From 86a7dac7e199a9e12c58193b3262b9bc64b2f11a Mon Sep 17 00:00:00 2001 From: twall Date: Wed, 31 Jul 2019 10:24:55 -0500 Subject: [PATCH 01/12] adding noether_simulator --- noether_examples/CMakeLists.txt | 22 + noether_examples/launch/thick_sim.launch | 5 + noether_examples/package.xml | 2 + .../src/thickness_simulator_client.cpp | 198 +++++++++ noether_msgs/CMakeLists.txt | 1 + noether_msgs/action/ThickSimulator.action | 10 + noether_msgs/msg/ToolPathConfig.msg | 9 +- noether_msgs/msg/ToolRasterPath.msg | 2 +- noether_simulator/CMakeLists.txt | 103 +++++ noether_simulator/cfg/NoetherSimulator.cfg | 17 + .../noether_simulator/noether_simulator.h | 87 ++++ noether_simulator/package.xml | 43 ++ noether_simulator/src/noether_simulator.cpp | 393 ++++++++++++++++++ .../src/thickness_simulator_node.cpp | 250 +++++++++++ noether_simulator/test/utest.cpp | 265 ++++++++++++ .../src/simple_path_sequence_planner.cpp | 2 - path_sequence_planner/test/utest.cpp | 1 - .../tool_path_planner/raster_path_generator.h | 1 - .../raster_tool_path_planner.h | 1 - .../tool_path_planner_base.h | 3 + .../include/tool_path_planner/utilities.h | 4 - .../src/raster_path_generator.cpp | 1 - .../src/raster_tool_path_planner.cpp | 8 +- tool_path_planner/src/utilities.cpp | 11 +- vtk_viewer/include/vtk_viewer/vtk_viewer.h | 2 +- vtk_viewer/src/mouse_interactor.cpp | 2 - vtk_viewer/src/vtk_utils.cpp | 2 - vtk_viewer/src/vtk_viewer.cpp | 44 +- vtk_viewer/test/utest.cpp | 5 +- 29 files changed, 1460 insertions(+), 34 deletions(-) create mode 100644 noether_examples/launch/thick_sim.launch create mode 100644 noether_examples/src/thickness_simulator_client.cpp create mode 100644 noether_msgs/action/ThickSimulator.action create mode 100644 noether_simulator/CMakeLists.txt create mode 100755 noether_simulator/cfg/NoetherSimulator.cfg create mode 100644 noether_simulator/include/noether_simulator/noether_simulator.h create mode 100644 noether_simulator/package.xml create mode 100644 noether_simulator/src/noether_simulator.cpp create mode 100644 noether_simulator/src/thickness_simulator_node.cpp create mode 100644 noether_simulator/test/utest.cpp diff --git a/noether_examples/CMakeLists.txt b/noether_examples/CMakeLists.txt index d96c2f64..872a1ec4 100644 --- a/noether_examples/CMakeLists.txt +++ b/noether_examples/CMakeLists.txt @@ -8,8 +8,12 @@ project(noether_examples) find_package(VTK 7.1 REQUIRED NO_MODULE) include(${VTK_USE_FILE}) +find_package(PCL 1.8 REQUIRED) +find_package(Boost REQUIRED COMPONENTS system) + find_package(catkin REQUIRED COMPONENTS actionlib + #actionlib_msgs cmake_modules mesh_segmenter noether_conversions @@ -20,6 +24,7 @@ find_package(catkin REQUIRED COMPONENTS roslib tool_path_planner vtk_viewer + noether_simulator ) catkin_package( @@ -37,10 +42,14 @@ catkin_package( roslib tool_path_planner vtk_viewer + noether_simulator DEPENDS VTK ) + + + include_directories( include ${catkin_INCLUDE_DIRS} @@ -62,6 +71,19 @@ target_link_libraries(mesh_segmenter_node ${VTK_LIBRARIES} ) +#action client +add_executable(thickness_simulator_client src/thickness_simulator_client.cpp) +add_dependencies(thickness_simulator_client ${${PROJECT_NAME}_EXPORTED_TARGETS} + ${catkin_EXPORTED_TARGETS} + ${actionlib_tutorials_EXPORTED_TARGETS} +) +target_link_libraries(thickness_simulator_client + ${catkin_LIBRARIES} + ${VTK_LIBRARIES} + ${PCL_LIBRARIES} +) + + ############# ## Install ## ############# diff --git a/noether_examples/launch/thick_sim.launch b/noether_examples/launch/thick_sim.launch new file mode 100644 index 00000000..3dcca9f7 --- /dev/null +++ b/noether_examples/launch/thick_sim.launch @@ -0,0 +1,5 @@ + + + + + diff --git a/noether_examples/package.xml b/noether_examples/package.xml index 19ce7e4c..35062e53 100644 --- a/noether_examples/package.xml +++ b/noether_examples/package.xml @@ -10,6 +10,7 @@ cmake_modules noether_conversions + actionlib mesh_segmenter noether_msgs @@ -19,5 +20,6 @@ roslib tool_path_planner vtk_viewer + noether_simulator diff --git a/noether_examples/src/thickness_simulator_client.cpp b/noether_examples/src/thickness_simulator_client.cpp new file mode 100644 index 00000000..3f810482 --- /dev/null +++ b/noether_examples/src/thickness_simulator_client.cpp @@ -0,0 +1,198 @@ +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include + +#include +#include + +#include +#include + + + +//make modified meshes +vtkSmartPointer createPlaneMod(unsigned int grid_size_x, unsigned int grid_size_y, vtk_viewer::plane_type type) +{ + // Create points on an XY grid with a sinusoidal Z component + vtkSmartPointer points = vtkSmartPointer::New(); + + for (unsigned int x = grid_size_x; x < 10; x++) + { + for (unsigned int y = 0; y < grid_size_y; y++) + { + switch (type) + { + case vtk_viewer::FLAT: + points->InsertNextPoint(x, y, vtkMath::Random(0.0, 0.001)); + break; + case vtk_viewer::SINUSOIDAL_1D: + points->InsertNextPoint(x, y, sin(double(y) / 2.0) + vtkMath::Random(0.0, 0.001)); + break; + case vtk_viewer::SINUSOIDAL_2D: + if(x==grid_size_x) + { + points->InsertNextPoint(x, y, 1.0 * cos(double(x) / 2.0) - 1.0 * sin(double(y) / 2.0) + vtkMath::Random(0.0, 0.001)); + } + else + { + points->InsertNextPoint(x+0.25, y, 1.0 * cos(double(x) / 2.0) - 1.0 * sin(double(y) / 2.0) + vtkMath::Random(0.0, 0.001)); + } + break; + } + } + } + + // Add the grid points to a polydata object + vtkSmartPointer polydata = vtkSmartPointer::New(); + polydata->SetPoints(points); + + return points; +} + + +int main (int argc, char **argv) +{ + ros::init(argc, argv, "test_noether_simulator"); + + // create the action client + // true causes the client to spin its own thread + actionlib::SimpleActionClient ac("noether_simulator", true); + + ROS_INFO("Waiting for action server to start."); + // wait for the action server to start + ac.waitForServer(); + + ROS_INFO("Action server started, sending goal."); + // send a goal to the action + noether_msgs::ThickSimulatorGoal goal; + + //......setup test meshes and path + pcl_msgs::PolygonMesh myMesh; + std::vector myMeshs; + std::vector myPath; + + vtkSmartPointer points2 = vtkSmartPointer::New(); + double pt1[3] = {3.0, 3.0, 0.0}; + double pt2[3] = {4.0, 2.0, 0.0}; + double pt3[3] = {5.0, 3.0, 0.0}; + double pt4[3] = {4.0, 4.0, 0.0}; + + + points2->InsertNextPoint(pt1); + points2->InsertNextPoint(pt2); + points2->InsertNextPoint(pt3); + points2->InsertNextPoint(pt4); + //......end setup test meshes and path + + //.......create control meshes + for(int count = 0; count<3; count++)//start multimesh creation loop + { + vtkSmartPointer points; + if(count==0) + { + points = vtk_viewer::createPlane(10,10,vtk_viewer::SINUSOIDAL_2D); + } + if(count==1) + { + points = vtk_viewer::createPlane(9,10,vtk_viewer::SINUSOIDAL_2D); + } + if(count==2) + { + points = createPlaneMod(8,10,vtk_viewer::SINUSOIDAL_2D); + } + + vtkSmartPointer data = vtkSmartPointer::New(); + data = vtk_viewer::createMesh(points, 0.5, 5); + + vtk_viewer::generateNormals(data); + + vtkSmartPointer cut = vtkSmartPointer::New(); + cut = vtk_viewer::cutMesh(data, points2, false); + pcl::PolygonMesh *test = new(pcl::PolygonMesh); + pcl::VTKUtils::convertToPCL(cut, *test); + pcl_conversions::fromPCL(*test, myMesh); + if(count>0) + { + myMeshs.push_back(myMesh); + } + //........end create control meshes + //........create robot path + //if(count==0) + //{ + //vtkSmartPointer cut = vtkSmartPointer::New(); + cut = vtk_viewer::cutMesh(data, points2, false); + //pcl::PolygonMesh *test = new(pcl::PolygonMesh); + pcl::VTKUtils::convertToPCL(cut, *test); + + // Run tool path planner on mesh + tool_path_planner::RasterToolPathPlanner planner; + planner.setInputMesh(cut); + + tool_path_planner::ProcessTool tool; + tool.pt_spacing = 0.5; + tool.line_spacing = .75; + tool.tool_offset = 0.0; // currently unused + tool.intersecting_plane_height = 0.15; // 0.5 works best, not sure if this should be included in the tool + tool.nearest_neighbors = 30; // not sure if this should be a part of the tool + tool.min_hole_size = 0.1; + tool.min_segment_size = 1; + tool.raster_angle = 0; + tool.raster_wrt_global_axes = 0; + tool.tool_radius = 1; + tool.tool_height = 2; + planner.setTool(tool); + planner.setDebugMode(false); + + planner.computePaths(); + + + std::vector paths = planner.getPaths(); + myPath = tool_path_planner::toPosesMsgs(paths); + + noether_msgs::ToolRasterPath rasterPath; + rasterPath.paths = myPath; + goal.path.push_back(rasterPath); + + //} + //........end robot path + }//end multimesh creation loop + + //set goal values + goal.input_mesh = myMeshs; + //noether_msgs::ToolRasterPath rasterPath; + //rasterPath.paths = myPath; + //goal.path.push_back(rasterPath); + ac.sendGoal(goal); + ROS_INFO(" sent mesh and path generation"); + ROS_INFO("number of paths sent: %d ",goal.path.size()); + //wait for the action to return + bool finished_before_timeout = ac.waitForResult(ros::Duration(300.0)); + + if (finished_before_timeout) + { + actionlib::SimpleClientGoalState state = ac.getState(); + ROS_INFO("Action finished: %s",state.toString().c_str()); + } + else + ROS_INFO("Action did not finish before the time out."); + + for(int i=0; ipainted[i]); + } + ROS_INFO("number of paths required is: %d",ac.getResult()->requiredPath.size()); + //exit + return 0; +} diff --git a/noether_msgs/CMakeLists.txt b/noether_msgs/CMakeLists.txt index 530936ac..2ccea337 100644 --- a/noether_msgs/CMakeLists.txt +++ b/noether_msgs/CMakeLists.txt @@ -29,6 +29,7 @@ add_action_files( FILES GenerateToolPaths.action Segment.action + ThickSimulator.action ) generate_messages( diff --git a/noether_msgs/action/ThickSimulator.action b/noether_msgs/action/ThickSimulator.action new file mode 100644 index 00000000..003b0cba --- /dev/null +++ b/noether_msgs/action/ThickSimulator.action @@ -0,0 +1,10 @@ +#goal definition - Input Mesh +pcl_msgs/PolygonMesh[] input_mesh +noether_msgs/ToolRasterPath[] path +--- +#result definition - are messhes painted enough +bool[] painted +noether_msgs/ToolRasterPath[] requiredPath +--- +#feedback - Some sort of percentage +float32 percent diff --git a/noether_msgs/msg/ToolPathConfig.msg b/noether_msgs/msg/ToolPathConfig.msg index 5ef6f13f..21d39ca0 100644 --- a/noether_msgs/msg/ToolPathConfig.msg +++ b/noether_msgs/msg/ToolPathConfig.msg @@ -1,10 +1,13 @@ -float64 pt_spacing # Required spacing between path points +float64 pt_spacing # Required spacing between path points float64 line_spacing # Offset between two rasters float64 tool_offset # How far off the surface the tool needs to be -float64 intersecting_plane_height # Used by the raster_tool_path_planner when offsetting to an adjacent path, a new plane has to be formed, but not too big +float64 intersecting_plane_height # Used by the raster_tool_path_planner when offsetting to an adjacent path, a new plane has to be formed, but not too big +float64 nearest_neighbors # how many neighbors are used to compute local normals Trent Added float64 min_hole_size # A path may pass over holes smaller than this, but must be broken when larger holes are encounterd. float64 min_segment_size # The minimum segment size to allow when finding intersections; small segments will be discarded -float64 raster_angle # Specifies the direction of the raster path in radians +float64 raster_angle # Specifies the direction of the raster path in radians +float64 tool_radius # The radius of the tool (for process simulation) Trent added +float64 tool_height # The height of the tool (for process simulation) # When set to TRUE: initial cuts are determined using the axes of the # coordinate frame in which the mesh is placed. This may cause the diff --git a/noether_msgs/msg/ToolRasterPath.msg b/noether_msgs/msg/ToolRasterPath.msg index 65ff65e8..0a2e09d7 100644 --- a/noether_msgs/msg/ToolRasterPath.msg +++ b/noether_msgs/msg/ToolRasterPath.msg @@ -1 +1 @@ -geometry_msgs/PoseArray[] paths # The raster paths on a surface \ No newline at end of file +geometry_msgs/PoseArray[] paths # The raster paths on a surface diff --git a/noether_simulator/CMakeLists.txt b/noether_simulator/CMakeLists.txt new file mode 100644 index 00000000..7ba6374c --- /dev/null +++ b/noether_simulator/CMakeLists.txt @@ -0,0 +1,103 @@ +cmake_minimum_required(VERSION 2.8.3) +project(noether_simulator) +SET(CMAKE_CXX_FLAGS "-std=c++0x") + +find_package(VTK 7.1 CONFIG) +find_package(VTK 7.1 REQUIRED) +include(${VTK_USE_FILE}) + +find_package(Eigen3 REQUIRED) + +find_package(PCL 1.8 REQUIRED) + +find_package(Boost REQUIRED COMPONENTS system) + +find_package(catkin REQUIRED cmake_modules + message_generation + mesh_segmenter + tool_path_planner + path_sequence_planner + vtk_viewer + sensor_msgs + geometry_msgs + roscpp + pcl_msgs + std_srvs + pcl_conversions + dynamic_reconfigure + genmsg + actionlib + actionlib_msgs +) + +generate_messages( + DEPENDENCIES + pcl_msgs + sensor_msgs + geometry_msgs + actionlib_msgs +) + +generate_dynamic_reconfigure_options( + cfg/NoetherSimulator.cfg +) + +catkin_package( + INCLUDE_DIRS include + LIBRARIES noether_simulator_ + CATKIN_DEPENDS + mesh_segmenter + tool_path_planner + path_sequence_planner + vtk_viewer + message_runtime + sensor_msgs + std_srvs + pcl_msgs + geometry_msgs + pcl_conversions + dynamic_reconfigure + DEPENDS + VTK + PCL +) + +include_directories(include + ${catkin_INCLUDE_DIRS} ${Boost_INCLUDE_DIRS} +) + +add_library(noether_simulator_ + src/noether_simulator.cpp +) + +target_link_libraries(noether_simulator_ + ${catkin_LIBRARIES} + ${VTK_LIBRARIES} + ${PCL_LIBRARIES} +) + +#action server +add_executable(thick_sim src/thickness_simulator_node.cpp) +add_dependencies(thick_sim ${${PROJECT_NAME}_EXPORTED_TARGETS} + ${catkin_EXPORTED_TARGETS} + ${actionlib_tutorials_EXPORTED_TARGETS} +) +target_link_libraries(thick_sim + noether_simulator_ + ${catkin_LIBRARIES} + ${VTK_LIBRARIES} + ${PCL_LIBRARIES} +) + +#Test +if (CATKIN_ENABLE_TESTING) + catkin_add_gtest(${PROJECT_NAME}-test + test/utest.cpp +) + +target_link_libraries(noether_simulator-test + noether_simulator_ + ${catkin_LIBRARIES} + ${VTK_LIBRARIES} +) +endif() diff --git a/noether_simulator/cfg/NoetherSimulator.cfg b/noether_simulator/cfg/NoetherSimulator.cfg new file mode 100755 index 00000000..cdbc969d --- /dev/null +++ b/noether_simulator/cfg/NoetherSimulator.cfg @@ -0,0 +1,17 @@ +#!/usr/bin/env python + +PACKAGE = "noether_simulator" + +from dynamic_reconfigure.parameter_generator_catkin import * +import math + +gen = ParameterGenerator() + +to = gen #.add_group("toggle_options") + +to.add("display_sigma", double_t, 0, "display_sigma", 1.0, 0.1, 10.0) +to.add("tool_radius", double_t, 0, "tool_radius", 0.05, 0.001, 1.0) +to.add("process_rate", double_t, 0, "process base deposition/removal rate", 5.0, 0.001, 20.0) +to.add("tool_height", double_t, 0, "tool_height", 0.1, 0.001, 1.0) + +exit(gen.generate(PACKAGE, "noether_simulator", "NoetherSimulator")) diff --git a/noether_simulator/include/noether_simulator/noether_simulator.h b/noether_simulator/include/noether_simulator/noether_simulator.h new file mode 100644 index 00000000..6924d265 --- /dev/null +++ b/noether_simulator/include/noether_simulator/noether_simulator.h @@ -0,0 +1,87 @@ +#ifndef NOETHER_SIMULATOR_H +#define NOETHER_SIMULATOR_H + +/* + * Copyright (c) 2016, Southwest Research Institute + * All rights reserved. + * + */ + +#include +#include +#include +#include +#include +#include +#include +#include +#include + +namespace noether_simulator +{ + +class NoetherSimulator +{ +public: + + NoetherSimulator(); + ~NoetherSimulator(){} + + /** + * @brief getSimulatedPoints returns the simulated_points_ from run simulation + */ + vtkSmartPointer getSimulatedPoints(); + /** + * @brief setDebugModeOn Turn on debug mode to visualize every step of the path planning process + * @param debug Turns on debug if true, turns off debug if false + */ + void setDebugMode(bool debug){debug_on_ = debug;} + + /** + * @brief setInputMesh Sets the input mesh to generate paths + * @param mesh The input mesh to be operated on + */ + void setInputMesh(vtkSmartPointer mesh){input_mesh_ = mesh;} + + /** + * @brief setInputMesh Sets the input mesh to generate paths + * @param mesh The input mesh to be operated on + */ + void setInputPaths(std::vector paths){input_paths_ = paths;} + + /** + * @brief setTool Sets the tool parameters used during path generation + * @param tool The tool object with all of the parameters necessary for path generation + */ + void setTool(tool_path_planner::ProcessTool tool){tool_ = tool;} + + void runSimulation(); + + void setDisplaySigma(double sigma){scalar_sigma_ = sigma;} + + void setBaseProcessRate(double rate){process_base_rate_ = rate;} + + void displayResults(); + +private: + + double process_base_rate_; /**< For a given process (i.e. painting), the base material processing rate (in this case, the amount of paint flow at the tip) */ + double scalar_sigma_; /**< number of sigmas for displaying final simulation coloring, higher sigma will show a "smoother" result */ + bool debug_on_; /**< Turns on/off the debug display which views the simulation output one step at a time */ + vtk_viewer::VTKViewer debug_viewer_; /**< The vtk viewer for displaying debug output */ + + vtkSmartPointer simulation_points_; /**< The simulated points with resulting process data */ + vtkSmartPointer input_mesh_; /**< input mesh to operate on */ + std::vector input_paths_; /**< input paths to simulate process on */ + tool_path_planner::ProcessTool tool_; /**< The tool parameters which defines how to generate the tool paths (spacing, offset, etc.) */ + + vtkSmartPointer createMatrix(double pt[3], double norm[3], double derv[3]); + + double integral(double pt[3]); + double calculateIntegration(vtkSmartPointer points); +}; + +} + +#endif // NOETHER_SIMULATOR_H + diff --git a/noether_simulator/package.xml b/noether_simulator/package.xml new file mode 100644 index 00000000..5f5c4551 --- /dev/null +++ b/noether_simulator/package.xml @@ -0,0 +1,43 @@ + + + noether_simulator + 0.0.0 + The noether_simulator package + alex + Proprietary + + catkin + + message_generation + roscpp + mesh_segmenter + tool_path_planner + path_sequence_planner + vtk_viewer + mesh_segmenter + vtk_viewer + sensor_msgs + geometry_msgs + pcl_msgs + std_srvs + pcl_conversions + dynamic_reconfigure + + message_runtime + message_generation + roscpp + mesh_segmenter + tool_path_planner + path_sequence_planner + vtk_viewer + mesh_segmenter + vtk_viewer + sensor_msgs + geometry_msgs + pcl_msgs + std_srvs + pcl_conversions + dynamic_reconfigure + + + diff --git a/noether_simulator/src/noether_simulator.cpp b/noether_simulator/src/noether_simulator.cpp new file mode 100644 index 00000000..fc03a8e3 --- /dev/null +++ b/noether_simulator/src/noether_simulator.cpp @@ -0,0 +1,393 @@ +/* + * Copyright (c) 2016, Southwest Research Institute + * All rights reserved. + * + */ + +#include + +#include +#include +#include + +#include +#include + +#include +#include +#include + +#include +#include +#include +#include + +namespace noether_simulator +{ + NoetherSimulator::NoetherSimulator() + { + process_base_rate_ = 5.0; + scalar_sigma_ = 3.0; + debug_on_ = false; + simulation_points_ = vtkSmartPointer::New(); + } + + double NoetherSimulator::integral(double pt[3]) + { + //double k = process_base_rate_; + double result; + // t is not currently added/used, but can be so as to allow time parameterization between process points + // f(x,y,z,t) = -x^2 - y^2 - (z - k) + // integral(f) = -x^3*y*z/3 - x*y^3*z/3 - x*y*z^2/2 + k*x*y*z + // TODO: the above equation does not work (integrates area, not along a line) + // TODO: again, cylinder is along y-axis, so y and z are flipped + result = -( pow(pt[0],3.0)) /3.0 - (pow(pt[2],3.0))/3.0 ; + + return 10*result; + } + + double NoetherSimulator::calculateIntegration(vtkSmartPointer points) + { + if(points->GetNumberOfPoints() < 2) + return 0; + // This is a place holder equation for the tool and is process specific + // TODO: create a more generic interface to allow for other tools to be created and used + + double pt1[3], pt2[3]; + double val1, val2; + + points->GetPoint(0, pt1); + points->GetPoint(1, pt2); + + val1 = integral(pt1); + val2 = integral(pt2); + + double value = (val2 - val1); + return fabs(value); + } + +vtkSmartPointer NoetherSimulator::getSimulatedPoints() + { + vtkSmartPointer simulated_points = simulation_points_; + return simulated_points; + } + + void NoetherSimulator::runSimulation() + { + + cout << "starting simulation\n"; + std::vector color(3); + color[0] = 0.9; color[1] = 0.9; color[2] = 0.9; + + // densly sample surface based upon point spacing + double spacing = tool_.pt_spacing /10.0; + vtkSmartPointer simulation_points; + simulation_points = vtk_viewer::sampleMesh(input_mesh_, spacing); + + // add scalar data for all points + vtkSmartPointer scalars = vtkSmartPointer::New(); + scalars->SetNumberOfComponents(1); + scalars->SetNumberOfTuples(simulation_points->GetNumberOfPoints()); + int number_Tuples = scalars->GetNumberOfTuples(); + for(int i = 0; i < number_Tuples; ++i) + { + scalars->SetTuple1(i, 0.0); + } + + // create tool object + vtkSmartPointer cylinder = vtkSmartPointer::New(); + cylinder->SetCenter(0.0, 0.0, 0.0); + cylinder->SetRadius(tool_.tool_radius ); + cylinder->SetHeight(tool_.tool_height); + cylinder->SetResolution(20); + cylinder->Update(); + + //vtkSmartPointer tree = vtkSmartPointer::New(); + vtkSmartPointer tree = vtkSmartPointer::New(); + tree->SetDataSet(cylinder->GetOutput()); + tree->BuildLocator(); + + // use tool to integrate over time and distance + int number_paths =input_paths_.size(); + for(int i = 0; i GetNumberOfPoints() - 1; + for(int j = 0; j < number_points; ++j) + { + // get pt1 and pt2 + double path_pt1[3], norm1[3], derv1[3]; + this_path.line->GetPoints()->GetPoint(j, path_pt1); + this_path.line->GetPointData()->GetNormals()->GetTuple(j, norm1); + this_path.derivatives->GetPointData()->GetNormals()->GetTuple(j, derv1); + + double path_pt2[3], norm2[3], derv2[3]; + this_path.line->GetPoints()->GetPoint(j+1, path_pt2); + this_path.line->GetPointData()->GetNormals()->GetTuple(j+1, norm2); + this_path.derivatives->GetPointData()->GetNormals()->GetTuple(j+1, derv2); + + // transform tool to pt1 and pt2 location + vtkSmartPointer transform1 = createMatrix(path_pt1, norm1, derv1); + vtkSmartPointer transform2 = createMatrix(path_pt2, norm2, derv2); + + vtkSmartPointer trans = vtkSmartPointer::New(); + trans->SetMatrix(transform1); + + // transform to point 1 and get data + vtkSmartPointer transform_filter = + vtkSmartPointer::New(); + vtkSmartPointer cylinder_poly = vtkSmartPointer::New(); + cylinder_poly->DeepCopy(cylinder->GetOutput()); + transform_filter->SetInputData(cylinder_poly); + transform_filter->SetTransform(trans); + transform_filter->Update(); + + vtkSmartPointer point_set1 = vtkSmartPointer::New(); + point_set1->DeepCopy(transform_filter->GetOutput()); + + // transform to point 2 and get data + trans->SetMatrix(transform2); + transform_filter->SetTransform(trans); + transform_filter->Update(); + + vtkSmartPointer point_set2 = vtkSmartPointer::New(); + point_set2->DeepCopy(transform_filter->GetOutput()); + + // create convex hull of two tool locations + vtkSmartPointer delaunay_3D = + vtkSmartPointer::New(); + vtkSmartPointer hull_data = vtkSmartPointer::New(); + vtkSmartPointer point_data = vtkSmartPointer::New(); + point_data->DeepCopy(point_set1->GetPoints()); + point_data->Resize(point_set1->GetPoints()->GetNumberOfPoints() + point_set2->GetPoints()->GetNumberOfPoints()); + point_data->InsertPoints(point_set1->GetPoints()->GetNumberOfPoints(), point_set2->GetPoints()->GetNumberOfPoints(), 0, point_set2->GetPoints()); + + hull_data->SetPoints(point_data); + + delaunay_3D->SetInputData (hull_data); + delaunay_3D->Update(); + + vtkGeometryFilter *extract = vtkGeometryFilter::New(); + extract->SetInputData(delaunay_3D->GetOutput()); + extract->Update(); + + vtkSmartPointer convex_hull = vtkSmartPointer::New(); + convex_hull = extract->GetOutput(); + + // find all simulation points located inside convex hull + vtkSmartPointer select_enclosed = + vtkSmartPointer::New(); + select_enclosed->SetTolerance(0.0001); + select_enclosed->SetInputData(simulation_points); + select_enclosed->SetSurfaceData(convex_hull); + select_enclosed->Update(); + + int num_pts = simulation_points->GetPoints()->GetNumberOfPoints(); + vtkSmartPointer pts_inside = vtkSmartPointer::New(); + for(int i = 0; i < num_pts ; ++i) + { + if(select_enclosed->IsInside(i)) + { + pts_inside->InsertNextId(i); + } + } + vtkSmartPointer tool_points = vtkSmartPointer::New(); + simulation_points->GetPoints()->GetPoints(pts_inside, tool_points); + + // transform all points into tool_pt1 frame of referece + vtkSmartPointer temp_data = vtkSmartPointer::New(); + temp_data->SetPoints(tool_points); + vtkSmartPointer tool_pts1 = vtkSmartPointer::New(); + trans->SetMatrix(transform1); + trans->Inverse(); + transform_filter->SetInputData(temp_data); + transform_filter->SetTransform(trans); + transform_filter->Update(); + tool_pts1->DeepCopy(transform_filter->GetOutput()->GetPoints()); + + // transform all points into tool_pt2 frame of referece + vtkSmartPointer tool_pts2 = vtkSmartPointer::New(); + trans->SetMatrix(transform2); + trans->Inverse(); + transform_filter->SetTransform(trans); + transform_filter->Update(); + tool_pts2->DeepCopy(transform_filter->GetOutput()->GetPoints()); + + // use tool_pt1 and tool_pt2 to calculate deposition for each point + // using tool deposition model. + vtkSmartPointer select_enclosed2 = + vtkSmartPointer::New(); + select_enclosed2->SetTolerance(0.000001); + num_pts = tool_points->GetNumberOfPoints(); + select_enclosed2->SetSurfaceData(cylinder->GetOutput()); + vtkSmartPointer test_poly = vtkSmartPointer::New(); + vtkSmartPointer test_pts = vtkSmartPointer::New(); + vtkSmartPointer integration_pts = vtkSmartPointer::New(); + + //test_pts->SetNumberOfPoints(2); + for(int i = 0; i < num_pts; ++i) + { + integration_pts->Reset(); + + // check to see if the point begin/end locations are inside of the tool + double pt1[3], pt2[3]; + tool_pts1->GetPoint(i, pt1); + tool_pts2->GetPoint(i, pt2); + + test_pts->Reset(); + test_pts->InsertNextPoint(pt1); + test_pts->InsertNextPoint(pt2); + test_poly->SetPoints(test_pts); + select_enclosed2->SetInputData(test_poly); + select_enclosed2->Update(); + + if(select_enclosed2->IsInside(0)) + { + integration_pts->InsertNextPoint(pt1); + } + if(select_enclosed2->IsInside(1)) + { + integration_pts->InsertNextPoint(pt2); + } + + // if one or both points are not inside the tool, + // create line from point start/stop location and find intersection with the tool + if(integration_pts->GetNumberOfPoints() < 2) + { + vtkSmartPointer temp_pts = vtkSmartPointer::New(); + tree->IntersectWithLine(pt1, pt2, 0.001, temp_pts, NULL); + + int intersections = temp_pts->GetNumberOfPoints(); + + // get intersection point(s) + for(int j = 0; j < intersections; ++j) + { + double temp_pt[3]; + temp_pts->GetPoint(j, temp_pt); + integration_pts->InsertNextPoint(temp_pt); + } + } + + // We should now have two points; combine pts with tool to get integrated value + double integral_sum = 0; + integral_sum = calculateIntegration(integration_pts); + + // assuming that the tool_pts are in the same order as pts_inside, + // use the point indeces from pts_inside to modify the scalar values + int index = pts_inside->GetId(i); + // get scalar value, color data is stored in scalars + double *tmp_value = scalars->GetTuple(index); + double value = *tmp_value + integral_sum; + scalars->SetTuple1(index, value); + + }// end loop through all tool points found + }// end loop through all process points in this path + + }// end loop through all paths + + // display of simulation points + + // create look up table for point coloring + simulation_points->GetPointData()->SetScalars(scalars); + + simulation_points_->Reset(); + simulation_points_ = simulation_points; + + displayResults(); + + } // end runSimulation() + + void NoetherSimulator::displayResults() + { + if(!simulation_points_) + { + return; + } + + double mean = 0; + double *value; + vtkSmartPointer scalars = vtkSmartPointer::New(); + scalars = vtkDoubleArray::SafeDownCast(simulation_points_->GetPointData()->GetScalars()); + + // calculate mean of data and std_dev of data + int number_tuples = scalars->GetNumberOfTuples(); + for(int i = 0; i < number_tuples; ++i) + { + value = scalars->GetTuple(i); + mean += *value; + } + mean = mean/scalars->GetNumberOfTuples(); + double std_dev = 0; + int number_scalars = scalars->GetNumberOfTuples(); + for(int i = 0; i < number_scalars; ++i) + { + value = scalars->GetTuple(i); + std_dev += pow((mean - *value), 2.0); + } + std_dev = std_dev/ (scalars->GetNumberOfTuples() - 1); + std_dev = sqrt(std_dev); + + // calculate the lower and upper limits for the display color range + double range[2]; + scalars->GetRange(range); + + cout << "scalar range " << range[0] << " " << range[1] << "\n"; + double upper_bound = mean + std_dev * scalar_sigma_; + double lower_bound = mean - std_dev * scalar_sigma_; + + // TODO: this limit assumes that the process is an additive one, + // for subtractive processes, something else will need to be done + if(lower_bound < 0.0) + { + lower_bound = 0.0; + } + + vtk_viewer::VTKViewer viewer; + std::vector color2(3); + color2[0] = 0.1; color2[1] = 0.1; color2[2] = 0.1; + viewer.addPolyDataDisplay(simulation_points_, color2, lower_bound, upper_bound); + viewer.renderDisplay(); + } + + vtkSmartPointer NoetherSimulator::createMatrix(double pt[3], double norm[3], double derv[3]) + { + // Get the point normal and derivative for creating the 3x3 transform + //double* norm = paths[j].line->GetPointData()->GetNormals()->GetTuple(k); + //double* der = paths[j].derivatives->GetPointData()->GetNormals()->GetTuple(k); + + // perform cross product to get the third axis direction + Eigen::Vector3d u(norm[0], norm[1], norm[2]); + Eigen::Vector3d v(derv[0], derv[1], derv[2]); + Eigen::Vector3d w = u.cross(v); + w.normalize(); + + // after first cross product, u and w will be orthogonal. Perform cross + // product one more time to make sure that v is perfectly orthogonal to u and w + v = u.cross(w); + v.normalize(); + + // TODO: the test currently uses a cylinder source, with the y-axis as the major axis + // for correct visualization, need to set the norm vector (u) to the y-axis + Eigen::Affine3d epose = Eigen::Affine3d::Identity(); + epose.matrix().col(0).head<3>() = w; + epose.matrix().col(1).head<3>() = u; + epose.matrix().col(2).head<3>() = -v; + epose.matrix().col(3).head<3>() = Eigen::Vector3d(pt[0], pt[1], pt[2]); + + // the eigen epose.data() returns column major data whereas the vtk matrix DeepCopy() + // takes row major data, need to transpose the data before setting the vtk matrix + vtkSmartPointer temp_matrix = vtkSmartPointer::New(); + double* array = epose.data(); + double out_array[16]; + out_array[0] = array[0]; out_array[1] = array[4]; out_array[2] = array[8]; out_array[3] = array[12]; + out_array[4] = array[1]; out_array[5] = array[5]; out_array[6] = array[9]; out_array[7] = array[13]; + out_array[8] = array[2]; out_array[9] = array[6]; out_array[10] = array[10]; out_array[11] = array[14]; + out_array[12] = array[3]; out_array[13] = array[7]; out_array[14] = array[11]; out_array[15] = array[15]; + + temp_matrix->DeepCopy(out_array); + return temp_matrix; + } + +} diff --git a/noether_simulator/src/thickness_simulator_node.cpp b/noether_simulator/src/thickness_simulator_node.cpp new file mode 100644 index 00000000..6699f9d8 --- /dev/null +++ b/noether_simulator/src/thickness_simulator_node.cpp @@ -0,0 +1,250 @@ +#include "ros/ros.h" +#include +#include +#include +#include + +#include +#include +#include + +#include +#include +#include + +#include "noether_simulator/noether_simulator.h" +#include "noether_simulator/NoetherSimulatorConfig.h" +#include "noether_msgs/ThickSimulatorAction.h" + +#include +#include +#include + + +namespace noether_simulator { +class ProcessSimulatorNode{ +private: + + ros::NodeHandle nh_; + actionlib::SimpleActionServer simulation_service_; + + double tool_height_; + double process_rate_; + double display_sigma_; + double tool_radius_; + + void updateParameters(noether_simulator::NoetherSimulatorConfig& config, uint32_t level); + dynamic_reconfigure::Server reconfigurer_; + boost::mutex param_lock_; + //tool_path_planner::ProcessTool tool_; + double vect_[3], center_[3]; + bool debug_on_; + std::string log_directory_; + noether_msgs::ThickSimulatorFeedback feedback_; + noether_msgs::ThickSimulatorResult result_; + + tool_path_planner::ProcessPath convertPoseArraytoVTK(geometry_msgs::PoseArray array) + { + tool_path_planner::ProcessPath path; + + vtkSmartPointer line = vtkSmartPointer::New(); + vtkSmartPointer derivatives_ = vtkSmartPointer::New(); + vtkSmartPointer pts = vtkSmartPointer::New(); + + // set the point positions + for(int ii = 0; ii < array.poses.size(); ii++) + { + geometry_msgs::Pose pose = array.poses[ii]; + + double pt[3]; + pt[0] = (double)pose.position.x; + pt[1] = (double)pose.position.y; + pt[2] = (double)pose.position.z; + + pts->InsertNextPoint(pt); + } + + line->SetPoints(pts); + derivatives_->SetPoints(pts); + + // calculate point normals + vtkSmartPointer normals = vtkSmartPointer::New(); + vtkSmartPointer deriv_normals = vtkSmartPointer::New(); + normals->SetNumberOfComponents(3); + deriv_normals->SetNumberOfComponents(3); + + for(int ii = 0; ii < line->GetPoints()->GetNumberOfPoints(); ii++) + { + double pt[3]; + geometry_msgs::Quaternion q = array.poses[ii].orientation; + + //calculate z-axis from quaternion + double x = (2*q.x*q.z + 2*q.y*q.w); + double y = (2*q.y*q.z - 2*q.x*q.w); + double z = (1 - 2*q.x*q.x - 2*q.y*q.y); + double n[3] = {x, y, z}; + normals->InsertNextTypedTuple(n); + + // calculate y-axis from quaternion + x = (2*q.x*q.y - 2*q.z*q.w); + y = (1 - 2*q.x*q.x - 2*q.z*q.z); + z = (1 - 2*q.y*q.z + 2*q.x*q.w); + double m[3] = {x, y, z}; + deriv_normals->InsertNextTypedTuple(m); + } + line->GetPointData()->SetNormals(normals); + path.line = line; + + derivatives_->GetPointData()->SetNormals(deriv_normals); + path.derivatives = derivatives_; + + vtkSmartPointer inter_ = vtkSmartPointer::New(); + vtkSmartPointer spline_ = vtkSmartPointer::New(); + path.intersection_plane = inter_; + path.spline = spline_; + + return path; + } + +public: + + ProcessSimulatorNode(std::string name) : + simulation_service_(nh_, name, boost::bind(&ProcessSimulatorNode::executeCB,this, _1), false), + tool_height_(2), + process_rate_(0),//not used in utest + display_sigma_(0),//not used in utest + tool_radius_(1) + { + simulation_service_.start(); + } + void executeCB(const noether_msgs::ThickSimulatorGoalConstPtr &goal) + { + ros::Rate r(0.05); + bool success = true; + feedback_.percent = 0.0; + ROS_INFO("simulator running"); + int num_meshes= goal->input_mesh.size(); + int num_paths = goal->path.size(); + noether_simulator::NoetherSimulator sim; + + //add tool + tool_path_planner::ProcessTool tool; + tool.pt_spacing = 0.5; + tool.line_spacing = 0.75; + tool.tool_offset = 0.0; // currently unused + tool.intersecting_plane_height = 0.15; // 0.5 works best, not sure if this should be included in the tool + tool.nearest_neighbors = 30; // not sure if this should be a part of the tool + tool.min_hole_size = 0.1; + tool.min_segment_size = 1; + tool.raster_angle = 0; + tool.raster_wrt_global_axes = 0; + tool.tool_radius = 1; + tool.tool_height = 2; + sim.setTool(tool); + + for(int i=0; ipath.size();curPathNum++) + { + bool added = false; + //convert robot path for simulator + std::vector robot_paths_in = goal->path[curPathNum].paths; + std::vector robot_paths_arg; + int number_paths = robot_paths_in.size(); + + for(int ii = 0; ii < number_paths; ii++) + { + robot_paths_arg.push_back(convertPoseArraytoVTK(robot_paths_in[ii])); + } + + sim.setInputPaths(robot_paths_arg);//add path to simulator + + //run simulator for each mesh + for(int i=0; i input_mesh[i], surface_mesh); + vtkSmartPointer surface_mesh_vtk = vtkSmartPointer::New(); + pcl::VTKUtils::convertToVTK(surface_mesh, surface_mesh_vtk); + + sim.setInputMesh(surface_mesh_vtk);//add mesh to simulator + sim.runSimulation();//display painted parts + + //deterimine if painted enough + vtkSmartPointer processedPoints = vtkSmartPointer::New(); + processedPoints = sim.getSimulatedPoints();//get a copy of simulated points to operate on + vtkIdType length = processedPoints->GetNumberOfPoints(); + double intensity[3]; + int missed = 0; + double minPaintThreshold = 5; + double maxPassableNonpainted = 0.1; + + //******TODO*******// + // replace with FLANN + for(vtkIdType a = 0; a < length; a++)//iterate through points to check if painted + { + intensity[0] = processedPoints->GetPointData()->GetScalars()->GetComponent(a,0); + intensity[1] = processedPoints->GetPointData()->GetScalars()->GetComponent(a,1); + intensity[2] = processedPoints->GetPointData()->GetScalars()->GetComponent(a,2); + + if((intensity[0]+intensity[1]+intensity[2])/3.0 < minPaintThreshold) //averge of each pixel if less than threshold incrament counter + { + missed++; + } + }//end iterate through points to check if painted + + if(missed/float(processedPoints->GetNumberOfPoints())>maxPassableNonpainted)//get ratio of missed spots, if below threshold set not painted + { + result_.painted[i]=false; + } + else + { + result_.painted[i]=true; + if(added ==false) + { + result_.requiredPath.push_back(goal->path[curPathNum]); + added = true; + } + } + //******END TODO******// + feedback_.percent =float(i)/float(num_meshes); + simulation_service_.publishFeedback(feedback_); + + }//if not yet painted + }//end each mesh + }//end multiple paths + + if(success) + { + ROS_INFO("Succeeded"); + // set the action state to succeeded + simulation_service_.setSucceeded(result_); + } + }//end executeCB +};//end class +}//end namespace + + + +int main(int argc, char** argv) +{ + ros::init(argc, argv, "noether_simulator"); + + noether_simulator::ProcessSimulatorNode node("noether_simulator"); + ros::spin(); + + return 0; +} diff --git a/noether_simulator/test/utest.cpp b/noether_simulator/test/utest.cpp new file mode 100644 index 00000000..46ce1493 --- /dev/null +++ b/noether_simulator/test/utest.cpp @@ -0,0 +1,265 @@ +/* + * Copyright (c) 2016, Southwest Research Institute + * All rights reserved. + * + */ +#include +#include +#include +#include +#include +#include + +#include +#include + +// This tests runs the noether simulator +// it displays the mesh and path, then it +// displays a "heat" map that shows the +// result of painting the mesh using the +// given path. + + +//This test uses poor path to paint mesh +TEST(ViewerTest, TestCase1) +{ + + // Create mesh to work with + vtkSmartPointer points = vtk_viewer::createPlane(); + + vtkSmartPointer data = vtkSmartPointer::New(); + data = vtk_viewer::createMesh(points, 0.5, 5); + + vtk_viewer::generateNormals(data); + + vtkSmartPointer points2 = vtkSmartPointer::New(); + double pt1[3] = {3.0, 3.0, 0.0}; + double pt2[3] = {4.0, 2.0, 0.0}; + double pt3[3] = {5.0, 3.0, 0.0}; + double pt4[3] = {4.0, 4.0, 0.0}; + + points2->InsertNextPoint(pt1); + points2->InsertNextPoint(pt2); + points2->InsertNextPoint(pt3); + points2->InsertNextPoint(pt4); + + vtkSmartPointer cut = vtkSmartPointer::New(); + cut = vtk_viewer::cutMesh(data, points2, false); + + cout << "cutter points: " << cut->GetPoints()->GetNumberOfPoints() << "\n"; + cout << "cutter polys: " << cut->GetNumberOfPolys() << "\n"; + + // Run tool path planner on mesh + tool_path_planner::RasterToolPathPlanner planner; + planner.setInputMesh(cut); + + tool_path_planner::ProcessTool tool; + tool.pt_spacing = 0.5; + tool.line_spacing = 0.75; + tool.tool_offset = 0.0; // currently unused + tool.intersecting_plane_height = 0.5; // 0.5 works best, not sure if this should be included in the tool + tool.nearest_neighbors = 30; // not sure if this should be a part of the tool + tool.min_hole_size = 0.1; + tool.min_segment_size = 1; + tool.raster_angle = 0; + tool.raster_wrt_global_axes = 0; + tool.tool_radius = 1; + tool.tool_height = 2; + planner.setTool(tool); + planner.setDebugMode(false); + + planner.computePaths(); + + vtk_viewer::VTKViewer viz; + std::vector color(3); + + double scale = 1.0; + + // Display mesh results + color[0] = 0.9; + color[1] = 0.9; + color[2] = 0.9; + viz.addPolyDataDisplay(cut, color); + + std::vector paths = planner.getPaths(); + + for(int i = 0; i < paths.size(); ++i) + { + color[0] = 0.2; + color[1] = 0.9; + color[2] = 0.2; + viz.addPolyNormalsDisplay(paths[i].line, color, scale); + + color[0] = 0.9; + color[1] = 0.9; + color[2] = 0.2; + viz.addPolyNormalsDisplay(paths[i].derivatives, color, scale); + } + viz.renderDisplay(); + + // Run simulator on mesh and tool paths + + noether_simulator::NoetherSimulator simulator; + simulator.setInputMesh(cut); + simulator.setInputPaths(paths); + simulator.setTool(tool); + simulator.setDebugMode(true); + + simulator.runSimulation(); + + vtkSmartPointer processedPoints = vtkSmartPointer::New(); + processedPoints = simulator.getSimulatedPoints();//get a copy of simulated points to operate on + + vtkIdType length = processedPoints->GetNumberOfPoints(); + double p[3]; + double intensity[3]; + int missed = 0; + + for(vtkIdType i = 0; i < length; i++)//iterate through points to check if painted + { + + //processedPoints->GetPoint(i,p); + intensity[0] = processedPoints->GetPointData()->GetScalars()->GetComponent(i,0); + intensity[1] = processedPoints->GetPointData()->GetScalars()->GetComponent(i,1); + intensity[2] = processedPoints->GetPointData()->GetScalars()->GetComponent(i,2); + + + if((intensity[0]+intensity[1]+intensity[2])/3.0 < 5) //averge of each pixel if less than threshold incrament counter + { + missed++; + } + + } + bool painted; + if(missed/float(processedPoints->GetNumberOfPoints())>0.1)//get ratio of missed spots, if below threshold set not painted + { + painted = false; + } + else painted = true; + EXPECT_FALSE(painted);//expect partial path to fail +} + +//This test uses a good path to paint mesh +TEST(ViewerTest, TestCase2) +{ + + // Create mesh to work with + vtkSmartPointer points = vtk_viewer::createPlane(); + + vtkSmartPointer data = vtkSmartPointer::New(); + data = vtk_viewer::createMesh(points, 0.5, 5); + + vtk_viewer::generateNormals(data); + + vtkSmartPointer points2 = vtkSmartPointer::New(); + double pt1[3] = {3.0, 3.0, 0.0}; + double pt2[3] = {4.0, 2.0, 0.0}; + double pt3[3] = {5.0, 3.0, 0.0}; + double pt4[3] = {4.0, 4.0, 0.0}; + + points2->InsertNextPoint(pt1); + points2->InsertNextPoint(pt2); + points2->InsertNextPoint(pt3); + points2->InsertNextPoint(pt4); + + vtkSmartPointer cut = vtkSmartPointer::New(); + cut = vtk_viewer::cutMesh(data, points2, false); + + cout << "cutter points: " << cut->GetPoints()->GetNumberOfPoints() << "\n"; + cout << "cutter polys: " << cut->GetNumberOfPolys() << "\n"; + + // Run tool path planner on mesh + tool_path_planner::RasterToolPathPlanner planner; + planner.setInputMesh(cut); + + tool_path_planner::ProcessTool tool; + tool.pt_spacing = 0.5; + tool.line_spacing = 0.75; + tool.tool_offset = 0.0; // currentlyc unused + tool.intersecting_plane_height = 0.15; // 0.5 works best, not sure if this should be included in the tool + tool.nearest_neighbors = 30; // not sure if this should be a part of the tool + tool.min_hole_size = 0.1; + tool.min_segment_size = 1; + tool.raster_angle = 0; + tool.raster_wrt_global_axes = 0; + tool.tool_radius = 1; + tool.tool_height = 2; + planner.setTool(tool); + planner.setDebugMode(false); + + planner.computePaths(); + + vtk_viewer::VTKViewer viz; + std::vector color(3); + + double scale = 1.0; + + // Display mesh results + color[0] = 0.9; + color[1] = 0.9; + color[2] = 0.9; + viz.addPolyDataDisplay(cut, color); + + std::vector paths = planner.getPaths(); + + for(int i = 0; i < paths.size(); ++i) + { + color[0] = 0.2; + color[1] = 0.9; + color[2] = 0.2; + viz.addPolyNormalsDisplay(paths[i].line, color, scale); + + color[0] = 0.9; + color[1] = 0.9; + color[2] = 0.2; + viz.addPolyNormalsDisplay(paths[i].derivatives, color, scale); + } + viz.renderDisplay();//display planned paths on mesh + + // Run simulator on mesh and tool paths + + noether_simulator::NoetherSimulator simulator; + simulator.setInputMesh(cut); + simulator.setInputPaths(paths); + simulator.setTool(tool); + simulator.setDebugMode(true); + simulator.runSimulation(); + + vtkSmartPointer processedPoints = vtkSmartPointer::New(); + processedPoints = simulator.getSimulatedPoints();//get a copy of simulated points to operate on + + vtkIdType length = processedPoints->GetNumberOfPoints(); + double p[3]; + double intensity[3]; + int missed = 0; + bool painted; + + for(vtkIdType i = 0; i < length; i++)//iterate through points to check if painted + { + + intensity[0] = processedPoints->GetPointData()->GetScalars()->GetComponent(i,0); + intensity[1] = processedPoints->GetPointData()->GetScalars()->GetComponent(i,1); + intensity[2] = processedPoints->GetPointData()->GetScalars()->GetComponent(i,2); + + if((intensity[0]+intensity[1]+intensity[2])/3.0 < 5) //averge of each pixel if less than threshold incrament counter + { + missed++; + } + + } + if(missed/float(processedPoints->GetNumberOfPoints())>0.1)//get ratio of missed spots, if below threshold set not painted + { + painted = false; + } + else painted = true; + EXPECT_TRUE(painted);//expect good mesh to pass +} + + +// Run all the tests that were declared with TEST() +int main(int argc, char **argv) +{ + //ros::init(argc, argv, "test"); // some tests need ROS framework + testing::InitGoogleTest(&argc, argv); + return RUN_ALL_TESTS(); +} diff --git a/path_sequence_planner/src/simple_path_sequence_planner.cpp b/path_sequence_planner/src/simple_path_sequence_planner.cpp index 8817e463..b1f3f793 100644 --- a/path_sequence_planner/src/simple_path_sequence_planner.cpp +++ b/path_sequence_planner/src/simple_path_sequence_planner.cpp @@ -37,8 +37,6 @@ void SimplePathSequencePlanner::linkPaths() int next_index = findNextNearestPath(paths_, indices_, last_index, insert_front); - - if(indices_.size() > 1) { // check the distance of next_index with front and back to make sure it is in the right location diff --git a/path_sequence_planner/test/utest.cpp b/path_sequence_planner/test/utest.cpp index cf17cd9b..2b233aac 100644 --- a/path_sequence_planner/test/utest.cpp +++ b/path_sequence_planner/test/utest.cpp @@ -1,5 +1,4 @@ - /* * Copyright (c) 2016, Southwest Research Institute * All rights reserved. diff --git a/tool_path_planner/include/tool_path_planner/raster_path_generator.h b/tool_path_planner/include/tool_path_planner/raster_path_generator.h index 7014efd0..a13f9a75 100644 --- a/tool_path_planner/include/tool_path_planner/raster_path_generator.h +++ b/tool_path_planner/include/tool_path_planner/raster_path_generator.h @@ -57,7 +57,6 @@ class RasterPathGenerator { */ static tool_path_planner::ProcessTool generateDefaultToolConfig(); - }; } /* namespace tool_path_planner */ diff --git a/tool_path_planner/include/tool_path_planner/raster_tool_path_planner.h b/tool_path_planner/include/tool_path_planner/raster_tool_path_planner.h index 206a1463..05fdf964 100644 --- a/tool_path_planner/include/tool_path_planner/raster_tool_path_planner.h +++ b/tool_path_planner/include/tool_path_planner/raster_tool_path_planner.h @@ -162,7 +162,6 @@ namespace tool_path_planner bool getNextPath(const ProcessPath this_path, ProcessPath& next_path, double dist = 0.0, bool test_self_intersection = true); - /** * @brief Estimates the normals of a line that lies on the surface of the current mesh. For each point, it uses the normal of * the closes cell in the mesh diff --git a/tool_path_planner/include/tool_path_planner/tool_path_planner_base.h b/tool_path_planner/include/tool_path_planner/tool_path_planner_base.h index 09d5bd1e..0e41a6bf 100644 --- a/tool_path_planner/include/tool_path_planner/tool_path_planner_base.h +++ b/tool_path_planner/include/tool_path_planner/tool_path_planner_base.h @@ -30,6 +30,7 @@ namespace tool_path_planner double tool_offset; /** how far off the surface the tool needs to be */ double intersecting_plane_height; /** Used in creating planes from that originate from an adjacent raster line to the surface*/ + int nearest_neighbors; /** how many neighbors are used to compute local normals*/ double min_hole_size; /** A path may pass over holes smaller than this, but must be broken when larger holes are encountered */ double min_segment_size; /** The minimum segment size to allow when finding intersections; small segments will @@ -46,6 +47,8 @@ namespace tool_path_planner * axis being 0. Then the resultant vector is projected onto the plane * created by the bounding box x and y axes */ bool raster_wrt_global_axes; + double tool_radius; /** the radius of the tool (for process simulation)*/ + double tool_height; /** the height of the tool (for process simulation)*/ }; /** diff --git a/tool_path_planner/include/tool_path_planner/utilities.h b/tool_path_planner/include/tool_path_planner/utilities.h index d22efcbe..3490fdc2 100644 --- a/tool_path_planner/include/tool_path_planner/utilities.h +++ b/tool_path_planner/include/tool_path_planner/utilities.h @@ -9,7 +9,6 @@ * Author: Jorge Nicho */ - #ifndef INCLUDE_TOOL_PATH_PLANNER_UTILITIES_H_ #define INCLUDE_TOOL_PATH_PLANNER_UTILITIES_H_ @@ -22,7 +21,6 @@ #include "tool_path_planner_base.h" - namespace tool_path_planner { @@ -63,6 +61,4 @@ namespace tool_path_planner } - - #endif /* INCLUDE_TOOL_PATH_PLANNER_UTILITIES_H_ */ diff --git a/tool_path_planner/src/raster_path_generator.cpp b/tool_path_planner/src/raster_path_generator.cpp index bce35756..a6c962f3 100644 --- a/tool_path_planner/src/raster_path_generator.cpp +++ b/tool_path_planner/src/raster_path_generator.cpp @@ -357,4 +357,3 @@ boost::optional< std::vector > RasterPathGenerator::ge } } /* namespace tool_path_planner */ - diff --git a/tool_path_planner/src/raster_tool_path_planner.cpp b/tool_path_planner/src/raster_tool_path_planner.cpp index 1e3623d4..6d15e0fc 100644 --- a/tool_path_planner/src/raster_tool_path_planner.cpp +++ b/tool_path_planner/src/raster_tool_path_planner.cpp @@ -6,6 +6,7 @@ #include #include +#include #include #include @@ -39,7 +40,6 @@ #include #include "tool_path_planner/utilities.h" - static const std::size_t MAX_ATTEMPTS = 1000; static const double ANGLE_CORRECTION_THRESHOLD = (150.0/180.0)*M_PI; static const double EXTRUDE_EXTEND_PERCENTAGE = 1.5; @@ -248,7 +248,6 @@ namespace tool_path_planner debug_viewer_.removeObjectDisplay(debug_viewer_.getNumberOfDisplayObjects() - 1); } - std::vector new_paths; std::vector delete_paths; for(int i = 0; i < paths_.size(); ++i) @@ -823,6 +822,7 @@ namespace tool_path_planner // Check to make sure that the input cut surface contains a valid mesh if(cut_surface->GetNumberOfCells() < 1) { + LOG4CXX_ERROR(RASTER_PATH_PLANNER_LOGGER, "Number of input cells for calculating intersection is less than 1, cannot compute intersection"); return false; @@ -944,7 +944,6 @@ namespace tool_path_planner double dist4 = vtk_viewer::pt_dist(temp_points->GetPoint( temp_points->GetNumberOfPoints() - 1 ), lines[i]->GetPoint(lines[i]->GetNumberOfPoints() - 1) ); - double dist = std::min(dist1, dist2); dist = std::min(dist, dist3); dist = std::min(dist, dist4); @@ -1186,7 +1185,6 @@ namespace tool_path_planner new_pt[2] += (new_pt[2] - pt1[2]); new_points->SetPoint(0, new_pt); - points->SetNumberOfPoints(new_points->GetNumberOfPoints()); points->DeepCopy(new_points); } @@ -1199,7 +1197,6 @@ namespace tool_path_planner vtkSmartPointer derv = vtkSmartPointer::New(); derv->SetNumberOfComponents(3); - // get points which are evenly spaced along the spline // initialize num_line_pts to some number, find the Euclidean distance between two points (m & n), // then use this distance to determine how many points should be used in the given line @@ -1233,7 +1230,6 @@ namespace tool_path_planner spline->Evaluate(u, pt, d); new_points->InsertNextPoint(pt); - double pt1[3], pt2[3]; // find nearby points in order to calculate the local derivative if(i == 0) diff --git a/tool_path_planner/src/utilities.cpp b/tool_path_planner/src/utilities.cpp index 3e53053e..02123d2d 100644 --- a/tool_path_planner/src/utilities.cpp +++ b/tool_path_planner/src/utilities.cpp @@ -7,7 +7,6 @@ * Author: Jorge Nicho */ - #include #include @@ -76,7 +75,6 @@ void flipPointOrder(tool_path_planner::ProcessPath& path) } path.derivatives->SetPoints(dpoints2); - vtkDataArray* ders = path.derivatives->GetPointData()->GetNormals(); vtkSmartPointer new_ders = vtkSmartPointer::New(); new_ders->SetNumberOfComponents(3); @@ -118,7 +116,6 @@ bool convertToPCLMesh(const shape_msgs::Mesh& mesh_msg, pcl::PolygonMesh& mesh) return true; } - std::vector toPosesMsgs(const std::vector& paths) { std::vector poseArrayVector; @@ -182,10 +179,13 @@ tool_path_planner::ProcessTool fromTppMsg(const noether_msgs::ToolPathConfig& tp .line_spacing = tpp_msg_config.line_spacing, .tool_offset = tpp_msg_config.tool_offset, .intersecting_plane_height = tpp_msg_config.intersecting_plane_height, + .nearest_neighbors = tpp_msg_config.nearest_neighbors, .min_hole_size = tpp_msg_config.min_hole_size, .min_segment_size = tpp_msg_config.min_segment_size, .raster_angle = tpp_msg_config.raster_angle, - .raster_wrt_global_axes = tpp_msg_config.raster_wrt_global_axes + .raster_wrt_global_axes = tpp_msg_config.raster_wrt_global_axes, + .tool_radius = tpp_msg_config.tool_radius, + .tool_height = tpp_msg_config.tool_height }; } @@ -196,10 +196,13 @@ noether_msgs::ToolPathConfig toTppMsg(const tool_path_planner::ProcessTool& tool tpp_config_msg.line_spacing = tool_config.line_spacing; tpp_config_msg.tool_offset = tool_config.tool_offset; tpp_config_msg.intersecting_plane_height = tool_config.intersecting_plane_height; + tpp_config_msg.nearest_neighbors = tool_config.nearest_neighbors;//Trent added tpp_config_msg.min_hole_size = tool_config.min_hole_size; tpp_config_msg.min_segment_size = tool_config.min_segment_size; tpp_config_msg.raster_angle = tpp_config_msg.raster_angle; tpp_config_msg.raster_wrt_global_axes = tpp_config_msg.raster_wrt_global_axes; + tpp_config_msg.tool_radius = tpp_config_msg.tool_radius;//Trent added + tpp_config_msg.tool_height = tpp_config_msg.tool_radius;//Trent added return std::move(tpp_config_msg); } diff --git a/vtk_viewer/include/vtk_viewer/vtk_viewer.h b/vtk_viewer/include/vtk_viewer/vtk_viewer.h index f0bc5a89..4b873a59 100644 --- a/vtk_viewer/include/vtk_viewer/vtk_viewer.h +++ b/vtk_viewer/include/vtk_viewer/vtk_viewer.h @@ -35,7 +35,7 @@ namespace vtk_viewer * @param polydata The polydata to be displayed * @param color The color to use for rendering the data */ - void addPolyDataDisplay(vtkPolyData* polydata, std::vector color); + void addPolyDataDisplay(vtkPolyData* polydata, std::vector color, double lower_bounds = 0.0, double upper_bounds = 0.0); /** * @brief addPolyNormalsDisplay Add a renderer and actor for a polydata diff --git a/vtk_viewer/src/mouse_interactor.cpp b/vtk_viewer/src/mouse_interactor.cpp index 9070c7f5..f1efd5da 100644 --- a/vtk_viewer/src/mouse_interactor.cpp +++ b/vtk_viewer/src/mouse_interactor.cpp @@ -85,8 +85,6 @@ namespace vtk_viewer { std::cout << "Directory " << save_location_.str().c_str() << " does not exist. Not saving polydata file." << std::endl; } - - } } } diff --git a/vtk_viewer/src/vtk_utils.cpp b/vtk_viewer/src/vtk_utils.cpp index a7685ed1..b7beaaf7 100644 --- a/vtk_viewer/src/vtk_utils.cpp +++ b/vtk_viewer/src/vtk_utils.cpp @@ -52,7 +52,6 @@ #include #include #include - log4cxx::LoggerPtr createConsoleLogger(const std::string& logger_name) { using namespace log4cxx; @@ -115,7 +114,6 @@ vtkSmartPointer createMesh(vtkSmartPointer points, // surface reconstruction vtkSmartPointer cf; vtkSmartPointer surf = vtkSmartPointer::New(); - surf->SetInputData(polydata); surf->SetSampleSpacing(sample_spacing); surf->SetNeighborhoodSize(neigborhood_size); diff --git a/vtk_viewer/src/vtk_viewer.cpp b/vtk_viewer/src/vtk_viewer.cpp index 3dad2f8d..da22f29a 100644 --- a/vtk_viewer/src/vtk_viewer.cpp +++ b/vtk_viewer/src/vtk_viewer.cpp @@ -20,9 +20,10 @@ #include #include #include +#include +#include #include - #define VTK_SP(type, name)\ vtkSmartPointer name = vtkSmartPointer::New() @@ -82,15 +83,53 @@ namespace vtk_viewer } - void VTKViewer::addPolyDataDisplay(vtkPolyData* polydata , std::vector color) + void VTKViewer::addPolyDataDisplay(vtkPolyData* polydata , std::vector color, double lower_bounds, double upper_bounds) { // create mapper and add to list vtkSmartPointer triangulated_mapper = vtkSmartPointer::New(); triangulated_mapper->SetInputData(polydata); + + // check to see if there is scalar data, if so, create a look up table to display + vtkSmartPointer scalars = vtkDoubleArray::SafeDownCast(polydata->GetPointData()->GetScalars()); + if(scalars) + { + vtkSmartPointer color_table = vtkSmartPointer::New(); + double *bounds = polydata->GetPointData()->GetScalars()->GetRange(); + if((lower_bounds != 0.0 || upper_bounds != 0.0) && upper_bounds > lower_bounds) + { + color_table->SetTableRange(lower_bounds, upper_bounds ); + bounds[0] = lower_bounds; + bounds[1] = upper_bounds; + } + else + { + color_table->SetTableRange(bounds[0], bounds[1] ); + } + color_table->SetHueRange(0.0,0.66); + color_table->SetRampToLinear(); + color_table->SetNumberOfTableValues(256); + color_table->Build(); + + triangulated_mapper->SetLookupTable(color_table); + triangulated_mapper->SetScalarRange(bounds[0], bounds[1]); // this line is necessary otherwise display is incorrect + vtkSmartPointer scalar_bar = vtkSmartPointer::New(); + scalar_bar->SetLookupTable(color_table); + scalar_bar->GetPositionCoordinate()->SetCoordinateSystemToNormalizedDisplay(); + scalar_bar->SetOrientationToHorizontal(); + scalar_bar->GetPositionCoordinate()->SetValue(0.1,0.01); + scalar_bar->SetWidth(0.8); + scalar_bar->SetHeight(0.15); + this->renderer_->AddActor2D(scalar_bar); + } this->poly_mappers_.push_back(triangulated_mapper); // create actor and add to list vtkSmartPointer triangulated_actor = vtkSmartPointer::New(); + if(scalars) + { + triangulated_actor->GetProperty()->SetPointSize(20); + } + triangulated_actor->SetMapper(poly_mappers_.back()); triangulated_actor->GetProperty()->SetColor(color[0],color[1],color[2]); @@ -100,6 +139,7 @@ namespace vtk_viewer this->renderer_->AddActor(actors_.back()); } + VTKViewer::~VTKViewer() { renWin_->Delete(); diff --git a/vtk_viewer/test/utest.cpp b/vtk_viewer/test/utest.cpp index 55e709c1..d2464b1d 100644 --- a/vtk_viewer/test/utest.cpp +++ b/vtk_viewer/test/utest.cpp @@ -8,7 +8,7 @@ #include #include #include - +#include // This test shows the results of meshing on a square grid that has a sinusoidal // variability in the z axis. Red arrows show the surface normal for each triangle // in the mesh, and cyan boxes show the points used to seed the mesh creation algorithm @@ -19,7 +19,6 @@ TEST(ViewerTest, TestCase1) vtkSmartPointer data = vtkSmartPointer::New(); data = vtk_viewer::createMesh(points, 0.5, 5); - vtk_viewer::generateNormals(data); vtkSmartPointer points2 = vtkSmartPointer::New(); @@ -32,7 +31,7 @@ TEST(ViewerTest, TestCase1) points2->InsertNextPoint(pt2); points2->InsertNextPoint(pt3); points2->InsertNextPoint(pt4); - + vtkSmartPointer cut = vtkSmartPointer::New(); cut = vtk_viewer::cutMesh(data, points2, false); From 5f2227e02f0bb08bec827730d785ac541c665d54 Mon Sep 17 00:00:00 2001 From: twall Date: Wed, 31 Jul 2019 11:34:47 -0500 Subject: [PATCH 02/12] fixing stylistic errors. --- noether_examples/CMakeLists.txt | 10 +-- noether_examples/launch/thick_sim.launch | 2 - noether_examples/package.xml | 1 - .../src/thickness_simulator_client.cpp | 86 ++++++++----------- noether_simulator/CMakeLists.txt | 15 +++- noether_simulator/package.xml | 1 - .../src/thickness_simulator_node.cpp | 5 +- noether_simulator/test/utest.cpp | 4 - .../src/raster_tool_path_planner.cpp | 2 - vtk_viewer/src/vtk_viewer.cpp | 2 +- vtk_viewer/test/utest.cpp | 4 +- 11 files changed, 53 insertions(+), 79 deletions(-) diff --git a/noether_examples/CMakeLists.txt b/noether_examples/CMakeLists.txt index 872a1ec4..fa9ba62f 100644 --- a/noether_examples/CMakeLists.txt +++ b/noether_examples/CMakeLists.txt @@ -8,12 +8,8 @@ project(noether_examples) find_package(VTK 7.1 REQUIRED NO_MODULE) include(${VTK_USE_FILE}) -find_package(PCL 1.8 REQUIRED) -find_package(Boost REQUIRED COMPONENTS system) - find_package(catkin REQUIRED COMPONENTS actionlib - #actionlib_msgs cmake_modules mesh_segmenter noether_conversions @@ -47,9 +43,6 @@ catkin_package( VTK ) - - - include_directories( include ${catkin_INCLUDE_DIRS} @@ -71,7 +64,6 @@ target_link_libraries(mesh_segmenter_node ${VTK_LIBRARIES} ) -#action client add_executable(thickness_simulator_client src/thickness_simulator_client.cpp) add_dependencies(thickness_simulator_client ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS} @@ -87,7 +79,7 @@ target_link_libraries(thickness_simulator_client ############# ## Install ## ############# -install(TARGETS mesh_segmenter_client_node mesh_segmenter_node +install(TARGETS mesh_segmenter_client_node mesh_segmenter_node thickness_simulator_client ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} diff --git a/noether_examples/launch/thick_sim.launch b/noether_examples/launch/thick_sim.launch index 3dcca9f7..05f9f82d 100644 --- a/noether_examples/launch/thick_sim.launch +++ b/noether_examples/launch/thick_sim.launch @@ -1,5 +1,3 @@ - - diff --git a/noether_examples/package.xml b/noether_examples/package.xml index 35062e53..68a631dc 100644 --- a/noether_examples/package.xml +++ b/noether_examples/package.xml @@ -10,7 +10,6 @@ cmake_modules noether_conversions - actionlib mesh_segmenter noether_msgs diff --git a/noether_examples/src/thickness_simulator_client.cpp b/noether_examples/src/thickness_simulator_client.cpp index 3f810482..b0bab43a 100644 --- a/noether_examples/src/thickness_simulator_client.cpp +++ b/noether_examples/src/thickness_simulator_client.cpp @@ -2,26 +2,22 @@ #include #include #include -#include #include #include -#include #include -#include - -#include -#include #include #include +#include +#include +#include +#include +#include #include #include - #include #include - - //make modified meshes vtkSmartPointer createPlaneMod(unsigned int grid_size_x, unsigned int grid_size_y, vtk_viewer::plane_type type) { @@ -61,7 +57,6 @@ vtkSmartPointer createPlaneMod(unsigned int grid_size_x, unsigned int return points; } - int main (int argc, char **argv) { ros::init(argc, argv, "test_noether_simulator"); @@ -89,7 +84,6 @@ int main (int argc, char **argv) double pt3[3] = {5.0, 3.0, 0.0}; double pt4[3] = {4.0, 4.0, 0.0}; - points2->InsertNextPoint(pt1); points2->InsertNextPoint(pt2); points2->InsertNextPoint(pt3); @@ -129,51 +123,41 @@ int main (int argc, char **argv) } //........end create control meshes //........create robot path - //if(count==0) - //{ - //vtkSmartPointer cut = vtkSmartPointer::New(); - cut = vtk_viewer::cutMesh(data, points2, false); - //pcl::PolygonMesh *test = new(pcl::PolygonMesh); - pcl::VTKUtils::convertToPCL(cut, *test); - - // Run tool path planner on mesh - tool_path_planner::RasterToolPathPlanner planner; - planner.setInputMesh(cut); - - tool_path_planner::ProcessTool tool; - tool.pt_spacing = 0.5; - tool.line_spacing = .75; - tool.tool_offset = 0.0; // currently unused - tool.intersecting_plane_height = 0.15; // 0.5 works best, not sure if this should be included in the tool - tool.nearest_neighbors = 30; // not sure if this should be a part of the tool - tool.min_hole_size = 0.1; - tool.min_segment_size = 1; - tool.raster_angle = 0; - tool.raster_wrt_global_axes = 0; - tool.tool_radius = 1; - tool.tool_height = 2; - planner.setTool(tool); - planner.setDebugMode(false); - - planner.computePaths(); - - - std::vector paths = planner.getPaths(); - myPath = tool_path_planner::toPosesMsgs(paths); - - noether_msgs::ToolRasterPath rasterPath; - rasterPath.paths = myPath; - goal.path.push_back(rasterPath); - - //} + + cut = vtk_viewer::cutMesh(data, points2, false); + pcl::VTKUtils::convertToPCL(cut, *test); + + // Run tool path planner on mesh + tool_path_planner::RasterToolPathPlanner planner; + planner.setInputMesh(cut); + + tool_path_planner::ProcessTool tool; + tool.pt_spacing = 0.5; + tool.line_spacing = .75; + tool.tool_offset = 0.0; // currently unused + tool.intersecting_plane_height = 0.15; // 0.5 works best, not sure if this should be included in the tool + tool.nearest_neighbors = 30; // not sure if this should be a part of the tool + tool.min_hole_size = 0.1; + tool.min_segment_size = 1; + tool.raster_angle = 0; + tool.raster_wrt_global_axes = 0; + tool.tool_radius = 1; + tool.tool_height = 2; + planner.setTool(tool); + planner.setDebugMode(false); + planner.computePaths(); + std::vector paths = planner.getPaths(); + myPath = tool_path_planner::toPosesMsgs(paths); + + noether_msgs::ToolRasterPath rasterPath; + rasterPath.paths = myPath; + goal.path.push_back(rasterPath); + //........end robot path }//end multimesh creation loop //set goal values goal.input_mesh = myMeshs; - //noether_msgs::ToolRasterPath rasterPath; - //rasterPath.paths = myPath; - //goal.path.push_back(rasterPath); ac.sendGoal(goal); ROS_INFO(" sent mesh and path generation"); ROS_INFO("number of paths sent: %d ",goal.path.size()); diff --git a/noether_simulator/CMakeLists.txt b/noether_simulator/CMakeLists.txt index 7ba6374c..9ed3d711 100644 --- a/noether_simulator/CMakeLists.txt +++ b/noether_simulator/CMakeLists.txt @@ -76,7 +76,6 @@ target_link_libraries(noether_simulator_ ${PCL_LIBRARIES} ) -#action server add_executable(thick_sim src/thickness_simulator_node.cpp) add_dependencies(thick_sim ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS} @@ -101,3 +100,17 @@ target_link_libraries(noether_simulator-test ${VTK_LIBRARIES} ) endif() + +############# +## Install ## +############# +install(TARGETS noether_simulator_ thick_sim + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +) + +install(DIRECTORY include/${PROJECT_NAME}/ + DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} + PATTERN ".svn" EXCLUDE +) diff --git a/noether_simulator/package.xml b/noether_simulator/package.xml index 5f5c4551..1304d720 100644 --- a/noether_simulator/package.xml +++ b/noether_simulator/package.xml @@ -39,5 +39,4 @@ pcl_conversions dynamic_reconfigure - diff --git a/noether_simulator/src/thickness_simulator_node.cpp b/noether_simulator/src/thickness_simulator_node.cpp index 6699f9d8..2dacae3b 100644 --- a/noether_simulator/src/thickness_simulator_node.cpp +++ b/noether_simulator/src/thickness_simulator_node.cpp @@ -10,6 +10,7 @@ #include #include + #include #include "noether_simulator/noether_simulator.h" @@ -18,8 +19,6 @@ #include #include -#include - namespace noether_simulator { class ProcessSimulatorNode{ @@ -237,8 +236,6 @@ class ProcessSimulatorNode{ };//end class }//end namespace - - int main(int argc, char** argv) { ros::init(argc, argv, "noether_simulator"); diff --git a/noether_simulator/test/utest.cpp b/noether_simulator/test/utest.cpp index 46ce1493..8060554d 100644 --- a/noether_simulator/test/utest.cpp +++ b/noether_simulator/test/utest.cpp @@ -19,7 +19,6 @@ // result of painting the mesh using the // given path. - //This test uses poor path to paint mesh TEST(ViewerTest, TestCase1) { @@ -123,7 +122,6 @@ TEST(ViewerTest, TestCase1) intensity[1] = processedPoints->GetPointData()->GetScalars()->GetComponent(i,1); intensity[2] = processedPoints->GetPointData()->GetScalars()->GetComponent(i,2); - if((intensity[0]+intensity[1]+intensity[2])/3.0 < 5) //averge of each pixel if less than threshold incrament counter { missed++; @@ -245,7 +243,6 @@ TEST(ViewerTest, TestCase2) { missed++; } - } if(missed/float(processedPoints->GetNumberOfPoints())>0.1)//get ratio of missed spots, if below threshold set not painted { @@ -255,7 +252,6 @@ TEST(ViewerTest, TestCase2) EXPECT_TRUE(painted);//expect good mesh to pass } - // Run all the tests that were declared with TEST() int main(int argc, char **argv) { diff --git a/tool_path_planner/src/raster_tool_path_planner.cpp b/tool_path_planner/src/raster_tool_path_planner.cpp index 6d15e0fc..a09d19c1 100644 --- a/tool_path_planner/src/raster_tool_path_planner.cpp +++ b/tool_path_planner/src/raster_tool_path_planner.cpp @@ -6,7 +6,6 @@ #include #include -#include #include #include @@ -822,7 +821,6 @@ namespace tool_path_planner // Check to make sure that the input cut surface contains a valid mesh if(cut_surface->GetNumberOfCells() < 1) { - LOG4CXX_ERROR(RASTER_PATH_PLANNER_LOGGER, "Number of input cells for calculating intersection is less than 1, cannot compute intersection"); return false; diff --git a/vtk_viewer/src/vtk_viewer.cpp b/vtk_viewer/src/vtk_viewer.cpp index da22f29a..eba32377 100644 --- a/vtk_viewer/src/vtk_viewer.cpp +++ b/vtk_viewer/src/vtk_viewer.cpp @@ -24,6 +24,7 @@ #include #include + #define VTK_SP(type, name)\ vtkSmartPointer name = vtkSmartPointer::New() @@ -139,7 +140,6 @@ namespace vtk_viewer this->renderer_->AddActor(actors_.back()); } - VTKViewer::~VTKViewer() { renWin_->Delete(); diff --git a/vtk_viewer/test/utest.cpp b/vtk_viewer/test/utest.cpp index d2464b1d..98c050eb 100644 --- a/vtk_viewer/test/utest.cpp +++ b/vtk_viewer/test/utest.cpp @@ -8,7 +8,7 @@ #include #include #include -#include + // This test shows the results of meshing on a square grid that has a sinusoidal // variability in the z axis. Red arrows show the surface normal for each triangle // in the mesh, and cyan boxes show the points used to seed the mesh creation algorithm @@ -38,8 +38,6 @@ TEST(ViewerTest, TestCase1) cout << "cutter points: " << cut->GetPoints()->GetNumberOfPoints() << "\n"; cout << "cutter lines: " << cut->GetNumberOfLines() << "\n"; - - vtk_viewer::VTKViewer viz; std::vector color(3); From af2599a40285e90272eca8fac5de82e42c7b0109 Mon Sep 17 00:00:00 2001 From: twall Date: Thu, 1 Aug 2019 08:57:24 -0500 Subject: [PATCH 03/12] More stylisitic updates --- .../src/thickness_simulator_client.cpp | 41 +++++++++ noether_simulator/cfg/NoetherSimulator.cfg | 8 +- .../noether_simulator/noether_simulator.h | 19 +++++ noether_simulator/package.xml | 4 +- noether_simulator/src/noether_simulator.cpp | 39 +++++---- .../src/thickness_simulator_node.cpp | 85 ++++++++++++++----- noether_simulator/test/utest.cpp | 31 ++++++- .../path_sequence_planner.h | 16 +++- .../simple_path_sequence_planner.h | 16 +++- .../src/path_sequence_planner.cpp | 16 +++- .../src/simple_path_sequence_planner.cpp | 16 +++- path_sequence_planner/test/utest.cpp | 16 +++- .../tool_path_planner/raster_path_generator.h | 18 +++- .../raster_tool_path_planner.h | 15 +++- .../tool_path_planner_base.h | 16 +++- .../include/tool_path_planner/utilities.h | 15 +++- .../src/raster_path_generator.cpp | 17 +++- .../src/raster_tool_path_planner.cpp | 16 +++- tool_path_planner/src/utilities.cpp | 23 +++-- tool_path_planner/test/utest.cpp | 19 ++++- .../include/vtk_viewer/mouse_interactor.h | 18 ++++ vtk_viewer/include/vtk_viewer/vtk_utils.h | 21 +++-- vtk_viewer/include/vtk_viewer/vtk_viewer.h | 20 ++++- vtk_viewer/src/mouse_interactor.cpp | 18 ++++ vtk_viewer/src/vtk_utils.cpp | 14 ++- vtk_viewer/src/vtk_viewer.cpp | 14 ++- vtk_viewer/test/utest.cpp | 17 +++- 27 files changed, 471 insertions(+), 97 deletions(-) diff --git a/noether_examples/src/thickness_simulator_client.cpp b/noether_examples/src/thickness_simulator_client.cpp index b0bab43a..8355fbd1 100644 --- a/noether_examples/src/thickness_simulator_client.cpp +++ b/noether_examples/src/thickness_simulator_client.cpp @@ -1,3 +1,28 @@ +/* + * Software License Agreement (Apache License) + * + * Copyright (c) 2016, Southwest Research Institute + * + * file thickness_simulator_client.cpp + * All rights reserved. + * copyright Copyright (c) 2019, Southwest Research Institute + * + * License + * Software License Agreement (Apache License) + * + * 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. + */ + #include #include #include @@ -18,6 +43,22 @@ #include #include +/*This example shows how the thickness_simulator_node.cpp works. + * First, it creates 3 meshes and three paths. + * Then, it passes these meshes and paths to the thickness_simulator_node. + * The thickness_simulator_node runs the first path across each mesh. + * If the mesh is sufficently painted the bool corasponding to that mesh in the painted[] + * is set to true, the mesh is excluded from future iterations, and the path is added to the reuqiredPaths[] unless, + * it has already been added. + * once all the meshes have been evaluated using the first path, the simulator moves on to the second path. + * The simulator evaluates the remaining meshes with the second path and so on until all meshes have the coraspoinding + * bool value in painted[] set to true, or all paths have been tried. + * + * To use roslauch to launch the thick_sim.launch file. Then, in a seperate termial window use rosrun to run the + * noether_simulator_node.cpp + * +*/ + //make modified meshes vtkSmartPointer createPlaneMod(unsigned int grid_size_x, unsigned int grid_size_y, vtk_viewer::plane_type type) { diff --git a/noether_simulator/cfg/NoetherSimulator.cfg b/noether_simulator/cfg/NoetherSimulator.cfg index cdbc969d..934767d9 100755 --- a/noether_simulator/cfg/NoetherSimulator.cfg +++ b/noether_simulator/cfg/NoetherSimulator.cfg @@ -9,9 +9,9 @@ gen = ParameterGenerator() to = gen #.add_group("toggle_options") -to.add("display_sigma", double_t, 0, "display_sigma", 1.0, 0.1, 10.0) -to.add("tool_radius", double_t, 0, "tool_radius", 0.05, 0.001, 1.0) -to.add("process_rate", double_t, 0, "process base deposition/removal rate", 5.0, 0.001, 20.0) -to.add("tool_height", double_t, 0, "tool_height", 0.1, 0.001, 1.0) +#to.add("display_sigma", double_t, 0, "display_sigma", 1.0, 0.1, 10.0) +#to.add("tool_radius", double_t, 0, "tool_radius", 0.05, 0.001, 1.0) +#to.add("process_rate", double_t, 0, "process base deposition/removal rate", 5.0, 0.001, 20.0) +#to.add("tool_height", double_t, 0, "tool_height", 0.1, 0.001, 1.0) exit(gen.generate(PACKAGE, "noether_simulator", "NoetherSimulator")) diff --git a/noether_simulator/include/noether_simulator/noether_simulator.h b/noether_simulator/include/noether_simulator/noether_simulator.h index 6924d265..b566704b 100644 --- a/noether_simulator/include/noether_simulator/noether_simulator.h +++ b/noether_simulator/include/noether_simulator/noether_simulator.h @@ -2,9 +2,28 @@ #define NOETHER_SIMULATOR_H /* + * Software License Agreement (Apache License) + * * Copyright (c) 2016, Southwest Research Institute + * + * file noether_simulator.h * All rights reserved. + * copyright Copyright (c) 2019, Southwest Research Institute + * + * License + * Software License Agreement (Apache License) + * + * 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. */ #include diff --git a/noether_simulator/package.xml b/noether_simulator/package.xml index 1304d720..2814c1f4 100644 --- a/noether_simulator/package.xml +++ b/noether_simulator/package.xml @@ -3,8 +3,8 @@ noether_simulator 0.0.0 The noether_simulator package - alex - Proprietary + trent + Apache catkin diff --git a/noether_simulator/src/noether_simulator.cpp b/noether_simulator/src/noether_simulator.cpp index fc03a8e3..479f9c62 100644 --- a/noether_simulator/src/noether_simulator.cpp +++ b/noether_simulator/src/noether_simulator.cpp @@ -1,9 +1,28 @@ /* + * Software License Agreement (Apache License) + * * Copyright (c) 2016, Southwest Research Institute + * + * file noether_simulator.cpp * All rights reserved. + * copyright Copyright (c) 2019, Southwest Research Institute + * + * License + * Software License Agreement (Apache License) + * + * 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. */ - +#include #include #include @@ -34,14 +53,9 @@ namespace noether_simulator double NoetherSimulator::integral(double pt[3]) { - //double k = process_base_rate_; + double result; - // t is not currently added/used, but can be so as to allow time parameterization between process points - // f(x,y,z,t) = -x^2 - y^2 - (z - k) - // integral(f) = -x^3*y*z/3 - x*y^3*z/3 - x*y*z^2/2 + k*x*y*z - // TODO: the above equation does not work (integrates area, not along a line) - // TODO: again, cylinder is along y-axis, so y and z are flipped - result = -( pow(pt[0],3.0)) /3.0 - (pow(pt[2],3.0))/3.0 ; + result = -( pow(pt[0],3.0)) /3.0 - (pow(pt[2],3.0))/3.0 ; return 10*result; } @@ -50,8 +64,6 @@ namespace noether_simulator { if(points->GetNumberOfPoints() < 2) return 0; - // This is a place holder equation for the tool and is process specific - // TODO: create a more generic interface to allow for other tools to be created and used double pt1[3], pt2[3]; double val1, val2; @@ -74,8 +86,7 @@ vtkSmartPointer NoetherSimulator::getSimulatedPoints() void NoetherSimulator::runSimulation() { - - cout << "starting simulation\n"; + ROS_INFO("starting simulation\n"); std::vector color(3); color[0] = 0.9; color[1] = 0.9; color[2] = 0.9; @@ -111,8 +122,6 @@ vtkSmartPointer NoetherSimulator::getSimulatedPoints() int number_paths =input_paths_.size(); for(int i = 0; i GetNumberOfPoints() - 1; for(int j = 0; j < number_points; ++j) @@ -333,7 +342,7 @@ vtkSmartPointer NoetherSimulator::getSimulatedPoints() double range[2]; scalars->GetRange(range); - cout << "scalar range " << range[0] << " " << range[1] << "\n"; + ROS_INFO("scalar range %f %f \n",range[0],range[1]); double upper_bound = mean + std_dev * scalar_sigma_; double lower_bound = mean - std_dev * scalar_sigma_; diff --git a/noether_simulator/src/thickness_simulator_node.cpp b/noether_simulator/src/thickness_simulator_node.cpp index 2dacae3b..cc8cb807 100644 --- a/noether_simulator/src/thickness_simulator_node.cpp +++ b/noether_simulator/src/thickness_simulator_node.cpp @@ -1,3 +1,27 @@ +/* + * Software License Agreement (Apache License) + * + * Copyright (c) 2016, Southwest Research Institute + * + * file thickness_simulator_node.cpp + * All rights reserved. + * copyright Copyright (c) 2019, Southwest Research Institute + * + * License + * Software License Agreement (Apache License) + * + * 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. + */ #include "ros/ros.h" #include #include @@ -35,7 +59,6 @@ class ProcessSimulatorNode{ void updateParameters(noether_simulator::NoetherSimulatorConfig& config, uint32_t level); dynamic_reconfigure::Server reconfigurer_; boost::mutex param_lock_; - //tool_path_planner::ProcessTool tool_; double vect_[3], center_[3]; bool debug_on_; std::string log_directory_; @@ -128,17 +151,17 @@ class ProcessSimulatorNode{ //add tool tool_path_planner::ProcessTool tool; - tool.pt_spacing = 0.5; - tool.line_spacing = 0.75; - tool.tool_offset = 0.0; // currently unused - tool.intersecting_plane_height = 0.15; // 0.5 works best, not sure if this should be included in the tool - tool.nearest_neighbors = 30; // not sure if this should be a part of the tool - tool.min_hole_size = 0.1; - tool.min_segment_size = 1; - tool.raster_angle = 0; - tool.raster_wrt_global_axes = 0; - tool.tool_radius = 1; - tool.tool_height = 2; + nh_.param("/noether_simulator/pt_spacing",tool.pt_spacing, 0.5); + nh_.param("/nnoether_simulator/line_spacing",tool.line_spacing,0.75); + nh_.param("/noether_simulator/tool_offset",tool.tool_offset, 0.0); + nh_.param("/noether_simulator/intersecting_plane_hiehgt",tool.intersecting_plane_height,0.15); + nh_.param("/noether_simulator/nearest_neighbors",tool.nearest_neighbors,30); + nh_.param("/noether_simulator/min_hole_size",tool.min_hole_size,0.1); + nh_.param("/noether_simulator/min_segment_size",tool.min_segment_size,1.0); + nh_.param("/noether_simulator/raster_angle",tool.raster_angle,0.0); + nh_.param("/noether_simulator/raster_wrt_global_axes",tool.raster_wrt_global_axes ,false); + nh_.param("/noether_simulator/tool_radius",tool.tool_radius,1.0); + nh_.param("/noeterh_simulator/tool_height",tool.tool_height,2.0); sim.setTool(tool); for(int i=0; i processedPoints = vtkSmartPointer::New(); processedPoints = sim.getSimulatedPoints();//get a copy of simulated points to operate on vtkIdType length = processedPoints->GetNumberOfPoints(); - double intensity[3]; + + double intensity[3] = {0,0,0};//setup flann int missed = 0; double minPaintThreshold = 5; double maxPassableNonpainted = 0.1; + double p [3]; + vtkSmartPointer pointTree = + vtkSmartPointer::New(); + pointTree->SetDataSet(processedPoints); + pointTree->BuildLocator(); + unsigned int k = 30; + double currPoint [3]; - //******TODO*******// - // replace with FLANN for(vtkIdType a = 0; a < length; a++)//iterate through points to check if painted { - intensity[0] = processedPoints->GetPointData()->GetScalars()->GetComponent(a,0); - intensity[1] = processedPoints->GetPointData()->GetScalars()->GetComponent(a,1); - intensity[2] = processedPoints->GetPointData()->GetScalars()->GetComponent(a,2); + intensity[0] =0;//reseting intensity for next point in mesh + intensity[1] =0; + intensity[2] =0; + + vtkSmartPointer result = vtkSmartPointer::New(); + processedPoints->GetPoint(a,currPoint); + pointTree->FindClosestNPoints(k, currPoint, result);//flann + + for (vtkIdType i = 0; i < k; i++)//iterate through k closest points average intensities + { + vtkIdType point_ind = result->GetId(i); + + //find average color intensity for each neighorhood + intensity[0] += processedPoints->GetPointData()->GetScalars()->GetComponent(point_ind,0); + intensity[1] += processedPoints->GetPointData()->GetScalars()->GetComponent(point_ind,1); + intensity[2] += processedPoints->GetPointData()->GetScalars()->GetComponent(point_ind,2); + } - if((intensity[0]+intensity[1]+intensity[2])/3.0 < minPaintThreshold) //averge of each pixel if less than threshold incrament counter + if((intensity[0])/float(k)+(intensity[1])/float(k)+(intensity[2])/30 < minPaintThreshold) //averge of each pixel if less than threshold incrament counter { missed++; } @@ -218,7 +260,6 @@ class ProcessSimulatorNode{ added = true; } } - //******END TODO******// feedback_.percent =float(i)/float(num_meshes); simulation_service_.publishFeedback(feedback_); diff --git a/noether_simulator/test/utest.cpp b/noether_simulator/test/utest.cpp index 8060554d..5faa6d8b 100644 --- a/noether_simulator/test/utest.cpp +++ b/noether_simulator/test/utest.cpp @@ -1,7 +1,26 @@ /* + * Software License Agreement (Apache License) + * * Copyright (c) 2016, Southwest Research Institute + * + * file utest.cpp * All rights reserved. + * copyright Copyright (c) 2019, Southwest Research Institute + * + * License + * Software License Agreement (Apache License) + * + * 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. */ #include #include @@ -69,6 +88,10 @@ TEST(ViewerTest, TestCase1) planner.computePaths(); + // The NDEBUG variable is defined by the C/C++ standard when building + // "Not Debug" (e.g. release). NDEBUG is not defined during debug + // builds - so the below code runs when building debug + #ifndef NDEBUG vtk_viewer::VTKViewer viz; std::vector color(3); @@ -95,7 +118,7 @@ TEST(ViewerTest, TestCase1) viz.addPolyNormalsDisplay(paths[i].derivatives, color, scale); } viz.renderDisplay(); - + #endif // Run simulator on mesh and tool paths noether_simulator::NoetherSimulator simulator; @@ -187,6 +210,10 @@ TEST(ViewerTest, TestCase2) planner.computePaths(); + // The NDEBUG variable is defined by the C/C++ standard when building + // "Not Debug" (e.g. release). NDEBUG is not defined during debug + // builds - so the below code runs when building debug + #ifndef NDEBUG vtk_viewer::VTKViewer viz; std::vector color(3); @@ -213,7 +240,7 @@ TEST(ViewerTest, TestCase2) viz.addPolyNormalsDisplay(paths[i].derivatives, color, scale); } viz.renderDisplay();//display planned paths on mesh - + #endif // Run simulator on mesh and tool paths noether_simulator::NoetherSimulator simulator; diff --git a/path_sequence_planner/include/path_sequence_planner/path_sequence_planner.h b/path_sequence_planner/include/path_sequence_planner/path_sequence_planner.h index 6043da38..cd329c53 100644 --- a/path_sequence_planner/include/path_sequence_planner/path_sequence_planner.h +++ b/path_sequence_planner/include/path_sequence_planner/path_sequence_planner.h @@ -1,7 +1,19 @@ /* - * Copyright (c) 2016, Southwest Research Institute - * All rights reserved. + * Software License Agreement (Apache License) * + * Copyright (c) 2018, Southwest Research Institute + * + * 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. */ #ifndef PATH_SEQUENCE_PLANNER_H diff --git a/path_sequence_planner/include/path_sequence_planner/simple_path_sequence_planner.h b/path_sequence_planner/include/path_sequence_planner/simple_path_sequence_planner.h index c350a001..cf1035ba 100644 --- a/path_sequence_planner/include/path_sequence_planner/simple_path_sequence_planner.h +++ b/path_sequence_planner/include/path_sequence_planner/simple_path_sequence_planner.h @@ -1,7 +1,19 @@ /* - * Copyright (c) 2016, Southwest Research Institute - * All rights reserved. + * Software License Agreement (Apache License) * + * Copyright (c) 2018, Southwest Research Institute + * + * 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. */ #ifndef SIMPLE_PATH_SEQUENCE_PLANNER_H diff --git a/path_sequence_planner/src/path_sequence_planner.cpp b/path_sequence_planner/src/path_sequence_planner.cpp index e641b0f3..a9e275cd 100644 --- a/path_sequence_planner/src/path_sequence_planner.cpp +++ b/path_sequence_planner/src/path_sequence_planner.cpp @@ -1,7 +1,19 @@ /* - * Copyright (c) 2016, Southwest Research Institute - * All rights reserved. + * Software License Agreement (Apache License) * + * Copyright (c) 2018, Southwest Research Institute + * + * 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. */ #include diff --git a/path_sequence_planner/src/simple_path_sequence_planner.cpp b/path_sequence_planner/src/simple_path_sequence_planner.cpp index b1f3f793..15aaa06d 100644 --- a/path_sequence_planner/src/simple_path_sequence_planner.cpp +++ b/path_sequence_planner/src/simple_path_sequence_planner.cpp @@ -1,7 +1,19 @@ /* - * Copyright (c) 2016, Southwest Research Institute - * All rights reserved. + * Software License Agreement (Apache License) * + * Copyright (c) 2018, Southwest Research Institute + * + * 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. */ #include diff --git a/path_sequence_planner/test/utest.cpp b/path_sequence_planner/test/utest.cpp index 2b233aac..16b3afb4 100644 --- a/path_sequence_planner/test/utest.cpp +++ b/path_sequence_planner/test/utest.cpp @@ -1,10 +1,22 @@ - /* + * Software License Agreement (Apache License) + * * Copyright (c) 2016, Southwest Research Institute - * 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. */ + #include #include #include diff --git a/tool_path_planner/include/tool_path_planner/raster_path_generator.h b/tool_path_planner/include/tool_path_planner/raster_path_generator.h index a13f9a75..07000428 100644 --- a/tool_path_planner/include/tool_path_planner/raster_path_generator.h +++ b/tool_path_planner/include/tool_path_planner/raster_path_generator.h @@ -1,12 +1,22 @@ /* + * Software License Agreement (Apache License) + * * Copyright (c) 2018, Southwest Research Institute - * All rights reserved.* - * tool_path_generator.h * - * Created on: Nov 15, 2018 - * Author: Jorge Nicho + * 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. */ + #ifndef INCLUDE_TOOL_PATH_PLANNER_RASTER_PATH_GENERATOR_H_ #define INCLUDE_TOOL_PATH_PLANNER_RASTER_PATH_GENERATOR_H_ diff --git a/tool_path_planner/include/tool_path_planner/raster_tool_path_planner.h b/tool_path_planner/include/tool_path_planner/raster_tool_path_planner.h index 05fdf964..4961639e 100644 --- a/tool_path_planner/include/tool_path_planner/raster_tool_path_planner.h +++ b/tool_path_planner/include/tool_path_planner/raster_tool_path_planner.h @@ -1,9 +1,22 @@ /* + * Software License Agreement (Apache License) + * * Copyright (c) 2016, Southwest Research Institute - * 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. */ + #ifndef RASTER_TOOL_PATH_PLANNER_H #define RASTER_TOOL_PATH_PLANNER_H diff --git a/tool_path_planner/include/tool_path_planner/tool_path_planner_base.h b/tool_path_planner/include/tool_path_planner/tool_path_planner_base.h index 0e41a6bf..4520ee37 100644 --- a/tool_path_planner/include/tool_path_planner/tool_path_planner_base.h +++ b/tool_path_planner/include/tool_path_planner/tool_path_planner_base.h @@ -1,7 +1,19 @@ /* - * Copyright (c) 2016, Southwest Research Institute - * All rights reserved. + * Software License Agreement (Apache License) * + * Copyright (c) 2018, Southwest Research Institute + * + * 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. */ #ifndef TOOL_PATH_PLANNER_H diff --git a/tool_path_planner/include/tool_path_planner/utilities.h b/tool_path_planner/include/tool_path_planner/utilities.h index 3490fdc2..d29efb80 100644 --- a/tool_path_planner/include/tool_path_planner/utilities.h +++ b/tool_path_planner/include/tool_path_planner/utilities.h @@ -1,12 +1,19 @@ /* + * Software License Agreement (Apache License) * * Copyright (c) 2018, Southwest Research Institute - * All rights reserved.* * - * utilities.h + * 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 * - * Created on: Nov 15, 2018 - * Author: Jorge Nicho + * 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. */ #ifndef INCLUDE_TOOL_PATH_PLANNER_UTILITIES_H_ diff --git a/tool_path_planner/src/raster_path_generator.cpp b/tool_path_planner/src/raster_path_generator.cpp index a6c962f3..cf268242 100644 --- a/tool_path_planner/src/raster_path_generator.cpp +++ b/tool_path_planner/src/raster_path_generator.cpp @@ -1,10 +1,19 @@ /* + * Software License Agreement (Apache License) + * * Copyright (c) 2018, Southwest Research Institute - * All rights reserved.* - * tool_path_generator.cpp * - * Created on: Nov 15, 2018 - * Author: Jorge Nicho + * 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. */ #include diff --git a/tool_path_planner/src/raster_tool_path_planner.cpp b/tool_path_planner/src/raster_tool_path_planner.cpp index a09d19c1..e1e9be35 100644 --- a/tool_path_planner/src/raster_tool_path_planner.cpp +++ b/tool_path_planner/src/raster_tool_path_planner.cpp @@ -1,7 +1,19 @@ /* - * Copyright (c) 2016, Southwest Research Institute - * All rights reserved. + * Software License Agreement (Apache License) * + * Copyright (c) 2018, Southwest Research Institute + * + * 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. */ #include diff --git a/tool_path_planner/src/utilities.cpp b/tool_path_planner/src/utilities.cpp index 02123d2d..5915deb2 100644 --- a/tool_path_planner/src/utilities.cpp +++ b/tool_path_planner/src/utilities.cpp @@ -1,10 +1,19 @@ /* + * Software License Agreement (Apache License) + * * Copyright (c) 2018, Southwest Research Institute - * All rights reserved.* - * utilities.cpp * - * Created on: Nov 16, 2018 - * Author: Jorge Nicho + * 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. */ #include @@ -196,13 +205,13 @@ noether_msgs::ToolPathConfig toTppMsg(const tool_path_planner::ProcessTool& tool tpp_config_msg.line_spacing = tool_config.line_spacing; tpp_config_msg.tool_offset = tool_config.tool_offset; tpp_config_msg.intersecting_plane_height = tool_config.intersecting_plane_height; - tpp_config_msg.nearest_neighbors = tool_config.nearest_neighbors;//Trent added + tpp_config_msg.nearest_neighbors = tool_config.nearest_neighbors; tpp_config_msg.min_hole_size = tool_config.min_hole_size; tpp_config_msg.min_segment_size = tool_config.min_segment_size; tpp_config_msg.raster_angle = tpp_config_msg.raster_angle; tpp_config_msg.raster_wrt_global_axes = tpp_config_msg.raster_wrt_global_axes; - tpp_config_msg.tool_radius = tpp_config_msg.tool_radius;//Trent added - tpp_config_msg.tool_height = tpp_config_msg.tool_radius;//Trent added + tpp_config_msg.tool_radius = tpp_config_msg.tool_radius; + tpp_config_msg.tool_height = tpp_config_msg.tool_radius; return std::move(tpp_config_msg); } diff --git a/tool_path_planner/test/utest.cpp b/tool_path_planner/test/utest.cpp index a0c30823..d24a762c 100644 --- a/tool_path_planner/test/utest.cpp +++ b/tool_path_planner/test/utest.cpp @@ -1,10 +1,23 @@ - /* - * Copyright (c) 2016, Southwest Research Institute - * All rights reserved. + * Software License Agreement (Apache License) + * + * Copyright (c) 2018, Southwest Research Institute + * + * 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. */ + + #include #include #include diff --git a/vtk_viewer/include/vtk_viewer/mouse_interactor.h b/vtk_viewer/include/vtk_viewer/mouse_interactor.h index 163e9cec..ca2a41bd 100644 --- a/vtk_viewer/include/vtk_viewer/mouse_interactor.h +++ b/vtk_viewer/include/vtk_viewer/mouse_interactor.h @@ -1,6 +1,24 @@ #ifndef MOUSE_INTERACTOR_H #define MOUSE_INTERACTOR_H +/* + * Software License Agreement (Apache License) + * + * Copyright (c) 2016, Southwest Research Institute + * + * 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. + */ + #include #include diff --git a/vtk_viewer/include/vtk_viewer/vtk_utils.h b/vtk_viewer/include/vtk_viewer/vtk_utils.h index 3367cb23..d653cb38 100644 --- a/vtk_viewer/include/vtk_viewer/vtk_utils.h +++ b/vtk_viewer/include/vtk_viewer/vtk_utils.h @@ -1,13 +1,24 @@ +#ifndef NOETHER_VTK_UTILS_H +#define NOETHER_VTK_UTILS_H + /* + * Software License Agreement (Apache License) + * * Copyright (c) 2016, Southwest Research Institute - * 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. */ - -#ifndef NOETHER_VTK_UTILS_H -#define NOETHER_VTK_UTILS_H - #include #include #include diff --git a/vtk_viewer/include/vtk_viewer/vtk_viewer.h b/vtk_viewer/include/vtk_viewer/vtk_viewer.h index 4b873a59..f9d1e1ac 100644 --- a/vtk_viewer/include/vtk_viewer/vtk_viewer.h +++ b/vtk_viewer/include/vtk_viewer/vtk_viewer.h @@ -1,12 +1,24 @@ +#ifndef VTK_VIEWER_H +#define VTK_VIEWER_H + /* + * Software License Agreement (Apache License) + * * Copyright (c) 2016, Southwest Research Institute - * 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. */ -#ifndef VTK_VIEWER_H -#define VTK_VIEWER_H - #include "vtkConeSource.h" #include "vtkPolyDataMapper.h" #include "vtkRenderWindow.h" diff --git a/vtk_viewer/src/mouse_interactor.cpp b/vtk_viewer/src/mouse_interactor.cpp index f1efd5da..a06ac0d2 100644 --- a/vtk_viewer/src/mouse_interactor.cpp +++ b/vtk_viewer/src/mouse_interactor.cpp @@ -1,3 +1,21 @@ +/* + * Software License Agreement (Apache License) + * + * Copyright (c) 2016, Southwest Research Institute + * + * 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. + */ + #include #include #include diff --git a/vtk_viewer/src/vtk_utils.cpp b/vtk_viewer/src/vtk_utils.cpp index b7beaaf7..9e980102 100644 --- a/vtk_viewer/src/vtk_utils.cpp +++ b/vtk_viewer/src/vtk_utils.cpp @@ -1,7 +1,19 @@ /* + * Software License Agreement (Apache License) + * * Copyright (c) 2016, Southwest Research Institute - * 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. */ #include "vtk_viewer/vtk_utils.h" diff --git a/vtk_viewer/src/vtk_viewer.cpp b/vtk_viewer/src/vtk_viewer.cpp index eba32377..888d5d71 100644 --- a/vtk_viewer/src/vtk_viewer.cpp +++ b/vtk_viewer/src/vtk_viewer.cpp @@ -1,7 +1,19 @@ /* + * Software License Agreement (Apache License) + * * Copyright (c) 2016, Southwest Research Institute - * 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. */ #include "vtk_viewer/vtk_viewer.h" diff --git a/vtk_viewer/test/utest.cpp b/vtk_viewer/test/utest.cpp index 98c050eb..5e85b113 100644 --- a/vtk_viewer/test/utest.cpp +++ b/vtk_viewer/test/utest.cpp @@ -1,7 +1,19 @@ /* + * Software License Agreement (Apache License) + * * Copyright (c) 2016, Southwest Research Institute - * 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. */ #include @@ -35,9 +47,6 @@ TEST(ViewerTest, TestCase1) vtkSmartPointer cut = vtkSmartPointer::New(); cut = vtk_viewer::cutMesh(data, points2, false); - cout << "cutter points: " << cut->GetPoints()->GetNumberOfPoints() << "\n"; - cout << "cutter lines: " << cut->GetNumberOfLines() << "\n"; - vtk_viewer::VTKViewer viz; std::vector color(3); From d2a1a4141ff825c3c8e3fd268353ef819ce02eaf Mon Sep 17 00:00:00 2001 From: twall Date: Thu, 1 Aug 2019 11:17:05 -0500 Subject: [PATCH 04/12] making more stylistic changes --- .../src/thickness_simulator_client.cpp | 18 ++++---- noether_msgs/CMakeLists.txt | 2 +- ...ulator.action => SimulateThickness.action} | 0 noether_msgs/msg/ToolPathConfig.msg | 4 +- noether_simulator/CMakeLists.txt | 26 +++--------- noether_simulator/package.xml | 42 ++++++------------- noether_simulator/src/noether_simulator.cpp | 7 +--- .../src/thickness_simulator_node.cpp | 18 ++++---- noether_simulator/test/utest.cpp | 12 +++--- .../tool_path_planner_base.h | 6 +-- tool_path_planner/src/utilities.cpp | 8 ++-- 11 files changed, 53 insertions(+), 90 deletions(-) rename noether_msgs/action/{ThickSimulator.action => SimulateThickness.action} (100%) diff --git a/noether_examples/src/thickness_simulator_client.cpp b/noether_examples/src/thickness_simulator_client.cpp index 8355fbd1..b555389c 100644 --- a/noether_examples/src/thickness_simulator_client.cpp +++ b/noether_examples/src/thickness_simulator_client.cpp @@ -23,8 +23,6 @@ * limitations under the License. */ -#include -#include #include #include #include @@ -40,7 +38,7 @@ #include #include #include -#include +#include #include /*This example shows how the thickness_simulator_node.cpp works. @@ -104,7 +102,7 @@ int main (int argc, char **argv) // create the action client // true causes the client to spin its own thread - actionlib::SimpleActionClient ac("noether_simulator", true); + actionlib::SimpleActionClient ac("noether_simulator", true); ROS_INFO("Waiting for action server to start."); // wait for the action server to start @@ -112,7 +110,7 @@ int main (int argc, char **argv) ROS_INFO("Action server started, sending goal."); // send a goal to the action - noether_msgs::ThickSimulatorGoal goal; + noether_msgs::SimulateThicknessGoal goal; //......setup test meshes and path pcl_msgs::PolygonMesh myMesh; @@ -175,15 +173,15 @@ int main (int argc, char **argv) tool_path_planner::ProcessTool tool; tool.pt_spacing = 0.5; tool.line_spacing = .75; - tool.tool_offset = 0.0; // currently unused - tool.intersecting_plane_height = 0.15; // 0.5 works best, not sure if this should be included in the tool - tool.nearest_neighbors = 30; // not sure if this should be a part of the tool + tool.tool_offset = 0.0; + tool.intersecting_plane_height = 0.15; + tool.simulator_nearest_neighbors = 30; tool.min_hole_size = 0.1; tool.min_segment_size = 1; tool.raster_angle = 0; tool.raster_wrt_global_axes = 0; - tool.tool_radius = 1; - tool.tool_height = 2; + tool.simulator_tool_radius = 1; + tool.simulator_tool_height = 2; planner.setTool(tool); planner.setDebugMode(false); planner.computePaths(); diff --git a/noether_msgs/CMakeLists.txt b/noether_msgs/CMakeLists.txt index 2ccea337..50f10876 100644 --- a/noether_msgs/CMakeLists.txt +++ b/noether_msgs/CMakeLists.txt @@ -29,7 +29,7 @@ add_action_files( FILES GenerateToolPaths.action Segment.action - ThickSimulator.action + SimulateThickness.action ) generate_messages( diff --git a/noether_msgs/action/ThickSimulator.action b/noether_msgs/action/SimulateThickness.action similarity index 100% rename from noether_msgs/action/ThickSimulator.action rename to noether_msgs/action/SimulateThickness.action diff --git a/noether_msgs/msg/ToolPathConfig.msg b/noether_msgs/msg/ToolPathConfig.msg index 21d39ca0..9f72e654 100644 --- a/noether_msgs/msg/ToolPathConfig.msg +++ b/noether_msgs/msg/ToolPathConfig.msg @@ -2,11 +2,11 @@ float64 pt_spacing # Required spacing between path points float64 line_spacing # Offset between two rasters float64 tool_offset # How far off the surface the tool needs to be float64 intersecting_plane_height # Used by the raster_tool_path_planner when offsetting to an adjacent path, a new plane has to be formed, but not too big -float64 nearest_neighbors # how many neighbors are used to compute local normals Trent Added +float64 nearest_neighbors # how many neighbors are used to compute local normals float64 min_hole_size # A path may pass over holes smaller than this, but must be broken when larger holes are encounterd. float64 min_segment_size # The minimum segment size to allow when finding intersections; small segments will be discarded float64 raster_angle # Specifies the direction of the raster path in radians -float64 tool_radius # The radius of the tool (for process simulation) Trent added +float64 tool_radius # The radius of the tool (for process simulation) float64 tool_height # The height of the tool (for process simulation) # When set to TRUE: initial cuts are determined using the axes of the diff --git a/noether_simulator/CMakeLists.txt b/noether_simulator/CMakeLists.txt index 9ed3d711..80400e6e 100644 --- a/noether_simulator/CMakeLists.txt +++ b/noether_simulator/CMakeLists.txt @@ -13,7 +13,6 @@ find_package(PCL 1.8 REQUIRED) find_package(Boost REQUIRED COMPONENTS system) find_package(catkin REQUIRED cmake_modules - message_generation mesh_segmenter tool_path_planner path_sequence_planner @@ -25,32 +24,22 @@ find_package(catkin REQUIRED cmake_modules std_srvs pcl_conversions dynamic_reconfigure - genmsg actionlib actionlib_msgs ) -generate_messages( - DEPENDENCIES - pcl_msgs - sensor_msgs - geometry_msgs - actionlib_msgs -) - generate_dynamic_reconfigure_options( cfg/NoetherSimulator.cfg ) catkin_package( INCLUDE_DIRS include - LIBRARIES noether_simulator_ + LIBRARIES ${PROJECT_NAME} CATKIN_DEPENDS mesh_segmenter tool_path_planner path_sequence_planner vtk_viewer - message_runtime sensor_msgs std_srvs pcl_msgs @@ -66,11 +55,11 @@ include_directories(include ${catkin_INCLUDE_DIRS} ${Boost_INCLUDE_DIRS} ) -add_library(noether_simulator_ +add_library(${PROJECT_NAME} src/noether_simulator.cpp ) -target_link_libraries(noether_simulator_ +target_link_libraries(${PROJECT_NAME} ${catkin_LIBRARIES} ${VTK_LIBRARIES} ${PCL_LIBRARIES} @@ -82,10 +71,7 @@ add_dependencies(thick_sim ${${PROJECT_NAME}_EXPORTED_TARGETS} ${actionlib_tutorials_EXPORTED_TARGETS} ) target_link_libraries(thick_sim - noether_simulator_ - ${catkin_LIBRARIES} - ${VTK_LIBRARIES} - ${PCL_LIBRARIES} + ${PROJECT_NAME} ) #Test @@ -95,7 +81,7 @@ if (CATKIN_ENABLE_TESTING) ) target_link_libraries(noether_simulator-test - noether_simulator_ + ${PROJECT_NAME} ${catkin_LIBRARIES} ${VTK_LIBRARIES} ) @@ -104,7 +90,7 @@ endif() ############# ## Install ## ############# -install(TARGETS noether_simulator_ thick_sim +install(TARGETS ${PROJECT_NAME} thick_sim ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} diff --git a/noether_simulator/package.xml b/noether_simulator/package.xml index 2814c1f4..8d80fcab 100644 --- a/noether_simulator/package.xml +++ b/noether_simulator/package.xml @@ -1,42 +1,24 @@ - + noether_simulator 0.0.0 The noether_simulator package trent - Apache + Apache 2 catkin - message_generation roscpp - mesh_segmenter - tool_path_planner - path_sequence_planner - vtk_viewer - mesh_segmenter - vtk_viewer - sensor_msgs - geometry_msgs - pcl_msgs - std_srvs - pcl_conversions - dynamic_reconfigure - message_runtime - message_generation - roscpp - mesh_segmenter - tool_path_planner - path_sequence_planner - vtk_viewer - mesh_segmenter - vtk_viewer - sensor_msgs - geometry_msgs - pcl_msgs - std_srvs - pcl_conversions - dynamic_reconfigure + mesh_segmenter + tool_path_planner + path_sequence_planner + vtk_viewer + sensor_msgs + geometry_msgs + pcl_msgs + std_srvs + pcl_conversions + dynamic_reconfigure diff --git a/noether_simulator/src/noether_simulator.cpp b/noether_simulator/src/noether_simulator.cpp index 479f9c62..719a9cd3 100644 --- a/noether_simulator/src/noether_simulator.cpp +++ b/noether_simulator/src/noether_simulator.cpp @@ -22,7 +22,6 @@ * See the License for the specific language governing permissions and * limitations under the License. */ -#include #include #include @@ -86,7 +85,6 @@ vtkSmartPointer NoetherSimulator::getSimulatedPoints() void NoetherSimulator::runSimulation() { - ROS_INFO("starting simulation\n"); std::vector color(3); color[0] = 0.9; color[1] = 0.9; color[2] = 0.9; @@ -108,8 +106,8 @@ vtkSmartPointer NoetherSimulator::getSimulatedPoints() // create tool object vtkSmartPointer cylinder = vtkSmartPointer::New(); cylinder->SetCenter(0.0, 0.0, 0.0); - cylinder->SetRadius(tool_.tool_radius ); - cylinder->SetHeight(tool_.tool_height); + cylinder->SetRadius(tool_.simulator_tool_radius ); + cylinder->SetHeight(tool_.simulator_tool_height); cylinder->SetResolution(20); cylinder->Update(); @@ -342,7 +340,6 @@ vtkSmartPointer NoetherSimulator::getSimulatedPoints() double range[2]; scalars->GetRange(range); - ROS_INFO("scalar range %f %f \n",range[0],range[1]); double upper_bound = mean + std_dev * scalar_sigma_; double lower_bound = mean - std_dev * scalar_sigma_; diff --git a/noether_simulator/src/thickness_simulator_node.cpp b/noether_simulator/src/thickness_simulator_node.cpp index cc8cb807..c79a878c 100644 --- a/noether_simulator/src/thickness_simulator_node.cpp +++ b/noether_simulator/src/thickness_simulator_node.cpp @@ -22,7 +22,7 @@ * See the License for the specific language governing permissions and * limitations under the License. */ -#include "ros/ros.h" + #include #include #include @@ -39,7 +39,7 @@ #include "noether_simulator/noether_simulator.h" #include "noether_simulator/NoetherSimulatorConfig.h" -#include "noether_msgs/ThickSimulatorAction.h" +#include "noether_msgs/SimulateThicknessAction.h" #include #include @@ -49,7 +49,7 @@ class ProcessSimulatorNode{ private: ros::NodeHandle nh_; - actionlib::SimpleActionServer simulation_service_; + actionlib::SimpleActionServer simulation_service_; double tool_height_; double process_rate_; @@ -62,8 +62,8 @@ class ProcessSimulatorNode{ double vect_[3], center_[3]; bool debug_on_; std::string log_directory_; - noether_msgs::ThickSimulatorFeedback feedback_; - noether_msgs::ThickSimulatorResult result_; + noether_msgs::SimulateThicknessFeedback feedback_; + noether_msgs::SimulateThicknessResult result_; tool_path_planner::ProcessPath convertPoseArraytoVTK(geometry_msgs::PoseArray array) { @@ -139,7 +139,7 @@ class ProcessSimulatorNode{ { simulation_service_.start(); } - void executeCB(const noether_msgs::ThickSimulatorGoalConstPtr &goal) + void executeCB(const noether_msgs::SimulateThicknessGoalConstPtr &goal) { ros::Rate r(0.05); bool success = true; @@ -155,13 +155,13 @@ class ProcessSimulatorNode{ nh_.param("/nnoether_simulator/line_spacing",tool.line_spacing,0.75); nh_.param("/noether_simulator/tool_offset",tool.tool_offset, 0.0); nh_.param("/noether_simulator/intersecting_plane_hiehgt",tool.intersecting_plane_height,0.15); - nh_.param("/noether_simulator/nearest_neighbors",tool.nearest_neighbors,30); + nh_.param("/noether_simulator/nearest_neighbors",tool.simulator_nearest_neighbors,30); nh_.param("/noether_simulator/min_hole_size",tool.min_hole_size,0.1); nh_.param("/noether_simulator/min_segment_size",tool.min_segment_size,1.0); nh_.param("/noether_simulator/raster_angle",tool.raster_angle,0.0); nh_.param("/noether_simulator/raster_wrt_global_axes",tool.raster_wrt_global_axes ,false); - nh_.param("/noether_simulator/tool_radius",tool.tool_radius,1.0); - nh_.param("/noeterh_simulator/tool_height",tool.tool_height,2.0); + nh_.param("/noether_simulator/tool_radius",tool.simulator_tool_radius,1.0); + nh_.param("/noeterh_simulator/tool_height",tool.simulator_tool_height,2.0); sim.setTool(tool); for(int i=0; i Date: Thu, 1 Aug 2019 14:12:46 -0500 Subject: [PATCH 05/12] finishing up stylistic changes. --- noether_simulator/CMakeLists.txt | 27 ++++++++++----------------- noether_simulator/package.xml | 6 +----- 2 files changed, 11 insertions(+), 22 deletions(-) diff --git a/noether_simulator/CMakeLists.txt b/noether_simulator/CMakeLists.txt index 80400e6e..85a5be9b 100644 --- a/noether_simulator/CMakeLists.txt +++ b/noether_simulator/CMakeLists.txt @@ -17,15 +17,9 @@ find_package(catkin REQUIRED cmake_modules tool_path_planner path_sequence_planner vtk_viewer - sensor_msgs - geometry_msgs roscpp - pcl_msgs - std_srvs - pcl_conversions dynamic_reconfigure actionlib - actionlib_msgs ) generate_dynamic_reconfigure_options( @@ -40,11 +34,7 @@ catkin_package( tool_path_planner path_sequence_planner vtk_viewer - sensor_msgs - std_srvs - pcl_msgs - geometry_msgs - pcl_conversions + dynamic_reconfigure DEPENDS VTK @@ -76,15 +66,18 @@ target_link_libraries(thick_sim #Test if (CATKIN_ENABLE_TESTING) - catkin_add_gtest(${PROJECT_NAME}-test + find_package(catkin REQUIRED COMPONENTS vtk_viewer) + include_directories( + include + ${catkin_INCLUDE_DIRS} + ) + catkin_add_gtest(${PROJECT_NAME}-test test/utest.cpp -) - -target_link_libraries(noether_simulator-test + ) + target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME} ${catkin_LIBRARIES} - ${VTK_LIBRARIES} -) + ) endif() ############# diff --git a/noether_simulator/package.xml b/noether_simulator/package.xml index 8d80fcab..be75a0f8 100644 --- a/noether_simulator/package.xml +++ b/noether_simulator/package.xml @@ -3,7 +3,7 @@ noether_simulator 0.0.0 The noether_simulator package - trent + jorge Apache 2 catkin @@ -14,10 +14,6 @@ tool_path_planner path_sequence_planner vtk_viewer - sensor_msgs - geometry_msgs - pcl_msgs - std_srvs pcl_conversions dynamic_reconfigure From 83300927baae99bbf31dbf5d6428dc280b84e883 Mon Sep 17 00:00:00 2001 From: twall Date: Fri, 2 Aug 2019 13:29:37 -0500 Subject: [PATCH 06/12] more stylistic changes --- noether_examples/data/square.pcd | 111 ++++++++++++ .../src/thickness_simulator_client.cpp | 171 +++++++++--------- noether_msgs/action/SimulateThickness.action | 2 +- .../noether_simulator/noether_simulator.h | 14 ++ noether_simulator/src/noether_simulator.cpp | 10 +- .../src/thickness_simulator_node.cpp | 31 ++-- 6 files changed, 231 insertions(+), 108 deletions(-) create mode 100644 noether_examples/data/square.pcd diff --git a/noether_examples/data/square.pcd b/noether_examples/data/square.pcd new file mode 100644 index 00000000..7de10ea2 --- /dev/null +++ b/noether_examples/data/square.pcd @@ -0,0 +1,111 @@ +# .PCD v.7 - Point Cloud Data file format +VERSION .7 +FIELDS x y z +SIZE 4 4 4 +TYPE F F F +COUNT 1 1 1 +WIDTH 10 +HEIGHT 10 +VIEWPOINT 0 0 0 1 0 0 0 +POINTS 100 +DATA ascii +0 0 0 +0 0.1 0 +0 0.2 0 +0 0.3 0 +0 0.4 0 +0 0.5 0 +0 0.6 0 +0 0.7 0 +0 0.8 0 +0 0.9 0 +0.1 0 0 +0.1 0.1 0 +0.1 0.2 0 +0.1 0.3 0 +0.1 0.4 0 +0.1 0.5 0 +0.1 0.6 0 +0.1 0.7 0 +0.1 0.8 0 +0.1 0.9 0 +0.2 0 0 +0.2 0.1 0 +0.2 0.2 0 +0.2 0.3 0 +0.2 0.4 0 +0.2 0.5 0 +0.2 0.6 0 +0.2 0.7 0 +0.2 0.8 0 +0.2 0.9 0 +0.3 0 0 +0.3 0.1 0 +0.3 0.2 0 +0.3 0.3 0 +0.3 0.4 0 +0.3 0.5 0 +0.3 0.6 0 +0.3 0.7 0 +0.3 0.8 0 +0.3 0.9 0 +0.4 0 0 +0.4 0.1 0 +0.4 0.2 0 +0.4 0.3 0 +0.4 0.4 0 +0.4 0.5 0 +0.4 0.6 0 +0.4 0.7 0 +0.4 0.8 0 +0.5 0.9 0 +0.5 0 0 +0.5 0.1 0 +0.5 0.2 0 +0.5 0.3 0 +0.5 0.4 0 +0.5 0.5 0 +0.5 0.6 0 +0.5 0.7 0 +0.5 0.8 0 +0.5 0.9 0 +0.6 0 0 +0.6 0.1 0 +0.6 0.2 0 +0.6 0.3 0 +0.6 0.4 0 +0.6 0.5 0 +0.6 0.6 0 +0.6 0.7 0 +0.6 0.8 0 +0.6 0.9 0 +0.7 0 0 +0.7 0.1 0 +0.7 0.2 0 +0.7 0.3 0 +0.7 0.4 0 +0.7 0.5 0 +0.7 0.6 0 +0.7 0.7 0 +0.7 0.8 0 +0.7 0.9 0 +0.8 0 0 +0.8 0.1 0 +0.8 0.2 0 +0.8 0.3 0 +0.8 0.4 0 +0.8 0.5 0 +0.8 0.6 0 +0.8 0.7 0 +0.8 0.8 0 +0.8 0.9 0 +0.9 0 0 +0.9 0.1 0 +0.9 0.2 0 +0.9 0.3 0 +0.9 0.4 0 +0.9 0.5 0 +0.9 0.6 0 +0.9 0.7 0 +0.9 0.8 0 +0.9 0.9 0 diff --git a/noether_examples/src/thickness_simulator_client.cpp b/noether_examples/src/thickness_simulator_client.cpp index b555389c..dd209da0 100644 --- a/noether_examples/src/thickness_simulator_client.cpp +++ b/noether_examples/src/thickness_simulator_client.cpp @@ -28,6 +28,7 @@ #include #include #include + #include #include #include @@ -41,23 +42,28 @@ #include #include +#include +#include + /*This example shows how the thickness_simulator_node.cpp works. * First, it creates 3 meshes and three paths. * Then, it passes these meshes and paths to the thickness_simulator_node. * The thickness_simulator_node runs the first path across each mesh. - * If the mesh is sufficently painted the bool corasponding to that mesh in the painted[] + * If the mesh is sufficently covered the bool corasponding to that mesh in the coverage[] * is set to true, the mesh is excluded from future iterations, and the path is added to the reuqiredPaths[] unless, * it has already been added. - * once all the meshes have been evaluated using the first path, the simulator moves on to the second path. + * Once all the meshes have been evaluated using the first path, the simulator moves on to the second path. * The simulator evaluates the remaining meshes with the second path and so on until all meshes have the coraspoinding - * bool value in painted[] set to true, or all paths have been tried. + * bool value in coverage[] set to true, or all paths have been tried. * - * To use roslauch to launch the thick_sim.launch file. Then, in a seperate termial window use rosrun to run the - * noether_simulator_node.cpp + *usage: + * roslaunch noether_examples thick_sim.launch * + * //in a seperate terminal: + * rosrun noether_simuator noether_simulator_client */ -//make modified meshes +//@brief This a helper function to create test meshes vtkSmartPointer createPlaneMod(unsigned int grid_size_x, unsigned int grid_size_y, vtk_viewer::plane_type type) { // Create points on an XY grid with a sinusoidal Z component @@ -97,7 +103,7 @@ vtkSmartPointer createPlaneMod(unsigned int grid_size_x, unsigned int } int main (int argc, char **argv) -{ +{ ros::init(argc, argv, "test_noether_simulator"); // create the action client @@ -112,88 +118,87 @@ int main (int argc, char **argv) // send a goal to the action noether_msgs::SimulateThicknessGoal goal; - //......setup test meshes and path - pcl_msgs::PolygonMesh myMesh; std::vector myMeshs; std::vector myPath; - vtkSmartPointer points2 = vtkSmartPointer::New(); - double pt1[3] = {3.0, 3.0, 0.0}; - double pt2[3] = {4.0, 2.0, 0.0}; - double pt3[3] = {5.0, 3.0, 0.0}; - double pt4[3] = {4.0, 4.0, 0.0}; - - points2->InsertNextPoint(pt1); - points2->InsertNextPoint(pt2); - points2->InsertNextPoint(pt3); - points2->InsertNextPoint(pt4); - //......end setup test meshes and path - - //.......create control meshes - for(int count = 0; count<3; count++)//start multimesh creation loop - { - vtkSmartPointer points; - if(count==0) - { - points = vtk_viewer::createPlane(10,10,vtk_viewer::SINUSOIDAL_2D); - } - if(count==1) - { - points = vtk_viewer::createPlane(9,10,vtk_viewer::SINUSOIDAL_2D); - } - if(count==2) + //......setup test meshes and path + pcl_msgs::PolygonMesh myMesh; + vtkSmartPointer points2 = vtkSmartPointer::New(); + double pt1[3] = {3.0, 3.0, 0.0}; + double pt2[3] = {4.0, 2.0, 0.0}; + double pt3[3] = {5.0, 3.0, 0.0}; + double pt4[3] = {4.0, 4.0, 0.0}; + + points2->InsertNextPoint(pt1); + points2->InsertNextPoint(pt2); + points2->InsertNextPoint(pt3); + points2->InsertNextPoint(pt4); + //......end setup test meshes and path + + //.......create control meshes + for(int count = 0; count<3; count++)//start multimesh creation loop { - points = createPlaneMod(8,10,vtk_viewer::SINUSOIDAL_2D); - } + vtkSmartPointer points; + if(count==0) + { + points = vtk_viewer::createPlane(10,10,vtk_viewer::SINUSOIDAL_2D); + } + if(count==1) + { + points = vtk_viewer::createPlane(9,10,vtk_viewer::SINUSOIDAL_2D); + } + if(count==2) + { + points = createPlaneMod(8,10,vtk_viewer::SINUSOIDAL_2D); + } - vtkSmartPointer data = vtkSmartPointer::New(); - data = vtk_viewer::createMesh(points, 0.5, 5); + vtkSmartPointer data = vtkSmartPointer::New(); + data = vtk_viewer::createMesh(points, 0.5, 5); - vtk_viewer::generateNormals(data); + vtk_viewer::generateNormals(data); - vtkSmartPointer cut = vtkSmartPointer::New(); - cut = vtk_viewer::cutMesh(data, points2, false); - pcl::PolygonMesh *test = new(pcl::PolygonMesh); - pcl::VTKUtils::convertToPCL(cut, *test); - pcl_conversions::fromPCL(*test, myMesh); - if(count>0) - { - myMeshs.push_back(myMesh); - } - //........end create control meshes - //........create robot path - - cut = vtk_viewer::cutMesh(data, points2, false); - pcl::VTKUtils::convertToPCL(cut, *test); - - // Run tool path planner on mesh - tool_path_planner::RasterToolPathPlanner planner; - planner.setInputMesh(cut); - - tool_path_planner::ProcessTool tool; - tool.pt_spacing = 0.5; - tool.line_spacing = .75; - tool.tool_offset = 0.0; - tool.intersecting_plane_height = 0.15; - tool.simulator_nearest_neighbors = 30; - tool.min_hole_size = 0.1; - tool.min_segment_size = 1; - tool.raster_angle = 0; - tool.raster_wrt_global_axes = 0; - tool.simulator_tool_radius = 1; - tool.simulator_tool_height = 2; - planner.setTool(tool); - planner.setDebugMode(false); - planner.computePaths(); - std::vector paths = planner.getPaths(); - myPath = tool_path_planner::toPosesMsgs(paths); - - noether_msgs::ToolRasterPath rasterPath; - rasterPath.paths = myPath; - goal.path.push_back(rasterPath); - - //........end robot path - }//end multimesh creation loop + vtkSmartPointer cut = vtkSmartPointer::New(); + cut = vtk_viewer::cutMesh(data, points2, false); + pcl::PolygonMesh *test = new(pcl::PolygonMesh); + pcl::VTKUtils::convertToPCL(cut, *test); + pcl_conversions::fromPCL(*test, myMesh); + if(count>0) + { + myMeshs.push_back(myMesh); + } + //........end create control meshes + //........create robot path + cut = vtk_viewer::cutMesh(data, points2, false); + pcl::VTKUtils::convertToPCL(cut, *test); + + // Run tool path planner on mesh + tool_path_planner::RasterToolPathPlanner planner; + planner.setInputMesh(cut); + + tool_path_planner::ProcessTool tool; + tool.pt_spacing = 0.5; + tool.line_spacing = .75; + tool.tool_offset = 0.0; + tool.intersecting_plane_height = 0.15; + tool.simulator_nearest_neighbors = 30; + tool.min_hole_size = 0.1; + tool.min_segment_size = 1; + tool.raster_angle = 0; + tool.raster_wrt_global_axes = 0; + tool.simulator_tool_radius = 1; + tool.simulator_tool_height = 2; + planner.setTool(tool); + planner.setDebugMode(false); + planner.computePaths(); + std::vector paths = planner.getPaths(); + myPath = tool_path_planner::toPosesMsgs(paths); + + noether_msgs::ToolRasterPath rasterPath; + rasterPath.paths = myPath; + goal.path.push_back(rasterPath); + + //........end robot path + }//end multimesh creation loop //set goal values goal.input_mesh = myMeshs; @@ -213,7 +218,7 @@ int main (int argc, char **argv) for(int i=0; ipainted[i]); + ROS_INFO("part %d, is %d",i+1,ac.getResult()->coverage[i]); } ROS_INFO("number of paths required is: %d",ac.getResult()->requiredPath.size()); //exit diff --git a/noether_msgs/action/SimulateThickness.action b/noether_msgs/action/SimulateThickness.action index 003b0cba..ca9d56e1 100644 --- a/noether_msgs/action/SimulateThickness.action +++ b/noether_msgs/action/SimulateThickness.action @@ -3,7 +3,7 @@ pcl_msgs/PolygonMesh[] input_mesh noether_msgs/ToolRasterPath[] path --- #result definition - are messhes painted enough -bool[] painted +bool[] coverage noether_msgs/ToolRasterPath[] requiredPath --- #feedback - Some sort of percentage diff --git a/noether_simulator/include/noether_simulator/noether_simulator.h b/noether_simulator/include/noether_simulator/noether_simulator.h index b566704b..3831161f 100644 --- a/noether_simulator/include/noether_simulator/noether_simulator.h +++ b/noether_simulator/include/noether_simulator/noether_simulator.h @@ -74,12 +74,26 @@ class NoetherSimulator */ void setTool(tool_path_planner::ProcessTool tool){tool_ = tool;} + /** + * @brief runSimulation Simulates how to the current path will process the current mesh with the current tool. + */ void runSimulation(); + /** + * @brief setDisplaySimga Sets the sigma value for displaying the mesh after being processed + * @param sigma A value used to modify how the processed mesh is displayed + */ void setDisplaySigma(double sigma){scalar_sigma_ = sigma;} + /** + * @brief setBaseProcessRate Sets the process rate for the simulator + * @param rate The rate that detirmines how many points are processed per line in the mesh + */ void setBaseProcessRate(double rate){process_base_rate_ = rate;} + /** + * @brief displayResults Displays the processed meshes + */ void displayResults(); private: diff --git a/noether_simulator/src/noether_simulator.cpp b/noether_simulator/src/noether_simulator.cpp index 719a9cd3..97638c4e 100644 --- a/noether_simulator/src/noether_simulator.cpp +++ b/noether_simulator/src/noether_simulator.cpp @@ -50,15 +50,17 @@ namespace noether_simulator simulation_points_ = vtkSmartPointer::New(); } + //Integrate in x^2 and z^2 double NoetherSimulator::integral(double pt[3]) { double result; result = -( pow(pt[0],3.0)) /3.0 - (pow(pt[2],3.0))/3.0 ; - return 10*result; + return 10*result;//10 to compansate for sampling the mesh } + //Integration between 2 points inside cylinder, or inside point and cylinder edge double NoetherSimulator::calculateIntegration(vtkSmartPointer points) { if(points->GetNumberOfPoints() < 2) @@ -233,7 +235,6 @@ vtkSmartPointer NoetherSimulator::getSimulatedPoints() vtkSmartPointer test_pts = vtkSmartPointer::New(); vtkSmartPointer integration_pts = vtkSmartPointer::New(); - //test_pts->SetNumberOfPoints(2); for(int i = 0; i < num_pts; ++i) { integration_pts->Reset(); @@ -287,7 +288,7 @@ vtkSmartPointer NoetherSimulator::getSimulatedPoints() // get scalar value, color data is stored in scalars double *tmp_value = scalars->GetTuple(index); double value = *tmp_value + integral_sum; - scalars->SetTuple1(index, value); + scalars->SetTuple1(index, value);//update intensity values }// end loop through all tool points found }// end loop through all process points in this path @@ -359,9 +360,6 @@ vtkSmartPointer NoetherSimulator::getSimulatedPoints() vtkSmartPointer NoetherSimulator::createMatrix(double pt[3], double norm[3], double derv[3]) { - // Get the point normal and derivative for creating the 3x3 transform - //double* norm = paths[j].line->GetPointData()->GetNormals()->GetTuple(k); - //double* der = paths[j].derivatives->GetPointData()->GetNormals()->GetTuple(k); // perform cross product to get the third axis direction Eigen::Vector3d u(norm[0], norm[1], norm[2]); diff --git a/noether_simulator/src/thickness_simulator_node.cpp b/noether_simulator/src/thickness_simulator_node.cpp index c79a878c..3f1d56db 100644 --- a/noether_simulator/src/thickness_simulator_node.cpp +++ b/noether_simulator/src/thickness_simulator_node.cpp @@ -120,11 +120,6 @@ class ProcessSimulatorNode{ derivatives_->GetPointData()->SetNormals(deriv_normals); path.derivatives = derivatives_; - vtkSmartPointer inter_ = vtkSmartPointer::New(); - vtkSmartPointer spline_ = vtkSmartPointer::New(); - path.intersection_plane = inter_; - path.spline = spline_; - return path; } @@ -152,7 +147,7 @@ class ProcessSimulatorNode{ //add tool tool_path_planner::ProcessTool tool; nh_.param("/noether_simulator/pt_spacing",tool.pt_spacing, 0.5); - nh_.param("/nnoether_simulator/line_spacing",tool.line_spacing,0.75); + nh_.param("/noether_simulator/line_spacing",tool.line_spacing,0.75); nh_.param("/noether_simulator/tool_offset",tool.tool_offset, 0.0); nh_.param("/noether_simulator/intersecting_plane_hiehgt",tool.intersecting_plane_height,0.15); nh_.param("/noether_simulator/nearest_neighbors",tool.simulator_nearest_neighbors,30); @@ -161,12 +156,12 @@ class ProcessSimulatorNode{ nh_.param("/noether_simulator/raster_angle",tool.raster_angle,0.0); nh_.param("/noether_simulator/raster_wrt_global_axes",tool.raster_wrt_global_axes ,false); nh_.param("/noether_simulator/tool_radius",tool.simulator_tool_radius,1.0); - nh_.param("/noeterh_simulator/tool_height",tool.simulator_tool_height,2.0); + nh_.param("/noether_simulator/tool_height",tool.simulator_tool_height,2.0); sim.setTool(tool); for(int i=0; ipath.size();curPathNum++) @@ -192,7 +187,7 @@ class ProcessSimulatorNode{ success = false; break; } - if(result_.painted[i]==false)//if not yet painted + if(result_.coverage[i]==false)//if not yet covered { //convert mesh for simulator @@ -202,9 +197,9 @@ class ProcessSimulatorNode{ pcl::VTKUtils::convertToVTK(surface_mesh, surface_mesh_vtk); sim.setInputMesh(surface_mesh_vtk);//add mesh to simulator - sim.runSimulation();//display painted parts + sim.runSimulation();//display covered parts - //deterimine if painted enough + //deterimine if covered enough vtkSmartPointer processedPoints = vtkSmartPointer::New(); processedPoints = sim.getSimulatedPoints();//get a copy of simulated points to operate on vtkIdType length = processedPoints->GetNumberOfPoints(); @@ -212,7 +207,7 @@ class ProcessSimulatorNode{ double intensity[3] = {0,0,0};//setup flann int missed = 0; double minPaintThreshold = 5; - double maxPassableNonpainted = 0.1; + double maxPassableNoncoverage = 0.1; double p [3]; vtkSmartPointer pointTree = vtkSmartPointer::New(); @@ -221,7 +216,7 @@ class ProcessSimulatorNode{ unsigned int k = 30; double currPoint [3]; - for(vtkIdType a = 0; a < length; a++)//iterate through points to check if painted + for(vtkIdType a = 0; a < length; a++)//iterate through points to check if covered { intensity[0] =0;//reseting intensity for next point in mesh intensity[1] =0; @@ -245,15 +240,15 @@ class ProcessSimulatorNode{ { missed++; } - }//end iterate through points to check if painted + }//end iterate through points to check if covered - if(missed/float(processedPoints->GetNumberOfPoints())>maxPassableNonpainted)//get ratio of missed spots, if below threshold set not painted + if(missed/float(processedPoints->GetNumberOfPoints())>maxPassableNoncoverage)//get ratio of missed spots, if below threshold set not covered { - result_.painted[i]=false; + result_.coverage[i]=false; } else { - result_.painted[i]=true; + result_.coverage[i]=true; if(added ==false) { result_.requiredPath.push_back(goal->path[curPathNum]); @@ -263,7 +258,7 @@ class ProcessSimulatorNode{ feedback_.percent =float(i)/float(num_meshes); simulation_service_.publishFeedback(feedback_); - }//if not yet painted + }//if not yet covered }//end each mesh }//end multiple paths From bebc44e237ea3922d96e84ec30c4907c10891216 Mon Sep 17 00:00:00 2001 From: twall Date: Fri, 2 Aug 2019 15:02:14 -0500 Subject: [PATCH 07/12] small fixes --- noether_examples/data/square.pcd | 111 ------------------ .../src/thickness_simulator_client.cpp | 12 +- noether_msgs/CMakeLists.txt | 2 +- ...ickness.action => SimulateCoverage.action} | 2 +- .../src/thickness_simulator_node.cpp | 12 +- 5 files changed, 14 insertions(+), 125 deletions(-) delete mode 100644 noether_examples/data/square.pcd rename noether_msgs/action/{SimulateThickness.action => SimulateCoverage.action} (81%) diff --git a/noether_examples/data/square.pcd b/noether_examples/data/square.pcd deleted file mode 100644 index 7de10ea2..00000000 --- a/noether_examples/data/square.pcd +++ /dev/null @@ -1,111 +0,0 @@ -# .PCD v.7 - Point Cloud Data file format -VERSION .7 -FIELDS x y z -SIZE 4 4 4 -TYPE F F F -COUNT 1 1 1 -WIDTH 10 -HEIGHT 10 -VIEWPOINT 0 0 0 1 0 0 0 -POINTS 100 -DATA ascii -0 0 0 -0 0.1 0 -0 0.2 0 -0 0.3 0 -0 0.4 0 -0 0.5 0 -0 0.6 0 -0 0.7 0 -0 0.8 0 -0 0.9 0 -0.1 0 0 -0.1 0.1 0 -0.1 0.2 0 -0.1 0.3 0 -0.1 0.4 0 -0.1 0.5 0 -0.1 0.6 0 -0.1 0.7 0 -0.1 0.8 0 -0.1 0.9 0 -0.2 0 0 -0.2 0.1 0 -0.2 0.2 0 -0.2 0.3 0 -0.2 0.4 0 -0.2 0.5 0 -0.2 0.6 0 -0.2 0.7 0 -0.2 0.8 0 -0.2 0.9 0 -0.3 0 0 -0.3 0.1 0 -0.3 0.2 0 -0.3 0.3 0 -0.3 0.4 0 -0.3 0.5 0 -0.3 0.6 0 -0.3 0.7 0 -0.3 0.8 0 -0.3 0.9 0 -0.4 0 0 -0.4 0.1 0 -0.4 0.2 0 -0.4 0.3 0 -0.4 0.4 0 -0.4 0.5 0 -0.4 0.6 0 -0.4 0.7 0 -0.4 0.8 0 -0.5 0.9 0 -0.5 0 0 -0.5 0.1 0 -0.5 0.2 0 -0.5 0.3 0 -0.5 0.4 0 -0.5 0.5 0 -0.5 0.6 0 -0.5 0.7 0 -0.5 0.8 0 -0.5 0.9 0 -0.6 0 0 -0.6 0.1 0 -0.6 0.2 0 -0.6 0.3 0 -0.6 0.4 0 -0.6 0.5 0 -0.6 0.6 0 -0.6 0.7 0 -0.6 0.8 0 -0.6 0.9 0 -0.7 0 0 -0.7 0.1 0 -0.7 0.2 0 -0.7 0.3 0 -0.7 0.4 0 -0.7 0.5 0 -0.7 0.6 0 -0.7 0.7 0 -0.7 0.8 0 -0.7 0.9 0 -0.8 0 0 -0.8 0.1 0 -0.8 0.2 0 -0.8 0.3 0 -0.8 0.4 0 -0.8 0.5 0 -0.8 0.6 0 -0.8 0.7 0 -0.8 0.8 0 -0.8 0.9 0 -0.9 0 0 -0.9 0.1 0 -0.9 0.2 0 -0.9 0.3 0 -0.9 0.4 0 -0.9 0.5 0 -0.9 0.6 0 -0.9 0.7 0 -0.9 0.8 0 -0.9 0.9 0 diff --git a/noether_examples/src/thickness_simulator_client.cpp b/noether_examples/src/thickness_simulator_client.cpp index dd209da0..09cfef00 100644 --- a/noether_examples/src/thickness_simulator_client.cpp +++ b/noether_examples/src/thickness_simulator_client.cpp @@ -39,7 +39,7 @@ #include #include #include -#include +#include #include #include @@ -108,7 +108,7 @@ int main (int argc, char **argv) // create the action client // true causes the client to spin its own thread - actionlib::SimpleActionClient ac("noether_simulator", true); + actionlib::SimpleActionClient ac("noether_simulator", true); ROS_INFO("Waiting for action server to start."); // wait for the action server to start @@ -116,7 +116,7 @@ int main (int argc, char **argv) ROS_INFO("Action server started, sending goal."); // send a goal to the action - noether_msgs::SimulateThicknessGoal goal; + noether_msgs::SimulateCoverageGoal goal; std::vector myMeshs; std::vector myPath; @@ -177,7 +177,7 @@ int main (int argc, char **argv) tool_path_planner::ProcessTool tool; tool.pt_spacing = 0.5; - tool.line_spacing = .75; + tool.line_spacing = 0.75; tool.tool_offset = 0.0; tool.intersecting_plane_height = 0.15; tool.simulator_nearest_neighbors = 30; @@ -185,8 +185,8 @@ int main (int argc, char **argv) tool.min_segment_size = 1; tool.raster_angle = 0; tool.raster_wrt_global_axes = 0; - tool.simulator_tool_radius = 1; - tool.simulator_tool_height = 2; + tool.simulator_tool_radius = 10.0; + tool.simulator_tool_height = 1; planner.setTool(tool); planner.setDebugMode(false); planner.computePaths(); diff --git a/noether_msgs/CMakeLists.txt b/noether_msgs/CMakeLists.txt index 50f10876..d7431b39 100644 --- a/noether_msgs/CMakeLists.txt +++ b/noether_msgs/CMakeLists.txt @@ -29,7 +29,7 @@ add_action_files( FILES GenerateToolPaths.action Segment.action - SimulateThickness.action + SimulateCoverage.action ) generate_messages( diff --git a/noether_msgs/action/SimulateThickness.action b/noether_msgs/action/SimulateCoverage.action similarity index 81% rename from noether_msgs/action/SimulateThickness.action rename to noether_msgs/action/SimulateCoverage.action index ca9d56e1..f82be66f 100644 --- a/noether_msgs/action/SimulateThickness.action +++ b/noether_msgs/action/SimulateCoverage.action @@ -2,7 +2,7 @@ pcl_msgs/PolygonMesh[] input_mesh noether_msgs/ToolRasterPath[] path --- -#result definition - are messhes painted enough +#result definition - are messhes covered enough bool[] coverage noether_msgs/ToolRasterPath[] requiredPath --- diff --git a/noether_simulator/src/thickness_simulator_node.cpp b/noether_simulator/src/thickness_simulator_node.cpp index 3f1d56db..e708e7b8 100644 --- a/noether_simulator/src/thickness_simulator_node.cpp +++ b/noether_simulator/src/thickness_simulator_node.cpp @@ -39,7 +39,7 @@ #include "noether_simulator/noether_simulator.h" #include "noether_simulator/NoetherSimulatorConfig.h" -#include "noether_msgs/SimulateThicknessAction.h" +#include "noether_msgs/SimulateCoverageAction.h" #include #include @@ -49,7 +49,7 @@ class ProcessSimulatorNode{ private: ros::NodeHandle nh_; - actionlib::SimpleActionServer simulation_service_; + actionlib::SimpleActionServer simulation_service_; double tool_height_; double process_rate_; @@ -62,8 +62,8 @@ class ProcessSimulatorNode{ double vect_[3], center_[3]; bool debug_on_; std::string log_directory_; - noether_msgs::SimulateThicknessFeedback feedback_; - noether_msgs::SimulateThicknessResult result_; + noether_msgs::SimulateCoverageFeedback feedback_; + noether_msgs::SimulateCoverageResult result_; tool_path_planner::ProcessPath convertPoseArraytoVTK(geometry_msgs::PoseArray array) { @@ -134,7 +134,7 @@ class ProcessSimulatorNode{ { simulation_service_.start(); } - void executeCB(const noether_msgs::SimulateThicknessGoalConstPtr &goal) + void executeCB(const noether_msgs::SimulateCoverageGoalConstPtr &goal) { ros::Rate r(0.05); bool success = true; @@ -147,7 +147,7 @@ class ProcessSimulatorNode{ //add tool tool_path_planner::ProcessTool tool; nh_.param("/noether_simulator/pt_spacing",tool.pt_spacing, 0.5); - nh_.param("/noether_simulator/line_spacing",tool.line_spacing,0.75); + nh_.param("/noether_simulator/line_spacing",tool.line_spacing,10.75); nh_.param("/noether_simulator/tool_offset",tool.tool_offset, 0.0); nh_.param("/noether_simulator/intersecting_plane_hiehgt",tool.intersecting_plane_height,0.15); nh_.param("/noether_simulator/nearest_neighbors",tool.simulator_nearest_neighbors,30); From dbdc80e97c0532c0f57ae8c8781152c3456bc660 Mon Sep 17 00:00:00 2001 From: twall Date: Mon, 5 Aug 2019 10:36:15 -0500 Subject: [PATCH 08/12] added comments to noether_simulator.cpp to make it more understandable.x --- noether_simulator/src/noether_simulator.cpp | 45 ++++++++++++--------- noether_simulator/test/utest.cpp | 2 - 2 files changed, 27 insertions(+), 20 deletions(-) diff --git a/noether_simulator/src/noether_simulator.cpp b/noether_simulator/src/noether_simulator.cpp index 97638c4e..229a5886 100644 --- a/noether_simulator/src/noether_simulator.cpp +++ b/noether_simulator/src/noether_simulator.cpp @@ -50,10 +50,11 @@ namespace noether_simulator simulation_points_ = vtkSmartPointer::New(); } - //Integrate in x^2 and z^2 + //This is a definite integral of the function (x^2 + z^2)/10 from one point pt1 to another point pt2. + //This function is expecting pt to be in the Tool frame of reference. + //The factor of one 10th stems from the subsampling of the surface at a 10x density. double NoetherSimulator::integral(double pt[3]) { - double result; result = -( pow(pt[0],3.0)) /3.0 - (pow(pt[2],3.0))/3.0 ; @@ -79,23 +80,26 @@ namespace noether_simulator return fabs(value); } +//Returns a copy of the private varible simulation_points vtkSmartPointer NoetherSimulator::getSimulatedPoints() { vtkSmartPointer simulated_points = simulation_points_; return simulated_points; } - void NoetherSimulator::runSimulation() +//simulate the process on the mesh and path +void NoetherSimulator::runSimulation() { std::vector color(3); color[0] = 0.9; color[1] = 0.9; color[2] = 0.9; // densly sample surface based upon point spacing double spacing = tool_.pt_spacing /10.0; - vtkSmartPointer simulation_points; + vtkSmartPointer simulation_points;//output stored as private member variable simulation_points = vtk_viewer::sampleMesh(input_mesh_, spacing); // add scalar data for all points + // where color information is stored vtkSmartPointer scalars = vtkSmartPointer::New(); scalars->SetNumberOfComponents(1); scalars->SetNumberOfTuples(simulation_points->GetNumberOfPoints()); @@ -106,6 +110,7 @@ vtkSmartPointer NoetherSimulator::getSimulatedPoints() } // create tool object + // the cylinder is defined in a different frame than the mesh or path vtkSmartPointer cylinder = vtkSmartPointer::New(); cylinder->SetCenter(0.0, 0.0, 0.0); cylinder->SetRadius(tool_.simulator_tool_radius ); @@ -113,13 +118,12 @@ vtkSmartPointer NoetherSimulator::getSimulatedPoints() cylinder->SetResolution(20); cylinder->Update(); - //vtkSmartPointer tree = vtkSmartPointer::New(); vtkSmartPointer tree = vtkSmartPointer::New(); tree->SetDataSet(cylinder->GetOutput()); tree->BuildLocator(); // use tool to integrate over time and distance - int number_paths =input_paths_.size(); + int number_paths = input_paths_.size(); for(int i = 0; i NoetherSimulator::getSimulatedPoints() this_path.line->GetPointData()->GetNormals()->GetTuple(j+1, norm2); this_path.derivatives->GetPointData()->GetNormals()->GetTuple(j+1, derv2); - // transform tool to pt1 and pt2 location - vtkSmartPointer transform1 = createMatrix(path_pt1, norm1, derv1); - vtkSmartPointer transform2 = createMatrix(path_pt2, norm2, derv2); + // transform tool (cylinder) to pt1 and pt2 location + vtkSmartPointer transform1 = createMatrix(path_pt1, norm1, derv1);//set up to rotate cylinder to pt1 frame + vtkSmartPointer transform2 = createMatrix(path_pt2, norm2, derv2);//set up to rotate cylinder to pt2 frame vtkSmartPointer trans = vtkSmartPointer::New(); - trans->SetMatrix(transform1); + trans->SetMatrix(transform1);//transform tool to pt1 frame // transform to point 1 and get data vtkSmartPointer transform_filter = vtkSmartPointer::New(); vtkSmartPointer cylinder_poly = vtkSmartPointer::New(); cylinder_poly->DeepCopy(cylinder->GetOutput()); - transform_filter->SetInputData(cylinder_poly); - transform_filter->SetTransform(trans); + transform_filter->SetInputData(cylinder_poly);//set data to be transformed (tool) + transform_filter->SetTransform(trans);//set transform (tramsform tool to pt1 frame) transform_filter->Update(); vtkSmartPointer point_set1 = vtkSmartPointer::New(); - point_set1->DeepCopy(transform_filter->GetOutput()); + point_set1->DeepCopy(transform_filter->GetOutput());//holds all the points in the cylinder transformed to pt1 frame // transform to point 2 and get data - trans->SetMatrix(transform2); + trans->SetMatrix(transform2);//transform tool to pt2 transform_filter->SetTransform(trans); transform_filter->Update(); vtkSmartPointer point_set2 = vtkSmartPointer::New(); - point_set2->DeepCopy(transform_filter->GetOutput()); + point_set2->DeepCopy(transform_filter->GetOutput());//holds all the points in the cylinder transformed to pt2 frame // create convex hull of two tool locations vtkSmartPointer delaunay_3D = vtkSmartPointer::New(); vtkSmartPointer hull_data = vtkSmartPointer::New(); vtkSmartPointer point_data = vtkSmartPointer::New(); - point_data->DeepCopy(point_set1->GetPoints()); - point_data->Resize(point_set1->GetPoints()->GetNumberOfPoints() + point_set2->GetPoints()->GetNumberOfPoints()); + point_data->DeepCopy(point_set1->GetPoints());//holds all the points in the cylinder transformed to pt1 frame + point_data->Resize(point_set1->GetPoints()->GetNumberOfPoints() + point_set2->GetPoints()->GetNumberOfPoints());//resize to hold both pt1 and pt2 data point_data->InsertPoints(point_set1->GetPoints()->GetNumberOfPoints(), point_set2->GetPoints()->GetNumberOfPoints(), 0, point_set2->GetPoints()); + //adds the data stored in point_set2 hull_data->SetPoints(point_data); @@ -203,9 +208,13 @@ vtkSmartPointer NoetherSimulator::getSimulatedPoints() } } vtkSmartPointer tool_points = vtkSmartPointer::New(); - simulation_points->GetPoints()->GetPoints(pts_inside, tool_points); + simulation_points->GetPoints()->GetPoints(pts_inside, tool_points);//pts_inside contains the points from the mesh inside the convex hull + //tool_points contains the convex hull of the transformed tool. // transform all points into tool_pt1 frame of referece + //transform both the convex hull and overlaying points from the mesh back to the tool frame of reference + + //transform all points into tool_pt1 frame of referece vtkSmartPointer temp_data = vtkSmartPointer::New(); temp_data->SetPoints(tool_points); vtkSmartPointer tool_pts1 = vtkSmartPointer::New(); diff --git a/noether_simulator/test/utest.cpp b/noether_simulator/test/utest.cpp index 3a71b49b..e160d9f2 100644 --- a/noether_simulator/test/utest.cpp +++ b/noether_simulator/test/utest.cpp @@ -139,8 +139,6 @@ TEST(ViewerTest, TestCase1) for(vtkIdType i = 0; i < length; i++)//iterate through points to check if painted { - - //processedPoints->GetPoint(i,p); intensity[0] = processedPoints->GetPointData()->GetScalars()->GetComponent(i,0); intensity[1] = processedPoints->GetPointData()->GetScalars()->GetComponent(i,1); intensity[2] = processedPoints->GetPointData()->GetScalars()->GetComponent(i,2); From 43c97020ce542a6e884b8fb66c6da0cd37ac36d7 Mon Sep 17 00:00:00 2001 From: twall Date: Wed, 7 Aug 2019 10:09:30 -0500 Subject: [PATCH 09/12] changed cylinder to cone and added display for paths --- noether_examples/CMakeLists.txt | 8 +- .../{thick_sim.launch => coverage_sim.launch} | 0 ...ient.cpp => coverage_simulator_client.cpp} | 58 +++++--- noether_simulator/CMakeLists.txt | 8 +- ...r_node.cpp => coverage_simulator_node.cpp} | 0 noether_simulator/src/noether_simulator.cpp | 133 +++++++----------- noether_simulator/test/utest.cpp | 26 ++-- 7 files changed, 114 insertions(+), 119 deletions(-) rename noether_examples/launch/{thick_sim.launch => coverage_sim.launch} (100%) rename noether_examples/src/{thickness_simulator_client.cpp => coverage_simulator_client.cpp} (84%) rename noether_simulator/src/{thickness_simulator_node.cpp => coverage_simulator_node.cpp} (100%) diff --git a/noether_examples/CMakeLists.txt b/noether_examples/CMakeLists.txt index fa9ba62f..ea8b19a5 100644 --- a/noether_examples/CMakeLists.txt +++ b/noether_examples/CMakeLists.txt @@ -64,12 +64,12 @@ target_link_libraries(mesh_segmenter_node ${VTK_LIBRARIES} ) -add_executable(thickness_simulator_client src/thickness_simulator_client.cpp) -add_dependencies(thickness_simulator_client ${${PROJECT_NAME}_EXPORTED_TARGETS} +add_executable(coverage_simulator_client src/coverage_simulator_client.cpp) +add_dependencies(coverage_simulator_client ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS} ${actionlib_tutorials_EXPORTED_TARGETS} ) -target_link_libraries(thickness_simulator_client +target_link_libraries(coverage_simulator_client ${catkin_LIBRARIES} ${VTK_LIBRARIES} ${PCL_LIBRARIES} @@ -79,7 +79,7 @@ target_link_libraries(thickness_simulator_client ############# ## Install ## ############# -install(TARGETS mesh_segmenter_client_node mesh_segmenter_node thickness_simulator_client +install(TARGETS mesh_segmenter_client_node mesh_segmenter_node coverage_simulator_client ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} diff --git a/noether_examples/launch/thick_sim.launch b/noether_examples/launch/coverage_sim.launch similarity index 100% rename from noether_examples/launch/thick_sim.launch rename to noether_examples/launch/coverage_sim.launch diff --git a/noether_examples/src/thickness_simulator_client.cpp b/noether_examples/src/coverage_simulator_client.cpp similarity index 84% rename from noether_examples/src/thickness_simulator_client.cpp rename to noether_examples/src/coverage_simulator_client.cpp index 09cfef00..60d5d80b 100644 --- a/noether_examples/src/thickness_simulator_client.cpp +++ b/noether_examples/src/coverage_simulator_client.cpp @@ -57,10 +57,10 @@ * bool value in coverage[] set to true, or all paths have been tried. * *usage: - * roslaunch noether_examples thick_sim.launch + * roslaunch noether_examples coverage_sim.launch * * //in a seperate terminal: - * rosrun noether_simuator noether_simulator_client + * rosrun noether_examples coverage_simulator_client */ //@brief This a helper function to create test meshes @@ -69,7 +69,7 @@ vtkSmartPointer createPlaneMod(unsigned int grid_size_x, unsigned int // Create points on an XY grid with a sinusoidal Z component vtkSmartPointer points = vtkSmartPointer::New(); - for (unsigned int x = grid_size_x; x < 10; x++) + for (unsigned int x = grid_size_x; x < 21; x++) { for (unsigned int y = 0; y < grid_size_y; y++) { @@ -79,7 +79,13 @@ vtkSmartPointer createPlaneMod(unsigned int grid_size_x, unsigned int points->InsertNextPoint(x, y, vtkMath::Random(0.0, 0.001)); break; case vtk_viewer::SINUSOIDAL_1D: - points->InsertNextPoint(x, y, sin(double(y) / 2.0) + vtkMath::Random(0.0, 0.001)); + if(x==grid_size_x) + { + points->InsertNextPoint(x, y, sin(double(y) / 2.0) + vtkMath::Random(0.0, 0.001)); + } + else + { + points->InsertNextPoint(x+0.25, y, sin(double(y) / 2.0) + vtkMath::Random(0.0, 0.001)); } break; case vtk_viewer::SINUSOIDAL_2D: if(x==grid_size_x) @@ -136,20 +142,16 @@ int main (int argc, char **argv) //......end setup test meshes and path //.......create control meshes - for(int count = 0; count<3; count++)//start multimesh creation loop + for(int count = 0; count<2; count++)//start multimesh creation loop { vtkSmartPointer points; if(count==0) { - points = vtk_viewer::createPlane(10,10,vtk_viewer::SINUSOIDAL_2D); + points = vtk_viewer::createPlane(19,10,vtk_viewer::SINUSOIDAL_1D); } if(count==1) { - points = vtk_viewer::createPlane(9,10,vtk_viewer::SINUSOIDAL_2D); - } - if(count==2) - { - points = createPlaneMod(8,10,vtk_viewer::SINUSOIDAL_2D); + points = createPlaneMod(19,10,vtk_viewer::SINUSOIDAL_1D); } vtkSmartPointer data = vtkSmartPointer::New(); @@ -162,10 +164,8 @@ int main (int argc, char **argv) pcl::PolygonMesh *test = new(pcl::PolygonMesh); pcl::VTKUtils::convertToPCL(cut, *test); pcl_conversions::fromPCL(*test, myMesh); - if(count>0) - { - myMeshs.push_back(myMesh); - } + + myMeshs.push_back(myMesh); //........end create control meshes //........create robot path cut = vtk_viewer::cutMesh(data, points2, false); @@ -191,8 +191,34 @@ int main (int argc, char **argv) planner.setDebugMode(false); planner.computePaths(); std::vector paths = planner.getPaths(); - myPath = tool_path_planner::toPosesMsgs(paths); + //display path + vtk_viewer::VTKViewer viz; + std::vector color(3); + double scale = 1.0; + + // Display mesh results + color[0] = 0.9; + color[1] = 0.9; + color[2] = 0.9; + viz.addPolyDataDisplay(cut, color); + + for(int i = 0; i < paths.size(); ++i) + { + color[0] = 0.2; + color[1] = 0.9; + color[2] = 0.2; + viz.addPolyNormalsDisplay(paths[i].line, color, scale); + + color[0] = 0.9; + color[1] = 0.9; + color[2] = 0.2; + viz.addPolyNormalsDisplay(paths[i].derivatives, color, scale); + } + viz.renderDisplay(); + //end display path + + myPath = tool_path_planner::toPosesMsgs(paths); noether_msgs::ToolRasterPath rasterPath; rasterPath.paths = myPath; goal.path.push_back(rasterPath); diff --git a/noether_simulator/CMakeLists.txt b/noether_simulator/CMakeLists.txt index 85a5be9b..985678ba 100644 --- a/noether_simulator/CMakeLists.txt +++ b/noether_simulator/CMakeLists.txt @@ -55,12 +55,12 @@ target_link_libraries(${PROJECT_NAME} ${PCL_LIBRARIES} ) -add_executable(thick_sim src/thickness_simulator_node.cpp) -add_dependencies(thick_sim ${${PROJECT_NAME}_EXPORTED_TARGETS} +add_executable(coverage_sim src/coverage_simulator_node.cpp) +add_dependencies(coverage_sim ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS} ${actionlib_tutorials_EXPORTED_TARGETS} ) -target_link_libraries(thick_sim +target_link_libraries(coverage_sim ${PROJECT_NAME} ) @@ -83,7 +83,7 @@ endif() ############# ## Install ## ############# -install(TARGETS ${PROJECT_NAME} thick_sim +install(TARGETS ${PROJECT_NAME} coverage_sim ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} diff --git a/noether_simulator/src/thickness_simulator_node.cpp b/noether_simulator/src/coverage_simulator_node.cpp similarity index 100% rename from noether_simulator/src/thickness_simulator_node.cpp rename to noether_simulator/src/coverage_simulator_node.cpp diff --git a/noether_simulator/src/noether_simulator.cpp b/noether_simulator/src/noether_simulator.cpp index 229a5886..1cadd868 100644 --- a/noether_simulator/src/noether_simulator.cpp +++ b/noether_simulator/src/noether_simulator.cpp @@ -22,6 +22,7 @@ * See the License for the specific language governing permissions and * limitations under the License. */ +#include #include #include @@ -50,36 +51,6 @@ namespace noether_simulator simulation_points_ = vtkSmartPointer::New(); } - //This is a definite integral of the function (x^2 + z^2)/10 from one point pt1 to another point pt2. - //This function is expecting pt to be in the Tool frame of reference. - //The factor of one 10th stems from the subsampling of the surface at a 10x density. - double NoetherSimulator::integral(double pt[3]) - { - double result; - result = -( pow(pt[0],3.0)) /3.0 - (pow(pt[2],3.0))/3.0 ; - - return 10*result;//10 to compansate for sampling the mesh - } - - //Integration between 2 points inside cylinder, or inside point and cylinder edge - double NoetherSimulator::calculateIntegration(vtkSmartPointer points) - { - if(points->GetNumberOfPoints() < 2) - return 0; - - double pt1[3], pt2[3]; - double val1, val2; - - points->GetPoint(0, pt1); - points->GetPoint(1, pt2); - - val1 = integral(pt1); - val2 = integral(pt2); - - double value = (val2 - val1); - return fabs(value); - } - //Returns a copy of the private varible simulation_points vtkSmartPointer NoetherSimulator::getSimulatedPoints() { @@ -112,12 +83,31 @@ void NoetherSimulator::runSimulation() // create tool object // the cylinder is defined in a different frame than the mesh or path vtkSmartPointer cylinder = vtkSmartPointer::New(); - cylinder->SetCenter(0.0, 0.0, 0.0); - cylinder->SetRadius(tool_.simulator_tool_radius ); + cylinder->SetCenter(0.0, 0.0,0.0); + cylinder->SetRadius(tool_.simulator_tool_radius); cylinder->SetHeight(tool_.simulator_tool_height); cylinder->SetResolution(20); cylinder->Update(); + //test cone + vtkSmartPointer cone = vtkSmartPointer::New(); + cone->SetCenter(0.0, 0.0, (double(tool_.simulator_tool_height)/2.0)); + cone->SetRadius(tool_.simulator_tool_radius); + double temp [3]; + cone->GetDirection(temp); + cone->SetDirection(0,0,1); + cone->GetDirection(temp); + cone->SetHeight(tool_.simulator_tool_height); + cone->SetResolution(20); + cone->Update(); + vtkSmartPointer cone_poly = vtkSmartPointer::New(); + cone_poly->DeepCopy(cone->GetOutput()); + vtk_viewer::VTKViewer viewer; + std::vector color2(3); + color2[0] = 0.1; color2[1] = 0.1; color2[2] = 0.1; + //viewer.renderDisplay(); + //end test cone + vtkSmartPointer tree = vtkSmartPointer::New(); tree->SetDataSet(cylinder->GetOutput()); tree->BuildLocator(); @@ -152,7 +142,9 @@ void NoetherSimulator::runSimulation() vtkSmartPointer transform_filter = vtkSmartPointer::New(); vtkSmartPointer cylinder_poly = vtkSmartPointer::New(); - cylinder_poly->DeepCopy(cylinder->GetOutput()); + //cylinder_poly->DeepCopy(cylinder->GetOutput()); + cylinder_poly->DeepCopy(cone->GetOutput()); + transform_filter->SetInputData(cylinder_poly);//set data to be transformed (tool) transform_filter->SetTransform(trans);//set transform (tramsform tool to pt1 frame) transform_filter->Update(); @@ -242,61 +234,17 @@ void NoetherSimulator::runSimulation() select_enclosed2->SetSurfaceData(cylinder->GetOutput()); vtkSmartPointer test_poly = vtkSmartPointer::New(); vtkSmartPointer test_pts = vtkSmartPointer::New(); - vtkSmartPointer integration_pts = vtkSmartPointer::New(); + // vtkSmartPointer integration_pts = vtkSmartPointer::New(); - for(int i = 0; i < num_pts; ++i) + for(int i = 0; i < num_pts; ++i)//for each point inside convex hull incrament the scalor (color) value { - integration_pts->Reset(); - - // check to see if the point begin/end locations are inside of the tool - double pt1[3], pt2[3]; - tool_pts1->GetPoint(i, pt1); - tool_pts2->GetPoint(i, pt2); - - test_pts->Reset(); - test_pts->InsertNextPoint(pt1); - test_pts->InsertNextPoint(pt2); - test_poly->SetPoints(test_pts); - select_enclosed2->SetInputData(test_poly); - select_enclosed2->Update(); - - if(select_enclosed2->IsInside(0)) - { - integration_pts->InsertNextPoint(pt1); - } - if(select_enclosed2->IsInside(1)) - { - integration_pts->InsertNextPoint(pt2); - } - - // if one or both points are not inside the tool, - // create line from point start/stop location and find intersection with the tool - if(integration_pts->GetNumberOfPoints() < 2) - { - vtkSmartPointer temp_pts = vtkSmartPointer::New(); - tree->IntersectWithLine(pt1, pt2, 0.001, temp_pts, NULL); - - int intersections = temp_pts->GetNumberOfPoints(); - - // get intersection point(s) - for(int j = 0; j < intersections; ++j) - { - double temp_pt[3]; - temp_pts->GetPoint(j, temp_pt); - integration_pts->InsertNextPoint(temp_pt); - } - } - - // We should now have two points; combine pts with tool to get integrated value - double integral_sum = 0; - integral_sum = calculateIntegration(integration_pts); - - // assuming that the tool_pts are in the same order as pts_inside, // use the point indeces from pts_inside to modify the scalar values int index = pts_inside->GetId(i); // get scalar value, color data is stored in scalars double *tmp_value = scalars->GetTuple(index); - double value = *tmp_value + integral_sum; + //double value = *tmp_value + integral_sum; + double process_sum = 0.75; + double value = *tmp_value + process_sum; scalars->SetTuple1(index, value);//update intensity values }// end loop through all tool points found @@ -369,6 +317,11 @@ void NoetherSimulator::runSimulation() vtkSmartPointer NoetherSimulator::createMatrix(double pt[3], double norm[3], double derv[3]) { + //test vectors view transform + Eigen::Vector4d a(1,0,0,0); + Eigen::Vector4d b(0,1,0,0); + Eigen::Vector4d c(0,0,1,0); + Eigen::Vector4d d(0,0,0,1); // perform cross product to get the third axis direction Eigen::Vector3d u(norm[0], norm[1], norm[2]); @@ -389,6 +342,22 @@ void NoetherSimulator::runSimulation() epose.matrix().col(2).head<3>() = -v; epose.matrix().col(3).head<3>() = Eigen::Vector3d(pt[0], pt[1], pt[2]); + //print out transforms + Eigen::Vector4d a1(0,0,0,0); + Eigen::Vector4d b1(0,0,0,0); + Eigen::Vector4d c1(0,0,0,0); + Eigen::Vector4d d1(0,0,0,0); + + a1 = epose*a; + b1 = epose*b; + c1 = epose*c; + d1 = epose*d; + ROS_INFO("w0: %f w1: %f w2: %f w3: %f\n",a1[0], a1[1], a1[2],a1[3]); + ROS_INFO("u0: %f u1: %f u2: %f u3: %f\n",b1[0], b1[1], b1[2],b1[3]); + ROS_INFO("-v0: %f -v1: %f -v2: %f -v3: %f\n",c1[0], c1[1], c1[2],c1[3]); + ROS_INFO("pt x:%f y:%f Z:%f last:%f\n",d1[0], d1[1], d1[2],d1[3]); + ROS_INFO(""); + // the eigen epose.data() returns column major data whereas the vtk matrix DeepCopy() // takes row major data, need to transpose the data before setting the vtk matrix vtkSmartPointer temp_matrix = vtkSmartPointer::New(); diff --git a/noether_simulator/test/utest.cpp b/noether_simulator/test/utest.cpp index e160d9f2..8fa3e512 100644 --- a/noether_simulator/test/utest.cpp +++ b/noether_simulator/test/utest.cpp @@ -137,7 +137,7 @@ TEST(ViewerTest, TestCase1) double intensity[3]; int missed = 0; - for(vtkIdType i = 0; i < length; i++)//iterate through points to check if painted + for(vtkIdType i = 0; i < length; i++)//iterate through points to check if covered { intensity[0] = processedPoints->GetPointData()->GetScalars()->GetComponent(i,0); intensity[1] = processedPoints->GetPointData()->GetScalars()->GetComponent(i,1); @@ -149,13 +149,13 @@ TEST(ViewerTest, TestCase1) } } - bool painted; - if(missed/float(processedPoints->GetNumberOfPoints())>0.1)//get ratio of missed spots, if below threshold set not painted + bool coverage; + if(missed/float(processedPoints->GetNumberOfPoints())>0.1)//get ratio of missed spots, if below threshold set not covered { - painted = false; + coverage = false; } - else painted = true; - EXPECT_FALSE(painted);//expect partial path to fail + else coverage = true; + EXPECT_FALSE(coverage);//expect partial path to fail } //This test uses a good path to paint mesh @@ -195,7 +195,7 @@ TEST(ViewerTest, TestCase2) tool.pt_spacing = 0.5; tool.line_spacing = 0.75; tool.tool_offset = 0.0; // currentlyc unused - tool.intersecting_plane_height = 0.15; // 0.5 works best, not sure if this should be included in the tool + tool.intersecting_plane_height = 1.95; // 0.5 works best, not sure if this should be included in the tool tool.simulator_nearest_neighbors = 30; // not sure if this should be a part of the tool tool.min_hole_size = 0.1; tool.min_segment_size = 1; @@ -255,9 +255,9 @@ TEST(ViewerTest, TestCase2) double p[3]; double intensity[3]; int missed = 0; - bool painted; + bool coverage; - for(vtkIdType i = 0; i < length; i++)//iterate through points to check if painted + for(vtkIdType i = 0; i < length; i++)//iterate through points to check if covered { intensity[0] = processedPoints->GetPointData()->GetScalars()->GetComponent(i,0); @@ -269,12 +269,12 @@ TEST(ViewerTest, TestCase2) missed++; } } - if(missed/float(processedPoints->GetNumberOfPoints())>0.1)//get ratio of missed spots, if below threshold set not painted + if(missed/float(processedPoints->GetNumberOfPoints())>0.1)//get ratio of missed spots, if below threshold set not covered { - painted = false; + coverage = false; } - else painted = true; - EXPECT_TRUE(painted);//expect good mesh to pass + else coverage = true; + EXPECT_TRUE(coverage);//expect good mesh to pass } // Run all the tests that were declared with TEST() From 49aa6bf21b3bb1a1cad7da4bfcce88feb7c1b8ea Mon Sep 17 00:00:00 2001 From: twall Date: Wed, 7 Aug 2019 13:44:06 -0500 Subject: [PATCH 10/12] changed example and test meshes to be rectangular instead of square --- .../src/coverage_simulator_client.cpp | 14 +- .../src/coverage_simulator_node.cpp | 164 +++++++++--------- noether_simulator/src/noether_simulator.cpp | 13 +- noether_simulator/test/utest.cpp | 5 +- 4 files changed, 98 insertions(+), 98 deletions(-) diff --git a/noether_examples/src/coverage_simulator_client.cpp b/noether_examples/src/coverage_simulator_client.cpp index 60d5d80b..feae5a87 100644 --- a/noether_examples/src/coverage_simulator_client.cpp +++ b/noether_examples/src/coverage_simulator_client.cpp @@ -130,21 +130,15 @@ int main (int argc, char **argv) //......setup test meshes and path pcl_msgs::PolygonMesh myMesh; vtkSmartPointer points2 = vtkSmartPointer::New(); - double pt1[3] = {3.0, 3.0, 0.0}; - double pt2[3] = {4.0, 2.0, 0.0}; - double pt3[3] = {5.0, 3.0, 0.0}; - double pt4[3] = {4.0, 4.0, 0.0}; - - points2->InsertNextPoint(pt1); - points2->InsertNextPoint(pt2); - points2->InsertNextPoint(pt3); - points2->InsertNextPoint(pt4); - //......end setup test meshes and path //.......create control meshes for(int count = 0; count<2; count++)//start multimesh creation loop { vtkSmartPointer points; + //if(count==0) + //{ + // points = vtk_viewer::createPlane(20,7,vtk_viewer::SINUSOIDAL_1D); + //} if(count==0) { points = vtk_viewer::createPlane(19,10,vtk_viewer::SINUSOIDAL_1D); diff --git a/noether_simulator/src/coverage_simulator_node.cpp b/noether_simulator/src/coverage_simulator_node.cpp index e708e7b8..b4c05997 100644 --- a/noether_simulator/src/coverage_simulator_node.cpp +++ b/noether_simulator/src/coverage_simulator_node.cpp @@ -166,100 +166,104 @@ class ProcessSimulatorNode{ //start multiple paths for (int curPathNum=0;curPathNumpath.size();curPathNum++) { - bool added = false; - //convert robot path for simulator - std::vector robot_paths_in = goal->path[curPathNum].paths; - std::vector robot_paths_arg; - int number_paths = robot_paths_in.size(); - - for(int ii = 0; ii < number_paths; ii++) + if(result_.coverage[curPathNum]==false) { - robot_paths_arg.push_back(convertPoseArraytoVTK(robot_paths_in[ii])); - } + bool added = false; - sim.setInputPaths(robot_paths_arg);//add path to simulator + //convert robot path for simulator + std::vector robot_paths_in = goal->path[curPathNum].paths; + std::vector robot_paths_arg; + int number_paths = robot_paths_in.size(); - for(int i=0; i input_mesh[i], surface_mesh); - vtkSmartPointer surface_mesh_vtk = vtkSmartPointer::New(); - pcl::VTKUtils::convertToVTK(surface_mesh, surface_mesh_vtk); - - sim.setInputMesh(surface_mesh_vtk);//add mesh to simulator - sim.runSimulation();//display covered parts - - //deterimine if covered enough - vtkSmartPointer processedPoints = vtkSmartPointer::New(); - processedPoints = sim.getSimulatedPoints();//get a copy of simulated points to operate on - vtkIdType length = processedPoints->GetNumberOfPoints(); - - double intensity[3] = {0,0,0};//setup flann - int missed = 0; - double minPaintThreshold = 5; - double maxPassableNoncoverage = 0.1; - double p [3]; - vtkSmartPointer pointTree = - vtkSmartPointer::New(); - pointTree->SetDataSet(processedPoints); - pointTree->BuildLocator(); - unsigned int k = 30; - double currPoint [3]; - - for(vtkIdType a = 0; a < length; a++)//iterate through points to check if covered - { - intensity[0] =0;//reseting intensity for next point in mesh - intensity[1] =0; - intensity[2] =0; + sim.setInputPaths(robot_paths_arg);//add path to simulator - vtkSmartPointer result = vtkSmartPointer::New(); - processedPoints->GetPoint(a,currPoint); - pointTree->FindClosestNPoints(k, currPoint, result);//flann + for(int i=0; i input_mesh[i], surface_mesh); + vtkSmartPointer surface_mesh_vtk = vtkSmartPointer::New(); + pcl::VTKUtils::convertToVTK(surface_mesh, surface_mesh_vtk); + + sim.setInputMesh(surface_mesh_vtk);//add mesh to simulator + sim.runSimulation();//display covered parts + + //deterimine if covered enough + vtkSmartPointer processedPoints = vtkSmartPointer::New(); + processedPoints = sim.getSimulatedPoints();//get a copy of simulated points to operate on + vtkIdType length = processedPoints->GetNumberOfPoints(); + + double intensity[3] = {0,0,0};//setup flann + int missed = 0; + double minPaintThreshold = 5; + double maxPassableNoncoverage = 0.1; + double p [3]; + vtkSmartPointer pointTree = + vtkSmartPointer::New(); + pointTree->SetDataSet(processedPoints); + pointTree->BuildLocator(); + unsigned int k = 30; + double currPoint [3]; + + for(vtkIdType a = 0; a < length; a++)//iterate through points to check if covered { - vtkIdType point_ind = result->GetId(i); - - //find average color intensity for each neighorhood - intensity[0] += processedPoints->GetPointData()->GetScalars()->GetComponent(point_ind,0); - intensity[1] += processedPoints->GetPointData()->GetScalars()->GetComponent(point_ind,1); - intensity[2] += processedPoints->GetPointData()->GetScalars()->GetComponent(point_ind,2); - } - - if((intensity[0])/float(k)+(intensity[1])/float(k)+(intensity[2])/30 < minPaintThreshold) //averge of each pixel if less than threshold incrament counter + intensity[0] =0;//reseting intensity for next point in mesh + intensity[1] =0; + intensity[2] =0; + + vtkSmartPointer result = vtkSmartPointer::New(); + processedPoints->GetPoint(a,currPoint); + pointTree->FindClosestNPoints(k, currPoint, result);//flann + + for (vtkIdType i = 0; i < k; i++)//iterate through k closest points average intensities + { + vtkIdType point_ind = result->GetId(i); + + //find average color intensity for each neighorhood + intensity[0] += processedPoints->GetPointData()->GetScalars()->GetComponent(point_ind,0); + intensity[1] += processedPoints->GetPointData()->GetScalars()->GetComponent(point_ind,1); + intensity[2] += processedPoints->GetPointData()->GetScalars()->GetComponent(point_ind,2); + } + + if((intensity[0])/float(k)+(intensity[1])/float(k)+(intensity[2])/30 < minPaintThreshold) //averge of each pixel if less than threshold incrament counter + { + missed++; + } + }//end iterate through points to check if covered + + if(missed/float(processedPoints->GetNumberOfPoints())>maxPassableNoncoverage)//get ratio of missed spots, if below threshold set not covered { - missed++; + result_.coverage[i]=false; } - }//end iterate through points to check if covered - - if(missed/float(processedPoints->GetNumberOfPoints())>maxPassableNoncoverage)//get ratio of missed spots, if below threshold set not covered - { - result_.coverage[i]=false; - } - else - { - result_.coverage[i]=true; - if(added ==false) + else { - result_.requiredPath.push_back(goal->path[curPathNum]); - added = true; + result_.coverage[i]=true; + if(added ==false) + { + result_.requiredPath.push_back(goal->path[curPathNum]); + added = true; + } } - } - feedback_.percent =float(i)/float(num_meshes); - simulation_service_.publishFeedback(feedback_); + feedback_.percent =float(i)/float(num_meshes); + simulation_service_.publishFeedback(feedback_); - }//if not yet covered - }//end each mesh + }//if not yet covered + }//end each mesh + }//end if path used }//end multiple paths if(success) diff --git a/noether_simulator/src/noether_simulator.cpp b/noether_simulator/src/noether_simulator.cpp index 1cadd868..5a22e584 100644 --- a/noether_simulator/src/noether_simulator.cpp +++ b/noether_simulator/src/noether_simulator.cpp @@ -102,14 +102,17 @@ void NoetherSimulator::runSimulation() cone->Update(); vtkSmartPointer cone_poly = vtkSmartPointer::New(); cone_poly->DeepCopy(cone->GetOutput()); - vtk_viewer::VTKViewer viewer; - std::vector color2(3); - color2[0] = 0.1; color2[1] = 0.1; color2[2] = 0.1; + + ////display cone + //vtk_viewer::VTKViewer viewer; + //std::vector color2(3); + //color2[0] = 0.1; color2[1] = 0.1; color2[2] = 0.1; //viewer.renderDisplay(); - //end test cone + ////end test cone vtkSmartPointer tree = vtkSmartPointer::New(); - tree->SetDataSet(cylinder->GetOutput()); + //tree->SetDataSet(cylinder->GetOutput()); + tree->SetDataSet(cone->GetOutput()); tree->BuildLocator(); // use tool to integrate over time and distance diff --git a/noether_simulator/test/utest.cpp b/noether_simulator/test/utest.cpp index 8fa3e512..e6d83bbd 100644 --- a/noether_simulator/test/utest.cpp +++ b/noether_simulator/test/utest.cpp @@ -43,7 +43,7 @@ TEST(ViewerTest, TestCase1) { // Create mesh to work with - vtkSmartPointer points = vtk_viewer::createPlane(); + vtkSmartPointer points = vtk_viewer::createPlane(19,10,vtk_viewer::SINUSOIDAL_1D); vtkSmartPointer data = vtkSmartPointer::New(); data = vtk_viewer::createMesh(points, 0.5, 5); @@ -163,8 +163,7 @@ TEST(ViewerTest, TestCase2) { // Create mesh to work with - vtkSmartPointer points = vtk_viewer::createPlane(); - + vtkSmartPointer points = vtk_viewer::createPlane(19,10,vtk_viewer::SINUSOIDAL_1D); vtkSmartPointer data = vtkSmartPointer::New(); data = vtk_viewer::createMesh(points, 0.5, 5); From 0a9f4373a53a1933feb33566c1cf30038b91103e Mon Sep 17 00:00:00 2001 From: twall Date: Wed, 7 Aug 2019 15:32:39 -0500 Subject: [PATCH 11/12] updated node names in covage_sim.launch --- noether_examples/launch/coverage_sim.launch | 2 +- noether_simulator/src/noether_simulator.cpp | 13 +++++++------ noether_simulator/test/utest.cpp | 2 +- 3 files changed, 9 insertions(+), 8 deletions(-) diff --git a/noether_examples/launch/coverage_sim.launch b/noether_examples/launch/coverage_sim.launch index 05f9f82d..2fe2ba16 100644 --- a/noether_examples/launch/coverage_sim.launch +++ b/noether_examples/launch/coverage_sim.launch @@ -1,3 +1,3 @@ - + diff --git a/noether_simulator/src/noether_simulator.cpp b/noether_simulator/src/noether_simulator.cpp index 5a22e584..c84ad2ad 100644 --- a/noether_simulator/src/noether_simulator.cpp +++ b/noether_simulator/src/noether_simulator.cpp @@ -84,7 +84,7 @@ void NoetherSimulator::runSimulation() // the cylinder is defined in a different frame than the mesh or path vtkSmartPointer cylinder = vtkSmartPointer::New(); cylinder->SetCenter(0.0, 0.0,0.0); - cylinder->SetRadius(tool_.simulator_tool_radius); + cylinder->SetRadius(tool_.simulator_tool_radius*3); cylinder->SetHeight(tool_.simulator_tool_height); cylinder->SetResolution(20); cylinder->Update(); @@ -104,11 +104,12 @@ void NoetherSimulator::runSimulation() cone_poly->DeepCopy(cone->GetOutput()); ////display cone - //vtk_viewer::VTKViewer viewer; - //std::vector color2(3); - //color2[0] = 0.1; color2[1] = 0.1; color2[2] = 0.1; - //viewer.renderDisplay(); - ////end test cone + vtk_viewer::VTKViewer viewer; + std::vector color2(3); + color2[0] = 0.1; color2[1] = 0.1; color2[2] = 0.1; + viewer.addPolyDataDisplay(cone_poly, color2); + viewer.renderDisplay(); + ////end display cone vtkSmartPointer tree = vtkSmartPointer::New(); //tree->SetDataSet(cylinder->GetOutput()); diff --git a/noether_simulator/test/utest.cpp b/noether_simulator/test/utest.cpp index e6d83bbd..e4bc7ba7 100644 --- a/noether_simulator/test/utest.cpp +++ b/noether_simulator/test/utest.cpp @@ -200,7 +200,7 @@ TEST(ViewerTest, TestCase2) tool.min_segment_size = 1; tool.raster_angle = 0; tool.raster_wrt_global_axes = 0; - tool.simulator_tool_radius = 1; + tool.simulator_tool_radius = 2; tool.simulator_tool_height = 2; planner.setTool(tool); planner.setDebugMode(false); From 0c9981fe8c7ce2d498cc4e9ca1f8850dd2fff06a Mon Sep 17 00:00:00 2001 From: twall Date: Sun, 11 Aug 2019 15:23:05 -0500 Subject: [PATCH 12/12] code for demo --- noether_examples/launch/coverage_sim.launch | 2 +- noether_examples/meshes/outputs/output_0.stl | 5784 + noether_examples/meshes/outputs/output_1.stl | 6953 + noether_examples/meshes/outputs/output_10.stl | 5098 + noether_examples/meshes/outputs/output_11.stl | 8647 + noether_examples/meshes/outputs/output_12.stl | 3740 + noether_examples/meshes/outputs/output_13.stl | 5777 + noether_examples/meshes/outputs/output_14.stl | 6547 + noether_examples/meshes/outputs/output_15.stl | 10257 + noether_examples/meshes/outputs/output_16.stl | 10320 + noether_examples/meshes/outputs/output_17.stl | 10306 + noether_examples/meshes/outputs/output_18.stl | 4678 + noether_examples/meshes/outputs/output_19.stl | 6001 + noether_examples/meshes/outputs/output_2.stl | 6953 + noether_examples/meshes/outputs/output_20.stl | 6554 + noether_examples/meshes/outputs/output_21.stl | 10306 + noether_examples/meshes/outputs/output_22.stl | 6057 + noether_examples/meshes/outputs/output_23.stl | 6057 + noether_examples/meshes/outputs/output_24.stl | 295171 +++++++++++++++ noether_examples/meshes/outputs/output_3.stl | 6477 + noether_examples/meshes/outputs/output_4.stl | 71458 ++++ noether_examples/meshes/outputs/output_5.stl | 69183 ++++ noether_examples/meshes/outputs/output_6.stl | 29619 ++ noether_examples/meshes/outputs/output_7.stl | 51270 +++ noether_examples/meshes/outputs/output_8.stl | 4678 + noether_examples/meshes/outputs/output_9.stl | 52950 +++ .../meshes/outputsBackDoor/output_0.stl | 57647 +++ .../meshes/outputsBackDoor/output_1.stl | 11454 + .../meshes/outputsBackDoor/output_2.stl | 6841 + .../meshes/outputsBackDoor/output_3.stl | 5721 + .../meshes/outputsBackDoor/output_4.stl | 65865 ++++ .../meshes/outputsBackDoor/output_5.stl | 15703 + .../meshes/outputsBackDoor/output_6.stl | 5343 + .../meshes/outputsBackDoor/output_7.stl | 159728 ++++++++ .../meshes/outputsBackDoor/output_8.stl | 73306 ++++ .../meshes/outputsBackDoor/output_9.stl | 253724 +++++++++++++ .../src/coverage_simulator_client.cpp | 195 +- .../src/coverage_simulator_node.cpp | 16 +- noether_simulator/src/noether_simulator.cpp | 96 +- .../src/raster_tool_path_planner.cpp | 7 +- 40 files changed, 1356430 insertions(+), 59 deletions(-) create mode 100644 noether_examples/meshes/outputs/output_0.stl create mode 100644 noether_examples/meshes/outputs/output_1.stl create mode 100644 noether_examples/meshes/outputs/output_10.stl create mode 100644 noether_examples/meshes/outputs/output_11.stl create mode 100644 noether_examples/meshes/outputs/output_12.stl create mode 100644 noether_examples/meshes/outputs/output_13.stl create mode 100644 noether_examples/meshes/outputs/output_14.stl create mode 100644 noether_examples/meshes/outputs/output_15.stl create mode 100644 noether_examples/meshes/outputs/output_16.stl create mode 100644 noether_examples/meshes/outputs/output_17.stl create mode 100644 noether_examples/meshes/outputs/output_18.stl create mode 100644 noether_examples/meshes/outputs/output_19.stl create mode 100644 noether_examples/meshes/outputs/output_2.stl create mode 100644 noether_examples/meshes/outputs/output_20.stl create mode 100644 noether_examples/meshes/outputs/output_21.stl create mode 100644 noether_examples/meshes/outputs/output_22.stl create mode 100644 noether_examples/meshes/outputs/output_23.stl create mode 100644 noether_examples/meshes/outputs/output_24.stl create mode 100644 noether_examples/meshes/outputs/output_3.stl create mode 100644 noether_examples/meshes/outputs/output_4.stl create mode 100644 noether_examples/meshes/outputs/output_5.stl create mode 100644 noether_examples/meshes/outputs/output_6.stl create mode 100644 noether_examples/meshes/outputs/output_7.stl create mode 100644 noether_examples/meshes/outputs/output_8.stl create mode 100644 noether_examples/meshes/outputs/output_9.stl create mode 100644 noether_examples/meshes/outputsBackDoor/output_0.stl create mode 100644 noether_examples/meshes/outputsBackDoor/output_1.stl create mode 100644 noether_examples/meshes/outputsBackDoor/output_2.stl create mode 100644 noether_examples/meshes/outputsBackDoor/output_3.stl create mode 100644 noether_examples/meshes/outputsBackDoor/output_4.stl create mode 100644 noether_examples/meshes/outputsBackDoor/output_5.stl create mode 100644 noether_examples/meshes/outputsBackDoor/output_6.stl create mode 100644 noether_examples/meshes/outputsBackDoor/output_7.stl create mode 100644 noether_examples/meshes/outputsBackDoor/output_8.stl create mode 100644 noether_examples/meshes/outputsBackDoor/output_9.stl diff --git a/noether_examples/launch/coverage_sim.launch b/noether_examples/launch/coverage_sim.launch index 2fe2ba16..bbf53202 100644 --- a/noether_examples/launch/coverage_sim.launch +++ b/noether_examples/launch/coverage_sim.launch @@ -1,3 +1,3 @@ - + diff --git a/noether_examples/meshes/outputs/output_0.stl b/noether_examples/meshes/outputs/output_0.stl new file mode 100644 index 00000000..8d3a6583 --- /dev/null +++ b/noether_examples/meshes/outputs/output_0.stl @@ -0,0 +1,5784 @@ +solid ascii + facet normal 0.422928 -0.344439 -0.838149 + outer loop + vertex 700.042 146.872 299.067 + vertex 701.865 147.435 299.756 + vertex 700.099 145.902 299.495 + endloop + endfacet + facet normal 0.443017 -0.339533 -0.829731 + outer loop + vertex 700.042 146.872 299.067 + vertex 700.099 145.902 299.495 + vertex 698.556 146.159 298.566 + endloop + endfacet + facet normal 0.44438 -0.34425 -0.827054 + outer loop + vertex 698.556 146.159 298.566 + vertex 699.332 148.114 298.169 + vertex 700.042 146.872 299.067 + endloop + endfacet + facet normal 0.452094 -0.338526 -0.825234 + outer loop + vertex 700.042 146.872 299.067 + vertex 699.332 148.114 298.169 + vertex 700.846 148.641 298.782 + endloop + endfacet + facet normal 0.448309 -0.314095 -0.836877 + outer loop + vertex 699.332 148.114 298.169 + vertex 700.364 151.131 297.589 + vertex 700.846 148.641 298.782 + endloop + endfacet + facet normal 0.456004 -0.31114 -0.833818 + outer loop + vertex 700.846 148.641 298.782 + vertex 700.364 151.131 297.589 + vertex 701.707 151.043 298.357 + endloop + endfacet + facet normal 0.436604 -0.359656 -0.824636 + outer loop + vertex 700.099 145.902 299.495 + vertex 697.309 144.808 298.495 + vertex 698.556 146.159 298.566 + endloop + endfacet + facet normal 0.448362 -0.424256 -0.786752 + outer loop + vertex 697.309 144.808 298.495 + vertex 700.099 145.902 299.495 + vertex 698.569 144.861 299.184 + endloop + endfacet + facet normal 0.447263 -0.429905 -0.784307 + outer loop + vertex 698.569 144.861 299.184 + vertex 696.323 144.017 298.366 + vertex 697.309 144.808 298.495 + endloop + endfacet + facet normal 0.455669 -0.496169 -0.739041 + outer loop + vertex 696.323 144.017 298.366 + vertex 698.569 144.861 299.184 + vertex 698.237 144.481 299.235 + endloop + endfacet + facet normal 0.41466 -0.360107 -0.835691 + outer loop + vertex 701.069 145.836 300.004 + vertex 698.569 144.861 299.184 + vertex 700.099 145.902 299.495 + endloop + endfacet + facet normal 0.411453 -0.373587 -0.831348 + outer loop + vertex 700.099 145.902 299.495 + vertex 703.255 147.157 300.493 + vertex 701.069 145.836 300.004 + endloop + endfacet + facet normal 0.437231 -0.482704 -0.758832 + outer loop + vertex 698.569 144.861 299.184 + vertex 701.069 145.836 300.004 + vertex 698.237 144.481 299.235 + endloop + endfacet + facet normal 0.420692 -0.327588 -0.845993 + outer loop + vertex 700.042 146.872 299.067 + vertex 700.846 148.641 298.782 + vertex 701.865 147.435 299.756 + endloop + endfacet + facet normal 0.429224 -0.319434 -0.844825 + outer loop + vertex 701.865 147.435 299.756 + vertex 700.846 148.641 298.782 + vertex 702.718 149.431 299.434 + endloop + endfacet + facet normal 0.395742 -0.308394 -0.865032 + outer loop + vertex 701.865 147.435 299.756 + vertex 702.718 149.431 299.434 + vertex 704.358 148.641 300.466 + endloop + endfacet + facet normal 0.39623 -0.309837 -0.864293 + outer loop + vertex 704.358 148.641 300.466 + vertex 703.255 147.157 300.493 + vertex 701.865 147.435 299.756 + endloop + endfacet + facet normal 0.396373 -0.309383 -0.86439 + outer loop + vertex 703.255 147.157 300.493 + vertex 700.099 145.902 299.495 + vertex 701.865 147.435 299.756 + endloop + endfacet + facet normal 0.362621 -0.28528 -0.887199 + outer loop + vertex 703.255 147.157 300.493 + vertex 704.358 148.641 300.466 + vertex 706.625 148.923 301.303 + endloop + endfacet + facet normal 0.368697 -0.300318 -0.8797 + outer loop + vertex 703.255 147.157 300.493 + vertex 706.625 148.923 301.303 + vertex 704.718 147.28 301.064 + endloop + endfacet + facet normal 0.36932 -0.284112 -0.884807 + outer loop + vertex 704.718 147.28 301.064 + vertex 701.069 145.836 300.004 + vertex 703.255 147.157 300.493 + endloop + endfacet + facet normal 0.362433 -0.264185 -0.893783 + outer loop + vertex 706.625 148.923 301.303 + vertex 704.358 148.641 300.466 + vertex 706.555 150.213 300.892 + endloop + endfacet + facet normal 0.344941 -0.267066 -0.899828 + outer loop + vertex 706.625 148.923 301.303 + vertex 706.555 150.213 300.892 + vertex 709.365 151.369 301.626 + endloop + endfacet + facet normal 0.343902 -0.263649 -0.901233 + outer loop + vertex 706.555 150.213 300.892 + vertex 707.169 153.061 300.294 + vertex 709.365 151.369 301.626 + endloop + endfacet + facet normal 0.358053 -0.245063 -0.900967 + outer loop + vertex 709.365 151.369 301.626 + vertex 707.169 153.061 300.294 + vertex 710.92 154.742 301.327 + endloop + endfacet + facet normal 0.350765 -0.22364 -0.909367 + outer loop + vertex 707.169 153.061 300.294 + vertex 708.406 157.874 299.587 + vertex 710.92 154.742 301.327 + endloop + endfacet + facet normal 0.376288 -0.200476 -0.904553 + outer loop + vertex 710.92 154.742 301.327 + vertex 708.406 157.874 299.587 + vertex 711.809 159.212 300.706 + endloop + endfacet + facet normal 0.36967 -0.177348 -0.912081 + outer loop + vertex 708.406 157.874 299.587 + vertex 709.261 163.511 298.837 + vertex 711.809 159.212 300.706 + endloop + endfacet + facet normal 0.402785 -0.153478 -0.902335 + outer loop + vertex 711.809 159.212 300.706 + vertex 709.261 163.511 298.837 + vertex 712.266 164.728 299.972 + endloop + endfacet + facet normal 0.395461 -0.128781 -0.90941 + outer loop + vertex 709.261 163.511 298.837 + vertex 709.842 169.816 298.198 + vertex 712.266 164.728 299.972 + endloop + endfacet + facet normal 0.424571 -0.111122 -0.89855 + outer loop + vertex 712.266 164.728 299.972 + vertex 709.842 169.816 298.198 + vertex 712.519 170.987 299.318 + endloop + endfacet + facet normal 0.41642 -0.0862521 -0.905072 + outer loop + vertex 709.842 169.816 298.198 + vertex 710.357 176.837 297.765 + vertex 712.519 170.987 299.318 + endloop + endfacet + facet normal 0.432168 -0.0786485 -0.898357 + outer loop + vertex 712.519 170.987 299.318 + vertex 710.357 176.837 297.765 + vertex 712.931 177.723 298.926 + endloop + endfacet + facet normal 0.426446 -0.0562509 -0.902762 + outer loop + vertex 710.357 176.837 297.765 + vertex 710.946 183.742 297.613 + vertex 712.931 177.723 298.926 + endloop + endfacet + facet normal 0.430792 -0.0543923 -0.900811 + outer loop + vertex 712.931 177.723 298.926 + vertex 710.946 183.742 297.613 + vertex 713.457 185.859 298.686 + endloop + endfacet + facet normal 0.420983 -0.0400379 -0.906184 + outer loop + vertex 710.946 183.742 297.613 + vertex 709.901 194.817 296.639 + vertex 713.457 185.859 298.686 + endloop + endfacet + facet normal 0.421303 -0.0398783 -0.906043 + outer loop + vertex 709.901 194.817 296.639 + vertex 715.044 196.182 298.97 + vertex 713.457 185.859 298.686 + endloop + endfacet + facet normal 0.383859 -0.0336603 -0.922778 + outer loop + vertex 716.5 185.353 299.971 + vertex 713.457 185.859 298.686 + vertex 715.044 196.182 298.97 + endloop + endfacet + facet normal 0.330097 -0.0427549 -0.942978 + outer loop + vertex 716.5 185.353 299.971 + vertex 715.044 196.182 298.97 + vertex 719.518 187.997 300.907 + endloop + endfacet + facet normal 0.334309 -0.0481789 -0.941231 + outer loop + vertex 718.974 178.936 301.178 + vertex 716.5 185.353 299.971 + vertex 719.518 187.997 300.907 + endloop + endfacet + facet normal 0.334073 -0.0482847 -0.94131 + outer loop + vertex 715.659 178.367 300.03 + vertex 716.5 185.353 299.971 + vertex 718.974 178.936 301.178 + endloop + endfacet + facet normal 0.337256 -0.0722179 -0.938639 + outer loop + vertex 717.492 171.465 301.22 + vertex 715.659 178.367 300.03 + vertex 718.974 178.936 301.178 + endloop + endfacet + facet normal 0.352046 -0.0674117 -0.933552 + outer loop + vertex 714.723 172.627 300.092 + vertex 715.659 178.367 300.03 + vertex 717.492 171.465 301.22 + endloop + endfacet + facet normal 0.340892 -0.0956347 -0.935225 + outer loop + vertex 714.723 172.627 300.092 + vertex 717.492 171.465 301.22 + vertex 715.126 166.889 300.826 + endloop + endfacet + facet normal 0.389038 -0.0899016 -0.916825 + outer loop + vertex 715.126 166.889 300.826 + vertex 712.519 170.987 299.318 + vertex 714.723 172.627 300.092 + endloop + endfacet + facet normal 0.380938 -0.0768564 -0.921401 + outer loop + vertex 712.519 170.987 299.318 + vertex 712.931 177.723 298.926 + vertex 714.723 172.627 300.092 + endloop + endfacet + facet normal 0.389071 -0.0732854 -0.918288 + outer loop + vertex 714.723 172.627 300.092 + vertex 712.931 177.723 298.926 + vertex 715.659 178.367 300.03 + endloop + endfacet + facet normal 0.38529 -0.0520576 -0.921326 + outer loop + vertex 712.931 177.723 298.926 + vertex 713.457 185.859 298.686 + vertex 715.659 178.367 300.03 + endloop + endfacet + facet normal 0.360555 -0.111413 -0.92606 + outer loop + vertex 712.266 164.728 299.972 + vertex 712.519 170.987 299.318 + vertex 715.126 166.889 300.826 + endloop + endfacet + facet normal 0.368717 -0.124126 -0.921217 + outer loop + vertex 715.156 160.938 301.64 + vertex 712.266 164.728 299.972 + vertex 715.126 166.889 300.826 + endloop + endfacet + facet normal 0.337233 -0.151613 -0.929133 + outer loop + vertex 711.809 159.212 300.706 + vertex 712.266 164.728 299.972 + vertex 715.156 160.938 301.64 + endloop + endfacet + facet normal 0.342824 -0.164782 -0.924834 + outer loop + vertex 714.657 156.28 302.284 + vertex 711.809 159.212 300.706 + vertex 715.156 160.938 301.64 + endloop + endfacet + facet normal 0.316951 -0.192037 -0.928797 + outer loop + vertex 710.92 154.742 301.327 + vertex 711.809 159.212 300.706 + vertex 714.657 156.28 302.284 + endloop + endfacet + facet normal 0.320756 -0.203644 -0.925011 + outer loop + vertex 713.446 152.976 302.592 + vertex 710.92 154.742 301.327 + vertex 714.657 156.28 302.284 + endloop + endfacet + facet normal 0.306857 -0.223599 -0.925117 + outer loop + vertex 709.365 151.369 301.626 + vertex 710.92 154.742 301.327 + vertex 713.446 152.976 302.592 + endloop + endfacet + facet normal 0.309993 -0.233701 -0.921568 + outer loop + vertex 709.365 151.369 301.626 + vertex 713.446 152.976 302.592 + vertex 710.332 150.037 302.29 + endloop + endfacet + facet normal 0.314465 -0.230147 -0.920947 + outer loop + vertex 710.332 150.037 302.29 + vertex 706.625 148.923 301.303 + vertex 709.365 151.369 301.626 + endloop + endfacet + facet normal 0.31482 -0.231801 -0.920411 + outer loop + vertex 710.332 150.037 302.29 + vertex 704.718 147.28 301.064 + vertex 706.625 148.923 301.303 + endloop + endfacet + facet normal 0.330918 -0.090121 -0.939346 + outer loop + vertex 717.492 171.465 301.22 + vertex 718.844 163.835 302.428 + vertex 715.126 166.889 300.826 + endloop + endfacet + facet normal 0.302349 -0.127666 -0.944609 + outer loop + vertex 715.156 160.938 301.64 + vertex 715.126 166.889 300.826 + vertex 718.844 163.835 302.428 + endloop + endfacet + facet normal 0.307735 -0.135284 -0.941806 + outer loop + vertex 718.187 158.003 303.052 + vertex 715.156 160.938 301.64 + vertex 718.844 163.835 302.428 + endloop + endfacet + facet normal 0.284096 -0.161299 -0.945131 + outer loop + vertex 714.657 156.28 302.284 + vertex 715.156 160.938 301.64 + vertex 718.187 158.003 303.052 + endloop + endfacet + facet normal 0.285194 -0.163894 -0.944353 + outer loop + vertex 717.631 154.773 303.444 + vertex 714.657 156.28 302.284 + vertex 718.187 158.003 303.052 + endloop + endfacet + facet normal 0.242323 -0.158071 -0.957232 + outer loop + vertex 717.631 154.773 303.444 + vertex 718.187 158.003 303.052 + vertex 720.736 156.386 303.964 + endloop + endfacet + facet normal 0.23359 -0.139641 -0.962256 + outer loop + vertex 717.631 154.773 303.444 + vertex 720.736 156.386 303.964 + vertex 721.204 154.832 304.303 + endloop + endfacet + facet normal 0.23317 -0.160876 -0.959036 + outer loop + vertex 721.204 154.832 304.303 + vertex 716.291 152.469 303.505 + vertex 717.631 154.773 303.444 + endloop + endfacet + facet normal 0.208831 -0.148063 -0.966678 + outer loop + vertex 720.736 156.386 303.964 + vertex 724.239 157.553 304.542 + vertex 721.204 154.832 304.303 + endloop + endfacet + facet normal 0.206002 -0.138574 -0.96869 + outer loop + vertex 720.736 156.386 303.964 + vertex 721.711 159.435 303.735 + vertex 724.239 157.553 304.542 + endloop + endfacet + facet normal 0.210183 -0.132911 -0.968585 + outer loop + vertex 724.239 157.553 304.542 + vertex 721.711 159.435 303.735 + vertex 725.601 161.079 304.353 + endloop + endfacet + facet normal 0.175726 -0.12006 -0.977091 + outer loop + vertex 724.239 157.553 304.542 + vertex 725.601 161.079 304.353 + vertex 729.047 159.877 305.121 + endloop + endfacet + facet normal 0.182904 -0.13575 -0.973714 + outer loop + vertex 724.239 157.553 304.542 + vertex 729.047 159.877 305.121 + vertex 726.341 156.605 305.069 + endloop + endfacet + facet normal 0.159684 -0.116444 -0.980276 + outer loop + vertex 732.798 159.632 305.761 + vertex 726.341 156.605 305.069 + vertex 729.047 159.877 305.121 + endloop + endfacet + facet normal 0.179288 -0.11018 -0.977607 + outer loop + vertex 729.047 159.877 305.121 + vertex 725.601 161.079 304.353 + vertex 729.871 163.878 304.821 + endloop + endfacet + facet normal 0.152412 -0.105027 -0.982721 + outer loop + vertex 729.047 159.877 305.121 + vertex 729.871 163.878 304.821 + vertex 734.433 163.225 305.598 + endloop + endfacet + facet normal 0.155441 -0.0855374 -0.984135 + outer loop + vertex 734.281 169.179 305.057 + vertex 734.433 163.225 305.598 + vertex 729.871 163.878 304.821 + endloop + endfacet + facet normal 0.158926 -0.0884725 -0.983318 + outer loop + vertex 729.543 167.652 304.429 + vertex 734.281 169.179 305.057 + vertex 729.871 163.878 304.821 + endloop + endfacet + facet normal 0.180563 -0.0862264 -0.979776 + outer loop + vertex 729.871 163.878 304.821 + vertex 726.184 166.18 303.939 + vertex 729.543 167.652 304.429 + endloop + endfacet + facet normal 0.173954 -0.0703228 -0.98224 + outer loop + vertex 729.543 167.652 304.429 + vertex 726.184 166.18 303.939 + vertex 728.099 174.037 303.716 + endloop + endfacet + facet normal 0.154808 -0.0749719 -0.985096 + outer loop + vertex 729.543 167.652 304.429 + vertex 728.099 174.037 303.716 + vertex 734.281 169.179 305.057 + endloop + endfacet + facet normal 0.168884 -0.0567562 -0.984 + outer loop + vertex 734.281 169.179 305.057 + vertex 728.099 174.037 303.716 + vertex 734.756 179.279 304.556 + endloop + endfacet + facet normal 0.161167 -0.0466645 -0.985823 + outer loop + vertex 728.099 174.037 303.716 + vertex 727.368 187.505 302.959 + vertex 734.756 179.279 304.556 + endloop + endfacet + facet normal 0.181251 -0.0280832 -0.983036 + outer loop + vertex 734.756 179.279 304.556 + vertex 727.368 187.505 302.959 + vertex 734.545 191.337 304.172 + endloop + endfacet + facet normal 0.175327 -0.0165667 -0.984371 + outer loop + vertex 727.368 187.505 302.959 + vertex 727.494 201.445 302.746 + vertex 734.545 191.337 304.172 + endloop + endfacet + facet normal 0.188584 -0.00698957 -0.982032 + outer loop + vertex 734.545 191.337 304.172 + vertex 727.494 201.445 302.746 + vertex 734.046 204.272 303.985 + endloop + endfacet + facet normal 0.184864 0.00195237 -0.982762 + outer loop + vertex 727.494 201.445 302.746 + vertex 727.043 215.087 302.689 + vertex 734.046 204.272 303.985 + endloop + endfacet + facet normal 0.190095 0.00546131 -0.98175 + outer loop + vertex 734.046 204.272 303.985 + vertex 727.043 215.087 302.689 + vertex 733.274 217.412 303.908 + endloop + endfacet + facet normal 0.188338 0.0103284 -0.98205 + outer loop + vertex 727.043 215.087 302.689 + vertex 726.324 228.315 302.69 + vertex 733.274 217.412 303.908 + endloop + endfacet + facet normal 0.190055 0.0114617 -0.981706 + outer loop + vertex 733.274 217.412 303.908 + vertex 726.324 228.315 302.69 + vertex 732.379 230.471 303.887 + endloop + endfacet + facet normal 0.189749 0.012349 -0.981755 + outer loop + vertex 726.324 228.315 302.69 + vertex 725.503 241.346 302.695 + vertex 732.379 230.471 303.887 + endloop + endfacet + facet normal 0.192372 0.0140657 -0.981221 + outer loop + vertex 732.379 230.471 303.887 + vertex 725.503 241.346 302.695 + vertex 731.429 243.427 303.887 + endloop + endfacet + facet normal 0.192847 0.0126708 -0.981147 + outer loop + vertex 725.503 241.346 302.695 + vertex 724.653 254.374 302.696 + vertex 731.429 243.427 303.887 + endloop + endfacet + facet normal 0.197365 0.0155696 -0.980207 + outer loop + vertex 731.429 243.427 303.887 + vertex 724.653 254.374 302.696 + vertex 730.431 256.345 303.891 + endloop + endfacet + facet normal 0.198133 0.0132454 -0.980086 + outer loop + vertex 724.653 254.374 302.696 + vertex 723.789 267.486 302.699 + vertex 730.431 256.345 303.891 + endloop + endfacet + facet normal 0.203233 0.0164031 -0.978993 + outer loop + vertex 730.431 256.345 303.891 + vertex 723.789 267.486 302.699 + vertex 729.386 269.298 303.891 + endloop + endfacet + facet normal 0.204048 0.013803 -0.978864 + outer loop + vertex 723.789 267.486 302.699 + vertex 722.913 280.695 302.703 + vertex 729.386 269.298 303.891 + endloop + endfacet + facet normal 0.21193 0.0184621 -0.97711 + outer loop + vertex 729.386 269.298 303.891 + vertex 722.913 280.695 302.703 + vertex 728.294 282.301 303.9 + endloop + endfacet + facet normal 0.213005 0.0147333 -0.97694 + outer loop + vertex 722.913 280.695 302.703 + vertex 722.025 293.952 302.709 + vertex 728.294 282.301 303.9 + endloop + endfacet + facet normal 0.220284 0.0188226 -0.975254 + outer loop + vertex 728.294 282.301 303.9 + vertex 722.025 293.952 302.709 + vertex 727.185 295.354 303.901 + endloop + endfacet + facet normal 0.221259 0.0151064 -0.975098 + outer loop + vertex 722.025 293.952 302.709 + vertex 721.13 307.174 302.711 + vertex 727.185 295.354 303.901 + endloop + endfacet + facet normal 0.231592 0.0206519 -0.972594 + outer loop + vertex 727.185 295.354 303.901 + vertex 721.13 307.174 302.711 + vertex 726.057 308.369 303.909 + endloop + endfacet + facet normal 0.23272 0.0158195 -0.972415 + outer loop + vertex 721.13 307.174 302.711 + vertex 720.23 320.286 302.709 + vertex 726.057 308.369 303.909 + endloop + endfacet + facet normal 0.244123 0.0216883 -0.969502 + outer loop + vertex 726.057 308.369 303.909 + vertex 720.23 320.286 302.709 + vertex 724.926 321.28 303.913 + endloop + endfacet + facet normal 0.245229 0.0162552 -0.969329 + outer loop + vertex 720.23 320.286 302.709 + vertex 719.331 333.295 302.699 + vertex 724.926 321.28 303.913 + endloop + endfacet + facet normal 0.259025 0.0230585 -0.965595 + outer loop + vertex 724.926 321.28 303.913 + vertex 719.331 333.295 302.699 + vertex 723.8 334.09 303.917 + endloop + endfacet + facet normal 0.260065 0.0169838 -0.965442 + outer loop + vertex 719.331 333.295 302.699 + vertex 718.439 346.294 302.688 + vertex 723.8 334.09 303.917 + endloop + endfacet + facet normal 0.279106 0.0259053 -0.959911 + outer loop + vertex 723.8 334.09 303.917 + vertex 718.439 346.294 302.688 + vertex 722.676 346.885 303.936 + endloop + endfacet + facet normal 0.28005 0.0188994 -0.959799 + outer loop + vertex 718.439 346.294 302.688 + vertex 717.583 359.417 302.696 + vertex 722.676 346.885 303.936 + endloop + endfacet + facet normal 0.299984 0.0276197 -0.953544 + outer loop + vertex 722.676 346.885 303.936 + vertex 717.583 359.417 302.696 + vertex 721.593 359.804 303.969 + endloop + endfacet + facet normal 0.300469 0.0225303 -0.953526 + outer loop + vertex 717.583 359.417 302.696 + vertex 716.946 372.793 302.812 + vertex 721.593 359.804 303.969 + endloop + endfacet + facet normal 0.318643 0.0295776 -0.947413 + outer loop + vertex 721.593 359.804 303.969 + vertex 716.946 372.793 302.812 + vertex 720.674 372.961 304.071 + endloop + endfacet + facet normal 0.318551 0.0314084 -0.947385 + outer loop + vertex 716.946 372.793 302.812 + vertex 716.82 386.5 303.224 + vertex 720.674 372.961 304.071 + endloop + endfacet + facet normal 0.32541 0.0335118 -0.944979 + outer loop + vertex 720.674 372.961 304.071 + vertex 716.82 386.5 303.224 + vertex 720.06 386.446 304.337 + endloop + endfacet + facet normal 0.124988 -0.0867004 -0.988363 + outer loop + vertex 734.433 163.225 305.598 + vertex 734.281 169.179 305.057 + vertex 740.612 166.916 306.056 + endloop + endfacet + facet normal 0.130444 -0.0716609 -0.988862 + outer loop + vertex 740.612 166.916 306.056 + vertex 734.281 169.179 305.057 + vertex 741.835 173.639 305.73 + endloop + endfacet + facet normal 0.0964681 -0.0656839 -0.993166 + outer loop + vertex 740.612 166.916 306.056 + vertex 741.835 173.639 305.73 + vertex 748.447 170.271 306.595 + endloop + endfacet + facet normal 0.0996238 -0.0595101 -0.993244 + outer loop + vertex 748.447 170.271 306.595 + vertex 741.835 173.639 305.73 + vertex 749.197 177.234 306.253 + endloop + endfacet + facet normal 0.069928 -0.0564434 -0.995954 + outer loop + vertex 748.447 170.271 306.595 + vertex 749.197 177.234 306.253 + vertex 755.515 174.302 306.863 + endloop + endfacet + facet normal 0.0807728 -0.0755938 -0.993862 + outer loop + vertex 748.447 170.271 306.595 + vertex 755.515 174.302 306.863 + vertex 754.294 170.504 307.053 + endloop + endfacet + facet normal 0.0812628 -0.0903668 -0.992588 + outer loop + vertex 754.294 170.504 307.053 + vertex 750.12 167.616 306.974 + vertex 748.447 170.271 306.595 + endloop + endfacet + facet normal 0.0924318 -0.0832745 -0.992231 + outer loop + vertex 750.12 167.616 306.974 + vertex 744.116 165.181 306.619 + vertex 748.447 170.271 306.595 + endloop + endfacet + facet normal 0.110172 -0.0983563 -0.989034 + outer loop + vertex 740.612 166.916 306.056 + vertex 748.447 170.271 306.595 + vertex 744.116 165.181 306.619 + endloop + endfacet + facet normal 0.110425 -0.128631 -0.985525 + outer loop + vertex 744.116 165.181 306.619 + vertex 750.12 167.616 306.974 + vertex 746.459 164.097 307.023 + endloop + endfacet + facet normal 0.0895484 -0.102392 -0.990705 + outer loop + vertex 750.12 167.616 306.974 + vertex 754.294 170.504 307.053 + vertex 754.907 168.574 307.308 + endloop + endfacet + facet normal 0.0906434 -0.10811 -0.989998 + outer loop + vertex 754.907 168.574 307.308 + vertex 746.459 164.097 307.023 + vertex 750.12 167.616 306.974 + endloop + endfacet + facet normal 0.0795885 -0.105624 -0.991216 + outer loop + vertex 754.294 170.504 307.053 + vertex 759.895 173.201 307.215 + vertex 754.907 168.574 307.308 + endloop + endfacet + facet normal 0.0624649 -0.0697988 -0.995603 + outer loop + vertex 759.895 173.201 307.215 + vertex 754.294 170.504 307.053 + vertex 755.515 174.302 306.863 + endloop + endfacet + facet normal 0.0622513 -0.0706335 -0.995558 + outer loop + vertex 755.515 174.302 306.863 + vertex 762.057 177.659 307.034 + vertex 759.895 173.201 307.215 + endloop + endfacet + facet normal 0.0493262 -0.0644117 -0.996704 + outer loop + vertex 765.5 176.371 307.287 + vertex 759.895 173.201 307.215 + vertex 762.057 177.659 307.034 + endloop + endfacet + facet normal 0.0486148 -0.0662966 -0.996615 + outer loop + vertex 762.057 177.659 307.034 + vertex 769.218 181.054 307.157 + vertex 765.5 176.371 307.287 + endloop + endfacet + facet normal 0.0499245 -0.0673327 -0.996481 + outer loop + vertex 769.578 177.917 307.387 + vertex 765.5 176.371 307.287 + vertex 769.218 181.054 307.157 + endloop + endfacet + facet normal 0.0433795 -0.068103 -0.996735 + outer loop + vertex 774.923 181.545 307.372 + vertex 769.578 177.917 307.387 + vertex 769.218 181.054 307.157 + endloop + endfacet + facet normal 0.0430665 -0.0643514 -0.996998 + outer loop + vertex 769.218 181.054 307.157 + vertex 775.95 185.638 307.152 + vertex 774.923 181.545 307.372 + endloop + endfacet + facet normal 0.0374786 -0.0629669 -0.997312 + outer loop + vertex 780.145 185.267 307.333 + vertex 774.923 181.545 307.372 + vertex 775.95 185.638 307.152 + endloop + endfacet + facet normal 0.0377355 -0.0601461 -0.997476 + outer loop + vertex 775.95 185.638 307.152 + vertex 782.192 189.543 307.153 + vertex 780.145 185.267 307.333 + endloop + endfacet + facet normal 0.0401672 -0.0613038 -0.997311 + outer loop + vertex 785.389 188.159 307.367 + vertex 780.145 185.267 307.333 + vertex 782.192 189.543 307.153 + endloop + endfacet + facet normal 0.0385934 -0.0649149 -0.997144 + outer loop + vertex 782.192 189.543 307.153 + vertex 789.205 193.633 307.158 + vertex 785.389 188.159 307.367 + endloop + endfacet + facet normal 0.0406443 -0.0663379 -0.996969 + outer loop + vertex 790.694 191.258 307.377 + vertex 785.389 188.159 307.367 + vertex 789.205 193.633 307.158 + endloop + endfacet + facet normal 0.0352811 -0.0696973 -0.996944 + outer loop + vertex 794.397 194.618 307.273 + vertex 790.694 191.258 307.377 + vertex 789.205 193.633 307.158 + endloop + endfacet + facet normal 0.0341587 -0.063734 -0.997382 + outer loop + vertex 789.205 193.633 307.158 + vertex 795.556 198.576 307.06 + vertex 794.397 194.618 307.273 + endloop + endfacet + facet normal 0.0301274 -0.0625644 -0.997586 + outer loop + vertex 799.175 197.774 307.219 + vertex 794.397 194.618 307.273 + vertex 795.556 198.576 307.06 + endloop + endfacet + facet normal 0.028096 -0.0716257 -0.997036 + outer loop + vertex 795.556 198.576 307.06 + vertex 801.964 202.774 306.939 + vertex 799.175 197.774 307.219 + endloop + endfacet + facet normal 0.0267605 -0.0708858 -0.997125 + outer loop + vertex 803.021 200.419 307.134 + vertex 799.175 197.774 307.219 + vertex 801.964 202.774 306.939 + endloop + endfacet + facet normal 0.0155732 -0.0758931 -0.996994 + outer loop + vertex 806.507 203.292 306.97 + vertex 803.021 200.419 307.134 + vertex 801.964 202.774 306.939 + endloop + endfacet + facet normal 0.0162518 -0.081873 -0.99651 + outer loop + vertex 801.964 202.774 306.939 + vertex 807.79 207.965 306.607 + vertex 806.507 203.292 306.97 + endloop + endfacet + facet normal 0.051243 -0.106347 -0.993008 + outer loop + vertex 799.175 197.774 307.219 + vertex 803.021 200.419 307.134 + vertex 802.448 198.221 307.34 + endloop + endfacet + facet normal 0.0563371 -0.102172 -0.99317 + outer loop + vertex 794.397 194.618 307.273 + vertex 799.175 197.774 307.219 + vertex 794.841 192.701 307.495 + endloop + endfacet + facet normal 0.019446 -0.0448588 -0.998804 + outer loop + vertex 789.205 193.633 307.158 + vertex 789.664 200.503 306.858 + vertex 795.556 198.576 307.06 + endloop + endfacet + facet normal 0.018827 -0.0467437 -0.998729 + outer loop + vertex 795.556 198.576 307.06 + vertex 789.664 200.503 306.858 + vertex 796.065 204.967 306.77 + endloop + endfacet + facet normal 0.0113753 -0.0461572 -0.998869 + outer loop + vertex 795.556 198.576 307.06 + vertex 796.065 204.967 306.77 + vertex 801.964 202.774 306.939 + endloop + endfacet + facet normal 0.00863689 -0.0534988 -0.998531 + outer loop + vertex 801.964 202.774 306.939 + vertex 796.065 204.967 306.77 + vertex 802.19 209.538 306.578 + endloop + endfacet + facet normal -0.00969188 -0.0528897 -0.998553 + outer loop + vertex 801.964 202.774 306.939 + vertex 802.19 209.538 306.578 + vertex 807.79 207.965 306.607 + endloop + endfacet + facet normal -0.0124997 -0.0628782 -0.997943 + outer loop + vertex 807.79 207.965 306.607 + vertex 802.19 209.538 306.578 + vertex 808.065 214.428 306.197 + endloop + endfacet + facet normal -0.0350154 -0.0618893 -0.997469 + outer loop + vertex 807.79 207.965 306.607 + vertex 808.065 214.428 306.197 + vertex 813.54 212.922 306.098 + endloop + endfacet + facet normal -0.0399222 -0.0798239 -0.996009 + outer loop + vertex 813.54 212.922 306.098 + vertex 808.065 214.428 306.197 + vertex 814.05 219.651 305.538 + endloop + endfacet + facet normal -0.0590221 -0.0783056 -0.995181 + outer loop + vertex 813.54 212.922 306.098 + vertex 814.05 219.651 305.538 + vertex 820.384 218.221 305.275 + endloop + endfacet + facet normal -0.0660279 -0.109966 -0.99174 + outer loop + vertex 820.384 218.221 305.275 + vertex 814.05 219.651 305.538 + vertex 820.202 225.35 304.497 + endloop + endfacet + facet normal -0.0881933 -0.110337 -0.989974 + outer loop + vertex 820.384 218.221 305.275 + vertex 820.202 225.35 304.497 + vertex 825.264 223.545 304.247 + endloop + endfacet + facet normal -0.102621 -0.151756 -0.983076 + outer loop + vertex 825.415 226.96 303.704 + vertex 825.264 223.545 304.247 + vertex 820.202 225.35 304.497 + endloop + endfacet + facet normal -0.111313 -0.125005 -0.985892 + outer loop + vertex 825.415 226.96 303.704 + vertex 820.202 225.35 304.497 + vertex 823.578 230.96 303.404 + endloop + endfacet + facet normal -0.0943236 -0.152242 -0.983832 + outer loop + vertex 825.264 223.545 304.247 + vertex 825.415 226.96 303.704 + vertex 828.82 226.824 303.399 + endloop + endfacet + facet normal -0.094951 -0.177635 -0.979505 + outer loop + vertex 828.82 226.824 303.399 + vertex 825.415 226.96 303.704 + vertex 827.931 230.038 302.902 + endloop + endfacet + facet normal -0.111961 -0.18194 -0.976915 + outer loop + vertex 828.82 226.824 303.399 + vertex 827.931 230.038 302.902 + vertex 831.457 229.831 302.536 + endloop + endfacet + facet normal -0.113156 -0.214311 -0.970189 + outer loop + vertex 831.457 229.831 302.536 + vertex 827.931 230.038 302.902 + vertex 830.478 232.981 301.955 + endloop + endfacet + facet normal -0.13127 -0.219314 -0.966783 + outer loop + vertex 831.457 229.831 302.536 + vertex 830.478 232.981 301.955 + vertex 833.89 232.556 301.588 + endloop + endfacet + facet normal -0.135161 -0.259705 -0.956182 + outer loop + vertex 833.89 232.556 301.588 + vertex 830.478 232.981 301.955 + vertex 832.838 235.601 300.909 + endloop + endfacet + facet normal -0.149137 -0.263815 -0.952974 + outer loop + vertex 833.89 232.556 301.588 + vertex 832.838 235.601 300.909 + vertex 836.458 235.303 300.425 + endloop + endfacet + facet normal -0.150976 -0.308682 -0.939107 + outer loop + vertex 836.458 235.303 300.425 + vertex 832.838 235.601 300.909 + vertex 834.993 238.132 299.731 + endloop + endfacet + facet normal -0.166076 -0.315331 -0.934337 + outer loop + vertex 836.458 235.303 300.425 + vertex 834.993 238.132 299.731 + vertex 838.919 238.066 299.056 + endloop + endfacet + facet normal -0.00466481 -0.035707 -0.999351 + outer loop + vertex 796.065 204.967 306.77 + vertex 795.471 213.61 306.464 + vertex 802.19 209.538 306.578 + endloop + endfacet + facet normal -0.00743623 -0.0402745 -0.999161 + outer loop + vertex 802.19 209.538 306.578 + vertex 795.471 213.61 306.464 + vertex 801.518 218.154 306.236 + endloop + endfacet + facet normal -0.0299178 -0.0420087 -0.998669 + outer loop + vertex 802.19 209.538 306.578 + vertex 801.518 218.154 306.236 + vertex 808.065 214.428 306.197 + endloop + endfacet + facet normal -0.0342808 -0.0496817 -0.998177 + outer loop + vertex 808.065 214.428 306.197 + vertex 801.518 218.154 306.236 + vertex 807.384 222.991 305.794 + endloop + endfacet + facet normal -0.0642726 -0.0519924 -0.996577 + outer loop + vertex 808.065 214.428 306.197 + vertex 807.384 222.991 305.794 + vertex 814.05 219.651 305.538 + endloop + endfacet + facet normal -0.070309 -0.0641285 -0.995462 + outer loop + vertex 814.05 219.651 305.538 + vertex 807.384 222.991 305.794 + vertex 813.049 228.228 305.056 + endloop + endfacet + facet normal -0.104976 -0.0679901 -0.992148 + outer loop + vertex 814.05 219.651 305.538 + vertex 813.049 228.228 305.056 + vertex 820.202 225.35 304.497 + endloop + endfacet + facet normal -0.111126 -0.0836377 -0.990281 + outer loop + vertex 820.202 225.35 304.497 + vertex 813.049 228.228 305.056 + vertex 818.007 233.487 304.056 + endloop + endfacet + facet normal -0.0909595 -0.0417215 -0.99498 + outer loop + vertex 807.384 222.991 305.794 + vertex 806.101 233.327 305.478 + vertex 813.049 228.228 305.056 + endloop + endfacet + facet normal -0.095726 -0.0482773 -0.994236 + outer loop + vertex 813.049 228.228 305.056 + vertex 806.101 233.327 305.478 + vertex 811.535 238.249 304.715 + endloop + endfacet + facet normal -0.141188 -0.054948 -0.988457 + outer loop + vertex 813.049 228.228 305.056 + vertex 811.535 238.249 304.715 + vertex 818.007 233.487 304.056 + endloop + endfacet + facet normal -0.148602 -0.0652624 -0.986741 + outer loop + vertex 818.007 233.487 304.056 + vertex 811.535 238.249 304.715 + vertex 816.582 243.045 303.638 + endloop + endfacet + facet normal -0.169835 -0.0424295 -0.984559 + outer loop + vertex 811.535 238.249 304.715 + vertex 810.051 249.202 304.499 + vertex 816.582 243.045 303.638 + endloop + endfacet + facet normal -0.17504 -0.0481149 -0.983385 + outer loop + vertex 816.582 243.045 303.638 + vertex 810.051 249.202 304.499 + vertex 815.172 253.774 303.364 + endloop + endfacet + facet normal -0.186814 -0.0345318 -0.981788 + outer loop + vertex 810.051 249.202 304.499 + vertex 808.443 260.414 304.411 + vertex 815.172 253.774 303.364 + endloop + endfacet + facet normal -0.190019 -0.0378962 -0.981049 + outer loop + vertex 815.172 253.774 303.364 + vertex 808.443 260.414 304.411 + vertex 813.479 264.815 303.266 + endloop + endfacet + facet normal -0.193833 -0.0333804 -0.980466 + outer loop + vertex 808.443 260.414 304.411 + vertex 806.577 271.375 304.407 + vertex 813.479 264.815 303.266 + endloop + endfacet + facet normal -0.198479 -0.0384624 -0.97935 + outer loop + vertex 813.479 264.815 303.266 + vertex 806.577 271.375 304.407 + vertex 811.583 275.529 303.229 + endloop + endfacet + facet normal -0.198283 -0.0387075 -0.97938 + outer loop + vertex 806.577 271.375 304.407 + vertex 804.416 281.88 304.429 + vertex 811.583 275.529 303.229 + endloop + endfacet + facet normal -0.200628 -0.041466 -0.97879 + outer loop + vertex 811.583 275.529 303.229 + vertex 804.416 281.88 304.429 + vertex 809.413 285.796 303.239 + endloop + endfacet + facet normal -0.198331 -0.0444995 -0.979124 + outer loop + vertex 804.416 281.88 304.429 + vertex 801.99 291.964 304.462 + vertex 809.413 285.796 303.239 + endloop + endfacet + facet normal -0.201122 -0.0480044 -0.978389 + outer loop + vertex 809.413 285.796 303.239 + vertex 801.99 291.964 304.462 + vertex 806.954 295.599 303.263 + endloop + endfacet + facet normal -0.198511 -0.0516822 -0.978735 + outer loop + vertex 801.99 291.964 304.462 + vertex 799.336 301.752 304.484 + vertex 806.954 295.599 303.263 + endloop + endfacet + facet normal -0.199038 -0.0523628 -0.978592 + outer loop + vertex 806.954 295.599 303.263 + vertex 799.336 301.752 304.484 + vertex 804.277 305.073 303.301 + endloop + endfacet + facet normal -0.196227 -0.0566623 -0.97892 + outer loop + vertex 799.336 301.752 304.484 + vertex 796.508 311.382 304.493 + vertex 804.277 305.073 303.301 + endloop + endfacet + facet normal -0.199174 -0.0604459 -0.978098 + outer loop + vertex 804.277 305.073 303.301 + vertex 796.508 311.382 304.493 + vertex 801.403 314.363 303.312 + endloop + endfacet + facet normal -0.198522 -0.0615404 -0.978162 + outer loop + vertex 796.508 311.382 304.493 + vertex 793.552 320.904 304.494 + vertex 801.403 314.363 303.312 + endloop + endfacet + facet normal -0.201652 -0.0654584 -0.977267 + outer loop + vertex 801.403 314.363 303.312 + vertex 793.552 320.904 304.494 + vertex 798.402 323.54 303.317 + endloop + endfacet + facet normal -0.201686 -0.0653941 -0.977265 + outer loop + vertex 793.552 320.904 304.494 + vertex 790.511 330.29 304.493 + vertex 798.402 323.54 303.317 + endloop + endfacet + facet normal -0.205963 -0.0706122 -0.976009 + outer loop + vertex 798.402 323.54 303.317 + vertex 790.511 330.29 304.493 + vertex 795.314 332.567 303.315 + endloop + endfacet + facet normal -0.206389 -0.0697004 -0.975984 + outer loop + vertex 790.511 330.29 304.493 + vertex 787.416 339.5 304.49 + vertex 795.314 332.567 303.315 + endloop + endfacet + facet normal -0.210223 -0.0742634 -0.974829 + outer loop + vertex 795.314 332.567 303.315 + vertex 787.416 339.5 304.49 + vertex 792.173 341.403 303.32 + endloop + endfacet + facet normal -0.211178 -0.0718578 -0.974803 + outer loop + vertex 787.416 339.5 304.49 + vertex 784.284 348.563 304.501 + vertex 792.173 341.403 303.32 + endloop + endfacet + facet normal -0.216665 -0.0781816 -0.973111 + outer loop + vertex 792.173 341.403 303.32 + vertex 784.284 348.563 304.501 + vertex 788.996 350.089 303.329 + endloop + endfacet + facet normal -0.218019 -0.0740196 -0.973134 + outer loop + vertex 784.284 348.563 304.501 + vertex 781.119 357.591 304.523 + vertex 788.996 350.089 303.329 + endloop + endfacet + facet normal -0.225014 -0.0817166 -0.970923 + outer loop + vertex 788.996 350.089 303.329 + vertex 781.119 357.591 304.523 + vertex 785.802 358.73 303.342 + endloop + endfacet + facet normal -0.226696 -0.0749599 -0.971077 + outer loop + vertex 781.119 357.591 304.523 + vertex 777.961 366.689 304.558 + vertex 785.802 358.73 303.342 + endloop + endfacet + facet normal -0.236384 -0.0849833 -0.967936 + outer loop + vertex 785.802 358.73 303.342 + vertex 777.961 366.689 304.558 + vertex 782.632 367.419 303.353 + endloop + endfacet + facet normal -0.239214 -0.0679506 -0.968586 + outer loop + vertex 777.961 366.689 304.558 + vertex 774.998 375.934 304.641 + vertex 782.632 367.419 303.353 + endloop + endfacet + facet normal -0.249693 -0.0778605 -0.96519 + outer loop + vertex 782.632 367.419 303.353 + vertex 774.998 375.934 304.641 + vertex 779.639 376.24 303.416 + endloop + endfacet + facet normal -0.253499 -0.0273232 -0.96695 + outer loop + vertex 774.998 375.934 304.641 + vertex 772.465 385.352 305.039 + vertex 779.639 376.24 303.416 + endloop + endfacet + facet normal -0.239897 -0.0159502 -0.970667 + outer loop + vertex 779.639 376.24 303.416 + vertex 772.465 385.352 305.039 + vertex 777.328 385.236 303.839 + endloop + endfacet + facet normal -0.1109 -0.0313846 -0.993336 + outer loop + vertex 806.101 233.327 305.478 + vertex 804.633 244.601 305.285 + vertex 811.535 238.249 304.715 + endloop + endfacet + facet normal -0.114243 -0.0350615 -0.992834 + outer loop + vertex 811.535 238.249 304.715 + vertex 804.633 244.601 305.285 + vertex 810.051 249.202 304.499 + endloop + endfacet + facet normal -0.123729 -0.023753 -0.992032 + outer loop + vertex 804.633 244.601 305.285 + vertex 803.058 256.068 305.207 + vertex 810.051 249.202 304.499 + endloop + endfacet + facet normal -0.12576 -0.0258529 -0.991724 + outer loop + vertex 810.051 249.202 304.499 + vertex 803.058 256.068 305.207 + vertex 808.443 260.414 304.411 + endloop + endfacet + facet normal -0.128752 -0.0220914 -0.991431 + outer loop + vertex 803.058 256.068 305.207 + vertex 801.24 267.262 305.194 + vertex 808.443 260.414 304.411 + endloop + endfacet + facet normal -0.12899 -0.0223456 -0.991394 + outer loop + vertex 808.443 260.414 304.411 + vertex 801.24 267.262 305.194 + vertex 806.577 271.375 304.407 + endloop + endfacet + facet normal -0.128513 -0.0229726 -0.991442 + outer loop + vertex 801.24 267.262 305.194 + vertex 799.143 278.015 305.217 + vertex 806.577 271.375 304.407 + endloop + endfacet + facet normal -0.129963 -0.0246238 -0.991213 + outer loop + vertex 806.577 271.375 304.407 + vertex 799.143 278.015 305.217 + vertex 804.416 281.88 304.429 + endloop + endfacet + facet normal -0.127616 -0.0278703 -0.991432 + outer loop + vertex 799.143 278.015 305.217 + vertex 796.761 288.376 305.232 + vertex 804.416 281.88 304.429 + endloop + endfacet + facet normal -0.127177 -0.0273438 -0.991503 + outer loop + vertex 804.416 281.88 304.429 + vertex 796.761 288.376 305.232 + vertex 801.99 291.964 304.462 + endloop + endfacet + facet normal -0.124894 -0.0307116 -0.991695 + outer loop + vertex 796.761 288.376 305.232 + vertex 794.166 298.478 305.246 + vertex 801.99 291.964 304.462 + endloop + endfacet + facet normal -0.12593 -0.0319769 -0.991524 + outer loop + vertex 801.99 291.964 304.462 + vertex 794.166 298.478 305.246 + vertex 799.336 301.752 304.484 + endloop + endfacet + facet normal -0.12446 -0.0343226 -0.991631 + outer loop + vertex 794.166 298.478 305.246 + vertex 791.395 308.444 305.249 + vertex 799.336 301.752 304.484 + endloop + endfacet + facet normal -0.12583 -0.0359751 -0.991399 + outer loop + vertex 799.336 301.752 304.484 + vertex 791.395 308.444 305.249 + vertex 796.508 311.382 304.493 + endloop + endfacet + facet normal -0.125248 -0.0369977 -0.991435 + outer loop + vertex 791.395 308.444 305.249 + vertex 788.496 318.318 305.246 + vertex 796.508 311.382 304.493 + endloop + endfacet + facet normal -0.127325 -0.0394346 -0.991077 + outer loop + vertex 796.508 311.382 304.493 + vertex 788.496 318.318 305.246 + vertex 793.552 320.904 304.494 + endloop + endfacet + facet normal -0.127388 -0.0393097 -0.991074 + outer loop + vertex 788.496 318.318 305.246 + vertex 785.513 328.065 305.243 + vertex 793.552 320.904 304.494 + endloop + endfacet + facet normal -0.129854 -0.0421233 -0.990638 + outer loop + vertex 793.552 320.904 304.494 + vertex 785.513 328.065 305.243 + vertex 790.511 330.29 304.493 + endloop + endfacet + facet normal -0.130119 -0.0415235 -0.990628 + outer loop + vertex 785.513 328.065 305.243 + vertex 782.479 337.642 305.24 + vertex 790.511 330.29 304.493 + endloop + endfacet + facet normal -0.133406 -0.0451744 -0.990031 + outer loop + vertex 790.511 330.29 304.493 + vertex 782.479 337.642 305.24 + vertex 787.416 339.5 304.49 + endloop + endfacet + facet normal -0.13395 -0.0437255 -0.990023 + outer loop + vertex 782.479 337.642 305.24 + vertex 779.408 347.083 305.239 + vertex 787.416 339.5 304.49 + endloop + endfacet + facet normal -0.135909 -0.0458298 -0.989661 + outer loop + vertex 787.416 339.5 304.49 + vertex 779.408 347.083 305.239 + vertex 784.284 348.563 304.501 + endloop + endfacet + facet normal -0.136782 -0.0429563 -0.989669 + outer loop + vertex 779.408 347.083 305.239 + vertex 776.303 356.478 305.26 + vertex 784.284 348.563 304.501 + endloop + endfacet + facet normal -0.140548 -0.0468201 -0.988966 + outer loop + vertex 784.284 348.563 304.501 + vertex 776.303 356.478 305.26 + vertex 781.119 357.591 304.523 + endloop + endfacet + facet normal -0.141676 -0.0419756 -0.989023 + outer loop + vertex 776.303 356.478 305.26 + vertex 773.186 365.964 305.304 + vertex 781.119 357.591 304.523 + endloop + endfacet + facet normal -0.147205 -0.047311 -0.987974 + outer loop + vertex 781.119 357.591 304.523 + vertex 773.186 365.964 305.304 + vertex 777.961 366.689 304.558 + endloop + endfacet + facet normal -0.14931 -0.0336982 -0.988216 + outer loop + vertex 773.186 365.964 305.304 + vertex 770.253 375.618 305.418 + vertex 777.961 366.689 304.558 + endloop + endfacet + facet normal -0.158704 -0.0419799 -0.986433 + outer loop + vertex 777.961 366.689 304.558 + vertex 770.253 375.618 305.418 + vertex 774.998 375.934 304.641 + endloop + endfacet + facet normal -0.161391 -0.0027468 -0.986887 + outer loop + vertex 770.253 375.618 305.418 + vertex 768.045 385.454 305.752 + vertex 774.998 375.934 304.641 + endloop + endfacet + facet normal -0.159197 -0.00110266 -0.987246 + outer loop + vertex 774.998 375.934 304.641 + vertex 768.045 385.454 305.752 + vertex 772.465 385.352 305.039 + endloop + endfacet + facet normal -0.0751347 -0.0222888 -0.996924 + outer loop + vertex 791.395 308.444 305.249 + vertex 783.248 315.818 305.698 + vertex 788.496 318.318 305.246 + endloop + endfacet + facet normal -0.0753143 -0.0219108 -0.996919 + outer loop + vertex 783.248 315.818 305.698 + vertex 780.339 325.92 305.696 + vertex 788.496 318.318 305.246 + endloop + endfacet + facet normal -0.0772077 -0.0239539 -0.996727 + outer loop + vertex 788.496 318.318 305.246 + vertex 780.339 325.92 305.696 + vertex 785.513 328.065 305.243 + endloop + endfacet + facet normal -0.0774753 -0.0233067 -0.996722 + outer loop + vertex 780.339 325.92 305.696 + vertex 777.38 335.861 305.693 + vertex 785.513 328.065 305.243 + endloop + endfacet + facet normal -0.0795798 -0.0255149 -0.996502 + outer loop + vertex 785.513 328.065 305.243 + vertex 777.38 335.861 305.693 + vertex 782.479 337.642 305.24 + endloop + endfacet + facet normal -0.0799617 -0.0244206 -0.996499 + outer loop + vertex 777.38 335.861 305.693 + vertex 774.39 345.661 305.693 + vertex 782.479 337.642 305.24 + endloop + endfacet + facet normal -0.0824874 -0.026984 -0.996227 + outer loop + vertex 782.479 337.642 305.24 + vertex 774.39 345.661 305.693 + vertex 779.408 347.083 305.239 + endloop + endfacet + facet normal -0.0830457 -0.0250151 -0.996232 + outer loop + vertex 774.39 345.661 305.693 + vertex 771.365 355.431 305.7 + vertex 779.408 347.083 305.239 + endloop + endfacet + facet normal -0.0833061 -0.0252675 -0.996204 + outer loop + vertex 779.408 347.083 305.239 + vertex 771.365 355.431 305.7 + vertex 776.303 356.478 305.26 + endloop + endfacet + facet normal -0.0840387 -0.0218195 -0.996224 + outer loop + vertex 771.365 355.431 305.7 + vertex 768.329 365.287 305.74 + vertex 776.303 356.478 305.26 + endloop + endfacet + facet normal -0.0860768 -0.0236763 -0.996007 + outer loop + vertex 776.303 356.478 305.26 + vertex 768.329 365.287 305.74 + vertex 773.186 365.964 305.304 + endloop + endfacet + facet normal -0.0876939 -0.0121256 -0.996074 + outer loop + vertex 768.329 365.287 305.74 + vertex 765.452 375.316 305.871 + vertex 773.186 365.964 305.304 + endloop + endfacet + facet normal -0.0929177 -0.0164785 -0.995537 + outer loop + vertex 773.186 365.964 305.304 + vertex 765.452 375.316 305.871 + vertex 770.253 375.618 305.418 + endloop + endfacet + facet normal -0.0948222 0.0140257 -0.995395 + outer loop + vertex 765.452 375.316 305.871 + vertex 762.992 385.567 306.25 + vertex 770.253 375.618 305.418 + endloop + endfacet + facet normal -0.0978394 0.0118016 -0.995132 + outer loop + vertex 770.253 375.618 305.418 + vertex 762.992 385.567 306.25 + vertex 768.045 385.454 305.752 + endloop + endfacet + facet normal -0.052969 0.0241765 -0.998303 + outer loop + vertex 765.452 375.316 305.871 + vertex 758.566 385.664 306.487 + vertex 762.992 385.567 306.25 + endloop + endfacet + facet normal -0.0511467 0.0253928 -0.998368 + outer loop + vertex 760.634 375.033 306.111 + vertex 758.566 385.664 306.487 + vertex 765.452 375.316 305.871 + endloop + endfacet + facet normal -0.0233208 0.0308352 -0.999252 + outer loop + vertex 760.634 375.033 306.111 + vertex 753.737 385.769 306.603 + vertex 758.566 385.664 306.487 + endloop + endfacet + facet normal -0.0254447 0.0294703 -0.999242 + outer loop + vertex 755.761 374.774 306.227 + vertex 753.737 385.769 306.603 + vertex 760.634 375.033 306.111 + endloop + endfacet + facet normal -0.0241958 0.0058055 -0.99969 + outer loop + vertex 763.389 364.636 305.984 + vertex 755.761 374.774 306.227 + vertex 760.634 375.033 306.111 + endloop + endfacet + facet normal -0.0491836 -0.000828695 -0.998789 + outer loop + vertex 763.389 364.636 305.984 + vertex 760.634 375.033 306.111 + vertex 768.329 365.287 305.74 + endloop + endfacet + facet normal -0.0257314 0.00464925 -0.999658 + outer loop + vertex 758.402 364.004 306.109 + vertex 755.761 374.774 306.227 + vertex 763.389 364.636 305.984 + endloop + endfacet + facet normal -0.0245906 -0.00435004 -0.999688 + outer loop + vertex 766.322 354.418 305.956 + vertex 758.402 364.004 306.109 + vertex 763.389 364.636 305.984 + endloop + endfacet + facet normal -0.0485185 -0.0112204 -0.998759 + outer loop + vertex 766.322 354.418 305.956 + vertex 763.389 364.636 305.984 + vertex 771.365 355.431 305.7 + endloop + endfacet + facet normal -0.0250218 -0.00470649 -0.999676 + outer loop + vertex 761.205 353.434 306.089 + vertex 758.402 364.004 306.109 + vertex 766.322 354.418 305.956 + endloop + endfacet + facet normal -0.0246157 -0.00681768 -0.999674 + outer loop + vertex 769.242 344.292 305.953 + vertex 761.205 353.434 306.089 + vertex 766.322 354.418 305.956 + endloop + endfacet + facet normal -0.0469829 -0.0132675 -0.998808 + outer loop + vertex 769.242 344.292 305.953 + vertex 766.322 354.418 305.956 + vertex 774.39 345.661 305.693 + endloop + endfacet + facet normal -0.0241316 -0.00639191 -0.999688 + outer loop + vertex 763.997 342.95 306.088 + vertex 761.205 353.434 306.089 + vertex 769.242 344.292 305.953 + endloop + endfacet + facet normal -0.0239562 -0.00707735 -0.999688 + outer loop + vertex 772.135 334.129 305.956 + vertex 763.997 342.95 306.088 + vertex 769.242 344.292 305.953 + endloop + endfacet + facet normal -0.0456589 -0.0132549 -0.998869 + outer loop + vertex 772.135 334.129 305.956 + vertex 769.242 344.292 305.953 + vertex 777.38 335.861 305.693 + endloop + endfacet + facet normal -0.0229269 -0.00612725 -0.999718 + outer loop + vertex 766.769 332.434 306.089 + vertex 763.997 342.95 306.088 + vertex 772.135 334.129 305.956 + endloop + endfacet + facet normal -0.0228841 -0.00626266 -0.999719 + outer loop + vertex 774.999 323.835 305.955 + vertex 766.769 332.434 306.089 + vertex 772.135 334.129 305.956 + endloop + endfacet + facet normal -0.0437746 -0.0120745 -0.998968 + outer loop + vertex 774.999 323.835 305.955 + vertex 772.135 334.129 305.956 + vertex 780.339 325.92 305.696 + endloop + endfacet + facet normal -0.0224019 -0.00580088 -0.999732 + outer loop + vertex 769.517 321.786 306.09 + vertex 766.769 332.434 306.089 + vertex 774.999 323.835 305.955 + endloop + endfacet + facet normal -0.0222428 -0.00622641 -0.999733 + outer loop + vertex 777.817 313.38 305.957 + vertex 769.517 321.786 306.09 + vertex 774.999 323.835 305.955 + endloop + endfacet + facet normal -0.0424672 -0.0116781 -0.99903 + outer loop + vertex 777.817 313.38 305.957 + vertex 774.999 323.835 305.955 + vertex 783.248 315.818 305.698 + endloop + endfacet + facet normal -0.0422806 -0.012094 -0.999033 + outer loop + vertex 786.073 305.596 305.702 + vertex 777.817 313.38 305.957 + vertex 783.248 315.818 305.698 + endloop + endfacet + facet normal -0.04132 -0.0110733 -0.999085 + outer loop + vertex 780.555 302.816 305.961 + vertex 777.817 313.38 305.957 + vertex 786.073 305.596 305.702 + endloop + endfacet + facet normal -0.0412813 -0.0111502 -0.999085 + outer loop + vertex 788.774 295.296 305.705 + vertex 780.555 302.816 305.961 + vertex 786.073 305.596 305.702 + endloop + endfacet + facet normal -0.0734239 -0.0195755 -0.997109 + outer loop + vertex 788.774 295.296 305.705 + vertex 786.073 305.596 305.702 + vertex 794.166 298.478 305.246 + endloop + endfacet + facet normal -0.040718 -0.0105336 -0.999115 + outer loop + vertex 783.171 292.19 305.966 + vertex 780.555 302.816 305.961 + vertex 788.774 295.296 305.705 + endloop + endfacet + facet normal -0.0410084 -0.0100092 -0.999109 + outer loop + vertex 791.306 284.884 305.706 + vertex 783.171 292.19 305.966 + vertex 788.774 295.296 305.705 + endloop + endfacet + facet normal -0.0749253 -0.0182584 -0.997022 + outer loop + vertex 791.306 284.884 305.706 + vertex 788.774 295.296 305.705 + vertex 796.761 288.376 305.232 + endloop + endfacet + facet normal -0.0404457 -0.0093815 -0.999138 + outer loop + vertex 785.618 281.483 305.968 + vertex 783.171 292.19 305.966 + vertex 791.306 284.884 305.706 + endloop + endfacet + facet normal -0.0412553 -0.00802587 -0.999116 + outer loop + vertex 793.611 274.255 305.696 + vertex 785.618 281.483 305.968 + vertex 791.306 284.884 305.706 + endloop + endfacet + facet normal -0.0758508 -0.0155303 -0.996998 + outer loop + vertex 793.611 274.255 305.696 + vertex 791.306 284.884 305.706 + vertex 799.143 278.015 305.217 + endloop + endfacet + facet normal -0.041244 -0.00801337 -0.999117 + outer loop + vertex 787.845 270.589 305.963 + vertex 785.618 281.483 305.968 + vertex 793.611 274.255 305.696 + endloop + endfacet + facet normal -0.0418872 -0.0070001 -0.999098 + outer loop + vertex 795.646 263.263 305.688 + vertex 787.845 270.589 305.963 + vertex 793.611 274.255 305.696 + endloop + endfacet + facet normal -0.078182 -0.0137211 -0.996845 + outer loop + vertex 795.646 263.263 305.688 + vertex 793.611 274.255 305.696 + vertex 801.24 267.262 305.194 + endloop + endfacet + facet normal -0.0416834 -0.00678271 -0.999108 + outer loop + vertex 789.806 259.363 305.958 + vertex 787.845 270.589 305.963 + vertex 795.646 263.263 305.688 + endloop + endfacet + facet normal -0.0412019 -0.00750453 -0.999123 + outer loop + vertex 797.398 251.833 305.701 + vertex 789.806 259.363 305.958 + vertex 795.646 263.263 305.688 + endloop + endfacet + facet normal -0.0772704 -0.0130299 -0.996925 + outer loop + vertex 797.398 251.833 305.701 + vertex 795.646 263.263 305.688 + vertex 803.058 256.068 305.207 + endloop + endfacet + facet normal -0.0408685 -0.0071678 -0.999139 + outer loop + vertex 791.497 247.718 305.972 + vertex 789.806 259.363 305.958 + vertex 797.398 251.833 305.701 + endloop + endfacet + facet normal -0.037865 -0.0114796 -0.999217 + outer loop + vertex 798.936 240.113 305.778 + vertex 791.497 247.718 305.972 + vertex 797.398 251.833 305.701 + endloop + endfacet + facet normal -0.0734603 -0.0161383 -0.997168 + outer loop + vertex 798.936 240.113 305.778 + vertex 797.398 251.833 305.701 + vertex 804.633 244.601 305.285 + endloop + endfacet + facet normal -0.037147 -0.0107764 -0.999252 + outer loop + vertex 792.989 235.801 306.045 + vertex 791.497 247.718 305.972 + vertex 798.936 240.113 305.778 + endloop + endfacet + facet normal -0.0310059 -0.0192508 -0.999334 + outer loop + vertex 800.34 228.603 305.956 + vertex 792.989 235.801 306.045 + vertex 798.936 240.113 305.778 + endloop + endfacet + facet normal -0.0637696 -0.0232214 -0.997694 + outer loop + vertex 800.34 228.603 305.956 + vertex 798.936 240.113 305.778 + vertex 806.101 233.327 305.478 + endloop + endfacet + facet normal -0.0292536 -0.0174601 -0.99942 + outer loop + vertex 794.343 224.142 306.209 + vertex 792.989 235.801 306.045 + vertex 800.34 228.603 305.956 + endloop + endfacet + facet normal -0.020579 -0.029118 -0.999364 + outer loop + vertex 801.518 218.154 306.236 + vertex 794.343 224.142 306.209 + vertex 800.34 228.603 305.956 + endloop + endfacet + facet normal -0.00945774 -0.0151678 -0.99984 + outer loop + vertex 794.343 224.142 306.209 + vertex 786.804 231.622 306.167 + vertex 792.989 235.801 306.045 + endloop + endfacet + facet normal -0.014682 -0.00743501 -0.999865 + outer loop + vertex 786.804 231.622 306.167 + vertex 785.366 243.702 306.098 + vertex 792.989 235.801 306.045 + endloop + endfacet + facet normal -0.00333637 -0.00608425 -0.999976 + outer loop + vertex 786.804 231.622 306.167 + vertex 779.019 239.779 306.143 + vertex 785.366 243.702 306.098 + endloop + endfacet + facet normal -0.00603701 -0.00171555 -0.99998 + outer loop + vertex 779.019 239.779 306.143 + vertex 777.463 251.801 306.132 + vertex 785.366 243.702 306.098 + endloop + endfacet + facet normal -0.0062985 -0.00197069 -0.999978 + outer loop + vertex 785.366 243.702 306.098 + vertex 777.463 251.801 306.132 + vertex 783.735 255.54 306.085 + endloop + endfacet + facet normal -0.0182204 -0.0036123 -0.999827 + outer loop + vertex 785.366 243.702 306.098 + vertex 783.735 255.54 306.085 + vertex 791.497 247.718 305.972 + endloop + endfacet + facet normal -0.00720783 -0.000445136 -0.999974 + outer loop + vertex 777.463 251.801 306.132 + vertex 775.667 263.474 306.14 + vertex 783.735 255.54 306.085 + endloop + endfacet + facet normal -0.0073388 -0.00057834 -0.999973 + outer loop + vertex 783.735 255.54 306.085 + vertex 775.667 263.474 306.14 + vertex 781.856 266.993 306.093 + endloop + endfacet + facet normal -0.0193975 -0.0025576 -0.999809 + outer loop + vertex 783.735 255.54 306.085 + vertex 781.856 266.993 306.093 + vertex 789.806 259.363 305.958 + endloop + endfacet + facet normal -0.00724503 -0.000743246 -0.999973 + outer loop + vertex 775.667 263.474 306.14 + vertex 773.628 274.884 306.146 + vertex 781.856 266.993 306.093 + endloop + endfacet + facet normal -0.0075955 -0.00110865 -0.999971 + outer loop + vertex 781.856 266.993 306.093 + vertex 773.628 274.884 306.146 + vertex 779.713 278.148 306.096 + endloop + endfacet + facet normal -0.0195137 -0.00339774 -0.999804 + outer loop + vertex 781.856 266.993 306.093 + vertex 779.713 278.148 306.096 + vertex 787.845 270.589 305.963 + endloop + endfacet + facet normal -0.00739264 -0.00148682 -0.999972 + outer loop + vertex 773.628 274.884 306.146 + vertex 771.387 286.174 306.146 + vertex 779.713 278.148 306.096 + endloop + endfacet + facet normal -0.00767901 -0.00178394 -0.999969 + outer loop + vertex 779.713 278.148 306.096 + vertex 771.387 286.174 306.146 + vertex 777.36 289.149 306.095 + endloop + endfacet + facet normal -0.0193372 -0.00427749 -0.999804 + outer loop + vertex 779.713 278.148 306.096 + vertex 777.36 289.149 306.095 + vertex 785.618 281.483 305.968 + endloop + endfacet + facet normal -0.00766411 -0.00181385 -0.999969 + outer loop + vertex 771.387 286.174 306.146 + vertex 768.998 297.428 306.144 + vertex 777.36 289.149 306.095 + endloop + endfacet + facet normal -0.00790459 -0.00205675 -0.999967 + outer loop + vertex 777.36 289.149 306.095 + vertex 768.998 297.428 306.144 + vertex 774.849 300.089 306.092 + endloop + endfacet + facet normal -0.0196082 -0.00474262 -0.999796 + outer loop + vertex 777.36 289.149 306.095 + vertex 774.849 300.089 306.092 + vertex 783.171 292.19 305.966 + endloop + endfacet + facet normal -0.00800112 -0.00184445 -0.999966 + outer loop + vertex 768.998 297.428 306.144 + vertex 766.503 308.648 306.143 + vertex 774.849 300.089 306.092 + endloop + endfacet + facet normal -0.00843015 -0.00226283 -0.999962 + outer loop + vertex 774.849 300.089 306.092 + vertex 766.503 308.648 306.143 + vertex 772.221 310.987 306.09 + endloop + endfacet + facet normal -0.0205064 -0.00517541 -0.999776 + outer loop + vertex 774.849 300.089 306.092 + vertex 772.221 310.987 306.09 + vertex 780.555 302.816 305.961 + endloop + endfacet + facet normal -0.00854284 -0.00198736 -0.999962 + outer loop + vertex 766.503 308.648 306.143 + vertex 763.938 319.783 306.143 + vertex 772.221 310.987 306.09 + endloop + endfacet + facet normal -0.00878724 -0.00221752 -0.999959 + outer loop + vertex 772.221 310.987 306.09 + vertex 763.938 319.783 306.143 + vertex 769.517 321.786 306.09 + endloop + endfacet + facet normal -0.00885575 -0.00202664 -0.999959 + outer loop + vertex 763.938 319.783 306.143 + vertex 761.331 330.769 306.144 + vertex 769.517 321.786 306.09 + endloop + endfacet + facet normal 0.000167845 0.000114837 -1 + outer loop + vertex 763.938 319.783 306.143 + vertex 755.886 329.16 306.143 + vertex 761.331 330.769 306.144 + endloop + endfacet + facet normal 0.000206127 -1.46841e-05 -1 + outer loop + vertex 755.886 329.16 306.143 + vertex 753.426 340.349 306.142 + vertex 761.331 330.769 306.144 + endloop + endfacet + facet normal 0.000249377 2.10001e-05 -1 + outer loop + vertex 761.331 330.769 306.144 + vertex 753.426 340.349 306.142 + vertex 758.703 341.628 306.143 + endloop + endfacet + facet normal -0.00931932 -0.00229448 -0.999954 + outer loop + vertex 761.331 330.769 306.144 + vertex 758.703 341.628 306.143 + vertex 766.769 332.434 306.089 + endloop + endfacet + facet normal 0.000223305 0.000128611 -1 + outer loop + vertex 753.426 340.349 306.142 + vertex 750.957 351.518 306.143 + vertex 758.703 341.628 306.143 + endloop + endfacet + facet normal 7.53808e-05 1.27538e-05 -1 + outer loop + vertex 758.703 341.628 306.143 + vertex 750.957 351.518 306.143 + vertex 756.06 352.46 306.143 + endloop + endfacet + facet normal -0.00978364 -0.00239224 -0.999949 + outer loop + vertex 758.703 341.628 306.143 + vertex 756.06 352.46 306.143 + vertex 763.997 342.95 306.088 + endloop + endfacet + facet normal -0.000180762 0.00139964 -0.999999 + outer loop + vertex 750.957 351.518 306.143 + vertex 748.489 362.777 306.159 + vertex 756.06 352.46 306.143 + endloop + endfacet + facet normal -7.212e-05 0.00147937 -0.999999 + outer loop + vertex 756.06 352.46 306.143 + vertex 748.489 362.777 306.159 + vertex 753.419 363.389 306.16 + endloop + endfacet + facet normal -0.0104072 -0.00101911 -0.999945 + outer loop + vertex 756.06 352.46 306.143 + vertex 753.419 363.389 306.16 + vertex 761.205 353.434 306.089 + endloop + endfacet + facet normal -0.00103241 0.00921884 -0.999957 + outer loop + vertex 748.489 362.777 306.159 + vertex 746.176 374.249 306.267 + vertex 753.419 363.389 306.16 + endloop + endfacet + facet normal -0.000227193 0.00975577 -0.999952 + outer loop + vertex 753.419 363.389 306.16 + vertex 746.176 374.249 306.267 + vertex 750.911 374.507 306.269 + endloop + endfacet + facet normal -0.0110366 0.00731758 -0.999912 + outer loop + vertex 753.419 363.389 306.16 + vertex 750.911 374.507 306.269 + vertex 758.402 364.004 306.109 + endloop + endfacet + facet normal -0.00137097 0.030804 -0.999525 + outer loop + vertex 746.176 374.249 306.267 + vertex 744.286 385.97 306.631 + vertex 750.911 374.507 306.269 + endloop + endfacet + facet normal 0.000870873 0.0320986 -0.999484 + outer loop + vertex 750.911 374.507 306.269 + vertex 744.286 385.97 306.631 + vertex 748.869 385.873 306.632 + endloop + endfacet + facet normal -0.0102056 0.0301088 -0.999495 + outer loop + vertex 750.911 374.507 306.269 + vertex 748.869 385.873 306.632 + vertex 755.761 374.774 306.227 + endloop + endfacet + facet normal 0.00773122 0.0322698 -0.999449 + outer loop + vertex 746.176 374.249 306.267 + vertex 739.917 386.061 306.6 + vertex 744.286 385.97 306.631 + endloop + endfacet + facet normal 0.00885872 0.0328665 -0.99942 + outer loop + vertex 741.579 373.998 306.218 + vertex 739.917 386.061 306.6 + vertex 746.176 374.249 306.267 + endloop + endfacet + facet normal 0.0257139 0.0351772 -0.99905 + outer loop + vertex 741.579 373.998 306.218 + vertex 735.788 386.146 306.497 + vertex 739.917 386.061 306.6 + endloop + endfacet + facet normal 0.0244299 0.0345664 -0.999104 + outer loop + vertex 737.117 373.763 306.101 + vertex 735.788 386.146 306.497 + vertex 741.579 373.998 306.218 + endloop + endfacet + facet normal 0.0255298 0.0139316 -0.999577 + outer loop + vertex 743.677 362.2 306.107 + vertex 737.117 373.763 306.101 + vertex 741.579 373.998 306.218 + endloop + endfacet + facet normal 0.00941539 0.0110686 -0.999894 + outer loop + vertex 743.677 362.2 306.107 + vertex 741.579 373.998 306.218 + vertex 748.489 362.777 306.159 + endloop + endfacet + facet normal 0.0241132 0.0131279 -0.999623 + outer loop + vertex 738.995 361.649 305.987 + vertex 737.117 373.763 306.101 + vertex 743.677 362.2 306.107 + endloop + endfacet + facet normal 0.0249023 0.00644084 -0.999669 + outer loop + vertex 745.94 350.609 306.089 + vertex 738.995 361.649 305.987 + vertex 743.677 362.2 306.107 + endloop + endfacet + facet normal 0.0100805 0.00354757 -0.999943 + outer loop + vertex 745.94 350.609 306.089 + vertex 743.677 362.2 306.107 + vertex 750.957 351.518 306.143 + endloop + endfacet + facet normal 0.0251137 0.00657384 -0.999663 + outer loop + vertex 741.048 349.763 305.961 + vertex 738.995 361.649 305.987 + vertex 745.94 350.609 306.089 + endloop + endfacet + facet normal 0.0253189 0.00538704 -0.999665 + outer loop + vertex 748.223 339.132 306.085 + vertex 741.048 349.763 305.961 + vertex 745.94 350.609 306.089 + endloop + endfacet + facet normal 0.0103784 0.00241535 -0.999943 + outer loop + vertex 748.223 339.132 306.085 + vertex 745.94 350.609 306.089 + vertex 753.426 340.349 306.142 + endloop + endfacet + facet normal 0.0247382 0.00499492 -0.999681 + outer loop + vertex 743.11 337.98 305.953 + vertex 741.048 349.763 305.961 + vertex 748.223 339.132 306.085 + endloop + endfacet + facet normal 0.0247915 0.00475834 -0.999681 + outer loop + vertex 750.491 327.626 306.087 + vertex 743.11 337.98 305.953 + vertex 748.223 339.132 306.085 + endloop + endfacet + facet normal 0.00988549 0.00181921 -0.999949 + outer loop + vertex 750.491 327.626 306.087 + vertex 748.223 339.132 306.085 + vertex 755.886 329.16 306.143 + endloop + endfacet + facet normal 0.00982981 0.00201509 -0.99995 + outer loop + vertex 758.327 317.844 306.144 + vertex 750.491 327.626 306.087 + vertex 755.886 329.16 306.143 + endloop + endfacet + facet normal 0.00918239 0.00149647 -0.999957 + outer loop + vertex 752.745 315.999 306.09 + vertex 750.491 327.626 306.087 + vertex 758.327 317.844 306.144 + endloop + endfacet + facet normal 0.00905963 0.00186789 -0.999957 + outer loop + vertex 760.732 306.391 306.144 + vertex 752.745 315.999 306.09 + vertex 758.327 317.844 306.144 + endloop + endfacet + facet normal -0.000163397 -6.89521e-05 -1 + outer loop + vertex 760.732 306.391 306.144 + vertex 758.327 317.844 306.144 + vertex 766.503 308.648 306.143 + endloop + endfacet + facet normal 0.00846447 0.00137314 -0.999963 + outer loop + vertex 754.967 304.236 306.093 + vertex 752.745 315.999 306.09 + vertex 760.732 306.391 306.144 + endloop + endfacet + facet normal 0.00837911 0.00160148 -0.999964 + outer loop + vertex 763.072 294.854 306.145 + vertex 754.967 304.236 306.093 + vertex 760.732 306.391 306.144 + endloop + endfacet + facet normal -0.000192828 -0.000136982 -1 + outer loop + vertex 763.072 294.854 306.145 + vertex 760.732 306.391 306.144 + vertex 768.998 297.428 306.144 + endloop + endfacet + facet normal 0.00823293 0.00147519 -0.999965 + outer loop + vertex 757.135 292.409 306.093 + vertex 754.967 304.236 306.093 + vertex 763.072 294.854 306.145 + endloop + endfacet + facet normal 0.00822484 0.00149483 -0.999965 + outer loop + vertex 765.316 283.302 306.147 + vertex 757.135 292.409 306.093 + vertex 763.072 294.854 306.145 + endloop + endfacet + facet normal -4.28355e-05 -0.000111349 -1 + outer loop + vertex 765.316 283.302 306.147 + vertex 763.072 294.854 306.145 + vertex 771.387 286.174 306.146 + endloop + endfacet + facet normal 0.00804606 0.00133421 -0.999967 + outer loop + vertex 759.215 280.574 306.094 + vertex 757.135 292.409 306.093 + vertex 765.316 283.302 306.147 + endloop + endfacet + facet normal 0.00795316 0.00154199 -0.999967 + outer loop + vertex 767.424 271.735 306.146 + vertex 759.215 280.574 306.094 + vertex 765.316 283.302 306.147 + endloop + endfacet + facet normal 6.06463e-05 0.000103397 -1 + outer loop + vertex 767.424 271.735 306.146 + vertex 765.316 283.302 306.147 + vertex 773.628 274.884 306.146 + endloop + endfacet + facet normal 0.0077485 0.00135188 -0.999969 + outer loop + vertex 761.173 268.74 306.093 + vertex 759.215 280.574 306.094 + vertex 767.424 271.735 306.146 + endloop + endfacet + facet normal 0.00752693 0.00181445 -0.99997 + outer loop + vertex 769.348 260.073 306.139 + vertex 761.173 268.74 306.093 + vertex 767.424 271.735 306.146 + endloop + endfacet + facet normal -0.000123586 0.000552721 -1 + outer loop + vertex 769.348 260.073 306.139 + vertex 767.424 271.735 306.146 + vertex 775.667 263.474 306.14 + endloop + endfacet + facet normal 0.00736957 0.00166601 -0.999971 + outer loop + vertex 762.965 256.838 306.086 + vertex 761.173 268.74 306.093 + vertex 769.348 260.073 306.139 + endloop + endfacet + facet normal 0.00732319 0.00175751 -0.999972 + outer loop + vertex 771.047 248.183 306.13 + vertex 762.965 256.838 306.086 + vertex 769.348 260.073 306.139 + endloop + endfacet + facet normal -0.00011129 0.000695075 -1 + outer loop + vertex 771.047 248.183 306.13 + vertex 769.348 260.073 306.139 + vertex 777.463 251.801 306.132 + endloop + endfacet + facet normal 0.00726017 0.00169866 -0.999972 + outer loop + vertex 764.552 244.738 306.077 + vertex 762.965 256.838 306.086 + vertex 771.047 248.183 306.13 + endloop + endfacet + facet normal 0.00810325 0.000109061 -0.999967 + outer loop + vertex 772.522 235.981 306.141 + vertex 764.552 244.738 306.077 + vertex 771.047 248.183 306.13 + endloop + endfacet + facet normal 0.000821711 -0.000770991 -0.999999 + outer loop + vertex 772.522 235.981 306.141 + vertex 771.047 248.183 306.13 + vertex 779.019 239.779 306.143 + endloop + endfacet + facet normal 0.00337131 -0.00513278 -0.999981 + outer loop + vertex 780.4 227.552 306.211 + vertex 772.522 235.981 306.141 + vertex 779.019 239.779 306.143 + endloop + endfacet + facet normal 0.00345674 -0.00505293 -0.999981 + outer loop + vertex 773.843 223.597 306.208 + vertex 772.522 235.981 306.141 + vertex 780.4 227.552 306.211 + endloop + endfacet + facet normal 0.00774297 -0.0121606 -0.999896 + outer loop + vertex 781.654 215.631 306.366 + vertex 773.843 223.597 306.208 + vertex 780.4 227.552 306.211 + endloop + endfacet + facet normal 0.00186637 -0.0127792 -0.999917 + outer loop + vertex 781.654 215.631 306.366 + vertex 780.4 227.552 306.211 + vertex 788.105 219.849 306.324 + endloop + endfacet + facet normal 0.00800302 -0.0221621 -0.999722 + outer loop + vertex 789.168 209.228 306.568 + vertex 781.654 215.631 306.366 + vertex 788.105 219.849 306.324 + endloop + endfacet + facet normal -0.000421011 -0.0230055 -0.999735 + outer loop + vertex 789.168 209.228 306.568 + vertex 788.105 219.849 306.324 + vertex 795.471 213.61 306.464 + endloop + endfacet + facet normal -0.00157062 -0.0243619 -0.999702 + outer loop + vertex 795.471 213.61 306.464 + vertex 788.105 219.849 306.324 + vertex 794.343 224.142 306.209 + endloop + endfacet + facet normal 0.00833676 -0.0217706 -0.999728 + outer loop + vertex 782.658 204.906 306.607 + vertex 781.654 215.631 306.366 + vertex 789.168 209.228 306.568 + endloop + endfacet + facet normal 0.0154183 -0.0324347 -0.999355 + outer loop + vertex 789.664 200.503 306.858 + vertex 782.658 204.906 306.607 + vertex 789.168 209.228 306.568 + endloop + endfacet + facet normal 0.0158503 -0.0317482 -0.99937 + outer loop + vertex 783.064 196.108 306.893 + vertex 782.658 204.906 306.607 + vertex 789.664 200.503 306.858 + endloop + endfacet + facet normal 0.0199104 -0.0315588 -0.999304 + outer loop + vertex 783.064 196.108 306.893 + vertex 776.029 200.736 306.607 + vertex 782.658 204.906 306.607 + endloop + endfacet + facet normal 0.0133882 -0.021192 -0.999686 + outer loop + vertex 776.029 200.736 306.607 + vertex 775.047 211.572 306.364 + vertex 782.658 204.906 306.607 + endloop + endfacet + facet normal 0.0196128 -0.0206254 -0.999595 + outer loop + vertex 776.029 200.736 306.607 + vertex 768.367 207.667 306.314 + vertex 775.047 211.572 306.364 + endloop + endfacet + facet normal 0.0143786 -0.0116696 -0.999829 + outer loop + vertex 768.367 207.667 306.314 + vertex 767.195 219.826 306.155 + vertex 775.047 211.572 306.364 + endloop + endfacet + facet normal 0.0145359 -0.01152 -0.999828 + outer loop + vertex 775.047 211.572 306.364 + vertex 767.195 219.826 306.155 + vertex 773.843 223.597 306.208 + endloop + endfacet + facet normal 0.0104626 -0.00433914 -0.999936 + outer loop + vertex 767.195 219.826 306.155 + vertex 765.941 232.352 306.088 + vertex 773.843 223.597 306.208 + endloop + endfacet + facet normal 0.021904 -0.00319308 -0.999755 + outer loop + vertex 767.195 219.826 306.155 + vertex 759.313 228.927 305.953 + vertex 765.941 232.352 306.088 + endloop + endfacet + facet normal 0.0196234 0.00122181 -0.999807 + outer loop + vertex 759.313 228.927 305.953 + vertex 758.024 241.491 305.943 + vertex 765.941 232.352 306.088 + endloop + endfacet + facet normal 0.0198403 0.00140976 -0.999802 + outer loop + vertex 765.941 232.352 306.088 + vertex 758.024 241.491 305.943 + vertex 764.552 244.738 306.077 + endloop + endfacet + facet normal 0.0189932 0.003113 -0.999815 + outer loop + vertex 758.024 241.491 305.943 + vertex 756.561 253.795 305.954 + vertex 764.552 244.738 306.077 + endloop + endfacet + facet normal 0.0368945 0.0052402 -0.999305 + outer loop + vertex 758.024 241.491 305.943 + vertex 750.158 250.941 305.702 + vertex 756.561 253.795 305.954 + endloop + endfacet + facet normal 0.0369495 0.00511663 -0.999304 + outer loop + vertex 750.158 250.941 305.702 + vertex 748.67 263.287 305.711 + vertex 756.561 253.795 305.954 + endloop + endfacet + facet normal 0.0377391 0.00577381 -0.999271 + outer loop + vertex 756.561 253.795 305.954 + vertex 748.67 263.287 305.711 + vertex 754.914 265.921 305.962 + endloop + endfacet + facet normal 0.0191621 0.0032514 -0.999811 + outer loop + vertex 756.561 253.795 305.954 + vertex 754.914 265.921 305.962 + vertex 762.965 256.838 306.086 + endloop + endfacet + facet normal 0.0379506 0.00527176 -0.999266 + outer loop + vertex 748.67 263.287 305.711 + vertex 747.051 275.594 305.714 + vertex 754.914 265.921 305.962 + endloop + endfacet + facet normal 0.0386113 0.00580958 -0.999237 + outer loop + vertex 754.914 265.921 305.962 + vertex 747.051 275.594 305.714 + vertex 753.12 278.001 305.963 + endloop + endfacet + facet normal 0.0196408 0.00299122 -0.999803 + outer loop + vertex 754.914 265.921 305.962 + vertex 753.12 278.001 305.963 + vertex 761.173 268.74 306.093 + endloop + endfacet + facet normal 0.0388661 0.00516656 -0.999231 + outer loop + vertex 747.051 275.594 305.714 + vertex 745.344 287.947 305.712 + vertex 753.12 278.001 305.963 + endloop + endfacet + facet normal 0.0403057 0.00629364 -0.999168 + outer loop + vertex 753.12 278.001 305.963 + vertex 745.344 287.947 305.712 + vertex 751.219 290.099 305.962 + endloop + endfacet + facet normal 0.0202171 0.00313674 -0.999791 + outer loop + vertex 753.12 278.001 305.963 + vertex 751.219 290.099 305.962 + vertex 759.215 280.574 306.094 + endloop + endfacet + facet normal 0.0405347 0.00566821 -0.999162 + outer loop + vertex 745.344 287.947 305.712 + vertex 743.576 300.318 305.71 + vertex 751.219 290.099 305.962 + endloop + endfacet + facet normal 0.0417685 0.00659236 -0.999106 + outer loop + vertex 751.219 290.099 305.962 + vertex 743.576 300.318 305.71 + vertex 749.245 302.213 305.96 + endloop + endfacet + facet normal 0.0208702 0.00318805 -0.999777 + outer loop + vertex 751.219 290.099 305.962 + vertex 749.245 302.213 305.96 + vertex 757.135 292.409 306.093 + endloop + endfacet + facet normal 0.0419777 0.00596579 -0.999101 + outer loop + vertex 743.576 300.318 305.71 + vertex 741.767 312.636 305.708 + vertex 749.245 302.213 305.96 + endloop + endfacet + facet normal 0.0434528 0.0070258 -0.999031 + outer loop + vertex 749.245 302.213 305.96 + vertex 741.767 312.636 305.708 + vertex 747.222 314.262 305.956 + endloop + endfacet + facet normal 0.0220311 0.00342849 -0.999751 + outer loop + vertex 749.245 302.213 305.96 + vertex 747.222 314.262 305.956 + vertex 754.967 304.236 306.093 + endloop + endfacet + facet normal 0.0436394 0.00639927 -0.999027 + outer loop + vertex 741.767 312.636 305.708 + vertex 739.937 324.83 305.706 + vertex 747.222 314.262 305.956 + endloop + endfacet + facet normal 0.0452344 0.00750057 -0.998948 + outer loop + vertex 747.222 314.262 305.956 + vertex 739.937 324.83 305.706 + vertex 745.171 326.18 305.953 + endloop + endfacet + facet normal 0.0230319 0.00367948 -0.999728 + outer loop + vertex 747.222 314.262 305.956 + vertex 745.171 326.18 305.953 + vertex 752.745 315.999 306.09 + endloop + endfacet + facet normal 0.0452876 0.00729425 -0.998947 + outer loop + vertex 739.937 324.83 305.706 + vertex 738.102 336.909 305.711 + vertex 745.171 326.18 305.953 + endloop + endfacet + facet normal 0.046547 0.00812556 -0.998883 + outer loop + vertex 745.171 326.18 305.953 + vertex 738.102 336.909 305.711 + vertex 743.11 337.98 305.953 + endloop + endfacet + facet normal 0.0464307 0.00866966 -0.998884 + outer loop + vertex 738.102 336.909 305.711 + vertex 736.267 348.964 305.73 + vertex 743.11 337.98 305.953 + endloop + endfacet + facet normal 0.078043 0.0134794 -0.996859 + outer loop + vertex 738.102 336.909 305.711 + vertex 731.607 348.227 305.355 + vertex 736.267 348.964 305.73 + endloop + endfacet + facet normal 0.0779491 0.0140718 -0.996858 + outer loop + vertex 731.607 348.227 305.355 + vertex 730.038 360.66 305.408 + vertex 736.267 348.964 305.73 + endloop + endfacet + facet normal 0.0795545 0.0149307 -0.996719 + outer loop + vertex 736.267 348.964 305.73 + vertex 730.038 360.66 305.408 + vertex 734.457 361.141 305.768 + endloop + endfacet + facet normal 0.0465023 0.0100242 -0.998868 + outer loop + vertex 736.267 348.964 305.73 + vertex 734.457 361.141 305.768 + vertex 741.048 349.763 305.961 + endloop + endfacet + facet normal 0.0792381 0.0178255 -0.996696 + outer loop + vertex 730.038 360.66 305.408 + vertex 728.634 373.332 305.523 + vertex 734.457 361.141 305.768 + endloop + endfacet + facet normal 0.0852524 0.0207091 -0.996144 + outer loop + vertex 734.457 361.141 305.768 + vertex 728.634 373.332 305.523 + vertex 732.798 373.536 305.884 + endloop + endfacet + facet normal 0.0465154 0.0155508 -0.998797 + outer loop + vertex 734.457 361.141 305.768 + vertex 732.798 373.536 305.884 + vertex 738.995 361.649 305.987 + endloop + endfacet + facet normal 0.0846217 0.0330921 -0.995863 + outer loop + vertex 728.634 373.332 305.523 + vertex 727.734 386.305 305.878 + vertex 732.798 373.536 305.884 + endloop + endfacet + facet normal 0.100384 0.0393442 -0.994171 + outer loop + vertex 732.798 373.536 305.884 + vertex 727.734 386.305 305.878 + vertex 731.559 386.23 306.261 + endloop + endfacet + facet normal 0.04842 0.0343903 -0.998235 + outer loop + vertex 732.798 373.536 305.884 + vertex 731.559 386.23 306.261 + vertex 737.117 373.763 306.101 + endloop + endfacet + facet normal 0.0756079 0.0120755 -0.997065 + outer loop + vertex 733.198 335.905 305.327 + vertex 731.607 348.227 305.355 + vertex 738.102 336.909 305.711 + endloop + endfacet + facet normal 0.0756427 0.0119052 -0.997064 + outer loop + vertex 739.937 324.83 305.706 + vertex 733.198 335.905 305.327 + vertex 738.102 336.909 305.711 + endloop + endfacet + facet normal 0.0729466 0.0102569 -0.997283 + outer loop + vertex 734.795 323.564 305.317 + vertex 733.198 335.905 305.327 + vertex 739.937 324.83 305.706 + endloop + endfacet + facet normal 0.11529 0.0157336 -0.993207 + outer loop + vertex 734.795 323.564 305.317 + vertex 728.42 334.964 304.757 + vertex 733.198 335.905 305.327 + endloop + endfacet + facet normal 0.115492 0.0147035 -0.9932 + outer loop + vertex 728.42 334.964 304.757 + vertex 727.069 347.533 304.786 + vertex 733.198 335.905 305.327 + endloop + endfacet + facet normal 0.121707 0.0180165 -0.992402 + outer loop + vertex 733.198 335.905 305.327 + vertex 727.069 347.533 304.786 + vertex 731.607 348.227 305.355 + endloop + endfacet + facet normal 0.121881 0.0168791 -0.992401 + outer loop + vertex 727.069 347.533 304.786 + vertex 725.747 360.217 304.84 + vertex 731.607 348.227 305.355 + endloop + endfacet + facet normal 0.129252 0.0205243 -0.991399 + outer loop + vertex 731.607 348.227 305.355 + vertex 725.747 360.217 304.84 + vertex 730.038 360.66 305.408 + endloop + endfacet + facet normal 0.129331 0.0197686 -0.991404 + outer loop + vertex 725.747 360.217 304.84 + vertex 724.572 373.14 304.944 + vertex 730.038 360.66 305.408 + endloop + endfacet + facet normal 0.139983 0.0244915 -0.989851 + outer loop + vertex 730.038 360.66 305.408 + vertex 724.572 373.14 304.944 + vertex 728.634 373.332 305.523 + endloop + endfacet + facet normal 0.139664 0.0308352 -0.989719 + outer loop + vertex 724.572 373.14 304.944 + vertex 723.833 386.378 305.252 + vertex 728.634 373.332 305.523 + endloop + endfacet + facet normal 0.158935 0.0379924 -0.986558 + outer loop + vertex 728.634 373.332 305.523 + vertex 723.833 386.378 305.252 + vertex 727.734 386.305 305.878 + endloop + endfacet + facet normal 0.110989 0.0133024 -0.993733 + outer loop + vertex 729.785 322.384 304.741 + vertex 728.42 334.964 304.757 + vertex 734.795 323.564 305.317 + endloop + endfacet + facet normal 0.110725 0.0144273 -0.993746 + outer loop + vertex 736.394 311.113 305.314 + vertex 729.785 322.384 304.741 + vertex 734.795 323.564 305.317 + endloop + endfacet + facet normal 0.0704379 0.00925316 -0.997473 + outer loop + vertex 736.394 311.113 305.314 + vertex 734.795 323.564 305.317 + vertex 741.767 312.636 305.708 + endloop + endfacet + facet normal 0.106457 0.0118992 -0.994246 + outer loop + vertex 731.149 309.692 304.735 + vertex 729.785 322.384 304.741 + vertex 736.394 311.113 305.314 + endloop + endfacet + facet normal 0.106052 0.0134061 -0.99427 + outer loop + vertex 737.979 298.543 305.314 + vertex 731.149 309.692 304.735 + vertex 736.394 311.113 305.314 + endloop + endfacet + facet normal 0.0679398 0.00860234 -0.997652 + outer loop + vertex 737.979 298.543 305.314 + vertex 736.394 311.113 305.314 + vertex 743.576 300.318 305.71 + endloop + endfacet + facet normal 0.102214 0.0110326 -0.994701 + outer loop + vertex 732.503 296.89 304.733 + vertex 731.149 309.692 304.735 + vertex 737.979 298.543 305.314 + endloop + endfacet + facet normal 0.101757 0.0125558 -0.99473 + outer loop + vertex 739.533 285.93 305.313 + vertex 732.503 296.89 304.733 + vertex 737.979 298.543 305.314 + endloop + endfacet + facet normal 0.0655712 0.00809778 -0.997815 + outer loop + vertex 739.533 285.93 305.313 + vertex 737.979 298.543 305.314 + vertex 745.344 287.947 305.712 + endloop + endfacet + facet normal 0.0987058 0.0105815 -0.99506 + outer loop + vertex 733.838 284.055 304.729 + vertex 732.503 296.89 304.733 + vertex 739.533 285.93 305.313 + endloop + endfacet + facet normal 0.0982959 0.0118346 -0.995087 + outer loop + vertex 741.039 273.353 305.313 + vertex 733.838 284.055 304.729 + vertex 739.533 285.93 305.313 + endloop + endfacet + facet normal 0.0637852 0.00770012 -0.997934 + outer loop + vertex 741.039 273.353 305.313 + vertex 739.533 285.93 305.313 + vertex 747.051 275.594 305.714 + endloop + endfacet + facet normal 0.095194 0.00972981 -0.995411 + outer loop + vertex 735.136 271.257 304.727 + vertex 733.838 284.055 304.729 + vertex 741.039 273.353 305.313 + endloop + endfacet + facet normal 0.0947211 0.0110708 -0.995442 + outer loop + vertex 742.471 260.82 305.309 + vertex 735.136 271.257 304.727 + vertex 741.039 273.353 305.313 + endloop + endfacet + facet normal 0.0616967 0.00729871 -0.998068 + outer loop + vertex 742.471 260.82 305.309 + vertex 741.039 273.353 305.313 + vertex 748.67 263.287 305.711 + endloop + endfacet + facet normal 0.092393 0.00942142 -0.995678 + outer loop + vertex 736.376 258.511 304.722 + vertex 735.136 271.257 304.727 + vertex 742.471 260.82 305.309 + endloop + endfacet + facet normal 0.0919938 0.0104817 -0.995704 + outer loop + vertex 743.793 248.263 305.299 + vertex 736.376 258.511 304.722 + vertex 742.471 260.82 305.309 + endloop + endfacet + facet normal 0.0602131 0.00713931 -0.99816 + outer loop + vertex 743.793 248.263 305.299 + vertex 742.471 260.82 305.309 + vertex 750.158 250.941 305.702 + endloop + endfacet + facet normal 0.0601675 0.00724804 -0.998162 + outer loop + vertex 751.485 238.434 305.692 + vertex 743.793 248.263 305.299 + vertex 750.158 250.941 305.702 + endloop + endfacet + facet normal 0.0586765 0.00607729 -0.998259 + outer loop + vertex 744.982 235.564 305.292 + vertex 743.793 248.263 305.299 + vertex 751.485 238.434 305.692 + endloop + endfacet + facet normal 0.0593605 0.00452307 -0.998226 + outer loop + vertex 752.671 225.69 305.704 + vertex 744.982 235.564 305.292 + vertex 751.485 238.434 305.692 + endloop + endfacet + facet normal 0.0362841 0.00237425 -0.999339 + outer loop + vertex 752.671 225.69 305.704 + vertex 751.485 238.434 305.692 + vertex 759.313 228.927 305.953 + endloop + endfacet + facet normal 0.03839 -0.00195309 -0.999261 + outer loop + vertex 760.502 216.241 306.024 + vertex 752.671 225.69 305.704 + vertex 759.313 228.927 305.953 + endloop + endfacet + facet normal 0.0373432 -0.00282194 -0.999299 + outer loop + vertex 753.804 212.882 305.783 + vertex 752.671 225.69 305.704 + vertex 760.502 216.241 306.024 + endloop + endfacet + facet normal 0.0408722 -0.00987316 -0.999116 + outer loop + vertex 761.647 203.987 306.192 + vertex 753.804 212.882 305.783 + vertex 760.502 216.241 306.024 + endloop + endfacet + facet normal 0.0244153 -0.011418 -0.999637 + outer loop + vertex 761.647 203.987 306.192 + vertex 760.502 216.241 306.024 + vertex 768.367 207.667 306.314 + endloop + endfacet + facet normal 0.0292653 -0.0202835 -0.999366 + outer loop + vertex 769.349 196.78 306.563 + vertex 761.647 203.987 306.192 + vertex 768.367 207.667 306.314 + endloop + endfacet + facet normal 0.0279427 -0.0216974 -0.999374 + outer loop + vertex 762.617 193.033 306.457 + vertex 761.647 203.987 306.192 + vertex 769.349 196.78 306.563 + endloop + endfacet + facet normal 0.0335517 -0.0317873 -0.998931 + outer loop + vertex 769.801 187.946 306.86 + vertex 762.617 193.033 306.457 + vertex 769.349 196.78 306.563 + endloop + endfacet + facet normal 0.0242068 -0.0322744 -0.999186 + outer loop + vertex 769.801 187.946 306.86 + vertex 769.349 196.78 306.563 + vertex 776.442 191.961 306.891 + endloop + endfacet + facet normal 0.031099 -0.043681 -0.998561 + outer loop + vertex 775.95 185.638 307.152 + vertex 769.801 187.946 306.86 + vertex 776.442 191.961 306.891 + endloop + endfacet + facet normal 0.0249724 -0.0311487 -0.999203 + outer loop + vertex 776.442 191.961 306.891 + vertex 769.349 196.78 306.563 + vertex 776.029 200.736 306.607 + endloop + endfacet + facet normal 0.0322467 -0.033629 -0.998914 + outer loop + vertex 762.999 184.128 306.769 + vertex 762.617 193.033 306.457 + vertex 769.801 187.946 306.86 + endloop + endfacet + facet normal 0.0394219 -0.0464291 -0.998143 + outer loop + vertex 769.218 181.054 307.157 + vertex 762.999 184.128 306.769 + vertex 769.801 187.946 306.86 + endloop + endfacet + facet normal 0.0470193 -0.0329757 -0.99835 + outer loop + vertex 762.999 184.128 306.769 + vertex 755.842 189.522 306.254 + vertex 762.617 193.033 306.457 + endloop + endfacet + facet normal 0.0415469 -0.0223868 -0.998886 + outer loop + vertex 755.842 189.522 306.254 + vertex 754.917 200.545 305.968 + vertex 762.617 193.033 306.457 + endloop + endfacet + facet normal 0.0637285 -0.0204957 -0.997757 + outer loop + vertex 755.842 189.522 306.254 + vertex 748.198 197.36 305.604 + vertex 754.917 200.545 305.968 + endloop + endfacet + facet normal 0.0593307 -0.0111718 -0.998176 + outer loop + vertex 748.198 197.36 305.604 + vertex 747.154 209.778 305.403 + vertex 754.917 200.545 305.968 + endloop + endfacet + facet normal 0.0613917 -0.0094324 -0.998069 + outer loop + vertex 754.917 200.545 305.968 + vertex 747.154 209.778 305.403 + vertex 753.804 212.882 305.783 + endloop + endfacet + facet normal 0.0580448 -0.00223354 -0.998311 + outer loop + vertex 747.154 209.778 305.403 + vertex 746.077 222.673 305.312 + vertex 753.804 212.882 305.783 + endloop + endfacet + facet normal 0.0879457 0.000278942 -0.996125 + outer loop + vertex 747.154 209.778 305.403 + vertex 739.606 219.918 304.74 + vertex 746.077 222.673 305.312 + endloop + endfacet + facet normal 0.0861554 0.0045151 -0.996271 + outer loop + vertex 739.606 219.918 304.74 + vertex 738.596 232.901 304.711 + vertex 746.077 222.673 305.312 + endloop + endfacet + facet normal 0.0881049 0.00595131 -0.996093 + outer loop + vertex 746.077 222.673 305.312 + vertex 738.596 232.901 304.711 + vertex 744.982 235.564 305.292 + endloop + endfacet + facet normal 0.087446 0.00754189 -0.996141 + outer loop + vertex 738.596 232.901 304.711 + vertex 737.53 245.754 304.715 + vertex 744.982 235.564 305.292 + endloop + endfacet + facet normal 0.13032 0.0110968 -0.99141 + outer loop + vertex 738.596 232.901 304.711 + vertex 731.429 243.427 303.887 + vertex 737.53 245.754 304.715 + endloop + endfacet + facet normal 0.130578 0.0104103 -0.991383 + outer loop + vertex 731.429 243.427 303.887 + vertex 730.431 256.345 303.891 + vertex 737.53 245.754 304.715 + endloop + endfacet + facet normal 0.133879 0.0126593 -0.990917 + outer loop + vertex 737.53 245.754 304.715 + vertex 730.431 256.345 303.891 + vertex 736.376 258.511 304.722 + endloop + endfacet + facet normal 0.134526 0.0108601 -0.990851 + outer loop + vertex 730.431 256.345 303.891 + vertex 729.386 269.298 303.891 + vertex 736.376 258.511 304.722 + endloop + endfacet + facet normal 0.139258 0.0139803 -0.990157 + outer loop + vertex 736.376 258.511 304.722 + vertex 729.386 269.298 303.891 + vertex 735.136 271.257 304.727 + endloop + endfacet + facet normal 0.139784 0.0124124 -0.990104 + outer loop + vertex 729.386 269.298 303.891 + vertex 728.294 282.301 303.9 + vertex 735.136 271.257 304.727 + endloop + endfacet + facet normal 0.143253 0.0146007 -0.989578 + outer loop + vertex 735.136 271.257 304.727 + vertex 728.294 282.301 303.9 + vertex 733.838 284.055 304.729 + endloop + endfacet + facet normal 0.143957 0.012341 -0.989507 + outer loop + vertex 728.294 282.301 303.9 + vertex 727.185 295.354 303.901 + vertex 733.838 284.055 304.729 + endloop + endfacet + facet normal 0.149893 0.0159049 -0.988574 + outer loop + vertex 733.838 284.055 304.729 + vertex 727.185 295.354 303.901 + vertex 732.503 296.89 304.733 + endloop + endfacet + facet normal 0.150539 0.0136363 -0.98851 + outer loop + vertex 727.185 295.354 303.901 + vertex 726.057 308.369 303.909 + vertex 732.503 296.89 304.733 + endloop + endfacet + facet normal 0.155897 0.0167084 -0.987632 + outer loop + vertex 732.503 296.89 304.733 + vertex 726.057 308.369 303.909 + vertex 731.149 309.692 304.735 + endloop + endfacet + facet normal 0.156582 0.0140286 -0.987565 + outer loop + vertex 726.057 308.369 303.909 + vertex 724.926 321.28 303.913 + vertex 731.149 309.692 304.735 + endloop + endfacet + facet normal 0.163951 0.0180754 -0.986303 + outer loop + vertex 731.149 309.692 304.735 + vertex 724.926 321.28 303.913 + vertex 729.785 322.384 304.741 + endloop + endfacet + facet normal 0.16469 0.014769 -0.986235 + outer loop + vertex 724.926 321.28 303.913 + vertex 723.8 334.09 303.917 + vertex 729.785 322.384 304.741 + endloop + endfacet + facet normal 0.175157 0.0202538 -0.984332 + outer loop + vertex 729.785 322.384 304.741 + vertex 723.8 334.09 303.917 + vertex 728.42 334.964 304.757 + endloop + endfacet + facet normal 0.175789 0.0168665 -0.984283 + outer loop + vertex 723.8 334.09 303.917 + vertex 722.676 346.885 303.936 + vertex 728.42 334.964 304.757 + endloop + endfacet + facet normal 0.186854 0.0223462 -0.982134 + outer loop + vertex 728.42 334.964 304.757 + vertex 722.676 346.885 303.936 + vertex 727.069 347.533 304.786 + endloop + endfacet + facet normal 0.187451 0.0182606 -0.982104 + outer loop + vertex 722.676 346.885 303.936 + vertex 721.593 359.804 303.969 + vertex 727.069 347.533 304.786 + endloop + endfacet + facet normal 0.202609 0.0252363 -0.978934 + outer loop + vertex 727.069 347.533 304.786 + vertex 721.593 359.804 303.969 + vertex 725.747 360.217 304.84 + endloop + endfacet + facet normal 0.202959 0.0217441 -0.978946 + outer loop + vertex 721.593 359.804 303.969 + vertex 720.674 372.961 304.071 + vertex 725.747 360.217 304.84 + endloop + endfacet + facet normal 0.217287 0.0276425 -0.975716 + outer loop + vertex 725.747 360.217 304.84 + vertex 720.674 372.961 304.071 + vertex 724.572 373.14 304.944 + endloop + endfacet + facet normal 0.21721 0.0291873 -0.975689 + outer loop + vertex 720.674 372.961 304.071 + vertex 720.06 386.446 304.337 + vertex 724.572 373.14 304.944 + endloop + endfacet + facet normal 0.236028 0.0357784 -0.971087 + outer loop + vertex 724.572 373.14 304.944 + vertex 720.06 386.446 304.337 + vertex 723.833 386.378 305.252 + endloop + endfacet + facet normal 0.127764 0.00932897 -0.991761 + outer loop + vertex 732.379 230.471 303.887 + vertex 731.429 243.427 303.887 + vertex 738.596 232.901 304.711 + endloop + endfacet + facet normal 0.128351 0.00780656 -0.991698 + outer loop + vertex 739.606 219.918 304.74 + vertex 732.379 230.471 303.887 + vertex 738.596 232.901 304.711 + endloop + endfacet + facet normal 0.127409 0.00715099 -0.991825 + outer loop + vertex 733.274 217.412 303.908 + vertex 732.379 230.471 303.887 + vertex 739.606 219.918 304.74 + endloop + endfacet + facet normal 0.129265 0.00238934 -0.991607 + outer loop + vertex 740.581 206.942 304.836 + vertex 733.274 217.412 303.908 + vertex 739.606 219.918 304.74 + endloop + endfacet + facet normal 0.128404 0.0017781 -0.99172 + outer loop + vertex 734.046 204.272 303.985 + vertex 733.274 217.412 303.908 + vertex 740.581 206.942 304.836 + endloop + endfacet + facet normal 0.131769 -0.00660667 -0.991258 + outer loop + vertex 741.442 194.405 305.034 + vertex 734.046 204.272 303.985 + vertex 740.581 206.942 304.836 + endloop + endfacet + facet normal 0.0883697 -0.00966143 -0.996041 + outer loop + vertex 741.442 194.405 305.034 + vertex 740.581 206.942 304.836 + vertex 748.198 197.36 305.604 + endloop + endfacet + facet normal 0.0928903 -0.0201048 -0.995473 + outer loop + vertex 748.993 186.297 305.902 + vertex 741.442 194.405 305.034 + vertex 748.198 197.36 305.604 + endloop + endfacet + facet normal 0.0897499 -0.0230538 -0.995697 + outer loop + vertex 741.962 183.063 305.343 + vertex 741.442 194.405 305.034 + vertex 748.993 186.297 305.902 + endloop + endfacet + facet normal 0.0958143 -0.0364036 -0.994733 + outer loop + vertex 749.197 177.234 306.253 + vertex 741.962 183.063 305.343 + vertex 748.993 186.297 305.902 + endloop + endfacet + facet normal 0.0649607 -0.0371928 -0.997194 + outer loop + vertex 749.197 177.234 306.253 + vertex 748.993 186.297 305.902 + vertex 756.155 180.661 306.579 + endloop + endfacet + facet normal 0.0673007 -0.0342139 -0.997146 + outer loop + vertex 756.155 180.661 306.579 + vertex 748.993 186.297 305.902 + vertex 755.842 189.522 306.254 + endloop + endfacet + facet normal 0.133024 -0.020938 -0.990892 + outer loop + vertex 741.962 183.063 305.343 + vertex 734.545 191.337 304.172 + vertex 741.442 194.405 305.034 + endloop + endfacet + facet normal 0.123773 -0.029371 -0.991876 + outer loop + vertex 734.756 179.279 304.556 + vertex 734.545 191.337 304.172 + vertex 741.962 183.063 305.343 + endloop + endfacet + facet normal 0.130496 -0.0424537 -0.99054 + outer loop + vertex 741.835 173.639 305.73 + vertex 734.756 179.279 304.556 + vertex 741.962 183.063 305.343 + endloop + endfacet + facet normal 0.128024 -0.00946286 -0.991726 + outer loop + vertex 734.545 191.337 304.172 + vertex 734.046 204.272 303.985 + vertex 741.442 194.405 305.034 + endloop + endfacet + facet normal 0.0864186 -0.00086648 -0.996259 + outer loop + vertex 740.581 206.942 304.836 + vertex 739.606 219.918 304.74 + vertex 747.154 209.778 305.403 + endloop + endfacet + facet normal 0.0897188 -0.00858021 -0.99593 + outer loop + vertex 748.198 197.36 305.604 + vertex 740.581 206.942 304.836 + vertex 747.154 209.778 305.403 + endloop + endfacet + facet normal 0.0617772 -0.0224053 -0.997838 + outer loop + vertex 748.993 186.297 305.902 + vertex 748.198 197.36 305.604 + vertex 755.842 189.522 306.254 + endloop + endfacet + facet normal 0.0454717 -0.0350294 -0.998351 + outer loop + vertex 756.155 180.661 306.579 + vertex 755.842 189.522 306.254 + vertex 762.999 184.128 306.769 + endloop + endfacet + facet normal 0.0522675 -0.0484924 -0.997455 + outer loop + vertex 762.057 177.659 307.034 + vertex 756.155 180.661 306.579 + vertex 762.999 184.128 306.769 + endloop + endfacet + facet normal 0.0516061 -0.0497883 -0.997426 + outer loop + vertex 755.515 174.302 306.863 + vertex 756.155 180.661 306.579 + vertex 762.057 177.659 307.034 + endloop + endfacet + facet normal 0.0435799 -0.0203001 -0.998844 + outer loop + vertex 762.617 193.033 306.457 + vertex 754.917 200.545 305.968 + vertex 761.647 203.987 306.192 + endloop + endfacet + facet normal 0.0390724 -0.0114627 -0.999171 + outer loop + vertex 754.917 200.545 305.968 + vertex 753.804 212.882 305.783 + vertex 761.647 203.987 306.192 + endloop + endfacet + facet normal 0.05982 -0.000827663 -0.998209 + outer loop + vertex 753.804 212.882 305.783 + vertex 746.077 222.673 305.312 + vertex 752.671 225.69 305.704 + endloop + endfacet + facet normal 0.0579003 0.00338215 -0.998317 + outer loop + vertex 746.077 222.673 305.312 + vertex 744.982 235.564 305.292 + vertex 752.671 225.69 305.704 + endloop + endfacet + facet normal 0.0893556 0.00894867 -0.99596 + outer loop + vertex 744.982 235.564 305.292 + vertex 737.53 245.754 304.715 + vertex 743.793 248.263 305.299 + endloop + endfacet + facet normal 0.0894762 0.00864583 -0.995951 + outer loop + vertex 737.53 245.754 304.715 + vertex 736.376 258.511 304.722 + vertex 743.793 248.263 305.299 + endloop + endfacet + facet normal 0.0728185 0.0107786 -0.997287 + outer loop + vertex 741.767 312.636 305.708 + vertex 734.795 323.564 305.317 + vertex 739.937 324.83 305.706 + endloop + endfacet + facet normal 0.0701958 0.0101095 -0.997482 + outer loop + vertex 743.576 300.318 305.71 + vertex 736.394 311.113 305.314 + vertex 741.767 312.636 305.708 + endloop + endfacet + facet normal 0.0676423 0.00954308 -0.997664 + outer loop + vertex 745.344 287.947 305.712 + vertex 737.979 298.543 305.314 + vertex 743.576 300.318 305.71 + endloop + endfacet + facet normal 0.0653209 0.00882133 -0.997825 + outer loop + vertex 747.051 275.594 305.714 + vertex 739.533 285.93 305.313 + vertex 745.344 287.947 305.712 + endloop + endfacet + facet normal 0.063441 0.00862588 -0.997948 + outer loop + vertex 748.67 263.287 305.711 + vertex 741.039 273.353 305.313 + vertex 747.051 275.594 305.714 + endloop + endfacet + facet normal 0.061394 0.00806123 -0.998081 + outer loop + vertex 750.158 250.941 305.702 + vertex 742.471 260.82 305.309 + vertex 748.67 263.287 305.711 + endloop + endfacet + facet normal 0.0362617 0.00471281 -0.999331 + outer loop + vertex 751.485 238.434 305.692 + vertex 750.158 250.941 305.702 + vertex 758.024 241.491 305.943 + endloop + endfacet + facet normal 0.0370564 0.00301094 -0.999309 + outer loop + vertex 759.313 228.927 305.953 + vertex 751.485 238.434 305.692 + vertex 758.024 241.491 305.943 + endloop + endfacet + facet normal 0.0215044 -0.00353932 -0.999762 + outer loop + vertex 760.502 216.241 306.024 + vertex 759.313 228.927 305.953 + vertex 767.195 219.826 306.155 + endloop + endfacet + facet normal 0.0252911 -0.0106142 -0.999624 + outer loop + vertex 768.367 207.667 306.314 + vertex 760.502 216.241 306.024 + vertex 767.195 219.826 306.155 + endloop + endfacet + facet normal 0.0190874 -0.0212062 -0.999593 + outer loop + vertex 769.349 196.78 306.563 + vertex 768.367 207.667 306.314 + vertex 776.029 200.736 306.607 + endloop + endfacet + facet normal 0.020025 -0.0313848 -0.999307 + outer loop + vertex 776.442 191.961 306.891 + vertex 776.029 200.736 306.607 + vertex 783.064 196.108 306.893 + endloop + endfacet + facet normal 0.0273695 -0.0431119 -0.998695 + outer loop + vertex 782.192 189.543 307.153 + vertex 776.442 191.961 306.891 + vertex 783.064 196.108 306.893 + endloop + endfacet + facet normal 0.0132881 -0.0213062 -0.999685 + outer loop + vertex 782.658 204.906 306.607 + vertex 775.047 211.572 306.364 + vertex 781.654 215.631 306.366 + endloop + endfacet + facet normal 0.00151407 -0.0131316 -0.999913 + outer loop + vertex 788.105 219.849 306.324 + vertex 780.4 227.552 306.211 + vertex 786.804 231.622 306.167 + endloop + endfacet + facet normal 0.00769709 -0.0122055 -0.999896 + outer loop + vertex 775.047 211.572 306.364 + vertex 773.843 223.597 306.208 + vertex 781.654 215.631 306.366 + endloop + endfacet + facet normal 0.010505 -0.00430084 -0.999936 + outer loop + vertex 773.843 223.597 306.208 + vertex 765.941 232.352 306.088 + vertex 772.522 235.981 306.141 + endloop + endfacet + facet normal 0.00808351 9.1091e-05 -0.999967 + outer loop + vertex 765.941 232.352 306.088 + vertex 764.552 244.738 306.077 + vertex 772.522 235.981 306.141 + endloop + endfacet + facet normal 0.0191585 0.0032589 -0.999811 + outer loop + vertex 764.552 244.738 306.077 + vertex 756.561 253.795 305.954 + vertex 762.965 256.838 306.086 + endloop + endfacet + facet normal 0.0194204 0.00348044 -0.999805 + outer loop + vertex 762.965 256.838 306.086 + vertex 754.914 265.921 305.962 + vertex 761.173 268.74 306.093 + endloop + endfacet + facet normal 0.0201073 0.00339704 -0.999792 + outer loop + vertex 761.173 268.74 306.093 + vertex 753.12 278.001 305.963 + vertex 759.215 280.574 306.094 + endloop + endfacet + facet normal 0.0207241 0.00356248 -0.999779 + outer loop + vertex 759.215 280.574 306.094 + vertex 751.219 290.099 305.962 + vertex 757.135 292.409 306.093 + endloop + endfacet + facet normal 0.0218402 0.0039688 -0.999754 + outer loop + vertex 757.135 292.409 306.093 + vertex 749.245 302.213 305.96 + vertex 754.967 304.236 306.093 + endloop + endfacet + facet normal 0.0228998 0.00409983 -0.999729 + outer loop + vertex 754.967 304.236 306.093 + vertex 747.222 314.262 305.956 + vertex 752.745 315.999 306.09 + endloop + endfacet + facet normal 0.0239433 0.00435782 -0.999704 + outer loop + vertex 752.745 315.999 306.09 + vertex 745.171 326.18 305.953 + vertex 750.491 327.626 306.087 + endloop + endfacet + facet normal 0.0239899 0.00418658 -0.999703 + outer loop + vertex 745.171 326.18 305.953 + vertex 743.11 337.98 305.953 + vertex 750.491 327.626 306.087 + endloop + endfacet + facet normal 0.0467004 0.00883803 -0.99887 + outer loop + vertex 743.11 337.98 305.953 + vertex 736.267 348.964 305.73 + vertex 741.048 349.763 305.961 + endloop + endfacet + facet normal 0.0470975 0.0103696 -0.998836 + outer loop + vertex 741.048 349.763 305.961 + vertex 734.457 361.141 305.768 + vertex 738.995 361.649 305.987 + endloop + endfacet + facet normal 0.0493513 0.0170305 -0.998636 + outer loop + vertex 738.995 361.649 305.987 + vertex 732.798 373.536 305.884 + vertex 737.117 373.763 306.101 + endloop + endfacet + facet normal 0.0564341 0.0379565 -0.997685 + outer loop + vertex 737.117 373.763 306.101 + vertex 731.559 386.23 306.261 + vertex 735.788 386.146 306.497 + endloop + endfacet + facet normal 0.010034 0.0114495 -0.999884 + outer loop + vertex 748.489 362.777 306.159 + vertex 741.579 373.998 306.218 + vertex 746.176 374.249 306.267 + endloop + endfacet + facet normal 0.0102991 0.00369652 -0.99994 + outer loop + vertex 750.957 351.518 306.143 + vertex 743.677 362.2 306.107 + vertex 748.489 362.777 306.159 + endloop + endfacet + facet normal 0.0102966 0.00235561 -0.999944 + outer loop + vertex 753.426 340.349 306.142 + vertex 745.94 350.609 306.089 + vertex 750.957 351.518 306.143 + endloop + endfacet + facet normal 0.0104215 0.00223116 -0.999943 + outer loop + vertex 755.886 329.16 306.143 + vertex 748.223 339.132 306.085 + vertex 753.426 340.349 306.142 + endloop + endfacet + facet normal -0.000118019 -0.000130635 -1 + outer loop + vertex 758.327 317.844 306.144 + vertex 755.886 329.16 306.143 + vertex 763.938 319.783 306.143 + endloop + endfacet + facet normal -0.000144994 -5.25895e-05 -1 + outer loop + vertex 766.503 308.648 306.143 + vertex 758.327 317.844 306.144 + vertex 763.938 319.783 306.143 + endloop + endfacet + facet normal -0.000151644 -9.89988e-05 -1 + outer loop + vertex 768.998 297.428 306.144 + vertex 760.732 306.391 306.144 + vertex 766.503 308.648 306.143 + endloop + endfacet + facet normal -0.000156619 -0.000220346 -1 + outer loop + vertex 771.387 286.174 306.146 + vertex 763.072 294.854 306.145 + vertex 768.998 297.428 306.144 + endloop + endfacet + facet normal -7.91273e-05 -3.46343e-05 -1 + outer loop + vertex 773.628 274.884 306.146 + vertex 765.316 283.302 306.147 + vertex 771.387 286.174 306.146 + endloop + endfacet + facet normal -0.000152704 0.000523669 -1 + outer loop + vertex 775.667 263.474 306.14 + vertex 767.424 271.735 306.146 + vertex 773.628 274.884 306.146 + endloop + endfacet + facet normal -0.000169475 0.000637992 -1 + outer loop + vertex 777.463 251.801 306.132 + vertex 769.348 260.073 306.139 + vertex 775.667 263.474 306.14 + endloop + endfacet + facet normal 0.000752408 -0.000836729 -0.999999 + outer loop + vertex 779.019 239.779 306.143 + vertex 771.047 248.183 306.13 + vertex 777.463 251.801 306.132 + endloop + endfacet + facet normal -0.00310558 -0.00586397 -0.999978 + outer loop + vertex 780.4 227.552 306.211 + vertex 779.019 239.779 306.143 + vertex 786.804 231.622 306.167 + endloop + endfacet + facet normal -0.00853842 -0.0142416 -0.999862 + outer loop + vertex 788.105 219.849 306.324 + vertex 786.804 231.622 306.167 + vertex 794.343 224.142 306.209 + endloop + endfacet + facet normal -0.0153163 -0.00804708 -0.99985 + outer loop + vertex 792.989 235.801 306.045 + vertex 785.366 243.702 306.098 + vertex 791.497 247.718 305.972 + endloop + endfacet + facet normal -0.0185362 -0.00392575 -0.99982 + outer loop + vertex 791.497 247.718 305.972 + vertex 783.735 255.54 306.085 + vertex 789.806 259.363 305.958 + endloop + endfacet + facet normal -0.0197792 -0.00295551 -0.9998 + outer loop + vertex 789.806 259.363 305.958 + vertex 781.856 266.993 306.093 + vertex 787.845 270.589 305.963 + endloop + endfacet + facet normal -0.0197129 -0.00361206 -0.999799 + outer loop + vertex 787.845 270.589 305.963 + vertex 779.713 278.148 306.096 + vertex 785.618 281.483 305.968 + endloop + endfacet + facet normal -0.0196661 -0.00463193 -0.999796 + outer loop + vertex 785.618 281.483 305.968 + vertex 777.36 289.149 306.095 + vertex 783.171 292.19 305.966 + endloop + endfacet + facet normal -0.0203431 -0.00551715 -0.999778 + outer loop + vertex 783.171 292.19 305.966 + vertex 774.849 300.089 306.092 + vertex 780.555 302.816 305.961 + endloop + endfacet + facet normal -0.0211698 -0.00585229 -0.999759 + outer loop + vertex 780.555 302.816 305.961 + vertex 772.221 310.987 306.09 + vertex 777.817 313.38 305.957 + endloop + endfacet + facet normal -0.0213759 -0.00537008 -0.999757 + outer loop + vertex 772.221 310.987 306.09 + vertex 769.517 321.786 306.09 + vertex 777.817 313.38 305.957 + endloop + endfacet + facet normal -0.00928231 -0.00241537 -0.999954 + outer loop + vertex 769.517 321.786 306.09 + vertex 761.331 330.769 306.144 + vertex 766.769 332.434 306.089 + endloop + endfacet + facet normal -0.00972023 -0.00264624 -0.999949 + outer loop + vertex 766.769 332.434 306.089 + vertex 758.703 341.628 306.143 + vertex 763.997 342.95 306.088 + endloop + endfacet + facet normal -0.0100977 -0.00265433 -0.999945 + outer loop + vertex 763.997 342.95 306.088 + vertex 756.06 352.46 306.143 + vertex 761.205 353.434 306.089 + endloop + endfacet + facet normal -0.0100432 -0.000734359 -0.999949 + outer loop + vertex 761.205 353.434 306.089 + vertex 753.419 363.389 306.16 + vertex 758.402 364.004 306.109 + endloop + endfacet + facet normal -0.00903246 0.00874717 -0.999921 + outer loop + vertex 758.402 364.004 306.109 + vertex 750.911 374.507 306.269 + vertex 755.761 374.774 306.227 + endloop + endfacet + facet normal -0.00522474 0.0331996 -0.999435 + outer loop + vertex 755.761 374.774 306.227 + vertex 748.869 385.873 306.632 + vertex 753.737 385.769 306.603 + endloop + endfacet + facet normal -0.0496088 -0.00116521 -0.998768 + outer loop + vertex 768.329 365.287 305.74 + vertex 760.634 375.033 306.111 + vertex 765.452 375.316 305.871 + endloop + endfacet + facet normal -0.0478874 -0.0106725 -0.998796 + outer loop + vertex 771.365 355.431 305.7 + vertex 763.389 364.636 305.984 + vertex 768.329 365.287 305.74 + endloop + endfacet + facet normal -0.0479311 -0.0141427 -0.998751 + outer loop + vertex 774.39 345.661 305.693 + vertex 766.322 354.418 305.956 + vertex 771.365 355.431 305.7 + endloop + endfacet + facet normal -0.0467147 -0.0142759 -0.998806 + outer loop + vertex 777.38 335.861 305.693 + vertex 769.242 344.292 305.953 + vertex 774.39 345.661 305.693 + endloop + endfacet + facet normal -0.0454836 -0.0137856 -0.99887 + outer loop + vertex 780.339 325.92 305.696 + vertex 772.135 334.129 305.956 + vertex 777.38 335.861 305.693 + endloop + endfacet + facet normal -0.0435099 -0.0127527 -0.998972 + outer loop + vertex 783.248 315.818 305.698 + vertex 774.999 323.835 305.955 + vertex 780.339 325.92 305.696 + endloop + endfacet + facet normal -0.0738007 -0.0208068 -0.997056 + outer loop + vertex 786.073 305.596 305.702 + vertex 783.248 315.818 305.698 + vertex 791.395 308.444 305.249 + endloop + endfacet + facet normal -0.0740661 -0.0203094 -0.997047 + outer loop + vertex 794.166 298.478 305.246 + vertex 786.073 305.596 305.702 + vertex 791.395 308.444 305.249 + endloop + endfacet + facet normal -0.0744932 -0.0177569 -0.997063 + outer loop + vertex 796.761 288.376 305.232 + vertex 788.774 295.296 305.705 + vertex 794.166 298.478 305.246 + endloop + endfacet + facet normal -0.0763205 -0.0160692 -0.996954 + outer loop + vertex 799.143 278.015 305.217 + vertex 791.306 284.884 305.706 + vertex 796.761 288.376 305.232 + endloop + endfacet + facet normal -0.0775464 -0.0130235 -0.996904 + outer loop + vertex 801.24 267.262 305.194 + vertex 793.611 274.255 305.696 + vertex 799.143 278.015 305.217 + endloop + endfacet + facet normal -0.0780782 -0.013867 -0.996851 + outer loop + vertex 803.058 256.068 305.207 + vertex 795.646 263.263 305.688 + vertex 801.24 267.262 305.194 + endloop + endfacet + facet normal -0.0743156 -0.0169985 -0.99709 + outer loop + vertex 804.633 244.601 305.285 + vertex 797.398 251.833 305.701 + vertex 803.058 256.068 305.207 + endloop + endfacet + facet normal -0.0660242 -0.0256114 -0.997489 + outer loop + vertex 806.101 233.327 305.478 + vertex 798.936 240.113 305.778 + vertex 804.633 244.601 305.285 + endloop + endfacet + facet normal -0.0524624 -0.0370359 -0.997936 + outer loop + vertex 807.384 222.991 305.794 + vertex 800.34 228.603 305.956 + vertex 806.101 233.327 305.478 + endloop + endfacet + facet normal -0.0486609 -0.0322543 -0.998294 + outer loop + vertex 801.518 218.154 306.236 + vertex 800.34 228.603 305.956 + vertex 807.384 222.991 305.794 + endloop + endfacet + facet normal -0.0180806 -0.0261252 -0.999495 + outer loop + vertex 795.471 213.61 306.464 + vertex 794.343 224.142 306.209 + vertex 801.518 218.154 306.236 + endloop + endfacet + facet normal 0.00781939 -0.0348495 -0.999362 + outer loop + vertex 796.065 204.967 306.77 + vertex 789.168 209.228 306.568 + vertex 795.471 213.61 306.464 + endloop + endfacet + facet normal 0.00908955 -0.0327965 -0.999421 + outer loop + vertex 789.664 200.503 306.858 + vertex 789.168 209.228 306.568 + vertex 796.065 204.967 306.77 + endloop + endfacet + facet normal 0.0248195 -0.0452119 -0.998669 + outer loop + vertex 789.205 193.633 307.158 + vertex 783.064 196.108 306.893 + vertex 789.664 200.503 306.858 + endloop + endfacet + facet normal 0.0633608 -0.100517 -0.992916 + outer loop + vertex 790.694 191.258 307.377 + vertex 794.397 194.618 307.273 + vertex 794.841 192.701 307.495 + endloop + endfacet + facet normal 0.0667972 -0.110497 -0.991629 + outer loop + vertex 794.841 192.701 307.495 + vertex 787.444 187.383 307.59 + vertex 790.694 191.258 307.377 + endloop + endfacet + facet normal 0.0951207 -0.149755 -0.984137 + outer loop + vertex 794.841 192.701 307.495 + vertex 789.77 186.635 307.928 + vertex 787.444 187.383 307.59 + endloop + endfacet + facet normal 0.0949728 -0.150191 -0.984085 + outer loop + vertex 789.77 186.635 307.928 + vertex 782.073 181.634 307.949 + vertex 787.444 187.383 307.59 + endloop + endfacet + facet normal 0.091396 -0.146902 -0.98492 + outer loop + vertex 787.444 187.383 307.59 + vertex 782.073 181.634 307.949 + vertex 779.799 182.751 307.571 + endloop + endfacet + facet normal 0.0672215 -0.106969 -0.991987 + outer loop + vertex 787.444 187.383 307.59 + vertex 779.799 182.751 307.571 + vertex 785.389 188.159 307.367 + endloop + endfacet + facet normal 0.0912455 -0.147198 -0.984889 + outer loop + vertex 782.073 181.634 307.949 + vertex 774.183 176.816 307.938 + vertex 779.799 182.751 307.571 + endloop + endfacet + facet normal 0.0952202 -0.150901 -0.983952 + outer loop + vertex 779.799 182.751 307.571 + vertex 774.183 176.816 307.938 + vertex 771.806 177.606 307.587 + endloop + endfacet + facet normal 0.0669708 -0.107035 -0.991997 + outer loop + vertex 779.799 182.751 307.571 + vertex 771.806 177.606 307.587 + vertex 774.923 181.545 307.372 + endloop + endfacet + facet normal 0.094316 -0.153484 -0.98364 + outer loop + vertex 774.183 176.816 307.938 + vertex 766.037 172.122 307.889 + vertex 771.806 177.606 307.587 + endloop + endfacet + facet normal 0.0959603 -0.155189 -0.983213 + outer loop + vertex 771.806 177.606 307.587 + vertex 766.037 172.122 307.889 + vertex 764.03 173.432 307.487 + endloop + endfacet + facet normal 0.0729911 -0.112221 -0.990999 + outer loop + vertex 771.806 177.606 307.587 + vertex 764.03 173.432 307.487 + vertex 769.578 177.917 307.387 + endloop + endfacet + facet normal 0.0974064 -0.153033 -0.983409 + outer loop + vertex 766.037 172.122 307.889 + vertex 757.602 167.558 307.764 + vertex 764.03 173.432 307.487 + endloop + endfacet + facet normal 0.105288 -0.161555 -0.981231 + outer loop + vertex 764.03 173.432 307.487 + vertex 757.602 167.558 307.764 + vertex 754.907 168.574 307.308 + endloop + endfacet + facet normal 0.107153 -0.15686 -0.981791 + outer loop + vertex 757.602 167.558 307.764 + vertex 749.04 163.118 307.539 + vertex 754.907 168.574 307.308 + endloop + endfacet + facet normal 0.127384 -0.178357 -0.975685 + outer loop + vertex 754.907 168.574 307.308 + vertex 749.04 163.118 307.539 + vertex 746.459 164.097 307.023 + endloop + endfacet + facet normal 0.129249 -0.17375 -0.976271 + outer loop + vertex 749.04 163.118 307.539 + vertex 740.456 158.917 307.15 + vertex 746.459 164.097 307.023 + endloop + endfacet + facet normal 0.15384 -0.202026 -0.967222 + outer loop + vertex 746.459 164.097 307.023 + vertex 740.456 158.917 307.15 + vertex 737.847 160.294 306.447 + endloop + endfacet + facet normal 0.158155 -0.194304 -0.968108 + outer loop + vertex 740.456 158.917 307.15 + vertex 731.509 154.748 306.525 + vertex 737.847 160.294 306.447 + endloop + endfacet + facet normal 0.197559 -0.23909 -0.950687 + outer loop + vertex 737.847 160.294 306.447 + vertex 731.509 154.748 306.525 + vertex 728.736 155.896 305.66 + endloop + endfacet + facet normal 0.199395 -0.235114 -0.951295 + outer loop + vertex 731.509 154.748 306.525 + vertex 721.717 150.471 305.53 + vertex 728.736 155.896 305.66 + endloop + endfacet + facet normal 0.0921888 -0.14735 -0.984779 + outer loop + vertex 797.33 191.882 307.851 + vertex 789.77 186.635 307.928 + vertex 794.841 192.701 307.495 + endloop + endfacet + facet normal 0.0904697 -0.152317 -0.984182 + outer loop + vertex 802.448 198.221 307.34 + vertex 797.33 191.882 307.851 + vertex 794.841 192.701 307.495 + endloop + endfacet + facet normal 0.0896048 -0.151633 -0.984367 + outer loop + vertex 804.57 197.178 307.694 + vertex 797.33 191.882 307.851 + vertex 802.448 198.221 307.34 + endloop + endfacet + facet normal 0.0837957 -0.16301 -0.983059 + outer loop + vertex 809.125 203.236 307.078 + vertex 804.57 197.178 307.694 + vertex 802.448 198.221 307.34 + endloop + endfacet + facet normal 0.0883173 -0.166314 -0.98211 + outer loop + vertex 811.524 202.638 307.395 + vertex 804.57 197.178 307.694 + vertex 809.125 203.236 307.078 + endloop + endfacet + facet normal 0.0829652 -0.18614 -0.979014 + outer loop + vertex 815.976 209.208 306.523 + vertex 811.524 202.638 307.395 + vertex 809.125 203.236 307.078 + endloop + endfacet + facet normal 0.0891487 -0.190155 -0.977698 + outer loop + vertex 818.253 208.24 306.919 + vertex 811.524 202.638 307.395 + vertex 815.976 209.208 306.523 + endloop + endfacet + facet normal 0.0769121 -0.217077 -0.97312 + outer loop + vertex 822.231 214.413 305.856 + vertex 818.253 208.24 306.919 + vertex 815.976 209.208 306.523 + endloop + endfacet + facet normal 0.0937731 -0.227287 -0.969302 + outer loop + vertex 824.793 213.95 306.213 + vertex 818.253 208.24 306.919 + vertex 822.231 214.413 305.856 + endloop + endfacet + facet normal 0.0660845 -0.109906 -0.991743 + outer loop + vertex 785.389 188.159 307.367 + vertex 790.694 191.258 307.377 + vertex 787.444 187.383 307.59 + endloop + endfacet + facet normal 0.0257547 -0.0428997 -0.998747 + outer loop + vertex 782.192 189.543 307.153 + vertex 783.064 196.108 306.893 + vertex 789.205 193.633 307.158 + endloop + endfacet + facet normal 0.0628382 -0.102466 -0.99275 + outer loop + vertex 780.145 185.267 307.333 + vertex 785.389 188.159 307.367 + vertex 779.799 182.751 307.571 + endloop + endfacet + facet normal 0.0272535 -0.0433868 -0.998687 + outer loop + vertex 775.95 185.638 307.152 + vertex 776.442 191.961 306.891 + vertex 782.192 189.543 307.153 + endloop + endfacet + facet normal 0.0659614 -0.102872 -0.992505 + outer loop + vertex 774.923 181.545 307.372 + vertex 780.145 185.267 307.333 + vertex 779.799 182.751 307.571 + endloop + endfacet + facet normal 0.0303469 -0.0456763 -0.998495 + outer loop + vertex 769.218 181.054 307.157 + vertex 769.801 187.946 306.86 + vertex 775.95 185.638 307.152 + endloop + endfacet + facet normal 0.0730539 -0.111798 -0.991042 + outer loop + vertex 769.578 177.917 307.387 + vertex 774.923 181.545 307.372 + vertex 771.806 177.606 307.587 + endloop + endfacet + facet normal 0.0614804 -0.0980319 -0.993282 + outer loop + vertex 765.5 176.371 307.287 + vertex 769.578 177.917 307.387 + vertex 764.03 173.432 307.487 + endloop + endfacet + facet normal 0.0393198 -0.046635 -0.998138 + outer loop + vertex 762.057 177.659 307.034 + vertex 762.999 184.128 306.769 + vertex 769.218 181.054 307.157 + endloop + endfacet + facet normal 0.0709096 -0.102674 -0.992184 + outer loop + vertex 759.895 173.201 307.215 + vertex 765.5 176.371 307.287 + vertex 764.03 173.432 307.487 + endloop + endfacet + facet normal 0.0720963 -0.0517909 -0.996052 + outer loop + vertex 755.515 174.302 306.863 + vertex 749.197 177.234 306.253 + vertex 756.155 180.661 306.579 + endloop + endfacet + facet normal 0.0912452 -0.0421064 -0.994938 + outer loop + vertex 741.835 173.639 305.73 + vertex 741.962 183.063 305.343 + vertex 749.197 177.234 306.253 + endloop + endfacet + facet normal 0.120725 -0.0548488 -0.99117 + outer loop + vertex 734.281 169.179 305.057 + vertex 734.756 179.279 304.556 + vertex 741.835 173.639 305.73 + endloop + endfacet + facet normal 0.172437 -0.0993252 -0.98 + outer loop + vertex 725.601 161.079 304.353 + vertex 726.184 166.18 303.939 + vertex 729.871 163.878 304.821 + endloop + endfacet + facet normal 0.210668 -0.103058 -0.97211 + outer loop + vertex 725.601 161.079 304.353 + vertex 722.738 163.582 303.468 + vertex 726.184 166.18 303.939 + endloop + endfacet + facet normal 0.205057 -0.0952527 -0.974104 + outer loop + vertex 722.738 163.582 303.468 + vertex 722.059 170.825 302.616 + vertex 726.184 166.18 303.939 + endloop + endfacet + facet normal 0.220131 -0.0812863 -0.972078 + outer loop + vertex 722.059 170.825 302.616 + vertex 728.099 174.037 303.716 + vertex 726.184 166.18 303.939 + endloop + endfacet + facet normal 0.208037 -0.0570525 -0.976456 + outer loop + vertex 722.059 170.825 302.616 + vertex 723.038 181.12 302.224 + vertex 728.099 174.037 303.716 + endloop + endfacet + facet normal 0.227577 -0.042328 -0.97284 + outer loop + vertex 727.368 187.505 302.959 + vertex 728.099 174.037 303.716 + vertex 723.038 181.12 302.224 + endloop + endfacet + facet normal 0.225057 -0.0405427 -0.973502 + outer loop + vertex 722.716 188.623 301.837 + vertex 727.368 187.505 302.959 + vertex 723.038 181.12 302.224 + endloop + endfacet + facet normal 0.225711 -0.0377809 -0.973461 + outer loop + vertex 722.716 188.623 301.837 + vertex 721.131 197.986 301.106 + vertex 727.368 187.505 302.959 + endloop + endfacet + facet normal 0.258327 -0.0170384 -0.965907 + outer loop + vertex 727.368 187.505 302.959 + vertex 721.131 197.986 301.106 + vertex 727.494 201.445 302.746 + endloop + endfacet + facet normal 0.251668 -0.00388771 -0.967806 + outer loop + vertex 721.131 197.986 301.106 + vertex 720.946 212.882 300.998 + vertex 727.494 201.445 302.746 + endloop + endfacet + facet normal 0.265675 0.00470525 -0.964051 + outer loop + vertex 727.494 201.445 302.746 + vertex 720.946 212.882 300.998 + vertex 727.043 215.087 302.689 + endloop + endfacet + facet normal 0.263633 0.0107438 -0.964563 + outer loop + vertex 720.946 212.882 300.998 + vertex 720.429 226.501 301.008 + vertex 727.043 215.087 302.689 + endloop + endfacet + facet normal 0.270111 0.0147696 -0.962716 + outer loop + vertex 727.043 215.087 302.689 + vertex 720.429 226.501 301.008 + vertex 726.324 228.315 302.69 + endloop + endfacet + facet normal 0.270033 0.0150401 -0.962734 + outer loop + vertex 720.429 226.501 301.008 + vertex 719.759 239.654 301.026 + vertex 726.324 228.315 302.69 + endloop + endfacet + facet normal 0.274246 0.0176607 -0.961497 + outer loop + vertex 726.324 228.315 302.69 + vertex 719.759 239.654 301.026 + vertex 725.503 241.346 302.695 + endloop + endfacet + facet normal 0.274995 0.0149526 -0.961329 + outer loop + vertex 719.759 239.654 301.026 + vertex 719.057 252.749 301.029 + vertex 725.503 241.346 302.695 + endloop + endfacet + facet normal 0.280654 0.0183995 -0.959633 + outer loop + vertex 725.503 241.346 302.695 + vertex 719.057 252.749 301.029 + vertex 724.653 254.374 302.696 + endloop + endfacet + facet normal 0.281743 0.0143895 -0.959382 + outer loop + vertex 719.057 252.749 301.029 + vertex 718.375 265.97 301.027 + vertex 724.653 254.374 302.696 + endloop + endfacet + facet normal 0.290132 0.0193044 -0.956792 + outer loop + vertex 724.653 254.374 302.696 + vertex 718.375 265.97 301.027 + vertex 723.789 267.486 302.699 + endloop + endfacet + facet normal 0.291263 0.0149762 -0.956526 + outer loop + vertex 718.375 265.97 301.027 + vertex 717.702 279.327 301.031 + vertex 723.789 267.486 302.699 + endloop + endfacet + facet normal 0.300599 0.0201966 -0.953537 + outer loop + vertex 723.789 267.486 302.699 + vertex 717.702 279.327 301.031 + vertex 722.913 280.695 302.703 + endloop + endfacet + facet normal 0.301698 0.0156891 -0.953274 + outer loop + vertex 717.702 279.327 301.031 + vertex 717.032 292.76 301.04 + vertex 722.913 280.695 302.703 + endloop + endfacet + facet normal 0.312373 0.021383 -0.949719 + outer loop + vertex 722.913 280.695 302.703 + vertex 717.032 292.76 301.04 + vertex 722.025 293.952 302.709 + endloop + endfacet + facet normal 0.313638 0.0156516 -0.949414 + outer loop + vertex 717.032 292.76 301.04 + vertex 716.364 306.172 301.04 + vertex 722.025 293.952 302.709 + endloop + endfacet + facet normal 0.326501 0.0222212 -0.944935 + outer loop + vertex 722.025 293.952 302.709 + vertex 716.364 306.172 301.04 + vertex 721.13 307.174 302.711 + endloop + endfacet + facet normal 0.327864 0.0151841 -0.944603 + outer loop + vertex 716.364 306.172 301.04 + vertex 715.701 319.474 301.024 + vertex 721.13 307.174 302.711 + endloop + endfacet + facet normal 0.344817 0.0235213 -0.938375 + outer loop + vertex 721.13 307.174 302.711 + vertex 715.701 319.474 301.024 + vertex 720.23 320.286 302.709 + endloop + endfacet + facet normal 0.346108 0.0156755 -0.938064 + outer loop + vertex 715.701 319.474 301.024 + vertex 715.033 332.655 300.998 + vertex 720.23 320.286 302.709 + endloop + endfacet + facet normal 0.364823 0.0245498 -0.930753 + outer loop + vertex 720.23 320.286 302.709 + vertex 715.033 332.655 300.998 + vertex 719.331 333.295 302.699 + endloop + endfacet + facet normal 0.365978 0.0160826 -0.930485 + outer loop + vertex 715.033 332.655 300.998 + vertex 714.378 345.813 300.968 + vertex 719.331 333.295 302.699 + endloop + endfacet + facet normal 0.387307 0.0257514 -0.921591 + outer loop + vertex 719.331 333.295 302.699 + vertex 714.378 345.813 300.968 + vertex 718.439 346.294 302.688 + endloop + endfacet + facet normal 0.38817 0.0178302 -0.921415 + outer loop + vertex 714.378 345.813 300.968 + vertex 713.753 359.09 300.961 + vertex 718.439 346.294 302.688 + endloop + endfacet + facet normal 0.410576 0.0273852 -0.911415 + outer loop + vertex 718.439 346.294 302.688 + vertex 713.753 359.09 300.961 + vertex 717.583 359.417 302.696 + endloop + endfacet + facet normal 0.411068 0.0213096 -0.911355 + outer loop + vertex 713.753 359.09 300.961 + vertex 713.367 372.639 301.104 + vertex 717.583 359.417 302.696 + endloop + endfacet + facet normal 0.429492 0.0282348 -0.902629 + outer loop + vertex 717.583 359.417 302.696 + vertex 713.367 372.639 301.104 + vertex 716.946 372.793 302.812 + endloop + endfacet + facet normal 0.429305 0.0321295 -0.902588 + outer loop + vertex 713.367 372.639 301.104 + vertex 713.582 386.55 301.701 + vertex 716.946 372.793 302.812 + endloop + endfacet + facet normal 0.425674 0.0311001 -0.904342 + outer loop + vertex 716.946 372.793 302.812 + vertex 713.582 386.55 301.701 + vertex 716.82 386.5 303.224 + endloop + endfacet + facet normal 0.251392 -0.0896866 -0.963721 + outer loop + vertex 722.738 163.582 303.468 + vertex 718.844 163.835 302.428 + vertex 722.059 170.825 302.616 + endloop + endfacet + facet normal 0.248409 -0.12344 -0.960758 + outer loop + vertex 721.711 159.435 303.735 + vertex 718.844 163.835 302.428 + vertex 722.738 163.582 303.468 + endloop + endfacet + facet normal 0.239361 -0.12977 -0.962219 + outer loop + vertex 718.187 158.003 303.052 + vertex 718.844 163.835 302.428 + vertex 721.711 159.435 303.735 + endloop + endfacet + facet normal 0.202354 -0.112808 -0.972793 + outer loop + vertex 721.711 159.435 303.735 + vertex 722.738 163.582 303.468 + vertex 725.601 161.079 304.353 + endloop + endfacet + facet normal 0.246936 -0.150794 -0.957227 + outer loop + vertex 720.736 156.386 303.964 + vertex 718.187 158.003 303.052 + vertex 721.711 159.435 303.735 + endloop + endfacet + facet normal 0.272784 -0.187788 -0.94357 + outer loop + vertex 713.446 152.976 302.592 + vertex 714.657 156.28 302.284 + vertex 717.631 154.773 303.444 + endloop + endfacet + facet normal 0.270798 -0.182392 -0.945199 + outer loop + vertex 713.446 152.976 302.592 + vertex 717.631 154.773 303.444 + vertex 716.291 152.469 303.505 + endloop + endfacet + facet normal 0.277766 -0.102046 -0.955213 + outer loop + vertex 722.059 170.825 302.616 + vertex 718.844 163.835 302.428 + vertex 717.492 171.465 301.22 + endloop + endfacet + facet normal 0.283923 -0.0617423 -0.956857 + outer loop + vertex 717.492 171.465 301.22 + vertex 718.974 178.936 301.178 + vertex 722.059 170.825 302.616 + endloop + endfacet + facet normal 0.280452 -0.0632266 -0.957783 + outer loop + vertex 722.059 170.825 302.616 + vertex 718.974 178.936 301.178 + vertex 723.038 181.12 302.224 + endloop + endfacet + facet normal 0.271585 -0.0450157 -0.961361 + outer loop + vertex 718.974 178.936 301.178 + vertex 719.518 187.997 300.907 + vertex 723.038 181.12 302.224 + endloop + endfacet + facet normal 0.28561 -0.037123 -0.957627 + outer loop + vertex 723.038 181.12 302.224 + vertex 719.518 187.997 300.907 + vertex 722.716 188.623 301.837 + endloop + endfacet + facet normal 0.283839 -0.0267763 -0.958498 + outer loop + vertex 722.716 188.623 301.837 + vertex 719.518 187.997 300.907 + vertex 721.131 197.986 301.106 + endloop + endfacet + facet normal 0.340442 -0.0362929 -0.939565 + outer loop + vertex 715.044 196.182 298.97 + vertex 721.131 197.986 301.106 + vertex 719.518 187.997 300.907 + endloop + endfacet + facet normal 0.333536 -0.00928552 -0.942692 + outer loop + vertex 715.044 196.182 298.97 + vertex 715.204 211.14 298.879 + vertex 721.131 197.986 301.106 + endloop + endfacet + facet normal 0.346823 -0.00249196 -0.937927 + outer loop + vertex 721.131 197.986 301.106 + vertex 715.204 211.14 298.879 + vertex 720.946 212.882 300.998 + endloop + endfacet + facet normal 0.343909 0.00837535 -0.938965 + outer loop + vertex 715.204 211.14 298.879 + vertex 714.862 225.155 298.879 + vertex 720.946 212.882 300.998 + endloop + endfacet + facet normal 0.354222 0.014163 -0.935054 + outer loop + vertex 720.946 212.882 300.998 + vertex 714.862 225.155 298.879 + vertex 720.429 226.501 301.008 + endloop + endfacet + facet normal 0.353943 0.0154536 -0.935139 + outer loop + vertex 714.862 225.155 298.879 + vertex 714.339 238.501 298.901 + vertex 720.429 226.501 301.008 + endloop + endfacet + facet normal 0.361208 0.0196432 -0.932278 + outer loop + vertex 720.429 226.501 301.008 + vertex 714.339 238.501 298.901 + vertex 719.759 239.654 301.026 + endloop + endfacet + facet normal 0.361802 0.0165407 -0.932108 + outer loop + vertex 714.339 238.501 298.901 + vertex 713.77 251.661 298.914 + vertex 719.759 239.654 301.026 + endloop + endfacet + facet normal 0.367728 0.0199169 -0.92972 + outer loop + vertex 719.759 239.654 301.026 + vertex 713.77 251.661 298.914 + vertex 719.057 252.749 301.029 + endloop + endfacet + facet normal 0.368818 0.0139928 -0.929396 + outer loop + vertex 713.77 251.661 298.914 + vertex 713.258 264.938 298.911 + vertex 719.057 252.749 301.029 + endloop + endfacet + facet normal 0.378689 0.0193971 -0.925321 + outer loop + vertex 719.057 252.749 301.029 + vertex 713.258 264.938 298.911 + vertex 718.375 265.97 301.027 + endloop + endfacet + facet normal 0.37971 0.0136799 -0.925004 + outer loop + vertex 713.258 264.938 298.911 + vertex 712.781 278.376 298.914 + vertex 718.375 265.97 301.027 + endloop + endfacet + facet normal 0.391835 0.0200301 -0.919818 + outer loop + vertex 718.375 265.97 301.027 + vertex 712.781 278.376 298.914 + vertex 717.702 279.327 301.031 + endloop + endfacet + facet normal 0.392998 0.0131794 -0.919445 + outer loop + vertex 712.781 278.376 298.914 + vertex 712.33 291.927 298.915 + vertex 717.702 279.327 301.031 + endloop + endfacet + facet normal 0.408589 0.0209966 -0.912477 + outer loop + vertex 717.702 279.327 301.031 + vertex 712.33 291.927 298.915 + vertex 717.032 292.76 301.04 + endloop + endfacet + facet normal 0.409779 0.0132991 -0.912088 + outer loop + vertex 712.33 291.927 298.915 + vertex 711.886 305.474 298.913 + vertex 717.032 292.76 301.04 + endloop + endfacet + facet normal 0.426243 0.021256 -0.904359 + outer loop + vertex 717.032 292.76 301.04 + vertex 711.886 305.474 298.913 + vertex 716.364 306.172 301.04 + endloop + endfacet + facet normal 0.427361 0.0129624 -0.903988 + outer loop + vertex 711.886 305.474 298.913 + vertex 711.437 318.925 298.894 + vertex 716.364 306.172 301.04 + endloop + endfacet + facet normal 0.444628 0.0210667 -0.895468 + outer loop + vertex 716.364 306.172 301.04 + vertex 711.437 318.925 298.894 + vertex 715.701 319.474 301.024 + endloop + endfacet + facet normal 0.445624 0.012063 -0.895139 + outer loop + vertex 711.437 318.925 298.894 + vertex 711.007 332.255 298.859 + vertex 715.701 319.474 301.024 + endloop + endfacet + facet normal 0.46725 0.0219168 -0.883854 + outer loop + vertex 715.701 319.474 301.024 + vertex 711.007 332.255 298.859 + vertex 715.033 332.655 300.998 + endloop + endfacet + facet normal 0.467982 0.0133845 -0.883637 + outer loop + vertex 711.007 332.255 298.859 + vertex 710.581 345.523 298.835 + vertex 715.033 332.655 300.998 + endloop + endfacet + facet normal 0.488318 0.0223115 -0.872381 + outer loop + vertex 715.033 332.655 300.998 + vertex 710.581 345.523 298.835 + vertex 714.378 345.813 300.968 + endloop + endfacet + facet normal 0.488896 0.0136698 -0.872235 + outer loop + vertex 710.581 345.523 298.835 + vertex 710.221 358.896 298.842 + vertex 714.378 345.813 300.968 + endloop + endfacet + facet normal 0.513289 0.0237515 -0.857887 + outer loop + vertex 714.378 345.813 300.968 + vertex 710.221 358.896 298.842 + vertex 713.753 359.09 300.961 + endloop + endfacet + facet normal 0.513646 0.0167247 -0.857839 + outer loop + vertex 710.221 358.896 298.842 + vertex 710.053 372.532 299.008 + vertex 713.753 359.09 300.961 + endloop + endfacet + facet normal 0.533825 0.0241077 -0.845251 + outer loop + vertex 713.753 359.09 300.961 + vertex 710.053 372.532 299.008 + vertex 713.367 372.639 301.104 + endloop + endfacet + facet normal 0.533727 0.0267664 -0.845233 + outer loop + vertex 710.053 372.532 299.008 + vertex 710.506 386.592 299.74 + vertex 713.367 372.639 301.104 + endloop + endfacet + facet normal 0.537872 0.027877 -0.842565 + outer loop + vertex 713.367 372.639 301.104 + vertex 710.506 386.592 299.74 + vertex 713.582 386.55 301.701 + endloop + endfacet + facet normal 0.380671 -0.0537419 -0.923147 + outer loop + vertex 715.659 178.367 300.03 + vertex 713.457 185.859 298.686 + vertex 716.5 185.353 299.971 + endloop + endfacet + facet normal 0.415276 -0.0110556 -0.909628 + outer loop + vertex 709.901 194.817 296.639 + vertex 710.22 210.034 296.599 + vertex 715.044 196.182 298.97 + endloop + endfacet + facet normal 0.417801 -0.00998043 -0.908484 + outer loop + vertex 715.044 196.182 298.97 + vertex 710.22 210.034 296.599 + vertex 715.204 211.14 298.879 + endloop + endfacet + facet normal 0.415081 0.00493975 -0.909771 + outer loop + vertex 710.22 210.034 296.599 + vertex 710.019 224.293 296.585 + vertex 715.204 211.14 298.879 + endloop + endfacet + facet normal 0.426538 0.0103922 -0.90441 + outer loop + vertex 715.204 211.14 298.879 + vertex 710.019 224.293 296.585 + vertex 714.862 225.155 298.879 + endloop + endfacet + facet normal 0.42602 0.0138255 -0.904608 + outer loop + vertex 710.019 224.293 296.585 + vertex 709.592 237.844 296.591 + vertex 714.862 225.155 298.879 + endloop + endfacet + facet normal 0.435496 0.0185925 -0.899999 + outer loop + vertex 714.862 225.155 298.879 + vertex 709.592 237.844 296.591 + vertex 714.339 238.501 298.901 + endloop + endfacet + facet normal 0.43596 0.0147031 -0.899846 + outer loop + vertex 709.592 237.844 296.591 + vertex 709.161 251.129 296.599 + vertex 714.339 238.501 298.901 + endloop + endfacet + facet normal 0.446881 0.0201806 -0.894366 + outer loop + vertex 714.339 238.501 298.901 + vertex 709.161 251.129 296.599 + vertex 713.77 251.661 298.914 + endloop + endfacet + facet normal 0.447642 0.012538 -0.894125 + outer loop + vertex 709.161 251.129 296.599 + vertex 708.804 264.473 296.608 + vertex 713.77 251.661 298.914 + endloop + endfacet + facet normal 0.457848 0.0174418 -0.88886 + outer loop + vertex 713.77 251.661 298.914 + vertex 708.804 264.473 296.608 + vertex 713.258 264.938 298.911 + endloop + endfacet + facet normal 0.458439 0.0107954 -0.88866 + outer loop + vertex 708.804 264.473 296.608 + vertex 708.489 277.961 296.609 + vertex 713.258 264.938 298.911 + endloop + endfacet + facet normal 0.471777 0.0169354 -0.881555 + outer loop + vertex 713.258 264.938 298.911 + vertex 708.489 277.961 296.609 + vertex 712.781 278.376 298.914 + endloop + endfacet + facet normal 0.472386 0.00945251 -0.881341 + outer loop + vertex 708.489 277.961 296.609 + vertex 708.224 291.534 296.613 + vertex 712.781 278.376 298.914 + endloop + endfacet + facet normal 0.487902 0.0163294 -0.872745 + outer loop + vertex 712.781 278.376 298.914 + vertex 708.224 291.534 296.613 + vertex 712.33 291.927 298.915 + endloop + endfacet + facet normal 0.488497 0.00880311 -0.872521 + outer loop + vertex 708.224 291.534 296.613 + vertex 707.97 305.105 296.607 + vertex 712.33 291.927 298.915 + endloop + endfacet + facet normal 0.506227 0.0164698 -0.862243 + outer loop + vertex 712.33 291.927 298.915 + vertex 707.97 305.105 296.607 + vertex 711.886 305.474 298.913 + endloop + endfacet + facet normal 0.506907 0.00752977 -0.861968 + outer loop + vertex 707.97 305.105 296.607 + vertex 707.722 318.625 296.579 + vertex 711.886 305.474 298.913 + endloop + endfacet + facet normal 0.527753 0.0163898 -0.84924 + outer loop + vertex 711.886 305.474 298.913 + vertex 707.722 318.625 296.579 + vertex 711.437 318.925 298.894 + endloop + endfacet + facet normal 0.52835 0.00712143 -0.848997 + outer loop + vertex 707.722 318.625 296.579 + vertex 707.492 332.059 296.549 + vertex 711.437 318.925 298.894 + endloop + endfacet + facet normal 0.548621 0.0155438 -0.835927 + outer loop + vertex 711.437 318.925 298.894 + vertex 707.492 332.059 296.549 + vertex 711.007 332.255 298.859 + endloop + endfacet + facet normal 0.548965 0.00797771 -0.835807 + outer loop + vertex 707.492 332.059 296.549 + vertex 707.296 345.432 296.548 + vertex 711.007 332.255 298.859 + endloop + endfacet + facet normal 0.57095 0.0168005 -0.820813 + outer loop + vertex 711.007 332.255 298.859 + vertex 707.296 345.432 296.548 + vertex 710.581 345.523 298.835 + endloop + endfacet + facet normal 0.571152 0.00909107 -0.820794 + outer loop + vertex 707.296 345.432 296.548 + vertex 707.149 358.853 296.594 + vertex 710.581 345.523 298.835 + endloop + endfacet + facet normal 0.59039 0.0163722 -0.806952 + outer loop + vertex 710.581 345.523 298.835 + vertex 707.149 358.853 296.594 + vertex 710.221 358.896 298.842 + endloop + endfacet + facet normal 0.590543 0.00681051 -0.806978 + outer loop + vertex 707.149 358.853 296.594 + vertex 707.188 372.516 296.738 + vertex 710.221 358.896 298.842 + endloop + endfacet + facet normal 0.62083 0.017143 -0.783758 + outer loop + vertex 710.221 358.896 298.842 + vertex 707.188 372.516 296.738 + vertex 710.053 372.532 299.008 + endloop + endfacet + facet normal 0.620906 0.0107743 -0.783811 + outer loop + vertex 707.188 372.516 296.738 + vertex 707.708 386.624 297.344 + vertex 710.053 372.532 299.008 + endloop + endfacet + facet normal 0.650303 0.0185443 -0.759449 + outer loop + vertex 710.053 372.532 299.008 + vertex 707.708 386.624 297.344 + vertex 710.506 386.592 299.74 + endloop + endfacet + facet normal 0.376976 -0.288183 -0.88025 + outer loop + vertex 704.358 148.641 300.466 + vertex 704.808 150.686 299.989 + vertex 706.555 150.213 300.892 + endloop + endfacet + facet normal 0.405058 -0.291195 -0.866679 + outer loop + vertex 704.358 148.641 300.466 + vertex 702.718 149.431 299.434 + vertex 704.808 150.686 299.989 + endloop + endfacet + facet normal 0.40375 -0.288323 -0.868249 + outer loop + vertex 702.718 149.431 299.434 + vertex 703.407 152.246 298.82 + vertex 704.808 150.686 299.989 + endloop + endfacet + facet normal 0.417298 -0.27467 -0.866267 + outer loop + vertex 704.808 150.686 299.989 + vertex 703.407 152.246 298.82 + vertex 705.002 152.724 299.436 + endloop + endfacet + facet normal 0.390241 -0.275428 -0.878551 + outer loop + vertex 705.002 152.724 299.436 + vertex 707.169 153.061 300.294 + vertex 704.808 150.686 299.989 + endloop + endfacet + facet normal 0.383947 -0.268542 -0.883442 + outer loop + vertex 707.169 153.061 300.294 + vertex 706.555 150.213 300.892 + vertex 704.808 150.686 299.989 + endloop + endfacet + facet normal 0.389614 -0.25505 -0.884958 + outer loop + vertex 705.002 152.724 299.436 + vertex 705.062 156.24 298.45 + vertex 707.169 153.061 300.294 + endloop + endfacet + facet normal 0.41411 -0.235499 -0.879234 + outer loop + vertex 707.169 153.061 300.294 + vertex 705.062 156.24 298.45 + vertex 708.406 157.874 299.587 + endloop + endfacet + facet normal 0.402962 -0.203591 -0.892285 + outer loop + vertex 705.062 156.24 298.45 + vertex 706.322 162.595 297.569 + vertex 708.406 157.874 299.587 + endloop + endfacet + facet normal 0.437255 -0.183388 -0.880441 + outer loop + vertex 708.406 157.874 299.587 + vertex 706.322 162.595 297.569 + vertex 709.261 163.511 298.837 + endloop + endfacet + facet normal 0.430353 -0.147242 -0.890571 + outer loop + vertex 706.322 162.595 297.569 + vertex 707.172 169.114 296.902 + vertex 709.261 163.511 298.837 + endloop + endfacet + facet normal 0.460551 -0.131581 -0.877826 + outer loop + vertex 709.261 163.511 298.837 + vertex 707.172 169.114 296.902 + vertex 709.842 169.816 298.198 + endloop + endfacet + facet normal 0.454793 -0.0956025 -0.885451 + outer loop + vertex 707.172 169.114 296.902 + vertex 707.822 176.194 296.471 + vertex 709.842 169.816 298.198 + endloop + endfacet + facet normal 0.470603 -0.0885487 -0.877891 + outer loop + vertex 709.842 169.816 298.198 + vertex 707.822 176.194 296.471 + vertex 710.357 176.837 297.765 + endloop + endfacet + facet normal 0.465418 -0.0573667 -0.88323 + outer loop + vertex 707.822 176.194 296.471 + vertex 708.401 184.555 296.233 + vertex 710.357 176.837 297.765 + endloop + endfacet + facet normal 0.461246 -0.0588387 -0.885319 + outer loop + vertex 710.357 176.837 297.765 + vertex 708.401 184.555 296.233 + vertex 710.946 183.742 297.613 + endloop + endfacet + facet normal 0.46809 -0.0335552 -0.883044 + outer loop + vertex 710.946 183.742 297.613 + vertex 708.401 184.555 296.233 + vertex 709.901 194.817 296.639 + endloop + endfacet + facet normal 0.4898 -0.0372034 -0.871041 + outer loop + vertex 705.956 194.059 294.452 + vertex 709.901 194.817 296.639 + vertex 708.401 184.555 296.233 + endloop + endfacet + facet normal 0.496912 -0.0346368 -0.867109 + outer loop + vertex 706.271 182.758 295.085 + vertex 705.956 194.059 294.452 + vertex 708.401 184.555 296.233 + endloop + endfacet + facet normal 0.512532 -0.0598701 -0.856578 + outer loop + vertex 707.822 176.194 296.471 + vertex 706.271 182.758 295.085 + vertex 708.401 184.555 296.233 + endloop + endfacet + facet normal 0.506159 -0.0621409 -0.860199 + outer loop + vertex 705.584 175.819 295.182 + vertex 706.271 182.758 295.085 + vertex 707.822 176.194 296.471 + endloop + endfacet + facet normal 0.509266 -0.0987476 -0.854925 + outer loop + vertex 707.172 169.114 296.902 + vertex 705.584 175.819 295.182 + vertex 707.822 176.194 296.471 + endloop + endfacet + facet normal 0.492759 -0.104937 -0.863815 + outer loop + vertex 704.826 168.673 295.617 + vertex 705.584 175.819 295.182 + vertex 707.172 169.114 296.902 + endloop + endfacet + facet normal 0.496574 -0.152192 -0.854548 + outer loop + vertex 706.322 162.595 297.569 + vertex 704.826 168.673 295.617 + vertex 707.172 169.114 296.902 + endloop + endfacet + facet normal 0.469017 -0.163281 -0.867965 + outer loop + vertex 703.758 161.929 296.308 + vertex 704.826 168.673 295.617 + vertex 706.322 162.595 297.569 + endloop + endfacet + facet normal 0.474932 -0.212551 -0.853968 + outer loop + vertex 705.062 156.24 298.45 + vertex 703.758 161.929 296.308 + vertex 706.322 162.595 297.569 + endloop + endfacet + facet normal 0.446147 -0.22387 -0.866508 + outer loop + vertex 702.164 155.367 297.183 + vertex 703.758 161.929 296.308 + vertex 705.062 156.24 298.45 + endloop + endfacet + facet normal 0.486076 -0.00968436 -0.873863 + outer loop + vertex 705.956 194.059 294.452 + vertex 706.447 209.264 294.557 + vertex 709.901 194.817 296.639 + endloop + endfacet + facet normal 0.477884 -0.0122876 -0.878337 + outer loop + vertex 709.901 194.817 296.639 + vertex 706.447 209.264 294.557 + vertex 710.22 210.034 296.599 + endloop + endfacet + facet normal 0.475449 0.00335367 -0.879737 + outer loop + vertex 706.447 209.264 294.557 + vertex 706.321 223.646 294.544 + vertex 710.22 210.034 296.599 + endloop + endfacet + facet normal 0.48242 0.00592678 -0.87592 + outer loop + vertex 710.22 210.034 296.599 + vertex 706.321 223.646 294.544 + vertex 710.019 224.293 296.585 + endloop + endfacet + facet normal 0.481708 0.0110736 -0.876262 + outer loop + vertex 706.321 223.646 294.544 + vertex 705.981 237.281 294.529 + vertex 710.019 224.293 296.585 + endloop + endfacet + facet normal 0.493886 0.0159483 -0.86938 + outer loop + vertex 710.019 224.293 296.585 + vertex 705.981 237.281 294.529 + vertex 709.592 237.844 296.591 + endloop + endfacet + facet normal 0.494291 0.0127057 -0.869204 + outer loop + vertex 705.981 237.281 294.529 + vertex 705.64 250.636 294.53 + vertex 709.592 237.844 296.591 + endloop + endfacet + facet normal 0.504721 0.016908 -0.863117 + outer loop + vertex 709.592 237.844 296.591 + vertex 705.64 250.636 294.53 + vertex 709.161 251.129 296.599 + endloop + endfacet + facet normal 0.505435 0.0104928 -0.862801 + outer loop + vertex 705.64 250.636 294.53 + vertex 705.376 264.089 294.539 + vertex 709.161 251.129 296.599 + endloop + endfacet + facet normal 0.515329 0.014325 -0.856873 + outer loop + vertex 709.161 251.129 296.599 + vertex 705.376 264.089 294.539 + vertex 708.804 264.473 296.608 + endloop + endfacet + facet normal 0.515962 0.00712364 -0.856582 + outer loop + vertex 705.376 264.089 294.539 + vertex 705.222 277.715 294.56 + vertex 708.804 264.473 296.608 + endloop + endfacet + facet normal 0.530584 0.0124767 -0.847541 + outer loop + vertex 708.804 264.473 296.608 + vertex 705.222 277.715 294.56 + vertex 708.489 277.961 296.609 + endloop + endfacet + facet normal 0.531011 0.00521987 -0.847349 + outer loop + vertex 705.222 277.715 294.56 + vertex 705.104 291.349 294.57 + vertex 708.489 277.961 296.609 + endloop + endfacet + facet normal 0.547197 0.0108994 -0.836933 + outer loop + vertex 708.489 277.961 296.609 + vertex 705.104 291.349 294.57 + vertex 708.224 291.534 296.613 + endloop + endfacet + facet normal 0.547518 0.003835 -0.836785 + outer loop + vertex 705.104 291.349 294.57 + vertex 704.985 304.88 294.554 + vertex 708.224 291.534 296.613 + endloop + endfacet + facet normal 0.566101 0.0102756 -0.824272 + outer loop + vertex 708.224 291.534 296.613 + vertex 704.985 304.88 294.554 + vertex 707.97 305.105 296.607 + endloop + endfacet + facet normal 0.566551 0.00203791 -0.824024 + outer loop + vertex 704.985 304.88 294.554 + vertex 704.889 318.329 294.522 + vertex 707.97 305.105 296.607 + endloop + endfacet + facet normal 0.58707 0.00911173 -0.809485 + outer loop + vertex 707.97 305.105 296.607 + vertex 704.889 318.329 294.522 + vertex 707.722 318.625 296.579 + endloop + endfacet + facet normal 0.587621 0.00141604 -0.809135 + outer loop + vertex 704.889 318.329 294.522 + vertex 704.812 331.771 294.489 + vertex 707.722 318.625 296.579 + endloop + endfacet + facet normal 0.608786 0.00861948 -0.793287 + outer loop + vertex 707.722 318.625 296.579 + vertex 704.812 331.771 294.489 + vertex 707.492 332.059 296.549 + endloop + endfacet + facet normal 0.609208 0.00268447 -0.793006 + outer loop + vertex 704.812 331.771 294.489 + vertex 704.771 345.239 294.503 + vertex 707.492 332.059 296.549 + endloop + endfacet + facet normal 0.628874 0.00915992 -0.777454 + outer loop + vertex 707.492 332.059 296.549 + vertex 704.771 345.239 294.503 + vertex 707.296 345.432 296.548 + endloop + endfacet + facet normal 0.629143 0.00379736 -0.77728 + outer loop + vertex 704.771 345.239 294.503 + vertex 704.796 358.786 294.59 + vertex 707.296 345.432 296.548 + endloop + endfacet + facet normal 0.648316 0.00972731 -0.761309 + outer loop + vertex 707.296 345.432 296.548 + vertex 704.796 358.786 294.59 + vertex 707.149 358.853 296.594 + endloop + endfacet + facet normal 0.648573 -0.00445588 -0.76114 + outer loop + vertex 704.796 358.786 294.59 + vertex 704.959 372.526 294.648 + vertex 707.149 358.853 296.594 + endloop + endfacet + facet normal 0.68402 0.00573137 -0.729441 + outer loop + vertex 707.149 358.853 296.594 + vertex 704.959 372.526 294.648 + vertex 707.188 372.516 296.738 + endloop + endfacet + facet normal 0.683871 -0.0174921 -0.729393 + outer loop + vertex 704.959 372.526 294.648 + vertex 705.335 386.645 294.662 + vertex 707.188 372.516 296.738 + endloop + endfacet + facet normal 0.748963 0.000851164 -0.662611 + outer loop + vertex 707.188 372.516 296.738 + vertex 705.335 386.645 294.662 + vertex 707.708 386.624 297.344 + endloop + endfacet + facet normal 0.413877 -0.252557 -0.874598 + outer loop + vertex 705.002 152.724 299.436 + vertex 703.407 152.246 298.82 + vertex 705.062 156.24 298.45 + endloop + endfacet + facet normal 0.43879 -0.29283 -0.849538 + outer loop + vertex 702.718 149.431 299.434 + vertex 701.707 151.043 298.357 + vertex 703.407 152.246 298.82 + endloop + endfacet + facet normal 0.431016 -0.278456 -0.858305 + outer loop + vertex 701.707 151.043 298.357 + vertex 702.164 155.367 297.183 + vertex 703.407 152.246 298.82 + endloop + endfacet + facet normal 0.452251 -0.266278 -0.851214 + outer loop + vertex 702.164 155.367 297.183 + vertex 705.062 156.24 298.45 + vertex 703.407 152.246 298.82 + endloop + endfacet + facet normal 0.462834 -0.277375 -0.841931 + outer loop + vertex 701.707 151.043 298.357 + vertex 700.364 151.131 297.589 + vertex 702.164 155.367 297.183 + endloop + endfacet + facet normal 0.425224 -0.303446 -0.852704 + outer loop + vertex 700.846 148.641 298.782 + vertex 701.707 151.043 298.357 + vertex 702.718 149.431 299.434 + endloop + endfacet +endsolid diff --git a/noether_examples/meshes/outputs/output_1.stl b/noether_examples/meshes/outputs/output_1.stl new file mode 100644 index 00000000..3f3c252d --- /dev/null +++ b/noether_examples/meshes/outputs/output_1.stl @@ -0,0 +1,6953 @@ +solid ascii + facet normal -0.910077 -0.27702 -0.308252 + outer loop + vertex 841.727 275.017 275.071 + vertex 842.536 275.713 272.057 + vertex 843.235 270.379 274.787 + endloop + endfacet + facet normal -0.898097 -0.270778 -0.346556 + outer loop + vertex 842.526 268.657 277.97 + vertex 841.727 275.017 275.071 + vertex 843.235 270.379 274.787 + endloop + endfacet + facet normal -0.886544 -0.279431 -0.368724 + outer loop + vertex 841.15 272.402 278.439 + vertex 841.727 275.017 275.071 + vertex 842.526 268.657 277.97 + endloop + endfacet + facet normal -0.913051 -0.274177 -0.301935 + outer loop + vertex 843.235 270.379 274.787 + vertex 842.536 275.713 272.057 + vertex 843.833 272.008 271.497 + endloop + endfacet + facet normal -0.917984 -0.278922 -0.281972 + outer loop + vertex 842.536 275.713 272.057 + vertex 842.905 278.133 268.461 + vertex 843.833 272.008 271.497 + endloop + endfacet + facet normal -0.926378 -0.27037 -0.262154 + outer loop + vertex 843.833 272.008 271.497 + vertex 842.905 278.133 268.461 + vertex 844.34 273.553 268.114 + endloop + endfacet + facet normal -0.933406 -0.274971 -0.230529 + outer loop + vertex 842.905 278.133 268.461 + vertex 843.534 278.688 265.251 + vertex 844.34 273.553 268.114 + endloop + endfacet + facet normal -0.934208 -0.273956 -0.228481 + outer loop + vertex 844.34 273.553 268.114 + vertex 843.534 278.688 265.251 + vertex 844.763 275.026 264.62 + endloop + endfacet + facet normal -0.936293 -0.276765 -0.216234 + outer loop + vertex 843.534 278.688 265.251 + vertex 843.747 280.954 261.431 + vertex 844.763 275.026 264.62 + endloop + endfacet + facet normal -0.942841 -0.268063 -0.19797 + outer loop + vertex 844.763 275.026 264.62 + vertex 843.747 280.954 261.431 + vertex 845.121 276.443 260.997 + endloop + endfacet + facet normal -0.946614 -0.271543 -0.173744 + outer loop + vertex 843.747 280.954 261.431 + vertex 844.248 281.398 258.005 + vertex 845.121 276.443 260.997 + endloop + endfacet + facet normal -0.946261 -0.272107 -0.174781 + outer loop + vertex 845.121 276.443 260.997 + vertex 844.248 281.398 258.005 + vertex 845.425 277.776 257.272 + endloop + endfacet + facet normal -0.947096 -0.27389 -0.167313 + outer loop + vertex 844.248 281.398 258.005 + vertex 844.35 283.472 254.033 + vertex 845.425 277.776 257.272 + endloop + endfacet + facet normal -0.952036 -0.265839 -0.151518 + outer loop + vertex 845.425 277.776 257.272 + vertex 844.35 283.472 254.033 + vertex 845.679 279.003 253.522 + endloop + endfacet + facet normal -0.954238 -0.268841 -0.130974 + outer loop + vertex 844.35 283.472 254.033 + vertex 844.757 283.735 250.527 + vertex 845.679 279.003 253.522 + endloop + endfacet + facet normal -0.954811 -0.267735 -0.12905 + outer loop + vertex 845.679 279.003 253.522 + vertex 844.757 283.735 250.527 + vertex 845.867 280.129 249.798 + endloop + endfacet + facet normal -0.955096 -0.268644 -0.124989 + outer loop + vertex 844.757 283.735 250.527 + vertex 844.754 285.594 246.557 + vertex 845.867 280.129 249.798 + endloop + endfacet + facet normal -0.961073 -0.256559 -0.102553 + outer loop + vertex 845.867 280.129 249.798 + vertex 844.754 285.594 246.557 + vertex 845.967 281.234 246.1 + endloop + endfacet + facet normal -0.961839 -0.257961 -0.0912183 + outer loop + vertex 844.754 285.594 246.557 + vertex 845.051 285.715 243.085 + vertex 845.967 281.234 246.1 + endloop + endfacet + facet normal -0.962455 -0.256489 -0.0888432 + outer loop + vertex 845.967 281.234 246.1 + vertex 845.051 285.715 243.085 + vertex 846.038 282.233 242.438 + endloop + endfacet + facet normal -0.962381 -0.256128 -0.0906767 + outer loop + vertex 845.051 285.715 243.085 + vertex 844.957 287.475 239.102 + vertex 846.038 282.233 242.438 + endloop + endfacet + facet normal -0.964649 -0.250666 -0.0813601 + outer loop + vertex 846.038 282.233 242.438 + vertex 844.957 287.475 239.102 + vertex 846.12 283.125 238.728 + endloop + endfacet + facet normal -0.965397 -0.252134 -0.0666052 + outer loop + vertex 844.957 287.475 239.102 + vertex 845.169 287.617 235.502 + vertex 846.12 283.125 238.728 + endloop + endfacet + facet normal -0.964518 -0.254518 -0.070184 + outer loop + vertex 846.12 283.125 238.728 + vertex 845.169 287.617 235.502 + vertex 846.152 284.089 234.783 + endloop + endfacet + facet normal -0.964481 -0.25411 -0.0721349 + outer loop + vertex 845.169 287.617 235.502 + vertex 844.963 289.674 231.012 + vertex 846.152 284.089 234.783 + endloop + endfacet + facet normal -0.968794 -0.242128 -0.0530269 + outer loop + vertex 846.152 284.089 234.783 + vertex 844.963 289.674 231.012 + vertex 846.158 285.015 230.438 + endloop + endfacet + facet normal -0.968834 -0.242365 -0.0511915 + outer loop + vertex 844.963 289.674 231.012 + vertex 845.044 290.551 225.312 + vertex 846.158 285.015 230.438 + endloop + endfacet + facet normal -0.9686 -0.243116 -0.0520535 + outer loop + vertex 846.158 285.015 230.438 + vertex 845.044 290.551 225.312 + vertex 846.417 284.903 226.156 + endloop + endfacet + facet normal -0.969131 -0.242285 -0.045634 + outer loop + vertex 845.044 290.551 225.312 + vertex 845.693 289.153 218.966 + vertex 846.417 284.903 226.156 + endloop + endfacet + facet normal -0.949644 -0.302145 -0.0829766 + outer loop + vertex 847.276 282.85 223.8 + vertex 846.417 284.903 226.156 + vertex 845.693 289.153 218.966 + endloop + endfacet + facet normal -0.956881 -0.284667 -0.057822 + outer loop + vertex 847.343 283.366 220.157 + vertex 847.276 282.85 223.8 + vertex 845.693 289.153 218.966 + endloop + endfacet + facet normal -0.959239 -0.280503 -0.0343296 + outer loop + vertex 847.343 283.366 220.157 + vertex 845.693 289.153 218.966 + vertex 847.064 284.839 215.911 + endloop + endfacet + facet normal -0.959959 -0.277408 -0.0390235 + outer loop + vertex 845.693 289.153 218.966 + vertex 845.644 290.561 210.162 + vertex 847.064 284.839 215.911 + endloop + endfacet + facet normal -0.960858 -0.27468 -0.0360865 + outer loop + vertex 847.243 284.722 212.03 + vertex 847.064 284.839 215.911 + vertex 845.644 290.561 210.162 + endloop + endfacet + facet normal -0.961975 -0.271866 -0.0263324 + outer loop + vertex 847.243 284.722 212.03 + vertex 845.644 290.561 210.162 + vertex 847.016 285.933 207.825 + endloop + endfacet + facet normal -0.962397 -0.269943 -0.0303886 + outer loop + vertex 845.644 290.561 210.162 + vertex 845.635 291.502 202.072 + vertex 847.016 285.933 207.825 + endloop + endfacet + facet normal -0.961515 -0.272728 -0.0332965 + outer loop + vertex 847.224 285.65 204.117 + vertex 847.016 285.933 207.825 + vertex 845.635 291.502 202.072 + endloop + endfacet + facet normal -0.962963 -0.268816 -0.0209779 + outer loop + vertex 847.224 285.65 204.117 + vertex 845.635 291.502 202.072 + vertex 847.008 286.754 199.917 + endloop + endfacet + facet normal -0.963082 -0.268289 -0.0222145 + outer loop + vertex 845.635 291.502 202.072 + vertex 845.63 292.18 194.11 + vertex 847.008 286.754 199.917 + endloop + endfacet + facet normal -0.962563 -0.269998 -0.0239346 + outer loop + vertex 847.211 286.361 196.194 + vertex 847.008 286.754 199.917 + vertex 845.63 292.18 194.11 + endloop + endfacet + facet normal -0.963634 -0.266842 -0.0143076 + outer loop + vertex 847.211 286.361 196.194 + vertex 845.63 292.18 194.11 + vertex 846.997 287.359 191.948 + endloop + endfacet + facet normal -0.963827 -0.266036 -0.0162259 + outer loop + vertex 845.63 292.18 194.11 + vertex 845.636 292.645 186.134 + vertex 846.997 287.359 191.948 + endloop + endfacet + facet normal -0.962667 -0.269943 -0.0200497 + outer loop + vertex 847.208 286.885 188.189 + vertex 846.997 287.359 191.948 + vertex 845.636 292.645 186.134 + endloop + endfacet + facet normal -0.964217 -0.265063 -0.00518701 + outer loop + vertex 847.208 286.885 188.189 + vertex 845.636 292.645 186.134 + vertex 846.989 287.767 183.942 + endloop + endfacet + facet normal -0.964586 -0.263629 -0.00860538 + outer loop + vertex 845.636 292.645 186.134 + vertex 845.638 292.898 178.181 + vertex 846.989 287.767 183.942 + endloop + endfacet + facet normal -0.963157 -0.268607 -0.0133748 + outer loop + vertex 847.201 287.194 180.188 + vertex 846.989 287.767 183.942 + vertex 845.638 292.898 178.181 + endloop + endfacet + facet normal -0.964555 -0.263881 0.001142 + outer loop + vertex 847.201 287.194 180.188 + vertex 845.638 292.898 178.181 + vertex 846.984 287.967 175.982 + endloop + endfacet + facet normal -0.964871 -0.262718 -0.00165872 + outer loop + vertex 845.638 292.898 178.181 + vertex 845.637 292.951 170.305 + vertex 846.984 287.967 175.982 + endloop + endfacet + facet normal -0.963416 -0.267931 -0.00658035 + outer loop + vertex 847.195 287.298 172.278 + vertex 846.984 287.967 175.982 + vertex 845.637 292.951 170.305 + endloop + endfacet + facet normal -0.964521 -0.263945 0.00570831 + outer loop + vertex 847.195 287.298 172.278 + vertex 845.637 292.951 170.305 + vertex 846.987 287.97 168.144 + endloop + endfacet + facet normal -0.964523 -0.263938 0.00569102 + outer loop + vertex 845.637 292.951 170.305 + vertex 845.63 292.808 162.518 + vertex 846.987 287.97 168.144 + endloop + endfacet + facet normal -0.963588 -0.267378 0.00250743 + outer loop + vertex 847.191 287.201 164.516 + vertex 846.987 287.97 168.144 + vertex 845.63 292.808 162.518 + endloop + endfacet + facet normal -0.964341 -0.264417 0.0114056 + outer loop + vertex 847.191 287.201 164.516 + vertex 845.63 292.808 162.518 + vertex 846.986 287.773 160.413 + endloop + endfacet + facet normal -0.964308 -0.264525 0.0116843 + outer loop + vertex 845.63 292.808 162.518 + vertex 845.627 292.475 154.73 + vertex 846.986 287.773 160.413 + endloop + endfacet + facet normal -0.963541 -0.267406 0.00911666 + outer loop + vertex 847.191 286.909 156.776 + vertex 846.986 287.773 160.413 + vertex 845.627 292.475 154.73 + endloop + endfacet + facet normal -0.964321 -0.264067 0.0187974 + outer loop + vertex 847.191 286.909 156.776 + vertex 845.627 292.475 154.73 + vertex 846.982 287.377 152.612 + endloop + endfacet + facet normal -0.964322 -0.264064 0.0187872 + outer loop + vertex 845.627 292.475 154.73 + vertex 845.619 291.947 146.869 + vertex 846.982 287.377 152.612 + endloop + endfacet + facet normal -0.962906 -0.269465 0.0141536 + outer loop + vertex 847.193 286.428 148.913 + vertex 846.982 287.377 152.612 + vertex 845.619 291.947 146.869 + endloop + endfacet + facet normal -0.963727 -0.265726 0.0248813 + outer loop + vertex 847.193 286.428 148.913 + vertex 845.619 291.947 146.869 + vertex 846.983 286.796 144.712 + endloop + endfacet + facet normal -0.963629 -0.266011 0.0256251 + outer loop + vertex 845.619 291.947 146.869 + vertex 845.614 291.198 138.939 + vertex 846.983 286.796 144.712 + endloop + endfacet + facet normal -0.962347 -0.270971 0.021539 + outer loop + vertex 847.194 285.752 140.991 + vertex 846.983 286.796 144.712 + vertex 845.614 291.198 138.939 + endloop + endfacet + facet normal -0.963091 -0.267278 0.0319132 + outer loop + vertex 847.194 285.752 140.991 + vertex 845.614 291.198 138.939 + vertex 846.989 285.983 136.757 + endloop + endfacet + facet normal -0.962907 -0.26778 0.0332281 + outer loop + vertex 845.614 291.198 138.939 + vertex 845.631 290.14 130.897 + vertex 846.989 285.983 136.757 + endloop + endfacet + facet normal -0.96109 -0.274833 0.0278033 + outer loop + vertex 847.216 284.809 133.001 + vertex 846.989 285.983 136.757 + vertex 845.631 290.14 130.897 + endloop + endfacet + facet normal -0.961871 -0.270744 0.0387539 + outer loop + vertex 847.216 284.809 133.001 + vertex 845.631 290.14 130.897 + vertex 847.033 284.845 128.705 + endloop + endfacet + facet normal -0.960849 -0.273298 0.0455771 + outer loop + vertex 845.631 290.14 130.897 + vertex 845.642 288.714 122.573 + vertex 847.033 284.845 128.705 + endloop + endfacet + facet normal -0.957899 -0.284611 0.0377684 + outer loop + vertex 847.292 283.487 125.026 + vertex 847.033 284.845 128.705 + vertex 845.642 288.714 122.573 + endloop + endfacet + facet normal -0.959368 -0.276566 0.0559 + outer loop + vertex 847.292 283.487 125.026 + vertex 845.642 288.714 122.573 + vertex 847.125 283.274 121.103 + endloop + endfacet + facet normal -0.956245 -0.28183 0.0785319 + outer loop + vertex 845.926 286.317 117.431 + vertex 847.125 283.274 121.103 + vertex 845.642 288.714 122.573 + endloop + endfacet + facet normal -0.970386 -0.234996 0.0559185 + outer loop + vertex 845.058 289.884 117.366 + vertex 845.926 286.317 117.431 + vertex 845.642 288.714 122.573 + endloop + endfacet + facet normal -0.978032 -0.198034 0.065079 + outer loop + vertex 845.642 288.714 122.573 + vertex 843.914 295.02 115.79 + vertex 845.058 289.884 117.366 + endloop + endfacet + facet normal -0.977957 -0.20305 0.0486843 + outer loop + vertex 845.058 289.884 117.366 + vertex 843.914 295.02 115.79 + vertex 844.937 289.554 113.546 + endloop + endfacet + facet normal -0.976982 -0.205852 0.0559533 + outer loop + vertex 843.914 295.02 115.79 + vertex 843.774 293.495 107.749 + vertex 844.937 289.554 113.546 + endloop + endfacet + facet normal -0.976022 -0.211369 0.0520098 + outer loop + vertex 845.107 287.845 109.788 + vertex 844.937 289.554 113.546 + vertex 843.774 293.495 107.749 + endloop + endfacet + facet normal -0.976199 -0.207909 0.0617168 + outer loop + vertex 845.107 287.845 109.788 + vertex 843.774 293.495 107.749 + vertex 844.889 287.622 105.596 + endloop + endfacet + facet normal -0.967349 -0.245426 0.0632554 + outer loop + vertex 845.107 287.845 109.788 + vertex 844.889 287.622 105.596 + vertex 846.043 283.984 109.119 + endloop + endfacet + facet normal -0.968008 -0.244441 0.056648 + outer loop + vertex 846.022 285.008 113.184 + vertex 845.107 287.845 109.788 + vertex 846.043 283.984 109.119 + endloop + endfacet + facet normal -0.967826 -0.24277 0.0661542 + outer loop + vertex 846.043 283.984 109.119 + vertex 844.889 287.622 105.596 + vertex 846.004 283.067 105.185 + endloop + endfacet + facet normal -0.965869 -0.244134 0.0865735 + outer loop + vertex 844.889 287.622 105.596 + vertex 844.974 286.008 101.991 + vertex 846.004 283.067 105.185 + endloop + endfacet + facet normal -0.964728 -0.250767 0.0800977 + outer loop + vertex 846.004 283.067 105.185 + vertex 844.974 286.008 101.991 + vertex 845.92 282.164 101.349 + endloop + endfacet + facet normal -0.963466 -0.252156 0.0902772 + outer loop + vertex 844.974 286.008 101.991 + vertex 844.661 285.773 97.9974 + vertex 845.92 282.164 101.349 + endloop + endfacet + facet normal -0.963822 -0.249826 0.0929208 + outer loop + vertex 845.92 282.164 101.349 + vertex 844.661 285.773 97.9974 + vertex 845.812 281.171 97.56 + endloop + endfacet + facet normal -0.960744 -0.251382 0.117384 + outer loop + vertex 844.661 285.773 97.9974 + vertex 844.69 284.037 94.5161 + vertex 845.812 281.171 97.56 + endloop + endfacet + facet normal -0.959594 -0.259145 0.109652 + outer loop + vertex 845.812 281.171 97.56 + vertex 844.69 284.037 94.5161 + vertex 845.691 280.028 93.7971 + endloop + endfacet + facet normal -0.957784 -0.260744 0.121091 + outer loop + vertex 844.69 284.037 94.5161 + vertex 844.311 283.618 90.6152 + vertex 845.691 280.028 93.7971 + endloop + endfacet + facet normal -0.9584 -0.255461 0.127318 + outer loop + vertex 845.691 280.028 93.7971 + vertex 844.311 283.618 90.6152 + vertex 845.52 278.804 90.0569 + endloop + endfacet + facet normal -0.954195 -0.257338 0.152608 + outer loop + vertex 844.311 283.618 90.6152 + vertex 844.277 281.714 87.1905 + vertex 845.52 278.804 90.0569 + endloop + endfacet + facet normal -0.953852 -0.260637 0.149111 + outer loop + vertex 845.52 278.804 90.0569 + vertex 844.277 281.714 87.1905 + vertex 845.283 277.569 86.3801 + endloop + endfacet + facet normal -0.950619 -0.262936 0.164886 + outer loop + vertex 844.277 281.714 87.1905 + vertex 843.767 281.185 83.4104 + vertex 845.283 277.569 86.3801 + endloop + endfacet + facet normal -0.950904 -0.257609 0.171518 + outer loop + vertex 845.283 277.569 86.3801 + vertex 843.767 281.185 83.4104 + vertex 844.986 276.272 82.7864 + endloop + endfacet + facet normal -0.944161 -0.259877 0.202545 + outer loop + vertex 843.767 281.185 83.4104 + vertex 843.615 279.153 80.0909 + vertex 844.986 276.272 82.7864 + endloop + endfacet + facet normal -0.944084 -0.261644 0.200617 + outer loop + vertex 844.986 276.272 82.7864 + vertex 843.615 279.153 80.0909 + vertex 844.617 274.901 79.2623 + endloop + endfacet + facet normal -0.937872 -0.264784 0.224245 + outer loop + vertex 843.615 279.153 80.0909 + vertex 842.932 278.485 76.4461 + vertex 844.617 274.901 79.2623 + endloop + endfacet + facet normal -0.937777 -0.260833 0.229217 + outer loop + vertex 844.617 274.901 79.2623 + vertex 842.932 278.485 76.4461 + vertex 844.173 273.449 75.7928 + endloop + endfacet + facet normal -0.927083 -0.2631 0.267012 + outer loop + vertex 842.932 278.485 76.4461 + vertex 842.627 276.298 73.2344 + vertex 844.173 273.449 75.7928 + endloop + endfacet + facet normal -0.927141 -0.265062 0.264862 + outer loop + vertex 844.173 273.449 75.7928 + vertex 842.627 276.298 73.2344 + vertex 843.637 271.927 72.3943 + endloop + endfacet + facet normal -0.915177 -0.269069 0.30009 + outer loop + vertex 842.627 276.298 73.2344 + vertex 841.732 275.473 69.7629 + vertex 843.637 271.927 72.3943 + endloop + endfacet + facet normal -0.914758 -0.265673 0.304362 + outer loop + vertex 843.637 271.927 72.3943 + vertex 841.732 275.473 69.7629 + vertex 842.999 270.336 69.0886 + endloop + endfacet + facet normal -0.89634 -0.26758 0.353517 + outer loop + vertex 841.732 275.473 69.7629 + vertex 841.238 273.124 66.7336 + vertex 842.999 270.336 69.0886 + endloop + endfacet + facet normal -0.896383 -0.26791 0.353159 + outer loop + vertex 842.999 270.336 69.0886 + vertex 841.238 273.124 66.7336 + vertex 842.248 268.658 65.9094 + endloop + endfacet + facet normal -0.962798 -0.217625 0.160186 + outer loop + vertex 844.277 281.714 87.1905 + vertex 842.7 287.401 85.4404 + vertex 843.767 281.185 83.4104 + endloop + endfacet + facet normal -0.955134 -0.226368 0.190987 + outer loop + vertex 842.7 287.401 85.4404 + vertex 841.901 284.872 78.4458 + vertex 843.767 281.185 83.4104 + endloop + endfacet + facet normal -0.954602 -0.232479 0.186249 + outer loop + vertex 843.615 279.153 80.0909 + vertex 843.767 281.185 83.4104 + vertex 841.901 284.872 78.4458 + endloop + endfacet + facet normal -0.950242 -0.221842 0.218691 + outer loop + vertex 843.615 279.153 80.0909 + vertex 841.901 284.872 78.4458 + vertex 842.932 278.485 76.4461 + endloop + endfacet + facet normal -0.937238 -0.232603 0.25977 + outer loop + vertex 841.901 284.872 78.4458 + vertex 840.745 282.013 71.715 + vertex 842.932 278.485 76.4461 + endloop + endfacet + facet normal -0.936861 -0.241309 0.253104 + outer loop + vertex 842.627 276.298 73.2344 + vertex 842.932 278.485 76.4461 + vertex 840.745 282.013 71.715 + endloop + endfacet + facet normal -0.928384 -0.227729 0.293672 + outer loop + vertex 842.627 276.298 73.2344 + vertex 840.745 282.013 71.715 + vertex 841.732 275.473 69.7629 + endloop + endfacet + facet normal -0.907782 -0.239704 0.3442 + outer loop + vertex 840.745 282.013 71.715 + vertex 839.242 278.71 65.4507 + vertex 841.732 275.473 69.7629 + endloop + endfacet + facet normal -0.907865 -0.246566 0.339098 + outer loop + vertex 841.238 273.124 66.7336 + vertex 841.732 275.473 69.7629 + vertex 839.242 278.71 65.4507 + endloop + endfacet + facet normal -0.892189 -0.229499 0.389009 + outer loop + vertex 841.238 273.124 66.7336 + vertex 839.242 278.71 65.4507 + vertex 840.138 272.058 63.5828 + endloop + endfacet + facet normal -0.867674 -0.239318 0.43574 + outer loop + vertex 839.242 278.71 65.4507 + vertex 837.6 274.838 60.0558 + vertex 840.138 272.058 63.5828 + endloop + endfacet + facet normal -0.867516 -0.237558 0.437014 + outer loop + vertex 839.472 269.486 60.8625 + vertex 840.138 272.058 63.5828 + vertex 837.6 274.838 60.0558 + endloop + endfacet + facet normal -0.891498 -0.193089 0.409815 + outer loop + vertex 839.242 278.71 65.4507 + vertex 835.889 284.17 60.7303 + vertex 837.6 274.838 60.0558 + endloop + endfacet + facet normal -0.892749 -0.198462 0.404489 + outer loop + vertex 837.535 287.938 66.2107 + vertex 835.889 284.17 60.7303 + vertex 839.242 278.71 65.4507 + endloop + endfacet + facet normal -0.89938 -0.184018 0.396552 + outer loop + vertex 837.535 287.938 66.2107 + vertex 834.2 293.291 61.1309 + vertex 835.889 284.17 60.7303 + endloop + endfacet + facet normal -0.900547 -0.189947 0.39107 + outer loop + vertex 835.841 296.701 66.567 + vertex 834.2 293.291 61.1309 + vertex 837.535 287.938 66.2107 + endloop + endfacet + facet normal -0.893735 -0.205488 0.398763 + outer loop + vertex 835.841 296.701 66.567 + vertex 832.275 301.744 61.1726 + vertex 834.2 293.291 61.1309 + endloop + endfacet + facet normal -0.894576 -0.21149 0.393706 + outer loop + vertex 833.917 304.913 66.6069 + vertex 832.275 301.744 61.1726 + vertex 835.841 296.701 66.567 + endloop + endfacet + facet normal -0.881377 -0.240485 0.406622 + outer loop + vertex 833.917 304.913 66.6069 + vertex 829.927 310.016 60.9752 + vertex 832.275 301.744 61.1726 + endloop + endfacet + facet normal -0.881978 -0.246193 0.401876 + outer loop + vertex 831.684 312.766 66.5174 + vertex 829.927 310.016 60.9752 + vertex 833.917 304.913 66.6069 + endloop + endfacet + facet normal -0.869424 -0.273513 0.411451 + outer loop + vertex 831.684 312.766 66.5174 + vertex 827.412 318.026 60.9858 + vertex 829.927 310.016 60.9752 + endloop + endfacet + facet normal -0.870307 -0.28311 0.403007 + outer loop + vertex 829.196 320.334 66.4603 + vertex 827.412 318.026 60.9858 + vertex 831.684 312.766 66.5174 + endloop + endfacet + facet normal -0.86003 -0.305144 0.408944 + outer loop + vertex 829.196 320.334 66.4603 + vertex 824.859 325.388 61.1096 + vertex 827.412 318.026 60.9858 + endloop + endfacet + facet normal -0.860859 -0.319653 0.39591 + outer loop + vertex 826.475 327.654 66.453 + vertex 824.859 325.388 61.1096 + vertex 829.196 320.334 66.4603 + endloop + endfacet + facet normal -0.85075 -0.339449 0.401246 + outer loop + vertex 826.475 327.654 66.453 + vertex 822.066 332.393 61.1145 + vertex 824.859 325.388 61.1096 + endloop + endfacet + facet normal -0.850806 -0.352665 0.38956 + outer loop + vertex 823.479 334.88 66.4514 + vertex 822.066 332.393 61.1145 + vertex 826.475 327.654 66.453 + endloop + endfacet + facet normal -0.841468 -0.368984 0.394693 + outer loop + vertex 823.479 334.88 66.4514 + vertex 818.814 339.678 60.9918 + vertex 822.066 332.393 61.1145 + endloop + endfacet + facet normal -0.841195 -0.379223 0.385461 + outer loop + vertex 820.21 342.135 66.456 + vertex 818.814 339.678 60.9918 + vertex 823.479 334.88 66.4514 + endloop + endfacet + facet normal -0.83721 -0.385942 0.387464 + outer loop + vertex 820.21 342.135 66.456 + vertex 815.227 347.38 60.9117 + vertex 818.814 339.678 60.9918 + endloop + endfacet + facet normal -0.836878 -0.398433 0.37535 + outer loop + vertex 816.786 349.349 66.4788 + vertex 815.227 347.38 60.9117 + vertex 820.21 342.135 66.456 + endloop + endfacet + facet normal -0.837222 -0.397821 0.37523 + outer loop + vertex 816.786 349.349 66.4788 + vertex 811.741 354.832 61.0357 + vertex 815.227 347.38 60.9117 + endloop + endfacet + facet normal -0.836586 -0.416833 0.355491 + outer loop + vertex 813.291 356.375 66.4924 + vertex 811.741 354.832 61.0357 + vertex 816.786 349.349 66.4788 + endloop + endfacet + facet normal -0.839295 -0.411893 0.354864 + outer loop + vertex 813.291 356.375 66.4924 + vertex 808.335 361.82 61.0915 + vertex 811.741 354.832 61.0357 + endloop + endfacet + facet normal -0.837987 -0.432021 0.33337 + outer loop + vertex 809.705 363.277 66.4235 + vertex 808.335 361.82 61.0915 + vertex 813.291 356.375 66.4924 + endloop + endfacet + facet normal -0.842967 -0.423127 0.33222 + outer loop + vertex 809.705 363.277 66.4235 + vertex 804.705 368.964 60.9798 + vertex 808.335 361.82 61.0915 + endloop + endfacet + facet normal -0.841685 -0.438815 0.314654 + outer loop + vertex 806.05 370.235 66.3485 + vertex 804.705 368.964 60.9798 + vertex 809.705 363.277 66.4235 + endloop + endfacet + facet normal -0.860802 -0.402908 0.310942 + outer loop + vertex 806.05 370.235 66.3485 + vertex 801.069 376.705 60.9438 + vertex 804.705 368.964 60.9798 + endloop + endfacet + facet normal -0.860092 -0.418897 0.291147 + outer loop + vertex 802.61 377.321 66.383 + vertex 801.069 376.705 60.9438 + vertex 806.05 370.235 66.3485 + endloop + endfacet + facet normal -0.902629 -0.316582 0.291612 + outer loop + vertex 802.61 377.321 66.383 + vertex 798.325 384.627 61.051 + vertex 801.069 376.705 60.9438 + endloop + endfacet + facet normal -0.903363 -0.329344 0.274714 + outer loop + vertex 800.054 384.55 66.6435 + vertex 798.325 384.627 61.051 + vertex 802.61 377.321 66.383 + endloop + endfacet + facet normal -0.924389 -0.19786 0.326124 + outer loop + vertex 840.745 282.013 71.715 + vertex 837.535 287.938 66.2107 + vertex 839.242 278.71 65.4507 + endloop + endfacet + facet normal -0.924732 -0.200398 0.323592 + outer loop + vertex 839.051 291.086 72.4927 + vertex 837.535 287.938 66.2107 + vertex 840.745 282.013 71.715 + endloop + endfacet + facet normal -0.927618 -0.192299 0.320229 + outer loop + vertex 839.051 291.086 72.4927 + vertex 835.841 296.701 66.567 + vertex 837.535 287.938 66.2107 + endloop + endfacet + facet normal -0.928029 -0.196518 0.316454 + outer loop + vertex 837.371 299.626 72.8703 + vertex 835.841 296.701 66.567 + vertex 839.051 291.086 72.4927 + endloop + endfacet + facet normal -0.920668 -0.217266 0.324293 + outer loop + vertex 837.371 299.626 72.8703 + vertex 833.917 304.913 66.6069 + vertex 835.841 296.701 66.567 + endloop + endfacet + facet normal -0.920882 -0.221724 0.320648 + outer loop + vertex 835.473 307.605 72.935 + vertex 833.917 304.913 66.6069 + vertex 837.371 299.626 72.8703 + endloop + endfacet + facet normal -0.908458 -0.254522 0.331547 + outer loop + vertex 835.473 307.605 72.935 + vertex 831.684 312.766 66.5174 + vertex 833.917 304.913 66.6069 + endloop + endfacet + facet normal -0.908495 -0.259898 0.327245 + outer loop + vertex 833.268 315.209 72.8539 + vertex 831.684 312.766 66.5174 + vertex 835.473 307.605 72.935 + endloop + endfacet + facet normal -0.895391 -0.291862 0.336291 + outer loop + vertex 833.268 315.209 72.8539 + vertex 829.196 320.334 66.4603 + vertex 831.684 312.766 66.5174 + endloop + endfacet + facet normal -0.895189 -0.299643 0.329925 + outer loop + vertex 830.769 322.585 72.7717 + vertex 829.196 320.334 66.4603 + vertex 833.268 315.209 72.8539 + endloop + endfacet + facet normal -0.88265 -0.327813 0.336849 + outer loop + vertex 830.769 322.585 72.7717 + vertex 826.475 327.654 66.453 + vertex 829.196 320.334 66.4603 + endloop + endfacet + facet normal -0.881957 -0.339245 0.327208 + outer loop + vertex 827.988 329.798 72.7552 + vertex 826.475 327.654 66.453 + vertex 830.769 322.585 72.7717 + endloop + endfacet + facet normal -0.87134 -0.361191 0.332126 + outer loop + vertex 827.988 329.798 72.7552 + vertex 823.479 334.88 66.4514 + vertex 826.475 327.654 66.453 + endloop + endfacet + facet normal -0.870236 -0.372972 0.32184 + outer loop + vertex 824.961 336.886 72.7846 + vertex 823.479 334.88 66.4514 + vertex 827.988 329.798 72.7552 + endloop + endfacet + facet normal -0.862195 -0.388646 0.324921 + outer loop + vertex 824.961 336.886 72.7846 + vertex 820.21 342.135 66.456 + vertex 823.479 334.88 66.4514 + endloop + endfacet + facet normal -0.860958 -0.399256 0.315191 + outer loop + vertex 821.734 343.866 72.8116 + vertex 820.21 342.135 66.456 + vertex 824.961 336.886 72.7846 + endloop + endfacet + facet normal -0.856587 -0.407602 0.316415 + outer loop + vertex 821.734 343.866 72.8116 + vertex 816.786 349.349 66.4788 + vertex 820.21 342.135 66.456 + endloop + endfacet + facet normal -0.854369 -0.423964 0.300514 + outer loop + vertex 818.337 350.722 72.8264 + vertex 816.786 349.349 66.4788 + vertex 821.734 343.866 72.8116 + endloop + endfacet + facet normal -0.853696 -0.425238 0.300626 + outer loop + vertex 818.337 350.722 72.8264 + vertex 813.291 356.375 66.4924 + vertex 816.786 349.349 66.4788 + endloop + endfacet + facet normal -0.850758 -0.443504 0.281985 + outer loop + vertex 814.813 357.465 72.7982 + vertex 813.291 356.375 66.4924 + vertex 818.337 350.722 72.8264 + endloop + endfacet + facet normal -0.863393 -0.450336 0.227486 + outer loop + vertex 819.563 351.794 79.6002 + vertex 814.813 357.465 72.7982 + vertex 818.337 350.722 72.8264 + endloop + endfacet + facet normal -0.865468 -0.446458 0.227247 + outer loop + vertex 819.563 351.794 79.6002 + vertex 818.337 350.722 72.8264 + vertex 822.956 345.212 79.5924 + endloop + endfacet + facet normal -0.874257 -0.450933 0.179815 + outer loop + vertex 823.774 346.422 86.6011 + vertex 819.563 351.794 79.6002 + vertex 822.956 345.212 79.5924 + endloop + endfacet + facet normal -0.88093 -0.438326 0.178417 + outer loop + vertex 823.774 346.422 86.6011 + vertex 822.956 345.212 79.5924 + vertex 826.99 339.949 86.5768 + endloop + endfacet + facet normal -0.88608 -0.440754 0.143518 + outer loop + vertex 827.485 341.3 93.7855 + vertex 823.774 346.422 86.6011 + vertex 826.99 339.949 86.5768 + endloop + endfacet + facet normal -0.897374 -0.418436 0.140113 + outer loop + vertex 827.485 341.3 93.7855 + vertex 826.99 339.949 86.5768 + vertex 830.492 334.845 93.7635 + endloop + endfacet + facet normal -0.900225 -0.419682 0.116029 + outer loop + vertex 830.794 336.246 101.176 + vertex 827.485 341.3 93.7855 + vertex 830.492 334.845 93.7635 + endloop + endfacet + facet normal -0.91488 -0.388257 0.110686 + outer loop + vertex 830.794 336.246 101.176 + vertex 830.492 334.845 93.7635 + vertex 833.562 329.723 101.177 + endloop + endfacet + facet normal -0.916517 -0.388955 0.0933302 + outer loop + vertex 833.76 331.076 108.76 + vertex 830.794 336.246 101.176 + vertex 833.562 329.723 101.177 + endloop + endfacet + facet normal -0.933577 -0.347799 0.0864291 + outer loop + vertex 833.76 331.076 108.76 + vertex 833.562 329.723 101.177 + vertex 836.244 324.422 108.817 + endloop + endfacet + facet normal -0.934575 -0.348292 0.0725441 + outer loop + vertex 836.377 325.671 116.515 + vertex 833.76 331.076 108.76 + vertex 836.244 324.422 108.817 + endloop + endfacet + facet normal -0.933443 -0.351899 0.0696477 + outer loop + vertex 833.892 332.253 116.47 + vertex 833.76 331.076 108.76 + vertex 836.377 325.671 116.515 + endloop + endfacet + facet normal -0.934051 -0.3522 0.0591989 + outer loop + vertex 836.465 326.744 124.297 + vertex 833.892 332.253 116.47 + vertex 836.377 325.671 116.515 + endloop + endfacet + facet normal -0.932405 -0.357182 0.0551509 + outer loop + vertex 833.969 333.254 124.269 + vertex 833.892 332.253 116.47 + vertex 836.465 326.744 124.297 + endloop + endfacet + facet normal -0.932795 -0.357367 0.046727 + outer loop + vertex 836.513 327.646 132.147 + vertex 833.969 333.254 124.269 + vertex 836.465 326.744 124.297 + endloop + endfacet + facet normal -0.931848 -0.360114 0.0444657 + outer loop + vertex 834.017 334.102 132.128 + vertex 833.969 333.254 124.269 + vertex 836.513 327.646 132.147 + endloop + endfacet + facet normal -0.93208 -0.360221 0.0383009 + outer loop + vertex 836.546 328.398 140.036 + vertex 834.017 334.102 132.128 + vertex 836.513 327.646 132.147 + endloop + endfacet + facet normal -0.931076 -0.36305 0.0359394 + outer loop + vertex 834.049 334.8 140.021 + vertex 834.017 334.102 132.128 + vertex 836.546 328.398 140.036 + endloop + endfacet + facet normal -0.931248 -0.363131 0.0302324 + outer loop + vertex 836.572 328.99 147.927 + vertex 834.049 334.8 140.021 + vertex 836.546 328.398 140.036 + endloop + endfacet + facet normal -0.930036 -0.366445 0.0274104 + outer loop + vertex 834.07 335.338 147.91 + vertex 834.049 334.8 140.021 + vertex 836.572 328.99 147.927 + endloop + endfacet + facet normal -0.930175 -0.366518 0.0209504 + outer loop + vertex 836.585 329.406 155.785 + vertex 834.07 335.338 147.91 + vertex 836.572 328.99 147.927 + endloop + endfacet + facet normal -0.929988 -0.367016 0.020515 + outer loop + vertex 834.09 335.727 155.764 + vertex 834.07 335.338 147.91 + vertex 836.585 329.406 155.785 + endloop + endfacet + facet normal -0.930084 -0.367074 0.0141688 + outer loop + vertex 836.6 329.668 163.606 + vertex 834.09 335.727 155.764 + vertex 836.585 329.406 155.785 + endloop + endfacet + facet normal -0.929187 -0.369412 0.012076 + outer loop + vertex 834.099 335.959 163.585 + vertex 834.09 335.727 155.764 + vertex 836.6 329.668 163.606 + endloop + endfacet + facet normal -0.929238 -0.369458 0.004144 + outer loop + vertex 836.599 329.758 171.43 + vertex 834.099 335.959 163.585 + vertex 836.6 329.668 163.606 + endloop + endfacet + facet normal -0.929416 -0.369005 0.00455906 + outer loop + vertex 834.103 336.047 171.409 + vertex 834.099 335.959 163.585 + vertex 836.599 329.758 171.43 + endloop + endfacet + facet normal -0.92941 -0.369031 -0.00366568 + outer loop + vertex 836.595 329.692 179.301 + vertex 834.103 336.047 171.409 + vertex 836.599 329.758 171.43 + endloop + endfacet + facet normal -0.929396 -0.369065 -0.00369753 + outer loop + vertex 834.097 335.982 179.281 + vertex 834.103 336.047 171.409 + vertex 836.595 329.692 179.301 + endloop + endfacet + facet normal -0.929325 -0.369063 -0.0121473 + outer loop + vertex 836.584 329.457 187.242 + vertex 834.097 335.982 179.281 + vertex 836.595 329.692 179.301 + endloop + endfacet + facet normal -0.929667 -0.368227 -0.0113552 + outer loop + vertex 834.085 335.767 187.222 + vertex 834.097 335.982 179.281 + vertex 836.584 329.457 187.242 + endloop + endfacet + facet normal -0.929492 -0.36819 -0.0219364 + outer loop + vertex 836.561 329.039 195.235 + vertex 834.085 335.767 187.222 + vertex 836.584 329.457 187.242 + endloop + endfacet + facet normal -0.930883 -0.364838 -0.0186923 + outer loop + vertex 834.069 335.399 195.21 + vertex 834.085 335.767 187.222 + vertex 836.561 329.039 195.235 + endloop + endfacet + facet normal -0.930639 -0.364784 -0.0290426 + outer loop + vertex 836.537 328.463 203.228 + vertex 834.069 335.399 195.21 + vertex 836.561 329.039 195.235 + endloop + endfacet + facet normal -0.931076 -0.363749 -0.028013 + outer loop + vertex 834.038 334.863 203.193 + vertex 834.069 335.399 195.21 + vertex 836.537 328.463 203.228 + endloop + endfacet + facet normal -0.930797 -0.363687 -0.0367235 + outer loop + vertex 836.508 327.737 211.169 + vertex 834.038 334.863 203.193 + vertex 836.537 328.463 203.228 + endloop + endfacet + facet normal -0.931927 -0.361048 -0.0340159 + outer loop + vertex 834.009 334.19 211.121 + vertex 834.038 334.863 203.193 + vertex 836.508 327.737 211.169 + endloop + endfacet + facet normal -0.931435 -0.360949 -0.0463102 + outer loop + vertex 836.461 326.85 219.028 + vertex 834.009 334.19 211.121 + vertex 836.508 327.737 211.169 + endloop + endfacet + facet normal -0.93288 -0.357638 -0.042788 + outer loop + vertex 833.968 333.359 218.97 + vertex 834.009 334.19 211.121 + vertex 836.461 326.85 219.028 + endloop + endfacet + facet normal -0.932169 -0.357492 -0.0570999 + outer loop + vertex 836.388 325.797 226.805 + vertex 833.968 333.359 218.97 + vertex 836.461 326.85 219.028 + endloop + endfacet + facet normal -0.9338 -0.353838 -0.0530682 + outer loop + vertex 833.904 332.362 226.739 + vertex 833.968 333.359 218.97 + vertex 836.388 325.797 226.805 + endloop + endfacet + facet normal -0.932638 -0.353586 -0.0718634 + outer loop + vertex 836.268 324.55 234.505 + vertex 833.904 332.362 226.739 + vertex 836.388 325.797 226.805 + endloop + endfacet + facet normal -0.934678 -0.349165 -0.0667943 + outer loop + vertex 833.792 331.191 234.433 + vertex 833.904 332.362 226.739 + vertex 836.268 324.55 234.505 + endloop + endfacet + facet normal -0.932884 -0.348747 -0.0900195 + outer loop + vertex 836.071 323.109 242.124 + vertex 833.792 331.191 234.433 + vertex 836.268 324.55 234.505 + endloop + endfacet + facet normal -0.935578 -0.343145 -0.0833342 + outer loop + vertex 833.602 329.859 242.046 + vertex 833.792 331.191 234.433 + vertex 836.071 323.109 242.124 + endloop + endfacet + facet normal -0.932515 -0.342386 -0.11484 + outer loop + vertex 835.746 321.476 249.632 + vertex 833.602 329.859 242.046 + vertex 836.071 323.109 242.124 + endloop + endfacet + facet normal -0.935747 -0.336067 -0.106943 + outer loop + vertex 833.282 328.364 249.552 + vertex 833.602 329.859 242.046 + vertex 835.746 321.476 249.632 + endloop + endfacet + facet normal -0.93087 -0.334778 -0.146303 + outer loop + vertex 835.243 319.657 256.995 + vertex 833.282 328.364 249.552 + vertex 835.746 321.476 249.632 + endloop + endfacet + facet normal -0.934551 -0.328155 -0.137584 + outer loop + vertex 832.781 326.703 256.917 + vertex 833.282 328.364 249.552 + vertex 835.243 319.657 256.995 + endloop + endfacet + facet normal -0.91214 -0.406891 0.0493912 + outer loop + vertex 834.017 334.102 132.128 + vertex 831.189 339.491 124.293 + vertex 833.969 333.254 124.269 + endloop + endfacet + facet normal -0.911758 -0.406749 0.0570312 + outer loop + vertex 831.189 339.491 124.293 + vertex 831.11 338.573 116.49 + vertex 833.969 333.254 124.269 + endloop + endfacet + facet normal -0.893396 -0.445061 0.0613495 + outer loop + vertex 831.189 339.491 124.293 + vertex 828.091 344.638 116.516 + vertex 831.11 338.573 116.49 + endloop + endfacet + facet normal -0.892889 -0.444845 0.0697267 + outer loop + vertex 828.091 344.638 116.516 + vertex 827.966 343.677 108.797 + vertex 831.11 338.573 116.49 + endloop + endfacet + facet normal -0.895696 -0.438253 0.075247 + outer loop + vertex 831.11 338.573 116.49 + vertex 827.966 343.677 108.797 + vertex 830.988 337.497 108.768 + endloop + endfacet + facet normal -0.912914 -0.402021 0.0704703 + outer loop + vertex 831.11 338.573 116.49 + vertex 830.988 337.497 108.768 + vertex 833.892 332.253 116.47 + endloop + endfacet + facet normal -0.894884 -0.437906 0.0861449 + outer loop + vertex 827.966 343.677 108.797 + vertex 827.782 342.56 101.201 + vertex 830.988 337.497 108.768 + endloop + endfacet + facet normal -0.898457 -0.428959 0.0936448 + outer loop + vertex 830.988 337.497 108.768 + vertex 827.782 342.56 101.201 + vertex 830.794 336.246 101.176 + endloop + endfacet + facet normal -0.881328 -0.463923 0.0896428 + outer loop + vertex 827.966 343.677 108.797 + vertex 824.56 348.684 101.222 + vertex 827.782 342.56 101.201 + endloop + endfacet + facet normal -0.880128 -0.46334 0.103401 + outer loop + vertex 824.56 348.684 101.222 + vertex 824.266 347.588 93.8095 + vertex 827.782 342.56 101.201 + endloop + endfacet + facet normal -0.884351 -0.453093 0.112381 + outer loop + vertex 827.782 342.56 101.201 + vertex 824.266 347.588 93.8095 + vertex 827.485 341.3 93.7855 + endloop + endfacet + facet normal -0.871491 -0.478959 0.105368 + outer loop + vertex 824.56 348.684 101.222 + vertex 820.879 353.755 93.8263 + vertex 824.266 347.588 93.8095 + endloop + endfacet + facet normal -0.869577 -0.477958 0.124066 + outer loop + vertex 820.879 353.755 93.8263 + vertex 820.385 352.782 86.6136 + vertex 824.266 347.588 93.8095 + endloop + endfacet + facet normal -0.874336 -0.466115 0.13518 + outer loop + vertex 824.266 347.588 93.8095 + vertex 820.385 352.782 86.6136 + vertex 823.774 346.422 86.6011 + endloop + endfacet + facet normal -0.865523 -0.485084 0.12475 + outer loop + vertex 820.879 353.755 93.8263 + vertex 816.863 359.066 86.6137 + vertex 820.385 352.782 86.6136 + endloop + endfacet + facet normal -0.86191 -0.48306 0.154159 + outer loop + vertex 816.863 359.066 86.6137 + vertex 816.039 358.292 79.5795 + vertex 820.385 352.782 86.6136 + endloop + endfacet + facet normal -0.866812 -0.469569 0.167757 + outer loop + vertex 820.385 352.782 86.6136 + vertex 816.039 358.292 79.5795 + vertex 819.563 351.794 79.6002 + endloop + endfacet + facet normal -0.862284 -0.482401 0.154131 + outer loop + vertex 816.863 359.066 86.6137 + vertex 812.424 364.737 79.5292 + vertex 816.039 358.292 79.5795 + endloop + endfacet + facet normal -0.855766 -0.478412 0.196944 + outer loop + vertex 812.424 364.737 79.5292 + vertex 811.193 364.14 72.7282 + vertex 816.039 358.292 79.5795 + endloop + endfacet + facet normal -0.859982 -0.464166 0.212086 + outer loop + vertex 816.039 358.292 79.5795 + vertex 811.193 364.14 72.7282 + vertex 814.813 357.465 72.7982 + endloop + endfacet + facet normal -0.849248 -0.457809 0.263039 + outer loop + vertex 811.193 364.14 72.7282 + vertex 809.705 363.277 66.4235 + vertex 814.813 357.465 72.7982 + endloop + endfacet + facet normal -0.855278 -0.446514 0.262915 + outer loop + vertex 811.193 364.14 72.7282 + vertex 806.05 370.235 66.3485 + vertex 809.705 363.277 66.4235 + endloop + endfacet + facet normal -0.85191 -0.463272 0.244191 + outer loop + vertex 807.546 370.805 72.6478 + vertex 806.05 370.235 66.3485 + vertex 811.193 364.14 72.7282 + endloop + endfacet + facet normal -0.871655 -0.424286 0.245354 + outer loop + vertex 807.546 370.805 72.6478 + vertex 802.61 377.321 66.383 + vertex 806.05 370.235 66.3485 + endloop + endfacet + facet normal -0.868274 -0.443051 0.223172 + outer loop + vertex 804.117 377.54 72.6783 + vertex 802.61 377.321 66.383 + vertex 807.546 370.805 72.6478 + endloop + endfacet + facet normal -0.876023 -0.446808 0.18151 + outer loop + vertex 808.771 371.173 79.4709 + vertex 804.117 377.54 72.6783 + vertex 807.546 370.805 72.6478 + endloop + endfacet + facet normal -0.856186 -0.484309 0.179974 + outer loop + vertex 808.771 371.173 79.4709 + vertex 807.546 370.805 72.6478 + vertex 812.424 364.737 79.5292 + endloop + endfacet + facet normal -0.861613 -0.487748 0.140446 + outer loop + vertex 813.256 365.302 86.5925 + vertex 808.771 371.173 79.4709 + vertex 812.424 364.737 79.5292 + endloop + endfacet + facet normal -0.85593 -0.501657 0.1254 + outer loop + vertex 809.6 371.532 86.5617 + vertex 808.771 371.173 79.4709 + vertex 813.256 365.302 86.5925 + endloop + endfacet + facet normal -0.85844 -0.50326 0.0990433 + outer loop + vertex 813.754 365.877 93.8365 + vertex 809.6 371.532 86.5617 + vertex 813.256 365.302 86.5925 + endloop + endfacet + facet normal -0.853945 -0.510794 0.0993324 + outer loop + vertex 813.754 365.877 93.8365 + vertex 813.256 365.302 86.5925 + vertex 817.366 359.84 93.8351 + endloop + endfacet + facet normal -0.855118 -0.511493 0.0845447 + outer loop + vertex 817.659 360.574 101.243 + vertex 813.754 365.877 93.8365 + vertex 817.366 359.84 93.8351 + endloop + endfacet + facet normal -0.855957 -0.510105 0.0844403 + outer loop + vertex 817.659 360.574 101.243 + vertex 817.366 359.84 93.8351 + vertex 821.174 354.674 101.235 + endloop + endfacet + facet normal -0.856568 -0.510456 0.0756698 + outer loop + vertex 821.36 355.486 108.816 + vertex 817.659 360.574 101.243 + vertex 821.174 354.674 101.235 + endloop + endfacet + facet normal -0.862242 -0.500944 0.0747896 + outer loop + vertex 821.36 355.486 108.816 + vertex 821.174 354.674 101.235 + vertex 824.747 349.655 108.811 + endloop + endfacet + facet normal -0.862698 -0.501202 0.0674509 + outer loop + vertex 824.869 350.483 116.525 + vertex 821.36 355.486 108.816 + vertex 824.747 349.655 108.811 + endloop + endfacet + facet normal -0.873868 -0.481725 0.0655377 + outer loop + vertex 824.869 350.483 116.525 + vertex 824.747 349.655 108.811 + vertex 828.091 344.638 116.516 + endloop + endfacet + facet normal -0.874265 -0.481932 0.0583224 + outer loop + vertex 828.166 345.446 124.317 + vertex 824.869 350.483 116.525 + vertex 828.091 344.638 116.516 + endloop + endfacet + facet normal -0.870874 -0.488692 0.0525182 + outer loop + vertex 824.947 351.183 124.323 + vertex 824.869 350.483 116.525 + vertex 828.166 345.446 124.317 + endloop + endfacet + facet normal -0.871099 -0.488813 0.047423 + outer loop + vertex 828.213 346.124 132.175 + vertex 824.947 351.183 124.323 + vertex 828.166 345.446 124.317 + endloop + endfacet + facet normal -0.887994 -0.457663 0.0448352 + outer loop + vertex 828.213 346.124 132.175 + vertex 828.166 345.446 124.317 + vertex 831.235 340.258 132.152 + endloop + endfacet + facet normal -0.888204 -0.457751 0.0394623 + outer loop + vertex 831.264 340.882 140.044 + vertex 828.213 346.124 132.175 + vertex 831.235 340.258 132.152 + endloop + endfacet + facet normal -0.90854 -0.416221 0.0362505 + outer loop + vertex 831.264 340.882 140.044 + vertex 831.235 340.258 132.152 + vertex 834.049 334.8 140.021 + endloop + endfacet + facet normal -0.908716 -0.416281 0.0307516 + outer loop + vertex 834.07 335.338 147.91 + vertex 831.264 340.882 140.044 + vertex 834.049 334.8 140.021 + endloop + endfacet + facet normal -0.90764 -0.418773 0.028611 + outer loop + vertex 831.287 341.37 147.931 + vertex 831.264 340.882 140.044 + vertex 834.07 335.338 147.91 + endloop + endfacet + facet normal -0.907778 -0.418817 0.0230265 + outer loop + vertex 834.09 335.727 155.764 + vertex 831.287 341.37 147.931 + vertex 834.07 335.338 147.91 + endloop + endfacet + facet normal -0.90652 -0.421663 0.020526 + outer loop + vertex 831.304 341.717 155.785 + vertex 831.287 341.37 147.931 + vertex 834.09 335.727 155.764 + endloop + endfacet + facet normal -0.906636 -0.421694 0.0136024 + outer loop + vertex 834.099 335.959 163.585 + vertex 831.304 341.717 155.785 + vertex 834.09 335.727 155.764 + endloop + endfacet + facet normal -0.906353 -0.422319 0.0130391 + outer loop + vertex 831.316 341.932 163.605 + vertex 831.304 341.717 155.785 + vertex 834.099 335.959 163.585 + endloop + endfacet + facet normal -0.906428 -0.422329 0.00514425 + outer loop + vertex 834.103 336.047 171.409 + vertex 831.316 341.932 163.605 + vertex 834.099 335.959 163.585 + endloop + endfacet + facet normal -0.905775 -0.423742 0.00384478 + outer loop + vertex 831.317 342.002 171.428 + vertex 831.316 341.932 163.605 + vertex 834.103 336.047 171.409 + endloop + endfacet + facet normal -0.905784 -0.42372 -0.00412759 + outer loop + vertex 834.097 335.982 179.281 + vertex 831.317 342.002 171.428 + vertex 834.103 336.047 171.409 + endloop + endfacet + facet normal -0.906253 -0.422723 -0.00319736 + outer loop + vertex 831.315 341.946 179.3 + vertex 831.317 342.002 171.428 + vertex 834.097 335.982 179.281 + endloop + endfacet + facet normal -0.906196 -0.422665 -0.0127965 + outer loop + vertex 834.085 335.767 187.222 + vertex 831.315 341.946 179.3 + vertex 834.097 335.982 179.281 + endloop + endfacet + facet normal -0.906505 -0.42202 -0.0121847 + outer loop + vertex 831.302 341.745 187.241 + vertex 831.315 341.946 179.3 + vertex 834.085 335.767 187.222 + endloop + endfacet + facet normal -0.906378 -0.421932 -0.0212689 + outer loop + vertex 834.069 335.399 195.21 + vertex 831.302 341.745 187.241 + vertex 834.085 335.767 187.222 + endloop + endfacet + facet normal -0.907191 -0.42026 -0.0196552 + outer loop + vertex 831.286 341.407 195.225 + vertex 831.302 341.745 187.241 + vertex 834.069 335.399 195.21 + endloop + endfacet + facet normal -0.906921 -0.420106 -0.031708 + outer loop + vertex 834.038 334.863 203.193 + vertex 831.286 341.407 195.225 + vertex 834.069 335.399 195.21 + endloop + endfacet + facet normal -0.908811 -0.416273 -0.0279077 + outer loop + vertex 831.262 340.923 203.199 + vertex 831.286 341.407 195.225 + vertex 834.038 334.863 203.193 + endloop + endfacet + facet normal -0.908491 -0.416117 -0.0386024 + outer loop + vertex 834.009 334.19 211.121 + vertex 831.262 340.923 203.199 + vertex 834.038 334.863 203.193 + endloop + endfacet + facet normal -0.910226 -0.412626 -0.0350345 + outer loop + vertex 831.238 340.305 211.118 + vertex 831.262 340.923 203.199 + vertex 834.009 334.19 211.121 + endloop + endfacet + facet normal -0.909712 -0.412401 -0.0484684 + outer loop + vertex 833.968 333.359 218.97 + vertex 831.238 340.305 211.118 + vertex 834.009 334.19 211.121 + endloop + endfacet + facet normal -0.911045 -0.40977 -0.045678 + outer loop + vertex 831.195 339.526 218.958 + vertex 831.238 340.305 211.118 + vertex 833.968 333.359 218.97 + endloop + endfacet + facet normal -0.910342 -0.409482 -0.0600115 + outer loop + vertex 833.904 332.362 226.739 + vertex 831.195 339.526 218.958 + vertex 833.968 333.359 218.97 + endloop + endfacet + facet normal -0.912892 -0.404538 -0.0545716 + outer loop + vertex 831.135 338.613 226.722 + vertex 831.195 339.526 218.958 + vertex 833.904 332.362 226.739 + endloop + endfacet + facet normal -0.911671 -0.404052 -0.0748124 + outer loop + vertex 833.792 331.191 234.433 + vertex 831.135 338.613 226.722 + vertex 833.904 332.362 226.739 + endloop + endfacet + facet normal -0.914813 -0.398109 -0.0680101 + outer loop + vertex 831.026 337.549 234.413 + vertex 831.135 338.613 226.722 + vertex 833.792 331.191 234.433 + endloop + endfacet + facet normal -0.912997 -0.397397 -0.092264 + outer loop + vertex 833.602 329.859 242.046 + vertex 831.026 337.549 234.413 + vertex 833.792 331.191 234.433 + endloop + endfacet + facet normal -0.916097 -0.391732 -0.0855116 + outer loop + vertex 830.834 336.339 242.023 + vertex 831.026 337.549 234.413 + vertex 833.602 329.859 242.046 + endloop + endfacet + facet normal -0.913126 -0.390577 -0.116838 + outer loop + vertex 833.282 328.364 249.552 + vertex 830.834 336.339 242.023 + vertex 833.602 329.859 242.046 + endloop + endfacet + facet normal -0.918139 -0.381833 -0.105946 + outer loop + vertex 830.524 335.002 249.527 + vertex 830.834 336.339 242.023 + vertex 833.282 328.364 249.552 + endloop + endfacet + facet normal -0.913138 -0.379912 -0.147801 + outer loop + vertex 832.781 326.703 256.917 + vertex 830.524 335.002 249.527 + vertex 833.282 328.364 249.552 + endloop + endfacet + facet normal -0.917895 -0.372179 -0.137663 + outer loop + vertex 830.024 333.51 256.891 + vertex 830.524 335.002 249.527 + vertex 832.781 326.703 256.917 + endloop + endfacet + facet normal -0.895361 -0.420738 -0.145976 + outer loop + vertex 830.024 333.51 256.891 + vertex 827.505 341.421 249.54 + vertex 830.524 335.002 249.527 + endloop + endfacet + facet normal -0.900073 -0.423037 -0.104442 + outer loop + vertex 827.505 341.421 249.54 + vertex 827.817 342.609 242.04 + vertex 830.524 335.002 249.527 + endloop + endfacet + facet normal -0.895421 -0.430465 -0.11367 + outer loop + vertex 830.524 335.002 249.527 + vertex 827.817 342.609 242.04 + vertex 830.834 336.339 242.023 + endloop + endfacet + facet normal -0.898119 -0.431847 -0.0830078 + outer loop + vertex 827.817 342.609 242.04 + vertex 828.006 343.679 234.431 + vertex 830.834 336.339 242.023 + endloop + endfacet + facet normal -0.893266 -0.43989 -0.0925921 + outer loop + vertex 830.834 336.339 242.023 + vertex 828.006 343.679 234.431 + vertex 831.026 337.549 234.413 + endloop + endfacet + facet normal -0.895078 -0.44086 -0.0669162 + outer loop + vertex 828.006 343.679 234.431 + vertex 828.116 344.624 226.74 + vertex 831.026 337.549 234.413 + endloop + endfacet + facet normal -0.891182 -0.447486 -0.0745032 + outer loop + vertex 831.026 337.549 234.413 + vertex 828.116 344.624 226.74 + vertex 831.135 338.613 226.722 + endloop + endfacet + facet normal -0.892289 -0.448101 -0.0550079 + outer loop + vertex 828.116 344.624 226.74 + vertex 828.182 345.446 218.978 + vertex 831.135 338.613 226.722 + endloop + endfacet + facet normal -0.88965 -0.452678 -0.0600528 + outer loop + vertex 831.135 338.613 226.722 + vertex 828.182 345.446 218.978 + vertex 831.195 339.526 218.958 + endloop + endfacet + facet normal -0.890381 -0.453104 -0.0438023 + outer loop + vertex 828.182 345.446 218.978 + vertex 828.218 346.132 211.138 + vertex 831.195 339.526 218.958 + endloop + endfacet + facet normal -0.886799 -0.45939 -0.0504749 + outer loop + vertex 831.195 339.526 218.958 + vertex 828.218 346.132 211.138 + vertex 831.238 340.305 211.118 + endloop + endfacet + facet normal -0.887354 -0.459727 -0.0354211 + outer loop + vertex 828.218 346.132 211.138 + vertex 828.244 346.692 203.22 + vertex 831.238 340.305 211.118 + endloop + endfacet + facet normal -0.885433 -0.463135 -0.0389052 + outer loop + vertex 831.238 340.305 211.118 + vertex 828.244 346.692 203.22 + vertex 831.262 340.923 203.199 + endloop + endfacet + facet normal -0.885763 -0.463351 -0.0270222 + outer loop + vertex 828.244 346.692 203.22 + vertex 828.263 347.121 195.247 + vertex 831.262 340.923 203.199 + endloop + endfacet + facet normal -0.88356 -0.467297 -0.0309278 + outer loop + vertex 831.262 340.923 203.199 + vertex 828.263 347.121 195.247 + vertex 831.286 341.407 195.225 + endloop + endfacet + facet normal -0.883781 -0.467455 -0.0204175 + outer loop + vertex 828.263 347.121 195.247 + vertex 828.282 347.433 187.264 + vertex 831.286 341.407 195.225 + endloop + endfacet + facet normal -0.883071 -0.468739 -0.0216567 + outer loop + vertex 831.286 341.407 195.225 + vertex 828.282 347.433 187.264 + vertex 831.302 341.745 187.241 + endloop + endfacet + facet normal -0.883203 -0.468849 -0.011545 + outer loop + vertex 828.282 347.433 187.264 + vertex 828.292 347.611 179.323 + vertex 831.302 341.745 187.241 + endloop + endfacet + facet normal -0.882145 -0.470787 -0.0133824 + outer loop + vertex 831.302 341.745 187.241 + vertex 828.292 347.611 179.323 + vertex 831.315 341.946 179.3 + endloop + endfacet + facet normal -0.882202 -0.470855 -0.00395803 + outer loop + vertex 828.292 347.611 179.323 + vertex 828.296 347.669 171.45 + vertex 831.315 341.946 179.3 + endloop + endfacet + facet normal -0.882447 -0.470398 -0.0035306 + outer loop + vertex 831.315 341.946 179.3 + vertex 828.296 347.669 171.45 + vertex 831.317 342.002 171.428 + endloop + endfacet + facet normal -0.88243 -0.47042 0.00475334 + outer loop + vertex 828.296 347.669 171.45 + vertex 828.29 347.6 163.626 + vertex 831.317 342.002 171.428 + endloop + endfacet + facet normal -0.860745 -0.509011 0.00507357 + outer loop + vertex 828.296 347.669 171.45 + vertex 825.07 353.046 163.632 + vertex 828.29 347.6 163.626 + endloop + endfacet + facet normal -0.860697 -0.50899 0.0113759 + outer loop + vertex 825.07 353.046 163.632 + vertex 825.061 352.887 155.812 + vertex 828.29 347.6 163.626 + endloop + endfacet + facet normal -0.861813 -0.507056 0.0131453 + outer loop + vertex 828.29 347.6 163.626 + vertex 825.061 352.887 155.812 + vertex 828.28 347.415 155.806 + endloop + endfacet + facet normal -0.882081 -0.470936 0.0123147 + outer loop + vertex 828.29 347.6 163.626 + vertex 828.28 347.415 155.806 + vertex 831.316 341.932 163.605 + endloop + endfacet + facet normal -0.861725 -0.507012 0.0191892 + outer loop + vertex 825.061 352.887 155.812 + vertex 825.043 352.619 147.958 + vertex 828.28 347.415 155.806 + endloop + endfacet + facet normal -0.863285 -0.504251 0.0216628 + outer loop + vertex 828.28 347.415 155.806 + vertex 825.043 352.619 147.958 + vertex 828.263 347.106 147.952 + endloop + endfacet + facet normal -0.883103 -0.468739 0.0203101 + outer loop + vertex 828.28 347.415 155.806 + vertex 828.263 347.106 147.952 + vertex 831.304 341.717 155.785 + endloop + endfacet + facet normal -0.863188 -0.504199 0.0262596 + outer loop + vertex 825.043 352.619 147.958 + vertex 825.021 352.246 140.07 + vertex 828.263 347.106 147.952 + endloop + endfacet + facet normal -0.865465 -0.500077 0.029884 + outer loop + vertex 828.263 347.106 147.952 + vertex 825.021 352.246 140.07 + vertex 828.24 346.675 140.065 + endloop + endfacet + facet normal -0.884198 -0.466268 0.0280883 + outer loop + vertex 828.263 347.106 147.952 + vertex 828.24 346.675 140.065 + vertex 831.287 341.37 147.931 + endloop + endfacet + facet normal -0.865355 -0.500017 0.0338243 + outer loop + vertex 825.021 352.246 140.07 + vertex 824.99 351.766 132.18 + vertex 828.24 346.675 140.065 + endloop + endfacet + facet normal -0.867703 -0.495659 0.0376062 + outer loop + vertex 828.24 346.675 140.065 + vertex 824.99 351.766 132.18 + vertex 828.213 346.124 132.175 + endloop + endfacet + facet normal -0.85033 -0.525066 0.0352894 + outer loop + vertex 825.021 352.246 140.07 + vertex 821.602 357.252 132.176 + vertex 824.99 351.766 132.18 + endloop + endfacet + facet normal -0.850256 -0.525018 0.0376822 + outer loop + vertex 821.602 357.252 132.176 + vertex 821.557 356.762 124.32 + vertex 824.99 351.766 132.18 + endloop + endfacet + facet normal -0.853835 -0.518745 0.0432329 + outer loop + vertex 824.99 351.766 132.18 + vertex 821.557 356.762 124.32 + vertex 824.947 351.183 124.323 + endloop + endfacet + facet normal -0.85368 -0.518648 0.0472708 + outer loop + vertex 821.557 356.762 124.32 + vertex 821.48 356.178 116.525 + vertex 824.947 351.183 124.323 + endloop + endfacet + facet normal -0.845311 -0.532097 0.0481965 + outer loop + vertex 821.557 356.762 124.32 + vertex 817.959 361.772 116.521 + vertex 821.48 356.178 116.525 + endloop + endfacet + facet normal -0.845199 -0.532024 0.0508867 + outer loop + vertex 817.959 361.772 116.521 + vertex 817.841 361.222 108.818 + vertex 821.48 356.178 116.525 + endloop + endfacet + facet normal -0.850841 -0.521971 0.0601311 + outer loop + vertex 821.48 356.178 116.525 + vertex 817.841 361.222 108.818 + vertex 821.36 355.486 108.816 + endloop + endfacet + facet normal -0.841845 -0.537284 0.0512114 + outer loop + vertex 817.959 361.772 116.521 + vertex 814.22 366.895 108.822 + vertex 817.841 361.222 108.818 + endloop + endfacet + facet normal -0.841753 -0.537227 0.053281 + outer loop + vertex 814.22 366.895 108.822 + vertex 814.044 366.42 101.251 + vertex 817.841 361.222 108.818 + endloop + endfacet + facet normal -0.848722 -0.52479 0.0653229 + outer loop + vertex 817.841 361.222 108.818 + vertex 814.044 366.42 101.251 + vertex 817.659 360.574 101.243 + endloop + endfacet + facet normal -0.845853 -0.53078 0.0529718 + outer loop + vertex 814.22 366.895 108.822 + vertex 810.39 372.245 101.257 + vertex 814.044 366.42 101.251 + endloop + endfacet + facet normal -0.845641 -0.530651 0.057448 + outer loop + vertex 810.39 372.245 101.257 + vertex 810.101 371.901 93.8321 + vertex 814.044 366.42 101.251 + endloop + endfacet + facet normal -0.8529 -0.517189 0.0712517 + outer loop + vertex 814.044 366.42 101.251 + vertex 810.101 371.901 93.8321 + vertex 813.754 365.877 93.8365 + endloop + endfacet + facet normal -0.865619 -0.497484 0.0566888 + outer loop + vertex 810.39 372.245 101.257 + vertex 806.6 377.993 93.84 + vertex 810.101 371.901 93.8321 + endloop + endfacet + facet normal -0.864856 -0.497063 0.0703749 + outer loop + vertex 806.6 377.993 93.84 + vertex 806.099 377.835 86.5683 + vertex 810.101 371.901 93.8321 + endloop + endfacet + facet normal -0.871068 -0.483819 0.0846165 + outer loop + vertex 810.101 371.901 93.8321 + vertex 806.099 377.835 86.5683 + vertex 809.6 371.532 86.5617 + endloop + endfacet + facet normal -0.868966 -0.482678 0.109182 + outer loop + vertex 806.099 377.835 86.5683 + vertex 805.294 377.681 79.4762 + vertex 809.6 371.532 86.5617 + endloop + endfacet + facet normal -0.915107 -0.387243 0.112346 + outer loop + vertex 806.099 377.835 86.5683 + vertex 802.465 384.411 79.6268 + vertex 805.294 377.681 79.4762 + endloop + endfacet + facet normal -0.9121 -0.386523 0.136654 + outer loop + vertex 802.465 384.411 79.6268 + vertex 801.425 384.478 72.8769 + vertex 805.294 377.681 79.4762 + endloop + endfacet + facet normal -0.917679 -0.360786 0.166431 + outer loop + vertex 805.294 377.681 79.4762 + vertex 801.425 384.478 72.8769 + vertex 804.117 377.54 72.6783 + endloop + endfacet + facet normal -0.912215 -0.359527 0.196477 + outer loop + vertex 801.425 384.478 72.8769 + vertex 800.054 384.55 66.6435 + vertex 804.117 377.54 72.6783 + endloop + endfacet + facet normal -0.909586 -0.405074 0.0925637 + outer loop + vertex 803.2 384.352 86.5938 + vertex 802.465 384.411 79.6268 + vertex 806.099 377.835 86.5683 + endloop + endfacet + facet normal -0.911195 -0.405708 0.0715876 + outer loop + vertex 806.6 377.993 93.84 + vertex 803.2 384.352 86.5938 + vertex 806.099 377.835 86.5683 + endloop + endfacet + facet normal -0.907231 -0.416265 0.0604633 + outer loop + vertex 803.706 384.299 93.8248 + vertex 803.2 384.352 86.5938 + vertex 806.6 377.993 93.84 + endloop + endfacet + facet normal -0.907996 -0.416655 0.0440732 + outer loop + vertex 806.895 378.136 101.27 + vertex 803.706 384.299 93.8248 + vertex 806.6 377.993 93.84 + endloop + endfacet + facet normal -0.905065 -0.423659 0.0370208 + outer loop + vertex 804.033 384.252 101.281 + vertex 803.706 384.299 93.8248 + vertex 806.895 378.136 101.27 + endloop + endfacet + facet normal -0.905358 -0.423779 0.0271793 + outer loop + vertex 807.066 378.259 108.854 + vertex 804.033 384.252 101.281 + vertex 806.895 378.136 101.27 + endloop + endfacet + facet normal -0.85297 -0.521231 0.0275763 + outer loop + vertex 807.066 378.259 108.854 + vertex 806.895 378.136 101.27 + vertex 810.557 372.544 108.825 + endloop + endfacet + facet normal -0.852948 -0.521221 0.0284254 + outer loop + vertex 810.659 372.797 116.516 + vertex 807.066 378.259 108.854 + vertex 810.557 372.544 108.825 + endloop + endfacet + facet normal -0.831192 -0.555216 0.0292586 + outer loop + vertex 810.659 372.797 116.516 + vertex 810.557 372.544 108.825 + vertex 814.331 367.299 116.517 + endloop + endfacet + facet normal -0.831125 -0.555171 0.0318812 + outer loop + vertex 814.401 367.642 124.305 + vertex 810.659 372.797 116.516 + vertex 814.331 367.299 116.517 + endloop + endfacet + facet normal -0.829764 -0.557199 0.0319584 + outer loop + vertex 814.401 367.642 124.305 + vertex 814.331 367.299 116.517 + vertex 818.03 362.238 124.314 + endloop + endfacet + facet normal -0.829743 -0.557183 0.0327683 + outer loop + vertex 818.077 362.63 132.168 + vertex 814.401 367.642 124.305 + vertex 818.03 362.238 124.314 + endloop + endfacet + facet normal -0.835905 -0.54792 0.0323425 + outer loop + vertex 818.077 362.63 132.168 + vertex 818.03 362.238 124.314 + vertex 821.602 357.252 132.176 + endloop + endfacet + facet normal -0.835938 -0.547944 0.0310577 + outer loop + vertex 821.632 357.654 140.065 + vertex 818.077 362.63 132.168 + vertex 821.602 357.252 132.176 + endloop + endfacet + facet normal -0.832259 -0.553791 0.025717 + outer loop + vertex 818.107 362.951 140.06 + vertex 818.077 362.63 132.168 + vertex 821.632 357.654 140.065 + endloop + endfacet + facet normal -0.832289 -0.553813 0.0242052 + outer loop + vertex 821.654 357.966 147.953 + vertex 818.107 362.951 140.06 + vertex 821.632 357.654 140.065 + endloop + endfacet + facet normal -0.84438 -0.535229 0.0235016 + outer loop + vertex 821.654 357.966 147.953 + vertex 821.632 357.654 140.065 + vertex 825.043 352.619 147.958 + endloop + endfacet + facet normal -0.829237 -0.558544 0.019846 + outer loop + vertex 818.128 363.2 147.95 + vertex 818.107 362.951 140.06 + vertex 821.654 357.966 147.953 + endloop + endfacet + facet normal -0.829269 -0.558568 0.0177416 + outer loop + vertex 821.671 358.191 155.808 + vertex 818.128 363.2 147.95 + vertex 821.654 357.966 147.953 + endloop + endfacet + facet normal -0.842472 -0.538465 0.0171968 + outer loop + vertex 821.671 358.191 155.808 + vertex 821.654 357.966 147.953 + vertex 825.061 352.887 155.812 + endloop + endfacet + facet normal -0.826925 -0.562127 0.0144162 + outer loop + vertex 818.144 363.378 155.805 + vertex 818.128 363.2 147.95 + vertex 821.671 358.191 155.808 + endloop + endfacet + facet normal -0.826962 -0.562153 0.0108719 + outer loop + vertex 821.682 358.326 163.63 + vertex 818.144 363.378 155.805 + vertex 821.671 358.191 155.808 + endloop + endfacet + facet normal -0.841561 -0.540061 0.0105104 + outer loop + vertex 821.682 358.326 163.63 + vertex 821.671 358.191 155.808 + vertex 825.07 353.046 163.632 + endloop + endfacet + facet normal -0.841599 -0.540088 0.0040374 + outer loop + vertex 825.073 353.1 171.457 + vertex 821.682 358.326 163.63 + vertex 825.07 353.046 163.632 + endloop + endfacet + facet normal -0.841233 -0.540662 0.00349593 + outer loop + vertex 821.685 358.371 171.455 + vertex 821.682 358.326 163.63 + vertex 825.073 353.1 171.457 + endloop + endfacet + facet normal -0.84123 -0.540663 -0.00386421 + outer loop + vertex 825.069 353.049 179.332 + vertex 821.685 358.371 171.455 + vertex 825.073 353.1 171.457 + endloop + endfacet + facet normal -0.860327 -0.50973 -0.00367283 + outer loop + vertex 825.069 353.049 179.332 + vertex 825.073 353.1 171.457 + vertex 828.292 347.611 179.323 + endloop + endfacet + facet normal -0.841653 -0.54001 -0.00324133 + outer loop + vertex 821.682 358.329 179.331 + vertex 821.685 358.371 171.455 + vertex 825.069 353.049 179.332 + endloop + endfacet + facet normal -0.841598 -0.539976 -0.0117973 + outer loop + vertex 825.059 352.891 187.275 + vertex 821.682 358.329 179.331 + vertex 825.069 353.049 179.332 + endloop + endfacet + facet normal -0.861058 -0.508384 -0.0111947 + outer loop + vertex 825.059 352.891 187.275 + vertex 825.069 353.049 179.332 + vertex 828.282 347.433 187.264 + endloop + endfacet + facet normal -0.842659 -0.53835 -0.0102328 + outer loop + vertex 821.671 358.195 187.276 + vertex 821.682 358.329 179.331 + vertex 825.059 352.891 187.275 + endloop + endfacet + facet normal -0.842542 -0.538274 -0.0195845 + outer loop + vertex 825.044 352.625 195.261 + vertex 821.671 358.195 187.276 + vertex 825.059 352.891 187.275 + endloop + endfacet + facet normal -0.863087 -0.504715 -0.0185059 + outer loop + vertex 825.044 352.625 195.261 + vertex 825.059 352.891 187.275 + vertex 828.263 347.121 195.247 + endloop + endfacet + facet normal -0.84443 -0.535403 -0.0167839 + outer loop + vertex 821.655 357.97 195.263 + vertex 821.671 358.195 187.276 + vertex 825.044 352.625 195.261 + endloop + endfacet + facet normal -0.844229 -0.535271 -0.0276125 + outer loop + vertex 825.022 352.247 203.236 + vertex 821.655 357.97 195.263 + vertex 825.044 352.625 195.261 + endloop + endfacet + facet normal -0.86481 -0.501422 -0.0260656 + outer loop + vertex 825.022 352.247 203.236 + vertex 825.044 352.625 195.261 + vertex 828.244 346.692 203.22 + endloop + endfacet + facet normal -0.847178 -0.530805 -0.0231616 + outer loop + vertex 821.634 357.655 203.24 + vertex 821.655 357.97 195.263 + vertex 825.022 352.247 203.236 + endloop + endfacet + facet normal -0.846881 -0.530609 -0.0352997 + outer loop + vertex 824.996 351.762 211.156 + vertex 821.634 357.655 203.24 + vertex 825.022 352.247 203.236 + endloop + endfacet + facet normal -0.867511 -0.496304 -0.0332674 + outer loop + vertex 824.996 351.762 211.156 + vertex 825.022 352.247 203.236 + vertex 828.218 346.132 211.138 + endloop + endfacet + facet normal -0.850473 -0.525178 -0.02973 + outer loop + vertex 821.608 357.249 211.163 + vertex 821.634 357.655 203.24 + vertex 824.996 351.762 211.156 + endloop + endfacet + facet normal -0.850037 -0.52489 -0.0439082 + outer loop + vertex 824.958 351.168 218.998 + vertex 821.608 357.249 211.163 + vertex 824.996 351.762 211.156 + endloop + endfacet + facet normal -0.870588 -0.49027 -0.0413818 + outer loop + vertex 824.958 351.168 218.998 + vertex 824.996 351.762 211.156 + vertex 828.182 345.446 218.978 + endloop + endfacet + facet normal -0.854325 -0.518416 -0.0370496 + outer loop + vertex 821.57 356.75 219.007 + vertex 821.608 357.249 211.163 + vertex 824.958 351.168 218.998 + endloop + endfacet + facet normal -0.853677 -0.517995 -0.05401 + outer loop + vertex 824.896 350.461 226.763 + vertex 821.57 356.75 219.007 + vertex 824.958 351.168 218.998 + endloop + endfacet + facet normal -0.874561 -0.482234 -0.0509231 + outer loop + vertex 824.896 350.461 226.763 + vertex 824.958 351.168 218.998 + vertex 828.116 344.624 226.74 + endloop + endfacet + facet normal -0.858468 -0.510789 -0.0461124 + outer loop + vertex 821.508 356.155 226.774 + vertex 821.57 356.75 219.007 + vertex 824.896 350.461 226.763 + endloop + endfacet + facet normal -0.857457 -0.510148 -0.0672069 + outer loop + vertex 824.784 349.636 234.454 + vertex 821.508 356.155 226.774 + vertex 824.896 350.461 226.763 + endloop + endfacet + facet normal -0.877879 -0.474627 -0.0636943 + outer loop + vertex 824.784 349.636 234.454 + vertex 824.896 350.461 226.763 + vertex 828.006 343.679 234.431 + endloop + endfacet + facet normal -0.863117 -0.501705 -0.0576262 + outer loop + vertex 821.397 355.461 234.465 + vertex 821.508 356.155 226.774 + vertex 824.784 349.636 234.454 + endloop + endfacet + facet normal -0.861597 -0.500773 -0.0829278 + outer loop + vertex 824.594 348.703 242.061 + vertex 821.397 355.461 234.465 + vertex 824.784 349.636 234.454 + endloop + endfacet + facet normal -0.881293 -0.465896 -0.0791443 + outer loop + vertex 824.594 348.703 242.061 + vertex 824.784 349.636 234.454 + vertex 827.817 342.609 242.04 + endloop + endfacet + facet normal -0.867937 -0.491435 -0.0719522 + outer loop + vertex 821.21 354.678 242.072 + vertex 821.397 355.461 234.465 + vertex 824.594 348.703 242.061 + endloop + endfacet + facet normal -0.865637 -0.490076 -0.102466 + outer loop + vertex 824.286 347.68 249.559 + vertex 821.21 354.678 242.072 + vertex 824.594 348.703 242.061 + endloop + endfacet + facet normal -0.88503 -0.455001 -0.0984733 + outer loop + vertex 824.286 347.68 249.559 + vertex 824.594 348.703 242.061 + vertex 827.505 341.421 249.54 + endloop + endfacet + facet normal -0.880563 -0.452576 -0.140653 + outer loop + vertex 827.007 340.104 256.9 + vertex 824.286 347.68 249.559 + vertex 827.505 341.421 249.54 + endloop + endfacet + facet normal -0.886787 -0.443743 -0.12923 + outer loop + vertex 823.783 346.542 256.912 + vertex 824.286 347.68 249.559 + vertex 827.007 340.104 256.9 + endloop + endfacet + facet normal -0.867851 -0.478601 -0.133329 + outer loop + vertex 823.783 346.542 256.912 + vertex 820.899 353.819 249.565 + vertex 824.286 347.68 249.559 + endloop + endfacet + facet normal -0.876108 -0.467241 -0.118834 + outer loop + vertex 820.401 352.883 256.916 + vertex 820.899 353.819 249.565 + vertex 823.783 346.542 256.912 + endloop + endfacet + facet normal -0.857981 -0.499066 -0.121664 + outer loop + vertex 820.401 352.883 256.916 + vertex 817.378 359.873 249.561 + vertex 820.899 353.819 249.565 + endloop + endfacet + facet normal -0.861544 -0.501111 -0.0814183 + outer loop + vertex 817.378 359.873 249.561 + vertex 817.689 360.555 242.073 + vertex 820.899 353.819 249.565 + endloop + endfacet + facet normal -0.854045 -0.511621 -0.0940781 + outer loop + vertex 820.899 353.819 249.565 + vertex 817.689 360.555 242.073 + vertex 821.21 354.678 242.072 + endloop + endfacet + facet normal -0.856136 -0.512878 -0.0631416 + outer loop + vertex 817.689 360.555 242.073 + vertex 817.875 361.181 234.468 + vertex 821.21 354.678 242.072 + endloop + endfacet + facet normal -0.83941 -0.539606 -0.0649325 + outer loop + vertex 817.689 360.555 242.073 + vertex 814.249 366.822 234.471 + vertex 817.875 361.181 234.468 + endloop + endfacet + facet normal -0.840465 -0.540294 -0.0412322 + outer loop + vertex 814.249 366.822 234.471 + vertex 814.357 367.241 226.781 + vertex 817.875 361.181 234.468 + endloop + endfacet + facet normal -0.833268 -0.550374 -0.0524736 + outer loop + vertex 817.875 361.181 234.468 + vertex 814.357 367.241 226.781 + vertex 817.987 361.745 226.778 + endloop + endfacet + facet normal -0.85043 -0.523633 -0.0507624 + outer loop + vertex 817.875 361.181 234.468 + vertex 817.987 361.745 226.778 + vertex 821.397 355.461 234.465 + endloop + endfacet + facet normal -0.83398 -0.550856 -0.0321671 + outer loop + vertex 814.357 367.241 226.781 + vertex 814.418 367.602 219.013 + vertex 817.987 361.745 226.778 + endloop + endfacet + facet normal -0.828147 -0.55901 -0.0409985 + outer loop + vertex 817.987 361.745 226.778 + vertex 814.418 367.602 219.013 + vertex 818.048 362.224 219.01 + endloop + endfacet + facet normal -0.845527 -0.53247 -0.0394988 + outer loop + vertex 817.987 361.745 226.778 + vertex 818.048 362.224 219.01 + vertex 821.508 356.155 226.774 + endloop + endfacet + facet normal -0.828575 -0.559307 -0.0252755 + outer loop + vertex 814.418 367.602 219.013 + vertex 814.453 367.904 211.163 + vertex 818.048 362.224 219.01 + endloop + endfacet + facet normal -0.823684 -0.56612 -0.0324482 + outer loop + vertex 818.048 362.224 219.01 + vertex 814.453 367.904 211.163 + vertex 818.084 362.622 211.162 + endloop + endfacet + facet normal -0.840534 -0.540857 -0.0312424 + outer loop + vertex 818.048 362.224 219.01 + vertex 818.084 362.622 211.162 + vertex 821.57 356.75 219.007 + endloop + endfacet + facet normal -0.823952 -0.566308 -0.0199586 + outer loop + vertex 814.453 367.904 211.163 + vertex 814.478 368.147 203.237 + vertex 818.084 362.622 211.162 + endloop + endfacet + facet normal -0.8192 -0.572885 -0.026706 + outer loop + vertex 818.084 362.622 211.162 + vertex 814.478 368.147 203.237 + vertex 818.111 362.952 203.239 + endloop + endfacet + facet normal -0.835897 -0.548283 -0.0257394 + outer loop + vertex 818.084 362.622 211.162 + vertex 818.111 362.952 203.239 + vertex 821.608 357.249 211.163 + endloop + endfacet + facet normal -0.819394 -0.573015 -0.0157248 + outer loop + vertex 814.478 368.147 203.237 + vertex 814.499 368.337 195.257 + vertex 818.111 362.952 203.239 + endloop + endfacet + facet normal -0.816246 -0.577355 -0.0200768 + outer loop + vertex 818.111 362.952 203.239 + vertex 814.499 368.337 195.257 + vertex 818.13 363.202 195.259 + endloop + endfacet + facet normal -0.832498 -0.553689 -0.019374 + outer loop + vertex 818.111 362.952 203.239 + vertex 818.13 363.202 195.259 + vertex 821.634 357.655 203.24 + endloop + endfacet + facet normal -0.816362 -0.577432 -0.011223 + outer loop + vertex 814.499 368.337 195.257 + vertex 814.513 368.471 187.269 + vertex 818.13 363.202 195.259 + endloop + endfacet + facet normal -0.813971 -0.580726 -0.0144776 + outer loop + vertex 818.13 363.202 195.259 + vertex 814.513 368.471 187.269 + vertex 818.145 363.38 187.272 + endloop + endfacet + facet normal -0.829301 -0.558627 -0.014013 + outer loop + vertex 818.13 363.202 195.259 + vertex 818.145 363.38 187.272 + vertex 821.655 357.97 195.263 + endloop + endfacet + facet normal -0.814037 -0.58077 -0.00707069 + outer loop + vertex 814.513 368.471 187.269 + vertex 814.523 368.554 179.323 + vertex 818.145 363.38 187.272 + endloop + endfacet + facet normal -0.812775 -0.582512 -0.00878004 + outer loop + vertex 818.145 363.38 187.272 + vertex 814.523 368.554 179.323 + vertex 818.155 363.487 179.328 + endloop + endfacet + facet normal -0.826931 -0.562238 -0.00852631 + outer loop + vertex 818.145 363.38 187.272 + vertex 818.155 363.487 179.328 + vertex 821.671 358.195 187.276 + endloop + endfacet + facet normal -0.812807 -0.582529 -0.00218252 + outer loop + vertex 814.523 368.554 179.323 + vertex 814.525 368.581 171.448 + vertex 818.155 363.487 179.328 + endloop + endfacet + facet normal -0.812162 -0.583424 -0.00305842 + outer loop + vertex 818.155 363.487 179.328 + vertex 814.525 368.581 171.448 + vertex 818.159 363.522 171.451 + endloop + endfacet + facet normal -0.825464 -0.564447 -0.00297894 + outer loop + vertex 818.155 363.487 179.328 + vertex 818.159 363.522 171.451 + vertex 821.682 358.329 179.331 + endloop + endfacet + facet normal -0.812165 -0.583423 0.00224152 + outer loop + vertex 814.525 368.581 171.448 + vertex 814.521 368.556 163.624 + vertex 818.159 363.522 171.451 + endloop + endfacet + facet normal -0.812906 -0.582385 0.00325351 + outer loop + vertex 818.159 363.522 171.451 + vertex 814.521 368.556 163.624 + vertex 818.154 363.485 163.627 + endloop + endfacet + facet normal -0.82519 -0.564846 0.00317704 + outer loop + vertex 818.159 363.522 171.451 + vertex 818.154 363.485 163.627 + vertex 821.685 358.371 171.455 + endloop + endfacet + facet normal -0.812892 -0.582373 0.00695502 + outer loop + vertex 814.521 368.556 163.624 + vertex 814.51 368.478 155.805 + vertex 818.154 363.485 163.627 + endloop + endfacet + facet normal -0.814371 -0.580275 0.00898357 + outer loop + vertex 818.154 363.485 163.627 + vertex 814.51 368.478 155.805 + vertex 818.144 363.378 155.805 + endloop + endfacet + facet normal -0.814354 -0.580262 0.0111223 + outer loop + vertex 814.51 368.478 155.805 + vertex 814.495 368.35 147.95 + vertex 818.144 363.378 155.805 + endloop + endfacet + facet normal -0.811209 -0.584649 0.0111882 + outer loop + vertex 814.51 368.478 155.805 + vertex 810.815 373.455 147.958 + vertex 814.495 368.35 147.95 + endloop + endfacet + facet normal -0.81121 -0.58465 0.011036 + outer loop + vertex 810.815 373.455 147.958 + vertex 810.79 373.341 140.066 + vertex 814.495 368.35 147.95 + endloop + endfacet + facet normal -0.814613 -0.579792 0.0157094 + outer loop + vertex 814.495 368.35 147.95 + vertex 810.79 373.341 140.066 + vertex 814.473 368.167 140.058 + endloop + endfacet + facet normal -0.816956 -0.576487 0.0156394 + outer loop + vertex 814.495 368.35 147.95 + vertex 814.473 368.167 140.058 + vertex 818.128 363.2 147.95 + endloop + endfacet + facet normal -0.814639 -0.579808 0.0136014 + outer loop + vertex 810.79 373.341 140.066 + vertex 810.763 373.194 132.167 + vertex 814.473 368.167 140.058 + endloop + endfacet + facet normal -0.819285 -0.573035 0.0201007 + outer loop + vertex 814.473 368.167 140.058 + vertex 810.763 373.194 132.167 + vertex 814.444 367.931 132.162 + endloop + endfacet + facet normal -0.82027 -0.571624 0.0200621 + outer loop + vertex 814.473 368.167 140.058 + vertex 814.444 367.931 132.162 + vertex 818.107 362.951 140.06 + endloop + endfacet + facet normal -0.81934 -0.57307 0.0165244 + outer loop + vertex 810.763 373.194 132.167 + vertex 810.728 373.017 124.309 + vertex 814.444 367.931 132.162 + endloop + endfacet + facet normal -0.825379 -0.564015 0.0252458 + outer loop + vertex 814.444 367.931 132.162 + vertex 810.728 373.017 124.309 + vertex 814.401 367.642 124.305 + endloop + endfacet + facet normal -0.840142 -0.542133 0.0159182 + outer loop + vertex 810.763 373.194 132.167 + vertex 807.223 378.45 124.368 + vertex 810.728 373.017 124.309 + endloop + endfacet + facet normal -0.840201 -0.542133 0.0124121 + outer loop + vertex 807.223 378.45 124.368 + vertex 807.165 378.362 116.571 + vertex 810.728 373.017 124.309 + endloop + endfacet + facet normal -0.846611 -0.531735 0.0225479 + outer loop + vertex 810.728 373.017 124.309 + vertex 807.165 378.362 116.571 + vertex 810.659 372.797 116.516 + endloop + endfacet + facet normal -0.898288 -0.439252 0.0116896 + outer loop + vertex 807.223 378.45 124.368 + vertex 804.327 384.172 116.819 + vertex 807.165 378.362 116.571 + endloop + endfacet + facet normal -0.89835 -0.439182 0.00935167 + outer loop + vertex 804.327 384.172 116.819 + vertex 804.227 384.209 108.998 + vertex 807.165 378.362 116.571 + endloop + endfacet + facet normal -0.902283 -0.430795 0.0173522 + outer loop + vertex 807.165 378.362 116.571 + vertex 804.227 384.209 108.998 + vertex 807.066 378.259 108.854 + endloop + endfacet + facet normal -0.894052 -0.447949 0.00347126 + outer loop + vertex 804.372 384.141 124.545 + vertex 804.327 384.172 116.819 + vertex 807.223 378.45 124.368 + endloop + endfacet + facet normal -0.893965 -0.448058 0.0083667 + outer loop + vertex 807.26 378.523 132.206 + vertex 804.372 384.141 124.545 + vertex 807.223 378.45 124.368 + endloop + endfacet + facet normal -0.890377 -0.455221 0.00176161 + outer loop + vertex 804.401 384.115 132.225 + vertex 804.372 384.141 124.545 + vertex 807.26 378.523 132.206 + endloop + endfacet + facet normal -0.890354 -0.455225 0.00637679 + outer loop + vertex 807.287 378.582 140.105 + vertex 804.401 384.115 132.225 + vertex 807.26 378.523 132.206 + endloop + endfacet + facet normal -0.831307 -0.55577 0.00692173 + outer loop + vertex 807.287 378.582 140.105 + vertex 807.26 378.523 132.206 + vertex 810.79 373.341 140.066 + endloop + endfacet + facet normal -0.887493 -0.460819 0.00140098 + outer loop + vertex 804.425 384.093 140.323 + vertex 804.401 384.115 132.225 + vertex 807.287 378.582 140.105 + endloop + endfacet + facet normal -0.887429 -0.46092 0.00478094 + outer loop + vertex 807.307 378.625 148.012 + vertex 804.425 384.093 140.323 + vertex 807.287 378.582 140.105 + endloop + endfacet + facet normal -0.827425 -0.561553 0.00517843 + outer loop + vertex 807.307 378.625 148.012 + vertex 807.287 378.582 140.105 + vertex 810.815 373.455 147.958 + endloop + endfacet + facet normal -0.827408 -0.561559 0.00685979 + outer loop + vertex 810.828 373.532 155.81 + vertex 807.307 378.625 148.012 + vertex 810.815 373.455 147.958 + endloop + endfacet + facet normal -0.825198 -0.564832 0.00372401 + outer loop + vertex 807.322 378.654 155.872 + vertex 807.307 378.625 148.012 + vertex 810.828 373.532 155.81 + endloop + endfacet + facet normal -0.825191 -0.564836 0.00440344 + outer loop + vertex 810.839 373.577 163.628 + vertex 807.322 378.654 155.872 + vertex 810.828 373.532 155.81 + endloop + endfacet + facet normal -0.806364 -0.591402 0.0045309 + outer loop + vertex 810.839 373.577 163.628 + vertex 810.828 373.532 155.81 + vertex 814.521 368.556 163.624 + endloop + endfacet + facet normal -0.823597 -0.567172 0.00215127 + outer loop + vertex 807.333 378.669 163.697 + vertex 807.322 378.654 155.872 + vertex 810.839 373.577 163.628 + endloop + endfacet + facet normal -0.823603 -0.567165 0.00134653 + outer loop + vertex 810.843 373.589 171.453 + vertex 807.333 378.669 163.697 + vertex 810.839 373.577 163.628 + endloop + endfacet + facet normal -0.805709 -0.592309 0.00137397 + outer loop + vertex 810.843 373.589 171.453 + vertex 810.839 373.577 163.628 + vertex 814.525 368.581 171.448 + endloop + endfacet + facet normal -0.822963 -0.568094 0.000448593 + outer loop + vertex 807.337 378.669 171.501 + vertex 807.333 378.669 163.697 + vertex 810.843 373.589 171.453 + endloop + endfacet + facet normal -0.822972 -0.568079 -0.00184416 + outer loop + vertex 810.841 373.567 179.33 + vertex 807.337 378.669 171.501 + vertex 810.843 373.589 171.453 + endloop + endfacet + facet normal -0.80594 -0.591994 -0.00190618 + outer loop + vertex 810.841 373.567 179.33 + vertex 810.843 373.589 171.453 + vertex 814.523 368.554 179.323 + endloop + endfacet + facet normal -0.823338 -0.56755 -0.00133588 + outer loop + vertex 807.334 378.654 179.381 + vertex 807.337 378.669 171.501 + vertex 810.841 373.567 179.33 + endloop + endfacet + facet normal -0.823345 -0.56752 -0.0048895 + outer loop + vertex 810.832 373.511 187.278 + vertex 807.334 378.654 179.381 + vertex 810.841 373.567 179.33 + endloop + endfacet + facet normal -0.80754 -0.589791 -0.0050278 + outer loop + vertex 810.832 373.511 187.278 + vertex 810.841 373.567 179.33 + vertex 814.513 368.471 187.269 + endloop + endfacet + facet normal -0.824657 -0.565625 -0.00307476 + outer loop + vertex 807.325 378.624 187.349 + vertex 807.334 378.654 179.381 + vertex 810.832 373.511 187.278 + endloop + endfacet + facet normal -0.824666 -0.565562 -0.00812888 + outer loop + vertex 810.817 373.419 195.267 + vertex 807.325 378.624 187.349 + vertex 810.832 373.511 187.278 + endloop + endfacet + facet normal -0.809801 -0.586645 -0.00834306 + outer loop + vertex 810.817 373.419 195.267 + vertex 810.832 373.511 187.278 + vertex 814.499 368.337 195.257 + endloop + endfacet + facet normal -0.827109 -0.562021 -0.00472481 + outer loop + vertex 807.31 378.579 195.339 + vertex 807.325 378.624 187.349 + vertex 810.817 373.419 195.267 + endloop + endfacet + facet normal -0.827109 -0.561933 -0.0110439 + outer loop + vertex 810.796 373.292 203.247 + vertex 807.31 378.579 195.339 + vertex 810.817 373.419 195.267 + endloop + endfacet + facet normal -0.813192 -0.581885 -0.0113268 + outer loop + vertex 810.796 373.292 203.247 + vertex 810.817 373.419 195.267 + vertex 814.478 368.147 203.237 + endloop + endfacet + facet normal -0.830534 -0.556934 -0.00619246 + outer loop + vertex 807.291 378.519 203.322 + vertex 807.31 378.579 195.339 + vertex 810.796 373.292 203.247 + endloop + endfacet + facet normal -0.83052 -0.556816 -0.013894 + outer loop + vertex 810.772 373.13 211.175 + vertex 807.291 378.519 203.322 + vertex 810.796 373.292 203.247 + endloop + endfacet + facet normal -0.817508 -0.575742 -0.0142405 + outer loop + vertex 810.772 373.13 211.175 + vertex 810.796 373.292 203.247 + vertex 814.453 367.904 211.163 + endloop + endfacet + facet normal -0.834781 -0.550528 -0.00769145 + outer loop + vertex 807.268 378.443 211.245 + vertex 807.291 378.519 203.322 + vertex 810.772 373.13 211.175 + endloop + endfacet + facet normal -0.83474 -0.550376 -0.0171717 + outer loop + vertex 810.741 372.933 219.027 + vertex 807.268 378.443 211.245 + vertex 810.772 373.13 211.175 + endloop + endfacet + facet normal -0.823093 -0.567635 -0.0175582 + outer loop + vertex 810.741 372.933 219.027 + vertex 810.772 373.13 211.175 + vertex 814.418 367.602 219.013 + endloop + endfacet + facet normal -0.839563 -0.543172 -0.00991864 + outer loop + vertex 807.235 378.351 219.101 + vertex 807.268 378.443 211.245 + vertex 810.741 372.933 219.027 + endloop + endfacet + facet normal -0.839458 -0.54292 -0.02342 + outer loop + vertex 810.679 372.693 226.795 + vertex 807.235 378.351 219.101 + vertex 810.741 372.933 219.027 + endloop + endfacet + facet normal -0.828855 -0.558955 -0.0238314 + outer loop + vertex 810.679 372.693 226.795 + vertex 810.741 372.933 219.027 + vertex 814.357 367.241 226.781 + endloop + endfacet + facet normal -0.845815 -0.533305 -0.0135044 + outer loop + vertex 807.181 378.239 226.87 + vertex 807.235 378.351 219.101 + vertex 810.679 372.693 226.795 + endloop + endfacet + facet normal -0.8456 -0.532937 -0.0306429 + outer loop + vertex 810.575 372.416 234.48 + vertex 807.181 378.239 226.87 + vertex 810.679 372.693 226.795 + endloop + endfacet + facet normal -0.835528 -0.548569 -0.0310708 + outer loop + vertex 810.575 372.416 234.48 + vertex 810.679 372.693 226.795 + vertex 814.249 366.822 234.471 + endloop + endfacet + facet normal -0.834722 -0.548002 -0.0541488 + outer loop + vertex 814.063 366.353 242.069 + vertex 810.575 372.416 234.48 + vertex 814.249 366.822 234.471 + endloop + endfacet + facet normal -0.843183 -0.536081 -0.0407373 + outer loop + vertex 810.4 372.116 242.074 + vertex 810.575 372.416 234.48 + vertex 814.063 366.353 242.069 + endloop + endfacet + facet normal -0.841837 -0.5352 -0.0697951 + outer loop + vertex 813.758 365.858 249.553 + vertex 810.4 372.116 242.074 + vertex 814.063 366.353 242.069 + endloop + endfacet + facet normal -0.853548 -0.516421 -0.069032 + outer loop + vertex 813.758 365.858 249.553 + vertex 814.063 366.353 242.069 + vertex 817.378 359.873 249.561 + endloop + endfacet + facet normal -0.850453 -0.514607 -0.109133 + outer loop + vertex 816.879 359.14 256.906 + vertex 813.758 365.858 249.553 + vertex 817.378 359.873 249.561 + endloop + endfacet + facet normal -0.859851 -0.501904 -0.0935363 + outer loop + vertex 813.264 365.335 256.897 + vertex 813.758 365.858 249.553 + vertex 816.879 359.14 256.906 + endloop + endfacet + facet normal -0.848123 -0.521369 -0.0941355 + outer loop + vertex 813.264 365.335 256.897 + vertex 810.099 371.809 249.561 + vertex 813.758 365.858 249.553 + endloop + endfacet + facet normal -0.856745 -0.509506 -0.0799486 + outer loop + vertex 809.605 371.484 256.921 + vertex 810.099 371.809 249.561 + vertex 813.264 365.335 256.897 + endloop + endfacet + facet normal -0.864067 -0.496997 -0.0798873 + outer loop + vertex 809.605 371.484 256.921 + vertex 806.61 377.857 249.67 + vertex 810.099 371.809 249.561 + endloop + endfacet + facet normal -0.865741 -0.498625 -0.0431847 + outer loop + vertex 806.61 377.857 249.67 + vertex 806.911 377.984 242.157 + vertex 810.099 371.809 249.561 + endloop + endfacet + facet normal -0.858638 -0.509583 -0.0553819 + outer loop + vertex 810.099 371.809 249.561 + vertex 806.911 377.984 242.157 + vertex 810.4 372.116 242.074 + endloop + endfacet + facet normal -0.859446 -0.510444 -0.0282621 + outer loop + vertex 806.911 377.984 242.157 + vertex 807.085 378.114 234.544 + vertex 810.4 372.116 242.074 + endloop + endfacet + facet normal -0.906355 -0.4216 -0.0278187 + outer loop + vertex 806.911 377.984 242.157 + vertex 804.245 384.204 234.765 + vertex 807.085 378.114 234.544 + endloop + endfacet + facet normal -0.906405 -0.422322 -0.00857398 + outer loop + vertex 804.245 384.204 234.765 + vertex 804.334 384.169 227.118 + vertex 807.085 378.114 234.544 + endloop + endfacet + facet normal -0.901601 -0.432177 -0.0183903 + outer loop + vertex 807.085 378.114 234.544 + vertex 804.334 384.169 227.118 + vertex 807.181 378.239 226.87 + endloop + endfacet + facet normal -0.901501 -0.432764 -0.00321925 + outer loop + vertex 804.334 384.169 227.118 + vertex 804.376 384.138 219.41 + vertex 807.181 378.239 226.87 + endloop + endfacet + facet normal -0.91059 -0.412876 -0.0189495 + outer loop + vertex 804.064 384.246 242.56 + vertex 804.245 384.204 234.765 + vertex 806.911 377.984 242.157 + endloop + endfacet + facet normal -0.910486 -0.411245 -0.0435088 + outer loop + vertex 806.61 377.857 249.67 + vertex 804.064 384.246 242.56 + vertex 806.911 377.984 242.157 + endloop + endfacet + facet normal -0.914338 -0.403427 -0.0351033 + outer loop + vertex 803.757 384.293 250.007 + vertex 804.064 384.246 242.56 + vertex 806.61 377.857 249.67 + endloop + endfacet + facet normal -0.913347 -0.40118 -0.0696519 + outer loop + vertex 806.108 377.719 257.047 + vertex 803.757 384.293 250.007 + vertex 806.61 377.857 249.67 + endloop + endfacet + facet normal -0.918677 -0.390713 -0.0581008 + outer loop + vertex 803.272 384.345 257.329 + vertex 803.757 384.293 250.007 + vertex 806.108 377.719 257.047 + endloop + endfacet + facet normal -0.915452 -0.387134 -0.109885 + outer loop + vertex 805.321 377.521 264.297 + vertex 803.272 384.345 257.329 + vertex 806.108 377.719 257.047 + endloop + endfacet + facet normal -0.874747 -0.472436 -0.107807 + outer loop + vertex 805.321 377.521 264.297 + vertex 806.108 377.719 257.047 + vertex 808.823 371.074 264.133 + endloop + endfacet + facet normal -0.86676 -0.483713 -0.121444 + outer loop + vertex 808.823 371.074 264.133 + vertex 806.108 377.719 257.047 + vertex 809.605 371.484 256.921 + endloop + endfacet + facet normal -0.860671 -0.494477 -0.121395 + outer loop + vertex 808.823 371.074 264.133 + vertex 809.605 371.484 256.921 + vertex 812.487 364.712 264.076 + endloop + endfacet + facet normal -0.851588 -0.506219 -0.136165 + outer loop + vertex 812.487 364.712 264.076 + vertex 809.605 371.484 256.921 + vertex 813.264 365.335 256.897 + endloop + endfacet + facet normal -0.863236 -0.486221 -0.13569 + outer loop + vertex 812.487 364.712 264.076 + vertex 813.264 365.335 256.897 + vertex 816.104 358.29 264.074 + endloop + endfacet + facet normal -0.853646 -0.498363 -0.151406 + outer loop + vertex 816.104 358.29 264.074 + vertex 813.264 365.335 256.897 + vertex 816.879 359.14 256.906 + endloop + endfacet + facet normal -0.868912 -0.471724 -0.149898 + outer loop + vertex 816.104 358.29 264.074 + vertex 816.879 359.14 256.906 + vertex 819.626 351.799 264.087 + endloop + endfacet + facet normal -0.859221 -0.483905 -0.166058 + outer loop + vertex 819.626 351.799 264.087 + vertex 816.879 359.14 256.906 + vertex 820.401 352.883 256.916 + endloop + endfacet + facet normal -0.87699 -0.451963 -0.163152 + outer loop + vertex 819.626 351.799 264.087 + vertex 820.401 352.883 256.916 + vertex 823.009 345.234 264.087 + endloop + endfacet + facet normal -0.868267 -0.463019 -0.178115 + outer loop + vertex 823.009 345.234 264.087 + vertex 820.401 352.883 256.916 + vertex 823.783 346.542 256.912 + endloop + endfacet + facet normal -0.886345 -0.429132 -0.173891 + outer loop + vertex 823.009 345.234 264.087 + vertex 823.783 346.542 256.912 + vertex 826.23 338.584 264.079 + endloop + endfacet + facet normal -0.87838 -0.439421 -0.188035 + outer loop + vertex 826.23 338.584 264.079 + vertex 823.783 346.542 256.912 + vertex 827.007 340.104 256.9 + endloop + endfacet + facet normal -0.898934 -0.398661 -0.181625 + outer loop + vertex 826.23 338.584 264.079 + vertex 827.007 340.104 256.9 + vertex 829.246 331.787 264.074 + endloop + endfacet + facet normal -0.892024 -0.407966 -0.194569 + outer loop + vertex 829.246 331.787 264.074 + vertex 827.007 340.104 256.9 + vertex 830.024 333.51 256.891 + endloop + endfacet + facet normal -0.91383 -0.36115 -0.185704 + outer loop + vertex 829.246 331.787 264.074 + vertex 830.024 333.51 256.891 + vertex 832.005 324.793 264.097 + endloop + endfacet + facet normal -0.908626 -0.368649 -0.196206 + outer loop + vertex 832.005 324.793 264.097 + vertex 830.024 333.51 256.891 + vertex 832.781 326.703 256.917 + endloop + endfacet + facet normal -0.924224 -0.370778 -0.0912855 + outer loop + vertex 802.509 384.408 264.801 + vertex 803.272 384.345 257.329 + vertex 805.321 377.521 264.297 + endloop + endfacet + facet normal -0.870719 -0.487006 -0.0683576 + outer loop + vertex 806.108 377.719 257.047 + vertex 806.61 377.857 249.67 + vertex 809.605 371.484 256.921 + endloop + endfacet + facet normal -0.850564 -0.522923 -0.0556046 + outer loop + vertex 810.099 371.809 249.561 + vertex 810.4 372.116 242.074 + vertex 813.758 365.858 249.553 + endloop + endfacet + facet normal -0.852204 -0.521649 -0.0403751 + outer loop + vertex 810.4 372.116 242.074 + vertex 807.085 378.114 234.544 + vertex 810.575 372.416 234.48 + endloop + endfacet + facet normal -0.852636 -0.522151 -0.0192503 + outer loop + vertex 807.085 378.114 234.544 + vertex 807.181 378.239 226.87 + vertex 810.575 372.416 234.48 + endloop + endfacet + facet normal -0.89677 -0.442318 -0.0125534 + outer loop + vertex 807.181 378.239 226.87 + vertex 804.376 384.138 219.41 + vertex 807.235 378.351 219.101 + endloop + endfacet + facet normal -0.896611 -0.442816 -0.00177064 + outer loop + vertex 804.376 384.138 219.41 + vertex 804.405 384.112 211.471 + vertex 807.235 378.351 219.101 + endloop + endfacet + facet normal -0.892708 -0.450545 -0.00905393 + outer loop + vertex 807.235 378.351 219.101 + vertex 804.405 384.112 211.471 + vertex 807.268 378.443 211.245 + endloop + endfacet + facet normal -0.892621 -0.450805 -0.00140799 + outer loop + vertex 804.405 384.112 211.471 + vertex 804.428 384.091 203.587 + vertex 807.268 378.443 211.245 + endloop + endfacet + facet normal -0.88955 -0.456785 -0.00695665 + outer loop + vertex 807.268 378.443 211.245 + vertex 804.428 384.091 203.587 + vertex 807.291 378.519 203.322 + endloop + endfacet + facet normal -0.889457 -0.457018 -0.00106001 + outer loop + vertex 804.428 384.091 203.587 + vertex 804.446 384.074 195.596 + vertex 807.291 378.519 203.322 + endloop + endfacet + facet normal -0.886855 -0.462013 -0.00561058 + outer loop + vertex 807.291 378.519 203.322 + vertex 804.446 384.074 195.596 + vertex 807.31 378.579 195.339 + endloop + endfacet + facet normal -0.886775 -0.4622 -0.000721649 + outer loop + vertex 804.446 384.074 195.596 + vertex 804.458 384.063 187.557 + vertex 807.31 378.579 195.339 + endloop + endfacet + facet normal -0.884681 -0.466176 -0.00429078 + outer loop + vertex 807.31 378.579 195.339 + vertex 804.458 384.063 187.557 + vertex 807.325 378.624 187.349 + endloop + endfacet + facet normal -0.884628 -0.466297 -0.000423374 + outer loop + vertex 804.458 384.063 187.557 + vertex 804.466 384.056 179.614 + vertex 807.325 378.624 187.349 + endloop + endfacet + facet normal -0.883237 -0.468919 -0.00277991 + outer loop + vertex 807.325 378.624 187.349 + vertex 804.466 384.056 179.614 + vertex 807.334 378.654 179.381 + endloop + endfacet + facet normal -0.883192 -0.469011 -0.000121831 + outer loop + vertex 804.466 384.056 179.614 + vertex 804.468 384.054 171.53 + vertex 807.334 378.654 179.381 + endloop + endfacet + facet normal -0.882558 -0.470203 -0.0011735 + outer loop + vertex 807.334 378.654 179.381 + vertex 804.468 384.054 171.53 + vertex 807.337 378.669 171.501 + endloop + endfacet + facet normal -0.882555 -0.470209 0.000171186 + outer loop + vertex 804.468 384.054 171.53 + vertex 804.465 384.057 163.949 + vertex 807.337 378.669 171.501 + endloop + endfacet + facet normal -0.882735 -0.469872 0.000480084 + outer loop + vertex 807.337 378.669 171.501 + vertex 804.465 384.057 163.949 + vertex 807.333 378.669 163.697 + endloop + endfacet + facet normal -0.882735 -0.469871 0.000456317 + outer loop + vertex 804.465 384.057 163.949 + vertex 804.457 384.064 156.165 + vertex 807.333 378.669 163.697 + endloop + endfacet + facet normal -0.883653 -0.468138 0.00204754 + outer loop + vertex 807.333 378.669 163.697 + vertex 804.457 384.064 156.165 + vertex 807.322 378.654 155.872 + endloop + endfacet + facet normal -0.883683 -0.468085 0.000757928 + outer loop + vertex 804.457 384.064 156.165 + vertex 804.444 384.076 148.224 + vertex 807.322 378.654 155.872 + endloop + endfacet + facet normal -0.885258 -0.465087 0.00347548 + outer loop + vertex 807.322 378.654 155.872 + vertex 804.444 384.076 148.224 + vertex 807.307 378.625 148.012 + endloop + endfacet + facet normal -0.885301 -0.465017 0.00107026 + outer loop + vertex 804.444 384.076 148.224 + vertex 804.425 384.093 140.323 + vertex 807.307 378.625 148.012 + endloop + endfacet + facet normal -0.835591 -0.549277 0.00903852 + outer loop + vertex 807.26 378.523 132.206 + vertex 807.223 378.45 124.368 + vertex 810.763 373.194 132.167 + endloop + endfacet + facet normal -0.83554 -0.549273 0.0131074 + outer loop + vertex 810.79 373.341 140.066 + vertex 807.26 378.523 132.206 + vertex 810.763 373.194 132.167 + endloop + endfacet + facet normal -0.831267 -0.555771 0.0106792 + outer loop + vertex 810.815 373.455 147.958 + vertex 807.287 378.582 140.105 + vertex 810.79 373.341 140.066 + endloop + endfacet + facet normal -0.808199 -0.588866 0.00709632 + outer loop + vertex 810.828 373.532 155.81 + vertex 810.815 373.455 147.958 + vertex 814.51 368.478 155.805 + endloop + endfacet + facet normal -0.8082 -0.588867 0.00701292 + outer loop + vertex 814.521 368.556 163.624 + vertex 810.828 373.532 155.81 + vertex 814.51 368.478 155.805 + endloop + endfacet + facet normal -0.806371 -0.591405 0.00226361 + outer loop + vertex 814.525 368.581 171.448 + vertex 810.839 373.577 163.628 + vertex 814.521 368.556 163.624 + endloop + endfacet + facet normal -0.80571 -0.592306 -0.00221369 + outer loop + vertex 814.523 368.554 179.323 + vertex 810.843 373.589 171.453 + vertex 814.525 368.581 171.448 + endloop + endfacet + facet normal -0.805924 -0.591975 -0.0071773 + outer loop + vertex 814.513 368.471 187.269 + vertex 810.841 373.567 179.33 + vertex 814.523 368.554 179.323 + endloop + endfacet + facet normal -0.807503 -0.589753 -0.0114149 + outer loop + vertex 814.499 368.337 195.257 + vertex 810.832 373.511 187.278 + vertex 814.513 368.471 187.269 + endloop + endfacet + facet normal -0.809733 -0.58658 -0.0160217 + outer loop + vertex 814.478 368.147 203.237 + vertex 810.817 373.419 195.267 + vertex 814.499 368.337 195.257 + endloop + endfacet + facet normal -0.813084 -0.581789 -0.0204001 + outer loop + vertex 814.453 367.904 211.163 + vertex 810.796 373.292 203.247 + vertex 814.478 368.147 203.237 + endloop + endfacet + facet normal -0.81733 -0.57559 -0.0258504 + outer loop + vertex 814.418 367.602 219.013 + vertex 810.772 373.13 211.175 + vertex 814.453 367.904 211.163 + endloop + endfacet + facet normal -0.822795 -0.567388 -0.0328477 + outer loop + vertex 814.357 367.241 226.781 + vertex 810.741 372.933 219.027 + vertex 814.418 367.602 219.013 + endloop + endfacet + facet normal -0.828378 -0.558588 -0.0420599 + outer loop + vertex 814.249 366.822 234.471 + vertex 810.679 372.693 226.795 + vertex 814.357 367.241 226.781 + endloop + endfacet + facet normal -0.846654 -0.529468 -0.0532972 + outer loop + vertex 814.063 366.353 242.069 + vertex 814.249 366.822 234.471 + vertex 817.689 360.555 242.073 + endloop + endfacet + facet normal -0.844911 -0.528396 -0.0832095 + outer loop + vertex 817.378 359.873 249.561 + vertex 814.063 366.353 242.069 + vertex 817.689 360.555 242.073 + endloop + endfacet + facet normal -0.866308 -0.487798 -0.107531 + outer loop + vertex 816.879 359.14 256.906 + vertex 817.378 359.873 249.561 + vertex 820.401 352.883 256.916 + endloop + endfacet + facet normal -0.871992 -0.48093 -0.0913066 + outer loop + vertex 820.899 353.819 249.565 + vertex 821.21 354.678 242.072 + vertex 824.286 347.68 249.559 + endloop + endfacet + facet normal -0.849153 -0.522835 -0.0747196 + outer loop + vertex 821.21 354.678 242.072 + vertex 817.875 361.181 234.468 + vertex 821.397 355.461 234.465 + endloop + endfacet + facet normal -0.844665 -0.531912 -0.0600871 + outer loop + vertex 821.397 355.461 234.465 + vertex 817.987 361.745 226.778 + vertex 821.508 356.155 226.774 + endloop + endfacet + facet normal -0.839969 -0.540485 -0.0482411 + outer loop + vertex 821.508 356.155 226.774 + vertex 818.048 362.224 219.01 + vertex 821.57 356.75 219.007 + endloop + endfacet + facet normal -0.835542 -0.548052 -0.0388456 + outer loop + vertex 821.57 356.75 219.007 + vertex 818.084 362.622 211.162 + vertex 821.608 357.249 211.163 + endloop + endfacet + facet normal -0.832249 -0.553527 -0.0311229 + outer loop + vertex 821.608 357.249 211.163 + vertex 818.111 362.952 203.239 + vertex 821.634 357.655 203.24 + endloop + endfacet + facet normal -0.829136 -0.558523 -0.0242085 + outer loop + vertex 821.634 357.655 203.24 + vertex 818.13 363.202 195.259 + vertex 821.655 357.97 195.263 + endloop + endfacet + facet normal -0.826832 -0.562177 -0.0175011 + outer loop + vertex 821.655 357.97 195.263 + vertex 818.145 363.38 187.272 + vertex 821.671 358.195 187.276 + endloop + endfacet + facet normal -0.825419 -0.564421 -0.0106485 + outer loop + vertex 821.671 358.195 187.276 + vertex 818.155 363.487 179.328 + vertex 821.682 358.329 179.331 + endloop + endfacet + facet normal -0.825187 -0.564849 -0.00336819 + outer loop + vertex 821.682 358.329 179.331 + vertex 818.159 363.522 171.451 + vertex 821.685 358.371 171.455 + endloop + endfacet + facet normal -0.825509 -0.564377 0.00362711 + outer loop + vertex 821.685 358.371 171.455 + vertex 818.154 363.485 163.627 + vertex 821.682 358.326 163.63 + endloop + endfacet + facet normal -0.825484 -0.564357 0.00878074 + outer loop + vertex 818.154 363.485 163.627 + vertex 818.144 363.378 155.805 + vertex 821.682 358.326 163.63 + endloop + endfacet + facet normal -0.816968 -0.576495 0.0147209 + outer loop + vertex 818.144 363.378 155.805 + vertex 814.495 368.35 147.95 + vertex 818.128 363.2 147.95 + endloop + endfacet + facet normal -0.820267 -0.571622 0.0202347 + outer loop + vertex 818.128 363.2 147.95 + vertex 814.473 368.167 140.058 + vertex 818.107 362.951 140.06 + endloop + endfacet + facet normal -0.824581 -0.565139 0.0261501 + outer loop + vertex 818.107 362.951 140.06 + vertex 814.444 367.931 132.162 + vertex 818.077 362.63 132.168 + endloop + endfacet + facet normal -0.824599 -0.565153 0.0252833 + outer loop + vertex 814.444 367.931 132.162 + vertex 814.401 367.642 124.305 + vertex 818.077 362.63 132.168 + endloop + endfacet + facet normal -0.83536 -0.548213 0.0404453 + outer loop + vertex 818.03 362.238 124.314 + vertex 814.331 367.299 116.517 + vertex 817.959 361.772 116.521 + endloop + endfacet + facet normal -0.825419 -0.564041 0.0232694 + outer loop + vertex 810.728 373.017 124.309 + vertex 810.659 372.797 116.516 + vertex 814.401 367.642 124.305 + endloop + endfacet + facet normal -0.838296 -0.543702 0.0405949 + outer loop + vertex 814.331 367.299 116.517 + vertex 810.557 372.544 108.825 + vertex 814.22 366.895 108.822 + endloop + endfacet + facet normal -0.846709 -0.531751 0.0179931 + outer loop + vertex 807.165 378.362 116.571 + vertex 807.066 378.259 108.854 + vertex 810.659 372.797 116.516 + endloop + endfacet + facet normal -0.859392 -0.509816 0.0391397 + outer loop + vertex 810.557 372.544 108.825 + vertex 806.895 378.136 101.27 + vertex 810.39 372.245 101.257 + endloop + endfacet + facet normal -0.902204 -0.43083 0.0203368 + outer loop + vertex 804.227 384.209 108.998 + vertex 804.033 384.252 101.281 + vertex 807.066 378.259 108.854 + endloop + endfacet + facet normal -0.859216 -0.509723 0.0439333 + outer loop + vertex 806.895 378.136 101.27 + vertex 806.6 377.993 93.84 + vertex 810.39 372.245 101.257 + endloop + endfacet + facet normal -0.838316 -0.543715 0.0400087 + outer loop + vertex 810.557 372.544 108.825 + vertex 810.39 372.245 101.257 + vertex 814.22 366.895 108.822 + endloop + endfacet + facet normal -0.835349 -0.548205 0.0407886 + outer loop + vertex 814.331 367.299 116.517 + vertex 814.22 366.895 108.822 + vertex 817.959 361.772 116.521 + endloop + endfacet + facet normal -0.840067 -0.541001 0.0400574 + outer loop + vertex 818.03 362.238 124.314 + vertex 817.959 361.772 116.521 + vertex 821.557 356.762 124.32 + endloop + endfacet + facet normal -0.840114 -0.541033 0.0386227 + outer loop + vertex 821.602 357.252 132.176 + vertex 818.03 362.238 124.314 + vertex 821.557 356.762 124.32 + endloop + endfacet + facet normal -0.84698 -0.530764 0.0302249 + outer loop + vertex 821.632 357.654 140.065 + vertex 821.602 357.252 132.176 + vertex 825.021 352.246 140.07 + endloop + endfacet + facet normal -0.847047 -0.530808 0.027474 + outer loop + vertex 825.043 352.619 147.958 + vertex 821.632 357.654 140.065 + vertex 825.021 352.246 140.07 + endloop + endfacet + facet normal -0.844441 -0.53527 0.0201155 + outer loop + vertex 825.061 352.887 155.812 + vertex 821.654 357.966 147.953 + vertex 825.043 352.619 147.958 + endloop + endfacet + facet normal -0.842535 -0.538509 0.0119544 + outer loop + vertex 825.07 353.046 163.632 + vertex 821.671 358.191 155.808 + vertex 825.061 352.887 155.812 + endloop + endfacet + facet normal -0.859966 -0.510337 0.00383973 + outer loop + vertex 825.073 353.1 171.457 + vertex 825.07 353.046 163.632 + vertex 828.296 347.669 171.45 + endloop + endfacet + facet normal -0.859969 -0.510328 -0.00423615 + outer loop + vertex 828.292 347.611 179.323 + vertex 825.073 353.1 171.457 + vertex 828.296 347.669 171.45 + endloop + endfacet + facet normal -0.860272 -0.509683 -0.012433 + outer loop + vertex 828.282 347.433 187.264 + vertex 825.069 353.049 179.332 + vertex 828.292 347.611 179.323 + endloop + endfacet + facet normal -0.860914 -0.508277 -0.0219572 + outer loop + vertex 828.263 347.121 195.247 + vertex 825.059 352.891 187.275 + vertex 828.282 347.433 187.264 + endloop + endfacet + facet normal -0.862879 -0.504567 -0.0291869 + outer loop + vertex 828.244 346.692 203.22 + vertex 825.044 352.625 195.261 + vertex 828.263 347.121 195.247 + endloop + endfacet + facet normal -0.864485 -0.501199 -0.0382792 + outer loop + vertex 828.218 346.132 211.138 + vertex 825.022 352.247 203.236 + vertex 828.244 346.692 203.22 + endloop + endfacet + facet normal -0.867034 -0.495985 -0.047445 + outer loop + vertex 828.182 345.446 218.978 + vertex 824.996 351.762 211.156 + vertex 828.218 346.132 211.138 + endloop + endfacet + facet normal -0.869832 -0.48978 -0.0592305 + outer loop + vertex 828.116 344.624 226.74 + vertex 824.958 351.168 218.998 + vertex 828.182 345.446 218.978 + endloop + endfacet + facet normal -0.873484 -0.481557 -0.0716063 + outer loop + vertex 828.006 343.679 234.431 + vertex 824.896 350.461 226.763 + vertex 828.116 344.624 226.74 + endloop + endfacet + facet normal -0.876266 -0.473659 -0.0883459 + outer loop + vertex 827.817 342.609 242.04 + vertex 824.784 349.636 234.454 + vertex 828.006 343.679 234.431 + endloop + endfacet + facet normal -0.878734 -0.464437 -0.110111 + outer loop + vertex 827.505 341.421 249.54 + vertex 824.594 348.703 242.061 + vertex 827.817 342.609 242.04 + endloop + endfacet + facet normal -0.901073 -0.412182 -0.134812 + outer loop + vertex 827.007 340.104 256.9 + vertex 827.505 341.421 249.54 + vertex 830.024 333.51 256.891 + endloop + endfacet + facet normal -0.882153 -0.470944 0.00426918 + outer loop + vertex 831.317 342.002 171.428 + vertex 828.29 347.6 163.626 + vertex 831.316 341.932 163.605 + endloop + endfacet + facet normal -0.883205 -0.468771 0.0142748 + outer loop + vertex 831.316 341.932 163.605 + vertex 828.28 347.415 155.806 + vertex 831.304 341.717 155.785 + endloop + endfacet + facet normal -0.884332 -0.466318 0.0224526 + outer loop + vertex 831.304 341.717 155.785 + vertex 828.263 347.106 147.952 + vertex 831.287 341.37 147.931 + endloop + endfacet + facet normal -0.886011 -0.462609 0.0312584 + outer loop + vertex 831.287 341.37 147.931 + vertex 828.24 346.675 140.065 + vertex 831.264 340.882 140.044 + endloop + endfacet + facet normal -0.910479 -0.411602 0.0401487 + outer loop + vertex 834.049 334.8 140.021 + vertex 831.235 340.258 132.152 + vertex 834.017 334.102 132.128 + endloop + endfacet + facet normal -0.885884 -0.462557 0.0353609 + outer loop + vertex 828.24 346.675 140.065 + vertex 828.213 346.124 132.175 + vertex 831.264 340.882 140.044 + endloop + endfacet + facet normal -0.89051 -0.452275 0.0493888 + outer loop + vertex 831.235 340.258 132.152 + vertex 828.166 345.446 124.317 + vertex 831.189 339.491 124.293 + endloop + endfacet + facet normal -0.867564 -0.495584 0.041591 + outer loop + vertex 824.99 351.766 132.18 + vertex 824.947 351.183 124.323 + vertex 828.213 346.124 132.175 + endloop + endfacet + facet normal -0.858078 -0.510634 0.0543596 + outer loop + vertex 824.947 351.183 124.323 + vertex 821.48 356.178 116.525 + vertex 824.869 350.483 116.525 + endloop + endfacet + facet normal -0.857841 -0.510493 0.0592106 + outer loop + vertex 821.48 356.178 116.525 + vertex 821.36 355.486 108.816 + vertex 824.869 350.483 116.525 + endloop + endfacet + facet normal -0.867352 -0.49054 0.0840911 + outer loop + vertex 824.747 349.655 108.811 + vertex 821.174 354.674 101.235 + vertex 824.56 348.684 101.222 + endloop + endfacet + facet normal -0.850574 -0.521809 0.0651127 + outer loop + vertex 817.841 361.222 108.818 + vertex 817.659 360.574 101.243 + vertex 821.36 355.486 108.816 + endloop + endfacet + facet normal -0.861913 -0.497877 0.096042 + outer loop + vertex 821.174 354.674 101.235 + vertex 817.366 359.84 93.8351 + vertex 820.879 353.755 93.8263 + endloop + endfacet + facet normal -0.84835 -0.524569 0.0716145 + outer loop + vertex 814.044 366.42 101.251 + vertex 813.754 365.877 93.8365 + vertex 817.659 360.574 101.243 + endloop + endfacet + facet normal -0.86021 -0.497237 0.113112 + outer loop + vertex 817.366 359.84 93.8351 + vertex 813.256 365.302 86.5925 + vertex 816.863 359.066 86.6137 + endloop + endfacet + facet normal -0.851986 -0.516624 0.0849699 + outer loop + vertex 810.101 371.901 93.8321 + vertex 809.6 371.532 86.5617 + vertex 813.754 365.877 93.8365 + endloop + endfacet + facet normal -0.874932 -0.467593 0.125899 + outer loop + vertex 809.6 371.532 86.5617 + vertex 805.294 377.681 79.4762 + vertex 808.771 371.173 79.4709 + endloop + endfacet + facet normal -0.870513 -0.46526 0.16044 + outer loop + vertex 805.294 377.681 79.4762 + vertex 804.117 377.54 72.6783 + vertex 808.771 371.173 79.4709 + endloop + endfacet + facet normal -0.914779 -0.331785 0.23043 + outer loop + vertex 804.117 377.54 72.6783 + vertex 800.054 384.55 66.6435 + vertex 802.61 377.321 66.383 + endloop + endfacet + facet normal -0.861027 -0.468829 0.197056 + outer loop + vertex 812.424 364.737 79.5292 + vertex 807.546 370.805 72.6478 + vertex 811.193 364.14 72.7282 + endloop + endfacet + facet normal -0.857214 -0.49541 0.140542 + outer loop + vertex 813.256 365.302 86.5925 + vertex 812.424 364.737 79.5292 + vertex 816.863 359.066 86.6137 + endloop + endfacet + facet normal -0.86035 -0.496999 0.113096 + outer loop + vertex 817.366 359.84 93.8351 + vertex 816.863 359.066 86.6137 + vertex 820.879 353.755 93.8263 + endloop + endfacet + facet normal -0.866467 -0.490063 0.0952542 + outer loop + vertex 821.174 354.674 101.235 + vertex 820.879 353.755 93.8263 + vertex 824.56 348.684 101.222 + endloop + endfacet + facet normal -0.877385 -0.472717 0.0820574 + outer loop + vertex 824.747 349.655 108.811 + vertex 824.56 348.684 101.222 + vertex 827.966 343.677 108.797 + endloop + endfacet + facet normal -0.878015 -0.473035 0.0729955 + outer loop + vertex 828.091 344.638 116.516 + vertex 824.747 349.655 108.811 + vertex 827.966 343.677 108.797 + endloop + endfacet + facet normal -0.89022 -0.452152 0.0553913 + outer loop + vertex 828.166 345.446 124.317 + vertex 828.091 344.638 116.516 + vertex 831.189 339.491 124.293 + endloop + endfacet + facet normal -0.910261 -0.411524 0.0455266 + outer loop + vertex 831.235 340.258 132.152 + vertex 831.189 339.491 124.293 + vertex 834.017 334.102 132.128 + endloop + endfacet + facet normal -0.913511 -0.402253 0.0607498 + outer loop + vertex 833.969 333.254 124.269 + vertex 831.11 338.573 116.49 + vertex 833.892 332.253 116.47 + endloop + endfacet + facet normal -0.915395 -0.395325 0.0759653 + outer loop + vertex 833.892 332.253 116.47 + vertex 830.988 337.497 108.768 + vertex 833.76 331.076 108.76 + endloop + endfacet + facet normal -0.935199 -0.342277 0.0908301 + outer loop + vertex 836.244 324.422 108.817 + vertex 833.562 329.723 101.177 + vertex 836.04 322.971 101.245 + endloop + endfacet + facet normal -0.933545 -0.341489 0.108995 + outer loop + vertex 833.562 329.723 101.177 + vertex 833.255 328.198 93.7723 + vertex 836.04 322.971 101.245 + endloop + endfacet + facet normal -0.935303 -0.334891 0.114265 + outer loop + vertex 836.04 322.971 101.245 + vertex 833.255 328.198 93.7723 + vertex 835.726 321.323 93.847 + endloop + endfacet + facet normal -0.932021 -0.33341 0.142038 + outer loop + vertex 833.255 328.198 93.7723 + vertex 832.76 326.514 86.5655 + vertex 835.726 321.323 93.847 + endloop + endfacet + facet normal -0.93341 -0.327354 0.146921 + outer loop + vertex 835.726 321.323 93.847 + vertex 832.76 326.514 86.5655 + vertex 835.237 319.485 86.6426 + endloop + endfacet + facet normal -0.926302 -0.324357 0.191719 + outer loop + vertex 832.76 326.514 86.5655 + vertex 831.96 324.652 79.55 + vertex 835.237 319.485 86.6426 + endloop + endfacet + facet normal -0.927307 -0.318692 0.19631 + outer loop + vertex 835.237 319.485 86.6426 + vertex 831.96 324.652 79.55 + vertex 834.453 317.447 79.63 + endloop + endfacet + facet normal -0.941585 -0.280261 0.18674 + outer loop + vertex 835.237 319.485 86.6426 + vertex 834.453 317.447 79.63 + vertex 837.428 312.174 86.7164 + endloop + endfacet + facet normal -0.948754 -0.282872 0.140885 + outer loop + vertex 837.91 314.143 93.9213 + vertex 835.237 319.485 86.6426 + vertex 837.428 312.174 86.7164 + endloop + endfacet + facet normal -0.961247 -0.242714 0.130747 + outer loop + vertex 837.91 314.143 93.9213 + vertex 837.428 312.174 86.7164 + vertex 839.827 306.507 93.8356 + endloop + endfacet + facet normal -0.964695 -0.243245 0.100972 + outer loop + vertex 840.133 308.379 101.272 + vertex 837.91 314.143 93.9213 + vertex 839.827 306.507 93.8356 + endloop + endfacet + facet normal -0.972306 -0.214008 0.0939253 + outer loop + vertex 840.133 308.379 101.272 + vertex 839.827 306.507 93.8356 + vertex 841.88 300.26 100.856 + endloop + endfacet + facet normal -0.974181 -0.213378 0.073765 + outer loop + vertex 842.076 302.033 108.574 + vertex 840.133 308.379 101.272 + vertex 841.88 300.26 100.856 + endloop + endfacet + facet normal -0.976971 -0.201198 0.0710378 + outer loop + vertex 842.076 302.033 108.574 + vertex 841.88 300.26 100.856 + vertex 843.774 293.495 107.749 + endloop + endfacet + facet normal -0.977228 -0.199225 0.0730441 + outer loop + vertex 843.774 293.495 107.749 + vertex 841.88 300.26 100.856 + vertex 843.571 291.663 100.036 + endloop + endfacet + facet normal -0.974911 -0.200938 0.0957764 + outer loop + vertex 841.88 300.26 100.856 + vertex 841.551 298.31 93.4191 + vertex 843.571 291.663 100.036 + endloop + endfacet + facet normal -0.975227 -0.197804 0.0990213 + outer loop + vertex 843.571 291.663 100.036 + vertex 841.551 298.31 93.4191 + vertex 843.225 289.665 92.6353 + endloop + endfacet + facet normal -0.970985 -0.215531 0.10361 + outer loop + vertex 843.571 291.663 100.036 + vertex 843.225 289.665 92.6353 + vertex 844.661 285.773 97.9974 + endloop + endfacet + facet normal -0.971265 -0.199786 0.129347 + outer loop + vertex 841.551 298.31 93.4191 + vertex 841.034 296.17 86.2309 + vertex 843.225 289.665 92.6353 + endloop + endfacet + facet normal -0.971473 -0.196524 0.132732 + outer loop + vertex 843.225 289.665 92.6353 + vertex 841.034 296.17 86.2309 + vertex 842.7 287.401 85.4404 + endloop + endfacet + facet normal -0.96544 -0.22003 0.139686 + outer loop + vertex 843.225 289.665 92.6353 + vertex 842.7 287.401 85.4404 + vertex 844.311 283.618 90.6152 + endloop + endfacet + facet normal -0.963521 -0.199164 0.178776 + outer loop + vertex 841.034 296.17 86.2309 + vertex 840.23 293.786 79.2379 + vertex 842.7 287.401 85.4404 + endloop + endfacet + facet normal -0.962684 -0.202309 0.179752 + outer loop + vertex 841.034 296.17 86.2309 + vertex 838.544 302.159 79.6324 + vertex 840.23 293.786 79.2379 + endloop + endfacet + facet normal -0.962488 -0.206943 0.175473 + outer loop + vertex 839.33 304.435 86.6324 + vertex 838.544 302.159 79.6324 + vertex 841.034 296.17 86.2309 + endloop + endfacet + facet normal -0.955289 -0.232307 0.182911 + outer loop + vertex 839.33 304.435 86.6324 + vertex 836.651 310 79.7083 + vertex 838.544 302.159 79.6324 + endloop + endfacet + facet normal -0.954905 -0.236728 0.17921 + outer loop + vertex 837.428 312.174 86.7164 + vertex 836.651 310 79.7083 + vertex 839.33 304.435 86.6324 + endloop + endfacet + facet normal -0.969665 -0.20627 0.131163 + outer loop + vertex 841.551 298.31 93.4191 + vertex 839.33 304.435 86.6324 + vertex 841.034 296.17 86.2309 + endloop + endfacet + facet normal -0.969291 -0.210387 0.127324 + outer loop + vertex 839.827 306.507 93.8356 + vertex 839.33 304.435 86.6324 + vertex 841.551 298.31 93.4191 + endloop + endfacet + facet normal -0.973838 -0.215632 0.0717141 + outer loop + vertex 840.321 310.076 108.922 + vertex 840.133 308.379 101.272 + vertex 842.076 302.033 108.574 + endloop + endfacet + facet normal -0.974954 -0.215202 0.0561407 + outer loop + vertex 842.16 303.71 116.456 + vertex 840.321 310.076 108.922 + vertex 842.076 302.033 108.574 + endloop + endfacet + facet normal -0.978045 -0.201474 0.0532515 + outer loop + vertex 842.16 303.71 116.456 + vertex 842.076 302.033 108.574 + vertex 843.914 295.02 115.79 + endloop + endfacet + facet normal -0.978684 -0.200818 0.0430113 + outer loop + vertex 843.856 297.01 123.774 + vertex 842.16 303.71 116.456 + vertex 843.914 295.02 115.79 + endloop + endfacet + facet normal -0.978371 -0.202712 0.0412048 + outer loop + vertex 842.182 305.214 124.38 + vertex 842.16 303.71 116.456 + vertex 843.856 297.01 123.774 + endloop + endfacet + facet normal -0.97884 -0.202122 0.0319271 + outer loop + vertex 843.837 298.374 131.818 + vertex 842.182 305.214 124.38 + vertex 843.856 297.01 123.774 + endloop + endfacet + facet normal -0.975689 -0.216447 0.0343649 + outer loop + vertex 843.837 298.374 131.818 + vertex 843.856 297.01 123.774 + vertex 845.631 290.14 130.897 + endloop + endfacet + facet normal -0.976117 -0.215642 0.0263396 + outer loop + vertex 845.614 291.198 138.939 + vertex 843.837 298.374 131.818 + vertex 845.631 290.14 130.897 + endloop + endfacet + facet normal -0.976205 -0.215183 0.0268245 + outer loop + vertex 843.841 299.345 139.769 + vertex 843.837 298.374 131.818 + vertex 845.614 291.198 138.939 + endloop + endfacet + facet normal -0.976475 -0.214626 0.0207839 + outer loop + vertex 845.619 291.947 146.869 + vertex 843.841 299.345 139.769 + vertex 845.614 291.198 138.939 + endloop + endfacet + facet normal -0.976532 -0.214339 0.0210978 + outer loop + vertex 843.858 300.046 147.662 + vertex 843.841 299.345 139.769 + vertex 845.619 291.947 146.869 + endloop + endfacet + facet normal -0.976749 -0.21383 0.0154216 + outer loop + vertex 845.627 292.475 154.73 + vertex 843.858 300.046 147.662 + vertex 845.619 291.947 146.869 + endloop + endfacet + facet normal -0.976797 -0.213591 0.01569 + outer loop + vertex 843.877 300.535 155.498 + vertex 843.858 300.046 147.662 + vertex 845.627 292.475 154.73 + endloop + endfacet + facet normal -0.976997 -0.213044 0.00949198 + outer loop + vertex 845.63 292.808 162.518 + vertex 843.877 300.535 155.498 + vertex 845.627 292.475 154.73 + endloop + endfacet + facet normal -0.977082 -0.212631 0.00996772 + outer loop + vertex 843.888 300.852 163.312 + vertex 843.877 300.535 155.498 + vertex 845.63 292.808 162.518 + endloop + endfacet + facet normal -0.977226 -0.212147 0.00475005 + outer loop + vertex 845.637 292.951 170.305 + vertex 843.888 300.852 163.312 + vertex 845.63 292.808 162.518 + endloop + endfacet + facet normal -0.97703 -0.213073 0.0036554 + outer loop + vertex 843.89 300.975 171.136 + vertex 843.888 300.852 163.312 + vertex 845.637 292.951 170.305 + endloop + endfacet + facet normal -0.977142 -0.212581 -0.00132239 + outer loop + vertex 845.638 292.898 178.181 + vertex 843.89 300.975 171.136 + vertex 845.637 292.951 170.305 + endloop + endfacet + facet normal -0.976967 -0.213376 -0.00227674 + outer loop + vertex 843.888 300.903 179.01 + vertex 843.89 300.975 171.136 + vertex 845.638 292.898 178.181 + endloop + endfacet + facet normal -0.977048 -0.212905 -0.00699222 + outer loop + vertex 845.636 292.645 186.134 + vertex 843.888 300.903 179.01 + vertex 845.638 292.898 178.181 + endloop + endfacet + facet normal -0.976814 -0.213931 -0.00823811 + outer loop + vertex 843.881 300.629 186.934 + vertex 843.888 300.903 179.01 + vertex 845.636 292.645 186.134 + endloop + endfacet + facet normal -0.976866 -0.213448 -0.0131727 + outer loop + vertex 845.63 292.18 194.11 + vertex 843.881 300.629 186.934 + vertex 845.636 292.645 186.134 + endloop + endfacet + facet normal -0.976673 -0.214264 -0.0141803 + outer loop + vertex 843.872 300.141 194.895 + vertex 843.881 300.629 186.934 + vertex 845.63 292.18 194.11 + endloop + endfacet + facet normal -0.97669 -0.213933 -0.017573 + outer loop + vertex 845.635 291.502 202.072 + vertex 843.872 300.141 194.895 + vertex 845.63 292.18 194.11 + endloop + endfacet + facet normal -0.976232 -0.215809 -0.0199433 + outer loop + vertex 843.867 299.424 202.908 + vertex 843.872 300.141 194.895 + vertex 845.635 291.502 202.072 + endloop + endfacet + facet normal -0.976235 -0.215378 -0.0240291 + outer loop + vertex 845.644 290.561 210.162 + vertex 843.867 299.424 202.908 + vertex 845.635 291.502 202.072 + endloop + endfacet + facet normal -0.97605 -0.21611 -0.024969 + outer loop + vertex 843.861 298.515 211.002 + vertex 843.867 299.424 202.908 + vertex 845.644 290.561 210.162 + endloop + endfacet + facet normal -0.976033 -0.215674 -0.0290589 + outer loop + vertex 845.693 289.153 218.966 + vertex 843.861 298.515 211.002 + vertex 845.644 290.561 210.162 + endloop + endfacet + facet normal -0.975393 -0.218126 -0.0320893 + outer loop + vertex 843.753 297.866 218.701 + vertex 843.861 298.515 211.002 + vertex 845.693 289.153 218.966 + endloop + endfacet + facet normal -0.978885 -0.202079 -0.0307857 + outer loop + vertex 843.753 297.866 218.701 + vertex 842.234 306.362 211.238 + vertex 843.861 298.515 211.002 + endloop + endfacet + facet normal -0.979026 -0.202309 -0.0240834 + outer loop + vertex 842.234 306.362 211.238 + vertex 842.256 307.199 203.311 + vertex 843.861 298.515 211.002 + endloop + endfacet + facet normal -0.975663 -0.217762 -0.0257052 + outer loop + vertex 842.234 306.362 211.238 + vertex 840.596 314.631 203.375 + vertex 842.256 307.199 203.311 + endloop + endfacet + facet normal -0.975762 -0.217825 -0.0209777 + outer loop + vertex 840.596 314.631 203.375 + vertex 840.612 315.325 195.386 + vertex 842.256 307.199 203.311 + endloop + endfacet + facet normal -0.975879 -0.217349 -0.0204651 + outer loop + vertex 842.256 307.199 203.311 + vertex 840.612 315.325 195.386 + vertex 842.264 307.915 195.303 + endloop + endfacet + facet normal -0.979216 -0.201918 -0.0190902 + outer loop + vertex 842.256 307.199 203.311 + vertex 842.264 307.915 195.303 + vertex 843.867 299.424 202.908 + endloop + endfacet + facet normal -0.975965 -0.217432 -0.0146704 + outer loop + vertex 840.612 315.325 195.386 + vertex 840.625 315.808 187.399 + vertex 842.264 307.915 195.303 + endloop + endfacet + facet normal -0.975889 -0.217752 -0.0150052 + outer loop + vertex 842.264 307.915 195.303 + vertex 840.625 315.808 187.399 + vertex 842.276 308.414 187.329 + endloop + endfacet + facet normal -0.979325 -0.201807 -0.0140114 + outer loop + vertex 842.264 307.915 195.303 + vertex 842.276 308.414 187.329 + vertex 843.872 300.141 194.895 + endloop + endfacet + facet normal -0.975947 -0.217821 -0.00905056 + outer loop + vertex 840.625 315.808 187.399 + vertex 840.637 316.084 179.472 + vertex 842.276 308.414 187.329 + endloop + endfacet + facet normal -0.975951 -0.217804 -0.0090333 + outer loop + vertex 842.276 308.414 187.329 + vertex 840.637 316.084 179.472 + vertex 842.287 308.693 179.408 + endloop + endfacet + facet normal -0.97945 -0.20151 -0.00846482 + outer loop + vertex 842.276 308.414 187.329 + vertex 842.287 308.693 179.408 + vertex 843.881 300.629 186.934 + endloop + endfacet + facet normal -0.975975 -0.217862 -0.00293281 + outer loop + vertex 840.637 316.084 179.472 + vertex 840.643 316.163 171.608 + vertex 842.287 308.693 179.408 + endloop + endfacet + facet normal -0.976 -0.217751 -0.00282173 + outer loop + vertex 842.287 308.693 179.408 + vertex 840.643 316.163 171.608 + vertex 842.292 308.772 171.542 + endloop + endfacet + facet normal -0.979554 -0.201163 -0.00265695 + outer loop + vertex 842.287 308.693 179.408 + vertex 842.292 308.772 171.542 + vertex 843.888 300.903 179.01 + endloop + endfacet + facet normal -0.975986 -0.217804 0.00349021 + outer loop + vertex 840.643 316.163 171.608 + vertex 840.639 316.054 163.781 + vertex 842.292 308.772 171.542 + endloop + endfacet + facet normal -0.975934 -0.218042 0.00325541 + outer loop + vertex 842.292 308.772 171.542 + vertex 840.639 316.054 163.781 + vertex 842.29 308.663 163.715 + endloop + endfacet + facet normal -0.979592 -0.200972 0.00301864 + outer loop + vertex 842.292 308.772 171.542 + vertex 842.29 308.663 163.715 + vertex 843.89 300.975 171.136 + endloop + endfacet + facet normal -0.975887 -0.218085 0.00914007 + outer loop + vertex 840.639 316.054 163.781 + vertex 840.63 315.768 155.953 + vertex 842.29 308.663 163.715 + endloop + endfacet + facet normal -0.976007 -0.217524 0.00967936 + outer loop + vertex 842.29 308.663 163.715 + vertex 840.63 315.768 155.953 + vertex 842.279 308.366 155.891 + endloop + endfacet + facet normal -0.979584 -0.200832 0.00905109 + outer loop + vertex 842.29 308.663 163.715 + vertex 842.279 308.366 155.891 + vertex 843.888 300.852 163.312 + endloop + endfacet + facet normal -0.975929 -0.217553 0.0153057 + outer loop + vertex 840.63 315.768 155.953 + vertex 840.611 315.3 148.096 + vertex 842.279 308.366 155.891 + endloop + endfacet + facet normal -0.976027 -0.217081 0.0157468 + outer loop + vertex 842.279 308.366 155.891 + vertex 840.611 315.3 148.096 + vertex 842.258 307.888 148.044 + endloop + endfacet + facet normal -0.979548 -0.20067 0.0147554 + outer loop + vertex 842.279 308.366 155.891 + vertex 842.258 307.888 148.044 + vertex 843.877 300.535 155.498 + endloop + endfacet + facet normal -0.975925 -0.217095 0.0209704 + outer loop + vertex 840.611 315.3 148.096 + vertex 840.583 314.663 140.221 + vertex 842.258 307.888 148.044 + endloop + endfacet + facet normal -0.976064 -0.216408 0.0215957 + outer loop + vertex 842.258 307.888 148.044 + vertex 840.583 314.663 140.221 + vertex 842.23 307.229 140.173 + endloop + endfacet + facet normal -0.979426 -0.20078 0.0203003 + outer loop + vertex 842.258 307.888 148.044 + vertex 842.23 307.229 140.173 + vertex 843.858 300.046 147.662 + endloop + endfacet + facet normal -0.975929 -0.216412 0.0269822 + outer loop + vertex 840.583 314.663 140.221 + vertex 840.545 313.853 132.355 + vertex 842.23 307.229 140.173 + endloop + endfacet + facet normal -0.975978 -0.216162 0.0272047 + outer loop + vertex 842.23 307.229 140.173 + vertex 840.545 313.853 132.355 + vertex 842.203 306.362 132.289 + endloop + endfacet + facet normal -0.979174 -0.201402 0.0255931 + outer loop + vertex 842.23 307.229 140.173 + vertex 842.203 306.362 132.289 + vertex 843.841 299.345 139.769 + endloop + endfacet + facet normal -0.975762 -0.216174 0.0340256 + outer loop + vertex 840.545 313.853 132.355 + vertex 840.497 312.839 124.513 + vertex 842.203 306.362 132.289 + endloop + endfacet + facet normal -0.975743 -0.21627 0.033942 + outer loop + vertex 842.203 306.362 132.289 + vertex 840.497 312.839 124.513 + vertex 842.182 305.214 124.38 + endloop + endfacet + facet normal -0.975356 -0.216348 0.0433036 + outer loop + vertex 840.497 312.839 124.513 + vertex 840.429 311.578 116.695 + vertex 842.182 305.214 124.38 + endloop + endfacet + facet normal -0.966774 -0.250932 0.0488056 + outer loop + vertex 840.497 312.839 124.513 + vertex 838.545 318.826 116.633 + vertex 840.429 311.578 116.695 + endloop + endfacet + facet normal -0.966192 -0.250683 0.0602597 + outer loop + vertex 838.545 318.826 116.633 + vertex 838.414 317.478 108.927 + vertex 840.429 311.578 116.695 + endloop + endfacet + facet normal -0.966531 -0.249047 0.0615902 + outer loop + vertex 840.429 311.578 116.695 + vertex 838.414 317.478 108.927 + vertex 840.321 310.076 108.922 + endloop + endfacet + facet normal -0.965549 -0.248803 0.0762422 + outer loop + vertex 838.414 317.478 108.927 + vertex 838.217 315.915 101.335 + vertex 840.321 310.076 108.922 + endloop + endfacet + facet normal -0.96632 -0.252992 0.0471281 + outer loop + vertex 838.628 319.957 124.409 + vertex 838.545 318.826 116.633 + vertex 840.497 312.839 124.513 + endloop + endfacet + facet normal -0.966638 -0.253198 0.0387558 + outer loop + vertex 840.545 313.853 132.355 + vertex 838.628 319.957 124.409 + vertex 840.497 312.839 124.513 + endloop + endfacet + facet normal -0.966413 -0.254176 0.0379505 + outer loop + vertex 838.685 320.908 132.242 + vertex 838.628 319.957 124.409 + vertex 840.545 313.853 132.355 + endloop + endfacet + facet normal -0.966622 -0.254345 0.0308439 + outer loop + vertex 840.583 314.663 140.221 + vertex 838.685 320.908 132.242 + vertex 840.545 313.853 132.355 + endloop + endfacet + facet normal -0.96619 -0.256157 0.0293232 + outer loop + vertex 838.718 321.687 140.12 + vertex 838.685 320.908 132.242 + vertex 840.583 314.663 140.221 + endloop + endfacet + facet normal -0.966307 -0.256263 0.0241034 + outer loop + vertex 840.611 315.3 148.096 + vertex 838.718 321.687 140.12 + vertex 840.583 314.663 140.221 + endloop + endfacet + facet normal -0.966145 -0.256922 0.0235374 + outer loop + vertex 838.744 322.311 148.007 + vertex 838.718 321.687 140.12 + vertex 840.611 315.3 148.096 + endloop + endfacet + facet normal -0.966244 -0.257024 0.0176343 + outer loop + vertex 840.63 315.768 155.953 + vertex 838.744 322.311 148.007 + vertex 840.611 315.3 148.096 + endloop + endfacet + facet normal -0.966095 -0.257621 0.0171069 + outer loop + vertex 838.763 322.763 155.866 + vertex 838.744 322.311 148.007 + vertex 840.63 315.768 155.953 + endloop + endfacet + facet normal -0.966162 -0.25772 0.010578 + outer loop + vertex 840.639 316.054 163.781 + vertex 838.763 322.763 155.866 + vertex 840.63 315.768 155.953 + endloop + endfacet + facet normal -0.966096 -0.257974 0.0103474 + outer loop + vertex 838.773 323.038 163.692 + vertex 838.763 322.763 155.866 + vertex 840.639 316.054 163.781 + endloop + endfacet + facet normal -0.96612 -0.25806 0.00404777 + outer loop + vertex 840.643 316.163 171.608 + vertex 838.773 323.038 163.692 + vertex 840.639 316.054 163.781 + endloop + endfacet + facet normal -0.966016 -0.258455 0.00368049 + outer loop + vertex 838.776 323.139 171.515 + vertex 838.773 323.038 163.692 + vertex 840.643 316.163 171.608 + endloop + endfacet + facet normal -0.965994 -0.258542 -0.00333275 + outer loop + vertex 840.637 316.084 179.472 + vertex 838.776 323.139 171.515 + vertex 840.643 316.163 171.608 + endloop + endfacet + facet normal -0.966021 -0.258444 -0.00324005 + outer loop + vertex 838.77 323.064 179.382 + vertex 838.776 323.139 171.515 + vertex 840.637 316.084 179.472 + endloop + endfacet + facet normal -0.96595 -0.258518 -0.0104528 + outer loop + vertex 840.625 315.808 187.399 + vertex 838.77 323.064 179.382 + vertex 840.637 316.084 179.472 + endloop + endfacet + facet normal -0.96604 -0.258193 -0.0101379 + outer loop + vertex 838.756 322.802 187.319 + vertex 838.77 323.064 179.382 + vertex 840.625 315.808 187.399 + endloop + endfacet + facet normal -0.965928 -0.258243 -0.0171271 + outer loop + vertex 840.612 315.325 195.386 + vertex 838.756 322.802 187.319 + vertex 840.625 315.808 187.399 + endloop + endfacet + facet normal -0.966142 -0.257489 -0.0163794 + outer loop + vertex 838.741 322.35 195.311 + vertex 838.756 322.802 187.319 + vertex 840.612 315.325 195.386 + endloop + endfacet + facet normal -0.965963 -0.257527 -0.0244055 + outer loop + vertex 840.596 314.631 203.375 + vertex 838.741 322.35 195.311 + vertex 840.612 315.325 195.386 + endloop + endfacet + facet normal -0.966518 -0.255614 -0.0224464 + outer loop + vertex 838.723 321.716 203.307 + vertex 838.741 322.35 195.311 + vertex 840.596 314.631 203.375 + endloop + endfacet + facet normal -0.966322 -0.255631 -0.0295743 + outer loop + vertex 840.579 313.778 211.296 + vertex 838.723 321.716 203.307 + vertex 840.596 314.631 203.375 + endloop + endfacet + facet normal -0.966202 -0.256035 -0.0300041 + outer loop + vertex 838.692 320.904 211.246 + vertex 838.723 321.716 203.307 + vertex 840.579 313.778 211.296 + endloop + endfacet + facet normal -0.965907 -0.256017 -0.0384434 + outer loop + vertex 840.549 312.719 219.101 + vertex 838.692 320.904 211.246 + vertex 840.579 313.778 211.296 + endloop + endfacet + facet normal -0.975316 -0.21828 -0.0333572 + outer loop + vertex 840.549 312.719 219.101 + vertex 840.579 313.778 211.296 + vertex 842.199 305.37 218.937 + endloop + endfacet + facet normal -0.975015 -0.218004 -0.0426743 + outer loop + vertex 842.187 303.936 226.536 + vertex 840.549 312.719 219.101 + vertex 842.199 305.37 218.937 + endloop + endfacet + facet normal -0.978575 -0.202032 -0.0396647 + outer loop + vertex 842.187 303.936 226.536 + vertex 842.199 305.37 218.937 + vertex 843.656 296.96 225.822 + endloop + endfacet + facet normal -0.978377 -0.201103 -0.0483278 + outer loop + vertex 843.824 294.313 233.439 + vertex 842.187 303.936 226.536 + vertex 843.656 296.96 225.822 + endloop + endfacet + facet normal -0.975834 -0.21218 -0.0522337 + outer loop + vertex 843.824 294.313 233.439 + vertex 843.656 296.96 225.822 + vertex 844.963 289.674 231.012 + endloop + endfacet + facet normal -0.977549 -0.204035 -0.0526103 + outer loop + vertex 842.13 302.243 234.156 + vertex 842.187 303.936 226.536 + vertex 843.824 294.313 233.439 + endloop + endfacet + facet normal -0.977017 -0.20272 -0.0658948 + outer loop + vertex 843.714 292.372 241.04 + vertex 842.13 302.243 234.156 + vertex 843.824 294.313 233.439 + endloop + endfacet + facet normal -0.973128 -0.21934 -0.0700838 + outer loop + vertex 843.714 292.372 241.04 + vertex 843.824 294.313 233.439 + vertex 844.957 287.475 239.102 + endloop + endfacet + facet normal -0.975855 -0.206403 -0.071443 + outer loop + vertex 841.931 300.562 241.739 + vertex 842.13 302.243 234.156 + vertex 843.714 292.372 241.04 + endloop + endfacet + facet normal -0.974639 -0.204475 -0.0909336 + outer loop + vertex 843.411 290.48 248.549 + vertex 841.931 300.562 241.739 + vertex 843.714 292.372 241.04 + endloop + endfacet + facet normal -0.969081 -0.227126 -0.0964164 + outer loop + vertex 843.411 290.48 248.549 + vertex 843.714 292.372 241.04 + vertex 844.754 285.594 246.557 + endloop + endfacet + facet normal -0.973611 -0.207327 -0.0953791 + outer loop + vertex 841.587 298.712 249.267 + vertex 841.931 300.562 241.739 + vertex 843.411 290.48 248.549 + endloop + endfacet + facet normal -0.971123 -0.204355 -0.123124 + outer loop + vertex 842.926 288.295 256 + vertex 841.587 298.712 249.267 + vertex 843.411 290.48 248.549 + endloop + endfacet + facet normal -0.964037 -0.231458 -0.130611 + outer loop + vertex 842.926 288.295 256 + vertex 843.411 290.48 248.549 + vertex 844.35 283.472 254.033 + endloop + endfacet + facet normal -0.963521 -0.226298 -0.142886 + outer loop + vertex 844.248 281.398 258.005 + vertex 842.926 288.295 256 + vertex 844.35 283.472 254.033 + endloop + endfacet + facet normal -0.957412 -0.233112 -0.170352 + outer loop + vertex 844.248 281.398 258.005 + vertex 843.747 280.954 261.431 + vertex 842.926 288.295 256 + endloop + endfacet + facet normal -0.956633 -0.234672 -0.172578 + outer loop + vertex 842.238 285.773 263.241 + vertex 842.926 288.295 256 + vertex 843.747 280.954 261.431 + endloop + endfacet + facet normal -0.955184 -0.22824 -0.188496 + outer loop + vertex 843.534 278.688 265.251 + vertex 842.238 285.773 263.241 + vertex 843.747 280.954 261.431 + endloop + endfacet + facet normal -0.944799 -0.237038 -0.226203 + outer loop + vertex 843.534 278.688 265.251 + vertex 842.905 278.133 268.461 + vertex 842.238 285.773 263.241 + endloop + endfacet + facet normal -0.943004 -0.239905 -0.230629 + outer loop + vertex 841.272 282.951 270.125 + vertex 842.238 285.773 263.241 + vertex 842.905 278.133 268.461 + endloop + endfacet + facet normal -0.939629 -0.231323 -0.252164 + outer loop + vertex 842.536 275.713 272.057 + vertex 841.272 282.951 270.125 + vertex 842.905 278.133 268.461 + endloop + endfacet + facet normal -0.921713 -0.241833 -0.303253 + outer loop + vertex 842.536 275.713 272.057 + vertex 841.727 275.017 275.071 + vertex 841.272 282.951 270.125 + endloop + endfacet + facet normal -0.919245 -0.244833 -0.308293 + outer loop + vertex 839.946 279.8 276.582 + vertex 841.272 282.951 270.125 + vertex 841.727 275.017 275.071 + endloop + endfacet + facet normal -0.912151 -0.233087 -0.33712 + outer loop + vertex 841.15 272.402 278.439 + vertex 839.946 279.8 276.582 + vertex 841.727 275.017 275.071 + endloop + endfacet + facet normal -0.935894 -0.20015 -0.289902 + outer loop + vertex 839.946 279.8 276.582 + vertex 839.308 291.361 270.66 + vertex 841.272 282.951 270.125 + endloop + endfacet + facet normal -0.929267 -0.20775 -0.305454 + outer loop + vertex 837.907 288.269 277.027 + vertex 839.308 291.361 270.66 + vertex 839.946 279.8 276.582 + endloop + endfacet + facet normal -0.932251 -0.19927 -0.301992 + outer loop + vertex 837.907 288.269 277.027 + vertex 837.453 299.57 270.971 + vertex 839.308 291.361 270.66 + endloop + endfacet + facet normal -0.930181 -0.201717 -0.306714 + outer loop + vertex 836.013 296.572 277.31 + vertex 837.453 299.57 270.971 + vertex 837.907 288.269 277.027 + endloop + endfacet + facet normal -0.922701 -0.222483 -0.314839 + outer loop + vertex 836.013 296.572 277.31 + vertex 835.512 307.488 271.063 + vertex 837.453 299.57 270.971 + endloop + endfacet + facet normal -0.923295 -0.221792 -0.313585 + outer loop + vertex 834.055 304.591 277.403 + vertex 835.512 307.488 271.063 + vertex 836.013 296.572 277.31 + endloop + endfacet + facet normal -0.955147 -0.201811 -0.216716 + outer loop + vertex 841.272 282.951 270.125 + vertex 840.343 294.12 263.82 + vertex 842.238 285.773 263.241 + endloop + endfacet + facet normal -0.951314 -0.207707 -0.227725 + outer loop + vertex 839.308 291.361 270.66 + vertex 840.343 294.12 263.82 + vertex 841.272 282.951 270.125 + endloop + endfacet + facet normal -0.952924 -0.202351 -0.225808 + outer loop + vertex 839.308 291.361 270.66 + vertex 838.536 302.266 264.145 + vertex 840.343 294.12 263.82 + endloop + endfacet + facet normal -0.950573 -0.206051 -0.23228 + outer loop + vertex 837.453 299.57 270.971 + vertex 838.536 302.266 264.145 + vertex 839.308 291.361 270.66 + endloop + endfacet + facet normal -0.943288 -0.229118 -0.240235 + outer loop + vertex 837.453 299.57 270.971 + vertex 836.622 310.073 264.215 + vertex 838.536 302.266 264.145 + endloop + endfacet + facet normal -0.943693 -0.228503 -0.239229 + outer loop + vertex 835.512 307.488 271.063 + vertex 836.622 310.073 264.215 + vertex 837.453 299.57 270.971 + endloop + endfacet + facet normal -0.965773 -0.202408 -0.162212 + outer loop + vertex 842.238 285.773 263.241 + vertex 841.078 296.575 256.67 + vertex 842.926 288.295 256 + endloop + endfacet + facet normal -0.96346 -0.206936 -0.170064 + outer loop + vertex 840.343 294.12 263.82 + vertex 841.078 296.575 256.67 + vertex 842.238 285.773 263.241 + endloop + endfacet + facet normal -0.963533 -0.206667 -0.169979 + outer loop + vertex 840.343 294.12 263.82 + vertex 839.292 304.622 257.006 + vertex 841.078 296.575 256.67 + endloop + endfacet + facet normal -0.96957 -0.209841 -0.126101 + outer loop + vertex 839.292 304.622 257.006 + vertex 839.803 306.69 249.637 + vertex 841.078 296.575 256.67 + endloop + endfacet + facet normal -0.969174 -0.210794 -0.127544 + outer loop + vertex 841.078 296.575 256.67 + vertex 839.803 306.69 249.637 + vertex 841.587 298.712 249.267 + endloop + endfacet + facet normal -0.972354 -0.212978 -0.0957443 + outer loop + vertex 839.803 306.69 249.637 + vertex 840.148 308.499 242.113 + vertex 841.587 298.712 249.267 + endloop + endfacet + facet normal -0.964211 -0.244348 -0.102914 + outer loop + vertex 839.803 306.69 249.637 + vertex 838.234 316.017 242.194 + vertex 840.148 308.499 242.113 + endloop + endfacet + facet normal -0.966522 -0.245234 -0.0754724 + outer loop + vertex 838.234 316.017 242.194 + vertex 838.445 317.53 234.571 + vertex 840.148 308.499 242.113 + endloop + endfacet + facet normal -0.965527 -0.248016 -0.0790283 + outer loop + vertex 840.148 308.499 242.113 + vertex 838.445 317.53 234.571 + vertex 840.369 310.064 234.497 + endloop + endfacet + facet normal -0.973844 -0.215324 -0.0725524 + outer loop + vertex 840.148 308.499 242.113 + vertex 840.369 310.064 234.497 + vertex 841.931 300.562 241.739 + endloop + endfacet + facet normal -0.966881 -0.248574 -0.0579022 + outer loop + vertex 838.445 317.53 234.571 + vertex 838.574 318.824 226.87 + vertex 840.369 310.064 234.497 + endloop + endfacet + facet normal -0.965824 -0.25173 -0.0617761 + outer loop + vertex 840.369 310.064 234.497 + vertex 838.574 318.824 226.87 + vertex 840.494 311.466 226.829 + endloop + endfacet + facet normal -0.974584 -0.217022 -0.055571 + outer loop + vertex 840.369 310.064 234.497 + vertex 840.494 311.466 226.829 + vertex 842.13 302.243 234.156 + endloop + endfacet + facet normal -0.966647 -0.252036 -0.0455143 + outer loop + vertex 838.574 318.824 226.87 + vertex 838.648 319.941 219.099 + vertex 840.494 311.466 226.829 + endloop + endfacet + facet normal -0.965971 -0.254157 -0.0480021 + outer loop + vertex 840.494 311.466 226.829 + vertex 838.648 319.941 219.099 + vertex 840.549 312.719 219.101 + endloop + endfacet + facet normal -0.965543 -0.24094 -0.0983601 + outer loop + vertex 837.902 314.279 249.71 + vertex 838.234 316.017 242.194 + vertex 839.803 306.69 249.637 + endloop + endfacet + facet normal -0.961592 -0.239607 -0.133898 + outer loop + vertex 839.292 304.622 257.006 + vertex 837.902 314.279 249.71 + vertex 839.803 306.69 249.637 + endloop + endfacet + facet normal -0.962608 -0.237306 -0.130658 + outer loop + vertex 837.389 312.309 257.066 + vertex 837.902 314.279 249.71 + vertex 839.292 304.622 257.006 + endloop + endfacet + facet normal -0.955371 -0.235142 -0.178816 + outer loop + vertex 838.536 302.266 264.145 + vertex 837.389 312.309 257.066 + vertex 839.292 304.622 257.006 + endloop + endfacet + facet normal -0.956524 -0.232939 -0.175504 + outer loop + vertex 836.622 310.073 264.215 + vertex 837.389 312.309 257.066 + vertex 838.536 302.266 264.145 + endloop + endfacet + facet normal -0.96342 -0.206893 -0.170345 + outer loop + vertex 838.536 302.266 264.145 + vertex 839.292 304.622 257.006 + vertex 840.343 294.12 263.82 + endloop + endfacet + facet normal -0.964454 -0.23047 -0.129277 + outer loop + vertex 844.757 283.735 250.527 + vertex 844.35 283.472 254.033 + vertex 843.411 290.48 248.549 + endloop + endfacet + facet normal -0.970295 -0.20632 -0.126329 + outer loop + vertex 841.078 296.575 256.67 + vertex 841.587 298.712 249.267 + vertex 842.926 288.295 256 + endloop + endfacet + facet normal -0.972066 -0.213776 -0.0968937 + outer loop + vertex 841.587 298.712 249.267 + vertex 840.148 308.499 242.113 + vertex 841.931 300.562 241.739 + endloop + endfacet + facet normal -0.973617 -0.216021 -0.0735156 + outer loop + vertex 841.931 300.562 241.739 + vertex 840.369 310.064 234.497 + vertex 842.13 302.243 234.156 + endloop + endfacet + facet normal -0.97461 -0.216934 -0.0554547 + outer loop + vertex 842.13 302.243 234.156 + vertex 840.494 311.466 226.829 + vertex 842.187 303.936 226.536 + endloop + endfacet + facet normal -0.978723 -0.201457 -0.0389312 + outer loop + vertex 843.656 296.96 225.822 + vertex 842.199 305.37 218.937 + vertex 843.753 297.866 218.701 + endloop + endfacet + facet normal -0.977213 -0.208497 -0.0398059 + outer loop + vertex 843.656 296.96 225.822 + vertex 843.753 297.866 218.701 + vertex 845.044 290.551 225.312 + endloop + endfacet + facet normal -0.975135 -0.21757 -0.042135 + outer loop + vertex 840.494 311.466 226.829 + vertex 840.549 312.719 219.101 + vertex 842.187 303.936 226.536 + endloop + endfacet + facet normal -0.975526 -0.217479 -0.0324317 + outer loop + vertex 842.199 305.37 218.937 + vertex 840.579 313.778 211.296 + vertex 842.234 306.362 211.238 + endloop + endfacet + facet normal -0.966442 -0.254278 -0.0365049 + outer loop + vertex 838.648 319.941 219.099 + vertex 838.692 320.904 211.246 + vertex 840.549 312.719 219.101 + endloop + endfacet + facet normal -0.97571 -0.217575 -0.0254986 + outer loop + vertex 840.579 313.778 211.296 + vertex 840.596 314.631 203.375 + vertex 842.234 306.362 211.238 + endloop + endfacet + facet normal -0.978959 -0.201774 -0.0304235 + outer loop + vertex 842.199 305.37 218.937 + vertex 842.234 306.362 211.238 + vertex 843.753 297.866 218.701 + endloop + endfacet + facet normal -0.979171 -0.201688 -0.0233511 + outer loop + vertex 843.861 298.515 211.002 + vertex 842.256 307.199 203.311 + vertex 843.867 299.424 202.908 + endloop + endfacet + facet normal -0.979299 -0.201557 -0.0186705 + outer loop + vertex 843.867 299.424 202.908 + vertex 842.264 307.915 195.303 + vertex 843.872 300.141 194.895 + endloop + endfacet + facet normal -0.979446 -0.20126 -0.0133868 + outer loop + vertex 843.872 300.141 194.895 + vertex 842.276 308.414 187.329 + vertex 843.881 300.629 186.934 + endloop + endfacet + facet normal -0.97958 -0.200906 -0.00778976 + outer loop + vertex 843.881 300.629 186.934 + vertex 842.287 308.693 179.408 + vertex 843.888 300.903 179.01 + endloop + endfacet + facet normal -0.979648 -0.200713 -0.00216231 + outer loop + vertex 843.888 300.903 179.01 + vertex 842.292 308.772 171.542 + vertex 843.89 300.975 171.136 + endloop + endfacet + facet normal -0.979675 -0.200562 0.00346044 + outer loop + vertex 843.89 300.975 171.136 + vertex 842.29 308.663 163.715 + vertex 843.888 300.852 163.312 + endloop + endfacet + facet normal -0.979662 -0.200429 0.00947632 + outer loop + vertex 843.888 300.852 163.312 + vertex 842.279 308.366 155.891 + vertex 843.877 300.535 155.498 + endloop + endfacet + facet normal -0.979571 -0.200546 0.014883 + outer loop + vertex 843.877 300.535 155.498 + vertex 842.258 307.888 148.044 + vertex 843.858 300.046 147.662 + endloop + endfacet + facet normal -0.979358 -0.201149 0.0199314 + outer loop + vertex 843.858 300.046 147.662 + vertex 842.23 307.229 140.173 + vertex 843.841 299.345 139.769 + endloop + endfacet + facet normal -0.979101 -0.20181 0.0251941 + outer loop + vertex 843.841 299.345 139.769 + vertex 842.203 306.362 132.289 + vertex 843.837 298.374 131.818 + endloop + endfacet + facet normal -0.975917 -0.215215 0.0356095 + outer loop + vertex 845.631 290.14 130.897 + vertex 843.856 297.01 123.774 + vertex 845.642 288.714 122.573 + endloop + endfacet + facet normal -0.978835 -0.202151 0.0318993 + outer loop + vertex 842.203 306.362 132.289 + vertex 842.182 305.214 124.38 + vertex 843.837 298.374 131.818 + endloop + endfacet + facet normal -0.975438 -0.215895 0.0436974 + outer loop + vertex 842.182 305.214 124.38 + vertex 840.429 311.578 116.695 + vertex 842.16 303.71 116.456 + endloop + endfacet + facet normal -0.9748 -0.216108 0.055338 + outer loop + vertex 840.429 311.578 116.695 + vertex 840.321 310.076 108.922 + vertex 842.16 303.71 116.456 + endloop + endfacet + facet normal -0.96603 -0.246278 0.0783189 + outer loop + vertex 840.321 310.076 108.922 + vertex 838.217 315.915 101.335 + vertex 840.133 308.379 101.272 + endloop + endfacet + facet normal -0.972857 -0.209646 0.097968 + outer loop + vertex 841.88 300.26 100.856 + vertex 839.827 306.507 93.8356 + vertex 841.551 298.31 93.4191 + endloop + endfacet + facet normal -0.964236 -0.24599 0.0986813 + outer loop + vertex 838.217 315.915 101.335 + vertex 837.91 314.143 93.9213 + vertex 840.133 308.379 101.272 + endloop + endfacet + facet normal -0.961883 -0.237961 0.134744 + outer loop + vertex 839.827 306.507 93.8356 + vertex 837.428 312.174 86.7164 + vertex 839.33 304.435 86.6324 + endloop + endfacet + facet normal -0.948006 -0.286965 0.137606 + outer loop + vertex 835.726 321.323 93.847 + vertex 835.237 319.485 86.6426 + vertex 837.91 314.143 93.9213 + endloop + endfacet + facet normal -0.9514 -0.288301 0.108265 + outer loop + vertex 838.217 315.915 101.335 + vertex 835.726 321.323 93.847 + vertex 837.91 314.143 93.9213 + endloop + endfacet + facet normal -0.950608 -0.291967 0.105354 + outer loop + vertex 836.04 322.971 101.245 + vertex 835.726 321.323 93.847 + vertex 838.217 315.915 101.335 + endloop + endfacet + facet normal -0.952399 -0.29278 0.0849525 + outer loop + vertex 838.414 317.478 108.927 + vertex 836.04 322.971 101.245 + vertex 838.217 315.915 101.335 + endloop + endfacet + facet normal -0.951625 -0.296006 0.0824062 + outer loop + vertex 836.244 324.422 108.817 + vertex 836.04 322.971 101.245 + vertex 838.414 317.478 108.927 + endloop + endfacet + facet normal -0.952594 -0.296536 0.0680499 + outer loop + vertex 838.545 318.826 116.633 + vertex 836.244 324.422 108.817 + vertex 838.414 317.478 108.927 + endloop + endfacet + facet normal -0.951618 -0.300317 0.0650552 + outer loop + vertex 836.377 325.671 116.515 + vertex 836.244 324.422 108.817 + vertex 838.545 318.826 116.633 + endloop + endfacet + facet normal -0.952196 -0.300692 0.0539151 + outer loop + vertex 838.628 319.957 124.409 + vertex 836.377 325.671 116.515 + vertex 838.545 318.826 116.633 + endloop + endfacet + facet normal -0.951728 -0.302413 0.0525356 + outer loop + vertex 836.465 326.744 124.297 + vertex 836.377 325.671 116.515 + vertex 838.628 319.957 124.409 + endloop + endfacet + facet normal -0.95209 -0.302674 0.0437315 + outer loop + vertex 838.685 320.908 132.242 + vertex 836.465 326.744 124.297 + vertex 838.628 319.957 124.409 + endloop + endfacet + facet normal -0.95112 -0.306095 0.0409471 + outer loop + vertex 836.513 327.646 132.147 + vertex 836.465 326.744 124.297 + vertex 838.685 320.908 132.242 + endloop + endfacet + facet normal -0.951333 -0.306259 0.0342168 + outer loop + vertex 838.718 321.687 140.12 + vertex 836.513 327.646 132.147 + vertex 838.685 320.908 132.242 + endloop + endfacet + facet normal -0.951023 -0.307318 0.033339 + outer loop + vertex 836.546 328.398 140.036 + vertex 836.513 327.646 132.147 + vertex 838.718 321.687 140.12 + endloop + endfacet + facet normal -0.951171 -0.307439 0.0274834 + outer loop + vertex 838.744 322.311 148.007 + vertex 836.546 328.398 140.036 + vertex 838.718 321.687 140.12 + endloop + endfacet + facet normal -0.950725 -0.308923 0.0262269 + outer loop + vertex 836.572 328.99 147.927 + vertex 836.546 328.398 140.036 + vertex 838.744 322.311 148.007 + endloop + endfacet + facet normal -0.95084 -0.309034 0.0200281 + outer loop + vertex 838.763 322.763 155.866 + vertex 836.572 328.99 147.927 + vertex 838.744 322.311 148.007 + endloop + endfacet + facet normal -0.950142 -0.311295 0.0180624 + outer loop + vertex 836.585 329.406 155.785 + vertex 836.572 328.99 147.927 + vertex 838.763 322.763 155.866 + endloop + endfacet + facet normal -0.950205 -0.311387 0.0122036 + outer loop + vertex 838.773 323.038 163.692 + vertex 836.585 329.406 155.785 + vertex 838.763 322.763 155.866 + endloop + endfacet + facet normal -0.95025 -0.311243 0.0123328 + outer loop + vertex 836.6 329.668 163.606 + vertex 836.585 329.406 155.785 + vertex 838.773 323.038 163.692 + endloop + endfacet + facet normal -0.950283 -0.311357 0.00435555 + outer loop + vertex 838.776 323.139 171.515 + vertex 836.6 329.668 163.606 + vertex 838.773 323.038 163.692 + endloop + endfacet + facet normal -0.949975 -0.312307 0.00348629 + outer loop + vertex 836.599 329.758 171.43 + vertex 836.6 329.668 163.606 + vertex 838.776 323.139 171.515 + endloop + endfacet + facet normal -0.949946 -0.31239 -0.003739 + outer loop + vertex 838.77 323.064 179.382 + vertex 836.599 329.758 171.43 + vertex 838.776 323.139 171.515 + endloop + endfacet + facet normal -0.95014 -0.311806 -0.00319441 + outer loop + vertex 836.595 329.692 179.301 + vertex 836.599 329.758 171.43 + vertex 838.77 323.064 179.382 + endloop + endfacet + facet normal -0.950046 -0.311883 -0.0118807 + outer loop + vertex 838.756 322.802 187.319 + vertex 836.595 329.692 179.301 + vertex 838.77 323.064 179.382 + endloop + endfacet + facet normal -0.950558 -0.310371 -0.0104442 + outer loop + vertex 836.584 329.457 187.242 + vertex 836.595 329.692 179.301 + vertex 838.756 322.802 187.319 + endloop + endfacet + facet normal -0.950401 -0.310424 -0.019344 + outer loop + vertex 838.741 322.35 195.311 + vertex 836.584 329.457 187.242 + vertex 838.756 322.802 187.319 + endloop + endfacet + facet normal -0.95054 -0.310022 -0.0189528 + outer loop + vertex 836.561 329.039 195.235 + vertex 836.584 329.457 187.242 + vertex 838.741 322.35 195.311 + endloop + endfacet + facet normal -0.950346 -0.310046 -0.0267248 + outer loop + vertex 838.723 321.716 203.307 + vertex 836.561 329.039 195.235 + vertex 838.741 322.35 195.311 + endloop + endfacet + facet normal -0.950939 -0.308364 -0.0250398 + outer loop + vertex 836.537 328.463 203.228 + vertex 836.561 329.039 195.235 + vertex 838.723 321.716 203.307 + endloop + endfacet + facet normal -0.950609 -0.308377 -0.0352974 + outer loop + vertex 838.692 320.904 211.246 + vertex 836.537 328.463 203.228 + vertex 838.723 321.716 203.307 + endloop + endfacet + facet normal -0.951954 -0.304626 -0.0313994 + outer loop + vertex 836.508 327.737 211.169 + vertex 836.537 328.463 203.228 + vertex 838.692 320.904 211.246 + endloop + endfacet + facet normal -0.951523 -0.304613 -0.0425932 + outer loop + vertex 838.648 319.941 219.099 + vertex 836.508 327.737 211.169 + vertex 838.692 320.904 211.246 + endloop + endfacet + facet normal -0.952471 -0.302019 -0.0397873 + outer loop + vertex 836.461 326.85 219.028 + vertex 836.508 327.737 211.169 + vertex 838.648 319.941 219.099 + endloop + endfacet + facet normal -0.951871 -0.301961 -0.052552 + outer loop + vertex 838.574 318.824 226.87 + vertex 836.461 326.85 219.028 + vertex 838.648 319.941 219.099 + endloop + endfacet + facet normal -0.952928 -0.299147 -0.0493875 + outer loop + vertex 836.388 325.797 226.805 + vertex 836.461 326.85 219.028 + vertex 838.574 318.824 226.87 + endloop + endfacet + facet normal -0.951959 -0.299001 -0.066127 + outer loop + vertex 838.445 317.53 234.571 + vertex 836.388 325.797 226.805 + vertex 838.574 318.824 226.87 + endloop + endfacet + facet normal -0.953042 -0.296234 -0.0628947 + outer loop + vertex 836.268 324.55 234.505 + vertex 836.388 325.797 226.805 + vertex 838.445 317.53 234.571 + endloop + endfacet + facet normal -0.951409 -0.295935 -0.0851119 + outer loop + vertex 838.234 316.017 242.194 + vertex 836.268 324.55 234.505 + vertex 838.445 317.53 234.571 + endloop + endfacet + facet normal -0.953242 -0.291503 -0.0797257 + outer loop + vertex 836.071 323.109 242.124 + vertex 836.268 324.55 234.505 + vertex 838.234 316.017 242.194 + endloop + endfacet + facet normal -0.950477 -0.290955 -0.109264 + outer loop + vertex 837.902 314.279 249.71 + vertex 836.071 323.109 242.124 + vertex 838.234 316.017 242.194 + endloop + endfacet + facet normal -0.952484 -0.286452 -0.103538 + outer loop + vertex 835.746 321.476 249.632 + vertex 836.071 323.109 242.124 + vertex 837.902 314.279 249.71 + endloop + endfacet + facet normal -0.947737 -0.285453 -0.142515 + outer loop + vertex 837.389 312.309 257.066 + vertex 835.746 321.476 249.632 + vertex 837.902 314.279 249.71 + endloop + endfacet + facet normal -0.950903 -0.279027 -0.133892 + outer loop + vertex 835.243 319.657 256.995 + vertex 835.746 321.476 249.632 + vertex 837.389 312.309 257.066 + endloop + endfacet + facet normal -0.94214 -0.276155 0.190029 + outer loop + vertex 837.428 312.174 86.7164 + vertex 834.453 317.447 79.63 + vertex 836.651 310 79.7083 + endloop + endfacet + facet normal -0.911207 -0.360385 0.19956 + outer loop + vertex 832.76 326.514 86.5655 + vertex 829.182 331.667 79.5368 + vertex 831.96 324.652 79.55 + endloop + endfacet + facet normal -0.898907 -0.355409 0.256225 + outer loop + vertex 829.182 331.667 79.5368 + vertex 827.988 329.798 72.7552 + vertex 831.96 324.652 79.55 + endloop + endfacet + facet normal -0.900222 -0.346431 0.263793 + outer loop + vertex 831.96 324.652 79.55 + vertex 827.988 329.798 72.7552 + vertex 830.769 322.585 72.7717 + endloop + endfacet + facet normal -0.914347 -0.313542 0.256244 + outer loop + vertex 831.96 324.652 79.55 + vertex 830.769 322.585 72.7717 + vertex 834.453 317.447 79.63 + endloop + endfacet + facet normal -0.915055 -0.307138 0.261421 + outer loop + vertex 834.453 317.447 79.63 + vertex 830.769 322.585 72.7717 + vertex 833.268 315.209 72.8539 + endloop + endfacet + facet normal -0.92882 -0.271571 0.252077 + outer loop + vertex 834.453 317.447 79.63 + vertex 833.268 315.209 72.8539 + vertex 836.651 310 79.7083 + endloop + endfacet + facet normal -0.929175 -0.266654 0.255988 + outer loop + vertex 836.651 310 79.7083 + vertex 833.268 315.209 72.8539 + vertex 835.473 307.605 72.935 + endloop + endfacet + facet normal -0.941892 -0.229677 0.245128 + outer loop + vertex 836.651 310 79.7083 + vertex 835.473 307.605 72.935 + vertex 838.544 302.159 79.6324 + endloop + endfacet + facet normal -0.941984 -0.226156 0.248033 + outer loop + vertex 838.544 302.159 79.6324 + vertex 835.473 307.605 72.935 + vertex 837.371 299.626 72.8703 + endloop + endfacet + facet normal -0.949314 -0.202476 0.24043 + outer loop + vertex 838.544 302.159 79.6324 + vertex 837.371 299.626 72.8703 + vertex 840.23 293.786 79.2379 + endloop + endfacet + facet normal -0.949208 -0.197521 0.244927 + outer loop + vertex 840.23 293.786 79.2379 + vertex 837.371 299.626 72.8703 + vertex 839.051 291.086 72.4927 + endloop + endfacet + facet normal -0.94856 -0.199688 0.245681 + outer loop + vertex 840.23 293.786 79.2379 + vertex 839.051 291.086 72.4927 + vertex 841.901 284.872 78.4458 + endloop + endfacet + facet normal -0.887386 -0.380044 0.260983 + outer loop + vertex 829.182 331.667 79.5368 + vertex 824.961 336.886 72.7846 + vertex 827.988 329.798 72.7552 + endloop + endfacet + facet normal -0.885636 -0.389862 0.252301 + outer loop + vertex 826.176 338.514 79.5632 + vertex 824.961 336.886 72.7846 + vertex 829.182 331.667 79.5368 + endloop + endfacet + facet normal -0.897366 -0.394801 0.197146 + outer loop + vertex 829.995 333.323 86.5529 + vertex 826.176 338.514 79.5632 + vertex 829.182 331.667 79.5368 + endloop + endfacet + facet normal -0.894384 -0.406368 0.186926 + outer loop + vertex 826.99 339.949 86.5768 + vertex 826.176 338.514 79.5632 + vertex 829.995 333.323 86.5529 + endloop + endfacet + facet normal -0.877346 -0.406599 0.254836 + outer loop + vertex 826.176 338.514 79.5632 + vertex 821.734 343.866 72.8116 + vertex 824.961 336.886 72.7846 + endloop + endfacet + facet normal -0.874275 -0.421278 0.24118 + outer loop + vertex 822.956 345.212 79.5924 + vertex 821.734 343.866 72.8116 + vertex 826.176 338.514 79.5632 + endloop + endfacet + facet normal -0.909355 -0.368853 0.19241 + outer loop + vertex 829.995 333.323 86.5529 + vertex 829.182 331.667 79.5368 + vertex 832.76 326.514 86.5655 + endloop + endfacet + facet normal -0.916172 -0.371699 0.149895 + outer loop + vertex 833.255 328.198 93.7723 + vertex 829.995 333.323 86.5529 + vertex 832.76 326.514 86.5655 + endloop + endfacet + facet normal -0.913919 -0.379833 0.143104 + outer loop + vertex 830.492 334.845 93.7635 + vertex 829.995 333.323 86.5529 + vertex 833.255 328.198 93.7723 + endloop + endfacet + facet normal -0.914444 -0.394931 0.0884451 + outer loop + vertex 830.988 337.497 108.768 + vertex 830.794 336.246 101.176 + vertex 833.76 331.076 108.76 + endloop + endfacet + facet normal -0.917124 -0.381201 0.116491 + outer loop + vertex 833.562 329.723 101.177 + vertex 830.492 334.845 93.7635 + vertex 833.255 328.198 93.7723 + endloop + endfacet + facet normal -0.897054 -0.428347 0.108684 + outer loop + vertex 827.782 342.56 101.201 + vertex 827.485 341.3 93.7855 + vertex 830.794 336.246 101.176 + endloop + endfacet + facet normal -0.900416 -0.408964 0.148322 + outer loop + vertex 830.492 334.845 93.7635 + vertex 826.99 339.949 86.5768 + vertex 829.995 333.323 86.5529 + endloop + endfacet + facet normal -0.882 -0.45197 0.133415 + outer loop + vertex 824.266 347.588 93.8095 + vertex 823.774 346.422 86.6011 + vertex 827.485 341.3 93.7855 + endloop + endfacet + facet normal -0.884584 -0.426009 0.189808 + outer loop + vertex 826.99 339.949 86.5768 + vertex 822.956 345.212 79.5924 + vertex 826.176 338.514 79.5632 + endloop + endfacet + facet normal -0.869969 -0.463851 0.167322 + outer loop + vertex 820.385 352.782 86.6136 + vertex 819.563 351.794 79.6002 + vertex 823.774 346.422 86.6011 + endloop + endfacet + facet normal -0.869154 -0.431163 0.24222 + outer loop + vertex 822.956 345.212 79.5924 + vertex 818.337 350.722 72.8264 + vertex 821.734 343.866 72.8116 + endloop + endfacet + facet normal -0.859326 -0.465368 0.212114 + outer loop + vertex 816.039 358.292 79.5795 + vertex 814.813 357.465 72.7982 + vertex 819.563 351.794 79.6002 + endloop + endfacet + facet normal -0.852568 -0.440111 0.281835 + outer loop + vertex 814.813 357.465 72.7982 + vertex 809.705 363.277 66.4235 + vertex 813.291 356.375 66.4924 + endloop + endfacet + facet normal -0.948483 -0.198278 0.247117 + outer loop + vertex 841.901 284.872 78.4458 + vertex 839.051 291.086 72.4927 + vertex 840.745 282.013 71.715 + endloop + endfacet + facet normal -0.96355 -0.196774 0.181248 + outer loop + vertex 842.7 287.401 85.4404 + vertex 840.23 293.786 79.2379 + vertex 841.901 284.872 78.4458 + endloop + endfacet + facet normal -0.964733 -0.225847 0.135213 + outer loop + vertex 844.277 281.714 87.1905 + vertex 844.311 283.618 90.6152 + vertex 842.7 287.401 85.4404 + endloop + endfacet + facet normal -0.969931 -0.213317 0.117176 + outer loop + vertex 844.69 284.037 94.5161 + vertex 843.225 289.665 92.6353 + vertex 844.311 283.618 90.6152 + endloop + endfacet + facet normal -0.97051 -0.218848 0.101075 + outer loop + vertex 844.69 284.037 94.5161 + vertex 844.661 285.773 97.9974 + vertex 843.225 289.665 92.6353 + endloop + endfacet + facet normal -0.973501 -0.210811 0.0886279 + outer loop + vertex 844.974 286.008 101.991 + vertex 843.571 291.663 100.036 + vertex 844.661 285.773 97.9974 + endloop + endfacet + facet normal -0.973609 -0.215967 0.0737846 + outer loop + vertex 844.974 286.008 101.991 + vertex 844.889 287.622 105.596 + vertex 843.571 291.663 100.036 + endloop + endfacet + facet normal -0.974116 -0.212822 0.0761914 + outer loop + vertex 843.774 293.495 107.749 + vertex 843.571 291.663 100.036 + vertex 844.889 287.622 105.596 + endloop + endfacet + facet normal -0.969547 -0.236472 0.0637186 + outer loop + vertex 844.937 289.554 113.546 + vertex 845.107 287.845 109.788 + vertex 846.022 285.008 113.184 + endloop + endfacet + facet normal -0.970507 -0.235669 0.0507497 + outer loop + vertex 845.926 286.317 117.431 + vertex 844.937 289.554 113.546 + vertex 846.022 285.008 113.184 + endloop + endfacet + facet normal -0.978281 -0.199895 0.0548463 + outer loop + vertex 843.914 295.02 115.79 + vertex 842.076 302.033 108.574 + vertex 843.774 293.495 107.749 + endloop + endfacet + facet normal -0.975109 -0.216689 0.0469933 + outer loop + vertex 843.856 297.01 123.774 + vertex 843.914 295.02 115.79 + vertex 845.642 288.714 122.573 + endloop + endfacet + facet normal -0.970612 -0.235136 0.0512208 + outer loop + vertex 845.058 289.884 117.366 + vertex 844.937 289.554 113.546 + vertex 845.926 286.317 117.431 + endloop + endfacet + facet normal -0.951785 -0.300521 0.0615869 + outer loop + vertex 847.2 282.158 116.819 + vertex 847.125 283.274 121.103 + vertex 845.926 286.317 117.431 + endloop + endfacet + facet normal -0.950728 -0.301662 0.071535 + outer loop + vertex 845.926 286.317 117.431 + vertex 846.022 285.008 113.184 + vertex 847.2 282.158 116.819 + endloop + endfacet + facet normal -0.948221 -0.311261 0.0631937 + outer loop + vertex 847.2 282.158 116.819 + vertex 846.022 285.008 113.184 + vertex 847.264 281.123 112.68 + endloop + endfacet + facet normal -0.947111 -0.31229 0.0738587 + outer loop + vertex 846.022 285.008 113.184 + vertex 846.043 283.984 109.119 + vertex 847.264 281.123 112.68 + endloop + endfacet + facet normal -0.94578 -0.317314 0.0693663 + outer loop + vertex 847.264 281.123 112.68 + vertex 846.043 283.984 109.119 + vertex 847.29 280.166 108.665 + endloop + endfacet + facet normal -0.944233 -0.318497 0.0835631 + outer loop + vertex 846.043 283.984 109.119 + vertex 846.004 283.067 105.185 + vertex 847.29 280.166 108.665 + endloop + endfacet + facet normal -0.94386 -0.319952 0.0822125 + outer loop + vertex 847.29 280.166 108.665 + vertex 846.004 283.067 105.185 + vertex 847.26 279.244 104.73 + endloop + endfacet + facet normal -0.942166 -0.321055 0.0961579 + outer loop + vertex 846.004 283.067 105.185 + vertex 845.92 282.164 101.349 + vertex 847.26 279.244 104.73 + endloop + endfacet + facet normal -0.941791 -0.322589 0.0946843 + outer loop + vertex 847.26 279.244 104.73 + vertex 845.92 282.164 101.349 + vertex 847.193 278.297 100.84 + endloop + endfacet + facet normal -0.939429 -0.324043 0.11167 + outer loop + vertex 845.92 282.164 101.349 + vertex 845.812 281.171 97.56 + vertex 847.193 278.297 100.84 + endloop + endfacet + facet normal -0.939067 -0.325608 0.110146 + outer loop + vertex 847.193 278.297 100.84 + vertex 845.812 281.171 97.56 + vertex 847.123 277.189 96.9699 + endloop + endfacet + facet normal -0.935927 -0.327464 0.129643 + outer loop + vertex 845.812 281.171 97.56 + vertex 845.691 280.028 93.7971 + vertex 847.123 277.189 96.9699 + endloop + endfacet + facet normal -0.937162 -0.321486 0.13555 + outer loop + vertex 847.123 277.189 96.9699 + vertex 845.691 280.028 93.7971 + vertex 847.063 275.749 93.1335 + endloop + endfacet + facet normal -0.93482 -0.322703 0.148241 + outer loop + vertex 845.691 280.028 93.7971 + vertex 845.52 278.804 90.0569 + vertex 847.063 275.749 93.1335 + endloop + endfacet + facet normal -0.935596 -0.318105 0.153197 + outer loop + vertex 847.063 275.749 93.1335 + vertex 845.52 278.804 90.0569 + vertex 846.843 274.553 89.306 + endloop + endfacet + facet normal -0.932578 -0.319708 0.167588 + outer loop + vertex 845.52 278.804 90.0569 + vertex 845.283 277.569 86.3801 + vertex 846.843 274.553 89.306 + endloop + endfacet + facet normal -0.932647 -0.319224 0.168123 + outer loop + vertex 846.843 274.553 89.306 + vertex 845.283 277.569 86.3801 + vertex 846.613 273.278 85.6116 + endloop + endfacet + facet normal -0.92696 -0.321868 0.192733 + outer loop + vertex 845.283 277.569 86.3801 + vertex 844.986 276.272 82.7864 + vertex 846.613 273.278 85.6116 + endloop + endfacet + facet normal -0.927331 -0.318479 0.19654 + outer loop + vertex 846.613 273.278 85.6116 + vertex 844.986 276.272 82.7864 + vertex 846.312 271.933 82.0131 + endloop + endfacet + facet normal -0.920902 -0.320918 0.22125 + outer loop + vertex 844.986 276.272 82.7864 + vertex 844.617 274.901 79.2623 + vertex 846.312 271.933 82.0131 + endloop + endfacet + facet normal -0.920996 -0.319687 0.222636 + outer loop + vertex 846.312 271.933 82.0131 + vertex 844.617 274.901 79.2623 + vertex 845.951 270.505 78.4687 + endloop + endfacet + facet normal -0.912525 -0.322371 0.251744 + outer loop + vertex 844.617 274.901 79.2623 + vertex 844.173 273.449 75.7928 + vertex 845.951 270.505 78.4687 + endloop + endfacet + facet normal -0.91264 -0.319423 0.255064 + outer loop + vertex 845.951 270.505 78.4687 + vertex 844.173 273.449 75.7928 + vertex 845.51 268.97 74.9695 + endloop + endfacet + facet normal -0.902309 -0.322116 0.286494 + outer loop + vertex 844.173 273.449 75.7928 + vertex 843.637 271.927 72.3943 + vertex 845.51 268.97 74.9695 + endloop + endfacet + facet normal -0.902292 -0.320045 0.28886 + outer loop + vertex 845.51 268.97 74.9695 + vertex 843.637 271.927 72.3943 + vertex 844.985 267.365 71.5489 + endloop + endfacet + facet normal -0.888219 -0.322917 0.326791 + outer loop + vertex 843.637 271.927 72.3943 + vertex 842.999 270.336 69.0886 + vertex 844.985 267.365 71.5489 + endloop + endfacet + facet normal -0.888019 -0.31986 0.330321 + outer loop + vertex 844.985 267.365 71.5489 + vertex 842.999 270.336 69.0886 + vertex 844.358 265.685 68.2376 + endloop + endfacet + facet normal -0.86889 -0.322539 0.375497 + outer loop + vertex 842.999 270.336 69.0886 + vertex 842.248 268.658 65.9094 + vertex 844.358 265.685 68.2376 + endloop + endfacet + facet normal -0.868623 -0.32051 0.377846 + outer loop + vertex 844.358 265.685 68.2376 + vertex 842.248 268.658 65.9094 + vertex 843.622 263.932 65.0583 + endloop + endfacet + facet normal -0.945702 -0.317879 -0.0678311 + outer loop + vertex 847.568 281.187 227.521 + vertex 846.417 284.903 226.156 + vertex 847.276 282.85 223.8 + endloop + endfacet + facet normal -0.947645 -0.314298 -0.0564416 + outer loop + vertex 847.419 281.109 230.463 + vertex 846.417 284.903 226.156 + vertex 847.568 281.187 227.521 + endloop + endfacet + facet normal -0.950461 -0.306913 -0.0492805 + outer loop + vertex 846.158 285.015 230.438 + vertex 846.417 284.903 226.156 + vertex 847.419 281.109 230.463 + endloop + endfacet + facet normal -0.950278 -0.306877 -0.0529019 + outer loop + vertex 847.421 280.438 234.307 + vertex 846.158 285.015 230.438 + vertex 847.419 281.109 230.463 + endloop + endfacet + facet normal -0.945054 -0.319447 -0.0694781 + outer loop + vertex 846.152 284.089 234.783 + vertex 846.158 285.015 230.438 + vertex 847.421 280.438 234.307 + endloop + endfacet + facet normal -0.944847 -0.318474 -0.0764047 + outer loop + vertex 847.411 279.512 238.292 + vertex 846.152 284.089 234.783 + vertex 847.421 280.438 234.307 + endloop + endfacet + facet normal -0.941324 -0.325977 -0.0874558 + outer loop + vertex 846.12 283.125 238.728 + vertex 846.152 284.089 234.783 + vertex 847.411 279.512 238.292 + endloop + endfacet + facet normal -0.940571 -0.323974 -0.101822 + outer loop + vertex 847.274 278.736 242.027 + vertex 846.12 283.125 238.728 + vertex 847.411 279.512 238.292 + endloop + endfacet + facet normal -0.941896 -0.321337 -0.0978499 + outer loop + vertex 846.038 282.233 242.438 + vertex 846.12 283.125 238.728 + vertex 847.274 278.736 242.027 + endloop + endfacet + facet normal -0.940826 -0.319021 -0.114331 + outer loop + vertex 847.129 277.927 245.478 + vertex 846.038 282.233 242.438 + vertex 847.274 278.736 242.027 + endloop + endfacet + facet normal -0.94426 -0.312423 -0.103754 + outer loop + vertex 845.967 281.234 246.1 + vertex 846.038 282.233 242.438 + vertex 847.129 277.927 245.478 + endloop + endfacet + facet normal -0.944287 -0.31255 -0.103128 + outer loop + vertex 847.227 276.413 249.171 + vertex 845.967 281.234 246.1 + vertex 847.129 277.927 245.478 + endloop + endfacet + facet normal -0.938553 -0.322935 -0.121781 + outer loop + vertex 845.867 280.129 249.798 + vertex 845.967 281.234 246.1 + vertex 847.227 276.413 249.171 + endloop + endfacet + facet normal -0.937892 -0.321064 -0.131439 + outer loop + vertex 847.12 275.204 252.884 + vertex 845.867 280.129 249.798 + vertex 847.227 276.413 249.171 + endloop + endfacet + facet normal -0.932812 -0.329227 -0.14653 + outer loop + vertex 845.679 279.003 253.522 + vertex 845.867 280.129 249.798 + vertex 847.12 275.204 252.884 + endloop + endfacet + facet normal -0.93149 -0.326344 -0.160704 + outer loop + vertex 846.907 273.974 256.62 + vertex 845.679 279.003 253.522 + vertex 847.12 275.204 252.884 + endloop + endfacet + facet normal -0.927542 -0.332038 -0.171513 + outer loop + vertex 845.425 277.776 257.272 + vertex 845.679 279.003 253.522 + vertex 846.907 273.974 256.62 + endloop + endfacet + facet normal -0.92597 -0.329084 -0.185157 + outer loop + vertex 846.633 272.616 260.4 + vertex 845.425 277.776 257.272 + vertex 846.907 273.974 256.62 + endloop + endfacet + facet normal -0.922119 -0.334161 -0.19502 + outer loop + vertex 845.121 276.443 260.997 + vertex 845.425 277.776 257.272 + vertex 846.633 272.616 260.4 + endloop + endfacet + facet normal -0.919957 -0.330952 -0.210119 + outer loop + vertex 846.309 271.171 264.097 + vertex 845.121 276.443 260.997 + vertex 846.633 272.616 260.4 + endloop + endfacet + facet normal -0.914968 -0.336888 -0.222126 + outer loop + vertex 844.763 275.026 264.62 + vertex 845.121 276.443 260.997 + vertex 846.309 271.171 264.097 + endloop + endfacet + facet normal -0.911597 -0.332958 -0.241101 + outer loop + vertex 845.922 269.671 267.63 + vertex 844.763 275.026 264.62 + vertex 846.309 271.171 264.097 + endloop + endfacet + facet normal -0.906677 -0.33813 -0.252199 + outer loop + vertex 844.34 273.553 268.114 + vertex 844.763 275.026 264.62 + vertex 845.922 269.671 267.63 + endloop + endfacet + facet normal -0.901633 -0.333132 -0.275829 + outer loop + vertex 845.46 268.098 271.042 + vertex 844.34 273.553 268.114 + vertex 845.922 269.671 267.63 + endloop + endfacet + facet normal -0.895435 -0.338816 -0.288789 + outer loop + vertex 843.833 272.008 271.497 + vertex 844.34 273.553 268.114 + vertex 845.46 268.098 271.042 + endloop + endfacet + facet normal -0.888822 -0.333036 -0.314774 + outer loop + vertex 844.903 266.428 274.381 + vertex 843.833 272.008 271.497 + vertex 845.46 268.098 271.042 + endloop + endfacet + facet normal -0.881847 -0.338615 -0.328156 + outer loop + vertex 843.235 270.379 274.787 + vertex 843.833 272.008 271.497 + vertex 844.903 266.428 274.381 + endloop + endfacet + facet normal -0.872503 -0.331506 -0.358947 + outer loop + vertex 844.239 264.652 277.636 + vertex 843.235 270.379 274.787 + vertex 844.903 266.428 274.381 + endloop + endfacet + facet normal -0.863192 -0.337917 -0.375116 + outer loop + vertex 842.526 268.657 277.97 + vertex 843.235 270.379 274.787 + vertex 844.239 264.652 277.636 + endloop + endfacet + facet normal -0.974479 -0.218511 -0.0514195 + outer loop + vertex 845.044 290.551 225.312 + vertex 843.753 297.866 218.701 + vertex 845.693 289.153 218.966 + endloop + endfacet + facet normal -0.977053 -0.207969 -0.0460139 + outer loop + vertex 845.044 290.551 225.312 + vertex 844.963 289.674 231.012 + vertex 843.656 296.96 225.822 + endloop + endfacet + facet normal -0.975841 -0.21211 -0.0523718 + outer loop + vertex 845.169 287.617 235.502 + vertex 843.824 294.313 233.439 + vertex 844.963 289.674 231.012 + endloop + endfacet + facet normal -0.974206 -0.215887 -0.0656977 + outer loop + vertex 845.169 287.617 235.502 + vertex 844.957 287.475 239.102 + vertex 843.824 294.313 233.439 + endloop + endfacet + facet normal -0.973178 -0.217977 -0.0735605 + outer loop + vertex 845.051 285.715 243.085 + vertex 843.714 292.372 241.04 + vertex 844.957 287.475 239.102 + endloop + endfacet + facet normal -0.970644 -0.222747 -0.090743 + outer loop + vertex 845.051 285.715 243.085 + vertex 844.754 285.594 246.557 + vertex 843.714 292.372 241.04 + endloop + endfacet + facet normal -0.969019 -0.223989 -0.10407 + outer loop + vertex 844.757 283.735 250.527 + vertex 843.411 290.48 248.549 + vertex 844.754 285.594 246.557 + endloop + endfacet +endsolid diff --git a/noether_examples/meshes/outputs/output_10.stl b/noether_examples/meshes/outputs/output_10.stl new file mode 100644 index 00000000..b2f6fe7e --- /dev/null +++ b/noether_examples/meshes/outputs/output_10.stl @@ -0,0 +1,5098 @@ +solid ascii + facet normal 0.130374 -0.859198 -0.494753 + outer loop + vertex 358.208 46.997 315.974 + vertex 357.069 47.6436 314.551 + vertex 367.085 48.7569 315.257 + endloop + endfacet + facet normal 0.130398 -0.856822 -0.498852 + outer loop + vertex 361.426 49.3496 312.76 + vertex 367.085 48.7569 315.257 + vertex 357.069 47.6436 314.551 + endloop + endfacet + facet normal 0.115951 -0.844735 -0.522474 + outer loop + vertex 353.872 47.9628 313.326 + vertex 361.426 49.3496 312.76 + vertex 357.069 47.6436 314.551 + endloop + endfacet + facet normal 0.122154 -0.835221 -0.536176 + outer loop + vertex 357.069 47.6436 314.551 + vertex 348.411 46.6116 314.186 + vertex 353.872 47.9628 313.326 + endloop + endfacet + facet normal 0.122095 -0.834119 -0.537901 + outer loop + vertex 350.231 46.0333 315.496 + vertex 348.411 46.6116 314.186 + vertex 357.069 47.6436 314.551 + endloop + endfacet + facet normal 0.124465 -0.832189 -0.540343 + outer loop + vertex 350.231 46.0333 315.496 + vertex 341.802 45.1492 314.916 + vertex 348.411 46.6116 314.186 + endloop + endfacet + facet normal 0.124456 -0.836655 -0.533403 + outer loop + vertex 341.751 44.3021 316.233 + vertex 341.802 45.1492 314.916 + vertex 350.231 46.0333 315.496 + endloop + endfacet + facet normal 0.115583 -0.837403 -0.534226 + outer loop + vertex 341.802 45.1492 314.916 + vertex 341.751 44.3021 316.233 + vertex 329.078 43.5056 314.74 + endloop + endfacet + facet normal 0.115743 -0.836053 -0.536301 + outer loop + vertex 331.536 42.1263 317.42 + vertex 329.078 43.5056 314.74 + vertex 341.751 44.3021 316.233 + endloop + endfacet + facet normal 0.128701 -0.866965 -0.481464 + outer loop + vertex 344.993 43.9768 317.686 + vertex 331.536 42.1263 317.42 + vertex 341.751 44.3021 316.233 + endloop + endfacet + facet normal 0.133982 -0.860354 -0.491772 + outer loop + vertex 344.993 43.9768 317.686 + vertex 341.751 44.3021 316.233 + vertex 352.209 45.5379 316.92 + endloop + endfacet + facet normal 0.133989 -0.863373 -0.486451 + outer loop + vertex 352.209 45.5379 316.92 + vertex 341.751 44.3021 316.233 + vertex 350.231 46.0333 315.496 + endloop + endfacet + facet normal 0.133474 -0.863777 -0.485875 + outer loop + vertex 352.209 45.5379 316.92 + vertex 350.231 46.0333 315.496 + vertex 358.208 46.997 315.974 + endloop + endfacet + facet normal 0.119765 -0.833844 -0.538852 + outer loop + vertex 331.536 42.1263 317.42 + vertex 312.184 40.6744 315.366 + vertex 329.078 43.5056 314.74 + endloop + endfacet + facet normal 0.119569 -0.836068 -0.535438 + outer loop + vertex 313.876 39.2025 318.042 + vertex 312.184 40.6744 315.366 + vertex 331.536 42.1263 317.42 + endloop + endfacet + facet normal 0.113979 -0.838314 -0.533139 + outer loop + vertex 313.876 39.2025 318.042 + vertex 294.205 38.0508 315.648 + vertex 312.184 40.6744 315.366 + endloop + endfacet + facet normal 0.115195 -0.828656 -0.547777 + outer loop + vertex 295.319 36.4552 318.296 + vertex 294.205 38.0508 315.648 + vertex 313.876 39.2025 318.042 + endloop + endfacet + facet normal 0.102597 -0.832336 -0.544694 + outer loop + vertex 295.319 36.4552 318.296 + vertex 274.918 35.6348 315.707 + vertex 294.205 38.0508 315.648 + endloop + endfacet + facet normal 0.104542 -0.81895 -0.564263 + outer loop + vertex 275.759 33.9344 318.33 + vertex 274.918 35.6348 315.707 + vertex 295.319 36.4552 318.296 + endloop + endfacet + facet normal 0.0920046 -0.821899 -0.562154 + outer loop + vertex 275.759 33.9344 318.33 + vertex 254.322 33.3455 315.683 + vertex 274.918 35.6348 315.707 + endloop + endfacet + facet normal 0.0938457 -0.809289 -0.579866 + outer loop + vertex 255.047 31.5521 318.303 + vertex 254.322 33.3455 315.683 + vertex 275.759 33.9344 318.33 + endloop + endfacet + facet normal 0.0846475 -0.811191 -0.578622 + outer loop + vertex 255.047 31.5521 318.303 + vertex 232.798 31.1182 315.657 + vertex 254.322 33.3455 315.683 + endloop + endfacet + facet normal 0.086372 -0.798981 -0.595122 + outer loop + vertex 233.523 29.2407 318.283 + vertex 232.798 31.1182 315.657 + vertex 255.047 31.5521 318.303 + endloop + endfacet + facet normal 0.078496 -0.800567 -0.59408 + outer loop + vertex 233.523 29.2407 318.283 + vertex 210.915 28.9808 315.646 + vertex 232.798 31.1182 315.657 + endloop + endfacet + facet normal 0.07996 -0.790164 -0.607657 + outer loop + vertex 211.71 27.0381 318.276 + vertex 210.915 28.9808 315.646 + vertex 233.523 29.2407 318.283 + endloop + endfacet + facet normal 0.074422 -0.791329 -0.606844 + outer loop + vertex 211.71 27.0381 318.276 + vertex 189.165 26.9524 315.623 + vertex 210.915 28.9808 315.646 + endloop + endfacet + facet normal 0.0752517 -0.78565 -0.614078 + outer loop + vertex 190.039 24.9757 318.259 + vertex 189.165 26.9524 315.623 + vertex 211.71 27.0381 318.276 + endloop + endfacet + facet normal 0.0698356 -0.786849 -0.613182 + outer loop + vertex 190.039 24.9757 318.259 + vertex 167.72 25.0811 315.582 + vertex 189.165 26.9524 315.623 + endloop + endfacet + facet normal 0.070651 -0.781595 -0.619773 + outer loop + vertex 168.633 23.0711 318.221 + vertex 167.72 25.0811 315.582 + vertex 190.039 24.9757 318.259 + endloop + endfacet + facet normal 0.0643295 -0.783015 -0.618667 + outer loop + vertex 168.633 23.0711 318.221 + vertex 146.513 23.3802 315.53 + vertex 167.72 25.0811 315.582 + endloop + endfacet + facet normal 0.0646141 -0.781295 -0.620809 + outer loop + vertex 147.401 21.3507 318.176 + vertex 146.513 23.3802 315.53 + vertex 168.633 23.0711 318.221 + endloop + endfacet + facet normal 0.0579299 -0.782726 -0.619664 + outer loop + vertex 147.401 21.3507 318.176 + vertex 125.419 21.8585 315.48 + vertex 146.513 23.3802 315.53 + endloop + endfacet + facet normal 0.0579778 -0.782454 -0.620003 + outer loop + vertex 126.248 19.8182 318.132 + vertex 125.419 21.8585 315.48 + vertex 147.401 21.3507 318.176 + endloop + endfacet + facet normal 0.0495384 -0.784112 -0.618639 + outer loop + vertex 126.248 19.8182 318.132 + vertex 104.381 20.5552 315.447 + vertex 125.419 21.8585 315.48 + endloop + endfacet + facet normal 0.0491183 -0.786345 -0.615832 + outer loop + vertex 105.123 18.5177 318.108 + vertex 104.381 20.5552 315.447 + vertex 126.248 19.8182 318.132 + endloop + endfacet + facet normal 0.0398379 -0.787938 -0.614465 + outer loop + vertex 105.123 18.5177 318.108 + vertex 83.3936 19.4992 315.441 + vertex 104.381 20.5552 315.447 + endloop + endfacet + facet normal 0.0402544 -0.78586 -0.617093 + outer loop + vertex 84.0486 17.446 318.098 + vertex 83.3936 19.4992 315.441 + vertex 105.123 18.5177 318.108 + endloop + endfacet + facet normal 0.0302247 -0.787346 -0.61577 + outer loop + vertex 84.0486 17.446 318.098 + vertex 62.4902 18.6873 315.453 + vertex 83.3936 19.4992 315.441 + endloop + endfacet + facet normal 0.0299938 -0.788428 -0.614396 + outer loop + vertex 63.0499 16.6368 318.111 + vertex 62.4902 18.6873 315.453 + vertex 84.0486 17.446 318.098 + endloop + endfacet + facet normal 0.0208969 -0.789542 -0.61334 + outer loop + vertex 63.0499 16.6368 318.111 + vertex 41.6942 18.1196 315.475 + vertex 62.4902 18.6873 315.453 + endloop + endfacet + facet normal 0.0208782 -0.789625 -0.613235 + outer loop + vertex 42.1626 16.0691 318.131 + vertex 41.6942 18.1196 315.475 + vertex 63.0499 16.6368 318.111 + endloop + endfacet + facet normal 0.0122408 -0.790477 -0.61237 + outer loop + vertex 42.1626 16.0691 318.131 + vertex 20.9977 17.7842 315.494 + vertex 41.6942 18.1196 315.475 + endloop + endfacet + facet normal 0.0125457 -0.789211 -0.613994 + outer loop + vertex 21.3737 15.7272 318.146 + vertex 20.9977 17.7842 315.494 + vertex 42.1626 16.0691 318.131 + endloop + endfacet + facet normal 0.0040663 -0.78985 -0.613287 + outer loop + vertex 21.3737 15.7272 318.146 + vertex 0.341601 17.6727 315.501 + vertex 20.9977 17.7842 315.494 + endloop + endfacet + facet normal 0.00406486 -0.789855 -0.61328 + outer loop + vertex 0.61874 15.6153 318.152 + vertex 0.341601 17.6727 315.501 + vertex 21.3737 15.7272 318.146 + endloop + endfacet + facet normal -0.00408443 -0.790268 -0.612748 + outer loop + vertex 0.61874 15.6153 318.152 + vertex -20.3545 17.7863 315.492 + vertex 0.341601 17.6727 315.501 + endloop + endfacet + facet normal -0.00375195 -0.789022 -0.614353 + outer loop + vertex -20.1748 15.7208 318.144 + vertex -20.3545 17.7863 315.492 + vertex 0.61874 15.6153 318.152 + endloop + endfacet + facet normal -0.011754 -0.789236 -0.613977 + outer loop + vertex -20.1748 15.7208 318.144 + vertex -41.141 18.1129 315.47 + vertex -20.3545 17.7863 315.492 + endloop + endfacet + facet normal -0.0118969 -0.789749 -0.613315 + outer loop + vertex -41.0557 16.0494 318.126 + vertex -41.141 18.1129 315.47 + vertex -20.1748 15.7208 318.144 + endloop + endfacet + facet normal -0.0209636 -0.789772 -0.613042 + outer loop + vertex -41.0557 16.0494 318.126 + vertex -61.9842 18.682 315.45 + vertex -41.141 18.1129 315.47 + endloop + endfacet + facet normal -0.020467 -0.788067 -0.615249 + outer loop + vertex -61.9962 16.6079 318.107 + vertex -61.9842 18.682 315.45 + vertex -41.0557 16.0494 318.126 + endloop + endfacet + facet normal -0.0298831 -0.78786 -0.61513 + outer loop + vertex -61.9962 16.6079 318.107 + vertex -82.8098 19.4797 315.44 + vertex -61.9842 18.682 315.45 + endloop + endfacet + facet normal -0.0296911 -0.787228 -0.615947 + outer loop + vertex -82.9133 17.4033 318.099 + vertex -82.8098 19.4797 315.44 + vertex -61.9962 16.6079 318.107 + endloop + endfacet + facet normal -0.0395747 -0.786771 -0.615975 + outer loop + vertex -82.9133 17.4033 318.099 + vertex -103.559 20.5154 315.45 + vertex -82.8098 19.4797 315.44 + endloop + endfacet + facet normal -0.0393688 -0.786121 -0.616817 + outer loop + vertex -103.748 18.4391 318.108 + vertex -103.559 20.5154 315.45 + vertex -82.9133 17.4033 318.099 + endloop + endfacet + facet normal -0.0491518 -0.785442 -0.61698 + outer loop + vertex -103.748 18.4391 318.108 + vertex -124.279 21.7863 315.483 + vertex -103.559 20.5154 315.45 + endloop + endfacet + facet normal -0.0489593 -0.784857 -0.61774 + outer loop + vertex -124.546 19.7131 318.138 + vertex -124.279 21.7863 315.483 + vertex -103.748 18.4391 318.108 + endloop + endfacet + facet normal -0.0576154 -0.784068 -0.617995 + outer loop + vertex -124.546 19.7131 318.138 + vertex -145.129 23.2794 315.532 + vertex -124.279 21.7863 315.483 + endloop + endfacet + facet normal -0.0570453 -0.782379 -0.620185 + outer loop + vertex -145.453 21.2051 318.179 + vertex -145.129 23.2794 315.532 + vertex -124.546 19.7131 318.138 + endloop + endfacet + facet normal -0.0637334 -0.78166 -0.62044 + outer loop + vertex -145.453 21.2051 318.179 + vertex -166.31 24.9647 315.585 + vertex -145.129 23.2794 315.532 + endloop + endfacet + facet normal -0.0644309 -0.7837 -0.617789 + outer loop + vertex -166.676 22.9122 318.227 + vertex -166.31 24.9647 315.585 + vertex -145.453 21.2051 318.179 + endloop + endfacet + facet normal -0.0686924 -0.783187 -0.61798 + outer loop + vertex -166.676 22.9122 318.227 + vertex -187.961 26.8295 315.628 + vertex -166.31 24.9647 315.585 + endloop + endfacet + facet normal -0.0702123 -0.787597 -0.612177 + outer loop + vertex -188.331 24.8115 318.267 + vertex -187.961 26.8295 315.628 + vertex -166.676 22.9122 318.227 + endloop + endfacet + facet normal -0.0728894 -0.787261 -0.612296 + outer loop + vertex -188.331 24.8115 318.267 + vertex -210.013 28.8542 315.65 + vertex -187.961 26.8295 315.628 + endloop + endfacet + facet normal -0.0742813 -0.791264 -0.606946 + outer loop + vertex -210.325 26.8644 318.282 + vertex -210.013 28.8542 315.65 + vertex -188.331 24.8115 318.267 + endloop + endfacet + facet normal -0.0769908 -0.790945 -0.607025 + outer loop + vertex -210.325 26.8644 318.282 + vertex -232.07 31.0049 315.645 + vertex -210.013 28.8542 315.65 + endloop + endfacet + facet normal -0.0795638 -0.798171 -0.597154 + outer loop + vertex -232.316 29.0602 318.277 + vertex -232.07 31.0049 315.645 + vertex -210.325 26.8644 318.282 + endloop + endfacet + facet normal -0.0821675 -0.797884 -0.597185 + outer loop + vertex -232.316 29.0602 318.277 + vertex -253.518 33.2294 315.624 + vertex -232.07 31.0049 315.645 + endloop + endfacet + facet normal -0.0861393 -0.808509 -0.582145 + outer loop + vertex -253.734 31.3518 318.264 + vertex -253.518 33.2294 315.624 + vertex -232.316 29.0602 318.277 + endloop + endfacet + facet normal -0.090283 -0.808049 -0.582156 + outer loop + vertex -253.734 31.3518 318.264 + vertex -273.796 35.4998 315.618 + vertex -253.518 33.2294 315.624 + endloop + endfacet + facet normal -0.0945083 -0.818558 -0.566596 + outer loop + vertex -274.156 33.7106 318.263 + vertex -273.796 35.4998 315.618 + vertex -253.734 31.3518 318.264 + endloop + endfacet + facet normal -0.101415 -0.817551 -0.566855 + outer loop + vertex -274.156 33.7106 318.263 + vertex -292.771 37.8373 315.641 + vertex -273.796 35.4998 315.618 + endloop + endfacet + facet normal -0.106519 -0.829123 -0.548825 + outer loop + vertex -293.507 36.1817 318.285 + vertex -292.771 37.8373 315.641 + vertex -274.156 33.7106 318.263 + endloop + endfacet + facet normal -0.111806 -0.827941 -0.549557 + outer loop + vertex -293.507 36.1817 318.285 + vertex -310.966 40.2996 315.634 + vertex -292.771 37.8373 315.641 + endloop + endfacet + facet normal -0.117285 -0.83922 -0.530994 + outer loop + vertex -312.204 38.8079 318.264 + vertex -310.966 40.2996 315.634 + vertex -293.507 36.1817 318.285 + endloop + endfacet + facet normal -0.1196 -0.838472 -0.531658 + outer loop + vertex -312.204 38.8079 318.264 + vertex -329.118 42.9828 315.485 + vertex -310.966 40.2996 315.634 + endloop + endfacet + facet normal -0.123424 -0.845682 -0.519218 + outer loop + vertex -330.768 41.6107 318.112 + vertex -329.118 42.9828 315.485 + vertex -312.204 38.8079 318.264 + endloop + endfacet + facet normal -0.119097 -0.847413 -0.517404 + outer loop + vertex -329.118 42.9828 315.485 + vertex -330.768 41.6107 318.112 + vertex -341.339 44.5761 315.689 + endloop + endfacet + facet normal -0.116275 -0.820329 -0.559947 + outer loop + vertex -341.451 45.5597 314.271 + vertex -329.118 42.9828 315.485 + vertex -341.339 44.5761 315.689 + endloop + endfacet + facet normal -0.115761 -0.82036 -0.560008 + outer loop + vertex -341.339 44.5761 315.689 + vertex -348.934 46.7884 314.018 + vertex -341.451 45.5597 314.271 + endloop + endfacet + facet normal -0.113228 -0.808526 -0.577465 + outer loop + vertex -348.934 46.7884 314.018 + vertex -347.126 47.4287 312.767 + vertex -341.451 45.5597 314.271 + endloop + endfacet + facet normal -0.108185 -0.80164 -0.587937 + outer loop + vertex -341.451 45.5597 314.271 + vertex -347.126 47.4287 312.767 + vertex -338.387 45.9463 313.18 + endloop + endfacet + facet normal -0.109089 -0.800062 -0.589916 + outer loop + vertex -341.451 45.5597 314.271 + vertex -338.387 45.9463 313.18 + vertex -329.118 42.9828 315.485 + endloop + endfacet + facet normal -0.103221 -0.791455 -0.602448 + outer loop + vertex -326.875 44.594 312.984 + vertex -329.118 42.9828 315.485 + vertex -338.387 45.9463 313.18 + endloop + endfacet + facet normal -0.101831 -0.776877 -0.621363 + outer loop + vertex -338.245 47.0438 311.785 + vertex -326.875 44.594 312.984 + vertex -338.387 45.9463 313.18 + endloop + endfacet + facet normal -0.0981615 -0.77735 -0.621362 + outer loop + vertex -338.387 45.9463 313.18 + vertex -345.25 48.1414 311.518 + vertex -338.245 47.0438 311.785 + endloop + endfacet + facet normal -0.0936974 -0.755445 -0.648477 + outer loop + vertex -345.25 48.1414 311.518 + vertex -343.415 48.9733 310.284 + vertex -338.245 47.0438 311.785 + endloop + endfacet + facet normal -0.0845424 -0.742966 -0.663968 + outer loop + vertex -338.245 47.0438 311.785 + vertex -343.415 48.9733 310.284 + vertex -335.319 47.6569 310.726 + endloop + endfacet + facet normal -0.0880684 -0.736923 -0.670215 + outer loop + vertex -338.245 47.0438 311.785 + vertex -335.319 47.6569 310.726 + vertex -326.875 44.594 312.984 + endloop + endfacet + facet normal -0.0805541 -0.725778 -0.683197 + outer loop + vertex -324.501 46.6107 310.562 + vertex -326.875 44.594 312.984 + vertex -335.319 47.6569 310.726 + endloop + endfacet + facet normal -0.0785647 -0.701221 -0.708602 + outer loop + vertex -335.052 49.0133 309.354 + vertex -324.501 46.6107 310.562 + vertex -335.319 47.6569 310.726 + endloop + endfacet + facet normal -0.0700215 -0.702512 -0.708219 + outer loop + vertex -335.319 47.6569 310.726 + vertex -341.544 49.9756 309.041 + vertex -335.052 49.0133 309.354 + endloop + endfacet + facet normal -0.0641841 -0.672568 -0.737247 + outer loop + vertex -341.544 49.9756 309.041 + vertex -339.623 51.1738 307.781 + vertex -335.052 49.0133 309.354 + endloop + endfacet + facet normal -0.0561402 -0.662572 -0.746891 + outer loop + vertex -335.052 49.0133 309.354 + vertex -339.623 51.1738 307.781 + vertex -332.103 49.9106 308.336 + endloop + endfacet + facet normal -0.0621155 -0.65245 -0.755282 + outer loop + vertex -335.052 49.0133 309.354 + vertex -332.103 49.9106 308.336 + vertex -324.501 46.6107 310.562 + endloop + endfacet + facet normal -0.0578589 -0.646379 -0.76082 + outer loop + vertex -322.003 49.1298 308.232 + vertex -324.501 46.6107 310.562 + vertex -332.103 49.9106 308.336 + endloop + endfacet + facet normal -0.0556589 -0.614397 -0.787031 + outer loop + vertex -331.564 51.52 307.042 + vertex -322.003 49.1298 308.232 + vertex -332.103 49.9106 308.336 + endloop + endfacet + facet normal -0.0398593 -0.618117 -0.785075 + outer loop + vertex -332.103 49.9106 308.336 + vertex -337.45 52.3753 306.667 + vertex -331.564 51.52 307.042 + endloop + endfacet + facet normal -0.0346938 -0.591531 -0.805536 + outer loop + vertex -337.45 52.3753 306.667 + vertex -335.565 53.7047 305.61 + vertex -331.564 51.52 307.042 + endloop + endfacet + facet normal -0.0281731 -0.583555 -0.811585 + outer loop + vertex -331.564 51.52 307.042 + vertex -335.565 53.7047 305.61 + vertex -328.825 52.6989 306.099 + endloop + endfacet + facet normal -0.0392924 -0.56679 -0.822925 + outer loop + vertex -331.564 51.52 307.042 + vertex -328.825 52.6989 306.099 + vertex -322.003 49.1298 308.232 + endloop + endfacet + facet normal -0.0357768 -0.562088 -0.826303 + outer loop + vertex -319.575 52.1777 306.053 + vertex -322.003 49.1298 308.232 + vertex -328.825 52.6989 306.099 + endloop + endfacet + facet normal -0.034112 -0.530726 -0.846857 + outer loop + vertex -328.354 54.6119 304.881 + vertex -319.575 52.1777 306.053 + vertex -328.825 52.6989 306.099 + endloop + endfacet + facet normal -0.00888053 -0.535452 -0.844519 + outer loop + vertex -328.825 52.6989 306.099 + vertex -333.857 55.282 304.514 + vertex -328.354 54.6119 304.881 + endloop + endfacet + facet normal -0.00506622 -0.512032 -0.858952 + outer loop + vertex -333.857 55.282 304.514 + vertex -332.097 56.9705 303.497 + vertex -328.354 54.6119 304.881 + endloop + endfacet + facet normal 0.00361522 -0.501793 -0.86498 + outer loop + vertex -328.354 54.6119 304.881 + vertex -332.097 56.9705 303.497 + vertex -325.865 56.0317 304.068 + endloop + endfacet + facet normal -0.0149797 -0.477074 -0.878736 + outer loop + vertex -328.354 54.6119 304.881 + vertex -325.865 56.0317 304.068 + vertex -319.575 52.1777 306.053 + endloop + endfacet + facet normal -0.0102143 -0.471012 -0.882067 + outer loop + vertex -317.354 55.7577 304.116 + vertex -319.575 52.1777 306.053 + vertex -325.865 56.0317 304.068 + endloop + endfacet + facet normal -0.00907855 -0.438622 -0.898626 + outer loop + vertex -325.494 58.1487 303.031 + vertex -317.354 55.7577 304.116 + vertex -325.865 56.0317 304.068 + endloop + endfacet + facet normal 0.026035 -0.443454 -0.895919 + outer loop + vertex -325.865 56.0317 304.068 + vertex -330.429 58.7273 302.601 + vertex -325.494 58.1487 303.031 + endloop + endfacet + facet normal 0.0302588 -0.416777 -0.908505 + outer loop + vertex -330.429 58.7273 302.601 + vertex -328.945 60.6124 301.786 + vertex -325.494 58.1487 303.031 + endloop + endfacet + facet normal 0.0371828 -0.408781 -0.911875 + outer loop + vertex -325.494 58.1487 303.031 + vertex -328.945 60.6124 301.786 + vertex -323.313 59.8463 302.359 + endloop + endfacet + facet normal 0.0442254 -0.369268 -0.92827 + outer loop + vertex -328.945 60.6124 301.786 + vertex -327.556 62.6925 301.025 + vertex -323.313 59.8463 302.359 + endloop + endfacet + facet normal 0.0614851 -0.347075 -0.93582 + outer loop + vertex -323.313 59.8463 302.359 + vertex -327.556 62.6925 301.025 + vertex -323.052 62.3278 301.456 + endloop + endfacet + facet normal 0.0641098 -0.32414 -0.943834 + outer loop + vertex -327.556 62.6925 301.025 + vertex -326.231 65.0322 300.311 + vertex -323.052 62.3278 301.456 + endloop + endfacet + facet normal 0.074108 -0.313586 -0.946663 + outer loop + vertex -323.052 62.3278 301.456 + vertex -326.231 65.0322 300.311 + vertex -321.067 64.5608 300.872 + endloop + endfacet + facet normal 0.0785959 -0.27736 -0.957546 + outer loop + vertex -326.231 65.0322 300.311 + vertex -324.951 67.6082 299.67 + vertex -321.067 64.5608 300.872 + endloop + endfacet + facet normal 0.0982428 -0.254137 -0.962166 + outer loop + vertex -321.067 64.5608 300.872 + vertex -324.951 67.6082 299.67 + vertex -320.975 67.4991 300.105 + endloop + endfacet + facet normal 0.099212 -0.236392 -0.966579 + outer loop + vertex -324.951 67.6082 299.67 + vertex -323.826 70.2387 299.142 + vertex -320.975 67.4991 300.105 + endloop + endfacet + facet normal 0.114781 -0.220877 -0.968524 + outer loop + vertex -320.975 67.4991 300.105 + vertex -323.826 70.2387 299.142 + vertex -319.907 69.9965 299.662 + endloop + endfacet + facet normal 0.116061 -0.206589 -0.97152 + outer loop + vertex -323.826 70.2387 299.142 + vertex -323 72.9193 298.671 + vertex -319.907 69.9965 299.662 + endloop + endfacet + facet normal 0.147088 -0.174467 -0.973615 + outer loop + vertex -319.907 69.9965 299.662 + vertex -323 72.9193 298.671 + vertex -320.237 72.9482 299.083 + endloop + endfacet + facet normal 0.146869 -0.187432 -0.971236 + outer loop + vertex -323 72.9193 298.671 + vertex -322.262 75.6214 298.261 + vertex -320.237 72.9482 299.083 + endloop + endfacet + facet normal 0.146994 -0.187338 -0.971235 + outer loop + vertex -320.237 72.9482 299.083 + vertex -322.262 75.6214 298.261 + vertex -318.945 75.0134 298.88 + endloop + endfacet + facet normal 0.152959 -0.158991 -0.975359 + outer loop + vertex -322.262 75.6214 298.261 + vertex -321.384 78.3759 297.95 + vertex -318.945 75.0134 298.88 + endloop + endfacet + facet normal 0.156105 -0.156674 -0.975236 + outer loop + vertex -318.945 75.0134 298.88 + vertex -321.384 78.3759 297.95 + vertex -317.94 77.804 298.593 + endloop + endfacet + facet normal 0.161209 -0.129487 -0.978389 + outer loop + vertex -321.384 78.3759 297.95 + vertex -320.596 81.2908 297.694 + vertex -317.94 77.804 298.593 + endloop + endfacet + facet normal 0.16978 -0.122808 -0.9778 + outer loop + vertex -317.94 77.804 298.593 + vertex -320.596 81.2908 297.694 + vertex -317.266 80.7333 298.342 + endloop + endfacet + facet normal 0.173177 -0.104316 -0.979351 + outer loop + vertex -320.596 81.2908 297.694 + vertex -319.929 84.2313 297.498 + vertex -317.266 80.7333 298.342 + endloop + endfacet + facet normal 0.177118 -0.101224 -0.97897 + outer loop + vertex -317.266 80.7333 298.342 + vertex -319.929 84.2313 297.498 + vertex -316.65 83.6152 298.155 + endloop + endfacet + facet normal 0.18022 -0.0856878 -0.979887 + outer loop + vertex -319.929 84.2313 297.498 + vertex -319.319 87.1171 297.358 + vertex -316.65 83.6152 298.155 + endloop + endfacet + facet normal 0.183967 -0.082732 -0.979445 + outer loop + vertex -316.65 83.6152 298.155 + vertex -319.319 87.1171 297.358 + vertex -316.068 86.4903 298.022 + endloop + endfacet + facet normal 0.186503 -0.0701138 -0.979949 + outer loop + vertex -319.319 87.1171 297.358 + vertex -318.762 90.0076 297.258 + vertex -316.068 86.4903 298.022 + endloop + endfacet + facet normal 0.185861 -0.0706241 -0.980035 + outer loop + vertex -316.068 86.4903 298.022 + vertex -318.762 90.0076 297.258 + vertex -315.496 89.4006 297.921 + endloop + endfacet + facet normal 0.18838 -0.057481 -0.980413 + outer loop + vertex -318.762 90.0076 297.258 + vertex -318.254 92.9185 297.184 + vertex -315.496 89.4006 297.921 + endloop + endfacet + facet normal 0.190694 -0.0555954 -0.980074 + outer loop + vertex -315.496 89.4006 297.921 + vertex -318.254 92.9185 297.184 + vertex -315.002 92.3476 297.849 + endloop + endfacet + facet normal 0.192128 -0.0475972 -0.980215 + outer loop + vertex -318.254 92.9185 297.184 + vertex -317.778 95.8439 297.136 + vertex -315.002 92.3476 297.849 + endloop + endfacet + facet normal 0.193522 -0.0464456 -0.979996 + outer loop + vertex -315.002 92.3476 297.849 + vertex -317.778 95.8439 297.136 + vertex -314.538 95.306 297.801 + endloop + endfacet + facet normal 0.194654 -0.0397188 -0.980068 + outer loop + vertex -317.778 95.8439 297.136 + vertex -317.328 98.7764 297.106 + vertex -314.538 95.306 297.801 + endloop + endfacet + facet normal 0.196485 -0.0381861 -0.979763 + outer loop + vertex -314.538 95.306 297.801 + vertex -317.328 98.7764 297.106 + vertex -314.102 98.2551 297.773 + endloop + endfacet + facet normal 0.197072 -0.0345729 -0.979779 + outer loop + vertex -317.328 98.7764 297.106 + vertex -316.888 101.703 297.091 + vertex -314.102 98.2551 297.773 + endloop + endfacet + facet normal 0.198901 -0.0330325 -0.979463 + outer loop + vertex -314.102 98.2551 297.773 + vertex -316.888 101.703 297.091 + vertex -313.678 101.186 297.761 + endloop + endfacet + facet normal 0.199262 -0.0307891 -0.979462 + outer loop + vertex -316.888 101.703 297.091 + vertex -316.464 104.627 297.086 + vertex -313.678 101.186 297.761 + endloop + endfacet + facet normal 0.199876 -0.0302711 -0.979354 + outer loop + vertex -313.678 101.186 297.761 + vertex -316.464 104.627 297.086 + vertex -313.261 104.1 297.756 + endloop + endfacet + facet normal 0.199975 -0.0296669 -0.979352 + outer loop + vertex -316.464 104.627 297.086 + vertex -316.035 107.541 297.085 + vertex -313.261 104.1 297.756 + endloop + endfacet + facet normal 0.200494 -0.02923 -0.979259 + outer loop + vertex -313.261 104.1 297.756 + vertex -316.035 107.541 297.085 + vertex -312.845 107.005 297.754 + endloop + endfacet + facet normal 0.200591 -0.0286465 -0.979256 + outer loop + vertex -316.035 107.541 297.085 + vertex -315.618 110.46 297.085 + vertex -312.845 107.005 297.754 + endloop + endfacet + facet normal 0.201471 -0.0279094 -0.979097 + outer loop + vertex -312.845 107.005 297.754 + vertex -315.618 110.46 297.085 + vertex -312.438 109.911 297.755 + endloop + endfacet + facet normal 0.201401 -0.0283173 -0.979099 + outer loop + vertex -315.618 110.46 297.085 + vertex -315.205 113.388 297.085 + vertex -312.438 109.911 297.755 + endloop + endfacet + facet normal 0.200201 -0.029314 -0.979316 + outer loop + vertex -312.438 109.911 297.755 + vertex -315.205 113.388 297.085 + vertex -312.015 112.828 297.754 + endloop + endfacet + facet normal 0.200265 -0.0289489 -0.979314 + outer loop + vertex -315.205 113.388 297.085 + vertex -314.777 116.329 297.086 + vertex -312.015 112.828 297.754 + endloop + endfacet + facet normal 0.201309 -0.0280886 -0.979125 + outer loop + vertex -312.015 112.828 297.754 + vertex -314.777 116.329 297.086 + vertex -311.601 115.769 297.755 + endloop + endfacet + facet normal 0.201295 -0.0281716 -0.979125 + outer loop + vertex -314.777 116.329 297.086 + vertex -314.354 119.297 297.087 + vertex -311.601 115.769 297.755 + endloop + endfacet + facet normal 0.200885 -0.0285054 -0.9792 + outer loop + vertex -311.601 115.769 297.755 + vertex -314.354 119.297 297.087 + vertex -311.175 118.736 297.756 + endloop + endfacet + facet normal 0.200952 -0.0281248 -0.979197 + outer loop + vertex -314.354 119.297 297.087 + vertex -313.923 122.29 297.09 + vertex -311.175 118.736 297.756 + endloop + endfacet + facet normal 0.200747 -0.0282907 -0.979235 + outer loop + vertex -311.175 118.736 297.756 + vertex -313.923 122.29 297.09 + vertex -310.748 121.738 297.757 + endloop + endfacet + facet normal 0.200597 -0.0291585 -0.97924 + outer loop + vertex -313.923 122.29 297.09 + vertex -313.48 125.304 297.091 + vertex -310.748 121.738 297.757 + endloop + endfacet + facet normal 0.203773 -0.0266163 -0.978656 + outer loop + vertex -310.748 121.738 297.757 + vertex -313.48 125.304 297.091 + vertex -310.335 124.764 297.761 + endloop + endfacet + facet normal 0.20355 -0.0279285 -0.978666 + outer loop + vertex -313.48 125.304 297.091 + vertex -313.059 128.337 297.092 + vertex -310.335 124.764 297.761 + endloop + endfacet + facet normal 0.201628 -0.0294609 -0.979019 + outer loop + vertex -310.335 124.764 297.761 + vertex -313.059 128.337 297.092 + vertex -309.894 127.798 297.76 + endloop + endfacet + facet normal 0.201731 -0.0288491 -0.979016 + outer loop + vertex -313.059 128.337 297.092 + vertex -312.626 131.346 297.093 + vertex -309.894 127.798 297.76 + endloop + endfacet + facet normal 0.202583 -0.0281639 -0.97886 + outer loop + vertex -309.894 127.798 297.76 + vertex -312.626 131.346 297.093 + vertex -309.468 130.809 297.762 + endloop + endfacet + facet normal 0.202425 -0.0291045 -0.978865 + outer loop + vertex -312.626 131.346 297.093 + vertex -312.194 134.315 297.094 + vertex -309.468 130.809 297.762 + endloop + endfacet + facet normal 0.204106 -0.0277384 -0.978556 + outer loop + vertex -309.468 130.809 297.762 + vertex -312.194 134.315 297.094 + vertex -309.054 133.775 297.764 + endloop + endfacet + facet normal 0.203942 -0.0286985 -0.978562 + outer loop + vertex -312.194 134.315 297.094 + vertex -311.778 137.244 297.094 + vertex -309.054 133.775 297.764 + endloop + endfacet + facet normal 0.206013 -0.0269977 -0.978177 + outer loop + vertex -309.054 133.775 297.764 + vertex -311.778 137.244 297.094 + vertex -308.653 136.693 297.768 + endloop + endfacet + facet normal 0.205675 -0.0289354 -0.978193 + outer loop + vertex -311.778 137.244 297.094 + vertex -311.367 140.147 297.095 + vertex -308.653 136.693 297.768 + endloop + endfacet + facet normal 0.206307 -0.0284151 -0.978075 + outer loop + vertex -308.653 136.693 297.768 + vertex -311.367 140.147 297.095 + vertex -308.248 139.593 297.769 + endloop + endfacet + facet normal 0.206364 -0.0280937 -0.978072 + outer loop + vertex -311.367 140.147 297.095 + vertex -310.973 143.073 297.094 + vertex -308.248 139.593 297.769 + endloop + endfacet + facet normal 0.204638 -0.0295078 -0.978393 + outer loop + vertex -308.248 139.593 297.769 + vertex -310.973 143.073 297.094 + vertex -307.833 142.522 297.767 + endloop + endfacet + facet normal 0.204802 -0.0285669 -0.978387 + outer loop + vertex -310.973 143.073 297.094 + vertex -310.574 146.04 297.091 + vertex -307.833 142.522 297.767 + endloop + endfacet + facet normal 0.207232 -0.0265856 -0.97793 + outer loop + vertex -307.833 142.522 297.767 + vertex -310.574 146.04 297.091 + vertex -307.448 145.501 297.768 + endloop + endfacet + facet normal 0.206747 -0.0294301 -0.977952 + outer loop + vertex -310.574 146.04 297.091 + vertex -310.162 149.037 297.088 + vertex -307.448 145.501 297.768 + endloop + endfacet + facet normal 0.203902 -0.0317148 -0.978478 + outer loop + vertex -307.448 145.501 297.768 + vertex -310.162 149.037 297.088 + vertex -307.015 148.504 297.761 + endloop + endfacet + facet normal 0.204147 -0.0302618 -0.978472 + outer loop + vertex -310.162 149.037 297.088 + vertex -309.743 152.035 297.082 + vertex -307.015 148.504 297.761 + endloop + endfacet + facet normal 0.202682 -0.031445 -0.97874 + outer loop + vertex -307.015 148.504 297.761 + vertex -309.743 152.035 297.082 + vertex -306.567 151.48 297.758 + endloop + endfacet + facet normal 0.202138 -0.0345688 -0.978747 + outer loop + vertex -309.743 152.035 297.082 + vertex -309.239 154.961 297.083 + vertex -306.567 151.48 297.758 + endloop + endfacet + facet normal 0.200342 -0.0360094 -0.979064 + outer loop + vertex -306.567 151.48 297.758 + vertex -309.239 154.961 297.083 + vertex -306.047 154.385 297.758 + endloop + endfacet + facet normal 0.200328 -0.0360879 -0.979064 + outer loop + vertex -309.239 154.961 297.083 + vertex -308.681 157.823 297.092 + vertex -306.047 154.385 297.758 + endloop + endfacet + facet normal 0.203396 -0.0336308 -0.978519 + outer loop + vertex -306.047 154.385 297.758 + vertex -308.681 157.823 297.092 + vertex -305.549 157.263 297.762 + endloop + endfacet + facet normal 0.20474 -0.0260424 -0.97847 + outer loop + vertex -308.681 157.823 297.092 + vertex -308.223 160.733 297.11 + vertex -305.549 157.263 297.762 + endloop + endfacet + facet normal 0.21819 -0.0151746 -0.975788 + outer loop + vertex -305.549 157.263 297.762 + vertex -308.223 160.733 297.11 + vertex -305.247 160.233 297.784 + endloop + endfacet + facet normal 0.224411 0.023913 -0.974201 + outer loop + vertex -308.223 160.733 297.11 + vertex -308.007 163.899 297.238 + vertex -305.247 160.233 297.784 + endloop + endfacet + facet normal 0.235964 0.0330563 -0.9712 + outer loop + vertex -305.247 160.233 297.784 + vertex -308.007 163.899 297.238 + vertex -305.135 163.337 297.917 + endloop + endfacet + facet normal 0.253453 0.139293 -0.957266 + outer loop + vertex -308.007 163.899 297.238 + vertex -307.754 167.169 297.781 + vertex -305.135 163.337 297.917 + endloop + endfacet + facet normal 0.217522 0.114298 -0.96934 + outer loop + vertex -305.135 163.337 297.917 + vertex -307.754 167.169 297.781 + vertex -304.706 166.479 298.383 + endloop + endfacet + facet normal 0.0114157 -0.462971 -0.8863 + outer loop + vertex -332.097 56.9705 303.497 + vertex -330.429 58.7273 302.601 + vertex -325.865 56.0317 304.068 + endloop + endfacet + facet normal -0.0409831 -0.455757 -0.88916 + outer loop + vertex -319.575 52.1777 306.053 + vertex -317.354 55.7577 304.116 + vertex -305.072 50.429 306.281 + endloop + endfacet + facet normal -0.031351 -0.437434 -0.898704 + outer loop + vertex -305.072 50.429 306.281 + vertex -317.354 55.7577 304.116 + vertex -303.619 54.27 304.361 + endloop + endfacet + facet normal -0.0460341 -0.432706 -0.900359 + outer loop + vertex -305.072 50.429 306.281 + vertex -303.619 54.27 304.361 + vertex -289.253 48.6414 306.331 + endloop + endfacet + facet normal -0.0403762 -0.420395 -0.906442 + outer loop + vertex -289.253 48.6414 306.331 + vertex -303.619 54.27 304.361 + vertex -288.229 52.6452 304.429 + endloop + endfacet + facet normal -0.0434919 -0.419686 -0.906627 + outer loop + vertex -289.253 48.6414 306.331 + vertex -288.229 52.6452 304.429 + vertex -271.395 46.7714 306.34 + endloop + endfacet + facet normal -0.0410259 -0.41357 -0.909548 + outer loop + vertex -271.395 46.7714 306.34 + vertex -288.229 52.6452 304.429 + vertex -270.637 50.8615 304.446 + endloop + endfacet + facet normal -0.0400182 -0.413741 -0.909515 + outer loop + vertex -271.395 46.7714 306.34 + vertex -270.637 50.8615 304.446 + vertex -251.463 44.8089 306.356 + endloop + endfacet + facet normal -0.0382391 -0.408829 -0.911809 + outer loop + vertex -251.463 44.8089 306.356 + vertex -270.637 50.8615 304.446 + vertex -250.789 48.9642 304.465 + endloop + endfacet + facet normal -0.0371246 -0.408997 -0.91178 + outer loop + vertex -251.463 44.8089 306.356 + vertex -250.789 48.9642 304.465 + vertex -229.93 42.8127 306.375 + endloop + endfacet + facet normal -0.035823 -0.405134 -0.913555 + outer loop + vertex -229.93 42.8127 306.375 + vertex -250.789 48.9642 304.465 + vertex -229.248 47.0135 304.485 + endloop + endfacet + facet normal -0.0355922 -0.405169 -0.913549 + outer loop + vertex -229.93 42.8127 306.375 + vertex -229.248 47.0135 304.485 + vertex -207.664 40.8589 306.374 + endloop + endfacet + facet normal -0.0350056 -0.403364 -0.91437 + outer loop + vertex -207.664 40.8589 306.374 + vertex -229.248 47.0135 304.485 + vertex -206.964 45.0871 304.482 + endloop + endfacet + facet normal -0.0354376 -0.403298 -0.914382 + outer loop + vertex -207.664 40.8589 306.374 + vertex -206.964 45.0871 304.482 + vertex -185.477 38.9903 306.338 + endloop + endfacet + facet normal -0.0346639 -0.400901 -0.915465 + outer loop + vertex -185.477 38.9903 306.338 + vertex -206.964 45.0871 304.482 + vertex -184.781 43.2515 304.446 + endloop + endfacet + facet normal -0.0352693 -0.400809 -0.915482 + outer loop + vertex -185.477 38.9903 306.338 + vertex -184.781 43.2515 304.446 + vertex -163.826 37.2361 306.272 + endloop + endfacet + facet normal -0.0352125 -0.400635 -0.915561 + outer loop + vertex -163.826 37.2361 306.272 + vertex -184.781 43.2515 304.446 + vertex -163.148 41.5158 304.373 + endloop + endfacet + facet normal -0.0341143 -0.400797 -0.915532 + outer loop + vertex -163.826 37.2361 306.272 + vertex -163.148 41.5158 304.373 + vertex -142.797 35.624 306.194 + endloop + endfacet + facet normal -0.0344257 -0.401741 -0.915106 + outer loop + vertex -142.797 35.624 306.194 + vertex -163.148 41.5158 304.373 + vertex -142.16 39.9126 304.288 + endloop + endfacet + facet normal -0.0317192 -0.402113 -0.91504 + outer loop + vertex -142.797 35.624 306.194 + vertex -142.16 39.9126 304.288 + vertex -122.214 34.1681 306.121 + endloop + endfacet + facet normal -0.0314879 -0.401411 -0.915357 + outer loop + vertex -122.214 34.1681 306.121 + vertex -142.16 39.9126 304.288 + vertex -121.653 38.4744 304.213 + endloop + endfacet + facet normal -0.0266645 -0.401994 -0.915254 + outer loop + vertex -122.214 34.1681 306.121 + vertex -121.653 38.4744 304.213 + vertex -101.836 32.9187 306.076 + endloop + endfacet + facet normal -0.0275001 -0.404583 -0.914088 + outer loop + vertex -101.836 32.9187 306.076 + vertex -121.653 38.4744 304.213 + vertex -101.36 37.2151 304.16 + endloop + endfacet + facet normal -0.021587 -0.405188 -0.913978 + outer loop + vertex -101.836 32.9187 306.076 + vertex -101.36 37.2151 304.16 + vertex -81.4615 31.8729 306.058 + endloop + endfacet + facet normal -0.0215125 -0.404949 -0.914086 + outer loop + vertex -81.4615 31.8729 306.058 + vertex -101.36 37.2151 304.16 + vertex -81.08 36.1746 304.143 + endloop + endfacet + facet normal -0.0150283 -0.405478 -0.913981 + outer loop + vertex -81.4615 31.8729 306.058 + vertex -81.08 36.1746 304.143 + vertex -61.0208 31.0739 306.076 + endloop + endfacet + facet normal -0.0150447 -0.405533 -0.913957 + outer loop + vertex -61.0208 31.0739 306.076 + vertex -81.08 36.1746 304.143 + vertex -60.7325 35.3747 304.163 + endloop + endfacet + facet normal -0.0100099 -0.40584 -0.913889 + outer loop + vertex -61.0208 31.0739 306.076 + vertex -60.7325 35.3747 304.163 + vertex -40.5604 30.4991 306.108 + endloop + endfacet + facet normal -0.0102217 -0.406584 -0.913556 + outer loop + vertex -40.5604 30.4991 306.108 + vertex -60.7325 35.3747 304.163 + vertex -40.363 34.7921 304.195 + endloop + endfacet + facet normal -0.0055535 -0.406778 -0.91351 + outer loop + vertex -40.5604 30.4991 306.108 + vertex -40.363 34.7921 304.195 + vertex -20.1578 30.1547 306.137 + endloop + endfacet + facet normal -0.00518126 -0.405411 -0.91412 + outer loop + vertex -20.1578 30.1547 306.137 + vertex -40.363 34.7921 304.195 + vertex -20.0507 34.4551 304.229 + endloop + endfacet + facet normal -0.00174817 -0.405487 -0.914099 + outer loop + vertex -20.1578 30.1547 306.137 + vertex -20.0507 34.4551 304.229 + vertex 0.157814 30.0389 306.149 + endloop + endfacet + facet normal -0.00153558 -0.404672 -0.914461 + outer loop + vertex 0.157814 30.0389 306.149 + vertex -20.0507 34.4551 304.229 + vertex 0.176449 34.3444 304.244 + endloop + endfacet + facet normal 0.00184927 -0.404684 -0.914455 + outer loop + vertex 0.157814 30.0389 306.149 + vertex 0.176449 34.3444 304.244 + vertex 20.4336 30.1538 306.14 + endloop + endfacet + facet normal 0.00162363 -0.405593 -0.914052 + outer loop + vertex 20.4336 30.1538 306.14 + vertex 0.176449 34.3444 304.244 + vertex 20.3643 34.454 304.231 + endloop + endfacet + facet normal 0.00563153 -0.405533 -0.914063 + outer loop + vertex 20.4336 30.1538 306.14 + vertex 20.3643 34.454 304.231 + vertex 40.7521 30.4978 306.112 + endloop + endfacet + facet normal 0.00524311 -0.407186 -0.91333 + outer loop + vertex 40.7521 30.4978 306.112 + vertex 20.3643 34.454 304.231 + vertex 40.5918 34.789 304.198 + endloop + endfacet + facet normal 0.00995611 -0.407025 -0.913363 + outer loop + vertex 40.7521 30.4978 306.112 + vertex 40.5918 34.789 304.198 + vertex 61.1679 31.0702 306.08 + endloop + endfacet + facet normal 0.00985454 -0.407484 -0.913159 + outer loop + vertex 61.1679 31.0702 306.08 + vertex 40.5918 34.789 304.198 + vertex 60.9173 35.3615 304.162 + endloop + endfacet + facet normal 0.0152821 -0.407191 -0.913215 + outer loop + vertex 61.1679 31.0702 306.08 + vertex 60.9173 35.3615 304.162 + vertex 81.6878 31.8814 306.061 + endloop + endfacet + facet normal 0.0156668 -0.40534 -0.914032 + outer loop + vertex 81.6878 31.8814 306.061 + vertex 60.9173 35.3615 304.162 + vertex 81.3479 36.1854 304.147 + endloop + endfacet + facet normal 0.0211284 -0.404939 -0.914099 + outer loop + vertex 81.6878 31.8814 306.061 + vertex 81.3479 36.1854 304.147 + vertex 102.291 32.9311 306.072 + endloop + endfacet + facet normal 0.0215011 -0.403034 -0.914932 + outer loop + vertex 102.291 32.9311 306.072 + vertex 81.3479 36.1854 304.147 + vertex 101.86 37.2432 304.163 + endloop + endfacet + facet normal 0.0271823 -0.402503 -0.915015 + outer loop + vertex 102.291 32.9311 306.072 + vertex 101.86 37.2432 304.163 + vertex 122.97 34.2156 306.122 + endloop + endfacet + facet normal 0.0271904 -0.402458 -0.915034 + outer loop + vertex 122.97 34.2156 306.122 + vertex 101.86 37.2432 304.163 + vertex 122.449 38.5184 304.214 + endloop + endfacet + facet normal 0.031624 -0.401956 -0.915113 + outer loop + vertex 122.97 34.2156 306.122 + vertex 122.449 38.5184 304.214 + vertex 143.774 35.6893 306.193 + endloop + endfacet + facet normal 0.031857 -0.400608 -0.915696 + outer loop + vertex 143.774 35.6893 306.193 + vertex 122.449 38.5184 304.214 + vertex 143.179 39.9877 304.292 + endloop + endfacet + facet normal 0.0345075 -0.400265 -0.91575 + outer loop + vertex 143.774 35.6893 306.193 + vertex 143.179 39.9877 304.292 + vertex 164.841 37.3301 306.27 + endloop + endfacet + facet normal 0.0344978 -0.400325 -0.915724 + outer loop + vertex 164.841 37.3301 306.27 + vertex 143.179 39.9877 304.292 + vertex 164.197 41.6134 304.373 + endloop + endfacet + facet normal 0.0354773 -0.400187 -0.915746 + outer loop + vertex 164.841 37.3301 306.27 + vertex 164.197 41.6134 304.373 + vertex 186.33 39.1026 306.328 + endloop + endfacet + facet normal 0.0353442 -0.401066 -0.915367 + outer loop + vertex 186.33 39.1026 306.328 + vertex 164.197 41.6134 304.373 + vertex 185.671 43.3652 304.435 + endloop + endfacet + facet normal 0.0358533 -0.400993 -0.915379 + outer loop + vertex 186.33 39.1026 306.328 + vertex 185.671 43.3652 304.435 + vertex 208.266 40.9835 306.363 + endloop + endfacet + facet normal 0.0354956 -0.403504 -0.914289 + outer loop + vertex 208.266 40.9835 306.363 + vertex 185.671 43.3652 304.435 + vertex 207.625 45.2119 304.472 + endloop + endfacet + facet normal 0.0358235 -0.403457 -0.914297 + outer loop + vertex 208.266 40.9835 306.363 + vertex 207.625 45.2119 304.472 + vertex 230.336 42.9002 306.382 + endloop + endfacet + facet normal 0.0352104 -0.407879 -0.912357 + outer loop + vertex 230.336 42.9002 306.382 + vertex 207.625 45.2119 304.472 + vertex 229.722 47.0804 304.49 + endloop + endfacet + facet normal 0.0372096 -0.407605 -0.9124 + outer loop + vertex 230.336 42.9002 306.382 + vertex 229.722 47.0804 304.49 + vertex 251.864 44.8154 306.404 + endloop + endfacet + facet normal 0.0366667 -0.411464 -0.910688 + outer loop + vertex 251.864 44.8154 306.404 + vertex 229.722 47.0804 304.49 + vertex 251.213 48.9406 304.514 + endloop + endfacet + facet normal 0.0399395 -0.410984 -0.910767 + outer loop + vertex 251.864 44.8154 306.404 + vertex 251.213 48.9406 304.514 + vertex 271.97 46.7397 306.418 + endloop + endfacet + facet normal 0.0387321 -0.419179 -0.907077 + outer loop + vertex 271.97 46.7397 306.418 + vertex 251.213 48.9406 304.514 + vertex 271.227 50.774 304.522 + endloop + endfacet + facet normal 0.0425078 -0.418543 -0.907202 + outer loop + vertex 271.97 46.7397 306.418 + vertex 271.227 50.774 304.522 + vertex 290.051 48.7332 306.345 + endloop + endfacet + facet normal 0.0417876 -0.423258 -0.905045 + outer loop + vertex 290.051 48.7332 306.345 + vertex 271.227 50.774 304.522 + vertex 289.024 52.6809 304.452 + endloop + endfacet + facet normal 0.042296 -0.42314 -0.905076 + outer loop + vertex 290.051 48.7332 306.345 + vertex 289.024 52.6809 304.452 + vertex 305.867 50.9112 306.066 + endloop + endfacet + facet normal 0.0419946 -0.425159 -0.904144 + outer loop + vertex 305.867 50.9112 306.066 + vertex 289.024 52.6809 304.452 + vertex 304.312 54.7836 304.173 + endloop + endfacet + facet normal 0.0314525 -0.428769 -0.902867 + outer loop + vertex 305.867 50.9112 306.066 + vertex 304.312 54.7836 304.173 + vertex 319.662 53.2293 305.446 + endloop + endfacet + facet normal 0.0313141 -0.429756 -0.902402 + outer loop + vertex 319.662 53.2293 305.446 + vertex 304.312 54.7836 304.173 + vertex 317.312 57.0446 303.547 + endloop + endfacet + facet normal 0.00418912 -0.443428 -0.8963 + outer loop + vertex 319.662 53.2293 305.446 + vertex 317.312 57.0446 303.547 + vertex 326.734 55.4022 304.404 + endloop + endfacet + facet normal 0.023859 -0.49433 -0.868947 + outer loop + vertex 329.472 53.7547 305.416 + vertex 319.662 53.2293 305.446 + vertex 326.734 55.4022 304.404 + endloop + endfacet + facet normal 0.00834022 -0.513449 -0.85808 + outer loop + vertex 329.472 53.7547 305.416 + vertex 326.734 55.4022 304.404 + vertex 333.989 55.0399 304.691 + endloop + endfacet + facet normal 0.00819692 -0.515394 -0.856914 + outer loop + vertex 333.989 55.0399 304.691 + vertex 326.734 55.4022 304.404 + vertex 332.228 56.6688 303.695 + endloop + endfacet + facet normal -0.00759443 -0.527819 -0.849323 + outer loop + vertex 333.989 55.0399 304.691 + vertex 332.228 56.6688 303.695 + vertex 337.324 56.1963 303.943 + endloop + endfacet + facet normal -0.00884157 -0.537923 -0.842948 + outer loop + vertex 337.324 56.1963 303.943 + vertex 332.228 56.6688 303.695 + vertex 336.564 57.6758 303.007 + endloop + endfacet + facet normal -0.0176696 -0.541088 -0.84078 + outer loop + vertex 337.324 56.1963 303.943 + vertex 336.564 57.6758 303.007 + vertex 341.548 56.5947 303.598 + endloop + endfacet + facet normal -0.030279 -0.583315 -0.811682 + outer loop + vertex 341.548 56.5947 303.598 + vertex 336.564 57.6758 303.007 + vertex 340.169 58.4289 302.331 + endloop + endfacet + facet normal -0.0523491 -0.59383 -0.802886 + outer loop + vertex 341.548 56.5947 303.598 + vertex 340.169 58.4289 302.331 + vertex 344.644 57.3774 302.817 + endloop + endfacet + facet normal -0.0609046 -0.620514 -0.781827 + outer loop + vertex 344.644 57.3774 302.817 + vertex 340.169 58.4289 302.331 + vertex 342.428 59.1072 301.617 + endloop + endfacet + facet normal -0.0970471 -0.648317 -0.75516 + outer loop + vertex 344.644 57.3774 302.817 + vertex 342.428 59.1072 301.617 + vertex 345.362 58.3468 301.892 + endloop + endfacet + facet normal -0.0926707 -0.635536 -0.766489 + outer loop + vertex 345.362 58.3468 301.892 + vertex 342.428 59.1072 301.617 + vertex 343.478 59.7581 300.95 + endloop + endfacet + facet normal -0.000426938 -0.464356 -0.885649 + outer loop + vertex 326.367 57.2984 303.41 + vertex 326.734 55.4022 304.404 + vertex 317.312 57.0446 303.547 + endloop + endfacet + facet normal -0.00698045 -0.46534 -0.885105 + outer loop + vertex 326.734 55.4022 304.404 + vertex 326.367 57.2984 303.41 + vertex 332.228 56.6688 303.695 + endloop + endfacet + facet normal -0.00801687 -0.473115 -0.880964 + outer loop + vertex 332.228 56.6688 303.695 + vertex 326.367 57.2984 303.41 + vertex 330.737 58.4705 302.741 + endloop + endfacet + facet normal -0.0261958 -0.484641 -0.874321 + outer loop + vertex 332.228 56.6688 303.695 + vertex 330.737 58.4705 302.741 + vertex 336.564 57.6758 303.007 + endloop + endfacet + facet normal -0.0296393 -0.505809 -0.862136 + outer loop + vertex 336.564 57.6758 303.007 + vertex 330.737 58.4705 302.741 + vertex 334.949 59.4878 301.999 + endloop + endfacet + facet normal -0.0512365 -0.519824 -0.852735 + outer loop + vertex 336.564 57.6758 303.007 + vertex 334.949 59.4878 301.999 + vertex 340.169 58.4289 302.331 + endloop + endfacet + facet normal -0.0573565 -0.544912 -0.836529 + outer loop + vertex 340.169 58.4289 302.331 + vertex 334.949 59.4878 301.999 + vertex 338.187 60.2535 301.278 + endloop + endfacet + facet normal -0.0882317 -0.567942 -0.818326 + outer loop + vertex 340.169 58.4289 302.331 + vertex 338.187 60.2535 301.278 + vertex 342.428 59.1072 301.617 + endloop + endfacet + facet normal -0.0912634 -0.577149 -0.811523 + outer loop + vertex 342.428 59.1072 301.617 + vertex 338.187 60.2535 301.278 + vertex 340.212 60.8461 300.629 + endloop + endfacet + facet normal -0.124282 -0.605 -0.786466 + outer loop + vertex 342.428 59.1072 301.617 + vertex 340.212 60.8461 300.629 + vertex 343.478 59.7581 300.95 + endloop + endfacet + facet normal -0.1186 -0.591262 -0.797712 + outer loop + vertex 343.478 59.7581 300.95 + vertex 340.212 60.8461 300.629 + vertex 341.136 61.5165 299.995 + endloop + endfacet + facet normal 0.0253141 -0.534985 -0.844482 + outer loop + vertex -333.857 55.282 304.514 + vertex -337.107 57.6024 302.947 + vertex -332.097 56.9705 303.497 + endloop + endfacet + facet normal 0.0307515 -0.506743 -0.861548 + outer loop + vertex -337.107 57.6024 302.947 + vertex -335.156 59.3521 301.987 + vertex -332.097 56.9705 303.497 + endloop + endfacet + facet normal 0.0482713 -0.489884 -0.87045 + outer loop + vertex -332.097 56.9705 303.497 + vertex -335.156 59.3521 301.987 + vertex -330.429 58.7273 302.601 + endloop + endfacet + facet normal 0.0550836 -0.455905 -0.888322 + outer loop + vertex -335.156 59.3521 301.987 + vertex -333.38 61.187 301.156 + vertex -330.429 58.7273 302.601 + endloop + endfacet + facet normal 0.069812 -0.441798 -0.894394 + outer loop + vertex -330.429 58.7273 302.601 + vertex -333.38 61.187 301.156 + vertex -328.945 60.6124 301.786 + endloop + endfacet + facet normal 0.0763156 -0.408318 -0.909644 + outer loop + vertex -333.38 61.187 301.156 + vertex -331.747 63.261 300.362 + vertex -328.945 60.6124 301.786 + endloop + endfacet + facet normal 0.0909218 -0.395245 -0.914065 + outer loop + vertex -328.945 60.6124 301.786 + vertex -331.747 63.261 300.362 + vertex -327.556 62.6925 301.025 + endloop + endfacet + facet normal 0.097728 -0.360761 -0.927524 + outer loop + vertex -331.747 63.261 300.362 + vertex -330.178 65.5088 299.653 + vertex -327.556 62.6925 301.025 + endloop + endfacet + facet normal 0.113169 -0.347919 -0.930669 + outer loop + vertex -327.556 62.6925 301.025 + vertex -330.178 65.5088 299.653 + vertex -326.231 65.0322 300.311 + endloop + endfacet + facet normal 0.119119 -0.31412 -0.941881 + outer loop + vertex -330.178 65.5088 299.653 + vertex -328.692 68.0168 299.004 + vertex -326.231 65.0322 300.311 + endloop + endfacet + facet normal 0.13492 -0.301905 -0.943743 + outer loop + vertex -326.231 65.0322 300.311 + vertex -328.692 68.0168 299.004 + vertex -324.951 67.6082 299.67 + endloop + endfacet + facet normal 0.140126 -0.2691 -0.952864 + outer loop + vertex -328.692 68.0168 299.004 + vertex -327.161 70.7076 298.47 + vertex -324.951 67.6082 299.67 + endloop + endfacet + facet normal 0.155966 -0.258041 -0.953462 + outer loop + vertex -324.951 67.6082 299.67 + vertex -327.161 70.7076 298.47 + vertex -323.826 70.2387 299.142 + endloop + endfacet + facet normal 0.161177 -0.229996 -0.959752 + outer loop + vertex -327.161 70.7076 298.47 + vertex -325.627 72.8017 298.225 + vertex -323.826 70.2387 299.142 + endloop + endfacet + facet normal 0.172619 -0.221923 -0.959663 + outer loop + vertex -323.826 70.2387 299.142 + vertex -325.627 72.8017 298.225 + vertex -323 72.9193 298.671 + endloop + endfacet + facet normal 0.172583 -0.215863 -0.96105 + outer loop + vertex -325.627 72.8017 298.225 + vertex -325.176 75.5894 297.68 + vertex -323 72.9193 298.671 + endloop + endfacet + facet normal 0.193613 -0.198617 -0.960763 + outer loop + vertex -323 72.9193 298.671 + vertex -325.176 75.5894 297.68 + vertex -322.262 75.6214 298.261 + endloop + endfacet + facet normal 0.194036 -0.183207 -0.963735 + outer loop + vertex -325.176 75.5894 297.68 + vertex -324.073 78.1944 297.407 + vertex -322.262 75.6214 298.261 + endloop + endfacet + facet normal 0.20601 -0.174488 -0.962868 + outer loop + vertex -322.262 75.6214 298.261 + vertex -324.073 78.1944 297.407 + vertex -321.384 78.3759 297.95 + endloop + endfacet + facet normal 0.205287 -0.151903 -0.966842 + outer loop + vertex -324.073 78.1944 297.407 + vertex -323.564 81.4002 297.012 + vertex -321.384 78.3759 297.95 + endloop + endfacet + facet normal 0.216633 -0.143359 -0.96567 + outer loop + vertex -321.384 78.3759 297.95 + vertex -323.564 81.4002 297.012 + vertex -320.596 81.2908 297.694 + endloop + endfacet + facet normal 0.21801 -0.122199 -0.968266 + outer loop + vertex -323.564 81.4002 297.012 + vertex -322.365 84.2947 296.916 + vertex -320.596 81.2908 297.694 + endloop + endfacet + facet normal 0.228015 -0.115908 -0.966734 + outer loop + vertex -320.596 81.2908 297.694 + vertex -322.365 84.2947 296.916 + vertex -319.929 84.2313 297.498 + endloop + endfacet + facet normal 0.228564 -0.105033 -0.967846 + outer loop + vertex -322.365 84.2947 296.916 + vertex -322.001 87.5179 296.653 + vertex -319.929 84.2313 297.498 + endloop + endfacet + facet normal 0.23963 -0.0975689 -0.965949 + outer loop + vertex -319.929 84.2313 297.498 + vertex -322.001 87.5179 296.653 + vertex -319.319 87.1171 297.358 + endloop + endfacet + facet normal 0.242257 -0.0814691 -0.966786 + outer loop + vertex -322.001 87.5179 296.653 + vertex -321.096 90.2152 296.652 + vertex -319.319 87.1171 297.358 + endloop + endfacet + facet normal 0.243578 -0.0806508 -0.966522 + outer loop + vertex -319.319 87.1171 297.358 + vertex -321.096 90.2152 296.652 + vertex -318.762 90.0076 297.258 + endloop + endfacet + facet normal 0.244193 -0.0746834 -0.966846 + outer loop + vertex -321.096 90.2152 296.652 + vertex -320.858 93.3785 296.468 + vertex -318.762 90.0076 297.258 + endloop + endfacet + facet normal 0.253478 -0.0684561 -0.964916 + outer loop + vertex -318.762 90.0076 297.258 + vertex -320.858 93.3785 296.468 + vertex -318.254 92.9185 297.184 + endloop + endfacet + facet normal 0.255937 -0.0548721 -0.965135 + outer loop + vertex -320.858 93.3785 296.468 + vertex -320.063 96.0122 296.529 + vertex -318.254 92.9185 297.184 + endloop + endfacet + facet normal 0.252326 -0.0571563 -0.965953 + outer loop + vertex -318.254 92.9185 297.184 + vertex -320.063 96.0122 296.529 + vertex -317.778 95.8439 297.136 + endloop + endfacet + facet normal 0.252539 -0.0546083 -0.966045 + outer loop + vertex -320.063 96.0122 296.529 + vertex -319.918 99.1851 296.387 + vertex -317.778 95.8439 297.136 + endloop + endfacet + facet normal 0.259843 -0.0495561 -0.964378 + outer loop + vertex -317.778 95.8439 297.136 + vertex -319.918 99.1851 296.387 + vertex -317.328 98.7764 297.106 + endloop + endfacet + facet normal 0.261321 -0.0402508 -0.964412 + outer loop + vertex -319.918 99.1851 296.387 + vertex -319.165 101.823 296.481 + vertex -317.328 98.7764 297.106 + endloop + endfacet + facet normal 0.256442 -0.0434334 -0.965583 + outer loop + vertex -317.328 98.7764 297.106 + vertex -319.165 101.823 296.481 + vertex -316.888 101.703 297.091 + endloop + endfacet + facet normal 0.25631 -0.0456036 -0.965518 + outer loop + vertex -319.165 101.823 296.481 + vertex -319.041 105 296.364 + vertex -316.888 101.703 297.091 + endloop + endfacet + facet normal 0.264042 -0.0401463 -0.963675 + outer loop + vertex -316.888 101.703 297.091 + vertex -319.041 105 296.364 + vertex -316.464 104.627 297.086 + endloop + endfacet + facet normal 0.264922 -0.0340487 -0.963669 + outer loop + vertex -319.041 105 296.364 + vertex -318.31 107.661 296.471 + vertex -316.464 104.627 297.086 + endloop + endfacet + facet normal 0.258489 -0.0382848 -0.965255 + outer loop + vertex -316.464 104.627 297.086 + vertex -318.31 107.661 296.471 + vertex -316.035 107.541 297.085 + endloop + endfacet + facet normal 0.2582 -0.0431106 -0.965129 + outer loop + vertex -318.31 107.661 296.471 + vertex -318.181 110.842 296.363 + vertex -316.035 107.541 297.085 + endloop + endfacet + facet normal 0.265589 -0.037915 -0.96334 + outer loop + vertex -316.035 107.541 297.085 + vertex -318.181 110.842 296.363 + vertex -315.618 110.46 297.085 + endloop + endfacet + facet normal 0.266321 -0.0329714 -0.96332 + outer loop + vertex -318.181 110.842 296.363 + vertex -317.45 113.516 296.474 + vertex -315.618 110.46 297.085 + endloop + endfacet + facet normal 0.260603 -0.0366851 -0.964749 + outer loop + vertex -315.618 110.46 297.085 + vertex -317.45 113.516 296.474 + vertex -315.205 113.388 297.085 + endloop + endfacet + facet normal 0.260226 -0.0426279 -0.964606 + outer loop + vertex -317.45 113.516 296.474 + vertex -317.328 116.724 296.365 + vertex -315.205 113.388 297.085 + endloop + endfacet + facet normal 0.266156 -0.0385404 -0.963159 + outer loop + vertex -315.205 113.388 297.085 + vertex -317.328 116.724 296.365 + vertex -314.777 116.329 297.086 + endloop + endfacet + facet normal 0.267006 -0.0329892 -0.96313 + outer loop + vertex -317.328 116.724 296.365 + vertex -316.598 119.425 296.475 + vertex -314.777 116.329 297.086 + endloop + endfacet + facet normal 0.261194 -0.0366961 -0.964589 + outer loop + vertex -314.777 116.329 297.086 + vertex -316.598 119.425 296.475 + vertex -314.354 119.297 297.087 + endloop + endfacet + facet normal 0.260785 -0.0431228 -0.964433 + outer loop + vertex -316.598 119.425 296.475 + vertex -316.456 122.66 296.369 + vertex -314.354 119.297 297.087 + endloop + endfacet + facet normal 0.268522 -0.0378816 -0.962528 + outer loop + vertex -314.354 119.297 297.087 + vertex -316.456 122.66 296.369 + vertex -313.923 122.29 297.09 + endloop + endfacet + facet normal 0.269358 -0.0321181 -0.962504 + outer loop + vertex -316.456 122.66 296.369 + vertex -315.739 125.411 296.478 + vertex -313.923 122.29 297.09 + endloop + endfacet + facet normal 0.260163 -0.0379221 -0.96482 + outer loop + vertex -313.923 122.29 297.09 + vertex -315.739 125.411 296.478 + vertex -313.48 125.304 297.091 + endloop + endfacet + facet normal 0.259844 -0.0437115 -0.964661 + outer loop + vertex -315.739 125.411 296.478 + vertex -315.591 128.661 296.37 + vertex -313.48 125.304 297.091 + endloop + endfacet + facet normal 0.269567 -0.0370839 -0.962267 + outer loop + vertex -313.48 125.304 297.091 + vertex -315.591 128.661 296.37 + vertex -313.059 128.337 297.092 + endloop + endfacet + facet normal 0.270008 -0.0336465 -0.96227 + outer loop + vertex -315.591 128.661 296.37 + vertex -314.858 131.412 296.48 + vertex -313.059 128.337 297.092 + endloop + endfacet + facet normal 0.263531 -0.0377603 -0.963912 + outer loop + vertex -313.059 128.337 297.092 + vertex -314.858 131.412 296.48 + vertex -312.626 131.346 297.093 + endloop + endfacet + facet normal 0.263306 -0.0436022 -0.963726 + outer loop + vertex -314.858 131.412 296.48 + vertex -314.732 134.628 296.369 + vertex -312.626 131.346 297.093 + endloop + endfacet + facet normal 0.269998 -0.0389437 -0.962073 + outer loop + vertex -312.626 131.346 297.093 + vertex -314.732 134.628 296.369 + vertex -312.194 134.315 297.094 + endloop + endfacet + facet normal 0.270777 -0.0326567 -0.962088 + outer loop + vertex -314.732 134.628 296.369 + vertex -314.023 137.338 296.476 + vertex -312.194 134.315 297.094 + endloop + endfacet + facet normal 0.26385 -0.0372075 -0.963846 + outer loop + vertex -312.194 134.315 297.094 + vertex -314.023 137.338 296.476 + vertex -311.778 137.244 297.094 + endloop + endfacet + facet normal 0.263487 -0.0445083 -0.963636 + outer loop + vertex -314.023 137.338 296.476 + vertex -313.895 140.489 296.366 + vertex -311.778 137.244 297.094 + endloop + endfacet + facet normal 0.272187 -0.0383488 -0.96148 + outer loop + vertex -311.778 137.244 297.094 + vertex -313.895 140.489 296.366 + vertex -311.367 140.147 297.095 + endloop + endfacet + facet normal 0.272977 -0.0324968 -0.961472 + outer loop + vertex -313.895 140.489 296.366 + vertex -313.197 143.174 296.473 + vertex -311.367 140.147 297.095 + endloop + endfacet + facet normal 0.267211 -0.0362854 -0.962955 + outer loop + vertex -311.367 140.147 297.095 + vertex -313.197 143.174 296.473 + vertex -310.973 143.073 297.094 + endloop + endfacet + facet normal 0.266781 -0.044372 -0.962735 + outer loop + vertex -313.197 143.174 296.473 + vertex -313.071 146.377 296.36 + vertex -310.973 143.073 297.094 + endloop + endfacet + facet normal 0.275845 -0.0381089 -0.960446 + outer loop + vertex -310.973 143.073 297.094 + vertex -313.071 146.377 296.36 + vertex -310.574 146.04 297.091 + endloop + endfacet + facet normal 0.276594 -0.0325333 -0.960436 + outer loop + vertex -313.071 146.377 296.36 + vertex -312.376 149.126 296.468 + vertex -310.574 146.04 297.091 + endloop + endfacet + facet normal 0.268233 -0.0378552 -0.96261 + outer loop + vertex -310.574 146.04 297.091 + vertex -312.376 149.126 296.468 + vertex -310.162 149.037 297.088 + endloop + endfacet + facet normal 0.267953 -0.0436899 -0.962441 + outer loop + vertex -312.376 149.126 296.468 + vertex -312.235 152.374 296.359 + vertex -310.162 149.037 297.088 + endloop + endfacet + facet normal 0.273527 -0.0399195 -0.961035 + outer loop + vertex -310.162 149.037 297.088 + vertex -312.235 152.374 296.359 + vertex -309.743 152.035 297.082 + endloop + endfacet + facet normal 0.274033 -0.0362061 -0.961039 + outer loop + vertex -312.235 152.374 296.359 + vertex -311.477 155.083 296.473 + vertex -309.743 152.035 297.082 + endloop + endfacet + facet normal 0.260423 -0.0446293 -0.964463 + outer loop + vertex -309.743 152.035 297.082 + vertex -311.477 155.083 296.473 + vertex -309.239 154.961 297.083 + endloop + endfacet + facet normal 0.260198 -0.048181 -0.964353 + outer loop + vertex -311.477 155.083 296.473 + vertex -311.24 158.238 296.38 + vertex -309.239 154.961 297.083 + endloop + endfacet + facet normal 0.260649 -0.0478822 -0.964245 + outer loop + vertex -309.239 154.961 297.083 + vertex -311.24 158.238 296.38 + vertex -308.681 157.823 297.092 + endloop + endfacet + facet normal 0.26265 -0.0355269 -0.964237 + outer loop + vertex -311.24 158.238 296.38 + vertex -310.444 160.866 296.5 + vertex -308.681 157.823 297.092 + endloop + endfacet + facet normal 0.262989 -0.0353142 -0.964152 + outer loop + vertex -308.681 157.823 297.092 + vertex -310.444 160.866 296.5 + vertex -308.223 160.733 297.11 + endloop + endfacet + facet normal 0.264407 -0.0123473 -0.964332 + outer loop + vertex -310.444 160.866 296.5 + vertex -310.62 164.192 296.409 + vertex -308.223 160.733 297.11 + endloop + endfacet + facet normal 0.304155 0.0176139 -0.95246 + outer loop + vertex -308.223 160.733 297.11 + vertex -310.62 164.192 296.409 + vertex -308.007 163.899 297.238 + endloop + endfacet + facet normal 0.313001 0.129079 -0.94094 + outer loop + vertex -310.62 164.192 296.409 + vertex -310.46 167.866 296.966 + vertex -308.007 163.899 297.238 + endloop + endfacet + facet normal 0.316644 0.131437 -0.939394 + outer loop + vertex -308.007 163.899 297.238 + vertex -310.46 167.866 296.966 + vertex -307.754 167.169 297.781 + endloop + endfacet + facet normal 0.00629808 -0.553667 -0.832714 + outer loop + vertex -338.962 55.8663 304.087 + vertex -337.107 57.6024 302.947 + vertex -333.857 55.282 304.514 + endloop + endfacet + facet normal 0.00303447 -0.572704 -0.819757 + outer loop + vertex -335.565 53.7047 305.61 + vertex -338.962 55.8663 304.087 + vertex -333.857 55.282 304.514 + endloop + endfacet + facet normal -0.0139226 -0.59037 -0.807012 + outer loop + vertex -340.092 54.3376 305.225 + vertex -338.962 55.8663 304.087 + vertex -335.565 53.7047 305.61 + endloop + endfacet + facet normal 0.00470844 -0.599307 -0.800506 + outer loop + vertex -338.962 55.8663 304.087 + vertex -340.092 54.3376 305.225 + vertex -342.935 55.8179 304.1 + endloop + endfacet + facet normal 0.00467111 -0.596754 -0.802411 + outer loop + vertex -342.935 55.8179 304.1 + vertex -341.179 57.8536 302.596 + vertex -338.962 55.8663 304.087 + endloop + endfacet + facet normal 0.0349628 -0.57448 -0.817771 + outer loop + vertex -338.962 55.8663 304.087 + vertex -341.179 57.8536 302.596 + vertex -337.107 57.6024 302.947 + endloop + endfacet + facet normal 0.0318327 -0.611476 -0.790622 + outer loop + vertex -341.179 57.8536 302.596 + vertex -342.935 55.8179 304.1 + vertex -344.248 57.6591 302.623 + endloop + endfacet + facet normal 0.0302585 -0.588978 -0.807582 + outer loop + vertex -344.248 57.6591 302.623 + vertex -341.798 59.724 301.209 + vertex -341.179 57.8536 302.596 + endloop + endfacet + facet normal 0.0761202 -0.6233 -0.778269 + outer loop + vertex -344.248 57.6591 302.623 + vertex -343.431 59.5064 301.224 + vertex -341.798 59.724 301.209 + endloop + endfacet + facet normal 0.0314791 -0.6124 -0.789921 + outer loop + vertex -346.302 57.4498 302.704 + vertex -343.431 59.5064 301.224 + vertex -344.248 57.6591 302.623 + endloop + endfacet + facet normal 0.166928 -0.718736 -0.674947 + outer loop + vertex -346.302 57.4498 302.704 + vertex -344.117 59.2775 301.298 + vertex -343.431 59.5064 301.224 + endloop + endfacet + facet normal 0.127612 -0.696051 -0.706561 + outer loop + vertex -346.698 57.7132 302.373 + vertex -344.117 59.2775 301.298 + vertex -346.302 57.4498 302.704 + endloop + endfacet + facet normal 0.284824 -0.815775 -0.503376 + outer loop + vertex -346.698 57.7132 302.373 + vertex -344.571 59.1189 301.298 + vertex -344.117 59.2775 301.298 + endloop + endfacet + facet normal 0.353576 -0.843734 -0.403852 + outer loop + vertex -346.221 58.1136 301.953 + vertex -344.571 59.1189 301.298 + vertex -346.698 57.7132 302.373 + endloop + endfacet + facet normal -0.01833 -0.627034 -0.778776 + outer loop + vertex -340.092 54.3376 305.225 + vertex -342.744 53.551 305.921 + vertex -342.935 55.8179 304.1 + endloop + endfacet + facet normal -0.0145756 -0.626881 -0.778979 + outer loop + vertex -342.744 53.551 305.921 + vertex -346.815 55.0018 304.829 + vertex -342.935 55.8179 304.1 + endloop + endfacet + facet normal -0.0250065 -0.613697 -0.789146 + outer loop + vertex -342.744 53.551 305.921 + vertex -340.092 54.3376 305.225 + vertex -337.45 52.3753 306.667 + endloop + endfacet + facet normal -0.0353405 -0.644256 -0.763993 + outer loop + vertex -339.623 51.1738 307.781 + vertex -342.744 53.551 305.921 + vertex -337.45 52.3753 306.667 + endloop + endfacet + facet normal -0.0469704 -0.653115 -0.755801 + outer loop + vertex -345.493 52.2083 307.252 + vertex -342.744 53.551 305.921 + vertex -339.623 51.1738 307.781 + endloop + endfacet + facet normal -0.0590392 -0.548915 -0.833791 + outer loop + vertex -322.003 49.1298 308.232 + vertex -319.575 52.1777 306.053 + vertex -306.602 47.1839 308.422 + endloop + endfacet + facet normal -0.0510163 -0.533145 -0.844484 + outer loop + vertex -306.602 47.1839 308.422 + vertex -319.575 52.1777 306.053 + vertex -305.072 50.429 306.281 + endloop + endfacet + facet normal -0.0614366 -0.529348 -0.846177 + outer loop + vertex -306.602 47.1839 308.422 + vertex -305.072 50.429 306.281 + vertex -290.266 45.2313 308.458 + endloop + endfacet + facet normal -0.0556286 -0.516324 -0.854585 + outer loop + vertex -290.266 45.2313 308.458 + vertex -305.072 50.429 306.281 + vertex -289.253 48.6414 306.331 + endloop + endfacet + facet normal -0.0564103 -0.516132 -0.854649 + outer loop + vertex -290.266 45.2313 308.458 + vertex -289.253 48.6414 306.331 + vertex -272.156 43.2487 308.46 + endloop + endfacet + facet normal -0.0525982 -0.506425 -0.860678 + outer loop + vertex -272.156 43.2487 308.46 + vertex -289.253 48.6414 306.331 + vertex -271.395 46.7714 306.34 + endloop + endfacet + facet normal -0.0510641 -0.506711 -0.860602 + outer loop + vertex -272.156 43.2487 308.46 + vertex -271.395 46.7714 306.34 + vertex -252.15 41.2092 308.473 + endloop + endfacet + facet normal -0.048497 -0.499498 -0.864956 + outer loop + vertex -252.15 41.2092 308.473 + vertex -271.395 46.7714 306.34 + vertex -251.463 44.8089 306.356 + endloop + endfacet + facet normal -0.046475 -0.499835 -0.864873 + outer loop + vertex -252.15 41.2092 308.473 + vertex -251.463 44.8089 306.356 + vertex -230.617 39.1688 308.496 + endloop + endfacet + facet normal -0.0452379 -0.496102 -0.867085 + outer loop + vertex -230.617 39.1688 308.496 + vertex -251.463 44.8089 306.356 + vertex -229.93 42.8127 306.375 + endloop + endfacet + facet normal -0.0445475 -0.496215 -0.867056 + outer loop + vertex -230.617 39.1688 308.496 + vertex -229.93 42.8127 306.375 + vertex -208.397 37.1731 308.496 + endloop + endfacet + facet normal -0.0432132 -0.49204 -0.8695 + outer loop + vertex -208.397 37.1731 308.496 + vertex -229.93 42.8127 306.375 + vertex -207.664 40.8589 306.374 + endloop + endfacet + facet normal -0.0435681 -0.491979 -0.869516 + outer loop + vertex -208.397 37.1731 308.496 + vertex -207.664 40.8589 306.374 + vertex -186.235 35.269 308.463 + endloop + endfacet + facet normal -0.0425731 -0.488843 -0.871332 + outer loop + vertex -186.235 35.269 308.463 + vertex -207.664 40.8589 306.374 + vertex -185.477 38.9903 306.338 + endloop + endfacet + facet normal -0.0428263 -0.488799 -0.871345 + outer loop + vertex -186.235 35.269 308.463 + vertex -185.477 38.9903 306.338 + vertex -164.569 33.4815 308.401 + endloop + endfacet + facet normal -0.0420784 -0.486463 -0.872687 + outer loop + vertex -164.569 33.4815 308.401 + vertex -185.477 38.9903 306.338 + vertex -163.826 37.2361 306.272 + endloop + endfacet + facet normal -0.0408204 -0.486678 -0.872627 + outer loop + vertex -164.569 33.4815 308.401 + vertex -163.826 37.2361 306.272 + vertex -143.494 31.8459 308.327 + endloop + endfacet + facet normal -0.0404547 -0.485545 -0.873275 + outer loop + vertex -143.494 31.8459 308.327 + vertex -163.826 37.2361 306.272 + vertex -142.797 35.624 306.194 + endloop + endfacet + facet normal -0.0370272 -0.486092 -0.873123 + outer loop + vertex -143.494 31.8459 308.327 + vertex -142.797 35.624 306.194 + vertex -122.845 30.3902 308.262 + endloop + endfacet + facet normal -0.0376401 -0.487997 -0.872033 + outer loop + vertex -122.845 30.3902 308.262 + vertex -142.797 35.624 306.194 + vertex -122.214 34.1681 306.121 + endloop + endfacet + facet normal -0.0321614 -0.488787 -0.87181 + outer loop + vertex -122.845 30.3902 308.262 + vertex -122.214 34.1681 306.121 + vertex -102.378 29.1246 308.216 + endloop + endfacet + facet normal -0.0318261 -0.487721 -0.872419 + outer loop + vertex -102.378 29.1246 308.216 + vertex -122.214 34.1681 306.121 + vertex -101.836 32.9187 306.076 + endloop + endfacet + facet normal -0.0252169 -0.488531 -0.872182 + outer loop + vertex -102.378 29.1246 308.216 + vertex -101.836 32.9187 306.076 + vertex -81.9077 28.0904 308.204 + endloop + endfacet + facet normal -0.0259522 -0.490956 -0.870798 + outer loop + vertex -81.9077 28.0904 308.204 + vertex -101.836 32.9187 306.076 + vertex -81.4615 31.8729 306.058 + endloop + endfacet + facet normal -0.0187841 -0.491676 -0.870576 + outer loop + vertex -81.9077 28.0904 308.204 + vertex -81.4615 31.8729 306.058 + vertex -61.3715 27.282 308.217 + endloop + endfacet + facet normal -0.0183813 -0.490286 -0.871368 + outer loop + vertex -61.3715 27.282 308.217 + vertex -81.4615 31.8729 306.058 + vertex -61.0208 31.0739 306.076 + endloop + endfacet + facet normal -0.0124445 -0.490747 -0.871213 + outer loop + vertex -61.3715 27.282 308.217 + vertex -61.0208 31.0739 306.076 + vertex -40.8148 26.7088 308.247 + endloop + endfacet + facet normal -0.0124622 -0.490811 -0.871177 + outer loop + vertex -40.8148 26.7088 308.247 + vertex -61.0208 31.0739 306.076 + vertex -40.5604 30.4991 306.108 + endloop + endfacet + facet normal -0.00681281 -0.491125 -0.871062 + outer loop + vertex -40.8148 26.7088 308.247 + vertex -40.5604 30.4991 306.108 + vertex -20.318 26.3729 308.276 + endloop + endfacet + facet normal -0.00705452 -0.492039 -0.870544 + outer loop + vertex -20.318 26.3729 308.276 + vertex -40.5604 30.4991 306.108 + vertex -20.1578 30.1547 306.137 + endloop + endfacet + facet normal -0.00244808 -0.492198 -0.87048 + outer loop + vertex -20.318 26.3729 308.276 + vertex -20.1578 30.1547 306.137 + vertex 0.0901424 26.2519 308.287 + endloop + endfacet + facet normal -0.00226488 -0.491473 -0.87089 + outer loop + vertex 0.0901424 26.2519 308.287 + vertex -20.1578 30.1547 306.137 + vertex 0.157814 30.0389 306.149 + endloop + endfacet + facet normal 0.00247812 -0.491537 -0.870853 + outer loop + vertex 0.0901424 26.2519 308.287 + vertex 0.157814 30.0389 306.149 + vertex 20.4609 26.3696 308.278 + endloop + endfacet + facet normal 0.0023652 -0.492008 -0.870588 + outer loop + vertex 20.4609 26.3696 308.278 + vertex 0.157814 30.0389 306.149 + vertex 20.4336 30.1538 306.14 + endloop + endfacet + facet normal 0.00689764 -0.491973 -0.870583 + outer loop + vertex 20.4609 26.3696 308.278 + vertex 20.4336 30.1538 306.14 + vertex 40.871 26.704 308.251 + endloop + endfacet + facet normal 0.00713517 -0.490926 -0.871172 + outer loop + vertex 40.871 26.704 308.251 + vertex 20.4336 30.1538 306.14 + vertex 40.7521 30.4978 306.112 + endloop + endfacet + facet normal 0.0123843 -0.490776 -0.871198 + outer loop + vertex 40.871 26.704 308.251 + vertex 40.7521 30.4978 306.112 + vertex 61.3806 27.2749 308.221 + endloop + endfacet + facet normal 0.0123732 -0.490828 -0.871169 + outer loop + vertex 61.3806 27.2749 308.221 + vertex 40.7521 30.4978 306.112 + vertex 61.1679 31.0702 306.08 + endloop + endfacet + facet normal 0.0185675 -0.490517 -0.871234 + outer loop + vertex 61.3806 27.2749 308.221 + vertex 61.1679 31.0702 306.08 + vertex 81.9955 28.0847 308.204 + endloop + endfacet + facet normal 0.0186059 -0.490326 -0.871341 + outer loop + vertex 81.9955 28.0847 308.204 + vertex 61.1679 31.0702 306.08 + vertex 81.6878 31.8814 306.061 + endloop + endfacet + facet normal 0.0253992 -0.489834 -0.871445 + outer loop + vertex 81.9955 28.0847 308.204 + vertex 81.6878 31.8814 306.061 + vertex 102.696 29.1379 308.216 + endloop + endfacet + facet normal 0.0254237 -0.489704 -0.871518 + outer loop + vertex 102.696 29.1379 308.216 + vertex 81.6878 31.8814 306.061 + vertex 102.291 32.9311 306.072 + endloop + endfacet + facet normal 0.032017 -0.489077 -0.871653 + outer loop + vertex 102.696 29.1379 308.216 + vertex 102.291 32.9311 306.072 + vertex 123.464 30.4204 308.259 + endloop + endfacet + facet normal 0.0323438 -0.487217 -0.872682 + outer loop + vertex 123.464 30.4204 308.259 + vertex 102.291 32.9311 306.072 + vertex 122.97 34.2156 306.122 + endloop + endfacet + facet normal 0.0375508 -0.486612 -0.872811 + outer loop + vertex 123.464 30.4204 308.259 + vertex 122.97 34.2156 306.122 + vertex 144.345 31.9096 308.327 + endloop + endfacet + facet normal 0.0374975 -0.486935 -0.872633 + outer loop + vertex 144.345 31.9096 308.327 + vertex 122.97 34.2156 306.122 + vertex 143.774 35.6893 306.193 + endloop + endfacet + facet normal 0.0410239 -0.486462 -0.872738 + outer loop + vertex 144.345 31.9096 308.327 + vertex 143.774 35.6893 306.193 + vertex 165.457 33.5635 308.397 + endloop + endfacet + facet normal 0.041051 -0.486286 -0.872835 + outer loop + vertex 165.457 33.5635 308.397 + vertex 143.774 35.6893 306.193 + vertex 164.841 37.3301 306.27 + endloop + endfacet + facet normal 0.0428507 -0.486025 -0.872894 + outer loop + vertex 165.457 33.5635 308.397 + vertex 164.841 37.3301 306.27 + vertex 186.951 35.3613 308.452 + endloop + endfacet + facet normal 0.0425897 -0.487845 -0.871891 + outer loop + vertex 186.951 35.3613 308.452 + vertex 164.841 37.3301 306.27 + vertex 186.33 39.1026 306.328 + endloop + endfacet + facet normal 0.0439258 -0.487648 -0.871935 + outer loop + vertex 186.951 35.3613 308.452 + vertex 186.33 39.1026 306.328 + vertex 208.861 37.2771 308.484 + endloop + endfacet + facet normal 0.0434896 -0.4909 -0.87013 + outer loop + vertex 208.861 37.2771 308.484 + vertex 186.33 39.1026 306.328 + vertex 208.266 40.9835 306.363 + endloop + endfacet + facet normal 0.0445145 -0.490753 -0.870161 + outer loop + vertex 208.861 37.2771 308.484 + vertex 208.266 40.9835 306.363 + vertex 230.896 39.2432 308.502 + endloop + endfacet + facet normal 0.0438252 -0.496056 -0.867184 + outer loop + vertex 230.896 39.2432 308.502 + vertex 208.266 40.9835 306.363 + vertex 230.336 42.9002 306.382 + endloop + endfacet + facet normal 0.0467336 -0.495655 -0.867261 + outer loop + vertex 230.896 39.2432 308.502 + vertex 230.336 42.9002 306.382 + vertex 252.432 41.2302 308.527 + endloop + endfacet + facet normal 0.0456958 -0.503579 -0.86274 + outer loop + vertex 252.432 41.2302 308.527 + vertex 230.336 42.9002 306.382 + vertex 251.864 44.8154 306.404 + endloop + endfacet + facet normal 0.0503975 -0.50291 -0.862868 + outer loop + vertex 252.432 41.2302 308.527 + vertex 251.864 44.8154 306.404 + vertex 272.68 43.2349 308.541 + endloop + endfacet + facet normal 0.0494042 -0.510239 -0.858612 + outer loop + vertex 272.68 43.2349 308.541 + vertex 251.864 44.8154 306.404 + vertex 271.97 46.7397 306.418 + endloop + endfacet + facet normal 0.0548957 -0.509272 -0.858853 + outer loop + vertex 272.68 43.2349 308.541 + vertex 271.97 46.7397 306.418 + vertex 291.043 45.3386 308.468 + endloop + endfacet + facet normal 0.0536939 -0.518045 -0.853667 + outer loop + vertex 291.043 45.3386 308.468 + vertex 271.97 46.7397 306.418 + vertex 290.051 48.7332 306.345 + endloop + endfacet + facet normal 0.056862 -0.51728 -0.853925 + outer loop + vertex 291.043 45.3386 308.468 + vertex 290.051 48.7332 306.345 + vertex 307.431 47.6052 308.186 + endloop + endfacet + facet normal 0.056537 -0.519812 -0.852408 + outer loop + vertex 307.431 47.6052 308.186 + vertex 290.051 48.7332 306.345 + vertex 305.867 50.9112 306.066 + endloop + endfacet + facet normal 0.0507201 -0.521958 -0.851462 + outer loop + vertex 307.431 47.6052 308.186 + vertex 305.867 50.9112 306.066 + vertex 322.05 50.0056 307.585 + endloop + endfacet + facet normal 0.0502449 -0.526155 -0.848903 + outer loop + vertex 322.05 50.0056 307.585 + vertex 305.867 50.9112 306.066 + vertex 319.662 53.2293 305.446 + endloop + endfacet + facet normal 0.0304763 -0.536931 -0.843075 + outer loop + vertex 322.05 50.0056 307.585 + vertex 319.662 53.2293 305.446 + vertex 329.846 52.1065 306.529 + endloop + endfacet + facet normal 0.0488772 -0.587467 -0.807771 + outer loop + vertex 332.664 50.7959 307.653 + vertex 322.05 50.0056 307.585 + vertex 329.846 52.1065 306.529 + endloop + endfacet + facet normal 0.0378482 -0.602282 -0.797386 + outer loop + vertex 332.664 50.7959 307.653 + vertex 329.846 52.1065 306.529 + vertex 337.774 52.1348 306.884 + endloop + endfacet + facet normal 0.0379165 -0.600012 -0.799092 + outer loop + vertex 337.774 52.1348 306.884 + vertex 329.846 52.1065 306.529 + vertex 335.872 53.5195 305.754 + endloop + endfacet + facet normal 0.0225374 -0.613316 -0.789516 + outer loop + vertex 337.774 52.1348 306.884 + vertex 335.872 53.5195 305.754 + vertex 341.663 53.5451 305.899 + endloop + endfacet + facet normal 0.0227239 -0.600668 -0.799175 + outer loop + vertex 341.663 53.5451 305.899 + vertex 335.872 53.5195 305.754 + vertex 340.123 54.9496 304.8 + endloop + endfacet + facet normal 0.00196138 -0.615062 -0.788476 + outer loop + vertex 341.663 53.5451 305.899 + vertex 340.123 54.9496 304.8 + vertex 347.14 54.9833 304.791 + endloop + endfacet + facet normal 0.00182355 -0.591132 -0.806573 + outer loop + vertex 340.123 54.9496 304.8 + vertex 341.548 56.5947 303.598 + vertex 347.14 54.9833 304.791 + endloop + endfacet + facet normal -0.0112927 -0.583674 -0.81191 + outer loop + vertex 337.324 56.1963 303.943 + vertex 341.548 56.5947 303.598 + vertex 340.123 54.9496 304.8 + endloop + endfacet + facet normal 0.00654563 -0.556589 -0.830762 + outer loop + vertex 340.123 54.9496 304.8 + vertex 333.989 55.0399 304.691 + vertex 337.324 56.1963 303.943 + endloop + endfacet + facet normal 0.00624744 -0.567721 -0.823197 + outer loop + vertex 335.872 53.5195 305.754 + vertex 333.989 55.0399 304.691 + vertex 340.123 54.9496 304.8 + endloop + endfacet + facet normal 0.023629 -0.552955 -0.832876 + outer loop + vertex 335.872 53.5195 305.754 + vertex 329.472 53.7547 305.416 + vertex 333.989 55.0399 304.691 + endloop + endfacet + facet normal 0.0234291 -0.555738 -0.831027 + outer loop + vertex 329.846 52.1065 306.529 + vertex 329.472 53.7547 305.416 + vertex 335.872 53.5195 305.754 + endloop + endfacet + facet normal 0.0272261 -0.555092 -0.831343 + outer loop + vertex 329.472 53.7547 305.416 + vertex 329.846 52.1065 306.529 + vertex 319.662 53.2293 305.446 + endloop + endfacet + facet normal -0.0222606 -0.553978 -0.832233 + outer loop + vertex -335.565 53.7047 305.61 + vertex -333.857 55.282 304.514 + vertex -328.825 52.6989 306.099 + endloop + endfacet + facet normal -0.0173547 -0.607217 -0.794347 + outer loop + vertex -337.45 52.3753 306.667 + vertex -340.092 54.3376 305.225 + vertex -335.565 53.7047 305.61 + endloop + endfacet + facet normal -0.076478 -0.635121 -0.768617 + outer loop + vertex -324.501 46.6107 310.562 + vertex -322.003 49.1298 308.232 + vertex -308.171 44.4451 310.726 + endloop + endfacet + facet normal -0.068531 -0.618996 -0.782398 + outer loop + vertex -308.171 44.4451 310.726 + vertex -322.003 49.1298 308.232 + vertex -306.602 47.1839 308.422 + endloop + endfacet + facet normal -0.0757969 -0.616156 -0.783968 + outer loop + vertex -308.171 44.4451 310.726 + vertex -306.602 47.1839 308.422 + vertex -291.255 42.341 310.745 + endloop + endfacet + facet normal -0.0704757 -0.604028 -0.793841 + outer loop + vertex -291.255 42.341 310.745 + vertex -306.602 47.1839 308.422 + vertex -290.266 45.2313 308.458 + endloop + endfacet + facet normal -0.0691756 -0.604362 -0.793701 + outer loop + vertex -291.255 42.341 310.745 + vertex -290.266 45.2313 308.458 + vertex -272.889 40.2475 310.738 + endloop + endfacet + facet normal -0.0648628 -0.593292 -0.80237 + outer loop + vertex -272.889 40.2475 310.738 + vertex -290.266 45.2313 308.458 + vertex -272.156 43.2487 308.46 + endloop + endfacet + facet normal -0.0620626 -0.593838 -0.802188 + outer loop + vertex -272.889 40.2475 310.738 + vertex -272.156 43.2487 308.46 + vertex -252.801 38.1297 310.752 + endloop + endfacet + facet normal -0.0591426 -0.585598 -0.808441 + outer loop + vertex -252.801 38.1297 310.752 + vertex -272.156 43.2487 308.46 + vertex -252.15 41.2092 308.473 + endloop + endfacet + facet normal -0.0564556 -0.58606 -0.808298 + outer loop + vertex -252.801 38.1297 310.752 + vertex -252.15 41.2092 308.473 + vertex -231.287 36.0258 310.774 + endloop + endfacet + facet normal -0.05399 -0.578591 -0.813829 + outer loop + vertex -231.287 36.0258 310.774 + vertex -252.15 41.2092 308.473 + vertex -230.617 39.1688 308.496 + endloop + endfacet + facet normal -0.0534198 -0.578689 -0.813797 + outer loop + vertex -231.287 36.0258 310.774 + vertex -230.617 39.1688 308.496 + vertex -209.11 33.9757 310.777 + endloop + endfacet + facet normal -0.0513806 -0.572285 -0.818443 + outer loop + vertex -209.11 33.9757 310.777 + vertex -230.617 39.1688 308.496 + vertex -208.397 37.1731 308.496 + endloop + endfacet + facet normal -0.0511433 -0.572328 -0.818429 + outer loop + vertex -209.11 33.9757 310.777 + vertex -208.397 37.1731 308.496 + vertex -186.977 32.0384 310.748 + endloop + endfacet + facet normal -0.0501195 -0.569077 -0.820755 + outer loop + vertex -186.977 32.0384 310.748 + vertex -208.397 37.1731 308.496 + vertex -186.235 35.269 308.463 + endloop + endfacet + facet normal -0.049646 -0.569164 -0.820724 + outer loop + vertex -186.977 32.0384 310.748 + vertex -186.235 35.269 308.463 + vertex -165.316 30.2282 310.693 + endloop + endfacet + facet normal -0.0491974 -0.567748 -0.821731 + outer loop + vertex -165.316 30.2282 310.693 + vertex -186.235 35.269 308.463 + vertex -164.569 33.4815 308.401 + endloop + endfacet + facet normal -0.047062 -0.568137 -0.821587 + outer loop + vertex -165.316 30.2282 310.693 + vertex -164.569 33.4815 308.401 + vertex -144.202 28.5751 310.627 + endloop + endfacet + facet normal -0.046934 -0.567735 -0.821872 + outer loop + vertex -144.202 28.5751 310.627 + vertex -164.569 33.4815 308.401 + vertex -143.494 31.8459 308.327 + endloop + endfacet + facet normal -0.0429969 -0.568411 -0.82162 + outer loop + vertex -144.202 28.5751 310.627 + vertex -143.494 31.8459 308.327 + vertex -123.479 27.0975 310.565 + endloop + endfacet + facet normal -0.0425772 -0.567084 -0.822558 + outer loop + vertex -123.479 27.0975 310.565 + vertex -143.494 31.8459 308.327 + vertex -122.845 30.3902 308.262 + endloop + endfacet + facet normal -0.0366388 -0.567991 -0.822219 + outer loop + vertex -123.479 27.0975 310.565 + vertex -122.845 30.3902 308.262 + vertex -102.926 25.8307 310.524 + endloop + endfacet + facet normal -0.0370236 -0.569236 -0.82134 + outer loop + vertex -102.926 25.8307 310.524 + vertex -122.845 30.3902 308.262 + vertex -102.378 29.1246 308.216 + endloop + endfacet + facet normal -0.0293732 -0.570238 -0.820954 + outer loop + vertex -102.926 25.8307 310.524 + vertex -102.378 29.1246 308.216 + vertex -82.3611 24.79 310.511 + endloop + endfacet + facet normal -0.029302 -0.569998 -0.821123 + outer loop + vertex -82.3611 24.79 310.511 + vertex -102.378 29.1246 308.216 + vertex -81.9077 28.0904 308.204 + endloop + endfacet + facet normal -0.021827 -0.570799 -0.8208 + outer loop + vertex -82.3611 24.79 310.511 + vertex -81.9077 28.0904 308.204 + vertex -61.7275 23.9831 310.524 + endloop + endfacet + facet normal -0.021948 -0.571224 -0.8205 + outer loop + vertex -61.7275 23.9831 310.524 + vertex -81.9077 28.0904 308.204 + vertex -61.3715 27.282 308.217 + endloop + endfacet + facet normal -0.0145561 -0.571838 -0.820237 + outer loop + vertex -61.7275 23.9831 310.524 + vertex -61.3715 27.282 308.217 + vertex -41.0724 23.4177 310.551 + endloop + endfacet + facet normal -0.0148045 -0.572754 -0.819593 + outer loop + vertex -41.0724 23.4177 310.551 + vertex -61.3715 27.282 308.217 + vertex -40.8148 26.7088 308.247 + endloop + endfacet + facet normal -0.00848968 -0.573128 -0.819422 + outer loop + vertex -41.0724 23.4177 310.551 + vertex -40.8148 26.7088 308.247 + vertex -20.4802 23.0762 310.577 + endloop + endfacet + facet normal -0.00821161 -0.572055 -0.820174 + outer loop + vertex -20.4802 23.0762 310.577 + vertex -40.8148 26.7088 308.247 + vertex -20.318 26.3729 308.276 + endloop + endfacet + facet normal -0.00279564 -0.572251 -0.820074 + outer loop + vertex -20.4802 23.0762 310.577 + vertex -20.318 26.3729 308.276 + vertex 0.0240575 22.9601 310.588 + endloop + endfacet + facet normal -0.00295362 -0.57289 -0.819627 + outer loop + vertex 0.0240575 22.9601 310.588 + vertex -20.318 26.3729 308.276 + vertex 0.0901424 26.2519 308.287 + endloop + endfacet + facet normal 0.00294348 -0.572969 -0.819571 + outer loop + vertex 0.0240575 22.9601 310.588 + vertex 0.0901424 26.2519 308.287 + vertex 20.4906 23.0762 310.58 + endloop + endfacet + facet normal 0.00296916 -0.57286 -0.819648 + outer loop + vertex 20.4906 23.0762 310.58 + vertex 0.0901424 26.2519 308.287 + vertex 20.4609 26.3696 308.278 + endloop + endfacet + facet normal 0.00820466 -0.572811 -0.819646 + outer loop + vertex 20.4906 23.0762 310.58 + vertex 20.4609 26.3696 308.278 + vertex 40.9956 23.4059 310.555 + endloop + endfacet + facet normal 0.00828386 -0.572454 -0.819895 + outer loop + vertex 40.9956 23.4059 310.555 + vertex 20.4609 26.3696 308.278 + vertex 40.871 26.704 308.251 + endloop + endfacet + facet normal 0.0145896 -0.572252 -0.819948 + outer loop + vertex 40.9956 23.4059 310.555 + vertex 40.871 26.704 308.251 + vertex 61.5999 23.9714 310.527 + endloop + endfacet + facet normal 0.0147106 -0.57167 -0.820351 + outer loop + vertex 61.5999 23.9714 310.527 + vertex 40.871 26.704 308.251 + vertex 61.3806 27.2749 308.221 + endloop + endfacet + facet normal 0.0220439 -0.571266 -0.820469 + outer loop + vertex 61.5999 23.9714 310.527 + vertex 61.3806 27.2749 308.221 + vertex 82.3157 24.7897 310.514 + endloop + endfacet + facet normal 0.021825 -0.572391 -0.81969 + outer loop + vertex 82.3157 24.7897 310.514 + vertex 61.3806 27.2749 308.221 + vertex 81.9955 28.0847 308.204 + endloop + endfacet + facet normal 0.0293053 -0.571793 -0.819874 + outer loop + vertex 82.3157 24.7897 310.514 + vertex 81.9955 28.0847 308.204 + vertex 103.111 25.8414 310.524 + endloop + endfacet + facet normal 0.0294898 -0.570779 -0.820574 + outer loop + vertex 103.111 25.8414 310.524 + vertex 81.9955 28.0847 308.204 + vertex 102.696 29.1379 308.216 + endloop + endfacet + facet normal 0.0365676 -0.570045 -0.820799 + outer loop + vertex 103.111 25.8414 310.524 + vertex 102.696 29.1379 308.216 + vertex 123.971 27.1241 310.562 + endloop + endfacet + facet normal 0.0368212 -0.568555 -0.821821 + outer loop + vertex 123.971 27.1241 310.562 + vertex 102.696 29.1379 308.216 + vertex 123.464 30.4204 308.259 + endloop + endfacet + facet normal 0.0428522 -0.567793 -0.822055 + outer loop + vertex 123.971 27.1241 310.562 + vertex 123.464 30.4204 308.259 + vertex 144.923 28.6171 310.623 + endloop + endfacet + facet normal 0.0430774 -0.566377 -0.823019 + outer loop + vertex 144.923 28.6171 310.623 + vertex 123.464 30.4204 308.259 + vertex 144.345 31.9096 308.327 + endloop + endfacet + facet normal 0.047166 -0.565787 -0.823202 + outer loop + vertex 144.923 28.6171 310.623 + vertex 144.345 31.9096 308.327 + vertex 166.072 30.2854 310.688 + endloop + endfacet + facet normal 0.0471042 -0.566203 -0.822919 + outer loop + vertex 166.072 30.2854 310.688 + vertex 144.345 31.9096 308.327 + vertex 165.457 33.5635 308.397 + endloop + endfacet + facet normal 0.0501161 -0.565737 -0.823062 + outer loop + vertex 166.072 30.2854 310.688 + vertex 165.457 33.5635 308.397 + vertex 187.569 32.1157 310.739 + endloop + endfacet + facet normal 0.0496624 -0.569032 -0.820814 + outer loop + vertex 187.569 32.1157 310.739 + vertex 165.457 33.5635 308.397 + vertex 186.951 35.3613 308.452 + endloop + endfacet + facet normal 0.0516001 -0.568727 -0.820906 + outer loop + vertex 187.569 32.1157 310.739 + vertex 186.951 35.3613 308.452 + vertex 209.436 34.06 310.767 + endloop + endfacet + facet normal 0.0512053 -0.571796 -0.818796 + outer loop + vertex 209.436 34.06 310.767 + vertex 186.951 35.3613 308.452 + vertex 208.861 37.2771 308.484 + endloop + endfacet + facet normal 0.053302 -0.571482 -0.818882 + outer loop + vertex 209.436 34.06 310.767 + vertex 208.861 37.2771 308.484 + vertex 231.432 36.0852 310.785 + endloop + endfacet + facet normal 0.0523535 -0.57914 -0.813545 + outer loop + vertex 231.432 36.0852 310.785 + vertex 208.861 37.2771 308.484 + vertex 230.896 39.2432 308.502 + endloop + endfacet + facet normal 0.0562857 -0.578574 -0.813685 + outer loop + vertex 231.432 36.0852 310.785 + vertex 230.896 39.2432 308.502 + vertex 252.979 38.1448 310.811 + endloop + endfacet + facet normal 0.0551554 -0.587685 -0.807208 + outer loop + vertex 252.979 38.1448 310.811 + vertex 230.896 39.2432 308.502 + vertex 252.432 41.2302 308.527 + endloop + endfacet + facet normal 0.0612891 -0.586765 -0.807435 + outer loop + vertex 252.979 38.1448 310.811 + vertex 252.432 41.2302 308.527 + vertex 273.339 40.2479 310.828 + endloop + endfacet + facet normal 0.0598082 -0.598414 -0.798951 + outer loop + vertex 273.339 40.2479 310.828 + vertex 252.432 41.2302 308.527 + vertex 272.68 43.2349 308.541 + endloop + endfacet + facet normal 0.0671687 -0.597097 -0.799352 + outer loop + vertex 273.339 40.2479 310.828 + vertex 272.68 43.2349 308.541 + vertex 292.032 42.4485 310.755 + endloop + endfacet + facet normal 0.0661487 -0.605207 -0.793315 + outer loop + vertex 292.032 42.4485 310.755 + vertex 272.68 43.2349 308.541 + vertex 291.043 45.3386 308.468 + endloop + endfacet + facet normal 0.0718998 -0.603732 -0.793938 + outer loop + vertex 292.032 42.4485 310.755 + vertex 291.043 45.3386 308.468 + vertex 308.956 44.8438 310.466 + endloop + endfacet + facet normal 0.0710277 -0.611505 -0.788046 + outer loop + vertex 308.956 44.8438 310.466 + vertex 291.043 45.3386 308.468 + vertex 307.431 47.6052 308.186 + endloop + endfacet + facet normal 0.0696233 -0.612041 -0.787756 + outer loop + vertex 308.956 44.8438 310.466 + vertex 307.431 47.6052 308.186 + vertex 324.366 47.3732 309.863 + endloop + endfacet + facet normal 0.0691519 -0.617256 -0.783718 + outer loop + vertex 324.366 47.3732 309.863 + vertex 307.431 47.6052 308.186 + vertex 322.05 50.0056 307.585 + endloop + endfacet + facet normal 0.0553976 -0.624987 -0.778667 + outer loop + vertex 324.366 47.3732 309.863 + vertex 322.05 50.0056 307.585 + vertex 332.831 49.4317 308.813 + endloop + endfacet + facet normal 0.0725568 -0.673569 -0.735555 + outer loop + vertex 335.684 48.4665 309.978 + vertex 324.366 47.3732 309.863 + vertex 332.831 49.4317 308.813 + endloop + endfacet + facet normal 0.0662565 -0.682695 -0.727693 + outer loop + vertex 335.684 48.4665 309.978 + vertex 332.831 49.4317 308.813 + vertex 341.369 49.7972 309.247 + endloop + endfacet + facet normal 0.0662468 -0.684608 -0.725895 + outer loop + vertex 341.369 49.7972 309.247 + vertex 332.831 49.4317 308.813 + vertex 339.569 50.8822 308.06 + endloop + endfacet + facet normal 0.0573228 -0.692265 -0.719363 + outer loop + vertex 341.369 49.7972 309.247 + vertex 339.569 50.8822 308.06 + vertex 345.837 51.1314 308.32 + endloop + endfacet + facet normal 0.0573203 -0.684192 -0.727046 + outer loop + vertex 345.837 51.1314 308.32 + vertex 339.569 50.8822 308.06 + vertex 344.585 52.4483 306.982 + endloop + endfacet + facet normal 0.0459543 -0.690115 -0.722239 + outer loop + vertex 345.837 51.1314 308.32 + vertex 344.585 52.4483 306.982 + vertex 351.975 52.4331 307.466 + endloop + endfacet + facet normal 0.0466246 -0.679569 -0.732129 + outer loop + vertex 347.14 54.9833 304.791 + vertex 351.975 52.4331 307.466 + vertex 344.585 52.4483 306.982 + endloop + endfacet + facet normal 0.0248231 -0.667796 -0.74393 + outer loop + vertex 341.663 53.5451 305.899 + vertex 347.14 54.9833 304.791 + vertex 344.585 52.4483 306.982 + endloop + endfacet + facet normal 0.0406067 -0.644816 -0.763259 + outer loop + vertex 344.585 52.4483 306.982 + vertex 337.774 52.1348 306.884 + vertex 341.663 53.5451 305.899 + endloop + endfacet + facet normal 0.0408523 -0.652089 -0.757041 + outer loop + vertex 339.569 50.8822 308.06 + vertex 337.774 52.1348 306.884 + vertex 344.585 52.4483 306.982 + endloop + endfacet + facet normal 0.0531177 -0.641919 -0.76493 + outer loop + vertex 339.569 50.8822 308.06 + vertex 332.664 50.7959 307.653 + vertex 337.774 52.1348 306.884 + endloop + endfacet + facet normal 0.0530722 -0.643151 -0.763898 + outer loop + vertex 332.831 49.4317 308.813 + vertex 332.664 50.7959 307.653 + vertex 339.569 50.8822 308.06 + endloop + endfacet + facet normal 0.0527463 -0.643185 -0.763892 + outer loop + vertex 332.664 50.7959 307.653 + vertex 332.831 49.4317 308.813 + vertex 322.05 50.0056 307.585 + endloop + endfacet + facet normal -0.0486468 -0.630261 -0.774858 + outer loop + vertex -339.623 51.1738 307.781 + vertex -337.45 52.3753 306.667 + vertex -332.103 49.9106 308.336 + endloop + endfacet + facet normal -0.0542134 -0.681109 -0.730172 + outer loop + vertex -341.544 49.9756 309.041 + vertex -345.493 52.2083 307.252 + vertex -339.623 51.1738 307.781 + endloop + endfacet + facet normal -0.0645064 -0.691079 -0.719895 + outer loop + vertex -346.933 50.7917 308.741 + vertex -345.493 52.2083 307.252 + vertex -341.544 49.9756 309.041 + endloop + endfacet + facet normal -0.0708493 -0.721504 -0.688776 + outer loop + vertex -343.415 48.9733 310.284 + vertex -346.933 50.7917 308.741 + vertex -341.544 49.9756 309.041 + endloop + endfacet + facet normal -0.0821059 -0.732379 -0.675929 + outer loop + vertex -349.617 50.0802 309.838 + vertex -346.933 50.7917 308.741 + vertex -343.415 48.9733 310.284 + endloop + endfacet + facet normal -0.0844171 -0.72894 -0.679353 + outer loop + vertex -346.933 50.7917 308.741 + vertex -349.617 50.0802 309.838 + vertex -350.971 52.4741 307.437 + endloop + endfacet + facet normal -0.0871912 -0.729526 -0.678372 + outer loop + vertex -355.646 50.6073 310.046 + vertex -350.971 52.4741 307.437 + vertex -349.617 50.0802 309.838 + endloop + endfacet + facet normal -0.089025 -0.767841 -0.634424 + outer loop + vertex -349.617 50.0802 309.838 + vertex -351.057 49.0731 311.259 + vertex -355.646 50.6073 310.046 + endloop + endfacet + facet normal -0.094228 -0.764694 -0.637467 + outer loop + vertex -351.057 49.0731 311.259 + vertex -349.617 50.0802 309.838 + vertex -345.25 48.1414 311.518 + endloop + endfacet + facet normal -0.100156 -0.791883 -0.602403 + outer loop + vertex -347.126 47.4287 312.767 + vertex -351.057 49.0731 311.259 + vertex -345.25 48.1414 311.518 + endloop + endfacet + facet normal -0.105986 -0.79775 -0.593601 + outer loop + vertex -353.833 48.6226 312.36 + vertex -351.057 49.0731 311.259 + vertex -347.126 47.4287 312.767 + endloop + endfacet + facet normal -0.107886 -0.794811 -0.59719 + outer loop + vertex -351.057 49.0731 311.259 + vertex -353.833 48.6226 312.36 + vertex -355.646 50.6073 310.046 + endloop + endfacet + facet normal -0.10836 -0.794941 -0.596931 + outer loop + vertex -360.22 49.2973 312.621 + vertex -355.646 50.6073 310.046 + vertex -353.833 48.6226 312.36 + endloop + endfacet + facet normal -0.109393 -0.816131 -0.567419 + outer loop + vertex -353.833 48.6226 312.36 + vertex -355.172 47.8236 313.767 + vertex -360.22 49.2973 312.621 + endloop + endfacet + facet normal -0.112291 -0.814471 -0.569234 + outer loop + vertex -355.172 47.8236 313.767 + vertex -353.833 48.6226 312.36 + vertex -348.934 46.7884 314.018 + endloop + endfacet + facet normal -0.114754 -0.825339 -0.552854 + outer loop + vertex -350.699 46.1994 315.263 + vertex -355.172 47.8236 313.767 + vertex -348.934 46.7884 314.018 + endloop + endfacet + facet normal -0.122584 -0.833669 -0.538488 + outer loop + vertex -357.95 47.5176 314.873 + vertex -355.172 47.8236 313.767 + vertex -350.699 46.1994 315.263 + endloop + endfacet + facet normal -0.121799 -0.834845 -0.536841 + outer loop + vertex -355.172 47.8236 313.767 + vertex -357.95 47.5176 314.873 + vertex -360.22 49.2973 312.621 + endloop + endfacet + facet normal -0.138789 -0.840311 -0.524037 + outer loop + vertex -365.023 48.4576 315.239 + vertex -360.22 49.2973 312.621 + vertex -357.95 47.5176 314.873 + endloop + endfacet + facet normal -0.139568 -0.857212 -0.49569 + outer loop + vertex -357.95 47.5176 314.873 + vertex -359.391 46.8738 316.392 + vertex -365.023 48.4576 315.239 + endloop + endfacet + facet normal -0.135828 -0.859337 -0.493042 + outer loop + vertex -359.391 46.8738 316.392 + vertex -357.95 47.5176 314.873 + vertex -352.31 45.6388 316.594 + endloop + endfacet + facet normal -0.12695 -0.849752 -0.511669 + outer loop + vertex -352.31 45.6388 316.594 + vertex -357.95 47.5176 314.873 + vertex -350.699 46.1994 315.263 + endloop + endfacet + facet normal -0.128481 -0.848677 -0.513069 + outer loop + vertex -352.31 45.6388 316.594 + vertex -350.699 46.1994 315.263 + vertex -344.203 44.2782 316.815 + endloop + endfacet + facet normal -0.121378 -0.838857 -0.530647 + outer loop + vertex -344.203 44.2782 316.815 + vertex -350.699 46.1994 315.263 + vertex -341.339 44.5761 315.689 + endloop + endfacet + facet normal -0.109214 -0.870697 -0.47954 + outer loop + vertex -365.023 48.4576 315.239 + vertex -366.846 50.0829 312.703 + vertex -360.22 49.2973 312.621 + endloop + endfacet + facet normal -0.134664 -0.875401 -0.464261 + outer loop + vertex -372.282 49.5969 315.197 + vertex -366.846 50.0829 312.703 + vertex -365.023 48.4576 315.239 + endloop + endfacet + facet normal -0.0766053 -0.827065 -0.556862 + outer loop + vertex -360.22 49.2973 312.621 + vertex -362.456 51.3693 309.851 + vertex -355.646 50.6073 310.046 + endloop + endfacet + facet normal -0.105766 -0.835319 -0.539496 + outer loop + vertex -366.846 50.0829 312.703 + vertex -362.456 51.3693 309.851 + vertex -360.22 49.2973 312.621 + endloop + endfacet + facet normal -0.0466891 -0.770819 -0.635341 + outer loop + vertex -355.646 50.6073 310.046 + vertex -356.658 52.9522 307.275 + vertex -350.971 52.4741 307.437 + endloop + endfacet + facet normal -0.0685488 -0.773718 -0.629811 + outer loop + vertex -362.456 51.3693 309.851 + vertex -356.658 52.9522 307.275 + vertex -355.646 50.6073 310.046 + endloop + endfacet + facet normal -0.0579856 -0.694661 -0.716996 + outer loop + vertex -345.493 52.2083 307.252 + vertex -346.933 50.7917 308.741 + vertex -350.971 52.4741 307.437 + endloop + endfacet + facet normal -0.0575622 -0.669477 -0.740599 + outer loop + vertex -350.971 52.4741 307.437 + vertex -346.815 55.0018 304.829 + vertex -345.493 52.2083 307.252 + endloop + endfacet + facet normal -0.0367702 -0.664586 -0.746307 + outer loop + vertex -342.744 53.551 305.921 + vertex -345.493 52.2083 307.252 + vertex -346.815 55.0018 304.829 + endloop + endfacet + facet normal -0.00792857 -0.711706 -0.702433 + outer loop + vertex -350.971 52.4741 307.437 + vertex -350.771 55.4629 304.407 + vertex -346.815 55.0018 304.829 + endloop + endfacet + facet normal -0.039659 -0.71012 -0.702963 + outer loop + vertex -356.658 52.9522 307.275 + vertex -350.771 55.4629 304.407 + vertex -350.971 52.4741 307.437 + endloop + endfacet + facet normal -0.0947853 -0.717409 -0.690174 + outer loop + vertex -326.875 44.594 312.984 + vertex -324.501 46.6107 310.562 + vertex -309.621 42.1696 313.135 + endloop + endfacet + facet normal -0.0853983 -0.69801 -0.710977 + outer loop + vertex -309.621 42.1696 313.135 + vertex -324.501 46.6107 310.562 + vertex -308.171 44.4451 310.726 + endloop + endfacet + facet normal -0.090176 -0.696208 -0.712153 + outer loop + vertex -309.621 42.1696 313.135 + vertex -308.171 44.4451 310.726 + vertex -292.095 39.8914 313.143 + endloop + endfacet + facet normal -0.0840716 -0.682182 -0.726333 + outer loop + vertex -292.095 39.8914 313.143 + vertex -308.171 44.4451 310.726 + vertex -291.255 42.341 310.745 + endloop + endfacet + facet normal -0.0813255 -0.682832 -0.726035 + outer loop + vertex -292.095 39.8914 313.143 + vertex -291.255 42.341 310.745 + vertex -273.444 37.6857 313.128 + endloop + endfacet + facet normal -0.0767729 -0.671184 -0.737304 + outer loop + vertex -273.444 37.6857 313.128 + vertex -291.255 42.341 310.745 + vertex -272.889 40.2475 310.738 + endloop + endfacet + facet normal -0.0726838 -0.671872 -0.737093 + outer loop + vertex -273.444 37.6857 313.128 + vertex -272.889 40.2475 310.738 + vertex -253.279 35.4924 313.139 + endloop + endfacet + facet normal -0.0693395 -0.662499 -0.745847 + outer loop + vertex -253.279 35.4924 313.139 + vertex -272.889 40.2475 310.738 + vertex -252.801 38.1297 310.752 + endloop + endfacet + facet normal -0.066256 -0.662949 -0.745727 + outer loop + vertex -253.279 35.4924 313.139 + vertex -252.801 38.1297 310.752 + vertex -231.805 33.3215 313.161 + endloop + endfacet + facet normal -0.0631067 -0.653492 -0.754298 + outer loop + vertex -231.805 33.3215 313.161 + vertex -252.801 38.1297 310.752 + vertex -231.287 36.0258 310.774 + endloop + endfacet + facet normal -0.0615929 -0.653719 -0.754227 + outer loop + vertex -231.805 33.3215 313.161 + vertex -231.287 36.0258 310.774 + vertex -209.673 31.2292 313.167 + endloop + endfacet + facet normal -0.05986 -0.648303 -0.759025 + outer loop + vertex -209.673 31.2292 313.167 + vertex -231.287 36.0258 310.774 + vertex -209.11 33.9757 310.777 + endloop + endfacet + facet normal -0.0591952 -0.648407 -0.758989 + outer loop + vertex -209.673 31.2292 313.167 + vertex -209.11 33.9757 310.777 + vertex -187.58 29.2423 313.141 + endloop + endfacet + facet normal -0.0571734 -0.641999 -0.76457 + outer loop + vertex -187.58 29.2423 313.141 + vertex -209.11 33.9757 310.777 + vertex -186.977 32.0384 310.748 + endloop + endfacet + facet normal -0.0564382 -0.642119 -0.764525 + outer loop + vertex -187.58 29.2423 313.141 + vertex -186.977 32.0384 310.748 + vertex -165.919 27.3985 313.091 + endloop + endfacet + facet normal -0.0553087 -0.638543 -0.767596 + outer loop + vertex -165.919 27.3985 313.091 + vertex -186.977 32.0384 310.748 + vertex -165.316 30.2282 310.693 + endloop + endfacet + facet normal -0.0526041 -0.638975 -0.767427 + outer loop + vertex -165.919 27.3985 313.091 + vertex -165.316 30.2282 310.693 + vertex -144.772 25.7289 313.031 + endloop + endfacet + facet normal -0.0523858 -0.638284 -0.768016 + outer loop + vertex -144.772 25.7289 313.031 + vertex -165.316 30.2282 310.693 + vertex -144.202 28.5751 310.627 + endloop + endfacet + facet normal -0.0475397 -0.63901 -0.767728 + outer loop + vertex -144.772 25.7289 313.031 + vertex -144.202 28.5751 310.627 + vertex -123.985 24.2481 312.977 + endloop + endfacet + facet normal -0.0479617 -0.640357 -0.766578 + outer loop + vertex -123.985 24.2481 312.977 + vertex -144.202 28.5751 310.627 + vertex -123.479 27.0975 310.565 + endloop + endfacet + facet normal -0.0409047 -0.641293 -0.766205 + outer loop + vertex -123.985 24.2481 312.977 + vertex -123.479 27.0975 310.565 + vertex -103.346 22.9761 312.939 + endloop + endfacet + facet normal -0.0410801 -0.641867 -0.765715 + outer loop + vertex -103.346 22.9761 312.939 + vertex -123.479 27.0975 310.565 + vertex -102.926 25.8307 310.524 + endloop + endfacet + facet normal -0.0329809 -0.642759 -0.765359 + outer loop + vertex -103.346 22.9761 312.939 + vertex -102.926 25.8307 310.524 + vertex -82.6892 21.9314 312.927 + endloop + endfacet + facet normal -0.033014 -0.642871 -0.765263 + outer loop + vertex -82.6892 21.9314 312.927 + vertex -102.926 25.8307 310.524 + vertex -82.3611 24.79 310.511 + endloop + endfacet + facet normal -0.0245299 -0.643598 -0.76497 + outer loop + vertex -82.6892 21.9314 312.927 + vertex -82.3611 24.79 310.511 + vertex -61.9591 21.1277 312.938 + endloop + endfacet + facet normal -0.0247369 -0.644335 -0.764343 + outer loop + vertex -61.9591 21.1277 312.938 + vertex -82.3611 24.79 310.511 + vertex -61.7275 23.9831 310.524 + endloop + endfacet + facet normal -0.016484 -0.644836 -0.764143 + outer loop + vertex -61.9591 21.1277 312.938 + vertex -61.7275 23.9831 310.524 + vertex -41.206 20.567 312.964 + endloop + endfacet + facet normal -0.0166466 -0.645443 -0.763627 + outer loop + vertex -41.206 20.567 312.964 + vertex -61.7275 23.9831 310.524 + vertex -41.0724 23.4177 310.551 + endloop + endfacet + facet normal -0.00987948 -0.645686 -0.763539 + outer loop + vertex -41.206 20.567 312.964 + vertex -41.0724 23.4177 310.551 + vertex -20.5189 20.2241 312.986 + endloop + endfacet + facet normal -0.0097533 -0.645193 -0.763957 + outer loop + vertex -20.5189 20.2241 312.986 + vertex -41.0724 23.4177 310.551 + vertex -20.4802 23.0762 310.577 + endloop + endfacet + facet normal -0.00293735 -0.645275 -0.763945 + outer loop + vertex -20.5189 20.2241 312.986 + vertex -20.4802 23.0762 310.577 + vertex 0.0840002 20.1171 312.997 + endloop + endfacet + facet normal -0.00324752 -0.646548 -0.762866 + outer loop + vertex 0.0840002 20.1171 312.997 + vertex -20.4802 23.0762 310.577 + vertex 0.0240575 22.9601 310.588 + endloop + endfacet + facet normal 0.00300891 -0.646472 -0.762932 + outer loop + vertex 0.0840002 20.1171 312.997 + vertex 0.0240575 22.9601 310.588 + vertex 20.6425 20.2224 312.989 + endloop + endfacet + facet normal 0.00337222 -0.6449 -0.764259 + outer loop + vertex 20.6425 20.2224 312.989 + vertex 0.0240575 22.9601 310.588 + vertex 20.4906 23.0762 310.58 + endloop + endfacet + facet normal 0.0097776 -0.644674 -0.764395 + outer loop + vertex 20.6425 20.2224 312.989 + vertex 20.4906 23.0762 310.58 + vertex 41.247 20.5603 312.967 + endloop + endfacet + facet normal 0.00945352 -0.64616 -0.763143 + outer loop + vertex 41.247 20.5603 312.967 + vertex 20.4906 23.0762 310.58 + vertex 40.9956 23.4059 310.555 + endloop + endfacet + facet normal 0.0166002 -0.645732 -0.763383 + outer loop + vertex 41.247 20.5603 312.967 + vertex 40.9956 23.4059 310.555 + vertex 61.9455 21.1225 312.942 + endloop + endfacet + facet normal 0.0166729 -0.645377 -0.763682 + outer loop + vertex 61.9455 21.1225 312.942 + vertex 40.9956 23.4059 310.555 + vertex 61.5999 23.9714 310.527 + endloop + endfacet + facet normal 0.0247724 -0.644696 -0.764037 + outer loop + vertex 61.9455 21.1225 312.942 + vertex 61.5999 23.9714 310.527 + vertex 82.7576 21.9373 312.929 + endloop + endfacet + facet normal 0.0249446 -0.643795 -0.764791 + outer loop + vertex 82.7576 21.9373 312.929 + vertex 61.5999 23.9714 310.527 + vertex 82.3157 24.7897 310.514 + endloop + endfacet + facet normal 0.0327731 -0.642941 -0.765214 + outer loop + vertex 82.7576 21.9373 312.929 + vertex 82.3157 24.7897 310.514 + vertex 103.649 22.9916 312.938 + endloop + endfacet + facet normal 0.0328546 -0.642485 -0.765593 + outer loop + vertex 103.649 22.9916 312.938 + vertex 82.3157 24.7897 310.514 + vertex 103.111 25.8414 310.524 + endloop + endfacet + facet normal 0.0407408 -0.641427 -0.766101 + outer loop + vertex 103.649 22.9916 312.938 + vertex 103.111 25.8414 310.524 + vertex 124.599 24.2807 312.973 + endloop + endfacet + facet normal 0.0408258 -0.640918 -0.766523 + outer loop + vertex 124.599 24.2807 312.973 + vertex 103.111 25.8414 310.524 + vertex 123.971 27.1241 310.562 + endloop + endfacet + facet normal 0.0475996 -0.639849 -0.767025 + outer loop + vertex 124.599 24.2807 312.973 + vertex 123.971 27.1241 310.562 + vertex 145.619 25.7795 313.027 + endloop + endfacet + facet normal 0.0477568 -0.63884 -0.767856 + outer loop + vertex 145.619 25.7795 313.027 + vertex 123.971 27.1241 310.562 + vertex 144.923 28.6171 310.623 + endloop + endfacet + facet normal 0.0531906 -0.637881 -0.768296 + outer loop + vertex 145.619 25.7795 313.027 + vertex 144.923 28.6171 310.623 + vertex 166.807 27.473 313.088 + endloop + endfacet + facet normal 0.0528587 -0.64017 -0.766413 + outer loop + vertex 166.807 27.473 313.088 + vertex 144.923 28.6171 310.623 + vertex 166.072 30.2854 310.688 + endloop + endfacet + facet normal 0.0568489 -0.639419 -0.766754 + outer loop + vertex 166.807 27.473 313.088 + vertex 166.072 30.2854 310.688 + vertex 188.287 29.327 313.135 + endloop + endfacet + facet normal 0.056483 -0.642144 -0.7645 + outer loop + vertex 188.287 29.327 313.135 + vertex 166.072 30.2854 310.688 + vertex 187.569 32.1157 310.739 + endloop + endfacet + facet normal 0.0591184 -0.641651 -0.764715 + outer loop + vertex 188.287 29.327 313.135 + vertex 187.569 32.1157 310.739 + vertex 210.102 31.3079 313.159 + endloop + endfacet + facet normal 0.0584683 -0.646829 -0.760391 + outer loop + vertex 210.102 31.3079 313.159 + vertex 187.569 32.1157 310.739 + vertex 209.436 34.06 310.767 + endloop + endfacet + facet normal 0.0618253 -0.64623 -0.760635 + outer loop + vertex 210.102 31.3079 313.159 + vertex 209.436 34.06 310.767 + vertex 232.046 33.3887 313.175 + endloop + endfacet + facet normal 0.0608655 -0.654221 -0.75385 + outer loop + vertex 232.046 33.3887 313.175 + vertex 209.436 34.06 310.767 + vertex 231.432 36.0852 310.785 + endloop + endfacet + facet normal 0.0659811 -0.653347 -0.754178 + outer loop + vertex 232.046 33.3887 313.175 + vertex 231.432 36.0852 310.785 + vertex 253.583 35.5329 313.201 + endloop + endfacet + facet normal 0.0645165 -0.665566 -0.743545 + outer loop + vertex 253.583 35.5329 313.201 + vertex 231.432 36.0852 310.785 + vertex 252.979 38.1448 310.811 + endloop + endfacet + facet normal 0.0717915 -0.664306 -0.744005 + outer loop + vertex 253.583 35.5329 313.201 + vertex 252.979 38.1448 310.811 + vertex 274.068 37.7251 313.221 + endloop + endfacet + facet normal 0.0704075 -0.675635 -0.733866 + outer loop + vertex 274.068 37.7251 313.221 + vertex 252.979 38.1448 310.811 + vertex 273.339 40.2479 310.828 + endloop + endfacet + facet normal 0.0792694 -0.673809 -0.734641 + outer loop + vertex 274.068 37.7251 313.221 + vertex 273.339 40.2479 310.828 + vertex 293.059 40.0342 313.152 + endloop + endfacet + facet normal 0.0778734 -0.685524 -0.723873 + outer loop + vertex 293.059 40.0342 313.152 + vertex 273.339 40.2479 310.828 + vertex 292.032 42.4485 310.755 + endloop + endfacet + facet normal 0.0864193 -0.683152 -0.725145 + outer loop + vertex 293.059 40.0342 313.152 + vertex 292.032 42.4485 310.755 + vertex 310.518 42.55 312.862 + endloop + endfacet + facet normal 0.0855934 -0.69127 -0.717509 + outer loop + vertex 310.518 42.55 312.862 + vertex 292.032 42.4485 310.755 + vertex 308.956 44.8438 310.466 + endloop + endfacet + facet normal 0.0875269 -0.690492 -0.718025 + outer loop + vertex 310.518 42.55 312.862 + vertex 308.956 44.8438 310.466 + vertex 326.69 45.2406 312.246 + endloop + endfacet + facet normal 0.0869088 -0.698804 -0.710014 + outer loop + vertex 326.69 45.2406 312.246 + vertex 308.956 44.8438 310.466 + vertex 324.366 47.3732 309.863 + endloop + endfacet + facet normal 0.0784782 -0.703687 -0.706163 + outer loop + vertex 326.69 45.2406 312.246 + vertex 324.366 47.3732 309.863 + vertex 335.76 47.3312 311.171 + endloop + endfacet + facet normal 0.0939922 -0.746557 -0.658649 + outer loop + vertex 338.728 46.6263 312.394 + vertex 326.69 45.2406 312.246 + vertex 335.76 47.3312 311.171 + endloop + endfacet + facet normal 0.0913781 -0.750469 -0.654558 + outer loop + vertex 338.728 46.6263 312.394 + vertex 335.76 47.3312 311.171 + vertex 344.922 48.0203 311.66 + endloop + endfacet + facet normal 0.0914505 -0.755879 -0.648293 + outer loop + vertex 344.922 48.0203 311.66 + vertex 335.76 47.3312 311.171 + vertex 343.14 48.8535 310.437 + endloop + endfacet + facet normal 0.0853258 -0.761138 -0.642953 + outer loop + vertex 344.922 48.0203 311.66 + vertex 343.14 48.8535 310.437 + vertex 350.08 49.3627 310.755 + endloop + endfacet + facet normal 0.0852083 -0.755103 -0.650046 + outer loop + vertex 350.08 49.3627 310.755 + vertex 343.14 48.8535 310.437 + vertex 348.938 50.3616 309.445 + endloop + endfacet + facet normal 0.0761063 -0.759795 -0.645693 + outer loop + vertex 350.08 49.3627 310.755 + vertex 348.938 50.3616 309.445 + vertex 357.858 50.8127 309.966 + endloop + endfacet + facet normal 0.0763492 -0.745032 -0.662645 + outer loop + vertex 351.975 52.4331 307.466 + vertex 357.858 50.8127 309.966 + vertex 348.938 50.3616 309.445 + endloop + endfacet + facet normal 0.0622567 -0.735672 -0.674471 + outer loop + vertex 345.837 51.1314 308.32 + vertex 351.975 52.4331 307.466 + vertex 348.938 50.3616 309.445 + endloop + endfacet + facet normal 0.0717513 -0.7202 -0.690046 + outer loop + vertex 348.938 50.3616 309.445 + vertex 341.369 49.7972 309.247 + vertex 345.837 51.1314 308.32 + endloop + endfacet + facet normal 0.0720443 -0.726449 -0.683434 + outer loop + vertex 343.14 48.8535 310.437 + vertex 341.369 49.7972 309.247 + vertex 348.938 50.3616 309.445 + endloop + endfacet + facet normal 0.079811 -0.719721 -0.689661 + outer loop + vertex 343.14 48.8535 310.437 + vertex 335.684 48.4665 309.978 + vertex 341.369 49.7972 309.247 + endloop + endfacet + facet normal 0.0798136 -0.719508 -0.689883 + outer loop + vertex 335.76 47.3312 311.171 + vertex 335.684 48.4665 309.978 + vertex 343.14 48.8535 310.437 + endloop + endfacet + facet normal 0.0765574 -0.719797 -0.68995 + outer loop + vertex 335.684 48.4665 309.978 + vertex 335.76 47.3312 311.171 + vertex 324.366 47.3732 309.863 + endloop + endfacet + facet normal -0.07831 -0.714977 -0.694749 + outer loop + vertex -343.415 48.9733 310.284 + vertex -341.544 49.9756 309.041 + vertex -335.319 47.6569 310.726 + endloop + endfacet + facet normal -0.0891946 -0.759418 -0.64446 + outer loop + vertex -345.25 48.1414 311.518 + vertex -349.617 50.0802 309.838 + vertex -343.415 48.9733 310.284 + endloop + endfacet + facet normal -0.111371 -0.786965 -0.606863 + outer loop + vertex -329.118 42.9828 315.485 + vertex -326.875 44.594 312.984 + vertex -310.966 40.2996 315.634 + endloop + endfacet + facet normal -0.102571 -0.769134 -0.630803 + outer loop + vertex -310.966 40.2996 315.634 + vertex -326.875 44.594 312.984 + vertex -309.621 42.1696 313.135 + endloop + endfacet + facet normal -0.103755 -0.768712 -0.631124 + outer loop + vertex -310.966 40.2996 315.634 + vertex -309.621 42.1696 313.135 + vertex -292.771 37.8373 315.641 + endloop + endfacet + facet normal -0.0979265 -0.75561 -0.64766 + outer loop + vertex -292.771 37.8373 315.641 + vertex -309.621 42.1696 313.135 + vertex -292.095 39.8914 313.143 + endloop + endfacet + facet normal -0.0939874 -0.756439 -0.647276 + outer loop + vertex -292.771 37.8373 315.641 + vertex -292.095 39.8914 313.143 + vertex -273.796 35.4998 315.618 + endloop + endfacet + facet normal -0.0883124 -0.742326 -0.664193 + outer loop + vertex -273.796 35.4998 315.618 + vertex -292.095 39.8914 313.143 + vertex -273.444 37.6857 313.128 + endloop + endfacet + facet normal -0.0829791 -0.743048 -0.664074 + outer loop + vertex -273.796 35.4998 315.618 + vertex -273.444 37.6857 313.128 + vertex -253.518 33.2294 315.624 + endloop + endfacet + facet normal -0.0793984 -0.7333 -0.675253 + outer loop + vertex -253.518 33.2294 315.624 + vertex -273.444 37.6857 313.128 + vertex -253.279 35.4924 313.139 + endloop + endfacet + facet normal -0.0754356 -0.733718 -0.675254 + outer loop + vertex -253.518 33.2294 315.624 + vertex -253.279 35.4924 313.139 + vertex -232.07 31.0049 315.645 + endloop + endfacet + facet normal -0.0726532 -0.725602 -0.684268 + outer loop + vertex -232.07 31.0049 315.645 + vertex -253.279 35.4924 313.139 + vertex -231.805 33.3215 313.161 + endloop + endfacet + facet normal -0.0706232 -0.725818 -0.684252 + outer loop + vertex -232.07 31.0049 315.645 + vertex -231.805 33.3215 313.161 + vertex -210.013 28.8542 315.65 + endloop + endfacet + facet normal -0.0675364 -0.716415 -0.694398 + outer loop + vertex -210.013 28.8542 315.65 + vertex -231.805 33.3215 313.161 + vertex -209.673 31.2292 313.167 + endloop + endfacet + facet normal -0.0664781 -0.716539 -0.694372 + outer loop + vertex -210.013 28.8542 315.65 + vertex -209.673 31.2292 313.167 + vertex -187.961 26.8295 315.628 + endloop + endfacet + facet normal -0.0647794 -0.711266 -0.699932 + outer loop + vertex -187.961 26.8295 315.628 + vertex -209.673 31.2292 313.167 + vertex -187.58 29.2423 313.141 + endloop + endfacet + facet normal -0.0626831 -0.711524 -0.69986 + outer loop + vertex -187.961 26.8295 315.628 + vertex -187.58 29.2423 313.141 + vertex -166.31 24.9647 315.585 + endloop + endfacet + facet normal -0.0620258 -0.709475 -0.701995 + outer loop + vertex -166.31 24.9647 315.585 + vertex -187.58 29.2423 313.141 + vertex -165.919 27.3985 313.091 + endloop + endfacet + facet normal -0.0582292 -0.709939 -0.701852 + outer loop + vertex -166.31 24.9647 315.585 + vertex -165.919 27.3985 313.091 + vertex -145.129 23.2794 315.532 + endloop + endfacet + facet normal -0.0579585 -0.709093 -0.702729 + outer loop + vertex -145.129 23.2794 315.532 + vertex -165.919 27.3985 313.091 + vertex -144.772 25.7289 313.031 + endloop + endfacet + facet normal -0.0524908 -0.709702 -0.702544 + outer loop + vertex -145.129 23.2794 315.532 + vertex -144.772 25.7289 313.031 + vertex -124.279 21.7863 315.483 + endloop + endfacet + facet normal -0.0523804 -0.709352 -0.702905 + outer loop + vertex -124.279 21.7863 315.483 + vertex -144.772 25.7289 313.031 + vertex -123.985 24.2481 312.977 + endloop + endfacet + facet normal -0.0446642 -0.710074 -0.702709 + outer loop + vertex -124.279 21.7863 315.483 + vertex -123.985 24.2481 312.977 + vertex -103.559 20.5154 315.45 + endloop + endfacet + facet normal -0.0451175 -0.711547 -0.701189 + outer loop + vertex -103.559 20.5154 315.45 + vertex -123.985 24.2481 312.977 + vertex -103.346 22.9761 312.939 + endloop + endfacet + facet normal -0.0358948 -0.712207 -0.701051 + outer loop + vertex -103.559 20.5154 315.45 + vertex -103.346 22.9761 312.939 + vertex -82.8098 19.4797 315.44 + endloop + endfacet + facet normal -0.0365666 -0.714475 -0.698705 + outer loop + vertex -82.8098 19.4797 315.44 + vertex -103.346 22.9761 312.939 + vertex -82.6892 21.9314 312.927 + endloop + endfacet + facet normal -0.0270488 -0.71492 -0.698683 + outer loop + vertex -82.8098 19.4797 315.44 + vertex -82.6892 21.9314 312.927 + vertex -61.9842 18.682 315.45 + endloop + endfacet + facet normal -0.0273773 -0.71608 -0.697481 + outer loop + vertex -61.9842 18.682 315.45 + vertex -82.6892 21.9314 312.927 + vertex -61.9591 21.1277 312.938 + endloop + endfacet + facet normal -0.0188743 -0.716263 -0.697575 + outer loop + vertex -61.9842 18.682 315.45 + vertex -61.9591 21.1277 312.938 + vertex -41.141 18.1129 315.47 + endloop + endfacet + facet normal -0.0184509 -0.714697 -0.699191 + outer loop + vertex -41.141 18.1129 315.47 + vertex -61.9591 21.1277 312.938 + vertex -41.206 20.567 312.964 + endloop + endfacet + facet normal -0.0104926 -0.714676 -0.699377 + outer loop + vertex -41.141 18.1129 315.47 + vertex -41.206 20.567 312.964 + vertex -20.3545 17.7863 315.492 + endloop + endfacet + facet normal -0.0111366 -0.71717 -0.69681 + outer loop + vertex -20.3545 17.7863 315.492 + vertex -41.206 20.567 312.964 + vertex -20.5189 20.2241 312.986 + endloop + endfacet + facet normal -0.00364706 -0.716964 -0.697101 + outer loop + vertex -20.3545 17.7863 315.492 + vertex -20.5189 20.2241 312.986 + vertex 0.341601 17.6727 315.501 + endloop + endfacet + facet normal -0.00333851 -0.715711 -0.698389 + outer loop + vertex 0.341601 17.6727 315.501 + vertex -20.5189 20.2241 312.986 + vertex 0.0840002 20.1171 312.997 + endloop + endfacet + facet normal 0.00363661 -0.715351 -0.698756 + outer loop + vertex 0.341601 17.6727 315.501 + vertex 0.0840002 20.1171 312.997 + vertex 20.9977 17.7842 315.494 + endloop + endfacet + facet normal 0.0033927 -0.716394 -0.697687 + outer loop + vertex 20.9977 17.7842 315.494 + vertex 0.0840002 20.1171 312.997 + vertex 20.6425 20.2224 312.989 + endloop + endfacet + facet normal 0.010951 -0.715819 -0.6982 + outer loop + vertex 20.9977 17.7842 315.494 + vertex 20.6425 20.2224 312.989 + vertex 41.6942 18.1196 315.475 + endloop + endfacet + facet normal 0.0110086 -0.715558 -0.698466 + outer loop + vertex 41.6942 18.1196 315.475 + vertex 20.6425 20.2224 312.989 + vertex 41.247 20.5603 312.967 + endloop + endfacet + facet normal 0.0187648 -0.714783 -0.699095 + outer loop + vertex 41.6942 18.1196 315.475 + vertex 41.247 20.5603 312.967 + vertex 62.4902 18.6873 315.453 + endloop + endfacet + facet normal 0.0185801 -0.715674 -0.698188 + outer loop + vertex 62.4902 18.6873 315.453 + vertex 41.247 20.5603 312.967 + vertex 61.9455 21.1225 312.942 + endloop + endfacet + facet normal 0.0273501 -0.714575 -0.699024 + outer loop + vertex 62.4902 18.6873 315.453 + vertex 61.9455 21.1225 312.942 + vertex 83.3936 19.4992 315.441 + endloop + endfacet + facet normal 0.0275142 -0.713728 -0.699883 + outer loop + vertex 83.3936 19.4992 315.441 + vertex 61.9455 21.1225 312.942 + vertex 82.7576 21.9373 312.929 + endloop + endfacet + facet normal 0.0360663 -0.712443 -0.700802 + outer loop + vertex 83.3936 19.4992 315.441 + vertex 82.7576 21.9373 312.929 + vertex 104.381 20.5552 315.447 + endloop + endfacet + facet normal 0.0362128 -0.711634 -0.701616 + outer loop + vertex 104.381 20.5552 315.447 + vertex 82.7576 21.9373 312.929 + vertex 103.649 22.9916 312.938 + endloop + endfacet + facet normal 0.0450818 -0.710071 -0.702686 + outer loop + vertex 104.381 20.5552 315.447 + vertex 103.649 22.9916 312.938 + vertex 125.419 21.8585 315.48 + endloop + endfacet + facet normal 0.0449177 -0.711042 -0.701713 + outer loop + vertex 125.419 21.8585 315.48 + vertex 103.649 22.9916 312.938 + vertex 124.599 24.2807 312.973 + endloop + endfacet + facet normal 0.0528405 -0.709453 -0.702769 + outer loop + vertex 125.419 21.8585 315.48 + vertex 124.599 24.2807 312.973 + vertex 146.513 23.3802 315.53 + endloop + endfacet + facet normal 0.0525312 -0.711412 -0.700809 + outer loop + vertex 146.513 23.3802 315.53 + vertex 124.599 24.2807 312.973 + vertex 145.619 25.7795 313.027 + endloop + endfacet + facet normal 0.0586827 -0.710052 -0.7017 + outer loop + vertex 146.513 23.3802 315.53 + vertex 145.619 25.7795 313.027 + vertex 167.72 25.0811 315.582 + endloop + endfacet + facet normal 0.0587389 -0.70967 -0.702082 + outer loop + vertex 167.72 25.0811 315.582 + vertex 145.619 25.7795 313.027 + vertex 166.807 27.473 313.088 + endloop + endfacet + facet normal 0.0631836 -0.708647 -0.702728 + outer loop + vertex 167.72 25.0811 315.582 + vertex 166.807 27.473 313.088 + vertex 189.165 26.9524 315.623 + endloop + endfacet + facet normal 0.0628749 -0.710907 -0.70047 + outer loop + vertex 189.165 26.9524 315.623 + vertex 166.807 27.473 313.088 + vertex 188.287 29.327 313.135 + endloop + endfacet + facet normal 0.066933 -0.709989 -0.701025 + outer loop + vertex 189.165 26.9524 315.623 + vertex 188.287 29.327 313.135 + vertex 210.915 28.9808 315.646 + endloop + endfacet + facet normal 0.0659467 -0.71772 -0.693202 + outer loop + vertex 210.915 28.9808 315.646 + vertex 188.287 29.327 313.135 + vertex 210.102 31.3079 313.159 + endloop + endfacet + facet normal 0.0703608 -0.716767 -0.693754 + outer loop + vertex 210.915 28.9808 315.646 + vertex 210.102 31.3079 313.159 + vertex 232.798 31.1182 315.657 + endloop + endfacet + facet normal 0.0692898 -0.725534 -0.684689 + outer loop + vertex 232.798 31.1182 315.657 + vertex 210.102 31.3079 313.159 + vertex 232.046 33.3887 313.175 + endloop + endfacet + facet normal 0.0757747 -0.724191 -0.685423 + outer loop + vertex 232.798 31.1182 315.657 + vertex 232.046 33.3887 313.175 + vertex 254.322 33.3455 315.683 + endloop + endfacet + facet normal 0.074212 -0.737037 -0.671765 + outer loop + vertex 254.322 33.3455 315.683 + vertex 232.046 33.3887 313.175 + vertex 253.583 35.5329 313.201 + endloop + endfacet + facet normal 0.0825061 -0.735299 -0.672702 + outer loop + vertex 254.322 33.3455 315.683 + vertex 253.583 35.5329 313.201 + vertex 274.918 35.6348 315.707 + endloop + endfacet + facet normal 0.0807858 -0.74912 -0.65749 + outer loop + vertex 274.918 35.6348 315.707 + vertex 253.583 35.5329 313.201 + vertex 274.068 37.7251 313.221 + endloop + endfacet + facet normal 0.0915029 -0.746559 -0.658997 + outer loop + vertex 274.918 35.6348 315.707 + vertex 274.068 37.7251 313.221 + vertex 294.205 38.0508 315.648 + endloop + endfacet + facet normal 0.0899755 -0.759181 -0.64463 + outer loop + vertex 294.205 38.0508 315.648 + vertex 274.068 37.7251 313.221 + vertex 293.059 40.0342 313.152 + endloop + endfacet + facet normal 0.10019 -0.756034 -0.646819 + outer loop + vertex 294.205 38.0508 315.648 + vertex 293.059 40.0342 313.152 + vertex 312.184 40.6744 315.366 + endloop + endfacet + facet normal 0.0994351 -0.763469 -0.638144 + outer loop + vertex 312.184 40.6744 315.366 + vertex 293.059 40.0342 313.152 + vertex 310.518 42.55 312.862 + endloop + endfacet + facet normal 0.103916 -0.761567 -0.6397 + outer loop + vertex 312.184 40.6744 315.366 + vertex 310.518 42.55 312.862 + vertex 329.078 43.5056 314.74 + endloop + endfacet + facet normal 0.103528 -0.767194 -0.633005 + outer loop + vertex 329.078 43.5056 314.74 + vertex 310.518 42.55 312.862 + vertex 326.69 45.2406 312.246 + endloop + endfacet + facet normal 0.0989497 -0.769872 -0.630481 + outer loop + vertex 329.078 43.5056 314.74 + vertex 326.69 45.2406 312.246 + vertex 338.717 45.6487 313.636 + endloop + endfacet + facet normal 0.111996 -0.804345 -0.583512 + outer loop + vertex 341.802 45.1492 314.916 + vertex 329.078 43.5056 314.74 + vertex 338.717 45.6487 313.636 + endloop + endfacet + facet normal 0.113004 -0.802859 -0.585361 + outer loop + vertex 341.802 45.1492 314.916 + vertex 338.717 45.6487 313.636 + vertex 348.411 46.6116 314.186 + endloop + endfacet + facet normal 0.113151 -0.810171 -0.575169 + outer loop + vertex 348.411 46.6116 314.186 + vertex 338.717 45.6487 313.636 + vertex 346.636 47.2696 312.91 + endloop + endfacet + facet normal 0.110687 -0.812197 -0.572786 + outer loop + vertex 348.411 46.6116 314.186 + vertex 346.636 47.2696 312.91 + vertex 353.872 47.9628 313.326 + endloop + endfacet + facet normal 0.110712 -0.813926 -0.570322 + outer loop + vertex 353.872 47.9628 313.326 + vertex 346.636 47.2696 312.91 + vertex 353.024 48.8051 311.959 + endloop + endfacet + facet normal 0.107077 -0.815367 -0.568956 + outer loop + vertex 353.872 47.9628 313.326 + vertex 353.024 48.8051 311.959 + vertex 361.426 49.3496 312.76 + endloop + endfacet + facet normal 0.106876 -0.81819 -0.564928 + outer loop + vertex 357.858 50.8127 309.966 + vertex 361.426 49.3496 312.76 + vertex 353.024 48.8051 311.959 + endloop + endfacet + facet normal 0.0895622 -0.801982 -0.590595 + outer loop + vertex 350.08 49.3627 310.755 + vertex 357.858 50.8127 309.966 + vertex 353.024 48.8051 311.959 + endloop + endfacet + facet normal 0.0987839 -0.788579 -0.606947 + outer loop + vertex 353.024 48.8051 311.959 + vertex 344.922 48.0203 311.66 + vertex 350.08 49.3627 310.755 + endloop + endfacet + facet normal 0.0987356 -0.787588 -0.608241 + outer loop + vertex 346.636 47.2696 312.91 + vertex 344.922 48.0203 311.66 + vertex 353.024 48.8051 311.959 + endloop + endfacet + facet normal 0.103768 -0.783491 -0.612677 + outer loop + vertex 346.636 47.2696 312.91 + vertex 338.728 46.6263 312.394 + vertex 344.922 48.0203 311.66 + endloop + endfacet + facet normal 0.103771 -0.781986 -0.614597 + outer loop + vertex 338.717 45.6487 313.636 + vertex 338.728 46.6263 312.394 + vertex 346.636 47.2696 312.91 + endloop + endfacet + facet normal 0.0975901 -0.782452 -0.615017 + outer loop + vertex 338.728 46.6263 312.394 + vertex 338.717 45.6487 313.636 + vertex 326.69 45.2406 312.246 + endloop + endfacet + facet normal -0.104905 -0.787653 -0.607123 + outer loop + vertex -347.126 47.4287 312.767 + vertex -345.25 48.1414 311.518 + vertex -338.387 45.9463 313.18 + endloop + endfacet + facet normal -0.109647 -0.811584 -0.573854 + outer loop + vertex -348.934 46.7884 314.018 + vertex -353.833 48.6226 312.36 + vertex -347.126 47.4287 312.767 + endloop + endfacet + facet normal -0.117502 -0.823059 -0.555668 + outer loop + vertex -350.699 46.1994 315.263 + vertex -348.934 46.7884 314.018 + vertex -341.339 44.5761 315.689 + endloop + endfacet + facet normal -0.117337 -0.844863 -0.521957 + outer loop + vertex -344.203 44.2782 316.815 + vertex -341.339 44.5761 315.689 + vertex -330.768 41.6107 318.112 + endloop + endfacet + facet normal 0.13338 -0.857732 -0.496493 + outer loop + vertex 358.208 46.997 315.974 + vertex 350.231 46.0333 315.496 + vertex 357.069 47.6436 314.551 + endloop + endfacet +endsolid diff --git a/noether_examples/meshes/outputs/output_11.stl b/noether_examples/meshes/outputs/output_11.stl new file mode 100644 index 00000000..1d1471ab --- /dev/null +++ b/noether_examples/meshes/outputs/output_11.stl @@ -0,0 +1,8647 @@ +solid ascii + facet normal -0.0133322 -0.177704 -0.983994 + outer loop + vertex 301.464 64.1726 301.31 + vertex 300.218 69.568 300.352 + vertex 313.371 66.3356 300.758 + endloop + endfacet + facet normal -0.0125334 -0.174526 -0.984573 + outer loop + vertex 313.371 66.3356 300.758 + vertex 300.218 69.568 300.352 + vertex 311.813 71.7192 299.823 + endloop + endfacet + facet normal 0.00783085 -0.172974 -0.984895 + outer loop + vertex 301.464 64.1726 301.31 + vertex 286.016 67.6399 300.578 + vertex 300.218 69.568 300.352 + endloop + endfacet + facet normal 0.00730927 -0.175216 -0.984503 + outer loop + vertex 286.985 62.2042 301.552 + vertex 286.016 67.6399 300.578 + vertex 301.464 64.1726 301.31 + endloop + endfacet + facet normal 0.0144491 -0.173969 -0.984645 + outer loop + vertex 286.985 62.2042 301.552 + vertex 268.914 65.9038 300.634 + vertex 286.016 67.6399 300.578 + endloop + endfacet + facet normal 0.014358 -0.174395 -0.984571 + outer loop + vertex 269.676 60.4246 301.615 + vertex 268.914 65.9038 300.634 + vertex 286.985 62.2042 301.552 + endloop + endfacet + facet normal 0.0148765 -0.174324 -0.984576 + outer loop + vertex 269.676 60.4246 301.615 + vertex 249.19 64.2392 300.63 + vertex 268.914 65.9038 300.634 + endloop + endfacet + facet normal 0.0151939 -0.172692 -0.984859 + outer loop + vertex 249.868 58.7149 301.609 + vertex 249.19 64.2392 300.63 + vertex 269.676 60.4246 301.615 + endloop + endfacet + facet normal 0.0143532 -0.172794 -0.984853 + outer loop + vertex 249.868 58.7149 301.609 + vertex 227.764 62.5273 300.618 + vertex 249.19 64.2392 300.63 + endloop + endfacet + facet normal 0.014755 -0.170565 -0.985236 + outer loop + vertex 228.416 56.9637 301.591 + vertex 227.764 62.5273 300.618 + vertex 249.868 58.7149 301.609 + endloop + endfacet + facet normal 0.0144569 -0.170599 -0.985234 + outer loop + vertex 228.416 56.9637 301.591 + vertex 205.684 60.7545 300.601 + vertex 227.764 62.5273 300.618 + endloop + endfacet + facet normal 0.0145622 -0.169995 -0.985337 + outer loop + vertex 206.31 55.1673 301.575 + vertex 205.684 60.7545 300.601 + vertex 228.416 56.9637 301.591 + endloop + endfacet + facet normal 0.0155759 -0.169882 -0.985341 + outer loop + vertex 206.31 55.1673 301.575 + vertex 183.765 58.9776 300.561 + vertex 205.684 60.7545 300.601 + endloop + endfacet + facet normal 0.0155774 -0.169873 -0.985343 + outer loop + vertex 184.367 53.3757 301.537 + vertex 183.765 58.9776 300.561 + vertex 206.31 55.1673 301.575 + endloop + endfacet + facet normal 0.0169888 -0.169722 -0.985345 + outer loop + vertex 184.367 53.3757 301.537 + vertex 162.386 57.2641 300.488 + vertex 183.765 58.9776 300.561 + endloop + endfacet + facet normal 0.0170501 -0.169391 -0.985401 + outer loop + vertex 162.939 51.6469 301.463 + vertex 162.386 57.2641 300.488 + vertex 184.367 53.3757 301.537 + endloop + endfacet + facet normal 0.0173341 -0.169363 -0.985401 + outer loop + vertex 162.939 51.6469 301.463 + vertex 141.541 55.6657 300.396 + vertex 162.386 57.2641 300.488 + endloop + endfacet + facet normal 0.0172336 -0.169876 -0.985315 + outer loop + vertex 142.034 50.0431 301.374 + vertex 141.541 55.6657 300.396 + vertex 162.939 51.6469 301.463 + endloop + endfacet + facet normal 0.0163988 -0.169949 -0.985316 + outer loop + vertex 142.034 50.0431 301.374 + vertex 121.031 54.2111 300.305 + vertex 141.541 55.6657 300.396 + endloop + endfacet + facet normal 0.0161202 -0.171294 -0.985088 + outer loop + vertex 121.455 48.5895 301.29 + vertex 121.031 54.2111 300.305 + vertex 142.034 50.0431 301.374 + endloop + endfacet + facet normal 0.0137165 -0.171476 -0.985093 + outer loop + vertex 121.455 48.5895 301.29 + vertex 100.687 52.9374 300.244 + vertex 121.031 54.2111 300.305 + endloop + endfacet + facet normal 0.0136951 -0.171574 -0.985076 + outer loop + vertex 101.032 47.3115 301.229 + vertex 100.687 52.9374 300.244 + vertex 121.455 48.5895 301.29 + endloop + endfacet + facet normal 0.00959166 -0.171826 -0.985081 + outer loop + vertex 101.032 47.3115 301.229 + vertex 80.4233 51.8869 300.23 + vertex 100.687 52.9374 300.244 + endloop + endfacet + facet normal 0.00952674 -0.172108 -0.985032 + outer loop + vertex 80.6931 46.2627 301.215 + vertex 80.4233 51.8869 300.23 + vertex 101.032 47.3115 301.229 + endloop + endfacet + facet normal 0.00596414 -0.172279 -0.98503 + outer loop + vertex 80.6931 46.2627 301.215 + vertex 60.2294 51.0681 300.251 + vertex 80.4233 51.8869 300.23 + endloop + endfacet + facet normal 0.00596051 -0.172294 -0.985028 + outer loop + vertex 60.4289 45.4456 301.235 + vertex 60.2294 51.0681 300.251 + vertex 80.6931 46.2627 301.215 + endloop + endfacet + facet normal 0.00310445 -0.172394 -0.985023 + outer loop + vertex 60.4289 45.4456 301.235 + vertex 40.1256 50.4859 300.289 + vertex 60.2294 51.0681 300.251 + endloop + endfacet + facet normal 0.00329366 -0.171656 -0.985151 + outer loop + vertex 40.2581 44.8596 301.27 + vertex 40.1256 50.4859 300.289 + vertex 60.4289 45.4456 301.235 + endloop + endfacet + facet normal 0.00117526 -0.171706 -0.985148 + outer loop + vertex 40.2581 44.8596 301.27 + vertex 20.1123 50.141 300.325 + vertex 40.1256 50.4859 300.289 + endloop + endfacet + facet normal 0.00108594 -0.172036 -0.98509 + outer loop + vertex 20.1842 44.5203 301.307 + vertex 20.1123 50.141 300.325 + vertex 40.2581 44.8596 301.27 + endloop + endfacet + facet normal 0.000398276 -0.172045 -0.985089 + outer loop + vertex 20.1842 44.5203 301.307 + vertex 0.137975 50.024 300.338 + vertex 20.1123 50.141 300.325 + endloop + endfacet + facet normal 0.000300433 -0.17239 -0.985029 + outer loop + vertex 0.148762 44.4072 301.321 + vertex 0.137975 50.024 300.338 + vertex 20.1842 44.5203 301.307 + endloop + endfacet + facet normal -0.000440675 -0.172392 -0.985028 + outer loop + vertex 0.148762 44.4072 301.321 + vertex -19.8734 50.1444 300.326 + vertex 0.137975 50.024 300.338 + endloop + endfacet + facet normal -0.000346923 -0.172074 -0.985084 + outer loop + vertex -19.9249 44.5249 301.307 + vertex -19.8734 50.1444 300.326 + vertex 0.148762 44.4072 301.321 + endloop + endfacet + facet normal -0.00106717 -0.172068 -0.985085 + outer loop + vertex -19.9249 44.5249 301.307 + vertex -39.965 50.4885 300.287 + vertex -19.8734 50.1444 300.326 + endloop + endfacet + facet normal -0.00104362 -0.171991 -0.985098 + outer loop + vertex -40.0811 44.8655 301.269 + vertex -39.965 50.4885 300.287 + vertex -19.9249 44.5249 301.307 + endloop + endfacet + facet normal -0.00293092 -0.171952 -0.985101 + outer loop + vertex -40.0811 44.8655 301.269 + vertex -60.1068 51.0666 300.246 + vertex -39.965 50.4885 300.287 + endloop + endfacet + facet normal -0.00314926 -0.172638 -0.98498 + outer loop + vertex -60.2896 45.4459 301.232 + vertex -60.1068 51.0666 300.246 + vertex -40.0811 44.8655 301.269 + endloop + endfacet + facet normal -0.00601563 -0.172545 -0.984983 + outer loop + vertex -60.2896 45.4459 301.232 + vertex -80.2165 51.8806 300.227 + vertex -60.1068 51.0666 300.246 + endloop + endfacet + facet normal -0.00621549 -0.173147 -0.984876 + outer loop + vertex -80.4689 46.2623 301.216 + vertex -80.2165 51.8806 300.227 + vertex -60.2896 45.4459 301.232 + endloop + endfacet + facet normal -0.00988434 -0.172982 -0.984875 + outer loop + vertex -80.4689 46.2623 301.216 + vertex -100.251 52.9237 300.244 + vertex -80.2165 51.8806 300.227 + endloop + endfacet + facet normal -0.00943936 -0.171694 -0.985105 + outer loop + vertex -100.58 47.2962 301.228 + vertex -100.251 52.9237 300.244 + vertex -80.4689 46.2623 301.216 + endloop + endfacet + facet normal -0.0134744 -0.171458 -0.985099 + outer loop + vertex -100.58 47.2962 301.228 + vertex -120.299 54.1738 300.301 + vertex -100.251 52.9237 300.244 + endloop + endfacet + facet normal -0.0134822 -0.171479 -0.985095 + outer loop + vertex -120.705 48.5498 301.286 + vertex -120.299 54.1738 300.301 + vertex -100.58 47.2962 301.228 + endloop + endfacet + facet normal -0.0162853 -0.171276 -0.985089 + outer loop + vertex -120.705 48.5498 301.286 + vertex -140.595 55.6035 300.388 + vertex -120.299 54.1738 300.301 + endloop + endfacet + facet normal -0.0158053 -0.169952 -0.985326 + outer loop + vertex -141.067 49.9762 301.366 + vertex -140.595 55.6035 300.388 + vertex -120.705 48.5498 301.286 + endloop + endfacet + facet normal -0.0172099 -0.169834 -0.985322 + outer loop + vertex -141.067 49.9762 301.366 + vertex -161.416 57.1732 300.481 + vertex -140.595 55.6035 300.388 + endloop + endfacet + facet normal -0.017398 -0.170354 -0.985229 + outer loop + vertex -161.953 51.5593 301.461 + vertex -161.416 57.1732 300.481 + vertex -141.067 49.9762 301.366 + endloop + endfacet + facet normal -0.0172556 -0.170368 -0.985229 + outer loop + vertex -161.953 51.5593 301.461 + vertex -182.941 58.8668 300.565 + vertex -161.416 57.1732 300.481 + endloop + endfacet + facet normal -0.0169597 -0.169536 -0.985378 + outer loop + vertex -183.515 53.2596 301.54 + vertex -182.941 58.8668 300.565 + vertex -161.953 51.5593 301.461 + endloop + endfacet + facet normal -0.0158467 -0.16965 -0.985377 + outer loop + vertex -183.515 53.2596 301.54 + vertex -205.022 60.656 300.612 + vertex -182.941 58.8668 300.565 + endloop + endfacet + facet normal -0.0159749 -0.170015 -0.985312 + outer loop + vertex -205.642 55.0656 301.587 + vertex -205.022 60.656 300.612 + vertex -183.515 53.2596 301.54 + endloop + endfacet + facet normal -0.0147984 -0.170145 -0.985308 + outer loop + vertex -205.642 55.0656 301.587 + vertex -227.182 62.5189 300.624 + vertex -205.022 60.656 300.612 + endloop + endfacet + facet normal -0.0145255 -0.169374 -0.985445 + outer loop + vertex -227.869 56.9429 301.592 + vertex -227.182 62.5189 300.624 + vertex -205.642 55.0656 301.587 + endloop + endfacet + facet normal -0.0136968 -0.169475 -0.985439 + outer loop + vertex -227.869 56.9429 301.592 + vertex -248.607 64.3683 300.603 + vertex -227.182 62.5189 300.624 + endloop + endfacet + facet normal -0.0139814 -0.170251 -0.985301 + outer loop + vertex -249.362 58.8257 301.572 + vertex -248.607 64.3683 300.603 + vertex -227.869 56.9429 301.592 + endloop + endfacet + facet normal -0.0129078 -0.170396 -0.985291 + outer loop + vertex -249.362 58.8257 301.572 + vertex -268.388 66.0654 300.569 + vertex -248.607 64.3683 300.603 + endloop + endfacet + facet normal -0.0139264 -0.173008 -0.984822 + outer loop + vertex -269.124 60.5798 301.543 + vertex -268.388 66.0654 300.569 + vertex -249.362 58.8257 301.572 + endloop + endfacet + facet normal -0.0124567 -0.173202 -0.984807 + outer loop + vertex -269.124 60.5798 301.543 + vertex -285.567 67.4486 300.543 + vertex -268.388 66.0654 300.569 + endloop + endfacet + facet normal -0.0145305 -0.178037 -0.983917 + outer loop + vertex -286.209 62.0937 301.521 + vertex -285.567 67.4486 300.543 + vertex -269.124 60.5798 301.543 + endloop + endfacet + facet normal -0.0092707 -0.178659 -0.983867 + outer loop + vertex -286.209 62.0937 301.521 + vertex -299.116 68.3289 300.511 + vertex -285.567 67.4486 300.543 + endloop + endfacet + facet normal -0.0118158 -0.18377 -0.982898 + outer loop + vertex -300.441 63.5083 301.428 + vertex -299.116 68.3289 300.511 + vertex -286.209 62.0937 301.521 + endloop + endfacet + facet normal 0.00112885 -0.187217 -0.982318 + outer loop + vertex -300.441 63.5083 301.428 + vertex -309.315 69.2756 300.319 + vertex -299.116 68.3289 300.511 + endloop + endfacet + facet normal 0.00562708 -0.140333 -0.990088 + outer loop + vertex -309.315 69.2756 300.319 + vertex -308.212 73.292 299.756 + vertex -299.116 68.3289 300.511 + endloop + endfacet + facet normal 0.0125711 -0.127853 -0.991713 + outer loop + vertex -299.86 74.1187 299.755 + vertex -299.116 68.3289 300.511 + vertex -308.212 73.292 299.756 + endloop + endfacet + facet normal 0.0109909 -0.111889 -0.99366 + outer loop + vertex -309.081 76.821 299.349 + vertex -299.86 74.1187 299.755 + vertex -308.212 73.292 299.756 + endloop + endfacet + facet normal 0.047544 -0.102879 -0.993557 + outer loop + vertex -308.212 73.292 299.756 + vertex -313.736 77.1211 299.095 + vertex -309.081 76.821 299.349 + endloop + endfacet + facet normal 0.0482155 -0.0932419 -0.994475 + outer loop + vertex -313.736 77.1211 299.095 + vertex -313.186 80.0971 298.842 + vertex -309.081 76.821 299.349 + endloop + endfacet + facet normal 0.0461624 -0.0957921 -0.99433 + outer loop + vertex -309.081 76.821 299.349 + vertex -313.186 80.0971 298.842 + vertex -307.55 79.4404 299.167 + endloop + endfacet + facet normal 0.0491227 -0.0713291 -0.996243 + outer loop + vertex -313.186 80.0971 298.842 + vertex -312.596 82.9871 298.665 + vertex -307.55 79.4404 299.167 + endloop + endfacet + facet normal 0.0566078 -0.0607232 -0.996548 + outer loop + vertex -307.55 79.4404 299.167 + vertex -312.596 82.9871 298.665 + vertex -308.013 82.6833 298.943 + endloop + endfacet + facet normal 0.0175041 -0.0663832 -0.997641 + outer loop + vertex -308.013 82.6833 298.943 + vertex -299.147 79.9811 299.279 + vertex -307.55 79.4404 299.167 + endloop + endfacet + facet normal 0.0185674 -0.0831714 -0.996362 + outer loop + vertex -299.147 79.9811 299.279 + vertex -299.86 74.1187 299.755 + vertex -307.55 79.4404 299.167 + endloop + endfacet + facet normal 0.000678564 -0.0810243 -0.996712 + outer loop + vertex -299.86 74.1187 299.755 + vertex -299.147 79.9811 299.279 + vertex -284.99 73.158 299.843 + endloop + endfacet + facet normal -0.00195919 -0.12147 -0.992593 + outer loop + vertex -285.567 67.4486 300.543 + vertex -299.86 74.1187 299.755 + vertex -284.99 73.158 299.843 + endloop + endfacet + facet normal -0.00822899 -0.120842 -0.992638 + outer loop + vertex -285.567 67.4486 300.543 + vertex -284.99 73.158 299.843 + vertex -268.388 66.0654 300.569 + endloop + endfacet + facet normal -0.00641585 -0.11665 -0.993152 + outer loop + vertex -268.388 66.0654 300.569 + vertex -284.99 73.158 299.843 + vertex -267.582 71.8191 299.888 + endloop + endfacet + facet normal -0.00826092 -0.116394 -0.993169 + outer loop + vertex -268.388 66.0654 300.569 + vertex -267.582 71.8191 299.888 + vertex -248.607 64.3683 300.603 + endloop + endfacet + facet normal -0.00786353 -0.115393 -0.993289 + outer loop + vertex -248.607 64.3683 300.603 + vertex -267.582 71.8191 299.888 + vertex -247.867 70.1667 299.924 + endloop + endfacet + facet normal -0.00900855 -0.115248 -0.993296 + outer loop + vertex -248.607 64.3683 300.603 + vertex -247.867 70.1667 299.924 + vertex -227.182 62.5189 300.624 + endloop + endfacet + facet normal -0.00885905 -0.114848 -0.993344 + outer loop + vertex -227.182 62.5189 300.624 + vertex -247.867 70.1667 299.924 + vertex -226.523 68.3428 299.944 + endloop + endfacet + facet normal -0.0101418 -0.114703 -0.993348 + outer loop + vertex -227.182 62.5189 300.624 + vertex -226.523 68.3428 299.944 + vertex -205.022 60.656 300.612 + endloop + endfacet + facet normal -0.0102778 -0.11508 -0.993303 + outer loop + vertex -205.022 60.656 300.612 + vertex -226.523 68.3428 299.944 + vertex -204.439 66.4944 299.93 + endloop + endfacet + facet normal -0.0114325 -0.114965 -0.993304 + outer loop + vertex -205.022 60.656 300.612 + vertex -204.439 66.4944 299.93 + vertex -182.941 58.8668 300.565 + endloop + endfacet + facet normal -0.0117643 -0.115891 -0.993192 + outer loop + vertex -182.941 58.8668 300.565 + vertex -204.439 66.4944 299.93 + vertex -182.395 64.7099 299.877 + endloop + endfacet + facet normal -0.0129914 -0.115776 -0.99319 + outer loop + vertex -182.941 58.8668 300.565 + vertex -182.395 64.7099 299.877 + vertex -161.416 57.1732 300.481 + endloop + endfacet + facet normal -0.0128958 -0.115512 -0.993222 + outer loop + vertex -161.416 57.1732 300.481 + vertex -182.395 64.7099 299.877 + vertex -160.923 63.0272 299.794 + endloop + endfacet + facet normal -0.0131484 -0.115491 -0.993221 + outer loop + vertex -161.416 57.1732 300.481 + vertex -160.923 63.0272 299.794 + vertex -140.595 55.6035 300.388 + endloop + endfacet + facet normal -0.013255 -0.11578 -0.993186 + outer loop + vertex -140.595 55.6035 300.388 + vertex -160.923 63.0272 299.794 + vertex -140.167 61.4617 299.699 + endloop + endfacet + facet normal -0.0124151 -0.115842 -0.99319 + outer loop + vertex -140.595 55.6035 300.388 + vertex -140.167 61.4617 299.699 + vertex -120.299 54.1738 300.301 + endloop + endfacet + facet normal -0.0125631 -0.116242 -0.993142 + outer loop + vertex -120.299 54.1738 300.301 + vertex -140.167 61.4617 299.699 + vertex -119.94 60.0339 299.611 + endloop + endfacet + facet normal -0.0100637 -0.116396 -0.993152 + outer loop + vertex -120.299 54.1738 300.301 + vertex -119.94 60.0339 299.611 + vertex -100.251 52.9237 300.244 + endloop + endfacet + facet normal -0.0102171 -0.116816 -0.993101 + outer loop + vertex -100.251 52.9237 300.244 + vertex -119.94 60.0339 299.611 + vertex -99.9626 58.7829 299.552 + endloop + endfacet + facet normal -0.00697563 -0.116977 -0.99311 + outer loop + vertex -100.251 52.9237 300.244 + vertex -99.9626 58.7829 299.552 + vertex -80.2165 51.8806 300.227 + endloop + endfacet + facet normal -0.00698357 -0.116999 -0.993107 + outer loop + vertex -80.2165 51.8806 300.227 + vertex -99.9626 58.7829 299.552 + vertex -79.9948 57.7395 299.535 + endloop + endfacet + facet normal -0.00376422 -0.117121 -0.99311 + outer loop + vertex -80.2165 51.8806 300.227 + vertex -79.9948 57.7395 299.535 + vertex -60.1068 51.0666 300.246 + endloop + endfacet + facet normal -0.00367935 -0.116872 -0.99314 + outer loop + vertex -60.1068 51.0666 300.246 + vertex -79.9948 57.7395 299.535 + vertex -59.9469 56.925 299.556 + endloop + endfacet + facet normal -0.00133545 -0.116935 -0.993139 + outer loop + vertex -60.1068 51.0666 300.246 + vertex -59.9469 56.925 299.556 + vertex -39.965 50.4885 300.287 + endloop + endfacet + facet normal -0.00133855 -0.116945 -0.993137 + outer loop + vertex -39.965 50.4885 300.287 + vertex -59.9469 56.925 299.556 + vertex -39.8636 56.3442 299.598 + endloop + endfacet + facet normal -0.00010825 -0.116966 -0.993136 + outer loop + vertex -39.965 50.4885 300.287 + vertex -39.8636 56.3442 299.598 + vertex -19.8734 50.1444 300.326 + endloop + endfacet + facet normal -0.000352385 -0.117742 -0.993044 + outer loop + vertex -19.8734 50.1444 300.326 + vertex -39.8636 56.3442 299.598 + vertex -19.8262 55.9918 299.632 + endloop + endfacet + facet normal -0.000107085 -0.117744 -0.993044 + outer loop + vertex -19.8734 50.1444 300.326 + vertex -19.8262 55.9918 299.632 + vertex 0.137975 50.024 300.338 + endloop + endfacet + facet normal 0.000215168 -0.116681 -0.993169 + outer loop + vertex 0.137975 50.024 300.338 + vertex -19.8262 55.9918 299.632 + vertex 0.132592 55.8795 299.65 + endloop + endfacet + facet normal 6.89624e-05 -0.116681 -0.993169 + outer loop + vertex 0.137975 50.024 300.338 + vertex 0.132592 55.8795 299.65 + vertex 20.1123 50.141 300.325 + endloop + endfacet + facet normal -0.000102098 -0.117269 -0.9931 + outer loop + vertex 20.1123 50.141 300.325 + vertex 0.132592 55.8795 299.65 + vertex 20.0546 55.993 299.634 + endloop + endfacet + facet normal 0.000222895 -0.117266 -0.993101 + outer loop + vertex 20.1123 50.141 300.325 + vertex 20.0546 55.993 299.634 + vertex 40.1256 50.4859 300.289 + endloop + endfacet + facet normal 5.02131e-05 -0.117886 -0.993027 + outer loop + vertex 40.1256 50.4859 300.289 + vertex 20.0546 55.993 299.634 + vertex 40.0126 56.3356 299.595 + endloop + endfacet + facet normal 0.0015096 -0.117858 -0.993029 + outer loop + vertex 40.1256 50.4859 300.289 + vertex 40.0126 56.3356 299.595 + vertex 60.2294 51.0681 300.251 + endloop + endfacet + facet normal 0.00138736 -0.118321 -0.992974 + outer loop + vertex 60.2294 51.0681 300.251 + vertex 40.0126 56.3356 299.595 + vertex 60.0589 56.9175 299.553 + endloop + endfacet + facet normal 0.00376528 -0.118252 -0.992977 + outer loop + vertex 60.2294 51.0681 300.251 + vertex 60.0589 56.9175 299.553 + vertex 80.4233 51.8869 300.23 + endloop + endfacet + facet normal 0.00403134 -0.117191 -0.993101 + outer loop + vertex 80.4233 51.8869 300.23 + vertex 60.0589 56.9175 299.553 + vertex 80.1943 57.7454 299.538 + endloop + endfacet + facet normal 0.00675931 -0.117084 -0.993099 + outer loop + vertex 80.4233 51.8869 300.23 + vertex 80.1943 57.7454 299.538 + vertex 100.687 52.9374 300.244 + endloop + endfacet + facet normal 0.00687796 -0.116587 -0.993157 + outer loop + vertex 100.687 52.9374 300.244 + vertex 80.1943 57.7454 299.538 + vertex 100.391 58.7993 299.554 + endloop + endfacet + facet normal 0.0102935 -0.116414 -0.993147 + outer loop + vertex 100.687 52.9374 300.244 + vertex 100.391 58.7993 299.554 + vertex 121.031 54.2111 300.305 + endloop + endfacet + facet normal 0.0103417 -0.116201 -0.993172 + outer loop + vertex 121.031 54.2111 300.305 + vertex 100.391 58.7993 299.554 + vertex 120.664 60.071 299.616 + endloop + endfacet + facet normal 0.0126112 -0.116058 -0.993162 + outer loop + vertex 121.031 54.2111 300.305 + vertex 120.664 60.071 299.616 + vertex 141.541 55.6657 300.396 + endloop + endfacet + facet normal 0.012549 -0.116346 -0.993129 + outer loop + vertex 141.541 55.6657 300.396 + vertex 120.664 60.071 299.616 + vertex 141.097 61.5189 299.705 + endloop + endfacet + facet normal 0.0132987 -0.116289 -0.993126 + outer loop + vertex 141.541 55.6657 300.396 + vertex 141.097 61.5189 299.705 + vertex 162.386 57.2641 300.488 + endloop + endfacet + facet normal 0.0134799 -0.115401 -0.993228 + outer loop + vertex 162.386 57.2641 300.488 + vertex 141.097 61.5189 299.705 + vertex 161.88 63.116 299.801 + endloop + endfacet + facet normal 0.0126678 -0.115471 -0.99323 + outer loop + vertex 162.386 57.2641 300.488 + vertex 161.88 63.116 299.801 + vertex 183.765 58.9776 300.561 + endloop + endfacet + facet normal 0.0127803 -0.114888 -0.993296 + outer loop + vertex 183.765 58.9776 300.561 + vertex 161.88 63.116 299.801 + vertex 183.211 64.824 299.878 + endloop + endfacet + facet normal 0.0111449 -0.115044 -0.993298 + outer loop + vertex 183.765 58.9776 300.561 + vertex 183.211 64.824 299.878 + vertex 205.684 60.7545 300.601 + endloop + endfacet + facet normal 0.0111294 -0.115127 -0.993288 + outer loop + vertex 205.684 60.7545 300.601 + vertex 183.211 64.824 299.878 + vertex 205.088 66.5895 299.918 + endloop + endfacet + facet normal 0.0100184 -0.11524 -0.993287 + outer loop + vertex 205.684 60.7545 300.601 + vertex 205.088 66.5895 299.918 + vertex 227.764 62.5273 300.618 + endloop + endfacet + facet normal 0.00990393 -0.115867 -0.993215 + outer loop + vertex 227.764 62.5273 300.618 + vertex 205.088 66.5895 299.918 + vertex 227.136 68.3449 299.934 + endloop + endfacet + facet normal 0.00981024 -0.115877 -0.993215 + outer loop + vertex 227.764 62.5273 300.618 + vertex 227.136 68.3449 299.934 + vertex 249.19 64.2392 300.63 + endloop + endfacet + facet normal 0.00955519 -0.117221 -0.99306 + outer loop + vertex 249.19 64.2392 300.63 + vertex 227.136 68.3449 299.934 + vertex 248.525 70.0312 299.94 + endloop + endfacet + facet normal 0.0100539 -0.117164 -0.993062 + outer loop + vertex 249.19 64.2392 300.63 + vertex 248.525 70.0312 299.94 + vertex 268.914 65.9038 300.634 + endloop + endfacet + facet normal 0.00990643 -0.117878 -0.992979 + outer loop + vertex 268.914 65.9038 300.634 + vertex 248.525 70.0312 299.94 + vertex 268.143 71.6663 299.942 + endloop + endfacet + facet normal 0.00874345 -0.118033 -0.992971 + outer loop + vertex 268.914 65.9038 300.634 + vertex 268.143 71.6663 299.942 + vertex 286.016 67.6399 300.578 + endloop + endfacet + facet normal 0.00873917 -0.118052 -0.992969 + outer loop + vertex 286.016 67.6399 300.578 + vertex 268.143 71.6663 299.942 + vertex 285.08 73.3642 299.889 + endloop + endfacet + facet normal 0.000430505 -0.119396 -0.992847 + outer loop + vertex 286.016 67.6399 300.578 + vertex 285.08 73.3642 299.889 + vertex 300.218 69.568 300.352 + endloop + endfacet + facet normal 0.000739821 -0.11818 -0.992992 + outer loop + vertex 300.218 69.568 300.352 + vertex 285.08 73.3642 299.889 + vertex 299.104 75.2505 299.675 + endloop + endfacet + facet normal -0.0225075 -0.122641 -0.992196 + outer loop + vertex 300.218 69.568 300.352 + vertex 299.104 75.2505 299.675 + vertex 311.813 71.7192 299.823 + endloop + endfacet + facet normal -0.0220289 -0.120928 -0.992417 + outer loop + vertex 311.813 71.7192 299.823 + vertex 299.104 75.2505 299.675 + vertex 310.48 77.3782 299.163 + endloop + endfacet + facet normal -0.0297943 -0.0803487 -0.996321 + outer loop + vertex 299.104 75.2505 299.675 + vertex 298.082 81.0867 299.235 + vertex 310.48 77.3782 299.163 + endloop + endfacet + facet normal -0.0289426 -0.0774964 -0.996572 + outer loop + vertex 310.48 77.3782 299.163 + vertex 298.082 81.0867 299.235 + vertex 309.351 83.1869 298.744 + endloop + endfacet + facet normal -0.034449 -0.0483394 -0.998237 + outer loop + vertex 298.082 81.0867 299.235 + vertex 297.17 86.9752 298.981 + vertex 309.351 83.1869 298.744 + endloop + endfacet + facet normal -0.0332187 -0.0443693 -0.998463 + outer loop + vertex 309.351 83.1869 298.744 + vertex 297.17 86.9752 298.981 + vertex 308.336 89.0637 298.517 + endloop + endfacet + facet normal -0.0365484 -0.0266813 -0.998976 + outer loop + vertex 297.17 86.9752 298.981 + vertex 296.314 92.8589 298.855 + vertex 308.336 89.0637 298.517 + endloop + endfacet + facet normal -0.035632 -0.0237689 -0.999082 + outer loop + vertex 308.336 89.0637 298.517 + vertex 296.314 92.8589 298.855 + vertex 307.396 94.9278 298.411 + endloop + endfacet + facet normal -0.0374656 -0.0139727 -0.9992 + outer loop + vertex 296.314 92.8589 298.855 + vertex 295.517 98.7182 298.803 + vertex 307.396 94.9278 298.411 + endloop + endfacet + facet normal -0.0372052 -0.0131545 -0.999221 + outer loop + vertex 307.396 94.9278 298.411 + vertex 295.517 98.7182 298.803 + vertex 306.548 100.768 298.366 + endloop + endfacet + facet normal -0.0381069 -0.00830635 -0.999239 + outer loop + vertex 295.517 98.7182 298.803 + vertex 294.729 104.574 298.785 + vertex 306.548 100.768 298.366 + endloop + endfacet + facet normal -0.037746 -0.00718323 -0.999262 + outer loop + vertex 306.548 100.768 298.366 + vertex 294.729 104.574 298.785 + vertex 305.751 106.611 298.354 + endloop + endfacet + facet normal -0.0381851 -0.0048065 -0.999259 + outer loop + vertex 294.729 104.574 298.785 + vertex 293.978 110.449 298.785 + vertex 305.751 106.611 298.354 + endloop + endfacet + facet normal -0.0382847 -0.00511272 -0.999254 + outer loop + vertex 305.751 106.611 298.354 + vertex 293.978 110.449 298.785 + vertex 304.937 112.487 298.355 + endloop + endfacet + facet normal -0.0383909 -0.00454121 -0.999252 + outer loop + vertex 293.978 110.449 298.785 + vertex 293.206 116.367 298.788 + vertex 304.937 112.487 298.355 + endloop + endfacet + facet normal -0.0386021 -0.00518106 -0.999241 + outer loop + vertex 304.937 112.487 298.355 + vertex 293.206 116.367 298.788 + vertex 304.128 118.414 298.355 + endloop + endfacet + facet normal -0.0386625 -0.00485901 -0.999241 + outer loop + vertex 293.206 116.367 298.788 + vertex 292.422 122.325 298.789 + vertex 304.128 118.414 298.355 + endloop + endfacet + facet normal -0.0388427 -0.00539968 -0.999231 + outer loop + vertex 304.128 118.414 298.355 + vertex 292.422 122.325 298.789 + vertex 303.308 124.4 298.355 + endloop + endfacet + facet normal -0.0389293 -0.0049452 -0.99923 + outer loop + vertex 292.422 122.325 298.789 + vertex 291.612 128.294 298.791 + vertex 303.308 124.4 298.355 + endloop + endfacet + facet normal -0.0389394 -0.00497551 -0.999229 + outer loop + vertex 303.308 124.4 298.355 + vertex 291.612 128.294 298.791 + vertex 302.463 130.399 298.358 + endloop + endfacet + facet normal -0.0389131 -0.00511122 -0.99923 + outer loop + vertex 291.612 128.294 298.791 + vertex 290.765 134.229 298.794 + vertex 302.463 130.399 298.358 + endloop + endfacet + facet normal -0.0387274 -0.00454286 -0.999239 + outer loop + vertex 302.463 130.399 298.358 + vertex 290.765 134.229 298.794 + vertex 301.621 136.325 298.364 + endloop + endfacet + facet normal -0.0387983 -0.0041754 -0.999238 + outer loop + vertex 290.765 134.229 298.794 + vertex 289.972 140.122 298.8 + vertex 301.621 136.325 298.364 + endloop + endfacet + facet normal -0.0389814 -0.00473821 -0.999229 + outer loop + vertex 301.621 136.325 298.364 + vertex 289.972 140.122 298.8 + vertex 300.803 142.199 298.368 + endloop + endfacet + facet normal -0.0390598 -0.00432923 -0.999227 + outer loop + vertex 289.972 140.122 298.8 + vertex 289.293 146.042 298.801 + vertex 300.803 142.199 298.368 + endloop + endfacet + facet normal -0.0392418 -0.00487554 -0.999218 + outer loop + vertex 300.803 142.199 298.368 + vertex 289.293 146.042 298.801 + vertex 300.1 148.124 298.366 + endloop + endfacet + facet normal -0.0398497 -0.00171792 -0.999204 + outer loop + vertex 289.293 146.042 298.801 + vertex 288.822 152.031 298.81 + vertex 300.1 148.124 298.366 + endloop + endfacet + facet normal -0.0401654 -0.00263095 -0.99919 + outer loop + vertex 300.1 148.124 298.366 + vertex 288.822 152.031 298.81 + vertex 299.532 154.092 298.374 + endloop + endfacet + facet normal -0.0430355 0.012322 -0.998998 + outer loop + vertex 288.822 152.031 298.81 + vertex 288.394 158.041 298.902 + vertex 299.532 154.092 298.374 + endloop + endfacet + facet normal -0.0421406 0.0148468 -0.999001 + outer loop + vertex 299.532 154.092 298.374 + vertex 288.394 158.041 298.902 + vertex 298.864 159.969 298.489 + endloop + endfacet + facet normal -0.052578 0.0721529 -0.996007 + outer loop + vertex 288.394 158.041 298.902 + vertex 288.176 163.852 299.335 + vertex 298.864 159.969 298.489 + endloop + endfacet + facet normal -0.043179 0.0976492 -0.994284 + outer loop + vertex 298.864 159.969 298.489 + vertex 288.176 163.852 299.335 + vertex 297.833 165.215 299.049 + endloop + endfacet + facet normal -0.0159175 0.073611 -0.99716 + outer loop + vertex 288.394 158.041 298.902 + vertex 275.713 162.453 299.43 + vertex 288.176 163.852 299.335 + endloop + endfacet + facet normal -0.0222029 0.0556717 -0.998202 + outer loop + vertex 275.071 156.276 299.1 + vertex 275.713 162.453 299.43 + vertex 288.394 158.041 298.902 + endloop + endfacet + facet normal -0.00932008 0.0543469 -0.998479 + outer loop + vertex 275.071 156.276 299.1 + vertex 258.804 160.848 299.501 + vertex 275.713 162.453 299.43 + endloop + endfacet + facet normal -0.0101343 0.0514626 -0.998624 + outer loop + vertex 258.774 154.59 299.178 + vertex 258.804 160.848 299.501 + vertex 275.071 156.276 299.1 + endloop + endfacet + facet normal -0.00625109 0.0138726 -0.999884 + outer loop + vertex 275.441 150.177 299.013 + vertex 258.774 154.59 299.178 + vertex 275.071 156.276 299.1 + endloop + endfacet + facet normal -0.0170404 0.013216 -0.999767 + outer loop + vertex 275.441 150.177 299.013 + vertex 275.071 156.276 299.1 + vertex 288.822 152.031 298.81 + endloop + endfacet + facet normal -0.00575606 0.015741 -0.99986 + outer loop + vertex 259.136 148.502 299.081 + vertex 258.774 154.59 299.178 + vertex 275.441 150.177 299.013 + endloop + endfacet + facet normal -0.00433567 0.00190478 -0.999989 + outer loop + vertex 275.966 144.193 298.999 + vertex 259.136 148.502 299.081 + vertex 275.441 150.177 299.013 + endloop + endfacet + facet normal -0.0150185 0.000968395 -0.999887 + outer loop + vertex 275.966 144.193 298.999 + vertex 275.441 150.177 299.013 + vertex 289.293 146.042 298.801 + endloop + endfacet + facet normal -0.0039251 0.00350806 -0.999986 + outer loop + vertex 259.716 142.556 299.057 + vertex 259.136 148.502 299.081 + vertex 275.966 144.193 298.999 + endloop + endfacet + facet normal -0.00364532 0.00072898 -0.999993 + outer loop + vertex 276.653 138.292 298.993 + vertex 259.716 142.556 299.057 + vertex 275.966 144.193 298.999 + endloop + endfacet + facet normal -0.0143775 -0.000520366 -0.999897 + outer loop + vertex 276.653 138.292 298.993 + vertex 275.966 144.193 298.999 + vertex 289.972 140.122 298.8 + endloop + endfacet + facet normal -0.00357074 0.00102515 -0.999993 + outer loop + vertex 260.393 136.671 299.049 + vertex 259.716 142.556 299.057 + vertex 276.653 138.292 298.993 + endloop + endfacet + facet normal -0.00349942 0.000309699 -0.999994 + outer loop + vertex 277.448 132.399 298.988 + vertex 260.393 136.671 299.049 + vertex 276.653 138.292 298.993 + endloop + endfacet + facet normal -0.0144086 -0.00116274 -0.999896 + outer loop + vertex 277.448 132.399 298.988 + vertex 276.653 138.292 298.993 + vertex 290.765 134.229 298.794 + endloop + endfacet + facet normal -0.00353311 0.00017519 -0.999994 + outer loop + vertex 261.146 130.773 299.045 + vertex 260.393 136.671 299.049 + vertex 277.448 132.399 298.988 + endloop + endfacet + facet normal -0.00354773 0.000321869 -0.999994 + outer loop + vertex 278.209 126.471 298.983 + vertex 261.146 130.773 299.045 + vertex 277.448 132.399 298.988 + endloop + endfacet + facet normal -0.0141851 -0.00104391 -0.999899 + outer loop + vertex 278.209 126.471 298.983 + vertex 277.448 132.399 298.988 + vertex 291.612 128.294 298.791 + endloop + endfacet + facet normal -0.00366004 -0.000123573 -0.999993 + outer loop + vertex 261.872 124.837 299.043 + vertex 261.146 130.773 299.045 + vertex 278.209 126.471 298.983 + endloop + endfacet + facet normal -0.00365094 -0.000214549 -0.999993 + outer loop + vertex 278.977 120.511 298.982 + vertex 261.872 124.837 299.043 + vertex 278.209 126.471 298.983 + endloop + endfacet + facet normal -0.0141081 -0.00156244 -0.999899 + outer loop + vertex 278.977 120.511 298.982 + vertex 278.209 126.471 298.983 + vertex 292.422 122.325 298.789 + endloop + endfacet + facet normal -0.00362666 -0.000118534 -0.999993 + outer loop + vertex 262.563 118.875 299.042 + vertex 261.872 124.837 299.043 + vertex 278.977 120.511 298.982 + endloop + endfacet + facet normal -0.00363852 3.63854e-07 -0.999993 + outer loop + vertex 279.715 114.559 298.979 + vertex 262.563 118.875 299.042 + vertex 278.977 120.511 298.982 + endloop + endfacet + facet normal -0.014 -0.00128348 -0.999901 + outer loop + vertex 279.715 114.559 298.979 + vertex 278.977 120.511 298.982 + vertex 293.206 116.367 298.788 + endloop + endfacet + facet normal -0.00362187 6.6538e-05 -0.999993 + outer loop + vertex 263.246 112.921 299.039 + vertex 262.563 118.875 299.042 + vertex 279.715 114.559 298.979 + endloop + endfacet + facet normal -0.00362782 0.000126393 -0.999993 + outer loop + vertex 280.442 108.643 298.976 + vertex 263.246 112.921 299.039 + vertex 279.715 114.559 298.979 + endloop + endfacet + facet normal -0.0139266 -0.00114039 -0.999902 + outer loop + vertex 280.442 108.643 298.976 + vertex 279.715 114.559 298.979 + vertex 293.978 110.449 298.785 + endloop + endfacet + facet normal -0.00360151 0.000232187 -0.999993 + outer loop + vertex 263.923 107.006 299.035 + vertex 263.246 112.921 299.039 + vertex 280.442 108.643 298.976 + endloop + endfacet + facet normal -0.00350834 -0.000707636 -0.999994 + outer loop + vertex 281.175 102.768 298.977 + vertex 263.923 107.006 299.035 + vertex 280.442 108.643 298.976 + endloop + endfacet + facet normal -0.0139424 -0.00200888 -0.999901 + outer loop + vertex 281.175 102.768 298.977 + vertex 280.442 108.643 298.976 + vertex 294.729 104.574 298.785 + endloop + endfacet + facet normal -0.00339575 -0.000249281 -0.999994 + outer loop + vertex 264.597 101.137 299.034 + vertex 263.923 107.006 299.035 + vertex 281.175 102.768 298.977 + endloop + endfacet + facet normal -0.00311476 -0.00310449 -0.99999 + outer loop + vertex 281.893 96.9159 298.993 + vertex 264.597 101.137 299.034 + vertex 281.175 102.768 298.977 + endloop + endfacet + facet normal -0.0133617 -0.00436237 -0.999901 + outer loop + vertex 281.893 96.9159 298.993 + vertex 281.175 102.768 298.977 + vertex 295.517 98.7182 298.803 + endloop + endfacet + facet normal -0.00303265 -0.00276798 -0.999992 + outer loop + vertex 265.275 95.2893 299.048 + vertex 264.597 101.137 299.034 + vertex 281.893 96.9159 298.993 + endloop + endfacet + facet normal -0.00235801 -0.00965909 -0.999951 + outer loop + vertex 282.637 91.0508 299.048 + vertex 265.275 95.2893 299.048 + vertex 281.893 96.9159 298.993 + endloop + endfacet + facet normal -0.0126437 -0.0109623 -0.99986 + outer loop + vertex 282.637 91.0508 299.048 + vertex 281.893 96.9159 298.993 + vertex 296.314 92.8589 298.855 + endloop + endfacet + facet normal -0.00227366 -0.00931357 -0.999954 + outer loop + vertex 265.953 89.4226 299.101 + vertex 265.275 95.2893 299.048 + vertex 282.637 91.0508 299.048 + endloop + endfacet + facet normal -0.000987717 -0.022484 -0.999747 + outer loop + vertex 283.408 85.1522 299.18 + vertex 265.953 89.4226 299.101 + vertex 282.637 91.0508 299.048 + endloop + endfacet + facet normal -0.0112859 -0.0238271 -0.999652 + outer loop + vertex 283.408 85.1522 299.18 + vertex 282.637 91.0508 299.048 + vertex 297.17 86.9752 298.981 + endloop + endfacet + facet normal -0.000910496 -0.0221685 -0.999754 + outer loop + vertex 266.675 83.5121 299.232 + vertex 265.953 89.4226 299.101 + vertex 283.408 85.1522 299.18 + endloop + endfacet + facet normal 0.00120722 -0.0437525 -0.999042 + outer loop + vertex 284.257 79.233 299.44 + vertex 266.675 83.5121 299.232 + vertex 283.408 85.1522 299.18 + endloop + endfacet + facet normal -0.00878434 -0.0451818 -0.99894 + outer loop + vertex 284.257 79.233 299.44 + vertex 283.408 85.1522 299.18 + vertex 298.082 81.0867 299.235 + endloop + endfacet + facet normal 0.00123875 -0.0436232 -0.999047 + outer loop + vertex 267.4 77.5718 299.492 + vertex 266.675 83.5121 299.232 + vertex 284.257 79.233 299.44 + endloop + endfacet + facet normal 0.00439827 -0.0756238 -0.997127 + outer loop + vertex 285.08 73.3642 299.889 + vertex 267.4 77.5718 299.492 + vertex 284.257 79.233 299.44 + endloop + endfacet + facet normal 0.00324221 -0.0433787 -0.999053 + outer loop + vertex 267.4 77.5718 299.492 + vertex 247.193 81.9126 299.238 + vertex 266.675 83.5121 299.232 + endloop + endfacet + facet normal 0.0014638 -0.0217204 -0.999763 + outer loop + vertex 247.193 81.9126 299.238 + vertex 246.582 87.8302 299.108 + vertex 266.675 83.5121 299.232 + endloop + endfacet + facet normal 0.00160554 -0.0217058 -0.999763 + outer loop + vertex 247.193 81.9126 299.238 + vertex 225.367 86.1667 299.111 + vertex 246.582 87.8302 299.108 + endloop + endfacet + facet normal 0.000559486 -0.00836475 -0.999965 + outer loop + vertex 225.367 86.1667 299.111 + vertex 224.815 92.0326 299.061 + vertex 246.582 87.8302 299.108 + endloop + endfacet + facet normal 0.000546579 -0.00843159 -0.999964 + outer loop + vertex 246.582 87.8302 299.108 + vertex 224.815 92.0326 299.061 + vertex 245.944 93.6955 299.059 + endloop + endfacet + facet normal 0.000324925 -0.00845571 -0.999964 + outer loop + vertex 246.582 87.8302 299.108 + vertex 245.944 93.6955 299.059 + vertex 265.953 89.4226 299.101 + endloop + endfacet + facet normal 3.44391e-05 -0.00192416 -0.999998 + outer loop + vertex 224.815 92.0326 299.061 + vertex 224.257 97.8751 299.05 + vertex 245.944 93.6955 299.059 + endloop + endfacet + facet normal 1.09908e-05 -0.00204582 -0.999998 + outer loop + vertex 245.944 93.6955 299.059 + vertex 224.257 97.8751 299.05 + vertex 245.341 99.5397 299.047 + endloop + endfacet + facet normal -0.000369575 -0.00208511 -0.999998 + outer loop + vertex 245.944 93.6955 299.059 + vertex 245.341 99.5397 299.047 + vertex 265.275 95.2893 299.048 + endloop + endfacet + facet normal -0.000178379 0.000352624 -1 + outer loop + vertex 224.257 97.8751 299.05 + vertex 223.704 103.74 299.052 + vertex 245.341 99.5397 299.047 + endloop + endfacet + facet normal -0.000183912 0.000324121 -1 + outer loop + vertex 245.341 99.5397 299.047 + vertex 223.704 103.74 299.052 + vertex 244.725 105.405 299.049 + endloop + endfacet + facet normal -0.000678686 0.00027222 -1 + outer loop + vertex 245.341 99.5397 299.047 + vertex 244.725 105.405 299.049 + vertex 264.597 101.137 299.034 + endloop + endfacet + facet normal -0.000206148 0.000604881 -1 + outer loop + vertex 223.704 103.74 299.052 + vertex 223.149 109.656 299.056 + vertex 244.725 105.405 299.049 + endloop + endfacet + facet normal -0.000188923 0.000692312 -1 + outer loop + vertex 244.725 105.405 299.049 + vertex 223.149 109.656 299.056 + vertex 244.106 111.319 299.053 + endloop + endfacet + facet normal -0.000772732 0.000631199 -1 + outer loop + vertex 244.725 105.405 299.049 + vertex 244.106 111.319 299.053 + vertex 263.923 107.006 299.035 + endloop + endfacet + facet normal -0.000157197 0.000292613 -1 + outer loop + vertex 223.149 109.656 299.056 + vertex 222.596 115.616 299.058 + vertex 244.106 111.319 299.053 + endloop + endfacet + facet normal -0.000132448 0.000416501 -1 + outer loop + vertex 244.106 111.319 299.053 + vertex 222.596 115.616 299.058 + vertex 243.485 117.276 299.055 + endloop + endfacet + facet normal -0.000772307 0.000349785 -1 + outer loop + vertex 244.106 111.319 299.053 + vertex 243.485 117.276 299.055 + vertex 263.246 112.921 299.039 + endloop + endfacet + facet normal -0.000110719 0.000143107 -1 + outer loop + vertex 222.596 115.616 299.058 + vertex 222.048 121.589 299.058 + vertex 243.485 117.276 299.055 + endloop + endfacet + facet normal -0.000104727 0.000172886 -1 + outer loop + vertex 243.485 117.276 299.055 + vertex 222.048 121.589 299.058 + vertex 242.847 123.244 299.057 + endloop + endfacet + facet normal -0.00073824 0.000105098 -1 + outer loop + vertex 243.485 117.276 299.055 + vertex 242.847 123.244 299.057 + vertex 262.563 118.875 299.042 + endloop + endfacet + facet normal -0.000103646 0.000159293 -1 + outer loop + vertex 222.048 121.589 299.058 + vertex 221.481 127.542 299.059 + vertex 242.847 123.244 299.057 + endloop + endfacet + facet normal -9.22905e-05 0.000215739 -1 + outer loop + vertex 242.847 123.244 299.057 + vertex 221.481 127.542 299.059 + vertex 242.196 129.19 299.058 + endloop + endfacet + facet normal -0.000706996 0.000148471 -1 + outer loop + vertex 242.847 123.244 299.057 + vertex 242.196 129.19 299.058 + vertex 261.872 124.837 299.043 + endloop + endfacet + facet normal -9.89241e-05 0.000299147 -1 + outer loop + vertex 221.481 127.542 299.059 + vertex 220.88 133.465 299.061 + vertex 242.196 129.19 299.058 + endloop + endfacet + facet normal -7.78971e-05 0.000403995 -1 + outer loop + vertex 242.196 129.19 299.058 + vertex 220.88 133.465 299.061 + vertex 241.507 135.1 299.06 + endloop + endfacet + facet normal -0.000694471 0.000332165 -1 + outer loop + vertex 242.196 129.19 299.058 + vertex 241.507 135.1 299.06 + vertex 261.146 130.773 299.045 + endloop + endfacet + facet normal -0.000110097 0.00081009 -1 + outer loop + vertex 220.88 133.465 299.061 + vertex 220.264 139.371 299.066 + vertex 241.507 135.1 299.06 + endloop + endfacet + facet normal -4.91271e-05 0.00111339 -0.999999 + outer loop + vertex 241.507 135.1 299.06 + vertex 220.264 139.371 299.066 + vertex 240.855 140.992 299.067 + endloop + endfacet + facet normal -0.000689416 0.00104248 -0.999999 + outer loop + vertex 241.507 135.1 299.06 + vertex 240.855 140.992 299.067 + vertex 260.393 136.671 299.049 + endloop + endfacet + facet normal -0.000254603 0.00372316 -0.999993 + outer loop + vertex 220.264 139.371 299.066 + vertex 219.701 145.291 299.088 + vertex 240.855 140.992 299.067 + endloop + endfacet + facet normal -0.000182791 0.00407649 -0.999992 + outer loop + vertex 240.855 140.992 299.067 + vertex 219.701 145.291 299.088 + vertex 240.27 146.91 299.091 + endloop + endfacet + facet normal -0.000837596 0.00401176 -0.999992 + outer loop + vertex 240.855 140.992 299.067 + vertex 240.27 146.91 299.091 + vertex 259.716 142.556 299.057 + endloop + endfacet + facet normal -0.00134304 0.0188211 -0.999822 + outer loop + vertex 219.701 145.291 299.088 + vertex 219.211 151.293 299.202 + vertex 240.27 146.91 299.091 + endloop + endfacet + facet normal -0.00144782 0.018318 -0.999831 + outer loop + vertex 240.27 146.91 299.091 + vertex 219.211 151.293 299.202 + vertex 239.798 152.946 299.202 + endloop + endfacet + facet normal -0.00210451 0.0182666 -0.999831 + outer loop + vertex 240.27 146.91 299.091 + vertex 239.798 152.946 299.202 + vertex 259.136 148.502 299.081 + endloop + endfacet + facet normal -0.00469178 0.0587397 -0.998262 + outer loop + vertex 219.211 151.293 299.202 + vertex 218.273 157.446 299.568 + vertex 239.798 152.946 299.202 + endloop + endfacet + facet normal -0.00546059 0.0550795 -0.998467 + outer loop + vertex 239.798 152.946 299.202 + vertex 218.273 157.446 299.568 + vertex 240.263 159.25 299.548 + endloop + endfacet + facet normal -0.00603756 0.0551218 -0.998461 + outer loop + vertex 239.798 152.946 299.202 + vertex 240.263 159.25 299.548 + vertex 258.774 154.59 299.178 + endloop + endfacet + facet normal -0.00396312 0.0588505 -0.998259 + outer loop + vertex 219.211 151.293 299.202 + vertex 197.909 155.805 299.553 + vertex 218.273 157.446 299.568 + endloop + endfacet + facet normal -0.0035935 0.0605879 -0.998156 + outer loop + vertex 198.061 149.607 299.176 + vertex 197.909 155.805 299.553 + vertex 219.211 151.293 299.202 + endloop + endfacet + facet normal -0.0020961 0.0606246 -0.998158 + outer loop + vertex 198.061 149.607 299.176 + vertex 176.255 154.042 299.491 + vertex 197.909 155.805 299.553 + endloop + endfacet + facet normal -0.00231585 0.0595486 -0.998223 + outer loop + vertex 177.104 147.906 299.123 + vertex 176.255 154.042 299.491 + vertex 198.061 149.607 299.176 + endloop + endfacet + facet normal 0.00107915 0.0177857 -0.999841 + outer loop + vertex 198.5 143.603 299.069 + vertex 177.104 147.906 299.123 + vertex 198.061 149.607 299.176 + endloop + endfacet + facet normal -0.000515704 0.0176691 -0.999844 + outer loop + vertex 198.5 143.603 299.069 + vertex 198.061 149.607 299.176 + vertex 219.701 145.291 299.088 + endloop + endfacet + facet normal 0.00105097 0.0176456 -0.999844 + outer loop + vertex 177.494 141.884 299.017 + vertex 177.104 147.906 299.123 + vertex 198.5 143.603 299.069 + endloop + endfacet + facet normal 0.00220089 0.00360407 -0.999991 + outer loop + vertex 199.015 137.666 299.049 + vertex 177.494 141.884 299.017 + vertex 198.5 143.603 299.069 + endloop + endfacet + facet normal 0.000521144 0.00345825 -0.999994 + outer loop + vertex 199.015 137.666 299.049 + vertex 198.5 143.603 299.069 + vertex 220.264 139.371 299.066 + endloop + endfacet + facet normal 0.00209284 0.00305269 -0.999993 + outer loop + vertex 177.971 135.939 299 + vertex 177.494 141.884 299.017 + vertex 199.015 137.666 299.049 + endloop + endfacet + facet normal 0.00227534 0.000829713 -0.999997 + outer loop + vertex 199.563 131.75 299.046 + vertex 177.971 135.939 299 + vertex 199.015 137.666 299.049 + endloop + endfacet + facet normal 0.00068525 0.000682433 -1 + outer loop + vertex 199.563 131.75 299.046 + vertex 199.015 137.666 299.049 + vertex 220.88 133.465 299.061 + endloop + endfacet + facet normal 0.00225216 0.000710242 -0.999997 + outer loop + vertex 178.429 130.017 298.997 + vertex 177.971 135.939 299 + vertex 199.563 131.75 299.046 + endloop + endfacet + facet normal 0.00226343 0.00057281 -0.999997 + outer loop + vertex 200.08 125.821 299.043 + vertex 178.429 130.017 298.997 + vertex 199.563 131.75 299.046 + endloop + endfacet + facet normal 0.000720502 0.000438471 -1 + outer loop + vertex 200.08 125.821 299.043 + vertex 199.563 131.75 299.046 + vertex 221.481 127.542 299.059 + endloop + endfacet + facet normal 0.0022229 0.00036372 -0.999997 + outer loop + vertex 178.851 124.086 298.995 + vertex 178.429 130.017 298.997 + vertex 200.08 125.821 299.043 + endloop + endfacet + facet normal 0.0022325 0.000246257 -0.999997 + outer loop + vertex 200.559 119.863 299.043 + vertex 178.851 124.086 298.995 + vertex 200.08 125.821 299.043 + endloop + endfacet + facet normal 0.000714312 0.000124076 -1 + outer loop + vertex 200.559 119.863 299.043 + vertex 200.08 125.821 299.043 + vertex 222.048 121.589 299.058 + endloop + endfacet + facet normal 0.0022165 0.00016403 -0.999998 + outer loop + vertex 179.251 118.123 298.995 + vertex 178.851 124.086 298.995 + vertex 200.559 119.863 299.043 + endloop + endfacet + facet normal 0.00221413 0.000193069 -0.999998 + outer loop + vertex 201.039 113.885 299.043 + vertex 179.251 118.123 298.995 + vertex 200.559 119.863 299.043 + endloop + endfacet + facet normal 0.000678159 6.97595e-05 -1 + outer loop + vertex 201.039 113.885 299.043 + vertex 200.559 119.863 299.043 + vertex 222.596 115.616 299.058 + endloop + endfacet + facet normal 0.00221776 0.000211719 -0.999998 + outer loop + vertex 179.67 112.142 298.995 + vertex 179.251 118.123 298.995 + vertex 201.039 113.885 299.043 + endloop + endfacet + facet normal 0.00220035 0.000425133 -0.999997 + outer loop + vertex 201.526 107.921 299.041 + vertex 179.67 112.142 298.995 + vertex 201.039 113.885 299.043 + endloop + endfacet + facet normal 0.00064083 0.000297888 -1 + outer loop + vertex 201.526 107.921 299.041 + vertex 201.039 113.885 299.043 + vertex 223.149 109.656 299.056 + endloop + endfacet + facet normal 0.0021609 0.000220859 -0.999998 + outer loop + vertex 180.083 106.173 298.995 + vertex 179.67 112.142 298.995 + vertex 201.526 107.921 299.041 + endloop + endfacet + facet normal 0.00212687 0.000638169 -0.999998 + outer loop + vertex 202.01 102.002 299.039 + vertex 180.083 106.173 298.995 + vertex 201.526 107.921 299.041 + endloop + endfacet + facet normal 0.000577994 0.000511352 -1 + outer loop + vertex 202.01 102.002 299.039 + vertex 201.526 107.921 299.041 + vertex 223.704 103.74 299.052 + endloop + endfacet + facet normal 0.00210438 0.000519895 -0.999998 + outer loop + vertex 180.501 100.251 298.992 + vertex 180.083 106.173 298.995 + vertex 202.01 102.002 299.039 + endloop + endfacet + facet normal 0.00211463 0.000393913 -0.999998 + outer loop + vertex 202.497 96.1358 299.037 + vertex 180.501 100.251 298.992 + vertex 202.01 102.002 299.039 + endloop + endfacet + facet normal 0.000555254 0.000264555 -1 + outer loop + vertex 202.497 96.1358 299.037 + vertex 202.01 102.002 299.039 + vertex 224.257 97.8751 299.05 + endloop + endfacet + facet normal 0.00208106 0.000214461 -0.999998 + outer loop + vertex 180.916 94.3819 298.992 + vertex 180.501 100.251 298.992 + vertex 202.497 96.1358 299.037 + endloop + endfacet + facet normal 0.00224668 -0.00182354 -0.999996 + outer loop + vertex 202.984 90.2923 299.049 + vertex 180.916 94.3819 298.992 + vertex 202.497 96.1358 299.037 + endloop + endfacet + facet normal 0.000707739 -0.00195171 -0.999998 + outer loop + vertex 202.984 90.2923 299.049 + vertex 202.497 96.1358 299.037 + vertex 224.815 92.0326 299.061 + endloop + endfacet + facet normal 0.00220895 -0.00202715 -0.999996 + outer loop + vertex 181.341 88.5382 299.005 + vertex 180.916 94.3819 298.992 + vertex 202.984 90.2923 299.049 + endloop + endfacet + facet normal 0.00271082 -0.00821999 -0.999963 + outer loop + vertex 203.48 84.4269 299.099 + vertex 181.341 88.5382 299.005 + vertex 202.984 90.2923 299.049 + endloop + endfacet + facet normal 0.00120591 -0.00834732 -0.999964 + outer loop + vertex 203.48 84.4269 299.099 + vertex 202.984 90.2923 299.049 + vertex 225.367 86.1667 299.111 + endloop + endfacet + facet normal 0.00221962 -0.0211014 -0.999775 + outer loop + vertex 225.944 80.2486 299.237 + vertex 203.48 84.4269 299.099 + vertex 225.367 86.1667 299.111 + endloop + endfacet + facet normal 0.00224276 -0.0209771 -0.999777 + outer loop + vertex 203.99 78.5079 299.224 + vertex 203.48 84.4269 299.099 + vertex 225.944 80.2486 299.237 + endloop + endfacet + facet normal 0.00393775 -0.0423597 -0.999095 + outer loop + vertex 226.527 74.2875 299.492 + vertex 203.99 78.5079 299.224 + vertex 225.944 80.2486 299.237 + endloop + endfacet + facet normal 0.00348598 -0.0424039 -0.999094 + outer loop + vertex 226.527 74.2875 299.492 + vertex 225.944 80.2486 299.237 + vertex 247.851 75.96 299.495 + endloop + endfacet + facet normal 0.00597845 -0.0741863 -0.997226 + outer loop + vertex 248.525 70.0312 299.94 + vertex 226.527 74.2875 299.492 + vertex 247.851 75.96 299.495 + endloop + endfacet + facet normal 0.0034089 -0.0427966 -0.999078 + outer loop + vertex 247.851 75.96 299.495 + vertex 225.944 80.2486 299.237 + vertex 247.193 81.9126 299.238 + endloop + endfacet + facet normal 0.00396037 -0.0422391 -0.9991 + outer loop + vertex 204.523 72.5421 299.478 + vertex 203.99 78.5079 299.224 + vertex 226.527 74.2875 299.492 + endloop + endfacet + facet normal 0.00643723 -0.0734769 -0.997276 + outer loop + vertex 227.136 68.3449 299.934 + vertex 204.523 72.5421 299.478 + vertex 226.527 74.2875 299.492 + endloop + endfacet + facet normal 0.00535435 -0.0421145 -0.999098 + outer loop + vertex 204.523 72.5421 299.478 + vertex 182.212 76.7505 299.181 + vertex 203.99 78.5079 299.224 + endloop + endfacet + facet normal 0.00365431 -0.0210312 -0.999772 + outer loop + vertex 182.212 76.7505 299.181 + vertex 181.767 82.6719 299.055 + vertex 203.99 78.5079 299.224 + endloop + endfacet + facet normal 0.00543274 -0.0208973 -0.999767 + outer loop + vertex 182.212 76.7505 299.181 + vertex 160.623 80.9727 298.976 + vertex 181.767 82.6719 299.055 + endloop + endfacet + facet normal 0.00443095 -0.0084233 -0.999955 + outer loop + vertex 160.623 80.9727 298.976 + vertex 160.262 86.8399 298.925 + vertex 181.767 82.6719 299.055 + endloop + endfacet + facet normal 0.00446366 -0.00825458 -0.999956 + outer loop + vertex 181.767 82.6719 299.055 + vertex 160.262 86.8399 298.925 + vertex 181.341 88.5382 299.005 + endloop + endfacet + facet normal 0.00396562 -0.00207096 -0.99999 + outer loop + vertex 160.262 86.8399 298.925 + vertex 159.913 92.686 298.911 + vertex 181.341 88.5382 299.005 + endloop + endfacet + facet normal 0.00505817 -0.00200584 -0.999985 + outer loop + vertex 160.262 86.8399 298.925 + vertex 139.458 91.0973 298.811 + vertex 159.913 92.686 298.911 + endloop + endfacet + facet normal 0.0048872 0.000195621 -0.999988 + outer loop + vertex 139.458 91.0973 298.811 + vertex 139.173 96.9695 298.811 + vertex 159.913 92.686 298.911 + endloop + endfacet + facet normal 0.00489902 0.000252839 -0.999988 + outer loop + vertex 159.913 92.686 298.911 + vertex 139.173 96.9695 298.811 + vertex 159.567 98.5578 298.911 + endloop + endfacet + facet normal 0.00383088 0.00018978 -0.999993 + outer loop + vertex 159.913 92.686 298.911 + vertex 159.567 98.5578 298.911 + vertex 180.916 94.3819 298.992 + endloop + endfacet + facet normal 0.00488093 0.000485057 -0.999988 + outer loop + vertex 139.173 96.9695 298.811 + vertex 138.89 102.897 298.812 + vertex 159.567 98.5578 298.911 + endloop + endfacet + facet normal 0.00489953 0.0005737 -0.999988 + outer loop + vertex 159.567 98.5578 298.911 + vertex 138.89 102.897 298.812 + vertex 159.216 104.482 298.913 + endloop + endfacet + facet normal 0.00384642 0.000511289 -0.999992 + outer loop + vertex 159.567 98.5578 298.911 + vertex 159.216 104.482 298.913 + vertex 180.501 100.251 298.992 + endloop + endfacet + facet normal 0.0049206 0.000303557 -0.999988 + outer loop + vertex 138.89 102.897 298.812 + vertex 138.602 108.871 298.813 + vertex 159.216 104.482 298.913 + endloop + endfacet + facet normal 0.00493781 0.000384415 -0.999988 + outer loop + vertex 159.216 104.482 298.913 + vertex 138.602 108.871 298.813 + vertex 158.862 110.453 298.913 + endloop + endfacet + facet normal 0.00389909 0.0003229 -0.999992 + outer loop + vertex 159.216 104.482 298.913 + vertex 158.862 110.453 298.913 + vertex 180.083 106.173 298.995 + endloop + endfacet + facet normal 0.0049502 0.00022583 -0.999988 + outer loop + vertex 138.602 108.871 298.813 + vertex 138.317 114.86 298.813 + vertex 158.862 110.453 298.913 + endloop + endfacet + facet normal 0.00495192 0.000233868 -0.999988 + outer loop + vertex 158.862 110.453 298.913 + vertex 138.317 114.86 298.813 + vertex 158.518 116.439 298.913 + endloop + endfacet + facet normal 0.00391633 0.000174297 -0.999992 + outer loop + vertex 158.862 110.453 298.913 + vertex 158.518 116.439 298.913 + vertex 179.67 112.142 298.995 + endloop + endfacet + facet normal 0.00495236 0.00022835 -0.999988 + outer loop + vertex 138.317 114.86 298.813 + vertex 138.042 120.829 298.813 + vertex 158.518 116.439 298.913 + endloop + endfacet + facet normal 0.00496917 0.000306788 -0.999988 + outer loop + vertex 158.518 116.439 298.913 + vertex 138.042 120.829 298.813 + vertex 158.18 122.405 298.913 + endloop + endfacet + facet normal 0.0039554 0.000249418 -0.999992 + outer loop + vertex 158.518 116.439 298.913 + vertex 158.18 122.405 298.913 + vertex 179.251 118.123 298.995 + endloop + endfacet + facet normal 0.00497913 0.00017951 -0.999988 + outer loop + vertex 138.042 120.829 298.813 + vertex 137.779 126.765 298.812 + vertex 158.18 122.405 298.913 + endloop + endfacet + facet normal 0.00500934 0.000320858 -0.999987 + outer loop + vertex 158.18 122.405 298.913 + vertex 137.779 126.765 298.812 + vertex 157.849 128.339 298.913 + endloop + endfacet + facet normal 0.00396335 0.000262451 -0.999992 + outer loop + vertex 158.18 122.405 298.913 + vertex 157.849 128.339 298.913 + vertex 178.851 124.086 298.995 + endloop + endfacet + facet normal 0.00500098 0.000427448 -0.999987 + outer loop + vertex 137.779 126.765 298.812 + vertex 137.504 132.687 298.813 + vertex 157.849 128.339 298.913 + endloop + endfacet + facet normal 0.00506417 0.000723178 -0.999987 + outer loop + vertex 157.849 128.339 298.913 + vertex 137.504 132.687 298.813 + vertex 157.479 134.26 298.916 + endloop + endfacet + facet normal 0.00399605 0.000656525 -0.999992 + outer loop + vertex 157.849 128.339 298.913 + vertex 157.479 134.26 298.916 + vertex 178.429 130.017 298.997 + endloop + endfacet + facet normal 0.00487603 0.00311114 -0.999983 + outer loop + vertex 137.504 132.687 298.813 + vertex 137.183 138.634 298.83 + vertex 157.479 134.26 298.916 + endloop + endfacet + facet normal 0.00489198 0.00318514 -0.999983 + outer loop + vertex 157.479 134.26 298.916 + vertex 137.183 138.634 298.83 + vertex 157.069 140.207 298.933 + endloop + endfacet + facet normal 0.00384934 0.0031133 -0.999988 + outer loop + vertex 157.479 134.26 298.916 + vertex 157.069 140.207 298.933 + vertex 177.971 135.939 299 + endloop + endfacet + facet normal 0.00375803 0.0175066 -0.99984 + outer loop + vertex 137.183 138.634 298.83 + vertex 136.884 144.666 298.935 + vertex 157.069 140.207 298.933 + endloop + endfacet + facet normal 0.00382276 0.0177997 -0.999834 + outer loop + vertex 157.069 140.207 298.933 + vertex 136.884 144.666 298.935 + vertex 156.767 146.245 299.039 + endloop + endfacet + facet normal 0.00267145 0.0177421 -0.999839 + outer loop + vertex 157.069 140.207 298.933 + vertex 156.767 146.245 299.039 + vertex 177.494 141.884 299.017 + endloop + endfacet + facet normal 0.000687226 0.0571949 -0.998363 + outer loop + vertex 136.884 144.666 298.935 + vertex 136.739 150.846 299.289 + vertex 156.767 146.245 299.039 + endloop + endfacet + facet normal 0.00087143 0.0579941 -0.998317 + outer loop + vertex 156.767 146.245 299.039 + vertex 136.739 150.846 299.289 + vertex 156.849 152.45 299.4 + endloop + endfacet + facet normal -0.000621289 0.0580139 -0.998316 + outer loop + vertex 156.767 146.245 299.039 + vertex 156.849 152.45 299.4 + vertex 177.104 147.906 299.123 + endloop + endfacet + facet normal 0.000857475 0.0571988 -0.998362 + outer loop + vertex 136.884 144.666 298.935 + vertex 117.299 149.4 299.189 + vertex 136.739 150.846 299.289 + endloop + endfacet + facet normal 0.000575028 0.056034 -0.998429 + outer loop + vertex 117.323 143.228 298.843 + vertex 117.299 149.4 299.189 + vertex 136.884 144.666 298.935 + endloop + endfacet + facet normal -0.000243482 0.0560309 -0.998429 + outer loop + vertex 117.323 143.228 298.843 + vertex 97.6157 148.106 299.121 + vertex 117.299 149.4 299.189 + endloop + endfacet + facet normal -0.000347671 0.0556113 -0.998452 + outer loop + vertex 97.8156 141.957 298.779 + vertex 97.6157 148.106 299.121 + vertex 117.323 143.228 298.843 + endloop + endfacet + facet normal 0.00211699 0.0178518 -0.999838 + outer loop + vertex 117.574 137.195 298.736 + vertex 97.8156 141.957 298.779 + vertex 117.323 143.228 298.843 + endloop + endfacet + facet normal 0.00351279 0.0179099 -0.999833 + outer loop + vertex 117.574 137.195 298.736 + vertex 117.323 143.228 298.843 + vertex 137.183 138.634 298.83 + endloop + endfacet + facet normal 0.00198897 0.0173207 -0.999848 + outer loop + vertex 98.0345 135.932 298.675 + vertex 97.8156 141.957 298.779 + vertex 117.574 137.195 298.736 + endloop + endfacet + facet normal 0.0029336 0.00272163 -0.999992 + outer loop + vertex 117.804 131.251 298.72 + vertex 98.0345 135.932 298.675 + vertex 117.574 137.195 298.736 + endloop + endfacet + facet normal 0.00452955 0.00278341 -0.999986 + outer loop + vertex 117.804 131.251 298.72 + vertex 117.574 137.195 298.736 + vertex 137.504 132.687 298.813 + endloop + endfacet + facet normal 0.00289687 0.00256649 -0.999993 + outer loop + vertex 98.1802 129.988 298.66 + vertex 98.0345 135.932 298.675 + vertex 117.804 131.251 298.72 + endloop + endfacet + facet normal 0.00305111 0.000169536 -0.999995 + outer loop + vertex 118.003 125.329 298.72 + vertex 98.1802 129.988 298.66 + vertex 117.804 131.251 298.72 + endloop + endfacet + facet normal 0.00465961 0.000223595 -0.999989 + outer loop + vertex 118.003 125.329 298.72 + vertex 117.804 131.251 298.72 + vertex 137.779 126.765 298.812 + endloop + endfacet + facet normal 0.00307606 0.000275691 -0.999995 + outer loop + vertex 98.3242 124.064 298.659 + vertex 98.1802 129.988 298.66 + vertex 118.003 125.329 298.72 + endloop + endfacet + facet normal 0.00308756 9.68273e-05 -0.999995 + outer loop + vertex 118.209 119.39 298.72 + vertex 98.3242 124.064 298.659 + vertex 118.003 125.329 298.72 + endloop + endfacet + facet normal 0.00466065 0.000151396 -0.999989 + outer loop + vertex 118.209 119.39 298.72 + vertex 118.003 125.329 298.72 + vertex 138.042 120.829 298.813 + endloop + endfacet + facet normal 0.003103 0.000162488 -0.999995 + outer loop + vertex 98.4877 118.124 298.659 + vertex 98.3242 124.064 298.659 + vertex 118.209 119.39 298.72 + endloop + endfacet + facet normal 0.00310271 0.000167 -0.999995 + outer loop + vertex 118.432 113.418 298.72 + vertex 98.4877 118.124 298.659 + vertex 118.209 119.39 298.72 + endloop + endfacet + facet normal 0.0046584 0.00022511 -0.999989 + outer loop + vertex 118.432 113.418 298.72 + vertex 118.209 119.39 298.72 + vertex 138.317 114.86 298.813 + endloop + endfacet + facet normal 0.00309694 0.000142568 -0.999995 + outer loop + vertex 98.6641 112.151 298.658 + vertex 98.4877 118.124 298.659 + vertex 118.432 113.418 298.72 + endloop + endfacet + facet normal 0.00310199 6.38496e-05 -0.999995 + outer loop + vertex 118.664 107.429 298.72 + vertex 98.6641 112.151 298.658 + vertex 118.432 113.418 298.72 + endloop + endfacet + facet normal 0.00463936 0.000123273 -0.999989 + outer loop + vertex 118.664 107.429 298.72 + vertex 118.432 113.418 298.72 + vertex 138.602 108.871 298.813 + endloop + endfacet + facet normal 0.00310145 6.15713e-05 -0.999995 + outer loop + vertex 98.8421 106.159 298.658 + vertex 98.6641 112.151 298.658 + vertex 118.664 107.429 298.72 + endloop + endfacet + facet normal 0.00309258 0.000200049 -0.999995 + outer loop + vertex 118.892 101.453 298.719 + vertex 98.8421 106.159 298.658 + vertex 118.664 107.429 298.72 + endloop + endfacet + facet normal 0.00462042 0.000258517 -0.999989 + outer loop + vertex 118.892 101.453 298.719 + vertex 118.664 107.429 298.72 + vertex 138.89 102.897 298.812 + endloop + endfacet + facet normal 0.00307658 0.000131888 -0.999995 + outer loop + vertex 99.019 100.184 298.658 + vertex 98.8421 106.159 298.658 + vertex 118.892 101.453 298.719 + endloop + endfacet + facet normal 0.00306144 0.000368948 -0.999995 + outer loop + vertex 119.118 95.5255 298.718 + vertex 99.019 100.184 298.658 + vertex 118.892 101.453 298.719 + endloop + endfacet + facet normal 0.00459517 0.000427388 -0.999989 + outer loop + vertex 119.118 95.5255 298.718 + vertex 118.892 101.453 298.719 + vertex 139.173 96.9695 298.811 + endloop + endfacet + facet normal 0.00306583 0.000387876 -0.999995 + outer loop + vertex 99.1917 94.2554 298.656 + vertex 99.019 100.184 298.658 + vertex 119.118 95.5255 298.718 + endloop + endfacet + facet normal 0.00308308 0.000117229 -0.999995 + outer loop + vertex 119.342 89.6507 298.718 + vertex 99.1917 94.2554 298.656 + vertex 119.118 95.5255 298.718 + endloop + endfacet + facet normal 0.0046113 0.000175338 -0.999989 + outer loop + vertex 119.342 89.6507 298.718 + vertex 119.118 95.5255 298.718 + vertex 139.458 91.0973 298.811 + endloop + endfacet + facet normal 0.0047786 -0.00215131 -0.999986 + outer loop + vertex 139.744 85.2504 298.825 + vertex 119.342 89.6507 298.718 + vertex 139.458 91.0973 298.811 + endloop + endfacet + facet normal 0.00480716 -0.00201887 -0.999986 + outer loop + vertex 119.564 83.8015 298.731 + vertex 119.342 89.6507 298.718 + vertex 139.744 85.2504 298.825 + endloop + endfacet + facet normal 0.00527386 -0.00852147 -0.99995 + outer loop + vertex 140.041 79.3819 298.876 + vertex 119.564 83.8015 298.731 + vertex 139.744 85.2504 298.825 + endloop + endfacet + facet normal 0.00548084 -0.00851099 -0.999949 + outer loop + vertex 140.041 79.3819 298.876 + vertex 139.744 85.2504 298.825 + vertex 160.623 80.9727 298.976 + endloop + endfacet + facet normal 0.00645169 -0.0210847 -0.999757 + outer loop + vertex 161.007 75.0503 299.103 + vertex 140.041 79.3819 298.876 + vertex 160.623 80.9727 298.976 + endloop + endfacet + facet normal 0.00642559 -0.0212109 -0.999754 + outer loop + vertex 140.357 73.4578 299.004 + vertex 140.041 79.3819 298.876 + vertex 161.007 75.0503 299.103 + endloop + endfacet + facet normal 0.00804449 -0.0422466 -0.999075 + outer loop + vertex 161.423 69.0795 299.359 + vertex 140.357 73.4578 299.004 + vertex 161.007 75.0503 299.103 + endloop + endfacet + facet normal 0.0070816 -0.0423139 -0.999079 + outer loop + vertex 161.423 69.0795 299.359 + vertex 161.007 75.0503 299.103 + vertex 182.7 70.7828 299.438 + endloop + endfacet + facet normal 0.00952123 -0.0728712 -0.997296 + outer loop + vertex 183.211 64.824 299.878 + vertex 161.423 69.0795 299.359 + vertex 182.7 70.7828 299.438 + endloop + endfacet + facet normal 0.00707802 -0.0423321 -0.999079 + outer loop + vertex 182.7 70.7828 299.438 + vertex 161.007 75.0503 299.103 + vertex 182.212 76.7505 299.181 + endloop + endfacet + facet normal 0.00793036 -0.042794 -0.999052 + outer loop + vertex 140.71 67.4866 299.263 + vertex 140.357 73.4578 299.004 + vertex 161.423 69.0795 299.359 + endloop + endfacet + facet normal 0.0102555 -0.073138 -0.997269 + outer loop + vertex 161.88 63.116 299.801 + vertex 140.71 67.4866 299.263 + vertex 161.423 69.0795 299.359 + endloop + endfacet + facet normal 0.00752841 -0.0428178 -0.999055 + outer loop + vertex 140.71 67.4866 299.263 + vertex 120.059 72.0109 298.913 + vertex 140.357 73.4578 299.004 + endloop + endfacet + facet normal 0.00601538 -0.0215488 -0.99975 + outer loop + vertex 120.059 72.0109 298.913 + vertex 119.805 77.9346 298.784 + vertex 140.357 73.4578 299.004 + endloop + endfacet + facet normal 0.00451817 -0.0216132 -0.999756 + outer loop + vertex 120.059 72.0109 298.913 + vertex 99.7166 76.663 298.721 + vertex 119.805 77.9346 298.784 + endloop + endfacet + facet normal 0.00369179 -0.00854836 -0.999957 + outer loop + vertex 99.7166 76.663 298.721 + vertex 99.5366 82.5327 298.67 + vertex 119.805 77.9346 298.784 + endloop + endfacet + facet normal 0.00360666 -0.00892353 -0.999954 + outer loop + vertex 119.805 77.9346 298.784 + vertex 99.5366 82.5327 298.67 + vertex 119.564 83.8015 298.731 + endloop + endfacet + facet normal 0.00318292 -0.00223298 -0.999992 + outer loop + vertex 99.5366 82.5327 298.67 + vertex 99.3632 88.3808 298.656 + vertex 119.564 83.8015 298.731 + endloop + endfacet + facet normal 0.00103574 -0.00229666 -0.999997 + outer loop + vertex 99.5366 82.5327 298.67 + vertex 79.4228 87.3209 298.638 + vertex 99.3632 88.3808 298.656 + endloop + endfacet + facet normal 0.000913726 -1.04659e-06 -1 + outer loop + vertex 79.4228 87.3209 298.638 + vertex 79.2959 93.1938 298.638 + vertex 99.3632 88.3808 298.656 + endloop + endfacet + facet normal 0.000922934 3.7343e-05 -1 + outer loop + vertex 99.3632 88.3808 298.656 + vertex 79.2959 93.1938 298.638 + vertex 99.1917 94.2554 298.656 + endloop + endfacet + facet normal 0.000904948 0.000374406 -1 + outer loop + vertex 79.2959 93.1938 298.638 + vertex 79.1689 99.125 298.64 + vertex 99.1917 94.2554 298.656 + endloop + endfacet + facet normal -0.00104328 0.000332675 -0.999999 + outer loop + vertex 79.2959 93.1938 298.638 + vertex 59.3341 98.2925 298.66 + vertex 79.1689 99.125 298.64 + endloop + endfacet + facet normal -0.00103059 3.03029e-05 -0.999999 + outer loop + vertex 59.3341 98.2925 298.66 + vertex 59.2433 104.268 298.661 + vertex 79.1689 99.125 298.64 + endloop + endfacet + facet normal -0.00103104 2.85585e-05 -0.999999 + outer loop + vertex 79.1689 99.125 298.64 + vertex 59.2433 104.268 298.661 + vertex 79.0384 105.101 298.64 + endloop + endfacet + facet normal 0.000906363 7.0859e-05 -1 + outer loop + vertex 79.1689 99.125 298.64 + vertex 79.0384 105.101 298.64 + vertex 99.019 100.184 298.658 + endloop + endfacet + facet normal -0.00102832 -3.60466e-05 -0.999999 + outer loop + vertex 59.2433 104.268 298.661 + vertex 59.1519 110.263 298.661 + vertex 79.0384 105.101 298.64 + endloop + endfacet + facet normal -0.00104348 -9.44396e-05 -0.999999 + outer loop + vertex 79.0384 105.101 298.64 + vertex 59.1519 110.263 298.661 + vertex 78.9057 111.091 298.64 + endloop + endfacet + facet normal 0.000911923 -5.11113e-05 -1 + outer loop + vertex 79.0384 105.101 298.64 + vertex 78.9057 111.091 298.64 + vertex 98.8421 106.159 298.658 + endloop + endfacet + facet normal -0.00104868 2.95746e-05 -0.999999 + outer loop + vertex 59.1519 110.263 298.661 + vertex 59.0584 116.234 298.661 + vertex 78.9057 111.091 298.64 + endloop + endfacet + facet normal -0.00105445 7.30411e-06 -0.999999 + outer loop + vertex 78.9057 111.091 298.64 + vertex 59.0584 116.234 298.661 + vertex 78.7734 117.064 298.64 + endloop + endfacet + facet normal 0.000920889 5.10537e-05 -1 + outer loop + vertex 78.9057 111.091 298.64 + vertex 78.7734 117.064 298.64 + vertex 98.6641 112.151 298.658 + endloop + endfacet + facet normal -0.00106796 0.000328156 -0.999999 + outer loop + vertex 59.0584 116.234 298.661 + vertex 58.9702 122.177 298.663 + vertex 78.7734 117.064 298.64 + endloop + endfacet + facet normal -0.00109363 0.000228762 -0.999999 + outer loop + vertex 78.7734 117.064 298.64 + vertex 58.9702 122.177 298.663 + vertex 78.649 123.006 298.642 + endloop + endfacet + facet normal 0.000917323 0.000270858 -1 + outer loop + vertex 78.7734 117.064 298.64 + vertex 78.649 123.006 298.642 + vertex 98.4877 118.124 298.659 + endloop + endfacet + facet normal -0.00110748 0.000557714 -0.999999 + outer loop + vertex 58.9702 122.177 298.663 + vertex 58.8943 128.101 298.666 + vertex 78.649 123.006 298.642 + endloop + endfacet + facet normal -0.00117035 0.000313918 -0.999999 + outer loop + vertex 78.649 123.006 298.642 + vertex 58.8943 128.101 298.666 + vertex 78.543 128.93 298.644 + endloop + endfacet + facet normal 0.000862174 0.000350281 -1 + outer loop + vertex 78.649 123.006 298.642 + vertex 78.543 128.93 298.644 + vertex 98.3242 124.064 298.659 + endloop + endfacet + facet normal -0.00127318 0.00275009 -0.999995 + outer loop + vertex 58.8943 128.101 298.666 + vertex 58.8363 134.044 298.683 + vertex 78.543 128.93 298.644 + endloop + endfacet + facet normal -0.00131494 0.00258915 -0.999996 + outer loop + vertex 78.543 128.93 298.644 + vertex 58.8363 134.044 298.683 + vertex 78.4563 134.874 298.659 + endloop + endfacet + facet normal 0.000701161 0.00261855 -0.999996 + outer loop + vertex 78.543 128.93 298.644 + vertex 78.4563 134.874 298.659 + vertex 98.1802 129.988 298.66 + endloop + endfacet + facet normal -0.00194644 0.0175267 -0.999845 + outer loop + vertex 58.8363 134.044 298.683 + vertex 58.7804 140.073 298.789 + vertex 78.4563 134.874 298.659 + endloop + endfacet + facet normal -0.0020001 0.0173238 -0.999848 + outer loop + vertex 78.4563 134.874 298.659 + vertex 58.7804 140.073 298.789 + vertex 78.397 140.903 298.764 + endloop + endfacet + facet normal -0.000126833 0.0173422 -0.99985 + outer loop + vertex 78.4563 134.874 298.659 + vertex 78.397 140.903 298.764 + vertex 98.0345 135.932 298.675 + endloop + endfacet + facet normal -0.00365986 0.0566265 -0.998389 + outer loop + vertex 58.7804 140.073 298.789 + vertex 59.4692 146.254 299.137 + vertex 78.397 140.903 298.764 + endloop + endfacet + facet normal -0.00390442 0.0557648 -0.998436 + outer loop + vertex 78.397 140.903 298.764 + vertex 59.4692 146.254 299.137 + vertex 77.9262 147.037 299.108 + endloop + endfacet + facet normal -0.00225118 0.0558916 -0.998434 + outer loop + vertex 78.397 140.903 298.764 + vertex 77.9262 147.037 299.108 + vertex 97.8156 141.957 298.779 + endloop + endfacet + facet normal -0.00429042 0.0566964 -0.998382 + outer loop + vertex 58.7804 140.073 298.789 + vertex 38.3076 145.615 299.191 + vertex 59.4692 146.254 299.137 + endloop + endfacet + facet normal -0.00391664 0.0580717 -0.998305 + outer loop + vertex 39.1502 139.474 298.831 + vertex 38.3076 145.615 299.191 + vertex 58.7804 140.073 298.789 + endloop + endfacet + facet normal -0.00346157 0.058134 -0.998303 + outer loop + vertex 39.1502 139.474 298.831 + vertex 19.8895 145.283 299.236 + vertex 38.3076 145.615 299.191 + endloop + endfacet + facet normal -0.00324285 0.0588563 -0.998261 + outer loop + vertex 19.6613 139.127 298.874 + vertex 19.8895 145.283 299.236 + vertex 39.1502 139.474 298.831 + endloop + endfacet + facet normal -0.00249991 0.0170051 -0.999852 + outer loop + vertex 39.2308 133.456 298.728 + vertex 19.6613 139.127 298.874 + vertex 39.1502 139.474 298.831 + endloop + endfacet + facet normal -0.00282597 0.0170007 -0.999851 + outer loop + vertex 39.2308 133.456 298.728 + vertex 39.1502 139.474 298.831 + vertex 58.8363 134.044 298.683 + endloop + endfacet + facet normal -0.00227047 0.0177965 -0.999839 + outer loop + vertex 19.6579 133.1 298.766 + vertex 19.6613 139.127 298.874 + vertex 39.2308 133.456 298.728 + endloop + endfacet + facet normal -0.00200463 0.00315001 -0.999993 + outer loop + vertex 39.2676 127.511 298.709 + vertex 19.6579 133.1 298.766 + vertex 39.2308 133.456 298.728 + endloop + endfacet + facet normal -0.00228694 0.00314826 -0.999992 + outer loop + vertex 39.2676 127.511 298.709 + vertex 39.2308 133.456 298.728 + vertex 58.8943 128.101 298.666 + endloop + endfacet + facet normal -0.00202228 0.00308807 -0.999993 + outer loop + vertex 19.6799 127.155 298.748 + vertex 19.6579 133.1 298.766 + vertex 39.2676 127.511 298.709 + endloop + endfacet + facet normal -0.00198048 0.000786618 -0.999998 + outer loop + vertex 39.3176 121.585 298.705 + vertex 19.6799 127.155 298.748 + vertex 39.2676 127.511 298.709 + endloop + endfacet + facet normal -0.00214332 0.000785244 -0.999997 + outer loop + vertex 39.3176 121.585 298.705 + vertex 39.2676 127.511 298.709 + vertex 58.9702 122.177 298.663 + endloop + endfacet + facet normal -0.00197704 0.000798733 -0.999998 + outer loop + vertex 19.7096 121.23 298.743 + vertex 19.6799 127.155 298.748 + vertex 39.3176 121.585 298.705 + endloop + endfacet + facet normal -0.00196857 0.000330316 -0.999998 + outer loop + vertex 39.3744 115.641 298.703 + vertex 19.7096 121.23 298.743 + vertex 39.3176 121.585 298.705 + endloop + endfacet + facet normal -0.00212461 0.000328824 -0.999998 + outer loop + vertex 39.3744 115.641 298.703 + vertex 39.3176 121.585 298.705 + vertex 59.0584 116.234 298.661 + endloop + endfacet + facet normal -0.00196895 0.000328968 -0.999998 + outer loop + vertex 19.74 115.29 298.741 + vertex 19.7096 121.23 298.743 + vertex 39.3744 115.641 298.703 + endloop + endfacet + facet normal -0.00196382 4.17921e-05 -0.999998 + outer loop + vertex 39.4339 109.671 298.702 + vertex 19.74 115.29 298.741 + vertex 39.3744 115.641 298.703 + endloop + endfacet + facet normal -0.00210762 4.03604e-05 -0.999998 + outer loop + vertex 39.4339 109.671 298.702 + vertex 39.3744 115.641 298.703 + vertex 59.1519 110.263 298.661 + endloop + endfacet + facet normal -0.00197259 1.10361e-05 -0.999998 + outer loop + vertex 19.7685 109.317 298.741 + vertex 19.74 115.29 298.741 + vertex 39.4339 109.671 298.702 + endloop + endfacet + facet normal -0.00197049 -0.000105355 -0.999998 + outer loop + vertex 39.491 103.679 298.703 + vertex 19.7685 109.317 298.741 + vertex 39.4339 109.671 298.702 + endloop + endfacet + facet normal -0.00211965 -0.000106776 -0.999998 + outer loop + vertex 39.491 103.679 298.703 + vertex 39.4339 109.671 298.702 + vertex 59.2433 104.268 298.661 + endloop + endfacet + facet normal -0.00196046 -7.02621e-05 -0.999998 + outer loop + vertex 19.7964 103.327 298.741 + vertex 19.7685 109.317 298.741 + vertex 39.491 103.679 298.703 + endloop + endfacet + facet normal -0.00196284 6.29999e-05 -0.999998 + outer loop + vertex 39.548 97.7041 298.702 + vertex 19.7964 103.327 298.741 + vertex 39.491 103.679 298.703 + endloop + endfacet + facet normal -0.00211025 6.15936e-05 -0.999998 + outer loop + vertex 39.548 97.7041 298.702 + vertex 39.491 103.679 298.703 + vertex 59.3341 98.2925 298.66 + endloop + endfacet + facet normal -0.00211604 0.000256398 -0.999998 + outer loop + vertex 59.4236 92.3657 298.659 + vertex 39.548 97.7041 298.702 + vertex 59.3341 98.2925 298.66 + endloop + endfacet + facet normal -0.00210452 0.000299289 -0.999998 + outer loop + vertex 39.6041 91.7768 298.7 + vertex 39.548 97.7041 298.702 + vertex 59.4236 92.3657 298.659 + endloop + endfacet + facet normal -0.00209499 -2.1368e-05 -0.999998 + outer loop + vertex 59.5127 86.4936 298.659 + vertex 39.6041 91.7768 298.7 + vertex 59.4236 92.3657 298.659 + endloop + endfacet + facet normal -0.00103593 -5.31167e-06 -0.999999 + outer loop + vertex 59.5127 86.4936 298.659 + vertex 59.4236 92.3657 298.659 + vertex 79.4228 87.3209 298.638 + endloop + endfacet + facet normal -0.000939655 -0.00232205 -0.999997 + outer loop + vertex 79.5509 81.4732 298.652 + vertex 59.5127 86.4936 298.659 + vertex 79.4228 87.3209 298.638 + endloop + endfacet + facet normal -0.000943409 -0.00233703 -0.999997 + outer loop + vertex 59.6026 80.6464 298.672 + vertex 59.5127 86.4936 298.659 + vertex 79.5509 81.4732 298.652 + endloop + endfacet + facet normal -0.000674452 -0.00882466 -0.999961 + outer loop + vertex 79.6853 75.605 298.703 + vertex 59.6026 80.6464 298.672 + vertex 79.5509 81.4732 298.652 + endloop + endfacet + facet normal 0.00133814 -0.00877857 -0.999961 + outer loop + vertex 79.6853 75.605 298.703 + vertex 79.5509 81.4732 298.652 + vertex 99.7166 76.663 298.721 + endloop + endfacet + facet normal 0.0020235 -0.0217572 -0.999761 + outer loop + vertex 99.9143 70.7398 298.85 + vertex 79.6853 75.605 298.703 + vertex 99.7166 76.663 298.721 + endloop + endfacet + facet normal 0.00202502 -0.0217508 -0.999761 + outer loop + vertex 79.8324 69.6824 298.832 + vertex 79.6853 75.605 298.703 + vertex 99.9143 70.7398 298.85 + endloop + endfacet + facet normal 0.00315135 -0.043152 -0.999064 + outer loop + vertex 100.137 64.7674 299.109 + vertex 79.8324 69.6824 298.832 + vertex 99.9143 70.7398 298.85 + endloop + endfacet + facet normal 0.00569218 -0.043057 -0.999056 + outer loop + vertex 100.137 64.7674 299.109 + vertex 99.9143 70.7398 298.85 + vertex 120.34 66.0362 299.169 + endloop + endfacet + facet normal 0.0076474 -0.0742776 -0.997208 + outer loop + vertex 120.664 60.071 299.616 + vertex 100.137 64.7674 299.109 + vertex 120.34 66.0362 299.169 + endloop + endfacet + facet normal 0.00581714 -0.0425158 -0.999079 + outer loop + vertex 120.34 66.0362 299.169 + vertex 99.9143 70.7398 298.85 + vertex 120.059 72.0109 298.913 + endloop + endfacet + facet normal 0.00316056 -0.043114 -0.999065 + outer loop + vertex 79.9995 63.7105 299.091 + vertex 79.8324 69.6824 298.832 + vertex 100.137 64.7674 299.109 + endloop + endfacet + facet normal 0.00478722 -0.0741398 -0.997236 + outer loop + vertex 100.391 58.7993 299.554 + vertex 79.9995 63.7105 299.091 + vertex 100.137 64.7674 299.109 + endloop + endfacet + facet normal 0.000759386 -0.0431812 -0.999067 + outer loop + vertex 79.9995 63.7105 299.091 + vertex 59.8011 68.857 298.853 + vertex 79.8324 69.6824 298.832 + endloop + endfacet + facet normal -0.000124803 -0.0217389 -0.999764 + outer loop + vertex 59.8011 68.857 298.853 + vertex 59.6973 74.779 298.724 + vertex 79.8324 69.6824 298.832 + endloop + endfacet + facet normal -0.00140631 -0.0217613 -0.999762 + outer loop + vertex 59.8011 68.857 298.853 + vertex 39.7771 74.1904 298.765 + vertex 59.6973 74.779 298.724 + endloop + endfacet + facet normal -0.00179 -0.00878963 -0.99996 + outer loop + vertex 39.7771 74.1904 298.765 + vertex 39.7165 80.0562 298.713 + vertex 59.6973 74.779 298.724 + endloop + endfacet + facet normal -0.00180734 -0.00885528 -0.999959 + outer loop + vertex 59.6973 74.779 298.724 + vertex 39.7165 80.0562 298.713 + vertex 59.6026 80.6464 298.672 + endloop + endfacet + facet normal -0.00200178 -0.00230558 -0.999995 + outer loop + vertex 39.7165 80.0562 298.713 + vertex 39.6597 85.9031 298.7 + vertex 59.6026 80.6464 298.672 + endloop + endfacet + facet normal -0.00191032 -0.00230469 -0.999996 + outer loop + vertex 39.7165 80.0562 298.713 + vertex 19.8764 85.5508 298.739 + vertex 39.6597 85.9031 298.7 + endloop + endfacet + facet normal -0.00195186 2.74679e-05 -0.999998 + outer loop + vertex 19.8764 85.5508 298.739 + vertex 19.8496 91.4227 298.739 + vertex 39.6597 85.9031 298.7 + endloop + endfacet + facet normal -0.00195454 1.78694e-05 -0.999998 + outer loop + vertex 39.6597 85.9031 298.7 + vertex 19.8496 91.4227 298.739 + vertex 39.6041 91.7768 298.7 + endloop + endfacet + facet normal -0.00196006 0.000325897 -0.999998 + outer loop + vertex 19.8496 91.4227 298.739 + vertex 19.823 97.3497 298.741 + vertex 39.6041 91.7768 298.7 + endloop + endfacet + facet normal -0.000785882 0.000331158 -1 + outer loop + vertex 19.8496 91.4227 298.739 + vertex 0.12549 97.2348 298.756 + vertex 19.823 97.3497 298.741 + endloop + endfacet + facet normal -0.000784785 0.000143119 -1 + outer loop + vertex 0.12549 97.2348 298.756 + vertex 0.125999 103.208 298.757 + vertex 19.823 97.3497 298.741 + endloop + endfacet + facet normal -0.000807162 6.78839e-05 -1 + outer loop + vertex 19.823 97.3497 298.741 + vertex 0.125999 103.208 298.757 + vertex 19.7964 103.327 298.741 + endloop + endfacet + facet normal -0.000806537 -3.57723e-05 -1 + outer loop + vertex 0.125999 103.208 298.757 + vertex 0.12517 109.199 298.757 + vertex 19.7964 103.327 298.741 + endloop + endfacet + facet normal 0.000772005 -3.55539e-05 -1 + outer loop + vertex 0.125999 103.208 298.757 + vertex -19.5554 109.317 298.742 + vertex 0.12517 109.199 298.757 + endloop + endfacet + facet normal 0.000772142 -1.29316e-05 -1 + outer loop + vertex -19.5554 109.317 298.742 + vertex -19.5345 115.289 298.742 + vertex 0.12517 109.199 298.757 + endloop + endfacet + facet normal 0.000773095 -9.85537e-06 -1 + outer loop + vertex 0.12517 109.199 298.757 + vertex -19.5345 115.289 298.742 + vertex 0.122353 115.171 298.757 + endloop + endfacet + facet normal -0.000815567 -1.06046e-05 -1 + outer loop + vertex 0.12517 109.199 298.757 + vertex 0.122353 115.171 298.757 + vertex 19.7685 109.317 298.741 + endloop + endfacet + facet normal 0.000773543 6.44649e-05 -1 + outer loop + vertex -19.5345 115.289 298.742 + vertex -19.5167 121.23 298.742 + vertex 0.122353 115.171 298.757 + endloop + endfacet + facet normal 0.000799841 0.000149704 -1 + outer loop + vertex 0.122353 115.171 298.757 + vertex -19.5167 121.23 298.742 + vertex 0.116348 121.114 298.758 + endloop + endfacet + facet normal -0.000808263 0.00014808 -1 + outer loop + vertex 0.122353 115.171 298.757 + vertex 0.116348 121.114 298.758 + vertex 19.74 115.29 298.741 + endloop + endfacet + facet normal 0.000801551 0.000441068 -1 + outer loop + vertex -19.5167 121.23 298.742 + vertex -19.5031 127.156 298.745 + vertex 0.116348 121.114 298.758 + endloop + endfacet + facet normal 0.000893064 0.000738274 -0.999999 + outer loop + vertex 0.116348 121.114 298.758 + vertex -19.5031 127.156 298.745 + vertex 0.106732 127.037 298.762 + endloop + endfacet + facet normal -0.000755082 0.000735598 -0.999999 + outer loop + vertex 0.116348 121.114 298.758 + vertex 0.106732 127.037 298.762 + vertex 19.7096 121.23 298.743 + endloop + endfacet + facet normal 0.000907144 0.00307317 -0.999995 + outer loop + vertex -19.5031 127.156 298.745 + vertex -19.4895 133.1 298.763 + vertex 0.106732 127.037 298.762 + endloop + endfacet + facet normal 0.000919472 0.00311302 -0.999995 + outer loop + vertex 0.106732 127.037 298.762 + vertex -19.4895 133.1 298.763 + vertex 0.0973219 132.981 298.781 + endloop + endfacet + facet normal -0.000748443 0.00311038 -0.999995 + outer loop + vertex 0.106732 127.037 298.762 + vertex 0.0973219 132.981 298.781 + vertex 19.6799 127.155 298.748 + endloop + endfacet + facet normal 0.00100887 0.0178506 -0.99984 + outer loop + vertex -19.4895 133.1 298.763 + vertex -19.4191 139.125 298.871 + vertex 0.0973219 132.981 298.781 + endloop + endfacet + facet normal 0.000940862 0.0176346 -0.999844 + outer loop + vertex 0.0973219 132.981 298.781 + vertex -19.4191 139.125 298.871 + vertex 0.0857732 139.006 298.887 + endloop + endfacet + facet normal -0.000842151 0.0176312 -0.999844 + outer loop + vertex 0.0973219 132.981 298.781 + vertex 0.0857732 139.006 298.887 + vertex 19.6579 133.1 298.766 + endloop + endfacet + facet normal 0.00119298 0.0593869 -0.998234 + outer loop + vertex -19.4191 139.125 298.871 + vertex -19.4315 145.278 299.237 + vertex 0.0857732 139.006 298.887 + endloop + endfacet + facet normal 0.0014236 0.0601022 -0.998191 + outer loop + vertex 0.0857732 139.006 298.887 + vertex -19.4315 145.278 299.237 + vertex -1.80473e-13 145.161 299.257 + endloop + endfacet + facet normal -0.00105205 0.0600678 -0.998194 + outer loop + vertex 0.0857732 139.006 298.887 + vertex -1.80473e-13 145.161 299.257 + vertex 19.6613 139.127 298.874 + endloop + endfacet + facet normal 0.00346916 0.0593912 -0.998229 + outer loop + vertex -19.4191 139.125 298.871 + vertex -38.4362 145.618 299.191 + vertex -19.4315 145.278 299.237 + endloop + endfacet + facet normal 0.00311047 0.0583438 -0.998292 + outer loop + vertex -39.0552 139.482 298.83 + vertex -38.4362 145.618 299.191 + vertex -19.4191 139.125 298.871 + endloop + endfacet + facet normal 0.00433752 0.0582202 -0.998294 + outer loop + vertex -39.0552 139.482 298.83 + vertex -58.9254 146.234 299.138 + vertex -38.4362 145.618 299.191 + endloop + endfacet + facet normal 0.00412636 0.0576004 -0.998331 + outer loop + vertex -58.731 140.073 298.783 + vertex -58.9254 146.234 299.138 + vertex -39.0552 139.482 298.83 + endloop + endfacet + facet normal 0.00294065 0.017988 -0.999834 + outer loop + vertex -39.1263 133.455 298.722 + vertex -58.731 140.073 298.783 + vertex -39.0552 139.482 298.83 + endloop + endfacet + facet normal 0.00242797 0.017994 -0.999835 + outer loop + vertex -39.1263 133.455 298.722 + vertex -39.0552 139.482 298.83 + vertex -19.4895 133.1 298.763 + endloop + endfacet + facet normal 0.00279256 0.0175493 -0.999842 + outer loop + vertex -58.7417 134.043 298.677 + vertex -58.731 140.073 298.783 + vertex -39.1263 133.455 298.722 + endloop + endfacet + facet normal 0.0023531 0.00287925 -0.999993 + outer loop + vertex -39.1664 127.51 298.705 + vertex -58.7417 134.043 298.677 + vertex -39.1263 133.455 298.722 + endloop + endfacet + facet normal 0.00209747 0.00288098 -0.999994 + outer loop + vertex -39.1664 127.51 298.705 + vertex -39.1263 133.455 298.722 + vertex -19.5031 127.156 298.745 + endloop + endfacet + facet normal 0.00224824 0.00256505 -0.999994 + outer loop + vertex -58.8274 128.098 298.662 + vertex -58.7417 134.043 298.677 + vertex -39.1664 127.51 298.705 + endloop + endfacet + facet normal 0.0021775 0.000200365 -0.999998 + outer loop + vertex -39.2099 121.585 298.703 + vertex -58.8274 128.098 298.662 + vertex -39.1664 127.51 298.705 + endloop + endfacet + facet normal 0.00197789 0.000201829 -0.999998 + outer loop + vertex -39.2099 121.585 298.703 + vertex -39.1664 127.51 298.705 + vertex -19.5167 121.23 298.742 + endloop + endfacet + facet normal 0.00211687 1.77257e-05 -0.999998 + outer loop + vertex -58.9075 122.173 298.662 + vertex -58.8274 128.098 298.662 + vertex -39.2099 121.585 298.703 + endloop + endfacet + facet normal 0.00211511 -4.11355e-05 -0.999998 + outer loop + vertex -39.2533 115.643 298.703 + vertex -58.9075 122.173 298.662 + vertex -39.2099 121.585 298.703 + endloop + endfacet + facet normal 0.00194311 -3.98788e-05 -0.999998 + outer loop + vertex -39.2533 115.643 298.703 + vertex -39.2099 121.585 298.703 + vertex -19.5345 115.289 298.742 + endloop + endfacet + facet normal 0.00210128 -8.27523e-05 -0.999998 + outer loop + vertex -58.9817 116.233 298.662 + vertex -58.9075 122.173 298.662 + vertex -39.2533 115.643 298.703 + endloop + endfacet + facet normal 0.00210267 -3.64683e-05 -0.999998 + outer loop + vertex -39.2988 109.673 298.704 + vertex -58.9817 116.233 298.662 + vertex -39.2533 115.643 298.703 + endloop + endfacet + facet normal 0.00193769 -3.52111e-05 -0.999998 + outer loop + vertex -39.2988 109.673 298.704 + vertex -39.2533 115.643 298.703 + vertex -19.5554 109.317 298.742 + endloop + endfacet + facet normal 0.00193781 -2.83146e-05 -0.999998 + outer loop + vertex -19.58 103.327 298.742 + vertex -39.2988 109.673 298.704 + vertex -19.5554 109.317 298.742 + endloop + endfacet + facet normal 0.00194322 -1.15085e-05 -0.999998 + outer loop + vertex -39.35 103.682 298.703 + vertex -39.2988 109.673 298.704 + vertex -19.58 103.327 298.742 + endloop + endfacet + facet normal 0.00194529 0.000103452 -0.999998 + outer loop + vertex -19.6073 97.351 298.741 + vertex -39.35 103.682 298.703 + vertex -19.58 103.327 298.742 + endloop + endfacet + facet normal 0.00076618 0.00010884 -1 + outer loop + vertex -19.6073 97.351 298.741 + vertex -19.58 103.327 298.742 + vertex 0.12549 97.2348 298.756 + endloop + endfacet + facet normal 0.00076757 0.000344868 -1 + outer loop + vertex 0.124528 91.3081 298.754 + vertex -19.6073 97.351 298.741 + vertex 0.12549 97.2348 298.756 + endloop + endfacet + facet normal 0.000768051 0.00034644 -1 + outer loop + vertex -19.6356 91.4237 298.739 + vertex -19.6073 97.351 298.741 + vertex 0.124528 91.3081 298.754 + endloop + endfacet + facet normal 0.000766114 1.55228e-05 -1 + outer loop + vertex 0.124001 85.4361 298.754 + vertex -19.6356 91.4237 298.739 + vertex 0.124528 91.3081 298.754 + endloop + endfacet + facet normal -0.000784954 1.56619e-05 -1 + outer loop + vertex 0.124001 85.4361 298.754 + vertex 0.124528 91.3081 298.754 + vertex 19.8764 85.5508 298.739 + endloop + endfacet + facet normal -0.000771445 -0.00231172 -0.999997 + outer loop + vertex 19.9046 79.7064 298.752 + vertex 0.124001 85.4361 298.754 + vertex 19.8764 85.5508 298.739 + endloop + endfacet + facet normal -0.000768796 -0.00230257 -0.999997 + outer loop + vertex 0.124188 79.5912 298.768 + vertex 0.124001 85.4361 298.754 + vertex 19.9046 79.7064 298.752 + endloop + endfacet + facet normal -0.000730884 -0.00880808 -0.999961 + outer loop + vertex 19.9347 73.8418 298.804 + vertex 0.124188 79.5912 298.768 + vertex 19.9046 79.7064 298.752 + endloop + endfacet + facet normal -0.00180605 -0.00881357 -0.99996 + outer loop + vertex 19.9347 73.8418 298.804 + vertex 19.9046 79.7064 298.752 + vertex 39.7771 74.1904 298.765 + endloop + endfacet + facet normal -0.00157728 -0.0218152 -0.999761 + outer loop + vertex 39.8446 68.2709 298.894 + vertex 19.9347 73.8418 298.804 + vertex 39.7771 74.1904 298.765 + endloop + endfacet + facet normal -0.00155326 -0.0217294 -0.999763 + outer loop + vertex 19.9683 67.9225 298.932 + vertex 19.9347 73.8418 298.804 + vertex 39.8446 68.2709 298.894 + endloop + endfacet + facet normal -0.00118013 -0.0429423 -0.999077 + outer loop + vertex 39.9214 62.3005 299.151 + vertex 19.9683 67.9225 298.932 + vertex 39.8446 68.2709 298.894 + endloop + endfacet + facet normal -0.000701125 -0.0429362 -0.999078 + outer loop + vertex 39.9214 62.3005 299.151 + vertex 39.8446 68.2709 298.894 + vertex 59.9209 62.8871 299.111 + endloop + endfacet + facet normal 0.000209709 -0.073868 -0.997268 + outer loop + vertex 60.0589 56.9175 299.553 + vertex 39.9214 62.3005 299.151 + vertex 59.9209 62.8871 299.111 + endloop + endfacet + facet normal -0.000788773 -0.0432625 -0.999063 + outer loop + vertex 59.9209 62.8871 299.111 + vertex 39.8446 68.2709 298.894 + vertex 59.8011 68.857 298.853 + endloop + endfacet + facet normal -0.00119448 -0.0429932 -0.999075 + outer loop + vertex 20.0075 61.9538 299.189 + vertex 19.9683 67.9225 298.932 + vertex 39.9214 62.3005 299.151 + endloop + endfacet + facet normal -0.000646143 -0.0742867 -0.997237 + outer loop + vertex 40.0126 56.3356 299.595 + vertex 20.0075 61.9538 299.189 + vertex 39.9214 62.3005 299.151 + endloop + endfacet + facet normal -0.000485012 -0.0429886 -0.999075 + outer loop + vertex 20.0075 61.9538 299.189 + vertex 0.126706 67.8059 298.947 + vertex 19.9683 67.9225 298.932 + endloop + endfacet + facet normal -0.000610924 -0.0216448 -0.999766 + outer loop + vertex 0.126706 67.8059 298.947 + vertex 0.125038 73.7249 298.819 + vertex 19.9683 67.9225 298.932 + endloop + endfacet + facet normal 0.000625806 -0.0216445 -0.999766 + outer loop + vertex 0.126706 67.8059 298.947 + vertex -19.7199 73.8432 298.804 + vertex 0.125038 73.7249 298.819 + endloop + endfacet + facet normal 0.000702644 -0.0087848 -0.999961 + outer loop + vertex -19.7199 73.8432 298.804 + vertex -19.6916 79.7092 298.752 + vertex 0.125038 73.7249 298.819 + endloop + endfacet + facet normal 0.000716424 -0.00873917 -0.999962 + outer loop + vertex 0.125038 73.7249 298.819 + vertex -19.6916 79.7092 298.752 + vertex 0.124188 79.5912 298.768 + endloop + endfacet + facet normal 0.000754717 -0.00231283 -0.999997 + outer loop + vertex -19.6916 79.7092 298.752 + vertex -19.6634 85.5505 298.739 + vertex 0.124188 79.5912 298.768 + endloop + endfacet + facet normal 0.00189346 -0.00231833 -0.999996 + outer loop + vertex -19.6916 79.7092 298.752 + vertex -39.5196 85.9062 298.701 + vertex -19.6634 85.5505 298.739 + endloop + endfacet + facet normal 0.00193494 -3.16965e-06 -0.999998 + outer loop + vertex -39.5196 85.9062 298.701 + vertex -39.4626 91.7781 298.701 + vertex -19.6634 85.5505 298.739 + endloop + endfacet + facet normal 0.00194448 2.71636e-05 -0.999998 + outer loop + vertex -19.6634 85.5505 298.739 + vertex -39.4626 91.7781 298.701 + vertex -19.6356 91.4237 298.739 + endloop + endfacet + facet normal 0.00194982 0.000326183 -0.999998 + outer loop + vertex -39.4626 91.7781 298.701 + vertex -39.4056 97.7057 298.703 + vertex -19.6356 91.4237 298.739 + endloop + endfacet + facet normal 0.00211149 0.000324627 -0.999998 + outer loop + vertex -39.4626 91.7781 298.701 + vertex -59.225 98.2968 298.661 + vertex -39.4056 97.7057 298.703 + endloop + endfacet + facet normal 0.00210395 7.20191e-05 -0.999998 + outer loop + vertex -59.225 98.2968 298.661 + vertex -59.1394 104.271 298.662 + vertex -39.4056 97.7057 298.703 + endloop + endfacet + facet normal 0.00211929 0.000118131 -0.999998 + outer loop + vertex -39.4056 97.7057 298.703 + vertex -59.1394 104.271 298.662 + vertex -39.35 103.682 298.703 + endloop + endfacet + facet normal 0.00211568 -3.29618e-06 -0.999998 + outer loop + vertex -59.1394 104.271 298.662 + vertex -59.0579 110.261 298.662 + vertex -39.35 103.682 298.703 + endloop + endfacet + facet normal 0.0011015 1.04941e-05 -0.999999 + outer loop + vertex -59.1394 104.271 298.662 + vertex -78.7366 111.084 298.64 + vertex -59.0579 110.261 298.662 + endloop + endfacet + facet normal 0.00110572 0.000111278 -0.999999 + outer loop + vertex -78.7366 111.084 298.64 + vertex -78.6201 117.057 298.641 + vertex -59.0579 110.261 298.662 + endloop + endfacet + facet normal 0.00106942 6.79456e-06 -0.999999 + outer loop + vertex -59.0579 110.261 298.662 + vertex -78.6201 117.057 298.641 + vertex -58.9817 116.233 298.662 + endloop + endfacet + facet normal 0.00106804 -2.61348e-05 -0.999999 + outer loop + vertex -78.6201 117.057 298.641 + vertex -78.5033 122.997 298.641 + vertex -58.9817 116.233 298.662 + endloop + endfacet + facet normal -0.000859477 1.17591e-05 -1 + outer loop + vertex -78.6201 117.057 298.641 + vertex -97.947 124.04 298.658 + vertex -78.5033 122.997 298.641 + endloop + endfacet + facet normal -0.000843206 0.000315197 -1 + outer loop + vertex -97.947 124.04 298.658 + vertex -97.7577 129.968 298.659 + vertex -78.5033 122.997 298.641 + endloop + endfacet + facet normal -0.00094998 2.0277e-05 -1 + outer loop + vertex -78.5033 122.997 298.641 + vertex -97.7577 129.968 298.659 + vertex -78.3769 128.922 298.641 + endloop + endfacet + facet normal 0.00105494 -2.25173e-05 -0.999999 + outer loop + vertex -78.5033 122.997 298.641 + vertex -78.3769 128.922 298.641 + vertex -58.9075 122.173 298.662 + endloop + endfacet + facet normal -0.00082571 0.00232195 -0.999997 + outer loop + vertex -97.7577 129.968 298.659 + vertex -97.5636 135.912 298.673 + vertex -78.3769 128.922 298.641 + endloop + endfacet + facet normal -0.000770969 0.0024722 -0.999997 + outer loop + vertex -78.3769 128.922 298.641 + vertex -97.5636 135.912 298.673 + vertex -78.2335 134.867 298.655 + endloop + endfacet + facet normal 0.00117459 0.00242528 -0.999996 + outer loop + vertex -78.3769 128.922 298.641 + vertex -78.2335 134.867 298.655 + vertex -58.8274 128.098 298.662 + endloop + endfacet + facet normal 2.272e-05 0.0171504 -0.999853 + outer loop + vertex -97.5636 135.912 298.673 + vertex -97.3771 141.938 298.776 + vertex -78.2335 134.867 298.655 + endloop + endfacet + facet normal 0.000208586 0.0176535 -0.999844 + outer loop + vertex -78.2335 134.867 298.655 + vertex -97.3771 141.938 298.776 + vertex -78.0958 140.894 298.762 + endloop + endfacet + facet normal 0.00186377 0.0176156 -0.999843 + outer loop + vertex -78.2335 134.867 298.655 + vertex -78.0958 140.894 298.762 + vertex -58.7417 134.043 298.677 + endloop + endfacet + facet normal 0.00227579 0.0558258 -0.998438 + outer loop + vertex -97.3771 141.938 298.776 + vertex -96.8116 148.058 299.12 + vertex -78.0958 140.894 298.762 + endloop + endfacet + facet normal 0.00238957 0.0561222 -0.998421 + outer loop + vertex -78.0958 140.894 298.762 + vertex -96.8116 148.058 299.12 + vertex -78.4809 147.064 299.108 + endloop + endfacet + facet normal 0.00347777 0.0561898 -0.998414 + outer loop + vertex -78.0958 140.894 298.762 + vertex -78.4809 147.064 299.108 + vertex -58.731 140.073 298.783 + endloop + endfacet + facet normal 0.000296415 0.0560083 -0.99843 + outer loop + vertex -97.3771 141.938 298.776 + vertex -116.908 149.373 299.188 + vertex -96.8116 148.058 299.12 + endloop + endfacet + facet normal 0.000406884 0.0562975 -0.998414 + outer loop + vertex -116.644 143.192 298.839 + vertex -116.908 149.373 299.188 + vertex -97.3771 141.938 298.776 + endloop + endfacet + facet normal -0.000910008 0.0562416 -0.998417 + outer loop + vertex -116.644 143.192 298.839 + vertex -135.914 150.782 299.284 + vertex -116.908 149.373 299.188 + endloop + endfacet + facet normal -0.000443095 0.0574231 -0.99835 + outer loop + vertex -135.91 144.605 298.929 + vertex -135.914 150.782 299.284 + vertex -116.644 143.192 298.839 + endloop + endfacet + facet normal -0.00337742 0.0174903 -0.999841 + outer loop + vertex -116.8 137.161 298.734 + vertex -135.91 144.605 298.929 + vertex -116.644 143.192 298.839 + endloop + endfacet + facet normal -0.00205156 0.0174562 -0.999846 + outer loop + vertex -116.8 137.161 298.734 + vertex -116.644 143.192 298.839 + vertex -97.5636 135.912 298.673 + endloop + endfacet + facet normal -0.00348632 0.0172109 -0.999846 + outer loop + vertex -136.19 138.58 298.826 + vertex -135.91 144.605 298.929 + vertex -116.8 137.161 298.734 + endloop + endfacet + facet normal -0.00454417 0.00276733 -0.999986 + outer loop + vertex -117.057 131.213 298.719 + vertex -136.19 138.58 298.826 + vertex -116.8 137.161 298.734 + endloop + endfacet + facet normal -0.00291575 0.0026968 -0.999992 + outer loop + vertex -117.057 131.213 298.719 + vertex -116.8 137.161 298.734 + vertex -97.7577 129.968 298.659 + endloop + endfacet + facet normal -0.00449078 0.00290598 -0.999986 + outer loop + vertex -136.518 132.634 298.81 + vertex -136.19 138.58 298.826 + vertex -117.057 131.213 298.719 + endloop + endfacet + facet normal -0.00466329 0.000543529 -0.999989 + outer loop + vertex -117.316 125.289 298.717 + vertex -136.518 132.634 298.81 + vertex -117.057 131.213 298.719 + endloop + endfacet + facet normal -0.00303247 0.000472345 -0.999995 + outer loop + vertex -117.316 125.289 298.717 + vertex -117.057 131.213 298.719 + vertex -97.947 124.04 298.658 + endloop + endfacet + facet normal -0.00305093 0.000186179 -0.999995 + outer loop + vertex -98.1193 118.101 298.657 + vertex -117.316 125.289 298.717 + vertex -97.947 124.04 298.658 + endloop + endfacet + facet normal -0.00297774 0.000381655 -0.999995 + outer loop + vertex -117.554 119.35 298.715 + vertex -117.316 125.289 298.717 + vertex -98.1193 118.101 298.657 + endloop + endfacet + facet normal -0.0029931 0.000142558 -0.999996 + outer loop + vertex -98.2813 112.132 298.657 + vertex -117.554 119.35 298.715 + vertex -98.1193 118.101 298.657 + endloop + endfacet + facet normal -0.000841779 8.41922e-05 -1 + outer loop + vertex -98.2813 112.132 298.657 + vertex -98.1193 118.101 298.657 + vertex -78.7366 111.084 298.64 + endloop + endfacet + facet normal -0.000847053 -1.41583e-05 -1 + outer loop + vertex -78.8527 105.096 298.64 + vertex -98.2813 112.132 298.657 + vertex -78.7366 111.084 298.64 + endloop + endfacet + facet normal -0.0008466 -1.29057e-05 -1 + outer loop + vertex -98.4423 106.144 298.657 + vertex -98.2813 112.132 298.657 + vertex -78.8527 105.096 298.64 + endloop + endfacet + facet normal -0.000837342 0.000160164 -1 + outer loop + vertex -78.9756 99.1185 298.639 + vertex -98.4423 106.144 298.657 + vertex -78.8527 105.096 298.64 + endloop + endfacet + facet normal 0.00109743 0.000120387 -0.999999 + outer loop + vertex -78.9756 99.1185 298.639 + vertex -78.8527 105.096 298.64 + vertex -59.225 98.2968 298.661 + endloop + endfacet + facet normal 0.00110693 0.000348725 -0.999999 + outer loop + vertex -59.3145 92.3676 298.659 + vertex -78.9756 99.1185 298.639 + vertex -59.225 98.2968 298.661 + endloop + endfacet + facet normal 0.00109416 0.000311535 -0.999999 + outer loop + vertex -79.1007 93.1905 298.637 + vertex -78.9756 99.1185 298.639 + vertex -59.3145 92.3676 298.659 + endloop + endfacet + facet normal 0.0010831 4.57389e-05 -0.999999 + outer loop + vertex -59.4045 86.4923 298.658 + vertex -79.1007 93.1905 298.637 + vertex -59.3145 92.3676 298.659 + endloop + endfacet + facet normal 0.00211571 2.99201e-05 -0.999998 + outer loop + vertex -59.4045 86.4923 298.658 + vertex -59.3145 92.3676 298.659 + vertex -39.5196 85.9062 298.701 + endloop + endfacet + facet normal 0.00204902 -0.00223254 -0.999995 + outer loop + vertex -39.577 80.0578 298.713 + vertex -59.4045 86.4923 298.658 + vertex -39.5196 85.9062 298.701 + endloop + endfacet + facet normal 0.00198065 -0.00244323 -0.999995 + outer loop + vertex -59.494 80.649 298.673 + vertex -59.4045 86.4923 298.658 + vertex -39.577 80.0578 298.713 + endloop + endfacet + facet normal 0.00178646 -0.00898177 -0.999958 + outer loop + vertex -39.6369 74.1952 298.766 + vertex -59.494 80.649 298.673 + vertex -39.577 80.0578 298.713 + endloop + endfacet + facet normal 0.00174576 -0.00898135 -0.999958 + outer loop + vertex -39.6369 74.1952 298.766 + vertex -39.577 80.0578 298.713 + vertex -19.7199 73.8432 298.804 + endloop + endfacet + facet normal 0.00151947 -0.0217654 -0.999762 + outer loop + vertex -19.7506 67.9242 298.933 + vertex -39.6369 74.1952 298.766 + vertex -19.7199 73.8432 298.804 + endloop + endfacet + facet normal 0.00154682 -0.0216787 -0.999764 + outer loop + vertex -39.702 68.2739 298.894 + vertex -39.6369 74.1952 298.766 + vertex -19.7506 67.9242 298.933 + endloop + endfacet + facet normal 0.00117231 -0.0429683 -0.999076 + outer loop + vertex -19.7854 61.9557 299.189 + vertex -39.702 68.2739 298.894 + vertex -19.7506 67.9242 298.933 + endloop + endfacet + facet normal 0.000512797 -0.0429645 -0.999076 + outer loop + vertex -19.7854 61.9557 299.189 + vertex -19.7506 67.9242 298.933 + vertex 0.129371 61.8392 299.205 + endloop + endfacet + facet normal 0.000327008 -0.0745025 -0.997221 + outer loop + vertex 0.132592 55.8795 299.65 + vertex -19.7854 61.9557 299.189 + vertex 0.129371 61.8392 299.205 + endloop + endfacet + facet normal 0.000462892 -0.0431272 -0.999069 + outer loop + vertex 0.129371 61.8392 299.205 + vertex -19.7506 67.9242 298.933 + vertex 0.126706 67.8059 298.947 + endloop + endfacet + facet normal 0.00110439 -0.0431819 -0.999067 + outer loop + vertex -39.7766 62.3058 299.152 + vertex -39.702 68.2739 298.894 + vertex -19.7854 61.9557 299.189 + endloop + endfacet + facet normal 0.00055998 -0.0740747 -0.997253 + outer loop + vertex -19.8262 55.9918 299.632 + vertex -39.7766 62.3058 299.152 + vertex -19.7854 61.9557 299.189 + endloop + endfacet + facet normal 0.000835905 -0.0431786 -0.999067 + outer loop + vertex -39.7766 62.3058 299.152 + vertex -59.6931 68.8585 298.852 + vertex -39.702 68.2739 298.894 + endloop + endfacet + facet normal 0.00146419 -0.0217435 -0.999763 + outer loop + vertex -59.6931 68.8585 298.852 + vertex -59.5896 74.7799 298.724 + vertex -39.702 68.2739 298.894 + endloop + endfacet + facet normal 0.000158862 -0.0217207 -0.999764 + outer loop + vertex -59.6931 68.8585 298.852 + vertex -79.4911 75.6008 298.703 + vertex -59.5896 74.7799 298.724 + endloop + endfacet + facet normal 0.000693622 -0.00876058 -0.999961 + outer loop + vertex -79.4911 75.6008 298.703 + vertex -79.3555 81.4705 298.651 + vertex -59.5896 74.7799 298.724 + endloop + endfacet + facet normal 0.000707144 -0.00872064 -0.999962 + outer loop + vertex -59.5896 74.7799 298.724 + vertex -79.3555 81.4705 298.651 + vertex -59.494 80.649 298.673 + endloop + endfacet + facet normal 0.000964858 -0.00249073 -0.999996 + outer loop + vertex -79.3555 81.4705 298.651 + vertex -79.2283 87.3152 298.637 + vertex -59.494 80.649 298.673 + endloop + endfacet + facet normal -0.00100492 -0.00244785 -0.999996 + outer loop + vertex -79.3555 81.4705 298.651 + vertex -98.9442 88.3654 298.654 + vertex -79.2283 87.3152 298.637 + endloop + endfacet + facet normal -0.000874025 9.74446e-06 -1 + outer loop + vertex -98.9442 88.3654 298.654 + vertex -98.774 94.2392 298.654 + vertex -79.2283 87.3152 298.637 + endloop + endfacet + facet normal -0.000839735 0.000106543 -1 + outer loop + vertex -79.2283 87.3152 298.637 + vertex -98.774 94.2392 298.654 + vertex -79.1007 93.1905 298.637 + endloop + endfacet + facet normal -0.000824696 0.0003887 -1 + outer loop + vertex -98.774 94.2392 298.654 + vertex -98.6066 100.169 298.656 + vertex -79.1007 93.1905 298.637 + endloop + endfacet + facet normal -0.00295059 0.000448694 -0.999996 + outer loop + vertex -98.774 94.2392 298.654 + vertex -118.202 101.418 298.715 + vertex -98.6066 100.169 298.656 + endloop + endfacet + facet normal -0.00296817 0.000172953 -0.999996 + outer loop + vertex -118.202 101.418 298.715 + vertex -117.988 107.393 298.715 + vertex -98.6066 100.169 298.656 + endloop + endfacet + facet normal -0.00296418 0.000183655 -0.999996 + outer loop + vertex -98.6066 100.169 298.656 + vertex -117.988 107.393 298.715 + vertex -98.4423 106.144 298.657 + endloop + endfacet + facet normal -0.00297175 6.52095e-05 -0.999996 + outer loop + vertex -117.988 107.393 298.715 + vertex -117.774 113.381 298.715 + vertex -98.4423 106.144 298.657 + endloop + endfacet + facet normal -0.00457149 0.00012226 -0.99999 + outer loop + vertex -117.988 107.393 298.715 + vertex -137.449 114.805 298.805 + vertex -117.774 113.381 298.715 + endloop + endfacet + facet normal -0.00456108 0.000266098 -0.99999 + outer loop + vertex -137.449 114.805 298.805 + vertex -137.161 120.772 298.805 + vertex -117.774 113.381 298.715 + endloop + endfacet + facet normal -0.00456142 0.000265208 -0.99999 + outer loop + vertex -117.774 113.381 298.715 + vertex -137.161 120.772 298.805 + vertex -117.554 119.35 298.715 + endloop + endfacet + facet normal -0.00454113 0.000544876 -0.99999 + outer loop + vertex -137.161 120.772 298.805 + vertex -136.852 126.709 298.807 + vertex -117.554 119.35 298.715 + endloop + endfacet + facet normal -0.0049251 0.00056487 -0.999988 + outer loop + vertex -137.161 120.772 298.805 + vertex -156.861 128.263 298.906 + vertex -136.852 126.709 298.807 + endloop + endfacet + facet normal -0.00488598 0.00106844 -0.999987 + outer loop + vertex -156.861 128.263 298.906 + vertex -156.459 134.189 298.911 + vertex -136.852 126.709 298.807 + endloop + endfacet + facet normal -0.00496459 0.000862364 -0.999987 + outer loop + vertex -136.852 126.709 298.807 + vertex -156.459 134.189 298.911 + vertex -136.518 132.634 298.81 + endloop + endfacet + facet normal -0.00477771 0.00325944 -0.999983 + outer loop + vertex -156.459 134.189 298.911 + vertex -156.062 140.136 298.928 + vertex -136.518 132.634 298.81 + endloop + endfacet + facet normal -0.00400497 0.00320785 -0.999987 + outer loop + vertex -156.459 134.189 298.911 + vertex -176.645 141.788 299.016 + vertex -156.062 140.136 298.928 + endloop + endfacet + facet normal -0.00283534 0.0177672 -0.999838 + outer loop + vertex -176.645 141.788 299.016 + vertex -176.277 147.82 299.122 + vertex -156.062 140.136 298.928 + endloop + endfacet + facet normal -0.00284241 0.0177486 -0.999838 + outer loop + vertex -156.062 140.136 298.928 + vertex -176.277 147.82 299.122 + vertex -155.758 146.167 299.034 + endloop + endfacet + facet normal -0.00374053 0.0177938 -0.999835 + outer loop + vertex -156.062 140.136 298.928 + vertex -155.758 146.167 299.034 + vertex -136.19 138.58 298.826 + endloop + endfacet + facet normal 0.000499893 0.0591513 -0.998249 + outer loop + vertex -176.277 147.82 299.122 + vertex -176.355 154.05 299.491 + vertex -155.758 146.167 299.034 + endloop + endfacet + facet normal -4.09374e-06 0.057839 -0.998326 + outer loop + vertex -155.758 146.167 299.034 + vertex -176.355 154.05 299.491 + vertex -155.09 152.307 299.39 + endloop + endfacet + facet normal -0.000747663 0.0579195 -0.998321 + outer loop + vertex -155.758 146.167 299.034 + vertex -155.09 152.307 299.39 + vertex -135.91 144.605 298.929 + endloop + endfacet + facet normal 0.00191992 0.0591689 -0.998246 + outer loop + vertex -176.277 147.82 299.122 + vertex -196.712 155.708 299.55 + vertex -176.355 154.05 299.491 + endloop + endfacet + facet normal 0.00202807 0.0594482 -0.998229 + outer loop + vertex -197.403 149.532 299.181 + vertex -196.712 155.708 299.55 + vertex -176.277 147.82 299.122 + endloop + endfacet + facet normal 0.00394498 0.059234 -0.998236 + outer loop + vertex -197.403 149.532 299.181 + vertex -218.394 157.456 299.568 + vertex -196.712 155.708 299.55 + endloop + endfacet + facet normal 0.0040494 0.0595098 -0.99822 + outer loop + vertex -218.83 151.279 299.198 + vertex -218.394 157.456 299.568 + vertex -197.403 149.532 299.181 + endloop + endfacet + facet normal 0.00067646 0.0181747 -0.999835 + outer loop + vertex -197.881 143.507 299.071 + vertex -218.83 151.279 299.198 + vertex -197.403 149.532 299.181 + endloop + endfacet + facet normal -0.00112209 0.0183173 -0.999832 + outer loop + vertex -197.881 143.507 299.071 + vertex -197.403 149.532 299.181 + vertex -176.645 141.788 299.016 + endloop + endfacet + facet normal -0.00233169 0.00338065 -0.999992 + outer loop + vertex -177.089 135.84 298.997 + vertex -197.881 143.507 299.071 + vertex -176.645 141.788 299.016 + endloop + endfacet + facet normal -0.00228546 0.003506 -0.999991 + outer loop + vertex -198.353 137.568 299.052 + vertex -197.881 143.507 299.071 + vertex -177.089 135.84 298.997 + endloop + endfacet + facet normal -0.00248205 0.00108735 -0.999996 + outer loop + vertex -177.556 129.919 298.992 + vertex -198.353 137.568 299.052 + vertex -177.089 135.84 298.997 + endloop + endfacet + facet normal -0.004022 0.00120871 -0.999991 + outer loop + vertex -177.556 129.919 298.992 + vertex -177.089 135.84 298.997 + vertex -156.861 128.263 298.906 + endloop + endfacet + facet normal -0.00407333 0.00056713 -0.999992 + outer loop + vertex -157.246 122.328 298.905 + vertex -177.556 129.919 298.992 + vertex -156.861 128.263 298.906 + endloop + endfacet + facet normal -0.00409333 0.000513632 -0.999991 + outer loop + vertex -178.01 123.987 298.99 + vertex -177.556 129.919 298.992 + vertex -157.246 122.328 298.905 + endloop + endfacet + facet normal -0.00411282 0.000269738 -0.999992 + outer loop + vertex -157.615 116.363 298.905 + vertex -178.01 123.987 298.99 + vertex -157.246 122.328 298.905 + endloop + endfacet + facet normal -0.00491638 0.00031944 -0.999988 + outer loop + vertex -157.615 116.363 298.905 + vertex -157.246 122.328 298.905 + vertex -137.449 114.805 298.805 + endloop + endfacet + facet normal -0.00492833 0.000164713 -0.999988 + outer loop + vertex -137.73 108.819 298.805 + vertex -157.615 116.363 298.905 + vertex -137.449 114.805 298.805 + endloop + endfacet + facet normal -0.0049139 0.000202767 -0.999988 + outer loop + vertex -157.967 110.376 298.905 + vertex -157.615 116.363 298.905 + vertex -137.73 108.819 298.805 + endloop + endfacet + facet normal -0.00490675 0.000295625 -0.999988 + outer loop + vertex -138.003 102.844 298.805 + vertex -157.967 110.376 298.905 + vertex -137.73 108.819 298.805 + endloop + endfacet + facet normal -0.00453741 0.000278756 -0.99999 + outer loop + vertex -138.003 102.844 298.805 + vertex -137.73 108.819 298.805 + vertex -118.202 101.418 298.715 + endloop + endfacet + facet normal -0.00451741 0.000556569 -0.99999 + outer loop + vertex -118.42 95.4891 298.712 + vertex -138.003 102.844 298.805 + vertex -118.202 101.418 298.715 + endloop + endfacet + facet normal -0.00450556 0.000588127 -0.99999 + outer loop + vertex -138.275 96.9156 298.803 + vertex -138.003 102.844 298.805 + vertex -118.42 95.4891 298.712 + endloop + endfacet + facet normal -0.00453603 0.00016402 -0.99999 + outer loop + vertex -118.639 89.6156 298.712 + vertex -138.275 96.9156 298.803 + vertex -118.42 95.4891 298.712 + endloop + endfacet + facet normal -0.00294679 0.000104734 -0.999996 + outer loop + vertex -118.639 89.6156 298.712 + vertex -118.42 95.4891 298.712 + vertex -98.9442 88.3654 298.654 + endloop + endfacet + facet normal -0.00309069 -0.00216222 -0.999993 + outer loop + vertex -99.1171 82.5154 298.667 + vertex -118.639 89.6156 298.712 + vertex -98.9442 88.3654 298.654 + endloop + endfacet + facet normal -0.00309445 -0.00217258 -0.999993 + outer loop + vertex -118.862 83.7672 298.726 + vertex -118.639 89.6156 298.712 + vertex -99.1171 82.5154 298.667 + endloop + endfacet + facet normal -0.00351286 -0.00877368 -0.999955 + outer loop + vertex -99.2973 76.6468 298.719 + vertex -118.862 83.7672 298.726 + vertex -99.1171 82.5154 298.667 + endloop + endfacet + facet normal -0.00131435 -0.00884122 -0.99996 + outer loop + vertex -99.2973 76.6468 298.719 + vertex -99.1171 82.5154 298.667 + vertex -79.4911 75.6008 298.703 + endloop + endfacet + facet normal -0.00199887 -0.0218052 -0.99976 + outer loop + vertex -79.6376 69.6787 298.832 + vertex -99.2973 76.6468 298.719 + vertex -79.4911 75.6008 298.703 + endloop + endfacet + facet normal -0.00190697 -0.021546 -0.999766 + outer loop + vertex -99.4928 70.7223 298.848 + vertex -99.2973 76.6468 298.719 + vertex -79.6376 69.6787 298.832 + endloop + endfacet + facet normal -0.00303374 -0.0429932 -0.999071 + outer loop + vertex -79.8033 63.7065 299.09 + vertex -99.4928 70.7223 298.848 + vertex -79.6376 69.6787 298.832 + endloop + endfacet + facet normal -0.000743393 -0.0430569 -0.999072 + outer loop + vertex -79.8033 63.7065 299.09 + vertex -79.6376 69.6787 298.832 + vertex -59.8106 62.8883 299.11 + endloop + endfacet + facet normal -0.00203596 -0.0745942 -0.997212 + outer loop + vertex -59.9469 56.925 299.556 + vertex -79.8033 63.7065 299.09 + vertex -59.8106 62.8883 299.11 + endloop + endfacet + facet normal -0.000762529 -0.0431126 -0.99907 + outer loop + vertex -59.8106 62.8883 299.11 + vertex -79.6376 69.6787 298.832 + vertex -59.6931 68.8585 298.852 + endloop + endfacet + facet normal -0.00313089 -0.0432655 -0.999059 + outer loop + vertex -99.7123 64.7504 299.107 + vertex -99.4928 70.7223 298.848 + vertex -79.8033 63.7065 299.09 + endloop + endfacet + facet normal -0.00475374 -0.0742441 -0.997229 + outer loop + vertex -79.9948 57.7395 299.535 + vertex -99.7123 64.7504 299.107 + vertex -79.8033 63.7065 299.09 + endloop + endfacet + facet normal -0.00568296 -0.0431714 -0.999052 + outer loop + vertex -99.7123 64.7504 299.107 + vertex -119.345 71.9741 298.906 + vertex -99.4928 70.7223 298.848 + endloop + endfacet + facet normal -0.00432646 -0.021624 -0.999757 + outer loop + vertex -119.345 71.9741 298.906 + vertex -119.095 77.8978 298.777 + vertex -99.4928 70.7223 298.848 + endloop + endfacet + facet normal -0.0060431 -0.0215512 -0.999749 + outer loop + vertex -119.345 71.9741 298.906 + vertex -139.127 79.3247 298.867 + vertex -119.095 77.8978 298.777 + endloop + endfacet + facet normal -0.00511662 -0.00853103 -0.999951 + outer loop + vertex -139.127 79.3247 298.867 + vertex -138.834 85.1941 298.816 + vertex -119.095 77.8978 298.777 + endloop + endfacet + facet normal -0.00512637 -0.0085574 -0.99995 + outer loop + vertex -119.095 77.8978 298.777 + vertex -138.834 85.1941 298.816 + vertex -118.862 83.7672 298.726 + endloop + endfacet + facet normal -0.00466345 -0.00207548 -0.999987 + outer loop + vertex -138.834 85.1941 298.816 + vertex -138.558 91.0439 298.802 + vertex -118.862 83.7672 298.726 + endloop + endfacet + facet normal -0.0050208 -0.00205863 -0.999985 + outer loop + vertex -138.834 85.1941 298.816 + vertex -158.988 92.6031 298.902 + vertex -138.558 91.0439 298.802 + endloop + endfacet + facet normal -0.00483857 0.000329324 -0.999988 + outer loop + vertex -158.988 92.6031 298.902 + vertex -158.651 98.4762 298.902 + vertex -138.558 91.0439 298.802 + endloop + endfacet + facet normal -0.00486595 0.00025532 -0.999988 + outer loop + vertex -138.558 91.0439 298.802 + vertex -158.651 98.4762 298.902 + vertex -138.275 96.9156 298.803 + endloop + endfacet + facet normal -0.00483487 0.000661038 -0.999988 + outer loop + vertex -158.651 98.4762 298.902 + vertex -158.314 104.404 298.904 + vertex -138.275 96.9156 298.803 + endloop + endfacet + facet normal -0.00402608 0.000615054 -0.999992 + outer loop + vertex -158.651 98.4762 298.902 + vertex -179.329 106.071 298.99 + vertex -158.314 104.404 298.904 + endloop + endfacet + facet normal -0.00404121 0.000424377 -0.999992 + outer loop + vertex -179.329 106.071 298.99 + vertex -178.906 112.043 298.991 + vertex -158.314 104.404 298.904 + endloop + endfacet + facet normal -0.00407293 0.000338858 -0.999992 + outer loop + vertex -158.314 104.404 298.904 + vertex -178.906 112.043 298.991 + vertex -157.967 110.376 298.905 + endloop + endfacet + facet normal -0.00407822 0.00027242 -0.999992 + outer loop + vertex -178.906 112.043 298.991 + vertex -178.461 118.026 298.991 + vertex -157.967 110.376 298.905 + endloop + endfacet + facet normal -0.00259656 0.000162328 -0.999997 + outer loop + vertex -178.906 112.043 298.991 + vertex -199.895 119.781 299.047 + vertex -178.461 118.026 298.991 + endloop + endfacet + facet normal -0.00259267 0.000209784 -0.999997 + outer loop + vertex -199.895 119.781 299.047 + vertex -199.354 125.735 299.047 + vertex -178.461 118.026 298.991 + endloop + endfacet + facet normal -0.00261217 0.00015694 -0.999997 + outer loop + vertex -178.461 118.026 298.991 + vertex -199.354 125.735 299.047 + vertex -178.01 123.987 298.99 + endloop + endfacet + facet normal -0.00259584 0.000356406 -0.999997 + outer loop + vertex -199.354 125.735 299.047 + vertex -198.835 131.656 299.047 + vertex -178.01 123.987 298.99 + endloop + endfacet + facet normal -0.000907376 0.000208389 -1 + outer loop + vertex -199.354 125.735 299.047 + vertex -220.217 133.452 299.067 + vertex -198.835 131.656 299.047 + endloop + endfacet + facet normal -0.000872766 0.000620485 -0.999999 + outer loop + vertex -220.217 133.452 299.067 + vertex -219.732 139.348 299.07 + vertex -198.835 131.656 299.047 + endloop + endfacet + facet normal -0.000807115 0.000798858 -0.999999 + outer loop + vertex -198.835 131.656 299.047 + vertex -219.732 139.348 299.07 + vertex -198.353 137.568 299.052 + endloop + endfacet + facet normal -0.00059128 0.00339182 -0.999994 + outer loop + vertex -219.732 139.348 299.07 + vertex -219.298 145.272 299.09 + vertex -198.353 137.568 299.052 + endloop + endfacet + facet normal 0.000853854 0.00328591 -0.999994 + outer loop + vertex -219.732 139.348 299.07 + vertex -239.972 147.022 299.078 + vertex -219.298 145.272 299.09 + endloop + endfacet + facet normal 0.00210281 0.0180395 -0.999835 + outer loop + vertex -239.972 147.022 299.078 + vertex -239.539 153.016 299.187 + vertex -219.298 145.272 299.09 + endloop + endfacet + facet normal 0.00203823 0.0178708 -0.999838 + outer loop + vertex -219.298 145.272 299.09 + vertex -239.539 153.016 299.187 + vertex -218.83 151.279 299.198 + endloop + endfacet + facet normal 0.00544603 0.058509 -0.998272 + outer loop + vertex -239.539 153.016 299.187 + vertex -239.421 159.179 299.549 + vertex -218.83 151.279 299.198 + endloop + endfacet + facet normal 0.00750858 0.058469 -0.998261 + outer loop + vertex -239.539 153.016 299.187 + vertex -258.443 160.816 299.502 + vertex -239.421 159.179 299.549 + endloop + endfacet + facet normal 0.00678415 0.0567174 -0.998367 + outer loop + vertex -258.488 154.66 299.152 + vertex -258.443 160.816 299.502 + vertex -239.539 153.016 299.187 + endloop + endfacet + facet normal 0.00946952 0.0566966 -0.998347 + outer loop + vertex -258.488 154.66 299.152 + vertex -275.106 162.391 299.433 + vertex -258.443 160.816 299.502 + endloop + endfacet + facet normal 0.00878546 0.0552294 -0.998435 + outer loop + vertex -274.851 156.059 299.085 + vertex -275.106 162.391 299.433 + vertex -258.488 154.66 299.152 + endloop + endfacet + facet normal 0.00559525 0.0178523 -0.999825 + outer loop + vertex -258.896 148.628 299.042 + vertex -274.851 156.059 299.085 + vertex -258.488 154.66 299.152 + endloop + endfacet + facet normal 0.00344643 0.0179979 -0.999832 + outer loop + vertex -258.896 148.628 299.042 + vertex -258.488 154.66 299.152 + vertex -239.972 147.022 299.078 + endloop + endfacet + facet normal 0.0022019 0.00333215 -0.999992 + outer loop + vertex -240.361 141.106 299.058 + vertex -258.896 148.628 299.042 + vertex -239.972 147.022 299.078 + endloop + endfacet + facet normal 0.00236516 0.00373443 -0.99999 + outer loop + vertex -259.293 142.693 299.019 + vertex -258.896 148.628 299.042 + vertex -240.361 141.106 299.058 + endloop + endfacet + facet normal 0.00208622 0.000407684 -0.999998 + outer loop + vertex -240.835 135.222 299.054 + vertex -259.293 142.693 299.019 + vertex -240.361 141.106 299.058 + endloop + endfacet + facet normal 0.00066499 0.000522145 -1 + outer loop + vertex -240.835 135.222 299.054 + vertex -240.361 141.106 299.058 + vertex -220.217 133.452 299.067 + endloop + endfacet + facet normal 0.00062043 2.90472e-06 -1 + outer loop + vertex -220.779 127.544 299.067 + vertex -240.835 135.222 299.054 + vertex -220.217 133.452 299.067 + endloop + endfacet + facet normal 0.000599646 -5.13873e-05 -1 + outer loop + vertex -241.442 129.322 299.054 + vertex -240.835 135.222 299.054 + vertex -220.779 127.544 299.067 + endloop + endfacet + facet normal 0.000598357 -6.63696e-05 -1 + outer loop + vertex -221.388 121.597 299.067 + vertex -241.442 129.322 299.054 + vertex -220.779 127.544 299.067 + endloop + endfacet + facet normal -0.000925291 8.95656e-05 -1 + outer loop + vertex -221.388 121.597 299.067 + vertex -220.779 127.544 299.067 + vertex -199.895 119.781 299.047 + endloop + endfacet + facet normal -0.000920407 0.000147356 -1 + outer loop + vertex -200.421 113.802 299.046 + vertex -221.388 121.597 299.067 + vertex -199.895 119.781 299.047 + endloop + endfacet + facet normal -0.000932278 0.000115426 -1 + outer loop + vertex -221.997 115.623 299.067 + vertex -221.388 121.597 299.067 + vertex -200.421 113.802 299.046 + endloop + endfacet + facet normal -0.000922094 0.000236086 -1 + outer loop + vertex -200.923 107.833 299.045 + vertex -221.997 115.623 299.067 + vertex -200.421 113.802 299.046 + endloop + endfacet + facet normal -0.00252764 0.000371178 -0.999997 + outer loop + vertex -200.923 107.833 299.045 + vertex -200.421 113.802 299.046 + vertex -179.329 106.071 298.99 + endloop + endfacet + facet normal -0.00251061 0.000579926 -0.999997 + outer loop + vertex -179.737 100.146 298.988 + vertex -200.923 107.833 299.045 + vertex -179.329 106.071 298.99 + endloop + endfacet + facet normal -0.00252133 0.000550366 -0.999997 + outer loop + vertex -201.405 101.91 299.043 + vertex -200.923 107.833 299.045 + vertex -179.737 100.146 298.988 + endloop + endfacet + facet normal -0.00254933 0.000206414 -0.999997 + outer loop + vertex -180.141 94.2739 298.987 + vertex -201.405 101.91 299.043 + vertex -179.737 100.146 298.988 + endloop + endfacet + facet normal -0.00402393 0.000307774 -0.999992 + outer loop + vertex -180.141 94.2739 298.987 + vertex -179.737 100.146 298.988 + vertex -158.988 92.6031 298.902 + endloop + endfacet + facet normal -0.00420414 -0.00197374 -0.999989 + outer loop + vertex -159.328 86.755 298.915 + vertex -180.141 94.2739 298.987 + vertex -158.988 92.6031 298.902 + endloop + endfacet + facet normal -0.00420194 -0.00196764 -0.999989 + outer loop + vertex -180.548 88.4272 299.001 + vertex -180.141 94.2739 298.987 + vertex -159.328 86.755 298.915 + endloop + endfacet + facet normal -0.00470339 -0.00833283 -0.999954 + outer loop + vertex -159.681 80.8861 298.965 + vertex -180.548 88.4272 299.001 + vertex -159.328 86.755 298.915 + endloop + endfacet + facet normal -0.00539292 -0.00829132 -0.999951 + outer loop + vertex -159.681 80.8861 298.965 + vertex -159.328 86.755 298.915 + vertex -139.127 79.3247 298.867 + endloop + endfacet + facet normal -0.00638301 -0.0213362 -0.999752 + outer loop + vertex -139.437 73.4001 298.996 + vertex -159.681 80.8861 298.965 + vertex -139.127 79.3247 298.867 + endloop + endfacet + facet normal -0.0064519 -0.0215225 -0.999748 + outer loop + vertex -160.07 74.9638 299.095 + vertex -159.681 80.8861 298.965 + vertex -139.437 73.4001 298.996 + endloop + endfacet + facet normal -0.0080323 -0.0424179 -0.999068 + outer loop + vertex -139.777 67.4259 299.252 + vertex -160.07 74.9638 299.095 + vertex -139.437 73.4001 298.996 + endloop + endfacet + facet normal -0.00746134 -0.0424505 -0.999071 + outer loop + vertex -139.777 67.4259 299.252 + vertex -139.437 73.4001 298.996 + vertex -119.623 65.9988 299.162 + endloop + endfacet + facet normal -0.00971699 -0.0744233 -0.997179 + outer loop + vertex -119.94 60.0339 299.611 + vertex -139.777 67.4259 299.252 + vertex -119.623 65.9988 299.162 + endloop + endfacet + facet normal -0.00746609 -0.0424632 -0.99907 + outer loop + vertex -119.623 65.9988 299.162 + vertex -139.437 73.4001 298.996 + vertex -119.345 71.9741 298.906 + endloop + endfacet + facet normal -0.00802411 -0.0423959 -0.999069 + outer loop + vertex -160.477 68.9922 299.352 + vertex -160.07 74.9638 299.095 + vertex -139.777 67.4259 299.252 + endloop + endfacet + facet normal -0.0104124 -0.0740803 -0.997198 + outer loop + vertex -140.167 61.4617 299.699 + vertex -160.477 68.9922 299.352 + vertex -139.777 67.4259 299.252 + endloop + endfacet + facet normal -0.00727171 -0.0424474 -0.999072 + outer loop + vertex -160.477 68.9922 299.352 + vertex -181.416 76.6383 299.18 + vertex -160.07 74.9638 299.095 + endloop + endfacet + facet normal -0.00559938 -0.0210934 -0.999762 + outer loop + vertex -181.416 76.6383 299.18 + vertex -180.976 82.5602 299.052 + vertex -160.07 74.9638 299.095 + endloop + endfacet + facet normal -0.00421759 -0.0211963 -0.999766 + outer loop + vertex -181.416 76.6383 299.18 + vertex -202.851 84.3305 299.107 + vertex -180.976 82.5602 299.052 + endloop + endfacet + facet normal -0.00318128 -0.00838526 -0.99996 + outer loop + vertex -202.851 84.3305 299.107 + vertex -202.359 90.1961 299.056 + vertex -180.976 82.5602 299.052 + endloop + endfacet + facet normal -0.00323783 -0.00854361 -0.999958 + outer loop + vertex -180.976 82.5602 299.052 + vertex -202.359 90.1961 299.056 + vertex -180.548 88.4272 299.001 + endloop + endfacet + facet normal -0.00271172 -0.00205499 -0.999994 + outer loop + vertex -202.359 90.1961 299.056 + vertex -201.881 96.0407 299.043 + vertex -180.548 88.4272 299.001 + endloop + endfacet + facet normal -0.00107612 -0.00218864 -0.999997 + outer loop + vertex -202.359 90.1961 299.056 + vertex -223.672 97.8724 299.062 + vertex -201.881 96.0407 299.043 + endloop + endfacet + facet normal -0.000879993 0.000144443 -1 + outer loop + vertex -223.672 97.8724 299.062 + vertex -223.125 103.739 299.063 + vertex -201.881 96.0407 299.043 + endloop + endfacet + facet normal -0.000883737 0.000134111 -1 + outer loop + vertex -201.881 96.0407 299.043 + vertex -223.125 103.739 299.063 + vertex -201.405 101.91 299.043 + endloop + endfacet + facet normal -0.000850221 0.000532101 -0.999999 + outer loop + vertex -223.125 103.739 299.063 + vertex -222.579 109.659 299.065 + vertex -201.405 101.91 299.043 + endloop + endfacet + facet normal 0.000675794 0.00039132 -1 + outer loop + vertex -223.125 103.739 299.063 + vertex -243.442 111.452 299.052 + vertex -222.579 109.659 299.065 + endloop + endfacet + facet normal 0.000660727 0.000216046 -1 + outer loop + vertex -243.442 111.452 299.052 + vertex -242.804 117.413 299.054 + vertex -222.579 109.659 299.065 + endloop + endfacet + facet normal 0.000630799 0.000137983 -1 + outer loop + vertex -222.579 109.659 299.065 + vertex -242.804 117.413 299.054 + vertex -221.997 115.623 299.067 + endloop + endfacet + facet normal 0.000621669 3.18322e-05 -1 + outer loop + vertex -242.804 117.413 299.054 + vertex -242.128 123.382 299.054 + vertex -221.997 115.623 299.067 + endloop + endfacet + facet normal 0.00214543 -0.000140758 -0.999998 + outer loop + vertex -242.804 117.413 299.054 + vertex -261.213 124.969 299.013 + vertex -242.128 123.382 299.054 + endloop + endfacet + facet normal 0.00214103 -0.000193754 -0.999998 + outer loop + vertex -261.213 124.969 299.013 + vertex -260.461 130.906 299.014 + vertex -242.128 123.382 299.054 + endloop + endfacet + facet normal 0.00211201 -0.000264463 -0.999998 + outer loop + vertex -242.128 123.382 299.054 + vertex -260.461 130.906 299.014 + vertex -241.442 129.322 299.054 + endloop + endfacet + facet normal 0.00212516 -0.000106571 -0.999998 + outer loop + vertex -260.461 130.906 299.014 + vertex -259.792 136.807 299.014 + vertex -241.442 129.322 299.054 + endloop + endfacet + facet normal 0.00423264 -0.000345613 -0.999991 + outer loop + vertex -260.461 130.906 299.014 + vertex -276.511 138.06 298.943 + vertex -259.792 136.807 299.014 + endloop + endfacet + facet normal 0.00428545 0.000359056 -0.999991 + outer loop + vertex -276.511 138.06 298.943 + vertex -275.894 143.952 298.948 + vertex -259.792 136.807 299.014 + endloop + endfacet + facet normal 0.00429559 0.000381908 -0.999991 + outer loop + vertex -259.792 136.807 299.014 + vertex -275.894 143.952 298.948 + vertex -259.293 142.693 299.019 + endloop + endfacet + facet normal 0.00451806 0.00331571 -0.999984 + outer loop + vertex -275.894 143.952 298.948 + vertex -275.438 149.902 298.97 + vertex -259.293 142.693 299.019 + endloop + endfacet + facet normal 0.0104422 0.00286149 -0.999941 + outer loop + vertex -275.894 143.952 298.948 + vertex -289.557 150.804 298.825 + vertex -275.438 149.902 298.97 + endloop + endfacet + facet normal 0.0109585 0.0109599 -0.99988 + outer loop + vertex -289.557 150.804 298.825 + vertex -289.009 156.91 298.898 + vertex -275.438 149.902 298.97 + endloop + endfacet + facet normal 0.014283 0.0173997 -0.999747 + outer loop + vertex -275.438 149.902 298.97 + vertex -289.009 156.91 298.898 + vertex -274.851 156.059 299.085 + endloop + endfacet + facet normal 0.0168821 0.0610293 -0.997993 + outer loop + vertex -289.009 156.91 298.898 + vertex -287.692 163.792 299.341 + vertex -274.851 156.059 299.085 + endloop + endfacet + facet normal 0.051876 0.0542784 -0.997177 + outer loop + vertex -287.692 163.792 299.341 + vertex -289.009 156.91 298.898 + vertex -296.264 162.261 298.812 + endloop + endfacet + facet normal 0.0422306 0.106986 -0.993363 + outer loop + vertex -297.332 165.134 299.076 + vertex -287.692 163.792 299.341 + vertex -296.264 162.261 298.812 + endloop + endfacet + facet normal 0.0904311 0.124414 -0.988101 + outer loop + vertex -296.264 162.261 298.812 + vertex -301.3 165.81 298.798 + vertex -297.332 165.134 299.076 + endloop + endfacet + facet normal 0.0813397 0.111503 -0.99043 + outer loop + vertex -301.612 162.798 298.433 + vertex -301.3 165.81 298.798 + vertex -296.264 162.261 298.812 + endloop + endfacet + facet normal 0.0730268 0.0239366 -0.997043 + outer loop + vertex -297.638 159.511 298.645 + vertex -301.612 162.798 298.433 + vertex -296.264 162.261 298.812 + endloop + endfacet + facet normal 0.0809253 0.0335423 -0.996156 + outer loop + vertex -301.732 159.716 298.319 + vertex -301.612 162.798 298.433 + vertex -297.638 159.511 298.645 + endloop + endfacet + facet normal 0.0802499 0.0194155 -0.996586 + outer loop + vertex -296.762 156.141 298.65 + vertex -301.732 159.716 298.319 + vertex -297.638 159.511 298.645 + endloop + endfacet + facet normal 0.0312948 0.00667514 -0.999488 + outer loop + vertex -297.638 159.511 298.645 + vertex -289.009 156.91 298.898 + vertex -296.762 156.141 298.65 + endloop + endfacet + facet normal 0.0701617 0.00530259 -0.997522 + outer loop + vertex -301.81 156.706 298.298 + vertex -301.732 159.716 298.319 + vertex -296.762 156.141 298.65 + endloop + endfacet + facet normal 0.0681428 -0.0127744 -0.997594 + outer loop + vertex -297.909 153.488 298.606 + vertex -301.81 156.706 298.298 + vertex -296.762 156.141 298.65 + endloop + endfacet + facet normal 0.0277678 0.0047203 -0.999603 + outer loop + vertex -297.909 153.488 298.606 + vertex -296.762 156.141 298.65 + vertex -289.557 150.804 298.825 + endloop + endfacet + facet normal 0.0248764 -0.00428203 -0.999681 + outer loop + vertex -297.909 153.488 298.606 + vertex -289.557 150.804 298.825 + vertex -297.286 150.227 298.635 + endloop + endfacet + facet normal 0.0747378 0.0052716 -0.997189 + outer loop + vertex -297.286 150.227 298.635 + vertex -302.128 153.785 298.291 + vertex -297.909 153.488 298.606 + endloop + endfacet + facet normal 0.0632598 -0.0104235 -0.997943 + outer loop + vertex -302.604 150.882 298.291 + vertex -302.128 153.785 298.291 + vertex -297.286 150.227 298.635 + endloop + endfacet + facet normal 0.0621949 -0.019044 -0.997882 + outer loop + vertex -298.67 147.631 298.598 + vertex -302.604 150.882 298.291 + vertex -297.286 150.227 298.635 + endloop + endfacet + facet normal 0.0255638 0.000515176 -0.999673 + outer loop + vertex -298.67 147.631 298.598 + vertex -297.286 150.227 298.635 + vertex -290.181 144.891 298.814 + endloop + endfacet + facet normal 0.0230065 -0.00741056 -0.999708 + outer loop + vertex -298.67 147.631 298.598 + vertex -290.181 144.891 298.814 + vertex -298.137 144.321 298.635 + endloop + endfacet + facet normal 0.0686399 -3.57745e-05 -0.997642 + outer loop + vertex -298.137 144.321 298.635 + vertex -303.084 147.93 298.295 + vertex -298.67 147.631 298.598 + endloop + endfacet + facet normal 0.061201 -0.0102716 -0.998073 + outer loop + vertex -303.528 144.936 298.298 + vertex -303.084 147.93 298.295 + vertex -298.137 144.321 298.635 + endloop + endfacet + facet normal 0.0600566 -0.0202575 -0.997989 + outer loop + vertex -299.558 141.675 298.603 + vertex -303.528 144.936 298.298 + vertex -298.137 144.321 298.635 + endloop + endfacet + facet normal 0.0241168 -0.000928574 -0.999709 + outer loop + vertex -299.558 141.675 298.603 + vertex -298.137 144.321 298.635 + vertex -290.98 138.979 298.813 + endloop + endfacet + facet normal 0.022752 -0.00527214 -0.999727 + outer loop + vertex -299.558 141.675 298.603 + vertex -290.98 138.979 298.813 + vertex -298.974 138.385 298.634 + endloop + endfacet + facet normal 0.0698417 0.00310244 -0.997553 + outer loop + vertex -298.974 138.385 298.634 + vertex -303.937 141.951 298.298 + vertex -299.558 141.675 298.603 + endloop + endfacet + facet normal 0.0613104 -0.00881899 -0.99808 + outer loop + vertex -304.352 139.005 298.298 + vertex -303.937 141.951 298.298 + vertex -298.974 138.385 298.634 + endloop + endfacet + facet normal 0.0602888 -0.0176444 -0.998025 + outer loop + vertex -300.363 135.79 298.596 + vertex -304.352 139.005 298.298 + vertex -298.974 138.385 298.634 + endloop + endfacet + facet normal 0.0251386 0.00119574 -0.999683 + outer loop + vertex -300.363 135.79 298.596 + vertex -298.974 138.385 298.634 + vertex -291.781 133.077 298.808 + endloop + endfacet + facet normal 0.022993 -0.00559289 -0.99972 + outer loop + vertex -300.363 135.79 298.596 + vertex -291.781 133.077 298.808 + vertex -299.782 132.529 298.628 + endloop + endfacet + facet normal 0.0689915 0.00262496 -0.997614 + outer loop + vertex -299.782 132.529 298.628 + vertex -304.747 136.095 298.294 + vertex -300.363 135.79 298.596 + endloop + endfacet + facet normal 0.0611893 -0.00828021 -0.998092 + outer loop + vertex -305.158 133.181 298.292 + vertex -304.747 136.095 298.294 + vertex -299.782 132.529 298.628 + endloop + endfacet + facet normal 0.0599311 -0.0186154 -0.998029 + outer loop + vertex -301.178 129.923 298.592 + vertex -305.158 133.181 298.292 + vertex -299.782 132.529 298.628 + endloop + endfacet + facet normal 0.0248643 0.00019208 -0.999691 + outer loop + vertex -301.178 129.923 298.592 + vertex -299.782 132.529 298.628 + vertex -292.59 127.16 298.805 + endloop + endfacet + facet normal 0.022898 -0.00592063 -0.99972 + outer loop + vertex -301.178 129.923 298.592 + vertex -292.59 127.16 298.805 + vertex -300.599 126.591 298.625 + endloop + endfacet + facet normal 0.0686407 0.00204608 -0.997639 + outer loop + vertex -300.599 126.591 298.625 + vertex -305.568 130.227 298.291 + vertex -301.178 129.923 298.592 + endloop + endfacet + facet normal 0.0615398 -0.00769937 -0.998075 + outer loop + vertex -305.981 127.223 298.289 + vertex -305.568 130.227 298.291 + vertex -300.599 126.591 298.625 + endloop + endfacet + facet normal 0.0601495 -0.0194999 -0.997999 + outer loop + vertex -302.016 123.915 298.592 + vertex -305.981 127.223 298.289 + vertex -300.599 126.591 298.625 + endloop + endfacet + facet normal 0.0242534 -0.000464969 -0.999706 + outer loop + vertex -302.016 123.915 298.592 + vertex -300.599 126.591 298.625 + vertex -293.383 121.175 298.803 + endloop + endfacet + facet normal 0.022734 -0.00525421 -0.999728 + outer loop + vertex -302.016 123.915 298.592 + vertex -293.383 121.175 298.803 + vertex -301.422 120.557 298.623 + endloop + endfacet + facet normal 0.0696859 0.00307 -0.997564 + outer loop + vertex -301.422 120.557 298.623 + vertex -306.401 124.193 298.287 + vertex -302.016 123.915 298.592 + endloop + endfacet + facet normal 0.0614852 -0.00820473 -0.998074 + outer loop + vertex -306.823 121.165 298.286 + vertex -306.401 124.193 298.287 + vertex -301.422 120.557 298.623 + endloop + endfacet + facet normal 0.0601828 -0.0197276 -0.997992 + outer loop + vertex -302.839 117.887 298.591 + vertex -306.823 121.165 298.286 + vertex -301.422 120.557 298.623 + endloop + endfacet + facet normal 0.0241894 -0.000615686 -0.999707 + outer loop + vertex -302.839 117.887 298.591 + vertex -301.422 120.557 298.623 + vertex -294.18 115.197 298.802 + endloop + endfacet + facet normal 0.0229861 -0.00449097 -0.999726 + outer loop + vertex -302.839 117.887 298.591 + vertex -294.18 115.197 298.802 + vertex -302.221 114.586 298.62 + endloop + endfacet + facet normal 0.0694835 0.00422242 -0.997574 + outer loop + vertex -302.221 114.586 298.62 + vertex -307.242 118.162 298.285 + vertex -302.839 117.887 298.591 + endloop + endfacet + facet normal 0.0602177 -0.0088393 -0.998146 + outer loop + vertex -307.666 115.191 298.286 + vertex -307.242 118.162 298.285 + vertex -302.221 114.586 298.62 + endloop + endfacet + facet normal 0.0588989 -0.0206412 -0.998051 + outer loop + vertex -303.656 111.972 298.589 + vertex -307.666 115.191 298.286 + vertex -302.221 114.586 298.62 + endloop + endfacet + facet normal 0.0235573 -0.00121562 -0.999722 + outer loop + vertex -303.656 111.972 298.589 + vertex -302.221 114.586 298.62 + vertex -294.943 109.302 298.798 + endloop + endfacet + facet normal 0.0226237 -0.00426397 -0.999735 + outer loop + vertex -303.656 111.972 298.589 + vertex -294.943 109.302 298.798 + vertex -303.025 108.726 298.617 + endloop + endfacet + facet normal 0.0696689 0.00491147 -0.997558 + outer loop + vertex -303.025 108.726 298.617 + vertex -308.064 112.255 298.283 + vertex -303.656 111.972 298.589 + endloop + endfacet + facet normal 0.0604247 -0.00834774 -0.998138 + outer loop + vertex -308.475 109.34 298.282 + vertex -308.064 112.255 298.283 + vertex -303.025 108.726 298.617 + endloop + endfacet + facet normal 0.0591751 -0.0194109 -0.998059 + outer loop + vertex -304.432 106.153 298.584 + vertex -308.475 109.34 298.282 + vertex -303.025 108.726 298.617 + endloop + endfacet + facet normal 0.0243823 -0.000363099 -0.999703 + outer loop + vertex -304.432 106.153 298.584 + vertex -303.025 108.726 298.617 + vertex -295.712 103.474 298.797 + endloop + endfacet + facet normal 0.0226306 -0.00606668 -0.999725 + outer loop + vertex -304.432 106.153 298.584 + vertex -295.712 103.474 298.797 + vertex -303.817 102.924 298.617 + endloop + endfacet + facet normal 0.0681741 0.00262563 -0.99767 + outer loop + vertex -303.817 102.924 298.617 + vertex -308.875 106.439 298.281 + vertex -304.432 106.153 298.584 + endloop + endfacet + facet normal 0.060321 -0.00872093 -0.998141 + outer loop + vertex -309.281 103.543 298.282 + vertex -308.875 106.439 298.281 + vertex -303.817 102.924 298.617 + endloop + endfacet + facet normal 0.0589199 -0.021049 -0.998041 + outer loop + vertex -305.226 100.354 298.588 + vertex -309.281 103.543 298.282 + vertex -303.817 102.924 298.617 + endloop + endfacet + facet normal 0.0248666 -0.00235804 -0.999688 + outer loop + vertex -305.226 100.354 298.588 + vertex -303.817 102.924 298.617 + vertex -296.488 97.6535 298.812 + endloop + endfacet + facet normal 0.0225772 -0.00976562 -0.999697 + outer loop + vertex -305.226 100.354 298.588 + vertex -296.488 97.6535 298.812 + vertex -304.607 97.1027 298.634 + endloop + endfacet + facet normal 0.0679558 -0.00109729 -0.997688 + outer loop + vertex -304.607 97.1027 298.634 + vertex -309.678 100.638 298.285 + vertex -305.226 100.354 298.588 + endloop + endfacet + facet normal 0.0600104 -0.0125368 -0.998119 + outer loop + vertex -310.09 97.7149 298.297 + vertex -309.678 100.638 298.285 + vertex -304.607 97.1027 298.634 + endloop + endfacet + facet normal 0.0583098 -0.0276556 -0.997915 + outer loop + vertex -306.043 94.5023 298.622 + vertex -310.09 97.7149 298.297 + vertex -304.607 97.1027 298.634 + endloop + endfacet + facet normal 0.0251435 -0.00933955 -0.99964 + outer loop + vertex -306.043 94.5023 298.622 + vertex -304.607 97.1027 298.634 + vertex -297.285 91.7863 298.868 + endloop + endfacet + facet normal 0.0218551 -0.0199364 -0.999562 + outer loop + vertex -306.043 94.5023 298.622 + vertex -297.285 91.7863 298.868 + vertex -305.445 91.2098 298.701 + endloop + endfacet + facet normal 0.0658864 -0.0119014 -0.997756 + outer loop + vertex -305.445 91.2098 298.701 + vertex -310.52 94.7692 298.323 + vertex -306.043 94.5023 298.622 + endloop + endfacet + facet normal 0.057573 -0.0237859 -0.998058 + outer loop + vertex -310.968 91.8033 298.368 + vertex -310.52 94.7692 298.323 + vertex -305.445 91.2098 298.701 + endloop + endfacet + facet normal 0.0556073 -0.0418074 -0.997577 + outer loop + vertex -306.949 88.5756 298.728 + vertex -310.968 91.8033 298.368 + vertex -305.445 91.2098 298.701 + endloop + endfacet + facet normal 0.0243494 -0.0239771 -0.999416 + outer loop + vertex -306.949 88.5756 298.728 + vertex -305.445 91.2098 298.701 + vertex -298.155 85.8724 299.007 + endloop + endfacet + facet normal 0.0199643 -0.0382077 -0.99907 + outer loop + vertex -306.949 88.5756 298.728 + vertex -298.155 85.8724 299.007 + vertex -306.44 85.2837 298.864 + endloop + endfacet + facet normal 0.0623072 -0.0315889 -0.997557 + outer loop + vertex -306.44 85.2837 298.864 + vertex -311.458 88.835 298.438 + vertex -306.949 88.5756 298.728 + endloop + endfacet + facet normal 0.0545416 -0.0425671 -0.997604 + outer loop + vertex -312.002 85.8906 298.534 + vertex -311.458 88.835 298.438 + vertex -306.44 85.2837 298.864 + endloop + endfacet + facet normal 0.0523397 -0.0622476 -0.996687 + outer loop + vertex -308.013 82.6833 298.943 + vertex -312.002 85.8906 298.534 + vertex -306.44 85.2837 298.864 + endloop + endfacet + facet normal 0.119336 -0.054338 -0.991366 + outer loop + vertex -312.002 85.8906 298.534 + vertex -315.496 89.4006 297.921 + vertex -311.458 88.835 298.438 + endloop + endfacet + facet normal 0.120801 -0.0441776 -0.991693 + outer loop + vertex -315.496 89.4006 297.921 + vertex -315.002 92.3476 297.849 + vertex -311.458 88.835 298.438 + endloop + endfacet + facet normal 0.12168 -0.0432789 -0.991625 + outer loop + vertex -311.458 88.835 298.438 + vertex -315.002 92.3476 297.849 + vertex -310.968 91.8033 298.368 + endloop + endfacet + facet normal 0.122747 -0.0355355 -0.991802 + outer loop + vertex -315.002 92.3476 297.849 + vertex -314.538 95.306 297.801 + vertex -310.968 91.8033 298.368 + endloop + endfacet + facet normal 0.116332 -0.0573606 -0.991553 + outer loop + vertex -316.068 86.4903 298.022 + vertex -315.496 89.4006 297.921 + vertex -312.002 85.8906 298.534 + endloop + endfacet + facet normal 0.114678 -0.0681538 -0.991062 + outer loop + vertex -312.596 82.9871 298.665 + vertex -316.068 86.4903 298.022 + vertex -312.002 85.8906 298.534 + endloop + endfacet + facet normal 0.113785 -0.0690472 -0.991103 + outer loop + vertex -316.65 83.6152 298.155 + vertex -316.068 86.4903 298.022 + vertex -312.596 82.9871 298.665 + endloop + endfacet + facet normal 0.0207663 -0.0496206 -0.998552 + outer loop + vertex -298.155 85.8724 299.007 + vertex -299.147 79.9811 299.279 + vertex -306.44 85.2837 298.864 + endloop + endfacet + facet normal 0.00456189 -0.0469076 -0.998889 + outer loop + vertex -299.147 79.9811 299.279 + vertex -298.155 85.8724 299.007 + vertex -284.122 79.0131 299.393 + endloop + endfacet + facet normal 0.00545472 -0.0450855 -0.998968 + outer loop + vertex -284.122 79.0131 299.393 + vertex -298.155 85.8724 299.007 + vertex -283.264 84.9328 299.13 + endloop + endfacet + facet normal -0.000101207 -0.0442825 -0.999019 + outer loop + vertex -284.122 79.0131 299.393 + vertex -283.264 84.9328 299.13 + vertex -266.769 77.7177 299.449 + endloop + endfacet + facet normal -0.00232251 -0.0739615 -0.997258 + outer loop + vertex -267.582 71.8191 299.888 + vertex -284.122 79.0131 299.393 + vertex -266.769 77.7177 299.449 + endloop + endfacet + facet normal 0.000585806 -0.0427149 -0.999087 + outer loop + vertex -266.769 77.7177 299.449 + vertex -283.264 84.9328 299.13 + vertex -266.001 83.6591 299.195 + endloop + endfacet + facet normal -0.00146754 -0.0424497 -0.999098 + outer loop + vertex -266.769 77.7177 299.449 + vertex -266.001 83.6591 299.195 + vertex -247.153 76.0964 299.489 + endloop + endfacet + facet normal -0.00397254 -0.0727159 -0.997345 + outer loop + vertex -247.867 70.1667 299.924 + vertex -266.769 77.7177 299.449 + vertex -247.153 76.0964 299.489 + endloop + endfacet + facet normal -0.00139436 -0.0422676 -0.999105 + outer loop + vertex -247.153 76.0964 299.489 + vertex -266.001 83.6591 299.195 + vertex -246.513 82.0547 299.236 + endloop + endfacet + facet normal -0.00282136 -0.0421145 -0.999109 + outer loop + vertex -247.153 76.0964 299.489 + vertex -246.513 82.0547 299.236 + vertex -225.92 74.2888 299.505 + endloop + endfacet + facet normal -0.00546523 -0.0731544 -0.997306 + outer loop + vertex -226.523 68.3428 299.944 + vertex -247.153 76.0964 299.489 + vertex -225.92 74.2888 299.505 + endloop + endfacet + facet normal -0.0028228 -0.0421183 -0.999109 + outer loop + vertex -225.92 74.2888 299.505 + vertex -246.513 82.0547 299.236 + vertex -225.343 80.2507 299.252 + endloop + endfacet + facet normal -0.00417893 -0.0419872 -0.999109 + outer loop + vertex -225.92 74.2888 299.505 + vertex -225.343 80.2507 299.252 + vertex -203.885 72.4472 299.49 + endloop + endfacet + facet normal -0.00677507 -0.0730642 -0.997304 + outer loop + vertex -204.439 66.4944 299.93 + vertex -225.92 74.2888 299.505 + vertex -203.885 72.4472 299.49 + endloop + endfacet + facet normal -0.00437285 -0.0425197 -0.999086 + outer loop + vertex -203.885 72.4472 299.49 + vertex -225.343 80.2507 299.252 + vertex -203.36 78.4115 299.234 + endloop + endfacet + facet normal -0.00592062 -0.0423833 -0.999084 + outer loop + vertex -203.885 72.4472 299.49 + vertex -203.36 78.4115 299.234 + vertex -181.889 70.6694 299.435 + endloop + endfacet + facet normal -0.00840994 -0.0732383 -0.997279 + outer loop + vertex -182.395 64.7099 299.877 + vertex -203.885 72.4472 299.49 + vertex -181.889 70.6694 299.435 + endloop + endfacet + facet normal -0.00589003 -0.0422986 -0.999088 + outer loop + vertex -181.889 70.6694 299.435 + vertex -203.36 78.4115 299.234 + vertex -181.416 76.6383 299.18 + endloop + endfacet + facet normal -0.00257855 -0.0210663 -0.999775 + outer loop + vertex -225.343 80.2507 299.252 + vertex -224.772 86.1668 299.126 + vertex -203.36 78.4115 299.234 + endloop + endfacet + facet normal -0.0026332 -0.0212171 -0.999771 + outer loop + vertex -203.36 78.4115 299.234 + vertex -224.772 86.1668 299.126 + vertex -202.851 84.3305 299.107 + endloop + endfacet + facet normal -0.00156664 -0.00848234 -0.999963 + outer loop + vertex -224.772 86.1668 299.126 + vertex -224.229 92.0314 299.075 + vertex -202.851 84.3305 299.107 + endloop + endfacet + facet normal -4.61278e-05 -0.00862312 -0.999963 + outer loop + vertex -224.772 86.1668 299.126 + vertex -245.287 93.8356 299.061 + vertex -224.229 92.0314 299.075 + endloop + endfacet + facet normal 0.000509513 -0.00213832 -0.999998 + outer loop + vertex -245.287 93.8356 299.061 + vertex -244.68 99.6748 299.048 + vertex -224.229 92.0314 299.075 + endloop + endfacet + facet normal 0.000473615 -0.00223437 -0.999997 + outer loop + vertex -224.229 92.0314 299.075 + vertex -244.68 99.6748 299.048 + vertex -223.672 97.8724 299.062 + endloop + endfacet + facet normal 0.000673007 8.98137e-05 -1 + outer loop + vertex -244.68 99.6748 299.048 + vertex -244.057 105.536 299.049 + vertex -223.672 97.8724 299.062 + endloop + endfacet + facet normal 0.00219418 -7.20328e-05 -0.999998 + outer loop + vertex -244.68 99.6748 299.048 + vertex -263.323 107.137 299.007 + vertex -244.057 105.536 299.049 + endloop + endfacet + facet normal 0.0022224 0.000267579 -0.999997 + outer loop + vertex -263.323 107.137 299.007 + vertex -262.634 113.047 299.01 + vertex -244.057 105.536 299.049 + endloop + endfacet + facet normal 0.00220506 0.000224696 -0.999998 + outer loop + vertex -244.057 105.536 299.049 + vertex -262.634 113.047 299.01 + vertex -243.442 111.452 299.052 + endloop + endfacet + facet normal 0.00219191 6.64968e-05 -0.999998 + outer loop + vertex -262.634 113.047 299.01 + vertex -261.937 119.004 299.012 + vertex -243.442 111.452 299.052 + endloop + endfacet + facet normal 0.00438323 -0.000189679 -0.99999 + outer loop + vertex -262.634 113.047 299.01 + vertex -278.815 120.256 298.938 + vertex -261.937 119.004 299.012 + endloop + endfacet + facet normal 0.00437936 -0.000241736 -0.99999 + outer loop + vertex -278.815 120.256 298.938 + vertex -278.054 126.219 298.94 + vertex -261.937 119.004 299.012 + endloop + endfacet + facet normal 0.00434079 -0.00032789 -0.999991 + outer loop + vertex -261.937 119.004 299.012 + vertex -278.054 126.219 298.94 + vertex -261.213 124.969 299.013 + endloop + endfacet + facet normal 0.00435348 -0.000157043 -0.999991 + outer loop + vertex -278.054 126.219 298.94 + vertex -277.286 132.156 298.942 + vertex -261.213 124.969 299.013 + endloop + endfacet + facet normal 0.00916734 -0.000779792 -0.999958 + outer loop + vertex -278.054 126.219 298.94 + vertex -291.781 133.077 298.808 + vertex -277.286 132.156 298.942 + endloop + endfacet + facet normal 0.00918367 -0.000523026 -0.999958 + outer loop + vertex -291.781 133.077 298.808 + vertex -290.98 138.979 298.813 + vertex -277.286 132.156 298.942 + endloop + endfacet + facet normal 0.008956 -0.000979947 -0.999959 + outer loop + vertex -277.286 132.156 298.942 + vertex -290.98 138.979 298.813 + vertex -276.511 138.06 298.943 + endloop + endfacet + facet normal 0.00895483 -0.000998493 -0.999959 + outer loop + vertex -290.98 138.979 298.813 + vertex -290.181 144.891 298.814 + vertex -276.511 138.06 298.943 + endloop + endfacet + facet normal 0.00919013 -0.000734169 -0.999958 + outer loop + vertex -292.59 127.16 298.805 + vertex -291.781 133.077 298.808 + vertex -278.054 126.219 298.94 + endloop + endfacet + facet normal 0.00918233 -0.000854819 -0.999957 + outer loop + vertex -278.815 120.256 298.938 + vertex -292.59 127.16 298.805 + vertex -278.054 126.219 298.94 + endloop + endfacet + facet normal 0.00920841 -0.000802773 -0.999957 + outer loop + vertex -293.383 121.175 298.803 + vertex -292.59 127.16 298.805 + vertex -278.815 120.256 298.938 + endloop + endfacet + facet normal 0.00920893 -0.000794638 -0.999957 + outer loop + vertex -279.562 114.296 298.936 + vertex -293.383 121.175 298.803 + vertex -278.815 120.256 298.938 + endloop + endfacet + facet normal 0.00908744 -0.00103873 -0.999958 + outer loop + vertex -294.18 115.197 298.802 + vertex -293.383 121.175 298.803 + vertex -279.562 114.296 298.936 + endloop + endfacet + facet normal 0.00911078 -0.000660222 -0.999958 + outer loop + vertex -280.305 108.39 298.933 + vertex -294.18 115.197 298.802 + vertex -279.562 114.296 298.936 + endloop + endfacet + facet normal 0.00436401 -6.31712e-05 -0.99999 + outer loop + vertex -280.305 108.39 298.933 + vertex -279.562 114.296 298.936 + vertex -263.323 107.137 299.007 + endloop + endfacet + facet normal 0.00435082 -0.00024187 -0.999991 + outer loop + vertex -263.999 101.281 299.005 + vertex -280.305 108.39 298.933 + vertex -263.323 107.137 299.007 + endloop + endfacet + facet normal 0.00431024 -0.000334938 -0.999991 + outer loop + vertex -281.042 102.545 298.932 + vertex -280.305 108.39 298.933 + vertex -263.999 101.281 299.005 + endloop + endfacet + facet normal 0.00415151 -0.00247536 -0.999988 + outer loop + vertex -264.637 95.4402 299.017 + vertex -281.042 102.545 298.932 + vertex -263.999 101.281 299.005 + endloop + endfacet + facet normal 0.00205332 -0.00224627 -0.999995 + outer loop + vertex -264.637 95.4402 299.017 + vertex -263.999 101.281 299.005 + vertex -245.287 93.8356 299.061 + endloop + endfacet + facet normal 0.00152797 -0.00858066 -0.999962 + outer loop + vertex -245.899 87.9725 299.11 + vertex -264.637 95.4402 299.017 + vertex -245.287 93.8356 299.061 + endloop + endfacet + facet normal 0.00145721 -0.00875821 -0.999961 + outer loop + vertex -265.308 89.5759 299.068 + vertex -264.637 95.4402 299.017 + vertex -245.899 87.9725 299.11 + endloop + endfacet + facet normal 0.000422341 -0.0212804 -0.999773 + outer loop + vertex -246.513 82.0547 299.236 + vertex -265.308 89.5759 299.068 + vertex -245.899 87.9725 299.11 + endloop + endfacet + facet normal 0.00359699 -0.00900304 -0.999953 + outer loop + vertex -265.308 89.5759 299.068 + vertex -281.724 96.7075 298.944 + vertex -264.637 95.4402 299.017 + endloop + endfacet + facet normal 0.00337147 -0.00952208 -0.999949 + outer loop + vertex -282.471 90.8443 298.998 + vertex -281.724 96.7075 298.944 + vertex -265.308 89.5759 299.068 + endloop + endfacet + facet normal 0.00246281 -0.0218067 -0.999759 + outer loop + vertex -266.001 83.6591 299.195 + vertex -282.471 90.8443 298.998 + vertex -265.308 89.5759 299.068 + endloop + endfacet + facet normal 0.00830922 -0.0101507 -0.999914 + outer loop + vertex -282.471 90.8443 298.998 + vertex -296.488 97.6535 298.812 + vertex -281.724 96.7075 298.944 + endloop + endfacet + facet normal 0.00872487 -0.00367011 -0.999955 + outer loop + vertex -296.488 97.6535 298.812 + vertex -295.712 103.474 298.797 + vertex -281.724 96.7075 298.944 + endloop + endfacet + facet normal 0.00893305 -0.00323977 -0.999955 + outer loop + vertex -281.724 96.7075 298.944 + vertex -295.712 103.474 298.797 + vertex -281.042 102.545 298.932 + endloop + endfacet + facet normal 0.00906432 -0.00116873 -0.999958 + outer loop + vertex -295.712 103.474 298.797 + vertex -294.943 109.302 298.798 + vertex -281.042 102.545 298.932 + endloop + endfacet + facet normal 0.00808145 -0.0106195 -0.999911 + outer loop + vertex -297.285 91.7863 298.868 + vertex -296.488 97.6535 298.812 + vertex -282.471 90.8443 298.998 + endloop + endfacet + facet normal 0.00726568 -0.0234191 -0.999699 + outer loop + vertex -283.264 84.9328 299.13 + vertex -297.285 91.7863 298.868 + vertex -282.471 90.8443 298.998 + endloop + endfacet + facet normal 0.00406675 -0.00267109 -0.999988 + outer loop + vertex -281.724 96.7075 298.944 + vertex -281.042 102.545 298.932 + vertex -264.637 95.4402 299.017 + endloop + endfacet + facet normal 0.0091715 -0.000948232 -0.999957 + outer loop + vertex -281.042 102.545 298.932 + vertex -294.943 109.302 298.798 + vertex -280.305 108.39 298.933 + endloop + endfacet + facet normal 0.0092009 -0.000476514 -0.999958 + outer loop + vertex -294.943 109.302 298.798 + vertex -294.18 115.197 298.802 + vertex -280.305 108.39 298.933 + endloop + endfacet + facet normal 0.00438292 -0.00019036 -0.99999 + outer loop + vertex -279.562 114.296 298.936 + vertex -278.815 120.256 298.938 + vertex -262.634 113.047 299.01 + endloop + endfacet + facet normal 0.004398 1.39245e-05 -0.99999 + outer loop + vertex -263.323 107.137 299.007 + vertex -279.562 114.296 298.936 + vertex -262.634 113.047 299.01 + endloop + endfacet + facet normal 0.00222448 3.68739e-06 -0.999998 + outer loop + vertex -263.999 101.281 299.005 + vertex -263.323 107.137 299.007 + vertex -244.68 99.6748 299.048 + endloop + endfacet + facet normal 0.00203323 -0.00229678 -0.999995 + outer loop + vertex -245.287 93.8356 299.061 + vertex -263.999 101.281 299.005 + vertex -244.68 99.6748 299.048 + endloop + endfacet + facet normal 2.81966e-05 -0.00842431 -0.999965 + outer loop + vertex -245.899 87.9725 299.11 + vertex -245.287 93.8356 299.061 + vertex -224.772 86.1668 299.126 + endloop + endfacet + facet normal -0.00106496 -0.0212123 -0.999774 + outer loop + vertex -225.343 80.2507 299.252 + vertex -245.899 87.9725 299.11 + vertex -224.772 86.1668 299.126 + endloop + endfacet + facet normal -0.00103375 -0.0211293 -0.999776 + outer loop + vertex -246.513 82.0547 299.236 + vertex -245.899 87.9725 299.11 + vertex -225.343 80.2507 299.252 + endloop + endfacet + facet normal 0.000312321 -0.0215552 -0.999768 + outer loop + vertex -266.001 83.6591 299.195 + vertex -265.308 89.5759 299.068 + vertex -246.513 82.0547 299.236 + endloop + endfacet + facet normal 0.00206324 -0.0227221 -0.99974 + outer loop + vertex -283.264 84.9328 299.13 + vertex -282.471 90.8443 298.998 + vertex -266.001 83.6591 299.195 + endloop + endfacet + facet normal 0.00676293 -0.0244467 -0.999678 + outer loop + vertex -298.155 85.8724 299.007 + vertex -297.285 91.7863 298.868 + vertex -283.264 84.9328 299.13 + endloop + endfacet + facet normal 0.0621873 -0.0336061 -0.997499 + outer loop + vertex -311.458 88.835 298.438 + vertex -310.968 91.8033 298.368 + vertex -306.949 88.5756 298.728 + endloop + endfacet + facet normal 0.124434 -0.0337925 -0.991652 + outer loop + vertex -310.968 91.8033 298.368 + vertex -314.538 95.306 297.801 + vertex -310.52 94.7692 298.323 + endloop + endfacet + facet normal 0.125251 -0.0277542 -0.991737 + outer loop + vertex -314.538 95.306 297.801 + vertex -314.102 98.2551 297.773 + vertex -310.52 94.7692 298.323 + endloop + endfacet + facet normal 0.125667 -0.0273205 -0.991696 + outer loop + vertex -310.52 94.7692 298.323 + vertex -314.102 98.2551 297.773 + vertex -310.09 97.7149 298.297 + endloop + endfacet + facet normal 0.126308 -0.0225974 -0.991734 + outer loop + vertex -314.102 98.2551 297.773 + vertex -313.678 101.186 297.761 + vertex -310.09 97.7149 298.297 + endloop + endfacet + facet normal 0.0223317 -0.0267317 -0.999393 + outer loop + vertex -297.285 91.7863 298.868 + vertex -298.155 85.8724 299.007 + vertex -305.445 91.2098 298.701 + endloop + endfacet + facet normal 0.0654822 -0.0185957 -0.99768 + outer loop + vertex -310.52 94.7692 298.323 + vertex -310.09 97.7149 298.297 + vertex -306.043 94.5023 298.622 + endloop + endfacet + facet normal 0.126918 -0.0219564 -0.99167 + outer loop + vertex -310.09 97.7149 298.297 + vertex -313.678 101.186 297.761 + vertex -309.678 100.638 298.285 + endloop + endfacet + facet normal 0.127205 -0.0198747 -0.991677 + outer loop + vertex -313.678 101.186 297.761 + vertex -313.261 104.1 297.756 + vertex -309.678 100.638 298.285 + endloop + endfacet + facet normal 0.128414 -0.0186034 -0.991546 + outer loop + vertex -309.678 100.638 298.285 + vertex -313.261 104.1 297.756 + vertex -309.281 103.543 298.282 + endloop + endfacet + facet normal 0.12837 -0.018918 -0.991546 + outer loop + vertex -313.261 104.1 297.756 + vertex -312.845 107.005 297.754 + vertex -309.281 103.543 298.282 + endloop + endfacet + facet normal 0.0227694 -0.0126105 -0.999661 + outer loop + vertex -296.488 97.6535 298.812 + vertex -297.285 91.7863 298.868 + vertex -304.607 97.1027 298.634 + endloop + endfacet + facet normal 0.0673717 -0.0102667 -0.997675 + outer loop + vertex -309.678 100.638 298.285 + vertex -309.281 103.543 298.282 + vertex -305.226 100.354 298.588 + endloop + endfacet + facet normal 0.128944 -0.0183173 -0.991483 + outer loop + vertex -309.281 103.543 298.282 + vertex -312.845 107.005 297.754 + vertex -308.875 106.439 298.281 + endloop + endfacet + facet normal 0.129025 -0.0177511 -0.991482 + outer loop + vertex -312.845 107.005 297.754 + vertex -312.438 109.911 297.755 + vertex -308.875 106.439 298.281 + endloop + endfacet + facet normal 0.129312 -0.0174517 -0.99145 + outer loop + vertex -308.875 106.439 298.281 + vertex -312.438 109.911 297.755 + vertex -308.475 109.34 298.282 + endloop + endfacet + facet normal 0.129086 -0.0190216 -0.991451 + outer loop + vertex -312.438 109.911 297.755 + vertex -312.015 112.828 297.754 + vertex -308.475 109.34 298.282 + endloop + endfacet + facet normal 0.0225936 -0.00551995 -0.999729 + outer loop + vertex -295.712 103.474 298.797 + vertex -296.488 97.6535 298.812 + vertex -303.817 102.924 298.617 + endloop + endfacet + facet normal 0.0674331 -0.00889834 -0.997684 + outer loop + vertex -308.875 106.439 298.281 + vertex -308.475 109.34 298.282 + vertex -304.432 106.153 298.584 + endloop + endfacet + facet normal 0.129947 -0.0181337 -0.991355 + outer loop + vertex -308.475 109.34 298.282 + vertex -312.015 112.828 297.754 + vertex -308.064 112.255 298.283 + endloop + endfacet + facet normal 0.129961 -0.0180364 -0.991355 + outer loop + vertex -312.015 112.828 297.754 + vertex -311.601 115.769 297.755 + vertex -308.064 112.255 298.283 + endloop + endfacet + facet normal 0.131266 -0.0167003 -0.991207 + outer loop + vertex -308.064 112.255 298.283 + vertex -311.601 115.769 297.755 + vertex -307.666 115.191 298.286 + endloop + endfacet + facet normal 0.131008 -0.0184593 -0.991209 + outer loop + vertex -311.601 115.769 297.755 + vertex -311.175 118.736 297.756 + vertex -307.666 115.191 298.286 + endloop + endfacet + facet normal 0.0225297 -0.00294383 -0.999742 + outer loop + vertex -294.943 109.302 298.798 + vertex -295.712 103.474 298.797 + vertex -303.025 108.726 298.617 + endloop + endfacet + facet normal 0.0688286 -0.00823033 -0.997595 + outer loop + vertex -308.064 112.255 298.283 + vertex -307.666 115.191 298.286 + vertex -303.656 111.972 298.589 + endloop + endfacet + facet normal 0.13059 -0.01888 -0.991257 + outer loop + vertex -307.666 115.191 298.286 + vertex -311.175 118.736 297.756 + vertex -307.242 118.162 298.285 + endloop + endfacet + facet normal 0.13067 -0.0183323 -0.991256 + outer loop + vertex -311.175 118.736 297.756 + vertex -310.748 121.738 297.757 + vertex -307.242 118.162 298.285 + endloop + endfacet + facet normal 0.130878 -0.0181252 -0.991233 + outer loop + vertex -307.242 118.162 298.285 + vertex -310.748 121.738 297.757 + vertex -306.823 121.165 298.286 + endloop + endfacet + facet normal 0.131091 -0.0166633 -0.99123 + outer loop + vertex -310.748 121.738 297.757 + vertex -310.335 124.764 297.761 + vertex -306.823 121.165 298.286 + endloop + endfacet + facet normal 0.022815 -0.00223877 -0.999737 + outer loop + vertex -294.18 115.197 298.802 + vertex -294.943 109.302 298.798 + vertex -302.221 114.586 298.62 + endloop + endfacet + facet normal 0.0686318 -0.00942222 -0.997598 + outer loop + vertex -307.242 118.162 298.285 + vertex -306.823 121.165 298.286 + vertex -302.839 117.887 298.591 + endloop + endfacet + facet normal 0.129993 -0.0177525 -0.991356 + outer loop + vertex -306.823 121.165 298.286 + vertex -310.335 124.764 297.761 + vertex -306.401 124.193 298.287 + endloop + endfacet + facet normal 0.129807 -0.0190358 -0.991357 + outer loop + vertex -310.335 124.764 297.761 + vertex -309.894 127.798 297.76 + vertex -306.401 124.193 298.287 + endloop + endfacet + facet normal 0.131283 -0.0175809 -0.991189 + outer loop + vertex -306.401 124.193 298.287 + vertex -309.894 127.798 297.76 + vertex -305.981 127.223 298.289 + endloop + endfacet + facet normal 0.131214 -0.01805 -0.99119 + outer loop + vertex -309.894 127.798 297.76 + vertex -309.468 130.809 297.762 + vertex -305.981 127.223 298.289 + endloop + endfacet + facet normal 0.0225482 -0.00283447 -0.999742 + outer loop + vertex -293.383 121.175 298.803 + vertex -294.18 115.197 298.802 + vertex -301.422 120.557 298.623 + endloop + endfacet + facet normal 0.068926 -0.00894191 -0.997582 + outer loop + vertex -306.401 124.193 298.287 + vertex -305.981 127.223 298.289 + vertex -302.016 123.915 298.592 + endloop + endfacet + facet normal 0.131885 -0.0173868 -0.991113 + outer loop + vertex -305.981 127.223 298.289 + vertex -309.468 130.809 297.762 + vertex -305.568 130.227 298.291 + endloop + endfacet + facet normal 0.131845 -0.0176521 -0.991113 + outer loop + vertex -309.468 130.809 297.762 + vertex -309.054 133.775 297.764 + vertex -305.568 130.227 298.291 + endloop + endfacet + facet normal 0.131781 -0.0177159 -0.99112 + outer loop + vertex -305.568 130.227 298.291 + vertex -309.054 133.775 297.764 + vertex -305.158 133.181 298.292 + endloop + endfacet + facet normal 0.13192 -0.0168072 -0.991118 + outer loop + vertex -309.054 133.775 297.764 + vertex -308.653 136.693 297.768 + vertex -305.158 133.181 298.292 + endloop + endfacet + facet normal 0.0226619 -0.00258665 -0.99974 + outer loop + vertex -292.59 127.16 298.805 + vertex -293.383 121.175 298.803 + vertex -300.599 126.591 298.625 + endloop + endfacet + facet normal 0.0678877 -0.0088598 -0.997654 + outer loop + vertex -305.568 130.227 298.291 + vertex -305.158 133.181 298.292 + vertex -301.178 129.923 298.592 + endloop + endfacet + facet normal 0.130646 -0.0180969 -0.991264 + outer loop + vertex -305.158 133.181 298.292 + vertex -308.653 136.693 297.768 + vertex -304.747 136.095 298.294 + endloop + endfacet + facet normal 0.130685 -0.0178392 -0.991263 + outer loop + vertex -308.653 136.693 297.768 + vertex -308.248 139.593 297.769 + vertex -304.747 136.095 298.294 + endloop + endfacet + facet normal 0.13214 -0.0163583 -0.991096 + outer loop + vertex -304.747 136.095 298.294 + vertex -308.248 139.593 297.769 + vertex -304.352 139.005 298.298 + endloop + endfacet + facet normal 0.131712 -0.0191955 -0.991102 + outer loop + vertex -308.248 139.593 297.769 + vertex -307.833 142.522 297.767 + vertex -304.352 139.005 298.298 + endloop + endfacet + facet normal 0.0227877 -0.00259119 -0.999737 + outer loop + vertex -291.781 133.077 298.808 + vertex -292.59 127.16 298.805 + vertex -299.782 132.529 298.628 + endloop + endfacet + facet normal 0.0682748 -0.00769849 -0.997637 + outer loop + vertex -304.747 136.095 298.294 + vertex -304.352 139.005 298.298 + vertex -300.363 135.79 298.596 + endloop + endfacet + facet normal 0.132107 -0.0187982 -0.991057 + outer loop + vertex -304.352 139.005 298.298 + vertex -307.833 142.522 297.767 + vertex -303.937 141.951 298.298 + endloop + endfacet + facet normal 0.132385 -0.0168972 -0.991054 + outer loop + vertex -307.833 142.522 297.767 + vertex -307.448 145.501 297.768 + vertex -303.937 141.951 298.298 + endloop + endfacet + facet normal 0.131473 -0.0178148 -0.99116 + outer loop + vertex -303.937 141.951 298.298 + vertex -307.448 145.501 297.768 + vertex -303.528 144.936 298.298 + endloop + endfacet + facet normal 0.130981 -0.0212239 -0.991158 + outer loop + vertex -307.448 145.501 297.768 + vertex -307.015 148.504 297.761 + vertex -303.528 144.936 298.298 + endloop + endfacet + facet normal 0.0225341 -0.00233582 -0.999743 + outer loop + vertex -290.98 138.979 298.813 + vertex -291.781 133.077 298.808 + vertex -298.974 138.385 298.634 + endloop + endfacet + facet normal 0.0690651 -0.00925117 -0.997569 + outer loop + vertex -303.937 141.951 298.298 + vertex -303.528 144.936 298.298 + vertex -299.558 141.675 298.603 + endloop + endfacet + facet normal 0.131522 -0.0206862 -0.991097 + outer loop + vertex -303.528 144.936 298.298 + vertex -307.015 148.504 297.761 + vertex -303.084 147.93 298.295 + endloop + endfacet + facet normal 0.131513 -0.0207467 -0.991097 + outer loop + vertex -307.015 148.504 297.761 + vertex -306.567 151.48 297.758 + vertex -303.084 147.93 298.295 + endloop + endfacet + facet normal 0.129937 -0.0223197 -0.991271 + outer loop + vertex -303.084 147.93 298.295 + vertex -306.567 151.48 297.758 + vertex -302.604 150.882 298.291 + endloop + endfacet + facet normal 0.129777 -0.0233712 -0.991268 + outer loop + vertex -306.567 151.48 297.758 + vertex -306.047 154.385 297.758 + vertex -302.604 150.882 298.291 + endloop + endfacet + facet normal 0.0226808 -0.00285345 -0.999739 + outer loop + vertex -290.181 144.891 298.814 + vertex -290.98 138.979 298.813 + vertex -298.137 144.321 298.635 + endloop + endfacet + facet normal 0.0678107 -0.0122242 -0.997623 + outer loop + vertex -303.084 147.93 298.295 + vertex -302.604 150.882 298.291 + vertex -298.67 147.631 298.598 + endloop + endfacet + facet normal 0.131544 -0.0216065 -0.991075 + outer loop + vertex -302.604 150.882 298.291 + vertex -306.047 154.385 297.758 + vertex -302.128 153.785 298.291 + endloop + endfacet + facet normal 0.131607 -0.0211916 -0.991075 + outer loop + vertex -306.047 154.385 297.758 + vertex -305.549 157.263 297.762 + vertex -302.128 153.785 298.291 + endloop + endfacet + facet normal 0.139916 -0.0128702 -0.99008 + outer loop + vertex -302.128 153.785 298.291 + vertex -305.549 157.263 297.762 + vertex -301.81 156.706 298.298 + endloop + endfacet + facet normal 0.140752 -0.00720225 -0.990019 + outer loop + vertex -305.549 157.263 297.762 + vertex -305.247 160.233 297.784 + vertex -301.81 156.706 298.298 + endloop + endfacet + facet normal 0.0246133 -0.000750949 -0.999697 + outer loop + vertex -289.557 150.804 298.825 + vertex -290.181 144.891 298.814 + vertex -297.286 150.227 298.635 + endloop + endfacet + facet normal 0.0739713 -0.00567576 -0.997244 + outer loop + vertex -302.128 153.785 298.291 + vertex -301.81 156.706 298.298 + vertex -297.909 153.488 298.606 + endloop + endfacet + facet normal 0.151138 0.00314055 -0.988508 + outer loop + vertex -301.81 156.706 298.298 + vertex -305.247 160.233 297.784 + vertex -301.732 159.716 298.319 + endloop + endfacet + facet normal 0.155843 0.036632 -0.987102 + outer loop + vertex -305.247 160.233 297.784 + vertex -305.135 163.337 297.917 + vertex -301.732 159.716 298.319 + endloop + endfacet + facet normal 0.149526 0.0305651 -0.988285 + outer loop + vertex -301.732 159.716 298.319 + vertex -305.135 163.337 297.917 + vertex -301.612 162.798 298.433 + endloop + endfacet + facet normal 0.162368 0.123264 -0.979001 + outer loop + vertex -305.135 163.337 297.917 + vertex -304.706 166.479 298.383 + vertex -301.612 162.798 298.433 + endloop + endfacet + facet normal 0.14035 0.104683 -0.984552 + outer loop + vertex -301.612 162.798 298.433 + vertex -304.706 166.479 298.383 + vertex -301.3 165.81 298.798 + endloop + endfacet + facet normal 0.0412701 0.0398816 -0.998352 + outer loop + vertex -297.638 159.511 298.645 + vertex -296.264 162.261 298.812 + vertex -289.009 156.91 298.898 + endloop + endfacet + facet normal 0.0310487 0.00915286 -0.999476 + outer loop + vertex -289.009 156.91 298.898 + vertex -289.557 150.804 298.825 + vertex -296.762 156.141 298.65 + endloop + endfacet + facet normal 0.0094345 0.000851741 -0.999955 + outer loop + vertex -290.181 144.891 298.814 + vertex -289.557 150.804 298.825 + vertex -275.894 143.952 298.948 + endloop + endfacet + facet normal 0.00936718 -0.00017323 -0.999956 + outer loop + vertex -276.511 138.06 298.943 + vertex -290.181 144.891 298.814 + vertex -275.894 143.952 298.948 + endloop + endfacet + facet normal 0.00422678 -0.000358763 -0.999991 + outer loop + vertex -277.286 132.156 298.942 + vertex -276.511 138.06 298.943 + vertex -260.461 130.906 299.014 + endloop + endfacet + facet normal 0.00421951 -0.000456701 -0.999991 + outer loop + vertex -261.213 124.969 299.013 + vertex -277.286 132.156 298.942 + vertex -260.461 130.906 299.014 + endloop + endfacet + facet normal 0.00217656 -6.4936e-05 -0.999998 + outer loop + vertex -261.937 119.004 299.012 + vertex -261.213 124.969 299.013 + vertex -242.804 117.413 299.054 + endloop + endfacet + facet normal 0.00218636 5.28879e-05 -0.999998 + outer loop + vertex -243.442 111.452 299.052 + vertex -261.937 119.004 299.012 + vertex -242.804 117.413 299.054 + endloop + endfacet + facet normal 0.000672999 0.000383958 -1 + outer loop + vertex -244.057 105.536 299.049 + vertex -243.442 111.452 299.052 + vertex -223.125 103.739 299.063 + endloop + endfacet + facet normal 0.000640277 2.74914e-06 -1 + outer loop + vertex -223.672 97.8724 299.062 + vertex -244.057 105.536 299.049 + vertex -223.125 103.739 299.063 + endloop + endfacet + facet normal -0.0010405 -0.00208975 -0.999997 + outer loop + vertex -224.229 92.0314 299.075 + vertex -223.672 97.8724 299.062 + vertex -202.359 90.1961 299.056 + endloop + endfacet + facet normal -0.00158005 -0.00851956 -0.999962 + outer loop + vertex -202.851 84.3305 299.107 + vertex -224.229 92.0314 299.075 + vertex -202.359 90.1961 299.056 + endloop + endfacet + facet normal -0.00417739 -0.0210843 -0.999769 + outer loop + vertex -203.36 78.4115 299.234 + vertex -202.851 84.3305 299.107 + vertex -181.416 76.6383 299.18 + endloop + endfacet + facet normal -0.00717991 -0.0421963 -0.999084 + outer loop + vertex -181.889 70.6694 299.435 + vertex -181.416 76.6383 299.18 + vertex -160.477 68.9922 299.352 + endloop + endfacet + facet normal -0.00959812 -0.0731575 -0.997274 + outer loop + vertex -160.923 63.0272 299.794 + vertex -181.889 70.6694 299.435 + vertex -160.477 68.9922 299.352 + endloop + endfacet + facet normal -0.00577157 -0.0215672 -0.999751 + outer loop + vertex -160.07 74.9638 299.095 + vertex -180.976 82.5602 299.052 + vertex -159.681 80.8861 298.965 + endloop + endfacet + facet normal -0.00473995 -0.00843399 -0.999953 + outer loop + vertex -180.976 82.5602 299.052 + vertex -180.548 88.4272 299.001 + vertex -159.681 80.8861 298.965 + endloop + endfacet + facet normal -0.00271742 -0.00207096 -0.999994 + outer loop + vertex -180.548 88.4272 299.001 + vertex -201.881 96.0407 299.043 + vertex -180.141 94.2739 298.987 + endloop + endfacet + facet normal -0.0025274 0.000267492 -0.999997 + outer loop + vertex -201.881 96.0407 299.043 + vertex -201.405 101.91 299.043 + vertex -180.141 94.2739 298.987 + endloop + endfacet + facet normal -0.00089206 0.000417774 -1 + outer loop + vertex -201.405 101.91 299.043 + vertex -222.579 109.659 299.065 + vertex -200.923 107.833 299.045 + endloop + endfacet + facet normal -0.000903026 0.000287673 -1 + outer loop + vertex -222.579 109.659 299.065 + vertex -221.997 115.623 299.067 + vertex -200.923 107.833 299.045 + endloop + endfacet + facet normal 0.00059395 -4.0086e-05 -1 + outer loop + vertex -221.997 115.623 299.067 + vertex -242.128 123.382 299.054 + vertex -221.388 121.597 299.067 + endloop + endfacet + facet normal 0.000589769 -8.8662e-05 -1 + outer loop + vertex -242.128 123.382 299.054 + vertex -241.442 129.322 299.054 + vertex -221.388 121.597 299.067 + endloop + endfacet + facet normal 0.00208528 -0.000204333 -0.999998 + outer loop + vertex -241.442 129.322 299.054 + vertex -259.792 136.807 299.014 + vertex -240.835 135.222 299.054 + endloop + endfacet + facet normal 0.00214953 0.000564075 -0.999998 + outer loop + vertex -259.792 136.807 299.014 + vertex -259.293 142.693 299.019 + vertex -240.835 135.222 299.054 + endloop + endfacet + facet normal 0.00463724 0.00358262 -0.999983 + outer loop + vertex -259.293 142.693 299.019 + vertex -275.438 149.902 298.97 + vertex -258.896 148.628 299.042 + endloop + endfacet + facet normal 0.00576342 0.0182133 -0.999818 + outer loop + vertex -275.438 149.902 298.97 + vertex -274.851 156.059 299.085 + vertex -258.896 148.628 299.042 + endloop + endfacet + facet normal 0.0134945 0.0554162 -0.998372 + outer loop + vertex -274.851 156.059 299.085 + vertex -287.692 163.792 299.341 + vertex -275.106 162.391 299.433 + endloop + endfacet + facet normal 0.00342413 0.0179439 -0.999833 + outer loop + vertex -239.972 147.022 299.078 + vertex -258.488 154.66 299.152 + vertex -239.539 153.016 299.187 + endloop + endfacet + facet normal 0.000903695 0.00341736 -0.999994 + outer loop + vertex -240.361 141.106 299.058 + vertex -239.972 147.022 299.078 + vertex -219.732 139.348 299.07 + endloop + endfacet + facet normal 0.000654632 0.00049488 -1 + outer loop + vertex -220.217 133.452 299.067 + vertex -240.361 141.106 299.058 + vertex -219.732 139.348 299.07 + endloop + endfacet + facet normal -0.000928818 0.000150425 -1 + outer loop + vertex -220.779 127.544 299.067 + vertex -220.217 133.452 299.067 + vertex -199.354 125.735 299.047 + endloop + endfacet + facet normal -0.000936502 5.94066e-05 -1 + outer loop + vertex -199.895 119.781 299.047 + vertex -220.779 127.544 299.067 + vertex -199.354 125.735 299.047 + endloop + endfacet + facet normal -0.00254923 0.000290698 -0.999997 + outer loop + vertex -200.421 113.802 299.046 + vertex -199.895 119.781 299.047 + vertex -178.906 112.043 298.991 + endloop + endfacet + facet normal -0.00254696 0.000318483 -0.999997 + outer loop + vertex -179.329 106.071 298.99 + vertex -200.421 113.802 299.046 + vertex -178.906 112.043 298.991 + endloop + endfacet + facet normal -0.00400125 0.000682653 -0.999992 + outer loop + vertex -179.737 100.146 298.988 + vertex -179.329 106.071 298.99 + vertex -158.651 98.4762 298.902 + endloop + endfacet + facet normal -0.00403289 0.000283139 -0.999992 + outer loop + vertex -158.988 92.6031 298.902 + vertex -179.737 100.146 298.988 + vertex -158.651 98.4762 298.902 + endloop + endfacet + facet normal -0.00497318 -0.00192908 -0.999986 + outer loop + vertex -159.328 86.755 298.915 + vertex -158.988 92.6031 298.902 + vertex -138.834 85.1941 298.816 + endloop + endfacet + facet normal -0.00547451 -0.00851314 -0.999949 + outer loop + vertex -139.127 79.3247 298.867 + vertex -159.328 86.755 298.915 + vertex -138.834 85.1941 298.816 + endloop + endfacet + facet normal -0.0059712 -0.0213578 -0.999754 + outer loop + vertex -139.437 73.4001 298.996 + vertex -139.127 79.3247 298.867 + vertex -119.345 71.9741 298.906 + endloop + endfacet + facet normal -0.00545664 -0.0425571 -0.999079 + outer loop + vertex -119.623 65.9988 299.162 + vertex -119.345 71.9741 298.906 + vertex -99.7123 64.7504 299.107 + endloop + endfacet + facet normal -0.00743087 -0.0741287 -0.997221 + outer loop + vertex -99.9626 58.7829 299.552 + vertex -119.623 65.9988 299.162 + vertex -99.7123 64.7504 299.107 + endloop + endfacet + facet normal -0.00426929 -0.0214679 -0.99976 + outer loop + vertex -99.4928 70.7223 298.848 + vertex -119.095 77.8978 298.777 + vertex -99.2973 76.6468 298.719 + endloop + endfacet + facet normal -0.00345823 -0.00862358 -0.999957 + outer loop + vertex -119.095 77.8978 298.777 + vertex -118.862 83.7672 298.726 + vertex -99.2973 76.6468 298.719 + endloop + endfacet + facet normal -0.00467699 -0.00211214 -0.999987 + outer loop + vertex -118.862 83.7672 298.726 + vertex -138.558 91.0439 298.802 + vertex -118.639 89.6156 298.712 + endloop + endfacet + facet normal -0.00450849 0.000238091 -0.99999 + outer loop + vertex -138.558 91.0439 298.802 + vertex -138.275 96.9156 298.803 + vertex -118.639 89.6156 298.712 + endloop + endfacet + facet normal -0.00485609 0.000604247 -0.999988 + outer loop + vertex -138.275 96.9156 298.803 + vertex -158.314 104.404 298.904 + vertex -138.003 102.844 298.805 + endloop + endfacet + facet normal -0.0048729 0.000385343 -0.999988 + outer loop + vertex -158.314 104.404 298.904 + vertex -157.967 110.376 298.905 + vertex -138.003 102.844 298.805 + endloop + endfacet + facet normal -0.00412163 0.000156103 -0.999991 + outer loop + vertex -157.967 110.376 298.905 + vertex -178.461 118.026 298.991 + vertex -157.615 116.363 298.905 + endloop + endfacet + facet normal -0.0041125 0.000270602 -0.999992 + outer loop + vertex -178.461 118.026 298.991 + vertex -178.01 123.987 298.99 + vertex -157.615 116.363 298.905 + endloop + endfacet + facet normal -0.00258053 0.000397957 -0.999997 + outer loop + vertex -178.01 123.987 298.99 + vertex -198.835 131.656 299.047 + vertex -177.556 129.919 298.992 + endloop + endfacet + facet normal -0.0025363 0.000939846 -0.999996 + outer loop + vertex -198.835 131.656 299.047 + vertex -198.353 137.568 299.052 + vertex -177.556 129.919 298.992 + endloop + endfacet + facet normal -0.000598576 0.00337198 -0.999994 + outer loop + vertex -198.353 137.568 299.052 + vertex -219.298 145.272 299.09 + vertex -197.881 143.507 299.071 + endloop + endfacet + facet normal 0.000605084 0.0179824 -0.999838 + outer loop + vertex -219.298 145.272 299.09 + vertex -218.83 151.279 299.198 + vertex -197.881 143.507 299.071 + endloop + endfacet + facet normal 0.00578395 0.0593874 -0.998218 + outer loop + vertex -218.83 151.279 299.198 + vertex -239.421 159.179 299.549 + vertex -218.394 157.456 299.568 + endloop + endfacet + facet normal -0.00136093 0.0176773 -0.999843 + outer loop + vertex -176.645 141.788 299.016 + vertex -197.403 149.532 299.181 + vertex -176.277 147.82 299.122 + endloop + endfacet + facet normal -0.00389593 0.00349748 -0.999986 + outer loop + vertex -177.089 135.84 298.997 + vertex -176.645 141.788 299.016 + vertex -156.459 134.189 298.911 + endloop + endfacet + facet normal -0.00409467 0.00101469 -0.999991 + outer loop + vertex -156.861 128.263 298.906 + vertex -177.089 135.84 298.997 + vertex -156.459 134.189 298.911 + endloop + endfacet + facet normal -0.00490378 0.000620911 -0.999988 + outer loop + vertex -157.246 122.328 298.905 + vertex -156.861 128.263 298.906 + vertex -137.161 120.772 298.805 + endloop + endfacet + facet normal -0.00492989 0.000283893 -0.999988 + outer loop + vertex -137.449 114.805 298.805 + vertex -157.246 122.328 298.905 + vertex -137.161 120.772 298.805 + endloop + endfacet + facet normal -0.00456186 0.000147537 -0.99999 + outer loop + vertex -137.73 108.819 298.805 + vertex -137.449 114.805 298.805 + vertex -117.988 107.393 298.715 + endloop + endfacet + facet normal -0.00455591 0.000229947 -0.99999 + outer loop + vertex -118.202 101.418 298.715 + vertex -137.73 108.819 298.805 + vertex -117.988 107.393 298.715 + endloop + endfacet + facet normal -0.00293217 0.000498526 -0.999996 + outer loop + vertex -118.42 95.4891 298.712 + vertex -118.202 101.418 298.715 + vertex -98.774 94.2392 298.654 + endloop + endfacet + facet normal -0.00295942 7.01839e-05 -0.999996 + outer loop + vertex -98.9442 88.3654 298.654 + vertex -118.42 95.4891 298.712 + vertex -98.774 94.2392 298.654 + endloop + endfacet + facet normal -0.000926906 -0.00222619 -0.999997 + outer loop + vertex -99.1171 82.5154 298.667 + vertex -98.9442 88.3654 298.654 + vertex -79.3555 81.4705 298.651 + endloop + endfacet + facet normal -0.00126996 -0.00871522 -0.999961 + outer loop + vertex -79.4911 75.6008 298.703 + vertex -99.1171 82.5154 298.667 + vertex -79.3555 81.4705 298.651 + endloop + endfacet + facet normal 0.00011229 -0.0218574 -0.999761 + outer loop + vertex -79.6376 69.6787 298.832 + vertex -79.4911 75.6008 298.703 + vertex -59.6931 68.8585 298.852 + endloop + endfacet + facet normal 0.000847234 -0.0431442 -0.999068 + outer loop + vertex -59.8106 62.8883 299.11 + vertex -59.6931 68.8585 298.852 + vertex -39.7766 62.3058 299.152 + endloop + endfacet + facet normal -6.90621e-05 -0.0745241 -0.997219 + outer loop + vertex -39.8636 56.3442 299.598 + vertex -59.8106 62.8883 299.11 + vertex -39.7766 62.3058 299.152 + endloop + endfacet + facet normal 0.00148563 -0.021678 -0.999764 + outer loop + vertex -39.702 68.2739 298.894 + vertex -59.5896 74.7799 298.724 + vertex -39.6369 74.1952 298.766 + endloop + endfacet + facet normal 0.00186521 -0.00873948 -0.99996 + outer loop + vertex -59.5896 74.7799 298.724 + vertex -59.494 80.649 298.673 + vertex -39.6369 74.1952 298.766 + endloop + endfacet + facet normal 0.000986051 -0.00242799 -0.999997 + outer loop + vertex -59.494 80.649 298.673 + vertex -79.2283 87.3152 298.637 + vertex -59.4045 86.4923 298.658 + endloop + endfacet + facet normal 0.00108953 6.46347e-05 -0.999999 + outer loop + vertex -79.2283 87.3152 298.637 + vertex -79.1007 93.1905 298.637 + vertex -59.4045 86.4923 298.658 + endloop + endfacet + facet normal -0.000837716 0.000352301 -1 + outer loop + vertex -79.1007 93.1905 298.637 + vertex -98.6066 100.169 298.656 + vertex -78.9756 99.1185 298.639 + endloop + endfacet + facet normal -0.000849847 0.000125513 -1 + outer loop + vertex -98.6066 100.169 298.656 + vertex -98.4423 106.144 298.657 + vertex -78.9756 99.1185 298.639 + endloop + endfacet + facet normal -0.00297952 4.44527e-05 -0.999996 + outer loop + vertex -98.4423 106.144 298.657 + vertex -117.774 113.381 298.715 + vertex -98.2813 112.132 298.657 + endloop + endfacet + facet normal -0.00296914 0.000206541 -0.999996 + outer loop + vertex -117.774 113.381 298.715 + vertex -117.554 119.35 298.715 + vertex -98.2813 112.132 298.657 + endloop + endfacet + facet normal -0.00457886 0.000445952 -0.999989 + outer loop + vertex -117.554 119.35 298.715 + vertex -136.852 126.709 298.807 + vertex -117.316 125.289 298.717 + endloop + endfacet + facet normal -0.00455028 0.000838971 -0.999989 + outer loop + vertex -136.852 126.709 298.807 + vertex -136.518 132.634 298.81 + vertex -117.316 125.289 298.717 + endloop + endfacet + facet normal -0.00490463 0.00292878 -0.999984 + outer loop + vertex -136.518 132.634 298.81 + vertex -156.062 140.136 298.928 + vertex -136.19 138.58 298.826 + endloop + endfacet + facet normal -0.00395814 0.0172328 -0.999844 + outer loop + vertex -136.19 138.58 298.826 + vertex -155.758 146.167 299.034 + vertex -135.91 144.605 298.929 + endloop + endfacet + facet normal -0.000947851 0.0574227 -0.99835 + outer loop + vertex -135.91 144.605 298.929 + vertex -155.09 152.307 299.39 + vertex -135.914 150.782 299.284 + endloop + endfacet + facet normal -0.00214274 0.0172174 -0.999849 + outer loop + vertex -97.5636 135.912 298.673 + vertex -116.644 143.192 298.839 + vertex -97.3771 141.938 298.776 + endloop + endfacet + facet normal -0.00303016 0.00239392 -0.999993 + outer loop + vertex -97.7577 129.968 298.659 + vertex -116.8 137.161 298.734 + vertex -97.5636 135.912 298.673 + endloop + endfacet + facet normal -0.00306483 0.000386133 -0.999995 + outer loop + vertex -97.947 124.04 298.658 + vertex -117.057 131.213 298.719 + vertex -97.7577 129.968 298.659 + endloop + endfacet + facet normal -0.000819853 0.000121433 -1 + outer loop + vertex -98.1193 118.101 298.657 + vertex -97.947 124.04 298.658 + vertex -78.6201 117.057 298.641 + endloop + endfacet + facet normal -0.000818387 0.000148809 -1 + outer loop + vertex -78.7366 111.084 298.64 + vertex -98.1193 118.101 298.657 + vertex -78.6201 117.057 298.641 + endloop + endfacet + facet normal 0.00107994 -5.15098e-05 -0.999999 + outer loop + vertex -78.8527 105.096 298.64 + vertex -78.7366 111.084 298.64 + vertex -59.1394 104.271 298.662 + endloop + endfacet + facet normal 0.00108572 8.66093e-05 -0.999999 + outer loop + vertex -59.225 98.2968 298.661 + vertex -78.8527 105.096 298.64 + vertex -59.1394 104.271 298.662 + endloop + endfacet + facet normal 0.00211442 0.000333516 -0.999998 + outer loop + vertex -59.3145 92.3676 298.659 + vertex -59.225 98.2968 298.661 + vertex -39.4626 91.7781 298.701 + endloop + endfacet + facet normal 0.00210437 -4.81253e-06 -0.999998 + outer loop + vertex -39.5196 85.9062 298.701 + vertex -59.3145 92.3676 298.659 + vertex -39.4626 91.7781 298.701 + endloop + endfacet + facet normal 0.00192066 -0.00223128 -0.999996 + outer loop + vertex -39.577 80.0578 298.713 + vertex -39.5196 85.9062 298.701 + vertex -19.6916 79.7092 298.752 + endloop + endfacet + facet normal 0.00180563 -0.0087901 -0.99996 + outer loop + vertex -19.7199 73.8432 298.804 + vertex -39.577 80.0578 298.713 + vertex -19.6916 79.7092 298.752 + endloop + endfacet + facet normal 0.000590466 -0.0217606 -0.999763 + outer loop + vertex -19.7506 67.9242 298.933 + vertex -19.7199 73.8432 298.804 + vertex 0.126706 67.8059 298.947 + endloop + endfacet + facet normal -0.000526025 -0.0431276 -0.999069 + outer loop + vertex 0.129371 61.8392 299.205 + vertex 0.126706 67.8059 298.947 + vertex 20.0075 61.9538 299.189 + endloop + endfacet + facet normal -0.00034387 -0.0744863 -0.997222 + outer loop + vertex 20.0546 55.993 299.634 + vertex 0.129371 61.8392 299.205 + vertex 20.0075 61.9538 299.189 + endloop + endfacet + facet normal -0.000634135 -0.0217242 -0.999764 + outer loop + vertex 19.9683 67.9225 298.932 + vertex 0.125038 73.7249 298.819 + vertex 19.9347 73.8418 298.804 + endloop + endfacet + facet normal -0.000710945 -0.00873938 -0.999962 + outer loop + vertex 0.125038 73.7249 298.819 + vertex 0.124188 79.5912 298.768 + vertex 19.9347 73.8418 298.804 + endloop + endfacet + facet normal 0.000757822 -0.00230253 -0.999997 + outer loop + vertex 0.124188 79.5912 298.768 + vertex -19.6634 85.5505 298.739 + vertex 0.124001 85.4361 298.754 + endloop + endfacet + facet normal 0.000771325 3.27195e-05 -1 + outer loop + vertex -19.6634 85.5505 298.739 + vertex -19.6356 91.4237 298.739 + vertex 0.124001 85.4361 298.754 + endloop + endfacet + facet normal 0.00195446 0.000340773 -0.999998 + outer loop + vertex -19.6356 91.4237 298.739 + vertex -39.4056 97.7057 298.703 + vertex -19.6073 97.351 298.741 + endloop + endfacet + facet normal 0.0019505 0.000119703 -0.999998 + outer loop + vertex -39.4056 97.7057 298.703 + vertex -39.35 103.682 298.703 + vertex -19.6073 97.351 298.741 + endloop + endfacet + facet normal 0.00211246 -1.29544e-05 -0.999998 + outer loop + vertex -39.35 103.682 298.703 + vertex -59.0579 110.261 298.662 + vertex -39.2988 109.673 298.704 + endloop + endfacet + facet normal 0.00211265 -6.51675e-06 -0.999998 + outer loop + vertex -59.0579 110.261 298.662 + vertex -58.9817 116.233 298.662 + vertex -39.2988 109.673 298.704 + endloop + endfacet + facet normal 0.00105296 -6.96629e-05 -0.999999 + outer loop + vertex -58.9817 116.233 298.662 + vertex -78.5033 122.997 298.641 + vertex -58.9075 122.173 298.662 + endloop + endfacet + facet normal 0.00107378 3.18339e-05 -0.999999 + outer loop + vertex -58.9075 122.173 298.662 + vertex -78.3769 128.922 298.641 + vertex -58.8274 128.098 298.662 + endloop + endfacet + facet normal 0.00122847 0.00257976 -0.999996 + outer loop + vertex -58.8274 128.098 298.662 + vertex -78.2335 134.867 298.655 + vertex -58.7417 134.043 298.677 + endloop + endfacet + facet normal 0.00184091 0.0175511 -0.999844 + outer loop + vertex -58.7417 134.043 298.677 + vertex -78.0958 140.894 298.762 + vertex -58.731 140.073 298.783 + endloop + endfacet + facet normal 0.00397679 0.0575958 -0.998332 + outer loop + vertex -58.731 140.073 298.783 + vertex -78.4809 147.064 299.108 + vertex -58.9254 146.234 299.138 + endloop + endfacet + facet normal 0.00237594 0.0178346 -0.999838 + outer loop + vertex -19.4895 133.1 298.763 + vertex -39.0552 139.482 298.83 + vertex -19.4191 139.125 298.871 + endloop + endfacet + facet normal 0.00215824 0.0030703 -0.999993 + outer loop + vertex -19.5031 127.156 298.745 + vertex -39.1263 133.455 298.722 + vertex -19.4895 133.1 298.763 + endloop + endfacet + facet normal 0.00205344 0.00043821 -0.999998 + outer loop + vertex -19.5167 121.23 298.742 + vertex -39.1664 127.51 298.705 + vertex -19.5031 127.156 298.745 + endloop + endfacet + facet normal 0.00197535 6.08631e-05 -0.999998 + outer loop + vertex -19.5345 115.289 298.742 + vertex -39.2099 121.585 298.703 + vertex -19.5167 121.23 298.742 + endloop + endfacet + facet normal 0.00194352 -1.70441e-05 -0.999998 + outer loop + vertex -19.5554 109.317 298.742 + vertex -39.2533 115.643 298.703 + vertex -19.5345 115.289 298.742 + endloop + endfacet + facet normal 0.000775729 -2.35554e-05 -1 + outer loop + vertex -19.58 103.327 298.742 + vertex -19.5554 109.317 298.742 + vertex 0.125999 103.208 298.757 + endloop + endfacet + facet normal 0.000776737 0.000142986 -1 + outer loop + vertex 0.12549 97.2348 298.756 + vertex -19.58 103.327 298.742 + vertex 0.125999 103.208 298.757 + endloop + endfacet + facet normal -0.000781768 0.000345119 -1 + outer loop + vertex 0.124528 91.3081 298.754 + vertex 0.12549 97.2348 298.756 + vertex 19.8496 91.4227 298.739 + endloop + endfacet + facet normal -0.000779953 3.2819e-05 -1 + outer loop + vertex 19.8764 85.5508 298.739 + vertex 0.124528 91.3081 298.754 + vertex 19.8496 91.4227 298.739 + endloop + endfacet + facet normal -0.0019138 -0.00231724 -0.999995 + outer loop + vertex 19.9046 79.7064 298.752 + vertex 19.8764 85.5508 298.739 + vertex 39.7165 80.0562 298.713 + endloop + endfacet + facet normal -0.00179944 -0.00878973 -0.99996 + outer loop + vertex 39.7771 74.1904 298.765 + vertex 19.9046 79.7064 298.752 + vertex 39.7165 80.0562 298.713 + endloop + endfacet + facet normal -0.00142019 -0.0218134 -0.999761 + outer loop + vertex 39.8446 68.2709 298.894 + vertex 39.7771 74.1904 298.765 + vertex 59.8011 68.857 298.853 + endloop + endfacet + facet normal 0.000746491 -0.0432317 -0.999065 + outer loop + vertex 59.9209 62.8871 299.111 + vertex 59.8011 68.857 298.853 + vertex 79.9995 63.7105 299.091 + endloop + endfacet + facet normal 0.00203639 -0.0746377 -0.997209 + outer loop + vertex 80.1943 57.7454 299.538 + vertex 59.9209 62.8871 299.111 + vertex 79.9995 63.7105 299.091 + endloop + endfacet + facet normal -0.000141467 -0.0218047 -0.999762 + outer loop + vertex 79.8324 69.6824 298.832 + vertex 59.6973 74.779 298.724 + vertex 79.6853 75.605 298.703 + endloop + endfacet + facet normal -0.000677564 -0.00883706 -0.999961 + outer loop + vertex 59.6973 74.779 298.724 + vertex 59.6026 80.6464 298.672 + vertex 79.6853 75.605 298.703 + endloop + endfacet + facet normal -0.00201441 -0.0023535 -0.999995 + outer loop + vertex 59.6026 80.6464 298.672 + vertex 39.6597 85.9031 298.7 + vertex 59.5127 86.4936 298.659 + endloop + endfacet + facet normal -0.00208491 1.66355e-05 -0.999998 + outer loop + vertex 39.6597 85.9031 298.7 + vertex 39.6041 91.7768 298.7 + vertex 59.5127 86.4936 298.659 + endloop + endfacet + facet normal -0.00196719 0.000300589 -0.999998 + outer loop + vertex 39.6041 91.7768 298.7 + vertex 19.823 97.3497 298.741 + vertex 39.548 97.7041 298.702 + endloop + endfacet + facet normal -0.00196292 6.27337e-05 -0.999998 + outer loop + vertex 19.823 97.3497 298.741 + vertex 19.7964 103.327 298.741 + vertex 39.548 97.7041 298.702 + endloop + endfacet + facet normal -0.000815241 -6.49325e-05 -1 + outer loop + vertex 19.7964 103.327 298.741 + vertex 0.12517 109.199 298.757 + vertex 19.7685 109.317 298.741 + endloop + endfacet + facet normal -0.000807465 1.65886e-05 -1 + outer loop + vertex 19.7685 109.317 298.741 + vertex 0.122353 115.171 298.757 + vertex 19.74 115.29 298.741 + endloop + endfacet + facet normal -0.00075272 0.000335205 -1 + outer loop + vertex 19.74 115.29 298.741 + vertex 0.116348 121.114 298.758 + vertex 19.7096 121.23 298.743 + endloop + endfacet + facet normal -0.000734538 0.00080495 -0.999999 + outer loop + vertex 19.7096 121.23 298.743 + vertex 0.106732 127.037 298.762 + vertex 19.6799 127.155 298.748 + endloop + endfacet + facet normal -0.000753677 0.00309279 -0.999995 + outer loop + vertex 19.6799 127.155 298.748 + vertex 0.0973219 132.981 298.781 + vertex 19.6579 133.1 298.766 + endloop + endfacet + facet normal -0.000792472 0.0177957 -0.999841 + outer loop + vertex 19.6579 133.1 298.766 + vertex 0.0857732 139.006 298.887 + vertex 19.6613 139.127 298.874 + endloop + endfacet + facet normal -0.00144563 0.0587902 -0.998269 + outer loop + vertex 19.6613 139.127 298.874 + vertex -1.80473e-13 145.161 299.257 + vertex 19.8895 145.283 299.236 + endloop + endfacet + facet normal -0.00268269 0.0175199 -0.999843 + outer loop + vertex 58.8363 134.044 298.683 + vertex 39.1502 139.474 298.831 + vertex 58.7804 140.073 298.789 + endloop + endfacet + facet normal -0.00239837 0.00273911 -0.999993 + outer loop + vertex 58.8943 128.101 298.666 + vertex 39.2308 133.456 298.728 + vertex 58.8363 134.044 298.683 + endloop + endfacet + facet normal -0.00220873 0.000543599 -0.999997 + outer loop + vertex 58.9702 122.177 298.663 + vertex 39.2676 127.511 298.709 + vertex 58.8943 128.101 298.666 + endloop + endfacet + facet normal -0.00212906 0.000312411 -0.999998 + outer loop + vertex 59.0584 116.234 298.661 + vertex 39.3176 121.585 298.705 + vertex 58.9702 122.177 298.663 + endloop + endfacet + facet normal -0.0021151 1.28733e-05 -0.999998 + outer loop + vertex 59.1519 110.263 298.661 + vertex 39.3744 115.641 298.703 + vertex 59.0584 116.234 298.661 + endloop + endfacet + facet normal -0.00210484 -5.2465e-05 -0.999998 + outer loop + vertex 59.2433 104.268 298.661 + vertex 39.4339 109.671 298.702 + vertex 59.1519 110.263 298.661 + endloop + endfacet + facet normal -0.00212325 1.36986e-05 -0.999998 + outer loop + vertex 59.3341 98.2925 298.66 + vertex 39.491 103.679 298.703 + vertex 59.2433 104.268 298.661 + endloop + endfacet + facet normal -0.00105869 0.000272365 -0.999999 + outer loop + vertex 59.4236 92.3657 298.659 + vertex 59.3341 98.2925 298.66 + vertex 79.2959 93.1938 298.638 + endloop + endfacet + facet normal -0.00104553 -4.33714e-05 -0.999999 + outer loop + vertex 79.4228 87.3209 298.638 + vertex 59.4236 92.3657 298.659 + vertex 79.2959 93.1938 298.638 + endloop + endfacet + facet normal 0.00104003 -0.00227867 -0.999997 + outer loop + vertex 79.5509 81.4732 298.652 + vertex 79.4228 87.3209 298.638 + vertex 99.5366 82.5327 298.67 + endloop + endfacet + facet normal 0.00137611 -0.0086194 -0.999962 + outer loop + vertex 99.7166 76.663 298.721 + vertex 79.5509 81.4732 298.652 + vertex 99.5366 82.5327 298.67 + endloop + endfacet + facet normal 0.00450421 -0.0216742 -0.999755 + outer loop + vertex 99.9143 70.7398 298.85 + vertex 99.7166 76.663 298.721 + vertex 120.059 72.0109 298.913 + endloop + endfacet + facet normal 0.00761342 -0.042431 -0.99907 + outer loop + vertex 120.34 66.0362 299.169 + vertex 120.059 72.0109 298.913 + vertex 140.71 67.4866 299.263 + endloop + endfacet + facet normal 0.00979494 -0.0731842 -0.99727 + outer loop + vertex 141.097 61.5189 299.705 + vertex 120.34 66.0362 299.169 + vertex 140.71 67.4866 299.263 + endloop + endfacet + facet normal 0.00608508 -0.0212291 -0.999756 + outer loop + vertex 140.357 73.4578 299.004 + vertex 119.805 77.9346 298.784 + vertex 140.041 79.3819 298.876 + endloop + endfacet + facet normal 0.00520118 -0.00885812 -0.999947 + outer loop + vertex 119.805 77.9346 298.784 + vertex 119.564 83.8015 298.731 + vertex 140.041 79.3819 298.876 + endloop + endfacet + facet normal 0.00321775 -0.00207933 -0.999993 + outer loop + vertex 119.564 83.8015 298.731 + vertex 99.3632 88.3808 298.656 + vertex 119.342 89.6507 298.718 + endloop + endfacet + facet normal 0.00307922 0.000100315 -0.999995 + outer loop + vertex 99.3632 88.3808 298.656 + vertex 99.1917 94.2554 298.656 + vertex 119.342 89.6507 298.718 + endloop + endfacet + facet normal 0.000892829 0.000324576 -1 + outer loop + vertex 99.1917 94.2554 298.656 + vertex 79.1689 99.125 298.64 + vertex 99.019 100.184 298.658 + endloop + endfacet + facet normal 0.000905573 6.76508e-05 -1 + outer loop + vertex 99.019 100.184 298.658 + vertex 79.0384 105.101 298.64 + vertex 98.8421 106.159 298.658 + endloop + endfacet + facet normal 0.000923796 -3.11676e-06 -1 + outer loop + vertex 98.8421 106.159 298.658 + vertex 78.9057 111.091 298.64 + vertex 98.6641 112.151 298.658 + endloop + endfacet + facet normal 0.000927667 7.84961e-05 -1 + outer loop + vertex 98.6641 112.151 298.658 + vertex 78.7734 117.064 298.64 + vertex 98.4877 118.124 298.659 + endloop + endfacet + facet normal 0.000875566 0.000101171 -1 + outer loop + vertex 98.4877 118.124 298.659 + vertex 78.649 123.006 298.642 + vertex 98.3242 124.064 298.659 + endloop + endfacet + facet normal 0.000830391 0.000221082 -1 + outer loop + vertex 98.3242 124.064 298.659 + vertex 78.543 128.93 298.644 + vertex 98.1802 129.988 298.66 + endloop + endfacet + facet normal 0.000674785 0.00251205 -0.999997 + outer loop + vertex 98.1802 129.988 298.66 + vertex 78.4563 134.874 298.659 + vertex 98.0345 135.932 298.675 + endloop + endfacet + facet normal -0.000151968 0.017243 -0.999851 + outer loop + vertex 98.0345 135.932 298.675 + vertex 78.397 140.903 298.764 + vertex 97.8156 141.957 298.779 + endloop + endfacet + facet normal -0.0023396 0.0555466 -0.998453 + outer loop + vertex 97.8156 141.957 298.779 + vertex 77.9262 147.037 299.108 + vertex 97.6157 148.106 299.121 + endloop + endfacet + facet normal 0.00341558 0.0174897 -0.999841 + outer loop + vertex 137.183 138.634 298.83 + vertex 117.323 143.228 298.843 + vertex 136.884 144.666 298.935 + endloop + endfacet + facet normal 0.00460031 0.00309626 -0.999985 + outer loop + vertex 137.504 132.687 298.813 + vertex 117.574 137.195 298.736 + vertex 137.183 138.634 298.83 + endloop + endfacet + facet normal 0.00470228 0.000413614 -0.999989 + outer loop + vertex 137.779 126.765 298.812 + vertex 117.804 131.251 298.72 + vertex 137.504 132.687 298.813 + endloop + endfacet + facet normal 0.00466382 0.000165538 -0.999989 + outer loop + vertex 138.042 120.829 298.813 + vertex 118.003 125.329 298.72 + vertex 137.779 126.765 298.812 + endloop + endfacet + facet normal 0.00465606 0.000214688 -0.999989 + outer loop + vertex 138.317 114.86 298.813 + vertex 118.209 119.39 298.72 + vertex 138.042 120.829 298.813 + endloop + endfacet + facet normal 0.00465936 0.000211963 -0.999989 + outer loop + vertex 138.602 108.871 298.813 + vertex 118.432 113.418 298.72 + vertex 138.317 114.86 298.813 + endloop + endfacet + facet normal 0.00462735 0.000289424 -0.999989 + outer loop + vertex 138.89 102.897 298.812 + vertex 118.664 107.429 298.72 + vertex 138.602 108.871 298.813 + endloop + endfacet + facet normal 0.00460501 0.000471898 -0.999989 + outer loop + vertex 139.173 96.9695 298.811 + vertex 118.892 101.453 298.719 + vertex 138.89 102.897 298.812 + endloop + endfacet + facet normal 0.00461282 0.000182304 -0.999989 + outer loop + vertex 139.458 91.0973 298.811 + vertex 119.118 95.5255 298.718 + vertex 139.173 96.9695 298.811 + endloop + endfacet + facet normal 0.00503093 -0.00213895 -0.999985 + outer loop + vertex 139.744 85.2504 298.825 + vertex 139.458 91.0973 298.811 + vertex 160.262 86.8399 298.925 + endloop + endfacet + facet normal 0.00551247 -0.00835664 -0.99995 + outer loop + vertex 160.623 80.9727 298.976 + vertex 139.744 85.2504 298.825 + vertex 160.262 86.8399 298.925 + endloop + endfacet + facet normal 0.00538247 -0.0211541 -0.999762 + outer loop + vertex 161.007 75.0503 299.103 + vertex 160.623 80.9727 298.976 + vertex 182.212 76.7505 299.181 + endloop + endfacet + facet normal 0.00528538 -0.0424791 -0.999083 + outer loop + vertex 182.7 70.7828 299.438 + vertex 182.212 76.7505 299.181 + vertex 204.523 72.5421 299.478 + endloop + endfacet + facet normal 0.00774284 -0.0730046 -0.997302 + outer loop + vertex 205.088 66.5895 299.918 + vertex 182.7 70.7828 299.438 + vertex 204.523 72.5421 299.478 + endloop + endfacet + facet normal 0.00368782 -0.0208524 -0.999776 + outer loop + vertex 203.99 78.5079 299.224 + vertex 181.767 82.6719 299.055 + vertex 203.48 84.4269 299.099 + endloop + endfacet + facet normal 0.00268039 -0.00838385 -0.999961 + outer loop + vertex 181.767 82.6719 299.055 + vertex 181.341 88.5382 299.005 + vertex 203.48 84.4269 299.099 + endloop + endfacet + facet normal 0.00399936 -0.00189668 -0.99999 + outer loop + vertex 181.341 88.5382 299.005 + vertex 159.913 92.686 298.911 + vertex 180.916 94.3819 298.992 + endloop + endfacet + facet normal 0.00386027 0.000340022 -0.999992 + outer loop + vertex 180.916 94.3819 298.992 + vertex 159.567 98.5578 298.911 + vertex 180.501 100.251 298.992 + endloop + endfacet + facet normal 0.00387299 0.00064499 -0.999992 + outer loop + vertex 180.501 100.251 298.992 + vertex 159.216 104.482 298.913 + vertex 180.083 106.173 298.995 + endloop + endfacet + facet normal 0.00390278 0.000341197 -0.999992 + outer loop + vertex 180.083 106.173 298.995 + vertex 158.862 110.453 298.913 + vertex 179.67 112.142 298.995 + endloop + endfacet + facet normal 0.0039486 0.000333152 -0.999992 + outer loop + vertex 179.67 112.142 298.995 + vertex 158.518 116.439 298.913 + vertex 179.251 118.123 298.995 + endloop + endfacet + facet normal 0.00396184 0.0002811 -0.999992 + outer loop + vertex 179.251 118.123 298.995 + vertex 158.18 122.405 298.913 + vertex 178.851 124.086 298.995 + endloop + endfacet + facet normal 0.00400957 0.000490654 -0.999992 + outer loop + vertex 178.851 124.086 298.995 + vertex 157.849 128.339 298.913 + vertex 178.429 130.017 298.997 + endloop + endfacet + facet normal 0.00403487 0.000848183 -0.999992 + outer loop + vertex 178.429 130.017 298.997 + vertex 157.479 134.26 298.916 + vertex 177.971 135.939 299 + endloop + endfacet + facet normal 0.00386599 0.00319483 -0.999987 + outer loop + vertex 177.971 135.939 299 + vertex 157.069 140.207 298.933 + vertex 177.494 141.884 299.017 + endloop + endfacet + facet normal 0.00267324 0.0177507 -0.999839 + outer loop + vertex 177.494 141.884 299.017 + vertex 156.767 146.245 299.039 + vertex 177.104 147.906 299.123 + endloop + endfacet + facet normal -0.000210268 0.0598392 -0.998208 + outer loop + vertex 177.104 147.906 299.123 + vertex 156.849 152.45 299.4 + vertex 176.255 154.042 299.491 + endloop + endfacet + facet normal -0.000268371 0.0189088 -0.999821 + outer loop + vertex 219.701 145.291 299.088 + vertex 198.061 149.607 299.176 + vertex 219.211 151.293 299.202 + endloop + endfacet + facet normal 0.00058824 0.00380324 -0.999993 + outer loop + vertex 220.264 139.371 299.066 + vertex 198.5 143.603 299.069 + vertex 219.701 145.291 299.088 + endloop + endfacet + facet normal 0.000726563 0.00089742 -0.999999 + outer loop + vertex 220.88 133.465 299.061 + vertex 199.015 137.666 299.049 + vertex 220.264 139.371 299.066 + endloop + endfacet + facet normal 0.000709491 0.000381111 -1 + outer loop + vertex 221.481 127.542 299.059 + vertex 199.563 131.75 299.046 + vertex 220.88 133.465 299.061 + endloop + endfacet + facet normal 0.000736519 0.000239371 -1 + outer loop + vertex 222.048 121.589 299.058 + vertex 200.08 125.821 299.043 + vertex 221.481 127.542 299.059 + endloop + endfacet + facet normal 0.000706754 0.000218144 -1 + outer loop + vertex 222.596 115.616 299.058 + vertex 200.559 119.863 299.043 + vertex 222.048 121.589 299.058 + endloop + endfacet + facet normal 0.000654224 0.000367902 -1 + outer loop + vertex 223.149 109.656 299.056 + vertex 201.039 113.885 299.043 + vertex 222.596 115.616 299.058 + endloop + endfacet + facet normal 0.000610063 0.000681461 -1 + outer loop + vertex 223.704 103.74 299.052 + vertex 201.526 107.921 299.041 + vertex 223.149 109.656 299.056 + endloop + endfacet + facet normal 0.000584944 0.000424603 -1 + outer loop + vertex 224.257 97.8751 299.05 + vertex 202.01 102.002 299.039 + vertex 223.704 103.74 299.052 + endloop + endfacet + facet normal 0.000724922 -0.00185824 -0.999998 + outer loop + vertex 224.815 92.0326 299.061 + vertex 202.497 96.1358 299.037 + vertex 224.257 97.8751 299.05 + endloop + endfacet + facet normal 0.00121404 -0.0083032 -0.999965 + outer loop + vertex 225.367 86.1667 299.111 + vertex 202.984 90.2923 299.049 + vertex 224.815 92.0326 299.061 + endloop + endfacet + facet normal 0.0017138 -0.0211507 -0.999775 + outer loop + vertex 225.944 80.2486 299.237 + vertex 225.367 86.1667 299.111 + vertex 247.193 81.9126 299.238 + endloop + endfacet + facet normal 0.00336657 -0.0428012 -0.999078 + outer loop + vertex 247.851 75.96 299.495 + vertex 247.193 81.9126 299.238 + vertex 267.4 77.5718 299.492 + endloop + endfacet + facet normal 0.00603844 -0.0752053 -0.99715 + outer loop + vertex 268.143 71.6663 299.942 + vertex 247.851 75.96 299.495 + vertex 267.4 77.5718 299.492 + endloop + endfacet + facet normal 0.00142885 -0.0218829 -0.99976 + outer loop + vertex 266.675 83.5121 299.232 + vertex 246.582 87.8302 299.108 + vertex 265.953 89.4226 299.101 + endloop + endfacet + facet normal 0.000202829 -0.00902741 -0.999959 + outer loop + vertex 265.953 89.4226 299.101 + vertex 245.944 93.6955 299.059 + vertex 265.275 95.2893 299.048 + endloop + endfacet + facet normal -0.000451367 -0.00246871 -0.999997 + outer loop + vertex 265.275 95.2893 299.048 + vertex 245.341 99.5397 299.047 + vertex 264.597 101.137 299.034 + endloop + endfacet + facet normal -0.000724867 5.72124e-05 -1 + outer loop + vertex 264.597 101.137 299.034 + vertex 244.725 105.405 299.049 + vertex 263.923 107.006 299.035 + endloop + endfacet + facet normal -0.000789435 0.000554457 -1 + outer loop + vertex 263.923 107.006 299.035 + vertex 244.106 111.319 299.053 + vertex 263.246 112.921 299.039 + endloop + endfacet + facet normal -0.000762478 0.000394376 -1 + outer loop + vertex 263.246 112.921 299.039 + vertex 243.485 117.276 299.055 + vertex 262.563 118.875 299.042 + endloop + endfacet + facet normal -0.000712928 0.000219316 -1 + outer loop + vertex 262.563 118.875 299.042 + vertex 242.847 123.244 299.057 + vertex 261.872 124.837 299.043 + endloop + endfacet + facet normal -0.000686764 0.000239929 -1 + outer loop + vertex 261.872 124.837 299.043 + vertex 242.196 129.19 299.058 + vertex 261.146 130.773 299.045 + endloop + endfacet + facet normal -0.000647919 0.000543442 -1 + outer loop + vertex 261.146 130.773 299.045 + vertex 241.507 135.1 299.06 + vertex 260.393 136.671 299.049 + endloop + endfacet + facet normal -0.000618063 0.00136509 -0.999999 + outer loop + vertex 260.393 136.671 299.049 + vertex 240.855 140.992 299.067 + vertex 259.716 142.556 299.057 + endloop + endfacet + facet normal -0.000884006 0.00380446 -0.999992 + outer loop + vertex 259.716 142.556 299.057 + vertex 240.27 146.91 299.091 + vertex 259.136 148.502 299.081 + endloop + endfacet + facet normal -0.00264251 0.0159263 -0.99987 + outer loop + vertex 259.136 148.502 299.081 + vertex 239.798 152.946 299.202 + vertex 258.774 154.59 299.178 + endloop + endfacet + facet normal -0.00696588 0.051449 -0.998651 + outer loop + vertex 258.774 154.59 299.178 + vertex 240.263 159.25 299.548 + vertex 258.804 160.848 299.501 + endloop + endfacet + facet normal -0.0167346 0.0142058 -0.999759 + outer loop + vertex 288.822 152.031 298.81 + vertex 275.071 156.276 299.1 + vertex 288.394 158.041 298.902 + endloop + endfacet + facet normal -0.0152416 0.000221118 -0.999884 + outer loop + vertex 289.293 146.042 298.801 + vertex 275.441 150.177 299.013 + vertex 288.822 152.031 298.81 + endloop + endfacet + facet normal -0.0146716 -0.00153276 -0.999891 + outer loop + vertex 289.972 140.122 298.8 + vertex 275.966 144.193 298.999 + vertex 289.293 146.042 298.801 + endloop + endfacet + facet normal -0.0143278 -0.000882006 -0.999897 + outer loop + vertex 290.765 134.229 298.794 + vertex 276.653 138.292 298.993 + vertex 289.972 140.122 298.8 + endloop + endfacet + facet normal -0.0143478 -0.00160532 -0.999896 + outer loop + vertex 291.612 128.294 298.791 + vertex 277.448 132.399 298.988 + vertex 290.765 134.229 298.794 + endloop + endfacet + facet normal -0.0141125 -0.00157755 -0.999899 + outer loop + vertex 292.422 122.325 298.789 + vertex 278.209 126.471 298.983 + vertex 291.612 128.294 298.791 + endloop + endfacet + facet normal -0.0140996 -0.00162553 -0.999899 + outer loop + vertex 293.206 116.367 298.788 + vertex 278.977 120.511 298.982 + vertex 292.422 122.325 298.789 + endloop + endfacet + facet normal -0.0139898 -0.00135974 -0.999901 + outer loop + vertex 293.978 110.449 298.785 + vertex 279.715 114.559 298.979 + vertex 293.206 116.367 298.788 + endloop + endfacet + facet normal -0.0138527 -0.00169403 -0.999903 + outer loop + vertex 294.729 104.574 298.785 + vertex 280.442 108.643 298.976 + vertex 293.978 110.449 298.785 + endloop + endfacet + facet normal -0.0135431 -0.00500505 -0.999896 + outer loop + vertex 295.517 98.7182 298.803 + vertex 281.175 102.768 298.977 + vertex 294.729 104.574 298.785 + endloop + endfacet + facet normal -0.0125379 -0.0105858 -0.999865 + outer loop + vertex 296.314 92.8589 298.855 + vertex 281.893 96.9159 298.993 + vertex 295.517 98.7182 298.803 + endloop + endfacet + facet normal -0.0110511 -0.0229896 -0.999675 + outer loop + vertex 297.17 86.9752 298.981 + vertex 282.637 91.0508 299.048 + vertex 296.314 92.8589 298.855 + endloop + endfacet + facet normal -0.00855635 -0.0443594 -0.998979 + outer loop + vertex 298.082 81.0867 299.235 + vertex 283.408 85.1522 299.18 + vertex 297.17 86.9752 298.981 + endloop + endfacet + facet normal -0.00462496 -0.0759989 -0.997097 + outer loop + vertex 299.104 75.2505 299.675 + vertex 284.257 79.233 299.44 + vertex 298.082 81.0867 299.235 + endloop + endfacet + facet normal -0.00487189 -0.0769153 -0.997026 + outer loop + vertex 285.08 73.3642 299.889 + vertex 284.257 79.233 299.44 + vertex 299.104 75.2505 299.675 + endloop + endfacet + facet normal 0.00445082 -0.0754045 -0.997143 + outer loop + vertex 268.143 71.6663 299.942 + vertex 267.4 77.5718 299.492 + vertex 285.08 73.3642 299.889 + endloop + endfacet + facet normal 0.00626258 -0.0741541 -0.997227 + outer loop + vertex 248.525 70.0312 299.94 + vertex 247.851 75.96 299.495 + vertex 268.143 71.6663 299.942 + endloop + endfacet + facet normal 0.00611025 -0.0735103 -0.997276 + outer loop + vertex 227.136 68.3449 299.934 + vertex 226.527 74.2875 299.492 + vertex 248.525 70.0312 299.94 + endloop + endfacet + facet normal 0.00650357 -0.0731222 -0.997302 + outer loop + vertex 205.088 66.5895 299.918 + vertex 204.523 72.5421 299.478 + vertex 227.136 68.3449 299.934 + endloop + endfacet + facet normal 0.00773915 -0.0730241 -0.9973 + outer loop + vertex 183.211 64.824 299.878 + vertex 182.7 70.7828 299.438 + vertex 205.088 66.5895 299.918 + endloop + endfacet + facet normal 0.00945657 -0.0731994 -0.997272 + outer loop + vertex 161.88 63.116 299.801 + vertex 161.423 69.0795 299.359 + vertex 183.211 64.824 299.878 + endloop + endfacet + facet normal 0.0102521 -0.0731544 -0.997268 + outer loop + vertex 141.097 61.5189 299.705 + vertex 140.71 67.4866 299.263 + vertex 161.88 63.116 299.801 + endloop + endfacet + facet normal 0.00957812 -0.0741721 -0.997199 + outer loop + vertex 120.664 60.071 299.616 + vertex 120.34 66.0362 299.169 + vertex 141.097 61.5189 299.705 + endloop + endfacet + facet normal 0.00770802 -0.0740147 -0.997227 + outer loop + vertex 100.391 58.7993 299.554 + vertex 100.137 64.7674 299.109 + vertex 120.664 60.071 299.616 + endloop + endfacet + facet normal 0.00468753 -0.0745509 -0.997206 + outer loop + vertex 80.1943 57.7454 299.538 + vertex 79.9995 63.7105 299.091 + vertex 100.391 58.7993 299.554 + endloop + endfacet + facet normal 0.00224478 -0.073821 -0.997269 + outer loop + vertex 60.0589 56.9175 299.553 + vertex 59.9209 62.8871 299.111 + vertex 80.1943 57.7454 299.538 + endloop + endfacet + facet normal 0.0001002 -0.0742754 -0.997238 + outer loop + vertex 40.0126 56.3356 299.595 + vertex 39.9214 62.3005 299.151 + vertex 60.0589 56.9175 299.553 + endloop + endfacet + facet normal -0.000703275 -0.0744891 -0.997222 + outer loop + vertex 20.0546 55.993 299.634 + vertex 20.0075 61.9538 299.189 + vertex 40.0126 56.3356 299.595 + endloop + endfacet + facet normal -0.00034878 -0.0745029 -0.997221 + outer loop + vertex 0.132592 55.8795 299.65 + vertex 0.129371 61.8392 299.205 + vertex 20.0546 55.993 299.634 + endloop + endfacet + facet normal 0.000458479 -0.074074 -0.997253 + outer loop + vertex -19.8262 55.9918 299.632 + vertex -19.7854 61.9557 299.189 + vertex 0.132592 55.8795 299.65 + endloop + endfacet + facet normal 0.000414713 -0.0745311 -0.997219 + outer loop + vertex -39.8636 56.3442 299.598 + vertex -39.7766 62.3058 299.152 + vertex -19.8262 55.9918 299.632 + endloop + endfacet + facet normal -0.000106711 -0.0746382 -0.997211 + outer loop + vertex -59.9469 56.925 299.556 + vertex -59.8106 62.8883 299.11 + vertex -39.8636 56.3442 299.598 + endloop + endfacet + facet normal -0.00194677 -0.0743344 -0.997231 + outer loop + vertex -79.9948 57.7395 299.535 + vertex -79.8033 63.7065 299.09 + vertex -59.9469 56.925 299.556 + endloop + endfacet + facet normal -0.00475285 -0.0742417 -0.997229 + outer loop + vertex -99.9626 58.7829 299.552 + vertex -99.7123 64.7504 299.107 + vertex -79.9948 57.7395 299.535 + endloop + endfacet + facet normal -0.00758158 -0.0745376 -0.997189 + outer loop + vertex -119.94 60.0339 299.611 + vertex -119.623 65.9988 299.162 + vertex -99.9626 58.7829 299.552 + endloop + endfacet + facet normal -0.00960846 -0.0741332 -0.997202 + outer loop + vertex -140.167 61.4617 299.699 + vertex -139.777 67.4259 299.252 + vertex -119.94 60.0339 299.611 + endloop + endfacet + facet normal -0.0100563 -0.0731231 -0.997272 + outer loop + vertex -160.923 63.0272 299.794 + vertex -160.477 68.9922 299.352 + vertex -140.167 61.4617 299.699 + endloop + endfacet + facet normal -0.00959087 -0.0731377 -0.997276 + outer loop + vertex -182.395 64.7099 299.877 + vertex -181.889 70.6694 299.435 + vertex -160.923 63.0272 299.794 + endloop + endfacet + facet normal -0.00829582 -0.0729225 -0.997303 + outer loop + vertex -204.439 66.4944 299.93 + vertex -203.885 72.4472 299.49 + vertex -182.395 64.7099 299.877 + endloop + endfacet + facet normal -0.00676009 -0.0730231 -0.997307 + outer loop + vertex -226.523 68.3428 299.944 + vertex -225.92 74.2888 299.505 + vertex -204.439 66.4944 299.93 + endloop + endfacet + facet normal -0.00524208 -0.0725633 -0.99735 + outer loop + vertex -247.867 70.1667 299.924 + vertex -247.153 76.0964 299.489 + vertex -226.523 68.3428 299.944 + endloop + endfacet + facet normal -0.00436022 -0.0736817 -0.997272 + outer loop + vertex -267.582 71.8191 299.888 + vertex -266.769 77.7177 299.449 + vertex -247.867 70.1667 299.924 + endloop + endfacet + facet normal -0.00329322 -0.0761816 -0.997089 + outer loop + vertex -284.99 73.158 299.843 + vertex -284.122 79.0131 299.393 + vertex -267.582 71.8191 299.888 + endloop + endfacet + facet normal 0.00260575 -0.0770515 -0.997024 + outer loop + vertex -284.99 73.158 299.843 + vertex -299.147 79.9811 299.279 + vertex -284.122 79.0131 299.393 + endloop + endfacet + facet normal 0.024009 -0.0451718 -0.998691 + outer loop + vertex -308.013 82.6833 298.943 + vertex -306.44 85.2837 298.864 + vertex -299.147 79.9811 299.279 + endloop + endfacet + facet normal 0.0568954 -0.0565927 -0.996775 + outer loop + vertex -312.596 82.9871 298.665 + vertex -312.002 85.8906 298.534 + vertex -308.013 82.6833 298.943 + endloop + endfacet + facet normal 0.111409 -0.0836896 -0.990245 + outer loop + vertex -313.186 80.0971 298.842 + vertex -316.65 83.6152 298.155 + vertex -312.596 82.9871 298.665 + endloop + endfacet + facet normal 0.107882 -0.0871797 -0.990334 + outer loop + vertex -317.266 80.7333 298.342 + vertex -316.65 83.6152 298.155 + vertex -313.186 80.0971 298.842 + endloop + endfacet + facet normal 0.105211 -0.10331 -0.989069 + outer loop + vertex -313.736 77.1211 299.095 + vertex -317.266 80.7333 298.342 + vertex -313.186 80.0971 298.842 + endloop + endfacet + facet normal 0.100578 -0.107837 -0.989068 + outer loop + vertex -317.94 77.804 298.593 + vertex -317.266 80.7333 298.342 + vertex -313.736 77.1211 299.095 + endloop + endfacet + facet normal 0.0968853 -0.12898 -0.986903 + outer loop + vertex -314.44 73.9428 299.441 + vertex -317.94 77.804 298.593 + vertex -313.736 77.1211 299.095 + endloop + endfacet + facet normal 0.0908853 -0.134386 -0.986752 + outer loop + vertex -318.945 75.0134 298.88 + vertex -317.94 77.804 298.593 + vertex -314.44 73.9428 299.441 + endloop + endfacet + facet normal 0.0822037 -0.168559 -0.982258 + outer loop + vertex -316.376 71.0953 299.768 + vertex -318.945 75.0134 298.88 + vertex -314.44 73.9428 299.441 + endloop + endfacet + facet normal 0.0407886 -0.141192 -0.989142 + outer loop + vertex -316.376 71.0953 299.768 + vertex -314.44 73.9428 299.441 + vertex -309.315 69.2756 300.319 + endloop + endfacet + facet normal 0.0266521 -0.193505 -0.980737 + outer loop + vertex -309.315 69.2756 300.319 + vertex -313.673 65.5224 300.941 + vertex -316.376 71.0953 299.768 + endloop + endfacet + facet normal 0.0815016 -0.167281 -0.982535 + outer loop + vertex -319.907 69.9965 299.662 + vertex -316.376 71.0953 299.768 + vertex -313.673 65.5224 300.941 + endloop + endfacet + facet normal 0.0861214 -0.182427 -0.97944 + outer loop + vertex -320.237 72.9482 299.083 + vertex -316.376 71.0953 299.768 + vertex -319.907 69.9965 299.662 + endloop + endfacet + facet normal 0.0983831 -0.158012 -0.982524 + outer loop + vertex -320.237 72.9482 299.083 + vertex -318.945 75.0134 298.88 + vertex -316.376 71.0953 299.768 + endloop + endfacet + facet normal 0.0379509 -0.116528 -0.992462 + outer loop + vertex -314.44 73.9428 299.441 + vertex -313.736 77.1211 299.095 + vertex -308.212 73.292 299.756 + endloop + endfacet + facet normal 0.020233 -0.0807829 -0.996526 + outer loop + vertex -309.081 76.821 299.349 + vertex -307.55 79.4404 299.167 + vertex -299.86 74.1187 299.755 + endloop + endfacet + facet normal -0.00610531 -0.130221 -0.991466 + outer loop + vertex -299.116 68.3289 300.511 + vertex -299.86 74.1187 299.755 + vertex -285.567 67.4486 300.543 + endloop + endfacet + facet normal 0.0344559 -0.148005 -0.988386 + outer loop + vertex -309.315 69.2756 300.319 + vertex -314.44 73.9428 299.441 + vertex -308.212 73.292 299.756 + endloop + endfacet + facet normal 0.00970373 -0.174465 -0.984615 + outer loop + vertex -313.673 65.5224 300.941 + vertex -309.315 69.2756 300.319 + vertex -300.441 63.5083 301.428 + endloop + endfacet +endsolid diff --git a/noether_examples/meshes/outputs/output_12.stl b/noether_examples/meshes/outputs/output_12.stl new file mode 100644 index 00000000..462f7e28 --- /dev/null +++ b/noether_examples/meshes/outputs/output_12.stl @@ -0,0 +1,3740 @@ +solid ascii + facet normal -0.107815 -0.90978 -0.400843 + outer loop + vertex -375.281 50.6439 313.627 + vertex -371.441 50.5987 312.697 + vertex -372.282 49.5969 315.197 + endloop + endfacet + facet normal -0.113058 -0.899047 -0.423005 + outer loop + vertex -371.441 50.5987 312.697 + vertex -375.281 50.6439 313.627 + vertex -375.084 51.9394 310.821 + endloop + endfacet + facet normal -0.113355 -0.899008 -0.423008 + outer loop + vertex -380.467 51.6237 312.934 + vertex -375.084 51.9394 310.821 + vertex -375.281 50.6439 313.627 + endloop + endfacet + facet normal -0.104409 -0.909746 -0.401823 + outer loop + vertex -380.467 51.6237 312.934 + vertex -382.742 53.4918 309.296 + vertex -375.084 51.9394 310.821 + endloop + endfacet + facet normal -0.114242 -0.910981 -0.39631 + outer loop + vertex -387.797 53.1393 311.563 + vertex -382.742 53.4918 309.296 + vertex -380.467 51.6237 312.934 + endloop + endfacet + facet normal -0.10545 -0.919751 -0.378072 + outer loop + vertex -387.797 53.1393 311.563 + vertex -390.47 55.2628 307.143 + vertex -382.742 53.4918 309.296 + endloop + endfacet + facet normal -0.113815 -0.920645 -0.373443 + outer loop + vertex -395.855 54.992 309.452 + vertex -390.47 55.2628 307.143 + vertex -387.797 53.1393 311.563 + endloop + endfacet + facet normal -0.103572 -0.930729 -0.350737 + outer loop + vertex -395.855 54.992 309.452 + vertex -398.025 57.1492 304.368 + vertex -390.47 55.2628 307.143 + endloop + endfacet + facet normal -0.0846705 -0.915986 -0.392174 + outer loop + vertex -398.025 57.1492 304.368 + vertex -391.817 57.575 302.033 + vertex -390.47 55.2628 307.143 + endloop + endfacet + facet normal -0.0758067 -0.915796 -0.394424 + outer loop + vertex -390.47 55.2628 307.143 + vertex -391.817 57.575 302.033 + vertex -384.808 55.7863 304.839 + endloop + endfacet + facet normal -0.0887752 -0.901722 -0.423103 + outer loop + vertex -390.47 55.2628 307.143 + vertex -384.808 55.7863 304.839 + vertex -382.742 53.4918 309.296 + endloop + endfacet + facet normal -0.0769357 -0.900513 -0.427968 + outer loop + vertex -382.742 53.4918 309.296 + vertex -384.808 55.7863 304.839 + vertex -377.514 54.1555 306.96 + endloop + endfacet + facet normal -0.0896923 -0.887136 -0.452709 + outer loop + vertex -382.742 53.4918 309.296 + vertex -377.514 54.1555 306.96 + vertex -375.084 51.9394 310.821 + endloop + endfacet + facet normal -0.0738768 -0.884301 -0.461037 + outer loop + vertex -375.084 51.9394 310.821 + vertex -377.514 54.1555 306.96 + vertex -370.852 52.976 308.154 + endloop + endfacet + facet normal -0.0889747 -0.872515 -0.480418 + outer loop + vertex -375.084 51.9394 310.821 + vertex -370.852 52.976 308.154 + vertex -368.666 51.4154 310.584 + endloop + endfacet + facet normal -0.0891188 -0.884062 -0.458795 + outer loop + vertex -368.666 51.4154 310.584 + vertex -371.441 50.5987 312.697 + vertex -375.084 51.9394 310.821 + endloop + endfacet + facet normal -0.0506801 -0.894715 -0.443752 + outer loop + vertex -391.817 57.575 302.033 + vertex -385.202 58.3195 299.777 + vertex -384.808 55.7863 304.839 + endloop + endfacet + facet normal -0.0390194 -0.894822 -0.444714 + outer loop + vertex -384.808 55.7863 304.839 + vertex -385.202 58.3195 299.777 + vertex -378.711 56.6533 302.56 + endloop + endfacet + facet normal -0.0556157 -0.874705 -0.481453 + outer loop + vertex -384.808 55.7863 304.839 + vertex -378.711 56.6533 302.56 + vertex -377.514 54.1555 306.96 + endloop + endfacet + facet normal -0.0408325 -0.873635 -0.484865 + outer loop + vertex -377.514 54.1555 306.96 + vertex -378.711 56.6533 302.56 + vertex -372.11 55.1799 304.659 + endloop + endfacet + facet normal -0.0583925 -0.853818 -0.517287 + outer loop + vertex -377.514 54.1555 306.96 + vertex -372.11 55.1799 304.659 + vertex -370.852 52.976 308.154 + endloop + endfacet + facet normal -0.0380233 -0.851419 -0.523106 + outer loop + vertex -370.852 52.976 308.154 + vertex -372.11 55.1799 304.659 + vertex -366.25 54.0845 306.016 + endloop + endfacet + facet normal -0.0548283 -0.83341 -0.549928 + outer loop + vertex -370.852 52.976 308.154 + vertex -366.25 54.0845 306.016 + vertex -365.905 52.4401 308.473 + endloop + endfacet + facet normal -0.0613738 -0.863979 -0.499773 + outer loop + vertex -365.905 52.4401 308.473 + vertex -368.666 51.4154 310.584 + vertex -370.852 52.976 308.154 + endloop + endfacet + facet normal -0.0346673 -0.914408 -0.403307 + outer loop + vertex -391.817 57.575 302.033 + vertex -391.169 59.9951 296.491 + vertex -385.202 58.3195 299.777 + endloop + endfacet + facet normal -0.00283943 -0.892944 -0.45016 + outer loop + vertex -391.169 59.9951 296.491 + vertex -383.483 61.0248 294.4 + vertex -385.202 58.3195 299.777 + endloop + endfacet + facet normal 0.00840544 -0.894356 -0.447277 + outer loop + vertex -385.202 58.3195 299.777 + vertex -383.483 61.0248 294.4 + vertex -377.998 59.4607 297.63 + endloop + endfacet + facet normal 0.0125722 -0.914596 -0.404173 + outer loop + vertex -391.169 59.9951 296.491 + vertex -388.509 62.5245 290.85 + vertex -383.483 61.0248 294.4 + endloop + endfacet + facet normal 0.000752945 -0.9126 -0.408852 + outer loop + vertex -396.683 61.5886 292.924 + vertex -388.509 62.5245 290.85 + vertex -391.169 59.9951 296.491 + endloop + endfacet + facet normal -0.0319034 -0.930011 -0.366145 + outer loop + vertex -398.363 59.3588 298.734 + vertex -396.683 61.5886 292.924 + vertex -391.169 59.9951 296.491 + endloop + endfacet + facet normal -0.0429881 -0.928523 -0.368779 + outer loop + vertex -404.636 61.0896 295.107 + vertex -396.683 61.5886 292.924 + vertex -398.363 59.3588 298.734 + endloop + endfacet + facet normal -0.0693563 -0.941632 -0.329423 + outer loop + vertex -405.312 59.0587 301.054 + vertex -404.636 61.0896 295.107 + vertex -398.363 59.3588 298.734 + endloop + endfacet + facet normal -0.0800038 -0.929612 -0.359751 + outer loop + vertex -405.312 59.0587 301.054 + vertex -398.363 59.3588 298.734 + vertex -398.025 57.1492 304.368 + endloop + endfacet + facet normal -0.100193 -0.941376 -0.322137 + outer loop + vertex -403.97 56.9797 306.713 + vertex -405.312 59.0587 301.054 + vertex -398.025 57.1492 304.368 + endloop + endfacet + facet normal -0.105717 -0.941237 -0.320777 + outer loop + vertex -412.071 58.9975 303.462 + vertex -405.312 59.0587 301.054 + vertex -403.97 56.9797 306.713 + endloop + endfacet + facet normal -0.122948 -0.950948 -0.283871 + outer loop + vertex -409.712 57.0207 309.062 + vertex -412.071 58.9975 303.462 + vertex -403.97 56.9797 306.713 + endloop + endfacet + facet normal -0.131775 -0.943004 -0.305579 + outer loop + vertex -409.712 57.0207 309.062 + vertex -403.97 56.9797 306.713 + vertex -400.977 54.9361 311.728 + endloop + endfacet + facet normal -0.126802 -0.942753 -0.308445 + outer loop + vertex -400.977 54.9361 311.728 + vertex -403.97 56.9797 306.713 + vertex -395.855 54.992 309.452 + endloop + endfacet + facet normal -0.134902 -0.935523 -0.326493 + outer loop + vertex -400.977 54.9361 311.728 + vertex -395.855 54.992 309.452 + vertex -392.476 52.9862 313.803 + endloop + endfacet + facet normal -0.128062 -0.934743 -0.331445 + outer loop + vertex -392.476 52.9862 313.803 + vertex -395.855 54.992 309.452 + vertex -387.797 53.1393 311.563 + endloop + endfacet + facet normal -0.13398 -0.929563 -0.343456 + outer loop + vertex -392.476 52.9862 313.803 + vertex -387.797 53.1393 311.563 + vertex -384.907 51.3953 315.156 + endloop + endfacet + facet normal -0.12677 -0.92859 -0.348785 + outer loop + vertex -384.907 51.3953 315.156 + vertex -387.797 53.1393 311.563 + vertex -380.467 51.6237 312.934 + endloop + endfacet + facet normal -0.131703 -0.924308 -0.358201 + outer loop + vertex -384.907 51.3953 315.156 + vertex -380.467 51.6237 312.934 + vertex -378.608 50.2762 315.728 + endloop + endfacet + facet normal -0.126234 -0.923757 -0.361576 + outer loop + vertex -375.281 50.6439 313.627 + vertex -378.608 50.2762 315.728 + vertex -380.467 51.6237 312.934 + endloop + endfacet + facet normal -0.129723 -0.921265 -0.366664 + outer loop + vertex -378.608 50.2762 315.728 + vertex -375.281 50.6439 313.627 + vertex -372.282 49.5969 315.197 + endloop + endfacet + facet normal -0.127848 -0.950918 -0.281796 + outer loop + vertex -418.446 59.1362 305.886 + vertex -412.071 58.9975 303.462 + vertex -409.712 57.0207 309.062 + endloop + endfacet + facet normal -0.145884 -0.96016 -0.238351 + outer loop + vertex -415.172 57.2671 311.412 + vertex -418.446 59.1362 305.886 + vertex -409.712 57.0207 309.062 + endloop + endfacet + facet normal -0.15284 -0.954763 -0.255084 + outer loop + vertex -415.172 57.2671 311.412 + vertex -409.712 57.0207 309.062 + vertex -405.851 55.0833 314 + endloop + endfacet + facet normal -0.149074 -0.954586 -0.25796 + outer loop + vertex -405.851 55.0833 314 + vertex -409.712 57.0207 309.062 + vertex -400.977 54.9361 311.728 + endloop + endfacet + facet normal -0.15538 -0.949727 -0.271802 + outer loop + vertex -405.851 55.0833 314 + vertex -400.977 54.9361 311.728 + vertex -396.823 53.0333 316.002 + endloop + endfacet + facet normal -0.150217 -0.949179 -0.276576 + outer loop + vertex -396.823 53.0333 316.002 + vertex -400.977 54.9361 311.728 + vertex -392.476 52.9862 313.803 + endloop + endfacet + facet normal -0.15503 -0.945555 -0.286167 + outer loop + vertex -396.823 53.0333 316.002 + vertex -392.476 52.9862 313.803 + vertex -389.014 51.3503 317.333 + endloop + endfacet + facet normal -0.14582 -0.944408 -0.294669 + outer loop + vertex -389.014 51.3503 317.333 + vertex -392.476 52.9862 313.803 + vertex -384.907 51.3953 315.156 + endloop + endfacet + facet normal -0.146874 -0.943627 -0.29664 + outer loop + vertex -389.014 51.3503 317.333 + vertex -384.907 51.3953 315.156 + vertex -383.01 50.1609 318.143 + endloop + endfacet + facet normal -0.140304 -0.943344 -0.300695 + outer loop + vertex -378.608 50.2762 315.728 + vertex -383.01 50.1609 318.143 + vertex -384.907 51.3953 315.156 + endloop + endfacet + facet normal -0.149544 -0.960135 -0.236174 + outer loop + vertex -424.466 59.4838 308.285 + vertex -418.446 59.1362 305.886 + vertex -415.172 57.2671 311.412 + endloop + endfacet + facet normal -0.142883 -0.965272 -0.218711 + outer loop + vertex -424.466 59.4838 308.285 + vertex -427.323 61.2817 302.216 + vertex -418.446 59.1362 305.886 + endloop + endfacet + facet normal -0.125468 -0.958297 -0.256759 + outer loop + vertex -427.323 61.2817 302.216 + vertex -420.424 61.0199 299.822 + vertex -418.446 59.1362 305.886 + endloop + endfacet + facet normal -0.117531 -0.965319 -0.23312 + outer loop + vertex -420.424 61.0199 299.822 + vertex -427.323 61.2817 302.216 + vertex -427.238 62.3596 297.71 + endloop + endfacet + facet normal -0.111412 -0.961672 -0.250549 + outer loop + vertex -423.897 62.4101 296.031 + vertex -420.424 61.0199 299.822 + vertex -427.238 62.3596 297.71 + endloop + endfacet + facet normal -0.109638 -0.96278 -0.247052 + outer loop + vertex -427.238 62.3596 297.71 + vertex -427.507 63.2993 294.167 + vertex -423.897 62.4101 296.031 + endloop + endfacet + facet normal -0.0998302 -0.959242 -0.264364 + outer loop + vertex -427.507 63.2993 294.167 + vertex -423.15 63.1907 292.916 + vertex -423.897 62.4101 296.031 + endloop + endfacet + facet normal -0.0953314 -0.959948 -0.263461 + outer loop + vertex -423.897 62.4101 296.031 + vertex -423.15 63.1907 292.916 + vertex -419.306 62.155 295.299 + endloop + endfacet + facet normal -0.083785 -0.956202 -0.28046 + outer loop + vertex -423.15 63.1907 292.916 + vertex -417.878 63.0874 291.693 + vertex -419.306 62.155 295.299 + endloop + endfacet + facet normal -0.0856718 -0.955842 -0.281115 + outer loop + vertex -419.306 62.155 295.299 + vertex -417.878 63.0874 291.693 + vertex -415.573 62.2353 293.888 + endloop + endfacet + facet normal -0.0861407 -0.955441 -0.282333 + outer loop + vertex -415.573 62.2353 293.888 + vertex -412.886 61.0098 297.215 + vertex -419.306 62.155 295.299 + endloop + endfacet + facet normal -0.0925081 -0.96013 -0.263806 + outer loop + vertex -412.886 61.0098 297.215 + vertex -420.424 61.0199 299.822 + vertex -419.306 62.155 295.299 + endloop + endfacet + facet normal -0.102548 -0.950636 -0.292875 + outer loop + vertex -420.424 61.0199 299.822 + vertex -412.886 61.0098 297.215 + vertex -412.071 58.9975 303.462 + endloop + endfacet + facet normal -0.0622473 -0.951813 -0.300296 + outer loop + vertex -415.573 62.2353 293.888 + vertex -410.773 62.7013 291.416 + vertex -412.886 61.0098 297.215 + endloop + endfacet + facet normal -0.0680101 -0.950843 -0.302113 + outer loop + vertex -412.886 61.0098 297.215 + vertex -410.773 62.7013 291.416 + vertex -404.636 61.0896 295.107 + endloop + endfacet + facet normal -0.0428316 -0.939764 -0.33913 + outer loop + vertex -410.773 62.7013 291.416 + vertex -401.818 63.0096 289.431 + vertex -404.636 61.0896 295.107 + endloop + endfacet + facet normal -0.0382643 -0.946774 -0.319617 + outer loop + vertex -410.773 62.7013 291.416 + vertex -405.423 64.2831 286.09 + vertex -401.818 63.0096 289.431 + endloop + endfacet + facet normal -0.0060834 -0.936563 -0.350447 + outer loop + vertex -405.423 64.2831 286.09 + vertex -397.833 64.6617 284.946 + vertex -401.818 63.0096 289.431 + endloop + endfacet + facet normal 0.00983519 -0.941104 -0.337973 + outer loop + vertex -401.818 63.0096 289.431 + vertex -397.833 64.6617 284.946 + vertex -393.342 63.8455 287.35 + endloop + endfacet + facet normal -0.000857045 -0.926723 -0.375745 + outer loop + vertex -401.818 63.0096 289.431 + vertex -393.342 63.8455 287.35 + vertex -396.683 61.5886 292.924 + endloop + endfacet + facet normal 0.0365231 -0.923496 -0.381865 + outer loop + vertex -397.833 64.6617 284.946 + vertex -389.055 66.3289 281.754 + vertex -393.342 63.8455 287.35 + endloop + endfacet + facet normal 0.0567046 -0.927945 -0.368379 + outer loop + vertex -393.342 63.8455 287.35 + vertex -389.055 66.3289 281.754 + vertex -384.324 65.2155 285.287 + endloop + endfacet + facet normal 0.0454649 -0.912253 -0.407095 + outer loop + vertex -393.342 63.8455 287.35 + vertex -384.324 65.2155 285.287 + vertex -388.509 62.5245 290.85 + endloop + endfacet + facet normal 0.0595977 -0.915444 -0.398008 + outer loop + vertex -388.509 62.5245 290.85 + vertex -384.324 65.2155 285.287 + vertex -379.917 63.8966 288.98 + endloop + endfacet + facet normal 0.046377 -0.894959 -0.443731 + outer loop + vertex -388.509 62.5245 290.85 + vertex -379.917 63.8966 288.98 + vertex -383.483 61.0248 294.4 + endloop + endfacet + facet normal 0.0573181 -0.897266 -0.437754 + outer loop + vertex -383.483 61.0248 294.4 + vertex -379.917 63.8966 288.98 + vertex -375.347 62.495 292.452 + endloop + endfacet + facet normal 0.0488963 -0.934183 -0.353427 + outer loop + vertex -389.055 66.3289 281.754 + vertex -397.833 64.6617 284.946 + vertex -397.804 65.9029 281.669 + endloop + endfacet + facet normal 0.048831 -0.931395 -0.360721 + outer loop + vertex -397.804 65.9029 281.669 + vertex -388.958 67.567 278.57 + vertex -389.055 66.3289 281.754 + endloop + endfacet + facet normal 0.0778446 -0.953866 -0.289966 + outer loop + vertex -397.804 65.9029 281.669 + vertex -392.268 67.3729 278.32 + vertex -388.958 67.567 278.57 + endloop + endfacet + facet normal 0.0508706 -0.942727 -0.329665 + outer loop + vertex -401.694 66.0121 280.757 + vertex -392.268 67.3729 278.32 + vertex -397.804 65.9029 281.669 + endloop + endfacet + facet normal -0.00673104 -0.93512 -0.354268 + outer loop + vertex -397.833 64.6617 284.946 + vertex -405.423 64.2831 286.09 + vertex -397.804 65.9029 281.669 + endloop + endfacet + facet normal 0.011347 -0.945043 -0.326748 + outer loop + vertex -407.51 65.1526 283.503 + vertex -397.804 65.9029 281.669 + vertex -405.423 64.2831 286.09 + endloop + endfacet + facet normal -0.0328811 -0.955102 -0.294447 + outer loop + vertex -405.423 64.2831 286.09 + vertex -414.559 64.1604 287.508 + vertex -407.51 65.1526 283.503 + endloop + endfacet + facet normal -0.0225711 -0.960425 -0.277623 + outer loop + vertex -414.381 64.9581 284.734 + vertex -407.51 65.1526 283.503 + vertex -414.559 64.1604 287.508 + endloop + endfacet + facet normal -0.0635456 -0.958023 -0.279559 + outer loop + vertex -421.757 64.6545 287.451 + vertex -414.381 64.9581 284.734 + vertex -414.559 64.1604 287.508 + endloop + endfacet + facet normal -0.0633938 -0.956436 -0.284975 + outer loop + vertex -414.559 64.1604 287.508 + vertex -421.208 63.8958 289.875 + vertex -421.757 64.6545 287.451 + endloop + endfacet + facet normal -0.0884345 -0.956149 -0.27921 + outer loop + vertex -421.208 63.8958 289.875 + vertex -426.263 64.0542 290.934 + vertex -421.757 64.6545 287.451 + endloop + endfacet + facet normal -0.0968734 -0.952276 -0.289459 + outer loop + vertex -430.433 64.7408 290.071 + vertex -421.757 64.6545 287.451 + vertex -426.263 64.0542 290.934 + endloop + endfacet + facet normal -0.102873 -0.958602 -0.265519 + outer loop + vertex -426.263 64.0542 290.934 + vertex -430.447 64.0541 292.555 + vertex -430.433 64.7408 290.071 + endloop + endfacet + facet normal -0.120879 -0.956622 -0.265072 + outer loop + vertex -430.447 64.0541 292.555 + vertex -434.344 64.322 293.366 + vertex -430.433 64.7408 290.071 + endloop + endfacet + facet normal -0.121093 -0.956527 -0.265315 + outer loop + vertex -438.486 65.1072 292.425 + vertex -430.433 64.7408 290.071 + vertex -434.344 64.322 293.366 + endloop + endfacet + facet normal -0.127821 -0.96221 -0.240443 + outer loop + vertex -434.344 64.322 293.366 + vertex -438.034 64.4373 294.866 + vertex -438.486 65.1072 292.425 + endloop + endfacet + facet normal -0.142524 -0.960908 -0.237366 + outer loop + vertex -438.034 64.4373 294.866 + vertex -442.069 64.8222 295.731 + vertex -438.486 65.1072 292.425 + endloop + endfacet + facet normal -0.143408 -0.960547 -0.238294 + outer loop + vertex -447.216 65.7726 294.997 + vertex -438.486 65.1072 292.425 + vertex -442.069 64.8222 295.731 + endloop + endfacet + facet normal -0.147926 -0.965725 -0.213292 + outer loop + vertex -442.069 64.8222 295.731 + vertex -445.781 65.0323 297.353 + vertex -447.216 65.7726 294.997 + endloop + endfacet + facet normal -0.161538 -0.965364 -0.204883 + outer loop + vertex -445.781 65.0323 297.353 + vertex -449.549 65.4405 298.401 + vertex -447.216 65.7726 294.997 + endloop + endfacet + facet normal -0.15962 -0.965949 -0.203626 + outer loop + vertex -453.617 66.2286 297.851 + vertex -447.216 65.7726 294.997 + vertex -449.549 65.4405 298.401 + endloop + endfacet + facet normal -0.163995 -0.970349 -0.177564 + outer loop + vertex -452.826 65.6935 300.045 + vertex -453.617 66.2286 297.851 + vertex -449.549 65.4405 298.401 + endloop + endfacet + facet normal -0.163172 -0.970799 -0.175854 + outer loop + vertex -452.826 65.6935 300.045 + vertex -449.549 65.4405 298.401 + vertex -449.49 64.8657 301.52 + endloop + endfacet + facet normal -0.173355 -0.972758 -0.153913 + outer loop + vertex -452.95 65.275 302.829 + vertex -452.826 65.6935 300.045 + vertex -449.49 64.8657 301.52 + endloop + endfacet + facet normal -0.171296 -0.974028 -0.14808 + outer loop + vertex -452.95 65.275 302.829 + vertex -449.49 64.8657 301.52 + vertex -448.071 64.0663 305.135 + endloop + endfacet + facet normal -0.180987 -0.975102 -0.128141 + outer loop + vertex -452.027 64.686 306.008 + vertex -452.95 65.275 302.829 + vertex -448.071 64.0663 305.135 + endloop + endfacet + facet normal -0.178204 -0.977379 -0.113902 + outer loop + vertex -452.027 64.686 306.008 + vertex -448.071 64.0663 305.135 + vertex -446.293 63.1937 309.841 + endloop + endfacet + facet normal -0.189928 -0.977069 -0.0962458 + outer loop + vertex -452.027 64.686 306.008 + vertex -446.293 63.1937 309.841 + vertex -454.484 64.9785 307.889 + endloop + endfacet + facet normal -0.1942 -0.97564 -0.102048 + outer loop + vertex -454.484 64.9785 307.889 + vertex -456.382 65.7543 304.083 + vertex -452.027 64.686 306.008 + endloop + endfacet + facet normal -0.190359 -0.976182 -0.104074 + outer loop + vertex -459.787 66.2705 305.468 + vertex -456.382 65.7543 304.083 + vertex -454.484 64.9785 307.889 + endloop + endfacet + facet normal -0.199546 -0.976281 -0.0840022 + outer loop + vertex -458.253 65.6697 308.808 + vertex -459.787 66.2705 305.468 + vertex -454.484 64.9785 307.889 + endloop + endfacet + facet normal -0.196177 -0.978153 -0.0687825 + outer loop + vertex -458.253 65.6697 308.808 + vertex -454.484 64.9785 307.889 + vertex -451.54 64.0681 312.435 + endloop + endfacet + facet normal -0.206731 -0.977179 -0.0488184 + outer loop + vertex -458.253 65.6697 308.808 + vertex -451.54 64.0681 312.435 + vertex -460.007 65.9493 310.635 + endloop + endfacet + facet normal -0.212345 -0.975677 -0.0544346 + outer loop + vertex -460.007 65.9493 310.635 + vertex -462.96 66.8 306.909 + vertex -458.253 65.6697 308.808 + endloop + endfacet + facet normal -0.207741 -0.976447 -0.0582588 + outer loop + vertex -465.871 67.3337 308.345 + vertex -462.96 66.8 306.909 + vertex -460.007 65.9493 310.635 + endloop + endfacet + facet normal -0.215498 -0.975765 -0.0379818 + outer loop + vertex -463.169 66.6139 311.502 + vertex -465.871 67.3337 308.345 + vertex -460.007 65.9493 310.635 + endloop + endfacet + facet normal -0.212361 -0.976853 -0.0256953 + outer loop + vertex -463.169 66.6139 311.502 + vertex -460.007 65.9493 310.635 + vertex -455.425 64.8475 314.657 + endloop + endfacet + facet normal -0.220657 -0.975341 -0.00449219 + outer loop + vertex -463.169 66.6139 311.502 + vertex -455.425 64.8475 314.657 + vertex -463.741 66.7365 313.02 + endloop + endfacet + facet normal -0.226726 -0.973934 -0.00689542 + outer loop + vertex -463.741 66.7365 313.02 + vertex -468.322 67.8266 309.674 + vertex -463.169 66.6139 311.502 + endloop + endfacet + facet normal -0.221442 -0.975066 -0.0144996 + outer loop + vertex -470.507 68.3073 310.721 + vertex -468.322 67.8266 309.674 + vertex -463.741 66.7365 313.02 + endloop + endfacet + facet normal -0.229953 -0.973129 0.0118695 + outer loop + vertex -465.936 67.2628 313.656 + vertex -470.507 68.3073 310.721 + vertex -463.741 66.7365 313.02 + endloop + endfacet + facet normal -0.227786 -0.973513 0.0196625 + outer loop + vertex -465.936 67.2628 313.656 + vertex -463.741 66.7365 313.02 + vertex -456.946 65.2123 316.276 + endloop + endfacet + facet normal -0.233005 -0.971694 0.0389936 + outer loop + vertex -459.679 65.8737 316.425 + vertex -465.936 67.2628 313.656 + vertex -456.946 65.2123 316.276 + endloop + endfacet + facet normal -0.23256 -0.971483 0.0462214 + outer loop + vertex -459.679 65.8737 316.425 + vertex -456.946 65.2123 316.276 + vertex -449.378 63.5407 319.222 + endloop + endfacet + facet normal -0.23175 -0.971827 0.0429518 + outer loop + vertex -459.679 65.8737 316.425 + vertex -449.378 63.5407 319.222 + vertex -453.029 64.3827 318.572 + endloop + endfacet + facet normal -0.234305 -0.970793 0.0515861 + outer loop + vertex -453.029 64.3827 318.572 + vertex -457.466 65.3906 317.385 + vertex -459.679 65.8737 316.425 + endloop + endfacet + facet normal -0.234703 -0.970644 0.0525798 + outer loop + vertex -457.466 65.3906 317.385 + vertex -460.868 66.1587 316.382 + vertex -459.679 65.8737 316.425 + endloop + endfacet + facet normal -0.234532 -0.971056 0.045228 + outer loop + vertex -460.868 66.1587 316.382 + vertex -463.922 66.8499 315.382 + vertex -459.679 65.8737 316.425 + endloop + endfacet + facet normal -0.231626 -0.972269 0.0322755 + outer loop + vertex -470.037 68.2296 313.062 + vertex -459.679 65.8737 316.425 + vertex -463.922 66.8499 315.382 + endloop + endfacet + facet normal -0.231766 -0.972223 0.0326718 + outer loop + vertex -463.922 66.8499 315.382 + vertex -466.575 67.4544 314.552 + vertex -470.037 68.2296 313.062 + endloop + endfacet + facet normal -0.235975 -0.970799 0.0431923 + outer loop + vertex -466.575 67.4544 314.552 + vertex -469.706 68.1685 313.5 + vertex -470.037 68.2296 313.062 + endloop + endfacet + facet normal -0.236128 -0.970756 0.0433139 + outer loop + vertex -469.706 68.1685 313.5 + vertex -474.183 69.1858 311.892 + vertex -470.037 68.2296 313.062 + endloop + endfacet + facet normal -0.230864 -0.972713 0.0230645 + outer loop + vertex -478.25 70.1106 310.187 + vertex -470.037 68.2296 313.062 + vertex -474.183 69.1858 311.892 + endloop + endfacet + facet normal -0.230765 -0.972742 0.0228125 + outer loop + vertex -474.183 69.1858 311.892 + vertex -477.262 69.8904 310.787 + vertex -478.25 70.1106 310.187 + endloop + endfacet + facet normal -0.232532 -0.972244 0.0259036 + outer loop + vertex -477.262 69.8904 310.787 + vertex -480.754 70.689 309.415 + vertex -478.25 70.1106 310.187 + endloop + endfacet + facet normal -0.22909 -0.973305 0.0139437 + outer loop + vertex -483.34 71.2789 308.105 + vertex -478.25 70.1106 310.187 + vertex -480.754 70.689 309.415 + endloop + endfacet + facet normal -0.233422 -0.972103 0.0230314 + outer loop + vertex -480.754 70.689 309.415 + vertex -484.953 71.6559 307.668 + vertex -483.34 71.2789 308.105 + endloop + endfacet + facet normal -0.229775 -0.973206 0.00858969 + outer loop + vertex -486.183 71.9393 306.866 + vertex -483.34 71.2789 308.105 + vertex -484.953 71.6559 307.668 + endloop + endfacet + facet normal -0.246655 -0.968429 0.0361434 + outer loop + vertex -484.953 71.6559 307.668 + vertex -489.091 72.6494 306.048 + vertex -486.183 71.9393 306.866 + endloop + endfacet + facet normal -0.235555 -0.97184 -0.00631303 + outer loop + vertex -486.619 72.049 306.218 + vertex -486.183 71.9393 306.866 + vertex -489.091 72.6494 306.048 + endloop + endfacet + facet normal -0.231463 -0.970834 -0.0624944 + outer loop + vertex -484.804 71.6612 305.521 + vertex -486.619 72.049 306.218 + vertex -489.091 72.6494 306.048 + endloop + endfacet + facet normal -0.229546 -0.972296 -0.0441556 + outer loop + vertex -489.091 72.6494 306.048 + vertex -483.723 71.4656 304.21 + vertex -484.804 71.6612 305.521 + endloop + endfacet + facet normal -0.219319 -0.97524 -0.0283946 + outer loop + vertex -486.619 72.049 306.218 + vertex -484.804 71.6612 305.521 + vertex -485.003 71.6677 306.836 + endloop + endfacet + facet normal -0.222114 -0.974595 -0.0288209 + outer loop + vertex -483.682 71.3703 306.712 + vertex -485.003 71.6677 306.836 + vertex -484.804 71.6612 305.521 + endloop + endfacet + facet normal -0.220175 -0.974976 -0.0307408 + outer loop + vertex -483.682 71.3703 306.712 + vertex -484.804 71.6612 305.521 + vertex -482.177 71.0605 305.754 + endloop + endfacet + facet normal -0.217606 -0.975678 -0.0264744 + outer loop + vertex -483.682 71.3703 306.712 + vertex -482.177 71.0605 305.754 + vertex -481.144 70.7778 307.688 + endloop + endfacet + facet normal -0.223996 -0.974547 -0.00916101 + outer loop + vertex -482.062 70.9838 308.208 + vertex -483.682 71.3703 306.712 + vertex -481.144 70.7778 307.688 + endloop + endfacet + facet normal -0.22277 -0.974847 -0.00688256 + outer loop + vertex -482.062 70.9838 308.208 + vertex -481.144 70.7778 307.688 + vertex -477.603 69.9529 309.901 + endloop + endfacet + facet normal -0.23062 -0.972929 0.0149592 + outer loop + vertex -478.25 70.1106 310.187 + vertex -482.062 70.9838 308.208 + vertex -477.603 69.9529 309.901 + endloop + endfacet + facet normal -0.229187 -0.973375 0.00393018 + outer loop + vertex -477.603 69.9529 309.901 + vertex -481.144 70.7778 307.688 + vertex -478.078 70.0604 308.839 + endloop + endfacet + facet normal -0.226759 -0.973947 0.00278747 + outer loop + vertex -478.078 70.0604 308.839 + vertex -473.375 68.9716 310.94 + vertex -477.603 69.9529 309.901 + endloop + endfacet + facet normal -0.220705 -0.975274 -0.0114462 + outer loop + vertex -478.078 70.0604 308.839 + vertex -475.857 69.5619 308.488 + vertex -473.375 68.9716 310.94 + endloop + endfacet + facet normal -0.226068 -0.974095 -0.00573688 + outer loop + vertex -473.375 68.9716 310.94 + vertex -475.857 69.5619 308.488 + vertex -470.507 68.3073 310.721 + endloop + endfacet + facet normal -0.217613 -0.975665 -0.0268723 + outer loop + vertex -475.857 69.5619 308.488 + vertex -473.199 68.9953 307.536 + vertex -470.507 68.3073 310.721 + endloop + endfacet + facet normal -0.219306 -0.975134 -0.0319191 + outer loop + vertex -475.857 69.5619 308.488 + vertex -477.101 69.9301 305.79 + vertex -473.199 68.9953 307.536 + endloop + endfacet + facet normal -0.211397 -0.976115 -0.0501185 + outer loop + vertex -477.101 69.9301 305.79 + vertex -473.961 69.3178 304.471 + vertex -473.199 68.9953 307.536 + endloop + endfacet + facet normal -0.215517 -0.97527 -0.0490042 + outer loop + vertex -473.199 68.9953 307.536 + vertex -473.961 69.3178 304.471 + vertex -470.335 68.4294 306.206 + endloop + endfacet + facet normal -0.213948 -0.975789 -0.0454052 + outer loop + vertex -473.199 68.9953 307.536 + vertex -470.335 68.4294 306.206 + vertex -468.322 67.8266 309.674 + endloop + endfacet + facet normal -0.218991 -0.974809 -0.0423073 + outer loop + vertex -468.322 67.8266 309.674 + vertex -470.335 68.4294 306.206 + vertex -465.871 67.3337 308.345 + endloop + endfacet + facet normal -0.207583 -0.975941 -0.0666899 + outer loop + vertex -470.335 68.4294 306.206 + vertex -467.155 67.8525 304.749 + vertex -465.871 67.3337 308.345 + endloop + endfacet + facet normal -0.208925 -0.975436 -0.0698208 + outer loop + vertex -470.335 68.4294 306.206 + vertex -470.497 68.6925 303.015 + vertex -467.155 67.8525 304.749 + endloop + endfacet + facet normal -0.197465 -0.975968 -0.0921671 + outer loop + vertex -470.497 68.6925 303.015 + vertex -466.793 68.0806 301.558 + vertex -467.155 67.8525 304.749 + endloop + endfacet + facet normal -0.199867 -0.975456 -0.0924032 + outer loop + vertex -467.155 67.8525 304.749 + vertex -466.793 68.0806 301.558 + vertex -463.699 67.2827 303.29 + endloop + endfacet + facet normal -0.198746 -0.975951 -0.0895552 + outer loop + vertex -467.155 67.8525 304.749 + vertex -463.699 67.2827 303.29 + vertex -462.96 66.8 306.909 + endloop + endfacet + facet normal -0.202949 -0.975173 -0.0885928 + outer loop + vertex -462.96 66.8 306.909 + vertex -463.699 67.2827 303.29 + vertex -459.787 66.2705 305.468 + endloop + endfacet + facet normal -0.188826 -0.975365 -0.11405 + outer loop + vertex -463.699 67.2827 303.29 + vertex -460.002 66.7304 301.892 + vertex -459.787 66.2705 305.468 + endloop + endfacet + facet normal -0.189716 -0.974892 -0.116589 + outer loop + vertex -463.699 67.2827 303.29 + vertex -462.875 67.5 300.132 + vertex -460.002 66.7304 301.892 + endloop + endfacet + facet normal -0.175069 -0.974504 -0.14033 + outer loop + vertex -462.875 67.5 300.132 + vertex -458.471 66.9055 298.765 + vertex -460.002 66.7304 301.892 + endloop + endfacet + facet normal -0.182247 -0.972689 -0.143745 + outer loop + vertex -460.002 66.7304 301.892 + vertex -458.471 66.9055 298.765 + vertex -456.172 66.1877 300.707 + endloop + endfacet + facet normal -0.180159 -0.974145 -0.136325 + outer loop + vertex -460.002 66.7304 301.892 + vertex -456.172 66.1877 300.707 + vertex -456.382 65.7543 304.083 + endloop + endfacet + facet normal -0.185734 -0.973068 -0.136535 + outer loop + vertex -456.382 65.7543 304.083 + vertex -456.172 66.1877 300.707 + vertex -452.95 65.275 302.829 + endloop + endfacet + facet normal -0.166255 -0.972578 -0.162637 + outer loop + vertex -458.471 66.9055 298.765 + vertex -453.617 66.2286 297.851 + vertex -456.172 66.1877 300.707 + endloop + endfacet + facet normal -0.167703 -0.970776 -0.171665 + outer loop + vertex -458.471 66.9055 298.765 + vertex -454.882 66.7508 296.134 + vertex -453.617 66.2286 297.851 + endloop + endfacet + facet normal -0.165277 -0.971782 -0.168297 + outer loop + vertex -461.088 67.5212 297.78 + vertex -454.882 66.7508 296.134 + vertex -458.471 66.9055 298.765 + endloop + endfacet + facet normal -0.160928 -0.975475 -0.15017 + outer loop + vertex -454.882 66.7508 296.134 + vertex -461.088 67.5212 297.78 + vertex -458.067 67.3106 295.911 + endloop + endfacet + facet normal -0.1573 -0.969631 -0.187279 + outer loop + vertex -458.067 67.3106 295.911 + vertex -449.614 66.4067 293.491 + vertex -454.882 66.7508 296.134 + endloop + endfacet + facet normal -0.149709 -0.973722 -0.171616 + outer loop + vertex -454.882 66.7508 296.134 + vertex -449.614 66.4067 293.491 + vertex -447.216 65.7726 294.997 + endloop + endfacet + facet normal -0.133843 -0.971443 -0.195922 + outer loop + vertex -449.614 66.4067 293.491 + vertex -441.458 65.7326 291.261 + vertex -447.216 65.7726 294.997 + endloop + endfacet + facet normal -0.175622 -0.974122 -0.142279 + outer loop + vertex -462.875 67.5 300.132 + vertex -461.088 67.5212 297.78 + vertex -458.471 66.9055 298.765 + endloop + endfacet + facet normal -0.17691 -0.973746 -0.143255 + outer loop + vertex -465.379 68.0704 299.347 + vertex -461.088 67.5212 297.78 + vertex -462.875 67.5 300.132 + endloop + endfacet + facet normal -0.186345 -0.975773 -0.114643 + outer loop + vertex -466.793 68.0806 301.558 + vertex -465.379 68.0704 299.347 + vertex -462.875 67.5 300.132 + endloop + endfacet + facet normal -0.191661 -0.974336 -0.118048 + outer loop + vertex -469.445 68.7198 300.587 + vertex -465.379 68.0704 299.347 + vertex -466.793 68.0806 301.558 + endloop + endfacet + facet normal -0.199356 -0.96898 -0.146063 + outer loop + vertex -465.379 68.0704 299.347 + vertex -469.445 68.7198 300.587 + vertex -465.945 68.3304 298.394 + endloop + endfacet + facet normal -0.181584 -0.970744 -0.157107 + outer loop + vertex -465.379 68.0704 299.347 + vertex -465.945 68.3304 298.394 + vertex -461.088 67.5212 297.78 + endloop + endfacet + facet normal -0.186756 -0.97555 -0.115862 + outer loop + vertex -466.793 68.0806 301.558 + vertex -462.875 67.5 300.132 + vertex -463.699 67.2827 303.29 + endloop + endfacet + facet normal -0.199385 -0.975066 -0.0974256 + outer loop + vertex -470.497 68.6925 303.015 + vertex -469.445 68.7198 300.587 + vertex -466.793 68.0806 301.558 + endloop + endfacet + facet normal -0.198095 -0.975384 -0.0968701 + outer loop + vertex -473.213 69.3279 302.172 + vertex -469.445 68.7198 300.587 + vertex -470.497 68.6925 303.015 + endloop + endfacet + facet normal -0.206158 -0.975917 -0.0713079 + outer loop + vertex -473.961 69.3178 304.471 + vertex -473.213 69.3279 302.172 + vertex -470.497 68.6925 303.015 + endloop + endfacet + facet normal -0.208088 -0.975461 -0.0719336 + outer loop + vertex -476.797 70.001 303.408 + vertex -473.213 69.3279 302.172 + vertex -473.961 69.3178 304.471 + endloop + endfacet + facet normal -0.217491 -0.970746 -0.101738 + outer loop + vertex -473.213 69.3279 302.172 + vertex -476.797 70.001 303.408 + vertex -473.8 69.5734 301.083 + endloop + endfacet + facet normal -0.203197 -0.972946 -0.109944 + outer loop + vertex -473.213 69.3279 302.172 + vertex -473.8 69.5734 301.083 + vertex -469.445 68.7198 300.587 + endloop + endfacet + facet normal -0.205662 -0.976113 -0.0700423 + outer loop + vertex -473.961 69.3178 304.471 + vertex -470.497 68.6925 303.015 + vertex -470.335 68.4294 306.206 + endloop + endfacet + facet normal -0.213861 -0.975235 -0.0563935 + outer loop + vertex -477.101 69.9301 305.79 + vertex -476.797 70.001 303.408 + vertex -473.961 69.3178 304.471 + endloop + endfacet + facet normal -0.210902 -0.9759 -0.0560349 + outer loop + vertex -479.781 70.5606 304.897 + vertex -476.797 70.001 303.408 + vertex -477.101 69.9301 305.79 + endloop + endfacet + facet normal -0.216992 -0.975455 -0.0374431 + outer loop + vertex -479.639 70.4545 306.838 + vertex -479.781 70.5606 304.897 + vertex -477.101 69.9301 305.79 + endloop + endfacet + facet normal -0.216991 -0.975455 -0.0374431 + outer loop + vertex -482.177 71.0605 305.754 + vertex -479.781 70.5606 304.897 + vertex -479.639 70.4545 306.838 + endloop + endfacet + facet normal -0.223613 -0.972987 -0.0573873 + outer loop + vertex -479.781 70.5606 304.897 + vertex -482.177 71.0605 305.754 + vertex -480.356 70.7639 303.688 + endloop + endfacet + facet normal -0.213856 -0.974874 -0.0623414 + outer loop + vertex -479.781 70.5606 304.897 + vertex -480.356 70.7639 303.688 + vertex -476.797 70.001 303.408 + endloop + endfacet + facet normal -0.215561 -0.975907 -0.0337524 + outer loop + vertex -479.639 70.4545 306.838 + vertex -477.101 69.9301 305.79 + vertex -475.857 69.5619 308.488 + endloop + endfacet + facet normal -0.221801 -0.974909 -0.0189056 + outer loop + vertex -478.078 70.0604 308.839 + vertex -479.639 70.4545 306.838 + vertex -475.857 69.5619 308.488 + endloop + endfacet + facet normal -0.220684 -0.975144 -0.0198236 + outer loop + vertex -481.144 70.7778 307.688 + vertex -479.639 70.4545 306.838 + vertex -478.078 70.0604 308.839 + endloop + endfacet + facet normal -0.222699 -0.974602 -0.0235972 + outer loop + vertex -481.144 70.7778 307.688 + vertex -482.177 71.0605 305.754 + vertex -479.639 70.4545 306.838 + endloop + endfacet + facet normal -0.22076 -0.975244 -0.0128463 + outer loop + vertex -485.003 71.6677 306.836 + vertex -483.682 71.3703 306.712 + vertex -482.062 70.9838 308.208 + endloop + endfacet + facet normal -0.224637 -0.974434 -0.00413053 + outer loop + vertex -483.34 71.2789 308.105 + vertex -485.003 71.6677 306.836 + vertex -482.062 70.9838 308.208 + endloop + endfacet + facet normal -0.224578 -0.974354 -0.0141125 + outer loop + vertex -486.183 71.9393 306.866 + vertex -486.619 72.049 306.218 + vertex -485.003 71.6677 306.836 + endloop + endfacet + facet normal -0.253674 -0.965681 0.0557561 + outer loop + vertex -489.091 72.6494 306.048 + vertex -484.953 71.6559 307.668 + vertex -483.551 71.3445 308.654 + endloop + endfacet + facet normal -0.229312 -0.973353 0.000104667 + outer loop + vertex -483.551 71.3445 308.654 + vertex -487.108 72.1823 307.722 + vertex -489.091 72.6494 306.048 + endloop + endfacet + facet normal -0.251916 -0.967327 0.0285669 + outer loop + vertex -487.108 72.1823 307.722 + vertex -488.791 72.6422 308.45 + vertex -489.091 72.6494 306.048 + endloop + endfacet + facet normal -0.246332 -0.968785 0.0278649 + outer loop + vertex -491.826 73.4291 308.984 + vertex -489.091 72.6494 306.048 + vertex -488.791 72.6422 308.45 + endloop + endfacet + facet normal -0.245404 -0.968408 0.0443084 + outer loop + vertex -488.791 72.6422 308.45 + vertex -487.108 72.1823 307.722 + vertex -485.438 71.8165 308.974 + endloop + endfacet + facet normal -0.246783 -0.967537 0.0545039 + outer loop + vertex -485.438 71.8165 308.974 + vertex -487.088 72.2967 310.03 + vertex -488.791 72.6422 308.45 + endloop + endfacet + facet normal -0.255361 -0.9647 0.0643767 + outer loop + vertex -490.416 73.2366 310.911 + vertex -488.791 72.6422 308.45 + vertex -487.088 72.2967 310.03 + endloop + endfacet + facet normal -0.255066 -0.964703 0.0654916 + outer loop + vertex -487.843 72.5953 311.486 + vertex -490.416 73.2366 310.911 + vertex -487.088 72.2967 310.03 + endloop + endfacet + facet normal -0.245714 -0.966756 0.0707635 + outer loop + vertex -487.843 72.5953 311.486 + vertex -487.088 72.2967 310.03 + vertex -483.875 71.6218 311.963 + endloop + endfacet + facet normal -0.24716 -0.965144 0.0860791 + outer loop + vertex -485.1 72.0688 313.46 + vertex -487.843 72.5953 311.486 + vertex -483.875 71.6218 311.963 + endloop + endfacet + facet normal -0.243101 -0.965853 0.0896124 + outer loop + vertex -485.1 72.0688 313.46 + vertex -483.875 71.6218 311.963 + vertex -478.594 70.5668 314.919 + endloop + endfacet + facet normal -0.247248 -0.962511 0.11154 + outer loop + vertex -480.857 71.2798 316.057 + vertex -485.1 72.0688 313.46 + vertex -478.594 70.5668 314.919 + endloop + endfacet + facet normal -0.241385 -0.962572 0.123241 + outer loop + vertex -480.857 71.2798 316.057 + vertex -478.594 70.5668 314.919 + vertex -471.754 69.4128 319.304 + endloop + endfacet + facet normal -0.251197 -0.955472 0.154832 + outer loop + vertex -480.857 71.2798 316.057 + vertex -471.754 69.4128 319.304 + vertex -480.663 71.6068 318.388 + endloop + endfacet + facet normal -0.252915 -0.955006 0.154909 + outer loop + vertex -480.663 71.6068 318.388 + vertex -486.368 72.6051 315.229 + vertex -480.857 71.2798 316.057 + endloop + endfacet + facet normal -0.25291 -0.955009 0.154898 + outer loop + vertex -487.799 73.3241 317.326 + vertex -486.368 72.6051 315.229 + vertex -480.663 71.6068 318.388 + endloop + endfacet + facet normal -0.25825 -0.942907 0.210316 + outer loop + vertex -482.405 72.6685 321.01 + vertex -487.799 73.3241 317.326 + vertex -480.663 71.6068 318.388 + endloop + endfacet + facet normal -0.258012 -0.942935 0.210486 + outer loop + vertex -482.405 72.6685 321.01 + vertex -480.663 71.6068 318.388 + vertex -472.328 70.2821 322.671 + endloop + endfacet + facet normal -0.256883 -0.943758 0.208163 + outer loop + vertex -489.954 74.3925 319.51 + vertex -487.799 73.3241 317.326 + vertex -482.405 72.6685 321.01 + endloop + endfacet + facet normal -0.262159 -0.943471 0.202819 + outer loop + vertex -489.954 74.3925 319.51 + vertex -492.276 74.4633 316.837 + vertex -487.799 73.3241 317.326 + endloop + endfacet + facet normal -0.259596 -0.95277 0.157608 + outer loop + vertex -492.276 74.4633 316.837 + vertex -490.406 73.652 315.014 + vertex -487.799 73.3241 317.326 + endloop + endfacet + facet normal -0.280982 -0.950236 0.13454 + outer loop + vertex -490.406 73.652 315.014 + vertex -492.276 74.4633 316.837 + vertex -492.618 74.2096 314.333 + endloop + endfacet + facet normal -0.272879 -0.956507 0.10311 + outer loop + vertex -490.406 73.652 315.014 + vertex -492.618 74.2096 314.333 + vertex -489.427 73.1607 313.046 + endloop + endfacet + facet normal -0.255 -0.960321 0.112954 + outer loop + vertex -490.406 73.652 315.014 + vertex -489.427 73.1607 313.046 + vertex -486.368 72.6051 315.229 + endloop + endfacet + facet normal -0.253036 -0.961185 0.109981 + outer loop + vertex -486.368 72.6051 315.229 + vertex -489.427 73.1607 313.046 + vertex -485.1 72.0688 313.46 + endloop + endfacet + facet normal -0.251986 -0.948116 0.193855 + outer loop + vertex -493.365 75.1179 318.624 + vertex -492.276 74.4633 316.837 + vertex -489.954 74.3925 319.51 + endloop + endfacet + facet normal -0.264376 -0.929647 0.256635 + outer loop + vertex -492.821 75.6907 321.26 + vertex -493.365 75.1179 318.624 + vertex -489.954 74.3925 319.51 + endloop + endfacet + facet normal -0.257923 -0.928684 0.266498 + outer loop + vertex -485.519 74.4765 324.096 + vertex -492.821 75.6907 321.26 + vertex -489.954 74.3925 319.51 + endloop + endfacet + facet normal -0.265497 -0.924432 0.273746 + outer loop + vertex -482.405 72.6685 321.01 + vertex -485.519 74.4765 324.096 + vertex -489.954 74.3925 319.51 + endloop + endfacet + facet normal -0.264373 -0.92442 0.274873 + outer loop + vertex -485.519 74.4765 324.096 + vertex -482.405 72.6685 321.01 + vertex -474.465 71.7668 325.614 + endloop + endfacet + facet normal -0.264226 -0.924544 0.274595 + outer loop + vertex -474.465 71.7668 325.614 + vertex -482.405 72.6685 321.01 + vertex -472.328 70.2821 322.671 + endloop + endfacet + facet normal -0.262173 -0.924666 0.276147 + outer loop + vertex -474.465 71.7668 325.614 + vertex -472.328 70.2821 322.671 + vertex -463.006 69.0869 327.52 + endloop + endfacet + facet normal -0.265793 -0.921265 0.283945 + outer loop + vertex -463.006 69.0869 327.52 + vertex -472.328 70.2821 322.671 + vertex -461.004 67.6472 324.722 + endloop + endfacet + facet normal -0.258578 -0.92165 0.289307 + outer loop + vertex -463.006 69.0869 327.52 + vertex -461.004 67.6472 324.722 + vertex -451.557 66.5001 329.512 + endloop + endfacet + facet normal -0.265951 -0.914257 0.305622 + outer loop + vertex -451.557 66.5001 329.512 + vertex -461.004 67.6472 324.722 + vertex -449.447 65.0344 326.964 + endloop + endfacet + facet normal -0.252939 -0.91428 0.316407 + outer loop + vertex -451.557 66.5001 329.512 + vertex -449.447 65.0344 326.964 + vertex -440.397 64.0516 331.358 + endloop + endfacet + facet normal -0.259797 -0.906717 0.33222 + outer loop + vertex -440.397 64.0516 331.358 + vertex -449.447 65.0344 326.964 + vertex -438.422 62.6005 328.942 + endloop + endfacet + facet normal -0.242882 -0.906324 0.34581 + outer loop + vertex -440.397 64.0516 331.358 + vertex -438.422 62.6005 328.942 + vertex -429.494 61.7313 332.935 + endloop + endfacet + facet normal -0.249917 -0.897458 0.363472 + outer loop + vertex -429.494 61.7313 332.935 + vertex -438.422 62.6005 328.942 + vertex -427.731 60.2977 330.607 + endloop + endfacet + facet normal -0.237121 -0.897056 0.372913 + outer loop + vertex -429.494 61.7313 332.935 + vertex -427.731 60.2977 330.607 + vertex -419.011 59.4856 334.199 + endloop + endfacet + facet normal -0.241072 -0.8914 0.383785 + outer loop + vertex -419.011 59.4856 334.199 + vertex -427.731 60.2977 330.607 + vertex -417.432 58.0889 331.946 + endloop + endfacet + facet normal -0.233944 -0.891191 0.38865 + outer loop + vertex -419.011 59.4856 334.199 + vertex -417.432 58.0889 331.946 + vertex -409.748 57.418 335.033 + endloop + endfacet + facet normal -0.236201 -0.887794 0.395006 + outer loop + vertex -409.748 57.418 335.033 + vertex -417.432 58.0889 331.946 + vertex -408.203 56.044 332.868 + endloop + endfacet + facet normal -0.232504 -0.887637 0.397545 + outer loop + vertex -409.748 57.418 335.033 + vertex -408.203 56.044 332.868 + vertex -402.763 55.7266 335.341 + endloop + endfacet + facet normal -0.230019 -0.890896 0.391659 + outer loop + vertex -402.763 55.7266 335.341 + vertex -408.203 56.044 332.868 + vertex -401.232 54.4059 333.237 + endloop + endfacet + facet normal -0.231204 -0.890952 0.390832 + outer loop + vertex -402.763 55.7266 335.341 + vertex -401.232 54.4059 333.237 + vertex -398.694 54.5913 335.161 + endloop + endfacet + facet normal -0.325542 -0.907773 0.264519 + outer loop + vertex -492.821 75.6907 321.26 + vertex -494.615 75.4824 318.337 + vertex -493.365 75.1179 318.624 + endloop + endfacet + facet normal -0.286693 -0.926944 0.242039 + outer loop + vertex -495.82 77.0016 322.727 + vertex -494.615 75.4824 318.337 + vertex -492.821 75.6907 321.26 + endloop + endfacet + facet normal -0.229941 -0.937478 0.261269 + outer loop + vertex -494.615 75.4824 318.337 + vertex -495.82 77.0016 322.727 + vertex -497.403 76.6627 320.118 + endloop + endfacet + facet normal -0.309348 -0.93819 0.155253 + outer loop + vertex -493.365 75.1179 318.624 + vertex -494.615 75.4824 318.337 + vertex -492.276 74.4633 316.837 + endloop + endfacet + facet normal -0.255645 -0.954604 0.152892 + outer loop + vertex -487.799 73.3241 317.326 + vertex -490.406 73.652 315.014 + vertex -486.368 72.6051 315.229 + endloop + endfacet + facet normal -0.253652 -0.946182 0.200997 + outer loop + vertex -471.754 69.4128 319.304 + vertex -472.328 70.2821 322.671 + vertex -480.663 71.6068 318.388 + endloop + endfacet + facet normal -0.256319 -0.945592 0.20039 + outer loop + vertex -472.328 70.2821 322.671 + vertex -471.754 69.4128 319.304 + vertex -461.004 67.6472 324.722 + endloop + endfacet + facet normal -0.26191 -0.941323 0.212873 + outer loop + vertex -461.004 67.6472 324.722 + vertex -471.754 69.4128 319.304 + vertex -459.122 66.5368 322.127 + endloop + endfacet + facet normal -0.255229 -0.941985 0.217999 + outer loop + vertex -461.004 67.6472 324.722 + vertex -459.122 66.5368 322.127 + vertex -449.447 65.0344 326.964 + endloop + endfacet + facet normal -0.263196 -0.935438 0.235973 + outer loop + vertex -449.447 65.0344 326.964 + vertex -459.122 66.5368 322.127 + vertex -447.459 63.8975 324.674 + endloop + endfacet + facet normal -0.250945 -0.935989 0.246883 + outer loop + vertex -449.447 65.0344 326.964 + vertex -447.459 63.8975 324.674 + vertex -438.422 62.6005 328.942 + endloop + endfacet + facet normal -0.257029 -0.930358 0.261477 + outer loop + vertex -438.422 62.6005 328.942 + vertex -447.459 63.8975 324.674 + vertex -436.623 61.4939 326.774 + endloop + endfacet + facet normal -0.243037 -0.930727 0.273277 + outer loop + vertex -438.422 62.6005 328.942 + vertex -436.623 61.4939 326.774 + vertex -427.731 60.2977 330.607 + endloop + endfacet + facet normal -0.248032 -0.925411 0.286522 + outer loop + vertex -427.731 60.2977 330.607 + vertex -436.623 61.4939 326.774 + vertex -426.114 59.2185 328.521 + endloop + endfacet + facet normal -0.236891 -0.925586 0.29525 + outer loop + vertex -427.731 60.2977 330.607 + vertex -426.114 59.2185 328.521 + vertex -417.432 58.0889 331.946 + endloop + endfacet + facet normal -0.241597 -0.919839 0.309075 + outer loop + vertex -417.432 58.0889 331.946 + vertex -426.114 59.2185 328.521 + vertex -415.868 57.008 329.952 + endloop + endfacet + facet normal -0.235204 -0.919804 0.314071 + outer loop + vertex -417.432 58.0889 331.946 + vertex -415.868 57.008 329.952 + vertex -408.203 56.044 332.868 + endloop + endfacet + facet normal -0.236643 -0.917918 0.318475 + outer loop + vertex -408.203 56.044 332.868 + vertex -415.868 57.008 329.952 + vertex -406.643 54.9757 330.949 + endloop + endfacet + facet normal -0.232649 -0.917825 0.321671 + outer loop + vertex -408.203 56.044 332.868 + vertex -406.643 54.9757 330.949 + vertex -401.232 54.4059 333.237 + endloop + endfacet + facet normal -0.231477 -0.919207 0.318555 + outer loop + vertex -401.232 54.4059 333.237 + vertex -406.643 54.9757 330.949 + vertex -399.601 53.3481 331.37 + endloop + endfacet + facet normal -0.230641 -0.91917 0.319266 + outer loop + vertex -401.232 54.4059 333.237 + vertex -399.601 53.3481 331.37 + vertex -397.044 53.3045 333.091 + endloop + endfacet + facet normal -0.251632 -0.957564 0.140545 + outer loop + vertex -469.655 68.4904 316.778 + vertex -471.754 69.4128 319.304 + vertex -478.594 70.5668 314.919 + endloop + endfacet + facet normal -0.244453 -0.964691 0.0980508 + outer loop + vertex -478.426 70.3528 313.234 + vertex -469.655 68.4904 316.778 + vertex -478.594 70.5668 314.919 + endloop + endfacet + facet normal -0.24238 -0.965776 0.0923472 + outer loop + vertex -478.426 70.3528 313.234 + vertex -475.64 69.6322 313.01 + vertex -469.655 68.4904 316.778 + endloop + endfacet + facet normal -0.249941 -0.962513 0.105348 + outer loop + vertex -467 67.6639 315.525 + vertex -469.655 68.4904 316.778 + vertex -475.64 69.6322 313.01 + endloop + endfacet + facet normal -0.243484 -0.966603 0.0799649 + outer loop + vertex -474.6 69.3309 312.535 + vertex -467 67.6639 315.525 + vertex -475.64 69.6322 313.01 + endloop + endfacet + facet normal -0.245731 -0.966438 0.0749312 + outer loop + vertex -475.64 69.6322 313.01 + vertex -479.865 70.5257 310.676 + vertex -474.6 69.3309 312.535 + endloop + endfacet + facet normal -0.23913 -0.969469 0.0542879 + outer loop + vertex -474.6 69.3309 312.535 + vertex -479.865 70.5257 310.676 + vertex -474.667 69.3149 311.95 + endloop + endfacet + facet normal -0.23473 -0.97145 0.0344498 + outer loop + vertex -479.865 70.5257 310.676 + vertex -483.551 71.3445 308.654 + vertex -474.667 69.3149 311.95 + endloop + endfacet + facet normal -0.242629 -0.968407 0.0576103 + outer loop + vertex -480.754 70.689 309.415 + vertex -474.667 69.3149 311.95 + vertex -483.551 71.3445 308.654 + endloop + endfacet + facet normal -0.236429 -0.970915 0.037762 + outer loop + vertex -479.865 70.5257 310.676 + vertex -485.438 71.8165 308.974 + vertex -483.551 71.3445 308.654 + endloop + endfacet + facet normal -0.241462 -0.968802 0.0558464 + outer loop + vertex -482.352 71.1589 310.912 + vertex -485.438 71.8165 308.974 + vertex -479.865 70.5257 310.676 + endloop + endfacet + facet normal -0.240535 -0.968479 0.0647412 + outer loop + vertex -482.352 71.1589 310.912 + vertex -479.865 70.5257 310.676 + vertex -475.64 69.6322 313.01 + endloop + endfacet + facet normal -0.234072 -0.970733 0.0537353 + outer loop + vertex -474.6 69.3309 312.535 + vertex -474.667 69.3149 311.95 + vertex -467 67.6639 315.525 + endloop + endfacet + facet normal -0.248417 -0.964713 0.087284 + outer loop + vertex -467 67.6639 315.525 + vertex -474.667 69.3149 311.95 + vertex -462.826 66.6242 315.913 + endloop + endfacet + facet normal -0.249786 -0.962169 0.108804 + outer loop + vertex -467 67.6639 315.525 + vertex -462.826 66.6242 315.913 + vertex -454.409 64.8138 319.228 + endloop + endfacet + facet normal -0.254458 -0.958656 0.127397 + outer loop + vertex -456.988 65.624 320.172 + vertex -467 67.6639 315.525 + vertex -454.409 64.8138 319.228 + endloop + endfacet + facet normal -0.250118 -0.958207 0.138858 + outer loop + vertex -456.988 65.624 320.172 + vertex -454.409 64.8138 319.228 + vertex -445.514 63.0278 322.924 + endloop + endfacet + facet normal -0.251356 -0.957387 0.142232 + outer loop + vertex -445.514 63.0278 322.924 + vertex -454.409 64.8138 319.228 + vertex -443.384 62.3284 321.982 + endloop + endfacet + facet normal -0.244514 -0.956808 0.157261 + outer loop + vertex -445.514 63.0278 322.924 + vertex -443.384 62.3284 321.982 + vertex -434.905 60.6756 325.109 + endloop + endfacet + facet normal -0.246548 -0.95522 0.163615 + outer loop + vertex -434.905 60.6756 325.109 + vertex -443.384 62.3284 321.982 + vertex -432.94 60.0115 324.193 + endloop + endfacet + facet normal -0.239152 -0.954367 0.178857 + outer loop + vertex -434.905 60.6756 325.109 + vertex -432.94 60.0115 324.193 + vertex -424.457 58.4004 326.938 + endloop + endfacet + facet normal -0.242085 -0.951556 0.189568 + outer loop + vertex -424.457 58.4004 326.938 + vertex -432.94 60.0115 324.193 + vertex -422.414 57.7115 326.09 + endloop + endfacet + facet normal -0.235784 -0.950225 0.203664 + outer loop + vertex -424.457 58.4004 326.938 + vertex -422.414 57.7115 326.09 + vertex -414.176 56.1737 328.452 + endloop + endfacet + facet normal -0.238001 -0.947598 0.213105 + outer loop + vertex -414.176 56.1737 328.452 + vertex -422.414 57.7115 326.09 + vertex -412.131 55.4805 327.653 + endloop + endfacet + facet normal -0.233538 -0.946331 0.223421 + outer loop + vertex -414.176 56.1737 328.452 + vertex -412.131 55.4805 327.653 + vertex -404.997 54.1574 329.506 + endloop + endfacet + facet normal -0.234314 -0.945242 0.227187 + outer loop + vertex -404.997 54.1574 329.506 + vertex -412.131 55.4805 327.653 + vertex -403.401 53.5678 328.699 + endloop + endfacet + facet normal -0.230321 -0.944439 0.234495 + outer loop + vertex -404.997 54.1574 329.506 + vertex -403.401 53.5678 328.699 + vertex -398.354 52.6337 329.894 + endloop + endfacet + facet normal -0.22994 -0.945046 0.232412 + outer loop + vertex -398.354 52.6337 329.894 + vertex -403.401 53.5678 328.699 + vertex -398.089 52.3727 329.095 + endloop + endfacet + facet normal -0.210448 -0.94775 0.239753 + outer loop + vertex -398.354 52.6337 329.894 + vertex -398.089 52.3727 329.095 + vertex -395.349 51.7985 329.23 + endloop + endfacet + facet normal -0.213298 -0.949696 0.229307 + outer loop + vertex -395.349 51.7985 329.23 + vertex -395.548 52.3116 331.17 + vertex -398.354 52.6337 329.894 + endloop + endfacet + facet normal -0.210472 -0.950194 0.229856 + outer loop + vertex -398.089 52.3727 329.095 + vertex -397.561 52.1931 328.836 + vertex -395.349 51.7985 329.23 + endloop + endfacet + facet normal -0.168718 -0.984885 -0.0391832 + outer loop + vertex -399.859 52.6165 328.087 + vertex -395.349 51.7985 329.23 + vertex -397.561 52.1931 328.836 + endloop + endfacet + facet normal -0.203305 -0.973409 0.105554 + outer loop + vertex -396.315 51.7358 326.793 + vertex -395.349 51.7985 329.23 + vertex -399.859 52.6165 328.087 + endloop + endfacet + facet normal -0.213767 -0.97383 0.0772 + outer loop + vertex -396.315 51.7358 326.793 + vertex -399.859 52.6165 328.087 + vertex -404.655 53.5457 326.529 + endloop + endfacet + facet normal -0.21325 -0.975878 0.0467678 + outer loop + vertex -404.655 53.5457 326.529 + vertex -403.414 53.2089 325.158 + vertex -396.315 51.7358 326.793 + endloop + endfacet + facet normal -0.218434 -0.974954 0.0418514 + outer loop + vertex -404.655 53.5457 326.529 + vertex -411.494 54.983 324.315 + vertex -403.414 53.2089 325.158 + endloop + endfacet + facet normal -0.21905 -0.974725 0.0439008 + outer loop + vertex -414.076 55.6169 325.506 + vertex -411.494 54.983 324.315 + vertex -404.655 53.5457 326.529 + endloop + endfacet + facet normal -0.222374 -0.971606 0.08082 + outer loop + vertex -407.204 54.189 327.25 + vertex -414.076 55.6169 325.506 + vertex -404.655 53.5457 326.529 + endloop + endfacet + facet normal -0.225118 -0.969878 0.0930526 + outer loop + vertex -416.749 56.2869 326.023 + vertex -414.076 55.6169 325.506 + vertex -407.204 54.189 327.25 + endloop + endfacet + facet normal -0.229184 -0.964015 0.134723 + outer loop + vertex -416.749 56.2869 326.023 + vertex -407.204 54.189 327.25 + vertex -408.501 54.5299 327.482 + endloop + endfacet + facet normal -0.22754 -0.965958 0.123088 + outer loop + vertex -408.501 54.5299 327.482 + vertex -415.032 55.959 326.624 + vertex -416.749 56.2869 326.023 + endloop + endfacet + facet normal -0.230438 -0.964036 0.132416 + outer loop + vertex -415.032 55.959 326.624 + vertex -421.234 57.3008 325.599 + vertex -416.749 56.2869 326.023 + endloop + endfacet + facet normal -0.226537 -0.971184 0.0740455 + outer loop + vertex -428.052 58.7733 324.056 + vertex -416.749 56.2869 326.023 + vertex -421.234 57.3008 325.599 + endloop + endfacet + facet normal -0.227387 -0.970651 0.0783084 + outer loop + vertex -421.234 57.3008 325.599 + vertex -426.494 58.4601 324.695 + vertex -428.052 58.7733 324.056 + endloop + endfacet + facet normal -0.230772 -0.969081 0.0873287 + outer loop + vertex -426.494 58.4601 324.695 + vertex -432.334 59.743 323.5 + vertex -428.052 58.7733 324.056 + endloop + endfacet + facet normal -0.226487 -0.972842 0.0477661 + outer loop + vertex -438.928 61.1925 321.754 + vertex -428.052 58.7733 324.056 + vertex -432.334 59.743 323.5 + endloop + endfacet + facet normal -0.228526 -0.971912 0.0562408 + outer loop + vertex -432.334 59.743 323.5 + vertex -437.204 60.8306 322.506 + vertex -438.928 61.1925 321.754 + endloop + endfacet + facet normal -0.231858 -0.970608 0.064512 + outer loop + vertex -437.204 60.8306 322.506 + vertex -442.826 62.084 321.16 + vertex -438.928 61.1925 321.754 + endloop + endfacet + facet normal -0.22908 -0.972433 0.0435517 + outer loop + vertex -449.378 63.5407 319.222 + vertex -438.928 61.1925 321.754 + vertex -442.826 62.084 321.16 + endloop + endfacet + facet normal -0.231461 -0.971434 0.0523518 + outer loop + vertex -442.826 62.084 321.16 + vertex -447.511 63.1414 320.064 + vertex -449.378 63.5407 319.222 + endloop + endfacet + facet normal -0.247348 -0.959983 0.131344 + outer loop + vertex -447.511 63.1414 320.064 + vertex -442.826 62.084 321.16 + vertex -440.921 61.6857 321.837 + endloop + endfacet + facet normal -0.255513 -0.952059 0.168216 + outer loop + vertex -440.921 61.6857 321.837 + vertex -451.339 64.0272 319.264 + vertex -447.511 63.1414 320.064 + endloop + endfacet + facet normal -0.244436 -0.964322 0.101653 + outer loop + vertex -453.029 64.3827 318.572 + vertex -447.511 63.1414 320.064 + vertex -451.339 64.0272 319.264 + endloop + endfacet + facet normal -0.244558 -0.962913 0.11397 + outer loop + vertex -443.384 62.3284 321.982 + vertex -451.339 64.0272 319.264 + vertex -440.921 61.6857 321.837 + endloop + endfacet + facet normal -0.229236 -0.972364 0.0442575 + outer loop + vertex -449.378 63.5407 319.222 + vertex -446.777 62.9107 318.854 + vertex -438.928 61.1925 321.754 + endloop + endfacet + facet normal -0.22876 -0.972539 0.0428661 + outer loop + vertex -438.928 61.1925 321.754 + vertex -446.777 62.9107 318.854 + vertex -435.829 60.4504 321.457 + endloop + endfacet + facet normal -0.22142 -0.975132 0.00953697 + outer loop + vertex -446.777 62.9107 318.854 + vertex -443.844 62.233 317.638 + vertex -435.829 60.4504 321.457 + endloop + endfacet + facet normal -0.223162 -0.974689 0.0133998 + outer loop + vertex -435.829 60.4504 321.457 + vertex -443.844 62.233 317.638 + vertex -432.622 59.7015 320.399 + endloop + endfacet + facet normal -0.221391 -0.975 0.0189867 + outer loop + vertex -435.829 60.4504 321.457 + vertex -432.622 59.7015 320.399 + vertex -424.755 57.9809 323.769 + endloop + endfacet + facet normal -0.228645 -0.971833 0.0571113 + outer loop + vertex -428.052 58.7733 324.056 + vertex -435.829 60.4504 321.457 + vertex -424.755 57.9809 323.769 + endloop + endfacet + facet normal -0.223507 -0.974401 0.024231 + outer loop + vertex -424.755 57.9809 323.769 + vertex -432.622 59.7015 320.399 + vertex -421.737 57.2613 322.67 + endloop + endfacet + facet normal -0.220923 -0.97478 0.0315771 + outer loop + vertex -424.755 57.9809 323.769 + vertex -421.737 57.2613 322.67 + vertex -414.076 55.6169 325.506 + endloop + endfacet + facet normal -0.222118 -0.974989 0.00777428 + outer loop + vertex -446.777 62.9107 318.854 + vertex -455.425 64.8475 314.657 + vertex -443.844 62.233 317.638 + endloop + endfacet + facet normal -0.223134 -0.974737 0.00998385 + outer loop + vertex -456.946 65.2123 316.276 + vertex -455.425 64.8475 314.657 + vertex -446.777 62.9107 318.854 + endloop + endfacet + facet normal -0.242457 -0.963245 0.115649 + outer loop + vertex -442.826 62.084 321.16 + vertex -437.204 60.8306 322.506 + vertex -440.921 61.6857 321.837 + endloop + endfacet + facet normal -0.258027 -0.936924 0.235785 + outer loop + vertex -430.473 59.367 324.056 + vertex -440.921 61.6857 321.837 + vertex -437.204 60.8306 322.506 + endloop + endfacet + facet normal -0.242952 -0.959737 0.140991 + outer loop + vertex -432.94 60.0115 324.193 + vertex -440.921 61.6857 321.837 + vertex -430.473 59.367 324.056 + endloop + endfacet + facet normal -0.253981 -0.943736 0.211791 + outer loop + vertex -437.204 60.8306 322.506 + vertex -432.334 59.743 323.5 + vertex -430.473 59.367 324.056 + endloop + endfacet + facet normal -0.22764 -0.972256 0.0538323 + outer loop + vertex -438.928 61.1925 321.754 + vertex -435.829 60.4504 321.457 + vertex -428.052 58.7733 324.056 + endloop + endfacet + facet normal -0.245821 -0.952756 0.178404 + outer loop + vertex -432.334 59.743 323.5 + vertex -426.494 58.4601 324.695 + vertex -430.473 59.367 324.056 + endloop + endfacet + facet normal -0.264305 -0.877037 0.401185 + outer loop + vertex -419.69 57.0077 326.003 + vertex -430.473 59.367 324.056 + vertex -426.494 58.4601 324.695 + endloop + endfacet + facet normal -0.24084 -0.954155 0.177717 + outer loop + vertex -422.414 57.7115 326.09 + vertex -430.473 59.367 324.056 + vertex -419.69 57.0077 326.003 + endloop + endfacet + facet normal -0.255504 -0.91444 0.313874 + outer loop + vertex -426.494 58.4601 324.695 + vertex -421.234 57.3008 325.599 + vertex -419.69 57.0077 326.003 + endloop + endfacet + facet normal -0.226807 -0.970981 0.075857 + outer loop + vertex -428.052 58.7733 324.056 + vertex -424.755 57.9809 323.769 + vertex -416.749 56.2869 326.023 + endloop + endfacet + facet normal -0.24491 -0.934344 0.258881 + outer loop + vertex -421.234 57.3008 325.599 + vertex -415.032 55.959 326.624 + vertex -419.69 57.0077 326.003 + endloop + endfacet + facet normal -0.252127 -0.875248 0.412763 + outer loop + vertex -409.727 54.8482 327.509 + vertex -419.69 57.0077 326.003 + vertex -415.032 55.959 326.624 + endloop + endfacet + facet normal -0.23713 -0.94898 0.207861 + outer loop + vertex -412.131 55.4805 327.653 + vertex -419.69 57.0077 326.003 + vertex -409.727 54.8482 327.509 + endloop + endfacet + facet normal -0.238166 -0.938617 0.24955 + outer loop + vertex -415.032 55.959 326.624 + vertex -408.501 54.5299 327.482 + vertex -409.727 54.8482 327.509 + endloop + endfacet + facet normal -0.227811 -0.970427 0.0798368 + outer loop + vertex -416.749 56.2869 326.023 + vertex -424.755 57.9809 323.769 + vertex -414.076 55.6169 325.506 + endloop + endfacet + facet normal -0.222508 -0.97426 0.0361597 + outer loop + vertex -414.076 55.6169 325.506 + vertex -421.737 57.2613 322.67 + vertex -411.494 54.983 324.315 + endloop + endfacet + facet normal -0.218645 -0.971292 0.0937326 + outer loop + vertex -407.204 54.189 327.25 + vertex -404.655 53.5457 326.529 + vertex -399.859 52.6165 328.087 + endloop + endfacet + facet normal -0.218565 -0.971397 0.0928315 + outer loop + vertex -399.859 52.6165 328.087 + vertex -403.488 53.4278 328.033 + vertex -407.204 54.189 327.25 + endloop + endfacet + facet normal -0.227483 -0.963215 0.143067 + outer loop + vertex -403.488 53.4278 328.033 + vertex -408.501 54.5299 327.482 + vertex -407.204 54.189 327.25 + endloop + endfacet + facet normal -0.234364 -0.937643 0.256709 + outer loop + vertex -408.501 54.5299 327.482 + vertex -403.488 53.4278 328.033 + vertex -401.973 53.1449 328.382 + endloop + endfacet + facet normal -0.235791 -0.931756 0.276102 + outer loop + vertex -401.973 53.1449 328.382 + vertex -409.727 54.8482 327.509 + vertex -408.501 54.5299 327.482 + endloop + endfacet + facet normal -0.232711 -0.948018 0.217043 + outer loop + vertex -403.401 53.5678 328.699 + vertex -409.727 54.8482 327.509 + vertex -401.973 53.1449 328.382 + endloop + endfacet + facet normal -0.217565 -0.962173 0.163979 + outer loop + vertex -403.488 53.4278 328.033 + vertex -399.859 52.6165 328.087 + vertex -401.973 53.1449 328.382 + endloop + endfacet + facet normal -0.226197 -0.953332 0.199981 + outer loop + vertex -398.089 52.3727 329.095 + vertex -401.973 53.1449 328.382 + vertex -397.561 52.1931 328.836 + endloop + endfacet + facet normal -0.229849 -0.946243 0.227582 + outer loop + vertex -403.401 53.5678 328.699 + vertex -401.973 53.1449 328.382 + vertex -398.089 52.3727 329.095 + endloop + endfacet + facet normal -0.234538 -0.944328 0.23073 + outer loop + vertex -412.131 55.4805 327.653 + vertex -409.727 54.8482 327.509 + vertex -403.401 53.5678 328.699 + endloop + endfacet + facet normal -0.238009 -0.947578 0.213183 + outer loop + vertex -422.414 57.7115 326.09 + vertex -419.69 57.0077 326.003 + vertex -412.131 55.4805 327.653 + endloop + endfacet + facet normal -0.239963 -0.955167 0.173417 + outer loop + vertex -432.94 60.0115 324.193 + vertex -430.473 59.367 324.056 + vertex -422.414 57.7115 326.09 + endloop + endfacet + facet normal -0.242392 -0.960203 0.138766 + outer loop + vertex -443.384 62.3284 321.982 + vertex -440.921 61.6857 321.837 + vertex -432.94 60.0115 324.193 + endloop + endfacet + facet normal -0.247678 -0.960821 0.124412 + outer loop + vertex -454.409 64.8138 319.228 + vertex -451.339 64.0272 319.264 + vertex -443.384 62.3284 321.982 + endloop + endfacet + facet normal -0.248034 -0.963174 0.103807 + outer loop + vertex -454.409 64.8138 319.228 + vertex -462.826 66.6242 315.913 + vertex -451.339 64.0272 319.264 + endloop + endfacet + facet normal -0.276487 -0.934688 0.223413 + outer loop + vertex -451.339 64.0272 319.264 + vertex -462.826 66.6242 315.913 + vertex -457.466 65.3906 317.385 + endloop + endfacet + facet normal -0.269891 -0.949166 0.161996 + outer loop + vertex -462.826 66.6242 315.913 + vertex -474.667 69.3149 311.95 + vertex -469.706 68.1685 313.5 + endloop + endfacet + facet normal -0.247467 -0.96256 0.110623 + outer loop + vertex -469.655 68.4904 316.778 + vertex -467 67.6639 315.525 + vertex -456.988 65.624 320.172 + endloop + endfacet + facet normal -0.243891 -0.966762 0.0767312 + outer loop + vertex -478.426 70.3528 313.234 + vertex -482.352 71.1589 310.912 + vertex -475.64 69.6322 313.01 + endloop + endfacet + facet normal -0.242562 -0.967286 0.0743018 + outer loop + vertex -483.875 71.6218 311.963 + vertex -482.352 71.1589 310.912 + vertex -478.426 70.3528 313.234 + endloop + endfacet + facet normal -0.249845 -0.9578 0.142117 + outer loop + vertex -471.754 69.4128 319.304 + vertex -469.655 68.4904 316.778 + vertex -459.122 66.5368 322.127 + endloop + endfacet + facet normal -0.258887 -0.952234 0.161951 + outer loop + vertex -459.122 66.5368 322.127 + vertex -469.655 68.4904 316.778 + vertex -456.988 65.624 320.172 + endloop + endfacet + facet normal -0.252508 -0.952698 0.169133 + outer loop + vertex -459.122 66.5368 322.127 + vertex -456.988 65.624 320.172 + vertex -447.459 63.8975 324.674 + endloop + endfacet + facet normal -0.258673 -0.948304 0.183869 + outer loop + vertex -447.459 63.8975 324.674 + vertex -456.988 65.624 320.172 + vertex -445.514 63.0278 322.924 + endloop + endfacet + facet normal -0.248333 -0.948726 0.195576 + outer loop + vertex -447.459 63.8975 324.674 + vertex -445.514 63.0278 322.924 + vertex -436.623 61.4939 326.774 + endloop + endfacet + facet normal -0.251899 -0.945796 0.204981 + outer loop + vertex -436.623 61.4939 326.774 + vertex -445.514 63.0278 322.924 + vertex -434.905 60.6756 325.109 + endloop + endfacet + facet normal -0.24087 -0.9461 0.216511 + outer loop + vertex -436.623 61.4939 326.774 + vertex -434.905 60.6756 325.109 + vertex -426.114 59.2185 328.521 + endloop + endfacet + facet normal -0.245345 -0.941786 0.22988 + outer loop + vertex -426.114 59.2185 328.521 + vertex -434.905 60.6756 325.109 + vertex -424.457 58.4004 326.938 + endloop + endfacet + facet normal -0.23655 -0.941749 0.239068 + outer loop + vertex -426.114 59.2185 328.521 + vertex -424.457 58.4004 326.938 + vertex -415.868 57.008 329.952 + endloop + endfacet + facet normal -0.24004 -0.937795 0.25084 + outer loop + vertex -415.868 57.008 329.952 + vertex -424.457 58.4004 326.938 + vertex -414.176 56.1737 328.452 + endloop + endfacet + facet normal -0.234332 -0.937534 0.257137 + outer loop + vertex -415.868 57.008 329.952 + vertex -414.176 56.1737 328.452 + vertex -406.643 54.9757 330.949 + endloop + endfacet + facet normal -0.235663 -0.935866 0.261952 + outer loop + vertex -406.643 54.9757 330.949 + vertex -414.176 56.1737 328.452 + vertex -404.997 54.1574 329.506 + endloop + endfacet + facet normal -0.232131 -0.935648 0.265854 + outer loop + vertex -406.643 54.9757 330.949 + vertex -404.997 54.1574 329.506 + vertex -399.601 53.3481 331.37 + endloop + endfacet + facet normal -0.230278 -0.937882 0.259518 + outer loop + vertex -399.601 53.3481 331.37 + vertex -404.997 54.1574 329.506 + vertex -398.354 52.6337 329.894 + endloop + endfacet + facet normal -0.226962 -0.937907 0.262333 + outer loop + vertex -399.601 53.3481 331.37 + vertex -398.354 52.6337 329.894 + vertex -395.548 52.3116 331.17 + endloop + endfacet + facet normal -0.248385 -0.961982 0.113556 + outer loop + vertex -486.368 72.6051 315.229 + vertex -485.1 72.0688 313.46 + vertex -480.857 71.2798 316.057 + endloop + endfacet + facet normal -0.247253 -0.964014 0.0976855 + outer loop + vertex -478.594 70.5668 314.919 + vertex -483.875 71.6218 311.963 + vertex -478.426 70.3528 313.234 + endloop + endfacet + facet normal -0.251956 -0.963235 0.0932531 + outer loop + vertex -489.427 73.1607 313.046 + vertex -487.843 72.5953 311.486 + vertex -485.1 72.0688 313.46 + endloop + endfacet + facet normal -0.245343 -0.966899 0.0700978 + outer loop + vertex -483.875 71.6218 311.963 + vertex -487.088 72.2967 310.03 + vertex -482.352 71.1589 310.912 + endloop + endfacet + facet normal -0.258937 -0.962081 0.085747 + outer loop + vertex -487.843 72.5953 311.486 + vertex -489.427 73.1607 313.046 + vertex -490.416 73.2366 310.911 + endloop + endfacet + facet normal -0.24366 -0.968027 0.0596098 + outer loop + vertex -487.088 72.2967 310.03 + vertex -485.438 71.8165 308.974 + vertex -482.352 71.1589 310.912 + endloop + endfacet + facet normal -0.237276 -0.97089 0.0327436 + outer loop + vertex -485.438 71.8165 308.974 + vertex -487.108 72.1823 307.722 + vertex -483.551 71.3445 308.654 + endloop + endfacet + facet normal -0.224371 -0.974493 -0.00449763 + outer loop + vertex -486.183 71.9393 306.866 + vertex -485.003 71.6677 306.836 + vertex -483.34 71.2789 308.105 + endloop + endfacet + facet normal -0.235193 -0.971557 0.0275914 + outer loop + vertex -484.953 71.6559 307.668 + vertex -480.754 70.689 309.415 + vertex -483.551 71.3445 308.654 + endloop + endfacet + facet normal -0.225266 -0.974289 0.00404549 + outer loop + vertex -483.34 71.2789 308.105 + vertex -482.062 70.9838 308.208 + vertex -478.25 70.1106 310.187 + endloop + endfacet + facet normal -0.265612 -0.956689 0.119153 + outer loop + vertex -480.754 70.689 309.415 + vertex -477.262 69.8904 310.787 + vertex -474.667 69.3149 311.95 + endloop + endfacet + facet normal -0.248143 -0.965763 0.0756789 + outer loop + vertex -477.262 69.8904 310.787 + vertex -474.183 69.1858 311.892 + vertex -474.667 69.3149 311.95 + endloop + endfacet + facet normal -0.229264 -0.973195 0.0181762 + outer loop + vertex -478.25 70.1106 310.187 + vertex -477.603 69.9529 309.901 + vertex -470.037 68.2296 313.062 + endloop + endfacet + facet normal -0.247725 -0.965615 0.0788707 + outer loop + vertex -474.183 69.1858 311.892 + vertex -469.706 68.1685 313.5 + vertex -474.667 69.3149 311.95 + endloop + endfacet + facet normal -0.289844 -0.928506 0.232093 + outer loop + vertex -469.706 68.1685 313.5 + vertex -466.575 67.4544 314.552 + vertex -462.826 66.6242 315.913 + endloop + endfacet + facet normal -0.256862 -0.958607 0.122862 + outer loop + vertex -466.575 67.4544 314.552 + vertex -463.922 66.8499 315.382 + vertex -462.826 66.6242 315.913 + endloop + endfacet + facet normal -0.257585 -0.958198 0.124528 + outer loop + vertex -463.922 66.8499 315.382 + vertex -460.868 66.1587 316.382 + vertex -462.826 66.6242 315.913 + endloop + endfacet + facet normal -0.271902 -0.94101 0.20142 + outer loop + vertex -460.868 66.1587 316.382 + vertex -457.466 65.3906 317.385 + vertex -462.826 66.6242 315.913 + endloop + endfacet + facet normal -0.24895 -0.961787 0.113975 + outer loop + vertex -457.466 65.3906 317.385 + vertex -453.029 64.3827 318.572 + vertex -451.339 64.0272 319.264 + endloop + endfacet + facet normal -0.234295 -0.970365 0.0591385 + outer loop + vertex -447.511 63.1414 320.064 + vertex -453.029 64.3827 318.572 + vertex -449.378 63.5407 319.222 + endloop + endfacet + facet normal -0.229981 -0.972411 0.0390701 + outer loop + vertex -449.378 63.5407 319.222 + vertex -456.946 65.2123 316.276 + vertex -446.777 62.9107 318.854 + endloop + endfacet + facet normal -0.23533 -0.970889 0.0446501 + outer loop + vertex -470.037 68.2296 313.062 + vertex -465.936 67.2628 313.656 + vertex -459.679 65.8737 316.425 + endloop + endfacet + facet normal -0.23301 -0.972109 0.0266483 + outer loop + vertex -465.936 67.2628 313.656 + vertex -470.037 68.2296 313.062 + vertex -473.375 68.9716 310.94 + endloop + endfacet + facet normal -0.231768 -0.972461 0.0245716 + outer loop + vertex -477.603 69.9529 309.901 + vertex -473.375 68.9716 310.94 + vertex -470.037 68.2296 313.062 + endloop + endfacet + facet normal -0.225342 -0.97427 0.00428141 + outer loop + vertex -473.375 68.9716 310.94 + vertex -470.507 68.3073 310.721 + vertex -465.936 67.2628 313.656 + endloop + endfacet + facet normal -0.224333 -0.974288 -0.0208952 + outer loop + vertex -470.507 68.3073 310.721 + vertex -473.199 68.9953 307.536 + vertex -468.322 67.8266 309.674 + endloop + endfacet + facet normal -0.223323 -0.974695 0.00979691 + outer loop + vertex -455.425 64.8475 314.657 + vertex -456.946 65.2123 316.276 + vertex -463.741 66.7365 313.02 + endloop + endfacet + facet normal -0.216377 -0.975601 -0.0371917 + outer loop + vertex -468.322 67.8266 309.674 + vertex -465.871 67.3337 308.345 + vertex -463.169 66.6139 311.502 + endloop + endfacet + facet normal -0.211035 -0.975291 -0.0653642 + outer loop + vertex -465.871 67.3337 308.345 + vertex -467.155 67.8525 304.749 + vertex -462.96 66.8 306.909 + endloop + endfacet + facet normal -0.211361 -0.977038 -0.026885 + outer loop + vertex -451.54 64.0681 312.435 + vertex -455.425 64.8475 314.657 + vertex -460.007 65.9493 310.635 + endloop + endfacet + facet normal -0.212858 -0.976633 -0.0296431 + outer loop + vertex -455.425 64.8475 314.657 + vertex -451.54 64.0681 312.435 + vertex -443.844 62.233 317.638 + endloop + endfacet + facet normal -0.212536 -0.976688 -0.0301379 + outer loop + vertex -443.844 62.233 317.638 + vertex -451.54 64.0681 312.435 + vertex -440.028 61.4623 315.704 + endloop + endfacet + facet normal -0.212769 -0.976622 -0.0306242 + outer loop + vertex -443.844 62.233 317.638 + vertex -440.028 61.4623 315.704 + vertex -432.622 59.7015 320.399 + endloop + endfacet + facet normal -0.215005 -0.976241 -0.026954 + outer loop + vertex -432.622 59.7015 320.399 + vertex -440.028 61.4623 315.704 + vertex -429.084 58.9728 318.568 + endloop + endfacet + facet normal -0.213818 -0.976565 -0.0245305 + outer loop + vertex -432.622 59.7015 320.399 + vertex -429.084 58.9728 318.568 + vertex -421.737 57.2613 322.67 + endloop + endfacet + facet normal -0.216025 -0.976174 -0.0204141 + outer loop + vertex -421.737 57.2613 322.67 + vertex -429.084 58.9728 318.568 + vertex -418.518 56.5866 320.868 + endloop + endfacet + facet normal -0.214423 -0.976586 -0.0173976 + outer loop + vertex -421.737 57.2613 322.67 + vertex -418.518 56.5866 320.868 + vertex -411.494 54.983 324.315 + endloop + endfacet + facet normal -0.21509 -0.976463 -0.0159816 + outer loop + vertex -411.494 54.983 324.315 + vertex -418.518 56.5866 320.868 + vertex -408.499 54.3518 322.565 + endloop + endfacet + facet normal -0.213191 -0.97693 -0.0125625 + outer loop + vertex -411.494 54.983 324.315 + vertex -408.499 54.3518 322.565 + vertex -403.414 53.2089 325.158 + endloop + endfacet + facet normal -0.210949 -0.977347 -0.0171415 + outer loop + vertex -403.414 53.2089 325.158 + vertex -408.499 54.3518 322.565 + vertex -399.509 52.3894 323.824 + endloop + endfacet + facet normal -0.204051 -0.978952 0.0040445 + outer loop + vertex -403.414 53.2089 325.158 + vertex -399.509 52.3894 323.824 + vertex -396.315 51.7358 326.793 + endloop + endfacet + facet normal -0.213418 -0.976852 0.0145883 + outer loop + vertex -392.534 50.8764 324.56 + vertex -396.315 51.7358 326.793 + vertex -399.509 52.3894 323.824 + endloop + endfacet + facet normal -0.20075 -0.976085 -0.0834141 + outer loop + vertex -462.96 66.8 306.909 + vertex -459.787 66.2705 305.468 + vertex -458.253 65.6697 308.808 + endloop + endfacet + facet normal -0.193972 -0.974405 -0.113617 + outer loop + vertex -459.787 66.2705 305.468 + vertex -460.002 66.7304 301.892 + vertex -456.382 65.7543 304.083 + endloop + endfacet + facet normal -0.196789 -0.978059 -0.0683678 + outer loop + vertex -446.293 63.1937 309.841 + vertex -451.54 64.0681 312.435 + vertex -454.484 64.9785 307.889 + endloop + endfacet + facet normal -0.199865 -0.976952 -0.0749648 + outer loop + vertex -451.54 64.0681 312.435 + vertex -446.293 63.1937 309.841 + vertex -440.028 61.4623 315.704 + endloop + endfacet + facet normal -0.200451 -0.976881 -0.074318 + outer loop + vertex -440.028 61.4623 315.704 + vertex -446.293 63.1937 309.841 + vertex -435.41 60.6978 313.298 + endloop + endfacet + facet normal -0.201878 -0.976362 -0.0772211 + outer loop + vertex -440.028 61.4623 315.704 + vertex -435.41 60.6978 313.298 + vertex -429.084 58.9728 318.568 + endloop + endfacet + facet normal -0.204254 -0.976096 -0.0742809 + outer loop + vertex -429.084 58.9728 318.568 + vertex -435.41 60.6978 313.298 + vertex -424.994 58.2921 316.267 + endloop + endfacet + facet normal -0.204274 -0.976089 -0.074317 + outer loop + vertex -429.084 58.9728 318.568 + vertex -424.994 58.2921 316.267 + vertex -418.518 56.5866 320.868 + endloop + endfacet + facet normal -0.206009 -0.975912 -0.0718091 + outer loop + vertex -418.518 56.5866 320.868 + vertex -424.994 58.2921 316.267 + vertex -414.757 55.9546 318.667 + endloop + endfacet + facet normal -0.20565 -0.976035 -0.0711596 + outer loop + vertex -418.518 56.5866 320.868 + vertex -414.757 55.9546 318.667 + vertex -408.499 54.3518 322.565 + endloop + endfacet + facet normal -0.204906 -0.976102 -0.0723799 + outer loop + vertex -408.499 54.3518 322.565 + vertex -414.757 55.9546 318.667 + vertex -404.773 53.7238 320.486 + endloop + endfacet + facet normal -0.203439 -0.976611 -0.0695956 + outer loop + vertex -408.499 54.3518 322.565 + vertex -404.773 53.7238 320.486 + vertex -399.509 52.3894 323.824 + endloop + endfacet + facet normal -0.203824 -0.976575 -0.0689747 + outer loop + vertex -399.509 52.3894 323.824 + vertex -404.773 53.7238 320.486 + vertex -395.888 51.781 321.736 + endloop + endfacet + facet normal -0.204395 -0.976381 -0.0700217 + outer loop + vertex -399.509 52.3894 323.824 + vertex -395.888 51.781 321.736 + vertex -392.534 50.8764 324.56 + endloop + endfacet + facet normal -0.198262 -0.977078 -0.0775283 + outer loop + vertex -388.999 50.327 322.445 + vertex -392.534 50.8764 324.56 + vertex -395.888 51.781 321.736 + endloop + endfacet + facet normal -0.180136 -0.977115 -0.113124 + outer loop + vertex -440.279 62.3952 307.163 + vertex -446.293 63.1937 309.841 + vertex -448.071 64.0663 305.135 + endloop + endfacet + facet normal -0.171912 -0.974714 -0.142754 + outer loop + vertex -445.287 63.8491 303.266 + vertex -440.279 62.3952 307.163 + vertex -448.071 64.0663 305.135 + endloop + endfacet + facet normal -0.159308 -0.974369 -0.158826 + outer loop + vertex -445.287 63.8491 303.266 + vertex -441.197 63.3143 302.445 + vertex -440.279 62.3952 307.163 + endloop + endfacet + facet normal -0.162036 -0.974017 -0.158226 + outer loop + vertex -433.874 61.7451 304.606 + vertex -440.279 62.3952 307.163 + vertex -441.197 63.3143 302.445 + endloop + endfacet + facet normal -0.153579 -0.970755 -0.184523 + outer loop + vertex -438.224 63.179 300.682 + vertex -433.874 61.7451 304.606 + vertex -441.197 63.3143 302.445 + endloop + endfacet + facet normal -0.154864 -0.970127 -0.186738 + outer loop + vertex -441.197 63.3143 302.445 + vertex -442.238 64.1717 298.854 + vertex -438.224 63.179 300.682 + endloop + endfacet + facet normal -0.145688 -0.967735 -0.205584 + outer loop + vertex -442.238 64.1717 298.854 + vertex -438.575 63.8825 297.62 + vertex -438.224 63.179 300.682 + endloop + endfacet + facet normal -0.141643 -0.968213 -0.206158 + outer loop + vertex -438.224 63.179 300.682 + vertex -438.575 63.8825 297.62 + vertex -434.226 62.7381 300.006 + endloop + endfacet + facet normal -0.134396 -0.966525 -0.218556 + outer loop + vertex -438.575 63.8825 297.62 + vertex -434.941 63.6378 296.468 + vertex -434.226 62.7381 300.006 + endloop + endfacet + facet normal -0.133779 -0.966579 -0.218695 + outer loop + vertex -434.226 62.7381 300.006 + vertex -434.941 63.6378 296.468 + vertex -431.269 62.7001 298.365 + endloop + endfacet + facet normal -0.133861 -0.966535 -0.218843 + outer loop + vertex -431.269 62.7001 298.365 + vertex -427.323 61.2817 302.216 + vertex -434.226 62.7381 300.006 + endloop + endfacet + facet normal -0.141046 -0.969878 -0.198604 + outer loop + vertex -427.323 61.2817 302.216 + vertex -433.874 61.7451 304.606 + vertex -434.226 62.7381 300.006 + endloop + endfacet + facet normal -0.125083 -0.964086 -0.234292 + outer loop + vertex -434.941 63.6378 296.468 + vertex -431.346 63.446 295.337 + vertex -431.269 62.7001 298.365 + endloop + endfacet + facet normal -0.119634 -0.964706 -0.234583 + outer loop + vertex -431.269 62.7001 298.365 + vertex -431.346 63.446 295.337 + vertex -427.238 62.3596 297.71 + endloop + endfacet + facet normal -0.125814 -0.963394 -0.236735 + outer loop + vertex -434.941 63.6378 296.468 + vertex -434.344 64.322 293.366 + vertex -431.346 63.446 295.337 + endloop + endfacet + facet normal -0.135166 -0.965832 -0.221131 + outer loop + vertex -438.575 63.8825 297.62 + vertex -438.034 64.4373 294.866 + vertex -434.941 63.6378 296.468 + endloop + endfacet + facet normal -0.146853 -0.966768 -0.20927 + outer loop + vertex -442.238 64.1717 298.854 + vertex -442.069 64.8222 295.731 + vertex -438.575 63.8825 297.62 + endloop + endfacet + facet normal -0.153377 -0.970273 -0.187204 + outer loop + vertex -445.928 64.503 300.16 + vertex -442.238 64.1717 298.854 + vertex -441.197 63.3143 302.445 + endloop + endfacet + facet normal -0.154604 -0.969357 -0.190906 + outer loop + vertex -445.928 64.503 300.16 + vertex -445.781 65.0323 297.353 + vertex -442.238 64.1717 298.854 + endloop + endfacet + facet normal -0.140564 -0.969937 -0.198653 + outer loop + vertex -438.224 63.179 300.682 + vertex -434.226 62.7381 300.006 + vertex -433.874 61.7451 304.606 + endloop + endfacet + facet normal -0.167041 -0.97091 -0.171554 + outer loop + vertex -440.279 62.3952 307.163 + vertex -433.874 61.7451 304.606 + vertex -430.155 60.0186 310.756 + endloop + endfacet + facet normal -0.166053 -0.970971 -0.172168 + outer loop + vertex -430.155 60.0186 310.756 + vertex -433.874 61.7451 304.606 + vertex -424.466 59.4838 308.285 + endloop + endfacet + facet normal -0.170596 -0.968154 -0.183235 + outer loop + vertex -430.155 60.0186 310.756 + vertex -424.466 59.4838 308.285 + vertex -420.311 57.7041 313.82 + endloop + endfacet + facet normal -0.168829 -0.968208 -0.184579 + outer loop + vertex -420.311 57.7041 313.82 + vertex -424.466 59.4838 308.285 + vertex -415.172 57.2671 311.412 + endloop + endfacet + facet normal -0.173415 -0.965375 -0.194881 + outer loop + vertex -420.311 57.7041 313.82 + vertex -415.172 57.2671 311.412 + vertex -410.467 55.4316 316.317 + endloop + endfacet + facet normal -0.171541 -0.965347 -0.196668 + outer loop + vertex -410.467 55.4316 316.317 + vertex -415.172 57.2671 311.412 + vertex -405.851 55.0833 314 + endloop + endfacet + facet normal -0.175797 -0.962729 -0.205543 + outer loop + vertex -410.467 55.4316 316.317 + vertex -405.851 55.0833 314 + vertex -400.86 53.2662 318.243 + endloop + endfacet + facet normal -0.172008 -0.962476 -0.20989 + outer loop + vertex -400.86 53.2662 318.243 + vertex -405.851 55.0833 314 + vertex -396.823 53.0333 316.002 + endloop + endfacet + facet normal -0.175657 -0.960307 -0.216691 + outer loop + vertex -400.86 53.2662 318.243 + vertex -396.823 53.0333 316.002 + vertex -392.525 51.4547 319.514 + endloop + endfacet + facet normal -0.16845 -0.959637 -0.225213 + outer loop + vertex -392.525 51.4547 319.514 + vertex -396.823 53.0333 316.002 + vertex -389.014 51.3503 317.333 + endloop + endfacet + facet normal -0.171802 -0.957738 -0.2307 + outer loop + vertex -392.525 51.4547 319.514 + vertex -389.014 51.3503 317.333 + vertex -386.839 50.3321 319.94 + endloop + endfacet + facet normal -0.156813 -0.957262 -0.243021 + outer loop + vertex -383.01 50.1609 318.143 + vertex -386.839 50.3321 319.94 + vertex -389.014 51.3503 317.333 + endloop + endfacet + facet normal -0.161483 -0.9719 -0.17127 + outer loop + vertex -445.287 63.8491 303.266 + vertex -445.928 64.503 300.16 + vertex -441.197 63.3143 302.445 + endloop + endfacet + facet normal -0.164055 -0.971575 -0.170671 + outer loop + vertex -449.49 64.8657 301.52 + vertex -445.928 64.503 300.16 + vertex -445.287 63.8491 303.266 + endloop + endfacet + facet normal -0.184443 -0.975065 -0.123403 + outer loop + vertex -446.293 63.1937 309.841 + vertex -440.279 62.3952 307.163 + vertex -435.41 60.6978 313.298 + endloop + endfacet + facet normal -0.185354 -0.974987 -0.122659 + outer loop + vertex -435.41 60.6978 313.298 + vertex -440.279 62.3952 307.163 + vertex -430.155 60.0186 310.756 + endloop + endfacet + facet normal -0.188153 -0.973657 -0.128801 + outer loop + vertex -435.41 60.6978 313.298 + vertex -430.155 60.0186 310.756 + vertex -424.994 58.2921 316.267 + endloop + endfacet + facet normal -0.189098 -0.973594 -0.127896 + outer loop + vertex -424.994 58.2921 316.267 + vertex -430.155 60.0186 310.756 + vertex -420.311 57.7041 313.82 + endloop + endfacet + facet normal -0.191141 -0.972642 -0.132035 + outer loop + vertex -424.994 58.2921 316.267 + vertex -420.311 57.7041 313.82 + vertex -414.757 55.9546 318.667 + endloop + endfacet + facet normal -0.190996 -0.972647 -0.132203 + outer loop + vertex -414.757 55.9546 318.667 + vertex -420.311 57.7041 313.82 + vertex -410.467 55.4316 316.317 + endloop + endfacet + facet normal -0.192534 -0.971936 -0.13517 + outer loop + vertex -414.757 55.9546 318.667 + vertex -410.467 55.4316 316.317 + vertex -404.773 53.7238 320.486 + endloop + endfacet + facet normal -0.19177 -0.971941 -0.136216 + outer loop + vertex -404.773 53.7238 320.486 + vertex -410.467 55.4316 316.317 + vertex -400.86 53.2662 318.243 + endloop + endfacet + facet normal -0.192936 -0.971408 -0.138357 + outer loop + vertex -404.773 53.7238 320.486 + vertex -400.86 53.2662 318.243 + vertex -395.888 51.781 321.736 + endloop + endfacet + facet normal -0.189199 -0.971373 -0.143662 + outer loop + vertex -395.888 51.781 321.736 + vertex -400.86 53.2662 318.243 + vertex -392.525 51.4547 319.514 + endloop + endfacet + facet normal -0.190037 -0.971013 -0.144984 + outer loop + vertex -395.888 51.781 321.736 + vertex -392.525 51.4547 319.514 + vertex -388.999 50.327 322.445 + endloop + endfacet + facet normal -0.179936 -0.971045 -0.157146 + outer loop + vertex -386.839 50.3321 319.94 + vertex -388.999 50.327 322.445 + vertex -392.525 51.4547 319.514 + endloop + endfacet + facet normal -0.182717 -0.974851 -0.127593 + outer loop + vertex -456.382 65.7543 304.083 + vertex -452.95 65.275 302.829 + vertex -452.027 64.686 306.008 + endloop + endfacet + facet normal -0.174505 -0.973661 -0.146738 + outer loop + vertex -448.071 64.0663 305.135 + vertex -449.49 64.8657 301.52 + vertex -445.287 63.8491 303.266 + endloop + endfacet + facet normal -0.17415 -0.972614 -0.153927 + outer loop + vertex -456.172 66.1877 300.707 + vertex -452.826 65.6935 300.045 + vertex -452.95 65.275 302.829 + endloop + endfacet + facet normal -0.165861 -0.970367 -0.175723 + outer loop + vertex -449.49 64.8657 301.52 + vertex -449.549 65.4405 298.401 + vertex -445.928 64.503 300.16 + endloop + endfacet + facet normal -0.177269 -0.968938 -0.172437 + outer loop + vertex -456.172 66.1877 300.707 + vertex -453.617 66.2286 297.851 + vertex -452.826 65.6935 300.045 + endloop + endfacet + facet normal -0.15122 -0.971235 -0.183942 + outer loop + vertex -453.617 66.2286 297.851 + vertex -454.882 66.7508 296.134 + vertex -447.216 65.7726 294.997 + endloop + endfacet + facet normal -0.158043 -0.968788 -0.190979 + outer loop + vertex -449.549 65.4405 298.401 + vertex -445.781 65.0323 297.353 + vertex -445.928 64.503 300.16 + endloop + endfacet + facet normal -0.146226 -0.966866 -0.209256 + outer loop + vertex -445.781 65.0323 297.353 + vertex -442.069 64.8222 295.731 + vertex -442.238 64.1717 298.854 + endloop + endfacet + facet normal -0.130233 -0.973041 -0.190341 + outer loop + vertex -447.216 65.7726 294.997 + vertex -441.458 65.7326 291.261 + vertex -438.486 65.1072 292.425 + endloop + endfacet + facet normal -0.115634 -0.967549 -0.224671 + outer loop + vertex -441.458 65.7326 291.261 + vertex -433.76 65.3195 289.078 + vertex -438.486 65.1072 292.425 + endloop + endfacet + facet normal -0.139591 -0.965039 -0.22184 + outer loop + vertex -442.069 64.8222 295.731 + vertex -438.034 64.4373 294.866 + vertex -438.575 63.8825 297.62 + endloop + endfacet + facet normal -0.126383 -0.963297 -0.236824 + outer loop + vertex -438.034 64.4373 294.866 + vertex -434.344 64.322 293.366 + vertex -434.941 63.6378 296.468 + endloop + endfacet + facet normal -0.105994 -0.971653 -0.211319 + outer loop + vertex -438.486 65.1072 292.425 + vertex -433.76 65.3195 289.078 + vertex -430.433 64.7408 290.071 + endloop + endfacet + facet normal -0.0935571 -0.964077 -0.248601 + outer loop + vertex -433.76 65.3195 289.078 + vertex -425.617 65.1074 286.837 + vertex -430.433 64.7408 290.071 + endloop + endfacet + facet normal -0.117712 -0.961523 -0.248227 + outer loop + vertex -434.344 64.322 293.366 + vertex -430.447 64.0541 292.555 + vertex -431.346 63.446 295.337 + endloop + endfacet + facet normal -0.111939 -0.96263 -0.246602 + outer loop + vertex -431.346 63.446 295.337 + vertex -430.447 64.0541 292.555 + vertex -427.507 63.2993 294.167 + endloop + endfacet + facet normal -0.101981 -0.959331 -0.263217 + outer loop + vertex -430.447 64.0541 292.555 + vertex -426.263 64.0542 290.934 + vertex -427.507 63.2993 294.167 + endloop + endfacet + facet normal -0.0779348 -0.970977 -0.226121 + outer loop + vertex -430.433 64.7408 290.071 + vertex -425.617 65.1074 286.837 + vertex -421.757 64.6545 287.451 + endloop + endfacet + facet normal -0.0708932 -0.961989 -0.263724 + outer loop + vertex -425.617 65.1074 286.837 + vertex -417.436 65.1427 284.509 + vertex -421.757 64.6545 287.451 + endloop + endfacet + facet normal -0.0882213 -0.95648 -0.278143 + outer loop + vertex -426.263 64.0542 290.934 + vertex -421.208 63.8958 289.875 + vertex -423.15 63.1907 292.916 + endloop + endfacet + facet normal -0.0682977 -0.952038 -0.298259 + outer loop + vertex -421.208 63.8958 289.875 + vertex -414.559 64.1604 287.508 + vertex -417.878 63.0874 291.693 + endloop + endfacet + facet normal -0.0633072 -0.953498 -0.294675 + outer loop + vertex -414.559 64.1604 287.508 + vertex -410.773 62.7013 291.416 + vertex -417.878 63.0874 291.693 + endloop + endfacet + facet normal -0.0423308 -0.973734 -0.22372 + outer loop + vertex -421.757 64.6545 287.451 + vertex -417.436 65.1427 284.509 + vertex -414.381 64.9581 284.734 + endloop + endfacet + facet normal -0.0375531 -0.960047 -0.277309 + outer loop + vertex -417.436 65.1427 284.509 + vertex -409.472 65.4177 282.478 + vertex -414.381 64.9581 284.734 + endloop + endfacet + facet normal -0.0131052 -0.973826 -0.226918 + outer loop + vertex -414.381 64.9581 284.734 + vertex -409.472 65.4177 282.478 + vertex -407.51 65.1526 283.503 + endloop + endfacet + facet normal 0.0129383 -0.961735 -0.273676 + outer loop + vertex -409.472 65.4177 282.478 + vertex -401.694 66.0121 280.757 + vertex -407.51 65.1526 283.503 + endloop + endfacet + facet normal 0.0293988 -0.969984 -0.241386 + outer loop + vertex -407.51 65.1526 283.503 + vertex -401.694 66.0121 280.757 + vertex -397.804 65.9029 281.669 + endloop + endfacet + facet normal -0.0366695 -0.947321 -0.318178 + outer loop + vertex -414.559 64.1604 287.508 + vertex -405.423 64.2831 286.09 + vertex -410.773 62.7013 291.416 + endloop + endfacet + facet normal -0.0634793 -0.951021 -0.302539 + outer loop + vertex -415.573 62.2353 293.888 + vertex -417.878 63.0874 291.693 + vertex -410.773 62.7013 291.416 + endloop + endfacet + facet normal -0.0825151 -0.957943 -0.274838 + outer loop + vertex -423.15 63.1907 292.916 + vertex -421.208 63.8958 289.875 + vertex -417.878 63.0874 291.693 + endloop + endfacet + facet normal -0.0992508 -0.959871 -0.262292 + outer loop + vertex -427.507 63.2993 294.167 + vertex -426.263 64.0542 290.934 + vertex -423.15 63.1907 292.916 + endloop + endfacet + facet normal -0.112002 -0.962568 -0.246817 + outer loop + vertex -431.346 63.446 295.337 + vertex -427.507 63.2993 294.167 + vertex -427.238 62.3596 297.71 + endloop + endfacet + facet normal -0.0954692 -0.95967 -0.264422 + outer loop + vertex -423.897 62.4101 296.031 + vertex -419.306 62.155 295.299 + vertex -420.424 61.0199 299.822 + endloop + endfacet + facet normal -0.119426 -0.965091 -0.233101 + outer loop + vertex -431.269 62.7001 298.365 + vertex -427.238 62.3596 297.71 + vertex -427.323 61.2817 302.216 + endloop + endfacet + facet normal -0.14727 -0.96509 -0.216592 + outer loop + vertex -433.874 61.7451 304.606 + vertex -427.323 61.2817 302.216 + vertex -424.466 59.4838 308.285 + endloop + endfacet + facet normal -0.119286 -0.958525 -0.258846 + outer loop + vertex -418.446 59.1362 305.886 + vertex -420.424 61.0199 299.822 + vertex -412.071 58.9975 303.462 + endloop + endfacet + facet normal -0.0960376 -0.951016 -0.293847 + outer loop + vertex -412.071 58.9975 303.462 + vertex -412.886 61.0098 297.215 + vertex -405.312 59.0587 301.054 + endloop + endfacet + facet normal -0.0752004 -0.941023 -0.329879 + outer loop + vertex -412.886 61.0098 297.215 + vertex -404.636 61.0896 295.107 + vertex -405.312 59.0587 301.054 + endloop + endfacet + facet normal -0.0328398 -0.941707 -0.334827 + outer loop + vertex -404.636 61.0896 295.107 + vertex -401.818 63.0096 289.431 + vertex -396.683 61.5886 292.924 + endloop + endfacet + facet normal 0.0128933 -0.92949 -0.368623 + outer loop + vertex -396.683 61.5886 292.924 + vertex -393.342 63.8455 287.35 + vertex -388.509 62.5245 290.85 + endloop + endfacet + facet normal -0.0452143 -0.913565 -0.404172 + outer loop + vertex -398.363 59.3588 298.734 + vertex -391.169 59.9951 296.491 + vertex -391.817 57.575 302.033 + endloop + endfacet + facet normal -0.0717596 -0.93003 -0.360409 + outer loop + vertex -398.025 57.1492 304.368 + vertex -398.363 59.3588 298.734 + vertex -391.817 57.575 302.033 + endloop + endfacet + facet normal -0.110625 -0.931003 -0.347844 + outer loop + vertex -403.97 56.9797 306.713 + vertex -398.025 57.1492 304.368 + vertex -395.855 54.992 309.452 + endloop + endfacet +endsolid diff --git a/noether_examples/meshes/outputs/output_13.stl b/noether_examples/meshes/outputs/output_13.stl new file mode 100644 index 00000000..dc5d5111 --- /dev/null +++ b/noether_examples/meshes/outputs/output_13.stl @@ -0,0 +1,5777 @@ +solid ascii + facet normal 0.879229 -0.347743 -0.325625 + outer loop + vertex 676.672 150.159 266.895 + vertex 677.912 148.868 271.622 + vertex 677.81 148.456 271.786 + endloop + endfacet + facet normal 0.838001 -0.429139 -0.337037 + outer loop + vertex 677.912 148.868 271.622 + vertex 676.672 150.159 266.895 + vertex 677.239 150.409 267.985 + endloop + endfacet + facet normal 0.815544 -0.46296 -0.347212 + outer loop + vertex 677.239 150.409 267.985 + vertex 678.118 149.625 271.097 + vertex 677.912 148.868 271.622 + endloop + endfacet + facet normal 0.799747 -0.488364 -0.349148 + outer loop + vertex 678.118 149.625 271.097 + vertex 677.239 150.409 267.985 + vertex 678.103 151.17 268.899 + endloop + endfacet + facet normal 0.797948 -0.498151 -0.3393 + outer loop + vertex 677.754 151.86 267.066 + vertex 678.103 151.17 268.899 + vertex 677.239 150.409 267.985 + endloop + endfacet + facet normal 0.806765 -0.492832 -0.325955 + outer loop + vertex 677.754 151.86 267.066 + vertex 677.239 150.409 267.985 + vertex 677.25 152.159 265.368 + endloop + endfacet + facet normal 0.810582 -0.486516 -0.325975 + outer loop + vertex 677.25 152.159 265.368 + vertex 678.38 153.99 265.445 + vertex 677.754 151.86 267.066 + endloop + endfacet + facet normal 0.809388 -0.487407 -0.327606 + outer loop + vertex 677.754 151.86 267.066 + vertex 678.38 153.99 265.445 + vertex 678.8 153.494 267.221 + endloop + endfacet + facet normal 0.813411 -0.488705 -0.315485 + outer loop + vertex 677.25 152.159 265.368 + vertex 678.018 154.546 263.648 + vertex 678.38 153.99 265.445 + endloop + endfacet + facet normal 0.818334 -0.485082 -0.30826 + outer loop + vertex 676.985 152.962 263.401 + vertex 678.018 154.546 263.648 + vertex 677.25 152.159 265.368 + endloop + endfacet + facet normal 0.811547 -0.494517 -0.311198 + outer loop + vertex 676.985 152.962 263.401 + vertex 677.25 152.159 265.368 + vertex 676.363 151.607 263.931 + endloop + endfacet + facet normal 0.818686 -0.491941 -0.296221 + outer loop + vertex 676.985 152.962 263.401 + vertex 676.363 151.607 263.931 + vertex 676.523 153.299 261.563 + endloop + endfacet + facet normal 0.822969 -0.484877 -0.296002 + outer loop + vertex 676.523 153.299 261.563 + vertex 677.679 155.106 261.816 + vertex 676.985 152.962 263.401 + endloop + endfacet + facet normal 0.825243 -0.487959 -0.284377 + outer loop + vertex 676.523 153.299 261.563 + vertex 677.333 155.59 259.982 + vertex 677.679 155.106 261.816 + endloop + endfacet + facet normal 0.829026 -0.485067 -0.278253 + outer loop + vertex 676.287 154.028 259.59 + vertex 677.333 155.59 259.982 + vertex 676.523 153.299 261.563 + endloop + endfacet + facet normal 0.822121 -0.495065 -0.281119 + outer loop + vertex 676.287 154.028 259.59 + vertex 676.523 153.299 261.563 + vertex 675.565 152.799 259.641 + endloop + endfacet + facet normal 0.825502 -0.49652 -0.268356 + outer loop + vertex 676.287 154.028 259.59 + vertex 675.565 152.799 259.641 + vertex 675.854 154.274 257.802 + endloop + endfacet + facet normal 0.830617 -0.487886 -0.268408 + outer loop + vertex 675.854 154.274 257.802 + vertex 676.964 155.937 258.215 + vertex 676.287 154.028 259.59 + endloop + endfacet + facet normal 0.830501 -0.487585 -0.269311 + outer loop + vertex 675.854 154.274 257.802 + vertex 676.719 156.493 256.45 + vertex 676.964 155.937 258.215 + endloop + endfacet + facet normal 0.838746 -0.48157 -0.254156 + outer loop + vertex 675.691 154.991 255.906 + vertex 676.719 156.493 256.45 + vertex 675.854 154.274 257.802 + endloop + endfacet + facet normal 0.828711 -0.496229 -0.258835 + outer loop + vertex 675.691 154.991 255.906 + vertex 675.854 154.274 257.802 + vertex 675.041 153.786 256.134 + endloop + endfacet + facet normal 0.831969 -0.496035 -0.248552 + outer loop + vertex 675.691 154.991 255.906 + vertex 675.041 153.786 256.134 + vertex 675.312 155.262 254.096 + endloop + endfacet + facet normal 0.846577 -0.471032 -0.247864 + outer loop + vertex 675.312 155.262 254.096 + vertex 676.567 157.269 254.57 + vertex 675.691 154.991 255.906 + endloop + endfacet + facet normal 0.847107 -0.472425 -0.243361 + outer loop + vertex 675.312 155.262 254.096 + vertex 676.343 157.873 252.615 + vertex 676.567 157.269 254.57 + endloop + endfacet + facet normal 0.854771 -0.466471 -0.227533 + outer loop + vertex 675.149 155.927 252.121 + vertex 676.343 157.873 252.615 + vertex 675.312 155.262 254.096 + endloop + endfacet + facet normal 0.835079 -0.496866 -0.236149 + outer loop + vertex 675.149 155.927 252.121 + vertex 675.312 155.262 254.096 + vertex 674.464 154.496 252.709 + endloop + endfacet + facet normal 0.839224 -0.494643 -0.225901 + outer loop + vertex 675.149 155.927 252.121 + vertex 674.464 154.496 252.709 + vertex 674.783 156.163 250.243 + endloop + endfacet + facet normal 0.855019 -0.467003 -0.225504 + outer loop + vertex 674.783 156.163 250.243 + vertex 676.092 158.358 250.664 + vertex 675.149 155.927 252.121 + endloop + endfacet + facet normal 0.856268 -0.469839 -0.214606 + outer loop + vertex 674.783 156.163 250.243 + vertex 675.851 158.805 248.722 + vertex 676.092 158.358 250.664 + endloop + endfacet + facet normal 0.858527 -0.467929 -0.209701 + outer loop + vertex 674.676 156.889 248.186 + vertex 675.851 158.805 248.722 + vertex 674.783 156.163 250.243 + endloop + endfacet + facet normal 0.836454 -0.501732 -0.220474 + outer loop + vertex 674.676 156.889 248.186 + vertex 674.783 156.163 250.243 + vertex 673.967 155.475 248.714 + endloop + endfacet + facet normal 0.839555 -0.500163 -0.212096 + outer loop + vertex 674.676 156.889 248.186 + vertex 673.967 155.475 248.714 + vertex 674.385 157.192 246.318 + endloop + endfacet + facet normal 0.858367 -0.468165 -0.209827 + outer loop + vertex 674.385 157.192 246.318 + vertex 675.661 159.324 246.786 + vertex 674.676 156.889 248.186 + endloop + endfacet + facet normal 0.859235 -0.470815 -0.200122 + outer loop + vertex 674.385 157.192 246.318 + vertex 675.487 159.821 244.865 + vertex 675.661 159.324 246.786 + endloop + endfacet + facet normal 0.862806 -0.467727 -0.191826 + outer loop + vertex 674.339 157.926 244.322 + vertex 675.487 159.821 244.865 + vertex 674.385 157.192 246.318 + endloop + endfacet + facet normal 0.839998 -0.502714 -0.204161 + outer loop + vertex 674.339 157.926 244.322 + vertex 674.385 157.192 246.318 + vertex 673.623 156.526 244.827 + endloop + endfacet + facet normal 0.844148 -0.500497 -0.192137 + outer loop + vertex 674.339 157.926 244.322 + vertex 673.623 156.526 244.827 + vertex 674.076 158.167 242.54 + endloop + endfacet + facet normal 0.862491 -0.468824 -0.190559 + outer loop + vertex 674.076 158.167 242.54 + vertex 675.332 160.301 242.976 + vertex 674.339 157.926 244.322 + endloop + endfacet + facet normal 0.863154 -0.470923 -0.182201 + outer loop + vertex 674.076 158.167 242.54 + vertex 675.204 160.777 241.139 + vertex 675.332 160.301 242.976 + endloop + endfacet + facet normal 0.86656 -0.467854 -0.17374 + outer loop + vertex 674.077 158.873 240.644 + vertex 675.204 160.777 241.139 + vertex 674.076 158.167 242.54 + endloop + endfacet + facet normal 0.842009 -0.505697 -0.187857 + outer loop + vertex 674.077 158.873 240.644 + vertex 674.076 158.167 242.54 + vertex 673.352 157.483 241.136 + endloop + endfacet + facet normal 0.845283 -0.503859 -0.17783 + outer loop + vertex 674.077 158.873 240.644 + vertex 673.352 157.483 241.136 + vertex 673.84 159.083 238.926 + endloop + endfacet + facet normal 0.865207 -0.469371 -0.176374 + outer loop + vertex 673.84 159.083 238.926 + vertex 675.078 161.205 239.349 + vertex 674.077 158.873 240.644 + endloop + endfacet + facet normal 0.865836 -0.471564 -0.167199 + outer loop + vertex 673.84 159.083 238.926 + vertex 674.971 161.635 237.584 + vertex 675.078 161.205 239.349 + endloop + endfacet + facet normal 0.869283 -0.468332 -0.158151 + outer loop + vertex 673.85 159.728 237.069 + vertex 674.971 161.635 237.584 + vertex 673.84 159.083 238.926 + endloop + endfacet + facet normal 0.842997 -0.509483 -0.17258 + outer loop + vertex 673.85 159.728 237.069 + vertex 673.84 159.083 238.926 + vertex 673.062 158.303 237.426 + endloop + endfacet + facet normal 0.846116 -0.508217 -0.160632 + outer loop + vertex 673.85 159.728 237.069 + vertex 673.062 158.303 237.426 + vertex 673.622 159.905 235.309 + endloop + endfacet + facet normal 0.868932 -0.468499 -0.159582 + outer loop + vertex 673.622 159.905 235.309 + vertex 674.866 162.044 235.801 + vertex 673.85 159.728 237.069 + endloop + endfacet + facet normal 0.869206 -0.470144 -0.153115 + outer loop + vertex 673.622 159.905 235.309 + vertex 674.773 162.469 233.968 + vertex 674.866 162.044 235.801 + endloop + endfacet + facet normal 0.872805 -0.466583 -0.143218 + outer loop + vertex 673.654 160.554 233.388 + vertex 674.773 162.469 233.968 + vertex 673.622 159.905 235.309 + endloop + endfacet + facet normal 0.848291 -0.505761 -0.156869 + outer loop + vertex 673.654 160.554 233.388 + vertex 673.622 159.905 235.309 + vertex 672.914 159.216 233.701 + endloop + endfacet + facet normal 0.85021 -0.504956 -0.148871 + outer loop + vertex 673.654 160.554 233.388 + vertex 672.914 159.216 233.701 + vertex 673.446 160.744 231.556 + endloop + endfacet + facet normal 0.87147 -0.467762 -0.147437 + outer loop + vertex 673.446 160.744 231.556 + vertex 674.67 162.859 232.081 + vertex 673.654 160.554 233.388 + endloop + endfacet + facet normal 0.87163 -0.469486 -0.140868 + outer loop + vertex 673.446 160.744 231.556 + vertex 674.594 163.296 230.149 + vertex 674.67 162.859 232.081 + endloop + endfacet + facet normal 0.874849 -0.466057 -0.132019 + outer loop + vertex 673.486 161.381 229.574 + vertex 674.594 163.296 230.149 + vertex 673.446 160.744 231.556 + endloop + endfacet + facet normal 0.850567 -0.505434 -0.145163 + outer loop + vertex 673.486 161.381 229.574 + vertex 673.446 160.744 231.556 + vertex 672.744 159.995 230.044 + endloop + endfacet + facet normal 0.852651 -0.504012 -0.137687 + outer loop + vertex 673.486 161.381 229.574 + vertex 672.744 159.995 230.044 + vertex 673.287 161.547 227.73 + endloop + endfacet + facet normal 0.87334 -0.467556 -0.136634 + outer loop + vertex 673.287 161.547 227.73 + vertex 674.518 163.707 228.207 + vertex 673.486 161.381 229.574 + endloop + endfacet + facet normal 0.873555 -0.469548 -0.128165 + outer loop + vertex 673.287 161.547 227.73 + vertex 674.453 164.114 226.276 + vertex 674.518 163.707 228.207 + endloop + endfacet + facet normal 0.875931 -0.466875 -0.121542 + outer loop + vertex 673.349 162.183 225.735 + vertex 674.453 164.114 226.276 + vertex 673.287 161.547 227.73 + endloop + endfacet + facet normal 0.850456 -0.508288 -0.135526 + outer loop + vertex 673.349 162.183 225.735 + vertex 673.287 161.547 227.73 + vertex 672.574 160.743 226.27 + endloop + endfacet + facet normal 0.853577 -0.50587 -0.124502 + outer loop + vertex 673.349 162.183 225.735 + vertex 672.574 160.743 226.27 + vertex 673.166 162.327 223.891 + endloop + endfacet + facet normal 0.875538 -0.467061 -0.12364 + outer loop + vertex 673.166 162.327 223.891 + vertex 674.395 164.505 224.37 + vertex 673.349 162.183 225.735 + endloop + endfacet + facet normal 0.875642 -0.468593 -0.116929 + outer loop + vertex 673.166 162.327 223.891 + vertex 674.332 164.859 222.48 + vertex 674.395 164.505 224.37 + endloop + endfacet + facet normal 0.87854 -0.465197 -0.10844 + outer loop + vertex 673.224 162.899 221.91 + vertex 674.332 164.859 222.48 + vertex 673.166 162.327 223.891 + endloop + endfacet + facet normal 0.855573 -0.503541 -0.120175 + outer loop + vertex 673.224 162.899 221.91 + vertex 673.166 162.327 223.891 + vertex 672.49 161.56 222.3 + endloop + endfacet + facet normal 0.856893 -0.502614 -0.114513 + outer loop + vertex 673.224 162.899 221.91 + vertex 672.49 161.56 222.3 + vertex 673.059 163.038 220.07 + endloop + endfacet + facet normal 0.877505 -0.46592 -0.113593 + outer loop + vertex 673.059 163.038 220.07 + vertex 674.271 165.194 220.586 + vertex 673.224 162.899 221.91 + endloop + endfacet + facet normal 0.877498 -0.467499 -0.106969 + outer loop + vertex 673.059 163.038 220.07 + vertex 674.227 165.553 218.653 + vertex 674.271 165.194 220.586 + endloop + endfacet + facet normal 0.879946 -0.464507 -0.0996425 + outer loop + vertex 673.134 163.609 218.065 + vertex 674.227 165.553 218.653 + vertex 673.059 163.038 220.07 + endloop + endfacet + facet normal 0.857261 -0.502692 -0.111374 + outer loop + vertex 673.134 163.609 218.065 + vertex 673.059 163.038 220.07 + vertex 672.387 162.239 218.502 + endloop + endfacet + facet normal 0.858702 -0.501541 -0.105292 + outer loop + vertex 673.134 163.609 218.065 + vertex 672.387 162.239 218.502 + vertex 672.964 163.722 216.139 + endloop + endfacet + facet normal 0.878351 -0.466349 -0.104967 + outer loop + vertex 672.964 163.722 216.139 + vertex 674.173 165.881 216.662 + vertex 673.134 163.609 218.065 + endloop + endfacet + facet normal 0.878265 -0.468232 -0.0970032 + outer loop + vertex 672.964 163.722 216.139 + vertex 674.126 166.216 214.62 + vertex 674.173 165.881 216.662 + endloop + endfacet + facet normal 0.880334 -0.465543 -0.0910048 + outer loop + vertex 673.039 164.275 214.033 + vertex 674.126 166.216 214.62 + vertex 672.964 163.722 216.139 + endloop + endfacet + facet normal 0.855898 -0.506839 -0.102723 + outer loop + vertex 673.039 164.275 214.033 + vertex 672.964 163.722 216.139 + vertex 672.264 162.875 214.487 + endloop + endfacet + facet normal 0.858164 -0.504904 -0.0928817 + outer loop + vertex 673.039 164.275 214.033 + vertex 672.264 162.875 214.487 + vertex 672.87 164.348 212.082 + endloop + endfacet + facet normal 0.879948 -0.465817 -0.0933112 + outer loop + vertex 672.87 164.348 212.082 + vertex 674.087 166.548 212.575 + vertex 673.039 164.275 214.033 + endloop + endfacet + facet normal 0.879857 -0.467329 -0.0863479 + outer loop + vertex 672.87 164.348 212.082 + vertex 674.041 166.83 210.577 + vertex 674.087 166.548 212.575 + endloop + endfacet + facet normal 0.88163 -0.464934 -0.0810211 + outer loop + vertex 672.966 164.891 210.011 + vertex 674.041 166.83 210.577 + vertex 672.87 164.348 212.082 + endloop + endfacet + facet normal 0.858423 -0.504536 -0.0924875 + outer loop + vertex 672.966 164.891 210.011 + vertex 672.87 164.348 212.082 + vertex 672.218 163.534 210.467 + endloop + endfacet + facet normal 0.859961 -0.503109 -0.0857177 + outer loop + vertex 672.966 164.891 210.011 + vertex 672.218 163.534 210.467 + vertex 672.803 164.931 208.14 + endloop + endfacet + facet normal 0.880716 -0.465638 -0.0867261 + outer loop + vertex 672.803 164.931 208.14 + vertex 674.008 167.115 208.65 + vertex 672.966 164.891 210.011 + endloop + endfacet + facet normal 0.880562 -0.467148 -0.0798975 + outer loop + vertex 672.803 164.931 208.14 + vertex 673.979 167.381 206.776 + vertex 674.008 167.115 208.65 + endloop + endfacet + facet normal 0.882524 -0.464497 -0.0734434 + outer loop + vertex 672.894 165.417 206.162 + vertex 673.979 167.381 206.776 + vertex 672.803 164.931 208.14 + endloop + endfacet + facet normal 0.85789 -0.50676 -0.0849579 + outer loop + vertex 672.894 165.417 206.162 + vertex 672.803 164.931 208.14 + vertex 672.111 164.042 206.461 + endloop + endfacet + facet normal 0.859595 -0.505494 -0.0746482 + outer loop + vertex 672.894 165.417 206.162 + vertex 672.111 164.042 206.461 + vertex 672.741 165.431 204.295 + endloop + endfacet + facet normal 0.881933 -0.465179 -0.0761788 + outer loop + vertex 672.741 165.431 204.295 + vertex 673.949 167.622 204.905 + vertex 672.894 165.417 206.162 + endloop + endfacet + facet normal 0.881581 -0.466937 -0.0691703 + outer loop + vertex 672.741 165.431 204.295 + vertex 673.924 167.856 203.008 + vertex 673.949 167.622 204.905 + endloop + endfacet + facet normal 0.883818 -0.463809 -0.0612151 + outer loop + vertex 672.834 165.871 202.314 + vertex 673.924 167.856 203.008 + vertex 672.741 165.431 204.295 + endloop + endfacet + facet normal 0.860734 -0.504046 -0.0712324 + outer loop + vertex 672.834 165.871 202.314 + vertex 672.741 165.431 204.295 + vertex 672.073 164.536 202.564 + endloop + endfacet + facet normal 0.861687 -0.503327 -0.0644854 + outer loop + vertex 672.834 165.871 202.314 + vertex 672.073 164.536 202.564 + vertex 672.652 165.799 200.443 + endloop + endfacet + facet normal 0.882439 -0.465493 -0.0679532 + outer loop + vertex 672.652 165.799 200.443 + vertex 673.878 168.032 201.065 + vertex 672.834 165.871 202.314 + endloop + endfacet + facet normal 0.88208 -0.467045 -0.0616774 + outer loop + vertex 672.652 165.799 200.443 + vertex 673.826 168.203 199.031 + vertex 673.878 168.032 201.065 + endloop + endfacet + facet normal 0.883216 -0.465379 -0.0578947 + outer loop + vertex 672.693 166.129 198.416 + vertex 673.826 168.203 199.031 + vertex 672.652 165.799 200.443 + endloop + endfacet + facet normal 0.859841 -0.5064 -0.0650494 + outer loop + vertex 672.693 166.129 198.416 + vertex 672.652 165.799 200.443 + vertex 671.938 164.765 199.052 + endloop + endfacet + facet normal 0.859927 -0.506297 -0.0647254 + outer loop + vertex 672.693 166.129 198.416 + vertex 671.938 164.765 199.052 + vertex 672.448 165.941 196.631 + endloop + endfacet + facet normal 0.881255 -0.467159 -0.0717774 + outer loop + vertex 672.448 165.941 196.631 + vertex 673.79 168.445 196.808 + vertex 672.693 166.129 198.416 + endloop + endfacet + facet normal 0.881556 -0.46804 -0.0616209 + outer loop + vertex 672.448 165.941 196.631 + vertex 673.64 168.505 194.211 + vertex 673.79 168.445 196.808 + endloop + endfacet + facet normal 0.881517 -0.468103 -0.0617079 + outer loop + vertex 672.224 165.81 194.425 + vertex 673.64 168.505 194.211 + vertex 672.448 165.941 196.631 + endloop + endfacet + facet normal 0.861459 -0.50456 -0.0575093 + outer loop + vertex 672.224 165.81 194.425 + vertex 672.448 165.941 196.631 + vertex 671.774 164.785 196.683 + endloop + endfacet + facet normal 0.86095 -0.505374 -0.0579801 + outer loop + vertex 672.224 165.81 194.425 + vertex 671.774 164.785 196.683 + vertex 671.644 164.709 195.412 + endloop + endfacet + facet normal 0.867864 -0.494995 -0.0423367 + outer loop + vertex 671.644 164.709 195.412 + vertex 671.852 165.342 192.262 + vertex 672.224 165.81 194.425 + endloop + endfacet + facet normal 0.881263 -0.469967 -0.0500649 + outer loop + vertex 673.247 168.107 190.868 + vertex 672.224 165.81 194.425 + vertex 671.852 165.342 192.262 + endloop + endfacet + facet normal 0.885652 -0.463225 -0.0323002 + outer loop + vertex 671.852 165.342 192.262 + vertex 672.095 166.055 188.707 + vertex 673.247 168.107 190.868 + endloop + endfacet + facet normal 0.887827 -0.45862 -0.0378319 + outer loop + vertex 673.262 168.486 186.634 + vertex 673.247 168.107 190.868 + vertex 672.095 166.055 188.707 + endloop + endfacet + facet normal 0.889388 -0.455903 -0.0337697 + outer loop + vertex 672.095 166.055 188.707 + vertex 671.86 165.87 185.011 + vertex 673.262 168.486 186.634 + endloop + endfacet + facet normal 0.888301 -0.458353 -0.0288824 + outer loop + vertex 672.937 168.103 182.709 + vertex 673.262 168.486 186.634 + vertex 671.86 165.87 185.011 + endloop + endfacet + facet normal 0.888862 -0.45734 -0.0276375 + outer loop + vertex 671.86 165.87 185.011 + vertex 671.684 165.681 182.468 + vertex 672.937 168.103 182.709 + endloop + endfacet + facet normal 0.888653 -0.458249 -0.0174084 + outer loop + vertex 671.684 165.681 182.468 + vertex 671.852 166.079 180.576 + vertex 672.937 168.103 182.709 + endloop + endfacet + facet normal 0.889421 -0.456682 -0.0192856 + outer loop + vertex 673.123 168.631 178.809 + vertex 672.937 168.103 182.709 + vertex 671.852 166.079 180.576 + endloop + endfacet + facet normal 0.890895 -0.453983 -0.0143277 + outer loop + vertex 671.852 166.079 180.576 + vertex 671.777 166.043 177.078 + vertex 673.123 168.631 178.809 + endloop + endfacet + facet normal 0.889912 -0.45601 -0.0105329 + outer loop + vertex 673.112 168.694 175.083 + vertex 673.123 168.631 178.809 + vertex 671.777 166.043 177.078 + endloop + endfacet + facet normal 0.890747 -0.454431 -0.00787646 + outer loop + vertex 671.777 166.043 177.078 + vertex 671.831 166.206 173.778 + vertex 673.112 168.694 175.083 + endloop + endfacet + facet normal 0.889661 -0.456614 -0.00265093 + outer loop + vertex 672.901 168.305 171.248 + vertex 673.112 168.694 175.083 + vertex 671.831 166.206 173.778 + endloop + endfacet + facet normal 0.888207 -0.45941 -0.00558552 + outer loop + vertex 671.831 166.206 173.778 + vertex 671.634 165.849 171.852 + vertex 672.901 168.305 171.248 + endloop + endfacet + facet normal 0.889393 -0.457101 0.00628905 + outer loop + vertex 671.634 165.849 171.852 + vertex 671.74 166.015 168.972 + vertex 672.901 168.305 171.248 + endloop + endfacet + facet normal 0.889093 -0.457674 0.00701837 + outer loop + vertex 673.152 168.729 167.105 + vertex 672.901 168.305 171.248 + vertex 671.74 166.015 168.972 + endloop + endfacet + facet normal 0.890641 -0.454529 0.0127617 + outer loop + vertex 671.74 166.015 168.972 + vertex 671.93 166.287 165.364 + vertex 673.152 168.729 167.105 + endloop + endfacet + facet normal 0.890022 -0.455677 0.0148059 + outer loop + vertex 673.155 168.612 163.262 + vertex 673.152 168.729 167.105 + vertex 671.93 166.287 165.364 + endloop + endfacet + facet normal 0.890396 -0.45491 0.0158719 + outer loop + vertex 671.93 166.287 165.364 + vertex 671.768 165.84 161.678 + vertex 673.155 168.612 163.262 + endloop + endfacet + facet normal 0.888599 -0.458106 0.0230359 + outer loop + vertex 672.923 167.964 159.349 + vertex 673.155 168.612 163.262 + vertex 671.768 165.84 161.678 + endloop + endfacet + facet normal 0.888572 -0.458162 0.0229711 + outer loop + vertex 671.768 165.84 161.678 + vertex 671.681 165.544 159.099 + vertex 672.923 167.964 159.349 + endloop + endfacet + facet normal 0.887854 -0.458894 0.0336442 + outer loop + vertex 671.681 165.544 159.099 + vertex 671.908 165.842 157.191 + vertex 672.923 167.964 159.349 + endloop + endfacet + facet normal 0.888745 -0.457308 0.0316643 + outer loop + vertex 673.196 168.225 155.437 + vertex 672.923 167.964 159.349 + vertex 671.908 165.842 157.191 + endloop + endfacet + facet normal 0.889941 -0.454641 0.0361642 + outer loop + vertex 671.908 165.842 157.191 + vertex 671.897 165.543 153.7 + vertex 673.196 168.225 155.437 + endloop + endfacet + facet normal 0.888994 -0.456227 0.0393214 + outer loop + vertex 673.257 168.022 151.715 + vertex 673.196 168.225 155.437 + vertex 671.897 165.543 153.7 + endloop + endfacet + facet normal 0.889657 -0.454727 0.0416484 + outer loop + vertex 671.897 165.543 153.7 + vertex 672.014 165.469 150.398 + vertex 673.257 168.022 151.715 + endloop + endfacet + facet normal 0.888235 -0.456948 0.0472948 + outer loop + vertex 673.052 167.215 147.772 + vertex 673.257 168.022 151.715 + vertex 672.014 165.469 150.398 + endloop + endfacet + facet normal 0.885792 -0.462095 0.0429058 + outer loop + vertex 672.014 165.469 150.398 + vertex 671.854 164.978 148.409 + vertex 673.052 167.215 147.772 + endloop + endfacet + facet normal 0.886492 -0.459768 0.0523968 + outer loop + vertex 671.854 164.978 148.409 + vertex 671.929 164.776 145.36 + vertex 673.052 167.215 147.772 + endloop + endfacet + facet normal 0.883414 -0.464865 0.0589837 + outer loop + vertex 673.105 166.712 143.013 + vertex 673.052 167.215 147.772 + vertex 671.929 164.776 145.36 + endloop + endfacet + facet normal 0.882505 -0.466849 0.0568923 + outer loop + vertex 671.929 164.776 145.36 + vertex 671.907 164.31 141.879 + vertex 673.105 166.712 143.013 + endloop + endfacet + facet normal 0.876613 -0.474582 0.0795066 + outer loop + vertex 671.907 164.31 141.879 + vertex 672.227 164.548 139.775 + vertex 673.105 166.712 143.013 + endloop + endfacet + facet normal 0.876053 -0.475489 0.0802643 + outer loop + vertex 672.227 164.548 139.775 + vertex 673.324 166.549 139.649 + vertex 673.105 166.712 143.013 + endloop + endfacet + facet normal 0.87565 -0.474739 0.0886547 + outer loop + vertex 672.227 164.548 139.775 + vertex 672.836 165.177 137.131 + vertex 673.324 166.549 139.649 + endloop + endfacet + facet normal 0.884572 -0.459709 0.0787386 + outer loop + vertex 672.836 165.177 137.131 + vertex 674.359 168.171 137.496 + vertex 673.324 166.549 139.649 + endloop + endfacet + facet normal 0.894119 -0.436298 0.100973 + outer loop + vertex 675.462 171.112 140.44 + vertex 673.324 166.549 139.649 + vertex 674.359 168.171 137.496 + endloop + endfacet + facet normal 0.900808 -0.425312 0.0874948 + outer loop + vertex 676.011 171.675 137.527 + vertex 675.462 171.112 140.44 + vertex 674.359 168.171 137.496 + endloop + endfacet + facet normal 0.901371 -0.425514 0.0804278 + outer loop + vertex 674.359 168.171 137.496 + vertex 675.749 170.737 135.496 + vertex 676.011 171.675 137.527 + endloop + endfacet + facet normal 0.899541 -0.430799 0.0723785 + outer loop + vertex 674.021 167.04 134.973 + vertex 675.749 170.737 135.496 + vertex 674.359 168.171 137.496 + endloop + endfacet + facet normal 0.89903 -0.431147 0.0765312 + outer loop + vertex 674.021 167.04 134.973 + vertex 675.679 170.203 133.315 + vertex 675.749 170.737 135.496 + endloop + endfacet + facet normal 0.898942 -0.431446 0.0758728 + outer loop + vertex 674.022 166.633 132.637 + vertex 675.679 170.203 133.315 + vertex 674.021 167.04 134.973 + endloop + endfacet + facet normal 0.898332 -0.431959 0.0800656 + outer loop + vertex 674.022 166.633 132.637 + vertex 675.735 169.938 131.257 + vertex 675.679 170.203 133.315 + endloop + endfacet + facet normal 0.898591 -0.430862 0.0830135 + outer loop + vertex 674.104 166.404 130.565 + vertex 675.735 169.938 131.257 + vertex 674.022 166.633 132.637 + endloop + endfacet + facet normal 0.89773 -0.431552 0.088568 + outer loop + vertex 674.104 166.404 130.565 + vertex 675.804 169.678 129.293 + vertex 675.735 169.938 131.257 + endloop + endfacet + facet normal 0.897811 -0.431144 0.0897272 + outer loop + vertex 674.168 166.129 128.599 + vertex 675.804 169.678 129.293 + vertex 674.104 166.404 130.565 + endloop + endfacet + facet normal 0.897292 -0.431538 0.0929689 + outer loop + vertex 674.168 166.129 128.599 + vertex 675.858 169.373 127.346 + vertex 675.804 169.678 129.293 + endloop + endfacet + facet normal 0.897282 -0.431586 0.0928313 + outer loop + vertex 674.21 165.795 126.644 + vertex 675.858 169.373 127.346 + vertex 674.168 166.129 128.599 + endloop + endfacet + facet normal 0.896663 -0.432043 0.0966111 + outer loop + vertex 674.21 165.795 126.644 + vertex 675.894 169.009 125.391 + vertex 675.858 169.373 127.346 + endloop + endfacet + facet normal 0.896679 -0.431957 0.0968512 + outer loop + vertex 674.244 165.426 124.687 + vertex 675.894 169.009 125.391 + vertex 674.21 165.795 126.644 + endloop + endfacet + facet normal 0.896412 -0.432149 0.0984515 + outer loop + vertex 674.244 165.426 124.687 + vertex 675.941 168.666 123.457 + vertex 675.894 169.009 125.391 + endloop + endfacet + facet normal 0.896519 -0.431501 0.100304 + outer loop + vertex 674.29 165.075 122.76 + vertex 675.941 168.666 123.457 + vertex 674.244 165.426 124.687 + endloop + endfacet + facet normal 0.895503 -0.432188 0.106247 + outer loop + vertex 674.29 165.075 122.76 + vertex 675.99 168.302 121.56 + vertex 675.941 168.666 123.457 + endloop + endfacet + facet normal 0.895478 -0.432364 0.105739 + outer loop + vertex 674.34 164.715 120.868 + vertex 675.99 168.302 121.56 + vertex 674.29 165.075 122.76 + endloop + endfacet + facet normal 0.894648 -0.432897 0.110475 + outer loop + vertex 674.34 164.715 120.868 + vertex 676.045 167.938 119.69 + vertex 675.99 168.302 121.56 + endloop + endfacet + facet normal 0.894648 -0.432895 0.11048 + outer loop + vertex 674.399 164.358 118.994 + vertex 676.045 167.938 119.69 + vertex 674.34 164.715 120.868 + endloop + endfacet + facet normal 0.894039 -0.433274 0.113873 + outer loop + vertex 674.399 164.358 118.994 + vertex 676.113 167.588 117.822 + vertex 676.045 167.938 119.69 + endloop + endfacet + facet normal 0.894081 -0.432897 0.114975 + outer loop + vertex 674.471 164.008 117.117 + vertex 676.113 167.588 117.822 + vertex 674.399 164.358 118.994 + endloop + endfacet + facet normal 0.893011 -0.433539 0.12073 + outer loop + vertex 674.471 164.008 117.117 + vertex 676.176 167.193 115.941 + vertex 676.113 167.588 117.822 + endloop + endfacet + facet normal 0.893002 -0.433632 0.120464 + outer loop + vertex 674.536 163.618 115.227 + vertex 676.176 167.193 115.941 + vertex 674.471 164.008 117.117 + endloop + endfacet + facet normal 0.892159 -0.434123 0.124858 + outer loop + vertex 674.536 163.618 115.227 + vertex 676.246 166.794 114.049 + vertex 676.176 167.193 115.941 + endloop + endfacet + facet normal 0.892211 -0.433527 0.126541 + outer loop + vertex 674.605 163.205 113.328 + vertex 676.246 166.794 114.049 + vertex 674.536 163.618 115.227 + endloop + endfacet + facet normal 0.891375 -0.433994 0.130766 + outer loop + vertex 674.605 163.205 113.328 + vertex 676.319 166.371 112.152 + vertex 676.246 166.794 114.049 + endloop + endfacet + facet normal 0.8914 -0.433657 0.131707 + outer loop + vertex 674.678 162.781 111.433 + vertex 676.319 166.371 112.152 + vertex 674.605 163.205 113.328 + endloop + endfacet + facet normal 0.890086 -0.434349 0.138157 + outer loop + vertex 674.678 162.781 111.433 + vertex 676.404 165.941 110.253 + vertex 676.319 166.371 112.152 + endloop + endfacet + facet normal 0.890106 -0.433994 0.13914 + outer loop + vertex 674.765 162.351 109.538 + vertex 676.404 165.941 110.253 + vertex 674.678 162.781 111.433 + endloop + endfacet + facet normal 0.889054 -0.434513 0.144161 + outer loop + vertex 674.765 162.351 109.538 + vertex 676.508 165.523 108.349 + vertex 676.404 165.941 110.253 + endloop + endfacet + facet normal 0.889069 -0.43417 0.145097 + outer loop + vertex 674.875 161.94 107.637 + vertex 676.508 165.523 108.349 + vertex 674.765 162.351 109.538 + endloop + endfacet + facet normal 0.887326 -0.434973 0.153136 + outer loop + vertex 674.875 161.94 107.637 + vertex 676.617 165.071 106.436 + vertex 676.508 165.523 108.349 + endloop + endfacet + facet normal 0.887325 -0.435012 0.153032 + outer loop + vertex 674.985 161.491 105.723 + vertex 676.617 165.071 106.436 + vertex 674.875 161.94 107.637 + endloop + endfacet + facet normal 0.885823 -0.435662 0.159739 + outer loop + vertex 674.985 161.491 105.723 + vertex 676.738 164.615 104.521 + vertex 676.617 165.071 106.436 + endloop + endfacet + facet normal 0.885823 -0.435635 0.15981 + outer loop + vertex 675.105 161.034 103.808 + vertex 676.738 164.615 104.521 + vertex 674.985 161.491 105.723 + endloop + endfacet + facet normal 0.884068 -0.436347 0.167407 + outer loop + vertex 675.105 161.034 103.808 + vertex 676.869 164.148 102.613 + vertex 676.738 164.615 104.521 + endloop + endfacet + facet normal 0.884068 -0.436177 0.16785 + outer loop + vertex 675.229 160.55 101.9 + vertex 676.869 164.148 102.613 + vertex 675.105 161.034 103.808 + endloop + endfacet + facet normal 0.882261 -0.436854 0.175427 + outer loop + vertex 675.229 160.55 101.9 + vertex 677.013 163.68 100.72 + vertex 676.869 164.148 102.613 + endloop + endfacet + facet normal 0.882261 -0.436845 0.175451 + outer loop + vertex 675.378 160.094 100.013 + vertex 677.013 163.68 100.72 + vertex 675.229 160.55 101.9 + endloop + endfacet + facet normal 0.879977 -0.437631 0.184715 + outer loop + vertex 675.378 160.094 100.013 + vertex 677.172 163.206 98.8446 + vertex 677.013 163.68 100.72 + endloop + endfacet + facet normal 0.87998 -0.437703 0.18453 + outer loop + vertex 675.534 159.619 98.147 + vertex 677.172 163.206 98.8446 + vertex 675.378 160.094 100.013 + endloop + endfacet + facet normal 0.878175 -0.438264 0.191657 + outer loop + vertex 675.534 159.619 98.147 + vertex 677.345 162.744 96.9906 + vertex 677.172 163.206 98.8446 + endloop + endfacet + facet normal 0.878165 -0.438109 0.192061 + outer loop + vertex 675.7 159.145 96.3037 + vertex 677.345 162.744 96.9906 + vertex 675.534 159.619 98.147 + endloop + endfacet + facet normal 0.876121 -0.438677 0.199934 + outer loop + vertex 675.7 159.145 96.3037 + vertex 677.523 162.263 95.1586 + vertex 677.345 162.744 96.9906 + endloop + endfacet + facet normal 0.876149 -0.438997 0.199107 + outer loop + vertex 675.886 158.687 94.4777 + vertex 677.523 162.263 95.1586 + vertex 675.7 159.145 96.3037 + endloop + endfacet + facet normal 0.874197 -0.4395 0.206443 + outer loop + vertex 675.886 158.687 94.4777 + vertex 677.717 161.79 93.3308 + vertex 677.523 162.263 95.1586 + endloop + endfacet + facet normal 0.87413 -0.438834 0.208138 + outer loop + vertex 676.087 158.21 92.6264 + vertex 677.717 161.79 93.3308 + vertex 675.886 158.687 94.4777 + endloop + endfacet + facet normal 0.87077 -0.439663 0.220127 + outer loop + vertex 676.087 158.21 92.6264 + vertex 677.963 161.323 91.4227 + vertex 677.717 161.79 93.3308 + endloop + endfacet + facet normal 0.870749 -0.439468 0.220599 + outer loop + vertex 676.337 157.733 90.6895 + vertex 677.963 161.323 91.4227 + vertex 676.087 158.21 92.6264 + endloop + endfacet + facet normal 0.865333 -0.440711 0.238692 + outer loop + vertex 676.337 157.733 90.6895 + vertex 678.427 161.012 89.1684 + vertex 677.963 161.323 91.4227 + endloop + endfacet + facet normal 0.865362 -0.441196 0.237686 + outer loop + vertex 676.525 157.036 88.7095 + vertex 678.427 161.012 89.1684 + vertex 676.337 157.733 90.6895 + endloop + endfacet + facet normal 0.853371 -0.440251 0.279173 + outer loop + vertex 676.525 157.036 88.7095 + vertex 678.223 159.311 87.107 + vertex 678.427 161.012 89.1684 + endloop + endfacet + facet normal 0.852332 -0.457094 0.254156 + outer loop + vertex 676.702 156.291 86.7762 + vertex 678.223 159.311 87.107 + vertex 676.525 157.036 88.7095 + endloop + endfacet + facet normal 0.847144 -0.45644 0.272046 + outer loop + vertex 676.702 156.291 86.7762 + vertex 678.387 158.474 85.193 + vertex 678.223 159.311 87.107 + endloop + endfacet + facet normal 0.846383 -0.465481 0.258772 + outer loop + vertex 676.993 155.774 84.8941 + vertex 678.387 158.474 85.193 + vertex 676.702 156.291 86.7762 + endloop + endfacet + facet normal 0.842319 -0.464921 0.272666 + outer loop + vertex 676.993 155.774 84.8941 + vertex 678.719 157.967 83.3031 + vertex 678.387 158.474 85.193 + endloop + endfacet + facet normal 0.84205 -0.468169 0.267896 + outer loop + vertex 677.343 155.34 83.0383 + vertex 678.719 157.967 83.3031 + vertex 676.993 155.774 84.8941 + endloop + endfacet + facet normal 0.837253 -0.46728 0.284001 + outer loop + vertex 677.343 155.34 83.0383 + vertex 679.1 157.52 81.4435 + vertex 678.719 157.967 83.3031 + endloop + endfacet + facet normal 0.837153 -0.468701 0.281948 + outer loop + vertex 677.706 154.88 81.1926 + vertex 679.1 157.52 81.4435 + vertex 677.343 155.34 83.0383 + endloop + endfacet + facet normal 0.832381 -0.467649 0.2974 + outer loop + vertex 677.706 154.88 81.1926 + vertex 679.489 157.048 79.6121 + vertex 679.1 157.52 81.4435 + endloop + endfacet + facet normal 0.832346 -0.468317 0.296445 + outer loop + vertex 678.079 154.374 79.3485 + vertex 679.489 157.048 79.6121 + vertex 677.706 154.88 81.1926 + endloop + endfacet + facet normal 0.827362 -0.467198 0.311766 + outer loop + vertex 678.079 154.374 79.3485 + vertex 679.884 156.537 77.7981 + vertex 679.489 157.048 79.6121 + endloop + endfacet + facet normal 0.827317 -0.468733 0.309572 + outer loop + vertex 678.463 153.836 77.5061 + vertex 679.884 156.537 77.7981 + vertex 678.079 154.374 79.3485 + endloop + endfacet + facet normal 0.821457 -0.467489 0.326593 + outer loop + vertex 678.463 153.836 77.5061 + vertex 680.307 156.016 75.9879 + vertex 679.884 156.537 77.7981 + endloop + endfacet + facet normal 0.821455 -0.469132 0.324232 + outer loop + vertex 678.89 153.31 75.6642 + vertex 680.307 156.016 75.9879 + vertex 678.463 153.836 77.5061 + endloop + endfacet + facet normal 0.815114 -0.467885 0.341574 + outer loop + vertex 678.89 153.31 75.6642 + vertex 680.779 155.506 74.163 + vertex 680.307 156.016 75.9879 + endloop + endfacet + facet normal 0.815144 -0.469137 0.33978 + outer loop + vertex 679.359 152.787 73.8166 + vertex 680.779 155.506 74.163 + vertex 678.89 153.31 75.6642 + endloop + endfacet + facet normal 0.807957 -0.467749 0.358352 + outer loop + vertex 679.359 152.787 73.8166 + vertex 681.306 154.993 72.3075 + vertex 680.779 155.506 74.163 + endloop + endfacet + facet normal 0.808 -0.468747 0.356949 + outer loop + vertex 679.891 152.28 71.947 + vertex 681.306 154.993 72.3075 + vertex 679.359 152.787 73.8166 + endloop + endfacet + facet normal 0.800608 -0.467296 0.375048 + outer loop + vertex 679.891 152.28 71.947 + vertex 681.901 154.495 70.4161 + vertex 681.306 154.993 72.3075 + endloop + endfacet + facet normal 0.800638 -0.467814 0.374338 + outer loop + vertex 680.47 151.764 70.063 + vertex 681.901 154.495 70.4161 + vertex 679.891 152.28 71.947 + endloop + endfacet + facet normal 0.792131 -0.465932 0.394253 + outer loop + vertex 680.47 151.764 70.063 + vertex 682.545 153.986 68.5208 + vertex 681.901 154.495 70.4161 + endloop + endfacet + facet normal 0.792265 -0.467702 0.391881 + outer loop + vertex 681.108 151.262 68.1751 + vertex 682.545 153.986 68.5208 + vertex 680.47 151.764 70.063 + endloop + endfacet + facet normal 0.783605 -0.4656 0.411315 + outer loop + vertex 681.108 151.262 68.1751 + vertex 683.239 153.514 66.6637 + vertex 682.545 153.986 68.5208 + endloop + endfacet + facet normal 0.783731 -0.466779 0.409736 + outer loop + vertex 681.783 150.774 66.3278 + vertex 683.239 153.514 66.6637 + vertex 681.108 151.262 68.1751 + endloop + endfacet + facet normal 0.774245 -0.46424 0.430146 + outer loop + vertex 681.783 150.774 66.3278 + vertex 683.96 153.072 64.8902 + vertex 683.239 153.514 66.6637 + endloop + endfacet + facet normal 0.7746 -0.466537 0.427011 + outer loop + vertex 682.49 150.324 64.5536 + vertex 683.96 153.072 64.8902 + vertex 681.783 150.774 66.3278 + endloop + endfacet + facet normal 0.763366 -0.463355 0.450083 + outer loop + vertex 682.49 150.324 64.5536 + vertex 684.693 152.651 63.2126 + vertex 683.96 153.072 64.8902 + endloop + endfacet + facet normal 0.764082 -0.466799 0.445284 + outer loop + vertex 683.205 149.88 62.8621 + vertex 684.693 152.651 63.2126 + vertex 682.49 150.324 64.5536 + endloop + endfacet + facet normal 0.751998 -0.463294 0.46889 + outer loop + vertex 683.205 149.88 62.8621 + vertex 685.449 152.257 61.6101 + vertex 684.693 152.651 63.2126 + endloop + endfacet + facet normal 0.752678 -0.465854 0.465249 + outer loop + vertex 683.95 149.459 61.2337 + vertex 685.449 152.257 61.6101 + vertex 683.205 149.88 62.8621 + endloop + endfacet + facet normal 0.739569 -0.46208 0.489408 + outer loop + vertex 683.95 149.459 61.2337 + vertex 686.265 151.89 60.0311 + vertex 685.449 152.257 61.6101 + endloop + endfacet + facet normal 0.740094 -0.463763 0.487017 + outer loop + vertex 684.754 149.047 59.6205 + vertex 686.265 151.89 60.0311 + vertex 683.95 149.459 61.2337 + endloop + endfacet + facet normal 0.726253 -0.459863 0.510963 + outer loop + vertex 684.754 149.047 59.6205 + vertex 687.158 151.53 58.4376 + vertex 686.265 151.89 60.0311 + endloop + endfacet + facet normal 0.7267 -0.461157 0.509157 + outer loop + vertex 685.644 148.66 57.9985 + vertex 687.158 151.53 58.4376 + vertex 684.754 149.047 59.6205 + endloop + endfacet + facet normal 0.712456 -0.457191 0.532337 + outer loop + vertex 685.644 148.66 57.9985 + vertex 688.141 151.191 56.8306 + vertex 687.158 151.53 58.4376 + endloop + endfacet + facet normal 0.712894 -0.458355 0.530748 + outer loop + vertex 686.625 148.301 56.3719 + vertex 688.141 151.191 56.8306 + vertex 685.644 148.66 57.9985 + endloop + endfacet + facet normal 0.698075 -0.454195 0.553533 + outer loop + vertex 686.625 148.301 56.3719 + vertex 689.209 150.902 55.2473 + vertex 688.141 151.191 56.8306 + endloop + endfacet + facet normal 0.698131 -0.454328 0.553353 + outer loop + vertex 687.708 148.008 54.7639 + vertex 689.209 150.902 55.2473 + vertex 686.625 148.301 56.3719 + endloop + endfacet + facet normal 0.682403 -0.449968 0.576069 + outer loop + vertex 687.708 148.008 54.7639 + vertex 690.355 150.709 53.7383 + vertex 689.209 150.902 55.2473 + endloop + endfacet + facet normal 0.681463 -0.448065 0.578658 + outer loop + vertex 688.881 147.768 53.1973 + vertex 690.355 150.709 53.7383 + vertex 687.708 148.008 54.7639 + endloop + endfacet + facet normal 0.661456 -0.442921 0.605225 + outer loop + vertex 688.881 147.768 53.1973 + vertex 691.541 150.545 52.3232 + vertex 690.355 150.709 53.7383 + endloop + endfacet + facet normal 0.661662 -0.443271 0.604743 + outer loop + vertex 690.086 147.518 51.6953 + vertex 691.541 150.545 52.3232 + vertex 688.881 147.768 53.1973 + endloop + endfacet + facet normal 0.638052 -0.437866 0.633374 + outer loop + vertex 690.086 147.518 51.6953 + vertex 692.706 150.344 51.0093 + vertex 691.541 150.545 52.3232 + endloop + endfacet + facet normal 0.639266 -0.439578 0.63096 + outer loop + vertex 691.232 147.091 50.2364 + vertex 692.706 150.344 51.0093 + vertex 690.086 147.518 51.6953 + endloop + endfacet + facet normal 0.607249 -0.433374 0.66591 + outer loop + vertex 691.232 147.091 50.2364 + vertex 693.718 149.878 49.784 + vertex 692.706 150.344 51.0093 + endloop + endfacet + facet normal 0.601705 -0.426951 0.675029 + outer loop + vertex 692.282 147.384 49.4857 + vertex 693.718 149.878 49.784 + vertex 691.232 147.091 50.2364 + endloop + endfacet + facet normal 0.60339 -0.427685 0.673057 + outer loop + vertex 692.282 147.384 49.4857 + vertex 692.937 147.446 48.9382 + vertex 693.718 149.878 49.784 + endloop + endfacet + facet normal 0.588501 -0.427489 0.686236 + outer loop + vertex 694.89 149.947 48.8217 + vertex 693.718 149.878 49.784 + vertex 692.937 147.446 48.9382 + endloop + endfacet + facet normal 0.598775 -0.436187 0.671721 + outer loop + vertex 693.358 147.026 48.2909 + vertex 694.89 149.947 48.8217 + vertex 692.937 147.446 48.9382 + endloop + endfacet + facet normal 0.575877 -0.428617 0.696171 + outer loop + vertex 693.358 147.026 48.2909 + vertex 694.208 147.537 47.9014 + vertex 694.89 149.947 48.8217 + endloop + endfacet + facet normal 0.576075 -0.428611 0.69601 + outer loop + vertex 695.911 150.521 48.3301 + vertex 694.89 149.947 48.8217 + vertex 694.208 147.537 47.9014 + endloop + endfacet + facet normal 0.575974 -0.428569 0.696119 + outer loop + vertex 694.777 147.621 47.4836 + vertex 695.911 150.521 48.3301 + vertex 694.208 147.537 47.9014 + endloop + endfacet + facet normal 0.561274 -0.426634 0.709193 + outer loop + vertex 694.777 147.621 47.4836 + vertex 696.276 150.513 48.0363 + vertex 695.911 150.521 48.3301 + endloop + endfacet + facet normal 0.589719 -0.435793 0.679938 + outer loop + vertex 694.953 147.392 47.1834 + vertex 696.276 150.513 48.0363 + vertex 694.777 147.621 47.4836 + endloop + endfacet + facet normal 0.59424 -0.436505 0.675531 + outer loop + vertex 694.953 147.392 47.1834 + vertex 696.334 150.345 47.8768 + vertex 696.276 150.513 48.0363 + endloop + endfacet + facet normal 0.590141 -0.43557 0.679715 + outer loop + vertex 694.989 147.193 47.0251 + vertex 696.334 150.345 47.8768 + vertex 694.953 147.392 47.1834 + endloop + endfacet + facet normal 0.772229 -0.450644 0.447864 + outer loop + vertex 694.989 147.193 47.0251 + vertex 696.318 150.248 47.8074 + vertex 696.334 150.345 47.8768 + endloop + endfacet + facet normal 0.598994 -0.433058 0.673548 + outer loop + vertex 695.013 147.133 46.9646 + vertex 696.318 150.248 47.8074 + vertex 694.989 147.193 47.0251 + endloop + endfacet + facet normal 0.925946 -0.348171 -0.146294 + outer loop + vertex 695.013 147.133 46.9646 + vertex 696.356 150.352 47.803 + vertex 696.318 150.248 47.8074 + endloop + endfacet + facet normal 0.627651 -0.430727 0.648482 + outer loop + vertex 695.071 147.203 46.9552 + vertex 696.356 150.352 47.803 + vertex 695.013 147.133 46.9646 + endloop + endfacet + facet normal 0.763924 -0.439076 0.472898 + outer loop + vertex 695.071 147.203 46.9552 + vertex 696.458 150.535 47.8083 + vertex 696.356 150.352 47.803 + endloop + endfacet + facet normal 0.600788 -0.423651 0.677919 + outer loop + vertex 695.163 147.289 46.9275 + vertex 696.458 150.535 47.8083 + vertex 695.071 147.203 46.9552 + endloop + endfacet + facet normal 0.611491 -0.425064 0.667382 + outer loop + vertex 695.163 147.289 46.9275 + vertex 696.496 150.453 47.7213 + vertex 696.458 150.535 47.8083 + endloop + endfacet + facet normal 0.652153 -0.43119 0.623515 + outer loop + vertex 695.121 147.004 46.7744 + vertex 696.496 150.453 47.7213 + vertex 695.163 147.289 46.9275 + endloop + endfacet + facet normal 0.561575 -0.419681 0.713093 + outer loop + vertex 695.121 147.004 46.7744 + vertex 696.206 149.509 47.3945 + vertex 696.496 150.453 47.7213 + endloop + endfacet + facet normal 0.871804 -0.433816 0.227511 + outer loop + vertex 694.675 145.917 46.4103 + vertex 696.206 149.509 47.3945 + vertex 695.121 147.004 46.7744 + endloop + endfacet + facet normal 0.897333 -0.434108 0.0796486 + outer loop + vertex 673.324 166.549 139.649 + vertex 675.462 171.112 140.44 + vertex 673.105 166.712 143.013 + endloop + endfacet + facet normal 0.896175 -0.437765 0.072332 + outer loop + vertex 673.105 166.712 143.013 + vertex 675.462 171.112 140.44 + vertex 675.501 171.911 144.792 + endloop + endfacet + facet normal 0.899374 -0.433598 0.0558526 + outer loop + vertex 673.105 166.712 143.013 + vertex 675.501 171.911 144.792 + vertex 673.052 167.215 147.772 + endloop + endfacet + facet normal 0.898837 -0.435051 0.0531233 + outer loop + vertex 673.052 167.215 147.772 + vertex 675.501 171.911 144.792 + vertex 675.493 172.393 148.88 + endloop + endfacet + facet normal 0.900273 -0.433311 0.0418287 + outer loop + vertex 673.052 167.215 147.772 + vertex 675.493 172.393 148.88 + vertex 673.257 168.022 151.715 + endloop + endfacet + facet normal 0.900691 -0.432246 0.0438001 + outer loop + vertex 673.257 168.022 151.715 + vertex 675.493 172.393 148.88 + vertex 675.472 172.741 152.735 + endloop + endfacet + facet normal 0.901376 -0.431352 0.0381724 + outer loop + vertex 673.257 168.022 151.715 + vertex 675.472 172.741 152.735 + vertex 673.196 168.225 155.437 + endloop + endfacet + facet normal 0.901094 -0.432064 0.0367431 + outer loop + vertex 673.196 168.225 155.437 + vertex 675.472 172.741 152.735 + vertex 675.401 172.919 156.582 + endloop + endfacet + facet normal 0.901411 -0.431607 0.0342573 + outer loop + vertex 673.196 168.225 155.437 + vertex 675.401 172.919 156.582 + vertex 672.923 167.964 159.349 + endloop + endfacet + facet normal 0.900294 -0.434359 0.0283281 + outer loop + vertex 672.923 167.964 159.349 + vertex 675.401 172.919 156.582 + vertex 675.376 173.12 160.461 + endloop + endfacet + facet normal 0.901376 -0.432661 0.01807 + outer loop + vertex 672.923 167.964 159.349 + vertex 675.376 173.12 160.461 + vertex 673.155 168.612 163.262 + endloop + endfacet + facet normal 0.901641 -0.432057 0.0192527 + outer loop + vertex 673.155 168.612 163.262 + vertex 675.376 173.12 160.461 + vertex 675.393 173.328 164.336 + endloop + endfacet + facet normal 0.90218 -0.431131 0.0140666 + outer loop + vertex 673.155 168.612 163.262 + vertex 675.393 173.328 164.336 + vertex 673.152 168.729 167.105 + endloop + endfacet + facet normal 0.901938 -0.431671 0.0129752 + outer loop + vertex 673.152 168.729 167.105 + vertex 675.393 173.328 164.336 + vertex 675.351 173.359 168.275 + endloop + endfacet + facet normal 0.902205 -0.431179 0.0105283 + outer loop + vertex 673.152 168.729 167.105 + vertex 675.351 173.359 168.275 + vertex 672.901 168.305 171.248 + endloop + endfacet + facet normal 0.900922 -0.433955 0.00475047 + outer loop + vertex 672.901 168.305 171.248 + vertex 675.351 173.359 168.275 + vertex 675.339 173.379 172.235 + endloop + endfacet + facet normal 0.901717 -0.432289 -0.00578027 + outer loop + vertex 672.901 168.305 171.248 + vertex 675.339 173.379 172.235 + vertex 673.112 168.694 175.083 + endloop + endfacet + facet normal 0.901834 -0.43205 -0.00529534 + outer loop + vertex 673.112 168.694 175.083 + vertex 675.339 173.379 172.235 + vertex 675.363 173.38 176.134 + endloop + endfacet + facet normal 0.902224 -0.431148 -0.010153 + outer loop + vertex 673.112 168.694 175.083 + vertex 675.363 173.38 176.134 + vertex 673.123 168.631 178.809 + endloop + endfacet + facet normal 0.901797 -0.431993 -0.0120115 + outer loop + vertex 673.123 168.631 178.809 + vertex 675.363 173.38 176.134 + vertex 675.347 173.239 179.998 + endloop + endfacet + facet normal 0.902081 -0.431297 -0.0152425 + outer loop + vertex 673.123 168.631 178.809 + vertex 675.347 173.239 179.998 + vertex 672.937 168.103 182.709 + endloop + endfacet + facet normal 0.900615 -0.43407 -0.0218003 + outer loop + vertex 672.937 168.103 182.709 + vertex 675.347 173.239 179.998 + vertex 675.394 173.146 183.815 + endloop + endfacet + facet normal 0.90127 -0.432036 -0.0325249 + outer loop + vertex 672.937 168.103 182.709 + vertex 675.394 173.146 183.815 + vertex 673.262 168.486 186.634 + endloop + endfacet + facet normal 0.901328 -0.43193 -0.0323047 + outer loop + vertex 673.262 168.486 186.634 + vertex 675.394 173.146 183.815 + vertex 675.506 173.093 187.644 + endloop + endfacet + facet normal 0.901495 -0.431345 -0.0353425 + outer loop + vertex 673.262 168.486 186.634 + vertex 675.506 173.093 187.644 + vertex 673.247 168.107 190.868 + endloop + endfacet + facet normal 0.899667 -0.434587 -0.0416363 + outer loop + vertex 673.247 168.107 190.868 + vertex 675.506 173.093 187.644 + vertex 675.661 173.053 191.406 + endloop + endfacet + facet normal 0.899658 -0.43321 -0.0542566 + outer loop + vertex 673.247 168.107 190.868 + vertex 675.661 173.053 191.406 + vertex 673.64 168.505 194.211 + endloop + endfacet + facet normal 0.900631 -0.43159 -0.0509277 + outer loop + vertex 675.777 172.892 194.821 + vertex 673.64 168.505 194.211 + vertex 675.661 173.053 191.406 + endloop + endfacet + facet normal 0.900666 -0.430088 -0.0618462 + outer loop + vertex 673.64 168.505 194.211 + vertex 675.777 172.892 194.821 + vertex 673.79 168.445 196.808 + endloop + endfacet + facet normal 0.900057 -0.43098 -0.0644501 + outer loop + vertex 673.79 168.445 196.808 + vertex 675.777 172.892 194.821 + vertex 675.51 171.923 197.569 + endloop + endfacet + facet normal 0.89998 -0.431543 -0.0617033 + outer loop + vertex 673.79 168.445 196.808 + vertex 675.51 171.923 197.569 + vertex 673.826 168.203 199.031 + endloop + endfacet + facet normal 0.900995 -0.43009 -0.0568372 + outer loop + vertex 673.826 168.203 199.031 + vertex 675.51 171.923 197.569 + vertex 675.504 171.623 199.743 + endloop + endfacet + facet normal 0.901057 -0.429666 -0.0590171 + outer loop + vertex 673.826 168.203 199.031 + vertex 675.504 171.623 199.743 + vertex 673.878 168.032 201.065 + endloop + endfacet + facet normal 0.901177 -0.429498 -0.0584133 + outer loop + vertex 673.878 168.032 201.065 + vertex 675.504 171.623 199.743 + vertex 675.546 171.44 201.733 + endloop + endfacet + facet normal 0.901217 -0.429166 -0.0602094 + outer loop + vertex 673.878 168.032 201.065 + vertex 675.546 171.44 201.733 + vertex 673.924 167.856 203.008 + endloop + endfacet + facet normal 0.900931 -0.429558 -0.0616744 + outer loop + vertex 673.924 167.856 203.008 + vertex 675.546 171.44 201.733 + vertex 675.586 171.251 203.64 + endloop + endfacet + facet normal 0.900977 -0.42901 -0.0647406 + outer loop + vertex 673.924 167.856 203.008 + vertex 675.586 171.251 203.64 + vertex 673.949 167.622 204.905 + endloop + endfacet + facet normal 0.900049 -0.430224 -0.0694225 + outer loop + vertex 673.949 167.622 204.905 + vertex 675.586 171.251 203.64 + vertex 675.611 171.003 205.498 + endloop + endfacet + facet normal 0.900052 -0.430124 -0.0700035 + outer loop + vertex 673.949 167.622 204.905 + vertex 675.611 171.003 205.498 + vertex 673.979 167.381 206.776 + endloop + endfacet + facet normal 0.900021 -0.430164 -0.0701551 + outer loop + vertex 673.979 167.381 206.776 + vertex 675.611 171.003 205.498 + vertex 675.643 170.771 207.335 + endloop + endfacet + facet normal 0.900014 -0.429388 -0.0748381 + outer loop + vertex 673.979 167.381 206.776 + vertex 675.643 170.771 207.335 + vertex 674.008 167.115 208.65 + endloop + endfacet + facet normal 0.899278 -0.430309 -0.078316 + outer loop + vertex 674.008 167.115 208.65 + vertex 675.643 170.771 207.335 + vertex 675.677 170.503 209.196 + endloop + endfacet + facet normal 0.899273 -0.430213 -0.078899 + outer loop + vertex 674.008 167.115 208.65 + vertex 675.677 170.503 209.196 + vertex 674.041 166.83 210.577 + endloop + endfacet + facet normal 0.899118 -0.430407 -0.079601 + outer loop + vertex 674.041 166.83 210.577 + vertex 675.677 170.503 209.196 + vertex 675.719 170.233 211.13 + endloop + endfacet + facet normal 0.8991 -0.430083 -0.0815375 + outer loop + vertex 674.041 166.83 210.577 + vertex 675.719 170.233 211.13 + vertex 674.087 166.548 212.575 + endloop + endfacet + facet normal 0.89814 -0.431282 -0.0856778 + outer loop + vertex 674.087 166.548 212.575 + vertex 675.719 170.233 211.13 + vertex 675.759 169.916 213.142 + endloop + endfacet + facet normal 0.898125 -0.43107 -0.0868931 + outer loop + vertex 674.087 166.548 212.575 + vertex 675.759 169.916 213.142 + vertex 674.126 166.216 214.62 + endloop + endfacet + facet normal 0.897907 -0.431339 -0.0878071 + outer loop + vertex 674.126 166.216 214.62 + vertex 675.759 169.916 213.142 + vertex 675.809 169.603 215.199 + endloop + endfacet + facet normal 0.897857 -0.430718 -0.0912932 + outer loop + vertex 674.126 166.216 214.62 + vertex 675.809 169.603 215.199 + vertex 674.173 165.881 216.662 + endloop + endfacet + facet normal 0.897363 -0.431307 -0.093346 + outer loop + vertex 674.173 165.881 216.662 + vertex 675.809 169.603 215.199 + vertex 675.858 169.264 217.241 + endloop + endfacet + facet normal 0.897325 -0.430935 -0.0954125 + outer loop + vertex 674.173 165.881 216.662 + vertex 675.858 169.264 217.241 + vertex 674.227 165.553 218.653 + endloop + endfacet + facet normal 0.896425 -0.431962 -0.0991496 + outer loop + vertex 674.227 165.553 218.653 + vertex 675.858 169.264 217.241 + vertex 675.903 168.9 219.224 + endloop + endfacet + facet normal 0.896388 -0.431675 -0.100726 + outer loop + vertex 674.227 165.553 218.653 + vertex 675.903 168.9 219.224 + vertex 674.271 165.194 220.586 + endloop + endfacet + facet normal 0.895985 -0.432115 -0.102406 + outer loop + vertex 674.271 165.194 220.586 + vertex 675.903 168.9 219.224 + vertex 675.958 168.56 221.145 + endloop + endfacet + facet normal 0.895904 -0.431605 -0.105232 + outer loop + vertex 674.271 165.194 220.586 + vertex 675.958 168.56 221.145 + vertex 674.332 164.859 222.48 + endloop + endfacet + facet normal 0.895356 -0.432182 -0.107499 + outer loop + vertex 674.332 164.859 222.48 + vertex 675.958 168.56 221.145 + vertex 676.019 168.217 223.03 + endloop + endfacet + facet normal 0.895247 -0.431611 -0.110655 + outer loop + vertex 674.332 164.859 222.48 + vertex 676.019 168.217 223.03 + vertex 674.395 164.505 224.37 + endloop + endfacet + facet normal 0.894422 -0.432453 -0.113989 + outer loop + vertex 674.395 164.505 224.37 + vertex 676.019 168.217 223.03 + vertex 676.078 167.842 224.915 + endloop + endfacet + facet normal 0.894341 -0.432082 -0.11601 + outer loop + vertex 674.395 164.505 224.37 + vertex 676.078 167.842 224.915 + vertex 674.453 164.114 226.276 + endloop + endfacet + facet normal 0.894042 -0.432383 -0.117191 + outer loop + vertex 674.453 164.114 226.276 + vertex 676.078 167.842 224.915 + vertex 676.142 167.456 226.825 + endloop + endfacet + facet normal 0.893883 -0.431698 -0.120874 + outer loop + vertex 674.453 164.114 226.276 + vertex 676.142 167.456 226.825 + vertex 674.518 163.707 228.207 + endloop + endfacet + facet normal 0.892928 -0.432633 -0.124532 + outer loop + vertex 674.518 163.707 228.207 + vertex 676.142 167.456 226.825 + vertex 676.208 167.035 228.763 + endloop + endfacet + facet normal 0.892847 -0.432307 -0.126234 + outer loop + vertex 674.518 163.707 228.207 + vertex 676.208 167.035 228.763 + vertex 674.594 163.296 230.149 + endloop + endfacet + facet normal 0.892332 -0.432802 -0.128168 + outer loop + vertex 674.594 163.296 230.149 + vertex 676.208 167.035 228.763 + vertex 676.288 166.625 230.708 + endloop + endfacet + facet normal 0.892071 -0.431832 -0.133153 + outer loop + vertex 674.594 163.296 230.149 + vertex 676.288 166.625 230.708 + vertex 674.67 162.859 232.081 + endloop + endfacet + facet normal 0.891197 -0.432632 -0.136376 + outer loop + vertex 674.67 162.859 232.081 + vertex 676.288 166.625 230.708 + vertex 676.373 166.194 232.626 + endloop + endfacet + facet normal 0.891106 -0.432337 -0.137897 + outer loop + vertex 674.67 162.859 232.081 + vertex 676.373 166.194 232.626 + vertex 674.773 162.469 233.968 + endloop + endfacet + facet normal 0.889882 -0.433414 -0.142344 + outer loop + vertex 674.773 162.469 233.968 + vertex 676.373 166.194 232.626 + vertex 676.465 165.772 234.487 + endloop + endfacet + facet normal 0.889666 -0.432806 -0.14551 + outer loop + vertex 674.773 162.469 233.968 + vertex 676.465 165.772 234.487 + vertex 674.866 162.044 235.801 + endloop + endfacet + facet normal 0.888411 -0.43385 -0.15 + outer loop + vertex 674.866 162.044 235.801 + vertex 676.465 165.772 234.487 + vertex 676.564 165.353 236.287 + endloop + endfacet + facet normal 0.888263 -0.433498 -0.151884 + outer loop + vertex 674.866 162.044 235.801 + vertex 676.564 165.353 236.287 + vertex 674.971 161.635 237.584 + endloop + endfacet + facet normal 0.887101 -0.434425 -0.155969 + outer loop + vertex 674.971 161.635 237.584 + vertex 676.564 165.353 236.287 + vertex 676.671 164.938 238.05 + endloop + endfacet + facet normal 0.886816 -0.433814 -0.159259 + outer loop + vertex 674.971 161.635 237.584 + vertex 676.671 164.938 238.05 + vertex 675.078 161.205 239.349 + endloop + endfacet + facet normal 0.886151 -0.434325 -0.161546 + outer loop + vertex 675.078 161.205 239.349 + vertex 676.671 164.938 238.05 + vertex 676.791 164.524 239.821 + endloop + endfacet + facet normal 0.885736 -0.43347 -0.166058 + outer loop + vertex 675.078 161.205 239.349 + vertex 676.791 164.524 239.821 + vertex 675.204 160.777 241.139 + endloop + endfacet + facet normal 0.884115 -0.434679 -0.17145 + outer loop + vertex 675.204 160.777 241.139 + vertex 676.791 164.524 239.821 + vertex 676.916 164.064 241.631 + endloop + endfacet + facet normal 0.883857 -0.434147 -0.174106 + outer loop + vertex 675.204 160.777 241.139 + vertex 676.916 164.064 241.631 + vertex 675.332 160.301 242.976 + endloop + endfacet + facet normal 0.882561 -0.435092 -0.178275 + outer loop + vertex 675.332 160.301 242.976 + vertex 676.916 164.064 241.631 + vertex 677.064 163.601 243.494 + endloop + endfacet + facet normal 0.882139 -0.434215 -0.18245 + outer loop + vertex 675.332 160.301 242.976 + vertex 677.064 163.601 243.494 + vertex 675.487 159.821 244.865 + endloop + endfacet + facet normal 0.880161 -0.43561 -0.188574 + outer loop + vertex 675.487 159.821 244.865 + vertex 677.064 163.601 243.494 + vertex 677.225 163.107 245.39 + endloop + endfacet + facet normal 0.879719 -0.434728 -0.192629 + outer loop + vertex 675.487 159.821 244.865 + vertex 677.225 163.107 245.39 + vertex 675.661 159.324 246.786 + endloop + endfacet + facet normal 0.878465 -0.435589 -0.196368 + outer loop + vertex 675.661 159.324 246.786 + vertex 677.225 163.107 245.39 + vertex 677.411 162.623 247.294 + endloop + endfacet + facet normal 0.877757 -0.4343 -0.202302 + outer loop + vertex 675.661 159.324 246.786 + vertex 677.411 162.623 247.294 + vertex 675.851 158.805 248.722 + endloop + endfacet + facet normal 0.877644 -0.434376 -0.20263 + outer loop + vertex 675.851 158.805 248.722 + vertex 677.411 162.623 247.294 + vertex 677.627 162.171 249.197 + endloop + endfacet + facet normal 0.876852 -0.433103 -0.208693 + outer loop + vertex 675.851 158.805 248.722 + vertex 677.627 162.171 249.197 + vertex 676.092 158.358 250.664 + endloop + endfacet + facet normal 0.875276 -0.434155 -0.213077 + outer loop + vertex 676.092 158.358 250.664 + vertex 677.627 162.171 249.197 + vertex 677.863 161.701 251.126 + endloop + endfacet + facet normal 0.874349 -0.432762 -0.219615 + outer loop + vertex 676.092 158.358 250.664 + vertex 677.863 161.701 251.126 + vertex 676.343 157.873 252.615 + endloop + endfacet + facet normal 0.870618 -0.435135 -0.229526 + outer loop + vertex 676.343 157.873 252.615 + vertex 677.863 161.701 251.126 + vertex 678.082 161.072 253.148 + endloop + endfacet + facet normal 0.869958 -0.434013 -0.234106 + outer loop + vertex 676.343 157.873 252.615 + vertex 678.082 161.072 253.148 + vertex 676.567 157.269 254.57 + endloop + endfacet + facet normal 0.857983 -0.440505 -0.264236 + outer loop + vertex 676.567 157.269 254.57 + vertex 678.082 161.072 253.148 + vertex 678.069 159.824 255.187 + endloop + endfacet + facet normal 0.859584 -0.444302 -0.252411 + outer loop + vertex 676.567 157.269 254.57 + vertex 678.069 159.824 255.187 + vertex 676.719 156.493 256.45 + endloop + endfacet + facet normal 0.84161 -0.45289 -0.294249 + outer loop + vertex 676.719 156.493 256.45 + vertex 678.069 159.824 255.187 + vertex 677.853 158.335 256.861 + endloop + endfacet + facet normal 0.846413 -0.46267 -0.263668 + outer loop + vertex 676.719 156.493 256.45 + vertex 677.853 158.335 256.861 + vertex 676.964 155.937 258.215 + endloop + endfacet + facet normal 0.850263 -0.459838 -0.25613 + outer loop + vertex 676.964 155.937 258.215 + vertex 677.853 158.335 256.861 + vertex 678.347 158.486 258.23 + endloop + endfacet + facet normal 0.84774 -0.458408 -0.266831 + outer loop + vertex 676.964 155.937 258.215 + vertex 678.347 158.486 258.23 + vertex 677.333 155.59 259.982 + endloop + endfacet + facet normal 0.847579 -0.458533 -0.26713 + outer loop + vertex 677.333 155.59 259.982 + vertex 678.347 158.486 258.23 + vertex 678.77 158.25 259.977 + endloop + endfacet + facet normal 0.844405 -0.456838 -0.279785 + outer loop + vertex 677.333 155.59 259.982 + vertex 678.77 158.25 259.977 + vertex 677.679 155.106 261.816 + endloop + endfacet + facet normal 0.842848 -0.457961 -0.282628 + outer loop + vertex 677.679 155.106 261.816 + vertex 678.77 158.25 259.977 + vertex 679.108 157.742 261.806 + endloop + endfacet + facet normal 0.83961 -0.456252 -0.294771 + outer loop + vertex 677.679 155.106 261.816 + vertex 679.108 157.742 261.806 + vertex 678.018 154.546 263.648 + endloop + endfacet + facet normal 0.836414 -0.458424 -0.300431 + outer loop + vertex 678.018 154.546 263.648 + vertex 679.108 157.742 261.806 + vertex 679.442 157.164 263.621 + endloop + endfacet + facet normal 0.833741 -0.457065 -0.309785 + outer loop + vertex 678.018 154.546 263.648 + vertex 679.442 157.164 263.621 + vertex 678.38 153.99 265.445 + endloop + endfacet + facet normal 0.831545 -0.458495 -0.313553 + outer loop + vertex 678.38 153.99 265.445 + vertex 679.442 157.164 263.621 + vertex 679.827 156.635 265.413 + endloop + endfacet + facet normal 0.828523 -0.456964 -0.323627 + outer loop + vertex 678.38 153.99 265.445 + vertex 679.827 156.635 265.413 + vertex 678.8 153.494 267.221 + endloop + endfacet + facet normal 0.827144 -0.457832 -0.325919 + outer loop + vertex 678.8 153.494 267.221 + vertex 679.827 156.635 265.413 + vertex 680.268 156.154 267.208 + endloop + endfacet + facet normal 0.823438 -0.455845 -0.337869 + outer loop + vertex 678.8 153.494 267.221 + vertex 680.268 156.154 267.208 + vertex 679.261 153.004 269.005 + endloop + endfacet + facet normal 0.822044 -0.456685 -0.340122 + outer loop + vertex 679.261 153.004 269.005 + vertex 680.268 156.154 267.208 + vertex 680.75 155.673 269.02 + endloop + endfacet + facet normal 0.818055 -0.454389 -0.352587 + outer loop + vertex 679.261 153.004 269.005 + vertex 680.75 155.673 269.02 + vertex 679.773 152.528 270.807 + endloop + endfacet + facet normal 0.814498 -0.456435 -0.358133 + outer loop + vertex 679.773 152.528 270.807 + vertex 680.75 155.673 269.02 + vertex 681.272 155.168 270.852 + endloop + endfacet + facet normal 0.810845 -0.454175 -0.369127 + outer loop + vertex 679.773 152.528 270.807 + vertex 681.272 155.168 270.852 + vertex 680.327 152.024 272.642 + endloop + endfacet + facet normal 0.807685 -0.455924 -0.373868 + outer loop + vertex 680.327 152.024 272.642 + vertex 681.272 155.168 270.852 + vertex 681.842 154.673 272.687 + endloop + endfacet + facet normal 0.803005 -0.453018 -0.387244 + outer loop + vertex 680.327 152.024 272.642 + vertex 681.842 154.673 272.687 + vertex 680.94 151.538 274.482 + endloop + endfacet + facet normal 0.799322 -0.454982 -0.392525 + outer loop + vertex 680.94 151.538 274.482 + vertex 681.842 154.673 272.687 + vertex 682.462 154.186 274.513 + endloop + endfacet + facet normal 0.79403 -0.45177 -0.406719 + outer loop + vertex 680.94 151.538 274.482 + vertex 682.462 154.186 274.513 + vertex 681.599 151.04 276.323 + endloop + endfacet + facet normal 0.790736 -0.453461 -0.411229 + outer loop + vertex 681.599 151.04 276.323 + vertex 682.462 154.186 274.513 + vertex 683.13 153.711 276.321 + endloop + endfacet + facet normal 0.784759 -0.450042 -0.426164 + outer loop + vertex 681.599 151.04 276.323 + vertex 683.13 153.711 276.321 + vertex 682.315 150.57 278.137 + endloop + endfacet + facet normal 0.781054 -0.451876 -0.431003 + outer loop + vertex 682.315 150.57 278.137 + vertex 683.13 153.711 276.321 + vertex 683.844 153.242 278.107 + endloop + endfacet + facet normal 0.774209 -0.448135 -0.446963 + outer loop + vertex 682.315 150.57 278.137 + vertex 683.844 153.242 278.107 + vertex 683.071 150.093 279.926 + endloop + endfacet + facet normal 0.770918 -0.449696 -0.451064 + outer loop + vertex 683.071 150.093 279.926 + vertex 683.844 153.242 278.107 + vertex 684.609 152.789 279.865 + endloop + endfacet + facet normal 0.762825 -0.445475 -0.468669 + outer loop + vertex 683.071 150.093 279.926 + vertex 684.609 152.789 279.865 + vertex 683.888 149.634 281.691 + endloop + endfacet + facet normal 0.760159 -0.446694 -0.47183 + outer loop + vertex 683.888 149.634 281.691 + vertex 684.609 152.789 279.865 + vertex 685.435 152.368 281.595 + endloop + endfacet + facet normal 0.750749 -0.442041 -0.490893 + outer loop + vertex 683.888 149.634 281.691 + vertex 685.435 152.368 281.595 + vertex 684.761 149.192 283.424 + endloop + endfacet + facet normal 0.747536 -0.443446 -0.494515 + outer loop + vertex 684.761 149.192 283.424 + vertex 685.435 152.368 281.595 + vertex 686.316 151.957 283.296 + endloop + endfacet + facet normal 0.736872 -0.43838 -0.514629 + outer loop + vertex 684.761 149.192 283.424 + vertex 686.316 151.957 283.296 + vertex 685.689 148.769 285.113 + endloop + endfacet + facet normal 0.733442 -0.4398 -0.518305 + outer loop + vertex 685.689 148.769 285.113 + vertex 686.316 151.957 283.296 + vertex 687.262 151.573 284.96 + endloop + endfacet + facet normal 0.721191 -0.434097 -0.539855 + outer loop + vertex 685.689 148.769 285.113 + vertex 687.262 151.573 284.96 + vertex 686.692 148.4 286.75 + endloop + endfacet + facet normal 0.716511 -0.435926 -0.544591 + outer loop + vertex 686.692 148.4 286.75 + vertex 687.262 151.573 284.96 + vertex 688.283 151.221 286.586 + endloop + endfacet + facet normal 0.702758 -0.429478 -0.567169 + outer loop + vertex 686.692 148.4 286.75 + vertex 688.283 151.221 286.586 + vertex 687.788 148.1 288.334 + endloop + endfacet + facet normal 0.699774 -0.430593 -0.570005 + outer loop + vertex 687.788 148.1 288.334 + vertex 688.283 151.221 286.586 + vertex 689.389 150.95 288.148 + endloop + endfacet + facet normal 0.684542 -0.423555 -0.593299 + outer loop + vertex 687.788 148.1 288.334 + vertex 689.389 150.95 288.148 + vertex 688.962 147.87 289.853 + endloop + endfacet + facet normal 0.681642 -0.424589 -0.595893 + outer loop + vertex 688.962 147.87 289.853 + vertex 689.389 150.95 288.148 + vertex 690.555 150.774 289.606 + endloop + endfacet + facet normal 0.665625 -0.417718 -0.618429 + outer loop + vertex 688.962 147.87 289.853 + vertex 690.555 150.774 289.606 + vertex 690.161 147.701 291.258 + endloop + endfacet + facet normal 0.662599 -0.418713 -0.621001 + outer loop + vertex 690.161 147.701 291.258 + vertex 690.555 150.774 289.606 + vertex 691.728 150.705 290.905 + endloop + endfacet + facet normal 0.643796 -0.411726 -0.644986 + outer loop + vertex 690.161 147.701 291.258 + vertex 691.728 150.705 290.905 + vertex 691.332 147.689 292.436 + endloop + endfacet + facet normal 0.64096 -0.412526 -0.647296 + outer loop + vertex 691.332 147.689 292.436 + vertex 691.728 150.705 290.905 + vertex 692.862 150.721 292.018 + endloop + endfacet + facet normal 0.619128 -0.405022 -0.672784 + outer loop + vertex 691.332 147.689 292.436 + vertex 692.862 150.721 292.018 + vertex 692.402 147.783 293.362 + endloop + endfacet + facet normal 0.62304 -0.404204 -0.669656 + outer loop + vertex 692.402 147.783 293.362 + vertex 692.862 150.721 292.018 + vertex 693.884 150.669 293 + endloop + endfacet + facet normal 0.60458 -0.397322 -0.690375 + outer loop + vertex 692.402 147.783 293.362 + vertex 693.884 150.669 293 + vertex 693.245 147.646 294.18 + endloop + endfacet + facet normal 0.590689 -0.431546 -0.681802 + outer loop + vertex 691.988 145.556 294.414 + vertex 692.402 147.783 293.362 + vertex 693.245 147.646 294.18 + endloop + endfacet + facet normal 0.578368 -0.425705 -0.695892 + outer loop + vertex 691.988 145.556 294.414 + vertex 693.245 147.646 294.18 + vertex 692.689 145.486 295.04 + endloop + endfacet + facet normal 0.568032 -0.452659 -0.687343 + outer loop + vertex 691.795 144.234 295.125 + vertex 691.988 145.556 294.414 + vertex 692.689 145.486 295.04 + endloop + endfacet + facet normal 0.564146 -0.450209 -0.692136 + outer loop + vertex 691.795 144.234 295.125 + vertex 692.689 145.486 295.04 + vertex 692.349 144.116 295.654 + endloop + endfacet + facet normal 0.554475 -0.470391 -0.686506 + outer loop + vertex 691.795 144.234 295.125 + vertex 692.349 144.116 295.654 + vertex 691.363 143.311 295.408 + endloop + endfacet + facet normal 0.568334 -0.472843 -0.673362 + outer loop + vertex 691.795 144.234 295.125 + vertex 691.363 143.311 295.408 + vertex 691.019 144.085 294.575 + endloop + endfacet + facet normal 0.585794 -0.459141 -0.667858 + outer loop + vertex 691.363 143.311 295.408 + vertex 690.058 143.531 294.113 + vertex 691.019 144.085 294.575 + endloop + endfacet + facet normal 0.586832 -0.465219 -0.662721 + outer loop + vertex 690.42 144.256 293.924 + vertex 691.019 144.085 294.575 + vertex 690.058 143.531 294.113 + endloop + endfacet + facet normal 0.602503 -0.468678 -0.646012 + outer loop + vertex 690.42 144.256 293.924 + vertex 690.058 143.531 294.113 + vertex 689.914 145.187 292.777 + endloop + endfacet + facet normal 0.608775 -0.463036 -0.644198 + outer loop + vertex 690.42 144.256 293.924 + vertex 689.914 145.187 292.777 + vertex 691.107 145.489 293.687 + endloop + endfacet + facet normal 0.612886 -0.437312 -0.658125 + outer loop + vertex 689.914 145.187 292.777 + vertex 691.332 147.689 292.436 + vertex 691.107 145.489 293.687 + endloop + endfacet + facet normal 0.610709 -0.437985 -0.6597 + outer loop + vertex 692.402 147.783 293.362 + vertex 691.107 145.489 293.687 + vertex 691.332 147.689 292.436 + endloop + endfacet + facet normal 0.591121 -0.457121 -0.664542 + outer loop + vertex 690.42 144.256 293.924 + vertex 691.107 145.489 293.687 + vertex 691.019 144.085 294.575 + endloop + endfacet + facet normal 0.585863 -0.458939 -0.667937 + outer loop + vertex 691.019 144.085 294.575 + vertex 691.107 145.489 293.687 + vertex 691.988 145.556 294.414 + endloop + endfacet + facet normal 0.557798 -0.516826 -0.649425 + outer loop + vertex 690.662 142.907 295.128 + vertex 690.058 143.531 294.113 + vertex 691.363 143.311 295.408 + endloop + endfacet + facet normal 0.551202 -0.484821 -0.679062 + outer loop + vertex 690.662 142.907 295.128 + vertex 691.363 143.311 295.408 + vertex 691.931 143.064 296.046 + endloop + endfacet + facet normal -0.461228 0.723377 0.513804 + outer loop + vertex 690.662 142.907 295.128 + vertex 691.931 143.064 296.046 + vertex 690.686 142.952 295.086 + endloop + endfacet + facet normal -0.509928 0.627675 0.588216 + outer loop + vertex 693.645 143.512 297.054 + vertex 690.686 142.952 295.086 + vertex 691.931 143.064 296.046 + endloop + endfacet + facet normal 0.551029 -0.485089 -0.679011 + outer loop + vertex 691.931 143.064 296.046 + vertex 691.363 143.311 295.408 + vertex 692.448 143.558 296.112 + endloop + endfacet + facet normal 0.555399 -0.490699 -0.671376 + outer loop + vertex 691.931 143.064 296.046 + vertex 692.448 143.558 296.112 + vertex 693.193 143.896 296.482 + endloop + endfacet + facet normal 0.537997 -0.438901 -0.71967 + outer loop + vertex 691.931 143.064 296.046 + vertex 693.193 143.896 296.482 + vertex 693.645 143.512 297.054 + endloop + endfacet + facet normal 0.544008 -0.431639 -0.719543 + outer loop + vertex 693.645 143.512 297.054 + vertex 693.193 143.896 296.482 + vertex 694.191 145.258 296.42 + endloop + endfacet + facet normal 0.56571 -0.446334 -0.693368 + outer loop + vertex 693.193 143.896 296.482 + vertex 694.056 145.334 296.26 + vertex 694.191 145.258 296.42 + endloop + endfacet + facet normal 0.575935 -0.450711 -0.682025 + outer loop + vertex 694.056 145.334 296.26 + vertex 693.193 143.896 296.482 + vertex 693.473 144.69 296.194 + endloop + endfacet + facet normal 0.546177 -0.419357 -0.725141 + outer loop + vertex 693.473 144.69 296.194 + vertex 694.687 147.065 295.734 + vertex 694.056 145.334 296.26 + endloop + endfacet + facet normal 0.582489 -0.423127 -0.694024 + outer loop + vertex 694.056 145.334 296.26 + vertex 694.687 147.065 295.734 + vertex 695.116 147.448 295.861 + endloop + endfacet + facet normal 0.581298 -0.42276 -0.695246 + outer loop + vertex 694.056 145.334 296.26 + vertex 695.116 147.448 295.861 + vertex 694.191 145.258 296.42 + endloop + endfacet + facet normal 0.611034 -0.427856 -0.666016 + outer loop + vertex 694.191 145.258 296.42 + vertex 695.116 147.448 295.861 + vertex 695.286 147.486 295.993 + endloop + endfacet + facet normal 0.55209 -0.449637 -0.702156 + outer loop + vertex 692.448 143.558 296.112 + vertex 693.473 144.69 296.194 + vertex 693.193 143.896 296.482 + endloop + endfacet + facet normal 0.579835 -0.477799 -0.659924 + outer loop + vertex 693.02 144.432 295.982 + vertex 693.473 144.69 296.194 + vertex 692.448 143.558 296.112 + endloop + endfacet + facet normal 0.55675 -0.466757 -0.687144 + outer loop + vertex 693.02 144.432 295.982 + vertex 692.448 143.558 296.112 + vertex 692.349 144.116 295.654 + endloop + endfacet + facet normal 0.554396 -0.445036 -0.70327 + outer loop + vertex 692.349 144.116 295.654 + vertex 693.305 145.537 295.508 + vertex 693.02 144.432 295.982 + endloop + endfacet + facet normal 0.572023 -0.4438 -0.689805 + outer loop + vertex 693.02 144.432 295.982 + vertex 693.305 145.537 295.508 + vertex 693.898 145.873 295.783 + endloop + endfacet + facet normal 0.567023 -0.419157 -0.709078 + outer loop + vertex 693.305 145.537 295.508 + vertex 694.336 147.534 295.151 + vertex 693.898 145.873 295.783 + endloop + endfacet + facet normal 0.571943 -0.418987 -0.705218 + outer loop + vertex 693.898 145.873 295.783 + vertex 694.336 147.534 295.151 + vertex 694.646 147.452 295.452 + endloop + endfacet + facet normal 0.604137 -0.427388 -0.672576 + outer loop + vertex 694.646 147.452 295.452 + vertex 694.687 147.065 295.734 + vertex 693.898 145.873 295.783 + endloop + endfacet + facet normal 0.584663 -0.42504 -0.691021 + outer loop + vertex 693.305 145.537 295.508 + vertex 693.683 147.121 294.853 + vertex 694.336 147.534 295.151 + endloop + endfacet + facet normal 0.575961 -0.392438 -0.71712 + outer loop + vertex 693.683 147.121 294.853 + vertex 694.695 150.088 294.043 + vertex 694.336 147.534 295.151 + endloop + endfacet + facet normal 0.594092 -0.389268 -0.703935 + outer loop + vertex 694.695 150.088 294.043 + vertex 695.486 149.965 294.778 + vertex 694.336 147.534 295.151 + endloop + endfacet + facet normal 0.586584 -0.386876 -0.71151 + outer loop + vertex 694.646 147.452 295.452 + vertex 694.336 147.534 295.151 + vertex 695.486 149.965 294.778 + endloop + endfacet + facet normal 0.666062 -0.392731 -0.634132 + outer loop + vertex 694.646 147.452 295.452 + vertex 695.486 149.965 294.778 + vertex 694.687 147.065 295.734 + endloop + endfacet + facet normal 0.588438 -0.394863 -0.705566 + outer loop + vertex 694.687 147.065 295.734 + vertex 695.486 149.965 294.778 + vertex 696.112 150.361 295.078 + endloop + endfacet + facet normal 0.562242 -0.388409 -0.730084 + outer loop + vertex 694.687 147.065 295.734 + vertex 696.112 150.361 295.078 + vertex 695.116 147.448 295.861 + endloop + endfacet + facet normal 0.568671 -0.389158 -0.724686 + outer loop + vertex 695.116 147.448 295.861 + vertex 696.112 150.361 295.078 + vertex 696.49 150.648 295.22 + endloop + endfacet + facet normal 0.615106 -0.400034 -0.679424 + outer loop + vertex 695.116 147.448 295.861 + vertex 696.49 150.648 295.22 + vertex 695.286 147.486 295.993 + endloop + endfacet + facet normal 0.678458 -0.407495 -0.611264 + outer loop + vertex 695.286 147.486 295.993 + vertex 696.49 150.648 295.22 + vertex 696.818 151.206 295.214 + endloop + endfacet + facet normal 0.598472 -0.394672 -0.697183 + outer loop + vertex 693.683 147.121 294.853 + vertex 693.245 147.646 294.18 + vertex 694.695 150.088 294.043 + endloop + endfacet + facet normal 0.569637 -0.426281 -0.702708 + outer loop + vertex 692.689 145.486 295.04 + vertex 693.683 147.121 294.853 + vertex 693.305 145.537 295.508 + endloop + endfacet + facet normal 0.573957 -0.444677 -0.687631 + outer loop + vertex 693.02 144.432 295.982 + vertex 693.898 145.873 295.783 + vertex 693.473 144.69 296.194 + endloop + endfacet + facet normal 0.587028 -0.485706 -0.647679 + outer loop + vertex 689.545 143.08 293.986 + vertex 690.058 143.531 294.113 + vertex 690.662 142.907 295.128 + endloop + endfacet + facet normal -0.432876 0.726584 0.533566 + outer loop + vertex 689.545 143.08 293.986 + vertex 690.662 142.907 295.128 + vertex 690.686 142.952 295.086 + endloop + endfacet + facet normal 0.600565 -0.510222 -0.615626 + outer loop + vertex 689.545 143.08 293.986 + vertex 688.166 144.145 291.758 + vertex 690.058 143.531 294.113 + endloop + endfacet + facet normal 0.563797 -0.45024 -0.692399 + outer loop + vertex 692.349 144.116 295.654 + vertex 692.689 145.486 295.04 + vertex 693.305 145.537 295.508 + endloop + endfacet + facet normal 0.572175 -0.451738 -0.684506 + outer loop + vertex 691.019 144.085 294.575 + vertex 691.988 145.556 294.414 + vertex 691.795 144.234 295.125 + endloop + endfacet + facet normal 0.569469 -0.4262 -0.702893 + outer loop + vertex 692.689 145.486 295.04 + vertex 693.245 147.646 294.18 + vertex 693.683 147.121 294.853 + endloop + endfacet + facet normal 0.59344 -0.431069 -0.679712 + outer loop + vertex 691.107 145.489 293.687 + vertex 692.402 147.783 293.362 + vertex 691.988 145.556 294.414 + endloop + endfacet + facet normal 0.603674 -0.397419 -0.691112 + outer loop + vertex 693.884 150.669 293 + vertex 694.695 150.088 294.043 + vertex 693.245 147.646 294.18 + endloop + endfacet + facet normal 0.88345 -0.460236 0.0877415 + outer loop + vertex 672.836 165.177 137.131 + vertex 674.021 167.04 134.973 + vertex 674.359 168.171 137.496 + endloop + endfacet + facet normal 0.879864 -0.468703 0.0784631 + outer loop + vertex 672.769 164.567 134.235 + vertex 674.021 167.04 134.973 + vertex 672.836 165.177 137.131 + endloop + endfacet + facet normal 0.858477 -0.505472 0.0866972 + outer loop + vertex 672.836 165.177 137.131 + vertex 671.996 163.628 136.42 + vertex 672.769 164.567 134.235 + endloop + endfacet + facet normal 0.858491 -0.505445 0.0867135 + outer loop + vertex 671.996 163.628 136.42 + vertex 672.21 163.279 132.263 + vertex 672.769 164.567 134.235 + endloop + endfacet + facet normal 0.858333 -0.505678 0.0869105 + outer loop + vertex 672.981 164.528 131.917 + vertex 672.769 164.567 134.235 + vertex 672.21 163.279 132.263 + endloop + endfacet + facet normal 0.858623 -0.503958 0.0937722 + outer loop + vertex 672.981 164.528 131.917 + vertex 672.21 163.279 132.263 + vertex 672.924 164.061 129.933 + endloop + endfacet + facet normal 0.880525 -0.466442 0.0843094 + outer loop + vertex 672.924 164.061 129.933 + vertex 674.104 166.404 130.565 + vertex 672.981 164.528 131.917 + endloop + endfacet + facet normal 0.880915 -0.465373 0.0861165 + outer loop + vertex 672.981 164.528 131.917 + vertex 674.104 166.404 130.565 + vertex 674.022 166.633 132.637 + endloop + endfacet + facet normal 0.878597 -0.468162 0.0942972 + outer loop + vertex 672.924 164.061 129.933 + vertex 674.168 166.129 128.599 + vertex 674.104 166.404 130.565 + endloop + endfacet + facet normal 0.879314 -0.465974 0.0983589 + outer loop + vertex 673.108 163.98 127.899 + vertex 674.168 166.129 128.599 + vertex 672.924 164.061 129.933 + endloop + endfacet + facet normal 0.855793 -0.507968 0.0979129 + outer loop + vertex 673.108 163.98 127.899 + vertex 672.924 164.061 129.933 + vertex 672.31 162.683 128.145 + endloop + endfacet + facet normal 0.855728 -0.505912 0.108549 + outer loop + vertex 673.108 163.98 127.899 + vertex 672.31 162.683 128.145 + vertex 673.014 163.409 125.981 + endloop + endfacet + facet normal 0.878862 -0.46733 0.0959382 + outer loop + vertex 673.014 163.409 125.981 + vertex 674.21 165.795 126.644 + vertex 673.108 163.98 127.899 + endloop + endfacet + facet normal 0.877318 -0.468634 0.103421 + outer loop + vertex 673.014 163.409 125.981 + vertex 674.244 165.426 124.687 + vertex 674.21 165.795 126.644 + endloop + endfacet + facet normal 0.878114 -0.466058 0.108194 + outer loop + vertex 673.185 163.268 123.981 + vertex 674.244 165.426 124.687 + vertex 673.014 163.409 125.981 + endloop + endfacet + facet normal 0.8561 -0.505168 0.109079 + outer loop + vertex 673.185 163.268 123.981 + vertex 673.014 163.409 125.981 + vertex 672.43 162.043 124.236 + endloop + endfacet + facet normal 0.856059 -0.503763 0.115697 + outer loop + vertex 673.185 163.268 123.981 + vertex 672.43 162.043 124.236 + vertex 673.102 162.7 122.126 + endloop + endfacet + facet normal 0.878136 -0.467084 0.10349 + outer loop + vertex 673.102 162.7 122.126 + vertex 674.29 165.075 122.76 + vertex 673.185 163.268 123.981 + endloop + endfacet + facet normal 0.876334 -0.46848 0.112098 + outer loop + vertex 673.102 162.7 122.126 + vertex 674.34 164.715 120.868 + vertex 674.29 165.075 122.76 + endloop + endfacet + facet normal 0.877023 -0.46608 0.116619 + outer loop + vertex 673.279 162.55 120.195 + vertex 674.34 164.715 120.868 + vertex 673.102 162.7 122.126 + endloop + endfacet + facet normal 0.854554 -0.505859 0.117662 + outer loop + vertex 673.279 162.55 120.195 + vertex 673.102 162.7 122.126 + vertex 672.508 161.33 120.546 + endloop + endfacet + facet normal 0.854681 -0.50417 0.123825 + outer loop + vertex 673.279 162.55 120.195 + vertex 672.508 161.33 120.546 + vertex 673.208 161.983 118.378 + endloop + endfacet + facet normal 0.876367 -0.46848 0.111838 + outer loop + vertex 673.208 161.983 118.378 + vertex 674.399 164.358 118.994 + vertex 673.279 162.55 120.195 + endloop + endfacet + facet normal 0.874376 -0.46989 0.121115 + outer loop + vertex 673.208 161.983 118.378 + vertex 674.471 164.008 117.117 + vertex 674.399 164.358 118.994 + endloop + endfacet + facet normal 0.87515 -0.467024 0.126496 + outer loop + vertex 673.404 161.825 116.438 + vertex 674.471 164.008 117.117 + vertex 673.208 161.983 118.378 + endloop + endfacet + facet normal 0.851089 -0.509303 0.127504 + outer loop + vertex 673.404 161.825 116.438 + vertex 673.208 161.983 118.378 + vertex 672.588 160.553 116.802 + endloop + endfacet + facet normal 0.851201 -0.506463 0.137669 + outer loop + vertex 673.404 161.825 116.438 + vertex 672.588 160.553 116.802 + vertex 673.344 161.219 114.581 + endloop + endfacet + facet normal 0.874724 -0.468362 0.124477 + outer loop + vertex 673.344 161.219 114.581 + vertex 674.536 163.618 115.227 + vertex 673.404 161.825 116.438 + endloop + endfacet + facet normal 0.872589 -0.469791 0.133732 + outer loop + vertex 673.344 161.219 114.581 + vertex 674.605 163.205 113.328 + vertex 674.536 163.618 115.227 + endloop + endfacet + facet normal 0.873293 -0.466974 0.138904 + outer loop + vertex 673.549 161.021 112.622 + vertex 674.605 163.205 113.328 + vertex 673.344 161.219 114.581 + endloop + endfacet + facet normal 0.851486 -0.50521 0.140479 + outer loop + vertex 673.549 161.021 112.622 + vertex 673.344 161.219 114.581 + vertex 672.781 159.8 112.888 + endloop + endfacet + facet normal 0.85124 -0.50326 0.148729 + outer loop + vertex 673.549 161.021 112.622 + vertex 672.781 159.8 112.888 + vertex 673.495 160.388 110.791 + endloop + endfacet + facet normal 0.873041 -0.468297 0.136002 + outer loop + vertex 673.495 160.388 110.791 + vertex 674.678 162.781 111.433 + vertex 673.549 161.021 112.622 + endloop + endfacet + facet normal 0.870531 -0.46984 0.146377 + outer loop + vertex 673.495 160.388 110.791 + vertex 674.765 162.351 109.538 + vertex 674.678 162.781 111.433 + endloop + endfacet + facet normal 0.871033 -0.46767 0.150286 + outer loop + vertex 673.723 160.19 108.856 + vertex 674.765 162.351 109.538 + vertex 673.495 160.388 110.791 + endloop + endfacet + facet normal 0.848068 -0.507716 0.151677 + outer loop + vertex 673.723 160.19 108.856 + vertex 673.495 160.388 110.791 + vertex 672.952 159.001 109.183 + endloop + endfacet + facet normal 0.847952 -0.505348 0.160002 + outer loop + vertex 673.723 160.19 108.856 + vertex 672.952 159.001 109.183 + vertex 673.692 159.555 107.012 + endloop + endfacet + facet normal 0.870175 -0.470149 0.147495 + outer loop + vertex 673.692 159.555 107.012 + vertex 674.875 161.94 107.637 + vertex 673.723 160.19 108.856 + endloop + endfacet + facet normal 0.866901 -0.471932 0.160507 + outer loop + vertex 673.692 159.555 107.012 + vertex 674.985 161.491 105.723 + vertex 674.875 161.94 107.637 + endloop + endfacet + facet normal 0.867328 -0.469998 0.163843 + outer loop + vertex 673.927 159.304 105.048 + vertex 674.985 161.491 105.723 + vertex 673.692 159.555 107.012 + endloop + endfacet + facet normal 0.840689 -0.515304 0.166446 + outer loop + vertex 673.927 159.304 105.048 + vertex 673.692 159.555 107.012 + vertex 673.103 158.063 105.366 + endloop + endfacet + facet normal 0.840326 -0.512301 0.177198 + outer loop + vertex 673.927 159.304 105.048 + vertex 673.103 158.063 105.366 + vertex 673.926 158.66 103.193 + endloop + endfacet + facet normal 0.865946 -0.472678 0.163442 + outer loop + vertex 673.926 158.66 103.193 + vertex 675.105 161.034 103.808 + vertex 673.927 159.304 105.048 + endloop + endfacet + facet normal 0.86257 -0.47429 0.176129 + outer loop + vertex 673.926 158.66 103.193 + vertex 675.229 160.55 101.9 + vertex 675.105 161.034 103.808 + endloop + endfacet + facet normal 0.863114 -0.471617 0.180588 + outer loop + vertex 674.191 158.397 101.236 + vertex 675.229 160.55 101.9 + vertex 673.926 158.66 103.193 + endloop + endfacet + facet normal 0.839409 -0.511838 0.182796 + outer loop + vertex 674.191 158.397 101.236 + vertex 673.926 158.66 103.193 + vertex 673.384 157.189 101.563 + endloop + endfacet + facet normal 0.838976 -0.508748 0.193118 + outer loop + vertex 674.191 158.397 101.236 + vertex 673.384 157.189 101.563 + vertex 674.198 157.719 99.4208 + endloop + endfacet + facet normal 0.862266 -0.473387 0.180008 + outer loop + vertex 674.198 157.719 99.4208 + vertex 675.378 160.094 100.013 + vertex 674.191 158.397 101.236 + endloop + endfacet + facet normal 0.858884 -0.474742 0.192192 + outer loop + vertex 674.198 157.719 99.4208 + vertex 675.534 159.619 98.147 + vertex 675.378 160.094 100.013 + endloop + endfacet + facet normal 0.859326 -0.472184 0.196471 + outer loop + vertex 674.48 157.437 97.5084 + vertex 675.534 159.619 98.147 + vertex 674.198 157.719 99.4208 + endloop + endfacet + facet normal 0.834958 -0.513105 0.198918 + outer loop + vertex 674.48 157.437 97.5084 + vertex 674.198 157.719 99.4208 + vertex 673.671 156.25 97.8448 + endloop + endfacet + facet normal 0.834495 -0.510138 0.208271 + outer loop + vertex 674.48 157.437 97.5084 + vertex 673.671 156.25 97.8448 + vertex 674.509 156.752 95.7152 + endloop + endfacet + facet normal 0.858047 -0.475015 0.195233 + outer loop + vertex 674.509 156.752 95.7152 + vertex 675.7 159.145 96.3037 + vertex 674.48 157.437 97.5084 + endloop + endfacet + facet normal 0.854847 -0.47613 0.206244 + outer loop + vertex 674.509 156.752 95.7152 + vertex 675.886 158.687 94.4777 + vertex 675.7 159.145 96.3037 + endloop + endfacet + facet normal 0.855289 -0.472869 0.211837 + outer loop + vertex 674.835 156.486 93.8074 + vertex 675.886 158.687 94.4777 + vertex 674.509 156.752 95.7152 + endloop + endfacet + facet normal 0.832708 -0.510986 0.213286 + outer loop + vertex 674.835 156.486 93.8074 + vertex 674.509 156.752 95.7152 + vertex 674.031 155.26 94.0058 + endloop + endfacet + facet normal 0.831457 -0.508433 0.223998 + outer loop + vertex 674.835 156.486 93.8074 + vertex 674.031 155.26 94.0058 + vertex 674.917 155.796 91.9371 + endloop + endfacet + facet normal 0.854072 -0.474742 0.212558 + outer loop + vertex 674.917 155.796 91.9371 + vertex 676.087 158.21 92.6264 + vertex 674.835 156.486 93.8074 + endloop + endfacet + facet normal 0.849336 -0.476562 0.226975 + outer loop + vertex 674.917 155.796 91.9371 + vertex 676.337 157.733 90.6895 + vertex 676.087 158.21 92.6264 + endloop + endfacet + facet normal 0.849633 -0.473795 0.231608 + outer loop + vertex 675.268 155.472 89.9876 + vertex 676.337 157.733 90.6895 + vertex 674.917 155.796 91.9371 + endloop + endfacet + facet normal 0.829507 -0.507317 0.233555 + outer loop + vertex 675.268 155.472 89.9876 + vertex 674.917 155.796 91.9371 + vertex 674.522 154.219 89.913 + endloop + endfacet + facet normal 0.826578 -0.506304 0.245816 + outer loop + vertex 675.268 155.472 89.9876 + vertex 674.522 154.219 89.913 + vertex 675.376 154.756 88.1468 + endloop + endfacet + facet normal 0.842517 -0.483332 0.237814 + outer loop + vertex 675.376 154.756 88.1468 + vertex 676.525 157.036 88.7095 + vertex 675.268 155.472 89.9876 + endloop + endfacet + facet normal 0.833804 -0.485229 0.263293 + outer loop + vertex 675.376 154.756 88.1468 + vertex 676.702 156.291 86.7762 + vertex 676.525 157.036 88.7095 + endloop + endfacet + facet normal 0.83249 -0.492386 0.254003 + outer loop + vertex 675.781 154.468 86.2617 + vertex 676.702 156.291 86.7762 + vertex 675.376 154.756 88.1468 + endloop + endfacet + facet normal 0.817374 -0.516853 0.254487 + outer loop + vertex 675.781 154.468 86.2617 + vertex 675.376 154.756 88.1468 + vertex 675.065 153.443 86.4817 + endloop + endfacet + facet normal 0.81655 -0.514861 0.261082 + outer loop + vertex 675.781 154.468 86.2617 + vertex 675.065 153.443 86.4817 + vertex 675.969 153.878 84.5088 + endloop + endfacet + facet normal 0.827542 -0.499143 0.256964 + outer loop + vertex 675.969 153.878 84.5088 + vertex 676.993 155.774 84.8941 + vertex 675.781 154.468 86.2617 + endloop + endfacet + facet normal 0.822668 -0.499475 0.271556 + outer loop + vertex 675.969 153.878 84.5088 + vertex 677.343 155.34 83.0383 + vertex 676.993 155.774 84.8941 + endloop + endfacet + facet normal 0.82302 -0.497806 0.273546 + outer loop + vertex 676.422 153.596 82.6327 + vertex 677.343 155.34 83.0383 + vertex 675.969 153.878 84.5088 + endloop + endfacet + facet normal 0.812815 -0.514296 0.273554 + outer loop + vertex 676.422 153.596 82.6327 + vertex 675.969 153.878 84.5088 + vertex 675.566 152.499 83.1148 + endloop + endfacet + facet normal 0.812144 -0.507434 0.287981 + outer loop + vertex 676.422 153.596 82.6327 + vertex 675.566 152.499 83.1148 + vertex 676.634 152.907 80.8226 + endloop + endfacet + facet normal 0.818531 -0.498577 0.285357 + outer loop + vertex 676.634 152.907 80.8226 + vertex 677.706 154.88 81.1926 + vertex 676.422 153.596 82.6327 + endloop + endfacet + facet normal 0.813033 -0.498487 0.300813 + outer loop + vertex 676.634 152.907 80.8226 + vertex 678.079 154.374 79.3485 + vertex 677.706 154.88 81.1926 + endloop + endfacet + facet normal 0.813292 -0.497028 0.30252 + outer loop + vertex 677.152 152.559 78.8577 + vertex 678.079 154.374 79.3485 + vertex 676.634 152.907 80.8226 + endloop + endfacet + facet normal 0.804472 -0.511084 0.302685 + outer loop + vertex 677.152 152.559 78.8577 + vertex 676.634 152.907 80.8226 + vertex 676.313 151.385 79.1047 + endloop + endfacet + facet normal 0.802064 -0.506445 0.316556 + outer loop + vertex 677.152 152.559 78.8577 + vertex 676.313 151.385 79.1047 + vertex 677.424 151.819 76.986 + endloop + endfacet + facet normal 0.808459 -0.497761 0.314052 + outer loop + vertex 677.424 151.819 76.986 + vertex 678.463 153.836 77.5061 + vertex 677.152 152.559 78.8577 + endloop + endfacet + facet normal 0.802487 -0.498322 0.32816 + outer loop + vertex 677.424 151.819 76.986 + vertex 678.89 153.31 75.6642 + vertex 678.463 153.836 77.5061 + endloop + endfacet + facet normal 0.80272 -0.496153 0.330865 + outer loop + vertex 677.997 151.463 75.0608 + vertex 678.89 153.31 75.6642 + vertex 677.424 151.819 76.986 + endloop + endfacet + facet normal 0.794917 -0.508579 0.330839 + outer loop + vertex 677.997 151.463 75.0608 + vertex 677.424 151.819 76.986 + vertex 677.219 150.205 74.9959 + endloop + endfacet + facet normal 0.789869 -0.506248 0.34615 + outer loop + vertex 677.997 151.463 75.0608 + vertex 677.219 150.205 74.9959 + vertex 678.341 150.763 73.2519 + endloop + endfacet + facet normal 0.796904 -0.496732 0.343803 + outer loop + vertex 678.341 150.763 73.2519 + vertex 679.359 152.787 73.8166 + vertex 677.997 151.463 75.0608 + endloop + endfacet + facet normal 0.789541 -0.4974 0.35947 + outer loop + vertex 678.341 150.763 73.2519 + vertex 679.891 152.28 71.947 + vertex 679.359 152.787 73.8166 + endloop + endfacet + facet normal 0.789694 -0.494954 0.362496 + outer loop + vertex 678.995 150.443 71.3907 + vertex 679.891 152.28 71.947 + vertex 678.341 150.763 73.2519 + endloop + endfacet + facet normal 0.778029 -0.513716 0.361618 + outer loop + vertex 678.995 150.443 71.3907 + vertex 678.341 150.763 73.2519 + vertex 678.188 149.355 71.5805 + endloop + endfacet + facet normal 0.774319 -0.508297 0.376914 + outer loop + vertex 678.995 150.443 71.3907 + vertex 678.188 149.355 71.5805 + vertex 679.402 149.744 69.612 + endloop + endfacet + facet normal 0.782462 -0.49748 0.374523 + outer loop + vertex 679.402 149.744 69.612 + vertex 680.47 151.764 70.063 + vertex 678.995 150.443 71.3907 + endloop + endfacet + facet normal 0.773523 -0.496949 0.393324 + outer loop + vertex 679.402 149.744 69.612 + vertex 681.108 151.262 68.1751 + vertex 680.47 151.764 70.063 + endloop + endfacet + facet normal 0.773583 -0.49602 0.394376 + outer loop + vertex 680.17 149.431 67.7122 + vertex 681.108 151.262 68.1751 + vertex 679.402 149.744 69.612 + endloop + endfacet + facet normal 0.759442 -0.518892 0.392427 + outer loop + vertex 680.17 149.431 67.7122 + vertex 679.402 149.744 69.612 + vertex 679.149 148.323 68.2221 + endloop + endfacet + facet normal 0.757246 -0.509285 0.40891 + outer loop + vertex 680.17 149.431 67.7122 + vertex 679.149 148.323 68.2221 + vertex 680.67 148.751 65.9388 + endloop + endfacet + facet normal 0.764925 -0.499101 0.407171 + outer loop + vertex 680.67 148.751 65.9388 + vertex 681.783 150.774 66.3278 + vertex 680.17 149.431 67.7122 + endloop + endfacet + facet normal 0.755058 -0.497499 0.427063 + outer loop + vertex 680.67 148.751 65.9388 + vertex 682.49 150.324 64.5536 + vertex 681.783 150.774 66.3278 + endloop + endfacet + facet normal 0.755058 -0.497474 0.427091 + outer loop + vertex 681.541 148.476 64.0776 + vertex 682.49 150.324 64.5536 + vertex 680.67 148.751 65.9388 + endloop + endfacet + facet normal 0.73992 -0.522486 0.423705 + outer loop + vertex 681.541 148.476 64.0776 + vertex 680.67 148.751 65.9388 + vertex 680.506 147.248 64.371 + endloop + endfacet + facet normal 0.734102 -0.512336 0.445652 + outer loop + vertex 681.541 148.476 64.0776 + vertex 680.506 147.248 64.371 + vertex 682.099 147.815 62.3988 + endloop + endfacet + facet normal 0.744963 -0.498172 0.443684 + outer loop + vertex 682.099 147.815 62.3988 + vertex 683.205 149.88 62.8621 + vertex 681.541 148.476 64.0776 + endloop + endfacet + facet normal 0.733337 -0.496586 0.464349 + outer loop + vertex 682.099 147.815 62.3988 + vertex 683.95 149.459 61.2337 + vertex 683.205 149.88 62.8621 + endloop + endfacet + facet normal 0.733148 -0.494861 0.466483 + outer loop + vertex 683.015 147.561 60.6901 + vertex 683.95 149.459 61.2337 + vertex 682.099 147.815 62.3988 + endloop + endfacet + facet normal 0.724611 -0.50948 0.464078 + outer loop + vertex 683.015 147.561 60.6901 + vertex 682.099 147.815 62.3988 + vertex 682.133 146.289 60.6719 + endloop + endfacet + facet normal 0.71426 -0.502624 0.487033 + outer loop + vertex 683.015 147.561 60.6901 + vertex 682.133 146.289 60.6719 + vertex 683.668 146.953 59.1051 + endloop + endfacet + facet normal 0.721034 -0.493542 0.48634 + outer loop + vertex 683.668 146.953 59.1051 + vertex 684.754 149.047 59.6205 + vertex 683.015 147.561 60.6901 + endloop + endfacet + facet normal 0.708275 -0.491859 0.506381 + outer loop + vertex 683.668 146.953 59.1051 + vertex 685.644 148.66 57.9985 + vertex 684.754 149.047 59.6205 + endloop + endfacet + facet normal 0.707716 -0.488782 0.510127 + outer loop + vertex 684.722 146.767 57.4641 + vertex 685.644 148.66 57.9985 + vertex 683.668 146.953 59.1051 + endloop + endfacet + facet normal 0.700911 -0.501473 0.507198 + outer loop + vertex 684.722 146.767 57.4641 + vertex 683.668 146.953 59.1051 + vertex 683.771 145.628 57.6531 + endloop + endfacet + facet normal 0.692027 -0.490292 0.529823 + outer loop + vertex 684.722 146.767 57.4641 + vertex 683.771 145.628 57.6531 + vertex 685.537 146.221 55.8952 + endloop + endfacet + facet normal 0.695521 -0.485255 0.529885 + outer loop + vertex 685.537 146.221 55.8952 + vertex 686.625 148.301 56.3719 + vertex 684.722 146.767 57.4641 + endloop + endfacet + facet normal 0.682849 -0.482838 0.548256 + outer loop + vertex 685.537 146.221 55.8952 + vertex 687.708 148.008 54.7639 + vertex 686.625 148.301 56.3719 + endloop + endfacet + facet normal 0.681914 -0.478655 0.553067 + outer loop + vertex 686.797 146.096 54.2325 + vertex 687.708 148.008 54.7639 + vertex 685.537 146.221 55.8952 + endloop + endfacet + facet normal 0.679425 -0.483889 0.551573 + outer loop + vertex 686.797 146.096 54.2325 + vertex 685.537 146.221 55.8952 + vertex 685.604 144.86 54.6185 + endloop + endfacet + facet normal 0.6701 -0.466946 0.576999 + outer loop + vertex 686.797 146.096 54.2325 + vertex 685.604 144.86 54.6185 + vertex 687.841 145.6 52.6193 + endloop + endfacet + facet normal 0.666169 -0.473265 0.576402 + outer loop + vertex 687.841 145.6 52.6193 + vertex 688.881 147.768 53.1973 + vertex 686.797 146.096 54.2325 + endloop + endfacet + facet normal 0.648283 -0.47059 0.59856 + outer loop + vertex 687.841 145.6 52.6193 + vertex 690.086 147.518 51.6953 + vertex 688.881 147.768 53.1973 + endloop + endfacet + facet normal 0.648603 -0.471462 0.597527 + outer loop + vertex 689.226 145.491 51.0298 + vertex 690.086 147.518 51.6953 + vertex 687.841 145.6 52.6193 + endloop + endfacet + facet normal 0.643274 -0.483439 0.593704 + outer loop + vertex 689.226 145.491 51.0298 + vertex 687.841 145.6 52.6193 + vertex 688.142 143.974 50.9683 + endloop + endfacet + facet normal 0.628475 -0.473808 0.616867 + outer loop + vertex 689.226 145.491 51.0298 + vertex 688.142 143.974 50.9683 + vertex 689.922 144.799 49.7897 + endloop + endfacet + facet normal 0.625059 -0.477863 0.61721 + outer loop + vertex 689.922 144.799 49.7897 + vertex 691.232 147.091 50.2364 + vertex 689.226 145.491 51.0298 + endloop + endfacet + facet normal 0.622159 -0.469698 0.62634 + outer loop + vertex 689.226 145.491 51.0298 + vertex 691.232 147.091 50.2364 + vertex 690.086 147.518 51.6953 + endloop + endfacet + facet normal 0.66708 -0.476935 0.572309 + outer loop + vertex 686.797 146.096 54.2325 + vertex 688.881 147.768 53.1973 + vertex 687.708 148.008 54.7639 + endloop + endfacet + facet normal 0.695924 -0.487804 0.527007 + outer loop + vertex 684.722 146.767 57.4641 + vertex 686.625 148.301 56.3719 + vertex 685.644 148.66 57.9985 + endloop + endfacet + facet normal 0.721131 -0.494351 0.485373 + outer loop + vertex 683.015 147.561 60.6901 + vertex 684.754 149.047 59.6205 + vertex 683.95 149.459 61.2337 + endloop + endfacet + facet normal 0.744948 -0.496925 0.445105 + outer loop + vertex 681.541 148.476 64.0776 + vertex 683.205 149.88 62.8621 + vertex 682.49 150.324 64.5536 + endloop + endfacet + facet normal 0.765191 -0.495835 0.410647 + outer loop + vertex 680.17 149.431 67.7122 + vertex 681.783 150.774 66.3278 + vertex 681.108 151.262 68.1751 + endloop + endfacet + facet normal 0.78264 -0.495742 0.37645 + outer loop + vertex 678.995 150.443 71.3907 + vertex 680.47 151.764 70.063 + vertex 679.891 152.28 71.947 + endloop + endfacet + facet normal 0.792034 -0.500648 0.349334 + outer loop + vertex 677.219 150.205 74.9959 + vertex 678.188 149.355 71.5805 + vertex 678.341 150.763 73.2519 + endloop + endfacet + facet normal 0.79083 -0.50247 0.349445 + outer loop + vertex 678.188 149.355 71.5805 + vertex 677.219 150.205 74.9959 + vertex 677.889 148.596 71.1656 + endloop + endfacet + facet normal 0.821233 -0.460384 0.337079 + outer loop + vertex 676.468 150.063 76.6316 + vertex 677.889 148.596 71.1656 + vertex 677.219 150.205 74.9959 + endloop + endfacet + facet normal 0.796839 -0.497312 0.343115 + outer loop + vertex 677.997 151.463 75.0608 + vertex 679.359 152.787 73.8166 + vertex 678.89 153.31 75.6642 + endloop + endfacet + facet normal 0.806156 -0.497341 0.320568 + outer loop + vertex 676.313 151.385 79.1047 + vertex 677.219 150.205 74.9959 + vertex 677.424 151.819 76.986 + endloop + endfacet + facet normal 0.808469 -0.497702 0.314118 + outer loop + vertex 677.152 152.559 78.8577 + vertex 678.463 153.836 77.5061 + vertex 678.079 154.374 79.3485 + endloop + endfacet + facet normal 0.815621 -0.500138 0.290902 + outer loop + vertex 675.566 152.499 83.1148 + vertex 676.313 151.385 79.1047 + vertex 676.634 152.907 80.8226 + endloop + endfacet + facet normal 0.818596 -0.49829 0.285671 + outer loop + vertex 676.422 153.596 82.6327 + vertex 677.706 154.88 81.1926 + vertex 677.343 155.34 83.0383 + endloop + endfacet + facet normal 0.820224 -0.507251 0.264442 + outer loop + vertex 675.065 153.443 86.4817 + vertex 675.566 152.499 83.1148 + vertex 675.969 153.878 84.5088 + endloop + endfacet + facet normal 0.825694 -0.49908 0.262963 + outer loop + vertex 675.566 152.499 83.1148 + vertex 675.065 153.443 86.4817 + vertex 674.778 152.63 85.8377 + endloop + endfacet + facet normal 0.838571 -0.487675 0.242842 + outer loop + vertex 675.065 153.443 86.4817 + vertex 674.522 154.219 89.913 + vertex 674.778 152.63 85.8377 + endloop + endfacet + facet normal 0.828904 -0.493319 0.26373 + outer loop + vertex 675.781 154.468 86.2617 + vertex 676.993 155.774 84.8941 + vertex 676.702 156.291 86.7762 + endloop + endfacet + facet normal 0.826132 -0.507279 0.245304 + outer loop + vertex 674.522 154.219 89.913 + vertex 675.065 153.443 86.4817 + vertex 675.376 154.756 88.1468 + endloop + endfacet + facet normal 0.843742 -0.476069 0.247906 + outer loop + vertex 675.268 155.472 89.9876 + vertex 676.525 157.036 88.7095 + vertex 676.337 157.733 90.6895 + endloop + endfacet + facet normal 0.83506 -0.500923 0.227488 + outer loop + vertex 674.031 155.26 94.0058 + vertex 674.522 154.219 89.913 + vertex 674.917 155.796 91.9371 + endloop + endfacet + facet normal 0.854286 -0.473314 0.214869 + outer loop + vertex 674.835 156.486 93.8074 + vertex 676.087 158.21 92.6264 + vertex 675.886 158.687 94.4777 + endloop + endfacet + facet normal 0.835803 -0.507527 0.209402 + outer loop + vertex 673.671 156.25 97.8448 + vertex 674.031 155.26 94.0058 + vertex 674.509 156.752 95.7152 + endloop + endfacet + facet normal 0.858496 -0.472569 0.199155 + outer loop + vertex 674.48 157.437 97.5084 + vertex 675.7 159.145 96.3037 + vertex 675.534 159.619 98.147 + endloop + endfacet + facet normal 0.839105 -0.508493 0.19323 + outer loop + vertex 673.384 157.189 101.563 + vertex 673.671 156.25 97.8448 + vertex 674.198 157.719 99.4208 + endloop + endfacet + facet normal 0.862581 -0.471908 0.182365 + outer loop + vertex 674.191 158.397 101.236 + vertex 675.378 160.094 100.013 + vertex 675.229 160.55 101.9 + endloop + endfacet + facet normal 0.842211 -0.50859 0.178931 + outer loop + vertex 673.103 158.063 105.366 + vertex 673.384 157.189 101.563 + vertex 673.926 158.66 103.193 + endloop + endfacet + facet normal 0.866453 -0.470527 0.166926 + outer loop + vertex 673.927 159.304 105.048 + vertex 675.105 161.034 103.808 + vertex 674.985 161.491 105.723 + endloop + endfacet + facet normal 0.846193 -0.508748 0.158535 + outer loop + vertex 672.952 159.001 109.183 + vertex 673.103 158.063 105.366 + vertex 673.692 159.555 107.012 + endloop + endfacet + facet normal 0.804529 -0.568588 0.171583 + outer loop + vertex 673.103 158.063 105.366 + vertex 672.952 159.001 109.183 + vertex 672.705 158.133 107.465 + endloop + endfacet + facet normal 0.798803 -0.576845 0.170771 + outer loop + vertex 672.705 158.133 107.465 + vertex 672.822 157.556 104.971 + vertex 673.103 158.063 105.366 + endloop + endfacet + facet normal 0.786444 -0.586905 0.192477 + outer loop + vertex 672.822 157.556 104.971 + vertex 672.958 157.136 103.133 + vertex 673.103 158.063 105.366 + endloop + endfacet + facet normal 0.7855 -0.587999 0.192992 + outer loop + vertex 673.384 157.189 101.563 + vertex 673.103 158.063 105.366 + vertex 672.958 157.136 103.133 + endloop + endfacet + facet normal 0.805243 -0.558434 0.199337 + outer loop + vertex 672.958 157.136 103.133 + vertex 673.187 156.219 99.6376 + vertex 673.384 157.189 101.563 + endloop + endfacet + facet normal 0.797005 -0.5681 0.205048 + outer loop + vertex 673.671 156.25 97.8448 + vertex 673.384 157.189 101.563 + vertex 673.187 156.219 99.6376 + endloop + endfacet + facet normal 0.809923 -0.548085 0.208871 + outer loop + vertex 673.187 156.219 99.6376 + vertex 673.52 155.277 95.8777 + vertex 673.671 156.25 97.8448 + endloop + endfacet + facet normal 0.790875 -0.570516 0.221423 + outer loop + vertex 674.031 155.26 94.0058 + vertex 673.671 156.25 97.8448 + vertex 673.52 155.277 95.8777 + endloop + endfacet + facet normal 0.860994 -0.470214 0.193875 + outer loop + vertex 673.52 155.277 95.8777 + vertex 673.187 156.219 99.6376 + vertex 673.427 154.649 94.7653 + endloop + endfacet + facet normal 0.839017 -0.51026 0.188903 + outer loop + vertex 673.187 156.219 99.6376 + vertex 672.958 157.136 103.133 + vertex 672.797 156.722 102.73 + endloop + endfacet + facet normal 0.846359 -0.502129 0.177605 + outer loop + vertex 672.958 157.136 103.133 + vertex 672.822 157.556 104.971 + vertex 672.797 156.722 102.73 + endloop + endfacet + facet normal 0.917681 -0.375532 0.129756 + outer loop + vertex 672.822 157.556 104.971 + vertex 672.705 158.133 107.465 + vertex 672.797 156.722 102.73 + endloop + endfacet + facet normal 0.868295 -0.47052 0.157083 + outer loop + vertex 672.387 158.355 109.887 + vertex 672.797 156.722 102.73 + vertex 672.705 158.133 107.465 + endloop + endfacet + facet normal 0.81829 -0.551766 0.161105 + outer loop + vertex 672.56 158.947 110.989 + vertex 672.705 158.133 107.465 + vertex 672.952 159.001 109.183 + endloop + endfacet + facet normal 0.810478 -0.563763 0.159053 + outer loop + vertex 672.952 159.001 109.183 + vertex 672.781 159.8 112.888 + vertex 672.56 158.947 110.989 + endloop + endfacet + facet normal 0.821686 -0.549482 0.151331 + outer loop + vertex 672.394 159.642 114.417 + vertex 672.56 158.947 110.989 + vertex 672.781 159.8 112.888 + endloop + endfacet + facet normal 0.814061 -0.561566 0.148151 + outer loop + vertex 672.781 159.8 112.888 + vertex 672.588 160.553 116.802 + vertex 672.394 159.642 114.417 + endloop + endfacet + facet normal 0.811553 -0.564804 0.149591 + outer loop + vertex 672.281 160.2 117.138 + vertex 672.394 159.642 114.417 + vertex 672.588 160.553 116.802 + endloop + endfacet + facet normal 0.807125 -0.574719 0.13508 + outer loop + vertex 672.246 160.597 119.034 + vertex 672.281 160.2 117.138 + vertex 672.588 160.553 116.802 + endloop + endfacet + facet normal 0.81048 -0.569879 0.135499 + outer loop + vertex 672.588 160.553 116.802 + vertex 672.508 161.33 120.546 + vertex 672.246 160.597 119.034 + endloop + endfacet + facet normal 0.822756 -0.554293 0.125823 + outer loop + vertex 672.148 161.188 122.275 + vertex 672.246 160.597 119.034 + vertex 672.508 161.33 120.546 + endloop + endfacet + facet normal 0.820733 -0.557437 0.125145 + outer loop + vertex 672.508 161.33 120.546 + vertex 672.43 162.043 124.236 + vertex 672.148 161.188 122.275 + endloop + endfacet + facet normal 0.824027 -0.553088 0.122775 + outer loop + vertex 672.085 161.869 125.765 + vertex 672.148 161.188 122.275 + vertex 672.43 162.043 124.236 + endloop + endfacet + facet normal 0.812907 -0.570249 0.118313 + outer loop + vertex 672.43 162.043 124.236 + vertex 672.31 162.683 128.145 + vertex 672.085 161.869 125.765 + endloop + endfacet + facet normal 0.810442 -0.57347 0.119647 + outer loop + vertex 672.025 162.174 127.632 + vertex 672.085 161.869 125.765 + vertex 672.31 162.683 128.145 + endloop + endfacet + facet normal 0.82116 -0.561536 0.101853 + outer loop + vertex 671.96 162.555 130.263 + vertex 672.025 162.174 127.632 + vertex 672.31 162.683 128.145 + endloop + endfacet + facet normal 0.819775 -0.56362 0.101499 + outer loop + vertex 672.31 162.683 128.145 + vertex 672.21 163.279 132.263 + vertex 671.96 162.555 130.263 + endloop + endfacet + facet normal 0.830189 -0.549324 0.0950204 + outer loop + vertex 671.841 163.018 133.975 + vertex 671.96 162.555 130.263 + vertex 672.21 163.279 132.263 + endloop + endfacet + facet normal 0.844638 -0.527246 0.0927273 + outer loop + vertex 671.96 162.555 130.263 + vertex 671.841 163.018 133.975 + vertex 671.642 162.47 132.673 + endloop + endfacet + facet normal 0.858896 -0.50563 0.0814588 + outer loop + vertex 671.841 163.018 133.975 + vertex 671.691 163.231 136.886 + vertex 671.642 162.47 132.673 + endloop + endfacet + facet normal 0.835042 -0.543885 0.0830281 + outer loop + vertex 671.691 163.231 136.886 + vertex 671.841 163.018 133.975 + vertex 671.996 163.628 136.42 + endloop + endfacet + facet normal 0.833086 -0.547523 0.0786468 + outer loop + vertex 671.709 163.616 139.379 + vertex 671.691 163.231 136.886 + vertex 671.996 163.628 136.42 + endloop + endfacet + facet normal 0.855878 -0.510793 0.0810072 + outer loop + vertex 671.996 163.628 136.42 + vertex 672.227 164.548 139.775 + vertex 671.709 163.616 139.379 + endloop + endfacet + facet normal 0.859805 -0.505526 0.071962 + outer loop + vertex 671.691 163.231 136.886 + vertex 671.709 163.616 139.379 + vertex 671.462 163.337 140.362 + endloop + endfacet + facet normal 0.886839 -0.456396 0.0722452 + outer loop + vertex 671.462 163.337 140.362 + vertex 671.642 162.47 132.673 + vertex 671.691 163.231 136.886 + endloop + endfacet + facet normal 0.887236 -0.452888 0.087772 + outer loop + vertex 672.025 162.174 127.632 + vertex 671.96 162.555 130.263 + vertex 671.887 161.457 125.333 + endloop + endfacet + facet normal 0.865424 -0.491617 0.0967158 + outer loop + vertex 671.642 162.47 132.673 + vertex 671.887 161.457 125.333 + vertex 671.96 162.555 130.263 + endloop + endfacet + facet normal 0.843846 -0.524608 0.112742 + outer loop + vertex 672.085 161.869 125.765 + vertex 672.025 162.174 127.632 + vertex 671.887 161.457 125.333 + endloop + endfacet + facet normal 0.840437 -0.528831 0.118338 + outer loop + vertex 672.148 161.188 122.275 + vertex 672.085 161.869 125.765 + vertex 671.887 161.457 125.333 + endloop + endfacet + facet normal 0.859772 -0.497049 0.117193 + outer loop + vertex 671.887 161.457 125.333 + vertex 672.112 159.981 117.427 + vertex 672.148 161.188 122.275 + endloop + endfacet + facet normal 0.864389 -0.489435 0.115263 + outer loop + vertex 672.246 160.597 119.034 + vertex 672.148 161.188 122.275 + vertex 672.112 159.981 117.427 + endloop + endfacet + facet normal 0.856404 -0.501989 0.120745 + outer loop + vertex 672.281 160.2 117.138 + vertex 672.246 160.597 119.034 + vertex 672.112 159.981 117.427 + endloop + endfacet + facet normal 0.862779 -0.487009 0.135773 + outer loop + vertex 672.394 159.642 114.417 + vertex 672.281 160.2 117.138 + vertex 672.112 159.981 117.427 + endloop + endfacet + facet normal 0.866222 -0.48096 0.135414 + outer loop + vertex 672.112 159.981 117.427 + vertex 672.387 158.355 109.887 + vertex 672.394 159.642 114.417 + endloop + endfacet + facet normal 0.842877 -0.517933 0.145957 + outer loop + vertex 672.56 158.947 110.989 + vertex 672.394 159.642 114.417 + vertex 672.387 158.355 109.887 + endloop + endfacet + facet normal 0.829117 -0.536291 0.157975 + outer loop + vertex 672.705 158.133 107.465 + vertex 672.56 158.947 110.989 + vertex 672.387 158.355 109.887 + endloop + endfacet + facet normal 0.870751 -0.467861 0.151323 + outer loop + vertex 673.723 160.19 108.856 + vertex 674.875 161.94 107.637 + vertex 674.765 162.351 109.538 + endloop + endfacet + facet normal 0.850562 -0.504581 0.148128 + outer loop + vertex 672.781 159.8 112.888 + vertex 672.952 159.001 109.183 + vertex 673.495 160.388 110.791 + endloop + endfacet + facet normal 0.873414 -0.466884 0.138445 + outer loop + vertex 673.549 161.021 112.622 + vertex 674.678 162.781 111.433 + vertex 674.605 163.205 113.328 + endloop + endfacet + facet normal 0.852575 -0.503798 0.138934 + outer loop + vertex 672.588 160.553 116.802 + vertex 672.781 159.8 112.888 + vertex 673.344 161.219 114.581 + endloop + endfacet + facet normal 0.875091 -0.46707 0.126734 + outer loop + vertex 673.404 161.825 116.438 + vertex 674.536 163.618 115.227 + vertex 674.471 164.008 117.117 + endloop + endfacet + facet normal 0.853891 -0.50568 0.123115 + outer loop + vertex 672.508 161.33 120.546 + vertex 672.588 160.553 116.802 + vertex 673.208 161.983 118.378 + endloop + endfacet + facet normal 0.87711 -0.466009 0.116251 + outer loop + vertex 673.279 162.55 120.195 + vertex 674.399 164.358 118.994 + vertex 674.34 164.715 120.868 + endloop + endfacet + facet normal 0.855917 -0.504035 0.115567 + outer loop + vertex 672.43 162.043 124.236 + vertex 672.508 161.33 120.546 + vertex 673.102 162.7 122.126 + endloop + endfacet + facet normal 0.878606 -0.465612 0.106094 + outer loop + vertex 673.185 163.268 123.981 + vertex 674.29 165.075 122.76 + vertex 674.244 165.426 124.687 + endloop + endfacet + facet normal 0.856171 -0.505069 0.108977 + outer loop + vertex 672.31 162.683 128.145 + vertex 672.43 162.043 124.236 + vertex 673.014 163.409 125.981 + endloop + endfacet + facet normal 0.879324 -0.465965 0.098317 + outer loop + vertex 673.108 163.98 127.899 + vertex 674.21 165.795 126.644 + vertex 674.168 166.129 128.599 + endloop + endfacet + facet normal 0.858652 -0.503904 0.093799 + outer loop + vertex 672.21 163.279 132.263 + vertex 672.31 162.683 128.145 + vertex 672.924 164.061 129.933 + endloop + endfacet + facet normal 0.88044 -0.465871 0.08826 + outer loop + vertex 672.981 164.528 131.917 + vertex 674.022 166.633 132.637 + vertex 672.769 164.567 134.235 + endloop + endfacet + facet normal 0.818749 -0.567077 0.0898523 + outer loop + vertex 672.21 163.279 132.263 + vertex 671.996 163.628 136.42 + vertex 671.841 163.018 133.975 + endloop + endfacet + facet normal 0.879069 -0.469503 0.0824902 + outer loop + vertex 672.769 164.567 134.235 + vertex 674.022 166.633 132.637 + vertex 674.021 167.04 134.973 + endloop + endfacet + facet normal 0.860744 -0.502946 0.0785198 + outer loop + vertex 671.996 163.628 136.42 + vertex 672.836 165.177 137.131 + vertex 672.227 164.548 139.775 + endloop + endfacet + facet normal 0.857985 -0.508487 0.0728258 + outer loop + vertex 671.907 164.31 141.879 + vertex 671.709 163.616 139.379 + vertex 672.227 164.548 139.775 + endloop + endfacet + facet normal 0.85973 -0.505663 0.071904 + outer loop + vertex 671.709 163.616 139.379 + vertex 671.907 164.31 141.879 + vertex 671.462 163.337 140.362 + endloop + endfacet + facet normal 0.868692 -0.491668 0.0603023 + outer loop + vertex 671.907 164.31 141.879 + vertex 671.929 164.776 145.36 + vertex 671.462 163.337 140.362 + endloop + endfacet + facet normal 0.870206 -0.489722 0.0539833 + outer loop + vertex 671.929 164.776 145.36 + vertex 671.854 164.978 148.409 + vertex 671.332 164.077 148.655 + endloop + endfacet + facet normal 0.874862 -0.481046 0.0566677 + outer loop + vertex 671.332 164.077 148.655 + vertex 671.462 163.337 140.362 + vertex 671.929 164.776 145.36 + endloop + endfacet + facet normal 0.870008 -0.490376 0.0511608 + outer loop + vertex 671.854 164.978 148.409 + vertex 672.014 165.469 150.398 + vertex 671.332 164.077 148.655 + endloop + endfacet + facet normal 0.875559 -0.481304 0.0417408 + outer loop + vertex 672.014 165.469 150.398 + vertex 671.897 165.543 153.7 + vertex 671.332 164.077 148.655 + endloop + endfacet + facet normal 0.87543 -0.481532 0.0418214 + outer loop + vertex 671.185 164.52 156.826 + vertex 671.332 164.077 148.655 + vertex 671.897 165.543 153.7 + endloop + endfacet + facet normal 0.872139 -0.487696 0.0390547 + outer loop + vertex 671.897 165.543 153.7 + vertex 671.908 165.842 157.191 + vertex 671.185 164.52 156.826 + endloop + endfacet + facet normal 0.873796 -0.485496 0.0278105 + outer loop + vertex 671.908 165.842 157.191 + vertex 671.681 165.544 159.099 + vertex 671.185 164.52 156.826 + endloop + endfacet + facet normal 0.875348 -0.48278 0.0262485 + outer loop + vertex 671.681 165.544 159.099 + vertex 671.768 165.84 161.678 + vertex 671.185 164.52 156.826 + endloop + endfacet + facet normal 0.875336 -0.482802 0.0262558 + outer loop + vertex 671.101 164.774 164.315 + vertex 671.185 164.52 156.826 + vertex 671.768 165.84 161.678 + endloop + endfacet + facet normal 0.870316 -0.492034 0.021254 + outer loop + vertex 671.768 165.84 161.678 + vertex 671.93 166.287 165.364 + vertex 671.101 164.774 164.315 + endloop + endfacet + facet normal 0.873965 -0.485896 0.0095148 + outer loop + vertex 671.93 166.287 165.364 + vertex 671.74 166.015 168.972 + vertex 671.101 164.774 164.315 + endloop + endfacet + facet normal 0.871874 -0.489716 0.00376361 + outer loop + vertex 671.74 166.015 168.972 + vertex 671.634 165.849 171.852 + vertex 671.106 164.912 172.186 + endloop + endfacet + facet normal 0.876779 -0.480831 0.00777973 + outer loop + vertex 671.106 164.912 172.186 + vertex 671.101 164.774 164.315 + vertex 671.74 166.015 168.972 + endloop + endfacet + facet normal 0.871584 -0.490242 0.00182789 + outer loop + vertex 671.634 165.849 171.852 + vertex 671.831 166.206 173.778 + vertex 671.106 164.912 172.186 + endloop + endfacet + facet normal 0.877365 -0.479733 -0.00933892 + outer loop + vertex 671.831 166.206 173.778 + vertex 671.777 166.043 177.078 + vertex 671.106 164.912 172.186 + endloop + endfacet + facet normal 0.877091 -0.480237 -0.00918465 + outer loop + vertex 671.161 164.857 180.232 + vertex 671.106 164.912 172.186 + vertex 671.777 166.043 177.078 + endloop + endfacet + facet normal 0.872034 -0.489257 -0.0135645 + outer loop + vertex 671.777 166.043 177.078 + vertex 671.852 166.079 180.576 + vertex 671.161 164.857 180.232 + endloop + endfacet + facet normal 0.873188 -0.486753 -0.0247724 + outer loop + vertex 671.852 166.079 180.576 + vertex 671.684 165.681 182.468 + vertex 671.161 164.857 180.232 + endloop + endfacet + facet normal 0.872623 -0.487792 -0.024257 + outer loop + vertex 671.684 165.681 182.468 + vertex 671.86 165.87 185.011 + vertex 671.161 164.857 180.232 + endloop + endfacet + facet normal 0.872069 -0.488796 -0.0239636 + outer loop + vertex 671.283 164.713 187.623 + vertex 671.161 164.857 180.232 + vertex 671.86 165.87 185.011 + endloop + endfacet + facet normal 0.865803 -0.49948 -0.0300794 + outer loop + vertex 671.86 165.87 185.011 + vertex 672.095 166.055 188.707 + vertex 671.283 164.713 187.623 + endloop + endfacet + facet normal 0.868777 -0.493621 -0.0395582 + outer loop + vertex 672.095 166.055 188.707 + vertex 671.852 165.342 192.262 + vertex 671.283 164.713 187.623 + endloop + endfacet + facet normal 0.861392 -0.505947 -0.0449645 + outer loop + vertex 671.852 165.342 192.262 + vertex 671.644 164.709 195.412 + vertex 671.376 164.241 195.541 + endloop + endfacet + facet normal 0.868954 -0.493305 -0.0396227 + outer loop + vertex 671.376 164.241 195.541 + vertex 671.283 164.713 187.623 + vertex 671.852 165.342 192.262 + endloop + endfacet + facet normal 0.847657 -0.527656 -0.0552841 + outer loop + vertex 671.584 164.385 197.571 + vertex 671.644 164.709 195.412 + vertex 671.774 164.785 196.683 + endloop + endfacet + facet normal 0.839503 -0.539751 -0.0624801 + outer loop + vertex 671.774 164.785 196.683 + vertex 671.938 164.765 199.052 + vertex 671.584 164.385 197.571 + endloop + endfacet + facet normal 0.84187 -0.535867 -0.0640398 + outer loop + vertex 671.662 164.146 200.597 + vertex 671.584 164.385 197.571 + vertex 671.938 164.765 199.052 + endloop + endfacet + facet normal 0.837195 -0.54271 -0.067613 + outer loop + vertex 671.938 164.765 199.052 + vertex 672.073 164.536 202.564 + vertex 671.662 164.146 200.597 + endloop + endfacet + facet normal 0.837872 -0.541619 -0.0679705 + outer loop + vertex 671.773 163.881 204.089 + vertex 671.662 164.146 200.597 + vertex 672.073 164.536 202.564 + endloop + endfacet + facet normal 0.823583 -0.561616 -0.0793625 + outer loop + vertex 672.073 164.536 202.564 + vertex 672.111 164.042 206.461 + vertex 671.773 163.881 204.089 + endloop + endfacet + facet normal 0.819285 -0.568013 -0.078316 + outer loop + vertex 671.792 163.64 206.028 + vertex 671.773 163.881 204.089 + vertex 672.111 164.042 206.461 + endloop + endfacet + facet normal 0.825113 -0.557338 -0.0925365 + outer loop + vertex 671.858 163.288 208.738 + vertex 671.792 163.64 206.028 + vertex 672.111 164.042 206.461 + endloop + endfacet + facet normal 0.825177 -0.557249 -0.0925001 + outer loop + vertex 672.111 164.042 206.461 + vertex 672.218 163.534 210.467 + vertex 671.858 163.288 208.738 + endloop + endfacet + facet normal 0.828658 -0.551806 -0.0940004 + outer loop + vertex 671.941 162.818 212.228 + vertex 671.858 163.288 208.738 + vertex 672.218 163.534 210.467 + endloop + endfacet + facet normal 0.816624 -0.567998 -0.102483 + outer loop + vertex 672.218 163.534 210.467 + vertex 672.264 162.875 214.487 + vertex 671.941 162.818 212.228 + endloop + endfacet + facet normal 0.815543 -0.569585 -0.102288 + outer loop + vertex 671.957 162.494 214.157 + vertex 671.941 162.818 212.228 + vertex 672.264 162.875 214.487 + endloop + endfacet + facet normal 0.819379 -0.561581 -0.115087 + outer loop + vertex 672.03 162.071 216.743 + vertex 671.957 162.494 214.157 + vertex 672.264 162.875 214.487 + endloop + endfacet + facet normal 0.821739 -0.558403 -0.113711 + outer loop + vertex 672.264 162.875 214.487 + vertex 672.387 162.239 218.502 + vertex 672.03 162.071 216.743 + endloop + endfacet + facet normal 0.829005 -0.54702 -0.116273 + outer loop + vertex 672.139 161.454 220.424 + vertex 672.03 162.071 216.743 + vertex 672.387 162.239 218.502 + endloop + endfacet + facet normal 0.820245 -0.558803 -0.122218 + outer loop + vertex 672.387 162.239 218.502 + vertex 672.49 161.56 222.3 + vertex 672.139 161.454 220.424 + endloop + endfacet + facet normal 0.828822 -0.545467 -0.124578 + outer loop + vertex 672.217 160.774 223.921 + vertex 672.139 161.454 220.424 + vertex 672.49 161.56 222.3 + endloop + endfacet + facet normal 0.81975 -0.557335 -0.131861 + outer loop + vertex 672.49 161.56 222.3 + vertex 672.574 160.743 226.27 + vertex 672.217 160.774 223.921 + endloop + endfacet + facet normal 0.817129 -0.561252 -0.131516 + outer loop + vertex 672.281 160.214 226.713 + vertex 672.217 160.774 223.921 + vertex 672.574 160.743 226.27 + endloop + endfacet + facet normal 0.806833 -0.571325 -0.150364 + outer loop + vertex 672.374 159.846 228.608 + vertex 672.281 160.214 226.713 + vertex 672.574 160.743 226.27 + endloop + endfacet + facet normal 0.809355 -0.568126 -0.148922 + outer loop + vertex 672.574 160.743 226.27 + vertex 672.744 159.995 230.044 + vertex 672.374 159.846 228.608 + endloop + endfacet + facet normal 0.820845 -0.550068 -0.153752 + outer loop + vertex 672.502 159.139 231.819 + vertex 672.374 159.846 228.608 + vertex 672.744 159.995 230.044 + endloop + endfacet + facet normal 0.817288 -0.554592 -0.15642 + outer loop + vertex 672.744 159.995 230.044 + vertex 672.914 159.216 233.701 + vertex 672.502 159.139 231.819 + endloop + endfacet + facet normal 0.820789 -0.549116 -0.157409 + outer loop + vertex 672.667 158.409 235.229 + vertex 672.502 159.139 231.819 + vertex 672.914 159.216 233.701 + endloop + endfacet + facet normal 0.802908 -0.570824 -0.171753 + outer loop + vertex 672.914 159.216 233.701 + vertex 673.062 158.303 237.426 + vertex 672.667 158.409 235.229 + endloop + endfacet + facet normal 0.79937 -0.575885 -0.171359 + outer loop + vertex 672.74 157.97 237.042 + vertex 672.667 158.409 235.229 + vertex 673.062 158.303 237.426 + endloop + endfacet + facet normal 0.805603 -0.561447 -0.18916 + outer loop + vertex 672.919 157.391 239.525 + vertex 672.74 157.97 237.042 + vertex 673.062 158.303 237.426 + endloop + endfacet + facet normal 0.810839 -0.554937 -0.185972 + outer loop + vertex 673.062 158.303 237.426 + vertex 673.352 157.483 241.136 + vertex 672.919 157.391 239.525 + endloop + endfacet + facet normal 0.824156 -0.533259 -0.190793 + outer loop + vertex 673.182 156.516 243.104 + vertex 672.919 157.391 239.525 + vertex 673.352 157.483 241.136 + endloop + endfacet + facet normal 0.806028 -0.555817 -0.203438 + outer loop + vertex 673.352 157.483 241.136 + vertex 673.623 156.526 244.827 + vertex 673.182 156.516 243.104 + endloop + endfacet + facet normal 0.824989 -0.525299 -0.208458 + outer loop + vertex 673.481 155.525 246.787 + vertex 673.182 156.516 243.104 + vertex 673.623 156.526 244.827 + endloop + endfacet + facet normal 0.810969 -0.542797 -0.218405 + outer loop + vertex 673.623 156.526 244.827 + vertex 673.967 155.475 248.714 + vertex 673.481 155.525 246.787 + endloop + endfacet + facet normal 0.872714 -0.448982 -0.191798 + outer loop + vertex 673.182 156.516 243.104 + vertex 673.481 155.525 246.787 + vertex 672.914 156.436 242.075 + endloop + endfacet + facet normal 0.851042 -0.492268 -0.182758 + outer loop + vertex 672.919 157.391 239.525 + vertex 673.182 156.516 243.104 + vertex 672.914 156.436 242.075 + endloop + endfacet + facet normal 0.928569 -0.340986 -0.146588 + outer loop + vertex 672.74 157.97 237.042 + vertex 672.919 157.391 239.525 + vertex 672.472 158.191 234.833 + endloop + endfacet + facet normal 0.891604 -0.4246 -0.157342 + outer loop + vertex 672.914 156.436 242.075 + vertex 672.472 158.191 234.833 + vertex 672.919 157.391 239.525 + endloop + endfacet + facet normal 0.857921 -0.490464 -0.153026 + outer loop + vertex 672.667 158.409 235.229 + vertex 672.74 157.97 237.042 + vertex 672.472 158.191 234.833 + endloop + endfacet + facet normal 0.85498 -0.497117 -0.14793 + outer loop + vertex 672.502 159.139 231.819 + vertex 672.667 158.409 235.229 + vertex 672.472 158.191 234.833 + endloop + endfacet + facet normal 0.872923 -0.468007 -0.137752 + outer loop + vertex 672.374 159.846 228.608 + vertex 672.502 159.139 231.819 + vertex 672.128 159.866 226.977 + endloop + endfacet + facet normal 0.863401 -0.485693 -0.136533 + outer loop + vertex 672.281 160.214 226.713 + vertex 672.374 159.846 228.608 + vertex 672.128 159.866 226.977 + endloop + endfacet + facet normal 0.873085 -0.473756 -0.11523 + outer loop + vertex 672.217 160.774 223.921 + vertex 672.281 160.214 226.713 + vertex 672.128 159.866 226.977 + endloop + endfacet + facet normal 0.870363 -0.478386 -0.116685 + outer loop + vertex 672.128 159.866 226.977 + vertex 671.884 161.299 219.285 + vertex 672.217 160.774 223.921 + endloop + endfacet + facet normal 0.847907 -0.516528 -0.119383 + outer loop + vertex 672.139 161.454 220.424 + vertex 672.217 160.774 223.921 + vertex 671.884 161.299 219.285 + endloop + endfacet + facet normal 0.837151 -0.534858 -0.114474 + outer loop + vertex 672.03 162.071 216.743 + vertex 672.139 161.454 220.424 + vertex 671.884 161.299 219.285 + endloop + endfacet + facet normal 0.894303 -0.436865 -0.0968038 + outer loop + vertex 671.957 162.494 214.157 + vertex 672.03 162.071 216.743 + vertex 671.725 162.533 211.845 + endloop + endfacet + facet normal 0.864185 -0.49309 -0.100228 + outer loop + vertex 671.884 161.299 219.285 + vertex 671.725 162.533 211.845 + vertex 672.03 162.071 216.743 + endloop + endfacet + facet normal 0.85079 -0.51707 -0.0937765 + outer loop + vertex 671.941 162.818 212.228 + vertex 671.957 162.494 214.157 + vertex 671.725 162.533 211.845 + endloop + endfacet + facet normal 0.849081 -0.520493 -0.0902636 + outer loop + vertex 671.858 163.288 208.738 + vertex 671.941 162.818 212.228 + vertex 671.725 162.533 211.845 + endloop + endfacet + facet normal 0.895455 -0.438131 -0.0787536 + outer loop + vertex 671.792 163.64 206.028 + vertex 671.858 163.288 208.738 + vertex 671.545 163.539 203.784 + endloop + endfacet + facet normal 0.873366 -0.480531 -0.0795106 + outer loop + vertex 671.725 162.533 211.845 + vertex 671.545 163.539 203.784 + vertex 671.858 163.288 208.738 + endloop + endfacet + facet normal 0.857637 -0.509274 -0.0713988 + outer loop + vertex 671.773 163.881 204.089 + vertex 671.792 163.64 206.028 + vertex 671.545 163.539 203.784 + endloop + endfacet + facet normal 0.856001 -0.512698 -0.0663506 + outer loop + vertex 671.662 164.146 200.597 + vertex 671.773 163.881 204.089 + vertex 671.545 163.539 203.784 + endloop + endfacet + facet normal 0.877743 -0.475549 -0.0584804 + outer loop + vertex 671.545 163.539 203.784 + vertex 671.376 164.241 195.541 + vertex 671.662 164.146 200.597 + endloop + endfacet + facet normal 0.889557 -0.453033 -0.0587277 + outer loop + vertex 671.584 164.385 197.571 + vertex 671.662 164.146 200.597 + vertex 671.376 164.241 195.541 + endloop + endfacet + facet normal 0.860261 -0.507209 -0.0518698 + outer loop + vertex 671.644 164.709 195.412 + vertex 671.584 164.385 197.571 + vertex 671.376 164.241 195.541 + endloop + endfacet + facet normal 0.882623 -0.467609 -0.0481512 + outer loop + vertex 672.224 165.81 194.425 + vertex 673.247 168.107 190.868 + vertex 673.64 168.505 194.211 + endloop + endfacet + facet normal 0.861015 -0.50458 -0.0636619 + outer loop + vertex 671.938 164.765 199.052 + vertex 671.774 164.785 196.683 + vertex 672.448 165.941 196.631 + endloop + endfacet + facet normal 0.883688 -0.463553 -0.0649233 + outer loop + vertex 672.693 166.129 198.416 + vertex 673.79 168.445 196.808 + vertex 673.826 168.203 199.031 + endloop + endfacet + facet normal 0.860361 -0.505384 -0.0660724 + outer loop + vertex 672.073 164.536 202.564 + vertex 671.938 164.765 199.052 + vertex 672.652 165.799 200.443 + endloop + endfacet + facet normal 0.883965 -0.463304 -0.0628894 + outer loop + vertex 672.834 165.871 202.314 + vertex 673.878 168.032 201.065 + vertex 673.924 167.856 203.008 + endloop + endfacet + facet normal 0.861481 -0.502622 -0.0722576 + outer loop + vertex 672.111 164.042 206.461 + vertex 672.073 164.536 202.564 + vertex 672.741 165.431 204.295 + endloop + endfacet + facet normal 0.882567 -0.464309 -0.0741204 + outer loop + vertex 672.894 165.417 206.162 + vertex 673.949 167.622 204.905 + vertex 673.979 167.381 206.776 + endloop + endfacet + facet normal 0.859105 -0.504401 -0.0867084 + outer loop + vertex 672.218 163.534 210.467 + vertex 672.111 164.042 206.461 + vertex 672.803 164.931 208.14 + endloop + endfacet + facet normal 0.881753 -0.464237 -0.0836423 + outer loop + vertex 672.966 164.891 210.011 + vertex 674.008 167.115 208.65 + vertex 674.041 166.83 210.577 + endloop + endfacet + facet normal 0.858459 -0.504465 -0.0925383 + outer loop + vertex 672.264 162.875 214.487 + vertex 672.218 163.534 210.467 + vertex 672.87 164.348 212.082 + endloop + endfacet + facet normal 0.880381 -0.465239 -0.0920975 + outer loop + vertex 673.039 164.275 214.033 + vertex 674.087 166.548 212.575 + vertex 674.126 166.216 214.62 + endloop + endfacet + facet normal 0.858132 -0.502377 -0.105956 + outer loop + vertex 672.387 162.239 218.502 + vertex 672.264 162.875 214.487 + vertex 672.964 163.722 216.139 + endloop + endfacet + facet normal 0.879973 -0.464286 -0.100426 + outer loop + vertex 673.134 163.609 218.065 + vertex 674.173 165.881 216.662 + vertex 674.227 165.553 218.653 + endloop + endfacet + facet normal 0.85827 -0.500637 -0.112851 + outer loop + vertex 672.49 161.56 222.3 + vertex 672.387 162.239 218.502 + vertex 673.059 163.038 220.07 + endloop + endfacet + facet normal 0.878586 -0.464625 -0.110495 + outer loop + vertex 673.224 162.899 221.91 + vertex 674.271 165.194 220.586 + vertex 674.332 164.859 222.48 + endloop + endfacet + facet normal 0.856328 -0.502 -0.121239 + outer loop + vertex 672.574 160.743 226.27 + vertex 672.49 161.56 222.3 + vertex 673.166 162.327 223.891 + endloop + endfacet + facet normal 0.875939 -0.466598 -0.122545 + outer loop + vertex 673.349 162.183 225.735 + vertex 674.395 164.505 224.37 + vertex 674.453 164.114 226.276 + endloop + endfacet + facet normal 0.852124 -0.504736 -0.138297 + outer loop + vertex 672.744 159.995 230.044 + vertex 672.574 160.743 226.27 + vertex 673.287 161.547 227.73 + endloop + endfacet + facet normal 0.874854 -0.465876 -0.132631 + outer loop + vertex 673.486 161.381 229.574 + vertex 674.518 163.707 228.207 + vertex 674.594 163.296 230.149 + endloop + endfacet + facet normal 0.851773 -0.502867 -0.146995 + outer loop + vertex 672.914 159.216 233.701 + vertex 672.744 159.995 230.044 + vertex 673.446 160.744 231.556 + endloop + endfacet + facet normal 0.872804 -0.466365 -0.143937 + outer loop + vertex 673.654 160.554 233.388 + vertex 674.67 162.859 232.081 + vertex 674.773 162.469 233.968 + endloop + endfacet + facet normal 0.848708 -0.504887 -0.157427 + outer loop + vertex 673.062 158.303 237.426 + vertex 672.914 159.216 233.701 + vertex 673.622 159.905 235.309 + endloop + endfacet + facet normal 0.869267 -0.468171 -0.158715 + outer loop + vertex 673.85 159.728 237.069 + vertex 674.866 162.044 235.801 + vertex 674.971 161.635 237.584 + endloop + endfacet + facet normal 0.845774 -0.503232 -0.177267 + outer loop + vertex 673.352 157.483 241.136 + vertex 673.062 158.303 237.426 + vertex 673.84 159.083 238.926 + endloop + endfacet + facet normal 0.866595 -0.468075 -0.17297 + outer loop + vertex 674.077 158.873 240.644 + vertex 675.078 161.205 239.349 + vertex 675.204 160.777 241.139 + endloop + endfacet + facet normal 0.844436 -0.500133 -0.191819 + outer loop + vertex 673.623 156.526 244.827 + vertex 673.352 157.483 241.136 + vertex 674.076 158.167 242.54 + endloop + endfacet + facet normal 0.862918 -0.468441 -0.189568 + outer loop + vertex 674.339 157.926 244.322 + vertex 675.332 160.301 242.976 + vertex 675.487 159.821 244.865 + endloop + endfacet + facet normal 0.842854 -0.496073 -0.208589 + outer loop + vertex 673.967 155.475 248.714 + vertex 673.623 156.526 244.827 + vertex 674.385 157.192 246.318 + endloop + endfacet + facet normal 0.858545 -0.468013 -0.209438 + outer loop + vertex 674.676 156.889 248.186 + vertex 675.661 159.324 246.786 + vertex 675.851 158.805 248.722 + endloop + endfacet + facet normal 0.839589 -0.494187 -0.225545 + outer loop + vertex 674.464 154.496 252.709 + vertex 673.967 155.475 248.714 + vertex 674.783 156.163 250.243 + endloop + endfacet + facet normal 0.85495 -0.46706 -0.225643 + outer loop + vertex 675.149 155.927 252.121 + vertex 676.092 158.358 250.664 + vertex 676.343 157.873 252.615 + endloop + endfacet + facet normal 0.838061 -0.48874 -0.242458 + outer loop + vertex 675.041 153.786 256.134 + vertex 674.464 154.496 252.709 + vertex 675.312 155.262 254.096 + endloop + endfacet + facet normal 0.830095 -0.501519 -0.243764 + outer loop + vertex 674.464 154.496 252.709 + vertex 675.041 153.786 256.134 + vertex 674.581 153.305 255.557 + endloop + endfacet + facet normal 0.834629 -0.484966 -0.261157 + outer loop + vertex 675.041 153.786 256.134 + vertex 675.565 152.799 259.641 + vertex 674.581 153.305 255.557 + endloop + endfacet + facet normal 0.838001 -0.477381 -0.264313 + outer loop + vertex 675.691 154.991 255.906 + vertex 676.567 157.269 254.57 + vertex 676.719 156.493 256.45 + endloop + endfacet + facet normal 0.831492 -0.489843 -0.26206 + outer loop + vertex 675.565 152.799 259.641 + vertex 675.041 153.786 256.134 + vertex 675.854 154.274 257.802 + endloop + endfacet + facet normal 0.830237 -0.488194 -0.269023 + outer loop + vertex 676.287 154.028 259.59 + vertex 676.964 155.937 258.215 + vertex 677.333 155.59 259.982 + endloop + endfacet + facet normal 0.828138 -0.481015 -0.287772 + outer loop + vertex 676.363 151.607 263.931 + vertex 675.565 152.799 259.641 + vertex 676.523 153.299 261.563 + endloop + endfacet + facet normal 0.816066 -0.482116 -0.31875 + outer loop + vertex 677.239 150.409 267.985 + vertex 676.363 151.607 263.931 + vertex 677.25 152.159 265.368 + endloop + endfacet + facet normal 0.819876 -0.487279 -0.300605 + outer loop + vertex 676.985 152.962 263.401 + vertex 677.679 155.106 261.816 + vertex 678.018 154.546 263.648 + endloop + endfacet + facet normal 0.807197 -0.485193 -0.336186 + outer loop + vertex 677.754 151.86 267.066 + vertex 678.8 153.494 267.221 + vertex 678.103 151.17 268.899 + endloop + endfacet + facet normal 0.80336 -0.487861 -0.341473 + outer loop + vertex 678.103 151.17 268.899 + vertex 678.8 153.494 267.221 + vertex 679.261 153.004 269.005 + endloop + endfacet + facet normal 0.799583 -0.48472 -0.354561 + outer loop + vertex 678.103 151.17 268.899 + vertex 679.261 153.004 269.005 + vertex 678.665 150.908 270.526 + endloop + endfacet + facet normal 0.793194 -0.495448 -0.354083 + outer loop + vertex 678.665 150.908 270.526 + vertex 678.118 149.625 271.097 + vertex 678.103 151.17 268.899 + endloop + endfacet + facet normal 0.784546 -0.498373 -0.368932 + outer loop + vertex 678.665 150.908 270.526 + vertex 679.084 150.194 272.382 + vertex 678.118 149.625 271.097 + endloop + endfacet + facet normal 0.796597 -0.481699 -0.365239 + outer loop + vertex 678.665 150.908 270.526 + vertex 679.773 152.528 270.807 + vertex 679.084 150.194 272.382 + endloop + endfacet + facet normal 0.791781 -0.48466 -0.371737 + outer loop + vertex 679.084 150.194 272.382 + vertex 679.773 152.528 270.807 + vertex 680.327 152.024 272.642 + endloop + endfacet + facet normal 0.788142 -0.480323 -0.384867 + outer loop + vertex 679.084 150.194 272.382 + vertex 680.327 152.024 272.642 + vertex 679.767 149.925 274.116 + endloop + endfacet + facet normal 0.782635 -0.489794 -0.384166 + outer loop + vertex 679.767 149.925 274.116 + vertex 679.093 148.583 274.454 + vertex 679.084 150.194 272.382 + endloop + endfacet + facet normal 0.773319 -0.489755 -0.402637 + outer loop + vertex 679.767 149.925 274.116 + vertex 680.322 149.211 276.05 + vertex 679.093 148.583 274.454 + endloop + endfacet + facet normal 0.781958 -0.477553 -0.400606 + outer loop + vertex 679.767 149.925 274.116 + vertex 680.94 151.538 274.482 + vertex 680.322 149.211 276.05 + endloop + endfacet + facet normal 0.775904 -0.481029 -0.408147 + outer loop + vertex 680.322 149.211 276.05 + vertex 680.94 151.538 274.482 + vertex 681.599 151.04 276.323 + endloop + endfacet + facet normal 0.771813 -0.476207 -0.421345 + outer loop + vertex 680.322 149.211 276.05 + vertex 681.599 151.04 276.323 + vertex 681.124 148.92 277.849 + endloop + endfacet + facet normal 0.767572 -0.483615 -0.420653 + outer loop + vertex 681.124 148.92 277.849 + vertex 680.526 147.52 278.366 + vertex 680.322 149.211 276.05 + endloop + endfacet + facet normal 0.753309 -0.485857 -0.443247 + outer loop + vertex 681.124 148.92 277.849 + vertex 681.792 148.193 279.78 + vertex 680.526 147.52 278.366 + endloop + endfacet + facet normal 0.762402 -0.473038 -0.441564 + outer loop + vertex 681.124 148.92 277.849 + vertex 682.315 150.57 278.137 + vertex 681.792 148.193 279.78 + endloop + endfacet + facet normal 0.75735 -0.475834 -0.447217 + outer loop + vertex 681.792 148.193 279.78 + vertex 682.315 150.57 278.137 + vertex 683.071 150.093 279.926 + endloop + endfacet + facet normal 0.750889 -0.470214 -0.46375 + outer loop + vertex 681.792 148.193 279.78 + vertex 683.071 150.093 279.926 + vertex 682.698 147.942 281.502 + endloop + endfacet + facet normal 0.748745 -0.474162 -0.463196 + outer loop + vertex 682.698 147.942 281.502 + vertex 682.2 146.476 282.197 + vertex 681.792 148.193 279.78 + endloop + endfacet + facet normal 0.729728 -0.47928 -0.487636 + outer loop + vertex 682.698 147.942 281.502 + vertex 683.509 147.254 283.392 + vertex 682.2 146.476 282.197 + endloop + endfacet + facet normal 0.739203 -0.465522 -0.48669 + outer loop + vertex 682.698 147.942 281.502 + vertex 683.888 149.634 281.691 + vertex 683.509 147.254 283.392 + endloop + endfacet + facet normal 0.735968 -0.467292 -0.489887 + outer loop + vertex 683.509 147.254 283.392 + vertex 683.888 149.634 281.691 + vertex 684.761 149.192 283.424 + endloop + endfacet + facet normal 0.727319 -0.461404 -0.508049 + outer loop + vertex 683.509 147.254 283.392 + vertex 684.761 149.192 283.424 + vertex 684.503 147.026 285.021 + endloop + endfacet + facet normal 0.730638 -0.454886 -0.509162 + outer loop + vertex 684.503 147.026 285.021 + vertex 684.176 145.557 285.865 + vertex 683.509 147.254 283.392 + endloop + endfacet + facet normal 0.708514 -0.463276 -0.532337 + outer loop + vertex 684.503 147.026 285.021 + vertex 685.411 146.432 286.747 + vertex 684.176 145.557 285.865 + endloop + endfacet + facet normal 0.712599 -0.456986 -0.532322 + outer loop + vertex 684.503 147.026 285.021 + vertex 685.689 148.769 285.113 + vertex 685.411 146.432 286.747 + endloop + endfacet + facet normal 0.707258 -0.459689 -0.537096 + outer loop + vertex 685.411 146.432 286.747 + vertex 685.689 148.769 285.113 + vertex 686.692 148.4 286.75 + endloop + endfacet + facet normal 0.696201 -0.452462 -0.557299 + outer loop + vertex 685.411 146.432 286.747 + vertex 686.692 148.4 286.75 + vertex 686.523 146.333 288.217 + endloop + endfacet + facet normal 0.695409 -0.454265 -0.556821 + outer loop + vertex 686.523 146.333 288.217 + vertex 686.082 144.977 288.772 + vertex 685.411 146.432 286.747 + endloop + endfacet + facet normal 0.673984 -0.456962 -0.580458 + outer loop + vertex 686.523 146.333 288.217 + vertex 687.563 145.789 289.852 + vertex 686.082 144.977 288.772 + endloop + endfacet + facet normal 0.679672 -0.447745 -0.581008 + outer loop + vertex 686.523 146.333 288.217 + vertex 687.788 148.1 288.334 + vertex 687.563 145.789 289.852 + endloop + endfacet + facet normal 0.671672 -0.451265 -0.587552 + outer loop + vertex 687.563 145.789 289.852 + vertex 687.788 148.1 288.334 + vertex 688.962 147.87 289.853 + endloop + endfacet + facet normal 0.66092 -0.444031 -0.604997 + outer loop + vertex 687.563 145.789 289.852 + vertex 688.962 147.87 289.853 + vertex 688.834 145.775 291.251 + endloop + endfacet + facet normal 0.65647 -0.455817 -0.601064 + outer loop + vertex 688.834 145.775 291.251 + vertex 688.166 144.145 291.758 + vertex 687.563 145.789 289.852 + endloop + endfacet + facet normal 0.635012 -0.454389 -0.624733 + outer loop + vertex 688.834 145.775 291.251 + vertex 689.914 145.187 292.777 + vertex 688.166 144.145 291.758 + endloop + endfacet + facet normal 0.64347 -0.441107 -0.625597 + outer loop + vertex 688.834 145.775 291.251 + vertex 690.161 147.701 291.258 + vertex 689.914 145.187 292.777 + endloop + endfacet + facet normal 0.632411 -0.445092 -0.633995 + outer loop + vertex 689.914 145.187 292.777 + vertex 690.161 147.701 291.258 + vertex 691.332 147.689 292.436 + endloop + endfacet + facet normal 0.652827 -0.447615 -0.611112 + outer loop + vertex 688.834 145.775 291.251 + vertex 688.962 147.87 289.853 + vertex 690.161 147.701 291.258 + endloop + endfacet + facet normal 0.689402 -0.4559 -0.562921 + outer loop + vertex 686.523 146.333 288.217 + vertex 686.692 148.4 286.75 + vertex 687.788 148.1 288.334 + endloop + endfacet + facet normal 0.72197 -0.464378 -0.512946 + outer loop + vertex 684.503 147.026 285.021 + vertex 684.761 149.192 283.424 + vertex 685.689 148.769 285.113 + endloop + endfacet + facet normal 0.746524 -0.472731 -0.468217 + outer loop + vertex 682.698 147.942 281.502 + vertex 683.071 150.093 279.926 + vertex 683.888 149.634 281.691 + endloop + endfacet + facet normal 0.767111 -0.479019 -0.426711 + outer loop + vertex 681.124 148.92 277.849 + vertex 681.599 151.04 276.323 + vertex 682.315 150.57 278.137 + endloop + endfacet + facet normal 0.7849 -0.482332 -0.388957 + outer loop + vertex 679.767 149.925 274.116 + vertex 680.327 152.024 272.642 + vertex 680.94 151.538 274.482 + endloop + endfacet + facet normal 0.799031 -0.485094 -0.355293 + outer loop + vertex 678.665 150.908 270.526 + vertex 679.261 153.004 269.005 + vertex 679.773 152.528 270.807 + endloop + endfacet +endsolid diff --git a/noether_examples/meshes/outputs/output_14.stl b/noether_examples/meshes/outputs/output_14.stl new file mode 100644 index 00000000..af48b446 --- /dev/null +++ b/noether_examples/meshes/outputs/output_14.stl @@ -0,0 +1,6547 @@ +solid ascii + facet normal 0.238586 -0.376094 0.895338 + outer loop + vertex 729.65 152.688 35.367 + vertex 729.355 155.053 36.4391 + vertex 720.779 148.506 35.9744 + endloop + endfacet + facet normal 0.243226 -0.375132 0.894493 + outer loop + vertex 729.65 152.688 35.367 + vertex 738.255 159.336 35.8152 + vertex 729.355 155.053 36.4391 + endloop + endfacet + facet normal 0.2113 -0.335396 0.918075 + outer loop + vertex 738.391 156.883 34.8878 + vertex 738.255 159.336 35.8152 + vertex 729.65 152.688 35.367 + endloop + endfacet + facet normal 0.213731 -0.335091 0.917624 + outer loop + vertex 738.391 156.883 34.8878 + vertex 746.823 163.539 35.3543 + vertex 738.255 159.336 35.8152 + endloop + endfacet + facet normal 0.192047 -0.308601 0.931603 + outer loop + vertex 746.891 161.075 34.5242 + vertex 746.823 163.539 35.3543 + vertex 738.391 156.883 34.8878 + endloop + endfacet + facet normal 0.192489 -0.308562 0.931524 + outer loop + vertex 746.891 161.075 34.5242 + vertex 755.197 167.807 35.0379 + vertex 746.823 163.539 35.3543 + endloop + endfacet + facet normal 0.177531 -0.290768 0.940179 + outer loop + vertex 755.259 165.385 34.2771 + vertex 755.197 167.807 35.0379 + vertex 746.891 161.075 34.5242 + endloop + endfacet + facet normal 0.178665 -0.290679 0.939992 + outer loop + vertex 755.259 165.385 34.2771 + vertex 763.486 172.277 34.8448 + vertex 755.197 167.807 35.0379 + endloop + endfacet + facet normal 0.170189 -0.280934 0.944517 + outer loop + vertex 763.531 169.871 34.1208 + vertex 763.486 172.277 34.8448 + vertex 755.259 165.385 34.2771 + endloop + endfacet + facet normal 0.173735 -0.280694 0.943942 + outer loop + vertex 763.531 169.871 34.1208 + vertex 771.638 176.965 34.7383 + vertex 763.486 172.277 34.8448 + endloop + endfacet + facet normal 0.168762 -0.27523 0.94645 + outer loop + vertex 771.644 174.537 34.0311 + vertex 771.638 176.965 34.7383 + vertex 763.531 169.871 34.1208 + endloop + endfacet + facet normal 0.175594 -0.274882 0.945308 + outer loop + vertex 771.644 174.537 34.0311 + vertex 779.562 181.823 34.6788 + vertex 771.638 176.965 34.7383 + endloop + endfacet + facet normal 0.176461 -0.275786 0.944883 + outer loop + vertex 779.587 179.398 33.9667 + vertex 779.562 181.823 34.6788 + vertex 771.644 174.537 34.0311 + endloop + endfacet + facet normal 0.183119 -0.275381 0.943733 + outer loop + vertex 779.587 179.398 33.9667 + vertex 787.287 186.898 34.6609 + vertex 779.562 181.823 34.6788 + endloop + endfacet + facet normal 0.189847 -0.281985 0.940448 + outer loop + vertex 787.423 184.52 33.9205 + vertex 787.287 186.898 34.6609 + vertex 779.587 179.398 33.9667 + endloop + endfacet + facet normal 0.194309 -0.281492 0.939684 + outer loop + vertex 787.423 184.52 33.9205 + vertex 794.817 192.187 34.6883 + vertex 787.287 186.898 34.6609 + endloop + endfacet + facet normal 0.203445 -0.289853 0.935198 + outer loop + vertex 795.141 189.866 33.8981 + vertex 794.817 192.187 34.6883 + vertex 787.423 184.52 33.9205 + endloop + endfacet + facet normal 0.202827 -0.289972 0.935295 + outer loop + vertex 795.141 189.866 33.8981 + vertex 802.095 197.679 34.8126 + vertex 794.817 192.187 34.6883 + endloop + endfacet + facet normal 0.216763 -0.301576 0.928475 + outer loop + vertex 802.608 195.395 33.9509 + vertex 802.095 197.679 34.8126 + vertex 795.141 189.866 33.8981 + endloop + endfacet + facet normal 0.208685 -0.303814 0.929595 + outer loop + vertex 802.608 195.395 33.9509 + vertex 809.022 203.219 35.0684 + vertex 802.095 197.679 34.8126 + endloop + endfacet + facet normal 0.196728 -0.2892 0.936836 + outer loop + vertex 809.022 203.219 35.0684 + vertex 808.56 204.379 35.5235 + vertex 802.095 197.679 34.8126 + endloop + endfacet + facet normal 0.183019 -0.276667 0.943376 + outer loop + vertex 802.095 197.679 34.8126 + vertex 808.56 204.379 35.5235 + vertex 801.735 198.838 35.2222 + endloop + endfacet + facet normal 0.190671 -0.274029 0.942631 + outer loop + vertex 802.095 197.679 34.8126 + vertex 801.735 198.838 35.2222 + vertex 794.817 192.187 34.6883 + endloop + endfacet + facet normal 0.180779 -0.264121 0.947396 + outer loop + vertex 794.817 192.187 34.6883 + vertex 801.735 198.838 35.2222 + vertex 794.53 193.361 35.0703 + endloop + endfacet + facet normal 0.181866 -0.263815 0.947273 + outer loop + vertex 794.817 192.187 34.6883 + vertex 794.53 193.361 35.0703 + vertex 787.287 186.898 34.6609 + endloop + endfacet + facet normal 0.172489 -0.253595 0.951807 + outer loop + vertex 787.287 186.898 34.6609 + vertex 794.53 193.361 35.0703 + vertex 787.005 188.045 35.0177 + endloop + endfacet + facet normal 0.169392 -0.254457 0.952133 + outer loop + vertex 787.287 186.898 34.6609 + vertex 787.005 188.045 35.0177 + vertex 779.562 181.823 34.6788 + endloop + endfacet + facet normal 0.16793 -0.252749 0.952847 + outer loop + vertex 779.562 181.823 34.6788 + vertex 787.005 188.045 35.0177 + vertex 779.333 183.006 35.0331 + endloop + endfacet + facet normal 0.162802 -0.253913 0.953427 + outer loop + vertex 779.562 181.823 34.6788 + vertex 779.333 183.006 35.0331 + vertex 771.638 176.965 34.7383 + endloop + endfacet + facet normal 0.163069 -0.254247 0.953293 + outer loop + vertex 771.638 176.965 34.7383 + vertex 779.333 183.006 35.0331 + vertex 771.336 178.098 35.0921 + endloop + endfacet + facet normal 0.159295 -0.255361 0.953633 + outer loop + vertex 771.638 176.965 34.7383 + vertex 771.336 178.098 35.0921 + vertex 763.486 172.277 34.8448 + endloop + endfacet + facet normal 0.158193 -0.2539 0.954206 + outer loop + vertex 763.486 172.277 34.8448 + vertex 771.336 178.098 35.0921 + vertex 763.084 173.41 35.2128 + endloop + endfacet + facet normal 0.158997 -0.253598 0.954153 + outer loop + vertex 763.486 172.277 34.8448 + vertex 763.084 173.41 35.2128 + vertex 755.197 167.807 35.0379 + endloop + endfacet + facet normal 0.161263 -0.25675 0.952929 + outer loop + vertex 755.197 167.807 35.0379 + vertex 763.084 173.41 35.2128 + vertex 754.802 169.036 35.4358 + endloop + endfacet + facet normal 0.16603 -0.255096 0.952555 + outer loop + vertex 755.197 167.807 35.0379 + vertex 754.802 169.036 35.4358 + vertex 746.823 163.539 35.3543 + endloop + endfacet + facet normal 0.176687 -0.27047 0.946376 + outer loop + vertex 746.823 163.539 35.3543 + vertex 754.802 169.036 35.4358 + vertex 746.424 164.82 35.795 + endloop + endfacet + facet normal 0.182562 -0.268457 0.945834 + outer loop + vertex 746.823 163.539 35.3543 + vertex 746.424 164.82 35.795 + vertex 738.255 159.336 35.8152 + endloop + endfacet + facet normal 0.203678 -0.299961 0.931954 + outer loop + vertex 738.255 159.336 35.8152 + vertex 746.424 164.82 35.795 + vertex 737.82 160.64 36.33 + endloop + endfacet + facet normal 0.208734 -0.298071 0.931442 + outer loop + vertex 738.255 159.336 35.8152 + vertex 737.82 160.64 36.33 + vertex 729.355 155.053 36.4391 + endloop + endfacet + facet normal 0.243323 -0.351011 0.904204 + outer loop + vertex 729.355 155.053 36.4391 + vertex 737.82 160.64 36.33 + vertex 728.77 156.357 37.1027 + endloop + endfacet + facet normal 0.247879 -0.348778 0.903831 + outer loop + vertex 729.355 155.053 36.4391 + vertex 728.77 156.357 37.1027 + vertex 720.295 150.797 37.2816 + endloop + endfacet + facet normal 0.164346 -0.215077 0.962669 + outer loop + vertex 746.424 164.82 35.795 + vertex 745.15 164.885 36.027 + vertex 737.82 160.64 36.33 + endloop + endfacet + facet normal 0.186615 -0.254512 0.948893 + outer loop + vertex 737.82 160.64 36.33 + vertex 745.15 164.885 36.027 + vertex 736.783 160.962 36.6202 + endloop + endfacet + facet normal 0.193183 -0.236393 0.95226 + outer loop + vertex 737.82 160.64 36.33 + vertex 736.783 160.962 36.6202 + vertex 728.77 156.357 37.1027 + endloop + endfacet + facet normal 0.228205 -0.300067 0.926219 + outer loop + vertex 728.77 156.357 37.1027 + vertex 736.783 160.962 36.6202 + vertex 727.142 156.538 37.5626 + endloop + endfacet + facet normal 0.23329 -0.272659 0.933399 + outer loop + vertex 728.77 156.357 37.1027 + vertex 727.142 156.538 37.5626 + vertex 719.591 152.124 38.1604 + endloop + endfacet + facet normal 0.287018 -0.371388 0.883002 + outer loop + vertex 719.591 152.124 38.1604 + vertex 727.142 156.538 37.5626 + vertex 718.219 152.508 38.7682 + endloop + endfacet + facet normal 0.29561 -0.350026 0.888874 + outer loop + vertex 719.591 152.124 38.1604 + vertex 718.219 152.508 38.7682 + vertex 711.117 148.446 39.53 + endloop + endfacet + facet normal 0.162452 -0.235967 0.958086 + outer loop + vertex 746.424 164.82 35.795 + vertex 753.473 169.118 35.6584 + vertex 745.15 164.885 36.027 + endloop + endfacet + facet normal 0.148583 -0.212979 0.965693 + outer loop + vertex 754.802 169.036 35.4358 + vertex 753.473 169.118 35.6584 + vertex 746.424 164.82 35.795 + endloop + endfacet + facet normal 0.146889 -0.230333 0.961962 + outer loop + vertex 754.802 169.036 35.4358 + vertex 761.665 173.317 35.4128 + vertex 753.473 169.118 35.6584 + endloop + endfacet + facet normal 0.150891 -0.236762 0.959779 + outer loop + vertex 763.084 173.41 35.2128 + vertex 761.665 173.317 35.4128 + vertex 754.802 169.036 35.4358 + endloop + endfacet + facet normal 0.15122 -0.247894 0.956912 + outer loop + vertex 763.084 173.41 35.2128 + vertex 769.972 177.897 35.2866 + vertex 761.665 173.317 35.4128 + endloop + endfacet + facet normal 0.111487 -0.175243 0.978192 + outer loop + vertex 761.665 173.317 35.4128 + vertex 769.972 177.897 35.2866 + vertex 766.104 176.707 35.5143 + endloop + endfacet + facet normal 0.113964 -0.178461 0.977325 + outer loop + vertex 766.104 176.707 35.5143 + vertex 759.273 173.173 35.6655 + vertex 761.665 173.317 35.4128 + endloop + endfacet + facet normal 0.0881125 -0.128042 0.987847 + outer loop + vertex 759.273 173.173 35.6655 + vertex 766.104 176.707 35.5143 + vertex 761.939 177.605 36.0021 + endloop + endfacet + facet normal 0.0984966 -0.134154 0.986053 + outer loop + vertex 761.939 177.605 36.0021 + vertex 755.003 173.814 36.1793 + vertex 759.273 173.173 35.6655 + endloop + endfacet + facet normal 0.0983458 -0.13507 0.985943 + outer loop + vertex 753.699 170.293 35.827 + vertex 759.273 173.173 35.6655 + vertex 755.003 173.814 36.1793 + endloop + endfacet + facet normal 0.114234 -0.140705 0.983439 + outer loop + vertex 755.003 173.814 36.1793 + vertex 748.367 169.253 36.2974 + vertex 753.699 170.293 35.827 + endloop + endfacet + facet normal 0.117239 -0.157405 0.98055 + outer loop + vertex 749.463 167.589 35.8993 + vertex 753.699 170.293 35.827 + vertex 748.367 169.253 36.2974 + endloop + endfacet + facet normal 0.127191 -0.150801 0.980348 + outer loop + vertex 743.883 164.981 36.222 + vertex 749.463 167.589 35.8993 + vertex 748.367 169.253 36.2974 + endloop + endfacet + facet normal 0.121272 -0.163762 0.979017 + outer loop + vertex 753.699 170.293 35.827 + vertex 749.463 167.589 35.8993 + vertex 753.473 169.118 35.6584 + endloop + endfacet + facet normal 0.112205 -0.162212 0.980356 + outer loop + vertex 759.273 173.173 35.6655 + vertex 753.699 170.293 35.827 + vertex 753.473 169.118 35.6584 + endloop + endfacet + facet normal 0.113363 -0.163868 0.979947 + outer loop + vertex 753.473 169.118 35.6584 + vertex 761.665 173.317 35.4128 + vertex 759.273 173.173 35.6655 + endloop + endfacet + facet normal 0.0874297 -0.131032 0.987515 + outer loop + vertex 769.382 181.144 35.8128 + vertex 761.939 177.605 36.0021 + vertex 766.104 176.707 35.5143 + endloop + endfacet + facet normal 0.083006 -0.127818 0.988318 + outer loop + vertex 766.104 176.707 35.5143 + vertex 770.688 178.974 35.4224 + vertex 769.382 181.144 35.8128 + endloop + endfacet + facet normal 0.0819045 -0.128482 0.988324 + outer loop + vertex 770.688 178.974 35.4224 + vertex 774.602 181.558 35.4341 + vertex 769.382 181.144 35.8128 + endloop + endfacet + facet normal 0.0818637 -0.127896 0.988403 + outer loop + vertex 775.803 185.389 35.8303 + vertex 769.382 181.144 35.8128 + vertex 774.602 181.558 35.4341 + endloop + endfacet + facet normal 0.0795853 -0.12721 0.988678 + outer loop + vertex 774.602 181.558 35.4341 + vertex 779.7 184.993 35.4656 + vertex 775.803 185.389 35.8303 + endloop + endfacet + facet normal 0.080285 -0.120997 0.989401 + outer loop + vertex 781.826 189.242 35.8128 + vertex 775.803 185.389 35.8303 + vertex 779.7 184.993 35.4656 + endloop + endfacet + facet normal 0.0885278 -0.125023 0.988196 + outer loop + vertex 779.7 184.993 35.4656 + vertex 784.694 187.977 35.3958 + vertex 781.826 189.242 35.8128 + endloop + endfacet + facet normal 0.0869488 -0.128502 0.98789 + outer loop + vertex 788.679 193.331 35.7414 + vertex 781.826 189.242 35.8128 + vertex 784.694 187.977 35.3958 + endloop + endfacet + facet normal 0.0929972 -0.132931 0.986753 + outer loop + vertex 784.694 187.977 35.3958 + vertex 789.859 191.171 35.3393 + vertex 788.679 193.331 35.7414 + endloop + endfacet + facet normal 0.0864321 -0.136535 0.986857 + outer loop + vertex 789.859 191.171 35.3393 + vertex 793.676 194.405 35.4524 + vertex 788.679 193.331 35.7414 + endloop + endfacet + facet normal 0.0851876 -0.130497 0.987782 + outer loop + vertex 795.04 198.318 35.8516 + vertex 788.679 193.331 35.7414 + vertex 793.676 194.405 35.4524 + endloop + endfacet + facet normal 0.0842917 -0.130197 0.987899 + outer loop + vertex 793.676 194.405 35.4524 + vertex 798.38 197.795 35.4978 + vertex 795.04 198.318 35.8516 + endloop + endfacet + facet normal 0.0826276 -0.140025 0.986694 + outer loop + vertex 801.537 202.867 35.9532 + vertex 795.04 198.318 35.8516 + vertex 798.38 197.795 35.4978 + endloop + endfacet + facet normal 0.0854486 -0.141738 0.986209 + outer loop + vertex 798.38 197.795 35.4978 + vertex 802.267 200.611 35.5657 + vertex 801.537 202.867 35.9532 + endloop + endfacet + facet normal 0.0743195 -0.145401 0.986578 + outer loop + vertex 802.267 200.611 35.5657 + vertex 805.859 203.696 35.7497 + vertex 801.537 202.867 35.9532 + endloop + endfacet + facet normal 0.0760953 -0.155062 0.98497 + outer loop + vertex 808.166 208.565 36.338 + vertex 801.537 202.867 35.9532 + vertex 805.859 203.696 35.7497 + endloop + endfacet + facet normal 0.121027 -0.190558 0.974187 + outer loop + vertex 802.267 200.611 35.5657 + vertex 798.38 197.795 35.4978 + vertex 801.037 198.92 35.3877 + endloop + endfacet + facet normal 0.12853 -0.191388 0.973063 + outer loop + vertex 798.38 197.795 35.4978 + vertex 793.676 194.405 35.4524 + vertex 793.434 193.164 35.2403 + endloop + endfacet + facet normal 0.13413 -0.192321 0.972122 + outer loop + vertex 793.676 194.405 35.4524 + vertex 789.859 191.171 35.3393 + vertex 793.434 193.164 35.2403 + endloop + endfacet + facet normal 0.151174 -0.223351 0.962944 + outer loop + vertex 785.966 187.878 35.1864 + vertex 793.434 193.164 35.2403 + vertex 789.859 191.171 35.3393 + endloop + endfacet + facet normal 0.198944 -0.290553 0.935949 + outer loop + vertex 787.005 188.045 35.0177 + vertex 793.434 193.164 35.2403 + vertex 785.966 187.878 35.1864 + endloop + endfacet + facet normal 0.142347 -0.213089 0.966608 + outer loop + vertex 789.859 191.171 35.3393 + vertex 784.694 187.977 35.3958 + vertex 785.966 187.878 35.1864 + endloop + endfacet + facet normal 0.142395 -0.212656 0.966696 + outer loop + vertex 778.464 183.081 35.2363 + vertex 785.966 187.878 35.1864 + vertex 784.694 187.977 35.3958 + endloop + endfacet + facet normal 0.193673 -0.293175 0.936237 + outer loop + vertex 779.333 183.006 35.0331 + vertex 785.966 187.878 35.1864 + vertex 778.464 183.081 35.2363 + endloop + endfacet + facet normal 0.0669178 -0.0948303 0.993242 + outer loop + vertex 788.679 193.331 35.7414 + vertex 782.736 196.02 36.3986 + vertex 781.826 189.242 35.8128 + endloop + endfacet + facet normal 0.0634583 -0.094389 0.993511 + outer loop + vertex 782.736 196.02 36.3986 + vertex 776.227 191.941 36.4268 + vertex 781.826 189.242 35.8128 + endloop + endfacet + facet normal 0.0648269 -0.0993773 0.992936 + outer loop + vertex 789.233 200.427 36.4154 + vertex 782.736 196.02 36.3986 + vertex 788.679 193.331 35.7414 + endloop + endfacet + facet normal 0.060451 -0.0990651 0.993243 + outer loop + vertex 795.04 198.318 35.8516 + vertex 789.233 200.427 36.4154 + vertex 788.679 193.331 35.7414 + endloop + endfacet + facet normal 0.0595164 -0.101585 0.993045 + outer loop + vertex 795.592 205.073 36.5096 + vertex 789.233 200.427 36.4154 + vertex 795.04 198.318 35.8516 + endloop + endfacet + facet normal 0.0553892 -0.101274 0.993315 + outer loop + vertex 801.537 202.867 35.9532 + vertex 795.592 205.073 36.5096 + vertex 795.04 198.318 35.8516 + endloop + endfacet + facet normal 0.0517983 -0.110746 0.992498 + outer loop + vertex 801.81 209.955 36.7299 + vertex 795.592 205.073 36.5096 + vertex 801.537 202.867 35.9532 + endloop + endfacet + facet normal 0.0371098 -0.11026 0.99321 + outer loop + vertex 808.166 208.565 36.338 + vertex 801.81 209.955 36.7299 + vertex 801.537 202.867 35.9532 + endloop + endfacet + facet normal 0.0347979 -0.120515 0.992101 + outer loop + vertex 807.439 214.847 37.1267 + vertex 801.81 209.955 36.7299 + vertex 808.166 208.565 36.338 + endloop + endfacet + facet normal 0.0131566 -0.123047 0.992314 + outer loop + vertex 807.439 214.847 37.1267 + vertex 808.166 208.565 36.338 + vertex 812.795 213.383 36.8742 + endloop + endfacet + facet normal 0.0102472 -0.133468 0.991 + outer loop + vertex 812.391 219.068 37.644 + vertex 807.439 214.847 37.1267 + vertex 812.795 213.383 36.8742 + endloop + endfacet + facet normal -0.00588652 -0.134598 0.990883 + outer loop + vertex 816.679 216.882 37.3724 + vertex 812.391 219.068 37.644 + vertex 812.795 213.383 36.8742 + endloop + endfacet + facet normal -0.0190163 -0.15986 0.986957 + outer loop + vertex 816.816 221.556 38.1323 + vertex 812.391 219.068 37.644 + vertex 816.679 216.882 37.3724 + endloop + endfacet + facet normal -0.0153929 -0.159973 0.987001 + outer loop + vertex 819.959 219.532 37.8531 + vertex 816.816 221.556 38.1323 + vertex 816.679 216.882 37.3724 + endloop + endfacet + facet normal -0.0389102 -0.195503 0.979931 + outer loop + vertex 820.073 222.521 38.454 + vertex 816.816 221.556 38.1323 + vertex 819.959 219.532 37.8531 + endloop + endfacet + facet normal -0.00580169 -0.196861 0.980414 + outer loop + vertex 822.646 221.92 38.3485 + vertex 820.073 222.521 38.454 + vertex 819.959 219.532 37.8531 + endloop + endfacet + facet normal -0.006773 -0.200875 0.979593 + outer loop + vertex 822.096 225.323 39.0425 + vertex 820.073 222.521 38.454 + vertex 822.646 221.92 38.3485 + endloop + endfacet + facet normal -0.0204103 -0.202952 0.978976 + outer loop + vertex 825.261 224.576 38.9537 + vertex 822.096 225.323 39.0425 + vertex 822.646 221.92 38.3485 + endloop + endfacet + facet normal -0.0245263 -0.219953 0.975202 + outer loop + vertex 824.698 228.239 39.7657 + vertex 822.096 225.323 39.0425 + vertex 825.261 224.576 38.9537 + endloop + endfacet + facet normal -0.0395 -0.222043 0.974236 + outer loop + vertex 827.949 227.291 39.6815 + vertex 824.698 228.239 39.7657 + vertex 825.261 224.576 38.9537 + endloop + endfacet + facet normal -0.046359 -0.245046 0.968402 + outer loop + vertex 827.275 230.86 40.5524 + vertex 824.698 228.239 39.7657 + vertex 827.949 227.291 39.6815 + endloop + endfacet + facet normal -0.0628118 -0.247757 0.966784 + outer loop + vertex 830.425 229.84 40.4956 + vertex 827.275 230.86 40.5524 + vertex 827.949 227.291 39.6815 + endloop + endfacet + facet normal -0.0723744 -0.276812 0.958195 + outer loop + vertex 829.671 233.264 41.4278 + vertex 827.275 230.86 40.5524 + vertex 830.425 229.84 40.4956 + endloop + endfacet + facet normal -0.0849296 -0.279114 0.956495 + outer loop + vertex 832.798 232.382 41.4481 + vertex 829.671 233.264 41.4278 + vertex 830.425 229.84 40.4956 + endloop + endfacet + facet normal -0.0943446 -0.312758 0.945136 + outer loop + vertex 831.955 235.767 42.484 + vertex 829.671 233.264 41.4278 + vertex 832.798 232.382 41.4481 + endloop + endfacet + facet normal -0.105973 -0.315044 0.943142 + outer loop + vertex 835.364 235.181 42.6713 + vertex 831.955 235.767 42.484 + vertex 832.798 232.382 41.4481 + endloop + endfacet + facet normal -0.112702 -0.359581 0.926283 + outer loop + vertex 834.131 238.415 43.7769 + vertex 831.955 235.767 42.484 + vertex 835.364 235.181 42.6713 + endloop + endfacet + facet normal -0.132306 -0.365389 0.921404 + outer loop + vertex 837.785 238.04 44.1527 + vertex 834.131 238.415 43.7769 + vertex 835.364 235.181 42.6713 + endloop + endfacet + facet normal 0.135277 -0.203695 0.969644 + outer loop + vertex 784.694 187.977 35.3958 + vertex 779.7 184.993 35.4656 + vertex 778.464 183.081 35.2363 + endloop + endfacet + facet normal 0.0633784 -0.0945523 0.9935 + outer loop + vertex 781.826 189.242 35.8128 + vertex 776.227 191.941 36.4268 + vertex 775.803 185.389 35.8303 + endloop + endfacet + facet normal 0.0630995 -0.094536 0.99352 + outer loop + vertex 776.227 191.941 36.4268 + vertex 769.698 188.056 36.4718 + vertex 775.803 185.389 35.8303 + endloop + endfacet + facet normal 0.0617718 -0.0975264 0.993314 + outer loop + vertex 775.803 185.389 35.8303 + vertex 769.698 188.056 36.4718 + vertex 769.382 181.144 35.8128 + endloop + endfacet + facet normal 0.0706867 -0.0978741 0.992685 + outer loop + vertex 769.698 188.056 36.4718 + vertex 762.827 184.312 36.5919 + vertex 769.382 181.144 35.8128 + endloop + endfacet + facet normal 0.071249 -0.0967285 0.992757 + outer loop + vertex 769.382 181.144 35.8128 + vertex 762.827 184.312 36.5919 + vertex 761.939 177.605 36.0021 + endloop + endfacet + facet normal 0.0814432 -0.0979984 0.991848 + outer loop + vertex 762.827 184.312 36.5919 + vertex 755.608 180.55 36.813 + vertex 761.939 177.605 36.0021 + endloop + endfacet + facet normal 0.0802553 -0.100509 0.991694 + outer loop + vertex 761.939 177.605 36.0021 + vertex 755.608 180.55 36.813 + vertex 755.003 173.814 36.1793 + endloop + endfacet + facet normal 0.100967 -0.102176 0.989629 + outer loop + vertex 755.608 180.55 36.813 + vertex 748.044 175.767 37.0909 + vertex 755.003 173.814 36.1793 + endloop + endfacet + facet normal 0.0970604 -0.115589 0.988544 + outer loop + vertex 755.003 173.814 36.1793 + vertex 748.044 175.767 37.0909 + vertex 748.367 169.253 36.2974 + endloop + endfacet + facet normal 0.128985 -0.113588 0.98512 + outer loop + vertex 748.367 169.253 36.2974 + vertex 748.044 175.767 37.0909 + vertex 743.445 170.026 37.0312 + endloop + endfacet + facet normal 0.125019 -0.136549 0.982713 + outer loop + vertex 742.144 165.737 36.6006 + vertex 748.367 169.253 36.2974 + vertex 743.445 170.026 37.0312 + endloop + endfacet + facet normal 0.144467 -0.142099 0.979253 + outer loop + vertex 743.445 170.026 37.0312 + vertex 739.007 167.037 37.252 + vertex 742.144 165.737 36.6006 + endloop + endfacet + facet normal 0.141489 -0.14899 0.978664 + outer loop + vertex 742.144 165.737 36.6006 + vertex 739.007 167.037 37.252 + vertex 738.083 163.891 36.9068 + endloop + endfacet + facet normal 0.152008 -0.17306 0.97311 + outer loop + vertex 742.144 165.737 36.6006 + vertex 738.083 163.891 36.9068 + vertex 738.487 162.574 36.6095 + endloop + endfacet + facet normal 0.14223 -0.161743 0.976529 + outer loop + vertex 738.487 162.574 36.6095 + vertex 743.883 164.981 36.222 + vertex 742.144 165.737 36.6006 + endloop + endfacet + facet normal 0.127951 -0.128615 0.983406 + outer loop + vertex 743.883 164.981 36.222 + vertex 738.487 162.574 36.6095 + vertex 736.783 160.962 36.6202 + endloop + endfacet + facet normal 0.159335 -0.170647 0.972364 + outer loop + vertex 738.083 163.891 36.9068 + vertex 734.747 162.013 37.1239 + vertex 738.487 162.574 36.6095 + endloop + endfacet + facet normal 0.158989 -0.167844 0.972908 + outer loop + vertex 733.068 159.859 37.0265 + vertex 738.487 162.574 36.6095 + vertex 734.747 162.013 37.1239 + endloop + endfacet + facet normal 0.154752 -0.162254 0.974539 + outer loop + vertex 738.083 163.891 36.9068 + vertex 735.21 165.023 37.5515 + vertex 734.747 162.013 37.1239 + endloop + endfacet + facet normal 0.178162 -0.165214 0.970032 + outer loop + vertex 735.21 165.023 37.5515 + vertex 731.579 163.374 37.9374 + vertex 734.747 162.013 37.1239 + endloop + endfacet + facet normal 0.173675 -0.175113 0.969109 + outer loop + vertex 734.747 162.013 37.1239 + vertex 731.579 163.374 37.9374 + vertex 730.759 160.252 37.5202 + endloop + endfacet + facet normal 0.176096 -0.180933 0.967602 + outer loop + vertex 734.747 162.013 37.1239 + vertex 730.759 160.252 37.5202 + vertex 733.068 159.859 37.0265 + endloop + endfacet + facet normal 0.177778 -0.172573 0.968821 + outer loop + vertex 728.044 157.891 37.598 + vertex 733.068 159.859 37.0265 + vertex 730.759 160.252 37.5202 + endloop + endfacet + facet normal 0.198547 -0.196748 0.96014 + outer loop + vertex 730.759 160.252 37.5202 + vertex 727.48 159.129 37.9681 + vertex 728.044 157.891 37.598 + endloop + endfacet + facet normal 0.211723 -0.190296 0.958625 + outer loop + vertex 727.48 159.129 37.9681 + vertex 724.453 157.546 38.3225 + vertex 728.044 157.891 37.598 + endloop + endfacet + facet normal 0.21161 -0.18821 0.959061 + outer loop + vertex 722.875 155.393 38.2481 + vertex 728.044 157.891 37.598 + vertex 724.453 157.546 38.3225 + endloop + endfacet + facet normal 0.219246 -0.205785 0.953721 + outer loop + vertex 727.48 159.129 37.9681 + vertex 724.754 160.279 38.8429 + vertex 724.453 157.546 38.3225 + endloop + endfacet + facet normal 0.241784 -0.207172 0.947956 + outer loop + vertex 724.754 160.279 38.8429 + vertex 721.356 158.866 39.4009 + vertex 724.453 157.546 38.3225 + endloop + endfacet + facet normal 0.238698 -0.213838 0.947257 + outer loop + vertex 724.453 157.546 38.3225 + vertex 721.356 158.866 39.4009 + vertex 720.307 155.833 38.9804 + endloop + endfacet + facet normal 0.235676 -0.205528 0.94985 + outer loop + vertex 724.453 157.546 38.3225 + vertex 720.307 155.833 38.9804 + vertex 722.875 155.393 38.2481 + endloop + endfacet + facet normal 0.238151 -0.194051 0.951645 + outer loop + vertex 716.64 152.892 39.2984 + vertex 722.875 155.393 38.2481 + vertex 720.307 155.833 38.9804 + endloop + endfacet + facet normal 0.265469 -0.22977 0.936339 + outer loop + vertex 720.307 155.833 38.9804 + vertex 716.816 154.741 39.7023 + vertex 716.64 152.892 39.2984 + endloop + endfacet + facet normal 0.286302 -0.230373 0.930032 + outer loop + vertex 716.816 154.741 39.7023 + vertex 713.632 152.998 40.2506 + vertex 716.64 152.892 39.2984 + endloop + endfacet + facet normal 0.295201 -0.249022 0.922412 + outer loop + vertex 716.816 154.741 39.7023 + vertex 714.385 156.174 40.867 + vertex 713.632 152.998 40.2506 + endloop + endfacet + facet normal 0.301586 -0.23872 0.92307 + outer loop + vertex 717.848 157.565 40.0954 + vertex 714.385 156.174 40.867 + vertex 716.816 154.741 39.7023 + endloop + endfacet + facet normal 0.295151 -0.218835 0.930052 + outer loop + vertex 717.848 157.565 40.0954 + vertex 714.97 160.553 41.712 + vertex 714.385 156.174 40.867 + endloop + endfacet + facet normal 0.307807 -0.206008 0.928879 + outer loop + vertex 718.255 161.721 40.8823 + vertex 714.97 160.553 41.712 + vertex 717.848 157.565 40.0954 + endloop + endfacet + facet normal 0.262484 -0.204257 0.94307 + outer loop + vertex 721.356 158.866 39.4009 + vertex 718.255 161.721 40.8823 + vertex 717.848 157.565 40.0954 + endloop + endfacet + facet normal 0.273408 -0.192108 0.942519 + outer loop + vertex 721.524 162.919 40.1783 + vertex 718.255 161.721 40.8823 + vertex 721.356 158.866 39.4009 + endloop + endfacet + facet normal 0.264552 -0.163262 0.950452 + outer loop + vertex 721.524 162.919 40.1783 + vertex 718.4 166.989 41.747 + vertex 718.255 161.721 40.8823 + endloop + endfacet + facet normal 0.284142 -0.147063 0.947436 + outer loop + vertex 721.603 168.351 40.9978 + vertex 718.4 166.989 41.747 + vertex 721.524 162.919 40.1783 + endloop + endfacet + facet normal 0.238252 -0.148261 0.95982 + outer loop + vertex 724.832 164.404 39.5866 + vertex 721.603 168.351 40.9978 + vertex 721.524 162.919 40.1783 + endloop + endfacet + facet normal 0.249497 -0.176339 0.952185 + outer loop + vertex 724.832 164.404 39.5866 + vertex 721.524 162.919 40.1783 + vertex 724.754 160.279 38.8429 + endloop + endfacet + facet normal 0.214794 -0.17718 0.960454 + outer loop + vertex 728.051 161.75 38.3769 + vertex 724.832 164.404 39.5866 + vertex 724.754 160.279 38.8429 + endloop + endfacet + facet normal 0.229797 -0.15886 0.960186 + outer loop + vertex 728.287 166.2 39.0567 + vertex 724.832 164.404 39.5866 + vertex 728.051 161.75 38.3769 + endloop + endfacet + facet normal 0.193456 -0.158166 0.968276 + outer loop + vertex 731.579 163.374 37.9374 + vertex 728.287 166.2 39.0567 + vertex 728.051 161.75 38.3769 + endloop + endfacet + facet normal 0.209457 -0.139361 0.967836 + outer loop + vertex 732 168.372 38.566 + vertex 728.287 166.2 39.0567 + vertex 731.579 163.374 37.9374 + endloop + endfacet + facet normal 0.196248 -0.11545 0.973734 + outer loop + vertex 728.287 166.2 39.0567 + vertex 732 168.372 38.566 + vertex 728.584 172.501 39.7441 + endloop + endfacet + facet normal 0.233554 -0.116292 0.965365 + outer loop + vertex 728.584 172.501 39.7441 + vertex 724.989 170.188 40.3351 + vertex 728.287 166.2 39.0567 + endloop + endfacet + facet normal 0.216032 -0.0872454 0.972481 + outer loop + vertex 728.584 172.501 39.7441 + vertex 725.385 177.399 40.8942 + vertex 724.989 170.188 40.3351 + endloop + endfacet + facet normal 0.262832 -0.0888998 0.960737 + outer loop + vertex 725.385 177.399 40.8942 + vertex 721.897 175.131 41.6384 + vertex 724.989 170.188 40.3351 + endloop + endfacet + facet normal 0.243917 -0.101713 0.964448 + outer loop + vertex 724.989 170.188 40.3351 + vertex 721.897 175.131 41.6384 + vertex 721.603 168.351 40.9978 + endloop + endfacet + facet normal 0.292211 -0.102521 0.950843 + outer loop + vertex 721.897 175.131 41.6384 + vertex 718.637 173.436 42.4575 + vertex 721.603 168.351 40.9978 + endloop + endfacet + facet normal 0.279385 -0.0747563 0.957265 + outer loop + vertex 721.897 175.131 41.6384 + vertex 719.043 180.92 42.9234 + vertex 718.637 173.436 42.4575 + endloop + endfacet + facet normal 0.293052 -0.0672347 0.953729 + outer loop + vertex 722.387 183.089 42.0488 + vertex 719.043 180.92 42.9234 + vertex 721.897 175.131 41.6384 + endloop + endfacet + facet normal 0.281872 -0.048179 0.958241 + outer loop + vertex 722.387 183.089 42.0488 + vertex 719.314 189.538 43.2769 + vertex 719.043 180.92 42.9234 + endloop + endfacet + facet normal 0.293392 -0.0420849 0.955065 + outer loop + vertex 722.303 189.771 42.3691 + vertex 719.314 189.538 43.2769 + vertex 722.387 183.089 42.0488 + endloop + endfacet + facet normal 0.292473 -0.0271122 0.955889 + outer loop + vertex 722.303 189.771 42.3691 + vertex 720.862 199.623 43.0893 + vertex 719.314 189.538 43.2769 + endloop + endfacet + facet normal 0.342757 -0.0351481 0.938766 + outer loop + vertex 720.862 199.623 43.0893 + vertex 714.933 198.058 45.1958 + vertex 719.314 189.538 43.2769 + endloop + endfacet + facet normal 0.329276 -0.0430913 0.94325 + outer loop + vertex 716.484 186.821 44.141 + vertex 719.314 189.538 43.2769 + vertex 714.933 198.058 45.1958 + endloop + endfacet + facet normal 0.379208 -0.0344555 0.92467 + outer loop + vertex 716.484 186.821 44.141 + vertex 714.933 198.058 45.1958 + vertex 713.448 187.297 45.4038 + endloop + endfacet + facet normal 0.375829 -0.0567555 0.924949 + outer loop + vertex 716.484 186.821 44.141 + vertex 713.448 187.297 45.4038 + vertex 715.964 179.556 43.9063 + endloop + endfacet + facet normal 0.372767 -0.0579757 0.926112 + outer loop + vertex 715.964 179.556 43.9063 + vertex 713.448 187.297 45.4038 + vertex 713.084 178.669 45.0101 + endloop + endfacet + facet normal 0.379443 -0.0857225 0.921235 + outer loop + vertex 715.964 179.556 43.9063 + vertex 713.084 178.669 45.0101 + vertex 715.589 172.305 43.3859 + endloop + endfacet + facet normal 0.366105 -0.0921886 0.925996 + outer loop + vertex 715.589 172.305 43.3859 + vertex 713.084 178.669 45.0101 + vertex 712.672 171.462 44.4554 + endloop + endfacet + facet normal 0.373636 -0.12738 0.918787 + outer loop + vertex 715.589 172.305 43.3859 + vertex 712.672 171.462 44.4554 + vertex 715.302 165.959 42.6229 + endloop + endfacet + facet normal 0.351824 -0.140052 0.92553 + outer loop + vertex 715.302 165.959 42.6229 + vertex 712.672 171.462 44.4554 + vertex 712.221 165.017 43.6514 + endloop + endfacet + facet normal 0.359849 -0.176504 0.916163 + outer loop + vertex 715.302 165.959 42.6229 + vertex 712.221 165.017 43.6514 + vertex 714.97 160.553 41.712 + endloop + endfacet + facet normal 0.337361 -0.192649 0.921452 + outer loop + vertex 714.97 160.553 41.712 + vertex 712.221 165.017 43.6514 + vertex 711.587 159.241 42.6762 + endloop + endfacet + facet normal 0.345957 -0.222054 0.911595 + outer loop + vertex 714.97 160.553 41.712 + vertex 711.587 159.241 42.6762 + vertex 714.385 156.174 40.867 + endloop + endfacet + facet normal 0.326625 -0.24105 0.913899 + outer loop + vertex 714.385 156.174 40.867 + vertex 711.587 159.241 42.6762 + vertex 710.654 154.285 41.7024 + endloop + endfacet + facet normal 0.332389 -0.255046 0.908003 + outer loop + vertex 714.385 156.174 40.867 + vertex 710.654 154.285 41.7024 + vertex 713.632 152.998 40.2506 + endloop + endfacet + facet normal 0.31797 -0.28439 0.904443 + outer loop + vertex 713.632 152.998 40.2506 + vertex 710.654 154.285 41.7024 + vertex 710.048 151.037 40.8944 + endloop + endfacet + facet normal 0.42383 -0.0409969 0.904813 + outer loop + vertex 714.933 198.058 45.1958 + vertex 709.819 196.784 47.5335 + vertex 713.448 187.297 45.4038 + endloop + endfacet + facet normal 0.419691 -0.0429921 0.906648 + outer loop + vertex 710.922 185.181 46.4724 + vertex 713.448 187.297 45.4038 + vertex 709.819 196.784 47.5335 + endloop + endfacet + facet normal 0.430728 -0.0592531 0.900535 + outer loop + vertex 713.448 187.297 45.4038 + vertex 710.922 185.181 46.4724 + vertex 713.084 178.669 45.0101 + endloop + endfacet + facet normal 0.423912 -0.0621961 0.903565 + outer loop + vertex 713.084 178.669 45.0101 + vertex 710.922 185.181 46.4724 + vertex 710.383 178.018 46.2325 + endloop + endfacet + facet normal 0.429146 -0.0936643 0.898366 + outer loop + vertex 713.084 178.669 45.0101 + vertex 710.383 178.018 46.2325 + vertex 712.672 171.462 44.4554 + endloop + endfacet + facet normal 0.41479 -0.100304 0.904372 + outer loop + vertex 712.672 171.462 44.4554 + vertex 710.383 178.018 46.2325 + vertex 709.85 170.703 45.6654 + endloop + endfacet + facet normal 0.421995 -0.141216 0.895533 + outer loop + vertex 712.672 171.462 44.4554 + vertex 709.85 170.703 45.6654 + vertex 712.221 165.017 43.6514 + endloop + endfacet + facet normal 0.395445 -0.155707 0.905195 + outer loop + vertex 712.221 165.017 43.6514 + vertex 709.85 170.703 45.6654 + vertex 709.155 163.973 44.8115 + endloop + endfacet + facet normal 0.404478 -0.195296 0.893453 + outer loop + vertex 712.221 165.017 43.6514 + vertex 709.155 163.973 44.8115 + vertex 711.587 159.241 42.6762 + endloop + endfacet + facet normal 0.373939 -0.21494 0.902203 + outer loop + vertex 711.587 159.241 42.6762 + vertex 709.155 163.973 44.8115 + vertex 708.136 157.431 43.6751 + endloop + endfacet + facet normal 0.386929 -0.247371 0.888309 + outer loop + vertex 711.587 159.241 42.6762 + vertex 708.136 157.431 43.6751 + vertex 710.654 154.285 41.7024 + endloop + endfacet + facet normal 0.362204 -0.269631 0.892249 + outer loop + vertex 710.654 154.285 41.7024 + vertex 708.136 157.431 43.6751 + vertex 708.322 153.872 42.5243 + endloop + endfacet + facet normal 0.381486 -0.266339 0.885173 + outer loop + vertex 708.322 153.872 42.5243 + vertex 708.136 157.431 43.6751 + vertex 706.599 153.348 43.1093 + endloop + endfacet + facet normal 0.386385 -0.295127 0.873846 + outer loop + vertex 708.322 153.872 42.5243 + vertex 706.599 153.348 43.1093 + vertex 708.122 151.741 41.8927 + endloop + endfacet + facet normal 0.363692 -0.29581 0.883304 + outer loop + vertex 708.322 153.872 42.5243 + vertex 708.122 151.741 41.8927 + vertex 710.654 154.285 41.7024 + endloop + endfacet + facet normal 0.355952 -0.287672 0.889125 + outer loop + vertex 710.048 151.037 40.8944 + vertex 710.654 154.285 41.7024 + vertex 708.122 151.741 41.8927 + endloop + endfacet + facet normal 0.371014 -0.31066 0.875122 + outer loop + vertex 708.122 151.741 41.8927 + vertex 706.599 153.348 43.1093 + vertex 705.912 150.504 42.3909 + endloop + endfacet + facet normal 0.377989 -0.326701 0.866251 + outer loop + vertex 708.122 151.741 41.8927 + vertex 705.912 150.504 42.3909 + vertex 707.177 149.458 41.4442 + endloop + endfacet + facet normal 0.343249 -0.315902 0.884526 + outer loop + vertex 707.177 149.458 41.4442 + vertex 710.048 151.037 40.8944 + vertex 708.122 151.741 41.8927 + endloop + endfacet + facet normal 0.341861 -0.312812 0.88616 + outer loop + vertex 710.048 151.037 40.8944 + vertex 707.177 149.458 41.4442 + vertex 707.841 148.762 40.9425 + endloop + endfacet + facet normal 0.335813 -0.318727 0.886365 + outer loop + vertex 707.177 149.458 41.4442 + vertex 705.585 147.92 41.4945 + vertex 707.841 148.762 40.9425 + endloop + endfacet + facet normal 0.321019 -0.263858 0.909574 + outer loop + vertex 704.065 146.919 41.7404 + vertex 707.841 148.762 40.9425 + vertex 705.585 147.92 41.4945 + endloop + endfacet + facet normal 0.373068 -0.358299 0.855828 + outer loop + vertex 707.177 149.458 41.4442 + vertex 704.922 148.481 42.0182 + vertex 705.585 147.92 41.4945 + endloop + endfacet + facet normal 0.376452 -0.354425 0.85596 + outer loop + vertex 703.146 146.972 42.1742 + vertex 705.585 147.92 41.4945 + vertex 704.922 148.481 42.0182 + endloop + endfacet + facet normal 0.367402 -0.339256 0.86598 + outer loop + vertex 707.177 149.458 41.4442 + vertex 705.912 150.504 42.3909 + vertex 704.922 148.481 42.0182 + endloop + endfacet + facet normal 0.40029 -0.3517 0.846212 + outer loop + vertex 705.912 150.504 42.3909 + vertex 704.025 149.753 42.9715 + vertex 704.922 148.481 42.0182 + endloop + endfacet + facet normal 0.393715 -0.35699 0.847081 + outer loop + vertex 704.922 148.481 42.0182 + vertex 704.025 149.753 42.9715 + vertex 703.254 148.016 42.5975 + endloop + endfacet + facet normal 0.396192 -0.379718 0.83597 + outer loop + vertex 703.254 148.016 42.5975 + vertex 703.146 146.972 42.1742 + vertex 704.922 148.481 42.0182 + endloop + endfacet + facet normal 0.4126 -0.378416 0.828591 + outer loop + vertex 703.254 148.016 42.5975 + vertex 701.665 147.251 43.0394 + vertex 703.146 146.972 42.1742 + endloop + endfacet + facet normal 0.409482 -0.387178 0.826086 + outer loop + vertex 700.223 145.816 43.0818 + vertex 703.146 146.972 42.1742 + vertex 701.665 147.251 43.0394 + endloop + endfacet + facet normal 0.410634 -0.372124 0.832408 + outer loop + vertex 703.254 148.016 42.5975 + vertex 702.383 149.162 43.5393 + vertex 701.665 147.251 43.0394 + endloop + endfacet + facet normal 0.43945 -0.378322 0.814712 + outer loop + vertex 702.383 149.162 43.5393 + vertex 700.874 148.629 44.1059 + vertex 701.665 147.251 43.0394 + endloop + endfacet + facet normal 0.430746 -0.38463 0.816405 + outer loop + vertex 701.665 147.251 43.0394 + vertex 700.874 148.629 44.1059 + vertex 700.108 146.832 43.6638 + endloop + endfacet + facet normal 0.432299 -0.4108 0.802721 + outer loop + vertex 700.108 146.832 43.6638 + vertex 700.223 145.816 43.0818 + vertex 701.665 147.251 43.0394 + endloop + endfacet + facet normal 0.446938 -0.405957 0.797148 + outer loop + vertex 700.108 146.832 43.6638 + vertex 698.654 146.112 44.1121 + vertex 700.223 145.816 43.0818 + endloop + endfacet + facet normal 0.441422 -0.420188 0.792836 + outer loop + vertex 697.405 144.737 44.079 + vertex 700.223 145.816 43.0818 + vertex 698.654 146.112 44.1121 + endloop + endfacet + facet normal 0.448163 -0.464848 0.763588 + outer loop + vertex 700.223 145.816 43.0818 + vertex 697.405 144.737 44.079 + vertex 699.023 144.93 43.2466 + endloop + endfacet + facet normal 0.421537 -0.421471 0.802913 + outer loop + vertex 699.023 144.93 43.2466 + vertex 701.58 145.927 42.4275 + vertex 700.223 145.816 43.0818 + endloop + endfacet + facet normal 0.419496 -0.435963 0.796216 + outer loop + vertex 703.146 146.972 42.1742 + vertex 700.223 145.816 43.0818 + vertex 701.58 145.927 42.4275 + endloop + endfacet + facet normal 0.44923 -0.457571 0.767347 + outer loop + vertex 696.23 143.898 44.2665 + vertex 699.023 144.93 43.2466 + vertex 697.405 144.737 44.079 + endloop + endfacet + facet normal 0.44497 -0.399183 0.801657 + outer loop + vertex 700.108 146.832 43.6638 + vertex 699.444 148.105 44.6659 + vertex 698.654 146.112 44.1121 + endloop + endfacet + facet normal 0.472141 -0.404796 0.783086 + outer loop + vertex 699.444 148.105 44.6659 + vertex 698.158 147.66 45.2118 + vertex 698.654 146.112 44.1121 + endloop + endfacet + facet normal 0.462922 -0.409803 0.78598 + outer loop + vertex 698.654 146.112 44.1121 + vertex 698.158 147.66 45.2118 + vertex 697.293 145.757 44.7284 + endloop + endfacet + facet normal 0.463232 -0.439447 0.769611 + outer loop + vertex 697.293 145.757 44.7284 + vertex 697.405 144.737 44.079 + vertex 698.654 146.112 44.1121 + endloop + endfacet + facet normal 0.472654 -0.436007 0.76583 + outer loop + vertex 697.293 145.757 44.7284 + vertex 696.198 145.169 45.0701 + vertex 697.405 144.737 44.079 + endloop + endfacet + facet normal 0.466074 -0.447898 0.762996 + outer loop + vertex 695.17 143.916 44.9621 + vertex 697.405 144.737 44.079 + vertex 696.198 145.169 45.0701 + endloop + endfacet + facet normal 0.468206 -0.42142 0.776652 + outer loop + vertex 697.293 145.757 44.7284 + vertex 697.052 147.263 45.6908 + vertex 696.198 145.169 45.0701 + endloop + endfacet + facet normal 0.483338 -0.415196 0.770712 + outer loop + vertex 698.158 147.66 45.2118 + vertex 697.052 147.263 45.6908 + vertex 697.293 145.757 44.7284 + endloop + endfacet + facet normal 0.47927 -0.378325 0.791941 + outer loop + vertex 698.158 147.66 45.2118 + vertex 698.32 150.528 46.4835 + vertex 697.052 147.263 45.6908 + endloop + endfacet + facet normal 0.515448 -0.385864 0.765129 + outer loop + vertex 698.32 150.528 46.4835 + vertex 697.361 149.713 46.7182 + vertex 697.052 147.263 45.6908 + endloop + endfacet + facet normal 0.486949 -0.38929 0.781878 + outer loop + vertex 697.052 147.263 45.6908 + vertex 697.361 149.713 46.7182 + vertex 696.247 146.98 46.0512 + endloop + endfacet + facet normal 0.490191 -0.42564 0.76062 + outer loop + vertex 697.052 147.263 45.6908 + vertex 696.247 146.98 46.0512 + vertex 696.198 145.169 45.0701 + endloop + endfacet + facet normal 0.484512 -0.42703 0.763475 + outer loop + vertex 696.198 145.169 45.0701 + vertex 696.247 146.98 46.0512 + vertex 695.398 145.028 45.4987 + endloop + endfacet + facet normal 0.481241 -0.458941 0.746847 + outer loop + vertex 695.398 145.028 45.4987 + vertex 695.17 143.916 44.9621 + vertex 696.198 145.169 45.0701 + endloop + endfacet + facet normal 0.491144 -0.458094 0.740896 + outer loop + vertex 695.398 145.028 45.4987 + vertex 694.888 144.638 45.5953 + vertex 695.17 143.916 44.9621 + endloop + endfacet + facet normal 0.484015 -0.462565 0.742808 + outer loop + vertex 694.217 143.622 45.3995 + vertex 695.17 143.916 44.9621 + vertex 694.888 144.638 45.5953 + endloop + endfacet + facet normal 0.489455 -0.465153 0.737609 + outer loop + vertex 694.703 144.728 45.7748 + vertex 694.217 143.622 45.3995 + vertex 694.888 144.638 45.5953 + endloop + endfacet + facet normal 0.511464 -0.43132 0.743214 + outer loop + vertex 694.888 144.638 45.5953 + vertex 695.525 146.731 46.3716 + vertex 694.703 144.728 45.7748 + endloop + endfacet + facet normal 0.461052 -0.421805 0.780712 + outer loop + vertex 695.525 146.731 46.3716 + vertex 695.464 146.765 46.4259 + vertex 694.703 144.728 45.7748 + endloop + endfacet + facet normal 0.399033 -0.411072 0.819629 + outer loop + vertex 694.703 144.728 45.7748 + vertex 695.464 146.765 46.4259 + vertex 694.563 144.592 45.775 + endloop + endfacet + facet normal 0.400027 -0.411304 0.819028 + outer loop + vertex 695.464 146.765 46.4259 + vertex 695.497 146.924 46.4893 + vertex 694.563 144.592 45.775 + endloop + endfacet + facet normal 0.533319 -0.435903 0.724955 + outer loop + vertex 694.563 144.592 45.775 + vertex 695.497 146.924 46.4893 + vertex 694.656 144.931 45.9104 + endloop + endfacet + facet normal 0.393961 -0.432106 0.811221 + outer loop + vertex 694.656 144.931 45.9104 + vertex 694.018 143.68 45.5536 + vertex 694.563 144.592 45.775 + endloop + endfacet + facet normal 0.456411 -0.457696 0.763022 + outer loop + vertex 694.018 143.68 45.5536 + vertex 694.217 143.622 45.3995 + vertex 694.563 144.592 45.775 + endloop + endfacet + facet normal 0.447542 -0.474537 0.757972 + outer loop + vertex 694.217 143.622 45.3995 + vertex 694.018 143.68 45.5536 + vertex 693.15 143.184 45.7555 + endloop + endfacet + facet normal 0.401948 -0.360769 0.841596 + outer loop + vertex 694.018 143.68 45.5536 + vertex 693.93 143.717 45.6119 + vertex 693.15 143.184 45.7555 + endloop + endfacet + facet normal 0.438013 -0.427065 0.79105 + outer loop + vertex 693.15 143.184 45.7555 + vertex 693.93 143.717 45.6119 + vertex 694.014 144.04 45.7392 + endloop + endfacet + facet normal 0.387147 -0.424609 0.818428 + outer loop + vertex 693.93 143.717 45.6119 + vertex 694.418 144.659 45.8697 + vertex 694.014 144.04 45.7392 + endloop + endfacet + facet normal 0.372444 -0.417245 0.82897 + outer loop + vertex 694.418 144.659 45.8697 + vertex 694.716 145.593 46.2058 + vertex 694.014 144.04 45.7392 + endloop + endfacet + facet normal 0.40829 -0.421704 0.809608 + outer loop + vertex 695.264 146.57 46.4382 + vertex 694.716 145.593 46.2058 + vertex 694.418 144.659 45.8697 + endloop + endfacet + facet normal 0.319586 -0.397468 0.860165 + outer loop + vertex 694.51 144.726 45.8664 + vertex 695.264 146.57 46.4382 + vertex 694.418 144.659 45.8697 + endloop + endfacet + facet normal 0.550346 -0.444303 0.706905 + outer loop + vertex 695.502 147.03 46.5415 + vertex 695.264 146.57 46.4382 + vertex 694.51 144.726 45.8664 + endloop + endfacet + facet normal 0.249544 -0.369835 0.894958 + outer loop + vertex 694.656 144.931 45.9104 + vertex 695.502 147.03 46.5415 + vertex 694.51 144.726 45.8664 + endloop + endfacet + facet normal 0.322572 -0.401726 0.857067 + outer loop + vertex 694.418 144.659 45.8697 + vertex 693.93 143.717 45.6119 + vertex 694.51 144.726 45.8664 + endloop + endfacet + facet normal 0.36824 -0.420906 0.828998 + outer loop + vertex 693.93 143.717 45.6119 + vertex 694.018 143.68 45.5536 + vertex 694.51 144.726 45.8664 + endloop + endfacet + facet normal 0.301282 -0.40033 0.865428 + outer loop + vertex 694.656 144.931 45.9104 + vertex 694.51 144.726 45.8664 + vertex 694.018 143.68 45.5536 + endloop + endfacet + facet normal 0.429826 -0.414611 0.80209 + outer loop + vertex 695.497 146.924 46.4893 + vertex 695.502 147.03 46.5415 + vertex 694.656 144.931 45.9104 + endloop + endfacet + facet normal 0.481764 -0.429849 0.763632 + outer loop + vertex 695.747 146.796 46.2679 + vertex 695.525 146.731 46.3716 + vertex 694.888 144.638 45.5953 + endloop + endfacet + facet normal 0.442686 -0.456251 0.771922 + outer loop + vertex 694.703 144.728 45.7748 + vertex 694.563 144.592 45.775 + vertex 694.217 143.622 45.3995 + endloop + endfacet + facet normal 0.467443 -0.688643 0.554318 + outer loop + vertex 695.17 143.916 44.9621 + vertex 694.217 143.622 45.3995 + vertex 693.15 143.184 45.7555 + endloop + endfacet + facet normal 0.47385 -0.428476 0.769334 + outer loop + vertex 695.398 145.028 45.4987 + vertex 695.747 146.796 46.2679 + vertex 694.888 144.638 45.5953 + endloop + endfacet + facet normal 0.487351 -0.427655 0.761315 + outer loop + vertex 696.247 146.98 46.0512 + vertex 695.747 146.796 46.2679 + vertex 695.398 145.028 45.4987 + endloop + endfacet + facet normal 0.459763 -0.382935 0.801236 + outer loop + vertex 697.361 149.713 46.7182 + vertex 697.072 150.228 47.1302 + vertex 696.247 146.98 46.0512 + endloop + endfacet + facet normal 0.482496 -0.384049 0.787213 + outer loop + vertex 696.247 146.98 46.0512 + vertex 697.072 150.228 47.1302 + vertex 695.747 146.796 46.2679 + endloop + endfacet + facet normal 0.556249 -0.398025 0.729495 + outer loop + vertex 697.072 150.228 47.1302 + vertex 696.581 149.523 47.1204 + vertex 695.747 146.796 46.2679 + endloop + endfacet + facet normal 0.480507 -0.392059 0.784476 + outer loop + vertex 695.747 146.796 46.2679 + vertex 696.581 149.523 47.1204 + vertex 695.525 146.731 46.3716 + endloop + endfacet + facet normal 0.266577 -0.342417 0.900937 + outer loop + vertex 696.581 149.523 47.1204 + vertex 696.736 150.214 47.3372 + vertex 695.525 146.731 46.3716 + endloop + endfacet + facet normal 0.484799 -0.386077 0.784802 + outer loop + vertex 695.525 146.731 46.3716 + vertex 696.736 150.214 47.3372 + vertex 695.464 146.765 46.4259 + endloop + endfacet + facet normal 0.91249 -0.377844 0.156831 + outer loop + vertex 696.736 150.214 47.3372 + vertex 696.531 149.674 47.2269 + vertex 695.464 146.765 46.4259 + endloop + endfacet + facet normal 0.56664 -0.405346 0.717366 + outer loop + vertex 695.464 146.765 46.4259 + vertex 696.531 149.674 47.2269 + vertex 695.497 146.924 46.4893 + endloop + endfacet + facet normal 0.267835 -0.342185 0.900652 + outer loop + vertex 696.531 149.674 47.2269 + vertex 696.79 150.449 47.4443 + vertex 695.497 146.924 46.4893 + endloop + endfacet + facet normal 0.521642 -0.396003 0.755692 + outer loop + vertex 695.497 146.924 46.4893 + vertex 696.79 150.449 47.4443 + vertex 695.502 147.03 46.5415 + endloop + endfacet + facet normal 0.88482 -0.397481 0.243108 + outer loop + vertex 696.79 150.449 47.4443 + vertex 696.553 149.857 47.3429 + vertex 695.502 147.03 46.5415 + endloop + endfacet + facet normal 0.343241 -0.371889 0.862487 + outer loop + vertex 695.502 147.03 46.5415 + vertex 696.553 149.857 47.3429 + vertex 695.264 146.57 46.4382 + endloop + endfacet + facet normal 0.721582 -0.431757 0.541207 + outer loop + vertex 696.553 149.857 47.3429 + vertex 695.916 148.33 46.9732 + vertex 695.264 146.57 46.4382 + endloop + endfacet + facet normal 0.30308 -0.378146 0.874727 + outer loop + vertex 695.264 146.57 46.4382 + vertex 695.916 148.33 46.9732 + vertex 694.716 145.593 46.2058 + endloop + endfacet + facet normal 0.478699 -0.378425 0.792238 + outer loop + vertex 699.173 150.227 45.8241 + vertex 698.32 150.528 46.4835 + vertex 698.158 147.66 45.2118 + endloop + endfacet + facet normal 0.469034 -0.376223 0.799039 + outer loop + vertex 699.444 148.105 44.6659 + vertex 699.173 150.227 45.8241 + vertex 698.158 147.66 45.2118 + endloop + endfacet + facet normal 0.491829 -0.36791 0.789143 + outer loop + vertex 700.475 151.174 45.4544 + vertex 699.173 150.227 45.8241 + vertex 699.444 148.105 44.6659 + endloop + endfacet + facet normal 0.4518 -0.361288 0.815688 + outer loop + vertex 700.874 148.629 44.1059 + vertex 700.475 151.174 45.4544 + vertex 699.444 148.105 44.6659 + endloop + endfacet + facet normal 0.459071 -0.358617 0.812802 + outer loop + vertex 701.707 151.048 44.7026 + vertex 700.475 151.174 45.4544 + vertex 700.874 148.629 44.1059 + endloop + endfacet + facet normal 0.456321 -0.391297 0.799161 + outer loop + vertex 700.874 148.629 44.1059 + vertex 699.444 148.105 44.6659 + vertex 700.108 146.832 43.6638 + endloop + endfacet + facet normal 0.43572 -0.354193 0.827463 + outer loop + vertex 702.383 149.162 43.5393 + vertex 701.707 151.048 44.7026 + vertex 700.874 148.629 44.1059 + endloop + endfacet + facet normal 0.454116 -0.34411 0.821807 + outer loop + vertex 703.211 152.054 44.2935 + vertex 701.707 151.048 44.7026 + vertex 702.383 149.162 43.5393 + endloop + endfacet + facet normal 0.414285 -0.338708 0.844775 + outer loop + vertex 704.025 149.753 42.9715 + vertex 703.211 152.054 44.2935 + vertex 702.383 149.162 43.5393 + endloop + endfacet + facet normal 0.424182 -0.333559 0.841907 + outer loop + vertex 704.805 152.097 43.5071 + vertex 703.211 152.054 44.2935 + vertex 704.025 149.753 42.9715 + endloop + endfacet + facet normal 0.441037 -0.317399 0.83949 + outer loop + vertex 701.707 151.048 44.7026 + vertex 703.211 152.054 44.2935 + vertex 702.211 155.495 46.1195 + endloop + endfacet + facet normal 0.470323 -0.315801 0.824055 + outer loop + vertex 701.707 151.048 44.7026 + vertex 702.211 155.495 46.1195 + vertex 700.475 151.174 45.4544 + endloop + endfacet + facet normal 0.46623 -0.305228 0.830341 + outer loop + vertex 704.889 156.307 44.9146 + vertex 702.211 155.495 46.1195 + vertex 703.211 152.054 44.2935 + endloop + endfacet + facet normal 0.419091 -0.364872 0.831403 + outer loop + vertex 704.025 149.753 42.9715 + vertex 702.383 149.162 43.5393 + vertex 703.254 148.016 42.5975 + endloop + endfacet + facet normal 0.394459 -0.327473 0.858582 + outer loop + vertex 705.912 150.504 42.3909 + vertex 704.805 152.097 43.5071 + vertex 704.025 149.753 42.9715 + endloop + endfacet + facet normal 0.409631 -0.315179 0.856075 + outer loop + vertex 706.599 153.348 43.1093 + vertex 704.805 152.097 43.5071 + vertex 705.912 150.504 42.3909 + endloop + endfacet + facet normal 0.399868 -0.297747 0.866864 + outer loop + vertex 704.805 152.097 43.5071 + vertex 706.599 153.348 43.1093 + vertex 704.889 156.307 44.9146 + endloop + endfacet + facet normal 0.429108 -0.294043 0.854052 + outer loop + vertex 704.805 152.097 43.5071 + vertex 704.889 156.307 44.9146 + vertex 703.211 152.054 44.2935 + endloop + endfacet + facet normal 0.425218 -0.279439 0.860874 + outer loop + vertex 708.136 157.431 43.6751 + vertex 704.889 156.307 44.9146 + vertex 706.599 153.348 43.1093 + endloop + endfacet + facet normal 0.418193 -0.0119903 0.908279 + outer loop + vertex 714.933 198.058 45.1958 + vertex 710.117 212.897 47.6089 + vertex 709.819 196.784 47.5335 + endloop + endfacet + facet normal 0.421764 -0.0105655 0.906644 + outer loop + vertex 715.084 213.965 45.3108 + vertex 710.117 212.897 47.6089 + vertex 714.933 198.058 45.1958 + endloop + endfacet + facet normal 0.41906 0.00481402 0.907946 + outer loop + vertex 715.084 213.965 45.3108 + vertex 709.895 228.239 47.6299 + vertex 710.117 212.897 47.6089 + endloop + endfacet + facet normal 0.430047 0.00965152 0.902755 + outer loop + vertex 714.724 229.109 45.3203 + vertex 709.895 228.239 47.6299 + vertex 715.084 213.965 45.3108 + endloop + endfacet + facet normal 0.429524 0.0131027 0.90296 + outer loop + vertex 714.724 229.109 45.3203 + vertex 709.456 242.893 47.6262 + vertex 709.895 228.239 47.6299 + endloop + endfacet + facet normal 0.442922 0.019329 0.896352 + outer loop + vertex 714.129 243.544 45.3032 + vertex 709.456 242.893 47.6262 + vertex 714.724 229.109 45.3203 + endloop + endfacet + facet normal 0.443458 0.0148455 0.896172 + outer loop + vertex 714.129 243.544 45.3032 + vertex 708.978 257.205 47.6254 + vertex 709.456 242.893 47.6262 + endloop + endfacet + facet normal 0.456085 0.0207072 0.889695 + outer loop + vertex 713.504 257.74 45.2933 + vertex 708.978 257.205 47.6254 + vertex 714.129 243.544 45.3032 + endloop + endfacet + facet normal 0.456958 0.0120675 0.889406 + outer loop + vertex 713.504 257.74 45.2933 + vertex 708.596 271.478 47.6281 + vertex 708.978 257.205 47.6254 + endloop + endfacet + facet normal 0.469818 0.017821 0.882583 + outer loop + vertex 712.959 271.965 45.2956 + vertex 708.596 271.478 47.6281 + vertex 713.504 257.74 45.2933 + endloop + endfacet + facet normal 0.470544 0.0100636 0.882319 + outer loop + vertex 712.959 271.965 45.2956 + vertex 708.294 285.772 47.626 + vertex 708.596 271.478 47.6281 + endloop + endfacet + facet normal 0.484954 0.0162711 0.874389 + outer loop + vertex 712.484 286.211 45.2941 + vertex 708.294 285.772 47.626 + vertex 712.959 271.965 45.2956 + endloop + endfacet + facet normal 0.485571 0.00910512 0.87415 + outer loop + vertex 712.484 286.211 45.2941 + vertex 708.043 300.054 47.617 + vertex 708.294 285.772 47.626 + endloop + endfacet + facet normal 0.505409 0.0173903 0.862705 + outer loop + vertex 712.016 300.411 45.282 + vertex 708.043 300.054 47.617 + vertex 712.484 286.211 45.2941 + endloop + endfacet + facet normal 0.506034 0.00889264 0.862468 + outer loop + vertex 712.016 300.411 45.282 + vertex 707.802 314.316 47.6113 + vertex 708.043 300.054 47.617 + endloop + endfacet + facet normal 0.524922 0.0165399 0.85099 + outer loop + vertex 711.567 314.595 45.2833 + vertex 707.802 314.316 47.6113 + vertex 712.016 300.411 45.282 + endloop + endfacet + facet normal 0.525417 0.00829994 0.850805 + outer loop + vertex 711.567 314.595 45.2833 + vertex 707.549 328.577 47.6285 + vertex 707.802 314.316 47.6113 + endloop + endfacet + facet normal 0.547146 0.0168826 0.836867 + outer loop + vertex 711.11 328.779 45.2963 + vertex 707.549 328.577 47.6285 + vertex 711.567 314.595 45.2833 + endloop + endfacet + facet normal 0.5476 0.00704962 0.836711 + outer loop + vertex 711.11 328.779 45.2963 + vertex 707.306 342.853 47.6669 + vertex 707.549 328.577 47.6285 + endloop + endfacet + facet normal 0.574398 0.0173772 0.818392 + outer loop + vertex 710.646 342.99 45.3201 + vertex 707.306 342.853 47.6669 + vertex 711.11 328.779 45.2963 + endloop + endfacet + facet normal 0.574796 0.00571822 0.818277 + outer loop + vertex 710.646 342.99 45.3201 + vertex 707.103 357.185 47.7093 + vertex 707.306 342.853 47.6669 + endloop + endfacet + facet normal 0.602371 0.0160033 0.798056 + outer loop + vertex 710.231 357.288 45.3469 + vertex 707.103 357.185 47.7093 + vertex 710.646 342.99 45.3201 + endloop + endfacet + facet normal 0.602801 -0.00073626 0.797892 + outer loop + vertex 710.231 357.288 45.3469 + vertex 707.122 371.714 47.7088 + vertex 707.103 357.185 47.7093 + endloop + endfacet + facet normal 0.632668 0.0095522 0.774364 + outer loop + vertex 710.054 371.777 45.3126 + vertex 707.122 371.714 47.7088 + vertex 710.231 357.288 45.3469 + endloop + endfacet + facet normal 0.632922 -0.0106125 0.774143 + outer loop + vertex 710.054 371.777 45.3126 + vertex 707.708 386.624 47.4344 + vertex 707.122 371.714 47.7088 + endloop + endfacet + facet normal 0.650244 -0.00581138 0.759703 + outer loop + vertex 710.506 386.592 45.0385 + vertex 707.708 386.624 47.4344 + vertex 710.054 371.777 45.3126 + endloop + endfacet + facet normal 0.334429 -0.0491309 0.94114 + outer loop + vertex 719.314 189.538 43.2769 + vertex 716.484 186.821 44.141 + vertex 719.043 180.92 42.9234 + endloop + endfacet + facet normal 0.32519 -0.0537541 0.94412 + outer loop + vertex 719.043 180.92 42.9234 + vertex 716.484 186.821 44.141 + vertex 715.964 179.556 43.9063 + endloop + endfacet + facet normal 0.333842 -0.0766073 0.939511 + outer loop + vertex 719.043 180.92 42.9234 + vertex 715.964 179.556 43.9063 + vertex 718.637 173.436 42.4575 + endloop + endfacet + facet normal 0.318852 -0.0842288 0.944054 + outer loop + vertex 718.637 173.436 42.4575 + vertex 715.964 179.556 43.9063 + vertex 715.589 172.305 43.3859 + endloop + endfacet + facet normal 0.32841 -0.115408 0.937458 + outer loop + vertex 718.637 173.436 42.4575 + vertex 715.589 172.305 43.3859 + vertex 718.4 166.989 41.747 + endloop + endfacet + facet normal 0.308871 -0.127305 0.942546 + outer loop + vertex 718.4 166.989 41.747 + vertex 715.589 172.305 43.3859 + vertex 715.302 165.959 42.6229 + endloop + endfacet + facet normal 0.318039 -0.162045 0.934127 + outer loop + vertex 718.4 166.989 41.747 + vertex 715.302 165.959 42.6229 + vertex 718.255 161.721 40.8823 + endloop + endfacet + facet normal 0.337065 -0.0100113 0.941428 + outer loop + vertex 720.862 199.623 43.0893 + vertex 715.084 213.965 45.3108 + vertex 714.933 198.058 45.1958 + endloop + endfacet + facet normal 0.347308 -0.00531273 0.937736 + outer loop + vertex 720.739 215.769 43.2266 + vertex 715.084 213.965 45.3108 + vertex 720.862 199.623 43.0893 + endloop + endfacet + facet normal 0.343682 0.00757686 0.939055 + outer loop + vertex 720.739 215.769 43.2266 + vertex 714.724 229.109 45.3203 + vertex 715.084 213.965 45.3108 + endloop + endfacet + facet normal 0.354351 0.0130198 0.935022 + outer loop + vertex 720.183 230.538 43.2314 + vertex 714.724 229.109 45.3203 + vertex 720.739 215.769 43.2266 + endloop + endfacet + facet normal 0.353725 0.0156957 0.935218 + outer loop + vertex 720.183 230.538 43.2314 + vertex 714.129 243.544 45.3032 + vertex 714.724 229.109 45.3203 + endloop + endfacet + facet normal 0.364487 0.0213833 0.930963 + outer loop + vertex 719.409 244.724 43.2088 + vertex 714.129 243.544 45.3032 + vertex 720.183 230.538 43.2314 + endloop + endfacet + facet normal 0.365417 0.0167434 0.930693 + outer loop + vertex 719.409 244.724 43.2088 + vertex 713.504 257.74 45.2933 + vertex 714.129 243.544 45.3032 + endloop + endfacet + facet normal 0.374103 0.0212526 0.927144 + outer loop + vertex 718.623 258.831 43.2027 + vertex 713.504 257.74 45.2933 + vertex 719.409 244.724 43.2088 + endloop + endfacet + facet normal 0.375439 0.0142039 0.926738 + outer loop + vertex 718.623 258.831 43.2027 + vertex 712.959 271.965 45.2956 + vertex 713.504 257.74 45.2933 + endloop + endfacet + facet normal 0.386735 0.0198329 0.921978 + outer loop + vertex 717.893 272.989 43.2042 + vertex 712.959 271.965 45.2956 + vertex 718.623 258.831 43.2027 + endloop + endfacet + facet normal 0.387975 0.013041 0.921578 + outer loop + vertex 717.893 272.989 43.2042 + vertex 712.484 286.211 45.2941 + vertex 712.959 271.965 45.2956 + endloop + endfacet + facet normal 0.401589 0.0195533 0.915611 + outer loop + vertex 717.203 287.13 43.2049 + vertex 712.484 286.211 45.2941 + vertex 717.893 272.989 43.2042 + endloop + endfacet + facet normal 0.402525 0.0140452 0.915301 + outer loop + vertex 717.203 287.13 43.2049 + vertex 712.016 300.411 45.282 + vertex 712.484 286.211 45.2941 + endloop + endfacet + facet normal 0.416568 0.0205349 0.908873 + outer loop + vertex 716.519 301.204 43.2005 + vertex 712.016 300.411 45.282 + vertex 717.203 287.13 43.2049 + endloop + endfacet + facet normal 0.417694 0.0131407 0.908493 + outer loop + vertex 716.519 301.204 43.2005 + vertex 711.567 314.595 45.2833 + vertex 712.016 300.411 45.282 + endloop + endfacet + facet normal 0.436787 0.021629 0.899305 + outer loop + vertex 715.83 315.241 43.1974 + vertex 711.567 314.595 45.2833 + vertex 716.519 301.204 43.2005 + endloop + endfacet + facet normal 0.437871 0.0132996 0.898939 + outer loop + vertex 715.83 315.241 43.1974 + vertex 711.11 328.779 45.2963 + vertex 711.567 314.595 45.2833 + endloop + endfacet + facet normal 0.460231 0.0228688 0.887505 + outer loop + vertex 715.135 329.286 43.1958 + vertex 711.11 328.779 45.2963 + vertex 715.83 315.241 43.1974 + endloop + endfacet + facet normal 0.461233 0.0135681 0.887176 + outer loop + vertex 715.135 329.286 43.1958 + vertex 710.646 342.99 45.3201 + vertex 711.11 328.779 45.2963 + endloop + endfacet + facet normal 0.485857 0.0237215 0.873716 + outer loop + vertex 714.442 343.377 43.1989 + vertex 710.646 342.99 45.3201 + vertex 715.135 329.286 43.1958 + endloop + endfacet + facet normal 0.486828 0.0125066 0.873408 + outer loop + vertex 714.442 343.377 43.1989 + vertex 710.231 357.288 45.3469 + vertex 710.646 342.99 45.3201 + endloop + endfacet + facet normal 0.514166 0.0232574 0.857375 + outer loop + vertex 713.787 357.556 43.2066 + vertex 710.231 357.288 45.3469 + vertex 714.442 343.377 43.1989 + endloop + endfacet + facet normal 0.515114 0.00831403 0.857082 + outer loop + vertex 713.787 357.556 43.2066 + vertex 710.054 371.777 45.3126 + vertex 710.231 357.288 45.3469 + endloop + endfacet + facet normal 0.538752 0.016709 0.842299 + outer loop + vertex 713.357 371.908 43.1974 + vertex 710.054 371.777 45.3126 + vertex 713.787 357.556 43.2066 + endloop + endfacet + facet normal 0.539322 -0.000897949 0.842099 + outer loop + vertex 713.357 371.908 43.1974 + vertex 710.506 386.592 45.0385 + vertex 710.054 371.777 45.3126 + endloop + endfacet + facet normal 0.540211 -0.000653896 0.841529 + outer loop + vertex 713.445 386.552 43.1523 + vertex 710.506 386.592 45.0385 + vertex 713.357 371.908 43.1974 + endloop + endfacet + facet normal 0.248599 -0.0651507 0.966413 + outer loop + vertex 721.897 175.131 41.6384 + vertex 725.385 177.399 40.8942 + vertex 722.387 183.089 42.0488 + endloop + endfacet + facet normal 0.261723 -0.0576303 0.963421 + outer loop + vertex 722.387 183.089 42.0488 + vertex 725.385 177.399 40.8942 + vertex 726.626 187.351 41.1522 + endloop + endfacet + facet normal 0.248191 -0.0432611 0.967745 + outer loop + vertex 722.303 189.771 42.3691 + vertex 722.387 183.089 42.0488 + vertex 726.626 187.351 41.1522 + endloop + endfacet + facet normal 0.253313 -0.0336363 0.966799 + outer loop + vertex 726.626 187.351 41.1522 + vertex 720.862 199.623 43.0893 + vertex 722.303 189.771 42.3691 + endloop + endfacet + facet normal 0.266788 -0.0267691 0.963384 + outer loop + vertex 727.062 203.131 41.47 + vertex 720.862 199.623 43.0893 + vertex 726.626 187.351 41.1522 + endloop + endfacet + facet normal 0.256034 -0.0062572 0.966648 + outer loop + vertex 727.062 203.131 41.47 + vertex 720.739 215.769 43.2266 + vertex 720.862 199.623 43.0893 + endloop + endfacet + facet normal 0.266071 -0.000860438 0.963953 + outer loop + vertex 726.725 218.122 41.5763 + vertex 720.739 215.769 43.2266 + vertex 727.062 203.131 41.47 + endloop + endfacet + facet normal 0.262257 0.00954645 0.964951 + outer loop + vertex 726.725 218.122 41.5763 + vertex 720.183 230.538 43.2314 + vertex 720.739 215.769 43.2266 + endloop + endfacet + facet normal 0.270179 0.0140198 0.962708 + outer loop + vertex 725.943 232.377 41.5883 + vertex 720.183 230.538 43.2314 + vertex 726.725 218.122 41.5763 + endloop + endfacet + facet normal 0.269511 0.0162497 0.96286 + outer loop + vertex 725.943 232.377 41.5883 + vertex 719.409 244.724 43.2088 + vertex 720.183 230.538 43.2314 + endloop + endfacet + facet normal 0.275129 0.0194391 0.961211 + outer loop + vertex 724.996 246.374 41.5762 + vertex 719.409 244.724 43.2088 + vertex 725.943 232.377 41.5883 + endloop + endfacet + facet normal 0.276136 0.0158073 0.960989 + outer loop + vertex 724.996 246.374 41.5762 + vertex 718.623 258.831 43.2027 + vertex 719.409 244.724 43.2088 + endloop + endfacet + facet normal 0.28374 0.0199976 0.958693 + outer loop + vertex 724.043 260.396 41.5659 + vertex 718.623 258.831 43.2027 + vertex 724.996 246.374 41.5762 + endloop + endfacet + facet normal 0.285198 0.0145946 0.958357 + outer loop + vertex 724.043 260.396 41.5659 + vertex 717.893 272.989 43.2042 + vertex 718.623 258.831 43.2027 + endloop + endfacet + facet normal 0.29342 0.0189427 0.955796 + outer loop + vertex 723.122 274.445 41.57 + vertex 717.893 272.989 43.2042 + vertex 724.043 260.396 41.5659 + endloop + endfacet + facet normal 0.294615 0.0143324 0.955509 + outer loop + vertex 723.122 274.445 41.57 + vertex 717.203 287.13 43.2049 + vertex 717.893 272.989 43.2042 + endloop + endfacet + facet normal 0.30625 0.0202484 0.951736 + outer loop + vertex 722.203 288.417 41.5685 + vertex 717.203 287.13 43.2049 + vertex 723.122 274.445 41.57 + endloop + endfacet + facet normal 0.307443 0.0152418 0.951444 + outer loop + vertex 722.203 288.417 41.5685 + vertex 716.519 301.204 43.2005 + vertex 717.203 287.13 43.2049 + endloop + endfacet + facet normal 0.319429 0.0210896 0.947375 + outer loop + vertex 721.283 302.303 41.5696 + vertex 716.519 301.204 43.2005 + vertex 722.203 288.417 41.5685 + endloop + endfacet + facet normal 0.320526 0.0159354 0.947106 + outer loop + vertex 721.283 302.303 41.5696 + vertex 715.83 315.241 43.1974 + vertex 716.519 301.204 43.2005 + endloop + endfacet + facet normal 0.336473 0.0233743 0.941403 + outer loop + vertex 720.35 316.149 41.5595 + vertex 715.83 315.241 43.1974 + vertex 721.283 302.303 41.5696 + endloop + endfacet + facet normal 0.337684 0.0168126 0.941109 + outer loop + vertex 720.35 316.149 41.5595 + vertex 715.135 329.286 43.1958 + vertex 715.83 315.241 43.1974 + endloop + endfacet + facet normal 0.354625 0.0243361 0.934692 + outer loop + vertex 719.419 330.013 41.5517 + vertex 715.135 329.286 43.1958 + vertex 720.35 316.149 41.5595 + endloop + endfacet + facet normal 0.355719 0.017304 0.934433 + outer loop + vertex 719.419 330.013 41.5517 + vertex 714.442 343.377 43.1989 + vertex 715.135 329.286 43.1958 + endloop + endfacet + facet normal 0.376725 0.0261722 0.925955 + outer loop + vertex 718.487 343.921 41.5375 + vertex 714.442 343.377 43.1989 + vertex 719.419 330.013 41.5517 + endloop + endfacet + facet normal 0.377867 0.016932 0.925705 + outer loop + vertex 718.487 343.921 41.5375 + vertex 713.787 357.556 43.2066 + vertex 714.442 343.377 43.1989 + endloop + endfacet + facet normal 0.404406 0.0274926 0.914166 + outer loop + vertex 717.583 357.908 41.517 + vertex 713.787 357.556 43.2066 + vertex 718.487 343.921 41.5375 + endloop + endfacet + facet normal 0.405669 0.0127603 0.913931 + outer loop + vertex 717.583 357.908 41.517 + vertex 713.357 371.908 43.1974 + vertex 713.787 357.556 43.2066 + endloop + endfacet + facet normal 0.425087 0.0197016 0.904938 + outer loop + vertex 716.885 372.068 41.5366 + vertex 713.357 371.908 43.1974 + vertex 717.583 357.908 41.517 + endloop + endfacet + facet normal 0.425893 0.000228055 0.904773 + outer loop + vertex 716.885 372.068 41.5366 + vertex 713.445 386.552 43.1523 + vertex 713.357 371.908 43.1974 + endloop + endfacet + facet normal 0.430829 0.00166166 0.902432 + outer loop + vertex 716.638 386.503 41.6277 + vertex 713.445 386.552 43.1523 + vertex 716.885 372.068 41.5366 + endloop + endfacet + facet normal 0.225378 -0.0807726 0.970917 + outer loop + vertex 728.342 178.279 40.2809 + vertex 725.385 177.399 40.8942 + vertex 728.584 172.501 39.7441 + endloop + endfacet + facet normal 0.196828 -0.0825281 0.976958 + outer loop + vertex 728.342 178.279 40.2809 + vertex 728.584 172.501 39.7441 + vertex 733.069 177.235 39.2403 + endloop + endfacet + facet normal 0.20294 -0.0555126 0.977616 + outer loop + vertex 733.069 177.235 39.2403 + vertex 726.626 187.351 41.1522 + vertex 728.342 178.279 40.2809 + endloop + endfacet + facet normal 0.20555 -0.0537655 0.977169 + outer loop + vertex 733.686 191.576 39.8996 + vertex 726.626 187.351 41.1522 + vertex 733.069 177.235 39.2403 + endloop + endfacet + facet normal 0.189125 -0.0249912 0.981635 + outer loop + vertex 733.686 191.576 39.8996 + vertex 727.062 203.131 41.47 + vertex 726.626 187.351 41.1522 + endloop + endfacet + facet normal 0.194904 -0.0215359 0.980586 + outer loop + vertex 733.569 206.264 40.2454 + vertex 727.062 203.131 41.47 + vertex 733.686 191.576 39.8996 + endloop + endfacet + facet normal 0.186237 -0.00278568 0.982501 + outer loop + vertex 733.569 206.264 40.2454 + vertex 726.725 218.122 41.5763 + vertex 727.062 203.131 41.47 + endloop + endfacet + facet normal 0.190598 -0.000175107 0.981668 + outer loop + vertex 732.881 220.513 40.3816 + vertex 726.725 218.122 41.5763 + vertex 733.569 206.264 40.2454 + endloop + endfacet + facet normal 0.186989 0.00943844 0.982317 + outer loop + vertex 732.881 220.513 40.3816 + vertex 725.943 232.377 41.5883 + vertex 726.725 218.122 41.5763 + endloop + endfacet + facet normal 0.191504 0.0121702 0.981416 + outer loop + vertex 731.881 234.445 40.4038 + vertex 725.943 232.377 41.5883 + vertex 732.881 220.513 40.3816 + endloop + endfacet + facet normal 0.190965 0.0137645 0.9815 + outer loop + vertex 731.881 234.445 40.4038 + vertex 724.996 246.374 41.5762 + vertex 725.943 232.377 41.5883 + endloop + endfacet + facet normal 0.19547 0.016456 0.980572 + outer loop + vertex 730.783 248.333 40.3896 + vertex 724.996 246.374 41.5762 + vertex 731.881 234.445 40.4038 + endloop + endfacet + facet normal 0.196256 0.0140633 0.980452 + outer loop + vertex 730.783 248.333 40.3896 + vertex 724.043 260.396 41.5659 + vertex 724.996 246.374 41.5762 + endloop + endfacet + facet normal 0.200197 0.0163469 0.979619 + outer loop + vertex 729.678 262.265 40.3831 + vertex 724.043 260.396 41.5659 + vertex 730.783 248.333 40.3896 + endloop + endfacet + facet normal 0.201303 0.0129017 0.979444 + outer loop + vertex 729.678 262.265 40.3831 + vertex 723.122 274.445 41.57 + vertex 724.043 260.396 41.5659 + endloop + endfacet + facet normal 0.208638 0.0170054 0.977845 + outer loop + vertex 728.552 276.144 40.3819 + vertex 723.122 274.445 41.57 + vertex 729.678 262.265 40.3831 + endloop + endfacet + facet normal 0.209579 0.0138919 0.977693 + outer loop + vertex 728.552 276.144 40.3819 + vertex 722.203 288.417 41.5685 + vertex 723.122 274.445 41.57 + endloop + endfacet + facet normal 0.217245 0.0180267 0.975951 + outer loop + vertex 727.402 289.903 40.3837 + vertex 722.203 288.417 41.5685 + vertex 728.552 276.144 40.3819 + endloop + endfacet + facet normal 0.218249 0.0143847 0.975787 + outer loop + vertex 727.402 289.903 40.3837 + vertex 721.283 302.303 41.5696 + vertex 722.203 288.417 41.5685 + endloop + endfacet + facet normal 0.227407 0.0191119 0.973612 + outer loop + vertex 726.241 303.571 40.3866 + vertex 721.283 302.303 41.5696 + vertex 727.402 289.903 40.3837 + endloop + endfacet + facet normal 0.22815 0.0160935 0.973493 + outer loop + vertex 726.241 303.571 40.3866 + vertex 720.35 316.149 41.5595 + vertex 721.283 302.303 41.5696 + endloop + endfacet + facet normal 0.237456 0.0206685 0.971178 + outer loop + vertex 725.069 317.206 40.3831 + vertex 720.35 316.149 41.5595 + vertex 726.241 303.571 40.3866 + endloop + endfacet + facet normal 0.238345 0.0165478 0.97104 + outer loop + vertex 725.069 317.206 40.3831 + vertex 719.419 330.013 41.5517 + vertex 720.35 316.149 41.5595 + endloop + endfacet + facet normal 0.252232 0.0230073 0.967393 + outer loop + vertex 723.887 330.849 40.3669 + vertex 719.419 330.013 41.5517 + vertex 725.069 317.206 40.3831 + endloop + endfacet + facet normal 0.253146 0.0179398 0.967262 + outer loop + vertex 723.887 330.849 40.3669 + vertex 718.487 343.921 41.5375 + vertex 719.419 330.013 41.5517 + endloop + endfacet + facet normal 0.269962 0.0253087 0.962538 + outer loop + vertex 722.707 344.537 40.3378 + vertex 718.487 343.921 41.5375 + vertex 723.887 330.849 40.3669 + endloop + endfacet + facet normal 0.270862 0.0189283 0.962432 + outer loop + vertex 722.707 344.537 40.3378 + vertex 717.583 357.908 41.517 + vertex 718.487 343.921 41.5375 + endloop + endfacet + facet normal 0.288381 0.0261067 0.95716 + outer loop + vertex 721.564 358.309 40.3065 + vertex 717.583 357.908 41.517 + vertex 722.707 344.537 40.3378 + endloop + endfacet + facet normal 0.289667 0.0129542 0.95704 + outer loop + vertex 721.564 358.309 40.3065 + vertex 716.885 372.068 41.5366 + vertex 717.583 357.908 41.517 + endloop + endfacet + facet normal 0.309985 0.0204463 0.950522 + outer loop + vertex 720.598 372.243 40.3219 + vertex 716.885 372.068 41.5366 + vertex 721.564 358.309 40.3065 + endloop + endfacet + facet normal 0.310949 -0.000689888 0.950426 + outer loop + vertex 720.598 372.243 40.3219 + vertex 716.638 386.503 41.6277 + vertex 716.885 372.068 41.5366 + endloop + endfacet + facet normal 0.327872 0.00453273 0.944711 + outer loop + vertex 720.06 386.446 40.4405 + vertex 716.638 386.503 41.6277 + vertex 720.598 372.243 40.3219 + endloop + endfacet + facet normal 0.217707 -0.0524298 0.974605 + outer loop + vertex 728.342 178.279 40.2809 + vertex 726.626 187.351 41.1522 + vertex 725.385 177.399 40.8942 + endloop + endfacet + facet normal 0.214447 -0.0997903 0.971625 + outer loop + vertex 728.584 172.501 39.7441 + vertex 732 168.372 38.566 + vertex 733.069 177.235 39.2403 + endloop + endfacet + facet normal 0.216474 -0.131086 0.967448 + outer loop + vertex 728.287 166.2 39.0567 + vertex 724.989 170.188 40.3351 + vertex 724.832 164.404 39.5866 + endloop + endfacet + facet normal 0.258318 -0.130895 0.957151 + outer loop + vertex 724.989 170.188 40.3351 + vertex 721.603 168.351 40.9978 + vertex 724.832 164.404 39.5866 + endloop + endfacet + facet normal 0.272457 -0.115306 0.955234 + outer loop + vertex 721.603 168.351 40.9978 + vertex 718.637 173.436 42.4575 + vertex 718.4 166.989 41.747 + endloop + endfacet + facet normal 0.299496 -0.176414 0.937646 + outer loop + vertex 718.255 161.721 40.8823 + vertex 715.302 165.959 42.6229 + vertex 714.97 160.553 41.712 + endloop + endfacet + facet normal 0.264845 -0.227248 0.937132 + outer loop + vertex 720.307 155.833 38.9804 + vertex 717.848 157.565 40.0954 + vertex 716.816 154.741 39.7023 + endloop + endfacet + facet normal 0.268161 -0.222645 0.937293 + outer loop + vertex 721.356 158.866 39.4009 + vertex 717.848 157.565 40.0954 + vertex 720.307 155.833 38.9804 + endloop + endfacet + facet normal 0.236403 -0.192474 0.952401 + outer loop + vertex 724.754 160.279 38.8429 + vertex 721.524 162.919 40.1783 + vertex 721.356 158.866 39.4009 + endloop + endfacet + facet normal 0.223027 -0.197492 0.954597 + outer loop + vertex 728.051 161.75 38.3769 + vertex 724.754 160.279 38.8429 + vertex 727.48 159.129 37.9681 + endloop + endfacet + facet normal 0.197377 -0.192927 0.961156 + outer loop + vertex 730.759 160.252 37.5202 + vertex 728.051 161.75 38.3769 + vertex 727.48 159.129 37.9681 + endloop + endfacet + facet normal 0.203658 -0.182036 0.96197 + outer loop + vertex 731.579 163.374 37.9374 + vertex 728.051 161.75 38.3769 + vertex 730.759 160.252 37.5202 + endloop + endfacet + facet normal 0.165948 -0.136798 0.9766 + outer loop + vertex 735.21 165.023 37.5515 + vertex 732 168.372 38.566 + vertex 731.579 163.374 37.9374 + endloop + endfacet + facet normal 0.172664 -0.130278 0.976327 + outer loop + vertex 735.639 169.37 38.0555 + vertex 732 168.372 38.566 + vertex 735.21 165.023 37.5515 + endloop + endfacet + facet normal 0.145306 -0.128125 0.981056 + outer loop + vertex 739.007 167.037 37.252 + vertex 735.639 169.37 38.0555 + vertex 735.21 165.023 37.5515 + endloop + endfacet + facet normal 0.153528 -0.11633 0.981273 + outer loop + vertex 739.171 172.534 37.8781 + vertex 735.639 169.37 38.0555 + vertex 739.007 167.037 37.252 + endloop + endfacet + facet normal 0.141072 -0.102233 0.984707 + outer loop + vertex 735.639 169.37 38.0555 + vertex 739.171 172.534 37.8781 + vertex 733.069 177.235 39.2403 + endloop + endfacet + facet normal 0.16364 -0.0944501 0.981988 + outer loop + vertex 735.639 169.37 38.0555 + vertex 733.069 177.235 39.2403 + vertex 732 168.372 38.566 + endloop + endfacet + facet normal 0.155398 -0.0835255 0.984314 + outer loop + vertex 740.904 181.305 38.3488 + vertex 733.069 177.235 39.2403 + vertex 739.171 172.534 37.8781 + endloop + endfacet + facet normal 0.120007 -0.0768278 0.989796 + outer loop + vertex 742.975 174.179 37.5446 + vertex 740.904 181.305 38.3488 + vertex 739.171 172.534 37.8781 + endloop + endfacet + facet normal 0.113336 -0.0788375 0.990424 + outer loop + vertex 748.044 175.767 37.0909 + vertex 740.904 181.305 38.3488 + vertex 742.975 174.179 37.5446 + endloop + endfacet + facet normal 0.117125 -0.0739371 0.990361 + outer loop + vertex 748.239 186.352 37.858 + vertex 740.904 181.305 38.3488 + vertex 748.044 175.767 37.0909 + endloop + endfacet + facet normal 0.0830272 -0.0735594 0.993829 + outer loop + vertex 755.608 180.55 36.813 + vertex 748.239 186.352 37.858 + vertex 748.044 175.767 37.0909 + endloop + endfacet + facet normal 0.0863718 -0.069315 0.993849 + outer loop + vertex 755.443 190.173 37.4985 + vertex 748.239 186.352 37.858 + vertex 755.608 180.55 36.813 + endloop + endfacet + facet normal 0.0668294 -0.0697542 0.995323 + outer loop + vertex 762.827 184.312 36.5919 + vertex 755.443 190.173 37.4985 + vertex 755.608 180.55 36.813 + endloop + endfacet + facet normal 0.0678919 -0.0684189 0.995344 + outer loop + vertex 762.398 193.699 37.2664 + vertex 755.443 190.173 37.4985 + vertex 762.827 184.312 36.5919 + endloop + endfacet + facet normal 0.0550474 -0.06906 0.996093 + outer loop + vertex 769.698 188.056 36.4718 + vertex 762.398 193.699 37.2664 + vertex 762.827 184.312 36.5919 + endloop + endfacet + facet normal 0.0555247 -0.0684449 0.996109 + outer loop + vertex 769.15 197.342 37.1403 + vertex 762.398 193.699 37.2664 + vertex 769.698 188.056 36.4718 + endloop + endfacet + facet normal 0.0478787 -0.068922 0.996472 + outer loop + vertex 776.227 191.941 36.4268 + vertex 769.15 197.342 37.1403 + vertex 769.698 188.056 36.4718 + endloop + endfacet + facet normal 0.0486422 -0.0679258 0.996504 + outer loop + vertex 775.767 201.242 37.0832 + vertex 769.15 197.342 37.1403 + vertex 776.227 191.941 36.4268 + endloop + endfacet + facet normal 0.0469418 -0.0680152 0.996579 + outer loop + vertex 782.736 196.02 36.3986 + vertex 775.767 201.242 37.0832 + vertex 776.227 191.941 36.4268 + endloop + endfacet + facet normal 0.0459548 -0.0693267 0.996535 + outer loop + vertex 782.314 205.359 37.0677 + vertex 775.767 201.242 37.0832 + vertex 782.736 196.02 36.3986 + endloop + endfacet + facet normal 0.0444841 -0.0693975 0.996597 + outer loop + vertex 789.233 200.427 36.4154 + vertex 782.314 205.359 37.0677 + vertex 782.736 196.02 36.3986 + endloop + endfacet + facet normal 0.0428559 -0.0716695 0.996507 + outer loop + vertex 788.751 209.691 37.1024 + vertex 782.314 205.359 37.0677 + vertex 789.233 200.427 36.4154 + endloop + endfacet + facet normal 0.0378055 -0.0719457 0.996692 + outer loop + vertex 795.592 205.073 36.5096 + vertex 788.751 209.691 37.1024 + vertex 789.233 200.427 36.4154 + endloop + endfacet + facet normal 0.0355949 -0.0752005 0.996533 + outer loop + vertex 795.017 214.242 37.222 + vertex 788.751 209.691 37.1024 + vertex 795.592 205.073 36.5096 + endloop + endfacet + facet normal 0.0243059 -0.0759304 0.996817 + outer loop + vertex 801.81 209.955 36.7299 + vertex 795.017 214.242 37.222 + vertex 795.592 205.073 36.5096 + endloop + endfacet + facet normal 0.0210556 -0.0810435 0.996488 + outer loop + vertex 801.013 218.932 37.4768 + vertex 795.017 214.242 37.222 + vertex 801.81 209.955 36.7299 + endloop + endfacet + facet normal 0.00168462 -0.0827699 0.996567 + outer loop + vertex 807.439 214.847 37.1267 + vertex 801.013 218.932 37.4768 + vertex 801.81 209.955 36.7299 + endloop + endfacet + facet normal -0.0026063 -0.0894707 0.995986 + outer loop + vertex 806.703 223.572 37.9085 + vertex 801.013 218.932 37.4768 + vertex 807.439 214.847 37.1267 + endloop + endfacet + facet normal -0.0260759 -0.0914035 0.995472 + outer loop + vertex 812.391 219.068 37.644 + vertex 806.703 223.572 37.9085 + vertex 807.439 214.847 37.1267 + endloop + endfacet + facet normal -0.037492 -0.105717 0.993689 + outer loop + vertex 812.645 227.893 38.5924 + vertex 806.703 223.572 37.9085 + vertex 812.391 219.068 37.644 + endloop + endfacet + facet normal -0.0503867 -0.10529 0.993164 + outer loop + vertex 812.391 219.068 37.644 + vertex 816.816 221.556 38.1323 + vertex 812.645 227.893 38.5924 + endloop + endfacet + facet normal -0.0961396 -0.1349 0.986184 + outer loop + vertex 816.816 221.556 38.1323 + vertex 818.311 226.507 38.9552 + vertex 812.645 227.893 38.5924 + endloop + endfacet + facet normal -0.0898255 -0.108075 0.990076 + outer loop + vertex 816.67 233.966 39.6205 + vertex 812.645 227.893 38.5924 + vertex 818.311 226.507 38.9552 + endloop + endfacet + facet normal -0.132233 -0.116891 0.984302 + outer loop + vertex 821.103 230.441 39.7975 + vertex 816.67 233.966 39.6205 + vertex 818.311 226.507 38.9552 + endloop + endfacet + facet normal -0.138909 -0.125386 0.982335 + outer loop + vertex 820.538 237.597 40.6309 + vertex 816.67 233.966 39.6205 + vertex 821.103 230.441 39.7975 + endloop + endfacet + facet normal -0.157608 -0.126516 0.979364 + outer loop + vertex 823.997 233.21 40.6209 + vertex 820.538 237.597 40.6309 + vertex 821.103 230.441 39.7975 + endloop + endfacet + facet normal -0.188398 -0.150778 0.970449 + outer loop + vertex 823.704 238.577 41.3979 + vertex 820.538 237.597 40.6309 + vertex 823.997 233.21 40.6209 + endloop + endfacet + facet normal -0.186915 -0.150739 0.970742 + outer loop + vertex 826.542 235.417 41.4536 + vertex 823.704 238.577 41.3979 + vertex 823.997 233.21 40.6209 + endloop + endfacet + facet normal -0.210991 -0.172513 0.962145 + outer loop + vertex 825.866 240.842 42.2781 + vertex 823.704 238.577 41.3979 + vertex 826.542 235.417 41.4536 + endloop + endfacet + facet normal -0.228432 -0.174036 0.957878 + outer loop + vertex 828.826 237.481 42.3733 + vertex 825.866 240.842 42.2781 + vertex 826.542 235.417 41.4536 + endloop + endfacet + facet normal -0.27337 -0.214181 0.937761 + outer loop + vertex 828.293 241.487 43.1329 + vertex 825.866 240.842 42.2781 + vertex 828.826 237.481 42.3733 + endloop + endfacet + facet normal -0.257874 -0.213003 0.942407 + outer loop + vertex 830.897 239.698 43.441 + vertex 828.293 241.487 43.1329 + vertex 828.826 237.481 42.3733 + endloop + endfacet + facet normal -0.257828 -0.212931 0.942436 + outer loop + vertex 829.699 244.234 44.1381 + vertex 828.293 241.487 43.1329 + vertex 830.897 239.698 43.441 + endloop + endfacet + facet normal -0.320333 -0.225985 0.919955 + outer loop + vertex 832.738 242.246 44.708 + vertex 829.699 244.234 44.1381 + vertex 830.897 239.698 43.441 + endloop + endfacet + facet normal -0.322571 -0.229908 0.9182 + outer loop + vertex 831.493 246.845 45.4221 + vertex 829.699 244.234 44.1381 + vertex 832.738 242.246 44.708 + endloop + endfacet + facet normal -0.393242 -0.244109 0.886438 + outer loop + vertex 834.268 244.624 46.0418 + vertex 831.493 246.845 45.4221 + vertex 832.738 242.246 44.708 + endloop + endfacet + facet normal -0.395561 -0.247563 0.884446 + outer loop + vertex 833.144 248.891 46.7333 + vertex 831.493 246.845 45.4221 + vertex 834.268 244.624 46.0418 + endloop + endfacet + facet normal -0.455957 -0.25818 0.851732 + outer loop + vertex 835.482 246.471 47.2515 + vertex 833.144 248.891 46.7333 + vertex 834.268 244.624 46.0418 + endloop + endfacet + facet normal -0.456117 -0.258365 0.85159 + outer loop + vertex 834.576 250.446 47.9719 + vertex 833.144 248.891 46.7333 + vertex 835.482 246.471 47.2515 + endloop + endfacet + facet normal -0.473344 -0.260462 0.84149 + outer loop + vertex 835.482 246.471 47.2515 + vertex 836.6 247.67 48.2517 + vertex 834.576 250.446 47.9719 + endloop + endfacet + facet normal -0.490506 -0.274432 0.827098 + outer loop + vertex 836.026 251.309 49.1185 + vertex 834.576 250.446 47.9719 + vertex 836.6 247.67 48.2517 + endloop + endfacet + facet normal -0.469451 -0.27403 0.839359 + outer loop + vertex 837.561 247.932 48.8743 + vertex 836.026 251.309 49.1185 + vertex 836.6 247.67 48.2517 + endloop + endfacet + facet normal -0.500148 -0.286379 0.817214 + outer loop + vertex 837.561 247.932 48.8743 + vertex 837.862 248.943 49.4131 + vertex 836.026 251.309 49.1185 + endloop + endfacet + facet normal -0.500977 -0.287117 0.816447 + outer loop + vertex 836.842 252.675 50.0992 + vertex 836.026 251.309 49.1185 + vertex 837.862 248.943 49.4131 + endloop + endfacet + facet normal -0.491822 -0.285722 0.82248 + outer loop + vertex 838.382 249.074 49.7692 + vertex 836.842 252.675 50.0992 + vertex 837.862 248.943 49.4131 + endloop + endfacet + facet normal -0.573908 -0.314736 0.756023 + outer loop + vertex 838.382 249.074 49.7692 + vertex 838.287 250.084 50.118 + vertex 836.842 252.675 50.0992 + endloop + endfacet + facet normal -0.550953 -0.301769 0.778066 + outer loop + vertex 837.012 254.123 50.7815 + vertex 836.842 252.675 50.0992 + vertex 838.287 250.084 50.118 + endloop + endfacet + facet normal -0.643926 -0.317645 0.696033 + outer loop + vertex 838.462 250.13 50.3006 + vertex 837.012 254.123 50.7815 + vertex 838.287 250.084 50.118 + endloop + endfacet + facet normal -0.0537487 -0.147931 0.987536 + outer loop + vertex 820.073 222.521 38.454 + vertex 818.311 226.507 38.9552 + vertex 816.816 221.556 38.1323 + endloop + endfacet + facet normal -0.0713572 -0.155426 0.985267 + outer loop + vertex 822.096 225.323 39.0425 + vertex 818.311 226.507 38.9552 + vertex 820.073 222.521 38.454 + endloop + endfacet + facet normal -0.0725514 -0.159295 0.984562 + outer loop + vertex 821.103 230.441 39.7975 + vertex 818.311 226.507 38.9552 + vertex 822.096 225.323 39.0425 + endloop + endfacet + facet normal -0.0909017 -0.162552 0.982504 + outer loop + vertex 824.698 228.239 39.7657 + vertex 821.103 230.441 39.7975 + vertex 822.096 225.323 39.0425 + endloop + endfacet + facet normal -0.103327 -0.182766 0.977712 + outer loop + vertex 823.997 233.21 40.6209 + vertex 821.103 230.441 39.7975 + vertex 824.698 228.239 39.7657 + endloop + endfacet + facet normal -0.111275 -0.183706 0.976663 + outer loop + vertex 827.275 230.86 40.5524 + vertex 823.997 233.21 40.6209 + vertex 824.698 228.239 39.7657 + endloop + endfacet + facet normal -0.132273 -0.212745 0.968113 + outer loop + vertex 826.542 235.417 41.4536 + vertex 823.997 233.21 40.6209 + vertex 827.275 230.86 40.5524 + endloop + endfacet + facet normal -0.139003 -0.213603 0.966981 + outer loop + vertex 829.671 233.264 41.4278 + vertex 826.542 235.417 41.4536 + vertex 827.275 230.86 40.5524 + endloop + endfacet + facet normal -0.161835 -0.246646 0.955497 + outer loop + vertex 828.826 237.481 42.3733 + vertex 826.542 235.417 41.4536 + vertex 829.671 233.264 41.4278 + endloop + endfacet + facet normal -0.169532 -0.247821 0.953857 + outer loop + vertex 831.955 235.767 42.484 + vertex 828.826 237.481 42.3733 + vertex 829.671 233.264 41.4278 + endloop + endfacet + facet normal -0.186454 -0.279482 0.941873 + outer loop + vertex 830.897 239.698 43.441 + vertex 828.826 237.481 42.3733 + vertex 831.955 235.767 42.484 + endloop + endfacet + facet normal -0.209883 -0.284237 0.935499 + outer loop + vertex 834.131 238.415 43.7769 + vertex 830.897 239.698 43.441 + vertex 831.955 235.767 42.484 + endloop + endfacet + facet normal -0.217033 -0.30436 0.927503 + outer loop + vertex 832.738 242.246 44.708 + vertex 830.897 239.698 43.441 + vertex 834.131 238.415 43.7769 + endloop + endfacet + facet normal -0.277556 -0.321017 0.90549 + outer loop + vertex 836.036 241.103 45.3137 + vertex 832.738 242.246 44.708 + vertex 834.131 238.415 43.7769 + endloop + endfacet + facet normal -0.279106 -0.326847 0.902924 + outer loop + vertex 834.268 244.624 46.0418 + vertex 832.738 242.246 44.708 + vertex 836.036 241.103 45.3137 + endloop + endfacet + facet normal 0.02542 -0.0457743 0.998628 + outer loop + vertex 788.751 209.691 37.1024 + vertex 781.314 216.77 37.6162 + vertex 782.314 205.359 37.0677 + endloop + endfacet + facet normal 0.0296442 -0.0453992 0.998529 + outer loop + vertex 781.314 216.77 37.6162 + vertex 774.772 212.736 37.627 + vertex 782.314 205.359 37.0677 + endloop + endfacet + facet normal 0.0167699 -0.024515 0.999559 + outer loop + vertex 781.314 216.77 37.6162 + vertex 773.543 225.496 37.9606 + vertex 774.772 212.736 37.627 + endloop + endfacet + facet normal 0.0223476 -0.0239751 0.999463 + outer loop + vertex 773.543 225.496 37.9606 + vertex 766.911 221.761 38.0193 + vertex 774.772 212.736 37.627 + endloop + endfacet + facet normal 0.022643 -0.0237177 0.999462 + outer loop + vertex 774.772 212.736 37.627 + vertex 766.911 221.761 38.0193 + vertex 768.126 208.886 37.6862 + endloop + endfacet + facet normal 0.0345288 -0.0442497 0.998424 + outer loop + vertex 774.772 212.736 37.627 + vertex 768.126 208.886 37.6862 + vertex 775.767 201.242 37.0832 + endloop + endfacet + facet normal 0.0322778 -0.0228028 0.999219 + outer loop + vertex 766.911 221.761 38.0193 + vertex 760.2 218.212 38.1551 + vertex 768.126 208.886 37.6862 + endloop + endfacet + facet normal 0.0320894 -0.022963 0.999221 + outer loop + vertex 768.126 208.886 37.6862 + vertex 760.2 218.212 38.1551 + vertex 761.402 205.266 37.819 + endloop + endfacet + facet normal 0.0430581 -0.0433786 0.99813 + outer loop + vertex 768.126 208.886 37.6862 + vertex 761.402 205.266 37.819 + vertex 769.15 197.342 37.1403 + endloop + endfacet + facet normal 0.0477618 -0.021493 0.998627 + outer loop + vertex 760.2 218.212 38.1551 + vertex 753.471 214.916 38.406 + vertex 761.402 205.266 37.819 + endloop + endfacet + facet normal 0.0466842 -0.0223805 0.998659 + outer loop + vertex 761.402 205.266 37.819 + vertex 753.471 214.916 38.406 + vertex 754.607 201.922 38.0617 + endloop + endfacet + facet normal 0.056677 -0.0427689 0.997476 + outer loop + vertex 761.402 205.266 37.819 + vertex 754.607 201.922 38.0617 + vertex 762.398 193.699 37.2664 + endloop + endfacet + facet normal 0.0684954 -0.0204423 0.997442 + outer loop + vertex 753.471 214.916 38.406 + vertex 746.779 211.933 38.8044 + vertex 754.607 201.922 38.0617 + endloop + endfacet + facet normal 0.066661 -0.0218833 0.997536 + outer loop + vertex 754.607 201.922 38.0617 + vertex 746.779 211.933 38.8044 + vertex 747.732 198.7 38.4504 + endloop + endfacet + facet normal 0.0761706 -0.0423351 0.996196 + outer loop + vertex 754.607 201.922 38.0617 + vertex 747.732 198.7 38.4504 + vertex 755.443 190.173 37.4985 + endloop + endfacet + facet normal 0.0965545 -0.0196679 0.995133 + outer loop + vertex 746.779 211.933 38.8044 + vertex 740.152 209.124 39.3919 + vertex 747.732 198.7 38.4504 + endloop + endfacet + facet normal 0.0934433 -0.0219528 0.995383 + outer loop + vertex 747.732 198.7 38.4504 + vertex 740.152 209.124 39.3919 + vertex 740.763 195.277 39.0291 + endloop + endfacet + facet normal 0.103835 -0.0434067 0.993647 + outer loop + vertex 747.732 198.7 38.4504 + vertex 740.763 195.277 39.0291 + vertex 748.239 186.352 37.858 + endloop + endfacet + facet normal 0.137048 -0.0198951 0.990365 + outer loop + vertex 740.152 209.124 39.3919 + vertex 733.569 206.264 40.2454 + vertex 740.763 195.277 39.0291 + endloop + endfacet + facet normal 0.133504 -0.0222639 0.990798 + outer loop + vertex 740.763 195.277 39.0291 + vertex 733.569 206.264 40.2454 + vertex 733.686 191.576 39.8996 + endloop + endfacet + facet normal 0.14594 -0.0466529 0.988193 + outer loop + vertex 740.763 195.277 39.0291 + vertex 733.686 191.576 39.8996 + vertex 740.904 181.305 38.3488 + endloop + endfacet + facet normal 0.139263 -0.0514544 0.988918 + outer loop + vertex 740.904 181.305 38.3488 + vertex 733.686 191.576 39.8996 + vertex 733.069 177.235 39.2403 + endloop + endfacet + facet normal 0.129945 -0.00320074 0.991516 + outer loop + vertex 740.152 209.124 39.3919 + vertex 732.881 220.513 40.3816 + vertex 733.569 206.264 40.2454 + endloop + endfacet + facet normal 0.13302 -0.00120281 0.991113 + outer loop + vertex 739.168 222.934 39.5407 + vertex 732.881 220.513 40.3816 + vertex 740.152 209.124 39.3919 + endloop + endfacet + facet normal 0.12964 0.00771662 0.991531 + outer loop + vertex 739.168 222.934 39.5407 + vertex 731.881 234.445 40.4038 + vertex 732.881 220.513 40.3816 + endloop + endfacet + facet normal 0.132115 0.00930884 0.991191 + outer loop + vertex 738.015 236.725 39.5649 + vertex 731.881 234.445 40.4038 + vertex 739.168 222.934 39.5407 + endloop + endfacet + facet normal 0.0889191 0.00568723 0.996023 + outer loop + vertex 745.622 225.549 38.9496 + vertex 738.015 236.725 39.5649 + vertex 739.168 222.934 39.5407 + endloop + endfacet + facet normal 0.0923195 -0.00277135 0.995726 + outer loop + vertex 745.622 225.549 38.9496 + vertex 739.168 222.934 39.5407 + vertex 746.779 211.933 38.8044 + endloop + endfacet + facet normal 0.090446 0.00673445 0.995879 + outer loop + vertex 744.374 239.285 38.97 + vertex 738.015 236.725 39.5649 + vertex 745.622 225.549 38.9496 + endloop + endfacet + facet normal 0.0596523 0.00393455 0.998211 + outer loop + vertex 752.229 228.473 38.5432 + vertex 744.374 239.285 38.97 + vertex 745.622 225.549 38.9496 + endloop + endfacet + facet normal 0.0632846 -0.00430692 0.997986 + outer loop + vertex 752.229 228.473 38.5432 + vertex 745.622 225.549 38.9496 + vertex 753.471 214.916 38.406 + endloop + endfacet + facet normal 0.0610486 0.00495249 0.998123 + outer loop + vertex 750.897 242.119 38.557 + vertex 744.374 239.285 38.97 + vertex 752.229 228.473 38.5432 + endloop + endfacet + facet normal 0.037054 0.00260778 0.99931 + outer loop + vertex 758.91 231.69 38.2871 + vertex 750.897 242.119 38.557 + vertex 752.229 228.473 38.5432 + endloop + endfacet + facet normal 0.041121 -0.00585203 0.999137 + outer loop + vertex 758.91 231.69 38.2871 + vertex 752.229 228.473 38.5432 + vertex 760.2 218.212 38.1551 + endloop + endfacet + facet normal 0.0379096 0.003266 0.999276 + outer loop + vertex 757.478 245.172 38.2974 + vertex 750.897 242.119 38.557 + vertex 758.91 231.69 38.2871 + endloop + endfacet + facet normal 0.0200988 0.00137449 0.999797 + outer loop + vertex 765.565 235.113 38.1486 + vertex 757.478 245.172 38.2974 + vertex 758.91 231.69 38.2871 + endloop + endfacet + facet normal 0.0245131 -0.00721208 0.999673 + outer loop + vertex 765.565 235.113 38.1486 + vertex 758.91 231.69 38.2871 + vertex 766.911 221.761 38.0193 + endloop + endfacet + facet normal 0.0202504 0.00149647 0.999794 + outer loop + vertex 764.022 248.389 38.16 + vertex 757.478 245.172 38.2974 + vertex 765.565 235.113 38.1486 + endloop + endfacet + facet normal 0.00885395 0.000172216 0.999961 + outer loop + vertex 772.131 238.682 38.0899 + vertex 764.022 248.389 38.16 + vertex 765.565 235.113 38.1486 + endloop + endfacet + facet normal 0.0134905 -0.00835941 0.999874 + outer loop + vertex 772.131 238.682 38.0899 + vertex 765.565 235.113 38.1486 + vertex 773.543 225.496 37.9606 + endloop + endfacet + facet normal 0.00682434 -0.00907366 0.999936 + outer loop + vertex 780.053 229.392 37.9515 + vertex 772.131 238.682 38.0899 + vertex 773.543 225.496 37.9606 + endloop + endfacet + facet normal 0.00641916 -0.00941913 0.999935 + outer loop + vertex 778.583 242.393 38.0834 + vertex 772.131 238.682 38.0899 + vertex 780.053 229.392 37.9515 + endloop + endfacet + facet normal -0.000510104 -0.0102028 0.999948 + outer loop + vertex 786.42 233.45 37.9962 + vertex 778.583 242.393 38.0834 + vertex 780.053 229.392 37.9515 + endloop + endfacet + facet normal 0.00950857 -0.0259173 0.999619 + outer loop + vertex 786.42 233.45 37.9962 + vertex 780.053 229.392 37.9515 + vertex 787.717 220.975 37.6604 + endloop + endfacet + facet normal -0.0018112 -0.0270943 0.999631 + outer loop + vertex 793.933 225.366 37.7907 + vertex 786.42 233.45 37.9962 + vertex 787.717 220.975 37.6604 + endloop + endfacet + facet normal 0.0141576 -0.0496695 0.998665 + outer loop + vertex 793.933 225.366 37.7907 + vertex 787.717 220.975 37.6604 + vertex 795.017 214.242 37.222 + endloop + endfacet + facet normal -0.00232386 -0.0512767 0.998682 + outer loop + vertex 801.013 218.932 37.4768 + vertex 793.933 225.366 37.7907 + vertex 795.017 214.242 37.222 + endloop + endfacet + facet normal -0.00422131 -0.0533587 0.998566 + outer loop + vertex 799.916 229.926 38.0596 + vertex 793.933 225.366 37.7907 + vertex 801.013 218.932 37.4768 + endloop + endfacet + facet normal -0.0301236 -0.0559107 0.997981 + outer loop + vertex 806.703 223.572 37.9085 + vertex 799.916 229.926 38.0596 + vertex 801.013 218.932 37.4768 + endloop + endfacet + facet normal -0.0337065 -0.0597297 0.997645 + outer loop + vertex 805.685 234.561 38.532 + vertex 799.916 229.926 38.0596 + vertex 806.703 223.572 37.9085 + endloop + endfacet + facet normal -0.0688785 -0.0628738 0.995642 + outer loop + vertex 812.645 227.893 38.5924 + vertex 805.685 234.561 38.532 + vertex 806.703 223.572 37.9085 + endloop + endfacet + facet normal -0.0756046 -0.0699032 0.994685 + outer loop + vertex 810.967 239.427 39.2755 + vertex 805.685 234.561 38.532 + vertex 812.645 227.893 38.5924 + endloop + endfacet + facet normal -0.134518 -0.0780673 0.987831 + outer loop + vertex 816.67 233.966 39.6205 + vertex 810.967 239.427 39.2755 + vertex 812.645 227.893 38.5924 + endloop + endfacet + facet normal -0.13617 -0.0798152 0.987465 + outer loop + vertex 815.849 243.929 40.3126 + vertex 810.967 239.427 39.2755 + vertex 816.67 233.966 39.6205 + endloop + endfacet + facet normal -0.17839 -0.0828077 0.980469 + outer loop + vertex 816.67 233.966 39.6205 + vertex 820.538 237.597 40.6309 + vertex 815.849 243.929 40.3126 + endloop + endfacet + facet normal -0.206559 -0.104046 0.972886 + outer loop + vertex 821.512 246.993 41.8424 + vertex 815.849 243.929 40.3126 + vertex 820.538 237.597 40.6309 + endloop + endfacet + facet normal -0.20349 -0.104442 0.97349 + outer loop + vertex 823.704 238.577 41.3979 + vertex 821.512 246.993 41.8424 + vertex 820.538 237.597 40.6309 + endloop + endfacet + facet normal -0.162678 -0.0505893 0.985381 + outer loop + vertex 815.849 243.929 40.3126 + vertex 809.655 251.111 39.6587 + vertex 810.967 239.427 39.2755 + endloop + endfacet + facet normal -0.168585 -0.0558 0.984106 + outer loop + vertex 814.825 255.401 40.7876 + vertex 809.655 251.111 39.6587 + vertex 815.849 243.929 40.3126 + endloop + endfacet + facet normal -0.182865 -0.0381414 0.982398 + outer loop + vertex 814.825 255.401 40.7876 + vertex 808.047 262.995 39.8208 + vertex 809.655 251.111 39.6587 + endloop + endfacet + facet normal -0.187972 -0.0428475 0.981239 + outer loop + vertex 813.098 267.327 40.9777 + vertex 808.047 262.995 39.8208 + vertex 814.825 255.401 40.7876 + endloop + endfacet + facet normal -0.193624 -0.0360368 0.980414 + outer loop + vertex 813.098 267.327 40.9777 + vertex 805.99 274.645 39.8429 + vertex 808.047 262.995 39.8208 + endloop + endfacet + facet normal -0.197484 -0.0399285 0.979493 + outer loop + vertex 811.022 278.746 41.0244 + vertex 805.99 274.645 39.8429 + vertex 813.098 267.327 40.9777 + endloop + endfacet + facet normal -0.19724 -0.0402378 0.979529 + outer loop + vertex 811.022 278.746 41.0244 + vertex 803.547 285.832 39.8104 + vertex 805.99 274.645 39.8429 + endloop + endfacet + facet normal -0.200536 -0.0438548 0.978704 + outer loop + vertex 808.558 289.648 41.0082 + vertex 803.547 285.832 39.8104 + vertex 811.022 278.746 41.0244 + endloop + endfacet + facet normal -0.198008 -0.0472857 0.979059 + outer loop + vertex 808.558 289.648 41.0082 + vertex 800.806 296.569 39.7746 + vertex 803.547 285.832 39.8104 + endloop + endfacet + facet normal -0.199152 -0.0486201 0.978762 + outer loop + vertex 805.8 300.064 40.9643 + vertex 800.806 296.569 39.7746 + vertex 808.558 289.648 41.0082 + endloop + endfacet + facet normal -0.195947 -0.0533357 0.979163 + outer loop + vertex 805.8 300.064 40.9643 + vertex 797.871 306.931 39.7517 + vertex 800.806 296.569 39.7746 + endloop + endfacet + facet normal -0.198072 -0.0558903 0.978593 + outer loop + vertex 802.83 310.06 40.9342 + vertex 797.871 306.931 39.7517 + vertex 805.8 300.064 40.9643 + endloop + endfacet + facet normal -0.196045 -0.0591836 0.978807 + outer loop + vertex 802.83 310.06 40.9342 + vertex 794.807 317.012 39.7476 + vertex 797.871 306.931 39.7517 + endloop + endfacet + facet normal -0.198925 -0.0626437 0.978011 + outer loop + vertex 799.727 319.76 40.9243 + vertex 794.807 317.012 39.7476 + vertex 802.83 310.06 40.9342 + endloop + endfacet + facet normal -0.198337 -0.0637174 0.978061 + outer loop + vertex 799.727 319.76 40.9243 + vertex 791.649 326.898 39.7512 + vertex 794.807 317.012 39.7476 + endloop + endfacet + facet normal -0.202152 -0.0682123 0.976976 + outer loop + vertex 796.525 329.26 40.9251 + vertex 791.649 326.898 39.7512 + vertex 799.727 319.76 40.9243 + endloop + endfacet + facet normal -0.202261 -0.0679833 0.976969 + outer loop + vertex 796.525 329.26 40.9251 + vertex 788.406 336.654 39.7588 + vertex 791.649 326.898 39.7512 + endloop + endfacet + facet normal -0.208428 -0.0750421 0.975154 + outer loop + vertex 793.228 338.632 40.9416 + vertex 788.406 336.654 39.7588 + vertex 796.525 329.26 40.9251 + endloop + endfacet + facet normal -0.209437 -0.0725664 0.975126 + outer loop + vertex 793.228 338.632 40.9416 + vertex 785.086 346.338 39.7662 + vertex 788.406 336.654 39.7588 + endloop + endfacet + facet normal -0.212687 -0.0761497 0.974149 + outer loop + vertex 789.859 347.912 40.9314 + vertex 785.086 346.338 39.7662 + vertex 793.228 338.632 40.9416 + endloop + endfacet + facet normal -0.213843 -0.0726564 0.974162 + outer loop + vertex 789.859 347.912 40.9314 + vertex 781.706 356.001 39.7449 + vertex 785.086 346.338 39.7662 + endloop + endfacet + facet normal -0.216066 -0.0749955 0.973494 + outer loop + vertex 786.435 357.155 40.8836 + vertex 781.706 356.001 39.7449 + vertex 789.859 347.912 40.9314 + endloop + endfacet + facet normal -0.217369 -0.0697556 0.973594 + outer loop + vertex 786.435 357.155 40.8836 + vertex 778.321 365.69 39.6834 + vertex 781.706 356.001 39.7449 + endloop + endfacet + facet normal -0.223692 -0.0760355 0.971689 + outer loop + vertex 783.028 366.41 40.8235 + vertex 778.321 365.69 39.6834 + vertex 786.435 357.155 40.8836 + endloop + endfacet + facet normal -0.224498 -0.0710667 0.97188 + outer loop + vertex 783.028 366.41 40.8235 + vertex 775.153 375.453 39.6657 + vertex 778.321 365.69 39.6834 + endloop + endfacet + facet normal -0.239946 -0.0851371 0.967046 + outer loop + vertex 779.842 375.74 40.8544 + vertex 775.153 375.453 39.6657 + vertex 783.028 366.41 40.8235 + endloop + endfacet + facet normal -0.240911 -0.0725809 0.967829 + outer loop + vertex 779.842 375.74 40.8544 + vertex 772.465 385.352 39.7387 + vertex 775.153 375.453 39.6657 + endloop + endfacet + facet normal -0.240558 -0.0722975 0.967938 + outer loop + vertex 777.328 385.236 40.9389 + vertex 772.465 385.352 39.7387 + vertex 779.842 375.74 40.8544 + endloop + endfacet + facet normal -0.101828 -0.0413263 0.993943 + outer loop + vertex 810.967 239.427 39.2755 + vertex 804.284 246.592 38.8887 + vertex 805.685 234.561 38.532 + endloop + endfacet + facet normal -0.0566728 -0.0361803 0.997737 + outer loop + vertex 804.284 246.592 38.8887 + vertex 798.591 242.069 38.4013 + vertex 805.685 234.561 38.532 + endloop + endfacet + facet normal -0.069708 -0.0197321 0.997372 + outer loop + vertex 804.284 246.592 38.8887 + vertex 796.967 254.445 38.5327 + vertex 798.591 242.069 38.4013 + endloop + endfacet + facet normal -0.0355571 -0.0152718 0.999251 + outer loop + vertex 796.967 254.445 38.5327 + vertex 791.035 250.286 38.2581 + vertex 798.591 242.069 38.4013 + endloop + endfacet + facet normal -0.0349821 -0.0147426 0.999279 + outer loop + vertex 798.591 242.069 38.4013 + vertex 791.035 250.286 38.2581 + vertex 792.612 237.68 38.1273 + endloop + endfacet + facet normal -0.0232963 -0.030661 0.999258 + outer loop + vertex 798.591 242.069 38.4013 + vertex 792.612 237.68 38.1273 + vertex 799.916 229.926 38.0596 + endloop + endfacet + facet normal -0.0133096 -0.0120381 0.999839 + outer loop + vertex 791.035 250.286 38.2581 + vertex 784.896 246.263 38.1279 + vertex 792.612 237.68 38.1273 + endloop + endfacet + facet normal -0.0130822 -0.0118338 0.999844 + outer loop + vertex 792.612 237.68 38.1273 + vertex 784.896 246.263 38.1279 + vertex 786.42 233.45 37.9962 + endloop + endfacet + facet normal -0.0186502 -0.00388776 0.999819 + outer loop + vertex 791.035 250.286 38.2581 + vertex 783.068 258.898 38.1429 + vertex 784.896 246.263 38.1279 + endloop + endfacet + facet normal -0.00614282 -0.00207889 0.999979 + outer loop + vertex 783.068 258.898 38.1429 + vertex 776.841 255.252 38.0971 + vertex 784.896 246.263 38.1279 + endloop + endfacet + facet normal -0.00590031 -0.00186155 0.999981 + outer loop + vertex 784.896 246.263 38.1279 + vertex 776.841 255.252 38.0971 + vertex 778.583 242.393 38.0834 + endloop + endfacet + facet normal 0.00128668 -0.000888065 0.999999 + outer loop + vertex 776.841 255.252 38.0971 + vertex 770.485 251.747 38.1022 + vertex 778.583 242.393 38.0834 + endloop + endfacet + facet normal -0.000127515 0.00167688 0.999999 + outer loop + vertex 776.841 255.252 38.0971 + vertex 768.564 264.545 38.0805 + vertex 770.485 251.747 38.1022 + endloop + endfacet + facet normal 0.00736895 0.00280183 0.999969 + outer loop + vertex 768.564 264.545 38.0805 + vertex 762.237 261.423 38.1358 + vertex 770.485 251.747 38.1022 + endloop + endfacet + facet normal 0.00745771 0.00287748 0.999968 + outer loop + vertex 770.485 251.747 38.1022 + vertex 762.237 261.423 38.1358 + vertex 764.022 248.389 38.16 + endloop + endfacet + facet normal 0.019383 0.00451045 0.999802 + outer loop + vertex 762.237 261.423 38.1358 + vertex 755.84 258.45 38.2733 + vertex 764.022 248.389 38.16 + endloop + endfacet + facet normal 0.0196921 0.00384523 0.999799 + outer loop + vertex 762.237 261.423 38.1358 + vertex 754.005 271.52 38.2591 + vertex 755.84 258.45 38.2733 + endloop + endfacet + facet normal 0.0388169 0.00652931 0.999225 + outer loop + vertex 754.005 271.52 38.2591 + vertex 747.766 268.961 38.5182 + vertex 755.84 258.45 38.2733 + endloop + endfacet + facet normal 0.0377269 0.00569092 0.999272 + outer loop + vertex 755.84 258.45 38.2733 + vertex 747.766 268.961 38.5182 + vertex 749.413 255.63 38.532 + endloop + endfacet + facet normal 0.0374028 0.00643011 0.99928 + outer loop + vertex 755.84 258.45 38.2733 + vertex 749.413 255.63 38.532 + vertex 757.478 245.172 38.2974 + endloop + endfacet + facet normal 0.0633805 0.00885927 0.99795 + outer loop + vertex 747.766 268.961 38.5182 + vertex 741.577 266.56 38.9326 + vertex 749.413 255.63 38.532 + endloop + endfacet + facet normal 0.0619478 0.00782847 0.998049 + outer loop + vertex 749.413 255.63 38.532 + vertex 741.577 266.56 38.9326 + vertex 743.034 252.985 38.9487 + endloop + endfacet + facet normal 0.0616211 0.0086187 0.998062 + outer loop + vertex 749.413 255.63 38.532 + vertex 743.034 252.985 38.9487 + vertex 750.897 242.119 38.557 + endloop + endfacet + facet normal 0.095198 0.011395 0.995393 + outer loop + vertex 741.577 266.56 38.9326 + vertex 735.526 264.328 39.5369 + vertex 743.034 252.985 38.9487 + endloop + endfacet + facet normal 0.0924608 0.00956872 0.99567 + outer loop + vertex 743.034 252.985 38.9487 + vertex 735.526 264.328 39.5369 + vertex 736.801 250.546 39.5509 + endloop + endfacet + facet normal 0.0920747 0.0105616 0.995696 + outer loop + vertex 743.034 252.985 38.9487 + vertex 736.801 250.546 39.5509 + vertex 744.374 239.285 38.97 + endloop + endfacet + facet normal 0.138425 0.0138152 0.990277 + outer loop + vertex 735.526 264.328 39.5369 + vertex 729.678 262.265 40.3831 + vertex 736.801 250.546 39.5509 + endloop + endfacet + facet normal 0.134035 0.0111021 0.990914 + outer loop + vertex 736.801 250.546 39.5509 + vertex 729.678 262.265 40.3831 + vertex 730.783 248.333 40.3896 + endloop + endfacet + facet normal 0.133447 0.0127252 0.990974 + outer loop + vertex 736.801 250.546 39.5509 + vertex 730.783 248.333 40.3896 + vertex 738.015 236.725 39.5649 + endloop + endfacet + facet normal 0.139271 0.0113815 0.990189 + outer loop + vertex 735.526 264.328 39.5369 + vertex 728.552 276.144 40.3819 + vertex 729.678 262.265 40.3831 + endloop + endfacet + facet normal 0.143712 0.0140505 0.98952 + outer loop + vertex 734.189 277.992 39.5369 + vertex 728.552 276.144 40.3819 + vertex 735.526 264.328 39.5369 + endloop + endfacet + facet normal 0.144395 0.0119358 0.989448 + outer loop + vertex 734.189 277.992 39.5369 + vertex 727.402 289.903 40.3837 + vertex 728.552 276.144 40.3819 + endloop + endfacet + facet normal 0.148983 0.014601 0.988732 + outer loop + vertex 732.811 291.519 39.5448 + vertex 727.402 289.903 40.3837 + vertex 734.189 277.992 39.5369 + endloop + endfacet + facet normal 0.1496 0.0124996 0.988668 + outer loop + vertex 732.811 291.519 39.5448 + vertex 726.241 303.571 40.3866 + vertex 727.402 289.903 40.3837 + endloop + endfacet + facet normal 0.15647 0.0163229 0.987548 + outer loop + vertex 731.401 304.95 39.5463 + vertex 726.241 303.571 40.3866 + vertex 732.811 291.519 39.5448 + endloop + endfacet + facet normal 0.157143 0.0137663 0.98748 + outer loop + vertex 731.401 304.95 39.5463 + vertex 725.069 317.206 40.3831 + vertex 726.241 303.571 40.3866 + endloop + endfacet + facet normal 0.163759 0.017262 0.986349 + outer loop + vertex 729.983 318.354 39.5471 + vertex 725.069 317.206 40.3831 + vertex 731.401 304.95 39.5463 + endloop + endfacet + facet normal 0.164188 0.0154004 0.986309 + outer loop + vertex 729.983 318.354 39.5471 + vertex 723.887 330.849 40.3669 + vertex 725.069 317.206 40.3831 + endloop + endfacet + facet normal 0.17248 0.0195437 0.984819 + outer loop + vertex 728.546 331.76 39.5328 + vertex 723.887 330.849 40.3669 + vertex 729.983 318.354 39.5471 + endloop + endfacet + facet normal 0.172971 0.0169962 0.98478 + outer loop + vertex 728.546 331.76 39.5328 + vertex 722.707 344.537 40.3378 + vertex 723.887 330.849 40.3669 + endloop + endfacet + facet normal 0.182532 0.0214799 0.982965 + outer loop + vertex 727.116 345.211 39.5043 + vertex 722.707 344.537 40.3378 + vertex 728.546 331.76 39.5328 + endloop + endfacet + facet normal 0.183144 0.017432 0.982931 + outer loop + vertex 727.116 345.211 39.5043 + vertex 721.564 358.309 40.3065 + vertex 722.707 344.537 40.3378 + endloop + endfacet + facet normal 0.196477 0.0232494 0.980233 + outer loop + vertex 725.714 358.74 39.4645 + vertex 721.564 358.309 40.3065 + vertex 727.116 345.211 39.5043 + endloop + endfacet + facet normal 0.197576 0.0126206 0.980206 + outer loop + vertex 725.714 358.74 39.4645 + vertex 720.598 372.243 40.3219 + vertex 721.564 358.309 40.3065 + endloop + endfacet + facet normal 0.212366 0.0184264 0.977016 + outer loop + vertex 724.474 372.435 39.4758 + vertex 720.598 372.243 40.3219 + vertex 725.714 358.74 39.4645 + endloop + endfacet + facet normal 0.213275 -7.90821e-05 0.976992 + outer loop + vertex 724.474 372.435 39.4758 + vertex 720.06 386.446 40.4405 + vertex 720.598 372.243 40.3219 + endloop + endfacet + facet normal 0.238921 0.00841226 0.971003 + outer loop + vertex 723.539 386.384 39.585 + vertex 720.06 386.446 40.4405 + vertex 724.474 372.435 39.4758 + endloop + endfacet + facet normal 0.095937 0.00937818 0.995343 + outer loop + vertex 741.577 266.56 38.9326 + vertex 734.189 277.992 39.5369 + vertex 735.526 264.328 39.5369 + endloop + endfacet + facet normal 0.0988365 0.0112678 0.99504 + outer loop + vertex 740.024 279.98 38.9349 + vertex 734.189 277.992 39.5369 + vertex 741.577 266.56 38.9326 + endloop + endfacet + facet normal 0.0994182 0.00954785 0.995 + outer loop + vertex 740.024 279.98 38.9349 + vertex 732.811 291.519 39.5448 + vertex 734.189 277.992 39.5369 + endloop + endfacet + facet normal 0.103468 0.0121028 0.994559 + outer loop + vertex 738.409 293.256 38.9413 + vertex 732.811 291.519 39.5448 + vertex 740.024 279.98 38.9349 + endloop + endfacet + facet normal 0.0667895 0.00763959 0.997738 + outer loop + vertex 745.997 282.118 38.5187 + vertex 738.409 293.256 38.9413 + vertex 740.024 279.98 38.9349 + endloop + endfacet + facet normal 0.0663445 0.00888615 0.997757 + outer loop + vertex 745.997 282.118 38.5187 + vertex 740.024 279.98 38.9349 + vertex 747.766 268.961 38.5182 + endloop + endfacet + facet normal 0.0690187 0.00916453 0.997573 + outer loop + vertex 744.158 295.139 38.5263 + vertex 738.409 293.256 38.9413 + vertex 745.997 282.118 38.5187 + endloop + endfacet + facet normal 0.0409742 0.00520357 0.999147 + outer loop + vertex 752.034 284.412 38.2592 + vertex 744.158 295.139 38.5263 + vertex 745.997 282.118 38.5187 + endloop + endfacet + facet normal 0.0405944 0.00620422 0.999156 + outer loop + vertex 752.034 284.412 38.2592 + vertex 745.997 282.118 38.5187 + vertex 754.005 271.52 38.2591 + endloop + endfacet + facet normal 0.0206288 0.00315104 0.999782 + outer loop + vertex 760.23 274.233 38.1221 + vertex 752.034 284.412 38.2592 + vertex 754.005 271.52 38.2591 + endloop + endfacet + facet normal 0.0211828 0.00359728 0.999769 + outer loop + vertex 758.075 286.851 38.1224 + vertex 752.034 284.412 38.2592 + vertex 760.23 274.233 38.1221 + endloop + endfacet + facet normal 0.00828299 0.00139337 0.999965 + outer loop + vertex 766.407 277.089 38.067 + vertex 758.075 286.851 38.1224 + vertex 760.23 274.233 38.1221 + endloop + endfacet + facet normal 0.00780996 0.00241639 0.999967 + outer loop + vertex 766.407 277.089 38.067 + vertex 760.23 274.233 38.1221 + vertex 768.564 264.545 38.0805 + endloop + endfacet + facet normal 1.12319e-05 0.00107545 0.999999 + outer loop + vertex 774.804 267.807 38.0769 + vertex 766.407 277.089 38.067 + vertex 768.564 264.545 38.0805 + endloop + endfacet + facet normal -0.000255754 0.000833934 1 + outer loop + vertex 772.508 280.081 38.0661 + vertex 766.407 277.089 38.067 + vertex 774.804 267.807 38.0769 + endloop + endfacet + facet normal -0.00740679 -0.000503722 0.999972 + outer loop + vertex 780.923 271.198 38.1239 + vertex 772.508 280.081 38.0661 + vertex 774.804 267.807 38.0769 + endloop + endfacet + facet normal -0.00778982 0.00018759 0.99997 + outer loop + vertex 780.923 271.198 38.1239 + vertex 774.804 267.807 38.0769 + vertex 783.068 258.898 38.1429 + endloop + endfacet + facet normal -0.0200136 -0.00194479 0.999798 + outer loop + vertex 789.135 262.674 38.2717 + vertex 780.923 271.198 38.1239 + vertex 783.068 258.898 38.1429 + endloop + endfacet + facet normal -0.0203641 -0.00228254 0.99979 + outer loop + vertex 786.887 274.7 38.2534 + vertex 780.923 271.198 38.1239 + vertex 789.135 262.674 38.2717 + endloop + endfacet + facet normal -0.0423811 -0.00639896 0.999081 + outer loop + vertex 794.998 266.566 38.5453 + vertex 786.887 274.7 38.2534 + vertex 789.135 262.674 38.2717 + endloop + endfacet + facet normal -0.0414659 -0.00777985 0.99911 + outer loop + vertex 794.998 266.566 38.5453 + vertex 789.135 262.674 38.2717 + vertex 796.967 254.445 38.5327 + endloop + endfacet + facet normal -0.0767343 -0.0135078 0.99696 + outer loop + vertex 802.643 258.703 39.0273 + vertex 794.998 266.566 38.5453 + vertex 796.967 254.445 38.5327 + endloop + endfacet + facet normal -0.0776414 -0.0143948 0.996877 + outer loop + vertex 800.63 270.56 39.0417 + vertex 794.998 266.566 38.5453 + vertex 802.643 258.703 39.0273 + endloop + endfacet + facet normal -0.127466 -0.0228471 0.99158 + outer loop + vertex 808.047 262.995 39.8208 + vertex 800.63 270.56 39.0417 + vertex 802.643 258.703 39.0273 + endloop + endfacet + facet normal -0.121846 -0.030017 0.992095 + outer loop + vertex 808.047 262.995 39.8208 + vertex 802.643 258.703 39.0273 + vertex 809.655 251.111 39.6587 + endloop + endfacet + facet normal -0.119155 -0.0274977 0.992495 + outer loop + vertex 809.655 251.111 39.6587 + vertex 802.643 258.703 39.0273 + vertex 804.284 246.592 38.8887 + endloop + endfacet + facet normal -0.129336 -0.0247098 0.991293 + outer loop + vertex 805.99 274.645 39.8429 + vertex 800.63 270.56 39.0417 + vertex 808.047 262.995 39.8208 + endloop + endfacet + facet normal -0.129254 -0.024818 0.991301 + outer loop + vertex 805.99 274.645 39.8429 + vertex 798.231 282.021 39.0159 + vertex 800.63 270.56 39.0417 + endloop + endfacet + facet normal -0.0783268 -0.0141461 0.996827 + outer loop + vertex 798.231 282.021 39.0159 + vertex 792.665 278.307 38.5258 + vertex 800.63 270.56 39.0417 + endloop + endfacet + facet normal -0.0769255 -0.0162559 0.996904 + outer loop + vertex 798.231 282.021 39.0159 + vertex 790.057 289.681 38.5099 + vertex 792.665 278.307 38.5258 + endloop + endfacet + facet normal -0.0419852 -0.00823887 0.999084 + outer loop + vertex 790.057 289.681 38.5099 + vertex 784.366 286.385 38.2436 + vertex 792.665 278.307 38.5258 + endloop + endfacet + facet normal -0.0419678 -0.00822097 0.999085 + outer loop + vertex 792.665 278.307 38.5258 + vertex 784.366 286.385 38.2436 + vertex 786.887 274.7 38.2534 + endloop + endfacet + facet normal -0.0200755 -0.00349671 0.999792 + outer loop + vertex 784.366 286.385 38.2436 + vertex 778.506 283.184 38.1148 + vertex 786.887 274.7 38.2534 + endloop + endfacet + facet normal -0.0194639 -0.00461675 0.9998 + outer loop + vertex 784.366 286.385 38.2436 + vertex 775.91 294.907 38.1183 + vertex 778.506 283.184 38.1148 + endloop + endfacet + facet normal -0.00750546 -0.00196821 0.99997 + outer loop + vertex 775.91 294.907 38.1183 + vertex 770.039 292.117 38.0688 + vertex 778.506 283.184 38.1148 + endloop + endfacet + facet normal -0.00723498 -0.00171181 0.999972 + outer loop + vertex 778.506 283.184 38.1148 + vertex 770.039 292.117 38.0688 + vertex 772.508 280.081 38.0661 + endloop + endfacet + facet normal 0.000197861 -0.000186968 1 + outer loop + vertex 770.039 292.117 38.0688 + vertex 764.084 289.427 38.0695 + vertex 772.508 280.081 38.0661 + endloop + endfacet + facet normal 0.000318936 -0.000454978 1 + outer loop + vertex 770.039 292.117 38.0688 + vertex 761.659 301.586 38.0758 + vertex 764.084 289.427 38.0695 + endloop + endfacet + facet normal 0.00890018 0.00125633 0.99996 + outer loop + vertex 761.659 301.586 38.0758 + vertex 755.828 299.319 38.1305 + vertex 764.084 289.427 38.0695 + endloop + endfacet + facet normal 0.00843636 0.000869202 0.999964 + outer loop + vertex 764.084 289.427 38.0695 + vertex 755.828 299.319 38.1305 + vertex 758.075 286.851 38.1224 + endloop + endfacet + facet normal 0.0223976 0.00338468 0.999743 + outer loop + vertex 755.828 299.319 38.1305 + vertex 749.986 297.168 38.2687 + vertex 758.075 286.851 38.1224 + endloop + endfacet + facet normal 0.0224804 0.0031597 0.999742 + outer loop + vertex 755.828 299.319 38.1305 + vertex 747.881 309.816 38.276 + vertex 749.986 297.168 38.2687 + endloop + endfacet + facet normal 0.0445172 0.00682705 0.998985 + outer loop + vertex 747.881 309.816 38.276 + vertex 742.282 308.075 38.5374 + vertex 749.986 297.168 38.2687 + endloop + endfacet + facet normal 0.0423238 0.00527539 0.99909 + outer loop + vertex 749.986 297.168 38.2687 + vertex 742.282 308.075 38.5374 + vertex 744.158 295.139 38.5263 + endloop + endfacet + facet normal 0.071963 0.00957451 0.997361 + outer loop + vertex 742.282 308.075 38.5374 + vertex 736.768 306.451 38.9509 + vertex 744.158 295.139 38.5263 + endloop + endfacet + facet normal 0.0721002 0.00910707 0.997356 + outer loop + vertex 742.282 308.075 38.5374 + vertex 735.092 319.6 38.952 + vertex 736.768 306.451 38.9509 + endloop + endfacet + facet normal 0.112269 0.0142269 0.993576 + outer loop + vertex 735.092 319.6 38.952 + vertex 729.983 318.354 39.5471 + vertex 736.768 306.451 38.9509 + endloop + endfacet + facet normal 0.107139 0.0112728 0.99418 + outer loop + vertex 736.768 306.451 38.9509 + vertex 729.983 318.354 39.5471 + vertex 731.401 304.95 39.5463 + endloop + endfacet + facet normal 0.106782 0.0125597 0.994203 + outer loop + vertex 736.768 306.451 38.9509 + vertex 731.401 304.95 39.5463 + vertex 738.409 293.256 38.9413 + endloop + endfacet + facet normal 0.112535 0.0131265 0.993561 + outer loop + vertex 735.092 319.6 38.952 + vertex 728.546 331.76 39.5328 + vertex 729.983 318.354 39.5471 + endloop + endfacet + facet normal 0.116806 0.0154507 0.993035 + outer loop + vertex 733.404 332.754 38.9459 + vertex 728.546 331.76 39.5328 + vertex 735.092 319.6 38.952 + endloop + endfacet + facet normal 0.116992 0.0145371 0.993026 + outer loop + vertex 733.404 332.754 38.9459 + vertex 727.116 345.211 39.5043 + vertex 728.546 331.76 39.5328 + endloop + endfacet + facet normal 0.122588 0.0173936 0.992305 + outer loop + vertex 731.713 345.945 38.9235 + vertex 727.116 345.211 39.5043 + vertex 733.404 332.754 38.9459 + endloop + endfacet + facet normal 0.122865 0.015654 0.9923 + outer loop + vertex 731.713 345.945 38.9235 + vertex 725.714 358.74 39.4645 + vertex 727.116 345.211 39.5043 + endloop + endfacet + facet normal 0.128326 0.0182459 0.991564 + outer loop + vertex 730.053 359.219 38.8942 + vertex 725.714 358.74 39.4645 + vertex 731.713 345.945 38.9235 + endloop + endfacet + facet normal 0.12914 0.0108764 0.991567 + outer loop + vertex 730.053 359.219 38.8942 + vertex 724.474 372.435 39.4758 + vertex 725.714 358.74 39.4645 + endloop + endfacet + facet normal 0.140091 0.0155674 0.990016 + outer loop + vertex 728.542 372.642 38.8968 + vertex 724.474 372.435 39.4758 + vertex 730.053 359.219 38.8942 + endloop + endfacet + facet normal 0.140801 0.00168815 0.990036 + outer loop + vertex 728.542 372.642 38.8968 + vertex 723.539 386.384 39.585 + vertex 724.474 372.435 39.4758 + endloop + endfacet + facet normal 0.162942 0.00992307 0.986586 + outer loop + vertex 727.534 386.309 38.9259 + vertex 723.539 386.384 39.585 + vertex 728.542 372.642 38.8968 + endloop + endfacet + facet normal 0.0747269 0.0107534 0.997146 + outer loop + vertex 740.365 320.956 38.5423 + vertex 735.092 319.6 38.952 + vertex 742.282 308.075 38.5374 + endloop + endfacet + facet normal 0.0749011 0.0100742 0.99714 + outer loop + vertex 740.365 320.956 38.5423 + vertex 733.404 332.754 38.9459 + vertex 735.092 319.6 38.952 + endloop + endfacet + facet normal 0.0775156 0.0116242 0.996923 + outer loop + vertex 738.427 333.837 38.5427 + vertex 733.404 332.754 38.9459 + vertex 740.365 320.956 38.5423 + endloop + endfacet + facet normal 0.0462876 0.00692778 0.998904 + outer loop + vertex 745.735 322.413 38.2833 + vertex 738.427 333.837 38.5427 + vertex 740.365 320.956 38.5423 + endloop + endfacet + facet normal 0.0461883 0.00729443 0.998906 + outer loop + vertex 745.735 322.413 38.2833 + vertex 740.365 320.956 38.5423 + vertex 747.881 309.816 38.276 + endloop + endfacet + facet normal 0.0234945 0.00342833 0.999718 + outer loop + vertex 753.518 311.67 38.1372 + vertex 745.735 322.413 38.2833 + vertex 747.881 309.816 38.276 + endloop + endfacet + facet normal 0.0248702 0.00442554 0.999681 + outer loop + vertex 751.155 323.955 38.1416 + vertex 745.735 322.413 38.2833 + vertex 753.518 311.67 38.1372 + endloop + endfacet + facet normal 0.00938044 0.00144541 0.999955 + outer loop + vertex 759.163 313.623 38.0814 + vertex 751.155 323.955 38.1416 + vertex 753.518 311.67 38.1372 + endloop + endfacet + facet normal 0.00937082 0.00147322 0.999955 + outer loop + vertex 759.163 313.623 38.0814 + vertex 753.518 311.67 38.1372 + vertex 761.659 301.586 38.0758 + endloop + endfacet + facet normal 0.000144263 -0.000440703 1 + outer loop + vertex 767.458 303.961 38.076 + vertex 759.163 313.623 38.0814 + vertex 761.659 301.586 38.0758 + endloop + endfacet + facet normal 0.000209788 -0.000384449 1 + outer loop + vertex 764.796 315.665 38.081 + vertex 759.163 313.623 38.0814 + vertex 767.458 303.961 38.076 + endloop + endfacet + facet normal -0.00798538 -0.00224807 0.999966 + outer loop + vertex 773.194 306.421 38.1273 + vertex 764.796 315.665 38.081 + vertex 767.458 303.961 38.076 + endloop + endfacet + facet normal -0.00782398 -0.0026243 0.999966 + outer loop + vertex 773.194 306.421 38.1273 + vertex 767.458 303.961 38.076 + vertex 775.91 294.907 38.1183 + endloop + endfacet + facet normal -0.0198329 -0.00545675 0.999788 + outer loop + vertex 781.659 297.784 38.2481 + vertex 773.194 306.421 38.1273 + vertex 775.91 294.907 38.1183 + endloop + endfacet + facet normal -0.0203103 -0.00592485 0.999776 + outer loop + vertex 778.831 308.955 38.2569 + vertex 773.194 306.421 38.1273 + vertex 781.659 297.784 38.2481 + endloop + endfacet + facet normal -0.0409764 -0.011156 0.999098 + outer loop + vertex 787.256 300.744 38.5107 + vertex 778.831 308.955 38.2569 + vertex 781.659 297.784 38.2481 + endloop + endfacet + facet normal -0.0413093 -0.0105259 0.999091 + outer loop + vertex 787.256 300.744 38.5107 + vertex 781.659 297.784 38.2481 + vertex 790.057 289.681 38.5099 + endloop + endfacet + facet normal -0.0755005 -0.019182 0.996961 + outer loop + vertex 795.546 293.08 38.9911 + vertex 787.256 300.744 38.5107 + vertex 790.057 289.681 38.5099 + endloop + endfacet + facet normal -0.0757082 -0.019408 0.996941 + outer loop + vertex 792.669 303.798 38.9812 + vertex 787.256 300.744 38.5107 + vertex 795.546 293.08 38.9911 + endloop + endfacet + facet normal -0.125884 -0.0328816 0.9915 + outer loop + vertex 800.806 296.569 39.7746 + vertex 792.669 303.798 38.9812 + vertex 795.546 293.08 38.9911 + endloop + endfacet + facet normal -0.128158 -0.0294112 0.991318 + outer loop + vertex 800.806 296.569 39.7746 + vertex 795.546 293.08 38.9911 + vertex 803.547 285.832 39.8104 + endloop + endfacet + facet normal -0.127576 -0.0287581 0.991412 + outer loop + vertex 803.547 285.832 39.8104 + vertex 795.546 293.08 38.9911 + vertex 798.231 282.021 39.0159 + endloop + endfacet + facet normal -0.126562 -0.0336569 0.991388 + outer loop + vertex 797.871 306.931 39.7517 + vertex 792.669 303.798 38.9812 + vertex 800.806 296.569 39.7746 + endloop + endfacet + facet normal -0.125053 -0.0361866 0.99149 + outer loop + vertex 797.871 306.931 39.7517 + vertex 789.666 314.254 38.9841 + vertex 792.669 303.798 38.9812 + endloop + endfacet + facet normal -0.0757761 -0.022038 0.996881 + outer loop + vertex 789.666 314.254 38.9841 + vertex 784.332 311.564 38.5192 + vertex 792.669 303.798 38.9812 + endloop + endfacet + facet normal -0.0758029 -0.0219846 0.99688 + outer loop + vertex 789.666 314.254 38.9841 + vertex 781.316 322.204 38.5245 + vertex 784.332 311.564 38.5192 + endloop + endfacet + facet normal -0.0426888 -0.0126018 0.999009 + outer loop + vertex 781.316 322.204 38.5245 + vertex 775.91 319.965 38.2653 + vertex 784.332 311.564 38.5192 + endloop + endfacet + facet normal -0.0419957 -0.0119058 0.999047 + outer loop + vertex 784.332 311.564 38.5192 + vertex 775.91 319.965 38.2653 + vertex 778.831 308.955 38.2569 + endloop + endfacet + facet normal -0.0213077 -0.00641763 0.999752 + outer loop + vertex 775.91 319.965 38.2653 + vertex 770.391 317.785 38.1337 + vertex 778.831 308.955 38.2569 + endloop + endfacet + facet normal -0.0215942 -0.00569196 0.999751 + outer loop + vertex 775.91 319.965 38.2653 + vertex 767.516 329.049 38.1357 + vertex 770.391 317.785 38.1337 + endloop + endfacet + facet normal -0.00887734 -0.00244606 0.999958 + outer loop + vertex 767.516 329.049 38.1357 + vertex 762.068 327.288 38.083 + vertex 770.391 317.785 38.1337 + endloop + endfacet + facet normal -0.00857736 -0.0021833 0.999961 + outer loop + vertex 770.391 317.785 38.1337 + vertex 762.068 327.288 38.083 + vertex 764.796 315.665 38.081 + endloop + endfacet + facet normal 0.000258937 -0.000109243 1 + outer loop + vertex 762.068 327.288 38.083 + vertex 756.606 325.585 38.0842 + vertex 764.796 315.665 38.081 + endloop + endfacet + facet normal 0.000212144 4.08988e-05 1 + outer loop + vertex 762.068 327.288 38.083 + vertex 754.001 337.515 38.0843 + vertex 756.606 325.585 38.0842 + endloop + endfacet + facet normal 0.0106627 0.00232344 0.99994 + outer loop + vertex 754.001 337.515 38.0843 + vertex 748.752 336.221 38.1433 + vertex 756.606 325.585 38.0842 + endloop + endfacet + facet normal 0.00998045 0.00181952 0.999949 + outer loop + vertex 756.606 325.585 38.0842 + vertex 748.752 336.221 38.1433 + vertex 751.155 323.955 38.1416 + endloop + endfacet + facet normal 0.025903 0.00493918 0.999652 + outer loop + vertex 748.752 336.221 38.1433 + vertex 743.552 334.991 38.2841 + vertex 751.155 323.955 38.1416 + endloop + endfacet + facet normal 0.0259061 0.00492641 0.999652 + outer loop + vertex 748.752 336.221 38.1433 + vertex 741.354 347.599 38.2789 + vertex 743.552 334.991 38.2841 + endloop + endfacet + facet normal 0.0494948 0.0090397 0.998733 + outer loop + vertex 741.354 347.599 38.2789 + vertex 736.473 346.743 38.5286 + vertex 743.552 334.991 38.2841 + endloop + endfacet + facet normal 0.0484976 0.00843788 0.998788 + outer loop + vertex 743.552 334.991 38.2841 + vertex 736.473 346.743 38.5286 + vertex 738.427 333.837 38.5427 + endloop + endfacet + facet normal 0.0804831 0.0132794 0.996668 + outer loop + vertex 736.473 346.743 38.5286 + vertex 731.713 345.945 38.9235 + vertex 738.427 333.837 38.5427 + endloop + endfacet + facet normal 0.0806485 0.0122921 0.996667 + outer loop + vertex 736.473 346.743 38.5286 + vertex 730.053 359.219 38.8942 + vertex 731.713 345.945 38.9235 + endloop + endfacet + facet normal 0.083292 0.0136594 0.996432 + outer loop + vertex 734.546 359.732 38.5116 + vertex 730.053 359.219 38.8942 + vertex 736.473 346.743 38.5286 + endloop + endfacet + facet normal 0.0837979 0.00923313 0.99644 + outer loop + vertex 734.546 359.732 38.5116 + vertex 728.542 372.642 38.8968 + vertex 730.053 359.219 38.8942 + endloop + endfacet + facet normal 0.0892435 0.0117802 0.99594 + outer loop + vertex 732.797 372.868 38.5129 + vertex 728.542 372.642 38.8968 + vertex 734.546 359.732 38.5116 + endloop + endfacet + facet normal 0.0507849 0.00665925 0.998687 + outer loop + vertex 739.172 360.281 38.2727 + vertex 732.797 372.868 38.5129 + vertex 734.546 359.732 38.5116 + endloop + endfacet + facet normal 0.0504856 0.00917721 0.998683 + outer loop + vertex 739.172 360.281 38.2727 + vertex 734.546 359.732 38.5116 + vertex 741.354 347.599 38.2789 + endloop + endfacet + facet normal 0.0265773 0.00506524 0.999634 + outer loop + vertex 746.326 348.511 38.1421 + vertex 739.172 360.281 38.2727 + vertex 741.354 347.599 38.2789 + endloop + endfacet + facet normal 0.0268542 0.00523364 0.999626 + outer loop + vertex 743.911 360.869 38.1423 + vertex 739.172 360.281 38.2727 + vertex 746.326 348.511 38.1421 + endloop + endfacet + facet normal 0.0109899 0.00213435 0.999937 + outer loop + vertex 751.369 349.468 38.0846 + vertex 743.911 360.869 38.1423 + vertex 746.326 348.511 38.1421 + endloop + endfacet + facet normal 0.0109432 0.00238067 0.999937 + outer loop + vertex 751.369 349.468 38.0846 + vertex 746.326 348.511 38.1421 + vertex 754.001 337.515 38.0843 + endloop + endfacet + facet normal 0.000288397 3.50854e-05 1 + outer loop + vertex 759.286 338.867 38.0827 + vertex 751.369 349.468 38.0846 + vertex 754.001 337.515 38.0843 + endloop + endfacet + facet normal 7.57645e-05 -0.000123706 1 + outer loop + vertex 756.471 350.465 38.0844 + vertex 751.369 349.468 38.0846 + vertex 759.286 338.867 38.0827 + endloop + endfacet + facet normal -0.00984302 -0.00253101 0.999948 + outer loop + vertex 764.584 340.276 38.1385 + vertex 756.471 350.465 38.0844 + vertex 759.286 338.867 38.0827 + endloop + endfacet + facet normal -0.00977189 -0.00279845 0.999948 + outer loop + vertex 764.584 340.276 38.1385 + vertex 759.286 338.867 38.0827 + vertex 767.516 329.049 38.1357 + endloop + endfacet + facet normal -0.0226803 -0.00616924 0.999724 + outer loop + vertex 772.913 330.865 38.2693 + vertex 764.584 340.276 38.1385 + vertex 767.516 329.049 38.1357 + endloop + endfacet + facet normal -0.0239411 -0.00728549 0.999687 + outer loop + vertex 769.853 341.716 38.2751 + vertex 764.584 340.276 38.1385 + vertex 772.913 330.865 38.2693 + endloop + endfacet + facet normal -0.0454468 -0.0133509 0.998878 + outer loop + vertex 778.217 332.737 38.5357 + vertex 769.853 341.716 38.2751 + vertex 772.913 330.865 38.2693 + endloop + endfacet + facet normal -0.0451022 -0.0143274 0.99888 + outer loop + vertex 778.217 332.737 38.5357 + vertex 772.913 330.865 38.2693 + vertex 781.316 322.204 38.5245 + endloop + endfacet + facet normal -0.0782562 -0.0240821 0.996642 + outer loop + vertex 786.569 324.526 38.993 + vertex 778.217 332.737 38.5357 + vertex 781.316 322.204 38.5245 + endloop + endfacet + facet normal -0.0798269 -0.025689 0.996478 + outer loop + vertex 783.392 334.668 39 + vertex 778.217 332.737 38.5357 + vertex 786.569 324.526 38.993 + endloop + endfacet + facet normal -0.0801332 -0.0248674 0.996474 + outer loop + vertex 783.392 334.668 39 + vertex 775.052 343.2 38.5423 + vertex 778.217 332.737 38.5357 + endloop + endfacet + facet normal -0.0831439 -0.0278275 0.996149 + outer loop + vertex 780.141 344.746 39.0102 + vertex 775.052 343.2 38.5423 + vertex 783.392 334.668 39 + endloop + endfacet + facet normal -0.0836097 -0.0262957 0.996152 + outer loop + vertex 780.141 344.746 39.0102 + vertex 771.835 353.665 38.5485 + vertex 775.052 343.2 38.5423 + endloop + endfacet + facet normal -0.0493876 -0.0157745 0.998655 + outer loop + vertex 771.835 353.665 38.5485 + vertex 766.746 352.56 38.2794 + vertex 775.052 343.2 38.5423 + endloop + endfacet + facet normal -0.0473393 -0.0139531 0.998781 + outer loop + vertex 775.052 343.2 38.5423 + vertex 766.746 352.56 38.2794 + vertex 769.853 341.716 38.2751 + endloop + endfacet + facet normal -0.0252928 -0.00763793 0.999651 + outer loop + vertex 766.746 352.56 38.2794 + vertex 761.61 351.499 38.1413 + vertex 769.853 341.716 38.2751 + endloop + endfacet + facet normal -0.0253769 -0.00723104 0.999652 + outer loop + vertex 766.746 352.56 38.2794 + vertex 758.636 362.788 38.1475 + vertex 761.61 351.499 38.1413 + endloop + endfacet + facet normal -0.0111602 -0.00348639 0.999932 + outer loop + vertex 758.636 362.788 38.1475 + vertex 753.659 362.124 38.0896 + vertex 761.61 351.499 38.1413 + endloop + endfacet + facet normal -0.0104788 -0.00297648 0.999941 + outer loop + vertex 761.61 351.499 38.1413 + vertex 753.659 362.124 38.0896 + vertex 756.471 350.465 38.0844 + endloop + endfacet + facet normal -0.000382302 -0.000541414 1 + outer loop + vertex 753.659 362.124 38.0896 + vertex 748.742 361.482 38.0874 + vertex 756.471 350.465 38.0844 + endloop + endfacet + facet normal -0.000279331 -0.00132917 0.999999 + outer loop + vertex 753.659 362.124 38.0896 + vertex 746.284 373.63 38.1029 + vertex 748.742 361.482 38.0874 + endloop + endfacet + facet normal 0.010891 0.000930657 0.99994 + outer loop + vertex 746.284 373.63 38.1029 + vertex 741.67 373.365 38.1534 + vertex 748.742 361.482 38.0874 + endloop + endfacet + facet normal 0.0112185 0.00112561 0.999936 + outer loop + vertex 748.742 361.482 38.0874 + vertex 741.67 373.365 38.1534 + vertex 743.911 360.869 38.1423 + endloop + endfacet + facet normal 0.0275342 0.00405257 0.999613 + outer loop + vertex 741.67 373.365 38.1534 + vertex 737.165 373.106 38.2785 + vertex 743.911 360.869 38.1423 + endloop + endfacet + facet normal 0.0276184 0.00258973 0.999615 + outer loop + vertex 741.67 373.365 38.1534 + vertex 735.626 386.149 38.2872 + vertex 737.165 373.106 38.2785 + endloop + endfacet + facet normal 0.0565227 0.00600186 0.998383 + outer loop + vertex 735.626 386.149 38.2872 + vertex 731.559 386.23 38.517 + vertex 737.165 373.106 38.2785 + endloop + endfacet + facet normal 0.0533399 0.00463892 0.998566 + outer loop + vertex 737.165 373.106 38.2785 + vertex 731.559 386.23 38.517 + vertex 732.797 372.868 38.5129 + endloop + endfacet + facet normal 0.101253 0.0090795 0.994819 + outer loop + vertex 731.559 386.23 38.517 + vertex 727.534 386.309 38.9259 + vertex 732.797 372.868 38.5129 + endloop + endfacet + facet normal 0.0255456 0.00160913 0.999672 + outer loop + vertex 739.917 386.061 38.1777 + vertex 735.626 386.149 38.2872 + vertex 741.67 373.365 38.1534 + endloop + endfacet + facet normal 0.0109676 -0.00040466 0.99994 + outer loop + vertex 746.284 373.63 38.1029 + vertex 739.917 386.061 38.1777 + vertex 741.67 373.365 38.1534 + endloop + endfacet + facet normal 0.00701355 -0.00243039 0.999972 + outer loop + vertex 744.286 385.97 38.1469 + vertex 739.917 386.061 38.1777 + vertex 746.284 373.63 38.1029 + endloop + endfacet + facet normal -0.000468758 -0.00364249 0.999993 + outer loop + vertex 751.01 373.907 38.1061 + vertex 744.286 385.97 38.1469 + vertex 746.284 373.63 38.1029 + endloop + endfacet + facet normal 0.000118069 -0.00331538 0.999994 + outer loop + vertex 748.869 385.873 38.146 + vertex 744.286 385.97 38.1469 + vertex 751.01 373.907 38.1061 + endloop + endfacet + facet normal -0.0103572 -0.00518892 0.999933 + outer loop + vertex 755.818 374.189 38.1573 + vertex 748.869 385.873 38.146 + vertex 751.01 373.907 38.1061 + endloop + endfacet + facet normal -0.0104593 -0.00345044 0.999939 + outer loop + vertex 755.818 374.189 38.1573 + vertex 751.01 373.907 38.1061 + vertex 758.636 362.788 38.1475 + endloop + endfacet + facet normal -0.0259521 -0.00728009 0.999637 + outer loop + vertex 763.629 363.464 38.282 + vertex 755.818 374.189 38.1573 + vertex 758.636 362.788 38.1475 + endloop + endfacet + facet normal -0.0245976 -0.00629316 0.999678 + outer loop + vertex 760.685 374.484 38.279 + vertex 755.818 374.189 38.1573 + vertex 763.629 363.464 38.282 + endloop + endfacet + facet normal -0.0495503 -0.0129587 0.998688 + outer loop + vertex 768.604 364.179 38.5382 + vertex 760.685 374.484 38.279 + vertex 763.629 363.464 38.282 + endloop + endfacet + facet normal -0.0493729 -0.0141897 0.99868 + outer loop + vertex 768.604 364.179 38.5382 + vertex 763.629 363.464 38.282 + vertex 771.835 353.665 38.5485 + endloop + endfacet + facet normal -0.0857104 -0.0253565 0.995997 + outer loop + vertex 776.832 354.816 39.0079 + vertex 768.604 364.179 38.5382 + vertex 771.835 353.665 38.5485 + endloop + endfacet + facet normal -0.0840703 -0.0239064 0.996173 + outer loop + vertex 773.507 364.922 38.9697 + vertex 768.604 364.179 38.5382 + vertex 776.832 354.816 39.0079 + endloop + endfacet + facet normal -0.0843669 -0.0219595 0.996193 + outer loop + vertex 773.507 364.922 38.9697 + vertex 765.54 374.793 38.5127 + vertex 768.604 364.179 38.5382 + endloop + endfacet + facet normal -0.0859344 -0.0232321 0.99603 + outer loop + vertex 770.379 375.125 38.9379 + vertex 765.54 374.793 38.5127 + vertex 773.507 364.922 38.9697 + endloop + endfacet + facet normal -0.0860368 -0.0217701 0.996054 + outer loop + vertex 770.379 375.125 38.9379 + vertex 762.992 385.567 38.528 + vertex 765.54 374.793 38.5127 + endloop + endfacet + facet normal -0.0531921 -0.0140048 0.998486 + outer loop + vertex 762.992 385.567 38.528 + vertex 758.394 385.668 38.2845 + vertex 765.54 374.793 38.5127 + endloop + endfacet + facet normal -0.0474245 -0.0102074 0.998823 + outer loop + vertex 765.54 374.793 38.5127 + vertex 758.394 385.668 38.2845 + vertex 760.685 374.484 38.279 + endloop + endfacet + facet normal -0.023121 -0.00522864 0.999719 + outer loop + vertex 758.394 385.668 38.2845 + vertex 753.509 385.774 38.1721 + vertex 760.685 374.484 38.279 + endloop + endfacet + facet normal -0.0987444 -0.0308161 0.994636 + outer loop + vertex 768.045 385.454 39.0261 + vertex 762.992 385.567 38.528 + vertex 770.379 375.125 38.9379 + endloop + endfacet + facet normal -0.0473565 -0.0112695 0.998814 + outer loop + vertex 765.54 374.793 38.5127 + vertex 760.685 374.484 38.279 + vertex 768.604 364.179 38.5382 + endloop + endfacet + facet normal -0.0246049 -0.00617219 0.999678 + outer loop + vertex 760.685 374.484 38.279 + vertex 753.509 385.774 38.1721 + vertex 755.818 374.189 38.1573 + endloop + endfacet + facet normal -0.00566452 -0.00239794 0.999981 + outer loop + vertex 753.509 385.774 38.1721 + vertex 748.869 385.873 38.146 + vertex 755.818 374.189 38.1573 + endloop + endfacet + facet normal -0.00059254 -0.00152992 0.999999 + outer loop + vertex 751.01 373.907 38.1061 + vertex 746.284 373.63 38.1029 + vertex 753.659 362.124 38.0896 + endloop + endfacet + facet normal -0.0111058 -0.00389393 0.999931 + outer loop + vertex 758.636 362.788 38.1475 + vertex 751.01 373.907 38.1061 + vertex 753.659 362.124 38.0896 + endloop + endfacet + facet normal -0.0259023 -0.0076478 0.999635 + outer loop + vertex 763.629 363.464 38.282 + vertex 758.636 362.788 38.1475 + vertex 766.746 352.56 38.2794 + endloop + endfacet + facet normal -0.0496768 -0.0144447 0.998661 + outer loop + vertex 771.835 353.665 38.5485 + vertex 763.629 363.464 38.282 + vertex 766.746 352.56 38.2794 + endloop + endfacet + facet normal -0.0851583 -0.0277468 0.995981 + outer loop + vertex 776.832 354.816 39.0079 + vertex 771.835 353.665 38.5485 + vertex 780.141 344.746 39.0102 + endloop + endfacet + facet normal -0.0470769 -0.0148722 0.998781 + outer loop + vertex 775.052 343.2 38.5423 + vertex 769.853 341.716 38.2751 + vertex 778.217 332.737 38.5357 + endloop + endfacet + facet normal -0.0241159 -0.0066458 0.999687 + outer loop + vertex 769.853 341.716 38.2751 + vertex 761.61 351.499 38.1413 + vertex 764.584 340.276 38.1385 + endloop + endfacet + facet normal -0.0104682 -0.00302892 0.999941 + outer loop + vertex 761.61 351.499 38.1413 + vertex 756.471 350.465 38.0844 + vertex 764.584 340.276 38.1385 + endloop + endfacet + facet normal 9.23194e-05 -0.000208431 1 + outer loop + vertex 756.471 350.465 38.0844 + vertex 748.742 361.482 38.0874 + vertex 751.369 349.468 38.0846 + endloop + endfacet + facet normal 0.011083 0.00219523 0.999936 + outer loop + vertex 748.742 361.482 38.0874 + vertex 743.911 360.869 38.1423 + vertex 751.369 349.468 38.0846 + endloop + endfacet + facet normal 0.027035 0.00377723 0.999627 + outer loop + vertex 743.911 360.869 38.1423 + vertex 737.165 373.106 38.2785 + vertex 739.172 360.281 38.2727 + endloop + endfacet + facet normal 0.0531634 0.0078665 0.998555 + outer loop + vertex 737.165 373.106 38.2785 + vertex 732.797 372.868 38.5129 + vertex 739.172 360.281 38.2727 + endloop + endfacet + facet normal 0.0896329 0.00449454 0.995965 + outer loop + vertex 732.797 372.868 38.5129 + vertex 727.534 386.309 38.9259 + vertex 728.542 372.642 38.8968 + endloop + endfacet + facet normal 0.0495617 0.00865786 0.998734 + outer loop + vertex 741.354 347.599 38.2789 + vertex 734.546 359.732 38.5116 + vertex 736.473 346.743 38.5286 + endloop + endfacet + facet normal 0.0265285 0.00533135 0.999634 + outer loop + vertex 746.326 348.511 38.1421 + vertex 741.354 347.599 38.2789 + vertex 748.752 336.221 38.1433 + endloop + endfacet + facet normal 0.0106919 0.00220523 0.99994 + outer loop + vertex 754.001 337.515 38.0843 + vertex 746.326 348.511 38.1421 + vertex 748.752 336.221 38.1433 + endloop + endfacet + facet normal 0.000274352 8.997e-05 1 + outer loop + vertex 759.286 338.867 38.0827 + vertex 754.001 337.515 38.0843 + vertex 762.068 327.288 38.083 + endloop + endfacet + facet normal -0.00897848 -0.0021333 0.999957 + outer loop + vertex 767.516 329.049 38.1357 + vertex 759.286 338.867 38.0827 + vertex 762.068 327.288 38.083 + endloop + endfacet + facet normal -0.0225452 -0.006571 0.999724 + outer loop + vertex 772.913 330.865 38.2693 + vertex 767.516 329.049 38.1357 + vertex 775.91 319.965 38.2653 + endloop + endfacet + facet normal -0.0428719 -0.0121595 0.999007 + outer loop + vertex 781.316 322.204 38.5245 + vertex 772.913 330.865 38.2693 + vertex 775.91 319.965 38.2653 + endloop + endfacet + facet normal -0.0781076 -0.0244189 0.996646 + outer loop + vertex 786.569 324.526 38.993 + vertex 781.316 322.204 38.5245 + vertex 789.666 314.254 38.9841 + endloop + endfacet + facet normal -0.12675 -0.0381169 0.991202 + outer loop + vertex 794.807 317.012 39.7476 + vertex 789.666 314.254 38.9841 + vertex 797.871 306.931 39.7517 + endloop + endfacet + facet normal -0.126306 -0.0389498 0.991226 + outer loop + vertex 794.807 317.012 39.7476 + vertex 786.569 324.526 38.993 + vertex 789.666 314.254 38.9841 + endloop + endfacet + facet normal -0.128523 -0.0414189 0.990841 + outer loop + vertex 791.649 326.898 39.7512 + vertex 786.569 324.526 38.993 + vertex 794.807 317.012 39.7476 + endloop + endfacet + facet normal -0.128718 -0.0409997 0.990833 + outer loop + vertex 791.649 326.898 39.7512 + vertex 783.392 334.668 39 + vertex 786.569 324.526 38.993 + endloop + endfacet + facet normal -0.13213 -0.0446851 0.990225 + outer loop + vertex 788.406 336.654 39.7588 + vertex 783.392 334.668 39 + vertex 791.649 326.898 39.7512 + endloop + endfacet + facet normal -0.132502 -0.0437428 0.990217 + outer loop + vertex 788.406 336.654 39.7588 + vertex 780.141 344.746 39.0102 + vertex 783.392 334.668 39 + endloop + endfacet + facet normal -0.136032 -0.0474078 0.98957 + outer loop + vertex 785.086 346.338 39.7662 + vertex 780.141 344.746 39.0102 + vertex 788.406 336.654 39.7588 + endloop + endfacet + facet normal -0.13689 -0.0447448 0.989575 + outer loop + vertex 785.086 346.338 39.7662 + vertex 776.832 354.816 39.0079 + vertex 780.141 344.746 39.0102 + endloop + endfacet + facet normal -0.138387 -0.0462274 0.989299 + outer loop + vertex 781.706 356.001 39.7449 + vertex 776.832 354.816 39.0079 + vertex 785.086 346.338 39.7662 + endloop + endfacet + facet normal -0.139388 -0.0421366 0.989341 + outer loop + vertex 781.706 356.001 39.7449 + vertex 773.507 364.922 38.9697 + vertex 776.832 354.816 39.0079 + endloop + endfacet + facet normal -0.139863 -0.0425804 0.989255 + outer loop + vertex 778.321 365.69 39.6834 + vertex 773.507 364.922 38.9697 + vertex 781.706 356.001 39.7449 + endloop + endfacet + facet normal -0.140296 -0.0399146 0.989305 + outer loop + vertex 778.321 365.69 39.6834 + vertex 770.379 375.125 38.9379 + vertex 773.507 364.922 38.9697 + endloop + endfacet + facet normal -0.147454 -0.0460423 0.987997 + outer loop + vertex 775.153 375.453 39.6657 + vertex 770.379 375.125 38.9379 + vertex 778.321 365.69 39.6834 + endloop + endfacet + facet normal -0.147764 -0.04184 0.988137 + outer loop + vertex 775.153 375.453 39.6657 + vertex 768.045 385.454 39.0261 + vertex 770.379 375.125 38.9379 + endloop + endfacet + facet normal -0.16011 -0.0507662 0.985793 + outer loop + vertex 772.465 385.352 39.7387 + vertex 768.045 385.454 39.0261 + vertex 775.153 375.453 39.6657 + endloop + endfacet + facet normal -0.0748137 -0.0209991 0.996976 + outer loop + vertex 792.669 303.798 38.9812 + vertex 784.332 311.564 38.5192 + vertex 787.256 300.744 38.5107 + endloop + endfacet + facet normal -0.0419008 -0.012106 0.999048 + outer loop + vertex 784.332 311.564 38.5192 + vertex 778.831 308.955 38.2569 + vertex 787.256 300.744 38.5107 + endloop + endfacet + facet normal -0.0204552 -0.00560248 0.999775 + outer loop + vertex 778.831 308.955 38.2569 + vertex 770.391 317.785 38.1337 + vertex 773.194 306.421 38.1273 + endloop + endfacet + facet normal -0.00840754 -0.00263158 0.999961 + outer loop + vertex 770.391 317.785 38.1337 + vertex 764.796 315.665 38.081 + vertex 773.194 306.421 38.1273 + endloop + endfacet + facet normal 0.000144325 -0.000203866 1 + outer loop + vertex 764.796 315.665 38.081 + vertex 756.606 325.585 38.0842 + vertex 759.163 313.623 38.0814 + endloop + endfacet + facet normal 0.00995836 0.00189337 0.999949 + outer loop + vertex 756.606 325.585 38.0842 + vertex 751.155 323.955 38.1416 + vertex 759.163 313.623 38.0814 + endloop + endfacet + facet normal 0.0249174 0.00425978 0.99968 + outer loop + vertex 751.155 323.955 38.1416 + vertex 743.552 334.991 38.2841 + vertex 745.735 322.413 38.2833 + endloop + endfacet + facet normal 0.048516 0.00835591 0.998787 + outer loop + vertex 743.552 334.991 38.2841 + vertex 738.427 333.837 38.5427 + vertex 745.735 322.413 38.2833 + endloop + endfacet + facet normal 0.0775153 0.0116257 0.996923 + outer loop + vertex 738.427 333.837 38.5427 + vertex 731.713 345.945 38.9235 + vertex 733.404 332.754 38.9459 + endloop + endfacet + facet normal 0.0446871 0.00627977 0.998981 + outer loop + vertex 747.881 309.816 38.276 + vertex 740.365 320.956 38.5423 + vertex 742.282 308.075 38.5374 + endloop + endfacet + facet normal 0.023363 0.00382822 0.99972 + outer loop + vertex 753.518 311.67 38.1372 + vertex 747.881 309.816 38.276 + vertex 755.828 299.319 38.1305 + endloop + endfacet + facet normal 0.00894845 0.00113219 0.999959 + outer loop + vertex 761.659 301.586 38.0758 + vertex 753.518 311.67 38.1372 + vertex 755.828 299.319 38.1305 + endloop + endfacet + facet normal 0.000195007 -0.000564636 1 + outer loop + vertex 767.458 303.961 38.076 + vertex 761.659 301.586 38.0758 + vertex 770.039 292.117 38.0688 + endloop + endfacet + facet normal -0.00738737 -0.00221673 0.99997 + outer loop + vertex 775.91 294.907 38.1183 + vertex 767.458 303.961 38.076 + vertex 770.039 292.117 38.0688 + endloop + endfacet + facet normal -0.0199913 -0.00514028 0.999787 + outer loop + vertex 781.659 297.784 38.2481 + vertex 775.91 294.907 38.1183 + vertex 784.366 286.385 38.2436 + endloop + endfacet + facet normal -0.040905 -0.0101062 0.999112 + outer loop + vertex 790.057 289.681 38.5099 + vertex 781.659 297.784 38.2481 + vertex 784.366 286.385 38.2436 + endloop + endfacet + facet normal -0.0771539 -0.0165011 0.996883 + outer loop + vertex 795.546 293.08 38.9911 + vertex 790.057 289.681 38.5099 + vertex 798.231 282.021 39.0159 + endloop + endfacet + facet normal -0.129885 -0.0254931 0.991201 + outer loop + vertex 803.547 285.832 39.8104 + vertex 798.231 282.021 39.0159 + vertex 805.99 274.645 39.8429 + endloop + endfacet + facet normal -0.078032 -0.0138412 0.996855 + outer loop + vertex 800.63 270.56 39.0417 + vertex 792.665 278.307 38.5258 + vertex 794.998 266.566 38.5453 + endloop + endfacet + facet normal -0.0428262 -0.00684359 0.999059 + outer loop + vertex 792.665 278.307 38.5258 + vertex 786.887 274.7 38.2534 + vertex 794.998 266.566 38.5453 + endloop + endfacet + facet normal -0.019807 -0.00323143 0.999799 + outer loop + vertex 786.887 274.7 38.2534 + vertex 778.506 283.184 38.1148 + vertex 780.923 271.198 38.1239 + endloop + endfacet + facet normal -0.00771095 -0.000791898 0.99997 + outer loop + vertex 778.506 283.184 38.1148 + vertex 772.508 280.081 38.0661 + vertex 780.923 271.198 38.1239 + endloop + endfacet + facet normal 0.000230476 -0.000157573 1 + outer loop + vertex 772.508 280.081 38.0661 + vertex 764.084 289.427 38.0695 + vertex 766.407 277.089 38.067 + endloop + endfacet + facet normal 0.0082308 0.00134882 0.999965 + outer loop + vertex 764.084 289.427 38.0695 + vertex 758.075 286.851 38.1224 + vertex 766.407 277.089 38.067 + endloop + endfacet + facet normal 0.0215401 0.00271205 0.999764 + outer loop + vertex 758.075 286.851 38.1224 + vertex 749.986 297.168 38.2687 + vertex 752.034 284.412 38.2592 + endloop + endfacet + facet normal 0.0420689 0.00600851 0.999097 + outer loop + vertex 749.986 297.168 38.2687 + vertex 744.158 295.139 38.5263 + vertex 752.034 284.412 38.2592 + endloop + endfacet + facet normal 0.069428 0.00791104 0.997556 + outer loop + vertex 744.158 295.139 38.5263 + vertex 736.768 306.451 38.9509 + vertex 738.409 293.256 38.9413 + endloop + endfacet + facet normal 0.103871 0.010798 0.994532 + outer loop + vertex 738.409 293.256 38.9413 + vertex 731.401 304.95 39.5463 + vertex 732.811 291.519 39.5448 + endloop + endfacet + facet normal 0.0640074 0.00723786 0.997923 + outer loop + vertex 747.766 268.961 38.5182 + vertex 740.024 279.98 38.9349 + vertex 741.577 266.56 38.9326 + endloop + endfacet + facet normal 0.0393393 0.00525444 0.999212 + outer loop + vertex 754.005 271.52 38.2591 + vertex 745.997 282.118 38.5187 + vertex 747.766 268.961 38.5182 + endloop + endfacet + facet normal 0.0201601 0.00422692 0.999788 + outer loop + vertex 760.23 274.233 38.1221 + vertex 754.005 271.52 38.2591 + vertex 762.237 261.423 38.1358 + endloop + endfacet + facet normal 0.00763389 0.00226491 0.999968 + outer loop + vertex 768.564 264.545 38.0805 + vertex 760.23 274.233 38.1221 + vertex 762.237 261.423 38.1358 + endloop + endfacet + facet normal -0.000247392 0.00157013 0.999999 + outer loop + vertex 774.804 267.807 38.0769 + vertex 768.564 264.545 38.0805 + vertex 776.841 255.252 38.0971 + endloop + endfacet + facet normal -0.00758248 0.00037995 0.999971 + outer loop + vertex 783.068 258.898 38.1429 + vertex 774.804 267.807 38.0769 + vertex 776.841 255.252 38.0971 + endloop + endfacet + facet normal -0.0187482 -0.00397842 0.999816 + outer loop + vertex 789.135 262.674 38.2717 + vertex 783.068 258.898 38.1429 + vertex 791.035 250.286 38.2581 + endloop + endfacet + facet normal -0.0410696 -0.00740207 0.999129 + outer loop + vertex 796.967 254.445 38.5327 + vertex 789.135 262.674 38.2717 + vertex 791.035 250.286 38.2581 + endloop + endfacet + facet normal -0.0711082 -0.0210424 0.997247 + outer loop + vertex 802.643 258.703 39.0273 + vertex 796.967 254.445 38.5327 + vertex 804.284 246.592 38.8887 + endloop + endfacet + facet normal -0.105083 -0.0443873 0.993472 + outer loop + vertex 809.655 251.111 39.6587 + vertex 804.284 246.592 38.8887 + vertex 810.967 239.427 39.2755 + endloop + endfacet + facet normal -0.0543879 -0.0340177 0.99794 + outer loop + vertex 805.685 234.561 38.532 + vertex 798.591 242.069 38.4013 + vertex 799.916 229.926 38.0596 + endloop + endfacet + facet normal -0.0222806 -0.0297047 0.99931 + outer loop + vertex 799.916 229.926 38.0596 + vertex 792.612 237.68 38.1273 + vertex 793.933 225.366 37.7907 + endloop + endfacet + facet normal 0.0157551 -0.0479415 0.998726 + outer loop + vertex 795.017 214.242 37.222 + vertex 787.717 220.975 37.6604 + vertex 788.751 209.691 37.1024 + endloop + endfacet + facet normal -0.00232546 -0.0275719 0.999617 + outer loop + vertex 792.612 237.68 38.1273 + vertex 786.42 233.45 37.9962 + vertex 793.933 225.366 37.7907 + endloop + endfacet + facet normal 0.00989296 -0.0255674 0.999624 + outer loop + vertex 787.717 220.975 37.6604 + vertex 780.053 229.392 37.9515 + vertex 781.314 216.77 37.6162 + endloop + endfacet + facet normal -0.000690516 -0.0103609 0.999946 + outer loop + vertex 784.896 246.263 38.1279 + vertex 778.583 242.393 38.0834 + vertex 786.42 233.45 37.9962 + endloop + endfacet + facet normal 0.00143706 -0.000757889 0.999999 + outer loop + vertex 778.583 242.393 38.0834 + vertex 770.485 251.747 38.1022 + vertex 772.131 238.682 38.0899 + endloop + endfacet + facet normal 0.00886045 0.000177649 0.999961 + outer loop + vertex 770.485 251.747 38.1022 + vertex 764.022 248.389 38.16 + vertex 772.131 238.682 38.0899 + endloop + endfacet + facet normal 0.0189444 0.00415359 0.999812 + outer loop + vertex 764.022 248.389 38.16 + vertex 755.84 258.45 38.2733 + vertex 757.478 245.172 38.2974 + endloop + endfacet + facet normal 0.0366964 0.00588466 0.999309 + outer loop + vertex 757.478 245.172 38.2974 + vertex 749.413 255.63 38.532 + vertex 750.897 242.119 38.557 + endloop + endfacet + facet normal 0.0599773 0.00742527 0.998172 + outer loop + vertex 750.897 242.119 38.557 + vertex 743.034 252.985 38.9487 + vertex 744.374 239.285 38.97 + endloop + endfacet + facet normal 0.089589 0.00887719 0.995939 + outer loop + vertex 744.374 239.285 38.97 + vertex 736.801 250.546 39.5509 + vertex 738.015 236.725 39.5649 + endloop + endfacet + facet normal 0.13135 0.0113978 0.991271 + outer loop + vertex 738.015 236.725 39.5649 + vertex 730.783 248.333 40.3896 + vertex 731.881 234.445 40.4038 + endloop + endfacet + facet normal 0.0901141 -0.00431033 0.995922 + outer loop + vertex 746.779 211.933 38.8044 + vertex 739.168 222.934 39.5407 + vertex 740.152 209.124 39.3919 + endloop + endfacet + facet normal 0.0618238 -0.00538972 0.998073 + outer loop + vertex 753.471 214.916 38.406 + vertex 745.622 225.549 38.9496 + vertex 746.779 211.933 38.8044 + endloop + endfacet + facet normal 0.040397 -0.00641548 0.999163 + outer loop + vertex 760.2 218.212 38.1551 + vertex 752.229 228.473 38.5432 + vertex 753.471 214.916 38.406 + endloop + endfacet + facet normal 0.024182 -0.00747913 0.99968 + outer loop + vertex 766.911 221.761 38.0193 + vertex 758.91 231.69 38.2871 + vertex 760.2 218.212 38.1551 + endloop + endfacet + facet normal 0.0135366 -0.00832115 0.999874 + outer loop + vertex 773.543 225.496 37.9606 + vertex 765.565 235.113 38.1486 + vertex 766.911 221.761 38.0193 + endloop + endfacet + facet normal 0.01631 -0.0249244 0.999556 + outer loop + vertex 780.053 229.392 37.9515 + vertex 773.543 225.496 37.9606 + vertex 781.314 216.77 37.6162 + endloop + endfacet + facet normal 0.0240881 -0.0471712 0.998596 + outer loop + vertex 787.717 220.975 37.6604 + vertex 781.314 216.77 37.6162 + vertex 788.751 209.691 37.1024 + endloop + endfacet + facet normal 0.030416 -0.0446111 0.998541 + outer loop + vertex 782.314 205.359 37.0677 + vertex 774.772 212.736 37.627 + vertex 775.767 201.242 37.0832 + endloop + endfacet + facet normal 0.0346388 -0.0441398 0.998425 + outer loop + vertex 775.767 201.242 37.0832 + vertex 768.126 208.886 37.6862 + vertex 769.15 197.342 37.1403 + endloop + endfacet + facet normal 0.042391 -0.0440309 0.99813 + outer loop + vertex 769.15 197.342 37.1403 + vertex 761.402 205.266 37.819 + vertex 762.398 193.699 37.2664 + endloop + endfacet + facet normal 0.0555188 -0.0438681 0.997493 + outer loop + vertex 762.398 193.699 37.2664 + vertex 754.607 201.922 38.0617 + vertex 755.443 190.173 37.4985 + endloop + endfacet + facet normal 0.0734779 -0.0447812 0.996291 + outer loop + vertex 755.443 190.173 37.4985 + vertex 747.732 198.7 38.4504 + vertex 748.239 186.352 37.858 + endloop + endfacet + facet normal 0.0991105 -0.0474031 0.993947 + outer loop + vertex 748.239 186.352 37.858 + vertex 740.763 195.277 39.0291 + vertex 740.904 181.305 38.3488 + endloop + endfacet + facet normal 0.158354 -0.153583 0.975365 + outer loop + vertex 739.007 167.037 37.252 + vertex 735.21 165.023 37.5515 + vertex 738.083 163.891 36.9068 + endloop + endfacet + facet normal 0.127158 -0.115977 0.985079 + outer loop + vertex 743.445 170.026 37.0312 + vertex 739.171 172.534 37.8781 + vertex 739.007 167.037 37.252 + endloop + endfacet + facet normal 0.132592 -0.106822 0.985398 + outer loop + vertex 742.975 174.179 37.5446 + vertex 739.171 172.534 37.8781 + vertex 743.445 170.026 37.0312 + endloop + endfacet + facet normal 0.122178 -0.10815 0.986598 + outer loop + vertex 742.975 174.179 37.5446 + vertex 743.445 170.026 37.0312 + vertex 748.044 175.767 37.0909 + endloop + endfacet + facet normal 0.128363 -0.199445 0.971465 + outer loop + vertex 779.7 184.993 35.4656 + vertex 774.602 181.558 35.4341 + vertex 778.464 183.081 35.2363 + endloop + endfacet + facet normal 0.138429 -0.213991 0.966977 + outer loop + vertex 774.602 181.558 35.4341 + vertex 770.688 178.974 35.4224 + vertex 769.972 177.897 35.2866 + endloop + endfacet + facet normal 0.129804 -0.203227 0.970489 + outer loop + vertex 769.972 177.897 35.2866 + vertex 778.464 183.081 35.2363 + vertex 774.602 181.558 35.4341 + endloop + endfacet + facet normal 0.175735 -0.27872 0.944157 + outer loop + vertex 771.336 178.098 35.0921 + vertex 778.464 183.081 35.2363 + vertex 769.972 177.897 35.2866 + endloop + endfacet + facet normal 0.119344 -0.201957 0.972096 + outer loop + vertex 770.688 178.974 35.4224 + vertex 766.104 176.707 35.5143 + vertex 769.972 177.897 35.2866 + endloop + endfacet + facet normal 0.176526 -0.286494 0.941679 + outer loop + vertex 771.336 178.098 35.0921 + vertex 769.972 177.897 35.2866 + vertex 763.084 173.41 35.2128 + endloop + endfacet + facet normal 0.192307 -0.302121 0.933671 + outer loop + vertex 779.333 183.006 35.0331 + vertex 778.464 183.081 35.2363 + vertex 771.336 178.098 35.0921 + endloop + endfacet + facet normal 0.200146 -0.301858 0.932107 + outer loop + vertex 787.005 188.045 35.0177 + vertex 785.966 187.878 35.1864 + vertex 779.333 183.006 35.0331 + endloop + endfacet + facet normal 0.197075 -0.288253 0.937055 + outer loop + vertex 794.53 193.361 35.0703 + vertex 793.434 193.164 35.2403 + vertex 787.005 188.045 35.0177 + endloop + endfacet + facet normal 0.196477 -0.283585 0.938604 + outer loop + vertex 794.53 193.361 35.0703 + vertex 801.037 198.92 35.3877 + vertex 793.434 193.164 35.2403 + endloop + endfacet + facet normal 0.190611 -0.2769 0.941803 + outer loop + vertex 801.735 198.838 35.2222 + vertex 801.037 198.92 35.3877 + vertex 794.53 193.361 35.0703 + endloop + endfacet + facet normal 0.189594 -0.282554 0.940328 + outer loop + vertex 801.735 198.838 35.2222 + vertex 807.593 204.202 35.6531 + vertex 801.037 198.92 35.3877 + endloop + endfacet + facet normal 0.176196 -0.268464 0.947039 + outer loop + vertex 808.56 204.379 35.5235 + vertex 807.593 204.202 35.6531 + vertex 801.735 198.838 35.2222 + endloop + endfacet + facet normal 0.179283 -0.290491 0.939932 + outer loop + vertex 808.56 204.379 35.5235 + vertex 814.261 209.925 36.15 + vertex 807.593 204.202 35.6531 + endloop + endfacet + facet normal 0.154616 -0.266425 0.951374 + outer loop + vertex 815.089 209.965 36.0267 + vertex 814.261 209.925 36.15 + vertex 808.56 204.379 35.5235 + endloop + endfacet + facet normal 0.154749 -0.298525 0.941773 + outer loop + vertex 815.089 209.965 36.0267 + vertex 820.231 215.326 36.8811 + vertex 814.261 209.925 36.15 + endloop + endfacet + facet normal 0.0899854 -0.240345 0.966508 + outer loop + vertex 821.436 215.623 36.8427 + vertex 820.231 215.326 36.8811 + vertex 815.089 209.965 36.0267 + endloop + endfacet + facet normal 0.166194 -0.320928 0.932408 + outer loop + vertex 815.632 208.788 35.5249 + vertex 821.436 215.623 36.8427 + vertex 815.089 209.965 36.0267 + endloop + endfacet + facet normal 0.19466 -0.307389 0.931461 + outer loop + vertex 815.632 208.788 35.5249 + vertex 815.089 209.965 36.0267 + vertex 809.022 203.219 35.0684 + endloop + endfacet + facet normal 0.214381 -0.329807 0.919385 + outer loop + vertex 809.646 200.957 34.1112 + vertex 815.632 208.788 35.5249 + vertex 809.022 203.219 35.0684 + endloop + endfacet + facet normal 0.249619 -0.353512 0.90151 + outer loop + vertex 816.325 206.509 34.4389 + vertex 815.632 208.788 35.5249 + vertex 809.646 200.957 34.1112 + endloop + endfacet + facet normal 0.215755 -0.365671 0.905392 + outer loop + vertex 816.325 206.509 34.4389 + vertex 822.117 214.482 36.2789 + vertex 815.632 208.788 35.5249 + endloop + endfacet + facet normal 0.191786 -0.340372 0.920525 + outer loop + vertex 822.117 214.482 36.2789 + vertex 821.436 215.623 36.8427 + vertex 815.632 208.788 35.5249 + endloop + endfacet + facet normal 0.105406 -0.305555 0.946322 + outer loop + vertex 821.436 215.623 36.8427 + vertex 826.638 221.386 38.1239 + vertex 820.231 215.326 36.8811 + endloop + endfacet + facet normal 0.180895 -0.295928 0.937925 + outer loop + vertex 809.022 203.219 35.0684 + vertex 815.089 209.965 36.0267 + vertex 808.56 204.379 35.5235 + endloop + endfacet + facet normal 0.234518 -0.323166 0.916823 + outer loop + vertex 809.646 200.957 34.1112 + vertex 809.022 203.219 35.0684 + vertex 802.608 195.395 33.9509 + endloop + endfacet +endsolid diff --git a/noether_examples/meshes/outputs/output_15.stl b/noether_examples/meshes/outputs/output_15.stl new file mode 100644 index 00000000..e9def936 --- /dev/null +++ b/noether_examples/meshes/outputs/output_15.stl @@ -0,0 +1,10257 @@ +solid ascii + facet normal -0.540076 -0.219589 -0.812465 + outer loop + vertex 331.363 88.0972 292.464 + vertex 333.04 87.4705 291.519 + vertex 332.961 83.2927 292.7 + endloop + endfacet + facet normal -0.485207 -0.203209 -0.850459 + outer loop + vertex 331.434 83.2906 293.572 + vertex 331.363 88.0972 292.464 + vertex 332.961 83.2927 292.7 + endloop + endfacet + facet normal -0.49246 -0.202397 -0.846474 + outer loop + vertex 330.038 87.1117 293.471 + vertex 331.363 88.0972 292.464 + vertex 331.434 83.2906 293.572 + endloop + endfacet + facet normal -0.510432 -0.225091 -0.829936 + outer loop + vertex 332.961 83.2927 292.7 + vertex 333.04 87.4705 291.519 + vertex 334.51 83.669 291.646 + endloop + endfacet + facet normal -0.53938 -0.235568 -0.808441 + outer loop + vertex 333.04 87.4705 291.519 + vertex 334.356 88.574 290.319 + vertex 334.51 83.669 291.646 + endloop + endfacet + facet normal -0.539348 -0.235572 -0.808461 + outer loop + vertex 334.51 83.669 291.646 + vertex 334.356 88.574 290.319 + vertex 336.067 84.2507 290.438 + endloop + endfacet + facet normal -0.584075 -0.252262 -0.771505 + outer loop + vertex 334.356 88.574 290.319 + vertex 336.044 88.7845 288.973 + vertex 336.067 84.2507 290.438 + endloop + endfacet + facet normal -0.560709 -0.257167 -0.787065 + outer loop + vertex 336.067 84.2507 290.438 + vertex 336.044 88.7845 288.973 + vertex 337.663 84.6775 289.161 + endloop + endfacet + facet normal -0.5929 -0.268584 -0.759165 + outer loop + vertex 336.044 88.7845 288.973 + vertex 337.674 89.0429 287.608 + vertex 337.663 84.6775 289.161 + endloop + endfacet + facet normal -0.580156 -0.271705 -0.767851 + outer loop + vertex 337.663 84.6775 289.161 + vertex 337.674 89.0429 287.608 + vertex 339.233 85.0722 287.836 + endloop + endfacet + facet normal -0.606513 -0.280681 -0.743881 + outer loop + vertex 337.674 89.0429 287.608 + vertex 339.248 89.413 286.185 + vertex 339.233 85.0722 287.836 + endloop + endfacet + facet normal -0.593334 -0.284234 -0.753104 + outer loop + vertex 339.233 85.0722 287.836 + vertex 339.248 89.413 286.185 + vertex 340.801 85.5193 286.431 + endloop + endfacet + facet normal -0.617562 -0.292444 -0.730133 + outer loop + vertex 339.248 89.413 286.185 + vertex 340.803 89.8904 284.679 + vertex 340.801 85.5193 286.431 + endloop + endfacet + facet normal -0.608172 -0.295157 -0.736891 + outer loop + vertex 340.801 85.5193 286.431 + vertex 340.803 89.8904 284.679 + vertex 342.386 86.0122 284.926 + endloop + endfacet + facet normal -0.62938 -0.302475 -0.715814 + outer loop + vertex 340.803 89.8904 284.679 + vertex 342.353 90.4193 283.092 + vertex 342.386 86.0122 284.926 + endloop + endfacet + facet normal -0.623371 -0.304292 -0.720288 + outer loop + vertex 342.386 86.0122 284.926 + vertex 342.353 90.4193 283.092 + vertex 343.975 86.5219 283.336 + endloop + endfacet + facet normal -0.643645 -0.311404 -0.699105 + outer loop + vertex 342.353 90.4193 283.092 + vertex 343.885 90.9497 281.445 + vertex 343.975 86.5219 283.336 + endloop + endfacet + facet normal -0.634607 -0.3142 -0.706082 + outer loop + vertex 343.975 86.5219 283.336 + vertex 343.885 90.9497 281.445 + vertex 345.542 87.0406 281.696 + endloop + endfacet + facet normal -0.651514 -0.320189 -0.687756 + outer loop + vertex 343.885 90.9497 281.445 + vertex 345.396 91.4878 279.764 + vertex 345.542 87.0406 281.696 + endloop + endfacet + facet normal -0.646116 -0.321876 -0.692048 + outer loop + vertex 345.542 87.0406 281.696 + vertex 345.396 91.4878 279.764 + vertex 347.072 87.563 280.025 + endloop + endfacet + facet normal -0.665065 -0.328545 -0.670631 + outer loop + vertex 345.396 91.4878 279.764 + vertex 346.88 91.9988 278.041 + vertex 347.072 87.563 280.025 + endloop + endfacet + facet normal -0.657574 -0.330978 -0.676793 + outer loop + vertex 347.072 87.563 280.025 + vertex 346.88 91.9988 278.041 + vertex 348.575 88.0742 278.314 + endloop + endfacet + facet normal -0.674678 -0.33697 -0.656705 + outer loop + vertex 346.88 91.9988 278.041 + vertex 348.365 92.465 276.277 + vertex 348.575 88.0742 278.314 + endloop + endfacet + facet normal -0.669043 -0.338905 -0.661457 + outer loop + vertex 348.575 88.0742 278.314 + vertex 348.365 92.465 276.277 + vertex 350.075 88.5473 276.554 + endloop + endfacet + facet normal -0.683652 -0.34402 -0.643638 + outer loop + vertex 348.365 92.465 276.277 + vertex 349.824 92.8772 274.506 + vertex 350.075 88.5473 276.554 + endloop + endfacet + facet normal -0.678619 -0.345792 -0.648001 + outer loop + vertex 350.075 88.5473 276.554 + vertex 349.824 92.8772 274.506 + vertex 351.547 88.9672 274.789 + endloop + endfacet + facet normal -0.687683 -0.348965 -0.636644 + outer loop + vertex 349.824 92.8772 274.506 + vertex 351.169 93.2592 272.845 + vertex 351.547 88.9672 274.789 + endloop + endfacet + facet normal -0.684043 -0.350127 -0.639919 + outer loop + vertex 351.547 88.9672 274.789 + vertex 351.169 93.2592 272.845 + vertex 352.896 89.3497 273.138 + endloop + endfacet + facet normal -0.685872 -0.350762 -0.637609 + outer loop + vertex 351.169 93.2592 272.845 + vertex 352.252 93.6409 271.469 + vertex 352.896 89.3497 273.138 + endloop + endfacet + facet normal -0.680122 -0.352017 -0.643054 + outer loop + vertex 352.896 89.3497 273.138 + vertex 352.252 93.6409 271.469 + vertex 353.975 89.739 271.784 + endloop + endfacet + facet normal -0.677852 -0.351242 -0.645868 + outer loop + vertex 352.252 93.6409 271.469 + vertex 352.961 94.0161 270.521 + vertex 353.975 89.739 271.784 + endloop + endfacet + facet normal -0.67752 -0.351263 -0.646205 + outer loop + vertex 353.975 89.739 271.784 + vertex 352.961 94.0161 270.521 + vertex 354.68 90.1206 270.837 + endloop + endfacet + facet normal -0.676895 -0.35105 -0.646975 + outer loop + vertex 352.961 94.0161 270.521 + vertex 353.325 94.2453 270.017 + vertex 354.68 90.1206 270.837 + endloop + endfacet + facet normal -0.670078 -0.350296 -0.654437 + outer loop + vertex 354.68 90.1206 270.837 + vertex 353.325 94.2453 270.017 + vertex 355.04 90.4042 270.316 + endloop + endfacet + facet normal -0.73326 -0.37186 -0.569254 + outer loop + vertex 353.325 94.2453 270.017 + vertex 353.5 94.1834 269.832 + vertex 355.04 90.4042 270.316 + endloop + endfacet + facet normal -0.683212 -0.359942 -0.635345 + outer loop + vertex 355.04 90.4042 270.316 + vertex 353.5 94.1834 269.832 + vertex 355.235 90.4029 270.108 + endloop + endfacet + facet normal -0.886101 -0.388224 0.253194 + outer loop + vertex 353.5 94.1834 269.832 + vertex 353.678 93.7662 269.815 + vertex 355.235 90.4029 270.108 + endloop + endfacet + facet normal -0.766869 -0.398693 -0.502948 + outer loop + vertex 355.235 90.4029 270.108 + vertex 353.678 93.7662 269.815 + vertex 355.56 89.7963 270.093 + endloop + endfacet + facet normal -0.595283 -0.20204 -0.777701 + outer loop + vertex 336.044 88.7845 288.973 + vertex 334.356 88.574 290.319 + vertex 334.497 93.3799 288.963 + endloop + endfacet + facet normal -0.618614 -0.209847 -0.757153 + outer loop + vertex 334.497 93.3799 288.963 + vertex 336.207 93.3647 287.57 + vertex 336.044 88.7845 288.973 + endloop + endfacet + facet normal -0.607107 -0.212841 -0.765585 + outer loop + vertex 336.044 88.7845 288.973 + vertex 336.207 93.3647 287.57 + vertex 337.674 89.0429 287.608 + endloop + endfacet + facet normal -0.630348 -0.220541 -0.744328 + outer loop + vertex 336.207 93.3647 287.57 + vertex 337.812 93.6427 286.128 + vertex 337.674 89.0429 287.608 + endloop + endfacet + facet normal -0.62462 -0.222112 -0.748676 + outer loop + vertex 337.674 89.0429 287.608 + vertex 337.812 93.6427 286.128 + vertex 339.248 89.413 286.185 + endloop + endfacet + facet normal -0.645957 -0.229081 -0.728191 + outer loop + vertex 337.812 93.6427 286.128 + vertex 339.367 94.0739 284.613 + vertex 339.248 89.413 286.185 + endloop + endfacet + facet normal -0.639494 -0.230963 -0.733282 + outer loop + vertex 339.248 89.413 286.185 + vertex 339.367 94.0739 284.613 + vertex 340.803 89.8904 284.679 + endloop + endfacet + facet normal -0.660403 -0.237807 -0.712261 + outer loop + vertex 339.367 94.0739 284.613 + vertex 340.898 94.5988 283.018 + vertex 340.803 89.8904 284.679 + endloop + endfacet + facet normal -0.653114 -0.240051 -0.718204 + outer loop + vertex 340.803 89.8904 284.679 + vertex 340.898 94.5988 283.018 + vertex 342.353 90.4193 283.092 + endloop + endfacet + facet normal -0.672583 -0.246468 -0.697772 + outer loop + vertex 340.898 94.5988 283.018 + vertex 342.415 95.1507 281.361 + vertex 342.353 90.4193 283.092 + endloop + endfacet + facet normal -0.66819 -0.247882 -0.701482 + outer loop + vertex 342.353 90.4193 283.092 + vertex 342.415 95.1507 281.361 + vertex 343.885 90.9497 281.445 + endloop + endfacet + facet normal -0.684377 -0.253195 -0.683754 + outer loop + vertex 342.415 95.1507 281.361 + vertex 343.915 95.6912 279.66 + vertex 343.885 90.9497 281.445 + endloop + endfacet + facet normal -0.677099 -0.255617 -0.69007 + outer loop + vertex 343.885 90.9497 281.445 + vertex 343.915 95.6912 279.66 + vertex 345.396 91.4878 279.764 + endloop + endfacet + facet normal -0.695555 -0.261603 -0.669154 + outer loop + vertex 343.915 95.6912 279.66 + vertex 345.394 96.1983 277.924 + vertex 345.396 91.4878 279.764 + endloop + endfacet + facet normal -0.69078 -0.263273 -0.673432 + outer loop + vertex 345.396 91.4878 279.764 + vertex 345.394 96.1983 277.924 + vertex 346.88 91.9988 278.041 + endloop + endfacet + facet normal -0.706253 -0.268239 -0.655175 + outer loop + vertex 345.394 96.1983 277.924 + vertex 346.862 96.6228 276.168 + vertex 346.88 91.9988 278.041 + endloop + endfacet + facet normal -0.700277 -0.270438 -0.660663 + outer loop + vertex 346.88 91.9988 278.041 + vertex 346.862 96.6228 276.168 + vertex 348.365 92.465 276.277 + endloop + endfacet + facet normal -0.713763 -0.274884 -0.64419 + outer loop + vertex 346.862 96.6228 276.168 + vertex 348.304 96.9916 274.413 + vertex 348.365 92.465 276.277 + endloop + endfacet + facet normal -0.708891 -0.276707 -0.648774 + outer loop + vertex 348.365 92.465 276.277 + vertex 348.304 96.9916 274.413 + vertex 349.824 92.8772 274.506 + endloop + endfacet + facet normal -0.714777 -0.278714 -0.641414 + outer loop + vertex 348.304 96.9916 274.413 + vertex 349.624 97.4034 272.763 + vertex 349.824 92.8772 274.506 + endloop + endfacet + facet normal -0.714193 -0.278906 -0.641981 + outer loop + vertex 349.824 92.8772 274.506 + vertex 349.624 97.4034 272.763 + vertex 351.169 93.2592 272.845 + endloop + endfacet + facet normal -0.713258 -0.278582 -0.64316 + outer loop + vertex 349.624 97.4034 272.763 + vertex 350.714 97.8674 271.353 + vertex 351.169 93.2592 272.845 + endloop + endfacet + facet normal -0.715563 -0.278053 -0.640825 + outer loop + vertex 351.169 93.2592 272.845 + vertex 350.714 97.8674 271.353 + vertex 352.252 93.6409 271.469 + endloop + endfacet + facet normal -0.71242 -0.277017 -0.644763 + outer loop + vertex 350.714 97.8674 271.353 + vertex 351.45 98.2893 270.359 + vertex 352.252 93.6409 271.469 + endloop + endfacet + facet normal -0.713774 -0.276904 -0.643313 + outer loop + vertex 352.252 93.6409 271.469 + vertex 351.45 98.2893 270.359 + vertex 352.961 94.0161 270.521 + endloop + endfacet + facet normal -0.725502 -0.280487 -0.628469 + outer loop + vertex 351.45 98.2893 270.359 + vertex 351.839 98.5121 269.81 + vertex 352.961 94.0161 270.521 + endloop + endfacet + facet normal -0.714283 -0.279749 -0.641514 + outer loop + vertex 352.961 94.0161 270.521 + vertex 351.839 98.5121 269.81 + vertex 353.325 94.2453 270.017 + endloop + endfacet + facet normal -0.85652 -0.317923 -0.406569 + outer loop + vertex 351.839 98.5121 269.81 + vertex 352.117 98.0119 269.617 + vertex 353.325 94.2453 270.017 + endloop + endfacet + facet normal -0.740957 -0.301401 -0.600117 + outer loop + vertex 353.325 94.2453 270.017 + vertex 352.117 98.0119 269.617 + vertex 353.5 94.1834 269.832 + endloop + endfacet + facet normal -0.596835 -0.171656 0.783787 + outer loop + vertex 352.117 98.0119 269.617 + vertex 352.361 97.179 269.621 + vertex 353.5 94.1834 269.832 + endloop + endfacet + facet normal -0.859756 -0.352797 -0.369262 + outer loop + vertex 353.5 94.1834 269.832 + vertex 352.361 97.179 269.621 + vertex 353.678 93.7662 269.815 + endloop + endfacet + facet normal -0.714379 -0.205652 -0.668857 + outer loop + vertex 343.915 95.6912 279.66 + vertex 344.033 101.031 277.893 + vertex 345.394 96.1983 277.924 + endloop + endfacet + facet normal -0.734055 -0.211043 -0.645464 + outer loop + vertex 344.033 101.031 277.893 + vertex 345.581 100.567 276.284 + vertex 345.394 96.1983 277.924 + endloop + endfacet + facet normal -0.72294 -0.215625 -0.656402 + outer loop + vertex 345.394 96.1983 277.924 + vertex 345.581 100.567 276.284 + vertex 346.862 96.6228 276.168 + endloop + endfacet + facet normal -0.727419 -0.217242 -0.650898 + outer loop + vertex 345.581 100.567 276.284 + vertex 346.869 101.572 274.509 + vertex 346.862 96.6228 276.168 + endloop + endfacet + facet normal -0.731732 -0.215774 -0.646536 + outer loop + vertex 346.862 96.6228 276.168 + vertex 346.869 101.572 274.509 + vertex 348.304 96.9916 274.413 + endloop + endfacet + facet normal -0.747648 -0.22119 -0.626176 + outer loop + vertex 346.869 101.572 274.509 + vertex 348.289 101.07 272.99 + vertex 348.304 96.9916 274.413 + endloop + endfacet + facet normal -0.732122 -0.226763 -0.642321 + outer loop + vertex 348.304 96.9916 274.413 + vertex 348.289 101.07 272.99 + vertex 349.624 97.4034 272.763 + endloop + endfacet + facet normal -0.715409 -0.219373 -0.663374 + outer loop + vertex 348.289 101.07 272.99 + vertex 349.132 102.59 271.578 + vertex 349.624 97.4034 272.763 + endloop + endfacet + facet normal -0.736681 -0.216219 -0.640742 + outer loop + vertex 349.624 97.4034 272.763 + vertex 349.132 102.59 271.578 + vertex 350.714 97.8674 271.353 + endloop + endfacet + facet normal -0.745557 -0.219742 -0.629172 + outer loop + vertex 349.132 102.59 271.578 + vertex 350.096 102.465 270.48 + vertex 350.714 97.8674 271.353 + endloop + endfacet + facet normal -0.736983 -0.220446 -0.638953 + outer loop + vertex 350.714 97.8674 271.353 + vertex 350.096 102.465 270.48 + vertex 351.45 98.2893 270.359 + endloop + endfacet + facet normal -0.727579 -0.217051 -0.650783 + outer loop + vertex 350.096 102.465 270.48 + vertex 350.326 103.596 269.846 + vertex 351.45 98.2893 270.359 + endloop + endfacet + facet normal -0.75157 -0.219363 -0.622111 + outer loop + vertex 351.45 98.2893 270.359 + vertex 350.326 103.596 269.846 + vertex 351.839 98.5121 269.81 + endloop + endfacet + facet normal -0.87385 -0.257213 -0.412586 + outer loop + vertex 350.326 103.596 269.846 + vertex 350.765 102.651 269.505 + vertex 351.839 98.5121 269.81 + endloop + endfacet + facet normal -0.815132 -0.250073 -0.522517 + outer loop + vertex 351.839 98.5121 269.81 + vertex 350.765 102.651 269.505 + vertex 352.117 98.0119 269.617 + endloop + endfacet + facet normal -0.669585 -0.177808 0.721138 + outer loop + vertex 350.765 102.651 269.505 + vertex 351.434 100.088 269.495 + vertex 352.117 98.0119 269.617 + endloop + endfacet + facet normal -0.815303 -0.237034 0.528295 + outer loop + vertex 352.117 98.0119 269.617 + vertex 351.434 100.088 269.495 + vertex 352.361 97.179 269.621 + endloop + endfacet + facet normal -0.247252 -0.0685345 0.966524 + outer loop + vertex 351.434 100.088 269.495 + vertex 350.765 102.651 269.505 + vertex 350.862 102.001 269.484 + endloop + endfacet + facet normal -0.709242 -0.207392 -0.673768 + outer loop + vertex 342.64 99.7004 279.768 + vertex 344.033 101.031 277.893 + vertex 343.915 95.6912 279.66 + endloop + endfacet + facet normal -0.701126 -0.204561 -0.683064 + outer loop + vertex 342.415 95.1507 281.361 + vertex 342.64 99.7004 279.768 + vertex 343.915 95.6912 279.66 + endloop + endfacet + facet normal -0.712841 -0.200163 -0.672155 + outer loop + vertex 341.055 100.047 281.346 + vertex 342.64 99.7004 279.768 + vertex 342.415 95.1507 281.361 + endloop + endfacet + facet normal -0.690554 -0.194048 -0.696764 + outer loop + vertex 340.898 94.5988 283.018 + vertex 341.055 100.047 281.346 + vertex 342.415 95.1507 281.361 + endloop + endfacet + facet normal -0.68711 -0.1951 -0.699869 + outer loop + vertex 339.624 98.6201 283.148 + vertex 341.055 100.047 281.346 + vertex 340.898 94.5988 283.018 + endloop + endfacet + facet normal -0.675892 -0.19116 -0.711778 + outer loop + vertex 339.367 94.0739 284.613 + vertex 339.624 98.6201 283.148 + vertex 340.898 94.5988 283.018 + endloop + endfacet + facet normal -0.684713 -0.188186 -0.704098 + outer loop + vertex 338.007 98.9988 284.619 + vertex 339.624 98.6201 283.148 + vertex 339.367 94.0739 284.613 + endloop + endfacet + facet normal -0.684582 -0.161656 -0.710785 + outer loop + vertex 339.624 98.6201 283.148 + vertex 338.007 98.9988 284.619 + vertex 339.04 105.709 282.098 + endloop + endfacet + facet normal -0.707433 -0.160219 -0.68838 + outer loop + vertex 339.624 98.6201 283.148 + vertex 339.04 105.709 282.098 + vertex 341.055 100.047 281.346 + endloop + endfacet + facet normal -0.719306 -0.166287 -0.674498 + outer loop + vertex 339.04 105.709 282.098 + vertex 342.034 106.634 278.677 + vertex 341.055 100.047 281.346 + endloop + endfacet + facet normal -0.713642 -0.169259 -0.679754 + outer loop + vertex 342.64 99.7004 279.768 + vertex 341.055 100.047 281.346 + vertex 342.034 106.634 278.677 + endloop + endfacet + facet normal -0.730714 -0.167911 -0.661712 + outer loop + vertex 342.64 99.7004 279.768 + vertex 342.034 106.634 278.677 + vertex 344.033 101.031 277.893 + endloop + endfacet + facet normal -0.738679 -0.172153 -0.651702 + outer loop + vertex 342.034 106.634 278.677 + vertex 344.88 107.15 275.316 + vertex 344.033 101.031 277.893 + endloop + endfacet + facet normal -0.734193 -0.174625 -0.656099 + outer loop + vertex 345.581 100.567 276.284 + vertex 344.033 101.031 277.893 + vertex 344.88 107.15 275.316 + endloop + endfacet + facet normal -0.747619 -0.173832 -0.640974 + outer loop + vertex 345.581 100.567 276.284 + vertex 344.88 107.15 275.316 + vertex 346.869 101.572 274.509 + endloop + endfacet + facet normal -0.752271 -0.176383 -0.634805 + outer loop + vertex 344.88 107.15 275.316 + vertex 347.224 106.586 272.694 + vertex 346.869 101.572 274.509 + endloop + endfacet + facet normal -0.747352 -0.178602 -0.639973 + outer loop + vertex 348.289 101.07 272.99 + vertex 346.869 101.572 274.509 + vertex 347.224 106.586 272.694 + endloop + endfacet + facet normal -0.74808 -0.178696 -0.639096 + outer loop + vertex 348.289 101.07 272.99 + vertex 347.224 106.586 272.694 + vertex 349.132 102.59 271.578 + endloop + endfacet + facet normal -0.742135 -0.173538 -0.647395 + outer loop + vertex 349.132 102.59 271.578 + vertex 347.224 106.586 272.694 + vertex 348.253 109.991 270.602 + endloop + endfacet + facet normal -0.749992 -0.173279 -0.638346 + outer loop + vertex 350.096 102.465 270.48 + vertex 349.132 102.59 271.578 + vertex 348.253 109.991 270.602 + endloop + endfacet + facet normal -0.776804 -0.180411 -0.603346 + outer loop + vertex 350.096 102.465 270.48 + vertex 348.253 109.991 270.602 + vertex 350.326 103.596 269.846 + endloop + endfacet + facet normal -0.79827 -0.191178 -0.571153 + outer loop + vertex 348.253 109.991 270.602 + vertex 349.163 109.205 269.593 + vertex 350.326 103.596 269.846 + endloop + endfacet + facet normal -0.82808 -0.195302 -0.525491 + outer loop + vertex 350.765 102.651 269.505 + vertex 350.326 103.596 269.846 + vertex 349.163 109.205 269.593 + endloop + endfacet + facet normal -0.790878 -0.156217 -0.5917 + outer loop + vertex 348.253 109.991 270.602 + vertex 347.429 117.786 269.645 + vertex 349.163 109.205 269.593 + endloop + endfacet + facet normal -0.793578 -0.156062 -0.588114 + outer loop + vertex 346.42 119.96 270.43 + vertex 347.429 117.786 269.645 + vertex 348.253 109.991 270.602 + endloop + endfacet + facet normal -0.760544 -0.150739 -0.631546 + outer loop + vertex 346.42 119.96 270.43 + vertex 348.253 109.991 270.602 + vertex 345.466 116.28 272.458 + endloop + endfacet + facet normal -0.772913 -0.140488 -0.618764 + outer loop + vertex 344.577 127.773 270.959 + vertex 346.42 119.96 270.43 + vertex 345.466 116.28 272.458 + endloop + endfacet + facet normal -0.764168 -0.141196 -0.629374 + outer loop + vertex 345.466 116.28 272.458 + vertex 343.368 124.208 273.226 + vertex 344.577 127.773 270.959 + endloop + endfacet + facet normal -0.770959 -0.13453 -0.622514 + outer loop + vertex 343.368 124.208 273.226 + vertex 342.202 133.585 272.644 + vertex 344.577 127.773 270.959 + endloop + endfacet + facet normal -0.773704 -0.136786 -0.618604 + outer loop + vertex 343.356 136.814 270.487 + vertex 344.577 127.773 270.959 + vertex 342.202 133.585 272.644 + endloop + endfacet + facet normal -0.775285 -0.135139 -0.616985 + outer loop + vertex 341.666 143.992 271.038 + vertex 343.356 136.814 270.487 + vertex 342.202 133.585 272.644 + endloop + endfacet + facet normal -0.780284 -0.134443 -0.610805 + outer loop + vertex 342.202 133.585 272.644 + vertex 340.453 140.521 273.351 + vertex 341.666 143.992 271.038 + endloop + endfacet + facet normal -0.780119 -0.134615 -0.610977 + outer loop + vertex 340.453 140.521 273.351 + vertex 339.522 147.999 272.892 + vertex 341.666 143.992 271.038 + endloop + endfacet + facet normal -0.782902 -0.138119 -0.60662 + outer loop + vertex 340.13 153.77 270.794 + vertex 341.666 143.992 271.038 + vertex 339.522 147.999 272.892 + endloop + endfacet + facet normal -0.785852 -0.136547 -0.603152 + outer loop + vertex 339.522 147.999 272.892 + vertex 338.203 156.447 272.698 + vertex 340.13 153.77 270.794 + endloop + endfacet + facet normal -0.785682 -0.136215 -0.603447 + outer loop + vertex 338.683 162.553 270.695 + vertex 340.13 153.77 270.794 + vertex 338.203 156.447 272.698 + endloop + endfacet + facet normal -0.801518 -0.128584 -0.583982 + outer loop + vertex 338.203 156.447 272.698 + vertex 336.785 165.249 272.706 + vertex 338.683 162.553 270.695 + endloop + endfacet + facet normal -0.794715 -0.114813 -0.596025 + outer loop + vertex 337.42 171.019 270.749 + vertex 338.683 162.553 270.695 + vertex 336.785 165.249 272.706 + endloop + endfacet + facet normal -0.839737 -0.0893539 -0.535591 + outer loop + vertex 336.785 165.249 272.706 + vertex 335.548 176.209 272.818 + vertex 337.42 171.019 270.749 + endloop + endfacet + facet normal -0.812588 -0.0620439 -0.579527 + outer loop + vertex 335.548 176.209 272.818 + vertex 337.398 176.866 270.154 + vertex 337.42 171.019 270.749 + endloop + endfacet + facet normal -0.816343 -0.0615245 -0.574282 + outer loop + vertex 337.398 176.866 270.154 + vertex 337.505 176.904 269.998 + vertex 337.42 171.019 270.749 + endloop + endfacet + facet normal -0.772759 -0.069372 -0.630897 + outer loop + vertex 337.42 171.019 270.749 + vertex 337.505 176.904 269.998 + vertex 338.51 167.936 269.752 + endloop + endfacet + facet normal -0.991447 -0.109219 -0.0714381 + outer loop + vertex 338.51 167.936 269.752 + vertex 337.505 176.904 269.998 + vertex 338.048 172.236 269.592 + endloop + endfacet + facet normal -0.908089 -0.112669 -0.403337 + outer loop + vertex 338.048 172.236 269.592 + vertex 338.628 167.996 269.47 + vertex 338.51 167.936 269.752 + endloop + endfacet + facet normal -0.900768 -0.149083 -0.407911 + outer loop + vertex 338.628 167.996 269.47 + vertex 339.146 164.814 269.488 + vertex 338.51 167.936 269.752 + endloop + endfacet + facet normal -0.898646 -0.14823 -0.412872 + outer loop + vertex 339.942 159.364 269.714 + vertex 338.51 167.936 269.752 + vertex 339.146 164.814 269.488 + endloop + endfacet + facet normal -0.822288 -0.142811 -0.550861 + outer loop + vertex 339.146 164.814 269.488 + vertex 339.726 161.503 269.481 + vertex 339.942 159.364 269.714 + endloop + endfacet + facet normal -0.815165 -0.143222 -0.561243 + outer loop + vertex 339.726 161.503 269.481 + vertex 340.266 158.33 269.507 + vertex 339.942 159.364 269.714 + endloop + endfacet + facet normal -0.822742 -0.148098 -0.548783 + outer loop + vertex 340.266 158.33 269.507 + vertex 341.022 154.242 269.477 + vertex 339.942 159.364 269.714 + endloop + endfacet + facet normal -0.805764 -0.14332 -0.574634 + outer loop + vertex 341.539 150.171 269.767 + vertex 339.942 159.364 269.714 + vertex 341.022 154.242 269.477 + endloop + endfacet + facet normal -0.797418 -0.143087 -0.586217 + outer loop + vertex 341.022 154.242 269.477 + vertex 341.812 149.962 269.447 + vertex 341.539 150.171 269.767 + endloop + endfacet + facet normal -0.797464 -0.143335 -0.586094 + outer loop + vertex 341.812 149.962 269.447 + vertex 342.595 145.76 269.409 + vertex 341.539 150.171 269.767 + endloop + endfacet + facet normal -0.792837 -0.141687 -0.592735 + outer loop + vertex 343.04 142.094 269.69 + vertex 341.539 150.171 269.767 + vertex 342.595 145.76 269.409 + endloop + endfacet + facet normal -0.789593 -0.141625 -0.597064 + outer loop + vertex 342.595 145.76 269.409 + vertex 343.289 142.016 269.379 + vertex 343.04 142.094 269.69 + endloop + endfacet + facet normal -0.789588 -0.14097 -0.597225 + outer loop + vertex 343.289 142.016 269.379 + vertex 343.796 139.096 269.399 + vertex 343.04 142.094 269.69 + endloop + endfacet + facet normal -0.78493 -0.139162 -0.603754 + outer loop + vertex 344.397 134.455 269.687 + vertex 343.04 142.094 269.69 + vertex 343.796 139.096 269.399 + endloop + endfacet + facet normal -0.783702 -0.139103 -0.605361 + outer loop + vertex 343.796 139.096 269.399 + vertex 344.466 135.475 269.363 + vertex 344.397 134.455 269.687 + endloop + endfacet + facet normal -0.783552 -0.13917 -0.605539 + outer loop + vertex 344.466 135.475 269.363 + vertex 345.184 131.169 269.424 + vertex 344.397 134.455 269.687 + endloop + endfacet + facet normal -0.783758 -0.139242 -0.605256 + outer loop + vertex 345.84 126.225 269.711 + vertex 344.397 134.455 269.687 + vertex 345.184 131.169 269.424 + endloop + endfacet + facet normal -0.786723 -0.139409 -0.601358 + outer loop + vertex 345.184 131.169 269.424 + vertex 345.959 126.983 269.38 + vertex 345.84 126.225 269.711 + endloop + endfacet + facet normal -0.786037 -0.139863 -0.60215 + outer loop + vertex 345.959 126.983 269.38 + vertex 346.637 122.966 269.428 + vertex 345.84 126.225 269.711 + endloop + endfacet + facet normal -0.806303 -0.147356 -0.572855 + outer loop + vertex 347.429 117.786 269.645 + vertex 345.84 126.225 269.711 + vertex 346.637 122.966 269.428 + endloop + endfacet + facet normal -0.839169 -0.150283 -0.522696 + outer loop + vertex 346.637 122.966 269.428 + vertex 347.119 120.35 269.406 + vertex 347.429 117.786 269.645 + endloop + endfacet + facet normal -0.819117 -0.150724 -0.553471 + outer loop + vertex 347.119 120.35 269.406 + vertex 347.634 117.576 269.4 + vertex 347.429 117.786 269.645 + endloop + endfacet + facet normal -0.819867 -0.153704 -0.551537 + outer loop + vertex 347.634 117.576 269.4 + vertex 348.334 113.669 269.448 + vertex 347.429 117.786 269.645 + endloop + endfacet + facet normal -0.72326 -0.137909 -0.676665 + outer loop + vertex 348.334 113.669 269.448 + vertex 347.634 117.576 269.4 + vertex 348.659 112.985 269.24 + endloop + endfacet + facet normal -0.730816 -0.144383 -0.667129 + outer loop + vertex 349.127 109.66 269.446 + vertex 348.334 113.669 269.448 + vertex 348.659 112.985 269.24 + endloop + endfacet + facet normal -0.922617 -0.182429 -0.339848 + outer loop + vertex 348.334 113.669 269.448 + vertex 349.127 109.66 269.446 + vertex 349.163 109.205 269.593 + endloop + endfacet + facet normal -0.906158 -0.192948 -0.376363 + outer loop + vertex 349.127 109.66 269.446 + vertex 349.974 105.646 269.467 + vertex 349.163 109.205 269.593 + endloop + endfacet + facet normal -0.721477 -0.137442 -0.678661 + outer loop + vertex 347.108 121.774 269.109 + vertex 348.659 112.985 269.24 + vertex 347.634 117.576 269.4 + endloop + endfacet + facet normal -0.770703 -0.145256 -0.620418 + outer loop + vertex 348.659 112.985 269.24 + vertex 347.108 121.774 269.109 + vertex 349.484 114.19 267.932 + endloop + endfacet + facet normal -0.758106 -0.165217 -0.630856 + outer loop + vertex 348.659 112.985 269.24 + vertex 349.484 114.19 267.932 + vertex 350.133 106.965 269.045 + endloop + endfacet + facet normal -0.727452 -0.156499 -0.668073 + outer loop + vertex 349.988 105.872 269.459 + vertex 348.659 112.985 269.24 + vertex 350.133 106.965 269.045 + endloop + endfacet + facet normal -0.67509 -0.181273 -0.715118 + outer loop + vertex 351.339 101.334 269.334 + vertex 349.988 105.872 269.459 + vertex 350.133 106.965 269.045 + endloop + endfacet + facet normal -0.757228 -0.194159 -0.623625 + outer loop + vertex 351.339 101.334 269.334 + vertex 350.133 106.965 269.045 + vertex 351.846 101.434 268.687 + endloop + endfacet + facet normal -0.776025 -0.201664 -0.597592 + outer loop + vertex 351.846 101.434 268.687 + vertex 350.133 106.965 269.045 + vertex 350.921 106.113 268.309 + endloop + endfacet + facet normal -0.764593 -0.200608 -0.612499 + outer loop + vertex 351.846 101.434 268.687 + vertex 350.921 106.113 268.309 + vertex 352.769 101.6 267.481 + endloop + endfacet + facet normal -0.765516 -0.201236 -0.611137 + outer loop + vertex 352.769 101.6 267.481 + vertex 350.921 106.113 268.309 + vertex 351.787 106.889 266.969 + endloop + endfacet + facet normal -0.76855 -0.201424 -0.607256 + outer loop + vertex 352.769 101.6 267.481 + vertex 351.787 106.889 266.969 + vertex 354.03 101.945 265.77 + endloop + endfacet + facet normal -0.782486 -0.213128 -0.585057 + outer loop + vertex 354.03 101.945 265.77 + vertex 351.787 106.889 266.969 + vertex 353.272 106.088 265.274 + endloop + endfacet + facet normal -0.76864 -0.212777 -0.603257 + outer loop + vertex 354.03 101.945 265.77 + vertex 353.272 106.088 265.274 + vertex 355.491 102.468 263.724 + endloop + endfacet + facet normal -0.764228 -0.206806 -0.610889 + outer loop + vertex 355.491 102.468 263.724 + vertex 353.272 106.088 265.274 + vertex 354.447 107.496 263.328 + endloop + endfacet + facet normal -0.773142 -0.20774 -0.599246 + outer loop + vertex 355.491 102.468 263.724 + vertex 354.447 107.496 263.328 + vertex 357.089 103.104 261.441 + endloop + endfacet + facet normal -0.776665 -0.212556 -0.592968 + outer loop + vertex 357.089 103.104 261.441 + vertex 354.447 107.496 263.328 + vertex 356.202 107.476 261.036 + endloop + endfacet + facet normal -0.777169 -0.212596 -0.592293 + outer loop + vertex 357.089 103.104 261.441 + vertex 356.202 107.476 261.036 + vertex 358.765 103.704 259.028 + endloop + endfacet + facet normal -0.774943 -0.208825 -0.596536 + outer loop + vertex 358.765 103.704 259.028 + vertex 356.202 107.476 261.036 + vertex 357.549 108.96 258.767 + endloop + endfacet + facet normal -0.784984 -0.21046 -0.582672 + outer loop + vertex 358.765 103.704 259.028 + vertex 357.549 108.96 258.767 + vertex 360.494 104.227 256.509 + endloop + endfacet + facet normal -0.788393 -0.215711 -0.576112 + outer loop + vertex 360.494 104.227 256.509 + vertex 357.549 108.96 258.767 + vertex 359.572 108.706 256.094 + endloop + endfacet + facet normal -0.789061 -0.215762 -0.575178 + outer loop + vertex 360.494 104.227 256.509 + vertex 359.572 108.706 256.094 + vertex 362.253 104.742 253.903 + endloop + endfacet + facet normal -0.787359 -0.212697 -0.578641 + outer loop + vertex 362.253 104.742 253.903 + vertex 359.572 108.706 256.094 + vertex 361.007 110.114 253.623 + endloop + endfacet + facet normal -0.795939 -0.214042 -0.566275 + outer loop + vertex 362.253 104.742 253.903 + vertex 361.007 110.114 253.623 + vertex 364.027 105.264 251.212 + endloop + endfacet + facet normal -0.79888 -0.218866 -0.560258 + outer loop + vertex 364.027 105.264 251.212 + vertex 361.007 110.114 253.623 + vertex 363.122 109.775 250.741 + endloop + endfacet + facet normal -0.798973 -0.21887 -0.560124 + outer loop + vertex 364.027 105.264 251.212 + vertex 363.122 109.775 250.741 + vertex 365.818 105.823 248.439 + endloop + endfacet + facet normal -0.797135 -0.215293 -0.564114 + outer loop + vertex 365.818 105.823 248.439 + vertex 363.122 109.775 250.741 + vertex 364.587 111.203 248.125 + endloop + endfacet + facet normal -0.804911 -0.216397 -0.552531 + outer loop + vertex 365.818 105.823 248.439 + vertex 364.587 111.203 248.125 + vertex 367.604 106.395 245.614 + endloop + endfacet + facet normal -0.789097 -0.26762 -0.552906 + outer loop + vertex 368.944 101.842 245.903 + vertex 365.818 105.823 248.439 + vertex 367.604 106.395 245.614 + endloop + endfacet + facet normal -0.793006 -0.26839 -0.546907 + outer loop + vertex 368.944 101.842 245.903 + vertex 367.604 106.395 245.614 + vertex 370.72 102.432 243.039 + endloop + endfacet + facet normal -0.793439 -0.269489 -0.545739 + outer loop + vertex 370.72 102.432 243.039 + vertex 367.604 106.395 245.614 + vertex 369.37 106.966 242.764 + endloop + endfacet + facet normal -0.797356 -0.270285 -0.539601 + outer loop + vertex 370.72 102.432 243.039 + vertex 369.37 106.966 242.764 + vertex 372.477 103.01 240.154 + endloop + endfacet + facet normal -0.797152 -0.269747 -0.540172 + outer loop + vertex 372.477 103.01 240.154 + vertex 369.37 106.966 242.764 + vertex 371.122 107.541 239.89 + endloop + endfacet + facet normal -0.802697 -0.270888 -0.531317 + outer loop + vertex 372.477 103.01 240.154 + vertex 371.122 107.541 239.89 + vertex 374.221 103.572 237.233 + endloop + endfacet + facet normal -0.802663 -0.270797 -0.531414 + outer loop + vertex 374.221 103.572 237.233 + vertex 371.122 107.541 239.89 + vertex 372.864 108.1 236.975 + endloop + endfacet + facet normal -0.807731 -0.271844 -0.523136 + outer loop + vertex 374.221 103.572 237.233 + vertex 372.864 108.1 236.975 + vertex 375.972 104.124 234.242 + endloop + endfacet + facet normal -0.807379 -0.270838 -0.5242 + outer loop + vertex 375.972 104.124 234.242 + vertex 372.864 108.1 236.975 + vertex 374.621 108.657 233.981 + endloop + endfacet + facet normal -0.811492 -0.271672 -0.517373 + outer loop + vertex 375.972 104.124 234.242 + vertex 374.621 108.657 233.981 + vertex 377.755 104.684 231.151 + endloop + endfacet + facet normal -0.811515 -0.271742 -0.5173 + outer loop + vertex 377.755 104.684 231.151 + vertex 374.621 108.657 233.981 + vertex 376.403 109.214 230.893 + endloop + endfacet + facet normal -0.817097 -0.27287 -0.507833 + outer loop + vertex 377.755 104.684 231.151 + vertex 376.403 109.214 230.893 + vertex 379.542 105.224 227.986 + endloop + endfacet + facet normal -0.816408 -0.270663 -0.510117 + outer loop + vertex 379.542 105.224 227.986 + vertex 376.403 109.214 230.893 + vertex 378.198 109.766 227.727 + endloop + endfacet + facet normal -0.820946 -0.27156 -0.502297 + outer loop + vertex 379.542 105.224 227.986 + vertex 378.198 109.766 227.727 + vertex 381.335 105.767 224.763 + endloop + endfacet + facet normal -0.821011 -0.271777 -0.502073 + outer loop + vertex 381.335 105.767 224.763 + vertex 378.198 109.766 227.727 + vertex 379.983 110.302 224.518 + endloop + endfacet + facet normal -0.825291 -0.272645 -0.49453 + outer loop + vertex 381.335 105.767 224.763 + vertex 379.983 110.302 224.518 + vertex 383.111 106.3 221.504 + endloop + endfacet + facet normal -0.825003 -0.271647 -0.495558 + outer loop + vertex 383.111 106.3 221.504 + vertex 379.983 110.302 224.518 + vertex 381.76 110.833 221.269 + endloop + endfacet + facet normal -0.83031 -0.272733 -0.486007 + outer loop + vertex 383.111 106.3 221.504 + vertex 381.76 110.833 221.269 + vertex 384.871 106.813 218.21 + endloop + endfacet + facet normal -0.830043 -0.271771 -0.486999 + outer loop + vertex 384.871 106.813 218.21 + vertex 381.76 110.833 221.269 + vertex 383.522 111.332 217.988 + endloop + endfacet + facet normal -0.834346 -0.272665 -0.479084 + outer loop + vertex 384.871 106.813 218.21 + vertex 383.522 111.332 217.988 + vertex 386.63 107.304 214.867 + endloop + endfacet + facet normal -0.834191 -0.272079 -0.479687 + outer loop + vertex 386.63 107.304 214.867 + vertex 383.522 111.332 217.988 + vertex 385.285 111.8 214.656 + endloop + endfacet + facet normal -0.839229 -0.273139 -0.470202 + outer loop + vertex 386.63 107.304 214.867 + vertex 385.285 111.8 214.656 + vertex 388.383 107.75 211.479 + endloop + endfacet + facet normal -0.838753 -0.271257 -0.472137 + outer loop + vertex 388.383 107.75 211.479 + vertex 385.285 111.8 214.656 + vertex 387.053 112.258 211.252 + endloop + endfacet + facet normal -0.843496 -0.272199 -0.463058 + outer loop + vertex 388.383 107.75 211.479 + vertex 387.053 112.258 211.252 + vertex 390.138 108.2 208.018 + endloop + endfacet + facet normal -0.843417 -0.27187 -0.463395 + outer loop + vertex 390.138 108.2 208.018 + vertex 387.053 112.258 211.252 + vertex 388.815 112.767 207.745 + endloop + endfacet + facet normal -0.847934 -0.272653 -0.454608 + outer loop + vertex 390.138 108.2 208.018 + vertex 388.815 112.767 207.745 + vertex 391.882 108.734 204.445 + endloop + endfacet + facet normal -0.84727 -0.269706 -0.457594 + outer loop + vertex 391.882 108.734 204.445 + vertex 388.815 112.767 207.745 + vertex 390.572 113.469 204.078 + endloop + endfacet + facet normal -0.8515 -0.270237 -0.449355 + outer loop + vertex 391.882 108.734 204.445 + vertex 390.572 113.469 204.078 + vertex 393.629 109.468 200.692 + endloop + endfacet + facet normal -0.850384 -0.264967 -0.454577 + outer loop + vertex 393.629 109.468 200.692 + vertex 390.572 113.469 204.078 + vertex 392.312 114.565 200.185 + endloop + endfacet + facet normal -0.854673 -0.265251 -0.446292 + outer loop + vertex 393.629 109.468 200.692 + vertex 392.312 114.565 200.185 + vertex 395.423 110.377 196.715 + endloop + endfacet + facet normal -0.852557 -0.255871 -0.455716 + outer loop + vertex 395.423 110.377 196.715 + vertex 392.312 114.565 200.185 + vertex 394.168 116.939 195.38 + endloop + endfacet + facet normal -0.862209 -0.25415 -0.438182 + outer loop + vertex 397.341 110.249 193.017 + vertex 395.423 110.377 196.715 + vertex 394.168 116.939 195.38 + endloop + endfacet + facet normal -0.867366 -0.261893 -0.423188 + outer loop + vertex 397.341 110.249 193.017 + vertex 394.168 116.939 195.38 + vertex 398.6 111.658 189.564 + endloop + endfacet + facet normal -0.866599 -0.254782 -0.429059 + outer loop + vertex 394.168 116.939 195.38 + vertex 397.708 118.04 187.577 + vertex 398.6 111.658 189.564 + endloop + endfacet + facet normal -0.871915 -0.252551 -0.419503 + outer loop + vertex 400.652 111.322 185.502 + vertex 398.6 111.658 189.564 + vertex 397.708 118.04 187.577 + endloop + endfacet + facet normal -0.877001 -0.259437 -0.404428 + outer loop + vertex 400.652 111.322 185.502 + vertex 397.708 118.04 187.577 + vertex 401.905 112.59 181.97 + endloop + endfacet + facet normal -0.876386 -0.254189 -0.409068 + outer loop + vertex 397.708 118.04 187.577 + vertex 400.995 118.942 179.974 + vertex 401.905 112.59 181.97 + endloop + endfacet + facet normal -0.880736 -0.252232 -0.400854 + outer loop + vertex 403.877 112.129 177.928 + vertex 401.905 112.59 181.97 + vertex 400.995 118.942 179.974 + endloop + endfacet + facet normal -0.885041 -0.258089 -0.387419 + outer loop + vertex 403.877 112.129 177.928 + vertex 400.995 118.942 179.974 + vertex 405.076 113.346 174.38 + endloop + endfacet + facet normal -0.884609 -0.254296 -0.390897 + outer loop + vertex 400.995 118.942 179.974 + vertex 404.137 119.696 172.373 + vertex 405.076 113.346 174.38 + endloop + endfacet + facet normal -0.888378 -0.252498 -0.383444 + outer loop + vertex 406.973 112.845 170.313 + vertex 405.076 113.346 174.38 + vertex 404.137 119.696 172.373 + endloop + endfacet + facet normal -0.892733 -0.25866 -0.368947 + outer loop + vertex 406.973 112.845 170.313 + vertex 404.137 119.696 172.373 + vertex 408.107 114.047 166.727 + endloop + endfacet + facet normal -0.892328 -0.254571 -0.372753 + outer loop + vertex 404.137 119.696 172.373 + vertex 407.148 120.394 164.689 + vertex 408.107 114.047 166.727 + endloop + endfacet + facet normal -0.896386 -0.252484 -0.36434 + outer loop + vertex 409.93 113.527 162.602 + vertex 408.107 114.047 166.727 + vertex 407.148 120.394 164.689 + endloop + endfacet + facet normal -0.900313 -0.258355 -0.35027 + outer loop + vertex 409.93 113.527 162.602 + vertex 407.148 120.394 164.689 + vertex 411.007 114.726 158.949 + endloop + endfacet + facet normal -0.900086 -0.255495 -0.35294 + outer loop + vertex 407.148 120.394 164.689 + vertex 410.006 121.065 156.912 + vertex 411.007 114.726 158.949 + endloop + endfacet + facet normal -0.904059 -0.253328 -0.344242 + outer loop + vertex 412.75 114.196 154.762 + vertex 411.007 114.726 158.949 + vertex 410.006 121.065 156.912 + endloop + endfacet + facet normal -0.908106 -0.259936 -0.328295 + outer loop + vertex 412.75 114.196 154.762 + vertex 410.006 121.065 156.912 + vertex 413.733 115.37 151.115 + endloop + endfacet + facet normal -0.907871 -0.255981 -0.332029 + outer loop + vertex 410.006 121.065 156.912 + vertex 412.669 121.702 149.139 + vertex 413.733 115.37 151.115 + endloop + endfacet + facet normal -0.911762 -0.253794 -0.322921 + outer loop + vertex 415.358 114.817 146.961 + vertex 413.733 115.37 151.115 + vertex 412.669 121.702 149.139 + endloop + endfacet + facet normal -0.915603 -0.260578 -0.30622 + outer loop + vertex 415.358 114.817 146.961 + vertex 412.669 121.702 149.139 + vertex 416.223 115.971 143.392 + endloop + endfacet + facet normal -0.915481 -0.257743 -0.308971 + outer loop + vertex 412.669 121.702 149.139 + vertex 415.095 122.297 141.456 + vertex 416.223 115.971 143.392 + endloop + endfacet + facet normal -0.919651 -0.255271 -0.298461 + outer loop + vertex 417.705 115.385 139.326 + vertex 416.223 115.971 143.392 + vertex 415.095 122.297 141.456 + endloop + endfacet + facet normal -0.923222 -0.261959 -0.281139 + outer loop + vertex 417.705 115.385 139.326 + vertex 415.095 122.297 141.456 + vertex 418.457 116.524 135.795 + endloop + endfacet + facet normal -0.923172 -0.259942 -0.283166 + outer loop + vertex 415.095 122.297 141.456 + vertex 417.284 122.852 133.81 + vertex 418.457 116.524 135.795 + endloop + endfacet + facet normal -0.926981 -0.257411 -0.272848 + outer loop + vertex 419.822 115.926 131.724 + vertex 418.457 116.524 135.795 + vertex 417.284 122.852 133.81 + endloop + endfacet + facet normal -0.93068 -0.264972 -0.252239 + outer loop + vertex 419.822 115.926 131.724 + vertex 417.284 122.852 133.81 + vertex 420.478 117.048 128.124 + endloop + endfacet + facet normal -0.930691 -0.262725 -0.254539 + outer loop + vertex 417.284 122.852 133.81 + vertex 419.243 123.369 126.112 + vertex 420.478 117.048 128.124 + endloop + endfacet + facet normal -0.934663 -0.259753 -0.242761 + outer loop + vertex 421.728 116.427 123.974 + vertex 420.478 117.048 128.124 + vertex 419.243 123.369 126.112 + endloop + endfacet + facet normal -0.937599 -0.266948 -0.222817 + outer loop + vertex 421.728 116.427 123.974 + vertex 419.243 123.369 126.112 + vertex 422.272 117.538 120.356 + endloop + endfacet + facet normal -0.937667 -0.265129 -0.224695 + outer loop + vertex 419.243 123.369 126.112 + vertex 420.941 123.846 118.466 + vertex 422.272 117.538 120.356 + endloop + endfacet + facet normal -0.941435 -0.262145 -0.212085 + outer loop + vertex 423.374 116.892 116.259 + vertex 422.272 117.538 120.356 + vertex 420.941 123.846 118.466 + endloop + endfacet + facet normal -0.943847 -0.26976 -0.190744 + outer loop + vertex 423.374 116.892 116.259 + vertex 420.941 123.846 118.466 + vertex 423.763 117.968 112.816 + endloop + endfacet + facet normal -0.943977 -0.267803 -0.192845 + outer loop + vertex 420.941 123.846 118.466 + vertex 422.336 124.264 111.055 + vertex 423.763 117.968 112.816 + endloop + endfacet + facet normal -0.947587 -0.264719 -0.178895 + outer loop + vertex 424.689 117.283 108.923 + vertex 423.763 117.968 112.816 + vertex 422.336 124.264 111.055 + endloop + endfacet + facet normal -0.949546 -0.272713 -0.154886 + outer loop + vertex 424.689 117.283 108.923 + vertex 422.336 124.264 111.055 + vertex 424.928 118.331 105.616 + endloop + endfacet + facet normal -0.949669 -0.271481 -0.156288 + outer loop + vertex 422.336 124.264 111.055 + vertex 423.424 124.631 103.808 + vertex 424.928 118.331 105.616 + endloop + endfacet + facet normal -0.953253 -0.267706 -0.14015 + outer loop + vertex 425.692 117.609 101.793 + vertex 424.928 118.331 105.616 + vertex 423.424 124.631 103.808 + endloop + endfacet + facet normal -0.954511 -0.27583 -0.113253 + outer loop + vertex 425.692 117.609 101.793 + vertex 423.424 124.631 103.808 + vertex 425.796 118.641 98.406 + endloop + endfacet + facet normal -0.945763 -0.301555 -0.120822 + outer loop + vertex 427.416 113.491 98.5759 + vertex 425.692 117.609 101.793 + vertex 425.796 118.641 98.406 + endloop + endfacet + facet normal -0.94868 -0.301621 -0.0950291 + outer loop + vertex 427.416 113.491 98.5759 + vertex 425.796 118.641 98.406 + vertex 427.743 113.628 94.8848 + endloop + endfacet + facet normal -0.93235 -0.348764 -0.0953283 + outer loop + vertex 429.364 109.294 94.8859 + vertex 427.416 113.491 98.5759 + vertex 427.743 113.628 94.8848 + endloop + endfacet + facet normal -0.934381 -0.349517 -0.0690657 + outer loop + vertex 429.364 109.294 94.8859 + vertex 427.743 113.628 94.8848 + vertex 429.597 109.41 91.1404 + endloop + endfacet + facet normal -0.934795 -0.348031 -0.0709454 + outer loop + vertex 429.597 109.41 91.1404 + vertex 427.743 113.628 94.8848 + vertex 427.98 113.751 91.1522 + endloop + endfacet + facet normal -0.936365 -0.348699 -0.0403765 + outer loop + vertex 429.597 109.41 91.1404 + vertex 427.98 113.751 91.1522 + vertex 429.722 109.508 87.4037 + endloop + endfacet + facet normal -0.913543 -0.404663 -0.0410787 + outer loop + vertex 431.481 105.568 87.0853 + vertex 429.597 109.41 91.1404 + vertex 429.722 109.508 87.4037 + endloop + endfacet + facet normal -0.913116 -0.407699 -0.00115313 + outer loop + vertex 431.481 105.568 87.0853 + vertex 429.722 109.508 87.4037 + vertex 431.461 105.624 83.3876 + endloop + endfacet + facet normal -0.914867 -0.403715 -0.00576419 + outer loop + vertex 431.461 105.624 83.3876 + vertex 429.722 109.508 87.4037 + vertex 429.726 109.552 83.6905 + endloop + endfacet + facet normal -0.912829 -0.406359 0.0402057 + outer loop + vertex 431.461 105.624 83.3876 + vertex 429.726 109.552 83.6905 + vertex 431.321 105.581 79.7625 + endloop + endfacet + facet normal -0.914215 -0.403554 0.0368073 + outer loop + vertex 431.321 105.581 79.7625 + vertex 429.726 109.552 83.6905 + vertex 429.598 109.506 80.0127 + endloop + endfacet + facet normal -0.91076 -0.404869 0.081227 + outer loop + vertex 431.321 105.581 79.7625 + vertex 429.598 109.506 80.0127 + vertex 431.07 105.442 76.2639 + endloop + endfacet + facet normal -0.91263 -0.4015 0.0768404 + outer loop + vertex 431.07 105.442 76.2639 + vertex 429.598 109.506 80.0127 + vertex 429.321 109.455 76.4561 + endloop + endfacet + facet normal -0.933986 -0.348751 0.0777398 + outer loop + vertex 429.598 109.506 80.0127 + vertex 427.971 113.84 79.911 + vertex 429.321 109.455 76.4561 + endloop + endfacet + facet normal -0.935223 -0.346228 0.0740539 + outer loop + vertex 429.321 109.455 76.4561 + vertex 427.971 113.84 79.911 + vertex 427.646 113.962 76.3777 + endloop + endfacet + facet normal -0.932477 -0.344612 0.108304 + outer loop + vertex 429.321 109.455 76.4561 + vertex 427.646 113.962 76.3777 + vertex 428.875 109.668 73.2927 + endloop + endfacet + facet normal -0.914042 -0.392459 0.102484 + outer loop + vertex 430.705 105.353 73.0942 + vertex 429.321 109.455 76.4561 + vertex 428.875 109.668 73.2927 + endloop + endfacet + facet normal -0.908473 -0.401558 0.115879 + outer loop + vertex 431.07 105.442 76.2639 + vertex 429.321 109.455 76.4561 + vertex 430.705 105.353 73.0942 + endloop + endfacet + facet normal -0.935521 -0.339024 0.0993132 + outer loop + vertex 428.875 109.668 73.2927 + vertex 427.646 113.962 76.3777 + vertex 427.069 114.67 73.3589 + endloop + endfacet + facet normal -0.931254 -0.337972 0.136166 + outer loop + vertex 428.875 109.668 73.2927 + vertex 427.069 114.67 73.3589 + vertex 428.276 110.309 70.7922 + endloop + endfacet + facet normal -0.916713 -0.380538 0.121767 + outer loop + vertex 430.237 105.514 70.5691 + vertex 428.875 109.668 73.2927 + vertex 428.276 110.309 70.7922 + endloop + endfacet + facet normal -0.908231 -0.379598 0.176128 + outer loop + vertex 430.237 105.514 70.5691 + vertex 428.276 110.309 70.7922 + vertex 429.789 105.838 68.9543 + endloop + endfacet + facet normal -0.885469 -0.436899 0.158319 + outer loop + vertex 431.698 101.816 68.5325 + vertex 430.237 105.514 70.5691 + vertex 429.789 105.838 68.9543 + endloop + endfacet + facet normal -0.878306 -0.437189 0.193504 + outer loop + vertex 431.698 101.816 68.5325 + vertex 429.789 105.838 68.9543 + vertex 431.279 102.332 67.7991 + endloop + endfacet + facet normal -0.864621 -0.444673 0.233874 + outer loop + vertex 431.279 102.332 67.7991 + vertex 429.789 105.838 68.9543 + vertex 429.468 106.079 68.2251 + endloop + endfacet + facet normal -0.876121 -0.446344 0.182176 + outer loop + vertex 432.182 101.523 70.1434 + vertex 430.237 105.514 70.5691 + vertex 431.698 101.816 68.5325 + endloop + endfacet + facet normal -0.901246 -0.385869 0.197132 + outer loop + vertex 429.789 105.838 68.9543 + vertex 428.276 110.309 70.7922 + vertex 427.976 110.089 68.9861 + endloop + endfacet + facet normal -0.886274 -0.379989 0.264816 + outer loop + vertex 429.789 105.838 68.9543 + vertex 427.976 110.089 68.9861 + vertex 429.468 106.079 68.2251 + endloop + endfacet + facet normal -0.798095 -0.3849 0.463569 + outer loop + vertex 429.468 106.079 68.2251 + vertex 427.976 110.089 68.9861 + vertex 428.518 108.144 68.3042 + endloop + endfacet + facet normal -0.903665 -0.342111 0.257585 + outer loop + vertex 428.518 108.144 68.3042 + vertex 427.976 110.089 68.9861 + vertex 427.875 109.59 67.9713 + endloop + endfacet + facet normal -0.908695 -0.392071 0.143366 + outer loop + vertex 430.705 105.353 73.0942 + vertex 428.875 109.668 73.2927 + vertex 430.237 105.514 70.5691 + endloop + endfacet + facet normal -0.939068 -0.325318 0.110991 + outer loop + vertex 428.276 110.309 70.7922 + vertex 427.069 114.67 73.3589 + vertex 425.836 117.37 70.8448 + endloop + endfacet + facet normal -0.943154 -0.302656 0.137332 + outer loop + vertex 425.764 118.901 73.7227 + vertex 425.836 117.37 70.8448 + vertex 427.069 114.67 73.3589 + endloop + endfacet + facet normal -0.952054 -0.279354 0.12472 + outer loop + vertex 425.764 118.901 73.7227 + vertex 424.134 125.198 75.378 + vertex 425.836 117.37 70.8448 + endloop + endfacet + facet normal -0.954349 -0.275062 0.116447 + outer loop + vertex 425.836 117.37 70.8448 + vertex 424.134 125.198 75.378 + vertex 423.047 127.001 70.735 + endloop + endfacet + facet normal -0.95995 -0.249358 0.127739 + outer loop + vertex 424.134 125.198 75.378 + vertex 421.563 135.059 75.312 + vertex 423.047 127.001 70.735 + endloop + endfacet + facet normal -0.963716 -0.241764 0.113146 + outer loop + vertex 423.047 127.001 70.735 + vertex 421.563 135.059 75.312 + vertex 420.763 136.216 70.9688 + endloop + endfacet + facet normal -0.965454 -0.233494 0.115669 + outer loop + vertex 421.563 135.059 75.312 + vertex 419.358 144.116 75.1879 + vertex 420.763 136.216 70.9688 + endloop + endfacet + facet normal -0.965881 -0.232609 0.11387 + outer loop + vertex 420.763 136.216 70.9688 + vertex 419.358 144.116 75.1879 + vertex 418.63 144.92 70.6586 + endloop + endfacet + facet normal -0.958411 -0.228755 0.170645 + outer loop + vertex 420.763 136.216 70.9688 + vertex 418.63 144.92 70.6586 + vertex 419.858 138.455 68.8855 + endloop + endfacet + facet normal -0.958237 -0.232394 0.16666 + outer loop + vertex 419.858 138.455 68.8855 + vertex 420.732 134.893 68.9482 + vertex 420.763 136.216 70.9688 + endloop + endfacet + facet normal -0.958438 -0.231826 0.166291 + outer loop + vertex 420.732 134.893 68.9482 + vertex 421.543 131.511 68.9049 + vertex 420.763 136.216 70.9688 + endloop + endfacet + facet normal -0.94281 -0.229053 0.242166 + outer loop + vertex 421.543 131.511 68.9049 + vertex 420.732 134.893 68.9482 + vertex 420.283 135.122 67.4142 + endloop + endfacet + facet normal -0.942728 -0.22879 0.242733 + outer loop + vertex 420.283 135.122 67.4142 + vertex 421.34 130.491 67.1529 + vertex 421.543 131.511 68.9049 + endloop + endfacet + facet normal -0.939468 -0.237204 0.247255 + outer loop + vertex 422.409 127.667 68.5087 + vertex 421.543 131.511 68.9049 + vertex 421.34 130.491 67.1529 + endloop + endfacet + facet normal -0.939454 -0.237148 0.24736 + outer loop + vertex 421.34 130.491 67.1529 + vertex 422.318 126.517 67.0585 + vertex 422.409 127.667 68.5087 + endloop + endfacet + facet normal -0.935724 -0.245235 0.253535 + outer loop + vertex 423.224 124.557 68.5067 + vertex 422.409 127.667 68.5087 + vertex 422.318 126.517 67.0585 + endloop + endfacet + facet normal -0.936285 -0.252166 0.244507 + outer loop + vertex 422.318 126.517 67.0585 + vertex 423.401 122.538 67.1038 + vertex 423.224 124.557 68.5067 + endloop + endfacet + facet normal -0.931913 -0.258588 0.254303 + outer loop + vertex 424.366 120.799 68.871 + vertex 423.224 124.557 68.5067 + vertex 423.401 122.538 67.1038 + endloop + endfacet + facet normal -0.931588 -0.273564 0.239388 + outer loop + vertex 423.401 122.538 67.1038 + vertex 424.829 117.818 67.2662 + vertex 424.366 120.799 68.871 + endloop + endfacet + facet normal -0.931085 -0.274166 0.240653 + outer loop + vertex 425.395 117.283 68.8467 + vertex 424.366 120.799 68.871 + vertex 424.829 117.818 67.2662 + endloop + endfacet + facet normal -0.924117 -0.307466 0.226877 + outer loop + vertex 426.378 114.06 68.4811 + vertex 425.395 117.283 68.8467 + vertex 424.829 117.818 67.2662 + endloop + endfacet + facet normal -0.926338 -0.307145 0.21808 + outer loop + vertex 425.395 117.283 68.8467 + vertex 426.378 114.06 68.4811 + vertex 425.836 117.37 70.8448 + endloop + endfacet + facet normal -0.936069 -0.275475 0.218836 + outer loop + vertex 424.366 120.799 68.871 + vertex 425.395 117.283 68.8467 + vertex 425.836 117.37 70.8448 + endloop + endfacet + facet normal -0.948298 -0.248492 0.197441 + outer loop + vertex 422.409 127.667 68.5087 + vertex 423.224 124.557 68.5067 + vertex 423.047 127.001 70.735 + endloop + endfacet + facet normal -0.950721 -0.235091 0.202144 + outer loop + vertex 421.543 131.511 68.9049 + vertex 422.409 127.667 68.5087 + vertex 423.047 127.001 70.735 + endloop + endfacet + facet normal -0.95197 -0.24078 0.189149 + outer loop + vertex 423.047 127.001 70.735 + vertex 420.763 136.216 70.9688 + vertex 421.543 131.511 68.9049 + endloop + endfacet + facet normal -0.928073 -0.228349 0.294172 + outer loop + vertex 420.283 135.122 67.4142 + vertex 419.761 134.23 65.0748 + vertex 421.34 130.491 67.1529 + endloop + endfacet + facet normal -0.92798 -0.227991 0.294744 + outer loop + vertex 421.34 130.491 67.1529 + vertex 419.761 134.23 65.0748 + vertex 420.808 129.896 65.0204 + endloop + endfacet + facet normal -0.925798 -0.234945 0.296141 + outer loop + vertex 421.34 130.491 67.1529 + vertex 420.808 129.896 65.0204 + vertex 422.318 126.517 67.0585 + endloop + endfacet + facet normal -0.926453 -0.237936 0.29167 + outer loop + vertex 422.318 126.517 67.0585 + vertex 420.808 129.896 65.0204 + vertex 421.873 125.705 64.983 + endloop + endfacet + facet normal -0.922833 -0.247929 0.294806 + outer loop + vertex 422.318 126.517 67.0585 + vertex 421.873 125.705 64.983 + vertex 423.401 122.538 67.1038 + endloop + endfacet + facet normal -0.92371 -0.253333 0.28737 + outer loop + vertex 423.401 122.538 67.1038 + vertex 421.873 125.705 64.983 + vertex 423.046 121.39 64.9496 + endloop + endfacet + facet normal -0.917648 -0.267472 0.293907 + outer loop + vertex 423.401 122.538 67.1038 + vertex 423.046 121.39 64.9496 + vertex 424.829 117.818 67.2662 + endloop + endfacet + facet normal -0.9189 -0.27575 0.282108 + outer loop + vertex 424.829 117.818 67.2662 + vertex 423.046 121.39 64.9496 + vertex 424.349 116.936 64.8402 + endloop + endfacet + facet normal -0.907301 -0.304294 0.290189 + outer loop + vertex 424.829 117.818 67.2662 + vertex 424.349 116.936 64.8402 + vertex 426.269 113.122 66.8437 + endloop + endfacet + facet normal -0.90791 -0.307274 0.2851 + outer loop + vertex 426.269 113.122 66.8437 + vertex 424.349 116.936 64.8402 + vertex 425.815 112.451 64.6735 + endloop + endfacet + facet normal -0.891153 -0.34594 0.29355 + outer loop + vertex 426.269 113.122 66.8437 + vertex 425.815 112.451 64.6735 + vertex 428.07 108.374 66.716 + endloop + endfacet + facet normal -0.89155 -0.34799 0.289898 + outer loop + vertex 428.07 108.374 66.716 + vertex 425.815 112.451 64.6735 + vertex 427.463 108.035 64.4433 + endloop + endfacet + facet normal -0.929863 -0.223077 0.292559 + outer loop + vertex 420.283 135.122 67.4142 + vertex 418.671 138.787 65.0865 + vertex 419.761 134.23 65.0748 + endloop + endfacet + facet normal -0.929202 -0.219987 0.296965 + outer loop + vertex 419.051 139.987 67.1627 + vertex 418.671 138.787 65.0865 + vertex 420.283 135.122 67.4142 + endloop + endfacet + facet normal -0.943799 -0.226596 0.240621 + outer loop + vertex 419.051 139.987 67.1627 + vertex 420.283 135.122 67.4142 + vertex 419.858 138.455 68.8855 + endloop + endfacet + facet normal -0.94384 -0.220179 0.246349 + outer loop + vertex 419.858 138.455 68.8855 + vertex 418.893 142.157 68.4993 + vertex 419.051 139.987 67.1627 + endloop + endfacet + facet normal -0.942308 -0.222421 0.250169 + outer loop + vertex 418.055 144.138 67.1045 + vertex 419.051 139.987 67.1627 + vertex 418.893 142.157 68.4993 + endloop + endfacet + facet normal -0.942282 -0.22221 0.250453 + outer loop + vertex 418.893 142.157 68.4993 + vertex 418.14 145.357 68.5043 + vertex 418.055 144.138 67.1045 + endloop + endfacet + facet normal -0.942168 -0.222458 0.250662 + outer loop + vertex 417.083 148.334 67.1724 + vertex 418.055 144.138 67.1045 + vertex 418.14 145.357 68.5043 + endloop + endfacet + facet normal -0.943115 -0.225736 0.244087 + outer loop + vertex 418.14 145.357 68.5043 + vertex 417.295 149.313 68.8961 + vertex 417.083 148.334 67.1724 + endloop + endfacet + facet normal -0.944965 -0.220745 0.241481 + outer loop + vertex 416.044 153.073 67.44 + vertex 417.083 148.334 67.1724 + vertex 417.295 149.313 68.8961 + endloop + endfacet + facet normal -0.944579 -0.21965 0.243975 + outer loop + vertex 417.295 149.313 68.8961 + vertex 416.516 152.731 68.9599 + vertex 416.044 153.073 67.44 + endloop + endfacet + facet normal -0.943742 -0.224745 0.24257 + outer loop + vertex 416.516 152.731 68.9599 + vertex 415.635 156.375 68.9092 + vertex 416.044 153.073 67.44 + endloop + endfacet + facet normal -0.944665 -0.223689 0.239939 + outer loop + vertex 414.809 158.027 67.1951 + vertex 416.044 153.073 67.44 + vertex 415.635 156.375 68.9092 + endloop + endfacet + facet normal -0.944591 -0.217728 0.245648 + outer loop + vertex 415.635 156.375 68.9092 + vertex 414.677 160.114 68.5397 + vertex 414.809 158.027 67.1951 + endloop + endfacet + facet normal -0.942283 -0.221232 0.251316 + outer loop + vertex 413.827 162.138 67.1317 + vertex 414.809 158.027 67.1951 + vertex 414.677 160.114 68.5397 + endloop + endfacet + facet normal -0.942279 -0.221205 0.251352 + outer loop + vertex 414.677 160.114 68.5397 + vertex 413.93 163.279 68.525 + vertex 413.827 162.138 67.1317 + endloop + endfacet + facet normal -0.942306 -0.221146 0.251305 + outer loop + vertex 412.9 166.102 67.144 + vertex 413.827 162.138 67.1317 + vertex 413.93 163.279 68.525 + endloop + endfacet + facet normal -0.943211 -0.224745 0.244626 + outer loop + vertex 413.93 163.279 68.525 + vertex 413.068 167.227 68.8264 + vertex 412.9 166.102 67.144 + endloop + endfacet + facet normal -0.944367 -0.221849 0.242805 + outer loop + vertex 411.915 170.302 67.1499 + vertex 412.9 166.102 67.144 + vertex 413.068 167.227 68.8264 + endloop + endfacet + facet normal -0.943713 -0.218687 0.248158 + outer loop + vertex 413.068 167.227 68.8264 + vertex 412.047 171.436 68.6525 + vertex 411.915 170.302 67.1499 + endloop + endfacet + facet normal -0.942364 -0.221872 0.250444 + outer loop + vertex 410.866 175.019 67.3843 + vertex 411.915 170.302 67.1499 + vertex 412.047 171.436 68.6525 + endloop + endfacet + facet normal -0.944053 -0.226092 0.240097 + outer loop + vertex 412.047 171.436 68.6525 + vertex 411.364 174.877 69.2051 + vertex 410.866 175.019 67.3843 + endloop + endfacet + facet normal -0.945483 -0.219001 0.241041 + outer loop + vertex 411.364 174.877 69.2051 + vertex 410.486 178.112 68.7008 + vertex 410.866 175.019 67.3843 + endloop + endfacet + facet normal -0.940545 -0.224349 0.255034 + outer loop + vertex 409.604 180.117 67.2138 + vertex 410.866 175.019 67.3843 + vertex 410.486 178.112 68.7008 + endloop + endfacet + facet normal -0.940343 -0.22254 0.257353 + outer loop + vertex 410.486 178.112 68.7008 + vertex 409.486 182.549 68.8865 + vertex 409.604 180.117 67.2138 + endloop + endfacet + facet normal -0.942173 -0.219687 0.253076 + outer loop + vertex 408.557 184.585 67.1964 + vertex 409.604 180.117 67.2138 + vertex 409.486 182.549 68.8865 + endloop + endfacet + facet normal -0.941522 -0.212194 0.261744 + outer loop + vertex 409.486 182.549 68.8865 + vertex 408.545 186.317 68.5562 + vertex 408.557 184.585 67.1964 + endloop + endfacet + facet normal -0.944173 -0.207572 0.255836 + outer loop + vertex 407.726 188.359 67.1897 + vertex 408.557 184.585 67.1964 + vertex 408.545 186.317 68.5562 + endloop + endfacet + facet normal -0.943866 -0.205673 0.258488 + outer loop + vertex 408.545 186.317 68.5562 + vertex 407.923 189.13 68.522 + vertex 407.726 188.359 67.1897 + endloop + endfacet + facet normal -0.946929 -0.19706 0.253954 + outer loop + vertex 407.342 190.604 67.4986 + vertex 407.726 188.359 67.1897 + vertex 407.923 189.13 68.522 + endloop + endfacet + facet normal -0.945944 -0.191001 0.262124 + outer loop + vertex 407.923 189.13 68.522 + vertex 407.175 192.978 68.6281 + vertex 407.342 190.604 67.4986 + endloop + endfacet + facet normal -0.945912 -0.19104 0.26221 + outer loop + vertex 406.462 192.186 65.477 + vertex 407.342 190.604 67.4986 + vertex 407.175 192.978 68.6281 + endloop + endfacet + facet normal -0.960308 -0.125651 0.249038 + outer loop + vertex 405.807 197.021 65.3929 + vertex 406.462 192.186 65.477 + vertex 407.175 192.978 68.6281 + endloop + endfacet + facet normal -0.960472 -0.126598 0.247924 + outer loop + vertex 407.175 192.978 68.6281 + vertex 406.712 197.208 68.9935 + vertex 405.807 197.021 65.3929 + endloop + endfacet + facet normal -0.955107 -0.191781 0.225811 + outer loop + vertex 407.175 192.978 68.6281 + vertex 407.923 189.13 68.522 + vertex 408.664 187.893 70.6059 + endloop + endfacet + facet normal -0.954618 -0.190382 0.229039 + outer loop + vertex 407.175 192.978 68.6281 + vertex 408.664 187.893 70.6059 + vertex 407.635 197.374 74.199 + endloop + endfacet + facet normal -0.976574 -0.122243 0.177086 + outer loop + vertex 406.712 197.208 68.9935 + vertex 407.175 192.978 68.6281 + vertex 407.635 197.374 74.199 + endloop + endfacet + facet normal -0.975561 -0.162079 0.148361 + outer loop + vertex 408.664 187.893 70.6059 + vertex 409.312 188.202 75.206 + vertex 407.635 197.374 74.199 + endloop + endfacet + facet normal -0.96458 -0.21666 0.150478 + outer loop + vertex 410.485 180.064 71.0059 + vertex 409.312 188.202 75.206 + vertex 408.664 187.893 70.6059 + endloop + endfacet + facet normal -0.956175 -0.21208 0.201872 + outer loop + vertex 410.485 180.064 71.0059 + vertex 408.664 187.893 70.6059 + vertex 409.486 182.549 68.8865 + endloop + endfacet + facet normal -0.970089 -0.206038 0.128359 + outer loop + vertex 411.188 179.413 75.2755 + vertex 409.312 188.202 75.206 + vertex 410.485 180.064 71.0059 + endloop + endfacet + facet normal -0.966744 -0.222988 0.125226 + outer loop + vertex 412.359 171.925 70.9815 + vertex 411.188 179.413 75.2755 + vertex 410.485 180.064 71.0059 + endloop + endfacet + facet normal -0.960215 -0.221618 0.16992 + outer loop + vertex 412.359 171.925 70.9815 + vertex 410.485 180.064 71.0059 + vertex 411.364 174.877 69.2051 + endloop + endfacet + facet normal -0.968051 -0.220185 0.119981 + outer loop + vertex 413.187 170.58 75.1936 + vertex 411.188 179.413 75.2755 + vertex 412.359 171.925 70.9815 + endloop + endfacet + facet normal -0.967314 -0.224153 0.118569 + outer loop + vertex 414.451 162.73 70.6642 + vertex 413.187 170.58 75.1936 + vertex 412.359 171.925 70.9815 + endloop + endfacet + facet normal -0.959047 -0.224156 0.173159 + outer loop + vertex 414.451 162.73 70.6642 + vertex 412.359 171.925 70.9815 + vertex 413.068 167.227 68.8264 + endloop + endfacet + facet normal -0.967539 -0.223662 0.117656 + outer loop + vertex 415.234 161.718 75.1781 + vertex 413.187 170.58 75.1936 + vertex 414.451 162.73 70.6642 + endloop + endfacet + facet normal -0.966692 -0.227858 0.116568 + outer loop + vertex 416.546 153.984 70.9439 + vertex 415.234 161.718 75.1781 + vertex 414.451 162.73 70.6642 + endloop + endfacet + facet normal -0.960225 -0.224737 0.165711 + outer loop + vertex 416.546 153.984 70.9439 + vertex 414.451 162.73 70.6642 + vertex 415.635 156.375 68.9092 + endloop + endfacet + facet normal -0.967659 -0.22579 0.112491 + outer loop + vertex 417.285 152.917 75.1587 + vertex 415.234 161.718 75.1781 + vertex 416.546 153.984 70.9439 + endloop + endfacet + facet normal -0.967611 -0.226034 0.112421 + outer loop + vertex 418.63 144.92 70.6586 + vertex 417.285 152.917 75.1587 + vertex 416.546 153.984 70.9439 + endloop + endfacet + facet normal -0.960148 -0.225957 0.164498 + outer loop + vertex 418.63 144.92 70.6586 + vertex 416.546 153.984 70.9439 + vertex 417.295 149.313 68.8961 + endloop + endfacet + facet normal -0.945966 -0.197355 0.257292 + outer loop + vertex 407.342 190.604 67.4986 + vertex 406.462 192.186 65.477 + vertex 407.726 188.359 67.1897 + endloop + endfacet + facet normal -0.939597 -0.180152 0.291037 + outer loop + vertex 407.726 188.359 67.1897 + vertex 406.462 192.186 65.477 + vertex 407.16 187.924 65.0928 + endloop + endfacet + facet normal -0.953993 -0.208435 0.215529 + outer loop + vertex 407.923 189.13 68.522 + vertex 408.545 186.317 68.5562 + vertex 408.664 187.893 70.6059 + endloop + endfacet + facet normal -0.933368 -0.205123 0.294531 + outer loop + vertex 407.726 188.359 67.1897 + vertex 407.16 187.924 65.0928 + vertex 408.557 184.585 67.1964 + endloop + endfacet + facet normal -0.933742 -0.206749 0.292199 + outer loop + vertex 408.557 184.585 67.1964 + vertex 407.16 187.924 65.0928 + vertex 408.149 183.475 65.1056 + endloop + endfacet + facet normal -0.950281 -0.21782 0.222532 + outer loop + vertex 408.545 186.317 68.5562 + vertex 409.486 182.549 68.8865 + vertex 408.664 187.893 70.6059 + endloop + endfacet + facet normal -0.930049 -0.216677 0.296749 + outer loop + vertex 408.557 184.585 67.1964 + vertex 408.149 183.475 65.1056 + vertex 409.604 180.117 67.2138 + endloop + endfacet + facet normal -0.93047 -0.218564 0.294033 + outer loop + vertex 409.604 180.117 67.2138 + vertex 408.149 183.475 65.1056 + vertex 409.245 178.802 65.1004 + endloop + endfacet + facet normal -0.956296 -0.223264 0.188813 + outer loop + vertex 409.486 182.549 68.8865 + vertex 410.486 178.112 68.7008 + vertex 410.485 180.064 71.0059 + endloop + endfacet + facet normal -0.929741 -0.220337 0.295013 + outer loop + vertex 409.604 180.117 67.2138 + vertex 409.245 178.802 65.1004 + vertex 410.866 175.019 67.3843 + endloop + endfacet + facet normal -0.930048 -0.221648 0.293059 + outer loop + vertex 410.866 175.019 67.3843 + vertex 409.245 178.802 65.1004 + vertex 410.341 174.164 65.0716 + endloop + endfacet + facet normal -0.954069 -0.228749 0.193458 + outer loop + vertex 410.486 178.112 68.7008 + vertex 411.364 174.877 69.2051 + vertex 410.485 180.064 71.0059 + endloop + endfacet + facet normal -0.960035 -0.218744 0.174594 + outer loop + vertex 411.364 174.877 69.2051 + vertex 412.047 171.436 68.6525 + vertex 412.359 171.925 70.9815 + endloop + endfacet + facet normal -0.930171 -0.221274 0.292949 + outer loop + vertex 410.866 175.019 67.3843 + vertex 410.341 174.164 65.0716 + vertex 411.915 170.302 67.1499 + endloop + endfacet + facet normal -0.929705 -0.219627 0.295657 + outer loop + vertex 411.915 170.302 67.1499 + vertex 410.341 174.164 65.0716 + vertex 411.369 169.792 65.0548 + endloop + endfacet + facet normal -0.958329 -0.225225 0.175726 + outer loop + vertex 412.047 171.436 68.6525 + vertex 413.068 167.227 68.8264 + vertex 412.359 171.925 70.9815 + endloop + endfacet + facet normal -0.930014 -0.218557 0.295477 + outer loop + vertex 411.915 170.302 67.1499 + vertex 411.369 169.792 65.0548 + vertex 412.9 166.102 67.144 + endloop + endfacet + facet normal -0.92988 -0.218052 0.29627 + outer loop + vertex 412.9 166.102 67.144 + vertex 411.369 169.792 65.0548 + vertex 412.362 165.592 65.0806 + endloop + endfacet + facet normal -0.958815 -0.222915 0.17602 + outer loop + vertex 413.068 167.227 68.8264 + vertex 413.93 163.279 68.525 + vertex 414.451 162.73 70.6642 + endloop + endfacet + facet normal -0.929791 -0.218359 0.296323 + outer loop + vertex 412.9 166.102 67.144 + vertex 412.362 165.592 65.0806 + vertex 413.827 162.138 67.1317 + endloop + endfacet + facet normal -0.929595 -0.217565 0.29752 + outer loop + vertex 413.827 162.138 67.1317 + vertex 412.362 165.592 65.0806 + vertex 413.353 161.363 65.0842 + endloop + endfacet + facet normal -0.958378 -0.225359 0.175287 + outer loop + vertex 413.93 163.279 68.525 + vertex 414.677 160.114 68.5397 + vertex 414.451 162.73 70.6642 + endloop + endfacet + facet normal -0.929619 -0.217494 0.297499 + outer loop + vertex 413.827 162.138 67.1317 + vertex 413.353 161.363 65.0842 + vertex 414.809 158.027 67.1951 + endloop + endfacet + facet normal -0.929794 -0.218284 0.296371 + outer loop + vertex 414.809 158.027 67.1951 + vertex 413.353 161.363 65.0842 + vertex 414.407 156.897 65.1023 + endloop + endfacet + facet normal -0.957297 -0.227644 0.178216 + outer loop + vertex 414.677 160.114 68.5397 + vertex 415.635 156.375 68.9092 + vertex 414.451 162.73 70.6642 + endloop + endfacet + facet normal -0.930167 -0.217308 0.295916 + outer loop + vertex 414.809 158.027 67.1951 + vertex 414.407 156.897 65.1023 + vertex 416.044 153.073 67.44 + endloop + endfacet + facet normal -0.93043 -0.218434 0.294257 + outer loop + vertex 416.044 153.073 67.44 + vertex 414.407 156.897 65.1023 + vertex 415.49 152.275 65.0953 + endloop + endfacet + facet normal -0.960047 -0.229842 0.159634 + outer loop + vertex 415.635 156.375 68.9092 + vertex 416.516 152.731 68.9599 + vertex 416.546 153.984 70.9439 + endloop + endfacet + facet normal -0.962659 -0.222101 0.154784 + outer loop + vertex 416.516 152.731 68.9599 + vertex 417.295 149.313 68.8961 + vertex 416.546 153.984 70.9439 + endloop + endfacet + facet normal -0.929792 -0.22043 0.294785 + outer loop + vertex 416.044 153.073 67.44 + vertex 415.49 152.275 65.0953 + vertex 417.083 148.334 67.1724 + endloop + endfacet + facet normal -0.929366 -0.218989 0.29719 + outer loop + vertex 417.083 148.334 67.1724 + vertex 415.49 152.275 65.0953 + vertex 416.548 147.753 65.0709 + endloop + endfacet + facet normal -0.959471 -0.22222 0.1733 + outer loop + vertex 417.295 149.313 68.8961 + vertex 418.14 145.357 68.5043 + vertex 418.63 144.92 70.6586 + endloop + endfacet + facet normal -0.929013 -0.220165 0.297426 + outer loop + vertex 417.083 148.334 67.1724 + vertex 416.548 147.753 65.0709 + vertex 418.055 144.138 67.1045 + endloop + endfacet + facet normal -0.928717 -0.219067 0.299157 + outer loop + vertex 418.055 144.138 67.1045 + vertex 416.548 147.753 65.0709 + vertex 417.595 143.315 65.072 + endloop + endfacet + facet normal -0.958761 -0.225969 0.172378 + outer loop + vertex 418.14 145.357 68.5043 + vertex 418.893 142.157 68.4993 + vertex 418.63 144.92 70.6586 + endloop + endfacet + facet normal -0.928903 -0.218522 0.298978 + outer loop + vertex 418.055 144.138 67.1045 + vertex 417.595 143.315 65.072 + vertex 419.051 139.987 67.1627 + endloop + endfacet + facet normal -0.929221 -0.219941 0.296942 + outer loop + vertex 419.051 139.987 67.1627 + vertex 417.595 143.315 65.072 + vertex 418.671 138.787 65.0865 + endloop + endfacet + facet normal -0.943133 -0.227348 0.242516 + outer loop + vertex 420.732 134.893 68.9482 + vertex 419.858 138.455 68.8855 + vertex 420.283 135.122 67.4142 + endloop + endfacet + facet normal -0.956541 -0.230561 0.178525 + outer loop + vertex 418.893 142.157 68.4993 + vertex 419.858 138.455 68.8855 + vertex 418.63 144.92 70.6586 + endloop + endfacet + facet normal -0.966997 -0.227371 0.114979 + outer loop + vertex 419.358 144.116 75.1879 + vertex 417.285 152.917 75.1587 + vertex 418.63 144.92 70.6586 + endloop + endfacet + facet normal -0.946044 -0.305051 0.109292 + outer loop + vertex 427.646 113.962 76.3777 + vertex 425.972 119.177 76.4408 + vertex 427.069 114.67 73.3589 + endloop + endfacet + facet normal -0.94799 -0.301191 0.102954 + outer loop + vertex 427.069 114.67 73.3589 + vertex 425.972 119.177 76.4408 + vertex 425.764 118.901 73.7227 + endloop + endfacet + facet normal -0.956371 -0.274198 0.100851 + outer loop + vertex 425.764 118.901 73.7227 + vertex 425.972 119.177 76.4408 + vertex 424.134 125.198 75.378 + endloop + endfacet + facet normal -0.957566 -0.281247 0.0629852 + outer loop + vertex 424.566 125.134 81.6728 + vertex 424.134 125.198 75.378 + vertex 425.972 119.177 76.4408 + endloop + endfacet + facet normal -0.953224 -0.292348 0.0767911 + outer loop + vertex 426.548 118.093 79.4619 + vertex 424.566 125.134 81.6728 + vertex 425.972 119.177 76.4408 + endloop + endfacet + facet normal -0.958819 -0.281547 0.0373809 + outer loop + vertex 426.548 118.093 79.4619 + vertex 426.448 118.959 83.4229 + vertex 424.566 125.134 81.6728 + endloop + endfacet + facet normal -0.956912 -0.290347 0.00428076 + outer loop + vertex 424.607 125.108 88.9966 + vertex 424.566 125.134 81.6728 + vertex 426.448 118.959 83.4229 + endloop + endfacet + facet normal -0.956406 -0.291974 0.00624226 + outer loop + vertex 426.74 118.078 86.9462 + vertex 424.607 125.108 88.9966 + vertex 426.448 118.959 83.4229 + endloop + endfacet + facet normal -0.950343 -0.311202 0.000929301 + outer loop + vertex 428.117 113.862 83.6443 + vertex 426.74 118.078 86.9462 + vertex 426.448 118.959 83.4229 + endloop + endfacet + facet normal -0.950109 -0.309472 0.0389831 + outer loop + vertex 428.117 113.862 83.6443 + vertex 426.448 118.959 83.4229 + vertex 427.971 113.84 79.911 + endloop + endfacet + facet normal -0.951329 -0.308158 -0.00336907 + outer loop + vertex 428.111 113.838 87.4048 + vertex 426.74 118.078 86.9462 + vertex 428.117 113.862 83.6443 + endloop + endfacet + facet normal -0.936859 -0.349689 -0.00360429 + outer loop + vertex 429.726 109.552 83.6905 + vertex 428.111 113.838 87.4048 + vertex 428.117 113.862 83.6443 + endloop + endfacet + facet normal -0.950015 -0.310691 -0.0307148 + outer loop + vertex 428.111 113.838 87.4048 + vertex 426.342 118.897 90.9663 + vertex 426.74 118.078 86.9462 + endloop + endfacet + facet normal -0.951684 -0.304401 -0.0404784 + outer loop + vertex 427.98 113.751 91.1522 + vertex 426.342 118.897 90.9663 + vertex 428.111 113.838 87.4048 + endloop + endfacet + facet normal -0.949813 -0.304874 -0.0700538 + outer loop + vertex 427.98 113.751 91.1522 + vertex 426.403 117.905 94.4604 + vertex 426.342 118.897 90.9663 + endloop + endfacet + facet normal -0.957358 -0.281864 -0.0633898 + outer loop + vertex 426.403 117.905 94.4604 + vertex 424.2 124.934 96.4781 + vertex 426.342 118.897 90.9663 + endloop + endfacet + facet normal -0.956487 -0.285803 -0.0587375 + outer loop + vertex 424.2 124.934 96.4781 + vertex 424.607 125.108 88.9966 + vertex 426.342 118.897 90.9663 + endloop + endfacet + facet normal -0.967138 -0.247447 -0.0584294 + outer loop + vertex 424.2 124.934 96.4781 + vertex 421.767 134.63 95.6825 + vertex 424.607 125.108 88.9966 + endloop + endfacet + facet normal -0.965692 -0.255529 -0.0463042 + outer loop + vertex 424.607 125.108 88.9966 + vertex 421.767 134.63 95.6825 + vertex 422.096 134.738 88.2274 + endloop + endfacet + facet normal -0.971791 -0.231271 -0.0462201 + outer loop + vertex 421.767 134.63 95.6825 + vertex 419.572 143.944 95.2249 + vertex 422.096 134.738 88.2274 + endloop + endfacet + facet normal -0.970855 -0.236465 -0.0390493 + outer loop + vertex 422.096 134.738 88.2274 + vertex 419.572 143.944 95.2249 + vertex 419.857 144 87.8011 + endloop + endfacet + facet normal -0.974013 -0.223099 -0.0390702 + outer loop + vertex 419.572 143.944 95.2249 + vertex 417.535 152.86 95.1021 + vertex 419.857 144 87.8011 + endloop + endfacet + facet normal -0.973331 -0.226824 -0.034333 + outer loop + vertex 419.857 144 87.8011 + vertex 417.535 152.86 95.1021 + vertex 417.793 152.876 87.6806 + endloop + endfacet + facet normal -0.974858 -0.220159 -0.0343715 + outer loop + vertex 417.535 152.86 95.1021 + vertex 415.565 161.574 95.1659 + vertex 417.793 152.876 87.6806 + endloop + endfacet + facet normal -0.974367 -0.222796 -0.0311601 + outer loop + vertex 417.793 152.876 87.6806 + vertex 415.565 161.574 95.1659 + vertex 415.803 161.576 87.7095 + endloop + endfacet + facet normal -0.975232 -0.218976 -0.031187 + outer loop + vertex 415.565 161.574 95.1659 + vertex 413.604 170.296 95.2381 + vertex 415.803 161.576 87.7095 + endloop + endfacet + facet normal -0.974795 -0.221292 -0.0283775 + outer loop + vertex 415.803 161.576 87.7095 + vertex 413.604 170.296 95.2381 + vertex 413.822 170.299 87.7377 + endloop + endfacet + facet normal -0.975992 -0.215947 -0.0284101 + outer loop + vertex 413.604 170.296 95.2381 + vertex 411.653 179.11 95.2454 + vertex 413.822 170.299 87.7377 + endloop + endfacet + facet normal -0.975525 -0.218419 -0.0253734 + outer loop + vertex 413.822 170.299 87.7377 + vertex 411.653 179.11 95.2454 + vertex 411.844 179.129 87.7441 + endloop + endfacet + facet normal -0.978717 -0.203637 -0.0254169 + outer loop + vertex 411.653 179.11 95.2454 + vertex 409.791 188.051 95.3148 + vertex 411.844 179.129 87.7441 + endloop + endfacet + facet normal -0.97872 -0.203617 -0.025441 + outer loop + vertex 411.844 179.129 87.7441 + vertex 409.791 188.051 95.3148 + vertex 409.972 188.115 87.8636 + endloop + endfacet + facet normal -0.987055 -0.158379 -0.0252556 + outer loop + vertex 409.791 188.051 95.3148 + vertex 408.303 197.238 95.8584 + vertex 409.972 188.115 87.8636 + endloop + endfacet + facet normal -0.987796 -0.152375 -0.0322617 + outer loop + vertex 409.972 188.115 87.8636 + vertex 408.303 197.238 95.8584 + vertex 408.53 197.401 88.1358 + endloop + endfacet + facet normal -0.98442 -0.154476 -0.0839919 + outer loop + vertex 409.791 188.051 95.3148 + vertex 407.716 196.998 103.185 + vertex 408.303 197.238 95.8584 + endloop + endfacet + facet normal -0.983929 -0.161795 -0.0755423 + outer loop + vertex 409.244 187.87 102.836 + vertex 407.716 196.998 103.185 + vertex 409.791 188.051 95.3148 + endloop + endfacet + facet normal -0.979136 -0.159049 -0.126476 + outer loop + vertex 409.244 187.87 102.836 + vertex 406.869 196.709 110.104 + vertex 407.716 196.998 103.185 + endloop + endfacet + facet normal -0.979132 -0.159639 -0.125757 + outer loop + vertex 408.338 187.557 110.287 + vertex 406.869 196.709 110.104 + vertex 409.244 187.87 102.836 + endloop + endfacet + facet normal -0.971526 -0.200311 -0.126541 + outer loop + vertex 411.086 178.926 102.85 + vertex 408.338 187.557 110.287 + vertex 409.244 187.87 102.836 + endloop + endfacet + facet normal -0.97645 -0.20125 -0.0777398 + outer loop + vertex 411.086 178.926 102.85 + vertex 409.244 187.87 102.836 + vertex 411.653 179.11 95.2454 + endloop + endfacet + facet normal -0.971714 -0.196381 -0.131172 + outer loop + vertex 410.149 178.577 110.315 + vertex 408.338 187.557 110.287 + vertex 411.086 178.926 102.85 + endloop + endfacet + facet normal -0.968595 -0.211045 -0.131466 + outer loop + vertex 413.016 170.092 102.809 + vertex 410.149 178.577 110.315 + vertex 411.086 178.926 102.85 + endloop + endfacet + facet normal -0.973792 -0.212415 -0.0812912 + outer loop + vertex 413.016 170.092 102.809 + vertex 411.086 178.926 102.85 + vertex 413.604 170.296 95.2381 + endloop + endfacet + facet normal -0.968732 -0.208717 -0.134149 + outer loop + vertex 412.067 169.721 110.242 + vertex 410.149 178.577 110.315 + vertex 413.016 170.092 102.809 + endloop + endfacet + facet normal -0.967751 -0.213159 -0.134246 + outer loop + vertex 414.956 161.356 102.695 + vertex 412.067 169.721 110.242 + vertex 413.016 170.092 102.809 + endloop + endfacet + facet normal -0.972934 -0.214951 -0.0848229 + outer loop + vertex 414.956 161.356 102.695 + vertex 413.016 170.092 102.809 + vertex 415.565 161.574 95.1659 + endloop + endfacet + facet normal -0.967832 -0.211845 -0.135733 + outer loop + vertex 413.998 160.979 110.117 + vertex 412.067 169.721 110.242 + vertex 414.956 161.356 102.695 + endloop + endfacet + facet normal -0.967141 -0.214933 -0.1358 + outer loop + vertex 416.909 152.631 102.601 + vertex 413.998 160.979 110.117 + vertex 414.956 161.356 102.695 + endloop + endfacet + facet normal -0.972302 -0.216608 -0.0878071 + outer loop + vertex 416.909 152.631 102.601 + vertex 414.956 161.356 102.695 + vertex 417.535 152.86 95.1021 + endloop + endfacet + facet normal -0.967317 -0.211989 -0.139138 + outer loop + vertex 415.927 152.251 110.007 + vertex 413.998 160.979 110.117 + vertex 416.909 152.631 102.601 + endloop + endfacet + facet normal -0.965896 -0.218286 -0.139272 + outer loop + vertex 418.915 143.701 102.682 + vertex 415.927 152.251 110.007 + vertex 416.909 152.631 102.601 + endloop + endfacet + facet normal -0.971292 -0.219074 -0.092723 + outer loop + vertex 418.915 143.701 102.682 + vertex 416.909 152.631 102.601 + vertex 419.572 143.944 95.2249 + endloop + endfacet + facet normal -0.966056 -0.215123 -0.14303 + outer loop + vertex 417.908 143.32 110.057 + vertex 415.927 152.251 110.007 + vertex 418.915 143.701 102.682 + endloop + endfacet + facet normal -0.963212 -0.227367 -0.143273 + outer loop + vertex 421.059 134.36 103.09 + vertex 417.908 143.32 110.057 + vertex 418.915 143.701 102.682 + endloop + endfacet + facet normal -0.968716 -0.226777 -0.100804 + outer loop + vertex 421.059 134.36 103.09 + vertex 418.915 143.701 102.682 + vertex 421.767 134.63 95.6825 + endloop + endfacet + facet normal -0.962978 -0.249904 -0.1011 + outer loop + vertex 424.2 124.934 96.4781 + vertex 421.059 134.36 103.09 + vertex 421.767 134.63 95.6825 + endloop + endfacet + facet normal -0.963667 -0.242501 -0.111981 + outer loop + vertex 423.424 124.631 103.808 + vertex 421.059 134.36 103.09 + vertex 424.2 124.934 96.4781 + endloop + endfacet + facet normal -0.958237 -0.243933 -0.14926 + outer loop + vertex 423.424 124.631 103.808 + vertex 420.014 133.981 110.417 + vertex 421.059 134.36 103.09 + endloop + endfacet + facet normal -0.963369 -0.223037 -0.148912 + outer loop + vertex 420.014 133.981 110.417 + vertex 417.908 143.32 110.057 + vertex 421.059 134.36 103.09 + endloop + endfacet + facet normal -0.95728 -0.223017 -0.184062 + outer loop + vertex 420.014 133.981 110.417 + vertex 416.587 142.886 117.452 + vertex 417.908 143.32 110.057 + endloop + endfacet + facet normal -0.959931 -0.21149 -0.18386 + outer loop + vertex 416.587 142.886 117.452 + vertex 414.629 151.813 117.406 + vertex 417.908 143.32 110.057 + endloop + endfacet + facet normal -0.953545 -0.210252 -0.215746 + outer loop + vertex 416.587 142.886 117.452 + vertex 413.035 151.343 124.91 + vertex 414.629 151.813 117.406 + endloop + endfacet + facet normal -0.954496 -0.205961 -0.215679 + outer loop + vertex 413.035 151.343 124.91 + vertex 411.13 160.063 125.012 + vertex 414.629 151.813 117.406 + endloop + endfacet + facet normal -0.954528 -0.207245 -0.214301 + outer loop + vertex 414.629 151.813 117.406 + vertex 411.13 160.063 125.012 + vertex 412.711 160.533 117.517 + endloop + endfacet + facet normal -0.961019 -0.209097 -0.180889 + outer loop + vertex 414.629 151.813 117.406 + vertex 412.711 160.533 117.517 + vertex 415.927 152.251 110.007 + endloop + endfacet + facet normal -0.954894 -0.205581 -0.214274 + outer loop + vertex 411.13 160.063 125.012 + vertex 409.227 168.803 125.109 + vertex 412.711 160.533 117.517 + endloop + endfacet + facet normal -0.954922 -0.206663 -0.213107 + outer loop + vertex 412.711 160.533 117.517 + vertex 409.227 168.803 125.109 + vertex 410.794 169.274 117.629 + endloop + endfacet + facet normal -0.961359 -0.208504 -0.179763 + outer loop + vertex 412.711 160.533 117.517 + vertex 410.794 169.274 117.629 + vertex 413.998 160.979 110.117 + endloop + endfacet + facet normal -0.9557 -0.203097 -0.213046 + outer loop + vertex 409.227 168.803 125.109 + vertex 407.331 177.671 125.16 + vertex 410.794 169.274 117.629 + endloop + endfacet + facet normal -0.955716 -0.203568 -0.212528 + outer loop + vertex 410.794 169.274 117.629 + vertex 407.331 177.671 125.16 + vertex 408.89 178.139 117.702 + endloop + endfacet + facet normal -0.962341 -0.205273 -0.17822 + outer loop + vertex 410.794 169.274 117.629 + vertex 408.89 178.139 117.702 + vertex 412.067 169.721 110.242 + endloop + endfacet + facet normal -0.958912 -0.188265 -0.212234 + outer loop + vertex 407.331 177.671 125.16 + vertex 405.54 186.687 125.252 + vertex 408.89 178.139 117.702 + endloop + endfacet + facet normal -0.959024 -0.190647 -0.209588 + outer loop + vertex 408.89 178.139 117.702 + vertex 405.54 186.687 125.252 + vertex 407.091 187.146 117.741 + endloop + endfacet + facet normal -0.96548 -0.19208 -0.175936 + outer loop + vertex 408.89 178.139 117.702 + vertex 407.091 187.146 117.741 + vertex 410.149 178.577 110.315 + endloop + endfacet + facet normal -0.966858 -0.147281 -0.208554 + outer loop + vertex 405.54 186.687 125.252 + vertex 404.11 195.9 125.378 + vertex 407.091 187.146 117.741 + endloop + endfacet + facet normal -0.967367 -0.15359 -0.201522 + outer loop + vertex 407.091 187.146 117.741 + vertex 404.11 195.9 125.378 + vertex 405.665 196.34 117.578 + endloop + endfacet + facet normal -0.973121 -0.153947 -0.171276 + outer loop + vertex 407.091 187.146 117.741 + vertex 405.665 196.34 117.578 + vertex 408.338 187.557 110.287 + endloop + endfacet + facet normal -0.960632 -0.145936 -0.236407 + outer loop + vertex 405.54 186.687 125.252 + vertex 402.261 195.409 133.196 + vertex 404.11 195.9 125.378 + endloop + endfacet + facet normal -0.960227 -0.142285 -0.240248 + outer loop + vertex 403.721 186.198 132.813 + vertex 402.261 195.409 133.196 + vertex 405.54 186.687 125.252 + endloop + endfacet + facet normal -0.953064 -0.139977 -0.268467 + outer loop + vertex 403.721 186.198 132.813 + vertex 400.265 194.907 140.541 + vertex 402.261 195.409 133.196 + endloop + endfacet + facet normal -0.952897 -0.138882 -0.269627 + outer loop + vertex 401.631 185.673 140.472 + vertex 400.265 194.907 140.541 + vertex 403.721 186.198 132.813 + endloop + endfacet + facet normal -0.944885 -0.184366 -0.270558 + outer loop + vertex 405.499 177.177 132.751 + vertex 401.631 185.673 140.472 + vertex 403.721 186.198 132.813 + endloop + endfacet + facet normal -0.952298 -0.186024 -0.241915 + outer loop + vertex 405.499 177.177 132.751 + vertex 403.721 186.198 132.813 + vertex 407.331 177.671 125.16 + endloop + endfacet + facet normal -0.944824 -0.183788 -0.271164 + outer loop + vertex 403.393 176.651 140.446 + vertex 401.631 185.673 140.472 + vertex 405.499 177.177 132.751 + endloop + endfacet + facet normal -0.94174 -0.198745 -0.271343 + outer loop + vertex 407.38 168.309 132.719 + vertex 403.393 176.651 140.446 + vertex 405.499 177.177 132.751 + endloop + endfacet + facet normal -0.949013 -0.200389 -0.243347 + outer loop + vertex 407.38 168.309 132.719 + vertex 405.499 177.177 132.751 + vertex 409.227 168.803 125.109 + endloop + endfacet + facet normal -0.941677 -0.198035 -0.272077 + outer loop + vertex 405.269 167.777 140.412 + vertex 403.393 176.651 140.446 + vertex 407.38 168.309 132.719 + endloop + endfacet + facet normal -0.94101 -0.20114 -0.272109 + outer loop + vertex 409.276 159.566 132.625 + vertex 405.269 167.777 140.412 + vertex 407.38 168.309 132.719 + endloop + endfacet + facet normal -0.948229 -0.203007 -0.244233 + outer loop + vertex 409.276 159.566 132.625 + vertex 407.38 168.309 132.719 + vertex 411.13 160.063 125.012 + endloop + endfacet + facet normal -0.940888 -0.199638 -0.27363 + outer loop + vertex 407.154 159.029 140.311 + vertex 405.269 167.777 140.412 + vertex 409.276 159.566 132.625 + endloop + endfacet + facet normal -0.940572 -0.201103 -0.273645 + outer loop + vertex 411.17 150.845 132.525 + vertex 407.154 159.029 140.311 + vertex 409.276 159.566 132.625 + endloop + endfacet + facet normal -0.947905 -0.203019 -0.245478 + outer loop + vertex 411.17 150.845 132.525 + vertex 409.276 159.566 132.625 + vertex 413.035 151.343 124.91 + endloop + endfacet + facet normal -0.946945 -0.207391 -0.245528 + outer loop + vertex 414.974 142.417 124.97 + vertex 411.17 150.845 132.525 + vertex 413.035 151.343 124.91 + endloop + endfacet + facet normal -0.946838 -0.205724 -0.247335 + outer loop + vertex 413.091 141.915 132.598 + vertex 411.17 150.845 132.525 + vertex 414.974 142.417 124.97 + endloop + endfacet + facet normal -0.944247 -0.217178 -0.247449 + outer loop + vertex 417.019 133.088 125.357 + vertex 413.091 141.915 132.598 + vertex 414.974 142.417 124.97 + endloop + endfacet + facet normal -0.95083 -0.217502 -0.220488 + outer loop + vertex 417.019 133.088 125.357 + vertex 414.974 142.417 124.97 + vertex 418.663 133.553 117.809 + endloop + endfacet + facet normal -0.946117 -0.237003 -0.220664 + outer loop + vertex 420.941 123.846 118.466 + vertex 417.019 133.088 125.357 + vertex 418.663 133.553 117.809 + endloop + endfacet + facet normal -0.950943 -0.219791 -0.217714 + outer loop + vertex 418.663 133.553 117.809 + vertex 414.974 142.417 124.97 + vertex 416.587 142.886 117.452 + endloop + endfacet + facet normal -0.944038 -0.214598 -0.25048 + outer loop + vertex 415.102 132.573 133.021 + vertex 413.091 141.915 132.598 + vertex 417.019 133.088 125.357 + endloop + endfacet + facet normal -0.939257 -0.234492 -0.250621 + outer loop + vertex 419.243 123.369 126.112 + vertex 415.102 132.573 133.021 + vertex 417.019 133.088 125.357 + endloop + endfacet + facet normal -0.93678 -0.214222 -0.27668 + outer loop + vertex 415.102 132.573 133.021 + vertex 410.946 141.362 140.288 + vertex 413.091 141.915 132.598 + endloop + endfacet + facet normal -0.939354 -0.202778 -0.276576 + outer loop + vertex 410.946 141.362 140.288 + vertex 409.039 150.3 140.212 + vertex 413.091 141.915 132.598 + endloop + endfacet + facet normal -0.931629 -0.201351 -0.302532 + outer loop + vertex 410.946 141.362 140.288 + vertex 406.66 149.714 147.927 + vertex 409.039 150.3 140.212 + endloop + endfacet + facet normal -0.932522 -0.197233 -0.302494 + outer loop + vertex 406.66 149.714 147.927 + vertex 404.779 158.449 148.031 + vertex 409.039 150.3 140.212 + endloop + endfacet + facet normal -0.932593 -0.197898 -0.30184 + outer loop + vertex 409.039 150.3 140.212 + vertex 404.779 158.449 148.031 + vertex 407.154 159.029 140.311 + endloop + endfacet + facet normal -0.932872 -0.196596 -0.301828 + outer loop + vertex 404.779 158.449 148.031 + vertex 402.9 167.202 148.138 + vertex 407.154 159.029 140.311 + endloop + endfacet + facet normal -0.924686 -0.194525 -0.327284 + outer loop + vertex 404.779 158.449 148.031 + vertex 400.291 166.582 155.878 + vertex 402.9 167.202 148.138 + endloop + endfacet + facet normal -0.925147 -0.192355 -0.327265 + outer loop + vertex 400.291 166.582 155.878 + vertex 398.425 175.464 155.933 + vertex 402.9 167.202 148.138 + endloop + endfacet + facet normal -0.925254 -0.193127 -0.326508 + outer loop + vertex 402.9 167.202 148.138 + vertex 398.425 175.464 155.933 + vertex 401.03 176.079 148.185 + endloop + endfacet + facet normal -0.933539 -0.195007 -0.300793 + outer loop + vertex 402.9 167.202 148.138 + vertex 401.03 176.079 148.185 + vertex 405.269 167.777 140.412 + endloop + endfacet + facet normal -0.928194 -0.178742 -0.326354 + outer loop + vertex 398.425 175.464 155.933 + vertex 396.666 184.49 155.99 + vertex 401.03 176.079 148.185 + endloop + endfacet + facet normal -0.928326 -0.179593 -0.325512 + outer loop + vertex 401.03 176.079 148.185 + vertex 396.666 184.49 155.99 + vertex 399.275 185.105 148.211 + endloop + endfacet + facet normal -0.936747 -0.181306 -0.299387 + outer loop + vertex 401.03 176.079 148.185 + vertex 399.275 185.105 148.211 + vertex 403.393 176.651 140.446 + endloop + endfacet + facet normal -0.935969 -0.136254 -0.324648 + outer loop + vertex 396.666 184.49 155.99 + vertex 395.318 193.73 155.999 + vertex 399.275 185.105 148.211 + endloop + endfacet + facet normal -0.935927 -0.136048 -0.324855 + outer loop + vertex 399.275 185.105 148.211 + vertex 395.318 193.73 155.999 + vertex 397.868 194.33 148.402 + endloop + endfacet + facet normal -0.944656 -0.137942 -0.297653 + outer loop + vertex 399.275 185.105 148.211 + vertex 397.868 194.33 148.402 + vertex 401.631 185.673 140.472 + endloop + endfacet + facet normal -0.927385 -0.134979 -0.348909 + outer loop + vertex 396.666 184.49 155.99 + vertex 392.358 193.042 164.133 + vertex 395.318 193.73 155.999 + endloop + endfacet + facet normal -0.927383 -0.134966 -0.348921 + outer loop + vertex 393.851 183.831 163.728 + vertex 392.358 193.042 164.133 + vertex 396.666 184.49 155.99 + endloop + endfacet + facet normal -0.919504 -0.132763 -0.36998 + outer loop + vertex 393.851 183.831 163.728 + vertex 389.521 192.382 171.422 + vertex 392.358 193.042 164.133 + endloop + endfacet + facet normal -0.919491 -0.132707 -0.370035 + outer loop + vertex 390.855 183.132 171.422 + vertex 389.521 192.382 171.422 + vertex 393.851 183.831 163.728 + endloop + endfacet + facet normal -0.912029 -0.1749 -0.370962 + outer loop + vertex 395.606 174.802 163.669 + vertex 390.855 183.132 171.422 + vertex 393.851 183.831 163.728 + endloop + endfacet + facet normal -0.919879 -0.17656 -0.350212 + outer loop + vertex 395.606 174.802 163.669 + vertex 393.851 183.831 163.728 + vertex 398.425 175.464 155.933 + endloop + endfacet + facet normal -0.912039 -0.174949 -0.370915 + outer loop + vertex 392.61 174.098 171.368 + vertex 390.855 183.132 171.422 + vertex 395.606 174.802 163.669 + endloop + endfacet + facet normal -0.909184 -0.188902 -0.371079 + outer loop + vertex 397.474 165.916 163.617 + vertex 392.61 174.098 171.368 + vertex 395.606 174.802 163.669 + endloop + endfacet + facet normal -0.91706 -0.190679 -0.350205 + outer loop + vertex 397.474 165.916 163.617 + vertex 395.606 174.802 163.669 + vertex 400.291 166.582 155.878 + endloop + endfacet + facet normal -0.916662 -0.192552 -0.350221 + outer loop + vertex 402.172 157.823 155.769 + vertex 397.474 165.916 163.617 + vertex 400.291 166.582 155.878 + endloop + endfacet + facet normal -0.916654 -0.192497 -0.350273 + outer loop + vertex 399.355 157.153 163.51 + vertex 397.474 165.916 163.617 + vertex 402.172 157.823 155.769 + endloop + endfacet + facet normal -0.91664 -0.19256 -0.350273 + outer loop + vertex 404.048 149.082 155.665 + vertex 399.355 157.153 163.51 + vertex 402.172 157.823 155.769 + endloop + endfacet + facet normal -0.924457 -0.194504 -0.327945 + outer loop + vertex 404.048 149.082 155.665 + vertex 402.172 157.823 155.769 + vertex 406.66 149.714 147.927 + endloop + endfacet + facet normal -0.923582 -0.198556 -0.32798 + outer loop + vertex 408.558 140.774 147.994 + vertex 404.048 149.082 155.665 + vertex 406.66 149.714 147.927 + endloop + endfacet + facet normal -0.923446 -0.197592 -0.328945 + outer loop + vertex 405.938 140.137 155.732 + vertex 404.048 149.082 155.665 + vertex 408.558 140.774 147.994 + endloop + endfacet + facet normal -0.920998 -0.208583 -0.329021 + outer loop + vertex 410.531 131.426 148.399 + vertex 405.938 140.137 155.732 + vertex 408.558 140.774 147.994 + endloop + endfacet + facet normal -0.928646 -0.209215 -0.306342 + outer loop + vertex 410.531 131.426 148.399 + vertex 408.558 140.774 147.994 + vertex 412.936 132.018 140.705 + endloop + endfacet + facet normal -0.923964 -0.228936 -0.306396 + outer loop + vertex 415.095 122.297 141.456 + vertex 410.531 131.426 148.399 + vertex 412.936 132.018 140.705 + endloop + endfacet + facet normal -0.928948 -0.211361 -0.303945 + outer loop + vertex 412.936 132.018 140.705 + vertex 408.558 140.774 147.994 + vertex 410.946 141.362 140.288 + endloop + endfacet + facet normal -0.92077 -0.207183 -0.330542 + outer loop + vertex 407.896 130.787 156.14 + vertex 405.938 140.137 155.732 + vertex 410.531 131.426 148.399 + endloop + endfacet + facet normal -0.916154 -0.226669 -0.330579 + outer loop + vertex 412.669 121.702 149.139 + vertex 407.896 130.787 156.14 + vertex 410.531 131.426 148.399 + endloop + endfacet + facet normal -0.913247 -0.206511 -0.351189 + outer loop + vertex 407.896 130.787 156.14 + vertex 403.113 139.461 163.477 + vertex 405.938 140.137 155.732 + endloop + endfacet + facet normal -0.915706 -0.195443 -0.35112 + outer loop + vertex 403.113 139.461 163.477 + vertex 401.23 148.409 163.406 + vertex 405.938 140.137 155.732 + endloop + endfacet + facet normal -0.908163 -0.194011 -0.370944 + outer loop + vertex 403.113 139.461 163.477 + vertex 398.237 147.698 171.106 + vertex 401.23 148.409 163.406 + endloop + endfacet + facet normal -0.908914 -0.190521 -0.370914 + outer loop + vertex 398.237 147.698 171.106 + vertex 396.362 156.44 171.211 + vertex 401.23 148.409 163.406 + endloop + endfacet + facet normal -0.908914 -0.190524 -0.370911 + outer loop + vertex 401.23 148.409 163.406 + vertex 396.362 156.44 171.211 + vertex 399.355 157.153 163.51 + endloop + endfacet + facet normal -0.908878 -0.190693 -0.370913 + outer loop + vertex 396.362 156.44 171.211 + vertex 394.479 165.207 171.317 + vertex 399.355 157.153 163.51 + endloop + endfacet + facet normal -0.901377 -0.188855 -0.389683 + outer loop + vertex 396.362 156.44 171.211 + vertex 391.345 164.457 178.93 + vertex 394.479 165.207 171.317 + endloop + endfacet + facet normal -0.901682 -0.187426 -0.389668 + outer loop + vertex 391.345 164.457 178.93 + vertex 389.474 173.353 178.981 + vertex 394.479 165.207 171.317 + endloop + endfacet + facet normal -0.901653 -0.187279 -0.389805 + outer loop + vertex 394.479 165.207 171.317 + vertex 389.474 173.353 178.981 + vertex 392.61 174.098 171.368 + endloop + endfacet + facet normal -0.904508 -0.17338 -0.389621 + outer loop + vertex 389.474 173.353 178.981 + vertex 387.715 182.391 179.042 + vertex 392.61 174.098 171.368 + endloop + endfacet + facet normal -0.897271 -0.171857 -0.406658 + outer loop + vertex 389.474 173.353 178.981 + vertex 384.474 181.612 186.523 + vertex 387.715 182.391 179.042 + endloop + endfacet + facet normal -0.904734 -0.130295 -0.405561 + outer loop + vertex 384.474 181.612 186.523 + vertex 383.104 190.863 186.607 + vertex 387.715 182.391 179.042 + endloop + endfacet + facet normal -0.904629 -0.129922 -0.405915 + outer loop + vertex 387.715 182.391 179.042 + vertex 383.104 190.863 186.607 + vertex 386.215 191.606 179.436 + endloop + endfacet + facet normal -0.911907 -0.131847 -0.38864 + outer loop + vertex 387.715 182.391 179.042 + vertex 386.215 191.606 179.436 + vertex 390.855 183.132 171.422 + endloop + endfacet + facet normal -0.897772 -0.129122 -0.421109 + outer loop + vertex 384.474 181.612 186.523 + vertex 379.682 190.026 194.158 + vertex 383.104 190.863 186.607 + endloop + endfacet + facet normal -0.897674 -0.128781 -0.421423 + outer loop + vertex 381.135 180.786 193.887 + vertex 379.682 190.026 194.158 + vertex 384.474 181.612 186.523 + endloop + endfacet + facet normal -0.890151 -0.170259 -0.422663 + outer loop + vertex 386.228 172.566 186.472 + vertex 381.135 180.786 193.887 + vertex 384.474 181.612 186.523 + endloop + endfacet + facet normal -0.890155 -0.170276 -0.422646 + outer loop + vertex 382.896 171.739 193.823 + vertex 381.135 180.786 193.887 + vertex 386.228 172.566 186.472 + endloop + endfacet + facet normal -0.887269 -0.184153 -0.422897 + outer loop + vertex 388.101 163.672 186.416 + vertex 382.896 171.739 193.823 + vertex 386.228 172.566 186.472 + endloop + endfacet + facet normal -0.894326 -0.18574 -0.40704 + outer loop + vertex 388.101 163.672 186.416 + vertex 386.228 172.566 186.472 + vertex 391.345 164.457 178.93 + endloop + endfacet + facet normal -0.894025 -0.187147 -0.407057 + outer loop + vertex 393.23 155.693 178.82 + vertex 388.101 163.672 186.416 + vertex 391.345 164.457 178.93 + endloop + endfacet + facet normal -0.894041 -0.187224 -0.406987 + outer loop + vertex 389.987 154.924 186.297 + vertex 388.101 163.672 186.416 + vertex 393.23 155.693 178.82 + endloop + endfacet + facet normal -0.894107 -0.186916 -0.406984 + outer loop + vertex 395.106 146.966 178.706 + vertex 389.987 154.924 186.297 + vertex 393.23 155.693 178.82 + endloop + endfacet + facet normal -0.901454 -0.188723 -0.389568 + outer loop + vertex 395.106 146.966 178.706 + vertex 393.23 155.693 178.82 + vertex 398.237 147.698 171.106 + endloop + endfacet + facet normal -0.900673 -0.192361 -0.389597 + outer loop + vertex 400.118 138.765 171.167 + vertex 395.106 146.966 178.706 + vertex 398.237 147.698 171.106 + endloop + endfacet + facet normal -0.900647 -0.192233 -0.389719 + outer loop + vertex 396.988 138.041 178.759 + vertex 395.106 146.966 178.706 + vertex 400.118 138.765 171.167 + endloop + endfacet + facet normal -0.898153 -0.203481 -0.389765 + outer loop + vertex 402.056 129.417 171.583 + vertex 396.988 138.041 178.759 + vertex 400.118 138.765 171.167 + endloop + endfacet + facet normal -0.905513 -0.204213 -0.371946 + outer loop + vertex 402.056 129.417 171.583 + vertex 400.118 138.765 171.167 + vertex 405.057 130.115 163.893 + endloop + endfacet + facet normal -0.900795 -0.224157 -0.371915 + outer loop + vertex 407.148 120.394 164.689 + vertex 402.056 129.417 171.583 + vertex 405.057 130.115 163.893 + endloop + endfacet + facet normal -0.90566 -0.204934 -0.37119 + outer loop + vertex 405.057 130.115 163.893 + vertex 400.118 138.765 171.167 + vertex 403.113 139.461 163.477 + endloop + endfacet + facet normal -0.898014 -0.202867 -0.390404 + outer loop + vertex 398.922 128.687 179.171 + vertex 396.988 138.041 178.759 + vertex 402.056 129.417 171.583 + endloop + endfacet + facet normal -0.893256 -0.222941 -0.390372 + outer loop + vertex 404.137 119.696 172.373 + vertex 398.922 128.687 179.171 + vertex 402.056 129.417 171.583 + endloop + endfacet + facet normal -0.893073 -0.222199 -0.391214 + outer loop + vertex 400.995 118.942 179.974 + vertex 398.922 128.687 179.171 + vertex 404.137 119.696 172.373 + endloop + endfacet + facet normal -0.885664 -0.221991 -0.407822 + outer loop + vertex 400.995 118.942 179.974 + vertex 395.669 127.831 186.702 + vertex 398.922 128.687 179.171 + endloop + endfacet + facet normal -0.890615 -0.201577 -0.407642 + outer loop + vertex 395.669 127.831 186.702 + vertex 393.746 137.259 186.24 + vertex 398.922 128.687 179.171 + endloop + endfacet + facet normal -0.883526 -0.200889 -0.423113 + outer loop + vertex 395.669 127.831 186.702 + vertex 390.41 136.352 193.637 + vertex 393.746 137.259 186.24 + endloop + endfacet + facet normal -0.886212 -0.189191 -0.422889 + outer loop + vertex 390.41 136.352 193.637 + vertex 388.536 145.407 193.514 + vertex 393.746 137.259 186.24 + endloop + endfacet + facet normal -0.886204 -0.189156 -0.422922 + outer loop + vertex 393.746 137.259 186.24 + vertex 388.536 145.407 193.514 + vertex 391.867 146.216 186.173 + endloop + endfacet + facet normal -0.89333 -0.190532 -0.407013 + outer loop + vertex 393.746 137.259 186.24 + vertex 391.867 146.216 186.173 + vertex 396.988 138.041 178.759 + endloop + endfacet + facet normal -0.887008 -0.185446 -0.422879 + outer loop + vertex 388.536 145.407 193.514 + vertex 386.657 154.131 193.63 + vertex 391.867 146.216 186.173 + endloop + endfacet + facet normal -0.887003 -0.185422 -0.4229 + outer loop + vertex 391.867 146.216 186.173 + vertex 386.657 154.131 193.63 + vertex 389.987 154.924 186.297 + endloop + endfacet + facet normal -0.886973 -0.185562 -0.422902 + outer loop + vertex 386.657 154.131 193.63 + vertex 384.769 162.858 193.759 + vertex 389.987 154.924 186.297 + endloop + endfacet + facet normal -0.880062 -0.183847 -0.437825 + outer loop + vertex 386.657 154.131 193.63 + vertex 381.369 162.015 200.949 + vertex 384.769 162.858 193.759 + endloop + endfacet + facet normal -0.880404 -0.182262 -0.437801 + outer loop + vertex 381.369 162.015 200.949 + vertex 379.498 170.878 201.022 + vertex 384.769 162.858 193.759 + endloop + endfacet + facet normal -0.880477 -0.182552 -0.437534 + outer loop + vertex 384.769 162.858 193.759 + vertex 379.498 170.878 201.022 + vertex 382.896 171.739 193.823 + endloop + endfacet + facet normal -0.883491 -0.168144 -0.437232 + outer loop + vertex 379.498 170.878 201.022 + vertex 377.747 179.924 201.08 + vertex 382.896 171.739 193.823 + endloop + endfacet + facet normal -0.877183 -0.166839 -0.450238 + outer loop + vertex 379.498 170.878 201.022 + vertex 374.303 179.014 208.127 + vertex 377.747 179.924 201.08 + endloop + endfacet + facet normal -0.884904 -0.125177 -0.448637 + outer loop + vertex 374.303 179.014 208.127 + vertex 372.909 188.286 208.29 + vertex 377.747 179.924 201.08 + endloop + endfacet + facet normal -0.885236 -0.126174 -0.447703 + outer loop + vertex 377.747 179.924 201.08 + vertex 372.909 188.286 208.29 + vertex 376.327 189.18 201.279 + endloop + endfacet + facet normal -0.891321 -0.127379 -0.43511 + outer loop + vertex 377.747 179.924 201.08 + vertex 376.327 189.18 201.279 + vertex 381.135 180.786 193.887 + endloop + endfacet + facet normal -0.879501 -0.124175 -0.459411 + outer loop + vertex 374.303 179.014 208.127 + vertex 369.393 187.325 215.281 + vertex 372.909 188.286 208.29 + endloop + endfacet + facet normal -0.879258 -0.123466 -0.460067 + outer loop + vertex 370.856 178.071 214.968 + vertex 369.393 187.325 215.281 + vertex 374.303 179.014 208.127 + endloop + endfacet + facet normal -0.871419 -0.165229 -0.461875 + outer loop + vertex 376.054 169.979 208.055 + vertex 370.856 178.071 214.968 + vertex 374.303 179.014 208.127 + endloop + endfacet + facet normal -0.870979 -0.163806 -0.46321 + outer loop + vertex 372.596 169.046 214.887 + vertex 370.856 178.071 214.968 + vertex 376.054 169.979 208.055 + endloop + endfacet + facet normal -0.867824 -0.178658 -0.46364 + outer loop + vertex 377.921 161.136 207.968 + vertex 372.596 169.046 214.887 + vertex 376.054 169.979 208.055 + endloop + endfacet + facet normal -0.873817 -0.18004 -0.451696 + outer loop + vertex 377.921 161.136 207.968 + vertex 376.054 169.979 208.055 + vertex 381.369 162.015 200.949 + endloop + endfacet + facet normal -0.873385 -0.182032 -0.451733 + outer loop + vertex 383.255 153.295 200.815 + vertex 377.921 161.136 207.968 + vertex 381.369 162.015 200.949 + endloop + endfacet + facet normal -0.87334 -0.181859 -0.451889 + outer loop + vertex 379.803 152.399 207.847 + vertex 377.921 161.136 207.968 + vertex 383.255 153.295 200.815 + endloop + endfacet + facet normal -0.873222 -0.1824 -0.4519 + outer loop + vertex 385.133 144.5 200.737 + vertex 379.803 152.399 207.847 + vertex 383.255 153.295 200.815 + endloop + endfacet + facet normal -0.88007 -0.183987 -0.437751 + outer loop + vertex 385.133 144.5 200.737 + vertex 383.255 153.295 200.815 + vertex 388.536 145.407 193.514 + endloop + endfacet + facet normal -0.873199 -0.18231 -0.451982 + outer loop + vertex 381.67 143.51 207.826 + vertex 379.803 152.399 207.847 + vertex 385.133 144.5 200.737 + endloop + endfacet + facet normal -0.872296 -0.186298 -0.452098 + outer loop + vertex 387.001 135.23 200.952 + vertex 381.67 143.51 207.826 + vertex 385.133 144.5 200.737 + endloop + endfacet + facet normal -0.879034 -0.187337 -0.438411 + outer loop + vertex 387.001 135.23 200.952 + vertex 385.133 144.5 200.737 + vertex 390.41 136.352 193.637 + endloop + endfacet + facet normal -0.876264 -0.198847 -0.438886 + outer loop + vertex 392.301 126.732 194.221 + vertex 387.001 135.23 200.952 + vertex 390.41 136.352 193.637 + endloop + endfacet + facet normal -0.875322 -0.195635 -0.442198 + outer loop + vertex 388.937 125.097 201.603 + vertex 387.001 135.23 200.952 + vertex 392.301 126.732 194.221 + endloop + endfacet + facet normal -0.868895 -0.218258 -0.44428 + outer loop + vertex 394.168 116.939 195.38 + vertex 388.937 125.097 201.603 + vertex 392.301 126.732 194.221 + endloop + endfacet + facet normal -0.876865 -0.21791 -0.428512 + outer loop + vertex 394.168 116.939 195.38 + vertex 392.301 126.732 194.221 + vertex 397.708 118.04 187.577 + endloop + endfacet + facet normal -0.87766 -0.22078 -0.425404 + outer loop + vertex 397.708 118.04 187.577 + vertex 392.301 126.732 194.221 + vertex 395.669 127.831 186.702 + endloop + endfacet + facet normal -0.864209 -0.202979 -0.460373 + outer loop + vertex 391.138 118.86 200.222 + vertex 388.937 125.097 201.603 + vertex 394.168 116.939 195.38 + endloop + endfacet + facet normal -0.867788 -0.206052 -0.452201 + outer loop + vertex 391.138 118.86 200.222 + vertex 389.31 118.885 203.717 + vertex 388.937 125.097 201.603 + endloop + endfacet + facet normal -0.864959 -0.207494 -0.456938 + outer loop + vertex 385.277 124.249 208.916 + vertex 388.937 125.097 201.603 + vertex 389.31 118.885 203.717 + endloop + endfacet + facet normal -0.865649 -0.210715 -0.454149 + outer loop + vertex 387.9 117.307 207.138 + vertex 385.277 124.249 208.916 + vertex 389.31 118.885 203.717 + endloop + endfacet + facet normal -0.857517 -0.230507 -0.459925 + outer loop + vertex 390.572 113.469 204.078 + vertex 387.9 117.307 207.138 + vertex 389.31 118.885 203.717 + endloop + endfacet + facet normal -0.861311 -0.206496 -0.464222 + outer loop + vertex 387.9 117.307 207.138 + vertex 385.798 117.61 210.903 + vertex 385.277 124.249 208.916 + endloop + endfacet + facet normal -0.85757 -0.208056 -0.470411 + outer loop + vertex 381.719 123.226 215.855 + vertex 385.277 124.249 208.916 + vertex 385.798 117.61 210.903 + endloop + endfacet + facet normal -0.85776 -0.208785 -0.469741 + outer loop + vertex 384.36 116.242 214.137 + vertex 381.719 123.226 215.855 + vertex 385.798 117.61 210.903 + endloop + endfacet + facet normal -0.849341 -0.230144 -0.47503 + outer loop + vertex 387.053 112.258 211.252 + vertex 384.36 116.242 214.137 + vertex 385.798 117.61 210.903 + endloop + endfacet + facet normal -0.852473 -0.203927 -0.481356 + outer loop + vertex 384.36 116.242 214.137 + vertex 382.255 116.647 217.693 + vertex 381.719 123.226 215.855 + endloop + endfacet + facet normal -0.849704 -0.204942 -0.4858 + outer loop + vertex 378.185 122.221 222.459 + vertex 381.719 123.226 215.855 + vertex 382.255 116.647 217.693 + endloop + endfacet + facet normal -0.849783 -0.205217 -0.485546 + outer loop + vertex 380.825 115.284 220.772 + vertex 378.185 122.221 222.459 + vertex 382.255 116.647 217.693 + endloop + endfacet + facet normal -0.840747 -0.22761 -0.491261 + outer loop + vertex 383.522 111.332 217.988 + vertex 380.825 115.284 220.772 + vertex 382.255 116.647 217.693 + endloop + endfacet + facet normal -0.844781 -0.200765 -0.496023 + outer loop + vertex 380.825 115.284 220.772 + vertex 378.72 115.637 224.214 + vertex 378.185 122.221 222.459 + endloop + endfacet + facet normal -0.842012 -0.20169 -0.500337 + outer loop + vertex 374.658 121.158 228.824 + vertex 378.185 122.221 222.459 + vertex 378.72 115.637 224.214 + endloop + endfacet + facet normal -0.84217 -0.202203 -0.499863 + outer loop + vertex 377.276 114.228 227.216 + vertex 374.658 121.158 228.824 + vertex 378.72 115.637 224.214 + endloop + endfacet + facet normal -0.832283 -0.225908 -0.506232 + outer loop + vertex 379.983 110.302 224.518 + vertex 377.276 114.228 227.216 + vertex 378.72 115.637 224.214 + endloop + endfacet + facet normal -0.836756 -0.197653 -0.510658 + outer loop + vertex 377.276 114.228 227.216 + vertex 375.158 114.545 230.564 + vertex 374.658 121.158 228.824 + endloop + endfacet + facet normal -0.834616 -0.19834 -0.513884 + outer loop + vertex 371.139 120.054 234.965 + vertex 374.658 121.158 228.824 + vertex 375.158 114.545 230.564 + endloop + endfacet + facet normal -0.834816 -0.198926 -0.513334 + outer loop + vertex 373.712 113.121 233.468 + vertex 371.139 120.054 234.965 + vertex 375.158 114.545 230.564 + endloop + endfacet + facet normal -0.82388 -0.224468 -0.520419 + outer loop + vertex 376.403 109.214 230.893 + vertex 373.712 113.121 233.468 + vertex 375.158 114.545 230.564 + endloop + endfacet + facet normal -0.829216 -0.19455 -0.523977 + outer loop + vertex 373.712 113.121 233.468 + vertex 371.627 113.434 236.652 + vertex 371.139 120.054 234.965 + endloop + endfacet + facet normal -0.826678 -0.19531 -0.527691 + outer loop + vertex 367.635 118.958 240.86 + vertex 371.139 120.054 234.965 + vertex 371.627 113.434 236.652 + endloop + endfacet + facet normal -0.826601 -0.195106 -0.527887 + outer loop + vertex 370.206 112.002 239.406 + vertex 367.635 118.958 240.86 + vertex 371.627 113.434 236.652 + endloop + endfacet + facet normal -0.814924 -0.221482 -0.535578 + outer loop + vertex 372.864 108.1 236.975 + vertex 370.206 112.002 239.406 + vertex 371.627 113.434 236.652 + endloop + endfacet + facet normal -0.820859 -0.190804 -0.538315 + outer loop + vertex 370.206 112.002 239.406 + vertex 368.132 112.318 242.456 + vertex 367.635 118.958 240.86 + endloop + endfacet + facet normal -0.818311 -0.191485 -0.541941 + outer loop + vertex 364.103 117.879 246.575 + vertex 367.635 118.958 240.86 + vertex 368.132 112.318 242.456 + endloop + endfacet + facet normal -0.818224 -0.191268 -0.54215 + outer loop + vertex 366.698 110.88 245.128 + vertex 364.103 117.879 246.575 + vertex 368.132 112.318 242.456 + endloop + endfacet + facet normal -0.806135 -0.218065 -0.550086 + outer loop + vertex 369.37 106.966 242.764 + vertex 366.698 110.88 245.128 + vertex 368.132 112.318 242.456 + endloop + endfacet + facet normal -0.812524 -0.187101 -0.552085 + outer loop + vertex 366.698 110.88 245.128 + vertex 364.587 111.203 248.125 + vertex 364.103 117.879 246.575 + endloop + endfacet + facet normal -0.809554 -0.187838 -0.556183 + outer loop + vertex 360.533 116.786 252.14 + vertex 364.103 117.879 246.575 + vertex 364.587 111.203 248.125 + endloop + endfacet + facet normal -0.814619 -0.167195 -0.555376 + outer loop + vertex 360.533 116.786 252.14 + vertex 358.885 126.793 251.545 + vertex 364.103 117.879 246.575 + endloop + endfacet + facet normal -0.816858 -0.170995 -0.550911 + outer loop + vertex 364.103 117.879 246.575 + vertex 358.885 126.793 251.545 + vertex 362.452 127.841 245.931 + endloop + endfacet + facet normal -0.819418 -0.159845 -0.550457 + outer loop + vertex 358.885 126.793 251.545 + vertex 357.248 136.299 251.222 + vertex 362.452 127.841 245.931 + endloop + endfacet + facet normal -0.821469 -0.163747 -0.546237 + outer loop + vertex 362.452 127.841 245.931 + vertex 357.248 136.299 251.222 + vertex 360.795 137.312 245.583 + endloop + endfacet + facet normal -0.827954 -0.164509 -0.536124 + outer loop + vertex 362.452 127.841 245.931 + vertex 360.795 137.312 245.583 + vertex 365.976 128.873 240.172 + endloop + endfacet + facet normal -0.82545 -0.175378 -0.536539 + outer loop + vertex 367.635 118.958 240.86 + vertex 362.452 127.841 245.931 + vertex 365.976 128.873 240.172 + endloop + endfacet + facet normal -0.829792 -0.168204 -0.532121 + outer loop + vertex 365.976 128.873 240.172 + vertex 360.795 137.312 245.583 + vertex 364.295 138.318 239.808 + endloop + endfacet + facet normal -0.83592 -0.168912 -0.522213 + outer loop + vertex 365.976 128.873 240.172 + vertex 364.295 138.318 239.808 + vertex 369.46 129.943 234.249 + endloop + endfacet + facet normal -0.833458 -0.179384 -0.522656 + outer loop + vertex 371.139 120.054 234.965 + vertex 365.976 128.873 240.172 + vertex 369.46 129.943 234.249 + endloop + endfacet + facet normal -0.837468 -0.172242 -0.518632 + outer loop + vertex 369.46 129.943 234.249 + vertex 364.295 138.318 239.808 + vertex 367.746 139.373 233.884 + endloop + endfacet + facet normal -0.843208 -0.172913 -0.50902 + outer loop + vertex 369.46 129.943 234.249 + vertex 367.746 139.373 233.884 + vertex 372.939 131.033 228.116 + endloop + endfacet + facet normal -0.840831 -0.182925 -0.509452 + outer loop + vertex 374.658 121.158 228.824 + vertex 369.46 129.943 234.249 + vertex 372.939 131.033 228.116 + endloop + endfacet + facet normal -0.844475 -0.175861 -0.505899 + outer loop + vertex 372.939 131.033 228.116 + vertex 367.746 139.373 233.884 + vertex 371.193 140.451 227.756 + endloop + endfacet + facet normal -0.850317 -0.176557 -0.495771 + outer loop + vertex 372.939 131.033 228.116 + vertex 371.193 140.451 227.756 + vertex 376.435 132.086 221.744 + endloop + endfacet + facet normal -0.847999 -0.186424 -0.496129 + outer loop + vertex 378.185 122.221 222.459 + vertex 372.939 131.033 228.116 + vertex 376.435 132.086 221.744 + endloop + endfacet + facet normal -0.851383 -0.179239 -0.49297 + outer loop + vertex 376.435 132.086 221.744 + vertex 371.193 140.451 227.756 + vertex 374.666 141.496 221.378 + endloop + endfacet + facet normal -0.857614 -0.179974 -0.481776 + outer loop + vertex 376.435 132.086 221.744 + vertex 374.666 141.496 221.378 + vertex 379.958 133.11 215.09 + endloop + endfacet + facet normal -0.855354 -0.189673 -0.482073 + outer loop + vertex 381.719 123.226 215.855 + vertex 376.435 132.086 221.744 + vertex 379.958 133.11 215.09 + endloop + endfacet + facet normal -0.858387 -0.182097 -0.479596 + outer loop + vertex 379.958 133.11 215.09 + vertex 374.666 141.496 221.378 + vertex 378.168 142.506 214.727 + endloop + endfacet + facet normal -0.864901 -0.182868 -0.467446 + outer loop + vertex 379.958 133.11 215.09 + vertex 378.168 142.506 214.727 + vertex 383.505 134.117 208.134 + endloop + endfacet + facet normal -0.862785 -0.192011 -0.46769 + outer loop + vertex 385.277 124.249 208.916 + vertex 379.958 133.11 215.09 + vertex 383.505 134.117 208.134 + endloop + endfacet + facet normal -0.865382 -0.184325 -0.465981 + outer loop + vertex 383.505 134.117 208.134 + vertex 378.168 142.506 214.727 + vertex 381.67 143.51 207.826 + endloop + endfacet + facet normal -0.866307 -0.18025 -0.465857 + outer loop + vertex 378.168 142.506 214.727 + vertex 376.323 151.451 214.697 + vertex 381.67 143.51 207.826 + endloop + endfacet + facet normal -0.85985 -0.17896 -0.478154 + outer loop + vertex 378.168 142.506 214.727 + vertex 372.844 150.463 221.324 + vertex 376.323 151.451 214.697 + endloop + endfacet + facet normal -0.8603 -0.176955 -0.478091 + outer loop + vertex 372.844 150.463 221.324 + vertex 370.989 159.238 221.413 + vertex 376.323 151.451 214.697 + endloop + endfacet + facet normal -0.860683 -0.178216 -0.476932 + outer loop + vertex 376.323 151.451 214.697 + vertex 370.989 159.238 221.413 + vertex 374.452 160.211 214.799 + endloop + endfacet + facet normal -0.866757 -0.179651 -0.46525 + outer loop + vertex 376.323 151.451 214.697 + vertex 374.452 160.211 214.799 + vertex 379.803 152.399 207.847 + endloop + endfacet + facet normal -0.861437 -0.17482 -0.476828 + outer loop + vertex 370.989 159.238 221.413 + vertex 369.147 168.072 221.501 + vertex 374.452 160.211 214.799 + endloop + endfacet + facet normal -0.861905 -0.176335 -0.475421 + outer loop + vertex 374.452 160.211 214.799 + vertex 369.147 168.072 221.501 + vertex 372.596 169.046 214.887 + endloop + endfacet + facet normal -0.865171 -0.161131 -0.474884 + outer loop + vertex 369.147 168.072 221.501 + vertex 367.425 177.093 221.578 + vertex 372.596 169.046 214.887 + endloop + endfacet + facet normal -0.860059 -0.160074 -0.484433 + outer loop + vertex 369.147 168.072 221.501 + vertex 364.01 176.076 227.977 + vertex 367.425 177.093 221.578 + endloop + endfacet + facet normal -0.867992 -0.11893 -0.482126 + outer loop + vertex 364.01 176.076 227.977 + vertex 362.595 185.335 228.241 + vertex 367.425 177.093 221.578 + endloop + endfacet + facet normal -0.868485 -0.12019 -0.480925 + outer loop + vertex 367.425 177.093 221.578 + vertex 362.595 185.335 228.241 + vertex 366.033 186.362 221.776 + endloop + endfacet + facet normal -0.873582 -0.12116 -0.471355 + outer loop + vertex 367.425 177.093 221.578 + vertex 366.033 186.362 221.776 + vertex 370.856 178.071 214.968 + endloop + endfacet + facet normal -0.862682 -0.117843 -0.491826 + outer loop + vertex 364.01 176.076 227.977 + vertex 359.122 184.257 234.591 + vertex 362.595 185.335 228.241 + endloop + endfacet + facet normal -0.862274 -0.116825 -0.492783 + outer loop + vertex 360.644 175.03 234.115 + vertex 359.122 184.257 234.591 + vertex 364.01 176.076 227.977 + endloop + endfacet + facet normal -0.854391 -0.157078 -0.495321 + outer loop + vertex 365.733 167.058 227.865 + vertex 360.644 175.03 234.115 + vertex 364.01 176.076 227.977 + endloop + endfacet + facet normal -0.853494 -0.154714 -0.497606 + outer loop + vertex 362.352 166.004 233.991 + vertex 360.644 175.03 234.115 + vertex 365.733 167.058 227.865 + endloop + endfacet + facet normal -0.850048 -0.170357 -0.498395 + outer loop + vertex 367.557 158.218 227.777 + vertex 362.352 166.004 233.991 + vertex 365.733 167.058 227.865 + endloop + endfacet + facet normal -0.855331 -0.171543 -0.488858 + outer loop + vertex 367.557 158.218 227.777 + vertex 365.733 167.058 227.865 + vertex 370.989 159.238 221.413 + endloop + endfacet + facet normal -0.849249 -0.168139 -0.500506 + outer loop + vertex 364.158 157.161 233.898 + vertex 362.352 166.004 233.991 + vertex 367.557 158.218 227.777 + endloop + endfacet + facet normal -0.84824 -0.172563 -0.50071 + outer loop + vertex 369.392 149.431 227.696 + vertex 364.158 157.161 233.898 + vertex 367.557 158.218 227.777 + endloop + endfacet + facet normal -0.853832 -0.173823 -0.49067 + outer loop + vertex 369.392 149.431 227.696 + vertex 367.557 158.218 227.777 + vertex 372.844 150.463 221.324 + endloop + endfacet + facet normal -0.853244 -0.176406 -0.49077 + outer loop + vertex 374.666 141.496 221.378 + vertex 369.392 149.431 227.696 + vertex 372.844 150.463 221.324 + endloop + endfacet + facet normal -0.847358 -0.170092 -0.503045 + outer loop + vertex 365.972 148.367 233.817 + vertex 364.158 157.161 233.898 + vertex 369.392 149.431 227.696 + endloop + endfacet + facet normal -0.846641 -0.173212 -0.503187 + outer loop + vertex 371.193 140.451 227.756 + vertex 365.972 148.367 233.817 + vertex 369.392 149.431 227.696 + endloop + endfacet + facet normal -0.84155 -0.1688 -0.513128 + outer loop + vertex 365.972 148.367 233.817 + vertex 360.76 156.106 239.817 + vertex 364.158 157.161 233.898 + endloop + endfacet + facet normal -0.842598 -0.164181 -0.512907 + outer loop + vertex 360.76 156.106 239.817 + vertex 358.976 164.937 239.922 + vertex 364.158 157.161 233.898 + endloop + endfacet + facet normal -0.836348 -0.162792 -0.523469 + outer loop + vertex 360.76 156.106 239.817 + vertex 355.55 163.878 245.724 + vertex 358.976 164.937 239.922 + endloop + endfacet + facet normal -0.839758 -0.147176 -0.522633 + outer loop + vertex 355.55 163.878 245.724 + vertex 353.896 172.86 245.853 + vertex 358.976 164.937 239.922 + endloop + endfacet + facet normal -0.840999 -0.150092 -0.519802 + outer loop + vertex 358.976 164.937 239.922 + vertex 353.896 172.86 245.853 + vertex 357.295 173.956 240.038 + endloop + endfacet + facet normal -0.847075 -0.151357 -0.509465 + outer loop + vertex 358.976 164.937 239.922 + vertex 357.295 173.956 240.038 + vertex 362.352 166.004 233.991 + endloop + endfacet + facet normal -0.849176 -0.108757 -0.516791 + outer loop + vertex 353.896 172.86 245.853 + vertex 352.557 182.124 246.104 + vertex 357.295 173.956 240.038 + endloop + endfacet + facet normal -0.850842 -0.112336 -0.513273 + outer loop + vertex 357.295 173.956 240.038 + vertex 352.557 182.124 246.104 + vertex 355.892 183.222 240.335 + endloop + endfacet + facet normal -0.855903 -0.113383 -0.504554 + outer loop + vertex 357.295 173.956 240.038 + vertex 355.892 183.222 240.335 + vertex 360.644 175.03 234.115 + endloop + endfacet + facet normal -0.844528 -0.107875 -0.524534 + outer loop + vertex 353.896 172.86 245.853 + vertex 349.159 180.979 251.81 + vertex 352.557 182.124 246.104 + endloop + endfacet + facet normal -0.842394 -0.103476 -0.528833 + outer loop + vertex 350.483 171.765 251.504 + vertex 349.159 180.979 251.81 + vertex 353.896 172.86 245.853 + endloop + endfacet + facet normal -0.838036 -0.102617 -0.535877 + outer loop + vertex 350.483 171.765 251.504 + vertex 346.027 179.902 256.914 + vertex 349.159 180.979 251.81 + endloop + endfacet + facet normal -0.835243 -0.0975796 -0.541153 + outer loop + vertex 347.126 170.594 256.897 + vertex 346.027 179.902 256.914 + vertex 350.483 171.765 251.504 + endloop + endfacet + facet normal -0.826402 -0.141133 -0.545107 + outer loop + vertex 352.081 162.81 251.4 + vertex 347.126 170.594 256.897 + vertex 350.483 171.765 251.504 + endloop + endfacet + facet normal -0.832395 -0.142314 -0.535598 + outer loop + vertex 352.081 162.81 251.4 + vertex 350.483 171.765 251.504 + vertex 355.55 163.878 245.724 + endloop + endfacet + facet normal -0.828794 -0.158895 -0.536519 + outer loop + vertex 357.313 155.084 245.606 + vertex 352.081 162.81 251.4 + vertex 355.55 163.878 245.724 + endloop + endfacet + facet normal -0.827489 -0.155833 -0.539423 + outer loop + vertex 353.818 154.035 251.271 + vertex 352.081 162.81 251.4 + vertex 357.313 155.084 245.606 + endloop + endfacet + facet normal -0.826397 -0.16074 -0.539658 + outer loop + vertex 359.077 146.311 245.517 + vertex 353.818 154.035 251.271 + vertex 357.313 155.084 245.606 + endloop + endfacet + facet normal -0.833172 -0.162214 -0.528688 + outer loop + vertex 359.077 146.311 245.517 + vertex 357.313 155.084 245.606 + vertex 362.55 147.317 239.736 + endloop + endfacet + facet normal -0.832411 -0.165632 -0.528826 + outer loop + vertex 364.295 138.318 239.808 + vertex 359.077 146.311 245.517 + vertex 362.55 147.317 239.736 + endloop + endfacet + facet normal -0.834318 -0.165013 -0.526007 + outer loop + vertex 362.55 147.317 239.736 + vertex 357.313 155.084 245.606 + vertex 360.76 156.106 239.817 + endloop + endfacet + facet normal -0.825195 -0.157942 -0.542316 + outer loop + vertex 355.559 145.291 251.168 + vertex 353.818 154.035 251.271 + vertex 359.077 146.311 245.517 + endloop + endfacet + facet normal -0.824437 -0.161364 -0.542462 + outer loop + vertex 360.795 137.312 245.583 + vertex 355.559 145.291 251.168 + vertex 359.077 146.311 245.517 + endloop + endfacet + facet normal -0.81861 -0.15651 -0.552614 + outer loop + vertex 355.559 145.291 251.168 + vertex 350.427 152.751 256.658 + vertex 353.818 154.035 251.271 + endloop + endfacet + facet normal -0.819778 -0.15174 -0.552212 + outer loop + vertex 350.427 152.751 256.658 + vertex 348.688 161.536 256.824 + vertex 353.818 154.035 251.271 + endloop + endfacet + facet normal -0.813574 -0.150333 -0.561692 + outer loop + vertex 350.427 152.751 256.658 + vertex 345.748 159.607 261.6 + vertex 348.688 161.536 256.824 + endloop + endfacet + facet normal -0.818656 -0.134322 -0.558354 + outer loop + vertex 345.748 159.607 261.6 + vertex 344.101 169.054 261.741 + vertex 348.688 161.536 256.824 + endloop + endfacet + facet normal -0.820099 -0.137021 -0.555574 + outer loop + vertex 348.688 161.536 256.824 + vertex 344.101 169.054 261.741 + vertex 347.126 170.594 256.897 + endloop + endfacet + facet normal -0.830385 -0.0957852 -0.548894 + outer loop + vertex 344.101 169.054 261.741 + vertex 342.874 178.802 261.898 + vertex 347.126 170.594 256.897 + endloop + endfacet + facet normal -0.823467 -0.0947457 -0.559397 + outer loop + vertex 344.101 169.054 261.741 + vertex 340.141 177.839 266.083 + vertex 342.874 178.802 261.898 + endloop + endfacet + facet normal -0.825943 -0.0979469 -0.55518 + outer loop + vertex 341.926 165.994 265.517 + vertex 340.141 177.839 266.083 + vertex 344.101 169.054 261.741 + endloop + endfacet + facet normal -0.786736 -0.0893806 -0.610784 + outer loop + vertex 340.141 177.839 266.083 + vertex 341.926 165.994 265.517 + vertex 339.305 171.012 268.159 + endloop + endfacet + facet normal -0.819695 -0.0724015 -0.568206 + outer loop + vertex 337.826 177.018 269.528 + vertex 340.141 177.839 266.083 + vertex 339.305 171.012 268.159 + endloop + endfacet + facet normal -0.816046 -0.07025 -0.573701 + outer loop + vertex 339.305 171.012 268.159 + vertex 337.719 176.98 269.685 + vertex 337.826 177.018 269.528 + endloop + endfacet + facet normal -0.843233 -0.0886061 -0.530195 + outer loop + vertex 339.068 166.76 269.246 + vertex 337.719 176.98 269.685 + vertex 339.305 171.012 268.159 + endloop + endfacet + facet normal -0.776618 -0.115115 -0.619365 + outer loop + vertex 340.934 161.615 267.863 + vertex 339.068 166.76 269.246 + vertex 339.305 171.012 268.159 + endloop + endfacet + facet normal -0.801873 -0.134261 -0.582215 + outer loop + vertex 340.692 157.626 269.116 + vertex 339.068 166.76 269.246 + vertex 340.934 161.615 267.863 + endloop + endfacet + facet normal -0.791592 -0.138915 -0.59505 + outer loop + vertex 343.091 151.219 267.421 + vertex 340.692 157.626 269.116 + vertex 340.934 161.615 267.863 + endloop + endfacet + facet normal -0.803033 -0.14198 -0.578775 + outer loop + vertex 343.091 151.219 267.421 + vertex 340.934 161.615 267.863 + vertex 343.749 156.557 265.198 + endloop + endfacet + facet normal -0.799894 -0.143968 -0.582617 + outer loop + vertex 343.749 156.557 265.198 + vertex 345.605 148.944 264.531 + vertex 343.091 151.219 267.421 + endloop + endfacet + facet normal -0.800003 -0.14442 -0.582355 + outer loop + vertex 345.605 148.944 264.531 + vertex 346.435 141.996 265.114 + vertex 343.091 151.219 267.421 + endloop + endfacet + facet normal -0.797745 -0.142725 -0.585861 + outer loop + vertex 344.51 141.638 267.822 + vertex 343.091 151.219 267.421 + vertex 346.435 141.996 265.114 + endloop + endfacet + facet normal -0.797492 -0.144116 -0.585865 + outer loop + vertex 346.435 141.996 265.114 + vertex 347.783 132.002 265.737 + vertex 344.51 141.638 267.822 + endloop + endfacet + facet normal -0.79442 -0.142066 -0.59052 + outer loop + vertex 345.473 134.402 268.268 + vertex 344.51 141.638 267.822 + vertex 347.783 132.002 265.737 + endloop + endfacet + facet normal -0.795013 -0.143964 -0.589261 + outer loop + vertex 347.297 125.898 267.885 + vertex 345.473 134.402 268.268 + vertex 347.783 132.002 265.737 + endloop + endfacet + facet normal -0.790282 -0.146363 -0.595006 + outer loop + vertex 347.783 132.002 265.737 + vertex 350.168 120.453 265.411 + vertex 347.297 125.898 267.885 + endloop + endfacet + facet normal -0.793656 -0.150684 -0.58941 + outer loop + vertex 349.484 114.19 267.932 + vertex 347.297 125.898 267.885 + vertex 350.168 120.453 265.411 + endloop + endfacet + facet normal -0.785059 -0.155697 -0.599533 + outer loop + vertex 350.168 120.453 265.411 + vertex 351.92 111.603 265.414 + vertex 349.484 114.19 267.932 + endloop + endfacet + facet normal -0.790284 -0.171638 -0.588211 + outer loop + vertex 351.787 106.889 266.969 + vertex 349.484 114.19 267.932 + vertex 351.92 111.603 265.414 + endloop + endfacet + facet normal -0.790014 -0.156676 -0.592732 + outer loop + vertex 351.92 111.603 265.414 + vertex 350.168 120.453 265.411 + vertex 354.015 113.796 262.042 + endloop + endfacet + facet normal -0.780832 -0.175839 -0.599485 + outer loop + vertex 351.92 111.603 265.414 + vertex 354.015 113.796 262.042 + vertex 354.447 107.496 263.328 + endloop + endfacet + facet normal -0.790746 -0.157736 -0.591472 + outer loop + vertex 354.015 113.796 262.042 + vertex 350.168 120.453 265.411 + vertex 352.267 123.816 261.708 + endloop + endfacet + facet normal -0.796881 -0.158523 -0.582967 + outer loop + vertex 354.015 113.796 262.042 + vertex 352.267 123.816 261.708 + vertex 357.061 115.539 257.405 + endloop + endfacet + facet normal -0.789793 -0.179974 -0.586375 + outer loop + vertex 354.015 113.796 262.042 + vertex 357.061 115.539 257.405 + vertex 357.549 108.96 258.767 + endloop + endfacet + facet normal -0.799285 -0.162153 -0.578663 + outer loop + vertex 357.061 115.539 257.405 + vertex 352.267 123.816 261.708 + vertex 355.394 125.574 256.895 + endloop + endfacet + facet normal -0.805527 -0.162739 -0.569774 + outer loop + vertex 357.061 115.539 257.405 + vertex 355.394 125.574 256.895 + vertex 360.533 116.786 252.14 + endloop + endfacet + facet normal -0.800015 -0.183807 -0.571131 + outer loop + vertex 357.061 115.539 257.405 + vertex 360.533 116.786 252.14 + vertex 361.007 110.114 253.623 + endloop + endfacet + facet normal -0.802873 -0.150666 -0.576797 + outer loop + vertex 352.267 123.816 261.708 + vertex 350.549 133.859 261.476 + vertex 355.394 125.574 256.895 + endloop + endfacet + facet normal -0.805195 -0.154363 -0.572567 + outer loop + vertex 355.394 125.574 256.895 + vertex 350.549 133.859 261.476 + vertex 353.764 135.179 256.598 + endloop + endfacet + facet normal -0.810838 -0.155066 -0.564355 + outer loop + vertex 355.394 125.574 256.895 + vertex 353.764 135.179 256.598 + vertex 358.885 126.793 251.545 + endloop + endfacet + facet normal -0.806867 -0.147895 -0.571919 + outer loop + vertex 350.549 133.859 261.476 + vertex 349.077 142.785 261.244 + vertex 353.764 135.179 256.598 + endloop + endfacet + facet normal -0.809147 -0.151923 -0.567627 + outer loop + vertex 353.764 135.179 256.598 + vertex 349.077 142.785 261.244 + vertex 352.135 144.112 256.529 + endloop + endfacet + facet normal -0.814536 -0.152844 -0.559615 + outer loop + vertex 353.764 135.179 256.598 + vertex 352.135 144.112 256.529 + vertex 357.248 136.299 251.222 + endloop + endfacet + facet normal -0.81642 -0.156668 -0.5558 + outer loop + vertex 357.248 136.299 251.222 + vertex 352.135 144.112 256.529 + vertex 355.559 145.291 251.168 + endloop + endfacet + facet normal -0.80996 -0.148837 -0.567285 + outer loop + vertex 349.077 142.785 261.244 + vertex 347.505 151.007 261.331 + vertex 352.135 144.112 256.529 + endloop + endfacet + facet normal -0.811562 -0.152121 -0.564115 + outer loop + vertex 352.135 144.112 256.529 + vertex 347.505 151.007 261.331 + vertex 350.427 152.751 256.658 + endloop + endfacet + facet normal -0.805582 -0.147932 -0.57372 + outer loop + vertex 349.077 142.785 261.244 + vertex 345.605 148.944 264.531 + vertex 347.505 151.007 261.331 + endloop + endfacet + facet normal -0.802626 -0.147354 -0.577995 + outer loop + vertex 350.549 133.859 261.476 + vertex 346.435 141.996 265.114 + vertex 349.077 142.785 261.244 + endloop + endfacet + facet normal -0.798204 -0.15002 -0.583407 + outer loop + vertex 352.267 123.816 261.708 + vertex 347.783 132.002 265.737 + vertex 350.549 133.859 261.476 + endloop + endfacet + facet normal -0.796716 -0.147946 -0.585966 + outer loop + vertex 350.168 120.453 265.411 + vertex 347.783 132.002 265.737 + vertex 352.267 123.816 261.708 + endloop + endfacet + facet normal -0.789852 -0.142531 -0.596506 + outer loop + vertex 347.297 125.898 267.885 + vertex 345.444 131.094 269.096 + vertex 345.473 134.402 268.268 + endloop + endfacet + facet normal -0.793372 -0.141394 -0.592088 + outer loop + vertex 345.444 131.094 269.096 + vertex 343.825 140.033 269.131 + vertex 345.473 134.402 268.268 + endloop + endfacet + facet normal -0.795798 -0.141847 -0.588714 + outer loop + vertex 343.825 140.033 269.131 + vertex 345.444 131.094 269.096 + vertex 344.466 135.475 269.363 + endloop + endfacet + facet normal -0.78846 -0.141552 -0.598577 + outer loop + vertex 347.108 121.774 269.109 + vertex 345.444 131.094 269.096 + vertex 347.297 125.898 267.885 + endloop + endfacet + facet normal -0.77808 -0.139718 -0.612431 + outer loop + vertex 345.444 131.094 269.096 + vertex 347.108 121.774 269.109 + vertex 345.959 126.983 269.38 + endloop + endfacet + facet normal -0.794696 -0.142079 -0.590146 + outer loop + vertex 345.473 134.402 268.268 + vertex 343.825 140.033 269.131 + vertex 344.51 141.638 267.822 + endloop + endfacet + facet normal -0.79457 -0.14224 -0.590277 + outer loop + vertex 343.825 140.033 269.131 + vertex 342.303 148.837 269.059 + vertex 344.51 141.638 267.822 + endloop + endfacet + facet normal -0.79644 -0.142542 -0.587677 + outer loop + vertex 342.303 148.837 269.059 + vertex 343.825 140.033 269.131 + vertex 342.595 145.76 269.409 + endloop + endfacet + facet normal -0.800171 -0.144248 -0.582168 + outer loop + vertex 347.783 132.002 265.737 + vertex 346.435 141.996 265.114 + vertex 350.549 133.859 261.476 + endloop + endfacet + facet normal -0.794988 -0.142475 -0.589657 + outer loop + vertex 344.51 141.638 267.822 + vertex 342.303 148.837 269.059 + vertex 343.091 151.219 267.421 + endloop + endfacet + facet normal -0.80327 -0.144431 -0.577839 + outer loop + vertex 346.435 141.996 265.114 + vertex 345.605 148.944 264.531 + vertex 349.077 142.785 261.244 + endloop + endfacet + facet normal -0.806291 -0.146359 -0.573126 + outer loop + vertex 345.605 148.944 264.531 + vertex 343.749 156.557 265.198 + vertex 347.505 151.007 261.331 + endloop + endfacet + facet normal -0.806571 -0.146923 -0.572588 + outer loop + vertex 347.505 151.007 261.331 + vertex 343.749 156.557 265.198 + vertex 345.748 159.607 261.6 + endloop + endfacet + facet normal -0.811747 -0.137607 -0.567566 + outer loop + vertex 343.749 156.557 265.198 + vertex 341.926 165.994 265.517 + vertex 345.748 159.607 261.6 + endloop + endfacet + facet normal -0.797716 -0.134208 -0.58791 + outer loop + vertex 341.926 165.994 265.517 + vertex 343.749 156.557 265.198 + vertex 340.934 161.615 267.863 + endloop + endfacet + facet normal -0.795483 -0.141941 -0.589118 + outer loop + vertex 342.303 148.837 269.059 + vertex 340.692 157.626 269.116 + vertex 343.091 151.219 267.421 + endloop + endfacet + facet normal -0.788885 -0.140673 -0.598224 + outer loop + vertex 340.692 157.626 269.116 + vertex 342.303 148.837 269.059 + vertex 341.022 154.242 269.477 + endloop + endfacet + facet normal -0.740511 -0.122234 -0.660834 + outer loop + vertex 339.068 166.76 269.246 + vertex 340.692 157.626 269.116 + vertex 339.726 161.503 269.481 + endloop + endfacet + facet normal -0.348222 -0.00573797 -0.937394 + outer loop + vertex 337.719 176.98 269.685 + vertex 339.068 166.76 269.246 + vertex 338.048 172.236 269.592 + endloop + endfacet + facet normal -0.819631 -0.0456949 -0.571067 + outer loop + vertex 338.048 172.236 269.592 + vertex 337.611 176.942 269.842 + vertex 337.719 176.98 269.685 + endloop + endfacet + facet normal -0.811121 -0.122588 -0.571887 + outer loop + vertex 340.934 161.615 267.863 + vertex 339.305 171.012 268.159 + vertex 341.926 165.994 265.517 + endloop + endfacet + facet normal -0.808698 -0.132365 -0.573138 + outer loop + vertex 345.748 159.607 261.6 + vertex 341.926 165.994 265.517 + vertex 344.101 169.054 261.741 + endloop + endfacet + facet normal -0.812696 -0.148461 -0.563458 + outer loop + vertex 347.505 151.007 261.331 + vertex 345.748 159.607 261.6 + vertex 350.427 152.751 256.658 + endloop + endfacet + facet normal -0.817202 -0.153363 -0.555573 + outer loop + vertex 352.135 144.112 256.529 + vertex 350.427 152.751 256.658 + vertex 355.559 145.291 251.168 + endloop + endfacet + facet normal -0.820956 -0.154388 -0.549723 + outer loop + vertex 353.818 154.035 251.271 + vertex 348.688 161.536 256.824 + vertex 352.081 162.81 251.4 + endloop + endfacet + facet normal -0.824845 -0.137898 -0.548284 + outer loop + vertex 348.688 161.536 256.824 + vertex 347.126 170.594 256.897 + vertex 352.081 162.81 251.4 + endloop + endfacet + facet normal -0.831194 -0.0970902 -0.54744 + outer loop + vertex 347.126 170.594 256.897 + vertex 342.874 178.802 261.898 + vertex 346.027 179.902 256.914 + endloop + endfacet + facet normal -0.834045 -0.14599 -0.532029 + outer loop + vertex 355.55 163.878 245.724 + vertex 350.483 171.765 251.504 + vertex 353.896 172.86 245.853 + endloop + endfacet + facet normal -0.835355 -0.160354 -0.525802 + outer loop + vertex 357.313 155.084 245.606 + vertex 355.55 163.878 245.724 + vertex 360.76 156.106 239.817 + endloop + endfacet + facet normal -0.840624 -0.166394 -0.515427 + outer loop + vertex 362.55 147.317 239.736 + vertex 360.76 156.106 239.817 + vertex 365.972 148.367 233.817 + endloop + endfacet + facet normal -0.83989 -0.169612 -0.515573 + outer loop + vertex 367.746 139.373 233.884 + vertex 362.55 147.317 239.736 + vertex 365.972 148.367 233.817 + endloop + endfacet + facet normal -0.843643 -0.166891 -0.510307 + outer loop + vertex 364.158 157.161 233.898 + vertex 358.976 164.937 239.922 + vertex 362.352 166.004 233.991 + endloop + endfacet + facet normal -0.847958 -0.153534 -0.507341 + outer loop + vertex 362.352 166.004 233.991 + vertex 357.295 173.956 240.038 + vertex 360.644 175.03 234.115 + endloop + endfacet + facet normal -0.856803 -0.115418 -0.502561 + outer loop + vertex 360.644 175.03 234.115 + vertex 355.892 183.222 240.335 + vertex 359.122 184.257 234.591 + endloop + endfacet + facet normal -0.859375 -0.158143 -0.486277 + outer loop + vertex 365.733 167.058 227.865 + vertex 364.01 176.076 227.977 + vertex 369.147 168.072 221.501 + endloop + endfacet + facet normal -0.856015 -0.173589 -0.486935 + outer loop + vertex 370.989 159.238 221.413 + vertex 365.733 167.058 227.865 + vertex 369.147 168.072 221.501 + endloop + endfacet + facet normal -0.854417 -0.175599 -0.489015 + outer loop + vertex 372.844 150.463 221.324 + vertex 367.557 158.218 227.777 + vertex 370.989 159.238 221.413 + endloop + endfacet + facet normal -0.859412 -0.177591 -0.479451 + outer loop + vertex 374.666 141.496 221.378 + vertex 372.844 150.463 221.324 + vertex 378.168 142.506 214.727 + endloop + endfacet + facet normal -0.852514 -0.17432 -0.49278 + outer loop + vertex 371.193 140.451 227.756 + vertex 369.392 149.431 227.696 + vertex 374.666 141.496 221.378 + endloop + endfacet + facet normal -0.845678 -0.17068 -0.505665 + outer loop + vertex 367.746 139.373 233.884 + vertex 365.972 148.367 233.817 + vertex 371.193 140.451 227.756 + endloop + endfacet + facet normal -0.838724 -0.166774 -0.51839 + outer loop + vertex 364.295 138.318 239.808 + vertex 362.55 147.317 239.736 + vertex 367.746 139.373 233.884 + endloop + endfacet + facet normal -0.831058 -0.16255 -0.531903 + outer loop + vertex 360.795 137.312 245.583 + vertex 359.077 146.311 245.517 + vertex 364.295 138.318 239.808 + endloop + endfacet + facet normal -0.822789 -0.157805 -0.546 + outer loop + vertex 357.248 136.299 251.222 + vertex 355.559 145.291 251.168 + vertex 360.795 137.312 245.583 + endloop + endfacet + facet normal -0.813092 -0.15908 -0.559978 + outer loop + vertex 358.885 126.793 251.545 + vertex 353.764 135.179 256.598 + vertex 357.248 136.299 251.222 + endloop + endfacet + facet normal -0.807982 -0.166682 -0.565139 + outer loop + vertex 360.533 116.786 252.14 + vertex 355.394 125.574 256.895 + vertex 358.885 126.793 251.545 + endloop + endfacet + facet normal -0.823235 -0.171425 -0.5412 + outer loop + vertex 364.103 117.879 246.575 + vertex 362.452 127.841 245.931 + vertex 367.635 118.958 240.86 + endloop + endfacet + facet normal -0.816383 -0.225471 -0.531677 + outer loop + vertex 371.122 107.541 239.89 + vertex 368.132 112.318 242.456 + vertex 370.206 112.002 239.406 + endloop + endfacet + facet normal -0.831537 -0.175731 -0.526939 + outer loop + vertex 367.635 118.958 240.86 + vertex 365.976 128.873 240.172 + vertex 371.139 120.054 234.965 + endloop + endfacet + facet normal -0.824718 -0.227454 -0.517788 + outer loop + vertex 374.621 108.657 233.981 + vertex 371.627 113.434 236.652 + vertex 373.712 113.121 233.468 + endloop + endfacet + facet normal -0.839256 -0.179684 -0.51319 + outer loop + vertex 371.139 120.054 234.965 + vertex 369.46 129.943 234.249 + vertex 374.658 121.158 228.824 + endloop + endfacet + facet normal -0.832164 -0.229707 -0.504715 + outer loop + vertex 378.198 109.766 227.727 + vertex 375.158 114.545 230.564 + vertex 377.276 114.228 227.216 + endloop + endfacet + facet normal -0.846556 -0.183227 -0.499771 + outer loop + vertex 374.658 121.158 228.824 + vertex 372.939 131.033 228.116 + vertex 378.185 122.221 222.459 + endloop + endfacet + facet normal -0.840366 -0.231269 -0.490203 + outer loop + vertex 381.76 110.833 221.269 + vertex 378.72 115.637 224.214 + vertex 380.825 115.284 220.772 + endloop + endfacet + facet normal -0.854123 -0.186732 -0.485392 + outer loop + vertex 378.185 122.221 222.459 + vertex 376.435 132.086 221.744 + vertex 381.719 123.226 215.855 + endloop + endfacet + facet normal -0.848383 -0.232261 -0.47571 + outer loop + vertex 385.285 111.8 214.656 + vertex 382.255 116.647 217.693 + vertex 384.36 116.242 214.137 + endloop + endfacet + facet normal -0.861989 -0.18992 -0.470005 + outer loop + vertex 381.719 123.226 215.855 + vertex 379.958 133.11 215.09 + vertex 385.277 124.249 208.916 + endloop + endfacet + facet normal -0.856753 -0.234268 -0.459448 + outer loop + vertex 388.815 112.767 207.745 + vertex 385.798 117.61 210.903 + vertex 387.9 117.307 207.138 + endloop + endfacet + facet normal -0.868493 -0.192184 -0.456931 + outer loop + vertex 385.277 124.249 208.916 + vertex 383.505 134.117 208.134 + vertex 388.937 125.097 201.603 + endloop + endfacet + facet normal -0.86269 -0.232059 -0.449349 + outer loop + vertex 392.312 114.565 200.185 + vertex 389.31 118.885 203.717 + vertex 391.138 118.86 200.222 + endloop + endfacet + facet normal -0.869567 -0.195266 -0.453568 + outer loop + vertex 388.937 125.097 201.603 + vertex 383.505 134.117 208.134 + vertex 387.001 135.23 200.952 + endloop + endfacet + facet normal -0.871971 -0.185192 -0.453177 + outer loop + vertex 383.505 134.117 208.134 + vertex 381.67 143.51 207.826 + vertex 387.001 135.23 200.952 + endloop + endfacet + facet normal -0.866487 -0.18087 -0.465281 + outer loop + vertex 381.67 143.51 207.826 + vertex 376.323 151.451 214.697 + vertex 379.803 152.399 207.847 + endloop + endfacet + facet normal -0.866939 -0.180302 -0.464658 + outer loop + vertex 379.803 152.399 207.847 + vertex 374.452 160.211 214.799 + vertex 377.921 161.136 207.968 + endloop + endfacet + facet normal -0.867527 -0.177624 -0.464594 + outer loop + vertex 374.452 160.211 214.799 + vertex 372.596 169.046 214.887 + vertex 377.921 161.136 207.968 + endloop + endfacet + facet normal -0.86569 -0.162695 -0.473404 + outer loop + vertex 372.596 169.046 214.887 + vertex 367.425 177.093 221.578 + vertex 370.856 178.071 214.968 + endloop + endfacet + facet normal -0.874004 -0.12229 -0.470278 + outer loop + vertex 370.856 178.071 214.968 + vertex 366.033 186.362 221.776 + vertex 369.393 187.325 215.281 + endloop + endfacet + facet normal -0.877059 -0.166412 -0.450637 + outer loop + vertex 376.054 169.979 208.055 + vertex 374.303 179.014 208.127 + vertex 379.498 170.878 201.022 + endloop + endfacet + facet normal -0.874023 -0.180807 -0.45099 + outer loop + vertex 381.369 162.015 200.949 + vertex 376.054 169.979 208.055 + vertex 379.498 170.878 201.022 + endloop + endfacet + facet normal -0.880022 -0.183678 -0.437977 + outer loop + vertex 383.255 153.295 200.815 + vertex 381.369 162.015 200.949 + vertex 386.657 154.131 193.63 + endloop + endfacet + facet normal -0.880009 -0.183737 -0.437978 + outer loop + vertex 388.536 145.407 193.514 + vertex 383.255 153.295 200.815 + vertex 386.657 154.131 193.63 + endloop + endfacet + facet normal -0.879192 -0.187942 -0.437834 + outer loop + vertex 390.41 136.352 193.637 + vertex 385.133 144.5 200.737 + vertex 388.536 145.407 193.514 + endloop + endfacet + facet normal -0.883112 -0.199333 -0.424711 + outer loop + vertex 392.301 126.732 194.221 + vertex 390.41 136.352 193.637 + vertex 395.669 127.831 186.702 + endloop + endfacet + facet normal -0.885383 -0.220923 -0.40901 + outer loop + vertex 397.708 118.04 187.577 + vertex 395.669 127.831 186.702 + vertex 400.995 118.942 179.974 + endloop + endfacet + facet normal -0.890744 -0.2021 -0.407101 + outer loop + vertex 398.922 128.687 179.171 + vertex 393.746 137.259 186.24 + vertex 396.988 138.041 178.759 + endloop + endfacet + facet normal -0.89339 -0.190805 -0.406754 + outer loop + vertex 396.988 138.041 178.759 + vertex 391.867 146.216 186.173 + vertex 395.106 146.966 178.706 + endloop + endfacet + facet normal -0.894164 -0.187198 -0.406727 + outer loop + vertex 391.867 146.216 186.173 + vertex 389.987 154.924 186.297 + vertex 395.106 146.966 178.706 + endloop + endfacet + facet normal -0.886954 -0.185479 -0.422978 + outer loop + vertex 389.987 154.924 186.297 + vertex 384.769 162.858 193.759 + vertex 388.101 163.672 186.416 + endloop + endfacet + facet normal -0.887253 -0.184086 -0.422959 + outer loop + vertex 384.769 162.858 193.759 + vertex 382.896 171.739 193.823 + vertex 388.101 163.672 186.416 + endloop + endfacet + facet normal -0.883702 -0.168922 -0.436504 + outer loop + vertex 382.896 171.739 193.823 + vertex 377.747 179.924 201.08 + vertex 381.135 180.786 193.887 + endloop + endfacet + facet normal -0.891322 -0.127381 -0.435109 + outer loop + vertex 381.135 180.786 193.887 + vertex 376.327 189.18 201.279 + vertex 379.682 190.026 194.158 + endloop + endfacet + facet normal -0.897239 -0.171722 -0.406784 + outer loop + vertex 386.228 172.566 186.472 + vertex 384.474 181.612 186.523 + vertex 389.474 173.353 178.981 + endloop + endfacet + facet normal -0.894335 -0.185781 -0.407002 + outer loop + vertex 391.345 164.457 178.93 + vertex 386.228 172.566 186.472 + vertex 389.474 173.353 178.981 + endloop + endfacet + facet normal -0.901395 -0.18895 -0.389596 + outer loop + vertex 393.23 155.693 178.82 + vertex 391.345 164.457 178.93 + vertex 396.362 156.44 171.211 + endloop + endfacet + facet normal -0.901449 -0.188696 -0.389594 + outer loop + vertex 398.237 147.698 171.106 + vertex 393.23 155.693 178.82 + vertex 396.362 156.44 171.211 + endloop + endfacet + facet normal -0.908126 -0.193805 -0.371143 + outer loop + vertex 400.118 138.765 171.167 + vertex 398.237 147.698 171.106 + vertex 403.113 139.461 163.477 + endloop + endfacet + facet normal -0.913085 -0.20563 -0.352125 + outer loop + vertex 405.057 130.115 163.893 + vertex 403.113 139.461 163.477 + vertex 407.896 130.787 156.14 + endloop + endfacet + facet normal -0.908455 -0.225204 -0.352125 + outer loop + vertex 410.006 121.065 156.912 + vertex 405.057 130.115 163.893 + vertex 407.896 130.787 156.14 + endloop + endfacet + facet normal -0.915818 -0.196139 -0.350438 + outer loop + vertex 405.938 140.137 155.732 + vertex 401.23 148.409 163.406 + vertex 404.048 149.082 155.665 + endloop + endfacet + facet normal -0.916619 -0.192419 -0.350406 + outer loop + vertex 401.23 148.409 163.406 + vertex 399.355 157.153 163.51 + vertex 404.048 149.082 155.665 + endloop + endfacet + facet normal -0.908858 -0.190569 -0.371027 + outer loop + vertex 399.355 157.153 163.51 + vertex 394.479 165.207 171.317 + vertex 397.474 165.916 163.617 + endloop + endfacet + facet normal -0.909197 -0.188973 -0.371012 + outer loop + vertex 394.479 165.207 171.317 + vertex 392.61 174.098 171.368 + vertex 397.474 165.916 163.617 + endloop + endfacet + facet normal -0.904507 -0.173373 -0.389627 + outer loop + vertex 392.61 174.098 171.368 + vertex 387.715 182.391 179.042 + vertex 390.855 183.132 171.422 + endloop + endfacet + facet normal -0.911848 -0.131605 -0.388861 + outer loop + vertex 390.855 183.132 171.422 + vertex 386.215 191.606 179.436 + vertex 389.521 192.382 171.422 + endloop + endfacet + facet normal -0.919955 -0.176988 -0.349797 + outer loop + vertex 398.425 175.464 155.933 + vertex 393.851 183.831 163.728 + vertex 396.666 184.49 155.99 + endloop + endfacet + facet normal -0.917032 -0.190509 -0.350368 + outer loop + vertex 400.291 166.582 155.878 + vertex 395.606 174.802 163.669 + vertex 398.425 175.464 155.933 + endloop + endfacet + facet normal -0.924691 -0.194562 -0.327249 + outer loop + vertex 402.172 157.823 155.769 + vertex 400.291 166.582 155.878 + vertex 404.779 158.449 148.031 + endloop + endfacet + facet normal -0.92455 -0.195223 -0.327254 + outer loop + vertex 406.66 149.714 147.927 + vertex 402.172 157.823 155.769 + vertex 404.779 158.449 148.031 + endloop + endfacet + facet normal -0.931475 -0.200052 -0.303865 + outer loop + vertex 408.558 140.774 147.994 + vertex 406.66 149.714 147.927 + vertex 410.946 141.362 140.288 + endloop + endfacet + facet normal -0.936516 -0.211874 -0.279369 + outer loop + vertex 412.936 132.018 140.705 + vertex 410.946 141.362 140.288 + vertex 415.102 132.573 133.021 + endloop + endfacet + facet normal -0.93175 -0.23182 -0.279467 + outer loop + vertex 417.284 122.852 133.81 + vertex 412.936 132.018 140.705 + vertex 415.102 132.573 133.021 + endloop + endfacet + facet normal -0.939502 -0.204373 -0.274897 + outer loop + vertex 413.091 141.915 132.598 + vertex 409.039 150.3 140.212 + vertex 411.17 150.845 132.525 + endloop + endfacet + facet normal -0.940475 -0.199908 -0.274851 + outer loop + vertex 409.039 150.3 140.212 + vertex 407.154 159.029 140.311 + vertex 411.17 150.845 132.525 + endloop + endfacet + facet normal -0.932982 -0.197621 -0.300817 + outer loop + vertex 407.154 159.029 140.311 + vertex 402.9 167.202 148.138 + vertex 405.269 167.777 140.412 + endloop + endfacet + facet normal -0.93368 -0.196239 -0.299554 + outer loop + vertex 405.269 167.777 140.412 + vertex 401.03 176.079 148.185 + vertex 403.393 176.651 140.446 + endloop + endfacet + facet normal -0.936859 -0.182154 -0.298522 + outer loop + vertex 403.393 176.651 140.446 + vertex 399.275 185.105 148.211 + vertex 401.631 185.673 140.472 + endloop + endfacet + facet normal -0.944569 -0.137437 -0.298163 + outer loop + vertex 401.631 185.673 140.472 + vertex 397.868 194.33 148.402 + vertex 400.265 194.907 140.541 + endloop + endfacet + facet normal -0.952348 -0.186664 -0.241226 + outer loop + vertex 407.331 177.671 125.16 + vertex 403.721 186.198 132.813 + vertex 405.54 186.687 125.252 + endloop + endfacet + facet normal -0.949082 -0.201515 -0.242146 + outer loop + vertex 409.227 168.803 125.109 + vertex 405.499 177.177 132.751 + vertex 407.331 177.671 125.16 + endloop + endfacet + facet normal -0.948273 -0.203815 -0.243389 + outer loop + vertex 411.13 160.063 125.012 + vertex 407.38 168.309 132.719 + vertex 409.227 168.803 125.109 + endloop + endfacet + facet normal -0.947969 -0.204203 -0.244248 + outer loop + vertex 413.035 151.343 124.91 + vertex 409.276 159.566 132.625 + vertex 411.13 160.063 125.012 + endloop + endfacet + facet normal -0.953489 -0.208626 -0.217563 + outer loop + vertex 414.974 142.417 124.97 + vertex 413.035 151.343 124.91 + vertex 416.587 142.886 117.452 + endloop + endfacet + facet normal -0.957241 -0.220048 -0.187801 + outer loop + vertex 418.663 133.553 117.809 + vertex 416.587 142.886 117.452 + vertex 420.014 133.981 110.417 + endloop + endfacet + facet normal -0.9524 -0.239928 -0.188066 + outer loop + vertex 422.336 124.264 111.055 + vertex 418.663 133.553 117.809 + vertex 420.014 133.981 110.417 + endloop + endfacet + facet normal -0.959926 -0.213975 -0.180986 + outer loop + vertex 417.908 143.32 110.057 + vertex 414.629 151.813 117.406 + vertex 415.927 152.251 110.007 + endloop + endfacet + facet normal -0.961009 -0.210083 -0.179797 + outer loop + vertex 415.927 152.251 110.007 + vertex 412.711 160.533 117.517 + vertex 413.998 160.979 110.117 + endloop + endfacet + facet normal -0.961345 -0.209803 -0.178323 + outer loop + vertex 413.998 160.979 110.117 + vertex 410.794 169.274 117.629 + vertex 412.067 169.721 110.242 + endloop + endfacet + facet normal -0.962331 -0.206987 -0.176283 + outer loop + vertex 412.067 169.721 110.242 + vertex 408.89 178.139 117.702 + vertex 410.149 178.577 110.315 + endloop + endfacet + facet normal -0.965502 -0.195256 -0.172279 + outer loop + vertex 410.149 178.577 110.315 + vertex 407.091 187.146 117.741 + vertex 408.338 187.557 110.287 + endloop + endfacet + facet normal -0.973366 -0.159489 -0.16469 + outer loop + vertex 408.338 187.557 110.287 + vertex 405.665 196.34 117.578 + vertex 406.869 196.709 110.104 + endloop + endfacet + facet normal -0.976282 -0.202737 -0.07597 + outer loop + vertex 411.653 179.11 95.2454 + vertex 409.244 187.87 102.836 + vertex 409.791 188.051 95.3148 + endloop + endfacet + facet normal -0.973431 -0.215339 -0.0778557 + outer loop + vertex 413.604 170.296 95.2381 + vertex 411.086 178.926 102.85 + vertex 411.653 179.11 95.2454 + endloop + endfacet + facet normal -0.972562 -0.21796 -0.0813448 + outer loop + vertex 415.565 161.574 95.1659 + vertex 413.016 170.092 102.809 + vertex 413.604 170.296 95.2381 + endloop + endfacet + facet normal -0.971995 -0.219142 -0.0848687 + outer loop + vertex 417.535 152.86 95.1021 + vertex 414.956 161.356 102.695 + vertex 415.565 161.574 95.1659 + endloop + endfacet + facet normal -0.970838 -0.223046 -0.0878816 + outer loop + vertex 419.572 143.944 95.2249 + vertex 416.909 152.631 102.601 + vertex 417.535 152.86 95.1021 + endloop + endfacet + facet normal -0.968104 -0.232694 -0.0928864 + outer loop + vertex 421.767 134.63 95.6825 + vertex 418.915 143.701 102.682 + vertex 419.572 143.944 95.2249 + endloop + endfacet + facet normal -0.957347 -0.272389 -0.09639 + outer loop + vertex 426.403 117.905 94.4604 + vertex 425.796 118.641 98.406 + vertex 424.2 124.934 96.4781 + endloop + endfacet + facet normal -0.959261 -0.279967 -0.0378947 + outer loop + vertex 426.74 118.078 86.9462 + vertex 426.342 118.897 90.9663 + vertex 424.607 125.108 88.9966 + endloop + endfacet + facet normal -0.967717 -0.252001 0.00447739 + outer loop + vertex 424.607 125.108 88.9966 + vertex 422.096 134.738 88.2274 + vertex 424.566 125.134 81.6728 + endloop + endfacet + facet normal -0.966798 -0.255355 0.00973849 + outer loop + vertex 424.566 125.134 81.6728 + vertex 422.096 134.738 88.2274 + vertex 422.028 134.728 81.196 + endloop + endfacet + facet normal -0.972065 -0.234511 0.00975834 + outer loop + vertex 422.096 134.738 88.2274 + vertex 419.857 144 87.8011 + vertex 422.028 134.728 81.196 + endloop + endfacet + facet normal -0.971385 -0.237119 0.0136438 + outer loop + vertex 422.028 134.728 81.196 + vertex 419.857 144 87.8011 + vertex 419.773 143.95 80.9196 + endloop + endfacet + facet normal -0.973958 -0.226319 0.0135977 + outer loop + vertex 419.857 144 87.8011 + vertex 417.793 152.876 87.6806 + vertex 419.773 143.95 80.9196 + endloop + endfacet + facet normal -0.973412 -0.22846 0.0165838 + outer loop + vertex 419.773 143.95 80.9196 + vertex 417.793 152.876 87.6806 + vertex 417.7 152.777 80.8389 + endloop + endfacet + facet normal -0.974673 -0.223025 0.0165224 + outer loop + vertex 417.793 152.876 87.6806 + vertex 415.803 161.576 87.7095 + vertex 417.7 152.777 80.8389 + endloop + endfacet + facet normal -0.974086 -0.225326 0.0196323 + outer loop + vertex 417.7 152.777 80.8389 + vertex 415.803 161.576 87.7095 + vertex 415.685 161.487 80.8488 + endloop + endfacet + facet normal -0.974967 -0.221486 0.0195979 + outer loop + vertex 415.803 161.576 87.7095 + vertex 413.822 170.299 87.7377 + vertex 415.685 161.487 80.8488 + endloop + endfacet + facet normal -0.974357 -0.223852 0.0227893 + outer loop + vertex 415.685 161.487 80.8488 + vertex 413.822 170.299 87.7377 + vertex 413.669 170.265 80.8746 + endloop + endfacet + facet normal -0.975578 -0.218466 0.0227903 + outer loop + vertex 413.822 170.299 87.7377 + vertex 411.844 179.129 87.7441 + vertex 413.669 170.265 80.8746 + endloop + endfacet + facet normal -0.975309 -0.219514 0.0242146 + outer loop + vertex 413.669 170.265 80.8746 + vertex 411.844 179.129 87.7441 + vertex 411.673 179.133 80.8915 + endloop + endfacet + facet normal -0.978616 -0.204257 0.0243059 + outer loop + vertex 411.844 179.129 87.7441 + vertex 409.972 188.115 87.8636 + vertex 411.673 179.133 80.8915 + endloop + endfacet + facet normal -0.978578 -0.20441 0.0245127 + outer loop + vertex 411.673 179.133 80.8915 + vertex 409.972 188.115 87.8636 + vertex 409.793 188.15 81.0097 + endloop + endfacet + facet normal -0.987747 -0.154045 0.0250078 + outer loop + vertex 409.972 188.115 87.8636 + vertex 408.53 197.401 88.1358 + vertex 409.793 188.15 81.0097 + endloop + endfacet + facet normal -0.987102 -0.157362 0.0294277 + outer loop + vertex 409.793 188.15 81.0097 + vertex 408.53 197.401 88.1358 + vertex 408.306 197.449 80.857 + endloop + endfacet + facet normal -0.948764 -0.312839 0.0444747 + outer loop + vertex 427.971 113.84 79.911 + vertex 426.448 118.959 83.4229 + vertex 426.548 118.093 79.4619 + endloop + endfacet + facet normal -0.965533 -0.252332 0.0638267 + outer loop + vertex 424.566 125.134 81.6728 + vertex 422.028 134.728 81.196 + vertex 424.134 125.198 75.378 + endloop + endfacet + facet normal -0.965903 -0.25135 0.0620841 + outer loop + vertex 424.134 125.198 75.378 + vertex 422.028 134.728 81.196 + vertex 421.563 135.059 75.312 + endloop + endfacet + facet normal -0.969869 -0.235261 0.0633038 + outer loop + vertex 422.028 134.728 81.196 + vertex 419.773 143.95 80.9196 + vertex 421.563 135.059 75.312 + endloop + endfacet + facet normal -0.96986 -0.235284 0.0633427 + outer loop + vertex 421.563 135.059 75.312 + vertex 419.773 143.95 80.9196 + vertex 419.358 144.116 75.1879 + endloop + endfacet + facet normal -0.971665 -0.227619 0.0636948 + outer loop + vertex 419.773 143.95 80.9196 + vertex 417.7 152.777 80.8389 + vertex 419.358 144.116 75.1879 + endloop + endfacet + facet normal -0.971342 -0.228559 0.0652311 + outer loop + vertex 419.358 144.116 75.1879 + vertex 417.7 152.777 80.8389 + vertex 417.285 152.917 75.1587 + endloop + endfacet + facet normal -0.972177 -0.224937 0.0653815 + outer loop + vertex 417.7 152.777 80.8389 + vertex 415.685 161.487 80.8488 + vertex 417.285 152.917 75.1587 + endloop + endfacet + facet normal -0.971604 -0.226611 0.0680643 + outer loop + vertex 417.285 152.917 75.1587 + vertex 415.685 161.487 80.8488 + vertex 415.234 161.718 75.1781 + endloop + endfacet + facet normal -0.972308 -0.223515 0.0682463 + outer loop + vertex 415.685 161.487 80.8488 + vertex 413.669 170.265 80.8746 + vertex 415.234 161.718 75.1781 + endloop + endfacet + facet normal -0.971937 -0.224595 0.0699686 + outer loop + vertex 415.234 161.718 75.1781 + vertex 413.669 170.265 80.8746 + vertex 413.187 170.58 75.1936 + endloop + endfacet + facet normal -0.973157 -0.219118 0.0703757 + outer loop + vertex 413.669 170.265 80.8746 + vertex 411.673 179.133 80.8915 + vertex 413.187 170.58 75.1936 + endloop + endfacet + facet normal -0.972588 -0.220776 0.0730154 + outer loop + vertex 413.187 170.58 75.1936 + vertex 411.673 179.133 80.8915 + vertex 411.188 179.413 75.2755 + endloop + endfacet + facet normal -0.976049 -0.204533 0.0741242 + outer loop + vertex 411.673 179.133 80.8915 + vertex 409.793 188.15 81.0097 + vertex 411.188 179.413 75.2755 + endloop + endfacet + facet normal -0.975053 -0.207488 0.0788693 + outer loop + vertex 411.188 179.413 75.2755 + vertex 409.793 188.15 81.0097 + vertex 409.312 188.202 75.206 + endloop + endfacet + facet normal -0.984485 -0.156111 0.0801114 + outer loop + vertex 409.312 188.202 75.206 + vertex 409.793 188.15 81.0097 + vertex 408.306 197.449 80.857 + endloop + endfacet + facet normal -0.980595 -0.168238 0.100648 + outer loop + vertex 408.306 197.449 80.857 + vertex 407.635 197.374 74.199 + vertex 409.312 188.202 75.206 + endloop + endfacet + facet normal -0.949459 -0.305688 0.0712894 + outer loop + vertex 427.646 113.962 76.3777 + vertex 426.548 118.093 79.4619 + vertex 425.972 119.177 76.4408 + endloop + endfacet + facet normal -0.947923 -0.309175 0.0765073 + outer loop + vertex 427.971 113.84 79.911 + vertex 426.548 118.093 79.4619 + vertex 427.646 113.962 76.3777 + endloop + endfacet + facet normal -0.935818 -0.350356 0.0386634 + outer loop + vertex 429.598 109.506 80.0127 + vertex 428.117 113.862 83.6443 + vertex 427.971 113.84 79.911 + endloop + endfacet + facet normal -0.936369 -0.349072 0.0368996 + outer loop + vertex 429.726 109.552 83.6905 + vertex 428.117 113.862 83.6443 + vertex 429.598 109.506 80.0127 + endloop + endfacet + facet normal -0.937284 -0.348529 -0.00512776 + outer loop + vertex 429.722 109.508 87.4037 + vertex 428.111 113.838 87.4048 + vertex 429.726 109.552 83.6905 + endloop + endfacet + facet normal -0.911418 -0.409985 -0.0350488 + outer loop + vertex 431.377 105.479 90.8362 + vertex 429.597 109.41 91.1404 + vertex 431.481 105.568 87.0853 + endloop + endfacet + facet normal -0.910773 -0.407037 -0.0693772 + outer loop + vertex 431.377 105.479 90.8362 + vertex 429.364 109.294 94.8859 + vertex 429.597 109.41 91.1404 + endloop + endfacet + facet normal -0.908882 -0.412176 -0.0635958 + outer loop + vertex 431.157 105.384 94.5996 + vertex 429.364 109.294 94.8859 + vertex 431.377 105.479 90.8362 + endloop + endfacet + facet normal -0.907618 -0.409481 -0.0924941 + outer loop + vertex 431.157 105.384 94.5996 + vertex 429.039 109.178 98.5819 + vertex 429.364 109.294 94.8859 + endloop + endfacet + facet normal -0.906019 -0.414158 -0.0871886 + outer loop + vertex 430.843 105.29 98.3075 + vertex 429.039 109.178 98.5819 + vertex 431.157 105.384 94.5996 + endloop + endfacet + facet normal -0.904235 -0.411404 -0.114483 + outer loop + vertex 430.843 105.29 98.3075 + vertex 428.639 109.053 102.197 + vertex 429.039 109.178 98.5819 + endloop + endfacet + facet normal -0.902702 -0.41625 -0.108926 + outer loop + vertex 430.453 105.187 101.93 + vertex 428.639 109.053 102.197 + vertex 430.843 105.29 98.3075 + endloop + endfacet + facet normal -0.900557 -0.413493 -0.134243 + outer loop + vertex 430.453 105.187 101.93 + vertex 428.17 108.92 105.751 + vertex 428.639 109.053 102.197 + endloop + endfacet + facet normal -0.899892 -0.41578 -0.131612 + outer loop + vertex 429.99 105.059 105.505 + vertex 428.17 108.92 105.751 + vertex 430.453 105.187 101.93 + endloop + endfacet + facet normal -0.897273 -0.412991 -0.156011 + outer loop + vertex 429.99 105.059 105.505 + vertex 427.623 108.757 109.326 + vertex 428.17 108.92 105.751 + endloop + endfacet + facet normal -0.895955 -0.417882 -0.150462 + outer loop + vertex 429.453 104.919 109.091 + vertex 427.623 108.757 109.326 + vertex 429.99 105.059 105.505 + endloop + endfacet + facet normal -0.893175 -0.415188 -0.172791 + outer loop + vertex 429.453 104.919 109.091 + vertex 426.996 108.583 112.984 + vertex 427.623 108.757 109.326 + endloop + endfacet + facet normal -0.892649 -0.417257 -0.170512 + outer loop + vertex 428.83 104.75 112.767 + vertex 426.996 108.583 112.984 + vertex 429.453 104.919 109.091 + endloop + endfacet + facet normal -0.889938 -0.41489 -0.189412 + outer loop + vertex 428.83 104.75 112.767 + vertex 426.282 108.392 116.762 + vertex 426.996 108.583 112.984 + endloop + endfacet + facet normal -0.889205 -0.417907 -0.186194 + outer loop + vertex 428.121 104.569 116.557 + vertex 426.282 108.392 116.762 + vertex 428.83 104.75 112.767 + endloop + endfacet + facet normal -0.886022 -0.41531 -0.206114 + outer loop + vertex 428.121 104.569 116.557 + vertex 425.48 108.176 120.641 + vertex 426.282 108.392 116.762 + endloop + endfacet + facet normal -0.88529 -0.418463 -0.202856 + outer loop + vertex 427.326 104.366 120.445 + vertex 425.48 108.176 120.641 + vertex 428.121 104.569 116.557 + endloop + endfacet + facet normal -0.882057 -0.415949 -0.221272 + outer loop + vertex 427.326 104.366 120.445 + vertex 424.605 107.947 124.562 + vertex 425.48 108.176 120.641 + endloop + endfacet + facet normal -0.881071 -0.420396 -0.216751 + outer loop + vertex 426.462 104.155 124.368 + vertex 424.605 107.947 124.562 + vertex 427.326 104.366 120.445 + endloop + endfacet + facet normal -0.877384 -0.417596 -0.236243 + outer loop + vertex 426.462 104.155 124.368 + vertex 423.67 107.705 128.463 + vertex 424.605 107.947 124.562 + endloop + endfacet + facet normal -0.876578 -0.421459 -0.232344 + outer loop + vertex 425.536 103.927 128.275 + vertex 423.67 107.705 128.463 + vertex 426.462 104.155 124.368 + endloop + endfacet + facet normal -0.873377 -0.419094 -0.24814 + outer loop + vertex 425.536 103.927 128.275 + vertex 422.693 107.469 132.299 + vertex 423.67 107.705 128.463 + endloop + endfacet + facet normal -0.87276 -0.422267 -0.24491 + outer loop + vertex 424.566 103.697 132.127 + vertex 422.693 107.469 132.299 + vertex 425.536 103.927 128.275 + endloop + endfacet + facet normal -0.868738 -0.419422 -0.263401 + outer loop + vertex 424.566 103.697 132.127 + vertex 421.663 107.214 136.1 + vertex 422.693 107.469 132.299 + endloop + endfacet + facet normal -0.867972 -0.423684 -0.25907 + outer loop + vertex 423.546 103.455 135.94 + vertex 421.663 107.214 136.1 + vertex 424.566 103.697 132.127 + endloop + endfacet + facet normal -0.864197 -0.421096 -0.275394 + outer loop + vertex 423.546 103.455 135.94 + vertex 420.582 106.954 139.89 + vertex 421.663 107.214 136.1 + endloop + endfacet + facet normal -0.863361 -0.426008 -0.270416 + outer loop + vertex 422.477 103.208 139.744 + vertex 420.582 106.954 139.89 + vertex 423.546 103.455 135.94 + endloop + endfacet + facet normal -0.859315 -0.423311 -0.287028 + outer loop + vertex 422.477 103.208 139.744 + vertex 419.44 106.684 143.71 + vertex 420.582 106.954 139.89 + endloop + endfacet + facet normal -0.858598 -0.427703 -0.282631 + outer loop + vertex 421.345 102.947 143.577 + vertex 419.44 106.684 143.71 + vertex 422.477 103.208 139.744 + endloop + endfacet + facet normal -0.854496 -0.425042 -0.298622 + outer loop + vertex 421.345 102.947 143.577 + vertex 418.23 106.397 147.581 + vertex 419.44 106.684 143.71 + endloop + endfacet + facet normal -0.853538 -0.431038 -0.292709 + outer loop + vertex 420.151 102.676 147.457 + vertex 418.23 106.397 147.581 + vertex 421.345 102.947 143.577 + endloop + endfacet + facet normal -0.849551 -0.428479 -0.307684 + outer loop + vertex 420.151 102.676 147.457 + vertex 416.959 106.106 151.494 + vertex 418.23 106.397 147.581 + endloop + endfacet + facet normal -0.848782 -0.433367 -0.302923 + outer loop + vertex 418.895 102.393 151.381 + vertex 416.959 106.106 151.494 + vertex 420.151 102.676 147.457 + endloop + endfacet + facet normal -0.84421 -0.43048 -0.31937 + outer loop + vertex 418.895 102.393 151.381 + vertex 415.626 105.793 155.438 + vertex 416.959 106.106 151.494 + endloop + endfacet + facet normal -0.843264 -0.436645 -0.313442 + outer loop + vertex 417.581 102.095 155.331 + vertex 415.626 105.793 155.438 + vertex 418.895 102.393 151.381 + endloop + endfacet + facet normal -0.83916 -0.434064 -0.327719 + outer loop + vertex 417.581 102.095 155.331 + vertex 414.252 105.479 159.374 + vertex 415.626 105.793 155.438 + endloop + endfacet + facet normal -0.83854 -0.438262 -0.323694 + outer loop + vertex 416.221 101.782 159.279 + vertex 414.252 105.479 159.374 + vertex 417.581 102.095 155.331 + endloop + endfacet + facet normal -0.833904 -0.435394 -0.339169 + outer loop + vertex 416.221 101.782 159.279 + vertex 412.835 105.144 163.288 + vertex 414.252 105.479 159.374 + endloop + endfacet + facet normal -0.832794 -0.443238 -0.331653 + outer loop + vertex 414.829 101.467 163.195 + vertex 412.835 105.144 163.288 + vertex 416.221 101.782 159.279 + endloop + endfacet + facet normal -0.828151 -0.440338 -0.346796 + outer loop + vertex 414.829 101.467 163.195 + vertex 411.391 104.81 167.16 + vertex 412.835 105.144 163.288 + endloop + endfacet + facet normal -0.82748 -0.445301 -0.342029 + outer loop + vertex 413.401 101.134 167.083 + vertex 411.391 104.81 167.16 + vertex 414.829 101.467 163.195 + endloop + endfacet + facet normal -0.822779 -0.442418 -0.356792 + outer loop + vertex 413.401 101.134 167.083 + vertex 409.908 104.463 171.011 + vertex 411.391 104.81 167.16 + endloop + endfacet + facet normal -0.822069 -0.447978 -0.35145 + outer loop + vertex 411.935 100.79 170.95 + vertex 409.908 104.463 171.011 + vertex 413.401 101.134 167.083 + endloop + endfacet + facet normal -0.8182 -0.445647 -0.363246 + outer loop + vertex 411.935 100.79 170.95 + vertex 408.394 104.121 174.839 + vertex 409.908 104.463 171.011 + endloop + endfacet + facet normal -0.817634 -0.450322 -0.358726 + outer loop + vertex 410.437 100.445 174.799 + vertex 408.394 104.121 174.839 + vertex 411.935 100.79 170.95 + endloop + endfacet + facet normal -0.81331 -0.44778 -0.37151 + outer loop + vertex 410.437 100.445 174.799 + vertex 406.846 103.772 178.649 + vertex 408.394 104.121 174.839 + endloop + endfacet + facet normal -0.812656 -0.453517 -0.365941 + outer loop + vertex 408.908 100.099 178.623 + vertex 406.846 103.772 178.649 + vertex 410.437 100.445 174.799 + endloop + endfacet + facet normal -0.807781 -0.450684 -0.379966 + outer loop + vertex 408.908 100.099 178.623 + vertex 405.27 103.408 182.431 + vertex 406.846 103.772 178.649 + endloop + endfacet + facet normal -0.807039 -0.457512 -0.373323 + outer loop + vertex 407.355 99.7454 182.412 + vertex 405.27 103.408 182.431 + vertex 408.908 100.099 178.623 + endloop + endfacet + facet normal -0.801399 -0.454217 -0.389162 + outer loop + vertex 407.355 99.7454 182.412 + vertex 403.672 103.014 186.183 + vertex 405.27 103.408 182.431 + endloop + endfacet + facet normal -0.800492 -0.462763 -0.38087 + outer loop + vertex 405.783 99.3774 186.164 + vertex 403.672 103.014 186.183 + vertex 407.355 99.7454 182.412 + endloop + endfacet + facet normal -0.795211 -0.459618 -0.395463 + outer loop + vertex 405.783 99.3774 186.164 + vertex 402.065 102.596 189.9 + vertex 403.672 103.014 186.183 + endloop + endfacet + facet normal -0.794621 -0.465253 -0.390022 + outer loop + vertex 404.184 98.9868 189.888 + vertex 402.065 102.596 189.9 + vertex 405.783 99.3774 186.164 + endloop + endfacet + facet normal -0.788638 -0.461684 -0.406075 + outer loop + vertex 404.184 98.9868 189.888 + vertex 400.415 102.148 193.613 + vertex 402.065 102.596 189.9 + endloop + endfacet + facet normal -0.787459 -0.472757 -0.395487 + outer loop + vertex 402.567 98.5908 193.581 + vertex 400.415 102.148 193.613 + vertex 404.184 98.9868 189.888 + endloop + endfacet + facet normal -0.781666 -0.469109 -0.411017 + outer loop + vertex 402.567 98.5908 193.581 + vertex 398.745 101.698 197.302 + vertex 400.415 102.148 193.613 + endloop + endfacet + facet normal -0.78068 -0.477941 -0.40263 + outer loop + vertex 400.93 98.1871 197.233 + vertex 398.745 101.698 197.302 + vertex 402.567 98.5908 193.581 + endloop + endfacet + facet normal -0.774444 -0.473733 -0.419301 + outer loop + vertex 400.93 98.1871 197.233 + vertex 397.059 101.243 200.93 + vertex 398.745 101.698 197.302 + endloop + endfacet + facet normal -0.773265 -0.484176 -0.409433 + outer loop + vertex 399.278 97.7792 200.836 + vertex 397.059 101.243 200.93 + vertex 400.93 98.1871 197.233 + endloop + endfacet + facet normal -0.768498 -0.480776 -0.422214 + outer loop + vertex 399.278 97.7792 200.836 + vertex 395.371 100.822 204.482 + vertex 397.059 101.243 200.93 + endloop + endfacet + facet normal -0.767868 -0.48652 -0.416746 + outer loop + vertex 397.61 97.358 204.402 + vertex 395.371 100.822 204.482 + vertex 399.278 97.7792 200.836 + endloop + endfacet + facet normal -0.762196 -0.482511 -0.431555 + outer loop + vertex 397.61 97.358 204.402 + vertex 393.657 100.39 207.993 + vertex 395.371 100.822 204.482 + endloop + endfacet + facet normal -0.761529 -0.489147 -0.425216 + outer loop + vertex 395.92 96.9068 207.947 + vertex 393.657 100.39 207.993 + vertex 397.61 97.358 204.402 + endloop + endfacet + facet normal -0.756534 -0.485734 -0.437858 + outer loop + vertex 395.92 96.9068 207.947 + vertex 391.936 99.9322 211.475 + vertex 393.657 100.39 207.993 + endloop + endfacet + facet normal -0.75624 -0.488972 -0.434749 + outer loop + vertex 394.212 96.4234 211.463 + vertex 391.936 99.9322 211.475 + vertex 395.92 96.9068 207.947 + endloop + endfacet + facet normal -0.750713 -0.48534 -0.44819 + outer loop + vertex 394.212 96.4234 211.463 + vertex 390.202 99.4376 214.914 + vertex 391.936 99.9322 211.475 + endloop + endfacet + facet normal -0.750087 -0.493182 -0.440614 + outer loop + vertex 392.504 95.9272 214.924 + vertex 390.202 99.4376 214.914 + vertex 394.212 96.4234 211.463 + endloop + endfacet + facet normal -0.744185 -0.48935 -0.45467 + outer loop + vertex 392.504 95.9272 214.924 + vertex 388.472 98.9301 218.292 + vertex 390.202 99.4376 214.914 + endloop + endfacet + facet normal -0.743763 -0.495404 -0.448767 + outer loop + vertex 390.794 95.4204 218.318 + vertex 388.472 98.9301 218.292 + vertex 392.504 95.9272 214.924 + endloop + endfacet + facet normal -0.737118 -0.491123 -0.464171 + outer loop + vertex 390.794 95.4204 218.318 + vertex 386.729 98.4084 221.613 + vertex 388.472 98.9301 218.292 + endloop + endfacet + facet normal -0.736566 -0.500264 -0.455199 + outer loop + vertex 389.081 94.906 221.655 + vertex 386.729 98.4084 221.613 + vertex 390.794 95.4204 218.318 + endloop + endfacet + facet normal -0.730626 -0.496438 -0.468758 + outer loop + vertex 389.081 94.906 221.655 + vertex 384.981 97.8833 224.893 + vertex 386.729 98.4084 221.613 + endloop + endfacet + facet normal -0.730388 -0.500944 -0.464314 + outer loop + vertex 387.348 94.3738 224.955 + vertex 384.981 97.8833 224.893 + vertex 389.081 94.906 221.655 + endloop + endfacet + facet normal -0.723893 -0.496818 -0.478697 + outer loop + vertex 387.348 94.3738 224.955 + vertex 383.208 97.3381 228.14 + vertex 384.981 97.8833 224.893 + endloop + endfacet + facet normal -0.723527 -0.505117 -0.470496 + outer loop + vertex 385.603 93.8291 228.223 + vertex 383.208 97.3381 228.14 + vertex 387.348 94.3738 224.955 + endloop + endfacet + facet normal -0.71797 -0.50161 -0.482604 + outer loop + vertex 385.603 93.8291 228.223 + vertex 381.444 96.7919 231.331 + vertex 383.208 97.3381 228.14 + endloop + endfacet + facet normal -0.717878 -0.504441 -0.479782 + outer loop + vertex 383.848 93.2692 231.439 + vertex 381.444 96.7919 231.331 + vertex 385.603 93.8291 228.223 + endloop + endfacet + facet normal -0.711712 -0.500631 -0.492783 + outer loop + vertex 383.848 93.2692 231.439 + vertex 379.682 96.2329 234.444 + vertex 381.444 96.7919 231.331 + endloop + endfacet + facet normal -0.711576 -0.508905 -0.484434 + outer loop + vertex 382.113 92.7116 234.573 + vertex 379.682 96.2329 234.444 + vertex 383.848 93.2692 231.439 + endloop + endfacet + facet normal -0.704004 -0.504251 -0.500109 + outer loop + vertex 382.113 92.7116 234.573 + vertex 377.936 95.6715 237.468 + vertex 379.682 96.2329 234.444 + endloop + endfacet + facet normal -0.704006 -0.510656 -0.493564 + outer loop + vertex 380.387 92.1472 237.619 + vertex 377.936 95.6715 237.468 + vertex 382.113 92.7116 234.573 + endloop + endfacet + facet normal -0.698114 -0.507072 -0.505485 + outer loop + vertex 380.387 92.1472 237.619 + vertex 376.204 95.1085 240.425 + vertex 377.936 95.6715 237.468 + endloop + endfacet + facet normal -0.698154 -0.509462 -0.50302 + outer loop + vertex 378.659 91.5729 240.599 + vertex 376.204 95.1085 240.425 + vertex 380.387 92.1472 237.619 + endloop + endfacet + facet normal -0.691121 -0.505261 -0.516781 + outer loop + vertex 378.659 91.5729 240.599 + vertex 374.448 94.523 243.346 + vertex 376.204 95.1085 240.425 + endloop + endfacet + facet normal -0.69135 -0.513521 -0.508263 + outer loop + vertex 376.925 90.992 243.545 + vertex 374.448 94.523 243.346 + vertex 378.659 91.5729 240.599 + endloop + endfacet + facet normal -0.684665 -0.509554 -0.521142 + outer loop + vertex 376.925 90.992 243.545 + vertex 372.684 93.9284 246.245 + vertex 374.448 94.523 243.346 + endloop + endfacet + facet normal -0.684786 -0.512941 -0.517648 + outer loop + vertex 375.165 90.3906 246.468 + vertex 372.684 93.9284 246.245 + vertex 376.925 90.992 243.545 + endloop + endfacet + facet normal -0.676884 -0.508331 -0.532379 + outer loop + vertex 375.165 90.3906 246.468 + vertex 370.898 93.3132 249.103 + vertex 372.684 93.9284 246.245 + endloop + endfacet + facet normal -0.677105 -0.512696 -0.527894 + outer loop + vertex 373.385 89.7711 249.354 + vertex 370.898 93.3132 249.103 + vertex 375.165 90.3906 246.468 + endloop + endfacet + facet normal -0.672351 -0.50997 -0.53654 + outer loop + vertex 373.385 89.7711 249.354 + vertex 369.133 92.7099 251.888 + vertex 370.898 93.3132 249.103 + endloop + endfacet + facet normal -0.672634 -0.51409 -0.532236 + outer loop + vertex 371.626 89.1612 252.166 + vertex 369.133 92.7099 251.888 + vertex 373.385 89.7711 249.354 + endloop + endfacet + facet normal -0.665739 -0.510207 -0.5445 + outer loop + vertex 371.626 89.1612 252.166 + vertex 367.385 92.1222 254.576 + vertex 369.133 92.7099 251.888 + endloop + endfacet + facet normal -0.665973 -0.512633 -0.54193 + outer loop + vertex 369.881 88.5597 254.878 + vertex 367.385 92.1222 254.576 + vertex 371.626 89.1612 252.166 + endloop + endfacet + facet normal -0.659811 -0.50922 -0.552579 + outer loop + vertex 369.881 88.5597 254.878 + vertex 365.659 91.5522 257.163 + vertex 367.385 92.1222 254.576 + endloop + endfacet + facet normal -0.660139 -0.511825 -0.549774 + outer loop + vertex 368.162 87.9759 257.486 + vertex 365.659 91.5522 257.163 + vertex 369.881 88.5597 254.878 + endloop + endfacet + facet normal -0.654703 -0.508848 -0.558961 + outer loop + vertex 368.162 87.9759 257.486 + vertex 363.963 90.9897 259.661 + vertex 365.659 91.5522 257.163 + endloop + endfacet + facet normal -0.654721 -0.508962 -0.558837 + outer loop + vertex 366.465 87.3973 260.001 + vertex 363.963 90.9897 259.661 + vertex 368.162 87.9759 257.486 + endloop + endfacet + facet normal -0.646958 -0.50476 -0.571544 + outer loop + vertex 366.465 87.3973 260.001 + vertex 362.29 90.4031 262.073 + vertex 363.963 90.9897 259.661 + endloop + endfacet + facet normal -0.646906 -0.50447 -0.571859 + outer loop + vertex 364.781 86.8029 262.431 + vertex 362.29 90.4031 262.073 + vertex 366.465 87.3973 260.001 + endloop + endfacet + facet normal -0.639312 -0.500409 -0.583842 + outer loop + vertex 364.781 86.8029 262.431 + vertex 360.67 89.8036 264.36 + vertex 362.29 90.4031 262.073 + endloop + endfacet + facet normal -0.640217 -0.504639 -0.579191 + outer loop + vertex 363.16 86.2135 264.736 + vertex 360.67 89.8036 264.36 + vertex 364.781 86.8029 262.431 + endloop + endfacet + facet normal -0.633351 -0.50099 -0.58981 + outer loop + vertex 363.16 86.2135 264.736 + vertex 359.18 89.2644 266.419 + vertex 360.67 89.8036 264.36 + endloop + endfacet + facet normal -0.633341 -0.500954 -0.58985 + outer loop + vertex 361.652 85.6697 266.817 + vertex 359.18 89.2644 266.419 + vertex 363.16 86.2135 264.736 + endloop + endfacet + facet normal -0.638043 -0.503391 -0.582665 + outer loop + vertex 361.652 85.6697 266.817 + vertex 357.946 88.8968 268.088 + vertex 359.18 89.2644 266.419 + endloop + endfacet + facet normal -0.636667 -0.500113 -0.586977 + outer loop + vertex 360.405 85.2722 268.508 + vertex 357.946 88.8968 268.088 + vertex 361.652 85.6697 266.817 + endloop + endfacet + facet normal -0.644656 -0.504111 -0.574709 + outer loop + vertex 360.405 85.2722 268.508 + vertex 357.038 88.7221 269.259 + vertex 357.946 88.8968 268.088 + endloop + endfacet + facet normal -0.640046 -0.497202 -0.585774 + outer loop + vertex 359.497 85.0481 269.691 + vertex 357.038 88.7221 269.259 + vertex 360.405 85.2722 268.508 + endloop + endfacet + facet normal -0.651966 -0.503017 -0.567375 + outer loop + vertex 359.497 85.0481 269.691 + vertex 356.52 88.6505 269.918 + vertex 357.038 88.7221 269.259 + endloop + endfacet + facet normal -0.638214 -0.489986 -0.593799 + outer loop + vertex 358.963 84.9392 270.355 + vertex 356.52 88.6505 269.918 + vertex 359.497 85.0481 269.691 + endloop + endfacet + facet normal -0.587047 -0.464457 -0.663065 + outer loop + vertex 358.963 84.9392 270.355 + vertex 356.372 88.4431 270.194 + vertex 356.52 88.6505 269.918 + endloop + endfacet + facet normal -0.597045 -0.471213 -0.649227 + outer loop + vertex 358.777 84.805 270.623 + vertex 356.372 88.4431 270.194 + vertex 358.963 84.9392 270.355 + endloop + endfacet + facet normal -0.145159 -0.20999 -0.966868 + outer loop + vertex 358.777 84.805 270.623 + vertex 356.567 87.9236 270.278 + vertex 356.372 88.4431 270.194 + endloop + endfacet + facet normal -0.369406 -0.356842 -0.858022 + outer loop + vertex 358.918 84.4729 270.7 + vertex 356.567 87.9236 270.278 + vertex 358.777 84.805 270.623 + endloop + endfacet + facet normal -0.936512 -0.348233 -0.0409721 + outer loop + vertex 429.722 109.508 87.4037 + vertex 427.98 113.751 91.1522 + vertex 428.111 113.838 87.4048 + endloop + endfacet + facet normal -0.949881 -0.304565 -0.070474 + outer loop + vertex 427.743 113.628 94.8848 + vertex 426.403 117.905 94.4604 + vertex 427.98 113.751 91.1522 + endloop + endfacet + facet normal -0.931852 -0.350775 -0.0927788 + outer loop + vertex 429.039 109.178 98.5819 + vertex 427.416 113.491 98.5759 + vertex 429.364 109.294 94.8859 + endloop + endfacet + facet normal -0.92946 -0.349908 -0.116908 + outer loop + vertex 429.039 109.178 98.5819 + vertex 427.014 113.354 102.188 + vertex 427.416 113.491 98.5759 + endloop + endfacet + facet normal -0.929164 -0.351271 -0.115164 + outer loop + vertex 428.639 109.053 102.197 + vertex 427.014 113.354 102.188 + vertex 429.039 109.178 98.5819 + endloop + endfacet + facet normal -0.926382 -0.35027 -0.138299 + outer loop + vertex 428.639 109.053 102.197 + vertex 426.541 113.201 105.743 + vertex 427.014 113.354 102.188 + endloop + endfacet + facet normal -0.943769 -0.30022 -0.138451 + outer loop + vertex 426.541 113.201 105.743 + vertex 424.928 118.331 105.616 + vertex 427.014 113.354 102.188 + endloop + endfacet + facet normal -0.940065 -0.299657 -0.162738 + outer loop + vertex 426.541 113.201 105.743 + vertex 424.689 117.283 108.923 + vertex 424.928 118.331 105.616 + endloop + endfacet + facet normal -0.939714 -0.303439 -0.157678 + outer loop + vertex 425.996 113.04 109.301 + vertex 424.689 117.283 108.923 + vertex 426.541 113.201 105.743 + endloop + endfacet + facet normal -0.922892 -0.351474 -0.157276 + outer loop + vertex 428.17 108.92 105.751 + vertex 425.996 113.04 109.301 + vertex 426.541 113.201 105.743 + endloop + endfacet + facet normal -0.922873 -0.351591 -0.157129 + outer loop + vertex 427.623 108.757 109.326 + vertex 425.996 113.04 109.301 + vertex 428.17 108.92 105.751 + endloop + endfacet + facet normal -0.919825 -0.350546 -0.176183 + outer loop + vertex 427.623 108.757 109.326 + vertex 425.37 112.853 112.939 + vertex 425.996 113.04 109.301 + endloop + endfacet + facet normal -0.937782 -0.29894 -0.176633 + outer loop + vertex 425.37 112.853 112.939 + vertex 423.763 117.968 112.816 + vertex 425.996 113.04 109.301 + endloop + endfacet + facet normal -0.933651 -0.298167 -0.198476 + outer loop + vertex 425.37 112.853 112.939 + vertex 423.374 116.892 116.259 + vertex 423.763 117.968 112.816 + endloop + endfacet + facet normal -0.933407 -0.302299 -0.193304 + outer loop + vertex 424.657 112.653 116.693 + vertex 423.374 116.892 116.259 + vertex 425.37 112.853 112.939 + endloop + endfacet + facet normal -0.916336 -0.351014 -0.192661 + outer loop + vertex 426.996 108.583 112.984 + vertex 424.657 112.653 116.693 + vertex 425.37 112.853 112.939 + endloop + endfacet + facet normal -0.916167 -0.352254 -0.191194 + outer loop + vertex 426.282 108.392 116.762 + vertex 424.657 112.653 116.693 + vertex 426.996 108.583 112.984 + endloop + endfacet + facet normal -0.912594 -0.351184 -0.209384 + outer loop + vertex 426.282 108.392 116.762 + vertex 423.858 112.427 120.558 + vertex 424.657 112.653 116.693 + endloop + endfacet + facet normal -0.931371 -0.297321 -0.210117 + outer loop + vertex 423.858 112.427 120.558 + vertex 422.272 117.538 120.356 + vertex 424.657 112.653 116.693 + endloop + endfacet + facet normal -0.926779 -0.296697 -0.23033 + outer loop + vertex 423.858 112.427 120.558 + vertex 421.728 116.427 123.974 + vertex 422.272 117.538 120.356 + endloop + endfacet + facet normal -0.926633 -0.301478 -0.224639 + outer loop + vertex 422.985 112.197 124.465 + vertex 421.728 116.427 123.974 + vertex 423.858 112.427 120.558 + endloop + endfacet + facet normal -0.909131 -0.351361 -0.223664 + outer loop + vertex 425.48 108.176 120.641 + vertex 422.985 112.197 124.465 + vertex 423.858 112.427 120.558 + endloop + endfacet + facet normal -0.909119 -0.351474 -0.223538 + outer loop + vertex 424.605 107.947 124.562 + vertex 422.985 112.197 124.465 + vertex 425.48 108.176 120.641 + endloop + endfacet + facet normal -0.905381 -0.35042 -0.239773 + outer loop + vertex 424.605 107.947 124.562 + vertex 422.049 111.948 128.366 + vertex 422.985 112.197 124.465 + endloop + endfacet + facet normal -0.924282 -0.29614 -0.240838 + outer loop + vertex 422.049 111.948 128.366 + vertex 420.478 117.048 128.124 + vertex 422.985 112.197 124.465 + endloop + endfacet + facet normal -0.919362 -0.295519 -0.259695 + outer loop + vertex 422.049 111.948 128.366 + vertex 419.822 115.926 131.724 + vertex 420.478 117.048 128.124 + endloop + endfacet + facet normal -0.919387 -0.298892 -0.255716 + outer loop + vertex 421.062 111.691 132.215 + vertex 419.822 115.926 131.724 + vertex 422.049 111.948 128.366 + endloop + endfacet + facet normal -0.901445 -0.350158 -0.254531 + outer loop + vertex 423.67 107.705 128.463 + vertex 421.062 111.691 132.215 + vertex 422.049 111.948 128.366 + endloop + endfacet + facet normal -0.901214 -0.353161 -0.25118 + outer loop + vertex 422.693 107.469 132.299 + vertex 421.062 111.691 132.215 + vertex 423.67 107.705 128.463 + endloop + endfacet + facet normal -0.897067 -0.351883 -0.267298 + outer loop + vertex 422.693 107.469 132.299 + vertex 420.032 111.436 136.008 + vertex 421.062 111.691 132.215 + endloop + endfacet + facet normal -0.897028 -0.352535 -0.266573 + outer loop + vertex 421.663 107.214 136.1 + vertex 420.032 111.436 136.008 + vertex 422.693 107.469 132.299 + endloop + endfacet + facet normal -0.893121 -0.351338 -0.280886 + outer loop + vertex 421.663 107.214 136.1 + vertex 418.947 111.171 139.788 + vertex 420.032 111.436 136.008 + endloop + endfacet + facet normal -0.893039 -0.353078 -0.278959 + outer loop + vertex 420.582 106.954 139.89 + vertex 418.947 111.171 139.788 + vertex 421.663 107.214 136.1 + endloop + endfacet + facet normal -0.88885 -0.351808 -0.29356 + outer loop + vertex 420.582 106.954 139.89 + vertex 417.8 110.892 143.595 + vertex 418.947 111.171 139.788 + endloop + endfacet + facet normal -0.888758 -0.354212 -0.290936 + outer loop + vertex 419.44 106.684 143.71 + vertex 417.8 110.892 143.595 + vertex 420.582 106.954 139.89 + endloop + endfacet + facet normal -0.884455 -0.352928 -0.305257 + outer loop + vertex 419.44 106.684 143.71 + vertex 416.586 110.6 147.45 + vertex 417.8 110.892 143.595 + endloop + endfacet + facet normal -0.884381 -0.35523 -0.30279 + outer loop + vertex 418.23 106.397 147.581 + vertex 416.586 110.6 147.45 + vertex 419.44 106.684 143.71 + endloop + endfacet + facet normal -0.880388 -0.354065 -0.315523 + outer loop + vertex 418.23 106.397 147.581 + vertex 415.308 110.3 151.353 + vertex 416.586 110.6 147.45 + endloop + endfacet + facet normal -0.880306 -0.35706 -0.31236 + outer loop + vertex 416.959 106.106 151.494 + vertex 415.308 110.3 151.353 + vertex 418.23 106.397 147.581 + endloop + endfacet + facet normal -0.87573 -0.355732 -0.326422 + outer loop + vertex 416.959 106.106 151.494 + vertex 413.97 109.987 155.284 + vertex 415.308 110.3 151.353 + endloop + endfacet + facet normal -0.875687 -0.357819 -0.32425 + outer loop + vertex 415.626 105.793 155.438 + vertex 413.97 109.987 155.284 + vertex 416.959 106.106 151.494 + endloop + endfacet + facet normal -0.871377 -0.356585 -0.33697 + outer loop + vertex 415.626 105.793 155.438 + vertex 412.582 109.66 159.219 + vertex 413.97 109.987 155.284 + endloop + endfacet + facet normal -0.871325 -0.360357 -0.33307 + outer loop + vertex 414.252 105.479 159.374 + vertex 412.582 109.66 159.219 + vertex 415.626 105.793 155.438 + endloop + endfacet + facet normal -0.866361 -0.358902 -0.347286 + outer loop + vertex 414.252 105.479 159.374 + vertex 411.154 109.324 163.128 + vertex 412.582 109.66 159.219 + endloop + endfacet + facet normal -0.866348 -0.361519 -0.344594 + outer loop + vertex 412.835 105.144 163.288 + vertex 411.154 109.324 163.128 + vertex 414.252 105.479 159.374 + endloop + endfacet + facet normal -0.862072 -0.360251 -0.356443 + outer loop + vertex 412.835 105.144 163.288 + vertex 409.696 108.984 166.999 + vertex 411.154 109.324 163.128 + endloop + endfacet + facet normal -0.862087 -0.363739 -0.352846 + outer loop + vertex 411.391 104.81 167.16 + vertex 409.696 108.984 166.999 + vertex 412.835 105.144 163.288 + endloop + endfacet + facet normal -0.857315 -0.3623 -0.365718 + outer loop + vertex 411.391 104.81 167.16 + vertex 408.204 108.64 170.836 + vertex 409.696 108.984 166.999 + endloop + endfacet + facet normal -0.85735 -0.364843 -0.363099 + outer loop + vertex 409.908 104.463 171.011 + vertex 408.204 108.64 170.836 + vertex 411.391 104.81 167.16 + endloop + endfacet + facet normal -0.852724 -0.363461 -0.375178 + outer loop + vertex 409.908 104.463 171.011 + vertex 406.674 108.285 174.658 + vertex 408.204 108.64 170.836 + endloop + endfacet + facet normal -0.852827 -0.368443 -0.370047 + outer loop + vertex 408.394 104.121 174.839 + vertex 406.674 108.285 174.658 + vertex 409.908 104.463 171.011 + endloop + endfacet + facet normal -0.848129 -0.367026 -0.382058 + outer loop + vertex 408.394 104.121 174.839 + vertex 405.115 107.933 178.457 + vertex 406.674 108.285 174.658 + endloop + endfacet + facet normal -0.848219 -0.370378 -0.378608 + outer loop + vertex 406.846 103.772 178.649 + vertex 405.115 107.933 178.457 + vertex 408.394 104.121 174.839 + endloop + endfacet + facet normal -0.842934 -0.368783 -0.391741 + outer loop + vertex 406.846 103.772 178.649 + vertex 403.521 107.554 182.244 + vertex 405.115 107.933 178.457 + endloop + endfacet + facet normal -0.843077 -0.373212 -0.387214 + outer loop + vertex 405.27 103.408 182.431 + vertex 403.521 107.554 182.244 + vertex 406.846 103.772 178.649 + endloop + endfacet + facet normal -0.838185 -0.371686 -0.399118 + outer loop + vertex 405.27 103.408 182.431 + vertex 401.909 107.147 186.008 + vertex 403.521 107.554 182.244 + endloop + endfacet + facet normal -0.838278 -0.374303 -0.396469 + outer loop + vertex 403.672 103.014 186.183 + vertex 401.909 107.147 186.008 + vertex 405.27 103.408 182.431 + endloop + endfacet + facet normal -0.832409 -0.37239 -0.410391 + outer loop + vertex 403.672 103.014 186.183 + vertex 400.278 106.671 189.748 + vertex 401.909 107.147 186.008 + endloop + endfacet + facet normal -0.832667 -0.380099 -0.402729 + outer loop + vertex 402.065 102.596 189.9 + vertex 400.278 106.671 189.748 + vertex 403.672 103.014 186.183 + endloop + endfacet + facet normal -0.825447 -0.377563 -0.419622 + outer loop + vertex 402.065 102.596 189.9 + vertex 398.644 106.143 193.437 + vertex 400.278 106.671 189.748 + endloop + endfacet + facet normal -0.825645 -0.384194 -0.413164 + outer loop + vertex 400.415 102.148 193.613 + vertex 398.644 106.143 193.437 + vertex 402.065 102.596 189.9 + endloop + endfacet + facet normal -0.81981 -0.382193 -0.426426 + outer loop + vertex 400.415 102.148 193.613 + vertex 396.912 105.662 197.198 + vertex 398.644 106.143 193.437 + endloop + endfacet + facet normal -0.819993 -0.390209 -0.418745 + outer loop + vertex 398.745 101.698 197.302 + vertex 396.912 105.662 197.198 + vertex 400.415 102.148 193.613 + endloop + endfacet + facet normal -0.812672 -0.387262 -0.435423 + outer loop + vertex 398.745 101.698 197.302 + vertex 395.191 105.075 200.933 + vertex 396.912 105.662 197.198 + endloop + endfacet + facet normal -0.812739 -0.396014 -0.42735 + outer loop + vertex 397.059 101.243 200.93 + vertex 395.191 105.075 200.933 + vertex 398.745 101.698 197.302 + endloop + endfacet + facet normal -0.806975 -0.393193 -0.440671 + outer loop + vertex 397.059 101.243 200.93 + vertex 393.469 104.557 204.547 + vertex 395.191 105.075 200.933 + endloop + endfacet + facet normal -0.806984 -0.403396 -0.431334 + outer loop + vertex 395.371 100.822 204.482 + vertex 393.469 104.557 204.547 + vertex 397.059 101.243 200.93 + endloop + endfacet + facet normal -0.801374 -0.400311 -0.444467 + outer loop + vertex 395.371 100.822 204.482 + vertex 391.742 104.117 208.058 + vertex 393.469 104.557 204.547 + endloop + endfacet + facet normal -0.801391 -0.404045 -0.441044 + outer loop + vertex 393.657 100.39 207.993 + vertex 391.742 104.117 208.058 + vertex 395.371 100.822 204.482 + endloop + endfacet + facet normal -0.796384 -0.401273 -0.452495 + outer loop + vertex 393.657 100.39 207.993 + vertex 390.001 103.677 211.513 + vertex 391.742 104.117 208.058 + endloop + endfacet + facet normal -0.796457 -0.406994 -0.447228 + outer loop + vertex 391.936 99.9322 211.475 + vertex 390.001 103.677 211.513 + vertex 393.657 100.39 207.993 + endloop + endfacet + facet normal -0.790097 -0.403564 -0.461393 + outer loop + vertex 391.936 99.9322 211.475 + vertex 388.251 103.201 214.925 + vertex 390.001 103.677 211.513 + endloop + endfacet + facet normal -0.790205 -0.408305 -0.457017 + outer loop + vertex 390.202 99.4376 214.914 + vertex 388.251 103.201 214.925 + vertex 391.936 99.9322 211.475 + endloop + endfacet + facet normal -0.785161 -0.40566 -0.467934 + outer loop + vertex 390.202 99.4376 214.914 + vertex 386.508 102.7 218.284 + vertex 388.251 103.201 214.925 + endloop + endfacet + facet normal -0.785308 -0.410075 -0.46382 + outer loop + vertex 388.472 98.9301 218.292 + vertex 386.508 102.7 218.284 + vertex 390.202 99.4376 214.914 + endloop + endfacet + facet normal -0.778751 -0.406687 -0.477654 + outer loop + vertex 388.472 98.9301 218.292 + vertex 384.752 102.178 221.593 + vertex 386.508 102.7 218.284 + endloop + endfacet + facet normal -0.778948 -0.411075 -0.473559 + outer loop + vertex 386.729 98.4084 221.613 + vertex 384.752 102.178 221.593 + vertex 388.472 98.9301 218.292 + endloop + endfacet + facet normal -0.77397 -0.408519 -0.483821 + outer loop + vertex 386.729 98.4084 221.613 + vertex 382.987 101.652 224.859 + vertex 384.752 102.178 221.593 + endloop + endfacet + facet normal -0.774251 -0.413882 -0.478787 + outer loop + vertex 384.981 97.8833 224.893 + vertex 382.987 101.652 224.859 + vertex 386.729 98.4084 221.613 + endloop + endfacet + facet normal -0.767902 -0.41064 -0.491632 + outer loop + vertex 384.981 97.8833 224.893 + vertex 381.206 101.114 228.09 + vertex 382.987 101.652 224.859 + endloop + endfacet + facet normal -0.768085 -0.413601 -0.488856 + outer loop + vertex 383.208 97.3381 228.14 + vertex 381.206 101.114 228.09 + vertex 384.981 97.8833 224.893 + endloop + endfacet + facet normal -0.762176 -0.410622 -0.500477 + outer loop + vertex 383.208 97.3381 228.14 + vertex 379.417 100.561 231.269 + vertex 381.206 101.114 228.09 + endloop + endfacet + facet normal -0.762733 -0.418433 -0.493105 + outer loop + vertex 381.444 96.7919 231.331 + vertex 379.417 100.561 231.269 + vertex 383.208 97.3381 228.14 + endloop + endfacet + facet normal -0.75613 -0.415094 -0.50593 + outer loop + vertex 381.444 96.7919 231.331 + vertex 377.649 100.011 234.362 + vertex 379.417 100.561 231.269 + endloop + endfacet + facet normal -0.756375 -0.417941 -0.503213 + outer loop + vertex 379.682 96.2329 234.444 + vertex 377.649 100.011 234.362 + vertex 381.444 96.7919 231.331 + endloop + endfacet + facet normal -0.750553 -0.415046 -0.514205 + outer loop + vertex 379.682 96.2329 234.444 + vertex 375.898 99.454 237.368 + vertex 377.649 100.011 234.362 + endloop + endfacet + facet normal -0.75088 -0.418164 -0.511192 + outer loop + vertex 377.936 95.6715 237.468 + vertex 375.898 99.454 237.368 + vertex 379.682 96.2329 234.444 + endloop + endfacet + facet normal -0.74501 -0.415287 -0.522012 + outer loop + vertex 377.936 95.6715 237.468 + vertex 374.154 98.8901 240.305 + vertex 375.898 99.454 237.368 + endloop + endfacet + facet normal -0.74564 -0.420575 -0.516853 + outer loop + vertex 376.204 95.1085 240.425 + vertex 374.154 98.8901 240.305 + vertex 377.936 95.6715 237.468 + endloop + endfacet + facet normal -0.737801 -0.416772 -0.530989 + outer loop + vertex 376.204 95.1085 240.425 + vertex 372.395 98.3077 243.207 + vertex 374.154 98.8901 240.305 + endloop + endfacet + facet normal -0.738205 -0.41987 -0.52798 + outer loop + vertex 374.448 94.523 243.346 + vertex 372.395 98.3077 243.207 + vertex 376.204 95.1085 240.425 + endloop + endfacet + facet normal -0.732274 -0.417035 -0.538382 + outer loop + vertex 374.448 94.523 243.346 + vertex 370.618 97.7103 246.087 + vertex 372.395 98.3077 243.207 + endloop + endfacet + facet normal -0.733063 -0.422791 -0.532791 + outer loop + vertex 372.684 93.9284 246.245 + vertex 370.618 97.7103 246.087 + vertex 374.448 94.523 243.346 + endloop + endfacet + facet normal -0.726418 -0.419639 -0.544261 + outer loop + vertex 372.684 93.9284 246.245 + vertex 368.838 97.1111 248.925 + vertex 370.618 97.7103 246.087 + endloop + endfacet + facet normal -0.72642 -0.419652 -0.544248 + outer loop + vertex 370.898 93.3132 249.103 + vertex 368.838 97.1111 248.925 + vertex 372.684 93.9284 246.245 + endloop + endfacet + facet normal -0.722182 -0.417687 -0.551354 + outer loop + vertex 370.898 93.3132 249.103 + vertex 367.067 96.521 251.692 + vertex 368.838 97.1111 248.925 + endloop + endfacet + facet normal -0.722603 -0.420149 -0.548926 + outer loop + vertex 369.133 92.7099 251.888 + vertex 367.067 96.521 251.692 + vertex 370.898 93.3132 249.103 + endloop + endfacet + facet normal -0.716793 -0.417491 -0.558489 + outer loop + vertex 369.133 92.7099 251.888 + vertex 365.313 95.9548 254.365 + vertex 367.067 96.521 251.692 + endloop + endfacet + facet normal -0.716949 -0.418278 -0.557699 + outer loop + vertex 367.385 92.1222 254.576 + vertex 365.313 95.9548 254.365 + vertex 369.133 92.7099 251.888 + endloop + endfacet + facet normal -0.712004 -0.416041 -0.56565 + outer loop + vertex 367.385 92.1222 254.576 + vertex 363.582 95.4121 256.944 + vertex 365.313 95.9548 254.365 + endloop + endfacet + facet normal -0.711801 -0.415154 -0.566556 + outer loop + vertex 365.659 91.5522 257.163 + vertex 363.582 95.4121 256.944 + vertex 367.385 92.1222 254.576 + endloop + endfacet + facet normal -0.707176 -0.413077 -0.573819 + outer loop + vertex 365.659 91.5522 257.163 + vertex 361.875 94.8696 259.438 + vertex 363.582 95.4121 256.944 + endloop + endfacet + facet normal -0.707321 -0.413645 -0.573232 + outer loop + vertex 363.963 90.9897 259.661 + vertex 361.875 94.8696 259.438 + vertex 365.659 91.5522 257.163 + endloop + endfacet + facet normal -0.699489 -0.410121 -0.585249 + outer loop + vertex 363.963 90.9897 259.661 + vertex 360.199 94.2907 261.847 + vertex 361.875 94.8696 259.438 + endloop + endfacet + facet normal -0.699541 -0.410309 -0.585054 + outer loop + vertex 362.29 90.4031 262.073 + vertex 360.199 94.2907 261.847 + vertex 363.963 90.9897 259.661 + endloop + endfacet + facet normal -0.691186 -0.406537 -0.597486 + outer loop + vertex 362.29 90.4031 262.073 + vertex 358.585 93.6806 264.129 + vertex 360.199 94.2907 261.847 + endloop + endfacet + facet normal -0.691493 -0.407533 -0.596452 + outer loop + vertex 360.67 89.8036 264.36 + vertex 358.585 93.6806 264.129 + vertex 362.29 90.4031 262.073 + endloop + endfacet + facet normal -0.685469 -0.404816 -0.605191 + outer loop + vertex 360.67 89.8036 264.36 + vertex 357.107 93.1169 266.18 + vertex 358.585 93.6806 264.129 + endloop + endfacet + facet normal -0.68612 -0.406567 -0.603276 + outer loop + vertex 359.18 89.2644 266.419 + vertex 357.107 93.1169 266.18 + vertex 360.67 89.8036 264.36 + endloop + endfacet + facet normal -0.686897 -0.406916 -0.602156 + outer loop + vertex 359.18 89.2644 266.419 + vertex 355.879 92.7365 267.838 + vertex 357.107 93.1169 266.18 + endloop + endfacet + facet normal -0.688161 -0.409397 -0.599023 + outer loop + vertex 357.946 88.8968 268.088 + vertex 355.879 92.7365 267.838 + vertex 359.18 89.2644 266.419 + endloop + endfacet + facet normal -0.695807 -0.412779 -0.587764 + outer loop + vertex 357.946 88.8968 268.088 + vertex 354.998 92.5931 268.981 + vertex 355.879 92.7365 267.838 + endloop + endfacet + facet normal -0.691539 -0.40724 -0.596599 + outer loop + vertex 357.038 88.7221 269.259 + vertex 354.998 92.5931 268.981 + vertex 357.946 88.8968 268.088 + endloop + endfacet + facet normal -0.702108 -0.411689 -0.580997 + outer loop + vertex 357.038 88.7221 269.259 + vertex 354.483 92.5668 269.622 + vertex 354.998 92.5931 268.981 + endloop + endfacet + facet normal -0.696115 -0.406705 -0.591621 + outer loop + vertex 356.52 88.6505 269.918 + vertex 354.483 92.5668 269.622 + vertex 357.038 88.7221 269.259 + endloop + endfacet + facet normal -0.675575 -0.398212 -0.620504 + outer loop + vertex 356.52 88.6505 269.918 + vertex 354.36 92.3719 269.881 + vertex 354.483 92.5668 269.622 + endloop + endfacet + facet normal -0.658656 -0.388632 -0.644312 + outer loop + vertex 356.372 88.4431 270.194 + vertex 354.36 92.3719 269.881 + vertex 356.52 88.6505 269.918 + endloop + endfacet + facet normal -0.189142 -0.173833 -0.966441 + outer loop + vertex 356.372 88.4431 270.194 + vertex 354.656 91.5319 269.974 + vertex 354.36 92.3719 269.881 + endloop + endfacet + facet normal -0.424706 -0.296828 -0.855288 + outer loop + vertex 356.567 87.9236 270.278 + vertex 354.656 91.5319 269.974 + vertex 356.372 88.4431 270.194 + endloop + endfacet + facet normal -0.917133 -0.299124 -0.263422 + outer loop + vertex 421.062 111.691 132.215 + vertex 418.457 116.524 135.795 + vertex 419.822 115.926 131.724 + endloop + endfacet + facet normal -0.916901 -0.294978 -0.26885 + outer loop + vertex 420.032 111.436 136.008 + vertex 418.457 116.524 135.795 + vertex 421.062 111.691 132.215 + endloop + endfacet + facet normal -0.911095 -0.294019 -0.288893 + outer loop + vertex 420.032 111.436 136.008 + vertex 417.705 115.385 139.326 + vertex 418.457 116.524 135.795 + endloop + endfacet + facet normal -0.911309 -0.299534 -0.28248 + outer loop + vertex 418.947 111.171 139.788 + vertex 417.705 115.385 139.326 + vertex 420.032 111.436 136.008 + endloop + endfacet + facet normal -0.90944 -0.299626 -0.288345 + outer loop + vertex 418.947 111.171 139.788 + vertex 416.223 115.971 143.392 + vertex 417.705 115.385 139.326 + endloop + endfacet + facet normal -0.908989 -0.294081 -0.29539 + outer loop + vertex 417.8 110.892 143.595 + vertex 416.223 115.971 143.392 + vertex 418.947 111.171 139.788 + endloop + endfacet + facet normal -0.903184 -0.293011 -0.313694 + outer loop + vertex 417.8 110.892 143.595 + vertex 415.358 114.817 146.961 + vertex 416.223 115.971 143.392 + endloop + endfacet + facet normal -0.903524 -0.298819 -0.307168 + outer loop + vertex 416.586 110.6 147.45 + vertex 415.358 114.817 146.961 + vertex 417.8 110.892 143.595 + endloop + endfacet + facet normal -0.901523 -0.298902 -0.312911 + outer loop + vertex 416.586 110.6 147.45 + vertex 413.733 115.37 151.115 + vertex 415.358 114.817 146.961 + endloop + endfacet + facet normal -0.901131 -0.294942 -0.317762 + outer loop + vertex 415.308 110.3 151.353 + vertex 413.733 115.37 151.115 + vertex 416.586 110.6 147.45 + endloop + endfacet + facet normal -0.894965 -0.293868 -0.335678 + outer loop + vertex 415.308 110.3 151.353 + vertex 412.75 114.196 154.762 + vertex 413.733 115.37 151.115 + endloop + endfacet + facet normal -0.895426 -0.300268 -0.328711 + outer loop + vertex 413.97 109.987 155.284 + vertex 412.75 114.196 154.762 + vertex 415.308 110.3 151.353 + endloop + endfacet + facet normal -0.893484 -0.300345 -0.333884 + outer loop + vertex 413.97 109.987 155.284 + vertex 411.007 114.726 158.949 + vertex 412.75 114.196 154.762 + endloop + endfacet + facet normal -0.89293 -0.295644 -0.339516 + outer loop + vertex 412.582 109.66 159.219 + vertex 411.007 114.726 158.949 + vertex 413.97 109.987 155.284 + endloop + endfacet + facet normal -0.886086 -0.294499 -0.35794 + outer loop + vertex 412.582 109.66 159.219 + vertex 409.93 113.527 162.602 + vertex 411.007 114.726 158.949 + endloop + endfacet + facet normal -0.886776 -0.302044 -0.349855 + outer loop + vertex 411.154 109.324 163.128 + vertex 409.93 113.527 162.602 + vertex 412.582 109.66 159.219 + endloop + endfacet + facet normal -0.885421 -0.302074 -0.353243 + outer loop + vertex 411.154 109.324 163.128 + vertex 408.107 114.047 166.727 + vertex 409.93 113.527 162.602 + endloop + endfacet + facet normal -0.884689 -0.296909 -0.359403 + outer loop + vertex 409.696 108.984 166.999 + vertex 408.107 114.047 166.727 + vertex 411.154 109.324 163.128 + endloop + endfacet + facet normal -0.877884 -0.295702 -0.376671 + outer loop + vertex 409.696 108.984 166.999 + vertex 406.973 112.845 170.313 + vertex 408.107 114.047 166.727 + endloop + endfacet + facet normal -0.878727 -0.303117 -0.368726 + outer loop + vertex 408.204 108.64 170.836 + vertex 406.973 112.845 170.313 + vertex 409.696 108.984 166.999 + endloop + endfacet + facet normal -0.877327 -0.303121 -0.372042 + outer loop + vertex 408.204 108.64 170.836 + vertex 405.076 113.346 174.38 + vertex 406.973 112.845 170.313 + endloop + endfacet + facet normal -0.876425 -0.297621 -0.378551 + outer loop + vertex 406.674 108.285 174.658 + vertex 405.076 113.346 174.38 + vertex 408.204 108.64 170.836 + endloop + endfacet + facet normal -0.869449 -0.296337 -0.395275 + outer loop + vertex 406.674 108.285 174.658 + vertex 403.877 112.129 177.928 + vertex 405.076 113.346 174.38 + endloop + endfacet + facet normal -0.870645 -0.305441 -0.385594 + outer loop + vertex 405.115 107.933 178.457 + vertex 403.877 112.129 177.928 + vertex 406.674 108.285 174.658 + endloop + endfacet + facet normal -0.869087 -0.305425 -0.389106 + outer loop + vertex 405.115 107.933 178.457 + vertex 401.905 112.59 181.97 + vertex 403.877 112.129 177.928 + endloop + endfacet + facet normal -0.868118 -0.299958 -0.395469 + outer loop + vertex 403.521 107.554 182.244 + vertex 401.905 112.59 181.97 + vertex 405.115 107.933 178.457 + endloop + endfacet + facet normal -0.86061 -0.298482 -0.412624 + outer loop + vertex 403.521 107.554 182.244 + vertex 400.652 111.322 185.502 + vertex 401.905 112.59 181.97 + endloop + endfacet + facet normal -0.861963 -0.308317 -0.402443 + outer loop + vertex 401.909 107.147 186.008 + vertex 400.652 111.322 185.502 + vertex 403.521 107.554 182.244 + endloop + endfacet + facet normal -0.859164 -0.308204 -0.40847 + outer loop + vertex 401.909 107.147 186.008 + vertex 398.6 111.658 189.564 + vertex 400.652 111.322 185.502 + endloop + endfacet + facet normal -0.858448 -0.304066 -0.413051 + outer loop + vertex 400.278 106.671 189.748 + vertex 398.6 111.658 189.564 + vertex 401.909 107.147 186.008 + endloop + endfacet + facet normal -0.849429 -0.301768 -0.432904 + outer loop + vertex 400.278 106.671 189.748 + vertex 397.341 110.249 193.017 + vertex 398.6 111.658 189.564 + endloop + endfacet + facet normal -0.850918 -0.313236 -0.421689 + outer loop + vertex 398.644 106.143 193.437 + vertex 397.341 110.249 193.017 + vertex 400.278 106.671 189.748 + endloop + endfacet + facet normal -0.8476 -0.312887 -0.428574 + outer loop + vertex 398.644 106.143 193.437 + vertex 395.423 110.377 196.715 + vertex 397.341 110.249 193.017 + endloop + endfacet + facet normal -0.84734 -0.311523 -0.430079 + outer loop + vertex 396.912 105.662 197.198 + vertex 395.423 110.377 196.715 + vertex 398.644 106.143 193.437 + endloop + endfacet + facet normal -0.83784 -0.310463 -0.44904 + outer loop + vertex 396.912 105.662 197.198 + vertex 393.629 109.468 200.692 + vertex 395.423 110.377 196.715 + endloop + endfacet + facet normal -0.83942 -0.322391 -0.437536 + outer loop + vertex 395.191 105.075 200.933 + vertex 393.629 109.468 200.692 + vertex 396.912 105.662 197.198 + endloop + endfacet + facet normal -0.833047 -0.320844 -0.450657 + outer loop + vertex 395.191 105.075 200.933 + vertex 391.882 108.734 204.445 + vertex 393.629 109.468 200.692 + endloop + endfacet + facet normal -0.833838 -0.327839 -0.444113 + outer loop + vertex 393.469 104.557 204.547 + vertex 391.882 108.734 204.445 + vertex 395.191 105.075 200.933 + endloop + endfacet + facet normal -0.829328 -0.326357 -0.453549 + outer loop + vertex 393.469 104.557 204.547 + vertex 390.138 108.2 208.018 + vertex 391.882 108.734 204.445 + endloop + endfacet + facet normal -0.829802 -0.330465 -0.449691 + outer loop + vertex 391.742 104.117 208.058 + vertex 390.138 108.2 208.018 + vertex 393.469 104.557 204.547 + endloop + endfacet + facet normal -0.824499 -0.328491 -0.460755 + outer loop + vertex 391.742 104.117 208.058 + vertex 388.383 107.75 211.479 + vertex 390.138 108.2 208.018 + endloop + endfacet + facet normal -0.824865 -0.331453 -0.457969 + outer loop + vertex 390.001 103.677 211.513 + vertex 388.383 107.75 211.479 + vertex 391.742 104.117 208.058 + endloop + endfacet + facet normal -0.820098 -0.329641 -0.467734 + outer loop + vertex 390.001 103.677 211.513 + vertex 386.63 107.304 214.867 + vertex 388.383 107.75 211.479 + endloop + endfacet + facet normal -0.820248 -0.330743 -0.466693 + outer loop + vertex 388.251 103.201 214.925 + vertex 386.63 107.304 214.867 + vertex 390.001 103.677 211.513 + endloop + endfacet + facet normal -0.814991 -0.328812 -0.47715 + outer loop + vertex 388.251 103.201 214.925 + vertex 384.871 106.813 218.21 + vertex 386.63 107.304 214.867 + endloop + endfacet + facet normal -0.815641 -0.333243 -0.472948 + outer loop + vertex 386.508 102.7 218.284 + vertex 384.871 106.813 218.21 + vertex 388.251 103.201 214.925 + endloop + endfacet + facet normal -0.809875 -0.331149 -0.484192 + outer loop + vertex 386.508 102.7 218.284 + vertex 383.111 106.3 221.504 + vertex 384.871 106.813 218.21 + endloop + endfacet + facet normal -0.810133 -0.332781 -0.48264 + outer loop + vertex 384.752 102.178 221.593 + vertex 383.111 106.3 221.504 + vertex 386.508 102.7 218.284 + endloop + endfacet + facet normal -0.804754 -0.330859 -0.492853 + outer loop + vertex 384.752 102.178 221.593 + vertex 381.335 105.767 224.763 + vertex 383.111 106.3 221.504 + endloop + endfacet + facet normal -0.805434 -0.33493 -0.488977 + outer loop + vertex 382.987 101.652 224.859 + vertex 381.335 105.767 224.763 + vertex 384.752 102.178 221.593 + endloop + endfacet + facet normal -0.799239 -0.332711 -0.50052 + outer loop + vertex 382.987 101.652 224.859 + vertex 379.542 105.224 227.986 + vertex 381.335 105.767 224.763 + endloop + endfacet + facet normal -0.799898 -0.336494 -0.496926 + outer loop + vertex 381.206 101.114 228.09 + vertex 379.542 105.224 227.986 + vertex 382.987 101.652 224.859 + endloop + endfacet + facet normal -0.794988 -0.334733 -0.505913 + outer loop + vertex 381.206 101.114 228.09 + vertex 377.755 104.684 231.151 + vertex 379.542 105.224 227.986 + endloop + endfacet + facet normal -0.795013 -0.334867 -0.505784 + outer loop + vertex 379.417 100.561 231.269 + vertex 377.755 104.684 231.151 + vertex 381.206 101.114 228.09 + endloop + endfacet + facet normal -0.789431 -0.332901 -0.515729 + outer loop + vertex 379.417 100.561 231.269 + vertex 375.972 104.124 234.242 + vertex 377.755 104.684 231.151 + endloop + endfacet + facet normal -0.7903 -0.33719 -0.511595 + outer loop + vertex 377.649 100.011 234.362 + vertex 375.972 104.124 234.242 + vertex 379.417 100.561 231.269 + endloop + endfacet + facet normal -0.784738 -0.335209 -0.521364 + outer loop + vertex 377.649 100.011 234.362 + vertex 374.221 103.572 237.233 + vertex 375.972 104.124 234.242 + endloop + endfacet + facet normal -0.785086 -0.336786 -0.519823 + outer loop + vertex 375.898 99.454 237.368 + vertex 374.221 103.572 237.233 + vertex 377.649 100.011 234.362 + endloop + endfacet + facet normal -0.779346 -0.33477 -0.529668 + outer loop + vertex 375.898 99.454 237.368 + vertex 372.477 103.01 240.154 + vertex 374.221 103.572 237.233 + endloop + endfacet + facet normal -0.779838 -0.336843 -0.527627 + outer loop + vertex 374.154 98.8901 240.305 + vertex 372.477 103.01 240.154 + vertex 375.898 99.454 237.368 + endloop + endfacet + facet normal -0.773617 -0.334691 -0.538051 + outer loop + vertex 374.154 98.8901 240.305 + vertex 370.72 102.432 243.039 + vertex 372.477 103.01 240.154 + endloop + endfacet + facet normal -0.773955 -0.33605 -0.536716 + outer loop + vertex 372.395 98.3077 243.207 + vertex 370.72 102.432 243.039 + vertex 374.154 98.8901 240.305 + endloop + endfacet + facet normal -0.76866 -0.334254 -0.545377 + outer loop + vertex 372.395 98.3077 243.207 + vertex 368.944 101.842 245.903 + vertex 370.72 102.432 243.039 + endloop + endfacet + facet normal -0.76899 -0.33553 -0.544127 + outer loop + vertex 370.618 97.7103 246.087 + vertex 368.944 101.842 245.903 + vertex 372.395 98.3077 243.207 + endloop + endfacet + facet normal -0.76375 -0.333781 -0.552519 + outer loop + vertex 370.618 97.7103 246.087 + vertex 367.156 101.25 248.733 + vertex 368.944 101.842 245.903 + endloop + endfacet + facet normal -0.76434 -0.335957 -0.550379 + outer loop + vertex 368.838 97.1111 248.925 + vertex 367.156 101.25 248.733 + vertex 370.618 97.7103 246.087 + endloop + endfacet + facet normal -0.759873 -0.334469 -0.557427 + outer loop + vertex 368.838 97.1111 248.925 + vertex 365.38 100.684 251.494 + vertex 367.156 101.25 248.733 + endloop + endfacet + facet normal -0.759809 -0.334251 -0.557643 + outer loop + vertex 367.067 96.521 251.692 + vertex 365.38 100.684 251.494 + vertex 368.838 97.1111 248.925 + endloop + endfacet + facet normal -0.75477 -0.332579 -0.565431 + outer loop + vertex 367.067 96.521 251.692 + vertex 363.615 100.14 254.17 + vertex 365.38 100.684 251.494 + endloop + endfacet + facet normal -0.754775 -0.332592 -0.565418 + outer loop + vertex 365.313 95.9548 254.365 + vertex 363.615 100.14 254.17 + vertex 367.067 96.521 251.692 + endloop + endfacet + facet normal -0.750575 -0.331186 -0.571798 + outer loop + vertex 365.313 95.9548 254.365 + vertex 361.872 99.6276 256.755 + vertex 363.615 100.14 254.17 + endloop + endfacet + facet normal -0.750128 -0.329906 -0.573123 + outer loop + vertex 363.582 95.4121 256.944 + vertex 361.872 99.6276 256.755 + vertex 365.313 95.9548 254.365 + endloop + endfacet + facet normal -0.745269 -0.32826 -0.580361 + outer loop + vertex 363.582 95.4121 256.944 + vertex 360.154 99.1055 259.256 + vertex 361.872 99.6276 256.755 + endloop + endfacet + facet normal -0.745005 -0.327553 -0.581099 + outer loop + vertex 361.875 94.8696 259.438 + vertex 360.154 99.1055 259.256 + vertex 363.582 95.4121 256.944 + endloop + endfacet + facet normal -0.736627 -0.324672 -0.593269 + outer loop + vertex 361.875 94.8696 259.438 + vertex 358.46 98.5268 261.676 + vertex 360.154 99.1055 259.256 + endloop + endfacet + facet normal -0.737312 -0.326421 -0.591456 + outer loop + vertex 360.199 94.2907 261.847 + vertex 358.46 98.5268 261.676 + vertex 361.875 94.8696 259.438 + endloop + endfacet + facet normal -0.731281 -0.324292 -0.600053 + outer loop + vertex 360.199 94.2907 261.847 + vertex 356.853 97.9215 263.962 + vertex 358.46 98.5268 261.676 + endloop + endfacet + facet normal -0.730289 -0.321941 -0.602521 + outer loop + vertex 358.585 93.6806 264.129 + vertex 356.853 97.9215 263.962 + vertex 360.199 94.2907 261.847 + endloop + endfacet + facet normal -0.725026 -0.32008 -0.609824 + outer loop + vertex 358.585 93.6806 264.129 + vertex 355.373 97.3461 266.023 + vertex 356.853 97.9215 263.962 + endloop + endfacet + facet normal -0.724862 -0.319745 -0.610195 + outer loop + vertex 357.107 93.1169 266.18 + vertex 355.373 97.3461 266.023 + vertex 358.585 93.6806 264.129 + endloop + endfacet + facet normal -0.725479 -0.319967 -0.609345 + outer loop + vertex 357.107 93.1169 266.18 + vertex 354.151 96.9419 267.691 + vertex 355.373 97.3461 266.023 + endloop + endfacet + facet normal -0.725018 -0.319244 -0.610273 + outer loop + vertex 355.879 92.7365 267.838 + vertex 354.151 96.9419 267.691 + vertex 357.107 93.1169 266.18 + endloop + endfacet + facet normal -0.728939 -0.320666 -0.604831 + outer loop + vertex 355.879 92.7365 267.838 + vertex 353.277 96.7743 268.833 + vertex 354.151 96.9419 267.691 + endloop + endfacet + facet normal -0.730088 -0.321912 -0.602781 + outer loop + vertex 354.998 92.5931 268.981 + vertex 353.277 96.7743 268.833 + vertex 355.879 92.7365 267.838 + endloop + endfacet + facet normal -0.721979 -0.318971 -0.614007 + outer loop + vertex 354.998 92.5931 268.981 + vertex 352.784 96.6862 269.458 + vertex 353.277 96.7743 268.833 + endloop + endfacet + facet normal -0.730613 -0.325229 -0.600359 + outer loop + vertex 354.483 92.5668 269.622 + vertex 352.784 96.6862 269.458 + vertex 354.998 92.5931 268.981 + endloop + endfacet + facet normal -0.680173 -0.307025 -0.665657 + outer loop + vertex 354.483 92.5668 269.622 + vertex 352.66 96.4638 269.688 + vertex 352.784 96.6862 269.458 + endloop + endfacet + facet normal -0.730619 -0.331804 -0.596744 + outer loop + vertex 354.36 92.3719 269.881 + vertex 352.66 96.4638 269.688 + vertex 354.483 92.5668 269.622 + endloop + endfacet + facet normal -0.192893 -0.126096 -0.973084 + outer loop + vertex 354.36 92.3719 269.881 + vertex 352.864 95.7818 269.736 + vertex 352.66 96.4638 269.688 + endloop + endfacet + facet normal -0.591996 -0.291753 -0.751279 + outer loop + vertex 354.656 91.5319 269.974 + vertex 352.864 95.7818 269.736 + vertex 354.36 92.3719 269.881 + endloop + endfacet + facet normal -0.905301 -0.351274 -0.238822 + outer loop + vertex 423.67 107.705 128.463 + vertex 422.049 111.948 128.366 + vertex 424.605 107.947 124.562 + endloop + endfacet + facet normal -0.924362 -0.301817 -0.233369 + outer loop + vertex 422.985 112.197 124.465 + vertex 420.478 117.048 128.124 + vertex 421.728 116.427 123.974 + endloop + endfacet + facet normal -0.912452 -0.352325 -0.208081 + outer loop + vertex 425.48 108.176 120.641 + vertex 423.858 112.427 120.558 + vertex 426.282 108.392 116.762 + endloop + endfacet + facet normal -0.931249 -0.302633 -0.202952 + outer loop + vertex 424.657 112.653 116.693 + vertex 422.272 117.538 120.356 + vertex 423.374 116.892 116.259 + endloop + endfacet + facet normal -0.9196 -0.352063 -0.174322 + outer loop + vertex 426.996 108.583 112.984 + vertex 425.37 112.853 112.939 + vertex 427.623 108.757 109.326 + endloop + endfacet + facet normal -0.937509 -0.303823 -0.169612 + outer loop + vertex 425.996 113.04 109.301 + vertex 423.763 117.968 112.816 + vertex 424.689 117.283 108.923 + endloop + endfacet + facet normal -0.925941 -0.352595 -0.135317 + outer loop + vertex 428.17 108.92 105.751 + vertex 426.541 113.201 105.743 + vertex 428.639 109.053 102.197 + endloop + endfacet + facet normal -0.947962 -0.305773 -0.0887204 + outer loop + vertex 427.743 113.628 94.8848 + vertex 425.796 118.641 98.406 + vertex 426.403 117.905 94.4604 + endloop + endfacet + facet normal -0.945337 -0.304403 -0.116948 + outer loop + vertex 427.014 113.354 102.188 + vertex 425.692 117.609 101.793 + vertex 427.416 113.491 98.5759 + endloop + endfacet + facet normal -0.954403 -0.276549 -0.112408 + outer loop + vertex 423.424 124.631 103.808 + vertex 424.2 124.934 96.4781 + vertex 425.796 118.641 98.406 + endloop + endfacet + facet normal -0.943263 -0.305071 -0.1311 + outer loop + vertex 427.014 113.354 102.188 + vertex 424.928 118.331 105.616 + vertex 425.692 117.609 101.793 + endloop + endfacet + facet normal -0.958353 -0.23924 -0.155959 + outer loop + vertex 422.336 124.264 111.055 + vertex 420.014 133.981 110.417 + vertex 423.424 124.631 103.808 + endloop + endfacet + facet normal -0.952325 -0.236564 -0.192651 + outer loop + vertex 420.941 123.846 118.466 + vertex 418.663 133.553 117.809 + vertex 422.336 124.264 111.055 + endloop + endfacet + facet normal -0.94594 -0.233999 -0.224592 + outer loop + vertex 419.243 123.369 126.112 + vertex 417.019 133.088 125.357 + vertex 420.941 123.846 118.466 + endloop + endfacet + facet normal -0.938965 -0.231418 -0.25454 + outer loop + vertex 417.284 122.852 133.81 + vertex 415.102 132.573 133.021 + vertex 419.243 123.369 126.112 + endloop + endfacet + facet normal -0.931357 -0.228789 -0.283248 + outer loop + vertex 415.095 122.297 141.456 + vertex 412.936 132.018 140.705 + vertex 417.284 122.852 133.81 + endloop + endfacet + facet normal -0.923609 -0.226675 -0.309134 + outer loop + vertex 412.669 121.702 149.139 + vertex 410.531 131.426 148.399 + vertex 415.095 122.297 141.456 + endloop + endfacet + facet normal -0.915899 -0.225242 -0.332257 + outer loop + vertex 410.006 121.065 156.912 + vertex 407.896 130.787 156.14 + vertex 412.669 121.702 149.139 + endloop + endfacet + facet normal -0.90826 -0.224232 -0.353246 + outer loop + vertex 407.148 120.394 164.689 + vertex 405.057 130.115 163.893 + vertex 410.006 121.065 156.912 + endloop + endfacet + facet normal -0.900559 -0.223103 -0.37312 + outer loop + vertex 404.137 119.696 172.373 + vertex 402.056 129.417 171.583 + vertex 407.148 120.394 164.689 + endloop + endfacet + facet normal -0.863258 -0.232224 -0.448171 + outer loop + vertex 391.138 118.86 200.222 + vertex 394.168 116.939 195.38 + vertex 392.312 114.565 200.185 + endloop + endfacet + facet normal -0.862423 -0.231017 -0.450397 + outer loop + vertex 390.572 113.469 204.078 + vertex 389.31 118.885 203.717 + vertex 392.312 114.565 200.185 + endloop + endfacet + facet normal -0.858518 -0.234187 -0.456184 + outer loop + vertex 388.815 112.767 207.745 + vertex 387.9 117.307 207.138 + vertex 390.572 113.469 204.078 + endloop + endfacet + facet normal -0.855497 -0.230838 -0.463506 + outer loop + vertex 387.053 112.258 211.252 + vertex 385.798 117.61 210.903 + vertex 388.815 112.767 207.745 + endloop + endfacet + facet normal -0.850034 -0.23226 -0.472754 + outer loop + vertex 385.285 111.8 214.656 + vertex 384.36 116.242 214.137 + vertex 387.053 112.258 211.252 + endloop + endfacet + facet normal -0.846854 -0.228455 -0.480257 + outer loop + vertex 383.522 111.332 217.988 + vertex 382.255 116.647 217.693 + vertex 385.285 111.8 214.656 + endloop + endfacet + facet normal -0.842051 -0.231298 -0.487289 + outer loop + vertex 381.76 110.833 221.269 + vertex 380.825 115.284 220.772 + vertex 383.522 111.332 217.988 + endloop + endfacet + facet normal -0.838443 -0.22676 -0.495573 + outer loop + vertex 379.983 110.302 224.518 + vertex 378.72 115.637 224.214 + vertex 381.76 110.833 221.269 + endloop + endfacet + facet normal -0.833728 -0.229732 -0.502116 + outer loop + vertex 378.198 109.766 227.727 + vertex 377.276 114.228 227.216 + vertex 379.983 110.302 224.518 + endloop + endfacet + facet normal -0.830148 -0.225288 -0.51 + outer loop + vertex 376.403 109.214 230.893 + vertex 375.158 114.545 230.564 + vertex 378.198 109.766 227.727 + endloop + endfacet + facet normal -0.825109 -0.227462 -0.517161 + outer loop + vertex 374.621 108.657 233.981 + vertex 373.712 113.121 233.468 + vertex 376.403 109.214 230.893 + endloop + endfacet + facet normal -0.822212 -0.222464 -0.523906 + outer loop + vertex 372.864 108.1 236.975 + vertex 371.627 113.434 236.652 + vertex 374.621 108.657 233.981 + endloop + endfacet + facet normal -0.816734 -0.225484 -0.531133 + outer loop + vertex 371.122 107.541 239.89 + vertex 370.206 112.002 239.406 + vertex 372.864 108.1 236.975 + endloop + endfacet + facet normal -0.812913 -0.219029 -0.539628 + outer loop + vertex 369.37 106.966 242.764 + vertex 368.132 112.318 242.456 + vertex 371.122 107.541 239.89 + endloop + endfacet + facet normal -0.808163 -0.222277 -0.545404 + outer loop + vertex 367.604 106.395 245.614 + vertex 366.698 110.88 245.128 + vertex 369.37 106.966 242.764 + endloop + endfacet + facet normal -0.788621 -0.266456 -0.554146 + outer loop + vertex 367.156 101.25 248.733 + vertex 365.818 105.823 248.439 + vertex 368.944 101.842 245.903 + endloop + endfacet + facet normal -0.784572 -0.265663 -0.560241 + outer loop + vertex 367.156 101.25 248.733 + vertex 364.027 105.264 251.212 + vertex 365.818 105.823 248.439 + endloop + endfacet + facet normal -0.784861 -0.266335 -0.559517 + outer loop + vertex 365.38 100.684 251.494 + vertex 364.027 105.264 251.212 + vertex 367.156 101.25 248.733 + endloop + endfacet + facet normal -0.780464 -0.26544 -0.566054 + outer loop + vertex 365.38 100.684 251.494 + vertex 362.253 104.742 253.903 + vertex 364.027 105.264 251.212 + endloop + endfacet + facet normal -0.779696 -0.263753 -0.567899 + outer loop + vertex 363.615 100.14 254.17 + vertex 362.253 104.742 253.903 + vertex 365.38 100.684 251.494 + endloop + endfacet + facet normal -0.774899 -0.262738 -0.574892 + outer loop + vertex 363.615 100.14 254.17 + vertex 360.494 104.227 256.509 + vertex 362.253 104.742 253.903 + endloop + endfacet + facet normal -0.774978 -0.262902 -0.57471 + outer loop + vertex 361.872 99.6276 256.755 + vertex 360.494 104.227 256.509 + vertex 363.615 100.14 254.17 + endloop + endfacet + facet normal -0.769447 -0.261668 -0.582651 + outer loop + vertex 361.872 99.6276 256.755 + vertex 358.765 103.704 259.028 + vertex 360.494 104.227 256.509 + endloop + endfacet + facet normal -0.769322 -0.261419 -0.582927 + outer loop + vertex 360.154 99.1055 259.256 + vertex 358.765 103.704 259.028 + vertex 361.872 99.6276 256.755 + endloop + endfacet + facet normal -0.761877 -0.259687 -0.593385 + outer loop + vertex 360.154 99.1055 259.256 + vertex 357.089 103.104 261.441 + vertex 358.765 103.704 259.028 + endloop + endfacet + facet normal -0.761261 -0.258499 -0.594693 + outer loop + vertex 358.46 98.5268 261.676 + vertex 357.089 103.104 261.441 + vertex 360.154 99.1055 259.256 + endloop + endfacet + facet normal -0.756393 -0.257383 -0.601351 + outer loop + vertex 358.46 98.5268 261.676 + vertex 355.491 102.468 263.724 + vertex 357.089 103.104 261.441 + endloop + endfacet + facet normal -0.756818 -0.258152 -0.600487 + outer loop + vertex 356.853 97.9215 263.962 + vertex 355.491 102.468 263.724 + vertex 358.46 98.5268 261.676 + endloop + endfacet + facet normal -0.754029 -0.257513 -0.604258 + outer loop + vertex 356.853 97.9215 263.962 + vertex 354.03 101.945 265.77 + vertex 355.491 102.468 263.724 + endloop + endfacet + facet normal -0.751097 -0.252961 -0.609807 + outer loop + vertex 355.373 97.3461 266.023 + vertex 354.03 101.945 265.77 + vertex 356.853 97.9215 263.962 + endloop + endfacet + facet normal -0.753479 -0.253483 -0.606644 + outer loop + vertex 355.373 97.3461 266.023 + vertex 352.769 101.6 267.481 + vertex 354.03 101.945 265.77 + endloop + endfacet + facet normal -0.750901 -0.250373 -0.611114 + outer loop + vertex 354.151 96.9419 267.691 + vertex 352.769 101.6 267.481 + vertex 355.373 97.3461 266.023 + endloop + endfacet + facet normal -0.751954 -0.250622 -0.609716 + outer loop + vertex 354.151 96.9419 267.691 + vertex 351.846 101.434 268.687 + vertex 352.769 101.6 267.481 + endloop + endfacet + facet normal -0.750966 -0.249769 -0.611282 + outer loop + vertex 353.277 96.7743 268.833 + vertex 351.846 101.434 268.687 + vertex 354.151 96.9419 267.691 + endloop + endfacet + facet normal -0.743505 -0.247787 -0.621129 + outer loop + vertex 353.277 96.7743 268.833 + vertex 351.339 101.334 269.334 + vertex 351.846 101.434 268.687 + endloop + endfacet + facet normal -0.743588 -0.247835 -0.621012 + outer loop + vertex 352.784 96.6862 269.458 + vertex 351.339 101.334 269.334 + vertex 353.277 96.7743 268.833 + endloop + endfacet + facet normal -0.626304 -0.214777 -0.749409 + outer loop + vertex 352.784 96.6862 269.458 + vertex 351.283 100.651 269.576 + vertex 351.339 101.334 269.334 + endloop + endfacet + facet normal -0.724796 -0.255344 -0.639898 + outer loop + vertex 352.66 96.4638 269.688 + vertex 351.283 100.651 269.576 + vertex 352.784 96.6862 269.458 + endloop + endfacet + facet normal 0.0489463 -0.0105426 -0.998746 + outer loop + vertex 352.66 96.4638 269.688 + vertex 351.477 99.782 269.595 + vertex 351.283 100.651 269.576 + endloop + endfacet + facet normal -0.580913 -0.228938 -0.781106 + outer loop + vertex 352.864 95.7818 269.736 + vertex 351.477 99.782 269.595 + vertex 352.66 96.4638 269.688 + endloop + endfacet + facet normal -0.80825 -0.222281 -0.545274 + outer loop + vertex 367.604 106.395 245.614 + vertex 364.587 111.203 248.125 + vertex 366.698 110.88 245.128 + endloop + endfacet + facet normal -0.809581 -0.187902 -0.556121 + outer loop + vertex 363.122 109.775 250.741 + vertex 360.533 116.786 252.14 + vertex 364.587 111.203 248.125 + endloop + endfacet + facet normal -0.80284 -0.183169 -0.56736 + outer loop + vertex 363.122 109.775 250.741 + vertex 361.007 110.114 253.623 + vertex 360.533 116.786 252.14 + endloop + endfacet + facet normal -0.800418 -0.184693 -0.570279 + outer loop + vertex 359.572 108.706 256.094 + vertex 357.061 115.539 257.405 + vertex 361.007 110.114 253.623 + endloop + endfacet + facet normal -0.792601 -0.17943 -0.582742 + outer loop + vertex 359.572 108.706 256.094 + vertex 357.549 108.96 258.767 + vertex 357.061 115.539 257.405 + endloop + endfacet + facet normal -0.789765 -0.179916 -0.58643 + outer loop + vertex 356.202 107.476 261.036 + vertex 354.015 113.796 262.042 + vertex 357.549 108.96 258.767 + endloop + endfacet + facet normal -0.782324 -0.17556 -0.597619 + outer loop + vertex 356.202 107.476 261.036 + vertex 354.447 107.496 263.328 + vertex 354.015 113.796 262.042 + endloop + endfacet + facet normal -0.781118 -0.176267 -0.598987 + outer loop + vertex 353.272 106.088 265.274 + vertex 351.92 111.603 265.414 + vertex 354.447 107.496 263.328 + endloop + endfacet + facet normal -0.780047 -0.175967 -0.600469 + outer loop + vertex 353.272 106.088 265.274 + vertex 351.787 106.889 266.969 + vertex 351.92 111.603 265.414 + endloop + endfacet + facet normal -0.781226 -0.167029 -0.601488 + outer loop + vertex 351.787 106.889 266.969 + vertex 350.921 106.113 268.309 + vertex 349.484 114.19 267.932 + endloop + endfacet + facet normal -0.697207 -0.188504 -0.691642 + outer loop + vertex 351.283 100.651 269.576 + vertex 349.988 105.872 269.459 + vertex 351.339 101.334 269.334 + endloop + endfacet + facet normal -0.0311977 -0.030183 -0.999057 + outer loop + vertex 351.283 100.651 269.576 + vertex 350.559 103.041 269.527 + vertex 349.988 105.872 269.459 + endloop + endfacet + facet normal -0.0425886 -0.0324692 -0.998565 + outer loop + vertex 349.988 105.872 269.459 + vertex 350.559 103.041 269.527 + vertex 349.974 105.646 269.467 + endloop + endfacet + facet normal -0.00926854 -0.0235518 -0.99968 + outer loop + vertex 351.477 99.782 269.595 + vertex 350.559 103.041 269.527 + vertex 351.283 100.651 269.576 + endloop + endfacet + facet normal -0.762432 -0.164816 -0.625727 + outer loop + vertex 350.921 106.113 268.309 + vertex 350.133 106.965 269.045 + vertex 349.484 114.19 267.932 + endloop + endfacet + facet normal -0.774365 -0.147184 -0.615382 + outer loop + vertex 349.484 114.19 267.932 + vertex 347.108 121.774 269.109 + vertex 347.297 125.898 267.885 + endloop + endfacet + facet normal -0.757693 -0.139131 -0.637608 + outer loop + vertex 347.634 117.576 269.4 + vertex 347.119 120.35 269.406 + vertex 347.108 121.774 269.109 + endloop + endfacet + facet normal -0.768967 -0.136488 -0.624548 + outer loop + vertex 347.119 120.35 269.406 + vertex 346.637 122.966 269.428 + vertex 347.108 121.774 269.109 + endloop + endfacet + facet normal -0.770199 -0.137439 -0.622819 + outer loop + vertex 346.637 122.966 269.428 + vertex 345.959 126.983 269.38 + vertex 347.108 121.774 269.109 + endloop + endfacet + facet normal -0.790439 -0.140151 -0.596292 + outer loop + vertex 345.959 126.983 269.38 + vertex 345.184 131.169 269.424 + vertex 345.444 131.094 269.096 + endloop + endfacet + facet normal -0.776361 -0.137972 -0.615002 + outer loop + vertex 344.577 127.773 270.959 + vertex 344.397 134.455 269.687 + vertex 345.84 126.225 269.711 + endloop + endfacet + facet normal -0.790439 -0.140188 -0.596283 + outer loop + vertex 345.184 131.169 269.424 + vertex 344.466 135.475 269.363 + vertex 345.444 131.094 269.096 + endloop + endfacet + facet normal -0.798468 -0.142035 -0.585042 + outer loop + vertex 344.466 135.475 269.363 + vertex 343.796 139.096 269.399 + vertex 343.825 140.033 269.131 + endloop + endfacet + facet normal -0.781417 -0.138536 -0.608437 + outer loop + vertex 343.356 136.814 270.487 + vertex 343.04 142.094 269.69 + vertex 344.397 134.455 269.687 + endloop + endfacet + facet normal -0.797761 -0.142313 -0.585938 + outer loop + vertex 343.796 139.096 269.399 + vertex 343.289 142.016 269.379 + vertex 343.825 140.033 269.131 + endloop + endfacet + facet normal -0.801285 -0.143922 -0.580714 + outer loop + vertex 343.289 142.016 269.379 + vertex 342.595 145.76 269.409 + vertex 343.825 140.033 269.131 + endloop + endfacet + facet normal -0.785238 -0.140175 -0.603119 + outer loop + vertex 341.666 143.992 271.038 + vertex 341.539 150.171 269.767 + vertex 343.04 142.094 269.69 + endloop + endfacet + facet normal -0.794141 -0.142674 -0.590749 + outer loop + vertex 342.595 145.76 269.409 + vertex 341.812 149.962 269.447 + vertex 342.303 148.837 269.059 + endloop + endfacet + facet normal -0.793855 -0.142394 -0.5912 + outer loop + vertex 341.812 149.962 269.447 + vertex 341.022 154.242 269.477 + vertex 342.303 148.837 269.059 + endloop + endfacet + facet normal -0.792723 -0.14116 -0.593013 + outer loop + vertex 340.13 153.77 270.794 + vertex 339.942 159.364 269.714 + vertex 341.539 150.171 269.767 + endloop + endfacet + facet normal -0.785478 -0.140813 -0.602658 + outer loop + vertex 341.022 154.242 269.477 + vertex 340.266 158.33 269.507 + vertex 340.692 157.626 269.116 + endloop + endfacet + facet normal -0.783783 -0.138235 -0.605455 + outer loop + vertex 340.266 158.33 269.507 + vertex 339.726 161.503 269.481 + vertex 340.692 157.626 269.116 + endloop + endfacet + facet normal -0.679214 -0.117416 -0.724488 + outer loop + vertex 339.726 161.503 269.481 + vertex 339.146 164.814 269.488 + vertex 339.068 166.76 269.246 + endloop + endfacet + facet normal -0.792911 -0.129761 -0.59536 + outer loop + vertex 338.683 162.553 270.695 + vertex 338.51 167.936 269.752 + vertex 339.942 159.364 269.714 + endloop + endfacet + facet normal -0.690628 -0.116538 -0.713759 + outer loop + vertex 339.146 164.814 269.488 + vertex 338.628 167.996 269.47 + vertex 339.068 166.76 269.246 + endloop + endfacet + facet normal -0.570751 -0.0546524 -0.819303 + outer loop + vertex 338.628 167.996 269.47 + vertex 338.048 172.236 269.592 + vertex 339.068 166.76 269.246 + endloop + endfacet + facet normal -0.819262 -0.0456323 -0.571601 + outer loop + vertex 337.611 176.942 269.842 + vertex 338.048 172.236 269.592 + vertex 337.505 176.904 269.998 + endloop + endfacet + facet normal -0.78644 -0.0825607 -0.612124 + outer loop + vertex 334.324 166.426 275.709 + vertex 335.548 176.209 272.818 + vertex 336.785 165.249 272.706 + endloop + endfacet + facet normal -0.790218 -0.117867 -0.601384 + outer loop + vertex 334.324 166.426 275.709 + vertex 336.785 165.249 272.706 + vertex 335.725 157.636 275.592 + endloop + endfacet + facet normal -0.77014 -0.114317 -0.627547 + outer loop + vertex 332.927 157.501 279.05 + vertex 334.324 166.426 275.709 + vertex 335.725 157.636 275.592 + endloop + endfacet + facet normal -0.768819 -0.125991 -0.626932 + outer loop + vertex 332.927 157.501 279.05 + vertex 335.725 157.636 275.592 + vertex 334.262 149.226 279.076 + endloop + endfacet + facet normal -0.747129 -0.12258 -0.653278 + outer loop + vertex 331.359 148.303 282.569 + vertex 332.927 157.501 279.05 + vertex 334.262 149.226 279.076 + endloop + endfacet + facet normal -0.747485 -0.121018 -0.653162 + outer loop + vertex 331.359 148.303 282.569 + vertex 334.262 149.226 279.076 + vertex 332.659 140.146 282.593 + endloop + endfacet + facet normal -0.716453 -0.11618 -0.687893 + outer loop + vertex 329.819 138.878 285.765 + vertex 331.359 148.303 282.569 + vertex 332.659 140.146 282.593 + endloop + endfacet + facet normal -0.717558 -0.112397 -0.68737 + outer loop + vertex 329.819 138.878 285.765 + vertex 332.659 140.146 282.593 + vertex 331.095 130.715 285.768 + endloop + endfacet + facet normal -0.713094 -0.114575 -0.691643 + outer loop + vertex 331.095 130.715 285.768 + vertex 332.659 140.146 282.593 + vertex 333.965 131.974 282.6 + endloop + endfacet + facet normal -0.713801 -0.112134 -0.691313 + outer loop + vertex 331.095 130.715 285.768 + vertex 333.965 131.974 282.6 + vertex 332.456 122.391 285.713 + endloop + endfacet + facet normal -0.708902 -0.114416 -0.695965 + outer loop + vertex 332.456 122.391 285.713 + vertex 333.965 131.974 282.6 + vertex 335.379 123.597 282.537 + endloop + endfacet + facet normal -0.707866 -0.118087 -0.696406 + outer loop + vertex 332.456 122.391 285.713 + vertex 335.379 123.597 282.537 + vertex 334.057 113.691 285.561 + endloop + endfacet + facet normal -0.704913 -0.119329 -0.699184 + outer loop + vertex 334.057 113.691 285.561 + vertex 335.379 123.597 282.537 + vertex 337.05 114.829 282.349 + endloop + endfacet + facet normal -0.701454 -0.131873 -0.700408 + outer loop + vertex 334.057 113.691 285.561 + vertex 337.05 114.829 282.349 + vertex 335.995 104.676 285.317 + endloop + endfacet + facet normal -0.698245 -0.133076 -0.703381 + outer loop + vertex 335.995 104.676 285.317 + vertex 337.05 114.829 282.349 + vertex 339.04 105.709 282.098 + endloop + endfacet + facet normal -0.72782 -0.140414 -0.671239 + outer loop + vertex 337.05 114.829 282.349 + vertex 340.034 115.756 278.92 + vertex 339.04 105.709 282.098 + endloop + endfacet + facet normal -0.730908 -0.127551 -0.670451 + outer loop + vertex 337.05 114.829 282.349 + vertex 338.334 124.589 279.092 + vertex 340.034 115.756 278.92 + endloop + endfacet + facet normal -0.752279 -0.132152 -0.645454 + outer loop + vertex 338.334 124.589 279.092 + vertex 341.132 125.027 275.741 + vertex 340.034 115.756 278.92 + endloop + endfacet + facet normal -0.748159 -0.134137 -0.649819 + outer loop + vertex 340.034 115.756 278.92 + vertex 341.132 125.027 275.741 + vertex 342.853 116.167 275.589 + endloop + endfacet + facet normal -0.746077 -0.146389 -0.649569 + outer loop + vertex 340.034 115.756 278.92 + vertex 342.853 116.167 275.589 + vertex 342.034 106.634 278.677 + endloop + endfacet + facet normal -0.762047 -0.137125 -0.632836 + outer loop + vertex 341.132 125.027 275.741 + vertex 343.368 124.208 273.226 + vertex 342.853 116.167 275.589 + endloop + endfacet + facet normal -0.753023 -0.127673 -0.64549 + outer loop + vertex 338.334 124.589 279.092 + vertex 339.65 133.44 275.806 + vertex 341.132 125.027 275.741 + endloop + endfacet + facet normal -0.768608 -0.130566 -0.626254 + outer loop + vertex 339.65 133.44 275.806 + vertex 342.202 133.585 272.644 + vertex 341.132 125.027 275.741 + endloop + endfacet + facet normal -0.756972 -0.125521 -0.641278 + outer loop + vertex 336.88 132.986 279.165 + vertex 339.65 133.44 275.806 + vertex 338.334 124.589 279.092 + endloop + endfacet + facet normal -0.735797 -0.121638 -0.666189 + outer loop + vertex 335.379 123.597 282.537 + vertex 336.88 132.986 279.165 + vertex 338.334 124.589 279.092 + endloop + endfacet + facet normal -0.756729 -0.126989 -0.641276 + outer loop + vertex 336.88 132.986 279.165 + vertex 338.317 141.311 275.821 + vertex 339.65 133.44 275.806 + endloop + endfacet + facet normal -0.770016 -0.129271 -0.624792 + outer loop + vertex 338.317 141.311 275.821 + vertex 340.453 140.521 273.351 + vertex 339.65 133.44 275.806 + endloop + endfacet + facet normal -0.759687 -0.125211 -0.63812 + outer loop + vertex 335.563 141.102 279.14 + vertex 338.317 141.311 275.821 + vertex 336.88 132.986 279.165 + endloop + endfacet + facet normal -0.738789 -0.121899 -0.662821 + outer loop + vertex 333.965 131.974 282.6 + vertex 335.563 141.102 279.14 + vertex 336.88 132.986 279.165 + endloop + endfacet + facet normal -0.759062 -0.130018 -0.637903 + outer loop + vertex 335.563 141.102 279.14 + vertex 337.073 149.318 275.669 + vertex 338.317 141.311 275.821 + endloop + endfacet + facet normal -0.773619 -0.131936 -0.619763 + outer loop + vertex 337.073 149.318 275.669 + vertex 339.522 147.999 272.892 + vertex 338.317 141.311 275.821 + endloop + endfacet + facet normal -0.763399 -0.127262 -0.633267 + outer loop + vertex 334.262 149.226 279.076 + vertex 337.073 149.318 275.669 + vertex 335.563 141.102 279.14 + endloop + endfacet + facet normal -0.73481 -0.125725 -0.666519 + outer loop + vertex 335.379 123.597 282.537 + vertex 338.334 124.589 279.092 + vertex 337.05 114.829 282.349 + endloop + endfacet + facet normal -0.739299 -0.119802 -0.662635 + outer loop + vertex 333.965 131.974 282.6 + vertex 336.88 132.986 279.165 + vertex 335.379 123.597 282.537 + endloop + endfacet + facet normal -0.74329 -0.119372 -0.658233 + outer loop + vertex 332.659 140.146 282.593 + vertex 335.563 141.102 279.14 + vertex 333.965 131.974 282.6 + endloop + endfacet + facet normal -0.722027 -0.11344 -0.682501 + outer loop + vertex 328.538 147.054 285.761 + vertex 331.359 148.303 282.569 + vertex 329.819 138.878 285.765 + endloop + endfacet + facet normal -0.72168 -0.114646 -0.682667 + outer loop + vertex 328.538 147.054 285.761 + vertex 330.058 156.529 282.563 + vertex 331.359 148.303 282.569 + endloop + endfacet + facet normal -0.727964 -0.11155 -0.67648 + outer loop + vertex 327.262 155.332 285.769 + vertex 330.058 156.529 282.563 + vertex 328.538 147.054 285.761 + endloop + endfacet + facet normal -0.731036 -0.100238 -0.674936 + outer loop + vertex 327.262 155.332 285.769 + vertex 328.823 164.877 282.661 + vertex 330.058 156.529 282.563 + endloop + endfacet + facet normal -0.759641 -0.104863 -0.641833 + outer loop + vertex 328.823 164.877 282.661 + vertex 331.608 165.896 279.199 + vertex 330.058 156.529 282.563 + endloop + endfacet + facet normal -0.755318 -0.107261 -0.646521 + outer loop + vertex 330.058 156.529 282.563 + vertex 331.608 165.896 279.199 + vertex 332.927 157.501 279.05 + endloop + endfacet + facet normal -0.768335 -0.0640917 -0.636831 + outer loop + vertex 328.823 164.877 282.661 + vertex 330.469 174.409 279.715 + vertex 331.608 165.896 279.199 + endloop + endfacet + facet normal -0.787359 -0.0680971 -0.612723 + outer loop + vertex 330.469 174.409 279.715 + vertex 332.969 175.294 276.405 + vertex 331.608 165.896 279.199 + endloop + endfacet + facet normal -0.781806 -0.0709086 -0.619476 + outer loop + vertex 331.608 165.896 279.199 + vertex 332.969 175.294 276.405 + vertex 334.324 166.426 275.709 + endloop + endfacet + facet normal -0.768911 -0.0637864 -0.636165 + outer loop + vertex 327.784 173.465 283.056 + vertex 330.469 174.409 279.715 + vertex 328.823 164.877 282.661 + endloop + endfacet + facet normal -0.742973 -0.0592466 -0.666694 + outer loop + vertex 326.04 163.79 285.859 + vertex 327.784 173.465 283.056 + vertex 328.823 164.877 282.661 + endloop + endfacet + facet normal -0.742513 -0.059472 -0.667186 + outer loop + vertex 324.955 172.482 286.292 + vertex 327.784 173.465 283.056 + vertex 326.04 163.79 285.859 + endloop + endfacet + facet normal -0.733769 -0.0988881 -0.672164 + outer loop + vertex 326.04 163.79 285.859 + vertex 328.823 164.877 282.661 + vertex 327.262 155.332 285.769 + endloop + endfacet + facet normal -0.74219 -0.124062 -0.658607 + outer loop + vertex 332.659 140.146 282.593 + vertex 334.262 149.226 279.076 + vertex 335.563 141.102 279.14 + endloop + endfacet + facet normal -0.752527 -0.119498 -0.647629 + outer loop + vertex 330.058 156.529 282.563 + vertex 332.927 157.501 279.05 + vertex 331.359 148.303 282.569 + endloop + endfacet + facet normal -0.763141 -0.129541 -0.633116 + outer loop + vertex 334.262 149.226 279.076 + vertex 335.725 157.636 275.592 + vertex 337.073 149.318 275.669 + endloop + endfacet + facet normal -0.778987 -0.131921 -0.613006 + outer loop + vertex 335.725 157.636 275.592 + vertex 338.203 156.447 272.698 + vertex 337.073 149.318 275.669 + endloop + endfacet + facet normal -0.775929 -0.110955 -0.620985 + outer loop + vertex 331.608 165.896 279.199 + vertex 334.324 166.426 275.709 + vertex 332.927 157.501 279.05 + endloop + endfacet + facet normal -0.800345 -0.075684 -0.594743 + outer loop + vertex 332.969 175.294 276.405 + vertex 335.548 176.209 272.818 + vertex 334.324 166.426 275.709 + endloop + endfacet + facet normal -0.834135 -0.121058 -0.538111 + outer loop + vertex 337.42 171.019 270.749 + vertex 338.51 167.936 269.752 + vertex 338.683 162.553 270.695 + endloop + endfacet + facet normal -0.778311 -0.124817 -0.615348 + outer loop + vertex 335.725 157.636 275.592 + vertex 336.785 165.249 272.706 + vertex 338.203 156.447 272.698 + endloop + endfacet + facet normal -0.803297 -0.138843 -0.579168 + outer loop + vertex 338.683 162.553 270.695 + vertex 339.942 159.364 269.714 + vertex 340.13 153.77 270.794 + endloop + endfacet + facet normal -0.773998 -0.135051 -0.618618 + outer loop + vertex 337.073 149.318 275.669 + vertex 338.203 156.447 272.698 + vertex 339.522 147.999 272.892 + endloop + endfacet + facet normal -0.790123 -0.139012 -0.596976 + outer loop + vertex 340.13 153.77 270.794 + vertex 341.539 150.171 269.767 + vertex 341.666 143.992 271.038 + endloop + endfacet + facet normal -0.770269 -0.134153 -0.623449 + outer loop + vertex 338.317 141.311 275.821 + vertex 339.522 147.999 272.892 + vertex 340.453 140.521 273.351 + endloop + endfacet + facet normal -0.768686 -0.129941 -0.626288 + outer loop + vertex 339.65 133.44 275.806 + vertex 340.453 140.521 273.351 + vertex 342.202 133.585 272.644 + endloop + endfacet + facet normal -0.78422 -0.138171 -0.604903 + outer loop + vertex 341.666 143.992 271.038 + vertex 343.04 142.094 269.69 + vertex 343.356 136.814 270.487 + endloop + endfacet + facet normal -0.780026 -0.137218 -0.610516 + outer loop + vertex 343.356 136.814 270.487 + vertex 344.397 134.455 269.687 + vertex 344.577 127.773 270.959 + endloop + endfacet + facet normal -0.761886 -0.134093 -0.633679 + outer loop + vertex 341.132 125.027 275.741 + vertex 342.202 133.585 272.644 + vertex 343.368 124.208 273.226 + endloop + endfacet + facet normal -0.757887 -0.138751 -0.637461 + outer loop + vertex 342.853 116.167 275.589 + vertex 343.368 124.208 273.226 + vertex 345.466 116.28 272.458 + endloop + endfacet + facet normal -0.756326 -0.150741 -0.636591 + outer loop + vertex 342.853 116.167 275.589 + vertex 345.466 116.28 272.458 + vertex 344.88 107.15 275.316 + endloop + endfacet + facet normal -0.778251 -0.14223 -0.611634 + outer loop + vertex 344.577 127.773 270.959 + vertex 345.84 126.225 269.711 + vertex 346.42 119.96 270.43 + endloop + endfacet + facet normal -0.780077 -0.142134 -0.609326 + outer loop + vertex 346.42 119.96 270.43 + vertex 345.84 126.225 269.711 + vertex 347.429 117.786 269.645 + endloop + endfacet + facet normal -0.764224 -0.153912 -0.626317 + outer loop + vertex 347.224 106.586 272.694 + vertex 345.466 116.28 272.458 + vertex 348.253 109.991 270.602 + endloop + endfacet + facet normal -0.752767 -0.152179 -0.640456 + outer loop + vertex 344.88 107.15 275.316 + vertex 345.466 116.28 272.458 + vertex 347.224 106.586 272.694 + endloop + endfacet + facet normal -0.74365 -0.147421 -0.652113 + outer loop + vertex 342.034 106.634 278.677 + vertex 342.853 116.167 275.589 + vertex 344.88 107.15 275.316 + endloop + endfacet + facet normal -0.725704 -0.141289 -0.673343 + outer loop + vertex 339.04 105.709 282.098 + vertex 340.034 115.756 278.92 + vertex 342.034 106.634 278.677 + endloop + endfacet + facet normal -0.691316 -0.158435 -0.704969 + outer loop + vertex 335.995 104.676 285.317 + vertex 339.04 105.709 282.098 + vertex 338.007 98.9988 284.619 + endloop + endfacet + facet normal -0.673214 -0.14966 -0.724144 + outer loop + vertex 336.53 97.6989 286.262 + vertex 335.995 104.676 285.317 + vertex 338.007 98.9988 284.619 + endloop + endfacet + facet normal -0.654542 -0.182822 -0.733587 + outer loop + vertex 336.53 97.6989 286.262 + vertex 338.007 98.9988 284.619 + vertex 337.812 93.6427 286.128 + endloop + endfacet + facet normal -0.648389 -0.150749 -0.746235 + outer loop + vertex 336.53 97.6989 286.262 + vertex 334.899 98.2691 287.564 + vertex 335.995 104.676 285.317 + endloop + endfacet + facet normal -0.659007 -0.145986 -0.737833 + outer loop + vertex 333.014 103.493 288.214 + vertex 335.995 104.676 285.317 + vertex 334.899 98.2691 287.564 + endloop + endfacet + facet normal -0.64022 -0.13696 -0.755883 + outer loop + vertex 333.579 97.339 288.85 + vertex 333.014 103.493 288.214 + vertex 334.899 98.2691 287.564 + endloop + endfacet + facet normal -0.625422 -0.166771 -0.762256 + outer loop + vertex 333.579 97.339 288.85 + vertex 334.899 98.2691 287.564 + vertex 334.497 93.3799 288.963 + endloop + endfacet + facet normal -0.609525 -0.163467 -0.775731 + outer loop + vertex 333.579 97.339 288.85 + vertex 334.497 93.3799 288.963 + vertex 332.237 94.4082 290.522 + endloop + endfacet + facet normal -0.641422 -0.136965 -0.754863 + outer loop + vertex 332.237 94.4082 290.522 + vertex 333.014 103.493 288.214 + vertex 333.579 97.339 288.85 + endloop + endfacet + facet normal -0.617804 -0.143619 -0.773106 + outer loop + vertex 329.907 103.446 290.705 + vertex 333.014 103.493 288.214 + vertex 332.237 94.4082 290.522 + endloop + endfacet + facet normal -0.620551 -0.113121 -0.775964 + outer loop + vertex 329.907 103.446 290.705 + vertex 331.114 112.762 288.382 + vertex 333.014 103.493 288.214 + endloop + endfacet + facet normal -0.622901 -0.112374 -0.774188 + outer loop + vertex 328.158 112.365 290.818 + vertex 331.114 112.762 288.382 + vertex 329.907 103.446 290.705 + endloop + endfacet + facet normal -0.624721 -0.10014 -0.7744 + outer loop + vertex 328.158 112.365 290.818 + vertex 329.615 121.352 288.48 + vertex 331.114 112.762 288.382 + endloop + endfacet + facet normal -0.630538 -0.0980371 -0.769942 + outer loop + vertex 326.802 120.805 290.854 + vertex 329.615 121.352 288.48 + vertex 328.158 112.365 290.818 + endloop + endfacet + facet normal -0.630871 -0.096165 -0.769905 + outer loop + vertex 326.802 120.805 290.854 + vertex 328.331 129.597 288.503 + vertex 329.615 121.352 288.48 + endloop + endfacet + facet normal -0.635036 -0.094576 -0.766671 + outer loop + vertex 325.613 129.005 290.827 + vertex 328.331 129.597 288.503 + vertex 326.802 120.805 290.854 + endloop + endfacet + facet normal -0.634564 -0.0970566 -0.766752 + outer loop + vertex 325.613 129.005 290.827 + vertex 327.093 137.745 288.495 + vertex 328.331 129.597 288.503 + endloop + endfacet + facet normal -0.638742 -0.0954749 -0.763474 + outer loop + vertex 324.413 137.104 290.818 + vertex 327.093 137.745 288.495 + vertex 325.613 129.005 290.827 + endloop + endfacet + facet normal -0.638429 -0.0970233 -0.763541 + outer loop + vertex 324.413 137.104 290.818 + vertex 325.836 145.942 288.505 + vertex 327.093 137.745 288.495 + endloop + endfacet + facet normal -0.64242 -0.0955517 -0.760373 + outer loop + vertex 323.173 145.301 290.836 + vertex 325.836 145.942 288.505 + vertex 324.413 137.104 290.818 + endloop + endfacet + facet normal -0.642411 -0.0955962 -0.760375 + outer loop + vertex 323.173 145.301 290.836 + vertex 324.557 154.305 288.534 + vertex 325.836 145.942 288.505 + endloop + endfacet + facet normal -0.642051 -0.0957248 -0.760662 + outer loop + vertex 321.837 153.747 290.9 + vertex 324.557 154.305 288.534 + vertex 323.173 145.301 290.836 + endloop + endfacet + facet normal -0.644024 -0.0846281 -0.76031 + outer loop + vertex 321.837 153.747 290.9 + vertex 323.309 162.891 288.636 + vertex 324.557 154.305 288.534 + endloop + endfacet + facet normal -0.641308 -0.0856057 -0.762493 + outer loop + vertex 320.537 162.378 291.024 + vertex 323.309 162.891 288.636 + vertex 321.837 153.747 290.9 + endloop + endfacet + facet normal -0.647816 -0.0418095 -0.760649 + outer loop + vertex 320.537 162.378 291.024 + vertex 322.379 171.601 288.949 + vertex 323.309 162.891 288.636 + endloop + endfacet + facet normal -0.666793 -0.0343753 -0.74445 + outer loop + vertex 319.753 170.723 291.342 + vertex 322.379 171.601 288.949 + vertex 320.537 162.378 291.024 + endloop + endfacet + facet normal -0.665965 -0.123289 -0.735724 + outer loop + vertex 333.014 103.493 288.214 + vertex 334.057 113.691 285.561 + vertex 335.995 104.676 285.317 + endloop + endfacet + facet normal -0.666207 -0.123211 -0.735519 + outer loop + vertex 331.114 112.762 288.382 + vertex 334.057 113.691 285.561 + vertex 333.014 103.493 288.214 + endloop + endfacet + facet normal -0.669423 -0.110347 -0.73464 + outer loop + vertex 331.114 112.762 288.382 + vertex 332.456 122.391 285.713 + vertex 334.057 113.691 285.561 + endloop + endfacet + facet normal -0.672895 -0.109036 -0.731658 + outer loop + vertex 329.615 121.352 288.48 + vertex 332.456 122.391 285.713 + vertex 331.114 112.762 288.382 + endloop + endfacet + facet normal -0.673885 -0.105343 -0.731288 + outer loop + vertex 329.615 121.352 288.48 + vertex 331.095 130.715 285.768 + vertex 332.456 122.391 285.713 + endloop + endfacet + facet normal -0.678064 -0.103631 -0.72766 + outer loop + vertex 328.331 129.597 288.503 + vertex 331.095 130.715 285.768 + vertex 329.615 121.352 288.48 + endloop + endfacet + facet normal -0.677355 -0.106122 -0.727962 + outer loop + vertex 328.331 129.597 288.503 + vertex 329.819 138.878 285.765 + vertex 331.095 130.715 285.768 + endloop + endfacet + facet normal -0.68192 -0.104212 -0.723964 + outer loop + vertex 327.093 137.745 288.495 + vertex 329.819 138.878 285.765 + vertex 328.331 129.597 288.503 + endloop + endfacet + facet normal -0.681098 -0.107054 -0.724324 + outer loop + vertex 327.093 137.745 288.495 + vertex 328.538 147.054 285.761 + vertex 329.819 138.878 285.765 + endloop + endfacet + facet normal -0.687139 -0.104543 -0.718966 + outer loop + vertex 325.836 145.942 288.505 + vertex 328.538 147.054 285.761 + vertex 327.093 137.745 288.495 + endloop + endfacet + facet normal -0.686956 -0.105185 -0.719046 + outer loop + vertex 325.836 145.942 288.505 + vertex 327.262 155.332 285.769 + vertex 328.538 147.054 285.761 + endloop + endfacet + facet normal -0.691559 -0.103277 -0.714898 + outer loop + vertex 324.557 154.305 288.534 + vertex 327.262 155.332 285.769 + vertex 325.836 145.942 288.505 + endloop + endfacet + facet normal -0.694308 -0.0927423 -0.713677 + outer loop + vertex 324.557 154.305 288.534 + vertex 326.04 163.79 285.859 + vertex 327.262 155.332 285.769 + endloop + endfacet + facet normal -0.694749 -0.0925593 -0.713272 + outer loop + vertex 323.309 162.891 288.636 + vertex 326.04 163.79 285.859 + vertex 324.557 154.305 288.534 + endloop + endfacet + facet normal -0.703418 -0.0525184 -0.708834 + outer loop + vertex 323.309 162.891 288.636 + vertex 324.955 172.482 286.292 + vertex 326.04 163.79 285.859 + endloop + endfacet + facet normal -0.70871 -0.0503558 -0.703701 + outer loop + vertex 322.379 171.601 288.949 + vertex 324.955 172.482 286.292 + vertex 323.309 162.891 288.636 + endloop + endfacet + facet normal -0.650841 -0.174579 -0.73887 + outer loop + vertex 334.899 98.2691 287.564 + vertex 336.53 97.6989 286.262 + vertex 336.207 93.3647 287.57 + endloop + endfacet + facet normal -0.660018 -0.18134 -0.729035 + outer loop + vertex 337.812 93.6427 286.128 + vertex 338.007 98.9988 284.619 + vertex 339.367 94.0739 284.613 + endloop + endfacet + facet normal -0.640332 -0.177881 -0.747217 + outer loop + vertex 336.207 93.3647 287.57 + vertex 336.53 97.6989 286.262 + vertex 337.812 93.6427 286.128 + endloop + endfacet + facet normal -0.623545 -0.16733 -0.76367 + outer loop + vertex 334.497 93.3799 288.963 + vertex 334.899 98.2691 287.564 + vertex 336.207 93.3647 287.57 + endloop + endfacet + facet normal -0.615913 -0.19721 -0.762731 + outer loop + vertex 334.497 93.3799 288.963 + vertex 334.356 88.574 290.319 + vertex 332.237 94.4082 290.522 + endloop + endfacet +endsolid diff --git a/noether_examples/meshes/outputs/output_16.stl b/noether_examples/meshes/outputs/output_16.stl new file mode 100644 index 00000000..31f8f5b0 --- /dev/null +++ b/noether_examples/meshes/outputs/output_16.stl @@ -0,0 +1,10320 @@ +solid ascii + facet normal 0.886297 -0.356989 0.295019 + outer loop + vertex -428.342 107.33 66.0721 + vertex -426.855 111.389 66.5163 + vertex -428.212 108.757 67.4084 + endloop + endfacet + facet normal 0.874151 -0.356362 0.329949 + outer loop + vertex -426.855 111.389 66.5163 + vertex -428.342 107.33 66.0721 + vertex -427.453 107.812 64.2378 + endloop + endfacet + facet normal 0.884036 -0.347189 0.312954 + outer loop + vertex -427.453 107.812 64.2378 + vertex -425.856 112.146 64.5352 + vertex -426.855 111.389 66.5163 + endloop + endfacet + facet normal 0.889934 -0.317766 0.327173 + outer loop + vertex -425.39 115.456 66.4826 + vertex -426.855 111.389 66.5163 + vertex -425.856 112.146 64.5352 + endloop + endfacet + facet normal 0.901675 -0.306431 0.305095 + outer loop + vertex -425.856 112.146 64.5352 + vertex -424.389 116.631 64.7032 + vertex -425.39 115.456 66.4826 + endloop + endfacet + facet normal 0.903718 -0.280887 0.323104 + outer loop + vertex -423.987 120.256 66.7318 + vertex -425.39 115.456 66.4826 + vertex -424.389 116.631 64.7032 + endloop + endfacet + facet normal 0.909622 -0.27499 0.311398 + outer loop + vertex -424.389 116.631 64.7032 + vertex -423.022 121.113 64.6682 + vertex -423.987 120.256 66.7318 + endloop + endfacet + facet normal 0.911912 -0.257019 0.319934 + outer loop + vertex -422.384 125.438 66.3261 + vertex -423.987 120.256 66.7318 + vertex -423.022 121.113 64.6682 + endloop + endfacet + facet normal 0.913476 -0.255882 0.316365 + outer loop + vertex -423.022 121.113 64.6682 + vertex -421.919 124.618 64.3185 + vertex -422.384 125.438 66.3261 + endloop + endfacet + facet normal 0.918308 -0.243241 0.312321 + outer loop + vertex -421.919 124.618 64.3185 + vertex -421.087 128.521 64.9123 + vertex -422.384 125.438 66.3261 + endloop + endfacet + facet normal 0.918267 -0.243127 0.31253 + outer loop + vertex -421.258 130.632 67.0583 + vertex -422.384 125.438 66.3261 + vertex -421.087 128.521 64.9123 + endloop + endfacet + facet normal 0.925074 -0.231177 0.301324 + outer loop + vertex -421.087 128.521 64.9123 + vertex -419.975 133.709 65.4787 + vertex -421.258 130.632 67.0583 + endloop + endfacet + facet normal 0.925252 -0.231767 0.30032 + outer loop + vertex -420.382 134.435 67.2947 + vertex -421.258 130.632 67.0583 + vertex -419.975 133.709 65.4787 + endloop + endfacet + facet normal 0.929425 -0.219743 0.296448 + outer loop + vertex -419.457 138.116 67.1222 + vertex -420.382 134.435 67.2947 + vertex -419.975 133.709 65.4787 + endloop + endfacet + facet normal 0.928807 -0.220251 0.298005 + outer loop + vertex -419.975 133.709 65.4787 + vertex -418.667 138.601 65.0181 + vertex -419.457 138.116 67.1222 + endloop + endfacet + facet normal 0.929472 -0.215605 0.299326 + outer loop + vertex -418.128 143.073 66.5664 + vertex -419.457 138.116 67.1222 + vertex -418.667 138.601 65.0181 + endloop + endfacet + facet normal 0.92804 -0.216692 0.302961 + outer loop + vertex -418.667 138.601 65.0181 + vertex -417.628 142.345 64.5129 + vertex -418.128 143.073 66.5664 + endloop + endfacet + facet normal 0.927582 -0.218105 0.303351 + outer loop + vertex -417.628 142.345 64.5129 + vertex -416.737 147.028 65.157 + vertex -418.128 143.073 66.5664 + endloop + endfacet + facet normal 0.928873 -0.220639 0.297512 + outer loop + vertex -417.229 147.804 67.2662 + vertex -418.128 143.073 66.5664 + vertex -416.737 147.028 65.157 + endloop + endfacet + facet normal 0.930046 -0.217067 0.296472 + outer loop + vertex -415.987 152.182 66.5755 + vertex -417.229 147.804 67.2662 + vertex -416.737 147.028 65.157 + endloop + endfacet + facet normal 0.927273 -0.218699 0.303869 + outer loop + vertex -416.737 147.028 65.157 + vertex -415.553 151.193 64.5393 + vertex -415.987 152.182 66.5755 + endloop + endfacet + facet normal 0.926788 -0.220008 0.304402 + outer loop + vertex -415.553 151.193 64.5393 + vertex -414.706 155.374 64.9837 + vertex -415.987 152.182 66.5755 + endloop + endfacet + facet normal 0.927368 -0.221766 0.301344 + outer loop + vertex -414.874 157.515 67.0748 + vertex -415.987 152.182 66.5755 + vertex -414.706 155.374 64.9837 + endloop + endfacet + facet normal 0.928842 -0.219105 0.298738 + outer loop + vertex -414.706 155.374 64.9837 + vertex -413.574 160.652 65.3361 + vertex -414.874 157.515 67.0748 + endloop + endfacet + facet normal 0.928915 -0.219367 0.298321 + outer loop + vertex -413.966 161.546 67.2124 + vertex -414.874 157.515 67.0748 + vertex -413.574 160.652 65.3361 + endloop + endfacet + facet normal 0.929406 -0.218017 0.297781 + outer loop + vertex -412.884 165.616 66.817 + vertex -413.966 161.546 67.2124 + vertex -413.574 160.652 65.3361 + endloop + endfacet + facet normal 0.929322 -0.218072 0.298001 + outer loop + vertex -413.574 160.652 65.3361 + vertex -412.411 164.565 64.5729 + vertex -412.884 165.616 66.817 + endloop + endfacet + facet normal 0.928727 -0.21972 0.298647 + outer loop + vertex -412.411 164.565 64.5729 + vertex -411.611 168.537 65.005 + vertex -412.884 165.616 66.817 + endloop + endfacet + facet normal 0.928798 -0.220032 0.298195 + outer loop + vertex -411.72 170.699 66.9419 + vertex -412.884 165.616 66.817 + vertex -411.611 168.537 65.005 + endloop + endfacet + facet normal 0.928365 -0.220771 0.298995 + outer loop + vertex -411.611 168.537 65.005 + vertex -410.557 173.656 65.5134 + vertex -411.72 170.699 66.9419 + endloop + endfacet + facet normal 0.928701 -0.221765 0.297212 + outer loop + vertex -411.016 174.37 67.4802 + vertex -411.72 170.699 66.9419 + vertex -410.557 173.656 65.5134 + endloop + endfacet + facet normal 0.930635 -0.215847 0.295514 + outer loop + vertex -410.082 177.725 66.9893 + vertex -411.016 174.37 67.4802 + vertex -410.557 173.656 65.5134 + endloop + endfacet + facet normal 0.928153 -0.217835 0.301794 + outer loop + vertex -410.557 173.656 65.5134 + vertex -409.291 178.541 65.1444 + vertex -410.082 177.725 66.9893 + endloop + endfacet + facet normal 0.928583 -0.212225 0.304457 + outer loop + vertex -408.988 182.371 66.8911 + vertex -410.082 177.725 66.9893 + vertex -409.291 178.541 65.1444 + endloop + endfacet + facet normal 0.927255 -0.213539 0.307569 + outer loop + vertex -409.291 178.541 65.1444 + vertex -408.166 183.057 64.8887 + vertex -408.988 182.371 66.8911 + endloop + endfacet + facet normal 0.928122 -0.204673 0.310964 + outer loop + vertex -407.696 187.44 66.3717 + vertex -408.988 182.371 66.8911 + vertex -408.166 183.057 64.8887 + endloop + endfacet + facet normal 0.924461 -0.207331 0.319979 + outer loop + vertex -408.166 183.057 64.8887 + vertex -407.201 186.719 64.4734 + vertex -407.696 187.44 66.3717 + endloop + endfacet + facet normal 0.93066 -0.18763 0.314113 + outer loop + vertex -407.201 186.719 64.4734 + vertex -406.494 191.527 65.2509 + vertex -407.696 187.44 66.3717 + endloop + endfacet + facet normal 0.931438 -0.188665 0.311173 + outer loop + vertex -407.039 192.248 67.3203 + vertex -407.696 187.44 66.3717 + vertex -406.494 191.527 65.2509 + endloop + endfacet + facet normal 0.940162 -0.156947 0.302427 + outer loop + vertex -406.624 197.191 68.5932 + vertex -407.039 192.248 67.3203 + vertex -406.494 191.527 65.2509 + endloop + endfacet + facet normal 0.959 -0.127432 0.253143 + outer loop + vertex -405.755 197.01 65.2122 + vertex -406.624 197.191 68.5932 + vertex -406.494 191.527 65.2509 + endloop + endfacet + facet normal 0.965334 -0.138206 0.221428 + outer loop + vertex -406.624 197.191 68.5932 + vertex -406.668 197.199 68.793 + vertex -407.039 192.248 67.3203 + endloop + endfacet + facet normal 0.920626 -0.173087 0.349984 + outer loop + vertex -406.668 197.199 68.793 + vertex -408.193 187.706 68.1079 + vertex -407.039 192.248 67.3203 + endloop + endfacet + facet normal 0.979571 -0.165535 0.114185 + outer loop + vertex -408.193 187.706 68.1079 + vertex -406.668 197.199 68.793 + vertex -407.556 192.614 69.7607 + endloop + endfacet + facet normal 0.972723 -0.176775 0.150203 + outer loop + vertex -407.556 192.614 69.7607 + vertex -408.141 188.7 68.9456 + vertex -408.193 187.706 68.1079 + endloop + endfacet + facet normal 0.960352 -0.206957 0.186795 + outer loop + vertex -408.141 188.7 68.9456 + vertex -408.509 186.831 68.7641 + vertex -408.193 187.706 68.1079 + endloop + endfacet + facet normal 0.96064 -0.218348 0.171743 + outer loop + vertex -408.509 186.831 68.7641 + vertex -409.328 183.345 68.918 + vertex -408.193 187.706 68.1079 + endloop + endfacet + facet normal 0.957722 -0.213712 0.192601 + outer loop + vertex -410.204 178.728 68.1494 + vertex -408.193 187.706 68.1079 + vertex -409.328 183.345 68.918 + endloop + endfacet + facet normal 0.95044 -0.217287 0.222374 + outer loop + vertex -409.328 183.345 68.918 + vertex -410.296 179.184 68.9889 + vertex -410.204 178.728 68.1494 + endloop + endfacet + facet normal 0.949511 -0.219951 0.223718 + outer loop + vertex -410.296 179.184 68.9889 + vertex -411.303 174.973 69.1209 + vertex -410.204 178.728 68.1494 + endloop + endfacet + facet normal 0.950578 -0.221978 0.21709 + outer loop + vertex -412.186 170.32 68.2288 + vertex -410.204 178.728 68.1494 + vertex -411.303 174.973 69.1209 + endloop + endfacet + facet normal 0.948459 -0.223103 0.225058 + outer loop + vertex -411.303 174.973 69.1209 + vertex -412.327 170.615 69.1167 + vertex -412.186 170.32 68.2288 + endloop + endfacet + facet normal 0.948892 -0.221666 0.22465 + outer loop + vertex -412.327 170.615 69.1167 + vertex -413.328 166.367 69.1535 + vertex -412.186 170.32 68.2288 + endloop + endfacet + facet normal 0.95038 -0.224196 0.215669 + outer loop + vertex -414.268 161.533 68.2703 + vertex -412.186 170.32 68.2288 + vertex -413.328 166.367 69.1535 + endloop + endfacet + facet normal 0.948211 -0.225283 0.223926 + outer loop + vertex -413.328 166.367 69.1535 + vertex -414.205 162.576 69.0507 + vertex -414.268 161.533 68.2703 + endloop + endfacet + facet normal 0.948761 -0.224306 0.222575 + outer loop + vertex -414.205 162.576 69.0507 + vertex -414.639 160.732 69.0459 + vertex -414.268 161.533 68.2703 + endloop + endfacet + facet normal 0.948741 -0.221722 0.225232 + outer loop + vertex -414.639 160.732 69.0459 + vertex -415.494 157.163 69.1346 + vertex -414.268 161.533 68.2703 + endloop + endfacet + facet normal 0.950425 -0.224107 0.215564 + outer loop + vertex -416.364 152.563 68.1883 + vertex -414.268 161.533 68.2703 + vertex -415.494 157.163 69.1346 + endloop + endfacet + facet normal 0.949002 -0.224937 0.220905 + outer loop + vertex -415.494 157.163 69.1346 + vertex -416.519 152.812 69.1069 + vertex -416.364 152.563 68.1883 + endloop + endfacet + facet normal 0.949667 -0.222623 0.220391 + outer loop + vertex -416.519 152.812 69.1069 + vertex -417.532 148.497 69.1139 + vertex -416.364 152.563 68.1883 + endloop + endfacet + facet normal 0.950637 -0.224247 0.214484 + outer loop + vertex -418.533 143.402 68.2228 + vertex -416.364 152.563 68.1883 + vertex -417.532 148.497 69.1139 + endloop + endfacet + facet normal 0.947414 -0.225767 0.226795 + outer loop + vertex -417.532 148.497 69.1139 + vertex -418.424 144.638 68.996 + vertex -418.533 143.402 68.2228 + endloop + endfacet + facet normal 0.949072 -0.223163 0.222398 + outer loop + vertex -418.424 144.638 68.996 + vertex -418.852 142.804 68.9829 + vertex -418.533 143.402 68.2228 + endloop + endfacet + facet normal 0.949173 -0.220872 0.224244 + outer loop + vertex -418.852 142.804 68.9829 + vertex -419.682 139.338 69.0814 + vertex -418.533 143.402 68.2228 + endloop + endfacet + facet normal 0.952724 -0.226455 0.202572 + outer loop + vertex -420.604 134.678 68.2079 + vertex -418.533 143.402 68.2228 + vertex -419.682 139.338 69.0814 + endloop + endfacet + facet normal 0.952911 -0.226349 0.201811 + outer loop + vertex -419.682 139.338 69.0814 + vertex -420.677 135.14 69.0726 + vertex -420.604 134.678 68.2079 + endloop + endfacet + facet normal 0.950604 -0.232955 0.205142 + outer loop + vertex -420.677 135.14 69.0726 + vertex -421.713 130.924 69.0862 + vertex -420.604 134.678 68.2079 + endloop + endfacet + facet normal 0.958844 -0.235128 0.159167 + outer loop + vertex -421.713 130.924 69.0862 + vertex -420.677 135.14 69.0726 + vertex -420.636 136.479 70.8041 + endloop + endfacet + facet normal 0.961378 -0.228256 0.153792 + outer loop + vertex -420.677 135.14 69.0726 + vertex -419.682 139.338 69.0814 + vertex -420.636 136.479 70.8041 + endloop + endfacet + facet normal 0.961374 -0.228108 0.154036 + outer loop + vertex -418.562 145.068 70.578 + vertex -420.636 136.479 70.8041 + vertex -419.682 139.338 69.0814 + endloop + endfacet + facet normal 0.966596 -0.230472 0.112137 + outer loop + vertex -418.562 145.068 70.578 + vertex -419.281 144.203 74.9939 + vertex -420.636 136.479 70.8041 + endloop + endfacet + facet normal 0.965421 -0.232936 0.117059 + outer loop + vertex -420.636 136.479 70.8041 + vertex -419.281 144.203 74.9939 + vertex -421.472 135.18 75.1095 + endloop + endfacet + facet normal 0.963619 -0.24172 0.114059 + outer loop + vertex -420.636 136.479 70.8041 + vertex -421.472 135.18 75.1095 + vertex -422.931 127.265 70.6626 + endloop + endfacet + facet normal 0.959508 -0.249903 0.129974 + outer loop + vertex -422.931 127.265 70.6626 + vertex -421.472 135.18 75.1095 + vertex -424.064 125.303 75.2528 + endloop + endfacet + facet normal 0.953907 -0.276209 0.117345 + outer loop + vertex -422.931 127.265 70.6626 + vertex -424.064 125.303 75.2528 + vertex -425.735 117.637 70.7975 + endloop + endfacet + facet normal 0.951401 -0.280865 0.126297 + outer loop + vertex -425.735 117.637 70.7975 + vertex -424.064 125.303 75.2528 + vertex -425.711 118.986 73.6151 + endloop + endfacet + facet normal 0.942352 -0.304896 0.137883 + outer loop + vertex -425.711 118.986 73.6151 + vertex -427.053 114.694 73.2961 + vertex -425.735 117.637 70.7975 + endloop + endfacet + facet normal 0.938947 -0.325308 0.112046 + outer loop + vertex -427.053 114.694 73.2961 + vertex -428.224 110.43 70.7258 + vertex -425.735 117.637 70.7975 + endloop + endfacet + facet normal 0.929832 -0.340045 0.140644 + outer loop + vertex -428.914 109.606 73.3014 + vertex -428.224 110.43 70.7258 + vertex -427.053 114.694 73.2961 + endloop + endfacet + facet normal 0.934371 -0.341748 0.100788 + outer loop + vertex -427.053 114.694 73.2961 + vertex -427.677 113.9 76.3916 + vertex -428.914 109.606 73.3014 + endloop + endfacet + facet normal 0.932006 -0.346062 0.107728 + outer loop + vertex -428.914 109.606 73.3014 + vertex -427.677 113.9 76.3916 + vertex -429.366 109.386 76.502 + endloop + endfacet + facet normal 0.913351 -0.394248 0.101782 + outer loop + vertex -428.914 109.606 73.3014 + vertex -429.366 109.386 76.502 + vertex -430.769 105.27 73.1505 + endloop + endfacet + facet normal 0.908545 -0.402093 0.11343 + outer loop + vertex -430.769 105.27 73.1505 + vertex -429.366 109.386 76.502 + vertex -431.109 105.392 76.3055 + endloop + endfacet + facet normal 0.934716 -0.347939 0.0724153 + outer loop + vertex -427.677 113.9 76.3916 + vertex -427.992 113.794 79.9474 + vertex -429.366 109.386 76.502 + endloop + endfacet + facet normal 0.93439 -0.348607 0.0733997 + outer loop + vertex -429.366 109.386 76.502 + vertex -427.992 113.794 79.9474 + vertex -429.604 109.493 80.0417 + endloop + endfacet + facet normal 0.912704 -0.401947 0.0735579 + outer loop + vertex -429.366 109.386 76.502 + vertex -429.604 109.493 80.0417 + vertex -431.109 105.392 76.3055 + endloop + endfacet + facet normal 0.911119 -0.404819 0.0773494 + outer loop + vertex -431.109 105.392 76.3055 + vertex -429.604 109.493 80.0417 + vertex -431.316 105.589 79.7701 + endloop + endfacet + facet normal 0.914416 -0.403292 0.0346324 + outer loop + vertex -429.604 109.493 80.0417 + vertex -429.704 109.582 83.6966 + vertex -431.316 105.589 79.7701 + endloop + endfacet + facet normal 0.913294 -0.405579 0.0374183 + outer loop + vertex -431.316 105.589 79.7701 + vertex -429.704 109.582 83.6966 + vertex -431.433 105.658 83.3787 + endloop + endfacet + facet normal 0.915218 -0.402916 -0.0059142 + outer loop + vertex -429.704 109.582 83.6966 + vertex -429.696 109.545 87.3957 + vertex -431.433 105.658 83.3787 + endloop + endfacet + facet normal 0.913438 -0.406977 -0.00121488 + outer loop + vertex -431.433 105.658 83.3787 + vertex -429.696 109.545 87.3957 + vertex -431.455 105.599 87.0761 + endloop + endfacet + facet normal 0.913865 -0.403954 -0.0408919 + outer loop + vertex -429.696 109.545 87.3957 + vertex -429.579 109.43 91.1346 + vertex -431.455 105.599 87.0761 + endloop + endfacet + facet normal 0.911385 -0.410158 -0.0338889 + outer loop + vertex -431.455 105.599 87.0761 + vertex -429.579 109.43 91.1346 + vertex -431.36 105.498 90.8306 + endloop + endfacet + facet normal 0.910795 -0.407284 -0.0676146 + outer loop + vertex -429.579 109.43 91.1346 + vertex -429.356 109.309 94.8766 + vertex -431.36 105.498 90.8306 + endloop + endfacet + facet normal 0.90894 -0.412294 -0.0619766 + outer loop + vertex -431.36 105.498 90.8306 + vertex -429.356 109.309 94.8766 + vertex -431.15 105.396 94.5936 + endloop + endfacet + facet normal 0.907612 -0.409469 -0.0925987 + outer loop + vertex -429.356 109.309 94.8766 + vertex -429.036 109.181 98.5795 + vertex -431.15 105.396 94.5936 + endloop + endfacet + facet normal 0.906021 -0.414125 -0.0873343 + outer loop + vertex -431.15 105.396 94.5936 + vertex -429.036 109.181 98.5795 + vertex -430.84 105.292 98.3071 + endloop + endfacet + facet normal 0.904266 -0.411436 -0.114118 + outer loop + vertex -429.036 109.181 98.5795 + vertex -428.637 109.053 102.196 + vertex -430.84 105.292 98.3071 + endloop + endfacet + facet normal 0.90284 -0.415944 -0.108949 + outer loop + vertex -430.84 105.292 98.3071 + vertex -428.637 109.053 102.196 + vertex -430.452 105.185 101.931 + endloop + endfacet + facet normal 0.900689 -0.413207 -0.134238 + outer loop + vertex -428.637 109.053 102.196 + vertex -428.169 108.919 105.75 + vertex -430.452 105.185 101.931 + endloop + endfacet + facet normal 0.899786 -0.416306 -0.130667 + outer loop + vertex -430.452 105.185 101.931 + vertex -428.169 108.919 105.75 + vertex -429.99 105.061 105.503 + endloop + endfacet + facet normal 0.897245 -0.413572 -0.154625 + outer loop + vertex -428.169 108.919 105.75 + vertex -427.625 108.764 109.323 + vertex -429.99 105.061 105.503 + endloop + endfacet + facet normal 0.896548 -0.41617 -0.151675 + outer loop + vertex -429.99 105.061 105.503 + vertex -427.625 108.764 109.323 + vertex -429.451 104.914 109.093 + endloop + endfacet + facet normal 0.893738 -0.413512 -0.173896 + outer loop + vertex -427.625 108.764 109.323 + vertex -426.996 108.584 112.984 + vertex -429.451 104.914 109.093 + endloop + endfacet + facet normal 0.892621 -0.417917 -0.169037 + outer loop + vertex -429.451 104.914 109.093 + vertex -426.996 108.584 112.984 + vertex -428.831 104.753 112.766 + endloop + endfacet + facet normal 0.889547 -0.41522 -0.190525 + outer loop + vertex -426.996 108.584 112.984 + vertex -426.279 108.385 116.765 + vertex -428.831 104.753 112.766 + endloop + endfacet + facet normal 0.888631 -0.418979 -0.186527 + outer loop + vertex -428.831 104.753 112.766 + vertex -426.279 108.385 116.765 + vertex -428.121 104.57 116.557 + endloop + endfacet + facet normal 0.885679 -0.416539 -0.205103 + outer loop + vertex -426.279 108.385 116.765 + vertex -425.48 108.176 120.642 + vertex -428.121 104.57 116.557 + endloop + endfacet + facet normal 0.885216 -0.418526 -0.20305 + outer loop + vertex -428.121 104.57 116.557 + vertex -425.48 108.176 120.642 + vertex -427.326 104.366 120.445 + endloop + endfacet + facet normal 0.881994 -0.416016 -0.221399 + outer loop + vertex -425.48 108.176 120.642 + vertex -424.604 107.946 124.563 + vertex -427.326 104.366 120.445 + endloop + endfacet + facet normal 0.88097 -0.420625 -0.216715 + outer loop + vertex -427.326 104.366 120.445 + vertex -424.604 107.946 124.563 + vertex -426.462 104.155 124.368 + endloop + endfacet + facet normal 0.877387 -0.417893 -0.235706 + outer loop + vertex -424.604 107.946 124.563 + vertex -423.67 107.707 128.461 + vertex -426.462 104.155 124.368 + endloop + endfacet + facet normal 0.876564 -0.421822 -0.231735 + outer loop + vertex -426.462 104.155 124.368 + vertex -423.67 107.707 128.461 + vertex -425.538 103.93 128.273 + endloop + endfacet + facet normal 0.873135 -0.419282 -0.248671 + outer loop + vertex -423.67 107.707 128.461 + vertex -422.692 107.468 132.3 + vertex -425.538 103.93 128.273 + endloop + endfacet + facet normal 0.87266 -0.421734 -0.246181 + outer loop + vertex -425.538 103.93 128.273 + vertex -422.692 107.468 132.3 + vertex -424.564 103.694 132.129 + endloop + endfacet + facet normal 0.868975 -0.419138 -0.263071 + outer loop + vertex -422.692 107.468 132.3 + vertex -421.664 107.215 136.099 + vertex -424.564 103.694 132.129 + endloop + endfacet + facet normal 0.868127 -0.423856 -0.258267 + outer loop + vertex -424.564 103.694 132.129 + vertex -421.664 107.215 136.099 + vertex -423.547 103.456 135.939 + endloop + endfacet + facet normal 0.864195 -0.421161 -0.275301 + outer loop + vertex -421.664 107.215 136.099 + vertex -420.583 106.956 139.889 + vertex -423.547 103.456 135.939 + endloop + endfacet + facet normal 0.863466 -0.425455 -0.270951 + outer loop + vertex -423.547 103.456 135.939 + vertex -420.583 106.956 139.889 + vertex -422.476 103.206 139.744 + endloop + endfacet + facet normal 0.859586 -0.422879 -0.286856 + outer loop + vertex -420.583 106.956 139.889 + vertex -419.441 106.686 143.709 + vertex -422.476 103.206 139.744 + endloop + endfacet + facet normal 0.858788 -0.427764 -0.281959 + outer loop + vertex -422.476 103.206 139.744 + vertex -419.441 106.686 143.709 + vertex -421.346 102.948 143.577 + endloop + endfacet + facet normal 0.854845 -0.425208 -0.297385 + outer loop + vertex -419.441 106.686 143.709 + vertex -418.234 106.407 147.576 + vertex -421.346 102.948 143.577 + endloop + endfacet + facet normal 0.854083 -0.429995 -0.292653 + outer loop + vertex -421.346 102.948 143.577 + vertex -418.234 106.407 147.576 + vertex -420.153 102.679 147.456 + endloop + endfacet + facet normal 0.849495 -0.42708 -0.309777 + outer loop + vertex -418.234 106.407 147.576 + vertex -416.958 106.103 151.496 + vertex -420.153 102.679 147.456 + endloop + endfacet + facet normal 0.848607 -0.432792 -0.304233 + outer loop + vertex -420.153 102.679 147.456 + vertex -416.958 106.103 151.496 + vertex -418.892 102.388 151.383 + endloop + endfacet + facet normal 0.844678 -0.430319 -0.318347 + outer loop + vertex -416.958 106.103 151.496 + vertex -415.628 105.797 155.436 + vertex -418.892 102.388 151.383 + endloop + endfacet + facet normal 0.843879 -0.435568 -0.313288 + outer loop + vertex -418.892 102.388 151.383 + vertex -415.628 105.797 155.436 + vertex -417.579 102.092 155.333 + endloop + endfacet + facet normal 0.839586 -0.432894 -0.328173 + outer loop + vertex -415.628 105.797 155.436 + vertex -414.253 105.481 159.373 + vertex -417.579 102.092 155.333 + endloop + endfacet + facet normal 0.838859 -0.437863 -0.323405 + outer loop + vertex -417.579 102.092 155.333 + vertex -414.253 105.481 159.373 + vertex -416.22 101.781 159.279 + endloop + endfacet + facet normal 0.834288 -0.435046 -0.338673 + outer loop + vertex -414.253 105.481 159.373 + vertex -412.838 105.149 163.284 + vertex -416.22 101.781 159.279 + endloop + endfacet + facet normal 0.833283 -0.442205 -0.331804 + outer loop + vertex -416.22 101.781 159.279 + vertex -412.838 105.149 163.284 + vertex -414.828 101.465 163.195 + endloop + endfacet + facet normal 0.828351 -0.439151 -0.347824 + outer loop + vertex -412.838 105.149 163.284 + vertex -411.39 104.81 167.161 + vertex -414.828 101.465 163.195 + endloop + endfacet + facet normal 0.827499 -0.445483 -0.341746 + outer loop + vertex -414.828 101.465 163.195 + vertex -411.39 104.81 167.161 + vertex -413.401 101.134 167.083 + endloop + endfacet + facet normal 0.823318 -0.442916 -0.354926 + outer loop + vertex -411.39 104.81 167.161 + vertex -409.914 104.473 171.005 + vertex -413.401 101.134 167.083 + endloop + endfacet + facet normal 0.822887 -0.446324 -0.351641 + outer loop + vertex -413.401 101.134 167.083 + vertex -409.914 104.473 171.005 + vertex -411.935 100.789 170.951 + endloop + endfacet + facet normal 0.818365 -0.443638 -0.365327 + outer loop + vertex -409.914 104.473 171.005 + vertex -408.394 104.12 174.84 + vertex -411.935 100.789 170.951 + endloop + endfacet + facet normal 0.817525 -0.450661 -0.358549 + outer loop + vertex -411.935 100.789 170.951 + vertex -408.394 104.12 174.84 + vertex -410.437 100.446 174.799 + endloop + endfacet + facet normal 0.812822 -0.44789 -0.372444 + outer loop + vertex -408.394 104.12 174.84 + vertex -406.842 103.766 178.652 + vertex -410.437 100.446 174.799 + endloop + endfacet + facet normal 0.811945 -0.455463 -0.365101 + outer loop + vertex -410.437 100.446 174.799 + vertex -406.842 103.766 178.652 + vertex -408.911 100.103 178.621 + endloop + endfacet + facet normal 0.806992 -0.452543 -0.379433 + outer loop + vertex -406.842 103.766 178.652 + vertex -405.267 103.404 182.433 + vertex -408.911 100.103 178.621 + endloop + endfacet + facet normal 0.806437 -0.457573 -0.374548 + outer loop + vertex -408.911 100.103 178.621 + vertex -405.267 103.404 182.433 + vertex -407.354 99.743 182.413 + endloop + endfacet + facet normal 0.8017 -0.4548 -0.387858 + outer loop + vertex -405.267 103.404 182.433 + vertex -403.673 103.016 186.182 + vertex -407.354 99.743 182.413 + endloop + endfacet + facet normal 0.800956 -0.461835 -0.381021 + outer loop + vertex -407.354 99.743 182.413 + vertex -403.673 103.016 186.182 + vertex -405.781 99.3749 186.164 + endloop + endfacet + facet normal 0.795344 -0.458512 -0.396478 + outer loop + vertex -403.673 103.016 186.182 + vertex -402.063 102.594 189.901 + vertex -405.781 99.3749 186.164 + endloop + endfacet + facet normal 0.794545 -0.466151 -0.389104 + outer loop + vertex -405.781 99.3749 186.164 + vertex -402.063 102.594 189.901 + vertex -404.185 98.9881 189.887 + endloop + endfacet + facet normal 0.788849 -0.462736 -0.404467 + outer loop + vertex -402.063 102.594 189.901 + vertex -400.419 102.154 193.61 + vertex -404.185 98.9881 189.887 + endloop + endfacet + facet normal 0.787964 -0.471088 -0.396471 + outer loop + vertex -404.185 98.9881 189.887 + vertex -400.419 102.154 193.61 + vertex -402.565 98.5888 193.581 + endloop + endfacet + facet normal 0.781622 -0.467131 -0.413346 + outer loop + vertex -400.419 102.154 193.61 + vertex -398.741 101.693 197.304 + vertex -402.565 98.5888 193.581 + endloop + endfacet + facet normal 0.780291 -0.479123 -0.401979 + outer loop + vertex -402.565 98.5888 193.581 + vertex -398.741 101.693 197.304 + vertex -400.931 98.187 197.233 + endloop + endfacet + facet normal 0.774668 -0.475305 -0.417103 + outer loop + vertex -398.741 101.693 197.304 + vertex -397.063 101.247 200.929 + vertex -400.931 98.187 197.233 + endloop + endfacet + facet normal 0.773839 -0.482634 -0.410168 + outer loop + vertex -400.931 98.187 197.233 + vertex -397.063 101.247 200.929 + vertex -399.276 97.7771 200.836 + endloop + endfacet + facet normal 0.768583 -0.478908 -0.424178 + outer loop + vertex -397.063 101.247 200.929 + vertex -395.368 100.82 204.483 + vertex -399.276 97.7771 200.836 + endloop + endfacet + facet normal 0.767628 -0.48767 -0.415843 + outer loop + vertex -399.276 97.7771 200.836 + vertex -395.368 100.82 204.483 + vertex -397.611 97.3586 204.402 + endloop + endfacet + facet normal 0.762066 -0.483725 -0.430425 + outer loop + vertex -395.368 100.82 204.483 + vertex -393.657 100.391 207.993 + vertex -397.611 97.3586 204.402 + endloop + endfacet + facet normal 0.761581 -0.488522 -0.425841 + outer loop + vertex -397.611 97.3586 204.402 + vertex -393.657 100.391 207.993 + vertex -395.919 96.9056 207.947 + endloop + endfacet + facet normal 0.756616 -0.485135 -0.438379 + outer loop + vertex -393.657 100.391 207.993 + vertex -391.935 99.9314 211.475 + vertex -395.919 96.9056 207.947 + endloop + endfacet + facet normal 0.756245 -0.489242 -0.434438 + outer loop + vertex -395.919 96.9056 207.947 + vertex -391.935 99.9314 211.475 + vertex -394.212 96.4226 211.463 + endloop + endfacet + facet normal 0.750571 -0.485513 -0.448241 + outer loop + vertex -391.935 99.9314 211.475 + vertex -390.201 99.4359 214.915 + vertex -394.212 96.4226 211.463 + endloop + endfacet + facet normal 0.749907 -0.493773 -0.440259 + outer loop + vertex -394.212 96.4226 211.463 + vertex -390.201 99.4359 214.915 + vertex -392.506 95.9276 214.924 + endloop + endfacet + facet normal 0.743622 -0.489683 -0.455232 + outer loop + vertex -390.201 99.4359 214.915 + vertex -388.469 98.9263 218.293 + vertex -392.506 95.9276 214.924 + endloop + endfacet + facet normal 0.743115 -0.496832 -0.44826 + outer loop + vertex -392.506 95.9276 214.924 + vertex -388.469 98.9263 218.293 + vertex -390.797 95.4216 218.318 + endloop + endfacet + facet normal 0.736723 -0.492694 -0.463133 + outer loop + vertex -388.469 98.9263 218.293 + vertex -386.729 98.4069 221.613 + vertex -390.797 95.4216 218.318 + endloop + endfacet + facet normal 0.736265 -0.500147 -0.455814 + outer loop + vertex -390.797 95.4216 218.318 + vertex -386.729 98.4069 221.613 + vertex -389.081 94.9053 221.655 + endloop + endfacet + facet normal 0.730406 -0.496373 -0.46917 + outer loop + vertex -386.729 98.4069 221.613 + vertex -384.98 97.88 224.893 + vertex -389.081 94.9053 221.655 + endloop + endfacet + facet normal 0.730186 -0.500579 -0.465027 + outer loop + vertex -389.081 94.9053 221.655 + vertex -384.98 97.88 224.893 + vertex -387.346 94.3705 224.956 + endloop + endfacet + facet normal 0.724675 -0.497081 -0.477238 + outer loop + vertex -384.98 97.88 224.893 + vertex -383.213 97.3387 228.139 + vertex -387.346 94.3705 224.956 + endloop + endfacet + facet normal 0.724383 -0.50377 -0.470622 + outer loop + vertex -387.346 94.3705 224.956 + vertex -383.213 97.3387 228.139 + vertex -385.602 93.8257 228.224 + endloop + endfacet + facet normal 0.718046 -0.499791 -0.484375 + outer loop + vertex -383.213 97.3387 228.139 + vertex -381.444 96.7872 231.331 + vertex -385.602 93.8257 228.224 + endloop + endfacet + facet normal 0.717886 -0.504853 -0.479337 + outer loop + vertex -385.602 93.8257 228.224 + vertex -381.444 96.7872 231.331 + vertex -383.848 93.2665 231.439 + endloop + endfacet + facet normal 0.711573 -0.500949 -0.49266 + outer loop + vertex -381.444 96.7872 231.331 + vertex -379.683 96.2277 234.443 + vertex -383.848 93.2665 231.439 + endloop + endfacet + facet normal 0.711436 -0.509038 -0.484499 + outer loop + vertex -383.848 93.2665 231.439 + vertex -379.683 96.2277 234.443 + vertex -382.114 92.7079 234.572 + endloop + endfacet + facet normal 0.704056 -0.504504 -0.499781 + outer loop + vertex -379.683 96.2277 234.443 + vertex -377.94 95.6659 237.467 + vertex -382.114 92.7079 234.572 + endloop + endfacet + facet normal 0.704056 -0.510626 -0.493524 + outer loop + vertex -382.114 92.7079 234.572 + vertex -377.94 95.6659 237.467 + vertex -380.388 92.1427 237.619 + endloop + endfacet + facet normal 0.69807 -0.506987 -0.50563 + outer loop + vertex -377.94 95.6659 237.467 + vertex -376.207 95.1029 240.423 + vertex -380.388 92.1427 237.619 + endloop + endfacet + facet normal 0.698126 -0.510446 -0.502061 + outer loop + vertex -380.388 92.1427 237.619 + vertex -376.207 95.1029 240.423 + vertex -378.664 91.5703 240.598 + endloop + endfacet + facet normal 0.690852 -0.506095 -0.516325 + outer loop + vertex -376.207 95.1029 240.423 + vertex -374.45 94.5208 243.344 + vertex -378.664 91.5703 240.598 + endloop + endfacet + facet normal 0.691035 -0.512553 -0.509667 + outer loop + vertex -378.664 91.5703 240.598 + vertex -374.45 94.5208 243.344 + vertex -376.925 90.9861 243.544 + endloop + endfacet + facet normal 0.68516 -0.509077 -0.520958 + outer loop + vertex -374.45 94.5208 243.344 + vertex -372.684 93.9324 246.243 + vertex -376.925 90.9861 243.544 + endloop + endfacet + facet normal 0.68527 -0.512007 -0.517933 + outer loop + vertex -376.925 90.9861 243.544 + vertex -372.684 93.9324 246.243 + vertex -375.162 90.3881 246.467 + endloop + endfacet + facet normal 0.678388 -0.508009 -0.53077 + outer loop + vertex -372.684 93.9324 246.243 + vertex -370.898 93.3304 249.101 + vertex -375.162 90.3881 246.467 + endloop + endfacet + facet normal 0.67873 -0.514741 -0.523801 + outer loop + vertex -375.162 90.3881 246.467 + vertex -370.898 93.3304 249.101 + vertex -373.393 89.7852 249.352 + endloop + endfacet + facet normal 0.671277 -0.510463 -0.537414 + outer loop + vertex -370.898 93.3304 249.101 + vertex -369.123 92.7318 251.886 + vertex -373.393 89.7852 249.352 + endloop + endfacet + facet normal 0.671508 -0.513741 -0.533991 + outer loop + vertex -373.393 89.7852 249.352 + vertex -369.123 92.7318 251.886 + vertex -371.621 89.1776 252.165 + endloop + endfacet + facet normal 0.666703 -0.511036 -0.542539 + outer loop + vertex -369.123 92.7318 251.886 + vertex -367.383 92.1495 254.574 + vertex -371.621 89.1776 252.165 + endloop + endfacet + facet normal 0.666822 -0.512258 -0.541239 + outer loop + vertex -371.621 89.1776 252.165 + vertex -367.383 92.1495 254.574 + vertex -369.875 88.5821 254.879 + endloop + endfacet + facet normal 0.660295 -0.508665 -0.552513 + outer loop + vertex -367.383 92.1495 254.574 + vertex -365.662 91.5738 257.16 + vertex -369.875 88.5821 254.879 + endloop + endfacet + facet normal 0.660758 -0.512338 -0.548551 + outer loop + vertex -369.875 88.5821 254.879 + vertex -365.662 91.5738 257.16 + vertex -368.16 88.0009 257.488 + endloop + endfacet + facet normal 0.652826 -0.508019 -0.561903 + outer loop + vertex -365.662 91.5738 257.16 + vertex -363.961 90.9975 259.657 + vertex -368.16 88.0009 257.488 + endloop + endfacet + facet normal 0.65322 -0.510598 -0.559101 + outer loop + vertex -368.16 88.0009 257.488 + vertex -363.961 90.9975 259.657 + vertex -366.46 87.4191 260.005 + endloop + endfacet + facet normal 0.646473 -0.506962 -0.570142 + outer loop + vertex -363.961 90.9975 259.657 + vertex -362.293 90.4126 262.068 + vertex -366.46 87.4191 260.005 + endloop + endfacet + facet normal 0.6464 -0.506551 -0.570591 + outer loop + vertex -366.46 87.4191 260.005 + vertex -362.293 90.4126 262.068 + vertex -364.78 86.8247 262.437 + endloop + endfacet + facet normal 0.637856 -0.502012 -0.584058 + outer loop + vertex -362.293 90.4126 262.068 + vertex -360.666 89.8177 264.357 + vertex -364.78 86.8247 262.437 + endloop + endfacet + facet normal 0.63846 -0.504826 -0.580965 + outer loop + vertex -364.78 86.8247 262.437 + vertex -360.666 89.8177 264.357 + vertex -363.151 86.2284 264.745 + endloop + endfacet + facet normal 0.635662 -0.503355 -0.585293 + outer loop + vertex -360.666 89.8177 264.357 + vertex -359.187 89.2938 266.414 + vertex -363.151 86.2284 264.745 + endloop + endfacet + facet normal 0.634611 -0.49966 -0.589583 + outer loop + vertex -363.151 86.2284 264.745 + vertex -359.187 89.2938 266.414 + vertex -361.649 85.6827 266.824 + endloop + endfacet + facet normal 0.636523 -0.500635 -0.586688 + outer loop + vertex -359.187 89.2938 266.414 + vertex -357.939 88.9153 268.091 + vertex -361.649 85.6827 266.824 + endloop + endfacet + facet normal 0.635178 -0.49747 -0.590823 + outer loop + vertex -361.649 85.6827 266.824 + vertex -357.939 88.9153 268.091 + vertex -360.396 85.273 268.516 + endloop + endfacet + facet normal 0.64349 -0.501604 -0.578199 + outer loop + vertex -357.939 88.9153 268.091 + vertex -357.03 88.7283 269.265 + vertex -360.396 85.273 268.516 + endloop + endfacet + facet normal 0.640244 -0.496767 -0.585927 + outer loop + vertex -360.396 85.273 268.516 + vertex -357.03 88.7283 269.265 + vertex -359.495 85.0461 269.693 + endloop + endfacet + facet normal 0.65128 -0.502178 -0.568904 + outer loop + vertex -357.03 88.7283 269.265 + vertex -356.522 88.6451 269.92 + vertex -359.495 85.0461 269.693 + endloop + endfacet + facet normal 0.634826 -0.486606 -0.600175 + outer loop + vertex -359.495 85.0461 269.693 + vertex -356.522 88.6451 269.92 + vertex -358.953 84.9342 270.357 + endloop + endfacet + facet normal 0.586942 -0.462771 -0.664336 + outer loop + vertex -356.522 88.6451 269.92 + vertex -356.379 88.4319 270.195 + vertex -358.953 84.9342 270.357 + endloop + endfacet + facet normal 0.611715 -0.479382 -0.629283 + outer loop + vertex -358.953 84.9342 270.357 + vertex -356.379 88.4319 270.195 + vertex -358.785 84.8009 270.622 + endloop + endfacet + facet normal 0.144027 -0.209142 -0.967221 + outer loop + vertex -356.379 88.4319 270.195 + vertex -356.564 87.914 270.279 + vertex -358.785 84.8009 270.622 + endloop + endfacet + facet normal 0.334002 -0.335194 -0.880958 + outer loop + vertex -358.785 84.8009 270.622 + vertex -356.564 87.914 270.279 + vertex -358.91 84.4751 270.698 + endloop + endfacet + facet normal 0.93662 -0.348069 -0.0398827 + outer loop + vertex -429.696 109.545 87.3957 + vertex -427.963 113.778 91.1476 + vertex -429.579 109.43 91.1346 + endloop + endfacet + facet normal 0.935046 -0.347391 -0.070767 + outer loop + vertex -427.963 113.778 91.1476 + vertex -427.732 113.64 94.8815 + vertex -429.579 109.43 91.1346 + endloop + endfacet + facet normal 0.934246 -0.350248 -0.0671624 + outer loop + vertex -429.579 109.43 91.1346 + vertex -427.732 113.64 94.8815 + vertex -429.356 109.309 94.8766 + endloop + endfacet + facet normal 0.932183 -0.349444 -0.0944678 + outer loop + vertex -427.732 113.64 94.8815 + vertex -427.411 113.498 98.5714 + vertex -429.356 109.309 94.8766 + endloop + endfacet + facet normal 0.931828 -0.35087 -0.0926648 + outer loop + vertex -429.356 109.309 94.8766 + vertex -427.411 113.498 98.5714 + vertex -429.036 109.181 98.5795 + endloop + endfacet + facet normal 0.929448 -0.350019 -0.116675 + outer loop + vertex -427.411 113.498 98.5714 + vertex -427.011 113.356 102.185 + vertex -429.036 109.181 98.5795 + endloop + endfacet + facet normal 0.929119 -0.351526 -0.114746 + outer loop + vertex -429.036 109.181 98.5795 + vertex -427.011 113.356 102.185 + vertex -428.637 109.053 102.196 + endloop + endfacet + facet normal 0.926361 -0.350539 -0.13776 + outer loop + vertex -427.011 113.356 102.185 + vertex -426.54 113.203 105.74 + vertex -428.637 109.053 102.196 + endloop + endfacet + facet normal 0.925993 -0.352475 -0.135275 + outer loop + vertex -428.637 109.053 102.196 + vertex -426.54 113.203 105.74 + vertex -428.169 108.919 105.75 + endloop + endfacet + facet normal 0.922898 -0.351352 -0.157514 + outer loop + vertex -426.54 113.203 105.74 + vertex -425.995 113.039 109.301 + vertex -428.169 108.919 105.75 + endloop + endfacet + facet normal 0.922679 -0.352665 -0.155856 + outer loop + vertex -428.169 108.919 105.75 + vertex -425.995 113.039 109.301 + vertex -427.625 108.764 109.323 + endloop + endfacet + facet normal 0.919537 -0.351569 -0.175645 + outer loop + vertex -425.995 113.039 109.301 + vertex -425.37 112.856 112.938 + vertex -427.625 108.764 109.323 + endloop + endfacet + facet normal 0.919493 -0.351867 -0.17528 + outer loop + vertex -427.625 108.764 109.323 + vertex -425.37 112.856 112.938 + vertex -426.996 108.584 112.984 + endloop + endfacet + facet normal 0.916384 -0.350872 -0.192687 + outer loop + vertex -425.37 112.856 112.938 + vertex -424.658 112.654 116.693 + vertex -426.996 108.584 112.984 + endloop + endfacet + facet normal 0.916334 -0.35125 -0.19224 + outer loop + vertex -426.996 108.584 112.984 + vertex -424.658 112.654 116.693 + vertex -426.279 108.385 116.765 + endloop + endfacet + facet normal 0.912935 -0.350248 -0.209467 + outer loop + vertex -424.658 112.654 116.693 + vertex -423.858 112.428 120.558 + vertex -426.279 108.385 116.765 + endloop + endfacet + facet normal 0.912691 -0.352221 -0.207209 + outer loop + vertex -426.279 108.385 116.765 + vertex -423.858 112.428 120.558 + vertex -425.48 108.176 120.642 + endloop + endfacet + facet normal 0.909126 -0.351191 -0.223951 + outer loop + vertex -423.858 112.428 120.558 + vertex -422.985 112.196 124.466 + vertex -425.48 108.176 120.642 + endloop + endfacet + facet normal 0.909098 -0.35145 -0.223661 + outer loop + vertex -425.48 108.176 120.642 + vertex -422.985 112.196 124.466 + vertex -424.604 107.946 124.563 + endloop + endfacet + facet normal 0.905487 -0.350431 -0.239358 + outer loop + vertex -422.985 112.196 124.466 + vertex -422.049 111.949 128.365 + vertex -424.604 107.946 124.563 + endloop + endfacet + facet normal 0.905401 -0.351344 -0.23834 + outer loop + vertex -424.604 107.946 124.563 + vertex -422.049 111.949 128.365 + vertex -423.67 107.707 128.461 + endloop + endfacet + facet normal 0.901449 -0.350199 -0.254462 + outer loop + vertex -422.049 111.949 128.365 + vertex -421.063 111.694 132.213 + vertex -423.67 107.707 128.461 + endloop + endfacet + facet normal 0.901258 -0.352683 -0.25169 + outer loop + vertex -423.67 107.707 128.461 + vertex -421.063 111.694 132.213 + vertex -422.692 107.468 132.3 + endloop + endfacet + facet normal 0.897048 -0.351397 -0.268003 + outer loop + vertex -421.063 111.694 132.213 + vertex -420.03 111.433 136.009 + vertex -422.692 107.468 132.3 + endloop + endfacet + facet normal 0.896951 -0.352977 -0.266245 + outer loop + vertex -422.692 107.468 132.3 + vertex -420.03 111.433 136.009 + vertex -421.664 107.215 136.099 + endloop + endfacet + facet normal 0.892892 -0.351723 -0.281133 + outer loop + vertex -420.03 111.433 136.009 + vertex -418.945 111.167 139.79 + vertex -421.664 107.215 136.099 + endloop + endfacet + facet normal 0.892792 -0.353789 -0.278847 + outer loop + vertex -421.664 107.215 136.099 + vertex -418.945 111.167 139.79 + vertex -420.583 106.956 139.889 + endloop + endfacet + facet normal 0.888691 -0.352532 -0.29317 + outer loop + vertex -418.945 111.167 139.79 + vertex -417.799 110.89 143.596 + vertex -420.583 106.956 139.889 + endloop + endfacet + facet normal 0.888603 -0.354773 -0.290724 + outer loop + vertex -420.583 106.956 139.889 + vertex -417.799 110.89 143.596 + vertex -419.441 106.686 143.709 + endloop + endfacet + facet normal 0.884481 -0.353535 -0.304478 + outer loop + vertex -417.799 110.89 143.596 + vertex -416.587 110.603 147.449 + vertex -419.441 106.686 143.709 + endloop + endfacet + facet normal 0.884391 -0.356201 -0.301618 + outer loop + vertex -419.441 106.686 143.709 + vertex -416.587 110.603 147.449 + vertex -418.234 106.407 147.576 + endloop + endfacet + facet normal 0.879842 -0.354857 -0.316155 + outer loop + vertex -416.587 110.603 147.449 + vertex -415.307 110.298 151.354 + vertex -418.234 106.407 147.576 + endloop + endfacet + facet normal 0.879791 -0.356729 -0.314187 + outer loop + vertex -418.234 106.407 147.576 + vertex -415.307 110.298 151.354 + vertex -416.958 106.103 151.496 + endloop + endfacet + facet normal 0.875812 -0.355575 -0.326373 + outer loop + vertex -415.307 110.298 151.354 + vertex -413.97 109.985 155.285 + vertex -416.958 106.103 151.496 + endloop + endfacet + facet normal 0.875748 -0.358562 -0.323262 + outer loop + vertex -416.958 106.103 151.496 + vertex -413.97 109.985 155.285 + vertex -415.628 105.797 155.436 + endloop + endfacet + facet normal 0.871096 -0.357218 -0.337026 + outer loop + vertex -413.97 109.985 155.285 + vertex -412.581 109.658 159.22 + vertex -415.628 105.797 155.436 + endloop + endfacet + facet normal 0.871044 -0.360755 -0.333374 + outer loop + vertex -415.628 105.797 155.436 + vertex -412.581 109.658 159.22 + vertex -414.253 105.481 159.373 + endloop + endfacet + facet normal 0.866205 -0.359326 -0.347238 + outer loop + vertex -412.581 109.658 159.22 + vertex -411.153 109.323 163.129 + vertex -414.253 105.481 159.373 + endloop + endfacet + facet normal 0.866185 -0.362423 -0.344055 + outer loop + vertex -414.253 105.481 159.373 + vertex -411.153 109.323 163.129 + vertex -412.838 105.149 163.284 + endloop + endfacet + facet normal 0.862026 -0.361174 -0.355618 + outer loop + vertex -411.153 109.323 163.129 + vertex -409.698 108.988 166.997 + vertex -412.838 105.149 163.284 + endloop + endfacet + facet normal 0.862033 -0.363012 -0.353724 + outer loop + vertex -412.838 105.149 163.284 + vertex -409.698 108.988 166.997 + vertex -411.39 104.81 167.161 + endloop + endfacet + facet normal 0.857176 -0.361557 -0.366778 + outer loop + vertex -409.698 108.988 166.997 + vertex -408.202 108.636 170.839 + vertex -411.39 104.81 167.161 + endloop + endfacet + facet normal 0.857242 -0.366879 -0.361298 + outer loop + vertex -411.39 104.81 167.161 + vertex -408.202 108.636 170.839 + vertex -409.914 104.473 171.005 + endloop + endfacet + facet normal 0.85246 -0.365418 -0.373874 + outer loop + vertex -408.202 108.636 170.839 + vertex -406.677 108.289 174.655 + vertex -409.914 104.473 171.005 + endloop + endfacet + facet normal 0.8525 -0.367403 -0.371833 + outer loop + vertex -409.914 104.473 171.005 + vertex -406.677 108.289 174.655 + vertex -408.394 104.12 174.84 + endloop + endfacet + facet normal 0.847986 -0.366052 -0.383308 + outer loop + vertex -406.677 108.289 174.655 + vertex -405.113 107.929 178.459 + vertex -408.394 104.12 174.84 + endloop + endfacet + facet normal 0.848089 -0.369724 -0.379538 + outer loop + vertex -408.394 104.12 174.84 + vertex -405.113 107.929 178.459 + vertex -406.842 103.766 178.652 + endloop + endfacet + facet normal 0.843668 -0.368397 -0.390522 + outer loop + vertex -405.113 107.929 178.459 + vertex -403.524 107.559 182.241 + vertex -406.842 103.766 178.652 + endloop + endfacet + facet normal 0.843784 -0.371797 -0.387036 + outer loop + vertex -406.842 103.766 178.652 + vertex -403.524 107.559 182.241 + vertex -405.267 103.404 182.433 + endloop + endfacet + facet normal 0.838352 -0.370127 -0.400216 + outer loop + vertex -403.524 107.559 182.241 + vertex -401.908 107.146 186.008 + vertex -405.267 103.404 182.433 + endloop + endfacet + facet normal 0.838528 -0.37502 -0.395259 + outer loop + vertex -405.267 103.404 182.433 + vertex -401.908 107.146 186.008 + vertex -403.673 103.016 186.182 + endloop + endfacet + facet normal 0.832384 -0.373008 -0.40988 + outer loop + vertex -401.908 107.146 186.008 + vertex -400.279 106.673 189.748 + vertex -403.673 103.016 186.182 + endloop + endfacet + facet normal 0.832596 -0.379311 -0.403617 + outer loop + vertex -403.673 103.016 186.182 + vertex -400.279 106.673 189.748 + vertex -402.063 102.594 189.901 + endloop + endfacet + facet normal 0.825625 -0.376877 -0.419889 + outer loop + vertex -400.279 106.673 189.748 + vertex -398.644 106.143 193.437 + vertex -402.063 102.594 189.901 + endloop + endfacet + facet normal 0.825874 -0.385284 -0.41169 + outer loop + vertex -402.063 102.594 189.901 + vertex -398.644 106.143 193.437 + vertex -400.419 102.154 193.61 + endloop + endfacet + facet normal 0.819426 -0.383054 -0.426392 + outer loop + vertex -398.644 106.143 193.437 + vertex -396.912 105.662 197.198 + vertex -400.419 102.154 193.61 + endloop + endfacet + facet normal 0.81956 -0.388887 -0.42082 + outer loop + vertex -400.419 102.154 193.61 + vertex -396.912 105.662 197.198 + vertex -398.741 101.693 197.304 + endloop + endfacet + facet normal 0.812915 -0.386228 -0.435886 + outer loop + vertex -396.912 105.662 197.198 + vertex -395.189 105.071 200.935 + vertex -398.741 101.693 197.304 + endloop + endfacet + facet normal 0.812996 -0.397707 -0.425284 + outer loop + vertex -398.741 101.693 197.304 + vertex -395.189 105.071 200.935 + vertex -397.063 101.247 200.929 + endloop + endfacet + facet normal 0.806681 -0.394591 -0.439959 + outer loop + vertex -395.189 105.071 200.935 + vertex -393.47 104.558 204.547 + vertex -397.063 101.247 200.929 + endloop + endfacet + facet normal 0.806689 -0.402062 -0.433128 + outer loop + vertex -397.063 101.247 200.929 + vertex -393.47 104.558 204.547 + vertex -395.368 100.82 204.483 + endloop + endfacet + facet normal 0.801563 -0.399256 -0.445075 + outer loop + vertex -393.47 104.558 204.547 + vertex -391.741 104.115 208.059 + vertex -395.368 100.82 204.483 + endloop + endfacet + facet normal 0.801589 -0.40475 -0.440038 + outer loop + vertex -395.368 100.82 204.483 + vertex -391.741 104.115 208.059 + vertex -393.657 100.391 207.993 + endloop + endfacet + facet normal 0.796305 -0.401818 -0.452151 + outer loop + vertex -391.741 104.115 208.059 + vertex -390.001 103.678 211.512 + vertex -393.657 100.391 207.993 + endloop + endfacet + facet normal 0.796366 -0.406664 -0.447688 + outer loop + vertex -393.657 100.391 207.993 + vertex -390.001 103.678 211.512 + vertex -391.935 99.9314 211.475 + endloop + endfacet + facet normal 0.790759 -0.403647 -0.460184 + outer loop + vertex -390.001 103.678 211.512 + vertex -388.257 103.206 214.923 + vertex -391.935 99.9314 211.475 + endloop + endfacet + facet normal 0.790835 -0.406869 -0.457206 + outer loop + vertex -391.935 99.9314 211.475 + vertex -388.257 103.206 214.923 + vertex -390.201 99.4359 214.915 + endloop + endfacet + facet normal 0.785029 -0.403848 -0.469719 + outer loop + vertex -388.257 103.206 214.923 + vertex -386.507 102.697 218.284 + vertex -390.201 99.4359 214.915 + endloop + endfacet + facet normal 0.785227 -0.409494 -0.464471 + outer loop + vertex -390.201 99.4359 214.915 + vertex -386.507 102.697 218.284 + vertex -388.469 98.9263 218.293 + endloop + endfacet + facet normal 0.779311 -0.406444 -0.476946 + outer loop + vertex -386.507 102.697 218.284 + vertex -384.754 102.177 221.592 + vertex -388.469 98.9263 218.293 + endloop + endfacet + facet normal 0.779512 -0.41092 -0.472764 + outer loop + vertex -388.469 98.9263 218.293 + vertex -384.754 102.177 221.592 + vertex -386.729 98.4069 221.613 + endloop + endfacet + facet normal 0.773753 -0.407968 -0.484632 + outer loop + vertex -384.754 102.177 221.592 + vertex -382.987 101.647 224.859 + vertex -386.729 98.4069 221.613 + endloop + endfacet + facet normal 0.774059 -0.413786 -0.47918 + outer loop + vertex -386.729 98.4069 221.613 + vertex -382.987 101.647 224.859 + vertex -384.98 97.88 224.893 + endloop + endfacet + facet normal 0.767594 -0.410483 -0.492243 + outer loop + vertex -382.987 101.647 224.859 + vertex -381.204 101.106 228.091 + vertex -384.98 97.88 224.893 + endloop + endfacet + facet normal 0.767916 -0.415841 -0.487219 + outer loop + vertex -384.98 97.88 224.893 + vertex -381.204 101.106 228.091 + vertex -383.213 97.3387 228.139 + endloop + endfacet + facet normal 0.762067 -0.412869 -0.498792 + outer loop + vertex -381.204 101.106 228.091 + vertex -379.422 100.559 231.266 + vertex -383.213 97.3387 228.139 + endloop + endfacet + facet normal 0.762375 -0.417223 -0.494681 + outer loop + vertex -383.213 97.3387 228.139 + vertex -379.422 100.559 231.266 + vertex -381.444 96.7872 231.331 + endloop + endfacet + facet normal 0.755909 -0.413971 -0.507177 + outer loop + vertex -379.422 100.559 231.266 + vertex -377.649 100.003 234.362 + vertex -381.444 96.7872 231.331 + endloop + endfacet + facet normal 0.75628 -0.418261 -0.503089 + outer loop + vertex -381.444 96.7872 231.331 + vertex -377.649 100.003 234.362 + vertex -379.683 96.2277 234.443 + endloop + endfacet + facet normal 0.750578 -0.415422 -0.513865 + outer loop + vertex -377.649 100.003 234.362 + vertex -375.9 99.4475 237.366 + vertex -379.683 96.2277 234.443 + endloop + endfacet + facet normal 0.750905 -0.418561 -0.510831 + outer loop + vertex -379.683 96.2277 234.443 + vertex -375.9 99.4475 237.366 + vertex -377.94 95.6659 237.467 + endloop + endfacet + facet normal 0.744602 -0.41547 -0.522448 + outer loop + vertex -375.9 99.4475 237.366 + vertex -374.154 98.8839 240.303 + vertex -377.94 95.6659 237.467 + endloop + endfacet + facet normal 0.745275 -0.421115 -0.516941 + outer loop + vertex -377.94 95.6659 237.467 + vertex -374.154 98.8839 240.303 + vertex -376.207 95.1029 240.423 + endloop + endfacet + facet normal 0.738489 -0.417819 -0.529208 + outer loop + vertex -374.154 98.8839 240.303 + vertex -372.399 98.3115 243.204 + vertex -376.207 95.1029 240.423 + endloop + endfacet + facet normal 0.73868 -0.419277 -0.527787 + outer loop + vertex -376.207 95.1029 240.423 + vertex -372.399 98.3115 243.204 + vertex -374.45 94.5208 243.344 + endloop + endfacet + facet normal 0.732876 -0.416512 -0.537968 + outer loop + vertex -372.399 98.3115 243.204 + vertex -370.62 97.7226 246.083 + vertex -374.45 94.5208 243.344 + endloop + endfacet + facet normal 0.733618 -0.421835 -0.532784 + outer loop + vertex -374.45 94.5208 243.344 + vertex -370.62 97.7226 246.083 + vertex -372.684 93.9324 246.243 + endloop + endfacet + facet normal 0.727495 -0.418945 -0.543356 + outer loop + vertex -370.62 97.7226 246.083 + vertex -368.839 97.1339 248.922 + vertex -372.684 93.9324 246.243 + endloop + endfacet + facet normal 0.727575 -0.419465 -0.542848 + outer loop + vertex -372.684 93.9324 246.243 + vertex -368.839 97.1339 248.922 + vertex -370.898 93.3304 249.101 + endloop + endfacet + facet normal 0.721622 -0.416712 -0.552822 + outer loop + vertex -368.839 97.1339 248.922 + vertex -367.06 96.5411 251.691 + vertex -370.898 93.3304 249.101 + endloop + endfacet + facet normal 0.722081 -0.41937 -0.550207 + outer loop + vertex -370.898 93.3304 249.101 + vertex -367.06 96.5411 251.691 + vertex -369.123 92.7318 251.886 + endloop + endfacet + facet normal 0.716875 -0.41699 -0.558757 + outer loop + vertex -367.06 96.5411 251.691 + vertex -365.312 95.966 254.362 + vertex -369.123 92.7318 251.886 + endloop + endfacet + facet normal 0.717473 -0.420033 -0.555702 + outer loop + vertex -369.123 92.7318 251.886 + vertex -365.312 95.966 254.362 + vertex -367.383 92.1495 254.574 + endloop + endfacet + facet normal 0.710279 -0.416771 -0.567279 + outer loop + vertex -365.312 95.966 254.362 + vertex -363.589 95.3965 256.939 + vertex -367.383 92.1495 254.574 + endloop + endfacet + facet normal 0.710594 -0.418187 -0.565841 + outer loop + vertex -367.383 92.1495 254.574 + vertex -363.589 95.3965 256.939 + vertex -365.662 91.5738 257.16 + endloop + endfacet + facet normal 0.704469 -0.415422 -0.575455 + outer loop + vertex -363.589 95.3965 256.939 + vertex -361.891 94.8278 259.428 + vertex -365.662 91.5738 257.16 + endloop + endfacet + facet normal 0.704426 -0.415247 -0.575634 + outer loop + vertex -365.662 91.5738 257.16 + vertex -361.891 94.8278 259.428 + vertex -363.961 90.9975 259.657 + endloop + endfacet + facet normal 0.697113 -0.411963 -0.586788 + outer loop + vertex -361.891 94.8278 259.428 + vertex -360.216 94.2383 261.832 + vertex -363.961 90.9975 259.657 + endloop + endfacet + facet normal 0.697973 -0.415163 -0.583501 + outer loop + vertex -363.961 90.9975 259.657 + vertex -360.216 94.2383 261.832 + vertex -362.293 90.4126 262.068 + endloop + endfacet + facet normal 0.690071 -0.411601 -0.595304 + outer loop + vertex -360.216 94.2383 261.832 + vertex -358.604 93.6448 264.11 + vertex -362.293 90.4126 262.068 + endloop + endfacet + facet normal 0.689595 -0.410025 -0.59694 + outer loop + vertex -362.293 90.4126 262.068 + vertex -358.604 93.6448 264.11 + vertex -360.666 89.8177 264.357 + endloop + endfacet + facet normal 0.686598 -0.408692 -0.601294 + outer loop + vertex -358.604 93.6448 264.11 + vertex -357.127 93.1158 266.157 + vertex -360.666 89.8177 264.357 + endloop + endfacet + facet normal 0.687392 -0.41084 -0.598918 + outer loop + vertex -360.666 89.8177 264.357 + vertex -357.127 93.1158 266.157 + vertex -359.187 89.2938 266.414 + endloop + endfacet + facet normal 0.686083 -0.410262 -0.600812 + outer loop + vertex -357.127 93.1158 266.157 + vertex -355.885 92.7534 267.823 + vertex -359.187 89.2938 266.414 + endloop + endfacet + facet normal 0.685438 -0.408995 -0.60241 + outer loop + vertex -359.187 89.2938 266.414 + vertex -355.885 92.7534 267.823 + vertex -357.939 88.9153 268.091 + endloop + endfacet + facet normal 0.696708 -0.413873 -0.585924 + outer loop + vertex -355.885 92.7534 267.823 + vertex -354.998 92.6155 268.974 + vertex -357.939 88.9153 268.091 + endloop + endfacet + facet normal 0.690289 -0.405616 -0.599147 + outer loop + vertex -357.939 88.9153 268.091 + vertex -354.998 92.6155 268.974 + vertex -357.03 88.7283 269.265 + endloop + endfacet + facet normal 0.700031 -0.409645 -0.584933 + outer loop + vertex -354.998 92.6155 268.974 + vertex -354.482 92.5735 269.621 + vertex -357.03 88.7283 269.265 + endloop + endfacet + facet normal 0.69623 -0.406507 -0.591621 + outer loop + vertex -357.03 88.7283 269.265 + vertex -354.482 92.5735 269.621 + vertex -356.522 88.6451 269.92 + endloop + endfacet + facet normal 0.663461 -0.392932 -0.636729 + outer loop + vertex -354.482 92.5735 269.621 + vertex -354.354 92.3629 269.884 + vertex -356.522 88.6451 269.92 + endloop + endfacet + facet normal 0.657858 -0.38974 -0.644457 + outer loop + vertex -356.522 88.6451 269.92 + vertex -354.354 92.3629 269.884 + vertex -356.379 88.4319 270.195 + endloop + endfacet + facet normal 0.180307 -0.16938 -0.968917 + outer loop + vertex -354.354 92.3629 269.884 + vertex -354.658 91.5128 269.976 + vertex -356.379 88.4319 270.195 + endloop + endfacet + facet normal 0.39975 -0.285023 -0.871184 + outer loop + vertex -356.379 88.4319 270.195 + vertex -354.658 91.5128 269.976 + vertex -356.564 87.914 270.279 + endloop + endfacet + facet normal 0.919116 -0.299789 -0.255643 + outer loop + vertex -422.049 111.949 128.365 + vertex -419.819 115.92 131.728 + vertex -421.063 111.694 132.213 + endloop + endfacet + facet normal 0.917093 -0.299989 -0.262578 + outer loop + vertex -419.819 115.92 131.728 + vertex -418.457 116.523 135.795 + vertex -421.063 111.694 132.213 + endloop + endfacet + facet normal 0.916801 -0.29471 -0.269483 + outer loop + vertex -421.063 111.694 132.213 + vertex -418.457 116.523 135.795 + vertex -420.03 111.433 136.009 + endloop + endfacet + facet normal 0.911375 -0.293821 -0.288208 + outer loop + vertex -418.457 116.523 135.795 + vertex -417.707 115.39 139.323 + vertex -420.03 111.433 136.009 + endloop + endfacet + facet normal 0.911564 -0.298508 -0.282744 + outer loop + vertex -420.03 111.433 136.009 + vertex -417.707 115.39 139.323 + vertex -418.945 111.167 139.79 + endloop + endfacet + facet normal 0.909453 -0.29862 -0.289348 + outer loop + vertex -417.707 115.39 139.323 + vertex -416.222 115.97 143.391 + vertex -418.945 111.167 139.79 + endloop + endfacet + facet normal 0.909081 -0.294126 -0.295061 + outer loop + vertex -418.945 111.167 139.79 + vertex -416.222 115.97 143.391 + vertex -417.799 110.89 143.596 + endloop + endfacet + facet normal 0.903187 -0.293043 -0.313655 + outer loop + vertex -416.222 115.97 143.391 + vertex -415.357 114.815 146.962 + vertex -417.799 110.89 143.596 + endloop + endfacet + facet normal 0.903557 -0.299447 -0.306456 + outer loop + vertex -417.799 110.89 143.596 + vertex -415.357 114.815 146.962 + vertex -416.587 110.603 147.449 + endloop + endfacet + facet normal 0.901557 -0.299529 -0.312215 + outer loop + vertex -415.357 114.815 146.962 + vertex -413.734 115.371 151.115 + vertex -416.587 110.603 147.449 + endloop + endfacet + facet normal 0.90106 -0.294491 -0.31838 + outer loop + vertex -416.587 110.603 147.449 + vertex -413.734 115.371 151.115 + vertex -415.307 110.298 151.354 + endloop + endfacet + facet normal 0.894739 -0.293394 -0.336694 + outer loop + vertex -413.734 115.371 151.115 + vertex -412.747 114.19 154.765 + vertex -415.307 110.298 151.354 + endloop + endfacet + facet normal 0.895272 -0.300798 -0.328646 + outer loop + vertex -415.307 110.298 151.354 + vertex -412.747 114.19 154.765 + vertex -413.97 109.985 155.285 + endloop + endfacet + facet normal 0.893555 -0.300864 -0.333227 + outer loop + vertex -412.747 114.19 154.765 + vertex -411.007 114.725 158.949 + vertex -413.97 109.985 155.285 + endloop + endfacet + facet normal 0.892929 -0.295541 -0.339606 + outer loop + vertex -413.97 109.985 155.285 + vertex -411.007 114.725 158.949 + vertex -412.581 109.658 159.22 + endloop + endfacet + facet normal 0.886131 -0.294407 -0.357905 + outer loop + vertex -411.007 114.725 158.949 + vertex -409.93 113.526 162.602 + vertex -412.581 109.658 159.22 + endloop + endfacet + facet normal 0.88682 -0.301933 -0.349838 + outer loop + vertex -412.581 109.658 159.22 + vertex -409.93 113.526 162.602 + vertex -411.153 109.323 163.129 + endloop + endfacet + facet normal 0.885387 -0.301965 -0.353421 + outer loop + vertex -409.93 113.526 162.602 + vertex -408.106 114.045 166.728 + vertex -411.153 109.323 163.129 + endloop + endfacet + facet normal 0.884767 -0.297567 -0.358666 + outer loop + vertex -411.153 109.323 163.129 + vertex -408.106 114.045 166.728 + vertex -409.698 108.988 166.997 + endloop + endfacet + facet normal 0.87748 -0.296257 -0.377174 + outer loop + vertex -408.106 114.045 166.728 + vertex -406.971 112.84 170.316 + vertex -409.698 108.988 166.997 + endloop + endfacet + facet normal 0.878274 -0.303296 -0.369657 + outer loop + vertex -409.698 108.988 166.997 + vertex -406.971 112.84 170.316 + vertex -408.202 108.636 170.839 + endloop + endfacet + facet normal 0.877294 -0.303297 -0.371976 + outer loop + vertex -406.971 112.84 170.316 + vertex -405.073 113.343 174.381 + vertex -408.202 108.636 170.839 + endloop + endfacet + facet normal 0.876543 -0.29869 -0.377434 + outer loop + vertex -408.202 108.636 170.839 + vertex -405.073 113.343 174.381 + vertex -406.677 108.289 174.655 + endloop + endfacet + facet normal 0.869434 -0.297363 -0.394537 + outer loop + vertex -405.073 113.343 174.381 + vertex -403.879 112.129 177.928 + vertex -406.677 108.289 174.655 + endloop + endfacet + facet normal 0.870396 -0.304725 -0.386721 + outer loop + vertex -406.677 108.289 174.655 + vertex -403.879 112.129 177.928 + vertex -405.113 107.929 178.459 + endloop + endfacet + facet normal 0.869204 -0.304713 -0.389403 + outer loop + vertex -403.879 112.129 177.928 + vertex -401.906 112.589 181.971 + vertex -405.113 107.929 178.459 + endloop + endfacet + facet normal 0.86846 -0.300513 -0.394296 + outer loop + vertex -405.113 107.929 178.459 + vertex -401.906 112.589 181.971 + vertex -403.524 107.559 182.241 + endloop + endfacet + facet normal 0.859987 -0.298828 -0.413672 + outer loop + vertex -401.906 112.589 181.971 + vertex -400.648 111.318 185.505 + vertex -403.524 107.559 182.241 + endloop + endfacet + facet normal 0.861352 -0.308828 -0.403357 + outer loop + vertex -403.524 107.559 182.241 + vertex -400.648 111.318 185.505 + vertex -401.908 107.146 186.008 + endloop + endfacet + facet normal 0.85954 -0.308753 -0.407263 + outer loop + vertex -400.648 111.318 185.505 + vertex -398.603 111.659 189.563 + vertex -401.908 107.146 186.008 + endloop + endfacet + facet normal 0.858708 -0.303933 -0.412608 + outer loop + vertex -401.908 107.146 186.008 + vertex -398.603 111.659 189.563 + vertex -400.279 106.673 189.748 + endloop + endfacet + facet normal 0.849299 -0.301536 -0.433322 + outer loop + vertex -398.603 111.659 189.563 + vertex -397.341 110.249 193.018 + vertex -400.279 106.673 189.748 + endloop + endfacet + facet normal 0.850816 -0.313218 -0.421909 + outer loop + vertex -400.279 106.673 189.748 + vertex -397.341 110.249 193.018 + vertex -398.644 106.143 193.437 + endloop + endfacet + facet normal 0.847408 -0.312858 -0.428974 + outer loop + vertex -397.341 110.249 193.018 + vertex -395.422 110.374 196.717 + vertex -398.644 106.143 193.437 + endloop + endfacet + facet normal 0.847216 -0.311849 -0.430088 + outer loop + vertex -398.644 106.143 193.437 + vertex -395.422 110.374 196.717 + vertex -396.912 105.662 197.198 + endloop + endfacet + facet normal 0.838393 -0.310858 -0.447732 + outer loop + vertex -395.422 110.374 196.717 + vertex -393.634 109.477 200.687 + vertex -396.912 105.662 197.198 + endloop + endfacet + facet normal 0.839751 -0.320978 -0.437941 + outer loop + vertex -396.912 105.662 197.198 + vertex -393.634 109.477 200.687 + vertex -395.189 105.071 200.935 + endloop + endfacet + facet normal 0.832958 -0.319364 -0.451871 + outer loop + vertex -393.634 109.477 200.687 + vertex -391.881 108.732 204.446 + vertex -395.189 105.071 200.935 + endloop + endfacet + facet normal 0.833973 -0.328277 -0.443534 + outer loop + vertex -395.189 105.071 200.935 + vertex -391.881 108.732 204.446 + vertex -393.47 104.558 204.547 + endloop + endfacet + facet normal 0.829163 -0.326689 -0.453611 + outer loop + vertex -391.881 108.732 204.446 + vertex -390.137 108.198 208.018 + vertex -393.47 104.558 204.547 + endloop + endfacet + facet normal 0.829583 -0.330348 -0.450179 + outer loop + vertex -393.47 104.558 204.547 + vertex -390.137 108.198 208.018 + vertex -391.741 104.115 208.059 + endloop + endfacet + facet normal 0.824576 -0.328484 -0.460622 + outer loop + vertex -390.137 108.198 208.018 + vertex -388.383 107.749 211.478 + vertex -391.741 104.115 208.059 + endloop + endfacet + facet normal 0.824961 -0.33159 -0.457698 + outer loop + vertex -391.741 104.115 208.059 + vertex -388.383 107.749 211.478 + vertex -390.001 103.678 211.512 + endloop + endfacet + facet normal 0.820121 -0.329748 -0.467619 + outer loop + vertex -388.383 107.749 211.478 + vertex -386.63 107.302 214.867 + vertex -390.001 103.678 211.512 + endloop + endfacet + facet normal 0.820431 -0.332056 -0.465437 + outer loop + vertex -390.001 103.678 211.512 + vertex -386.63 107.302 214.867 + vertex -388.257 103.206 214.923 + endloop + endfacet + facet normal 0.814203 -0.329752 -0.477846 + outer loop + vertex -386.63 107.302 214.867 + vertex -384.868 106.806 218.212 + vertex -388.257 103.206 214.923 + endloop + endfacet + facet normal 0.814717 -0.333289 -0.474505 + outer loop + vertex -388.257 103.206 214.923 + vertex -384.868 106.806 218.212 + vertex -386.507 102.697 218.284 + endloop + endfacet + facet normal 0.80983 -0.331507 -0.484023 + outer loop + vertex -384.868 106.806 218.212 + vertex -383.11 106.292 221.505 + vertex -386.507 102.697 218.284 + endloop + endfacet + facet normal 0.810185 -0.333775 -0.481866 + outer loop + vertex -386.507 102.697 218.284 + vertex -383.11 106.292 221.505 + vertex -384.754 102.177 221.592 + endloop + endfacet + facet normal 0.804679 -0.331797 -0.492345 + outer loop + vertex -383.11 106.292 221.505 + vertex -381.336 105.762 224.762 + vertex -384.754 102.177 221.592 + endloop + endfacet + facet normal 0.80514 -0.334569 -0.489707 + outer loop + vertex -384.754 102.177 221.592 + vertex -381.336 105.762 224.762 + vertex -382.987 101.647 224.859 + endloop + endfacet + facet normal 0.799643 -0.332606 -0.499944 + outer loop + vertex -381.336 105.762 224.762 + vertex -379.547 105.221 227.984 + vertex -382.987 101.647 224.859 + endloop + endfacet + facet normal 0.800085 -0.33512 -0.497553 + outer loop + vertex -382.987 101.647 224.859 + vertex -379.547 105.221 227.984 + vertex -381.204 101.106 228.091 + endloop + endfacet + facet normal 0.794745 -0.333223 -0.507289 + outer loop + vertex -379.547 105.221 227.984 + vertex -377.754 104.674 231.153 + vertex -381.204 101.106 228.091 + endloop + endfacet + facet normal 0.79533 -0.336358 -0.504295 + outer loop + vertex -381.204 101.106 228.091 + vertex -377.754 104.674 231.153 + vertex -379.422 100.559 231.266 + endloop + endfacet + facet normal 0.789207 -0.334178 -0.515245 + outer loop + vertex -377.754 104.674 231.153 + vertex -375.973 104.118 234.241 + vertex -379.422 100.559 231.266 + endloop + endfacet + facet normal 0.789741 -0.336826 -0.512696 + outer loop + vertex -379.422 100.559 231.266 + vertex -375.973 104.118 234.241 + vertex -377.649 100.003 234.362 + endloop + endfacet + facet normal 0.784997 -0.335136 -0.521021 + outer loop + vertex -375.973 104.118 234.241 + vertex -374.222 103.57 237.232 + vertex -377.649 100.003 234.362 + endloop + endfacet + facet normal 0.785334 -0.336661 -0.519529 + outer loop + vertex -377.649 100.003 234.362 + vertex -374.222 103.57 237.232 + vertex -375.9 99.4475 237.366 + endloop + endfacet + facet normal 0.77955 -0.33463 -0.529456 + outer loop + vertex -374.222 103.57 237.232 + vertex -372.477 103.013 240.153 + vertex -375.9 99.4475 237.366 + endloop + endfacet + facet normal 0.779866 -0.33595 -0.528155 + outer loop + vertex -375.9 99.4475 237.366 + vertex -372.477 103.013 240.153 + vertex -374.154 98.8839 240.303 + endloop + endfacet + facet normal 0.773679 -0.333815 -0.538506 + outer loop + vertex -372.477 103.013 240.153 + vertex -370.717 102.438 243.039 + vertex -374.154 98.8839 240.303 + endloop + endfacet + facet normal 0.774538 -0.337252 -0.535119 + outer loop + vertex -374.154 98.8839 240.303 + vertex -370.717 102.438 243.039 + vertex -372.399 98.3115 243.204 + endloop + endfacet + facet normal 0.76916 -0.335413 -0.543958 + outer loop + vertex -370.717 102.438 243.039 + vertex -368.943 101.861 245.902 + vertex -372.399 98.3115 243.204 + endloop + endfacet + facet normal 0.769191 -0.335533 -0.543841 + outer loop + vertex -372.399 98.3115 243.204 + vertex -368.943 101.861 245.902 + vertex -370.62 97.7226 246.083 + endloop + endfacet + facet normal 0.76403 -0.333804 -0.552116 + outer loop + vertex -368.943 101.861 245.902 + vertex -367.153 101.274 248.733 + vertex -370.62 97.7226 246.083 + endloop + endfacet + facet normal 0.764727 -0.336369 -0.54959 + outer loop + vertex -370.62 97.7226 246.083 + vertex -367.153 101.274 248.733 + vertex -368.839 97.1339 248.922 + endloop + endfacet + facet normal 0.759523 -0.334625 -0.557809 + outer loop + vertex -367.153 101.274 248.733 + vertex -365.377 100.7 251.496 + vertex -368.839 97.1339 248.922 + endloop + endfacet + facet normal 0.75915 -0.333344 -0.559082 + outer loop + vertex -368.839 97.1339 248.922 + vertex -365.377 100.7 251.496 + vertex -367.06 96.5411 251.691 + endloop + endfacet + facet normal 0.753623 -0.331505 -0.567588 + outer loop + vertex -365.377 100.7 251.496 + vertex -363.614 100.124 254.174 + vertex -367.06 96.5411 251.691 + endloop + endfacet + facet normal 0.754326 -0.333739 -0.565341 + outer loop + vertex -367.06 96.5411 251.691 + vertex -363.614 100.124 254.174 + vertex -365.312 95.966 254.362 + endloop + endfacet + facet normal 0.747911 -0.33156 -0.575062 + outer loop + vertex -363.614 100.124 254.174 + vertex -361.879 99.5584 256.757 + vertex -365.312 95.966 254.362 + endloop + endfacet + facet normal 0.748245 -0.33255 -0.574056 + outer loop + vertex -365.312 95.966 254.362 + vertex -361.879 99.5584 256.757 + vertex -363.589 95.3965 256.939 + endloop + endfacet + facet normal 0.742871 -0.330691 -0.582054 + outer loop + vertex -361.879 99.5584 256.757 + vertex -360.174 98.9954 259.253 + vertex -363.589 95.3965 256.939 + endloop + endfacet + facet normal 0.742814 -0.330533 -0.582216 + outer loop + vertex -363.589 95.3965 256.939 + vertex -360.174 98.9954 259.253 + vertex -361.891 94.8278 259.428 + endloop + endfacet + facet normal 0.735357 -0.327915 -0.593061 + outer loop + vertex -360.174 98.9954 259.253 + vertex -358.492 98.4056 261.665 + vertex -361.891 94.8278 259.428 + endloop + endfacet + facet normal 0.735414 -0.328066 -0.592907 + outer loop + vertex -361.891 94.8278 259.428 + vertex -358.492 98.4056 261.665 + vertex -360.216 94.2383 261.832 + endloop + endfacet + facet normal 0.730705 -0.326387 -0.599618 + outer loop + vertex -358.492 98.4056 261.665 + vertex -356.885 97.8142 263.944 + vertex -360.216 94.2383 261.832 + endloop + endfacet + facet normal 0.73013 -0.32499 -0.601076 + outer loop + vertex -360.216 94.2383 261.832 + vertex -356.885 97.8142 263.944 + vertex -358.604 93.6448 264.11 + endloop + endfacet + facet normal 0.726203 -0.323589 -0.606563 + outer loop + vertex -356.885 97.8142 263.944 + vertex -355.416 97.2747 265.991 + vertex -358.604 93.6448 264.11 + endloop + endfacet + facet normal 0.72583 -0.322818 -0.60742 + outer loop + vertex -358.604 93.6448 264.11 + vertex -355.416 97.2747 265.991 + vertex -357.127 93.1158 266.157 + endloop + endfacet + facet normal 0.725715 -0.322777 -0.607579 + outer loop + vertex -355.416 97.2747 265.991 + vertex -354.185 96.9058 267.657 + vertex -357.127 93.1158 266.157 + endloop + endfacet + facet normal 0.72451 -0.320877 -0.610019 + outer loop + vertex -357.127 93.1158 266.157 + vertex -354.185 96.9058 267.657 + vertex -355.885 92.7534 267.823 + endloop + endfacet + facet normal 0.73066 -0.323053 -0.601475 + outer loop + vertex -354.185 96.9058 267.657 + vertex -353.294 96.7769 268.809 + vertex -355.885 92.7534 267.823 + endloop + endfacet + facet normal 0.730766 -0.323168 -0.601286 + outer loop + vertex -355.885 92.7534 267.823 + vertex -353.294 96.7769 268.809 + vertex -354.998 92.6155 268.974 + endloop + endfacet + facet normal 0.728564 -0.322388 -0.604368 + outer loop + vertex -353.294 96.7769 268.809 + vertex -352.799 96.7151 269.439 + vertex -354.998 92.6155 268.974 + endloop + endfacet + facet normal 0.729526 -0.323078 -0.602837 + outer loop + vertex -354.998 92.6155 268.974 + vertex -352.799 96.7151 269.439 + vertex -354.482 92.5735 269.621 + endloop + endfacet + facet normal 0.67085 -0.302503 -0.677091 + outer loop + vertex -352.799 96.7151 269.439 + vertex -352.658 96.4785 269.684 + vertex -354.482 92.5735 269.621 + endloop + endfacet + facet normal 0.720554 -0.326787 -0.611566 + outer loop + vertex -354.482 92.5735 269.621 + vertex -352.658 96.4785 269.684 + vertex -354.354 92.3629 269.884 + endloop + endfacet + facet normal 0.200728 -0.129978 -0.970986 + outer loop + vertex -352.658 96.4785 269.684 + vertex -352.859 95.7808 269.736 + vertex -354.354 92.3629 269.884 + endloop + endfacet + facet normal 0.601619 -0.29547 -0.742127 + outer loop + vertex -354.354 92.3629 269.884 + vertex -352.859 95.7808 269.736 + vertex -354.658 91.5128 269.976 + endloop + endfacet + facet normal 0.91909 -0.295697 -0.260456 + outer loop + vertex -420.477 117.047 128.125 + vertex -419.819 115.92 131.728 + vertex -422.049 111.949 128.365 + endloop + endfacet + facet normal 0.92431 -0.296366 -0.240454 + outer loop + vertex -422.985 112.196 124.466 + vertex -420.477 117.047 128.125 + vertex -422.049 111.949 128.365 + endloop + endfacet + facet normal 0.924382 -0.301426 -0.233795 + outer loop + vertex -421.729 116.43 123.973 + vertex -420.477 117.047 128.125 + vertex -422.985 112.196 124.466 + endloop + endfacet + facet normal 0.926699 -0.301077 -0.224903 + outer loop + vertex -423.858 112.428 120.558 + vertex -421.729 116.43 123.973 + vertex -422.985 112.196 124.466 + endloop + endfacet + facet normal 0.92682 -0.297126 -0.229609 + outer loop + vertex -422.27 117.534 120.358 + vertex -421.729 116.43 123.973 + vertex -423.858 112.428 120.558 + endloop + endfacet + facet normal 0.931225 -0.297734 -0.210175 + outer loop + vertex -424.658 112.654 116.693 + vertex -422.27 117.534 120.358 + vertex -423.858 112.428 120.558 + endloop + endfacet + facet normal 0.931099 -0.303046 -0.20302 + outer loop + vertex -423.373 116.89 116.26 + vertex -422.27 117.534 120.358 + vertex -424.658 112.654 116.693 + endloop + endfacet + facet normal 0.933272 -0.302711 -0.19331 + outer loop + vertex -425.37 112.856 112.938 + vertex -423.373 116.89 116.26 + vertex -424.658 112.654 116.693 + endloop + endfacet + facet normal 0.933527 -0.298435 -0.198655 + outer loop + vertex -423.762 117.969 112.814 + vertex -423.373 116.89 116.26 + vertex -425.37 112.856 112.938 + endloop + endfacet + facet normal 0.937781 -0.299232 -0.176147 + outer loop + vertex -425.995 113.039 109.301 + vertex -423.762 117.969 112.814 + vertex -425.37 112.856 112.938 + endloop + endfacet + facet normal 0.937513 -0.303967 -0.169332 + outer loop + vertex -424.687 117.283 108.921 + vertex -423.762 117.969 112.814 + vertex -425.995 113.039 109.301 + endloop + endfacet + facet normal 0.939632 -0.303595 -0.157865 + outer loop + vertex -426.54 113.203 105.74 + vertex -424.687 117.283 108.921 + vertex -425.995 113.039 109.301 + endloop + endfacet + facet normal 0.939977 -0.299892 -0.162814 + outer loop + vertex -424.925 118.336 105.612 + vertex -424.687 117.283 108.921 + vertex -426.54 113.203 105.74 + endloop + endfacet + facet normal 0.943769 -0.300466 -0.137915 + outer loop + vertex -427.011 113.356 102.185 + vertex -424.925 118.336 105.612 + vertex -426.54 113.203 105.74 + endloop + endfacet + facet normal 0.943288 -0.30506 -0.130946 + outer loop + vertex -425.688 117.617 101.788 + vertex -424.925 118.336 105.612 + vertex -427.011 113.356 102.185 + endloop + endfacet + facet normal 0.95327 -0.267748 -0.139955 + outer loop + vertex -425.688 117.617 101.788 + vertex -423.419 124.64 103.806 + vertex -424.925 118.336 105.612 + endloop + endfacet + facet normal 0.949665 -0.271543 -0.156208 + outer loop + vertex -423.419 124.64 103.806 + vertex -422.333 124.269 111.052 + vertex -424.925 118.336 105.612 + endloop + endfacet + facet normal 0.949547 -0.272725 -0.154862 + outer loop + vertex -424.687 117.283 108.921 + vertex -424.925 118.336 105.612 + vertex -422.333 124.269 111.052 + endloop + endfacet + facet normal 0.947608 -0.264824 -0.178629 + outer loop + vertex -424.687 117.283 108.921 + vertex -422.333 124.269 111.052 + vertex -423.762 117.969 112.814 + endloop + endfacet + facet normal 0.943949 -0.267952 -0.192775 + outer loop + vertex -422.333 124.269 111.052 + vertex -420.94 123.846 118.464 + vertex -423.762 117.969 112.814 + endloop + endfacet + facet normal 0.943828 -0.269761 -0.190833 + outer loop + vertex -423.373 116.89 116.26 + vertex -423.762 117.969 112.814 + vertex -420.94 123.846 118.464 + endloop + endfacet + facet normal 0.941407 -0.262134 -0.212222 + outer loop + vertex -423.373 116.89 116.26 + vertex -420.94 123.846 118.464 + vertex -422.27 117.534 120.358 + endloop + endfacet + facet normal 0.937712 -0.265064 -0.224581 + outer loop + vertex -420.94 123.846 118.464 + vertex -419.243 123.369 126.112 + vertex -422.27 117.534 120.358 + endloop + endfacet + facet normal 0.937624 -0.267419 -0.222147 + outer loop + vertex -421.729 116.43 123.973 + vertex -422.27 117.534 120.358 + vertex -419.243 123.369 126.112 + endloop + endfacet + facet normal 0.934556 -0.25988 -0.243037 + outer loop + vertex -421.729 116.43 123.973 + vertex -419.243 123.369 126.112 + vertex -420.477 117.047 128.125 + endloop + endfacet + facet normal 0.930687 -0.262774 -0.254502 + outer loop + vertex -419.243 123.369 126.112 + vertex -417.284 122.851 133.81 + vertex -420.477 117.047 128.125 + endloop + endfacet + facet normal 0.93068 -0.264439 -0.252798 + outer loop + vertex -419.819 115.92 131.728 + vertex -420.477 117.047 128.125 + vertex -417.284 122.851 133.81 + endloop + endfacet + facet normal 0.927175 -0.257304 -0.27229 + outer loop + vertex -419.819 115.92 131.728 + vertex -417.284 122.851 133.81 + vertex -418.457 116.523 135.795 + endloop + endfacet + facet normal 0.923187 -0.259957 -0.283104 + outer loop + vertex -417.284 122.851 133.81 + vertex -415.095 122.296 141.457 + vertex -418.457 116.523 135.795 + endloop + endfacet + facet normal 0.923246 -0.26241 -0.280637 + outer loop + vertex -417.707 115.39 139.323 + vertex -418.457 116.523 135.795 + vertex -415.095 122.296 141.457 + endloop + endfacet + facet normal 0.919427 -0.255238 -0.299178 + outer loop + vertex -417.707 115.39 139.323 + vertex -415.095 122.296 141.457 + vertex -416.222 115.97 143.391 + endloop + endfacet + facet normal 0.915519 -0.257551 -0.309018 + outer loop + vertex -415.095 122.296 141.457 + vertex -412.669 121.701 149.141 + vertex -416.222 115.97 143.391 + endloop + endfacet + facet normal 0.915646 -0.260506 -0.306151 + outer loop + vertex -415.357 114.815 146.962 + vertex -416.222 115.97 143.391 + vertex -412.669 121.701 149.141 + endloop + endfacet + facet normal 0.911921 -0.253918 -0.322374 + outer loop + vertex -415.357 114.815 146.962 + vertex -412.669 121.701 149.141 + vertex -413.734 115.371 151.115 + endloop + endfacet + facet normal 0.907801 -0.256235 -0.332026 + outer loop + vertex -412.669 121.701 149.141 + vertex -410.006 121.064 156.913 + vertex -413.734 115.371 151.115 + endloop + endfacet + facet normal 0.907979 -0.259216 -0.329214 + outer loop + vertex -412.747 114.19 154.765 + vertex -413.734 115.371 151.115 + vertex -410.006 121.064 156.913 + endloop + endfacet + facet normal 0.904273 -0.253187 -0.343783 + outer loop + vertex -412.747 114.19 154.765 + vertex -410.006 121.064 156.913 + vertex -411.007 114.725 158.949 + endloop + endfacet + facet normal 0.900073 -0.25548 -0.352985 + outer loop + vertex -410.006 121.064 156.913 + vertex -407.147 120.392 164.69 + vertex -411.007 114.725 158.949 + endloop + endfacet + facet normal 0.900304 -0.258394 -0.350264 + outer loop + vertex -409.93 113.526 162.602 + vertex -411.007 114.725 158.949 + vertex -407.147 120.392 164.69 + endloop + endfacet + facet normal 0.896336 -0.252462 -0.364479 + outer loop + vertex -409.93 113.526 162.602 + vertex -407.147 120.392 164.69 + vertex -408.106 114.045 166.728 + endloop + endfacet + facet normal 0.892406 -0.254484 -0.372626 + outer loop + vertex -407.147 120.392 164.69 + vertex -404.137 119.694 172.374 + vertex -408.106 114.045 166.728 + endloop + endfacet + facet normal 0.892771 -0.258151 -0.369214 + outer loop + vertex -406.971 112.84 170.316 + vertex -408.106 114.045 166.728 + vertex -404.137 119.694 172.374 + endloop + endfacet + facet normal 0.888461 -0.252069 -0.383534 + outer loop + vertex -406.971 112.84 170.316 + vertex -404.137 119.694 172.374 + vertex -405.073 113.343 174.381 + endloop + endfacet + facet normal 0.884611 -0.253907 -0.391146 + outer loop + vertex -404.137 119.694 172.374 + vertex -400.993 118.94 179.975 + vertex -405.073 113.343 174.381 + endloop + endfacet + facet normal 0.885168 -0.258816 -0.386642 + outer loop + vertex -403.879 112.129 177.928 + vertex -405.073 113.343 174.381 + vertex -400.993 118.94 179.975 + endloop + endfacet + facet normal 0.880613 -0.252603 -0.40089 + outer loop + vertex -403.879 112.129 177.928 + vertex -400.993 118.94 179.975 + vertex -401.906 112.589 181.971 + endloop + endfacet + facet normal 0.87625 -0.254564 -0.409125 + outer loop + vertex -400.993 118.94 179.975 + vertex -397.705 118.038 187.578 + vertex -401.906 112.589 181.971 + endloop + endfacet + facet normal 0.876761 -0.258909 -0.405286 + outer loop + vertex -400.648 111.318 185.505 + vertex -401.906 112.589 181.971 + vertex -397.705 118.038 187.578 + endloop + endfacet + facet normal 0.872335 -0.252923 -0.418404 + outer loop + vertex -400.648 111.318 185.505 + vertex -397.705 118.038 187.578 + vertex -398.603 111.659 189.563 + endloop + endfacet + facet normal 0.866552 -0.25535 -0.428816 + outer loop + vertex -397.705 118.038 187.578 + vertex -394.168 116.936 195.382 + vertex -398.603 111.659 189.563 + endloop + endfacet + facet normal 0.867231 -0.261671 -0.423602 + outer loop + vertex -397.341 110.249 193.018 + vertex -398.603 111.659 189.563 + vertex -394.168 116.936 195.382 + endloop + endfacet + facet normal 0.862076 -0.253933 -0.438569 + outer loop + vertex -397.341 110.249 193.018 + vertex -394.168 116.936 195.382 + vertex -395.422 110.374 196.717 + endloop + endfacet + facet normal 0.852617 -0.255622 -0.455744 + outer loop + vertex -392.312 114.563 200.187 + vertex -395.422 110.374 196.717 + vertex -394.168 116.936 195.382 + endloop + endfacet + facet normal 0.863138 -0.232371 -0.448327 + outer loop + vertex -391.137 118.856 200.223 + vertex -392.312 114.563 200.187 + vertex -394.168 116.936 195.382 + endloop + endfacet + facet normal 0.864097 -0.202813 -0.460655 + outer loop + vertex -394.168 116.936 195.382 + vertex -388.937 125.094 201.603 + vertex -391.137 118.856 200.223 + endloop + endfacet + facet normal 0.867911 -0.206085 -0.451952 + outer loop + vertex -391.137 118.856 200.223 + vertex -388.937 125.094 201.603 + vertex -389.311 118.882 203.718 + endloop + endfacet + facet normal 0.864908 -0.207615 -0.456979 + outer loop + vertex -388.937 125.094 201.603 + vertex -385.277 124.242 208.917 + vertex -389.311 118.882 203.718 + endloop + endfacet + facet normal 0.865503 -0.210396 -0.454575 + outer loop + vertex -387.898 117.3 207.141 + vertex -389.311 118.882 203.718 + vertex -385.277 124.242 208.917 + endloop + endfacet + facet normal 0.861536 -0.206543 -0.463784 + outer loop + vertex -387.898 117.3 207.141 + vertex -385.277 124.242 208.917 + vertex -385.799 117.606 210.903 + endloop + endfacet + facet normal 0.856898 -0.234819 -0.458896 + outer loop + vertex -387.898 117.3 207.141 + vertex -385.799 117.606 210.903 + vertex -388.817 112.768 207.743 + endloop + endfacet + facet normal 0.858511 -0.234749 -0.455907 + outer loop + vertex -390.572 113.466 204.079 + vertex -387.898 117.3 207.141 + vertex -388.817 112.768 207.743 + endloop + endfacet + facet normal 0.847426 -0.269771 -0.457267 + outer loop + vertex -390.572 113.466 204.079 + vertex -388.817 112.768 207.743 + vertex -391.881 108.732 204.446 + endloop + endfacet + facet normal 0.850905 -0.27021 -0.450497 + outer loop + vertex -393.634 109.477 200.687 + vertex -390.572 113.466 204.079 + vertex -391.881 108.732 204.446 + endloop + endfacet + facet normal 0.849988 -0.265838 -0.454809 + outer loop + vertex -392.312 114.563 200.187 + vertex -390.572 113.466 204.079 + vertex -393.634 109.477 200.687 + endloop + endfacet + facet normal 0.862414 -0.230848 -0.450502 + outer loop + vertex -392.312 114.563 200.187 + vertex -389.311 118.882 203.718 + vertex -390.572 113.466 204.079 + endloop + endfacet + facet normal 0.848002 -0.27232 -0.454681 + outer loop + vertex -391.881 108.732 204.446 + vertex -388.817 112.768 207.743 + vertex -390.137 108.198 208.018 + endloop + endfacet + facet normal 0.843338 -0.271519 -0.463744 + outer loop + vertex -388.817 112.768 207.743 + vertex -387.053 112.254 211.252 + vertex -390.137 108.198 208.018 + endloop + endfacet + facet normal 0.843527 -0.272302 -0.462941 + outer loop + vertex -390.137 108.198 208.018 + vertex -387.053 112.254 211.252 + vertex -388.383 107.749 211.478 + endloop + endfacet + facet normal 0.838871 -0.271375 -0.471859 + outer loop + vertex -387.053 112.254 211.252 + vertex -385.286 111.799 214.654 + vertex -388.383 107.749 211.478 + endloop + endfacet + facet normal 0.83931 -0.273107 -0.470076 + outer loop + vertex -388.383 107.749 211.478 + vertex -385.286 111.799 214.654 + vertex -386.63 107.302 214.867 + endloop + endfacet + facet normal 0.834207 -0.272037 -0.479681 + outer loop + vertex -385.286 111.799 214.654 + vertex -383.524 111.329 217.986 + vertex -386.63 107.302 214.867 + endloop + endfacet + facet normal 0.83418 -0.271933 -0.479788 + outer loop + vertex -386.63 107.302 214.867 + vertex -383.524 111.329 217.986 + vertex -384.868 106.806 218.212 + endloop + endfacet + facet normal 0.830092 -0.271093 -0.487294 + outer loop + vertex -383.524 111.329 217.986 + vertex -381.761 110.827 221.268 + vertex -384.868 106.806 218.212 + endloop + endfacet + facet normal 0.830483 -0.2725 -0.485841 + outer loop + vertex -384.868 106.806 218.212 + vertex -381.761 110.827 221.268 + vertex -383.11 106.292 221.505 + endloop + endfacet + facet normal 0.825385 -0.271462 -0.495023 + outer loop + vertex -381.761 110.827 221.268 + vertex -379.987 110.3 224.515 + vertex -383.11 106.292 221.505 + endloop + endfacet + facet normal 0.825647 -0.272371 -0.494085 + outer loop + vertex -383.11 106.292 221.505 + vertex -379.987 110.3 224.515 + vertex -381.336 105.762 224.762 + endloop + endfacet + facet normal 0.820943 -0.271422 -0.502377 + outer loop + vertex -379.987 110.3 224.515 + vertex -378.2 109.762 227.726 + vertex -381.336 105.762 224.762 + endloop + endfacet + facet normal 0.821132 -0.272051 -0.501728 + outer loop + vertex -381.336 105.762 224.762 + vertex -378.2 109.762 227.726 + vertex -379.547 105.221 227.984 + endloop + endfacet + facet normal 0.816321 -0.271096 -0.510027 + outer loop + vertex -378.2 109.762 227.726 + vertex -376.404 109.213 230.893 + vertex -379.547 105.221 227.984 + endloop + endfacet + facet normal 0.816606 -0.272009 -0.509083 + outer loop + vertex -379.547 105.221 227.984 + vertex -376.404 109.213 230.893 + vertex -377.754 104.674 231.153 + endloop + endfacet + facet normal 0.812044 -0.271094 -0.51681 + outer loop + vertex -376.404 109.213 230.893 + vertex -374.623 108.663 233.979 + vertex -377.754 104.674 231.153 + endloop + endfacet + facet normal 0.811984 -0.270914 -0.517 + outer loop + vertex -377.754 104.674 231.153 + vertex -374.623 108.663 233.979 + vertex -375.973 104.118 234.241 + endloop + endfacet + facet normal 0.80753 -0.270018 -0.52439 + outer loop + vertex -374.623 108.663 233.979 + vertex -372.863 108.11 236.975 + vertex -375.973 104.118 234.241 + endloop + endfacet + facet normal 0.808043 -0.271475 -0.522846 + outer loop + vertex -375.973 104.118 234.241 + vertex -372.863 108.11 236.975 + vertex -374.222 103.57 237.232 + endloop + endfacet + facet normal 0.802662 -0.270362 -0.531637 + outer loop + vertex -372.863 108.11 236.975 + vertex -371.118 107.554 239.892 + vertex -374.222 103.57 237.232 + endloop + endfacet + facet normal 0.802821 -0.270793 -0.531177 + outer loop + vertex -374.222 103.57 237.232 + vertex -371.118 107.554 239.892 + vertex -372.477 103.013 240.153 + endloop + endfacet + facet normal 0.798047 -0.269804 -0.53882 + outer loop + vertex -371.118 107.554 239.892 + vertex -369.369 106.993 242.763 + vertex -372.477 103.013 240.153 + endloop + endfacet + facet normal 0.797589 -0.268611 -0.540093 + outer loop + vertex -372.477 103.013 240.153 + vertex -369.369 106.993 242.763 + vertex -370.717 102.438 243.039 + endloop + endfacet + facet normal 0.79315 -0.267717 -0.547028 + outer loop + vertex -369.369 106.993 242.763 + vertex -367.595 106.416 245.618 + vertex -370.717 102.438 243.039 + endloop + endfacet + facet normal 0.793635 -0.268944 -0.545723 + outer loop + vertex -370.717 102.438 243.039 + vertex -367.595 106.416 245.618 + vertex -368.943 101.861 245.902 + endloop + endfacet + facet normal 0.78914 -0.268045 -0.55264 + outer loop + vertex -367.595 106.416 245.618 + vertex -365.809 105.843 248.446 + vertex -368.943 101.861 245.902 + endloop + endfacet + facet normal 0.788681 -0.266919 -0.553838 + outer loop + vertex -368.943 101.861 245.902 + vertex -365.809 105.843 248.446 + vertex -367.153 101.274 248.733 + endloop + endfacet + facet normal 0.784418 -0.266068 -0.560264 + outer loop + vertex -365.809 105.843 248.446 + vertex -364.021 105.271 251.22 + vertex -367.153 101.274 248.733 + endloop + endfacet + facet normal 0.78461 -0.266519 -0.559781 + outer loop + vertex -367.153 101.274 248.733 + vertex -364.021 105.271 251.22 + vertex -365.377 100.7 251.496 + endloop + endfacet + facet normal 0.778836 -0.265323 -0.568347 + outer loop + vertex -364.021 105.271 251.22 + vertex -362.246 104.704 253.918 + vertex -365.377 100.7 251.496 + endloop + endfacet + facet normal 0.778381 -0.264304 -0.569444 + outer loop + vertex -365.377 100.7 251.496 + vertex -362.246 104.704 253.918 + vertex -363.614 100.124 254.174 + endloop + endfacet + facet normal 0.774249 -0.263406 -0.575461 + outer loop + vertex -362.246 104.704 253.918 + vertex -360.503 104.145 256.519 + vertex -363.614 100.124 254.174 + endloop + endfacet + facet normal 0.773562 -0.261948 -0.577049 + outer loop + vertex -363.614 100.124 254.174 + vertex -360.503 104.145 256.519 + vertex -361.879 99.5584 256.757 + endloop + endfacet + facet normal 0.768641 -0.260836 -0.584086 + outer loop + vertex -360.503 104.145 256.519 + vertex -358.783 103.578 259.036 + vertex -361.879 99.5584 256.757 + endloop + endfacet + facet normal 0.768695 -0.260947 -0.583964 + outer loop + vertex -361.879 99.5584 256.757 + vertex -358.783 103.578 259.036 + vertex -360.174 98.9954 259.253 + endloop + endfacet + facet normal 0.763165 -0.259637 -0.591749 + outer loop + vertex -358.783 103.578 259.036 + vertex -357.107 103.003 261.45 + vertex -360.174 98.9954 259.253 + endloop + endfacet + facet normal 0.76195 -0.257289 -0.594336 + outer loop + vertex -360.174 98.9954 259.253 + vertex -357.107 103.003 261.45 + vertex -358.492 98.4056 261.665 + endloop + endfacet + facet normal 0.757677 -0.256276 -0.600206 + outer loop + vertex -357.107 103.003 261.45 + vertex -355.489 102.417 263.742 + vertex -358.492 98.4056 261.665 + endloop + endfacet + facet normal 0.757605 -0.256147 -0.600352 + outer loop + vertex -358.492 98.4056 261.665 + vertex -355.489 102.417 263.742 + vertex -356.885 97.8142 263.944 + endloop + endfacet + facet normal 0.753558 -0.255161 -0.60584 + outer loop + vertex -355.489 102.417 263.742 + vertex -354.02 101.878 265.796 + vertex -356.885 97.8142 263.944 + endloop + endfacet + facet normal 0.752793 -0.253958 -0.607296 + outer loop + vertex -356.885 97.8142 263.944 + vertex -354.02 101.878 265.796 + vertex -355.416 97.2747 265.991 + endloop + endfacet + facet normal 0.751137 -0.253549 -0.609513 + outer loop + vertex -354.02 101.878 265.796 + vertex -352.777 101.476 267.495 + vertex -355.416 97.2747 265.991 + endloop + endfacet + facet normal 0.750589 -0.252862 -0.610472 + outer loop + vertex -355.416 97.2747 265.991 + vertex -352.777 101.476 267.495 + vertex -354.185 96.9058 267.657 + endloop + endfacet + facet normal 0.752392 -0.253332 -0.608054 + outer loop + vertex -352.777 101.476 267.495 + vertex -351.869 101.326 268.681 + vertex -354.185 96.9058 267.657 + endloop + endfacet + facet normal 0.751412 -0.252453 -0.609629 + outer loop + vertex -354.185 96.9058 267.657 + vertex -351.869 101.326 268.681 + vertex -353.294 96.7769 268.809 + endloop + endfacet + facet normal 0.74874 -0.251717 -0.61321 + outer loop + vertex -351.869 101.326 268.681 + vertex -351.34 101.322 269.328 + vertex -353.294 96.7769 268.809 + endloop + endfacet + facet normal 0.748702 -0.251694 -0.613266 + outer loop + vertex -353.294 96.7769 268.809 + vertex -351.34 101.322 269.328 + vertex -352.799 96.7151 269.439 + endloop + endfacet + facet normal 0.63627 -0.219129 -0.739691 + outer loop + vertex -351.34 101.322 269.328 + vertex -351.276 100.705 269.567 + vertex -352.799 96.7151 269.439 + endloop + endfacet + facet normal 0.714228 -0.251673 -0.653099 + outer loop + vertex -352.799 96.7151 269.439 + vertex -351.276 100.705 269.567 + vertex -352.658 96.4785 269.684 + endloop + endfacet + facet normal 0.000232809 -0.0278637 -0.999612 + outer loop + vertex -351.276 100.705 269.567 + vertex -351.48 99.8057 269.592 + vertex -352.658 96.4785 269.684 + endloop + endfacet + facet normal 0.562443 -0.221223 -0.796692 + outer loop + vertex -352.658 96.4785 269.684 + vertex -351.48 99.8057 269.592 + vertex -352.859 95.7808 269.736 + endloop + endfacet + facet normal 0.804938 -0.216974 -0.552265 + outer loop + vertex -367.595 106.416 245.618 + vertex -364.575 111.212 248.135 + vertex -365.809 105.843 248.446 + endloop + endfacet + facet normal 0.797132 -0.215853 -0.563905 + outer loop + vertex -364.575 111.212 248.135 + vertex -363.114 109.768 250.754 + vertex -365.809 105.843 248.446 + endloop + endfacet + facet normal 0.798924 -0.219385 -0.559992 + outer loop + vertex -365.809 105.843 248.446 + vertex -363.114 109.768 250.754 + vertex -364.021 105.271 251.22 + endloop + endfacet + facet normal 0.798397 -0.219357 -0.560754 + outer loop + vertex -363.114 109.768 250.754 + vertex -361.004 110.074 253.637 + vertex -364.021 105.271 251.22 + endloop + endfacet + facet normal 0.794859 -0.21349 -0.567997 + outer loop + vertex -364.021 105.271 251.22 + vertex -361.004 110.074 253.637 + vertex -362.246 104.704 253.918 + endloop + endfacet + facet normal 0.786978 -0.212259 -0.57932 + outer loop + vertex -361.004 110.074 253.637 + vertex -359.573 108.635 256.109 + vertex -362.246 104.704 253.918 + endloop + endfacet + facet normal 0.789019 -0.215968 -0.575157 + outer loop + vertex -362.246 104.704 253.918 + vertex -359.573 108.635 256.109 + vertex -360.503 104.145 256.519 + endloop + endfacet + facet normal 0.789135 -0.215977 -0.574995 + outer loop + vertex -359.573 108.635 256.109 + vertex -357.554 108.92 258.773 + vertex -360.503 104.145 256.519 + endloop + endfacet + facet normal 0.784723 -0.209258 -0.583456 + outer loop + vertex -360.503 104.145 256.519 + vertex -357.554 108.92 258.773 + vertex -358.783 103.578 259.036 + endloop + endfacet + facet normal 0.775972 -0.20784 -0.595542 + outer loop + vertex -357.554 108.92 258.773 + vertex -356.191 107.474 261.053 + vertex -358.783 103.578 259.036 + endloop + endfacet + facet normal 0.778401 -0.211834 -0.590948 + outer loop + vertex -358.783 103.578 259.036 + vertex -356.191 107.474 261.053 + vertex -357.107 103.003 261.45 + endloop + endfacet + facet normal 0.780887 -0.212045 -0.587581 + outer loop + vertex -356.191 107.474 261.053 + vertex -354.327 107.814 263.408 + vertex -357.107 103.003 261.45 + endloop + endfacet + facet normal 0.774572 -0.203856 -0.598732 + outer loop + vertex -357.107 103.003 261.45 + vertex -354.327 107.814 263.408 + vertex -355.489 102.417 263.742 + endloop + endfacet + facet normal 0.767735 -0.202943 -0.60778 + outer loop + vertex -354.327 107.814 263.408 + vertex -353.13 106.434 265.38 + vertex -355.489 102.417 263.742 + endloop + endfacet + facet normal 0.769737 -0.205508 -0.604377 + outer loop + vertex -355.489 102.417 263.742 + vertex -353.13 106.434 265.38 + vertex -354.02 101.878 265.796 + endloop + endfacet + facet normal 0.777418 -0.206085 -0.594264 + outer loop + vertex -353.13 106.434 265.38 + vertex -351.674 106.962 267.102 + vertex -354.02 101.878 265.796 + endloop + endfacet + facet normal 0.768171 -0.198074 -0.608835 + outer loop + vertex -354.02 101.878 265.796 + vertex -351.674 106.962 267.102 + vertex -352.777 101.476 267.495 + endloop + endfacet + facet normal 0.758614 -0.197025 -0.621036 + outer loop + vertex -351.674 106.962 267.102 + vertex -350.913 105.82 268.394 + vertex -352.777 101.476 267.495 + endloop + endfacet + facet normal 0.765186 -0.201851 -0.611348 + outer loop + vertex -352.777 101.476 267.495 + vertex -350.913 105.82 268.394 + vertex -351.869 101.326 268.681 + endloop + endfacet + facet normal 0.77905 -0.203626 -0.592974 + outer loop + vertex -350.913 105.82 268.394 + vertex -350.13 106.749 269.104 + vertex -351.869 101.326 268.681 + endloop + endfacet + facet normal 0.758979 -0.194988 -0.621233 + outer loop + vertex -351.869 101.326 268.681 + vertex -350.13 106.749 269.104 + vertex -351.34 101.322 269.328 + endloop + endfacet + facet normal 0.676492 -0.180432 -0.714005 + outer loop + vertex -350.13 106.749 269.104 + vertex -349.972 105.923 269.462 + vertex -351.34 101.322 269.328 + endloop + endfacet + facet normal 0.705367 -0.18993 -0.682924 + outer loop + vertex -351.34 101.322 269.328 + vertex -349.972 105.923 269.462 + vertex -351.276 100.705 269.567 + endloop + endfacet + facet normal -0.00105554 -0.0197101 -0.999805 + outer loop + vertex -349.972 105.923 269.462 + vertex -350.549 103.123 269.518 + vertex -351.276 100.705 269.567 + endloop + endfacet + facet normal 0.105325 -0.0515438 -0.993101 + outer loop + vertex -351.276 100.705 269.567 + vertex -350.549 103.123 269.518 + vertex -351.48 99.8057 269.592 + endloop + endfacet + facet normal -0.14974 0.0111778 -0.988662 + outer loop + vertex -350.549 103.123 269.518 + vertex -349.972 105.923 269.462 + vertex -349.967 105.719 269.46 + endloop + endfacet + facet normal 0.721408 -0.154855 -0.674974 + outer loop + vertex -349.972 105.923 269.462 + vertex -350.13 106.749 269.104 + vertex -348.636 112.905 269.289 + endloop + endfacet + facet normal 0.756551 -0.164653 -0.632867 + outer loop + vertex -349.405 113.199 268.292 + vertex -348.636 112.905 269.289 + vertex -350.13 106.749 269.104 + endloop + endfacet + facet normal 0.762107 -0.144363 -0.631151 + outer loop + vertex -349.405 113.199 268.292 + vertex -347.156 121.555 269.096 + vertex -348.636 112.905 269.289 + endloop + endfacet + facet normal 0.715534 -0.13759 -0.684894 + outer loop + vertex -348.636 112.905 269.289 + vertex -347.156 121.555 269.096 + vertex -347.608 117.659 269.407 + endloop + endfacet + facet normal 0.700749 -0.133999 -0.70071 + outer loop + vertex -347.608 117.659 269.407 + vertex -348.317 113.739 269.448 + vertex -348.636 112.905 269.289 + endloop + endfacet + facet normal 0.710577 -0.13989 -0.689573 + outer loop + vertex -348.317 113.739 269.448 + vertex -349.103 109.765 269.444 + vertex -348.636 112.905 269.289 + endloop + endfacet + facet normal 0.962258 -0.190284 -0.194554 + outer loop + vertex -349.103 109.765 269.444 + vertex -348.317 113.739 269.448 + vertex -349.213 109.093 269.557 + endloop + endfacet + facet normal 0.937608 -0.201267 -0.28352 + outer loop + vertex -349.967 105.719 269.46 + vertex -349.103 109.765 269.444 + vertex -349.213 109.093 269.557 + endloop + endfacet + facet normal 0.822466 -0.154405 -0.547456 + outer loop + vertex -348.317 113.739 269.448 + vertex -347.608 117.659 269.407 + vertex -347.465 117.542 269.654 + endloop + endfacet + facet normal 0.823717 -0.150937 -0.546543 + outer loop + vertex -347.608 117.659 269.407 + vertex -347.103 120.419 269.407 + vertex -347.465 117.542 269.654 + endloop + endfacet + facet normal 0.839249 -0.150819 -0.522412 + outer loop + vertex -347.103 120.419 269.407 + vertex -346.615 123.025 269.437 + vertex -347.465 117.542 269.654 + endloop + endfacet + facet normal 0.805255 -0.147597 -0.574264 + outer loop + vertex -345.821 126.067 269.769 + vertex -347.465 117.542 269.654 + vertex -346.615 123.025 269.437 + endloop + endfacet + facet normal 0.787118 -0.139985 -0.600707 + outer loop + vertex -346.615 123.025 269.437 + vertex -345.946 127.068 269.372 + vertex -345.821 126.067 269.769 + endloop + endfacet + facet normal 0.787984 -0.139474 -0.59969 + outer loop + vertex -345.946 127.068 269.372 + vertex -345.167 131.287 269.414 + vertex -345.821 126.067 269.769 + endloop + endfacet + facet normal 0.784712 -0.139357 -0.603992 + outer loop + vertex -344.357 134.541 269.716 + vertex -345.821 126.067 269.769 + vertex -345.167 131.287 269.414 + endloop + endfacet + facet normal 0.783552 -0.138919 -0.605597 + outer loop + vertex -345.167 131.287 269.414 + vertex -344.453 135.629 269.343 + vertex -344.357 134.541 269.716 + endloop + endfacet + facet normal 0.783717 -0.138838 -0.605402 + outer loop + vertex -344.453 135.629 269.343 + vertex -343.768 139.277 269.392 + vertex -344.357 134.541 269.716 + endloop + endfacet + facet normal 0.783342 -0.138825 -0.60589 + outer loop + vertex -343.01 142.218 269.698 + vertex -344.357 134.541 269.716 + vertex -343.768 139.277 269.392 + endloop + endfacet + facet normal 0.78771 -0.140585 -0.599791 + outer loop + vertex -343.768 139.277 269.392 + vertex -343.262 142.176 269.377 + vertex -343.01 142.218 269.698 + endloop + endfacet + facet normal 0.787667 -0.141432 -0.599648 + outer loop + vertex -343.262 142.176 269.377 + vertex -342.566 145.889 269.416 + vertex -343.01 142.218 269.698 + endloop + endfacet + facet normal 0.789693 -0.141471 -0.596968 + outer loop + vertex -341.511 150.33 269.758 + vertex -343.01 142.218 269.698 + vertex -342.566 145.889 269.416 + endloop + endfacet + facet normal 0.792981 -0.14261 -0.59232 + outer loop + vertex -342.566 145.889 269.416 + vertex -341.768 150.114 269.467 + vertex -341.511 150.33 269.758 + endloop + endfacet + facet normal 0.792964 -0.142536 -0.592361 + outer loop + vertex -341.768 150.114 269.467 + vertex -340.995 154.317 269.49 + vertex -341.511 150.33 269.758 + endloop + endfacet + facet normal 0.799597 -0.142785 -0.583316 + outer loop + vertex -339.959 159.408 269.665 + vertex -341.511 150.33 269.758 + vertex -340.995 154.317 269.49 + endloop + endfacet + facet normal 0.816505 -0.147087 -0.558287 + outer loop + vertex -340.995 154.317 269.49 + vertex -340.242 158.411 269.512 + vertex -339.959 159.408 269.665 + endloop + endfacet + facet normal 0.80698 -0.142095 -0.573229 + outer loop + vertex -340.242 158.411 269.512 + vertex -339.721 161.47 269.488 + vertex -339.959 159.408 269.665 + endloop + endfacet + facet normal 0.810337 -0.142077 -0.568478 + outer loop + vertex -339.721 161.47 269.488 + vertex -339.144 164.762 269.488 + vertex -339.959 159.408 269.665 + endloop + endfacet + facet normal 0.915435 -0.151625 -0.372811 + outer loop + vertex -338.605 167.525 269.689 + vertex -339.959 159.408 269.665 + vertex -339.144 164.762 269.488 + endloop + endfacet + facet normal 0.915752 -0.151747 -0.371983 + outer loop + vertex -339.144 164.762 269.488 + vertex -338.637 167.849 269.476 + vertex -338.605 167.525 269.689 + endloop + endfacet + facet normal 0.938221 -0.118683 -0.325047 + outer loop + vertex -338.637 167.849 269.476 + vertex -338.057 172.114 269.594 + vertex -338.605 167.525 269.689 + endloop + endfacet + facet normal 0.992306 -0.117654 0.0385456 + outer loop + vertex -337.505 176.904 269.998 + vertex -338.605 167.525 269.689 + vertex -338.057 172.114 269.594 + endloop + endfacet + facet normal 0.819168 -0.0462494 -0.571686 + outer loop + vertex -338.057 172.114 269.594 + vertex -337.611 176.942 269.842 + vertex -337.505 176.904 269.998 + endloop + endfacet + facet normal 0.819537 -0.0463108 -0.571152 + outer loop + vertex -337.611 176.942 269.842 + vertex -338.057 172.114 269.594 + vertex -337.719 176.98 269.685 + endloop + endfacet + facet normal 0.314523 -0.00415124 -0.949241 + outer loop + vertex -339.194 166.022 269.244 + vertex -337.719 176.98 269.685 + vertex -338.057 172.114 269.594 + endloop + endfacet + facet normal 0.806885 -0.0851323 -0.584542 + outer loop + vertex -339.816 167.84 268.121 + vertex -337.719 176.98 269.685 + vertex -339.194 166.022 269.244 + endloop + endfacet + facet normal 0.772862 -0.120528 -0.623022 + outer loop + vertex -339.816 167.84 268.121 + vertex -339.194 166.022 269.244 + vertex -341.425 158.699 267.894 + endloop + endfacet + facet normal 0.805145 -0.127299 -0.579256 + outer loop + vertex -339.816 167.84 268.121 + vertex -341.425 158.699 267.894 + vertex -343.056 159.712 265.404 + endloop + endfacet + facet normal 0.806873 -0.128913 -0.576488 + outer loop + vertex -343.056 159.712 265.404 + vertex -341.46 168.649 265.638 + vertex -339.816 167.84 268.121 + endloop + endfacet + facet normal 0.816622 -0.089678 -0.570164 + outer loop + vertex -337.826 177.018 269.528 + vertex -339.816 167.84 268.121 + vertex -341.46 168.649 265.638 + endloop + endfacet + facet normal 0.816586 -0.0896356 -0.570222 + outer loop + vertex -340.141 177.839 266.083 + vertex -337.826 177.018 269.528 + vertex -341.46 168.649 265.638 + endloop + endfacet + facet normal 0.822248 -0.0908552 -0.56183 + outer loop + vertex -344.04 169.513 261.723 + vertex -340.141 177.839 266.083 + vertex -341.46 168.649 265.638 + endloop + endfacet + facet normal 0.813921 -0.132788 -0.565597 + outer loop + vertex -344.04 169.513 261.723 + vertex -341.46 168.649 265.638 + vertex -345.584 160.551 261.606 + endloop + endfacet + facet normal 0.817958 -0.133563 -0.559559 + outer loop + vertex -348.723 161.524 256.785 + vertex -344.04 169.513 261.723 + vertex -345.584 160.551 261.606 + endloop + endfacet + facet normal 0.814366 -0.150197 -0.560579 + outer loop + vertex -348.723 161.524 256.785 + vertex -345.584 160.551 261.606 + vertex -350.444 152.737 256.638 + endloop + endfacet + facet normal 0.819886 -0.151418 -0.55214 + outer loop + vertex -353.878 153.809 251.246 + vertex -348.723 161.524 256.785 + vertex -350.444 152.737 256.638 + endloop + endfacet + facet normal 0.818743 -0.156492 -0.552422 + outer loop + vertex -353.878 153.809 251.246 + vertex -350.444 152.737 256.638 + vertex -355.626 145.048 251.136 + endloop + endfacet + facet normal 0.825237 -0.157915 -0.542261 + outer loop + vertex -359.113 146.169 245.504 + vertex -353.878 153.809 251.246 + vertex -355.626 145.048 251.136 + endloop + endfacet + facet normal 0.824446 -0.161346 -0.542454 + outer loop + vertex -359.113 146.169 245.504 + vertex -355.626 145.048 251.136 + vertex -360.827 137.187 245.57 + endloop + endfacet + facet normal 0.831002 -0.162521 -0.531999 + outer loop + vertex -364.295 138.316 239.808 + vertex -359.113 146.169 245.504 + vertex -360.827 137.187 245.57 + endloop + endfacet + facet normal 0.829663 -0.168233 -0.532312 + outer loop + vertex -364.295 138.316 239.808 + vertex -360.827 137.187 245.57 + vertex -365.973 128.884 240.173 + endloop + endfacet + facet normal 0.83589 -0.168951 -0.522249 + outer loop + vertex -369.448 129.993 234.254 + vertex -364.295 138.316 239.808 + vertex -365.973 128.884 240.173 + endloop + endfacet + facet normal 0.833411 -0.179351 -0.522742 + outer loop + vertex -369.448 129.993 234.254 + vertex -365.973 128.884 240.173 + vertex -371.13 120.09 234.969 + endloop + endfacet + facet normal 0.839307 -0.179657 -0.513114 + outer loop + vertex -374.652 121.18 228.826 + vertex -369.448 129.993 234.254 + vertex -371.13 120.09 234.969 + endloop + endfacet + facet normal 0.8346 -0.198657 -0.513788 + outer loop + vertex -374.652 121.18 228.826 + vertex -371.13 120.09 234.969 + vertex -375.159 114.559 230.562 + endloop + endfacet + facet normal 0.837413 -0.197759 -0.509541 + outer loop + vertex -377.273 114.225 227.219 + vertex -374.652 121.18 228.826 + vertex -375.159 114.559 230.562 + endloop + endfacet + facet normal 0.832817 -0.230244 -0.503393 + outer loop + vertex -377.273 114.225 227.219 + vertex -375.159 114.559 230.562 + vertex -378.2 109.762 227.726 + endloop + endfacet + facet normal 0.842002 -0.201604 -0.500388 + outer loop + vertex -377.273 114.225 227.219 + vertex -378.721 115.636 224.214 + vertex -374.652 121.18 228.826 + endloop + endfacet + facet normal 0.842034 -0.201705 -0.500294 + outer loop + vertex -378.184 122.226 222.46 + vertex -374.652 121.18 228.826 + vertex -378.721 115.636 224.214 + endloop + endfacet + facet normal 0.844941 -0.200735 -0.495762 + outer loop + vertex -380.825 115.278 220.772 + vertex -378.184 122.226 222.46 + vertex -378.721 115.636 224.214 + endloop + endfacet + facet normal 0.840533 -0.231343 -0.489882 + outer loop + vertex -380.825 115.278 220.772 + vertex -378.721 115.636 224.214 + vertex -381.761 110.827 221.268 + endloop + endfacet + facet normal 0.849711 -0.204974 -0.485774 + outer loop + vertex -380.825 115.278 220.772 + vertex -382.257 116.643 217.692 + vertex -378.184 122.226 222.46 + endloop + endfacet + facet normal 0.849719 -0.205002 -0.485748 + outer loop + vertex -381.72 123.22 215.855 + vertex -378.184 122.226 222.46 + vertex -382.257 116.643 217.692 + endloop + endfacet + facet normal 0.852627 -0.203936 -0.48108 + outer loop + vertex -384.359 116.236 214.138 + vertex -381.72 123.22 215.855 + vertex -382.257 116.643 217.692 + endloop + endfacet + facet normal 0.848494 -0.232589 -0.475353 + outer loop + vertex -384.359 116.236 214.138 + vertex -382.257 116.643 217.692 + vertex -385.286 111.799 214.654 + endloop + endfacet + facet normal 0.857671 -0.208567 -0.47 + outer loop + vertex -384.359 116.236 214.138 + vertex -385.799 117.606 210.903 + vertex -381.72 123.22 215.855 + endloop + endfacet + facet normal 0.849235 -0.22997 -0.475305 + outer loop + vertex -385.799 117.606 210.903 + vertex -384.359 116.236 214.138 + vertex -387.053 112.254 211.252 + endloop + endfacet + facet normal 0.854141 -0.186723 -0.485364 + outer loop + vertex -381.72 123.22 215.855 + vertex -376.433 132.097 221.744 + vertex -378.184 122.226 222.46 + endloop + endfacet + facet normal 0.848031 -0.186415 -0.496078 + outer loop + vertex -376.433 132.097 221.744 + vertex -372.93 131.068 228.119 + vertex -378.184 122.226 222.46 + endloop + endfacet + facet normal 0.850317 -0.176611 -0.495751 + outer loop + vertex -376.433 132.097 221.744 + vertex -371.184 140.485 227.759 + vertex -372.93 131.068 228.119 + endloop + endfacet + facet normal 0.844496 -0.175918 -0.505846 + outer loop + vertex -371.184 140.485 227.759 + vertex -367.733 139.423 233.889 + vertex -372.93 131.068 228.119 + endloop + endfacet + facet normal 0.843222 -0.172962 -0.50898 + outer loop + vertex -372.93 131.068 228.119 + vertex -367.733 139.423 233.889 + vertex -369.448 129.993 234.254 + endloop + endfacet + facet normal 0.845718 -0.170627 -0.505617 + outer loop + vertex -371.184 140.485 227.759 + vertex -365.959 148.412 233.823 + vertex -367.733 139.423 233.889 + endloop + endfacet + facet normal 0.839875 -0.169548 -0.515619 + outer loop + vertex -365.959 148.412 233.823 + vertex -362.549 147.312 239.739 + vertex -367.733 139.423 233.889 + endloop + endfacet + facet normal 0.838727 -0.166732 -0.518399 + outer loop + vertex -367.733 139.423 233.889 + vertex -362.549 147.312 239.739 + vertex -364.295 138.316 239.808 + endloop + endfacet + facet normal 0.840595 -0.166442 -0.515457 + outer loop + vertex -365.959 148.412 233.823 + vertex -360.757 156.105 239.824 + vertex -362.549 147.312 239.739 + endloop + endfacet + facet normal 0.834245 -0.165045 -0.526114 + outer loop + vertex -360.757 156.105 239.824 + vertex -357.339 154.962 245.601 + vertex -362.549 147.312 239.739 + endloop + endfacet + facet normal 0.833104 -0.162212 -0.528796 + outer loop + vertex -362.549 147.312 239.739 + vertex -357.339 154.962 245.601 + vertex -359.113 146.169 245.504 + endloop + endfacet + facet normal 0.835355 -0.160274 -0.525827 + outer loop + vertex -360.757 156.105 239.824 + vertex -355.563 163.81 245.726 + vertex -357.339 154.962 245.601 + endloop + endfacet + facet normal 0.82866 -0.158775 -0.536761 + outer loop + vertex -355.563 163.81 245.726 + vertex -352.119 162.642 251.388 + vertex -357.339 154.962 245.601 + endloop + endfacet + facet normal 0.827523 -0.15609 -0.539297 + outer loop + vertex -357.339 154.962 245.601 + vertex -352.119 162.642 251.388 + vertex -353.878 153.809 251.246 + endloop + endfacet + facet normal 0.832336 -0.142501 -0.53564 + outer loop + vertex -355.563 163.81 245.726 + vertex -350.496 171.687 251.504 + vertex -352.119 162.642 251.388 + endloop + endfacet + facet normal 0.826707 -0.141377 -0.544581 + outer loop + vertex -350.496 171.687 251.504 + vertex -347.15 170.546 256.879 + vertex -352.119 162.642 251.388 + endloop + endfacet + facet normal 0.825101 -0.138099 -0.547847 + outer loop + vertex -352.119 162.642 251.388 + vertex -347.15 170.546 256.879 + vertex -348.723 161.524 256.785 + endloop + endfacet + facet normal 0.835376 -0.0982453 -0.540827 + outer loop + vertex -350.496 171.687 251.504 + vertex -346.027 179.902 256.914 + vertex -347.15 170.546 256.879 + endloop + endfacet + facet normal 0.83108 -0.0977046 -0.547503 + outer loop + vertex -346.027 179.902 256.914 + vertex -342.874 178.802 261.898 + vertex -347.15 170.546 256.879 + endloop + endfacet + facet normal 0.828582 -0.0936938 -0.551973 + outer loop + vertex -347.15 170.546 256.879 + vertex -342.874 178.802 261.898 + vertex -344.04 169.513 261.723 + endloop + endfacet + facet normal 0.837983 -0.102905 -0.535906 + outer loop + vertex -349.159 180.979 251.81 + vertex -346.027 179.902 256.914 + vertex -350.496 171.687 251.504 + endloop + endfacet + facet normal 0.842398 -0.103775 -0.528768 + outer loop + vertex -353.898 172.842 245.857 + vertex -349.159 180.979 251.81 + vertex -350.496 171.687 251.504 + endloop + endfacet + facet normal 0.84449 -0.108078 -0.524553 + outer loop + vertex -352.557 182.124 246.104 + vertex -349.159 180.979 251.81 + vertex -353.898 172.842 245.857 + endloop + endfacet + facet normal 0.849341 -0.108995 -0.516468 + outer loop + vertex -357.291 173.965 240.041 + vertex -352.557 182.124 246.104 + vertex -353.898 172.842 245.857 + endloop + endfacet + facet normal 0.841139 -0.149987 -0.519605 + outer loop + vertex -357.291 173.965 240.041 + vertex -353.898 172.842 245.857 + vertex -358.969 164.945 239.929 + endloop + endfacet + facet normal 0.846991 -0.151199 -0.509651 + outer loop + vertex -362.346 166.027 233.994 + vertex -357.291 173.965 240.041 + vertex -358.969 164.945 239.929 + endloop + endfacet + facet normal 0.843535 -0.166775 -0.510524 + outer loop + vertex -362.346 166.027 233.994 + vertex -358.969 164.945 239.929 + vertex -364.148 157.195 233.901 + endloop + endfacet + facet normal 0.849169 -0.168027 -0.500678 + outer loop + vertex -367.553 158.237 227.778 + vertex -362.346 166.027 233.994 + vertex -364.148 157.195 233.901 + endloop + endfacet + facet normal 0.848172 -0.172428 -0.500873 + outer loop + vertex -367.553 158.237 227.778 + vertex -364.148 157.195 233.901 + vertex -369.385 149.461 227.696 + endloop + endfacet + facet normal 0.853787 -0.173695 -0.490793 + outer loop + vertex -372.843 150.472 221.323 + vertex -367.553 158.237 227.778 + vertex -369.385 149.461 227.696 + endloop + endfacet + facet normal 0.853209 -0.176255 -0.490886 + outer loop + vertex -372.843 150.472 221.323 + vertex -369.385 149.461 227.696 + vertex -374.664 141.505 221.377 + endloop + endfacet + facet normal 0.859431 -0.177449 -0.479469 + outer loop + vertex -378.169 142.503 214.725 + vertex -372.843 150.472 221.323 + vertex -374.664 141.505 221.377 + endloop + endfacet + facet normal 0.858384 -0.18207 -0.479611 + outer loop + vertex -378.169 142.503 214.725 + vertex -374.664 141.505 221.377 + vertex -379.959 133.105 215.09 + endloop + endfacet + facet normal 0.864901 -0.182838 -0.467458 + outer loop + vertex -383.506 134.112 208.134 + vertex -378.169 142.503 214.725 + vertex -379.959 133.105 215.09 + endloop + endfacet + facet normal 0.862788 -0.191966 -0.467702 + outer loop + vertex -383.506 134.112 208.134 + vertex -379.959 133.105 215.09 + vertex -385.277 124.242 208.917 + endloop + endfacet + facet normal 0.86202 -0.18995 -0.469936 + outer loop + vertex -385.277 124.242 208.917 + vertex -379.959 133.105 215.09 + vertex -381.72 123.22 215.855 + endloop + endfacet + facet normal 0.865401 -0.184351 -0.465936 + outer loop + vertex -381.671 143.506 207.825 + vertex -378.169 142.503 214.725 + vertex -383.506 134.112 208.134 + endloop + endfacet + facet normal 0.871937 -0.18521 -0.453236 + outer loop + vertex -387.002 135.23 200.951 + vertex -381.671 143.506 207.825 + vertex -383.506 134.112 208.134 + endloop + endfacet + facet normal 0.869551 -0.195196 -0.453629 + outer loop + vertex -387.002 135.23 200.951 + vertex -383.506 134.112 208.134 + vertex -388.937 125.094 201.603 + endloop + endfacet + facet normal 0.875344 -0.195566 -0.442185 + outer loop + vertex -392.3 126.729 194.222 + vertex -387.002 135.23 200.951 + vertex -388.937 125.094 201.603 + endloop + endfacet + facet normal 0.876308 -0.198849 -0.438797 + outer loop + vertex -390.41 136.347 193.639 + vertex -387.002 135.23 200.951 + vertex -392.3 126.729 194.222 + endloop + endfacet + facet normal 0.883114 -0.199332 -0.424707 + outer loop + vertex -395.668 127.832 186.701 + vertex -390.41 136.347 193.639 + vertex -392.3 126.729 194.222 + endloop + endfacet + facet normal 0.877694 -0.220641 -0.425407 + outer loop + vertex -395.668 127.832 186.701 + vertex -392.3 126.729 194.222 + vertex -397.705 118.038 187.578 + endloop + endfacet + facet normal 0.885392 -0.220781 -0.409069 + outer loop + vertex -400.993 118.94 179.975 + vertex -395.668 127.832 186.701 + vertex -397.705 118.038 187.578 + endloop + endfacet + facet normal 0.885678 -0.221866 -0.40786 + outer loop + vertex -398.922 128.684 179.173 + vertex -395.668 127.832 186.701 + vertex -400.993 118.94 179.975 + endloop + endfacet + facet normal 0.892998 -0.222073 -0.391457 + outer loop + vertex -404.137 119.694 172.374 + vertex -398.922 128.684 179.173 + vertex -400.993 118.94 179.975 + endloop + endfacet + facet normal 0.893255 -0.223115 -0.390276 + outer loop + vertex -402.055 129.423 171.58 + vertex -398.922 128.684 179.173 + vertex -404.137 119.694 172.374 + endloop + endfacet + facet normal 0.89806 -0.202883 -0.39029 + outer loop + vertex -402.055 129.423 171.58 + vertex -396.988 138.043 178.758 + vertex -398.922 128.684 179.173 + endloop + endfacet + facet normal 0.890776 -0.202121 -0.407019 + outer loop + vertex -396.988 138.043 178.758 + vertex -393.747 137.262 186.239 + vertex -398.922 128.684 179.173 + endloop + endfacet + facet normal 0.893344 -0.190633 -0.406933 + outer loop + vertex -396.988 138.043 178.758 + vertex -391.866 146.215 186.173 + vertex -393.747 137.262 186.239 + endloop + endfacet + facet normal 0.886198 -0.189251 -0.422891 + outer loop + vertex -391.866 146.215 186.173 + vertex -388.536 145.407 193.513 + vertex -393.747 137.262 186.239 + endloop + endfacet + facet normal 0.886175 -0.189152 -0.422984 + outer loop + vertex -393.747 137.262 186.239 + vertex -388.536 145.407 193.513 + vertex -390.41 136.347 193.639 + endloop + endfacet + facet normal 0.879176 -0.18791 -0.43788 + outer loop + vertex -388.536 145.407 193.513 + vertex -385.133 144.495 200.737 + vertex -390.41 136.347 193.639 + endloop + endfacet + facet normal 0.880039 -0.184024 -0.437797 + outer loop + vertex -388.536 145.407 193.513 + vertex -383.255 153.294 200.813 + vertex -385.133 144.495 200.737 + endloop + endfacet + facet normal 0.873328 -0.182472 -0.451666 + outer loop + vertex -383.255 153.294 200.813 + vertex -379.805 152.399 207.846 + vertex -385.133 144.495 200.737 + endloop + endfacet + facet normal 0.873243 -0.182148 -0.451961 + outer loop + vertex -385.133 144.495 200.737 + vertex -379.805 152.399 207.846 + vertex -381.671 143.506 207.825 + endloop + endfacet + facet normal 0.866455 -0.180692 -0.465409 + outer loop + vertex -379.805 152.399 207.846 + vertex -376.325 151.448 214.695 + vertex -381.671 143.506 207.825 + endloop + endfacet + facet normal 0.866713 -0.179531 -0.465379 + outer loop + vertex -379.805 152.399 207.846 + vertex -374.453 160.208 214.801 + vertex -376.325 151.448 214.695 + endloop + endfacet + facet normal 0.860655 -0.178095 -0.477027 + outer loop + vertex -374.453 160.208 214.801 + vertex -370.989 159.239 221.412 + vertex -376.325 151.448 214.695 + endloop + endfacet + facet normal 0.860346 -0.177078 -0.477962 + outer loop + vertex -376.325 151.448 214.695 + vertex -370.989 159.239 221.412 + vertex -372.843 150.472 221.323 + endloop + endfacet + facet normal 0.861383 -0.174813 -0.476927 + outer loop + vertex -374.453 160.208 214.801 + vertex -369.148 168.072 221.499 + vertex -370.989 159.239 221.412 + endloop + endfacet + facet normal 0.856113 -0.173617 -0.486752 + outer loop + vertex -369.148 168.072 221.499 + vertex -365.732 167.067 227.866 + vertex -370.989 159.239 221.412 + endloop + endfacet + facet normal 0.855403 -0.171493 -0.48875 + outer loop + vertex -370.989 159.239 221.412 + vertex -365.732 167.067 227.866 + vertex -367.553 158.237 227.778 + endloop + endfacet + facet normal 0.859403 -0.158458 -0.486125 + outer loop + vertex -369.148 168.072 221.499 + vertex -364.008 176.076 227.978 + vertex -365.732 167.067 227.866 + endloop + endfacet + facet normal 0.854321 -0.15737 -0.495348 + outer loop + vertex -364.008 176.076 227.978 + vertex -360.641 175.038 234.115 + vertex -365.732 167.067 227.866 + endloop + endfacet + facet normal 0.853364 -0.154846 -0.497788 + outer loop + vertex -365.732 167.067 227.866 + vertex -360.641 175.038 234.115 + vertex -362.346 166.027 233.994 + endloop + endfacet + facet normal 0.86228 -0.116622 -0.492821 + outer loop + vertex -364.008 176.076 227.978 + vertex -359.122 184.257 234.591 + vertex -360.641 175.038 234.115 + endloop + endfacet + facet normal 0.856838 -0.115223 -0.502546 + outer loop + vertex -359.122 184.257 234.591 + vertex -355.892 183.222 240.335 + vertex -360.641 175.038 234.115 + endloop + endfacet + facet normal 0.855993 -0.113311 -0.504417 + outer loop + vertex -360.641 175.038 234.115 + vertex -355.892 183.222 240.335 + vertex -357.291 173.965 240.041 + endloop + endfacet + facet normal 0.862709 -0.117691 -0.491815 + outer loop + vertex -362.595 185.335 228.241 + vertex -359.122 184.257 234.591 + vertex -364.008 176.076 227.978 + endloop + endfacet + facet normal 0.867825 -0.118736 -0.482475 + outer loop + vertex -367.427 177.093 221.578 + vertex -362.595 185.335 228.241 + vertex -364.008 176.076 227.978 + endloop + endfacet + facet normal 0.868457 -0.12035 -0.480935 + outer loop + vertex -366.033 186.362 221.776 + vertex -362.595 185.335 228.241 + vertex -367.427 177.093 221.578 + endloop + endfacet + facet normal 0.873704 -0.12135 -0.471079 + outer loop + vertex -370.854 178.069 214.969 + vertex -366.033 186.362 221.776 + vertex -367.427 177.093 221.578 + endloop + endfacet + facet normal 0.865784 -0.163003 -0.473125 + outer loop + vertex -370.854 178.069 214.969 + vertex -367.427 177.093 221.578 + vertex -372.598 169.044 214.888 + endloop + endfacet + facet normal 0.871009 -0.164103 -0.463049 + outer loop + vertex -376.055 169.978 208.054 + vertex -370.854 178.069 214.969 + vertex -372.598 169.044 214.888 + endloop + endfacet + facet normal 0.867909 -0.178681 -0.463473 + outer loop + vertex -376.055 169.978 208.054 + vertex -372.598 169.044 214.888 + vertex -377.922 161.134 207.968 + endloop + endfacet + facet normal 0.873844 -0.180049 -0.451641 + outer loop + vertex -381.369 162.016 200.947 + vertex -376.055 169.978 208.054 + vertex -377.922 161.134 207.968 + endloop + endfacet + facet normal 0.873429 -0.18196 -0.451677 + outer loop + vertex -381.369 162.016 200.947 + vertex -377.922 161.134 207.968 + vertex -383.255 153.294 200.813 + endloop + endfacet + facet normal 0.880049 -0.183602 -0.437954 + outer loop + vertex -386.656 154.132 193.628 + vertex -381.369 162.016 200.947 + vertex -383.255 153.294 200.813 + endloop + endfacet + facet normal 0.880068 -0.183679 -0.437885 + outer loop + vertex -384.769 162.859 193.759 + vertex -381.369 162.016 200.947 + vertex -386.656 154.132 193.628 + endloop + endfacet + facet normal 0.886926 -0.185384 -0.423079 + outer loop + vertex -389.987 154.925 186.297 + vertex -384.769 162.859 193.759 + vertex -386.656 154.132 193.628 + endloop + endfacet + facet normal 0.886944 -0.1853 -0.423078 + outer loop + vertex -389.987 154.925 186.297 + vertex -386.656 154.132 193.628 + vertex -391.866 146.215 186.173 + endloop + endfacet + facet normal 0.894147 -0.187087 -0.406816 + outer loop + vertex -395.106 146.967 178.706 + vertex -389.987 154.925 186.297 + vertex -391.866 146.215 186.173 + endloop + endfacet + facet normal 0.894132 -0.18701 -0.406886 + outer loop + vertex -393.229 155.694 178.819 + vertex -389.987 154.925 186.297 + vertex -395.106 146.967 178.706 + endloop + endfacet + facet normal 0.901481 -0.188818 -0.389461 + outer loop + vertex -398.236 147.698 171.106 + vertex -393.229 155.694 178.819 + vertex -395.106 146.967 178.706 + endloop + endfacet + facet normal 0.900707 -0.192421 -0.389489 + outer loop + vertex -398.236 147.698 171.106 + vertex -395.106 146.967 178.706 + vertex -400.118 138.762 171.169 + endloop + endfacet + facet normal 0.908108 -0.193849 -0.371163 + outer loop + vertex -403.113 139.464 163.475 + vertex -398.236 147.698 171.106 + vertex -400.118 138.762 171.169 + endloop + endfacet + facet normal 0.905656 -0.204905 -0.371216 + outer loop + vertex -403.113 139.464 163.475 + vertex -400.118 138.762 171.169 + vertex -405.057 130.112 163.895 + endloop + endfacet + facet normal 0.913094 -0.205593 -0.352124 + outer loop + vertex -407.895 130.785 156.142 + vertex -403.113 139.464 163.475 + vertex -405.057 130.112 163.895 + endloop + endfacet + facet normal 0.908449 -0.225229 -0.352127 + outer loop + vertex -407.895 130.785 156.142 + vertex -405.057 130.112 163.895 + vertex -410.006 121.064 156.913 + endloop + endfacet + facet normal 0.913261 -0.206501 -0.351157 + outer loop + vertex -405.938 140.139 155.73 + vertex -403.113 139.464 163.475 + vertex -407.895 130.785 156.142 + endloop + endfacet + facet normal 0.920781 -0.207166 -0.330521 + outer loop + vertex -410.53 131.424 148.4 + vertex -405.938 140.139 155.73 + vertex -407.895 130.785 156.142 + endloop + endfacet + facet normal 0.91615 -0.226718 -0.330559 + outer loop + vertex -410.53 131.424 148.4 + vertex -407.895 130.785 156.142 + vertex -412.669 121.701 149.141 + endloop + endfacet + facet normal 0.921024 -0.208655 -0.328902 + outer loop + vertex -408.557 140.772 147.996 + vertex -405.938 140.139 155.73 + vertex -410.53 131.424 148.4 + endloop + endfacet + facet normal 0.92863 -0.209287 -0.306342 + outer loop + vertex -412.935 132.017 140.705 + vertex -408.557 140.772 147.996 + vertex -410.53 131.424 148.4 + endloop + endfacet + facet normal 0.923944 -0.229014 -0.306399 + outer loop + vertex -412.935 132.017 140.705 + vertex -410.53 131.424 148.4 + vertex -415.095 122.296 141.457 + endloop + endfacet + facet normal 0.928909 -0.211271 -0.304127 + outer loop + vertex -410.947 141.366 140.284 + vertex -408.557 140.772 147.996 + vertex -412.935 132.017 140.705 + endloop + endfacet + facet normal 0.936543 -0.211779 -0.279351 + outer loop + vertex -415.101 132.572 133.022 + vertex -410.947 141.366 140.284 + vertex -412.935 132.017 140.705 + endloop + endfacet + facet normal 0.931745 -0.231863 -0.279448 + outer loop + vertex -415.101 132.572 133.022 + vertex -412.935 132.017 140.705 + vertex -417.284 122.851 133.81 + endloop + endfacet + facet normal 0.936818 -0.214216 -0.276557 + outer loop + vertex -413.09 141.917 132.596 + vertex -410.947 141.366 140.284 + vertex -415.101 132.572 133.022 + endloop + endfacet + facet normal 0.944055 -0.214581 -0.250429 + outer loop + vertex -417.017 133.088 125.357 + vertex -413.09 141.917 132.596 + vertex -415.101 132.572 133.022 + endloop + endfacet + facet normal 0.939256 -0.234544 -0.250573 + outer loop + vertex -417.017 133.088 125.357 + vertex -415.101 132.572 133.022 + vertex -419.243 123.369 126.112 + endloop + endfacet + facet normal 0.944275 -0.217283 -0.247252 + outer loop + vertex -414.972 142.42 124.967 + vertex -413.09 141.917 132.596 + vertex -417.017 133.088 125.357 + endloop + endfacet + facet normal 0.950843 -0.217597 -0.220338 + outer loop + vertex -418.66 133.56 117.803 + vertex -414.972 142.42 124.967 + vertex -417.017 133.088 125.357 + endloop + endfacet + facet normal 0.946132 -0.23707 -0.220529 + outer loop + vertex -418.66 133.56 117.803 + vertex -417.017 133.088 125.357 + vertex -420.94 123.846 118.464 + endloop + endfacet + facet normal 0.950963 -0.22006 -0.217353 + outer loop + vertex -416.581 142.895 117.446 + vertex -414.972 142.42 124.967 + vertex -418.66 133.56 117.803 + endloop + endfacet + facet normal 0.957217 -0.220313 -0.187611 + outer loop + vertex -420.009 133.991 110.412 + vertex -416.581 142.895 117.446 + vertex -418.66 133.56 117.803 + endloop + endfacet + facet normal 0.952405 -0.240049 -0.187885 + outer loop + vertex -420.009 133.991 110.412 + vertex -418.66 133.56 117.803 + vertex -422.333 124.269 111.052 + endloop + endfacet + facet normal 0.957253 -0.223122 -0.184074 + outer loop + vertex -417.901 143.335 110.052 + vertex -416.581 142.895 117.446 + vertex -420.009 133.991 110.412 + endloop + endfacet + facet normal 0.963311 -0.223142 -0.149129 + outer loop + vertex -421.054 134.37 103.094 + vertex -417.901 143.335 110.052 + vertex -420.009 133.991 110.412 + endloop + endfacet + facet normal 0.958229 -0.243833 -0.149473 + outer loop + vertex -421.054 134.37 103.094 + vertex -420.009 133.991 110.412 + vertex -423.419 124.64 103.806 + endloop + endfacet + facet normal 0.963655 -0.242429 -0.11224 + outer loop + vertex -424.195 124.947 96.4863 + vertex -421.054 134.37 103.094 + vertex -423.419 124.64 103.806 + endloop + endfacet + facet normal 0.954437 -0.276319 -0.112681 + outer loop + vertex -424.195 124.947 96.4863 + vertex -423.419 124.64 103.806 + vertex -425.79 118.656 98.3986 + endloop + endfacet + facet normal 0.957538 -0.271951 -0.095728 + outer loop + vertex -426.392 117.923 94.4585 + vertex -424.195 124.947 96.4863 + vertex -425.79 118.656 98.3986 + endloop + endfacet + facet normal 0.94818 -0.305275 -0.0880977 + outer loop + vertex -426.392 117.923 94.4585 + vertex -425.79 118.656 98.3986 + vertex -427.732 113.64 94.8815 + endloop + endfacet + facet normal 0.957528 -0.281289 -0.0633735 + outer loop + vertex -426.392 117.923 94.4585 + vertex -426.331 118.916 90.9756 + vertex -424.195 124.947 96.4863 + endloop + endfacet + facet normal 0.956728 -0.284923 -0.0590869 + outer loop + vertex -424.61 125.1 89.021 + vertex -424.195 124.947 96.4863 + vertex -426.331 118.916 90.9756 + endloop + endfacet + facet normal 0.959456 -0.279204 -0.0385905 + outer loop + vertex -426.731 118.093 86.9664 + vertex -424.61 125.1 89.021 + vertex -426.331 118.916 90.9756 + endloop + endfacet + facet normal 0.950352 -0.309583 -0.0314468 + outer loop + vertex -426.731 118.093 86.9664 + vertex -426.331 118.916 90.9756 + vertex -428.092 113.873 87.4076 + endloop + endfacet + facet normal 0.95164 -0.307181 -0.00451215 + outer loop + vertex -428.11 113.87 83.6694 + vertex -426.731 118.093 86.9664 + vertex -428.092 113.873 87.4076 + endloop + endfacet + facet normal 0.937376 -0.348291 -0.0044015 + outer loop + vertex -428.11 113.87 83.6694 + vertex -428.092 113.873 87.4076 + vertex -429.704 109.582 83.6966 + endloop + endfacet + facet normal 0.950619 -0.31036 -1.36725e-05 + outer loop + vertex -426.455 118.941 83.4506 + vertex -426.731 118.093 86.9664 + vertex -428.11 113.87 83.6694 + endloop + endfacet + facet normal 0.95045 -0.30873 0.0364682 + outer loop + vertex -427.992 113.794 79.9474 + vertex -426.455 118.941 83.4506 + vertex -428.11 113.87 83.6694 + endloop + endfacet + facet normal 0.94859 -0.31341 0.0441605 + outer loop + vertex -426.569 118.037 79.4779 + vertex -426.455 118.941 83.4506 + vertex -427.992 113.794 79.9474 + endloop + endfacet + facet normal 0.958507 -0.282674 0.0368831 + outer loop + vertex -426.569 118.037 79.4779 + vertex -424.567 125.108 81.6581 + vertex -426.455 118.941 83.4506 + endloop + endfacet + facet normal 0.956619 -0.291293 0.00524119 + outer loop + vertex -424.567 125.108 81.6581 + vertex -424.61 125.1 89.021 + vertex -426.455 118.941 83.4506 + endloop + endfacet + facet normal 0.967761 -0.251814 0.00534608 + outer loop + vertex -424.567 125.108 81.6581 + vertex -422.107 134.705 88.2455 + vertex -424.61 125.1 89.021 + endloop + endfacet + facet normal 0.966481 -0.256431 0.0125511 + outer loop + vertex -422.011 134.717 81.1257 + vertex -422.107 134.705 88.2455 + vertex -424.567 125.108 81.6581 + endloop + endfacet + facet normal 0.972135 -0.234081 0.0126647 + outer loop + vertex -422.011 134.717 81.1257 + vertex -419.874 143.954 87.81 + vertex -422.107 134.705 88.2455 + endloop + endfacet + facet normal 0.971361 -0.237004 0.0169518 + outer loop + vertex -419.759 143.926 80.8212 + vertex -419.874 143.954 87.81 + vertex -422.011 134.717 81.1257 + endloop + endfacet + facet normal 0.973966 -0.226061 0.0169503 + outer loop + vertex -419.759 143.926 80.8212 + vertex -417.814 152.821 87.7092 + vertex -419.874 143.954 87.81 + endloop + endfacet + facet normal 0.973548 -0.227678 0.0191566 + outer loop + vertex -417.696 152.742 80.7778 + vertex -417.814 152.821 87.7092 + vertex -419.759 143.926 80.8212 + endloop + endfacet + facet normal 0.974813 -0.222203 0.0191156 + outer loop + vertex -417.696 152.742 80.7778 + vertex -415.832 161.523 87.7866 + vertex -417.814 152.821 87.7092 + endloop + endfacet + facet normal 0.974285 -0.224258 0.0218311 + outer loop + vertex -415.692 161.453 80.8345 + vertex -415.832 161.523 87.7866 + vertex -417.696 152.742 80.7778 + endloop + endfacet + facet normal 0.975256 -0.22 0.0218078 + outer loop + vertex -415.692 161.453 80.8345 + vertex -413.864 170.253 87.8527 + vertex -415.832 161.523 87.7866 + endloop + endfacet + facet normal 0.97432 -0.223595 0.0265581 + outer loop + vertex -413.678 170.229 80.8382 + vertex -413.864 170.253 87.8527 + vertex -415.692 161.453 80.8345 + endloop + endfacet + facet normal 0.97534 -0.219101 0.0265698 + outer loop + vertex -413.678 170.229 80.8382 + vertex -411.878 179.089 87.8017 + vertex -413.864 170.253 87.8527 + endloop + endfacet + facet normal 0.974472 -0.222364 0.0309465 + outer loop + vertex -411.646 179.121 80.7498 + vertex -411.878 179.089 87.8017 + vertex -413.678 170.229 80.8382 + endloop + endfacet + facet normal 0.977786 -0.207281 0.0311244 + outer loop + vertex -411.646 179.121 80.7498 + vertex -409.969 188.088 87.7698 + vertex -411.878 179.089 87.8017 + endloop + endfacet + facet normal 0.977704 -0.207603 0.0315542 + outer loop + vertex -409.727 188.156 80.7339 + vertex -409.969 188.088 87.7698 + vertex -411.646 179.121 80.7498 + endloop + endfacet + facet normal 0.987568 -0.153813 0.032415 + outer loop + vertex -409.727 188.156 80.7339 + vertex -408.53 197.401 88.1358 + vertex -409.969 188.088 87.7698 + endloop + endfacet + facet normal 0.988012 -0.151532 0.0294941 + outer loop + vertex -408.306 197.449 80.857 + vertex -408.53 197.401 88.1358 + vertex -409.727 188.156 80.7339 + endloop + endfacet + facet normal 0.95255 -0.293961 0.078959 + outer loop + vertex -426.569 118.037 79.4779 + vertex -425.968 119.154 76.3873 + vertex -424.567 125.108 81.6581 + endloop + endfacet + facet normal 0.956536 -0.283918 0.0665565 + outer loop + vertex -424.064 125.303 75.2528 + vertex -424.567 125.108 81.6581 + vertex -425.968 119.154 76.3873 + endloop + endfacet + facet normal 0.95527 -0.276399 0.10518 + outer loop + vertex -425.711 118.986 73.6151 + vertex -424.064 125.303 75.2528 + vertex -425.968 119.154 76.3873 + endloop + endfacet + facet normal 0.946777 -0.303915 0.106061 + outer loop + vertex -425.711 118.986 73.6151 + vertex -425.968 119.154 76.3873 + vertex -427.053 114.694 73.2961 + endloop + endfacet + facet normal 0.965068 -0.252974 0.0681699 + outer loop + vertex -424.064 125.303 75.2528 + vertex -422.011 134.717 81.1257 + vertex -424.567 125.108 81.6581 + endloop + endfacet + facet normal 0.965312 -0.252339 0.0670672 + outer loop + vertex -421.472 135.18 75.1095 + vertex -422.011 134.717 81.1257 + vertex -424.064 125.303 75.2528 + endloop + endfacet + facet normal 0.969592 -0.234858 0.0687971 + outer loop + vertex -421.472 135.18 75.1095 + vertex -419.759 143.926 80.8212 + vertex -422.011 134.717 81.1257 + endloop + endfacet + facet normal 0.969686 -0.234595 0.0683669 + outer loop + vertex -419.281 144.203 74.9939 + vertex -419.759 143.926 80.8212 + vertex -421.472 135.18 75.1095 + endloop + endfacet + facet normal 0.971469 -0.226947 0.0688761 + outer loop + vertex -419.281 144.203 74.9939 + vertex -417.696 152.742 80.7778 + vertex -419.759 143.926 80.8212 + endloop + endfacet + facet normal 0.971362 -0.227254 0.0693592 + outer loop + vertex -417.23 152.964 74.9777 + vertex -417.696 152.742 80.7778 + vertex -419.281 144.203 74.9939 + endloop + endfacet + facet normal 0.97209 -0.224064 0.0695401 + outer loop + vertex -417.23 152.964 74.9777 + vertex -415.692 161.453 80.8345 + vertex -417.696 152.742 80.7778 + endloop + endfacet + facet normal 0.971389 -0.226101 0.0726774 + outer loop + vertex -415.188 161.75 75.0192 + vertex -415.692 161.453 80.8345 + vertex -417.23 152.964 74.9777 + endloop + endfacet + facet normal 0.972067 -0.223097 0.0728898 + outer loop + vertex -415.188 161.75 75.0192 + vertex -413.678 170.229 80.8382 + vertex -415.692 161.453 80.8345 + endloop + endfacet + facet normal 0.971172 -0.225652 0.0768448 + outer loop + vertex -413.129 170.602 74.9907 + vertex -413.678 170.229 80.8382 + vertex -415.188 161.75 75.0192 + endloop + endfacet + facet normal 0.972129 -0.221369 0.0772077 + outer loop + vertex -413.129 170.602 74.9907 + vertex -411.646 179.121 80.7498 + vertex -413.678 170.229 80.8382 + endloop + endfacet + facet normal 0.971423 -0.223351 0.0803208 + outer loop + vertex -411.077 179.502 74.9264 + vertex -411.646 179.121 80.7498 + vertex -413.129 170.602 74.9907 + endloop + endfacet + facet normal 0.974936 -0.206926 0.081739 + outer loop + vertex -411.077 179.502 74.9264 + vertex -409.727 188.156 80.7339 + vertex -411.646 179.121 80.7498 + endloop + endfacet + facet normal 0.974509 -0.208159 0.083676 + outer loop + vertex -409.19 188.307 74.851 + vertex -409.727 188.156 80.7339 + vertex -411.077 179.502 74.9264 + endloop + endfacet + facet normal 0.984663 -0.151769 0.0860493 + outer loop + vertex -409.19 188.307 74.851 + vertex -408.306 197.449 80.857 + vertex -409.727 188.156 80.7339 + endloop + endfacet + facet normal 0.981787 -0.161108 0.100687 + outer loop + vertex -407.635 197.374 74.199 + vertex -408.306 197.449 80.857 + vertex -409.19 188.307 74.851 + endloop + endfacet + facet normal 0.948409 -0.30856 0.072875 + outer loop + vertex -425.968 119.154 76.3873 + vertex -426.569 118.037 79.4779 + vertex -427.677 113.9 76.3916 + endloop + endfacet + facet normal 0.951894 -0.303743 -0.0404615 + outer loop + vertex -428.092 113.873 87.4076 + vertex -426.331 118.916 90.9756 + vertex -427.963 113.778 91.1476 + endloop + endfacet + facet normal 0.956659 -0.291165 0.00508583 + outer loop + vertex -426.731 118.093 86.9664 + vertex -426.455 118.941 83.4506 + vertex -424.61 125.1 89.021 + endloop + endfacet + facet normal 0.967273 -0.24681 -0.0588901 + outer loop + vertex -424.61 125.1 89.021 + vertex -421.771 134.631 95.7028 + vertex -424.195 124.947 96.4863 + endloop + endfacet + facet normal 0.965736 -0.255427 -0.0459456 + outer loop + vertex -422.107 134.705 88.2455 + vertex -421.771 134.631 95.7028 + vertex -424.61 125.1 89.021 + endloop + endfacet + facet normal 0.971851 -0.231068 -0.0459787 + outer loop + vertex -422.107 134.705 88.2455 + vertex -419.582 143.928 95.2551 + vertex -421.771 134.631 95.7028 + endloop + endfacet + facet normal 0.968025 -0.23249 -0.0942106 + outer loop + vertex -419.582 143.928 95.2551 + vertex -418.911 143.707 102.694 + vertex -421.771 134.631 95.7028 + endloop + endfacet + facet normal 0.968612 -0.226707 -0.101958 + outer loop + vertex -421.771 134.631 95.7028 + vertex -418.911 143.707 102.694 + vertex -421.054 134.37 103.094 + endloop + endfacet + facet normal 0.971126 -0.219228 -0.094096 + outer loop + vertex -419.582 143.928 95.2551 + vertex -416.903 152.636 102.613 + vertex -418.911 143.707 102.694 + endloop + endfacet + facet normal 0.965791 -0.218443 -0.139754 + outer loop + vertex -416.903 152.636 102.613 + vertex -415.918 152.269 109.998 + vertex -418.911 143.707 102.694 + endloop + endfacet + facet normal 0.965948 -0.215261 -0.143549 + outer loop + vertex -418.911 143.707 102.694 + vertex -415.918 152.269 109.998 + vertex -417.901 143.335 110.052 + endloop + endfacet + facet normal 0.959876 -0.214142 -0.181059 + outer loop + vertex -415.918 152.269 109.998 + vertex -414.621 151.826 117.394 + vertex -417.901 143.335 110.052 + endloop + endfacet + facet normal 0.960894 -0.209603 -0.180965 + outer loop + vertex -415.918 152.269 109.998 + vertex -412.699 160.548 117.497 + vertex -414.621 151.826 117.394 + endloop + endfacet + facet normal 0.954567 -0.207822 -0.213568 + outer loop + vertex -412.699 160.548 117.497 + vertex -411.125 160.07 125 + vertex -414.621 151.826 117.394 + endloop + endfacet + facet normal 0.954534 -0.206421 -0.215071 + outer loop + vertex -414.621 151.826 117.394 + vertex -411.125 160.07 125 + vertex -413.033 151.35 124.902 + endloop + endfacet + facet normal 0.953621 -0.210527 -0.215138 + outer loop + vertex -414.621 151.826 117.394 + vertex -413.033 151.35 124.902 + vertex -416.581 142.895 117.446 + endloop + endfacet + facet normal 0.947943 -0.204654 -0.243969 + outer loop + vertex -411.125 160.07 125 + vertex -409.272 159.568 132.62 + vertex -413.033 151.35 124.902 + endloop + endfacet + facet normal 0.947863 -0.203141 -0.24554 + outer loop + vertex -413.033 151.35 124.902 + vertex -409.272 159.568 132.62 + vertex -411.166 150.843 132.526 + endloop + endfacet + facet normal 0.946914 -0.207455 -0.245595 + outer loop + vertex -413.033 151.35 124.902 + vertex -411.166 150.843 132.526 + vertex -414.972 142.42 124.967 + endloop + endfacet + facet normal 0.940661 -0.201277 -0.273211 + outer loop + vertex -409.272 159.568 132.62 + vertex -407.154 159.03 140.31 + vertex -411.166 150.843 132.526 + endloop + endfacet + facet normal 0.940566 -0.200097 -0.274403 + outer loop + vertex -411.166 150.843 132.526 + vertex -407.154 159.03 140.31 + vertex -409.04 150.302 140.21 + endloop + endfacet + facet normal 0.939566 -0.204679 -0.274449 + outer loop + vertex -411.166 150.843 132.526 + vertex -409.04 150.302 140.21 + vertex -413.09 141.917 132.596 + endloop + endfacet + facet normal 0.932678 -0.198082 -0.301455 + outer loop + vertex -407.154 159.03 140.31 + vertex -404.782 158.45 148.03 + vertex -409.04 150.302 140.21 + endloop + endfacet + facet normal 0.932557 -0.196949 -0.30257 + outer loop + vertex -409.04 150.302 140.21 + vertex -404.782 158.45 148.03 + vertex -406.66 149.716 147.925 + endloop + endfacet + facet normal 0.931608 -0.20133 -0.30261 + outer loop + vertex -409.04 150.302 140.21 + vertex -406.66 149.716 147.925 + vertex -410.947 141.366 140.284 + endloop + endfacet + facet normal 0.924547 -0.194929 -0.327438 + outer loop + vertex -404.782 158.45 148.03 + vertex -402.173 157.824 155.768 + vertex -406.66 149.716 147.925 + endloop + endfacet + facet normal 0.924477 -0.194393 -0.327953 + outer loop + vertex -406.66 149.716 147.925 + vertex -402.173 157.824 155.768 + vertex -404.048 149.083 155.664 + endloop + endfacet + facet normal 0.923599 -0.198464 -0.327989 + outer loop + vertex -406.66 149.716 147.925 + vertex -404.048 149.083 155.664 + vertex -408.557 140.772 147.996 + endloop + endfacet + facet normal 0.916558 -0.192425 -0.350563 + outer loop + vertex -402.173 157.824 155.768 + vertex -399.353 157.153 163.509 + vertex -404.048 149.083 155.664 + endloop + endfacet + facet normal 0.916577 -0.192553 -0.350442 + outer loop + vertex -404.048 149.083 155.664 + vertex -399.353 157.153 163.509 + vertex -401.229 148.409 163.407 + endloop + endfacet + facet normal 0.9158 -0.196158 -0.350473 + outer loop + vertex -404.048 149.083 155.664 + vertex -401.229 148.409 163.407 + vertex -405.938 140.139 155.73 + endloop + endfacet + facet normal 0.909018 -0.190696 -0.37057 + outer loop + vertex -399.353 157.153 163.509 + vertex -396.363 156.44 171.211 + vertex -401.229 148.409 163.407 + endloop + endfacet + facet normal 0.908958 -0.190341 -0.370899 + outer loop + vertex -401.229 148.409 163.407 + vertex -396.363 156.44 171.211 + vertex -398.236 147.698 171.106 + endloop + endfacet + facet normal 0.90899 -0.190824 -0.370571 + outer loop + vertex -399.353 157.153 163.509 + vertex -394.479 165.207 171.317 + vertex -396.363 156.44 171.211 + endloop + endfacet + facet normal 0.901389 -0.18896 -0.389605 + outer loop + vertex -394.479 165.207 171.317 + vertex -391.346 164.457 178.93 + vertex -396.363 156.44 171.211 + endloop + endfacet + facet normal 0.901358 -0.188796 -0.389755 + outer loop + vertex -396.363 156.44 171.211 + vertex -391.346 164.457 178.93 + vertex -393.229 155.694 178.819 + endloop + endfacet + facet normal 0.89403 -0.187002 -0.407112 + outer loop + vertex -391.346 164.457 178.93 + vertex -388.101 163.672 186.416 + vertex -393.229 155.694 178.819 + endloop + endfacet + facet normal 0.894314 -0.185677 -0.407096 + outer loop + vertex -391.346 164.457 178.93 + vertex -386.229 172.565 186.473 + vertex -388.101 163.672 186.416 + endloop + endfacet + facet normal 0.887293 -0.184096 -0.42287 + outer loop + vertex -386.229 172.565 186.473 + vertex -382.897 171.738 193.825 + vertex -388.101 163.672 186.416 + endloop + endfacet + facet normal 0.88727 -0.183998 -0.422961 + outer loop + vertex -388.101 163.672 186.416 + vertex -382.897 171.738 193.825 + vertex -384.769 162.859 193.759 + endloop + endfacet + facet normal 0.880474 -0.182456 -0.43758 + outer loop + vertex -382.897 171.738 193.825 + vertex -379.498 170.877 201.023 + vertex -384.769 162.859 193.759 + endloop + endfacet + facet normal 0.883429 -0.168333 -0.437284 + outer loop + vertex -382.897 171.738 193.825 + vertex -377.746 179.923 201.08 + vertex -379.498 170.877 201.023 + endloop + endfacet + facet normal 0.877369 -0.167081 -0.449786 + outer loop + vertex -377.746 179.923 201.08 + vertex -374.306 179.016 208.127 + vertex -379.498 170.877 201.023 + endloop + endfacet + facet normal 0.877088 -0.16611 -0.450693 + outer loop + vertex -379.498 170.877 201.023 + vertex -374.306 179.016 208.127 + vertex -376.055 169.978 208.054 + endloop + endfacet + facet normal 0.885076 -0.125524 -0.4482 + outer loop + vertex -377.746 179.923 201.08 + vertex -372.909 188.286 208.29 + vertex -374.306 179.016 208.127 + endloop + endfacet + facet normal 0.87945 -0.124479 -0.459427 + outer loop + vertex -372.909 188.286 208.29 + vertex -369.393 187.325 215.281 + vertex -374.306 179.016 208.127 + endloop + endfacet + facet normal 0.879052 -0.12332 -0.460499 + outer loop + vertex -374.306 179.016 208.127 + vertex -369.393 187.325 215.281 + vertex -370.854 178.069 214.969 + endloop + endfacet + facet normal 0.885255 -0.126061 -0.447697 + outer loop + vertex -376.327 189.18 201.279 + vertex -372.909 188.286 208.29 + vertex -377.746 179.923 201.08 + endloop + endfacet + facet normal 0.891278 -0.127253 -0.435236 + outer loop + vertex -381.135 180.786 193.888 + vertex -376.327 189.18 201.279 + vertex -377.746 179.923 201.08 + endloop + endfacet + facet normal 0.891321 -0.127388 -0.435109 + outer loop + vertex -379.682 190.026 194.158 + vertex -376.327 189.18 201.279 + vertex -381.135 180.786 193.888 + endloop + endfacet + facet normal 0.897665 -0.128786 -0.421439 + outer loop + vertex -384.474 181.612 186.523 + vertex -379.682 190.026 194.158 + vertex -381.135 180.786 193.888 + endloop + endfacet + facet normal 0.890129 -0.170327 -0.422681 + outer loop + vertex -384.474 181.612 186.523 + vertex -381.135 180.786 193.888 + vertex -386.229 172.565 186.473 + endloop + endfacet + facet normal 0.897195 -0.171784 -0.406855 + outer loop + vertex -389.475 173.353 178.981 + vertex -384.474 181.612 186.523 + vertex -386.229 172.565 186.473 + endloop + endfacet + facet normal 0.897236 -0.171959 -0.406692 + outer loop + vertex -387.716 182.391 179.042 + vertex -384.474 181.612 186.523 + vertex -389.475 173.353 178.981 + endloop + endfacet + facet normal 0.904539 -0.173497 -0.389497 + outer loop + vertex -392.611 174.098 171.368 + vertex -387.716 182.391 179.042 + vertex -389.475 173.353 178.981 + endloop + endfacet + facet normal 0.901711 -0.187263 -0.389679 + outer loop + vertex -392.611 174.098 171.368 + vertex -389.475 173.353 178.981 + vertex -394.479 165.207 171.317 + endloop + endfacet + facet normal 0.909204 -0.188945 -0.37101 + outer loop + vertex -397.474 165.916 163.617 + vertex -392.611 174.098 171.368 + vertex -394.479 165.207 171.317 + endloop + endfacet + facet normal 0.909155 -0.188673 -0.371267 + outer loop + vertex -395.608 174.803 163.67 + vertex -392.611 174.098 171.368 + vertex -397.474 165.916 163.617 + endloop + endfacet + facet normal 0.917074 -0.19046 -0.350286 + outer loop + vertex -400.292 166.582 155.878 + vertex -395.608 174.803 163.67 + vertex -397.474 165.916 163.617 + endloop + endfacet + facet normal 0.916639 -0.192511 -0.350303 + outer loop + vertex -400.292 166.582 155.878 + vertex -397.474 165.916 163.617 + vertex -402.173 157.824 155.768 + endloop + endfacet + facet normal 0.917104 -0.190648 -0.350105 + outer loop + vertex -398.425 175.463 155.932 + vertex -395.608 174.803 163.67 + vertex -400.292 166.582 155.878 + endloop + endfacet + facet normal 0.925213 -0.192492 -0.326998 + outer loop + vertex -402.898 167.202 148.137 + vertex -398.425 175.463 155.932 + vertex -400.292 166.582 155.878 + endloop + endfacet + facet normal 0.924691 -0.194948 -0.327019 + outer loop + vertex -402.898 167.202 148.137 + vertex -400.292 166.582 155.878 + vertex -404.782 158.45 148.03 + endloop + endfacet + facet normal 0.925327 -0.193322 -0.326184 + outer loop + vertex -401.028 176.079 148.181 + vertex -398.425 175.463 155.932 + vertex -402.898 167.202 148.137 + endloop + endfacet + facet normal 0.93359 -0.195188 -0.30052 + outer loop + vertex -405.266 167.779 140.408 + vertex -401.028 176.079 148.181 + vertex -402.898 167.202 148.137 + endloop + endfacet + facet normal 0.933001 -0.197942 -0.300545 + outer loop + vertex -405.266 167.779 140.408 + vertex -402.898 167.202 148.137 + vertex -407.154 159.03 140.31 + endloop + endfacet + facet normal 0.933714 -0.196287 -0.299414 + outer loop + vertex -403.392 176.651 140.436 + vertex -401.028 176.079 148.181 + vertex -405.266 167.779 140.408 + endloop + endfacet + facet normal 0.941686 -0.198057 -0.272033 + outer loop + vertex -407.378 168.312 132.708 + vertex -403.392 176.651 140.436 + vertex -405.266 167.779 140.408 + endloop + endfacet + facet normal 0.941035 -0.201082 -0.272064 + outer loop + vertex -407.378 168.312 132.708 + vertex -405.266 167.779 140.408 + vertex -409.272 159.568 132.62 + endloop + endfacet + facet normal 0.941825 -0.199665 -0.270369 + outer loop + vertex -405.491 177.182 132.733 + vertex -403.392 176.651 140.436 + vertex -407.378 168.312 132.708 + endloop + endfacet + facet normal 0.949061 -0.201283 -0.242423 + outer loop + vertex -409.219 168.811 125.087 + vertex -405.491 177.182 132.733 + vertex -407.378 168.312 132.708 + endloop + endfacet + facet normal 0.948392 -0.204363 -0.242463 + outer loop + vertex -409.219 168.811 125.087 + vertex -407.378 168.312 132.708 + vertex -411.125 160.07 125 + endloop + endfacet + facet normal 0.9491 -0.201956 -0.241706 + outer loop + vertex -407.32 177.678 125.134 + vertex -405.491 177.182 132.733 + vertex -409.219 168.811 125.087 + endloop + endfacet + facet normal 0.955734 -0.20353 -0.21248 + outer loop + vertex -410.781 169.289 117.601 + vertex -407.32 177.678 125.134 + vertex -409.219 168.811 125.087 + endloop + endfacet + facet normal 0.954973 -0.207005 -0.212543 + outer loop + vertex -410.781 169.289 117.601 + vertex -409.219 168.811 125.087 + vertex -412.699 160.548 117.497 + endloop + endfacet + facet normal 0.96128 -0.208779 -0.179869 + outer loop + vertex -413.985 160.999 110.102 + vertex -410.781 169.289 117.601 + vertex -412.699 160.548 117.497 + endloop + endfacet + facet normal 0.96127 -0.209641 -0.178912 + outer loop + vertex -412.054 169.739 110.235 + vertex -410.781 169.289 117.601 + vertex -413.985 160.999 110.102 + endloop + endfacet + facet normal 0.967597 -0.211667 -0.137668 + outer loop + vertex -414.956 161.365 102.714 + vertex -412.054 169.739 110.235 + vertex -413.985 160.999 110.102 + endloop + endfacet + facet normal 0.967053 -0.214108 -0.137718 + outer loop + vertex -414.956 161.365 102.714 + vertex -413.985 160.999 110.102 + vertex -416.903 152.636 102.613 + endloop + endfacet + facet normal 0.972263 -0.215821 -0.0901471 + outer loop + vertex -417.551 152.839 95.1408 + vertex -414.956 161.365 102.714 + vertex -416.903 152.636 102.613 + endloop + endfacet + facet normal 0.971975 -0.218279 -0.0872813 + outer loop + vertex -415.586 161.551 95.2305 + vertex -414.956 161.365 102.714 + vertex -417.551 152.839 95.1408 + endloop + endfacet + facet normal 0.975018 -0.219514 -0.0339621 + outer loop + vertex -417.814 152.821 87.7092 + vertex -415.586 161.551 95.2305 + vertex -417.551 152.839 95.1408 + endloop + endfacet + facet normal 0.973419 -0.226512 -0.0338884 + outer loop + vertex -417.814 152.821 87.7092 + vertex -417.551 152.839 95.1408 + vertex -419.874 143.954 87.81 + endloop + endfacet + facet normal 0.974148 -0.222527 -0.0389494 + outer loop + vertex -419.874 143.954 87.81 + vertex -417.551 152.839 95.1408 + vertex -419.582 143.928 95.2551 + endloop + endfacet + facet normal 0.974611 -0.221708 -0.0312939 + outer loop + vertex -415.832 161.523 87.7866 + vertex -415.586 161.551 95.2305 + vertex -417.814 152.821 87.7092 + endloop + endfacet + facet normal 0.975508 -0.217721 -0.0313386 + outer loop + vertex -415.832 161.523 87.7866 + vertex -413.635 170.274 95.3597 + vertex -415.586 161.551 95.2305 + endloop + endfacet + facet normal 0.972648 -0.216291 -0.0847051 + outer loop + vertex -413.635 170.274 95.3597 + vertex -413.021 170.099 102.862 + vertex -415.586 161.551 95.2305 + endloop + endfacet + facet normal 0.973968 -0.210279 -0.0846732 + outer loop + vertex -413.635 170.274 95.3597 + vertex -411.106 178.931 102.958 + vertex -413.021 170.099 102.862 + endloop + endfacet + facet normal 0.968597 -0.208564 -0.135357 + outer loop + vertex -411.106 178.931 102.958 + vertex -410.146 178.593 110.348 + vertex -413.021 170.099 102.862 + endloop + endfacet + facet normal 0.968676 -0.207039 -0.137118 + outer loop + vertex -413.021 170.099 102.862 + vertex -410.146 178.593 110.348 + vertex -412.054 169.739 110.235 + endloop + endfacet + facet normal 0.962235 -0.205116 -0.17897 + outer loop + vertex -410.146 178.593 110.348 + vertex -408.875 178.153 117.687 + vertex -412.054 169.739 110.235 + endloop + endfacet + facet normal 0.965376 -0.190118 -0.178616 + outer loop + vertex -410.146 178.593 110.348 + vertex -407.088 187.156 117.761 + vertex -408.875 178.153 117.687 + endloop + endfacet + facet normal 0.959063 -0.188597 -0.211258 + outer loop + vertex -407.088 187.156 117.761 + vertex -405.532 186.691 125.24 + vertex -408.875 178.153 117.687 + endloop + endfacet + facet normal 0.959023 -0.187787 -0.212157 + outer loop + vertex -408.875 178.153 117.687 + vertex -405.532 186.691 125.24 + vertex -407.32 177.678 125.134 + endloop + endfacet + facet normal 0.952417 -0.186132 -0.241364 + outer loop + vertex -405.532 186.691 125.24 + vertex -403.714 186.199 132.794 + vertex -407.32 177.678 125.134 + endloop + endfacet + facet normal 0.960387 -0.14104 -0.240344 + outer loop + vertex -405.532 186.691 125.24 + vertex -402.261 195.409 133.196 + vertex -403.714 186.199 132.794 + endloop + endfacet + facet normal 0.953262 -0.13869 -0.268433 + outer loop + vertex -402.261 195.409 133.196 + vertex -400.265 194.907 140.541 + vertex -403.714 186.199 132.794 + endloop + endfacet + facet normal 0.953171 -0.138091 -0.269066 + outer loop + vertex -403.714 186.199 132.794 + vertex -400.265 194.907 140.541 + vertex -401.626 185.673 140.458 + endloop + endfacet + facet normal 0.945032 -0.184394 -0.270023 + outer loop + vertex -403.714 186.199 132.794 + vertex -401.626 185.673 140.458 + vertex -405.491 177.182 132.733 + endloop + endfacet + facet normal 0.9447 -0.13658 -0.29814 + outer loop + vertex -400.265 194.907 140.541 + vertex -397.868 194.33 148.402 + vertex -401.626 185.673 140.458 + endloop + endfacet + facet normal 0.944858 -0.137496 -0.297217 + outer loop + vertex -401.626 185.673 140.458 + vertex -397.868 194.33 148.402 + vertex -399.273 185.105 148.203 + endloop + endfacet + facet normal 0.936904 -0.182592 -0.298111 + outer loop + vertex -401.626 185.673 140.458 + vertex -399.273 185.105 148.203 + vertex -403.392 176.651 140.436 + endloop + endfacet + facet normal 0.936004 -0.135553 -0.324842 + outer loop + vertex -397.868 194.33 148.402 + vertex -395.318 193.73 155.999 + vertex -399.273 185.105 148.203 + endloop + endfacet + facet normal 0.936097 -0.136011 -0.324381 + outer loop + vertex -399.273 185.105 148.203 + vertex -395.318 193.73 155.999 + vertex -396.665 184.489 155.987 + endloop + endfacet + facet normal 0.928378 -0.17978 -0.325259 + outer loop + vertex -399.273 185.105 148.203 + vertex -396.665 184.489 155.987 + vertex -401.028 176.079 148.181 + endloop + endfacet + facet normal 0.927426 -0.134716 -0.348901 + outer loop + vertex -395.318 193.73 155.999 + vertex -392.358 193.042 164.133 + vertex -396.665 184.489 155.987 + endloop + endfacet + facet normal 0.927499 -0.135066 -0.348572 + outer loop + vertex -396.665 184.489 155.987 + vertex -392.358 193.042 164.133 + vertex -393.852 183.832 163.728 + endloop + endfacet + facet normal 0.920038 -0.177257 -0.349442 + outer loop + vertex -396.665 184.489 155.987 + vertex -393.852 183.832 163.728 + vertex -398.425 175.463 155.932 + endloop + endfacet + facet normal 0.919495 -0.132826 -0.369982 + outer loop + vertex -392.358 193.042 164.133 + vertex -389.521 192.382 171.422 + vertex -393.852 183.832 163.728 + endloop + endfacet + facet normal 0.919481 -0.13277 -0.370037 + outer loop + vertex -393.852 183.832 163.728 + vertex -389.521 192.382 171.422 + vertex -390.856 183.132 171.423 + endloop + endfacet + facet normal 0.911998 -0.175049 -0.370969 + outer loop + vertex -393.852 183.832 163.728 + vertex -390.856 183.132 171.423 + vertex -395.608 174.803 163.67 + endloop + endfacet + facet normal 0.911838 -0.131668 -0.388863 + outer loop + vertex -389.521 192.382 171.422 + vertex -386.215 191.606 179.436 + vertex -390.856 183.132 171.423 + endloop + endfacet + facet normal 0.911895 -0.131898 -0.388652 + outer loop + vertex -390.856 183.132 171.423 + vertex -386.215 191.606 179.436 + vertex -387.716 182.391 179.042 + endloop + endfacet + facet normal 0.90462 -0.129975 -0.405917 + outer loop + vertex -386.215 191.606 179.436 + vertex -383.104 190.863 186.607 + vertex -387.716 182.391 179.042 + endloop + endfacet + facet normal 0.960809 -0.144818 -0.236378 + outer loop + vertex -404.11 195.9 125.378 + vertex -402.261 195.409 133.196 + vertex -405.532 186.691 125.24 + endloop + endfacet + facet normal 0.966678 -0.146116 -0.2102 + outer loop + vertex -407.088 187.156 117.761 + vertex -404.11 195.9 125.378 + vertex -405.532 186.691 125.24 + endloop + endfacet + facet normal 0.967318 -0.153888 -0.201529 + outer loop + vertex -405.665 196.34 117.578 + vertex -404.11 195.9 125.378 + vertex -407.088 187.156 117.761 + endloop + endfacet + facet normal 0.972601 -0.154158 -0.174019 + outer loop + vertex -408.348 187.566 110.357 + vertex -405.665 196.34 117.578 + vertex -407.088 187.156 117.761 + endloop + endfacet + facet normal 0.972958 -0.161902 -0.164743 + outer loop + vertex -406.869 196.709 110.104 + vertex -405.665 196.34 117.578 + vertex -408.348 187.566 110.357 + endloop + endfacet + facet normal 0.978467 -0.161785 -0.128173 + outer loop + vertex -409.269 187.87 102.937 + vertex -406.869 196.709 110.104 + vertex -408.348 187.566 110.357 + endloop + endfacet + facet normal 0.971319 -0.199847 -0.128844 + outer loop + vertex -409.269 187.87 102.937 + vertex -408.348 187.566 110.357 + vertex -411.106 178.931 102.958 + endloop + endfacet + facet normal 0.976347 -0.200763 -0.0802489 + outer loop + vertex -411.695 179.089 95.389 + vertex -409.269 187.87 102.937 + vertex -411.106 178.931 102.958 + endloop + endfacet + facet normal 0.975882 -0.204909 -0.0752766 + outer loop + vertex -409.819 188.033 95.3697 + vertex -409.269 187.87 102.937 + vertex -411.695 179.089 95.389 + endloop + endfacet + facet normal 0.978411 -0.205328 -0.0234963 + outer loop + vertex -411.878 179.089 87.8017 + vertex -409.819 188.033 95.3697 + vertex -411.695 179.089 95.389 + endloop + endfacet + facet normal 0.975355 -0.219393 -0.0234214 + outer loop + vertex -411.878 179.089 87.8017 + vertex -411.695 179.089 95.389 + vertex -413.864 170.253 87.8527 + endloop + endfacet + facet normal 0.976235 -0.214748 -0.0291202 + outer loop + vertex -413.864 170.253 87.8527 + vertex -411.695 179.089 95.389 + vertex -413.635 170.274 95.3597 + endloop + endfacet + facet normal 0.978011 -0.207513 -0.0208048 + outer loop + vertex -409.969 188.088 87.7698 + vertex -409.819 188.033 95.3697 + vertex -411.878 179.089 87.8017 + endloop + endfacet + facet normal 0.98668 -0.161355 -0.0206435 + outer loop + vertex -409.969 188.088 87.7698 + vertex -408.303 197.238 95.8584 + vertex -409.819 188.033 95.3697 + endloop + endfacet + facet normal 0.98393 -0.157536 -0.0840527 + outer loop + vertex -408.303 197.238 95.8584 + vertex -407.716 196.998 103.185 + vertex -409.819 188.033 95.3697 + endloop + endfacet + facet normal 0.987957 -0.151332 -0.0322444 + outer loop + vertex -408.53 197.401 88.1358 + vertex -408.303 197.238 95.8584 + vertex -409.969 188.088 87.7698 + endloop + endfacet + facet normal 0.983385 -0.165328 -0.0749687 + outer loop + vertex -409.819 188.033 95.3697 + vertex -407.716 196.998 103.185 + vertex -409.269 187.87 102.937 + endloop + endfacet + facet normal 0.97846 -0.163089 -0.126562 + outer loop + vertex -407.716 196.998 103.185 + vertex -406.869 196.709 110.104 + vertex -409.269 187.87 102.937 + endloop + endfacet + facet normal 0.965415 -0.193293 -0.174965 + outer loop + vertex -408.348 187.566 110.357 + vertex -407.088 187.156 117.761 + vertex -410.146 178.593 110.348 + endloop + endfacet + facet normal 0.971543 -0.194559 -0.135099 + outer loop + vertex -411.106 178.931 102.958 + vertex -408.348 187.566 110.357 + vertex -410.146 178.593 110.348 + endloop + endfacet + facet normal 0.973531 -0.213983 -0.080307 + outer loop + vertex -411.695 179.089 95.389 + vertex -411.106 178.931 102.958 + vertex -413.635 170.274 95.3597 + endloop + endfacet + facet normal 0.975158 -0.219593 -0.0290739 + outer loop + vertex -413.864 170.253 87.8527 + vertex -413.635 170.274 95.3597 + vertex -415.832 161.523 87.7866 + endloop + endfacet + facet normal 0.972909 -0.214092 -0.0872555 + outer loop + vertex -415.586 161.551 95.2305 + vertex -413.021 170.099 102.862 + vertex -414.956 161.365 102.714 + endloop + endfacet + facet normal 0.967574 -0.212063 -0.137219 + outer loop + vertex -413.021 170.099 102.862 + vertex -412.054 169.739 110.235 + vertex -414.956 161.365 102.714 + endloop + endfacet + facet normal 0.962235 -0.205257 -0.178811 + outer loop + vertex -412.054 169.739 110.235 + vertex -408.875 178.153 117.687 + vertex -410.781 169.289 117.601 + endloop + endfacet + facet normal 0.955734 -0.203533 -0.212476 + outer loop + vertex -408.875 178.153 117.687 + vertex -407.32 177.678 125.134 + vertex -410.781 169.289 117.601 + endloop + endfacet + facet normal 0.95241 -0.18604 -0.241464 + outer loop + vertex -407.32 177.678 125.134 + vertex -403.714 186.199 132.794 + vertex -405.491 177.182 132.733 + endloop + endfacet + facet normal 0.945017 -0.184248 -0.270176 + outer loop + vertex -405.491 177.182 132.733 + vertex -401.626 185.673 140.458 + vertex -403.392 176.651 140.436 + endloop + endfacet + facet normal 0.936758 -0.181474 -0.29925 + outer loop + vertex -403.392 176.651 140.436 + vertex -399.273 185.105 148.203 + vertex -401.028 176.079 148.181 + endloop + endfacet + facet normal 0.928258 -0.179002 -0.32603 + outer loop + vertex -401.028 176.079 148.181 + vertex -396.665 184.489 155.987 + vertex -398.425 175.463 155.932 + endloop + endfacet + facet normal 0.919945 -0.17673 -0.349953 + outer loop + vertex -398.425 175.463 155.932 + vertex -393.852 183.832 163.728 + vertex -395.608 174.803 163.67 + endloop + endfacet + facet normal 0.91197 -0.17491 -0.371102 + outer loop + vertex -395.608 174.803 163.67 + vertex -390.856 183.132 171.423 + vertex -392.611 174.098 171.368 + endloop + endfacet + facet normal 0.904507 -0.173348 -0.389638 + outer loop + vertex -390.856 183.132 171.423 + vertex -387.716 182.391 179.042 + vertex -392.611 174.098 171.368 + endloop + endfacet + facet normal 0.904716 -0.130314 -0.405595 + outer loop + vertex -387.716 182.391 179.042 + vertex -383.104 190.863 186.607 + vertex -384.474 181.612 186.523 + endloop + endfacet + facet normal 0.897769 -0.129144 -0.42111 + outer loop + vertex -383.104 190.863 186.607 + vertex -379.682 190.026 194.158 + vertex -384.474 181.612 186.523 + endloop + endfacet + facet normal 0.883616 -0.169022 -0.43664 + outer loop + vertex -381.135 180.786 193.888 + vertex -377.746 179.923 201.08 + vertex -382.897 171.738 193.825 + endloop + endfacet + facet normal 0.890145 -0.170391 -0.422622 + outer loop + vertex -386.229 172.565 186.473 + vertex -381.135 180.786 193.888 + vertex -382.897 171.738 193.825 + endloop + endfacet + facet normal 0.894319 -0.185701 -0.407073 + outer loop + vertex -389.475 173.353 178.981 + vertex -386.229 172.565 186.473 + vertex -391.346 164.457 178.93 + endloop + endfacet + facet normal 0.90173 -0.18736 -0.389588 + outer loop + vertex -394.479 165.207 171.317 + vertex -389.475 173.353 178.981 + vertex -391.346 164.457 178.93 + endloop + endfacet + facet normal 0.908908 -0.190336 -0.371023 + outer loop + vertex -397.474 165.916 163.617 + vertex -394.479 165.207 171.317 + vertex -399.353 157.153 163.509 + endloop + endfacet + facet normal 0.916598 -0.192238 -0.350561 + outer loop + vertex -402.173 157.824 155.768 + vertex -397.474 165.916 163.617 + vertex -399.353 157.153 163.509 + endloop + endfacet + facet normal 0.924635 -0.194516 -0.327434 + outer loop + vertex -404.782 158.45 148.03 + vertex -400.292 166.582 155.878 + vertex -402.173 157.824 155.768 + endloop + endfacet + facet normal 0.932904 -0.197029 -0.301446 + outer loop + vertex -407.154 159.03 140.31 + vertex -402.898 167.202 148.137 + vertex -404.782 158.45 148.03 + endloop + endfacet + facet normal 0.940945 -0.199963 -0.273197 + outer loop + vertex -409.272 159.568 132.62 + vertex -405.266 167.779 140.408 + vertex -407.154 159.03 140.31 + endloop + endfacet + facet normal 0.948317 -0.202941 -0.243947 + outer loop + vertex -411.125 160.07 125 + vertex -407.378 168.312 132.708 + vertex -409.272 159.568 132.62 + endloop + endfacet + facet normal 0.954951 -0.206083 -0.213537 + outer loop + vertex -412.699 160.548 117.497 + vertex -409.219 168.811 125.087 + vertex -411.125 160.07 125 + endloop + endfacet + facet normal 0.960884 -0.210556 -0.179909 + outer loop + vertex -413.985 160.999 110.102 + vertex -412.699 160.548 117.497 + vertex -415.918 152.269 109.998 + endloop + endfacet + facet normal 0.967149 -0.212424 -0.139636 + outer loop + vertex -416.903 152.636 102.613 + vertex -413.985 160.999 110.102 + vertex -415.918 152.269 109.998 + endloop + endfacet + facet normal 0.970771 -0.222414 -0.0901966 + outer loop + vertex -417.551 152.839 95.1408 + vertex -416.903 152.636 102.613 + vertex -419.582 143.928 95.2551 + endloop + endfacet + facet normal 0.970923 -0.236215 -0.0388715 + outer loop + vertex -419.874 143.954 87.81 + vertex -419.582 143.928 95.2551 + vertex -422.107 134.705 88.2455 + endloop + endfacet + facet normal 0.950049 -0.304146 -0.0700205 + outer loop + vertex -426.331 118.916 90.9756 + vertex -426.392 117.923 94.4585 + vertex -427.963 113.778 91.1476 + endloop + endfacet + facet normal 0.96303 -0.249253 -0.102212 + outer loop + vertex -421.771 134.631 95.7028 + vertex -421.054 134.37 103.094 + vertex -424.195 124.947 96.4863 + endloop + endfacet + facet normal 0.963166 -0.227248 -0.143773 + outer loop + vertex -418.911 143.707 102.694 + vertex -417.901 143.335 110.052 + vertex -421.054 134.37 103.094 + endloop + endfacet + facet normal 0.95988 -0.211718 -0.183864 + outer loop + vertex -417.901 143.335 110.052 + vertex -414.621 151.826 117.394 + vertex -416.581 142.895 117.446 + endloop + endfacet + facet normal 0.95356 -0.208691 -0.217191 + outer loop + vertex -416.581 142.895 117.446 + vertex -413.033 151.35 124.902 + vertex -414.972 142.42 124.967 + endloop + endfacet + facet normal 0.946823 -0.206029 -0.247139 + outer loop + vertex -414.972 142.42 124.967 + vertex -411.166 150.843 132.526 + vertex -413.09 141.917 132.596 + endloop + endfacet + facet normal 0.939391 -0.202773 -0.276455 + outer loop + vertex -413.09 141.917 132.596 + vertex -409.04 150.302 140.21 + vertex -410.947 141.366 140.284 + endloop + endfacet + facet normal 0.931443 -0.199938 -0.304039 + outer loop + vertex -410.947 141.366 140.284 + vertex -406.66 149.716 147.925 + vertex -408.557 140.772 147.996 + endloop + endfacet + facet normal 0.92348 -0.197622 -0.328831 + outer loop + vertex -408.557 140.772 147.996 + vertex -404.048 149.083 155.664 + vertex -405.938 140.139 155.73 + endloop + endfacet + facet normal 0.915699 -0.195528 -0.351091 + outer loop + vertex -405.938 140.139 155.73 + vertex -401.229 148.409 163.407 + vertex -403.113 139.464 163.475 + endloop + endfacet + facet normal 0.905495 -0.204121 -0.37204 + outer loop + vertex -405.057 130.112 163.895 + vertex -400.118 138.762 171.169 + vertex -402.055 129.423 171.58 + endloop + endfacet + facet normal 0.900768 -0.224142 -0.37199 + outer loop + vertex -405.057 130.112 163.895 + vertex -402.055 129.423 171.58 + vertex -407.147 120.392 164.69 + endloop + endfacet + facet normal 0.908152 -0.194089 -0.370931 + outer loop + vertex -401.229 148.409 163.407 + vertex -398.236 147.698 171.106 + vertex -403.113 139.464 163.475 + endloop + endfacet + facet normal 0.900656 -0.192165 -0.389733 + outer loop + vertex -400.118 138.762 171.169 + vertex -395.106 146.967 178.706 + vertex -396.988 138.043 178.758 + endloop + endfacet + facet normal 0.901422 -0.188499 -0.389752 + outer loop + vertex -396.363 156.44 171.211 + vertex -393.229 155.694 178.819 + vertex -398.236 147.698 171.106 + endloop + endfacet + facet normal 0.894081 -0.187247 -0.406888 + outer loop + vertex -393.229 155.694 178.819 + vertex -388.101 163.672 186.416 + vertex -389.987 154.925 186.297 + endloop + endfacet + facet normal 0.88695 -0.185492 -0.422981 + outer loop + vertex -388.101 163.672 186.416 + vertex -384.769 162.859 193.759 + vertex -389.987 154.925 186.297 + endloop + endfacet + facet normal 0.880397 -0.182151 -0.437861 + outer loop + vertex -384.769 162.859 193.759 + vertex -379.498 170.877 201.023 + vertex -381.369 162.016 200.947 + endloop + endfacet + facet normal 0.874016 -0.18069 -0.451051 + outer loop + vertex -379.498 170.877 201.023 + vertex -376.055 169.978 208.054 + vertex -381.369 162.016 200.947 + endloop + endfacet + facet normal 0.867583 -0.177551 -0.464516 + outer loop + vertex -377.922 161.134 207.968 + vertex -372.598 169.044 214.888 + vertex -374.453 160.208 214.801 + endloop + endfacet + facet normal 0.871251 -0.164887 -0.462314 + outer loop + vertex -374.306 179.016 208.127 + vertex -370.854 178.069 214.969 + vertex -376.055 169.978 208.054 + endloop + endfacet + facet normal 0.865103 -0.160947 -0.475072 + outer loop + vertex -372.598 169.044 214.888 + vertex -367.427 177.093 221.578 + vertex -369.148 168.072 221.499 + endloop + endfacet + facet normal 0.874021 -0.122196 -0.470272 + outer loop + vertex -369.393 187.325 215.281 + vertex -366.033 186.362 221.776 + vertex -370.854 178.069 214.969 + endloop + endfacet + facet normal 0.859903 -0.15987 -0.484777 + outer loop + vertex -367.427 177.093 221.578 + vertex -364.008 176.076 227.978 + vertex -369.148 168.072 221.499 + endloop + endfacet + facet normal 0.861822 -0.176232 -0.475609 + outer loop + vertex -372.598 169.044 214.888 + vertex -369.148 168.072 221.499 + vertex -374.453 160.208 214.801 + endloop + endfacet + facet normal 0.866957 -0.180406 -0.464585 + outer loop + vertex -377.922 161.134 207.968 + vertex -374.453 160.208 214.801 + vertex -379.805 152.399 207.846 + endloop + endfacet + facet normal 0.873435 -0.181983 -0.451656 + outer loop + vertex -383.255 153.294 200.813 + vertex -377.922 161.134 207.968 + vertex -379.805 152.399 207.846 + endloop + endfacet + facet normal 0.879996 -0.183846 -0.437958 + outer loop + vertex -386.656 154.132 193.628 + vertex -383.255 153.294 200.813 + vertex -388.536 145.407 193.513 + endloop + endfacet + facet normal 0.887 -0.185554 -0.422847 + outer loop + vertex -391.866 146.215 186.173 + vertex -386.656 154.132 193.628 + vertex -388.536 145.407 193.513 + endloop + endfacet + facet normal 0.893365 -0.190728 -0.406843 + outer loop + vertex -395.106 146.967 178.706 + vertex -391.866 146.215 186.173 + vertex -396.988 138.043 178.758 + endloop + endfacet + facet normal 0.898173 -0.203381 -0.389772 + outer loop + vertex -400.118 138.762 171.169 + vertex -396.988 138.043 178.758 + vertex -402.055 129.423 171.58 + endloop + endfacet + facet normal 0.890617 -0.201474 -0.407688 + outer loop + vertex -398.922 128.684 179.173 + vertex -393.747 137.262 186.239 + vertex -395.668 127.832 186.701 + endloop + endfacet + facet normal 0.876964 -0.218005 -0.428262 + outer loop + vertex -397.705 118.038 187.578 + vertex -392.3 126.729 194.222 + vertex -394.168 116.936 195.382 + endloop + endfacet + facet normal 0.883501 -0.200786 -0.423216 + outer loop + vertex -393.747 137.262 186.239 + vertex -390.41 136.347 193.639 + vertex -395.668 127.832 186.701 + endloop + endfacet + facet normal 0.879052 -0.187437 -0.438332 + outer loop + vertex -390.41 136.347 193.639 + vertex -385.133 144.495 200.737 + vertex -387.002 135.23 200.951 + endloop + endfacet + facet normal 0.872283 -0.18639 -0.452085 + outer loop + vertex -385.133 144.495 200.737 + vertex -381.671 143.506 207.825 + vertex -387.002 135.23 200.951 + endloop + endfacet + facet normal 0.866329 -0.180258 -0.465813 + outer loop + vertex -381.671 143.506 207.825 + vertex -376.325 151.448 214.695 + vertex -378.169 142.503 214.725 + endloop + endfacet + facet normal 0.857636 -0.18002 -0.48172 + outer loop + vertex -379.959 133.105 215.09 + vertex -374.664 141.505 221.377 + vertex -376.433 132.097 221.744 + endloop + endfacet + facet normal 0.859922 -0.178978 -0.478018 + outer loop + vertex -376.325 151.448 214.695 + vertex -372.843 150.472 221.323 + vertex -378.169 142.503 214.725 + endloop + endfacet + facet normal 0.852521 -0.174296 -0.492778 + outer loop + vertex -374.664 141.505 221.377 + vertex -369.385 149.461 227.696 + vertex -371.184 140.485 227.759 + endloop + endfacet + facet normal 0.854456 -0.175721 -0.488904 + outer loop + vertex -370.989 159.239 221.412 + vertex -367.553 158.237 227.778 + vertex -372.843 150.472 221.323 + endloop + endfacet + facet normal 0.84738 -0.170212 -0.502966 + outer loop + vertex -369.385 149.461 227.696 + vertex -364.148 157.195 233.901 + vertex -365.959 148.412 233.823 + endloop + endfacet + facet normal 0.84998 -0.170278 -0.498537 + outer loop + vertex -365.732 167.067 227.866 + vertex -362.346 166.027 233.994 + vertex -367.553 158.237 227.778 + endloop + endfacet + facet normal 0.842596 -0.164329 -0.512862 + outer loop + vertex -364.148 157.195 233.901 + vertex -358.969 164.945 239.929 + vertex -360.757 156.105 239.824 + endloop + endfacet + facet normal 0.848005 -0.153705 -0.50721 + outer loop + vertex -360.641 175.038 234.115 + vertex -357.291 173.965 240.041 + vertex -362.346 166.027 233.994 + endloop + endfacet + facet normal 0.839973 -0.147236 -0.522272 + outer loop + vertex -358.969 164.945 239.929 + vertex -353.898 172.842 245.857 + vertex -355.563 163.81 245.726 + endloop + endfacet + facet normal 0.850857 -0.112254 -0.513266 + outer loop + vertex -355.892 183.222 240.335 + vertex -352.557 182.124 246.104 + vertex -357.291 173.965 240.041 + endloop + endfacet + facet normal 0.833893 -0.14597 -0.532274 + outer loop + vertex -353.898 172.842 245.857 + vertex -350.496 171.687 251.504 + vertex -355.563 163.81 245.726 + endloop + endfacet + facet normal 0.836438 -0.16296 -0.523273 + outer loop + vertex -358.969 164.945 239.929 + vertex -355.563 163.81 245.726 + vertex -360.757 156.105 239.824 + endloop + endfacet + facet normal 0.841541 -0.168918 -0.513103 + outer loop + vertex -364.148 157.195 233.901 + vertex -360.757 156.105 239.824 + vertex -365.959 148.412 233.823 + endloop + endfacet + facet normal 0.846697 -0.173201 -0.503096 + outer loop + vertex -369.385 149.461 227.696 + vertex -365.959 148.412 233.823 + vertex -371.184 140.485 227.759 + endloop + endfacet + facet normal 0.851383 -0.179283 -0.492954 + outer loop + vertex -374.664 141.505 221.377 + vertex -371.184 140.485 227.759 + vertex -376.433 132.097 221.744 + endloop + endfacet + facet normal 0.855391 -0.189702 -0.481995 + outer loop + vertex -379.959 133.105 215.09 + vertex -376.433 132.097 221.744 + vertex -381.72 123.22 215.855 + endloop + endfacet + facet normal 0.840564 -0.227632 -0.491564 + outer loop + vertex -382.257 116.643 217.692 + vertex -380.825 115.278 220.772 + vertex -383.524 111.329 217.986 + endloop + endfacet + facet normal 0.846568 -0.183184 -0.499767 + outer loop + vertex -378.184 122.226 222.46 + vertex -372.93 131.068 228.119 + vertex -374.652 121.18 228.826 + endloop + endfacet + facet normal 0.831812 -0.226036 -0.506948 + outer loop + vertex -378.721 115.636 224.214 + vertex -377.273 114.225 227.219 + vertex -379.987 110.3 224.515 + endloop + endfacet + facet normal 0.834447 -0.19821 -0.514209 + outer loop + vertex -373.705 113.132 233.472 + vertex -375.159 114.559 230.562 + vertex -371.13 120.09 234.969 + endloop + endfacet + facet normal 0.829525 -0.194379 -0.52355 + outer loop + vertex -373.705 113.132 233.472 + vertex -371.13 120.09 234.969 + vertex -371.62 113.459 236.654 + endloop + endfacet + facet normal 0.824971 -0.2281 -0.517101 + outer loop + vertex -373.705 113.132 233.472 + vertex -371.62 113.459 236.654 + vertex -374.623 108.663 233.979 + endloop + endfacet + facet normal 0.826594 -0.195254 -0.527843 + outer loop + vertex -371.13 120.09 234.969 + vertex -367.627 118.982 240.864 + vertex -371.62 113.459 236.654 + endloop + endfacet + facet normal 0.826434 -0.194827 -0.528251 + outer loop + vertex -370.196 112.026 239.411 + vertex -371.62 113.459 236.654 + vertex -367.627 118.982 240.864 + endloop + endfacet + facet normal 0.821102 -0.190835 -0.537935 + outer loop + vertex -370.196 112.026 239.411 + vertex -367.627 118.982 240.864 + vertex -368.124 112.345 242.46 + endloop + endfacet + facet normal 0.816641 -0.22548 -0.531278 + outer loop + vertex -370.196 112.026 239.411 + vertex -368.124 112.345 242.46 + vertex -371.118 107.554 239.892 + endloop + endfacet + facet normal 0.818249 -0.191598 -0.541995 + outer loop + vertex -367.627 118.982 240.864 + vertex -364.104 117.863 246.579 + vertex -368.124 112.345 242.46 + endloop + endfacet + facet normal 0.818275 -0.191665 -0.541932 + outer loop + vertex -366.691 110.907 245.133 + vertex -368.124 112.345 242.46 + vertex -364.104 117.863 246.579 + endloop + endfacet + facet normal 0.811822 -0.186927 -0.553176 + outer loop + vertex -366.691 110.907 245.133 + vertex -364.104 117.863 246.579 + vertex -364.575 111.212 248.135 + endloop + endfacet + facet normal 0.809426 -0.187528 -0.556474 + outer loop + vertex -364.104 117.863 246.579 + vertex -360.541 116.73 252.143 + vertex -364.575 111.212 248.135 + endloop + endfacet + facet normal 0.814465 -0.167276 -0.555576 + outer loop + vertex -364.104 117.863 246.579 + vertex -358.92 126.653 251.532 + vertex -360.541 116.73 252.143 + endloop + endfacet + facet normal 0.808117 -0.166814 -0.564908 + outer loop + vertex -358.92 126.653 251.532 + vertex -355.438 125.471 256.861 + vertex -360.541 116.73 252.143 + endloop + endfacet + facet normal 0.805761 -0.163038 -0.569357 + outer loop + vertex -360.541 116.73 252.143 + vertex -355.438 125.471 256.861 + vertex -357.079 115.531 257.385 + endloop + endfacet + facet normal 0.80042 -0.183777 -0.570573 + outer loop + vertex -360.541 116.73 252.143 + vertex -357.079 115.531 257.385 + vertex -361.004 110.074 253.637 + endloop + endfacet + facet normal 0.800012 -0.16252 -0.577553 + outer loop + vertex -355.438 125.471 256.861 + vertex -352.355 123.985 261.55 + vertex -357.079 115.531 257.385 + endloop + endfacet + facet normal 0.79731 -0.158648 -0.582347 + outer loop + vertex -357.079 115.531 257.385 + vertex -352.355 123.985 261.55 + vertex -353.964 114.247 262.001 + endloop + endfacet + facet normal 0.791521 -0.179404 -0.584216 + outer loop + vertex -357.079 115.531 257.385 + vertex -353.964 114.247 262.001 + vertex -357.554 108.92 258.773 + endloop + endfacet + facet normal 0.792565 -0.158169 -0.588916 + outer loop + vertex -352.355 123.985 261.55 + vertex -350.402 121.766 264.775 + vertex -353.964 114.247 262.001 + endloop + endfacet + facet normal 0.790448 -0.155896 -0.592359 + outer loop + vertex -353.964 114.247 262.001 + vertex -350.402 121.766 264.775 + vertex -351.279 113.571 265.762 + endloop + endfacet + facet normal 0.786388 -0.174018 -0.592716 + outer loop + vertex -353.964 114.247 262.001 + vertex -351.279 113.571 265.762 + vertex -354.327 107.814 263.408 + endloop + endfacet + facet normal 0.793851 -0.155716 -0.587838 + outer loop + vertex -351.279 113.571 265.762 + vertex -350.402 121.766 264.775 + vertex -347.908 124.103 267.525 + endloop + endfacet + facet normal 0.783889 -0.150074 -0.602491 + outer loop + vertex -347.908 124.103 267.525 + vertex -349.405 113.199 268.292 + vertex -351.279 113.571 265.762 + endloop + endfacet + facet normal 0.7801 -0.168842 -0.602442 + outer loop + vertex -351.674 106.962 267.102 + vertex -351.279 113.571 265.762 + vertex -349.405 113.199 268.292 + endloop + endfacet + facet normal 0.791478 -0.146726 -0.593325 + outer loop + vertex -350.402 121.766 264.775 + vertex -347.95 131.824 265.558 + vertex -347.908 124.103 267.525 + endloop + endfacet + facet normal 0.79533 -0.145467 -0.588463 + outer loop + vertex -345.647 133.985 268.137 + vertex -347.908 124.103 267.525 + vertex -347.95 131.824 265.558 + endloop + endfacet + facet normal 0.794516 -0.142392 -0.590313 + outer loop + vertex -344.544 141.343 267.846 + vertex -345.647 133.985 268.137 + vertex -347.95 131.824 265.558 + endloop + endfacet + facet normal 0.797406 -0.144489 -0.58589 + outer loop + vertex -347.95 131.824 265.558 + vertex -346.309 142 265.282 + vertex -344.544 141.343 267.846 + endloop + endfacet + facet normal 0.797825 -0.142775 -0.585739 + outer loop + vertex -343.008 149.984 267.833 + vertex -344.544 141.343 267.846 + vertex -346.309 142 265.282 + endloop + endfacet + facet normal 0.799067 -0.14392 -0.583763 + outer loop + vertex -346.309 142 265.282 + vertex -344.692 150.938 265.292 + vertex -343.008 149.984 267.833 + endloop + endfacet + facet normal 0.799885 -0.141238 -0.583297 + outer loop + vertex -341.425 158.699 267.894 + vertex -343.008 149.984 267.833 + vertex -344.692 150.938 265.292 + endloop + endfacet + facet normal 0.790469 -0.139437 -0.596419 + outer loop + vertex -341.425 158.699 267.894 + vertex -340.754 157.059 269.166 + vertex -343.008 149.984 267.833 + endloop + endfacet + facet normal 0.794495 -0.141839 -0.590474 + outer loop + vertex -343.008 149.984 267.833 + vertex -340.754 157.059 269.166 + vertex -342.293 148.678 269.108 + endloop + endfacet + facet normal 0.786469 -0.140288 -0.601487 + outer loop + vertex -342.293 148.678 269.108 + vertex -340.754 157.059 269.166 + vertex -340.995 154.317 269.49 + endloop + endfacet + facet normal 0.803163 -0.144668 -0.577928 + outer loop + vertex -348.935 143.019 261.377 + vertex -344.692 150.938 265.292 + vertex -346.309 142 265.282 + endloop + endfacet + facet normal 0.802445 -0.147549 -0.578196 + outer loop + vertex -348.935 143.019 261.377 + vertex -346.309 142 265.282 + vertex -350.587 133.764 261.447 + endloop + endfacet + facet normal 0.80688 -0.148292 -0.571799 + outer loop + vertex -353.807 134.996 256.583 + vertex -348.935 143.019 261.377 + vertex -350.587 133.764 261.447 + endloop + endfacet + facet normal 0.805297 -0.15462 -0.572354 + outer loop + vertex -353.807 134.996 256.583 + vertex -350.587 133.764 261.447 + vertex -355.438 125.471 256.861 + endloop + endfacet + facet normal 0.808948 -0.151862 -0.567926 + outer loop + vertex -352.154 144.003 256.529 + vertex -348.935 143.019 261.377 + vertex -353.807 134.996 256.583 + endloop + endfacet + facet normal 0.814461 -0.152826 -0.559729 + outer loop + vertex -357.304 136.088 251.196 + vertex -352.154 144.003 256.529 + vertex -353.807 134.996 256.583 + endloop + endfacet + facet normal 0.813018 -0.159129 -0.560071 + outer loop + vertex -357.304 136.088 251.196 + vertex -353.807 134.996 256.583 + vertex -358.92 126.653 251.532 + endloop + endfacet + facet normal 0.819385 -0.159879 -0.550497 + outer loop + vertex -362.469 127.769 245.925 + vertex -357.304 136.088 251.196 + vertex -358.92 126.653 251.532 + endloop + endfacet + facet normal 0.821423 -0.163811 -0.546288 + outer loop + vertex -360.827 137.187 245.57 + vertex -357.304 136.088 251.196 + vertex -362.469 127.769 245.925 + endloop + endfacet + facet normal 0.816351 -0.156627 -0.555913 + outer loop + vertex -355.626 145.048 251.136 + vertex -352.154 144.003 256.529 + vertex -357.304 136.088 251.196 + endloop + endfacet + facet normal 0.809733 -0.148353 -0.567736 + outer loop + vertex -352.154 144.003 256.529 + vertex -347.265 151.805 261.463 + vertex -348.935 143.019 261.377 + endloop + endfacet + facet normal 0.811641 -0.151866 -0.56407 + outer loop + vertex -350.444 152.737 256.638 + vertex -347.265 151.805 261.463 + vertex -352.154 144.003 256.529 + endloop + endfacet + facet normal 0.80512 -0.14741 -0.574502 + outer loop + vertex -347.265 151.805 261.463 + vertex -344.692 150.938 265.292 + vertex -348.935 143.019 261.377 + endloop + endfacet + facet normal 0.806131 -0.143033 -0.574191 + outer loop + vertex -347.265 151.805 261.463 + vertex -343.056 159.712 265.404 + vertex -344.692 150.938 265.292 + endloop + endfacet + facet normal 0.808327 -0.146138 -0.570308 + outer loop + vertex -345.584 160.551 261.606 + vertex -343.056 159.712 265.404 + vertex -347.265 151.805 261.463 + endloop + endfacet + facet normal 0.794287 -0.142153 -0.590678 + outer loop + vertex -343.008 149.984 267.833 + vertex -342.293 148.678 269.108 + vertex -344.544 141.343 267.846 + endloop + endfacet + facet normal 0.794624 -0.142342 -0.59018 + outer loop + vertex -344.544 141.343 267.846 + vertex -342.293 148.678 269.108 + vertex -343.842 140.056 269.103 + endloop + endfacet + facet normal 0.796706 -0.142718 -0.587275 + outer loop + vertex -343.842 140.056 269.103 + vertex -342.293 148.678 269.108 + vertex -342.566 145.889 269.416 + endloop + endfacet + facet normal 0.800402 -0.144859 -0.581697 + outer loop + vertex -350.587 133.764 261.447 + vertex -346.309 142 265.282 + vertex -347.95 131.824 265.558 + endloop + endfacet + facet normal 0.798363 -0.150521 -0.583061 + outer loop + vertex -350.587 133.764 261.447 + vertex -347.95 131.824 265.558 + vertex -352.355 123.985 261.55 + endloop + endfacet + facet normal 0.794586 -0.142399 -0.590216 + outer loop + vertex -344.544 141.343 267.846 + vertex -343.842 140.056 269.103 + vertex -345.647 133.985 268.137 + endloop + endfacet + facet normal 0.792517 -0.141301 -0.593254 + outer loop + vertex -345.647 133.985 268.137 + vertex -343.842 140.056 269.103 + vertex -345.535 130.925 269.015 + endloop + endfacet + facet normal 0.794116 -0.141618 -0.591036 + outer loop + vertex -345.535 130.925 269.015 + vertex -343.842 140.056 269.103 + vertex -344.453 135.629 269.343 + endloop + endfacet + facet normal 0.787877 -0.14311 -0.598974 + outer loop + vertex -345.647 133.985 268.137 + vertex -345.535 130.925 269.015 + vertex -347.908 124.103 267.525 + endloop + endfacet + facet normal 0.784705 -0.140991 -0.603622 + outer loop + vertex -347.908 124.103 267.525 + vertex -345.535 130.925 269.015 + vertex -347.156 121.555 269.096 + endloop + endfacet + facet normal 0.775802 -0.139553 -0.615351 + outer loop + vertex -347.156 121.555 269.096 + vertex -345.535 130.925 269.015 + vertex -345.946 127.068 269.372 + endloop + endfacet + facet normal 0.797133 -0.148738 -0.585197 + outer loop + vertex -352.355 123.985 261.55 + vertex -347.95 131.824 265.558 + vertex -350.402 121.766 264.775 + endloop + endfacet + facet normal 0.803233 -0.151328 -0.576122 + outer loop + vertex -355.438 125.471 256.861 + vertex -350.587 133.764 261.447 + vertex -352.355 123.985 261.55 + endloop + endfacet + facet normal 0.810903 -0.155341 -0.564186 + outer loop + vertex -358.92 126.653 251.532 + vertex -353.807 134.996 256.583 + vertex -355.438 125.471 256.861 + endloop + endfacet + facet normal 0.816725 -0.171155 -0.551059 + outer loop + vertex -362.469 127.769 245.925 + vertex -358.92 126.653 251.532 + vertex -364.104 117.863 246.579 + endloop + endfacet + facet normal 0.80611 -0.218611 -0.549906 + outer loop + vertex -368.124 112.345 242.46 + vertex -366.691 110.907 245.133 + vertex -369.369 106.993 242.763 + endloop + endfacet + facet normal 0.823237 -0.171575 -0.54115 + outer loop + vertex -367.627 118.982 240.864 + vertex -362.469 127.769 245.925 + vertex -364.104 117.863 246.579 + endloop + endfacet + facet normal 0.825308 -0.175307 -0.536782 + outer loop + vertex -365.973 128.884 240.173 + vertex -362.469 127.769 245.925 + vertex -367.627 118.982 240.864 + endloop + endfacet + facet normal 0.814694 -0.221363 -0.535977 + outer loop + vertex -371.62 113.459 236.654 + vertex -370.196 112.026 239.411 + vertex -372.863 108.11 236.975 + endloop + endfacet + facet normal 0.823463 -0.223901 -0.521322 + outer loop + vertex -375.159 114.559 230.562 + vertex -373.705 113.132 233.472 + vertex -376.404 109.213 230.893 + endloop + endfacet + facet normal 0.84088 -0.182881 -0.509388 + outer loop + vertex -372.93 131.068 228.119 + vertex -369.448 129.993 234.254 + vertex -374.652 121.18 228.826 + endloop + endfacet + facet normal 0.831475 -0.175659 -0.527061 + outer loop + vertex -371.13 120.09 234.969 + vertex -365.973 128.884 240.173 + vertex -367.627 118.982 240.864 + endloop + endfacet + facet normal 0.837429 -0.172284 -0.518683 + outer loop + vertex -367.733 139.423 233.889 + vertex -364.295 138.316 239.808 + vertex -369.448 129.993 234.254 + endloop + endfacet + facet normal 0.827861 -0.164555 -0.536253 + outer loop + vertex -365.973 128.884 240.173 + vertex -360.827 137.187 245.57 + vertex -362.469 127.769 245.925 + endloop + endfacet + facet normal 0.832318 -0.16557 -0.528993 + outer loop + vertex -362.549 147.312 239.739 + vertex -359.113 146.169 245.504 + vertex -364.295 138.316 239.808 + endloop + endfacet + facet normal 0.822811 -0.15777 -0.545977 + outer loop + vertex -360.827 137.187 245.57 + vertex -355.626 145.048 251.136 + vertex -357.304 136.088 251.196 + endloop + endfacet + facet normal 0.826442 -0.16075 -0.539586 + outer loop + vertex -357.339 154.962 245.601 + vertex -353.878 153.809 251.246 + vertex -359.113 146.169 245.504 + endloop + endfacet + facet normal 0.817151 -0.153048 -0.555734 + outer loop + vertex -355.626 145.048 251.136 + vertex -350.444 152.737 256.638 + vertex -352.154 144.003 256.529 + endloop + endfacet + facet normal 0.821404 -0.154715 -0.548961 + outer loop + vertex -352.119 162.642 251.388 + vertex -348.723 161.524 256.785 + vertex -353.878 153.809 251.246 + endloop + endfacet + facet normal 0.812685 -0.147081 -0.563835 + outer loop + vertex -350.444 152.737 256.638 + vertex -345.584 160.551 261.606 + vertex -347.265 151.805 261.463 + endloop + endfacet + facet normal 0.819984 -0.137124 -0.555719 + outer loop + vertex -347.15 170.546 256.879 + vertex -344.04 169.513 261.723 + vertex -348.723 161.524 256.785 + endloop + endfacet + facet normal 0.823802 -0.0929576 -0.559205 + outer loop + vertex -342.874 178.802 261.898 + vertex -340.141 177.839 266.083 + vertex -344.04 169.513 261.723 + endloop + endfacet + facet normal 0.811907 -0.130004 -0.569128 + outer loop + vertex -345.584 160.551 261.606 + vertex -341.46 168.649 265.638 + vertex -343.056 159.712 265.404 + endloop + endfacet + facet normal 0.800569 -0.141894 -0.582199 + outer loop + vertex -344.692 150.938 265.292 + vertex -343.056 159.712 265.404 + vertex -341.425 158.699 267.894 + endloop + endfacet + facet normal 0.795477 -0.133295 -0.591142 + outer loop + vertex -341.425 158.699 267.894 + vertex -339.194 166.022 269.244 + vertex -340.754 157.059 269.166 + endloop + endfacet + facet normal 0.725283 -0.120329 -0.677853 + outer loop + vertex -340.754 157.059 269.166 + vertex -339.194 166.022 269.244 + vertex -339.721 161.47 269.488 + endloop + endfacet + facet normal 0.812837 -0.0879926 -0.575806 + outer loop + vertex -337.826 177.018 269.528 + vertex -337.719 176.98 269.685 + vertex -339.816 167.84 268.121 + endloop + endfacet + facet normal 0.816185 -0.0768412 -0.572658 + outer loop + vertex -338.605 167.525 269.689 + vertex -337.505 176.904 269.998 + vertex -337.918 168.294 270.564 + endloop + endfacet + facet normal 0.831471 -0.126611 -0.540949 + outer loop + vertex -339.108 161.809 270.253 + vertex -338.605 167.525 269.689 + vertex -337.918 168.294 270.564 + endloop + endfacet + facet normal 0.806727 -0.120263 -0.578558 + outer loop + vertex -339.108 161.809 270.253 + vertex -337.918 168.294 270.564 + vertex -338.162 158.469 272.266 + endloop + endfacet + facet normal 0.787973 -0.13846 -0.599939 + outer loop + vertex -340.175 154.032 270.646 + vertex -339.108 161.809 270.253 + vertex -338.162 158.469 272.266 + endloop + endfacet + facet normal 0.785873 -0.136327 -0.603174 + outer loop + vertex -338.162 158.469 272.266 + vertex -339.505 148.246 272.827 + vertex -340.175 154.032 270.646 + endloop + endfacet + facet normal 0.781205 -0.138921 -0.608622 + outer loop + vertex -341.651 143.998 271.042 + vertex -340.175 154.032 270.646 + vertex -339.505 148.246 272.827 + endloop + endfacet + facet normal 0.77858 -0.135901 -0.612653 + outer loop + vertex -339.505 148.246 272.827 + vertex -340.463 140.413 273.347 + vertex -341.651 143.998 271.042 + endloop + endfacet + facet normal 0.779661 -0.134813 -0.611517 + outer loop + vertex -340.463 140.413 273.347 + vertex -342.177 133.48 272.69 + vertex -341.651 143.998 271.042 + endloop + endfacet + facet normal 0.774079 -0.135611 -0.618395 + outer loop + vertex -343.326 136.797 270.524 + vertex -341.651 143.998 271.042 + vertex -342.177 133.48 272.69 + endloop + endfacet + facet normal 0.772939 -0.13677 -0.619564 + outer loop + vertex -344.496 127.655 271.082 + vertex -343.326 136.797 270.524 + vertex -342.177 133.48 272.69 + endloop + endfacet + facet normal 0.76988 -0.134359 -0.623885 + outer loop + vertex -342.177 133.48 272.69 + vertex -343.241 124.375 273.338 + vertex -344.496 127.655 271.082 + endloop + endfacet + facet normal 0.764197 -0.140404 -0.629515 + outer loop + vertex -343.241 124.375 273.338 + vertex -344.945 117.368 272.832 + vertex -344.496 127.655 271.082 + endloop + endfacet + facet normal 0.765912 -0.140134 -0.627488 + outer loop + vertex -346.525 117.999 270.763 + vertex -344.496 127.655 271.082 + vertex -344.945 117.368 272.832 + endloop + endfacet + facet normal 0.762433 -0.152935 -0.628735 + outer loop + vertex -344.945 117.368 272.832 + vertex -347.132 108.383 272.366 + vertex -346.525 117.999 270.763 + endloop + endfacet + facet normal 0.764534 -0.152653 -0.626247 + outer loop + vertex -348.668 108.938 270.355 + vertex -346.525 117.999 270.763 + vertex -347.132 108.383 272.366 + endloop + endfacet + facet normal 0.758164 -0.176079 -0.62784 + outer loop + vertex -349.205 102.686 271.46 + vertex -348.668 108.938 270.355 + vertex -347.132 108.383 272.366 + endloop + endfacet + facet normal 0.755331 -0.174434 -0.631703 + outer loop + vertex -348.294 101.431 272.896 + vertex -349.205 102.686 271.46 + vertex -347.132 108.383 272.366 + endloop + endfacet + facet normal 0.746632 -0.173775 -0.642139 + outer loop + vertex -348.294 101.431 272.896 + vertex -347.132 108.383 272.366 + vertex -346.861 101.895 274.436 + endloop + endfacet + facet normal 0.748316 -0.173133 -0.640349 + outer loop + vertex -347.132 108.383 272.366 + vertex -344.799 107.57 275.312 + vertex -346.861 101.895 274.436 + endloop + endfacet + facet normal 0.747178 -0.172488 -0.641851 + outer loop + vertex -345.587 100.578 276.273 + vertex -346.861 101.895 274.436 + vertex -344.799 107.57 275.312 + endloop + endfacet + facet normal 0.732953 -0.17309 -0.657891 + outer loop + vertex -345.587 100.578 276.273 + vertex -344.799 107.57 275.312 + vertex -344.04 100.995 277.888 + endloop + endfacet + facet normal 0.737219 -0.170945 -0.653671 + outer loop + vertex -344.799 107.57 275.312 + vertex -342.032 106.656 278.672 + vertex -344.04 100.995 277.888 + endloop + endfacet + facet normal 0.730739 -0.167523 -0.661783 + outer loop + vertex -342.652 99.633 279.764 + vertex -344.04 100.995 277.888 + vertex -342.032 106.656 278.672 + endloop + endfacet + facet normal 0.713148 -0.16886 -0.680372 + outer loop + vertex -342.652 99.633 279.764 + vertex -342.032 106.656 278.672 + vertex -341.061 100.014 281.337 + endloop + endfacet + facet normal 0.719359 -0.165637 -0.674602 + outer loop + vertex -342.032 106.656 278.672 + vertex -339.059 105.692 282.078 + vertex -341.061 100.014 281.337 + endloop + endfacet + facet normal 0.707318 -0.159557 -0.688653 + outer loop + vertex -339.622 98.6147 283.14 + vertex -341.061 100.014 281.337 + vertex -339.059 105.692 282.078 + endloop + endfacet + facet normal 0.686108 -0.160995 -0.709462 + outer loop + vertex -339.622 98.6147 283.14 + vertex -339.059 105.692 282.078 + vertex -338.014 99.0103 284.605 + endloop + endfacet + facet normal 0.686406 -0.187945 -0.702512 + outer loop + vertex -339.351 94.1003 284.612 + vertex -339.622 98.6147 283.14 + vertex -338.014 99.0103 284.605 + endloop + endfacet + facet normal 0.659442 -0.180642 -0.729729 + outer loop + vertex -339.351 94.1003 284.612 + vertex -338.014 99.0103 284.605 + vertex -337.803 93.663 286.119 + endloop + endfacet + facet normal 0.645084 -0.228961 -0.729002 + outer loop + vertex -339.222 89.4505 286.187 + vertex -339.351 94.1003 284.612 + vertex -337.803 93.663 286.119 + endloop + endfacet + facet normal 0.62457 -0.222368 -0.748642 + outer loop + vertex -339.222 89.4505 286.187 + vertex -337.803 93.663 286.119 + vertex -337.667 89.064 287.599 + endloop + endfacet + facet normal 0.63311 -0.220019 -0.742134 + outer loop + vertex -337.667 89.064 287.599 + vertex -337.803 93.663 286.119 + vertex -336.22 93.3737 287.555 + endloop + endfacet + facet normal 0.611482 -0.212964 -0.762061 + outer loop + vertex -337.667 89.064 287.599 + vertex -336.22 93.3737 287.555 + vertex -336.074 88.777 288.957 + endloop + endfacet + facet normal 0.618646 -0.211123 -0.756772 + outer loop + vertex -336.074 88.777 288.957 + vertex -336.22 93.3737 287.555 + vertex -334.508 93.3661 288.957 + endloop + endfacet + facet normal 0.594651 -0.202935 -0.777951 + outer loop + vertex -336.074 88.777 288.957 + vertex -334.508 93.3661 288.957 + vertex -334.385 88.5226 290.315 + endloop + endfacet + facet normal 0.582184 -0.254698 -0.772134 + outer loop + vertex -336.133 84.2122 290.419 + vertex -336.074 88.777 288.957 + vertex -334.385 88.5226 290.315 + endloop + endfacet + facet normal 0.53785 -0.237603 -0.808864 + outer loop + vertex -336.133 84.2122 290.419 + vertex -334.385 88.5226 290.315 + vertex -334.564 83.5936 291.644 + endloop + endfacet + facet normal 0.535328 -0.237936 -0.810439 + outer loop + vertex -334.564 83.5936 291.644 + vertex -334.385 88.5226 290.315 + vertex -333.002 87.4154 291.553 + endloop + endfacet + facet normal 0.500741 -0.2244 -0.836004 + outer loop + vertex -334.564 83.5936 291.644 + vertex -333.002 87.4154 291.553 + vertex -332.876 83.2428 292.749 + endloop + endfacet + facet normal 0.526678 -0.219396 -0.821265 + outer loop + vertex -332.876 83.2428 292.749 + vertex -333.002 87.4154 291.553 + vertex -331.152 88.1223 292.551 + endloop + endfacet + facet normal 0.470755 -0.201165 -0.859024 + outer loop + vertex -332.876 83.2428 292.749 + vertex -331.152 88.1223 292.551 + vertex -331.168 83.33 293.664 + endloop + endfacet + facet normal 0.484695 -0.199495 -0.851629 + outer loop + vertex -331.168 83.33 293.664 + vertex -331.152 88.1223 292.551 + vertex -329.707 87.2558 293.577 + endloop + endfacet + facet normal 0.567236 -0.257726 -0.78219 + outer loop + vertex -337.674 84.6759 289.148 + vertex -336.074 88.777 288.957 + vertex -336.133 84.2122 290.419 + endloop + endfacet + facet normal 0.596708 -0.268027 -0.756374 + outer loop + vertex -337.674 84.6759 289.148 + vertex -337.667 89.064 287.599 + vertex -336.074 88.777 288.957 + endloop + endfacet + facet normal 0.582223 -0.271522 -0.76635 + outer loop + vertex -339.207 85.0975 287.835 + vertex -337.667 89.064 287.599 + vertex -337.674 84.6759 289.148 + endloop + endfacet + facet normal 0.606439 -0.279616 -0.744343 + outer loop + vertex -339.207 85.0975 287.835 + vertex -339.222 89.4505 286.187 + vertex -337.667 89.064 287.599 + endloop + endfacet + facet normal 0.594389 -0.282857 -0.75279 + outer loop + vertex -340.766 85.5477 286.434 + vertex -339.222 89.4505 286.187 + vertex -339.207 85.0975 287.835 + endloop + endfacet + facet normal 0.617943 -0.290761 -0.730483 + outer loop + vertex -340.766 85.5477 286.434 + vertex -340.777 89.9216 284.684 + vertex -339.222 89.4505 286.187 + endloop + endfacet + facet normal 0.606188 -0.294168 -0.738919 + outer loop + vertex -342.361 86.0419 284.929 + vertex -340.777 89.9216 284.684 + vertex -340.766 85.5477 286.434 + endloop + endfacet + facet normal 0.630267 -0.302485 -0.715029 + outer loop + vertex -342.361 86.0419 284.929 + vertex -342.337 90.4295 283.095 + vertex -340.777 89.9216 284.684 + endloop + endfacet + facet normal 0.621717 -0.305092 -0.721378 + outer loop + vertex -343.96 86.5464 283.337 + vertex -342.337 90.4295 283.095 + vertex -342.361 86.0419 284.929 + endloop + endfacet + facet normal 0.642913 -0.312571 -0.699258 + outer loop + vertex -343.96 86.5464 283.337 + vertex -343.882 90.9323 281.449 + vertex -342.337 90.4295 283.095 + endloop + endfacet + facet normal 0.633873 -0.315402 -0.706206 + outer loop + vertex -345.536 87.0486 281.698 + vertex -343.882 90.9323 281.449 + vertex -343.96 86.5464 283.337 + endloop + endfacet + facet normal 0.65304 -0.322226 -0.685353 + outer loop + vertex -345.536 87.0486 281.698 + vertex -345.401 91.4249 279.77 + vertex -343.882 90.9323 281.449 + endloop + endfacet + facet normal 0.646624 -0.324274 -0.690452 + outer loop + vertex -347.07 87.5424 280.03 + vertex -345.401 91.4249 279.77 + vertex -345.536 87.0486 281.698 + endloop + endfacet + facet normal 0.665739 -0.331042 -0.668732 + outer loop + vertex -347.07 87.5424 280.03 + vertex -346.89 91.8995 278.053 + vertex -345.401 91.4249 279.77 + endloop + endfacet + facet normal 0.657275 -0.333843 -0.675676 + outer loop + vertex -348.577 88.0296 278.324 + vertex -346.89 91.8995 278.053 + vertex -347.07 87.5424 280.03 + endloop + endfacet + facet normal 0.673097 -0.339435 -0.657058 + outer loop + vertex -348.577 88.0296 278.324 + vertex -348.371 92.3657 276.294 + vertex -346.89 91.8995 278.053 + endloop + endfacet + facet normal 0.66901 -0.340848 -0.66049 + outer loop + vertex -350.072 88.4967 276.568 + vertex -348.371 92.3657 276.294 + vertex -348.577 88.0296 278.324 + endloop + endfacet + facet normal 0.682481 -0.345602 -0.644034 + outer loop + vertex -350.072 88.4967 276.568 + vertex -349.821 92.7992 274.526 + vertex -348.371 92.3657 276.294 + endloop + endfacet + facet normal 0.675289 -0.348122 -0.650227 + outer loop + vertex -351.539 88.9387 274.809 + vertex -349.821 92.7992 274.526 + vertex -350.072 88.4967 276.568 + endloop + endfacet + facet normal 0.684812 -0.35149 -0.638347 + outer loop + vertex -351.539 88.9387 274.809 + vertex -351.155 93.2115 272.867 + vertex -349.821 92.7992 274.526 + endloop + endfacet + facet normal 0.68099 -0.352698 -0.64176 + outer loop + vertex -352.882 89.3511 273.157 + vertex -351.155 93.2115 272.867 + vertex -351.539 88.9387 274.809 + endloop + endfacet + facet normal 0.679435 -0.352149 -0.643708 + outer loop + vertex -352.882 89.3511 273.157 + vertex -352.232 93.6328 271.5 + vertex -351.155 93.2115 272.867 + endloop + endfacet + facet normal 0.679694 -0.352094 -0.643464 + outer loop + vertex -353.961 89.7604 271.792 + vertex -352.232 93.6328 271.5 + vertex -352.882 89.3511 273.157 + endloop + endfacet + facet normal 0.6755 -0.350613 -0.648668 + outer loop + vertex -353.961 89.7604 271.792 + vertex -352.942 94.0378 270.542 + vertex -352.232 93.6328 271.5 + endloop + endfacet + facet normal 0.675664 -0.350604 -0.648503 + outer loop + vertex -354.671 90.1468 270.844 + vertex -352.942 94.0378 270.542 + vertex -353.961 89.7604 271.792 + endloop + endfacet + facet normal 0.674522 -0.350205 -0.649905 + outer loop + vertex -354.671 90.1468 270.844 + vertex -353.313 94.2716 270.03 + vertex -352.942 94.0378 270.542 + endloop + endfacet + facet normal 0.677551 -0.350543 -0.646563 + outer loop + vertex -355.037 90.4181 270.314 + vertex -353.313 94.2716 270.03 + vertex -354.671 90.1468 270.844 + endloop + endfacet + facet normal 0.744382 -0.373589 -0.553467 + outer loop + vertex -355.037 90.4181 270.314 + vertex -353.497 94.1927 269.836 + vertex -353.313 94.2716 270.03 + endloop + endfacet + facet normal 0.685358 -0.359609 -0.633219 + outer loop + vertex -355.239 90.3975 270.106 + vertex -353.497 94.1927 269.836 + vertex -355.037 90.4181 270.314 + endloop + endfacet + facet normal 0.876855 -0.381569 0.292456 + outer loop + vertex -355.239 90.3975 270.106 + vertex -353.683 93.7507 269.816 + vertex -353.497 94.1927 269.836 + endloop + endfacet + facet normal 0.806025 -0.410842 -0.426066 + outer loop + vertex -355.558 89.7887 270.09 + vertex -353.683 93.7507 269.816 + vertex -355.239 90.3975 270.106 + endloop + endfacet + facet normal 0.608903 -0.199697 -0.767697 + outer loop + vertex -334.385 88.5226 290.315 + vertex -334.508 93.3661 288.957 + vertex -332.137 94.4191 290.564 + endloop + endfacet + facet normal 0.602215 -0.163817 -0.781345 + outer loop + vertex -333.561 97.3265 288.857 + vertex -332.137 94.4191 290.564 + vertex -334.508 93.3661 288.957 + endloop + endfacet + facet normal 0.62198 -0.168124 -0.764771 + outer loop + vertex -334.508 93.3661 288.957 + vertex -334.909 98.265 287.554 + vertex -333.561 97.3265 288.857 + endloop + endfacet + facet normal 0.636514 -0.138778 -0.758677 + outer loop + vertex -333.561 97.3265 288.857 + vertex -334.909 98.265 287.554 + vertex -332.96 103.499 288.233 + endloop + endfacet + facet normal 0.654978 -0.147945 -0.741024 + outer loop + vertex -336.011 104.671 285.301 + vertex -332.96 103.499 288.233 + vertex -334.909 98.265 287.554 + endloop + endfacet + facet normal 0.647887 -0.151124 -0.746595 + outer loop + vertex -336.546 97.7157 286.245 + vertex -336.011 104.671 285.301 + vertex -334.909 98.265 287.554 + endloop + endfacet + facet normal 0.65009 -0.174458 -0.739559 + outer loop + vertex -336.22 93.3737 287.555 + vertex -336.546 97.7157 286.245 + vertex -334.909 98.265 287.554 + endloop + endfacet + facet normal 0.674873 -0.149938 -0.722541 + outer loop + vertex -336.546 97.7157 286.245 + vertex -338.014 99.0103 284.605 + vertex -336.011 104.671 285.301 + endloop + endfacet + facet normal 0.662533 -0.12291 -0.73888 + outer loop + vertex -336.011 104.671 285.301 + vertex -334.065 113.669 285.55 + vertex -332.96 103.499 288.233 + endloop + endfacet + facet normal 0.659151 -0.124025 -0.741712 + outer loop + vertex -332.96 103.499 288.233 + vertex -334.065 113.669 285.55 + vertex -330.989 112.783 288.431 + endloop + endfacet + facet normal 0.662685 -0.109124 -0.740905 + outer loop + vertex -334.065 113.669 285.55 + vertex -332.45 122.337 285.717 + vertex -330.989 112.783 288.431 + endloop + endfacet + facet normal 0.664516 -0.108408 -0.739368 + outer loop + vertex -330.989 112.783 288.431 + vertex -332.45 122.337 285.717 + vertex -329.465 121.355 288.544 + endloop + endfacet + facet normal 0.665607 -0.104064 -0.739011 + outer loop + vertex -332.45 122.337 285.717 + vertex -331.095 130.612 285.772 + vertex -329.465 121.355 288.544 + endloop + endfacet + facet normal 0.669095 -0.102567 -0.736065 + outer loop + vertex -329.465 121.355 288.544 + vertex -331.095 130.612 285.772 + vertex -328.189 129.574 288.559 + endloop + endfacet + facet normal 0.668538 -0.104687 -0.736273 + outer loop + vertex -331.095 130.612 285.772 + vertex -329.839 138.742 285.757 + vertex -328.189 129.574 288.559 + endloop + endfacet + facet normal 0.672604 -0.102898 -0.732814 + outer loop + vertex -328.189 129.574 288.559 + vertex -329.839 138.742 285.757 + vertex -326.965 137.712 288.539 + endloop + endfacet + facet normal 0.671801 -0.105948 -0.733115 + outer loop + vertex -329.839 138.742 285.757 + vertex -328.571 146.926 285.736 + vertex -326.965 137.712 288.539 + endloop + endfacet + facet normal 0.675491 -0.104342 -0.729949 + outer loop + vertex -326.965 137.712 288.539 + vertex -328.571 146.926 285.736 + vertex -325.685 145.917 288.551 + endloop + endfacet + facet normal 0.675307 -0.105056 -0.730016 + outer loop + vertex -328.571 146.926 285.736 + vertex -327.251 155.232 285.762 + vertex -325.685 145.917 288.551 + endloop + endfacet + facet normal 0.678772 -0.103573 -0.727008 + outer loop + vertex -325.685 145.917 288.551 + vertex -327.251 155.232 285.762 + vertex -324.332 154.294 288.621 + endloop + endfacet + facet normal 0.681357 -0.0926585 -0.726063 + outer loop + vertex -327.251 155.232 285.762 + vertex -325.954 163.733 285.895 + vertex -324.332 154.294 288.621 + endloop + endfacet + facet normal 0.688402 -0.0896306 -0.71977 + outer loop + vertex -324.332 154.294 288.621 + vertex -325.954 163.733 285.895 + vertex -323.071 162.869 288.759 + endloop + endfacet + facet normal 0.696969 -0.0470819 -0.715554 + outer loop + vertex -325.954 163.733 285.895 + vertex -324.955 172.482 286.292 + vertex -323.071 162.869 288.759 + endloop + endfacet + facet normal 0.710574 -0.0410458 -0.702424 + outer loop + vertex -323.071 162.869 288.759 + vertex -324.955 172.482 286.292 + vertex -322.379 171.601 288.949 + endloop + endfacet + facet normal 0.631413 -0.138712 -0.762939 + outer loop + vertex -333.561 97.3265 288.857 + vertex -332.96 103.499 288.233 + vertex -332.137 94.4191 290.564 + endloop + endfacet + facet normal 0.610363 -0.14469 -0.778795 + outer loop + vertex -332.137 94.4191 290.564 + vertex -332.96 103.499 288.233 + vertex -329.693 103.554 290.782 + endloop + endfacet + facet normal 0.612552 -0.113266 -0.782273 + outer loop + vertex -332.96 103.499 288.233 + vertex -330.989 112.783 288.431 + vertex -329.693 103.554 290.782 + endloop + endfacet + facet normal 0.615983 -0.112138 -0.779737 + outer loop + vertex -329.693 103.554 290.782 + vertex -330.989 112.783 288.431 + vertex -327.89 112.493 290.921 + endloop + endfacet + facet normal 0.617546 -0.0995201 -0.780213 + outer loop + vertex -330.989 112.783 288.431 + vertex -329.465 121.355 288.544 + vertex -327.89 112.493 290.921 + endloop + endfacet + facet normal 0.623209 -0.0973751 -0.77597 + outer loop + vertex -327.89 112.493 290.921 + vertex -329.465 121.355 288.544 + vertex -326.519 120.93 290.963 + endloop + endfacet + facet normal 0.6235 -0.0954151 -0.775979 + outer loop + vertex -329.465 121.355 288.544 + vertex -328.189 129.574 288.559 + vertex -326.519 120.93 290.963 + endloop + endfacet + facet normal 0.62698 -0.0940095 -0.773342 + outer loop + vertex -326.519 120.93 290.963 + vertex -328.189 129.574 288.559 + vertex -325.336 129.131 290.926 + endloop + endfacet + facet normal 0.62666 -0.0960903 -0.773346 + outer loop + vertex -328.189 129.574 288.559 + vertex -326.965 137.712 288.539 + vertex -325.336 129.131 290.926 + endloop + endfacet + facet normal 0.629705 -0.0948649 -0.77102 + outer loop + vertex -325.336 129.131 290.926 + vertex -326.965 137.712 288.539 + vertex -324.129 137.221 290.916 + endloop + endfacet + facet normal 0.62934 -0.0970811 -0.771042 + outer loop + vertex -326.965 137.712 288.539 + vertex -325.685 145.917 288.551 + vertex -324.129 137.221 290.916 + endloop + endfacet + facet normal 0.632105 -0.0960071 -0.768912 + outer loop + vertex -324.129 137.221 290.916 + vertex -325.685 145.917 288.551 + vertex -322.836 145.415 290.956 + endloop + endfacet + facet normal 0.632157 -0.0956949 -0.768908 + outer loop + vertex -325.685 145.917 288.551 + vertex -324.332 154.294 288.621 + vertex -322.836 145.415 290.956 + endloop + endfacet + facet normal 0.63692 -0.093914 -0.765188 + outer loop + vertex -322.836 145.415 290.956 + vertex -324.332 154.294 288.621 + vertex -321.468 153.836 291.061 + endloop + endfacet + facet normal 0.638775 -0.0815994 -0.765054 + outer loop + vertex -324.332 154.294 288.621 + vertex -323.071 162.869 288.759 + vertex -321.468 153.836 291.061 + endloop + endfacet + facet normal 0.648056 -0.0780491 -0.757583 + outer loop + vertex -321.468 153.836 291.061 + vertex -323.071 162.869 288.759 + vertex -320.324 162.444 291.153 + endloop + endfacet + facet normal 0.653423 -0.0353498 -0.756167 + outer loop + vertex -323.071 162.869 288.759 + vertex -322.379 171.601 288.949 + vertex -320.324 162.444 291.153 + endloop + endfacet + facet normal 0.667874 -0.0291068 -0.743705 + outer loop + vertex -320.324 162.444 291.153 + vertex -322.379 171.601 288.949 + vertex -319.753 170.723 291.342 + endloop + endfacet + facet normal 0.624091 -0.167497 -0.763187 + outer loop + vertex -336.22 93.3737 287.555 + vertex -334.909 98.265 287.554 + vertex -334.508 93.3661 288.957 + endloop + endfacet + facet normal 0.643492 -0.17654 -0.744816 + outer loop + vertex -337.803 93.663 286.119 + vertex -336.546 97.7157 286.245 + vertex -336.22 93.3737 287.555 + endloop + endfacet + facet normal 0.639184 -0.230695 -0.733638 + outer loop + vertex -340.777 89.9216 284.684 + vertex -339.351 94.1003 284.612 + vertex -339.222 89.4505 286.187 + endloop + endfacet + facet normal 0.661386 -0.237893 -0.711319 + outer loop + vertex -340.777 89.9216 284.684 + vertex -340.886 94.5994 283.018 + vertex -339.351 94.1003 284.612 + endloop + endfacet + facet normal 0.653371 -0.240404 -0.717853 + outer loop + vertex -342.337 90.4295 283.095 + vertex -340.886 94.5994 283.018 + vertex -340.777 89.9216 284.684 + endloop + endfacet + facet normal 0.67242 -0.246667 -0.697859 + outer loop + vertex -342.337 90.4295 283.095 + vertex -342.416 95.1148 281.362 + vertex -340.886 94.5994 283.018 + endloop + endfacet + facet normal 0.689733 -0.194211 -0.697532 + outer loop + vertex -342.416 95.1148 281.362 + vertex -341.061 100.014 281.337 + vertex -340.886 94.5994 283.018 + endloop + endfacet + facet normal 0.687004 -0.19506 -0.699984 + outer loop + vertex -340.886 94.5994 283.018 + vertex -341.061 100.014 281.337 + vertex -339.622 98.6147 283.14 + endloop + endfacet + facet normal 0.712677 -0.200426 -0.672251 + outer loop + vertex -342.416 95.1148 281.362 + vertex -342.652 99.633 279.764 + vertex -341.061 100.014 281.337 + endloop + endfacet + facet normal 0.702434 -0.204336 -0.681787 + outer loop + vertex -343.924 95.6057 279.661 + vertex -342.652 99.633 279.764 + vertex -342.416 95.1148 281.362 + endloop + endfacet + facet normal 0.685936 -0.2546 -0.681668 + outer loop + vertex -343.882 90.9323 281.449 + vertex -343.924 95.6057 279.661 + vertex -342.416 95.1148 281.362 + endloop + endfacet + facet normal 0.677805 -0.257372 -0.688724 + outer loop + vertex -345.401 91.4249 279.77 + vertex -343.924 95.6057 279.661 + vertex -343.882 90.9323 281.449 + endloop + endfacet + facet normal 0.69489 -0.2629 -0.669337 + outer loop + vertex -345.401 91.4249 279.77 + vertex -345.412 96.0837 277.929 + vertex -343.924 95.6057 279.661 + endloop + endfacet + facet normal 0.713824 -0.205043 -0.669636 + outer loop + vertex -345.412 96.0837 277.929 + vertex -344.04 100.995 277.888 + vertex -343.924 95.6057 279.661 + endloop + endfacet + facet normal 0.732319 -0.210027 -0.647764 + outer loop + vertex -345.412 96.0837 277.929 + vertex -345.587 100.578 276.273 + vertex -344.04 100.995 277.888 + endloop + endfacet + facet normal 0.721714 -0.214281 -0.658188 + outer loop + vertex -346.878 96.5476 276.17 + vertex -345.587 100.578 276.273 + vertex -345.412 96.0837 277.929 + endloop + endfacet + facet normal 0.723586 -0.214938 -0.655915 + outer loop + vertex -346.878 96.5476 276.17 + vertex -346.861 101.895 274.436 + vertex -345.587 100.578 276.273 + endloop + endfacet + facet normal 0.731955 -0.212224 -0.647459 + outer loop + vertex -348.312 96.9839 274.406 + vertex -346.861 101.895 274.436 + vertex -346.878 96.5476 276.17 + endloop + endfacet + facet normal 0.746515 -0.216637 -0.629113 + outer loop + vertex -348.312 96.9839 274.406 + vertex -348.294 101.431 272.896 + vertex -346.861 101.895 274.436 + endloop + endfacet + facet normal 0.734805 -0.220747 -0.641352 + outer loop + vertex -349.633 97.3949 272.751 + vertex -348.294 101.431 272.896 + vertex -348.312 96.9839 274.406 + endloop + endfacet + facet normal 0.726785 -0.217725 -0.651444 + outer loop + vertex -349.633 97.3949 272.751 + vertex -349.205 102.686 271.46 + vertex -348.294 101.431 272.896 + endloop + endfacet + facet normal 0.737448 -0.215795 -0.640002 + outer loop + vertex -350.724 97.8074 271.355 + vertex -349.205 102.686 271.46 + vertex -349.633 97.3949 272.751 + endloop + endfacet + facet normal 0.754179 -0.221471 -0.618195 + outer loop + vertex -350.724 97.8074 271.355 + vertex -350.188 102.21 270.432 + vertex -349.205 102.686 271.46 + endloop + endfacet + facet normal 0.73802 -0.223392 -0.636728 + outer loop + vertex -351.457 98.2211 270.36 + vertex -350.188 102.21 270.432 + vertex -350.724 97.8074 271.355 + endloop + endfacet + facet normal 0.722064 -0.217956 -0.656596 + outer loop + vertex -351.457 98.2211 270.36 + vertex -350.398 103.382 269.812 + vertex -350.188 102.21 270.432 + endloop + endfacet + facet normal 0.743005 -0.219666 -0.632211 + outer loop + vertex -351.832 98.5092 269.82 + vertex -350.398 103.382 269.812 + vertex -351.457 98.2211 270.36 + endloop + endfacet + facet normal 0.865241 -0.25531 -0.431481 + outer loop + vertex -351.832 98.5092 269.82 + vertex -350.762 102.67 269.502 + vertex -350.398 103.382 269.812 + endloop + endfacet + facet normal 0.810881 -0.24884 -0.52967 + outer loop + vertex -352.103 98.0433 269.623 + vertex -350.762 102.67 269.502 + vertex -351.832 98.5092 269.82 + endloop + endfacet + facet normal 0.642002 -0.166422 0.748423 + outer loop + vertex -352.103 98.0433 269.623 + vertex -351.422 100.123 269.501 + vertex -350.762 102.67 269.502 + endloop + endfacet + facet normal 0.237649 -0.0617867 0.969384 + outer loop + vertex -350.762 102.67 269.502 + vertex -351.422 100.123 269.501 + vertex -350.851 102.059 269.485 + endloop + endfacet + facet normal 0.851874 -0.252125 0.459069 + outer loop + vertex -352.361 97.1786 269.626 + vertex -351.422 100.123 269.501 + vertex -352.103 98.0433 269.623 + endloop + endfacet + facet normal 0.691373 -0.264151 -0.672478 + outer loop + vertex -346.89 91.8995 278.053 + vertex -345.412 96.0837 277.929 + vertex -345.401 91.4249 279.77 + endloop + endfacet + facet normal 0.703995 -0.26817 -0.65763 + outer loop + vertex -346.89 91.8995 278.053 + vertex -346.878 96.5476 276.17 + vertex -345.412 96.0837 277.929 + endloop + endfacet + facet normal 0.700038 -0.269625 -0.661248 + outer loop + vertex -348.371 92.3657 276.294 + vertex -346.878 96.5476 276.17 + vertex -346.89 91.8995 278.053 + endloop + endfacet + facet normal 0.712165 -0.273518 -0.646536 + outer loop + vertex -348.371 92.3657 276.294 + vertex -348.312 96.9839 274.406 + vertex -346.878 96.5476 276.17 + endloop + endfacet + facet normal 0.709677 -0.274443 -0.648876 + outer loop + vertex -349.821 92.7992 274.526 + vertex -348.312 96.9839 274.406 + vertex -348.371 92.3657 276.294 + endloop + endfacet + facet normal 0.716386 -0.276622 -0.640525 + outer loop + vertex -349.821 92.7992 274.526 + vertex -349.633 97.3949 272.751 + vertex -348.312 96.9839 274.406 + endloop + endfacet + facet normal 0.713659 -0.277532 -0.643169 + outer loop + vertex -351.155 93.2115 272.867 + vertex -349.633 97.3949 272.751 + vertex -349.821 92.7992 274.526 + endloop + endfacet + facet normal 0.715306 -0.278074 -0.641103 + outer loop + vertex -351.155 93.2115 272.867 + vertex -350.724 97.8074 271.355 + vertex -349.633 97.3949 272.751 + endloop + endfacet + facet normal 0.710635 -0.27918 -0.645798 + outer loop + vertex -352.232 93.6328 271.5 + vertex -350.724 97.8074 271.355 + vertex -351.155 93.2115 272.867 + endloop + endfacet + facet normal 0.713508 -0.280094 -0.642226 + outer loop + vertex -352.232 93.6328 271.5 + vertex -351.457 98.2211 270.36 + vertex -350.724 97.8074 271.355 + endloop + endfacet + facet normal 0.710792 -0.280354 -0.645117 + outer loop + vertex -352.942 94.0378 270.542 + vertex -351.457 98.2211 270.36 + vertex -352.232 93.6328 271.5 + endloop + endfacet + facet normal 0.712157 -0.280765 -0.643431 + outer loop + vertex -352.942 94.0378 270.542 + vertex -351.832 98.5092 269.82 + vertex -351.457 98.2211 270.36 + endloop + endfacet + facet normal 0.711055 -0.280693 -0.64468 + outer loop + vertex -353.313 94.2716 270.03 + vertex -351.832 98.5092 269.82 + vertex -352.942 94.0378 270.542 + endloop + endfacet + facet normal 0.850126 -0.31814 -0.41961 + outer loop + vertex -353.313 94.2716 270.03 + vertex -352.103 98.0433 269.623 + vertex -351.832 98.5092 269.82 + endloop + endfacet + facet normal 0.750174 -0.304148 -0.587139 + outer loop + vertex -353.497 94.1927 269.836 + vertex -352.103 98.0433 269.623 + vertex -353.313 94.2716 270.03 + endloop + endfacet + facet normal 0.616198 -0.180793 0.76656 + outer loop + vertex -353.497 94.1927 269.836 + vertex -352.361 97.1786 269.626 + vertex -352.103 98.0433 269.623 + endloop + endfacet + facet normal 0.883076 -0.357592 -0.303817 + outer loop + vertex -353.683 93.7507 269.816 + vertex -352.361 97.1786 269.626 + vertex -353.497 94.1927 269.836 + endloop + endfacet + facet normal 0.709094 -0.206633 -0.674158 + outer loop + vertex -343.924 95.6057 279.661 + vertex -344.04 100.995 277.888 + vertex -342.652 99.633 279.764 + endloop + endfacet + facet normal 0.667077 -0.248418 -0.702351 + outer loop + vertex -343.882 90.9323 281.449 + vertex -342.416 95.1148 281.362 + vertex -342.337 90.4295 283.095 + endloop + endfacet + facet normal 0.657295 -0.181233 -0.731517 + outer loop + vertex -337.803 93.663 286.119 + vertex -338.014 99.0103 284.605 + vertex -336.546 97.7157 286.245 + endloop + endfacet + facet normal 0.676413 -0.191384 -0.711223 + outer loop + vertex -340.886 94.5994 283.018 + vertex -339.622 98.6147 283.14 + vertex -339.351 94.1003 284.612 + endloop + endfacet + facet normal 0.691906 -0.15819 -0.704444 + outer loop + vertex -339.059 105.692 282.078 + vertex -336.011 104.671 285.301 + vertex -338.014 99.0103 284.605 + endloop + endfacet + facet normal 0.69887 -0.132449 -0.702878 + outer loop + vertex -339.059 105.692 282.078 + vertex -337.088 114.795 282.323 + vertex -336.011 104.671 285.301 + endloop + endfacet + facet normal 0.699976 -0.13203 -0.701856 + outer loop + vertex -336.011 104.671 285.301 + vertex -337.088 114.795 282.323 + vertex -334.065 113.669 285.55 + endloop + endfacet + facet normal 0.703626 -0.118631 -0.700598 + outer loop + vertex -337.088 114.795 282.323 + vertex -335.427 123.514 282.515 + vertex -334.065 113.669 285.55 + endloop + endfacet + facet normal 0.705365 -0.117889 -0.698973 + outer loop + vertex -334.065 113.669 285.55 + vertex -335.427 123.514 282.515 + vertex -332.45 122.337 285.717 + endloop + endfacet + facet normal 0.706549 -0.113579 -0.69849 + outer loop + vertex -335.427 123.514 282.515 + vertex -334.012 131.833 282.593 + vertex -332.45 122.337 285.717 + endloop + endfacet + facet normal 0.710502 -0.111705 -0.694772 + outer loop + vertex -332.45 122.337 285.717 + vertex -334.012 131.833 282.593 + vertex -331.095 130.612 285.772 + endloop + endfacet + facet normal 0.709863 -0.113974 -0.695057 + outer loop + vertex -334.012 131.833 282.593 + vertex -332.714 139.972 282.585 + vertex -331.095 130.612 285.772 + endloop + endfacet + facet normal 0.714455 -0.111698 -0.690708 + outer loop + vertex -331.095 130.612 285.772 + vertex -332.714 139.972 282.585 + vertex -329.839 138.742 285.757 + endloop + endfacet + facet normal 0.713283 -0.115816 -0.691241 + outer loop + vertex -332.714 139.972 282.585 + vertex -331.433 148.142 282.538 + vertex -329.839 138.742 285.757 + endloop + endfacet + facet normal 0.718745 -0.113099 -0.686014 + outer loop + vertex -329.839 138.742 285.757 + vertex -331.433 148.142 282.538 + vertex -328.571 146.926 285.736 + endloop + endfacet + facet normal 0.71846 -0.114112 -0.686144 + outer loop + vertex -331.433 148.142 282.538 + vertex -330.138 156.41 282.518 + vertex -328.571 146.926 285.736 + endloop + endfacet + facet normal 0.721605 -0.112557 -0.683093 + outer loop + vertex -328.571 146.926 285.736 + vertex -330.138 156.41 282.518 + vertex -327.251 155.232 285.762 + endloop + endfacet + facet normal 0.724596 -0.10134 -0.681683 + outer loop + vertex -330.138 156.41 282.518 + vertex -328.853 164.811 282.635 + vertex -327.251 155.232 285.762 + endloop + endfacet + facet normal 0.726697 -0.100307 -0.679595 + outer loop + vertex -327.251 155.232 285.762 + vertex -328.853 164.811 282.635 + vertex -325.954 163.733 285.895 + endloop + endfacet + facet normal 0.736271 -0.0581987 -0.67418 + outer loop + vertex -328.853 164.811 282.635 + vertex -327.784 173.465 283.056 + vertex -325.954 163.733 285.895 + endloop + endfacet + facet normal 0.743464 -0.0546177 -0.666542 + outer loop + vertex -325.954 163.733 285.895 + vertex -327.784 173.465 283.056 + vertex -324.955 172.482 286.292 + endloop + endfacet + facet normal 0.768857 -0.0640713 -0.636202 + outer loop + vertex -328.853 164.811 282.635 + vertex -330.469 174.409 279.715 + vertex -327.784 173.465 283.056 + endloop + endfacet + facet normal 0.76729 -0.0648851 -0.63801 + outer loop + vertex -331.645 165.896 279.167 + vertex -330.469 174.409 279.715 + vertex -328.853 164.811 282.635 + endloop + endfacet + facet normal 0.787146 -0.0692437 -0.612868 + outer loop + vertex -331.645 165.896 279.167 + vertex -332.969 175.294 276.405 + vertex -330.469 174.409 279.715 + endloop + endfacet + facet normal 0.787985 -0.0688219 -0.611835 + outer loop + vertex -334.273 166.844 275.676 + vertex -332.969 175.294 276.405 + vertex -331.645 165.896 279.167 + endloop + endfacet + facet normal 0.779293 -0.110998 -0.616751 + outer loop + vertex -332.954 157.531 279.018 + vertex -334.273 166.844 275.676 + vertex -331.645 165.896 279.167 + endloop + endfacet + facet normal 0.757575 -0.107116 -0.643899 + outer loop + vertex -332.954 157.531 279.018 + vertex -331.645 165.896 279.167 + vertex -330.138 156.41 282.518 + endloop + endfacet + facet normal 0.77532 -0.113207 -0.621339 + outer loop + vertex -335.653 158.329 275.506 + vertex -334.273 166.844 275.676 + vertex -332.954 157.531 279.018 + endloop + endfacet + facet normal 0.772633 -0.126098 -0.622204 + outer loop + vertex -334.281 149.204 279.059 + vertex -335.653 158.329 275.506 + vertex -332.954 157.531 279.018 + endloop + endfacet + facet normal 0.749285 -0.122518 -0.650816 + outer loop + vertex -334.281 149.204 279.059 + vertex -332.954 157.531 279.018 + vertex -331.433 148.142 282.538 + endloop + endfacet + facet normal 0.766327 -0.129772 -0.629207 + outer loop + vertex -337.051 149.614 275.6 + vertex -335.653 158.329 275.506 + vertex -334.281 149.204 279.059 + endloop + endfacet + facet normal 0.7666 -0.128071 -0.629223 + outer loop + vertex -335.591 140.963 279.14 + vertex -337.051 149.614 275.6 + vertex -334.281 149.204 279.059 + endloop + endfacet + facet normal 0.743572 -0.124681 -0.656929 + outer loop + vertex -335.591 140.963 279.14 + vertex -334.281 149.204 279.059 + vertex -332.714 139.972 282.585 + endloop + endfacet + facet normal 0.760744 -0.131652 -0.63556 + outer loop + vertex -338.324 141.19 275.822 + vertex -337.051 149.614 275.6 + vertex -335.591 140.963 279.14 + endloop + endfacet + facet normal 0.761513 -0.12592 -0.635801 + outer loop + vertex -336.918 132.819 279.163 + vertex -338.324 141.19 275.822 + vertex -335.591 140.963 279.14 + endloop + endfacet + facet normal 0.739609 -0.122424 -0.661808 + outer loop + vertex -336.918 132.819 279.163 + vertex -335.591 140.963 279.14 + vertex -334.012 131.833 282.593 + endloop + endfacet + facet normal 0.757862 -0.128096 -0.639716 + outer loop + vertex -339.67 133.272 275.813 + vertex -338.324 141.19 275.822 + vertex -336.918 132.819 279.163 + endloop + endfacet + facet normal 0.758277 -0.125601 -0.639719 + outer loop + vertex -338.372 124.493 279.075 + vertex -339.67 133.272 275.813 + vertex -336.918 132.819 279.163 + endloop + endfacet + facet normal 0.736671 -0.121558 -0.665237 + outer loop + vertex -338.372 124.493 279.075 + vertex -336.918 132.819 279.163 + vertex -335.427 123.514 282.515 + endloop + endfacet + facet normal 0.75401 -0.127928 -0.644285 + outer loop + vertex -341.124 125.001 275.752 + vertex -339.67 133.272 275.813 + vertex -338.372 124.493 279.075 + endloop + endfacet + facet normal 0.753313 -0.131861 -0.644308 + outer loop + vertex -340.048 115.742 278.906 + vertex -341.124 125.001 275.752 + vertex -338.372 124.493 279.075 + endloop + endfacet + facet normal 0.731956 -0.127287 -0.669357 + outer loop + vertex -340.048 115.742 278.906 + vertex -338.372 124.493 279.075 + vertex -337.088 114.795 282.323 + endloop + endfacet + facet normal 0.748446 -0.134188 -0.649478 + outer loop + vertex -342.754 116.396 275.652 + vertex -341.124 125.001 275.752 + vertex -340.048 115.742 278.906 + endloop + endfacet + facet normal 0.745938 -0.146116 -0.649789 + outer loop + vertex -342.032 106.656 278.672 + vertex -342.754 116.396 275.652 + vertex -340.048 115.742 278.906 + endloop + endfacet + facet normal 0.762232 -0.136996 -0.632641 + outer loop + vertex -342.754 116.396 275.652 + vertex -343.241 124.375 273.338 + vertex -341.124 125.001 275.752 + endloop + endfacet + facet normal 0.768796 -0.130662 -0.626003 + outer loop + vertex -341.124 125.001 275.752 + vertex -342.177 133.48 272.69 + vertex -339.67 133.272 275.813 + endloop + endfacet + facet normal 0.769949 -0.130168 -0.624687 + outer loop + vertex -339.67 133.272 275.813 + vertex -340.463 140.413 273.347 + vertex -338.324 141.19 275.822 + endloop + endfacet + facet normal 0.77393 -0.133212 -0.619102 + outer loop + vertex -338.324 141.19 275.822 + vertex -339.505 148.246 272.827 + vertex -337.051 149.614 275.6 + endloop + endfacet + facet normal 0.780914 -0.13191 -0.610552 + outer loop + vertex -337.051 149.614 275.6 + vertex -338.162 158.469 272.266 + vertex -335.653 158.329 275.506 + endloop + endfacet + facet normal 0.782483 -0.118934 -0.611208 + outer loop + vertex -338.162 158.469 272.266 + vertex -336.532 167.56 272.584 + vertex -335.653 158.329 275.506 + endloop + endfacet + facet normal 0.789075 -0.115797 -0.603284 + outer loop + vertex -335.653 158.329 275.506 + vertex -336.532 167.56 272.584 + vertex -334.273 166.844 275.676 + endloop + endfacet + facet normal 0.796932 -0.0744507 -0.599463 + outer loop + vertex -336.532 167.56 272.584 + vertex -335.548 176.209 272.818 + vertex -334.273 166.844 275.676 + endloop + endfacet + facet normal 0.810071 -0.0764364 -0.581328 + outer loop + vertex -337.398 176.866 270.154 + vertex -335.548 176.209 272.818 + vertex -336.532 167.56 272.584 + endloop + endfacet + facet normal 0.808826 -0.0769851 -0.582986 + outer loop + vertex -337.918 168.294 270.564 + vertex -337.398 176.866 270.154 + vertex -336.532 167.56 272.584 + endloop + endfacet + facet normal 0.800961 -0.0723357 -0.594331 + outer loop + vertex -334.273 166.844 275.676 + vertex -335.548 176.209 272.818 + vertex -332.969 175.294 276.405 + endloop + endfacet + facet normal 0.757866 -0.106958 -0.643583 + outer loop + vertex -330.138 156.41 282.518 + vertex -331.645 165.896 279.167 + vertex -328.853 164.811 282.635 + endloop + endfacet + facet normal 0.75443 -0.119648 -0.645383 + outer loop + vertex -331.433 148.142 282.538 + vertex -332.954 157.531 279.018 + vertex -330.138 156.41 282.518 + endloop + endfacet + facet normal 0.749595 -0.121277 -0.650692 + outer loop + vertex -332.714 139.972 282.585 + vertex -334.281 149.204 279.059 + vertex -331.433 148.142 282.538 + endloop + endfacet + facet normal 0.744816 -0.119509 -0.65648 + outer loop + vertex -334.012 131.833 282.593 + vertex -335.591 140.963 279.14 + vertex -332.714 139.972 282.585 + endloop + endfacet + facet normal 0.74027 -0.119662 -0.661575 + outer loop + vertex -335.427 123.514 282.515 + vertex -336.918 132.819 279.163 + vertex -334.012 131.833 282.593 + endloop + endfacet + facet normal 0.735722 -0.125514 -0.665552 + outer loop + vertex -337.088 114.795 282.323 + vertex -338.372 124.493 279.075 + vertex -335.427 123.514 282.515 + endloop + endfacet + facet normal 0.728902 -0.139832 -0.670186 + outer loop + vertex -339.059 105.692 282.078 + vertex -340.048 115.742 278.906 + vertex -337.088 114.795 282.323 + endloop + endfacet + facet normal 0.725799 -0.141113 -0.673278 + outer loop + vertex -342.032 106.656 278.672 + vertex -340.048 115.742 278.906 + vertex -339.059 105.692 282.078 + endloop + endfacet + facet normal 0.7435 -0.147093 -0.652358 + outer loop + vertex -344.799 107.57 275.312 + vertex -342.754 116.396 275.652 + vertex -342.032 106.656 278.672 + endloop + endfacet + facet normal 0.75497 -0.150293 -0.638305 + outer loop + vertex -344.799 107.57 275.312 + vertex -344.945 117.368 272.832 + vertex -342.754 116.396 275.652 + endloop + endfacet + facet normal 0.751165 -0.176915 -0.635966 + outer loop + vertex -349.205 102.686 271.46 + vertex -350.188 102.21 270.432 + vertex -348.668 108.938 270.355 + endloop + endfacet + facet normal 0.774409 -0.181821 -0.605997 + outer loop + vertex -350.188 102.21 270.432 + vertex -350.398 103.382 269.812 + vertex -348.668 108.938 270.355 + endloop + endfacet + facet normal 0.792999 -0.190269 -0.578749 + outer loop + vertex -349.213 109.093 269.557 + vertex -348.668 108.938 270.355 + vertex -350.398 103.382 269.812 + endloop + endfacet + facet normal 0.827968 -0.195156 -0.525722 + outer loop + vertex -350.762 102.67 269.502 + vertex -349.213 109.093 269.557 + vertex -350.398 103.382 269.812 + endloop + endfacet + facet normal 0.800536 -0.158961 -0.577818 + outer loop + vertex -349.213 109.093 269.557 + vertex -347.465 117.542 269.654 + vertex -348.668 108.938 270.355 + endloop + endfacet + facet normal 0.784151 -0.158476 -0.599994 + outer loop + vertex -348.668 108.938 270.355 + vertex -347.465 117.542 269.654 + vertex -346.525 117.999 270.763 + endloop + endfacet + facet normal 0.754417 -0.150456 -0.638919 + outer loop + vertex -347.132 108.383 272.366 + vertex -344.945 117.368 272.832 + vertex -344.799 107.57 275.312 + endloop + endfacet + facet normal 0.778088 -0.143219 -0.61161 + outer loop + vertex -346.525 117.999 270.763 + vertex -345.821 126.067 269.769 + vertex -344.496 127.655 271.082 + endloop + endfacet + facet normal 0.758411 -0.138464 -0.636899 + outer loop + vertex -344.945 117.368 272.832 + vertex -343.241 124.375 273.338 + vertex -342.754 116.396 275.652 + endloop + endfacet + facet normal 0.76217 -0.13413 -0.633329 + outer loop + vertex -343.241 124.375 273.338 + vertex -342.177 133.48 272.69 + vertex -341.124 125.001 275.752 + endloop + endfacet + facet normal 0.779384 -0.137093 -0.611363 + outer loop + vertex -344.496 127.655 271.082 + vertex -344.357 134.541 269.716 + vertex -343.326 136.797 270.524 + endloop + endfacet + facet normal 0.781922 -0.138194 -0.607865 + outer loop + vertex -343.326 136.797 270.524 + vertex -343.01 142.218 269.698 + vertex -341.651 143.998 271.042 + endloop + endfacet + facet normal 0.768784 -0.13075 -0.625999 + outer loop + vertex -342.177 133.48 272.69 + vertex -340.463 140.413 273.347 + vertex -339.67 133.272 275.813 + endloop + endfacet + facet normal 0.770209 -0.135579 -0.623214 + outer loop + vertex -340.463 140.413 273.347 + vertex -339.505 148.246 272.827 + vertex -338.324 141.19 275.822 + endloop + endfacet + facet normal 0.786106 -0.139387 -0.60217 + outer loop + vertex -341.651 143.998 271.042 + vertex -341.511 150.33 269.758 + vertex -340.175 154.032 270.646 + endloop + endfacet + facet normal 0.774241 -0.135623 -0.618188 + outer loop + vertex -339.505 148.246 272.827 + vertex -338.162 158.469 272.266 + vertex -337.051 149.614 275.6 + endloop + endfacet + facet normal 0.798004 -0.139149 -0.586367 + outer loop + vertex -340.175 154.032 270.646 + vertex -339.959 159.408 269.665 + vertex -339.108 161.809 270.253 + endloop + endfacet + facet normal 0.797071 -0.122243 -0.591383 + outer loop + vertex -336.532 167.56 272.584 + vertex -338.162 158.469 272.266 + vertex -337.918 168.294 270.564 + endloop + endfacet + facet normal 0.813674 -0.0769541 -0.576206 + outer loop + vertex -337.918 168.294 270.564 + vertex -337.505 176.904 269.998 + vertex -337.398 176.866 270.154 + endloop + endfacet + facet normal 0.507112 -0.0451964 -0.860694 + outer loop + vertex -338.057 172.114 269.594 + vertex -338.637 167.849 269.476 + vertex -339.194 166.022 269.244 + endloop + endfacet + facet normal 0.67695 -0.113937 -0.727156 + outer loop + vertex -338.637 167.849 269.476 + vertex -339.144 164.762 269.488 + vertex -339.194 166.022 269.244 + endloop + endfacet + facet normal 0.783853 -0.128978 -0.607404 + outer loop + vertex -339.959 159.408 269.665 + vertex -338.605 167.525 269.689 + vertex -339.108 161.809 270.253 + endloop + endfacet + facet normal 0.664615 -0.116542 -0.738042 + outer loop + vertex -339.144 164.762 269.488 + vertex -339.721 161.47 269.488 + vertex -339.194 166.022 269.244 + endloop + endfacet + facet normal 0.778366 -0.137526 -0.612563 + outer loop + vertex -339.721 161.47 269.488 + vertex -340.242 158.411 269.512 + vertex -340.754 157.059 269.166 + endloop + endfacet + facet normal 0.782396 -0.140546 -0.606715 + outer loop + vertex -340.242 158.411 269.512 + vertex -340.995 154.317 269.49 + vertex -340.754 157.059 269.166 + endloop + endfacet + facet normal 0.788401 -0.141029 -0.598778 + outer loop + vertex -341.511 150.33 269.758 + vertex -339.959 159.408 269.665 + vertex -340.175 154.032 270.646 + endloop + endfacet + facet normal 0.793978 -0.14273 -0.590955 + outer loop + vertex -340.995 154.317 269.49 + vertex -341.768 150.114 269.467 + vertex -342.293 148.678 269.108 + endloop + endfacet + facet normal 0.794135 -0.142847 -0.590715 + outer loop + vertex -341.768 150.114 269.467 + vertex -342.566 145.889 269.416 + vertex -342.293 148.678 269.108 + endloop + endfacet + facet normal 0.782848 -0.140138 -0.606226 + outer loop + vertex -343.01 142.218 269.698 + vertex -341.511 150.33 269.758 + vertex -341.651 143.998 271.042 + endloop + endfacet + facet normal 0.802413 -0.144409 -0.579033 + outer loop + vertex -342.566 145.889 269.416 + vertex -343.262 142.176 269.377 + vertex -343.842 140.056 269.103 + endloop + endfacet + facet normal 0.797863 -0.142286 -0.585807 + outer loop + vertex -343.262 142.176 269.377 + vertex -343.768 139.277 269.392 + vertex -343.842 140.056 269.103 + endloop + endfacet + facet normal 0.780659 -0.138361 -0.609449 + outer loop + vertex -344.357 134.541 269.716 + vertex -343.01 142.218 269.698 + vertex -343.326 136.797 270.524 + endloop + endfacet + facet normal 0.79856 -0.141901 -0.58495 + outer loop + vertex -343.768 139.277 269.392 + vertex -344.453 135.629 269.343 + vertex -343.842 140.056 269.103 + endloop + endfacet + facet normal 0.787683 -0.139509 -0.600077 + outer loop + vertex -344.453 135.629 269.343 + vertex -345.167 131.287 269.414 + vertex -345.535 130.925 269.015 + endloop + endfacet + facet normal 0.775793 -0.137889 -0.615737 + outer loop + vertex -345.821 126.067 269.769 + vertex -344.357 134.541 269.716 + vertex -344.496 127.655 271.082 + endloop + endfacet + facet normal 0.787653 -0.139409 -0.60014 + outer loop + vertex -345.167 131.287 269.414 + vertex -345.946 127.068 269.372 + vertex -345.535 130.925 269.015 + endloop + endfacet + facet normal 0.767233 -0.137112 -0.626541 + outer loop + vertex -345.946 127.068 269.372 + vertex -346.615 123.025 269.437 + vertex -347.156 121.555 269.096 + endloop + endfacet + facet normal 0.782975 -0.142882 -0.605421 + outer loop + vertex -347.465 117.542 269.654 + vertex -345.821 126.067 269.769 + vertex -346.525 117.999 270.763 + endloop + endfacet + facet normal 0.765171 -0.135699 -0.629364 + outer loop + vertex -346.615 123.025 269.437 + vertex -347.103 120.419 269.407 + vertex -347.156 121.555 269.096 + endloop + endfacet + facet normal 0.756705 -0.138693 -0.638875 + outer loop + vertex -347.103 120.419 269.407 + vertex -347.608 117.659 269.407 + vertex -347.156 121.555 269.096 + endloop + endfacet + facet normal 0.775518 -0.149687 -0.613324 + outer loop + vertex -347.908 124.103 267.525 + vertex -347.156 121.555 269.096 + vertex -349.405 113.199 268.292 + endloop + endfacet + facet normal 0.762368 -0.164431 -0.625905 + outer loop + vertex -350.913 105.82 268.394 + vertex -349.405 113.199 268.292 + vertex -350.13 106.749 269.104 + endloop + endfacet + facet normal 0.777684 -0.167287 -0.605989 + outer loop + vertex -350.913 105.82 268.394 + vertex -351.674 106.962 267.102 + vertex -349.405 113.199 268.292 + endloop + endfacet + facet normal 0.777525 -0.169334 -0.605624 + outer loop + vertex -353.13 106.434 265.38 + vertex -351.279 113.571 265.762 + vertex -351.674 106.962 267.102 + endloop + endfacet + facet normal 0.784428 -0.171638 -0.595998 + outer loop + vertex -353.13 106.434 265.38 + vertex -354.327 107.814 263.408 + vertex -351.279 113.571 265.762 + endloop + endfacet + facet normal 0.784122 -0.174513 -0.595565 + outer loop + vertex -356.191 107.474 261.053 + vertex -353.964 114.247 262.001 + vertex -354.327 107.814 263.408 + endloop + endfacet + facet normal 0.790818 -0.178115 -0.585561 + outer loop + vertex -356.191 107.474 261.053 + vertex -357.554 108.92 258.773 + vertex -353.964 114.247 262.001 + endloop + endfacet + facet normal 0.793209 -0.179066 -0.582027 + outer loop + vertex -359.573 108.635 256.109 + vertex -357.079 115.531 257.385 + vertex -357.554 108.92 258.773 + endloop + endfacet + facet normal 0.800431 -0.183801 -0.57055 + outer loop + vertex -359.573 108.635 256.109 + vertex -361.004 110.074 253.637 + vertex -357.079 115.531 257.385 + endloop + endfacet + facet normal 0.802603 -0.183275 -0.567661 + outer loop + vertex -363.114 109.768 250.754 + vertex -360.541 116.73 252.143 + vertex -361.004 110.074 253.637 + endloop + endfacet + facet normal 0.809749 -0.188293 -0.555745 + outer loop + vertex -363.114 109.768 250.754 + vertex -364.575 111.212 248.135 + vertex -360.541 116.73 252.143 + endloop + endfacet + facet normal 0.807528 -0.221561 -0.546634 + outer loop + vertex -366.691 110.907 245.133 + vertex -364.575 111.212 248.135 + vertex -367.595 106.416 245.618 + endloop + endfacet + facet normal 0.807527 -0.221561 -0.546636 + outer loop + vertex -369.369 106.993 242.763 + vertex -366.691 110.907 245.133 + vertex -367.595 106.416 245.618 + endloop + endfacet + facet normal 0.81352 -0.219686 -0.538445 + outer loop + vertex -371.118 107.554 239.892 + vertex -368.124 112.345 242.46 + vertex -369.369 106.993 242.763 + endloop + endfacet + facet normal 0.816559 -0.225477 -0.531405 + outer loop + vertex -372.863 108.11 236.975 + vertex -370.196 112.026 239.411 + vertex -371.118 107.554 239.892 + endloop + endfacet + facet normal 0.822089 -0.222369 -0.52414 + outer loop + vertex -374.623 108.663 233.979 + vertex -371.62 113.459 236.654 + vertex -372.863 108.11 236.975 + endloop + endfacet + facet normal 0.825193 -0.228105 -0.516743 + outer loop + vertex -376.404 109.213 230.893 + vertex -373.705 113.132 233.472 + vertex -374.623 108.663 233.979 + endloop + endfacet + facet normal 0.830321 -0.224793 -0.509937 + outer loop + vertex -378.2 109.762 227.726 + vertex -375.159 114.559 230.562 + vertex -376.404 109.213 230.893 + endloop + endfacet + facet normal 0.833402 -0.230255 -0.502418 + outer loop + vertex -379.987 110.3 224.515 + vertex -377.273 114.225 227.219 + vertex -378.2 109.762 227.726 + endloop + endfacet + facet normal 0.838678 -0.226993 -0.49507 + outer loop + vertex -381.761 110.827 221.268 + vertex -378.721 115.636 224.214 + vertex -379.987 110.3 224.515 + endloop + endfacet + facet normal 0.841883 -0.231367 -0.487547 + outer loop + vertex -383.524 111.329 217.986 + vertex -380.825 115.278 220.772 + vertex -381.761 110.827 221.268 + endloop + endfacet + facet normal 0.846854 -0.228504 -0.480233 + outer loop + vertex -385.286 111.799 214.654 + vertex -382.257 116.643 217.692 + vertex -383.524 111.329 217.986 + endloop + endfacet + facet normal 0.850092 -0.23259 -0.472489 + outer loop + vertex -387.053 112.254 211.252 + vertex -384.359 116.236 214.138 + vertex -385.286 111.799 214.654 + endloop + endfacet + facet normal 0.855378 -0.230658 -0.463816 + outer loop + vertex -388.817 112.768 207.743 + vertex -385.799 117.606 210.903 + vertex -387.053 112.254 211.252 + endloop + endfacet + facet normal 0.857574 -0.208194 -0.470343 + outer loop + vertex -385.277 124.242 208.917 + vertex -381.72 123.22 215.855 + vertex -385.799 117.606 210.903 + endloop + endfacet + facet normal 0.85731 -0.230321 -0.460403 + outer loop + vertex -389.311 118.882 203.718 + vertex -387.898 117.3 207.141 + vertex -390.572 113.466 204.079 + endloop + endfacet + facet normal 0.868484 -0.192137 -0.456966 + outer loop + vertex -388.937 125.094 201.603 + vertex -383.506 134.112 208.134 + vertex -385.277 124.242 208.917 + endloop + endfacet + facet normal 0.868868 -0.218358 -0.444283 + outer loop + vertex -392.3 126.729 194.222 + vertex -388.937 125.094 201.603 + vertex -394.168 116.936 195.382 + endloop + endfacet + facet normal 0.862776 -0.232265 -0.449076 + outer loop + vertex -391.137 118.856 200.223 + vertex -389.311 118.882 203.718 + vertex -392.312 114.563 200.187 + endloop + endfacet + facet normal 0.854994 -0.266187 -0.445118 + outer loop + vertex -393.634 109.477 200.687 + vertex -395.422 110.374 196.717 + vertex -392.312 114.563 200.187 + endloop + endfacet + facet normal 0.900572 -0.223269 -0.372989 + outer loop + vertex -407.147 120.392 164.69 + vertex -402.055 129.423 171.58 + vertex -404.137 119.694 172.374 + endloop + endfacet + facet normal 0.908246 -0.22422 -0.35329 + outer loop + vertex -410.006 121.064 156.913 + vertex -405.057 130.112 163.895 + vertex -407.147 120.392 164.69 + endloop + endfacet + facet normal 0.915891 -0.225269 -0.332262 + outer loop + vertex -412.669 121.701 149.141 + vertex -407.895 130.785 156.142 + vertex -410.006 121.064 156.913 + endloop + endfacet + facet normal 0.923584 -0.226723 -0.309174 + outer loop + vertex -415.095 122.296 141.457 + vertex -410.53 131.424 148.4 + vertex -412.669 121.701 149.141 + endloop + endfacet + facet normal 0.931357 -0.228866 -0.283187 + outer loop + vertex -417.284 122.851 133.81 + vertex -412.935 132.017 140.705 + vertex -415.095 122.296 141.457 + endloop + endfacet + facet normal 0.938965 -0.231463 -0.254501 + outer loop + vertex -419.243 123.369 126.112 + vertex -415.101 132.572 133.022 + vertex -417.284 122.851 133.81 + endloop + endfacet + facet normal 0.945955 -0.234051 -0.224476 + outer loop + vertex -420.94 123.846 118.464 + vertex -417.017 133.088 125.357 + vertex -419.243 123.369 126.112 + endloop + endfacet + facet normal 0.952329 -0.23662 -0.192562 + outer loop + vertex -422.333 124.269 111.052 + vertex -418.66 133.56 117.803 + vertex -420.94 123.846 118.464 + endloop + endfacet + facet normal 0.958339 -0.239361 -0.15586 + outer loop + vertex -423.419 124.64 103.806 + vertex -420.009 133.991 110.412 + vertex -422.333 124.269 111.052 + endloop + endfacet + facet normal 0.954513 -0.275813 -0.113274 + outer loop + vertex -425.688 117.617 101.788 + vertex -425.79 118.656 98.3986 + vertex -423.419 124.64 103.806 + endloop + endfacet + facet normal 0.945843 -0.301299 -0.120831 + outer loop + vertex -425.79 118.656 98.3986 + vertex -425.688 117.617 101.788 + vertex -427.411 113.498 98.5714 + endloop + endfacet + facet normal 0.945383 -0.304378 -0.116643 + outer loop + vertex -427.411 113.498 98.5714 + vertex -425.688 117.617 101.788 + vertex -427.011 113.356 102.185 + endloop + endfacet + facet normal 0.948862 -0.301351 -0.0940703 + outer loop + vertex -427.732 113.64 94.8815 + vertex -425.79 118.656 98.3986 + vertex -427.411 113.498 98.5714 + endloop + endfacet + facet normal 0.950062 -0.304086 -0.0701011 + outer loop + vertex -427.963 113.778 91.1476 + vertex -426.392 117.923 94.4585 + vertex -427.732 113.64 94.8815 + endloop + endfacet + facet normal 0.936911 -0.347148 -0.0410558 + outer loop + vertex -428.092 113.873 87.4076 + vertex -427.963 113.778 91.1476 + vertex -429.696 109.545 87.3957 + endloop + endfacet + facet normal 0.937656 -0.347522 -0.00541301 + outer loop + vertex -429.704 109.582 83.6966 + vertex -428.092 113.873 87.4076 + vertex -429.696 109.545 87.3957 + endloop + endfacet + facet normal 0.936926 -0.347881 0.0339005 + outer loop + vertex -429.604 109.493 80.0417 + vertex -428.11 113.87 83.6694 + vertex -429.704 109.582 83.6966 + endloop + endfacet + facet normal 0.936018 -0.350018 0.0368528 + outer loop + vertex -427.992 113.794 79.9474 + vertex -428.11 113.87 83.6694 + vertex -429.604 109.493 80.0417 + endloop + endfacet + facet normal 0.947866 -0.309786 0.0747144 + outer loop + vertex -427.677 113.9 76.3916 + vertex -426.569 118.037 79.4779 + vertex -427.992 113.794 79.9474 + endloop + endfacet + facet normal 0.944992 -0.307416 0.11174 + outer loop + vertex -427.053 114.694 73.2961 + vertex -425.968 119.154 76.3873 + vertex -427.677 113.9 76.3916 + endloop + endfacet + facet normal 0.915999 -0.38166 0.123621 + outer loop + vertex -428.224 110.43 70.7258 + vertex -428.914 109.606 73.3014 + vertex -430.249 105.523 70.5798 + endloop + endfacet + facet normal 0.905315 -0.379262 0.191218 + outer loop + vertex -429.672 106.016 68.8285 + vertex -428.224 110.43 70.7258 + vertex -430.249 105.523 70.5798 + endloop + endfacet + facet normal 0.884503 -0.434976 0.168673 + outer loop + vertex -429.672 106.016 68.8285 + vertex -430.249 105.523 70.5798 + vertex -431.615 101.933 68.4902 + endloop + endfacet + facet normal 0.873107 -0.433982 0.222134 + outer loop + vertex -431.128 102.456 67.5954 + vertex -429.672 106.016 68.8285 + vertex -431.615 101.933 68.4902 + endloop + endfacet + facet normal 0.864466 -0.43859 0.245635 + outer loop + vertex -429.258 106.355 67.9773 + vertex -429.672 106.016 68.8285 + vertex -431.128 102.456 67.5954 + endloop + endfacet + facet normal 0.873848 -0.445751 0.194154 + outer loop + vertex -431.615 101.933 68.4902 + vertex -430.249 105.523 70.5798 + vertex -432.208 101.515 70.1991 + endloop + endfacet + facet normal 0.901429 -0.382751 0.202303 + outer loop + vertex -427.799 110.465 68.9023 + vertex -428.224 110.43 70.7258 + vertex -429.672 106.016 68.8285 + endloop + endfacet + facet normal 0.883287 -0.376395 0.279519 + outer loop + vertex -429.258 106.355 67.9773 + vertex -427.799 110.465 68.9023 + vertex -429.672 106.016 68.8285 + endloop + endfacet + facet normal 0.811518 -0.386616 0.43814 + outer loop + vertex -428.257 108.637 68.1367 + vertex -427.799 110.465 68.9023 + vertex -429.258 106.355 67.9773 + endloop + endfacet + facet normal 0.91736 -0.325552 0.229055 + outer loop + vertex -427.799 110.465 68.9023 + vertex -428.257 108.637 68.1367 + vertex -427.721 110.223 68.2425 + endloop + endfacet + facet normal 0.907825 -0.393396 0.145236 + outer loop + vertex -430.249 105.523 70.5798 + vertex -428.914 109.606 73.3014 + vertex -430.769 105.27 73.1505 + endloop + endfacet + facet normal 0.967477 -0.226264 0.113105 + outer loop + vertex -418.562 145.068 70.578 + vertex -417.23 152.964 74.9777 + vertex -419.281 144.203 74.9939 + endloop + endfacet + facet normal 0.967457 -0.226308 0.113191 + outer loop + vertex -416.476 154.109 70.8222 + vertex -417.23 152.964 74.9777 + vertex -418.562 145.068 70.578 + endloop + endfacet + facet normal 0.962872 -0.226174 0.14739 + outer loop + vertex -416.476 154.109 70.8222 + vertex -418.562 145.068 70.578 + vertex -417.532 148.497 69.1139 + endloop + endfacet + facet normal 0.967631 -0.225421 0.113467 + outer loop + vertex -416.476 154.109 70.8222 + vertex -415.188 161.75 75.0192 + vertex -417.23 152.964 74.9777 + endloop + endfacet + facet normal 0.966601 -0.227618 0.117782 + outer loop + vertex -414.402 162.806 70.6094 + vertex -415.188 161.75 75.0192 + vertex -416.476 154.109 70.8222 + endloop + endfacet + facet normal 0.962404 -0.225805 0.150968 + outer loop + vertex -414.402 162.806 70.6094 + vertex -416.476 154.109 70.8222 + vertex -415.494 157.163 69.1346 + endloop + endfacet + facet normal 0.967206 -0.224595 0.118613 + outer loop + vertex -414.402 162.806 70.6094 + vertex -413.129 170.602 74.9907 + vertex -415.188 161.75 75.0192 + endloop + endfacet + facet normal 0.966735 -0.225597 0.120533 + outer loop + vertex -412.312 171.871 70.8128 + vertex -413.129 170.602 74.9907 + vertex -414.402 162.806 70.6094 + endloop + endfacet + facet normal 0.961383 -0.225208 0.15819 + outer loop + vertex -412.312 171.871 70.8128 + vertex -414.402 162.806 70.6094 + vertex -413.328 166.367 69.1535 + endloop + endfacet + facet normal 0.967392 -0.222122 0.121718 + outer loop + vertex -412.312 171.871 70.8128 + vertex -411.077 179.502 74.9264 + vertex -413.129 170.602 74.9907 + endloop + endfacet + facet normal 0.966329 -0.224303 0.126082 + outer loop + vertex -410.298 180.498 70.7273 + vertex -411.077 179.502 74.9264 + vertex -412.312 171.871 70.8128 + endloop + endfacet + facet normal 0.960876 -0.222647 0.164761 + outer loop + vertex -410.298 180.498 70.7273 + vertex -412.312 171.871 70.8128 + vertex -411.303 174.973 69.1209 + endloop + endfacet + facet normal 0.969612 -0.206705 0.130867 + outer loop + vertex -410.298 180.498 70.7273 + vertex -409.19 188.307 74.851 + vertex -411.077 179.502 74.9264 + endloop + endfacet + facet normal 0.966303 -0.213254 0.144157 + outer loop + vertex -408.592 188.073 70.4995 + vertex -409.19 188.307 74.851 + vertex -410.298 180.498 70.7273 + endloop + endfacet + facet normal 0.960254 -0.210722 0.183054 + outer loop + vertex -408.592 188.073 70.4995 + vertex -410.298 180.498 70.7273 + vertex -409.328 183.345 68.918 + endloop + endfacet + facet normal 0.977195 -0.157304 0.14264 + outer loop + vertex -409.19 188.307 74.851 + vertex -408.592 188.073 70.4995 + vertex -407.635 197.374 74.199 + endloop + endfacet + facet normal 0.959199 -0.184075 0.2146 + outer loop + vertex -407.556 192.614 69.7607 + vertex -407.635 197.374 74.199 + vertex -408.592 188.073 70.4995 + endloop + endfacet + facet normal 0.972812 -0.149038 0.177271 + outer loop + vertex -407.556 192.614 69.7607 + vertex -406.712 197.208 68.9935 + vertex -407.635 197.374 74.199 + endloop + endfacet + facet normal 0.933145 -0.221945 0.282809 + outer loop + vertex -418.533 143.402 68.2228 + vertex -420.604 134.678 68.2079 + vertex -419.457 138.116 67.1222 + endloop + endfacet + facet normal 0.962989 -0.226397 0.146274 + outer loop + vertex -419.682 139.338 69.0814 + vertex -418.852 142.804 68.9829 + vertex -418.562 145.068 70.578 + endloop + endfacet + facet normal 0.963211 -0.225917 0.145553 + outer loop + vertex -418.852 142.804 68.9829 + vertex -418.424 144.638 68.996 + vertex -418.562 145.068 70.578 + endloop + endfacet + facet normal 0.962949 -0.226879 0.145792 + outer loop + vertex -418.424 144.638 68.996 + vertex -417.532 148.497 69.1139 + vertex -418.562 145.068 70.578 + endloop + endfacet + facet normal 0.939218 -0.221363 0.262425 + outer loop + vertex -416.364 152.563 68.1883 + vertex -418.533 143.402 68.2228 + vertex -417.229 147.804 67.2662 + endloop + endfacet + facet normal 0.963096 -0.225898 0.146345 + outer loop + vertex -417.532 148.497 69.1139 + vertex -416.519 152.812 69.1069 + vertex -416.476 154.109 70.8222 + endloop + endfacet + facet normal 0.96248 -0.227645 0.147682 + outer loop + vertex -416.519 152.812 69.1069 + vertex -415.494 157.163 69.1346 + vertex -416.476 154.109 70.8222 + endloop + endfacet + facet normal 0.937095 -0.221488 0.269807 + outer loop + vertex -414.268 161.533 68.2703 + vertex -416.364 152.563 68.1883 + vertex -414.874 157.515 67.0748 + endloop + endfacet + facet normal 0.961666 -0.226578 0.154472 + outer loop + vertex -415.494 157.163 69.1346 + vertex -414.639 160.732 69.0459 + vertex -414.402 162.806 70.6094 + endloop + endfacet + facet normal 0.961418 -0.227115 0.155222 + outer loop + vertex -414.639 160.732 69.0459 + vertex -414.205 162.576 69.0507 + vertex -414.402 162.806 70.6094 + endloop + endfacet + facet normal 0.961573 -0.226507 0.155152 + outer loop + vertex -414.205 162.576 69.0507 + vertex -413.328 166.367 69.1535 + vertex -414.402 162.806 70.6094 + endloop + endfacet + facet normal 0.936703 -0.22069 0.271815 + outer loop + vertex -412.186 170.32 68.2288 + vertex -414.268 161.533 68.2703 + vertex -412.884 165.616 66.817 + endloop + endfacet + facet normal 0.961399 -0.22519 0.158118 + outer loop + vertex -413.328 166.367 69.1535 + vertex -412.327 170.615 69.1167 + vertex -412.312 171.871 70.8128 + endloop + endfacet + facet normal 0.961105 -0.226011 0.15873 + outer loop + vertex -412.327 170.615 69.1167 + vertex -411.303 174.973 69.1209 + vertex -412.312 171.871 70.8128 + endloop + endfacet + facet normal 0.934102 -0.217471 0.283125 + outer loop + vertex -410.204 178.728 68.1494 + vertex -412.186 170.32 68.2288 + vertex -411.016 174.37 67.4802 + endloop + endfacet + facet normal 0.959581 -0.224032 0.170336 + outer loop + vertex -411.303 174.973 69.1209 + vertex -410.296 179.184 68.9889 + vertex -410.298 180.498 70.7273 + endloop + endfacet + facet normal 0.960821 -0.220631 0.167766 + outer loop + vertex -410.296 179.184 68.9889 + vertex -409.328 183.345 68.918 + vertex -410.298 180.498 70.7273 + endloop + endfacet + facet normal 0.931151 -0.207261 0.300001 + outer loop + vertex -408.193 187.706 68.1079 + vertex -410.204 178.728 68.1494 + vertex -408.988 182.371 66.8911 + endloop + endfacet + facet normal 0.955581 -0.215881 0.200651 + outer loop + vertex -409.328 183.345 68.918 + vertex -408.509 186.831 68.7641 + vertex -408.592 188.073 70.4995 + endloop + endfacet + facet normal 0.95868 -0.207398 0.194728 + outer loop + vertex -408.509 186.831 68.7641 + vertex -408.141 188.7 68.9456 + vertex -408.592 188.073 70.4995 + endloop + endfacet + facet normal 0.961098 -0.186236 0.203978 + outer loop + vertex -408.141 188.7 68.9456 + vertex -407.556 192.614 69.7607 + vertex -408.592 188.073 70.4995 + endloop + endfacet + facet normal 0.965677 -0.14089 0.218216 + outer loop + vertex -406.712 197.208 68.9935 + vertex -407.556 192.614 69.7607 + vertex -406.668 197.199 68.793 + endloop + endfacet + facet normal 0.936694 -0.186463 0.296372 + outer loop + vertex -407.696 187.44 66.3717 + vertex -407.039 192.248 67.3203 + vertex -408.193 187.706 68.1079 + endloop + endfacet + facet normal 0.931828 -0.206933 0.298119 + outer loop + vertex -407.696 187.44 66.3717 + vertex -408.193 187.706 68.1079 + vertex -408.988 182.371 66.8911 + endloop + endfacet + facet normal 0.934726 -0.214112 0.283625 + outer loop + vertex -410.082 177.725 66.9893 + vertex -408.988 182.371 66.8911 + vertex -410.204 178.728 68.1494 + endloop + endfacet + facet normal 0.932959 -0.217795 0.286622 + outer loop + vertex -410.082 177.725 66.9893 + vertex -410.204 178.728 68.1494 + vertex -411.016 174.37 67.4802 + endloop + endfacet + facet normal 0.936297 -0.219807 0.27392 + outer loop + vertex -411.72 170.699 66.9419 + vertex -411.016 174.37 67.4802 + vertex -412.186 170.32 68.2288 + endloop + endfacet + facet normal 0.936122 -0.221102 0.273476 + outer loop + vertex -411.72 170.699 66.9419 + vertex -412.186 170.32 68.2288 + vertex -412.884 165.616 66.817 + endloop + endfacet + facet normal 0.937932 -0.223443 0.26525 + outer loop + vertex -413.966 161.546 67.2124 + vertex -412.884 165.616 66.817 + vertex -414.268 161.533 68.2703 + endloop + endfacet + facet normal 0.938583 -0.220423 0.265473 + outer loop + vertex -413.966 161.546 67.2124 + vertex -414.268 161.533 68.2703 + vertex -414.874 157.515 67.0748 + endloop + endfacet + facet normal 0.936676 -0.220934 0.271709 + outer loop + vertex -415.987 152.182 66.5755 + vertex -414.874 157.515 67.0748 + vertex -416.364 152.563 68.1883 + endloop + endfacet + facet normal 0.93618 -0.222667 0.272003 + outer loop + vertex -415.987 152.182 66.5755 + vertex -416.364 152.563 68.1883 + vertex -417.229 147.804 67.2662 + endloop + endfacet + facet normal 0.936994 -0.218496 0.272584 + outer loop + vertex -418.128 143.073 66.5664 + vertex -417.229 147.804 67.2662 + vertex -418.533 143.402 68.2228 + endloop + endfacet + facet normal 0.936461 -0.220449 0.272842 + outer loop + vertex -418.128 143.073 66.5664 + vertex -418.533 143.402 68.2228 + vertex -419.457 138.116 67.1222 + endloop + endfacet + facet normal 0.93268 -0.221098 0.284998 + outer loop + vertex -420.382 134.435 67.2947 + vertex -419.457 138.116 67.1222 + vertex -420.604 134.678 68.2079 + endloop + endfacet + facet normal 0.929412 -0.231902 0.28708 + outer loop + vertex -420.382 134.435 67.2947 + vertex -420.604 134.678 68.2079 + vertex -421.258 130.632 67.0583 + endloop + endfacet + facet normal 0.927703 -0.241273 0.284875 + outer loop + vertex -422.384 125.438 66.3261 + vertex -421.258 130.632 67.0583 + vertex -422.854 125.766 68.1346 + endloop + endfacet + facet normal 0.921255 -0.262484 0.28704 + outer loop + vertex -422.384 125.438 66.3261 + vertex -422.854 125.766 68.1346 + vertex -423.987 120.256 66.7318 + endloop + endfacet + facet normal 0.909705 -0.281701 0.305094 + outer loop + vertex -425.39 115.456 66.4826 + vertex -423.987 120.256 66.7318 + vertex -425.903 115.477 68.0317 + endloop + endfacet + facet normal 0.897811 -0.320814 0.301685 + outer loop + vertex -425.39 115.456 66.4826 + vertex -425.903 115.477 68.0317 + vertex -426.855 111.389 66.5163 + endloop + endfacet + facet normal 0.863279 -0.394676 0.314612 + outer loop + vertex -429.237 103.659 63.9237 + vertex -427.453 107.812 64.2378 + vertex -428.342 107.33 66.0721 + endloop + endfacet + facet normal 0.857234 -0.399333 0.325088 + outer loop + vertex -428.342 107.33 66.0721 + vertex -429.83 104.214 66.1694 + vertex -429.237 103.659 63.9237 + endloop + endfacet +endsolid diff --git a/noether_examples/meshes/outputs/output_17.stl b/noether_examples/meshes/outputs/output_17.stl new file mode 100644 index 00000000..bd64c60a --- /dev/null +++ b/noether_examples/meshes/outputs/output_17.stl @@ -0,0 +1,10306 @@ +solid ascii + facet normal 0.60342 -0.0677324 0.794542 + outer loop + vertex 704.618 185.487 50.1778 + vertex 703.388 184.076 50.9911 + vertex 703.988 176.715 49.9081 + endloop + endfacet + facet normal 0.581803 -0.0717907 0.810155 + outer loop + vertex 703.988 176.715 49.9081 + vertex 703.388 184.076 50.9911 + vertex 702.878 176.93 50.7245 + endloop + endfacet + facet normal 0.571969 -0.124749 0.810734 + outer loop + vertex 703.988 176.715 49.9081 + vertex 702.878 176.93 50.7245 + vertex 703.216 169.181 49.2936 + endloop + endfacet + facet normal 0.563186 -0.126222 0.816633 + outer loop + vertex 703.216 169.181 49.2936 + vertex 702.878 176.93 50.7245 + vertex 702.122 169.329 50.0712 + endloop + endfacet + facet normal 0.592437 -0.127315 0.795493 + outer loop + vertex 702.878 176.93 50.7245 + vertex 702.312 177.366 51.2152 + vertex 702.122 169.329 50.0712 + endloop + endfacet + facet normal 0.587002 -0.127748 0.799443 + outer loop + vertex 702.122 169.329 50.0712 + vertex 702.312 177.366 51.2152 + vertex 701.561 169.486 50.5075 + endloop + endfacet + facet normal 0.82999 -0.127865 0.542924 + outer loop + vertex 702.312 177.366 51.2152 + vertex 702.089 176.614 51.3798 + vertex 701.561 169.486 50.5075 + endloop + endfacet + facet normal 0.621987 -0.140301 0.770356 + outer loop + vertex 701.561 169.486 50.5075 + vertex 702.089 176.614 51.3798 + vertex 701.316 169.17 50.6482 + endloop + endfacet + facet normal 0.958226 -0.0723074 -0.276723 + outer loop + vertex 702.089 176.614 51.3798 + vertex 701.96 175.109 51.3268 + vertex 701.316 169.17 50.6482 + endloop + endfacet + facet normal 0.725501 -0.155301 0.67047 + outer loop + vertex 701.316 169.17 50.6482 + vertex 701.96 175.109 51.3268 + vertex 701.113 167.948 50.5844 + endloop + endfacet + facet normal 0.569296 -0.0712286 0.819041 + outer loop + vertex 703.388 184.076 50.9911 + vertex 702.788 186.177 51.5913 + vertex 702.878 176.93 50.7245 + endloop + endfacet + facet normal 0.624157 -0.0668863 0.778431 + outer loop + vertex 702.878 176.93 50.7245 + vertex 702.788 186.177 51.5913 + vertex 702.312 177.366 51.2152 + endloop + endfacet + facet normal 0.802257 -0.0685767 0.593027 + outer loop + vertex 702.788 186.177 51.5913 + vertex 702.501 185.543 51.905 + vertex 702.312 177.366 51.2152 + endloop + endfacet + facet normal 0.73985 -0.0735207 0.668743 + outer loop + vertex 702.312 177.366 51.2152 + vertex 702.501 185.543 51.905 + vertex 702.089 176.614 51.3798 + endloop + endfacet + facet normal 0.905741 -0.0169295 -0.423493 + outer loop + vertex 702.501 185.543 51.905 + vertex 702.357 181.116 51.7733 + vertex 702.089 176.614 51.3798 + endloop + endfacet + facet normal 0.890926 -0.0919323 0.444747 + outer loop + vertex 702.089 176.614 51.3798 + vertex 702.357 181.116 51.7733 + vertex 701.96 175.109 51.3268 + endloop + endfacet + facet normal 0.999133 -0.0317809 -0.0269102 + outer loop + vertex 702.357 181.116 51.7733 + vertex 702.501 185.543 51.905 + vertex 702.51 185.737 52.006 + endloop + endfacet + facet normal 0.767354 -0.029319 0.640553 + outer loop + vertex 702.501 185.543 51.905 + vertex 702.788 186.177 51.5913 + vertex 702.723 196.704 52.1505 + endloop + endfacet + facet normal 0.672475 -0.0351444 0.739285 + outer loop + vertex 703.525 195.847 51.3806 + vertex 702.723 196.704 52.1505 + vertex 702.788 186.177 51.5913 + endloop + endfacet + facet normal 0.690065 -0.00473594 0.723732 + outer loop + vertex 703.525 195.847 51.3806 + vertex 702.764 209.679 52.1965 + vertex 702.723 196.704 52.1505 + endloop + endfacet + facet normal 0.638617 -0.0102629 0.769456 + outer loop + vertex 703.868 211.263 51.301 + vertex 702.764 209.679 52.1965 + vertex 703.525 195.847 51.3806 + endloop + endfacet + facet normal 0.623252 0.00753206 0.781985 + outer loop + vertex 703.868 211.263 51.301 + vertex 702.582 224.493 52.1984 + vertex 702.764 209.679 52.1965 + endloop + endfacet + facet normal 0.712909 0.00864011 0.701203 + outer loop + vertex 702.764 209.679 52.1965 + vertex 702.582 224.493 52.1984 + vertex 702.353 218.171 52.51 + endloop + endfacet + facet normal 0.785738 0.015224 0.618373 + outer loop + vertex 702.353 218.171 52.51 + vertex 702.514 210.948 52.4829 + vertex 702.764 209.679 52.1965 + endloop + endfacet + facet normal 0.764781 0.00525395 0.644269 + outer loop + vertex 702.514 210.948 52.4829 + vertex 702.597 205.379 52.4295 + vertex 702.764 209.679 52.1965 + endloop + endfacet + facet normal 0.594901 0.00118398 0.803798 + outer loop + vertex 702.597 205.379 52.4295 + vertex 702.514 210.948 52.4829 + vertex 702.292 207.242 52.6526 + endloop + endfacet + facet normal 0.516105 0.00831274 0.856485 + outer loop + vertex 702.514 210.948 52.4829 + vertex 702.353 218.171 52.51 + vertex 702.292 207.242 52.6526 + endloop + endfacet + facet normal 0.653046 0.00625918 0.757293 + outer loop + vertex 701.777 225.154 52.9484 + vertex 702.292 207.242 52.6526 + vertex 702.353 218.171 52.51 + endloop + endfacet + facet normal 0.664665 0.0126531 0.747034 + outer loop + vertex 702.167 226.393 52.5357 + vertex 702.353 218.171 52.51 + vertex 702.582 224.493 52.1984 + endloop + endfacet + facet normal 0.665544 0.012985 0.746246 + outer loop + vertex 701.985 234.395 52.5592 + vertex 702.167 226.393 52.5357 + vertex 702.582 224.493 52.1984 + endloop + endfacet + facet normal 0.652548 0.0117848 0.757656 + outer loop + vertex 702.582 224.493 52.1984 + vertex 702.299 239.547 52.2082 + vertex 701.985 234.395 52.5592 + endloop + endfacet + facet normal 0.644893 0.0126957 0.764167 + outer loop + vertex 701.826 242.22 52.5628 + vertex 701.985 234.395 52.5592 + vertex 702.299 239.547 52.2082 + endloop + endfacet + facet normal 0.635899 0.0101048 0.771706 + outer loop + vertex 701.781 247.824 52.5268 + vertex 701.826 242.22 52.5628 + vertex 702.299 239.547 52.2082 + endloop + endfacet + facet normal 0.62736 0.00930212 0.778674 + outer loop + vertex 702.299 239.547 52.2082 + vertex 702.073 253.97 52.2179 + vertex 701.781 247.824 52.5268 + endloop + endfacet + facet normal 0.674435 0.00503655 0.738317 + outer loop + vertex 701.626 255.26 52.6177 + vertex 701.781 247.824 52.5268 + vertex 702.073 253.97 52.2179 + endloop + endfacet + facet normal 0.67607 0.00606983 0.736812 + outer loop + vertex 701.656 263.712 52.5204 + vertex 701.626 255.26 52.6177 + vertex 702.073 253.97 52.2179 + endloop + endfacet + facet normal 0.669105 0.00557499 0.743147 + outer loop + vertex 702.073 253.97 52.2179 + vertex 702.024 267.623 52.16 + vertex 701.656 263.712 52.5204 + endloop + endfacet + facet normal 0.696097 0.000716372 0.717948 + outer loop + vertex 701.628 274.25 52.5369 + vertex 701.656 263.712 52.5204 + vertex 702.024 267.623 52.16 + endloop + endfacet + facet normal 0.704442 0.00168006 0.709759 + outer loop + vertex 702.024 267.623 52.16 + vertex 701.971 282.126 52.178 + vertex 701.628 274.25 52.5369 + endloop + endfacet + facet normal 0.727207 -0.000374537 0.686418 + outer loop + vertex 701.67 283.119 52.4978 + vertex 701.628 274.25 52.5369 + vertex 701.971 282.126 52.178 + endloop + endfacet + facet normal 0.724176 -0.00232397 0.689611 + outer loop + vertex 701.693 291.534 52.5014 + vertex 701.67 283.119 52.4978 + vertex 701.971 282.126 52.178 + endloop + endfacet + facet normal 0.736019 -0.00153924 0.676959 + outer loop + vertex 701.971 282.126 52.178 + vertex 702.051 296.543 52.1234 + vertex 701.693 291.534 52.5014 + endloop + endfacet + facet normal 0.745825 -0.00305748 0.666135 + outer loop + vertex 701.748 304.736 52.5006 + vertex 701.693 291.534 52.5014 + vertex 702.051 296.543 52.1234 + endloop + endfacet + facet normal 0.747555 -0.00290404 0.664194 + outer loop + vertex 702.051 296.543 52.1234 + vertex 702.061 311.646 52.1789 + vertex 701.748 304.736 52.5006 + endloop + endfacet + facet normal 0.757535 -0.00388699 0.652783 + outer loop + vertex 701.799 313.805 52.4959 + vertex 701.748 304.736 52.5006 + vertex 702.061 311.646 52.1789 + endloop + endfacet + facet normal 0.752086 -0.0054675 0.659042 + outer loop + vertex 701.826 322.047 52.5327 + vertex 701.799 313.805 52.4959 + vertex 702.061 311.646 52.1789 + endloop + endfacet + facet normal 0.766092 -0.00459636 0.642714 + outer loop + vertex 702.061 311.646 52.1789 + vertex 702.143 325.554 52.1803 + vertex 701.826 322.047 52.5327 + endloop + endfacet + facet normal 0.773245 -0.00611007 0.634077 + outer loop + vertex 701.919 332.673 52.5216 + vertex 701.826 322.047 52.5327 + vertex 702.143 325.554 52.1803 + endloop + endfacet + facet normal 0.76218 -0.00709286 0.647326 + outer loop + vertex 702.143 325.554 52.1803 + vertex 702.192 340.612 52.2879 + vertex 701.919 332.673 52.5216 + endloop + endfacet + facet normal 0.789488 -0.00901951 0.6137 + outer loop + vertex 701.948 340.319 52.597 + vertex 701.919 332.673 52.5216 + vertex 702.192 340.612 52.2879 + endloop + endfacet + facet normal 0.788976 -0.00788329 0.614374 + outer loop + vertex 702.032 345.531 52.5559 + vertex 701.948 340.319 52.597 + vertex 702.192 340.612 52.2879 + endloop + endfacet + facet normal 0.784902 -0.00829805 0.619564 + outer loop + vertex 702.088 349.433 52.5381 + vertex 702.032 345.531 52.5559 + vertex 702.192 340.612 52.2879 + endloop + endfacet + facet normal 0.787701 -0.00816398 0.616004 + outer loop + vertex 702.192 340.612 52.2879 + vertex 702.333 355.087 52.2987 + vertex 702.088 349.433 52.5381 + endloop + endfacet + facet normal 0.804145 -0.00979591 0.594352 + outer loop + vertex 702.123 353.513 52.5575 + vertex 702.088 349.433 52.5381 + vertex 702.333 355.087 52.2987 + endloop + endfacet + facet normal 0.80207 -0.00905628 0.597161 + outer loop + vertex 702.17 358.08 52.5631 + vertex 702.123 353.513 52.5575 + vertex 702.333 355.087 52.2987 + endloop + endfacet + facet normal 0.808895 -0.00786606 0.5879 + outer loop + vertex 702.289 364.305 52.4825 + vertex 702.17 358.08 52.5631 + vertex 702.333 355.087 52.2987 + endloop + endfacet + facet normal 0.695079 -0.0110197 0.718848 + outer loop + vertex 702.333 355.087 52.2987 + vertex 702.615 370.29 52.2592 + vertex 702.289 364.305 52.4825 + endloop + endfacet + facet normal 0.657346 -0.00767061 0.75355 + outer loop + vertex 702.355 369.284 52.4762 + vertex 702.289 364.305 52.4825 + vertex 702.615 370.29 52.2592 + endloop + endfacet + facet normal 0.696495 -0.0256691 0.717103 + outer loop + vertex 702.546 374.879 52.4912 + vertex 702.355 369.284 52.4762 + vertex 702.615 370.29 52.2592 + endloop + endfacet + facet normal 0.619653 -0.0302321 0.784293 + outer loop + vertex 702.878 381.047 52.4659 + vertex 702.546 374.879 52.4912 + vertex 702.615 370.29 52.2592 + endloop + endfacet + facet normal 0.106609 -0.0217074 0.994064 + outer loop + vertex 702.615 370.29 52.2592 + vertex 703.672 386.655 52.5033 + vertex 702.878 381.047 52.4659 + endloop + endfacet + facet normal 0.842324 -0.122658 0.524828 + outer loop + vertex 703.566 386.655 52.6728 + vertex 702.878 381.047 52.4659 + vertex 703.672 386.655 52.5033 + endloop + endfacet + facet normal 0.845648 -0.122865 0.519407 + outer loop + vertex 702.878 381.047 52.4659 + vertex 703.566 386.655 52.6728 + vertex 703.461 386.656 52.8438 + endloop + endfacet + facet normal 0.737827 -0.0576654 0.672522 + outer loop + vertex 703.414 371.605 51.4955 + vertex 703.672 386.655 52.5033 + vertex 702.615 370.29 52.2592 + endloop + endfacet + facet normal 0.705836 -0.0175394 0.708158 + outer loop + vertex 703.414 371.605 51.4955 + vertex 702.615 370.29 52.2592 + vertex 703.135 356.874 51.4092 + endloop + endfacet + facet normal 0.844376 -0.0501739 0.533397 + outer loop + vertex 703.778 386.654 52.335 + vertex 703.672 386.655 52.5033 + vertex 703.414 371.605 51.4955 + endloop + endfacet + facet normal 0.818927 -0.0465598 -0.572006 + outer loop + vertex 702.546 374.879 52.4912 + vertex 702.878 381.047 52.4659 + vertex 703.461 386.656 52.8438 + endloop + endfacet + facet normal 0.901163 -0.0572155 -0.429689 + outer loop + vertex 703.461 386.656 52.8438 + vertex 702.147 365.934 52.8465 + vertex 702.546 374.879 52.4912 + endloop + endfacet + facet normal 0.844808 -0.053515 0.532386 + outer loop + vertex 702.147 365.934 52.8465 + vertex 703.461 386.656 52.8438 + vertex 701.473 370.937 54.4196 + endloop + endfacet + facet normal 0.884116 -0.0274858 0.466458 + outer loop + vertex 701.046 352.469 54.14 + vertex 702.147 365.934 52.8465 + vertex 701.473 370.937 54.4196 + endloop + endfacet + facet normal 0.8604 -0.02758 0.508872 + outer loop + vertex 701.046 352.469 54.14 + vertex 701.473 370.937 54.4196 + vertex 699.809 353.934 56.3104 + endloop + endfacet + facet normal 0.863666 -0.0172648 0.503768 + outer loop + vertex 699.809 353.934 56.3104 + vertex 699.591 340.968 56.2409 + vertex 701.046 352.469 54.14 + endloop + endfacet + facet normal 0.852819 -0.0125516 0.522055 + outer loop + vertex 700.562 334.921 54.5089 + vertex 701.046 352.469 54.14 + vertex 699.591 340.968 56.2409 + endloop + endfacet + facet normal 0.849856 -0.0143914 0.526818 + outer loop + vertex 699.591 340.968 56.2409 + vertex 699.127 330.923 56.7136 + vertex 700.562 334.921 54.5089 + endloop + endfacet + facet normal 0.850188 -0.0148127 0.52627 + outer loop + vertex 699.127 330.923 56.7136 + vertex 699.136 322.933 56.4742 + vertex 700.562 334.921 54.5089 + endloop + endfacet + facet normal 0.838959 -0.0105558 0.544092 + outer loop + vertex 700.276 317.741 54.617 + vertex 700.562 334.921 54.5089 + vertex 699.136 322.933 56.4742 + endloop + endfacet + facet normal 0.834432 -0.0139961 0.550933 + outer loop + vertex 699.136 322.933 56.4742 + vertex 698.762 314.122 56.8179 + vertex 700.276 317.741 54.617 + endloop + endfacet + facet normal 0.833462 -0.0126789 0.552431 + outer loop + vertex 698.762 314.122 56.8179 + vertex 698.847 306.116 56.5058 + vertex 700.276 317.741 54.617 + endloop + endfacet + facet normal 0.821385 -0.00828948 0.570313 + outer loop + vertex 700.08 300.692 54.6513 + vertex 700.276 317.741 54.617 + vertex 698.847 306.116 56.5058 + endloop + endfacet + facet normal 0.817765 -0.0108691 0.57545 + outer loop + vertex 698.847 306.116 56.5058 + vertex 698.514 296.982 56.8057 + vertex 700.08 300.692 54.6513 + endloop + endfacet + facet normal 0.816718 -0.00955191 0.576958 + outer loop + vertex 698.514 296.982 56.8057 + vertex 698.655 288.7 56.4691 + vertex 700.08 300.692 54.6513 + endloop + endfacet + facet normal 0.804646 -0.00557631 0.593728 + outer loop + vertex 699.947 283.582 54.6708 + vertex 700.08 300.692 54.6513 + vertex 698.655 288.7 56.4691 + endloop + endfacet + facet normal 0.802218 -0.00733385 0.596986 + outer loop + vertex 698.655 288.7 56.4691 + vertex 698.336 279.263 56.7823 + vertex 699.947 283.582 54.6708 + endloop + endfacet + facet normal 0.800682 -0.00574611 0.599062 + outer loop + vertex 698.336 279.263 56.7823 + vertex 698.488 270.909 56.4983 + vertex 699.947 283.582 54.6708 + endloop + endfacet + facet normal 0.79058 -0.00266684 0.612354 + outer loop + vertex 699.86 266.168 54.7075 + vertex 699.947 283.582 54.6708 + vertex 698.488 270.909 56.4983 + endloop + endfacet + facet normal 0.788806 -0.00403901 0.614629 + outer loop + vertex 698.488 270.909 56.4983 + vertex 698.193 261.466 56.8151 + vertex 699.86 266.168 54.7075 + endloop + endfacet + facet normal 0.786861 -0.00222999 0.617126 + outer loop + vertex 698.193 261.466 56.8151 + vertex 698.408 253.32 56.512 + vertex 699.86 266.168 54.7075 + endloop + endfacet + facet normal 0.773259 0.00168921 0.634088 + outer loop + vertex 699.869 248.038 54.7448 + vertex 699.86 266.168 54.7075 + vertex 698.408 253.32 56.512 + endloop + endfacet + facet normal 0.77285 0.00140928 0.634587 + outer loop + vertex 698.408 253.32 56.512 + vertex 698.15 243.919 56.8465 + vertex 699.869 248.038 54.7448 + endloop + endfacet + facet normal 0.769782 0.00457913 0.638291 + outer loop + vertex 698.15 243.919 56.8465 + vertex 698.457 235.315 56.538 + vertex 699.869 248.038 54.7448 + endloop + endfacet + facet normal 0.758996 0.00757405 0.651052 + outer loop + vertex 700.124 228.071 54.6797 + vertex 699.869 248.038 54.7448 + vertex 698.457 235.315 56.538 + endloop + endfacet + facet normal 0.760786 0.00852591 0.648947 + outer loop + vertex 698.457 235.315 56.538 + vertex 698.258 225.81 56.8968 + vertex 700.124 228.071 54.6797 + endloop + endfacet + facet normal 0.760399 0.00928104 0.64939 + outer loop + vertex 698.258 225.81 56.8968 + vertex 698.485 217.617 56.7474 + vertex 700.124 228.071 54.6797 + endloop + endfacet + facet normal 0.767988 0.00632008 0.640433 + outer loop + vertex 699.744 212.24 55.291 + vertex 700.124 228.071 54.6797 + vertex 698.485 217.617 56.7474 + endloop + endfacet + facet normal 0.768437 0.00657172 0.639892 + outer loop + vertex 698.232 208.882 57.1409 + vertex 699.744 212.24 55.291 + vertex 698.485 217.617 56.7474 + endloop + endfacet + facet normal 0.779109 -0.00541062 0.626865 + outer loop + vertex 698.606 201.816 56.6154 + vertex 699.744 212.24 55.291 + vertex 698.232 208.882 57.1409 + endloop + endfacet + facet normal 0.756274 0.000562231 0.654255 + outer loop + vertex 700.304 202.274 54.6522 + vertex 699.744 212.24 55.291 + vertex 698.606 201.816 56.6154 + endloop + endfacet + facet normal 0.759015 -0.025394 0.650578 + outer loop + vertex 698.696 192.449 56.145 + vertex 700.304 202.274 54.6522 + vertex 698.606 201.816 56.6154 + endloop + endfacet + facet normal 0.739505 -0.0188102 0.672888 + outer loop + vertex 700.396 192.302 54.273 + vertex 700.304 202.274 54.6522 + vertex 698.696 192.449 56.145 + endloop + endfacet + facet normal 0.737109 -0.0549066 0.67354 + outer loop + vertex 698.535 182.705 55.5273 + vertex 700.396 192.302 54.273 + vertex 698.696 192.449 56.145 + endloop + endfacet + facet normal 0.720052 -0.0491636 0.692176 + outer loop + vertex 700.284 183.934 53.7947 + vertex 700.396 192.302 54.273 + vertex 698.535 182.705 55.5273 + endloop + endfacet + facet normal 0.829941 -0.0111701 0.557739 + outer loop + vertex 700.562 334.921 54.5089 + vertex 701.844 348.43 52.8719 + vertex 701.046 352.469 54.14 + endloop + endfacet + facet normal 0.821221 -0.00879107 0.570542 + outer loop + vertex 701.541 330.516 53.0319 + vertex 701.844 348.43 52.8719 + vertex 700.562 334.921 54.5089 + endloop + endfacet + facet normal 0.819424 -0.0100478 0.573099 + outer loop + vertex 700.276 317.741 54.617 + vertex 701.541 330.516 53.0319 + vertex 700.562 334.921 54.5089 + endloop + endfacet + facet normal 0.807184 -0.00670594 0.590262 + outer loop + vertex 701.386 312.98 53.0441 + vertex 701.541 330.516 53.0319 + vertex 700.276 317.741 54.617 + endloop + endfacet + facet normal 0.805198 -0.00805799 0.592952 + outer loop + vertex 700.08 300.692 54.6513 + vertex 701.386 312.98 53.0441 + vertex 700.276 317.741 54.617 + endloop + endfacet + facet normal 0.793289 -0.0047154 0.608826 + outer loop + vertex 701.216 296.37 53.1367 + vertex 701.386 312.98 53.0441 + vertex 700.08 300.692 54.6513 + endloop + endfacet + facet normal 0.792249 -0.00546129 0.610174 + outer loop + vertex 699.947 283.582 54.6708 + vertex 701.216 296.37 53.1367 + vertex 700.08 300.692 54.6513 + endloop + endfacet + facet normal 0.781468 -0.00273981 0.623939 + outer loop + vertex 701.212 280.437 53.0728 + vertex 701.216 296.37 53.1367 + vertex 699.947 283.582 54.6708 + endloop + endfacet + facet normal 0.781605 -0.00259788 0.623768 + outer loop + vertex 699.86 266.168 54.7075 + vertex 701.212 280.437 53.0728 + vertex 699.947 283.582 54.6708 + endloop + endfacet + facet normal 0.76956 0.000239502 0.638574 + outer loop + vertex 701.182 262.452 53.1157 + vertex 701.212 280.437 53.0728 + vertex 699.86 266.168 54.7075 + endloop + endfacet + facet normal 0.771224 0.00169328 0.636562 + outer loop + vertex 699.869 248.038 54.7448 + vertex 701.182 262.452 53.1157 + vertex 699.86 266.168 54.7075 + endloop + endfacet + facet normal 0.753054 0.00576375 0.657934 + outer loop + vertex 701.388 243.72 53.0439 + vertex 701.182 262.452 53.1157 + vertex 699.869 248.038 54.7448 + endloop + endfacet + facet normal 0.755219 0.00751154 0.65543 + outer loop + vertex 700.124 228.071 54.6797 + vertex 701.388 243.72 53.0439 + vertex 699.869 248.038 54.7448 + endloop + endfacet + facet normal 0.733027 0.0118822 0.680095 + outer loop + vertex 701.777 225.154 52.9484 + vertex 701.388 243.72 53.0439 + vertex 700.124 228.071 54.6797 + endloop + endfacet + facet normal 0.729644 0.0077754 0.683783 + outer loop + vertex 701.23 213.041 53.6702 + vertex 701.777 225.154 52.9484 + vertex 700.124 228.071 54.6797 + endloop + endfacet + facet normal 0.735024 0.00856056 0.677987 + outer loop + vertex 699.744 212.24 55.291 + vertex 701.23 213.041 53.6702 + vertex 700.124 228.071 54.6797 + endloop + endfacet + facet normal 0.737609 -0.0018308 0.675226 + outer loop + vertex 700.304 202.274 54.6522 + vertex 701.23 213.041 53.6702 + vertex 699.744 212.24 55.291 + endloop + endfacet + facet normal 0.725072 0.000473463 0.688673 + outer loop + vertex 701.58 200.385 53.3107 + vertex 701.23 213.041 53.6702 + vertex 700.304 202.274 54.6522 + endloop + endfacet + facet normal 0.710202 -0.0202506 0.703706 + outer loop + vertex 700.396 192.302 54.273 + vertex 701.58 200.385 53.3107 + vertex 700.304 202.274 54.6522 + endloop + endfacet + facet normal 0.715665 -0.0217175 0.698106 + outer loop + vertex 701.412 191.164 53.1959 + vertex 701.58 200.385 53.3107 + vertex 700.396 192.302 54.273 + endloop + endfacet + facet normal 0.699527 -0.0500716 0.71285 + outer loop + vertex 700.284 183.934 53.7947 + vertex 701.412 191.164 53.1959 + vertex 700.396 192.302 54.273 + endloop + endfacet + facet normal 0.733163 -0.058241 0.677554 + outer loop + vertex 701.295 184.074 52.713 + vertex 701.412 191.164 53.1959 + vertex 700.284 183.934 53.7947 + endloop + endfacet + facet normal 0.733473 -0.089317 0.673825 + outer loop + vertex 699.909 176.426 53.2077 + vertex 701.295 184.074 52.713 + vertex 700.284 183.934 53.7947 + endloop + endfacet + facet normal 0.73173 -0.0893773 0.67571 + outer loop + vertex 699.909 176.426 53.2077 + vertex 700.284 183.934 53.7947 + vertex 698.758 176.543 54.4701 + endloop + endfacet + facet normal 0.731869 -0.0894204 0.675553 + outer loop + vertex 700.284 183.934 53.7947 + vertex 698.535 182.705 55.5273 + vertex 698.758 176.543 54.4701 + endloop + endfacet + facet normal 0.72728 -0.0904112 0.68036 + outer loop + vertex 697.492 175.21 55.6458 + vertex 698.758 176.543 54.4701 + vertex 698.535 182.705 55.5273 + endloop + endfacet + facet normal 0.764397 -0.0962515 0.637521 + outer loop + vertex 697.492 175.21 55.6458 + vertex 698.535 182.705 55.5273 + vertex 696.54 176.084 56.9196 + endloop + endfacet + facet normal 0.767021 -0.0977549 0.634132 + outer loop + vertex 698.535 182.705 55.5273 + vertex 696.498 182.6 57.9744 + vertex 696.54 176.084 56.9196 + endloop + endfacet + facet normal 0.779596 -0.0952255 0.619001 + outer loop + vertex 695.323 175.269 58.327 + vertex 696.54 176.084 56.9196 + vertex 696.498 182.6 57.9744 + endloop + endfacet + facet normal 0.813855 -0.102985 0.571869 + outer loop + vertex 695.323 175.269 58.327 + vertex 696.498 182.6 57.9744 + vertex 694.487 176.396 59.7186 + endloop + endfacet + facet normal 0.809965 -0.100033 0.577884 + outer loop + vertex 696.498 182.6 57.9744 + vertex 694.548 182.916 60.7619 + vertex 694.487 176.396 59.7186 + endloop + endfacet + facet normal 0.826599 -0.0964406 0.554467 + outer loop + vertex 693.406 175.728 61.214 + vertex 694.487 176.396 59.7186 + vertex 694.548 182.916 60.7619 + endloop + endfacet + facet normal 0.853442 -0.10345 0.510818 + outer loop + vertex 693.406 175.728 61.214 + vertex 694.548 182.916 60.7619 + vertex 692.708 176.877 62.614 + endloop + endfacet + facet normal 0.849649 -0.100169 0.517747 + outer loop + vertex 694.548 182.916 60.7619 + vertex 692.819 183.369 63.6871 + vertex 692.708 176.877 62.614 + endloop + endfacet + facet normal 0.864258 -0.0964473 0.493717 + outer loop + vertex 691.771 176.238 64.1285 + vertex 692.708 176.877 62.614 + vertex 692.819 183.369 63.6871 + endloop + endfacet + facet normal 0.888283 -0.10283 0.447637 + outer loop + vertex 691.771 176.238 64.1285 + vertex 692.819 183.369 63.6871 + vertex 691.167 177.415 65.5986 + endloop + endfacet + facet normal 0.884829 -0.0994514 0.455177 + outer loop + vertex 692.819 183.369 63.6871 + vertex 691.294 183.891 66.765 + vertex 691.167 177.415 65.5986 + endloop + endfacet + facet normal 0.896731 -0.0955374 0.432141 + outer loop + vertex 690.317 176.829 67.2325 + vertex 691.167 177.415 65.5986 + vertex 691.294 183.891 66.765 + endloop + endfacet + facet normal 0.913961 -0.100503 0.39316 + outer loop + vertex 690.317 176.829 67.2325 + vertex 691.294 183.891 66.765 + vertex 689.758 178.055 68.8447 + endloop + endfacet + facet normal 0.912626 -0.0989077 0.396651 + outer loop + vertex 691.294 183.891 66.765 + vertex 689.934 184.528 70.0541 + vertex 689.758 178.055 68.8447 + endloop + endfacet + facet normal 0.920362 -0.0958458 0.379139 + outer loop + vertex 688.969 177.538 70.6287 + vertex 689.758 178.055 68.8447 + vertex 689.934 184.528 70.0541 + endloop + endfacet + facet normal 0.934142 -0.100769 0.34238 + outer loop + vertex 688.969 177.538 70.6287 + vertex 689.934 184.528 70.0541 + vertex 688.489 178.813 72.3155 + endloop + endfacet + facet normal 0.932115 -0.0977452 0.348724 + outer loop + vertex 689.934 184.528 70.0541 + vertex 688.728 185.384 73.5185 + vertex 688.489 178.813 72.3155 + endloop + endfacet + facet normal 0.937481 -0.0953757 0.334714 + outer loop + vertex 687.785 178.364 74.1583 + vertex 688.489 178.813 72.3155 + vertex 688.728 185.384 73.5185 + endloop + endfacet + facet normal 0.949017 -0.100191 0.298878 + outer loop + vertex 687.785 178.364 74.1583 + vertex 688.728 185.384 73.5185 + vertex 687.394 179.713 75.8525 + endloop + endfacet + facet normal 0.946237 -0.0953266 0.309109 + outer loop + vertex 688.728 185.384 73.5185 + vertex 687.667 186.448 77.0941 + vertex 687.394 179.713 75.8525 + endloop + endfacet + facet normal 0.951009 -0.0928961 0.294876 + outer loop + vertex 686.782 179.307 77.6968 + vertex 687.394 179.713 75.8525 + vertex 687.667 186.448 77.0941 + endloop + endfacet + facet normal 0.960328 -0.096866 0.261511 + outer loop + vertex 686.782 179.307 77.6968 + vertex 687.667 186.448 77.0941 + vertex 686.456 180.646 79.3907 + endloop + endfacet + facet normal 0.958546 -0.0934619 0.269172 + outer loop + vertex 687.667 186.448 77.0941 + vertex 686.745 187.351 80.6889 + vertex 686.456 180.646 79.3907 + endloop + endfacet + facet normal 0.961322 -0.0917471 0.259697 + outer loop + vertex 685.914 180.19 81.2376 + vertex 686.456 180.646 79.3907 + vertex 686.745 187.351 80.6889 + endloop + endfacet + facet normal 0.970204 -0.0956195 0.222622 + outer loop + vertex 685.914 180.19 81.2376 + vertex 686.745 187.351 80.6889 + vertex 685.653 181.578 82.9702 + endloop + endfacet + facet normal 0.968848 -0.0925636 0.229707 + outer loop + vertex 686.745 187.351 80.6889 + vertex 685.997 188.507 84.3114 + vertex 685.653 181.578 82.9702 + endloop + endfacet + facet normal 0.97354 -0.0890682 0.210446 + outer loop + vertex 685.21 181.268 84.8877 + vertex 685.653 181.578 82.9702 + vertex 685.997 188.507 84.3114 + endloop + endfacet + facet normal 0.980324 -0.092685 0.174281 + outer loop + vertex 685.21 181.268 84.8877 + vertex 685.997 188.507 84.3114 + vertex 685.045 182.947 86.7106 + endloop + endfacet + facet normal 0.97709 -0.0827187 0.196093 + outer loop + vertex 685.997 188.507 84.3114 + vertex 685.325 189.587 88.1153 + vertex 685.045 182.947 86.7106 + endloop + endfacet + facet normal 0.979918 -0.0799945 0.182652 + outer loop + vertex 684.716 183.007 88.5001 + vertex 685.045 182.947 86.7106 + vertex 685.325 189.587 88.1153 + endloop + endfacet + facet normal 0.965265 -0.0746775 0.250373 + outer loop + vertex 684.716 183.007 88.5001 + vertex 685.325 189.587 88.1153 + vertex 683.959 181.226 90.887 + endloop + endfacet + facet normal 0.977596 -0.0979275 0.186323 + outer loop + vertex 683.959 181.226 90.887 + vertex 685.325 189.587 88.1153 + vertex 684.788 191.51 91.9457 + endloop + endfacet + facet normal 0.983963 -0.0948131 0.151089 + outer loop + vertex 683.959 181.226 90.887 + vertex 684.788 191.51 91.9457 + vertex 683.484 182.559 94.8188 + endloop + endfacet + facet normal 0.984544 -0.0964761 0.146172 + outer loop + vertex 683.484 182.559 94.8188 + vertex 684.788 191.51 91.9457 + vertex 684.349 192.738 95.7103 + endloop + endfacet + facet normal 0.987352 -0.0950276 0.126908 + outer loop + vertex 683.484 182.559 94.8188 + vertex 684.349 192.738 95.7103 + vertex 683.1 183.561 98.5541 + endloop + endfacet + facet normal 0.987859 -0.0967592 0.121543 + outer loop + vertex 683.1 183.561 98.5541 + vertex 684.349 192.738 95.7103 + vertex 683.985 193.642 99.3893 + endloop + endfacet + facet normal 0.989472 -0.0958171 0.108463 + outer loop + vertex 683.1 183.561 98.5541 + vertex 683.985 193.642 99.3893 + vertex 682.779 184.424 102.246 + endloop + endfacet + facet normal 0.989765 -0.0970433 0.104629 + outer loop + vertex 682.779 184.424 102.246 + vertex 683.985 193.642 99.3893 + vertex 683.675 194.433 103.053 + endloop + endfacet + facet normal 0.991018 -0.0962081 0.0928854 + outer loop + vertex 682.779 184.424 102.246 + vertex 683.675 194.433 103.053 + vertex 682.514 185.288 105.971 + endloop + endfacet + facet normal 0.991264 -0.0975531 0.0887675 + outer loop + vertex 682.514 185.288 105.971 + vertex 683.675 194.433 103.053 + vertex 683.423 195.244 106.757 + endloop + endfacet + facet normal 0.991936 -0.0970427 0.0815271 + outer loop + vertex 682.514 185.288 105.971 + vertex 683.423 195.244 106.757 + vertex 682.291 186.168 109.734 + endloop + endfacet + facet normal 0.992069 -0.0979699 0.0787502 + outer loop + vertex 682.291 186.168 109.734 + vertex 683.423 195.244 106.757 + vertex 683.209 196.08 110.494 + endloop + endfacet + facet normal 0.992733 -0.0974104 0.0706561 + outer loop + vertex 682.291 186.168 109.734 + vertex 683.209 196.08 110.494 + vertex 682.107 187.031 113.503 + endloop + endfacet + facet normal 0.992854 -0.098533 0.0673238 + outer loop + vertex 682.107 187.031 113.503 + vertex 683.209 196.08 110.494 + vertex 683.038 196.909 114.236 + endloop + endfacet + facet normal 0.993407 -0.0980026 0.0594748 + outer loop + vertex 682.107 187.031 113.503 + vertex 683.038 196.909 114.236 + vertex 681.964 187.852 117.252 + endloop + endfacet + facet normal 0.99339 -0.097789 0.0601103 + outer loop + vertex 681.964 187.852 117.252 + vertex 683.038 196.909 114.236 + vertex 682.891 197.712 117.973 + endloop + endfacet + facet normal 0.993726 -0.0974398 0.0549074 + outer loop + vertex 681.964 187.852 117.252 + vertex 682.891 197.712 117.973 + vertex 681.833 188.624 120.987 + endloop + endfacet + facet normal 0.993796 -0.0985876 0.0514705 + outer loop + vertex 681.833 188.624 120.987 + vertex 682.891 197.712 117.973 + vertex 682.772 198.478 121.734 + endloop + endfacet + facet normal 0.994059 -0.0982594 0.0468144 + outer loop + vertex 681.833 188.624 120.987 + vertex 682.772 198.478 121.734 + vertex 681.727 189.364 124.787 + endloop + endfacet + facet normal 0.994067 -0.098463 0.0462094 + outer loop + vertex 681.727 189.364 124.787 + vertex 682.772 198.478 121.734 + vertex 682.667 199.214 125.559 + endloop + endfacet + facet normal 0.994361 -0.098038 0.0404238 + outer loop + vertex 681.727 189.364 124.787 + vertex 682.667 199.214 125.559 + vertex 681.638 190.065 128.675 + endloop + endfacet + facet normal 0.994363 -0.0981108 0.0402105 + outer loop + vertex 681.638 190.065 128.675 + vertex 682.667 199.214 125.559 + vertex 682.577 199.9 129.446 + endloop + endfacet + facet normal 0.994265 -0.0982583 0.0422101 + outer loop + vertex 681.638 190.065 128.675 + vertex 682.577 199.9 129.446 + vertex 681.532 190.673 132.598 + endloop + endfacet + facet normal 0.994291 -0.0996652 0.0380996 + outer loop + vertex 681.532 190.673 132.598 + vertex 682.577 199.9 129.446 + vertex 682.489 200.516 133.369 + endloop + endfacet + facet normal 0.994426 -0.0994399 0.0350571 + outer loop + vertex 681.532 190.673 132.598 + vertex 682.489 200.516 133.369 + vertex 681.446 191.203 136.539 + endloop + endfacet + facet normal 0.994426 -0.0995452 0.0347476 + outer loop + vertex 681.446 191.203 136.539 + vertex 682.489 200.516 133.369 + vertex 682.407 201.066 137.287 + endloop + endfacet + facet normal 0.99445 -0.0995036 0.0341676 + outer loop + vertex 681.446 191.203 136.539 + vertex 682.407 201.066 137.287 + vertex 681.36 191.68 140.433 + endloop + endfacet + facet normal 0.994444 -0.100946 0.0298628 + outer loop + vertex 681.36 191.68 140.433 + vertex 682.407 201.066 137.287 + vertex 682.34 201.556 141.175 + endloop + endfacet + facet normal 0.994572 -0.100686 0.0262329 + outer loop + vertex 681.36 191.68 140.433 + vertex 682.34 201.556 141.175 + vertex 681.301 192.102 144.261 + endloop + endfacet + facet normal 0.99458 -0.100289 0.0274519 + outer loop + vertex 681.301 192.102 144.261 + vertex 682.34 201.556 141.175 + vertex 682.277 201.987 145.031 + endloop + endfacet + facet normal 0.994637 -0.100163 0.0257677 + outer loop + vertex 681.301 192.102 144.261 + vertex 682.277 201.987 145.031 + vertex 681.241 192.479 148.077 + endloop + endfacet + facet normal 0.994605 -0.101392 0.021921 + outer loop + vertex 681.241 192.479 148.077 + vertex 682.277 201.987 145.031 + vertex 682.23 202.361 148.877 + endloop + endfacet + facet normal 0.994629 -0.101329 0.021111 + outer loop + vertex 681.241 192.479 148.077 + vertex 682.23 202.361 148.877 + vertex 681.193 192.809 151.921 + endloop + endfacet + facet normal 0.994613 -0.101748 0.0197898 + outer loop + vertex 681.193 192.809 151.921 + vertex 682.23 202.361 148.877 + vertex 682.186 202.675 152.719 + endloop + endfacet + facet normal 0.994761 -0.101283 0.0138525 + outer loop + vertex 681.193 192.809 151.921 + vertex 682.186 202.675 152.719 + vertex 681.167 193.081 155.771 + endloop + endfacet + facet normal 0.994818 -0.100185 0.0173241 + outer loop + vertex 681.167 193.081 155.771 + vertex 682.186 202.675 152.719 + vertex 682.144 202.925 156.556 + endloop + endfacet + facet normal 0.994872 -0.100013 0.0150956 + outer loop + vertex 681.167 193.081 155.771 + vertex 682.144 202.925 156.556 + vertex 681.129 193.289 159.619 + endloop + endfacet + facet normal 0.99482 -0.10091 0.0122556 + outer loop + vertex 681.129 193.289 159.619 + vertex 682.144 202.925 156.556 + vertex 682.117 203.122 160.409 + endloop + endfacet + facet normal 0.994886 -0.100628 0.00866381 + outer loop + vertex 681.129 193.289 159.619 + vertex 682.117 203.122 160.409 + vertex 681.111 193.441 163.496 + endloop + endfacet + facet normal 0.99488 -0.100713 0.00839516 + outer loop + vertex 681.111 193.441 163.496 + vertex 682.117 203.122 160.409 + vertex 682.098 203.263 164.297 + endloop + endfacet + facet normal 0.994924 -0.100478 0.00545997 + outer loop + vertex 681.111 193.441 163.496 + vertex 682.098 203.263 164.297 + vertex 681.1 193.542 167.42 + endloop + endfacet + facet normal 0.994942 -0.100265 0.00612816 + outer loop + vertex 681.1 193.542 167.42 + vertex 682.098 203.263 164.297 + vertex 682.083 203.349 168.219 + endloop + endfacet + facet normal 0.994964 -0.100131 0.00445382 + outer loop + vertex 681.1 193.542 167.42 + vertex 682.083 203.349 168.219 + vertex 681.086 193.585 171.37 + endloop + endfacet + facet normal 0.994834 -0.101513 0.000130242 + outer loop + vertex 681.086 193.585 171.37 + vertex 682.083 203.349 168.219 + vertex 682.086 203.383 172.148 + endloop + endfacet + facet normal 0.994855 -0.10127 -0.00296562 + outer loop + vertex 681.086 193.585 171.37 + vertex 682.086 203.383 172.148 + vertex 681.097 193.572 175.295 + endloop + endfacet + facet normal 0.99491 -0.100756 -0.00134601 + outer loop + vertex 681.097 193.572 175.295 + vertex 682.086 203.383 172.148 + vertex 682.089 203.361 176.031 + endloop + endfacet + facet normal 0.994921 -0.100606 -0.00335096 + outer loop + vertex 681.097 193.572 175.295 + vertex 682.089 203.361 176.031 + vertex 681.102 193.499 179.128 + endloop + endfacet + facet normal 0.994889 -0.100881 -0.00423767 + outer loop + vertex 681.102 193.499 179.128 + vertex 682.089 203.361 176.031 + vertex 682.097 203.277 179.841 + endloop + endfacet + facet normal 0.99489 -0.100878 -0.00428111 + outer loop + vertex 681.102 193.499 179.128 + vertex 682.097 203.277 179.841 + vertex 681.103 193.349 182.879 + endloop + endfacet + facet normal 0.994759 -0.101948 -0.00781833 + outer loop + vertex 681.103 193.349 182.879 + vertex 682.097 203.277 179.841 + vertex 682.111 203.124 183.625 + endloop + endfacet + facet normal 0.994759 -0.101873 -0.00879859 + outer loop + vertex 681.103 193.349 182.879 + vertex 682.111 203.124 183.625 + vertex 681.114 193.129 186.689 + endloop + endfacet + facet normal 0.994689 -0.102388 -0.0105018 + outer loop + vertex 681.114 193.129 186.689 + vertex 682.111 203.124 183.625 + vertex 682.128 202.903 187.463 + endloop + endfacet + facet normal 0.994674 -0.102102 -0.014096 + outer loop + vertex 681.114 193.129 186.689 + vertex 682.128 202.903 187.463 + vertex 681.145 192.879 190.643 + endloop + endfacet + facet normal 0.994619 -0.10247 -0.0152741 + outer loop + vertex 681.145 192.879 190.643 + vertex 682.128 202.903 187.463 + vertex 682.161 202.638 191.392 + endloop + endfacet + facet normal 0.994537 -0.101893 -0.0226837 + outer loop + vertex 681.145 192.879 190.643 + vertex 682.161 202.638 191.392 + vertex 681.209 192.616 194.659 + endloop + endfacet + facet normal 0.994597 -0.101544 -0.0215976 + outer loop + vertex 681.209 192.616 194.659 + vertex 682.161 202.638 191.392 + vertex 682.216 202.33 195.367 + endloop + endfacet + facet normal 0.994471 -0.101015 -0.0286808 + outer loop + vertex 681.209 192.616 194.659 + vertex 682.216 202.33 195.367 + vertex 681.292 192.302 198.65 + endloop + endfacet + facet normal 0.994748 -0.099504 -0.0239882 + outer loop + vertex 681.292 192.302 198.65 + vertex 682.216 202.33 195.367 + vertex 682.275 201.96 199.317 + endloop + endfacet + facet normal 0.994679 -0.0992453 -0.0276319 + outer loop + vertex 681.292 192.302 198.65 + vertex 682.275 201.96 199.317 + vertex 681.361 191.898 202.555 + endloop + endfacet + facet normal 0.994766 -0.0987753 -0.0261469 + outer loop + vertex 681.361 191.898 202.555 + vertex 682.275 201.96 199.317 + vertex 682.333 201.521 203.2 + endloop + endfacet + facet normal 0.994648 -0.0984051 -0.031489 + outer loop + vertex 681.361 191.898 202.555 + vertex 682.333 201.521 203.2 + vertex 681.433 191.415 206.363 + endloop + endfacet + facet normal 0.994821 -0.0975258 -0.0286302 + outer loop + vertex 681.433 191.415 206.363 + vertex 682.333 201.521 203.2 + vertex 682.395 201.029 207.039 + endloop + endfacet + facet normal 0.994762 -0.0973404 -0.0311848 + outer loop + vertex 681.433 191.415 206.363 + vertex 682.395 201.029 207.039 + vertex 681.5 190.875 210.185 + endloop + endfacet + facet normal 0.994599 -0.098135 -0.0337962 + outer loop + vertex 681.5 190.875 210.185 + vertex 682.395 201.029 207.039 + vertex 682.472 200.48 210.901 + endloop + endfacet + facet normal 0.994436 -0.0977016 -0.0393895 + outer loop + vertex 681.5 190.875 210.185 + vertex 682.472 200.48 210.901 + vertex 681.596 190.266 214.114 + endloop + endfacet + facet normal 0.99444 -0.0976847 -0.0393345 + outer loop + vertex 681.596 190.266 214.114 + vertex 682.472 200.48 210.901 + vertex 682.567 199.869 214.806 + endloop + endfacet + facet normal 0.994442 -0.0976896 -0.0392684 + outer loop + vertex 681.596 190.266 214.114 + vertex 682.567 199.869 214.806 + vertex 681.686 189.594 218.057 + endloop + endfacet + facet normal 0.994329 -0.0981825 -0.0408565 + outer loop + vertex 681.686 189.594 218.057 + vertex 682.567 199.869 214.806 + vertex 682.661 199.196 218.711 + endloop + endfacet + facet normal 0.994118 -0.0977708 -0.0465849 + outer loop + vertex 681.686 189.594 218.057 + vertex 682.661 199.196 218.711 + vertex 681.796 188.874 221.929 + endloop + endfacet + facet normal 0.994067 -0.0979737 -0.0472493 + outer loop + vertex 681.796 188.874 221.929 + vertex 682.661 199.196 218.711 + vertex 682.774 198.474 222.585 + endloop + endfacet + facet normal 0.993927 -0.0977318 -0.0505772 + outer loop + vertex 681.796 188.874 221.929 + vertex 682.774 198.474 222.585 + vertex 681.916 188.107 225.759 + endloop + endfacet + facet normal 0.993651 -0.0987356 -0.0539309 + outer loop + vertex 681.916 188.107 225.759 + vertex 682.774 198.474 222.585 + vertex 682.906 197.704 226.424 + endloop + endfacet + facet normal 0.993308 -0.098228 -0.0607431 + outer loop + vertex 681.916 188.107 225.759 + vertex 682.906 197.704 226.424 + vertex 682.069 187.294 229.573 + endloop + endfacet + facet normal 0.99351 -0.0975607 -0.0584834 + outer loop + vertex 682.069 187.294 229.573 + vertex 682.906 197.704 226.424 + vertex 683.049 196.906 230.198 + endloop + endfacet + facet normal 0.993079 -0.0970147 -0.0661981 + outer loop + vertex 682.069 187.294 229.573 + vertex 683.049 196.906 230.198 + vertex 682.236 186.462 233.299 + endloop + endfacet + facet normal 0.992709 -0.0981188 -0.0700138 + outer loop + vertex 682.236 186.462 233.299 + vertex 683.049 196.906 230.198 + vertex 683.229 196.093 233.882 + endloop + endfacet + facet normal 0.992115 -0.0975317 -0.0787078 + outer loop + vertex 682.236 186.462 233.299 + vertex 683.229 196.093 233.882 + vertex 682.44 185.624 236.912 + endloop + endfacet + facet normal 0.991978 -0.0978909 -0.0799846 + outer loop + vertex 682.44 185.624 236.912 + vertex 683.229 196.093 233.882 + vertex 683.438 195.259 237.495 + endloop + endfacet + facet normal 0.991198 -0.0972119 -0.0898709 + outer loop + vertex 682.44 185.624 236.912 + vertex 683.438 195.259 237.495 + vertex 682.681 184.757 240.503 + endloop + endfacet + facet normal 0.990608 -0.0985702 -0.0947607 + outer loop + vertex 682.681 184.757 240.503 + vertex 683.438 195.259 237.495 + vertex 683.695 194.373 241.105 + endloop + endfacet + facet normal 0.989508 -0.0977249 -0.10641 + outer loop + vertex 682.681 184.757 240.503 + vertex 683.695 194.373 241.105 + vertex 682.982 183.82 244.166 + endloop + endfacet + facet normal 0.989611 -0.0975108 -0.105648 + outer loop + vertex 682.982 183.82 244.166 + vertex 683.695 194.373 241.105 + vertex 683.993 193.408 244.783 + endloop + endfacet + facet normal 0.988016 -0.0963834 -0.120561 + outer loop + vertex 682.982 183.82 244.166 + vertex 683.993 193.408 244.783 + vertex 683.343 182.775 247.957 + endloop + endfacet + facet normal 0.987713 -0.0969615 -0.122559 + outer loop + vertex 683.343 182.775 247.957 + vertex 683.993 193.408 244.783 + vertex 684.362 192.407 248.551 + endloop + endfacet + facet normal 0.985385 -0.0955778 -0.140998 + outer loop + vertex 683.343 182.775 247.957 + vertex 684.362 192.407 248.551 + vertex 683.807 181.392 252.142 + endloop + endfacet + facet normal 0.984473 -0.0972133 -0.146156 + outer loop + vertex 683.807 181.392 252.142 + vertex 684.362 192.407 248.551 + vertex 684.845 191.878 252.155 + endloop + endfacet + facet normal 0.973826 -0.0960884 -0.205984 + outer loop + vertex 683.807 181.392 252.142 + vertex 684.845 191.878 252.155 + vertex 684.635 183.353 255.14 + endloop + endfacet + facet normal 0.982292 -0.0829887 -0.167976 + outer loop + vertex 684.635 183.353 255.14 + vertex 684.845 191.878 252.155 + vertex 685.362 191.261 255.487 + endloop + endfacet + facet normal 0.978731 -0.0817736 -0.188146 + outer loop + vertex 684.635 183.353 255.14 + vertex 685.362 191.261 255.487 + vertex 685.099 182.788 257.8 + endloop + endfacet + facet normal 0.978408 -0.0821723 -0.189644 + outer loop + vertex 685.362 191.261 255.487 + vertex 685.856 188.937 259.039 + vertex 685.099 182.788 257.8 + endloop + endfacet + facet normal 0.978776 -0.082644 -0.187528 + outer loop + vertex 685.336 180.885 259.875 + vertex 685.099 182.788 257.8 + vertex 685.856 188.937 259.039 + endloop + endfacet + facet normal 0.971839 -0.085521 -0.21958 + outer loop + vertex 685.336 180.885 259.875 + vertex 685.856 188.937 259.039 + vertex 685.751 181.356 261.528 + endloop + endfacet + facet normal 0.972397 -0.0848052 -0.217376 + outer loop + vertex 685.856 188.937 259.039 + vertex 686.55 187.836 262.574 + vertex 685.751 181.356 261.528 + endloop + endfacet + facet normal 0.970882 -0.0834602 -0.224552 + outer loop + vertex 686.054 179.975 263.35 + vertex 685.751 181.356 261.528 + vertex 686.55 187.836 262.574 + endloop + endfacet + facet normal 0.962359 -0.0862013 -0.257749 + outer loop + vertex 686.054 179.975 263.35 + vertex 686.55 187.836 262.574 + vertex 686.539 180.6 264.952 + endloop + endfacet + facet normal 0.96196 -0.0866411 -0.259089 + outer loop + vertex 686.55 187.836 262.574 + vertex 687.394 186.875 266.028 + vertex 686.539 180.6 264.952 + endloop + endfacet + facet normal 0.961586 -0.0863355 -0.260575 + outer loop + vertex 686.918 179.27 266.791 + vertex 686.539 180.6 264.952 + vertex 687.394 186.875 266.028 + endloop + endfacet + facet normal 0.950757 -0.0892932 -0.296796 + outer loop + vertex 686.918 179.27 266.791 + vertex 687.394 186.875 266.028 + vertex 687.478 179.825 268.419 + endloop + endfacet + facet normal 0.949209 -0.0908231 -0.301252 + outer loop + vertex 687.394 186.875 266.028 + vertex 688.375 185.808 269.442 + vertex 687.478 179.825 268.419 + endloop + endfacet + facet normal 0.948644 -0.0904138 -0.30315 + outer loop + vertex 687.945 178.457 270.288 + vertex 687.478 179.825 268.419 + vertex 688.375 185.808 269.442 + endloop + endfacet + facet normal 0.936273 -0.0937616 -0.338527 + outer loop + vertex 687.945 178.457 270.288 + vertex 688.375 185.808 269.442 + vertex 688.587 178.979 271.919 + endloop + endfacet + facet normal 0.935455 -0.0945283 -0.340571 + outer loop + vertex 688.375 185.808 269.442 + vertex 689.5 184.908 272.783 + vertex 688.587 178.979 271.919 + endloop + endfacet + facet normal 0.931963 -0.0925363 -0.350545 + outer loop + vertex 689.156 177.618 273.791 + vertex 688.587 178.979 271.919 + vertex 689.5 184.908 272.783 + endloop + endfacet + facet normal 0.917866 -0.0966273 -0.384948 + outer loop + vertex 689.156 177.618 273.791 + vertex 689.5 184.908 272.783 + vertex 689.883 178.192 275.381 + endloop + endfacet + facet normal 0.920587 -0.0941758 -0.379011 + outer loop + vertex 689.5 184.908 272.783 + vertex 690.813 184.439 276.087 + vertex 689.883 178.192 275.381 + endloop + endfacet + facet normal 0.912388 -0.0906772 -0.399157 + outer loop + vertex 690.556 176.875 277.218 + vertex 689.883 178.192 275.381 + vertex 690.813 184.439 276.087 + endloop + endfacet + facet normal 0.891934 -0.0963508 -0.44178 + outer loop + vertex 690.556 176.875 277.218 + vertex 690.813 184.439 276.087 + vertex 691.37 177.475 278.731 + endloop + endfacet + facet normal 0.896404 -0.092817 -0.433411 + outer loop + vertex 690.813 184.439 276.087 + vertex 692.327 183.782 279.359 + vertex 691.37 177.475 278.731 + endloop + endfacet + facet normal 0.885721 -0.088986 -0.45561 + outer loop + vertex 692.143 176.184 280.486 + vertex 691.37 177.475 278.731 + vertex 692.327 183.782 279.359 + endloop + endfacet + facet normal 0.860354 -0.0950704 -0.500752 + outer loop + vertex 692.143 176.184 280.486 + vertex 692.327 183.782 279.359 + vertex 693.036 176.83 281.898 + endloop + endfacet + facet normal 0.863438 -0.126365 -0.488371 + outer loop + vertex 692.317 171.438 282.021 + vertex 692.143 176.184 280.486 + vertex 693.036 176.83 281.898 + endloop + endfacet + facet normal 0.843041 -0.124444 -0.523256 + outer loop + vertex 692.317 171.438 282.021 + vertex 693.036 176.83 281.898 + vertex 693.222 171.19 283.538 + endloop + endfacet + facet normal 0.833778 -0.17019 -0.525214 + outer loop + vertex 692.399 166.62 283.713 + vertex 692.317 171.438 282.021 + vertex 693.222 171.19 283.538 + endloop + endfacet + facet normal 0.816794 -0.168149 -0.551882 + outer loop + vertex 692.399 166.62 283.713 + vertex 693.222 171.19 283.538 + vertex 693.356 166.399 285.196 + endloop + endfacet + facet normal 0.804286 -0.220911 -0.551654 + outer loop + vertex 692.418 162.208 285.508 + vertex 692.399 166.62 283.713 + vertex 693.356 166.399 285.196 + endloop + endfacet + facet normal 0.781483 -0.218255 -0.584507 + outer loop + vertex 692.418 162.208 285.508 + vertex 693.356 166.399 285.196 + vertex 693.435 161.998 286.945 + endloop + endfacet + facet normal 0.782989 -0.217533 -0.582759 + outer loop + vertex 693.435 161.998 286.945 + vertex 693.356 166.399 285.196 + vertex 694.364 166.236 286.611 + endloop + endfacet + facet normal 0.758056 -0.214673 -0.615845 + outer loop + vertex 693.435 161.998 286.945 + vertex 694.364 166.236 286.611 + vertex 694.493 161.884 288.287 + endloop + endfacet + facet normal 0.759179 -0.214174 -0.614636 + outer loop + vertex 694.493 161.884 288.287 + vertex 694.364 166.236 286.611 + vertex 695.444 166.215 287.953 + endloop + endfacet + facet normal 0.730517 -0.210579 -0.649616 + outer loop + vertex 694.493 161.884 288.287 + vertex 695.444 166.215 287.953 + vertex 695.606 161.913 289.53 + endloop + endfacet + facet normal 0.735783 -0.208445 -0.64434 + outer loop + vertex 695.606 161.913 289.53 + vertex 695.444 166.215 287.953 + vertex 696.603 166.393 289.219 + endloop + endfacet + facet normal 0.704597 -0.203953 -0.679666 + outer loop + vertex 695.606 161.913 289.53 + vertex 696.603 166.393 289.219 + vertex 696.748 162.033 290.678 + endloop + endfacet + facet normal 0.698272 -0.257915 -0.667754 + outer loop + vertex 695.612 157.925 291.077 + vertex 695.606 161.913 289.53 + vertex 696.748 162.033 290.678 + endloop + endfacet + facet normal 0.667341 -0.252552 -0.700623 + outer loop + vertex 695.612 157.925 291.077 + vertex 696.748 162.033 290.678 + vertex 696.674 157.933 292.085 + endloop + endfacet + facet normal 0.672951 -0.250998 -0.6958 + outer loop + vertex 696.674 157.933 292.085 + vertex 696.748 162.033 290.678 + vertex 697.792 162.002 291.699 + endloop + endfacet + facet normal 0.651625 -0.247161 -0.717145 + outer loop + vertex 696.674 157.933 292.085 + vertex 697.792 162.002 291.699 + vertex 697.577 157.875 292.925 + endloop + endfacet + facet normal 0.637453 -0.30825 -0.706141 + outer loop + vertex 696.261 153.96 293.446 + vertex 696.674 157.933 292.085 + vertex 697.577 157.875 292.925 + endloop + endfacet + facet normal 0.612215 -0.302986 -0.730337 + outer loop + vertex 696.261 153.96 293.446 + vertex 697.577 157.875 292.925 + vertex 696.997 153.926 294.077 + endloop + endfacet + facet normal 0.598897 -0.355365 -0.717661 + outer loop + vertex 695.486 149.965 294.778 + vertex 696.261 153.96 293.446 + vertex 696.997 153.926 294.077 + endloop + endfacet + facet normal 0.576051 -0.350344 -0.738529 + outer loop + vertex 695.486 149.965 294.778 + vertex 696.997 153.926 294.077 + vertex 696.112 150.361 295.078 + endloop + endfacet + facet normal 0.570748 -0.350199 -0.742702 + outer loop + vertex 696.112 150.361 295.078 + vertex 696.997 153.926 294.077 + vertex 697.513 154.016 294.432 + endloop + endfacet + facet normal 0.54894 -0.345128 -0.761283 + outer loop + vertex 696.112 150.361 295.078 + vertex 697.513 154.016 294.432 + vertex 696.49 150.648 295.22 + endloop + endfacet + facet normal 0.600195 -0.350759 -0.718842 + outer loop + vertex 696.49 150.648 295.22 + vertex 697.513 154.016 294.432 + vertex 697.889 154.43 294.543 + endloop + endfacet + facet normal 0.567801 -0.34397 -0.747855 + outer loop + vertex 696.49 150.648 295.22 + vertex 697.889 154.43 294.543 + vertex 696.818 151.206 295.214 + endloop + endfacet + facet normal 0.837834 -0.362945 -0.407806 + outer loop + vertex 696.818 151.206 295.214 + vertex 697.889 154.43 294.543 + vertex 698.289 155.434 294.472 + endloop + endfacet + facet normal 0.60651 -0.354795 -0.711524 + outer loop + vertex 694.695 150.088 294.043 + vertex 696.261 153.96 293.446 + vertex 695.486 149.965 294.778 + endloop + endfacet + facet normal 0.623271 -0.358986 -0.694739 + outer loop + vertex 694.695 150.088 294.043 + vertex 695.351 154.09 292.563 + vertex 696.261 153.96 293.446 + endloop + endfacet + facet normal 0.629696 -0.358065 -0.6894 + outer loop + vertex 693.884 150.669 293 + vertex 695.351 154.09 292.563 + vertex 694.695 150.088 294.043 + endloop + endfacet + facet normal 0.642016 -0.36164 -0.676042 + outer loop + vertex 693.884 150.669 293 + vertex 694.325 154.164 291.549 + vertex 695.351 154.09 292.563 + endloop + endfacet + facet normal 0.636009 -0.362942 -0.681003 + outer loop + vertex 692.862 150.721 292.018 + vertex 694.325 154.164 291.549 + vertex 693.884 150.669 293 + endloop + endfacet + facet normal 0.659702 -0.369393 -0.654478 + outer loop + vertex 692.862 150.721 292.018 + vertex 693.226 154.157 290.445 + vertex 694.325 154.164 291.549 + endloop + endfacet + facet normal 0.652986 -0.371268 -0.660128 + outer loop + vertex 691.728 150.705 290.905 + vertex 693.226 154.157 290.445 + vertex 692.862 150.721 292.018 + endloop + endfacet + facet normal 0.677582 -0.378041 -0.630847 + outer loop + vertex 691.728 150.705 290.905 + vertex 692.097 154.223 289.193 + vertex 693.226 154.157 290.445 + endloop + endfacet + facet normal 0.676711 -0.378322 -0.631613 + outer loop + vertex 690.555 150.774 289.606 + vertex 692.097 154.223 289.193 + vertex 691.728 150.705 290.905 + endloop + endfacet + facet normal 0.698757 -0.384762 -0.603072 + outer loop + vertex 690.555 150.774 289.606 + vertex 690.976 154.386 287.791 + vertex 692.097 154.223 289.193 + endloop + endfacet + facet normal 0.697763 -0.385112 -0.603999 + outer loop + vertex 689.389 150.95 288.148 + vertex 690.976 154.386 287.791 + vertex 690.555 150.774 289.606 + endloop + endfacet + facet normal 0.717764 -0.391428 -0.575846 + outer loop + vertex 689.389 150.95 288.148 + vertex 689.892 154.63 286.273 + vertex 690.976 154.386 287.791 + endloop + endfacet + facet normal 0.717694 -0.391454 -0.575916 + outer loop + vertex 688.283 151.221 286.586 + vertex 689.892 154.63 286.273 + vertex 689.389 150.95 288.148 + endloop + endfacet + facet normal 0.735621 -0.3974 -0.548575 + outer loop + vertex 688.283 151.221 286.586 + vertex 688.869 154.931 284.683 + vertex 689.892 154.63 286.273 + endloop + endfacet + facet normal 0.735829 -0.39732 -0.548354 + outer loop + vertex 687.262 151.573 284.96 + vertex 688.869 154.931 284.683 + vertex 688.283 151.221 286.586 + endloop + endfacet + facet normal 0.750945 -0.402503 -0.52352 + outer loop + vertex 687.262 151.573 284.96 + vertex 687.914 155.279 283.045 + vertex 688.869 154.931 284.683 + endloop + endfacet + facet normal 0.75336 -0.401521 -0.520797 + outer loop + vertex 686.316 151.957 283.296 + vertex 687.914 155.279 283.045 + vertex 687.262 151.573 284.96 + endloop + endfacet + facet normal 0.76608 -0.405944 -0.498328 + outer loop + vertex 686.316 151.957 283.296 + vertex 687.023 155.655 281.37 + vertex 687.914 155.279 283.045 + endloop + endfacet + facet normal 0.768118 -0.405068 -0.495898 + outer loop + vertex 685.435 152.368 281.595 + vertex 687.023 155.655 281.37 + vertex 686.316 151.957 283.296 + endloop + endfacet + facet normal 0.778984 -0.408915 -0.475365 + outer loop + vertex 685.435 152.368 281.595 + vertex 686.19 156.054 279.66 + vertex 687.023 155.655 281.37 + endloop + endfacet + facet normal 0.781291 -0.407869 -0.472471 + outer loop + vertex 684.609 152.789 279.865 + vertex 686.19 156.054 279.66 + vertex 685.435 152.368 281.595 + endloop + endfacet + facet normal 0.7901 -0.411021 -0.454757 + outer loop + vertex 684.609 152.789 279.865 + vertex 685.41 156.484 277.919 + vertex 686.19 156.054 279.66 + endloop + endfacet + facet normal 0.793351 -0.409471 -0.450475 + outer loop + vertex 683.844 153.242 278.107 + vertex 685.41 156.484 277.919 + vertex 684.609 152.789 279.865 + endloop + endfacet + facet normal 0.801606 -0.412435 -0.43281 + outer loop + vertex 683.844 153.242 278.107 + vertex 684.686 156.931 276.151 + vertex 685.41 156.484 277.919 + endloop + endfacet + facet normal 0.804011 -0.411224 -0.429489 + outer loop + vertex 683.13 153.711 276.321 + vertex 684.686 156.931 276.151 + vertex 683.844 153.242 278.107 + endloop + endfacet + facet normal 0.811445 -0.413922 -0.412584 + outer loop + vertex 683.13 153.711 276.321 + vertex 684.014 157.4 274.36 + vertex 684.686 156.931 276.151 + endloop + endfacet + facet normal 0.813873 -0.412637 -0.409074 + outer loop + vertex 682.462 154.186 274.513 + vertex 684.014 157.4 274.36 + vertex 683.13 153.711 276.321 + endloop + endfacet + facet normal 0.820657 -0.415132 -0.392668 + outer loop + vertex 682.462 154.186 274.513 + vertex 683.394 157.88 272.554 + vertex 684.014 157.4 274.36 + endloop + endfacet + facet normal 0.822727 -0.413989 -0.38953 + outer loop + vertex 681.842 154.673 272.687 + vertex 683.394 157.88 272.554 + vertex 682.462 154.186 274.513 + endloop + endfacet + facet normal 0.827783 -0.4159 -0.376566 + outer loop + vertex 681.842 154.673 272.687 + vertex 682.82 158.383 270.739 + vertex 683.394 157.88 272.554 + endloop + endfacet + facet normal 0.831937 -0.41353 -0.369966 + outer loop + vertex 681.272 155.168 270.852 + vertex 682.82 158.383 270.739 + vertex 681.842 154.673 272.687 + endloop + endfacet + facet normal 0.837078 -0.415508 -0.355883 + outer loop + vertex 681.272 155.168 270.852 + vertex 682.295 158.877 268.925 + vertex 682.82 158.383 270.739 + endloop + endfacet + facet normal 0.838535 -0.414646 -0.353452 + outer loop + vertex 680.75 155.673 269.02 + vertex 682.295 158.877 268.925 + vertex 681.272 155.168 270.852 + endloop + endfacet + facet normal 0.843098 -0.416452 -0.340226 + outer loop + vertex 680.75 155.673 269.02 + vertex 681.806 159.366 267.118 + vertex 682.295 158.877 268.925 + endloop + endfacet + facet normal 0.845893 -0.414737 -0.335347 + outer loop + vertex 680.268 156.154 267.208 + vertex 681.806 159.366 267.118 + vertex 680.75 155.673 269.02 + endloop + endfacet + facet normal 0.849583 -0.416187 -0.324032 + outer loop + vertex 680.268 156.154 267.208 + vertex 681.357 159.847 265.321 + vertex 681.806 159.366 267.118 + endloop + endfacet + facet normal 0.851567 -0.414927 -0.320419 + outer loop + vertex 679.827 156.635 265.413 + vertex 681.357 159.847 265.321 + vertex 680.268 156.154 267.208 + endloop + endfacet + facet normal 0.854646 -0.416111 -0.310535 + outer loop + vertex 679.827 156.635 265.413 + vertex 680.957 160.364 263.527 + vertex 681.357 159.847 265.321 + endloop + endfacet + facet normal 0.857011 -0.414562 -0.306057 + outer loop + vertex 679.442 157.164 263.621 + vertex 680.957 160.364 263.527 + vertex 679.827 156.635 265.413 + endloop + endfacet + facet normal 0.859999 -0.415681 -0.29599 + outer loop + vertex 679.442 157.164 263.621 + vertex 680.612 160.942 261.714 + vertex 680.957 160.364 263.527 + endloop + endfacet + facet normal 0.862499 -0.413973 -0.291071 + outer loop + vertex 679.108 157.742 261.806 + vertex 680.612 160.942 261.714 + vertex 679.442 157.164 263.621 + endloop + endfacet + facet normal 0.865858 -0.415207 -0.279094 + outer loop + vertex 679.108 157.742 261.806 + vertex 680.293 161.516 259.87 + vertex 680.612 160.942 261.714 + endloop + endfacet + facet normal 0.867878 -0.413731 -0.274981 + outer loop + vertex 678.77 158.25 259.977 + vertex 680.293 161.516 259.87 + vertex 679.108 157.742 261.806 + endloop + endfacet + facet normal 0.871168 -0.414859 -0.262597 + outer loop + vertex 678.77 158.25 259.977 + vertex 679.899 161.852 258.031 + vertex 680.293 161.516 259.87 + endloop + endfacet + facet normal 0.869182 -0.416432 -0.26666 + outer loop + vertex 678.347 158.486 258.23 + vertex 679.899 161.852 258.031 + vertex 678.77 158.25 259.977 + endloop + endfacet + facet normal 0.871836 -0.417072 -0.256813 + outer loop + vertex 678.347 158.486 258.23 + vertex 679.248 161.532 256.34 + vertex 679.899 161.852 258.031 + endloop + endfacet + facet normal 0.866828 -0.421507 -0.266347 + outer loop + vertex 677.853 158.335 256.861 + vertex 679.248 161.532 256.34 + vertex 678.347 158.486 258.23 + endloop + endfacet + facet normal 0.867931 -0.421421 -0.26287 + outer loop + vertex 677.853 158.335 256.861 + vertex 678.069 159.824 255.187 + vertex 679.248 161.532 256.34 + endloop + endfacet + facet normal 0.614242 -0.302808 -0.728707 + outer loop + vertex 696.997 153.926 294.077 + vertex 697.577 157.875 292.925 + vertex 698.262 157.802 293.534 + endloop + endfacet + facet normal 0.575092 -0.294852 -0.763106 + outer loop + vertex 696.997 153.926 294.077 + vertex 698.262 157.802 293.534 + vertex 697.513 154.016 294.432 + endloop + endfacet + facet normal 0.60587 -0.295174 -0.738778 + outer loop + vertex 697.513 154.016 294.432 + vertex 698.262 157.802 293.534 + vertex 698.734 157.92 293.873 + endloop + endfacet + facet normal 0.546801 -0.283696 -0.787735 + outer loop + vertex 697.513 154.016 294.432 + vertex 698.734 157.92 293.873 + vertex 697.889 154.43 294.543 + endloop + endfacet + facet normal 0.641082 -0.291599 -0.709918 + outer loop + vertex 697.889 154.43 294.543 + vertex 698.734 157.92 293.873 + vertex 699.106 158.533 293.957 + endloop + endfacet + facet normal 0.554639 -0.276647 -0.784756 + outer loop + vertex 697.889 154.43 294.543 + vertex 699.106 158.533 293.957 + vertex 698.289 155.434 294.472 + endloop + endfacet + facet normal 0.748865 -0.295952 -0.59297 + outer loop + vertex 698.289 155.434 294.472 + vertex 699.106 158.533 293.957 + vertex 699.504 159.725 293.865 + endloop + endfacet + facet normal 0.281307 -0.16701 -0.944973 + outer loop + vertex 699.106 158.533 293.957 + vertex 700.085 162.904 293.476 + vertex 699.504 159.725 293.865 + endloop + endfacet + facet normal 0.226817 -0.158988 -0.960873 + outer loop + vertex 699.504 159.725 293.865 + vertex 700.085 162.904 293.476 + vertex 700.27 163.117 293.485 + endloop + endfacet + facet normal 0.361941 -0.184239 -0.913813 + outer loop + vertex 699.504 159.725 293.865 + vertex 700.27 163.117 293.485 + vertex 700.023 161.795 293.653 + endloop + endfacet + facet normal 0.699401 -0.21775 -0.680752 + outer loop + vertex 700.27 163.117 293.485 + vertex 700.557 164.412 293.365 + vertex 700.023 161.795 293.653 + endloop + endfacet + facet normal -0.0461255 -0.0817389 -0.995586 + outer loop + vertex 700.27 163.117 293.485 + vertex 700.867 167.237 293.119 + vertex 700.557 164.412 293.365 + endloop + endfacet + facet normal 0.679637 -0.13728 -0.720589 + outer loop + vertex 700.557 164.412 293.365 + vertex 700.867 167.237 293.119 + vertex 700.71 165.451 293.312 + endloop + endfacet + facet normal 0.173469 -0.111998 -0.97845 + outer loop + vertex 700.085 162.904 293.476 + vertex 700.867 167.237 293.119 + vertex 700.27 163.117 293.485 + endloop + endfacet + facet normal 0.413495 -0.148655 -0.898289 + outer loop + vertex 700.085 162.904 293.476 + vertex 700.596 167.909 292.883 + vertex 700.867 167.237 293.119 + endloop + endfacet + facet normal 0.477715 -0.151305 -0.865387 + outer loop + vertex 699.745 162.288 293.396 + vertex 700.596 167.909 292.883 + vertex 700.085 162.904 293.476 + endloop + endfacet + facet normal 0.691603 -0.168804 -0.702275 + outer loop + vertex 699.745 162.288 293.396 + vertex 700.052 166.354 292.721 + vertex 700.596 167.909 292.883 + endloop + endfacet + facet normal 0.634248 -0.172985 -0.753528 + outer loop + vertex 699.289 161.979 293.083 + vertex 700.052 166.354 292.721 + vertex 699.745 162.288 293.396 + endloop + endfacet + facet normal 0.651657 -0.229768 -0.722876 + outer loop + vertex 698.734 157.92 293.873 + vertex 699.289 161.979 293.083 + vertex 699.745 162.288 293.396 + endloop + endfacet + facet normal 0.658265 -0.175396 -0.732068 + outer loop + vertex 699.289 161.979 293.083 + vertex 699.475 167.04 292.037 + vertex 700.052 166.354 292.721 + endloop + endfacet + facet normal 0.659729 -0.175188 -0.730798 + outer loop + vertex 698.648 161.979 292.505 + vertex 699.475 167.04 292.037 + vertex 699.289 161.979 293.083 + endloop + endfacet + facet normal 0.650924 -0.237705 -0.720968 + outer loop + vertex 698.262 157.802 293.534 + vertex 698.648 161.979 292.505 + vertex 699.289 161.979 293.083 + endloop + endfacet + facet normal 0.713538 -0.179043 -0.677354 + outer loop + vertex 698.648 161.979 292.505 + vertex 698.647 166.035 291.431 + vertex 699.475 167.04 292.037 + endloop + endfacet + facet normal 0.670401 -0.18964 -0.717356 + outer loop + vertex 697.792 162.002 291.699 + vertex 698.647 166.035 291.431 + vertex 698.648 161.979 292.505 + endloop + endfacet + facet normal 0.682888 -0.191464 -0.704987 + outer loop + vertex 697.792 162.002 291.699 + vertex 697.779 166.717 290.405 + vertex 698.647 166.035 291.431 + endloop + endfacet + facet normal 0.576233 -0.215863 -0.788263 + outer loop + vertex 699.106 158.533 293.957 + vertex 699.745 162.288 293.396 + vertex 700.085 162.904 293.476 + endloop + endfacet + facet normal 0.536104 -0.213295 -0.816761 + outer loop + vertex 698.734 157.92 293.873 + vertex 699.745 162.288 293.396 + vertex 699.106 158.533 293.957 + endloop + endfacet + facet normal 0.605919 -0.230991 -0.761253 + outer loop + vertex 698.262 157.802 293.534 + vertex 699.289 161.979 293.083 + vertex 698.734 157.92 293.873 + endloop + endfacet + facet normal 0.629801 -0.240126 -0.738708 + outer loop + vertex 697.577 157.875 292.925 + vertex 698.648 161.979 292.505 + vertex 698.262 157.802 293.534 + endloop + endfacet + facet normal 0.639784 -0.307832 -0.704214 + outer loop + vertex 695.351 154.09 292.563 + vertex 696.674 157.933 292.085 + vertex 696.261 153.96 293.446 + endloop + endfacet + facet normal 0.655686 -0.311278 -0.687882 + outer loop + vertex 695.351 154.09 292.563 + vertex 695.612 157.925 291.077 + vertex 696.674 157.933 292.085 + endloop + endfacet + facet normal 0.656605 -0.311042 -0.687112 + outer loop + vertex 694.325 154.164 291.549 + vertex 695.612 157.925 291.077 + vertex 695.351 154.09 292.563 + endloop + endfacet + facet normal 0.681433 -0.316147 -0.660076 + outer loop + vertex 694.325 154.164 291.549 + vertex 694.51 157.884 289.959 + vertex 695.612 157.925 291.077 + endloop + endfacet + facet normal 0.672647 -0.318963 -0.667689 + outer loop + vertex 693.226 154.157 290.445 + vertex 694.51 157.884 289.959 + vertex 694.325 154.164 291.549 + endloop + endfacet + facet normal 0.699945 -0.324279 -0.636333 + outer loop + vertex 693.226 154.157 290.445 + vertex 693.411 157.933 288.724 + vertex 694.51 157.884 289.959 + endloop + endfacet + facet normal 0.693323 -0.326686 -0.642323 + outer loop + vertex 692.097 154.223 289.193 + vertex 693.411 157.933 288.724 + vertex 693.226 154.157 290.445 + endloop + endfacet + facet normal 0.720226 -0.332017 -0.60913 + outer loop + vertex 692.097 154.223 289.193 + vertex 692.332 158.093 287.362 + vertex 693.411 157.933 288.724 + endloop + endfacet + facet normal 0.717311 -0.333168 -0.611935 + outer loop + vertex 690.976 154.386 287.791 + vertex 692.332 158.093 287.362 + vertex 692.097 154.223 289.193 + endloop + endfacet + facet normal 0.741674 -0.33829 -0.579206 + outer loop + vertex 690.976 154.386 287.791 + vertex 691.285 158.32 285.888 + vertex 692.332 158.093 287.362 + endloop + endfacet + facet normal 0.738587 -0.339584 -0.582384 + outer loop + vertex 689.892 154.63 286.273 + vertex 691.285 158.32 285.888 + vertex 690.976 154.386 287.791 + endloop + endfacet + facet normal 0.75971 -0.344356 -0.551598 + outer loop + vertex 689.892 154.63 286.273 + vertex 690.281 158.589 284.337 + vertex 691.285 158.32 285.888 + endloop + endfacet + facet normal 0.758247 -0.344999 -0.553206 + outer loop + vertex 688.869 154.931 284.683 + vertex 690.281 158.589 284.337 + vertex 689.892 154.63 286.273 + endloop + endfacet + facet normal 0.77596 -0.349197 -0.525307 + outer loop + vertex 688.869 154.931 284.683 + vertex 689.332 158.893 282.733 + vertex 690.281 158.589 284.337 + endloop + endfacet + facet normal 0.775077 -0.349602 -0.526341 + outer loop + vertex 687.914 155.279 283.045 + vertex 689.332 158.893 282.733 + vertex 688.869 154.931 284.683 + endloop + endfacet + facet normal 0.789642 -0.353189 -0.50172 + outer loop + vertex 687.914 155.279 283.045 + vertex 688.437 159.234 281.085 + vertex 689.332 158.893 282.733 + endloop + endfacet + facet normal 0.79126 -0.35241 -0.499715 + outer loop + vertex 687.023 155.655 281.37 + vertex 688.437 159.234 281.085 + vertex 687.914 155.279 283.045 + endloop + endfacet + facet normal 0.804293 -0.355677 -0.476033 + outer loop + vertex 687.023 155.655 281.37 + vertex 687.601 159.602 279.398 + vertex 688.437 159.234 281.085 + endloop + endfacet + facet normal 0.804748 -0.355445 -0.475437 + outer loop + vertex 686.19 156.054 279.66 + vertex 687.601 159.602 279.398 + vertex 687.023 155.655 281.37 + endloop + endfacet + facet normal 0.815424 -0.358162 -0.454756 + outer loop + vertex 686.19 156.054 279.66 + vertex 686.816 160.004 277.674 + vertex 687.601 159.602 279.398 + endloop + endfacet + facet normal 0.816431 -0.357625 -0.453371 + outer loop + vertex 685.41 156.484 277.919 + vertex 686.816 160.004 277.674 + vertex 686.19 156.054 279.66 + endloop + endfacet + facet normal 0.826449 -0.360187 -0.432722 + outer loop + vertex 685.41 156.484 277.919 + vertex 686.085 160.434 275.918 + vertex 686.816 160.004 277.674 + endloop + endfacet + facet normal 0.828178 -0.359213 -0.430217 + outer loop + vertex 684.686 156.931 276.151 + vertex 686.085 160.434 275.918 + vertex 685.41 156.484 277.919 + endloop + endfacet + facet normal 0.837838 -0.361655 -0.408941 + outer loop + vertex 684.686 156.931 276.151 + vertex 685.41 160.883 274.14 + vertex 686.085 160.434 275.918 + endloop + endfacet + facet normal 0.837907 -0.361614 -0.408837 + outer loop + vertex 684.014 157.4 274.36 + vertex 685.41 160.883 274.14 + vertex 684.686 156.931 276.151 + endloop + endfacet + facet normal 0.845087 -0.363433 -0.392102 + outer loop + vertex 684.014 157.4 274.36 + vertex 684.784 161.361 272.348 + vertex 685.41 160.883 274.14 + endloop + endfacet + facet normal 0.847787 -0.361768 -0.387791 + outer loop + vertex 683.394 157.88 272.554 + vertex 684.784 161.361 272.348 + vertex 684.014 157.4 274.36 + endloop + endfacet + facet normal 0.854533 -0.363468 -0.37103 + outer loop + vertex 683.394 157.88 272.554 + vertex 684.214 161.851 270.553 + vertex 684.784 161.361 272.348 + endloop + endfacet + facet normal 0.854835 -0.363276 -0.370524 + outer loop + vertex 682.82 158.383 270.739 + vertex 684.214 161.851 270.553 + vertex 683.394 157.88 272.554 + endloop + endfacet + facet normal 0.860732 -0.364818 -0.355032 + outer loop + vertex 682.82 158.383 270.739 + vertex 683.687 162.351 268.762 + vertex 684.214 161.851 270.553 + endloop + endfacet + facet normal 0.863986 -0.362667 -0.349286 + outer loop + vertex 682.295 158.877 268.925 + vertex 683.687 162.351 268.762 + vertex 682.82 158.383 270.739 + endloop + endfacet + facet normal 0.869018 -0.364019 -0.335109 + outer loop + vertex 682.295 158.877 268.925 + vertex 683.202 162.838 266.977 + vertex 683.687 162.351 268.762 + endloop + endfacet + facet normal 0.870072 -0.363298 -0.333151 + outer loop + vertex 681.806 159.366 267.118 + vertex 683.202 162.838 266.977 + vertex 682.295 158.877 268.925 + endloop + endfacet + facet normal 0.874801 -0.364629 -0.319014 + outer loop + vertex 681.806 159.366 267.118 + vertex 682.753 163.314 265.201 + vertex 683.202 162.838 266.977 + endloop + endfacet + facet normal 0.876048 -0.363749 -0.316585 + outer loop + vertex 681.357 159.847 265.321 + vertex 682.753 163.314 265.201 + vertex 681.806 159.366 267.118 + endloop + endfacet + facet normal 0.879319 -0.364706 -0.306249 + outer loop + vertex 681.357 159.847 265.321 + vertex 682.341 163.812 263.424 + vertex 682.753 163.314 265.201 + endloop + endfacet + facet normal 0.881762 -0.362937 -0.301285 + outer loop + vertex 680.957 160.364 263.527 + vertex 682.341 163.812 263.424 + vertex 681.357 159.847 265.321 + endloop + endfacet + facet normal 0.885675 -0.364114 -0.288099 + outer loop + vertex 680.957 160.364 263.527 + vertex 681.983 164.362 261.629 + vertex 682.341 163.812 263.424 + endloop + endfacet + facet normal 0.887436 -0.362781 -0.284337 + outer loop + vertex 680.612 160.942 261.714 + vertex 681.983 164.362 261.629 + vertex 680.957 160.364 263.527 + endloop + endfacet + facet normal 0.89153 -0.364054 -0.269517 + outer loop + vertex 680.612 160.942 261.714 + vertex 681.673 164.952 259.805 + vertex 681.983 164.362 261.629 + endloop + endfacet + facet normal 0.892403 -0.363355 -0.267564 + outer loop + vertex 680.293 161.516 259.87 + vertex 681.673 164.952 259.805 + vertex 680.612 160.942 261.714 + endloop + endfacet + facet normal 0.896131 -0.364577 -0.253048 + outer loop + vertex 680.293 161.516 259.87 + vertex 681.362 165.479 257.945 + vertex 681.673 164.952 259.805 + endloop + endfacet + facet normal 0.89371 -0.366619 -0.258597 + outer loop + vertex 679.899 161.852 258.031 + vertex 681.362 165.479 257.945 + vertex 680.293 161.516 259.87 + endloop + endfacet + facet normal 0.894707 -0.366929 -0.254682 + outer loop + vertex 679.899 161.852 258.031 + vertex 680.894 165.648 256.059 + vertex 681.362 165.479 257.945 + endloop + endfacet + facet normal 0.887197 -0.373427 -0.270988 + outer loop + vertex 679.248 161.532 256.34 + vertex 680.894 165.648 256.059 + vertex 679.899 161.852 258.031 + endloop + endfacet + facet normal 0.892231 -0.3742 -0.252779 + outer loop + vertex 680.894 165.648 256.059 + vertex 679.248 161.532 256.34 + vertex 680.024 164.934 254.044 + endloop + endfacet + facet normal 0.661104 -0.245258 -0.709077 + outer loop + vertex 697.577 157.875 292.925 + vertex 697.792 162.002 291.699 + vertex 698.648 161.979 292.505 + endloop + endfacet + facet normal 0.68332 -0.191356 -0.704597 + outer loop + vertex 696.748 162.033 290.678 + vertex 697.779 166.717 290.405 + vertex 697.792 162.002 291.699 + endloop + endfacet + facet normal 0.692443 -0.259963 -0.67301 + outer loop + vertex 694.51 157.884 289.959 + vertex 695.606 161.913 289.53 + vertex 695.612 157.925 291.077 + endloop + endfacet + facet normal 0.721338 -0.264323 -0.640161 + outer loop + vertex 694.51 157.884 289.959 + vertex 694.493 161.884 288.287 + vertex 695.606 161.913 289.53 + endloop + endfacet + facet normal 0.714302 -0.267147 -0.646842 + outer loop + vertex 693.411 157.933 288.724 + vertex 694.493 161.884 288.287 + vertex 694.51 157.884 289.959 + endloop + endfacet + facet normal 0.744516 -0.271336 -0.609978 + outer loop + vertex 693.411 157.933 288.724 + vertex 693.435 161.998 286.945 + vertex 694.493 161.884 288.287 + endloop + endfacet + facet normal 0.738109 -0.274142 -0.616475 + outer loop + vertex 692.332 158.093 287.362 + vertex 693.435 161.998 286.945 + vertex 693.411 157.933 288.724 + endloop + endfacet + facet normal 0.764713 -0.277905 -0.581363 + outer loop + vertex 692.332 158.093 287.362 + vertex 692.418 162.208 285.508 + vertex 693.435 161.998 286.945 + endloop + endfacet + facet normal 0.761862 -0.279239 -0.584459 + outer loop + vertex 691.285 158.32 285.888 + vertex 692.418 162.208 285.508 + vertex 692.332 158.093 287.362 + endloop + endfacet + facet normal 0.784077 -0.282594 -0.552598 + outer loop + vertex 691.285 158.32 285.888 + vertex 691.44 162.454 283.994 + vertex 692.418 162.208 285.508 + endloop + endfacet + facet normal 0.781722 -0.283759 -0.55533 + outer loop + vertex 690.281 158.589 284.337 + vertex 691.44 162.454 283.994 + vertex 691.285 158.32 285.888 + endloop + endfacet + facet normal 0.800132 -0.286747 -0.526845 + outer loop + vertex 690.281 158.589 284.337 + vertex 690.503 162.726 282.422 + vertex 691.44 162.454 283.994 + endloop + endfacet + facet normal 0.79959 -0.287028 -0.527514 + outer loop + vertex 689.332 158.893 282.733 + vertex 690.503 162.726 282.422 + vertex 690.281 158.589 284.337 + endloop + endfacet + facet normal 0.815659 -0.289767 -0.500735 + outer loop + vertex 689.332 158.893 282.733 + vertex 689.617 163.031 280.803 + vertex 690.503 162.726 282.422 + endloop + endfacet + facet normal 0.814519 -0.290386 -0.50223 + outer loop + vertex 688.437 159.234 281.085 + vertex 689.617 163.031 280.803 + vertex 689.332 158.893 282.733 + endloop + endfacet + facet normal 0.829711 -0.293083 -0.475061 + outer loop + vertex 688.437 159.234 281.085 + vertex 688.784 163.371 279.138 + vertex 689.617 163.031 280.803 + endloop + endfacet + facet normal 0.829759 -0.293055 -0.474993 + outer loop + vertex 687.601 159.602 279.398 + vertex 688.784 163.371 279.138 + vertex 688.437 159.234 281.085 + endloop + endfacet + facet normal 0.841176 -0.295129 -0.453125 + outer loop + vertex 687.601 159.602 279.398 + vertex 687.999 163.755 277.432 + vertex 688.784 163.371 279.138 + endloop + endfacet + facet normal 0.841918 -0.294684 -0.452035 + outer loop + vertex 686.816 160.004 277.674 + vertex 687.999 163.755 277.432 + vertex 687.601 159.602 279.398 + endloop + endfacet + facet normal 0.853594 -0.296824 -0.428104 + outer loop + vertex 686.816 160.004 277.674 + vertex 687.269 164.166 275.69 + vertex 687.999 163.755 277.432 + endloop + endfacet + facet normal 0.853374 -0.296963 -0.428446 + outer loop + vertex 686.085 160.434 275.918 + vertex 687.269 164.166 275.69 + vertex 686.816 160.004 277.674 + endloop + endfacet + facet normal 0.864363 -0.298973 -0.40434 + outer loop + vertex 686.085 160.434 275.918 + vertex 686.591 164.599 273.922 + vertex 687.269 164.166 275.69 + endloop + endfacet + facet normal 0.864984 -0.298559 -0.403319 + outer loop + vertex 685.41 160.883 274.14 + vertex 686.591 164.599 273.922 + vertex 686.085 160.434 275.918 + endloop + endfacet + facet normal 0.873417 -0.300078 -0.383531 + outer loop + vertex 685.41 160.883 274.14 + vertex 685.966 165.054 272.141 + vertex 686.591 164.599 273.922 + endloop + endfacet + facet normal 0.872593 -0.300651 -0.384956 + outer loop + vertex 684.784 161.361 272.348 + vertex 685.966 165.054 272.141 + vertex 685.41 160.883 274.14 + endloop + endfacet + facet normal 0.881135 -0.302192 -0.363705 + outer loop + vertex 684.784 161.361 272.348 + vertex 685.393 165.528 270.36 + vertex 685.966 165.054 272.141 + endloop + endfacet + facet normal 0.88163 -0.301833 -0.362802 + outer loop + vertex 684.214 161.851 270.553 + vertex 685.393 165.528 270.36 + vertex 684.784 161.361 272.348 + endloop + endfacet + facet normal 0.888842 -0.303137 -0.343609 + outer loop + vertex 684.214 161.851 270.553 + vertex 684.871 166.008 268.585 + vertex 685.393 165.528 270.36 + endloop + endfacet + facet normal 0.887606 -0.304064 -0.345977 + outer loop + vertex 683.687 162.351 268.762 + vertex 684.871 166.008 268.585 + vertex 684.214 161.851 270.553 + endloop + endfacet + facet normal 0.894592 -0.305374 -0.32627 + outer loop + vertex 683.687 162.351 268.762 + vertex 684.39 166.483 266.822 + vertex 684.871 166.008 268.585 + endloop + endfacet + facet normal 0.894689 -0.305298 -0.326074 + outer loop + vertex 683.202 162.838 266.977 + vertex 684.39 166.483 266.822 + vertex 683.687 162.351 268.762 + endloop + endfacet + facet normal 0.90063 -0.306466 -0.30813 + outer loop + vertex 683.202 162.838 266.977 + vertex 683.945 166.94 265.068 + vertex 684.39 166.483 266.822 + endloop + endfacet + facet normal 0.899784 -0.307146 -0.309921 + outer loop + vertex 682.753 163.314 265.201 + vertex 683.945 166.94 265.068 + vertex 683.202 162.838 266.977 + endloop + endfacet + facet normal 0.904162 -0.308074 -0.29594 + outer loop + vertex 682.753 163.314 265.201 + vertex 683.532 167.409 263.318 + vertex 683.945 166.94 265.068 + endloop + endfacet + facet normal 0.904077 -0.308144 -0.296127 + outer loop + vertex 682.341 163.812 263.424 + vertex 683.532 167.409 263.318 + vertex 682.753 163.314 265.201 + endloop + endfacet + facet normal 0.908649 -0.309202 -0.280625 + outer loop + vertex 682.341 163.812 263.424 + vertex 683.16 167.924 261.547 + vertex 683.532 167.409 263.318 + endloop + endfacet + facet normal 0.910769 -0.307382 -0.275712 + outer loop + vertex 681.983 164.362 261.629 + vertex 683.16 167.924 261.547 + vertex 682.341 163.812 263.424 + endloop + endfacet + facet normal 0.915591 -0.308563 -0.257839 + outer loop + vertex 681.983 164.362 261.629 + vertex 682.834 168.457 259.749 + vertex 683.16 167.924 261.547 + endloop + endfacet + facet normal 0.916516 -0.30771 -0.255563 + outer loop + vertex 681.673 164.952 259.805 + vertex 682.834 168.457 259.749 + vertex 681.983 164.362 261.629 + endloop + endfacet + facet normal 0.921505 -0.309035 -0.235215 + outer loop + vertex 681.673 164.952 259.805 + vertex 682.537 168.924 257.973 + vertex 682.834 168.457 259.749 + endloop + endfacet + facet normal 0.918953 -0.311527 -0.24182 + outer loop + vertex 681.362 165.479 257.945 + vertex 682.537 168.924 257.973 + vertex 681.673 164.952 259.805 + endloop + endfacet + facet normal 0.9191 -0.311582 -0.241188 + outer loop + vertex 681.362 165.479 257.945 + vertex 682.255 169.503 256.15 + vertex 682.537 168.924 257.973 + endloop + endfacet + facet normal 0.913715 -0.31649 -0.254872 + outer loop + vertex 680.894 165.648 256.059 + vertex 682.255 169.503 256.15 + vertex 681.362 165.479 257.945 + endloop + endfacet + facet normal 0.915696 -0.317386 -0.246511 + outer loop + vertex 680.894 165.648 256.059 + vertex 681.886 169.936 254.222 + vertex 682.255 169.503 256.15 + endloop + endfacet + facet normal 0.904257 -0.326846 -0.274758 + outer loop + vertex 680.024 164.934 254.044 + vertex 681.886 169.936 254.222 + vertex 680.894 165.648 256.059 + endloop + endfacet + facet normal 0.913906 -0.331897 -0.233709 + outer loop + vertex 680.024 164.934 254.044 + vertex 681.536 170.399 252.196 + vertex 681.886 169.936 254.222 + endloop + endfacet + facet normal 0.920014 -0.327389 -0.215386 + outer loop + vertex 679.801 165.863 251.68 + vertex 681.536 170.399 252.196 + vertex 680.024 164.934 254.044 + endloop + endfacet + facet normal 0.922226 -0.329773 -0.201861 + outer loop + vertex 679.801 165.863 251.68 + vertex 681.29 170.943 250.185 + vertex 681.536 170.399 252.196 + endloop + endfacet + facet normal 0.924201 -0.328346 -0.195043 + outer loop + vertex 679.563 166.374 249.69 + vertex 681.29 170.943 250.185 + vertex 679.801 165.863 251.68 + endloop + endfacet + facet normal 0.92516 -0.329405 -0.188605 + outer loop + vertex 679.563 166.374 249.69 + vertex 681.068 171.409 248.279 + vertex 681.29 170.943 250.185 + endloop + endfacet + facet normal 0.925635 -0.32906 -0.186868 + outer loop + vertex 679.341 166.821 247.805 + vertex 681.068 171.409 248.279 + vertex 679.563 166.374 249.69 + endloop + endfacet + facet normal 0.926896 -0.330458 -0.177937 + outer loop + vertex 679.341 166.821 247.805 + vertex 680.872 171.863 246.416 + vertex 681.068 171.409 248.279 + endloop + endfacet + facet normal 0.92635 -0.330864 -0.180014 + outer loop + vertex 679.142 167.285 245.929 + vertex 680.872 171.863 246.416 + vertex 679.341 166.821 247.805 + endloop + endfacet + facet normal 0.927236 -0.331902 -0.173418 + outer loop + vertex 679.142 167.285 245.929 + vertex 680.692 172.335 244.552 + vertex 680.872 171.863 246.416 + endloop + endfacet + facet normal 0.92873 -0.330752 -0.167521 + outer loop + vertex 678.974 167.765 244.046 + vertex 680.692 172.335 244.552 + vertex 679.142 167.285 245.929 + endloop + endfacet + facet normal 0.928937 -0.331015 -0.165849 + outer loop + vertex 678.974 167.765 244.046 + vertex 680.529 172.81 242.689 + vertex 680.692 172.335 244.552 + endloop + endfacet + facet normal 0.930283 -0.329947 -0.160335 + outer loop + vertex 678.818 168.236 242.176 + vertex 680.529 172.81 242.689 + vertex 678.974 167.765 244.046 + endloop + endfacet + facet normal 0.931002 -0.330924 -0.154025 + outer loop + vertex 678.818 168.236 242.176 + vertex 680.388 173.268 240.854 + vertex 680.529 172.81 242.689 + endloop + endfacet + facet normal 0.931487 -0.330526 -0.151934 + outer loop + vertex 678.679 168.686 240.346 + vertex 680.388 173.268 240.854 + vertex 678.818 168.236 242.176 + endloop + endfacet + facet normal 0.931597 -0.33068 -0.15092 + outer loop + vertex 678.679 168.686 240.346 + vertex 680.253 173.708 239.058 + vertex 680.388 173.268 240.854 + endloop + endfacet + facet normal 0.932707 -0.329764 -0.145992 + outer loop + vertex 678.556 169.127 238.562 + vertex 680.253 173.708 239.058 + vertex 678.679 168.686 240.346 + endloop + endfacet + facet normal 0.933239 -0.330526 -0.140775 + outer loop + vertex 678.556 169.127 238.562 + vertex 680.137 174.133 237.291 + vertex 680.253 173.708 239.058 + endloop + endfacet + facet normal 0.933811 -0.330031 -0.138116 + outer loop + vertex 678.444 169.548 236.801 + vertex 680.137 174.133 237.291 + vertex 678.556 169.127 238.562 + endloop + endfacet + facet normal 0.934315 -0.330785 -0.132804 + outer loop + vertex 678.444 169.548 236.801 + vertex 680.034 174.552 235.52 + vertex 680.137 174.133 237.291 + endloop + endfacet + facet normal 0.934968 -0.330187 -0.12966 + outer loop + vertex 678.342 169.958 235.021 + vertex 680.034 174.552 235.52 + vertex 678.444 169.548 236.801 + endloop + endfacet + facet normal 0.935195 -0.330554 -0.127056 + outer loop + vertex 678.342 169.958 235.021 + vertex 679.937 174.974 233.708 + vertex 680.034 174.552 235.52 + endloop + endfacet + facet normal 0.935815 -0.329955 -0.124014 + outer loop + vertex 678.248 170.379 233.187 + vertex 679.937 174.974 233.708 + vertex 678.342 169.958 235.021 + endloop + endfacet + facet normal 0.935999 -0.33028 -0.121742 + outer loop + vertex 678.248 170.379 233.187 + vertex 679.845 175.402 231.839 + vertex 679.937 174.974 233.708 + endloop + endfacet + facet normal 0.936232 -0.330044 -0.120587 + outer loop + vertex 678.158 170.815 231.293 + vertex 679.845 175.402 231.839 + vertex 678.248 170.379 233.187 + endloop + endfacet + facet normal 0.936697 -0.330966 -0.114285 + outer loop + vertex 678.158 170.815 231.293 + vertex 679.762 175.827 229.926 + vertex 679.845 175.402 231.839 + endloop + endfacet + facet normal 0.937501 -0.330093 -0.110138 + outer loop + vertex 678.078 171.234 229.361 + vertex 679.762 175.827 229.926 + vertex 678.158 170.815 231.293 + endloop + endfacet + facet normal 0.937673 -0.330485 -0.107462 + outer loop + vertex 678.078 171.234 229.361 + vertex 679.688 176.246 227.997 + vertex 679.762 175.827 229.926 + endloop + endfacet + facet normal 0.937335 -0.330861 -0.10924 + outer loop + vertex 678.001 171.655 227.424 + vertex 679.688 176.246 227.997 + vertex 678.078 171.234 229.361 + endloop + endfacet + facet normal 0.937622 -0.331544 -0.104613 + outer loop + vertex 678.001 171.655 227.424 + vertex 679.617 176.651 226.079 + vertex 679.688 176.246 227.997 + endloop + endfacet + facet normal 0.938627 -0.330388 -0.099109 + outer loop + vertex 677.938 172.052 225.51 + vertex 679.617 176.651 226.079 + vertex 678.001 171.655 227.424 + endloop + endfacet + facet normal 0.938617 -0.33036 -0.099302 + outer loop + vertex 677.938 172.052 225.51 + vertex 679.554 177.04 224.185 + vertex 679.617 176.651 226.079 + endloop + endfacet + facet normal 0.939239 -0.329628 -0.0957865 + outer loop + vertex 677.879 172.429 223.623 + vertex 679.554 177.04 224.185 + vertex 677.938 172.052 225.51 + endloop + endfacet + facet normal 0.939338 -0.329898 -0.0938693 + outer loop + vertex 677.879 172.429 223.623 + vertex 679.496 177.412 222.302 + vertex 679.554 177.04 224.185 + endloop + endfacet + facet normal 0.939302 -0.329942 -0.0940786 + outer loop + vertex 677.819 172.795 221.742 + vertex 679.496 177.412 222.302 + vertex 677.879 172.429 223.623 + endloop + endfacet + facet normal 0.93952 -0.330563 -0.0896081 + outer loop + vertex 677.819 172.795 221.742 + vertex 679.442 177.772 220.402 + vertex 679.496 177.412 222.302 + endloop + endfacet + facet normal 0.939963 -0.330003 -0.086993 + outer loop + vertex 677.766 173.147 219.834 + vertex 679.442 177.772 220.402 + vertex 677.819 172.795 221.742 + endloop + endfacet + facet normal 0.94015 -0.330621 -0.0825079 + outer loop + vertex 677.766 173.147 219.834 + vertex 679.396 178.126 218.456 + vertex 679.442 177.772 220.402 + endloop + endfacet + facet normal 0.939966 -0.330866 -0.0836102 + outer loop + vertex 677.715 173.5 217.867 + vertex 679.396 178.126 218.456 + vertex 677.766 173.147 219.834 + endloop + endfacet + facet normal 0.939909 -0.33066 -0.0850634 + outer loop + vertex 677.715 173.5 217.867 + vertex 679.339 178.48 216.448 + vertex 679.396 178.126 218.456 + endloop + endfacet + facet normal 0.940969 -0.329206 -0.0787416 + outer loop + vertex 677.667 173.847 215.839 + vertex 679.339 178.48 216.448 + vertex 677.715 173.5 217.867 + endloop + endfacet + facet normal 0.941054 -0.329581 -0.0761175 + outer loop + vertex 677.667 173.847 215.839 + vertex 679.292 178.819 214.409 + vertex 679.339 178.48 216.448 + endloop + endfacet + facet normal 0.94125 -0.329298 -0.0749099 + outer loop + vertex 677.618 174.176 213.782 + vertex 679.292 178.819 214.409 + vertex 677.667 173.847 215.839 + endloop + endfacet + facet normal 0.941289 -0.329502 -0.0735096 + outer loop + vertex 677.618 174.176 213.782 + vertex 679.245 179.139 212.377 + vertex 679.292 178.819 214.409 + endloop + endfacet + facet normal 0.941136 -0.329722 -0.0744664 + outer loop + vertex 677.569 174.493 211.755 + vertex 679.245 179.139 212.377 + vertex 677.618 174.176 213.782 + endloop + endfacet + facet normal 0.941181 -0.329951 -0.0728787 + outer loop + vertex 677.569 174.493 211.755 + vertex 679.197 179.436 210.404 + vertex 679.245 179.139 212.377 + endloop + endfacet + facet normal 0.941993 -0.328764 -0.0675525 + outer loop + vertex 677.528 174.777 209.802 + vertex 679.197 179.436 210.404 + vertex 677.569 174.493 211.755 + endloop + endfacet + facet normal 0.942026 -0.32896 -0.0661256 + outer loop + vertex 677.528 174.777 209.802 + vertex 679.158 179.707 208.508 + vertex 679.197 179.436 210.404 + endloop + endfacet + facet normal 0.94225 -0.328627 -0.0645749 + outer loop + vertex 677.49 175.037 207.929 + vertex 679.158 179.707 208.508 + vertex 677.528 174.777 209.802 + endloop + endfacet + facet normal 0.942296 -0.328914 -0.0624 + outer loop + vertex 677.49 175.037 207.929 + vertex 679.125 179.963 206.662 + vertex 679.158 179.707 208.508 + endloop + endfacet + facet normal 0.942551 -0.328527 -0.0605671 + outer loop + vertex 677.459 175.286 206.098 + vertex 679.125 179.963 206.662 + vertex 677.49 175.037 207.929 + endloop + endfacet + facet normal 0.942587 -0.32877 -0.0586599 + outer loop + vertex 677.459 175.286 206.098 + vertex 679.097 180.209 204.822 + vertex 679.125 179.963 206.662 + endloop + endfacet + facet normal 0.942411 -0.329042 -0.0599366 + outer loop + vertex 677.428 175.532 204.256 + vertex 679.097 180.209 204.822 + vertex 677.459 175.286 206.098 + endloop + endfacet + facet normal 0.942436 -0.329214 -0.0585917 + outer loop + vertex 677.428 175.532 204.256 + vertex 679.061 180.441 202.943 + vertex 679.097 180.209 204.822 + endloop + endfacet + facet normal 0.943223 -0.327932 -0.0528215 + outer loop + vertex 677.393 175.735 202.375 + vertex 679.061 180.441 202.943 + vertex 677.428 175.532 204.256 + endloop + endfacet + facet normal 0.94323 -0.327995 -0.05232 + outer loop + vertex 677.393 175.735 202.375 + vertex 679.022 180.635 201.02 + vertex 679.061 180.441 202.943 + endloop + endfacet + facet normal 0.943137 -0.328152 -0.0530013 + outer loop + vertex 677.347 175.917 200.436 + vertex 679.022 180.635 201.02 + vertex 677.393 175.735 202.375 + endloop + endfacet + facet normal 0.943162 -0.328455 -0.050623 + outer loop + vertex 677.347 175.917 200.436 + vertex 678.973 180.798 199.051 + vertex 679.022 180.635 201.02 + endloop + endfacet + facet normal 0.943582 -0.327713 -0.0475128 + outer loop + vertex 677.317 176.123 198.416 + vertex 678.973 180.798 199.051 + vertex 677.347 175.917 200.436 + endloop + endfacet + facet normal 0.943586 -0.328093 -0.0447208 + outer loop + vertex 677.317 176.123 198.416 + vertex 678.947 180.996 197.043 + vertex 678.973 180.798 199.051 + endloop + endfacet + facet normal 0.944942 -0.325482 -0.0338489 + outer loop + vertex 677.395 176.568 196.297 + vertex 678.947 180.996 197.043 + vertex 677.317 176.123 198.416 + endloop + endfacet + facet normal 0.945015 -0.324816 -0.0379609 + outer loop + vertex 677.395 176.568 196.297 + vertex 678.976 181.315 195.046 + vertex 678.947 180.996 197.043 + endloop + endfacet + facet normal 0.94771 -0.318903 -0.0121184 + outer loop + vertex 677.724 177.616 194.442 + vertex 678.976 181.315 195.046 + vertex 677.395 176.568 196.297 + endloop + endfacet + facet normal 0.948364 -0.314906 -0.0379538 + outer loop + vertex 677.724 177.616 194.442 + vertex 678.949 181.47 193.077 + vertex 678.976 181.315 195.046 + endloop + endfacet + facet normal 0.944849 -0.321837 -0.0606807 + outer loop + vertex 677.425 177.084 192.619 + vertex 678.949 181.47 193.077 + vertex 677.724 177.616 194.442 + endloop + endfacet + facet normal 0.945179 -0.324206 -0.0390887 + outer loop + vertex 677.425 177.084 192.619 + vertex 678.896 181.56 191.068 + vertex 678.949 181.47 193.077 + endloop + endfacet + facet normal 0.947599 -0.318766 -0.0210985 + outer loop + vertex 677.617 177.787 190.601 + vertex 678.896 181.56 191.068 + vertex 677.425 177.084 192.619 + endloop + endfacet + facet normal 0.947746 -0.31714 -0.0346392 + outer loop + vertex 677.617 177.787 190.601 + vertex 678.851 181.644 189.059 + vertex 678.896 181.56 191.068 + endloop + endfacet + facet normal 0.943517 -0.325871 -0.0598562 + outer loop + vertex 677.297 177.201 188.753 + vertex 678.851 181.644 189.059 + vertex 677.617 177.787 190.601 + endloop + endfacet + facet normal 0.944154 -0.328182 -0.0294856 + outer loop + vertex 677.297 177.201 188.753 + vertex 678.823 181.74 187.087 + vertex 678.851 181.644 189.059 + endloop + endfacet + facet normal 0.946433 -0.322662 -0.0123691 + outer loop + vertex 677.514 177.915 186.71 + vertex 678.823 181.74 187.087 + vertex 677.297 177.201 188.753 + endloop + endfacet + facet normal 0.946605 -0.321151 -0.0282973 + outer loop + vertex 677.514 177.915 186.71 + vertex 678.803 181.849 185.182 + vertex 678.823 181.74 187.087 + endloop + endfacet + facet normal 0.94307 -0.328703 -0.0507184 + outer loop + vertex 677.214 177.327 184.944 + vertex 678.803 181.849 185.182 + vertex 677.514 177.915 186.71 + endloop + endfacet + facet normal 0.943589 -0.330425 -0.0214285 + outer loop + vertex 677.214 177.327 184.944 + vertex 678.794 181.943 183.326 + vertex 678.803 181.849 185.182 + endloop + endfacet + facet normal 0.946002 -0.324158 -0.00119438 + outer loop + vertex 677.461 178.056 182.967 + vertex 678.794 181.943 183.326 + vertex 677.214 177.327 184.944 + endloop + endfacet + facet normal 0.946311 -0.322819 -0.016863 + outer loop + vertex 677.461 178.056 182.967 + vertex 678.788 182.021 181.482 + vertex 678.794 181.943 183.326 + endloop + endfacet + facet normal 0.942899 -0.330587 -0.040655 + outer loop + vertex 677.174 177.451 181.211 + vertex 678.788 182.021 181.482 + vertex 677.461 178.056 182.967 + endloop + endfacet + facet normal 0.943081 -0.33234 -0.0122034 + outer loop + vertex 677.174 177.451 181.211 + vertex 678.786 182.084 179.615 + vertex 678.788 182.021 181.482 + endloop + endfacet + facet normal 0.9453 -0.326099 0.00814752 + outer loop + vertex 677.442 178.178 179.212 + vertex 678.786 182.084 179.615 + vertex 677.174 177.451 181.211 + endloop + endfacet + facet normal 0.945893 -0.324276 -0.0114929 + outer loop + vertex 677.442 178.178 179.212 + vertex 678.779 182.134 177.704 + vertex 678.786 182.084 179.615 + endloop + endfacet + facet normal 0.942899 -0.331445 -0.0329577 + outer loop + vertex 677.163 177.566 177.386 + vertex 678.779 182.134 177.704 + vertex 677.442 178.178 179.212 + endloop + endfacet + facet normal 0.942816 -0.333247 -0.00669062 + outer loop + vertex 677.163 177.566 177.386 + vertex 678.778 182.169 175.755 + vertex 678.779 182.134 177.704 + endloop + endfacet + facet normal 0.945154 -0.326263 0.0153421 + outer loop + vertex 677.441 178.276 175.324 + vertex 678.778 182.169 175.755 + vertex 677.163 177.566 177.386 + endloop + endfacet + facet normal 0.945902 -0.324433 -0.00348618 + outer loop + vertex 677.441 178.276 175.324 + vertex 678.777 182.188 173.783 + vertex 678.778 182.169 175.755 + endloop + endfacet + facet normal 0.943268 -0.331232 -0.0230334 + outer loop + vertex 677.159 177.602 173.464 + vertex 678.777 182.188 173.783 + vertex 677.441 178.276 175.324 + endloop + endfacet + facet normal 0.943085 -0.332536 -0.00334313 + outer loop + vertex 677.159 177.602 173.464 + vertex 678.775 182.201 171.8 + vertex 678.777 182.188 173.783 + endloop + endfacet + facet normal 0.945276 -0.325808 0.0173771 + outer loop + vertex 677.437 178.297 171.373 + vertex 678.775 182.201 171.8 + vertex 677.159 177.602 173.464 + endloop + endfacet + facet normal 0.945869 -0.324527 0.00380782 + outer loop + vertex 677.437 178.297 171.373 + vertex 678.778 182.188 169.814 + vertex 678.775 182.201 171.8 + endloop + endfacet + facet normal 0.943327 -0.331491 -0.0157527 + outer loop + vertex 677.161 177.601 169.503 + vertex 678.778 182.188 169.814 + vertex 677.437 178.297 171.373 + endloop + endfacet + facet normal 0.943002 -0.332755 0.0045761 + outer loop + vertex 677.161 177.601 169.503 + vertex 678.78 182.164 167.829 + vertex 678.778 182.188 169.814 + endloop + endfacet + facet normal 0.945213 -0.325341 0.0269357 + outer loop + vertex 677.445 178.252 167.406 + vertex 678.78 182.164 167.829 + vertex 677.161 177.601 169.503 + endloop + endfacet + facet normal 0.946139 -0.323651 0.00840074 + outer loop + vertex 677.445 178.252 167.406 + vertex 678.783 182.123 165.854 + vertex 678.78 182.164 167.829 + endloop + endfacet + facet normal 0.943913 -0.330057 -0.00949973 + outer loop + vertex 677.175 177.532 165.552 + vertex 678.783 182.123 165.854 + vertex 677.445 178.252 167.406 + endloop + endfacet + facet normal 0.943326 -0.331503 0.0155695 + outer loop + vertex 677.175 177.532 165.552 + vertex 678.794 182.062 163.894 + vertex 678.783 182.123 165.854 + endloop + endfacet + facet normal 0.944714 -0.326451 0.0307349 + outer loop + vertex 677.463 178.171 163.482 + vertex 678.794 182.062 163.894 + vertex 677.175 177.532 165.552 + endloop + endfacet + facet normal 0.945579 -0.325057 0.0147731 + outer loop + vertex 677.463 178.171 163.482 + vertex 678.802 181.996 161.953 + vertex 678.794 182.062 163.894 + endloop + endfacet + facet normal 0.943334 -0.33182 -0.00411182 + outer loop + vertex 677.192 177.424 161.66 + vertex 678.802 181.996 161.953 + vertex 677.463 178.171 163.482 + endloop + endfacet + facet normal 0.942682 -0.333114 0.0196412 + outer loop + vertex 677.192 177.424 161.66 + vertex 678.813 181.914 160.025 + vertex 678.802 181.996 161.953 + endloop + endfacet + facet normal 0.944339 -0.326647 0.0390457 + outer loop + vertex 677.476 178.001 159.619 + vertex 678.813 181.914 160.025 + vertex 677.192 177.424 161.66 + endloop + endfacet + facet normal 0.945299 -0.325361 0.0234763 + outer loop + vertex 677.476 178.001 159.619 + vertex 678.829 181.822 158.099 + vertex 678.813 181.914 160.025 + endloop + endfacet + facet normal 0.943175 -0.332268 0.00421788 + outer loop + vertex 677.211 177.227 157.799 + vertex 678.829 181.822 158.099 + vertex 677.476 178.001 159.619 + endloop + endfacet + facet normal 0.942521 -0.333309 0.0236547 + outer loop + vertex 677.211 177.227 157.799 + vertex 678.841 181.718 156.169 + vertex 678.829 181.822 158.099 + endloop + endfacet + facet normal 0.944421 -0.325253 0.0477479 + outer loop + vertex 677.505 177.778 155.752 + vertex 678.841 181.718 156.169 + vertex 677.211 177.227 157.799 + endloop + endfacet + facet normal 0.945642 -0.323807 0.0301782 + outer loop + vertex 677.505 177.778 155.752 + vertex 678.857 181.587 154.232 + vertex 678.841 181.718 156.169 + endloop + endfacet + facet normal 0.943259 -0.331972 0.00759245 + outer loop + vertex 677.247 177.003 153.927 + vertex 678.857 181.587 154.232 + vertex 677.505 177.778 155.752 + endloop + endfacet + facet normal 0.94222 -0.333324 0.0334296 + outer loop + vertex 677.247 177.003 153.927 + vertex 678.876 181.446 152.295 + vertex 678.857 181.587 154.232 + endloop + endfacet + facet normal 0.943818 -0.325749 0.0556358 + outer loop + vertex 677.549 177.529 151.885 + vertex 678.876 181.446 152.295 + vertex 677.247 177.003 153.927 + endloop + endfacet + facet normal 0.945276 -0.324234 0.036416 + outer loop + vertex 677.549 177.529 151.885 + vertex 678.898 181.293 150.369 + vertex 678.876 181.446 152.295 + endloop + endfacet + facet normal 0.943402 -0.331189 0.0174883 + outer loop + vertex 677.293 176.705 150.084 + vertex 678.898 181.293 150.369 + vertex 677.549 177.529 151.885 + endloop + endfacet + facet normal 0.942368 -0.332207 0.0397545 + outer loop + vertex 677.293 176.705 150.084 + vertex 678.925 181.141 148.462 + vertex 678.898 181.293 150.369 + endloop + endfacet + facet normal 0.943671 -0.325514 0.0593712 + outer loop + vertex 677.6 177.227 148.065 + vertex 678.925 181.141 148.462 + vertex 677.293 176.705 150.084 + endloop + endfacet + facet normal 0.945048 -0.324219 0.0420306 + outer loop + vertex 677.6 177.227 148.065 + vertex 678.954 180.979 146.57 + vertex 678.925 181.141 148.462 + endloop + endfacet + facet normal 0.943246 -0.331329 0.0225513 + outer loop + vertex 677.345 176.376 146.239 + vertex 678.954 180.979 146.57 + vertex 677.6 177.227 148.065 + endloop + endfacet + facet normal 0.941805 -0.332676 0.0482765 + outer loop + vertex 677.345 176.376 146.239 + vertex 678.985 180.794 144.677 + vertex 678.954 180.979 146.57 + endloop + endfacet + facet normal 0.942679 -0.327582 0.0636054 + outer loop + vertex 677.647 176.849 144.189 + vertex 678.985 180.794 144.677 + vertex 677.345 176.376 146.239 + endloop + endfacet + facet normal 0.943929 -0.326331 0.0500673 + outer loop + vertex 677.647 176.849 144.189 + vertex 679.016 180.587 142.752 + vertex 678.985 180.794 144.677 + endloop + endfacet + facet normal 0.942512 -0.332598 0.0324071 + outer loop + vertex 677.381 175.904 142.239 + vertex 679.016 180.587 142.752 + vertex 677.647 176.849 144.189 + endloop + endfacet + facet normal 0.940891 -0.334391 0.0539157 + outer loop + vertex 677.381 175.904 142.239 + vertex 679.052 180.371 140.792 + vertex 679.016 180.587 142.752 + endloop + endfacet + facet normal 0.941778 -0.327429 0.076446 + outer loop + vertex 677.703 176.344 140.154 + vertex 679.052 180.371 140.792 + vertex 677.381 175.904 142.239 + endloop + endfacet + facet normal 0.944038 -0.324995 0.0563039 + outer loop + vertex 677.703 176.344 140.154 + vertex 679.09 180.141 138.812 + vertex 679.052 180.371 140.792 + endloop + endfacet + facet normal 0.943627 -0.327319 0.0493062 + outer loop + vertex 677.481 175.426 138.313 + vertex 679.09 180.141 138.812 + vertex 677.703 176.344 140.154 + endloop + endfacet + facet normal 0.942507 -0.328317 0.0623513 + outer loop + vertex 677.481 175.426 138.313 + vertex 679.097 179.775 136.791 + vertex 679.09 180.141 138.812 + endloop + endfacet + facet normal 0.942801 -0.326194 0.068732 + outer loop + vertex 677.516 175.065 136.119 + vertex 679.097 179.775 136.791 + vertex 677.481 175.426 138.313 + endloop + endfacet + facet normal 0.943027 -0.325972 0.0666485 + outer loop + vertex 677.516 175.065 136.119 + vertex 679.146 179.497 134.734 + vertex 679.097 179.775 136.791 + endloop + endfacet + facet normal 0.942647 -0.328943 0.0566899 + outer loop + vertex 677.505 174.673 134.029 + vertex 679.146 179.497 134.734 + vertex 677.516 175.065 136.119 + endloop + endfacet + facet normal 0.941495 -0.330159 0.0676924 + outer loop + vertex 677.505 174.673 134.029 + vertex 679.201 179.243 132.728 + vertex 679.146 179.497 134.734 + endloop + endfacet + facet normal 0.941519 -0.329884 0.0686903 + outer loop + vertex 677.553 174.388 132.005 + vertex 679.201 179.243 132.728 + vertex 677.505 174.673 134.029 + endloop + endfacet + facet normal 0.941171 -0.330223 0.0717628 + outer loop + vertex 677.553 174.388 132.005 + vertex 679.262 178.989 130.762 + vertex 679.201 179.243 132.728 + endloop + endfacet + facet normal 0.941219 -0.329353 0.0750525 + outer loop + vertex 677.621 174.135 130.042 + vertex 679.262 178.989 130.762 + vertex 677.553 174.388 132.005 + endloop + endfacet + facet normal 0.94083 -0.329706 0.0783176 + outer loop + vertex 677.621 174.135 130.042 + vertex 679.321 178.692 128.806 + vertex 679.262 178.989 130.762 + endloop + endfacet + facet normal 0.940834 -0.329596 0.078729 + outer loop + vertex 677.679 173.835 128.092 + vertex 679.321 178.692 128.806 + vertex 677.621 174.135 130.042 + endloop + endfacet + facet normal 0.940774 -0.329648 0.0792272 + outer loop + vertex 677.679 173.835 128.092 + vertex 679.367 178.352 126.842 + vertex 679.321 178.692 128.806 + endloop + endfacet + facet normal 0.940763 -0.329884 0.0783637 + outer loop + vertex 677.722 173.494 126.134 + vertex 679.367 178.352 126.842 + vertex 677.679 173.835 128.092 + endloop + endfacet + facet normal 0.940531 -0.330085 0.0802863 + outer loop + vertex 677.722 173.494 126.134 + vertex 679.407 177.992 124.89 + vertex 679.367 178.352 126.842 + endloop + endfacet + facet normal 0.940557 -0.329262 0.0832972 + outer loop + vertex 677.766 173.127 124.192 + vertex 679.407 177.992 124.89 + vertex 677.722 173.494 126.134 + endloop + endfacet + facet normal 0.939986 -0.329719 0.0878215 + outer loop + vertex 677.766 173.127 124.192 + vertex 679.46 177.634 122.979 + vertex 679.407 177.992 124.89 + endloop + endfacet + facet normal 0.93998 -0.330384 0.0853448 + outer loop + vertex 677.815 172.777 122.29 + vertex 679.46 177.634 122.979 + vertex 677.766 173.127 124.192 + endloop + endfacet + facet normal 0.939652 -0.330639 0.0879326 + outer loop + vertex 677.815 172.777 122.29 + vertex 679.51 177.277 121.106 + vertex 679.46 177.634 122.979 + endloop + endfacet + facet normal 0.93965 -0.330264 0.0893552 + outer loop + vertex 677.869 172.424 120.423 + vertex 679.51 177.277 121.106 + vertex 677.815 172.777 122.29 + endloop + endfacet + facet normal 0.938338 -0.331197 0.099142 + outer loop + vertex 677.869 172.424 120.423 + vertex 679.575 176.909 119.256 + vertex 679.51 177.277 121.106 + endloop + endfacet + facet normal 0.938361 -0.331737 0.0971017 + outer loop + vertex 677.931 172.056 118.566 + vertex 679.575 176.909 119.256 + vertex 677.869 172.424 120.423 + endloop + endfacet + facet normal 0.938151 -0.331883 0.0986269 + outer loop + vertex 677.931 172.056 118.566 + vertex 679.636 176.529 117.396 + vertex 679.575 176.909 119.256 + endloop + endfacet + facet normal 0.938146 -0.331784 0.0989969 + outer loop + vertex 677.994 171.677 116.695 + vertex 679.636 176.529 117.396 + vertex 677.931 172.056 118.566 + endloop + endfacet + facet normal 0.937775 -0.332038 0.101627 + outer loop + vertex 677.994 171.677 116.695 + vertex 679.7 176.133 115.518 + vertex 679.636 176.529 117.396 + endloop + endfacet + facet normal 0.937707 -0.330841 0.10606 + outer loop + vertex 678.066 171.276 114.811 + vertex 679.7 176.133 115.518 + vertex 677.994 171.677 116.695 + endloop + endfacet + facet normal 0.936943 -0.331328 0.111171 + outer loop + vertex 678.066 171.276 114.811 + vertex 679.777 175.72 113.63 + vertex 679.7 176.133 115.518 + endloop + endfacet + facet normal 0.936951 -0.331428 0.110808 + outer loop + vertex 678.141 170.855 112.917 + vertex 679.777 175.72 113.63 + vertex 678.066 171.276 114.811 + endloop + endfacet + facet normal 0.935992 -0.332012 0.116995 + outer loop + vertex 678.141 170.855 112.917 + vertex 679.863 175.293 111.735 + vertex 679.777 175.72 113.63 + endloop + endfacet + facet normal 0.936006 -0.332165 0.116441 + outer loop + vertex 678.225 170.427 111.018 + vertex 679.863 175.293 111.735 + vertex 678.141 170.855 112.917 + endloop + endfacet + facet normal 0.93474 -0.332892 0.124274 + outer loop + vertex 678.225 170.427 111.018 + vertex 679.959 174.853 109.835 + vertex 679.863 175.293 111.735 + endloop + endfacet + facet normal 0.934764 -0.333095 0.123549 + outer loop + vertex 678.321 169.989 109.115 + vertex 679.959 174.853 109.835 + vertex 678.225 170.427 111.018 + endloop + endfacet + facet normal 0.934098 -0.333461 0.127532 + outer loop + vertex 678.321 169.989 109.115 + vertex 680.058 174.402 107.931 + vertex 679.959 174.853 109.835 + endloop + endfacet + facet normal 0.93408 -0.33332 0.128032 + outer loop + vertex 678.426 169.549 107.206 + vertex 680.058 174.402 107.931 + vertex 678.321 169.989 109.115 + endloop + endfacet + facet normal 0.932082 -0.334347 0.139408 + outer loop + vertex 678.426 169.549 107.206 + vertex 680.176 173.937 106.03 + vertex 680.058 174.402 107.931 + endloop + endfacet + facet normal 0.932153 -0.334789 0.137865 + outer loop + vertex 678.542 169.086 105.296 + vertex 680.176 173.937 106.03 + vertex 678.426 169.549 107.206 + endloop + endfacet + facet normal 0.931136 -0.335286 0.14342 + outer loop + vertex 678.542 169.086 105.296 + vertex 680.299 173.469 104.133 + vertex 680.176 173.937 106.03 + endloop + endfacet + facet normal 0.930896 -0.333997 0.147915 + outer loop + vertex 678.673 168.609 103.394 + vertex 680.299 173.469 104.133 + vertex 678.542 169.086 105.296 + endloop + endfacet + facet normal 0.929983 -0.334411 0.152647 + outer loop + vertex 678.673 168.609 103.394 + vertex 680.44 173.003 102.253 + vertex 680.299 173.469 104.133 + endloop + endfacet + facet normal 0.930023 -0.334595 0.152 + outer loop + vertex 678.815 168.147 101.506 + vertex 680.44 173.003 102.253 + vertex 678.673 168.609 103.394 + endloop + endfacet + facet normal 0.929001 -0.335048 0.157165 + outer loop + vertex 678.815 168.147 101.506 + vertex 680.591 172.546 100.386 + vertex 680.44 173.003 102.253 + endloop + endfacet + facet normal 0.928652 -0.333641 0.16214 + outer loop + vertex 678.975 167.68 99.6317 + vertex 680.591 172.546 100.386 + vertex 678.815 168.147 101.506 + endloop + endfacet + facet normal 0.927605 -0.334072 0.167169 + outer loop + vertex 678.975 167.68 99.6317 + vertex 680.764 172.098 98.5302 + vertex 680.591 172.546 100.386 + endloop + endfacet + facet normal 0.927358 -0.333208 0.170235 + outer loop + vertex 679.152 167.223 97.7721 + vertex 680.764 172.098 98.5302 + vertex 678.975 167.68 99.6317 + endloop + endfacet + facet normal 0.926024 -0.333722 0.176378 + outer loop + vertex 679.152 167.223 97.7721 + vertex 680.953 171.644 96.6802 + vertex 680.764 172.098 98.5302 + endloop + endfacet + facet normal 0.926243 -0.334431 0.173865 + outer loop + vertex 679.332 166.764 95.927 + vertex 680.953 171.644 96.6802 + vertex 679.152 167.223 97.7721 + endloop + endfacet + facet normal 0.924863 -0.334939 0.180121 + outer loop + vertex 679.332 166.764 95.927 + vertex 681.13 171.134 94.8256 + vertex 680.953 171.644 96.6802 + endloop + endfacet + facet normal 0.924525 -0.333873 0.183799 + outer loop + vertex 679.513 166.254 94.0939 + vertex 681.13 171.134 94.8256 + vertex 679.332 166.764 95.927 + endloop + endfacet + facet normal 0.922125 -0.334634 0.19418 + outer loop + vertex 679.513 166.254 94.0939 + vertex 681.303 170.538 92.9761 + vertex 681.13 171.134 94.8256 + endloop + endfacet + facet normal 0.922087 -0.33452 0.194555 + outer loop + vertex 679.708 165.719 92.2475 + vertex 681.303 170.538 92.9761 + vertex 679.513 166.254 94.0939 + endloop + endfacet + facet normal 0.917955 -0.335692 0.211351 + outer loop + vertex 679.708 165.719 92.2475 + vertex 681.497 169.905 91.1256 + vertex 681.303 170.538 92.9761 + endloop + endfacet + facet normal 0.917584 -0.334677 0.214548 + outer loop + vertex 680.014 165.324 90.3228 + vertex 681.497 169.905 91.1256 + vertex 679.708 165.719 92.2475 + endloop + endfacet + facet normal 0.914366 -0.335705 0.226358 + outer loop + vertex 680.014 165.324 90.3228 + vertex 681.811 169.478 89.2242 + vertex 681.497 169.905 91.1256 + endloop + endfacet + facet normal 0.909195 -0.324256 0.261193 + outer loop + vertex 680.618 165.486 88.4224 + vertex 681.811 169.478 89.2242 + vertex 680.014 165.324 90.3228 + endloop + endfacet + facet normal 0.914205 -0.322565 0.245317 + outer loop + vertex 680.618 165.486 88.4224 + vertex 682.194 169.154 87.3725 + vertex 681.811 169.478 89.2242 + endloop + endfacet + facet normal 0.907163 -0.307568 0.287154 + outer loop + vertex 681.329 166.142 86.8766 + vertex 682.194 169.154 87.3725 + vertex 680.618 165.486 88.4224 + endloop + endfacet + facet normal 0.921078 -0.304285 0.242954 + outer loop + vertex 681.329 166.142 86.8766 + vertex 682.517 168.749 85.6382 + vertex 682.194 169.154 87.3725 + endloop + endfacet + facet normal 0.922616 -0.313945 0.224096 + outer loop + vertex 681.361 165.241 85.4866 + vertex 682.517 168.749 85.6382 + vertex 681.329 166.142 86.8766 + endloop + endfacet + facet normal 0.91827 -0.313291 0.242135 + outer loop + vertex 681.361 165.241 85.4866 + vertex 682.797 168.214 83.8849 + vertex 682.517 168.749 85.6382 + endloop + endfacet + facet normal 0.918277 -0.313352 0.242029 + outer loop + vertex 681.601 164.579 83.7186 + vertex 682.797 168.214 83.8849 + vertex 681.361 165.241 85.4866 + endloop + endfacet + facet normal 0.913194 -0.31257 0.261489 + outer loop + vertex 681.601 164.579 83.7186 + vertex 683.161 167.75 82.0611 + vertex 682.797 168.214 83.8849 + endloop + endfacet + facet normal 0.913039 -0.311622 0.263157 + outer loop + vertex 681.972 164.101 81.8633 + vertex 683.161 167.75 82.0611 + vertex 681.601 164.579 83.7186 + endloop + endfacet + facet normal 0.908724 -0.31104 0.278344 + outer loop + vertex 681.972 164.101 81.8633 + vertex 683.573 167.319 80.2324 + vertex 683.161 167.75 82.0611 + endloop + endfacet + facet normal 0.908532 -0.310094 0.280022 + outer loop + vertex 682.387 163.652 80.0197 + vertex 683.573 167.319 80.2324 + vertex 681.972 164.101 81.8633 + endloop + endfacet + facet normal 0.904216 -0.309524 0.29426 + outer loop + vertex 682.387 163.652 80.0197 + vertex 684.004 166.858 78.4249 + vertex 683.573 167.319 80.2324 + endloop + endfacet + facet normal 0.904503 -0.310761 0.292065 + outer loop + vertex 682.809 163.174 78.2056 + vertex 684.004 166.858 78.4249 + vertex 682.387 163.652 80.0197 + endloop + endfacet + facet normal 0.899056 -0.310013 0.309176 + outer loop + vertex 682.809 163.174 78.2056 + vertex 684.453 166.372 76.6308 + vertex 684.004 166.858 78.4249 + endloop + endfacet + facet normal 0.899172 -0.310459 0.308391 + outer loop + vertex 683.253 162.671 76.4044 + vertex 684.453 166.372 76.6308 + vertex 682.809 163.174 78.2056 + endloop + endfacet + facet normal 0.893202 -0.309606 0.326089 + outer loop + vertex 683.253 162.671 76.4044 + vertex 684.941 165.886 74.8319 + vertex 684.453 166.372 76.6308 + endloop + endfacet + facet normal 0.893208 -0.309628 0.326051 + outer loop + vertex 683.739 162.171 74.5972 + vertex 684.941 165.886 74.8319 + vertex 683.253 162.671 76.4044 + endloop + endfacet + facet normal 0.886494 -0.308638 0.344777 + outer loop + vertex 683.739 162.171 74.5972 + vertex 685.483 165.412 73.0159 + vertex 684.941 165.886 74.8319 + endloop + endfacet + facet normal 0.886841 -0.309749 0.342883 + outer loop + vertex 684.277 161.689 72.7703 + vertex 685.483 165.412 73.0159 + vertex 683.739 162.171 74.5972 + endloop + endfacet + facet normal 0.877563 -0.308346 0.36716 + outer loop + vertex 684.277 161.689 72.7703 + vertex 686.085 164.944 71.1836 + vertex 685.483 165.412 73.0159 + endloop + endfacet + facet normal 0.877859 -0.309213 0.36572 + outer loop + vertex 684.877 161.208 70.9227 + vertex 686.085 164.944 71.1836 + vertex 684.277 161.689 72.7703 + endloop + endfacet + facet normal 0.869692 -0.307971 0.385734 + outer loop + vertex 684.877 161.208 70.9227 + vertex 686.735 164.495 69.3587 + vertex 686.085 164.944 71.1836 + endloop + endfacet + facet normal 0.869563 -0.307631 0.386294 + outer loop + vertex 685.531 160.736 69.0749 + vertex 686.735 164.495 69.3587 + vertex 684.877 161.208 70.9227 + endloop + endfacet + facet normal 0.85949 -0.306146 0.40933 + outer loop + vertex 685.531 160.736 69.0749 + vertex 687.43 164.058 67.5733 + vertex 686.735 164.495 69.3587 + endloop + endfacet + facet normal 0.86007 -0.307483 0.407104 + outer loop + vertex 686.228 160.286 67.2635 + vertex 687.43 164.058 67.5733 + vertex 685.531 160.736 69.0749 + endloop + endfacet + facet normal 0.849275 -0.305946 0.430267 + outer loop + vertex 686.228 160.286 67.2635 + vertex 688.151 163.659 65.8664 + vertex 687.43 164.058 67.5733 + endloop + endfacet + facet normal 0.850253 -0.30788 0.426943 + outer loop + vertex 686.95 159.877 65.5304 + vertex 688.151 163.659 65.8664 + vertex 686.228 160.286 67.2635 + endloop + endfacet + facet normal 0.83857 -0.306269 0.450555 + outer loop + vertex 686.95 159.877 65.5304 + vertex 688.889 163.308 64.2542 + vertex 688.151 163.659 65.8664 + endloop + endfacet + facet normal 0.83796 -0.305245 0.452381 + outer loop + vertex 687.7 159.498 63.8865 + vertex 688.889 163.308 64.2542 + vertex 686.95 159.877 65.5304 + endloop + endfacet + facet normal 0.82684 -0.303795 0.473333 + outer loop + vertex 687.7 159.498 63.8865 + vertex 689.655 163 62.7176 + vertex 688.889 163.308 64.2542 + endloop + endfacet + facet normal 0.826621 -0.303477 0.473919 + outer loop + vertex 688.474 159.166 62.3228 + vertex 689.655 163 62.7176 + vertex 687.7 159.498 63.8865 + endloop + endfacet + facet normal 0.811869 -0.301608 0.499902 + outer loop + vertex 688.474 159.166 62.3228 + vertex 690.473 162.714 61.2173 + vertex 689.655 163 62.7176 + endloop + endfacet + facet normal 0.811432 -0.301034 0.500955 + outer loop + vertex 689.301 158.855 60.7966 + vertex 690.473 162.714 61.2173 + vertex 688.474 159.166 62.3228 + endloop + endfacet + facet normal 0.795919 -0.299093 0.526361 + outer loop + vertex 689.301 158.855 60.7966 + vertex 691.359 162.441 59.7216 + vertex 690.473 162.714 61.2173 + endloop + endfacet + facet normal 0.796446 -0.299746 0.525192 + outer loop + vertex 690.196 158.568 59.2749 + vertex 691.359 162.441 59.7216 + vertex 689.301 158.855 60.7966 + endloop + endfacet + facet normal 0.779036 -0.297592 0.551853 + outer loop + vertex 690.196 158.568 59.2749 + vertex 692.326 162.196 58.225 + vertex 691.359 162.441 59.7216 + endloop + endfacet + facet normal 0.779779 -0.298469 0.550328 + outer loop + vertex 691.175 158.311 57.7489 + vertex 692.326 162.196 58.225 + vertex 690.196 158.568 59.2749 + endloop + endfacet + facet normal 0.759681 -0.29603 0.579009 + outer loop + vertex 691.175 158.311 57.7489 + vertex 693.375 162.007 56.7521 + vertex 692.326 162.196 58.225 + endloop + endfacet + facet normal 0.760501 -0.296933 0.577468 + outer loop + vertex 692.236 158.105 56.2455 + vertex 693.375 162.007 56.7521 + vertex 691.175 158.311 57.7489 + endloop + endfacet + facet normal 0.73916 -0.294383 0.605789 + outer loop + vertex 692.236 158.105 56.2455 + vertex 694.48 161.894 55.3484 + vertex 693.375 162.007 56.7521 + endloop + endfacet + facet normal 0.739117 -0.29434 0.605862 + outer loop + vertex 693.353 157.963 54.8144 + vertex 694.48 161.894 55.3484 + vertex 692.236 158.105 56.2455 + endloop + endfacet + facet normal 0.71446 -0.291375 0.636119 + outer loop + vertex 693.353 157.963 54.8144 + vertex 695.586 161.795 54.0607 + vertex 694.48 161.894 55.3484 + endloop + endfacet + facet normal 0.714931 -0.291792 0.635398 + outer loop + vertex 694.479 157.876 53.5071 + vertex 695.586 161.795 54.0607 + vertex 693.353 157.963 54.8144 + endloop + endfacet + facet normal 0.684543 -0.288044 0.66965 + outer loop + vertex 694.479 157.876 53.5071 + vertex 696.623 161.642 52.9352 + vertex 695.586 161.795 54.0607 + endloop + endfacet + facet normal 0.68742 -0.290277 0.665728 + outer loop + vertex 695.595 157.853 52.3447 + vertex 696.623 161.642 52.9352 + vertex 694.479 157.876 53.5071 + endloop + endfacet + facet normal 0.673664 -0.28881 0.680269 + outer loop + vertex 695.595 157.853 52.3447 + vertex 697.635 161.773 51.989 + vertex 696.623 161.642 52.9352 + endloop + endfacet + facet normal 0.661394 -0.281053 0.69539 + outer loop + vertex 696.672 157.882 51.3316 + vertex 697.635 161.773 51.989 + vertex 695.595 157.853 52.3447 + endloop + endfacet + facet normal 0.662652 -0.281154 0.69415 + outer loop + vertex 696.672 157.882 51.3316 + vertex 698.565 162.021 51.2016 + vertex 697.635 161.773 51.989 + endloop + endfacet + facet normal 0.638407 -0.269224 0.721079 + outer loop + vertex 697.615 157.906 50.5063 + vertex 698.565 162.021 51.2016 + vertex 696.672 157.882 51.3316 + endloop + endfacet + facet normal 0.648067 -0.269944 0.712138 + outer loop + vertex 697.615 157.906 50.5063 + vertex 699.274 162.197 50.6232 + vertex 698.565 162.021 51.2016 + endloop + endfacet + facet normal 0.614696 -0.257948 0.745394 + outer loop + vertex 698.314 157.901 49.9276 + vertex 699.274 162.197 50.6232 + vertex 697.615 157.906 50.5063 + endloop + endfacet + facet normal 0.61735 -0.258172 0.743119 + outer loop + vertex 698.314 157.901 49.9276 + vertex 699.701 162.201 50.2694 + vertex 699.274 162.197 50.6232 + endloop + endfacet + facet normal 0.594077 -0.252312 0.763814 + outer loop + vertex 698.712 157.867 49.6073 + vertex 699.701 162.201 50.2694 + vertex 698.314 157.901 49.9276 + endloop + endfacet + facet normal 0.66117 -0.258534 0.704283 + outer loop + vertex 698.712 157.867 49.6073 + vertex 699.849 162.183 50.1244 + vertex 699.701 162.201 50.2694 + endloop + endfacet + facet normal 0.605026 -0.249935 0.75596 + outer loop + vertex 698.846 157.813 49.4818 + vertex 699.849 162.183 50.1244 + vertex 698.712 157.867 49.6073 + endloop + endfacet + facet normal 0.964326 -0.194839 -0.179202 + outer loop + vertex 698.846 157.813 49.4818 + vertex 699.857 162.24 50.1062 + vertex 699.849 162.183 50.1244 + endloop + endfacet + facet normal 0.936994 -0.170902 -0.304687 + outer loop + vertex 698.844 157.846 49.4577 + vertex 699.857 162.24 50.1062 + vertex 698.846 157.813 49.4818 + endloop + endfacet + facet normal 0.329733 0.0630434 -0.941967 + outer loop + vertex 698.844 157.846 49.4577 + vertex 699.87 162.468 50.126 + vertex 699.857 162.24 50.1062 + endloop + endfacet + facet normal 0.762258 -0.0761936 -0.642773 + outer loop + vertex 698.863 158.027 49.458 + vertex 699.87 162.468 50.126 + vertex 698.844 157.846 49.4577 + endloop + endfacet + facet normal 0.692878 -0.258405 0.673162 + outer loop + vertex 698.863 158.027 49.458 + vertex 699.957 162.693 50.1232 + vertex 699.87 162.468 50.126 + endloop + endfacet + facet normal 0.443192 -0.227503 0.867077 + outer loop + vertex 698.951 158.171 49.4509 + vertex 699.957 162.693 50.1232 + vertex 698.863 158.027 49.458 + endloop + endfacet + facet normal 0.00682179 -0.148526 0.988885 + outer loop + vertex 698.951 158.171 49.4509 + vertex 699.981 162.068 50.029 + vertex 699.957 162.693 50.1232 + endloop + endfacet + facet normal 0.204871 -0.19646 0.95887 + outer loop + vertex 699.063 158.157 49.424 + vertex 699.981 162.068 50.029 + vertex 698.951 158.171 49.4509 + endloop + endfacet + facet normal -0.033931 -0.145007 0.988849 + outer loop + vertex 699.063 158.157 49.424 + vertex 699.898 161.077 49.8809 + vertex 699.981 162.068 50.029 + endloop + endfacet + facet normal 0.529186 -0.27682 0.802081 + outer loop + vertex 699.121 158.05 49.3489 + vertex 699.898 161.077 49.8809 + vertex 699.063 158.157 49.424 + endloop + endfacet + facet normal 0.962841 -0.260043 0.0728986 + outer loop + vertex 699.898 161.077 49.8809 + vertex 699.121 158.05 49.3489 + vertex 700.051 161.648 49.893 + endloop + endfacet + facet normal 0.722686 -0.197557 -0.662342 + outer loop + vertex 696.748 162.033 290.678 + vertex 696.603 166.393 289.219 + vertex 697.779 166.717 290.405 + endloop + endfacet + facet normal 0.722533 -0.157206 -0.673225 + outer loop + vertex 696.603 166.393 289.219 + vertex 697.502 171.417 289.011 + vertex 697.779 166.717 290.405 + endloop + endfacet + facet normal 0.763063 -0.142144 -0.6305 + outer loop + vertex 697.779 166.717 290.405 + vertex 697.502 171.417 289.011 + vertex 698.849 173.176 290.244 + endloop + endfacet + facet normal 0.747144 -0.160438 -0.645008 + outer loop + vertex 696.603 166.393 289.219 + vertex 696.316 170.962 287.75 + vertex 697.502 171.417 289.011 + endloop + endfacet + facet normal 0.744495 -0.121999 -0.656386 + outer loop + vertex 696.316 170.962 287.75 + vertex 697.025 176.293 287.563 + vertex 697.502 171.417 289.011 + endloop + endfacet + facet normal 0.749158 -0.120067 -0.651418 + outer loop + vertex 697.502 171.417 289.011 + vertex 697.025 176.293 287.563 + vertex 697.957 175.69 288.747 + endloop + endfacet + facet normal 0.762813 -0.0798411 -0.641671 + outer loop + vertex 697.957 175.69 288.747 + vertex 697.025 176.293 287.563 + vertex 697.99 182.227 287.971 + endloop + endfacet + facet normal 0.78467 -0.0853007 -0.614017 + outer loop + vertex 695.977 182.579 285.351 + vertex 697.99 182.227 287.971 + vertex 697.025 176.293 287.563 + endloop + endfacet + facet normal 0.767011 -0.0954485 -0.634494 + outer loop + vertex 695.93 175.326 286.385 + vertex 695.977 182.579 285.351 + vertex 697.025 176.293 287.563 + endloop + endfacet + facet normal 0.800726 -0.0896464 -0.592284 + outer loop + vertex 695.93 175.326 286.385 + vertex 694.911 176.341 284.854 + vertex 695.977 182.579 285.351 + endloop + endfacet + facet normal 0.819373 -0.0949801 -0.565337 + outer loop + vertex 694.04 183.086 282.458 + vertex 695.977 182.579 285.351 + vertex 694.911 176.341 284.854 + endloop + endfacet + facet normal 0.817557 -0.0960811 -0.567776 + outer loop + vertex 693.912 175.608 283.539 + vertex 694.04 183.086 282.458 + vertex 694.911 176.341 284.854 + endloop + endfacet + facet normal 0.822623 -0.127479 -0.554112 + outer loop + vertex 694.178 170.976 285 + vertex 693.912 175.608 283.539 + vertex 694.911 176.341 284.854 + endloop + endfacet + facet normal 0.797248 -0.125001 -0.590568 + outer loop + vertex 694.178 170.976 285 + vertex 694.911 176.341 284.854 + vertex 695.204 170.878 286.406 + endloop + endfacet + facet normal 0.790452 -0.169169 -0.5887 + outer loop + vertex 694.364 166.236 286.611 + vertex 694.178 170.976 285 + vertex 695.204 170.878 286.406 + endloop + endfacet + facet normal 0.82124 -0.128155 -0.556005 + outer loop + vertex 693.222 171.19 283.538 + vertex 693.912 175.608 283.539 + vertex 694.178 170.976 285 + endloop + endfacet + facet normal 0.849446 -0.0897121 -0.519994 + outer loop + vertex 693.912 175.608 283.539 + vertex 693.036 176.83 281.898 + vertex 694.04 183.086 282.458 + endloop + endfacet + facet normal 0.825232 -0.0544992 -0.562159 + outer loop + vertex 694.04 183.086 282.458 + vertex 694.728 192.707 282.535 + vertex 695.977 182.579 285.351 + endloop + endfacet + facet normal 0.822551 -0.0558811 -0.56594 + outer loop + vertex 695.977 182.579 285.351 + vertex 694.728 192.707 282.535 + vertex 696.66 192.253 285.389 + endloop + endfacet + facet normal 0.825863 -0.0252316 -0.563306 + outer loop + vertex 694.728 192.707 282.535 + vertex 695.043 201.838 282.588 + vertex 696.66 192.253 285.389 + endloop + endfacet + facet normal 0.824876 -0.0258124 -0.564723 + outer loop + vertex 696.66 192.253 285.389 + vertex 695.043 201.838 282.588 + vertex 696.967 201.778 285.401 + endloop + endfacet + facet normal 0.825361 -0.00411701 -0.564591 + outer loop + vertex 695.043 201.838 282.588 + vertex 695.065 210.646 282.556 + vertex 696.967 201.778 285.401 + endloop + endfacet + facet normal 0.827495 -0.00265694 -0.561466 + outer loop + vertex 696.967 201.778 285.401 + vertex 695.065 210.646 282.556 + vertex 696.942 210.909 285.322 + endloop + endfacet + facet normal 0.827124 0.00551415 -0.561992 + outer loop + vertex 695.065 210.646 282.556 + vertex 694.962 219.345 282.49 + vertex 696.942 210.909 285.322 + endloop + endfacet + facet normal 0.829942 0.00758385 -0.557798 + outer loop + vertex 696.942 210.909 285.322 + vertex 694.962 219.345 282.49 + vertex 696.839 219.67 285.287 + endloop + endfacet + facet normal 0.829949 0.00747928 -0.55779 + outer loop + vertex 694.962 219.345 282.49 + vertex 694.87 228.004 282.469 + vertex 696.839 219.67 285.287 + endloop + endfacet + facet normal 0.83211 0.00908962 -0.554536 + outer loop + vertex 696.839 219.67 285.287 + vertex 694.87 228.004 282.469 + vertex 696.744 228.429 285.288 + endloop + endfacet + facet normal 0.832588 0.00266369 -0.553886 + outer loop + vertex 694.87 228.004 282.469 + vertex 694.835 236.683 282.459 + vertex 696.744 228.429 285.288 + endloop + endfacet + facet normal 0.836997 0.00598449 -0.547174 + outer loop + vertex 696.744 228.429 285.288 + vertex 694.835 236.683 282.459 + vertex 696.696 237.188 285.31 + endloop + endfacet + facet normal 0.837606 -0.00133098 -0.546274 + outer loop + vertex 694.835 236.683 282.459 + vertex 694.842 245.366 282.448 + vertex 696.696 237.188 285.31 + endloop + endfacet + facet normal 0.841545 0.00169279 -0.540185 + outer loop + vertex 696.696 237.188 285.31 + vertex 694.842 245.366 282.448 + vertex 696.706 245.897 285.354 + endloop + endfacet + facet normal 0.842205 -0.00645585 -0.539119 + outer loop + vertex 694.842 245.366 282.448 + vertex 694.907 254.119 282.445 + vertex 696.706 245.897 285.354 + endloop + endfacet + facet normal 0.847861 -0.00206675 -0.530215 + outer loop + vertex 696.706 245.897 285.354 + vertex 694.907 254.119 282.445 + vertex 696.754 254.667 285.396 + endloop + endfacet + facet normal 0.848391 -0.00879051 -0.529298 + outer loop + vertex 694.907 254.119 282.445 + vertex 695.023 262.917 282.484 + vertex 696.754 254.667 285.396 + endloop + endfacet + facet normal 0.852071 -0.00593405 -0.523393 + outer loop + vertex 696.754 254.667 285.396 + vertex 695.023 262.917 282.484 + vertex 696.838 263.494 285.433 + endloop + endfacet + facet normal 0.85247 -0.0109214 -0.522662 + outer loop + vertex 695.023 262.917 282.484 + vertex 695.175 271.702 282.549 + vertex 696.838 263.494 285.433 + endloop + endfacet + facet normal 0.855768 -0.00836655 -0.517293 + outer loop + vertex 696.838 263.494 285.433 + vertex 695.175 271.702 282.549 + vertex 696.943 272.336 285.464 + endloop + endfacet + facet normal 0.85627 -0.0141748 -0.516334 + outer loop + vertex 695.175 271.702 282.549 + vertex 695.337 280.45 282.576 + vertex 696.943 272.336 285.464 + endloop + endfacet + facet normal 0.860283 -0.0110187 -0.509697 + outer loop + vertex 696.943 272.336 285.464 + vertex 695.337 280.45 282.576 + vertex 697.056 281.156 285.464 + endloop + endfacet + facet normal 0.860861 -0.017114 -0.508552 + outer loop + vertex 695.337 280.45 282.576 + vertex 695.492 289.208 282.546 + vertex 697.056 281.156 285.464 + endloop + endfacet + facet normal 0.865153 -0.0136602 -0.501322 + outer loop + vertex 697.056 281.156 285.464 + vertex 695.492 289.208 282.546 + vertex 697.168 290.055 285.414 + endloop + endfacet + facet normal 0.865791 -0.0192833 -0.500034 + outer loop + vertex 695.492 289.208 282.546 + vertex 695.671 298.113 282.512 + vertex 697.168 290.055 285.414 + endloop + endfacet + facet normal 0.871292 -0.014841 -0.49054 + outer loop + vertex 697.168 290.055 285.414 + vertex 695.671 298.113 282.512 + vertex 697.312 298.869 285.404 + endloop + endfacet + facet normal 0.871705 -0.0191066 -0.489659 + outer loop + vertex 695.671 298.113 282.512 + vertex 695.965 306.74 282.698 + vertex 697.312 298.869 285.404 + endloop + endfacet + facet normal 0.876336 -0.0154921 -0.481452 + outer loop + vertex 697.312 298.869 285.404 + vertex 695.965 306.74 282.698 + vertex 697.496 307.235 285.469 + endloop + endfacet + facet normal 0.876425 -0.016949 -0.48124 + outer loop + vertex 695.965 306.74 282.698 + vertex 696.386 313.362 283.232 + vertex 697.496 307.235 285.469 + endloop + endfacet + facet normal 0.874866 -0.0182459 -0.484021 + outer loop + vertex 697.496 307.235 285.469 + vertex 696.386 313.362 283.232 + vertex 697.623 315.334 285.392 + endloop + endfacet + facet normal 0.881179 -0.0360203 -0.471409 + outer loop + vertex 696.386 313.362 283.232 + vertex 696.236 321.678 282.315 + vertex 697.623 315.334 285.392 + endloop + endfacet + facet normal 0.896298 -0.0189614 -0.443047 + outer loop + vertex 697.623 315.334 285.392 + vertex 696.236 321.678 282.315 + vertex 697.735 323.493 285.27 + endloop + endfacet + facet normal 0.898227 -0.0277006 -0.438658 + outer loop + vertex 696.236 321.678 282.315 + vertex 696.52 329.62 282.396 + vertex 697.735 323.493 285.27 + endloop + endfacet + facet normal 0.904299 -0.0207445 -0.426395 + outer loop + vertex 697.735 323.493 285.27 + vertex 696.52 329.62 282.396 + vertex 697.896 332.154 285.191 + endloop + endfacet + facet normal 0.909195 -0.0362026 -0.414794 + outer loop + vertex 696.52 329.62 282.396 + vertex 696.478 339.844 281.411 + vertex 697.896 332.154 285.191 + endloop + endfacet + facet normal 0.91812 -0.0250754 -0.395508 + outer loop + vertex 697.896 332.154 285.191 + vertex 696.478 339.844 281.411 + vertex 698.193 342.331 285.236 + endloop + endfacet + facet normal 0.920378 -0.036082 -0.389362 + outer loop + vertex 696.478 339.844 281.411 + vertex 697.003 353.58 281.379 + vertex 698.193 342.331 285.236 + endloop + endfacet + facet normal 0.923787 -0.0330187 -0.38148 + outer loop + vertex 698.193 342.331 285.236 + vertex 697.003 353.58 281.379 + vertex 698.817 354.061 285.73 + endloop + endfacet + facet normal 0.923819 -0.0459314 -0.380065 + outer loop + vertex 697.003 353.58 281.379 + vertex 698.001 368.853 281.959 + vertex 698.817 354.061 285.73 + endloop + endfacet + facet normal 0.923852 -0.0459099 -0.379987 + outer loop + vertex 698.001 368.853 281.959 + vertex 700.024 366.703 287.137 + vertex 698.817 354.061 285.73 + endloop + endfacet + facet normal 0.922739 -0.0516755 -0.381946 + outer loop + vertex 700.024 366.703 287.137 + vertex 698.001 368.853 281.959 + vertex 699.392 386.649 282.913 + endloop + endfacet + facet normal 0.928758 -0.0484274 -0.367508 + outer loop + vertex 699.392 386.649 282.913 + vertex 701.505 386.658 288.252 + vertex 700.024 366.703 287.137 + endloop + endfacet + facet normal 0.783228 -0.130663 -0.607849 + outer loop + vertex 695.204 170.878 286.406 + vertex 694.911 176.341 284.854 + vertex 695.93 175.326 286.385 + endloop + endfacet + facet normal 0.768074 -0.128281 -0.62738 + outer loop + vertex 695.204 170.878 286.406 + vertex 695.93 175.326 286.385 + vertex 696.316 170.962 287.75 + endloop + endfacet + facet normal 0.764794 -0.167109 -0.622226 + outer loop + vertex 695.444 166.215 287.953 + vertex 695.204 170.878 286.406 + vertex 696.316 170.962 287.75 + endloop + endfacet + facet normal 0.788529 -0.0532956 -0.612684 + outer loop + vertex 695.977 182.579 285.351 + vertex 696.66 192.253 285.389 + vertex 697.99 182.227 287.971 + endloop + endfacet + facet normal 0.789726 -0.0527517 -0.611188 + outer loop + vertex 697.99 182.227 287.971 + vertex 696.66 192.253 285.389 + vertex 698.648 192.755 287.914 + endloop + endfacet + facet normal 0.787878 -0.0245575 -0.615341 + outer loop + vertex 696.66 192.253 285.389 + vertex 696.967 201.778 285.401 + vertex 698.648 192.755 287.914 + endloop + endfacet + facet normal 0.792168 -0.0222421 -0.609897 + outer loop + vertex 698.648 192.755 287.914 + vertex 696.967 201.778 285.401 + vertex 698.929 203.234 287.896 + endloop + endfacet + facet normal 0.787013 -0.00324697 -0.616928 + outer loop + vertex 696.967 201.778 285.401 + vertex 696.942 210.909 285.322 + vertex 698.929 203.234 287.896 + endloop + endfacet + facet normal 0.793615 0.00131574 -0.608419 + outer loop + vertex 698.929 203.234 287.896 + vertex 696.942 210.909 285.322 + vertex 698.61 212.334 287.5 + endloop + endfacet + facet normal 0.791822 0.0069209 -0.610712 + outer loop + vertex 696.942 210.909 285.322 + vertex 696.839 219.67 285.287 + vertex 698.61 212.334 287.5 + endloop + endfacet + facet normal 0.792842 0.00756904 -0.60938 + outer loop + vertex 698.61 212.334 287.5 + vertex 696.839 219.67 285.287 + vertex 698.778 220.787 287.823 + endloop + endfacet + facet normal 0.792599 0.00867392 -0.609681 + outer loop + vertex 696.839 219.67 285.287 + vertex 696.744 228.429 285.288 + vertex 698.778 220.787 287.823 + endloop + endfacet + facet normal 0.799429 0.0135003 -0.600609 + outer loop + vertex 698.778 220.787 287.823 + vertex 696.744 228.429 285.288 + vertex 698.35 230.15 287.464 + endloop + endfacet + facet normal 0.802379 0.00591416 -0.596785 + outer loop + vertex 696.744 228.429 285.288 + vertex 696.696 237.188 285.31 + vertex 698.35 230.15 287.464 + endloop + endfacet + facet normal 0.801238 0.00517523 -0.598323 + outer loop + vertex 698.35 230.15 287.464 + vertex 696.696 237.188 285.31 + vertex 698.583 238.681 287.851 + endloop + endfacet + facet normal 0.802133 0.00203203 -0.597141 + outer loop + vertex 696.696 237.188 285.31 + vertex 696.706 245.897 285.354 + vertex 698.583 238.681 287.851 + endloop + endfacet + facet normal 0.808953 0.00702681 -0.587832 + outer loop + vertex 698.583 238.681 287.851 + vertex 696.706 245.897 285.354 + vertex 698.295 247.839 287.563 + endloop + endfacet + facet normal 0.812586 -0.00162525 -0.582839 + outer loop + vertex 696.706 245.897 285.354 + vertex 696.754 254.667 285.396 + vertex 698.295 247.839 287.563 + endloop + endfacet + facet normal 0.811837 -0.00212437 -0.58388 + outer loop + vertex 698.295 247.839 287.563 + vertex 696.754 254.667 285.396 + vertex 698.566 256.573 287.909 + endloop + endfacet + facet normal 0.81297 -0.00531003 -0.582281 + outer loop + vertex 696.754 254.667 285.396 + vertex 696.838 263.494 285.433 + vertex 698.566 256.573 287.909 + endloop + endfacet + facet normal 0.819657 -0.000268656 -0.572854 + outer loop + vertex 698.566 256.573 287.909 + vertex 696.838 263.494 285.433 + vertex 698.343 265.767 287.584 + endloop + endfacet + facet normal 0.823355 -0.00781005 -0.567472 + outer loop + vertex 696.838 263.494 285.433 + vertex 696.943 272.336 285.464 + vertex 698.343 265.767 287.584 + endloop + endfacet + facet normal 0.822194 -0.00859638 -0.569142 + outer loop + vertex 698.343 265.767 287.584 + vertex 696.943 272.336 285.464 + vertex 698.655 274.545 287.903 + endloop + endfacet + facet normal 0.822998 -0.01054 -0.567946 + outer loop + vertex 696.943 272.336 285.464 + vertex 697.056 281.156 285.464 + vertex 698.655 274.545 287.903 + endloop + endfacet + facet normal 0.827931 -0.00670617 -0.56079 + outer loop + vertex 698.655 274.545 287.903 + vertex 697.056 281.156 285.464 + vertex 698.496 283.616 287.56 + endloop + endfacet + facet normal 0.831562 -0.0135366 -0.555266 + outer loop + vertex 697.056 281.156 285.464 + vertex 697.168 290.055 285.414 + vertex 698.496 283.616 287.56 + endloop + endfacet + facet normal 0.832554 -0.0128419 -0.553795 + outer loop + vertex 698.496 283.616 287.56 + vertex 697.168 290.055 285.414 + vertex 698.838 292.365 287.871 + endloop + endfacet + facet normal 0.833162 -0.0142913 -0.552845 + outer loop + vertex 697.168 290.055 285.414 + vertex 697.312 298.869 285.404 + vertex 698.838 292.365 287.871 + endloop + endfacet + facet normal 0.838979 -0.0096019 -0.544079 + outer loop + vertex 698.838 292.365 287.871 + vertex 697.312 298.869 285.404 + vertex 698.718 301.298 287.529 + endloop + endfacet + facet normal 0.841347 -0.0142711 -0.540308 + outer loop + vertex 697.312 298.869 285.404 + vertex 697.496 307.235 285.469 + vertex 698.718 301.298 287.529 + endloop + endfacet + facet normal 0.842321 -0.0135493 -0.538806 + outer loop + vertex 698.718 301.298 287.529 + vertex 697.496 307.235 285.469 + vertex 699.064 309.542 287.862 + endloop + endfacet + facet normal 0.844296 -0.0182522 -0.535566 + outer loop + vertex 697.496 307.235 285.469 + vertex 697.623 315.334 285.392 + vertex 699.064 309.542 287.862 + endloop + endfacet + facet normal 0.853046 -0.0101768 -0.521736 + outer loop + vertex 699.064 309.542 287.862 + vertex 697.623 315.334 285.392 + vertex 698.937 317.97 287.49 + endloop + endfacet + facet normal 0.858062 -0.0194878 -0.513177 + outer loop + vertex 697.623 315.334 285.392 + vertex 697.735 323.493 285.27 + vertex 698.937 317.97 287.49 + endloop + endfacet + facet normal 0.863914 -0.0143001 -0.503436 + outer loop + vertex 698.937 317.97 287.49 + vertex 697.735 323.493 285.27 + vertex 699.299 325.989 287.883 + endloop + endfacet + facet normal 0.866445 -0.0206955 -0.498844 + outer loop + vertex 697.735 323.493 285.27 + vertex 697.896 332.154 285.191 + vertex 699.299 325.989 287.883 + endloop + endfacet + facet normal 0.8765 -0.0107402 -0.481282 + outer loop + vertex 699.299 325.989 287.883 + vertex 697.896 332.154 285.191 + vertex 699.271 334.921 287.633 + endloop + endfacet + facet normal 0.882396 -0.0237085 -0.469909 + outer loop + vertex 697.896 332.154 285.191 + vertex 698.193 342.331 285.236 + vertex 699.271 334.921 287.633 + endloop + endfacet + facet normal 0.886496 -0.0206421 -0.462275 + outer loop + vertex 699.271 334.921 287.633 + vertex 698.193 342.331 285.236 + vertex 699.808 344.159 288.251 + endloop + endfacet + facet normal 0.888121 -0.0278686 -0.458764 + outer loop + vertex 698.193 342.331 285.236 + vertex 698.817 354.061 285.73 + vertex 699.808 344.159 288.251 + endloop + endfacet + facet normal 0.900221 -0.0205924 -0.434947 + outer loop + vertex 699.808 344.159 288.251 + vertex 698.817 354.061 285.73 + vertex 700.023 353.394 288.259 + endloop + endfacet + facet normal 0.898093 -0.0369642 -0.43825 + outer loop + vertex 700.023 353.394 288.259 + vertex 698.817 354.061 285.73 + vertex 700.024 366.703 287.137 + endloop + endfacet + facet normal 0.775796 -0.124825 -0.618514 + outer loop + vertex 696.316 170.962 287.75 + vertex 695.93 175.326 286.385 + vertex 697.025 176.293 287.563 + endloop + endfacet + facet normal 0.738969 -0.163697 -0.65355 + outer loop + vertex 695.444 166.215 287.953 + vertex 696.316 170.962 287.75 + vertex 696.603 166.393 289.219 + endloop + endfacet + facet normal 0.766788 -0.166266 -0.619993 + outer loop + vertex 694.364 166.236 286.611 + vertex 695.204 170.878 286.406 + vertex 695.444 166.215 287.953 + endloop + endfacet + facet normal 0.793748 -0.167673 -0.584679 + outer loop + vertex 693.356 166.399 285.196 + vertex 694.178 170.976 285 + vertex 694.364 166.236 286.611 + endloop + endfacet + facet normal 0.802073 -0.222045 -0.554414 + outer loop + vertex 691.44 162.454 283.994 + vertex 692.399 166.62 283.713 + vertex 692.418 162.208 285.508 + endloop + endfacet + facet normal 0.820202 -0.224319 -0.526261 + outer loop + vertex 691.44 162.454 283.994 + vertex 691.48 166.874 282.172 + vertex 692.399 166.62 283.713 + endloop + endfacet + facet normal 0.819249 -0.224831 -0.527524 + outer loop + vertex 690.503 162.726 282.422 + vertex 691.48 166.874 282.172 + vertex 691.44 162.454 283.994 + endloop + endfacet + facet normal 0.835627 -0.227038 -0.50018 + outer loop + vertex 690.503 162.726 282.422 + vertex 690.604 167.163 280.578 + vertex 691.48 166.874 282.172 + endloop + endfacet + facet normal 0.849754 -0.17265 -0.498107 + outer loop + vertex 690.604 167.163 280.578 + vertex 691.454 171.722 280.448 + vertex 691.48 166.874 282.172 + endloop + endfacet + facet normal 0.850285 -0.172361 -0.4973 + outer loop + vertex 691.48 166.874 282.172 + vertex 691.454 171.722 280.448 + vertex 692.317 171.438 282.021 + endloop + endfacet + facet normal 0.865198 -0.17473 -0.470001 + outer loop + vertex 690.604 167.163 280.578 + vertex 690.635 172.043 278.821 + vertex 691.454 171.722 280.448 + endloop + endfacet + facet normal 0.875849 -0.126184 -0.465796 + outer loop + vertex 690.635 172.043 278.821 + vertex 691.37 177.475 278.731 + vertex 691.454 171.722 280.448 + endloop + endfacet + facet normal 0.868558 -0.130004 -0.478232 + outer loop + vertex 691.454 171.722 280.448 + vertex 691.37 177.475 278.731 + vertex 692.143 176.184 280.486 + endloop + endfacet + facet normal 0.89364 -0.128 -0.430144 + outer loop + vertex 690.635 172.043 278.821 + vertex 690.556 176.875 277.218 + vertex 691.37 177.475 278.731 + endloop + endfacet + facet normal 0.888533 -0.131235 -0.439643 + outer loop + vertex 689.861 172.414 277.145 + vertex 690.556 176.875 277.218 + vertex 690.635 172.043 278.821 + endloop + endfacet + facet normal 0.878173 -0.176043 -0.444771 + outer loop + vertex 689.778 167.484 278.932 + vertex 689.861 172.414 277.145 + vertex 690.635 172.043 278.821 + endloop + endfacet + facet normal 0.878801 -0.175658 -0.443681 + outer loop + vertex 688.999 167.857 277.242 + vertex 689.861 172.414 277.145 + vertex 689.778 167.484 278.932 + endloop + endfacet + facet normal 0.891388 -0.177473 -0.417051 + outer loop + vertex 688.999 167.857 277.242 + vertex 689.135 172.805 275.426 + vertex 689.861 172.414 277.145 + endloop + endfacet + facet normal 0.902608 -0.128861 -0.410724 + outer loop + vertex 689.135 172.805 275.426 + vertex 689.883 178.192 275.381 + vertex 689.861 172.414 277.145 + endloop + endfacet + facet normal 0.918591 -0.130764 -0.372949 + outer loop + vertex 689.135 172.805 275.426 + vertex 689.156 177.618 273.791 + vertex 689.883 178.192 275.381 + endloop + endfacet + facet normal 0.913415 -0.134546 -0.384149 + outer loop + vertex 688.459 173.215 273.676 + vertex 689.156 177.618 273.791 + vertex 689.135 172.805 275.426 + endloop + endfacet + facet normal 0.903097 -0.178703 -0.390488 + outer loop + vertex 688.271 168.255 275.511 + vertex 688.459 173.215 273.676 + vertex 689.135 172.805 275.426 + endloop + endfacet + facet normal 0.903627 -0.178332 -0.38943 + outer loop + vertex 687.595 168.671 273.751 + vertex 688.459 173.215 273.676 + vertex 688.271 168.255 275.511 + endloop + endfacet + facet normal 0.913476 -0.1798 -0.365012 + outer loop + vertex 687.595 168.671 273.751 + vertex 687.833 173.629 271.905 + vertex 688.459 173.215 273.676 + endloop + endfacet + facet normal 0.924979 -0.129443 -0.357293 + outer loop + vertex 687.833 173.629 271.905 + vertex 688.587 178.979 271.919 + vertex 688.459 173.215 273.676 + endloop + endfacet + facet normal 0.936068 -0.131088 -0.326485 + outer loop + vertex 687.833 173.629 271.905 + vertex 687.945 178.457 270.288 + vertex 688.587 178.979 271.919 + endloop + endfacet + facet normal 0.93233 -0.134125 -0.335814 + outer loop + vertex 687.256 174.051 270.135 + vertex 687.945 178.457 270.288 + vertex 687.833 173.629 271.905 + endloop + endfacet + facet normal 0.921591 -0.180869 -0.343448 + outer loop + vertex 686.97 169.099 271.975 + vertex 687.256 174.051 270.135 + vertex 687.833 173.629 271.905 + endloop + endfacet + facet normal 0.921168 -0.181201 -0.344408 + outer loop + vertex 686.395 169.547 270.203 + vertex 687.256 174.051 270.135 + vertex 686.97 169.099 271.975 + endloop + endfacet + facet normal 0.929705 -0.182466 -0.31993 + outer loop + vertex 686.395 169.547 270.203 + vertex 686.729 174.458 268.372 + vertex 687.256 174.051 270.135 + endloop + endfacet + facet normal 0.941635 -0.128666 -0.311075 + outer loop + vertex 686.729 174.458 268.372 + vertex 687.478 179.825 268.419 + vertex 687.256 174.051 270.135 + endloop + endfacet + facet normal 0.95033 -0.13013 -0.282736 + outer loop + vertex 686.729 174.458 268.372 + vertex 686.918 179.27 266.791 + vertex 687.478 179.825 268.419 + endloop + endfacet + facet normal 0.94703 -0.133127 -0.292252 + outer loop + vertex 686.246 174.853 266.627 + vertex 686.918 179.27 266.791 + vertex 686.729 174.458 268.372 + endloop + endfacet + facet normal 0.935885 -0.183677 -0.300635 + outer loop + vertex 685.873 169.989 268.437 + vertex 686.246 174.853 266.627 + vertex 686.729 174.458 268.372 + endloop + endfacet + facet normal 0.935571 -0.183954 -0.301444 + outer loop + vertex 685.394 170.424 266.685 + vertex 686.246 174.853 266.627 + vertex 685.873 169.989 268.437 + endloop + endfacet + facet normal 0.941528 -0.184839 -0.281707 + outer loop + vertex 685.394 170.424 266.685 + vertex 685.802 175.223 264.9 + vertex 686.246 174.853 266.627 + endloop + endfacet + facet normal 0.953566 -0.12801 -0.272626 + outer loop + vertex 685.802 175.223 264.9 + vertex 686.539 180.6 264.952 + vertex 686.246 174.853 266.627 + endloop + endfacet + facet normal 0.961912 -0.129464 -0.240758 + outer loop + vertex 685.802 175.223 264.9 + vertex 686.054 179.975 263.35 + vertex 686.539 180.6 264.952 + endloop + endfacet + facet normal 0.956414 -0.135087 -0.258888 + outer loop + vertex 685.393 175.598 263.192 + vertex 686.054 179.975 263.35 + vertex 685.802 175.223 264.9 + endloop + endfacet + facet normal 0.945145 -0.187277 -0.267633 + outer loop + vertex 684.95 170.849 264.951 + vertex 685.393 175.598 263.192 + vertex 685.802 175.223 264.9 + endloop + endfacet + facet normal 0.944965 -0.187451 -0.268148 + outer loop + vertex 684.542 171.264 263.225 + vertex 685.393 175.598 263.192 + vertex 684.95 170.849 264.951 + endloop + endfacet + facet normal 0.949698 -0.188243 -0.250275 + outer loop + vertex 684.542 171.264 263.225 + vertex 685.021 176.015 261.468 + vertex 685.393 175.598 263.192 + endloop + endfacet + facet normal 0.962509 -0.128874 -0.238681 + outer loop + vertex 685.021 176.015 261.468 + vertex 685.751 181.356 261.528 + vertex 685.393 175.598 263.192 + endloop + endfacet + facet normal 0.969777 -0.130226 -0.206335 + outer loop + vertex 685.021 176.015 261.468 + vertex 685.336 180.885 259.875 + vertex 685.751 181.356 261.528 + endloop + endfacet + facet normal 0.965119 -0.135677 -0.223914 + outer loop + vertex 684.679 176.575 259.654 + vertex 685.336 180.885 259.875 + vertex 685.021 176.015 261.468 + endloop + endfacet + facet normal 0.9521 -0.191241 -0.238604 + outer loop + vertex 684.166 171.746 261.477 + vertex 684.679 176.575 259.654 + vertex 685.021 176.015 261.468 + endloop + endfacet + facet normal 0.952708 -0.190585 -0.236696 + outer loop + vertex 683.82 172.27 259.663 + vertex 684.679 176.575 259.654 + vertex 684.166 171.746 261.477 + endloop + endfacet + facet normal 0.954697 -0.190966 -0.228221 + outer loop + vertex 683.82 172.27 259.663 + vertex 684.32 177.196 257.632 + vertex 684.679 176.575 259.654 + endloop + endfacet + facet normal 0.968847 -0.128682 -0.211604 + outer loop + vertex 684.32 177.196 257.632 + vertex 685.099 182.788 257.8 + vertex 684.679 176.575 259.654 + endloop + endfacet + facet normal 0.971795 -0.129529 -0.197072 + outer loop + vertex 684.32 177.196 257.632 + vertex 684.635 183.353 255.14 + vertex 685.099 182.788 257.8 + endloop + endfacet + facet normal 0.969362 -0.13318 -0.206399 + outer loop + vertex 683.828 176.741 255.615 + vertex 684.635 183.353 255.14 + vertex 684.32 177.196 257.632 + endloop + endfacet + facet normal 0.963447 -0.185661 -0.193132 + outer loop + vertex 683.475 172.587 257.848 + vertex 683.828 176.741 255.615 + vertex 684.32 177.196 257.632 + endloop + endfacet + facet normal 0.959508 -0.192201 -0.20592 + outer loop + vertex 683.125 172.381 256.41 + vertex 683.828 176.741 255.615 + vertex 683.475 172.587 257.848 + endloop + endfacet + facet normal 0.958922 -0.192544 -0.208316 + outer loop + vertex 683.125 172.381 256.41 + vertex 683.057 174.092 254.515 + vertex 683.828 176.741 255.615 + endloop + endfacet + facet normal 0.953894 -0.176891 -0.24248 + outer loop + vertex 683.828 176.741 255.615 + vertex 683.057 174.092 254.515 + vertex 683.807 181.392 252.142 + endloop + endfacet + facet normal 0.966481 -0.163667 -0.197809 + outer loop + vertex 682.739 174.405 252.703 + vertex 683.807 181.392 252.142 + vertex 683.057 174.092 254.515 + endloop + endfacet + facet normal 0.974142 -0.161633 -0.157865 + outer loop + vertex 682.739 174.405 252.703 + vertex 682.658 175.941 250.633 + vertex 683.807 181.392 252.142 + endloop + endfacet + facet normal 0.973761 -0.160625 -0.161213 + outer loop + vertex 683.343 182.775 247.957 + vertex 683.807 181.392 252.142 + vertex 682.658 175.941 250.633 + endloop + endfacet + facet normal 0.973219 -0.161502 -0.163592 + outer loop + vertex 682.29 175.618 248.761 + vertex 683.343 182.775 247.957 + vertex 682.658 175.941 250.633 + endloop + endfacet + facet normal 0.978066 -0.15896 -0.134603 + outer loop + vertex 682.29 175.618 248.761 + vertex 682.241 176.999 246.775 + vertex 683.343 182.775 247.957 + endloop + endfacet + facet normal 0.977851 -0.158488 -0.136708 + outer loop + vertex 682.982 183.82 244.166 + vertex 683.343 182.775 247.957 + vertex 682.241 176.999 246.775 + endloop + endfacet + facet normal 0.975578 -0.162485 -0.147804 + outer loop + vertex 681.905 176.581 245.014 + vertex 682.982 183.82 244.166 + vertex 682.241 176.999 246.775 + endloop + endfacet + facet normal 0.980867 -0.159101 -0.112191 + outer loop + vertex 681.905 176.581 245.014 + vertex 681.904 177.956 243.06 + vertex 682.982 183.82 244.166 + endloop + endfacet + facet normal 0.980121 -0.157325 -0.120876 + outer loop + vertex 682.681 184.757 240.503 + vertex 682.982 183.82 244.166 + vertex 681.904 177.956 243.06 + endloop + endfacet + facet normal 0.977443 -0.162358 -0.135078 + outer loop + vertex 681.592 177.518 241.326 + vertex 682.681 184.757 240.503 + vertex 681.904 177.956 243.06 + endloop + endfacet + facet normal 0.982116 -0.159144 -0.100602 + outer loop + vertex 681.592 177.518 241.326 + vertex 681.615 178.861 239.422 + vertex 682.681 184.757 240.503 + endloop + endfacet + facet normal 0.981868 -0.158469 -0.104037 + outer loop + vertex 682.44 185.624 236.912 + vertex 682.681 184.757 240.503 + vertex 681.615 178.861 239.422 + endloop + endfacet + facet normal 0.979888 -0.162565 -0.115723 + outer loop + vertex 681.338 178.389 237.745 + vertex 682.44 185.624 236.912 + vertex 681.615 178.861 239.422 + endloop + endfacet + facet normal 0.98368 -0.159421 -0.0834145 + outer loop + vertex 681.338 178.389 237.745 + vertex 681.393 179.71 235.869 + vertex 682.44 185.624 236.912 + endloop + endfacet + facet normal 0.983162 -0.157785 -0.0921749 + outer loop + vertex 682.236 186.462 233.299 + vertex 682.44 185.624 236.912 + vertex 681.393 179.71 235.869 + endloop + endfacet + facet normal 0.98092 -0.162842 -0.106197 + outer loop + vertex 681.13 179.23 234.178 + vertex 682.236 186.462 233.299 + vertex 681.393 179.71 235.869 + endloop + endfacet + facet normal 0.984107 -0.159829 -0.0773798 + outer loop + vertex 681.13 179.23 234.178 + vertex 681.192 180.555 232.221 + vertex 682.236 186.462 233.299 + endloop + endfacet + facet normal 0.983993 -0.159382 -0.0797175 + outer loop + vertex 682.069 187.294 229.573 + vertex 682.236 186.462 233.299 + vertex 681.192 180.555 232.221 + endloop + endfacet + facet normal 0.98285 -0.162307 -0.0875375 + outer loop + vertex 680.955 180.081 230.442 + vertex 682.069 187.294 229.573 + vertex 681.192 180.555 232.221 + endloop + endfacet + facet normal 0.984834 -0.160116 -0.0668137 + outer loop + vertex 680.955 180.081 230.442 + vertex 681.032 181.399 228.419 + vertex 682.069 187.294 229.573 + endloop + endfacet + facet normal 0.984585 -0.158801 -0.0733065 + outer loop + vertex 681.916 188.107 225.759 + vertex 682.069 187.294 229.573 + vertex 681.032 181.399 228.419 + endloop + endfacet + facet normal 0.983634 -0.16138 -0.0801261 + outer loop + vertex 680.804 180.912 226.605 + vertex 681.916 188.107 225.759 + vertex 681.032 181.399 228.419 + endloop + endfacet + facet normal 0.985651 -0.15895 -0.0568129 + outer loop + vertex 680.804 180.912 226.605 + vertex 680.897 182.202 224.596 + vertex 681.916 188.107 225.759 + endloop + endfacet + facet normal 0.985495 -0.157832 -0.0623539 + outer loop + vertex 681.796 188.874 221.929 + vertex 681.916 188.107 225.759 + vertex 680.897 182.202 224.596 + endloop + endfacet + facet normal 0.983609 -0.163257 -0.0765612 + outer loop + vertex 680.672 181.687 222.805 + vertex 681.796 188.874 221.929 + vertex 680.897 182.202 224.596 + endloop + endfacet + facet normal 0.986211 -0.159645 -0.0435948 + outer loop + vertex 680.672 181.687 222.805 + vertex 680.787 182.948 220.796 + vertex 681.796 188.874 221.929 + endloop + endfacet + facet normal 0.985937 -0.156967 -0.0573549 + outer loop + vertex 681.686 189.594 218.057 + vertex 681.796 188.874 221.929 + vertex 680.787 182.948 220.796 + endloop + endfacet + facet normal 0.98429 -0.162021 -0.0701602 + outer loop + vertex 680.569 182.412 218.974 + vertex 681.686 189.594 218.057 + vertex 680.787 182.948 220.796 + endloop + endfacet + facet normal 0.986377 -0.158846 -0.0427596 + outer loop + vertex 680.569 182.412 218.974 + vertex 680.679 183.658 216.884 + vertex 681.686 189.594 218.057 + endloop + endfacet + facet normal 0.986282 -0.15754 -0.0492866 + outer loop + vertex 681.596 190.266 214.114 + vertex 681.686 189.594 218.057 + vertex 680.679 183.658 216.884 + endloop + endfacet + facet normal 0.984335 -0.163873 -0.065041 + outer loop + vertex 680.461 183.107 214.98 + vertex 681.596 190.266 214.114 + vertex 680.679 183.658 216.884 + endloop + endfacet + facet normal 0.986304 -0.160774 -0.0368375 + outer loop + vertex 680.461 183.107 214.98 + vertex 680.581 184.322 212.863 + vertex 681.596 190.266 214.114 + endloop + endfacet + facet normal 0.986198 -0.158284 -0.0485836 + outer loop + vertex 681.5 190.875 210.185 + vertex 681.596 190.266 214.114 + vertex 680.581 184.322 212.863 + endloop + endfacet + facet normal 0.985388 -0.161013 -0.0555403 + outer loop + vertex 680.378 183.737 210.976 + vertex 681.5 190.875 210.185 + vertex 680.581 184.322 212.863 + endloop + endfacet + facet normal 0.986595 -0.159078 -0.0363803 + outer loop + vertex 680.378 183.737 210.976 + vertex 680.493 184.907 208.959 + vertex 681.5 190.875 210.185 + endloop + endfacet + facet normal 0.986578 -0.158401 -0.039661 + outer loop + vertex 681.433 191.415 206.363 + vertex 681.5 190.875 210.185 + vertex 680.493 184.907 208.959 + endloop + endfacet + facet normal 0.985259 -0.163045 -0.0517828 + outer loop + vertex 680.296 184.281 207.181 + vertex 681.433 191.415 206.363 + vertex 680.493 184.907 208.959 + endloop + endfacet + facet normal 0.986769 -0.160206 -0.0249074 + outer loop + vertex 680.296 184.281 207.181 + vertex 680.432 185.422 205.223 + vertex 681.433 191.415 206.363 + endloop + endfacet + facet normal 0.986747 -0.157551 -0.0388432 + outer loop + vertex 681.361 191.898 202.555 + vertex 681.433 191.415 206.363 + vertex 680.432 185.422 205.223 + endloop + endfacet + facet normal 0.985894 -0.1607 -0.0467829 + outer loop + vertex 680.242 184.775 203.453 + vertex 681.361 191.898 202.555 + vertex 680.432 185.422 205.223 + endloop + endfacet + facet normal 0.987031 -0.158324 -0.0265136 + outer loop + vertex 680.242 184.775 203.453 + vertex 680.365 185.88 201.418 + vertex 681.361 191.898 202.555 + endloop + endfacet + facet normal 0.98703 -0.157008 -0.0334737 + outer loop + vertex 681.292 192.302 198.65 + vertex 681.361 191.898 202.555 + vertex 680.365 185.88 201.418 + endloop + endfacet + facet normal 0.985455 -0.163026 -0.047964 + outer loop + vertex 680.158 185.172 199.573 + vertex 681.292 192.302 198.65 + vertex 680.365 185.88 201.418 + endloop + endfacet + facet normal 0.986819 -0.160094 -0.0236297 + outer loop + vertex 680.158 185.172 199.573 + vertex 680.276 186.214 197.471 + vertex 681.292 192.302 198.65 + endloop + endfacet + facet normal 0.986842 -0.158277 -0.0330301 + outer loop + vertex 681.209 192.616 194.659 + vertex 681.292 192.302 198.65 + vertex 680.276 186.214 197.471 + endloop + endfacet + facet normal 0.985366 -0.163982 -0.0465086 + outer loop + vertex 680.066 185.486 195.578 + vertex 681.209 192.616 194.659 + vertex 680.276 186.214 197.471 + endloop + endfacet + facet normal 0.986912 -0.160391 -0.0167186 + outer loop + vertex 680.066 185.486 195.578 + vertex 680.198 186.518 193.451 + vertex 681.209 192.616 194.659 + endloop + endfacet + facet normal 0.987007 -0.158515 -0.026265 + outer loop + vertex 681.145 192.879 190.643 + vertex 681.209 192.616 194.659 + vertex 680.198 186.518 193.451 + endloop + endfacet + facet normal 0.985769 -0.163672 -0.0383623 + outer loop + vertex 679.993 185.736 191.54 + vertex 681.145 192.879 190.643 + vertex 680.198 186.518 193.451 + endloop + endfacet + facet normal 0.986825 -0.161015 -0.0158541 + outer loop + vertex 679.993 185.736 191.54 + vertex 680.123 186.739 189.401 + vertex 681.145 192.879 190.643 + endloop + endfacet + facet normal 0.986854 -0.16064 -0.0177338 + outer loop + vertex 681.114 193.129 186.689 + vertex 681.145 192.879 190.643 + vertex 680.123 186.739 189.401 + endloop + endfacet + facet normal 0.985608 -0.166148 -0.0311629 + outer loop + vertex 679.933 185.966 187.511 + vertex 681.114 193.129 186.689 + vertex 680.123 186.739 189.401 + endloop + endfacet + facet normal 0.986608 -0.163084 -0.00304638 + outer loop + vertex 679.933 185.966 187.511 + vertex 680.094 186.981 185.477 + vertex 681.114 193.129 186.689 + endloop + endfacet + facet normal 0.986828 -0.161314 -0.0122166 + outer loop + vertex 681.103 193.349 182.879 + vertex 681.114 193.129 186.689 + vertex 680.094 186.981 185.477 + endloop + endfacet + facet normal 0.986111 -0.164761 -0.0209453 + outer loop + vertex 679.925 186.197 183.701 + vertex 681.103 193.349 182.879 + vertex 680.094 186.981 185.477 + endloop + endfacet + facet normal 0.986792 -0.161921 0.00474113 + outer loop + vertex 679.925 186.197 183.701 + vertex 680.096 187.181 181.75 + vertex 681.103 193.349 182.879 + endloop + endfacet + facet normal 0.987112 -0.159891 -0.00663199 + outer loop + vertex 681.102 193.499 179.128 + vertex 681.103 193.349 182.879 + vertex 680.096 187.181 181.75 + endloop + endfacet + facet normal 0.986126 -0.164898 -0.0190751 + outer loop + vertex 679.926 186.362 180.004 + vertex 681.102 193.499 179.128 + vertex 680.096 187.181 181.75 + endloop + endfacet + facet normal 0.986719 -0.162424 0.00187956 + outer loop + vertex 679.926 186.362 180.004 + vertex 680.085 187.308 178 + vertex 681.102 193.499 179.128 + endloop + endfacet + facet normal 0.986897 -0.16129 -0.00450059 + outer loop + vertex 681.097 193.572 175.295 + vertex 681.102 193.499 179.128 + vertex 680.085 187.308 178 + endloop + endfacet + facet normal 0.986193 -0.165051 -0.0134742 + outer loop + vertex 679.917 186.45 176.181 + vertex 681.097 193.572 175.295 + vertex 680.085 187.308 178 + endloop + endfacet + facet normal 0.98665 -0.162763 0.00552457 + outer loop + vertex 679.917 186.45 176.181 + vertex 680.079 187.363 174.107 + vertex 681.097 193.572 175.295 + endloop + endfacet + facet normal 0.986925 -0.161149 -0.00314321 + outer loop + vertex 681.086 193.585 171.37 + vertex 681.097 193.572 175.295 + vertex 680.079 187.363 174.107 + endloop + endfacet + facet normal 0.986336 -0.164398 -0.010746 + outer loop + vertex 679.911 186.481 172.238 + vertex 681.086 193.585 171.37 + vertex 680.079 187.363 174.107 + endloop + endfacet + facet normal 0.986743 -0.162031 0.0091865 + outer loop + vertex 679.911 186.481 172.238 + vertex 680.076 187.364 170.145 + vertex 681.086 193.585 171.37 + endloop + endfacet + facet normal 0.9869 -0.16125 0.00509015 + outer loop + vertex 681.1 193.542 167.42 + vertex 681.086 193.585 171.37 + vertex 680.076 187.364 170.145 + endloop + endfacet + facet normal 0.985999 -0.16659 -0.00735237 + outer loop + vertex 679.909 186.457 168.269 + vertex 681.1 193.542 167.42 + vertex 680.076 187.364 170.145 + endloop + endfacet + facet normal 0.986361 -0.163603 0.0180769 + outer loop + vertex 679.909 186.457 168.269 + vertex 680.086 187.298 166.186 + vertex 681.1 193.542 167.42 + endloop + endfacet + facet normal 0.986849 -0.161495 0.00700439 + outer loop + vertex 681.111 193.441 163.496 + vertex 681.1 193.542 167.42 + vertex 680.086 187.298 166.186 + endloop + endfacet + facet normal 0.986026 -0.166524 -0.00479199 + outer loop + vertex 679.919 186.362 164.327 + vertex 681.111 193.441 163.496 + vertex 680.086 187.298 166.186 + endloop + endfacet + facet normal 0.986314 -0.16372 0.0195023 + outer loop + vertex 679.919 186.362 164.327 + vertex 680.096 187.182 162.276 + vertex 681.111 193.441 163.496 + endloop + endfacet + facet normal 0.986707 -0.162135 0.0110386 + outer loop + vertex 681.129 193.289 159.619 + vertex 681.111 193.441 163.496 + vertex 680.096 187.182 162.276 + endloop + endfacet + facet normal 0.98622 -0.165407 0.00332682 + outer loop + vertex 679.941 186.223 160.447 + vertex 681.129 193.289 159.619 + vertex 680.096 187.182 162.276 + endloop + endfacet + facet normal 0.986304 -0.162513 0.0281575 + outer loop + vertex 679.941 186.223 160.447 + vertex 680.129 187.013 158.418 + vertex 681.129 193.289 159.619 + endloop + endfacet + facet normal 0.986832 -0.160711 0.0182991 + outer loop + vertex 681.167 193.081 155.771 + vertex 681.129 193.289 159.619 + vertex 680.129 187.013 158.418 + endloop + endfacet + facet normal 0.985917 -0.167205 0.00305652 + outer loop + vertex 679.968 186.031 156.598 + vertex 681.167 193.081 155.771 + vertex 680.129 187.013 158.418 + endloop + endfacet + facet normal 0.985955 -0.163673 0.0332145 + outer loop + vertex 679.968 186.031 156.598 + vertex 680.162 186.782 154.564 + vertex 681.167 193.081 155.771 + endloop + endfacet + facet normal 0.986807 -0.160897 0.0180167 + outer loop + vertex 681.193 192.809 151.921 + vertex 681.167 193.081 155.771 + vertex 680.162 186.782 154.564 + endloop + endfacet + facet normal 0.986126 -0.165874 0.00640426 + outer loop + vertex 680.003 185.766 152.732 + vertex 681.193 192.809 151.921 + vertex 680.162 186.782 154.564 + endloop + endfacet + facet normal 0.986017 -0.162175 0.0383443 + outer loop + vertex 680.003 185.766 152.732 + vertex 680.2 186.485 150.699 + vertex 681.193 192.809 151.921 + endloop + endfacet + facet normal 0.986787 -0.159918 0.0260413 + outer loop + vertex 681.241 192.479 148.077 + vertex 681.193 192.809 151.921 + vertex 680.2 186.485 150.699 + endloop + endfacet + facet normal 0.986131 -0.165449 0.013134 + outer loop + vertex 680.05 185.444 148.88 + vertex 681.241 192.479 148.077 + vertex 680.2 186.485 150.699 + endloop + endfacet + facet normal 0.985963 -0.162585 0.0379894 + outer loop + vertex 680.05 185.444 148.88 + vertex 680.244 186.155 146.88 + vertex 681.241 192.479 148.077 + endloop + endfacet + facet normal 0.98637 -0.161458 0.031699 + outer loop + vertex 681.301 192.102 144.261 + vertex 681.241 192.479 148.077 + vertex 680.244 186.155 146.88 + endloop + endfacet + facet normal 0.985899 -0.165995 0.0212045 + outer loop + vertex 680.105 185.099 145.096 + vertex 681.301 192.102 144.261 + vertex 680.244 186.155 146.88 + endloop + endfacet + facet normal 0.985539 -0.162899 0.0466493 + outer loop + vertex 680.105 185.099 145.096 + vertex 680.311 185.777 143.101 + vertex 681.301 192.102 144.261 + endloop + endfacet + facet normal 0.986496 -0.160489 0.0326956 + outer loop + vertex 681.36 191.68 140.433 + vertex 681.301 192.102 144.261 + vertex 680.311 185.777 143.101 + endloop + endfacet + facet normal 0.985942 -0.165797 0.0207317 + outer loop + vertex 680.169 184.706 141.294 + vertex 681.36 191.68 140.433 + vertex 680.311 185.777 143.101 + endloop + endfacet + facet normal 0.985503 -0.162103 0.0500563 + outer loop + vertex 680.169 184.706 141.294 + vertex 680.38 185.356 139.242 + vertex 681.36 191.68 140.433 + endloop + endfacet + facet normal 0.986151 -0.160584 0.0414597 + outer loop + vertex 681.446 191.203 136.539 + vertex 681.36 191.68 140.433 + vertex 680.38 185.356 139.242 + endloop + endfacet + facet normal 0.985687 -0.16596 0.0296471 + outer loop + vertex 680.248 184.237 137.369 + vertex 681.446 191.203 136.539 + vertex 680.38 185.356 139.242 + endloop + endfacet + facet normal 0.985081 -0.16271 0.0560492 + outer loop + vertex 680.248 184.237 137.369 + vertex 680.469 184.849 135.27 + vertex 681.446 191.203 136.539 + endloop + endfacet + facet normal 0.986132 -0.160279 0.0430573 + outer loop + vertex 681.532 190.673 132.598 + vertex 681.446 191.203 136.539 + vertex 680.469 184.849 135.27 + endloop + endfacet + facet normal 0.985894 -0.163432 0.0360919 + outer loop + vertex 680.353 183.735 133.371 + vertex 681.532 190.673 132.598 + vertex 680.469 184.849 135.27 + endloop + endfacet + facet normal 0.985123 -0.160472 0.0614869 + outer loop + vertex 680.353 183.735 133.371 + vertex 680.58 184.338 131.31 + vertex 681.532 190.673 132.598 + endloop + endfacet + facet normal 0.986016 -0.158543 0.0513384 + outer loop + vertex 681.638 190.065 128.675 + vertex 681.532 190.673 132.598 + vertex 680.58 184.338 131.31 + endloop + endfacet + facet normal 0.985807 -0.162204 0.043295 + outer loop + vertex 680.472 183.182 129.442 + vertex 681.638 190.065 128.675 + vertex 680.58 184.338 131.31 + endloop + endfacet + facet normal 0.985095 -0.159824 0.0635864 + outer loop + vertex 680.472 183.182 129.442 + vertex 680.689 183.704 127.389 + vertex 681.638 190.065 128.675 + endloop + endfacet + facet normal 0.986214 -0.157436 0.0509496 + outer loop + vertex 681.727 189.364 124.787 + vertex 681.638 190.065 128.675 + vertex 680.689 183.704 127.389 + endloop + endfacet + facet normal 0.985936 -0.162081 0.0407364 + outer loop + vertex 680.566 182.487 125.521 + vertex 681.727 189.364 124.787 + vertex 680.689 183.704 127.389 + endloop + endfacet + facet normal 0.985136 -0.159483 0.0638074 + outer loop + vertex 680.566 182.487 125.521 + vertex 680.777 182.982 123.511 + vertex 681.727 189.364 124.787 + endloop + endfacet + facet normal 0.985643 -0.158458 0.0583021 + outer loop + vertex 681.833 188.624 120.987 + vertex 681.727 189.364 124.787 + vertex 680.777 182.982 123.511 + endloop + endfacet + facet normal 0.98548 -0.162515 0.0491681 + outer loop + vertex 680.665 181.762 121.711 + vertex 681.833 188.624 120.987 + vertex 680.777 182.982 123.511 + endloop + endfacet + facet normal 0.984491 -0.159922 0.0721315 + outer loop + vertex 680.665 181.762 121.711 + vertex 680.887 182.249 119.765 + vertex 681.833 188.624 120.987 + endloop + endfacet + facet normal 0.984967 -0.159074 0.0673398 + outer loop + vertex 681.964 187.852 117.252 + vertex 681.833 188.624 120.987 + vertex 680.887 182.249 119.765 + endloop + endfacet + facet normal 0.984792 -0.165425 0.0531066 + outer loop + vertex 680.775 181.015 117.996 + vertex 681.964 187.852 117.252 + vertex 680.887 182.249 119.765 + endloop + endfacet + facet normal 0.983232 -0.161774 0.0841701 + outer loop + vertex 680.775 181.015 117.996 + vertex 681.017 181.47 116.04 + vertex 681.964 187.852 117.252 + endloop + endfacet + facet normal 0.984476 -0.159774 0.0726629 + outer loop + vertex 682.107 187.031 113.503 + vertex 681.964 187.852 117.252 + vertex 681.017 181.47 116.04 + endloop + endfacet + facet normal 0.984434 -0.163502 0.0644761 + outer loop + vertex 680.925 180.208 114.249 + vertex 682.107 187.031 113.503 + vertex 681.017 181.47 116.04 + endloop + endfacet + facet normal 0.982719 -0.160093 0.0929151 + outer loop + vertex 680.925 180.208 114.249 + vertex 681.181 180.631 112.271 + vertex 682.107 187.031 113.503 + endloop + endfacet + facet normal 0.983749 -0.158568 0.0842206 + outer loop + vertex 682.291 186.168 109.734 + vertex 682.107 187.031 113.503 + vertex 681.181 180.631 112.271 + endloop + endfacet + facet normal 0.98379 -0.165131 0.0699174 + outer loop + vertex 681.094 179.343 110.46 + vertex 682.291 186.168 109.734 + vertex 681.181 180.631 112.271 + endloop + endfacet + facet normal 0.981412 -0.161046 0.104376 + outer loop + vertex 681.094 179.343 110.46 + vertex 681.37 179.744 108.478 + vertex 682.291 186.168 109.734 + endloop + endfacet + facet normal 0.982563 -0.15949 0.0955697 + outer loop + vertex 682.514 185.288 105.971 + vertex 682.291 186.168 109.734 + vertex 681.37 179.744 108.478 + endloop + endfacet + facet normal 0.982713 -0.163253 0.0873155 + outer loop + vertex 681.314 178.436 106.668 + vertex 682.514 185.288 105.971 + vertex 681.37 179.744 108.478 + endloop + endfacet + facet normal 0.980574 -0.160255 0.113104 + outer loop + vertex 681.314 178.436 106.668 + vertex 681.605 178.829 104.698 + vertex 682.514 185.288 105.971 + endloop + endfacet + facet normal 0.981462 -0.159138 0.106805 + outer loop + vertex 682.779 184.424 102.246 + vertex 682.514 185.288 105.971 + vertex 681.605 178.829 104.698 + endloop + endfacet + facet normal 0.981776 -0.163731 0.0964779 + outer loop + vertex 681.563 177.515 102.901 + vertex 682.779 184.424 102.246 + vertex 681.605 178.829 104.698 + endloop + endfacet + facet normal 0.97831 -0.159764 0.131855 + outer loop + vertex 681.563 177.515 102.901 + vertex 681.891 177.927 100.966 + vertex 682.779 184.424 102.246 + endloop + endfacet + facet normal 0.979841 -0.158068 0.122175 + outer loop + vertex 683.1 183.561 98.5541 + vertex 682.779 184.424 102.246 + vertex 681.891 177.927 100.966 + endloop + endfacet + facet normal 0.980151 -0.160785 0.115982 + outer loop + vertex 681.886 176.624 99.1943 + vertex 683.1 183.561 98.5541 + vertex 681.891 177.927 100.966 + endloop + endfacet + facet normal 0.97662 -0.157355 0.146465 + outer loop + vertex 681.886 176.624 99.1943 + vertex 682.242 177.035 97.2669 + vertex 683.1 183.561 98.5541 + endloop + endfacet + facet normal 0.977333 -0.156649 0.142411 + outer loop + vertex 683.484 182.559 94.8188 + vertex 683.1 183.561 98.5541 + vertex 682.242 177.035 97.2669 + endloop + endfacet + facet normal 0.978276 -0.16348 0.127476 + outer loop + vertex 682.249 175.686 95.4808 + vertex 683.484 182.559 94.8188 + vertex 682.242 177.035 97.2669 + endloop + endfacet + facet normal 0.974617 -0.160019 0.156577 + outer loop + vertex 682.249 175.686 95.4808 + vertex 682.607 175.938 93.5085 + vertex 683.484 182.559 94.8188 + endloop + endfacet + facet normal 0.971449 -0.162771 0.172605 + outer loop + vertex 683.959 181.226 90.887 + vertex 683.484 182.559 94.8188 + vertex 682.607 175.938 93.5085 + endloop + endfacet + facet normal 0.973173 -0.174364 0.150106 + outer loop + vertex 682.603 174.386 91.7318 + vertex 683.959 181.226 90.887 + vertex 682.607 175.938 93.5085 + endloop + endfacet + facet normal 0.966523 -0.167591 0.194283 + outer loop + vertex 682.603 174.386 91.7318 + vertex 682.976 174.407 89.8953 + vertex 683.959 181.226 90.887 + endloop + endfacet + facet normal 0.952552 -0.173674 0.249964 + outer loop + vertex 682.976 174.407 89.8953 + vertex 684.145 178.581 88.342 + vertex 683.959 181.226 90.887 + endloop + endfacet + facet normal 0.95917 -0.190882 0.208704 + outer loop + vertex 683.227 173.44 87.8561 + vertex 684.145 178.581 88.342 + vertex 682.976 174.407 89.8953 + endloop + endfacet + facet normal 0.957579 -0.191246 0.215561 + outer loop + vertex 683.227 173.44 87.8561 + vertex 684.364 177.389 86.3112 + vertex 684.145 178.581 88.342 + endloop + endfacet + facet normal 0.97417 -0.132495 0.182859 + outer loop + vertex 684.364 177.389 86.3112 + vertex 685.045 182.947 86.7106 + vertex 684.145 178.581 88.342 + endloop + endfacet + facet normal 0.974105 -0.132298 0.18335 + outer loop + vertex 684.145 178.581 88.342 + vertex 685.045 182.947 86.7106 + vertex 684.716 183.007 88.5001 + endloop + endfacet + facet normal 0.969022 -0.132536 0.2084 + outer loop + vertex 684.716 183.007 88.5001 + vertex 683.959 181.226 90.887 + vertex 684.145 178.581 88.342 + endloop + endfacet + facet normal 0.968274 -0.133799 0.211053 + outer loop + vertex 684.364 177.389 86.3112 + vertex 685.21 181.268 84.8877 + vertex 685.045 182.947 86.7106 + endloop + endfacet + facet normal 0.970595 -0.139857 0.195921 + outer loop + vertex 684.644 176.662 84.4046 + vertex 685.21 181.268 84.8877 + vertex 684.364 177.389 86.3112 + endloop + endfacet + facet normal 0.957396 -0.193451 0.214407 + outer loop + vertex 683.501 172.702 85.9355 + vertex 684.644 176.662 84.4046 + vertex 684.364 177.389 86.3112 + endloop + endfacet + facet normal 0.9572 -0.19285 0.215816 + outer loop + vertex 683.807 172.158 84.0937 + vertex 684.644 176.662 84.4046 + vertex 683.501 172.702 85.9355 + endloop + endfacet + facet normal 0.95339 -0.193241 0.231746 + outer loop + vertex 683.807 172.158 84.0937 + vertex 684.987 176.155 82.5705 + vertex 684.644 176.662 84.4046 + endloop + endfacet + facet normal 0.966587 -0.134776 0.218046 + outer loop + vertex 684.987 176.155 82.5705 + vertex 685.653 181.578 82.9702 + vertex 684.644 176.662 84.4046 + endloop + endfacet + facet normal 0.957736 -0.136288 0.253314 + outer loop + vertex 684.987 176.155 82.5705 + vertex 685.914 180.19 81.2376 + vertex 685.653 181.578 82.9702 + endloop + endfacet + facet normal 0.959597 -0.139712 0.244241 + outer loop + vertex 685.382 175.731 80.7765 + vertex 685.914 180.19 81.2376 + vertex 684.987 176.155 82.5705 + endloop + endfacet + facet normal 0.947854 -0.19237 0.2541 + outer loop + vertex 684.165 171.715 82.2763 + vertex 685.382 175.731 80.7765 + vertex 684.987 176.155 82.5705 + endloop + endfacet + facet normal 0.94727 -0.191004 0.257286 + outer loop + vertex 684.572 171.299 80.4696 + vertex 685.382 175.731 80.7765 + vertex 684.165 171.715 82.2763 + endloop + endfacet + facet normal 0.943736 -0.191225 0.269807 + outer loop + vertex 684.572 171.299 80.4696 + vertex 685.804 175.316 79.0065 + vertex 685.382 175.731 80.7765 + endloop + endfacet + facet normal 0.956091 -0.13575 0.259736 + outer loop + vertex 685.804 175.316 79.0065 + vertex 686.456 180.646 79.3907 + vertex 685.382 175.731 80.7765 + endloop + endfacet + facet normal 0.947019 -0.136861 0.290558 + outer loop + vertex 685.804 175.316 79.0065 + vertex 686.782 179.307 77.6968 + vertex 686.456 180.646 79.3907 + endloop + endfacet + facet normal 0.94954 -0.140866 0.280233 + outer loop + vertex 686.257 174.855 77.2394 + vertex 686.782 179.307 77.6968 + vertex 685.804 175.316 79.0065 + endloop + endfacet + facet normal 0.93772 -0.190904 0.290235 + outer loop + vertex 684.999 170.868 78.6817 + vertex 686.257 174.855 77.2394 + vertex 685.804 175.316 79.0065 + endloop + endfacet + facet normal 0.938166 -0.191777 0.288211 + outer loop + vertex 685.45 170.4 76.9023 + vertex 686.257 174.855 77.2394 + vertex 684.999 170.868 78.6817 + endloop + endfacet + facet normal 0.933063 -0.192059 0.304148 + outer loop + vertex 685.45 170.4 76.9023 + vertex 686.739 174.396 75.4713 + vertex 686.257 174.855 77.2394 + endloop + endfacet + facet normal 0.945997 -0.137608 0.29352 + outer loop + vertex 686.739 174.396 75.4713 + vertex 687.394 179.713 75.8525 + vertex 686.257 174.855 77.2394 + endloop + endfacet + facet normal 0.93507 -0.138607 0.326241 + outer loop + vertex 686.739 174.396 75.4713 + vertex 687.785 178.364 74.1583 + vertex 687.394 179.713 75.8525 + endloop + endfacet + facet normal 0.938265 -0.143208 0.31488 + outer loop + vertex 687.268 173.952 73.6926 + vertex 687.785 178.364 74.1583 + vertex 686.739 174.396 75.4713 + endloop + endfacet + facet normal 0.926671 -0.191457 0.323457 + outer loop + vertex 685.938 169.925 75.118 + vertex 687.268 173.952 73.6926 + vertex 686.739 174.396 75.4713 + endloop + endfacet + facet normal 0.926245 -0.190734 0.325101 + outer loop + vertex 686.476 169.471 73.3192 + vertex 687.268 173.952 73.6926 + vertex 685.938 169.925 75.118 + endloop + endfacet + facet normal 0.918884 -0.191105 0.345153 + outer loop + vertex 686.476 169.471 73.3192 + vertex 687.852 173.527 71.903 + vertex 687.268 173.952 73.6926 + endloop + endfacet + facet normal 0.931361 -0.1385 0.336727 + outer loop + vertex 687.852 173.527 71.903 + vertex 688.489 178.813 72.3155 + vertex 687.268 173.952 73.6926 + endloop + endfacet + facet normal 0.919514 -0.139473 0.367481 + outer loop + vertex 687.852 173.527 71.903 + vertex 688.969 177.538 70.6287 + vertex 688.489 178.813 72.3155 + endloop + endfacet + facet normal 0.921756 -0.142239 0.360741 + outer loop + vertex 688.486 173.119 70.1214 + vertex 688.969 177.538 70.6287 + vertex 687.852 173.527 71.903 + endloop + endfacet + facet normal 0.910143 -0.190805 0.367742 + outer loop + vertex 687.069 169.032 71.5073 + vertex 688.486 173.119 70.1214 + vertex 687.852 173.527 71.903 + endloop + endfacet + facet normal 0.908733 -0.188791 0.372239 + outer loop + vertex 687.719 168.593 69.699 + vertex 688.486 173.119 70.1214 + vertex 687.069 169.032 71.5073 + endloop + endfacet + facet normal 0.900863 -0.189181 0.390712 + outer loop + vertex 687.719 168.593 69.699 + vertex 689.161 172.727 68.374 + vertex 688.486 173.119 70.1214 + endloop + endfacet + facet normal 0.913383 -0.136165 0.383655 + outer loop + vertex 689.161 172.727 68.374 + vertex 689.758 178.055 68.8447 + vertex 688.486 173.119 70.1214 + endloop + endfacet + facet normal 0.898921 -0.137404 0.416006 + outer loop + vertex 689.161 172.727 68.374 + vertex 690.317 176.829 67.2325 + vertex 689.758 178.055 68.8447 + endloop + endfacet + facet normal 0.90223 -0.140654 0.407673 + outer loop + vertex 689.861 172.37 66.7036 + vertex 690.317 176.829 67.2325 + vertex 689.161 172.727 68.374 + endloop + endfacet + facet normal 0.890907 -0.188597 0.413179 + outer loop + vertex 688.403 168.184 67.9364 + vertex 689.861 172.37 66.7036 + vertex 689.161 172.727 68.374 + endloop + endfacet + facet normal 0.889432 -0.18693 0.417095 + outer loop + vertex 689.113 167.806 66.2527 + vertex 689.861 172.37 66.7036 + vertex 688.403 168.184 67.9364 + endloop + endfacet + facet normal 0.879516 -0.187317 0.437451 + outer loop + vertex 689.113 167.806 66.2527 + vertex 690.578 172.049 65.1236 + vertex 689.861 172.37 66.7036 + endloop + endfacet + facet normal 0.891355 -0.136034 0.432412 + outer loop + vertex 690.578 172.049 65.1236 + vertex 691.167 177.415 65.5986 + vertex 689.861 172.37 66.7036 + endloop + endfacet + facet normal 0.872636 -0.137193 0.468705 + outer loop + vertex 690.578 172.049 65.1236 + vertex 691.771 176.238 64.1285 + vertex 691.167 177.415 65.5986 + endloop + endfacet + facet normal 0.87536 -0.139334 0.462958 + outer loop + vertex 691.327 171.756 63.6194 + vertex 691.771 176.238 64.1285 + vertex 690.578 172.049 65.1236 + endloop + endfacet + facet normal 0.86476 -0.185528 0.466658 + outer loop + vertex 689.844 167.464 64.661 + vertex 691.327 171.756 63.6194 + vertex 690.578 172.049 65.1236 + endloop + endfacet + facet normal 0.863846 -0.184726 0.468664 + outer loop + vertex 690.601 167.164 63.1473 + vertex 691.327 171.756 63.6194 + vertex 689.844 167.464 64.661 + endloop + endfacet + facet normal 0.849357 -0.185072 0.494309 + outer loop + vertex 690.601 167.164 63.1473 + vertex 692.118 171.489 62.1596 + vertex 691.327 171.756 63.6194 + endloop + endfacet + facet normal 0.86042 -0.135529 0.491233 + outer loop + vertex 692.118 171.489 62.1596 + vertex 692.708 176.877 62.614 + vertex 691.327 171.756 63.6194 + endloop + endfacet + facet normal 0.837212 -0.13623 0.529639 + outer loop + vertex 692.118 171.489 62.1596 + vertex 693.406 175.728 61.214 + vertex 692.708 176.877 62.614 + endloop + endfacet + facet normal 0.842458 -0.139913 0.520277 + outer loop + vertex 692.975 171.239 60.7054 + vertex 693.406 175.728 61.214 + vertex 692.118 171.489 62.1596 + endloop + endfacet + facet normal 0.832612 -0.184674 0.522162 + outer loop + vertex 691.404 166.893 61.6731 + vertex 692.975 171.239 60.7054 + vertex 692.118 171.489 62.1596 + endloop + endfacet + facet normal 0.831365 -0.183706 0.524486 + outer loop + vertex 692.275 166.632 60.201 + vertex 692.975 171.239 60.7054 + vertex 691.404 166.893 61.6731 + endloop + endfacet + facet normal 0.813178 -0.183975 0.552173 + outer loop + vertex 692.275 166.632 60.201 + vertex 693.911 170.986 59.2429 + vertex 692.975 171.239 60.7054 + endloop + endfacet + facet normal 0.823606 -0.136187 0.550569 + outer loop + vertex 693.911 170.986 59.2429 + vertex 694.487 176.396 59.7186 + vertex 692.975 171.239 60.7054 + endloop + endfacet + facet normal 0.796623 -0.136674 0.588823 + outer loop + vertex 693.911 170.986 59.2429 + vertex 695.323 175.269 58.327 + vertex 694.487 176.396 59.7186 + endloop + endfacet + facet normal 0.800902 -0.139474 0.582325 + outer loop + vertex 694.925 170.777 57.798 + vertex 695.323 175.269 58.327 + vertex 693.911 170.986 59.2429 + endloop + endfacet + facet normal 0.791745 -0.184278 0.582393 + outer loop + vertex 693.223 166.393 58.7251 + vertex 694.925 170.777 57.798 + vertex 693.911 170.986 59.2429 + endloop + endfacet + facet normal 0.78951 -0.182664 0.585925 + outer loop + vertex 694.257 166.19 57.2685 + vertex 694.925 170.777 57.798 + vertex 693.223 166.393 58.7251 + endloop + endfacet + facet normal 0.767273 -0.18275 0.614731 + outer loop + vertex 694.257 166.19 57.2685 + vertex 696.015 170.668 56.4051 + vertex 694.925 170.777 57.798 + endloop + endfacet + facet normal 0.775347 -0.133746 0.617211 + outer loop + vertex 696.015 170.668 56.4051 + vertex 696.54 176.084 56.9196 + vertex 694.925 170.777 57.798 + endloop + endfacet + facet normal 0.747304 -0.134218 0.650786 + outer loop + vertex 696.015 170.668 56.4051 + vertex 697.492 175.21 55.6458 + vertex 696.54 176.084 56.9196 + endloop + endfacet + facet normal 0.749019 -0.135138 0.64862 + outer loop + vertex 697.151 170.73 55.106 + vertex 697.492 175.21 55.6458 + vertex 696.015 170.668 56.4051 + endloop + endfacet + facet normal 0.744547 -0.181324 0.642473 + outer loop + vertex 695.359 166.093 55.8747 + vertex 697.151 170.73 55.106 + vertex 696.015 170.668 56.4051 + endloop + endfacet + facet normal 0.740277 -0.178739 0.648107 + outer loop + vertex 696.482 166.048 54.5795 + vertex 697.151 170.73 55.106 + vertex 695.359 166.093 55.8747 + endloop + endfacet + facet normal 0.72513 -0.178481 0.66508 + outer loop + vertex 696.482 166.048 54.5795 + vertex 698.278 170.76 53.8855 + vertex 697.151 170.73 55.106 + endloop + endfacet + facet normal 0.730249 -0.128392 0.671008 + outer loop + vertex 698.278 170.76 53.8855 + vertex 698.758 176.543 54.4701 + vertex 697.151 170.73 55.106 + endloop + endfacet + facet normal 0.726732 -0.128484 0.674798 + outer loop + vertex 698.278 170.76 53.8855 + vertex 699.909 176.426 53.2077 + vertex 698.758 176.543 54.4701 + endloop + endfacet + facet normal 0.727322 -0.128735 0.674115 + outer loop + vertex 699.103 169.617 52.7772 + vertex 699.909 176.426 53.2077 + vertex 698.278 170.76 53.8855 + endloop + endfacet + facet normal 0.69641 -0.172776 0.696535 + outer loop + vertex 697.493 165.747 53.427 + vertex 699.103 169.617 52.7772 + vertex 698.278 170.76 53.8855 + endloop + endfacet + facet normal 0.700924 -0.175533 0.691299 + outer loop + vertex 698.162 164.998 52.5581 + vertex 699.103 169.617 52.7772 + vertex 697.493 165.747 53.427 + endloop + endfacet + facet normal 0.667496 -0.226415 0.709356 + outer loop + vertex 696.623 161.642 52.9352 + vertex 698.162 164.998 52.5581 + vertex 697.493 165.747 53.427 + endloop + endfacet + facet normal 0.700181 -0.229356 0.676123 + outer loop + vertex 696.623 161.642 52.9352 + vertex 697.493 165.747 53.427 + vertex 695.586 161.795 54.0607 + endloop + endfacet + facet normal 0.700986 -0.229908 0.675101 + outer loop + vertex 695.586 161.795 54.0607 + vertex 697.493 165.747 53.427 + vertex 696.482 166.048 54.5795 + endloop + endfacet + facet normal 0.728994 -0.23201 0.644003 + outer loop + vertex 695.586 161.795 54.0607 + vertex 696.482 166.048 54.5795 + vertex 694.48 161.894 55.3484 + endloop + endfacet + facet normal 0.730653 -0.233241 0.641673 + outer loop + vertex 694.48 161.894 55.3484 + vertex 696.482 166.048 54.5795 + vertex 695.359 166.093 55.8747 + endloop + endfacet + facet normal 0.754426 -0.234621 0.613021 + outer loop + vertex 694.48 161.894 55.3484 + vertex 695.359 166.093 55.8747 + vertex 693.375 162.007 56.7521 + endloop + endfacet + facet normal 0.754547 -0.234719 0.612835 + outer loop + vertex 693.375 162.007 56.7521 + vertex 695.359 166.093 55.8747 + vertex 694.257 166.19 57.2685 + endloop + endfacet + facet normal 0.77702 -0.235852 0.583621 + outer loop + vertex 693.375 162.007 56.7521 + vertex 694.257 166.19 57.2685 + vertex 692.326 162.196 58.225 + endloop + endfacet + facet normal 0.776692 -0.23556 0.584176 + outer loop + vertex 692.326 162.196 58.225 + vertex 694.257 166.19 57.2685 + vertex 693.223 166.393 58.7251 + endloop + endfacet + facet normal 0.798083 -0.236554 0.554171 + outer loop + vertex 692.326 162.196 58.225 + vertex 693.223 166.393 58.7251 + vertex 691.359 162.441 59.7216 + endloop + endfacet + facet normal 0.799407 -0.237795 0.551727 + outer loop + vertex 691.359 162.441 59.7216 + vertex 693.223 166.393 58.7251 + vertex 692.275 166.632 60.201 + endloop + endfacet + facet normal 0.815679 -0.238527 0.527041 + outer loop + vertex 691.359 162.441 59.7216 + vertex 692.275 166.632 60.201 + vertex 690.473 162.714 61.2173 + endloop + endfacet + facet normal 0.81645 -0.23928 0.525504 + outer loop + vertex 690.473 162.714 61.2173 + vertex 692.275 166.632 60.201 + vertex 691.404 166.893 61.6731 + endloop + endfacet + facet normal 0.832477 -0.240004 0.49938 + outer loop + vertex 690.473 162.714 61.2173 + vertex 691.404 166.893 61.6731 + vertex 689.655 163 62.7176 + endloop + endfacet + facet normal 0.833117 -0.240663 0.497994 + outer loop + vertex 689.655 163 62.7176 + vertex 691.404 166.893 61.6731 + vertex 690.601 167.164 63.1473 + endloop + endfacet + facet normal 0.84822 -0.241356 0.471455 + outer loop + vertex 689.655 163 62.7176 + vertex 690.601 167.164 63.1473 + vertex 688.889 163.308 64.2542 + endloop + endfacet + facet normal 0.848024 -0.241134 0.471922 + outer loop + vertex 688.889 163.308 64.2542 + vertex 690.601 167.164 63.1473 + vertex 689.844 167.464 64.661 + endloop + endfacet + facet normal 0.861289 -0.241736 0.446927 + outer loop + vertex 688.889 163.308 64.2542 + vertex 689.844 167.464 64.661 + vertex 688.151 163.659 65.8664 + endloop + endfacet + facet normal 0.861084 -0.241475 0.447465 + outer loop + vertex 688.151 163.659 65.8664 + vertex 689.844 167.464 64.661 + vertex 689.113 167.806 66.2527 + endloop + endfacet + facet normal 0.872248 -0.241973 0.425008 + outer loop + vertex 688.151 163.659 65.8664 + vertex 689.113 167.806 66.2527 + vertex 687.43 164.058 67.5733 + endloop + endfacet + facet normal 0.873013 -0.243099 0.42279 + outer loop + vertex 687.43 164.058 67.5733 + vertex 689.113 167.806 66.2527 + vertex 688.403 168.184 67.9364 + endloop + endfacet + facet normal 0.882259 -0.243527 0.402881 + outer loop + vertex 687.43 164.058 67.5733 + vertex 688.403 168.184 67.9364 + vertex 686.735 164.495 69.3587 + endloop + endfacet + facet normal 0.883252 -0.245214 0.39967 + outer loop + vertex 686.735 164.495 69.3587 + vertex 688.403 168.184 67.9364 + vertex 687.719 168.593 69.699 + endloop + endfacet + facet normal 0.892411 -0.245654 0.378492 + outer loop + vertex 686.735 164.495 69.3587 + vertex 687.719 168.593 69.699 + vertex 686.085 164.944 71.1836 + endloop + endfacet + facet normal 0.892027 -0.24492 0.379872 + outer loop + vertex 686.085 164.944 71.1836 + vertex 687.719 168.593 69.699 + vertex 687.069 169.032 71.5073 + endloop + endfacet + facet normal 0.900668 -0.24532 0.35863 + outer loop + vertex 686.085 164.944 71.1836 + vertex 687.069 169.032 71.5073 + vertex 685.483 165.412 73.0159 + endloop + endfacet + facet normal 0.901586 -0.247241 0.354986 + outer loop + vertex 685.483 165.412 73.0159 + vertex 687.069 169.032 71.5073 + vertex 686.476 169.471 73.3192 + endloop + endfacet + facet normal 0.908908 -0.247581 0.335545 + outer loop + vertex 685.483 165.412 73.0159 + vertex 686.476 169.471 73.3192 + vertex 684.941 165.886 74.8319 + endloop + endfacet + facet normal 0.909147 -0.248128 0.33449 + outer loop + vertex 684.941 165.886 74.8319 + vertex 686.476 169.471 73.3192 + vertex 685.938 169.925 75.118 + endloop + endfacet + facet normal 0.915764 -0.24843 0.315686 + outer loop + vertex 684.941 165.886 74.8319 + vertex 685.938 169.925 75.118 + vertex 684.453 166.372 76.6308 + endloop + endfacet + facet normal 0.915557 -0.247915 0.316693 + outer loop + vertex 684.453 166.372 76.6308 + vertex 685.938 169.925 75.118 + vertex 685.45 170.4 76.9023 + endloop + endfacet + facet normal 0.921707 -0.248184 0.298096 + outer loop + vertex 684.453 166.372 76.6308 + vertex 685.45 170.4 76.9023 + vertex 684.004 166.858 78.4249 + endloop + endfacet + facet normal 0.921586 -0.247859 0.298738 + outer loop + vertex 684.004 166.858 78.4249 + vertex 685.45 170.4 76.9023 + vertex 684.999 170.868 78.6817 + endloop + endfacet + facet normal 0.926236 -0.248057 0.283822 + outer loop + vertex 684.004 166.858 78.4249 + vertex 684.999 170.868 78.6817 + vertex 683.573 167.319 80.2324 + endloop + endfacet + facet normal 0.926628 -0.249226 0.281508 + outer loop + vertex 683.573 167.319 80.2324 + vertex 684.999 170.868 78.6817 + vertex 684.572 171.299 80.4696 + endloop + endfacet + facet normal 0.930377 -0.249403 0.268694 + outer loop + vertex 683.573 167.319 80.2324 + vertex 684.572 171.299 80.4696 + vertex 683.161 167.75 82.0611 + endloop + endfacet + facet normal 0.930611 -0.250189 0.267149 + outer loop + vertex 683.161 167.75 82.0611 + vertex 684.572 171.299 80.4696 + vertex 684.165 171.715 82.2763 + endloop + endfacet + facet normal 0.935271 -0.250443 0.250094 + outer loop + vertex 683.161 167.75 82.0611 + vertex 684.165 171.715 82.2763 + vertex 682.797 168.214 83.8849 + endloop + endfacet + facet normal 0.935796 -0.252533 0.245992 + outer loop + vertex 682.797 168.214 83.8849 + vertex 684.165 171.715 82.2763 + vertex 683.807 172.158 84.0937 + endloop + endfacet + facet normal 0.940477 -0.252738 0.227216 + outer loop + vertex 682.797 168.214 83.8849 + vertex 683.807 172.158 84.0937 + vertex 682.517 168.749 85.6382 + endloop + endfacet + facet normal 0.940145 -0.251253 0.230215 + outer loop + vertex 682.517 168.749 85.6382 + vertex 683.807 172.158 84.0937 + vertex 683.501 172.702 85.9355 + endloop + endfacet + facet normal 0.939212 -0.251301 0.23394 + outer loop + vertex 682.517 168.749 85.6382 + vertex 683.501 172.702 85.9355 + vertex 682.194 169.154 87.3725 + endloop + endfacet + facet normal 0.939594 -0.252665 0.230921 + outer loop + vertex 682.194 169.154 87.3725 + vertex 683.501 172.702 85.9355 + vertex 683.227 173.44 87.8561 + endloop + endfacet + facet normal 0.937725 -0.253015 0.238023 + outer loop + vertex 682.194 169.154 87.3725 + vertex 683.227 173.44 87.8561 + vertex 681.811 169.478 89.2242 + endloop + endfacet + facet normal 0.938025 -0.253836 0.235958 + outer loop + vertex 681.811 169.478 89.2242 + vertex 683.227 173.44 87.8561 + vertex 682.976 174.407 89.8953 + endloop + endfacet + facet normal 0.944097 -0.252073 0.212465 + outer loop + vertex 681.811 169.478 89.2242 + vertex 682.976 174.407 89.8953 + vertex 681.497 169.905 91.1256 + endloop + endfacet + facet normal 0.947046 -0.259378 0.189279 + outer loop + vertex 681.497 169.905 91.1256 + vertex 682.976 174.407 89.8953 + vertex 682.603 174.386 91.7318 + endloop + endfacet + facet normal 0.947261 -0.2593 0.188309 + outer loop + vertex 681.497 169.905 91.1256 + vertex 682.603 174.386 91.7318 + vertex 681.303 170.538 92.9761 + endloop + endfacet + facet normal 0.944084 -0.249374 0.215681 + outer loop + vertex 681.303 170.538 92.9761 + vertex 682.603 174.386 91.7318 + vertex 682.607 175.938 93.5085 + endloop + endfacet + facet normal 0.954115 -0.247195 0.168995 + outer loop + vertex 681.303 170.538 92.9761 + vertex 682.607 175.938 93.5085 + vertex 681.13 171.134 94.8256 + endloop + endfacet + facet normal 0.956441 -0.255561 0.141096 + outer loop + vertex 681.13 171.134 94.8256 + vertex 682.607 175.938 93.5085 + vertex 682.249 175.686 95.4808 + endloop + endfacet + facet normal 0.952662 -0.257573 0.161527 + outer loop + vertex 681.13 171.134 94.8256 + vertex 682.249 175.686 95.4808 + vertex 680.953 171.644 96.6802 + endloop + endfacet + facet normal 0.94976 -0.24787 0.191094 + outer loop + vertex 680.953 171.644 96.6802 + vertex 682.249 175.686 95.4808 + vertex 682.242 177.035 97.2669 + endloop + endfacet + facet normal 0.95637 -0.245835 0.157864 + outer loop + vertex 680.953 171.644 96.6802 + vertex 682.242 177.035 97.2669 + vertex 680.764 172.098 98.5302 + endloop + endfacet + facet normal 0.958989 -0.255742 0.122212 + outer loop + vertex 680.764 172.098 98.5302 + vertex 682.242 177.035 97.2669 + vertex 681.886 176.624 99.1943 + endloop + endfacet + facet normal 0.95398 -0.258795 0.151485 + outer loop + vertex 680.764 172.098 98.5302 + vertex 681.886 176.624 99.1943 + vertex 680.591 172.546 100.386 + endloop + endfacet + facet normal 0.951339 -0.249298 0.181123 + outer loop + vertex 680.591 172.546 100.386 + vertex 681.886 176.624 99.1943 + vertex 681.891 177.927 100.966 + endloop + endfacet + facet normal 0.959264 -0.246551 0.137934 + outer loop + vertex 680.591 172.546 100.386 + vertex 681.891 177.927 100.966 + vertex 680.44 173.003 102.253 + endloop + endfacet + facet normal 0.960898 -0.254664 0.108727 + outer loop + vertex 680.44 173.003 102.253 + vertex 681.891 177.927 100.966 + vertex 681.563 177.515 102.901 + endloop + endfacet + facet normal 0.956723 -0.257484 0.135586 + outer loop + vertex 680.44 173.003 102.253 + vertex 681.563 177.515 102.901 + vertex 680.299 173.469 104.133 + endloop + endfacet + facet normal 0.955067 -0.249571 0.159876 + outer loop + vertex 680.299 173.469 104.133 + vertex 681.563 177.515 102.901 + vertex 681.605 178.829 104.698 + endloop + endfacet + facet normal 0.961046 -0.247205 0.123609 + outer loop + vertex 680.299 173.469 104.133 + vertex 681.605 178.829 104.698 + vertex 680.176 173.937 106.03 + endloop + endfacet + facet normal 0.962264 -0.256386 0.091188 + outer loop + vertex 680.176 173.937 106.03 + vertex 681.605 178.829 104.698 + vertex 681.314 178.436 106.668 + endloop + endfacet + facet normal 0.957837 -0.259752 0.122786 + outer loop + vertex 680.176 173.937 106.03 + vertex 681.314 178.436 106.668 + vertex 680.058 174.402 107.931 + endloop + endfacet + facet normal 0.956275 -0.250395 0.151129 + outer loop + vertex 680.058 174.402 107.931 + vertex 681.314 178.436 106.668 + vertex 681.37 179.744 108.478 + endloop + endfacet + facet normal 0.96274 -0.247633 0.108675 + outer loop + vertex 680.058 174.402 107.931 + vertex 681.37 179.744 108.478 + vertex 679.959 174.853 109.835 + endloop + endfacet + facet normal 0.963388 -0.254976 0.0828897 + outer loop + vertex 679.959 174.853 109.835 + vertex 681.37 179.744 108.478 + vertex 681.094 179.343 110.46 + endloop + endfacet + facet normal 0.96016 -0.257675 0.108149 + outer loop + vertex 679.959 174.853 109.835 + vertex 681.094 179.343 110.46 + vertex 679.863 175.293 111.735 + endloop + endfacet + facet normal 0.95926 -0.250056 0.131497 + outer loop + vertex 679.863 175.293 111.735 + vertex 681.094 179.343 110.46 + vertex 681.181 180.631 112.271 + endloop + endfacet + facet normal 0.963679 -0.247913 0.0993128 + outer loop + vertex 679.863 175.293 111.735 + vertex 681.181 180.631 112.271 + vertex 679.777 175.72 113.63 + endloop + endfacet + facet normal 0.964101 -0.256159 0.0699466 + outer loop + vertex 679.777 175.72 113.63 + vertex 681.181 180.631 112.271 + vertex 680.925 180.208 114.249 + endloop + endfacet + facet normal 0.961056 -0.259022 0.0963319 + outer loop + vertex 679.777 175.72 113.63 + vertex 680.925 180.208 114.249 + vertex 679.7 176.133 115.518 + endloop + endfacet + facet normal 0.960127 -0.249418 0.126284 + outer loop + vertex 679.7 176.133 115.518 + vertex 680.925 180.208 114.249 + vertex 681.017 181.47 116.04 + endloop + endfacet + facet normal 0.965413 -0.246638 0.084542 + outer loop + vertex 679.7 176.133 115.518 + vertex 681.017 181.47 116.04 + vertex 679.636 176.529 117.396 + endloop + endfacet + facet normal 0.965507 -0.253206 0.0606925 + outer loop + vertex 679.636 176.529 117.396 + vertex 681.017 181.47 116.04 + vertex 680.775 181.015 117.996 + endloop + endfacet + facet normal 0.96311 -0.255699 0.0838884 + outer loop + vertex 679.636 176.529 117.396 + vertex 680.775 181.015 117.996 + vertex 679.575 176.909 119.256 + endloop + endfacet + facet normal 0.962564 -0.247077 0.111462 + outer loop + vertex 679.575 176.909 119.256 + vertex 680.775 181.015 117.996 + vertex 680.887 182.249 119.765 + endloop + endfacet + facet normal 0.965914 -0.245189 0.0830233 + outer loop + vertex 679.575 176.909 119.256 + vertex 680.887 182.249 119.765 + vertex 679.51 177.277 121.106 + endloop + endfacet + facet normal 0.965812 -0.25509 0.0462134 + outer loop + vertex 679.51 177.277 121.106 + vertex 680.887 182.249 119.765 + vertex 680.665 181.762 121.711 + endloop + endfacet + facet normal 0.96318 -0.258259 0.0747427 + outer loop + vertex 679.51 177.277 121.106 + vertex 680.665 181.762 121.711 + vertex 679.46 177.634 122.979 + endloop + endfacet + facet normal 0.962731 -0.247809 0.108347 + outer loop + vertex 679.46 177.634 122.979 + vertex 680.665 181.762 121.711 + vertex 680.777 182.982 123.511 + endloop + endfacet + facet normal 0.96673 -0.245246 0.0727215 + outer loop + vertex 679.46 177.634 122.979 + vertex 680.777 182.982 123.511 + vertex 679.407 177.992 124.89 + endloop + endfacet + facet normal 0.966283 -0.254599 0.0384291 + outer loop + vertex 679.407 177.992 124.89 + vertex 680.777 182.982 123.511 + vertex 680.566 182.487 125.521 + endloop + endfacet + facet normal 0.963774 -0.258036 0.0675072 + outer loop + vertex 679.407 177.992 124.89 + vertex 680.566 182.487 125.521 + vertex 679.367 178.352 126.842 + endloop + endfacet + facet normal 0.963712 -0.248189 0.0982894 + outer loop + vertex 679.367 178.352 126.842 + vertex 680.566 182.487 125.521 + vertex 680.689 183.704 127.389 + endloop + endfacet + facet normal 0.967154 -0.245663 0.0652837 + outer loop + vertex 679.367 178.352 126.842 + vertex 680.689 183.704 127.389 + vertex 679.321 178.692 128.806 + endloop + endfacet + facet normal 0.966653 -0.253276 0.03787 + outer loop + vertex 679.321 178.692 128.806 + vertex 680.689 183.704 127.389 + vertex 680.472 183.182 129.442 + endloop + endfacet + facet normal 0.964052 -0.256871 0.0679749 + outer loop + vertex 679.321 178.692 128.806 + vertex 680.472 183.182 129.442 + vertex 679.262 178.989 130.762 + endloop + endfacet + facet normal 0.96396 -0.247586 0.0973804 + outer loop + vertex 679.262 178.989 130.762 + vertex 680.472 183.182 129.442 + vertex 680.58 184.338 131.31 + endloop + endfacet + facet normal 0.967613 -0.244819 0.0615481 + outer loop + vertex 679.262 178.989 130.762 + vertex 680.58 184.338 131.31 + vertex 679.201 179.243 132.728 + endloop + endfacet + facet normal 0.96699 -0.252732 0.0325103 + outer loop + vertex 679.201 179.243 132.728 + vertex 680.58 184.338 131.31 + vertex 680.353 183.735 133.371 + endloop + endfacet + facet normal 0.964886 -0.255973 0.0589288 + outer loop + vertex 679.201 179.243 132.728 + vertex 680.353 183.735 133.371 + vertex 679.146 179.497 134.734 + endloop + endfacet + facet normal 0.965105 -0.247174 0.0864679 + outer loop + vertex 679.146 179.497 134.734 + vertex 680.353 183.735 133.371 + vertex 680.469 184.849 135.27 + endloop + endfacet + facet normal 0.967927 -0.244846 0.0562777 + outer loop + vertex 679.146 179.497 134.734 + vertex 680.469 184.849 135.27 + vertex 679.097 179.775 136.791 + endloop + endfacet + facet normal 0.96703 -0.253145 0.0277733 + outer loop + vertex 679.097 179.775 136.791 + vertex 680.469 184.849 135.27 + vertex 680.248 184.237 137.369 + endloop + endfacet + facet normal 0.965545 -0.255539 0.0492304 + outer loop + vertex 679.097 179.775 136.791 + vertex 680.248 184.237 137.369 + vertex 679.09 180.141 138.812 + endloop + endfacet + facet normal 0.966233 -0.245433 0.0784668 + outer loop + vertex 679.09 180.141 138.812 + vertex 680.248 184.237 137.369 + vertex 680.38 185.356 139.242 + endloop + endfacet + facet normal 0.968749 -0.243486 0.0473233 + outer loop + vertex 679.09 180.141 138.812 + vertex 680.38 185.356 139.242 + vertex 679.052 180.371 140.792 + endloop + endfacet + facet normal 0.967594 -0.25173 0.0198367 + outer loop + vertex 679.052 180.371 140.792 + vertex 680.38 185.356 139.242 + vertex 680.169 184.706 141.294 + endloop + endfacet + facet normal 0.966048 -0.25431 0.045575 + outer loop + vertex 679.052 180.371 140.792 + vertex 680.169 184.706 141.294 + vertex 679.016 180.587 142.752 + endloop + endfacet + facet normal 0.966769 -0.245953 0.0697482 + outer loop + vertex 679.016 180.587 142.752 + vertex 680.169 184.706 141.294 + vertex 680.311 185.777 143.101 + endloop + endfacet + facet normal 0.96874 -0.244558 0.0416487 + outer loop + vertex 679.016 180.587 142.752 + vertex 680.311 185.777 143.101 + vertex 678.985 180.794 144.677 + endloop + endfacet + facet normal 0.967394 -0.252875 0.0142239 + outer loop + vertex 678.985 180.794 144.677 + vertex 680.311 185.777 143.101 + vertex 680.105 185.099 145.096 + endloop + endfacet + facet normal 0.96603 -0.255139 0.041111 + outer loop + vertex 678.985 180.794 144.677 + vertex 680.105 185.099 145.096 + vertex 678.954 180.979 146.57 + endloop + endfacet + facet normal 0.966968 -0.245223 0.0695659 + outer loop + vertex 678.954 180.979 146.57 + vertex 680.105 185.099 145.096 + vertex 680.244 186.155 146.88 + endloop + endfacet + facet normal 0.969192 -0.243737 0.035494 + outer loop + vertex 678.954 180.979 146.57 + vertex 680.244 186.155 146.88 + vertex 678.925 181.141 148.462 + endloop + endfacet + facet normal 0.967404 -0.253208 0.0040068 + outer loop + vertex 678.925 181.141 148.462 + vertex 680.244 186.155 146.88 + vertex 680.05 185.444 148.88 + endloop + endfacet + facet normal 0.966135 -0.255788 0.0340063 + outer loop + vertex 678.925 181.141 148.462 + vertex 680.05 185.444 148.88 + vertex 678.898 181.293 150.369 + endloop + endfacet + facet normal 0.967243 -0.246408 0.0610234 + outer loop + vertex 678.898 181.293 150.369 + vertex 680.05 185.444 148.88 + vertex 680.2 186.485 150.699 + endloop + endfacet + facet normal 0.969067 -0.244918 0.030409 + outer loop + vertex 678.898 181.293 150.369 + vertex 680.2 186.485 150.699 + vertex 678.876 181.446 152.295 + endloop + endfacet + facet normal 0.967533 -0.252705 0.00454474 + outer loop + vertex 678.876 181.446 152.295 + vertex 680.2 186.485 150.699 + vertex 680.003 185.766 152.732 + endloop + endfacet + facet normal 0.966582 -0.254828 0.027947 + outer loop + vertex 678.876 181.446 152.295 + vertex 680.003 185.766 152.732 + vertex 678.857 181.587 154.232 + endloop + endfacet + facet normal 0.967764 -0.246304 0.0526103 + outer loop + vertex 678.857 181.587 154.232 + vertex 680.003 185.766 152.732 + vertex 680.162 186.782 154.564 + endloop + endfacet + facet normal 0.969224 -0.244907 0.0250258 + outer loop + vertex 678.857 181.587 154.232 + vertex 680.162 186.782 154.564 + vertex 678.841 181.718 156.169 + endloop + endfacet + facet normal 0.967501 -0.252862 -0.00149803 + outer loop + vertex 678.841 181.718 156.169 + vertex 680.162 186.782 154.564 + vertex 679.968 186.031 156.598 + endloop + endfacet + facet normal 0.966802 -0.254776 0.0195611 + outer loop + vertex 678.841 181.718 156.169 + vertex 679.968 186.031 156.598 + vertex 678.829 181.822 158.099 + endloop + endfacet + facet normal 0.968278 -0.245449 0.0468247 + outer loop + vertex 678.829 181.822 158.099 + vertex 679.968 186.031 156.598 + vertex 680.129 187.013 158.418 + endloop + endfacet + facet normal 0.969546 -0.244106 0.0197997 + outer loop + vertex 678.829 181.822 158.099 + vertex 680.129 187.013 158.418 + vertex 678.813 181.914 160.025 + endloop + endfacet + facet normal 0.967545 -0.252553 -0.00864019 + outer loop + vertex 678.813 181.914 160.025 + vertex 680.129 187.013 158.418 + vertex 679.941 186.223 160.447 + endloop + endfacet + facet normal 0.966847 -0.254827 0.0164642 + outer loop + vertex 678.813 181.914 160.025 + vertex 679.941 186.223 160.447 + vertex 678.802 181.996 161.953 + endloop + endfacet + facet normal 0.96851 -0.244625 0.0463474 + outer loop + vertex 678.802 181.996 161.953 + vertex 679.941 186.223 160.447 + vertex 680.096 187.182 162.276 + endloop + endfacet + facet normal 0.969987 -0.242857 0.0120565 + outer loop + vertex 678.802 181.996 161.953 + vertex 680.096 187.182 162.276 + vertex 678.794 182.062 163.894 + endloop + endfacet + facet normal 0.9677 -0.251518 -0.0171873 + outer loop + vertex 678.794 182.062 163.894 + vertex 680.096 187.182 162.276 + vertex 679.919 186.362 164.327 + endloop + endfacet + facet normal 0.967005 -0.254408 0.0133414 + outer loop + vertex 678.794 182.062 163.894 + vertex 679.919 186.362 164.327 + vertex 678.783 182.123 165.854 + endloop + endfacet + facet normal 0.968487 -0.246314 0.0369156 + outer loop + vertex 678.783 182.123 165.854 + vertex 679.919 186.362 164.327 + vertex 680.086 187.298 166.186 + endloop + endfacet + facet normal 0.969586 -0.244655 0.00678262 + outer loop + vertex 678.783 182.123 165.854 + vertex 680.086 187.298 166.186 + vertex 678.78 182.164 167.829 + endloop + endfacet + facet normal 0.967405 -0.252487 -0.0194209 + outer loop + vertex 678.78 182.164 167.829 + vertex 680.086 187.298 166.186 + vertex 679.909 186.457 168.269 + endloop + endfacet + facet normal 0.967001 -0.254745 0.00366913 + outer loop + vertex 678.78 182.164 167.829 + vertex 679.909 186.457 168.269 + vertex 678.778 182.188 169.814 + endloop + endfacet + facet normal 0.968994 -0.244993 0.0320803 + outer loop + vertex 678.778 182.188 169.814 + vertex 679.909 186.457 168.269 + vertex 680.076 187.364 170.145 + endloop + endfacet + facet normal 0.969925 -0.243383 0.00329613 + outer loop + vertex 678.778 182.188 169.814 + vertex 680.076 187.364 170.145 + vertex 678.775 182.201 171.8 + endloop + endfacet + facet normal 0.966811 -0.253601 -0.0310423 + outer loop + vertex 678.775 182.201 171.8 + vertex 680.076 187.364 170.145 + vertex 679.911 186.481 172.238 + endloop + endfacet + facet normal 0.966562 -0.256417 -0.00288731 + outer loop + vertex 678.775 182.201 171.8 + vertex 679.911 186.481 172.238 + vertex 678.777 182.188 173.783 + endloop + endfacet + facet normal 0.968952 -0.245527 0.0291252 + outer loop + vertex 678.777 182.188 173.783 + vertex 679.911 186.481 172.238 + vertex 680.079 187.363 174.107 + endloop + endfacet + facet normal 0.969833 -0.243755 -0.00269144 + outer loop + vertex 678.777 182.188 173.783 + vertex 680.079 187.363 174.107 + vertex 678.778 182.169 175.755 + endloop + endfacet + facet normal 0.96666 -0.253523 -0.0359813 + outer loop + vertex 678.778 182.169 175.755 + vertex 680.079 187.363 174.107 + vertex 679.917 186.45 176.181 + endloop + endfacet + facet normal 0.966519 -0.256538 -0.00533144 + outer loop + vertex 678.778 182.169 175.755 + vertex 679.917 186.45 176.181 + vertex 678.779 182.134 177.704 + endloop + endfacet + facet normal 0.96891 -0.246012 0.0262921 + outer loop + vertex 678.779 182.134 177.704 + vertex 679.917 186.45 176.181 + vertex 680.085 187.308 178 + endloop + endfacet + facet normal 0.969688 -0.244163 -0.00947611 + outer loop + vertex 678.779 182.134 177.704 + vertex 680.085 187.308 178 + vertex 678.786 182.084 179.615 + endloop + endfacet + facet normal 0.966353 -0.253633 -0.0427973 + outer loop + vertex 678.786 182.084 179.615 + vertex 680.085 187.308 178 + vertex 679.926 186.362 180.004 + endloop + endfacet + facet normal 0.96645 -0.256672 -0.00969727 + outer loop + vertex 678.786 182.084 179.615 + vertex 679.926 186.362 180.004 + vertex 678.788 182.021 181.482 + endloop + endfacet + facet normal 0.968832 -0.246821 0.0210621 + outer loop + vertex 678.788 182.021 181.482 + vertex 679.926 186.362 180.004 + vertex 680.096 187.181 181.75 + endloop + endfacet + facet normal 0.969386 -0.245161 -0.0136283 + outer loop + vertex 678.788 182.021 181.482 + vertex 680.096 187.181 181.75 + vertex 678.794 181.943 183.326 + endloop + endfacet + facet normal 0.966427 -0.253297 -0.043119 + outer loop + vertex 678.794 181.943 183.326 + vertex 680.096 187.181 181.75 + vertex 679.925 186.197 183.701 + endloop + endfacet + facet normal 0.966623 -0.255586 -0.0177819 + outer loop + vertex 678.794 181.943 183.326 + vertex 679.925 186.197 183.701 + vertex 678.803 181.849 185.182 + endloop + endfacet + facet normal 0.969438 -0.244814 0.0159911 + outer loop + vertex 678.803 181.849 185.182 + vertex 679.925 186.197 183.701 + vertex 680.094 186.981 185.477 + endloop + endfacet + facet normal 0.969828 -0.242607 -0.0240125 + outer loop + vertex 678.803 181.849 185.182 + vertex 680.094 186.981 185.477 + vertex 678.823 181.74 187.087 + endloop + endfacet + facet normal 0.967275 -0.249226 -0.0475883 + outer loop + vertex 678.823 181.74 187.087 + vertex 680.094 186.981 185.477 + vertex 679.933 185.966 187.511 + endloop + endfacet + facet normal 0.967519 -0.251447 -0.0261122 + outer loop + vertex 678.823 181.74 187.087 + vertex 679.933 185.966 187.511 + vertex 678.851 181.644 189.059 + endloop + endfacet + facet normal 0.970217 -0.242234 0.00149828 + outer loop + vertex 678.851 181.644 189.059 + vertex 679.933 185.966 187.511 + vertex 680.123 186.739 189.401 + endloop + endfacet + facet normal 0.970249 -0.239997 -0.0319017 + outer loop + vertex 678.851 181.644 189.059 + vertex 680.123 186.739 189.401 + vertex 678.896 181.56 191.068 + endloop + endfacet + facet normal 0.967162 -0.247543 -0.057623 + outer loop + vertex 678.896 181.56 191.068 + vertex 680.123 186.739 189.401 + vertex 679.993 185.736 191.54 + endloop + endfacet + facet normal 0.967551 -0.250045 -0.0363724 + outer loop + vertex 678.896 181.56 191.068 + vertex 679.993 185.736 191.54 + vertex 678.949 181.47 193.077 + endloop + endfacet + facet normal 0.970816 -0.239761 -0.00562801 + outer loop + vertex 678.949 181.47 193.077 + vertex 679.993 185.736 191.54 + vertex 680.198 186.518 193.451 + endloop + endfacet + facet normal 0.970784 -0.237789 -0.0321805 + outer loop + vertex 678.949 181.47 193.077 + vertex 680.198 186.518 193.451 + vertex 678.976 181.315 195.046 + endloop + endfacet + facet normal 0.967642 -0.245307 -0.0591055 + outer loop + vertex 678.976 181.315 195.046 + vertex 680.198 186.518 193.451 + vertex 680.066 185.486 195.578 + endloop + endfacet + facet normal 0.967993 -0.249666 -0.0256255 + outer loop + vertex 678.976 181.315 195.046 + vertex 680.066 185.486 195.578 + vertex 678.947 180.996 197.043 + endloop + endfacet + facet normal 0.969199 -0.245923 -0.013235 + outer loop + vertex 678.947 180.996 197.043 + vertex 680.066 185.486 195.578 + vertex 680.276 186.214 197.471 + endloop + endfacet + facet normal 0.969087 -0.243964 -0.036765 + outer loop + vertex 678.947 180.996 197.043 + vertex 680.276 186.214 197.471 + vertex 678.973 180.798 199.051 + endloop + endfacet + facet normal 0.964896 -0.252898 -0.0708419 + outer loop + vertex 678.973 180.798 199.051 + vertex 680.276 186.214 197.471 + vertex 680.158 185.172 199.573 + endloop + endfacet + facet normal 0.965582 -0.256143 -0.0451906 + outer loop + vertex 678.973 180.798 199.051 + vertex 680.158 185.172 199.573 + vertex 679.022 180.635 201.02 + endloop + endfacet + facet normal 0.968915 -0.247001 -0.0139142 + outer loop + vertex 679.022 180.635 201.02 + vertex 680.158 185.172 199.573 + vertex 680.365 185.88 201.418 + endloop + endfacet + facet normal 0.968604 -0.244606 -0.0444223 + outer loop + vertex 679.022 180.635 201.02 + vertex 680.365 185.88 201.418 + vertex 679.061 180.441 202.943 + endloop + endfacet + facet normal 0.964104 -0.253354 -0.0794714 + outer loop + vertex 679.061 180.441 202.943 + vertex 680.365 185.88 201.418 + vertex 680.242 184.775 203.453 + endloop + endfacet + facet normal 0.96509 -0.257078 -0.0501225 + outer loop + vertex 679.061 180.441 202.943 + vertex 680.242 184.775 203.453 + vertex 679.097 180.209 204.822 + endloop + endfacet + facet normal 0.968913 -0.247037 -0.0134364 + outer loop + vertex 679.097 180.209 204.822 + vertex 680.242 184.775 203.453 + vertex 680.432 185.422 205.223 + endloop + endfacet + facet normal 0.968525 -0.244297 -0.0477321 + outer loop + vertex 679.097 180.209 204.822 + vertex 680.432 185.422 205.223 + vertex 679.125 179.963 206.662 + endloop + endfacet + facet normal 0.964482 -0.251793 -0.0798427 + outer loop + vertex 679.125 179.963 206.662 + vertex 680.432 185.422 205.223 + vertex 680.296 184.281 207.181 + endloop + endfacet + facet normal 0.965424 -0.255321 -0.0526081 + outer loop + vertex 679.125 179.963 206.662 + vertex 680.296 184.281 207.181 + vertex 679.158 179.707 208.508 + endloop + endfacet + facet normal 0.968839 -0.246845 -0.0204674 + outer loop + vertex 679.158 179.707 208.508 + vertex 680.296 184.281 207.181 + vertex 680.493 184.907 208.959 + endloop + endfacet + facet normal 0.968305 -0.243757 -0.0544868 + outer loop + vertex 679.158 179.707 208.508 + vertex 680.493 184.907 208.959 + vertex 679.197 179.436 210.404 + endloop + endfacet + facet normal 0.963247 -0.252428 -0.0918399 + outer loop + vertex 679.197 179.436 210.404 + vertex 680.493 184.907 208.959 + vertex 680.378 183.737 210.976 + endloop + endfacet + facet normal 0.964479 -0.256681 -0.0624092 + outer loop + vertex 679.197 179.436 210.404 + vertex 680.378 183.737 210.976 + vertex 679.245 179.139 212.377 + endloop + endfacet + facet normal 0.968652 -0.246944 -0.0270701 + outer loop + vertex 679.245 179.139 212.377 + vertex 680.378 183.737 210.976 + vertex 680.581 184.322 212.863 + endloop + endfacet + facet normal 0.967973 -0.243624 -0.0606252 + outer loop + vertex 679.245 179.139 212.377 + vertex 680.581 184.322 212.863 + vertex 679.292 178.819 214.409 + endloop + endfacet + facet normal 0.963845 -0.250864 -0.0898296 + outer loop + vertex 679.292 178.819 214.409 + vertex 680.581 184.322 212.863 + vertex 680.461 183.107 214.98 + endloop + endfacet + facet normal 0.964921 -0.25457 -0.0641944 + outer loop + vertex 679.292 178.819 214.409 + vertex 680.461 183.107 214.98 + vertex 679.339 178.48 216.448 + endloop + endfacet + facet normal 0.968136 -0.247364 -0.0390318 + outer loop + vertex 679.339 178.48 216.448 + vertex 680.461 183.107 214.98 + vertex 680.679 183.658 216.884 + endloop + endfacet + facet normal 0.967089 -0.244433 -0.0706451 + outer loop + vertex 679.339 178.48 216.448 + vertex 680.679 183.658 216.884 + vertex 679.396 178.126 218.456 + endloop + endfacet + facet normal 0.962744 -0.25155 -0.0992315 + outer loop + vertex 679.396 178.126 218.456 + vertex 680.679 183.658 216.884 + vertex 680.569 182.412 218.974 + endloop + endfacet + facet normal 0.964293 -0.255577 -0.0694214 + outer loop + vertex 679.396 178.126 218.456 + vertex 680.569 182.412 218.974 + vertex 679.442 177.772 220.402 + endloop + endfacet + facet normal 0.967753 -0.248234 -0.0428217 + outer loop + vertex 679.442 177.772 220.402 + vertex 680.569 182.412 218.974 + vertex 680.787 182.948 220.796 + endloop + endfacet + facet normal 0.966541 -0.245527 -0.0742568 + outer loop + vertex 679.442 177.772 220.402 + vertex 680.787 182.948 220.796 + vertex 679.496 177.412 222.302 + endloop + endfacet + facet normal 0.962116 -0.252363 -0.103176 + outer loop + vertex 679.496 177.412 222.302 + vertex 680.787 182.948 220.796 + vertex 680.672 181.687 222.805 + endloop + endfacet + facet normal 0.963505 -0.255485 -0.0799083 + outer loop + vertex 679.496 177.412 222.302 + vertex 680.672 181.687 222.805 + vertex 679.554 177.04 224.185 + endloop + endfacet + facet normal 0.967543 -0.247656 -0.0502779 + outer loop + vertex 679.554 177.04 224.185 + vertex 680.672 181.687 222.805 + vertex 680.897 182.202 224.596 + endloop + endfacet + facet normal 0.966072 -0.244699 -0.0826317 + outer loop + vertex 679.554 177.04 224.185 + vertex 680.897 182.202 224.596 + vertex 679.617 176.651 226.079 + endloop + endfacet + facet normal 0.960238 -0.252883 -0.118294 + outer loop + vertex 679.617 176.651 226.079 + vertex 680.897 182.202 224.596 + vertex 680.804 180.912 226.605 + endloop + endfacet + facet normal 0.962244 -0.256963 -0.0897616 + outer loop + vertex 679.617 176.651 226.079 + vertex 680.804 180.912 226.605 + vertex 679.688 176.246 227.997 + endloop + endfacet + facet normal 0.967265 -0.247763 -0.0548902 + outer loop + vertex 679.688 176.246 227.997 + vertex 680.804 180.912 226.605 + vertex 681.032 181.399 228.419 + endloop + endfacet + facet normal 0.965495 -0.244436 -0.0898395 + outer loop + vertex 679.688 176.246 227.997 + vertex 681.032 181.399 228.419 + vertex 679.762 175.827 229.926 + endloop + endfacet + facet normal 0.958785 -0.253381 -0.128564 + outer loop + vertex 679.762 175.827 229.926 + vertex 681.032 181.399 228.419 + vertex 680.955 180.081 230.442 + endloop + endfacet + facet normal 0.961155 -0.257627 -0.0990439 + outer loop + vertex 679.762 175.827 229.926 + vertex 680.955 180.081 230.442 + vertex 679.845 175.402 231.839 + endloop + endfacet + facet normal 0.96673 -0.248044 -0.0625139 + outer loop + vertex 679.845 175.402 231.839 + vertex 680.955 180.081 230.442 + vertex 681.192 180.555 232.221 + endloop + endfacet + facet normal 0.964155 -0.244336 -0.103461 + outer loop + vertex 679.845 175.402 231.839 + vertex 681.192 180.555 232.221 + vertex 679.937 174.974 233.708 + endloop + endfacet + facet normal 0.957156 -0.252817 -0.141194 + outer loop + vertex 679.937 174.974 233.708 + vertex 681.192 180.555 232.221 + vertex 681.13 179.23 234.178 + endloop + endfacet + facet normal 0.960009 -0.25692 -0.111238 + outer loop + vertex 679.937 174.974 233.708 + vertex 681.13 179.23 234.178 + vertex 680.034 174.552 235.52 + endloop + endfacet + facet normal 0.965249 -0.248994 -0.0793481 + outer loop + vertex 680.034 174.552 235.52 + vertex 681.13 179.23 234.178 + vertex 681.393 179.71 235.869 + endloop + endfacet + facet normal 0.962523 -0.24591 -0.11436 + outer loop + vertex 680.034 174.552 235.52 + vertex 681.393 179.71 235.869 + vertex 680.137 174.133 237.291 + endloop + endfacet + facet normal 0.955544 -0.253549 -0.150495 + outer loop + vertex 680.137 174.133 237.291 + vertex 681.393 179.71 235.869 + vertex 681.338 178.389 237.745 + endloop + endfacet + facet normal 0.958306 -0.257078 -0.124744 + outer loop + vertex 680.137 174.133 237.291 + vertex 681.338 178.389 237.745 + vertex 680.253 173.708 239.058 + endloop + endfacet + facet normal 0.964534 -0.248499 -0.0890089 + outer loop + vertex 680.253 173.708 239.058 + vertex 681.338 178.389 237.745 + vertex 681.615 178.861 239.422 + endloop + endfacet + facet normal 0.960641 -0.244435 -0.131983 + outer loop + vertex 680.253 173.708 239.058 + vertex 681.615 178.861 239.422 + vertex 680.388 173.268 240.854 + endloop + endfacet + facet normal 0.953447 -0.251622 -0.16621 + outer loop + vertex 680.388 173.268 240.854 + vertex 681.615 178.861 239.422 + vertex 681.592 177.518 241.326 + endloop + endfacet + facet normal 0.956928 -0.255815 -0.137287 + outer loop + vertex 680.388 173.268 240.854 + vertex 681.592 177.518 241.326 + vertex 680.529 172.81 242.689 + endloop + endfacet + facet normal 0.962141 -0.249199 -0.110382 + outer loop + vertex 680.529 172.81 242.689 + vertex 681.592 177.518 241.326 + vertex 681.904 177.956 243.06 + endloop + endfacet + facet normal 0.958233 -0.245547 -0.146613 + outer loop + vertex 680.529 172.81 242.689 + vertex 681.904 177.956 243.06 + vertex 680.692 172.335 244.552 + endloop + endfacet + facet normal 0.951195 -0.252284 -0.177711 + outer loop + vertex 680.692 172.335 244.552 + vertex 681.904 177.956 243.06 + vertex 681.905 176.581 245.014 + endloop + endfacet + facet normal 0.954066 -0.255399 -0.156621 + outer loop + vertex 680.692 172.335 244.552 + vertex 681.905 176.581 245.014 + vertex 680.872 171.863 246.416 + endloop + endfacet + facet normal 0.960831 -0.247431 -0.124829 + outer loop + vertex 680.872 171.863 246.416 + vertex 681.905 176.581 245.014 + vertex 682.241 176.999 246.775 + endloop + endfacet + facet normal 0.956532 -0.243833 -0.159972 + outer loop + vertex 680.872 171.863 246.416 + vertex 682.241 176.999 246.775 + vertex 681.068 171.409 248.279 + endloop + endfacet + facet normal 0.947027 -0.252273 -0.198743 + outer loop + vertex 681.068 171.409 248.279 + vertex 682.241 176.999 246.775 + vertex 682.29 175.618 248.761 + endloop + endfacet + facet normal 0.950872 -0.256257 -0.173707 + outer loop + vertex 681.068 171.409 248.279 + vertex 682.29 175.618 248.761 + vertex 681.29 170.943 250.185 + endloop + endfacet + facet normal 0.957516 -0.249051 -0.145382 + outer loop + vertex 681.29 170.943 250.185 + vertex 682.29 175.618 248.761 + vertex 682.658 175.941 250.633 + endloop + endfacet + facet normal 0.952378 -0.244325 -0.182434 + outer loop + vertex 681.29 170.943 250.185 + vertex 682.658 175.941 250.633 + vertex 681.536 170.399 252.196 + endloop + endfacet + facet normal 0.940668 -0.253971 -0.225039 + outer loop + vertex 681.536 170.399 252.196 + vertex 682.658 175.941 250.633 + vertex 682.739 174.405 252.703 + endloop + endfacet + facet normal 0.941458 -0.254741 -0.220827 + outer loop + vertex 681.536 170.399 252.196 + vertex 682.739 174.405 252.703 + vertex 681.886 169.936 254.222 + endloop + endfacet + facet normal 0.944982 -0.251468 -0.209217 + outer loop + vertex 681.886 169.936 254.222 + vertex 682.739 174.405 252.703 + vertex 683.057 174.092 254.515 + endloop + endfacet + facet normal 0.939654 -0.248112 -0.235565 + outer loop + vertex 681.886 169.936 254.222 + vertex 683.057 174.092 254.515 + vertex 682.255 169.503 256.15 + endloop + endfacet + facet normal 0.929272 -0.256935 -0.2654 + outer loop + vertex 682.255 169.503 256.15 + vertex 683.057 174.092 254.515 + vertex 683.125 172.381 256.41 + endloop + endfacet + facet normal 0.937426 -0.262723 -0.228495 + outer loop + vertex 682.255 169.503 256.15 + vertex 683.125 172.381 256.41 + vertex 682.537 168.924 257.973 + endloop + endfacet + facet normal 0.948529 -0.249489 -0.195061 + outer loop + vertex 682.537 168.924 257.973 + vertex 683.125 172.381 256.41 + vertex 683.475 172.587 257.848 + endloop + endfacet + facet normal 0.94253 -0.2489 -0.222902 + outer loop + vertex 682.537 168.924 257.973 + vertex 683.475 172.587 257.848 + vertex 682.834 168.457 259.749 + endloop + endfacet + facet normal 0.942623 -0.24879 -0.222631 + outer loop + vertex 682.834 168.457 259.749 + vertex 683.475 172.587 257.848 + vertex 683.82 172.27 259.663 + endloop + endfacet + facet normal 0.937574 -0.247963 -0.243863 + outer loop + vertex 682.834 168.457 259.749 + vertex 683.82 172.27 259.663 + vertex 683.16 167.924 261.547 + endloop + endfacet + facet normal 0.935094 -0.250535 -0.250663 + outer loop + vertex 683.16 167.924 261.547 + vertex 683.82 172.27 259.663 + vertex 684.166 171.746 261.477 + endloop + endfacet + facet normal 0.930538 -0.249651 -0.267905 + outer loop + vertex 683.16 167.924 261.547 + vertex 684.166 171.746 261.477 + vertex 683.532 167.409 263.318 + endloop + endfacet + facet normal 0.929995 -0.250166 -0.269306 + outer loop + vertex 683.532 167.409 263.318 + vertex 684.166 171.746 261.477 + vertex 684.542 171.264 263.225 + endloop + endfacet + facet normal 0.925454 -0.24936 -0.285227 + outer loop + vertex 683.532 167.409 263.318 + vertex 684.542 171.264 263.225 + vertex 683.945 166.94 265.068 + endloop + endfacet + facet normal 0.92817 -0.246865 -0.278492 + outer loop + vertex 683.945 166.94 265.068 + vertex 684.542 171.264 263.225 + vertex 684.95 170.849 264.951 + endloop + endfacet + facet normal 0.922372 -0.245955 -0.297887 + outer loop + vertex 683.945 166.94 265.068 + vertex 684.95 170.849 264.951 + vertex 684.39 166.483 266.822 + endloop + endfacet + facet normal 0.92293 -0.24546 -0.296563 + outer loop + vertex 684.39 166.483 266.822 + vertex 684.95 170.849 264.951 + vertex 685.394 170.424 266.685 + endloop + endfacet + facet normal 0.916728 -0.24455 -0.31592 + outer loop + vertex 684.39 166.483 266.822 + vertex 685.394 170.424 266.685 + vertex 684.871 166.008 268.585 + endloop + endfacet + facet normal 0.918694 -0.24287 -0.311474 + outer loop + vertex 684.871 166.008 268.585 + vertex 685.394 170.424 266.685 + vertex 685.873 169.989 268.437 + endloop + endfacet + facet normal 0.911177 -0.241804 -0.333598 + outer loop + vertex 684.871 166.008 268.585 + vertex 685.873 169.989 268.437 + vertex 685.393 165.528 270.36 + endloop + endfacet + facet normal 0.912739 -0.240523 -0.330237 + outer loop + vertex 685.393 165.528 270.36 + vertex 685.873 169.989 268.437 + vertex 686.395 169.547 270.203 + endloop + endfacet + facet normal 0.903991 -0.239285 -0.354319 + outer loop + vertex 685.393 165.528 270.36 + vertex 686.395 169.547 270.203 + vertex 685.966 165.054 272.141 + endloop + endfacet + facet normal 0.904368 -0.238992 -0.353556 + outer loop + vertex 685.966 165.054 272.141 + vertex 686.395 169.547 270.203 + vertex 686.97 169.099 271.975 + endloop + endfacet + facet normal 0.895815 -0.237765 -0.375479 + outer loop + vertex 685.966 165.054 272.141 + vertex 686.97 169.099 271.975 + vertex 686.591 164.599 273.922 + endloop + endfacet + facet normal 0.897285 -0.236666 -0.372652 + outer loop + vertex 686.591 164.599 273.922 + vertex 686.97 169.099 271.975 + vertex 687.595 168.671 273.751 + endloop + endfacet + facet normal 0.887006 -0.235169 -0.397386 + outer loop + vertex 686.591 164.599 273.922 + vertex 687.595 168.671 273.751 + vertex 687.269 164.166 275.69 + endloop + endfacet + facet normal 0.887446 -0.234857 -0.396588 + outer loop + vertex 687.269 164.166 275.69 + vertex 687.595 168.671 273.751 + vertex 688.271 168.255 275.511 + endloop + endfacet + facet normal 0.875891 -0.233153 -0.422438 + outer loop + vertex 687.269 164.166 275.69 + vertex 688.271 168.255 275.511 + vertex 687.999 163.755 277.432 + endloop + endfacet + facet normal 0.876095 -0.233017 -0.422091 + outer loop + vertex 687.999 163.755 277.432 + vertex 688.271 168.255 275.511 + vertex 688.999 167.857 277.242 + endloop + endfacet + facet normal 0.863209 -0.231114 -0.44884 + outer loop + vertex 687.999 163.755 277.432 + vertex 688.999 167.857 277.242 + vertex 688.784 163.371 279.138 + endloop + endfacet + facet normal 0.863267 -0.231077 -0.448747 + outer loop + vertex 688.784 163.371 279.138 + vertex 688.999 167.857 277.242 + vertex 689.778 167.484 278.932 + endloop + endfacet + facet normal 0.850915 -0.229284 -0.472624 + outer loop + vertex 688.784 163.371 279.138 + vertex 689.778 167.484 278.932 + vertex 689.617 163.031 280.803 + endloop + endfacet + facet normal 0.851207 -0.229109 -0.472182 + outer loop + vertex 689.617 163.031 280.803 + vertex 689.778 167.484 278.932 + vertex 690.604 167.163 280.578 + endloop + endfacet + facet normal 0.680154 -0.233859 0.694766 + outer loop + vertex 697.635 161.773 51.989 + vertex 698.162 164.998 52.5581 + vertex 696.623 161.642 52.9352 + endloop + endfacet + facet normal 0.729051 -0.232836 0.643639 + outer loop + vertex 697.635 161.773 51.989 + vertex 699.178 166.359 51.9002 + vertex 698.162 164.998 52.5581 + endloop + endfacet + facet normal 0.663722 -0.209417 0.718065 + outer loop + vertex 698.565 162.021 51.2016 + vertex 699.178 166.359 51.9002 + vertex 697.635 161.773 51.989 + endloop + endfacet + facet normal 0.673588 -0.209326 0.708846 + outer loop + vertex 698.565 162.021 51.2016 + vertex 699.817 166.269 51.2663 + vertex 699.178 166.359 51.9002 + endloop + endfacet + facet normal 0.648771 -0.202388 0.733577 + outer loop + vertex 699.274 162.197 50.6232 + vertex 699.817 166.269 51.2663 + vertex 698.565 162.021 51.2016 + endloop + endfacet + facet normal 0.727198 -0.200663 0.656443 + outer loop + vertex 699.274 162.197 50.6232 + vertex 700.396 167.402 50.9713 + vertex 699.817 166.269 51.2663 + endloop + endfacet + facet normal 0.627556 -0.185846 0.756065 + outer loop + vertex 699.701 162.201 50.2694 + vertex 700.396 167.402 50.9713 + vertex 699.274 162.197 50.6232 + endloop + endfacet + facet normal 0.592117 -0.184928 0.784347 + outer loop + vertex 699.701 162.201 50.2694 + vertex 700.546 166.543 50.6551 + vertex 700.396 167.402 50.9713 + endloop + endfacet + facet normal 0.675504 -0.194664 0.711196 + outer loop + vertex 699.849 162.183 50.1244 + vertex 700.546 166.543 50.6551 + vertex 699.701 162.201 50.2694 + endloop + endfacet + facet normal 0.984154 -0.165301 0.0641621 + outer loop + vertex 699.849 162.183 50.1244 + vertex 700.712 167.543 50.6908 + vertex 700.546 166.543 50.6551 + endloop + endfacet + facet normal 0.987069 -0.154459 -0.042863 + outer loop + vertex 699.857 162.24 50.1062 + vertex 700.712 167.543 50.6908 + vertex 699.849 162.183 50.1244 + endloop + endfacet + facet normal -0.35207 -0.046289 0.934829 + outer loop + vertex 699.857 162.24 50.1062 + vertex 700.612 166.802 50.6164 + vertex 700.712 167.543 50.6908 + endloop + endfacet + facet normal 0.222462 0.0719264 -0.972285 + outer loop + vertex 699.87 162.468 50.126 + vertex 700.612 166.802 50.6164 + vertex 699.857 162.24 50.1062 + endloop + endfacet + facet normal 0.969028 -0.143056 -0.201294 + outer loop + vertex 699.87 162.468 50.126 + vertex 700.824 168.088 50.723 + vertex 700.612 166.802 50.6164 + endloop + endfacet + facet normal 0.475828 -0.172354 0.862486 + outer loop + vertex 699.957 162.693 50.1232 + vertex 700.824 168.088 50.723 + vertex 699.87 162.468 50.126 + endloop + endfacet + facet normal 0.0368083 -0.116274 0.992535 + outer loop + vertex 699.957 162.693 50.1232 + vertex 700.886 167.314 50.63 + vertex 700.824 168.088 50.723 + endloop + endfacet + facet normal 0.165692 -0.140379 0.976135 + outer loop + vertex 699.981 162.068 50.029 + vertex 700.886 167.314 50.63 + vertex 699.957 162.693 50.1232 + endloop + endfacet + facet normal -0.0731726 -0.101053 0.992186 + outer loop + vertex 699.981 162.068 50.029 + vertex 700.482 163.961 50.2587 + vertex 700.886 167.314 50.63 + endloop + endfacet + facet normal 0.374457 -0.146472 0.915602 + outer loop + vertex 700.886 167.314 50.63 + vertex 700.482 163.961 50.2587 + vertex 700.84 166.038 50.4445 + endloop + endfacet + facet normal 0.152701 -0.158725 0.975443 + outer loop + vertex 699.898 161.077 49.8809 + vertex 700.482 163.961 50.2587 + vertex 699.981 162.068 50.029 + endloop + endfacet + facet normal 0.833173 -0.234324 0.500915 + outer loop + vertex 700.482 163.961 50.2587 + vertex 699.898 161.077 49.8809 + vertex 700.051 161.648 49.893 + endloop + endfacet + facet normal 0.68877 -0.173654 0.703875 + outer loop + vertex 698.162 164.998 52.5581 + vertex 699.178 166.359 51.9002 + vertex 699.103 169.617 52.7772 + endloop + endfacet + facet normal 0.757507 -0.15341 0.634546 + outer loop + vertex 699.103 169.617 52.7772 + vertex 699.178 166.359 51.9002 + vertex 700.582 173.597 51.9736 + endloop + endfacet + facet normal 0.717146 -0.12822 0.685026 + outer loop + vertex 699.909 176.426 53.2077 + vertex 699.103 169.617 52.7772 + vertex 700.582 173.597 51.9736 + endloop + endfacet + facet normal 0.717229 -0.174044 0.674753 + outer loop + vertex 697.493 165.747 53.427 + vertex 698.278 170.76 53.8855 + vertex 696.482 166.048 54.5795 + endloop + endfacet + facet normal 0.765282 -0.181415 0.617601 + outer loop + vertex 695.359 166.093 55.8747 + vertex 696.015 170.668 56.4051 + vertex 694.257 166.19 57.2685 + endloop + endfacet + facet normal 0.787687 -0.140371 0.599871 + outer loop + vertex 694.925 170.777 57.798 + vertex 696.54 176.084 56.9196 + vertex 695.323 175.269 58.327 + endloop + endfacet + facet normal 0.813312 -0.184077 0.551941 + outer loop + vertex 693.223 166.393 58.7251 + vertex 693.911 170.986 59.2429 + vertex 692.275 166.632 60.201 + endloop + endfacet + facet normal 0.831158 -0.140824 0.537909 + outer loop + vertex 692.975 171.239 60.7054 + vertex 694.487 176.396 59.7186 + vertex 693.406 175.728 61.214 + endloop + endfacet + facet normal 0.848501 -0.184378 0.496035 + outer loop + vertex 691.404 166.893 61.6731 + vertex 692.118 171.489 62.1596 + vertex 690.601 167.164 63.1473 + endloop + endfacet + facet normal 0.867506 -0.140181 0.477266 + outer loop + vertex 691.327 171.756 63.6194 + vertex 692.708 176.877 62.614 + vertex 691.771 176.238 64.1285 + endloop + endfacet + facet normal 0.877301 -0.185129 0.442798 + outer loop + vertex 689.844 167.464 64.661 + vertex 690.578 172.049 65.1236 + vertex 689.113 167.806 66.2527 + endloop + endfacet + facet normal 0.898108 -0.141275 0.416465 + outer loop + vertex 689.861 172.37 66.7036 + vertex 691.167 177.415 65.5986 + vertex 690.317 176.829 67.2325 + endloop + endfacet + facet normal 0.900087 -0.188184 0.392977 + outer loop + vertex 688.403 168.184 67.9364 + vertex 689.161 172.727 68.374 + vertex 687.719 168.593 69.699 + endloop + endfacet + facet normal 0.919877 -0.142566 0.365378 + outer loop + vertex 688.486 173.119 70.1214 + vertex 689.758 178.055 68.8447 + vertex 688.969 177.538 70.6287 + endloop + endfacet + facet normal 0.918434 -0.190399 0.346738 + outer loop + vertex 687.069 169.032 71.5073 + vertex 687.852 173.527 71.903 + vertex 686.476 169.471 73.3192 + endloop + endfacet + facet normal 0.935683 -0.143684 0.32226 + outer loop + vertex 687.268 173.952 73.6926 + vertex 688.489 178.813 72.3155 + vertex 687.785 178.364 74.1583 + endloop + endfacet + facet normal 0.932567 -0.191151 0.306235 + outer loop + vertex 685.938 169.925 75.118 + vertex 686.739 174.396 75.4713 + vertex 685.45 170.4 76.9023 + endloop + endfacet + facet normal 0.948553 -0.14108 0.28345 + outer loop + vertex 686.257 174.855 77.2394 + vertex 687.394 179.713 75.8525 + vertex 686.782 179.307 77.6968 + endloop + endfacet + facet normal 0.943422 -0.190558 0.271372 + outer loop + vertex 684.999 170.868 78.6817 + vertex 685.804 175.316 79.0065 + vertex 684.572 171.299 80.4696 + endloop + endfacet + facet normal 0.958838 -0.139916 0.247088 + outer loop + vertex 685.382 175.731 80.7765 + vertex 686.456 180.646 79.3907 + vertex 685.914 180.19 81.2376 + endloop + endfacet + facet normal 0.952938 -0.19202 0.2346 + outer loop + vertex 684.165 171.715 82.2763 + vertex 684.987 176.155 82.5705 + vertex 683.807 172.158 84.0937 + endloop + endfacet + facet normal 0.96945 -0.140272 0.201224 + outer loop + vertex 684.644 176.662 84.4046 + vertex 685.653 181.578 82.9702 + vertex 685.21 181.268 84.8877 + endloop + endfacet + facet normal 0.958233 -0.193313 0.21076 + outer loop + vertex 683.501 172.702 85.9355 + vertex 684.364 177.389 86.3112 + vertex 683.227 173.44 87.8561 + endloop + endfacet + facet normal 0.974283 -0.132068 -0.182568 + outer loop + vertex 684.635 183.353 255.14 + vertex 683.828 176.741 255.615 + vertex 683.807 181.392 252.142 + endloop + endfacet + facet normal 0.958829 -0.185828 -0.214743 + outer loop + vertex 683.475 172.587 257.848 + vertex 684.32 177.196 257.632 + vertex 683.82 172.27 259.663 + endloop + endfacet + facet normal 0.962933 -0.134849 -0.233613 + outer loop + vertex 684.679 176.575 259.654 + vertex 685.099 182.788 257.8 + vertex 685.336 180.885 259.875 + endloop + endfacet + facet normal 0.94758 -0.190374 -0.256613 + outer loop + vertex 684.166 171.746 261.477 + vertex 685.021 176.015 261.468 + vertex 684.542 171.264 263.225 + endloop + endfacet + facet normal 0.955852 -0.134924 -0.261043 + outer loop + vertex 685.393 175.598 263.192 + vertex 685.751 181.356 261.528 + vertex 686.054 179.975 263.35 + endloop + endfacet + facet normal 0.93978 -0.186452 -0.286443 + outer loop + vertex 684.95 170.849 264.951 + vertex 685.802 175.223 264.9 + vertex 685.394 170.424 266.685 + endloop + endfacet + facet normal 0.947252 -0.133188 -0.291504 + outer loop + vertex 686.246 174.853 266.627 + vertex 686.539 180.6 264.952 + vertex 686.918 179.27 266.791 + endloop + endfacet + facet normal 0.929394 -0.182726 -0.320685 + outer loop + vertex 685.873 169.989 268.437 + vertex 686.729 174.458 268.372 + vertex 686.395 169.547 270.203 + endloop + endfacet + facet normal 0.933751 -0.13449 -0.331696 + outer loop + vertex 687.256 174.051 270.135 + vertex 687.478 179.825 268.419 + vertex 687.945 178.457 270.288 + endloop + endfacet + facet normal 0.91363 -0.179685 -0.364682 + outer loop + vertex 686.97 169.099 271.975 + vertex 687.833 173.629 271.905 + vertex 687.595 168.671 273.751 + endloop + endfacet + facet normal 0.916364 -0.135205 -0.376825 + outer loop + vertex 688.459 173.215 273.676 + vertex 688.587 178.979 271.919 + vertex 689.156 177.618 273.791 + endloop + endfacet + facet normal 0.891999 -0.177072 -0.415913 + outer loop + vertex 688.271 168.255 275.511 + vertex 689.135 172.805 275.426 + vertex 688.999 167.857 277.242 + endloop + endfacet + facet normal 0.896193 -0.132693 -0.423356 + outer loop + vertex 689.861 172.414 277.145 + vertex 689.883 178.192 275.381 + vertex 690.556 176.875 277.218 + endloop + endfacet + facet normal 0.865896 -0.174326 -0.468865 + outer loop + vertex 689.778 167.484 278.932 + vertex 690.635 172.043 278.821 + vertex 690.604 167.163 280.578 + endloop + endfacet + facet normal 0.835804 -0.226939 -0.499931 + outer loop + vertex 689.617 163.031 280.803 + vertex 690.604 167.163 280.578 + vertex 690.503 162.726 282.422 + endloop + endfacet + facet normal 0.813082 -0.16995 -0.556789 + outer loop + vertex 693.356 166.399 285.196 + vertex 693.222 171.19 283.538 + vertex 694.178 170.976 285 + endloop + endfacet + facet normal 0.83368 -0.170241 -0.525353 + outer loop + vertex 691.48 166.874 282.172 + vertex 692.317 171.438 282.021 + vertex 692.399 166.62 283.713 + endloop + endfacet + facet normal 0.831467 -0.129757 -0.540209 + outer loop + vertex 693.222 171.19 283.538 + vertex 693.036 176.83 281.898 + vertex 693.912 175.608 283.539 + endloop + endfacet + facet normal 0.859627 -0.128488 -0.494501 + outer loop + vertex 691.454 171.722 280.448 + vertex 692.143 176.184 280.486 + vertex 692.317 171.438 282.021 + endloop + endfacet + facet normal 0.862263 -0.0937627 -0.497706 + outer loop + vertex 692.327 183.782 279.359 + vertex 694.04 183.086 282.458 + vertex 693.036 176.83 281.898 + endloop + endfacet + facet normal 0.747092 -0.135256 0.650815 + outer loop + vertex 697.151 170.73 55.106 + vertex 698.758 176.543 54.4701 + vertex 697.492 175.21 55.6458 + endloop + endfacet + facet normal 0.763342 -0.0970027 0.63867 + outer loop + vertex 700.582 173.597 51.9736 + vertex 701.295 184.074 52.713 + vertex 699.909 176.426 53.2077 + endloop + endfacet + facet normal 0.74253 -0.0972838 0.66271 + outer loop + vertex 700.582 173.597 51.9736 + vertex 701.876 184.132 52.0702 + vertex 701.295 184.074 52.713 + endloop + endfacet + facet normal 0.743021 -0.0515309 0.667282 + outer loop + vertex 701.876 184.132 52.0702 + vertex 702.081 193.887 52.5951 + vertex 701.295 184.074 52.713 + endloop + endfacet + facet normal 0.644908 -0.0545809 0.762308 + outer loop + vertex 701.876 184.132 52.0702 + vertex 702.458 193.507 52.2488 + vertex 702.081 193.887 52.5951 + endloop + endfacet + facet normal 0.668644 -0.0137502 0.743455 + outer loop + vertex 702.458 193.507 52.2488 + vertex 702.292 207.242 52.6526 + vertex 702.081 193.887 52.5951 + endloop + endfacet + facet normal 0.603592 -0.0526476 0.795553 + outer loop + vertex 702.154 183.452 51.8145 + vertex 702.458 193.507 52.2488 + vertex 701.876 184.132 52.0702 + endloop + endfacet + facet normal 0.543361 -0.0919115 0.834453 + outer loop + vertex 701.287 173.95 51.3325 + vertex 702.154 183.452 51.8145 + vertex 701.876 184.132 52.0702 + endloop + endfacet + facet normal 0.542244 -0.0918468 0.835186 + outer loop + vertex 701.473 174.009 51.218 + vertex 702.154 183.452 51.8145 + vertex 701.287 173.95 51.3325 + endloop + endfacet + facet normal -0.209364 -0.0466108 0.976726 + outer loop + vertex 701.473 174.009 51.218 + vertex 702.233 181.868 51.7558 + vertex 702.154 183.452 51.8145 + endloop + endfacet + facet normal -0.0942788 -0.0415535 0.994678 + outer loop + vertex 702.233 181.868 51.7558 + vertex 702.558 189.909 52.1226 + vertex 702.154 183.452 51.8145 + endloop + endfacet + facet normal -0.136737 -0.0544772 0.989108 + outer loop + vertex 701.724 174.559 51.2829 + vertex 702.233 181.868 51.7558 + vertex 701.473 174.009 51.218 + endloop + endfacet + facet normal -0.138313 -0.0385537 0.989638 + outer loop + vertex 702.154 183.452 51.8145 + vertex 702.558 189.909 52.1226 + vertex 702.458 193.507 52.2488 + endloop + endfacet + facet normal 0.202028 -0.0287227 0.978959 + outer loop + vertex 702.458 193.507 52.2488 + vertex 702.558 189.909 52.1226 + vertex 702.631 198.289 52.3535 + endloop + endfacet + facet normal -0.478818 -0.020055 0.877685 + outer loop + vertex 702.63 191.946 52.208 + vertex 702.631 198.289 52.3535 + vertex 702.558 189.909 52.1226 + endloop + endfacet + facet normal -0.51174 -0.0181182 0.858949 + outer loop + vertex 702.51 185.737 52.006 + vertex 702.63 191.946 52.208 + vertex 702.558 189.909 52.1226 + endloop + endfacet + facet normal 0.874218 -0.0112887 0.485402 + outer loop + vertex 702.631 198.289 52.3535 + vertex 702.63 191.946 52.208 + vertex 702.723 196.704 52.1505 + endloop + endfacet + facet normal 0.694894 -0.0918962 0.713216 + outer loop + vertex 701.287 173.95 51.3325 + vertex 701.876 184.132 52.0702 + vertex 700.582 173.597 51.9736 + endloop + endfacet + facet normal 0.781817 -0.0551956 0.62106 + outer loop + vertex 701.295 184.074 52.713 + vertex 702.081 193.887 52.5951 + vertex 701.412 191.164 53.1959 + endloop + endfacet + facet normal 0.715219 -0.0217151 0.698563 + outer loop + vertex 701.412 191.164 53.1959 + vertex 702.081 193.887 52.5951 + vertex 701.58 200.385 53.3107 + endloop + endfacet + facet normal 0.687122 -0.00165112 0.72654 + outer loop + vertex 701.23 213.041 53.6702 + vertex 701.58 200.385 53.3107 + vertex 702.292 207.242 52.6526 + endloop + endfacet + facet normal 0.717281 0.00910521 0.696724 + outer loop + vertex 702.292 207.242 52.6526 + vertex 701.777 225.154 52.9484 + vertex 701.23 213.041 53.6702 + endloop + endfacet + facet normal 0.736263 0.0119681 0.67659 + outer loop + vertex 701.388 243.72 53.0439 + vertex 701.777 225.154 52.9484 + vertex 701.985 234.395 52.5592 + endloop + endfacet + facet normal 0.761879 0.0151182 0.647543 + outer loop + vertex 701.985 234.395 52.5592 + vertex 701.826 242.22 52.5628 + vertex 701.388 243.72 53.0439 + endloop + endfacet + facet normal 0.789861 0.00634004 0.613254 + outer loop + vertex 701.182 262.452 53.1157 + vertex 701.388 243.72 53.0439 + vertex 701.626 255.26 52.6177 + endloop + endfacet + facet normal 0.790247 0.000143408 0.612789 + outer loop + vertex 701.212 280.437 53.0728 + vertex 701.182 262.452 53.1157 + vertex 701.628 274.25 52.5369 + endloop + endfacet + facet normal 0.789775 -0.0027 0.61339 + outer loop + vertex 701.216 296.37 53.1367 + vertex 701.212 280.437 53.0728 + vertex 701.693 291.534 52.5014 + endloop + endfacet + facet normal 0.797318 -0.00478606 0.60354 + outer loop + vertex 701.386 312.98 53.0441 + vertex 701.216 296.37 53.1367 + vertex 701.748 304.736 52.5006 + endloop + endfacet + facet normal 0.814128 -0.00677384 0.580646 + outer loop + vertex 701.541 330.516 53.0319 + vertex 701.386 312.98 53.0441 + vertex 701.826 322.047 52.5327 + endloop + endfacet + facet normal 0.820897 -0.00878142 0.571009 + outer loop + vertex 701.844 348.43 52.8719 + vertex 701.541 330.516 53.0319 + vertex 701.948 340.319 52.597 + endloop + endfacet + facet normal 0.882823 -0.0342683 0.468454 + outer loop + vertex 699.763 365.708 57.259 + vertex 699.809 353.934 56.3104 + vertex 701.473 370.937 54.4196 + endloop + endfacet + facet normal 0.899988 -0.0597872 0.431796 + outer loop + vertex 701.478 386.658 56.5844 + vertex 699.763 365.708 57.259 + vertex 701.473 370.937 54.4196 + endloop + endfacet + facet normal 0.882999 -0.0643454 0.464943 + outer loop + vertex 703.357 386.656 53.016 + vertex 701.478 386.658 56.5844 + vertex 701.473 370.937 54.4196 + endloop + endfacet + facet normal 0.826397 -0.0134989 0.562927 + outer loop + vertex 701.844 348.43 52.8719 + vertex 702.147 365.934 52.8465 + vertex 701.046 352.469 54.14 + endloop + endfacet + facet normal 0.879536 -0.014546 0.47561 + outer loop + vertex 702.147 365.934 52.8465 + vertex 701.844 348.43 52.8719 + vertex 702.17 358.08 52.5631 + endloop + endfacet + facet normal 0.854091 -0.0562243 0.517076 + outer loop + vertex 701.473 370.937 54.4196 + vertex 703.461 386.656 52.8438 + vertex 703.357 386.656 53.016 + endloop + endfacet + facet normal 0.970298 -0.0337176 0.239552 + outer loop + vertex 702.355 369.284 52.4762 + vertex 702.546 374.879 52.4912 + vertex 702.147 365.934 52.8465 + endloop + endfacet + facet normal 0.912675 -0.0114626 0.408525 + outer loop + vertex 702.289 364.305 52.4825 + vertex 702.355 369.284 52.4762 + vertex 702.147 365.934 52.8465 + endloop + endfacet + facet normal 0.755087 -0.0122967 0.655509 + outer loop + vertex 703.135 356.874 51.4092 + vertex 702.615 370.29 52.2592 + vertex 702.333 355.087 52.2987 + endloop + endfacet + facet normal 0.748402 -0.00546044 0.663223 + outer loop + vertex 703.135 356.874 51.4092 + vertex 702.333 355.087 52.2987 + vertex 703.053 342.414 51.3823 + endloop + endfacet + facet normal 0.911542 -0.0121213 0.411029 + outer loop + vertex 702.17 358.08 52.5631 + vertex 702.289 364.305 52.4825 + vertex 702.147 365.934 52.8465 + endloop + endfacet + facet normal 0.816793 -0.00918394 0.576857 + outer loop + vertex 702.123 353.513 52.5575 + vertex 702.17 358.08 52.5631 + vertex 701.844 348.43 52.8719 + endloop + endfacet + facet normal 0.821308 -0.00983117 0.5704 + outer loop + vertex 702.088 349.433 52.5381 + vertex 702.123 353.513 52.5575 + vertex 701.844 348.43 52.8719 + endloop + endfacet + facet normal 0.732199 -0.00766942 0.681048 + outer loop + vertex 703.053 342.414 51.3823 + vertex 702.333 355.087 52.2987 + vertex 702.192 340.612 52.2879 + endloop + endfacet + facet normal 0.728906 -0.00431025 0.6846 + outer loop + vertex 703.053 342.414 51.3823 + vertex 702.192 340.612 52.2879 + vertex 702.993 327.968 51.3553 + endloop + endfacet + facet normal 0.82018 -0.00901332 0.572034 + outer loop + vertex 702.032 345.531 52.5559 + vertex 702.088 349.433 52.5381 + vertex 701.844 348.43 52.8719 + endloop + endfacet + facet normal 0.821355 -0.00875319 0.57035 + outer loop + vertex 701.948 340.319 52.597 + vertex 702.032 345.531 52.5559 + vertex 701.844 348.43 52.8719 + endloop + endfacet + facet normal 0.820338 -0.00872251 0.571813 + outer loop + vertex 701.919 332.673 52.5216 + vertex 701.948 340.319 52.597 + vertex 701.541 330.516 53.0319 + endloop + endfacet + facet normal 0.707159 -0.00734159 0.707016 + outer loop + vertex 702.993 327.968 51.3553 + vertex 702.192 340.612 52.2879 + vertex 702.143 325.554 52.1803 + endloop + endfacet + facet normal 0.699688 -0.00217174 0.714445 + outer loop + vertex 702.993 327.968 51.3553 + vertex 702.143 325.554 52.1803 + vertex 702.979 313.58 51.3247 + endloop + endfacet + facet normal 0.816098 -0.00654417 0.577876 + outer loop + vertex 701.826 322.047 52.5327 + vertex 701.919 332.673 52.5216 + vertex 701.541 330.516 53.0319 + endloop + endfacet + facet normal 0.685552 -0.00412849 0.728012 + outer loop + vertex 702.979 313.58 51.3247 + vertex 702.143 325.554 52.1803 + vertex 702.061 311.646 52.1789 + endloop + endfacet + facet normal 0.681859 -0.000840755 0.731483 + outer loop + vertex 702.979 313.58 51.3247 + vertex 702.061 311.646 52.1789 + vertex 702.965 299.222 51.3215 + endloop + endfacet + facet normal 0.802893 -0.00535672 0.596099 + outer loop + vertex 701.799 313.805 52.4959 + vertex 701.826 322.047 52.5327 + vertex 701.386 312.98 53.0441 + endloop + endfacet + facet normal 0.802042 -0.0041642 0.597253 + outer loop + vertex 701.748 304.736 52.5006 + vertex 701.799 313.805 52.4959 + vertex 701.386 312.98 53.0441 + endloop + endfacet + facet normal 0.664778 -0.0031574 0.747034 + outer loop + vertex 702.965 299.222 51.3215 + vertex 702.061 311.646 52.1789 + vertex 702.051 296.543 52.1234 + endloop + endfacet + facet normal 0.658597 0.000586185 0.752496 + outer loop + vertex 702.965 299.222 51.3215 + vertex 702.051 296.543 52.1234 + vertex 702.973 284.759 51.326 + endloop + endfacet + facet normal 0.787772 -0.00323501 0.615959 + outer loop + vertex 701.693 291.534 52.5014 + vertex 701.748 304.736 52.5006 + vertex 701.216 296.37 53.1367 + endloop + endfacet + facet normal 0.648923 -0.000735823 0.760854 + outer loop + vertex 702.973 284.759 51.326 + vertex 702.051 296.543 52.1234 + vertex 701.971 282.126 52.178 + endloop + endfacet + facet normal 0.642935 0.00318043 0.765914 + outer loop + vertex 702.973 284.759 51.326 + vertex 701.971 282.126 52.178 + vertex 703.031 270.381 51.3367 + endloop + endfacet + facet normal 0.787666 -0.00246906 0.616098 + outer loop + vertex 701.67 283.119 52.4978 + vertex 701.693 291.534 52.5014 + vertex 701.212 280.437 53.0728 + endloop + endfacet + facet normal 0.784202 -0.00093209 0.620505 + outer loop + vertex 701.628 274.25 52.5369 + vertex 701.67 283.119 52.4978 + vertex 701.212 280.437 53.0728 + endloop + endfacet + facet normal 0.630552 0.00132955 0.776146 + outer loop + vertex 703.031 270.381 51.3367 + vertex 701.971 282.126 52.178 + vertex 702.024 267.623 52.16 + endloop + endfacet + facet normal 0.620237 0.0075552 0.784378 + outer loop + vertex 703.031 270.381 51.3367 + vertex 702.024 267.623 52.16 + vertex 703.22 256.069 51.3254 + endloop + endfacet + facet normal 0.780826 0.00108682 0.624747 + outer loop + vertex 701.656 263.712 52.5204 + vertex 701.628 274.25 52.5369 + vertex 701.182 262.452 53.1157 + endloop + endfacet + facet normal 0.60781 0.00556899 0.794063 + outer loop + vertex 703.22 256.069 51.3254 + vertex 702.024 267.623 52.16 + vertex 702.073 253.97 52.2179 + endloop + endfacet + facet normal 0.602149 0.0104701 0.798315 + outer loop + vertex 703.22 256.069 51.3254 + vertex 702.073 253.97 52.2179 + vertex 703.479 241.646 51.319 + endloop + endfacet + facet normal 0.777312 0.00446725 0.629099 + outer loop + vertex 701.626 255.26 52.6177 + vertex 701.656 263.712 52.5204 + vertex 701.182 262.452 53.1157 + endloop + endfacet + facet normal 0.76409 0.00804681 0.64506 + outer loop + vertex 701.781 247.824 52.5268 + vertex 701.626 255.26 52.6177 + vertex 701.388 243.72 53.0439 + endloop + endfacet + facet normal 0.591803 0.00872662 0.806036 + outer loop + vertex 703.479 241.646 51.319 + vertex 702.073 253.97 52.2179 + vertex 702.299 239.547 52.2082 + endloop + endfacet + facet normal 0.589996 0.0102945 0.80734 + outer loop + vertex 703.479 241.646 51.319 + vertex 702.299 239.547 52.2082 + vertex 703.776 226.668 51.293 + endloop + endfacet + facet normal 0.754716 0.0103202 0.655971 + outer loop + vertex 701.826 242.22 52.5628 + vertex 701.781 247.824 52.5268 + vertex 701.388 243.72 53.0439 + endloop + endfacet + facet normal 0.591899 0.0106121 0.805942 + outer loop + vertex 703.776 226.668 51.293 + vertex 702.299 239.547 52.2082 + vertex 702.582 224.493 52.1984 + endloop + endfacet + facet normal 0.705492 0.0140063 0.708579 + outer loop + vertex 702.167 226.393 52.5357 + vertex 701.985 234.395 52.5592 + vertex 701.777 225.154 52.9484 + endloop + endfacet + facet normal 0.705959 0.0137062 0.70812 + outer loop + vertex 702.353 218.171 52.51 + vertex 702.167 226.393 52.5357 + vertex 701.777 225.154 52.9484 + endloop + endfacet + facet normal 0.59964 0.00399772 0.80026 + outer loop + vertex 703.776 226.668 51.293 + vertex 702.582 224.493 52.1984 + vertex 703.868 211.263 51.301 + endloop + endfacet + facet normal 0.646888 -0.0327015 0.761883 + outer loop + vertex 703.388 184.076 50.9911 + vertex 703.525 195.847 51.3806 + vertex 702.788 186.177 51.5913 + endloop + endfacet + facet normal 0.578061 -0.0336721 0.815299 + outer loop + vertex 703.388 184.076 50.9911 + vertex 704.618 185.487 50.1778 + vertex 703.525 195.847 51.3806 + endloop + endfacet + facet normal 0.566685 -0.0357846 0.823157 + outer loop + vertex 705.883 196.029 49.7651 + vertex 703.525 195.847 51.3806 + vertex 704.618 185.487 50.1778 + endloop + endfacet + facet normal 0.551498 -0.0335568 0.833501 + outer loop + vertex 706.325 184.223 48.9971 + vertex 705.883 196.029 49.7651 + vertex 704.618 185.487 50.1778 + endloop + endfacet + facet normal 0.53249 -0.0687132 0.843643 + outer loop + vertex 706.325 184.223 48.9971 + vertex 704.618 185.487 50.1778 + vertex 705.689 176.935 48.8049 + endloop + endfacet + facet normal 0.548874 -0.0650118 0.833373 + outer loop + vertex 705.689 176.935 48.8049 + vertex 704.618 185.487 50.1778 + vertex 703.988 176.715 49.9081 + endloop + endfacet + facet normal 0.551058 -0.119889 0.82581 + outer loop + vertex 705.689 176.935 48.8049 + vertex 703.988 176.715 49.9081 + vertex 704.935 169.413 48.2159 + endloop + endfacet + facet normal 0.538908 -0.123202 0.833306 + outer loop + vertex 704.935 169.413 48.2159 + vertex 703.988 176.715 49.9081 + vertex 703.216 169.181 49.2936 + endloop + endfacet + facet normal 0.565583 -0.00835002 0.824649 + outer loop + vertex 705.883 196.029 49.7651 + vertex 703.868 211.263 51.301 + vertex 703.525 195.847 51.3806 + endloop + endfacet + facet normal 0.547402 -0.0119779 0.836784 + outer loop + vertex 706.289 212.134 49.7299 + vertex 703.868 211.263 51.301 + vertex 705.883 196.029 49.7651 + endloop + endfacet + facet normal 0.543473 0.0036828 0.839418 + outer loop + vertex 706.289 212.134 49.7299 + vertex 703.776 226.668 51.293 + vertex 703.868 211.263 51.301 + endloop + endfacet + facet normal 0.542592 0.00346917 0.839989 + outer loop + vertex 706.164 227.643 49.7463 + vertex 703.776 226.668 51.293 + vertex 706.289 212.134 49.7299 + endloop + endfacet + facet normal 0.540904 0.00926244 0.841033 + outer loop + vertex 706.164 227.643 49.7463 + vertex 703.479 241.646 51.319 + vertex 703.776 226.668 51.293 + endloop + endfacet + facet normal 0.551298 0.0120206 0.834222 + outer loop + vertex 705.822 242.48 49.7589 + vertex 703.479 241.646 51.319 + vertex 706.164 227.643 49.7463 + endloop + endfacet + facet normal 0.551923 0.00955148 0.833841 + outer loop + vertex 705.822 242.48 49.7589 + vertex 703.22 256.069 51.3254 + vertex 703.479 241.646 51.319 + endloop + endfacet + facet normal 0.566073 0.0133665 0.824247 + outer loop + vertex 705.466 256.905 49.7691 + vertex 703.22 256.069 51.3254 + vertex 705.822 242.48 49.7589 + endloop + endfacet + facet normal 0.567757 0.00683342 0.823168 + outer loop + vertex 705.466 256.905 49.7691 + vertex 703.031 270.381 51.3367 + vertex 703.22 256.069 51.3254 + endloop + endfacet + facet normal 0.58022 0.0101056 0.814397 + outer loop + vertex 705.215 271.22 49.7705 + vertex 703.031 270.381 51.3367 + vertex 705.466 256.905 49.7691 + endloop + endfacet + facet normal 0.582061 0.00296775 0.813139 + outer loop + vertex 705.215 271.22 49.7705 + vertex 702.973 284.759 51.326 + vertex 703.031 270.381 51.3367 + endloop + endfacet + facet normal 0.598044 0.00695965 0.801433 + outer loop + vertex 705.035 285.577 49.7799 + vertex 702.973 284.759 51.326 + vertex 705.215 271.22 49.7705 + endloop + endfacet + facet normal 0.599682 0.000569831 0.800238 + outer loop + vertex 705.035 285.577 49.7799 + vertex 702.965 299.222 51.3215 + vertex 702.973 284.759 51.326 + endloop + endfacet + facet normal 0.617148 0.00473424 0.786833 + outer loop + vertex 704.936 299.906 49.7715 + vertex 702.965 299.222 51.3215 + vertex 705.035 285.577 49.7799 + endloop + endfacet + facet normal 0.618341 -0.000790148 0.78591 + outer loop + vertex 704.936 299.906 49.7715 + vertex 702.979 313.58 51.3247 + vertex 702.965 299.222 51.3215 + endloop + endfacet + facet normal 0.637773 0.00377335 0.770215 + outer loop + vertex 704.862 314.206 49.7631 + vertex 702.979 313.58 51.3247 + vertex 704.936 299.906 49.7715 + endloop + endfacet + facet normal 0.638959 -0.00223154 0.769238 + outer loop + vertex 704.862 314.206 49.7631 + vertex 702.993 327.968 51.3553 + vertex 702.979 313.58 51.3247 + endloop + endfacet + facet normal 0.66094 0.00292894 0.750433 + outer loop + vertex 704.776 328.53 49.7831 + vertex 702.993 327.968 51.3553 + vertex 704.862 314.206 49.7631 + endloop + endfacet + facet normal 0.662192 -0.00415387 0.749323 + outer loop + vertex 704.776 328.53 49.7831 + vertex 703.053 342.414 51.3823 + vertex 702.993 327.968 51.3553 + endloop + endfacet + facet normal 0.685833 0.00126336 0.727758 + outer loop + vertex 704.715 342.851 49.8156 + vertex 703.053 342.414 51.3823 + vertex 704.776 328.53 49.7831 + endloop + endfacet + facet normal 0.686728 -0.00523059 0.726895 + outer loop + vertex 704.715 342.851 49.8156 + vertex 703.135 356.874 51.4092 + vertex 703.053 342.414 51.3823 + endloop + endfacet + facet normal 0.707634 -0.000566263 0.706579 + outer loop + vertex 704.678 357.204 49.8642 + vertex 703.135 356.874 51.4092 + vertex 704.715 342.851 49.8156 + endloop + endfacet + facet normal 0.709341 -0.0175853 0.704646 + outer loop + vertex 704.678 357.204 49.8642 + vertex 703.414 371.605 51.4955 + vertex 703.135 356.874 51.4092 + endloop + endfacet + facet normal 0.736334 -0.0120298 0.676511 + outer loop + vertex 704.826 371.728 49.9609 + vertex 703.414 371.605 51.4955 + vertex 704.678 357.204 49.8642 + endloop + endfacet + facet normal 0.736996 -0.0553992 0.673623 + outer loop + vertex 704.826 371.728 49.9609 + vertex 703.778 386.654 52.335 + vertex 703.414 371.605 51.4955 + endloop + endfacet + facet normal 0.818048 -0.0338866 0.574152 + outer loop + vertex 705.335 386.645 50.1156 + vertex 703.778 386.654 52.335 + vertex 704.826 371.728 49.9609 + endloop + endfacet +endsolid diff --git a/noether_examples/meshes/outputs/output_18.stl b/noether_examples/meshes/outputs/output_18.stl new file mode 100644 index 00000000..8ad7873d --- /dev/null +++ b/noether_examples/meshes/outputs/output_18.stl @@ -0,0 +1,4678 @@ +solid ascii + facet normal -0.0552034 -0.208958 0.976365 + outer loop + vertex -606.501 81.8255 22.6493 + vertex -606.196 79.6874 22.209 + vertex -604.609 81.0773 22.5962 + endloop + endfacet + facet normal -0.0514398 -0.213066 0.975683 + outer loop + vertex -604.609 81.0773 22.5962 + vertex -606.196 79.6874 22.209 + vertex -604.451 80.0418 22.3784 + endloop + endfacet + facet normal -0.229083 -0.233697 0.944937 + outer loop + vertex -604.609 81.0773 22.5962 + vertex -604.451 80.0418 22.3784 + vertex -604.133 81.3022 22.767 + endloop + endfacet + facet normal -0.369929 0.357525 -0.857513 + outer loop + vertex -605.271 78.4781 22.0804 + vertex -604.133 81.3022 22.767 + vertex -604.451 80.0418 22.3784 + endloop + endfacet + facet normal -0.0658808 -0.210288 0.975417 + outer loop + vertex -606.501 81.8255 22.6493 + vertex -610.194 80.4569 22.1049 + vertex -606.196 79.6874 22.209 + endloop + endfacet + facet normal -0.0691196 -0.202144 0.976914 + outer loop + vertex -610.018 83.0571 22.6553 + vertex -610.194 80.4569 22.1049 + vertex -606.501 81.8255 22.6493 + endloop + endfacet + facet normal -0.0827466 -0.201046 0.976081 + outer loop + vertex -610.018 83.0571 22.6553 + vertex -614.176 82.1846 22.1231 + vertex -610.194 80.4569 22.1049 + endloop + endfacet + facet normal -0.081025 -0.208397 0.974682 + outer loop + vertex -614.801 84.5432 22.5755 + vertex -614.176 82.1846 22.1231 + vertex -610.018 83.0571 22.6553 + endloop + endfacet + facet normal -0.0716975 -0.206158 0.975889 + outer loop + vertex -614.801 84.5432 22.5755 + vertex -620.051 83.5297 21.9756 + vertex -614.176 82.1846 22.1231 + endloop + endfacet + facet normal -0.0761641 -0.18529 0.979728 + outer loop + vertex -620.391 86.2154 22.4572 + vertex -620.051 83.5297 21.9756 + vertex -614.801 84.5432 22.5755 + endloop + endfacet + facet normal -0.0738605 -0.185039 0.979952 + outer loop + vertex -620.391 86.2154 22.4572 + vertex -625.386 85.5846 21.9616 + vertex -620.051 83.5297 21.9756 + endloop + endfacet + facet normal -0.0734815 -0.187669 0.97948 + outer loop + vertex -626.19 87.9888 22.3619 + vertex -625.386 85.5846 21.9616 + vertex -620.391 86.2154 22.4572 + endloop + endfacet + facet normal -0.0602565 -0.183527 0.981166 + outer loop + vertex -626.19 87.9888 22.3619 + vertex -631.577 87.0633 21.8579 + vertex -625.386 85.5846 21.9616 + endloop + endfacet + facet normal -0.063956 -0.163764 0.984424 + outer loop + vertex -631.886 89.7669 22.2877 + vertex -631.577 87.0633 21.8579 + vertex -626.19 87.9888 22.3619 + endloop + endfacet + facet normal -0.0608559 -0.16345 0.984673 + outer loop + vertex -631.886 89.7669 22.2877 + vertex -636.901 89.1342 21.8727 + vertex -631.577 87.0633 21.8579 + endloop + endfacet + facet normal -0.0611263 -0.161506 0.984977 + outer loop + vertex -637.615 91.5584 22.2258 + vertex -636.901 89.1342 21.8727 + vertex -631.886 89.7669 22.2877 + endloop + endfacet + facet normal -0.0517253 -0.158876 0.985943 + outer loop + vertex -637.615 91.5584 22.2258 + vertex -643.44 90.6422 21.7726 + vertex -636.901 89.1342 21.8727 + endloop + endfacet + facet normal -0.0417681 -0.115269 0.992456 + outer loop + vertex -636.901 89.1342 21.8727 + vertex -643.44 90.6422 21.7726 + vertex -640.234 86.6858 21.448 + endloop + endfacet + facet normal -0.0419812 -0.114983 0.99248 + outer loop + vertex -636.901 89.1342 21.8727 + vertex -640.234 86.6858 21.448 + vertex -631.577 87.0633 21.8579 + endloop + endfacet + facet normal -0.0417952 -0.118773 0.992041 + outer loop + vertex -640.234 86.6858 21.448 + vertex -628.816 83.2085 21.5128 + vertex -631.577 87.0633 21.8579 + endloop + endfacet + facet normal -0.0456063 -0.121459 0.991548 + outer loop + vertex -625.386 85.5846 21.9616 + vertex -631.577 87.0633 21.8579 + vertex -628.816 83.2085 21.5128 + endloop + endfacet + facet normal -0.0480588 -0.117976 0.991853 + outer loop + vertex -625.386 85.5846 21.9616 + vertex -628.816 83.2085 21.5128 + vertex -620.051 83.5297 21.9756 + endloop + endfacet + facet normal -0.0475768 -0.129154 0.990483 + outer loop + vertex -628.816 83.2085 21.5128 + vertex -617.999 79.7895 21.5865 + vertex -620.051 83.5297 21.9756 + endloop + endfacet + facet normal -0.0553661 -0.133327 0.989524 + outer loop + vertex -614.176 82.1846 22.1231 + vertex -620.051 83.5297 21.9756 + vertex -617.999 79.7895 21.5865 + endloop + endfacet + facet normal -0.0541371 -0.135246 0.989332 + outer loop + vertex -614.176 82.1846 22.1231 + vertex -617.999 79.7895 21.5865 + vertex -610.194 80.4569 22.1049 + endloop + endfacet + facet normal -0.0530847 -0.146368 0.987805 + outer loop + vertex -617.999 79.7895 21.5865 + vertex -610.039 76.8679 21.5814 + vertex -610.194 80.4569 22.1049 + endloop + endfacet + facet normal -0.0539055 -0.146396 0.987756 + outer loop + vertex -606.196 79.6874 22.209 + vertex -610.194 80.4569 22.1049 + vertex -610.039 76.8679 21.5814 + endloop + endfacet + facet normal -0.053969 -0.146312 0.987765 + outer loop + vertex -606.196 79.6874 22.209 + vertex -610.039 76.8679 21.5814 + vertex -605.271 78.4781 22.0804 + endloop + endfacet + facet normal -0.0511021 -0.154463 0.986676 + outer loop + vertex -606.422 74.18 21.3479 + vertex -605.271 78.4781 22.0804 + vertex -610.039 76.8679 21.5814 + endloop + endfacet + facet normal -0.0486006 -0.151152 0.987315 + outer loop + vertex -610.039 76.8679 21.5814 + vertex -610.962 71.7345 20.75 + vertex -606.422 74.18 21.3479 + endloop + endfacet + facet normal -0.0448217 -0.157952 0.986429 + outer loop + vertex -607.088 68.947 20.4797 + vertex -606.422 74.18 21.3479 + vertex -610.962 71.7345 20.75 + endloop + endfacet + facet normal -0.0483814 -0.151192 0.98732 + outer loop + vertex -610.039 76.8679 21.5814 + vertex -618.014 74.7857 20.8717 + vertex -610.962 71.7345 20.75 + endloop + endfacet + facet normal -0.0589745 -0.17549 0.982713 + outer loop + vertex -618.014 74.7857 20.8717 + vertex -617.678 69.7833 19.9985 + vertex -610.962 71.7345 20.75 + endloop + endfacet + facet normal -0.0569045 -0.182193 0.981615 + outer loop + vertex -610.962 71.7345 20.75 + vertex -617.678 69.7833 19.9985 + vertex -610.924 66.88 19.8512 + endloop + endfacet + facet normal -0.0626077 -0.182174 0.981271 + outer loop + vertex -610.962 71.7345 20.75 + vertex -610.924 66.88 19.8512 + vertex -607.088 68.947 20.4797 + endloop + endfacet + facet normal -0.0566292 -0.175361 0.982874 + outer loop + vertex -618.014 74.7857 20.8717 + vertex -627.351 73.1776 20.0469 + vertex -617.678 69.7833 19.9985 + endloop + endfacet + facet normal -0.0574372 -0.171037 0.983589 + outer loop + vertex -628.018 78.204 20.8819 + vertex -627.351 73.1776 20.0469 + vertex -618.014 74.7857 20.8717 + endloop + endfacet + facet normal -0.047209 -0.141117 0.988867 + outer loop + vertex -617.999 79.7895 21.5865 + vertex -628.018 78.204 20.8819 + vertex -618.014 74.7857 20.8717 + endloop + endfacet + facet normal -0.0554138 -0.170794 0.983747 + outer loop + vertex -628.018 78.204 20.8819 + vertex -638.488 76.8262 20.053 + vertex -627.351 73.1776 20.0469 + endloop + endfacet + facet normal -0.055809 -0.168061 0.984196 + outer loop + vertex -639.286 81.7982 20.8568 + vertex -638.488 76.8262 20.053 + vertex -628.018 78.204 20.8819 + endloop + endfacet + facet normal -0.0442823 -0.131884 0.990276 + outer loop + vertex -628.816 83.2085 21.5128 + vertex -639.286 81.7982 20.8568 + vertex -628.018 78.204 20.8819 + endloop + endfacet + facet normal -0.0558562 -0.168068 0.984192 + outer loop + vertex -639.286 81.7982 20.8568 + vertex -649.909 80.5438 20.0396 + vertex -638.488 76.8262 20.053 + endloop + endfacet + facet normal -0.0558531 -0.168092 0.984188 + outer loop + vertex -650.583 85.3379 20.8202 + vertex -649.909 80.5438 20.0396 + vertex -639.286 81.7982 20.8568 + endloop + endfacet + facet normal -0.0434008 -0.12828 0.990788 + outer loop + vertex -640.234 86.6858 21.448 + vertex -650.583 85.3379 20.8202 + vertex -639.286 81.7982 20.8568 + endloop + endfacet + facet normal -0.0434523 -0.127906 0.990834 + outer loop + vertex -651.377 89.6996 21.3484 + vertex -650.583 85.3379 20.8202 + vertex -640.234 86.6858 21.448 + endloop + endfacet + facet normal -0.0448189 -0.128144 0.990742 + outer loop + vertex -651.377 89.6996 21.3484 + vertex -661.542 88.9537 20.7921 + vertex -650.583 85.3379 20.8202 + endloop + endfacet + facet normal -0.0575351 -0.166734 0.984322 + outer loop + vertex -661.542 88.9537 20.7921 + vertex -661.141 84.3051 20.0281 + vertex -650.583 85.3379 20.8202 + endloop + endfacet + facet normal -0.059584 -0.166886 0.984174 + outer loop + vertex -661.542 88.9537 20.7921 + vertex -672.259 88.2075 20.0167 + vertex -661.141 84.3051 20.0281 + endloop + endfacet + facet normal -0.0597592 -0.164735 0.984526 + outer loop + vertex -672.46 92.8727 20.7851 + vertex -672.259 88.2075 20.0167 + vertex -661.542 88.9537 20.7921 + endloop + endfacet + facet normal -0.0455168 -0.125044 0.991107 + outer loop + vertex -661.526 93.3634 21.3492 + vertex -672.46 92.8727 20.7851 + vertex -661.542 88.9537 20.7921 + endloop + endfacet + facet normal -0.0456242 -0.122947 0.991364 + outer loop + vertex -672.38 97.4992 21.3626 + vertex -672.46 92.8727 20.7851 + vertex -661.526 93.3634 21.3492 + endloop + endfacet + facet normal -0.0418358 -0.113009 0.992713 + outer loop + vertex -660.486 98.1127 21.9337 + vertex -672.38 97.4992 21.3626 + vertex -661.526 93.3634 21.3492 + endloop + endfacet + facet normal -0.0396291 -0.113496 0.992748 + outer loop + vertex -660.486 98.1127 21.9337 + vertex -661.526 93.3634 21.3492 + vertex -651.585 93.5135 21.7632 + endloop + endfacet + facet normal -0.0492234 -0.131964 0.990032 + outer loop + vertex -651.585 93.5135 21.7632 + vertex -649.938 96.2705 22.2125 + vertex -660.486 98.1127 21.9337 + endloop + endfacet + facet normal -0.0556238 -0.169531 0.983954 + outer loop + vertex -649.938 96.2705 22.2125 + vertex -653.339 99.0904 22.5062 + vertex -660.486 98.1127 21.9337 + endloop + endfacet + facet normal -0.059374 -0.144333 0.987746 + outer loop + vertex -658.527 100.94 22.4645 + vertex -660.486 98.1127 21.9337 + vertex -653.339 99.0904 22.5062 + endloop + endfacet + facet normal -0.060089 -0.143843 0.987774 + outer loop + vertex -658.527 100.94 22.4645 + vertex -664.465 102.497 22.3301 + vertex -660.486 98.1127 21.9337 + endloop + endfacet + facet normal -0.0514715 -0.136166 0.989348 + outer loop + vertex -672.884 102.437 21.8839 + vertex -660.486 98.1127 21.9337 + vertex -664.465 102.497 22.3301 + endloop + endfacet + facet normal -0.0515867 -0.12802 0.990429 + outer loop + vertex -669.769 104.811 22.3529 + vertex -672.884 102.437 21.8839 + vertex -664.465 102.497 22.3301 + endloop + endfacet + facet normal -0.0520764 -0.127388 0.990485 + outer loop + vertex -669.769 104.811 22.3529 + vertex -675.652 106.484 22.2587 + vertex -672.884 102.437 21.8839 + endloop + endfacet + facet normal -0.0477583 -0.124488 0.991071 + outer loop + vertex -684.205 106.445 21.8417 + vertex -672.884 102.437 21.8839 + vertex -675.652 106.484 22.2587 + endloop + endfacet + facet normal -0.0478057 -0.119989 0.991624 + outer loop + vertex -680.812 108.768 22.2864 + vertex -684.205 106.445 21.8417 + vertex -675.652 106.484 22.2587 + endloop + endfacet + facet normal -0.0467048 -0.121569 0.991484 + outer loop + vertex -680.812 108.768 22.2864 + vertex -687.279 110.567 22.2023 + vertex -684.205 106.445 21.8417 + endloop + endfacet + facet normal -0.0455572 -0.120727 0.99164 + outer loop + vertex -695.198 109.988 21.768 + vertex -684.205 106.445 21.8417 + vertex -687.279 110.567 22.2023 + endloop + endfacet + facet normal -0.0448814 -0.1292 0.990602 + outer loop + vertex -695.308 113.827 22.2637 + vertex -695.198 109.988 21.768 + vertex -687.279 110.567 22.2023 + endloop + endfacet + facet normal -0.0484398 -0.129279 0.990424 + outer loop + vertex -695.308 113.827 22.2637 + vertex -705.155 114.15 21.8244 + vertex -695.198 109.988 21.768 + endloop + endfacet + facet normal -0.043194 -0.116755 0.992221 + outer loop + vertex -705.155 114.15 21.8244 + vertex -705.525 109.882 21.306 + vertex -695.198 109.988 21.768 + endloop + endfacet + facet normal -0.0433241 -0.108272 0.993177 + outer loop + vertex -695.198 109.988 21.768 + vertex -705.525 109.882 21.306 + vertex -694.792 105.727 21.3213 + endloop + endfacet + facet normal -0.0489358 -0.122776 0.991227 + outer loop + vertex -705.525 109.882 21.306 + vertex -705.721 105.557 20.7606 + vertex -694.792 105.727 21.3213 + endloop + endfacet + facet normal -0.0489565 -0.121832 0.991343 + outer loop + vertex -694.792 105.727 21.3213 + vertex -705.721 105.557 20.7606 + vertex -694.764 101.254 20.7729 + endloop + endfacet + facet normal -0.0470765 -0.121831 0.991434 + outer loop + vertex -694.792 105.727 21.3213 + vertex -694.764 101.254 20.7729 + vertex -683.722 101.661 21.3473 + endloop + endfacet + facet normal -0.0415903 -0.106882 0.993402 + outer loop + vertex -684.205 106.445 21.8417 + vertex -694.792 105.727 21.3213 + vertex -683.722 101.661 21.3473 + endloop + endfacet + facet normal -0.0470756 -0.121853 0.991431 + outer loop + vertex -683.722 101.661 21.3473 + vertex -694.764 101.254 20.7729 + vertex -683.609 97.0181 20.7819 + endloop + endfacet + facet normal -0.0460487 -0.121835 0.991482 + outer loop + vertex -683.722 101.661 21.3473 + vertex -683.609 97.0181 20.7819 + vertex -672.38 97.4992 21.3626 + endloop + endfacet + facet normal -0.0413645 -0.109064 0.993174 + outer loop + vertex -672.884 102.437 21.8839 + vertex -683.722 101.661 21.3473 + vertex -672.38 97.4992 21.3626 + endloop + endfacet + facet normal -0.0625266 -0.162559 0.984716 + outer loop + vertex -694.764 101.254 20.7729 + vertex -694.613 96.577 20.0104 + vertex -683.609 97.0181 20.7819 + endloop + endfacet + facet normal -0.0625054 -0.16297 0.984649 + outer loop + vertex -683.609 97.0181 20.7819 + vertex -694.613 96.577 20.0104 + vertex -683.428 92.3111 20.0144 + endloop + endfacet + facet normal -0.0608602 -0.162925 0.98476 + outer loop + vertex -683.609 97.0181 20.7819 + vertex -683.428 92.3111 20.0144 + vertex -672.46 92.8727 20.7851 + endloop + endfacet + facet normal -0.0645311 -0.162601 0.984579 + outer loop + vertex -694.764 101.254 20.7729 + vertex -705.673 100.956 20.0087 + vertex -694.613 96.577 20.0104 + endloop + endfacet + facet normal -0.0645696 -0.161605 0.984741 + outer loop + vertex -705.721 105.557 20.7606 + vertex -705.673 100.956 20.0087 + vertex -694.764 101.254 20.7729 + endloop + endfacet + facet normal -0.0675664 -0.161604 0.98454 + outer loop + vertex -705.721 105.557 20.7606 + vertex -716.542 105.437 19.9984 + vertex -705.673 100.956 20.0087 + endloop + endfacet + facet normal -0.0675832 -0.160856 0.984661 + outer loop + vertex -716.518 110.002 20.7457 + vertex -716.542 105.437 19.9984 + vertex -705.721 105.557 20.7606 + endloop + endfacet + facet normal -0.0705163 -0.160807 0.984464 + outer loop + vertex -716.518 110.002 20.7457 + vertex -727.316 110.072 19.9836 + vertex -716.542 105.437 19.9984 + endloop + endfacet + facet normal -0.0705256 -0.158929 0.984768 + outer loop + vertex -727.252 114.631 20.724 + vertex -727.316 110.072 19.9836 + vertex -716.518 110.002 20.7457 + endloop + endfacet + facet normal -0.0554579 -0.123961 0.990736 + outer loop + vertex -716.134 114.329 21.3085 + vertex -727.252 114.631 20.724 + vertex -716.518 110.002 20.7457 + endloop + endfacet + facet normal -0.0518621 -0.1243 0.990888 + outer loop + vertex -716.134 114.329 21.3085 + vertex -716.518 110.002 20.7457 + vertex -705.525 109.882 21.306 + endloop + endfacet + facet normal -0.0554927 -0.125663 0.99052 + outer loop + vertex -726.853 118.997 21.3003 + vertex -727.252 114.631 20.724 + vertex -716.134 114.329 21.3085 + endloop + endfacet + facet normal -0.0542915 -0.122905 0.990932 + outer loop + vertex -715.676 118.8 21.8881 + vertex -726.853 118.997 21.3003 + vertex -716.134 114.329 21.3085 + endloop + endfacet + facet normal -0.0485731 -0.123519 0.991153 + outer loop + vertex -715.676 118.8 21.8881 + vertex -716.134 114.329 21.3085 + vertex -705.155 114.15 21.8244 + endloop + endfacet + facet normal -0.0588513 -0.146728 0.987425 + outer loop + vertex -703.947 118.756 22.5807 + vertex -715.676 118.8 21.8881 + vertex -705.155 114.15 21.8244 + endloop + endfacet + facet normal -0.0588345 -0.150009 0.986933 + outer loop + vertex -715.913 123.661 22.613 + vertex -715.676 118.8 21.8881 + vertex -703.947 118.756 22.5807 + endloop + endfacet + facet normal -0.0651399 -0.150252 0.986499 + outer loop + vertex -715.913 123.661 22.613 + vertex -726.575 123.548 21.8917 + vertex -715.676 118.8 21.8881 + endloop + endfacet + facet normal -0.0650979 -0.152264 0.986194 + outer loop + vertex -726.693 128.371 22.6286 + vertex -726.575 123.548 21.8917 + vertex -715.913 123.661 22.613 + endloop + endfacet + facet normal -0.0714473 -0.15235 0.985741 + outer loop + vertex -726.693 128.371 22.6286 + vertex -737.218 128.385 21.8678 + vertex -726.575 123.548 21.8917 + endloop + endfacet + facet normal -0.0595219 -0.126083 0.990232 + outer loop + vertex -737.218 128.385 21.8678 + vertex -737.528 123.821 21.2681 + vertex -726.575 123.548 21.8917 + endloop + endfacet + facet normal -0.059504 -0.125071 0.990362 + outer loop + vertex -726.575 123.548 21.8917 + vertex -737.528 123.821 21.2681 + vertex -726.853 118.997 21.3003 + endloop + endfacet + facet normal -0.0597885 -0.125701 0.990265 + outer loop + vertex -737.528 123.821 21.2681 + vertex -737.924 119.437 20.6877 + vertex -726.853 118.997 21.3003 + endloop + endfacet + facet normal -0.0637667 -0.125315 0.990066 + outer loop + vertex -737.528 123.821 21.2681 + vertex -748.492 124.428 20.6388 + vertex -737.924 119.437 20.6877 + endloop + endfacet + facet normal -0.0773751 -0.154177 0.985009 + outer loop + vertex -748.492 124.428 20.6388 + vertex -748.617 119.863 19.9144 + vertex -737.924 119.437 20.6877 + endloop + endfacet + facet normal -0.0774524 -0.15692 0.98457 + outer loop + vertex -737.924 119.437 20.6877 + vertex -748.617 119.863 19.9144 + vertex -738.015 114.876 19.9536 + endloop + endfacet + facet normal -0.0740669 -0.157026 0.984813 + outer loop + vertex -737.924 119.437 20.6877 + vertex -738.015 114.876 19.9536 + vertex -727.252 114.631 20.724 + endloop + endfacet + facet normal -0.0820958 -0.153992 0.984656 + outer loop + vertex -748.492 124.428 20.6388 + vertex -759.09 125.044 19.8516 + vertex -748.617 119.863 19.9144 + endloop + endfacet + facet normal -0.0819381 -0.15059 0.985195 + outer loop + vertex -758.915 129.615 20.5648 + vertex -759.09 125.044 19.8516 + vertex -748.492 124.428 20.6388 + endloop + endfacet + facet normal -0.0682239 -0.122961 0.990064 + outer loop + vertex -748.047 128.813 21.2141 + vertex -758.915 129.615 20.5648 + vertex -748.492 124.428 20.6388 + endloop + endfacet + facet normal -0.0680554 -0.120416 0.990388 + outer loop + vertex -758.406 133.987 21.1313 + vertex -758.915 129.615 20.5648 + vertex -748.047 128.813 21.2141 + endloop + endfacet + facet normal -0.0695137 -0.123343 0.989926 + outer loop + vertex -747.683 133.377 21.8082 + vertex -758.406 133.987 21.1313 + vertex -748.047 128.813 21.2141 + endloop + endfacet + facet normal -0.0646767 -0.123765 0.990202 + outer loop + vertex -747.683 133.377 21.8082 + vertex -748.047 128.813 21.2141 + vertex -737.218 128.385 21.8678 + endloop + endfacet + facet normal -0.0778343 -0.151405 0.985403 + outer loop + vertex -737.253 133.209 22.6062 + vertex -747.683 133.377 21.8082 + vertex -737.218 128.385 21.8678 + endloop + endfacet + facet normal -0.0778107 -0.146193 0.986191 + outer loop + vertex -747.693 138.199 22.5223 + vertex -747.683 133.377 21.8082 + vertex -737.253 133.209 22.6062 + endloop + endfacet + facet normal -0.0824362 -0.146147 0.985822 + outer loop + vertex -747.693 138.199 22.5223 + vertex -757.964 138.537 21.7135 + vertex -747.683 133.377 21.8082 + endloop + endfacet + facet normal -0.0823586 -0.142496 0.986363 + outer loop + vertex -757.841 143.313 22.4138 + vertex -757.964 138.537 21.7135 + vertex -747.693 138.199 22.5223 + endloop + endfacet + facet normal -0.0876152 -0.142298 0.985939 + outer loop + vertex -757.841 143.313 22.4138 + vertex -768.065 143.89 21.5884 + vertex -757.964 138.537 21.7135 + endloop + endfacet + facet normal -0.0739972 -0.116493 0.990431 + outer loop + vertex -768.065 143.89 21.5884 + vertex -768.59 139.342 21.0144 + vertex -757.964 138.537 21.7135 + endloop + endfacet + facet normal -0.0741994 -0.119484 0.99006 + outer loop + vertex -757.964 138.537 21.7135 + vertex -768.59 139.342 21.0144 + vertex -758.406 133.987 21.1313 + endloop + endfacet + facet normal -0.0723185 -0.115895 0.990625 + outer loop + vertex -768.59 139.342 21.0144 + vertex -769.182 134.987 20.4615 + vertex -758.406 133.987 21.1313 + endloop + endfacet + facet normal -0.0773782 -0.115169 0.990328 + outer loop + vertex -768.59 139.342 21.0144 + vertex -779.252 140.531 20.3195 + vertex -769.182 134.987 20.4615 + endloop + endfacet + facet normal -0.0902656 -0.13868 0.986215 + outer loop + vertex -779.252 140.531 20.3195 + vertex -779.603 135.985 19.6481 + vertex -769.182 134.987 20.4615 + endloop + endfacet + facet normal -0.0907849 -0.144865 0.985278 + outer loop + vertex -769.182 134.987 20.4615 + vertex -779.603 135.985 19.6481 + vertex -769.444 130.431 19.7676 + endloop + endfacet + facet normal -0.0858766 -0.145206 0.985668 + outer loop + vertex -769.182 134.987 20.4615 + vertex -769.444 130.431 19.7676 + vertex -758.915 129.615 20.5648 + endloop + endfacet + facet normal -0.0950217 -0.138255 0.985828 + outer loop + vertex -779.252 140.531 20.3195 + vertex -789.551 141.714 19.4927 + vertex -779.603 135.985 19.6481 + endloop + endfacet + facet normal -0.116192 -0.175236 0.977646 + outer loop + vertex -789.551 141.714 19.4927 + vertex -789.517 136.704 18.5987 + vertex -779.603 135.985 19.6481 + endloop + endfacet + facet normal -0.116713 -0.185206 0.975744 + outer loop + vertex -779.603 135.985 19.6481 + vertex -789.517 136.704 18.5987 + vertex -779.465 130.98 18.7146 + endloop + endfacet + facet normal -0.11272 -0.185184 0.976218 + outer loop + vertex -779.603 135.985 19.6481 + vertex -779.465 130.98 18.7146 + vertex -769.444 130.431 19.7676 + endloop + endfacet + facet normal -0.112983 -0.192899 0.974692 + outer loop + vertex -769.444 130.431 19.7676 + vertex -779.465 130.98 18.7146 + vertex -769.183 125.412 18.8045 + endloop + endfacet + facet normal -0.108189 -0.19276 0.975263 + outer loop + vertex -769.444 130.431 19.7676 + vertex -769.183 125.412 18.8045 + vertex -759.09 125.044 19.8516 + endloop + endfacet + facet normal -0.108278 -0.198565 0.974088 + outer loop + vertex -759.09 125.044 19.8516 + vertex -769.183 125.412 18.8045 + vertex -758.751 120.033 18.8676 + endloop + endfacet + facet normal -0.103995 -0.198375 0.974594 + outer loop + vertex -759.09 125.044 19.8516 + vertex -758.751 120.033 18.8676 + vertex -748.617 119.863 19.9144 + endloop + endfacet + facet normal -0.103973 -0.203242 0.973592 + outer loop + vertex -748.617 119.863 19.9144 + vertex -758.751 120.033 18.8676 + vertex -748.25 114.879 18.9132 + endloop + endfacet + facet normal -0.0990858 -0.202995 0.974154 + outer loop + vertex -748.617 119.863 19.9144 + vertex -748.25 114.879 18.9132 + vertex -738.015 114.876 19.9536 + endloop + endfacet + facet normal -0.0990088 -0.206675 0.973387 + outer loop + vertex -738.015 114.876 19.9536 + vertex -748.25 114.879 18.9132 + vertex -737.597 109.896 18.9386 + endloop + endfacet + facet normal -0.0954405 -0.206458 0.97379 + outer loop + vertex -738.015 114.876 19.9536 + vertex -737.597 109.896 18.9386 + vertex -727.316 110.072 19.9836 + endloop + endfacet + facet normal -0.0953382 -0.20912 0.973231 + outer loop + vertex -727.316 110.072 19.9836 + vertex -737.597 109.896 18.9386 + vertex -726.859 105.088 18.9575 + endloop + endfacet + facet normal -0.0911583 -0.208832 0.973694 + outer loop + vertex -727.316 110.072 19.9836 + vertex -726.859 105.088 18.9575 + vertex -716.542 105.437 19.9984 + endloop + endfacet + facet normal -0.0910152 -0.211427 0.973147 + outer loop + vertex -716.542 105.437 19.9984 + vertex -726.859 105.088 18.9575 + vertex -716.122 100.483 18.9612 + endloop + endfacet + facet normal -0.0880211 -0.211239 0.973463 + outer loop + vertex -716.542 105.437 19.9984 + vertex -716.122 100.483 18.9612 + vertex -705.673 100.956 20.0087 + endloop + endfacet + facet normal -0.0879016 -0.213035 0.973082 + outer loop + vertex -705.673 100.956 20.0087 + vertex -716.122 100.483 18.9612 + vertex -705.234 96.0047 18.9643 + endloop + endfacet + facet normal -0.0844052 -0.212802 0.973443 + outer loop + vertex -705.673 100.956 20.0087 + vertex -705.234 96.0047 18.9643 + vertex -694.613 96.577 20.0104 + endloop + endfacet + facet normal -0.0843489 -0.213554 0.973283 + outer loop + vertex -694.613 96.577 20.0104 + vertex -705.234 96.0047 18.9643 + vertex -694.106 91.6117 18.9648 + endloop + endfacet + facet normal -0.0817134 -0.213343 0.973554 + outer loop + vertex -694.613 96.577 20.0104 + vertex -694.106 91.6117 18.9648 + vertex -683.428 92.3111 20.0144 + endloop + endfacet + facet normal -0.0815574 -0.215148 0.97317 + outer loop + vertex -683.428 92.3111 20.0144 + vertex -694.106 91.6117 18.9648 + vertex -682.884 87.3562 18.9645 + endloop + endfacet + facet normal -0.0791757 -0.214938 0.973413 + outer loop + vertex -683.428 92.3111 20.0144 + vertex -682.884 87.3562 18.9645 + vertex -672.259 88.2075 20.0167 + endloop + endfacet + facet normal -0.079081 -0.215874 0.973214 + outer loop + vertex -672.259 88.2075 20.0167 + vertex -682.884 87.3562 18.9645 + vertex -671.667 83.2627 18.968 + endloop + endfacet + facet normal -0.0766853 -0.215638 0.973457 + outer loop + vertex -672.259 88.2075 20.0167 + vertex -671.667 83.2627 18.968 + vertex -661.141 84.3051 20.0281 + endloop + endfacet + facet normal -0.0764671 -0.217449 0.973072 + outer loop + vertex -661.141 84.3051 20.0281 + vertex -671.667 83.2627 18.968 + vertex -660.458 79.3242 18.9687 + endloop + endfacet + facet normal -0.0737101 -0.217131 0.973355 + outer loop + vertex -661.141 84.3051 20.0281 + vertex -660.458 79.3242 18.9687 + vertex -649.909 80.5438 20.0396 + endloop + endfacet + facet normal -0.0737471 -0.216861 0.973413 + outer loop + vertex -649.909 80.5438 20.0396 + vertex -660.458 79.3242 18.9687 + vertex -649.189 75.5122 18.9733 + endloop + endfacet + facet normal -0.0716429 -0.216605 0.973627 + outer loop + vertex -649.909 80.5438 20.0396 + vertex -649.189 75.5122 18.9733 + vertex -638.488 76.8262 20.053 + endloop + endfacet + facet normal -0.0715093 -0.217531 0.97343 + outer loop + vertex -638.488 76.8262 20.053 + vertex -649.189 75.5122 18.9733 + vertex -637.776 71.7743 18.9764 + endloop + endfacet + facet normal -0.070699 -0.217434 0.973511 + outer loop + vertex -638.488 76.8262 20.053 + vertex -637.776 71.7743 18.9764 + vertex -627.351 73.1776 20.0469 + endloop + endfacet + facet normal -0.0703171 -0.219874 0.972991 + outer loop + vertex -627.351 73.1776 20.0469 + vertex -637.776 71.7743 18.9764 + vertex -626.556 68.1382 18.9655 + endloop + endfacet + facet normal -0.0723996 -0.220156 0.972774 + outer loop + vertex -627.351 73.1776 20.0469 + vertex -626.556 68.1382 18.9655 + vertex -617.678 69.7833 19.9985 + endloop + endfacet + facet normal -0.0716182 -0.223875 0.971983 + outer loop + vertex -617.678 69.7833 19.9985 + vertex -626.556 68.1382 18.9655 + vertex -616.658 64.8621 18.9403 + endloop + endfacet + facet normal -0.0753319 -0.224552 0.971546 + outer loop + vertex -617.678 69.7833 19.9985 + vertex -616.658 64.8621 18.9403 + vertex -610.924 66.88 19.8512 + endloop + endfacet + facet normal -0.0731324 -0.230272 0.970374 + outer loop + vertex -610.924 66.88 19.8512 + vertex -616.658 64.8621 18.9403 + vertex -610.166 62.5844 18.889 + endloop + endfacet + facet normal -0.0771136 -0.230874 0.969923 + outer loop + vertex -610.924 66.88 19.8512 + vertex -610.166 62.5844 18.889 + vertex -607.214 64.2598 19.5225 + endloop + endfacet + facet normal -0.119894 -0.175183 0.977208 + outer loop + vertex -789.551 141.714 19.4927 + vertex -799.382 142.63 18.4508 + vertex -789.517 136.704 18.5987 + endloop + endfacet + facet normal -0.119044 -0.163669 0.979306 + outer loop + vertex -799.327 147.681 19.3016 + vertex -799.382 142.63 18.4508 + vertex -789.551 141.714 19.4927 + endloop + endfacet + facet normal -0.0981872 -0.129259 0.986738 + outer loop + vertex -789.127 146.29 20.1343 + vertex -799.327 147.681 19.3016 + vertex -789.551 141.714 19.4927 + endloop + endfacet + facet normal -0.0968894 -0.118885 0.988169 + outer loop + vertex -798.845 152.335 19.9087 + vertex -799.327 147.681 19.3016 + vertex -789.127 146.29 20.1343 + endloop + endfacet + facet normal -0.0863186 -0.101783 0.991055 + outer loop + vertex -788.48 150.781 20.652 + vertex -798.845 152.335 19.9087 + vertex -789.127 146.29 20.1343 + endloop + endfacet + facet normal -0.0814932 -0.102517 0.991388 + outer loop + vertex -788.48 150.781 20.652 + vertex -789.127 146.29 20.1343 + vertex -778.603 144.913 20.8571 + endloop + endfacet + facet normal -0.0866875 -0.111308 0.989998 + outer loop + vertex -778.083 149.552 21.4242 + vertex -788.48 150.781 20.652 + vertex -778.603 144.913 20.8571 + endloop + endfacet + facet normal -0.079636 -0.112159 0.990494 + outer loop + vertex -778.083 149.552 21.4242 + vertex -778.603 144.913 20.8571 + vertex -768.065 143.89 21.5884 + endloop + endfacet + facet normal -0.0960459 -0.141341 0.985291 + outer loop + vertex -767.861 148.702 22.2988 + vertex -778.083 149.552 21.4242 + vertex -768.065 143.89 21.5884 + endloop + endfacet + facet normal -0.0959171 -0.139508 0.985564 + outer loop + vertex -777.956 154.506 22.1377 + vertex -778.083 149.552 21.4242 + vertex -767.861 148.702 22.2988 + endloop + endfacet + facet normal -0.106906 -0.139072 0.984495 + outer loop + vertex -777.956 154.506 22.1377 + vertex -788.057 155.624 21.1988 + vertex -778.083 149.552 21.4242 + endloop + endfacet + facet normal -0.10605 -0.130249 0.985793 + outer loop + vertex -788.237 160.801 21.8634 + vertex -788.057 155.624 21.1988 + vertex -777.956 154.506 22.1377 + endloop + endfacet + facet normal -0.116614 -0.130461 0.984572 + outer loop + vertex -788.237 160.801 21.8634 + vertex -797.72 162.115 20.9145 + vertex -788.057 155.624 21.1988 + endloop + endfacet + facet normal -0.0906939 -0.0915666 0.99166 + outer loop + vertex -797.72 162.115 20.9145 + vertex -798.204 156.99 20.3969 + vertex -788.057 155.624 21.1988 + endloop + endfacet + facet normal -0.0922306 -0.103773 0.990315 + outer loop + vertex -788.057 155.624 21.1988 + vertex -798.204 156.99 20.3969 + vertex -788.48 150.781 20.652 + endloop + endfacet + facet normal -0.0928541 -0.0913444 0.991481 + outer loop + vertex -797.72 162.115 20.9145 + vertex -807.748 163.457 20.099 + vertex -798.204 156.99 20.3969 + endloop + endfacet + facet normal -0.086132 -0.0813574 0.992956 + outer loop + vertex -807.748 163.457 20.099 + vertex -808.407 158.685 19.6508 + vertex -798.204 156.99 20.3969 + endloop + endfacet + facet normal -0.0878099 -0.0919285 0.991886 + outer loop + vertex -798.204 156.99 20.3969 + vertex -808.407 158.685 19.6508 + vertex -798.845 152.335 19.9087 + endloop + endfacet + facet normal -0.0973123 -0.106331 0.989557 + outer loop + vertex -808.407 158.685 19.6508 + vertex -808.977 153.949 19.0859 + vertex -798.845 152.335 19.9087 + endloop + endfacet + facet normal -0.0981088 -0.106228 0.98949 + outer loop + vertex -808.407 158.685 19.6508 + vertex -818.437 160.507 18.8518 + vertex -808.977 153.949 19.0859 + endloop + endfacet + facet normal -0.11939 -0.137151 0.983329 + outer loop + vertex -818.437 160.507 18.8518 + vertex -818.824 155.418 18.0951 + vertex -808.977 153.949 19.0859 + endloop + endfacet + facet normal -0.121273 -0.151347 0.981013 + outer loop + vertex -808.977 153.949 19.0859 + vertex -818.824 155.418 18.0951 + vertex -809.152 148.855 18.2783 + endloop + endfacet + facet normal -0.120281 -0.151399 0.981127 + outer loop + vertex -808.977 153.949 19.0859 + vertex -809.152 148.855 18.2783 + vertex -799.327 147.681 19.3016 + endloop + endfacet + facet normal -0.118602 -0.137224 0.983414 + outer loop + vertex -818.437 160.507 18.8518 + vertex -828.241 162.237 17.9109 + vertex -818.824 155.418 18.0951 + endloop + endfacet + facet normal -0.116635 -0.125065 0.985269 + outer loop + vertex -827.62 167.264 18.6226 + vertex -828.241 162.237 17.9109 + vertex -818.437 160.507 18.8518 + endloop + endfacet + facet normal -0.0950162 -0.095498 0.990884 + outer loop + vertex -817.752 165.268 19.3764 + vertex -827.62 167.264 18.6226 + vertex -818.437 160.507 18.8518 + endloop + endfacet + facet normal -0.0928826 -0.0844973 0.992085 + outer loop + vertex -826.815 172.01 19.1022 + vertex -827.62 167.264 18.6226 + vertex -817.752 165.268 19.3764 + endloop + endfacet + facet normal -0.083284 -0.0715191 0.993956 + outer loop + vertex -817.031 170.068 19.7822 + vertex -826.815 172.01 19.1022 + vertex -817.752 165.268 19.3764 + endloop + endfacet + facet normal -0.084685 -0.0713 0.993853 + outer loop + vertex -817.031 170.068 19.7822 + vertex -817.752 165.268 19.3764 + vertex -807.748 163.457 20.099 + endloop + endfacet + facet normal -0.0911572 -0.0804496 0.992582 + outer loop + vertex -807.336 168.55 20.5496 + vertex -817.031 170.068 19.7822 + vertex -807.748 163.457 20.099 + endloop + endfacet + facet normal -0.0902225 -0.0741898 0.993154 + outer loop + vertex -816.471 175.182 20.2151 + vertex -817.031 170.068 19.7822 + vertex -807.336 168.55 20.5496 + endloop + endfacet + facet normal -0.113321 -0.106277 0.987858 + outer loop + vertex -816.471 175.182 20.2151 + vertex -807.336 168.55 20.5496 + vertex -808.844 173.142 20.8706 + endloop + endfacet + facet normal -0.114115 -0.109386 0.987427 + outer loop + vertex -812.891 176.625 20.7887 + vertex -816.471 175.182 20.2151 + vertex -808.844 173.142 20.8706 + endloop + endfacet + facet normal -0.117074 -0.102215 0.987849 + outer loop + vertex -812.891 176.625 20.7887 + vertex -817.744 179.759 20.5378 + vertex -816.471 175.182 20.2151 + endloop + endfacet + facet normal -0.115225 -0.10172 0.988118 + outer loop + vertex -825.243 181.898 19.8836 + vertex -816.471 175.182 20.2151 + vertex -817.744 179.759 20.5378 + endloop + endfacet + facet normal -0.115078 -0.101185 0.98819 + outer loop + vertex -821.621 183.287 20.4476 + vertex -825.243 181.898 19.8836 + vertex -817.744 179.759 20.5378 + endloop + endfacet + facet normal -0.117276 -0.0955753 0.98849 + outer loop + vertex -821.621 183.287 20.4476 + vertex -826.292 186.463 20.2005 + vertex -825.243 181.898 19.8836 + endloop + endfacet + facet normal -0.112267 -0.0944717 0.989177 + outer loop + vertex -833.657 188.732 19.5813 + vertex -825.243 181.898 19.8836 + vertex -826.292 186.463 20.2005 + endloop + endfacet + facet normal -0.112247 -0.0944036 0.989186 + outer loop + vertex -829.941 189.983 20.1224 + vertex -833.657 188.732 19.5813 + vertex -826.292 186.463 20.2005 + endloop + endfacet + facet normal -0.113152 -0.0917779 0.98933 + outer loop + vertex -829.941 189.983 20.1224 + vertex -834.414 193.193 19.9086 + vertex -833.657 188.732 19.5813 + endloop + endfacet + facet normal -0.109932 -0.091262 0.98974 + outer loop + vertex -841.661 195.749 19.3393 + vertex -833.657 188.732 19.5813 + vertex -834.414 193.193 19.9086 + endloop + endfacet + facet normal -0.111395 -0.0955366 0.989173 + outer loop + vertex -837.882 196.755 19.862 + vertex -841.661 195.749 19.3393 + vertex -834.414 193.193 19.9086 + endloop + endfacet + facet normal -0.111968 -0.0934524 0.989308 + outer loop + vertex -837.882 196.755 19.862 + vertex -842.24 200.136 19.6883 + vertex -841.661 195.749 19.3393 + endloop + endfacet + facet normal -0.112652 -0.0935358 0.989222 + outer loop + vertex -848.988 202.917 19.1826 + vertex -841.661 195.749 19.3393 + vertex -842.24 200.136 19.6883 + endloop + endfacet + facet normal -0.114758 -0.0987848 0.98847 + outer loop + vertex -845.628 203.841 19.6652 + vertex -848.988 202.917 19.1826 + vertex -842.24 200.136 19.6883 + endloop + endfacet + facet normal -0.115911 -0.0947312 0.988732 + outer loop + vertex -845.628 203.841 19.6652 + vertex -849.68 207.261 19.5178 + vertex -848.988 202.917 19.1826 + endloop + endfacet + facet normal -0.115314 -0.0946421 0.98881 + outer loop + vertex -854.628 209.239 19.1301 + vertex -848.988 202.917 19.1826 + vertex -849.68 207.261 19.5178 + endloop + endfacet + facet normal -0.119295 -0.104896 0.987302 + outer loop + vertex -852.872 210.915 19.5203 + vertex -854.628 209.239 19.1301 + vertex -849.68 207.261 19.5178 + endloop + endfacet + facet normal -0.116883 -0.107429 0.987318 + outer loop + vertex -852.872 210.915 19.5203 + vertex -856.428 213.816 19.4149 + vertex -854.628 209.239 19.1301 + endloop + endfacet + facet normal -0.102665 -0.101971 0.989476 + outer loop + vertex -856.428 213.816 19.4149 + vertex -860.521 213.567 18.9647 + vertex -854.628 209.239 19.1301 + endloop + endfacet + facet normal -0.102921 -0.0983637 0.989814 + outer loop + vertex -859.276 217.18 19.4532 + vertex -860.521 213.567 18.9647 + vertex -856.428 213.816 19.4149 + endloop + endfacet + facet normal -0.111818 -0.105799 0.988081 + outer loop + vertex -803.82 170.02 21.1049 + vertex -808.844 173.142 20.8706 + vertex -807.336 168.55 20.5496 + endloop + endfacet + facet normal -0.109476 -0.111271 0.987742 + outer loop + vertex -803.82 170.02 21.1049 + vertex -807.336 168.55 20.5496 + vertex -799.591 166.521 21.1794 + endloop + endfacet + facet normal -0.107979 -0.105304 0.98856 + outer loop + vertex -807.336 168.55 20.5496 + vertex -797.72 162.115 20.9145 + vertex -799.591 166.521 21.1794 + endloop + endfacet + facet normal -0.10779 -0.105225 0.988589 + outer loop + vertex -794.976 163.731 21.3857 + vertex -799.591 166.521 21.1794 + vertex -797.72 162.115 20.9145 + endloop + endfacet + facet normal -0.0902039 -0.074192 0.993156 + outer loop + vertex -816.471 175.182 20.2151 + vertex -825.987 176.813 19.4727 + vertex -817.031 170.068 19.7822 + endloop + endfacet + facet normal -0.0890647 -0.0672757 0.993751 + outer loop + vertex -825.243 181.898 19.8836 + vertex -825.987 176.813 19.4727 + vertex -816.471 175.182 20.2151 + endloop + endfacet + facet normal -0.0869333 -0.0676012 0.993918 + outer loop + vertex -825.243 181.898 19.8836 + vertex -834.643 183.721 19.1854 + vertex -825.987 176.813 19.4727 + endloop + endfacet + facet normal -0.0772463 -0.0553987 0.995472 + outer loop + vertex -834.643 183.721 19.1854 + vertex -835.612 178.933 18.8438 + vertex -825.987 176.813 19.4727 + endloop + endfacet + facet normal -0.0789133 -0.0631414 0.99488 + outer loop + vertex -825.987 176.813 19.4727 + vertex -835.612 178.933 18.8438 + vertex -826.815 172.01 19.1022 + endloop + endfacet + facet normal -0.0877773 -0.0744617 0.993353 + outer loop + vertex -835.612 178.933 18.8438 + vertex -836.501 174.176 18.4087 + vertex -826.815 172.01 19.1022 + endloop + endfacet + facet normal -0.0846463 -0.0750674 0.993579 + outer loop + vertex -835.612 178.933 18.8438 + vertex -845.166 181.332 18.2111 + vertex -836.501 174.176 18.4087 + endloop + endfacet + facet normal -0.106384 -0.101514 0.98913 + outer loop + vertex -845.166 181.332 18.2111 + vertex -845.931 176.25 17.6072 + vertex -836.501 174.176 18.4087 + endloop + endfacet + facet normal -0.108819 -0.113184 0.987597 + outer loop + vertex -836.501 174.176 18.4087 + vertex -845.931 176.25 17.6072 + vertex -837.246 169.176 17.7535 + endloop + endfacet + facet normal -0.111536 -0.112746 0.987344 + outer loop + vertex -836.501 174.176 18.4087 + vertex -837.246 169.176 17.7535 + vertex -827.62 167.264 18.6226 + endloop + endfacet + facet normal -0.105236 -0.101699 0.989233 + outer loop + vertex -845.166 181.332 18.2111 + vertex -854.597 183.747 17.4561 + vertex -845.931 176.25 17.6072 + endloop + endfacet + facet normal -0.103425 -0.0943409 0.990153 + outer loop + vertex -853.435 188.769 18.0559 + vertex -854.597 183.747 17.4561 + vertex -845.166 181.332 18.2111 + endloop + endfacet + facet normal -0.0792079 -0.0673218 0.994582 + outer loop + vertex -844.112 186.099 18.6176 + vertex -853.435 188.769 18.0559 + vertex -845.166 181.332 18.2111 + endloop + endfacet + facet normal -0.0773426 -0.0606884 0.995156 + outer loop + vertex -851.966 193.531 18.4605 + vertex -853.435 188.769 18.0559 + vertex -844.112 186.099 18.6176 + endloop + endfacet + facet normal -0.0685969 -0.0514229 0.996318 + outer loop + vertex -842.896 190.869 18.9476 + vertex -851.966 193.531 18.4605 + vertex -844.112 186.099 18.6176 + endloop + endfacet + facet normal -0.0723915 -0.0504404 0.9961 + outer loop + vertex -842.896 190.869 18.9476 + vertex -844.112 186.099 18.6176 + vertex -834.643 183.721 19.1854 + endloop + endfacet + facet normal -0.0826378 -0.0623198 0.994629 + outer loop + vertex -833.657 188.732 19.5813 + vertex -842.896 190.869 18.9476 + vertex -834.643 183.721 19.1854 + endloop + endfacet + facet normal -0.0819177 -0.0591322 0.994883 + outer loop + vertex -841.661 195.749 19.3393 + vertex -842.896 190.869 18.9476 + vertex -833.657 188.732 19.5813 + endloop + endfacet + facet normal -0.079524 -0.0597506 0.995041 + outer loop + vertex -841.661 195.749 19.3393 + vertex -850.393 198.259 18.7921 + vertex -842.896 190.869 18.9476 + endloop + endfacet + facet normal -0.0794409 -0.0594562 0.995065 + outer loop + vertex -848.988 202.917 19.1826 + vertex -850.393 198.259 18.7921 + vertex -841.661 195.749 19.3393 + endloop + endfacet + facet normal -0.0778963 -0.05993 0.995159 + outer loop + vertex -848.988 202.917 19.1826 + vertex -856.465 205.726 18.7666 + vertex -850.393 198.259 18.7921 + endloop + endfacet + facet normal -0.0623301 -0.0472674 0.996936 + outer loop + vertex -856.465 205.726 18.7666 + vertex -858.605 201.131 18.4149 + vertex -850.393 198.259 18.7921 + endloop + endfacet + facet normal -0.0629269 -0.0489892 0.996815 + outer loop + vertex -850.393 198.259 18.7921 + vertex -858.605 201.131 18.4149 + vertex -851.966 193.531 18.4605 + endloop + endfacet + facet normal -0.0703768 -0.055502 0.995975 + outer loop + vertex -858.605 201.131 18.4149 + vertex -860.765 196.267 17.9912 + vertex -851.966 193.531 18.4605 + endloop + endfacet + facet normal -0.0625747 -0.0589948 0.996295 + outer loop + vertex -860.765 196.267 17.9912 + vertex -858.605 201.131 18.4149 + vertex -866.936 204.044 18.0642 + endloop + endfacet + facet normal -0.0874517 -0.0787026 0.993055 + outer loop + vertex -866.936 204.044 18.0642 + vertex -869.353 198.16 17.385 + vertex -860.765 196.267 17.9912 + endloop + endfacet + facet normal -0.0894355 -0.0880087 0.992097 + outer loop + vertex -862.573 191.375 17.3942 + vertex -860.765 196.267 17.9912 + vertex -869.353 198.16 17.385 + endloop + endfacet + facet normal -0.0961798 -0.0854668 0.991688 + outer loop + vertex -860.765 196.267 17.9912 + vertex -862.573 191.375 17.3942 + vertex -853.435 188.769 18.0559 + endloop + endfacet + facet normal -0.0599687 -0.0514711 0.996872 + outer loop + vertex -863.393 208.75 18.5202 + vertex -866.936 204.044 18.0642 + vertex -858.605 201.131 18.4149 + endloop + endfacet + facet normal -0.0528291 -0.0568553 0.996984 + outer loop + vertex -866.936 204.044 18.0642 + vertex -863.393 208.75 18.5202 + vertex -869.902 211.372 18.3249 + endloop + endfacet + facet normal -0.0552567 -0.0578313 0.996796 + outer loop + vertex -869.902 211.372 18.3249 + vertex -872.694 208.231 17.9879 + vertex -866.936 204.044 18.0642 + endloop + endfacet + facet normal -0.0703304 -0.0786066 0.994422 + outer loop + vertex -872.694 208.231 17.9879 + vertex -873.163 203.98 17.6187 + vertex -866.936 204.044 18.0642 + endloop + endfacet + facet normal -0.0702136 -0.0858751 0.993829 + outer loop + vertex -869.353 198.16 17.385 + vertex -866.936 204.044 18.0642 + vertex -873.163 203.98 17.6187 + endloop + endfacet + facet normal -0.0787408 -0.0776305 0.993868 + outer loop + vertex -872.694 208.231 17.9879 + vertex -877.978 208.676 17.604 + vertex -873.163 203.98 17.6187 + endloop + endfacet + facet normal -0.0783262 -0.0723397 0.9943 + outer loop + vertex -876.299 213.346 18.076 + vertex -877.978 208.676 17.604 + vertex -872.694 208.231 17.9879 + endloop + endfacet + facet normal -0.0774778 -0.0726492 0.994344 + outer loop + vertex -876.299 213.346 18.076 + vertex -883.504 214.992 17.6348 + vertex -877.978 208.676 17.604 + endloop + endfacet + facet normal -0.0777257 -0.0737617 0.994242 + outer loop + vertex -881.393 219.81 18.1574 + vertex -883.504 214.992 17.6348 + vertex -876.299 213.346 18.076 + endloop + endfacet + facet normal -0.0563018 -0.0569121 0.99679 + outer loop + vertex -873.884 217.808 18.4672 + vertex -881.393 219.81 18.1574 + vertex -876.299 213.346 18.076 + endloop + endfacet + facet normal -0.0563326 -0.0568954 0.99679 + outer loop + vertex -873.884 217.808 18.4672 + vertex -876.299 213.346 18.076 + vertex -869.902 211.372 18.3249 + endloop + endfacet + facet normal -0.0512896 -0.053785 0.997234 + outer loop + vertex -866.78 216.177 18.7446 + vertex -873.884 217.808 18.4672 + vertex -869.902 211.372 18.3249 + endloop + endfacet + facet normal -0.0525514 -0.0593457 0.996853 + outer loop + vertex -871.177 222.455 18.8866 + vertex -873.884 217.808 18.4672 + vertex -866.78 216.177 18.7446 + endloop + endfacet + facet normal -0.0705741 -0.0719238 0.99491 + outer loop + vertex -871.177 222.455 18.8866 + vertex -866.78 216.177 18.7446 + vertex -865.597 220.799 19.1626 + endloop + endfacet + facet normal -0.0739222 -0.0833939 0.993771 + outer loop + vertex -867.184 223.571 19.2773 + vertex -871.177 222.455 18.8866 + vertex -865.597 220.799 19.1626 + endloop + endfacet + facet normal -0.0754524 -0.0780326 0.994091 + outer loop + vertex -867.184 223.571 19.2773 + vertex -870.328 226.376 19.2588 + vertex -871.177 222.455 18.8866 + endloop + endfacet + facet normal -0.0742633 -0.0782965 0.99416 + outer loop + vertex -876.674 228.923 18.9852 + vertex -871.177 222.455 18.8866 + vertex -870.328 226.376 19.2588 + endloop + endfacet + facet normal -0.0746831 -0.0793552 0.994045 + outer loop + vertex -872.823 229.718 19.3381 + vertex -876.674 228.923 18.9852 + vertex -870.328 226.376 19.2588 + endloop + endfacet + facet normal -0.0745973 -0.0797589 0.994019 + outer loop + vertex -872.823 229.718 19.3381 + vertex -876.367 233.027 19.3377 + vertex -876.674 228.923 18.9852 + endloop + endfacet + facet normal -0.0733863 -0.0798567 0.994101 + outer loop + vertex -882.594 235.904 19.1091 + vertex -876.674 228.923 18.9852 + vertex -876.367 233.027 19.3377 + endloop + endfacet + facet normal -0.0758983 -0.0853448 0.993456 + outer loop + vertex -878.871 236.579 19.4515 + vertex -882.594 235.904 19.1091 + vertex -876.367 233.027 19.3377 + endloop + endfacet + facet normal -0.0762954 -0.0832282 0.993606 + outer loop + vertex -878.871 236.579 19.4515 + vertex -882.166 239.987 19.484 + vertex -882.594 235.904 19.1091 + endloop + endfacet + facet normal -0.0780896 -0.0830289 0.993483 + outer loop + vertex -888.216 243.127 19.2708 + vertex -882.594 235.904 19.1091 + vertex -882.166 239.987 19.484 + endloop + endfacet + facet normal -0.0816327 -0.0899163 0.992598 + outer loop + vertex -884.436 243.601 19.6246 + vertex -888.216 243.127 19.2708 + vertex -882.166 239.987 19.484 + endloop + endfacet + facet normal -0.0822597 -0.0851825 0.992964 + outer loop + vertex -884.436 243.601 19.6246 + vertex -887.559 247.14 19.6695 + vertex -888.216 243.127 19.2708 + endloop + endfacet + facet normal -0.0851021 -0.0846971 0.992766 + outer loop + vertex -893.4 250.506 19.456 + vertex -888.216 243.127 19.2708 + vertex -887.559 247.14 19.6695 + endloop + endfacet + facet normal -0.0872139 -0.088393 0.99226 + outer loop + vertex -889.651 250.819 19.8133 + vertex -893.4 250.506 19.456 + vertex -887.559 247.14 19.6695 + endloop + endfacet + facet normal -0.0875776 -0.0843926 0.992576 + outer loop + vertex -889.651 250.819 19.8133 + vertex -892.545 254.419 19.8641 + vertex -893.4 250.506 19.456 + endloop + endfacet + facet normal -0.0912284 -0.0835681 0.992317 + outer loop + vertex -898.103 257.995 19.6543 + vertex -893.4 250.506 19.456 + vertex -892.545 254.419 19.8641 + endloop + endfacet + facet normal -0.0937144 -0.0874642 0.99175 + outer loop + vertex -894.393 258.101 20.0142 + vertex -898.103 257.995 19.6543 + vertex -892.545 254.419 19.8641 + endloop + endfacet + facet normal -0.0938656 -0.0833392 0.992091 + outer loop + vertex -894.393 258.101 20.0142 + vertex -897.036 261.771 20.0724 + vertex -898.103 257.995 19.6543 + endloop + endfacet + facet normal -0.0992794 -0.0817665 0.991694 + outer loop + vertex -902.339 265.678 19.8636 + vertex -898.103 257.995 19.6543 + vertex -897.036 261.771 20.0724 + endloop + endfacet + facet normal -0.103489 -0.0875295 0.990772 + outer loop + vertex -898.656 265.513 20.2337 + vertex -902.339 265.678 19.8636 + vertex -897.036 261.771 20.0724 + endloop + endfacet + facet normal -0.103256 -0.0810379 0.991348 + outer loop + vertex -898.656 265.513 20.2337 + vertex -901.097 269.386 20.2961 + vertex -902.339 265.678 19.8636 + endloop + endfacet + facet normal -0.110229 -0.0786371 0.990791 + outer loop + vertex -906.174 273.733 20.0763 + vertex -902.339 265.678 19.8636 + vertex -901.097 269.386 20.2961 + endloop + endfacet + facet normal -0.114032 -0.0831193 0.989994 + outer loop + vertex -902.54 273.32 20.4603 + vertex -906.174 273.733 20.0763 + vertex -901.097 269.386 20.2961 + endloop + endfacet + facet normal -0.113372 -0.0767512 0.990584 + outer loop + vertex -902.54 273.32 20.4603 + vertex -904.785 277.495 20.5268 + vertex -906.174 273.733 20.0763 + endloop + endfacet + facet normal -0.121984 -0.073478 0.989809 + outer loop + vertex -909.541 282.267 20.295 + vertex -906.174 273.733 20.0763 + vertex -904.785 277.495 20.5268 + endloop + endfacet + facet normal -0.126552 -0.078075 0.988883 + outer loop + vertex -906.027 281.673 20.6977 + vertex -909.541 282.267 20.295 + vertex -904.785 277.495 20.5268 + endloop + endfacet + facet normal -0.125243 -0.0698017 0.989668 + outer loop + vertex -906.027 281.673 20.6977 + vertex -907.997 286.077 20.759 + vertex -909.541 282.267 20.295 + endloop + endfacet + facet normal -0.133986 -0.0661506 0.988773 + outer loop + vertex -912.29 291.07 20.5114 + vertex -909.541 282.267 20.295 + vertex -907.997 286.077 20.759 + endloop + endfacet + facet normal -0.137222 -0.0689642 0.988137 + outer loop + vertex -908.964 290.385 20.9254 + vertex -912.29 291.07 20.5114 + vertex -907.997 286.077 20.759 + endloop + endfacet + facet normal -0.13557 -0.0604609 0.988921 + outer loop + vertex -908.964 290.385 20.9254 + vertex -910.576 294.845 20.9771 + vertex -912.29 291.07 20.5114 + endloop + endfacet + facet normal -0.144307 -0.0563737 0.987926 + outer loop + vertex -914.339 299.895 20.7157 + vertex -912.29 291.07 20.5114 + vertex -910.576 294.845 20.9771 + endloop + endfacet + facet normal -0.145702 -0.0574269 0.98766 + outer loop + vertex -911.21 299.118 21.1321 + vertex -914.339 299.895 20.7157 + vertex -910.576 294.845 20.9771 + endloop + endfacet + facet normal -0.143556 -0.0483493 0.98846 + outer loop + vertex -911.21 299.118 21.1321 + vertex -912.443 303.559 21.1702 + vertex -914.339 299.895 20.7157 + endloop + endfacet + facet normal -0.152476 -0.0435969 0.987345 + outer loop + vertex -915.779 308.829 20.8878 + vertex -914.339 299.895 20.7157 + vertex -912.443 303.559 21.1702 + endloop + endfacet + facet normal -0.15458 -0.0449492 0.986957 + outer loop + vertex -912.728 307.819 21.3196 + vertex -915.779 308.829 20.8878 + vertex -912.443 303.559 21.1702 + endloop + endfacet + facet normal -0.151458 -0.0351442 0.987839 + outer loop + vertex -912.728 307.819 21.3196 + vertex -913.596 312.402 21.3495 + vertex -915.779 308.829 20.8878 + endloop + endfacet + facet normal -0.160384 -0.0295331 0.986613 + outer loop + vertex -916.509 318.065 21.0455 + vertex -915.779 308.829 20.8878 + vertex -913.596 312.402 21.3495 + endloop + endfacet + facet normal -0.163668 -0.0312538 0.98602 + outer loop + vertex -913.571 316.757 21.4917 + vertex -916.509 318.065 21.0455 + vertex -913.596 312.402 21.3495 + endloop + endfacet + facet normal -0.160189 -0.0231734 0.986814 + outer loop + vertex -913.571 316.757 21.4917 + vertex -914.147 321.469 21.5088 + vertex -916.509 318.065 21.0455 + endloop + endfacet + facet normal -0.169424 -0.0165724 0.985404 + outer loop + vertex -916.671 327.485 21.1761 + vertex -916.509 318.065 21.0455 + vertex -914.147 321.469 21.5088 + endloop + endfacet + facet normal -0.170634 -0.0170918 0.985186 + outer loop + vertex -913.923 325.941 21.6252 + vertex -916.671 327.485 21.1761 + vertex -914.147 321.469 21.5088 + endloop + endfacet + facet normal -0.166863 -0.0101678 0.985928 + outer loop + vertex -913.923 325.941 21.6252 + vertex -914.312 331.218 21.6138 + vertex -916.671 327.485 21.1761 + endloop + endfacet + facet normal -0.173534 -0.00582195 0.984811 + outer loop + vertex -916.752 336.724 21.2165 + vertex -916.671 327.485 21.1761 + vertex -914.312 331.218 21.6138 + endloop + endfacet + facet normal -0.172031 -0.00513682 0.985078 + outer loop + vertex -913.823 338.135 21.7353 + vertex -916.752 336.724 21.2165 + vertex -914.312 331.218 21.6138 + endloop + endfacet + facet normal -0.17654 0.00451544 0.984283 + outer loop + vertex -913.823 338.135 21.7353 + vertex -915.843 345.401 21.3396 + vertex -916.752 336.724 21.2165 + endloop + endfacet + facet normal -0.178327 0.00470704 0.98396 + outer loop + vertex -915.843 345.401 21.3396 + vertex -919.213 344.1 20.7352 + vertex -916.752 336.724 21.2165 + endloop + endfacet + facet normal -0.175022 0.00584796 0.984547 + outer loop + vertex -916.752 336.724 21.2165 + vertex -919.213 344.1 20.7352 + vertex -920 334.674 20.6513 + endloop + endfacet + facet normal -0.183029 0.0173554 0.982954 + outer loop + vertex -915.843 345.401 21.3396 + vertex -917.947 353.467 20.8055 + vertex -919.213 344.1 20.7352 + endloop + endfacet + facet normal -0.188679 0.0158129 0.981911 + outer loop + vertex -914.474 354.633 21.4541 + vertex -917.947 353.467 20.8055 + vertex -915.843 345.401 21.3396 + endloop + endfacet + facet normal -0.197496 0.0171429 0.980154 + outer loop + vertex -912.004 345.982 22.103 + vertex -914.474 354.633 21.4541 + vertex -915.843 345.401 21.3396 + endloop + endfacet + facet normal -0.202649 0.0155951 0.979127 + outer loop + vertex -910.805 356.252 22.1876 + vertex -914.474 354.633 21.4541 + vertex -912.004 345.982 22.103 + endloop + endfacet + facet normal -0.20762 0.0274431 0.977825 + outer loop + vertex -910.805 356.252 22.1876 + vertex -912.915 364.22 21.5159 + vertex -914.474 354.633 21.4541 + endloop + endfacet + facet normal -0.195583 0.0254704 0.980356 + outer loop + vertex -912.915 364.22 21.5159 + vertex -916.323 363.016 20.8673 + vertex -914.474 354.633 21.4541 + endloop + endfacet + facet normal -0.198676 0.0347173 0.97945 + outer loop + vertex -912.915 364.22 21.5159 + vertex -914.372 372.644 20.9219 + vertex -916.323 363.016 20.8673 + endloop + endfacet + facet normal -0.20187 0.0341205 0.978818 + outer loop + vertex -911.081 373.677 21.5645 + vertex -914.372 372.644 20.9219 + vertex -912.915 364.22 21.5159 + endloop + endfacet + facet normal -0.211718 0.0360416 0.976666 + outer loop + vertex -909.307 365.679 22.2442 + vertex -911.081 373.677 21.5645 + vertex -912.915 364.22 21.5159 + endloop + endfacet + facet normal -0.211879 0.0360032 0.976633 + outer loop + vertex -907.519 374.953 22.2904 + vertex -911.081 373.677 21.5645 + vertex -909.307 365.679 22.2442 + endloop + endfacet + facet normal -0.214531 0.0439202 0.975729 + outer loop + vertex -907.519 374.953 22.2904 + vertex -908.973 383.047 21.6063 + vertex -911.081 373.677 21.5645 + endloop + endfacet + facet normal -0.204973 0.0417603 0.977876 + outer loop + vertex -908.973 383.047 21.6063 + vertex -912.14 382.202 20.9785 + vertex -911.081 373.677 21.5645 + endloop + endfacet + facet normal -0.206938 0.0497063 0.977091 + outer loop + vertex -908.973 383.047 21.6063 + vertex -909.675 391.636 21.0207 + vertex -912.14 382.202 20.9785 + endloop + endfacet + facet normal -0.20896 0.0495125 0.97667 + outer loop + vertex -906.652 392.327 21.6323 + vertex -909.675 391.636 21.0207 + vertex -908.973 383.047 21.6063 + endloop + endfacet + facet normal -0.216124 0.0513085 0.975017 + outer loop + vertex -905.48 384.195 22.3202 + vertex -906.652 392.327 21.6323 + vertex -908.973 383.047 21.6063 + endloop + endfacet + facet normal -0.216621 0.0512277 0.974911 + outer loop + vertex -903.234 393.371 22.3371 + vertex -906.652 392.327 21.6323 + vertex -905.48 384.195 22.3202 + endloop + endfacet + facet normal -0.218631 0.0583855 0.974059 + outer loop + vertex -903.234 393.371 22.3371 + vertex -904.136 401.53 21.6456 + vertex -906.652 392.327 21.6323 + endloop + endfacet + facet normal -0.2145 0.0572544 0.975044 + outer loop + vertex -904.136 401.53 21.6456 + vertex -907.04 400.937 21.0416 + vertex -906.652 392.327 21.6323 + endloop + endfacet + facet normal -0.216 0.0654645 0.974196 + outer loop + vertex -904.136 401.53 21.6456 + vertex -904.235 410.137 21.0453 + vertex -907.04 400.937 21.0416 + endloop + endfacet + facet normal -0.223998 0.0652477 0.972403 + outer loop + vertex -901.449 410.674 21.6509 + vertex -904.235 410.137 21.0453 + vertex -904.136 401.53 21.6456 + endloop + endfacet + facet normal -0.224023 0.0652552 0.972397 + outer loop + vertex -900.807 402.483 22.3484 + vertex -901.449 410.674 21.6509 + vertex -904.136 401.53 21.6456 + endloop + endfacet + facet normal -0.230266 0.0646455 0.970978 + outer loop + vertex -898.212 411.584 22.3579 + vertex -901.449 410.674 21.6509 + vertex -900.807 402.483 22.3484 + endloop + endfacet + facet normal -0.232144 0.0720798 0.970007 + outer loop + vertex -898.212 411.584 22.3579 + vertex -898.62 419.781 21.6512 + vertex -901.449 410.674 21.6509 + endloop + endfacet + facet normal -0.235086 0.0729936 0.96923 + outer loop + vertex -898.62 419.781 21.6512 + vertex -901.275 419.283 21.0448 + vertex -901.449 410.674 21.6509 + endloop + endfacet + facet normal -0.236176 0.0797806 0.96843 + outer loop + vertex -898.62 419.781 21.6512 + vertex -898.174 428.412 21.049 + vertex -901.275 419.283 21.0448 + endloop + endfacet + facet normal -0.245423 0.0800967 0.966102 + outer loop + vertex -895.666 428.851 21.6496 + vertex -898.174 428.412 21.049 + vertex -898.62 419.781 21.6512 + endloop + endfacet + facet normal -0.240999 0.078656 0.967333 + outer loop + vertex -895.479 420.674 22.3611 + vertex -895.666 428.851 21.6496 + vertex -898.62 419.781 21.6512 + endloop + endfacet + facet normal -0.249078 0.0782956 0.965313 + outer loop + vertex -892.659 429.671 22.359 + vertex -895.666 428.851 21.6496 + vertex -895.479 420.674 22.3611 + endloop + endfacet + facet normal -0.250708 0.0851441 0.964311 + outer loop + vertex -892.659 429.671 22.359 + vertex -892.632 437.872 21.642 + vertex -895.666 428.851 21.6496 + endloop + endfacet + facet normal -0.252013 0.0855827 0.963932 + outer loop + vertex -892.632 437.872 21.642 + vertex -894.974 437.523 21.0606 + vertex -895.666 428.851 21.6496 + endloop + endfacet + facet normal -0.25271 0.0914614 0.96321 + outer loop + vertex -892.632 437.872 21.642 + vertex -891.668 446.605 21.0658 + vertex -894.974 437.523 21.0606 + endloop + endfacet + facet normal -0.26272 0.0923838 0.960439 + outer loop + vertex -889.5 446.892 21.631 + vertex -891.668 446.605 21.0658 + vertex -892.632 437.872 21.642 + endloop + endfacet + facet normal -0.261593 0.091993 0.960784 + outer loop + vertex -889.773 438.605 22.3502 + vertex -889.5 446.892 21.631 + vertex -892.632 437.872 21.642 + endloop + endfacet + facet normal -0.275071 0.0921081 0.957002 + outer loop + vertex -886.789 447.623 22.3399 + vertex -889.5 446.892 21.631 + vertex -889.773 438.605 22.3502 + endloop + endfacet + facet normal -0.276998 0.100631 0.955587 + outer loop + vertex -886.789 447.623 22.3399 + vertex -886.212 455.944 21.631 + vertex -889.5 446.892 21.631 + endloop + endfacet + facet normal -0.297189 0.101505 0.949408 + outer loop + vertex -883.692 456.68 22.3412 + vertex -886.212 455.944 21.631 + vertex -886.789 447.623 22.3399 + endloop + endfacet + facet normal -0.299894 0.112827 0.947277 + outer loop + vertex -883.692 456.68 22.3412 + vertex -882.712 465.009 21.6593 + vertex -886.212 455.944 21.631 + endloop + endfacet + facet normal -0.328541 0.115389 0.937414 + outer loop + vertex -880.456 465.663 22.3695 + vertex -882.712 465.009 21.6593 + vertex -883.692 456.68 22.3412 + endloop + endfacet + facet normal -0.331805 0.129967 0.934352 + outer loop + vertex -880.456 465.663 22.3695 + vertex -878.971 474.126 21.7198 + vertex -882.712 465.009 21.6593 + endloop + endfacet + facet normal -0.369974 0.135496 0.919108 + outer loop + vertex -877.069 474.64 22.4093 + vertex -878.971 474.126 21.7198 + vertex -880.456 465.663 22.3695 + endloop + endfacet + facet normal -0.371429 0.143235 0.917346 + outer loop + vertex -877.069 474.64 22.4093 + vertex -875.36 483.35 21.7412 + vertex -878.971 474.126 21.7198 + endloop + endfacet + facet normal -0.263482 0.100043 0.959463 + outer loop + vertex -889.5 446.892 21.631 + vertex -888.23 455.654 21.0663 + vertex -891.668 446.605 21.0658 + endloop + endfacet + facet normal -0.281679 0.102332 0.954036 + outer loop + vertex -886.212 455.944 21.631 + vertex -888.23 455.654 21.0663 + vertex -889.5 446.892 21.631 + endloop + endfacet + facet normal -0.282803 0.113189 0.952476 + outer loop + vertex -886.212 455.944 21.631 + vertex -884.563 464.706 21.0793 + vertex -888.23 455.654 21.0663 + endloop + endfacet + facet normal -0.314503 0.118485 0.941833 + outer loop + vertex -882.712 465.009 21.6593 + vertex -884.563 464.706 21.0793 + vertex -886.212 455.944 21.631 + endloop + endfacet + facet normal -0.316039 0.132422 0.939459 + outer loop + vertex -882.712 465.009 21.6593 + vertex -880.604 473.84 21.1235 + vertex -884.563 464.706 21.0793 + endloop + endfacet + facet normal -0.361203 0.142116 0.921594 + outer loop + vertex -878.971 474.126 21.7198 + vertex -880.604 473.84 21.1235 + vertex -882.712 465.009 21.6593 + endloop + endfacet + facet normal -0.361984 0.149748 0.920078 + outer loop + vertex -878.971 474.126 21.7198 + vertex -876.631 483.191 21.1648 + vertex -880.604 473.84 21.1235 + endloop + endfacet + facet normal -0.260054 0.0849603 0.961849 + outer loop + vertex -889.773 438.605 22.3502 + vertex -892.632 437.872 21.642 + vertex -892.659 429.671 22.359 + endloop + endfacet + facet normal -0.246168 0.0852209 0.965473 + outer loop + vertex -895.666 428.851 21.6496 + vertex -894.974 437.523 21.0606 + vertex -898.174 428.412 21.049 + endloop + endfacet + facet normal -0.23921 0.0715829 0.968326 + outer loop + vertex -895.479 420.674 22.3611 + vertex -898.62 419.781 21.6512 + vertex -898.212 411.584 22.3579 + endloop + endfacet + facet normal -0.225301 0.0729597 0.971554 + outer loop + vertex -901.449 410.674 21.6509 + vertex -901.275 419.283 21.0448 + vertex -904.235 410.137 21.0453 + endloop + endfacet + facet normal -0.222116 0.0579356 0.973298 + outer loop + vertex -900.807 402.483 22.3484 + vertex -904.136 401.53 21.6456 + vertex -903.234 393.371 22.3371 + endloop + endfacet + facet normal -0.210623 0.0574859 0.975876 + outer loop + vertex -906.652 392.327 21.6323 + vertex -907.04 400.937 21.0416 + vertex -909.675 391.636 21.0207 + endloop + endfacet + facet normal -0.213908 0.0440431 0.97586 + outer loop + vertex -905.48 384.195 22.3202 + vertex -908.973 383.047 21.6063 + vertex -907.519 374.953 22.2904 + endloop + endfacet + facet normal -0.204152 0.0418738 0.978043 + outer loop + vertex -911.081 373.677 21.5645 + vertex -912.14 382.202 20.9785 + vertex -914.372 372.644 20.9219 + endloop + endfacet + facet normal -0.20836 0.0272343 0.977673 + outer loop + vertex -909.307 365.679 22.2442 + vertex -912.915 364.22 21.5159 + vertex -910.805 356.252 22.1876 + endloop + endfacet + facet normal -0.192037 0.0263002 0.981035 + outer loop + vertex -914.474 354.633 21.4541 + vertex -916.323 363.016 20.8673 + vertex -917.947 353.467 20.8055 + endloop + endfacet + facet normal -0.194916 -0.000782795 0.98082 + outer loop + vertex -912.004 345.982 22.103 + vertex -915.843 345.401 21.3396 + vertex -913.823 338.135 21.7353 + endloop + endfacet + facet normal -0.1679 -0.00577698 0.985787 + outer loop + vertex -916.752 336.724 21.2165 + vertex -920 334.674 20.6513 + vertex -916.671 327.485 21.1761 + endloop + endfacet + facet normal -0.164362 -0.00409486 0.986392 + outer loop + vertex -916.671 327.485 21.1761 + vertex -920 334.674 20.6513 + vertex -920.42 324.926 20.5408 + endloop + endfacet + facet normal -0.195786 -0.00267607 0.980643 + outer loop + vertex -920 334.674 20.6513 + vertex -923.619 332.463 19.9226 + vertex -920.42 324.926 20.5408 + endloop + endfacet + facet normal -0.182163 0.00332208 0.983263 + outer loop + vertex -920.42 324.926 20.5408 + vertex -923.619 332.463 19.9226 + vertex -924.311 321.901 19.8301 + endloop + endfacet + facet normal -0.170997 -0.0114995 0.985204 + outer loop + vertex -920.42 324.926 20.5408 + vertex -924.311 321.901 19.8301 + vertex -920.583 315.002 20.3966 + endloop + endfacet + facet normal -0.148532 -0.0119226 0.988836 + outer loop + vertex -916.509 318.065 21.0455 + vertex -920.42 324.926 20.5408 + vertex -920.583 315.002 20.3966 + endloop + endfacet + facet normal -0.13137 0.0104155 0.991279 + outer loop + vertex -920.583 315.002 20.3966 + vertex -924.311 321.901 19.8301 + vertex -923.534 315.557 19.9997 + endloop + endfacet + facet normal -0.136819 -0.0191902 0.99041 + outer loop + vertex -923.534 315.557 19.9997 + vertex -922.891 310.335 19.9873 + vertex -920.583 315.002 20.3966 + endloop + endfacet + facet normal -0.124467 -0.0254295 0.991898 + outer loop + vertex -919.141 305.541 20.335 + vertex -920.583 315.002 20.3966 + vertex -922.891 310.335 19.9873 + endloop + endfacet + facet normal -0.134573 -0.0334469 0.990339 + outer loop + vertex -922.071 302.721 19.8417 + vertex -919.141 305.541 20.335 + vertex -922.891 310.335 19.9873 + endloop + endfacet + facet normal -0.158721 -0.0359795 0.986668 + outer loop + vertex -922.891 310.335 19.9873 + vertex -925.092 308.251 19.5573 + vertex -922.071 302.721 19.8417 + endloop + endfacet + facet normal -0.165158 -0.0395577 0.985474 + outer loop + vertex -922.071 302.721 19.8417 + vertex -925.092 308.251 19.5573 + vertex -924.835 301.252 19.3195 + endloop + endfacet + facet normal -0.159609 -0.0501534 0.985905 + outer loop + vertex -922.071 302.721 19.8417 + vertex -924.835 301.252 19.3195 + vertex -921.109 294.314 19.5697 + endloop + endfacet + facet normal -0.134434 -0.0473986 0.989788 + outer loop + vertex -917.7 296.804 20.152 + vertex -922.071 302.721 19.8417 + vertex -921.109 294.314 19.5697 + endloop + endfacet + facet normal -0.129949 -0.0536043 0.990071 + outer loop + vertex -917.7 296.804 20.152 + vertex -921.109 294.314 19.5697 + vertex -915.706 287.871 19.93 + endloop + endfacet + facet normal -0.120459 -0.0515189 0.991381 + outer loop + vertex -912.29 291.07 20.5114 + vertex -917.7 296.804 20.152 + vertex -915.706 287.871 19.93 + endloop + endfacet + facet normal -0.12581 -0.0500936 0.990789 + outer loop + vertex -915.706 287.871 19.93 + vertex -921.109 294.314 19.5697 + vertex -919.409 284.786 19.3039 + endloop + endfacet + facet normal -0.118272 -0.0592259 0.991213 + outer loop + vertex -915.706 287.871 19.93 + vertex -919.409 284.786 19.3039 + vertex -912.837 278.856 19.7336 + endloop + endfacet + facet normal -0.110275 -0.0567044 0.992282 + outer loop + vertex -909.541 282.267 20.295 + vertex -915.706 287.871 19.93 + vertex -912.837 278.856 19.7336 + endloop + endfacet + facet normal -0.112198 -0.0524157 0.992302 + outer loop + vertex -912.837 278.856 19.7336 + vertex -919.409 284.786 19.3039 + vertex -915.726 275.372 19.2231 + endloop + endfacet + facet normal -0.100511 -0.0622048 0.99299 + outer loop + vertex -912.837 278.856 19.7336 + vertex -915.726 275.372 19.2231 + vertex -909.312 270.253 19.5516 + endloop + endfacet + facet normal -0.0981751 -0.0612538 0.993282 + outer loop + vertex -906.174 273.733 20.0763 + vertex -912.837 278.856 19.7336 + vertex -909.312 270.253 19.5516 + endloop + endfacet + facet normal -0.101305 -0.0632101 0.992845 + outer loop + vertex -909.312 270.253 19.5516 + vertex -915.726 275.372 19.2231 + vertex -912.466 267.044 19.0254 + endloop + endfacet + facet normal -0.0949709 -0.0694716 0.993053 + outer loop + vertex -909.312 270.253 19.5516 + vertex -912.466 267.044 19.0254 + vertex -905.419 262.115 19.3546 + endloop + endfacet + facet normal -0.0878459 -0.0660849 0.99394 + outer loop + vertex -902.339 265.678 19.8636 + vertex -909.312 270.253 19.5516 + vertex -905.419 262.115 19.3546 + endloop + endfacet + facet normal -0.0940825 -0.0681897 0.993226 + outer loop + vertex -905.419 262.115 19.3546 + vertex -912.466 267.044 19.0254 + vertex -908.61 258.663 18.8153 + endloop + endfacet + facet normal -0.0887709 -0.073123 0.993364 + outer loop + vertex -905.419 262.115 19.3546 + vertex -908.61 258.663 18.8153 + vertex -901.033 254.192 19.1633 + endloop + endfacet + facet normal -0.0788497 -0.06766 0.994588 + outer loop + vertex -898.103 257.995 19.6543 + vertex -905.419 262.115 19.3546 + vertex -901.033 254.192 19.1633 + endloop + endfacet + facet normal -0.0851417 -0.0669134 0.994119 + outer loop + vertex -901.033 254.192 19.1633 + vertex -908.61 258.663 18.8153 + vertex -903.973 250.349 18.6528 + endloop + endfacet + facet normal -0.0781273 -0.0723062 0.994318 + outer loop + vertex -901.033 254.192 19.1633 + vertex -903.973 250.349 18.6528 + vertex -896.125 246.447 18.9857 + endloop + endfacet + facet normal -0.070864 -0.0677239 0.995184 + outer loop + vertex -893.4 250.506 19.456 + vertex -901.033 254.192 19.1633 + vertex -896.125 246.447 18.9857 + endloop + endfacet + facet normal -0.0757447 -0.0674689 0.994842 + outer loop + vertex -896.125 246.447 18.9857 + vertex -903.973 250.349 18.6528 + vertex -898.865 242.377 18.5011 + endloop + endfacet + facet normal -0.0699553 -0.0713831 0.994993 + outer loop + vertex -896.125 246.447 18.9857 + vertex -898.865 242.377 18.5011 + vertex -890.716 238.866 18.8221 + endloop + endfacet + facet normal -0.0641133 -0.0672297 0.995675 + outer loop + vertex -888.216 243.127 19.2708 + vertex -896.125 246.447 18.9857 + vertex -890.716 238.866 18.8221 + endloop + endfacet + facet normal -0.0677405 -0.0661956 0.995505 + outer loop + vertex -890.716 238.866 18.8221 + vertex -898.865 242.377 18.5011 + vertex -893.248 234.573 18.3643 + endloop + endfacet + facet normal -0.0635968 -0.0686509 0.995612 + outer loop + vertex -890.716 238.866 18.8221 + vertex -893.248 234.573 18.3643 + vertex -884.889 231.46 18.6837 + endloop + endfacet + facet normal -0.0588793 -0.0649487 0.99615 + outer loop + vertex -882.594 235.904 19.1091 + vertex -890.716 238.866 18.8221 + vertex -884.889 231.46 18.6837 + endloop + endfacet + facet normal -0.0617912 -0.0637568 0.996051 + outer loop + vertex -884.889 231.46 18.6837 + vertex -893.248 234.573 18.3643 + vertex -887.263 226.98 18.2497 + endloop + endfacet + facet normal -0.0595154 -0.0649687 0.996111 + outer loop + vertex -884.889 231.46 18.6837 + vertex -887.263 226.98 18.2497 + vertex -879.046 224.408 18.5729 + endloop + endfacet + facet normal -0.0556697 -0.0617888 0.996536 + outer loop + vertex -876.674 228.923 18.9852 + vertex -884.889 231.46 18.6837 + vertex -879.046 224.408 18.5729 + endloop + endfacet + facet normal -0.0580961 -0.0603872 0.996483 + outer loop + vertex -879.046 224.408 18.5729 + vertex -887.263 226.98 18.2497 + vertex -881.393 219.81 18.1574 + endloop + endfacet + facet normal -0.0780267 -0.0766723 0.993999 + outer loop + vertex -887.263 226.98 18.2497 + vertex -889.649 222.326 17.7034 + vertex -881.393 219.81 18.1574 + endloop + endfacet + facet normal -0.0810219 -0.0751225 0.993877 + outer loop + vertex -887.263 226.98 18.2497 + vertex -895.855 230.177 17.7908 + vertex -889.649 222.326 17.7034 + endloop + endfacet + facet normal -0.0829545 -0.0803993 0.993305 + outer loop + vertex -893.248 234.573 18.3643 + vertex -895.855 230.177 17.7908 + vertex -887.263 226.98 18.2497 + endloop + endfacet + facet normal -0.0881499 -0.0772923 0.993104 + outer loop + vertex -893.248 234.573 18.3643 + vertex -901.675 238.228 17.9009 + vertex -895.855 230.177 17.7908 + endloop + endfacet + facet normal -0.090334 -0.0824042 0.992497 + outer loop + vertex -898.865 242.377 18.5011 + vertex -901.675 238.228 17.9009 + vertex -893.248 234.573 18.3643 + endloop + endfacet + facet normal -0.0973135 -0.0776376 0.992221 + outer loop + vertex -898.865 242.377 18.5011 + vertex -906.928 246.361 18.022 + vertex -901.675 238.228 17.9009 + endloop + endfacet + facet normal -0.0998502 -0.0828523 0.991547 + outer loop + vertex -903.973 250.349 18.6528 + vertex -906.928 246.361 18.022 + vertex -898.865 242.377 18.5011 + endloop + endfacet + facet normal -0.108625 -0.0762885 0.991151 + outer loop + vertex -903.973 250.349 18.6528 + vertex -911.725 254.826 18.1479 + vertex -906.928 246.361 18.022 + endloop + endfacet + facet normal -0.11166 -0.0816299 0.990388 + outer loop + vertex -908.61 258.663 18.8153 + vertex -911.725 254.826 18.1479 + vertex -903.973 250.349 18.6528 + endloop + endfacet + facet normal -0.120729 -0.0741867 0.98991 + outer loop + vertex -908.61 258.663 18.8153 + vertex -916.497 264.477 18.2892 + vertex -911.725 254.826 18.1479 + endloop + endfacet + facet normal -0.127421 -0.083407 0.988336 + outer loop + vertex -912.466 267.044 19.0254 + vertex -916.497 264.477 18.2892 + vertex -908.61 258.663 18.8153 + endloop + endfacet + facet normal -0.129326 -0.0804163 0.988336 + outer loop + vertex -912.466 267.044 19.0254 + vertex -918.424 272.604 18.6983 + vertex -916.497 264.477 18.2892 + endloop + endfacet + facet normal -0.120222 -0.0705508 0.990237 + outer loop + vertex -915.726 275.372 19.2231 + vertex -918.424 272.604 18.6983 + vertex -912.466 267.044 19.0254 + endloop + endfacet + facet normal -0.127217 -0.0636529 0.98983 + outer loop + vertex -918.424 272.604 18.6983 + vertex -915.726 275.372 19.2231 + vertex -920.761 279.871 18.8652 + endloop + endfacet + facet normal -0.119992 -0.0554558 0.991225 + outer loop + vertex -915.726 275.372 19.2231 + vertex -919.409 284.786 19.3039 + vertex -920.761 279.871 18.8652 + endloop + endfacet + facet normal -0.133641 -0.051562 0.989688 + outer loop + vertex -922.703 285.334 18.8876 + vertex -920.761 279.871 18.8652 + vertex -919.409 284.786 19.3039 + endloop + endfacet + facet normal -0.12958 -0.0259824 0.991229 + outer loop + vertex -919.409 284.786 19.3039 + vertex -925.485 293.039 18.7259 + vertex -922.703 285.334 18.8876 + endloop + endfacet + facet normal -0.172633 -0.0582375 0.983263 + outer loop + vertex -921.109 294.314 19.5697 + vertex -925.485 293.039 18.7259 + vertex -919.409 284.786 19.3039 + endloop + endfacet + facet normal -0.172885 -0.0573775 0.983269 + outer loop + vertex -925.485 293.039 18.7259 + vertex -921.109 294.314 19.5697 + vertex -924.835 301.252 19.3195 + endloop + endfacet + facet normal -0.205703 -0.0543336 0.977105 + outer loop + vertex -927.041 301.906 18.8914 + vertex -925.485 293.039 18.7259 + vertex -924.835 301.252 19.3195 + endloop + endfacet + facet normal -0.201541 -0.0392576 0.978693 + outer loop + vertex -924.835 301.252 19.3195 + vertex -927.04 307.316 19.1085 + vertex -927.041 301.906 18.8914 + endloop + endfacet + facet normal -0.263046 -0.0641244 0.96265 + outer loop + vertex -927.041 301.906 18.8914 + vertex -928.583 301.18 18.4216 + vertex -925.485 293.039 18.7259 + endloop + endfacet + facet normal -0.269472 -0.0666431 0.960699 + outer loop + vertex -928.583 301.18 18.4216 + vertex -929.288 297.482 17.9674 + vertex -925.485 293.039 18.7259 + endloop + endfacet + facet normal -0.251605 -0.0503553 0.966519 + outer loop + vertex -928.706 292.937 17.8821 + vertex -925.485 293.039 18.7259 + vertex -929.288 297.482 17.9674 + endloop + endfacet + facet normal -0.251421 -0.0546454 0.966334 + outer loop + vertex -928.706 292.937 17.8821 + vertex -927.419 288.113 17.9441 + vertex -925.485 293.039 18.7259 + endloop + endfacet + facet normal -0.246011 -0.0569691 0.967591 + outer loop + vertex -927.419 288.113 17.9441 + vertex -924.374 284.268 18.492 + vertex -925.485 293.039 18.7259 + endloop + endfacet + facet normal -0.198981 -0.0513063 0.978659 + outer loop + vertex -922.703 285.334 18.8876 + vertex -925.485 293.039 18.7259 + vertex -924.374 284.268 18.492 + endloop + endfacet + facet normal -0.187014 -0.0704906 0.979825 + outer loop + vertex -922.703 285.334 18.8876 + vertex -924.374 284.268 18.492 + vertex -920.761 279.871 18.8652 + endloop + endfacet + facet normal -0.180339 -0.0648665 0.981463 + outer loop + vertex -920.761 279.871 18.8652 + vertex -924.374 284.268 18.492 + vertex -922.801 277.854 18.3571 + endloop + endfacet + facet normal -0.168774 -0.0768551 0.982654 + outer loop + vertex -920.761 279.871 18.8652 + vertex -922.801 277.854 18.3571 + vertex -918.424 272.604 18.6983 + endloop + endfacet + facet normal -0.171545 -0.0792089 0.981987 + outer loop + vertex -918.424 272.604 18.6983 + vertex -922.801 277.854 18.3571 + vertex -921.417 272.068 18.1321 + endloop + endfacet + facet normal -0.169577 -0.0896144 0.981434 + outer loop + vertex -918.424 272.604 18.6983 + vertex -921.417 272.068 18.1321 + vertex -916.497 264.477 18.2892 + endloop + endfacet + facet normal -0.202071 -0.11085 0.973077 + outer loop + vertex -921.417 272.068 18.1321 + vertex -921.621 268.444 17.677 + vertex -916.497 264.477 18.2892 + endloop + endfacet + facet normal -0.186703 -0.0902014 0.978267 + outer loop + vertex -919.902 264.021 17.5972 + vertex -916.497 264.477 18.2892 + vertex -921.621 268.444 17.677 + endloop + endfacet + facet normal -0.186131 -0.0940869 0.97801 + outer loop + vertex -919.902 264.021 17.5972 + vertex -917.295 259.425 17.6513 + vertex -916.497 264.477 18.2892 + endloop + endfacet + facet normal -0.167848 -0.0973528 0.980994 + outer loop + vertex -911.725 254.826 18.1479 + vertex -916.497 264.477 18.2892 + vertex -917.295 259.425 17.6513 + endloop + endfacet + facet normal -0.165989 -0.0950434 0.981537 + outer loop + vertex -915.54 254.882 17.5082 + vertex -911.725 254.826 18.1479 + vertex -917.295 259.425 17.6513 + endloop + endfacet + facet normal -0.165986 -0.0970575 0.98134 + outer loop + vertex -915.54 254.882 17.5082 + vertex -912.792 250.575 17.547 + vertex -911.725 254.826 18.1479 + endloop + endfacet + facet normal -0.152102 -0.100807 0.983211 + outer loop + vertex -906.928 246.361 18.022 + vertex -911.725 254.826 18.1479 + vertex -912.792 250.575 17.547 + endloop + endfacet + facet normal -0.151276 -0.0996295 0.983458 + outer loop + vertex -910.934 246.405 17.4102 + vertex -906.928 246.361 18.022 + vertex -912.792 250.575 17.547 + endloop + endfacet + facet normal -0.151265 -0.102057 0.983211 + outer loop + vertex -910.934 246.405 17.4102 + vertex -907.934 242.281 17.4438 + vertex -906.928 246.361 18.022 + endloop + endfacet + facet normal -0.13992 -0.105047 0.984575 + outer loop + vertex -901.675 238.228 17.9009 + vertex -906.928 246.361 18.022 + vertex -907.934 242.281 17.4438 + endloop + endfacet + facet normal -0.139179 -0.103876 0.984804 + outer loop + vertex -905.81 238.155 17.3087 + vertex -901.675 238.228 17.9009 + vertex -907.934 242.281 17.4438 + endloop + endfacet + facet normal -0.139194 -0.103413 0.984851 + outer loop + vertex -905.81 238.155 17.3087 + vertex -902.477 234.025 17.3463 + vertex -901.675 238.228 17.9009 + endloop + endfacet + facet normal -0.127694 -0.10578 0.986157 + outer loop + vertex -895.855 230.177 17.7908 + vertex -901.675 238.228 17.9009 + vertex -902.477 234.025 17.3463 + endloop + endfacet + facet normal -0.127433 -0.10532 0.98624 + outer loop + vertex -900.04 229.858 17.216 + vertex -895.855 230.177 17.7908 + vertex -902.477 234.025 17.3463 + endloop + endfacet + facet normal -0.12764 -0.102997 0.986458 + outer loop + vertex -900.04 229.858 17.216 + vertex -896.411 225.792 17.2611 + vertex -895.855 230.177 17.7908 + endloop + endfacet + facet normal -0.118066 -0.104338 0.987509 + outer loop + vertex -889.649 222.326 17.7034 + vertex -895.855 230.177 17.7908 + vertex -896.411 225.792 17.2611 + endloop + endfacet + facet normal -0.118956 -0.106112 0.987213 + outer loop + vertex -893.723 221.668 17.1417 + vertex -889.649 222.326 17.7034 + vertex -896.411 225.792 17.2611 + endloop + endfacet + facet normal -0.11921 -0.104647 0.987339 + outer loop + vertex -893.723 221.668 17.1417 + vertex -889.945 217.797 17.1875 + vertex -889.649 222.326 17.7034 + endloop + endfacet + facet normal -0.114349 -0.105027 0.987873 + outer loop + vertex -883.504 214.992 17.6348 + vertex -889.649 222.326 17.7034 + vertex -889.945 217.797 17.1875 + endloop + endfacet + facet normal -0.116224 -0.109443 0.987175 + outer loop + vertex -887.142 213.83 17.0777 + vertex -883.504 214.992 17.6348 + vertex -889.945 217.797 17.1875 + endloop + endfacet + facet normal -0.117751 -0.104817 0.987496 + outer loop + vertex -887.142 213.83 17.0777 + vertex -883.482 210.372 17.1471 + vertex -883.504 214.992 17.6348 + endloop + endfacet + facet normal -0.114307 -0.104843 0.987898 + outer loop + vertex -877.978 208.676 17.604 + vertex -883.504 214.992 17.6348 + vertex -883.482 210.372 17.1471 + endloop + endfacet + facet normal -0.115578 -0.109134 0.987285 + outer loop + vertex -880.801 206.827 17.0692 + vertex -877.978 208.676 17.604 + vertex -883.482 210.372 17.1471 + endloop + endfacet + facet normal -0.116609 -0.107575 0.987335 + outer loop + vertex -880.801 206.827 17.0692 + vertex -877.616 204.159 17.1546 + vertex -877.978 208.676 17.604 + endloop + endfacet + facet normal -0.107308 -0.106941 0.988458 + outer loop + vertex -873.163 203.98 17.6187 + vertex -877.978 208.676 17.604 + vertex -877.616 204.159 17.1546 + endloop + endfacet + facet normal -0.107411 -0.110576 0.988046 + outer loop + vertex -874.862 200.735 17.0708 + vertex -873.163 203.98 17.6187 + vertex -877.616 204.159 17.1546 + endloop + endfacet + facet normal -0.107903 -0.110314 0.988022 + outer loop + vertex -873.163 203.98 17.6187 + vertex -874.862 200.735 17.0708 + vertex -869.353 198.16 17.385 + endloop + endfacet + facet normal -0.12054 -0.137953 0.983076 + outer loop + vertex -874.862 200.735 17.0708 + vertex -873.852 198.06 16.8193 + vertex -869.353 198.16 17.385 + endloop + endfacet + facet normal -0.244829 -0.107261 0.963615 + outer loop + vertex -923.889 272.87 17.5933 + vertex -921.621 268.444 17.677 + vertex -921.417 272.068 18.1321 + endloop + endfacet + facet normal -0.240927 -0.0936152 0.966018 + outer loop + vertex -921.417 272.068 18.1321 + vertex -924.848 276.901 17.7449 + vertex -923.889 272.87 17.5933 + endloop + endfacet + facet normal -0.243994 -0.0958716 0.965026 + outer loop + vertex -922.801 277.854 18.3571 + vertex -924.848 276.901 17.7449 + vertex -921.417 272.068 18.1321 + endloop + endfacet + facet normal -0.2502 -0.0823184 0.964688 + outer loop + vertex -922.801 277.854 18.3571 + vertex -926.168 282.226 17.8568 + vertex -924.848 276.901 17.7449 + endloop + endfacet + facet normal -0.249024 -0.0813683 0.965073 + outer loop + vertex -924.374 284.268 18.492 + vertex -926.168 282.226 17.8568 + vertex -922.801 277.854 18.3571 + endloop + endfacet + facet normal -0.261344 -0.0698064 0.962718 + outer loop + vertex -926.168 282.226 17.8568 + vertex -924.374 284.268 18.492 + vertex -927.419 288.113 17.9441 + endloop + endfacet + facet normal -0.327862 -0.0533737 0.943217 + outer loop + vertex -930.347 302.088 17.8598 + vertex -929.288 297.482 17.9674 + vertex -928.583 301.18 18.4216 + endloop + endfacet + facet normal -0.319902 -0.0356985 0.946778 + outer loop + vertex -928.583 301.18 18.4216 + vertex -930.382 306.207 18.0034 + vertex -930.347 302.088 17.8598 + endloop + endfacet + facet normal -0.336981 -0.0423272 0.94056 + outer loop + vertex -928.756 306.806 18.613 + vertex -930.382 306.207 18.0034 + vertex -928.583 301.18 18.4216 + endloop + endfacet + facet normal -0.344056 -0.0212453 0.938709 + outer loop + vertex -928.756 306.806 18.613 + vertex -930.464 311.522 18.0937 + vertex -930.382 306.207 18.0034 + endloop + endfacet + facet normal -0.341078 -0.0200441 0.939821 + outer loop + vertex -928.713 312.639 18.7528 + vertex -930.464 311.522 18.0937 + vertex -928.756 306.806 18.613 + endloop + endfacet + facet normal -0.347715 -0.00830091 0.937563 + outer loop + vertex -930.464 311.522 18.0937 + vertex -928.713 312.639 18.7528 + vertex -930.413 317.218 18.1631 + endloop + endfacet + facet normal -0.318505 0.00387223 0.947913 + outer loop + vertex -930.413 317.218 18.1631 + vertex -928.713 312.639 18.7528 + vertex -928.076 319.921 18.9371 + endloop + endfacet + facet normal -0.320661 0.00594797 0.947175 + outer loop + vertex -930.535 322.284 18.0897 + vertex -930.413 317.218 18.1631 + vertex -928.076 319.921 18.9371 + endloop + endfacet + facet normal -0.316708 0.0105232 0.948465 + outer loop + vertex -930.535 322.284 18.0897 + vertex -928.076 319.921 18.9371 + vertex -929.898 327.045 18.2498 + endloop + endfacet + facet normal -0.30375 0.0142396 0.952645 + outer loop + vertex -928.076 319.921 18.9371 + vertex -927.367 330.222 19.0092 + vertex -929.898 327.045 18.2498 + endloop + endfacet + facet normal -0.313032 0.0223915 0.949479 + outer loop + vertex -929.739 332.377 18.1764 + vertex -929.898 327.045 18.2498 + vertex -927.367 330.222 19.0092 + endloop + endfacet + facet normal -0.309479 0.0267077 0.950531 + outer loop + vertex -929.739 332.377 18.1764 + vertex -927.367 330.222 19.0092 + vertex -928.883 337.127 18.3218 + endloop + endfacet + facet normal -0.309083 0.0268072 0.950657 + outer loop + vertex -927.367 330.222 19.0092 + vertex -926.277 340.307 19.0792 + vertex -928.883 337.127 18.3218 + endloop + endfacet + facet normal -0.326052 0.0421959 0.94441 + outer loop + vertex -928.49 342.358 18.2237 + vertex -928.883 337.127 18.3218 + vertex -926.277 340.307 19.0792 + endloop + endfacet + facet normal -0.323241 0.0455677 0.945219 + outer loop + vertex -928.49 342.358 18.2237 + vertex -926.277 340.307 19.0792 + vertex -927.441 347.046 18.3565 + endloop + endfacet + facet normal -0.331477 0.0438478 0.942444 + outer loop + vertex -926.277 340.307 19.0792 + vertex -924.826 350.164 19.1309 + vertex -927.441 347.046 18.3565 + endloop + endfacet + facet normal -0.350198 0.0614765 0.934656 + outer loop + vertex -926.819 352.217 18.2492 + vertex -927.441 347.046 18.3565 + vertex -924.826 350.164 19.1309 + endloop + endfacet + facet normal -0.347394 0.0645597 0.935494 + outer loop + vertex -926.819 352.217 18.2492 + vertex -924.826 350.164 19.1309 + vertex -925.61 356.86 18.3779 + endloop + endfacet + facet normal -0.355361 0.0633001 0.932583 + outer loop + vertex -924.826 350.164 19.1309 + vertex -923 359.947 19.1628 + vertex -925.61 356.86 18.3779 + endloop + endfacet + facet normal -0.374748 0.0819998 0.923493 + outer loop + vertex -924.779 362.008 18.2579 + vertex -925.61 356.86 18.3779 + vertex -923 359.947 19.1628 + endloop + endfacet + facet normal -0.374247 0.0825018 0.923652 + outer loop + vertex -924.779 362.008 18.2579 + vertex -923 359.947 19.1628 + vertex -923.397 366.715 18.3975 + endloop + endfacet + facet normal -0.38185 0.0817113 0.920605 + outer loop + vertex -923 359.947 19.1628 + vertex -920.765 369.876 19.2087 + vertex -923.397 366.715 18.3975 + endloop + endfacet + facet normal -0.398534 0.0978331 0.911921 + outer loop + vertex -922.297 372.023 18.3087 + vertex -923.397 366.715 18.3975 + vertex -920.765 369.876 19.2087 + endloop + endfacet + facet normal -0.3968 0.0993198 0.912516 + outer loop + vertex -922.297 372.023 18.3087 + vertex -920.765 369.876 19.2087 + vertex -920.68 376.854 18.486 + endloop + endfacet + facet normal -0.38968 0.099548 0.915554 + outer loop + vertex -920.765 369.876 19.2087 + vertex -918.181 379.977 19.2099 + vertex -920.68 376.854 18.486 + endloop + endfacet + facet normal -0.411026 0.119358 0.903776 + outer loop + vertex -919.449 381.621 18.4164 + vertex -920.68 376.854 18.486 + vertex -918.181 379.977 19.2099 + endloop + endfacet + facet normal -0.369063 0.157576 0.915949 + outer loop + vertex -918.181 379.977 19.2099 + vertex -918.112 387.923 17.8708 + vertex -919.449 381.621 18.4164 + endloop + endfacet + facet normal -0.500959 0.148068 0.852711 + outer loop + vertex -915.15 389.832 19.2795 + vertex -918.112 387.923 17.8708 + vertex -918.181 379.977 19.2099 + endloop + endfacet + facet normal -0.510127 0.169246 0.843283 + outer loop + vertex -915.15 389.832 19.2795 + vertex -914.725 398.11 17.8753 + vertex -918.112 387.923 17.8708 + endloop + endfacet + facet normal -0.543084 0.167467 0.822809 + outer loop + vertex -912.056 399.586 19.3367 + vertex -914.725 398.11 17.8753 + vertex -915.15 389.832 19.2795 + endloop + endfacet + facet normal -0.550459 0.19073 0.812784 + outer loop + vertex -912.056 399.586 19.3367 + vertex -911.308 407.831 17.9083 + vertex -914.725 398.11 17.8753 + endloop + endfacet + facet normal -0.570536 0.190155 0.798956 + outer loop + vertex -908.871 409.066 19.3545 + vertex -911.308 407.831 17.9083 + vertex -912.056 399.586 19.3367 + endloop + endfacet + facet normal -0.576452 0.213915 0.788634 + outer loop + vertex -908.871 409.066 19.3545 + vertex -907.799 417.286 17.9083 + vertex -911.308 407.831 17.9083 + endloop + endfacet + facet normal -0.606562 0.213813 0.765746 + outer loop + vertex -905.58 418.373 19.3625 + vertex -907.799 417.286 17.9083 + vertex -908.871 409.066 19.3545 + endloop + endfacet + facet normal -0.611175 0.237613 0.754987 + outer loop + vertex -905.58 418.373 19.3625 + vertex -904.194 426.571 17.9047 + vertex -907.799 417.286 17.9083 + endloop + endfacet + facet normal -0.643884 0.238186 0.727104 + outer loop + vertex -902.139 427.64 19.374 + vertex -904.194 426.571 17.9047 + vertex -905.58 418.373 19.3625 + endloop + endfacet + facet normal -0.647299 0.258564 0.717042 + outer loop + vertex -902.139 427.64 19.374 + vertex -900.395 435.985 17.9391 + vertex -904.194 426.571 17.9047 + endloop + endfacet + facet normal -0.277747 -1.68323e-05 0.960654 + outer loop + vertex -927.015 312.685 19.2437 + vertex -928.076 319.921 18.9371 + vertex -928.713 312.639 18.7528 + endloop + endfacet + facet normal -0.277097 -0.0228929 0.960569 + outer loop + vertex -927.015 312.685 19.2437 + vertex -928.713 312.639 18.7528 + vertex -927.04 307.316 19.1085 + endloop + endfacet + facet normal -0.271676 -0.0210826 0.962158 + outer loop + vertex -927.04 307.316 19.1085 + vertex -928.713 312.639 18.7528 + vertex -928.756 306.806 18.613 + endloop + endfacet + facet normal -0.266704 -0.0386221 0.963004 + outer loop + vertex -927.04 307.316 19.1085 + vertex -928.756 306.806 18.613 + vertex -927.041 301.906 18.8914 + endloop + endfacet + facet normal -0.237744 0.00629926 0.971307 + outer loop + vertex -927.015 312.685 19.2437 + vertex -925.362 314.845 19.6343 + vertex -928.076 319.921 18.9371 + endloop + endfacet + facet normal -0.234749 0.00799919 0.972023 + outer loop + vertex -924.311 321.901 19.8301 + vertex -928.076 319.921 18.9371 + vertex -925.362 314.845 19.6343 + endloop + endfacet + facet normal -0.235446 0.00940554 0.971842 + outer loop + vertex -924.311 321.901 19.8301 + vertex -927.367 330.222 19.0092 + vertex -928.076 319.921 18.9371 + endloop + endfacet + facet normal -0.240878 0.00728085 0.970528 + outer loop + vertex -923.619 332.463 19.9226 + vertex -927.367 330.222 19.0092 + vertex -924.311 321.901 19.8301 + endloop + endfacet + facet normal -0.248049 0.0200854 0.968539 + outer loop + vertex -923.619 332.463 19.9226 + vertex -926.277 340.307 19.0792 + vertex -927.367 330.222 19.0092 + endloop + endfacet + facet normal -0.257044 0.016792 0.966254 + outer loop + vertex -922.644 342.362 20.01 + vertex -926.277 340.307 19.0792 + vertex -923.619 332.463 19.9226 + endloop + endfacet + facet normal -0.266096 0.0341151 0.963343 + outer loop + vertex -922.644 342.362 20.01 + vertex -924.826 350.164 19.1309 + vertex -926.277 340.307 19.0792 + endloop + endfacet + facet normal -0.275446 0.031214 0.96081 + outer loop + vertex -921.324 352.026 20.0743 + vertex -924.826 350.164 19.1309 + vertex -922.644 342.362 20.01 + endloop + endfacet + facet normal -0.284502 0.0499906 0.957371 + outer loop + vertex -921.324 352.026 20.0743 + vertex -923 359.947 19.1628 + vertex -924.826 350.164 19.1309 + endloop + endfacet + facet normal -0.295389 0.0473232 0.954204 + outer loop + vertex -919.613 361.705 20.1241 + vertex -923 359.947 19.1628 + vertex -921.324 352.026 20.0743 + endloop + endfacet + facet normal -0.302999 0.063819 0.950852 + outer loop + vertex -919.613 361.705 20.1241 + vertex -920.765 369.876 19.2087 + vertex -923 359.947 19.1628 + endloop + endfacet + facet normal -0.31361 0.0619515 0.947529 + outer loop + vertex -917.524 371.51 20.1745 + vertex -920.765 369.876 19.2087 + vertex -919.613 361.705 20.1241 + endloop + endfacet + facet normal -0.322546 0.0823762 0.942962 + outer loop + vertex -917.524 371.51 20.1745 + vertex -918.181 379.977 19.2099 + vertex -920.765 369.876 19.2087 + endloop + endfacet + facet normal -0.344898 0.0797613 0.935245 + outer loop + vertex -915.088 381.31 20.2371 + vertex -918.181 379.977 19.2099 + vertex -917.524 371.51 20.1745 + endloop + endfacet + facet normal -0.352762 0.101938 0.930144 + outer loop + vertex -915.088 381.31 20.2371 + vertex -915.15 389.832 19.2795 + vertex -918.181 379.977 19.2099 + endloop + endfacet + facet normal -0.384835 0.100285 0.917521 + outer loop + vertex -912.406 390.975 20.3055 + vertex -915.15 389.832 19.2795 + vertex -915.088 381.31 20.2371 + endloop + endfacet + facet normal -0.390714 0.1186 0.91284 + outer loop + vertex -912.406 390.975 20.3055 + vertex -912.056 399.586 19.3367 + vertex -915.15 389.832 19.2795 + endloop + endfacet + facet normal -0.407582 0.118456 0.905453 + outer loop + vertex -909.572 400.451 20.3417 + vertex -912.056 399.586 19.3367 + vertex -912.406 390.975 20.3055 + endloop + endfacet + facet normal -0.412076 0.136733 0.900831 + outer loop + vertex -909.572 400.451 20.3417 + vertex -908.871 409.066 19.3545 + vertex -912.056 399.586 19.3367 + endloop + endfacet + facet normal -0.434012 0.137319 0.89038 + outer loop + vertex -906.605 409.755 20.353 + vertex -908.871 409.066 19.3545 + vertex -909.572 400.451 20.3417 + endloop + endfacet + facet normal -0.437153 0.153809 0.886138 + outer loop + vertex -906.605 409.755 20.353 + vertex -905.58 418.373 19.3625 + vertex -908.871 409.066 19.3545 + endloop + endfacet + facet normal -0.460631 0.155196 0.873918 + outer loop + vertex -903.497 418.963 20.3561 + vertex -905.58 418.373 19.3625 + vertex -906.605 409.755 20.353 + endloop + endfacet + facet normal -0.463052 0.170862 0.869706 + outer loop + vertex -903.497 418.963 20.3561 + vertex -902.139 427.64 19.374 + vertex -905.58 418.373 19.3625 + endloop + endfacet + facet normal -0.494218 0.173711 0.851806 + outer loop + vertex -900.238 428.165 20.3701 + vertex -902.139 427.64 19.374 + vertex -903.497 418.963 20.3561 + endloop + endfacet + facet normal -0.496155 0.18911 0.847388 + outer loop + vertex -900.238 428.165 20.3701 + vertex -898.517 437.019 19.4018 + vertex -902.139 427.64 19.374 + endloop + endfacet + facet normal -0.5301 0.193325 0.825602 + outer loop + vertex -896.824 437.403 20.3992 + vertex -898.517 437.019 19.4018 + vertex -900.238 428.165 20.3701 + endloop + endfacet + facet normal -0.531049 0.209151 0.821123 + outer loop + vertex -896.824 437.403 20.3992 + vertex -894.742 446.435 19.4451 + vertex -898.517 437.019 19.4018 + endloop + endfacet + facet normal -0.572679 0.215558 0.790932 + outer loop + vertex -893.302 446.619 20.4373 + vertex -894.742 446.435 19.4451 + vertex -896.824 437.403 20.3992 + endloop + endfacet + facet normal -0.571934 0.232188 0.786753 + outer loop + vertex -893.302 446.619 20.4373 + vertex -890.872 455.757 19.5074 + vertex -894.742 446.435 19.4451 + endloop + endfacet + facet normal -0.205285 -0.0198355 0.978501 + outer loop + vertex -925.362 314.845 19.6343 + vertex -927.015 312.685 19.2437 + vertex -925.092 308.251 19.5573 + endloop + endfacet + facet normal -0.213641 -0.0235929 0.976627 + outer loop + vertex -925.092 308.251 19.5573 + vertex -927.015 312.685 19.2437 + vertex -927.04 307.316 19.1085 + endloop + endfacet + facet normal -0.273399 -0.0410778 0.961023 + outer loop + vertex -927.041 301.906 18.8914 + vertex -928.756 306.806 18.613 + vertex -928.583 301.18 18.4216 + endloop + endfacet + facet normal -0.205652 -0.0407849 0.977775 + outer loop + vertex -925.092 308.251 19.5573 + vertex -927.04 307.316 19.1085 + vertex -924.835 301.252 19.3195 + endloop + endfacet + facet normal -0.174694 -0.0186514 0.984446 + outer loop + vertex -922.891 310.335 19.9873 + vertex -925.362 314.845 19.6343 + vertex -925.092 308.251 19.5573 + endloop + endfacet + facet normal -0.126775 -0.0416747 0.991056 + outer loop + vertex -919.141 305.541 20.335 + vertex -922.071 302.721 19.8417 + vertex -917.7 296.804 20.152 + endloop + endfacet + facet normal -0.127715 -0.0418271 0.990929 + outer loop + vertex -914.339 299.895 20.7157 + vertex -919.141 305.541 20.335 + vertex -917.7 296.804 20.152 + endloop + endfacet + facet normal -0.136194 -0.0272059 0.990309 + outer loop + vertex -915.779 308.829 20.8878 + vertex -920.583 315.002 20.3966 + vertex -919.141 305.541 20.335 + endloop + endfacet + facet normal -0.186462 -0.0252799 0.982137 + outer loop + vertex -923.534 315.557 19.9997 + vertex -925.362 314.845 19.6343 + vertex -922.891 310.335 19.9873 + endloop + endfacet + facet normal -0.196787 0.00211007 0.980444 + outer loop + vertex -923.534 315.557 19.9997 + vertex -924.311 321.901 19.8301 + vertex -925.362 314.845 19.6343 + endloop + endfacet + facet normal -0.204068 0.0114604 0.97889 + outer loop + vertex -920 334.674 20.6513 + vertex -922.644 342.362 20.01 + vertex -923.619 332.463 19.9226 + endloop + endfacet + facet normal -0.211093 0.00892245 0.977425 + outer loop + vertex -919.213 344.1 20.7352 + vertex -922.644 342.362 20.01 + vertex -920 334.674 20.6513 + endloop + endfacet + facet normal -0.217989 0.0232705 0.975674 + outer loop + vertex -919.213 344.1 20.7352 + vertex -921.324 352.026 20.0743 + vertex -922.644 342.362 20.01 + endloop + endfacet + facet normal -0.220683 0.0225039 0.975086 + outer loop + vertex -917.947 353.467 20.8055 + vertex -921.324 352.026 20.0743 + vertex -919.213 344.1 20.7352 + endloop + endfacet + facet normal -0.225642 0.0348925 0.973585 + outer loop + vertex -917.947 353.467 20.8055 + vertex -919.613 361.705 20.1241 + vertex -921.324 352.026 20.0743 + endloop + endfacet + facet normal -0.232856 0.0332972 0.971941 + outer loop + vertex -916.323 363.016 20.8673 + vertex -919.613 361.705 20.1241 + vertex -917.947 353.467 20.8055 + endloop + endfacet + facet normal -0.237397 0.0455939 0.970342 + outer loop + vertex -916.323 363.016 20.8673 + vertex -917.524 371.51 20.1745 + vertex -919.613 361.705 20.1241 + endloop + endfacet + facet normal -0.245548 0.0442811 0.968373 + outer loop + vertex -914.372 372.644 20.9219 + vertex -917.524 371.51 20.1745 + vertex -916.323 363.016 20.8673 + endloop + endfacet + facet normal -0.249325 0.0558028 0.966811 + outer loop + vertex -914.372 372.644 20.9219 + vertex -915.088 381.31 20.2371 + vertex -917.524 371.51 20.1745 + endloop + endfacet + facet normal -0.259132 0.0547932 0.964286 + outer loop + vertex -912.14 382.202 20.9785 + vertex -915.088 381.31 20.2371 + vertex -914.372 372.644 20.9219 + endloop + endfacet + facet normal -0.262119 0.0659162 0.962782 + outer loop + vertex -912.14 382.202 20.9785 + vertex -912.406 390.975 20.3055 + vertex -915.088 381.31 20.2371 + endloop + endfacet + facet normal -0.267617 0.0656349 0.961287 + outer loop + vertex -909.675 391.636 21.0207 + vertex -912.406 390.975 20.3055 + vertex -912.14 382.202 20.9785 + endloop + endfacet + facet normal -0.269991 0.0770906 0.959772 + outer loop + vertex -909.675 391.636 21.0207 + vertex -909.572 400.451 20.3417 + vertex -912.406 390.975 20.3055 + endloop + endfacet + facet normal -0.279333 0.0769944 0.957102 + outer loop + vertex -907.04 400.937 21.0416 + vertex -909.572 400.451 20.3417 + vertex -909.675 391.636 21.0207 + endloop + endfacet + facet normal -0.281117 0.0884849 0.955586 + outer loop + vertex -907.04 400.937 21.0416 + vertex -906.605 409.755 20.353 + vertex -909.572 400.451 20.3417 + endloop + endfacet + facet normal -0.292422 0.088775 0.95216 + outer loop + vertex -904.235 410.137 21.0453 + vertex -906.605 409.755 20.353 + vertex -907.04 400.937 21.0416 + endloop + endfacet + facet normal -0.293638 0.0987976 0.950797 + outer loop + vertex -904.235 410.137 21.0453 + vertex -903.497 418.963 20.3561 + vertex -906.605 409.755 20.353 + endloop + endfacet + facet normal -0.307694 0.0996183 0.946256 + outer loop + vertex -901.275 419.283 21.0448 + vertex -903.497 418.963 20.3561 + vertex -904.235 410.137 21.0453 + endloop + endfacet + facet normal -0.308513 0.107809 0.945091 + outer loop + vertex -901.275 419.283 21.0448 + vertex -900.238 428.165 20.3701 + vertex -903.497 418.963 20.3561 + endloop + endfacet + facet normal -0.322328 0.10906 0.940325 + outer loop + vertex -898.174 428.412 21.049 + vertex -900.238 428.165 20.3701 + vertex -901.275 419.283 21.0448 + endloop + endfacet + facet normal -0.322856 0.11637 0.939267 + outer loop + vertex -898.174 428.412 21.049 + vertex -896.824 437.403 20.3992 + vertex -900.238 428.165 20.3701 + endloop + endfacet + facet normal -0.341186 0.118632 0.93248 + outer loop + vertex -894.974 437.523 21.0606 + vertex -896.824 437.403 20.3992 + vertex -898.174 428.412 21.049 + endloop + endfacet + facet normal -0.341313 0.126572 0.931389 + outer loop + vertex -894.974 437.523 21.0606 + vertex -893.302 446.619 20.4373 + vertex -896.824 437.403 20.3992 + endloop + endfacet + facet normal -0.354946 0.128707 0.925985 + outer loop + vertex -891.668 446.605 21.0658 + vertex -893.302 446.619 20.4373 + vertex -894.974 437.523 21.0606 + endloop + endfacet + facet normal -0.354423 0.138016 0.924844 + outer loop + vertex -891.668 446.605 21.0658 + vertex -889.678 455.752 20.4631 + vertex -893.302 446.619 20.4373 + endloop + endfacet + facet normal -0.372413 0.141426 0.917228 + outer loop + vertex -888.23 455.654 21.0663 + vertex -889.678 455.752 20.4631 + vertex -891.668 446.605 21.0658 + endloop + endfacet + facet normal -0.370835 0.155134 0.91565 + outer loop + vertex -888.23 455.654 21.0663 + vertex -885.874 464.811 20.4691 + vertex -889.678 455.752 20.4631 + endloop + endfacet + facet normal -0.405656 0.163032 0.899369 + outer loop + vertex -884.563 464.706 21.0793 + vertex -885.874 464.811 20.4691 + vertex -888.23 455.654 21.0663 + endloop + endfacet + facet normal -0.403355 0.179536 0.897258 + outer loop + vertex -884.563 464.706 21.0793 + vertex -881.806 473.901 20.4787 + vertex -885.874 464.811 20.4691 + endloop + endfacet + facet normal -0.156182 -0.0163751 0.987593 + outer loop + vertex -916.671 327.485 21.1761 + vertex -920.42 324.926 20.5408 + vertex -916.509 318.065 21.0455 + endloop + endfacet + facet normal -0.136862 -0.0277342 0.990202 + outer loop + vertex -916.509 318.065 21.0455 + vertex -920.583 315.002 20.3966 + vertex -915.779 308.829 20.8878 + endloop + endfacet + facet normal -0.124656 -0.0391918 0.991426 + outer loop + vertex -915.779 308.829 20.8878 + vertex -919.141 305.541 20.335 + vertex -914.339 299.895 20.7157 + endloop + endfacet + facet normal -0.119629 -0.0507271 0.991522 + outer loop + vertex -914.339 299.895 20.7157 + vertex -917.7 296.804 20.152 + vertex -912.29 291.07 20.5114 + endloop + endfacet + facet normal -0.112923 -0.0596477 0.991812 + outer loop + vertex -912.29 291.07 20.5114 + vertex -915.706 287.871 19.93 + vertex -909.541 282.267 20.295 + endloop + endfacet + facet normal -0.10134 -0.0654092 0.992699 + outer loop + vertex -909.541 282.267 20.295 + vertex -912.837 278.856 19.7336 + vertex -906.174 273.733 20.0763 + endloop + endfacet + facet normal -0.0897021 -0.0689381 0.99358 + outer loop + vertex -906.174 273.733 20.0763 + vertex -909.312 270.253 19.5516 + vertex -902.339 265.678 19.8636 + endloop + endfacet + facet normal -0.0811936 -0.071858 0.994105 + outer loop + vertex -902.339 265.678 19.8636 + vertex -905.419 262.115 19.3546 + vertex -898.103 257.995 19.6543 + endloop + endfacet + facet normal -0.0729999 -0.0721843 0.994716 + outer loop + vertex -898.103 257.995 19.6543 + vertex -901.033 254.192 19.1633 + vertex -893.4 250.506 19.456 + endloop + endfacet + facet normal -0.065753 -0.0711688 0.995295 + outer loop + vertex -893.4 250.506 19.456 + vertex -896.125 246.447 18.9857 + vertex -888.216 243.127 19.2708 + endloop + endfacet + facet normal -0.0604778 -0.069371 0.995756 + outer loop + vertex -888.216 243.127 19.2708 + vertex -890.716 238.866 18.8221 + vertex -882.594 235.904 19.1091 + endloop + endfacet + facet normal -0.0569435 -0.0659527 0.996197 + outer loop + vertex -882.594 235.904 19.1091 + vertex -884.889 231.46 18.6837 + vertex -876.674 228.923 18.9852 + endloop + endfacet + facet normal -0.055134 -0.0620713 0.996548 + outer loop + vertex -876.674 228.923 18.9852 + vertex -879.046 224.408 18.5729 + vertex -871.177 222.455 18.8866 + endloop + endfacet + facet normal -0.0596482 -0.0747637 0.995416 + outer loop + vertex -863.031 218.311 19.1295 + vertex -865.597 220.799 19.1626 + vertex -866.78 216.177 18.7446 + endloop + endfacet + facet normal -0.0634316 -0.0681633 0.995656 + outer loop + vertex -863.031 218.311 19.1295 + vertex -866.78 216.177 18.7446 + vertex -860.521 213.567 18.9647 + endloop + endfacet + facet normal -0.0542257 -0.0583673 0.996821 + outer loop + vertex -871.177 222.455 18.8866 + vertex -879.046 224.408 18.5729 + vertex -873.884 217.808 18.4672 + endloop + endfacet + facet normal -0.0573224 -0.060784 0.996504 + outer loop + vertex -879.046 224.408 18.5729 + vertex -881.393 219.81 18.1574 + vertex -873.884 217.808 18.4672 + endloop + endfacet + facet normal -0.0772223 -0.0739847 0.994265 + outer loop + vertex -881.393 219.81 18.1574 + vertex -889.649 222.326 17.7034 + vertex -883.504 214.992 17.6348 + endloop + endfacet + facet normal -0.0563275 -0.0568789 0.996791 + outer loop + vertex -869.902 211.372 18.3249 + vertex -876.299 213.346 18.076 + vertex -872.694 208.231 17.9879 + endloop + endfacet + facet normal -0.0515353 -0.053625 0.99723 + outer loop + vertex -866.78 216.177 18.7446 + vertex -869.902 211.372 18.3249 + vertex -863.393 208.75 18.5202 + endloop + endfacet + facet normal -0.0587735 -0.0569076 0.996648 + outer loop + vertex -863.393 208.75 18.5202 + vertex -860.521 213.567 18.9647 + vertex -866.78 216.177 18.7446 + endloop + endfacet + facet normal -0.0599607 -0.0561968 0.996618 + outer loop + vertex -860.521 213.567 18.9647 + vertex -863.393 208.75 18.5202 + vertex -856.465 205.726 18.7666 + endloop + endfacet + facet normal -0.0748254 -0.0638483 0.995151 + outer loop + vertex -856.465 205.726 18.7666 + vertex -854.628 209.239 19.1301 + vertex -860.521 213.567 18.9647 + endloop + endfacet + facet normal -0.0571424 -0.0496983 0.997128 + outer loop + vertex -858.605 201.131 18.4149 + vertex -856.465 205.726 18.7666 + vertex -863.393 208.75 18.5202 + endloop + endfacet + facet normal -0.078609 -0.0618525 0.994985 + outer loop + vertex -854.628 209.239 19.1301 + vertex -856.465 205.726 18.7666 + vertex -848.988 202.917 19.1826 + endloop + endfacet + facet normal -0.0674511 -0.0474689 0.996593 + outer loop + vertex -850.393 198.259 18.7921 + vertex -851.966 193.531 18.4605 + vertex -842.896 190.869 18.9476 + endloop + endfacet + facet normal -0.0724379 -0.0622247 0.99543 + outer loop + vertex -851.966 193.531 18.4605 + vertex -860.765 196.267 17.9912 + vertex -853.435 188.769 18.0559 + endloop + endfacet + facet normal -0.0989335 -0.0954226 0.990508 + outer loop + vertex -853.435 188.769 18.0559 + vertex -862.573 191.375 17.3942 + vertex -854.597 183.747 17.4561 + endloop + endfacet + facet normal -0.0825625 -0.0665613 0.994361 + outer loop + vertex -844.112 186.099 18.6176 + vertex -845.166 181.332 18.2111 + vertex -835.612 178.933 18.8438 + endloop + endfacet + facet normal -0.0737915 -0.0561135 0.995694 + outer loop + vertex -834.643 183.721 19.1854 + vertex -844.112 186.099 18.6176 + vertex -835.612 178.933 18.8438 + endloop + endfacet + facet normal -0.0858197 -0.0616755 0.9944 + outer loop + vertex -833.657 188.732 19.5813 + vertex -834.643 183.721 19.1854 + vertex -825.243 181.898 19.8836 + endloop + endfacet + facet normal -0.0815784 -0.0626679 0.994695 + outer loop + vertex -825.987 176.813 19.4727 + vertex -826.815 172.01 19.1022 + vertex -817.031 170.068 19.7822 + endloop + endfacet + facet normal -0.0900584 -0.0849983 0.992303 + outer loop + vertex -826.815 172.01 19.1022 + vertex -836.501 174.176 18.4087 + vertex -827.62 167.264 18.6226 + endloop + endfacet + facet normal -0.113895 -0.125443 0.985542 + outer loop + vertex -827.62 167.264 18.6226 + vertex -837.246 169.176 17.7535 + vertex -828.241 162.237 17.9109 + endloop + endfacet + facet normal -0.0962293 -0.0953124 0.990785 + outer loop + vertex -817.752 165.268 19.3764 + vertex -818.437 160.507 18.8518 + vertex -808.407 158.685 19.6508 + endloop + endfacet + facet normal -0.0864309 -0.081314 0.992934 + outer loop + vertex -807.748 163.457 20.099 + vertex -817.752 165.268 19.3764 + vertex -808.407 158.685 19.6508 + endloop + endfacet + facet normal -0.0914794 -0.0804211 0.992554 + outer loop + vertex -807.336 168.55 20.5496 + vertex -807.748 163.457 20.099 + vertex -797.72 162.115 20.9145 + endloop + endfacet + facet normal -0.112459 -0.0973804 0.988873 + outer loop + vertex -794.976 163.731 21.3857 + vertex -797.72 162.115 20.9145 + vertex -788.237 160.801 21.8634 + endloop + endfacet + facet normal -0.0859296 -0.104381 0.990818 + outer loop + vertex -788.057 155.624 21.1988 + vertex -788.48 150.781 20.652 + vertex -778.083 149.552 21.4242 + endloop + endfacet + facet normal -0.0823285 -0.109319 0.990591 + outer loop + vertex -778.603 144.913 20.8571 + vertex -789.127 146.29 20.1343 + vertex -779.252 140.531 20.3195 + endloop + endfacet + facet normal -0.0849779 -0.0923407 0.992095 + outer loop + vertex -798.204 156.99 20.3969 + vertex -798.845 152.335 19.9087 + vertex -788.48 150.781 20.652 + endloop + endfacet + facet normal -0.0991434 -0.118627 0.987977 + outer loop + vertex -798.845 152.335 19.9087 + vertex -808.977 153.949 19.0859 + vertex -799.327 147.681 19.3016 + endloop + endfacet + facet normal -0.121518 -0.163593 0.979015 + outer loop + vertex -799.327 147.681 19.3016 + vertex -809.152 148.855 18.2783 + vertex -799.382 142.63 18.4508 + endloop + endfacet + facet normal -0.0941371 -0.129682 0.987077 + outer loop + vertex -789.127 146.29 20.1343 + vertex -789.551 141.714 19.4927 + vertex -779.252 140.531 20.3195 + endloop + endfacet + facet normal -0.0768607 -0.110172 0.990936 + outer loop + vertex -778.603 144.913 20.8571 + vertex -779.252 140.531 20.3195 + vertex -768.59 139.342 21.0144 + endloop + endfacet + facet normal -0.079955 -0.115758 0.990054 + outer loop + vertex -768.065 143.89 21.5884 + vertex -778.603 144.913 20.8571 + vertex -768.59 139.342 21.0144 + endloop + endfacet + facet normal -0.0875934 -0.141807 0.986011 + outer loop + vertex -767.861 148.702 22.2988 + vertex -768.065 143.89 21.5884 + vertex -757.841 143.313 22.4138 + endloop + endfacet + facet normal -0.0693495 -0.119992 0.99035 + outer loop + vertex -757.964 138.537 21.7135 + vertex -758.406 133.987 21.1313 + vertex -747.683 133.377 21.8082 + endloop + endfacet + facet normal -0.0726542 -0.119847 0.99013 + outer loop + vertex -758.406 133.987 21.1313 + vertex -769.182 134.987 20.4615 + vertex -758.915 129.615 20.5648 + endloop + endfacet + facet normal -0.0862161 -0.150375 0.984862 + outer loop + vertex -758.915 129.615 20.5648 + vertex -769.444 130.431 19.7676 + vertex -759.09 125.044 19.8516 + endloop + endfacet + facet normal -0.0636774 -0.123454 0.990305 + outer loop + vertex -748.047 128.813 21.2141 + vertex -748.492 124.428 20.6388 + vertex -737.528 123.821 21.2681 + endloop + endfacet + facet normal -0.0647381 -0.125693 0.989955 + outer loop + vertex -737.218 128.385 21.8678 + vertex -748.047 128.813 21.2141 + vertex -737.528 123.821 21.2681 + endloop + endfacet + facet normal -0.0714563 -0.151432 0.985882 + outer loop + vertex -737.253 133.209 22.6062 + vertex -737.218 128.385 21.8678 + vertex -726.693 128.371 22.6286 + endloop + endfacet + facet normal -0.0543193 -0.12542 0.990616 + outer loop + vertex -726.575 123.548 21.8917 + vertex -726.853 118.997 21.3003 + vertex -715.676 118.8 21.8881 + endloop + endfacet + facet normal -0.0597736 -0.125247 0.990323 + outer loop + vertex -726.853 118.997 21.3003 + vertex -737.924 119.437 20.6877 + vertex -727.252 114.631 20.724 + endloop + endfacet + facet normal -0.0740872 -0.158839 0.984521 + outer loop + vertex -727.252 114.631 20.724 + vertex -738.015 114.876 19.9536 + vertex -727.316 110.072 19.9836 + endloop + endfacet + facet normal -0.0518545 -0.122628 0.991097 + outer loop + vertex -705.525 109.882 21.306 + vertex -716.518 110.002 20.7457 + vertex -705.721 105.557 20.7606 + endloop + endfacet + facet normal -0.0484969 -0.116272 0.992033 + outer loop + vertex -705.155 114.15 21.8244 + vertex -716.134 114.329 21.3085 + vertex -705.525 109.882 21.306 + endloop + endfacet + facet normal -0.0489719 -0.149343 0.987572 + outer loop + vertex -703.947 118.756 22.5807 + vertex -705.155 114.15 21.8244 + vertex -695.308 113.827 22.2637 + endloop + endfacet + facet normal -0.0415008 -0.108108 0.993273 + outer loop + vertex -695.198 109.988 21.768 + vertex -694.792 105.727 21.3213 + vertex -684.205 106.445 21.8417 + endloop + endfacet + facet normal -0.0415325 -0.106876 0.993405 + outer loop + vertex -684.205 106.445 21.8417 + vertex -683.722 101.661 21.3473 + vertex -672.884 102.437 21.8839 + endloop + endfacet + facet normal -0.0790042 -0.19702 0.977211 + outer loop + vertex -647.832 97.8812 22.7075 + vertex -653.339 99.0904 22.5062 + vertex -649.938 96.2705 22.2125 + endloop + endfacet + facet normal -0.0825789 -0.19253 0.97781 + outer loop + vertex -647.832 97.8812 22.7075 + vertex -649.938 96.2705 22.2125 + vertex -643.504 96.0543 22.7133 + endloop + endfacet + facet normal -0.0828219 -0.206342 0.974969 + outer loop + vertex -643.504 96.0543 22.7133 + vertex -649.938 96.2705 22.2125 + vertex -643.814 93.6002 22.1677 + endloop + endfacet + facet normal -0.0901016 -0.205327 0.974537 + outer loop + vertex -643.504 96.0543 22.7133 + vertex -643.814 93.6002 22.1677 + vertex -638.032 94.1252 22.8128 + endloop + endfacet + facet normal -0.08664 -0.235439 0.96802 + outer loop + vertex -638.032 94.1252 22.8128 + vertex -643.814 93.6002 22.1677 + vertex -637.615 91.5584 22.2258 + endloop + endfacet + facet normal -0.10069 -0.237304 0.966203 + outer loop + vertex -638.032 94.1252 22.8128 + vertex -637.615 91.5584 22.2258 + vertex -632.456 92.3534 22.9587 + endloop + endfacet + facet normal -0.0946098 -0.269513 0.958338 + outer loop + vertex -632.456 92.3534 22.9587 + vertex -637.615 91.5584 22.2258 + vertex -631.886 89.7669 22.2877 + endloop + endfacet + facet normal -0.109667 -0.272218 0.955966 + outer loop + vertex -632.456 92.3534 22.9587 + vertex -631.886 89.7669 22.2877 + vertex -626.858 90.6079 23.1039 + endloop + endfacet + facet normal -0.104693 -0.295706 0.949525 + outer loop + vertex -626.858 90.6079 23.1039 + vertex -631.886 89.7669 22.2877 + vertex -626.19 87.9888 22.3619 + endloop + endfacet + facet normal -0.117748 -0.298364 0.947161 + outer loop + vertex -626.858 90.6079 23.1039 + vertex -626.19 87.9888 22.3619 + vertex -621.148 88.8476 23.2592 + endloop + endfacet + facet normal -0.113078 -0.31924 0.940903 + outer loop + vertex -621.148 88.8476 23.2592 + vertex -626.19 87.9888 22.3619 + vertex -620.391 86.2154 22.4572 + endloop + endfacet + facet normal -0.12873 -0.322764 0.937685 + outer loop + vertex -621.148 88.8476 23.2592 + vertex -620.391 86.2154 22.4572 + vertex -615.587 87.1799 23.4486 + endloop + endfacet + facet normal -0.122844 -0.344799 0.930603 + outer loop + vertex -615.587 87.1799 23.4486 + vertex -620.391 86.2154 22.4572 + vertex -614.801 84.5432 22.5755 + endloop + endfacet + facet normal -0.130926 -0.346621 0.928823 + outer loop + vertex -615.587 87.1799 23.4486 + vertex -614.801 84.5432 22.5755 + vertex -610.683 85.6683 23.5757 + endloop + endfacet + facet normal -0.126784 -0.35833 0.924946 + outer loop + vertex -610.683 85.6683 23.5757 + vertex -614.801 84.5432 22.5755 + vertex -610.018 83.0571 22.6553 + endloop + endfacet + facet normal -0.124072 -0.357836 0.925505 + outer loop + vertex -610.683 85.6683 23.5757 + vertex -610.018 83.0571 22.6553 + vertex -607.055 84.3011 23.5336 + endloop + endfacet + facet normal -0.123865 -0.35824 0.925376 + outer loop + vertex -607.055 84.3011 23.5336 + vertex -610.018 83.0571 22.6553 + vertex -606.501 81.8255 22.6493 + endloop + endfacet + facet normal -0.0908431 -0.352944 0.931224 + outer loop + vertex -607.055 84.3011 23.5336 + vertex -606.501 81.8255 22.6493 + vertex -604.838 82.9711 23.2458 + endloop + endfacet + facet normal -0.105776 -0.334058 0.936598 + outer loop + vertex -604.838 82.9711 23.2458 + vertex -606.501 81.8255 22.6493 + vertex -604.609 81.0773 22.5962 + endloop + endfacet + facet normal -0.172519 -0.338194 0.925128 + outer loop + vertex -604.838 82.9711 23.2458 + vertex -604.609 81.0773 22.5962 + vertex -604.133 81.3022 22.767 + endloop + endfacet + facet normal -0.050065 -0.131465 0.990056 + outer loop + vertex -649.938 96.2705 22.2125 + vertex -651.585 93.5135 21.7632 + vertex -643.814 93.6002 22.1677 + endloop + endfacet + facet normal -0.0499387 -0.138407 0.989116 + outer loop + vertex -643.814 93.6002 22.1677 + vertex -651.585 93.5135 21.7632 + vertex -643.44 90.6422 21.7726 + endloop + endfacet + facet normal -0.0399933 -0.110182 0.993106 + outer loop + vertex -651.585 93.5135 21.7632 + vertex -651.377 89.6996 21.3484 + vertex -643.44 90.6422 21.7726 + endloop + endfacet + facet normal -0.0396949 -0.110168 0.99312 + outer loop + vertex -651.585 93.5135 21.7632 + vertex -661.526 93.3634 21.3492 + vertex -651.377 89.6996 21.3484 + endloop + endfacet + facet normal -0.0420562 -0.109131 0.993137 + outer loop + vertex -672.884 102.437 21.8839 + vertex -672.38 97.4992 21.3626 + vertex -660.486 98.1127 21.9337 + endloop + endfacet + facet normal -0.0459945 -0.122938 0.991348 + outer loop + vertex -672.38 97.4992 21.3626 + vertex -683.609 97.0181 20.7819 + vertex -672.46 92.8727 20.7851 + endloop + endfacet + facet normal -0.0607449 -0.164767 0.98446 + outer loop + vertex -672.46 92.8727 20.7851 + vertex -683.428 92.3111 20.0144 + vertex -672.259 88.2075 20.0167 + endloop + endfacet + facet normal -0.045067 -0.125048 0.991127 + outer loop + vertex -661.526 93.3634 21.3492 + vertex -661.542 88.9537 20.7921 + vertex -651.377 89.6996 21.3484 + endloop + endfacet + facet normal -0.0573644 -0.168285 0.984068 + outer loop + vertex -650.583 85.3379 20.8202 + vertex -661.141 84.3051 20.0281 + vertex -649.909 80.5438 20.0396 + endloop + endfacet + facet normal -0.0511429 -0.141078 0.988677 + outer loop + vertex -617.999 79.7895 21.5865 + vertex -618.014 74.7857 20.8717 + vertex -610.039 76.8679 21.5814 + endloop + endfacet + facet normal -0.0486444 -0.132542 0.989983 + outer loop + vertex -628.816 83.2085 21.5128 + vertex -628.018 78.204 20.8819 + vertex -617.999 79.7895 21.5865 + endloop + endfacet + facet normal -0.0447599 -0.128533 0.990695 + outer loop + vertex -640.234 86.6858 21.448 + vertex -639.286 81.7982 20.8568 + vertex -628.816 83.2085 21.5128 + endloop + endfacet + facet normal -0.0395779 -0.113518 0.992747 + outer loop + vertex -651.377 89.6996 21.3484 + vertex -640.234 86.6858 21.448 + vertex -643.44 90.6422 21.7726 + endloop + endfacet + facet normal -0.0550699 -0.139008 0.988759 + outer loop + vertex -643.814 93.6002 22.1677 + vertex -643.44 90.6422 21.7726 + vertex -637.615 91.5584 22.2258 + endloop + endfacet +endsolid diff --git a/noether_examples/meshes/outputs/output_19.stl b/noether_examples/meshes/outputs/output_19.stl new file mode 100644 index 00000000..e7927683 --- /dev/null +++ b/noether_examples/meshes/outputs/output_19.stl @@ -0,0 +1,6001 @@ +solid ascii + facet normal -0.549074 -0.580361 -0.601414 + outer loop + vertex -687.574 141.077 293.99 + vertex -689.763 141.631 295.455 + vertex -688.847 142.235 294.035 + endloop + endfacet + facet normal -0.556789 -0.571633 -0.602678 + outer loop + vertex -689.763 141.631 295.455 + vertex -690.722 142.349 295.659 + vertex -688.847 142.235 294.035 + endloop + endfacet + facet normal -0.573905 -0.528617 -0.625457 + outer loop + vertex -688.847 142.235 294.035 + vertex -690.722 142.349 295.659 + vertex -689.486 142.854 294.098 + endloop + endfacet + facet normal -0.586387 -0.51001 -0.629317 + outer loop + vertex -690.722 142.349 295.659 + vertex -690.924 142.781 295.498 + vertex -689.486 142.854 294.098 + endloop + endfacet + facet normal -0.606017 -0.46275 -0.646997 + outer loop + vertex -689.486 142.854 294.098 + vertex -690.924 142.781 295.498 + vertex -689.634 143.089 294.069 + endloop + endfacet + facet normal -0.55337 -0.556558 -0.619697 + outer loop + vertex -690.924 142.781 295.498 + vertex -690.94 142.851 295.448 + vertex -689.634 143.089 294.069 + endloop + endfacet + facet normal 0.53491 -0.756722 0.375822 + outer loop + vertex -689.634 143.089 294.069 + vertex -690.94 142.851 295.448 + vertex -689.42 143.115 293.816 + endloop + endfacet + facet normal -0.424836 -0.744135 -0.515536 + outer loop + vertex -689.42 143.115 293.816 + vertex -690.94 142.851 295.448 + vertex -691.353 142.932 295.671 + endloop + endfacet + facet normal -0.455513 -0.652316 -0.605798 + outer loop + vertex -691.718 142.613 296.29 + vertex -691.353 142.932 295.671 + vertex -690.94 142.851 295.448 + endloop + endfacet + facet normal -0.531063 -0.5832 -0.614695 + outer loop + vertex -693.615 143.55 297.04 + vertex -691.353 142.932 295.671 + vertex -691.718 142.613 296.29 + endloop + endfacet + facet normal -0.526531 -0.541406 -0.655473 + outer loop + vertex -691.718 142.613 296.29 + vertex -690.646 141.342 296.479 + vertex -693.615 143.55 297.04 + endloop + endfacet + facet normal -0.510993 -0.511546 -0.690802 + outer loop + vertex -691.388 141.209 297.126 + vertex -693.615 143.55 297.04 + vertex -690.646 141.342 296.479 + endloop + endfacet + facet normal -0.490149 -0.551375 -0.675084 + outer loop + vertex -689.318 139.552 296.976 + vertex -691.388 141.209 297.126 + vertex -690.646 141.342 296.479 + endloop + endfacet + facet normal -0.486474 -0.549749 -0.679057 + outer loop + vertex -690.646 141.342 296.479 + vertex -686.803 138.452 296.066 + vertex -689.318 139.552 296.976 + endloop + endfacet + facet normal -0.501898 -0.568145 -0.652158 + outer loop + vertex -691.388 141.209 297.126 + vertex -689.318 139.552 296.976 + vertex -690.67 139.775 297.822 + endloop + endfacet + facet normal -0.578984 -0.572152 -0.580878 + outer loop + vertex -693.615 143.55 297.04 + vertex -691.388 141.209 297.126 + vertex -690.67 139.775 297.822 + endloop + endfacet + facet normal -0.45319 -0.505772 -0.734039 + outer loop + vertex -694.396 142.026 298.572 + vertex -693.615 143.55 297.04 + vertex -690.67 139.775 297.822 + endloop + endfacet + facet normal -0.469954 -0.547363 -0.692486 + outer loop + vertex -690.67 139.775 297.822 + vertex -691.167 138.218 299.391 + vertex -694.396 142.026 298.572 + endloop + endfacet + facet normal -0.45178 -0.506715 -0.734258 + outer loop + vertex -693.615 143.55 297.04 + vertex -694.396 142.026 298.572 + vertex -695.433 143.453 298.225 + endloop + endfacet + facet normal -0.444445 -0.526657 -0.724638 + outer loop + vertex -696.135 143.944 298.3 + vertex -693.615 143.55 297.04 + vertex -695.433 143.453 298.225 + endloop + endfacet + facet normal -0.474938 -0.517981 -0.711428 + outer loop + vertex -696.285 143.722 298.598 + vertex -695.433 143.453 298.225 + vertex -694.396 142.026 298.572 + endloop + endfacet + facet normal -0.477807 -0.521241 -0.707113 + outer loop + vertex -696.701 143.857 298.78 + vertex -696.285 143.722 298.598 + vertex -694.396 142.026 298.572 + endloop + endfacet + facet normal -0.440932 -0.468177 -0.76576 + outer loop + vertex -697.056 143.646 299.113 + vertex -696.701 143.857 298.78 + vertex -694.396 142.026 298.572 + endloop + endfacet + facet normal -0.434287 -0.45298 -0.778591 + outer loop + vertex -697.387 142.631 299.889 + vertex -697.056 143.646 299.113 + vertex -694.396 142.026 298.572 + endloop + endfacet + facet normal -0.416038 -0.462344 -0.783039 + outer loop + vertex -697.056 143.646 299.113 + vertex -697.387 142.631 299.889 + vertex -700.472 144.968 300.148 + endloop + endfacet + facet normal -0.428898 -0.483822 -0.762864 + outer loop + vertex -697.056 143.646 299.113 + vertex -699.675 145.183 299.611 + vertex -696.701 143.857 298.78 + endloop + endfacet + facet normal -0.472693 -0.634582 -0.611447 + outer loop + vertex -696.701 143.857 298.78 + vertex -698.886 144.987 299.297 + vertex -696.285 143.722 298.598 + endloop + endfacet + facet normal -0.468034 -0.645259 -0.603809 + outer loop + vertex -696.285 143.722 298.598 + vertex -698.067 144.583 299.06 + vertex -695.433 143.453 298.225 + endloop + endfacet + facet normal -0.545377 -0.553434 -0.629504 + outer loop + vertex -690.646 141.342 296.479 + vertex -691.718 142.613 296.29 + vertex -690.722 142.349 295.659 + endloop + endfacet + facet normal -0.550249 -0.431392 -0.714932 + outer loop + vertex -691.353 142.932 295.671 + vertex -693.615 143.55 297.04 + vertex -692.987 143.724 296.452 + endloop + endfacet + facet normal 0.559011 0.509018 0.654528 + outer loop + vertex -692.987 143.724 296.452 + vertex -691.747 142.979 295.972 + vertex -691.353 142.932 295.671 + endloop + endfacet + facet normal -0.548514 -0.543438 -0.635459 + outer loop + vertex -691.747 142.979 295.972 + vertex -690.477 142.91 294.935 + vertex -691.353 142.932 295.671 + endloop + endfacet + facet normal -0.571046 -0.477959 -0.667429 + outer loop + vertex -691.747 142.979 295.972 + vertex -691.383 143.311 295.423 + vertex -690.477 142.91 294.935 + endloop + endfacet + facet normal -0.571559 -0.493712 -0.655415 + outer loop + vertex -691.383 143.311 295.423 + vertex -690.052 143.535 294.093 + vertex -690.477 142.91 294.935 + endloop + endfacet + facet normal -0.597861 -0.468797 -0.650224 + outer loop + vertex -690.477 142.91 294.935 + vertex -690.052 143.535 294.093 + vertex -689.375 143.146 293.752 + endloop + endfacet + facet normal -0.602763 -0.507917 -0.615383 + outer loop + vertex -689.375 143.146 293.752 + vertex -690.052 143.535 294.093 + vertex -688.225 144.133 291.81 + endloop + endfacet + facet normal -0.589795 -0.455019 -0.667158 + outer loop + vertex -690.052 143.535 294.093 + vertex -691.383 143.311 295.423 + vertex -691.054 144.105 294.591 + endloop + endfacet + facet normal -0.590182 -0.457448 -0.665152 + outer loop + vertex -690.436 144.251 293.942 + vertex -690.052 143.535 294.093 + vertex -691.054 144.105 294.591 + endloop + endfacet + facet normal -0.591158 -0.455473 -0.665639 + outer loop + vertex -691.054 144.105 294.591 + vertex -691.114 145.486 293.699 + vertex -690.436 144.251 293.942 + endloop + endfacet + facet normal -0.610203 -0.461633 -0.643854 + outer loop + vertex -690.436 144.251 293.942 + vertex -691.114 145.486 293.699 + vertex -689.926 145.188 292.786 + endloop + endfacet + facet normal -0.614255 -0.436646 -0.657291 + outer loop + vertex -691.326 147.686 292.435 + vertex -689.926 145.188 292.786 + vertex -691.114 145.486 293.699 + endloop + endfacet + facet normal -0.611955 -0.437376 -0.658948 + outer loop + vertex -692.389 147.783 293.358 + vertex -691.326 147.686 292.435 + vertex -691.114 145.486 293.699 + endloop + endfacet + facet normal -0.593407 -0.43025 -0.680259 + outer loop + vertex -691.999 145.555 294.427 + vertex -692.389 147.783 293.358 + vertex -691.114 145.486 293.699 + endloop + endfacet + facet normal -0.590339 -0.43082 -0.682564 + outer loop + vertex -693.228 147.643 294.172 + vertex -692.389 147.783 293.358 + vertex -691.999 145.555 294.427 + endloop + endfacet + facet normal -0.577198 -0.424888 -0.697361 + outer loop + vertex -692.706 145.482 295.057 + vertex -693.228 147.643 294.172 + vertex -691.999 145.555 294.427 + endloop + endfacet + facet normal -0.566674 -0.452263 -0.688723 + outer loop + vertex -692.706 145.482 295.057 + vertex -691.999 145.555 294.427 + vertex -691.838 144.238 295.159 + endloop + endfacet + facet normal -0.563958 -0.450636 -0.69201 + outer loop + vertex -692.411 144.136 295.693 + vertex -692.706 145.482 295.057 + vertex -691.838 144.238 295.159 + endloop + endfacet + facet normal -0.556042 -0.468038 -0.686847 + outer loop + vertex -691.838 144.238 295.159 + vertex -691.383 143.311 295.423 + vertex -692.411 144.136 295.693 + endloop + endfacet + facet normal -0.562226 -0.450854 -0.693277 + outer loop + vertex -693.335 145.549 295.523 + vertex -692.706 145.482 295.057 + vertex -692.411 144.136 295.693 + endloop + endfacet + facet normal -0.554219 -0.446703 -0.702351 + outer loop + vertex -693.087 144.451 296.026 + vertex -693.335 145.549 295.523 + vertex -692.411 144.136 295.693 + endloop + endfacet + facet normal -0.556666 -0.47119 -0.684181 + outer loop + vertex -693.087 144.451 296.026 + vertex -692.411 144.136 295.693 + vertex -692.476 143.536 296.159 + endloop + endfacet + facet normal -0.58416 -0.484758 -0.650973 + outer loop + vertex -693.087 144.451 296.026 + vertex -692.476 143.536 296.159 + vertex -693.516 144.685 296.236 + endloop + endfacet + facet normal -0.578897 -0.447915 -0.68136 + outer loop + vertex -693.087 144.451 296.026 + vertex -693.516 144.685 296.236 + vertex -693.937 145.892 295.801 + endloop + endfacet + facet normal -0.562629 -0.462983 -0.684906 + outer loop + vertex -693.516 144.685 296.236 + vertex -692.476 143.536 296.159 + vertex -692.987 143.724 296.452 + endloop + endfacet + facet normal -0.600527 -0.47454 -0.643567 + outer loop + vertex -694.089 145.34 296.288 + vertex -693.516 144.685 296.236 + vertex -692.987 143.724 296.452 + endloop + endfacet + facet normal -0.567479 -0.456248 -0.685423 + outer loop + vertex -694.089 145.34 296.288 + vertex -692.987 143.724 296.452 + vertex -694.2 145.253 296.438 + endloop + endfacet + facet normal -0.547546 -0.421853 -0.722657 + outer loop + vertex -694.089 145.34 296.288 + vertex -694.724 147.089 295.748 + vertex -693.516 144.685 296.236 + endloop + endfacet + facet normal -0.578377 -0.42492 -0.696364 + outer loop + vertex -695.158 147.462 295.881 + vertex -694.724 147.089 295.748 + vertex -694.089 145.34 296.288 + endloop + endfacet + facet normal -0.589058 -0.428186 -0.685323 + outer loop + vertex -694.2 145.253 296.438 + vertex -695.158 147.462 295.881 + vertex -694.089 145.34 296.288 + endloop + endfacet + facet normal -0.625198 -0.434531 -0.648314 + outer loop + vertex -695.307 147.497 296.001 + vertex -695.158 147.462 295.881 + vertex -694.2 145.253 296.438 + endloop + endfacet + facet normal -0.571382 -0.444789 -0.689699 + outer loop + vertex -693.937 145.892 295.801 + vertex -693.335 145.549 295.523 + vertex -693.087 144.451 296.026 + endloop + endfacet + facet normal -0.565954 -0.418707 -0.710198 + outer loop + vertex -693.937 145.892 295.801 + vertex -694.332 147.547 295.14 + vertex -693.335 145.549 295.523 + endloop + endfacet + facet normal -0.581874 -0.423594 -0.694256 + outer loop + vertex -694.332 147.547 295.14 + vertex -693.672 147.128 294.842 + vertex -693.335 145.549 295.523 + endloop + endfacet + facet normal -0.573346 -0.392287 -0.719295 + outer loop + vertex -693.672 147.128 294.842 + vertex -694.332 147.547 295.14 + vertex -694.672 150.08 294.03 + endloop + endfacet + facet normal -0.596843 -0.394567 -0.698638 + outer loop + vertex -693.672 147.128 294.842 + vertex -694.672 150.08 294.03 + vertex -693.228 147.643 294.172 + endloop + endfacet + facet normal -0.602869 -0.397728 -0.691637 + outer loop + vertex -694.672 150.08 294.03 + vertex -693.863 150.657 292.992 + vertex -693.228 147.643 294.172 + endloop + endfacet + facet normal -0.592732 -0.388777 -0.705352 + outer loop + vertex -695.481 149.97 294.77 + vertex -694.672 150.08 294.03 + vertex -694.332 147.547 295.14 + endloop + endfacet + facet normal -0.58193 -0.385313 -0.716164 + outer loop + vertex -694.66 147.46 295.453 + vertex -695.481 149.97 294.77 + vertex -694.332 147.547 295.14 + endloop + endfacet + facet normal -0.666081 -0.390821 -0.635291 + outer loop + vertex -694.724 147.089 295.748 + vertex -695.481 149.97 294.77 + vertex -694.66 147.46 295.453 + endloop + endfacet + facet normal -0.586951 -0.394403 -0.707061 + outer loop + vertex -696.126 150.376 295.078 + vertex -695.481 149.97 294.77 + vertex -694.724 147.089 295.748 + endloop + endfacet + facet normal -0.557813 -0.387457 -0.733977 + outer loop + vertex -695.158 147.462 295.881 + vertex -696.126 150.376 295.078 + vertex -694.724 147.089 295.748 + endloop + endfacet + facet normal -0.560194 -0.38771 -0.732027 + outer loop + vertex -696.51 150.656 295.224 + vertex -696.126 150.376 295.078 + vertex -695.158 147.462 295.881 + endloop + endfacet + facet normal -0.6301 -0.403205 -0.663626 + outer loop + vertex -695.307 147.497 296.001 + vertex -696.51 150.656 295.224 + vertex -695.158 147.462 295.881 + endloop + endfacet + facet normal -0.703864 -0.410617 -0.579629 + outer loop + vertex -696.826 151.213 295.214 + vertex -696.51 150.656 295.224 + vertex -695.307 147.497 296.001 + endloop + endfacet + facet normal -0.566782 -0.418654 -0.709568 + outer loop + vertex -694.66 147.46 295.453 + vertex -694.332 147.547 295.14 + vertex -693.937 145.892 295.801 + endloop + endfacet + facet normal -0.606916 -0.428271 -0.669505 + outer loop + vertex -694.66 147.46 295.453 + vertex -693.937 145.892 295.801 + vertex -694.724 147.089 295.748 + endloop + endfacet + facet normal -0.567989 -0.425151 -0.704724 + outer loop + vertex -693.335 145.549 295.523 + vertex -693.672 147.128 294.842 + vertex -692.706 145.482 295.057 + endloop + endfacet + facet normal -0.573174 -0.45065 -0.684388 + outer loop + vertex -691.838 144.238 295.159 + vertex -691.999 145.555 294.427 + vertex -691.054 144.105 294.591 + endloop + endfacet + facet normal -0.568807 -0.425515 -0.703843 + outer loop + vertex -693.672 147.128 294.842 + vertex -693.228 147.643 294.172 + vertex -692.706 145.482 295.057 + endloop + endfacet + facet normal -0.603899 -0.397618 -0.690801 + outer loop + vertex -692.389 147.783 293.358 + vertex -693.228 147.643 294.172 + vertex -693.863 150.657 292.992 + endloop + endfacet + facet normal -0.622171 -0.40439 -0.670352 + outer loop + vertex -693.863 150.657 292.992 + vertex -692.847 150.721 292.011 + vertex -692.389 147.783 293.358 + endloop + endfacet + facet normal -0.620214 -0.404802 -0.671916 + outer loop + vertex -692.389 147.783 293.358 + vertex -692.847 150.721 292.011 + vertex -691.326 147.686 292.435 + endloop + endfacet + facet normal -0.642636 -0.412376 -0.645729 + outer loop + vertex -692.847 150.721 292.011 + vertex -691.719 150.695 290.905 + vertex -691.326 147.686 292.435 + endloop + endfacet + facet normal -0.643501 -0.41213 -0.645023 + outer loop + vertex -691.326 147.686 292.435 + vertex -691.719 150.695 290.905 + vertex -690.156 147.714 291.25 + endloop + endfacet + facet normal -0.662014 -0.419101 -0.621363 + outer loop + vertex -691.719 150.695 290.905 + vertex -690.544 150.766 289.605 + vertex -690.156 147.714 291.25 + endloop + endfacet + facet normal -0.665669 -0.417894 -0.618263 + outer loop + vertex -690.156 147.714 291.25 + vertex -690.544 150.766 289.605 + vertex -688.948 147.86 289.85 + endloop + endfacet + facet normal -0.681322 -0.424634 -0.596227 + outer loop + vertex -690.544 150.766 289.605 + vertex -689.382 150.959 288.14 + vertex -688.948 147.86 289.85 + endloop + endfacet + facet normal -0.684456 -0.423524 -0.59342 + outer loop + vertex -688.948 147.86 289.85 + vertex -689.382 150.959 288.14 + vertex -687.772 148.097 288.325 + endloop + endfacet + facet normal -0.700188 -0.430814 -0.569329 + outer loop + vertex -689.382 150.959 288.14 + vertex -688.276 151.22 286.582 + vertex -687.772 148.097 288.325 + endloop + endfacet + facet normal -0.70256 -0.429934 -0.567068 + outer loop + vertex -687.772 148.097 288.325 + vertex -688.276 151.22 286.582 + vertex -686.679 148.403 286.738 + endloop + endfacet + facet normal -0.716737 -0.436678 -0.543691 + outer loop + vertex -688.276 151.22 286.582 + vertex -687.258 151.569 284.959 + vertex -686.679 148.403 286.738 + endloop + endfacet + facet normal -0.721077 -0.434995 -0.539283 + outer loop + vertex -686.679 148.403 286.738 + vertex -687.258 151.569 284.959 + vertex -685.681 148.777 285.103 + endloop + endfacet + facet normal -0.732981 -0.440634 -0.518248 + outer loop + vertex -687.258 151.569 284.959 + vertex -686.313 151.952 283.297 + vertex -685.681 148.777 285.103 + endloop + endfacet + facet normal -0.736595 -0.439148 -0.514371 + outer loop + vertex -685.681 148.777 285.103 + vertex -686.313 151.952 283.297 + vertex -684.752 149.19 283.42 + endloop + endfacet + facet normal -0.747131 -0.444216 -0.494437 + outer loop + vertex -686.313 151.952 283.297 + vertex -685.433 152.365 281.597 + vertex -684.752 149.19 283.42 + endloop + endfacet + facet normal -0.7509 -0.442579 -0.490177 + outer loop + vertex -684.752 149.19 283.42 + vertex -685.433 152.365 281.597 + vertex -683.887 149.642 281.687 + endloop + endfacet + facet normal -0.760095 -0.44718 -0.471472 + outer loop + vertex -685.433 152.365 281.597 + vertex -684.609 152.788 279.868 + vertex -683.887 149.642 281.687 + endloop + endfacet + facet normal -0.762834 -0.445929 -0.468222 + outer loop + vertex -683.887 149.642 281.687 + vertex -684.609 152.788 279.868 + vertex -683.068 150.088 279.927 + endloop + endfacet + facet normal -0.770387 -0.44988 -0.451787 + outer loop + vertex -684.609 152.788 279.868 + vertex -683.843 153.243 278.109 + vertex -683.068 150.088 279.927 + endloop + endfacet + facet normal -0.774557 -0.447907 -0.446587 + outer loop + vertex -683.068 150.088 279.927 + vertex -683.843 153.243 278.109 + vertex -682.314 150.568 278.139 + endloop + endfacet + facet normal -0.781521 -0.451704 -0.430335 + outer loop + vertex -683.843 153.243 278.109 + vertex -683.127 153.701 276.326 + vertex -682.314 150.568 278.139 + endloop + endfacet + facet normal -0.784821 -0.450066 -0.426024 + outer loop + vertex -682.314 150.568 278.139 + vertex -683.127 153.701 276.326 + vertex -681.604 151.05 276.322 + endloop + endfacet + facet normal -0.790633 -0.453428 -0.411464 + outer loop + vertex -683.127 153.701 276.326 + vertex -682.46 154.182 274.515 + vertex -681.604 151.05 276.322 + endloop + endfacet + facet normal -0.794489 -0.451439 -0.406188 + outer loop + vertex -681.604 151.05 276.322 + vertex -682.46 154.182 274.515 + vertex -680.943 151.541 274.483 + endloop + endfacet + facet normal -0.799478 -0.45447 -0.392799 + outer loop + vertex -682.46 154.182 274.515 + vertex -681.843 154.677 272.686 + vertex -680.943 151.541 274.483 + endloop + endfacet + facet normal -0.80357 -0.452281 -0.386933 + outer loop + vertex -680.943 151.541 274.483 + vertex -681.843 154.677 272.686 + vertex -680.327 152.019 272.645 + endloop + endfacet + facet normal -0.80825 -0.455156 -0.373584 + outer loop + vertex -681.843 154.677 272.686 + vertex -681.271 155.167 270.852 + vertex -680.327 152.019 272.645 + endloop + endfacet + facet normal -0.810859 -0.45371 -0.369669 + outer loop + vertex -680.327 152.019 272.645 + vertex -681.271 155.167 270.852 + vertex -679.768 152.513 270.812 + endloop + endfacet + facet normal -0.814946 -0.45621 -0.3574 + outer loop + vertex -681.271 155.167 270.852 + vertex -680.746 155.663 269.023 + vertex -679.768 152.513 270.812 + endloop + endfacet + facet normal -0.817864 -0.45453 -0.352846 + outer loop + vertex -679.768 152.513 270.812 + vertex -680.746 155.663 269.023 + vertex -679.263 153.007 269.006 + endloop + endfacet + facet normal -0.821658 -0.456722 -0.341003 + outer loop + vertex -680.746 155.663 269.023 + vertex -680.268 156.155 267.209 + vertex -679.263 153.007 269.006 + endloop + endfacet + facet normal -0.823604 -0.45555 -0.337863 + outer loop + vertex -679.263 153.007 269.006 + vertex -680.268 156.155 267.209 + vertex -678.806 153.506 267.22 + endloop + endfacet + facet normal -0.827443 -0.457618 -0.325458 + outer loop + vertex -680.268 156.155 267.209 + vertex -679.833 156.648 265.412 + vertex -678.806 153.506 267.22 + endloop + endfacet + facet normal -0.828783 -0.456774 -0.323229 + outer loop + vertex -678.806 153.506 267.22 + vertex -679.833 156.648 265.412 + vertex -678.391 154.013 265.438 + endloop + endfacet + facet normal -0.831553 -0.458195 -0.313969 + outer loop + vertex -679.833 156.648 265.412 + vertex -679.45 157.185 263.614 + vertex -678.391 154.013 265.438 + endloop + endfacet + facet normal -0.834159 -0.456496 -0.309501 + outer loop + vertex -678.391 154.013 265.438 + vertex -679.45 157.185 263.614 + vertex -678.021 154.556 263.64 + endloop + endfacet + facet normal -0.83694 -0.457912 -0.299746 + outer loop + vertex -679.45 157.185 263.614 + vertex -679.099 157.729 261.802 + vertex -678.021 154.556 263.64 + endloop + endfacet + facet normal -0.840372 -0.455558 -0.293669 + outer loop + vertex -678.021 154.556 263.64 + vertex -679.099 157.729 261.802 + vertex -677.666 155.075 261.819 + endloop + endfacet + facet normal -0.843688 -0.457273 -0.281231 + outer loop + vertex -679.099 157.729 261.802 + vertex -678.738 158.178 259.991 + vertex -677.666 155.075 261.819 + endloop + endfacet + facet normal -0.844943 -0.456358 -0.278942 + outer loop + vertex -677.666 155.075 261.819 + vertex -678.738 158.178 259.991 + vertex -677.303 155.511 260.005 + endloop + endfacet + facet normal -0.847889 -0.45788 -0.267263 + outer loop + vertex -678.738 158.178 259.991 + vertex -678.328 158.435 258.249 + vertex -677.303 155.511 260.005 + endloop + endfacet + facet normal -0.847865 -0.457899 -0.267308 + outer loop + vertex -677.303 155.511 260.005 + vertex -678.328 158.435 258.249 + vertex -676.944 155.875 258.244 + endloop + endfacet + facet normal -0.848782 -0.458403 -0.263507 + outer loop + vertex -678.328 158.435 258.249 + vertex -677.907 158.491 256.796 + vertex -676.944 155.875 258.244 + endloop + endfacet + facet normal -0.847365 -0.459418 -0.266285 + outer loop + vertex -676.944 155.875 258.244 + vertex -677.907 158.491 256.796 + vertex -676.751 156.584 256.407 + endloop + endfacet + facet normal -0.841272 -0.448446 -0.301924 + outer loop + vertex -677.907 158.491 256.796 + vertex -678.404 160.833 254.7 + vertex -676.751 156.584 256.407 + endloop + endfacet + facet normal -0.864937 -0.436133 -0.248338 + outer loop + vertex -676.751 156.584 256.407 + vertex -678.404 160.833 254.7 + vertex -676.589 157.394 254.419 + endloop + endfacet + facet normal -0.866062 -0.437208 -0.242458 + outer loop + vertex -678.404 160.833 254.7 + vertex -678.049 161.376 252.455 + vertex -676.589 157.394 254.419 + endloop + endfacet + facet normal -0.870816 -0.433616 -0.231637 + outer loop + vertex -676.589 157.394 254.419 + vertex -678.049 161.376 252.455 + vertex -676.302 157.881 252.429 + endloop + endfacet + facet normal -0.872842 -0.434704 -0.221763 + outer loop + vertex -678.049 161.376 252.455 + vertex -677.761 161.809 250.471 + vertex -676.302 157.881 252.429 + endloop + endfacet + facet normal -0.873929 -0.433825 -0.219191 + outer loop + vertex -676.302 157.881 252.429 + vertex -677.761 161.809 250.471 + vertex -676.045 158.348 250.479 + endloop + endfacet + facet normal -0.875522 -0.434596 -0.211157 + outer loop + vertex -677.761 161.809 250.471 + vertex -677.538 162.295 248.544 + vertex -676.045 158.348 250.479 + endloop + endfacet + facet normal -0.876176 -0.434056 -0.20955 + outer loop + vertex -676.045 158.348 250.479 + vertex -677.538 162.295 248.544 + vertex -675.831 158.859 248.529 + endloop + endfacet + facet normal -0.877539 -0.434765 -0.202248 + outer loop + vertex -677.538 162.295 248.544 + vertex -677.347 162.802 246.628 + vertex -675.831 158.859 248.529 + endloop + endfacet + facet normal -0.877839 -0.434513 -0.201486 + outer loop + vertex -675.831 158.859 248.529 + vertex -677.347 162.802 246.628 + vertex -675.648 159.39 246.583 + endloop + endfacet + facet normal -0.879371 -0.435394 -0.192715 + outer loop + vertex -677.347 162.802 246.628 + vertex -677.172 163.292 244.72 + vertex -675.648 159.39 246.583 + endloop + endfacet + facet normal -0.8801 -0.434764 -0.190799 + outer loop + vertex -675.648 159.39 246.583 + vertex -677.172 163.292 244.72 + vertex -675.481 159.897 244.66 + endloop + endfacet + facet normal -0.881001 -0.43531 -0.185318 + outer loop + vertex -677.172 163.292 244.72 + vertex -677.013 163.772 242.838 + vertex -675.481 159.897 244.66 + endloop + endfacet + facet normal -0.882504 -0.433983 -0.181234 + outer loop + vertex -675.481 159.897 244.66 + vertex -677.013 163.772 242.838 + vertex -675.327 160.368 242.782 + endloop + endfacet + facet normal -0.883185 -0.434391 -0.176888 + outer loop + vertex -677.013 163.772 242.838 + vertex -676.873 164.238 240.998 + vertex -675.327 160.368 242.782 + endloop + endfacet + facet normal -0.884821 -0.432915 -0.172267 + outer loop + vertex -675.327 160.368 242.782 + vertex -676.873 164.238 240.998 + vertex -675.188 160.81 240.958 + endloop + endfacet + facet normal -0.885769 -0.433454 -0.165926 + outer loop + vertex -676.873 164.238 240.998 + vertex -676.745 164.662 239.205 + vertex -675.188 160.81 240.958 + endloop + endfacet + facet normal -0.885821 -0.433406 -0.165775 + outer loop + vertex -675.188 160.81 240.958 + vertex -676.745 164.662 239.205 + vertex -675.071 161.252 239.175 + endloop + endfacet + facet normal -0.88653 -0.433796 -0.160887 + outer loop + vertex -676.745 164.662 239.205 + vertex -676.635 165.093 237.437 + vertex -675.071 161.252 239.175 + endloop + endfacet + facet normal -0.887261 -0.433106 -0.158703 + outer loop + vertex -675.071 161.252 239.175 + vertex -676.635 165.093 237.437 + vertex -674.964 161.681 237.408 + endloop + endfacet + facet normal -0.888115 -0.433576 -0.152521 + outer loop + vertex -676.635 165.093 237.437 + vertex -676.53 165.504 235.659 + vertex -674.964 161.681 237.408 + endloop + endfacet + facet normal -0.888414 -0.433284 -0.151614 + outer loop + vertex -674.964 161.681 237.408 + vertex -676.53 165.504 235.659 + vertex -674.86 162.095 235.617 + endloop + endfacet + facet normal -0.889169 -0.433726 -0.145808 + outer loop + vertex -676.53 165.504 235.659 + vertex -676.433 165.917 233.836 + vertex -674.86 162.095 235.617 + endloop + endfacet + facet normal -0.889759 -0.433122 -0.143992 + outer loop + vertex -674.86 162.095 235.617 + vertex -676.433 165.917 233.836 + vertex -674.757 162.493 233.778 + endloop + endfacet + facet normal -0.889947 -0.43324 -0.142468 + outer loop + vertex -676.433 165.917 233.836 + vertex -676.344 166.353 231.953 + vertex -674.757 162.493 233.778 + endloop + endfacet + facet normal -0.891303 -0.431811 -0.138266 + outer loop + vertex -674.757 162.493 233.778 + vertex -676.344 166.353 231.953 + vertex -674.666 162.913 231.882 + endloop + endfacet + facet normal -0.892066 -0.432319 -0.131597 + outer loop + vertex -676.344 166.353 231.953 + vertex -676.255 166.757 230.029 + vertex -674.666 162.913 231.882 + endloop + endfacet + facet normal -0.891754 -0.432663 -0.132578 + outer loop + vertex -674.666 162.913 231.882 + vertex -676.255 166.757 230.029 + vertex -674.588 163.345 229.948 + endloop + endfacet + facet normal -0.892201 -0.432978 -0.128482 + outer loop + vertex -676.255 166.757 230.029 + vertex -676.18 167.177 228.09 + vertex -674.588 163.345 229.948 + endloop + endfacet + facet normal -0.893091 -0.431974 -0.125649 + outer loop + vertex -674.588 163.345 229.948 + vertex -676.18 167.177 228.09 + vertex -674.51 163.746 228.013 + endloop + endfacet + facet normal -0.893488 -0.432254 -0.121803 + outer loop + vertex -676.18 167.177 228.09 + vertex -676.115 167.586 226.163 + vertex -674.51 163.746 228.013 + endloop + endfacet + facet normal -0.89374 -0.431964 -0.120982 + outer loop + vertex -674.51 163.746 228.013 + vertex -676.115 167.586 226.163 + vertex -674.451 164.163 226.086 + endloop + endfacet + facet normal -0.894235 -0.432317 -0.115958 + outer loop + vertex -676.115 167.586 226.163 + vertex -676.054 167.97 224.262 + vertex -674.451 164.163 226.086 + endloop + endfacet + facet normal -0.894397 -0.432126 -0.115417 + outer loop + vertex -674.451 164.163 226.086 + vertex -676.054 167.97 224.262 + vertex -674.391 164.548 224.184 + endloop + endfacet + facet normal -0.894831 -0.432442 -0.110776 + outer loop + vertex -676.054 167.97 224.262 + vertex -675.995 168.33 222.374 + vertex -674.391 164.548 224.184 + endloop + endfacet + facet normal -0.895202 -0.431995 -0.109512 + outer loop + vertex -674.391 164.548 224.184 + vertex -675.995 168.33 222.374 + vertex -674.326 164.892 222.296 + endloop + endfacet + facet normal -0.895518 -0.432229 -0.10595 + outer loop + vertex -675.995 168.33 222.374 + vertex -675.938 168.678 220.472 + vertex -674.326 164.892 222.296 + endloop + endfacet + facet normal -0.89591 -0.431746 -0.1046 + outer loop + vertex -674.326 164.892 222.296 + vertex -675.938 168.678 220.472 + vertex -674.273 165.243 220.391 + endloop + endfacet + facet normal -0.896132 -0.431915 -0.101967 + outer loop + vertex -675.938 168.678 220.472 + vertex -675.89 169.038 218.523 + vertex -674.273 165.243 220.391 + endloop + endfacet + facet normal -0.896801 -0.431064 -0.0996602 + outer loop + vertex -674.273 165.243 220.391 + vertex -675.89 169.038 218.523 + vertex -674.219 165.581 218.447 + endloop + endfacet + facet normal -0.897001 -0.431216 -0.0971656 + outer loop + vertex -675.89 169.038 218.523 + vertex -675.838 169.384 216.519 + vertex -674.219 165.581 218.447 + endloop + endfacet + facet normal -0.89736 -0.430745 -0.0959367 + outer loop + vertex -674.219 165.581 218.447 + vertex -675.838 169.384 216.519 + vertex -674.174 165.933 216.443 + endloop + endfacet + facet normal -0.89775 -0.431045 -0.090805 + outer loop + vertex -675.838 169.384 216.519 + vertex -675.789 169.71 214.477 + vertex -674.174 165.933 216.443 + endloop + endfacet + facet normal -0.897785 -0.430997 -0.0906827 + outer loop + vertex -674.174 165.933 216.443 + vertex -675.789 169.71 214.477 + vertex -674.13 166.27 214.401 + endloop + endfacet + facet normal -0.897981 -0.431151 -0.0879702 + outer loop + vertex -675.789 169.71 214.477 + vertex -675.745 170.035 212.441 + vertex -674.13 166.27 214.401 + endloop + endfacet + facet normal -0.898506 -0.430425 -0.0861439 + outer loop + vertex -674.13 166.27 214.401 + vertex -675.745 170.035 212.441 + vertex -674.087 166.588 212.368 + endloop + endfacet + facet normal -0.898777 -0.43064 -0.0821519 + outer loop + vertex -675.745 170.035 212.441 + vertex -675.701 170.32 210.459 + vertex -674.087 166.588 212.368 + endloop + endfacet + facet normal -0.898849 -0.430538 -0.0818932 + outer loop + vertex -674.087 166.588 212.368 + vertex -675.701 170.32 210.459 + vertex -674.047 166.881 210.387 + endloop + endfacet + facet normal -0.898978 -0.430641 -0.0799193 + outer loop + vertex -675.701 170.32 210.459 + vertex -675.661 170.59 208.553 + vertex -674.047 166.881 210.387 + endloop + endfacet + facet normal -0.899514 -0.429887 -0.0779212 + outer loop + vertex -674.047 166.881 210.387 + vertex -675.661 170.59 208.553 + vertex -674.005 167.141 208.472 + endloop + endfacet + facet normal -0.899634 -0.429991 -0.0759402 + outer loop + vertex -675.661 170.59 208.553 + vertex -675.628 170.851 206.696 + vertex -674.005 167.141 208.472 + endloop + endfacet + facet normal -0.900132 -0.429285 -0.0740106 + outer loop + vertex -674.005 167.141 208.472 + vertex -675.628 170.851 206.696 + vertex -673.974 167.399 206.597 + endloop + endfacet + facet normal -0.900432 -0.429592 -0.0683607 + outer loop + vertex -675.628 170.851 206.696 + vertex -675.594 171.072 204.848 + vertex -673.974 167.399 206.597 + endloop + endfacet + facet normal -0.900001 -0.430218 -0.0700756 + outer loop + vertex -673.974 167.399 206.597 + vertex -675.594 171.072 204.848 + vertex -673.945 167.645 204.719 + endloop + endfacet + facet normal -0.900155 -0.430415 -0.0668063 + outer loop + vertex -675.594 171.072 204.848 + vertex -675.57 171.315 202.966 + vertex -673.945 167.645 204.719 + endloop + endfacet + facet normal -0.900712 -0.429591 -0.0645642 + outer loop + vertex -673.945 167.645 204.719 + vertex -675.57 171.315 202.966 + vertex -673.925 167.89 202.809 + endloop + endfacet + facet normal -0.900834 -0.429793 -0.0614469 + outer loop + vertex -675.57 171.315 202.966 + vertex -675.548 171.545 201.034 + vertex -673.925 167.89 202.809 + endloop + endfacet + facet normal -0.901143 -0.429322 -0.0601935 + outer loop + vertex -673.925 167.89 202.809 + vertex -675.548 171.545 201.034 + vertex -673.9 168.112 200.845 + endloop + endfacet + facet normal -0.901221 -0.429493 -0.057758 + outer loop + vertex -675.548 171.545 201.034 + vertex -675.51 171.734 199.029 + vertex -673.9 168.112 200.845 + endloop + endfacet + facet normal -0.901133 -0.429631 -0.0581121 + outer loop + vertex -673.9 168.112 200.845 + vertex -675.51 171.734 199.029 + vertex -673.843 168.269 198.803 + endloop + endfacet + facet normal -0.901242 -0.429964 -0.0537967 + outer loop + vertex -675.51 171.734 199.029 + vertex -675.446 171.868 196.897 + vertex -673.843 168.269 198.803 + endloop + endfacet + facet normal -0.899721 -0.432373 -0.0596232 + outer loop + vertex -673.843 168.269 198.803 + vertex -675.446 171.868 196.897 + vertex -673.743 168.36 196.64 + endloop + endfacet + facet normal -0.899775 -0.432561 -0.0574083 + outer loop + vertex -675.446 171.868 196.897 + vertex -675.415 172.122 194.489 + vertex -673.743 168.36 196.64 + endloop + endfacet + facet normal -0.898386 -0.434761 -0.0623354 + outer loop + vertex -673.743 168.36 196.64 + vertex -675.415 172.122 194.489 + vertex -673.599 168.42 194.147 + endloop + endfacet + facet normal -0.898449 -0.435108 -0.0589136 + outer loop + vertex -675.415 172.122 194.489 + vertex -675.619 172.969 191.352 + vertex -673.599 168.42 194.147 + endloop + endfacet + facet normal -0.899329 -0.433678 -0.0559503 + outer loop + vertex -675.619 172.969 191.352 + vertex -673.252 168.122 190.865 + vertex -673.599 168.42 194.147 + endloop + endfacet + facet normal -0.880927 -0.470532 -0.0506627 + outer loop + vertex -672.237 165.838 194.442 + vertex -673.599 168.42 194.147 + vertex -673.252 168.122 190.865 + endloop + endfacet + facet normal -0.880284 -0.471637 -0.0515509 + outer loop + vertex -672.237 165.838 194.442 + vertex -673.252 168.122 190.865 + vertex -671.844 165.341 192.268 + endloop + endfacet + facet normal -0.866577 -0.497167 -0.0432317 + outer loop + vertex -671.844 165.341 192.268 + vertex -671.643 164.715 195.433 + vertex -672.237 165.838 194.442 + endloop + endfacet + facet normal -0.859737 -0.507334 -0.0588581 + outer loop + vertex -671.792 164.817 196.736 + vertex -672.237 165.838 194.442 + vertex -671.643 164.715 195.433 + endloop + endfacet + facet normal -0.847613 -0.527665 -0.0558727 + outer loop + vertex -671.643 164.715 195.433 + vertex -671.583 164.389 197.609 + vertex -671.792 164.817 196.736 + endloop + endfacet + facet normal -0.840033 -0.538844 -0.0631816 + outer loop + vertex -671.954 164.788 199.136 + vertex -671.792 164.817 196.736 + vertex -671.583 164.389 197.609 + endloop + endfacet + facet normal -0.841966 -0.535663 -0.0644828 + outer loop + vertex -671.583 164.389 197.609 + vertex -671.648 164.126 200.645 + vertex -671.954 164.788 199.136 + endloop + endfacet + facet normal -0.83685 -0.543094 -0.0687799 + outer loop + vertex -672.075 164.527 202.676 + vertex -671.954 164.788 199.136 + vertex -671.648 164.126 200.645 + endloop + endfacet + facet normal -0.836752 -0.543252 -0.068728 + outer loop + vertex -671.648 164.126 200.645 + vertex -671.752 163.842 204.157 + vertex -672.075 164.527 202.676 + endloop + endfacet + facet normal -0.822763 -0.562621 -0.080738 + outer loop + vertex -672.098 164.002 206.571 + vertex -672.075 164.527 202.676 + vertex -671.752 163.842 204.157 + endloop + endfacet + facet normal -0.817256 -0.570777 -0.0794081 + outer loop + vertex -671.752 163.842 204.157 + vertex -671.766 163.596 206.061 + vertex -672.098 164.002 206.571 + endloop + endfacet + facet normal -0.823433 -0.559893 -0.0920802 + outer loop + vertex -671.766 163.596 206.061 + vertex -671.839 163.259 208.77 + vertex -672.098 164.002 206.571 + endloop + endfacet + facet normal -0.82252 -0.561146 -0.0926111 + outer loop + vertex -672.214 163.509 210.584 + vertex -672.098 164.002 206.571 + vertex -671.839 163.259 208.77 + endloop + endfacet + facet normal -0.826398 -0.555144 -0.0942394 + outer loop + vertex -671.839 163.259 208.77 + vertex -671.929 162.797 212.274 + vertex -672.214 163.509 210.584 + endloop + endfacet + facet normal -0.813269 -0.572558 -0.103782 + outer loop + vertex -672.253 162.837 214.595 + vertex -672.214 163.509 210.584 + vertex -671.929 162.797 212.274 + endloop + endfacet + facet normal -0.811955 -0.574459 -0.103566 + outer loop + vertex -671.929 162.797 212.274 + vertex -671.94 162.472 214.168 + vertex -672.253 162.837 214.595 + endloop + endfacet + facet normal -0.816927 -0.565114 -0.115223 + outer loop + vertex -671.94 162.472 214.168 + vertex -672.009 162.038 216.785 + vertex -672.253 162.837 214.595 + endloop + endfacet + facet normal -0.819705 -0.561415 -0.113564 + outer loop + vertex -672.397 162.235 218.609 + vertex -672.253 162.837 214.595 + vertex -672.009 162.038 216.785 + endloop + endfacet + facet normal -0.827905 -0.548595 -0.116692 + outer loop + vertex -672.009 162.038 216.785 + vertex -672.12 161.417 220.492 + vertex -672.397 162.235 218.609 + endloop + endfacet + facet normal -0.819293 -0.560042 -0.122933 + outer loop + vertex -672.495 161.543 222.414 + vertex -672.397 162.235 218.609 + vertex -672.12 161.417 220.492 + endloop + endfacet + facet normal -0.826654 -0.548624 -0.125116 + outer loop + vertex -672.12 161.417 220.492 + vertex -672.195 160.737 223.967 + vertex -672.495 161.543 222.414 + endloop + endfacet + facet normal -0.816536 -0.561577 -0.133792 + outer loop + vertex -672.562 160.698 226.375 + vertex -672.495 161.543 222.414 + vertex -672.195 160.737 223.967 + endloop + endfacet + facet normal -0.812111 -0.568091 -0.133222 + outer loop + vertex -672.195 160.737 223.967 + vertex -672.262 160.184 226.738 + vertex -672.562 160.698 226.375 + endloop + endfacet + facet normal -0.803374 -0.575885 -0.151479 + outer loop + vertex -672.262 160.184 226.738 + vertex -672.36 159.817 228.653 + vertex -672.562 160.698 226.375 + endloop + endfacet + facet normal -0.808227 -0.56979 -0.148691 + outer loop + vertex -672.753 159.985 230.146 + vertex -672.562 160.698 226.375 + vertex -672.36 159.817 228.653 + endloop + endfacet + facet normal -0.819875 -0.551494 -0.153814 + outer loop + vertex -672.36 159.817 228.653 + vertex -672.482 159.1 231.871 + vertex -672.753 159.985 230.146 + endloop + endfacet + facet normal -0.814323 -0.558424 -0.158242 + outer loop + vertex -672.909 159.173 233.814 + vertex -672.753 159.985 230.146 + vertex -672.482 159.1 231.871 + endloop + endfacet + facet normal -0.816656 -0.554822 -0.15889 + outer loop + vertex -672.482 159.1 231.871 + vertex -672.656 158.383 235.27 + vertex -672.909 159.173 233.814 + endloop + endfacet + facet normal -0.800109 -0.574529 -0.172458 + outer loop + vertex -673.061 158.271 237.524 + vertex -672.909 159.173 233.814 + vertex -672.656 158.383 235.27 + endloop + endfacet + facet normal -0.796236 -0.580011 -0.172035 + outer loop + vertex -672.656 158.383 235.27 + vertex -672.725 157.946 237.063 + vertex -673.061 158.271 237.524 + endloop + endfacet + facet normal -0.804123 -0.563466 -0.189453 + outer loop + vertex -672.725 157.946 237.063 + vertex -672.902 157.36 239.557 + vertex -673.061 158.271 237.524 + endloop + endfacet + facet normal -0.80709 -0.559834 -0.187593 + outer loop + vertex -673.351 157.441 241.246 + vertex -673.061 158.271 237.524 + vertex -672.902 157.36 239.557 + endloop + endfacet + facet normal -0.820094 -0.539039 -0.192049 + outer loop + vertex -672.902 157.36 239.557 + vertex -673.169 156.48 243.165 + vertex -673.351 157.441 241.246 + endloop + endfacet + facet normal -0.803451 -0.559397 -0.203816 + outer loop + vertex -673.636 156.505 244.938 + vertex -673.351 157.441 241.246 + vertex -673.169 156.48 243.165 + endloop + endfacet + facet normal -0.821718 -0.530179 -0.209022 + outer loop + vertex -673.169 156.48 243.165 + vertex -673.471 155.499 246.843 + vertex -673.636 156.505 244.938 + endloop + endfacet + facet normal -0.80781 -0.547169 -0.219202 + outer loop + vertex -673.98 155.453 248.834 + vertex -673.636 156.505 244.938 + vertex -673.471 155.499 246.843 + endloop + endfacet + facet normal -0.870235 -0.453462 -0.19252 + outer loop + vertex -673.471 155.499 246.843 + vertex -673.169 156.48 243.165 + vertex -672.899 156.43 242.063 + endloop + endfacet + facet normal -0.846092 -0.500094 -0.184482 + outer loop + vertex -673.169 156.48 243.165 + vertex -672.902 157.36 239.557 + vertex -672.899 156.43 242.063 + endloop + endfacet + facet normal -0.844479 -0.505044 -0.178286 + outer loop + vertex -673.061 158.271 237.524 + vertex -673.351 157.441 241.246 + vertex -673.846 159.066 238.988 + endloop + endfacet + facet normal -0.842247 -0.510128 -0.174327 + outer loop + vertex -673.858 159.726 237.116 + vertex -673.061 158.271 237.524 + vertex -673.846 159.066 238.988 + endloop + endfacet + facet normal -0.869273 -0.467965 -0.159288 + outer loop + vertex -673.846 159.066 238.988 + vertex -674.964 161.681 237.408 + vertex -673.858 159.726 237.116 + endloop + endfacet + facet normal -0.869331 -0.468107 -0.158554 + outer loop + vertex -674.964 161.681 237.408 + vertex -674.86 162.095 235.617 + vertex -673.858 159.726 237.116 + endloop + endfacet + facet normal -0.868634 -0.468845 -0.160186 + outer loop + vertex -673.858 159.726 237.116 + vertex -674.86 162.095 235.617 + vertex -673.634 159.908 235.368 + endloop + endfacet + facet normal -0.869471 -0.470367 -0.150915 + outer loop + vertex -674.86 162.095 235.617 + vertex -674.757 162.493 233.778 + vertex -673.634 159.908 235.368 + endloop + endfacet + facet normal -0.872672 -0.466896 -0.143012 + outer loop + vertex -673.634 159.908 235.368 + vertex -674.757 162.493 233.778 + vertex -673.661 160.551 233.434 + endloop + endfacet + facet normal -0.848297 -0.505919 -0.156325 + outer loop + vertex -673.661 160.551 233.434 + vertex -672.909 159.173 233.814 + vertex -673.634 159.908 235.368 + endloop + endfacet + facet normal -0.850305 -0.50488 -0.148588 + outer loop + vertex -673.661 160.551 233.434 + vertex -673.45 160.73 231.618 + vertex -672.909 159.173 233.814 + endloop + endfacet + facet normal -0.851013 -0.503934 -0.147743 + outer loop + vertex -672.753 159.985 230.146 + vertex -672.909 159.173 233.814 + vertex -673.45 160.73 231.618 + endloop + endfacet + facet normal -0.850073 -0.505942 -0.146282 + outer loop + vertex -673.492 161.378 229.622 + vertex -672.753 159.985 230.146 + vertex -673.45 160.73 231.618 + endloop + endfacet + facet normal -0.875084 -0.465452 -0.132594 + outer loop + vertex -673.45 160.73 231.618 + vertex -674.588 163.345 229.948 + vertex -673.492 161.378 229.622 + endloop + endfacet + facet normal -0.875119 -0.465591 -0.131876 + outer loop + vertex -674.588 163.345 229.948 + vertex -674.51 163.746 228.013 + vertex -673.492 161.378 229.622 + endloop + endfacet + facet normal -0.873035 -0.468066 -0.136836 + outer loop + vertex -673.492 161.378 229.622 + vertex -674.51 163.746 228.013 + vertex -673.299 161.552 227.789 + endloop + endfacet + facet normal -0.873664 -0.469269 -0.128444 + outer loop + vertex -674.51 163.746 228.013 + vertex -674.451 164.163 226.086 + vertex -673.299 161.552 227.789 + endloop + endfacet + facet normal -0.876458 -0.465918 -0.121418 + outer loop + vertex -673.299 161.552 227.789 + vertex -674.451 164.163 226.086 + vertex -673.356 162.183 225.783 + endloop + endfacet + facet normal -0.850371 -0.508434 -0.135513 + outer loop + vertex -673.356 162.183 225.783 + vertex -672.562 160.698 226.375 + vertex -673.299 161.552 227.789 + endloop + endfacet + facet normal -0.853373 -0.505997 -0.125384 + outer loop + vertex -673.356 162.183 225.783 + vertex -673.177 162.332 223.959 + vertex -672.562 160.698 226.375 + endloop + endfacet + facet normal -0.87536 -0.467204 -0.124359 + outer loop + vertex -673.356 162.183 225.783 + vertex -674.391 164.548 224.184 + vertex -673.177 162.332 223.959 + endloop + endfacet + facet normal -0.875928 -0.468416 -0.115489 + outer loop + vertex -674.391 164.548 224.184 + vertex -674.326 164.892 222.296 + vertex -673.177 162.332 223.959 + endloop + endfacet + facet normal -0.878873 -0.464724 -0.107771 + outer loop + vertex -673.177 162.332 223.959 + vertex -674.326 164.892 222.296 + vertex -673.23 162.893 221.973 + endloop + endfacet + facet normal -0.855066 -0.504526 -0.119653 + outer loop + vertex -673.23 162.893 221.973 + vertex -672.495 161.543 222.414 + vertex -673.177 162.332 223.959 + endloop + endfacet + facet normal -0.856406 -0.503498 -0.114276 + outer loop + vertex -673.23 162.893 221.973 + vertex -673.059 163.017 220.148 + vertex -672.495 161.543 222.414 + endloop + endfacet + facet normal -0.877391 -0.466106 -0.113714 + outer loop + vertex -673.23 162.893 221.973 + vertex -674.273 165.243 220.391 + vertex -673.059 163.017 220.148 + endloop + endfacet + facet normal -0.877818 -0.467243 -0.105444 + outer loop + vertex -674.273 165.243 220.391 + vertex -674.219 165.581 218.447 + vertex -673.059 163.017 220.148 + endloop + endfacet + facet normal -0.879764 -0.46471 -0.100297 + outer loop + vertex -673.059 163.017 220.148 + vertex -674.219 165.581 218.447 + vertex -673.138 163.606 218.116 + endloop + endfacet + facet normal -0.856494 -0.50374 -0.112535 + outer loop + vertex -673.138 163.606 218.116 + vertex -672.397 162.235 218.609 + vertex -673.059 163.017 220.148 + endloop + endfacet + facet normal -0.858618 -0.501905 -0.104241 + outer loop + vertex -673.138 163.606 218.116 + vertex -672.962 163.703 216.198 + vertex -672.397 162.235 218.609 + endloop + endfacet + facet normal -0.878605 -0.466025 -0.104277 + outer loop + vertex -673.138 163.606 218.116 + vertex -674.174 165.933 216.443 + vertex -672.962 163.703 216.198 + endloop + endfacet + facet normal -0.878952 -0.467098 -0.0962416 + outer loop + vertex -674.174 165.933 216.443 + vertex -674.13 166.27 214.401 + vertex -672.962 163.703 216.198 + endloop + endfacet + facet normal -0.881017 -0.464276 -0.0908671 + outer loop + vertex -672.962 163.703 216.198 + vertex -674.13 166.27 214.401 + vertex -673.044 164.275 214.068 + endloop + endfacet + facet normal -0.85495 -0.508242 -0.103684 + outer loop + vertex -673.044 164.275 214.068 + vertex -672.253 162.837 214.595 + vertex -672.962 163.703 216.198 + endloop + endfacet + facet normal -0.857289 -0.506115 -0.0943574 + outer loop + vertex -673.044 164.275 214.068 + vertex -672.886 164.367 212.137 + vertex -672.253 162.837 214.595 + endloop + endfacet + facet normal -0.879731 -0.46603 -0.0942841 + outer loop + vertex -673.044 164.275 214.068 + vertex -674.087 166.588 212.368 + vertex -672.886 164.367 212.137 + endloop + endfacet + facet normal -0.880005 -0.466949 -0.086887 + outer loop + vertex -674.087 166.588 212.368 + vertex -674.047 166.881 210.387 + vertex -672.886 164.367 212.137 + endloop + endfacet + facet normal -0.88263 -0.463242 -0.0798179 + outer loop + vertex -672.886 164.367 212.137 + vertex -674.047 166.881 210.387 + vertex -672.959 164.862 210.07 + endloop + endfacet + facet normal -0.857506 -0.506356 -0.0910356 + outer loop + vertex -672.959 164.862 210.07 + vertex -672.214 163.509 210.584 + vertex -672.886 164.367 212.137 + endloop + endfacet + facet normal -0.85843 -0.505448 -0.0872999 + outer loop + vertex -672.959 164.862 210.07 + vertex -672.809 164.929 208.208 + vertex -672.214 163.509 210.584 + endloop + endfacet + facet normal -0.880508 -0.465856 -0.087657 + outer loop + vertex -672.959 164.862 210.07 + vertex -674.005 167.141 208.472 + vertex -672.809 164.929 208.208 + endloop + endfacet + facet normal -0.880722 -0.46702 -0.0788777 + outer loop + vertex -674.005 167.141 208.472 + vertex -673.974 167.399 206.597 + vertex -672.809 164.929 208.208 + endloop + endfacet + facet normal -0.882855 -0.463987 -0.0726855 + outer loop + vertex -672.809 164.929 208.208 + vertex -673.974 167.399 206.597 + vertex -672.887 165.389 206.222 + endloop + endfacet + facet normal -0.857127 -0.508218 -0.0839441 + outer loop + vertex -672.887 165.389 206.222 + vertex -672.098 164.002 206.571 + vertex -672.809 164.929 208.208 + endloop + endfacet + facet normal -0.858493 -0.5071 -0.0764119 + outer loop + vertex -672.887 165.389 206.222 + vertex -672.747 165.433 204.362 + vertex -672.098 164.002 206.571 + endloop + endfacet + facet normal -0.881827 -0.465215 -0.077181 + outer loop + vertex -672.887 165.389 206.222 + vertex -673.945 167.645 204.719 + vertex -672.747 165.433 204.362 + endloop + endfacet + facet normal -0.881811 -0.46651 -0.0691192 + outer loop + vertex -673.945 167.645 204.719 + vertex -673.925 167.89 202.809 + vertex -672.747 165.433 204.362 + endloop + endfacet + facet normal -0.884173 -0.463047 -0.0618456 + outer loop + vertex -672.747 165.433 204.362 + vertex -673.925 167.89 202.809 + vertex -672.85 165.897 202.359 + endloop + endfacet + facet normal -0.860902 -0.503586 -0.0724426 + outer loop + vertex -672.85 165.897 202.359 + vertex -672.075 164.527 202.676 + vertex -672.747 165.433 204.362 + endloop + endfacet + facet normal -0.862073 -0.502573 -0.0651941 + outer loop + vertex -672.85 165.897 202.359 + vertex -672.676 165.842 200.486 + vertex -672.075 164.527 202.676 + endloop + endfacet + facet normal -0.882692 -0.464975 -0.0682088 + outer loop + vertex -672.85 165.897 202.359 + vertex -673.9 168.112 200.845 + vertex -672.676 165.842 200.486 + endloop + endfacet + facet normal -0.882627 -0.466177 -0.0603988 + outer loop + vertex -673.9 168.112 200.845 + vertex -673.843 168.269 198.803 + vertex -672.676 165.842 200.486 + endloop + endfacet + facet normal -0.883532 -0.464793 -0.0577755 + outer loop + vertex -672.676 165.842 200.486 + vertex -673.843 168.269 198.803 + vertex -672.725 166.19 198.426 + endloop + endfacet + facet normal -0.86006 -0.505998 -0.0652871 + outer loop + vertex -672.725 166.19 198.426 + vertex -671.954 164.788 199.136 + vertex -672.676 165.842 200.486 + endloop + endfacet + facet normal -0.860531 -0.50541 -0.0636142 + outer loop + vertex -672.725 166.19 198.426 + vertex -672.465 165.971 196.656 + vertex -671.954 164.788 199.136 + endloop + endfacet + facet normal -0.879332 -0.470943 -0.0706239 + outer loop + vertex -672.725 166.19 198.426 + vertex -673.743 168.36 196.64 + vertex -672.465 165.971 196.656 + endloop + endfacet + facet normal -0.879852 -0.471167 -0.062143 + outer loop + vertex -673.743 168.36 196.64 + vertex -673.599 168.42 194.147 + vertex -672.465 165.971 196.656 + endloop + endfacet + facet normal -0.883587 -0.464379 -0.0602242 + outer loop + vertex -673.843 168.269 198.803 + vertex -673.743 168.36 196.64 + vertex -672.725 166.19 198.426 + endloop + endfacet + facet normal -0.884243 -0.462657 -0.0637412 + outer loop + vertex -673.925 167.89 202.809 + vertex -673.9 168.112 200.845 + vertex -672.85 165.897 202.359 + endloop + endfacet + facet normal -0.882872 -0.463715 -0.0741934 + outer loop + vertex -673.974 167.399 206.597 + vertex -673.945 167.645 204.719 + vertex -672.887 165.389 206.222 + endloop + endfacet + facet normal -0.882614 -0.462884 -0.0820399 + outer loop + vertex -674.047 166.881 210.387 + vertex -674.005 167.141 208.472 + vertex -672.959 164.862 210.07 + endloop + endfacet + facet normal -0.881015 -0.464242 -0.0910628 + outer loop + vertex -674.13 166.27 214.401 + vertex -674.087 166.588 212.368 + vertex -673.044 164.275 214.068 + endloop + endfacet + facet normal -0.879741 -0.464503 -0.101457 + outer loop + vertex -674.219 165.581 218.447 + vertex -674.174 165.933 216.443 + vertex -673.138 163.606 218.116 + endloop + endfacet + facet normal -0.878803 -0.464307 -0.110112 + outer loop + vertex -674.326 164.892 222.296 + vertex -674.273 165.243 220.391 + vertex -673.23 162.893 221.973 + endloop + endfacet + facet normal -0.876446 -0.465871 -0.121684 + outer loop + vertex -674.451 164.163 226.086 + vertex -674.391 164.548 224.184 + vertex -673.356 162.183 225.783 + endloop + endfacet + facet normal -0.872149 -0.46882 -0.139872 + outer loop + vertex -674.666 162.913 231.882 + vertex -674.588 163.345 229.948 + vertex -673.45 160.73 231.618 + endloop + endfacet + facet normal -0.852502 -0.504152 -0.138095 + outer loop + vertex -673.492 161.378 229.622 + vertex -673.299 161.552 227.789 + vertex -672.753 159.985 230.146 + endloop + endfacet + facet normal -0.871573 -0.46759 -0.14738 + outer loop + vertex -673.661 160.551 233.434 + vertex -674.666 162.913 231.882 + vertex -673.45 160.73 231.618 + endloop + endfacet + facet normal -0.872562 -0.466475 -0.145042 + outer loop + vertex -674.757 162.493 233.778 + vertex -674.666 162.913 231.882 + vertex -673.661 160.551 233.434 + endloop + endfacet + facet normal -0.866185 -0.471108 -0.166674 + outer loop + vertex -675.071 161.252 239.175 + vertex -674.964 161.681 237.408 + vertex -673.846 159.066 238.988 + endloop + endfacet + facet normal -0.865024 -0.469601 -0.176662 + outer loop + vertex -674.079 158.853 240.697 + vertex -675.071 161.252 239.175 + vertex -673.846 159.066 238.988 + endloop + endfacet + facet normal -0.866622 -0.467986 -0.173076 + outer loop + vertex -675.188 160.81 240.958 + vertex -675.071 161.252 239.175 + vertex -674.079 158.853 240.697 + endloop + endfacet + facet normal -0.866555 -0.467857 -0.17376 + outer loop + vertex -674.084 158.154 242.604 + vertex -675.188 160.81 240.958 + vertex -674.079 158.853 240.697 + endloop + endfacet + facet normal -0.841105 -0.507116 -0.188086 + outer loop + vertex -674.079 158.853 240.697 + vertex -673.351 157.441 241.246 + vertex -674.084 158.154 242.604 + endloop + endfacet + facet normal -0.84346 -0.501614 -0.192246 + outer loop + vertex -673.351 157.441 241.246 + vertex -673.636 156.505 244.938 + vertex -674.084 158.154 242.604 + endloop + endfacet + facet normal -0.843789 -0.501198 -0.191889 + outer loop + vertex -674.352 157.93 244.365 + vertex -674.084 158.154 242.604 + vertex -673.636 156.505 244.938 + endloop + endfacet + facet normal -0.839533 -0.503744 -0.203532 + outer loop + vertex -674.352 157.93 244.365 + vertex -673.636 156.505 244.938 + vertex -674.399 157.195 246.377 + endloop + endfacet + facet normal -0.863386 -0.467116 -0.1907 + outer loop + vertex -674.399 157.195 246.377 + vertex -675.481 159.897 244.66 + vertex -674.352 157.93 244.365 + endloop + endfacet + facet normal -0.863659 -0.467661 -0.188114 + outer loop + vertex -675.481 159.897 244.66 + vertex -675.327 160.368 242.782 + vertex -674.352 157.93 244.365 + endloop + endfacet + facet normal -0.859731 -0.4706 -0.198491 + outer loop + vertex -675.648 159.39 246.583 + vertex -675.481 159.897 244.66 + vertex -674.399 157.195 246.377 + endloop + endfacet + facet normal -0.858215 -0.468735 -0.209175 + outer loop + vertex -674.695 156.909 248.233 + vertex -675.648 159.39 246.583 + vertex -674.399 157.195 246.377 + endloop + endfacet + facet normal -0.840258 -0.499425 -0.211048 + outer loop + vertex -674.695 156.909 248.233 + vertex -674.399 157.195 246.377 + vertex -673.98 155.453 248.834 + endloop + endfacet + facet normal -0.835497 -0.502115 -0.223218 + outer loop + vertex -674.695 156.909 248.233 + vertex -673.98 155.453 248.834 + vertex -674.777 156.122 250.313 + endloop + endfacet + facet normal -0.858042 -0.468122 -0.211247 + outer loop + vertex -674.777 156.122 250.313 + vertex -675.831 158.859 248.529 + vertex -674.695 156.909 248.233 + endloop + endfacet + facet normal -0.855229 -0.470696 -0.216861 + outer loop + vertex -676.045 158.348 250.479 + vertex -675.831 158.859 248.529 + vertex -674.777 156.122 250.313 + endloop + endfacet + facet normal -0.853525 -0.468962 -0.227091 + outer loop + vertex -675.138 155.879 252.169 + vertex -676.045 158.348 250.479 + vertex -674.777 156.122 250.313 + endloop + endfacet + facet normal -0.837602 -0.496606 -0.227609 + outer loop + vertex -675.138 155.879 252.169 + vertex -674.777 156.122 250.313 + vertex -674.46 154.439 252.816 + endloop + endfacet + facet normal -0.832678 -0.499463 -0.239131 + outer loop + vertex -675.138 155.879 252.169 + vertex -674.46 154.439 252.816 + vertex -675.286 155.174 254.16 + endloop + endfacet + facet normal -0.854093 -0.466901 -0.229192 + outer loop + vertex -675.286 155.174 254.16 + vertex -676.302 157.881 252.429 + vertex -675.138 155.879 252.169 + endloop + endfacet + facet normal -0.849698 -0.470669 -0.237664 + outer loop + vertex -676.589 157.394 254.419 + vertex -676.302 157.881 252.429 + vertex -675.286 155.174 254.16 + endloop + endfacet + facet normal -0.847995 -0.468483 -0.247845 + outer loop + vertex -675.68 154.934 255.96 + vertex -676.589 157.394 254.419 + vertex -675.286 155.174 254.16 + endloop + endfacet + facet normal -0.831235 -0.497514 -0.248049 + outer loop + vertex -675.68 154.934 255.96 + vertex -675.286 155.174 254.16 + vertex -675.018 153.695 256.225 + endloop + endfacet + facet normal -0.827124 -0.497986 -0.260528 + outer loop + vertex -675.68 154.934 255.96 + vertex -675.018 153.695 256.225 + vertex -675.832 154.192 257.861 + endloop + endfacet + facet normal -0.841293 -0.477391 -0.25362 + outer loop + vertex -675.832 154.192 257.861 + vertex -676.751 156.584 256.407 + vertex -675.68 154.934 255.96 + endloop + endfacet + facet normal -0.829844 -0.485752 -0.274599 + outer loop + vertex -676.944 155.875 258.244 + vertex -676.751 156.584 256.407 + vertex -675.832 154.192 257.861 + endloop + endfacet + facet normal -0.830654 -0.487605 -0.268802 + outer loop + vertex -676.258 153.943 259.629 + vertex -676.944 155.875 258.244 + vertex -675.832 154.192 257.861 + endloop + endfacet + facet normal -0.822394 -0.501436 -0.268758 + outer loop + vertex -676.258 153.943 259.629 + vertex -675.832 154.192 257.861 + vertex -675.542 152.743 259.677 + endloop + endfacet + facet normal -0.81945 -0.50013 -0.279948 + outer loop + vertex -676.258 153.943 259.629 + vertex -675.542 152.743 259.677 + vertex -676.514 153.276 261.569 + endloop + endfacet + facet normal -0.829096 -0.486024 -0.276371 + outer loop + vertex -676.514 153.276 261.569 + vertex -677.303 155.511 260.005 + vertex -676.258 153.943 259.629 + endloop + endfacet + facet normal -0.825077 -0.489131 -0.28284 + outer loop + vertex -677.666 155.075 261.819 + vertex -677.303 155.511 260.005 + vertex -676.514 153.276 261.569 + endloop + endfacet + facet normal -0.822811 -0.486061 -0.294495 + outer loop + vertex -676.987 152.972 263.393 + vertex -677.666 155.075 261.819 + vertex -676.514 153.276 261.569 + endloop + endfacet + facet normal -0.818996 -0.49242 -0.294565 + outer loop + vertex -676.987 152.972 263.393 + vertex -676.514 153.276 261.569 + vertex -676.361 151.614 263.921 + endloop + endfacet + facet normal -0.810974 -0.49529 -0.311461 + outer loop + vertex -676.987 152.972 263.393 + vertex -676.361 151.614 263.921 + vertex -677.261 152.187 265.355 + endloop + endfacet + facet normal -0.817831 -0.48572 -0.308591 + outer loop + vertex -677.261 152.187 265.355 + vertex -678.021 154.556 263.64 + vertex -676.987 152.972 263.393 + endloop + endfacet + facet normal -0.813414 -0.48898 -0.31505 + outer loop + vertex -678.391 154.013 265.438 + vertex -678.021 154.556 263.64 + vertex -677.261 152.187 265.355 + endloop + endfacet + facet normal -0.810505 -0.486684 -0.325916 + outer loop + vertex -677.765 151.884 267.061 + vertex -678.391 154.013 265.438 + vertex -677.261 152.187 265.355 + endloop + endfacet + facet normal -0.807044 -0.492403 -0.325913 + outer loop + vertex -677.765 151.884 267.061 + vertex -677.261 152.187 265.355 + vertex -677.247 150.429 267.975 + endloop + endfacet + facet normal -0.797508 -0.498109 -0.340396 + outer loop + vertex -677.765 151.884 267.061 + vertex -677.247 150.429 267.975 + vertex -678.097 151.157 268.903 + endloop + endfacet + facet normal -0.806963 -0.485052 -0.336951 + outer loop + vertex -678.097 151.157 268.903 + vertex -678.806 153.506 267.22 + vertex -677.765 151.884 267.061 + endloop + endfacet + facet normal -0.803582 -0.487385 -0.34163 + outer loop + vertex -679.263 153.007 269.006 + vertex -678.806 153.506 267.22 + vertex -678.097 151.157 268.903 + endloop + endfacet + facet normal -0.799848 -0.484317 -0.354515 + outer loop + vertex -678.672 150.919 270.526 + vertex -679.263 153.007 269.006 + vertex -678.097 151.157 268.903 + endloop + endfacet + facet normal -0.793251 -0.495542 -0.353824 + outer loop + vertex -678.672 150.919 270.526 + vertex -678.097 151.157 268.903 + vertex -678.113 149.612 271.102 + endloop + endfacet + facet normal -0.784299 -0.498519 -0.36926 + outer loop + vertex -678.672 150.919 270.526 + vertex -678.113 149.612 271.102 + vertex -679.093 150.207 272.381 + endloop + endfacet + facet normal -0.796475 -0.481663 -0.365552 + outer loop + vertex -679.093 150.207 272.381 + vertex -679.768 152.513 270.812 + vertex -678.672 150.919 270.526 + endloop + endfacet + facet normal -0.791564 -0.484706 -0.372138 + outer loop + vertex -680.327 152.019 272.645 + vertex -679.768 152.513 270.812 + vertex -679.093 150.207 272.381 + endloop + endfacet + facet normal -0.788003 -0.480399 -0.385056 + outer loop + vertex -679.768 149.919 274.121 + vertex -680.327 152.019 272.645 + vertex -679.093 150.207 272.381 + endloop + endfacet + facet normal -0.782132 -0.490393 -0.384427 + outer loop + vertex -679.768 149.919 274.121 + vertex -679.093 150.207 272.381 + vertex -679.094 148.581 274.456 + endloop + endfacet + facet normal -0.773019 -0.490335 -0.40251 + outer loop + vertex -679.768 149.919 274.121 + vertex -679.094 148.581 274.456 + vertex -680.319 149.198 276.057 + endloop + endfacet + facet normal -0.78226 -0.477321 -0.400293 + outer loop + vertex -680.319 149.198 276.057 + vertex -680.943 151.541 274.483 + vertex -679.768 149.919 274.121 + endloop + endfacet + facet normal -0.77648 -0.480634 -0.407516 + outer loop + vertex -681.604 151.05 276.322 + vertex -680.943 151.541 274.483 + vertex -680.319 149.198 276.057 + endloop + endfacet + facet normal -0.77229 -0.475804 -0.420927 + outer loop + vertex -681.125 148.92 277.851 + vertex -681.604 151.05 276.322 + vertex -680.319 149.198 276.057 + endloop + endfacet + facet normal -0.767264 -0.484636 -0.42004 + outer loop + vertex -681.125 148.92 277.851 + vertex -680.319 149.198 276.057 + vertex -680.522 147.518 278.366 + endloop + endfacet + facet normal -0.752965 -0.486826 -0.442768 + outer loop + vertex -681.125 148.92 277.851 + vertex -680.522 147.518 278.366 + vertex -681.794 148.205 279.775 + endloop + endfacet + facet normal -0.762671 -0.473093 -0.44104 + outer loop + vertex -681.794 148.205 279.775 + vertex -682.314 150.568 278.139 + vertex -681.125 148.92 277.851 + endloop + endfacet + facet normal -0.757427 -0.476002 -0.446907 + outer loop + vertex -683.068 150.088 279.927 + vertex -682.314 150.568 278.139 + vertex -681.794 148.205 279.775 + endloop + endfacet + facet normal -0.751285 -0.470567 -0.46275 + outer loop + vertex -682.69 147.939 281.499 + vertex -683.068 150.088 279.927 + vertex -681.794 148.205 279.775 + endloop + endfacet + facet normal -0.749383 -0.474033 -0.462297 + outer loop + vertex -682.69 147.939 281.499 + vertex -681.794 148.205 279.775 + vertex -682.193 146.48 282.19 + endloop + endfacet + facet normal -0.729891 -0.479278 -0.487394 + outer loop + vertex -682.69 147.939 281.499 + vertex -682.193 146.48 282.19 + vertex -683.5 147.256 283.384 + endloop + endfacet + facet normal -0.739081 -0.465914 -0.486502 + outer loop + vertex -683.5 147.256 283.384 + vertex -683.887 149.642 281.687 + vertex -682.69 147.939 281.499 + endloop + endfacet + facet normal -0.736219 -0.467469 -0.489341 + outer loop + vertex -684.752 149.19 283.42 + vertex -683.887 149.642 281.687 + vertex -683.5 147.256 283.384 + endloop + endfacet + facet normal -0.727758 -0.461659 -0.507188 + outer loop + vertex -684.489 147.027 285.011 + vertex -684.752 149.19 283.42 + vertex -683.5 147.256 283.384 + endloop + endfacet + facet normal -0.73267 -0.451998 -0.508815 + outer loop + vertex -684.489 147.027 285.011 + vertex -683.5 147.256 283.384 + vertex -684.175 145.547 285.873 + endloop + endfacet + facet normal -0.710004 -0.460923 -0.532396 + outer loop + vertex -684.489 147.027 285.011 + vertex -684.175 145.547 285.873 + vertex -685.396 146.432 286.737 + endloop + endfacet + facet normal -0.712319 -0.457353 -0.532381 + outer loop + vertex -685.396 146.432 286.737 + vertex -685.681 148.777 285.103 + vertex -684.489 147.027 285.011 + endloop + endfacet + facet normal -0.707529 -0.459763 -0.536675 + outer loop + vertex -686.679 148.403 286.738 + vertex -685.681 148.777 285.103 + vertex -685.396 146.432 286.737 + endloop + endfacet + facet normal -0.696423 -0.452524 -0.556972 + outer loop + vertex -686.501 146.315 288.212 + vertex -686.679 148.403 286.738 + vertex -685.396 146.432 286.737 + endloop + endfacet + facet normal -0.698859 -0.447022 -0.558361 + outer loop + vertex -686.501 146.315 288.212 + vertex -685.396 146.432 286.737 + vertex -686.109 145.004 288.773 + endloop + endfacet + facet normal -0.676493 -0.450652 -0.582469 + outer loop + vertex -686.501 146.315 288.212 + vertex -686.109 145.004 288.773 + vertex -687.563 145.79 289.852 + endloop + endfacet + facet normal -0.678547 -0.447242 -0.582708 + outer loop + vertex -687.563 145.79 289.852 + vertex -687.772 148.097 288.325 + vertex -686.501 146.315 288.212 + endloop + endfacet + facet normal -0.672044 -0.450144 -0.587985 + outer loop + vertex -688.948 147.86 289.85 + vertex -687.772 148.097 288.325 + vertex -687.563 145.79 289.852 + endloop + endfacet + facet normal -0.660942 -0.442739 -0.605919 + outer loop + vertex -688.843 145.785 291.252 + vertex -688.948 147.86 289.85 + vertex -687.563 145.79 289.852 + endloop + endfacet + facet normal -0.65826 -0.449991 -0.603491 + outer loop + vertex -688.843 145.785 291.252 + vertex -687.563 145.79 289.852 + vertex -688.225 144.133 291.81 + endloop + endfacet + facet normal -0.63778 -0.449696 -0.625308 + outer loop + vertex -688.843 145.785 291.252 + vertex -688.225 144.133 291.81 + vertex -689.926 145.188 292.786 + endloop + endfacet + facet normal -0.644356 -0.439349 -0.625922 + outer loop + vertex -689.926 145.188 292.786 + vertex -690.156 147.714 291.25 + vertex -688.843 145.785 291.252 + endloop + endfacet + facet normal -0.632478 -0.443717 -0.634891 + outer loop + vertex -691.326 147.686 292.435 + vertex -690.156 147.714 291.25 + vertex -689.926 145.188 292.786 + endloop + endfacet + facet normal -0.653994 -0.445899 -0.611118 + outer loop + vertex -690.156 147.714 291.25 + vertex -688.948 147.86 289.85 + vertex -688.843 145.785 291.252 + endloop + endfacet + facet normal -0.689237 -0.456125 -0.562941 + outer loop + vertex -687.772 148.097 288.325 + vertex -686.679 148.403 286.738 + vertex -686.501 146.315 288.212 + endloop + endfacet + facet normal -0.721888 -0.464911 -0.512578 + outer loop + vertex -685.681 148.777 285.103 + vertex -684.752 149.19 283.42 + vertex -684.489 147.027 285.011 + endloop + endfacet + facet normal -0.746575 -0.473274 -0.467587 + outer loop + vertex -683.887 149.642 281.687 + vertex -683.068 150.088 279.927 + vertex -682.69 147.939 281.499 + endloop + endfacet + facet normal -0.76719 -0.478846 -0.426762 + outer loop + vertex -682.314 150.568 278.139 + vertex -681.604 151.05 276.322 + vertex -681.125 148.92 277.851 + endloop + endfacet + facet normal -0.785245 -0.482111 -0.388535 + outer loop + vertex -680.943 151.541 274.483 + vertex -680.327 152.019 272.645 + vertex -679.768 149.919 274.121 + endloop + endfacet + facet normal -0.798822 -0.485014 -0.355872 + outer loop + vertex -679.768 152.513 270.812 + vertex -679.263 153.007 269.006 + vertex -678.672 150.919 270.526 + endloop + endfacet + facet normal -0.799341 -0.48896 -0.349245 + outer loop + vertex -677.247 150.429 267.975 + vertex -678.113 149.612 271.102 + vertex -678.097 151.157 268.903 + endloop + endfacet + facet normal -0.814381 -0.465036 -0.347167 + outer loop + vertex -678.113 149.612 271.102 + vertex -677.247 150.429 267.975 + vertex -677.905 148.861 271.621 + endloop + endfacet + facet normal -0.833811 -0.436252 -0.338293 + outer loop + vertex -676.657 150.152 266.879 + vertex -677.905 148.861 271.621 + vertex -677.247 150.429 267.975 + endloop + endfacet + facet normal -0.874371 -0.357954 -0.327634 + outer loop + vertex -677.905 148.861 271.621 + vertex -676.657 150.152 266.879 + vertex -677.799 148.447 271.789 + endloop + endfacet + facet normal -0.809373 -0.487529 -0.327462 + outer loop + vertex -678.806 153.506 267.22 + vertex -678.391 154.013 265.438 + vertex -677.765 151.884 267.061 + endloop + endfacet + facet normal -0.815501 -0.482681 -0.31934 + outer loop + vertex -676.361 151.614 263.921 + vertex -677.247 150.429 267.975 + vertex -677.261 152.187 265.355 + endloop + endfacet + facet normal -0.819748 -0.488464 -0.299026 + outer loop + vertex -678.021 154.556 263.64 + vertex -677.666 155.075 261.819 + vertex -676.987 152.972 263.393 + endloop + endfacet + facet normal -0.826353 -0.4839 -0.288066 + outer loop + vertex -675.542 152.743 259.677 + vertex -676.361 151.614 263.921 + vertex -676.514 153.276 261.569 + endloop + endfacet + facet normal -0.829971 -0.488156 -0.269909 + outer loop + vertex -677.303 155.511 260.005 + vertex -676.944 155.875 258.244 + vertex -676.258 153.943 259.629 + endloop + endfacet + facet normal -0.828607 -0.49458 -0.262299 + outer loop + vertex -675.018 153.695 256.225 + vertex -675.542 152.743 259.677 + vertex -675.832 154.192 257.861 + endloop + endfacet + facet normal -0.827735 -0.495914 -0.262534 + outer loop + vertex -675.542 152.743 259.677 + vertex -675.018 153.695 256.225 + vertex -674.56 153.268 255.59 + endloop + endfacet + facet normal -0.821941 -0.513441 -0.246558 + outer loop + vertex -675.018 153.695 256.225 + vertex -674.46 154.439 252.816 + vertex -674.56 153.268 255.59 + endloop + endfacet + facet normal -0.840356 -0.474519 -0.261981 + outer loop + vertex -676.751 156.584 256.407 + vertex -676.589 157.394 254.419 + vertex -675.68 154.934 255.96 + endloop + endfacet + facet normal -0.835116 -0.492882 -0.244229 + outer loop + vertex -674.46 154.439 252.816 + vertex -675.018 153.695 256.225 + vertex -675.286 155.174 254.16 + endloop + endfacet + facet normal -0.854741 -0.467845 -0.224807 + outer loop + vertex -676.302 157.881 252.429 + vertex -676.045 158.348 250.479 + vertex -675.138 155.879 252.169 + endloop + endfacet + facet normal -0.837971 -0.496146 -0.227252 + outer loop + vertex -673.98 155.453 248.834 + vertex -674.46 154.439 252.816 + vertex -674.777 156.122 250.313 + endloop + endfacet + facet normal -0.858324 -0.468633 -0.208959 + outer loop + vertex -675.831 158.859 248.529 + vertex -675.648 159.39 246.583 + vertex -674.695 156.909 248.233 + endloop + endfacet + facet normal -0.842575 -0.496538 -0.208607 + outer loop + vertex -673.636 156.505 244.938 + vertex -673.98 155.453 248.834 + vertex -674.399 157.195 246.377 + endloop + endfacet + facet normal -0.86248 -0.468819 -0.190623 + outer loop + vertex -674.352 157.93 244.365 + vertex -675.327 160.368 242.782 + vertex -674.084 158.154 242.604 + endloop + endfacet + facet normal -0.863898 -0.470486 -0.179784 + outer loop + vertex -675.327 160.368 242.782 + vertex -675.188 160.81 240.958 + vertex -674.084 158.154 242.604 + endloop + endfacet + facet normal -0.845834 -0.508455 -0.161363 + outer loop + vertex -673.858 159.726 237.116 + vertex -673.634 159.908 235.368 + vertex -673.061 158.271 237.524 + endloop + endfacet + facet normal -0.844479 -0.505044 -0.178286 + outer loop + vertex -674.079 158.853 240.697 + vertex -673.846 159.066 238.988 + vertex -673.351 157.441 241.246 + endloop + endfacet + facet normal -0.925375 -0.349081 -0.147727 + outer loop + vertex -672.902 157.36 239.557 + vertex -672.725 157.946 237.063 + vertex -672.451 158.178 234.803 + endloop + endfacet + facet normal -0.889347 -0.429042 -0.158068 + outer loop + vertex -672.451 158.178 234.803 + vertex -672.899 156.43 242.063 + vertex -672.902 157.36 239.557 + endloop + endfacet + facet normal -0.853019 -0.498539 -0.154329 + outer loop + vertex -672.725 157.946 237.063 + vertex -672.656 158.383 235.27 + vertex -672.451 158.178 234.803 + endloop + endfacet + facet normal -0.849027 -0.504357 -0.157404 + outer loop + vertex -672.909 159.173 233.814 + vertex -673.061 158.271 237.524 + vertex -673.634 159.908 235.368 + endloop + endfacet + facet normal -0.849923 -0.505073 -0.150103 + outer loop + vertex -672.656 158.383 235.27 + vertex -672.482 159.1 231.871 + vertex -672.451 158.178 234.803 + endloop + endfacet + facet normal -0.868646 -0.475608 -0.138748 + outer loop + vertex -672.482 159.1 231.871 + vertex -672.36 159.817 228.653 + vertex -672.111 159.856 226.955 + endloop + endfacet + facet normal -0.852057 -0.504765 -0.138606 + outer loop + vertex -672.562 160.698 226.375 + vertex -672.753 159.985 230.146 + vertex -673.299 161.552 227.789 + endloop + endfacet + facet normal -0.860834 -0.489837 -0.13793 + outer loop + vertex -672.36 159.817 228.653 + vertex -672.262 160.184 226.738 + vertex -672.111 159.856 226.955 + endloop + endfacet + facet normal -0.869439 -0.479982 -0.117021 + outer loop + vertex -672.262 160.184 226.738 + vertex -672.195 160.737 223.967 + vertex -672.111 159.856 226.955 + endloop + endfacet + facet normal -0.869806 -0.479363 -0.116828 + outer loop + vertex -671.862 161.283 219.248 + vertex -672.111 159.856 226.955 + vertex -672.195 160.737 223.967 + endloop + endfacet + facet normal -0.856437 -0.501702 -0.121701 + outer loop + vertex -672.495 161.543 222.414 + vertex -672.562 160.698 226.375 + vertex -673.177 162.332 223.959 + endloop + endfacet + facet normal -0.846311 -0.519053 -0.119756 + outer loop + vertex -672.195 160.737 223.967 + vertex -672.12 161.417 220.492 + vertex -671.862 161.283 219.248 + endloop + endfacet + facet normal -0.857113 -0.502483 -0.11344 + outer loop + vertex -672.397 162.235 218.609 + vertex -672.495 161.543 222.414 + vertex -673.059 163.017 220.148 + endloop + endfacet + facet normal -0.83464 -0.53861 -0.11522 + outer loop + vertex -672.12 161.417 220.492 + vertex -672.009 162.038 216.785 + vertex -671.862 161.283 219.248 + endloop + endfacet + facet normal -0.85672 -0.504692 -0.106383 + outer loop + vertex -672.253 162.837 214.595 + vertex -672.397 162.235 218.609 + vertex -672.962 163.703 216.198 + endloop + endfacet + facet normal -0.889909 -0.445626 -0.0973581 + outer loop + vertex -672.009 162.038 216.785 + vertex -671.94 162.472 214.168 + vertex -671.707 162.517 211.825 + endloop + endfacet + facet normal -0.862326 -0.496266 -0.100572 + outer loop + vertex -671.707 162.517 211.825 + vertex -671.862 161.283 219.248 + vertex -672.009 162.038 216.785 + endloop + endfacet + facet normal -0.847974 -0.521514 -0.0946706 + outer loop + vertex -671.94 162.472 214.168 + vertex -671.929 162.797 212.274 + vertex -671.707 162.517 211.825 + endloop + endfacet + facet normal -0.85864 -0.504115 -0.0927645 + outer loop + vertex -672.214 163.509 210.584 + vertex -672.253 162.837 214.595 + vertex -672.886 164.367 212.137 + endloop + endfacet + facet normal -0.845729 -0.525818 -0.0908726 + outer loop + vertex -671.929 162.797 212.274 + vertex -671.839 163.259 208.77 + vertex -671.707 162.517 211.825 + endloop + endfacet + facet normal -0.858931 -0.504694 -0.0867236 + outer loop + vertex -672.098 164.002 206.571 + vertex -672.214 163.509 210.584 + vertex -672.809 164.929 208.208 + endloop + endfacet + facet normal -0.894004 -0.441011 -0.0791644 + outer loop + vertex -671.839 163.259 208.77 + vertex -671.766 163.596 206.061 + vertex -671.526 163.519 203.782 + endloop + endfacet + facet normal -0.87058 -0.485478 -0.08001 + outer loop + vertex -671.526 163.519 203.782 + vertex -671.707 162.517 211.825 + vertex -671.839 163.259 208.77 + endloop + endfacet + facet normal -0.854266 -0.514762 -0.0724568 + outer loop + vertex -671.766 163.596 206.061 + vertex -671.752 163.842 204.157 + vertex -671.526 163.519 203.782 + endloop + endfacet + facet normal -0.861235 -0.502949 -0.0729176 + outer loop + vertex -672.075 164.527 202.676 + vertex -672.098 164.002 206.571 + vertex -672.747 165.433 204.362 + endloop + endfacet + facet normal -0.85199 -0.519222 -0.0672379 + outer loop + vertex -671.752 163.842 204.157 + vertex -671.648 164.126 200.645 + vertex -671.526 163.519 203.782 + endloop + endfacet + facet normal -0.874996 -0.480538 -0.0588567 + outer loop + vertex -671.362 164.231 195.532 + vertex -671.526 163.519 203.782 + vertex -671.648 164.126 200.645 + endloop + endfacet + facet normal -0.860772 -0.504594 -0.0667648 + outer loop + vertex -671.954 164.788 199.136 + vertex -672.075 164.527 202.676 + vertex -672.676 165.842 200.486 + endloop + endfacet + facet normal -0.884845 -0.462132 -0.0590273 + outer loop + vertex -671.648 164.126 200.645 + vertex -671.583 164.389 197.609 + vertex -671.362 164.231 195.532 + endloop + endfacet + facet normal -0.860002 -0.506246 -0.0641222 + outer loop + vertex -671.792 164.817 196.736 + vertex -671.954 164.788 199.136 + vertex -672.465 165.971 196.656 + endloop + endfacet + facet normal -0.859176 -0.508954 -0.0527474 + outer loop + vertex -671.583 164.389 197.609 + vertex -671.643 164.715 195.433 + vertex -671.362 164.231 195.532 + endloop + endfacet + facet normal -0.8605 -0.506119 -0.0581697 + outer loop + vertex -672.237 165.838 194.442 + vertex -671.792 164.817 196.736 + vertex -672.465 165.971 196.656 + endloop + endfacet + facet normal -0.860096 -0.508072 -0.0457984 + outer loop + vertex -671.643 164.715 195.433 + vertex -671.844 165.341 192.268 + vertex -671.362 164.231 195.532 + endloop + endfacet + facet normal -0.868554 -0.493997 -0.0397646 + outer loop + vertex -671.271 164.709 187.617 + vertex -671.362 164.231 195.532 + vertex -671.844 165.341 192.268 + endloop + endfacet + facet normal -0.8849 -0.464611 -0.0329966 + outer loop + vertex -672.101 166.084 188.7 + vertex -671.844 165.341 192.268 + vertex -673.252 168.122 190.865 + endloop + endfacet + facet normal -0.886908 -0.460376 -0.0380526 + outer loop + vertex -673.252 168.122 190.865 + vertex -673.265 168.496 186.641 + vertex -672.101 166.084 188.7 + endloop + endfacet + facet normal -0.888783 -0.457125 -0.0331815 + outer loop + vertex -671.832 165.828 185.028 + vertex -672.101 166.084 188.7 + vertex -673.265 168.496 186.641 + endloop + endfacet + facet normal -0.887789 -0.459361 -0.0286025 + outer loop + vertex -673.265 168.496 186.641 + vertex -672.933 168.1 182.71 + vertex -671.832 165.828 185.028 + endloop + endfacet + facet normal -0.888262 -0.45851 -0.0275443 + outer loop + vertex -671.666 165.66 182.467 + vertex -671.832 165.828 185.028 + vertex -672.933 168.1 182.71 + endloop + endfacet + facet normal -0.888047 -0.459433 -0.0171418 + outer loop + vertex -671.842 166.071 180.567 + vertex -671.666 165.66 182.467 + vertex -672.933 168.1 182.71 + endloop + endfacet + facet normal -0.888789 -0.457924 -0.0189475 + outer loop + vertex -672.933 168.1 182.71 + vertex -673.115 168.614 178.811 + vertex -671.842 166.071 180.567 + endloop + endfacet + facet normal -0.890134 -0.45547 -0.0144198 + outer loop + vertex -671.753 166.008 177.085 + vertex -671.842 166.071 180.567 + vertex -673.115 168.614 178.811 + endloop + endfacet + facet normal -0.889199 -0.457394 -0.0107774 + outer loop + vertex -673.115 168.614 178.811 + vertex -673.109 168.691 175.082 + vertex -671.753 166.008 177.085 + endloop + endfacet + facet normal -0.89007 -0.455755 -0.00799087 + outer loop + vertex -671.827 166.211 173.768 + vertex -671.753 166.008 177.085 + vertex -673.109 168.691 175.082 + endloop + endfacet + facet normal -0.888815 -0.458261 -0.00203945 + outer loop + vertex -673.109 168.691 175.082 + vertex -672.883 168.269 171.259 + vertex -671.827 166.211 173.768 + endloop + endfacet + facet normal -0.887095 -0.461554 -0.00546538 + outer loop + vertex -671.625 165.845 171.844 + vertex -671.827 166.211 173.768 + vertex -672.883 168.269 171.259 + endloop + endfacet + facet normal -0.888241 -0.459336 0.0061976 + outer loop + vertex -671.716 165.983 168.984 + vertex -671.625 165.845 171.844 + vertex -672.883 168.269 171.259 + endloop + endfacet + facet normal -0.88805 -0.459698 0.00665981 + outer loop + vertex -672.883 168.269 171.259 + vertex -673.144 168.713 167.113 + vertex -671.716 165.983 168.984 + endloop + endfacet + facet normal -0.889648 -0.456473 0.0125838 + outer loop + vertex -671.926 166.292 165.358 + vertex -671.716 165.983 168.984 + vertex -673.144 168.713 167.113 + endloop + endfacet + facet normal -0.889077 -0.457529 0.0144373 + outer loop + vertex -673.144 168.713 167.113 + vertex -673.157 168.617 163.262 + vertex -671.926 166.292 165.358 + endloop + endfacet + facet normal -0.889638 -0.456384 0.016036 + outer loop + vertex -671.74 165.801 161.694 + vertex -671.926 166.292 165.358 + vertex -673.157 168.617 163.262 + endloop + endfacet + facet normal -0.887986 -0.459306 0.0227766 + outer loop + vertex -673.157 168.617 163.262 + vertex -672.93 167.983 159.334 + vertex -671.74 165.801 161.694 + endloop + endfacet + facet normal -0.88805 -0.459175 0.0229296 + outer loop + vertex -671.667 165.529 159.09 + vertex -671.74 165.801 161.694 + vertex -672.93 167.983 159.334 + endloop + endfacet + facet normal -0.887295 -0.45992 0.0343624 + outer loop + vertex -671.879 165.795 157.19 + vertex -671.667 165.529 159.09 + vertex -672.93 167.983 159.334 + endloop + endfacet + facet normal -0.888283 -0.458174 0.0320972 + outer loop + vertex -672.93 167.983 159.334 + vertex -673.192 168.216 155.415 + vertex -671.879 165.795 157.19 + endloop + endfacet + facet normal -0.889351 -0.455794 0.0361354 + outer loop + vertex -671.865 165.49 153.685 + vertex -671.879 165.795 157.19 + vertex -673.192 168.216 155.415 + endloop + endfacet + facet normal -0.888127 -0.457829 0.0402808 + outer loop + vertex -673.192 168.216 155.415 + vertex -673.231 167.968 151.714 + vertex -671.865 165.49 153.685 + endloop + endfacet + facet normal -0.888675 -0.45659 0.0422204 + outer loop + vertex -671.998 165.444 150.37 + vertex -671.865 165.49 153.685 + vertex -673.231 167.968 151.714 + endloop + endfacet + facet normal -0.887355 -0.458654 0.0473084 + outer loop + vertex -673.231 167.968 151.714 + vertex -673.064 167.247 147.856 + vertex -671.998 165.444 150.37 + endloop + endfacet + facet normal -0.885789 -0.461972 0.0442644 + outer loop + vertex -671.83 164.932 148.413 + vertex -671.998 165.444 150.37 + vertex -673.064 167.247 147.856 + endloop + endfacet + facet normal -0.886315 -0.459933 0.0539161 + outer loop + vertex -671.952 164.815 145.393 + vertex -671.83 164.932 148.413 + vertex -673.064 167.247 147.856 + endloop + endfacet + facet normal -0.884213 -0.46343 0.058318 + outer loop + vertex -673.064 167.247 147.856 + vertex -673.28 167.123 143.594 + vertex -671.952 164.815 145.393 + endloop + endfacet + facet normal -0.884549 -0.462623 0.0596015 + outer loop + vertex -672.032 164.474 141.57 + vertex -671.952 164.815 145.393 + vertex -673.28 167.123 143.594 + endloop + endfacet + facet normal -0.877617 -0.473053 0.0775224 + outer loop + vertex -673.28 167.123 143.594 + vertex -673.066 166.146 140.061 + vertex -672.032 164.474 141.57 + endloop + endfacet + facet normal -0.876127 -0.476583 0.0725905 + outer loop + vertex -673.066 166.146 140.061 + vertex -672.064 164.159 139.104 + vertex -672.032 164.474 141.57 + endloop + endfacet + facet normal -0.849821 -0.521272 0.0779691 + outer loop + vertex -671.694 163.563 139.154 + vertex -672.032 164.474 141.57 + vertex -672.064 164.159 139.104 + endloop + endfacet + facet normal -0.849759 -0.521056 0.0800617 + outer loop + vertex -672.064 164.159 139.104 + vertex -671.955 163.563 136.388 + vertex -671.694 163.563 139.154 + endloop + endfacet + facet normal -0.828086 -0.555144 0.0780312 + outer loop + vertex -671.669 163.2 136.841 + vertex -671.694 163.563 139.154 + vertex -671.955 163.563 136.388 + endloop + endfacet + facet normal -0.830249 -0.551252 0.0825104 + outer loop + vertex -671.828 163.018 134.031 + vertex -671.669 163.2 136.841 + vertex -671.955 163.563 136.388 + endloop + endfacet + facet normal -0.814911 -0.572818 0.0883176 + outer loop + vertex -671.955 163.563 136.388 + vertex -672.215 163.316 132.381 + vertex -671.828 163.018 134.031 + endloop + endfacet + facet normal -0.828735 -0.551447 0.0954213 + outer loop + vertex -671.948 162.561 130.344 + vertex -671.828 163.018 134.031 + vertex -672.215 163.316 132.381 + endloop + endfacet + facet normal -0.817705 -0.566452 0.102425 + outer loop + vertex -672.215 163.316 132.381 + vertex -672.305 162.701 128.266 + vertex -671.948 162.561 130.344 + endloop + endfacet + facet normal -0.819383 -0.563938 0.102883 + outer loop + vertex -672.012 162.171 127.694 + vertex -671.948 162.561 130.344 + vertex -672.305 162.701 128.266 + endloop + endfacet + facet normal -0.807835 -0.57689 0.120833 + outer loop + vertex -672.07 161.862 125.826 + vertex -672.012 162.171 127.694 + vertex -672.305 162.701 128.266 + endloop + endfacet + facet normal -0.812523 -0.570802 0.118286 + outer loop + vertex -672.305 162.701 128.266 + vertex -672.424 162.059 124.35 + vertex -672.07 161.862 125.826 + endloop + endfacet + facet normal -0.822492 -0.555378 0.122731 + outer loop + vertex -672.13 161.176 122.322 + vertex -672.07 161.862 125.826 + vertex -672.424 162.059 124.35 + endloop + endfacet + facet normal -0.820084 -0.558545 0.124457 + outer loop + vertex -672.424 162.059 124.35 + vertex -672.512 161.363 120.647 + vertex -672.13 161.176 122.322 + endloop + endfacet + facet normal -0.823285 -0.553525 0.125747 + outer loop + vertex -672.226 160.582 119.077 + vertex -672.13 161.176 122.322 + vertex -672.512 161.363 120.647 + endloop + endfacet + facet normal -0.811382 -0.568614 0.135418 + outer loop + vertex -672.512 161.363 120.647 + vertex -672.578 160.564 116.896 + vertex -672.226 160.582 119.077 + endloop + endfacet + facet normal -0.806793 -0.575268 0.13473 + outer loop + vertex -672.257 160.176 117.164 + vertex -672.226 160.582 119.077 + vertex -672.578 160.564 116.896 + endloop + endfacet + facet normal -0.809739 -0.567377 0.149687 + outer loop + vertex -672.375 159.627 114.444 + vertex -672.257 160.176 117.164 + vertex -672.578 160.564 116.896 + endloop + endfacet + facet normal -0.81355 -0.562477 0.147498 + outer loop + vertex -672.578 160.564 116.896 + vertex -672.779 159.832 112.996 + vertex -672.375 159.627 114.444 + endloop + endfacet + facet normal -0.82111 -0.550344 0.151327 + outer loop + vertex -672.539 158.937 111.046 + vertex -672.375 159.627 114.444 + vertex -672.779 159.832 112.996 + endloop + endfacet + facet normal -0.809317 -0.565264 0.159632 + outer loop + vertex -672.779 159.832 112.996 + vertex -672.934 159.011 109.303 + vertex -672.539 158.937 111.046 + endloop + endfacet + facet normal -0.816197 -0.554703 0.16164 + outer loop + vertex -672.69 158.122 107.485 + vertex -672.539 158.937 111.046 + vertex -672.934 159.011 109.303 + endloop + endfacet + facet normal -0.803511 -0.570221 0.170933 + outer loop + vertex -672.934 159.011 109.303 + vertex -673.098 158.089 105.46 + vertex -672.69 158.122 107.485 + endloop + endfacet + facet normal -0.8006 -0.574455 0.170414 + outer loop + vertex -672.798 157.536 105.001 + vertex -672.69 158.122 107.485 + vertex -673.098 158.089 105.46 + endloop + endfacet + facet normal -0.78758 -0.585468 0.192211 + outer loop + vertex -672.93 157.12 103.197 + vertex -672.798 157.536 105.001 + vertex -673.098 158.089 105.46 + endloop + endfacet + facet normal -0.786608 -0.586592 0.192764 + outer loop + vertex -673.098 158.089 105.46 + vertex -673.378 157.22 101.671 + vertex -672.93 157.12 103.197 + endloop + endfacet + facet normal -0.803939 -0.560221 0.199586 + outer loop + vertex -673.162 156.204 99.6871 + vertex -672.93 157.12 103.197 + vertex -673.378 157.22 101.671 + endloop + endfacet + facet normal -0.79707 -0.56823 0.204438 + outer loop + vertex -673.378 157.22 101.671 + vertex -673.658 156.281 97.967 + vertex -673.162 156.204 99.6871 + endloop + endfacet + facet normal -0.80897 -0.549555 0.208701 + outer loop + vertex -673.494 155.271 95.9442 + vertex -673.162 156.204 99.6871 + vertex -673.658 156.281 97.967 + endloop + endfacet + facet normal -0.793424 -0.567866 0.219103 + outer loop + vertex -673.658 156.281 97.967 + vertex -674.039 155.32 94.0991 + vertex -673.494 155.271 95.9442 + endloop + endfacet + facet normal -0.859153 -0.473448 0.194175 + outer loop + vertex -673.162 156.204 99.6871 + vertex -673.494 155.271 95.9442 + vertex -673.407 154.622 94.7492 + endloop + endfacet + facet normal -0.833863 -0.518036 0.190555 + outer loop + vertex -672.93 157.12 103.197 + vertex -673.162 156.204 99.6871 + vertex -672.781 156.703 102.714 + endloop + endfacet + facet normal -0.843275 -0.507078 0.178209 + outer loop + vertex -672.798 157.536 105.001 + vertex -672.93 157.12 103.197 + vertex -672.781 156.703 102.714 + endloop + endfacet + facet normal -0.921097 -0.368036 0.127002 + outer loop + vertex -672.69 158.122 107.485 + vertex -672.798 157.536 105.001 + vertex -672.781 156.703 102.714 + endloop + endfacet + facet normal -0.864287 -0.477397 0.158428 + outer loop + vertex -672.781 156.703 102.714 + vertex -672.373 158.336 109.859 + vertex -672.69 158.122 107.485 + endloop + endfacet + facet normal -0.846047 -0.509126 0.158097 + outer loop + vertex -673.098 158.089 105.46 + vertex -672.934 159.011 109.303 + vertex -673.693 159.58 107.073 + endloop + endfacet + facet normal -0.840324 -0.515894 0.166459 + outer loop + vertex -673.932 159.329 105.091 + vertex -673.098 158.089 105.46 + vertex -673.693 159.58 107.073 + endloop + endfacet + facet normal -0.867198 -0.47021 0.163924 + outer loop + vertex -673.693 159.58 107.073 + vertex -675.003 161.455 105.525 + vertex -673.932 159.329 105.091 + endloop + endfacet + facet normal -0.866194 -0.470568 0.168147 + outer loop + vertex -675.003 161.455 105.525 + vertex -675.124 160.995 103.611 + vertex -673.932 159.329 105.091 + endloop + endfacet + facet normal -0.865382 -0.473417 0.164285 + outer loop + vertex -673.932 159.329 105.091 + vertex -675.124 160.995 103.611 + vertex -673.917 158.665 103.255 + endloop + endfacet + facet normal -0.862466 -0.473936 0.177589 + outer loop + vertex -675.124 160.995 103.611 + vertex -675.253 160.516 101.707 + vertex -673.917 158.665 103.255 + endloop + endfacet + facet normal -0.863171 -0.471153 0.181524 + outer loop + vertex -673.917 158.665 103.255 + vertex -675.253 160.516 101.707 + vertex -674.172 158.375 101.29 + endloop + endfacet + facet normal -0.837243 -0.51474 0.184573 + outer loop + vertex -674.172 158.375 101.29 + vertex -673.378 157.22 101.671 + vertex -673.917 158.665 103.255 + endloop + endfacet + facet normal -0.841036 -0.510395 0.179322 + outer loop + vertex -673.378 157.22 101.671 + vertex -673.098 158.089 105.46 + vertex -673.917 158.665 103.255 + endloop + endfacet + facet normal -0.837109 -0.511977 0.192687 + outer loop + vertex -674.172 158.375 101.29 + vertex -674.185 157.721 99.4954 + vertex -673.378 157.22 101.671 + endloop + endfacet + facet normal -0.837514 -0.511189 0.193019 + outer loop + vertex -673.658 156.281 97.967 + vertex -673.378 157.22 101.671 + vertex -674.185 157.721 99.4954 + endloop + endfacet + facet normal -0.833728 -0.515357 0.198255 + outer loop + vertex -674.47 157.442 97.5731 + vertex -673.658 156.281 97.967 + vertex -674.185 157.721 99.4954 + endloop + endfacet + facet normal -0.859628 -0.471924 0.195775 + outer loop + vertex -674.185 157.721 99.4954 + vertex -675.559 159.588 97.9647 + vertex -674.47 157.442 97.5731 + endloop + endfacet + facet normal -0.858698 -0.472109 0.199376 + outer loop + vertex -675.559 159.588 97.9647 + vertex -675.73 159.122 96.124 + vertex -674.47 157.442 97.5731 + endloop + endfacet + facet normal -0.85762 -0.476603 0.193228 + outer loop + vertex -674.47 157.442 97.5731 + vertex -675.73 159.122 96.124 + vertex -674.526 156.816 95.7807 + endloop + endfacet + facet normal -0.854419 -0.476877 0.206292 + outer loop + vertex -675.73 159.122 96.124 + vertex -675.924 158.674 94.2861 + vertex -674.526 156.816 95.7807 + endloop + endfacet + facet normal -0.8551 -0.473565 0.211046 + outer loop + vertex -674.526 156.816 95.7807 + vertex -675.924 158.674 94.2861 + vertex -674.847 156.536 93.8485 + endloop + endfacet + facet normal -0.833249 -0.510334 0.212733 + outer loop + vertex -674.847 156.536 93.8485 + vertex -674.039 155.32 94.0991 + vertex -674.526 156.816 95.7807 + endloop + endfacet + facet normal -0.836878 -0.506295 0.20809 + outer loop + vertex -674.039 155.32 94.0991 + vertex -673.658 156.281 97.967 + vertex -674.526 156.816 95.7807 + endloop + endfacet + facet normal -0.83219 -0.507374 0.223677 + outer loop + vertex -674.847 156.536 93.8485 + vertex -674.931 155.847 91.9733 + vertex -674.039 155.32 94.0991 + endloop + endfacet + facet normal -0.835542 -0.500429 0.226806 + outer loop + vertex -674.524 154.262 89.9784 + vertex -674.039 155.32 94.0991 + vertex -674.931 155.847 91.9733 + endloop + endfacet + facet normal -0.828509 -0.508455 0.234618 + outer loop + vertex -675.284 155.515 90.0084 + vertex -674.524 154.262 89.9784 + vertex -674.931 155.847 91.9733 + endloop + endfacet + facet normal -0.847446 -0.477151 0.232729 + outer loop + vertex -674.931 155.847 91.9733 + vertex -676.308 157.594 90.5408 + vertex -675.284 155.515 90.0084 + endloop + endfacet + facet normal -0.84181 -0.478663 0.249473 + outer loop + vertex -676.308 157.594 90.5408 + vertex -676.485 156.926 88.6631 + vertex -675.284 155.515 90.0084 + endloop + endfacet + facet normal -0.839974 -0.487229 0.238852 + outer loop + vertex -675.284 155.515 90.0084 + vertex -676.485 156.926 88.6631 + vertex -675.407 154.828 88.1727 + endloop + endfacet + facet normal -0.833492 -0.488444 0.258291 + outer loop + vertex -676.485 156.926 88.6631 + vertex -676.722 156.333 86.7793 + vertex -675.407 154.828 88.1727 + endloop + endfacet + facet normal -0.832814 -0.491859 0.25396 + outer loop + vertex -675.407 154.828 88.1727 + vertex -676.722 156.333 86.7793 + vertex -675.807 154.528 86.2826 + endloop + endfacet + facet normal -0.818321 -0.515286 0.25462 + outer loop + vertex -675.807 154.528 86.2826 + vertex -675.074 153.475 86.5079 + vertex -675.407 154.828 88.1727 + endloop + endfacet + facet normal -0.826465 -0.50648 0.245834 + outer loop + vertex -675.074 153.475 86.5079 + vertex -674.524 154.262 89.9784 + vertex -675.407 154.828 88.1727 + endloop + endfacet + facet normal -0.835864 -0.491737 0.24398 + outer loop + vertex -674.524 154.262 89.9784 + vertex -675.074 153.475 86.5079 + vertex -674.764 152.62 85.8458 + endloop + endfacet + facet normal -0.823045 -0.502772 0.264229 + outer loop + vertex -675.074 153.475 86.5079 + vertex -675.56 152.488 83.1148 + vertex -674.764 152.62 85.8458 + endloop + endfacet + facet normal -0.820028 -0.507227 0.265094 + outer loop + vertex -675.56 152.488 83.1148 + vertex -675.074 153.475 86.5079 + vertex -675.978 153.896 84.5167 + endloop + endfacet + facet normal -0.812316 -0.514482 0.274682 + outer loop + vertex -676.431 153.602 82.6233 + vertex -675.56 152.488 83.1148 + vertex -675.978 153.896 84.5167 + endloop + endfacet + facet normal -0.823416 -0.496593 0.274558 + outer loop + vertex -675.978 153.896 84.5167 + vertex -677.35 155.354 83.0386 + vertex -676.431 153.602 82.6233 + endloop + endfacet + facet normal -0.818915 -0.49713 0.286776 + outer loop + vertex -677.35 155.354 83.0386 + vertex -677.699 154.863 81.1896 + vertex -676.431 153.602 82.6233 + endloop + endfacet + facet normal -0.818633 -0.498358 0.285446 + outer loop + vertex -676.431 153.602 82.6233 + vertex -677.699 154.863 81.1896 + vertex -676.63 152.893 80.8158 + endloop + endfacet + facet normal -0.813234 -0.498299 0.30058 + outer loop + vertex -677.699 154.863 81.1896 + vertex -678.071 154.358 79.3471 + vertex -676.63 152.893 80.8158 + endloop + endfacet + facet normal -0.813451 -0.497078 0.302011 + outer loop + vertex -676.63 152.893 80.8158 + vertex -678.071 154.358 79.3471 + vertex -677.153 152.556 78.8532 + endloop + endfacet + facet normal -0.804366 -0.511603 0.30209 + outer loop + vertex -677.153 152.556 78.8532 + vertex -676.306 151.371 79.1002 + vertex -676.63 152.893 80.8158 + endloop + endfacet + facet normal -0.814812 -0.501375 0.291041 + outer loop + vertex -676.306 151.371 79.1002 + vertex -675.56 152.488 83.1148 + vertex -676.63 152.893 80.8158 + endloop + endfacet + facet normal -0.801846 -0.506789 0.316557 + outer loop + vertex -677.153 152.556 78.8532 + vertex -677.419 151.812 76.988 + vertex -676.306 151.371 79.1002 + endloop + endfacet + facet normal -0.80617 -0.497134 0.320855 + outer loop + vertex -677.232 150.219 74.9891 + vertex -676.306 151.371 79.1002 + vertex -677.419 151.812 76.988 + endloop + endfacet + facet normal -0.808822 -0.497337 0.313788 + outer loop + vertex -677.153 152.556 78.8532 + vertex -678.466 153.84 77.5045 + vertex -677.419 151.812 76.988 + endloop + endfacet + facet normal -0.802887 -0.497863 0.32788 + outer loop + vertex -678.466 153.84 77.5045 + vertex -678.895 153.32 75.6643 + vertex -677.419 151.812 76.988 + endloop + endfacet + facet normal -0.803099 -0.495825 0.330437 + outer loop + vertex -677.419 151.812 76.988 + vertex -678.895 153.32 75.6643 + vertex -677.991 151.458 75.0668 + endloop + endfacet + facet normal -0.795547 -0.507872 0.330411 + outer loop + vertex -677.991 151.458 75.0668 + vertex -677.232 150.219 74.9891 + vertex -677.419 151.812 76.988 + endloop + endfacet + facet normal -0.790337 -0.505657 0.345945 + outer loop + vertex -677.991 151.458 75.0668 + vertex -678.341 150.765 73.2553 + vertex -677.232 150.219 74.9891 + endloop + endfacet + facet normal -0.792515 -0.500045 0.349106 + outer loop + vertex -678.188 149.356 71.5836 + vertex -677.232 150.219 74.9891 + vertex -678.341 150.765 73.2553 + endloop + endfacet + facet normal -0.787423 -0.507679 0.349611 + outer loop + vertex -677.232 150.219 74.9891 + vertex -678.188 149.356 71.5836 + vertex -677.871 148.582 71.1746 + endloop + endfacet + facet normal -0.817669 -0.466681 0.337084 + outer loop + vertex -677.871 148.582 71.1746 + vertex -676.466 150.049 76.6134 + vertex -677.232 150.219 74.9891 + endloop + endfacet + facet normal -0.797111 -0.49645 0.34373 + outer loop + vertex -677.991 151.458 75.0668 + vertex -679.365 152.798 73.8163 + vertex -678.341 150.765 73.2553 + endloop + endfacet + facet normal -0.789546 -0.497095 0.359881 + outer loop + vertex -679.365 152.798 73.8163 + vertex -679.887 152.275 71.9502 + vertex -678.341 150.765 73.2553 + endloop + endfacet + facet normal -0.789676 -0.495061 0.36239 + outer loop + vertex -678.341 150.765 73.2553 + vertex -679.887 152.275 71.9502 + vertex -679 150.452 71.3911 + endloop + endfacet + facet normal -0.778455 -0.513179 0.361463 + outer loop + vertex -679 150.452 71.3911 + vertex -678.188 149.356 71.5836 + vertex -678.341 150.765 73.2553 + endloop + endfacet + facet normal -0.774626 -0.507568 0.377264 + outer loop + vertex -679 150.452 71.3911 + vertex -679.417 149.764 69.6097 + vertex -678.188 149.356 71.5836 + endloop + endfacet + facet normal -0.782778 -0.496659 0.374951 + outer loop + vertex -679 150.452 71.3911 + vertex -680.472 151.769 70.0629 + vertex -679.417 149.764 69.6097 + endloop + endfacet + facet normal -0.773828 -0.496184 0.393689 + outer loop + vertex -680.472 151.769 70.0629 + vertex -681.108 151.263 68.1754 + vertex -679.417 149.764 69.6097 + endloop + endfacet + facet normal -0.773829 -0.496172 0.393703 + outer loop + vertex -679.417 149.764 69.6097 + vertex -681.108 151.263 68.1754 + vertex -680.165 149.428 67.7163 + endloop + endfacet + facet normal -0.759959 -0.518344 0.39215 + outer loop + vertex -680.165 149.428 67.7163 + vertex -679.147 148.321 68.2255 + vertex -679.417 149.764 69.6097 + endloop + endfacet + facet normal -0.757704 -0.508517 0.409017 + outer loop + vertex -680.165 149.428 67.7163 + vertex -680.68 148.765 65.9386 + vertex -679.147 148.321 68.2255 + endloop + endfacet + facet normal -0.765241 -0.498405 0.407431 + outer loop + vertex -680.165 149.428 67.7163 + vertex -681.784 150.781 66.3295 + vertex -680.68 148.765 65.9386 + endloop + endfacet + facet normal -0.755534 -0.496872 0.426951 + outer loop + vertex -681.784 150.781 66.3295 + vertex -682.488 150.328 64.5565 + vertex -680.68 148.765 65.9386 + endloop + endfacet + facet normal -0.755531 -0.497134 0.42665 + outer loop + vertex -680.68 148.765 65.9386 + vertex -682.488 150.328 64.5565 + vertex -681.528 148.463 64.0827 + endloop + endfacet + facet normal -0.741127 -0.520619 0.423894 + outer loop + vertex -681.528 148.463 64.0827 + vertex -680.519 147.256 64.3659 + vertex -680.68 148.765 65.9386 + endloop + endfacet + facet normal -0.735114 -0.510332 0.446284 + outer loop + vertex -681.528 148.463 64.0827 + vertex -682.105 147.818 62.3956 + vertex -680.519 147.256 64.3659 + endloop + endfacet + facet normal -0.744968 -0.497287 0.444667 + outer loop + vertex -681.528 148.463 64.0827 + vertex -683.202 149.881 62.8643 + vertex -682.105 147.818 62.3956 + endloop + endfacet + facet normal -0.733814 -0.495838 0.464395 + outer loop + vertex -683.202 149.881 62.8643 + vertex -683.95 149.462 61.2351 + vertex -682.105 147.818 62.3956 + endloop + endfacet + facet normal -0.733663 -0.494482 0.466075 + outer loop + vertex -682.105 147.818 62.3956 + vertex -683.95 149.462 61.2351 + vertex -683.012 147.555 60.6879 + endloop + endfacet + facet normal -0.72575 -0.507972 0.463951 + outer loop + vertex -683.012 147.555 60.6879 + vertex -682.132 146.275 60.664 + vertex -682.105 147.818 62.3956 + endloop + endfacet + facet normal -0.715062 -0.501059 0.48747 + outer loop + vertex -683.012 147.555 60.6879 + vertex -683.678 146.955 59.0953 + vertex -682.132 146.275 60.664 + endloop + endfacet + facet normal -0.721517 -0.492308 0.486875 + outer loop + vertex -683.012 147.555 60.6879 + vertex -684.75 149.048 59.622 + vertex -683.678 146.955 59.0953 + endloop + endfacet + facet normal -0.708533 -0.490746 0.507098 + outer loop + vertex -684.75 149.048 59.622 + vertex -685.638 148.65 57.9976 + vertex -683.678 146.955 59.0953 + endloop + endfacet + facet normal -0.708051 -0.488113 0.510303 + outer loop + vertex -683.678 146.955 59.0953 + vertex -685.638 148.65 57.9976 + vertex -684.727 146.76 57.454 + endloop + endfacet + facet normal -0.702235 -0.49893 0.507872 + outer loop + vertex -684.727 146.76 57.454 + vertex -683.801 145.641 57.6336 + vertex -683.678 146.955 59.0953 + endloop + endfacet + facet normal -0.693382 -0.488044 0.530127 + outer loop + vertex -684.727 146.76 57.454 + vertex -685.542 146.212 55.883 + vertex -683.801 145.641 57.6336 + endloop + endfacet + facet normal -0.695702 -0.484694 0.530161 + outer loop + vertex -684.727 146.76 57.454 + vertex -686.622 148.291 56.3665 + vertex -685.542 146.212 55.883 + endloop + endfacet + facet normal -0.682866 -0.482332 0.54868 + outer loop + vertex -686.622 148.291 56.3665 + vertex -687.706 147.992 54.7542 + vertex -685.542 146.212 55.883 + endloop + endfacet + facet normal -0.68193 -0.478142 0.55349 + outer loop + vertex -685.542 146.212 55.883 + vertex -687.706 147.992 54.7542 + vertex -686.813 146.099 54.2195 + endloop + endfacet + facet normal -0.678527 -0.485365 0.551382 + outer loop + vertex -686.813 146.099 54.2195 + vertex -685.595 144.859 54.6271 + vertex -685.542 146.212 55.883 + endloop + endfacet + facet normal -0.669694 -0.468531 0.576185 + outer loop + vertex -686.813 146.099 54.2195 + vertex -687.837 145.593 52.6172 + vertex -685.595 144.859 54.6271 + endloop + endfacet + facet normal -0.66648 -0.473632 0.575741 + outer loop + vertex -686.813 146.099 54.2195 + vertex -688.881 147.753 53.1865 + vertex -687.837 145.593 52.6172 + endloop + endfacet + facet normal -0.647857 -0.470739 0.598904 + outer loop + vertex -688.881 147.753 53.1865 + vertex -690.094 147.516 51.6872 + vertex -687.837 145.593 52.6172 + endloop + endfacet + facet normal -0.648392 -0.472207 0.597167 + outer loop + vertex -687.837 145.593 52.6172 + vertex -690.094 147.516 51.6872 + vertex -689.216 145.481 51.0322 + endloop + endfacet + facet normal -0.641875 -0.486739 0.592522 + outer loop + vertex -689.216 145.481 51.0322 + vertex -688.102 144.007 51.0275 + vertex -687.837 145.593 52.6172 + endloop + endfacet + facet normal -0.627095 -0.475654 0.61685 + outer loop + vertex -689.216 145.481 51.0322 + vertex -689.913 144.79 49.7904 + vertex -688.102 144.007 51.0275 + endloop + endfacet + facet normal -0.624827 -0.478343 0.617072 + outer loop + vertex -689.216 145.481 51.0322 + vertex -691.236 147.087 50.2311 + vertex -689.913 144.79 49.7904 + endloop + endfacet + facet normal -0.621937 -0.470137 0.626231 + outer loop + vertex -690.094 147.516 51.6872 + vertex -691.236 147.087 50.2311 + vertex -689.216 145.481 51.0322 + endloop + endfacet + facet normal -0.667195 -0.476555 0.572491 + outer loop + vertex -687.706 147.992 54.7542 + vertex -688.881 147.753 53.1865 + vertex -686.813 146.099 54.2195 + endloop + endfacet + facet normal -0.696109 -0.487242 0.527283 + outer loop + vertex -685.638 148.65 57.9976 + vertex -686.622 148.291 56.3665 + vertex -684.727 146.76 57.454 + endloop + endfacet + facet normal -0.721726 -0.493998 0.484848 + outer loop + vertex -683.95 149.462 61.2351 + vertex -684.75 149.048 59.622 + vertex -683.012 147.555 60.6879 + endloop + endfacet + facet normal -0.744955 -0.496499 0.445567 + outer loop + vertex -682.488 150.328 64.5565 + vertex -683.202 149.881 62.8643 + vertex -681.528 148.463 64.0827 + endloop + endfacet + facet normal -0.765435 -0.495948 0.410054 + outer loop + vertex -681.108 151.263 68.1754 + vertex -681.784 150.781 66.3295 + vertex -680.165 149.428 67.7163 + endloop + endfacet + facet normal -0.78286 -0.495867 0.375827 + outer loop + vertex -679.887 152.275 71.9502 + vertex -680.472 151.769 70.0629 + vertex -679 150.452 71.3911 + endloop + endfacet + facet normal -0.797055 -0.496962 0.34312 + outer loop + vertex -678.895 153.32 75.6643 + vertex -679.365 152.798 73.8163 + vertex -677.991 151.458 75.0668 + endloop + endfacet + facet normal -0.808744 -0.497773 0.313297 + outer loop + vertex -678.071 154.358 79.3471 + vertex -678.466 153.84 77.5045 + vertex -677.153 152.556 78.8532 + endloop + endfacet + facet normal -0.823177 -0.497725 0.27322 + outer loop + vertex -677.014 155.821 84.9035 + vertex -677.35 155.354 83.0386 + vertex -675.978 153.896 84.5167 + endloop + endfacet + facet normal -0.828201 -0.49741 0.2582 + outer loop + vertex -675.807 154.528 86.2826 + vertex -677.014 155.821 84.9035 + vertex -675.978 153.896 84.5167 + endloop + endfacet + facet normal -0.811681 -0.50792 0.288429 + outer loop + vertex -676.431 153.602 82.6233 + vertex -676.63 152.893 80.8158 + vertex -675.56 152.488 83.1148 + endloop + endfacet + facet normal -0.817303 -0.512856 0.262667 + outer loop + vertex -675.807 154.528 86.2826 + vertex -675.978 153.896 84.5167 + vertex -675.074 153.475 86.5079 + endloop + endfacet + facet normal -0.82931 -0.492725 0.263565 + outer loop + vertex -676.722 156.333 86.7793 + vertex -677.014 155.821 84.9035 + vertex -675.807 154.528 86.2826 + endloop + endfacet + facet normal -0.847456 -0.477092 0.232811 + outer loop + vertex -676.122 158.181 92.4232 + vertex -676.308 157.594 90.5408 + vertex -674.931 155.847 91.9733 + endloop + endfacet + facet normal -0.826111 -0.507258 0.245417 + outer loop + vertex -675.284 155.515 90.0084 + vertex -675.407 154.828 88.1727 + vertex -674.524 154.262 89.9784 + endloop + endfacet + facet normal -0.853117 -0.476191 0.213153 + outer loop + vertex -674.847 156.536 93.8485 + vertex -676.122 158.181 92.4232 + vertex -674.931 155.847 91.9733 + endloop + endfacet + facet normal -0.853617 -0.473886 0.216261 + outer loop + vertex -675.924 158.674 94.2861 + vertex -676.122 158.181 92.4232 + vertex -674.847 156.536 93.8485 + endloop + endfacet + facet normal -0.858969 -0.474793 0.191685 + outer loop + vertex -675.396 160.044 99.8245 + vertex -675.559 159.588 97.9647 + vertex -674.185 157.721 99.4954 + endloop + endfacet + facet normal -0.83357 -0.512905 0.205158 + outer loop + vertex -674.47 157.442 97.5731 + vertex -674.526 156.816 95.7807 + vertex -673.658 156.281 97.967 + endloop + endfacet + facet normal -0.861813 -0.474509 0.179217 + outer loop + vertex -674.172 158.375 101.29 + vertex -675.396 160.044 99.8245 + vertex -674.185 157.721 99.4954 + endloop + endfacet + facet normal -0.862658 -0.471295 0.183581 + outer loop + vertex -675.253 160.516 101.707 + vertex -675.396 160.044 99.8245 + vertex -674.172 158.375 101.29 + endloop + endfacet + facet normal -0.866564 -0.472527 0.160581 + outer loop + vertex -674.883 161.887 107.442 + vertex -675.003 161.455 105.525 + vertex -673.693 159.58 107.073 + endloop + endfacet + facet normal -0.869352 -0.471803 0.147071 + outer loop + vertex -673.718 160.198 108.91 + vertex -674.883 161.887 107.442 + vertex -673.693 159.58 107.073 + endloop + endfacet + facet normal -0.870658 -0.467448 0.153123 + outer loop + vertex -674.786 162.33 109.345 + vertex -674.883 161.887 107.442 + vertex -673.718 160.198 108.91 + endloop + endfacet + facet normal -0.871292 -0.467187 0.150287 + outer loop + vertex -673.499 160.417 110.86 + vertex -674.786 162.33 109.345 + vertex -673.718 160.198 108.91 + endloop + endfacet + facet normal -0.847208 -0.508963 0.152299 + outer loop + vertex -673.718 160.198 108.91 + vertex -672.934 159.011 109.303 + vertex -673.499 160.417 110.86 + endloop + endfacet + facet normal -0.870456 -0.470145 0.145843 + outer loop + vertex -674.693 162.746 111.242 + vertex -674.786 162.33 109.345 + vertex -673.499 160.417 110.86 + endloop + endfacet + facet normal -0.872432 -0.469503 0.135753 + outer loop + vertex -673.539 161.019 112.681 + vertex -674.693 162.746 111.242 + vertex -673.499 160.417 110.86 + endloop + endfacet + facet normal -0.85015 -0.505293 0.148068 + outer loop + vertex -673.539 161.019 112.681 + vertex -673.499 160.417 110.86 + vertex -672.779 159.832 112.996 + endloop + endfacet + facet normal -0.850205 -0.506941 0.141992 + outer loop + vertex -673.539 161.019 112.681 + vertex -672.779 159.832 112.996 + vertex -673.348 161.247 114.643 + endloop + endfacet + facet normal -0.873307 -0.466749 0.139569 + outer loop + vertex -673.348 161.247 114.643 + vertex -674.616 163.169 113.136 + vertex -673.539 161.019 112.681 + endloop + endfacet + facet normal -0.872223 -0.470392 0.134009 + outer loop + vertex -674.541 163.571 115.034 + vertex -674.616 163.169 113.136 + vertex -673.348 161.247 114.643 + endloop + endfacet + facet normal -0.873975 -0.469715 0.124641 + outer loop + vertex -673.406 161.843 116.481 + vertex -674.541 163.571 115.034 + vertex -673.348 161.247 114.643 + endloop + endfacet + facet normal -0.851287 -0.50643 0.13726 + outer loop + vertex -673.406 161.843 116.481 + vertex -673.348 161.247 114.643 + vertex -672.578 160.564 116.896 + endloop + endfacet + facet normal -0.850995 -0.509644 0.126769 + outer loop + vertex -673.406 161.843 116.481 + vertex -672.578 160.564 116.896 + vertex -673.208 161.999 118.438 + endloop + endfacet + facet normal -0.874964 -0.46755 0.125835 + outer loop + vertex -673.208 161.999 118.438 + vertex -674.476 163.964 116.923 + vertex -673.406 161.843 116.481 + endloop + endfacet + facet normal -0.874049 -0.470449 0.121308 + outer loop + vertex -674.409 164.324 118.803 + vertex -674.476 163.964 116.923 + vertex -673.208 161.999 118.438 + endloop + endfacet + facet normal -0.875731 -0.469764 0.111433 + outer loop + vertex -673.272 162.548 120.248 + vertex -674.409 164.324 118.803 + vertex -673.208 161.999 118.438 + endloop + endfacet + facet normal -0.85366 -0.506045 0.123218 + outer loop + vertex -673.272 162.548 120.248 + vertex -673.208 161.999 118.438 + vertex -672.512 161.363 120.647 + endloop + endfacet + facet normal -0.853426 -0.507743 0.117734 + outer loop + vertex -673.272 162.548 120.248 + vertex -672.512 161.363 120.647 + vertex -673.097 162.705 122.193 + endloop + endfacet + facet normal -0.87742 -0.465369 0.116474 + outer loop + vertex -673.097 162.705 122.193 + vertex -674.352 164.692 120.678 + vertex -673.272 162.548 120.248 + endloop + endfacet + facet normal -0.8763 -0.468791 0.111056 + outer loop + vertex -674.294 165.031 122.57 + vertex -674.352 164.692 120.678 + vertex -673.097 162.705 122.193 + endloop + endfacet + facet normal -0.877505 -0.468219 0.103709 + outer loop + vertex -673.185 163.277 124.029 + vertex -674.294 165.031 122.57 + vertex -673.097 162.705 122.193 + endloop + endfacet + facet normal -0.855698 -0.504309 0.115987 + outer loop + vertex -673.185 163.277 124.029 + vertex -673.097 162.705 122.193 + vertex -672.424 162.059 124.35 + endloop + endfacet + facet normal -0.85558 -0.506016 0.109228 + outer loop + vertex -673.185 163.277 124.029 + vertex -672.424 162.059 124.35 + vertex -673.016 163.427 126.046 + endloop + endfacet + facet normal -0.878293 -0.465735 0.108134 + outer loop + vertex -673.016 163.427 126.046 + vertex -674.253 165.397 124.491 + vertex -673.185 163.277 124.029 + endloop + endfacet + facet normal -0.877353 -0.468453 0.103941 + outer loop + vertex -674.222 165.772 126.439 + vertex -674.253 165.397 124.491 + vertex -673.016 163.427 126.046 + endloop + endfacet + facet normal -0.878671 -0.467745 0.0956624 + outer loop + vertex -673.118 164.005 127.946 + vertex -674.222 165.772 126.439 + vertex -673.016 163.427 126.046 + endloop + endfacet + facet normal -0.855494 -0.50629 0.108633 + outer loop + vertex -673.118 164.005 127.946 + vertex -673.016 163.427 126.046 + vertex -672.305 162.701 128.266 + endloop + endfacet + facet normal -0.855297 -0.508818 0.0978338 + outer loop + vertex -673.118 164.005 127.946 + vertex -672.305 162.701 128.266 + vertex -672.935 164.096 130.011 + endloop + endfacet + facet normal -0.879487 -0.465706 0.0980857 + outer loop + vertex -672.935 164.096 130.011 + vertex -674.177 166.101 128.396 + vertex -673.118 164.005 127.946 + endloop + endfacet + facet normal -0.878515 -0.468369 0.0940304 + outer loop + vertex -674.114 166.378 130.365 + vertex -674.177 166.101 128.396 + vertex -672.935 164.096 130.011 + endloop + endfacet + facet normal -0.879917 -0.467585 0.0843232 + outer loop + vertex -672.994 164.562 131.98 + vertex -674.114 166.378 130.365 + vertex -672.935 164.096 130.011 + endloop + endfacet + facet normal -0.857591 -0.505666 0.0940216 + outer loop + vertex -672.994 164.562 131.98 + vertex -672.935 164.096 130.011 + vertex -672.215 163.316 132.381 + endloop + endfacet + facet normal -0.857138 -0.507737 0.0867051 + outer loop + vertex -672.994 164.562 131.98 + vertex -672.215 163.316 132.381 + vertex -672.761 164.563 134.287 + endloop + endfacet + facet normal -0.879853 -0.466839 0.0889964 + outer loop + vertex -672.761 164.563 134.287 + vertex -674.03 166.602 132.444 + vertex -672.994 164.562 131.98 + endloop + endfacet + facet normal -0.878864 -0.46934 0.0855503 + outer loop + vertex -674.026 167.023 134.797 + vertex -674.03 166.602 132.444 + vertex -672.761 164.563 134.287 + endloop + endfacet + facet normal -0.879615 -0.46876 0.0808832 + outer loop + vertex -672.773 165.075 137.133 + vertex -674.026 167.023 134.797 + vertex -672.761 164.563 134.287 + endloop + endfacet + facet normal -0.85746 -0.506994 0.0878551 + outer loop + vertex -672.773 165.075 137.133 + vertex -672.761 164.563 134.287 + vertex -671.955 163.563 136.388 + endloop + endfacet + facet normal -0.883537 -0.459493 0.0907139 + outer loop + vertex -674.377 168.217 137.426 + vertex -674.026 167.023 134.797 + vertex -672.773 165.075 137.133 + endloop + endfacet + facet normal -0.884847 -0.459091 0.0792492 + outer loop + vertex -672.773 165.075 137.133 + vertex -673.066 166.146 140.061 + vertex -674.377 168.217 137.426 + endloop + endfacet + facet normal -0.89325 -0.438357 0.0997323 + outer loop + vertex -673.066 166.146 140.061 + vertex -675.497 171.208 140.541 + vertex -674.377 168.217 137.426 + endloop + endfacet + facet normal -0.902939 -0.42213 0.0806684 + outer loop + vertex -676.387 172.439 137.019 + vertex -674.377 168.217 137.426 + vertex -675.497 171.208 140.541 + endloop + endfacet + facet normal -0.902617 -0.421197 0.0887442 + outer loop + vertex -676.387 172.439 137.019 + vertex -675.82 170.766 134.845 + vertex -674.377 168.217 137.426 + endloop + endfacet + facet normal -0.898749 -0.431808 0.0761087 + outer loop + vertex -674.377 168.217 137.426 + vertex -675.82 170.766 134.845 + vertex -674.026 167.023 134.797 + endloop + endfacet + facet normal -0.898482 -0.431725 0.079648 + outer loop + vertex -675.82 170.766 134.845 + vertex -675.684 170.074 132.63 + vertex -674.026 167.023 134.797 + endloop + endfacet + facet normal -0.898337 -0.432159 0.0789256 + outer loop + vertex -674.026 167.023 134.797 + vertex -675.684 170.074 132.63 + vertex -674.03 166.602 132.444 + endloop + endfacet + facet normal -0.898067 -0.432185 0.0818001 + outer loop + vertex -675.684 170.074 132.63 + vertex -675.739 169.795 130.555 + vertex -674.03 166.602 132.444 + endloop + endfacet + facet normal -0.898241 -0.431606 0.0829369 + outer loop + vertex -674.03 166.602 132.444 + vertex -675.739 169.795 130.555 + vertex -674.114 166.378 130.365 + endloop + endfacet + facet normal -0.897709 -0.43165 0.0882952 + outer loop + vertex -675.739 169.795 130.555 + vertex -675.817 169.557 128.59 + vertex -674.114 166.378 130.365 + endloop + endfacet + facet normal -0.89786 -0.431106 0.0894147 + outer loop + vertex -674.114 166.378 130.365 + vertex -675.817 169.557 128.59 + vertex -674.177 166.101 128.396 + endloop + endfacet + facet normal -0.89744 -0.431131 0.0934239 + outer loop + vertex -675.817 169.557 128.59 + vertex -675.878 169.263 126.652 + vertex -674.177 166.101 128.396 + endloop + endfacet + facet normal -0.897404 -0.431266 0.0931439 + outer loop + vertex -674.177 166.101 128.396 + vertex -675.878 169.263 126.652 + vertex -674.222 165.772 126.439 + endloop + endfacet + facet normal -0.8967 -0.431318 0.099464 + outer loop + vertex -675.878 169.263 126.652 + vertex -675.913 168.889 124.717 + vertex -674.222 165.772 126.439 + endloop + endfacet + facet normal -0.896431 -0.432371 0.0972927 + outer loop + vertex -674.222 165.772 126.439 + vertex -675.913 168.889 124.717 + vertex -674.253 165.397 124.491 + endloop + endfacet + facet normal -0.896138 -0.432397 0.0998448 + outer loop + vertex -675.913 168.889 124.717 + vertex -675.958 168.54 122.799 + vertex -674.253 165.397 124.491 + endloop + endfacet + facet normal -0.896318 -0.431665 0.101386 + outer loop + vertex -674.253 165.397 124.491 + vertex -675.958 168.54 122.799 + vertex -674.294 165.031 122.57 + endloop + endfacet + facet normal -0.89557 -0.431715 0.107599 + outer loop + vertex -675.958 168.54 122.799 + vertex -676.007 168.172 120.91 + vertex -674.294 165.031 122.57 + endloop + endfacet + facet normal -0.895311 -0.432839 0.105205 + outer loop + vertex -674.294 165.031 122.57 + vertex -676.007 168.172 120.91 + vertex -674.352 164.692 120.678 + endloop + endfacet + facet normal -0.894504 -0.432887 0.111681 + outer loop + vertex -676.007 168.172 120.91 + vertex -676.068 167.815 119.038 + vertex -674.352 164.692 120.678 + endloop + endfacet + facet normal -0.894526 -0.432784 0.111899 + outer loop + vertex -674.352 164.692 120.678 + vertex -676.068 167.815 119.038 + vertex -674.409 164.324 118.803 + endloop + endfacet + facet normal -0.893889 -0.43281 0.116786 + outer loop + vertex -676.068 167.815 119.038 + vertex -676.134 167.445 117.164 + vertex -674.409 164.324 118.803 + endloop + endfacet + facet normal -0.893708 -0.433671 0.114958 + outer loop + vertex -674.409 164.324 118.803 + vertex -676.134 167.445 117.164 + vertex -674.476 163.964 116.923 + endloop + endfacet + facet normal -0.892787 -0.433704 0.121789 + outer loop + vertex -676.134 167.445 117.164 + vertex -676.201 167.054 115.28 + vertex -674.476 163.964 116.923 + endloop + endfacet + facet normal -0.892724 -0.434017 0.121134 + outer loop + vertex -674.476 163.964 116.923 + vertex -676.201 167.054 115.28 + vertex -674.541 163.571 115.034 + endloop + endfacet + facet normal -0.891763 -0.434041 0.127937 + outer loop + vertex -676.201 167.054 115.28 + vertex -676.272 166.642 113.388 + vertex -674.541 163.571 115.034 + endloop + endfacet + facet normal -0.89169 -0.434421 0.127151 + outer loop + vertex -674.541 163.571 115.034 + vertex -676.272 166.642 113.388 + vertex -674.616 163.169 113.136 + endloop + endfacet + facet normal -0.890808 -0.434434 0.133148 + outer loop + vertex -676.272 166.642 113.388 + vertex -676.351 166.223 111.49 + vertex -674.616 163.169 113.136 + endloop + endfacet + facet normal -0.890814 -0.434401 0.133216 + outer loop + vertex -674.616 163.169 113.136 + vertex -676.351 166.223 111.49 + vertex -674.693 162.746 111.242 + endloop + endfacet + facet normal -0.889809 -0.434392 0.139797 + outer loop + vertex -676.351 166.223 111.49 + vertex -676.443 165.798 109.588 + vertex -674.693 162.746 111.242 + endloop + endfacet + facet normal -0.889744 -0.434771 0.139029 + outer loop + vertex -674.693 162.746 111.242 + vertex -676.443 165.798 109.588 + vertex -674.786 162.33 109.345 + endloop + endfacet + facet normal -0.888347 -0.434721 0.147843 + outer loop + vertex -676.443 165.798 109.588 + vertex -676.544 165.356 107.681 + vertex -674.786 162.33 109.345 + endloop + endfacet + facet normal -0.888243 -0.43537 0.146552 + outer loop + vertex -674.786 162.33 109.345 + vertex -676.544 165.356 107.681 + vertex -674.883 161.887 107.442 + endloop + endfacet + facet normal -0.886664 -0.435271 0.156097 + outer loop + vertex -676.544 165.356 107.681 + vertex -676.657 164.901 105.768 + vertex -674.883 161.887 107.442 + endloop + endfacet + facet normal -0.886481 -0.436495 0.153699 + outer loop + vertex -674.883 161.887 107.442 + vertex -676.657 164.901 105.768 + vertex -675.003 161.455 105.525 + endloop + endfacet + facet normal -0.88493 -0.436385 0.162686 + outer loop + vertex -676.657 164.901 105.768 + vertex -676.783 164.443 103.856 + vertex -675.003 161.455 105.525 + endloop + endfacet + facet normal -0.88483 -0.437104 0.161292 + outer loop + vertex -675.003 161.455 105.525 + vertex -676.783 164.443 103.856 + vertex -675.124 160.995 103.611 + endloop + endfacet + facet normal -0.883119 -0.436957 0.170793 + outer loop + vertex -676.783 164.443 103.856 + vertex -676.917 163.972 101.954 + vertex -675.124 160.995 103.611 + endloop + endfacet + facet normal -0.883055 -0.437475 0.169794 + outer loop + vertex -675.124 160.995 103.611 + vertex -676.917 163.972 101.954 + vertex -675.253 160.516 101.707 + endloop + endfacet + facet normal -0.881568 -0.437325 0.177719 + outer loop + vertex -676.917 163.972 101.954 + vertex -677.067 163.506 100.067 + vertex -675.253 160.516 101.707 + endloop + endfacet + facet normal -0.88151 -0.437878 0.176645 + outer loop + vertex -675.253 160.516 101.707 + vertex -677.067 163.506 100.067 + vertex -675.396 160.044 99.8245 + endloop + endfacet + facet normal -0.879671 -0.437654 0.186111 + outer loop + vertex -677.067 163.506 100.067 + vertex -677.231 163.042 98.1994 + vertex -675.396 160.044 99.8245 + endloop + endfacet + facet normal -0.879601 -0.438447 0.184569 + outer loop + vertex -675.396 160.044 99.8245 + vertex -677.231 163.042 98.1994 + vertex -675.559 159.588 97.9647 + endloop + endfacet + facet normal -0.87797 -0.43821 0.192719 + outer loop + vertex -677.231 163.042 98.1994 + vertex -677.415 162.598 96.3498 + vertex -675.559 159.588 97.9647 + endloop + endfacet + facet normal -0.877966 -0.438267 0.19261 + outer loop + vertex -675.559 159.588 97.9647 + vertex -677.415 162.598 96.3498 + vertex -675.73 159.122 96.124 + endloop + endfacet + facet normal -0.876232 -0.437971 0.200997 + outer loop + vertex -677.415 162.598 96.3498 + vertex -677.608 162.141 94.5134 + vertex -675.73 159.122 96.124 + endloop + endfacet + facet normal -0.876182 -0.438839 0.199312 + outer loop + vertex -675.73 159.122 96.124 + vertex -677.608 162.141 94.5134 + vertex -675.924 158.674 94.2861 + endloop + endfacet + facet normal -0.873425 -0.438338 0.212106 + outer loop + vertex -677.608 162.141 94.5134 + vertex -677.798 161.625 92.6663 + vertex -675.924 158.674 94.2861 + endloop + endfacet + facet normal -0.873352 -0.439807 0.209347 + outer loop + vertex -675.924 158.674 94.2861 + vertex -677.798 161.625 92.6663 + vertex -676.122 158.181 92.4232 + endloop + endfacet + facet normal -0.869185 -0.439059 0.227474 + outer loop + vertex -677.798 161.625 92.6663 + vertex -677.987 161.014 90.7626 + vertex -676.122 158.181 92.4232 + endloop + endfacet + facet normal -0.869081 -0.44118 0.223739 + outer loop + vertex -676.122 158.181 92.4232 + vertex -677.987 161.014 90.7626 + vertex -676.308 157.594 90.5408 + endloop + endfacet + facet normal -0.861383 -0.439416 0.254821 + outer loop + vertex -677.987 161.014 90.7626 + vertex -678.082 160.112 88.8859 + vertex -676.308 157.594 90.5408 + endloop + endfacet + facet normal -0.860845 -0.448441 0.240513 + outer loop + vertex -676.308 157.594 90.5408 + vertex -678.082 160.112 88.8859 + vertex -676.485 156.926 88.6631 + endloop + endfacet + facet normal -0.853065 -0.446594 0.269877 + outer loop + vertex -678.082 160.112 88.8859 + vertex -678.176 159.184 87.0532 + vertex -676.485 156.926 88.6631 + endloop + endfacet + facet normal -0.8521 -0.459051 0.25139 + outer loop + vertex -676.485 156.926 88.6631 + vertex -678.176 159.184 87.0532 + vertex -676.722 156.333 86.7793 + endloop + endfacet + facet normal -0.847316 -0.458249 0.268448 + outer loop + vertex -678.176 159.184 87.0532 + vertex -678.409 158.521 85.1882 + vertex -676.722 156.333 86.7793 + endloop + endfacet + facet normal -0.84673 -0.464901 0.258681 + outer loop + vertex -676.722 156.333 86.7793 + vertex -678.409 158.521 85.1882 + vertex -677.014 155.821 84.9035 + endloop + endfacet + facet normal -0.842324 -0.464223 0.273837 + outer loop + vertex -678.409 158.521 85.1882 + vertex -678.732 157.997 83.3072 + vertex -677.014 155.821 84.9035 + endloop + endfacet + facet normal -0.842046 -0.467519 0.269044 + outer loop + vertex -677.014 155.821 84.9035 + vertex -678.732 157.997 83.3072 + vertex -677.35 155.354 83.0386 + endloop + endfacet + facet normal -0.837515 -0.466691 0.284196 + outer loop + vertex -678.732 157.997 83.3072 + vertex -679.097 157.519 81.445 + vertex -677.35 155.354 83.0386 + endloop + endfacet + facet normal -0.837431 -0.467864 0.28251 + outer loop + vertex -677.35 155.354 83.0386 + vertex -679.097 157.519 81.445 + vertex -677.699 154.863 81.1896 + endloop + endfacet + facet normal -0.832549 -0.466809 0.298247 + outer loop + vertex -679.097 157.519 81.445 + vertex -679.482 157.034 79.6115 + vertex -677.699 154.863 81.1896 + endloop + endfacet + facet normal -0.832478 -0.468227 0.296216 + outer loop + vertex -677.699 154.863 81.1896 + vertex -679.482 157.034 79.6115 + vertex -678.071 154.358 79.3471 + endloop + endfacet + facet normal -0.827476 -0.46711 0.311595 + outer loop + vertex -679.482 157.034 79.6115 + vertex -679.88 156.529 77.7985 + vertex -678.071 154.358 79.3471 + endloop + endfacet + facet normal -0.82743 -0.468799 0.309172 + outer loop + vertex -678.071 154.358 79.3471 + vertex -679.88 156.529 77.7985 + vertex -678.466 153.84 77.5045 + endloop + endfacet + facet normal -0.821405 -0.467543 0.326646 + outer loop + vertex -679.88 156.529 77.7985 + vertex -680.306 156.015 75.99 + vertex -678.466 153.84 77.5045 + endloop + endfacet + facet normal -0.821403 -0.469304 0.324115 + outer loop + vertex -678.466 153.84 77.5045 + vertex -680.306 156.015 75.99 + vertex -678.895 153.32 75.6643 + endloop + endfacet + facet normal -0.815171 -0.468099 0.341145 + outer loop + vertex -680.306 156.015 75.99 + vertex -680.779 155.508 74.1649 + vertex -678.895 153.32 75.6643 + endloop + endfacet + facet normal -0.815192 -0.469011 0.33984 + outer loop + vertex -678.895 153.32 75.6643 + vertex -680.779 155.508 74.1649 + vertex -679.365 152.798 73.8163 + endloop + endfacet + facet normal -0.808422 -0.467729 0.357327 + outer loop + vertex -680.779 155.508 74.1649 + vertex -681.31 155.005 72.3059 + vertex -679.365 152.798 73.8163 + endloop + endfacet + facet normal -0.808432 -0.467962 0.357001 + outer loop + vertex -679.365 152.798 73.8163 + vertex -681.31 155.005 72.3059 + vertex -679.887 152.275 71.9502 + endloop + endfacet + facet normal -0.800942 -0.466453 0.375386 + outer loop + vertex -681.31 155.005 72.3059 + vertex -681.898 154.495 70.4172 + vertex -679.887 152.275 71.9502 + endloop + endfacet + facet normal -0.801006 -0.467567 0.373858 + outer loop + vertex -679.887 152.275 71.9502 + vertex -681.898 154.495 70.4172 + vertex -680.472 151.769 70.0629 + endloop + endfacet + facet normal -0.792296 -0.46566 0.394242 + outer loop + vertex -681.898 154.495 70.4172 + vertex -682.543 153.988 68.5215 + vertex -680.472 151.769 70.0629 + endloop + endfacet + facet normal -0.792412 -0.467197 0.392186 + outer loop + vertex -680.472 151.769 70.0629 + vertex -682.543 153.988 68.5215 + vertex -681.108 151.263 68.1754 + endloop + endfacet + facet normal -0.783648 -0.465075 0.411825 + outer loop + vertex -682.543 153.988 68.5215 + vertex -683.238 153.514 66.664 + vertex -681.108 151.263 68.1754 + endloop + endfacet + facet normal -0.783855 -0.46701 0.409235 + outer loop + vertex -681.108 151.263 68.1754 + vertex -683.238 153.514 66.664 + vertex -681.784 150.781 66.3295 + endloop + endfacet + facet normal -0.773928 -0.464345 0.430603 + outer loop + vertex -683.238 153.514 66.664 + vertex -683.956 153.067 64.8906 + vertex -681.784 150.781 66.3295 + endloop + endfacet + facet normal -0.77435 -0.467126 0.426821 + outer loop + vertex -681.784 150.781 66.3295 + vertex -683.956 153.067 64.8906 + vertex -682.488 150.328 64.5565 + endloop + endfacet + facet normal -0.763766 -0.464112 0.448622 + outer loop + vertex -683.956 153.067 64.8906 + vertex -684.689 152.654 63.2155 + vertex -682.488 150.328 64.5565 + endloop + endfacet + facet normal -0.764202 -0.466215 0.44569 + outer loop + vertex -682.488 150.328 64.5565 + vertex -684.689 152.654 63.2155 + vertex -683.202 149.881 62.8643 + endloop + endfacet + facet normal -0.752521 -0.462839 0.4685 + outer loop + vertex -684.689 152.654 63.2155 + vertex -685.451 152.27 61.6129 + vertex -683.202 149.881 62.8643 + endloop + endfacet + facet normal -0.753116 -0.465052 0.465342 + outer loop + vertex -683.202 149.881 62.8643 + vertex -685.451 152.27 61.6129 + vertex -683.95 149.462 61.2351 + endloop + endfacet + facet normal -0.739394 -0.461116 0.490581 + outer loop + vertex -685.451 152.27 61.6129 + vertex -686.259 151.887 60.035 + vertex -683.95 149.462 61.2351 + endloop + endfacet + facet normal -0.740317 -0.46407 0.486384 + outer loop + vertex -683.95 149.462 61.2351 + vertex -686.259 151.887 60.035 + vertex -684.75 149.048 59.622 + endloop + endfacet + facet normal -0.726302 -0.46015 0.510635 + outer loop + vertex -686.259 151.887 60.035 + vertex -687.152 151.529 58.4413 + vertex -684.75 149.048 59.622 + endloop + endfacet + facet normal -0.726552 -0.460872 0.509626 + outer loop + vertex -684.75 149.048 59.622 + vertex -687.152 151.529 58.4413 + vertex -685.638 148.65 57.9976 + endloop + endfacet + facet normal -0.712736 -0.457062 0.532073 + outer loop + vertex -687.152 151.529 58.4413 + vertex -688.138 151.194 56.8333 + vertex -685.638 148.65 57.9976 + endloop + endfacet + facet normal -0.713026 -0.457826 0.531027 + outer loop + vertex -685.638 148.65 57.9976 + vertex -688.138 151.194 56.8333 + vertex -686.622 148.291 56.3665 + endloop + endfacet + facet normal -0.698035 -0.453689 0.553997 + outer loop + vertex -688.138 151.194 56.8333 + vertex -689.207 150.902 55.2474 + vertex -686.622 148.291 56.3665 + endloop + endfacet + facet normal -0.698138 -0.453933 0.553668 + outer loop + vertex -686.622 148.291 56.3665 + vertex -689.207 150.902 55.2474 + vertex -687.706 147.992 54.7542 + endloop + endfacet + facet normal -0.682113 -0.449574 0.576719 + outer loop + vertex -689.207 150.902 55.2474 + vertex -690.354 150.701 53.7342 + vertex -687.706 147.992 54.7542 + endloop + endfacet + facet normal -0.681363 -0.448066 0.578776 + outer loop + vertex -687.706 147.992 54.7542 + vertex -690.354 150.701 53.7342 + vertex -688.881 147.753 53.1865 + endloop + endfacet + facet normal -0.661987 -0.443157 0.604471 + outer loop + vertex -690.354 150.701 53.7342 + vertex -691.545 150.553 52.3211 + vertex -688.881 147.753 53.1865 + endloop + endfacet + facet normal -0.661543 -0.442417 0.605498 + outer loop + vertex -688.881 147.753 53.1865 + vertex -691.545 150.553 52.3211 + vertex -690.094 147.516 51.6872 + endloop + endfacet + facet normal -0.637801 -0.437063 0.634181 + outer loop + vertex -691.545 150.553 52.3211 + vertex -692.708 150.34 51.0049 + vertex -690.094 147.516 51.6872 + endloop + endfacet + facet normal -0.639452 -0.43938 0.630909 + outer loop + vertex -690.094 147.516 51.6872 + vertex -692.708 150.34 51.0049 + vertex -691.236 147.087 50.2311 + endloop + endfacet + facet normal -0.606447 -0.433006 0.666879 + outer loop + vertex -692.708 150.34 51.0049 + vertex -693.725 149.874 49.7776 + vertex -691.236 147.087 50.2311 + endloop + endfacet + facet normal -0.601744 -0.427548 0.674617 + outer loop + vertex -691.236 147.087 50.2311 + vertex -693.725 149.874 49.7776 + vertex -692.288 147.383 49.4808 + endloop + endfacet + facet normal -0.603492 -0.428312 0.672567 + outer loop + vertex -692.288 147.383 49.4808 + vertex -693.725 149.874 49.7776 + vertex -692.942 147.45 48.9359 + endloop + endfacet + facet normal -0.589767 -0.428113 0.684758 + outer loop + vertex -693.725 149.874 49.7776 + vertex -694.895 149.951 48.8176 + vertex -692.942 147.45 48.9359 + endloop + endfacet + facet normal -0.598714 -0.435699 0.672092 + outer loop + vertex -693.357 147.022 48.2894 + vertex -692.942 147.45 48.9359 + vertex -694.895 149.951 48.8176 + endloop + endfacet + facet normal -0.577811 -0.428757 0.69448 + outer loop + vertex -693.357 147.022 48.2894 + vertex -694.895 149.951 48.8176 + vertex -694.197 147.535 47.9074 + endloop + endfacet + facet normal -0.576073 -0.42879 0.695902 + outer loop + vertex -694.895 149.951 48.8176 + vertex -695.915 150.52 48.3243 + vertex -694.197 147.535 47.9074 + endloop + endfacet + facet normal -0.576714 -0.429062 0.695203 + outer loop + vertex -694.747 147.61 47.4968 + vertex -694.197 147.535 47.9074 + vertex -695.915 150.52 48.3243 + endloop + endfacet + facet normal -0.5683 -0.427855 0.702833 + outer loop + vertex -695.915 150.52 48.3243 + vertex -696.265 150.51 48.0351 + vertex -694.747 147.61 47.4968 + endloop + endfacet + facet normal -0.593283 -0.436072 0.676651 + outer loop + vertex -694.747 147.61 47.4968 + vertex -696.265 150.51 48.0351 + vertex -694.906 147.38 47.2095 + endloop + endfacet + facet normal -0.582505 -0.434163 0.687161 + outer loop + vertex -696.265 150.51 48.0351 + vertex -696.313 150.326 47.8782 + vertex -694.906 147.38 47.2095 + endloop + endfacet + facet normal -0.586687 -0.435201 0.682934 + outer loop + vertex -694.906 147.38 47.2095 + vertex -696.313 150.326 47.8782 + vertex -694.93 147.167 47.0534 + endloop + endfacet + facet normal -0.815085 -0.451611 0.362884 + outer loop + vertex -696.313 150.326 47.8782 + vertex -696.288 150.229 47.8139 + vertex -694.93 147.167 47.0534 + endloop + endfacet + facet normal -0.590573 -0.431323 0.682044 + outer loop + vertex -694.93 147.167 47.0534 + vertex -696.288 150.229 47.8139 + vertex -694.956 147.106 46.9923 + endloop + endfacet + facet normal -0.92444 -0.367841 -0.100521 + outer loop + vertex -696.288 150.229 47.8139 + vertex -696.325 150.325 47.805 + vertex -694.956 147.106 46.9923 + endloop + endfacet + facet normal -0.649446 -0.433904 0.624458 + outer loop + vertex -694.956 147.106 46.9923 + vertex -696.325 150.325 47.805 + vertex -695.018 147.182 46.9805 + endloop + endfacet + facet normal -0.760946 -0.441249 0.475669 + outer loop + vertex -696.325 150.325 47.805 + vertex -696.432 150.512 47.808 + vertex -695.018 147.182 46.9805 + endloop + endfacet + facet normal -0.598836 -0.423181 0.679937 + outer loop + vertex -695.018 147.182 46.9805 + vertex -696.432 150.512 47.808 + vertex -695.104 147.265 46.9565 + endloop + endfacet + facet normal -0.605597 -0.4242 0.67328 + outer loop + vertex -696.432 150.512 47.808 + vertex -696.47 150.441 47.7288 + vertex -695.104 147.265 46.9565 + endloop + endfacet + facet normal -0.681995 -0.436103 0.587109 + outer loop + vertex -695.104 147.265 46.9565 + vertex -696.47 150.441 47.7288 + vertex -695.051 146.995 46.8169 + endloop + endfacet + facet normal -0.54533 -0.41692 0.727181 + outer loop + vertex -696.47 150.441 47.7288 + vertex -696.175 149.508 47.415 + vertex -695.051 146.995 46.8169 + endloop + endfacet + facet normal -0.826953 -0.44998 0.337146 + outer loop + vertex -695.051 146.995 46.8169 + vertex -696.175 149.508 47.415 + vertex -694.6 145.883 46.4394 + endloop + endfacet + facet normal -0.89701 -0.436997 0.0663832 + outer loop + vertex -673.28 167.123 143.594 + vertex -675.497 171.208 140.541 + vertex -673.066 166.146 140.061 + endloop + endfacet + facet normal -0.897767 -0.43492 0.069712 + outer loop + vertex -675.514 171.944 144.904 + vertex -675.497 171.208 140.541 + vertex -673.28 167.123 143.594 + endloop + endfacet + facet normal -0.899669 -0.432675 0.0582025 + outer loop + vertex -673.064 167.247 147.856 + vertex -675.514 171.944 144.904 + vertex -673.28 167.123 143.594 + endloop + endfacet + facet normal -0.898862 -0.43489 0.0540091 + outer loop + vertex -675.491 172.39 148.884 + vertex -675.514 171.944 144.904 + vertex -673.064 167.247 147.856 + endloop + endfacet + facet normal -0.900329 -0.433179 0.0419857 + outer loop + vertex -673.231 167.968 151.714 + vertex -675.491 172.39 148.884 + vertex -673.064 167.247 147.856 + endloop + endfacet + facet normal -0.900557 -0.432598 0.0430747 + outer loop + vertex -675.468 172.724 152.721 + vertex -675.491 172.39 148.884 + vertex -673.231 167.968 151.714 + endloop + endfacet + facet normal -0.901084 -0.431916 0.0386807 + outer loop + vertex -673.192 168.216 155.415 + vertex -675.468 172.724 152.721 + vertex -673.231 167.968 151.714 + endloop + endfacet + facet normal -0.900784 -0.432675 0.0371578 + outer loop + vertex -675.402 172.917 156.579 + vertex -675.468 172.724 152.721 + vertex -673.192 168.216 155.415 + endloop + endfacet + facet normal -0.901127 -0.432179 0.0345042 + outer loop + vertex -672.93 167.983 159.334 + vertex -675.402 172.917 156.579 + vertex -673.192 168.216 155.415 + endloop + endfacet + facet normal -0.899957 -0.435058 0.0282979 + outer loop + vertex -675.382 173.129 160.462 + vertex -675.402 172.917 156.579 + vertex -672.93 167.983 159.334 + endloop + endfacet + facet normal -0.901076 -0.433295 0.0178236 + outer loop + vertex -673.157 168.617 163.262 + vertex -675.382 173.129 160.462 + vertex -672.93 167.983 159.334 + endloop + endfacet + facet normal -0.901397 -0.432566 0.0192539 + outer loop + vertex -675.402 173.343 164.336 + vertex -675.382 173.129 160.462 + vertex -673.157 168.617 163.262 + endloop + endfacet + facet normal -0.901959 -0.4316 0.0138307 + outer loop + vertex -673.144 168.713 167.113 + vertex -675.402 173.343 164.336 + vertex -673.157 168.617 163.262 + endloop + endfacet + facet normal -0.901811 -0.431931 0.01316 + outer loop + vertex -675.356 173.368 168.275 + vertex -675.402 173.343 164.336 + vertex -673.144 168.713 167.113 + endloop + endfacet + facet normal -0.90209 -0.431418 0.0105754 + outer loop + vertex -672.883 168.269 171.259 + vertex -675.356 173.368 168.275 + vertex -673.144 168.713 167.113 + endloop + endfacet + facet normal -0.900694 -0.434432 0.00426809 + outer loop + vertex -675.34 173.373 172.237 + vertex -675.356 173.368 168.275 + vertex -672.883 168.269 171.259 + endloop + endfacet + facet normal -0.901426 -0.432897 -0.00559022 + outer loop + vertex -673.109 168.691 175.082 + vertex -675.34 173.373 172.237 + vertex -672.883 168.269 171.259 + endloop + endfacet + facet normal -0.901604 -0.432535 -0.00485591 + outer loop + vertex -675.365 173.382 176.134 + vertex -675.34 173.373 172.237 + vertex -673.109 168.691 175.082 + endloop + endfacet + facet normal -0.902039 -0.431533 -0.010258 + outer loop + vertex -673.115 168.614 178.811 + vertex -675.365 173.382 176.134 + vertex -673.109 168.691 175.082 + endloop + endfacet + facet normal -0.90168 -0.432241 -0.0118201 + outer loop + vertex -675.348 173.24 179.999 + vertex -675.365 173.382 176.134 + vertex -673.115 168.614 178.811 + endloop + endfacet + facet normal -0.901948 -0.431589 -0.0148616 + outer loop + vertex -672.933 168.1 182.71 + vertex -675.348 173.24 179.999 + vertex -673.115 168.614 178.811 + endloop + endfacet + facet normal -0.900622 -0.434105 -0.0208133 + outer loop + vertex -675.403 173.172 183.819 + vertex -675.348 173.24 179.999 + vertex -672.933 168.1 182.71 + endloop + endfacet + facet normal -0.901338 -0.431895 -0.0325145 + outer loop + vertex -673.265 168.496 186.641 + vertex -675.403 173.172 183.819 + vertex -672.933 168.1 182.71 + endloop + endfacet + facet normal -0.901428 -0.431732 -0.032177 + outer loop + vertex -675.522 173.134 187.647 + vertex -675.403 173.172 183.819 + vertex -673.265 168.496 186.641 + endloop + endfacet + facet normal -0.901602 -0.431114 -0.0354193 + outer loop + vertex -673.252 168.122 190.865 + vertex -675.522 173.134 187.647 + vertex -673.265 168.496 186.641 + endloop + endfacet + facet normal -0.880379 -0.466416 0.0859581 + outer loop + vertex -674.03 166.602 132.444 + vertex -674.114 166.378 130.365 + vertex -672.994 164.562 131.98 + endloop + endfacet + facet normal -0.879408 -0.465761 0.0985279 + outer loop + vertex -674.177 166.101 128.396 + vertex -674.222 165.772 126.439 + vertex -673.118 164.005 127.946 + endloop + endfacet + facet normal -0.878415 -0.465655 0.107484 + outer loop + vertex -674.253 165.397 124.491 + vertex -674.294 165.031 122.57 + vertex -673.185 163.277 124.029 + endloop + endfacet + facet normal -0.877169 -0.465509 0.117798 + outer loop + vertex -674.352 164.692 120.678 + vertex -674.409 164.324 118.803 + vertex -673.272 162.548 120.248 + endloop + endfacet + facet normal -0.874624 -0.46773 0.12752 + outer loop + vertex -674.476 163.964 116.923 + vertex -674.541 163.571 115.034 + vertex -673.406 161.843 116.481 + endloop + endfacet + facet normal -0.873275 -0.466765 0.139716 + outer loop + vertex -674.616 163.169 113.136 + vertex -674.693 162.746 111.242 + vertex -673.539 161.019 112.681 + endloop + endfacet + facet normal -0.840126 -0.512172 0.17852 + outer loop + vertex -673.932 159.329 105.091 + vertex -673.917 158.665 103.255 + vertex -673.098 158.089 105.46 + endloop + endfacet + facet normal -0.847281 -0.506749 0.159123 + outer loop + vertex -673.718 160.198 108.91 + vertex -673.693 159.58 107.073 + vertex -672.934 159.011 109.303 + endloop + endfacet + facet normal -0.825457 -0.5416 0.159032 + outer loop + vertex -672.539 158.937 111.046 + vertex -672.69 158.122 107.485 + vertex -672.373 158.336 109.859 + endloop + endfacet + facet normal -0.850098 -0.505393 0.148023 + outer loop + vertex -672.934 159.011 109.303 + vertex -672.779 159.832 112.996 + vertex -673.499 160.417 110.86 + endloop + endfacet + facet normal -0.841096 -0.520731 0.146276 + outer loop + vertex -672.375 159.627 114.444 + vertex -672.539 158.937 111.046 + vertex -672.373 158.336 109.859 + endloop + endfacet + facet normal -0.852619 -0.503845 0.138499 + outer loop + vertex -672.779 159.832 112.996 + vertex -672.578 160.564 116.896 + vertex -673.348 161.247 114.643 + endloop + endfacet + facet normal -0.861085 -0.489856 0.136282 + outer loop + vertex -672.257 160.176 117.164 + vertex -672.375 159.627 114.444 + vertex -672.092 159.952 117.396 + endloop + endfacet + facet normal -0.864341 -0.484176 0.135969 + outer loop + vertex -672.373 158.336 109.859 + vertex -672.092 159.952 117.396 + vertex -672.375 159.627 114.444 + endloop + endfacet + facet normal -0.856001 -0.502821 0.120139 + outer loop + vertex -672.226 160.582 119.077 + vertex -672.257 160.176 117.164 + vertex -672.092 159.952 117.396 + endloop + endfacet + facet normal -0.853368 -0.506599 0.122967 + outer loop + vertex -672.578 160.564 116.896 + vertex -672.512 161.363 120.647 + vertex -673.208 161.999 118.438 + endloop + endfacet + facet normal -0.862622 -0.492436 0.115719 + outer loop + vertex -672.13 161.176 122.322 + vertex -672.226 160.582 119.077 + vertex -672.092 159.952 117.396 + endloop + endfacet + facet normal -0.854976 -0.505677 0.115352 + outer loop + vertex -672.512 161.363 120.647 + vertex -672.424 162.059 124.35 + vertex -673.097 162.705 122.193 + endloop + endfacet + facet normal -0.836077 -0.535532 0.119081 + outer loop + vertex -672.07 161.862 125.826 + vertex -672.13 161.176 122.322 + vertex -671.875 161.449 125.341 + endloop + endfacet + facet normal -0.857758 -0.50039 0.117734 + outer loop + vertex -672.092 159.952 117.396 + vertex -671.875 161.449 125.341 + vertex -672.13 161.176 122.322 + endloop + endfacet + facet normal -0.855794 -0.505721 0.108915 + outer loop + vertex -672.424 162.059 124.35 + vertex -672.305 162.701 128.266 + vertex -673.016 163.427 126.046 + endloop + endfacet + facet normal -0.839336 -0.53146 0.114303 + outer loop + vertex -672.012 162.171 127.694 + vertex -672.07 161.862 125.826 + vertex -671.875 161.449 125.341 + endloop + endfacet + facet normal -0.885357 -0.456388 0.0886115 + outer loop + vertex -671.948 162.561 130.344 + vertex -672.012 162.171 127.694 + vertex -671.875 161.449 125.341 + endloop + endfacet + facet normal -0.865118 -0.492129 0.0968525 + outer loop + vertex -671.875 161.449 125.341 + vertex -671.63 162.459 132.669 + vertex -671.948 162.561 130.344 + endloop + endfacet + facet normal -0.857759 -0.505352 0.0941756 + outer loop + vertex -672.305 162.701 128.266 + vertex -672.215 163.316 132.381 + vertex -672.935 164.096 130.011 + endloop + endfacet + facet normal -0.845822 -0.525341 0.0927453 + outer loop + vertex -671.828 163.018 134.031 + vertex -671.948 162.561 130.344 + vertex -671.63 162.459 132.669 + endloop + endfacet + facet normal -0.85685 -0.508161 0.0870653 + outer loop + vertex -672.215 163.316 132.381 + vertex -671.955 163.563 136.388 + vertex -672.761 164.563 134.287 + endloop + endfacet + facet normal -0.860912 -0.502253 0.0810732 + outer loop + vertex -671.669 163.2 136.841 + vertex -671.828 163.018 134.031 + vertex -671.63 162.459 132.669 + endloop + endfacet + facet normal -0.857216 -0.51009 0.0706333 + outer loop + vertex -671.694 163.563 139.154 + vertex -671.669 163.2 136.841 + vertex -671.46 163.327 140.294 + endloop + endfacet + facet normal -0.893389 -0.443738 0.070375 + outer loop + vertex -671.63 162.459 132.669 + vertex -671.46 163.327 140.294 + vertex -671.669 163.2 136.841 + endloop + endfacet + facet normal -0.861029 -0.502901 0.0756228 + outer loop + vertex -672.064 164.159 139.104 + vertex -672.773 165.075 137.133 + vertex -671.955 163.563 136.388 + endloop + endfacet + facet normal -0.85873 -0.507416 0.0714978 + outer loop + vertex -672.032 164.474 141.57 + vertex -671.694 163.563 139.154 + vertex -671.46 163.327 140.294 + endloop + endfacet + facet normal -0.871534 -0.482184 0.0890338 + outer loop + vertex -673.066 166.146 140.061 + vertex -672.773 165.075 137.133 + vertex -672.064 164.159 139.104 + endloop + endfacet + facet normal -0.863807 -0.499932 0.0624883 + outer loop + vertex -671.952 164.815 145.393 + vertex -672.032 164.474 141.57 + vertex -671.46 163.327 140.294 + endloop + endfacet + facet normal -0.868034 -0.493506 0.054486 + outer loop + vertex -671.83 164.932 148.413 + vertex -671.952 164.815 145.393 + vertex -671.316 164.051 148.616 + endloop + endfacet + facet normal -0.87253 -0.485184 0.0573442 + outer loop + vertex -671.46 163.327 140.294 + vertex -671.316 164.051 148.616 + vertex -671.952 164.815 145.393 + endloop + endfacet + facet normal -0.868012 -0.493593 0.0540548 + outer loop + vertex -671.998 165.444 150.37 + vertex -671.83 164.932 148.413 + vertex -671.316 164.051 148.616 + endloop + endfacet + facet normal -0.875182 -0.481965 0.0420298 + outer loop + vertex -671.865 165.49 153.685 + vertex -671.998 165.444 150.37 + vertex -671.316 164.051 148.616 + endloop + endfacet + facet normal -0.874801 -0.482636 0.0422618 + outer loop + vertex -671.316 164.051 148.616 + vertex -671.165 164.498 156.824 + vertex -671.865 165.49 153.685 + endloop + endfacet + facet normal -0.870988 -0.489741 0.039167 + outer loop + vertex -671.879 165.795 157.19 + vertex -671.865 165.49 153.685 + vertex -671.165 164.498 156.824 + endloop + endfacet + facet normal -0.872547 -0.487679 0.0288249 + outer loop + vertex -671.667 165.529 159.09 + vertex -671.879 165.795 157.19 + vertex -671.165 164.498 156.824 + endloop + endfacet + facet normal -0.87563 -0.482299 0.0256957 + outer loop + vertex -671.74 165.801 161.694 + vertex -671.667 165.529 159.09 + vertex -671.165 164.498 156.824 + endloop + endfacet + facet normal -0.874369 -0.48454 0.0264442 + outer loop + vertex -671.165 164.498 156.824 + vertex -671.088 164.767 164.318 + vertex -671.74 165.801 161.694 + endloop + endfacet + facet normal -0.869744 -0.493014 0.0219554 + outer loop + vertex -671.926 166.292 165.358 + vertex -671.74 165.801 161.694 + vertex -671.088 164.767 164.318 + endloop + endfacet + facet normal -0.87368 -0.486416 0.00910807 + outer loop + vertex -671.716 165.983 168.984 + vertex -671.926 166.292 165.358 + vertex -671.088 164.767 164.318 + endloop + endfacet + facet normal -0.871364 -0.490619 0.00415583 + outer loop + vertex -671.625 165.845 171.844 + vertex -671.716 165.983 168.984 + vertex -671.092 164.901 172.178 + endloop + endfacet + facet normal -0.875868 -0.482489 0.00778985 + outer loop + vertex -671.088 164.767 164.318 + vertex -671.092 164.901 172.178 + vertex -671.716 165.983 168.984 + endloop + endfacet + facet normal -0.871024 -0.491237 0.0018619 + outer loop + vertex -671.827 166.211 173.768 + vertex -671.625 165.845 171.844 + vertex -671.092 164.901 172.178 + endloop + endfacet + facet normal -0.876979 -0.480428 -0.00979336 + outer loop + vertex -671.753 166.008 177.085 + vertex -671.827 166.211 173.768 + vertex -671.092 164.901 172.178 + endloop + endfacet + facet normal -0.8758 -0.482587 -0.00914783 + outer loop + vertex -671.092 164.901 172.178 + vertex -671.148 164.849 180.217 + vertex -671.753 166.008 177.085 + endloop + endfacet + facet normal -0.870939 -0.491211 -0.0132773 + outer loop + vertex -671.842 166.071 180.567 + vertex -671.753 166.008 177.085 + vertex -671.148 164.849 180.217 + endloop + endfacet + facet normal -0.872167 -0.488573 -0.0249243 + outer loop + vertex -671.666 165.66 182.467 + vertex -671.842 166.071 180.567 + vertex -671.148 164.849 180.217 + endloop + endfacet + facet normal -0.871597 -0.489614 -0.0244181 + outer loop + vertex -671.832 165.828 185.028 + vertex -671.666 165.66 182.467 + vertex -671.148 164.849 180.217 + endloop + endfacet + facet normal -0.870565 -0.491473 -0.023893 + outer loop + vertex -671.148 164.849 180.217 + vertex -671.271 164.709 187.617 + vertex -671.832 165.828 185.028 + endloop + endfacet + facet normal -0.865698 -0.499753 -0.028527 + outer loop + vertex -672.101 166.084 188.7 + vertex -671.832 165.828 185.028 + vertex -671.271 164.709 187.617 + endloop + endfacet + facet normal -0.869204 -0.492833 -0.0400026 + outer loop + vertex -671.844 165.341 192.268 + vertex -672.101 166.084 188.7 + vertex -671.271 164.709 187.617 + endloop + endfacet + facet normal -0.879793 -0.471262 -0.0622621 + outer loop + vertex -672.465 165.971 196.656 + vertex -673.599 168.42 194.147 + vertex -672.237 165.838 194.442 + endloop + endfacet + facet normal -0.899397 -0.435009 -0.0430396 + outer loop + vertex -675.619 172.969 191.352 + vertex -675.522 173.134 187.647 + vertex -673.252 168.122 190.865 + endloop + endfacet + facet normal -0.586103 -0.457319 -0.668837 + outer loop + vertex -691.999 145.555 294.427 + vertex -691.114 145.486 293.699 + vertex -691.054 144.105 294.591 + endloop + endfacet + facet normal -0.608698 -0.462999 -0.644297 + outer loop + vertex -690.436 144.251 293.942 + vertex -689.926 145.188 292.786 + vertex -690.052 143.535 294.093 + endloop + endfacet + facet normal -0.569135 -0.470832 -0.674094 + outer loop + vertex -691.838 144.238 295.159 + vertex -691.054 144.105 294.591 + vertex -691.383 143.311 295.423 + endloop + endfacet + facet normal -0.552452 -0.498907 -0.667749 + outer loop + vertex -692.476 143.536 296.159 + vertex -691.383 143.311 295.423 + vertex -691.747 142.979 295.972 + endloop + endfacet + facet normal -0.560689 -0.516563 -0.64714 + outer loop + vertex -691.747 142.979 295.972 + vertex -692.987 143.724 296.452 + vertex -692.476 143.536 296.159 + endloop + endfacet + facet normal -0.546191 -0.439609 -0.713035 + outer loop + vertex -692.987 143.724 296.452 + vertex -693.615 143.55 297.04 + vertex -694.2 145.253 296.438 + endloop + endfacet + facet normal -0.520452 -0.564239 -0.640909 + outer loop + vertex -690.924 142.781 295.498 + vertex -691.718 142.613 296.29 + vertex -690.94 142.851 295.448 + endloop + endfacet + facet normal -0.553175 -0.506441 -0.661449 + outer loop + vertex -690.924 142.781 295.498 + vertex -690.722 142.349 295.659 + vertex -691.718 142.613 296.29 + endloop + endfacet + facet normal -0.547887 -0.552509 -0.628136 + outer loop + vertex -689.763 141.631 295.455 + vertex -690.646 141.342 296.479 + vertex -690.722 142.349 295.659 + endloop + endfacet + facet normal -0.524173 -0.586648 -0.617322 + outer loop + vertex -689.763 141.631 295.455 + vertex -688.302 140.288 295.489 + vertex -690.646 141.342 296.479 + endloop + endfacet +endsolid diff --git a/noether_examples/meshes/outputs/output_2.stl b/noether_examples/meshes/outputs/output_2.stl new file mode 100644 index 00000000..167a616a --- /dev/null +++ b/noether_examples/meshes/outputs/output_2.stl @@ -0,0 +1,6953 @@ +solid ascii + facet normal 0.913015 -0.273621 -0.302548 + outer loop + vertex -843.834 272.009 271.498 + vertex -842.538 275.714 272.056 + vertex -843.232 270.379 274.789 + endloop + endfacet + facet normal 0.910292 -0.276228 -0.30833 + outer loop + vertex -843.232 270.379 274.789 + vertex -842.538 275.714 272.056 + vertex -841.728 275.019 275.072 + endloop + endfacet + facet normal 0.89874 -0.270222 -0.345322 + outer loop + vertex -843.232 270.379 274.789 + vertex -841.728 275.019 275.072 + vertex -842.526 268.658 277.971 + endloop + endfacet + facet normal 0.886654 -0.279295 -0.368564 + outer loop + vertex -842.526 268.658 277.971 + vertex -841.728 275.019 275.072 + vertex -841.153 272.402 278.438 + endloop + endfacet + facet normal 0.918235 -0.278624 -0.281449 + outer loop + vertex -843.834 272.009 271.498 + vertex -842.905 278.136 268.464 + vertex -842.538 275.714 272.056 + endloop + endfacet + facet normal 0.926558 -0.270134 -0.261758 + outer loop + vertex -844.339 273.554 268.116 + vertex -842.905 278.136 268.464 + vertex -843.834 272.009 271.498 + endloop + endfacet + facet normal 0.933432 -0.274639 -0.230818 + outer loop + vertex -844.339 273.554 268.116 + vertex -843.537 278.689 265.248 + vertex -842.905 278.136 268.464 + endloop + endfacet + facet normal 0.934232 -0.273625 -0.228779 + outer loop + vertex -844.763 275.027 264.621 + vertex -843.537 278.689 265.248 + vertex -844.339 273.554 268.116 + endloop + endfacet + facet normal 0.936493 -0.276657 -0.215506 + outer loop + vertex -844.763 275.027 264.621 + vertex -843.746 280.954 261.43 + vertex -843.537 278.689 265.248 + endloop + endfacet + facet normal 0.942901 -0.268122 -0.197609 + outer loop + vertex -845.12 276.442 260.997 + vertex -843.746 280.954 261.43 + vertex -844.763 275.027 264.621 + endloop + endfacet + facet normal 0.946502 -0.271434 -0.174523 + outer loop + vertex -845.12 276.442 260.997 + vertex -844.251 281.398 258.004 + vertex -843.746 280.954 261.43 + endloop + endfacet + facet normal 0.946263 -0.271815 -0.175222 + outer loop + vertex -845.426 277.777 257.273 + vertex -844.251 281.398 258.004 + vertex -845.12 276.442 260.997 + endloop + endfacet + facet normal 0.947213 -0.273837 -0.166734 + outer loop + vertex -845.426 277.777 257.273 + vertex -844.35 283.472 254.033 + vertex -844.251 281.398 258.004 + endloop + endfacet + facet normal 0.95214 -0.265788 -0.150949 + outer loop + vertex -845.678 279.004 253.523 + vertex -844.35 283.472 254.033 + vertex -845.426 277.777 257.273 + endloop + endfacet + facet normal 0.954295 -0.26873 -0.130789 + outer loop + vertex -845.678 279.004 253.523 + vertex -844.756 283.736 250.528 + vertex -844.35 283.472 254.033 + endloop + endfacet + facet normal 0.954589 -0.268164 -0.129804 + outer loop + vertex -845.868 280.132 249.797 + vertex -844.756 283.736 250.528 + vertex -845.678 279.004 253.523 + endloop + endfacet + facet normal 0.954919 -0.269216 -0.125112 + outer loop + vertex -845.868 280.132 249.797 + vertex -844.753 285.594 246.559 + vertex -844.756 283.736 250.528 + endloop + endfacet + facet normal 0.969089 -0.223794 -0.103842 + outer loop + vertex -844.756 283.736 250.528 + vertex -844.753 285.594 246.559 + vertex -843.411 290.481 248.549 + endloop + endfacet + facet normal 0.964523 -0.230288 -0.129083 + outer loop + vertex -844.756 283.736 250.528 + vertex -843.411 290.481 248.549 + vertex -844.35 283.472 254.033 + endloop + endfacet + facet normal 0.964092 -0.231311 -0.130464 + outer loop + vertex -843.411 290.481 248.549 + vertex -842.927 288.296 256.001 + vertex -844.35 283.472 254.033 + endloop + endfacet + facet normal 0.963598 -0.226328 -0.142321 + outer loop + vertex -844.251 281.398 258.004 + vertex -844.35 283.472 254.033 + vertex -842.927 288.296 256.001 + endloop + endfacet + facet normal 0.957178 -0.233474 -0.171175 + outer loop + vertex -844.251 281.398 258.004 + vertex -842.927 288.296 256.001 + vertex -843.746 280.954 261.43 + endloop + endfacet + facet normal 0.956709 -0.23441 -0.172512 + outer loop + vertex -842.927 288.296 256.001 + vertex -842.237 285.777 263.246 + vertex -843.746 280.954 261.43 + endloop + endfacet + facet normal 0.955324 -0.228222 -0.187803 + outer loop + vertex -843.537 278.689 265.248 + vertex -843.746 280.954 261.43 + vertex -842.237 285.777 263.246 + endloop + endfacet + facet normal 0.944659 -0.237225 -0.226592 + outer loop + vertex -843.537 278.689 265.248 + vertex -842.237 285.777 263.246 + vertex -842.905 278.136 268.464 + endloop + endfacet + facet normal 0.942977 -0.239908 -0.230735 + outer loop + vertex -842.237 285.777 263.246 + vertex -841.273 282.951 270.124 + vertex -842.905 278.136 268.464 + endloop + endfacet + facet normal 0.939664 -0.2315 -0.251871 + outer loop + vertex -842.538 275.714 272.056 + vertex -842.905 278.136 268.464 + vertex -841.273 282.951 270.124 + endloop + endfacet + facet normal 0.921557 -0.242121 -0.303496 + outer loop + vertex -842.538 275.714 272.056 + vertex -841.273 282.951 270.124 + vertex -841.728 275.019 275.072 + endloop + endfacet + facet normal 0.919175 -0.245017 -0.308357 + outer loop + vertex -841.273 282.951 270.124 + vertex -839.947 279.8 276.581 + vertex -841.728 275.019 275.072 + endloop + endfacet + facet normal 0.912092 -0.233294 -0.337138 + outer loop + vertex -841.153 272.402 278.438 + vertex -841.728 275.019 275.072 + vertex -839.947 279.8 276.581 + endloop + endfacet + facet normal 0.935882 -0.20019 -0.289912 + outer loop + vertex -841.273 282.951 270.124 + vertex -839.308 291.361 270.661 + vertex -839.947 279.8 276.581 + endloop + endfacet + facet normal 0.929527 -0.207486 -0.304843 + outer loop + vertex -839.947 279.8 276.581 + vertex -839.308 291.361 270.661 + vertex -837.908 288.269 277.035 + endloop + endfacet + facet normal 0.932375 -0.199379 -0.301538 + outer loop + vertex -839.308 291.361 270.661 + vertex -837.452 299.569 270.971 + vertex -837.908 288.269 277.035 + endloop + endfacet + facet normal 0.929916 -0.202288 -0.307142 + outer loop + vertex -837.908 288.269 277.035 + vertex -837.452 299.569 270.971 + vertex -836.012 296.57 277.307 + endloop + endfacet + facet normal 0.922753 -0.222155 -0.31492 + outer loop + vertex -837.452 299.569 270.971 + vertex -835.514 307.489 271.066 + vertex -836.012 296.57 277.307 + endloop + endfacet + facet normal 0.922858 -0.222033 -0.314698 + outer loop + vertex -836.012 296.57 277.307 + vertex -835.514 307.489 271.066 + vertex -834.052 304.589 277.396 + endloop + endfacet + facet normal 0.955245 -0.201428 -0.216644 + outer loop + vertex -842.237 285.777 263.246 + vertex -840.346 294.125 263.824 + vertex -841.273 282.951 270.124 + endloop + endfacet + facet normal 0.951167 -0.207691 -0.228355 + outer loop + vertex -841.273 282.951 270.124 + vertex -840.346 294.125 263.824 + vertex -839.308 291.361 270.661 + endloop + endfacet + facet normal 0.952434 -0.203491 -0.226849 + outer loop + vertex -840.346 294.125 263.824 + vertex -838.533 302.259 264.14 + vertex -839.308 291.361 270.661 + endloop + endfacet + facet normal 0.950726 -0.206177 -0.231542 + outer loop + vertex -839.308 291.361 270.661 + vertex -838.533 302.259 264.14 + vertex -837.452 299.569 270.971 + endloop + endfacet + facet normal 0.943577 -0.228862 -0.239342 + outer loop + vertex -838.533 302.259 264.14 + vertex -836.62 310.07 264.213 + vertex -837.452 299.569 270.971 + endloop + endfacet + facet normal 0.943971 -0.228262 -0.238361 + outer loop + vertex -837.452 299.569 270.971 + vertex -836.62 310.07 264.213 + vertex -835.514 307.489 271.066 + endloop + endfacet + facet normal 0.965736 -0.202526 -0.162285 + outer loop + vertex -842.927 288.296 256.001 + vertex -841.079 296.573 256.668 + vertex -842.237 285.777 263.246 + endloop + endfacet + facet normal 0.963655 -0.20661 -0.169355 + outer loop + vertex -842.237 285.777 263.246 + vertex -841.079 296.573 256.668 + vertex -840.346 294.125 263.824 + endloop + endfacet + facet normal 0.963659 -0.206596 -0.169351 + outer loop + vertex -841.079 296.573 256.668 + vertex -839.293 304.623 257.006 + vertex -840.346 294.125 263.824 + endloop + endfacet + facet normal 0.962962 -0.207987 -0.171599 + outer loop + vertex -840.346 294.125 263.824 + vertex -839.293 304.623 257.006 + vertex -838.533 302.259 264.14 + endloop + endfacet + facet normal 0.955447 -0.234297 -0.179516 + outer loop + vertex -839.293 304.623 257.006 + vertex -837.395 312.317 257.07 + vertex -838.533 302.259 264.14 + endloop + endfacet + facet normal 0.956352 -0.232574 -0.17692 + outer loop + vertex -838.533 302.259 264.14 + vertex -837.395 312.317 257.07 + vertex -836.62 310.07 264.213 + endloop + endfacet + facet normal 0.963051 -0.236593 -0.12867 + outer loop + vertex -839.293 304.623 257.006 + vertex -837.898 314.272 249.707 + vertex -837.395 312.317 257.07 + endloop + endfacet + facet normal 0.961377 -0.2404 -0.134022 + outer loop + vertex -839.804 306.689 249.636 + vertex -837.898 314.272 249.707 + vertex -839.293 304.623 257.006 + endloop + endfacet + facet normal 0.965276 -0.241706 -0.0990951 + outer loop + vertex -839.804 306.689 249.636 + vertex -838.233 316.014 242.193 + vertex -837.898 314.272 249.707 + endloop + endfacet + facet normal 0.963957 -0.245066 -0.103583 + outer loop + vertex -840.151 308.504 242.116 + vertex -838.233 316.014 242.193 + vertex -839.804 306.689 249.636 + endloop + endfacet + facet normal 0.972318 -0.212934 -0.0962134 + outer loop + vertex -841.588 298.712 249.267 + vertex -840.151 308.504 242.116 + vertex -839.804 306.689 249.636 + endloop + endfacet + facet normal 0.969173 -0.21078 -0.127572 + outer loop + vertex -841.588 298.712 249.267 + vertex -839.804 306.689 249.636 + vertex -841.079 296.573 256.668 + endloop + endfacet + facet normal 0.972207 -0.213241 -0.0966569 + outer loop + vertex -841.931 300.562 241.736 + vertex -840.151 308.504 242.116 + vertex -841.588 298.712 249.267 + endloop + endfacet + facet normal 0.97362 -0.207333 -0.0952703 + outer loop + vertex -843.411 290.481 248.549 + vertex -841.931 300.562 241.736 + vertex -841.588 298.712 249.267 + endloop + endfacet + facet normal 0.97459 -0.204644 -0.0910818 + outer loop + vertex -843.714 292.375 241.044 + vertex -841.931 300.562 241.736 + vertex -843.411 290.481 248.549 + endloop + endfacet + facet normal 0.975808 -0.206553 -0.0716585 + outer loop + vertex -843.714 292.375 241.044 + vertex -842.131 302.245 234.155 + vertex -841.931 300.562 241.736 + endloop + endfacet + facet normal 0.973644 -0.21585 -0.0736654 + outer loop + vertex -842.131 302.245 234.155 + vertex -840.371 310.067 234.498 + vertex -841.931 300.562 241.736 + endloop + endfacet + facet normal 0.974631 -0.216876 -0.0553055 + outer loop + vertex -842.131 302.245 234.155 + vertex -840.495 311.467 226.829 + vertex -840.371 310.067 234.498 + endloop + endfacet + facet normal 0.965828 -0.251774 -0.061534 + outer loop + vertex -840.495 311.467 226.829 + vertex -838.574 318.824 226.869 + vertex -840.371 310.067 234.498 + endloop + endfacet + facet normal 0.966835 -0.248765 -0.0578423 + outer loop + vertex -840.371 310.067 234.498 + vertex -838.574 318.824 226.869 + vertex -838.446 317.531 234.57 + endloop + endfacet + facet normal 0.965492 -0.248214 -0.0788305 + outer loop + vertex -840.371 310.067 234.498 + vertex -838.446 317.531 234.57 + vertex -840.151 308.504 242.116 + endloop + endfacet + facet normal 0.966615 -0.252065 -0.0460294 + outer loop + vertex -840.495 311.467 226.829 + vertex -838.651 319.947 219.1 + vertex -838.574 318.824 226.869 + endloop + endfacet + facet normal 0.966014 -0.253948 -0.0482389 + outer loop + vertex -840.55 312.722 219.104 + vertex -838.651 319.947 219.1 + vertex -840.495 311.467 226.829 + endloop + endfacet + facet normal 0.975194 -0.217265 -0.0423436 + outer loop + vertex -842.186 303.933 226.531 + vertex -840.55 312.722 219.104 + vertex -840.495 311.467 226.829 + endloop + endfacet + facet normal 0.975049 -0.217785 -0.0429912 + outer loop + vertex -842.2 305.371 218.94 + vertex -840.55 312.722 219.104 + vertex -842.186 303.933 226.531 + endloop + endfacet + facet normal 0.978484 -0.202391 -0.0400814 + outer loop + vertex -843.658 296.96 225.819 + vertex -842.2 305.371 218.94 + vertex -842.186 303.933 226.531 + endloop + endfacet + facet normal 0.978288 -0.201484 -0.0485505 + outer loop + vertex -843.658 296.96 225.819 + vertex -842.186 303.933 226.531 + vertex -843.824 294.314 233.441 + endloop + endfacet + facet normal 0.975819 -0.212222 -0.052333 + outer loop + vertex -843.658 296.96 225.819 + vertex -843.824 294.314 233.441 + vertex -844.964 289.675 231.009 + endloop + endfacet + facet normal 0.97711 -0.207759 -0.0457437 + outer loop + vertex -845.044 290.551 225.317 + vertex -843.658 296.96 225.819 + vertex -844.964 289.675 231.009 + endloop + endfacet + facet normal 0.968742 -0.24277 -0.0510147 + outer loop + vertex -846.161 285.017 230.437 + vertex -845.044 290.551 225.317 + vertex -844.964 289.675 231.009 + endloop + endfacet + facet normal 0.968681 -0.242417 -0.0537607 + outer loop + vertex -846.161 285.017 230.437 + vertex -844.964 289.675 231.009 + vertex -846.152 284.088 234.783 + endloop + endfacet + facet normal 0.964565 -0.25384 -0.0719656 + outer loop + vertex -846.152 284.088 234.783 + vertex -844.964 289.675 231.009 + vertex -845.17 287.619 235.501 + endloop + endfacet + facet normal 0.964593 -0.254144 -0.070505 + outer loop + vertex -846.152 284.088 234.783 + vertex -845.17 287.619 235.501 + vertex -846.119 283.122 238.729 + endloop + endfacet + facet normal 0.965451 -0.25182 -0.0670141 + outer loop + vertex -846.119 283.122 238.729 + vertex -845.17 287.619 235.501 + vertex -844.957 287.475 239.103 + endloop + endfacet + facet normal 0.964777 -0.250493 -0.0803613 + outer loop + vertex -846.119 283.122 238.729 + vertex -844.957 287.475 239.103 + vertex -846.039 282.236 242.438 + endloop + endfacet + facet normal 0.962301 -0.25647 -0.090553 + outer loop + vertex -846.039 282.236 242.438 + vertex -844.957 287.475 239.103 + vertex -845.051 285.716 243.083 + endloop + endfacet + facet normal 0.962349 -0.2567 -0.0893872 + outer loop + vertex -846.039 282.236 242.438 + vertex -845.051 285.716 243.083 + vertex -845.967 281.234 246.099 + endloop + endfacet + facet normal 0.961735 -0.258163 -0.0917476 + outer loop + vertex -845.967 281.234 246.099 + vertex -845.051 285.716 243.083 + vertex -844.753 285.594 246.559 + endloop + endfacet + facet normal 0.970581 -0.222809 -0.0912592 + outer loop + vertex -845.051 285.716 243.083 + vertex -843.714 292.375 241.044 + vertex -844.753 285.594 246.559 + endloop + endfacet + facet normal 0.97324 -0.217817 -0.073215 + outer loop + vertex -845.051 285.716 243.083 + vertex -844.957 287.475 239.103 + vertex -843.714 292.375 241.044 + endloop + endfacet + facet normal 0.973192 -0.2191 -0.0699448 + outer loop + vertex -843.824 294.314 233.441 + vertex -843.714 292.375 241.044 + vertex -844.957 287.475 239.103 + endloop + endfacet + facet normal 0.974137 -0.216074 -0.0661007 + outer loop + vertex -845.17 287.619 235.501 + vertex -843.824 294.314 233.441 + vertex -844.957 287.475 239.103 + endloop + endfacet + facet normal 0.968733 -0.242797 -0.0510457 + outer loop + vertex -846.416 284.9 226.159 + vertex -845.044 290.551 225.317 + vertex -846.161 285.017 230.437 + endloop + endfacet + facet normal 0.969203 -0.242057 -0.0453116 + outer loop + vertex -845.044 290.551 225.317 + vertex -846.416 284.9 226.159 + vertex -845.69 289.152 218.968 + endloop + endfacet + facet normal 0.97461 -0.217986 -0.0511659 + outer loop + vertex -845.69 289.152 218.968 + vertex -843.755 297.867 218.701 + vertex -845.044 290.551 225.317 + endloop + endfacet + facet normal 0.975518 -0.217597 -0.0318811 + outer loop + vertex -845.69 289.152 218.968 + vertex -843.862 298.514 211.001 + vertex -843.755 297.867 218.701 + endloop + endfacet + facet normal 0.978878 -0.202137 -0.0306287 + outer loop + vertex -843.862 298.514 211.001 + vertex -842.234 306.363 211.238 + vertex -843.755 297.867 218.701 + endloop + endfacet + facet normal 0.978932 -0.201914 -0.0303644 + outer loop + vertex -843.755 297.867 218.701 + vertex -842.234 306.363 211.238 + vertex -842.2 305.371 218.94 + endloop + endfacet + facet normal 0.975414 -0.217984 -0.0324171 + outer loop + vertex -842.234 306.363 211.238 + vertex -840.576 313.773 211.294 + vertex -842.2 305.371 218.94 + endloop + endfacet + facet normal 0.975575 -0.218066 -0.0264719 + outer loop + vertex -842.234 306.363 211.238 + vertex -840.598 314.636 203.377 + vertex -840.576 313.773 211.294 + endloop + endfacet + facet normal 0.96601 -0.256679 -0.030652 + outer loop + vertex -840.598 314.636 203.377 + vertex -838.72 321.711 203.306 + vertex -840.576 313.773 211.294 + endloop + endfacet + facet normal 0.966608 -0.254669 -0.0285159 + outer loop + vertex -840.576 313.773 211.294 + vertex -838.72 321.711 203.306 + vertex -838.696 320.913 211.248 + endloop + endfacet + facet normal 0.966309 -0.254649 -0.0374329 + outer loop + vertex -840.576 313.773 211.294 + vertex -838.696 320.913 211.248 + vertex -840.55 312.722 219.104 + endloop + endfacet + facet normal 0.966223 -0.256661 -0.0231816 + outer loop + vertex -840.598 314.636 203.377 + vertex -838.742 322.351 195.311 + vertex -838.72 321.711 203.306 + endloop + endfacet + facet normal 0.966159 -0.256883 -0.0234088 + outer loop + vertex -840.611 315.316 195.382 + vertex -838.742 322.351 195.311 + vertex -840.598 314.636 203.377 + endloop + endfacet + facet normal 0.975835 -0.217585 -0.0200802 + outer loop + vertex -842.257 307.201 203.311 + vertex -840.611 315.316 195.382 + vertex -840.598 314.636 203.377 + endloop + endfacet + facet normal 0.97575 -0.217929 -0.0204495 + outer loop + vertex -842.266 307.913 195.301 + vertex -840.611 315.316 195.382 + vertex -842.257 307.201 203.311 + endloop + endfacet + facet normal 0.979217 -0.201921 -0.0190315 + outer loop + vertex -843.868 299.426 202.909 + vertex -842.266 307.913 195.301 + vertex -842.257 307.201 203.311 + endloop + endfacet + facet normal 0.97917 -0.201682 -0.0234671 + outer loop + vertex -843.868 299.426 202.909 + vertex -842.257 307.201 203.311 + vertex -843.862 298.514 211.001 + endloop + endfacet + facet normal 0.975983 -0.216395 -0.0251227 + outer loop + vertex -845.647 290.563 210.162 + vertex -843.868 299.426 202.909 + vertex -843.862 298.514 211.001 + endloop + endfacet + facet normal 0.976278 -0.21523 -0.0236269 + outer loop + vertex -845.635 291.504 202.073 + vertex -843.868 299.426 202.909 + vertex -845.647 290.563 210.162 + endloop + endfacet + facet normal 0.976274 -0.215623 -0.0198867 + outer loop + vertex -845.635 291.504 202.073 + vertex -843.873 300.144 194.896 + vertex -843.868 299.426 202.909 + endloop + endfacet + facet normal 0.976624 -0.214192 -0.0180779 + outer loop + vertex -845.633 292.184 194.109 + vertex -843.873 300.144 194.896 + vertex -845.635 291.504 202.073 + endloop + endfacet + facet normal 0.976605 -0.214579 -0.0141244 + outer loop + vertex -845.633 292.184 194.109 + vertex -843.881 300.63 186.934 + vertex -843.873 300.144 194.896 + endloop + endfacet + facet normal 0.979474 -0.201132 -0.013307 + outer loop + vertex -843.881 300.63 186.934 + vertex -842.277 308.415 187.328 + vertex -843.873 300.144 194.896 + endloop + endfacet + facet normal 0.979322 -0.201818 -0.0140882 + outer loop + vertex -843.873 300.144 194.896 + vertex -842.277 308.415 187.328 + vertex -842.266 307.913 195.301 + endloop + endfacet + facet normal 0.975853 -0.217904 -0.0150975 + outer loop + vertex -842.277 308.415 187.328 + vertex -840.625 315.808 187.398 + vertex -842.266 307.913 195.301 + endloop + endfacet + facet normal 0.975914 -0.217976 -0.00890404 + outer loop + vertex -842.277 308.415 187.328 + vertex -840.636 316.082 179.471 + vertex -840.625 315.808 187.398 + endloop + endfacet + facet normal 0.966043 -0.258178 -0.0102846 + outer loop + vertex -840.636 316.082 179.471 + vertex -838.771 323.066 179.382 + vertex -840.625 315.808 187.398 + endloop + endfacet + facet normal 0.966005 -0.258314 -0.0104164 + outer loop + vertex -840.625 315.808 187.398 + vertex -838.771 323.066 179.382 + vertex -838.756 322.801 187.319 + endloop + endfacet + facet normal 0.965886 -0.258364 -0.0176684 + outer loop + vertex -840.625 315.808 187.398 + vertex -838.756 322.801 187.319 + vertex -840.611 315.316 195.382 + endloop + endfacet + facet normal 0.966114 -0.258102 -0.00278158 + outer loop + vertex -840.636 316.082 179.471 + vertex -838.775 323.137 171.515 + vertex -838.771 323.066 179.382 + endloop + endfacet + facet normal 0.96601 -0.258484 -0.00314466 + outer loop + vertex -840.641 316.16 171.607 + vertex -838.775 323.137 171.515 + vertex -840.636 316.082 179.471 + endloop + endfacet + facet normal 0.975908 -0.218163 -0.00275383 + outer loop + vertex -842.287 308.7 179.412 + vertex -840.641 316.16 171.607 + vertex -840.636 316.082 179.471 + endloop + endfacet + facet normal 0.975898 -0.218211 -0.00280213 + outer loop + vertex -842.293 308.774 171.543 + vertex -840.641 316.16 171.607 + vertex -842.287 308.7 179.412 + endloop + endfacet + facet normal 0.979562 -0.201126 -0.00264484 + outer loop + vertex -843.89 300.9 179.006 + vertex -842.293 308.774 171.543 + vertex -842.287 308.7 179.412 + endloop + endfacet + facet normal 0.979588 -0.20086 -0.00785934 + outer loop + vertex -843.89 300.9 179.006 + vertex -842.287 308.7 179.412 + vertex -843.881 300.63 186.934 + endloop + endfacet + facet normal 0.976831 -0.213851 -0.00829945 + outer loop + vertex -845.636 292.645 186.134 + vertex -843.89 300.9 179.006 + vertex -843.881 300.63 186.934 + endloop + endfacet + facet normal 0.977051 -0.212884 -0.00712516 + outer loop + vertex -845.639 292.9 178.181 + vertex -843.89 300.9 179.006 + vertex -845.636 292.645 186.134 + endloop + endfacet + facet normal 0.97697 -0.213364 -0.00230347 + outer loop + vertex -845.639 292.9 178.181 + vertex -843.892 300.975 171.135 + vertex -843.89 300.9 179.006 + endloop + endfacet + facet normal 0.977191 -0.212359 -0.00109754 + outer loop + vertex -845.636 292.954 170.307 + vertex -843.892 300.975 171.135 + vertex -845.639 292.9 178.181 + endloop + endfacet + facet normal 0.97708 -0.212838 0.00378494 + outer loop + vertex -845.636 292.954 170.307 + vertex -843.888 300.853 163.312 + vertex -843.892 300.975 171.135 + endloop + endfacet + facet normal 0.979651 -0.200677 0.00359692 + outer loop + vertex -843.888 300.853 163.312 + vertex -842.29 308.661 163.713 + vertex -843.892 300.975 171.135 + endloop + endfacet + facet normal 0.97959 -0.20098 0.00326989 + outer loop + vertex -843.892 300.975 171.135 + vertex -842.29 308.661 163.713 + vertex -842.293 308.774 171.543 + endloop + endfacet + facet normal 0.975949 -0.217971 0.00351465 + outer loop + vertex -842.29 308.661 163.713 + vertex -840.639 316.054 163.781 + vertex -842.293 308.774 171.543 + endloop + endfacet + facet normal 0.975902 -0.218013 0.00928772 + outer loop + vertex -842.29 308.661 163.713 + vertex -840.629 315.766 155.952 + vertex -840.639 316.054 163.781 + endloop + endfacet + facet normal 0.966156 -0.257734 0.0107372 + outer loop + vertex -840.629 315.766 155.952 + vertex -838.762 322.761 155.866 + vertex -840.639 316.054 163.781 + endloop + endfacet + facet normal 0.96624 -0.257407 0.0110339 + outer loop + vertex -840.639 316.054 163.781 + vertex -838.762 322.761 155.866 + vertex -838.776 323.043 163.692 + endloop + endfacet + facet normal 0.966269 -0.257507 0.00375767 + outer loop + vertex -840.639 316.054 163.781 + vertex -838.776 323.043 163.692 + vertex -840.641 316.16 171.607 + endloop + endfacet + facet normal 0.966095 -0.257643 0.0167241 + outer loop + vertex -840.629 315.766 155.952 + vertex -838.745 322.313 148.007 + vertex -838.762 322.761 155.866 + endloop + endfacet + facet normal 0.966235 -0.257086 0.0172168 + outer loop + vertex -840.612 315.304 148.098 + vertex -838.745 322.313 148.007 + vertex -840.629 315.766 155.952 + endloop + endfacet + facet normal 0.975877 -0.217809 0.0149262 + outer loop + vertex -842.279 308.367 155.891 + vertex -840.612 315.304 148.098 + vertex -840.629 315.766 155.952 + endloop + endfacet + facet normal 0.97612 -0.216639 0.0160191 + outer loop + vertex -842.258 307.882 148.04 + vertex -840.612 315.304 148.098 + vertex -842.279 308.367 155.891 + endloop + endfacet + facet normal 0.979532 -0.200727 0.0150451 + outer loop + vertex -843.877 300.543 155.504 + vertex -842.258 307.882 148.04 + vertex -842.279 308.367 155.891 + endloop + endfacet + facet normal 0.979655 -0.200471 0.00936754 + outer loop + vertex -843.877 300.543 155.504 + vertex -842.279 308.367 155.891 + vertex -843.888 300.853 163.312 + endloop + endfacet + facet normal 0.976983 -0.213087 0.00986453 + outer loop + vertex -845.634 292.812 162.517 + vertex -843.877 300.543 155.504 + vertex -843.888 300.853 163.312 + endloop + endfacet + facet normal 0.977009 -0.212965 0.0100051 + outer loop + vertex -845.627 292.476 154.731 + vertex -843.877 300.543 155.504 + vertex -845.634 292.812 162.517 + endloop + endfacet + facet normal 0.976826 -0.213465 0.015634 + outer loop + vertex -845.627 292.476 154.731 + vertex -843.86 300.045 147.659 + vertex -843.877 300.543 155.504 + endloop + endfacet + facet normal 0.976819 -0.213499 0.015596 + outer loop + vertex -845.617 291.947 146.871 + vertex -843.86 300.045 147.659 + vertex -845.627 292.476 154.731 + endloop + endfacet + facet normal 0.976607 -0.213993 0.0211407 + outer loop + vertex -845.617 291.947 146.871 + vertex -843.843 299.345 139.769 + vertex -843.86 300.045 147.659 + endloop + endfacet + facet normal 0.979387 -0.201 0.0199944 + outer loop + vertex -843.843 299.345 139.769 + vertex -842.232 307.231 140.173 + vertex -843.86 300.045 147.659 + endloop + endfacet + facet normal 0.979361 -0.20114 0.0198539 + outer loop + vertex -843.86 300.045 147.659 + vertex -842.232 307.231 140.173 + vertex -842.258 307.882 148.04 + endloop + endfacet + facet normal 0.975922 -0.217089 0.0211633 + outer loop + vertex -842.232 307.231 140.173 + vertex -840.582 314.657 140.219 + vertex -842.258 307.882 148.04 + endloop + endfacet + facet normal 0.97579 -0.217094 0.026526 + outer loop + vertex -842.232 307.231 140.173 + vertex -840.547 313.851 132.354 + vertex -840.582 314.657 140.219 + endloop + endfacet + facet normal 0.96666 -0.254265 0.0302925 + outer loop + vertex -840.547 313.851 132.354 + vertex -838.687 320.908 132.242 + vertex -840.582 314.657 140.219 + endloop + endfacet + facet normal 0.966428 -0.25524 0.0294735 + outer loop + vertex -840.582 314.657 140.219 + vertex -838.687 320.908 132.242 + vertex -838.721 321.69 140.12 + endloop + endfacet + facet normal 0.966537 -0.255336 0.024695 + outer loop + vertex -840.582 314.657 140.219 + vertex -838.721 321.69 140.12 + vertex -840.612 315.304 148.098 + endloop + endfacet + facet normal 0.966438 -0.254085 0.0379257 + outer loop + vertex -840.547 313.851 132.354 + vertex -838.63 319.955 124.409 + vertex -838.687 320.908 132.242 + endloop + endfacet + facet normal 0.966669 -0.253079 0.0387548 + outer loop + vertex -840.498 312.838 124.514 + vertex -838.63 319.955 124.409 + vertex -840.547 313.851 132.354 + endloop + endfacet + facet normal 0.975739 -0.216272 0.034054 + outer loop + vertex -842.205 306.362 132.288 + vertex -840.498 312.838 124.514 + vertex -840.547 313.851 132.354 + endloop + endfacet + facet normal 0.975785 -0.216034 0.0342626 + outer loop + vertex -842.183 305.207 124.378 + vertex -840.498 312.838 124.514 + vertex -842.205 306.362 132.288 + endloop + endfacet + facet normal 0.978853 -0.20201 0.0322235 + outer loop + vertex -843.837 298.378 131.821 + vertex -842.183 305.207 124.378 + vertex -842.205 306.362 132.288 + endloop + endfacet + facet normal 0.979131 -0.201658 0.0252269 + outer loop + vertex -843.837 298.378 131.821 + vertex -842.205 306.362 132.288 + vertex -843.843 299.345 139.769 + endloop + endfacet + facet normal 0.976258 -0.214942 0.0268415 + outer loop + vertex -845.614 291.198 138.94 + vertex -843.837 298.378 131.821 + vertex -843.843 299.345 139.769 + endloop + endfacet + facet normal 0.976093 -0.2158 0.0259352 + outer loop + vertex -845.633 290.142 130.897 + vertex -843.837 298.378 131.821 + vertex -845.614 291.198 138.94 + endloop + endfacet + facet normal 0.975646 -0.216646 0.0343462 + outer loop + vertex -845.633 290.142 130.897 + vertex -843.857 297.011 123.775 + vertex -843.837 298.378 131.821 + endloop + endfacet + facet normal 0.975882 -0.215369 0.0356374 + outer loop + vertex -845.644 288.716 122.573 + vertex -843.857 297.011 123.775 + vertex -845.633 290.142 130.897 + endloop + endfacet + facet normal 0.975071 -0.216848 0.0470499 + outer loop + vertex -845.644 288.716 122.573 + vertex -843.915 295.017 115.79 + vertex -843.857 297.011 123.775 + endloop + endfacet + facet normal 0.978671 -0.200877 0.0430364 + outer loop + vertex -843.915 295.017 115.79 + vertex -842.161 303.705 116.456 + vertex -843.857 297.011 123.775 + endloop + endfacet + facet normal 0.978333 -0.202922 0.0410881 + outer loop + vertex -843.857 297.011 123.775 + vertex -842.161 303.705 116.456 + vertex -842.183 305.207 124.378 + endloop + endfacet + facet normal 0.975405 -0.216072 0.0435731 + outer loop + vertex -842.161 303.705 116.456 + vertex -840.43 311.569 116.694 + vertex -842.183 305.207 124.378 + endloop + endfacet + facet normal 0.974786 -0.21628 0.0549176 + outer loop + vertex -842.161 303.705 116.456 + vertex -840.324 310.072 108.922 + vertex -840.43 311.569 116.694 + endloop + endfacet + facet normal 0.966582 -0.248969 0.0611037 + outer loop + vertex -840.324 310.072 108.922 + vertex -838.418 317.474 108.925 + vertex -840.43 311.569 116.694 + endloop + endfacet + facet normal 0.966187 -0.250871 0.0595556 + outer loop + vertex -840.43 311.569 116.694 + vertex -838.418 317.474 108.925 + vertex -838.545 318.816 116.632 + endloop + endfacet + facet normal 0.966714 -0.251097 0.0491367 + outer loop + vertex -840.43 311.569 116.694 + vertex -838.545 318.816 116.632 + vertex -840.498 312.838 124.514 + endloop + endfacet + facet normal 0.965533 -0.248707 0.0767537 + outer loop + vertex -840.324 310.072 108.922 + vertex -838.216 315.914 101.334 + vertex -838.418 317.474 108.925 + endloop + endfacet + facet normal 0.965842 -0.247086 0.0780876 + outer loop + vertex -840.136 308.391 101.273 + vertex -838.216 315.914 101.334 + vertex -840.324 310.072 108.922 + endloop + endfacet + facet normal 0.9739 -0.215473 0.0713406 + outer loop + vertex -842.078 302.029 108.574 + vertex -840.136 308.391 101.273 + vertex -840.324 310.072 108.922 + endloop + endfacet + facet normal 0.974297 -0.21286 0.0737229 + outer loop + vertex -841.88 300.266 100.857 + vertex -840.136 308.391 101.273 + vertex -842.078 302.029 108.574 + endloop + endfacet + facet normal 0.976942 -0.201299 0.0711497 + outer loop + vertex -843.776 293.497 107.751 + vertex -841.88 300.266 100.857 + vertex -842.078 302.029 108.574 + endloop + endfacet + facet normal 0.97827 -0.19998 0.0547274 + outer loop + vertex -843.776 293.497 107.751 + vertex -842.078 302.029 108.574 + vertex -843.915 295.017 115.79 + endloop + endfacet + facet normal 0.976932 -0.206113 0.0558635 + outer loop + vertex -843.776 293.497 107.751 + vertex -843.915 295.017 115.79 + vertex -844.939 289.556 113.546 + endloop + endfacet + facet normal 0.975994 -0.211496 0.0520141 + outer loop + vertex -845.109 287.848 109.79 + vertex -843.776 293.497 107.751 + vertex -844.939 289.556 113.546 + endloop + endfacet + facet normal 0.969809 -0.235529 0.0632194 + outer loop + vertex -846.021 285.004 113.183 + vertex -845.109 287.848 109.79 + vertex -844.939 289.556 113.546 + endloop + endfacet + facet normal 0.970726 -0.234757 0.0508055 + outer loop + vertex -846.021 285.004 113.183 + vertex -844.939 289.556 113.546 + vertex -845.926 286.317 117.432 + endloop + endfacet + facet normal 0.970565 -0.235574 0.050084 + outer loop + vertex -845.926 286.317 117.432 + vertex -844.939 289.556 113.546 + vertex -845.057 289.883 117.369 + endloop + endfacet + facet normal 0.970252 -0.235381 0.0566306 + outer loop + vertex -845.057 289.883 117.369 + vertex -845.644 288.716 122.573 + vertex -845.926 286.317 117.432 + endloop + endfacet + facet normal 0.956301 -0.28153 0.0789304 + outer loop + vertex -847.125 283.275 121.104 + vertex -845.926 286.317 117.432 + vertex -845.644 288.716 122.573 + endloop + endfacet + facet normal 0.959638 -0.27588 0.0546409 + outer loop + vertex -847.288 283.483 125.027 + vertex -847.125 283.275 121.104 + vertex -845.644 288.716 122.573 + endloop + endfacet + facet normal 0.958398 -0.28273 0.0392022 + outer loop + vertex -847.288 283.483 125.027 + vertex -845.644 288.716 122.573 + vertex -847.035 284.85 128.706 + endloop + endfacet + facet normal 0.960807 -0.27344 0.0456056 + outer loop + vertex -845.644 288.716 122.573 + vertex -845.633 290.142 130.897 + vertex -847.035 284.85 128.706 + endloop + endfacet + facet normal 0.961687 -0.271252 0.0397564 + outer loop + vertex -847.222 284.818 133 + vertex -847.035 284.85 128.706 + vertex -845.633 290.142 130.897 + endloop + endfacet + facet normal 0.96078 -0.275986 0.0270847 + outer loop + vertex -847.222 284.818 133 + vertex -845.633 290.142 130.897 + vertex -846.992 285.987 136.756 + endloop + endfacet + facet normal 0.962731 -0.268455 0.0328781 + outer loop + vertex -845.633 290.142 130.897 + vertex -845.614 291.198 138.94 + vertex -846.992 285.987 136.756 + endloop + endfacet + facet normal 0.962911 -0.267963 0.0315911 + outer loop + vertex -847.196 285.755 140.991 + vertex -846.992 285.987 136.756 + vertex -845.614 291.198 138.94 + endloop + endfacet + facet normal 0.962178 -0.271577 0.0214382 + outer loop + vertex -847.196 285.755 140.991 + vertex -845.614 291.198 138.94 + vertex -846.984 286.797 144.711 + endloop + endfacet + facet normal 0.963499 -0.266483 0.0256362 + outer loop + vertex -845.614 291.198 138.94 + vertex -845.617 291.947 146.871 + vertex -846.984 286.797 144.711 + endloop + endfacet + facet normal 0.963516 -0.266432 0.0255031 + outer loop + vertex -847.196 286.435 148.913 + vertex -846.984 286.797 144.711 + vertex -845.617 291.947 146.871 + endloop + endfacet + facet normal 0.962619 -0.270505 0.0138187 + outer loop + vertex -847.196 286.435 148.913 + vertex -845.617 291.947 146.871 + vertex -846.983 287.381 152.613 + endloop + endfacet + facet normal 0.964211 -0.264455 0.0190092 + outer loop + vertex -845.617 291.947 146.871 + vertex -845.627 292.476 154.731 + vertex -846.983 287.381 152.613 + endloop + endfacet + facet normal 0.964299 -0.264183 0.0182985 + outer loop + vertex -847.191 286.91 156.776 + vertex -846.983 287.381 152.613 + vertex -845.627 292.476 154.731 + endloop + endfacet + facet normal 0.963498 -0.267582 0.00843558 + outer loop + vertex -847.191 286.91 156.776 + vertex -845.627 292.476 154.731 + vertex -846.983 287.772 160.415 + endloop + endfacet + facet normal 0.964612 -0.263394 0.0121678 + outer loop + vertex -845.627 292.476 154.731 + vertex -845.634 292.812 162.517 + vertex -846.983 287.772 160.415 + endloop + endfacet + facet normal 0.964422 -0.264008 0.0137624 + outer loop + vertex -847.196 287.208 164.515 + vertex -846.983 287.772 160.415 + vertex -845.634 292.812 162.517 + endloop + endfacet + facet normal 0.963243 -0.268631 -0.000127823 + outer loop + vertex -847.196 287.208 164.515 + vertex -845.634 292.812 162.517 + vertex -846.984 287.969 168.147 + endloop + endfacet + facet normal 0.964769 -0.263049 0.00503988 + outer loop + vertex -845.634 292.812 162.517 + vertex -845.636 292.954 170.307 + vertex -846.984 287.969 168.147 + endloop + endfacet + facet normal 0.964643 -0.263488 0.00613068 + outer loop + vertex -847.193 287.297 172.279 + vertex -846.984 287.969 168.147 + vertex -845.636 292.954 170.307 + endloop + endfacet + facet normal 0.963608 -0.267262 -0.00551419 + outer loop + vertex -847.193 287.297 172.279 + vertex -845.636 292.954 170.307 + vertex -846.986 287.969 175.982 + endloop + endfacet + facet normal 0.964806 -0.262957 -0.00144839 + outer loop + vertex -845.636 292.954 170.307 + vertex -845.639 292.9 178.181 + vertex -846.986 287.969 175.982 + endloop + endfacet + facet normal 0.964555 -0.263881 0.000777055 + outer loop + vertex -847.201 287.195 180.188 + vertex -846.986 287.969 175.982 + vertex -845.639 292.9 178.181 + endloop + endfacet + facet normal 0.963165 -0.268566 -0.0136195 + outer loop + vertex -847.201 287.195 180.188 + vertex -845.639 292.9 178.181 + vertex -846.989 287.766 183.941 + endloop + endfacet + facet normal 0.964625 -0.26348 -0.00874349 + outer loop + vertex -845.639 292.9 178.181 + vertex -845.636 292.645 186.134 + vertex -846.989 287.766 183.941 + endloop + endfacet + facet normal 0.964393 -0.264391 -0.00657378 + outer loop + vertex -847.203 286.879 188.191 + vertex -846.989 287.766 183.941 + vertex -845.636 292.645 186.134 + endloop + endfacet + facet normal 0.963262 -0.267991 -0.0175299 + outer loop + vertex -847.203 286.879 188.191 + vertex -845.636 292.645 186.134 + vertex -846.999 287.365 191.949 + endloop + endfacet + facet normal 0.963802 -0.266156 -0.015737 + outer loop + vertex -845.636 292.645 186.134 + vertex -845.633 292.184 194.109 + vertex -846.999 287.365 191.949 + endloop + endfacet + facet normal 0.963569 -0.267121 -0.0134379 + outer loop + vertex -847.216 286.37 196.193 + vertex -846.999 287.365 191.949 + vertex -845.633 292.184 194.109 + endloop + endfacet + facet normal 0.962072 -0.271482 -0.0267414 + outer loop + vertex -847.216 286.37 196.193 + vertex -845.633 292.184 194.109 + vertex -847.005 286.752 199.919 + endloop + endfacet + facet normal 0.96332 -0.267399 -0.0226294 + outer loop + vertex -845.633 292.184 194.109 + vertex -845.635 291.504 202.073 + vertex -847.005 286.752 199.919 + endloop + endfacet + facet normal 0.963185 -0.268001 -0.0212159 + outer loop + vertex -847.22 285.645 204.117 + vertex -847.005 286.752 199.919 + vertex -845.635 291.504 202.073 + endloop + endfacet + facet normal 0.962075 -0.271041 -0.0307877 + outer loop + vertex -847.22 285.645 204.117 + vertex -845.635 291.504 202.073 + vertex -847.019 285.938 207.825 + endloop + endfacet + facet normal 0.962296 -0.270338 -0.0300548 + outer loop + vertex -845.635 291.504 202.073 + vertex -845.647 290.563 210.162 + vertex -847.019 285.938 207.825 + endloop + endfacet + facet normal 0.961894 -0.272164 -0.0262051 + outer loop + vertex -847.247 284.727 212.031 + vertex -847.019 285.938 207.825 + vertex -845.647 290.563 210.162 + endloop + endfacet + facet normal 0.960446 -0.275766 -0.0386907 + outer loop + vertex -847.247 284.727 212.031 + vertex -845.647 290.563 210.162 + vertex -847.059 284.837 215.911 + endloop + endfacet + facet normal 0.96017 -0.276598 -0.0395881 + outer loop + vertex -845.647 290.563 210.162 + vertex -845.69 289.152 218.968 + vertex -847.059 284.837 215.911 + endloop + endfacet + facet normal 0.959043 -0.281415 -0.032282 + outer loop + vertex -847.347 283.368 220.157 + vertex -847.059 284.837 215.911 + vertex -845.69 289.152 218.968 + endloop + endfacet + facet normal 0.956086 -0.286568 -0.0614665 + outer loop + vertex -847.347 283.368 220.157 + vertex -845.69 289.152 218.968 + vertex -847.27 282.845 223.8 + endloop + endfacet + facet normal 0.951694 -0.300842 0.0614274 + outer loop + vertex -847.201 282.159 116.819 + vertex -845.926 286.317 117.432 + vertex -847.125 283.275 121.104 + endloop + endfacet + facet normal 0.950561 -0.302062 0.07206 + outer loop + vertex -847.201 282.159 116.819 + vertex -846.021 285.004 113.183 + vertex -845.926 286.317 117.432 + endloop + endfacet + facet normal 0.947977 -0.311943 0.0634909 + outer loop + vertex -847.265 281.123 112.68 + vertex -846.021 285.004 113.183 + vertex -847.201 282.159 116.819 + endloop + endfacet + facet normal 0.946912 -0.312928 0.0737203 + outer loop + vertex -847.265 281.123 112.68 + vertex -846.043 283.98 109.118 + vertex -846.021 285.004 113.183 + endloop + endfacet + facet normal 0.945907 -0.316725 0.0703285 + outer loop + vertex -847.289 280.159 108.664 + vertex -846.043 283.98 109.118 + vertex -847.265 281.123 112.68 + endloop + endfacet + facet normal 0.944463 -0.317825 0.0835319 + outer loop + vertex -847.289 280.159 108.664 + vertex -846.004 283.063 105.184 + vertex -846.043 283.98 109.118 + endloop + endfacet + facet normal 0.943637 -0.321032 0.0805501 + outer loop + vertex -847.263 279.247 104.73 + vertex -846.004 283.063 105.184 + vertex -847.289 280.159 108.664 + endloop + endfacet + facet normal 0.941641 -0.322332 0.0970271 + outer loop + vertex -847.263 279.247 104.73 + vertex -845.918 282.159 101.347 + vertex -846.004 283.063 105.184 + endloop + endfacet + facet normal 0.94109 -0.324574 0.0948787 + outer loop + vertex -847.198 278.3 100.841 + vertex -845.918 282.159 101.347 + vertex -847.263 279.247 104.73 + endloop + endfacet + facet normal 0.938834 -0.325953 0.111106 + outer loop + vertex -847.198 278.3 100.841 + vertex -845.811 281.174 97.5594 + vertex -845.918 282.159 101.347 + endloop + endfacet + facet normal 0.939116 -0.324733 0.112294 + outer loop + vertex -847.121 277.184 96.9685 + vertex -845.811 281.174 97.5594 + vertex -847.198 278.3 100.841 + endloop + endfacet + facet normal 0.936276 -0.326396 0.129817 + outer loop + vertex -847.121 277.184 96.9685 + vertex -845.686 280.036 93.7966 + vertex -845.811 281.174 97.5594 + endloop + endfacet + facet normal 0.937204 -0.321898 0.134281 + outer loop + vertex -847.062 275.753 93.1334 + vertex -845.686 280.036 93.7966 + vertex -847.121 277.184 96.9685 + endloop + endfacet + facet normal 0.934874 -0.323117 0.146989 + outer loop + vertex -847.062 275.753 93.1334 + vertex -845.517 278.825 90.0576 + vertex -845.686 280.036 93.7966 + endloop + endfacet + facet normal 0.935785 -0.317725 0.152832 + outer loop + vertex -846.841 274.564 89.3064 + vertex -845.517 278.825 90.0576 + vertex -847.062 275.753 93.1334 + endloop + endfacet + facet normal 0.932804 -0.319311 0.167086 + outer loop + vertex -846.841 274.564 89.3064 + vertex -845.279 277.596 86.3812 + vertex -845.517 278.825 90.0576 + endloop + endfacet + facet normal 0.932906 -0.318595 0.167883 + outer loop + vertex -846.61 273.294 85.6113 + vertex -845.279 277.596 86.3812 + vertex -846.841 274.564 89.3064 + endloop + endfacet + facet normal 0.927205 -0.321252 0.192583 + outer loop + vertex -846.61 273.294 85.6113 + vertex -844.981 276.303 82.7881 + vertex -845.279 277.596 86.3812 + endloop + endfacet + facet normal 0.927526 -0.318293 0.195923 + outer loop + vertex -846.308 271.96 82.0136 + vertex -844.981 276.303 82.7881 + vertex -846.61 273.294 85.6113 + endloop + endfacet + facet normal 0.920841 -0.320835 0.221625 + outer loop + vertex -846.308 271.96 82.0136 + vertex -844.613 274.925 79.2649 + vertex -844.981 276.303 82.7881 + endloop + endfacet + facet normal 0.920948 -0.319416 0.223221 + outer loop + vertex -845.944 270.532 78.4677 + vertex -844.613 274.925 79.2649 + vertex -846.308 271.96 82.0136 + endloop + endfacet + facet normal 0.912608 -0.322079 0.251816 + outer loop + vertex -845.944 270.532 78.4677 + vertex -844.175 273.453 75.7953 + vertex -844.613 274.925 79.2649 + endloop + endfacet + facet normal 0.912712 -0.319531 0.254669 + outer loop + vertex -845.504 268.998 74.9691 + vertex -844.175 273.453 75.7953 + vertex -845.944 270.532 78.4677 + endloop + endfacet + facet normal 0.901343 -0.32252 0.289071 + outer loop + vertex -845.504 268.998 74.9691 + vertex -843.646 271.885 72.3969 + vertex -844.175 273.453 75.7953 + endloop + endfacet + facet normal 0.90134 -0.321619 0.29008 + outer loop + vertex -844.983 267.375 71.549 + vertex -843.646 271.885 72.3969 + vertex -845.504 268.998 74.9691 + endloop + endfacet + facet normal 0.886504 -0.32467 0.329697 + outer loop + vertex -844.983 267.375 71.549 + vertex -843.023 270.232 69.0939 + vertex -843.646 271.885 72.3969 + endloop + endfacet + facet normal 0.886353 -0.321878 0.332826 + outer loop + vertex -844.363 265.658 68.2388 + vertex -843.023 270.232 69.0939 + vertex -844.983 267.375 71.549 + endloop + endfacet + facet normal 0.86691 -0.32467 0.378228 + outer loop + vertex -844.363 265.658 68.2388 + vertex -842.287 268.502 65.9198 + vertex -843.023 270.232 69.0939 + endloop + endfacet + facet normal 0.866727 -0.323106 0.379982 + outer loop + vertex -843.64 263.867 65.0653 + vertex -842.287 268.502 65.9198 + vertex -844.363 265.658 68.2388 + endloop + endfacet + facet normal 0.968274 -0.24351 0.0561191 + outer loop + vertex -846.043 283.98 109.118 + vertex -845.109 287.848 109.79 + vertex -846.021 285.004 113.183 + endloop + endfacet + facet normal 0.967475 -0.244706 0.064122 + outer loop + vertex -846.043 283.98 109.118 + vertex -844.889 287.619 105.594 + vertex -845.109 287.848 109.79 + endloop + endfacet + facet normal 0.967825 -0.242742 0.0662646 + outer loop + vertex -846.004 283.063 105.184 + vertex -844.889 287.619 105.594 + vertex -846.043 283.98 109.118 + endloop + endfacet + facet normal 0.965887 -0.24409 0.086497 + outer loop + vertex -846.004 283.063 105.184 + vertex -844.973 286.009 101.99 + vertex -844.889 287.619 105.594 + endloop + endfacet + facet normal 0.973731 -0.215501 0.073541 + outer loop + vertex -844.973 286.009 101.99 + vertex -843.572 291.674 100.038 + vertex -844.889 287.619 105.594 + endloop + endfacet + facet normal 0.974245 -0.212296 0.0760017 + outer loop + vertex -843.572 291.674 100.038 + vertex -843.776 293.497 107.751 + vertex -844.889 287.619 105.594 + endloop + endfacet + facet normal 0.973623 -0.210404 0.0882553 + outer loop + vertex -844.973 286.009 101.99 + vertex -844.661 285.781 97.9983 + vertex -843.572 291.674 100.038 + endloop + endfacet + facet normal 0.971059 -0.215225 0.103551 + outer loop + vertex -843.226 289.677 92.6381 + vertex -843.572 291.674 100.038 + vertex -844.661 285.781 97.9983 + endloop + endfacet + facet normal 0.970465 -0.219366 0.100382 + outer loop + vertex -844.691 284.053 94.5176 + vertex -843.226 289.677 92.6381 + vertex -844.661 285.781 97.9983 + endloop + endfacet + facet normal 0.960949 -0.251127 0.11624 + outer loop + vertex -845.811 281.174 97.5594 + vertex -844.691 284.053 94.5176 + vertex -844.661 285.781 97.9983 + endloop + endfacet + facet normal 0.96398 -0.249571 0.091964 + outer loop + vertex -845.811 281.174 97.5594 + vertex -844.661 285.781 97.9983 + vertex -845.918 282.159 101.347 + endloop + endfacet + facet normal 0.96 -0.257578 0.109785 + outer loop + vertex -845.686 280.036 93.7966 + vertex -844.691 284.053 94.5176 + vertex -845.811 281.174 97.5594 + endloop + endfacet + facet normal 0.958262 -0.259122 0.120784 + outer loop + vertex -845.686 280.036 93.7966 + vertex -844.312 283.637 90.6176 + vertex -844.691 284.053 94.5176 + endloop + endfacet + facet normal 0.958766 -0.254773 0.125928 + outer loop + vertex -845.517 278.825 90.0576 + vertex -844.312 283.637 90.6176 + vertex -845.686 280.036 93.7966 + endloop + endfacet + facet normal 0.954392 -0.256753 0.152359 + outer loop + vertex -845.517 278.825 90.0576 + vertex -844.276 281.739 87.194 + vertex -844.312 283.637 90.6176 + endloop + endfacet + facet normal 0.964766 -0.225688 0.135246 + outer loop + vertex -844.276 281.739 87.194 + vertex -842.709 287.39 85.4477 + vertex -844.312 283.637 90.6176 + endloop + endfacet + facet normal 0.965426 -0.220298 0.139364 + outer loop + vertex -842.709 287.39 85.4477 + vertex -843.226 289.677 92.6381 + vertex -844.312 283.637 90.6176 + endloop + endfacet + facet normal 0.971481 -0.196767 0.132317 + outer loop + vertex -842.709 287.39 85.4477 + vertex -841.04 296.162 86.2358 + vertex -843.226 289.677 92.6381 + endloop + endfacet + facet normal 0.971289 -0.199734 0.129247 + outer loop + vertex -843.226 289.677 92.6381 + vertex -841.04 296.162 86.2358 + vertex -841.55 298.331 93.4222 + endloop + endfacet + facet normal 0.969497 -0.206965 0.131302 + outer loop + vertex -841.04 296.162 86.2358 + vertex -839.322 304.46 86.6334 + vertex -841.55 298.331 93.4222 + endloop + endfacet + facet normal 0.969143 -0.210863 0.127667 + outer loop + vertex -841.55 298.331 93.4222 + vertex -839.322 304.46 86.6334 + vertex -839.82 306.533 93.8367 + endloop + endfacet + facet normal 0.972774 -0.210118 0.0977763 + outer loop + vertex -841.55 298.331 93.4222 + vertex -839.82 306.533 93.8367 + vertex -841.88 300.266 100.857 + endloop + endfacet + facet normal 0.974894 -0.201135 0.0955319 + outer loop + vertex -843.572 291.674 100.038 + vertex -841.55 298.331 93.4222 + vertex -841.88 300.266 100.857 + endloop + endfacet + facet normal 0.961653 -0.238659 0.135146 + outer loop + vertex -839.322 304.46 86.6334 + vertex -837.409 312.218 86.7181 + vertex -839.82 306.533 93.8367 + endloop + endfacet + facet normal 0.961088 -0.242895 0.131572 + outer loop + vertex -839.82 306.533 93.8367 + vertex -837.409 312.218 86.7181 + vertex -837.903 314.167 93.9229 + endloop + endfacet + facet normal 0.964564 -0.243431 0.101769 + outer loop + vertex -839.82 306.533 93.8367 + vertex -837.903 314.167 93.9229 + vertex -840.136 308.391 101.273 + endloop + endfacet + facet normal 0.949073 -0.281629 0.141229 + outer loop + vertex -837.409 312.218 86.7181 + vertex -835.23 319.525 86.6473 + vertex -837.903 314.167 93.9229 + endloop + endfacet + facet normal 0.948315 -0.285819 0.137865 + outer loop + vertex -837.903 314.167 93.9229 + vertex -835.23 319.525 86.6473 + vertex -835.729 321.342 93.8456 + endloop + endfacet + facet normal 0.951769 -0.287188 0.107972 + outer loop + vertex -837.903 314.167 93.9229 + vertex -835.729 321.342 93.8456 + vertex -838.216 315.914 101.334 + endloop + endfacet + facet normal 0.950632 -0.292452 0.103779 + outer loop + vertex -838.216 315.914 101.334 + vertex -835.729 321.342 93.8456 + vertex -836.037 322.968 101.246 + endloop + endfacet + facet normal 0.952226 -0.293172 0.0855326 + outer loop + vertex -838.216 315.914 101.334 + vertex -836.037 322.968 101.246 + vertex -838.418 317.474 108.925 + endloop + endfacet + facet normal 0.951463 -0.296354 0.083019 + outer loop + vertex -838.418 317.474 108.925 + vertex -836.037 322.968 101.246 + vertex -836.246 324.416 108.817 + endloop + endfacet + facet normal 0.952521 -0.29693 0.0673516 + outer loop + vertex -838.418 317.474 108.925 + vertex -836.246 324.416 108.817 + vertex -838.545 318.816 116.632 + endloop + endfacet + facet normal 0.951694 -0.300127 0.0648173 + outer loop + vertex -838.545 318.816 116.632 + vertex -836.246 324.416 108.817 + vertex -836.377 325.664 116.516 + endloop + endfacet + facet normal 0.952231 -0.300471 0.0545262 + outer loop + vertex -838.545 318.816 116.632 + vertex -836.377 325.664 116.516 + vertex -838.63 319.955 124.409 + endloop + endfacet + facet normal 0.951527 -0.303058 0.0524546 + outer loop + vertex -838.63 319.955 124.409 + vertex -836.377 325.664 116.516 + vertex -836.464 326.737 124.298 + endloop + endfacet + facet normal 0.951884 -0.303312 0.0438113 + outer loop + vertex -838.63 319.955 124.409 + vertex -836.464 326.737 124.298 + vertex -838.687 320.908 132.242 + endloop + endfacet + facet normal 0.951168 -0.305836 0.041759 + outer loop + vertex -838.687 320.908 132.242 + vertex -836.464 326.737 124.298 + vertex -836.516 327.647 132.147 + endloop + endfacet + facet normal 0.951403 -0.306016 0.0344487 + outer loop + vertex -838.687 320.908 132.242 + vertex -836.516 327.647 132.147 + vertex -838.721 321.69 140.12 + endloop + endfacet + facet normal 0.950809 -0.30804 0.0327725 + outer loop + vertex -838.721 321.69 140.12 + vertex -836.516 327.647 132.147 + vertex -836.546 328.396 140.037 + endloop + endfacet + facet normal 0.950946 -0.308152 0.0272745 + outer loop + vertex -838.721 321.69 140.12 + vertex -836.546 328.396 140.037 + vertex -838.745 322.313 148.007 + endloop + endfacet + facet normal 0.950569 -0.309404 0.0262151 + outer loop + vertex -838.745 322.313 148.007 + vertex -836.546 328.396 140.037 + vertex -836.57 328.988 147.927 + endloop + endfacet + facet normal 0.950689 -0.309521 0.0196547 + outer loop + vertex -838.745 322.313 148.007 + vertex -836.57 328.988 147.927 + vertex -838.762 322.761 155.866 + endloop + endfacet + facet normal 0.950247 -0.310952 0.0184099 + outer loop + vertex -838.762 322.761 155.866 + vertex -836.57 328.988 147.927 + vertex -836.586 329.407 155.785 + endloop + endfacet + facet normal 0.950309 -0.31104 0.0129364 + outer loop + vertex -838.762 322.761 155.866 + vertex -836.586 329.407 155.785 + vertex -838.776 323.043 163.692 + endloop + endfacet + facet normal 0.949839 -0.312523 0.0116127 + outer loop + vertex -838.776 323.043 163.692 + vertex -836.586 329.407 155.785 + vertex -836.597 329.663 163.607 + endloop + endfacet + facet normal 0.949866 -0.312635 0.00356531 + outer loop + vertex -838.776 323.043 163.692 + vertex -836.597 329.663 163.607 + vertex -838.775 323.137 171.515 + endloop + endfacet + facet normal 0.950139 -0.311797 0.00433279 + outer loop + vertex -838.775 323.137 171.515 + vertex -836.597 329.663 163.607 + vertex -836.601 329.76 171.43 + endloop + endfacet + facet normal 0.950114 -0.311886 -0.00325668 + outer loop + vertex -838.775 323.137 171.515 + vertex -836.601 329.76 171.43 + vertex -838.771 323.066 179.382 + endloop + endfacet + facet normal 0.950123 -0.311858 -0.00323039 + outer loop + vertex -838.771 323.066 179.382 + vertex -836.601 329.76 171.43 + vertex -836.596 329.693 179.3 + endloop + endfacet + facet normal 0.950025 -0.311936 -0.0121741 + outer loop + vertex -838.771 323.066 179.382 + vertex -836.596 329.693 179.3 + vertex -838.756 322.801 187.319 + endloop + endfacet + facet normal 0.95026 -0.311245 -0.0115171 + outer loop + vertex -838.756 322.801 187.319 + vertex -836.596 329.693 179.3 + vertex -836.58 329.45 187.243 + endloop + endfacet + facet normal 0.950122 -0.311288 -0.0192014 + outer loop + vertex -838.756 322.801 187.319 + vertex -836.58 329.45 187.243 + vertex -838.742 322.351 195.311 + endloop + endfacet + facet normal 0.950634 -0.309805 -0.0177593 + outer loop + vertex -838.742 322.351 195.311 + vertex -836.58 329.45 187.243 + vertex -836.563 329.042 195.235 + endloop + endfacet + facet normal 0.950395 -0.309836 -0.0273973 + outer loop + vertex -838.742 322.351 195.311 + vertex -836.563 329.042 195.235 + vertex -838.72 321.711 203.306 + endloop + endfacet + facet normal 0.951203 -0.307543 -0.0250986 + outer loop + vertex -838.72 321.711 203.306 + vertex -836.563 329.042 195.235 + vertex -836.539 328.466 203.228 + endloop + endfacet + facet normal 0.95093 -0.307555 -0.0337857 + outer loop + vertex -838.72 321.711 203.306 + vertex -836.539 328.466 203.228 + vertex -838.696 320.913 211.248 + endloop + endfacet + facet normal 0.951616 -0.305639 -0.0317965 + outer loop + vertex -838.696 320.913 211.248 + vertex -836.539 328.466 203.228 + vertex -836.507 327.736 211.169 + endloop + endfacet + facet normal 0.951178 -0.305629 -0.0430358 + outer loop + vertex -838.696 320.913 211.248 + vertex -836.507 327.736 211.169 + vertex -838.651 319.947 219.1 + endloop + endfacet + facet normal 0.95212 -0.303063 -0.0402618 + outer loop + vertex -838.651 319.947 219.1 + vertex -836.507 327.736 211.169 + vertex -836.458 326.846 219.027 + endloop + endfacet + facet normal 0.951501 -0.303004 -0.0532399 + outer loop + vertex -838.651 319.947 219.1 + vertex -836.458 326.846 219.027 + vertex -838.574 318.824 226.869 + endloop + endfacet + facet normal 0.952846 -0.299436 -0.0492275 + outer loop + vertex -838.574 318.824 226.869 + vertex -836.458 326.846 219.027 + vertex -836.387 325.794 226.804 + endloop + endfacet + facet normal 0.951871 -0.299289 -0.0660828 + outer loop + vertex -838.574 318.824 226.869 + vertex -836.387 325.794 226.804 + vertex -838.446 317.531 234.57 + endloop + endfacet + facet normal 0.953106 -0.296134 -0.0623987 + outer loop + vertex -838.446 317.531 234.57 + vertex -836.387 325.794 226.804 + vertex -836.269 324.551 234.505 + endloop + endfacet + facet normal 0.951413 -0.295824 -0.0854438 + outer loop + vertex -838.446 317.531 234.57 + vertex -836.269 324.551 234.505 + vertex -838.233 316.014 242.193 + endloop + endfacet + facet normal 0.953027 -0.291934 -0.0807116 + outer loop + vertex -838.233 316.014 242.193 + vertex -836.269 324.551 234.505 + vertex -836.067 323.104 242.123 + endloop + endfacet + facet normal 0.950268 -0.291381 -0.109948 + outer loop + vertex -838.233 316.014 242.193 + vertex -836.067 323.104 242.123 + vertex -837.898 314.272 249.707 + endloop + endfacet + facet normal 0.953194 -0.28479 -0.101565 + outer loop + vertex -837.898 314.272 249.707 + vertex -836.067 323.104 242.123 + vertex -835.751 321.483 249.634 + endloop + endfacet + facet normal 0.948575 -0.283805 -0.140215 + outer loop + vertex -837.898 314.272 249.707 + vertex -835.751 321.483 249.634 + vertex -837.395 312.317 257.07 + endloop + endfacet + facet normal 0.950027 -0.280858 -0.136261 + outer loop + vertex -837.395 312.317 257.07 + vertex -835.751 321.483 249.634 + vertex -835.238 319.65 256.992 + endloop + endfacet + facet normal 0.941927 -0.279057 0.186817 + outer loop + vertex -837.409 312.218 86.7181 + vertex -834.443 317.491 79.6382 + vertex -835.23 319.525 86.6473 + endloop + endfacet + facet normal 0.927001 -0.319274 0.196808 + outer loop + vertex -834.443 317.491 79.6382 + vertex -831.955 324.671 79.5672 + vertex -835.23 319.525 86.6473 + endloop + endfacet + facet normal 0.92594 -0.325236 0.191983 + outer loop + vertex -835.23 319.525 86.6473 + vertex -831.955 324.671 79.5672 + vertex -832.755 326.527 86.5718 + endloop + endfacet + facet normal 0.933014 -0.328217 0.147507 + outer loop + vertex -835.23 319.525 86.6473 + vertex -832.755 326.527 86.5718 + vertex -835.729 321.342 93.8456 + endloop + endfacet + facet normal 0.931408 -0.335182 0.141885 + outer loop + vertex -835.729 321.342 93.8456 + vertex -832.755 326.527 86.5718 + vertex -833.249 328.203 93.774 + endloop + endfacet + facet normal 0.934819 -0.336718 0.112849 + outer loop + vertex -835.729 321.342 93.8456 + vertex -833.249 328.203 93.774 + vertex -836.037 322.968 101.246 + endloop + endfacet + facet normal 0.933737 -0.340765 0.109609 + outer loop + vertex -836.037 322.968 101.246 + vertex -833.249 328.203 93.774 + vertex -833.562 329.727 101.176 + endloop + endfacet + facet normal 0.935418 -0.34157 0.0912264 + outer loop + vertex -836.037 322.968 101.246 + vertex -833.562 329.727 101.176 + vertex -836.246 324.416 108.817 + endloop + endfacet + facet normal 0.933796 -0.347116 0.0868021 + outer loop + vertex -836.246 324.416 108.817 + vertex -833.562 329.727 101.176 + vertex -833.765 331.078 108.759 + endloop + endfacet + facet normal 0.934845 -0.347632 0.0722275 + outer loop + vertex -836.246 324.416 108.817 + vertex -833.765 331.078 108.759 + vertex -836.377 325.664 116.516 + endloop + endfacet + facet normal 0.933385 -0.35228 0.0684922 + outer loop + vertex -836.377 325.664 116.516 + vertex -833.765 331.078 108.759 + vertex -833.89 332.244 116.473 + endloop + endfacet + facet normal 0.933927 -0.352547 0.059083 + outer loop + vertex -836.377 325.664 116.516 + vertex -833.89 332.244 116.473 + vertex -836.464 326.737 124.298 + endloop + endfacet + facet normal 0.932505 -0.356856 0.0555826 + outer loop + vertex -836.464 326.737 124.298 + vertex -833.89 332.244 116.473 + vertex -833.97 333.249 124.27 + endloop + endfacet + facet normal 0.932879 -0.357033 0.0475732 + outer loop + vertex -836.464 326.737 124.298 + vertex -833.97 333.249 124.27 + vertex -836.516 327.647 132.147 + endloop + endfacet + facet normal 0.93161 -0.36072 0.044541 + outer loop + vertex -836.516 327.647 132.147 + vertex -833.97 333.249 124.27 + vertex -834.017 334.099 132.129 + endloop + endfacet + facet normal 0.931866 -0.360837 0.0377129 + outer loop + vertex -836.516 327.647 132.147 + vertex -834.017 334.099 132.129 + vertex -836.546 328.396 140.037 + endloop + endfacet + facet normal 0.931135 -0.362893 0.035997 + outer loop + vertex -836.546 328.396 140.037 + vertex -834.017 334.099 132.129 + vertex -834.049 334.799 140.021 + endloop + endfacet + facet normal 0.93131 -0.362975 0.0301738 + outer loop + vertex -836.546 328.396 140.037 + vertex -834.049 334.799 140.021 + vertex -836.57 328.988 147.927 + endloop + endfacet + facet normal 0.930107 -0.366268 0.0273696 + outer loop + vertex -836.57 328.988 147.927 + vertex -834.049 334.799 140.021 + vertex -834.07 335.337 147.91 + endloop + endfacet + facet normal 0.930238 -0.366336 0.0213243 + outer loop + vertex -836.57 328.988 147.927 + vertex -834.07 335.337 147.91 + vertex -836.586 329.407 155.785 + endloop + endfacet + facet normal 0.929806 -0.367489 0.0203182 + outer loop + vertex -836.586 329.407 155.785 + vertex -834.07 335.337 147.91 + vertex -834.088 335.725 155.765 + endloop + endfacet + facet normal 0.929907 -0.367551 0.0133887 + outer loop + vertex -836.586 329.407 155.785 + vertex -834.088 335.725 155.765 + vertex -836.597 329.663 163.607 + endloop + endfacet + facet normal 0.929606 -0.368336 0.0126859 + outer loop + vertex -836.597 329.663 163.607 + vertex -834.088 335.725 155.765 + vertex -834.101 335.962 163.585 + endloop + endfacet + facet normal 0.92966 -0.368384 0.00502131 + outer loop + vertex -836.597 329.663 163.607 + vertex -834.101 335.962 163.585 + vertex -836.601 329.76 171.43 + endloop + endfacet + facet normal 0.929425 -0.368985 0.00447073 + outer loop + vertex -836.601 329.76 171.43 + vertex -834.101 335.962 163.585 + vertex -834.104 336.049 171.408 + endloop + endfacet + facet normal 0.929418 -0.369011 -0.00370154 + outer loop + vertex -836.601 329.76 171.43 + vertex -834.104 336.049 171.408 + vertex -836.596 329.693 179.3 + endloop + endfacet + facet normal 0.929218 -0.369508 -0.00416489 + outer loop + vertex -836.596 329.693 179.3 + vertex -834.104 336.049 171.408 + vertex -834.096 335.981 179.281 + endloop + endfacet + facet normal 0.929135 -0.369502 -0.0132615 + outer loop + vertex -836.596 329.693 179.3 + vertex -834.096 335.981 179.281 + vertex -836.58 329.45 187.243 + endloop + endfacet + facet normal 0.930221 -0.366843 -0.0107409 + outer loop + vertex -836.58 329.45 187.243 + vertex -834.096 335.981 179.281 + vertex -834.087 335.77 187.222 + endloop + endfacet + facet normal 0.930066 -0.366814 -0.0206227 + outer loop + vertex -836.58 329.45 187.243 + vertex -834.087 335.77 187.222 + vertex -836.563 329.042 195.235 + endloop + endfacet + facet normal 0.930444 -0.365902 -0.0197402 + outer loop + vertex -836.563 329.042 195.235 + vertex -834.087 335.77 187.222 + vertex -834.066 335.394 195.211 + endloop + endfacet + facet normal 0.930215 -0.365849 -0.0292405 + outer loop + vertex -836.563 329.042 195.235 + vertex -834.066 335.394 195.211 + vertex -836.539 328.466 203.228 + endloop + endfacet + facet normal 0.931139 -0.363658 -0.0270627 + outer loop + vertex -836.539 328.466 203.228 + vertex -834.066 335.394 195.211 + vertex -834.04 334.866 203.194 + endloop + endfacet + facet normal 0.930823 -0.363589 -0.0370379 + outer loop + vertex -836.539 328.466 203.228 + vertex -834.04 334.866 203.194 + vertex -836.507 327.736 211.169 + endloop + endfacet + facet normal 0.932104 -0.360595 -0.0339651 + outer loop + vertex -836.507 327.736 211.169 + vertex -834.04 334.866 203.194 + vertex -834.011 334.193 211.122 + endloop + endfacet + facet normal 0.931596 -0.360491 -0.0466394 + outer loop + vertex -836.507 327.736 211.169 + vertex -834.011 334.193 211.122 + vertex -836.458 326.846 219.027 + endloop + endfacet + facet normal 0.93303 -0.357202 -0.0431393 + outer loop + vertex -836.458 326.846 219.027 + vertex -834.011 334.193 211.122 + vertex -833.968 333.358 218.97 + endloop + endfacet + facet normal 0.93235 -0.357062 -0.0568356 + outer loop + vertex -836.458 326.846 219.027 + vertex -833.968 333.358 218.97 + vertex -836.387 325.794 226.804 + endloop + endfacet + facet normal 0.934038 -0.353272 -0.0526551 + outer loop + vertex -836.387 325.794 226.804 + vertex -833.968 333.358 218.97 + vertex -833.906 332.365 226.739 + endloop + endfacet + facet normal 0.932896 -0.353025 -0.0712697 + outer loop + vertex -836.387 325.794 226.804 + vertex -833.906 332.365 226.739 + vertex -836.269 324.551 234.505 + endloop + endfacet + facet normal 0.934444 -0.349668 -0.0674215 + outer loop + vertex -836.269 324.551 234.505 + vertex -833.906 332.365 226.739 + vertex -833.791 331.189 234.433 + endloop + endfacet + facet normal 0.9326 -0.349236 -0.0910563 + outer loop + vertex -836.269 324.551 234.505 + vertex -833.791 331.189 234.433 + vertex -836.067 323.104 242.123 + endloop + endfacet + facet normal 0.935649 -0.342912 -0.0835052 + outer loop + vertex -836.067 323.104 242.123 + vertex -833.791 331.189 234.433 + vertex -833.6 329.856 242.046 + endloop + endfacet + facet normal 0.932794 -0.342205 -0.113094 + outer loop + vertex -836.067 323.104 242.123 + vertex -833.6 329.856 242.046 + vertex -835.751 321.483 249.634 + endloop + endfacet + facet normal 0.935709 -0.336485 -0.105956 + outer loop + vertex -835.751 321.483 249.634 + vertex -833.6 329.856 242.046 + vertex -833.285 328.368 249.552 + endloop + endfacet + facet normal 0.930423 -0.335093 -0.148409 + outer loop + vertex -835.751 321.483 249.634 + vertex -833.285 328.368 249.552 + vertex -835.238 319.65 256.992 + endloop + endfacet + facet normal 0.935166 -0.326569 -0.137174 + outer loop + vertex -835.238 319.65 256.992 + vertex -833.285 328.368 249.552 + vertex -832.784 326.707 256.918 + endloop + endfacet + facet normal 0.912355 -0.406412 0.0493664 + outer loop + vertex -833.97 333.249 124.27 + vertex -831.193 339.488 124.293 + vertex -834.017 334.099 132.129 + endloop + endfacet + facet normal 0.910416 -0.411198 0.0453756 + outer loop + vertex -834.017 334.099 132.129 + vertex -831.193 339.488 124.293 + vertex -831.237 340.257 132.153 + endloop + endfacet + facet normal 0.910625 -0.411272 0.0402042 + outer loop + vertex -834.017 334.099 132.129 + vertex -831.237 340.257 132.153 + vertex -834.049 334.799 140.021 + endloop + endfacet + facet normal 0.908482 -0.416379 0.0358955 + outer loop + vertex -834.049 334.799 140.021 + vertex -831.237 340.257 132.153 + vertex -831.263 340.88 140.044 + endloop + endfacet + facet normal 0.908646 -0.416435 0.030736 + outer loop + vertex -834.049 334.799 140.021 + vertex -831.263 340.88 140.044 + vertex -834.07 335.337 147.91 + endloop + endfacet + facet normal 0.907646 -0.418752 0.0287463 + outer loop + vertex -834.07 335.337 147.91 + vertex -831.263 340.88 140.044 + vertex -831.287 341.37 147.931 + endloop + endfacet + facet normal 0.907793 -0.418799 0.0227999 + outer loop + vertex -834.07 335.337 147.91 + vertex -831.287 341.37 147.931 + vertex -834.088 335.725 155.765 + endloop + endfacet + facet normal 0.906518 -0.421681 0.0202673 + outer loop + vertex -834.088 335.725 155.765 + vertex -831.287 341.37 147.931 + vertex -831.302 341.715 155.785 + endloop + endfacet + facet normal 0.90662 -0.421708 0.0142681 + outer loop + vertex -834.088 335.725 155.765 + vertex -831.302 341.715 155.785 + vertex -834.101 335.962 163.585 + endloop + endfacet + facet normal 0.906079 -0.422903 0.0131928 + outer loop + vertex -834.101 335.962 163.585 + vertex -831.302 341.715 155.785 + vertex -831.316 341.93 163.605 + endloop + endfacet + facet normal 0.906157 -0.422912 0.00505958 + outer loop + vertex -834.101 335.962 163.585 + vertex -831.316 341.93 163.605 + vertex -834.104 336.049 171.408 + endloop + endfacet + facet normal 0.905724 -0.423848 0.00419957 + outer loop + vertex -834.104 336.049 171.408 + vertex -831.316 341.93 163.605 + vertex -831.318 342.004 171.428 + endloop + endfacet + facet normal 0.905733 -0.423823 -0.00461205 + outer loop + vertex -834.104 336.049 171.408 + vertex -831.318 342.004 171.428 + vertex -834.096 335.981 179.281 + endloop + endfacet + facet normal 0.906475 -0.422248 -0.00314188 + outer loop + vertex -834.096 335.981 179.281 + vertex -831.318 342.004 171.428 + vertex -831.316 341.948 179.3 + endloop + endfacet + facet normal 0.906423 -0.422195 -0.0121812 + outer loop + vertex -834.096 335.981 179.281 + vertex -831.316 341.948 179.3 + vertex -834.087 335.77 187.222 + endloop + endfacet + facet normal 0.906259 -0.422537 -0.0125053 + outer loop + vertex -834.087 335.77 187.222 + vertex -831.316 341.948 179.3 + vertex -831.302 341.744 187.241 + endloop + endfacet + facet normal 0.906117 -0.422438 -0.0223383 + outer loop + vertex -834.087 335.77 187.222 + vertex -831.302 341.744 187.241 + vertex -834.066 335.394 195.211 + endloop + endfacet + facet normal 0.907457 -0.419683 -0.0196782 + outer loop + vertex -834.066 335.394 195.211 + vertex -831.302 341.744 187.241 + vertex -831.285 341.406 195.225 + endloop + endfacet + facet normal 0.907216 -0.419546 -0.0306803 + outer loop + vertex -834.066 335.394 195.211 + vertex -831.285 341.406 195.225 + vertex -834.04 334.866 203.194 + endloop + endfacet + facet normal 0.908429 -0.417085 -0.0282414 + outer loop + vertex -834.04 334.866 203.194 + vertex -831.285 341.406 195.225 + vertex -831.26 340.92 203.199 + endloop + endfacet + facet normal 0.908115 -0.416932 -0.0386578 + outer loop + vertex -834.04 334.866 203.194 + vertex -831.26 340.92 203.199 + vertex -834.011 334.193 211.122 + endloop + endfacet + facet normal 0.909801 -0.413549 -0.0352002 + outer loop + vertex -834.011 334.193 211.122 + vertex -831.26 340.92 203.199 + vertex -831.235 340.3 211.118 + endloop + endfacet + facet normal 0.90927 -0.413315 -0.0489809 + outer loop + vertex -834.011 334.193 211.122 + vertex -831.235 340.3 211.118 + vertex -833.968 333.358 218.97 + endloop + endfacet + facet normal 0.911253 -0.409401 -0.0448301 + outer loop + vertex -833.968 333.358 218.97 + vertex -831.235 340.3 211.118 + vertex -831.197 339.528 218.959 + endloop + endfacet + facet normal 0.910537 -0.409107 -0.0596086 + outer loop + vertex -833.968 333.358 218.97 + vertex -831.197 339.528 218.959 + vertex -833.906 332.365 226.739 + endloop + endfacet + facet normal 0.912783 -0.404749 -0.0548141 + outer loop + vertex -833.906 332.365 226.739 + vertex -831.197 339.528 218.959 + vertex -831.136 338.614 226.722 + endloop + endfacet + facet normal 0.911533 -0.404251 -0.0754168 + outer loop + vertex -833.906 332.365 226.739 + vertex -831.136 338.614 226.722 + vertex -833.791 331.189 234.433 + endloop + endfacet + facet normal 0.915222 -0.39727 -0.067425 + outer loop + vertex -833.791 331.189 234.433 + vertex -831.136 338.614 226.722 + vertex -831.03 337.553 234.413 + endloop + endfacet + facet normal 0.913362 -0.39654 -0.0923375 + outer loop + vertex -833.791 331.189 234.433 + vertex -831.03 337.553 234.413 + vertex -833.6 329.856 242.046 + endloop + endfacet + facet normal 0.916399 -0.390983 -0.0857103 + outer loop + vertex -833.6 329.856 242.046 + vertex -831.03 337.553 234.413 + vertex -830.835 336.341 242.023 + endloop + endfacet + facet normal 0.913577 -0.389885 -0.115615 + outer loop + vertex -833.6 329.856 242.046 + vertex -830.835 336.341 242.023 + vertex -833.285 328.368 249.552 + endloop + endfacet + facet normal 0.917474 -0.383092 -0.107154 + outer loop + vertex -833.285 328.368 249.552 + vertex -830.835 336.341 242.023 + vertex -830.52 334.997 249.526 + endloop + endfacet + facet normal 0.912572 -0.381209 -0.14796 + outer loop + vertex -833.285 328.368 249.552 + vertex -830.52 334.997 249.526 + vertex -832.784 326.707 256.918 + endloop + endfacet + facet normal 0.917759 -0.372787 -0.136925 + outer loop + vertex -832.784 326.707 256.918 + vertex -830.52 334.997 249.526 + vertex -830.025 333.51 256.892 + endloop + endfacet + facet normal 0.896117 -0.419497 -0.144902 + outer loop + vertex -830.52 334.997 249.526 + vertex -827.509 341.425 249.54 + vertex -830.025 333.51 256.892 + endloop + endfacet + facet normal 0.900875 -0.412359 -0.135589 + outer loop + vertex -830.025 333.51 256.892 + vertex -827.509 341.425 249.54 + vertex -827.006 340.103 256.899 + endloop + endfacet + facet normal 0.880056 -0.453291 -0.141521 + outer loop + vertex -827.509 341.425 249.54 + vertex -824.285 347.678 249.557 + vertex -827.006 340.103 256.899 + endloop + endfacet + facet normal 0.887477 -0.442751 -0.127894 + outer loop + vertex -827.006 340.103 256.899 + vertex -824.285 347.678 249.557 + vertex -823.789 346.548 256.913 + endloop + endfacet + facet normal 0.868054 -0.478576 -0.132087 + outer loop + vertex -824.285 347.678 249.557 + vertex -820.898 353.819 249.564 + vertex -823.789 346.548 256.913 + endloop + endfacet + facet normal 0.87591 -0.46775 -0.118287 + outer loop + vertex -823.789 346.548 256.913 + vertex -820.898 353.819 249.564 + vertex -820.402 352.888 256.918 + endloop + endfacet + facet normal 0.858243 -0.49877 -0.121023 + outer loop + vertex -820.898 353.819 249.564 + vertex -817.378 359.877 249.562 + vertex -820.402 352.888 256.918 + endloop + endfacet + facet normal 0.86631 -0.48784 -0.107321 + outer loop + vertex -820.402 352.888 256.918 + vertex -817.378 359.877 249.562 + vertex -816.879 359.147 256.912 + endloop + endfacet + facet normal 0.850485 -0.514601 -0.108905 + outer loop + vertex -817.378 359.877 249.562 + vertex -813.756 365.864 249.556 + vertex -816.879 359.147 256.912 + endloop + endfacet + facet normal 0.859176 -0.502877 -0.0945094 + outer loop + vertex -816.879 359.147 256.912 + vertex -813.756 365.864 249.556 + vertex -813.259 365.333 256.903 + endloop + endfacet + facet normal 0.847638 -0.521981 -0.0951066 + outer loop + vertex -813.756 365.864 249.556 + vertex -810.095 371.808 249.564 + vertex -813.259 365.333 256.903 + endloop + endfacet + facet normal 0.856826 -0.50936 -0.0800109 + outer loop + vertex -813.259 365.333 256.903 + vertex -810.095 371.808 249.564 + vertex -809.605 371.477 256.923 + endloop + endfacet + facet normal 0.864073 -0.496979 -0.0799353 + outer loop + vertex -810.095 371.808 249.564 + vertex -806.607 377.855 249.672 + vertex -809.605 371.477 256.923 + endloop + endfacet + facet normal 0.871094 -0.48642 -0.0677469 + outer loop + vertex -809.605 371.477 256.923 + vertex -806.607 377.855 249.672 + vertex -806.114 377.711 257.044 + endloop + endfacet + facet normal 0.867151 -0.483187 -0.120747 + outer loop + vertex -809.605 371.477 256.923 + vertex -806.114 377.711 257.044 + vertex -808.836 371.057 264.122 + endloop + endfacet + facet normal 0.860823 -0.494378 -0.120724 + outer loop + vertex -812.492 364.703 264.08 + vertex -809.605 371.477 256.923 + vertex -808.836 371.057 264.122 + endloop + endfacet + facet normal 0.851733 -0.506145 -0.135529 + outer loop + vertex -813.259 365.333 256.903 + vertex -809.605 371.477 256.923 + vertex -812.492 364.703 264.08 + endloop + endfacet + facet normal 0.863584 -0.485794 -0.135007 + outer loop + vertex -816.099 358.289 264.082 + vertex -813.259 365.333 256.903 + vertex -812.492 364.703 264.08 + endloop + endfacet + facet normal 0.85291 -0.499295 -0.152478 + outer loop + vertex -816.879 359.147 256.912 + vertex -813.259 365.333 256.903 + vertex -816.099 358.289 264.082 + endloop + endfacet + facet normal 0.868925 -0.471386 -0.150879 + outer loop + vertex -819.618 351.799 264.09 + vertex -816.879 359.147 256.912 + vertex -816.099 358.289 264.082 + endloop + endfacet + facet normal 0.859027 -0.4838 -0.167364 + outer loop + vertex -820.402 352.888 256.918 + vertex -816.879 359.147 256.912 + vertex -819.618 351.799 264.09 + endloop + endfacet + facet normal 0.876502 -0.452416 -0.164512 + outer loop + vertex -823.007 345.236 264.088 + vertex -820.402 352.888 256.918 + vertex -819.618 351.799 264.09 + endloop + endfacet + facet normal 0.867817 -0.463379 -0.179368 + outer loop + vertex -823.789 346.548 256.913 + vertex -820.402 352.888 256.918 + vertex -823.007 345.236 264.088 + endloop + endfacet + facet normal 0.885829 -0.429679 -0.175167 + outer loop + vertex -826.233 338.587 264.08 + vertex -823.789 346.548 256.913 + vertex -823.007 345.236 264.088 + endloop + endfacet + facet normal 0.879065 -0.438417 -0.187179 + outer loop + vertex -827.006 340.103 256.899 + vertex -823.789 346.548 256.913 + vertex -826.233 338.587 264.08 + endloop + endfacet + facet normal 0.89941 -0.397949 -0.180827 + outer loop + vertex -829.244 331.785 264.073 + vertex -827.006 340.103 256.899 + vertex -826.233 338.587 264.08 + endloop + endfacet + facet normal 0.891837 -0.408158 -0.195025 + outer loop + vertex -830.025 333.51 256.892 + vertex -827.006 340.103 256.899 + vertex -829.244 331.785 264.073 + endloop + endfacet + facet normal 0.913438 -0.36186 -0.18625 + outer loop + vertex -832.008 324.796 264.098 + vertex -830.025 333.51 256.892 + vertex -829.244 331.785 264.073 + endloop + endfacet + facet normal 0.908334 -0.369197 -0.196527 + outer loop + vertex -832.784 326.707 256.918 + vertex -830.025 333.51 256.892 + vertex -832.008 324.796 264.098 + endloop + endfacet + facet normal 0.874749 -0.472449 -0.10773 + outer loop + vertex -808.836 371.057 264.122 + vertex -806.114 377.711 257.044 + vertex -805.332 377.51 264.28 + endloop + endfacet + facet normal 0.915338 -0.387441 -0.109751 + outer loop + vertex -806.114 377.711 257.044 + vertex -803.272 384.345 257.329 + vertex -805.332 377.51 264.28 + endloop + endfacet + facet normal 0.924033 -0.371259 -0.0912619 + outer loop + vertex -805.332 377.51 264.28 + vertex -803.272 384.345 257.329 + vertex -802.509 384.408 264.801 + endloop + endfacet + facet normal 0.918543 -0.391031 -0.0580896 + outer loop + vertex -806.114 377.711 257.044 + vertex -803.757 384.293 250.007 + vertex -803.272 384.345 257.329 + endloop + endfacet + facet normal 0.913558 -0.400826 -0.0689197 + outer loop + vertex -806.607 377.855 249.672 + vertex -803.757 384.293 250.007 + vertex -806.114 377.711 257.044 + endloop + endfacet + facet normal 0.914521 -0.403012 -0.0351134 + outer loop + vertex -806.607 377.855 249.672 + vertex -804.064 384.246 242.56 + vertex -803.757 384.293 250.007 + endloop + endfacet + facet normal 0.910562 -0.41105 -0.0437536 + outer loop + vertex -806.91 377.984 242.158 + vertex -804.064 384.246 242.56 + vertex -806.607 377.855 249.672 + endloop + endfacet + facet normal 0.910672 -0.412694 -0.0189524 + outer loop + vertex -806.91 377.984 242.158 + vertex -804.245 384.204 234.765 + vertex -804.064 384.246 242.56 + endloop + endfacet + facet normal 0.906359 -0.421581 -0.0279842 + outer loop + vertex -807.084 378.114 234.544 + vertex -804.245 384.204 234.765 + vertex -806.91 377.984 242.158 + endloop + endfacet + facet normal 0.859525 -0.510303 -0.0284229 + outer loop + vertex -810.396 372.117 242.075 + vertex -807.084 378.114 234.544 + vertex -806.91 377.984 242.158 + endloop + endfacet + facet normal 0.858713 -0.50944 -0.0555312 + outer loop + vertex -810.396 372.117 242.075 + vertex -806.91 377.984 242.158 + vertex -810.095 371.808 249.564 + endloop + endfacet + facet normal 0.852223 -0.5216 -0.0406285 + outer loop + vertex -810.575 372.416 234.479 + vertex -807.084 378.114 234.544 + vertex -810.396 372.117 242.075 + endloop + endfacet + facet normal 0.842897 -0.536511 -0.0409938 + outer loop + vertex -814.063 366.356 242.069 + vertex -810.575 372.416 234.479 + vertex -810.396 372.117 242.075 + endloop + endfacet + facet normal 0.841568 -0.535635 -0.0697041 + outer loop + vertex -814.063 366.356 242.069 + vertex -810.396 372.117 242.075 + vertex -813.756 365.864 249.556 + endloop + endfacet + facet normal 0.834795 -0.547923 -0.0538293 + outer loop + vertex -814.248 366.821 234.47 + vertex -810.575 372.416 234.479 + vertex -814.063 366.356 242.069 + endloop + endfacet + facet normal 0.847039 -0.528886 -0.0529624 + outer loop + vertex -817.687 360.552 242.071 + vertex -814.248 366.821 234.47 + vertex -814.063 366.356 242.069 + endloop + endfacet + facet normal 0.84534 -0.527831 -0.082434 + outer loop + vertex -817.687 360.552 242.071 + vertex -814.063 366.356 242.069 + vertex -817.378 359.877 249.562 + endloop + endfacet + facet normal 0.839037 -0.540079 -0.0658128 + outer loop + vertex -817.877 361.183 234.468 + vertex -814.248 366.821 234.47 + vertex -817.687 360.552 242.071 + endloop + endfacet + facet normal 0.855836 -0.513271 -0.0640068 + outer loop + vertex -821.21 354.677 242.071 + vertex -817.877 361.183 234.468 + vertex -817.687 360.552 242.071 + endloop + endfacet + facet normal 0.853781 -0.512041 -0.0941945 + outer loop + vertex -821.21 354.677 242.071 + vertex -817.687 360.552 242.071 + vertex -820.898 353.819 249.564 + endloop + endfacet + facet normal 0.849363 -0.522492 -0.074735 + outer loop + vertex -821.398 355.46 234.465 + vertex -817.877 361.183 234.468 + vertex -821.21 354.677 242.071 + endloop + endfacet + facet normal 0.867913 -0.49147 -0.0719988 + outer loop + vertex -824.594 348.703 242.061 + vertex -821.398 355.46 234.465 + vertex -821.21 354.677 242.071 + endloop + endfacet + facet normal 0.865593 -0.490103 -0.102706 + outer loop + vertex -824.594 348.703 242.061 + vertex -821.21 354.677 242.071 + vertex -824.285 347.678 249.557 + endloop + endfacet + facet normal 0.861495 -0.50092 -0.0831065 + outer loop + vertex -824.785 349.637 234.454 + vertex -821.398 355.46 234.465 + vertex -824.594 348.703 242.061 + endloop + endfacet + facet normal 0.881437 -0.465602 -0.0792697 + outer loop + vertex -827.816 342.607 242.04 + vertex -824.785 349.637 234.454 + vertex -824.594 348.703 242.061 + endloop + endfacet + facet normal 0.878974 -0.464198 -0.109206 + outer loop + vertex -827.816 342.607 242.04 + vertex -824.594 348.703 242.061 + vertex -827.509 341.425 249.54 + endloop + endfacet + facet normal 0.876435 -0.47333 -0.0884309 + outer loop + vertex -828.005 343.678 234.431 + vertex -824.785 349.637 234.454 + vertex -827.816 342.607 242.04 + endloop + endfacet + facet normal 0.897858 -0.432353 -0.0831964 + outer loop + vertex -830.835 336.341 242.023 + vertex -828.005 343.678 234.431 + vertex -827.816 342.607 242.04 + endloop + endfacet + facet normal 0.89506 -0.430922 -0.114775 + outer loop + vertex -830.835 336.341 242.023 + vertex -827.816 342.607 242.04 + vertex -830.52 334.997 249.526 + endloop + endfacet + facet normal 0.892877 -0.44059 -0.0930142 + outer loop + vertex -831.03 337.553 234.413 + vertex -828.005 343.678 234.431 + vertex -830.835 336.341 242.023 + endloop + endfacet + facet normal 0.894687 -0.441558 -0.0675417 + outer loop + vertex -831.03 337.553 234.413 + vertex -828.118 344.627 226.741 + vertex -828.005 343.678 234.431 + endloop + endfacet + facet normal 0.873122 -0.482121 -0.0722318 + outer loop + vertex -828.118 344.627 226.741 + vertex -824.895 350.46 226.763 + vertex -828.005 343.678 234.431 + endloop + endfacet + facet normal 0.874229 -0.482814 -0.051132 + outer loop + vertex -828.118 344.627 226.741 + vertex -824.958 351.168 218.998 + vertex -824.895 350.46 226.763 + endloop + endfacet + facet normal 0.853753 -0.517853 -0.0541607 + outer loop + vertex -824.958 351.168 218.998 + vertex -821.571 356.751 219.008 + vertex -824.895 350.46 226.763 + endloop + endfacet + facet normal 0.858643 -0.510497 -0.046097 + outer loop + vertex -824.895 350.46 226.763 + vertex -821.571 356.751 219.008 + vertex -821.508 356.155 226.774 + endloop + endfacet + facet normal 0.857653 -0.509868 -0.066829 + outer loop + vertex -824.895 350.46 226.763 + vertex -821.508 356.155 226.774 + vertex -824.785 349.637 234.454 + endloop + endfacet + facet normal 0.839875 -0.54063 -0.0482585 + outer loop + vertex -821.571 356.751 219.008 + vertex -818.048 362.224 219.01 + vertex -821.508 356.155 226.774 + endloop + endfacet + facet normal 0.845176 -0.532994 -0.0399277 + outer loop + vertex -821.508 356.155 226.774 + vertex -818.048 362.224 219.01 + vertex -817.985 361.741 226.777 + endloop + endfacet + facet normal 0.84432 -0.532443 -0.0602322 + outer loop + vertex -821.508 356.155 226.774 + vertex -817.985 361.741 226.777 + vertex -821.398 355.46 234.465 + endloop + endfacet + facet normal 0.828077 -0.559084 -0.0414098 + outer loop + vertex -818.048 362.224 219.01 + vertex -814.417 367.601 219.012 + vertex -817.985 361.741 226.777 + endloop + endfacet + facet normal 0.834243 -0.550464 -0.0320707 + outer loop + vertex -817.985 361.741 226.777 + vertex -814.417 367.601 219.012 + vertex -814.356 367.241 226.781 + endloop + endfacet + facet normal 0.833565 -0.550002 -0.0516478 + outer loop + vertex -817.985 361.741 226.777 + vertex -814.356 367.241 226.781 + vertex -817.877 361.183 234.468 + endloop + endfacet + facet normal 0.82278 -0.567415 -0.0327675 + outer loop + vertex -814.417 367.601 219.012 + vertex -810.74 372.932 219.027 + vertex -814.356 367.241 226.781 + endloop + endfacet + facet normal 0.828796 -0.559044 -0.0238185 + outer loop + vertex -814.356 367.241 226.781 + vertex -810.74 372.932 219.027 + vertex -810.679 372.693 226.794 + endloop + endfacet + facet normal 0.828314 -0.558674 -0.0421913 + outer loop + vertex -814.356 367.241 226.781 + vertex -810.679 372.693 226.794 + vertex -814.248 366.821 234.47 + endloop + endfacet + facet normal 0.839272 -0.543207 -0.0234129 + outer loop + vertex -810.74 372.932 219.027 + vertex -807.232 378.349 219.1 + vertex -810.679 372.693 226.794 + endloop + endfacet + facet normal 0.846126 -0.532832 -0.0127146 + outer loop + vertex -810.679 372.693 226.794 + vertex -807.232 378.349 219.1 + vertex -807.184 378.24 226.87 + endloop + endfacet + facet normal 0.845909 -0.53245 -0.0305732 + outer loop + vertex -810.679 372.693 226.794 + vertex -807.184 378.24 226.87 + vertex -810.575 372.416 234.479 + endloop + endfacet + facet normal 0.896974 -0.441927 -0.0117551 + outer loop + vertex -807.232 378.349 219.1 + vertex -804.376 384.138 219.41 + vertex -807.184 378.24 226.87 + endloop + endfacet + facet normal 0.901299 -0.433186 -0.00321647 + outer loop + vertex -807.184 378.24 226.87 + vertex -804.376 384.138 219.41 + vertex -804.334 384.169 227.118 + endloop + endfacet + facet normal 0.901399 -0.432581 -0.0188058 + outer loop + vertex -807.184 378.24 226.87 + vertex -804.334 384.169 227.118 + vertex -807.084 378.114 234.544 + endloop + endfacet + facet normal 0.896822 -0.442387 -0.00177282 + outer loop + vertex -807.232 378.349 219.1 + vertex -804.405 384.112 211.471 + vertex -804.376 384.138 219.41 + endloop + endfacet + facet normal 0.892723 -0.450507 -0.00942473 + outer loop + vertex -807.268 378.443 211.245 + vertex -804.405 384.112 211.471 + vertex -807.232 378.349 219.1 + endloop + endfacet + facet normal 0.892634 -0.45078 -0.00140809 + outer loop + vertex -807.268 378.443 211.245 + vertex -804.428 384.091 203.587 + vertex -804.405 384.112 211.471 + endloop + endfacet + facet normal 0.889506 -0.456868 -0.00705679 + outer loop + vertex -807.292 378.519 203.322 + vertex -804.428 384.091 203.587 + vertex -807.268 378.443 211.245 + endloop + endfacet + facet normal 0.83447 -0.550999 -0.0077893 + outer loop + vertex -810.776 373.131 211.176 + vertex -807.292 378.519 203.322 + vertex -807.268 378.443 211.245 + endloop + endfacet + facet normal 0.834424 -0.550838 -0.0177341 + outer loop + vertex -810.776 373.131 211.176 + vertex -807.268 378.443 211.245 + vertex -810.74 372.932 219.027 + endloop + endfacet + facet normal 0.830535 -0.556802 -0.013516 + outer loop + vertex -810.797 373.293 203.248 + vertex -807.292 378.519 203.322 + vertex -810.776 373.131 211.176 + endloop + endfacet + facet normal 0.817807 -0.575326 -0.0138594 + outer loop + vertex -814.453 367.904 211.163 + vertex -810.797 373.293 203.248 + vertex -810.776 373.131 211.176 + endloop + endfacet + facet normal 0.817623 -0.575168 -0.025943 + outer loop + vertex -814.453 367.904 211.163 + vertex -810.776 373.131 211.176 + vertex -814.417 367.601 219.012 + endloop + endfacet + facet normal 0.813199 -0.581632 -0.020281 + outer loop + vertex -814.478 368.146 203.236 + vertex -810.797 373.293 203.248 + vertex -814.453 367.904 211.163 + endloop + endfacet + facet normal 0.82385 -0.56646 -0.0198491 + outer loop + vertex -818.084 362.623 211.163 + vertex -814.478 368.146 203.236 + vertex -814.453 367.904 211.163 + endloop + endfacet + facet normal 0.823575 -0.566268 -0.0326295 + outer loop + vertex -818.084 362.623 211.163 + vertex -814.453 367.904 211.163 + vertex -818.048 362.224 219.01 + endloop + endfacet + facet normal 0.819488 -0.572505 -0.0260463 + outer loop + vertex -818.109 362.948 203.238 + vertex -814.478 368.146 203.236 + vertex -818.084 362.623 211.163 + endloop + endfacet + facet normal 0.836028 -0.548113 -0.0250991 + outer loop + vertex -821.608 357.249 211.163 + vertex -818.109 362.948 203.238 + vertex -818.084 362.623 211.163 + endloop + endfacet + facet normal 0.835665 -0.547875 -0.0386874 + outer loop + vertex -821.608 357.249 211.163 + vertex -818.084 362.623 211.163 + vertex -821.571 356.751 219.008 + endloop + endfacet + facet normal 0.83177 -0.554233 -0.0313794 + outer loop + vertex -821.635 357.657 203.241 + vertex -818.109 362.948 203.238 + vertex -821.608 357.249 211.163 + endloop + endfacet + facet normal 0.850491 -0.525136 -0.029945 + outer loop + vertex -824.996 351.762 211.156 + vertex -821.635 357.657 203.241 + vertex -821.608 357.249 211.163 + endloop + endfacet + facet normal 0.850062 -0.524854 -0.0438588 + outer loop + vertex -824.996 351.762 211.156 + vertex -821.608 357.249 211.163 + vertex -824.958 351.168 218.998 + endloop + endfacet + facet normal 0.870717 -0.490046 -0.04132 + outer loop + vertex -828.181 345.444 218.978 + vertex -824.996 351.762 211.156 + vertex -824.958 351.168 218.998 + endloop + endfacet + facet normal 0.867298 -0.49555 -0.0471575 + outer loop + vertex -828.216 346.128 211.137 + vertex -824.996 351.762 211.156 + vertex -828.181 345.444 218.978 + endloop + endfacet + facet normal 0.890108 -0.453658 -0.0436065 + outer loop + vertex -831.197 339.528 218.959 + vertex -828.216 346.128 211.137 + vertex -828.181 345.444 218.978 + endloop + endfacet + facet normal 0.889354 -0.45322 -0.060342 + outer loop + vertex -831.197 339.528 218.959 + vertex -828.181 345.444 218.978 + vertex -831.136 338.614 226.722 + endloop + endfacet + facet normal 0.892485 -0.44779 -0.0543583 + outer loop + vertex -831.136 338.614 226.722 + vertex -828.181 345.444 218.978 + vertex -828.118 344.627 226.741 + endloop + endfacet + facet normal 0.886878 -0.459332 -0.0496246 + outer loop + vertex -831.235 340.3 211.118 + vertex -828.216 346.128 211.137 + vertex -831.197 339.528 218.959 + endloop + endfacet + facet normal 0.887379 -0.459636 -0.0359535 + outer loop + vertex -831.235 340.3 211.118 + vertex -828.245 346.692 203.221 + vertex -828.216 346.128 211.137 + endloop + endfacet + facet normal 0.864307 -0.501462 -0.0388522 + outer loop + vertex -828.245 346.692 203.221 + vertex -825.021 352.246 203.236 + vertex -828.216 346.128 211.137 + endloop + endfacet + facet normal 0.864647 -0.501694 -0.0262504 + outer loop + vertex -828.245 346.692 203.221 + vertex -825.044 352.625 195.261 + vertex -825.021 352.246 203.236 + endloop + endfacet + facet normal 0.844278 -0.535185 -0.027784 + outer loop + vertex -825.044 352.625 195.261 + vertex -821.655 357.971 195.263 + vertex -825.021 352.246 203.236 + endloop + endfacet + facet normal 0.847429 -0.530409 -0.0230238 + outer loop + vertex -825.021 352.246 203.236 + vertex -821.655 357.971 195.263 + vertex -821.635 357.657 203.241 + endloop + endfacet + facet normal 0.829065 -0.558634 -0.0240883 + outer loop + vertex -821.655 357.971 195.263 + vertex -818.13 363.202 195.259 + vertex -821.635 357.657 203.241 + endloop + endfacet + facet normal 0.829227 -0.558736 -0.0140215 + outer loop + vertex -821.655 357.971 195.263 + vertex -818.145 363.38 187.272 + vertex -818.13 363.202 195.259 + endloop + endfacet + facet normal 0.813996 -0.580689 -0.0144829 + outer loop + vertex -818.145 363.38 187.272 + vertex -814.513 368.472 187.269 + vertex -818.13 363.202 195.259 + endloop + endfacet + facet normal 0.816357 -0.577438 -0.0112701 + outer loop + vertex -818.13 363.202 195.259 + vertex -814.513 368.472 187.269 + vertex -814.498 368.337 195.257 + endloop + endfacet + facet normal 0.816234 -0.577356 -0.0205342 + outer loop + vertex -818.13 363.202 195.259 + vertex -814.498 368.337 195.257 + vertex -818.109 362.948 203.238 + endloop + endfacet + facet normal 0.807361 -0.589946 -0.011464 + outer loop + vertex -814.513 368.472 187.269 + vertex -810.831 373.51 187.278 + vertex -814.498 368.337 195.257 + endloop + endfacet + facet normal 0.809775 -0.586682 -0.00823831 + outer loop + vertex -814.498 368.337 195.257 + vertex -810.831 373.51 187.278 + vertex -810.816 373.419 195.267 + endloop + endfacet + facet normal 0.809706 -0.586615 -0.0160964 + outer loop + vertex -814.498 368.337 195.257 + vertex -810.816 373.419 195.267 + vertex -814.478 368.146 203.236 + endloop + endfacet + facet normal 0.82477 -0.565411 -0.00802332 + outer loop + vertex -810.831 373.51 187.278 + vertex -807.325 378.624 187.349 + vertex -810.816 373.419 195.267 + endloop + endfacet + facet normal 0.827456 -0.561515 -0.00427785 + outer loop + vertex -810.816 373.419 195.267 + vertex -807.325 378.624 187.349 + vertex -807.313 378.58 195.34 + endloop + endfacet + facet normal 0.827457 -0.561422 -0.0109233 + outer loop + vertex -810.816 373.419 195.267 + vertex -807.313 378.58 195.34 + vertex -810.797 373.293 203.248 + endloop + endfacet + facet normal 0.884686 -0.466171 -0.00383994 + outer loop + vertex -807.325 378.624 187.349 + vertex -804.458 384.063 187.557 + vertex -807.313 378.58 195.34 + endloop + endfacet + facet normal 0.886517 -0.462696 -0.000720522 + outer loop + vertex -807.313 378.58 195.34 + vertex -804.458 384.063 187.557 + vertex -804.446 384.074 195.596 + endloop + endfacet + facet normal 0.886602 -0.462495 -0.00597111 + outer loop + vertex -807.313 378.58 195.34 + vertex -804.446 384.074 195.596 + vertex -807.292 378.519 203.322 + endloop + endfacet + facet normal 0.884639 -0.466277 -0.0004234 + outer loop + vertex -807.325 378.624 187.349 + vertex -804.466 384.056 179.614 + vertex -804.458 384.063 187.557 + endloop + endfacet + facet normal 0.883505 -0.468416 -0.00234502 + outer loop + vertex -807.331 378.652 179.38 + vertex -804.466 384.056 179.614 + vertex -807.325 378.624 187.349 + endloop + endfacet + facet normal 0.883467 -0.468493 -0.000122027 + outer loop + vertex -807.331 378.652 179.38 + vertex -804.468 384.054 171.53 + vertex -804.466 384.056 179.614 + endloop + endfacet + facet normal 0.882562 -0.470193 -0.00162199 + outer loop + vertex -807.337 378.669 171.501 + vertex -804.468 384.054 171.53 + vertex -807.331 378.652 179.38 + endloop + endfacet + facet normal 0.823054 -0.567961 -0.00178042 + outer loop + vertex -810.841 373.567 179.33 + vertex -807.337 378.669 171.501 + vertex -807.331 378.652 179.38 + endloop + endfacet + facet normal 0.823059 -0.567933 -0.00499796 + outer loop + vertex -810.841 373.567 179.33 + vertex -807.331 378.652 179.38 + vertex -810.831 373.51 187.278 + endloop + endfacet + facet normal 0.822985 -0.568061 -0.00187636 + outer loop + vertex -810.843 373.589 171.452 + vertex -807.337 378.669 171.501 + vertex -810.841 373.567 179.33 + endloop + endfacet + facet normal 0.806035 -0.591864 -0.00193825 + outer loop + vertex -814.522 368.553 179.324 + vertex -810.843 373.589 171.452 + vertex -810.841 373.567 179.33 + endloop + endfacet + facet normal 0.80602 -0.591847 -0.00697017 + outer loop + vertex -814.522 368.553 179.324 + vertex -810.841 373.567 179.33 + vertex -814.513 368.472 187.269 + endloop + endfacet + facet normal 0.805753 -0.592247 -0.00231509 + outer loop + vertex -814.525 368.58 171.448 + vertex -810.843 373.589 171.452 + vertex -814.522 368.553 179.324 + endloop + endfacet + facet normal 0.812697 -0.582682 -0.00228389 + outer loop + vertex -818.155 363.486 179.328 + vertex -814.525 368.58 171.448 + vertex -814.522 368.553 179.324 + endloop + endfacet + facet normal 0.812666 -0.582664 -0.00876044 + outer loop + vertex -818.155 363.486 179.328 + vertex -814.522 368.553 179.324 + vertex -818.145 363.38 187.272 + endloop + endfacet + facet normal 0.826979 -0.562169 -0.00850403 + outer loop + vertex -821.671 358.194 187.276 + vertex -818.155 363.486 179.328 + vertex -818.145 363.38 187.272 + endloop + endfacet + facet normal 0.825305 -0.564583 -0.0108519 + outer loop + vertex -821.682 358.33 179.331 + vertex -818.155 363.486 179.328 + vertex -821.671 358.194 187.276 + endloop + endfacet + facet normal 0.8425 -0.538595 -0.0104346 + outer loop + vertex -825.06 352.892 187.275 + vertex -821.682 358.33 179.331 + vertex -821.671 358.194 187.276 + endloop + endfacet + facet normal 0.842382 -0.538518 -0.0197407 + outer loop + vertex -825.06 352.892 187.275 + vertex -821.671 358.194 187.276 + vertex -825.044 352.625 195.261 + endloop + endfacet + facet normal 0.862932 -0.504975 -0.0186596 + outer loop + vertex -828.264 347.123 195.247 + vertex -825.06 352.892 187.275 + vertex -825.044 352.625 195.261 + endloop + endfacet + facet normal 0.861474 -0.507369 -0.0209782 + outer loop + vertex -828.279 347.427 187.265 + vertex -825.06 352.892 187.275 + vertex -828.264 347.123 195.247 + endloop + endfacet + facet normal 0.88401 -0.467062 -0.0194841 + outer loop + vertex -831.285 341.406 195.225 + vertex -828.279 347.427 187.265 + vertex -828.264 347.123 195.247 + endloop + endfacet + facet normal 0.883766 -0.466888 -0.0312019 + outer loop + vertex -831.285 341.406 195.225 + vertex -828.264 347.123 195.247 + vertex -831.26 340.92 203.199 + endloop + endfacet + facet normal 0.886051 -0.462792 -0.027146 + outer loop + vertex -831.26 340.92 203.199 + vertex -828.264 347.123 195.247 + vertex -828.245 346.692 203.221 + endloop + endfacet + facet normal 0.882723 -0.469392 -0.021732 + outer loop + vertex -831.302 341.744 187.241 + vertex -828.279 347.427 187.265 + vertex -831.285 341.406 195.225 + endloop + endfacet + facet normal 0.882848 -0.469496 -0.0123641 + outer loop + vertex -831.302 341.744 187.241 + vertex -828.292 347.612 179.323 + vertex -828.279 347.427 187.265 + endloop + endfacet + facet normal 0.860083 -0.509981 -0.0132683 + outer loop + vertex -828.292 347.612 179.323 + vertex -825.069 353.048 179.333 + vertex -828.279 347.427 187.265 + endloop + endfacet + facet normal 0.860145 -0.510033 -0.00402632 + outer loop + vertex -828.292 347.612 179.323 + vertex -825.074 353.101 171.457 + vertex -825.069 353.048 179.333 + endloop + endfacet + facet normal 0.840994 -0.541027 -0.0042245 + outer loop + vertex -825.074 353.101 171.457 + vertex -821.684 358.37 171.455 + vertex -825.069 353.048 179.333 + endloop + endfacet + facet normal 0.841844 -0.539713 -0.00297108 + outer loop + vertex -825.069 353.048 179.333 + vertex -821.684 358.37 171.455 + vertex -821.682 358.33 179.331 + endloop + endfacet + facet normal 0.82528 -0.564715 -0.00309536 + outer loop + vertex -821.684 358.37 171.455 + vertex -818.159 363.522 171.451 + vertex -821.682 358.33 179.331 + endloop + endfacet + facet normal 0.825283 -0.564711 0.00312886 + outer loop + vertex -821.684 358.37 171.455 + vertex -818.155 363.485 163.627 + vertex -818.159 363.522 171.451 + endloop + endfacet + facet normal 0.812898 -0.582397 0.00320598 + outer loop + vertex -818.155 363.485 163.627 + vertex -814.521 368.556 163.624 + vertex -818.159 363.522 171.451 + endloop + endfacet + facet normal 0.812119 -0.583488 0.00214188 + outer loop + vertex -818.159 363.522 171.451 + vertex -814.521 368.556 163.624 + vertex -814.525 368.58 171.448 + endloop + endfacet + facet normal 0.806372 -0.591405 0.00216375 + outer loop + vertex -814.521 368.556 163.624 + vertex -810.839 373.577 163.628 + vertex -814.525 368.58 171.448 + endloop + endfacet + facet normal 0.806366 -0.591402 0.00410962 + outer loop + vertex -814.521 368.556 163.624 + vertex -810.831 373.534 155.81 + vertex -810.839 373.577 163.628 + endloop + endfacet + facet normal 0.824582 -0.565729 0.0039844 + outer loop + vertex -810.831 373.534 155.81 + vertex -807.319 378.653 155.871 + vertex -810.839 373.577 163.628 + endloop + endfacet + facet normal 0.823883 -0.566751 0.00299862 + outer loop + vertex -810.839 373.577 163.628 + vertex -807.319 378.653 155.871 + vertex -807.336 378.67 163.698 + endloop + endfacet + facet normal 0.823897 -0.566737 0.00130314 + outer loop + vertex -810.839 373.577 163.628 + vertex -807.336 378.67 163.698 + vertex -810.843 373.589 171.452 + endloop + endfacet + facet normal 0.883885 -0.467696 0.00290403 + outer loop + vertex -807.319 378.653 155.871 + vertex -804.457 384.064 156.165 + vertex -807.336 378.67 163.698 + endloop + endfacet + facet normal 0.882474 -0.470362 0.000455596 + outer loop + vertex -807.336 378.67 163.698 + vertex -804.457 384.064 156.165 + vertex -804.465 384.057 163.949 + endloop + endfacet + facet normal 0.882482 -0.470347 3.77943e-05 + outer loop + vertex -807.336 378.67 163.698 + vertex -804.465 384.057 163.949 + vertex -807.337 378.669 171.501 + endloop + endfacet + facet normal 0.883937 -0.467606 0.000759082 + outer loop + vertex -807.319 378.653 155.871 + vertex -804.444 384.076 148.224 + vertex -804.457 384.064 156.165 + endloop + endfacet + facet normal 0.88526 -0.465087 0.00304354 + outer loop + vertex -807.307 378.625 148.012 + vertex -804.444 384.076 148.224 + vertex -807.319 378.653 155.871 + endloop + endfacet + facet normal 0.885295 -0.465029 0.00107022 + outer loop + vertex -807.307 378.625 148.012 + vertex -804.425 384.093 140.323 + vertex -804.444 384.076 148.224 + endloop + endfacet + facet normal 0.88746 -0.460859 0.00484647 + outer loop + vertex -807.286 378.582 140.105 + vertex -804.425 384.093 140.323 + vertex -807.307 378.625 148.012 + endloop + endfacet + facet normal 0.827776 -0.561034 0.00524291 + outer loop + vertex -810.812 373.453 147.958 + vertex -807.286 378.582 140.105 + vertex -807.307 378.625 148.012 + endloop + endfacet + facet normal 0.82775 -0.561043 0.00778464 + outer loop + vertex -810.812 373.453 147.958 + vertex -807.307 378.625 148.012 + vertex -810.831 373.534 155.81 + endloop + endfacet + facet normal 0.808492 -0.588452 0.00801741 + outer loop + vertex -814.51 368.479 155.805 + vertex -810.812 373.453 147.958 + vertex -810.831 373.534 155.81 + endloop + endfacet + facet normal 0.811001 -0.584933 0.0114312 + outer loop + vertex -814.493 368.349 147.95 + vertex -810.812 373.453 147.958 + vertex -814.51 368.479 155.805 + endloop + endfacet + facet normal 0.814434 -0.580144 0.0113593 + outer loop + vertex -818.144 363.378 155.805 + vertex -814.493 368.349 147.95 + vertex -814.51 368.479 155.805 + endloop + endfacet + facet normal 0.814453 -0.580158 0.00909264 + outer loop + vertex -818.144 363.378 155.805 + vertex -814.51 368.479 155.805 + vertex -818.155 363.485 163.627 + endloop + endfacet + facet normal 0.825601 -0.564184 0.00888892 + outer loop + vertex -821.681 358.325 163.629 + vertex -818.144 363.378 155.805 + vertex -818.155 363.485 163.627 + endloop + endfacet + facet normal 0.826764 -0.562451 0.0105344 + outer loop + vertex -821.672 358.192 155.808 + vertex -818.144 363.378 155.805 + vertex -821.681 358.325 163.629 + endloop + endfacet + facet normal 0.84166 -0.539912 0.0101685 + outer loop + vertex -825.069 353.044 163.632 + vertex -821.672 358.192 155.808 + vertex -821.681 358.325 163.629 + endloop + endfacet + facet normal 0.841694 -0.539937 0.00451705 + outer loop + vertex -825.069 353.044 163.632 + vertex -821.681 358.325 163.629 + vertex -825.074 353.101 171.457 + endloop + endfacet + facet normal 0.860193 -0.50995 0.00430944 + outer loop + vertex -828.295 347.667 171.45 + vertex -825.069 353.044 163.632 + vertex -825.074 353.101 171.457 + endloop + endfacet + facet normal 0.860435 -0.509538 0.00469297 + outer loop + vertex -828.291 347.602 163.626 + vertex -825.069 353.044 163.632 + vertex -828.295 347.667 171.45 + endloop + endfacet + facet normal 0.882233 -0.470793 0.00437967 + outer loop + vertex -831.318 342.004 171.428 + vertex -828.291 347.602 163.626 + vertex -828.295 347.667 171.45 + endloop + endfacet + facet normal 0.882248 -0.470772 -0.00347805 + outer loop + vertex -831.318 342.004 171.428 + vertex -828.295 347.667 171.45 + vertex -831.316 341.948 179.3 + endloop + endfacet + facet normal 0.882135 -0.470982 -0.00367486 + outer loop + vertex -831.316 341.948 179.3 + vertex -828.295 347.667 171.45 + vertex -828.292 347.612 179.323 + endloop + endfacet + facet normal 0.860386 -0.509516 0.0113243 + outer loop + vertex -828.291 347.602 163.626 + vertex -825.06 352.885 155.812 + vertex -825.069 353.044 163.632 + endloop + endfacet + facet normal 0.861708 -0.507227 0.0134188 + outer loop + vertex -828.28 347.414 155.806 + vertex -825.06 352.885 155.812 + vertex -828.291 347.602 163.626 + endloop + endfacet + facet normal 0.882304 -0.470512 0.0125686 + outer loop + vertex -831.316 341.93 163.605 + vertex -828.28 347.414 155.806 + vertex -828.291 347.602 163.626 + endloop + endfacet + facet normal 0.861623 -0.507183 0.0192597 + outer loop + vertex -828.28 347.414 155.806 + vertex -825.042 352.617 147.958 + vertex -825.06 352.885 155.812 + endloop + endfacet + facet normal 0.844684 -0.534885 0.0201679 + outer loop + vertex -825.042 352.617 147.958 + vertex -821.654 357.967 147.954 + vertex -825.06 352.885 155.812 + endloop + endfacet + facet normal 0.842752 -0.538024 0.0173001 + outer loop + vertex -825.06 352.885 155.812 + vertex -821.654 357.967 147.954 + vertex -821.672 358.192 155.808 + endloop + endfacet + facet normal 0.829205 -0.55866 0.0178613 + outer loop + vertex -821.654 357.967 147.954 + vertex -818.128 363.2 147.95 + vertex -821.672 358.192 155.808 + endloop + endfacet + facet normal 0.82917 -0.558635 0.0201105 + outer loop + vertex -821.654 357.967 147.954 + vertex -818.106 362.95 140.06 + vertex -818.128 363.2 147.95 + endloop + endfacet + facet normal 0.820358 -0.571483 0.0204932 + outer loop + vertex -818.106 362.95 140.06 + vertex -814.472 368.166 140.058 + vertex -818.128 363.2 147.95 + endloop + endfacet + facet normal 0.816812 -0.576694 0.0155717 + outer loop + vertex -818.128 363.2 147.95 + vertex -814.472 368.166 140.058 + vertex -814.493 368.349 147.95 + endloop + endfacet + facet normal 0.814633 -0.579766 0.0156368 + outer loop + vertex -814.472 368.166 140.058 + vertex -810.79 373.34 140.066 + vertex -814.493 368.349 147.95 + endloop + endfacet + facet normal 0.814659 -0.579781 0.0135736 + outer loop + vertex -814.472 368.166 140.058 + vertex -810.762 373.194 132.168 + vertex -810.79 373.34 140.066 + endloop + endfacet + facet normal 0.835577 -0.549217 0.0130792 + outer loop + vertex -810.762 373.194 132.168 + vertex -807.26 378.523 132.206 + vertex -810.79 373.34 140.066 + endloop + endfacet + facet normal 0.831342 -0.555718 0.00688942 + outer loop + vertex -810.79 373.34 140.066 + vertex -807.26 378.523 132.206 + vertex -807.286 378.582 140.105 + endloop + endfacet + facet normal 0.890368 -0.455198 0.00634554 + outer loop + vertex -807.26 378.523 132.206 + vertex -804.401 384.115 132.225 + vertex -807.286 378.582 140.105 + endloop + endfacet + facet normal 0.89039 -0.455194 0.00176175 + outer loop + vertex -807.26 378.523 132.206 + vertex -804.372 384.141 124.545 + vertex -804.401 384.115 132.225 + endloop + endfacet + facet normal 0.893982 -0.448024 0.0083737 + outer loop + vertex -807.223 378.45 124.368 + vertex -804.372 384.141 124.545 + vertex -807.26 378.523 132.206 + endloop + endfacet + facet normal 0.89407 -0.447915 0.0034715 + outer loop + vertex -807.223 378.45 124.368 + vertex -804.327 384.172 116.819 + vertex -804.372 384.141 124.545 + endloop + endfacet + facet normal 0.898298 -0.439232 0.0116753 + outer loop + vertex -807.165 378.362 116.571 + vertex -804.327 384.172 116.819 + vertex -807.223 378.45 124.368 + endloop + endfacet + facet normal 0.840884 -0.541074 0.012396 + outer loop + vertex -810.721 373.012 124.306 + vertex -807.165 378.362 116.571 + vertex -807.223 378.45 124.368 + endloop + endfacet + facet normal 0.840805 -0.541075 0.0168849 + outer loop + vertex -810.721 373.012 124.306 + vertex -807.223 378.45 124.368 + vertex -810.762 373.194 132.168 + endloop + endfacet + facet normal 0.819355 -0.573019 0.017513 + outer loop + vertex -814.443 367.93 132.162 + vertex -810.721 373.012 124.306 + vertex -810.762 373.194 132.168 + endloop + endfacet + facet normal 0.824759 -0.564917 0.0253147 + outer loop + vertex -814.4 367.64 124.305 + vertex -810.721 373.012 124.306 + vertex -814.443 367.93 132.162 + endloop + endfacet + facet normal 0.824556 -0.565213 0.0253245 + outer loop + vertex -818.077 362.629 132.168 + vertex -814.4 367.64 124.305 + vertex -814.443 367.93 132.162 + endloop + endfacet + facet normal 0.824543 -0.565204 0.025946 + outer loop + vertex -818.077 362.629 132.168 + vertex -814.443 367.93 132.162 + vertex -818.106 362.95 140.06 + endloop + endfacet + facet normal 0.832136 -0.553984 0.0255171 + outer loop + vertex -821.632 357.653 140.066 + vertex -818.077 362.629 132.168 + vertex -818.106 362.95 140.06 + endloop + endfacet + facet normal 0.835801 -0.548167 0.0308314 + outer loop + vertex -821.604 357.252 132.176 + vertex -818.077 362.629 132.168 + vertex -821.632 357.653 140.066 + endloop + endfacet + facet normal 0.846996 -0.530753 0.0299851 + outer loop + vertex -825.021 352.245 140.07 + vertex -821.604 357.252 132.176 + vertex -821.632 357.653 140.066 + endloop + endfacet + facet normal 0.84706 -0.530796 0.0272893 + outer loop + vertex -825.021 352.245 140.07 + vertex -821.632 357.653 140.066 + vertex -825.042 352.617 147.958 + endloop + endfacet + facet normal 0.862741 -0.504971 0.0261117 + outer loop + vertex -828.265 347.11 147.953 + vertex -825.021 352.245 140.07 + vertex -825.042 352.617 147.958 + endloop + endfacet + facet normal 0.865232 -0.50047 0.0300692 + outer loop + vertex -828.242 346.676 140.065 + vertex -825.021 352.245 140.07 + vertex -828.265 347.11 147.953 + endloop + endfacet + facet normal 0.884471 -0.465741 0.028217 + outer loop + vertex -831.287 341.37 147.931 + vertex -828.242 346.676 140.065 + vertex -828.265 347.11 147.953 + endloop + endfacet + facet normal 0.865139 -0.50042 0.0333796 + outer loop + vertex -828.242 346.676 140.065 + vertex -824.994 351.766 132.18 + vertex -825.021 352.245 140.07 + endloop + endfacet + facet normal 0.868147 -0.494833 0.0382251 + outer loop + vertex -828.212 346.12 132.175 + vertex -824.994 351.766 132.18 + vertex -828.242 346.676 140.065 + endloop + endfacet + facet normal 0.886129 -0.462039 0.0359844 + outer loop + vertex -831.263 340.88 140.044 + vertex -828.212 346.12 132.175 + vertex -828.242 346.676 140.065 + endloop + endfacet + facet normal 0.868008 -0.494758 0.0421647 + outer loop + vertex -828.212 346.12 132.175 + vertex -824.947 351.178 124.324 + vertex -824.994 351.766 132.18 + endloop + endfacet + facet normal 0.853992 -0.518435 0.0438554 + outer loop + vertex -824.947 351.178 124.324 + vertex -821.559 356.76 124.32 + vertex -824.994 351.766 132.18 + endloop + endfacet + facet normal 0.850114 -0.525237 0.0378398 + outer loop + vertex -824.994 351.766 132.18 + vertex -821.559 356.76 124.32 + vertex -821.604 357.252 132.176 + endloop + endfacet + facet normal 0.840166 -0.540942 0.0387665 + outer loop + vertex -821.559 356.76 124.32 + vertex -818.032 362.236 124.313 + vertex -821.604 357.252 132.176 + endloop + endfacet + facet normal 0.840114 -0.540907 0.040364 + outer loop + vertex -821.559 356.76 124.32 + vertex -817.958 361.769 116.522 + vertex -818.032 362.236 124.313 + endloop + endfacet + facet normal 0.835398 -0.548132 0.0407518 + outer loop + vertex -817.958 361.769 116.522 + vertex -814.331 367.297 116.518 + vertex -818.032 362.236 124.313 + endloop + endfacet + facet normal 0.829599 -0.557445 0.0319522 + outer loop + vertex -818.032 362.236 124.313 + vertex -814.331 367.297 116.518 + vertex -814.4 367.64 124.305 + endloop + endfacet + facet normal 0.831188 -0.555077 0.0318621 + outer loop + vertex -814.331 367.297 116.518 + vertex -810.659 372.796 116.517 + vertex -814.4 367.64 124.305 + endloop + endfacet + facet normal 0.831255 -0.555123 0.0292264 + outer loop + vertex -814.331 367.297 116.518 + vertex -810.557 372.544 108.826 + vertex -810.659 372.796 116.517 + endloop + endfacet + facet normal 0.852976 -0.521177 0.0284008 + outer loop + vertex -810.557 372.544 108.826 + vertex -807.066 378.259 108.854 + vertex -810.659 372.796 116.517 + endloop + endfacet + facet normal 0.846723 -0.531731 0.0179444 + outer loop + vertex -810.659 372.796 116.517 + vertex -807.066 378.259 108.854 + vertex -807.165 378.362 116.571 + endloop + endfacet + facet normal 0.902268 -0.430828 0.0173028 + outer loop + vertex -807.066 378.259 108.854 + vertex -804.227 384.209 108.998 + vertex -807.165 378.362 116.571 + endloop + endfacet + facet normal 0.902188 -0.430863 0.0203362 + outer loop + vertex -807.066 378.259 108.854 + vertex -804.033 384.252 101.281 + vertex -804.227 384.209 108.998 + endloop + endfacet + facet normal 0.905222 -0.424086 0.0269142 + outer loop + vertex -806.896 378.14 101.271 + vertex -804.033 384.252 101.281 + vertex -807.066 378.259 108.854 + endloop + endfacet + facet normal 0.904923 -0.423962 0.0370127 + outer loop + vertex -806.896 378.14 101.271 + vertex -803.706 384.299 93.8248 + vertex -804.033 384.252 101.281 + endloop + endfacet + facet normal 0.908184 -0.416159 0.0448655 + outer loop + vertex -806.595 377.996 93.8381 + vertex -803.706 384.299 93.8248 + vertex -806.896 378.14 101.271 + endloop + endfacet + facet normal 0.859427 -0.509301 0.0446959 + outer loop + vertex -810.385 372.251 101.257 + vertex -806.595 377.996 93.8381 + vertex -806.896 378.14 101.271 + endloop + endfacet + facet normal 0.859631 -0.509409 0.039207 + outer loop + vertex -810.385 372.251 101.257 + vertex -806.896 378.14 101.271 + vertex -810.557 372.544 108.826 + endloop + endfacet + facet normal 0.838339 -0.543677 0.0400516 + outer loop + vertex -814.22 366.896 108.822 + vertex -810.385 372.251 101.257 + vertex -810.557 372.544 108.826 + endloop + endfacet + facet normal 0.845874 -0.530741 0.0530282 + outer loop + vertex -814.038 366.429 101.249 + vertex -810.385 372.251 101.257 + vertex -814.22 366.896 108.822 + endloop + endfacet + facet normal 0.841792 -0.537162 0.0533262 + outer loop + vertex -817.839 361.223 108.818 + vertex -814.038 366.429 101.249 + vertex -814.22 366.896 108.822 + endloop + endfacet + facet normal 0.84189 -0.537224 0.0511117 + outer loop + vertex -817.839 361.223 108.818 + vertex -814.22 366.896 108.822 + vertex -817.958 361.769 116.522 + endloop + endfacet + facet normal 0.84493 -0.532458 0.0508208 + outer loop + vertex -821.484 356.176 116.524 + vertex -817.839 361.223 108.818 + vertex -817.958 361.769 116.522 + endloop + endfacet + facet normal 0.8507 -0.522184 0.0602788 + outer loop + vertex -821.359 355.489 108.815 + vertex -817.839 361.223 108.818 + vertex -821.484 356.176 116.524 + endloop + endfacet + facet normal 0.858043 -0.510139 0.0593254 + outer loop + vertex -824.87 350.479 116.526 + vertex -821.359 355.489 108.815 + vertex -821.484 356.176 116.524 + endloop + endfacet + facet normal 0.858294 -0.51029 0.0541801 + outer loop + vertex -824.87 350.479 116.526 + vertex -821.484 356.176 116.524 + vertex -824.947 351.178 124.324 + endloop + endfacet + facet normal 0.870593 -0.489204 0.052412 + outer loop + vertex -828.169 345.444 124.318 + vertex -824.87 350.479 116.526 + vertex -824.947 351.178 124.324 + endloop + endfacet + facet normal 0.874257 -0.481903 0.0586819 + outer loop + vertex -828.092 344.633 116.517 + vertex -824.87 350.479 116.526 + vertex -828.169 345.444 124.318 + endloop + endfacet + facet normal 0.890189 -0.452168 0.0557483 + outer loop + vertex -831.193 339.488 124.293 + vertex -828.092 344.633 116.517 + vertex -828.169 345.444 124.318 + endloop + endfacet + facet normal 0.89307 -0.445744 0.0611474 + outer loop + vertex -831.116 338.572 116.49 + vertex -828.092 344.633 116.517 + vertex -831.193 339.488 124.293 + endloop + endfacet + facet normal 0.892549 -0.445522 0.0697676 + outer loop + vertex -831.116 338.572 116.49 + vertex -827.965 343.68 108.799 + vertex -828.092 344.633 116.517 + endloop + endfacet + facet normal 0.877992 -0.473086 0.072932 + outer loop + vertex -827.965 343.68 108.799 + vertex -824.745 349.658 108.812 + vertex -828.092 344.633 116.517 + endloop + endfacet + facet normal 0.877401 -0.472786 0.0814918 + outer loop + vertex -827.965 343.68 108.799 + vertex -824.553 348.706 101.221 + vertex -824.745 349.658 108.812 + endloop + endfacet + facet normal 0.867157 -0.490982 0.0835163 + outer loop + vertex -824.553 348.706 101.221 + vertex -821.165 354.692 101.233 + vertex -824.745 349.658 108.812 + endloop + endfacet + facet normal 0.862342 -0.500781 0.0747338 + outer loop + vertex -824.745 349.658 108.812 + vertex -821.165 354.692 101.233 + vertex -821.359 355.489 108.815 + endloop + endfacet + facet normal 0.856444 -0.510671 0.0756234 + outer loop + vertex -821.165 354.692 101.233 + vertex -817.65 360.587 101.241 + vertex -821.359 355.489 108.815 + endloop + endfacet + facet normal 0.85584 -0.510324 0.0843055 + outer loop + vertex -821.165 354.692 101.233 + vertex -817.353 359.861 93.8324 + vertex -817.65 360.587 101.241 + endloop + endfacet + facet normal 0.855097 -0.511552 0.0843962 + outer loop + vertex -817.353 359.861 93.8324 + vertex -813.746 365.891 93.8317 + vertex -817.65 360.587 101.241 + endloop + endfacet + facet normal 0.848311 -0.524657 0.0714403 + outer loop + vertex -817.65 360.587 101.241 + vertex -813.746 365.891 93.8317 + vertex -814.038 366.429 101.249 + endloop + endfacet + facet normal 0.852835 -0.517319 0.0710864 + outer loop + vertex -813.746 365.891 93.8317 + vertex -810.095 371.91 93.828 + vertex -814.038 366.429 101.249 + endloop + endfacet + facet normal 0.851908 -0.516748 0.0850006 + outer loop + vertex -813.746 365.891 93.8317 + vertex -809.599 371.531 86.5602 + vertex -810.095 371.91 93.828 + endloop + endfacet + facet normal 0.871227 -0.483537 0.0845876 + outer loop + vertex -809.599 371.531 86.5602 + vertex -806.099 377.839 86.568 + vertex -810.095 371.91 93.828 + endloop + endfacet + facet normal 0.864739 -0.497357 0.0697298 + outer loop + vertex -810.095 371.91 93.828 + vertex -806.099 377.839 86.568 + vertex -806.595 377.996 93.8381 + endloop + endfacet + facet normal 0.911174 -0.40587 0.0709314 + outer loop + vertex -806.099 377.839 86.568 + vertex -803.2 384.352 86.5938 + vertex -806.595 377.996 93.8381 + endloop + endfacet + facet normal 0.909522 -0.40522 0.0925558 + outer loop + vertex -806.099 377.839 86.568 + vertex -802.465 384.411 79.6268 + vertex -803.2 384.352 86.5938 + endloop + endfacet + facet normal 0.91511 -0.387171 0.11257 + outer loop + vertex -805.301 377.665 79.4783 + vertex -802.465 384.411 79.6268 + vertex -806.099 377.839 86.568 + endloop + endfacet + facet normal 0.91213 -0.386449 0.13666 + outer loop + vertex -805.301 377.665 79.4783 + vertex -801.425 384.478 72.8769 + vertex -802.465 384.411 79.6268 + endloop + endfacet + facet normal 0.917524 -0.361638 0.165432 + outer loop + vertex -804.143 377.497 72.6914 + vertex -801.425 384.478 72.8769 + vertex -805.301 377.665 79.4783 + endloop + endfacet + facet normal 0.870283 -0.465859 0.159948 + outer loop + vertex -808.8 371.128 79.4781 + vertex -804.143 377.497 72.6914 + vertex -805.301 377.665 79.4783 + endloop + endfacet + facet normal 0.874675 -0.468209 0.125395 + outer loop + vertex -808.8 371.128 79.4781 + vertex -805.301 377.665 79.4783 + vertex -809.599 371.531 86.5602 + endloop + endfacet + facet normal 0.855975 -0.501632 0.12519 + outer loop + vertex -813.256 365.299 86.5942 + vertex -808.8 371.128 79.4781 + vertex -809.599 371.531 86.5602 + endloop + endfacet + facet normal 0.86195 -0.487021 0.140899 + outer loop + vertex -812.455 364.678 79.5471 + vertex -808.8 371.128 79.4781 + vertex -813.256 365.299 86.5942 + endloop + endfacet + facet normal 0.856961 -0.49569 0.141096 + outer loop + vertex -816.865 359.066 86.6134 + vertex -812.455 364.678 79.5471 + vertex -813.256 365.299 86.5942 + endloop + endfacet + facet normal 0.86004 -0.497559 0.112983 + outer loop + vertex -816.865 359.066 86.6134 + vertex -813.256 365.299 86.5942 + vertex -817.353 359.861 93.8324 + endloop + endfacet + facet normal 0.860179 -0.497324 0.112967 + outer loop + vertex -820.865 353.785 93.8224 + vertex -816.865 359.066 86.6134 + vertex -817.353 359.861 93.8324 + endloop + endfacet + facet normal 0.865536 -0.485007 0.124962 + outer loop + vertex -820.38 352.791 86.6064 + vertex -816.865 359.066 86.6134 + vertex -820.865 353.785 93.8224 + endloop + endfacet + facet normal 0.869672 -0.47774 0.124239 + outer loop + vertex -824.249 347.621 93.8055 + vertex -820.38 352.791 86.6064 + vertex -820.865 353.785 93.8224 + endloop + endfacet + facet normal 0.871567 -0.47873 0.105779 + outer loop + vertex -824.249 347.621 93.8055 + vertex -820.865 353.785 93.8224 + vertex -824.553 348.706 101.221 + endloop + endfacet + facet normal 0.88029 -0.462936 0.103826 + outer loop + vertex -827.773 342.578 101.201 + vertex -824.249 347.621 93.8055 + vertex -824.553 348.706 101.221 + endloop + endfacet + facet normal 0.884518 -0.452649 0.112855 + outer loop + vertex -827.468 341.324 93.7818 + vertex -824.249 347.621 93.8055 + vertex -827.773 342.578 101.201 + endloop + endfacet + facet normal 0.89691 -0.428497 0.109285 + outer loop + vertex -830.789 336.258 101.176 + vertex -827.468 341.324 93.7818 + vertex -827.773 342.578 101.201 + endloop + endfacet + facet normal 0.898429 -0.429157 0.0929995 + outer loop + vertex -830.789 336.258 101.176 + vertex -827.773 342.578 101.201 + vertex -830.984 337.495 108.772 + endloop + endfacet + facet normal 0.913979 -0.396101 0.088012 + outer loop + vertex -833.765 331.078 108.759 + vertex -830.789 336.258 101.176 + vertex -830.984 337.495 108.772 + endloop + endfacet + facet normal 0.895123 -0.437439 0.086038 + outer loop + vertex -830.984 337.495 108.772 + vertex -827.773 342.578 101.201 + vertex -827.965 343.68 108.799 + endloop + endfacet + facet normal 0.899799 -0.420605 0.11599 + outer loop + vertex -830.487 334.859 93.7583 + vertex -827.468 341.324 93.7818 + vertex -830.789 336.258 101.176 + endloop + endfacet + facet normal 0.914855 -0.388361 0.110525 + outer loop + vertex -833.562 329.727 101.176 + vertex -830.487 334.859 93.7583 + vertex -830.789 336.258 101.176 + endloop + endfacet + facet normal 0.896868 -0.419326 0.140689 + outer loop + vertex -830.487 334.859 93.7583 + vertex -826.977 339.954 86.5673 + vertex -827.468 341.324 93.7818 + endloop + endfacet + facet normal 0.885838 -0.441061 0.144068 + outer loop + vertex -826.977 339.954 86.5673 + vertex -823.754 346.434 86.5915 + vertex -827.468 341.324 93.7818 + endloop + endfacet + facet normal 0.88091 -0.438736 0.177506 + outer loop + vertex -826.977 339.954 86.5673 + vertex -822.971 345.167 79.5726 + vertex -823.754 346.434 86.5915 + endloop + endfacet + facet normal 0.874266 -0.451233 0.179019 + outer loop + vertex -822.971 345.167 79.5726 + vertex -819.583 351.737 79.5868 + vertex -823.754 346.434 86.5915 + endloop + endfacet + facet normal 0.870521 -0.462465 0.168286 + outer loop + vertex -823.754 346.434 86.5915 + vertex -819.583 351.737 79.5868 + vertex -820.38 352.791 86.6064 + endloop + endfacet + facet normal 0.866854 -0.469094 0.168865 + outer loop + vertex -819.583 351.737 79.5868 + vertex -816.071 358.226 79.5827 + vertex -820.38 352.791 86.6064 + endloop + endfacet + facet normal 0.859181 -0.464913 0.21369 + outer loop + vertex -819.583 351.737 79.5868 + vertex -814.873 357.321 72.7974 + vertex -816.071 358.226 79.5827 + endloop + endfacet + facet normal 0.860347 -0.462788 0.213612 + outer loop + vertex -814.873 357.321 72.7974 + vertex -811.255 364.024 72.7497 + vertex -816.071 358.226 79.5827 + endloop + endfacet + facet normal 0.855725 -0.478426 0.197086 + outer loop + vertex -816.071 358.226 79.5827 + vertex -811.255 364.024 72.7497 + vertex -812.455 364.678 79.5471 + endloop + endfacet + facet normal 0.861403 -0.468121 0.197097 + outer loop + vertex -811.255 364.024 72.7497 + vertex -807.599 370.724 72.6829 + vertex -812.455 364.678 79.5471 + endloop + endfacet + facet normal 0.852244 -0.462653 0.244198 + outer loop + vertex -811.255 364.024 72.7497 + vertex -806.041 370.268 66.3825 + vertex -807.599 370.724 72.6829 + endloop + endfacet + facet normal 0.872088 -0.422887 0.246229 + outer loop + vertex -806.041 370.268 66.3825 + vertex -802.631 377.326 66.4264 + vertex -807.599 370.724 72.6829 + endloop + endfacet + facet normal 0.868465 -0.443428 0.221674 + outer loop + vertex -807.599 370.724 72.6829 + vertex -802.631 377.326 66.4264 + vertex -804.143 377.497 72.6914 + endloop + endfacet + facet normal 0.914453 -0.333143 0.229763 + outer loop + vertex -802.631 377.326 66.4264 + vertex -800.054 384.55 66.6435 + vertex -804.143 377.497 72.6914 + endloop + endfacet + facet normal 0.855806 -0.444053 0.265355 + outer loop + vertex -809.706 363.223 66.4138 + vertex -806.041 370.268 66.3825 + vertex -811.255 364.024 72.7497 + endloop + endfacet + facet normal 0.849272 -0.456443 0.265324 + outer loop + vertex -814.873 357.321 72.7974 + vertex -809.706 363.223 66.4138 + vertex -811.255 364.024 72.7497 + endloop + endfacet + facet normal 0.851999 -0.441552 0.281298 + outer loop + vertex -813.372 356.197 66.4864 + vertex -809.706 363.223 66.4138 + vertex -814.873 357.321 72.7974 + endloop + endfacet + facet normal 0.85069 -0.443991 0.281421 + outer loop + vertex -818.392 350.591 72.8186 + vertex -813.372 356.197 66.4864 + vertex -814.873 357.321 72.7974 + endloop + endfacet + facet normal 0.853103 -0.429597 0.296077 + outer loop + vertex -816.881 349.253 66.5231 + vertex -813.372 356.197 66.4864 + vertex -818.392 350.591 72.8186 + endloop + endfacet + facet normal 0.855039 -0.425948 0.295766 + outer loop + vertex -821.772 343.798 72.8052 + vertex -816.881 349.253 66.5231 + vertex -818.392 350.591 72.8186 + endloop + endfacet + facet normal 0.857719 -0.406556 0.314691 + outer loop + vertex -820.195 342.236 66.4895 + vertex -816.881 349.253 66.5231 + vertex -821.772 343.798 72.8052 + endloop + endfacet + facet normal 0.861347 -0.399476 0.313846 + outer loop + vertex -824.976 336.87 72.7812 + vertex -820.195 342.236 66.4895 + vertex -821.772 343.798 72.8052 + endloop + endfacet + facet normal 0.862936 -0.384652 0.327696 + outer loop + vertex -823.41 334.97 66.4279 + vertex -820.195 342.236 66.4895 + vertex -824.976 336.87 72.7812 + endloop + endfacet + facet normal 0.869077 -0.372446 0.325559 + outer loop + vertex -828.004 329.787 72.7626 + vertex -823.41 334.97 66.4279 + vertex -824.976 336.87 72.7812 + endloop + endfacet + facet normal 0.870059 -0.361141 0.335521 + outer loop + vertex -826.495 327.555 66.4452 + vertex -823.41 334.97 66.4279 + vertex -828.004 329.787 72.7626 + endloop + endfacet + facet normal 0.881107 -0.338567 0.330185 + outer loop + vertex -830.788 322.569 72.7881 + vertex -826.495 327.555 66.4452 + vertex -828.004 329.787 72.7626 + endloop + endfacet + facet normal 0.881632 -0.330532 0.336857 + outer loop + vertex -829.284 320.161 66.4906 + vertex -826.495 327.555 66.4452 + vertex -830.788 322.569 72.7881 + endloop + endfacet + facet normal 0.895795 -0.299524 0.328384 + outer loop + vertex -833.279 315.193 72.8569 + vertex -829.284 320.161 66.4906 + vertex -830.788 322.569 72.7881 + endloop + endfacet + facet normal 0.896094 -0.290281 0.335786 + outer loop + vertex -831.726 312.679 66.5391 + vertex -829.284 320.161 66.4906 + vertex -833.279 315.193 72.8569 + endloop + endfacet + facet normal 0.909672 -0.257323 0.326009 + outer loop + vertex -835.465 307.543 72.9176 + vertex -831.726 312.679 66.5391 + vertex -833.279 315.193 72.8569 + endloop + endfacet + facet normal 0.909608 -0.250713 0.331294 + outer loop + vertex -833.884 304.888 66.567 + vertex -831.726 312.679 66.5391 + vertex -835.465 307.543 72.9176 + endloop + endfacet + facet normal 0.920829 -0.220668 0.321527 + outer loop + vertex -837.372 299.475 72.8426 + vertex -833.884 304.888 66.567 + vertex -835.465 307.543 72.9176 + endloop + endfacet + facet normal 0.920575 -0.216055 0.325364 + outer loop + vertex -835.795 296.663 66.5126 + vertex -833.884 304.888 66.567 + vertex -837.372 299.475 72.8426 + endloop + endfacet + facet normal 0.926917 -0.197868 0.318863 + outer loop + vertex -839.078 290.897 72.4795 + vertex -835.795 296.663 66.5126 + vertex -837.372 299.475 72.8426 + endloop + endfacet + facet normal 0.926702 -0.195758 0.320784 + outer loop + vertex -837.526 287.939 66.1908 + vertex -835.795 296.663 66.5126 + vertex -839.078 290.897 72.4795 + endloop + endfacet + facet normal 0.924815 -0.201181 0.322869 + outer loop + vertex -840.781 281.852 71.7203 + vertex -837.526 287.939 66.1908 + vertex -839.078 290.897 72.4795 + endloop + endfacet + facet normal 0.924462 -0.198678 0.325417 + outer loop + vertex -839.254 278.695 65.4552 + vertex -837.526 287.939 66.1908 + vertex -840.781 281.852 71.7203 + endloop + endfacet + facet normal 0.908606 -0.239535 0.342138 + outer loop + vertex -839.254 278.695 65.4552 + vertex -840.781 281.852 71.7203 + vertex -841.768 275.326 69.7716 + endloop + endfacet + facet normal 0.908714 -0.244638 0.338218 + outer loop + vertex -841.283 272.94 66.7435 + vertex -839.254 278.695 65.4552 + vertex -841.768 275.326 69.7716 + endloop + endfacet + facet normal 0.893081 -0.22802 0.387831 + outer loop + vertex -841.283 272.94 66.7435 + vertex -840.165 271.946 63.5858 + vertex -839.254 278.695 65.4552 + endloop + endfacet + facet normal 0.871877 -0.236513 0.428826 + outer loop + vertex -837.452 275.472 60.0141 + vertex -839.254 278.695 65.4552 + vertex -840.165 271.946 63.5858 + endloop + endfacet + facet normal 0.871261 -0.232631 0.43219 + outer loop + vertex -839.485 269.435 60.8618 + vertex -837.452 275.472 60.0141 + vertex -840.165 271.946 63.5858 + endloop + endfacet + facet normal 0.892298 -0.191397 0.408865 + outer loop + vertex -837.452 275.472 60.0141 + vertex -835.769 284.96 60.7824 + vertex -839.254 278.695 65.4552 + endloop + endfacet + facet normal 0.894518 -0.199038 0.400276 + outer loop + vertex -839.254 278.695 65.4552 + vertex -835.769 284.96 60.7824 + vertex -837.526 287.939 66.1908 + endloop + endfacet + facet normal 0.898669 -0.18873 0.395948 + outer loop + vertex -835.769 284.96 60.7824 + vertex -834.02 293.852 61.0521 + vertex -837.526 287.939 66.1908 + endloop + endfacet + facet normal 0.899628 -0.193 0.391689 + outer loop + vertex -837.526 287.939 66.1908 + vertex -834.02 293.852 61.0521 + vertex -835.795 296.663 66.5126 + endloop + endfacet + facet normal 0.893804 -0.207794 0.397411 + outer loop + vertex -834.02 293.852 61.0521 + vertex -832.087 302.236 61.0881 + vertex -835.795 296.663 66.5126 + endloop + endfacet + facet normal 0.894247 -0.210399 0.395036 + outer loop + vertex -835.795 296.663 66.5126 + vertex -832.087 302.236 61.0881 + vertex -833.884 304.888 66.567 + endloop + endfacet + facet normal 0.883798 -0.235988 0.403993 + outer loop + vertex -832.087 302.236 61.0881 + vertex -829.941 310.208 61.0494 + vertex -833.884 304.888 66.567 + endloop + endfacet + facet normal 0.88475 -0.243592 0.397341 + outer loop + vertex -833.884 304.888 66.567 + vertex -829.941 310.208 61.0494 + vertex -831.726 312.679 66.5391 + endloop + endfacet + facet normal 0.873214 -0.270207 0.405567 + outer loop + vertex -829.941 310.208 61.0494 + vertex -827.67 317.657 61.122 + vertex -831.726 312.679 66.5391 + endloop + endfacet + facet normal 0.87419 -0.282749 0.394772 + outer loop + vertex -831.726 312.679 66.5391 + vertex -827.67 317.657 61.122 + vertex -829.284 320.161 66.4906 + endloop + endfacet + facet normal 0.86007 -0.311584 0.403974 + outer loop + vertex -827.67 317.657 61.122 + vertex -825.05 324.848 61.0904 + vertex -829.284 320.161 66.4906 + endloop + endfacet + facet normal 0.860338 -0.322141 0.395023 + outer loop + vertex -829.284 320.161 66.4906 + vertex -825.05 324.848 61.0904 + vertex -826.495 327.555 66.4452 + endloop + endfacet + facet normal 0.847553 -0.345105 0.403183 + outer loop + vertex -825.05 324.848 61.0904 + vertex -821.839 332.491 60.8837 + vertex -826.495 327.555 66.4452 + endloop + endfacet + facet normal 0.847591 -0.351651 0.397405 + outer loop + vertex -826.495 327.555 66.4452 + vertex -821.839 332.491 60.8837 + vertex -823.41 334.97 66.4279 + endloop + endfacet + facet normal 0.8414 -0.362719 0.4006 + outer loop + vertex -821.839 332.491 60.8837 + vertex -818.452 340.387 60.9181 + vertex -823.41 334.97 66.4279 + endloop + endfacet + facet normal 0.8416 -0.375722 0.387997 + outer loop + vertex -823.41 334.97 66.4279 + vertex -818.452 340.387 60.9181 + vertex -820.195 342.236 66.4895 + endloop + endfacet + facet normal 0.840163 -0.378457 0.388455 + outer loop + vertex -818.452 340.387 60.9181 + vertex -815.278 347.687 61.1649 + vertex -820.195 342.236 66.4895 + endloop + endfacet + facet normal 0.84014 -0.39851 0.367904 + outer loop + vertex -820.195 342.236 66.4895 + vertex -815.278 347.687 61.1649 + vertex -816.881 349.253 66.5231 + endloop + endfacet + facet normal 0.838078 -0.402364 0.368413 + outer loop + vertex -815.278 347.687 61.1649 + vertex -811.967 354.58 61.1618 + vertex -816.881 349.253 66.5231 + endloop + endfacet + facet normal 0.837179 -0.421269 0.348803 + outer loop + vertex -816.881 349.253 66.5231 + vertex -811.967 354.58 61.1618 + vertex -813.372 356.197 66.4864 + endloop + endfacet + facet normal 0.837437 -0.420814 0.348733 + outer loop + vertex -811.967 354.58 61.1618 + vertex -808.187 361.914 60.935 + vertex -813.372 356.197 66.4864 + endloop + endfacet + facet normal 0.836652 -0.432986 0.335464 + outer loop + vertex -813.372 356.197 66.4864 + vertex -808.187 361.914 60.935 + vertex -809.706 363.223 66.4138 + endloop + endfacet + facet normal 0.843379 -0.420604 0.334371 + outer loop + vertex -808.187 361.914 60.935 + vertex -804.338 369.577 60.8658 + vertex -809.706 363.223 66.4138 + endloop + endfacet + facet normal 0.842574 -0.436949 0.314874 + outer loop + vertex -809.706 363.223 66.4138 + vertex -804.338 369.577 60.8658 + vertex -806.041 370.268 66.3825 + endloop + endfacet + facet normal 0.86092 -0.398886 0.315765 + outer loop + vertex -804.338 369.577 60.8658 + vertex -800.885 377.096 60.95 + vertex -806.041 370.268 66.3825 + endloop + endfacet + facet normal 0.860491 -0.417567 0.291878 + outer loop + vertex -806.041 370.268 66.3825 + vertex -800.885 377.096 60.95 + vertex -802.631 377.326 66.4264 + endloop + endfacet + facet normal 0.901784 -0.31057 0.300551 + outer loop + vertex -800.885 377.096 60.95 + vertex -798.325 384.627 61.051 + vertex -802.631 377.326 66.4264 + endloop + endfacet + facet normal 0.903012 -0.330408 0.274591 + outer loop + vertex -802.631 377.326 66.4264 + vertex -798.325 384.627 61.051 + vertex -800.054 384.55 66.6435 + endloop + endfacet + facet normal 0.928186 -0.228118 0.293994 + outer loop + vertex -842.649 276.21 73.2405 + vertex -841.768 275.326 69.7716 + vertex -840.781 281.852 71.7203 + endloop + endfacet + facet normal 0.936408 -0.241441 0.25465 + outer loop + vertex -842.649 276.21 73.2405 + vertex -840.781 281.852 71.7203 + vertex -842.949 278.433 76.4517 + endloop + endfacet + facet normal 0.936801 -0.233341 0.260682 + outer loop + vertex -840.781 281.852 71.7203 + vertex -841.925 284.779 78.4516 + vertex -842.949 278.433 76.4517 + endloop + endfacet + facet normal 0.95028 -0.222136 0.21823 + outer loop + vertex -843.618 279.151 80.0968 + vertex -842.949 278.433 76.4517 + vertex -841.925 284.779 78.4516 + endloop + endfacet + facet normal 0.954464 -0.232573 0.186835 + outer loop + vertex -843.618 279.151 80.0968 + vertex -841.925 284.779 78.4516 + vertex -843.77 281.194 83.4155 + endloop + endfacet + facet normal 0.955029 -0.226337 0.191549 + outer loop + vertex -841.925 284.779 78.4516 + vertex -842.709 287.39 85.4477 + vertex -843.77 281.194 83.4155 + endloop + endfacet + facet normal 0.963261 -0.197695 0.181781 + outer loop + vertex -841.925 284.779 78.4516 + vertex -840.248 293.674 79.2362 + vertex -842.709 287.39 85.4477 + endloop + endfacet + facet normal 0.948102 -0.199263 0.247782 + outer loop + vertex -840.781 281.852 71.7203 + vertex -839.078 290.897 72.4795 + vertex -841.925 284.779 78.4516 + endloop + endfacet + facet normal 0.948167 -0.200557 0.246488 + outer loop + vertex -841.925 284.779 78.4516 + vertex -839.078 290.897 72.4795 + vertex -840.248 293.674 79.2362 + endloop + endfacet + facet normal 0.94861 -0.199097 0.245965 + outer loop + vertex -839.078 290.897 72.4795 + vertex -837.372 299.475 72.8426 + vertex -840.248 293.674 79.2362 + endloop + endfacet + facet normal 0.948672 -0.202174 0.243201 + outer loop + vertex -840.248 293.674 79.2362 + vertex -837.372 299.475 72.8426 + vertex -838.548 302.117 79.6269 + endloop + endfacet + facet normal 0.941546 -0.224908 0.250816 + outer loop + vertex -837.372 299.475 72.8426 + vertex -835.465 307.543 72.9176 + vertex -838.548 302.117 79.6269 + endloop + endfacet + facet normal 0.941414 -0.230148 0.246517 + outer loop + vertex -838.548 302.117 79.6269 + vertex -835.465 307.543 72.9176 + vertex -836.636 310.021 79.7049 + endloop + endfacet + facet normal 0.929829 -0.263632 0.256744 + outer loop + vertex -835.465 307.543 72.9176 + vertex -833.279 315.193 72.8569 + vertex -836.636 310.021 79.7049 + endloop + endfacet + facet normal 0.929324 -0.270687 0.251168 + outer loop + vertex -836.636 310.021 79.7049 + vertex -833.279 315.193 72.8569 + vertex -834.443 317.491 79.6382 + endloop + endfacet + facet normal 0.915311 -0.306745 0.260984 + outer loop + vertex -833.279 315.193 72.8569 + vertex -830.788 322.569 72.7881 + vertex -834.443 317.491 79.6382 + endloop + endfacet + facet normal 0.914449 -0.31435 0.254887 + outer loop + vertex -834.443 317.491 79.6382 + vertex -830.788 322.569 72.7881 + vertex -831.955 324.671 79.5672 + endloop + endfacet + facet normal 0.900653 -0.346343 0.262433 + outer loop + vertex -830.788 322.569 72.7881 + vertex -828.004 329.787 72.7626 + vertex -831.955 324.671 79.5672 + endloop + endfacet + facet normal 0.899588 -0.353562 0.256387 + outer loop + vertex -831.955 324.671 79.5672 + vertex -828.004 329.787 72.7626 + vertex -829.2 331.659 79.5391 + endloop + endfacet + facet normal 0.88723 -0.38004 0.261519 + outer loop + vertex -828.004 329.787 72.7626 + vertex -824.976 336.87 72.7812 + vertex -829.2 331.659 79.5391 + endloop + endfacet + facet normal 0.885008 -0.392355 0.250634 + outer loop + vertex -829.2 331.659 79.5391 + vertex -824.976 336.87 72.7812 + vertex -826.18 338.483 79.5565 + endloop + endfacet + facet normal 0.896622 -0.397355 0.195393 + outer loop + vertex -829.2 331.659 79.5391 + vertex -826.18 338.483 79.5565 + vertex -829.991 333.323 86.5514 + endloop + endfacet + facet normal 0.909596 -0.369394 0.190219 + outer loop + vertex -832.755 326.527 86.5718 + vertex -829.2 331.659 79.5391 + vertex -829.991 333.323 86.5514 + endloop + endfacet + facet normal 0.89414 -0.406857 0.187032 + outer loop + vertex -829.991 333.323 86.5514 + vertex -826.18 338.483 79.5565 + vertex -826.977 339.954 86.5673 + endloop + endfacet + facet normal 0.877804 -0.406876 0.25281 + outer loop + vertex -824.976 336.87 72.7812 + vertex -821.772 343.798 72.8052 + vertex -826.18 338.483 79.5565 + endloop + endfacet + facet normal 0.874902 -0.420575 0.240131 + outer loop + vertex -826.18 338.483 79.5565 + vertex -821.772 343.798 72.8052 + vertex -822.971 345.167 79.5726 + endloop + endfacet + facet normal 0.868646 -0.43261 0.241459 + outer loop + vertex -821.772 343.798 72.8052 + vertex -818.392 350.591 72.8186 + vertex -822.971 345.167 79.5726 + endloop + endfacet + facet normal 0.863068 -0.450632 0.228134 + outer loop + vertex -818.392 350.591 72.8186 + vertex -814.873 357.321 72.7974 + vertex -819.583 351.737 79.5868 + endloop + endfacet + facet normal 0.865205 -0.446665 0.227839 + outer loop + vertex -822.971 345.167 79.5726 + vertex -818.392 350.591 72.8186 + vertex -819.583 351.737 79.5868 + endloop + endfacet + facet normal 0.884932 -0.425269 0.189847 + outer loop + vertex -826.18 338.483 79.5565 + vertex -822.971 345.167 79.5726 + vertex -826.977 339.954 86.5673 + endloop + endfacet + facet normal 0.900044 -0.40945 0.149236 + outer loop + vertex -829.991 333.323 86.5514 + vertex -826.977 339.954 86.5673 + vertex -830.487 334.859 93.7583 + endloop + endfacet + facet normal 0.914165 -0.379007 0.14372 + outer loop + vertex -833.249 328.203 93.774 + vertex -829.991 333.323 86.5514 + vertex -830.487 334.859 93.7583 + endloop + endfacet + facet normal 0.882057 -0.451473 0.134716 + outer loop + vertex -827.468 341.324 93.7818 + vertex -823.754 346.434 86.5915 + vertex -824.249 347.621 93.8055 + endloop + endfacet + facet normal 0.874893 -0.464711 0.136403 + outer loop + vertex -823.754 346.434 86.5915 + vertex -820.38 352.791 86.6064 + vertex -824.249 347.621 93.8055 + endloop + endfacet + facet normal 0.86181 -0.482954 0.155046 + outer loop + vertex -820.38 352.791 86.6064 + vertex -816.071 358.226 79.5827 + vertex -816.865 359.066 86.6134 + endloop + endfacet + facet normal 0.862192 -0.482283 0.155009 + outer loop + vertex -816.071 358.226 79.5827 + vertex -812.455 364.678 79.5471 + vertex -816.865 359.066 86.6134 + endloop + endfacet + facet normal 0.856584 -0.483561 0.18009 + outer loop + vertex -812.455 364.678 79.5471 + vertex -807.599 370.724 72.6829 + vertex -808.8 371.128 79.4781 + endloop + endfacet + facet normal 0.875879 -0.447161 0.181336 + outer loop + vertex -807.599 370.724 72.6829 + vertex -804.143 377.497 72.6914 + vertex -808.8 371.128 79.4781 + endloop + endfacet + facet normal 0.911932 -0.360284 0.196406 + outer loop + vertex -804.143 377.497 72.6914 + vertex -800.054 384.55 66.6435 + vertex -801.425 384.478 72.8769 + endloop + endfacet + facet normal 0.869068 -0.48237 0.109727 + outer loop + vertex -809.599 371.531 86.5602 + vertex -805.301 377.665 79.4783 + vertex -806.099 377.839 86.568 + endloop + endfacet + facet normal 0.858443 -0.503221 0.0992193 + outer loop + vertex -813.256 365.299 86.5942 + vertex -809.599 371.531 86.5602 + vertex -813.746 365.891 93.8317 + endloop + endfacet + facet normal 0.853898 -0.510833 0.0995344 + outer loop + vertex -817.353 359.861 93.8324 + vertex -813.256 365.299 86.5942 + vertex -813.746 365.891 93.8317 + endloop + endfacet + facet normal 0.86175 -0.498204 0.095815 + outer loop + vertex -820.865 353.785 93.8224 + vertex -817.353 359.861 93.8324 + vertex -821.165 354.692 101.233 + endloop + endfacet + facet normal 0.866247 -0.490491 0.0950529 + outer loop + vertex -824.553 348.706 101.221 + vertex -820.865 353.785 93.8224 + vertex -821.165 354.692 101.233 + endloop + endfacet + facet normal 0.881542 -0.463548 0.0894831 + outer loop + vertex -827.773 342.578 101.201 + vertex -824.553 348.706 101.221 + vertex -827.965 343.68 108.799 + endloop + endfacet + facet normal 0.895854 -0.437753 0.0762807 + outer loop + vertex -830.984 337.495 108.772 + vertex -827.965 343.68 108.799 + vertex -831.116 338.572 116.49 + endloop + endfacet + facet normal 0.913411 -0.400726 0.0714139 + outer loop + vertex -833.89 332.244 116.473 + vertex -830.984 337.495 108.772 + vertex -831.116 338.572 116.49 + endloop + endfacet + facet normal 0.87388 -0.481706 0.0655237 + outer loop + vertex -828.092 344.633 116.517 + vertex -824.745 349.658 108.812 + vertex -824.87 350.479 116.526 + endloop + endfacet + facet normal 0.862795 -0.50104 0.067401 + outer loop + vertex -824.745 349.658 108.812 + vertex -821.359 355.489 108.815 + vertex -824.87 350.479 116.526 + endloop + endfacet + facet normal 0.850444 -0.52203 0.0650403 + outer loop + vertex -821.359 355.489 108.815 + vertex -817.65 360.587 101.241 + vertex -817.839 361.223 108.818 + endloop + endfacet + facet normal 0.848676 -0.524874 0.0652349 + outer loop + vertex -817.65 360.587 101.241 + vertex -814.038 366.429 101.249 + vertex -817.839 361.223 108.818 + endloop + endfacet + facet normal 0.845664 -0.530614 0.0574562 + outer loop + vertex -814.038 366.429 101.249 + vertex -810.095 371.91 93.828 + vertex -810.385 372.251 101.257 + endloop + endfacet + facet normal 0.865463 -0.497751 0.0567233 + outer loop + vertex -810.095 371.91 93.828 + vertex -806.595 377.996 93.8381 + vertex -810.385 372.251 101.257 + endloop + endfacet + facet normal 0.907448 -0.415788 0.060482 + outer loop + vertex -806.595 377.996 93.8381 + vertex -803.2 384.352 86.5938 + vertex -803.706 384.299 93.8248 + endloop + endfacet + facet normal 0.853005 -0.521189 0.027271 + outer loop + vertex -810.557 372.544 108.826 + vertex -806.896 378.14 101.271 + vertex -807.066 378.259 108.854 + endloop + endfacet + facet normal 0.838323 -0.543667 0.0405076 + outer loop + vertex -814.22 366.896 108.822 + vertex -810.557 372.544 108.826 + vertex -814.331 367.297 116.518 + endloop + endfacet + facet normal 0.8354 -0.548134 0.0406985 + outer loop + vertex -817.958 361.769 116.522 + vertex -814.22 366.896 108.822 + vertex -814.331 367.297 116.518 + endloop + endfacet + facet normal 0.845046 -0.532532 0.0480218 + outer loop + vertex -821.484 356.176 116.524 + vertex -817.958 361.769 116.522 + vertex -821.559 356.76 124.32 + endloop + endfacet + facet normal 0.853869 -0.518358 0.0470447 + outer loop + vertex -824.947 351.178 124.324 + vertex -821.484 356.176 116.524 + vertex -821.559 356.76 124.32 + endloop + endfacet + facet normal 0.870837 -0.489336 0.046834 + outer loop + vertex -828.169 345.444 124.318 + vertex -824.947 351.178 124.324 + vertex -828.212 346.12 132.175 + endloop + endfacet + facet normal 0.887717 -0.458258 0.0442504 + outer loop + vertex -831.237 340.257 132.153 + vertex -828.169 345.444 124.318 + vertex -828.212 346.12 132.175 + endloop + endfacet + facet normal 0.850206 -0.525297 0.0348355 + outer loop + vertex -824.994 351.766 132.18 + vertex -821.604 357.252 132.176 + vertex -825.021 352.245 140.07 + endloop + endfacet + facet normal 0.835765 -0.548142 0.0322037 + outer loop + vertex -821.604 357.252 132.176 + vertex -818.032 362.236 124.313 + vertex -818.077 362.629 132.168 + endloop + endfacet + facet normal 0.829581 -0.557432 0.0326336 + outer loop + vertex -818.032 362.236 124.313 + vertex -814.4 367.64 124.305 + vertex -818.077 362.629 132.168 + endloop + endfacet + facet normal 0.824819 -0.564958 0.0222621 + outer loop + vertex -814.4 367.64 124.305 + vertex -810.659 372.796 116.517 + vertex -810.721 373.012 124.306 + endloop + endfacet + facet normal 0.846648 -0.531719 0.0215179 + outer loop + vertex -810.659 372.796 116.517 + vertex -807.165 378.362 116.571 + vertex -810.721 373.012 124.306 + endloop + endfacet + facet normal 0.898359 -0.439163 0.00935188 + outer loop + vertex -807.165 378.362 116.571 + vertex -804.227 384.209 108.998 + vertex -804.327 384.172 116.819 + endloop + endfacet + facet normal 0.835628 -0.549221 0.00904498 + outer loop + vertex -810.762 373.194 132.168 + vertex -807.223 378.45 124.368 + vertex -807.26 378.523 132.206 + endloop + endfacet + facet normal 0.819314 -0.572993 0.0200874 + outer loop + vertex -814.443 367.93 132.162 + vertex -810.762 373.194 132.168 + vertex -814.472 368.166 140.058 + endloop + endfacet + facet normal 0.820365 -0.571488 0.0200461 + outer loop + vertex -818.106 362.95 140.06 + vertex -814.443 367.93 132.162 + vertex -814.472 368.166 140.058 + endloop + endfacet + facet normal 0.832159 -0.554 0.0243798 + outer loop + vertex -821.632 357.653 140.066 + vertex -818.106 362.95 140.06 + vertex -821.654 357.967 147.954 + endloop + endfacet + facet normal 0.844621 -0.534842 0.0236535 + outer loop + vertex -825.042 352.617 147.958 + vertex -821.632 357.653 140.066 + vertex -821.654 357.967 147.954 + endloop + endfacet + facet normal 0.862844 -0.505026 0.0211931 + outer loop + vertex -828.265 347.11 147.953 + vertex -825.042 352.617 147.958 + vertex -828.28 347.414 155.806 + endloop + endfacet + facet normal 0.883268 -0.46845 0.0198109 + outer loop + vertex -831.302 341.715 155.785 + vertex -828.265 347.11 147.953 + vertex -828.28 347.414 155.806 + endloop + endfacet + facet normal 0.842817 -0.538069 0.0118834 + outer loop + vertex -825.06 352.885 155.812 + vertex -821.672 358.192 155.808 + vertex -825.069 353.044 163.632 + endloop + endfacet + facet normal 0.826726 -0.562422 0.0143454 + outer loop + vertex -821.672 358.192 155.808 + vertex -818.128 363.2 147.95 + vertex -818.144 363.378 155.805 + endloop + endfacet + facet normal 0.816824 -0.576702 0.0146481 + outer loop + vertex -818.128 363.2 147.95 + vertex -814.493 368.349 147.95 + vertex -818.144 363.378 155.805 + endloop + endfacet + facet normal 0.811009 -0.584937 0.0106607 + outer loop + vertex -814.493 368.349 147.95 + vertex -810.79 373.34 140.066 + vertex -810.812 373.453 147.958 + endloop + endfacet + facet normal 0.831306 -0.55572 0.0102975 + outer loop + vertex -810.79 373.34 140.066 + vertex -807.286 378.582 140.105 + vertex -810.812 373.453 147.958 + endloop + endfacet + facet normal 0.887526 -0.460756 0.00140126 + outer loop + vertex -807.286 378.582 140.105 + vertex -804.401 384.115 132.225 + vertex -804.425 384.093 140.323 + endloop + endfacet + facet normal 0.824588 -0.565725 0.00329858 + outer loop + vertex -810.831 373.534 155.81 + vertex -807.307 378.625 148.012 + vertex -807.319 378.653 155.871 + endloop + endfacet + facet normal 0.808499 -0.588456 0.00699401 + outer loop + vertex -814.51 368.479 155.805 + vertex -810.831 373.534 155.81 + vertex -814.521 368.556 163.624 + endloop + endfacet + facet normal 0.812884 -0.582384 0.00693993 + outer loop + vertex -818.155 363.485 163.627 + vertex -814.51 368.479 155.805 + vertex -814.521 368.556 163.624 + endloop + endfacet + facet normal 0.825627 -0.564205 0.00361483 + outer loop + vertex -821.681 358.325 163.629 + vertex -818.155 363.485 163.627 + vertex -821.684 358.37 171.455 + endloop + endfacet + facet normal 0.840998 -0.541027 0.00348747 + outer loop + vertex -825.074 353.101 171.457 + vertex -821.681 358.325 163.629 + vertex -821.684 358.37 171.455 + endloop + endfacet + facet normal 0.860199 -0.509943 -0.00394134 + outer loop + vertex -828.295 347.667 171.45 + vertex -825.074 353.101 171.457 + vertex -828.292 347.612 179.323 + endloop + endfacet + facet normal 0.882075 -0.470909 -0.0137048 + outer loop + vertex -831.316 341.948 179.3 + vertex -828.292 347.612 179.323 + vertex -831.302 341.744 187.241 + endloop + endfacet + facet normal 0.861604 -0.507465 -0.0108703 + outer loop + vertex -828.279 347.427 187.265 + vertex -825.069 353.048 179.333 + vertex -825.06 352.892 187.275 + endloop + endfacet + facet normal 0.841791 -0.539681 -0.0114791 + outer loop + vertex -825.069 353.048 179.333 + vertex -821.682 358.33 179.331 + vertex -825.06 352.892 187.275 + endloop + endfacet + facet normal 0.825352 -0.56461 -0.00299473 + outer loop + vertex -821.682 358.33 179.331 + vertex -818.159 363.522 171.451 + vertex -818.155 363.486 179.328 + endloop + endfacet + facet normal 0.812115 -0.583489 -0.00307398 + outer loop + vertex -818.159 363.522 171.451 + vertex -814.525 368.58 171.448 + vertex -818.155 363.486 179.328 + endloop + endfacet + facet normal 0.805753 -0.59225 0.00133164 + outer loop + vertex -814.525 368.58 171.448 + vertex -810.839 373.577 163.628 + vertex -810.843 373.589 171.452 + endloop + endfacet + facet normal 0.822978 -0.568074 1.1451e-05 + outer loop + vertex -810.843 373.589 171.452 + vertex -807.336 378.67 163.698 + vertex -807.337 378.669 171.501 + endloop + endfacet + facet normal 0.882559 -0.470201 0.00017119 + outer loop + vertex -807.337 378.669 171.501 + vertex -804.465 384.057 163.949 + vertex -804.468 384.054 171.53 + endloop + endfacet + facet normal 0.824759 -0.565478 -0.00264571 + outer loop + vertex -810.831 373.51 187.278 + vertex -807.331 378.652 179.38 + vertex -807.325 378.624 187.349 + endloop + endfacet + facet normal 0.807398 -0.589985 -0.0051379 + outer loop + vertex -814.513 368.472 187.269 + vertex -810.841 373.567 179.33 + vertex -810.831 373.51 187.278 + endloop + endfacet + facet normal 0.814065 -0.580733 -0.00686636 + outer loop + vertex -818.145 363.38 187.272 + vertex -814.522 368.553 179.324 + vertex -814.513 368.472 187.269 + endloop + endfacet + facet normal 0.826881 -0.56211 -0.0173354 + outer loop + vertex -821.671 358.194 187.276 + vertex -818.145 363.38 187.272 + vertex -821.655 357.971 195.263 + endloop + endfacet + facet normal 0.844485 -0.535321 -0.0166216 + outer loop + vertex -825.044 352.625 195.261 + vertex -821.671 358.194 187.276 + vertex -821.655 357.971 195.263 + endloop + endfacet + facet normal 0.862722 -0.504825 -0.029358 + outer loop + vertex -828.264 347.123 195.247 + vertex -825.044 352.625 195.261 + vertex -828.245 346.692 203.221 + endloop + endfacet + facet normal 0.885723 -0.462576 -0.0389605 + outer loop + vertex -831.26 340.92 203.199 + vertex -828.245 346.692 203.221 + vertex -831.235 340.3 211.118 + endloop + endfacet + facet normal 0.867768 -0.495865 -0.0331188 + outer loop + vertex -828.216 346.128 211.137 + vertex -825.021 352.246 203.236 + vertex -824.996 351.762 211.156 + endloop + endfacet + facet normal 0.847135 -0.530213 -0.0351515 + outer loop + vertex -825.021 352.246 203.236 + vertex -821.635 357.657 203.241 + vertex -824.996 351.762 211.156 + endloop + endfacet + facet normal 0.832019 -0.554392 -0.0198448 + outer loop + vertex -821.635 357.657 203.241 + vertex -818.13 363.202 195.259 + vertex -818.109 362.948 203.238 + endloop + endfacet + facet normal 0.819665 -0.572625 -0.0157873 + outer loop + vertex -818.109 362.948 203.238 + vertex -814.498 368.337 195.257 + vertex -814.478 368.146 203.236 + endloop + endfacet + facet normal 0.813306 -0.581728 -0.0112092 + outer loop + vertex -814.478 368.146 203.236 + vertex -810.816 373.419 195.267 + vertex -810.797 373.293 203.248 + endloop + endfacet + facet normal 0.830547 -0.55691 -0.00654479 + outer loop + vertex -810.797 373.293 203.248 + vertex -807.313 378.58 195.34 + vertex -807.292 378.519 203.322 + endloop + endfacet + facet normal 0.889412 -0.457105 -0.00105972 + outer loop + vertex -807.292 378.519 203.322 + vertex -804.446 384.074 195.596 + vertex -804.428 384.091 203.587 + endloop + endfacet + facet normal 0.839377 -0.543453 -0.0102931 + outer loop + vertex -810.74 372.932 219.027 + vertex -807.268 378.443 211.245 + vertex -807.232 378.349 219.1 + endloop + endfacet + facet normal 0.823069 -0.567653 -0.0181094 + outer loop + vertex -814.417 367.601 219.012 + vertex -810.776 373.131 211.176 + vertex -810.74 372.932 219.027 + endloop + endfacet + facet normal 0.828517 -0.559388 -0.0253852 + outer loop + vertex -818.048 362.224 219.01 + vertex -814.453 367.904 211.163 + vertex -814.417 367.601 219.012 + endloop + endfacet + facet normal 0.840436 -0.540999 -0.0314199 + outer loop + vertex -821.571 356.751 219.008 + vertex -818.084 362.623 211.163 + vertex -818.048 362.224 219.01 + endloop + endfacet + facet normal 0.854413 -0.518282 -0.0368975 + outer loop + vertex -824.958 351.168 218.998 + vertex -821.608 357.249 211.163 + vertex -821.571 356.751 219.008 + endloop + endfacet + facet normal 0.869991 -0.489576 -0.0585741 + outer loop + vertex -828.181 345.444 218.978 + vertex -824.958 351.168 218.998 + vertex -828.118 344.627 226.741 + endloop + endfacet + facet normal 0.891382 -0.447176 -0.073975 + outer loop + vertex -831.136 338.614 226.722 + vertex -828.118 344.627 226.741 + vertex -831.03 337.553 234.413 + endloop + endfacet + facet normal 0.878075 -0.474315 -0.0633195 + outer loop + vertex -828.005 343.678 234.431 + vertex -824.895 350.46 226.763 + vertex -824.785 349.637 234.454 + endloop + endfacet + facet normal 0.863023 -0.501855 -0.0577368 + outer loop + vertex -824.785 349.637 234.454 + vertex -821.508 356.155 226.774 + vertex -821.398 355.46 234.465 + endloop + endfacet + facet normal 0.850675 -0.523313 -0.0499524 + outer loop + vertex -821.398 355.46 234.465 + vertex -817.985 361.741 226.777 + vertex -817.877 361.183 234.468 + endloop + endfacet + facet normal 0.840138 -0.540793 -0.0413802 + outer loop + vertex -817.877 361.183 234.468 + vertex -814.356 367.241 226.781 + vertex -814.248 366.821 234.47 + endloop + endfacet + facet normal 0.835587 -0.548482 -0.0310116 + outer loop + vertex -814.248 366.821 234.47 + vertex -810.679 372.693 226.794 + vertex -810.575 372.416 234.479 + endloop + endfacet + facet normal 0.852656 -0.522104 -0.0196453 + outer loop + vertex -810.575 372.416 234.479 + vertex -807.184 378.24 226.87 + vertex -807.084 378.114 234.544 + endloop + endfacet + facet normal 0.906411 -0.42231 -0.0085741 + outer loop + vertex -807.084 378.114 234.544 + vertex -804.334 384.169 227.118 + vertex -804.245 384.204 234.765 + endloop + endfacet + facet normal 0.865746 -0.498592 -0.0434606 + outer loop + vertex -810.095 371.808 249.564 + vertex -806.91 377.984 242.158 + vertex -806.607 377.855 249.672 + endloop + endfacet + facet normal 0.85015 -0.523578 -0.0557705 + outer loop + vertex -813.756 365.864 249.556 + vertex -810.396 372.117 242.075 + vertex -810.095 371.808 249.564 + endloop + endfacet + facet normal 0.853556 -0.516421 -0.0689335 + outer loop + vertex -817.378 359.877 249.562 + vertex -814.063 366.356 242.069 + vertex -813.756 365.864 249.556 + endloop + endfacet + facet normal 0.861785 -0.500816 -0.080679 + outer loop + vertex -820.898 353.819 249.564 + vertex -817.687 360.552 242.071 + vertex -817.378 359.877 249.562 + endloop + endfacet + facet normal 0.872044 -0.480821 -0.0913778 + outer loop + vertex -824.285 347.678 249.557 + vertex -821.21 354.677 242.071 + vertex -820.898 353.819 249.564 + endloop + endfacet + facet normal 0.884607 -0.455752 -0.0987927 + outer loop + vertex -827.509 341.425 249.54 + vertex -824.594 348.703 242.061 + vertex -824.285 347.678 249.557 + endloop + endfacet + facet normal 0.900784 -0.421776 -0.103411 + outer loop + vertex -830.52 334.997 249.526 + vertex -827.816 342.607 242.04 + vertex -827.509 341.425 249.54 + endloop + endfacet + facet normal 0.882377 -0.470521 0.00463033 + outer loop + vertex -831.316 341.93 163.605 + vertex -828.291 347.602 163.626 + vertex -831.318 342.004 171.428 + endloop + endfacet + facet normal 0.883358 -0.468477 0.0144097 + outer loop + vertex -831.302 341.715 155.785 + vertex -828.28 347.414 155.806 + vertex -831.316 341.93 163.605 + endloop + endfacet + facet normal 0.884615 -0.465794 0.0221625 + outer loop + vertex -831.287 341.37 147.931 + vertex -828.265 347.11 147.953 + vertex -831.302 341.715 155.785 + endloop + endfacet + facet normal 0.886274 -0.462098 0.0313721 + outer loop + vertex -831.263 340.88 140.044 + vertex -828.242 346.676 140.065 + vertex -831.287 341.37 147.931 + endloop + endfacet + facet normal 0.887915 -0.45834 0.03914 + outer loop + vertex -831.237 340.257 132.153 + vertex -828.212 346.12 132.175 + vertex -831.263 340.88 140.044 + endloop + endfacet + facet normal 0.890503 -0.452301 0.0492842 + outer loop + vertex -831.193 339.488 124.293 + vertex -828.169 345.444 124.318 + vertex -831.237 340.257 132.153 + endloop + endfacet + facet normal 0.911989 -0.406276 0.0566991 + outer loop + vertex -833.97 333.249 124.27 + vertex -831.116 338.572 116.49 + vertex -831.193 339.488 124.293 + endloop + endfacet + facet normal 0.914049 -0.400977 0.0610802 + outer loop + vertex -833.89 332.244 116.473 + vertex -831.116 338.572 116.49 + vertex -833.97 333.249 124.27 + endloop + endfacet + facet normal 0.914973 -0.396506 0.0748808 + outer loop + vertex -833.765 331.078 108.759 + vertex -830.984 337.495 108.772 + vertex -833.89 332.244 116.473 + endloop + endfacet + facet normal 0.916436 -0.389032 0.0938046 + outer loop + vertex -833.562 329.727 101.176 + vertex -830.789 336.258 101.176 + vertex -833.765 331.078 108.759 + endloop + endfacet + facet normal 0.91738 -0.380404 0.117076 + outer loop + vertex -833.249 328.203 93.774 + vertex -830.487 334.859 93.7583 + vertex -833.562 329.727 101.176 + endloop + endfacet + facet normal 0.916064 -0.372148 0.14944 + outer loop + vertex -832.755 326.527 86.5718 + vertex -829.991 333.323 86.5514 + vertex -833.249 328.203 93.774 + endloop + endfacet + facet normal 0.911955 -0.358666 0.19924 + outer loop + vertex -831.955 324.671 79.5672 + vertex -829.2 331.659 79.5391 + vertex -832.755 326.527 86.5718 + endloop + endfacet + facet normal 0.942458 -0.275091 0.189993 + outer loop + vertex -836.636 310.021 79.7049 + vertex -834.443 317.491 79.6382 + vertex -837.409 312.218 86.7181 + endloop + endfacet + facet normal 0.954671 -0.237421 0.17954 + outer loop + vertex -839.322 304.46 86.6334 + vertex -836.636 310.021 79.7049 + vertex -837.409 312.218 86.7181 + endloop + endfacet + facet normal 0.955072 -0.232828 0.183382 + outer loop + vertex -838.548 302.117 79.6269 + vertex -836.636 310.021 79.7049 + vertex -839.322 304.46 86.6334 + endloop + endfacet + facet normal 0.962297 -0.207604 0.175742 + outer loop + vertex -841.04 296.162 86.2358 + vertex -838.548 302.117 79.6269 + vertex -839.322 304.46 86.6334 + endloop + endfacet + facet normal 0.962534 -0.202077 0.18081 + outer loop + vertex -840.248 293.674 79.2362 + vertex -838.548 302.117 79.6269 + vertex -841.04 296.162 86.2358 + endloop + endfacet + facet normal 0.963234 -0.199479 0.179966 + outer loop + vertex -842.709 287.39 85.4477 + vertex -840.248 293.674 79.2362 + vertex -841.04 296.162 86.2358 + endloop + endfacet + facet normal 0.96283 -0.217417 0.160276 + outer loop + vertex -844.276 281.739 87.194 + vertex -843.77 281.194 83.4155 + vertex -842.709 287.39 85.4477 + endloop + endfacet + facet normal 0.950662 -0.262606 0.165168 + outer loop + vertex -845.279 277.596 86.3812 + vertex -843.77 281.194 83.4155 + vertex -844.276 281.739 87.194 + endloop + endfacet + facet normal 0.95094 -0.257434 0.171583 + outer loop + vertex -844.981 276.303 82.7881 + vertex -843.77 281.194 83.4155 + vertex -845.279 277.596 86.3812 + endloop + endfacet + facet normal 0.944068 -0.259776 0.203104 + outer loop + vertex -844.981 276.303 82.7881 + vertex -843.618 279.151 80.0968 + vertex -843.77 281.194 83.4155 + endloop + endfacet + facet normal 0.943979 -0.261771 0.200947 + outer loop + vertex -844.613 274.925 79.2649 + vertex -843.618 279.151 80.0968 + vertex -844.981 276.303 82.7881 + endloop + endfacet + facet normal 0.937804 -0.264927 0.224361 + outer loop + vertex -844.613 274.925 79.2649 + vertex -842.949 278.433 76.4517 + vertex -843.618 279.151 80.0968 + endloop + endfacet + facet normal 0.937733 -0.261092 0.229102 + outer loop + vertex -844.175 273.453 75.7953 + vertex -842.949 278.433 76.4517 + vertex -844.613 274.925 79.2649 + endloop + endfacet + facet normal 0.92637 -0.263556 0.269028 + outer loop + vertex -844.175 273.453 75.7953 + vertex -842.649 276.21 73.2405 + vertex -842.949 278.433 76.4517 + endloop + endfacet + facet normal 0.926418 -0.265686 0.266758 + outer loop + vertex -843.646 271.885 72.3969 + vertex -842.649 276.21 73.2405 + vertex -844.175 273.453 75.7953 + endloop + endfacet + facet normal 0.91465 -0.26968 0.301143 + outer loop + vertex -843.646 271.885 72.3969 + vertex -841.768 275.326 69.7716 + vertex -842.649 276.21 73.2405 + endloop + endfacet + facet normal 0.914235 -0.266056 0.305596 + outer loop + vertex -843.023 270.232 69.0939 + vertex -841.768 275.326 69.7716 + vertex -843.646 271.885 72.3969 + endloop + endfacet + facet normal 0.895791 -0.268024 0.354573 + outer loop + vertex -843.023 270.232 69.0939 + vertex -841.283 272.94 66.7435 + vertex -841.768 275.326 69.7716 + endloop + endfacet + facet normal 0.895829 -0.268343 0.354235 + outer loop + vertex -842.287 268.502 65.9198 + vertex -841.283 272.94 66.7435 + vertex -843.023 270.232 69.0939 + endloop + endfacet + facet normal 0.954037 -0.260193 0.148705 + outer loop + vertex -845.279 277.596 86.3812 + vertex -844.276 281.739 87.194 + vertex -845.517 278.825 90.0576 + endloop + endfacet + facet normal 0.969874 -0.213637 0.117063 + outer loop + vertex -844.691 284.053 94.5176 + vertex -844.312 283.637 90.6176 + vertex -843.226 289.677 92.6381 + endloop + endfacet + facet normal 0.975235 -0.19776 0.0990318 + outer loop + vertex -843.226 289.677 92.6381 + vertex -841.55 298.331 93.4222 + vertex -843.572 291.674 100.038 + endloop + endfacet + facet normal 0.963693 -0.251453 0.0898191 + outer loop + vertex -845.918 282.159 101.347 + vertex -844.661 285.781 97.9983 + vertex -844.973 286.009 101.99 + endloop + endfacet + facet normal 0.964842 -0.250185 0.0805386 + outer loop + vertex -845.918 282.159 101.347 + vertex -844.973 286.009 101.99 + vertex -846.004 283.063 105.184 + endloop + endfacet + facet normal 0.976183 -0.207733 0.0625638 + outer loop + vertex -845.109 287.848 109.79 + vertex -844.889 287.619 105.594 + vertex -843.776 293.497 107.751 + endloop + endfacet + facet normal 0.978048 -0.202892 0.0475137 + outer loop + vertex -845.057 289.883 117.369 + vertex -844.939 289.556 113.546 + vertex -843.915 295.017 115.79 + endloop + endfacet + facet normal 0.977184 -0.199442 0.0730405 + outer loop + vertex -843.572 291.674 100.038 + vertex -841.88 300.266 100.857 + vertex -843.776 293.497 107.751 + endloop + endfacet + facet normal 0.972347 -0.213512 0.0946214 + outer loop + vertex -841.88 300.266 100.857 + vertex -839.82 306.533 93.8367 + vertex -840.136 308.391 101.273 + endloop + endfacet + facet normal 0.964004 -0.246785 0.0989636 + outer loop + vertex -840.136 308.391 101.273 + vertex -837.903 314.167 93.9229 + vertex -838.216 315.914 101.334 + endloop + endfacet + facet normal 0.974996 -0.215049 0.0560087 + outer loop + vertex -842.078 302.029 108.574 + vertex -840.324 310.072 108.922 + vertex -842.161 303.705 116.456 + endloop + endfacet + facet normal 0.978039 -0.201526 0.0531659 + outer loop + vertex -843.915 295.017 115.79 + vertex -842.078 302.029 108.574 + vertex -842.161 303.705 116.456 + endloop + endfacet + facet normal 0.978134 -0.197201 0.0660793 + outer loop + vertex -845.057 289.883 117.369 + vertex -843.915 295.017 115.79 + vertex -845.644 288.716 122.573 + endloop + endfacet + facet normal 0.978795 -0.202341 0.0319071 + outer loop + vertex -843.857 297.011 123.775 + vertex -842.183 305.207 124.378 + vertex -843.837 298.378 131.821 + endloop + endfacet + facet normal 0.975397 -0.216114 0.0435373 + outer loop + vertex -842.183 305.207 124.378 + vertex -840.43 311.569 116.694 + vertex -840.498 312.838 124.514 + endloop + endfacet + facet normal 0.966327 -0.252856 0.0477063 + outer loop + vertex -840.498 312.838 124.514 + vertex -838.545 318.816 116.632 + vertex -838.63 319.955 124.409 + endloop + endfacet + facet normal 0.975955 -0.21626 0.0272676 + outer loop + vertex -842.205 306.362 132.288 + vertex -840.547 313.851 132.354 + vertex -842.232 307.231 140.173 + endloop + endfacet + facet normal 0.979205 -0.201251 0.0256252 + outer loop + vertex -843.843 299.345 139.769 + vertex -842.205 306.362 132.288 + vertex -842.232 307.231 140.173 + endloop + endfacet + facet normal 0.976531 -0.214378 0.0207198 + outer loop + vertex -845.614 291.198 138.94 + vertex -843.843 299.345 139.769 + vertex -845.617 291.947 146.871 + endloop + endfacet + facet normal 0.979494 -0.200924 0.0148435 + outer loop + vertex -843.86 300.045 147.659 + vertex -842.258 307.882 148.04 + vertex -843.877 300.543 155.504 + endloop + endfacet + facet normal 0.97601 -0.216658 0.0215556 + outer loop + vertex -842.258 307.882 148.04 + vertex -840.582 314.657 140.219 + vertex -840.612 315.304 148.098 + endloop + endfacet + facet normal 0.966136 -0.25698 0.0232839 + outer loop + vertex -840.612 315.304 148.098 + vertex -838.721 321.69 140.12 + vertex -838.745 322.313 148.007 + endloop + endfacet + facet normal 0.975951 -0.217781 0.00951096 + outer loop + vertex -842.279 308.367 155.891 + vertex -840.629 315.766 155.952 + vertex -842.29 308.661 163.713 + endloop + endfacet + facet normal 0.979565 -0.20093 0.00888313 + outer loop + vertex -843.888 300.853 163.312 + vertex -842.279 308.367 155.891 + vertex -842.29 308.661 163.713 + endloop + endfacet + facet normal 0.977141 -0.212553 0.00412194 + outer loop + vertex -845.634 292.812 162.517 + vertex -843.888 300.853 163.312 + vertex -845.636 292.954 170.307 + endloop + endfacet + facet normal 0.979649 -0.200707 -0.00218375 + outer loop + vertex -843.892 300.975 171.135 + vertex -842.293 308.774 171.543 + vertex -843.89 300.9 179.006 + endloop + endfacet + facet normal 0.975885 -0.218261 0.00322901 + outer loop + vertex -842.293 308.774 171.543 + vertex -840.639 316.054 163.781 + vertex -840.641 316.16 171.607 + endloop + endfacet + facet normal 0.966031 -0.25841 0.00291586 + outer loop + vertex -840.641 316.16 171.607 + vertex -838.776 323.043 163.692 + vertex -838.775 323.137 171.515 + endloop + endfacet + facet normal 0.975883 -0.218107 -0.00903885 + outer loop + vertex -842.287 308.7 179.412 + vertex -840.636 316.082 179.471 + vertex -842.277 308.415 187.328 + endloop + endfacet + facet normal 0.979477 -0.20138 -0.00844057 + outer loop + vertex -843.881 300.63 186.934 + vertex -842.287 308.7 179.412 + vertex -842.277 308.415 187.328 + endloop + endfacet + facet normal 0.976878 -0.213421 -0.0126955 + outer loop + vertex -845.636 292.645 186.134 + vertex -843.881 300.63 186.934 + vertex -845.633 292.184 194.109 + endloop + endfacet + facet normal 0.979296 -0.201576 -0.0186297 + outer loop + vertex -843.873 300.144 194.896 + vertex -842.266 307.913 195.301 + vertex -843.868 299.426 202.909 + endloop + endfacet + facet normal 0.975829 -0.218004 -0.0152022 + outer loop + vertex -842.266 307.913 195.301 + vertex -840.625 315.808 187.398 + vertex -840.611 315.316 195.382 + endloop + endfacet + facet normal 0.966316 -0.256851 -0.0161652 + outer loop + vertex -840.611 315.316 195.382 + vertex -838.756 322.801 187.319 + vertex -838.742 322.351 195.311 + endloop + endfacet + facet normal 0.975716 -0.217508 -0.0258556 + outer loop + vertex -842.257 307.201 203.311 + vertex -840.598 314.636 203.377 + vertex -842.234 306.363 211.238 + endloop + endfacet + facet normal 0.979011 -0.202357 -0.0242625 + outer loop + vertex -843.862 298.514 211.001 + vertex -842.257 307.201 203.311 + vertex -842.234 306.363 211.238 + endloop + endfacet + facet normal 0.975962 -0.215898 -0.0297825 + outer loop + vertex -845.647 290.563 210.162 + vertex -843.862 298.514 211.001 + vertex -845.69 289.152 218.968 + endloop + endfacet + facet normal 0.950165 -0.300782 -0.0819512 + outer loop + vertex -846.416 284.9 226.159 + vertex -847.27 282.845 223.8 + vertex -845.69 289.152 218.968 + endloop + endfacet + facet normal 0.946229 -0.316523 -0.066809 + outer loop + vertex -847.563 281.182 227.522 + vertex -847.27 282.845 223.8 + vertex -846.416 284.9 226.159 + endloop + endfacet + facet normal 0.948408 -0.312445 -0.0538523 + outer loop + vertex -847.563 281.182 227.522 + vertex -846.416 284.9 226.159 + vertex -847.42 281.109 230.463 + endloop + endfacet + facet normal 0.950604 -0.306637 -0.0482235 + outer loop + vertex -847.42 281.109 230.463 + vertex -846.416 284.9 226.159 + vertex -846.161 285.017 230.437 + endloop + endfacet + facet normal 0.950343 -0.306588 -0.0533995 + outer loop + vertex -847.42 281.109 230.463 + vertex -846.161 285.017 230.437 + vertex -847.421 280.437 234.308 + endloop + endfacet + facet normal 0.94506 -0.319284 -0.0701432 + outer loop + vertex -847.421 280.437 234.308 + vertex -846.161 285.017 230.437 + vertex -846.152 284.088 234.783 + endloop + endfacet + facet normal 0.944919 -0.31861 -0.0749402 + outer loop + vertex -847.421 280.437 234.308 + vertex -846.152 284.088 234.783 + vertex -847.415 279.519 238.292 + endloop + endfacet + facet normal 0.940644 -0.327702 -0.0883178 + outer loop + vertex -847.415 279.519 238.292 + vertex -846.152 284.088 234.783 + vertex -846.119 283.122 238.729 + endloop + endfacet + facet normal 0.939783 -0.325449 -0.104358 + outer loop + vertex -847.415 279.519 238.292 + vertex -846.119 283.122 238.729 + vertex -847.273 278.73 242.028 + endloop + endfacet + facet normal 0.942397 -0.320263 -0.0965414 + outer loop + vertex -847.273 278.73 242.028 + vertex -846.119 283.122 238.729 + vertex -846.039 282.236 242.438 + endloop + endfacet + facet normal 0.941351 -0.317983 -0.112896 + outer loop + vertex -847.273 278.73 242.028 + vertex -846.039 282.236 242.438 + vertex -847.13 277.929 245.478 + endloop + endfacet + facet normal 0.944121 -0.312647 -0.104343 + outer loop + vertex -847.13 277.929 245.478 + vertex -846.039 282.236 242.438 + vertex -845.967 281.234 246.099 + endloop + endfacet + facet normal 0.944164 -0.312851 -0.103334 + outer loop + vertex -847.13 277.929 245.478 + vertex -845.967 281.234 246.099 + vertex -847.227 276.415 249.171 + endloop + endfacet + facet normal 0.938661 -0.322826 -0.121241 + outer loop + vertex -847.227 276.415 249.171 + vertex -845.967 281.234 246.099 + vertex -845.868 280.132 249.797 + endloop + endfacet + facet normal 0.937937 -0.320776 -0.131823 + outer loop + vertex -847.227 276.415 249.171 + vertex -845.868 280.132 249.797 + vertex -847.12 275.204 252.884 + endloop + endfacet + facet normal 0.932782 -0.329049 -0.147122 + outer loop + vertex -847.12 275.204 252.884 + vertex -845.868 280.132 249.797 + vertex -845.678 279.004 253.523 + endloop + endfacet + facet normal 0.931492 -0.326241 -0.160904 + outer loop + vertex -847.12 275.204 252.884 + vertex -845.678 279.004 253.523 + vertex -846.906 273.972 256.62 + endloop + endfacet + facet normal 0.927885 -0.331449 -0.170795 + outer loop + vertex -846.906 273.972 256.62 + vertex -845.678 279.004 253.523 + vertex -845.426 277.777 257.273 + endloop + endfacet + facet normal 0.926384 -0.328613 -0.183917 + outer loop + vertex -846.906 273.972 256.62 + vertex -845.426 277.777 257.273 + vertex -846.635 272.619 260.402 + endloop + endfacet + facet normal 0.921763 -0.334712 -0.195755 + outer loop + vertex -846.635 272.619 260.402 + vertex -845.426 277.777 257.273 + vertex -845.12 276.442 260.997 + endloop + endfacet + facet normal 0.91952 -0.331397 -0.211326 + outer loop + vertex -846.635 272.619 260.402 + vertex -845.12 276.442 260.997 + vertex -846.308 271.17 264.097 + endloop + endfacet + facet normal 0.91526 -0.33646 -0.221571 + outer loop + vertex -846.308 271.17 264.097 + vertex -845.12 276.442 260.997 + vertex -844.763 275.027 264.621 + endloop + endfacet + facet normal 0.911832 -0.332463 -0.240894 + outer loop + vertex -846.308 271.17 264.097 + vertex -844.763 275.027 264.621 + vertex -845.922 269.669 267.63 + endloop + endfacet + facet normal 0.906683 -0.337878 -0.252517 + outer loop + vertex -845.922 269.669 267.63 + vertex -844.763 275.027 264.621 + vertex -844.339 273.554 268.116 + endloop + endfacet + facet normal 0.901908 -0.333133 -0.274927 + outer loop + vertex -845.922 269.669 267.63 + vertex -844.339 273.554 268.116 + vertex -845.461 268.101 271.042 + endloop + endfacet + facet normal 0.895368 -0.339137 -0.28862 + outer loop + vertex -845.461 268.101 271.042 + vertex -844.339 273.554 268.116 + vertex -843.834 272.009 271.498 + endloop + endfacet + facet normal 0.888703 -0.333304 -0.314827 + outer loop + vertex -845.461 268.101 271.042 + vertex -843.834 272.009 271.498 + vertex -844.905 266.43 274.381 + endloop + endfacet + facet normal 0.881157 -0.339322 -0.329277 + outer loop + vertex -844.905 266.43 274.381 + vertex -843.834 272.009 271.498 + vertex -843.232 270.379 274.789 + endloop + endfacet + facet normal 0.871736 -0.332138 -0.360222 + outer loop + vertex -844.905 266.43 274.381 + vertex -843.232 270.379 274.789 + vertex -844.238 264.651 277.636 + endloop + endfacet + facet normal 0.863805 -0.337592 -0.373996 + outer loop + vertex -844.238 264.651 277.636 + vertex -843.232 270.379 274.789 + vertex -842.526 268.658 277.971 + endloop + endfacet + facet normal 0.977262 -0.20825 -0.0398837 + outer loop + vertex -845.044 290.551 225.317 + vertex -843.755 297.867 218.701 + vertex -843.658 296.96 225.819 + endloop + endfacet + facet normal 0.975822 -0.212194 -0.0523869 + outer loop + vertex -845.17 287.619 235.501 + vertex -844.964 289.675 231.009 + vertex -843.824 294.314 233.441 + endloop + endfacet + facet normal 0.977576 -0.204005 -0.0522293 + outer loop + vertex -843.824 294.314 233.441 + vertex -842.186 303.933 226.531 + vertex -842.131 302.245 234.155 + endloop + endfacet + facet normal 0.978692 -0.201587 -0.0390548 + outer loop + vertex -843.755 297.867 218.701 + vertex -842.2 305.371 218.94 + vertex -843.658 296.96 225.819 + endloop + endfacet + facet normal 0.975385 -0.218094 -0.0325433 + outer loop + vertex -842.2 305.371 218.94 + vertex -840.576 313.773 211.294 + vertex -840.55 312.722 219.104 + endloop + endfacet + facet normal 0.966487 -0.254066 -0.0367836 + outer loop + vertex -840.55 312.722 219.104 + vertex -838.696 320.913 211.248 + vertex -838.651 319.947 219.1 + endloop + endfacet + facet normal 0.974697 -0.216654 -0.0550102 + outer loop + vertex -842.186 303.933 226.531 + vertex -840.495 311.467 226.829 + vertex -842.131 302.245 234.155 + endloop + endfacet + facet normal 0.977034 -0.202668 -0.0658099 + outer loop + vertex -843.824 294.314 233.441 + vertex -842.131 302.245 234.155 + vertex -843.714 292.375 241.044 + endloop + endfacet + facet normal 0.973983 -0.214806 -0.0722224 + outer loop + vertex -841.931 300.562 241.736 + vertex -840.371 310.067 234.498 + vertex -840.151 308.504 242.116 + endloop + endfacet + facet normal 0.966303 -0.245951 -0.0759398 + outer loop + vertex -840.151 308.504 242.116 + vertex -838.446 317.531 234.57 + vertex -838.233 316.014 242.193 + endloop + endfacet + facet normal 0.969605 -0.209739 -0.125996 + outer loop + vertex -841.079 296.573 256.668 + vertex -839.804 306.689 249.636 + vertex -839.293 304.623 257.006 + endloop + endfacet + facet normal 0.970265 -0.206428 -0.126389 + outer loop + vertex -842.927 288.296 256.001 + vertex -841.588 298.712 249.267 + vertex -841.079 296.573 256.668 + endloop + endfacet + facet normal 0.971134 -0.204362 -0.12302 + outer loop + vertex -843.411 290.481 248.549 + vertex -841.588 298.712 249.267 + vertex -842.927 288.296 256.001 + endloop + endfacet + facet normal 0.969149 -0.226818 -0.0964584 + outer loop + vertex -843.714 292.375 241.044 + vertex -843.411 290.481 248.549 + vertex -844.753 285.594 246.559 + endloop + endfacet + facet normal 0.96103 -0.256867 -0.102181 + outer loop + vertex -845.967 281.234 246.099 + vertex -844.753 285.594 246.559 + vertex -845.868 280.132 249.797 + endloop + endfacet +endsolid diff --git a/noether_examples/meshes/outputs/output_20.stl b/noether_examples/meshes/outputs/output_20.stl new file mode 100644 index 00000000..239d55f8 --- /dev/null +++ b/noether_examples/meshes/outputs/output_20.stl @@ -0,0 +1,6554 @@ +solid ascii + facet normal -0.294665 -0.347893 0.890024 + outer loop + vertex -711.206 148.495 39.5151 + vertex -718.284 152.551 38.757 + vertex -719.648 152.16 38.153 + endloop + endfacet + facet normal -0.285693 -0.369954 0.884033 + outer loop + vertex -718.284 152.551 38.757 + vertex -727.166 156.545 37.5583 + vertex -719.648 152.16 38.153 + endloop + endfacet + facet normal -0.232616 -0.272208 0.933698 + outer loop + vertex -719.648 152.16 38.153 + vertex -727.166 156.545 37.5583 + vertex -728.772 156.354 37.1025 + endloop + endfacet + facet normal -0.227465 -0.29898 0.926753 + outer loop + vertex -727.166 156.545 37.5583 + vertex -736.787 160.955 36.6194 + vertex -728.772 156.354 37.1025 + endloop + endfacet + facet normal -0.192575 -0.23548 0.952609 + outer loop + vertex -728.772 156.354 37.1025 + vertex -736.787 160.955 36.6194 + vertex -737.803 160.631 36.3341 + endloop + endfacet + facet normal -0.186062 -0.25308 0.949385 + outer loop + vertex -736.787 160.955 36.6194 + vertex -745.142 164.878 36.0278 + vertex -737.803 160.631 36.3341 + endloop + endfacet + facet normal -0.164472 -0.214806 0.962708 + outer loop + vertex -737.803 160.631 36.3341 + vertex -745.142 164.878 36.0278 + vertex -746.421 164.82 35.7965 + endloop + endfacet + facet normal -0.204217 -0.300553 0.931645 + outer loop + vertex -737.803 160.631 36.3341 + vertex -746.421 164.82 35.7965 + vertex -738.241 159.322 35.8157 + endloop + endfacet + facet normal -0.209322 -0.298639 0.931128 + outer loop + vertex -729.35 155.059 36.4472 + vertex -737.803 160.631 36.3341 + vertex -738.241 159.322 35.8157 + endloop + endfacet + facet normal -0.242572 -0.34961 0.904948 + outer loop + vertex -728.772 156.354 37.1025 + vertex -737.803 160.631 36.3341 + vertex -729.35 155.059 36.4472 + endloop + endfacet + facet normal -0.246998 -0.34745 0.904583 + outer loop + vertex -720.313 150.812 37.2838 + vertex -728.772 156.354 37.1025 + vertex -729.35 155.059 36.4472 + endloop + endfacet + facet normal -0.182571 -0.268303 0.945876 + outer loop + vertex -738.241 159.322 35.8157 + vertex -746.421 164.82 35.7965 + vertex -746.821 163.541 35.3564 + endloop + endfacet + facet normal -0.176713 -0.270319 0.946414 + outer loop + vertex -746.421 164.82 35.7965 + vertex -754.791 169.03 35.436 + vertex -746.821 163.541 35.3564 + endloop + endfacet + facet normal -0.165874 -0.254671 0.952696 + outer loop + vertex -746.821 163.541 35.3564 + vertex -754.791 169.03 35.436 + vertex -755.198 167.813 35.0397 + endloop + endfacet + facet normal -0.161141 -0.25637 0.953052 + outer loop + vertex -754.791 169.03 35.436 + vertex -763.085 173.41 35.2119 + vertex -755.198 167.813 35.0397 + endloop + endfacet + facet normal -0.159214 -0.253687 0.954093 + outer loop + vertex -755.198 167.813 35.0397 + vertex -763.085 173.41 35.2119 + vertex -763.487 172.277 34.8435 + endloop + endfacet + facet normal -0.158276 -0.25404 0.954155 + outer loop + vertex -763.085 173.41 35.2119 + vertex -771.332 178.096 35.0917 + vertex -763.487 172.277 34.8435 + endloop + endfacet + facet normal -0.158647 -0.254533 0.953962 + outer loop + vertex -763.487 172.277 34.8435 + vertex -771.332 178.096 35.0917 + vertex -771.637 176.963 34.7384 + endloop + endfacet + facet normal -0.162474 -0.253395 0.953621 + outer loop + vertex -771.332 178.096 35.0917 + vertex -779.333 183.006 35.0329 + vertex -771.637 176.963 34.7384 + endloop + endfacet + facet normal -0.162151 -0.252991 0.953783 + outer loop + vertex -771.637 176.963 34.7384 + vertex -779.333 183.006 35.0329 + vertex -779.563 181.827 34.6812 + endloop + endfacet + facet normal -0.167261 -0.251823 0.95321 + outer loop + vertex -779.333 183.006 35.0329 + vertex -787.004 188.046 35.0185 + vertex -779.563 181.827 34.6812 + endloop + endfacet + facet normal -0.168758 -0.253575 0.952481 + outer loop + vertex -779.563 181.827 34.6812 + vertex -787.004 188.046 35.0185 + vertex -787.283 186.896 34.6628 + endloop + endfacet + facet normal -0.171799 -0.252738 0.95216 + outer loop + vertex -787.004 188.046 35.0185 + vertex -794.522 193.36 35.0724 + vertex -787.283 186.896 34.6628 + endloop + endfacet + facet normal -0.181272 -0.263058 0.947598 + outer loop + vertex -787.283 186.896 34.6628 + vertex -794.522 193.36 35.0724 + vertex -794.813 192.188 34.6916 + endloop + endfacet + facet normal -0.180157 -0.263374 0.947722 + outer loop + vertex -794.522 193.36 35.0724 + vertex -801.73 198.837 35.2244 + vertex -794.813 192.188 34.6916 + endloop + endfacet + facet normal -0.191097 -0.274334 0.942456 + outer loop + vertex -794.813 192.188 34.6916 + vertex -801.73 198.837 35.2244 + vertex -802.093 197.681 34.8144 + endloop + endfacet + facet normal -0.183558 -0.276962 0.943185 + outer loop + vertex -801.73 198.837 35.2244 + vertex -808.567 204.388 35.524 + vertex -802.093 197.681 34.8144 + endloop + endfacet + facet normal -0.197973 -0.290146 0.936281 + outer loop + vertex -802.093 197.681 34.8144 + vertex -808.567 204.388 35.524 + vertex -809.026 203.223 35.0657 + endloop + endfacet + facet normal -0.210781 -0.305814 0.928466 + outer loop + vertex -802.093 197.681 34.8144 + vertex -809.026 203.223 35.0657 + vertex -802.618 195.39 33.9403 + endloop + endfacet + facet normal -0.218989 -0.303498 0.927326 + outer loop + vertex -795.142 189.866 33.8979 + vertex -802.093 197.681 34.8144 + vertex -802.618 195.39 33.9403 + endloop + endfacet + facet normal -0.203527 -0.290639 0.934936 + outer loop + vertex -794.813 192.188 34.6916 + vertex -802.093 197.681 34.8144 + vertex -795.142 189.866 33.8979 + endloop + endfacet + facet normal -0.204289 -0.29049 0.934816 + outer loop + vertex -787.419 184.519 33.9243 + vertex -794.813 192.188 34.6916 + vertex -795.142 189.866 33.8979 + endloop + endfacet + facet normal -0.193904 -0.280989 0.939918 + outer loop + vertex -787.283 186.896 34.6628 + vertex -794.813 192.188 34.6916 + vertex -787.419 184.519 33.9243 + endloop + endfacet + facet normal -0.189782 -0.281444 0.940623 + outer loop + vertex -779.586 179.406 33.9747 + vertex -787.283 186.896 34.6628 + vertex -787.419 184.519 33.9243 + endloop + endfacet + facet normal -0.182043 -0.273838 0.94439 + outer loop + vertex -779.563 181.827 34.6812 + vertex -787.283 186.896 34.6628 + vertex -779.586 179.406 33.9747 + endloop + endfacet + facet normal -0.174956 -0.274259 0.945607 + outer loop + vertex -771.643 174.534 34.0313 + vertex -779.563 181.827 34.6812 + vertex -779.586 179.406 33.9747 + endloop + endfacet + facet normal -0.175475 -0.2748 0.945354 + outer loop + vertex -771.637 176.963 34.7384 + vertex -779.563 181.827 34.6812 + vertex -771.643 174.534 34.0313 + endloop + endfacet + facet normal -0.168544 -0.275152 0.946512 + outer loop + vertex -763.532 169.869 34.1196 + vertex -771.637 176.963 34.7384 + vertex -771.643 174.534 34.0313 + endloop + endfacet + facet normal -0.173511 -0.28061 0.944008 + outer loop + vertex -763.487 172.277 34.8435 + vertex -771.637 176.963 34.7384 + vertex -763.532 169.869 34.1196 + endloop + endfacet + facet normal -0.169815 -0.280859 0.944606 + outer loop + vertex -755.26 165.379 34.2715 + vertex -763.487 172.277 34.8435 + vertex -763.532 169.869 34.1196 + endloop + endfacet + facet normal -0.17948 -0.291958 0.93944 + outer loop + vertex -755.198 167.813 35.0397 + vertex -763.487 172.277 34.8435 + vertex -755.26 165.379 34.2715 + endloop + endfacet + facet normal -0.17881 -0.29201 0.939552 + outer loop + vertex -746.89 161.076 34.5271 + vertex -755.198 167.813 35.0397 + vertex -755.26 165.379 34.2715 + endloop + endfacet + facet normal -0.192301 -0.308054 0.931731 + outer loop + vertex -746.821 163.541 35.3564 + vertex -755.198 167.813 35.0397 + vertex -746.89 161.076 34.5271 + endloop + endfacet + facet normal -0.191729 -0.308104 0.931833 + outer loop + vertex -738.385 156.879 34.8894 + vertex -746.821 163.541 35.3564 + vertex -746.89 161.076 34.5271 + endloop + endfacet + facet normal -0.213994 -0.335292 0.917489 + outer loop + vertex -738.241 159.322 35.8157 + vertex -746.821 163.541 35.3564 + vertex -738.385 156.879 34.8894 + endloop + endfacet + facet normal -0.21147 -0.335617 0.917955 + outer loop + vertex -729.64 152.677 35.3678 + vertex -738.241 159.322 35.8157 + vertex -738.385 156.879 34.8894 + endloop + endfacet + facet normal -0.243603 -0.375609 0.89419 + outer loop + vertex -729.35 155.059 36.4472 + vertex -738.241 159.322 35.8157 + vertex -729.64 152.677 35.3678 + endloop + endfacet + facet normal -0.238841 -0.376586 0.895063 + outer loop + vertex -720.779 148.506 35.9773 + vertex -729.35 155.059 36.4472 + vertex -729.64 152.677 35.3678 + endloop + endfacet + facet normal -0.235407 -0.324199 0.916231 + outer loop + vertex -802.618 195.39 33.9403 + vertex -809.026 203.223 35.0657 + vertex -809.672 200.966 34.1013 + endloop + endfacet + facet normal -0.215223 -0.331049 0.918741 + outer loop + vertex -809.026 203.223 35.0657 + vertex -815.64 208.786 35.5209 + vertex -809.672 200.966 34.1013 + endloop + endfacet + facet normal -0.249477 -0.354034 0.901344 + outer loop + vertex -809.672 200.966 34.1013 + vertex -815.64 208.786 35.5209 + vertex -816.348 206.527 34.4375 + endloop + endfacet + facet normal -0.215573 -0.36648 0.905108 + outer loop + vertex -815.64 208.786 35.5209 + vertex -822.116 214.486 36.2863 + vertex -816.348 206.527 34.4375 + endloop + endfacet + facet normal -0.189461 -0.339014 0.921506 + outer loop + vertex -815.64 208.786 35.5209 + vertex -821.44 215.63 36.8463 + vertex -822.116 214.486 36.2863 + endloop + endfacet + facet normal -0.195427 -0.308511 0.930929 + outer loop + vertex -809.026 203.223 35.0657 + vertex -815.081 209.956 36.026 + vertex -815.64 208.786 35.5209 + endloop + endfacet + facet normal -0.16736 -0.322266 0.931738 + outer loop + vertex -815.081 209.956 36.026 + vertex -821.44 215.63 36.8463 + vertex -815.64 208.786 35.5209 + endloop + endfacet + facet normal -0.0901325 -0.240727 0.966399 + outer loop + vertex -815.081 209.956 36.026 + vertex -820.229 215.321 36.8824 + vertex -821.44 215.63 36.8463 + endloop + endfacet + facet normal -0.10614 -0.305909 0.946126 + outer loop + vertex -820.229 215.321 36.8824 + vertex -826.649 221.402 38.1281 + vertex -821.44 215.63 36.8463 + endloop + endfacet + facet normal -0.15323 -0.297429 0.942368 + outer loop + vertex -814.261 209.925 36.1496 + vertex -820.229 215.321 36.8824 + vertex -815.081 209.956 36.026 + endloop + endfacet + facet normal -0.153452 -0.265365 0.951858 + outer loop + vertex -808.567 204.388 35.524 + vertex -814.261 209.925 36.1496 + vertex -815.081 209.956 36.026 + endloop + endfacet + facet normal -0.181051 -0.292297 0.939033 + outer loop + vertex -807.575 204.192 35.6543 + vertex -814.261 209.925 36.1496 + vertex -808.567 204.388 35.524 + endloop + endfacet + facet normal -0.181633 -0.297034 0.937433 + outer loop + vertex -808.567 204.388 35.524 + vertex -815.081 209.956 36.026 + vertex -809.026 203.223 35.0657 + endloop + endfacet + facet normal -0.177571 -0.269763 0.946413 + outer loop + vertex -801.73 198.837 35.2244 + vertex -807.575 204.192 35.6543 + vertex -808.567 204.388 35.524 + endloop + endfacet + facet normal -0.188848 -0.281616 0.94076 + outer loop + vertex -801.041 198.921 35.3879 + vertex -807.575 204.192 35.6543 + vertex -801.73 198.837 35.2244 + endloop + endfacet + facet normal -0.189875 -0.276011 0.942213 + outer loop + vertex -794.522 193.36 35.0724 + vertex -801.041 198.921 35.3879 + vertex -801.73 198.837 35.2244 + endloop + endfacet + facet normal -0.195982 -0.28298 0.938889 + outer loop + vertex -793.442 193.169 35.2405 + vertex -801.041 198.921 35.3879 + vertex -794.522 193.36 35.0724 + endloop + endfacet + facet normal -0.196565 -0.287627 0.937354 + outer loop + vertex -787.004 188.046 35.0185 + vertex -793.442 193.169 35.2405 + vertex -794.522 193.36 35.0724 + endloop + endfacet + facet normal -0.197162 -0.288363 0.937003 + outer loop + vertex -785.956 187.878 35.1872 + vertex -793.442 193.169 35.2405 + vertex -787.004 188.046 35.0185 + endloop + endfacet + facet normal -0.152361 -0.225234 0.962318 + outer loop + vertex -793.442 193.169 35.2405 + vertex -785.956 187.878 35.1872 + vertex -789.872 191.171 35.3379 + endloop + endfacet + facet normal -0.13332 -0.190726 0.972548 + outer loop + vertex -789.872 191.171 35.3379 + vertex -793.662 194.413 35.4542 + vertex -793.442 193.169 35.2405 + endloop + endfacet + facet normal -0.126475 -0.189704 0.973661 + outer loop + vertex -793.662 194.413 35.4542 + vertex -798.399 197.78 35.4949 + vertex -793.442 193.169 35.2405 + endloop + endfacet + facet normal -0.0833879 -0.129264 0.988098 + outer loop + vertex -798.399 197.78 35.4949 + vertex -793.662 194.413 35.4542 + vertex -795.025 198.342 35.8532 + endloop + endfacet + facet normal -0.0816481 -0.138959 0.986927 + outer loop + vertex -795.025 198.342 35.8532 + vertex -801.526 202.883 35.9548 + vertex -798.399 197.78 35.4949 + endloop + endfacet + facet normal -0.0850551 -0.140994 0.98635 + outer loop + vertex -802.286 200.6 35.5629 + vertex -798.399 197.78 35.4949 + vertex -801.526 202.883 35.9548 + endloop + endfacet + facet normal -0.0740291 -0.144725 0.986699 + outer loop + vertex -805.846 203.709 35.7517 + vertex -802.286 200.6 35.5629 + vertex -801.526 202.883 35.9548 + endloop + endfacet + facet normal -0.0760255 -0.155622 0.984887 + outer loop + vertex -801.526 202.883 35.9548 + vertex -808.186 208.544 36.3351 + vertex -805.846 203.709 35.7517 + endloop + endfacet + facet normal -0.122493 -0.192284 0.973664 + outer loop + vertex -798.399 197.78 35.4949 + vertex -802.286 200.6 35.5629 + vertex -801.041 198.921 35.3879 + endloop + endfacet + facet normal -0.0849421 -0.129783 0.987897 + outer loop + vertex -788.675 193.339 35.7419 + vertex -795.025 198.342 35.8532 + vertex -793.662 194.413 35.4542 + endloop + endfacet + facet normal -0.0862799 -0.136258 0.986909 + outer loop + vertex -793.662 194.413 35.4542 + vertex -789.872 191.171 35.3379 + vertex -788.675 193.339 35.7419 + endloop + endfacet + facet normal -0.0928231 -0.132625 0.98681 + outer loop + vertex -789.872 191.171 35.3379 + vertex -784.695 187.975 35.3954 + vertex -788.675 193.339 35.7419 + endloop + endfacet + facet normal -0.0881489 -0.129213 0.987691 + outer loop + vertex -781.85 189.203 35.8099 + vertex -788.675 193.339 35.7419 + vertex -784.695 187.975 35.3954 + endloop + endfacet + facet normal -0.0892721 -0.126687 0.987917 + outer loop + vertex -784.695 187.975 35.3954 + vertex -779.679 185.004 35.4676 + vertex -781.85 189.203 35.8099 + endloop + endfacet + facet normal -0.0798331 -0.121921 0.989324 + outer loop + vertex -775.78 185.417 35.8332 + vertex -781.85 189.203 35.8099 + vertex -779.679 185.004 35.4676 + endloop + endfacet + facet normal -0.0793361 -0.126175 0.98883 + outer loop + vertex -779.679 185.004 35.4676 + vertex -774.627 181.535 35.4303 + vertex -775.78 185.417 35.8332 + endloop + endfacet + facet normal -0.0815785 -0.126814 0.988566 + outer loop + vertex -769.381 181.14 35.8126 + vertex -775.78 185.417 35.8332 + vertex -774.627 181.535 35.4303 + endloop + endfacet + facet normal -0.0817133 -0.128873 0.988289 + outer loop + vertex -774.627 181.535 35.4303 + vertex -770.662 178.981 35.4251 + vertex -769.381 181.14 35.8126 + endloop + endfacet + facet normal -0.0830919 -0.128054 0.98828 + outer loop + vertex -770.662 178.981 35.4251 + vertex -766.118 176.701 35.5118 + vertex -769.381 181.14 35.8126 + endloop + endfacet + facet normal -0.0875927 -0.131308 0.987464 + outer loop + vertex -761.951 177.592 35.9999 + vertex -769.381 181.14 35.8126 + vertex -766.118 176.701 35.5118 + endloop + endfacet + facet normal -0.0882267 -0.128515 0.987775 + outer loop + vertex -766.118 176.701 35.5118 + vertex -759.25 173.194 35.669 + vertex -761.951 177.592 35.9999 + endloop + endfacet + facet normal -0.0984795 -0.134677 0.985984 + outer loop + vertex -755.003 173.822 36.1789 + vertex -761.951 177.592 35.9999 + vertex -759.25 173.194 35.669 + endloop + endfacet + facet normal -0.0984487 -0.134867 0.985961 + outer loop + vertex -759.25 173.194 35.669 + vertex -753.716 170.282 35.8232 + vertex -755.003 173.822 36.1789 + endloop + endfacet + facet normal -0.114149 -0.140329 0.983503 + outer loop + vertex -748.384 169.23 36.2919 + vertex -755.003 173.822 36.1789 + vertex -753.716 170.282 35.8232 + endloop + endfacet + facet normal -0.117299 -0.15763 0.980507 + outer loop + vertex -753.716 170.282 35.8232 + vertex -749.458 167.592 35.9001 + vertex -748.384 169.23 36.2919 + endloop + endfacet + facet normal -0.127441 -0.150932 0.980295 + outer loop + vertex -749.458 167.592 35.9001 + vertex -743.865 164.975 36.2243 + vertex -748.384 169.23 36.2919 + endloop + endfacet + facet normal -0.121709 -0.164657 0.978813 + outer loop + vertex -749.458 167.592 35.9001 + vertex -753.716 170.282 35.8232 + vertex -753.484 169.125 35.6574 + endloop + endfacet + facet normal -0.113154 -0.163127 0.980095 + outer loop + vertex -753.716 170.282 35.8232 + vertex -759.25 173.194 35.669 + vertex -753.484 169.125 35.6574 + endloop + endfacet + facet normal -0.112461 -0.162145 0.980337 + outer loop + vertex -761.654 173.316 35.4132 + vertex -753.484 169.125 35.6574 + vertex -759.25 173.194 35.669 + endloop + endfacet + facet normal -0.112944 -0.177377 0.97764 + outer loop + vertex -759.25 173.194 35.669 + vertex -766.118 176.701 35.5118 + vertex -761.654 173.316 35.4132 + endloop + endfacet + facet normal -0.11164 -0.175671 0.978098 + outer loop + vertex -769.988 177.897 35.2848 + vertex -761.654 173.316 35.4132 + vertex -766.118 176.701 35.5118 + endloop + endfacet + facet normal -0.150977 -0.247826 0.956968 + outer loop + vertex -761.654 173.316 35.4132 + vertex -769.988 177.897 35.2848 + vertex -763.085 173.41 35.2119 + endloop + endfacet + facet normal -0.118756 -0.199738 0.972626 + outer loop + vertex -766.118 176.701 35.5118 + vertex -770.662 178.981 35.4251 + vertex -769.988 177.897 35.2848 + endloop + endfacet + facet normal -0.132667 -0.207932 0.969105 + outer loop + vertex -770.662 178.981 35.4251 + vertex -774.627 181.535 35.4303 + vertex -769.988 177.897 35.2848 + endloop + endfacet + facet normal -0.132494 -0.207714 0.969175 + outer loop + vertex -778.471 183.076 35.2351 + vertex -769.988 177.897 35.2848 + vertex -774.627 181.535 35.4303 + endloop + endfacet + facet normal -0.177345 -0.28143 0.943051 + outer loop + vertex -769.988 177.897 35.2848 + vertex -778.471 183.076 35.2351 + vertex -771.332 178.096 35.0917 + endloop + endfacet + facet normal -0.128663 -0.19783 0.971756 + outer loop + vertex -774.627 181.535 35.4303 + vertex -779.679 185.004 35.4676 + vertex -778.471 183.076 35.2351 + endloop + endfacet + facet normal -0.0628424 -0.0946535 0.993525 + outer loop + vertex -775.78 185.417 35.8332 + vertex -776.221 191.948 36.4276 + vertex -781.85 189.203 35.8099 + endloop + endfacet + facet normal -0.0631366 -0.0940587 0.993563 + outer loop + vertex -781.85 189.203 35.8099 + vertex -776.221 191.948 36.4276 + vertex -782.735 196.017 36.3988 + endloop + endfacet + facet normal -0.0634602 -0.0946913 0.993482 + outer loop + vertex -775.78 185.417 35.8332 + vertex -769.704 188.041 36.4714 + vertex -776.221 191.948 36.4276 + endloop + endfacet + facet normal -0.0621251 -0.0977317 0.993272 + outer loop + vertex -769.381 181.14 35.8126 + vertex -769.704 188.041 36.4714 + vertex -775.78 185.417 35.8332 + endloop + endfacet + facet normal -0.0703195 -0.0980596 0.992693 + outer loop + vertex -769.381 181.14 35.8126 + vertex -762.817 184.335 36.5932 + vertex -769.704 188.041 36.4714 + endloop + endfacet + facet normal -0.0710988 -0.0964826 0.992792 + outer loop + vertex -761.951 177.592 35.9999 + vertex -762.817 184.335 36.5932 + vertex -769.381 181.14 35.8126 + endloop + endfacet + facet normal -0.0817496 -0.0977668 0.991846 + outer loop + vertex -761.951 177.592 35.9999 + vertex -755.621 180.526 36.8108 + vertex -762.817 184.335 36.5932 + endloop + endfacet + facet normal -0.0802837 -0.100877 0.991654 + outer loop + vertex -755.003 173.822 36.1789 + vertex -755.621 180.526 36.8108 + vertex -761.951 177.592 35.9999 + endloop + endfacet + facet normal -0.100906 -0.102586 0.989593 + outer loop + vertex -755.003 173.822 36.1789 + vertex -748.041 175.784 37.0921 + vertex -755.621 180.526 36.8108 + endloop + endfacet + facet normal -0.0970937 -0.11562 0.988537 + outer loop + vertex -748.384 169.23 36.2919 + vertex -748.041 175.784 37.0921 + vertex -755.003 173.822 36.1789 + endloop + endfacet + facet normal -0.129137 -0.113526 0.985107 + outer loop + vertex -748.041 175.784 37.0921 + vertex -748.384 169.23 36.2919 + vertex -743.445 170.023 37.0307 + endloop + endfacet + facet normal -0.122647 -0.108363 0.986517 + outer loop + vertex -742.981 174.16 37.5428 + vertex -748.041 175.784 37.0921 + vertex -743.445 170.023 37.0307 + endloop + endfacet + facet normal -0.132417 -0.107127 0.985388 + outer loop + vertex -743.445 170.023 37.0307 + vertex -739.174 172.528 37.877 + vertex -742.981 174.16 37.5428 + endloop + endfacet + facet normal -0.127102 -0.116082 0.985074 + outer loop + vertex -739.007 167.043 37.2522 + vertex -739.174 172.528 37.877 + vertex -743.445 170.023 37.0307 + endloop + endfacet + facet normal -0.144395 -0.142271 0.979239 + outer loop + vertex -742.139 165.742 36.6014 + vertex -739.007 167.043 37.2522 + vertex -743.445 170.023 37.0307 + endloop + endfacet + facet normal -0.141556 -0.148827 0.978679 + outer loop + vertex -738.088 163.862 36.9015 + vertex -739.007 167.043 37.2522 + vertex -742.139 165.742 36.6014 + endloop + endfacet + facet normal -0.151982 -0.172155 0.973275 + outer loop + vertex -738.088 163.862 36.9015 + vertex -742.139 165.742 36.6014 + vertex -738.456 162.589 36.6188 + endloop + endfacet + facet normal -0.158911 -0.169991 0.972548 + outer loop + vertex -734.74 162.015 37.1256 + vertex -738.088 163.862 36.9015 + vertex -738.456 162.589 36.6188 + endloop + endfacet + facet normal -0.158524 -0.166968 0.973135 + outer loop + vertex -738.456 162.589 36.6188 + vertex -733.056 159.846 37.0278 + vertex -734.74 162.015 37.1256 + endloop + endfacet + facet normal -0.154417 -0.161586 0.974703 + outer loop + vertex -734.74 162.015 37.1256 + vertex -735.209 165.041 37.5529 + vertex -738.088 163.862 36.9015 + endloop + endfacet + facet normal -0.178396 -0.16465 0.970085 + outer loop + vertex -734.74 162.015 37.1256 + vertex -731.576 163.355 37.9348 + vertex -735.209 165.041 37.5529 + endloop + endfacet + facet normal -0.166081 -0.136641 0.976599 + outer loop + vertex -731.576 163.355 37.9348 + vertex -732.001 168.376 38.5651 + vertex -735.209 165.041 37.5529 + endloop + endfacet + facet normal -0.172586 -0.130306 0.976337 + outer loop + vertex -735.209 165.041 37.5529 + vertex -732.001 168.376 38.5651 + vertex -735.641 169.372 38.0545 + endloop + endfacet + facet normal -0.145219 -0.12812 0.981069 + outer loop + vertex -735.209 165.041 37.5529 + vertex -735.641 169.372 38.0545 + vertex -739.007 167.043 37.2522 + endloop + endfacet + facet normal -0.209511 -0.139219 0.967845 + outer loop + vertex -731.576 163.355 37.9348 + vertex -728.284 166.187 39.0549 + vertex -732.001 168.376 38.5651 + endloop + endfacet + facet normal -0.196383 -0.115618 0.973687 + outer loop + vertex -728.284 166.187 39.0549 + vertex -728.584 172.495 39.7434 + vertex -732.001 168.376 38.5651 + endloop + endfacet + facet normal -0.214595 -0.0999008 0.971581 + outer loop + vertex -732.001 168.376 38.5651 + vertex -728.584 172.495 39.7434 + vertex -733.071 177.234 39.2396 + endloop + endfacet + facet normal -0.196586 -0.0822715 0.977029 + outer loop + vertex -728.347 178.297 40.2795 + vertex -733.071 177.234 39.2396 + vertex -728.584 172.495 39.7434 + endloop + endfacet + facet normal -0.225185 -0.0805488 0.970981 + outer loop + vertex -728.584 172.495 39.7434 + vertex -725.39 177.415 40.8923 + vertex -728.347 178.297 40.2795 + endloop + endfacet + facet normal -0.217593 -0.0525355 0.974625 + outer loop + vertex -728.347 178.297 40.2795 + vertex -725.39 177.415 40.8923 + vertex -726.628 187.356 41.1517 + endloop + endfacet + facet normal -0.215803 -0.0870049 0.972553 + outer loop + vertex -724.985 170.171 40.3341 + vertex -725.39 177.415 40.8923 + vertex -728.584 172.495 39.7434 + endloop + endfacet + facet normal -0.262909 -0.0887266 0.960732 + outer loop + vertex -724.985 170.171 40.3341 + vertex -721.896 175.132 41.6374 + vertex -725.39 177.415 40.8923 + endloop + endfacet + facet normal -0.248753 -0.0652314 0.966368 + outer loop + vertex -721.896 175.132 41.6374 + vertex -722.389 183.097 42.0482 + vertex -725.39 177.415 40.8923 + endloop + endfacet + facet normal -0.261781 -0.0577465 0.963398 + outer loop + vertex -725.39 177.415 40.8923 + vertex -722.389 183.097 42.0482 + vertex -726.628 187.356 41.1517 + endloop + endfacet + facet normal -0.248102 -0.0432122 0.96777 + outer loop + vertex -722.304 189.766 42.3678 + vertex -726.628 187.356 41.1517 + vertex -722.389 183.097 42.0482 + endloop + endfacet + facet normal -0.25312 -0.0337479 0.966846 + outer loop + vertex -722.304 189.766 42.3678 + vertex -720.863 199.625 43.0892 + vertex -726.628 187.356 41.1517 + endloop + endfacet + facet normal -0.267065 -0.0266376 0.96331 + outer loop + vertex -726.628 187.356 41.1517 + vertex -720.863 199.625 43.0892 + vertex -727.063 203.134 41.4675 + endloop + endfacet + facet normal -0.25642 -0.00633111 0.966545 + outer loop + vertex -720.863 199.625 43.0892 + vertex -720.74 215.769 43.2277 + vertex -727.063 203.134 41.4675 + endloop + endfacet + facet normal -0.265961 -0.0011992 0.963983 + outer loop + vertex -727.063 203.134 41.4675 + vertex -720.74 215.769 43.2277 + vertex -726.726 218.122 41.5791 + endloop + endfacet + facet normal -0.261938 0.00977402 0.965035 + outer loop + vertex -720.74 215.769 43.2277 + vertex -720.182 230.536 43.2296 + vertex -726.726 218.122 41.5791 + endloop + endfacet + facet normal -0.269955 0.0143024 0.962767 + outer loop + vertex -726.726 218.122 41.5791 + vertex -720.182 230.536 43.2296 + vertex -725.943 232.377 41.5869 + endloop + endfacet + facet normal -0.269454 0.0159737 0.962881 + outer loop + vertex -720.182 230.536 43.2296 + vertex -719.411 244.726 43.2098 + vertex -725.943 232.377 41.5869 + endloop + endfacet + facet normal -0.275298 0.0192902 0.961165 + outer loop + vertex -725.943 232.377 41.5869 + vertex -719.411 244.726 43.2098 + vertex -724.997 246.375 41.5768 + endloop + endfacet + facet normal -0.276321 0.0156001 0.960939 + outer loop + vertex -719.411 244.726 43.2098 + vertex -718.628 258.837 43.206 + vertex -724.997 246.375 41.5768 + endloop + endfacet + facet normal -0.284118 0.0198932 0.958583 + outer loop + vertex -724.997 246.375 41.5768 + vertex -718.628 258.837 43.206 + vertex -724.044 260.399 41.5682 + endloop + endfacet + facet normal -0.285383 0.0152052 0.958293 + outer loop + vertex -718.628 258.837 43.206 + vertex -717.889 272.987 43.2015 + vertex -724.044 260.399 41.5682 + endloop + endfacet + facet normal -0.292314 0.0188743 0.956136 + outer loop + vertex -724.044 260.399 41.5682 + vertex -717.889 272.987 43.2015 + vertex -723.124 274.449 41.5722 + endloop + endfacet + facet normal -0.293482 0.0143818 0.955856 + outer loop + vertex -717.889 272.987 43.2015 + vertex -717.197 287.127 43.2013 + vertex -723.124 274.449 41.5722 + endloop + endfacet + facet normal -0.304475 0.019977 0.952311 + outer loop + vertex -723.124 274.449 41.5722 + vertex -717.197 287.127 43.2013 + vertex -722.206 288.421 41.5726 + endloop + endfacet + facet normal -0.305663 0.0150142 0.952021 + outer loop + vertex -717.197 287.127 43.2013 + vertex -716.514 301.2 43.1985 + vertex -722.206 288.421 41.5726 + endloop + endfacet + facet normal -0.318551 0.0213086 0.947666 + outer loop + vertex -722.206 288.421 41.5726 + vertex -716.514 301.2 43.1985 + vertex -721.283 302.305 41.5705 + endloop + endfacet + facet normal -0.319731 0.0157901 0.947377 + outer loop + vertex -716.514 301.2 43.1985 + vertex -715.828 315.238 43.196 + vertex -721.283 302.305 41.5705 + endloop + endfacet + facet normal -0.335488 0.0231424 0.94176 + outer loop + vertex -721.283 302.305 41.5705 + vertex -715.828 315.238 43.196 + vertex -720.352 316.151 41.5622 + endloop + endfacet + facet normal -0.336777 0.0161917 0.941445 + outer loop + vertex -715.828 315.238 43.196 + vertex -715.142 329.289 43.1999 + vertex -720.352 316.151 41.5622 + endloop + endfacet + facet normal -0.355235 0.0243814 0.934459 + outer loop + vertex -720.352 316.151 41.5622 + vertex -715.142 329.289 43.1999 + vertex -719.421 330.015 41.5544 + endloop + endfacet + facet normal -0.356218 0.0180615 0.934228 + outer loop + vertex -715.142 329.289 43.1999 + vertex -714.439 343.373 43.1955 + vertex -719.421 330.015 41.5544 + endloop + endfacet + facet normal -0.375801 0.0263353 0.926326 + outer loop + vertex -719.421 330.015 41.5544 + vertex -714.439 343.373 43.1955 + vertex -718.487 343.922 41.5378 + endloop + endfacet + facet normal -0.377024 0.0164976 0.926056 + outer loop + vertex -714.439 343.373 43.1955 + vertex -713.79 357.556 43.2071 + vertex -718.487 343.922 41.5378 + endloop + endfacet + facet normal -0.404237 0.027318 0.914246 + outer loop + vertex -718.487 343.922 41.5378 + vertex -713.79 357.556 43.2071 + vertex -717.584 357.91 41.5189 + endloop + endfacet + facet normal -0.40546 0.0131049 0.914019 + outer loop + vertex -713.79 357.556 43.2071 + vertex -713.353 371.906 43.1954 + vertex -717.584 357.91 41.5189 + endloop + endfacet + facet normal -0.424325 0.0198541 0.905292 + outer loop + vertex -717.584 357.91 41.5189 + vertex -713.353 371.906 43.1954 + vertex -716.886 372.068 41.5358 + endloop + endfacet + facet normal -0.425157 -4.48969e-06 0.905119 + outer loop + vertex -713.353 371.906 43.1954 + vertex -713.445 386.552 43.1523 + vertex -716.886 372.068 41.5358 + endloop + endfacet + facet normal -0.430829 0.00164296 0.902432 + outer loop + vertex -716.886 372.068 41.5358 + vertex -713.445 386.552 43.1523 + vertex -716.638 386.503 41.6277 + endloop + endfacet + facet normal -0.292995 -0.0673186 0.953741 + outer loop + vertex -721.896 175.132 41.6374 + vertex -719.044 180.924 42.9226 + vertex -722.389 183.097 42.0482 + endloop + endfacet + facet normal -0.281793 -0.0482535 0.958261 + outer loop + vertex -719.044 180.924 42.9226 + vertex -719.316 189.541 43.2764 + vertex -722.389 183.097 42.0482 + endloop + endfacet + facet normal -0.293563 -0.0420219 0.955016 + outer loop + vertex -722.389 183.097 42.0482 + vertex -719.316 189.541 43.2764 + vertex -722.304 189.766 42.3678 + endloop + endfacet + facet normal -0.292688 -0.0271576 0.955822 + outer loop + vertex -722.304 189.766 42.3678 + vertex -719.316 189.541 43.2764 + vertex -720.863 199.625 43.0892 + endloop + endfacet + facet normal -0.342692 -0.0351462 0.93879 + outer loop + vertex -714.932 198.056 45.1955 + vertex -720.863 199.625 43.0892 + vertex -719.316 189.541 43.2764 + endloop + endfacet + facet normal -0.329112 -0.0431553 0.943304 + outer loop + vertex -716.482 186.813 44.1404 + vertex -714.932 198.056 45.1955 + vertex -719.316 189.541 43.2764 + endloop + endfacet + facet normal -0.334296 -0.0492123 0.941182 + outer loop + vertex -719.044 180.924 42.9226 + vertex -716.482 186.813 44.1404 + vertex -719.316 189.541 43.2764 + endloop + endfacet + facet normal -0.325078 -0.0538358 0.944154 + outer loop + vertex -715.96 179.548 43.9059 + vertex -716.482 186.813 44.1404 + vertex -719.044 180.924 42.9226 + endloop + endfacet + facet normal -0.333831 -0.0767813 0.939501 + outer loop + vertex -718.635 173.438 42.4562 + vertex -715.96 179.548 43.9059 + vertex -719.044 180.924 42.9226 + endloop + endfacet + facet normal -0.31934 -0.084169 0.943895 + outer loop + vertex -715.581 172.284 43.3862 + vertex -715.96 179.548 43.9059 + vertex -718.635 173.438 42.4562 + endloop + endfacet + facet normal -0.329068 -0.115265 0.937245 + outer loop + vertex -718.396 166.984 41.7464 + vertex -715.581 172.284 43.3862 + vertex -718.635 173.438 42.4562 + endloop + endfacet + facet normal -0.309323 -0.12734 0.942392 + outer loop + vertex -715.307 165.961 42.622 + vertex -715.581 172.284 43.3862 + vertex -718.396 166.984 41.7464 + endloop + endfacet + facet normal -0.318324 -0.161609 0.934105 + outer loop + vertex -718.262 161.727 40.8824 + vertex -715.307 165.961 42.622 + vertex -718.396 166.984 41.7464 + endloop + endfacet + facet normal -0.299895 -0.175911 0.937613 + outer loop + vertex -714.988 160.582 41.715 + vertex -715.307 165.961 42.622 + vertex -718.262 161.727 40.8824 + endloop + endfacet + facet normal -0.308014 -0.205455 0.928933 + outer loop + vertex -717.874 157.581 40.0939 + vertex -714.988 160.582 41.715 + vertex -718.262 161.727 40.8824 + endloop + endfacet + facet normal -0.262362 -0.203901 0.943181 + outer loop + vertex -717.874 157.581 40.0939 + vertex -718.262 161.727 40.8824 + vertex -721.364 158.857 39.3992 + endloop + endfacet + facet normal -0.268024 -0.222558 0.937353 + outer loop + vertex -720.33 155.858 38.9828 + vertex -717.874 157.581 40.0939 + vertex -721.364 158.857 39.3992 + endloop + endfacet + facet normal -0.23849 -0.213761 0.947327 + outer loop + vertex -720.33 155.858 38.9828 + vertex -721.364 158.857 39.3992 + vertex -724.446 157.553 38.329 + endloop + endfacet + facet normal -0.235819 -0.206385 0.949629 + outer loop + vertex -720.33 155.858 38.9828 + vertex -724.446 157.553 38.329 + vertex -722.89 155.416 38.2507 + endloop + endfacet + facet normal -0.238177 -0.195561 0.951329 + outer loop + vertex -722.89 155.416 38.2507 + vertex -716.679 152.924 39.2936 + vertex -720.33 155.858 38.9828 + endloop + endfacet + facet normal -0.26547 -0.231138 0.936003 + outer loop + vertex -716.843 154.768 39.7023 + vertex -720.33 155.858 38.9828 + vertex -716.679 152.924 39.2936 + endloop + endfacet + facet normal -0.286169 -0.2316 0.929768 + outer loop + vertex -713.57 152.963 40.2601 + vertex -716.843 154.768 39.7023 + vertex -716.679 152.924 39.2936 + endloop + endfacet + facet normal -0.294806 -0.249539 0.922399 + outer loop + vertex -713.57 152.963 40.2601 + vertex -714.4 156.196 40.8696 + vertex -716.843 154.768 39.7023 + endloop + endfacet + facet normal -0.301339 -0.23893 0.923097 + outer loop + vertex -716.843 154.768 39.7023 + vertex -714.4 156.196 40.8696 + vertex -717.874 157.581 40.0939 + endloop + endfacet + facet normal -0.241669 -0.206842 0.948057 + outer loop + vertex -724.446 157.553 38.329 + vertex -721.364 158.857 39.3992 + vertex -724.742 160.265 38.8452 + endloop + endfacet + facet normal -0.2194 -0.205496 0.953748 + outer loop + vertex -724.446 157.553 38.329 + vertex -724.742 160.265 38.8452 + vertex -727.462 159.124 37.9737 + endloop + endfacet + facet normal -0.211869 -0.189926 0.958666 + outer loop + vertex -724.446 157.553 38.329 + vertex -727.462 159.124 37.9737 + vertex -728.023 157.895 37.6062 + endloop + endfacet + facet normal -0.211834 -0.189265 0.958804 + outer loop + vertex -728.023 157.895 37.6062 + vertex -722.89 155.416 38.2507 + vertex -724.446 157.553 38.329 + endloop + endfacet + facet normal -0.199008 -0.196245 0.960148 + outer loop + vertex -727.462 159.124 37.9737 + vertex -730.753 160.24 37.5197 + vertex -728.023 157.895 37.6062 + endloop + endfacet + facet normal -0.177706 -0.171115 0.969093 + outer loop + vertex -733.056 159.846 37.0278 + vertex -728.023 157.895 37.6062 + vertex -730.753 160.24 37.5197 + endloop + endfacet + facet normal -0.175874 -0.180195 0.96778 + outer loop + vertex -730.753 160.24 37.5197 + vertex -734.74 162.015 37.1256 + vertex -733.056 159.846 37.0278 + endloop + endfacet + facet normal -0.197844 -0.192398 0.961166 + outer loop + vertex -727.462 159.124 37.9737 + vertex -728.045 161.722 38.3737 + vertex -730.753 160.24 37.5197 + endloop + endfacet + facet normal -0.203747 -0.182063 0.961946 + outer loop + vertex -730.753 160.24 37.5197 + vertex -728.045 161.722 38.3737 + vertex -731.576 163.355 37.9348 + endloop + endfacet + facet normal -0.223213 -0.197087 0.954637 + outer loop + vertex -727.462 159.124 37.9737 + vertex -724.742 160.265 38.8452 + vertex -728.045 161.722 38.3737 + endloop + endfacet + facet normal -0.214918 -0.176365 0.960576 + outer loop + vertex -724.742 160.265 38.8452 + vertex -724.823 164.412 39.5883 + vertex -728.045 161.722 38.3737 + endloop + endfacet + facet normal -0.229488 -0.158777 0.960273 + outer loop + vertex -728.045 161.722 38.3737 + vertex -724.823 164.412 39.5883 + vertex -728.284 166.187 39.0549 + endloop + endfacet + facet normal -0.216505 -0.131335 0.967407 + outer loop + vertex -724.823 164.412 39.5883 + vertex -724.985 170.171 40.3341 + vertex -728.284 166.187 39.0549 + endloop + endfacet + facet normal -0.258008 -0.131176 0.957196 + outer loop + vertex -724.823 164.412 39.5883 + vertex -721.598 168.347 40.997 + vertex -724.985 170.171 40.3341 + endloop + endfacet + facet normal -0.238618 -0.147991 0.959771 + outer loop + vertex -721.515 162.923 40.1813 + vertex -721.598 168.347 40.997 + vertex -724.823 164.412 39.5883 + endloop + endfacet + facet normal -0.28419 -0.146835 0.947457 + outer loop + vertex -721.515 162.923 40.1813 + vertex -718.396 166.984 41.7464 + vertex -721.598 168.347 40.997 + endloop + endfacet + facet normal -0.272523 -0.115147 0.955234 + outer loop + vertex -718.396 166.984 41.7464 + vertex -718.635 173.438 42.4562 + vertex -721.598 168.347 40.997 + endloop + endfacet + facet normal -0.291965 -0.102594 0.950911 + outer loop + vertex -721.598 168.347 40.997 + vertex -718.635 173.438 42.4562 + vertex -721.896 175.132 41.6374 + endloop + endfacet + facet normal -0.264743 -0.162931 0.950455 + outer loop + vertex -718.262 161.727 40.8824 + vertex -718.396 166.984 41.7464 + vertex -721.515 162.923 40.1813 + endloop + endfacet + facet normal -0.249678 -0.175561 0.952281 + outer loop + vertex -724.742 160.265 38.8452 + vertex -721.515 162.923 40.1813 + vertex -724.823 164.412 39.5883 + endloop + endfacet + facet normal -0.236226 -0.19202 0.952536 + outer loop + vertex -721.364 158.857 39.3992 + vertex -721.515 162.923 40.1813 + vertex -724.742 160.265 38.8452 + endloop + endfacet + facet normal -0.264545 -0.227405 0.937178 + outer loop + vertex -716.843 154.768 39.7023 + vertex -717.874 157.581 40.0939 + vertex -720.33 155.858 38.9828 + endloop + endfacet + facet normal -0.273557 -0.191499 0.9426 + outer loop + vertex -721.364 158.857 39.3992 + vertex -718.262 161.727 40.8824 + vertex -721.515 162.923 40.1813 + endloop + endfacet + facet normal -0.294872 -0.218757 0.930159 + outer loop + vertex -714.4 156.196 40.8696 + vertex -714.988 160.582 41.715 + vertex -717.874 157.581 40.0939 + endloop + endfacet + facet normal -0.379107 -0.0345179 0.924709 + outer loop + vertex -716.482 186.813 44.1404 + vertex -713.448 187.3 45.4025 + vertex -714.932 198.056 45.1955 + endloop + endfacet + facet normal -0.423626 -0.0410423 0.904907 + outer loop + vertex -709.82 196.787 47.5314 + vertex -714.932 198.056 45.1955 + vertex -713.448 187.3 45.4025 + endloop + endfacet + facet normal -0.419585 -0.04299 0.906698 + outer loop + vertex -710.914 185.171 46.4741 + vertex -709.82 196.787 47.5314 + vertex -713.448 187.3 45.4025 + endloop + endfacet + facet normal -0.430743 -0.0593787 0.900519 + outer loop + vertex -713.08 178.668 45.0093 + vertex -710.914 185.171 46.4741 + vertex -713.448 187.3 45.4025 + endloop + endfacet + facet normal -0.424039 -0.0622829 0.9035 + outer loop + vertex -710.379 178.016 46.2321 + vertex -710.914 185.171 46.4741 + vertex -713.08 178.668 45.0093 + endloop + endfacet + facet normal -0.429227 -0.0934343 0.898351 + outer loop + vertex -712.673 171.465 44.4546 + vertex -710.379 178.016 46.2321 + vertex -713.08 178.668 45.0093 + endloop + endfacet + facet normal -0.41454 -0.100244 0.904493 + outer loop + vertex -709.859 170.719 45.6615 + vertex -710.379 178.016 46.2321 + vertex -712.673 171.465 44.4546 + endloop + endfacet + facet normal -0.421512 -0.140494 0.895873 + outer loop + vertex -712.236 165.021 43.6495 + vertex -709.859 170.719 45.6615 + vertex -712.673 171.465 44.4546 + endloop + endfacet + facet normal -0.39534 -0.154778 0.9054 + outer loop + vertex -709.175 163.979 44.808 + vertex -709.859 170.719 45.6615 + vertex -712.236 165.021 43.6495 + endloop + endfacet + facet normal -0.404604 -0.195347 0.893384 + outer loop + vertex -711.61 159.248 42.6708 + vertex -709.175 163.979 44.808 + vertex -712.236 165.021 43.6495 + endloop + endfacet + facet normal -0.373543 -0.215344 0.902271 + outer loop + vertex -708.153 157.436 43.6696 + vertex -709.175 163.979 44.808 + vertex -711.61 159.248 42.6708 + endloop + endfacet + facet normal -0.387041 -0.249079 0.887783 + outer loop + vertex -710.589 154.239 41.7106 + vertex -708.153 157.436 43.6696 + vertex -711.61 159.248 42.6708 + endloop + endfacet + facet normal -0.363329 -0.269614 0.891796 + outer loop + vertex -708.303 153.861 42.5273 + vertex -708.153 157.436 43.6696 + vertex -710.589 154.239 41.7106 + endloop + endfacet + facet normal -0.382078 -0.266602 0.884839 + outer loop + vertex -708.303 153.861 42.5273 + vertex -706.589 153.343 43.1117 + vertex -708.153 157.436 43.6696 + endloop + endfacet + facet normal -0.387064 -0.296339 0.873135 + outer loop + vertex -708.006 151.7 41.926 + vertex -706.589 153.343 43.1117 + vertex -708.303 153.861 42.5273 + endloop + endfacet + facet normal -0.364521 -0.295955 0.882913 + outer loop + vertex -708.303 153.861 42.5273 + vertex -710.589 154.239 41.7106 + vertex -708.006 151.7 41.926 + endloop + endfacet + facet normal -0.362399 -0.293657 0.884552 + outer loop + vertex -710.589 154.239 41.7106 + vertex -709.531 150.631 40.9462 + vertex -708.006 151.7 41.926 + endloop + endfacet + facet normal -0.373121 -0.309458 0.874652 + outer loop + vertex -705.873 150.509 42.4146 + vertex -706.589 153.343 43.1117 + vertex -708.006 151.7 41.926 + endloop + endfacet + facet normal -0.380055 -0.325516 0.865793 + outer loop + vertex -707.035 149.62 41.5702 + vertex -705.873 150.509 42.4146 + vertex -708.006 151.7 41.926 + endloop + endfacet + facet normal -0.347854 -0.313523 0.883573 + outer loop + vertex -707.035 149.62 41.5702 + vertex -708.006 151.7 41.926 + vertex -709.531 150.631 40.9462 + endloop + endfacet + facet normal -0.353622 -0.333783 0.873808 + outer loop + vertex -706.317 148.362 41.3798 + vertex -707.035 149.62 41.5702 + vertex -709.531 150.631 40.9462 + endloop + endfacet + facet normal -0.337002 -0.307159 0.88999 + outer loop + vertex -708.028 148.706 40.8509 + vertex -706.317 148.362 41.3798 + vertex -709.531 150.631 40.9462 + endloop + endfacet + facet normal -0.336654 -0.303082 0.891519 + outer loop + vertex -708.028 148.706 40.8509 + vertex -704.198 146.947 41.6992 + vertex -706.317 148.362 41.3798 + endloop + endfacet + facet normal -0.373702 -0.343388 0.861645 + outer loop + vertex -707.035 149.62 41.5702 + vertex -706.317 148.362 41.3798 + vertex -705.005 148.559 42.0277 + endloop + endfacet + facet normal -0.372283 -0.348336 0.860272 + outer loop + vertex -706.317 148.362 41.3798 + vertex -703.23 147.009 42.1682 + vertex -705.005 148.559 42.0277 + endloop + endfacet + facet normal -0.371098 -0.336805 0.865361 + outer loop + vertex -705.005 148.559 42.0277 + vertex -705.873 150.509 42.4146 + vertex -707.035 149.62 41.5702 + endloop + endfacet + facet normal -0.399563 -0.346193 0.848822 + outer loop + vertex -705.005 148.559 42.0277 + vertex -704.018 149.744 42.9756 + vertex -705.873 150.509 42.4146 + endloop + endfacet + facet normal -0.394328 -0.325861 0.859255 + outer loop + vertex -704.018 149.744 42.9756 + vertex -704.799 152.085 43.5049 + vertex -705.873 150.509 42.4146 + endloop + endfacet + facet normal -0.424342 -0.33207 0.842415 + outer loop + vertex -704.018 149.744 42.9756 + vertex -703.206 152.033 44.2867 + vertex -704.799 152.085 43.5049 + endloop + endfacet + facet normal -0.413243 -0.337848 0.84563 + outer loop + vertex -702.364 149.141 43.5429 + vertex -703.206 152.033 44.2867 + vertex -704.018 149.744 42.9756 + endloop + endfacet + facet normal -0.417734 -0.361533 0.833542 + outer loop + vertex -703.253 148.012 42.6076 + vertex -702.364 149.141 43.5429 + vertex -704.018 149.744 42.9756 + endloop + endfacet + facet normal -0.408736 -0.369444 0.834534 + outer loop + vertex -701.631 147.234 43.0577 + vertex -702.364 149.141 43.5429 + vertex -703.253 148.012 42.6076 + endloop + endfacet + facet normal -0.410145 -0.373943 0.831834 + outer loop + vertex -703.253 148.012 42.6076 + vertex -703.23 147.009 42.1682 + vertex -701.631 147.234 43.0577 + endloop + endfacet + facet normal -0.40666 -0.385177 0.828412 + outer loop + vertex -703.23 147.009 42.1682 + vertex -700.133 145.782 43.1181 + vertex -701.631 147.234 43.0577 + endloop + endfacet + facet normal -0.394967 -0.376325 0.838082 + outer loop + vertex -703.253 148.012 42.6076 + vertex -705.005 148.559 42.0277 + vertex -703.23 147.009 42.1682 + endloop + endfacet + facet normal -0.439245 -0.376383 0.815721 + outer loop + vertex -701.631 147.234 43.0577 + vertex -700.853 148.619 44.1161 + vertex -702.364 149.141 43.5429 + endloop + endfacet + facet normal -0.435816 -0.353061 0.827896 + outer loop + vertex -700.853 148.619 44.1161 + vertex -701.706 151.044 44.7006 + vertex -702.364 149.141 43.5429 + endloop + endfacet + facet normal -0.45976 -0.357842 0.812755 + outer loop + vertex -700.853 148.619 44.1161 + vertex -700.486 151.187 45.454 + vertex -701.706 151.044 44.7006 + endloop + endfacet + facet normal -0.45216 -0.360528 0.815825 + outer loop + vertex -699.428 148.108 44.6799 + vertex -700.486 151.187 45.454 + vertex -700.853 148.619 44.1161 + endloop + endfacet + facet normal -0.456512 -0.390991 0.799201 + outer loop + vertex -700.057 146.825 43.6927 + vertex -699.428 148.108 44.6799 + vertex -700.853 148.619 44.1161 + endloop + endfacet + facet normal -0.444883 -0.398778 0.801907 + outer loop + vertex -698.585 146.093 44.1454 + vertex -699.428 148.108 44.6799 + vertex -700.057 146.825 43.6927 + endloop + endfacet + facet normal -0.447133 -0.406484 0.79677 + outer loop + vertex -700.057 146.825 43.6927 + vertex -700.133 145.782 43.1181 + vertex -698.585 146.093 44.1454 + endloop + endfacet + facet normal -0.44005 -0.424198 0.791462 + outer loop + vertex -700.133 145.782 43.1181 + vertex -697.271 144.655 44.1055 + vertex -698.585 146.093 44.1454 + endloop + endfacet + facet normal -0.449897 -0.486407 0.749 + outer loop + vertex -697.271 144.655 44.1055 + vertex -700.133 145.782 43.1181 + vertex -698.863 144.783 43.2318 + endloop + endfacet + facet normal -0.420064 -0.443648 0.791658 + outer loop + vertex -701.52 145.855 42.4231 + vertex -698.863 144.783 43.2318 + vertex -700.133 145.782 43.1181 + endloop + endfacet + facet normal -0.419429 -0.447156 0.79002 + outer loop + vertex -700.133 145.782 43.1181 + vertex -703.23 147.009 42.1682 + vertex -701.52 145.855 42.4231 + endloop + endfacet + facet normal -0.430898 -0.411237 0.803251 + outer loop + vertex -700.057 146.825 43.6927 + vertex -701.631 147.234 43.0577 + vertex -700.133 145.782 43.1181 + endloop + endfacet + facet normal -0.473151 -0.405365 0.782181 + outer loop + vertex -698.585 146.093 44.1454 + vertex -698.139 147.661 45.2275 + vertex -699.428 148.108 44.6799 + endloop + endfacet + facet normal -0.469966 -0.376221 0.798492 + outer loop + vertex -698.139 147.661 45.2275 + vertex -699.187 150.239 45.8259 + vertex -699.428 148.108 44.6799 + endloop + endfacet + facet normal -0.479064 -0.378415 0.792022 + outer loop + vertex -698.139 147.661 45.2275 + vertex -698.336 150.54 46.4842 + vertex -699.187 150.239 45.8259 + endloop + endfacet + facet normal -0.480263 -0.378221 0.791389 + outer loop + vertex -697.037 147.275 45.7123 + vertex -698.336 150.54 46.4842 + vertex -698.139 147.661 45.2275 + endloop + endfacet + facet normal -0.484023 -0.416202 0.769739 + outer loop + vertex -697.225 145.742 44.7648 + vertex -697.037 147.275 45.7123 + vertex -698.139 147.661 45.2275 + endloop + endfacet + facet normal -0.469035 -0.421857 0.775914 + outer loop + vertex -696.122 145.151 45.1105 + vertex -697.037 147.275 45.7123 + vertex -697.225 145.742 44.7648 + endloop + endfacet + facet normal -0.475039 -0.441789 0.761026 + outer loop + vertex -697.225 145.742 44.7648 + vertex -697.271 144.655 44.1055 + vertex -696.122 145.151 45.1105 + endloop + endfacet + facet normal -0.467152 -0.454623 0.758345 + outer loop + vertex -697.271 144.655 44.1055 + vertex -695.058 143.825 44.9708 + vertex -696.122 145.151 45.1105 + endloop + endfacet + facet normal -0.463832 -0.445229 0.765918 + outer loop + vertex -697.225 145.742 44.7648 + vertex -698.585 146.093 44.1454 + vertex -697.271 144.655 44.1055 + endloop + endfacet + facet normal -0.516367 -0.386195 0.764342 + outer loop + vertex -697.037 147.275 45.7123 + vertex -697.374 149.725 46.7224 + vertex -698.336 150.54 46.4842 + endloop + endfacet + facet normal -0.486844 -0.389371 0.781904 + outer loop + vertex -696.235 147 46.0742 + vertex -697.374 149.725 46.7224 + vertex -697.037 147.275 45.7123 + endloop + endfacet + facet normal -0.489864 -0.42643 0.760389 + outer loop + vertex -696.122 145.151 45.1105 + vertex -696.235 147 46.0742 + vertex -697.037 147.275 45.7123 + endloop + endfacet + facet normal -0.486014 -0.427242 0.7624 + outer loop + vertex -695.327 144.998 45.5318 + vertex -696.235 147 46.0742 + vertex -696.122 145.151 45.1105 + endloop + endfacet + facet normal -0.482547 -0.465259 0.74208 + outer loop + vertex -695.327 144.998 45.5318 + vertex -696.122 145.151 45.1105 + vertex -695.058 143.825 44.9708 + endloop + endfacet + facet normal -0.490665 -0.464726 0.737074 + outer loop + vertex -695.327 144.998 45.5318 + vertex -695.058 143.825 44.9708 + vertex -694.834 144.628 45.626 + endloop + endfacet + facet normal -0.470288 -0.428957 0.771249 + outer loop + vertex -694.834 144.628 45.626 + vertex -695.731 146.801 46.288 + vertex -695.327 144.998 45.5318 + endloop + endfacet + facet normal -0.490435 -0.428316 0.758959 + outer loop + vertex -695.327 144.998 45.5318 + vertex -695.731 146.801 46.288 + vertex -696.235 147 46.0742 + endloop + endfacet + facet normal -0.477542 -0.430349 0.765998 + outer loop + vertex -694.834 144.628 45.626 + vertex -695.511 146.724 46.3814 + vertex -695.731 146.801 46.288 + endloop + endfacet + facet normal -0.514719 -0.432984 0.739993 + outer loop + vertex -694.677 144.74 45.8014 + vertex -695.511 146.724 46.3814 + vertex -694.834 144.628 45.626 + endloop + endfacet + facet normal -0.488234 -0.466405 0.737627 + outer loop + vertex -694.677 144.74 45.8014 + vertex -694.834 144.628 45.626 + vertex -694.165 143.599 45.4186 + endloop + endfacet + facet normal -0.454692 -0.459792 0.762788 + outer loop + vertex -694.677 144.74 45.8014 + vertex -694.165 143.599 45.4186 + vertex -694.538 144.591 45.794 + endloop + endfacet + facet normal -0.396627 -0.408787 0.821937 + outer loop + vertex -694.538 144.591 45.794 + vertex -695.465 146.765 46.4278 + vertex -694.677 144.74 45.8014 + endloop + endfacet + facet normal -0.381692 -0.40501 0.83083 + outer loop + vertex -694.538 144.591 45.794 + vertex -695.509 146.936 46.4913 + vertex -695.465 146.765 46.4278 + endloop + endfacet + facet normal -0.551546 -0.439149 0.709186 + outer loop + vertex -694.643 144.945 45.9314 + vertex -695.509 146.936 46.4913 + vertex -694.538 144.591 45.794 + endloop + endfacet + facet normal -0.39101 -0.431585 0.812924 + outer loop + vertex -694.643 144.945 45.9314 + vertex -694.538 144.591 45.794 + vertex -693.974 143.652 45.5673 + endloop + endfacet + facet normal -0.382226 -0.428643 0.818638 + outer loop + vertex -694.643 144.945 45.9314 + vertex -693.974 143.652 45.5673 + vertex -694.48 144.743 45.902 + endloop + endfacet + facet normal -0.325127 -0.38877 0.862062 + outer loop + vertex -694.48 144.743 45.902 + vertex -695.508 147.047 46.5532 + vertex -694.643 144.945 45.9314 + endloop + endfacet + facet normal -0.54208 -0.443643 0.713673 + outer loop + vertex -694.48 144.743 45.902 + vertex -695.247 146.59 46.4675 + vertex -695.508 147.047 46.5532 + endloop + endfacet + facet normal -0.360253 -0.406685 0.839539 + outer loop + vertex -694.369 144.671 45.9145 + vertex -695.247 146.59 46.4675 + vertex -694.48 144.743 45.902 + endloop + endfacet + facet normal -0.370171 -0.424124 0.826494 + outer loop + vertex -694.369 144.671 45.9145 + vertex -694.48 144.743 45.902 + vertex -693.876 143.689 45.6319 + endloop + endfacet + facet normal -0.358359 -0.420247 0.83365 + outer loop + vertex -694.369 144.671 45.9145 + vertex -693.876 143.689 45.6319 + vertex -693.959 144.012 45.7587 + endloop + endfacet + facet normal -0.315455 -0.399899 0.860563 + outer loop + vertex -693.959 144.012 45.7587 + vertex -694.674 145.582 46.226 + vertex -694.369 144.671 45.9145 + endloop + endfacet + facet normal -0.386008 -0.422099 0.820262 + outer loop + vertex -693.959 144.012 45.7587 + vertex -693.876 143.689 45.6319 + vertex -693.155 142.971 45.6015 + endloop + endfacet + facet normal -0.383846 -0.420017 0.822343 + outer loop + vertex -693.876 143.689 45.6319 + vertex -693.974 143.652 45.5673 + vertex -693.155 142.971 45.6015 + endloop + endfacet + facet normal -0.442975 -0.494813 0.747618 + outer loop + vertex -693.974 143.652 45.5673 + vertex -694.165 143.599 45.4186 + vertex -693.155 142.971 45.6015 + endloop + endfacet + facet normal -0.478095 -0.57593 0.663122 + outer loop + vertex -694.165 143.599 45.4186 + vertex -695.058 143.825 44.9708 + vertex -693.155 142.971 45.6015 + endloop + endfacet + facet normal -0.471451 -0.53064 0.704383 + outer loop + vertex -696.119 143.781 44.2272 + vertex -693.155 142.971 45.6015 + vertex -695.058 143.825 44.9708 + endloop + endfacet + facet normal -0.473566 -0.525148 0.707075 + outer loop + vertex -695.058 143.825 44.9708 + vertex -697.271 144.655 44.1055 + vertex -696.119 143.781 44.2272 + endloop + endfacet + facet normal -0.366924 -0.40863 0.835696 + outer loop + vertex -694.369 144.671 45.9145 + vertex -694.674 145.582 46.226 + vertex -695.247 146.59 46.4675 + endloop + endfacet + facet normal -0.379516 -0.427892 0.82029 + outer loop + vertex -693.974 143.652 45.5673 + vertex -693.876 143.689 45.6319 + vertex -694.48 144.743 45.902 + endloop + endfacet + facet normal -0.481814 -0.424919 0.766354 + outer loop + vertex -694.643 144.945 45.9314 + vertex -695.508 147.047 46.5532 + vertex -695.509 146.936 46.4913 + endloop + endfacet + facet normal -0.461038 -0.460558 0.758505 + outer loop + vertex -694.165 143.599 45.4186 + vertex -693.974 143.652 45.5673 + vertex -694.538 144.591 45.794 + endloop + endfacet + facet normal -0.433019 -0.416049 0.799623 + outer loop + vertex -694.677 144.74 45.8014 + vertex -695.465 146.765 46.4278 + vertex -695.511 146.724 46.3814 + endloop + endfacet + facet normal -0.48787 -0.466238 0.737974 + outer loop + vertex -695.058 143.825 44.9708 + vertex -694.165 143.599 45.4186 + vertex -694.834 144.628 45.626 + endloop + endfacet + facet normal -0.456129 -0.381761 0.803868 + outer loop + vertex -696.235 147 46.0742 + vertex -697.086 150.24 47.1303 + vertex -697.374 149.725 46.7224 + endloop + endfacet + facet normal -0.484371 -0.383466 0.786345 + outer loop + vertex -695.731 146.801 46.288 + vertex -697.086 150.24 47.1303 + vertex -696.235 147 46.0742 + endloop + endfacet + facet normal -0.553874 -0.397454 0.73161 + outer loop + vertex -695.731 146.801 46.288 + vertex -696.596 149.538 47.1194 + vertex -697.086 150.24 47.1303 + endloop + endfacet + facet normal -0.473404 -0.389718 0.789942 + outer loop + vertex -695.511 146.724 46.3814 + vertex -696.596 149.538 47.1194 + vertex -695.731 146.801 46.288 + endloop + endfacet + facet normal -0.262829 -0.33832 0.903582 + outer loop + vertex -695.511 146.724 46.3814 + vertex -696.752 150.214 47.3275 + vertex -696.596 149.538 47.1194 + endloop + endfacet + facet normal -0.463584 -0.381524 0.799706 + outer loop + vertex -695.465 146.765 46.4278 + vertex -696.752 150.214 47.3275 + vertex -695.511 146.724 46.3814 + endloop + endfacet + facet normal -0.940562 -0.327138 -0.0912386 + outer loop + vertex -695.465 146.765 46.4278 + vertex -696.555 149.678 47.2155 + vertex -696.752 150.214 47.3275 + endloop + endfacet + facet normal -0.586805 -0.408498 0.699135 + outer loop + vertex -695.509 146.936 46.4913 + vertex -696.555 149.678 47.2155 + vertex -695.465 146.765 46.4278 + endloop + endfacet + facet normal -0.321329 -0.354488 0.878115 + outer loop + vertex -695.509 146.936 46.4913 + vertex -696.815 150.461 47.4361 + vertex -696.555 149.678 47.2155 + endloop + endfacet + facet normal -0.559071 -0.401663 0.725331 + outer loop + vertex -695.508 147.047 46.5532 + vertex -696.815 150.461 47.4361 + vertex -695.509 146.936 46.4913 + endloop + endfacet + facet normal -0.833185 -0.413884 0.366746 + outer loop + vertex -695.508 147.047 46.5532 + vertex -696.562 149.872 47.3473 + vertex -696.815 150.461 47.4361 + endloop + endfacet + facet normal -0.393944 -0.381933 0.836024 + outer loop + vertex -695.247 146.59 46.4675 + vertex -696.562 149.872 47.3473 + vertex -695.508 147.047 46.5532 + endloop + endfacet + facet normal -0.691482 -0.432214 0.578829 + outer loop + vertex -695.247 146.59 46.4675 + vertex -695.903 148.345 46.9943 + vertex -696.562 149.872 47.3473 + endloop + endfacet + facet normal -0.276647 -0.369635 0.887038 + outer loop + vertex -694.674 145.582 46.226 + vertex -695.903 148.345 46.9943 + vertex -695.247 146.59 46.4675 + endloop + endfacet + facet normal -0.463631 -0.410248 0.78533 + outer loop + vertex -697.225 145.742 44.7648 + vertex -698.139 147.661 45.2275 + vertex -698.585 146.093 44.1454 + endloop + endfacet + facet normal -0.493839 -0.367837 0.787921 + outer loop + vertex -699.428 148.108 44.6799 + vertex -699.187 150.239 45.8259 + vertex -700.486 151.187 45.454 + endloop + endfacet + facet normal -0.429475 -0.38336 0.817671 + outer loop + vertex -700.057 146.825 43.6927 + vertex -700.853 148.619 44.1161 + vertex -701.631 147.234 43.0577 + endloop + endfacet + facet normal -0.453497 -0.34359 0.822366 + outer loop + vertex -702.364 149.141 43.5429 + vertex -701.706 151.044 44.7006 + vertex -703.206 152.033 44.2867 + endloop + endfacet + facet normal -0.440526 -0.316495 0.8401 + outer loop + vertex -701.706 151.044 44.7006 + vertex -702.229 155.507 46.1079 + vertex -703.206 152.033 44.2867 + endloop + endfacet + facet normal -0.464832 -0.305 0.831208 + outer loop + vertex -702.229 155.507 46.1079 + vertex -704.902 156.306 44.9061 + vertex -703.206 152.033 44.2867 + endloop + endfacet + facet normal -0.471538 -0.314952 0.823685 + outer loop + vertex -701.706 151.044 44.7006 + vertex -700.486 151.187 45.454 + vertex -702.229 155.507 46.1079 + endloop + endfacet + facet normal -0.391612 -0.3534 0.849558 + outer loop + vertex -703.253 148.012 42.6076 + vertex -704.018 149.744 42.9756 + vertex -705.005 148.559 42.0277 + endloop + endfacet + facet normal -0.409016 -0.314127 0.856756 + outer loop + vertex -705.873 150.509 42.4146 + vertex -704.799 152.085 43.5049 + vertex -706.589 153.343 43.1117 + endloop + endfacet + facet normal -0.399654 -0.2976 0.867013 + outer loop + vertex -704.799 152.085 43.5049 + vertex -704.902 156.306 44.9061 + vertex -706.589 153.343 43.1117 + endloop + endfacet + facet normal -0.424772 -0.279669 0.861019 + outer loop + vertex -704.902 156.306 44.9061 + vertex -708.153 157.436 43.6696 + vertex -706.589 153.343 43.1117 + endloop + endfacet + facet normal -0.428856 -0.29405 0.854176 + outer loop + vertex -704.799 152.085 43.5049 + vertex -703.206 152.033 44.2867 + vertex -704.902 156.306 44.9061 + endloop + endfacet + facet normal -0.418005 -0.0120347 0.908365 + outer loop + vertex -709.82 196.787 47.5314 + vertex -710.115 212.898 47.6087 + vertex -714.932 198.056 45.1955 + endloop + endfacet + facet normal -0.421907 -0.0104775 0.906578 + outer loop + vertex -714.932 198.056 45.1955 + vertex -710.115 212.898 47.6087 + vertex -715.081 213.967 45.31 + endloop + endfacet + facet normal -0.41926 0.00456508 0.907855 + outer loop + vertex -710.115 212.898 47.6087 + vertex -709.906 228.236 47.6281 + vertex -715.081 213.967 45.31 + endloop + endfacet + facet normal -0.430784 0.00962972 0.902404 + outer loop + vertex -715.081 213.967 45.31 + vertex -709.906 228.236 47.6281 + vertex -714.721 229.11 45.3204 + endloop + endfacet + facet normal -0.430205 0.0134225 0.902631 + outer loop + vertex -709.906 228.236 47.6281 + vertex -709.456 242.89 47.6249 + vertex -714.721 229.11 45.3204 + endloop + endfacet + facet normal -0.443494 0.019598 0.896063 + outer loop + vertex -714.721 229.11 45.3204 + vertex -709.456 242.89 47.6249 + vertex -714.124 243.539 45.3 + endloop + endfacet + facet normal -0.444084 0.0146432 0.895865 + outer loop + vertex -709.456 242.89 47.6249 + vertex -708.987 257.205 47.6234 + vertex -714.124 243.539 45.3 + endloop + endfacet + facet normal -0.456398 0.0203475 0.889543 + outer loop + vertex -714.124 243.539 45.3 + vertex -708.987 257.205 47.6234 + vertex -713.505 257.741 45.2927 + endloop + endfacet + facet normal -0.457231 0.0121186 0.889266 + outer loop + vertex -708.987 257.205 47.6234 + vertex -708.602 271.477 47.6266 + vertex -713.505 257.741 45.2927 + endloop + endfacet + facet normal -0.46993 0.0177973 0.882524 + outer loop + vertex -713.505 257.741 45.2927 + vertex -708.602 271.477 47.6266 + vertex -712.961 271.966 45.296 + endloop + endfacet + facet normal -0.470668 0.00993543 0.882254 + outer loop + vertex -708.602 271.477 47.6266 + vertex -708.308 285.767 47.6224 + vertex -712.961 271.966 45.296 + endloop + endfacet + facet normal -0.485784 0.0164348 0.873924 + outer loop + vertex -712.961 271.966 45.296 + vertex -708.308 285.767 47.6224 + vertex -712.481 286.208 45.2947 + endloop + endfacet + facet normal -0.486407 0.00926221 0.873683 + outer loop + vertex -708.308 285.767 47.6224 + vertex -708.056 300.044 47.6117 + vertex -712.481 286.208 45.2947 + endloop + endfacet + facet normal -0.504967 0.0169917 0.862972 + outer loop + vertex -712.481 286.208 45.2947 + vertex -708.056 300.044 47.6117 + vertex -712.019 300.409 45.2852 + endloop + endfacet + facet normal -0.505533 0.00946138 0.862755 + outer loop + vertex -708.056 300.044 47.6117 + vertex -707.794 314.302 47.609 + vertex -712.019 300.409 45.2852 + endloop + endfacet + facet normal -0.523546 0.0167671 0.851833 + outer loop + vertex -712.019 300.409 45.2852 + vertex -707.794 314.302 47.609 + vertex -711.571 314.589 45.2819 + endloop + endfacet + facet normal -0.524091 0.00790484 0.851625 + outer loop + vertex -707.794 314.302 47.609 + vertex -707.554 328.57 47.6243 + vertex -711.571 314.589 45.2819 + endloop + endfacet + facet normal -0.547943 0.0173199 0.836336 + outer loop + vertex -711.571 314.589 45.2819 + vertex -707.554 328.57 47.6243 + vertex -711.107 328.769 45.2922 + endloop + endfacet + facet normal -0.54841 0.00714755 0.836179 + outer loop + vertex -707.554 328.57 47.6243 + vertex -707.307 342.848 47.6637 + vertex -711.107 328.769 45.2922 + endloop + endfacet + facet normal -0.574214 0.0170841 0.818527 + outer loop + vertex -711.107 328.769 45.2922 + vertex -707.307 342.848 47.6637 + vertex -710.647 342.985 45.318 + endloop + endfacet + facet normal -0.574602 0.00567102 0.818414 + outer loop + vertex -707.307 342.848 47.6637 + vertex -707.104 357.182 47.707 + vertex -710.647 342.985 45.318 + endloop + endfacet + facet normal -0.60278 0.0161808 0.797744 + outer loop + vertex -710.647 342.985 45.318 + vertex -707.104 357.182 47.707 + vertex -710.229 357.283 45.344 + endloop + endfacet + facet normal -0.603212 -0.000946822 0.79758 + outer loop + vertex -707.104 357.182 47.707 + vertex -707.127 371.714 47.7068 + vertex -710.229 357.283 45.344 + endloop + endfacet + facet normal -0.633118 0.00934215 0.773999 + outer loop + vertex -710.229 357.283 45.344 + vertex -707.127 371.714 47.7068 + vertex -710.054 371.776 45.312 + endloop + endfacet + facet normal -0.633364 -0.0105065 0.773783 + outer loop + vertex -707.127 371.714 47.7068 + vertex -707.708 386.624 47.4344 + vertex -710.054 371.776 45.312 + endloop + endfacet + facet normal -0.650244 -0.00582633 0.759703 + outer loop + vertex -710.054 371.776 45.312 + vertex -707.708 386.624 47.4344 + vertex -710.506 386.592 45.0385 + endloop + endfacet + facet normal -0.375651 -0.0568533 0.925016 + outer loop + vertex -715.96 179.548 43.9059 + vertex -713.448 187.3 45.4025 + vertex -716.482 186.813 44.1404 + endloop + endfacet + facet normal -0.372589 -0.0580697 0.926178 + outer loop + vertex -713.08 178.668 45.0093 + vertex -713.448 187.3 45.4025 + vertex -715.96 179.548 43.9059 + endloop + endfacet + facet normal -0.379174 -0.0856732 0.921351 + outer loop + vertex -715.581 172.284 43.3862 + vertex -713.08 178.668 45.0093 + vertex -715.96 179.548 43.9059 + endloop + endfacet + facet normal -0.366071 -0.0919962 0.926028 + outer loop + vertex -712.673 171.465 44.4546 + vertex -713.08 178.668 45.0093 + vertex -715.581 172.284 43.3862 + endloop + endfacet + facet normal -0.373397 -0.127286 0.918898 + outer loop + vertex -715.307 165.961 42.622 + vertex -712.673 171.465 44.4546 + vertex -715.581 172.284 43.3862 + endloop + endfacet + facet normal -0.352395 -0.139499 0.925396 + outer loop + vertex -712.236 165.021 43.6495 + vertex -712.673 171.465 44.4546 + vertex -715.307 165.961 42.622 + endloop + endfacet + facet normal -0.360403 -0.175867 0.916068 + outer loop + vertex -714.988 160.582 41.715 + vertex -712.236 165.021 43.6495 + vertex -715.307 165.961 42.622 + endloop + endfacet + facet normal -0.336971 -0.192786 0.921566 + outer loop + vertex -711.61 159.248 42.6708 + vertex -712.236 165.021 43.6495 + vertex -714.988 160.582 41.715 + endloop + endfacet + facet normal -0.345725 -0.222013 0.911693 + outer loop + vertex -714.4 156.196 40.8696 + vertex -711.61 159.248 42.6708 + vertex -714.988 160.582 41.715 + endloop + endfacet + facet normal -0.32578 -0.241632 0.914047 + outer loop + vertex -710.589 154.239 41.7106 + vertex -711.61 159.248 42.6708 + vertex -714.4 156.196 40.8696 + endloop + endfacet + facet normal -0.331941 -0.256316 0.907809 + outer loop + vertex -713.57 152.963 40.2601 + vertex -710.589 154.239 41.7106 + vertex -714.4 156.196 40.8696 + endloop + endfacet + facet normal -0.31802 -0.284825 0.904289 + outer loop + vertex -709.531 150.631 40.9462 + vertex -710.589 154.239 41.7106 + vertex -713.57 152.963 40.2601 + endloop + endfacet + facet normal -0.336971 -0.00993291 0.941463 + outer loop + vertex -714.932 198.056 45.1955 + vertex -715.081 213.967 45.31 + vertex -720.863 199.625 43.0892 + endloop + endfacet + facet normal -0.346864 -0.00539248 0.9379 + outer loop + vertex -720.863 199.625 43.0892 + vertex -715.081 213.967 45.31 + vertex -720.74 215.769 43.2277 + endloop + endfacet + facet normal -0.343236 0.00752101 0.939219 + outer loop + vertex -715.081 213.967 45.31 + vertex -714.721 229.11 45.3204 + vertex -720.74 215.769 43.2277 + endloop + endfacet + facet normal -0.354512 0.0132768 0.934957 + outer loop + vertex -720.74 215.769 43.2277 + vertex -714.721 229.11 45.3204 + vertex -720.182 230.536 43.2296 + endloop + endfacet + facet normal -0.353888 0.0159499 0.935152 + outer loop + vertex -714.721 229.11 45.3204 + vertex -714.124 243.539 45.3 + vertex -720.182 230.536 43.2296 + endloop + endfacet + facet normal -0.363506 0.0210343 0.931354 + outer loop + vertex -720.182 230.536 43.2296 + vertex -714.124 243.539 45.3 + vertex -719.411 244.726 43.2098 + endloop + endfacet + facet normal -0.364446 0.0163612 0.931081 + outer loop + vertex -714.124 243.539 45.3 + vertex -713.505 257.741 45.2927 + vertex -719.411 244.726 43.2098 + endloop + endfacet + facet normal -0.373343 0.0209783 0.927456 + outer loop + vertex -719.411 244.726 43.2098 + vertex -713.505 257.741 45.2927 + vertex -718.628 258.837 43.206 + endloop + endfacet + facet normal -0.374646 0.0141369 0.92706 + outer loop + vertex -713.505 257.741 45.2927 + vertex -712.961 271.966 45.296 + vertex -718.628 258.837 43.206 + endloop + endfacet + facet normal -0.387447 0.0205218 0.921664 + outer loop + vertex -718.628 258.837 43.206 + vertex -712.961 271.966 45.296 + vertex -717.889 272.987 43.2015 + endloop + endfacet + facet normal -0.388786 0.0131734 0.921234 + outer loop + vertex -712.961 271.966 45.296 + vertex -712.481 286.208 45.2947 + vertex -717.889 272.987 43.2015 + endloop + endfacet + facet normal -0.402462 0.0197188 0.915224 + outer loop + vertex -717.889 272.987 43.2015 + vertex -712.481 286.208 45.2947 + vertex -717.197 287.127 43.2013 + endloop + endfacet + facet normal -0.403479 0.0137277 0.914886 + outer loop + vertex -712.481 286.208 45.2947 + vertex -712.019 300.409 45.2852 + vertex -717.197 287.127 43.2013 + endloop + endfacet + facet normal -0.418047 0.0204555 0.908195 + outer loop + vertex -717.197 287.127 43.2013 + vertex -712.019 300.409 45.2852 + vertex -716.514 301.2 43.1985 + endloop + endfacet + facet normal -0.419108 0.0134746 0.907836 + outer loop + vertex -712.019 300.409 45.2852 + vertex -711.571 314.589 45.2819 + vertex -716.514 301.2 43.1985 + endloop + endfacet + facet normal -0.437218 0.0215206 0.899098 + outer loop + vertex -716.514 301.2 43.1985 + vertex -711.571 314.589 45.2819 + vertex -715.828 315.238 43.196 + endloop + endfacet + facet normal -0.438242 0.0136855 0.898753 + outer loop + vertex -711.571 314.589 45.2819 + vertex -711.107 328.769 45.2922 + vertex -715.828 315.238 43.196 + endloop + endfacet + facet normal -0.45797 0.0221276 0.888692 + outer loop + vertex -715.828 315.238 43.196 + vertex -711.107 328.769 45.2922 + vertex -715.142 329.289 43.1999 + endloop + endfacet + facet normal -0.458947 0.0132304 0.888365 + outer loop + vertex -711.107 328.769 45.2922 + vertex -710.647 342.985 45.318 + vertex -715.142 329.289 43.1999 + endloop + endfacet + facet normal -0.486351 0.0245356 0.873419 + outer loop + vertex -715.142 329.289 43.1999 + vertex -710.647 342.985 45.318 + vertex -714.439 343.373 43.1955 + endloop + endfacet + facet normal -0.487384 0.0126688 0.873096 + outer loop + vertex -710.647 342.985 45.318 + vertex -710.229 357.283 45.344 + vertex -714.439 343.373 43.1955 + endloop + endfacet + facet normal -0.513104 0.0227808 0.858024 + outer loop + vertex -714.439 343.373 43.1955 + vertex -710.229 357.283 45.344 + vertex -713.79 357.556 43.2071 + endloop + endfacet + facet normal -0.514048 0.00809045 0.857723 + outer loop + vertex -710.229 357.283 45.344 + vertex -710.054 371.776 45.312 + vertex -713.79 357.556 43.2071 + endloop + endfacet + facet normal -0.539498 0.0171322 0.841812 + outer loop + vertex -713.79 357.556 43.2071 + vertex -710.054 371.776 45.312 + vertex -713.353 371.906 43.1954 + endloop + endfacet + facet normal -0.540082 -0.000950233 0.841612 + outer loop + vertex -710.054 371.776 45.312 + vertex -710.506 386.592 45.0385 + vertex -713.353 371.906 43.1954 + endloop + endfacet + facet normal -0.540209 -0.000915511 0.841531 + outer loop + vertex -713.353 371.906 43.1954 + vertex -710.506 386.592 45.0385 + vertex -713.445 386.552 43.1523 + endloop + endfacet + facet normal -0.279196 -0.0749071 0.957308 + outer loop + vertex -718.635 173.438 42.4562 + vertex -719.044 180.924 42.9226 + vertex -721.896 175.132 41.6374 + endloop + endfacet + facet normal -0.243592 -0.10175 0.964526 + outer loop + vertex -721.598 168.347 40.997 + vertex -721.896 175.132 41.6374 + vertex -724.985 170.171 40.3341 + endloop + endfacet + facet normal -0.202713 -0.0556517 0.977655 + outer loop + vertex -728.347 178.297 40.2795 + vertex -726.628 187.356 41.1517 + vertex -733.071 177.234 39.2396 + endloop + endfacet + facet normal -0.205552 -0.0537532 0.977169 + outer loop + vertex -733.071 177.234 39.2396 + vertex -726.628 187.356 41.1517 + vertex -733.687 191.585 39.8995 + endloop + endfacet + facet normal -0.189031 -0.0248543 0.981656 + outer loop + vertex -726.628 187.356 41.1517 + vertex -727.063 203.134 41.4675 + vertex -733.687 191.585 39.8995 + endloop + endfacet + facet normal -0.194585 -0.0215317 0.980649 + outer loop + vertex -733.687 191.585 39.8995 + vertex -727.063 203.134 41.4675 + vertex -733.57 206.263 40.245 + endloop + endfacet + facet normal -0.18609 -0.00313336 0.982528 + outer loop + vertex -727.063 203.134 41.4675 + vertex -726.726 218.122 41.5791 + vertex -733.57 206.263 40.245 + endloop + endfacet + facet normal -0.191427 6.17949e-05 0.981507 + outer loop + vertex -733.57 206.263 40.245 + vertex -726.726 218.122 41.5791 + vertex -732.879 220.511 40.3788 + endloop + endfacet + facet normal -0.187783 0.00977821 0.982162 + outer loop + vertex -726.726 218.122 41.5791 + vertex -725.943 232.377 41.5869 + vertex -732.879 220.511 40.3788 + endloop + endfacet + facet normal -0.191511 0.0120335 0.981417 + outer loop + vertex -732.879 220.511 40.3788 + vertex -725.943 232.377 41.5869 + vertex -731.88 234.443 40.403 + endloop + endfacet + facet normal -0.19098 0.0136077 0.9815 + outer loop + vertex -725.943 232.377 41.5869 + vertex -724.997 246.375 41.5768 + vertex -731.88 234.443 40.403 + endloop + endfacet + facet normal -0.19529 0.0161813 0.980612 + outer loop + vertex -731.88 234.443 40.403 + vertex -724.997 246.375 41.5768 + vertex -730.785 248.335 40.3917 + endloop + endfacet + facet normal -0.196032 0.0139211 0.980499 + outer loop + vertex -724.997 246.375 41.5768 + vertex -724.044 260.399 41.5682 + vertex -730.785 248.335 40.3917 + endloop + endfacet + facet normal -0.200723 0.0166395 0.979507 + outer loop + vertex -730.785 248.335 40.3917 + vertex -724.044 260.399 41.5682 + vertex -729.677 262.265 40.3823 + endloop + endfacet + facet normal -0.201907 0.0129466 0.979319 + outer loop + vertex -724.044 260.399 41.5682 + vertex -723.124 274.449 41.5722 + vertex -729.677 262.265 40.3823 + endloop + endfacet + facet normal -0.208984 0.0169032 0.977773 + outer loop + vertex -729.677 262.265 40.3823 + vertex -723.124 274.449 41.5722 + vertex -728.553 276.146 40.3826 + endloop + endfacet + facet normal -0.20993 0.0137659 0.977619 + outer loop + vertex -723.124 274.449 41.5722 + vertex -722.206 288.421 41.5726 + vertex -728.553 276.146 40.3826 + endloop + endfacet + facet normal -0.217567 0.0178829 0.975881 + outer loop + vertex -728.553 276.146 40.3826 + vertex -722.206 288.421 41.5726 + vertex -727.405 289.906 40.3862 + endloop + endfacet + facet normal -0.218455 0.0146607 0.975737 + outer loop + vertex -722.206 288.421 41.5726 + vertex -721.283 302.305 41.5705 + vertex -727.405 289.906 40.3862 + endloop + endfacet + facet normal -0.227575 0.0193712 0.973568 + outer loop + vertex -727.405 289.906 40.3862 + vertex -721.283 302.305 41.5705 + vertex -726.24 303.571 40.3866 + endloop + endfacet + facet normal -0.228415 0.0159566 0.973433 + outer loop + vertex -721.283 302.305 41.5705 + vertex -720.352 316.151 41.5622 + vertex -726.24 303.571 40.3866 + endloop + endfacet + facet normal -0.237651 0.0204947 0.971134 + outer loop + vertex -726.24 303.571 40.3866 + vertex -720.352 316.151 41.5622 + vertex -725.071 317.208 40.385 + endloop + endfacet + facet normal -0.238499 0.0165634 0.971002 + outer loop + vertex -720.352 316.151 41.5622 + vertex -719.421 330.015 41.5544 + vertex -725.071 317.208 40.385 + endloop + endfacet + facet normal -0.253077 0.0233453 0.967164 + outer loop + vertex -725.071 317.208 40.385 + vertex -719.421 330.015 41.5544 + vertex -723.885 330.849 40.3661 + endloop + endfacet + facet normal -0.254002 0.0182066 0.967032 + outer loop + vertex -719.421 330.015 41.5544 + vertex -718.487 343.922 41.5378 + vertex -723.885 330.849 40.3661 + endloop + endfacet + facet normal -0.269995 0.0252142 0.962531 + outer loop + vertex -723.885 330.849 40.3661 + vertex -718.487 343.922 41.5378 + vertex -722.707 344.537 40.338 + endloop + endfacet + facet normal -0.270903 0.0187789 0.962423 + outer loop + vertex -718.487 343.922 41.5378 + vertex -717.584 357.91 41.5189 + vertex -722.707 344.537 40.338 + endloop + endfacet + facet normal -0.288867 0.0261377 0.957012 + outer loop + vertex -722.707 344.537 40.338 + vertex -717.584 357.91 41.5189 + vertex -721.564 358.309 40.3067 + endloop + endfacet + facet normal -0.290132 0.0131718 0.956896 + outer loop + vertex -717.584 357.91 41.5189 + vertex -716.886 372.068 41.5358 + vertex -721.564 358.309 40.3067 + endloop + endfacet + facet normal -0.309108 0.0201671 0.950813 + outer loop + vertex -721.564 358.309 40.3067 + vertex -716.886 372.068 41.5358 + vertex -720.602 372.245 40.3239 + endloop + endfacet + facet normal -0.31007 -0.000735549 0.950713 + outer loop + vertex -716.886 372.068 41.5358 + vertex -716.638 386.503 41.6277 + vertex -720.602 372.245 40.3239 + endloop + endfacet + facet normal -0.327875 0.00476365 0.944709 + outer loop + vertex -720.602 372.245 40.3239 + vertex -716.638 386.503 41.6277 + vertex -720.06 386.446 40.4405 + endloop + endfacet + facet normal -0.233641 -0.116474 0.965322 + outer loop + vertex -728.284 166.187 39.0549 + vertex -724.985 170.171 40.3341 + vertex -728.584 172.495 39.7434 + endloop + endfacet + facet normal -0.193443 -0.15807 0.968294 + outer loop + vertex -728.045 161.722 38.3737 + vertex -728.284 166.187 39.0549 + vertex -731.576 163.355 37.9348 + endloop + endfacet + facet normal -0.173728 -0.175081 0.969105 + outer loop + vertex -730.753 160.24 37.5197 + vertex -731.576 163.355 37.9348 + vertex -734.74 162.015 37.1256 + endloop + endfacet + facet normal -0.142053 -0.160539 0.976754 + outer loop + vertex -743.865 164.975 36.2243 + vertex -738.456 162.589 36.6188 + vertex -742.139 165.742 36.6014 + endloop + endfacet + facet normal -0.130083 -0.132434 0.982619 + outer loop + vertex -738.456 162.589 36.6188 + vertex -743.865 164.975 36.2243 + vertex -736.787 160.955 36.6194 + endloop + endfacet + facet normal -0.158012 -0.153229 0.975476 + outer loop + vertex -738.088 163.862 36.9015 + vertex -735.209 165.041 37.5529 + vertex -739.007 167.043 37.2522 + endloop + endfacet + facet normal -0.153346 -0.11645 0.981287 + outer loop + vertex -739.007 167.043 37.2522 + vertex -735.641 169.372 38.0545 + vertex -739.174 172.528 37.877 + endloop + endfacet + facet normal -0.140927 -0.102356 0.984715 + outer loop + vertex -735.641 169.372 38.0545 + vertex -733.071 177.234 39.2396 + vertex -739.174 172.528 37.877 + endloop + endfacet + facet normal -0.155417 -0.08345 0.984318 + outer loop + vertex -733.071 177.234 39.2396 + vertex -740.905 181.319 38.349 + vertex -739.174 172.528 37.877 + endloop + endfacet + facet normal -0.119781 -0.0767285 0.989831 + outer loop + vertex -742.981 174.16 37.5428 + vertex -739.174 172.528 37.877 + vertex -740.905 181.319 38.349 + endloop + endfacet + facet normal -0.113452 -0.0786309 0.990427 + outer loop + vertex -742.981 174.16 37.5428 + vertex -740.905 181.319 38.349 + vertex -748.041 175.784 37.0921 + endloop + endfacet + facet normal -0.116969 -0.0740833 0.990369 + outer loop + vertex -748.041 175.784 37.0921 + vertex -740.905 181.319 38.349 + vertex -748.243 186.34 37.8579 + endloop + endfacet + facet normal -0.08298 -0.0736835 0.993823 + outer loop + vertex -748.041 175.784 37.0921 + vertex -748.243 186.34 37.8579 + vertex -755.621 180.526 36.8108 + endloop + endfacet + facet normal -0.0865425 -0.069166 0.993844 + outer loop + vertex -755.621 180.526 36.8108 + vertex -748.243 186.34 37.8579 + vertex -755.438 190.188 37.4991 + endloop + endfacet + facet normal -0.0669672 -0.0696421 0.995322 + outer loop + vertex -755.621 180.526 36.8108 + vertex -755.438 190.188 37.4991 + vertex -762.817 184.335 36.5932 + endloop + endfacet + facet normal -0.0677269 -0.0686866 0.995337 + outer loop + vertex -762.817 184.335 36.5932 + vertex -755.438 190.188 37.4991 + vertex -762.404 193.681 37.2662 + endloop + endfacet + facet normal -0.0549078 -0.0693064 0.996083 + outer loop + vertex -762.817 184.335 36.5932 + vertex -762.404 193.681 37.2662 + vertex -769.704 188.041 36.4714 + endloop + endfacet + facet normal -0.0557708 -0.0681934 0.996112 + outer loop + vertex -769.704 188.041 36.4714 + vertex -762.404 193.681 37.2662 + vertex -769.144 197.361 37.1408 + endloop + endfacet + facet normal -0.0478921 -0.068694 0.996488 + outer loop + vertex -769.704 188.041 36.4714 + vertex -769.144 197.361 37.1408 + vertex -776.221 191.948 36.4276 + endloop + endfacet + facet normal -0.0484737 -0.0679368 0.996511 + outer loop + vertex -776.221 191.948 36.4276 + vertex -769.144 197.361 37.1408 + vertex -775.766 201.244 37.0834 + endloop + endfacet + facet normal -0.0468852 -0.0680195 0.996582 + outer loop + vertex -776.221 191.948 36.4276 + vertex -775.766 201.244 37.0834 + vertex -782.735 196.017 36.3988 + endloop + endfacet + facet normal -0.0459089 -0.0693155 0.996538 + outer loop + vertex -782.735 196.017 36.3988 + vertex -775.766 201.244 37.0834 + vertex -782.315 205.358 37.0678 + endloop + endfacet + facet normal -0.0447923 -0.0693691 0.996585 + outer loop + vertex -782.735 196.017 36.3988 + vertex -782.315 205.358 37.0678 + vertex -789.232 200.438 36.4145 + endloop + endfacet + facet normal -0.042904 -0.0720104 0.996481 + outer loop + vertex -789.232 200.438 36.4145 + vertex -782.315 205.358 37.0678 + vertex -788.759 209.671 37.102 + endloop + endfacet + facet normal -0.0378537 -0.072283 0.996666 + outer loop + vertex -789.232 200.438 36.4145 + vertex -788.759 209.671 37.102 + vertex -795.603 205.062 36.5079 + endloop + endfacet + facet normal -0.0358616 -0.0752224 0.996522 + outer loop + vertex -795.603 205.062 36.5079 + vertex -788.759 209.671 37.102 + vertex -795.017 214.244 37.222 + endloop + endfacet + facet normal -0.0242147 -0.0759874 0.996815 + outer loop + vertex -795.603 205.062 36.5079 + vertex -795.017 214.244 37.222 + vertex -801.805 209.961 36.7306 + endloop + endfacet + facet normal -0.0210114 -0.0810265 0.99649 + outer loop + vertex -801.805 209.961 36.7306 + vertex -795.017 214.244 37.222 + vertex -801.012 218.934 37.477 + endloop + endfacet + facet normal -0.00154198 -0.0827551 0.996569 + outer loop + vertex -801.805 209.961 36.7306 + vertex -801.012 218.934 37.477 + vertex -807.437 214.844 37.1274 + endloop + endfacet + facet normal 0.00269495 -0.0893623 0.995996 + outer loop + vertex -807.437 214.844 37.1274 + vertex -801.012 218.934 37.477 + vertex -806.699 223.582 37.9095 + endloop + endfacet + facet normal 0.026193 -0.0913002 0.995479 + outer loop + vertex -807.437 214.844 37.1274 + vertex -806.699 223.582 37.9095 + vertex -812.4 219.043 37.6431 + endloop + endfacet + facet normal 0.0375364 -0.105443 0.993717 + outer loop + vertex -812.4 219.043 37.6431 + vertex -806.699 223.582 37.9095 + vertex -812.641 227.905 38.5926 + endloop + endfacet + facet normal 0.0502439 -0.105042 0.993198 + outer loop + vertex -812.4 219.043 37.6431 + vertex -812.641 227.905 38.5926 + vertex -816.814 221.553 38.1318 + endloop + endfacet + facet normal 0.0963309 -0.134809 0.986178 + outer loop + vertex -818.309 226.504 38.9546 + vertex -816.814 221.553 38.1318 + vertex -812.641 227.905 38.5926 + endloop + endfacet + facet normal 0.0899739 -0.108093 0.990061 + outer loop + vertex -816.669 233.964 39.6202 + vertex -818.309 226.504 38.9546 + vertex -812.641 227.905 38.5926 + endloop + endfacet + facet normal 0.131933 -0.116802 0.984353 + outer loop + vertex -818.309 226.504 38.9546 + vertex -816.669 233.964 39.6202 + vertex -821.099 230.441 39.7959 + endloop + endfacet + facet normal 0.138419 -0.125053 0.982447 + outer loop + vertex -821.099 230.441 39.7959 + vertex -816.669 233.964 39.6202 + vertex -820.534 237.607 40.6284 + endloop + endfacet + facet normal 0.158503 -0.126267 0.979251 + outer loop + vertex -821.099 230.441 39.7959 + vertex -820.534 237.607 40.6284 + vertex -823.995 233.193 40.6194 + endloop + endfacet + facet normal 0.188539 -0.149798 0.970574 + outer loop + vertex -823.995 233.193 40.6194 + vertex -820.534 237.607 40.6284 + vertex -823.699 238.587 41.3944 + endloop + endfacet + facet normal 0.1871 -0.14976 0.970858 + outer loop + vertex -823.995 233.193 40.6194 + vertex -823.699 238.587 41.3944 + vertex -826.538 235.418 41.4526 + endloop + endfacet + facet normal 0.212358 -0.172551 0.961837 + outer loop + vertex -826.538 235.418 41.4526 + vertex -823.699 238.587 41.3944 + vertex -825.862 240.84 42.2763 + endloop + endfacet + facet normal 0.228198 -0.173933 0.957952 + outer loop + vertex -826.538 235.418 41.4526 + vertex -825.862 240.84 42.2763 + vertex -828.825 237.491 42.3739 + endloop + endfacet + facet normal 0.272175 -0.213405 0.938285 + outer loop + vertex -828.825 237.491 42.3739 + vertex -825.862 240.84 42.2763 + vertex -828.291 241.497 43.1303 + endloop + endfacet + facet normal 0.259504 -0.212435 0.942088 + outer loop + vertex -828.825 237.491 42.3739 + vertex -828.291 241.497 43.1303 + vertex -830.897 239.7 43.4428 + endloop + endfacet + facet normal 0.260132 -0.213414 0.941693 + outer loop + vertex -830.897 239.7 43.4428 + vertex -828.291 241.497 43.1303 + vertex -829.695 244.23 44.1374 + endloop + endfacet + facet normal 0.319268 -0.225831 0.920363 + outer loop + vertex -830.897 239.7 43.4428 + vertex -829.695 244.23 44.1374 + vertex -832.74 242.255 44.7088 + endloop + endfacet + facet normal 0.321235 -0.229309 0.918817 + outer loop + vertex -832.74 242.255 44.7088 + vertex -829.695 244.23 44.1374 + vertex -831.489 246.852 45.4191 + endloop + endfacet + facet normal 0.394885 -0.244215 0.885678 + outer loop + vertex -832.74 242.255 44.7088 + vertex -831.489 246.852 45.4191 + vertex -834.269 244.616 46.0419 + endloop + endfacet + facet normal 0.397219 -0.247676 0.88367 + outer loop + vertex -834.269 244.616 46.0419 + vertex -831.489 246.852 45.4191 + vertex -833.142 248.882 46.731 + endloop + endfacet + facet normal 0.45324 -0.257579 0.853362 + outer loop + vertex -834.269 244.616 46.0419 + vertex -833.142 248.882 46.731 + vertex -835.479 246.477 47.2466 + endloop + endfacet + facet normal 0.45468 -0.259252 0.852088 + outer loop + vertex -835.479 246.477 47.2466 + vertex -833.142 248.882 46.731 + vertex -834.576 250.434 47.9682 + endloop + endfacet + facet normal 0.475893 -0.261825 0.839627 + outer loop + vertex -835.479 246.477 47.2466 + vertex -834.576 250.434 47.9682 + vertex -836.601 247.659 48.2509 + endloop + endfacet + facet normal 0.491294 -0.274389 0.826644 + outer loop + vertex -834.576 250.434 47.9682 + vertex -836.029 251.289 49.1157 + vertex -836.601 247.659 48.2509 + endloop + endfacet + facet normal 0.4664 -0.27391 0.841097 + outer loop + vertex -837.559 247.934 48.8717 + vertex -836.601 247.659 48.2509 + vertex -836.029 251.289 49.1157 + endloop + endfacet + facet normal 0.502118 -0.288328 0.815319 + outer loop + vertex -837.559 247.934 48.8717 + vertex -836.029 251.289 49.1157 + vertex -837.862 248.936 49.4124 + endloop + endfacet + facet normal 0.500332 -0.286726 0.81698 + outer loop + vertex -836.029 251.289 49.1157 + vertex -836.845 252.658 50.0956 + vertex -837.862 248.936 49.4124 + endloop + endfacet + facet normal 0.496358 -0.286123 0.819611 + outer loop + vertex -838.38 249.064 49.7706 + vertex -837.862 248.936 49.4124 + vertex -836.845 252.658 50.0956 + endloop + endfacet + facet normal 0.572777 -0.313148 0.757539 + outer loop + vertex -838.38 249.064 49.7706 + vertex -836.845 252.658 50.0956 + vertex -838.285 250.073 50.1167 + endloop + endfacet + facet normal 0.551309 -0.301011 0.778107 + outer loop + vertex -836.845 252.658 50.0956 + vertex -837.017 254.105 50.7774 + vertex -838.285 250.073 50.1167 + endloop + endfacet + facet normal 0.63722 -0.315745 0.703033 + outer loop + vertex -838.462 250.122 50.2989 + vertex -838.285 250.073 50.1167 + vertex -837.017 254.105 50.7774 + endloop + endfacet + facet normal 0.0525541 -0.148253 0.987552 + outer loop + vertex -820.062 222.545 38.4536 + vertex -816.814 221.553 38.1318 + vertex -818.309 226.504 38.9546 + endloop + endfacet + facet normal 0.0718889 -0.156499 0.985058 + outer loop + vertex -820.062 222.545 38.4536 + vertex -818.309 226.504 38.9546 + vertex -822.094 225.309 39.0411 + endloop + endfacet + facet normal 0.0726336 -0.158891 0.984621 + outer loop + vertex -822.094 225.309 39.0411 + vertex -818.309 226.504 38.9546 + vertex -821.099 230.441 39.7959 + endloop + endfacet + facet normal 0.0901424 -0.161996 0.982666 + outer loop + vertex -822.094 225.309 39.0411 + vertex -821.099 230.441 39.7959 + vertex -824.689 228.258 39.7654 + endloop + endfacet + facet normal 0.1034 -0.183731 0.977523 + outer loop + vertex -824.689 228.258 39.7654 + vertex -821.099 230.441 39.7959 + vertex -823.995 233.193 40.6194 + endloop + endfacet + facet normal 0.111672 -0.184706 0.976429 + outer loop + vertex -824.689 228.258 39.7654 + vertex -823.995 233.193 40.6194 + vertex -827.276 230.857 40.5528 + endloop + endfacet + facet normal 0.131506 -0.212338 0.968307 + outer loop + vertex -827.276 230.857 40.5528 + vertex -823.995 233.193 40.6194 + vertex -826.538 235.418 41.4526 + endloop + endfacet + facet normal 0.139524 -0.213369 0.966957 + outer loop + vertex -827.276 230.857 40.5528 + vertex -826.538 235.418 41.4526 + vertex -829.674 233.274 41.4321 + endloop + endfacet + facet normal 0.161926 -0.246034 0.95564 + outer loop + vertex -829.674 233.274 41.4321 + vertex -826.538 235.418 41.4526 + vertex -828.825 237.491 42.3739 + endloop + endfacet + facet normal 0.170804 -0.247397 0.95374 + outer loop + vertex -829.674 233.274 41.4321 + vertex -828.825 237.491 42.3739 + vertex -831.962 235.771 42.4897 + endloop + endfacet + facet normal 0.187878 -0.279366 0.941624 + outer loop + vertex -831.962 235.771 42.4897 + vertex -828.825 237.491 42.3739 + vertex -830.897 239.7 43.4428 + endloop + endfacet + facet normal 0.210133 -0.283924 0.935538 + outer loop + vertex -831.962 235.771 42.4897 + vertex -830.897 239.7 43.4428 + vertex -834.143 238.419 43.7832 + endloop + endfacet + facet normal 0.216987 -0.303335 0.927849 + outer loop + vertex -834.143 238.419 43.7832 + vertex -830.897 239.7 43.4428 + vertex -832.74 242.255 44.7088 + endloop + endfacet + facet normal 0.27827 -0.320364 0.905502 + outer loop + vertex -834.143 238.419 43.7832 + vertex -832.74 242.255 44.7088 + vertex -836.048 241.111 45.3209 + endloop + endfacet + facet normal 0.280238 -0.327813 0.902222 + outer loop + vertex -836.048 241.111 45.3209 + vertex -832.74 242.255 44.7088 + vertex -834.269 244.616 46.0419 + endloop + endfacet + facet normal -0.0254561 -0.0459589 0.998619 + outer loop + vertex -782.315 205.358 37.0678 + vertex -781.318 216.758 37.6179 + vertex -788.759 209.671 37.102 + endloop + endfacet + facet normal -0.0244746 -0.0469877 0.998596 + outer loop + vertex -788.759 209.671 37.102 + vertex -781.318 216.758 37.6179 + vertex -787.716 220.979 37.6597 + endloop + endfacet + facet normal -0.0157772 -0.0477965 0.998732 + outer loop + vertex -788.759 209.671 37.102 + vertex -787.716 220.979 37.6597 + vertex -795.017 214.244 37.222 + endloop + endfacet + facet normal -0.0140514 -0.049663 0.998667 + outer loop + vertex -795.017 214.244 37.222 + vertex -787.716 220.979 37.6597 + vertex -793.932 225.372 37.7907 + endloop + endfacet + facet normal 0.00236599 -0.0512652 0.998682 + outer loop + vertex -795.017 214.244 37.222 + vertex -793.932 225.372 37.7907 + vertex -801.012 218.934 37.477 + endloop + endfacet + facet normal 0.00421096 -0.0532887 0.99857 + outer loop + vertex -801.012 218.934 37.477 + vertex -793.932 225.372 37.7907 + vertex -799.915 229.933 38.0593 + endloop + endfacet + facet normal 0.0302345 -0.0558532 0.997981 + outer loop + vertex -801.012 218.934 37.477 + vertex -799.915 229.933 38.0593 + vertex -806.699 223.582 37.9095 + endloop + endfacet + facet normal 0.0338456 -0.0597029 0.997642 + outer loop + vertex -806.699 223.582 37.9095 + vertex -799.915 229.933 38.0593 + vertex -805.685 234.563 38.5322 + endloop + endfacet + facet normal 0.0687695 -0.0628155 0.995653 + outer loop + vertex -806.699 223.582 37.9095 + vertex -805.685 234.563 38.5322 + vertex -812.641 227.905 38.5926 + endloop + endfacet + facet normal 0.0755764 -0.069935 0.994685 + outer loop + vertex -812.641 227.905 38.5926 + vertex -805.685 234.563 38.5322 + vertex -810.969 239.428 39.2756 + endloop + endfacet + facet normal 0.134541 -0.0780858 0.987827 + outer loop + vertex -812.641 227.905 38.5926 + vertex -810.969 239.428 39.2756 + vertex -816.669 233.964 39.6202 + endloop + endfacet + facet normal 0.13606 -0.0796914 0.98749 + outer loop + vertex -816.669 233.964 39.6202 + vertex -810.969 239.428 39.2756 + vertex -815.849 243.935 40.3118 + endloop + endfacet + facet normal 0.177899 -0.0826539 0.980571 + outer loop + vertex -816.669 233.964 39.6202 + vertex -815.849 243.935 40.3118 + vertex -820.534 237.607 40.6284 + endloop + endfacet + facet normal 0.206571 -0.104266 0.97286 + outer loop + vertex -815.849 243.935 40.3118 + vertex -821.51 246.993 41.8415 + vertex -820.534 237.607 40.6284 + endloop + endfacet + facet normal 0.203211 -0.104701 0.973521 + outer loop + vertex -823.699 238.587 41.3944 + vertex -820.534 237.607 40.6284 + vertex -821.51 246.993 41.8415 + endloop + endfacet + facet normal 0.16257 -0.0505078 0.985404 + outer loop + vertex -810.969 239.428 39.2756 + vertex -809.657 251.115 39.6584 + vertex -815.849 243.935 40.3118 + endloop + endfacet + facet normal 0.168706 -0.05592 0.984079 + outer loop + vertex -815.849 243.935 40.3118 + vertex -809.657 251.115 39.6584 + vertex -814.821 255.408 40.7875 + endloop + endfacet + facet normal 0.183145 -0.0380989 0.982347 + outer loop + vertex -809.657 251.115 39.6584 + vertex -808.049 263 39.8195 + vertex -814.821 255.408 40.7875 + endloop + endfacet + facet normal 0.188007 -0.0425754 0.981245 + outer loop + vertex -814.821 255.408 40.7875 + vertex -808.049 263 39.8195 + vertex -813.103 267.334 40.9758 + endloop + endfacet + facet normal 0.193196 -0.0363216 0.980488 + outer loop + vertex -808.049 263 39.8195 + vertex -805.985 274.65 39.8443 + vertex -813.103 267.334 40.9758 + endloop + endfacet + facet normal 0.197298 -0.0404636 0.979508 + outer loop + vertex -813.103 267.334 40.9758 + vertex -805.985 274.65 39.8443 + vertex -811.015 278.742 41.0266 + endloop + endfacet + facet normal 0.197405 -0.0403266 0.979492 + outer loop + vertex -805.985 274.65 39.8443 + vertex -803.541 285.837 39.8124 + vertex -811.015 278.742 41.0266 + endloop + endfacet + facet normal 0.199629 -0.042764 0.978938 + outer loop + vertex -811.015 278.742 41.0266 + vertex -803.541 285.837 39.8124 + vertex -808.566 289.646 41.0035 + endloop + endfacet + facet normal 0.196684 -0.0467769 0.97935 + outer loop + vertex -803.541 285.837 39.8124 + vertex -800.803 296.574 39.7753 + vertex -808.566 289.646 41.0035 + endloop + endfacet + facet normal 0.198907 -0.0493692 0.978774 + outer loop + vertex -808.566 289.646 41.0035 + vertex -800.803 296.574 39.7753 + vertex -805.798 300.054 40.966 + endloop + endfacet + facet normal 0.196252 -0.0532916 0.979104 + outer loop + vertex -800.803 296.574 39.7753 + vertex -797.869 306.935 39.7512 + vertex -805.798 300.054 40.966 + endloop + endfacet + facet normal 0.198321 -0.0557737 0.978549 + outer loop + vertex -805.798 300.054 40.966 + vertex -797.869 306.935 39.7512 + vertex -802.83 310.054 40.9344 + endloop + endfacet + facet normal 0.196341 -0.0590022 0.978759 + outer loop + vertex -797.869 306.935 39.7512 + vertex -794.806 317.016 39.7444 + vertex -802.83 310.054 40.9344 + endloop + endfacet + facet normal 0.199029 -0.0622283 0.978016 + outer loop + vertex -802.83 310.054 40.9344 + vertex -794.806 317.016 39.7444 + vertex -799.728 319.76 40.9206 + endloop + endfacet + facet normal 0.198221 -0.0637069 0.978085 + outer loop + vertex -794.806 317.016 39.7444 + vertex -791.647 326.903 39.7482 + vertex -799.728 319.76 40.9206 + endloop + endfacet + facet normal 0.203015 -0.0693544 0.976716 + outer loop + vertex -799.728 319.76 40.9206 + vertex -791.647 326.903 39.7482 + vertex -796.52 329.269 40.929 + endloop + endfacet + facet normal 0.203151 -0.069071 0.976708 + outer loop + vertex -791.647 326.903 39.7482 + vertex -788.401 336.665 39.7634 + vertex -796.52 329.269 40.929 + endloop + endfacet + facet normal 0.207112 -0.0736028 0.975545 + outer loop + vertex -796.52 329.269 40.929 + vertex -788.401 336.665 39.7634 + vertex -793.23 338.64 40.9376 + endloop + endfacet + facet normal 0.207819 -0.0718624 0.975524 + outer loop + vertex -788.401 336.665 39.7634 + vertex -785.084 346.348 39.77 + vertex -793.23 338.64 40.9376 + endloop + endfacet + facet normal 0.211884 -0.0763426 0.974309 + outer loop + vertex -793.23 338.64 40.9376 + vertex -785.084 346.348 39.77 + vertex -789.863 347.915 40.9321 + endloop + endfacet + facet normal 0.213275 -0.0721141 0.974327 + outer loop + vertex -785.084 346.348 39.77 + vertex -781.708 356.004 39.7457 + vertex -789.863 347.915 40.9321 + endloop + endfacet + facet normal 0.216552 -0.0755623 0.973342 + outer loop + vertex -789.863 347.915 40.9321 + vertex -781.708 356.004 39.7457 + vertex -786.44 357.147 40.8873 + endloop + endfacet + facet normal 0.217931 -0.069964 0.973453 + outer loop + vertex -781.708 356.004 39.7457 + vertex -778.325 365.686 39.6842 + vertex -786.44 357.147 40.8873 + endloop + endfacet + facet normal 0.221983 -0.0739856 0.97224 + outer loop + vertex -786.44 357.147 40.8873 + vertex -778.325 365.686 39.6842 + vertex -783.035 366.383 40.8126 + endloop + endfacet + facet normal 0.222606 -0.0700144 0.972391 + outer loop + vertex -778.325 365.686 39.6842 + vertex -775.154 375.442 39.6607 + vertex -783.035 366.383 40.8126 + endloop + endfacet + facet normal 0.240111 -0.085936 0.966934 + outer loop + vertex -783.035 366.383 40.8126 + vertex -775.154 375.442 39.6607 + vertex -779.846 375.725 40.8511 + endloop + endfacet + facet normal 0.241097 -0.0730416 0.967749 + outer loop + vertex -775.154 375.442 39.6607 + vertex -772.465 385.352 39.7387 + vertex -779.846 375.725 40.8511 + endloop + endfacet + facet normal 0.24056 -0.0726108 0.967915 + outer loop + vertex -779.846 375.725 40.8511 + vertex -772.465 385.352 39.7387 + vertex -777.328 385.236 40.9389 + endloop + endfacet + facet normal 0.10182 -0.0413137 0.993945 + outer loop + vertex -805.685 234.563 38.5322 + vertex -804.283 246.595 38.8887 + vertex -810.969 239.428 39.2756 + endloop + endfacet + facet normal 0.105011 -0.044315 0.993483 + outer loop + vertex -810.969 239.428 39.2756 + vertex -804.283 246.595 38.8887 + vertex -809.657 251.115 39.6584 + endloop + endfacet + facet normal 0.119112 -0.0273797 0.992503 + outer loop + vertex -804.283 246.595 38.8887 + vertex -802.645 258.705 39.0262 + vertex -809.657 251.115 39.6584 + endloop + endfacet + facet normal 0.121842 -0.0299353 0.992098 + outer loop + vertex -809.657 251.115 39.6584 + vertex -802.645 258.705 39.0262 + vertex -808.049 263 39.8195 + endloop + endfacet + facet normal 0.127381 -0.0228723 0.99159 + outer loop + vertex -802.645 258.705 39.0262 + vertex -800.63 270.564 39.0409 + vertex -808.049 263 39.8195 + endloop + endfacet + facet normal 0.129589 -0.0250733 0.991251 + outer loop + vertex -808.049 263 39.8195 + vertex -800.63 270.564 39.0409 + vertex -805.985 274.65 39.8443 + endloop + endfacet + facet normal 0.129851 -0.024725 0.991225 + outer loop + vertex -800.63 270.564 39.0409 + vertex -798.235 282.027 39.013 + vertex -805.985 274.65 39.8443 + endloop + endfacet + facet normal 0.130808 -0.0257475 0.991073 + outer loop + vertex -805.985 274.65 39.8443 + vertex -798.235 282.027 39.013 + vertex -803.541 285.837 39.8124 + endloop + endfacet + facet normal 0.128436 -0.0290983 0.991291 + outer loop + vertex -798.235 282.027 39.013 + vertex -795.546 293.086 38.9893 + vertex -803.541 285.837 39.8124 + endloop + endfacet + facet normal 0.128705 -0.0294 0.991247 + outer loop + vertex -803.541 285.837 39.8124 + vertex -795.546 293.086 38.9893 + vertex -800.803 296.574 39.7753 + endloop + endfacet + facet normal 0.126188 -0.0332391 0.991449 + outer loop + vertex -795.546 293.086 38.9893 + vertex -792.666 303.805 38.9821 + vertex -800.803 296.574 39.7753 + endloop + endfacet + facet normal 0.126402 -0.0334841 0.991414 + outer loop + vertex -800.803 296.574 39.7753 + vertex -792.666 303.805 38.9821 + vertex -797.869 306.935 39.7512 + endloop + endfacet + facet normal 0.124913 -0.0359851 0.991515 + outer loop + vertex -792.666 303.805 38.9821 + vertex -789.665 314.259 38.9834 + vertex -797.869 306.935 39.7512 + endloop + endfacet + facet normal 0.126477 -0.0377653 0.99125 + outer loop + vertex -797.869 306.935 39.7512 + vertex -789.665 314.259 38.9834 + vertex -794.806 317.016 39.7444 + endloop + endfacet + facet normal 0.126007 -0.0386484 0.991276 + outer loop + vertex -789.665 314.259 38.9834 + vertex -786.568 324.527 38.9901 + vertex -794.806 317.016 39.7444 + endloop + endfacet + facet normal 0.128513 -0.0414397 0.990842 + outer loop + vertex -794.806 317.016 39.7444 + vertex -786.568 324.527 38.9901 + vertex -791.647 326.903 39.7482 + endloop + endfacet + facet normal 0.128646 -0.0411533 0.990836 + outer loop + vertex -786.568 324.527 38.9901 + vertex -783.39 334.672 38.9988 + vertex -791.647 326.903 39.7482 + endloop + endfacet + facet normal 0.132878 -0.0457249 0.990077 + outer loop + vertex -791.647 326.903 39.7482 + vertex -783.39 334.672 38.9988 + vertex -788.401 336.665 39.7634 + endloop + endfacet + facet normal 0.133447 -0.0442915 0.990066 + outer loop + vertex -783.39 334.672 38.9988 + vertex -780.138 344.754 39.0116 + vertex -788.401 336.665 39.7634 + endloop + endfacet + facet normal 0.136462 -0.0474236 0.98951 + outer loop + vertex -788.401 336.665 39.7634 + vertex -780.138 344.754 39.0116 + vertex -785.084 346.348 39.77 + endloop + endfacet + facet normal 0.13727 -0.0449199 0.989515 + outer loop + vertex -780.138 344.754 39.0116 + vertex -776.832 354.823 39.01 + vertex -785.084 346.348 39.77 + endloop + endfacet + facet normal 0.138183 -0.0458244 0.989346 + outer loop + vertex -785.084 346.348 39.77 + vertex -776.832 354.823 39.01 + vertex -781.708 356.004 39.7457 + endloop + endfacet + facet normal 0.139151 -0.0418514 0.989386 + outer loop + vertex -776.832 354.823 39.01 + vertex -773.507 364.923 38.9696 + vertex -781.708 356.004 39.7457 + endloop + endfacet + facet normal 0.139978 -0.0426245 0.989237 + outer loop + vertex -781.708 356.004 39.7457 + vertex -773.507 364.923 38.9696 + vertex -778.325 365.686 39.6842 + endloop + endfacet + facet normal 0.140399 -0.0400142 0.989286 + outer loop + vertex -773.507 364.923 38.9696 + vertex -770.383 375.127 38.939 + vertex -778.325 365.686 39.6842 + endloop + endfacet + facet normal 0.146513 -0.0452455 0.988173 + outer loop + vertex -778.325 365.686 39.6842 + vertex -770.383 375.127 38.939 + vertex -775.154 375.442 39.6607 + endloop + endfacet + facet normal 0.146774 -0.0415744 0.988296 + outer loop + vertex -770.383 375.127 38.939 + vertex -768.045 385.454 39.0261 + vertex -775.154 375.442 39.6607 + endloop + endfacet + facet normal 0.160117 -0.0512085 0.985769 + outer loop + vertex -775.154 375.442 39.6607 + vertex -768.045 385.454 39.0261 + vertex -772.465 385.352 39.7387 + endloop + endfacet + facet normal 0.0762552 -0.0220155 0.996845 + outer loop + vertex -792.666 303.805 38.9821 + vertex -784.333 311.564 38.516 + vertex -789.665 314.259 38.9834 + endloop + endfacet + facet normal 0.0759321 -0.0226565 0.996856 + outer loop + vertex -784.333 311.564 38.516 + vertex -781.313 322.212 38.528 + vertex -789.665 314.259 38.9834 + endloop + endfacet + facet normal 0.0771188 -0.0239097 0.996735 + outer loop + vertex -789.665 314.259 38.9834 + vertex -781.313 322.212 38.528 + vertex -786.568 324.527 38.9901 + endloop + endfacet + facet normal 0.0773827 -0.0233095 0.996729 + outer loop + vertex -781.313 322.212 38.528 + vertex -778.217 332.735 38.5337 + vertex -786.568 324.527 38.9901 + endloop + endfacet + facet normal 0.0799003 -0.0258858 0.996467 + outer loop + vertex -786.568 324.527 38.9901 + vertex -778.217 332.735 38.5337 + vertex -783.39 334.672 38.9988 + endloop + endfacet + facet normal 0.080232 -0.0249988 0.996463 + outer loop + vertex -778.217 332.735 38.5337 + vertex -775.051 343.201 38.5414 + vertex -783.39 334.672 38.9988 + endloop + endfacet + facet normal 0.0834665 -0.0281799 0.996112 + outer loop + vertex -783.39 334.672 38.9988 + vertex -775.051 343.201 38.5414 + vertex -780.138 344.754 39.0116 + endloop + endfacet + facet normal 0.0840103 -0.0263989 0.996115 + outer loop + vertex -775.051 343.201 38.5414 + vertex -771.834 353.664 38.5473 + vertex -780.138 344.754 39.0116 + endloop + endfacet + facet normal 0.0857009 -0.0279843 0.995928 + outer loop + vertex -780.138 344.754 39.0116 + vertex -771.834 353.664 38.5473 + vertex -776.832 354.823 39.01 + endloop + endfacet + facet normal 0.08624 -0.0256663 0.995944 + outer loop + vertex -771.834 353.664 38.5473 + vertex -768.604 364.182 38.5387 + vertex -776.832 354.823 39.01 + endloop + endfacet + facet normal 0.0839766 -0.0236641 0.996187 + outer loop + vertex -776.832 354.823 39.01 + vertex -768.604 364.182 38.5387 + vertex -773.507 364.923 38.9696 + endloop + endfacet + facet normal 0.0842589 -0.0218078 0.996205 + outer loop + vertex -768.604 364.182 38.5387 + vertex -765.537 374.793 38.5116 + vertex -773.507 364.923 38.9696 + endloop + endfacet + facet normal 0.0862318 -0.0234106 0.996 + outer loop + vertex -773.507 364.923 38.9696 + vertex -765.537 374.793 38.5116 + vertex -770.383 375.127 38.939 + endloop + endfacet + facet normal 0.0863372 -0.0219138 0.996025 + outer loop + vertex -765.537 374.793 38.5116 + vertex -762.992 385.567 38.528 + vertex -770.383 375.127 38.939 + endloop + endfacet + facet normal 0.0987432 -0.0307515 0.994638 + outer loop + vertex -770.383 375.127 38.939 + vertex -762.992 385.567 38.528 + vertex -768.045 385.454 39.0261 + endloop + endfacet + facet normal 0.0531939 -0.0140881 0.998485 + outer loop + vertex -765.537 374.793 38.5116 + vertex -758.394 385.668 38.2845 + vertex -762.992 385.567 38.528 + endloop + endfacet + facet normal 0.047217 -0.0101549 0.998833 + outer loop + vertex -760.685 374.485 38.2791 + vertex -758.394 385.668 38.2845 + vertex -765.537 374.793 38.5116 + endloop + endfacet + facet normal 0.0231208 -0.00521834 0.999719 + outer loop + vertex -760.685 374.485 38.2791 + vertex -753.509 385.774 38.1721 + vertex -758.394 385.668 38.2845 + endloop + endfacet + facet normal 0.0245547 -0.00613022 0.99968 + outer loop + vertex -755.822 374.193 38.1578 + vertex -753.509 385.774 38.1721 + vertex -760.685 374.485 38.2791 + endloop + endfacet + facet normal 0.0245462 -0.00627283 0.999679 + outer loop + vertex -763.629 363.466 38.2822 + vertex -755.822 374.193 38.1578 + vertex -760.685 374.485 38.2791 + endloop + endfacet + facet normal 0.0496149 -0.0129714 0.998684 + outer loop + vertex -763.629 363.466 38.2822 + vertex -760.685 374.485 38.2791 + vertex -768.604 364.182 38.5387 + endloop + endfacet + facet normal 0.0261698 -0.00745509 0.99963 + outer loop + vertex -758.632 362.782 38.1463 + vertex -755.822 374.193 38.1578 + vertex -763.629 363.466 38.2822 + endloop + endfacet + facet normal 0.0261405 -0.0076685 0.999629 + outer loop + vertex -766.745 352.563 38.2801 + vertex -758.632 362.782 38.1463 + vertex -763.629 363.466 38.2822 + endloop + endfacet + facet normal 0.0493537 -0.0143029 0.998679 + outer loop + vertex -766.745 352.563 38.2801 + vertex -763.629 363.466 38.2822 + vertex -771.834 353.664 38.5473 + endloop + endfacet + facet normal 0.0254467 -0.00711734 0.999651 + outer loop + vertex -761.611 351.503 38.1418 + vertex -758.632 362.782 38.1463 + vertex -766.745 352.563 38.2801 + endloop + endfacet + facet normal 0.0253022 -0.00781723 0.999649 + outer loop + vertex -769.852 341.713 38.2739 + vertex -761.611 351.503 38.1418 + vertex -766.745 352.563 38.2801 + endloop + endfacet + facet normal 0.0473475 -0.0141292 0.998779 + outer loop + vertex -769.852 341.713 38.2739 + vertex -766.745 352.563 38.2801 + vertex -775.051 343.201 38.5414 + endloop + endfacet + facet normal 0.0239673 -0.00669306 0.99969 + outer loop + vertex -764.583 340.273 38.1379 + vertex -761.611 351.503 38.1418 + vertex -769.852 341.713 38.2739 + endloop + endfacet + facet normal 0.0238676 -0.0070581 0.99969 + outer loop + vertex -772.912 330.869 38.2704 + vertex -764.583 340.273 38.1379 + vertex -769.852 341.713 38.2739 + endloop + endfacet + facet normal 0.0450055 -0.0130231 0.998902 + outer loop + vertex -772.912 330.869 38.2704 + vertex -769.852 341.713 38.2739 + vertex -778.217 332.735 38.5337 + endloop + endfacet + facet normal 0.0228982 -0.0061991 0.999719 + outer loop + vertex -767.516 329.05 38.1355 + vertex -764.583 340.273 38.1379 + vertex -772.912 330.869 38.2704 + endloop + endfacet + facet normal 0.0226961 -0.00679853 0.999719 + outer loop + vertex -775.91 319.964 38.2643 + vertex -767.516 329.05 38.1355 + vertex -772.912 330.869 38.2704 + endloop + endfacet + facet normal 0.0435466 -0.0125304 0.998973 + outer loop + vertex -775.91 319.964 38.2643 + vertex -772.912 330.869 38.2704 + vertex -781.313 322.212 38.528 + endloop + endfacet + facet normal 0.0215576 -0.00574622 0.999751 + outer loop + vertex -770.391 317.782 38.1327 + vertex -767.516 329.05 38.1355 + vertex -775.91 319.964 38.2643 + endloop + endfacet + facet normal 0.0213315 -0.00631812 0.999752 + outer loop + vertex -778.83 308.957 38.257 + vertex -770.391 317.782 38.1327 + vertex -775.91 319.964 38.2643 + endloop + endfacet + facet normal 0.0414952 -0.0116663 0.999071 + outer loop + vertex -778.83 308.957 38.257 + vertex -775.91 319.964 38.2643 + vertex -784.333 311.564 38.516 + endloop + endfacet + facet normal 0.0414374 -0.0117883 0.999072 + outer loop + vertex -787.255 300.747 38.5096 + vertex -778.83 308.957 38.257 + vertex -784.333 311.564 38.516 + endloop + endfacet + facet normal 0.0409495 -0.0112867 0.999097 + outer loop + vertex -781.66 297.784 38.2468 + vertex -778.83 308.957 38.257 + vertex -787.255 300.747 38.5096 + endloop + endfacet + facet normal 0.0414074 -0.010421 0.999088 + outer loop + vertex -790.055 289.683 38.5102 + vertex -781.66 297.784 38.2468 + vertex -787.255 300.747 38.5096 + endloop + endfacet + facet normal 0.0752229 -0.0189785 0.996986 + outer loop + vertex -790.055 289.683 38.5102 + vertex -787.255 300.747 38.5096 + vertex -795.546 293.086 38.9893 + endloop + endfacet + facet normal 0.0409909 -0.00998868 0.99911 + outer loop + vertex -784.365 286.386 38.2438 + vertex -781.66 297.784 38.2468 + vertex -790.055 289.683 38.5102 + endloop + endfacet + facet normal 0.0419041 -0.00841087 0.999086 + outer loop + vertex -792.668 278.308 38.524 + vertex -784.365 286.386 38.2438 + vertex -790.055 289.683 38.5102 + endloop + endfacet + facet normal 0.0766215 -0.0163881 0.996926 + outer loop + vertex -792.668 278.308 38.524 + vertex -790.055 289.683 38.5102 + vertex -798.235 282.027 39.013 + endloop + endfacet + facet normal 0.0416419 -0.00814093 0.999099 + outer loop + vertex -786.885 274.701 38.2536 + vertex -784.365 286.386 38.2438 + vertex -792.668 278.308 38.524 + endloop + endfacet + facet normal 0.0426589 -0.00650837 0.999068 + outer loop + vertex -794.992 266.567 38.5468 + vertex -786.885 274.701 38.2536 + vertex -792.668 278.308 38.524 + endloop + endfacet + facet normal 0.0778134 -0.013472 0.996877 + outer loop + vertex -794.992 266.567 38.5468 + vertex -792.668 278.308 38.524 + vertex -800.63 270.564 39.0409 + endloop + endfacet + facet normal 0.0426669 -0.0065164 0.999068 + outer loop + vertex -789.134 262.675 38.2712 + vertex -786.885 274.701 38.2536 + vertex -794.992 266.567 38.5468 + endloop + endfacet + facet normal 0.0416766 -0.00800921 0.999099 + outer loop + vertex -796.967 254.447 38.532 + vertex -789.134 262.675 38.2712 + vertex -794.992 266.567 38.5468 + endloop + endfacet + facet normal 0.0765126 -0.013683 0.996975 + outer loop + vertex -796.967 254.447 38.532 + vertex -794.992 266.567 38.5468 + vertex -802.645 258.705 39.0262 + endloop + endfacet + facet normal 0.0410949 -0.00745448 0.999127 + outer loop + vertex -791.041 250.285 38.2572 + vertex -789.134 262.675 38.2712 + vertex -796.967 254.447 38.532 + endloop + endfacet + facet normal 0.0356267 -0.0152496 0.999249 + outer loop + vertex -798.593 242.069 38.4011 + vertex -791.041 250.285 38.2572 + vertex -796.967 254.447 38.532 + endloop + endfacet + facet normal 0.0697855 -0.0197168 0.997367 + outer loop + vertex -798.593 242.069 38.4011 + vertex -796.967 254.447 38.532 + vertex -804.283 246.595 38.8887 + endloop + endfacet + facet normal 0.0350023 -0.0146751 0.999279 + outer loop + vertex -792.612 237.681 38.1272 + vertex -791.041 250.285 38.2572 + vertex -798.593 242.069 38.4011 + endloop + endfacet + facet normal 0.0232658 -0.0306735 0.999259 + outer loop + vertex -799.915 229.933 38.0593 + vertex -792.612 237.681 38.1272 + vertex -798.593 242.069 38.4011 + endloop + endfacet + facet normal 0.0131491 -0.0119574 0.999842 + outer loop + vertex -792.612 237.681 38.1272 + vertex -784.896 246.261 38.1283 + vertex -791.041 250.285 38.2572 + endloop + endfacet + facet normal 0.018517 -0.00375954 0.999821 + outer loop + vertex -784.896 246.261 38.1283 + vertex -783.072 258.898 38.142 + vertex -791.041 250.285 38.2572 + endloop + endfacet + facet normal 0.00606842 -0.00196271 0.99998 + outer loop + vertex -784.896 246.261 38.1283 + vertex -776.841 255.252 38.0971 + vertex -783.072 258.898 38.142 + endloop + endfacet + facet normal 0.0074696 0.000431702 0.999972 + outer loop + vertex -776.841 255.252 38.0971 + vertex -774.805 267.807 38.0764 + vertex -783.072 258.898 38.142 + endloop + endfacet + facet normal 0.00777927 0.000144349 0.99997 + outer loop + vertex -783.072 258.898 38.142 + vertex -774.805 267.807 38.0764 + vertex -780.922 271.198 38.1235 + endloop + endfacet + facet normal 0.0200602 -0.00200197 0.999797 + outer loop + vertex -783.072 258.898 38.142 + vertex -780.922 271.198 38.1235 + vertex -789.134 262.675 38.2712 + endloop + endfacet + facet normal 0.00743024 -0.000485265 0.999972 + outer loop + vertex -774.805 267.807 38.0764 + vertex -772.509 280.079 38.0653 + vertex -780.922 271.198 38.1235 + endloop + endfacet + facet normal 0.00773149 -0.000770672 0.99997 + outer loop + vertex -780.922 271.198 38.1235 + vertex -772.509 280.079 38.0653 + vertex -778.506 283.184 38.1141 + endloop + endfacet + facet normal 0.0199197 -0.0032275 0.999796 + outer loop + vertex -780.922 271.198 38.1235 + vertex -778.506 283.184 38.1141 + vertex -786.885 274.701 38.2536 + endloop + endfacet + facet normal 0.0072293 -0.00174081 0.999972 + outer loop + vertex -772.509 280.079 38.0653 + vertex -770.039 292.116 38.0684 + vertex -778.506 283.184 38.1141 + endloop + endfacet + facet normal 0.00762399 -0.002115 0.999969 + outer loop + vertex -778.506 283.184 38.1141 + vertex -770.039 292.116 38.0684 + vertex -775.908 294.91 38.1191 + endloop + endfacet + facet normal 0.0195388 -0.00475476 0.999798 + outer loop + vertex -778.506 283.184 38.1141 + vertex -775.908 294.91 38.1191 + vertex -784.365 286.386 38.2438 + endloop + endfacet + facet normal 0.00755558 -0.00225872 0.999969 + outer loop + vertex -770.039 292.116 38.0684 + vertex -767.458 303.96 38.0757 + vertex -775.908 294.91 38.1191 + endloop + endfacet + facet normal 0.00778702 -0.00247484 0.999967 + outer loop + vertex -775.908 294.91 38.1191 + vertex -767.458 303.96 38.0757 + vertex -773.194 306.42 38.1264 + endloop + endfacet + facet normal 0.0195714 -0.00525354 0.999795 + outer loop + vertex -775.908 294.91 38.1191 + vertex -773.194 306.42 38.1264 + vertex -781.66 297.784 38.2468 + endloop + endfacet + facet normal 0.00788343 -0.00225003 0.999966 + outer loop + vertex -767.458 303.96 38.0757 + vertex -764.796 315.666 38.081 + vertex -773.194 306.42 38.1264 + endloop + endfacet + facet normal 0.00826017 -0.00259222 0.999963 + outer loop + vertex -773.194 306.42 38.1264 + vertex -764.796 315.666 38.081 + vertex -770.391 317.782 38.1327 + endloop + endfacet + facet normal 0.00844323 -0.00210828 0.999962 + outer loop + vertex -764.796 315.666 38.081 + vertex -762.068 327.285 38.0825 + vertex -770.391 317.782 38.1327 + endloop + endfacet + facet normal -0.000367043 -3.922e-05 1 + outer loop + vertex -764.796 315.666 38.081 + vertex -756.607 325.585 38.0844 + vertex -762.068 327.285 38.0825 + endloop + endfacet + facet normal -0.000333662 6.80663e-05 1 + outer loop + vertex -756.607 325.585 38.0844 + vertex -754.001 337.516 38.0845 + vertex -762.068 327.285 38.0825 + endloop + endfacet + facet normal -0.000304599 4.51528e-05 1 + outer loop + vertex -762.068 327.285 38.0825 + vertex -754.001 337.516 38.0845 + vertex -759.286 338.868 38.0828 + endloop + endfacet + facet normal 0.00901857 -0.00219367 0.999957 + outer loop + vertex -762.068 327.285 38.0825 + vertex -759.286 338.868 38.0828 + vertex -767.516 329.05 38.1355 + endloop + endfacet + facet normal -0.00029719 7.41121e-05 1 + outer loop + vertex -754.001 337.516 38.0845 + vertex -751.368 349.466 38.0844 + vertex -759.286 338.868 38.0828 + endloop + endfacet + facet normal -2.59139e-05 -0.000128578 1 + outer loop + vertex -759.286 338.868 38.0828 + vertex -751.368 349.466 38.0844 + vertex -756.471 350.465 38.0844 + endloop + endfacet + facet normal 0.00973862 -0.002499 0.999949 + outer loop + vertex -759.286 338.868 38.0828 + vertex -756.471 350.465 38.0844 + vertex -764.583 340.273 38.1379 + endloop + endfacet + facet normal -5.39799e-05 -0.000271972 1 + outer loop + vertex -751.368 349.466 38.0844 + vertex -748.744 361.484 38.0878 + vertex -756.471 350.465 38.0844 + endloop + endfacet + facet normal 0.000283136 -0.000508358 1 + outer loop + vertex -756.471 350.465 38.0844 + vertex -748.744 361.484 38.0878 + vertex -753.659 362.124 38.0895 + endloop + endfacet + facet normal 0.0105761 -0.0029912 0.99994 + outer loop + vertex -756.471 350.465 38.0844 + vertex -753.659 362.124 38.0895 + vertex -761.611 351.503 38.1418 + endloop + endfacet + facet normal 0.000183699 -0.00127251 0.999999 + outer loop + vertex -748.744 361.484 38.0878 + vertex -746.284 373.63 38.1028 + vertex -753.659 362.124 38.0895 + endloop + endfacet + facet normal 0.000499248 -0.00147476 0.999999 + outer loop + vertex -753.659 362.124 38.0895 + vertex -746.284 373.63 38.1028 + vertex -751.006 373.904 38.1055 + endloop + endfacet + facet normal 0.0109145 -0.0038201 0.999933 + outer loop + vertex -753.659 362.124 38.0895 + vertex -751.006 373.904 38.1055 + vertex -758.632 362.782 38.1463 + endloop + endfacet + facet normal 0.000373926 -0.00363261 0.999993 + outer loop + vertex -746.284 373.63 38.1028 + vertex -744.286 385.97 38.1469 + vertex -751.006 373.904 38.1055 + endloop + endfacet + facet normal -0.000117145 -0.0033591 0.999994 + outer loop + vertex -751.006 373.904 38.1055 + vertex -744.286 385.97 38.1469 + vertex -748.869 385.873 38.146 + endloop + endfacet + facet normal 0.010541 -0.00526152 0.999931 + outer loop + vertex -751.006 373.904 38.1055 + vertex -748.869 385.873 38.146 + vertex -755.822 374.193 38.1578 + endloop + endfacet + facet normal -0.00701343 -0.00243624 0.999972 + outer loop + vertex -746.284 373.63 38.1028 + vertex -739.917 386.061 38.1777 + vertex -744.286 385.97 38.1469 + endloop + endfacet + facet normal -0.0108746 -0.000458328 0.999941 + outer loop + vertex -741.666 373.363 38.1529 + vertex -739.917 386.061 38.1777 + vertex -746.284 373.63 38.1028 + endloop + endfacet + facet normal -0.0255447 0.0015633 0.999672 + outer loop + vertex -741.666 373.363 38.1529 + vertex -735.626 386.149 38.2872 + vertex -739.917 386.061 38.1777 + endloop + endfacet + facet normal -0.0278388 0.00264772 0.999609 + outer loop + vertex -737.169 373.108 38.2788 + vertex -735.626 386.149 38.2872 + vertex -741.666 373.363 38.1529 + endloop + endfacet + facet normal -0.0277579 0.0040773 0.999606 + outer loop + vertex -743.908 360.866 38.1416 + vertex -737.169 373.108 38.2788 + vertex -741.666 373.363 38.1529 + endloop + endfacet + facet normal -0.0109908 0.00106874 0.999939 + outer loop + vertex -743.908 360.866 38.1416 + vertex -741.666 373.363 38.1529 + vertex -748.744 361.484 38.0878 + endloop + endfacet + facet normal -0.0272792 0.00381368 0.999621 + outer loop + vertex -739.174 360.283 38.273 + vertex -737.169 373.108 38.2788 + vertex -743.908 360.866 38.1416 + endloop + endfacet + facet normal -0.0270976 0.00528909 0.999619 + outer loop + vertex -746.324 348.508 38.1415 + vertex -739.174 360.283 38.273 + vertex -743.908 360.866 38.1416 + endloop + endfacet + facet normal -0.0109212 0.00212707 0.999938 + outer loop + vertex -746.324 348.508 38.1415 + vertex -743.908 360.866 38.1416 + vertex -751.368 349.466 38.0844 + endloop + endfacet + facet normal -0.0268107 0.00511476 0.999627 + outer loop + vertex -741.355 347.601 38.2794 + vertex -739.174 360.283 38.273 + vertex -746.324 348.508 38.1415 + endloop + endfacet + facet normal -0.0267404 0.00550015 0.999627 + outer loop + vertex -748.754 336.224 38.1441 + vertex -741.355 347.601 38.2794 + vertex -746.324 348.508 38.1415 + endloop + endfacet + facet normal -0.0107808 0.00234241 0.999939 + outer loop + vertex -748.754 336.224 38.1441 + vertex -746.324 348.508 38.1415 + vertex -754.001 337.516 38.0845 + endloop + endfacet + facet normal -0.0258716 0.0049348 0.999653 + outer loop + vertex -743.554 334.992 38.2847 + vertex -741.355 347.601 38.2794 + vertex -748.754 336.224 38.1441 + endloop + endfacet + facet normal -0.0258758 0.00491676 0.999653 + outer loop + vertex -751.156 323.956 38.1422 + vertex -743.554 334.992 38.2847 + vertex -748.754 336.224 38.1441 + endloop + endfacet + facet normal -0.0100635 0.00182078 0.999948 + outer loop + vertex -751.156 323.956 38.1422 + vertex -748.754 336.224 38.1441 + vertex -756.607 325.585 38.0844 + endloop + endfacet + facet normal -0.0100399 0.00189959 0.999948 + outer loop + vertex -759.163 313.623 38.0815 + vertex -751.156 323.956 38.1422 + vertex -756.607 325.585 38.0844 + endloop + endfacet + facet normal -0.00939461 0.00139952 0.999955 + outer loop + vertex -753.518 311.67 38.1372 + vertex -751.156 323.956 38.1422 + vertex -759.163 313.623 38.0815 + endloop + endfacet + facet normal -0.00936779 0.00147702 0.999955 + outer loop + vertex -761.659 301.587 38.0759 + vertex -753.518 311.67 38.1372 + vertex -759.163 313.623 38.0815 + endloop + endfacet + facet normal -0.000207372 -0.000423188 1 + outer loop + vertex -761.659 301.587 38.0759 + vertex -759.163 313.623 38.0815 + vertex -767.458 303.96 38.0757 + endloop + endfacet + facet normal -0.00889886 0.00109834 0.99996 + outer loop + vertex -755.828 299.318 38.1303 + vertex -753.518 311.67 38.1372 + vertex -761.659 301.587 38.0759 + endloop + endfacet + facet normal -0.00886509 0.00118514 0.99996 + outer loop + vertex -764.084 289.424 38.0688 + vertex -755.828 299.318 38.1303 + vertex -761.659 301.587 38.0759 + endloop + endfacet + facet normal -0.000298374 -0.000522627 1 + outer loop + vertex -764.084 289.424 38.0688 + vertex -761.659 301.587 38.0759 + vertex -770.039 292.116 38.0684 + endloop + endfacet + facet normal -0.00865451 0.00100941 0.999962 + outer loop + vertex -758.075 286.854 38.1234 + vertex -755.828 299.318 38.1303 + vertex -764.084 289.424 38.0688 + endloop + endfacet + facet normal -0.00845316 0.00148014 0.999963 + outer loop + vertex -766.406 277.09 38.0674 + vertex -758.075 286.854 38.1234 + vertex -764.084 289.424 38.0688 + endloop + endfacet + facet normal -0.000364124 -4.27874e-05 1 + outer loop + vertex -766.406 277.09 38.0674 + vertex -764.084 289.424 38.0688 + vertex -772.509 280.079 38.0653 + endloop + endfacet + facet normal -0.00828468 0.00133636 0.999965 + outer loop + vertex -760.231 274.233 38.1224 + vertex -758.075 286.854 38.1234 + vertex -766.406 277.09 38.0674 + endloop + endfacet + facet normal -0.00779657 0.00239146 0.999967 + outer loop + vertex -768.564 264.545 38.0806 + vertex -760.231 274.233 38.1224 + vertex -766.406 277.09 38.0674 + endloop + endfacet + facet normal -0.000108761 0.00106903 0.999999 + outer loop + vertex -768.564 264.545 38.0806 + vertex -766.406 277.09 38.0674 + vertex -774.805 267.807 38.0764 + endloop + endfacet + facet normal -0.00760616 0.00222766 0.999969 + outer loop + vertex -762.239 261.422 38.1357 + vertex -760.231 274.233 38.1224 + vertex -768.564 264.545 38.0806 + endloop + endfacet + facet normal -0.00731576 0.00281589 0.999969 + outer loop + vertex -770.485 251.748 38.1026 + vertex -762.239 261.422 38.1357 + vertex -768.564 264.545 38.0806 + endloop + endfacet + facet normal 7.20998e-05 0.00170734 0.999999 + outer loop + vertex -770.485 251.748 38.1026 + vertex -768.564 264.545 38.0806 + vertex -776.841 255.252 38.0971 + endloop + endfacet + facet normal -0.00135609 -0.000883759 0.999999 + outer loop + vertex -778.583 242.393 38.0833 + vertex -770.485 251.748 38.1026 + vertex -776.841 255.252 38.0971 + endloop + endfacet + facet normal -0.00152776 -0.00073515 0.999999 + outer loop + vertex -772.132 238.681 38.0905 + vertex -770.485 251.748 38.1026 + vertex -778.583 242.393 38.0833 + endloop + endfacet + facet normal -0.0065161 -0.00940322 0.999935 + outer loop + vertex -780.054 229.395 37.9515 + vertex -772.132 238.681 38.0905 + vertex -778.583 242.393 38.0833 + endloop + endfacet + facet normal 0.000357463 -0.0101813 0.999948 + outer loop + vertex -780.054 229.395 37.9515 + vertex -778.583 242.393 38.0833 + vertex -786.416 233.455 37.9951 + endloop + endfacet + facet normal -0.00965428 -0.0258681 0.999619 + outer loop + vertex -787.716 220.979 37.6597 + vertex -780.054 229.395 37.9515 + vertex -786.416 233.455 37.9951 + endloop + endfacet + facet normal 0.000699856 -0.0104814 0.999945 + outer loop + vertex -786.416 233.455 37.9951 + vertex -778.583 242.393 38.0833 + vertex -784.896 246.261 38.1283 + endloop + endfacet + facet normal -0.00668199 -0.0092617 0.999935 + outer loop + vertex -773.54 225.508 37.959 + vertex -772.132 238.681 38.0905 + vertex -780.054 229.395 37.9515 + endloop + endfacet + facet normal -0.0159474 -0.0247913 0.999565 + outer loop + vertex -781.318 216.758 37.6179 + vertex -773.54 225.508 37.959 + vertex -780.054 229.395 37.9515 + endloop + endfacet + facet normal -0.0164503 -0.0243443 0.999568 + outer loop + vertex -774.773 212.735 37.6277 + vertex -773.54 225.508 37.959 + vertex -781.318 216.758 37.6179 + endloop + endfacet + facet normal -0.0223242 -0.0237746 0.999468 + outer loop + vertex -774.773 212.735 37.6277 + vertex -766.91 221.773 38.0183 + vertex -773.54 225.508 37.959 + endloop + endfacet + facet normal -0.0136559 -0.00838356 0.999872 + outer loop + vertex -766.91 221.773 38.0183 + vertex -765.565 235.115 38.1485 + vertex -773.54 225.508 37.959 + endloop + endfacet + facet normal -0.0245557 -0.0072824 0.999672 + outer loop + vertex -766.91 221.773 38.0183 + vertex -758.909 231.696 38.2871 + vertex -765.565 235.115 38.1485 + endloop + endfacet + facet normal -0.0201134 0.00137022 0.999797 + outer loop + vertex -758.909 231.696 38.2871 + vertex -757.479 245.171 38.2974 + vertex -765.565 235.115 38.1485 + endloop + endfacet + facet normal -0.020197 0.00143747 0.999795 + outer loop + vertex -765.565 235.115 38.1485 + vertex -757.479 245.171 38.2974 + vertex -764.022 248.39 38.1606 + endloop + endfacet + facet normal -0.00877928 0.000110811 0.999961 + outer loop + vertex -765.565 235.115 38.1485 + vertex -764.022 248.39 38.1606 + vertex -772.132 238.681 38.0905 + endloop + endfacet + facet normal -0.0188604 0.00415556 0.999813 + outer loop + vertex -757.479 245.171 38.2974 + vertex -755.841 258.45 38.2731 + vertex -764.022 248.39 38.1606 + endloop + endfacet + facet normal -0.0193584 0.00456073 0.999802 + outer loop + vertex -764.022 248.39 38.1606 + vertex -755.841 258.45 38.2731 + vertex -762.239 261.422 38.1357 + endloop + endfacet + facet normal -0.0197159 0.0037912 0.999798 + outer loop + vertex -755.841 258.45 38.2731 + vertex -754.006 271.521 38.2597 + vertex -762.239 261.422 38.1357 + endloop + endfacet + facet normal -0.0385821 0.00643922 0.999235 + outer loop + vertex -755.841 258.45 38.2731 + vertex -747.765 268.959 38.5172 + vertex -754.006 271.521 38.2597 + endloop + endfacet + facet normal -0.0391385 0.00508239 0.999221 + outer loop + vertex -747.765 268.959 38.5172 + vertex -745.997 282.119 38.5195 + vertex -754.006 271.521 38.2597 + endloop + endfacet + facet normal -0.0407664 0.00631425 0.999149 + outer loop + vertex -754.006 271.521 38.2597 + vertex -745.997 282.119 38.5195 + vertex -752.034 284.411 38.2587 + endloop + endfacet + facet normal -0.020646 0.00323596 0.999782 + outer loop + vertex -754.006 271.521 38.2597 + vertex -752.034 284.411 38.2587 + vertex -760.231 274.233 38.1224 + endloop + endfacet + facet normal -0.0411894 0.00519881 0.999138 + outer loop + vertex -745.997 282.119 38.5195 + vertex -744.16 295.141 38.5275 + vertex -752.034 284.411 38.2587 + endloop + endfacet + facet normal -0.0423369 0.00604215 0.999085 + outer loop + vertex -752.034 284.411 38.2587 + vertex -744.16 295.141 38.5275 + vertex -749.985 297.167 38.2684 + endloop + endfacet + facet normal -0.0213192 0.00266607 0.999769 + outer loop + vertex -752.034 284.411 38.2587 + vertex -749.985 297.167 38.2684 + vertex -758.075 286.854 38.1234 + endloop + endfacet + facet normal -0.042562 0.00539418 0.999079 + outer loop + vertex -744.16 295.141 38.5275 + vertex -742.283 308.075 38.5376 + vertex -749.985 297.167 38.2684 + endloop + endfacet + facet normal -0.0444857 0.00675482 0.998987 + outer loop + vertex -749.985 297.167 38.2684 + vertex -742.283 308.075 38.5376 + vertex -747.882 309.817 38.2765 + endloop + endfacet + facet normal -0.0224965 0.00309796 0.999742 + outer loop + vertex -749.985 297.167 38.2684 + vertex -747.882 309.817 38.2765 + vertex -755.828 299.318 38.1303 + endloop + endfacet + facet normal -0.0446602 0.00619335 0.998983 + outer loop + vertex -742.283 308.075 38.5376 + vertex -740.367 320.958 38.5434 + vertex -747.882 309.817 38.2765 + endloop + endfacet + facet normal -0.0465114 0.00744425 0.99889 + outer loop + vertex -747.882 309.817 38.2765 + vertex -740.367 320.958 38.5434 + vertex -745.734 322.41 38.2827 + endloop + endfacet + facet normal -0.0235455 0.00352666 0.999717 + outer loop + vertex -747.882 309.817 38.2765 + vertex -745.734 322.41 38.2827 + vertex -753.518 311.67 38.1372 + endloop + endfacet + facet normal -0.0465824 0.00718148 0.998889 + outer loop + vertex -740.367 320.958 38.5434 + vertex -738.424 333.833 38.5415 + vertex -745.734 322.41 38.2827 + endloop + endfacet + facet normal -0.0481357 0.00817733 0.998807 + outer loop + vertex -745.734 322.41 38.2827 + vertex -738.424 333.833 38.5415 + vertex -743.554 334.992 38.2847 + endloop + endfacet + facet normal -0.0481252 0.00822386 0.998807 + outer loop + vertex -738.424 333.833 38.5415 + vertex -736.474 346.744 38.5291 + vertex -743.554 334.992 38.2847 + endloop + endfacet + facet normal -0.0805453 0.0131168 0.996665 + outer loop + vertex -738.424 333.833 38.5415 + vertex -731.714 345.946 38.9242 + vertex -736.474 346.744 38.5291 + endloop + endfacet + facet normal -0.0806644 0.0124064 0.996664 + outer loop + vertex -731.714 345.946 38.9242 + vertex -730.049 359.217 38.8938 + vertex -736.474 346.744 38.5291 + endloop + endfacet + facet normal -0.0828771 0.013552 0.996468 + outer loop + vertex -736.474 346.744 38.5291 + vertex -730.049 359.217 38.8938 + vertex -734.548 359.734 38.5126 + endloop + endfacet + facet normal -0.0495785 0.00861796 0.998733 + outer loop + vertex -736.474 346.744 38.5291 + vertex -734.548 359.734 38.5126 + vertex -741.355 347.601 38.2794 + endloop + endfacet + facet normal -0.083411 0.00891493 0.996475 + outer loop + vertex -730.049 359.217 38.8938 + vertex -728.548 372.646 38.8993 + vertex -734.548 359.734 38.5126 + endloop + endfacet + facet normal -0.0898571 0.0119281 0.995883 + outer loop + vertex -734.548 359.734 38.5126 + vertex -728.548 372.646 38.8993 + vertex -732.798 372.869 38.5132 + endloop + endfacet + facet normal -0.0509294 0.00673971 0.99868 + outer loop + vertex -734.548 359.734 38.5126 + vertex -732.798 372.869 38.5132 + vertex -739.174 360.283 38.273 + endloop + endfacet + facet normal -0.0902351 0.00476092 0.995909 + outer loop + vertex -728.548 372.646 38.8993 + vertex -727.534 386.309 38.9259 + vertex -732.798 372.869 38.5132 + endloop + endfacet + facet normal -0.101254 0.00910962 0.994819 + outer loop + vertex -732.798 372.869 38.5132 + vertex -727.534 386.309 38.9259 + vertex -731.559 386.23 38.517 + endloop + endfacet + facet normal -0.0533017 0.00466177 0.998568 + outer loop + vertex -732.798 372.869 38.5132 + vertex -731.559 386.23 38.517 + vertex -737.169 373.108 38.2788 + endloop + endfacet + facet normal -0.0779347 0.0116638 0.99689 + outer loop + vertex -733.405 332.755 38.9464 + vertex -731.714 345.946 38.9242 + vertex -738.424 333.833 38.5415 + endloop + endfacet + facet normal -0.0778829 0.0119055 0.996891 + outer loop + vertex -740.367 320.958 38.5434 + vertex -733.405 332.755 38.9464 + vertex -738.424 333.833 38.5415 + endloop + endfacet + facet normal -0.0746864 0.01001 0.997157 + outer loop + vertex -735.092 319.6 38.9521 + vertex -733.405 332.755 38.9464 + vertex -740.367 320.958 38.5434 + endloop + endfacet + facet normal -0.0745257 0.0106357 0.997162 + outer loop + vertex -742.283 308.075 38.5376 + vertex -735.092 319.6 38.9521 + vertex -740.367 320.958 38.5434 + endloop + endfacet + facet normal -0.0717559 0.00889964 0.997383 + outer loop + vertex -736.764 306.448 38.9492 + vertex -735.092 319.6 38.9521 + vertex -742.283 308.075 38.5376 + endloop + endfacet + facet normal -0.111966 0.0140116 0.993613 + outer loop + vertex -736.764 306.448 38.9492 + vertex -729.98 318.352 39.5458 + vertex -735.092 319.6 38.9521 + endloop + endfacet + facet normal -0.112234 0.0129068 0.993598 + outer loop + vertex -729.98 318.352 39.5458 + vertex -728.547 331.761 39.5335 + vertex -735.092 319.6 38.9521 + endloop + endfacet + facet normal -0.116845 0.0154156 0.99303 + outer loop + vertex -735.092 319.6 38.9521 + vertex -728.547 331.761 39.5335 + vertex -733.405 332.755 38.9464 + endloop + endfacet + facet normal -0.116983 0.0147398 0.993025 + outer loop + vertex -728.547 331.761 39.5335 + vertex -727.113 345.208 39.5028 + vertex -733.405 332.755 38.9464 + endloop + endfacet + facet normal -0.121998 0.0173026 0.99238 + outer loop + vertex -733.405 332.755 38.9464 + vertex -727.113 345.208 39.5028 + vertex -731.714 345.946 38.9242 + endloop + endfacet + facet normal -0.122295 0.0154501 0.992374 + outer loop + vertex -727.113 345.208 39.5028 + vertex -725.713 358.739 39.4646 + vertex -731.714 345.946 38.9242 + endloop + endfacet + facet normal -0.128502 0.0183972 0.991539 + outer loop + vertex -731.714 345.946 38.9242 + vertex -725.713 358.739 39.4646 + vertex -730.049 359.217 38.8938 + endloop + endfacet + facet normal -0.129317 0.0109942 0.991542 + outer loop + vertex -725.713 358.739 39.4646 + vertex -724.47 372.432 39.4749 + vertex -730.049 359.217 38.8938 + endloop + endfacet + facet normal -0.138968 0.0151282 0.990181 + outer loop + vertex -730.049 359.217 38.8938 + vertex -724.47 372.432 39.4749 + vertex -728.548 372.646 38.8993 + endloop + endfacet + facet normal -0.139684 0.00151187 0.990195 + outer loop + vertex -724.47 372.432 39.4749 + vertex -723.539 386.384 39.585 + vertex -728.548 372.646 38.8993 + endloop + endfacet + facet normal -0.162947 0.0101746 0.986582 + outer loop + vertex -728.548 372.646 38.8993 + vertex -723.539 386.384 39.585 + vertex -727.534 386.309 38.9259 + endloop + endfacet + facet normal -0.108145 0.0118115 0.994065 + outer loop + vertex -731.406 304.954 39.5498 + vertex -729.98 318.352 39.5458 + vertex -736.764 306.448 38.9492 + endloop + endfacet + facet normal -0.10785 0.0128785 0.994084 + outer loop + vertex -738.409 293.256 38.9416 + vertex -731.406 304.954 39.5498 + vertex -736.764 306.448 38.9492 + endloop + endfacet + facet normal -0.0691933 0.00805509 0.997571 + outer loop + vertex -738.409 293.256 38.9416 + vertex -736.764 306.448 38.9492 + vertex -744.16 295.141 38.5275 + endloop + endfacet + facet normal -0.103608 0.0103143 0.994565 + outer loop + vertex -732.808 291.517 39.5431 + vertex -731.406 304.954 39.5498 + vertex -738.409 293.256 38.9416 + endloop + endfacet + facet normal -0.103094 0.0119834 0.994599 + outer loop + vertex -740.023 279.978 38.9343 + vertex -732.808 291.517 39.5431 + vertex -738.409 293.256 38.9416 + endloop + endfacet + facet normal -0.0665707 0.00754294 0.997753 + outer loop + vertex -740.023 279.978 38.9343 + vertex -738.409 293.256 38.9416 + vertex -745.997 282.119 38.5195 + endloop + endfacet + facet normal -0.099242 0.00955306 0.995017 + outer loop + vertex -734.187 277.991 39.5355 + vertex -732.808 291.517 39.5431 + vertex -740.023 279.978 38.9343 + endloop + endfacet + facet normal -0.0986347 0.0113486 0.995059 + outer loop + vertex -741.577 266.561 38.9333 + vertex -734.187 277.991 39.5355 + vertex -740.023 279.978 38.9343 + endloop + endfacet + facet normal -0.0642433 0.00736455 0.997907 + outer loop + vertex -741.577 266.561 38.9333 + vertex -740.023 279.978 38.9343 + vertex -747.765 268.959 38.5172 + endloop + endfacet + facet normal -0.0636108 0.00900186 0.997934 + outer loop + vertex -749.414 255.631 38.5324 + vertex -741.577 266.561 38.9333 + vertex -747.765 268.959 38.5172 + endloop + endfacet + facet normal -0.0619186 0.00778437 0.998051 + outer loop + vertex -743.034 252.986 38.9488 + vertex -741.577 266.561 38.9333 + vertex -749.414 255.631 38.5324 + endloop + endfacet + facet normal -0.061607 0.00853794 0.998064 + outer loop + vertex -750.897 242.119 38.5564 + vertex -743.034 252.986 38.9488 + vertex -749.414 255.631 38.5324 + endloop + endfacet + facet normal -0.0366336 0.00579912 0.999312 + outer loop + vertex -750.897 242.119 38.5564 + vertex -749.414 255.631 38.5324 + vertex -757.479 245.171 38.2974 + endloop + endfacet + facet normal -0.0600547 0.00741104 0.998168 + outer loop + vertex -744.374 239.285 38.9699 + vertex -743.034 252.986 38.9488 + vertex -750.897 242.119 38.5564 + endloop + endfacet + facet normal -0.0611035 0.00498988 0.998119 + outer loop + vertex -752.23 228.476 38.543 + vertex -744.374 239.285 38.9699 + vertex -750.897 242.119 38.5564 + endloop + endfacet + facet normal -0.0370153 0.00263456 0.999311 + outer loop + vertex -752.23 228.476 38.543 + vertex -750.897 242.119 38.5564 + vertex -758.909 231.696 38.2871 + endloop + endfacet + facet normal -0.0410883 -0.00582674 0.999139 + outer loop + vertex -760.201 218.213 38.1553 + vertex -752.23 228.476 38.543 + vertex -758.909 231.696 38.2871 + endloop + endfacet + facet normal -0.0403531 -0.00639879 0.999165 + outer loop + vertex -753.471 214.917 38.406 + vertex -752.23 228.476 38.543 + vertex -760.201 218.213 38.1553 + endloop + endfacet + facet normal -0.0477215 -0.021485 0.99863 + outer loop + vertex -761.402 205.266 37.8194 + vertex -753.471 214.917 38.406 + vertex -760.201 218.213 38.1553 + endloop + endfacet + facet normal -0.0321407 -0.0229455 0.99922 + outer loop + vertex -761.402 205.266 37.8194 + vertex -760.201 218.213 38.1553 + vertex -768.125 208.892 37.6864 + endloop + endfacet + facet normal -0.0431592 -0.0434148 0.998124 + outer loop + vertex -769.144 197.361 37.1408 + vertex -761.402 205.266 37.8194 + vertex -768.125 208.892 37.6864 + endloop + endfacet + facet normal -0.0324493 -0.022683 0.999216 + outer loop + vertex -768.125 208.892 37.6864 + vertex -760.201 218.213 38.1553 + vertex -766.91 221.773 38.0183 + endloop + endfacet + facet normal -0.0467299 -0.0223017 0.998659 + outer loop + vertex -754.607 201.912 38.0624 + vertex -753.471 214.917 38.406 + vertex -761.402 205.266 37.8194 + endloop + endfacet + facet normal -0.0567657 -0.0427192 0.997473 + outer loop + vertex -762.404 193.681 37.2662 + vertex -754.607 201.912 38.0624 + vertex -761.402 205.266 37.8194 + endloop + endfacet + facet normal -0.0685017 -0.0203667 0.997443 + outer loop + vertex -754.607 201.912 38.0624 + vertex -746.779 211.935 38.8047 + vertex -753.471 214.917 38.406 + endloop + endfacet + facet normal -0.0618574 -0.00537436 0.998071 + outer loop + vertex -746.779 211.935 38.8047 + vertex -745.622 225.55 38.9498 + vertex -753.471 214.917 38.406 + endloop + endfacet + facet normal -0.0925761 -0.00273705 0.995702 + outer loop + vertex -746.779 211.935 38.8047 + vertex -739.169 222.935 39.5425 + vertex -745.622 225.55 38.9498 + endloop + endfacet + facet normal -0.0891304 0.0058356 0.996003 + outer loop + vertex -739.169 222.935 39.5425 + vertex -738.015 236.725 39.565 + vertex -745.622 225.55 38.9498 + endloop + endfacet + facet normal -0.090478 0.00675996 0.995876 + outer loop + vertex -745.622 225.55 38.9498 + vertex -738.015 236.725 39.565 + vertex -744.374 239.285 38.9699 + endloop + endfacet + facet normal -0.0895689 0.00903288 0.99594 + outer loop + vertex -738.015 236.725 39.565 + vertex -736.799 250.543 39.549 + vertex -744.374 239.285 38.9699 + endloop + endfacet + facet normal -0.134103 0.0129461 0.990883 + outer loop + vertex -738.015 236.725 39.565 + vertex -730.785 248.335 40.3917 + vertex -736.799 250.543 39.549 + endloop + endfacet + facet normal -0.134666 0.0113889 0.990826 + outer loop + vertex -730.785 248.335 40.3917 + vertex -729.677 262.265 40.3823 + vertex -736.799 250.543 39.549 + endloop + endfacet + facet normal -0.138204 0.0135749 0.990311 + outer loop + vertex -736.799 250.543 39.549 + vertex -729.677 262.265 40.3823 + vertex -735.527 264.329 39.5376 + endloop + endfacet + facet normal -0.0921995 0.0093344 0.995697 + outer loop + vertex -736.799 250.543 39.549 + vertex -735.527 264.329 39.5376 + vertex -743.034 252.986 38.9488 + endloop + endfacet + facet normal -0.139016 0.0112372 0.990226 + outer loop + vertex -729.677 262.265 40.3823 + vertex -728.553 276.146 40.3826 + vertex -735.527 264.329 39.5376 + endloop + endfacet + facet normal -0.144087 0.0142845 0.989462 + outer loop + vertex -735.527 264.329 39.5376 + vertex -728.553 276.146 40.3826 + vertex -734.187 277.991 39.5355 + endloop + endfacet + facet normal -0.144882 0.0118196 0.989378 + outer loop + vertex -728.553 276.146 40.3826 + vertex -727.405 289.906 40.3862 + vertex -734.187 277.991 39.5355 + endloop + endfacet + facet normal -0.149874 0.0147167 0.988596 + outer loop + vertex -734.187 277.991 39.5355 + vertex -727.405 289.906 40.3862 + vertex -732.808 291.517 39.5431 + endloop + endfacet + facet normal -0.150438 0.0127946 0.988537 + outer loop + vertex -727.405 289.906 40.3862 + vertex -726.24 303.571 40.3866 + vertex -732.808 291.517 39.5431 + endloop + endfacet + facet normal -0.155767 0.0157591 0.987668 + outer loop + vertex -732.808 291.517 39.5431 + vertex -726.24 303.571 40.3866 + vertex -731.406 304.954 39.5498 + endloop + endfacet + facet normal -0.156355 0.0135247 0.987608 + outer loop + vertex -726.24 303.571 40.3866 + vertex -725.071 317.208 40.385 + vertex -731.406 304.954 39.5498 + endloop + endfacet + facet normal -0.164452 0.0178053 0.986224 + outer loop + vertex -731.406 304.954 39.5498 + vertex -725.071 317.208 40.385 + vertex -729.98 318.352 39.5458 + endloop + endfacet + facet normal -0.164933 0.0157092 0.98618 + outer loop + vertex -725.071 317.208 40.385 + vertex -723.885 330.849 40.3661 + vertex -729.98 318.352 39.5458 + endloop + endfacet + facet normal -0.172118 0.0192982 0.984887 + outer loop + vertex -729.98 318.352 39.5458 + vertex -723.885 330.849 40.3661 + vertex -728.547 331.761 39.5335 + endloop + endfacet + facet normal -0.172586 0.0168747 0.98485 + outer loop + vertex -723.885 330.849 40.3661 + vertex -722.707 344.537 40.338 + vertex -728.547 331.761 39.5335 + endloop + endfacet + facet normal -0.182989 0.021755 0.982874 + outer loop + vertex -728.547 331.761 39.5335 + vertex -722.707 344.537 40.338 + vertex -727.113 345.208 39.5028 + endloop + endfacet + facet normal -0.183636 0.0174659 0.982839 + outer loop + vertex -722.707 344.537 40.338 + vertex -721.564 358.309 40.3067 + vertex -727.113 345.208 39.5028 + endloop + endfacet + facet normal -0.19655 0.0230963 0.980222 + outer loop + vertex -727.113 345.208 39.5028 + vertex -721.564 358.309 40.3067 + vertex -725.713 358.739 39.4646 + endloop + endfacet + facet normal -0.197651 0.0124377 0.980194 + outer loop + vertex -721.564 358.309 40.3067 + vertex -720.602 372.245 40.3239 + vertex -725.713 358.739 39.4646 + endloop + endfacet + facet normal -0.213484 0.0186475 0.976769 + outer loop + vertex -725.713 358.739 39.4646 + vertex -720.602 372.245 40.3239 + vertex -724.47 372.432 39.4749 + endloop + endfacet + facet normal -0.214373 0.000166 0.976752 + outer loop + vertex -720.602 372.245 40.3239 + vertex -720.06 386.446 40.4405 + vertex -724.47 372.432 39.4749 + endloop + endfacet + facet normal -0.238919 0.00828693 0.971004 + outer loop + vertex -724.47 372.432 39.4749 + vertex -720.06 386.446 40.4405 + vertex -723.539 386.384 39.585 + endloop + endfacet + facet normal -0.131258 0.011146 0.991286 + outer loop + vertex -731.88 234.443 40.403 + vertex -730.785 248.335 40.3917 + vertex -738.015 236.725 39.565 + endloop + endfacet + facet normal -0.131889 0.0094231 0.99122 + outer loop + vertex -739.169 222.935 39.5425 + vertex -731.88 234.443 40.403 + vertex -738.015 236.725 39.565 + endloop + endfacet + facet normal -0.128944 0.00752748 0.991623 + outer loop + vertex -732.879 220.511 40.3788 + vertex -731.88 234.443 40.403 + vertex -739.169 222.935 39.5425 + endloop + endfacet + facet normal -0.13233 -0.0013998 0.991205 + outer loop + vertex -740.151 209.124 39.3919 + vertex -732.879 220.511 40.3788 + vertex -739.169 222.935 39.5425 + endloop + endfacet + facet normal -0.12984 -0.00301812 0.99153 + outer loop + vertex -733.57 206.263 40.245 + vertex -732.879 220.511 40.3788 + vertex -740.151 209.124 39.3919 + endloop + endfacet + facet normal -0.137029 -0.0199 0.990367 + outer loop + vertex -740.764 195.276 39.0288 + vertex -733.57 206.263 40.245 + vertex -740.151 209.124 39.3919 + endloop + endfacet + facet normal -0.0934367 -0.0219618 0.995383 + outer loop + vertex -740.764 195.276 39.0288 + vertex -740.151 209.124 39.3919 + vertex -747.73 198.706 38.4506 + endloop + endfacet + facet normal -0.103811 -0.0433175 0.993653 + outer loop + vertex -748.243 186.34 37.8579 + vertex -740.764 195.276 39.0288 + vertex -747.73 198.706 38.4506 + endloop + endfacet + facet normal -0.0965137 -0.0197011 0.995137 + outer loop + vertex -747.73 198.706 38.4506 + vertex -740.151 209.124 39.3919 + vertex -746.779 211.935 38.8047 + endloop + endfacet + facet normal -0.133501 -0.0222578 0.990799 + outer loop + vertex -733.687 191.585 39.8995 + vertex -733.57 206.263 40.245 + vertex -740.764 195.276 39.0288 + endloop + endfacet + facet normal -0.145906 -0.0466624 0.988197 + outer loop + vertex -740.905 181.319 38.349 + vertex -733.687 191.585 39.8995 + vertex -740.764 195.276 39.0288 + endloop + endfacet + facet normal -0.139254 -0.0514479 0.988919 + outer loop + vertex -733.071 177.234 39.2396 + vertex -733.687 191.585 39.8995 + vertex -740.905 181.319 38.349 + endloop + endfacet + facet normal -0.0901178 -0.00445243 0.995921 + outer loop + vertex -740.151 209.124 39.3919 + vertex -739.169 222.935 39.5425 + vertex -746.779 211.935 38.8047 + endloop + endfacet + facet normal -0.0665212 -0.021921 0.997544 + outer loop + vertex -747.73 198.706 38.4506 + vertex -746.779 211.935 38.8047 + vertex -754.607 201.912 38.0624 + endloop + endfacet + facet normal -0.0760253 -0.0424742 0.996201 + outer loop + vertex -755.438 190.188 37.4991 + vertex -747.73 198.706 38.4506 + vertex -754.607 201.912 38.0624 + endloop + endfacet + facet normal -0.0633283 -0.00428413 0.997984 + outer loop + vertex -753.471 214.917 38.406 + vertex -745.622 225.55 38.9498 + vertex -752.23 228.476 38.543 + endloop + endfacet + facet normal -0.0596919 0.00396043 0.998209 + outer loop + vertex -745.622 225.55 38.9498 + vertex -744.374 239.285 38.9699 + vertex -752.23 228.476 38.543 + endloop + endfacet + facet normal -0.0917432 0.0105068 0.995727 + outer loop + vertex -744.374 239.285 38.9699 + vertex -736.799 250.543 39.549 + vertex -743.034 252.986 38.9488 + endloop + endfacet + facet normal -0.0952308 0.0113566 0.99539 + outer loop + vertex -743.034 252.986 38.9488 + vertex -735.527 264.329 39.5376 + vertex -741.577 266.561 38.9333 + endloop + endfacet + facet normal -0.0958897 0.00955852 0.995346 + outer loop + vertex -735.527 264.329 39.5376 + vertex -734.187 277.991 39.5355 + vertex -741.577 266.561 38.9333 + endloop + endfacet + facet normal -0.0715492 0.00960288 0.997391 + outer loop + vertex -744.16 295.141 38.5275 + vertex -736.764 306.448 38.9492 + vertex -742.283 308.075 38.5376 + endloop + endfacet + facet normal -0.0688509 0.00910293 0.997585 + outer loop + vertex -745.997 282.119 38.5195 + vertex -738.409 293.256 38.9416 + vertex -744.16 295.141 38.5275 + endloop + endfacet + facet normal -0.0661532 0.00871162 0.997771 + outer loop + vertex -747.765 268.959 38.5172 + vertex -740.023 279.978 38.9343 + vertex -745.997 282.119 38.5195 + endloop + endfacet + facet normal -0.03776 0.00580663 0.99927 + outer loop + vertex -749.414 255.631 38.5324 + vertex -747.765 268.959 38.5172 + vertex -755.841 258.45 38.2731 + endloop + endfacet + facet normal -0.0374777 0.0064508 0.999277 + outer loop + vertex -757.479 245.171 38.2974 + vertex -749.414 255.631 38.5324 + vertex -755.841 258.45 38.2731 + endloop + endfacet + facet normal -0.0378145 0.00324978 0.999279 + outer loop + vertex -758.909 231.696 38.2871 + vertex -750.897 242.119 38.5564 + vertex -757.479 245.171 38.2974 + endloop + endfacet + facet normal -0.0243677 -0.00743407 0.999675 + outer loop + vertex -760.201 218.213 38.1553 + vertex -758.909 231.696 38.2871 + vertex -766.91 221.773 38.0183 + endloop + endfacet + facet normal -0.0224917 -0.0236288 0.999468 + outer loop + vertex -768.125 208.892 37.6864 + vertex -766.91 221.773 38.0183 + vertex -774.773 212.735 37.6277 + endloop + endfacet + facet normal -0.0344401 -0.0443138 0.998424 + outer loop + vertex -775.766 201.244 37.0834 + vertex -768.125 208.892 37.6864 + vertex -774.773 212.735 37.6277 + endloop + endfacet + facet normal -0.0134732 -0.0085353 0.999873 + outer loop + vertex -773.54 225.508 37.959 + vertex -765.565 235.115 38.1485 + vertex -772.132 238.681 38.0905 + endloop + endfacet + facet normal -0.00887568 0.000191344 0.999961 + outer loop + vertex -772.132 238.681 38.0905 + vertex -764.022 248.39 38.1606 + vertex -770.485 251.748 38.1026 + endloop + endfacet + facet normal -0.00745179 0.00293183 0.999968 + outer loop + vertex -764.022 248.39 38.1606 + vertex -762.239 261.422 38.1357 + vertex -770.485 251.748 38.1026 + endloop + endfacet + facet normal -0.0202237 0.00420535 0.999787 + outer loop + vertex -762.239 261.422 38.1357 + vertex -754.006 271.521 38.2597 + vertex -760.231 274.233 38.1224 + endloop + endfacet + facet normal -0.02098 0.00350508 0.999774 + outer loop + vertex -760.231 274.233 38.1224 + vertex -752.034 284.411 38.2587 + vertex -758.075 286.854 38.1234 + endloop + endfacet + facet normal -0.022356 0.00347968 0.999744 + outer loop + vertex -758.075 286.854 38.1234 + vertex -749.985 297.167 38.2684 + vertex -755.828 299.318 38.1303 + endloop + endfacet + facet normal -0.0234493 0.00381945 0.999718 + outer loop + vertex -755.828 299.318 38.1303 + vertex -747.882 309.817 38.2765 + vertex -753.518 311.67 38.1372 + endloop + endfacet + facet normal -0.0246587 0.00433384 0.999687 + outer loop + vertex -753.518 311.67 38.1372 + vertex -745.734 322.41 38.2827 + vertex -751.156 323.956 38.1422 + endloop + endfacet + facet normal -0.0247197 0.00411985 0.999686 + outer loop + vertex -745.734 322.41 38.2827 + vertex -743.554 334.992 38.2847 + vertex -751.156 323.956 38.1422 + endloop + endfacet + facet normal -0.0495018 0.00905471 0.998733 + outer loop + vertex -743.554 334.992 38.2847 + vertex -736.474 346.744 38.5291 + vertex -741.355 347.601 38.2794 + endloop + endfacet + facet normal -0.0506356 0.00921216 0.998675 + outer loop + vertex -741.355 347.601 38.2794 + vertex -734.548 359.734 38.5126 + vertex -739.174 360.283 38.273 + endloop + endfacet + facet normal -0.0531261 0.00785493 0.998557 + outer loop + vertex -739.174 360.283 38.273 + vertex -732.798 372.869 38.5132 + vertex -737.169 373.108 38.2788 + endloop + endfacet + facet normal -0.0565235 0.00604255 0.998383 + outer loop + vertex -737.169 373.108 38.2788 + vertex -731.559 386.23 38.517 + vertex -735.626 386.149 38.2872 + endloop + endfacet + facet normal -0.0107931 0.000950945 0.999941 + outer loop + vertex -748.744 361.484 38.0878 + vertex -741.666 373.363 38.1529 + vertex -746.284 373.63 38.1028 + endloop + endfacet + facet normal -0.0108604 0.00208726 0.999939 + outer loop + vertex -751.368 349.466 38.0844 + vertex -743.908 360.866 38.1416 + vertex -748.744 361.484 38.0878 + endloop + endfacet + facet normal -0.0108687 0.0024038 0.999938 + outer loop + vertex -754.001 337.516 38.0845 + vertex -746.324 348.508 38.1415 + vertex -751.368 349.466 38.0844 + endloop + endfacet + facet normal -0.0107791 0.00234907 0.999939 + outer loop + vertex -756.607 325.585 38.0844 + vertex -748.754 336.224 38.1441 + vertex -754.001 337.516 38.0845 + endloop + endfacet + facet normal -0.000157518 -0.000212209 1 + outer loop + vertex -759.163 313.623 38.0815 + vertex -756.607 325.585 38.0844 + vertex -764.796 315.666 38.081 + endloop + endfacet + facet normal -0.000227688 -0.000405748 1 + outer loop + vertex -767.458 303.96 38.0757 + vertex -759.163 313.623 38.0815 + vertex -764.796 315.666 38.081 + endloop + endfacet + facet normal -0.000261435 -0.000555309 1 + outer loop + vertex -770.039 292.116 38.0684 + vertex -761.659 301.587 38.0759 + vertex -767.458 303.96 38.0757 + endloop + endfacet + facet normal -0.000163312 -0.000223829 1 + outer loop + vertex -772.509 280.079 38.0653 + vertex -764.084 289.424 38.0688 + vertex -770.039 292.116 38.0684 + endloop + endfacet + facet normal 9.16401e-05 0.000887715 1 + outer loop + vertex -774.805 267.807 38.0764 + vertex -766.406 277.09 38.0674 + vertex -772.509 280.079 38.0653 + endloop + endfacet + facet normal 0.000176335 0.00161451 0.999999 + outer loop + vertex -776.841 255.252 38.0971 + vertex -768.564 264.545 38.0806 + vertex -774.805 267.807 38.0764 + endloop + endfacet + facet normal 0.0059719 -0.00187624 0.99998 + outer loop + vertex -778.583 242.393 38.0833 + vertex -776.841 255.252 38.0971 + vertex -784.896 246.261 38.1283 + endloop + endfacet + facet normal 0.01315 -0.0119582 0.999842 + outer loop + vertex -786.416 233.455 37.9951 + vertex -784.896 246.261 38.1283 + vertex -792.612 237.681 38.1272 + endloop + endfacet + facet normal 0.00248262 -0.0275888 0.999616 + outer loop + vertex -793.932 225.372 37.7907 + vertex -786.416 233.455 37.9951 + vertex -792.612 237.681 38.1272 + endloop + endfacet + facet normal 0.0188014 -0.00402273 0.999815 + outer loop + vertex -791.041 250.285 38.2572 + vertex -783.072 258.898 38.142 + vertex -789.134 262.675 38.2712 + endloop + endfacet + facet normal 0.02043 -0.00235842 0.999789 + outer loop + vertex -789.134 262.675 38.2712 + vertex -780.922 271.198 38.1235 + vertex -786.885 274.701 38.2536 + endloop + endfacet + facet normal 0.0202143 -0.00351862 0.999789 + outer loop + vertex -786.885 274.701 38.2536 + vertex -778.506 283.184 38.1141 + vertex -784.365 286.386 38.2438 + endloop + endfacet + facet normal 0.0197272 -0.00494174 0.999793 + outer loop + vertex -784.365 286.386 38.2438 + vertex -775.908 294.91 38.1191 + vertex -781.66 297.784 38.2468 + endloop + endfacet + facet normal 0.0204238 -0.00608937 0.999773 + outer loop + vertex -781.66 297.784 38.2468 + vertex -773.194 306.42 38.1264 + vertex -778.83 308.957 38.257 + endloop + endfacet + facet normal 0.020625 -0.0056423 0.999771 + outer loop + vertex -773.194 306.42 38.1264 + vertex -770.391 317.782 38.1327 + vertex -778.83 308.957 38.257 + endloop + endfacet + facet normal 0.00891291 -0.00251974 0.999957 + outer loop + vertex -770.391 317.782 38.1327 + vertex -762.068 327.285 38.0825 + vertex -767.516 329.05 38.1355 + endloop + endfacet + facet normal 0.00967388 -0.00274303 0.999949 + outer loop + vertex -767.516 329.05 38.1355 + vertex -759.286 338.868 38.0828 + vertex -764.583 340.273 38.1379 + endloop + endfacet + facet normal 0.0105457 -0.00314151 0.999939 + outer loop + vertex -764.583 340.273 38.1379 + vertex -756.471 350.465 38.0844 + vertex -761.611 351.503 38.1418 + endloop + endfacet + facet normal 0.0109838 -0.00329648 0.999934 + outer loop + vertex -761.611 351.503 38.1418 + vertex -753.659 362.124 38.0895 + vertex -758.632 362.782 38.1463 + endloop + endfacet + facet normal 0.010639 -0.00363118 0.999937 + outer loop + vertex -758.632 362.782 38.1463 + vertex -751.006 373.904 38.1055 + vertex -755.822 374.193 38.1578 + endloop + endfacet + facet normal 0.00566367 -0.00235805 0.999981 + outer loop + vertex -755.822 374.193 38.1578 + vertex -748.869 385.873 38.146 + vertex -753.509 385.774 38.1721 + endloop + endfacet + facet normal 0.0471581 -0.0110797 0.998826 + outer loop + vertex -768.604 364.182 38.5387 + vertex -760.685 374.485 38.2791 + vertex -765.537 374.793 38.5116 + endloop + endfacet + facet normal 0.0494155 -0.0143547 0.998675 + outer loop + vertex -771.834 353.664 38.5473 + vertex -763.629 363.466 38.2822 + vertex -768.604 364.182 38.5387 + endloop + endfacet + facet normal 0.0490613 -0.0156526 0.998673 + outer loop + vertex -775.051 343.201 38.5414 + vertex -766.745 352.563 38.2801 + vertex -771.834 353.664 38.5473 + endloop + endfacet + facet normal 0.0471035 -0.0149814 0.998778 + outer loop + vertex -778.217 332.735 38.5337 + vertex -769.852 341.713 38.2739 + vertex -775.051 343.201 38.5414 + endloop + endfacet + facet normal 0.044763 -0.0137127 0.998904 + outer loop + vertex -781.313 322.212 38.528 + vertex -772.912 330.869 38.2704 + vertex -778.217 332.735 38.5337 + endloop + endfacet + facet normal 0.0431958 -0.0133743 0.998977 + outer loop + vertex -784.333 311.564 38.516 + vertex -775.91 319.964 38.2643 + vertex -781.313 322.212 38.528 + endloop + endfacet + facet normal 0.0752405 -0.0209197 0.996946 + outer loop + vertex -787.255 300.747 38.5096 + vertex -784.333 311.564 38.516 + vertex -792.666 303.805 38.9821 + endloop + endfacet + facet normal 0.0759117 -0.0197281 0.996919 + outer loop + vertex -795.546 293.086 38.9893 + vertex -787.255 300.747 38.5096 + vertex -792.666 303.805 38.9821 + endloop + endfacet + facet normal 0.0767417 -0.0165173 0.996914 + outer loop + vertex -798.235 282.027 39.013 + vertex -790.055 289.683 38.5102 + vertex -795.546 293.086 38.9893 + endloop + endfacet + facet normal 0.078256 -0.0139298 0.996836 + outer loop + vertex -800.63 270.564 39.0409 + vertex -792.668 278.308 38.524 + vertex -798.235 282.027 39.013 + endloop + endfacet + facet normal 0.077194 -0.0143501 0.996913 + outer loop + vertex -802.645 258.705 39.0262 + vertex -794.992 266.567 38.5468 + vertex -800.63 270.564 39.0409 + endloop + endfacet + facet normal 0.0710931 -0.0209405 0.99725 + outer loop + vertex -804.283 246.595 38.8887 + vertex -796.967 254.447 38.532 + vertex -802.645 258.705 39.0262 + endloop + endfacet + facet normal 0.0567266 -0.0361715 0.997734 + outer loop + vertex -805.685 234.563 38.5322 + vertex -798.593 242.069 38.4011 + vertex -804.283 246.595 38.8887 + endloop + endfacet + facet normal 0.0544675 -0.0340334 0.997935 + outer loop + vertex -799.915 229.933 38.0593 + vertex -798.593 242.069 38.4011 + vertex -805.685 234.563 38.5322 + endloop + endfacet + facet normal 0.0222304 -0.0296981 0.999312 + outer loop + vertex -793.932 225.372 37.7907 + vertex -792.612 237.681 38.1272 + vertex -799.915 229.933 38.0593 + endloop + endfacet + facet normal 0.00193034 -0.0270757 0.999632 + outer loop + vertex -787.716 220.979 37.6597 + vertex -786.416 233.455 37.9951 + vertex -793.932 225.372 37.7907 + endloop + endfacet + facet normal -0.0102045 -0.0253673 0.999626 + outer loop + vertex -781.318 216.758 37.6179 + vertex -780.054 229.395 37.9515 + vertex -787.716 220.979 37.6597 + endloop + endfacet + facet normal -0.0295148 -0.0455993 0.998524 + outer loop + vertex -782.315 205.358 37.0678 + vertex -774.773 212.735 37.6277 + vertex -781.318 216.758 37.6179 + endloop + endfacet + facet normal -0.0304292 -0.0446657 0.998538 + outer loop + vertex -775.766 201.244 37.0834 + vertex -774.773 212.735 37.6277 + vertex -782.315 205.358 37.0678 + endloop + endfacet + facet normal -0.0345659 -0.0441881 0.998425 + outer loop + vertex -769.144 197.361 37.1408 + vertex -768.125 208.892 37.6864 + vertex -775.766 201.244 37.0834 + endloop + endfacet + facet normal -0.0425851 -0.043977 0.998125 + outer loop + vertex -762.404 193.681 37.2662 + vertex -761.402 205.266 37.8194 + vertex -769.144 197.361 37.1408 + endloop + endfacet + facet normal -0.0554192 -0.0439966 0.997493 + outer loop + vertex -755.438 190.188 37.4991 + vertex -754.607 201.912 38.0624 + vertex -762.404 193.681 37.2662 + endloop + endfacet + facet normal -0.0735782 -0.0446982 0.996287 + outer loop + vertex -748.243 186.34 37.8579 + vertex -747.73 198.706 38.4506 + vertex -755.438 190.188 37.4991 + endloop + endfacet + facet normal -0.0989622 -0.0474163 0.993961 + outer loop + vertex -740.905 181.319 38.349 + vertex -740.764 195.276 39.0288 + vertex -748.243 186.34 37.8579 + endloop + endfacet + facet normal -0.163593 -0.0945346 0.981988 + outer loop + vertex -735.641 169.372 38.0545 + vertex -732.001 168.376 38.5651 + vertex -733.071 177.234 39.2396 + endloop + endfacet + facet normal -0.125053 -0.136714 0.982686 + outer loop + vertex -742.139 165.742 36.6014 + vertex -743.445 170.023 37.0307 + vertex -748.384 169.23 36.2919 + endloop + endfacet + facet normal -0.132541 -0.20014 0.970761 + outer loop + vertex -779.679 185.004 35.4676 + vertex -784.695 187.975 35.3954 + vertex -778.471 183.076 35.2351 + endloop + endfacet + facet normal -0.14305 -0.213347 0.966447 + outer loop + vertex -785.956 187.878 35.1872 + vertex -778.471 183.076 35.2351 + vertex -784.695 187.975 35.3954 + endloop + endfacet + facet normal -0.195315 -0.295124 0.935283 + outer loop + vertex -778.471 183.076 35.2351 + vertex -785.956 187.878 35.1872 + vertex -779.333 183.006 35.0329 + endloop + endfacet + facet normal -0.0672048 -0.0945596 0.993248 + outer loop + vertex -781.85 189.203 35.8099 + vertex -782.735 196.017 36.3988 + vertex -788.675 193.339 35.7419 + endloop + endfacet + facet normal -0.0650859 -0.0991821 0.992938 + outer loop + vertex -788.675 193.339 35.7419 + vertex -782.735 196.017 36.3988 + vertex -789.232 200.438 36.4145 + endloop + endfacet + facet normal -0.0604747 -0.0988508 0.993263 + outer loop + vertex -788.675 193.339 35.7419 + vertex -789.232 200.438 36.4145 + vertex -795.025 198.342 35.8532 + endloop + endfacet + facet normal -0.0593665 -0.10185 0.993027 + outer loop + vertex -795.025 198.342 35.8532 + vertex -789.232 200.438 36.4145 + vertex -795.603 205.062 36.5079 + endloop + endfacet + facet normal -0.0554069 -0.101535 0.993288 + outer loop + vertex -795.025 198.342 35.8532 + vertex -795.603 205.062 36.5079 + vertex -801.526 202.883 35.9548 + endloop + endfacet + facet normal -0.0519051 -0.110852 0.992481 + outer loop + vertex -801.526 202.883 35.9548 + vertex -795.603 205.062 36.5079 + vertex -801.805 209.961 36.7306 + endloop + endfacet + facet normal -0.037066 -0.110344 0.993202 + outer loop + vertex -801.526 202.883 35.9548 + vertex -801.805 209.961 36.7306 + vertex -808.186 208.544 36.3351 + endloop + endfacet + facet normal -0.0347108 -0.120641 0.992089 + outer loop + vertex -808.186 208.544 36.3351 + vertex -801.805 209.961 36.7306 + vertex -807.437 214.844 37.1274 + endloop + endfacet + facet normal -0.0134795 -0.123189 0.992292 + outer loop + vertex -808.186 208.544 36.3351 + vertex -807.437 214.844 37.1274 + vertex -812.794 213.386 36.8737 + endloop + endfacet + facet normal -0.0104579 -0.134055 0.990919 + outer loop + vertex -812.4 219.043 37.6431 + vertex -812.794 213.386 36.8737 + vertex -807.437 214.844 37.1274 + endloop + endfacet + facet normal 0.00539171 -0.135147 0.990811 + outer loop + vertex -812.794 213.386 36.8737 + vertex -812.4 219.043 37.6431 + vertex -816.684 216.872 37.3703 + endloop + endfacet + facet normal 0.0182666 -0.16007 0.986937 + outer loop + vertex -816.684 216.872 37.3703 + vertex -812.4 219.043 37.6431 + vertex -816.814 221.553 38.1318 + endloop + endfacet + facet normal 0.0152579 -0.16016 0.986973 + outer loop + vertex -816.684 216.872 37.3703 + vertex -816.814 221.553 38.1318 + vertex -819.954 219.53 37.8523 + endloop + endfacet + facet normal 0.0377892 -0.194219 0.98023 + outer loop + vertex -819.954 219.53 37.8523 + vertex -816.814 221.553 38.1318 + vertex -820.062 222.545 38.4536 + endloop + endfacet + facet normal 0.00744942 -0.195393 0.980697 + outer loop + vertex -819.954 219.53 37.8523 + vertex -820.062 222.545 38.4536 + vertex -822.645 221.91 38.3468 + endloop + endfacet + facet normal 0.0090089 -0.20153 0.979441 + outer loop + vertex -822.645 221.91 38.3468 + vertex -820.062 222.545 38.4536 + vertex -822.094 225.309 39.0411 + endloop + endfacet + facet normal 0.0203936 -0.203266 0.978911 + outer loop + vertex -822.645 221.91 38.3468 + vertex -822.094 225.309 39.0411 + vertex -825.255 224.581 38.9558 + endloop + endfacet + facet normal 0.0239858 -0.218466 0.97555 + outer loop + vertex -825.255 224.581 38.9558 + vertex -822.094 225.309 39.0411 + vertex -824.689 228.258 39.7654 + endloop + endfacet + facet normal 0.0411516 -0.220862 0.974436 + outer loop + vertex -825.255 224.581 38.9558 + vertex -824.689 228.258 39.7654 + vertex -827.957 227.289 39.6837 + endloop + endfacet + facet normal 0.0484991 -0.245111 0.968281 + outer loop + vertex -827.957 227.289 39.6837 + vertex -824.689 228.258 39.7654 + vertex -827.276 230.857 40.5528 + endloop + endfacet + facet normal 0.0635311 -0.247613 0.966774 + outer loop + vertex -827.957 227.289 39.6837 + vertex -827.276 230.857 40.5528 + vertex -830.436 229.848 40.5021 + endloop + endfacet + facet normal 0.0728509 -0.276381 0.958283 + outer loop + vertex -830.436 229.848 40.5021 + vertex -827.276 230.857 40.5528 + vertex -829.674 233.274 41.4321 + endloop + endfacet + facet normal 0.0853193 -0.278694 0.956583 + outer loop + vertex -830.436 229.848 40.5021 + vertex -829.674 233.274 41.4321 + vertex -832.811 232.397 41.4566 + endloop + endfacet + facet normal 0.0948759 -0.313225 0.944928 + outer loop + vertex -832.811 232.397 41.4566 + vertex -829.674 233.274 41.4321 + vertex -831.962 235.771 42.4897 + endloop + endfacet + facet normal 0.10526 -0.315291 0.943139 + outer loop + vertex -832.811 232.397 41.4566 + vertex -831.962 235.771 42.4897 + vertex -835.373 235.195 42.6777 + endloop + endfacet + facet normal 0.111914 -0.360211 0.926133 + outer loop + vertex -835.373 235.195 42.6777 + vertex -831.962 235.771 42.4897 + vertex -834.143 238.419 43.7832 + endloop + endfacet + facet normal 0.132092 -0.36619 0.921117 + outer loop + vertex -835.373 235.195 42.6777 + vertex -834.143 238.419 43.7832 + vertex -837.799 238.058 44.164 + endloop + endfacet + facet normal -0.142952 -0.214224 0.966267 + outer loop + vertex -784.695 187.975 35.3954 + vertex -789.872 191.171 35.3379 + vertex -785.956 187.878 35.1872 + endloop + endfacet + facet normal -0.198305 -0.299128 0.93338 + outer loop + vertex -779.333 183.006 35.0329 + vertex -785.956 187.878 35.1872 + vertex -787.004 188.046 35.0185 + endloop + endfacet + facet normal -0.193873 -0.304822 0.932468 + outer loop + vertex -771.332 178.096 35.0917 + vertex -778.471 183.076 35.2351 + vertex -779.333 183.006 35.0329 + endloop + endfacet + facet normal -0.178156 -0.289376 0.94049 + outer loop + vertex -763.085 173.41 35.2119 + vertex -769.988 177.897 35.2848 + vertex -771.332 178.096 35.0917 + endloop + endfacet + facet normal -0.150629 -0.23611 0.959981 + outer loop + vertex -754.791 169.03 35.436 + vertex -761.654 173.316 35.4132 + vertex -763.085 173.41 35.2119 + endloop + endfacet + facet normal -0.146298 -0.229161 0.962332 + outer loop + vertex -753.484 169.125 35.6574 + vertex -761.654 173.316 35.4132 + vertex -754.791 169.03 35.436 + endloop + endfacet + facet normal -0.148171 -0.211891 0.965996 + outer loop + vertex -746.421 164.82 35.7965 + vertex -753.484 169.125 35.6574 + vertex -754.791 169.03 35.436 + endloop + endfacet + facet normal -0.162683 -0.235959 0.958049 + outer loop + vertex -745.142 164.878 36.0278 + vertex -753.484 169.125 35.6574 + vertex -746.421 164.82 35.7965 + endloop + endfacet +endsolid diff --git a/noether_examples/meshes/outputs/output_21.stl b/noether_examples/meshes/outputs/output_21.stl new file mode 100644 index 00000000..ca1342c0 --- /dev/null +++ b/noether_examples/meshes/outputs/output_21.stl @@ -0,0 +1,10306 @@ +solid ascii + facet normal -0.581739 -0.0713918 0.810236 + outer loop + vertex -702.872 176.925 50.7282 + vertex -703.385 184.078 50.9901 + vertex -703.979 176.708 49.9136 + endloop + endfacet + facet normal -0.57174 -0.124819 0.810885 + outer loop + vertex -703.213 169.176 49.2946 + vertex -702.872 176.925 50.7282 + vertex -703.979 176.708 49.9136 + endloop + endfacet + facet normal -0.557629 -0.127181 0.820289 + outer loop + vertex -702.119 169.33 50.0622 + vertex -702.872 176.925 50.7282 + vertex -703.213 169.176 49.2946 + endloop + endfacet + facet normal -0.593399 -0.128472 0.794589 + outer loop + vertex -702.119 169.33 50.0622 + vertex -702.307 177.363 51.2203 + vertex -702.872 176.925 50.7282 + endloop + endfacet + facet normal -0.59394 -0.128427 0.794192 + outer loop + vertex -701.557 169.478 50.5068 + vertex -702.307 177.363 51.2203 + vertex -702.119 169.33 50.0622 + endloop + endfacet + facet normal -0.818999 -0.12859 0.5592 + outer loop + vertex -701.557 169.478 50.5068 + vertex -702.081 176.603 51.3766 + vertex -702.307 177.363 51.2203 + endloop + endfacet + facet normal -0.619894 -0.13992 0.77211 + outer loop + vertex -701.311 169.165 50.6472 + vertex -702.081 176.603 51.3766 + vertex -701.557 169.478 50.5068 + endloop + endfacet + facet normal -0.956344 -0.0712582 -0.283423 + outer loop + vertex -701.311 169.165 50.6472 + vertex -701.958 175.122 51.3322 + vertex -702.081 176.603 51.3766 + endloop + endfacet + facet normal -0.723512 -0.1559 0.672477 + outer loop + vertex -701.106 167.933 50.5819 + vertex -701.958 175.122 51.3322 + vertex -701.311 169.165 50.6472 + endloop + endfacet + facet normal -0.602548 -0.0675192 0.795222 + outer loop + vertex -703.979 176.708 49.9136 + vertex -703.385 184.078 50.9901 + vertex -704.608 185.488 50.1829 + endloop + endfacet + facet normal -0.577245 -0.0337361 0.815874 + outer loop + vertex -703.385 184.078 50.9901 + vertex -703.524 195.846 51.3782 + vertex -704.608 185.488 50.1829 + endloop + endfacet + facet normal -0.566911 -0.0356408 0.823007 + outer loop + vertex -703.524 195.846 51.3782 + vertex -705.887 196.03 49.7584 + vertex -704.608 185.488 50.1829 + endloop + endfacet + facet normal -0.551293 -0.0333178 0.833646 + outer loop + vertex -706.312 184.213 49.005 + vertex -704.608 185.488 50.1829 + vertex -705.887 196.03 49.7584 + endloop + endfacet + facet normal -0.531598 -0.0693546 0.844152 + outer loop + vertex -705.689 176.942 48.7997 + vertex -704.608 185.488 50.1829 + vertex -706.312 184.213 49.005 + endloop + endfacet + facet normal -0.5509 -0.0649517 0.83204 + outer loop + vertex -703.979 176.708 49.9136 + vertex -704.608 185.488 50.1829 + vertex -705.689 176.942 48.7997 + endloop + endfacet + facet normal -0.553337 -0.119319 0.824367 + outer loop + vertex -704.937 169.411 48.2149 + vertex -703.979 176.708 49.9136 + vertex -705.689 176.942 48.7997 + endloop + endfacet + facet normal -0.538815 -0.123315 0.83335 + outer loop + vertex -703.213 169.176 49.2946 + vertex -703.979 176.708 49.9136 + vertex -704.937 169.411 48.2149 + endloop + endfacet + facet normal -0.56581 -0.0084869 0.824492 + outer loop + vertex -703.524 195.846 51.3782 + vertex -703.87 211.255 51.2993 + vertex -705.887 196.03 49.7584 + endloop + endfacet + facet normal -0.547432 -0.0121636 0.836762 + outer loop + vertex -705.887 196.03 49.7584 + vertex -703.87 211.255 51.2993 + vertex -706.29 212.134 49.7289 + endloop + endfacet + facet normal -0.543422 0.00369111 0.839452 + outer loop + vertex -703.87 211.255 51.2993 + vertex -703.77 226.669 51.2961 + vertex -706.29 212.134 49.7289 + endloop + endfacet + facet normal -0.542055 0.00335878 0.840336 + outer loop + vertex -706.29 212.134 49.7289 + vertex -703.77 226.669 51.2961 + vertex -706.174 227.635 49.7415 + endloop + endfacet + facet normal -0.540394 0.00914752 0.841363 + outer loop + vertex -703.77 226.669 51.2961 + vertex -703.488 241.638 51.3148 + vertex -706.174 227.635 49.7415 + endloop + endfacet + facet normal -0.552693 0.0124138 0.833293 + outer loop + vertex -706.174 227.635 49.7415 + vertex -703.488 241.638 51.3148 + vertex -705.805 242.489 49.7651 + endloop + endfacet + facet normal -0.553411 0.00965905 0.832853 + outer loop + vertex -703.488 241.638 51.3148 + vertex -703.214 256.075 51.329 + vertex -705.805 242.489 49.7651 + endloop + endfacet + facet normal -0.566782 0.0132551 0.823761 + outer loop + vertex -705.805 242.489 49.7651 + vertex -703.214 256.075 51.329 + vertex -705.455 256.912 49.7739 + endloop + endfacet + facet normal -0.568504 0.00658696 0.822654 + outer loop + vertex -703.214 256.075 51.329 + vertex -703.046 270.37 51.3307 + vertex -705.455 256.912 49.7739 + endloop + endfacet + facet normal -0.582263 0.0101736 0.812937 + outer loop + vertex -705.455 256.912 49.7739 + vertex -703.046 270.37 51.3307 + vertex -705.197 271.233 49.7797 + endloop + endfacet + facet normal -0.584153 0.00312538 0.811638 + outer loop + vertex -703.046 270.37 51.3307 + vertex -702.979 284.753 51.3239 + vertex -705.197 271.233 49.7797 + endloop + endfacet + facet normal -0.598692 0.00673059 0.800951 + outer loop + vertex -705.197 271.233 49.7797 + vertex -702.979 284.753 51.3239 + vertex -705.037 285.57 49.7786 + endloop + endfacet + facet normal -0.600217 0.000778422 0.799837 + outer loop + vertex -702.979 284.753 51.3239 + vertex -702.966 299.215 51.3195 + vertex -705.037 285.57 49.7786 + endloop + endfacet + facet normal -0.618125 0.00505195 0.786064 + outer loop + vertex -705.037 285.57 49.7786 + vertex -702.966 299.215 51.3195 + vertex -704.93 299.894 49.7709 + endloop + endfacet + facet normal -0.619347 -0.000635027 0.785117 + outer loop + vertex -702.966 299.215 51.3195 + vertex -702.98 313.57 51.3201 + vertex -704.93 299.894 49.7709 + endloop + endfacet + facet normal -0.638639 0.00388506 0.769497 + outer loop + vertex -704.93 299.894 49.7709 + vertex -702.98 313.57 51.3201 + vertex -704.851 314.2 49.764 + endloop + endfacet + facet normal -0.639857 -0.00221714 0.768491 + outer loop + vertex -702.98 313.57 51.3201 + vertex -702.994 327.974 51.3495 + vertex -704.851 314.2 49.764 + endloop + endfacet + facet normal -0.660429 0.00258234 0.750884 + outer loop + vertex -704.851 314.2 49.764 + vertex -702.994 327.974 51.3495 + vertex -704.784 328.521 49.7734 + endloop + endfacet + facet normal -0.661606 -0.00427525 0.74984 + outer loop + vertex -702.994 327.974 51.3495 + vertex -703.049 342.448 51.3842 + vertex -704.784 328.521 49.7734 + endloop + endfacet + facet normal -0.686269 0.00139991 0.727347 + outer loop + vertex -704.784 328.521 49.7734 + vertex -703.049 342.448 51.3842 + vertex -704.712 342.859 49.8138 + endloop + endfacet + facet normal -0.687155 -0.00546436 0.726491 + outer loop + vertex -703.049 342.448 51.3842 + vertex -703.135 356.907 51.411 + vertex -704.712 342.859 49.8138 + endloop + endfacet + facet normal -0.708171 -0.000780371 0.70604 + outer loop + vertex -704.712 342.859 49.8138 + vertex -703.135 356.907 51.411 + vertex -704.682 357.213 49.8601 + endloop + endfacet + facet normal -0.709712 -0.0175528 0.704273 + outer loop + vertex -703.135 356.907 51.411 + vertex -703.413 371.624 51.4982 + vertex -704.682 357.213 49.8601 + endloop + endfacet + facet normal -0.737758 -0.0117513 0.674963 + outer loop + vertex -704.682 357.213 49.8601 + vertex -703.413 371.624 51.4982 + vertex -704.821 371.73 49.9608 + endloop + endfacet + facet normal -0.738168 -0.0553778 0.672341 + outer loop + vertex -703.413 371.624 51.4982 + vertex -703.778 386.654 52.335 + vertex -704.821 371.73 49.9608 + endloop + endfacet + facet normal -0.818039 -0.0341758 0.574147 + outer loop + vertex -704.821 371.73 49.9608 + vertex -703.778 386.654 52.335 + vertex -705.335 386.645 50.1156 + endloop + endfacet + facet normal -0.648018 -0.0327605 0.76092 + outer loop + vertex -703.385 184.078 50.9901 + vertex -702.782 186.172 51.5936 + vertex -703.524 195.846 51.3782 + endloop + endfacet + facet normal -0.673942 -0.0352604 0.737942 + outer loop + vertex -702.724 196.696 52.1496 + vertex -703.524 195.846 51.3782 + vertex -702.782 186.172 51.5936 + endloop + endfacet + facet normal -0.772014 -0.029274 0.634931 + outer loop + vertex -702.498 185.544 51.9098 + vertex -702.724 196.696 52.1496 + vertex -702.782 186.172 51.5936 + endloop + endfacet + facet normal -0.806082 -0.0683198 0.587847 + outer loop + vertex -702.307 177.363 51.2203 + vertex -702.498 185.544 51.9098 + vertex -702.782 186.172 51.5936 + endloop + endfacet + facet normal -0.626041 -0.0666352 0.776938 + outer loop + vertex -702.307 177.363 51.2203 + vertex -702.782 186.172 51.5936 + vertex -702.872 176.925 50.7282 + endloop + endfacet + facet normal -0.724525 -0.0746243 0.685197 + outer loop + vertex -702.081 176.603 51.3766 + vertex -702.498 185.544 51.9098 + vertex -702.307 177.363 51.2203 + endloop + endfacet + facet normal -0.909497 -0.0176127 -0.415336 + outer loop + vertex -702.081 176.603 51.3766 + vertex -702.349 181.092 51.7721 + vertex -702.498 185.544 51.9098 + endloop + endfacet + facet normal -0.998641 -0.0321697 -0.0410097 + outer loop + vertex -702.498 185.544 51.9098 + vertex -702.349 181.092 51.7721 + vertex -702.508 185.736 52.0082 + endloop + endfacet + facet normal -0.922062 -0.0881666 0.376865 + outer loop + vertex -701.958 175.122 51.3322 + vertex -702.349 181.092 51.7721 + vertex -702.081 176.603 51.3766 + endloop + endfacet + facet normal -0.691374 -0.00480166 0.722481 + outer loop + vertex -702.724 196.696 52.1496 + vertex -702.765 209.668 52.1965 + vertex -703.524 195.846 51.3782 + endloop + endfacet + facet normal -0.639201 -0.0104194 0.768969 + outer loop + vertex -703.524 195.846 51.3782 + vertex -702.765 209.668 52.1965 + vertex -703.87 211.255 51.2993 + endloop + endfacet + facet normal -0.623673 0.00756381 0.781649 + outer loop + vertex -702.765 209.668 52.1965 + vertex -702.575 224.518 52.2042 + vertex -703.87 211.255 51.2993 + endloop + endfacet + facet normal -0.600333 0.00405073 0.79974 + outer loop + vertex -703.87 211.255 51.2993 + vertex -702.575 224.518 52.2042 + vertex -703.77 226.669 51.2961 + endloop + endfacet + facet normal -0.592725 0.0106399 0.805334 + outer loop + vertex -702.575 224.518 52.2042 + vertex -702.3 239.542 52.2084 + vertex -703.77 226.669 51.2961 + endloop + endfacet + facet normal -0.589588 0.010118 0.807641 + outer loop + vertex -703.77 226.669 51.2961 + vertex -702.3 239.542 52.2084 + vertex -703.488 241.638 51.3148 + endloop + endfacet + facet normal -0.591196 0.00871165 0.806481 + outer loop + vertex -702.3 239.542 52.2084 + vertex -702.073 253.97 52.2185 + vertex -703.488 241.638 51.3148 + endloop + endfacet + facet normal -0.602477 0.0106223 0.798066 + outer loop + vertex -703.488 241.638 51.3148 + vertex -702.073 253.97 52.2185 + vertex -703.214 256.075 51.329 + endloop + endfacet + facet normal -0.608411 0.0055209 0.793603 + outer loop + vertex -702.073 253.97 52.2185 + vertex -702.024 267.608 52.1613 + vertex -703.214 256.075 51.329 + endloop + endfacet + facet normal -0.618841 0.00718332 0.785484 + outer loop + vertex -703.214 256.075 51.329 + vertex -702.024 267.608 52.1613 + vertex -703.046 270.37 51.3307 + endloop + endfacet + facet normal -0.628453 0.00132827 0.777847 + outer loop + vertex -702.024 267.608 52.1613 + vertex -701.973 282.105 52.1775 + vertex -703.046 270.37 51.3307 + endloop + endfacet + facet normal -0.642029 0.00337574 0.766673 + outer loop + vertex -703.046 270.37 51.3307 + vertex -701.973 282.105 52.1775 + vertex -702.979 284.753 51.3239 + endloop + endfacet + facet normal -0.648089 -0.000571217 0.761565 + outer loop + vertex -701.973 282.105 52.1775 + vertex -702.049 296.559 52.1243 + vertex -702.979 284.753 51.3239 + endloop + endfacet + facet normal -0.658191 0.000815724 0.75285 + outer loop + vertex -702.979 284.753 51.3239 + vertex -702.049 296.559 52.1243 + vertex -702.966 299.215 51.3195 + endloop + endfacet + facet normal -0.664504 -0.00305258 0.747279 + outer loop + vertex -702.049 296.559 52.1243 + vertex -702.059 311.647 52.1769 + vertex -702.966 299.215 51.3195 + endloop + endfacet + facet normal -0.681885 -0.000693284 0.731459 + outer loop + vertex -702.966 299.215 51.3195 + vertex -702.059 311.647 52.1769 + vertex -702.98 313.57 51.3201 + endloop + endfacet + facet normal -0.685806 -0.00421305 0.727772 + outer loop + vertex -702.059 311.647 52.1769 + vertex -702.15 325.534 52.1715 + vertex -702.98 313.57 51.3201 + endloop + endfacet + facet normal -0.700659 -0.00216642 0.713493 + outer loop + vertex -702.98 313.57 51.3201 + vertex -702.15 325.534 52.1715 + vertex -702.994 327.974 51.3495 + endloop + endfacet + facet normal -0.708368 -0.00742474 0.705804 + outer loop + vertex -702.15 325.534 52.1715 + vertex -702.188 340.663 52.2923 + vertex -702.994 327.974 51.3495 + endloop + endfacet + facet normal -0.730111 -0.00437227 0.683315 + outer loop + vertex -702.994 327.974 51.3495 + vertex -702.188 340.663 52.2923 + vertex -703.049 342.448 51.3842 + endloop + endfacet + facet normal -0.733669 -0.00804893 0.67946 + outer loop + vertex -702.188 340.663 52.2923 + vertex -702.325 355.157 52.3158 + vertex -703.049 342.448 51.3842 + endloop + endfacet + facet normal -0.750528 -0.00572259 0.660813 + outer loop + vertex -703.049 342.448 51.3842 + vertex -702.325 355.157 52.3158 + vertex -703.135 356.907 51.411 + endloop + endfacet + facet normal -0.756821 -0.0124148 0.653504 + outer loop + vertex -702.325 355.157 52.3158 + vertex -702.609 370.322 52.2758 + vertex -703.135 356.907 51.411 + endloop + endfacet + facet normal -0.709584 -0.0175512 0.704402 + outer loop + vertex -703.135 356.907 51.411 + vertex -702.609 370.322 52.2758 + vertex -703.413 371.624 51.4982 + endloop + endfacet + facet normal -0.740594 -0.0575349 0.669485 + outer loop + vertex -702.609 370.322 52.2758 + vertex -703.672 386.655 52.5033 + vertex -703.413 371.624 51.4982 + endloop + endfacet + facet normal -0.844373 -0.0502245 0.533396 + outer loop + vertex -703.413 371.624 51.4982 + vertex -703.672 386.655 52.5033 + vertex -703.778 386.654 52.335 + endloop + endfacet + facet normal -0.115119 -0.0213223 0.993123 + outer loop + vertex -703.672 386.655 52.5033 + vertex -702.609 370.322 52.2758 + vertex -702.875 381.06 52.4755 + endloop + endfacet + facet normal -0.84233 -0.122609 0.524831 + outer loop + vertex -702.875 381.06 52.4755 + vertex -703.566 386.655 52.6728 + vertex -703.672 386.655 52.5033 + endloop + endfacet + facet normal -0.845652 -0.122829 0.51941 + outer loop + vertex -703.566 386.655 52.6728 + vertex -702.875 381.06 52.4755 + vertex -703.461 386.656 52.8438 + endloop + endfacet + facet normal -0.806502 -0.0457538 -0.589458 + outer loop + vertex -702.875 381.06 52.4755 + vertex -702.543 374.838 52.5041 + vertex -703.461 386.656 52.8438 + endloop + endfacet + facet normal -0.857693 -0.0519733 -0.511528 + outer loop + vertex -702.165 365.618 52.8077 + vertex -703.461 386.656 52.8438 + vertex -702.543 374.838 52.5041 + endloop + endfacet + facet normal -0.984798 -0.034732 0.170195 + outer loop + vertex -702.543 374.838 52.5041 + vertex -702.347 369.244 52.4929 + vertex -702.165 365.618 52.8077 + endloop + endfacet + facet normal -0.91555 -0.0111239 0.402049 + outer loop + vertex -702.347 369.244 52.4929 + vertex -702.283 364.292 52.5033 + vertex -702.165 365.618 52.8077 + endloop + endfacet + facet normal -0.913762 -0.0122045 0.406067 + outer loop + vertex -702.283 364.292 52.5033 + vertex -702.164 358.073 52.582 + vertex -702.165 365.618 52.8077 + endloop + endfacet + facet normal -0.877644 -0.0143865 0.479097 + outer loop + vertex -701.836 348.368 52.8917 + vertex -702.165 365.618 52.8077 + vertex -702.164 358.073 52.582 + endloop + endfacet + facet normal -0.818437 -0.0093388 0.57452 + outer loop + vertex -702.164 358.073 52.582 + vertex -702.114 353.565 52.5811 + vertex -701.836 348.368 52.8917 + endloop + endfacet + facet normal -0.825655 -0.010348 0.56408 + outer loop + vertex -702.114 353.565 52.5811 + vertex -702.081 349.461 52.5532 + vertex -701.836 348.368 52.8917 + endloop + endfacet + facet normal -0.824448 -0.00952681 0.565858 + outer loop + vertex -702.081 349.461 52.5532 + vertex -702.025 345.574 52.5705 + vertex -701.836 348.368 52.8917 + endloop + endfacet + facet normal -0.826514 -0.00904098 0.562844 + outer loop + vertex -702.025 345.574 52.5705 + vertex -701.943 340.361 52.6067 + vertex -701.836 348.368 52.8917 + endloop + endfacet + facet normal -0.825169 -0.00912889 0.564812 + outer loop + vertex -701.533 330.52 53.0462 + vertex -701.836 348.368 52.8917 + vertex -701.943 340.361 52.6067 + endloop + endfacet + facet normal -0.824465 -0.00905368 0.56584 + outer loop + vertex -701.943 340.361 52.6067 + vertex -701.915 332.714 52.5256 + vertex -701.533 330.52 53.0462 + endloop + endfacet + facet normal -0.819715 -0.0065921 0.572734 + outer loop + vertex -701.915 332.714 52.5256 + vertex -701.826 322.083 52.5304 + vertex -701.533 330.52 53.0462 + endloop + endfacet + facet normal -0.816745 -0.00695326 0.576957 + outer loop + vertex -701.385 313.001 53.0449 + vertex -701.533 330.52 53.0462 + vertex -701.826 322.083 52.5304 + endloop + endfacet + facet normal -0.803396 -0.00525917 0.595422 + outer loop + vertex -701.826 322.083 52.5304 + vertex -701.795 313.77 52.4985 + vertex -701.385 313.001 53.0449 + endloop + endfacet + facet normal -0.802657 -0.00415043 0.596427 + outer loop + vertex -701.795 313.77 52.4985 + vertex -701.75 304.759 52.4964 + vertex -701.385 313.001 53.0449 + endloop + endfacet + facet normal -0.797862 -0.00478818 0.602821 + outer loop + vertex -701.222 296.393 53.1285 + vertex -701.385 313.001 53.0449 + vertex -701.75 304.759 52.4964 + endloop + endfacet + facet normal -0.787759 -0.00315679 0.615976 + outer loop + vertex -701.75 304.759 52.4964 + vertex -701.693 291.526 52.501 + vertex -701.222 296.393 53.1285 + endloop + endfacet + facet normal -0.789579 -0.00267979 0.613643 + outer loop + vertex -701.211 280.439 53.0735 + vertex -701.222 296.393 53.1285 + vertex -701.693 291.526 52.501 + endloop + endfacet + facet normal -0.789064 -0.00262318 0.614305 + outer loop + vertex -701.693 291.526 52.501 + vertex -701.666 283.148 52.4997 + vertex -701.211 280.439 53.0735 + endloop + endfacet + facet normal -0.785064 -0.000867954 0.619415 + outer loop + vertex -701.666 283.148 52.4997 + vertex -701.624 274.247 52.5407 + vertex -701.211 280.439 53.0735 + endloop + endfacet + facet normal -0.790905 0.000165536 0.611939 + outer loop + vertex -701.178 262.44 53.1201 + vertex -701.211 280.439 53.0735 + vertex -701.624 274.247 52.5407 + endloop + endfacet + facet normal -0.780745 0.00118273 0.624849 + outer loop + vertex -701.624 274.247 52.5407 + vertex -701.655 263.709 52.5217 + vertex -701.178 262.44 53.1201 + endloop + endfacet + facet normal -0.777254 0.00453417 0.629171 + outer loop + vertex -701.655 263.709 52.5217 + vertex -701.626 255.247 52.6193 + vertex -701.178 262.44 53.1201 + endloop + endfacet + facet normal -0.789447 0.00636349 0.613786 + outer loop + vertex -701.382 243.692 53.052 + vertex -701.178 262.44 53.1201 + vertex -701.626 255.247 52.6193 + endloop + endfacet + facet normal -0.766759 0.00789355 0.641886 + outer loop + vertex -701.626 255.247 52.6193 + vertex -701.778 247.845 52.5285 + vertex -701.382 243.692 53.052 + endloop + endfacet + facet normal -0.755866 0.0105391 0.654641 + outer loop + vertex -701.778 247.845 52.5285 + vertex -701.828 242.221 52.5609 + vertex -701.382 243.692 53.052 + endloop + endfacet + facet normal -0.63523 0.0101365 0.772256 + outer loop + vertex -701.828 242.221 52.5609 + vertex -701.778 247.845 52.5285 + vertex -702.3 239.542 52.2084 + endloop + endfacet + facet normal -0.643791 0.0125848 0.765098 + outer loop + vertex -701.987 234.424 52.5558 + vertex -701.828 242.221 52.5609 + vertex -702.3 239.542 52.2084 + endloop + endfacet + facet normal -0.674798 0.00482344 0.737986 + outer loop + vertex -701.778 247.845 52.5285 + vertex -701.626 255.247 52.6193 + vertex -702.073 253.97 52.2185 + endloop + endfacet + facet normal -0.752988 0.00580614 0.658009 + outer loop + vertex -699.868 248.041 54.747 + vertex -701.178 262.44 53.1201 + vertex -701.382 243.692 53.052 + endloop + endfacet + facet normal -0.755107 0.00749885 0.655559 + outer loop + vertex -699.868 248.041 54.747 + vertex -701.382 243.692 53.052 + vertex -700.123 228.073 54.6817 + endloop + endfacet + facet normal -0.733123 0.0118211 0.679993 + outer loop + vertex -700.123 228.073 54.6817 + vertex -701.382 243.692 53.052 + vertex -701.779 225.153 52.947 + endloop + endfacet + facet normal -0.72971 0.00767389 0.683714 + outer loop + vertex -700.123 228.073 54.6817 + vertex -701.779 225.153 52.947 + vertex -701.23 213.035 53.6685 + endloop + endfacet + facet normal -0.735541 0.00852694 0.677427 + outer loop + vertex -701.23 213.035 53.6685 + vertex -699.738 212.23 55.2992 + vertex -700.123 228.073 54.6817 + endloop + endfacet + facet normal -0.738098 -0.00174872 0.674692 + outer loop + vertex -699.738 212.23 55.2992 + vertex -701.23 213.035 53.6685 + vertex -700.307 202.276 54.6505 + endloop + endfacet + facet normal -0.726354 0.000411751 0.68732 + outer loop + vertex -700.307 202.276 54.6505 + vertex -701.23 213.035 53.6685 + vertex -701.571 200.377 53.3158 + endloop + endfacet + facet normal -0.711444 -0.0201486 0.702454 + outer loop + vertex -700.307 202.276 54.6505 + vertex -701.571 200.377 53.3158 + vertex -700.397 192.301 54.2729 + endloop + endfacet + facet normal -0.71651 -0.021502 0.697245 + outer loop + vertex -700.397 192.301 54.2729 + vertex -701.571 200.377 53.3158 + vertex -701.412 191.163 53.195 + endloop + endfacet + facet normal -0.700164 -0.050276 0.71221 + outer loop + vertex -700.397 192.301 54.2729 + vertex -701.412 191.163 53.195 + vertex -700.281 183.931 53.7967 + endloop + endfacet + facet normal -0.732442 -0.0581434 0.678342 + outer loop + vertex -700.281 183.931 53.7967 + vertex -701.412 191.163 53.195 + vertex -701.296 184.076 52.7132 + endloop + endfacet + facet normal -0.732822 -0.0884022 0.674653 + outer loop + vertex -700.281 183.931 53.7967 + vertex -701.296 184.076 52.7132 + vertex -699.921 176.427 53.2039 + endloop + endfacet + facet normal -0.72808 -0.0885774 0.679745 + outer loop + vertex -699.921 176.427 53.2039 + vertex -698.751 176.545 54.4732 + vertex -700.281 183.931 53.7967 + endloop + endfacet + facet normal -0.732106 -0.0898239 0.675242 + outer loop + vertex -698.531 182.701 55.5298 + vertex -700.281 183.931 53.7967 + vertex -698.751 176.545 54.4732 + endloop + endfacet + facet normal -0.729117 -0.0904694 0.678383 + outer loop + vertex -697.494 175.207 55.645 + vertex -698.531 182.701 55.5298 + vertex -698.751 176.545 54.4732 + endloop + endfacet + facet normal -0.749258 -0.135805 0.648205 + outer loop + vertex -697.494 175.207 55.645 + vertex -698.751 176.545 54.4732 + vertex -697.149 170.734 55.1068 + endloop + endfacet + facet normal -0.749011 -0.13582 0.648487 + outer loop + vertex -696.013 170.672 56.4058 + vertex -697.494 175.207 55.645 + vertex -697.149 170.734 55.1068 + endloop + endfacet + facet normal -0.744605 -0.180994 0.642498 + outer loop + vertex -696.013 170.672 56.4058 + vertex -697.149 170.734 55.1068 + vertex -695.359 166.094 55.8746 + endloop + endfacet + facet normal -0.765772 -0.181074 0.617094 + outer loop + vertex -694.258 166.187 57.2675 + vertex -696.013 170.672 56.4058 + vertex -695.359 166.094 55.8746 + endloop + endfacet + facet normal -0.76786 -0.182469 0.614081 + outer loop + vertex -694.925 170.777 57.7976 + vertex -696.013 170.672 56.4058 + vertex -694.258 166.187 57.2675 + endloop + endfacet + facet normal -0.789359 -0.182373 0.586219 + outer loop + vertex -693.224 166.392 58.7243 + vertex -694.925 170.777 57.7976 + vertex -694.258 166.187 57.2675 + endloop + endfacet + facet normal -0.791385 -0.183836 0.583021 + outer loop + vertex -693.91 170.988 59.2424 + vertex -694.925 170.777 57.7976 + vertex -693.224 166.392 58.7243 + endloop + endfacet + facet normal -0.81237 -0.183638 0.553473 + outer loop + vertex -692.273 166.638 60.2011 + vertex -693.91 170.988 59.2424 + vertex -693.224 166.392 58.7243 + endloop + endfacet + facet normal -0.813515 -0.184503 0.5515 + outer loop + vertex -692.975 171.238 60.7046 + vertex -693.91 170.988 59.2424 + vertex -692.273 166.638 60.2011 + endloop + endfacet + facet normal -0.83206 -0.184235 0.523196 + outer loop + vertex -691.404 166.893 61.6727 + vertex -692.975 171.238 60.7046 + vertex -692.273 166.638 60.2011 + endloop + endfacet + facet normal -0.832658 -0.1847 0.522079 + outer loop + vertex -692.119 171.488 62.1595 + vertex -692.975 171.238 60.7046 + vertex -691.404 166.893 61.6727 + endloop + endfacet + facet normal -0.847906 -0.184417 0.497037 + outer loop + vertex -690.599 167.168 63.1484 + vertex -692.119 171.488 62.1595 + vertex -691.404 166.893 61.6727 + endloop + endfacet + facet normal -0.849797 -0.185956 0.493219 + outer loop + vertex -691.329 171.751 63.6183 + vertex -692.119 171.488 62.1595 + vertex -690.599 167.168 63.1484 + endloop + endfacet + facet normal -0.864379 -0.185624 0.467325 + outer loop + vertex -689.845 167.462 64.6601 + vertex -691.329 171.751 63.6183 + vertex -690.599 167.168 63.1484 + endloop + endfacet + facet normal -0.864641 -0.185855 0.466748 + outer loop + vertex -690.581 172.044 65.122 + vertex -691.329 171.751 63.6183 + vertex -689.845 167.462 64.6601 + endloop + endfacet + facet normal -0.876986 -0.185471 0.443278 + outer loop + vertex -689.113 167.806 66.2525 + vertex -690.581 172.044 65.122 + vertex -689.845 167.462 64.6601 + endloop + endfacet + facet normal -0.878841 -0.187305 0.438812 + outer loop + vertex -689.86 172.371 66.7039 + vertex -690.581 172.044 65.122 + vertex -689.113 167.806 66.2525 + endloop + endfacet + facet normal -0.889422 -0.186893 0.417132 + outer loop + vertex -688.403 168.185 67.9363 + vertex -689.86 172.371 66.7039 + vertex -689.113 167.806 66.2525 + endloop + endfacet + facet normal -0.890802 -0.188452 0.41347 + outer loop + vertex -689.161 172.728 68.3742 + vertex -689.86 172.371 66.7039 + vertex -688.403 168.185 67.9363 + endloop + endfacet + facet normal -0.899558 -0.18806 0.394245 + outer loop + vertex -687.716 168.6 69.7004 + vertex -689.161 172.728 68.3742 + vertex -688.403 168.185 67.9363 + endloop + endfacet + facet normal -0.900746 -0.189586 0.390787 + outer loop + vertex -688.485 173.121 70.1212 + vertex -689.161 172.728 68.3742 + vertex -687.716 168.6 69.7004 + endloop + endfacet + facet normal -0.909486 -0.189157 0.370209 + outer loop + vertex -687.071 169.031 71.5063 + vertex -688.485 173.121 70.1212 + vertex -687.716 168.6 69.7004 + endloop + endfacet + facet normal -0.910495 -0.190603 0.366973 + outer loop + vertex -687.853 173.528 71.9014 + vertex -688.485 173.121 70.1212 + vertex -687.071 169.031 71.5063 + endloop + endfacet + facet normal -0.918368 -0.190218 0.347013 + outer loop + vertex -686.478 169.473 73.318 + vertex -687.853 173.528 71.9014 + vertex -687.071 169.031 71.5063 + endloop + endfacet + facet normal -0.918662 -0.190679 0.345979 + outer loop + vertex -687.268 173.957 73.691 + vertex -687.853 173.528 71.9014 + vertex -686.478 169.473 73.318 + endloop + endfacet + facet normal -0.92572 -0.19033 0.32683 + outer loop + vertex -685.937 169.931 75.1176 + vertex -687.268 173.957 73.691 + vertex -686.478 169.473 73.318 + endloop + endfacet + facet normal -0.92665 -0.191906 0.323252 + outer loop + vertex -686.739 174.395 75.4689 + vertex -687.268 173.957 73.691 + vertex -685.937 169.931 75.1176 + endloop + endfacet + facet normal -0.932568 -0.191607 0.305946 + outer loop + vertex -685.446 170.393 76.9022 + vertex -686.739 174.395 75.4689 + vertex -685.937 169.931 75.1176 + endloop + endfacet + facet normal -0.93246 -0.191409 0.3064 + outer loop + vertex -686.25 174.852 77.2402 + vertex -686.739 174.395 75.4689 + vertex -685.446 170.393 76.9022 + endloop + endfacet + facet normal -0.938239 -0.191089 0.288432 + outer loop + vertex -684.992 170.851 78.6843 + vertex -686.25 174.852 77.2402 + vertex -685.446 170.393 76.9022 + endloop + endfacet + facet normal -0.938214 -0.191042 0.288543 + outer loop + vertex -685.797 175.296 79.01 + vertex -686.25 174.852 77.2402 + vertex -684.992 170.851 78.6843 + endloop + endfacet + facet normal -0.942943 -0.190752 0.272896 + outer loop + vertex -684.564 171.3 80.4752 + vertex -685.797 175.296 79.01 + vertex -684.992 170.851 78.6843 + endloop + endfacet + facet normal -0.943328 -0.191571 0.270985 + outer loop + vertex -685.373 175.722 80.7849 + vertex -685.797 175.296 79.01 + vertex -684.564 171.3 80.4752 + endloop + endfacet + facet normal -0.948934 -0.191192 0.250936 + outer loop + vertex -684.177 171.738 82.2718 + vertex -685.373 175.722 80.7849 + vertex -684.564 171.3 80.4752 + endloop + endfacet + facet normal -0.948969 -0.191274 0.250745 + outer loop + vertex -684.989 176.163 82.5741 + vertex -685.373 175.722 80.7849 + vertex -684.177 171.738 82.2718 + endloop + endfacet + facet normal -0.954212 -0.190842 0.230346 + outer loop + vertex -683.839 172.216 84.0716 + vertex -684.989 176.163 82.5741 + vertex -684.177 171.738 82.2718 + endloop + endfacet + facet normal -0.954699 -0.192181 0.227193 + outer loop + vertex -684.661 176.683 84.3919 + vertex -684.989 176.163 82.5741 + vertex -683.839 172.216 84.0716 + endloop + endfacet + facet normal -0.957314 -0.191873 0.216183 + outer loop + vertex -683.534 172.758 85.8998 + vertex -684.661 176.683 84.3919 + vertex -683.839 172.216 84.0716 + endloop + endfacet + facet normal -0.957586 -0.192701 0.214231 + outer loop + vertex -684.388 177.42 86.2753 + vertex -684.661 176.683 84.3919 + vertex -683.534 172.758 85.8998 + endloop + endfacet + facet normal -0.958656 -0.192521 0.20956 + outer loop + vertex -683.257 173.465 87.8166 + vertex -684.388 177.42 86.2753 + vertex -683.534 172.758 85.8998 + endloop + endfacet + facet normal -0.957841 -0.189957 0.215541 + outer loop + vertex -684.173 178.605 88.2759 + vertex -684.388 177.42 86.2753 + vertex -683.257 173.465 87.8166 + endloop + endfacet + facet normal -0.959794 -0.189545 0.207046 + outer loop + vertex -683.257 173.465 87.8166 + vertex -683.011 174.445 89.8535 + vertex -684.173 178.605 88.2759 + endloop + endfacet + facet normal -0.952706 -0.17075 0.251386 + outer loop + vertex -684.173 178.605 88.2759 + vertex -683.011 174.445 89.8535 + vertex -683.977 181.229 90.8002 + endloop + endfacet + facet normal -0.96705 -0.164793 0.194056 + outer loop + vertex -682.64 174.435 91.6964 + vertex -683.977 181.229 90.8002 + vertex -683.011 174.445 89.8535 + endloop + endfacet + facet normal -0.972943 -0.171064 0.155302 + outer loop + vertex -682.64 174.435 91.6964 + vertex -682.626 175.948 93.4511 + vertex -683.977 181.229 90.8002 + endloop + endfacet + facet normal -0.971369 -0.16086 0.174831 + outer loop + vertex -683.49 182.525 94.7022 + vertex -683.977 181.229 90.8002 + vertex -682.626 175.948 93.4511 + endloop + endfacet + facet normal -0.974381 -0.158375 0.159686 + outer loop + vertex -682.256 175.667 95.4279 + vertex -683.49 182.525 94.7022 + vertex -682.626 175.948 93.4511 + endloop + endfacet + facet normal -0.977895 -0.161903 0.132317 + outer loop + vertex -682.256 175.667 95.4279 + vertex -682.238 177.003 97.1948 + vertex -683.49 182.525 94.7022 + endloop + endfacet + facet normal -0.977307 -0.157612 0.141529 + outer loop + vertex -683.111 183.522 98.4288 + vertex -683.49 182.525 94.7022 + vertex -682.238 177.003 97.1948 + endloop + endfacet + facet normal -0.976731 -0.158163 0.144848 + outer loop + vertex -681.885 176.6 99.1351 + vertex -683.111 183.522 98.4288 + vertex -682.238 177.003 97.1948 + endloop + endfacet + facet normal -0.979874 -0.161532 0.11728 + outer loop + vertex -681.885 176.6 99.1351 + vertex -681.89 177.908 100.894 + vertex -683.111 183.522 98.4288 + endloop + endfacet + facet normal -0.979578 -0.158832 0.123284 + outer loop + vertex -682.788 184.393 102.12 + vertex -683.111 183.522 98.4288 + vertex -681.89 177.908 100.894 + endloop + endfacet + facet normal -0.979215 -0.159227 0.125641 + outer loop + vertex -681.574 177.503 102.844 + vertex -682.788 184.393 102.12 + vertex -681.89 177.908 100.894 + endloop + endfacet + facet normal -0.98155 -0.162203 0.10124 + outer loop + vertex -681.574 177.503 102.844 + vertex -681.607 178.815 104.627 + vertex -682.788 184.393 102.12 + endloop + endfacet + facet normal -0.981329 -0.159057 0.108136 + outer loop + vertex -682.518 185.261 105.847 + vertex -682.788 184.393 102.12 + vertex -681.607 178.815 104.627 + endloop + endfacet + facet normal -0.980405 -0.160166 0.114686 + outer loop + vertex -681.311 178.425 106.612 + vertex -682.518 185.261 105.847 + vertex -681.607 178.815 104.627 + endloop + endfacet + facet normal -0.982777 -0.163856 0.0854393 + outer loop + vertex -681.311 178.425 106.612 + vertex -681.372 179.728 108.408 + vertex -682.518 185.261 105.847 + endloop + endfacet + facet normal -0.982636 -0.159473 0.0948449 + outer loop + vertex -682.297 186.139 109.611 + vertex -682.518 185.261 105.847 + vertex -681.372 179.728 108.408 + endloop + endfacet + facet normal -0.981923 -0.160424 0.100455 + outer loop + vertex -681.103 179.33 110.406 + vertex -682.297 186.139 109.611 + vertex -681.372 179.728 108.408 + endloop + endfacet + facet normal -0.983696 -0.163793 0.074262 + outer loop + vertex -681.103 179.33 110.406 + vertex -681.181 180.614 112.2 + vertex -682.297 186.139 109.611 + endloop + endfacet + facet normal -0.983667 -0.159437 0.083544 + outer loop + vertex -682.116 187.002 113.382 + vertex -682.297 186.139 109.611 + vertex -681.181 180.614 112.2 + endloop + endfacet + facet normal -0.982521 -0.161077 0.0933107 + outer loop + vertex -680.923 180.195 114.195 + vertex -682.116 187.002 113.382 + vertex -681.181 180.614 112.2 + endloop + endfacet + facet normal -0.984138 -0.164603 0.0661688 + outer loop + vertex -680.923 180.195 114.195 + vertex -681.014 181.453 115.971 + vertex -682.116 187.002 113.382 + endloop + endfacet + facet normal -0.984182 -0.159871 0.0763306 + outer loop + vertex -681.96 187.825 117.129 + vertex -682.116 187.002 113.382 + vertex -681.014 181.453 115.971 + endloop + endfacet + facet normal -0.983678 -0.160654 0.0810485 + outer loop + vertex -680.778 180.999 117.94 + vertex -681.96 187.825 117.129 + vertex -681.014 181.453 115.971 + endloop + endfacet + facet normal -0.984981 -0.164148 0.0535574 + outer loop + vertex -680.778 180.999 117.94 + vertex -680.888 182.233 119.693 + vertex -681.96 187.825 117.129 + endloop + endfacet + facet normal -0.985138 -0.159428 0.0639176 + outer loop + vertex -681.844 188.61 120.864 + vertex -681.96 187.825 117.129 + vertex -680.888 182.233 119.693 + endloop + endfacet + facet normal -0.984502 -0.160552 0.0705604 + outer loop + vertex -680.67 181.757 121.656 + vertex -681.844 188.61 120.864 + vertex -680.888 182.233 119.693 + endloop + endfacet + facet normal -0.985461 -0.163557 0.0459942 + outer loop + vertex -680.67 181.757 121.656 + vertex -680.791 182.992 123.444 + vertex -681.844 188.61 120.864 + endloop + endfacet + facet normal -0.985734 -0.157612 0.0590502 + outer loop + vertex -681.737 189.362 124.66 + vertex -681.844 188.61 120.864 + vertex -680.791 182.992 123.444 + endloop + endfacet + facet normal -0.984897 -0.159206 0.0680529 + outer loop + vertex -680.574 182.507 125.462 + vertex -681.737 189.362 124.66 + vertex -680.791 182.992 123.444 + endloop + endfacet + facet normal -0.985776 -0.162147 0.044206 + outer loop + vertex -680.574 182.507 125.462 + vertex -680.686 183.69 127.3 + vertex -681.737 189.362 124.66 + endloop + endfacet + facet normal -0.986053 -0.156791 0.0558189 + outer loop + vertex -681.621 190.017 128.549 + vertex -681.737 189.362 124.66 + vertex -680.686 183.69 127.3 + endloop + endfacet + facet normal -0.984546 -0.159725 0.0718152 + outer loop + vertex -680.44 183.104 129.368 + vertex -681.621 190.017 128.549 + vertex -680.686 183.69 127.3 + endloop + endfacet + facet normal -0.98552 -0.162775 0.0474757 + outer loop + vertex -680.44 183.104 129.368 + vertex -680.533 184.216 131.252 + vertex -681.621 190.017 128.549 + endloop + endfacet + facet normal -0.985647 -0.160437 0.0525438 + outer loop + vertex -681.501 190.579 132.516 + vertex -681.621 190.017 128.549 + vertex -680.533 184.216 131.252 + endloop + endfacet + facet normal -0.985014 -0.16178 0.0597897 + outer loop + vertex -680.307 183.618 133.355 + vertex -681.501 190.579 132.516 + vertex -680.533 184.216 131.252 + endloop + endfacet + facet normal -0.985664 -0.164665 0.0367669 + outer loop + vertex -680.307 183.618 133.355 + vertex -680.427 184.762 135.247 + vertex -681.501 190.579 132.516 + endloop + endfacet + facet normal -0.985935 -0.16111 0.0444454 + outer loop + vertex -681.41 191.123 136.503 + vertex -681.501 190.579 132.516 + vertex -680.427 184.762 135.247 + endloop + endfacet + facet normal -0.985176 -0.16286 0.0539045 + outer loop + vertex -680.209 184.138 137.349 + vertex -681.41 191.123 136.503 + vertex -680.427 184.762 135.247 + endloop + endfacet + facet normal -0.985676 -0.165628 0.0317792 + outer loop + vertex -680.209 184.138 137.349 + vertex -680.337 185.261 139.222 + vertex -681.41 191.123 136.503 + endloop + endfacet + facet normal -0.985936 -0.162698 0.0381965 + outer loop + vertex -681.346 191.655 140.422 + vertex -681.41 191.123 136.503 + vertex -680.337 185.261 139.222 + endloop + endfacet + facet normal -0.985542 -0.16368 0.0437604 + outer loop + vertex -680.145 184.651 141.279 + vertex -681.346 191.655 140.422 + vertex -680.337 185.261 139.222 + endloop + endfacet + facet normal -0.985807 -0.167108 0.016096 + outer loop + vertex -680.145 184.651 141.279 + vertex -680.305 185.772 143.086 + vertex -681.346 191.655 140.422 + endloop + endfacet + facet normal -0.986567 -0.160307 0.0314156 + outer loop + vertex -681.299 192.117 144.259 + vertex -681.346 191.655 140.422 + vertex -680.305 185.772 143.086 + endloop + endfacet + facet normal -0.985996 -0.161845 0.0402188 + outer loop + vertex -680.116 185.112 145.082 + vertex -681.299 192.117 144.259 + vertex -680.305 185.772 143.086 + endloop + endfacet + facet normal -0.986213 -0.164097 0.0213559 + outer loop + vertex -680.116 185.112 145.082 + vertex -680.252 186.167 146.873 + vertex -681.299 192.117 144.259 + endloop + endfacet + facet normal -0.986524 -0.16118 0.0281227 + outer loop + vertex -681.251 192.488 148.081 + vertex -681.299 192.117 144.259 + vertex -680.252 186.167 146.873 + endloop + endfacet + facet normal -0.985699 -0.163484 0.040864 + outer loop + vertex -680.051 185.453 148.879 + vertex -681.251 192.488 148.081 + vertex -680.252 186.167 146.873 + endloop + endfacet + facet normal -0.985937 -0.166375 0.0157389 + outer loop + vertex -680.051 185.453 148.879 + vertex -680.197 186.49 150.703 + vertex -681.251 192.488 148.081 + endloop + endfacet + facet normal -0.986485 -0.161653 0.0267638 + outer loop + vertex -681.199 192.808 151.925 + vertex -681.251 192.488 148.081 + vertex -680.197 186.49 150.703 + endloop + endfacet + facet normal -0.985824 -0.163586 0.0373016 + outer loop + vertex -680 185.766 152.737 + vertex -681.199 192.808 151.925 + vertex -680.197 186.49 150.703 + endloop + endfacet + facet normal -0.985932 -0.166934 0.00843023 + outer loop + vertex -680 185.766 152.737 + vertex -680.156 186.782 154.568 + vertex -681.199 192.808 151.925 + endloop + endfacet + facet normal -0.9866 -0.161908 0.0201541 + outer loop + vertex -681.164 193.076 155.771 + vertex -681.199 192.808 151.925 + vertex -680.156 186.782 154.568 + endloop + endfacet + facet normal -0.986035 -0.163759 0.0303031 + outer loop + vertex -679.968 186.027 156.6 + vertex -681.164 193.076 155.771 + vertex -680.156 186.782 154.568 + endloop + endfacet + facet normal -0.985978 -0.166821 0.00416068 + outer loop + vertex -679.968 186.027 156.6 + vertex -680.126 187.008 158.418 + vertex -681.164 193.076 155.771 + endloop + endfacet + facet normal -0.986757 -0.161295 0.0171339 + outer loop + vertex -681.131 193.284 159.618 + vertex -681.164 193.076 155.771 + vertex -680.126 187.008 158.418 + endloop + endfacet + facet normal -0.986233 -0.163123 0.027136 + outer loop + vertex -679.94 186.215 160.446 + vertex -681.131 193.284 159.618 + vertex -680.126 187.008 158.418 + endloop + endfacet + facet normal -0.986114 -0.166057 0.00191758 + outer loop + vertex -679.94 186.215 160.446 + vertex -680.098 187.175 162.275 + vertex -681.131 193.284 159.618 + endloop + endfacet + facet normal -0.986887 -0.160772 0.0143684 + outer loop + vertex -681.1 193.439 163.495 + vertex -681.131 193.284 159.618 + vertex -680.098 187.175 162.275 + endloop + endfacet + facet normal -0.986627 -0.161786 0.0197893 + outer loop + vertex -679.922 186.358 164.326 + vertex -681.1 193.439 163.495 + vertex -680.098 187.175 162.275 + endloop + endfacet + facet normal -0.986426 -0.164202 -0.00108399 + outer loop + vertex -679.922 186.358 164.326 + vertex -680.081 187.3 166.186 + vertex -681.1 193.439 163.495 + endloop + endfacet + facet normal -0.986831 -0.161686 0.004809 + outer loop + vertex -681.098 193.541 167.419 + vertex -681.1 193.439 163.495 + vertex -680.081 187.3 166.186 + endloop + endfacet + facet normal -0.986463 -0.163402 0.0138032 + outer loop + vertex -679.912 186.452 168.268 + vertex -681.098 193.541 167.419 + vertex -680.081 187.3 166.186 + endloop + endfacet + facet normal -0.986151 -0.165735 -0.00610664 + outer loop + vertex -679.912 186.452 168.268 + vertex -680.076 187.362 170.145 + vertex -681.098 193.541 167.419 + endloop + endfacet + facet normal -0.986924 -0.161121 0.00464324 + outer loop + vertex -681.087 193.586 171.369 + vertex -681.098 193.541 167.419 + vertex -680.076 187.362 170.145 + endloop + endfacet + facet normal -0.986725 -0.162106 0.00981687 + outer loop + vertex -679.911 186.482 172.237 + vertex -681.087 193.586 171.369 + vertex -680.076 187.362 170.145 + endloop + endfacet + facet normal -0.986328 -0.16448 -0.0101511 + outer loop + vertex -679.911 186.482 172.237 + vertex -680.077 187.364 174.106 + vertex -681.087 193.586 171.369 + endloop + endfacet + facet normal -0.986884 -0.161403 -0.00294876 + outer loop + vertex -681.096 193.571 175.293 + vertex -681.087 193.586 171.369 + vertex -680.077 187.364 174.106 + endloop + endfacet + facet normal -0.986556 -0.163268 0.00707793 + outer loop + vertex -679.911 186.452 176.179 + vertex -681.096 193.571 175.293 + vertex -680.077 187.364 174.106 + endloop + endfacet + facet normal -0.986017 -0.165951 -0.0152045 + outer loop + vertex -679.911 186.452 176.179 + vertex -680.083 187.303 177.998 + vertex -681.096 193.571 175.293 + endloop + endfacet + facet normal -0.986939 -0.161059 -0.003519 + outer loop + vertex -681.096 193.486 179.129 + vertex -681.096 193.571 175.293 + vertex -680.083 187.303 177.998 + endloop + endfacet + facet normal -0.986708 -0.162446 0.00427402 + outer loop + vertex -679.917 186.352 180.002 + vertex -681.096 193.486 179.129 + vertex -680.083 187.303 177.998 + endloop + endfacet + facet normal -0.986057 -0.165256 -0.0195569 + outer loop + vertex -679.917 186.352 180.002 + vertex -680.087 187.159 181.753 + vertex -681.096 193.486 179.129 + endloop + endfacet + facet normal -0.987111 -0.159913 -0.00626792 + outer loop + vertex -681.094 193.328 182.887 + vertex -681.096 193.486 179.129 + vertex -680.087 187.159 181.753 + endloop + endfacet + facet normal -0.98677 -0.162029 0.00554739 + outer loop + vertex -679.914 186.172 183.711 + vertex -681.094 193.328 182.887 + vertex -680.087 187.159 181.753 + endloop + endfacet + facet normal -0.985943 -0.16532 -0.0241921 + outer loop + vertex -679.914 186.172 183.711 + vertex -680.093 186.977 185.489 + vertex -681.094 193.328 182.887 + endloop + endfacet + facet normal -0.986725 -0.161701 -0.0150615 + outer loop + vertex -681.122 193.146 186.685 + vertex -681.094 193.328 182.887 + vertex -680.093 186.977 185.489 + endloop + endfacet + facet normal -0.986669 -0.162307 -0.0118857 + outer loop + vertex -679.958 186.008 187.513 + vertex -681.122 193.146 186.685 + vertex -680.093 186.977 185.489 + endloop + endfacet + facet normal -0.985765 -0.1647 -0.0337949 + outer loop + vertex -679.958 186.008 187.513 + vertex -680.158 186.824 189.374 + vertex -681.122 193.146 186.685 + endloop + endfacet + facet normal -0.986838 -0.160119 -0.0226374 + outer loop + vertex -681.18 192.949 190.589 + vertex -681.122 193.146 186.685 + vertex -680.158 186.824 189.374 + endloop + endfacet + facet normal -0.986754 -0.16144 -0.015908 + outer loop + vertex -680.029 185.825 191.488 + vertex -681.18 192.949 190.589 + vertex -680.158 186.824 189.374 + endloop + endfacet + facet normal -0.98588 -0.163724 -0.0351328 + outer loop + vertex -680.029 185.825 191.488 + vertex -680.223 186.588 193.392 + vertex -681.18 192.949 190.589 + endloop + endfacet + facet normal -0.986818 -0.159759 -0.0258159 + outer loop + vertex -681.242 192.691 194.556 + vertex -681.18 192.949 190.589 + vertex -680.223 186.588 193.392 + endloop + endfacet + facet normal -0.986808 -0.160126 -0.0238842 + outer loop + vertex -680.11 185.574 195.526 + vertex -681.242 192.691 194.556 + vertex -680.223 186.588 193.392 + endloop + endfacet + facet normal -0.985845 -0.162397 -0.041669 + outer loop + vertex -680.11 185.574 195.526 + vertex -680.309 186.302 197.394 + vertex -681.242 192.691 194.556 + endloop + endfacet + facet normal -0.987152 -0.157081 -0.0292718 + outer loop + vertex -681.302 192.333 198.526 + vertex -681.242 192.691 194.556 + vertex -680.309 186.302 197.394 + endloop + endfacet + facet normal -0.987079 -0.159268 -0.0175562 + outer loop + vertex -680.171 185.214 199.506 + vertex -681.302 192.333 198.526 + vertex -680.309 186.302 197.394 + endloop + endfacet + facet normal -0.985928 -0.162225 -0.0403712 + outer loop + vertex -680.171 185.214 199.506 + vertex -680.356 185.88 201.343 + vertex -681.302 192.333 198.526 + endloop + endfacet + facet normal -0.986873 -0.158425 -0.0313473 + outer loop + vertex -681.357 191.899 202.433 + vertex -681.302 192.333 198.526 + vertex -680.356 185.88 201.343 + endloop + endfacet + facet normal -0.98686 -0.159938 -0.0229787 + outer loop + vertex -680.222 184.76 203.394 + vertex -681.357 191.899 202.433 + vertex -680.356 185.88 201.343 + endloop + endfacet + facet normal -0.985206 -0.163496 -0.0513606 + outer loop + vertex -680.222 184.76 203.394 + vertex -680.423 185.419 205.148 + vertex -681.357 191.899 202.433 + endloop + endfacet + facet normal -0.986898 -0.157288 -0.03596 + outer loop + vertex -681.42 191.426 206.237 + vertex -681.357 191.899 202.433 + vertex -680.423 185.419 205.148 + endloop + endfacet + facet normal -0.986924 -0.158781 -0.02775 + outer loop + vertex -680.296 184.287 207.119 + vertex -681.42 191.426 206.237 + vertex -680.423 185.419 205.148 + endloop + endfacet + facet normal -0.985377 -0.161734 -0.0536146 + outer loop + vertex -680.296 184.287 207.119 + vertex -680.496 184.919 208.886 + vertex -681.42 191.426 206.237 + endloop + endfacet + facet normal -0.986703 -0.157083 -0.0417286 + outer loop + vertex -681.497 190.896 210.059 + vertex -681.42 191.426 206.237 + vertex -680.496 184.919 208.886 + endloop + endfacet + facet normal -0.98676 -0.159109 -0.0314567 + outer loop + vertex -680.372 183.748 210.924 + vertex -681.497 190.896 210.059 + vertex -680.496 184.919 208.886 + endloop + endfacet + facet normal -0.98501 -0.162149 -0.058842 + outer loop + vertex -680.372 183.748 210.924 + vertex -680.581 184.335 212.796 + vertex -681.497 190.896 210.059 + endloop + endfacet + facet normal -0.986329 -0.157714 -0.0477676 + outer loop + vertex -681.59 190.289 213.985 + vertex -681.497 190.896 210.059 + vertex -680.581 184.335 212.796 + endloop + endfacet + facet normal -0.986421 -0.159254 -0.0401384 + outer loop + vertex -680.471 183.115 214.928 + vertex -681.59 190.289 213.985 + vertex -680.581 184.335 212.796 + endloop + endfacet + facet normal -0.985011 -0.161664 -0.0601512 + outer loop + vertex -680.471 183.115 214.928 + vertex -680.677 183.669 216.812 + vertex -681.59 190.289 213.985 + endloop + endfacet + facet normal -0.986334 -0.157211 -0.0492958 + outer loop + vertex -681.68 189.617 217.93 + vertex -681.59 190.289 213.985 + vertex -680.677 183.669 216.812 + endloop + endfacet + facet normal -0.986427 -0.158285 -0.0436671 + outer loop + vertex -680.57 182.422 218.913 + vertex -681.68 189.617 217.93 + vertex -680.677 183.669 216.812 + endloop + endfacet + facet normal -0.984677 -0.161155 -0.0666298 + outer loop + vertex -680.57 182.422 218.913 + vertex -680.78 182.962 220.717 + vertex -681.68 189.617 217.93 + endloop + endfacet + facet normal -0.985705 -0.157946 -0.0586364 + outer loop + vertex -681.796 188.899 221.801 + vertex -681.68 189.617 217.93 + vertex -680.78 182.962 220.717 + endloop + endfacet + facet normal -0.986 -0.160358 -0.0456997 + outer loop + vertex -680.668 181.697 222.747 + vertex -681.796 188.899 221.801 + vertex -680.78 182.962 220.717 + endloop + endfacet + facet normal -0.983419 -0.164092 -0.0772141 + outer loop + vertex -680.668 181.697 222.747 + vertex -680.894 182.216 224.523 + vertex -681.796 188.899 221.801 + endloop + endfacet + facet normal -0.985267 -0.158777 -0.0635534 + outer loop + vertex -681.919 188.132 225.634 + vertex -681.796 188.899 221.801 + vertex -680.894 182.216 224.523 + endloop + endfacet + facet normal -0.985557 -0.160776 -0.0531851 + outer loop + vertex -680.793 180.922 226.552 + vertex -681.919 188.132 225.634 + vertex -680.894 182.216 224.523 + endloop + endfacet + facet normal -0.982814 -0.16429 -0.0841769 + outer loop + vertex -680.793 180.922 226.552 + vertex -681.029 181.412 228.353 + vertex -681.919 188.132 225.634 + endloop + endfacet + facet normal -0.985 -0.158303 -0.0686606 + outer loop + vertex -682.055 187.319 229.452 + vertex -681.919 188.132 225.634 + vertex -681.029 181.412 228.353 + endloop + endfacet + facet normal -0.985186 -0.159292 -0.0635209 + outer loop + vertex -680.947 180.09 230.39 + vertex -682.055 187.319 229.452 + vertex -681.029 181.412 228.353 + endloop + endfacet + facet normal -0.982239 -0.16272 -0.093423 + outer loop + vertex -680.947 180.09 230.39 + vertex -681.193 180.567 232.154 + vertex -682.055 187.319 229.452 + endloop + endfacet + facet normal -0.984089 -0.158053 -0.0811689 + outer loop + vertex -682.229 186.487 233.181 + vertex -682.055 187.319 229.452 + vertex -681.193 180.567 232.154 + endloop + endfacet + facet normal -0.984413 -0.15924 -0.0746572 + outer loop + vertex -681.128 179.24 234.12 + vertex -682.229 186.487 233.181 + vertex -681.193 180.567 232.154 + endloop + endfacet + facet normal -0.981257 -0.162507 -0.103569 + outer loop + vertex -681.128 179.24 234.12 + vertex -681.385 179.724 235.798 + vertex -682.229 186.487 233.181 + endloop + endfacet + facet normal -0.983248 -0.157909 -0.0910409 + outer loop + vertex -682.429 185.653 236.794 + vertex -682.229 186.487 233.181 + vertex -681.385 179.724 235.798 + endloop + endfacet + facet normal -0.983767 -0.159472 -0.0822863 + outer loop + vertex -681.329 178.4 237.694 + vertex -682.429 185.653 236.794 + vertex -681.385 179.724 235.798 + endloop + endfacet + facet normal -0.9793 -0.163404 -0.119462 + outer loop + vertex -681.329 178.4 237.694 + vertex -681.612 178.878 239.357 + vertex -682.429 185.653 236.794 + endloop + endfacet + facet normal -0.981644 -0.158579 -0.10596 + outer loop + vertex -682.677 184.793 240.38 + vertex -682.429 185.653 236.794 + vertex -681.612 178.878 239.357 + endloop + endfacet + facet normal -0.981978 -0.159403 -0.101541 + outer loop + vertex -681.592 177.537 241.271 + vertex -682.677 184.793 240.38 + vertex -681.612 178.878 239.357 + endloop + endfacet + facet normal -0.977803 -0.162548 -0.132208 + outer loop + vertex -681.592 177.537 241.271 + vertex -681.897 177.983 242.981 + vertex -682.677 184.793 240.38 + endloop + endfacet + facet normal -0.980053 -0.158235 -0.120244 + outer loop + vertex -682.974 183.851 244.035 + vertex -682.677 184.793 240.38 + vertex -681.897 177.983 242.981 + endloop + endfacet + facet normal -0.98053 -0.159295 -0.114827 + outer loop + vertex -681.902 176.597 244.944 + vertex -682.974 183.851 244.035 + vertex -681.897 177.983 242.981 + endloop + endfacet + facet normal -0.976743 -0.161955 -0.140511 + outer loop + vertex -681.902 176.597 244.944 + vertex -682.22 176.99 246.703 + vertex -682.974 183.851 244.035 + endloop + endfacet + facet normal -0.978462 -0.158793 -0.131894 + outer loop + vertex -683.313 182.769 247.856 + vertex -682.974 183.851 244.035 + vertex -682.22 176.99 246.703 + endloop + endfacet + facet normal -0.978586 -0.159066 -0.130645 + outer loop + vertex -682.259 175.572 248.724 + vertex -683.313 182.769 247.856 + vertex -682.22 176.99 246.703 + endloop + endfacet + facet normal -0.972851 -0.162362 -0.164924 + outer loop + vertex -682.259 175.572 248.724 + vertex -682.633 175.903 250.601 + vertex -683.313 182.769 247.856 + endloop + endfacet + facet normal -0.973753 -0.160882 -0.161001 + outer loop + vertex -683.781 181.363 252.09 + vertex -683.313 182.769 247.856 + vertex -682.633 175.903 250.601 + endloop + endfacet + facet normal -0.974118 -0.161826 -0.157821 + outer loop + vertex -682.717 174.378 252.682 + vertex -683.781 181.363 252.09 + vertex -682.633 175.903 250.601 + endloop + endfacet + facet normal -0.966869 -0.163931 -0.195682 + outer loop + vertex -682.717 174.378 252.682 + vertex -683.026 174.049 254.486 + vertex -683.781 181.363 252.09 + endloop + endfacet + facet normal -0.953427 -0.178165 -0.243379 + outer loop + vertex -683.026 174.049 254.486 + vertex -683.806 176.714 255.591 + vertex -683.781 181.363 252.09 + endloop + endfacet + facet normal -0.958471 -0.193798 -0.209227 + outer loop + vertex -683.094 172.328 256.391 + vertex -683.806 176.714 255.591 + vertex -683.026 174.049 254.486 + endloop + endfacet + facet normal -0.957382 -0.194418 -0.213593 + outer loop + vertex -683.466 172.567 257.842 + vertex -683.806 176.714 255.591 + vertex -683.094 172.328 256.391 + endloop + endfacet + facet normal -0.961892 -0.187086 -0.199406 + outer loop + vertex -684.322 177.194 257.632 + vertex -683.806 176.714 255.591 + vertex -683.466 172.567 257.842 + endloop + endfacet + facet normal -0.957609 -0.187182 -0.21897 + outer loop + vertex -683.827 172.278 259.667 + vertex -684.322 177.194 257.632 + vertex -683.466 172.567 257.842 + endloop + endfacet + facet normal -0.954659 -0.190829 -0.228496 + outer loop + vertex -684.687 176.586 259.661 + vertex -684.322 177.194 257.632 + vertex -683.827 172.278 259.667 + endloop + endfacet + facet normal -0.952918 -0.19049 -0.235927 + outer loop + vertex -684.173 171.76 261.482 + vertex -684.687 176.586 259.661 + vertex -683.827 172.278 259.667 + endloop + endfacet + facet normal -0.952436 -0.191011 -0.237444 + outer loop + vertex -685.025 176.021 261.473 + vertex -684.687 176.586 259.661 + vertex -684.173 171.76 261.482 + endloop + endfacet + facet normal -0.948223 -0.190206 -0.254352 + outer loop + vertex -684.543 171.272 263.227 + vertex -685.025 176.021 261.473 + vertex -684.173 171.76 261.482 + endloop + endfacet + facet normal -0.94929 -0.189133 -0.251153 + outer loop + vertex -685.394 175.59 263.191 + vertex -685.025 176.021 261.473 + vertex -684.543 171.272 263.227 + endloop + endfacet + facet normal -0.944382 -0.188322 -0.269587 + outer loop + vertex -684.949 170.843 264.95 + vertex -685.394 175.59 263.191 + vertex -684.543 171.272 263.227 + endloop + endfacet + facet normal -0.945663 -0.187087 -0.265931 + outer loop + vertex -685.801 175.22 264.898 + vertex -685.394 175.59 263.191 + vertex -684.949 170.843 264.95 + endloop + endfacet + facet normal -0.940245 -0.186258 -0.285041 + outer loop + vertex -685.392 170.423 266.685 + vertex -685.801 175.22 264.898 + vertex -684.949 170.843 264.95 + endloop + endfacet + facet normal -0.941323 -0.185261 -0.282116 + outer loop + vertex -686.245 174.85 266.625 + vertex -685.801 175.22 264.898 + vertex -685.392 170.423 266.685 + endloop + endfacet + facet normal -0.935537 -0.184404 -0.301275 + outer loop + vertex -685.871 169.991 268.437 + vertex -686.245 174.85 266.625 + vertex -685.392 170.423 266.685 + endloop + endfacet + facet normal -0.935883 -0.184099 -0.300385 + outer loop + vertex -686.728 174.456 268.371 + vertex -686.245 174.85 266.625 + vertex -685.871 169.991 268.437 + endloop + endfacet + facet normal -0.928968 -0.183087 -0.32171 + outer loop + vertex -686.395 169.546 270.202 + vertex -686.728 174.456 268.371 + vertex -685.871 169.991 268.437 + endloop + endfacet + facet normal -0.929184 -0.182907 -0.32119 + outer loop + vertex -687.256 174.045 270.133 + vertex -686.728 174.456 268.371 + vertex -686.395 169.546 270.202 + endloop + endfacet + facet normal -0.921322 -0.181747 -0.343706 + outer loop + vertex -686.969 169.101 271.976 + vertex -687.256 174.045 270.133 + vertex -686.395 169.546 270.202 + endloop + endfacet + facet normal -0.921724 -0.181431 -0.342795 + outer loop + vertex -687.833 173.627 271.904 + vertex -687.256 174.045 270.133 + vertex -686.969 169.101 271.976 + endloop + endfacet + facet normal -0.913755 -0.180251 -0.36409 + outer loop + vertex -687.593 168.677 273.752 + vertex -687.833 173.627 271.904 + vertex -686.969 169.101 271.976 + endloop + endfacet + facet normal -0.913165 -0.180692 -0.365349 + outer loop + vertex -688.459 173.21 273.675 + vertex -687.833 173.627 271.904 + vertex -687.593 168.677 273.752 + endloop + endfacet + facet normal -0.902798 -0.179145 -0.390977 + outer loop + vertex -688.271 168.255 275.512 + vertex -688.459 173.21 273.675 + vertex -687.593 168.677 273.752 + endloop + endfacet + facet normal -0.903307 -0.178789 -0.389964 + outer loop + vertex -689.134 172.802 275.426 + vertex -688.459 173.21 273.675 + vertex -688.271 168.255 275.512 + endloop + endfacet + facet normal -0.891939 -0.177121 -0.41602 + outer loop + vertex -688.999 167.856 277.242 + vertex -689.134 172.802 275.426 + vertex -688.271 168.255 275.512 + endloop + endfacet + facet normal -0.891029 -0.177718 -0.417711 + outer loop + vertex -689.861 172.41 277.144 + vertex -689.134 172.802 275.426 + vertex -688.999 167.856 277.242 + endloop + endfacet + facet normal -0.878517 -0.175917 -0.444142 + outer loop + vertex -689.779 167.482 278.932 + vertex -689.861 172.41 277.144 + vertex -688.999 167.856 277.242 + endloop + endfacet + facet normal -0.878681 -0.175816 -0.443856 + outer loop + vertex -690.634 172.043 278.82 + vertex -689.861 172.41 277.144 + vertex -689.779 167.482 278.932 + endloop + endfacet + facet normal -0.865779 -0.174017 -0.469195 + outer loop + vertex -690.605 167.16 280.578 + vertex -690.634 172.043 278.82 + vertex -689.779 167.482 278.932 + endloop + endfacet + facet normal -0.865285 -0.174304 -0.47 + outer loop + vertex -691.454 171.723 280.448 + vertex -690.634 172.043 278.82 + vertex -690.605 167.16 280.578 + endloop + endfacet + facet normal -0.850587 -0.172333 -0.496793 + outer loop + vertex -691.48 166.879 282.173 + vertex -691.454 171.723 280.448 + vertex -690.605 167.16 280.578 + endloop + endfacet + facet normal -0.836743 -0.226204 -0.498691 + outer loop + vertex -691.48 166.879 282.173 + vertex -690.605 167.16 280.578 + vertex -690.506 162.723 282.424 + endloop + endfacet + facet normal -0.820944 -0.224101 -0.525195 + outer loop + vertex -691.44 162.459 283.996 + vertex -691.48 166.879 282.173 + vertex -690.506 162.723 282.424 + endloop + endfacet + facet normal -0.820525 -0.224327 -0.525753 + outer loop + vertex -692.399 166.626 283.715 + vertex -691.48 166.879 282.173 + vertex -691.44 162.459 283.996 + endloop + endfacet + facet normal -0.801142 -0.221901 -0.555816 + outer loop + vertex -692.421 162.209 285.51 + vertex -692.399 166.626 283.715 + vertex -691.44 162.459 283.996 + endloop + endfacet + facet normal -0.802536 -0.22119 -0.554086 + outer loop + vertex -693.359 166.396 285.197 + vertex -692.399 166.626 283.715 + vertex -692.421 162.209 285.51 + endloop + endfacet + facet normal -0.781516 -0.218739 -0.584282 + outer loop + vertex -693.438 162.002 286.948 + vertex -693.359 166.396 285.197 + vertex -692.421 162.209 285.51 + endloop + endfacet + facet normal -0.782585 -0.218226 -0.583042 + outer loop + vertex -694.367 166.23 286.612 + vertex -693.359 166.396 285.197 + vertex -693.438 162.002 286.948 + endloop + endfacet + facet normal -0.757851 -0.215394 -0.615847 + outer loop + vertex -694.496 161.887 288.29 + vertex -694.367 166.23 286.612 + vertex -693.438 162.002 286.948 + endloop + endfacet + facet normal -0.760127 -0.214378 -0.613392 + outer loop + vertex -695.447 166.215 287.955 + vertex -694.367 166.23 286.612 + vertex -694.496 161.887 288.29 + endloop + endfacet + facet normal -0.730537 -0.210678 -0.649562 + outer loop + vertex -695.609 161.912 289.533 + vertex -695.447 166.215 287.955 + vertex -694.496 161.887 288.29 + endloop + endfacet + facet normal -0.735241 -0.208774 -0.644852 + outer loop + vertex -696.607 166.39 289.222 + vertex -695.447 166.215 287.955 + vertex -695.609 161.912 289.533 + endloop + endfacet + facet normal -0.705449 -0.204474 -0.678625 + outer loop + vertex -696.748 162.033 290.681 + vertex -696.607 166.39 289.222 + vertex -695.609 161.912 289.533 + endloop + endfacet + facet normal -0.699235 -0.257689 -0.666833 + outer loop + vertex -696.748 162.033 290.681 + vertex -695.609 161.912 289.533 + vertex -695.61 157.918 291.078 + endloop + endfacet + facet normal -0.668761 -0.252401 -0.699323 + outer loop + vertex -696.666 157.928 292.084 + vertex -696.748 162.033 290.681 + vertex -695.61 157.918 291.078 + endloop + endfacet + facet normal -0.67376 -0.251026 -0.695006 + outer loop + vertex -697.787 162.001 291.7 + vertex -696.748 162.033 290.681 + vertex -696.666 157.928 292.084 + endloop + endfacet + facet normal -0.650764 -0.246863 -0.718028 + outer loop + vertex -697.57 157.868 292.924 + vertex -697.787 162.001 291.7 + vertex -696.666 157.928 292.084 + endloop + endfacet + facet normal -0.636465 -0.30835 -0.706988 + outer loop + vertex -697.57 157.868 292.924 + vertex -696.666 157.928 292.084 + vertex -696.245 153.954 293.438 + endloop + endfacet + facet normal -0.610147 -0.302747 -0.732164 + outer loop + vertex -696.991 153.924 294.072 + vertex -697.57 157.868 292.924 + vertex -696.245 153.954 293.438 + endloop + endfacet + facet normal -0.597148 -0.354875 -0.71936 + outer loop + vertex -696.991 153.924 294.072 + vertex -696.245 153.954 293.438 + vertex -695.481 149.97 294.77 + endloop + endfacet + facet normal -0.574581 -0.349876 -0.739894 + outer loop + vertex -696.126 150.376 295.078 + vertex -696.991 153.924 294.072 + vertex -695.481 149.97 294.77 + endloop + endfacet + facet normal -0.571304 -0.349805 -0.742461 + outer loop + vertex -697.512 154.022 294.427 + vertex -696.991 153.924 294.072 + vertex -696.126 150.376 295.078 + endloop + endfacet + facet normal -0.541137 -0.342873 -0.76786 + outer loop + vertex -696.51 150.656 295.224 + vertex -697.512 154.022 294.427 + vertex -696.126 150.376 295.078 + endloop + endfacet + facet normal -0.600742 -0.349099 -0.719193 + outer loop + vertex -697.889 154.441 294.539 + vertex -697.512 154.022 294.427 + vertex -696.51 150.656 295.224 + endloop + endfacet + facet normal -0.585871 -0.346132 -0.732767 + outer loop + vertex -696.826 151.213 295.214 + vertex -697.889 154.441 294.539 + vertex -696.51 150.656 295.224 + endloop + endfacet + facet normal -0.830184 -0.362024 -0.423949 + outer loop + vertex -698.286 155.431 294.472 + vertex -697.889 154.441 294.539 + vertex -696.826 151.213 295.214 + endloop + endfacet + facet normal -0.604711 -0.354301 -0.713299 + outer loop + vertex -695.481 149.97 294.77 + vertex -696.245 153.954 293.438 + vertex -694.672 150.08 294.03 + endloop + endfacet + facet normal -0.624052 -0.359192 -0.693931 + outer loop + vertex -696.245 153.954 293.438 + vertex -695.338 154.08 292.557 + vertex -694.672 150.08 294.03 + endloop + endfacet + facet normal -0.628746 -0.358534 -0.690023 + outer loop + vertex -694.672 150.08 294.03 + vertex -695.338 154.08 292.557 + vertex -693.863 150.657 292.992 + endloop + endfacet + facet normal -0.641621 -0.362309 -0.676058 + outer loop + vertex -695.338 154.08 292.557 + vertex -694.316 154.155 291.547 + vertex -693.863 150.657 292.992 + endloop + endfacet + facet normal -0.6353 -0.36365 -0.681287 + outer loop + vertex -693.863 150.657 292.992 + vertex -694.316 154.155 291.547 + vertex -692.847 150.721 292.011 + endloop + endfacet + facet normal -0.659124 -0.37024 -0.654582 + outer loop + vertex -694.316 154.155 291.547 + vertex -693.22 154.155 290.444 + vertex -692.847 150.721 292.011 + endloop + endfacet + facet normal -0.654336 -0.371562 -0.658624 + outer loop + vertex -692.847 150.721 292.011 + vertex -693.22 154.155 290.444 + vertex -691.719 150.695 290.905 + endloop + endfacet + facet normal -0.678007 -0.378069 -0.630374 + outer loop + vertex -693.22 154.155 290.444 + vertex -692.094 154.221 289.194 + vertex -691.719 150.695 290.905 + endloop + endfacet + facet normal -0.676188 -0.378652 -0.631974 + outer loop + vertex -691.719 150.695 290.905 + vertex -692.094 154.221 289.194 + vertex -690.544 150.766 289.605 + endloop + endfacet + facet normal -0.698483 -0.385222 -0.603096 + outer loop + vertex -692.094 154.221 289.194 + vertex -690.974 154.386 287.79 + vertex -690.544 150.766 289.605 + endloop + endfacet + facet normal -0.697564 -0.385543 -0.603955 + outer loop + vertex -690.544 150.766 289.605 + vertex -690.974 154.386 287.79 + vertex -689.382 150.959 288.14 + endloop + endfacet + facet normal -0.718059 -0.392108 -0.575015 + outer loop + vertex -690.974 154.386 287.79 + vertex -689.891 154.626 286.275 + vertex -689.382 150.959 288.14 + endloop + endfacet + facet normal -0.717746 -0.392223 -0.575327 + outer loop + vertex -689.382 150.959 288.14 + vertex -689.891 154.626 286.275 + vertex -688.276 151.22 286.582 + endloop + endfacet + facet normal -0.734804 -0.39796 -0.549264 + outer loop + vertex -689.891 154.626 286.275 + vertex -688.869 154.933 284.685 + vertex -688.276 151.22 286.582 + endloop + endfacet + facet normal -0.736406 -0.397345 -0.547561 + outer loop + vertex -688.276 151.22 286.582 + vertex -688.869 154.933 284.685 + vertex -687.258 151.569 284.959 + endloop + endfacet + facet normal -0.751403 -0.402511 -0.522856 + outer loop + vertex -688.869 154.933 284.685 + vertex -687.916 155.28 283.048 + vertex -687.258 151.569 284.959 + endloop + endfacet + facet normal -0.753209 -0.40178 -0.520815 + outer loop + vertex -687.258 151.569 284.959 + vertex -687.916 155.28 283.048 + vertex -686.313 151.952 283.297 + endloop + endfacet + facet normal -0.766063 -0.406273 -0.498086 + outer loop + vertex -687.916 155.28 283.048 + vertex -687.025 155.653 281.374 + vertex -686.313 151.952 283.297 + endloop + endfacet + facet normal -0.767981 -0.405452 -0.495797 + outer loop + vertex -686.313 151.952 283.297 + vertex -687.025 155.653 281.374 + vertex -685.433 152.365 281.597 + endloop + endfacet + facet normal -0.778472 -0.409186 -0.475972 + outer loop + vertex -687.025 155.653 281.374 + vertex -686.19 156.054 279.663 + vertex -685.433 152.365 281.597 + endloop + endfacet + facet normal -0.781575 -0.40778 -0.472076 + outer loop + vertex -685.433 152.365 281.597 + vertex -686.19 156.054 279.663 + vertex -684.609 152.788 279.868 + endloop + endfacet + facet normal -0.790606 -0.411011 -0.453886 + outer loop + vertex -686.19 156.054 279.663 + vertex -685.411 156.479 277.922 + vertex -684.609 152.788 279.868 + endloop + endfacet + facet normal -0.792659 -0.410032 -0.451182 + outer loop + vertex -684.609 152.788 279.868 + vertex -685.411 156.479 277.922 + vertex -683.843 153.243 278.109 + endloop + endfacet + facet normal -0.801001 -0.413044 -0.433349 + outer loop + vertex -685.411 156.479 277.922 + vertex -684.685 156.926 276.154 + vertex -683.843 153.243 278.109 + endloop + endfacet + facet normal -0.804098 -0.411484 -0.429078 + outer loop + vertex -683.843 153.243 278.109 + vertex -684.685 156.926 276.154 + vertex -683.127 153.701 276.326 + endloop + endfacet + facet normal -0.811268 -0.414076 -0.412778 + outer loop + vertex -684.685 156.926 276.154 + vertex -684.012 157.394 274.362 + vertex -683.127 153.701 276.326 + endloop + endfacet + facet normal -0.81377 -0.412753 -0.409162 + outer loop + vertex -683.127 153.701 276.326 + vertex -684.012 157.394 274.362 + vertex -682.46 154.182 274.515 + endloop + endfacet + facet normal -0.82029 -0.415153 -0.393411 + outer loop + vertex -684.012 157.394 274.362 + vertex -683.391 157.88 272.555 + vertex -682.46 154.182 274.515 + endloop + endfacet + facet normal -0.822766 -0.413788 -0.389662 + outer loop + vertex -682.46 154.182 274.515 + vertex -683.391 157.88 272.555 + vertex -681.843 154.677 272.686 + endloop + endfacet + facet normal -0.828624 -0.416004 -0.374598 + outer loop + vertex -683.391 157.88 272.555 + vertex -682.819 158.374 270.74 + vertex -681.843 154.677 272.686 + endloop + endfacet + facet normal -0.83155 -0.414326 -0.369943 + outer loop + vertex -681.843 154.677 272.686 + vertex -682.819 158.374 270.74 + vertex -681.271 155.167 270.852 + endloop + endfacet + facet normal -0.8359 -0.41601 -0.358062 + outer loop + vertex -682.819 158.374 270.74 + vertex -682.291 158.874 268.925 + vertex -681.271 155.167 270.852 + endloop + endfacet + facet normal -0.838997 -0.414179 -0.352902 + outer loop + vertex -681.271 155.167 270.852 + vertex -682.291 158.874 268.925 + vertex -680.746 155.663 269.023 + endloop + endfacet + facet normal -0.843928 -0.416115 -0.338576 + outer loop + vertex -682.291 158.874 268.925 + vertex -681.805 159.36 267.119 + vertex -680.746 155.663 269.023 + endloop + endfacet + facet normal -0.845404 -0.41521 -0.335996 + outer loop + vertex -680.746 155.663 269.023 + vertex -681.805 159.36 267.119 + vertex -680.268 156.155 267.209 + endloop + endfacet + facet normal -0.849007 -0.416629 -0.324973 + outer loop + vertex -681.805 159.36 267.119 + vertex -681.36 159.855 265.322 + vertex -680.268 156.155 267.209 + endloop + endfacet + facet normal -0.851945 -0.414767 -0.319622 + outer loop + vertex -680.268 156.155 267.209 + vertex -681.36 159.855 265.322 + vertex -679.833 156.648 265.412 + endloop + endfacet + facet normal -0.854563 -0.415777 -0.31121 + outer loop + vertex -681.36 159.855 265.322 + vertex -680.961 160.378 263.525 + vertex -679.833 156.648 265.412 + endloop + endfacet + facet normal -0.857173 -0.414068 -0.306271 + outer loop + vertex -679.833 156.648 265.412 + vertex -680.961 160.378 263.525 + vertex -679.45 157.185 263.614 + endloop + endfacet + facet normal -0.860396 -0.415289 -0.295388 + outer loop + vertex -680.961 160.378 263.525 + vertex -680.605 160.93 261.712 + vertex -679.45 157.185 263.614 + endloop + endfacet + facet normal -0.862399 -0.41391 -0.291456 + outer loop + vertex -679.45 157.185 263.614 + vertex -680.605 160.93 261.712 + vertex -679.099 157.729 261.802 + endloop + endfacet + facet normal -0.866353 -0.415371 -0.277306 + outer loop + vertex -680.605 160.93 261.712 + vertex -680.267 161.451 259.875 + vertex -679.099 157.729 261.802 + endloop + endfacet + facet normal -0.867301 -0.414673 -0.275381 + outer loop + vertex -679.099 157.729 261.802 + vertex -680.267 161.451 259.875 + vertex -678.738 158.178 259.991 + endloop + endfacet + facet normal -0.870143 -0.415626 -0.264775 + outer loop + vertex -680.267 161.451 259.875 + vertex -679.881 161.806 258.049 + vertex -678.738 158.178 259.991 + endloop + endfacet + facet normal -0.869452 -0.416167 -0.266192 + outer loop + vertex -678.738 158.178 259.991 + vertex -679.881 161.806 258.049 + vertex -678.328 158.435 258.249 + endloop + endfacet + facet normal -0.871269 -0.416606 -0.25948 + outer loop + vertex -679.881 161.806 258.049 + vertex -679.351 161.777 256.318 + vertex -678.328 158.435 258.249 + endloop + endfacet + facet normal -0.86727 -0.419944 -0.267376 + outer loop + vertex -678.328 158.435 258.249 + vertex -679.351 161.777 256.318 + vertex -677.907 158.491 256.796 + endloop + endfacet + facet normal -0.868445 -0.419909 -0.26359 + outer loop + vertex -677.907 158.491 256.796 + vertex -679.351 161.777 256.318 + vertex -678.404 160.833 254.7 + endloop + endfacet + facet normal -0.612255 -0.302565 -0.730478 + outer loop + vertex -698.259 157.793 293.533 + vertex -697.57 157.868 292.924 + vertex -696.991 153.924 294.072 + endloop + endfacet + facet normal -0.575081 -0.294922 -0.763088 + outer loop + vertex -697.512 154.022 294.427 + vertex -698.259 157.793 293.533 + vertex -696.991 153.924 294.072 + endloop + endfacet + facet normal -0.60965 -0.295267 -0.735625 + outer loop + vertex -698.729 157.923 293.87 + vertex -698.259 157.793 293.533 + vertex -697.512 154.022 294.427 + endloop + endfacet + facet normal -0.547917 -0.283349 -0.787083 + outer loop + vertex -697.889 154.441 294.539 + vertex -698.729 157.923 293.87 + vertex -697.512 154.022 294.427 + endloop + endfacet + facet normal -0.633391 -0.290535 -0.71722 + outer loop + vertex -699.105 158.532 293.955 + vertex -698.729 157.923 293.87 + vertex -697.889 154.441 294.539 + endloop + endfacet + facet normal -0.558553 -0.277504 -0.781671 + outer loop + vertex -698.286 155.431 294.472 + vertex -699.105 158.532 293.955 + vertex -697.889 154.441 294.539 + endloop + endfacet + facet normal -0.774878 -0.297309 -0.557828 + outer loop + vertex -699.498 159.726 293.865 + vertex -699.105 158.532 293.955 + vertex -698.286 155.431 294.472 + endloop + endfacet + facet normal -0.305072 -0.171004 -0.93685 + outer loop + vertex -699.498 159.726 293.865 + vertex -700.084 162.907 293.475 + vertex -699.105 158.532 293.955 + endloop + endfacet + facet normal -0.57125 -0.214708 -0.792196 + outer loop + vertex -700.084 162.907 293.475 + vertex -699.742 162.296 293.395 + vertex -699.105 158.532 293.955 + endloop + endfacet + facet normal -0.475432 -0.151283 -0.866647 + outer loop + vertex -700.084 162.907 293.475 + vertex -700.596 167.911 292.883 + vertex -699.742 162.296 293.395 + endloop + endfacet + facet normal -0.692811 -0.169263 -0.700972 + outer loop + vertex -700.596 167.911 292.883 + vertex -700.054 166.352 292.723 + vertex -699.742 162.296 293.395 + endloop + endfacet + facet normal -0.635007 -0.1734 -0.752794 + outer loop + vertex -699.742 162.296 293.395 + vertex -700.054 166.352 292.723 + vertex -699.286 161.977 293.084 + endloop + endfacet + facet normal -0.653126 -0.229754 -0.721553 + outer loop + vertex -699.742 162.296 293.395 + vertex -699.286 161.977 293.084 + vertex -698.729 157.923 293.87 + endloop + endfacet + facet normal -0.658469 -0.175783 -0.731791 + outer loop + vertex -700.054 166.352 292.723 + vertex -699.478 167.035 292.041 + vertex -699.286 161.977 293.084 + endloop + endfacet + facet normal -0.658935 -0.175718 -0.731388 + outer loop + vertex -699.286 161.977 293.084 + vertex -699.478 167.035 292.041 + vertex -698.644 161.976 292.506 + endloop + endfacet + facet normal -0.650334 -0.237133 -0.721688 + outer loop + vertex -699.286 161.977 293.084 + vertex -698.644 161.976 292.506 + vertex -698.259 157.793 293.533 + endloop + endfacet + facet normal -0.711026 -0.179563 -0.679852 + outer loop + vertex -699.478 167.035 292.041 + vertex -698.644 166.037 291.432 + vertex -698.644 161.976 292.506 + endloop + endfacet + facet normal -0.669383 -0.189731 -0.718281 + outer loop + vertex -698.644 161.976 292.506 + vertex -698.644 166.037 291.432 + vertex -697.787 162.001 291.7 + endloop + endfacet + facet normal -0.683944 -0.191863 -0.703853 + outer loop + vertex -698.644 166.037 291.432 + vertex -697.779 166.716 290.407 + vertex -697.787 162.001 291.7 + endloop + endfacet + facet normal -0.415787 -0.148791 -0.897208 + outer loop + vertex -700.863 167.235 293.119 + vertex -700.596 167.911 292.883 + vertex -700.084 162.907 293.475 + endloop + endfacet + facet normal -0.167059 -0.110791 -0.979702 + outer loop + vertex -700.271 163.114 293.484 + vertex -700.863 167.235 293.119 + vertex -700.084 162.907 293.475 + endloop + endfacet + facet normal 0.0249505 -0.0846611 -0.996097 + outer loop + vertex -700.548 164.409 293.367 + vertex -700.863 167.235 293.119 + vertex -700.271 163.114 293.484 + endloop + endfacet + facet normal -0.874019 -0.225919 -0.430176 + outer loop + vertex -700.548 164.409 293.367 + vertex -700.271 163.114 293.484 + vertex -700.012 161.78 293.659 + endloop + endfacet + facet normal -0.465296 -0.203156 -0.861526 + outer loop + vertex -700.271 163.114 293.484 + vertex -699.498 159.726 293.865 + vertex -700.012 161.78 293.659 + endloop + endfacet + facet normal -0.657869 -0.13827 -0.740331 + outer loop + vertex -700.863 167.235 293.119 + vertex -700.548 164.409 293.367 + vertex -700.708 165.441 293.316 + endloop + endfacet + facet normal -0.218695 -0.158291 -0.962869 + outer loop + vertex -700.271 163.114 293.484 + vertex -700.084 162.907 293.475 + vertex -699.498 159.726 293.865 + endloop + endfacet + facet normal -0.529688 -0.212 -0.821271 + outer loop + vertex -699.105 158.532 293.955 + vertex -699.742 162.296 293.395 + vertex -698.729 157.923 293.87 + endloop + endfacet + facet normal -0.608672 -0.230919 -0.759075 + outer loop + vertex -698.729 157.923 293.87 + vertex -699.286 161.977 293.084 + vertex -698.259 157.793 293.533 + endloop + endfacet + facet normal -0.627903 -0.23968 -0.740467 + outer loop + vertex -698.259 157.793 293.533 + vertex -698.644 161.976 292.506 + vertex -697.57 157.868 292.924 + endloop + endfacet + facet normal -0.640575 -0.307625 -0.703584 + outer loop + vertex -696.245 153.954 293.438 + vertex -696.666 157.928 292.084 + vertex -695.338 154.08 292.557 + endloop + endfacet + facet normal -0.657105 -0.311233 -0.686547 + outer loop + vertex -696.666 157.928 292.084 + vertex -695.61 157.918 291.078 + vertex -695.338 154.08 292.557 + endloop + endfacet + facet normal -0.65636 -0.311422 -0.687174 + outer loop + vertex -695.338 154.08 292.557 + vertex -695.61 157.918 291.078 + vertex -694.316 154.155 291.547 + endloop + endfacet + facet normal -0.679997 -0.316343 -0.661462 + outer loop + vertex -695.61 157.918 291.078 + vertex -694.508 157.886 289.96 + vertex -694.316 154.155 291.547 + endloop + endfacet + facet normal -0.672536 -0.318708 -0.667922 + outer loop + vertex -694.316 154.155 291.547 + vertex -694.508 157.886 289.96 + vertex -693.22 154.155 290.444 + endloop + endfacet + facet normal -0.70175 -0.324422 -0.634269 + outer loop + vertex -694.508 157.886 289.96 + vertex -693.414 157.93 288.728 + vertex -693.22 154.155 290.444 + endloop + endfacet + facet normal -0.693554 -0.327388 -0.641717 + outer loop + vertex -693.22 154.155 290.444 + vertex -693.414 157.93 288.728 + vertex -692.094 154.221 289.194 + endloop + endfacet + facet normal -0.720183 -0.332725 -0.608794 + outer loop + vertex -693.414 157.93 288.728 + vertex -692.336 158.091 287.364 + vertex -692.094 154.221 289.194 + endloop + endfacet + facet normal -0.717 -0.333975 -0.611859 + outer loop + vertex -692.094 154.221 289.194 + vertex -692.336 158.091 287.364 + vertex -690.974 154.386 287.79 + endloop + endfacet + facet normal -0.740642 -0.339014 -0.580103 + outer loop + vertex -692.336 158.091 287.364 + vertex -691.287 158.32 285.891 + vertex -690.974 154.386 287.79 + endloop + endfacet + facet normal -0.73909 -0.339662 -0.581701 + outer loop + vertex -690.974 154.386 287.79 + vertex -691.287 158.32 285.891 + vertex -689.891 154.626 286.275 + endloop + endfacet + facet normal -0.760323 -0.344463 -0.550685 + outer loop + vertex -691.287 158.32 285.891 + vertex -690.285 158.587 284.341 + vertex -689.891 154.626 286.275 + endloop + endfacet + facet normal -0.757512 -0.345694 -0.553779 + outer loop + vertex -689.891 154.626 286.275 + vertex -690.285 158.587 284.341 + vertex -688.869 154.933 284.685 + endloop + endfacet + facet normal -0.774895 -0.349856 -0.526439 + outer loop + vertex -690.285 158.587 284.341 + vertex -689.334 158.895 282.736 + vertex -688.869 154.933 284.685 + endloop + endfacet + facet normal -0.775536 -0.349563 -0.52569 + outer loop + vertex -688.869 154.933 284.685 + vertex -689.334 158.895 282.736 + vertex -687.916 155.28 283.048 + endloop + endfacet + facet normal -0.789788 -0.353072 -0.501573 + outer loop + vertex -689.334 158.895 282.736 + vertex -688.439 159.235 281.088 + vertex -687.916 155.28 283.048 + endloop + endfacet + facet normal -0.791421 -0.352285 -0.499548 + outer loop + vertex -687.916 155.28 283.048 + vertex -688.439 159.235 281.088 + vertex -687.025 155.653 281.374 + endloop + endfacet + facet normal -0.804818 -0.355633 -0.475178 + outer loop + vertex -688.439 159.235 281.088 + vertex -687.604 159.6 279.4 + vertex -687.025 155.653 281.374 + endloop + endfacet + facet normal -0.804164 -0.355966 -0.476035 + outer loop + vertex -687.025 155.653 281.374 + vertex -687.604 159.6 279.4 + vertex -686.19 156.054 279.663 + endloop + endfacet + facet normal -0.814587 -0.358628 -0.455889 + outer loop + vertex -687.604 159.6 279.4 + vertex -686.817 160.005 277.675 + vertex -686.19 156.054 279.663 + endloop + endfacet + facet normal -0.816996 -0.357343 -0.452575 + outer loop + vertex -686.19 156.054 279.663 + vertex -686.817 160.005 277.675 + vertex -685.411 156.479 277.922 + endloop + endfacet + facet normal -0.826549 -0.359771 -0.432876 + outer loop + vertex -686.817 160.005 277.675 + vertex -686.084 160.434 275.919 + vertex -685.411 156.479 277.922 + endloop + endfacet + facet normal -0.827998 -0.358955 -0.430778 + outer loop + vertex -685.411 156.479 277.922 + vertex -686.084 160.434 275.919 + vertex -684.685 156.926 276.154 + endloop + endfacet + facet normal -0.837959 -0.36146 -0.408866 + outer loop + vertex -686.084 160.434 275.919 + vertex -685.409 160.882 274.14 + vertex -684.685 156.926 276.154 + endloop + endfacet + facet normal -0.837843 -0.361529 -0.409043 + outer loop + vertex -684.685 156.926 276.154 + vertex -685.409 160.882 274.14 + vertex -684.012 157.394 274.362 + endloop + endfacet + facet normal -0.845767 -0.363522 -0.390551 + outer loop + vertex -685.409 160.882 274.14 + vertex -684.785 161.356 272.348 + vertex -684.012 157.394 274.362 + endloop + endfacet + facet normal -0.847042 -0.362735 -0.388514 + outer loop + vertex -684.012 157.394 274.362 + vertex -684.785 161.356 272.348 + vertex -683.391 157.88 272.555 + endloop + endfacet + facet normal -0.852968 -0.364241 -0.373862 + outer loop + vertex -684.785 161.356 272.348 + vertex -684.21 161.852 270.553 + vertex -683.391 157.88 272.555 + endloop + endfacet + facet normal -0.856108 -0.362236 -0.368597 + outer loop + vertex -683.391 157.88 272.555 + vertex -684.21 161.852 270.553 + vertex -682.819 158.374 270.74 + endloop + endfacet + facet normal -0.862343 -0.363845 -0.35211 + outer loop + vertex -684.21 161.852 270.553 + vertex -683.687 162.344 268.762 + vertex -682.819 158.374 270.74 + endloop + endfacet + facet normal -0.862717 -0.363597 -0.35145 + outer loop + vertex -682.819 158.374 270.74 + vertex -683.687 162.344 268.762 + vertex -682.291 158.874 268.925 + endloop + endfacet + facet normal -0.868008 -0.365028 -0.336625 + outer loop + vertex -683.687 162.344 268.762 + vertex -683.201 162.834 266.978 + vertex -682.291 158.874 268.925 + endloop + endfacet + facet normal -0.870747 -0.363156 -0.331538 + outer loop + vertex -682.291 158.874 268.925 + vertex -683.201 162.834 266.978 + vertex -681.805 159.36 267.119 + endloop + endfacet + facet normal -0.874718 -0.364267 -0.319653 + outer loop + vertex -683.201 162.834 266.978 + vertex -682.753 163.318 265.202 + vertex -681.805 159.36 267.119 + endloop + endfacet + facet normal -0.876087 -0.363304 -0.31699 + outer loop + vertex -681.805 159.36 267.119 + vertex -682.753 163.318 265.202 + vertex -681.36 159.855 265.322 + endloop + endfacet + facet normal -0.880127 -0.364485 -0.304183 + outer loop + vertex -682.753 163.318 265.202 + vertex -682.348 163.822 263.425 + vertex -681.36 159.855 265.322 + endloop + endfacet + facet normal -0.881224 -0.363691 -0.301951 + outer loop + vertex -681.36 159.855 265.322 + vertex -682.348 163.822 263.425 + vertex -680.961 160.378 263.525 + endloop + endfacet + facet normal -0.884811 -0.364785 -0.289898 + outer loop + vertex -682.348 163.822 263.425 + vertex -681.984 164.367 261.629 + vertex -680.961 160.378 263.525 + endloop + endfacet + facet normal -0.887238 -0.362952 -0.284735 + outer loop + vertex -680.961 160.378 263.525 + vertex -681.984 164.367 261.629 + vertex -680.605 160.93 261.712 + endloop + endfacet + facet normal -0.891562 -0.364307 -0.269069 + outer loop + vertex -681.984 164.367 261.629 + vertex -681.657 164.915 259.805 + vertex -680.605 160.93 261.712 + endloop + endfacet + facet normal -0.892301 -0.363712 -0.267418 + outer loop + vertex -680.605 160.93 261.712 + vertex -681.657 164.915 259.805 + vertex -680.267 161.451 259.875 + endloop + endfacet + facet normal -0.89494 -0.364563 -0.257247 + outer loop + vertex -681.657 164.915 259.805 + vertex -681.33 165.417 257.955 + vertex -680.267 161.451 259.875 + endloop + endfacet + facet normal -0.893717 -0.365585 -0.260034 + outer loop + vertex -680.267 161.451 259.875 + vertex -681.33 165.417 257.955 + vertex -679.881 161.806 258.049 + endloop + endfacet + facet normal -0.896114 -0.366301 -0.250606 + outer loop + vertex -681.33 165.417 257.955 + vertex -680.949 165.752 256.101 + vertex -679.881 161.806 258.049 + endloop + endfacet + facet normal -0.889378 -0.371973 -0.265787 + outer loop + vertex -679.881 161.806 258.049 + vertex -680.949 165.752 256.101 + vertex -679.351 161.777 256.318 + endloop + endfacet + facet normal -0.892736 -0.372642 -0.253298 + outer loop + vertex -680.949 165.752 256.101 + vertex -680.439 165.774 254.271 + vertex -679.351 161.777 256.318 + endloop + endfacet + facet normal -0.660086 -0.245009 -0.71011 + outer loop + vertex -698.644 161.976 292.506 + vertex -697.787 162.001 291.7 + vertex -697.57 157.868 292.924 + endloop + endfacet + facet normal -0.68413 -0.191817 -0.703685 + outer loop + vertex -697.787 162.001 291.7 + vertex -697.779 166.716 290.407 + vertex -696.748 162.033 290.681 + endloop + endfacet + facet normal -0.691173 -0.260504 -0.674104 + outer loop + vertex -695.61 157.918 291.078 + vertex -695.609 161.912 289.533 + vertex -694.508 157.886 289.96 + endloop + endfacet + facet normal -0.721153 -0.26509 -0.640052 + outer loop + vertex -695.609 161.912 289.533 + vertex -694.496 161.887 288.29 + vertex -694.508 157.886 289.96 + endloop + endfacet + facet normal -0.716054 -0.267132 -0.644908 + outer loop + vertex -694.508 157.886 289.96 + vertex -694.496 161.887 288.29 + vertex -693.414 157.93 288.728 + endloop + endfacet + facet normal -0.744517 -0.271066 -0.610096 + outer loop + vertex -694.496 161.887 288.29 + vertex -693.438 162.002 286.948 + vertex -693.414 157.93 288.728 + endloop + endfacet + facet normal -0.738431 -0.27373 -0.616272 + outer loop + vertex -693.414 157.93 288.728 + vertex -693.438 162.002 286.948 + vertex -692.336 158.091 287.364 + endloop + endfacet + facet normal -0.765046 -0.27749 -0.581123 + outer loop + vertex -693.438 162.002 286.948 + vertex -692.421 162.209 285.51 + vertex -692.336 158.091 287.364 + endloop + endfacet + facet normal -0.761121 -0.279326 -0.585382 + outer loop + vertex -692.336 158.091 287.364 + vertex -692.421 162.209 285.51 + vertex -691.287 158.32 285.891 + endloop + endfacet + facet normal -0.783011 -0.282642 -0.554083 + outer loop + vertex -692.421 162.209 285.51 + vertex -691.44 162.459 283.996 + vertex -691.287 158.32 285.891 + endloop + endfacet + facet normal -0.782648 -0.282821 -0.554504 + outer loop + vertex -691.287 158.32 285.891 + vertex -691.44 162.459 283.996 + vertex -690.285 158.587 284.341 + endloop + endfacet + facet normal -0.802054 -0.28593 -0.52436 + outer loop + vertex -691.44 162.459 283.996 + vertex -690.506 162.723 282.424 + vertex -690.285 158.587 284.341 + endloop + endfacet + facet normal -0.798622 -0.287714 -0.528605 + outer loop + vertex -690.285 158.587 284.341 + vertex -690.506 162.723 282.424 + vertex -689.334 158.895 282.736 + endloop + endfacet + facet normal -0.814518 -0.290429 -0.502207 + outer loop + vertex -690.506 162.723 282.424 + vertex -689.618 163.033 280.805 + vertex -689.334 158.895 282.736 + endloop + endfacet + facet normal -0.814609 -0.29038 -0.502088 + outer loop + vertex -689.334 158.895 282.736 + vertex -689.618 163.033 280.805 + vertex -688.439 159.235 281.088 + endloop + endfacet + facet normal -0.829658 -0.293041 -0.475178 + outer loop + vertex -689.618 163.033 280.805 + vertex -688.784 163.373 279.139 + vertex -688.439 159.235 281.088 + endloop + endfacet + facet normal -0.830362 -0.292638 -0.474197 + outer loop + vertex -688.439 159.235 281.088 + vertex -688.784 163.373 279.139 + vertex -687.604 159.6 279.4 + endloop + endfacet + facet normal -0.841424 -0.29463 -0.452989 + outer loop + vertex -688.784 163.373 279.139 + vertex -688 163.757 277.433 + vertex -687.604 159.6 279.4 + endloop + endfacet + facet normal -0.841341 -0.294679 -0.45311 + outer loop + vertex -687.604 159.6 279.4 + vertex -688 163.757 277.433 + vertex -686.817 160.005 277.675 + endloop + endfacet + facet normal -0.853445 -0.296897 -0.42835 + outer loop + vertex -688 163.757 277.433 + vertex -687.268 164.167 275.69 + vertex -686.817 160.005 277.675 + endloop + endfacet + facet normal -0.853249 -0.297021 -0.428655 + outer loop + vertex -686.817 160.005 277.675 + vertex -687.268 164.167 275.69 + vertex -686.084 160.434 275.919 + endloop + endfacet + facet normal -0.864517 -0.299079 -0.403935 + outer loop + vertex -687.268 164.167 275.69 + vertex -686.591 164.598 273.921 + vertex -686.084 160.434 275.919 + endloop + endfacet + facet normal -0.864884 -0.298833 -0.40333 + outer loop + vertex -686.084 160.434 275.919 + vertex -686.591 164.598 273.921 + vertex -685.409 160.882 274.14 + endloop + endfacet + facet normal -0.873256 -0.30034 -0.383692 + outer loop + vertex -686.591 164.598 273.921 + vertex -685.965 165.053 272.141 + vertex -685.409 160.882 274.14 + endloop + endfacet + facet normal -0.873415 -0.30023 -0.383418 + outer loop + vertex -685.409 160.882 274.14 + vertex -685.965 165.053 272.141 + vertex -684.785 161.356 272.348 + endloop + endfacet + facet normal -0.881758 -0.301723 -0.362583 + outer loop + vertex -685.965 165.053 272.141 + vertex -685.394 165.524 270.359 + vertex -684.785 161.356 272.348 + endloop + endfacet + facet normal -0.880083 -0.302933 -0.365631 + outer loop + vertex -684.785 161.356 272.348 + vertex -685.394 165.524 270.359 + vertex -684.21 161.852 270.553 + endloop + endfacet + facet normal -0.887505 -0.30429 -0.346038 + outer loop + vertex -685.394 165.524 270.359 + vertex -684.868 166.008 268.586 + vertex -684.21 161.852 270.553 + endloop + endfacet + facet normal -0.888982 -0.303183 -0.343206 + outer loop + vertex -684.21 161.852 270.553 + vertex -684.868 166.008 268.586 + vertex -683.687 162.344 268.762 + endloop + endfacet + facet normal -0.895524 -0.304399 -0.324621 + outer loop + vertex -684.868 166.008 268.586 + vertex -684.388 166.479 266.821 + vertex -683.687 162.344 268.762 + endloop + endfacet + facet normal -0.894142 -0.305473 -0.327408 + outer loop + vertex -683.687 162.344 268.762 + vertex -684.388 166.479 266.821 + vertex -683.201 162.834 266.978 + endloop + endfacet + facet normal -0.900142 -0.306652 -0.309368 + outer loop + vertex -684.388 166.479 266.821 + vertex -683.943 166.94 265.069 + vertex -683.201 162.834 266.978 + endloop + endfacet + facet normal -0.899683 -0.30702 -0.310337 + outer loop + vertex -683.201 162.834 266.978 + vertex -683.943 166.94 265.069 + vertex -682.753 163.318 265.202 + endloop + endfacet + facet normal -0.904688 -0.308077 -0.294326 + outer loop + vertex -683.943 166.94 265.069 + vertex -683.537 167.417 263.32 + vertex -682.753 163.318 265.202 + endloop + endfacet + facet normal -0.904937 -0.307872 -0.293776 + outer loop + vertex -682.753 163.318 265.202 + vertex -683.537 167.417 263.32 + vertex -682.348 163.822 263.425 + endloop + endfacet + facet normal -0.908785 -0.308763 -0.280668 + outer loop + vertex -683.537 167.417 263.32 + vertex -683.167 167.938 261.55 + vertex -682.348 163.822 263.425 + endloop + endfacet + facet normal -0.910076 -0.30766 -0.277682 + outer loop + vertex -682.348 163.822 263.425 + vertex -683.167 167.938 261.55 + vertex -681.984 164.367 261.629 + endloop + endfacet + facet normal -0.91481 -0.308844 -0.260266 + outer loop + vertex -683.167 167.938 261.55 + vertex -682.828 168.452 259.748 + vertex -681.984 164.367 261.629 + endloop + endfacet + facet normal -0.916381 -0.307398 -0.256421 + outer loop + vertex -681.984 164.367 261.629 + vertex -682.828 168.452 259.748 + vertex -681.657 164.915 259.805 + endloop + endfacet + facet normal -0.920916 -0.308607 -0.238068 + outer loop + vertex -682.828 168.452 259.748 + vertex -682.51 168.875 257.968 + vertex -681.657 164.915 259.805 + endloop + endfacet + facet normal -0.917431 -0.31198 -0.246958 + outer loop + vertex -681.657 164.915 259.805 + vertex -682.51 168.875 257.968 + vertex -681.33 165.417 257.955 + endloop + endfacet + facet normal -0.919333 -0.312658 -0.238895 + outer loop + vertex -682.51 168.875 257.968 + vertex -682.236 169.463 256.146 + vertex -681.33 165.417 257.955 + endloop + endfacet + facet normal -0.916747 -0.315067 -0.245578 + outer loop + vertex -681.33 165.417 257.955 + vertex -682.236 169.463 256.146 + vertex -680.949 165.752 256.101 + endloop + endfacet + facet normal -0.917509 -0.315371 -0.242318 + outer loop + vertex -682.236 169.463 256.146 + vertex -681.933 170.03 254.261 + vertex -680.949 165.752 256.101 + endloop + endfacet + facet normal -0.911412 -0.320661 -0.257885 + outer loop + vertex -680.949 165.752 256.101 + vertex -681.933 170.03 254.261 + vertex -680.439 165.774 254.271 + endloop + endfacet + facet normal -0.917448 -0.322725 -0.232677 + outer loop + vertex -681.933 170.03 254.261 + vertex -681.605 170.481 252.342 + vertex -680.439 165.774 254.271 + endloop + endfacet + facet normal -0.915434 -0.324461 -0.238129 + outer loop + vertex -680.439 165.774 254.271 + vertex -681.605 170.481 252.342 + vertex -679.962 165.833 252.356 + endloop + endfacet + facet normal -0.921964 -0.326676 -0.208003 + outer loop + vertex -681.605 170.481 252.342 + vertex -681.305 170.868 250.401 + vertex -679.962 165.833 252.356 + endloop + endfacet + facet normal -0.921767 -0.326854 -0.208597 + outer loop + vertex -679.962 165.833 252.356 + vertex -681.305 170.868 250.401 + vertex -679.639 166.18 250.389 + endloop + endfacet + facet normal -0.925752 -0.328325 -0.187578 + outer loop + vertex -681.305 170.868 250.401 + vertex -681.073 171.314 248.479 + vertex -679.639 166.18 250.389 + endloop + endfacet + facet normal -0.924422 -0.329566 -0.191912 + outer loop + vertex -679.639 166.18 250.389 + vertex -681.073 171.314 248.479 + vertex -679.399 166.617 248.48 + endloop + endfacet + facet normal -0.926234 -0.330211 -0.181803 + outer loop + vertex -681.073 171.314 248.479 + vertex -680.878 171.8 246.601 + vertex -679.399 166.617 248.48 + endloop + endfacet + facet normal -0.926802 -0.329673 -0.179872 + outer loop + vertex -679.399 166.617 248.48 + vertex -680.878 171.8 246.601 + vertex -679.208 167.11 246.591 + endloop + endfacet + facet normal -0.92817 -0.330177 -0.171707 + outer loop + vertex -680.878 171.8 246.601 + vertex -680.708 172.293 244.735 + vertex -679.208 167.11 246.591 + endloop + endfacet + facet normal -0.92753 -0.330798 -0.173959 + outer loop + vertex -679.208 167.11 246.591 + vertex -680.708 172.293 244.735 + vertex -679.032 167.606 244.709 + endloop + endfacet + facet normal -0.928824 -0.331306 -0.165898 + outer loop + vertex -680.708 172.293 244.735 + vertex -680.547 172.769 242.881 + vertex -679.032 167.606 244.709 + endloop + endfacet + facet normal -0.930202 -0.329924 -0.160853 + outer loop + vertex -679.032 167.606 244.709 + vertex -680.547 172.769 242.881 + vertex -678.874 168.076 242.836 + endloop + endfacet + facet normal -0.931119 -0.330311 -0.154637 + outer loop + vertex -680.547 172.769 242.881 + vertex -680.403 173.222 241.048 + vertex -678.874 168.076 242.836 + endloop + endfacet + facet normal -0.930434 -0.331011 -0.157238 + outer loop + vertex -678.874 168.076 242.836 + vertex -680.403 173.222 241.048 + vertex -678.725 168.531 240.996 + endloop + endfacet + facet normal -0.931292 -0.331383 -0.15126 + outer loop + vertex -680.403 173.222 241.048 + vertex -680.266 173.659 239.248 + vertex -678.725 168.531 240.996 + endloop + endfacet + facet normal -0.932351 -0.33028 -0.147091 + outer loop + vertex -678.725 168.531 240.996 + vertex -680.266 173.659 239.248 + vertex -678.595 168.965 239.195 + endloop + endfacet + facet normal -0.932926 -0.330533 -0.142821 + outer loop + vertex -680.266 173.659 239.248 + vertex -680.145 174.084 237.473 + vertex -678.595 168.965 239.195 + endloop + endfacet + facet normal -0.932956 -0.3305 -0.142697 + outer loop + vertex -678.595 168.965 239.195 + vertex -680.145 174.084 237.473 + vertex -678.477 169.398 237.423 + endloop + endfacet + facet normal -0.934247 -0.331068 -0.132575 + outer loop + vertex -680.145 174.084 237.473 + vertex -680.042 174.506 235.698 + vertex -678.477 169.398 237.423 + endloop + endfacet + facet normal -0.934913 -0.330313 -0.129735 + outer loop + vertex -678.477 169.398 237.423 + vertex -680.042 174.506 235.698 + vertex -678.377 169.811 235.646 + endloop + endfacet + facet normal -0.934936 -0.330323 -0.129541 + outer loop + vertex -680.042 174.506 235.698 + vertex -679.942 174.93 233.891 + vertex -678.377 169.811 235.646 + endloop + endfacet + facet normal -0.935475 -0.329695 -0.127229 + outer loop + vertex -678.377 169.811 235.646 + vertex -679.942 174.93 233.891 + vertex -678.281 170.239 233.83 + endloop + endfacet + facet normal -0.936374 -0.330117 -0.119279 + outer loop + vertex -679.942 174.93 233.891 + vertex -679.855 175.356 232.031 + vertex -678.281 170.239 233.83 + endloop + endfacet + facet normal -0.935988 -0.330593 -0.120971 + outer loop + vertex -678.281 170.239 233.83 + vertex -679.855 175.356 232.031 + vertex -678.188 170.662 231.961 + endloop + endfacet + facet normal -0.936336 -0.330765 -0.117769 + outer loop + vertex -679.855 175.356 232.031 + vertex -679.766 175.782 230.128 + vertex -678.188 170.662 231.961 + endloop + endfacet + facet normal -0.937338 -0.32948 -0.113318 + outer loop + vertex -678.188 170.662 231.961 + vertex -679.766 175.782 230.128 + vertex -678.105 171.084 230.045 + endloop + endfacet + facet normal -0.938036 -0.329852 -0.10624 + outer loop + vertex -679.766 175.782 230.128 + vertex -679.695 176.201 228.199 + vertex -678.105 171.084 230.045 + endloop + endfacet + facet normal -0.93704 -0.331183 -0.11079 + outer loop + vertex -678.105 171.084 230.045 + vertex -679.695 176.201 228.199 + vertex -678.025 171.505 228.114 + endloop + endfacet + facet normal -0.9373 -0.331324 -0.108132 + outer loop + vertex -679.695 176.201 228.199 + vertex -679.618 176.609 226.281 + vertex -678.025 171.505 228.114 + endloop + endfacet + facet normal -0.938882 -0.329166 -0.100746 + outer loop + vertex -678.025 171.505 228.114 + vertex -679.618 176.609 226.281 + vertex -677.958 171.901 226.191 + endloop + endfacet + facet normal -0.939286 -0.329396 -0.0961222 + outer loop + vertex -679.618 176.609 226.281 + vertex -679.56 176.998 224.379 + vertex -677.958 171.901 226.191 + endloop + endfacet + facet normal -0.938455 -0.330565 -0.100142 + outer loop + vertex -677.958 171.901 226.191 + vertex -679.56 176.998 224.379 + vertex -677.895 172.297 224.292 + endloop + endfacet + facet normal -0.938768 -0.330741 -0.0965628 + outer loop + vertex -679.56 176.998 224.379 + vertex -679.498 177.374 222.491 + vertex -677.895 172.297 224.292 + endloop + endfacet + facet normal -0.93978 -0.329287 -0.0915642 + outer loop + vertex -677.895 172.297 224.292 + vertex -679.498 177.374 222.491 + vertex -677.84 172.665 222.405 + endloop + endfacet + facet normal -0.939997 -0.329414 -0.0888364 + outer loop + vertex -679.498 177.374 222.491 + vertex -679.445 177.735 220.591 + vertex -677.84 172.665 222.405 + endloop + endfacet + facet normal -0.939682 -0.329881 -0.0904225 + outer loop + vertex -677.84 172.665 222.405 + vertex -679.445 177.735 220.591 + vertex -677.783 173.024 220.503 + endloop + endfacet + facet normal -0.940106 -0.330134 -0.0849204 + outer loop + vertex -679.445 177.735 220.591 + vertex -679.395 178.091 218.651 + vertex -677.783 173.024 220.503 + endloop + endfacet + facet normal -0.939809 -0.330589 -0.086424 + outer loop + vertex -677.783 173.024 220.503 + vertex -679.395 178.091 218.651 + vertex -677.729 173.379 218.556 + endloop + endfacet + facet normal -0.940087 -0.330763 -0.0826597 + outer loop + vertex -679.395 178.091 218.651 + vertex -679.343 178.442 216.658 + vertex -677.729 173.379 218.556 + endloop + endfacet + facet normal -0.940941 -0.329396 -0.0782888 + outer loop + vertex -677.729 173.379 218.556 + vertex -679.343 178.442 216.658 + vertex -677.682 173.722 216.552 + endloop + endfacet + facet normal -0.941018 -0.32945 -0.0771217 + outer loop + vertex -679.343 178.442 216.658 + vertex -679.296 178.782 214.627 + vertex -677.682 173.722 216.552 + endloop + endfacet + facet normal -0.940534 -0.33024 -0.079606 + outer loop + vertex -677.682 173.722 216.552 + vertex -679.296 178.782 214.627 + vertex -677.63 174.065 214.513 + endloop + endfacet + facet normal -0.940853 -0.330471 -0.0747248 + outer loop + vertex -679.296 178.782 214.627 + vertex -679.249 179.107 212.596 + vertex -677.63 174.065 214.513 + endloop + endfacet + facet normal -0.941646 -0.329131 -0.0705308 + outer loop + vertex -677.63 174.065 214.513 + vertex -679.249 179.107 212.596 + vertex -677.587 174.378 212.476 + endloop + endfacet + facet normal -0.941678 -0.329156 -0.0699921 + outer loop + vertex -679.249 179.107 212.596 + vertex -679.206 179.408 210.612 + vertex -677.587 174.378 212.476 + endloop + endfacet + facet normal -0.941326 -0.32975 -0.0719014 + outer loop + vertex -677.587 174.378 212.476 + vertex -679.206 179.408 210.612 + vertex -677.542 174.681 210.496 + endloop + endfacet + facet normal -0.941438 -0.329836 -0.070026 + outer loop + vertex -679.206 179.408 210.612 + vertex -679.16 179.682 208.701 + vertex -677.542 174.681 210.496 + endloop + endfacet + facet normal -0.941797 -0.329229 -0.0680129 + outer loop + vertex -677.542 174.681 210.496 + vertex -679.16 179.682 208.701 + vertex -677.498 174.951 208.591 + endloop + endfacet + facet normal -0.942164 -0.329516 -0.061211 + outer loop + vertex -679.16 179.682 208.701 + vertex -679.127 179.933 206.842 + vertex -677.498 174.951 208.591 + endloop + endfacet + facet normal -0.942336 -0.329211 -0.0601812 + outer loop + vertex -677.498 174.951 208.591 + vertex -679.127 179.933 206.842 + vertex -677.464 175.191 206.738 + endloop + endfacet + facet normal -0.942247 -0.329141 -0.0619451 + outer loop + vertex -679.127 179.933 206.842 + vertex -679.089 180.169 205.002 + vertex -677.464 175.191 206.738 + endloop + endfacet + facet normal -0.942795 -0.328172 -0.0586545 + outer loop + vertex -677.464 175.191 206.738 + vertex -679.089 180.169 205.002 + vertex -677.432 175.427 204.896 + endloop + endfacet + facet normal -0.943027 -0.328365 -0.0536342 + outer loop + vertex -679.089 180.169 205.002 + vertex -679.062 180.4 203.125 + vertex -677.432 175.427 204.896 + endloop + endfacet + facet normal -0.942458 -0.329412 -0.0570958 + outer loop + vertex -677.432 175.427 204.896 + vertex -679.062 180.4 203.125 + vertex -677.401 175.665 203.022 + endloop + endfacet + facet normal -0.942541 -0.329479 -0.0553221 + outer loop + vertex -679.062 180.4 203.125 + vertex -679.03 180.632 201.2 + vertex -677.401 175.665 203.022 + endloop + endfacet + facet normal -0.94314 -0.328349 -0.0517057 + outer loop + vertex -677.401 175.665 203.022 + vertex -679.03 180.632 201.2 + vertex -677.377 175.897 201.101 + endloop + endfacet + facet normal -0.943252 -0.328446 -0.0489751 + outer loop + vertex -679.03 180.632 201.2 + vertex -679.005 180.85 199.237 + vertex -677.377 175.897 201.101 + endloop + endfacet + facet normal -0.943317 -0.328317 -0.0485778 + outer loop + vertex -677.377 175.897 201.101 + vertex -679.005 180.85 199.237 + vertex -677.347 176.104 199.134 + endloop + endfacet + facet normal -0.943402 -0.328395 -0.046358 + outer loop + vertex -679.005 180.85 199.237 + vertex -678.97 181.031 197.248 + vertex -677.347 176.104 199.134 + endloop + endfacet + facet normal -0.94368 -0.327834 -0.0446524 + outer loop + vertex -677.347 176.104 199.134 + vertex -678.97 181.031 197.248 + vertex -677.303 176.252 197.101 + endloop + endfacet + facet normal -0.943739 -0.327912 -0.0427971 + outer loop + vertex -678.97 181.031 197.248 + vertex -678.924 181.166 195.216 + vertex -677.303 176.252 197.101 + endloop + endfacet + facet normal -0.943095 -0.329218 -0.0467574 + outer loop + vertex -677.303 176.252 197.101 + vertex -678.924 181.166 195.216 + vertex -677.254 176.421 194.941 + endloop + endfacet + facet normal -0.943227 -0.329591 -0.0411347 + outer loop + vertex -678.924 181.166 195.216 + vertex -678.89 181.328 193.122 + vertex -677.254 176.421 194.941 + endloop + endfacet + facet normal -0.944116 -0.32772 -0.0352864 + outer loop + vertex -677.254 176.421 194.941 + vertex -678.89 181.328 193.122 + vertex -677.307 176.822 192.619 + endloop + endfacet + facet normal -0.944101 -0.328211 -0.0308482 + outer loop + vertex -678.89 181.328 193.122 + vertex -678.918 181.605 191.042 + vertex -677.307 176.822 192.619 + endloop + endfacet + facet normal -0.946985 -0.321208 -0.00666187 + outer loop + vertex -677.307 176.822 192.619 + vertex -678.918 181.605 191.042 + vertex -677.63 177.817 190.581 + endloop + endfacet + facet normal -0.947469 -0.31795 -0.034783 + outer loop + vertex -678.918 181.605 191.042 + vertex -678.886 181.726 189.05 + vertex -677.63 177.817 190.581 + endloop + endfacet + facet normal -0.943488 -0.326125 -0.05893 + outer loop + vertex -677.63 177.817 190.581 + vertex -678.886 181.726 189.05 + vertex -677.32 177.251 188.751 + endloop + endfacet + facet normal -0.944095 -0.328187 -0.0312764 + outer loop + vertex -678.886 181.726 189.05 + vertex -678.839 181.778 187.099 + vertex -677.32 177.251 188.751 + endloop + endfacet + facet normal -0.946412 -0.322658 -0.0139928 + outer loop + vertex -677.32 177.251 188.751 + vertex -678.839 181.778 187.099 + vertex -677.528 177.95 186.724 + endloop + endfacet + facet normal -0.946556 -0.321095 -0.0304812 + outer loop + vertex -678.839 181.778 187.099 + vertex -678.801 181.848 185.196 + vertex -677.528 177.95 186.724 + endloop + endfacet + facet normal -0.943431 -0.327763 -0.0500954 + outer loop + vertex -677.528 177.95 186.724 + vertex -678.801 181.848 185.196 + vertex -677.217 177.323 184.955 + endloop + endfacet + facet normal -0.943929 -0.329513 -0.0204585 + outer loop + vertex -678.801 181.848 185.196 + vertex -678.788 181.925 183.332 + vertex -677.217 177.323 184.955 + endloop + endfacet + facet normal -0.945967 -0.324242 -0.00354481 + outer loop + vertex -677.217 177.323 184.955 + vertex -678.788 181.925 183.332 + vertex -677.46 178.054 182.972 + endloop + endfacet + facet normal -0.94623 -0.323006 -0.01779 + outer loop + vertex -678.788 181.925 183.332 + vertex -678.782 182.009 181.482 + vertex -677.46 178.054 182.972 + endloop + endfacet + facet normal -0.943212 -0.329916 -0.0388155 + outer loop + vertex -677.46 178.054 182.972 + vertex -678.782 182.009 181.482 + vertex -677.171 177.434 181.214 + endloop + endfacet + facet normal -0.943366 -0.331525 -0.0123595 + outer loop + vertex -678.782 182.009 181.482 + vertex -678.782 182.079 179.612 + vertex -677.171 177.434 181.214 + endloop + endfacet + facet normal -0.945245 -0.326329 0.00460351 + outer loop + vertex -677.171 177.434 181.214 + vertex -678.782 182.079 179.612 + vertex -677.44 178.187 179.21 + endloop + endfacet + facet normal -0.945693 -0.324878 -0.010907 + outer loop + vertex -678.782 182.079 179.612 + vertex -678.778 182.131 177.702 + vertex -677.44 178.187 179.21 + endloop + endfacet + facet normal -0.943017 -0.331366 -0.0302534 + outer loop + vertex -677.44 178.187 179.21 + vertex -678.778 182.131 177.702 + vertex -677.165 177.569 177.385 + endloop + endfacet + facet normal -0.942916 -0.332962 -0.00679589 + outer loop + vertex -678.778 182.131 177.702 + vertex -678.778 182.171 175.754 + vertex -677.165 177.569 177.385 + endloop + endfacet + facet normal -0.945418 -0.325418 0.0169698 + outer loop + vertex -677.165 177.569 177.385 + vertex -678.778 182.171 175.754 + vertex -677.443 178.269 175.324 + endloop + endfacet + facet normal -0.946286 -0.323292 -0.00503713 + outer loop + vertex -678.778 182.171 175.754 + vertex -678.775 182.194 173.782 + vertex -677.443 178.269 175.324 + endloop + endfacet + facet normal -0.943258 -0.33095 -0.0271443 + outer loop + vertex -677.443 178.269 175.324 + vertex -678.775 182.194 173.782 + vertex -677.164 177.627 173.462 + endloop + endfacet + facet normal -0.94302 -0.332737 -0.000445539 + outer loop + vertex -678.775 182.194 173.782 + vertex -678.776 182.198 171.8 + vertex -677.164 177.627 173.462 + endloop + endfacet + facet normal -0.945281 -0.325548 0.0215189 + outer loop + vertex -677.164 177.627 173.462 + vertex -678.776 182.198 171.8 + vertex -677.438 178.285 171.374 + endloop + endfacet + facet normal -0.946202 -0.323576 0.000490053 + outer loop + vertex -678.776 182.198 171.8 + vertex -678.774 182.19 169.814 + vertex -677.438 178.285 171.374 + endloop + endfacet + facet normal -0.943486 -0.330812 -0.0199479 + outer loop + vertex -677.438 178.285 171.374 + vertex -678.774 182.19 169.814 + vertex -677.163 177.615 169.502 + endloop + endfacet + facet normal -0.943046 -0.332565 0.0080614 + outer loop + vertex -678.774 182.19 169.814 + vertex -678.78 182.159 167.829 + vertex -677.163 177.615 169.502 + endloop + endfacet + facet normal -0.945101 -0.325459 0.029345 + outer loop + vertex -677.163 177.615 169.502 + vertex -678.78 182.159 167.829 + vertex -677.446 178.245 167.407 + endloop + endfacet + facet normal -0.946162 -0.323579 0.00856108 + outer loop + vertex -678.78 182.159 167.829 + vertex -678.784 182.119 165.854 + vertex -677.446 178.245 167.407 + endloop + endfacet + facet normal -0.943671 -0.330691 -0.0113242 + outer loop + vertex -677.446 178.245 167.407 + vertex -678.784 182.119 165.854 + vertex -677.181 177.553 165.551 + endloop + endfacet + facet normal -0.943184 -0.332059 0.0118693 + outer loop + vertex -678.784 182.119 165.854 + vertex -678.79 182.066 163.894 + vertex -677.181 177.553 165.551 + endloop + endfacet + facet normal -0.945116 -0.325091 0.0327306 + outer loop + vertex -677.181 177.553 165.551 + vertex -678.79 182.066 163.894 + vertex -677.465 178.172 163.483 + endloop + endfacet + facet normal -0.946045 -0.32364 0.0160027 + outer loop + vertex -678.79 182.066 163.894 + vertex -678.799 181.995 161.954 + vertex -677.465 178.172 163.483 + endloop + endfacet + facet normal -0.943705 -0.330766 -0.00385042 + outer loop + vertex -677.465 178.172 163.483 + vertex -678.799 181.995 161.954 + vertex -677.197 177.428 161.662 + endloop + endfacet + facet normal -0.943077 -0.33202 0.0192047 + outer loop + vertex -678.799 181.995 161.954 + vertex -678.811 181.919 160.026 + vertex -677.197 177.428 161.662 + endloop + endfacet + facet normal -0.944793 -0.325293 0.0393724 + outer loop + vertex -677.197 177.428 161.662 + vertex -678.811 181.919 160.026 + vertex -677.48 178.005 159.622 + endloop + endfacet + facet normal -0.945804 -0.323931 0.0228675 + outer loop + vertex -678.811 181.919 160.026 + vertex -678.827 181.829 158.101 + vertex -677.48 178.005 159.622 + endloop + endfacet + facet normal -0.943603 -0.331065 0.00297561 + outer loop + vertex -677.48 178.005 159.622 + vertex -678.827 181.829 158.101 + vertex -677.215 177.233 157.801 + endloop + endfacet + facet normal -0.942735 -0.332383 0.0277871 + outer loop + vertex -678.827 181.829 158.101 + vertex -678.844 181.715 156.172 + vertex -677.215 177.233 157.801 + endloop + endfacet + facet normal -0.944156 -0.326269 0.0460249 + outer loop + vertex -677.215 177.233 157.801 + vertex -678.844 181.715 156.172 + vertex -677.507 177.789 155.752 + endloop + endfacet + facet normal -0.945366 -0.324785 0.0282574 + outer loop + vertex -678.844 181.715 156.172 + vertex -678.858 181.588 154.234 + vertex -677.507 177.789 155.752 + endloop + endfacet + facet normal -0.943379 -0.331582 0.00947597 + outer loop + vertex -677.507 177.789 155.752 + vertex -678.858 181.588 154.234 + vertex -677.249 177.002 153.923 + endloop + endfacet + facet normal -0.942314 -0.332923 0.034747 + outer loop + vertex -678.858 181.588 154.234 + vertex -678.878 181.443 152.295 + vertex -677.249 177.002 153.923 + endloop + endfacet + facet normal -0.943734 -0.326167 0.0545966 + outer loop + vertex -677.249 177.002 153.923 + vertex -678.878 181.443 152.295 + vertex -677.55 177.53 151.876 + endloop + endfacet + facet normal -0.945281 -0.324484 0.0339739 + outer loop + vertex -678.878 181.443 152.295 + vertex -678.898 181.298 150.364 + vertex -677.55 177.53 151.876 + endloop + endfacet + facet normal -0.943436 -0.331185 0.0156308 + outer loop + vertex -677.55 177.53 151.876 + vertex -678.898 181.298 150.364 + vertex -677.293 176.712 150.068 + endloop + endfacet + facet normal -0.942314 -0.332353 0.039822 + outer loop + vertex -678.898 181.298 150.364 + vertex -678.926 181.147 148.449 + vertex -677.293 176.712 150.068 + endloop + endfacet + facet normal -0.943712 -0.325046 0.0612518 + outer loop + vertex -677.293 176.712 150.068 + vertex -678.926 181.147 148.449 + vertex -677.597 177.212 148.046 + endloop + endfacet + facet normal -0.945188 -0.32368 0.0430244 + outer loop + vertex -678.926 181.147 148.449 + vertex -678.956 180.983 146.551 + vertex -677.597 177.212 148.046 + endloop + endfacet + facet normal -0.94319 -0.331571 0.0213099 + outer loop + vertex -677.597 177.212 148.046 + vertex -678.956 180.983 146.551 + vertex -677.341 176.368 146.236 + endloop + endfacet + facet normal -0.941806 -0.332844 0.0470821 + outer loop + vertex -678.956 180.983 146.551 + vertex -678.982 180.789 144.659 + vertex -677.341 176.368 146.236 + endloop + endfacet + facet normal -0.942929 -0.326227 0.0667887 + outer loop + vertex -677.341 176.368 146.236 + vertex -678.982 180.789 144.659 + vertex -677.636 176.804 144.201 + endloop + endfacet + facet normal -0.944701 -0.32455 0.0469729 + outer loop + vertex -678.982 180.789 144.659 + vertex -678.994 180.546 142.742 + vertex -677.636 176.804 144.201 + endloop + endfacet + facet normal -0.943046 -0.33152 0.0275643 + outer loop + vertex -677.636 176.804 144.201 + vertex -678.994 180.546 142.742 + vertex -677.362 175.867 142.274 + endloop + endfacet + facet normal -0.941328 -0.333402 0.0523971 + outer loop + vertex -678.994 180.546 142.742 + vertex -679.012 180.291 140.789 + vertex -677.362 175.867 142.274 + endloop + endfacet + facet normal -0.94246 -0.324728 0.0795007 + outer loop + vertex -677.362 175.867 142.274 + vertex -679.012 180.291 140.789 + vertex -677.69 176.307 140.185 + endloop + endfacet + facet normal -0.944761 -0.322395 0.0590666 + outer loop + vertex -679.012 180.291 140.789 + vertex -679.067 180.089 138.811 + vertex -677.69 176.307 140.185 + endloop + endfacet + facet normal -0.944725 -0.322615 0.0584272 + outer loop + vertex -677.69 176.307 140.185 + vertex -679.067 180.089 138.811 + vertex -677.602 175.708 138.304 + endloop + endfacet + facet normal -0.944015 -0.323246 0.0659316 + outer loop + vertex -679.067 180.089 138.811 + vertex -679.149 179.925 136.835 + vertex -677.602 175.708 138.304 + endloop + endfacet + facet normal -0.944916 -0.311084 0.101785 + outer loop + vertex -677.602 175.708 138.304 + vertex -679.149 179.925 136.835 + vertex -677.999 176.27 136.343 + endloop + endfacet + facet normal -0.949359 -0.30748 0.0646063 + outer loop + vertex -679.149 179.925 136.835 + vertex -679.196 179.663 134.895 + vertex -677.999 176.27 136.343 + endloop + endfacet + facet normal -0.946586 -0.320993 0.0306483 + outer loop + vertex -677.999 176.27 136.343 + vertex -679.196 179.663 134.895 + vertex -677.673 175.16 134.75 + endloop + endfacet + facet normal -0.944929 -0.321431 0.0615729 + outer loop + vertex -679.196 179.663 134.895 + vertex -679.169 179.211 132.949 + vertex -677.673 175.16 134.75 + endloop + endfacet + facet normal -0.94355 -0.328102 0.0454199 + outer loop + vertex -677.673 175.16 134.75 + vertex -679.169 179.211 132.949 + vertex -677.53 174.471 132.744 + endloop + endfacet + facet normal -0.941986 -0.328567 0.0685957 + outer loop + vertex -679.169 179.211 132.949 + vertex -679.206 178.9 130.951 + vertex -677.53 174.471 132.744 + endloop + endfacet + facet normal -0.941856 -0.329379 0.0664672 + outer loop + vertex -677.53 174.471 132.744 + vertex -679.206 178.9 130.951 + vertex -677.556 174.134 130.713 + endloop + endfacet + facet normal -0.94098 -0.3296 0.0769457 + outer loop + vertex -679.206 178.9 130.951 + vertex -679.284 178.662 128.974 + vertex -677.556 174.134 130.713 + endloop + endfacet + facet normal -0.940998 -0.32946 0.077328 + outer loop + vertex -677.556 174.134 130.713 + vertex -679.284 178.662 128.974 + vertex -677.637 173.904 128.743 + endloop + endfacet + facet normal -0.940225 -0.329597 0.0856918 + outer loop + vertex -679.284 178.662 128.974 + vertex -679.367 178.391 127.022 + vertex -677.637 173.904 128.743 + endloop + endfacet + facet normal -0.94018 -0.330026 0.0845279 + outer loop + vertex -677.637 173.904 128.743 + vertex -679.367 178.391 127.022 + vertex -677.71 173.613 126.806 + endloop + endfacet + facet normal -0.940513 -0.329978 0.0809293 + outer loop + vertex -679.367 178.391 127.022 + vertex -679.414 178.052 125.092 + vertex -677.71 173.613 126.806 + endloop + endfacet + facet normal -0.940458 -0.330441 0.0796768 + outer loop + vertex -677.71 173.613 126.806 + vertex -679.414 178.052 125.092 + vertex -677.754 173.275 124.879 + endloop + endfacet + facet normal -0.94007 -0.330495 0.0839103 + outer loop + vertex -679.414 178.052 125.092 + vertex -679.455 177.682 123.183 + vertex -677.754 173.275 124.879 + endloop + endfacet + facet normal -0.940148 -0.329768 0.0858759 + outer loop + vertex -677.754 173.275 124.879 + vertex -679.455 177.682 123.183 + vertex -677.798 172.902 122.968 + endloop + endfacet + facet normal -0.939596 -0.329829 0.0915024 + outer loop + vertex -679.455 177.682 123.183 + vertex -679.507 177.309 121.3 + vertex -677.798 172.902 122.968 + endloop + endfacet + facet normal -0.939534 -0.330533 0.089579 + outer loop + vertex -677.798 172.902 122.968 + vertex -679.507 177.309 121.3 + vertex -677.848 172.535 121.085 + endloop + endfacet + facet normal -0.939122 -0.330574 0.0936492 + outer loop + vertex -679.507 177.309 121.3 + vertex -679.562 176.94 119.442 + vertex -677.848 172.535 121.085 + endloop + endfacet + facet normal -0.939057 -0.331391 0.0913907 + outer loop + vertex -677.848 172.535 121.085 + vertex -679.562 176.94 119.442 + vertex -677.904 172.18 119.221 + endloop + endfacet + facet normal -0.938094 -0.331477 0.100507 + outer loop + vertex -679.562 176.94 119.442 + vertex -679.628 176.561 117.583 + vertex -677.904 172.18 119.221 + endloop + endfacet + facet normal -0.938071 -0.331857 0.0994684 + outer loop + vertex -677.904 172.18 119.221 + vertex -679.628 176.561 117.583 + vertex -677.97 171.806 117.356 + endloop + endfacet + facet normal -0.937808 -0.331879 0.101845 + outer loop + vertex -679.628 176.561 117.583 + vertex -679.692 176.17 115.713 + vertex -677.97 171.806 117.356 + endloop + endfacet + facet normal -0.93783 -0.331503 0.102864 + outer loop + vertex -677.97 171.806 117.356 + vertex -679.692 176.17 115.713 + vertex -678.038 171.416 115.477 + endloop + endfacet + facet normal -0.937169 -0.331556 0.108563 + outer loop + vertex -679.692 176.17 115.713 + vertex -679.766 175.761 113.827 + vertex -678.038 171.416 115.477 + endloop + endfacet + facet normal -0.93719 -0.331034 0.10996 + outer loop + vertex -678.038 171.416 115.477 + vertex -679.766 175.761 113.827 + vertex -678.115 171.006 113.587 + endloop + endfacet + facet normal -0.936289 -0.331089 0.117231 + outer loop + vertex -679.766 175.761 113.827 + vertex -679.853 175.335 111.931 + vertex -678.115 171.006 113.587 + endloop + endfacet + facet normal -0.93627 -0.331819 0.115303 + outer loop + vertex -678.115 171.006 113.587 + vertex -679.853 175.335 111.931 + vertex -678.196 170.576 111.689 + endloop + endfacet + facet normal -0.935405 -0.331858 0.122018 + outer loop + vertex -679.853 175.335 111.931 + vertex -679.945 174.897 110.031 + vertex -678.196 170.576 111.689 + endloop + endfacet + facet normal -0.935391 -0.332685 0.11985 + outer loop + vertex -678.196 170.576 111.689 + vertex -679.945 174.897 110.031 + vertex -678.287 170.146 109.787 + endloop + endfacet + facet normal -0.93417 -0.332723 0.128926 + outer loop + vertex -679.945 174.897 110.031 + vertex -680.048 174.447 108.128 + vertex -678.287 170.146 109.787 + endloop + endfacet + facet normal -0.934168 -0.333578 0.126708 + outer loop + vertex -678.287 170.146 109.787 + vertex -680.048 174.447 108.128 + vertex -678.387 169.704 107.882 + endloop + endfacet + facet normal -0.933025 -0.333599 0.134816 + outer loop + vertex -680.048 174.447 108.128 + vertex -680.159 173.989 106.226 + vertex -678.387 169.704 107.882 + endloop + endfacet + facet normal -0.933021 -0.333281 0.135633 + outer loop + vertex -678.387 169.704 107.882 + vertex -680.159 173.989 106.226 + vertex -678.502 169.248 105.974 + endloop + endfacet + facet normal -0.931579 -0.333287 0.14519 + outer loop + vertex -680.159 173.989 106.226 + vertex -680.287 173.521 104.329 + vertex -678.502 169.248 105.974 + endloop + endfacet + facet normal -0.931597 -0.333738 0.144036 + outer loop + vertex -678.502 169.248 105.974 + vertex -680.287 173.521 104.329 + vertex -678.628 168.779 104.069 + endloop + endfacet + facet normal -0.930589 -0.333736 0.150415 + outer loop + vertex -680.287 173.521 104.329 + vertex -680.423 173.052 102.447 + vertex -678.628 168.779 104.069 + endloop + endfacet + facet normal -0.930616 -0.334217 0.149177 + outer loop + vertex -678.628 168.779 104.069 + vertex -680.423 173.052 102.447 + vertex -678.763 168.31 102.177 + endloop + endfacet + facet normal -0.929432 -0.334213 0.15639 + outer loop + vertex -680.423 173.052 102.447 + vertex -680.571 172.59 100.58 + vertex -678.763 168.31 102.177 + endloop + endfacet + facet normal -0.929363 -0.333351 0.158623 + outer loop + vertex -678.763 168.31 102.177 + vertex -680.571 172.59 100.58 + vertex -678.915 167.84 100.298 + endloop + endfacet + facet normal -0.928228 -0.333343 0.165152 + outer loop + vertex -680.571 172.59 100.58 + vertex -680.737 172.134 98.7239 + vertex -678.915 167.84 100.298 + endloop + endfacet + facet normal -0.928285 -0.333894 0.163715 + outer loop + vertex -678.915 167.84 100.298 + vertex -680.737 172.134 98.7239 + vertex -679.081 167.386 98.4336 + endloop + endfacet + facet normal -0.926177 -0.333866 0.175298 + outer loop + vertex -680.737 172.134 98.7239 + vertex -680.925 171.68 96.8699 + vertex -679.081 167.386 98.4336 + endloop + endfacet + facet normal -0.926085 -0.333168 0.177106 + outer loop + vertex -679.081 167.386 98.4336 + vertex -680.925 171.68 96.8699 + vertex -679.27 166.925 96.5769 + endloop + endfacet + facet normal -0.925017 -0.333139 0.182653 + outer loop + vertex -680.925 171.68 96.8699 + vertex -681.117 171.197 95.014 + vertex -679.27 166.925 96.5769 + endloop + endfacet + facet normal -0.925091 -0.333653 0.181334 + outer loop + vertex -679.27 166.925 96.5769 + vertex -681.117 171.197 95.014 + vertex -679.462 166.453 94.7318 + endloop + endfacet + facet normal -0.922842 -0.333541 0.192648 + outer loop + vertex -681.117 171.197 95.014 + vertex -681.303 170.641 93.1623 + vertex -679.462 166.453 94.7318 + endloop + endfacet + facet normal -0.922982 -0.334448 0.190392 + outer loop + vertex -679.462 166.453 94.7318 + vertex -681.303 170.641 93.1623 + vertex -679.649 165.92 92.8862 + endloop + endfacet + facet normal -0.918943 -0.33415 0.209493 + outer loop + vertex -681.303 170.641 93.1623 + vertex -681.489 169.992 91.3107 + vertex -679.649 165.92 92.8862 + endloop + endfacet + facet normal -0.919483 -0.337349 0.201857 + outer loop + vertex -679.649 165.92 92.8862 + vertex -681.489 169.992 91.3107 + vertex -679.852 165.33 90.9768 + endloop + endfacet + facet normal -0.915398 -0.337204 0.219861 + outer loop + vertex -681.489 169.992 91.3107 + vertex -681.745 169.414 89.3608 + vertex -679.852 165.33 90.9768 + endloop + endfacet + facet normal -0.914515 -0.332749 0.230087 + outer loop + vertex -679.852 165.33 90.9768 + vertex -681.745 169.414 89.3608 + vertex -680.16 164.68 88.8102 + endloop + endfacet + facet normal -0.909853 -0.33319 0.24729 + outer loop + vertex -681.745 169.414 89.3608 + vertex -682.149 169.07 87.4086 + vertex -680.16 164.68 88.8102 + endloop + endfacet + facet normal -0.899942 -0.309657 0.306946 + outer loop + vertex -680.16 164.68 88.8102 + vertex -682.149 169.07 87.4086 + vertex -681.263 166.009 86.9181 + endloop + endfacet + facet normal -0.91859 -0.305957 0.250166 + outer loop + vertex -682.149 169.07 87.4086 + vertex -682.55 168.804 85.6114 + vertex -681.263 166.009 86.9181 + endloop + endfacet + facet normal -0.92012 -0.314512 0.23337 + outer loop + vertex -681.263 166.009 86.9181 + vertex -682.55 168.804 85.6114 + vertex -681.384 165.283 85.4627 + endloop + endfacet + facet normal -0.917395 -0.314077 0.244423 + outer loop + vertex -682.55 168.804 85.6114 + vertex -682.837 168.283 83.8636 + vertex -681.384 165.283 85.4627 + endloop + endfacet + facet normal -0.917338 -0.313636 0.245199 + outer loop + vertex -681.384 165.283 85.4627 + vertex -682.837 168.283 83.8636 + vertex -681.637 164.65 83.7054 + endloop + endfacet + facet normal -0.913994 -0.313091 0.258049 + outer loop + vertex -682.837 168.283 83.8636 + vertex -683.176 167.783 82.0577 + vertex -681.637 164.65 83.7054 + endloop + endfacet + facet normal -0.913767 -0.311638 0.260599 + outer loop + vertex -681.637 164.65 83.7054 + vertex -683.176 167.783 82.0577 + vertex -681.984 164.128 81.8648 + endloop + endfacet + facet normal -0.908897 -0.310962 0.277866 + outer loop + vertex -683.176 167.783 82.0577 + vertex -683.571 167.31 80.2358 + vertex -681.984 164.128 81.8648 + endloop + endfacet + facet normal -0.908884 -0.310898 0.277979 + outer loop + vertex -681.984 164.128 81.8648 + vertex -683.571 167.31 80.2358 + vertex -682.381 163.643 80.024 + endloop + endfacet + facet normal -0.904521 -0.31032 0.292477 + outer loop + vertex -683.571 167.31 80.2358 + vertex -683.996 166.844 78.4277 + vertex -682.381 163.643 80.024 + endloop + endfacet + facet normal -0.90466 -0.310926 0.291403 + outer loop + vertex -682.381 163.643 80.024 + vertex -683.996 166.844 78.4277 + vertex -682.801 163.162 78.2074 + endloop + endfacet + facet normal -0.899123 -0.310172 0.308823 + outer loop + vertex -683.996 166.844 78.4277 + vertex -684.449 166.369 76.6314 + vertex -682.801 163.162 78.2074 + endloop + endfacet + facet normal -0.899257 -0.310687 0.307914 + outer loop + vertex -682.801 163.162 78.2074 + vertex -684.449 166.369 76.6314 + vertex -683.249 162.671 76.4049 + endloop + endfacet + facet normal -0.892574 -0.309729 0.327687 + outer loop + vertex -684.449 166.369 76.6314 + vertex -684.942 165.887 74.8313 + vertex -683.249 162.671 76.4049 + endloop + endfacet + facet normal -0.892873 -0.310768 0.325885 + outer loop + vertex -683.249 162.671 76.4049 + vertex -684.942 165.887 74.8313 + vertex -683.737 162.178 74.5974 + endloop + endfacet + facet normal -0.886294 -0.309789 0.344259 + outer loop + vertex -684.942 165.887 74.8313 + vertex -685.483 165.417 73.0159 + vertex -683.737 162.178 74.5974 + endloop + endfacet + facet normal -0.88592 -0.308598 0.346285 + outer loop + vertex -683.737 162.178 74.5974 + vertex -685.483 165.417 73.0159 + vertex -684.28 161.687 72.7703 + endloop + endfacet + facet normal -0.877787 -0.307368 0.367445 + outer loop + vertex -685.483 165.417 73.0159 + vertex -686.085 164.945 71.1833 + vertex -684.28 161.687 72.7703 + endloop + endfacet + facet normal -0.878599 -0.309746 0.363485 + outer loop + vertex -684.28 161.687 72.7703 + vertex -686.085 164.945 71.1833 + vertex -684.876 161.21 70.9231 + endloop + endfacet + facet normal -0.869068 -0.308291 0.386882 + outer loop + vertex -686.085 164.945 71.1833 + vertex -686.737 164.49 69.3569 + vertex -684.876 161.21 70.9231 + endloop + endfacet + facet normal -0.869087 -0.30834 0.386801 + outer loop + vertex -684.876 161.21 70.9231 + vertex -686.737 164.49 69.3569 + vertex -685.53 160.736 69.0749 + endloop + endfacet + facet normal -0.859753 -0.306946 0.408178 + outer loop + vertex -686.737 164.49 69.3569 + vertex -687.43 164.058 67.5731 + vertex -685.53 160.736 69.0749 + endloop + endfacet + facet normal -0.859994 -0.307505 0.407248 + outer loop + vertex -685.53 160.736 69.0749 + vertex -687.43 164.058 67.5731 + vertex -686.227 160.286 67.2635 + endloop + endfacet + facet normal -0.850214 -0.306114 0.428288 + outer loop + vertex -687.43 164.058 67.5731 + vertex -688.147 163.666 65.869 + vertex -686.227 160.286 67.2635 + endloop + endfacet + facet normal -0.850036 -0.305764 0.428892 + outer loop + vertex -686.227 160.286 67.2635 + vertex -688.147 163.666 65.869 + vertex -686.953 159.869 65.5274 + endloop + endfacet + facet normal -0.838257 -0.304189 0.452541 + outer loop + vertex -688.147 163.666 65.869 + vertex -688.889 163.308 64.2541 + vertex -686.953 159.869 65.5274 + endloop + endfacet + facet normal -0.839066 -0.305538 0.450128 + outer loop + vertex -686.953 159.869 65.5274 + vertex -688.889 163.308 64.2541 + vertex -687.699 159.498 63.8864 + endloop + endfacet + facet normal -0.826693 -0.303929 0.473504 + outer loop + vertex -688.889 163.308 64.2541 + vertex -689.655 162.999 62.7172 + vertex -687.699 159.498 63.8864 + endloop + endfacet + facet normal -0.825922 -0.30281 0.475562 + outer loop + vertex -687.699 159.498 63.8864 + vertex -689.655 162.999 62.7172 + vertex -688.476 159.161 62.3212 + endloop + endfacet + facet normal -0.811416 -0.30098 0.501014 + outer loop + vertex -689.655 162.999 62.7172 + vertex -690.475 162.71 61.2163 + vertex -688.476 159.161 62.3212 + endloop + endfacet + facet normal -0.812681 -0.302646 0.49795 + outer loop + vertex -688.476 159.161 62.3212 + vertex -690.475 162.71 61.2163 + vertex -689.298 158.86 60.7978 + endloop + endfacet + facet normal -0.795892 -0.300517 0.525591 + outer loop + vertex -690.475 162.71 61.2163 + vertex -691.36 162.44 59.7211 + vertex -689.298 158.86 60.7978 + endloop + endfacet + facet normal -0.794977 -0.299379 0.527621 + outer loop + vertex -689.298 158.86 60.7978 + vertex -691.36 162.44 59.7211 + vertex -690.197 158.565 59.2751 + endloop + endfacet + facet normal -0.779216 -0.297419 0.551692 + outer loop + vertex -691.36 162.44 59.7211 + vertex -692.327 162.196 58.2245 + vertex -690.197 158.565 59.2751 + endloop + endfacet + facet normal -0.779896 -0.298221 0.550297 + outer loop + vertex -690.197 158.565 59.2751 + vertex -692.327 162.196 58.2245 + vertex -691.176 158.309 57.7494 + endloop + endfacet + facet normal -0.760531 -0.295869 0.577974 + outer loop + vertex -692.327 162.196 58.2245 + vertex -693.373 162.01 56.7533 + vertex -691.176 158.309 57.7494 + endloop + endfacet + facet normal -0.760851 -0.29622 0.577373 + outer loop + vertex -691.176 158.309 57.7494 + vertex -693.373 162.01 56.7533 + vertex -692.236 158.104 56.2467 + endloop + endfacet + facet normal -0.738769 -0.293593 0.60665 + outer loop + vertex -693.373 162.01 56.7533 + vertex -694.48 161.896 55.3493 + vertex -692.236 158.104 56.2467 + endloop + endfacet + facet normal -0.740152 -0.29497 0.604291 + outer loop + vertex -692.236 158.104 56.2467 + vertex -694.48 161.896 55.3493 + vertex -693.348 157.968 54.8187 + endloop + endfacet + facet normal -0.714133 -0.291794 0.636294 + outer loop + vertex -694.48 161.896 55.3493 + vertex -695.587 161.796 54.0617 + vertex -693.348 157.968 54.8187 + endloop + endfacet + facet normal -0.714687 -0.292286 0.635445 + outer loop + vertex -693.348 157.968 54.8187 + vertex -695.587 161.796 54.0617 + vertex -694.474 157.88 53.5113 + endloop + endfacet + facet normal -0.68472 -0.288526 0.669261 + outer loop + vertex -695.587 161.796 54.0617 + vertex -696.622 161.645 52.9373 + vertex -694.474 157.88 53.5113 + endloop + endfacet + facet normal -0.686029 -0.289544 0.667479 + outer loop + vertex -694.474 157.88 53.5113 + vertex -696.622 161.645 52.9373 + vertex -695.597 157.853 52.3458 + endloop + endfacet + facet normal -0.673679 -0.288237 0.680497 + outer loop + vertex -696.622 161.645 52.9373 + vertex -697.632 161.775 51.9918 + vertex -695.597 157.853 52.3458 + endloop + endfacet + facet normal -0.662356 -0.2811 0.694455 + outer loop + vertex -695.597 157.853 52.3458 + vertex -697.632 161.775 51.9918 + vertex -696.67 157.885 51.3348 + endloop + endfacet + facet normal -0.663081 -0.281158 0.693739 + outer loop + vertex -697.632 161.775 51.9918 + vertex -698.561 162.023 51.2053 + vertex -696.67 157.885 51.3348 + endloop + endfacet + facet normal -0.637813 -0.268739 0.721785 + outer loop + vertex -696.67 157.885 51.3348 + vertex -698.561 162.023 51.2053 + vertex -697.616 157.908 50.5079 + endloop + endfacet + facet normal -0.647826 -0.26947 0.712536 + outer loop + vertex -698.561 162.023 51.2053 + vertex -699.271 162.2 50.6263 + vertex -697.616 157.908 50.5079 + endloop + endfacet + facet normal -0.615032 -0.257726 0.745193 + outer loop + vertex -697.616 157.908 50.5079 + vertex -699.271 162.2 50.6263 + vertex -698.318 157.905 49.9276 + endloop + endfacet + facet normal -0.616841 -0.257876 0.743644 + outer loop + vertex -699.271 162.2 50.6263 + vertex -699.7 162.204 50.272 + vertex -698.318 157.905 49.9276 + endloop + endfacet + facet normal -0.593298 -0.251981 0.764528 + outer loop + vertex -698.318 157.905 49.9276 + vertex -699.7 162.204 50.272 + vertex -698.72 157.871 49.6043 + endloop + endfacet + facet normal -0.651831 -0.257335 0.713369 + outer loop + vertex -699.7 162.204 50.272 + vertex -699.852 162.184 50.1258 + vertex -698.72 157.871 49.6043 + endloop + endfacet + facet normal -0.602921 -0.249853 0.757667 + outer loop + vertex -698.72 157.871 49.6043 + vertex -699.852 162.184 50.1258 + vertex -698.857 157.816 49.477 + endloop + endfacet + facet normal -0.958033 -0.185753 -0.21833 + outer loop + vertex -699.852 162.184 50.1258 + vertex -699.86 162.246 50.1065 + vertex -698.857 157.816 49.477 + endloop + endfacet + facet normal -0.903026 -0.146968 -0.403665 + outer loop + vertex -698.857 157.816 49.477 + vertex -699.86 162.246 50.1065 + vertex -698.853 157.86 49.4509 + endloop + endfacet + facet normal -0.385976 0.0490844 -0.921202 + outer loop + vertex -699.86 162.246 50.1065 + vertex -699.875 162.471 50.1252 + vertex -698.853 157.86 49.4509 + endloop + endfacet + facet normal -0.837211 -0.107274 -0.536256 + outer loop + vertex -698.853 157.86 49.4509 + vertex -699.875 162.471 50.1252 + vertex -698.875 158.03 49.4516 + endloop + endfacet + facet normal -0.704233 -0.258902 0.661079 + outer loop + vertex -699.875 162.471 50.1252 + vertex -699.961 162.692 50.1202 + vertex -698.875 158.03 49.4516 + endloop + endfacet + facet normal -0.455382 -0.229468 0.860216 + outer loop + vertex -698.875 158.03 49.4516 + vertex -699.961 162.692 50.1202 + vertex -698.966 158.176 49.4425 + endloop + endfacet + facet normal -0.00740977 -0.149987 0.98866 + outer loop + vertex -699.961 162.692 50.1202 + vertex -699.99 162.069 50.0254 + vertex -698.966 158.176 49.4425 + endloop + endfacet + facet normal -0.245201 -0.20633 0.947262 + outer loop + vertex -698.966 158.176 49.4425 + vertex -699.99 162.069 50.0254 + vertex -699.076 158.158 49.41 + endloop + endfacet + facet normal 0.0331216 -0.147819 0.98846 + outer loop + vertex -699.99 162.069 50.0254 + vertex -699.909 161.081 49.8749 + vertex -699.076 158.158 49.41 + endloop + endfacet + facet normal -0.498346 -0.272957 0.822889 + outer loop + vertex -699.076 158.158 49.41 + vertex -699.909 161.081 49.8749 + vertex -699.139 158.057 49.3385 + endloop + endfacet + facet normal -0.967619 -0.251124 0.025481 + outer loop + vertex -699.139 158.057 49.3385 + vertex -699.909 161.081 49.8749 + vertex -700.054 161.637 49.8844 + endloop + endfacet + facet normal -0.72364 -0.19804 -0.661154 + outer loop + vertex -697.779 166.716 290.407 + vertex -696.607 166.39 289.222 + vertex -696.748 162.033 290.681 + endloop + endfacet + facet normal -0.723458 -0.156848 -0.672315 + outer loop + vertex -696.607 166.39 289.222 + vertex -697.779 166.716 290.407 + vertex -697.502 171.419 289.012 + endloop + endfacet + facet normal -0.748207 -0.160061 -0.643868 + outer loop + vertex -697.502 171.419 289.012 + vertex -696.319 170.958 287.751 + vertex -696.607 166.39 289.222 + endloop + endfacet + facet normal -0.745482 -0.121866 -0.65529 + outer loop + vertex -697.502 171.419 289.012 + vertex -697.026 176.293 287.563 + vertex -696.319 170.958 287.751 + endloop + endfacet + facet normal -0.775438 -0.124558 -0.619016 + outer loop + vertex -697.026 176.293 287.563 + vertex -695.931 175.327 286.386 + vertex -696.319 170.958 287.751 + endloop + endfacet + facet normal -0.767605 -0.128061 -0.627999 + outer loop + vertex -696.319 170.958 287.751 + vertex -695.931 175.327 286.386 + vertex -695.206 170.877 286.407 + endloop + endfacet + facet normal -0.76424 -0.167335 -0.622845 + outer loop + vertex -696.319 170.958 287.751 + vertex -695.206 170.877 286.407 + vertex -695.447 166.215 287.955 + endloop + endfacet + facet normal -0.783628 -0.130573 -0.607353 + outer loop + vertex -695.931 175.327 286.386 + vertex -694.912 176.339 284.854 + vertex -695.206 170.877 286.407 + endloop + endfacet + facet normal -0.79693 -0.125196 -0.590955 + outer loop + vertex -695.206 170.877 286.407 + vertex -694.912 176.339 284.854 + vertex -694.179 170.979 285.001 + endloop + endfacet + facet normal -0.790206 -0.168603 -0.589192 + outer loop + vertex -695.206 170.877 286.407 + vertex -694.179 170.979 285.001 + vertex -694.367 166.23 286.612 + endloop + endfacet + facet normal -0.821994 -0.127639 -0.555009 + outer loop + vertex -694.912 176.339 284.854 + vertex -693.911 175.61 283.54 + vertex -694.179 170.979 285.001 + endloop + endfacet + facet normal -0.821756 -0.127756 -0.555334 + outer loop + vertex -694.179 170.979 285.001 + vertex -693.911 175.61 283.54 + vertex -693.223 171.187 283.538 + endloop + endfacet + facet normal -0.813726 -0.169379 -0.556022 + outer loop + vertex -694.179 170.979 285.001 + vertex -693.223 171.187 283.538 + vertex -693.359 166.396 285.197 + endloop + endfacet + facet normal -0.831704 -0.129311 -0.539952 + outer loop + vertex -693.911 175.61 283.54 + vertex -693.034 176.829 281.897 + vertex -693.223 171.187 283.538 + endloop + endfacet + facet normal -0.842938 -0.124147 -0.523491 + outer loop + vertex -693.223 171.187 283.538 + vertex -693.034 176.829 281.897 + vertex -692.317 171.436 282.021 + endloop + endfacet + facet normal -0.833463 -0.170878 -0.52549 + outer loop + vertex -693.223 171.187 283.538 + vertex -692.317 171.436 282.021 + vertex -692.399 166.626 283.715 + endloop + endfacet + facet normal -0.864348 -0.126152 -0.486814 + outer loop + vertex -693.034 176.829 281.897 + vertex -692.144 176.178 280.485 + vertex -692.317 171.436 282.021 + endloop + endfacet + facet normal -0.859275 -0.128983 -0.494985 + outer loop + vertex -692.317 171.436 282.021 + vertex -692.144 176.178 280.485 + vertex -691.454 171.723 280.448 + endloop + endfacet + facet normal -0.868 -0.130466 -0.479119 + outer loop + vertex -692.144 176.178 280.485 + vertex -691.37 177.473 278.73 + vertex -691.454 171.723 280.448 + endloop + endfacet + facet normal -0.861226 -0.0947519 -0.499312 + outer loop + vertex -692.144 176.178 280.485 + vertex -693.034 176.829 281.897 + vertex -692.327 183.782 279.358 + endloop + endfacet + facet normal -0.885431 -0.0889437 -0.45618 + outer loop + vertex -692.144 176.178 280.485 + vertex -692.327 183.782 279.358 + vertex -691.37 177.473 278.73 + endloop + endfacet + facet normal -0.896375 -0.0928661 -0.43346 + outer loop + vertex -692.327 183.782 279.358 + vertex -690.813 184.437 276.086 + vertex -691.37 177.473 278.73 + endloop + endfacet + facet normal -0.891853 -0.0964409 -0.441925 + outer loop + vertex -690.555 176.871 277.217 + vertex -691.37 177.473 278.73 + vertex -690.813 184.437 276.086 + endloop + endfacet + facet normal -0.912202 -0.0908022 -0.399554 + outer loop + vertex -690.555 176.871 277.217 + vertex -690.813 184.437 276.086 + vertex -689.882 178.188 275.38 + endloop + endfacet + facet normal -0.920504 -0.0943413 -0.379172 + outer loop + vertex -690.813 184.437 276.086 + vertex -689.5 184.908 272.782 + vertex -689.882 178.188 275.38 + endloop + endfacet + facet normal -0.917677 -0.0968849 -0.385334 + outer loop + vertex -689.155 177.618 273.792 + vertex -689.882 178.188 275.38 + vertex -689.5 184.908 272.782 + endloop + endfacet + facet normal -0.932554 -0.0925496 -0.348966 + outer loop + vertex -689.155 177.618 273.792 + vertex -689.5 184.908 272.782 + vertex -688.588 178.977 271.916 + endloop + endfacet + facet normal -0.935523 -0.094247 -0.340463 + outer loop + vertex -689.5 184.908 272.782 + vertex -688.375 185.815 269.44 + vertex -688.588 178.977 271.916 + endloop + endfacet + facet normal -0.935952 -0.093846 -0.339392 + outer loop + vertex -687.945 178.456 270.287 + vertex -688.588 178.977 271.916 + vertex -688.375 185.815 269.44 + endloop + endfacet + facet normal -0.948227 -0.0905372 -0.304416 + outer loop + vertex -687.945 178.456 270.287 + vertex -688.375 185.815 269.44 + vertex -687.476 179.823 268.421 + endloop + endfacet + facet normal -0.949171 -0.0912164 -0.301254 + outer loop + vertex -688.375 185.815 269.44 + vertex -687.393 186.872 266.025 + vertex -687.476 179.823 268.421 + endloop + endfacet + facet normal -0.951226 -0.0891767 -0.295324 + outer loop + vertex -686.917 179.268 266.788 + vertex -687.476 179.823 268.421 + vertex -687.393 186.872 266.025 + endloop + endfacet + facet normal -0.961583 -0.0863384 -0.260584 + outer loop + vertex -686.917 179.268 266.788 + vertex -687.393 186.872 266.025 + vertex -686.538 180.595 264.95 + endloop + endfacet + facet normal -0.962036 -0.0867091 -0.258782 + outer loop + vertex -687.393 186.872 266.025 + vertex -686.551 187.831 262.573 + vertex -686.538 180.595 264.95 + endloop + endfacet + facet normal -0.962099 -0.0866397 -0.25857 + outer loop + vertex -686.052 179.973 263.35 + vertex -686.538 180.595 264.95 + vertex -686.551 187.831 262.573 + endloop + endfacet + facet normal -0.97089 -0.0838165 -0.224381 + outer loop + vertex -686.052 179.973 263.35 + vertex -686.551 187.831 262.573 + vertex -685.752 181.359 261.531 + endloop + endfacet + facet normal -0.972307 -0.0850707 -0.217673 + outer loop + vertex -686.551 187.831 262.573 + vertex -685.859 188.941 259.047 + vertex -685.752 181.359 261.531 + endloop + endfacet + facet normal -0.972313 -0.085063 -0.217649 + outer loop + vertex -685.341 180.893 259.881 + vertex -685.752 181.359 261.531 + vertex -685.859 188.941 259.047 + endloop + endfacet + facet normal -0.978998 -0.0822685 -0.186536 + outer loop + vertex -685.341 180.893 259.881 + vertex -685.859 188.941 259.047 + vertex -685.106 182.794 257.807 + endloop + endfacet + facet normal -0.978642 -0.0818104 -0.188591 + outer loop + vertex -685.859 188.941 259.047 + vertex -685.368 191.261 255.495 + vertex -685.106 182.794 257.807 + endloop + endfacet + facet normal -0.9779 -0.0827221 -0.192014 + outer loop + vertex -684.627 183.353 255.129 + vertex -685.106 182.794 257.807 + vertex -685.368 191.261 255.495 + endloop + endfacet + facet normal -0.981815 -0.0840993 -0.170198 + outer loop + vertex -685.368 191.261 255.495 + vertex -684.84 191.875 252.147 + vertex -684.627 183.353 255.129 + endloop + endfacet + facet normal -0.973404 -0.0969623 -0.207563 + outer loop + vertex -684.627 183.353 255.129 + vertex -684.84 191.875 252.147 + vertex -683.781 181.363 252.09 + endloop + endfacet + facet normal -0.984483 -0.0984168 -0.145285 + outer loop + vertex -684.84 191.875 252.147 + vertex -684.357 192.403 248.516 + vertex -683.781 181.363 252.09 + endloop + endfacet + facet normal -0.985223 -0.0970977 -0.141092 + outer loop + vertex -683.781 181.363 252.09 + vertex -684.357 192.403 248.516 + vertex -683.313 182.769 247.856 + endloop + endfacet + facet normal -0.987463 -0.0985595 -0.123297 + outer loop + vertex -684.357 192.403 248.516 + vertex -683.986 193.422 244.728 + vertex -683.313 182.769 247.856 + endloop + endfacet + facet normal -0.988684 -0.096225 -0.115083 + outer loop + vertex -683.313 182.769 247.856 + vertex -683.986 193.422 244.728 + vertex -682.974 183.851 244.035 + endloop + endfacet + facet normal -0.989739 -0.097078 -0.104841 + outer loop + vertex -683.986 193.422 244.728 + vertex -683.692 194.394 241.049 + vertex -682.974 183.851 244.035 + endloop + endfacet + facet normal -0.989679 -0.097203 -0.105297 + outer loop + vertex -682.974 183.851 244.035 + vertex -683.692 194.394 241.049 + vertex -682.677 184.793 240.38 + endloop + endfacet + facet normal -0.990651 -0.0980332 -0.0948637 + outer loop + vertex -683.692 194.394 241.049 + vertex -683.434 195.274 237.447 + vertex -682.677 184.793 240.38 + endloop + endfacet + facet normal -0.991011 -0.0972285 -0.0918954 + outer loop + vertex -682.677 184.793 240.38 + vertex -683.434 195.274 237.447 + vertex -682.429 185.653 236.794 + endloop + endfacet + facet normal -0.992047 -0.0982312 -0.0787033 + outer loop + vertex -683.434 195.274 237.447 + vertex -683.229 196.102 233.838 + vertex -682.429 185.653 236.794 + endloop + endfacet + facet normal -0.992154 -0.0979532 -0.0776916 + outer loop + vertex -682.429 185.653 236.794 + vertex -683.229 196.102 233.838 + vertex -682.229 186.487 233.181 + endloop + endfacet + facet normal -0.992675 -0.0985394 -0.0699037 + outer loop + vertex -683.229 196.102 233.838 + vertex -683.051 196.915 230.155 + vertex -682.229 186.487 233.181 + endloop + endfacet + facet normal -0.992843 -0.0980538 -0.068185 + outer loop + vertex -682.229 186.487 233.181 + vertex -683.051 196.915 230.155 + vertex -682.055 187.319 229.452 + endloop + endfacet + facet normal -0.993257 -0.0986271 -0.0609412 + outer loop + vertex -683.051 196.915 230.155 + vertex -682.898 197.711 226.375 + vertex -682.055 187.319 229.452 + endloop + endfacet + facet normal -0.993692 -0.0971866 -0.0559576 + outer loop + vertex -682.055 187.319 229.452 + vertex -682.898 197.711 226.375 + vertex -681.919 188.132 225.634 + endloop + endfacet + facet normal -0.993863 -0.0974895 -0.0522652 + outer loop + vertex -682.898 197.711 226.375 + vertex -682.772 198.482 222.536 + vertex -681.919 188.132 225.634 + endloop + endfacet + facet normal -0.993923 -0.0972729 -0.0515255 + outer loop + vertex -681.919 188.132 225.634 + vertex -682.772 198.482 222.536 + vertex -681.796 188.899 221.801 + endloop + endfacet + facet normal -0.994139 -0.0976958 -0.046297 + outer loop + vertex -682.772 198.482 222.536 + vertex -682.662 199.205 218.661 + vertex -681.796 188.899 221.801 + endloop + endfacet + facet normal -0.994024 -0.0981433 -0.0477976 + outer loop + vertex -681.796 188.899 221.801 + vertex -682.662 199.205 218.661 + vertex -681.68 189.617 217.93 + endloop + endfacet + facet normal -0.994229 -0.0985818 -0.0423227 + outer loop + vertex -682.662 199.205 218.661 + vertex -682.563 199.877 214.754 + vertex -681.68 189.617 217.93 + endloop + endfacet + facet normal -0.99444 -0.0976763 -0.0393384 + outer loop + vertex -681.68 189.617 217.93 + vertex -682.563 199.877 214.754 + vertex -681.59 190.289 213.985 + endloop + endfacet + facet normal -0.994486 -0.097799 -0.0378659 + outer loop + vertex -682.563 199.877 214.754 + vertex -682.474 200.489 210.85 + vertex -681.59 190.289 213.985 + endloop + endfacet + facet normal -0.994426 -0.0980613 -0.0387361 + outer loop + vertex -681.59 190.289 213.985 + vertex -682.474 200.489 210.85 + vertex -681.497 190.896 210.059 + endloop + endfacet + facet normal -0.994542 -0.098409 -0.0346641 + outer loop + vertex -682.474 200.489 210.85 + vertex -682.393 201.033 206.99 + vertex -681.497 190.896 210.059 + endloop + endfacet + facet normal -0.994603 -0.0981249 -0.0337078 + outer loop + vertex -681.497 190.896 210.059 + vertex -682.393 201.033 206.99 + vertex -681.42 191.426 206.237 + endloop + endfacet + facet normal -0.994682 -0.0983891 -0.0304417 + outer loop + vertex -682.393 201.033 206.99 + vertex -682.324 201.515 203.152 + vertex -681.42 191.426 206.237 + endloop + endfacet + facet normal -0.994785 -0.0978685 -0.0287093 + outer loop + vertex -681.42 191.426 206.237 + vertex -682.324 201.515 203.152 + vertex -681.357 191.899 202.433 + endloop + endfacet + facet normal -0.994835 -0.0980579 -0.0262432 + outer loop + vertex -682.324 201.515 203.152 + vertex -682.264 201.952 199.267 + vertex -681.357 191.899 202.433 + endloop + endfacet + facet normal -0.994922 -0.0975766 -0.0246899 + outer loop + vertex -681.357 191.899 202.433 + vertex -682.264 201.952 199.267 + vertex -681.302 192.333 198.526 + endloop + endfacet + facet normal -0.994965 -0.0977938 -0.0219265 + outer loop + vertex -682.264 201.952 199.267 + vertex -682.215 202.338 195.32 + vertex -681.302 192.333 198.526 + endloop + endfacet + facet normal -0.994847 -0.0984823 -0.0241086 + outer loop + vertex -681.302 192.333 198.526 + vertex -682.215 202.338 195.32 + vertex -681.242 192.691 194.556 + endloop + endfacet + facet normal -0.994899 -0.0987773 -0.0204497 + outer loop + vertex -682.215 202.338 195.32 + vertex -682.165 202.655 191.365 + vertex -681.242 192.691 194.556 + endloop + endfacet + facet normal -0.994817 -0.0992702 -0.0220127 + outer loop + vertex -681.242 192.691 194.556 + vertex -682.165 202.655 191.365 + vertex -681.18 192.949 190.589 + endloop + endfacet + facet normal -0.994877 -0.0996965 -0.0167587 + outer loop + vertex -682.165 202.655 191.365 + vertex -682.124 202.903 187.463 + vertex -681.18 192.949 190.589 + endloop + endfacet + facet normal -0.994729 -0.100619 -0.0197421 + outer loop + vertex -681.18 192.949 190.589 + vertex -682.124 202.903 187.463 + vertex -681.122 193.146 186.685 + endloop + endfacet + facet normal -0.994792 -0.101295 -0.0113503 + outer loop + vertex -682.124 202.903 187.463 + vertex -682.101 203.104 183.634 + vertex -681.122 193.146 186.685 + endloop + endfacet + facet normal -0.994754 -0.101563 -0.0122379 + outer loop + vertex -681.122 193.146 186.685 + vertex -682.101 203.104 183.634 + vertex -681.094 193.328 182.887 + endloop + endfacet + facet normal -0.994762 -0.102031 -0.00613884 + outer loop + vertex -682.101 203.104 183.634 + vertex -682.094 203.261 179.846 + vertex -681.094 193.328 182.887 + endloop + endfacet + facet normal -0.994846 -0.101326 -0.00380957 + outer loop + vertex -681.094 193.328 182.887 + vertex -682.094 203.261 179.846 + vertex -681.096 193.486 179.129 + endloop + endfacet + facet normal -0.994848 -0.101275 -0.00450554 + outer loop + vertex -682.094 203.261 179.846 + vertex -682.087 203.358 176.03 + vertex -681.096 193.486 179.129 + endloop + endfacet + facet normal -0.994929 -0.100553 -0.00217892 + outer loop + vertex -681.096 193.486 179.129 + vertex -682.087 203.358 176.03 + vertex -681.096 193.571 175.293 + endloop + endfacet + facet normal -0.994929 -0.100562 -0.00205247 + outer loop + vertex -682.087 203.358 176.03 + vertex -682.081 203.383 172.145 + vertex -681.096 193.571 175.293 + endloop + endfacet + facet normal -0.994905 -0.100776 -0.00272466 + outer loop + vertex -681.096 193.571 175.293 + vertex -682.081 203.383 172.145 + vertex -681.087 193.586 171.369 + endloop + endfacet + facet normal -0.994876 -0.101096 0.00135854 + outer loop + vertex -682.081 203.383 172.145 + vertex -682.083 203.349 168.216 + vertex -681.087 193.586 171.369 + endloop + endfacet + facet normal -0.994953 -0.10026 0.00397205 + outer loop + vertex -681.087 193.586 171.369 + vertex -682.083 203.349 168.216 + vertex -681.098 193.541 167.419 + endloop + endfacet + facet normal -0.99493 -0.100406 0.00579832 + outer loop + vertex -682.083 203.349 168.216 + vertex -682.097 203.262 164.295 + vertex -681.098 193.541 167.419 + endloop + endfacet + facet normal -0.994859 -0.101223 0.00323353 + outer loop + vertex -681.098 193.541 167.419 + vertex -682.097 203.262 164.295 + vertex -681.1 193.439 163.495 + endloop + endfacet + facet normal -0.994777 -0.101678 0.00892214 + outer loop + vertex -682.097 203.262 164.295 + vertex -682.117 203.119 160.408 + vertex -681.1 193.439 163.495 + endloop + endfacet + facet normal -0.994845 -0.100692 0.0120356 + outer loop + vertex -681.1 193.439 163.495 + vertex -682.117 203.119 160.408 + vertex -681.131 193.284 159.618 + endloop + endfacet + facet normal -0.994839 -0.100717 0.012347 + outer loop + vertex -682.117 203.119 160.408 + vertex -682.145 202.923 156.555 + vertex -681.131 193.284 159.618 + endloop + endfacet + facet normal -0.994868 -0.100224 0.0139051 + outer loop + vertex -681.131 193.284 159.618 + vertex -682.145 202.923 156.555 + vertex -681.164 193.076 155.771 + endloop + endfacet + facet normal -0.994837 -0.100331 0.0152825 + outer loop + vertex -682.145 202.923 156.555 + vertex -682.178 202.667 152.717 + vertex -681.164 193.076 155.771 + endloop + endfacet + facet normal -0.994847 -0.100131 0.015913 + outer loop + vertex -681.164 193.076 155.771 + vertex -682.178 202.667 152.717 + vertex -681.199 192.808 151.925 + endloop + endfacet + facet normal -0.994707 -0.100541 0.0211799 + outer loop + vertex -682.178 202.667 152.717 + vertex -682.229 202.362 148.88 + vertex -681.199 192.808 151.925 + endloop + endfacet + facet normal -0.994714 -0.10035 0.0217809 + outer loop + vertex -681.199 192.808 151.925 + vertex -682.229 202.362 148.88 + vertex -681.251 192.488 148.081 + endloop + endfacet + facet normal -0.994663 -0.100479 0.023437 + outer loop + vertex -682.229 202.362 148.88 + vertex -682.283 201.999 145.036 + vertex -681.251 192.488 148.081 + endloop + endfacet + facet normal -0.994653 -0.100822 0.0223609 + outer loop + vertex -681.251 192.488 148.081 + vertex -682.283 201.999 145.036 + vertex -681.299 192.117 144.259 + endloop + endfacet + facet normal -0.994459 -0.101265 0.0282381 + outer loop + vertex -682.283 201.999 145.036 + vertex -682.349 201.572 141.182 + vertex -681.299 192.117 144.259 + endloop + endfacet + facet normal -0.994434 -0.102465 0.0245427 + outer loop + vertex -681.299 192.117 144.259 + vertex -682.349 201.572 141.182 + vertex -681.346 191.655 140.422 + endloop + endfacet + facet normal -0.994315 -0.10272 0.0280333 + outer loop + vertex -682.349 201.572 141.182 + vertex -682.407 201.065 137.287 + vertex -681.346 191.655 140.422 + endloop + endfacet + facet normal -0.994326 -0.102034 0.0300962 + outer loop + vertex -681.346 191.655 140.422 + vertex -682.407 201.065 137.287 + vertex -681.41 191.123 136.503 + endloop + endfacet + facet normal -0.99421 -0.102254 0.0330255 + outer loop + vertex -682.407 201.065 137.287 + vertex -682.479 200.495 133.345 + vertex -681.41 191.123 136.503 + endloop + endfacet + facet normal -0.994208 -0.101097 0.036457 + outer loop + vertex -681.41 191.123 136.503 + vertex -682.479 200.495 133.345 + vertex -681.501 190.579 132.516 + endloop + endfacet + facet normal -0.994046 -0.101373 0.0399414 + outer loop + vertex -682.479 200.495 133.345 + vertex -682.576 199.887 129.397 + vertex -681.501 190.579 132.516 + endloop + endfacet + facet normal -0.994011 -0.0999354 0.0442172 + outer loop + vertex -681.501 190.579 132.516 + vertex -682.576 199.887 129.397 + vertex -681.621 190.017 128.549 + endloop + endfacet + facet normal -0.99403 -0.0999063 0.0438572 + outer loop + vertex -682.576 199.887 129.397 + vertex -682.68 199.221 125.501 + vertex -681.621 190.017 128.549 + endloop + endfacet + facet normal -0.994 -0.0990812 0.0463386 + outer loop + vertex -681.621 190.017 128.549 + vertex -682.68 199.221 125.501 + vertex -681.737 189.362 124.66 + endloop + endfacet + facet normal -0.994089 -0.098948 0.0446783 + outer loop + vertex -682.68 199.221 125.501 + vertex -682.779 198.483 121.683 + vertex -681.737 189.362 124.66 + endloop + endfacet + facet normal -0.99405 -0.098028 0.047484 + outer loop + vertex -681.737 189.362 124.66 + vertex -682.779 198.483 121.683 + vertex -681.844 188.61 120.864 + endloop + endfacet + facet normal -0.993824 -0.0983333 0.0514207 + outer loop + vertex -682.779 198.483 121.683 + vertex -682.896 197.704 117.927 + vertex -681.844 188.61 120.864 + endloop + endfacet + facet normal -0.993825 -0.0983545 0.0513556 + outer loop + vertex -681.844 188.61 120.864 + vertex -682.896 197.704 117.927 + vertex -681.96 187.825 117.129 + endloop + endfacet + facet normal -0.993348 -0.0989224 0.0589421 + outer loop + vertex -682.896 197.704 117.927 + vertex -683.037 196.896 114.192 + vertex -681.96 187.825 117.129 + endloop + endfacet + facet normal -0.99323 -0.0975883 0.063019 + outer loop + vertex -681.96 187.825 117.129 + vertex -683.037 196.896 114.192 + vertex -682.116 187.002 113.382 + endloop + endfacet + facet normal -0.992806 -0.0980188 0.0687628 + outer loop + vertex -683.037 196.896 114.192 + vertex -683.214 196.067 110.449 + vertex -682.116 187.002 113.382 + endloop + endfacet + facet normal -0.992765 -0.0976622 0.0698498 + outer loop + vertex -682.116 187.002 113.382 + vertex -683.214 196.067 110.449 + vertex -682.297 186.139 109.611 + endloop + endfacet + facet normal -0.992118 -0.0982688 0.0777463 + outer loop + vertex -683.214 196.067 110.449 + vertex -683.425 195.231 106.709 + vertex -682.297 186.139 109.611 + endloop + endfacet + facet normal -0.991969 -0.0972524 0.0808723 + outer loop + vertex -682.297 186.139 109.611 + vertex -683.425 195.231 106.709 + vertex -682.518 185.261 105.847 + endloop + endfacet + facet normal -0.991144 -0.0979387 0.0896801 + outer loop + vertex -683.425 195.231 106.709 + vertex -683.68 194.422 103.004 + vertex -682.518 185.261 105.847 + endloop + endfacet + facet normal -0.990862 -0.0964825 0.0942574 + outer loop + vertex -682.518 185.261 105.847 + vertex -683.68 194.422 103.004 + vertex -682.788 184.393 102.12 + endloop + endfacet + facet normal -0.989847 -0.0972234 0.103689 + outer loop + vertex -683.68 194.422 103.004 + vertex -683.986 193.626 99.3368 + vertex -682.788 184.393 102.12 + endloop + endfacet + facet normal -0.989421 -0.0955087 0.109194 + outer loop + vertex -682.788 184.393 102.12 + vertex -683.986 193.626 99.3368 + vertex -683.111 183.522 98.4288 + endloop + endfacet + facet normal -0.987862 -0.0964994 0.121721 + outer loop + vertex -683.986 193.626 99.3368 + vertex -684.351 192.72 95.66 + vertex -683.111 183.522 98.4288 + endloop + endfacet + facet normal -0.987468 -0.0951967 0.125873 + outer loop + vertex -683.111 183.522 98.4288 + vertex -684.351 192.72 95.66 + vertex -683.49 182.525 94.7022 + endloop + endfacet + facet normal -0.984431 -0.0968927 0.146655 + outer loop + vertex -684.351 192.72 95.66 + vertex -684.789 191.496 91.9078 + vertex -683.49 182.525 94.7022 + endloop + endfacet + facet normal -0.98351 -0.0943871 0.15427 + outer loop + vertex -683.49 182.525 94.7022 + vertex -684.789 191.496 91.9078 + vertex -683.977 181.229 90.8002 + endloop + endfacet + facet normal -0.977705 -0.0973567 0.186048 + outer loop + vertex -684.789 191.496 91.9078 + vertex -685.322 189.567 88.0997 + vertex -683.977 181.229 90.8002 + endloop + endfacet + facet normal -0.964774 -0.0737379 0.252535 + outer loop + vertex -683.977 181.229 90.8002 + vertex -685.322 189.567 88.0997 + vertex -684.728 183.003 88.4491 + endloop + endfacet + facet normal -0.980443 -0.0790021 0.180252 + outer loop + vertex -684.728 183.003 88.4491 + vertex -685.322 189.567 88.0997 + vertex -685.047 182.949 86.6921 + endloop + endfacet + facet normal -0.977102 -0.0822613 0.196227 + outer loop + vertex -685.322 189.567 88.0997 + vertex -685.989 188.491 84.3272 + vertex -685.047 182.949 86.6921 + endloop + endfacet + facet normal -0.980167 -0.0915075 0.175781 + outer loop + vertex -685.214 181.268 84.8885 + vertex -685.047 182.949 86.6921 + vertex -685.989 188.491 84.3272 + endloop + endfacet + facet normal -0.974423 -0.088499 0.206563 + outer loop + vertex -685.214 181.268 84.8885 + vertex -685.989 188.491 84.3272 + vertex -685.645 181.572 82.9854 + endloop + endfacet + facet normal -0.969004 -0.0925882 0.229039 + outer loop + vertex -685.989 188.491 84.3272 + vertex -686.735 187.337 80.7046 + vertex -685.645 181.572 82.9854 + endloop + endfacet + facet normal -0.970447 -0.0958615 0.221456 + outer loop + vertex -685.902 180.175 81.2521 + vertex -685.645 181.572 82.9854 + vertex -686.735 187.337 80.7046 + endloop + endfacet + facet normal -0.961302 -0.0918727 0.259727 + outer loop + vertex -685.902 180.175 81.2521 + vertex -686.735 187.337 80.7046 + vertex -686.446 180.63 79.3993 + endloop + endfacet + facet normal -0.958307 -0.0937301 0.269932 + outer loop + vertex -686.735 187.337 80.7046 + vertex -687.663 186.444 77.0972 + vertex -686.446 180.63 79.3993 + endloop + endfacet + facet normal -0.959795 -0.0965611 0.26357 + outer loop + vertex -686.779 179.297 77.698 + vertex -686.446 180.63 79.3993 + vertex -687.663 186.444 77.0972 + endloop + endfacet + facet normal -0.950654 -0.0926978 0.29608 + outer loop + vertex -686.779 179.297 77.698 + vertex -687.663 186.444 77.0972 + vertex -687.395 179.71 75.85 + endloop + endfacet + facet normal -0.946208 -0.0949704 0.309306 + outer loop + vertex -687.663 186.444 77.0972 + vertex -688.728 185.387 73.5159 + vertex -687.395 179.71 75.85 + endloop + endfacet + facet normal -0.948719 -0.0993428 0.300105 + outer loop + vertex -687.79 178.363 74.1549 + vertex -687.395 179.71 75.85 + vertex -688.728 185.387 73.5159 + endloop + endfacet + facet normal -0.938026 -0.0948936 0.33332 + outer loop + vertex -687.79 178.363 74.1549 + vertex -688.728 185.387 73.5159 + vertex -688.491 178.815 72.3132 + endloop + endfacet + facet normal -0.932208 -0.0974708 0.348552 + outer loop + vertex -688.728 185.387 73.5159 + vertex -689.934 184.529 70.0518 + vertex -688.491 178.815 72.3132 + endloop + endfacet + facet normal -0.933853 -0.0999192 0.343416 + outer loop + vertex -688.974 177.535 70.6266 + vertex -688.491 178.815 72.3132 + vertex -689.934 184.529 70.0518 + endloop + endfacet + facet normal -0.920422 -0.0951376 0.379173 + outer loop + vertex -688.974 177.535 70.6266 + vertex -689.934 184.529 70.0518 + vertex -689.762 178.053 68.8432 + endloop + endfacet + facet normal -0.912463 -0.0982872 0.397179 + outer loop + vertex -689.934 184.529 70.0518 + vertex -691.296 183.891 66.764 + vertex -689.762 178.053 68.8432 + endloop + endfacet + facet normal -0.914913 -0.101219 0.390755 + outer loop + vertex -690.315 176.831 67.2329 + vertex -689.762 178.053 68.8432 + vertex -691.296 183.891 66.764 + endloop + endfacet + facet normal -0.896686 -0.0959357 0.432147 + outer loop + vertex -690.315 176.831 67.2329 + vertex -691.296 183.891 66.764 + vertex -691.165 177.416 65.5986 + endloop + endfacet + facet normal -0.884928 -0.099795 0.454909 + outer loop + vertex -691.296 183.891 66.764 + vertex -692.819 183.37 63.6868 + vertex -691.165 177.416 65.5986 + endloop + endfacet + facet normal -0.887417 -0.102227 0.449489 + outer loop + vertex -691.773 176.237 64.129 + vertex -691.165 177.416 65.5986 + vertex -692.819 183.37 63.6868 + endloop + endfacet + facet normal -0.86475 -0.096213 0.4929 + outer loop + vertex -691.773 176.237 64.129 + vertex -692.819 183.37 63.6868 + vertex -692.708 176.877 62.6142 + endloop + endfacet + facet normal -0.849482 -0.100104 0.518034 + outer loop + vertex -692.819 183.37 63.6868 + vertex -694.549 182.915 60.7613 + vertex -692.708 176.877 62.6142 + endloop + endfacet + facet normal -0.853439 -0.103528 0.510808 + outer loop + vertex -693.407 175.726 61.2136 + vertex -692.708 176.877 62.6142 + vertex -694.549 182.915 60.7613 + endloop + endfacet + facet normal -0.826213 -0.0964174 0.555046 + outer loop + vertex -693.407 175.726 61.2136 + vertex -694.549 182.915 60.7613 + vertex -694.489 176.392 59.7184 + endloop + endfacet + facet normal -0.810134 -0.0998855 0.577672 + outer loop + vertex -694.549 182.915 60.7613 + vertex -696.498 182.597 57.9743 + vertex -694.489 176.392 59.7184 + endloop + endfacet + facet normal -0.814715 -0.103363 0.570574 + outer loop + vertex -695.321 175.269 58.3268 + vertex -694.489 176.392 59.7184 + vertex -696.498 182.597 57.9743 + endloop + endfacet + facet normal -0.779012 -0.0952664 0.619729 + outer loop + vertex -695.321 175.269 58.3268 + vertex -696.498 182.597 57.9743 + vertex -696.54 176.081 56.9193 + endloop + endfacet + facet normal -0.767092 -0.0976645 0.634059 + outer loop + vertex -696.498 182.597 57.9743 + vertex -698.531 182.701 55.5298 + vertex -696.54 176.081 56.9193 + endloop + endfacet + facet normal -0.862347 -0.0939831 -0.497519 + outer loop + vertex -694.039 183.085 282.457 + vertex -692.327 183.782 279.358 + vertex -693.034 176.829 281.897 + endloop + endfacet + facet normal -0.849348 -0.0898724 -0.520127 + outer loop + vertex -693.911 175.61 283.54 + vertex -694.039 183.085 282.457 + vertex -693.034 176.829 281.897 + endloop + endfacet + facet normal -0.816982 -0.0963372 -0.568559 + outer loop + vertex -693.911 175.61 283.54 + vertex -694.912 176.339 284.854 + vertex -694.039 183.085 282.457 + endloop + endfacet + facet normal -0.819642 -0.0947252 -0.564991 + outer loop + vertex -695.975 182.58 285.35 + vertex -694.039 183.085 282.457 + vertex -694.912 176.339 284.854 + endloop + endfacet + facet normal -0.825447 -0.0544568 -0.561846 + outer loop + vertex -695.975 182.58 285.35 + vertex -694.729 192.712 282.538 + vertex -694.039 183.085 282.457 + endloop + endfacet + facet normal -0.822622 -0.0559108 -0.565833 + outer loop + vertex -696.658 192.256 285.387 + vertex -694.729 192.712 282.538 + vertex -695.975 182.58 285.35 + endloop + endfacet + facet normal -0.825938 -0.0253554 -0.563191 + outer loop + vertex -696.658 192.256 285.387 + vertex -695.04 201.843 282.583 + vertex -694.729 192.712 282.538 + endloop + endfacet + facet normal -0.825193 -0.0257945 -0.564262 + outer loop + vertex -696.964 201.782 285.399 + vertex -695.04 201.843 282.583 + vertex -696.658 192.256 285.387 + endloop + endfacet + facet normal -0.825681 -0.00417895 -0.564122 + outer loop + vertex -696.964 201.782 285.399 + vertex -695.064 210.655 282.552 + vertex -695.04 201.843 282.583 + endloop + endfacet + facet normal -0.827938 -0.00263413 -0.560814 + outer loop + vertex -696.939 210.911 285.32 + vertex -695.064 210.655 282.552 + vertex -696.964 201.782 285.399 + endloop + endfacet + facet normal -0.827559 0.00591898 -0.561348 + outer loop + vertex -696.939 210.911 285.32 + vertex -694.96 219.344 282.49 + vertex -695.064 210.655 282.552 + endloop + endfacet + facet normal -0.829554 0.00738403 -0.558377 + outer loop + vertex -696.836 219.676 285.282 + vertex -694.96 219.344 282.49 + vertex -696.939 210.911 285.32 + endloop + endfacet + facet normal -0.829564 0.00721822 -0.558365 + outer loop + vertex -696.836 219.676 285.282 + vertex -694.869 228.008 282.467 + vertex -694.96 219.344 282.49 + endloop + endfacet + facet normal -0.83249 0.00939706 -0.55396 + outer loop + vertex -696.742 228.424 285.29 + vertex -694.869 228.008 282.467 + vertex -696.836 219.676 285.282 + endloop + endfacet + facet normal -0.832969 0.00284174 -0.553312 + outer loop + vertex -696.742 228.424 285.29 + vertex -694.833 236.686 282.458 + vertex -694.869 228.008 282.467 + endloop + endfacet + facet normal -0.836959 0.00584706 -0.547234 + outer loop + vertex -696.692 237.194 285.307 + vertex -694.833 236.686 282.458 + vertex -696.742 228.424 285.29 + endloop + endfacet + facet normal -0.837595 -0.00178672 -0.546289 + outer loop + vertex -696.692 237.194 285.307 + vertex -694.841 245.38 282.441 + vertex -694.833 236.686 282.458 + endloop + endfacet + facet normal -0.841934 0.00154397 -0.539578 + outer loop + vertex -696.702 245.914 285.346 + vertex -694.841 245.38 282.441 + vertex -696.692 237.194 285.307 + endloop + endfacet + facet normal -0.84254 -0.00586627 -0.538602 + outer loop + vertex -696.702 245.914 285.346 + vertex -694.904 254.124 282.444 + vertex -694.841 245.38 282.441 + endloop + endfacet + facet normal -0.847593 -0.00194554 -0.530643 + outer loop + vertex -696.752 254.67 285.395 + vertex -694.904 254.124 282.444 + vertex -696.702 245.914 285.346 + endloop + endfacet + facet normal -0.848166 -0.00924232 -0.52965 + outer loop + vertex -696.752 254.67 285.395 + vertex -695.023 262.923 282.481 + vertex -694.904 254.124 282.444 + endloop + endfacet + facet normal -0.852378 -0.00597385 -0.522892 + outer loop + vertex -696.837 263.5 285.432 + vertex -695.023 262.923 282.481 + vertex -696.752 254.67 285.395 + endloop + endfacet + facet normal -0.852768 -0.0108588 -0.522178 + outer loop + vertex -696.837 263.5 285.432 + vertex -695.174 271.71 282.546 + vertex -695.023 262.923 282.481 + endloop + endfacet + facet normal -0.856127 -0.00825356 -0.5167 + outer loop + vertex -696.941 272.335 285.464 + vertex -695.174 271.71 282.546 + vertex -696.837 263.5 285.432 + endloop + endfacet + facet normal -0.856662 -0.0145634 -0.515673 + outer loop + vertex -696.941 272.335 285.464 + vertex -695.339 280.452 282.572 + vertex -695.174 271.71 282.546 + endloop + endfacet + facet normal -0.860906 -0.01122 -0.508641 + outer loop + vertex -697.054 281.162 285.461 + vertex -695.339 280.452 282.572 + vertex -696.941 272.335 285.464 + endloop + endfacet + facet normal -0.861397 -0.0163607 -0.507669 + outer loop + vertex -697.054 281.162 285.461 + vertex -695.491 289.207 282.548 + vertex -695.339 280.452 282.572 + endloop + endfacet + facet normal -0.864846 -0.0135848 -0.501853 + outer loop + vertex -697.167 290.056 285.413 + vertex -695.491 289.207 282.548 + vertex -697.054 281.162 285.461 + endloop + endfacet + facet normal -0.865542 -0.0196997 -0.500449 + outer loop + vertex -697.167 290.056 285.413 + vertex -695.672 298.117 282.511 + vertex -695.491 289.207 282.548 + endloop + endfacet + facet normal -0.871357 -0.0150105 -0.490421 + outer loop + vertex -697.31 298.883 285.398 + vertex -695.672 298.117 282.511 + vertex -697.167 290.056 285.413 + endloop + endfacet + facet normal -0.871716 -0.0186625 -0.489656 + outer loop + vertex -697.31 298.883 285.398 + vertex -695.963 306.736 282.7 + vertex -695.672 298.117 282.511 + endloop + endfacet + facet normal -0.875918 -0.0153857 -0.482215 + outer loop + vertex -697.495 307.236 285.468 + vertex -695.963 306.736 282.7 + vertex -697.31 298.883 285.398 + endloop + endfacet + facet normal -0.876022 -0.0170678 -0.481969 + outer loop + vertex -697.495 307.236 285.468 + vertex -696.385 313.361 283.233 + vertex -695.963 306.736 282.7 + endloop + endfacet + facet normal -0.87438 -0.0184318 -0.484891 + outer loop + vertex -697.622 315.34 285.388 + vertex -696.385 313.361 283.233 + vertex -697.495 307.236 285.468 + endloop + endfacet + facet normal -0.880894 -0.0366559 -0.471893 + outer loop + vertex -697.622 315.34 285.388 + vertex -696.238 321.689 282.311 + vertex -696.385 313.361 283.233 + endloop + endfacet + facet normal -0.896633 -0.0189138 -0.442371 + outer loop + vertex -697.733 323.505 285.263 + vertex -696.238 321.689 282.311 + vertex -697.622 315.34 285.388 + endloop + endfacet + facet normal -0.898347 -0.0266533 -0.438477 + outer loop + vertex -697.733 323.505 285.263 + vertex -696.516 329.611 282.399 + vertex -696.238 321.689 282.311 + endloop + endfacet + facet normal -0.903737 -0.0204768 -0.427598 + outer loop + vertex -697.895 332.151 285.193 + vertex -696.516 329.611 282.399 + vertex -697.733 323.505 285.263 + endloop + endfacet + facet normal -0.908824 -0.0364562 -0.415584 + outer loop + vertex -697.895 332.151 285.193 + vertex -696.475 339.838 281.413 + vertex -696.516 329.611 282.399 + endloop + endfacet + facet normal -0.918072 -0.0249353 -0.395628 + outer loop + vertex -698.191 342.323 285.239 + vertex -696.475 339.838 281.413 + vertex -697.895 332.151 285.193 + endloop + endfacet + facet normal -0.920414 -0.0363726 -0.38925 + outer loop + vertex -698.191 342.323 285.239 + vertex -697.003 353.59 281.376 + vertex -696.475 339.838 281.413 + endloop + endfacet + facet normal -0.924162 -0.0330016 -0.380573 + outer loop + vertex -698.814 354.054 285.734 + vertex -697.003 353.59 281.376 + vertex -698.191 342.323 285.239 + endloop + endfacet + facet normal -0.924172 -0.046151 -0.379177 + outer loop + vertex -697.003 353.59 281.376 + vertex -698.814 354.054 285.734 + vertex -698.002 368.869 281.952 + endloop + endfacet + facet normal -0.924274 -0.0460842 -0.378937 + outer loop + vertex -700.023 366.697 287.145 + vertex -698.002 368.869 281.952 + vertex -698.814 354.054 285.734 + endloop + endfacet + facet normal -0.923206 -0.051594 -0.380826 + outer loop + vertex -700.023 366.697 287.145 + vertex -699.392 386.649 282.913 + vertex -698.002 368.869 281.952 + endloop + endfacet + facet normal -0.928751 -0.0485933 -0.367505 + outer loop + vertex -701.505 386.658 288.252 + vertex -699.392 386.649 282.913 + vertex -700.023 366.697 287.145 + endloop + endfacet + facet normal -0.801115 -0.0894375 -0.59179 + outer loop + vertex -695.931 175.327 286.386 + vertex -695.975 182.58 285.35 + vertex -694.912 176.339 284.854 + endloop + endfacet + facet normal -0.766722 -0.0953751 -0.634856 + outer loop + vertex -695.931 175.327 286.386 + vertex -697.026 176.293 287.563 + vertex -695.975 182.58 285.35 + endloop + endfacet + facet normal -0.784264 -0.0852931 -0.614537 + outer loop + vertex -697.991 182.226 287.972 + vertex -695.975 182.58 285.35 + vertex -697.026 176.293 287.563 + endloop + endfacet + facet normal -0.763558 -0.0801173 -0.64075 + outer loop + vertex -697.955 175.691 288.746 + vertex -697.991 182.226 287.972 + vertex -697.026 176.293 287.563 + endloop + endfacet + facet normal -0.788137 -0.0532969 -0.613188 + outer loop + vertex -697.991 182.226 287.972 + vertex -696.658 192.256 285.387 + vertex -695.975 182.58 285.35 + endloop + endfacet + facet normal -0.789069 -0.0528731 -0.612025 + outer loop + vertex -698.657 192.75 287.921 + vertex -696.658 192.256 285.387 + vertex -697.991 182.226 287.972 + endloop + endfacet + facet normal -0.787266 -0.0245123 -0.616126 + outer loop + vertex -698.657 192.75 287.921 + vertex -696.964 201.782 285.399 + vertex -696.658 192.256 285.387 + endloop + endfacet + facet normal -0.791925 -0.0219904 -0.610222 + outer loop + vertex -698.933 203.228 287.902 + vertex -696.964 201.782 285.399 + vertex -698.657 192.75 287.921 + endloop + endfacet + facet normal -0.78688 -0.00323299 -0.617097 + outer loop + vertex -698.933 203.228 287.902 + vertex -696.939 210.911 285.32 + vertex -696.964 201.782 285.399 + endloop + endfacet + facet normal -0.793588 0.00141195 -0.608454 + outer loop + vertex -698.61 212.331 287.502 + vertex -696.939 210.911 285.32 + vertex -698.933 203.228 287.902 + endloop + endfacet + facet normal -0.7919 0.0067161 -0.610614 + outer loop + vertex -698.61 212.331 287.502 + vertex -696.836 219.676 285.282 + vertex -696.939 210.911 285.32 + endloop + endfacet + facet normal -0.793225 0.00755939 -0.608882 + outer loop + vertex -698.774 220.786 287.82 + vertex -696.836 219.676 285.282 + vertex -698.61 212.331 287.502 + endloop + endfacet + facet normal -0.792906 0.00902117 -0.609278 + outer loop + vertex -698.774 220.786 287.82 + vertex -696.742 228.424 285.29 + vertex -696.836 219.676 285.282 + endloop + endfacet + facet normal -0.799231 0.0134876 -0.600873 + outer loop + vertex -698.35 230.147 287.467 + vertex -696.742 228.424 285.29 + vertex -698.774 220.786 287.82 + endloop + endfacet + facet normal -0.802243 0.00574544 -0.596971 + outer loop + vertex -698.35 230.147 287.467 + vertex -696.692 237.194 285.307 + vertex -696.742 228.424 285.29 + endloop + endfacet + facet normal -0.801408 0.00520407 -0.598096 + outer loop + vertex -698.58 238.68 287.849 + vertex -696.692 237.194 285.307 + vertex -698.35 230.147 287.467 + endloop + endfacet + facet normal -0.802359 0.00184497 -0.596839 + outer loop + vertex -698.58 238.68 287.849 + vertex -696.702 245.914 285.346 + vertex -696.692 237.194 285.307 + endloop + endfacet + facet normal -0.809641 0.0071811 -0.586882 + outer loop + vertex -698.296 247.828 287.568 + vertex -696.702 245.914 285.346 + vertex -698.58 238.68 287.849 + endloop + endfacet + facet normal -0.813196 -0.0014627 -0.581988 + outer loop + vertex -698.296 247.828 287.568 + vertex -696.752 254.67 285.395 + vertex -696.702 245.914 285.346 + endloop + endfacet + facet normal -0.812052 -0.00222671 -0.58358 + outer loop + vertex -698.566 256.567 287.912 + vertex -696.752 254.67 285.395 + vertex -698.296 247.828 287.568 + endloop + endfacet + facet normal -0.813155 -0.0053473 -0.582023 + outer loop + vertex -698.566 256.567 287.912 + vertex -696.837 263.5 285.432 + vertex -696.752 254.67 285.395 + endloop + endfacet + facet normal -0.819764 -0.000364439 -0.572702 + outer loop + vertex -698.342 265.766 287.585 + vertex -696.837 263.5 285.432 + vertex -698.566 256.567 287.912 + endloop + endfacet + facet normal -0.823338 -0.00768096 -0.567499 + outer loop + vertex -698.342 265.766 287.585 + vertex -696.941 272.335 285.464 + vertex -696.837 263.5 285.432 + endloop + endfacet + facet normal -0.822228 -0.00843297 -0.569096 + outer loop + vertex -698.656 274.533 287.908 + vertex -696.941 272.335 285.464 + vertex -698.342 265.766 287.585 + endloop + endfacet + facet normal -0.823184 -0.0107596 -0.567673 + outer loop + vertex -698.656 274.533 287.908 + vertex -697.054 281.162 285.461 + vertex -696.941 272.335 285.464 + endloop + endfacet + facet normal -0.828108 -0.00693087 -0.560525 + outer loop + vertex -698.494 283.62 287.557 + vertex -697.054 281.162 285.461 + vertex -698.656 274.533 287.908 + endloop + endfacet + facet normal -0.831569 -0.0134498 -0.555258 + outer loop + vertex -698.494 283.62 287.557 + vertex -697.167 290.056 285.413 + vertex -697.054 281.162 285.461 + endloop + endfacet + facet normal -0.832755 -0.012619 -0.553498 + outer loop + vertex -698.841 292.345 287.88 + vertex -697.167 290.056 285.413 + vertex -698.494 283.62 287.557 + endloop + endfacet + facet normal -0.833535 -0.0145064 -0.552276 + outer loop + vertex -698.841 292.345 287.88 + vertex -697.31 298.883 285.398 + vertex -697.167 290.056 285.413 + endloop + endfacet + facet normal -0.839495 -0.00969548 -0.543281 + outer loop + vertex -698.718 301.291 287.531 + vertex -697.31 298.883 285.398 + vertex -698.841 292.345 287.88 + endloop + endfacet + facet normal -0.841719 -0.0141404 -0.539731 + outer loop + vertex -698.718 301.291 287.531 + vertex -697.495 307.236 285.468 + vertex -697.31 298.883 285.398 + endloop + endfacet + facet normal -0.842288 -0.0137187 -0.538853 + outer loop + vertex -699.065 309.544 287.863 + vertex -697.495 307.236 285.468 + vertex -698.718 301.291 287.531 + endloop + endfacet + facet normal -0.844279 -0.0184618 -0.535586 + outer loop + vertex -699.065 309.544 287.863 + vertex -697.622 315.34 285.388 + vertex -697.495 307.236 285.468 + endloop + endfacet + facet normal -0.853666 -0.00978233 -0.52073 + outer loop + vertex -698.937 317.962 287.495 + vertex -697.622 315.34 285.388 + vertex -699.065 309.544 287.863 + endloop + endfacet + facet normal -0.858823 -0.0194641 -0.511902 + outer loop + vertex -698.937 317.962 287.495 + vertex -697.733 323.505 285.263 + vertex -697.622 315.34 285.388 + endloop + endfacet + facet normal -0.864376 -0.0145275 -0.502637 + outer loop + vertex -699.297 325.988 287.882 + vertex -697.733 323.505 285.263 + vertex -698.937 317.962 287.495 + endloop + endfacet + facet normal -0.866665 -0.0203578 -0.498475 + outer loop + vertex -699.297 325.988 287.882 + vertex -697.895 332.151 285.193 + vertex -697.733 323.505 285.263 + endloop + endfacet + facet normal -0.876181 -0.0109418 -0.481859 + outer loop + vertex -699.27 334.929 287.629 + vertex -697.895 332.151 285.193 + vertex -699.297 325.988 287.882 + endloop + endfacet + facet normal -0.881956 -0.0235436 -0.470743 + outer loop + vertex -699.27 334.929 287.629 + vertex -698.191 342.323 285.239 + vertex -697.895 332.151 285.193 + endloop + endfacet + facet normal -0.886037 -0.0204976 -0.463161 + outer loop + vertex -699.808 344.158 288.251 + vertex -698.191 342.323 285.239 + vertex -699.27 334.929 287.629 + endloop + endfacet + facet normal -0.887675 -0.0277264 -0.459635 + outer loop + vertex -699.808 344.158 288.251 + vertex -698.814 354.054 285.734 + vertex -698.191 342.323 285.239 + endloop + endfacet + facet normal -0.899918 -0.0203803 -0.435582 + outer loop + vertex -700.024 353.38 288.266 + vertex -698.814 354.054 285.734 + vertex -699.808 344.158 288.251 + endloop + endfacet + facet normal -0.897762 -0.0368533 -0.438936 + outer loop + vertex -700.024 353.38 288.266 + vertex -700.023 366.697 287.145 + vertex -698.814 354.054 285.734 + endloop + endfacet + facet normal -0.750054 -0.119967 -0.650406 + outer loop + vertex -697.955 175.691 288.746 + vertex -697.026 176.293 287.563 + vertex -697.502 171.419 289.012 + endloop + endfacet + facet normal -0.761873 -0.142573 -0.63184 + outer loop + vertex -697.502 171.419 289.012 + vertex -697.779 166.716 290.407 + vertex -698.855 173.169 290.248 + endloop + endfacet + facet normal -0.738499 -0.163944 -0.65402 + outer loop + vertex -696.607 166.39 289.222 + vertex -696.319 170.958 287.751 + vertex -695.447 166.215 287.955 + endloop + endfacet + facet normal -0.767719 -0.165861 -0.618949 + outer loop + vertex -695.447 166.215 287.955 + vertex -695.206 170.877 286.407 + vertex -694.367 166.23 286.612 + endloop + endfacet + facet normal -0.793675 -0.16703 -0.584963 + outer loop + vertex -694.367 166.23 286.612 + vertex -694.179 170.979 285.001 + vertex -693.359 166.396 285.197 + endloop + endfacet + facet normal -0.815166 -0.16868 -0.554122 + outer loop + vertex -693.359 166.396 285.197 + vertex -693.223 171.187 283.538 + vertex -692.399 166.626 283.715 + endloop + endfacet + facet normal -0.833882 -0.170662 -0.524896 + outer loop + vertex -692.399 166.626 283.715 + vertex -692.317 171.436 282.021 + vertex -691.48 166.879 282.173 + endloop + endfacet + facet normal -0.834897 -0.227249 -0.501303 + outer loop + vertex -690.506 162.723 282.424 + vertex -690.605 167.16 280.578 + vertex -689.618 163.033 280.805 + endloop + endfacet + facet normal -0.85088 -0.229495 -0.472583 + outer loop + vertex -690.605 167.16 280.578 + vertex -689.779 167.482 278.932 + vertex -689.618 163.033 280.805 + endloop + endfacet + facet normal -0.850757 -0.229569 -0.47277 + outer loop + vertex -689.618 163.033 280.805 + vertex -689.779 167.482 278.932 + vertex -688.784 163.373 279.139 + endloop + endfacet + facet normal -0.862949 -0.231334 -0.449226 + outer loop + vertex -689.779 167.482 278.932 + vertex -688.999 167.856 277.242 + vertex -688.784 163.373 279.139 + endloop + endfacet + facet normal -0.863256 -0.231141 -0.448735 + outer loop + vertex -688.784 163.373 279.139 + vertex -688.999 167.856 277.242 + vertex -688 163.757 277.433 + endloop + endfacet + facet normal -0.876035 -0.233022 -0.422212 + outer loop + vertex -688.999 167.856 277.242 + vertex -688.271 168.255 275.512 + vertex -688 163.757 277.433 + endloop + endfacet + facet normal -0.875736 -0.233222 -0.422722 + outer loop + vertex -688 163.757 277.433 + vertex -688.271 168.255 275.512 + vertex -687.268 164.167 275.69 + endloop + endfacet + facet normal -0.886747 -0.23485 -0.398151 + outer loop + vertex -688.271 168.255 275.512 + vertex -687.593 168.677 273.752 + vertex -687.268 164.167 275.69 + endloop + endfacet + facet normal -0.887409 -0.234382 -0.396951 + outer loop + vertex -687.268 164.167 275.69 + vertex -687.593 168.677 273.752 + vertex -686.591 164.598 273.921 + endloop + endfacet + facet normal -0.897842 -0.2359 -0.371794 + outer loop + vertex -687.593 168.677 273.752 + vertex -686.969 169.101 271.976 + vertex -686.591 164.598 273.921 + endloop + endfacet + facet normal -0.8959 -0.237353 -0.375536 + outer loop + vertex -686.591 164.598 273.921 + vertex -686.969 169.101 271.976 + vertex -685.965 165.053 272.141 + endloop + endfacet + facet normal -0.904829 -0.238637 -0.352614 + outer loop + vertex -686.969 169.101 271.976 + vertex -686.395 169.546 270.202 + vertex -685.965 165.053 272.141 + endloop + endfacet + facet normal -0.904496 -0.238897 -0.353292 + outer loop + vertex -685.965 165.053 272.141 + vertex -686.395 169.546 270.202 + vertex -685.394 165.524 270.359 + endloop + endfacet + facet normal -0.912518 -0.240034 -0.331203 + outer loop + vertex -686.395 169.546 270.202 + vertex -685.871 169.991 268.437 + vertex -685.394 165.524 270.359 + endloop + endfacet + facet normal -0.910406 -0.241756 -0.335731 + outer loop + vertex -685.394 165.524 270.359 + vertex -685.871 169.991 268.437 + vertex -684.868 166.008 268.586 + endloop + endfacet + facet normal -0.918788 -0.242952 -0.311131 + outer loop + vertex -685.871 169.991 268.437 + vertex -685.392 170.423 266.685 + vertex -684.868 166.008 268.586 + endloop + endfacet + facet normal -0.917298 -0.244229 -0.314509 + outer loop + vertex -684.868 166.008 268.586 + vertex -685.392 170.423 266.685 + vertex -684.388 166.479 266.821 + endloop + endfacet + facet normal -0.923509 -0.245137 -0.295024 + outer loop + vertex -685.392 170.423 266.685 + vertex -684.949 170.843 264.95 + vertex -684.388 166.479 266.821 + endloop + endfacet + facet normal -0.921809 -0.246646 -0.299056 + outer loop + vertex -684.388 166.479 266.821 + vertex -684.949 170.843 264.95 + vertex -683.943 166.94 265.069 + endloop + endfacet + facet normal -0.927444 -0.247528 -0.280317 + outer loop + vertex -684.949 170.843 264.95 + vertex -684.543 171.272 263.227 + vertex -683.943 166.94 265.069 + endloop + endfacet + facet normal -0.926313 -0.248566 -0.283125 + outer loop + vertex -683.943 166.94 265.069 + vertex -684.543 171.272 263.227 + vertex -683.537 167.417 263.32 + endloop + endfacet + facet normal -0.930815 -0.249358 -0.267215 + outer loop + vertex -684.543 171.272 263.227 + vertex -684.173 171.76 261.482 + vertex -683.537 167.417 263.32 + endloop + endfacet + facet normal -0.930587 -0.249574 -0.267805 + outer loop + vertex -683.537 167.417 263.32 + vertex -684.173 171.76 261.482 + vertex -683.167 167.938 261.55 + endloop + endfacet + facet normal -0.935354 -0.250508 -0.249715 + outer loop + vertex -684.173 171.76 261.482 + vertex -683.827 172.278 259.667 + vertex -683.167 167.938 261.55 + endloop + endfacet + facet normal -0.936201 -0.249636 -0.247407 + outer loop + vertex -683.167 167.938 261.55 + vertex -683.827 172.278 259.667 + vertex -682.828 168.452 259.748 + endloop + endfacet + facet normal -0.941407 -0.250534 -0.225799 + outer loop + vertex -683.827 172.278 259.667 + vertex -683.466 172.567 257.842 + vertex -682.828 168.452 259.748 + endloop + endfacet + facet normal -0.940636 -0.251435 -0.228001 + outer loop + vertex -682.828 168.452 259.748 + vertex -683.466 172.567 257.842 + vertex -682.51 168.875 257.968 + endloop + endfacet + facet normal -0.946545 -0.252054 -0.201301 + outer loop + vertex -683.466 172.567 257.842 + vertex -683.094 172.328 256.391 + vertex -682.51 168.875 257.968 + endloop + endfacet + facet normal -0.938492 -0.26166 -0.225316 + outer loop + vertex -682.51 168.875 257.968 + vertex -683.094 172.328 256.391 + vertex -682.236 169.463 256.146 + endloop + endfacet + facet normal -0.929932 -0.255779 -0.264202 + outer loop + vertex -683.094 172.328 256.391 + vertex -683.026 174.049 254.486 + vertex -682.236 169.463 256.146 + endloop + endfacet + facet normal -0.943355 -0.243881 -0.224954 + outer loop + vertex -682.236 169.463 256.146 + vertex -683.026 174.049 254.486 + vertex -681.933 170.03 254.261 + endloop + endfacet + facet normal -0.946901 -0.245836 -0.207227 + outer loop + vertex -683.026 174.049 254.486 + vertex -682.717 174.378 252.682 + vertex -681.933 170.03 254.261 + endloop + endfacet + facet normal -0.943004 -0.249747 -0.21993 + outer loop + vertex -681.933 170.03 254.261 + vertex -682.717 174.378 252.682 + vertex -681.605 170.481 252.342 + endloop + endfacet + facet normal -0.942819 -0.249611 -0.220878 + outer loop + vertex -682.717 174.378 252.682 + vertex -682.633 175.903 250.601 + vertex -681.605 170.481 252.342 + endloop + endfacet + facet normal -0.95012 -0.242895 -0.195636 + outer loop + vertex -681.605 170.481 252.342 + vertex -682.633 175.903 250.601 + vertex -681.305 170.868 250.401 + endloop + endfacet + facet normal -0.957828 -0.246859 -0.14706 + outer loop + vertex -682.633 175.903 250.601 + vertex -682.259 175.572 248.724 + vertex -681.305 170.868 250.401 + endloop + endfacet + facet normal -0.951225 -0.254995 -0.173634 + outer loop + vertex -681.305 170.868 250.401 + vertex -682.259 175.572 248.724 + vertex -681.073 171.314 248.479 + endloop + endfacet + facet normal -0.947544 -0.252702 -0.195707 + outer loop + vertex -682.259 175.572 248.724 + vertex -682.22 176.99 246.703 + vertex -681.073 171.314 248.479 + endloop + endfacet + facet normal -0.956035 -0.244053 -0.162592 + outer loop + vertex -681.073 171.314 248.479 + vertex -682.22 176.99 246.703 + vertex -680.878 171.8 246.601 + endloop + endfacet + facet normal -0.961838 -0.246412 -0.11895 + outer loop + vertex -682.22 176.99 246.703 + vertex -681.902 176.597 244.944 + vertex -680.878 171.8 246.601 + endloop + endfacet + facet normal -0.95392 -0.257082 -0.15474 + outer loop + vertex -680.878 171.8 246.601 + vertex -681.902 176.597 244.944 + vertex -680.708 172.293 244.735 + endloop + endfacet + facet normal -0.949753 -0.254599 -0.182067 + outer loop + vertex -681.902 176.597 244.944 + vertex -681.897 177.983 242.981 + vertex -680.708 172.293 244.735 + endloop + endfacet + facet normal -0.958299 -0.2454 -0.14643 + outer loop + vertex -680.708 172.293 244.735 + vertex -681.897 177.983 242.981 + vertex -680.547 172.769 242.881 + endloop + endfacet + facet normal -0.962953 -0.247352 -0.107417 + outer loop + vertex -681.897 177.983 242.981 + vertex -681.592 177.537 241.271 + vertex -680.547 172.769 242.881 + endloop + endfacet + facet normal -0.956609 -0.256416 -0.138385 + outer loop + vertex -680.547 172.769 242.881 + vertex -681.592 177.537 241.271 + vertex -680.403 173.222 241.048 + endloop + endfacet + facet normal -0.95257 -0.253768 -0.167962 + outer loop + vertex -681.592 177.537 241.271 + vertex -681.612 178.878 239.357 + vertex -680.403 173.222 241.048 + endloop + endfacet + facet normal -0.960477 -0.244841 -0.132428 + outer loop + vertex -680.403 173.222 241.048 + vertex -681.612 178.878 239.357 + vertex -680.266 173.659 239.248 + endloop + endfacet + facet normal -0.964612 -0.246731 -0.0929956 + outer loop + vertex -681.612 178.878 239.357 + vertex -681.329 178.4 237.694 + vertex -680.266 173.659 239.248 + endloop + endfacet + facet normal -0.958225 -0.256378 -0.126783 + outer loop + vertex -680.266 173.659 239.248 + vertex -681.329 178.4 237.694 + vertex -680.145 174.084 237.473 + endloop + endfacet + facet normal -0.955465 -0.254462 -0.149454 + outer loop + vertex -681.329 178.4 237.694 + vertex -681.385 179.724 235.798 + vertex -680.145 174.084 237.473 + endloop + endfacet + facet normal -0.962683 -0.24549 -0.113915 + outer loop + vertex -680.145 174.084 237.473 + vertex -681.385 179.724 235.798 + vertex -680.042 174.506 235.698 + endloop + endfacet + facet normal -0.965951 -0.247041 -0.0768699 + outer loop + vertex -681.385 179.724 235.798 + vertex -681.128 179.24 234.12 + vertex -680.042 174.506 235.698 + endloop + endfacet + facet normal -0.959438 -0.257886 -0.113904 + outer loop + vertex -680.042 174.506 235.698 + vertex -681.128 179.24 234.12 + vertex -679.942 174.93 233.891 + endloop + endfacet + facet normal -0.956485 -0.255652 -0.140638 + outer loop + vertex -681.128 179.24 234.12 + vertex -681.193 180.567 232.154 + vertex -679.942 174.93 233.891 + endloop + endfacet + facet normal -0.964192 -0.245178 -0.101097 + outer loop + vertex -679.942 174.93 233.891 + vertex -681.193 180.567 232.154 + vertex -679.855 175.356 232.031 + endloop + endfacet + facet normal -0.966693 -0.246584 -0.0685642 + outer loop + vertex -681.193 180.567 232.154 + vertex -680.947 180.09 230.39 + vertex -679.855 175.356 232.031 + endloop + endfacet + facet normal -0.96097 -0.257 -0.102413 + outer loop + vertex -679.855 175.356 232.031 + vertex -680.947 180.09 230.39 + vertex -679.766 175.782 230.128 + endloop + endfacet + facet normal -0.958647 -0.254893 -0.126595 + outer loop + vertex -680.947 180.09 230.39 + vertex -681.029 181.412 228.353 + vertex -679.766 175.782 230.128 + endloop + endfacet + facet normal -0.965583 -0.2445 -0.0887044 + outer loop + vertex -679.766 175.782 230.128 + vertex -681.029 181.412 228.353 + vertex -679.695 176.201 228.199 + endloop + endfacet + facet normal -0.967454 -0.245824 -0.0600282 + outer loop + vertex -681.029 181.412 228.353 + vertex -680.793 180.922 226.552 + vertex -679.695 176.201 228.199 + endloop + endfacet + facet normal -0.962136 -0.256152 -0.0931641 + outer loop + vertex -679.695 176.201 228.199 + vertex -680.793 180.922 226.552 + vertex -679.618 176.609 226.281 + endloop + endfacet + facet normal -0.960357 -0.254353 -0.114099 + outer loop + vertex -680.793 180.922 226.552 + vertex -680.894 182.216 224.523 + vertex -679.618 176.609 226.281 + endloop + endfacet + facet normal -0.966269 -0.244903 -0.0796684 + outer loop + vertex -679.618 176.609 226.281 + vertex -680.894 182.216 224.523 + vertex -679.56 176.998 224.379 + endloop + endfacet + facet normal -0.967887 -0.246099 -0.0512882 + outer loop + vertex -680.894 182.216 224.523 + vertex -680.668 181.697 222.747 + vertex -679.56 176.998 224.379 + endloop + endfacet + facet normal -0.963204 -0.255815 -0.082438 + outer loop + vertex -679.56 176.998 224.379 + vertex -680.668 181.697 222.747 + vertex -679.498 177.374 222.491 + endloop + endfacet + facet normal -0.961449 -0.253984 -0.105399 + outer loop + vertex -680.668 181.697 222.747 + vertex -680.78 182.962 220.717 + vertex -679.498 177.374 222.491 + endloop + endfacet + facet normal -0.966713 -0.245071 -0.0735217 + outer loop + vertex -679.498 177.374 222.491 + vertex -680.78 182.962 220.717 + vertex -679.445 177.735 220.591 + endloop + endfacet + facet normal -0.968393 -0.246324 -0.0392427 + outer loop + vertex -680.78 182.962 220.717 + vertex -680.57 182.422 218.913 + vertex -679.445 177.735 220.591 + endloop + endfacet + facet normal -0.963726 -0.25697 -0.0721052 + outer loop + vertex -679.445 177.735 220.591 + vertex -680.57 182.422 218.913 + vertex -679.395 178.091 218.651 + endloop + endfacet + facet normal -0.961646 -0.254589 -0.102089 + outer loop + vertex -680.57 182.422 218.913 + vertex -680.677 183.669 216.812 + vertex -679.395 178.091 218.651 + endloop + endfacet + facet normal -0.967192 -0.244707 -0.0682504 + outer loop + vertex -679.395 178.091 218.651 + vertex -680.677 183.669 216.812 + vertex -679.343 178.442 216.658 + endloop + endfacet + facet normal -0.968663 -0.246106 -0.0335199 + outer loop + vertex -680.677 183.669 216.812 + vertex -680.471 183.115 214.928 + vertex -679.343 178.442 216.658 + endloop + endfacet + facet normal -0.964227 -0.256863 -0.0654781 + outer loop + vertex -679.343 178.442 216.658 + vertex -680.471 183.115 214.928 + vertex -679.296 178.782 214.627 + endloop + endfacet + facet normal -0.962388 -0.254261 -0.095708 + outer loop + vertex -680.471 183.115 214.928 + vertex -680.581 184.335 212.796 + vertex -679.296 178.782 214.627 + endloop + endfacet + facet normal -0.967756 -0.244247 -0.0615795 + outer loop + vertex -679.296 178.782 214.627 + vertex -680.581 184.335 212.796 + vertex -679.249 179.107 212.596 + endloop + endfacet + facet normal -0.968854 -0.245703 -0.0308483 + outer loop + vertex -680.581 184.335 212.796 + vertex -680.372 183.748 210.924 + vertex -679.249 179.107 212.596 + endloop + endfacet + facet normal -0.965116 -0.255029 -0.0592578 + outer loop + vertex -679.249 179.107 212.596 + vertex -680.372 183.748 210.924 + vertex -679.206 179.408 210.612 + endloop + endfacet + facet normal -0.963667 -0.252668 -0.0866273 + outer loop + vertex -680.372 183.748 210.924 + vertex -680.496 184.919 208.886 + vertex -679.206 179.408 210.612 + endloop + endfacet + facet normal -0.967807 -0.244814 -0.0584463 + outer loop + vertex -679.206 179.408 210.612 + vertex -680.496 184.919 208.886 + vertex -679.16 179.682 208.701 + endloop + endfacet + facet normal -0.968929 -0.246408 -0.0214512 + outer loop + vertex -680.496 184.919 208.886 + vertex -680.296 184.287 207.119 + vertex -679.16 179.682 208.701 + endloop + endfacet + facet normal -0.965319 -0.255904 -0.0516958 + outer loop + vertex -679.16 179.682 208.701 + vertex -680.296 184.287 207.119 + vertex -679.127 179.933 206.842 + endloop + endfacet + facet normal -0.963732 -0.253452 -0.0835654 + outer loop + vertex -680.296 184.287 207.119 + vertex -680.423 185.419 205.148 + vertex -679.127 179.933 206.842 + endloop + endfacet + facet normal -0.968237 -0.244647 -0.0516213 + outer loop + vertex -679.127 179.933 206.842 + vertex -680.423 185.419 205.148 + vertex -679.089 180.169 205.002 + endloop + endfacet + facet normal -0.969143 -0.245795 -0.0186092 + outer loop + vertex -680.423 185.419 205.148 + vertex -680.222 184.76 203.394 + vertex -679.089 180.169 205.002 + endloop + endfacet + facet normal -0.9661 -0.25424 -0.0448642 + outer loop + vertex -679.089 180.169 205.002 + vertex -680.222 184.76 203.394 + vertex -679.062 180.4 203.125 + endloop + endfacet + facet normal -0.964824 -0.252057 -0.0747167 + outer loop + vertex -680.222 184.76 203.394 + vertex -680.356 185.88 201.343 + vertex -679.062 180.4 203.125 + endloop + endfacet + facet normal -0.968844 -0.243475 -0.0453973 + outer loop + vertex -679.062 180.4 203.125 + vertex -680.356 185.88 201.343 + vertex -679.03 180.632 201.2 + endloop + endfacet + facet normal -0.969569 -0.244657 -0.00885205 + outer loop + vertex -680.356 185.88 201.343 + vertex -680.171 185.214 199.506 + vertex -679.03 180.632 201.2 + endloop + endfacet + facet normal -0.965885 -0.255679 -0.0411575 + outer loop + vertex -679.03 180.632 201.2 + vertex -680.171 185.214 199.506 + vertex -679.005 180.85 199.237 + endloop + endfacet + facet normal -0.964892 -0.253778 -0.0676785 + outer loop + vertex -680.171 185.214 199.506 + vertex -680.309 186.302 197.394 + vertex -679.005 180.85 199.237 + endloop + endfacet + facet normal -0.968707 -0.245082 -0.0392583 + outer loop + vertex -679.005 180.85 199.237 + vertex -680.309 186.302 197.394 + vertex -678.97 181.031 197.248 + endloop + endfacet + facet normal -0.969218 -0.246097 -0.00730491 + outer loop + vertex -680.309 186.302 197.394 + vertex -680.11 185.574 195.526 + vertex -678.97 181.031 197.248 + endloop + endfacet + facet normal -0.965629 -0.257047 -0.0385746 + outer loop + vertex -678.97 181.031 197.248 + vertex -680.11 185.574 195.526 + vertex -678.924 181.166 195.216 + endloop + endfacet + facet normal -0.964529 -0.254547 -0.0699186 + outer loop + vertex -680.11 185.574 195.526 + vertex -680.223 186.588 193.392 + vertex -678.924 181.166 195.216 + endloop + endfacet + facet normal -0.969174 -0.24389 -0.0349292 + outer loop + vertex -678.924 181.166 195.216 + vertex -680.223 186.588 193.392 + vertex -678.89 181.328 193.122 + endloop + endfacet + facet normal -0.969347 -0.245694 -0.000622524 + outer loop + vertex -680.223 186.588 193.392 + vertex -680.029 185.825 191.488 + vertex -678.89 181.328 193.122 + endloop + endfacet + facet normal -0.967408 -0.252397 -0.0204156 + outer loop + vertex -678.89 181.328 193.122 + vertex -680.029 185.825 191.488 + vertex -678.918 181.605 191.042 + endloop + endfacet + facet normal -0.96694 -0.248288 -0.0581417 + outer loop + vertex -680.029 185.825 191.488 + vertex -680.158 186.824 189.374 + vertex -678.918 181.605 191.042 + endloop + endfacet + facet normal -0.97024 -0.240221 -0.0304507 + outer loop + vertex -678.918 181.605 191.042 + vertex -680.158 186.824 189.374 + vertex -678.886 181.726 189.05 + endloop + endfacet + facet normal -0.970208 -0.242266 0.00188327 + outer loop + vertex -680.158 186.824 189.374 + vertex -679.958 186.008 187.513 + vertex -678.886 181.726 189.05 + endloop + endfacet + facet normal -0.967047 -0.252849 -0.0297937 + outer loop + vertex -678.886 181.726 189.05 + vertex -679.958 186.008 187.513 + vertex -678.839 181.778 187.099 + endloop + endfacet + facet normal -0.966603 -0.25023 -0.0553431 + outer loop + vertex -679.958 186.008 187.513 + vertex -680.093 186.977 185.489 + vertex -678.839 181.778 187.099 + endloop + endfacet + facet normal -0.969732 -0.242549 -0.0280911 + outer loop + vertex -678.839 181.778 187.099 + vertex -680.093 186.977 185.489 + vertex -678.801 181.848 185.196 + endloop + endfacet + facet normal -0.969465 -0.244858 0.0134884 + outer loop + vertex -680.093 186.977 185.489 + vertex -679.914 186.172 183.711 + vertex -678.801 181.848 185.196 + endloop + endfacet + facet normal -0.966827 -0.254831 -0.0175358 + outer loop + vertex -678.801 181.848 185.196 + vertex -679.914 186.172 183.711 + vertex -678.788 181.925 183.332 + endloop + endfacet + facet normal -0.966661 -0.252616 -0.0418667 + outer loop + vertex -679.914 186.172 183.711 + vertex -680.087 187.159 181.753 + vertex -678.788 181.925 183.332 + endloop + endfacet + facet normal -0.969423 -0.244979 -0.01429 + outer loop + vertex -678.788 181.925 183.332 + vertex -680.087 187.159 181.753 + vertex -678.782 182.009 181.482 + endloop + endfacet + facet normal -0.968911 -0.246629 0.0196224 + outer loop + vertex -680.087 187.159 181.753 + vertex -679.917 186.352 180.002 + vertex -678.782 182.009 181.482 + endloop + endfacet + facet normal -0.966634 -0.255983 -0.00955879 + outer loop + vertex -678.782 182.009 181.482 + vertex -679.917 186.352 180.002 + vertex -678.782 182.079 179.612 + endloop + endfacet + facet normal -0.966581 -0.253154 -0.0404307 + outer loop + vertex -679.917 186.352 180.002 + vertex -680.083 187.303 177.998 + vertex -678.782 182.079 179.612 + endloop + endfacet + facet normal -0.969703 -0.24413 -0.00872582 + outer loop + vertex -678.782 182.079 179.612 + vertex -680.083 187.303 177.998 + vertex -678.778 182.131 177.702 + endloop + endfacet + facet normal -0.969026 -0.245815 0.0237527 + outer loop + vertex -680.083 187.303 177.998 + vertex -679.911 186.452 176.179 + vertex -678.778 182.131 177.702 + endloop + endfacet + facet normal -0.96681 -0.255444 -0.00521372 + outer loop + vertex -678.778 182.131 177.702 + vertex -679.911 186.452 176.179 + vertex -678.778 182.171 175.754 + endloop + endfacet + facet normal -0.966968 -0.252648 -0.03379 + outer loop + vertex -679.911 186.452 176.179 + vertex -680.077 187.364 174.106 + vertex -678.778 182.171 175.754 + endloop + endfacet + facet normal -0.969779 -0.24395 -0.00417299 + outer loop + vertex -678.778 182.171 175.754 + vertex -680.077 187.364 174.106 + vertex -678.775 182.194 173.782 + endloop + endfacet + facet normal -0.968851 -0.245842 0.0298189 + outer loop + vertex -680.077 187.364 174.106 + vertex -679.911 186.482 172.237 + vertex -678.775 182.194 173.782 + endloop + endfacet + facet normal -0.966652 -0.256093 -0.000253926 + outer loop + vertex -678.775 182.194 173.782 + vertex -679.911 186.482 172.237 + vertex -678.776 182.198 171.8 + endloop + endfacet + facet normal -0.966965 -0.253133 -0.0300478 + outer loop + vertex -679.911 186.482 172.237 + vertex -680.076 187.362 170.145 + vertex -678.776 182.198 171.8 + endloop + endfacet + facet normal -0.969735 -0.244158 0.000133936 + outer loop + vertex -678.776 182.198 171.8 + vertex -680.076 187.362 170.145 + vertex -678.774 182.19 169.814 + endloop + endfacet + facet normal -0.968639 -0.246075 0.0344201 + outer loop + vertex -680.076 187.362 170.145 + vertex -679.912 186.452 168.268 + vertex -678.774 182.19 169.814 + endloop + endfacet + facet normal -0.966774 -0.255539 0.00695384 + outer loop + vertex -678.774 182.19 169.814 + vertex -679.912 186.452 168.268 + vertex -678.78 182.159 167.829 + endloop + endfacet + facet normal -0.967297 -0.252505 -0.0240563 + outer loop + vertex -679.912 186.452 168.268 + vertex -680.081 187.3 166.186 + vertex -678.78 182.159 167.829 + endloop + endfacet + facet normal -0.969938 -0.243254 0.00697929 + outer loop + vertex -678.78 182.159 167.829 + vertex -680.081 187.3 166.186 + vertex -678.784 182.119 165.854 + endloop + endfacet + facet normal -0.968606 -0.245131 0.0414024 + outer loop + vertex -680.081 187.3 166.186 + vertex -679.922 186.358 164.326 + vertex -678.784 182.119 165.854 + endloop + endfacet + facet normal -0.966635 -0.255969 0.00986601 + outer loop + vertex -678.784 182.119 165.854 + vertex -679.922 186.358 164.326 + vertex -678.79 182.066 163.894 + endloop + endfacet + facet normal -0.967217 -0.253288 -0.0183413 + outer loop + vertex -679.922 186.358 164.326 + vertex -680.098 187.175 162.275 + vertex -678.79 182.066 163.894 + endloop + endfacet + facet normal -0.969704 -0.243926 0.0132074 + outer loop + vertex -678.79 182.066 163.894 + vertex -680.098 187.175 162.275 + vertex -678.799 181.995 161.954 + endloop + endfacet + facet normal -0.968327 -0.245565 0.0451798 + outer loop + vertex -680.098 187.175 162.275 + vertex -679.94 186.215 160.446 + vertex -678.799 181.995 161.954 + endloop + endfacet + facet normal -0.96669 -0.25543 0.0163248 + outer loop + vertex -678.799 181.995 161.954 + vertex -679.94 186.215 160.446 + vertex -678.811 181.919 160.026 + endloop + endfacet + facet normal -0.967399 -0.253068 -0.00974329 + outer loop + vertex -679.94 186.215 160.446 + vertex -680.126 187.008 158.418 + vertex -678.811 181.919 160.026 + endloop + endfacet + facet normal -0.969476 -0.244422 0.0193231 + outer loop + vertex -678.811 181.919 160.026 + vertex -680.126 187.008 158.418 + vertex -678.827 181.829 158.101 + endloop + endfacet + facet normal -0.968102 -0.245853 0.0483154 + outer loop + vertex -680.126 187.008 158.418 + vertex -679.968 186.027 156.6 + vertex -678.827 181.829 158.101 + endloop + endfacet + facet normal -0.966813 -0.254413 0.0234017 + outer loop + vertex -678.827 181.829 158.101 + vertex -679.968 186.027 156.6 + vertex -678.844 181.715 156.172 + endloop + endfacet + facet normal -0.967739 -0.251922 -0.00411855 + outer loop + vertex -679.968 186.027 156.6 + vertex -680.156 186.782 154.568 + vertex -678.844 181.715 156.172 + endloop + endfacet + facet normal -0.969558 -0.243766 0.0231338 + outer loop + vertex -678.844 181.715 156.172 + vertex -680.156 186.782 154.568 + vertex -678.858 181.588 154.234 + endloop + endfacet + facet normal -0.967968 -0.245315 0.0534684 + outer loop + vertex -680.156 186.782 154.568 + vertex -680 185.766 152.737 + vertex -678.858 181.588 154.234 + endloop + endfacet + facet normal -0.966835 -0.253738 0.0291039 + outer loop + vertex -678.858 181.588 154.234 + vertex -680 185.766 152.737 + vertex -678.878 181.443 152.295 + endloop + endfacet + facet normal -0.967857 -0.251463 0.00427043 + outer loop + vertex -680 185.766 152.737 + vertex -680.197 186.49 150.703 + vertex -678.878 181.443 152.295 + endloop + endfacet + facet normal -0.969291 -0.244294 0.028183 + outer loop + vertex -678.878 181.443 152.295 + vertex -680.197 186.49 150.703 + vertex -678.898 181.298 150.364 + endloop + endfacet + facet normal -0.967245 -0.246027 0.0625074 + outer loop + vertex -680.197 186.49 150.703 + vertex -680.051 185.453 148.879 + vertex -678.898 181.298 150.364 + endloop + endfacet + facet normal -0.966114 -0.255846 0.0341391 + outer loop + vertex -678.898 181.298 150.364 + vertex -680.051 185.453 148.879 + vertex -678.926 181.147 148.449 + endloop + endfacet + facet normal -0.967323 -0.253452 0.0070141 + outer loop + vertex -680.051 185.453 148.879 + vertex -680.252 186.167 146.873 + vertex -678.926 181.147 148.449 + endloop + endfacet + facet normal -0.968934 -0.244599 0.0365667 + outer loop + vertex -678.926 181.147 148.449 + vertex -680.252 186.167 146.873 + vertex -678.956 180.983 146.551 + endloop + endfacet + facet normal -0.966608 -0.246169 0.0712048 + outer loop + vertex -680.252 186.167 146.873 + vertex -680.116 185.112 145.082 + vertex -678.956 180.983 146.551 + endloop + endfacet + facet normal -0.965569 -0.257111 0.0396324 + outer loop + vertex -678.956 180.983 146.551 + vertex -680.116 185.112 145.082 + vertex -678.982 180.789 144.659 + endloop + endfacet + facet normal -0.96707 -0.25439 0.00783968 + outer loop + vertex -680.116 185.112 145.082 + vertex -680.305 185.772 143.086 + vertex -678.982 180.789 144.659 + endloop + endfacet + facet normal -0.968667 -0.245577 0.0371027 + outer loop + vertex -678.982 180.789 144.659 + vertex -680.305 185.772 143.086 + vertex -678.994 180.546 142.742 + endloop + endfacet + facet normal -0.966651 -0.247068 0.0674014 + outer loop + vertex -680.305 185.772 143.086 + vertex -680.145 184.651 141.279 + vertex -678.994 180.546 142.742 + endloop + endfacet + facet normal -0.96582 -0.255707 0.042504 + outer loop + vertex -678.994 180.546 142.742 + vertex -680.145 184.651 141.279 + vertex -679.012 180.291 140.789 + endloop + endfacet + facet normal -0.967324 -0.253066 0.0155192 + outer loop + vertex -680.145 184.651 141.279 + vertex -680.337 185.261 139.222 + vertex -679.012 180.291 140.789 + endloop + endfacet + facet normal -0.968875 -0.242132 0.0515155 + outer loop + vertex -679.012 180.291 140.789 + vertex -680.337 185.261 139.222 + vertex -679.067 180.089 138.811 + endloop + endfacet + facet normal -0.96652 -0.243815 0.079963 + outer loop + vertex -680.337 185.261 139.222 + vertex -680.209 184.138 137.349 + vertex -679.067 180.089 138.811 + endloop + endfacet + facet normal -0.966171 -0.250623 0.0608332 + outer loop + vertex -679.067 180.089 138.811 + vertex -680.209 184.138 137.349 + vertex -679.149 179.925 136.835 + endloop + endfacet + facet normal -0.968603 -0.247124 0.027174 + outer loop + vertex -680.209 184.138 137.349 + vertex -680.427 184.762 135.247 + vertex -679.149 179.925 136.835 + endloop + endfacet + facet normal -0.969657 -0.238042 0.0556963 + outer loop + vertex -679.149 179.925 136.835 + vertex -680.427 184.762 135.247 + vertex -679.196 179.663 134.895 + endloop + endfacet + facet normal -0.967363 -0.239381 0.0831043 + outer loop + vertex -680.427 184.762 135.247 + vertex -680.307 183.618 133.355 + vertex -679.196 179.663 134.895 + endloop + endfacet + facet normal -0.966215 -0.253679 0.045559 + outer loop + vertex -679.196 179.663 134.895 + vertex -680.307 183.618 133.355 + vertex -679.169 179.211 132.949 + endloop + endfacet + facet normal -0.967029 -0.252644 0.032029 + outer loop + vertex -680.307 183.618 133.355 + vertex -680.533 184.216 131.252 + vertex -679.169 179.211 132.949 + endloop + endfacet + facet normal -0.967963 -0.244762 0.0560203 + outer loop + vertex -679.169 179.211 132.949 + vertex -680.533 184.216 131.252 + vertex -679.206 178.9 130.951 + endloop + endfacet + facet normal -0.96428 -0.246202 0.0977198 + outer loop + vertex -680.533 184.216 131.252 + vertex -680.44 183.104 129.368 + vertex -679.206 178.9 130.951 + endloop + endfacet + facet normal -0.963968 -0.256881 0.0691279 + outer loop + vertex -679.206 178.9 130.951 + vertex -680.44 183.104 129.368 + vertex -679.284 178.662 128.974 + endloop + endfacet + facet normal -0.965988 -0.255054 0.042608 + outer loop + vertex -680.44 183.104 129.368 + vertex -680.686 183.69 127.3 + vertex -679.284 178.662 128.974 + endloop + endfacet + facet normal -0.966748 -0.244495 0.0749693 + outer loop + vertex -679.284 178.662 128.974 + vertex -680.686 183.69 127.3 + vertex -679.367 178.391 127.022 + endloop + endfacet + facet normal -0.96442 -0.245173 0.0989115 + outer loop + vertex -680.686 183.69 127.3 + vertex -680.574 182.507 125.462 + vertex -679.367 178.391 127.022 + endloop + endfacet + facet normal -0.964091 -0.256553 0.0686291 + outer loop + vertex -679.367 178.391 127.022 + vertex -680.574 182.507 125.462 + vertex -679.414 178.052 125.092 + endloop + endfacet + facet normal -0.966003 -0.254926 0.0430267 + outer loop + vertex -680.574 182.507 125.462 + vertex -680.791 182.992 123.444 + vertex -679.414 178.052 125.092 + endloop + endfacet + facet normal -0.966686 -0.2467 0.0682505 + outer loop + vertex -679.414 178.052 125.092 + vertex -680.791 182.992 123.444 + vertex -679.455 177.682 123.183 + endloop + endfacet + facet normal -0.963086 -0.247629 0.105572 + outer loop + vertex -680.791 182.992 123.444 + vertex -680.67 181.757 121.656 + vertex -679.455 177.682 123.183 + endloop + endfacet + facet normal -0.963007 -0.257973 0.077899 + outer loop + vertex -679.455 177.682 123.183 + vertex -680.67 181.757 121.656 + vertex -679.507 177.309 121.3 + endloop + endfacet + facet normal -0.9656 -0.256047 0.0453444 + outer loop + vertex -680.67 181.757 121.656 + vertex -680.888 182.233 119.693 + vertex -679.507 177.309 121.3 + endloop + endfacet + facet normal -0.966236 -0.245699 0.0775857 + outer loop + vertex -679.507 177.309 121.3 + vertex -680.888 182.233 119.693 + vertex -679.562 176.94 119.442 + endloop + endfacet + facet normal -0.962558 -0.246453 0.112884 + outer loop + vertex -680.888 182.233 119.693 + vertex -680.778 180.999 117.94 + vertex -679.562 176.94 119.442 + endloop + endfacet + facet normal -0.962726 -0.256414 0.0860864 + outer loop + vertex -679.562 176.94 119.442 + vertex -680.778 180.999 117.94 + vertex -679.628 176.561 117.583 + endloop + endfacet + facet normal -0.965312 -0.25476 0.0571779 + outer loop + vertex -680.778 180.999 117.94 + vertex -681.014 181.453 115.971 + vertex -679.628 176.561 117.583 + endloop + endfacet + facet normal -0.965619 -0.245749 0.0847758 + outer loop + vertex -679.628 176.561 117.583 + vertex -681.014 181.453 115.971 + vertex -679.692 176.17 115.713 + endloop + endfacet + facet normal -0.960971 -0.246571 0.125445 + outer loop + vertex -681.014 181.453 115.971 + vertex -680.923 180.195 114.195 + vertex -679.692 176.17 115.713 + endloop + endfacet + facet normal -0.96141 -0.258665 0.0937217 + outer loop + vertex -679.692 176.17 115.713 + vertex -680.923 180.195 114.195 + vertex -679.766 175.761 113.827 + endloop + endfacet + facet normal -0.963733 -0.257353 0.0706246 + outer loop + vertex -680.923 180.195 114.195 + vertex -681.181 180.614 112.2 + vertex -679.766 175.761 113.827 + endloop + endfacet + facet normal -0.963718 -0.247587 0.0997446 + outer loop + vertex -679.766 175.761 113.827 + vertex -681.181 180.614 112.2 + vertex -679.853 175.335 111.931 + endloop + endfacet + facet normal -0.959125 -0.248271 0.135799 + outer loop + vertex -681.181 180.614 112.2 + vertex -681.103 179.33 110.406 + vertex -679.853 175.335 111.931 + endloop + endfacet + facet normal -0.959807 -0.259647 0.106552 + outer loop + vertex -679.853 175.335 111.931 + vertex -681.103 179.33 110.406 + vertex -679.945 174.897 110.031 + endloop + endfacet + facet normal -0.962933 -0.258082 0.0784462 + outer loop + vertex -681.103 179.33 110.406 + vertex -681.372 179.728 108.408 + vertex -679.945 174.897 110.031 + endloop + endfacet + facet normal -0.962644 -0.24732 0.110228 + outer loop + vertex -679.945 174.897 110.031 + vertex -681.372 179.728 108.408 + vertex -680.048 174.447 108.128 + endloop + endfacet + facet normal -0.957486 -0.247996 0.147375 + outer loop + vertex -681.372 179.728 108.408 + vertex -681.311 178.425 106.612 + vertex -680.048 174.447 108.128 + endloop + endfacet + facet normal -0.958496 -0.259352 0.118418 + outer loop + vertex -680.048 174.447 108.128 + vertex -681.311 178.425 106.612 + vertex -680.159 173.989 106.226 + endloop + endfacet + facet normal -0.961707 -0.257949 0.0926441 + outer loop + vertex -681.311 178.425 106.612 + vertex -681.607 178.815 104.627 + vertex -680.159 173.989 106.226 + endloop + endfacet + facet normal -0.960887 -0.246713 0.125813 + outer loop + vertex -680.159 173.989 106.226 + vertex -681.607 178.815 104.627 + vertex -680.287 173.521 104.329 + endloop + endfacet + facet normal -0.954861 -0.247383 0.164447 + outer loop + vertex -681.607 178.815 104.627 + vertex -681.574 177.503 102.844 + vertex -680.287 173.521 104.329 + endloop + endfacet + facet normal -0.956476 -0.259347 0.133765 + outer loop + vertex -680.287 173.521 104.329 + vertex -681.574 177.503 102.844 + vertex -680.423 173.052 102.447 + endloop + endfacet + facet normal -0.960815 -0.257653 0.102221 + outer loop + vertex -681.574 177.503 102.844 + vertex -681.89 177.908 100.894 + vertex -680.423 173.052 102.447 + endloop + endfacet + facet normal -0.959506 -0.246143 0.136974 + outer loop + vertex -680.423 173.052 102.447 + vertex -681.89 177.908 100.894 + vertex -680.571 172.59 100.58 + endloop + endfacet + facet normal -0.952029 -0.246876 0.180815 + outer loop + vertex -681.89 177.908 100.894 + vertex -681.885 176.6 99.1351 + vertex -680.571 172.59 100.58 + endloop + endfacet + facet normal -0.954281 -0.258995 0.149231 + outer loop + vertex -680.571 172.59 100.58 + vertex -681.885 176.6 99.1351 + vertex -680.737 172.134 98.7239 + endloop + endfacet + facet normal -0.958676 -0.257519 0.120934 + outer loop + vertex -681.885 176.6 99.1351 + vertex -682.238 177.003 97.1948 + vertex -680.737 172.134 98.7239 + endloop + endfacet + facet normal -0.956604 -0.245628 0.156766 + outer loop + vertex -680.737 172.134 98.7239 + vertex -682.238 177.003 97.1948 + vertex -680.925 171.68 96.8699 + endloop + endfacet + facet normal -0.949249 -0.246192 0.195743 + outer loop + vertex -682.238 177.003 97.1948 + vertex -682.256 175.667 95.4279 + vertex -680.925 171.68 96.8699 + endloop + endfacet + facet normal -0.951838 -0.257863 0.165866 + outer loop + vertex -680.925 171.68 96.8699 + vertex -682.256 175.667 95.4279 + vertex -681.117 171.197 95.014 + endloop + endfacet + facet normal -0.955953 -0.256727 0.142282 + outer loop + vertex -682.256 175.667 95.4279 + vertex -682.626 175.948 93.4511 + vertex -681.117 171.197 95.014 + endloop + endfacet + facet normal -0.95401 -0.247065 0.169773 + outer loop + vertex -681.117 171.197 95.014 + vertex -682.626 175.948 93.4511 + vertex -681.303 170.641 93.1623 + endloop + endfacet + facet normal -0.943487 -0.247215 0.220718 + outer loop + vertex -682.626 175.948 93.4511 + vertex -682.64 174.435 91.6964 + vertex -681.303 170.641 93.1623 + endloop + endfacet + facet normal -0.94694 -0.26152 0.186846 + outer loop + vertex -681.303 170.641 93.1623 + vertex -682.64 174.435 91.6964 + vertex -681.489 169.992 91.3107 + endloop + endfacet + facet normal -0.946417 -0.261603 0.189364 + outer loop + vertex -682.64 174.435 91.6964 + vertex -683.011 174.445 89.8535 + vertex -681.489 169.992 91.3107 + endloop + endfacet + facet normal -0.945264 -0.257654 0.200226 + outer loop + vertex -681.489 169.992 91.3107 + vertex -683.011 174.445 89.8535 + vertex -681.745 169.414 89.3608 + endloop + endfacet + facet normal -0.936187 -0.25903 0.237608 + outer loop + vertex -683.011 174.445 89.8535 + vertex -683.257 173.465 87.8166 + vertex -681.745 169.414 89.3608 + endloop + endfacet + facet normal -0.935932 -0.25822 0.239485 + outer loop + vertex -681.745 169.414 89.3608 + vertex -683.257 173.465 87.8166 + vertex -682.149 169.07 87.4086 + endloop + endfacet + facet normal -0.938184 -0.257979 0.230776 + outer loop + vertex -683.257 173.465 87.8166 + vertex -683.534 172.758 85.8998 + vertex -682.149 169.07 87.4086 + endloop + endfacet + facet normal -0.936211 -0.251026 0.245956 + outer loop + vertex -682.149 169.07 87.4086 + vertex -683.534 172.758 85.8998 + vertex -682.55 168.804 85.6114 + endloop + endfacet + facet normal -0.940103 -0.250888 0.230786 + outer loop + vertex -683.534 172.758 85.8998 + vertex -683.839 172.216 84.0716 + vertex -682.55 168.804 85.6114 + endloop + endfacet + facet normal -0.940245 -0.25151 0.229527 + outer loop + vertex -682.55 168.804 85.6114 + vertex -683.839 172.216 84.0716 + vertex -682.837 168.283 83.8636 + endloop + endfacet + facet normal -0.936849 -0.251367 0.243163 + outer loop + vertex -683.839 172.216 84.0716 + vertex -684.177 171.738 82.2718 + vertex -682.837 168.283 83.8636 + endloop + endfacet + facet normal -0.936626 -0.250452 0.24496 + outer loop + vertex -682.837 168.283 83.8636 + vertex -684.177 171.738 82.2718 + vertex -683.176 167.783 82.0577 + endloop + endfacet + facet normal -0.932147 -0.250225 0.261705 + outer loop + vertex -684.177 171.738 82.2718 + vertex -684.564 171.3 80.4752 + vertex -683.176 167.783 82.0577 + endloop + endfacet + facet normal -0.93146 -0.247857 0.266363 + outer loop + vertex -683.176 167.783 82.0577 + vertex -684.564 171.3 80.4752 + vertex -683.571 167.31 80.2358 + endloop + endfacet + facet normal -0.926518 -0.247641 0.283264 + outer loop + vertex -684.564 171.3 80.4752 + vertex -684.992 170.851 78.6843 + vertex -683.571 167.31 80.2358 + endloop + endfacet + facet normal -0.926772 -0.248401 0.281762 + outer loop + vertex -683.571 167.31 80.2358 + vertex -684.992 170.851 78.6843 + vertex -683.996 166.844 78.4277 + endloop + endfacet + facet normal -0.921473 -0.248177 0.298824 + outer loop + vertex -684.992 170.851 78.6843 + vertex -685.446 170.393 76.9022 + vertex -683.996 166.844 78.4277 + endloop + endfacet + facet normal -0.921598 -0.248516 0.298155 + outer loop + vertex -683.996 166.844 78.4277 + vertex -685.446 170.393 76.9022 + vertex -684.449 166.369 76.6314 + endloop + endfacet + facet normal -0.91572 -0.248257 0.315953 + outer loop + vertex -685.446 170.393 76.9022 + vertex -685.937 169.931 75.1176 + vertex -684.449 166.369 76.6314 + endloop + endfacet + facet normal -0.915438 -0.247562 0.31731 + outer loop + vertex -684.449 166.369 76.6314 + vertex -685.937 169.931 75.1176 + vertex -684.942 165.887 74.8313 + endloop + endfacet + facet normal -0.90874 -0.247255 0.336239 + outer loop + vertex -685.937 169.931 75.1176 + vertex -686.478 169.473 73.318 + vertex -684.942 165.887 74.8313 + endloop + endfacet + facet normal -0.90902 -0.247894 0.335008 + outer loop + vertex -684.942 165.887 74.8313 + vertex -686.478 169.473 73.318 + vertex -685.483 165.417 73.0159 + endloop + endfacet + facet normal -0.901345 -0.24753 0.355396 + outer loop + vertex -686.478 169.473 73.318 + vertex -687.071 169.031 71.5063 + vertex -685.483 165.417 73.0159 + endloop + endfacet + facet normal -0.900438 -0.245628 0.358996 + outer loop + vertex -685.483 165.417 73.0159 + vertex -687.071 169.031 71.5063 + vertex -686.085 164.945 71.1833 + endloop + endfacet + facet normal -0.892856 -0.245276 0.377687 + outer loop + vertex -687.071 169.031 71.5063 + vertex -687.716 168.6 69.7004 + vertex -686.085 164.945 71.1833 + endloop + endfacet + facet normal -0.892405 -0.244418 0.379306 + outer loop + vertex -686.085 164.945 71.1833 + vertex -687.716 168.6 69.7004 + vertex -686.737 164.49 69.3569 + endloop + endfacet + facet normal -0.883006 -0.243987 0.400961 + outer loop + vertex -687.716 168.6 69.7004 + vertex -688.403 168.185 67.9363 + vertex -686.737 164.49 69.3569 + endloop + endfacet + facet normal -0.882759 -0.243569 0.40176 + outer loop + vertex -686.737 164.49 69.3569 + vertex -688.403 168.185 67.9363 + vertex -687.43 164.058 67.5731 + endloop + endfacet + facet normal -0.872983 -0.243118 0.42284 + outer loop + vertex -688.403 168.185 67.9363 + vertex -689.113 167.806 66.2525 + vertex -687.43 164.058 67.5731 + endloop + endfacet + facet normal -0.872836 -0.242901 0.423268 + outer loop + vertex -687.43 164.058 67.5731 + vertex -689.113 167.806 66.2525 + vertex -688.147 163.666 65.869 + endloop + endfacet + facet normal -0.860557 -0.242328 0.448017 + outer loop + vertex -689.113 167.806 66.2525 + vertex -689.845 167.462 64.6601 + vertex -688.147 163.666 65.869 + endloop + endfacet + facet normal -0.860244 -0.241928 0.448833 + outer loop + vertex -688.147 163.666 65.869 + vertex -689.845 167.462 64.6601 + vertex -688.889 163.308 64.2541 + endloop + endfacet + facet normal -0.848801 -0.2414 0.470385 + outer loop + vertex -689.845 167.462 64.6601 + vertex -690.599 167.168 63.1484 + vertex -688.889 163.308 64.2541 + endloop + endfacet + facet normal -0.848288 -0.240823 0.471606 + outer loop + vertex -688.889 163.308 64.2541 + vertex -690.599 167.168 63.1484 + vertex -689.655 162.999 62.7172 + endloop + endfacet + facet normal -0.832622 -0.240118 0.499082 + outer loop + vertex -690.599 167.168 63.1484 + vertex -691.404 166.893 61.6727 + vertex -689.655 162.999 62.7172 + endloop + endfacet + facet normal -0.832013 -0.239491 0.500399 + outer loop + vertex -689.655 162.999 62.7172 + vertex -691.404 166.893 61.6727 + vertex -690.475 162.71 61.2163 + endloop + endfacet + facet normal -0.817494 -0.238848 0.524075 + outer loop + vertex -691.404 166.893 61.6727 + vertex -692.273 166.638 60.2011 + vertex -690.475 162.71 61.2163 + endloop + endfacet + facet normal -0.816344 -0.237728 0.526372 + outer loop + vertex -690.475 162.71 61.2163 + vertex -692.273 166.638 60.2011 + vertex -691.36 162.44 59.7211 + endloop + endfacet + facet normal -0.798493 -0.236938 0.553417 + outer loop + vertex -692.273 166.638 60.2011 + vertex -693.224 166.392 58.7243 + vertex -691.36 162.44 59.7211 + endloop + endfacet + facet normal -0.798164 -0.23663 0.554022 + outer loop + vertex -691.36 162.44 59.7211 + vertex -693.224 166.392 58.7243 + vertex -692.327 162.196 58.2245 + endloop + endfacet + facet normal -0.776422 -0.235614 0.584512 + outer loop + vertex -693.224 166.392 58.7243 + vertex -694.258 166.187 57.2675 + vertex -692.327 162.196 58.2245 + endloop + endfacet + facet normal -0.777558 -0.236625 0.58259 + outer loop + vertex -692.327 162.196 58.2245 + vertex -694.258 166.187 57.2675 + vertex -693.373 162.01 56.7533 + endloop + endfacet + facet normal -0.754884 -0.235454 0.612136 + outer loop + vertex -694.258 166.187 57.2675 + vertex -695.359 166.094 55.8746 + vertex -693.373 162.01 56.7533 + endloop + endfacet + facet normal -0.753853 -0.234609 0.61373 + outer loop + vertex -693.373 162.01 56.7533 + vertex -695.359 166.094 55.8746 + vertex -694.48 161.896 55.3493 + endloop + endfacet + facet normal -0.730296 -0.233227 0.642085 + outer loop + vertex -695.359 166.094 55.8746 + vertex -696.483 166.047 54.5792 + vertex -694.48 161.896 55.3493 + endloop + endfacet + facet normal -0.728754 -0.232082 0.644248 + outer loop + vertex -694.48 161.896 55.3493 + vertex -696.483 166.047 54.5792 + vertex -695.587 161.796 54.0617 + endloop + endfacet + facet normal -0.700931 -0.229976 0.675135 + outer loop + vertex -696.483 166.047 54.5792 + vertex -697.494 165.748 53.4269 + vertex -695.587 161.796 54.0617 + endloop + endfacet + facet normal -0.700407 -0.229616 0.675801 + outer loop + vertex -695.587 161.796 54.0617 + vertex -697.494 165.748 53.4269 + vertex -696.622 161.645 52.9373 + endloop + endfacet + facet normal -0.6665 -0.226516 0.710259 + outer loop + vertex -697.494 165.748 53.4269 + vertex -698.166 164.999 52.558 + vertex -696.622 161.645 52.9373 + endloop + endfacet + facet normal -0.68005 -0.234521 0.694645 + outer loop + vertex -696.622 161.645 52.9373 + vertex -698.166 164.999 52.558 + vertex -697.632 161.775 51.9918 + endloop + endfacet + facet normal -0.733505 -0.233478 0.638325 + outer loop + vertex -698.166 164.999 52.558 + vertex -699.168 166.362 51.9045 + vertex -697.632 161.775 51.9918 + endloop + endfacet + facet normal -0.664122 -0.208729 0.717896 + outer loop + vertex -697.632 161.775 51.9918 + vertex -699.168 166.362 51.9045 + vertex -698.561 162.023 51.2053 + endloop + endfacet + facet normal -0.668632 -0.208686 0.713709 + outer loop + vertex -699.168 166.362 51.9045 + vertex -699.82 166.271 51.2676 + vertex -698.561 162.023 51.2053 + endloop + endfacet + facet normal -0.648493 -0.203008 0.733652 + outer loop + vertex -698.561 162.023 51.2053 + vertex -699.82 166.271 51.2676 + vertex -699.271 162.2 50.6263 + endloop + endfacet + facet normal -0.725251 -0.201494 0.65834 + outer loop + vertex -699.82 166.271 51.2676 + vertex -700.402 167.401 50.9725 + vertex -699.271 162.2 50.6263 + endloop + endfacet + facet normal -0.626856 -0.186634 0.756452 + outer loop + vertex -699.271 162.2 50.6263 + vertex -700.402 167.401 50.9725 + vertex -699.7 162.204 50.272 + endloop + endfacet + facet normal -0.596189 -0.185808 0.781047 + outer loop + vertex -700.402 167.401 50.9725 + vertex -700.546 166.546 50.6591 + vertex -699.7 162.204 50.272 + endloop + endfacet + facet normal -0.666351 -0.194032 0.71995 + outer loop + vertex -699.7 162.204 50.272 + vertex -700.546 166.546 50.6591 + vertex -699.852 162.184 50.1258 + endloop + endfacet + facet normal -0.983372 -0.165554 0.074639 + outer loop + vertex -700.546 166.546 50.6591 + vertex -700.711 167.546 50.6948 + vertex -699.852 162.184 50.1258 + endloop + endfacet + facet normal -0.984938 -0.148481 -0.0885982 + outer loop + vertex -699.852 162.184 50.1258 + vertex -700.711 167.546 50.6948 + vertex -699.86 162.246 50.1065 + endloop + endfacet + facet normal 0.366931 -0.0441674 0.929199 + outer loop + vertex -700.711 167.546 50.6948 + vertex -700.612 166.803 50.6202 + vertex -699.86 162.246 50.1065 + endloop + endfacet + facet normal -0.300891 0.057633 -0.951916 + outer loop + vertex -699.86 162.246 50.1065 + vertex -700.612 166.803 50.6202 + vertex -699.875 162.471 50.1252 + endloop + endfacet + facet normal -0.970596 -0.142909 -0.193701 + outer loop + vertex -700.612 166.803 50.6202 + vertex -700.822 168.086 50.7262 + vertex -699.875 162.471 50.1252 + endloop + endfacet + facet normal -0.499538 -0.175033 0.848425 + outer loop + vertex -699.875 162.471 50.1252 + vertex -700.822 168.086 50.7262 + vertex -699.961 162.692 50.1202 + endloop + endfacet + facet normal -0.0340809 -0.116952 0.992553 + outer loop + vertex -700.822 168.086 50.7262 + vertex -700.883 167.307 50.6322 + vertex -699.961 162.692 50.1202 + endloop + endfacet + facet normal -0.163681 -0.141036 0.97638 + outer loop + vertex -699.961 162.692 50.1202 + vertex -700.883 167.307 50.6322 + vertex -699.99 162.069 50.0254 + endloop + endfacet + facet normal 0.08652 -0.100089 0.99121 + outer loop + vertex -700.883 167.307 50.6322 + vertex -700.489 163.97 50.261 + vertex -699.99 162.069 50.0254 + endloop + endfacet + facet normal -0.152491 -0.160864 0.975125 + outer loop + vertex -699.99 162.069 50.0254 + vertex -700.489 163.97 50.261 + vertex -699.909 161.081 49.8749 + endloop + endfacet + facet normal -0.869291 -0.232631 0.436137 + outer loop + vertex -699.909 161.081 49.8749 + vertex -700.489 163.97 50.261 + vertex -700.054 161.637 49.8844 + endloop + endfacet + facet normal -0.367264 -0.145582 0.918653 + outer loop + vertex -700.489 163.97 50.261 + vertex -700.883 167.307 50.6322 + vertex -700.844 166.047 50.4483 + endloop + endfacet + facet normal -0.692697 -0.173887 0.699952 + outer loop + vertex -698.166 164.999 52.558 + vertex -699.104 169.619 52.7774 + vertex -699.168 166.362 51.9045 + endloop + endfacet + facet normal -0.760292 -0.154079 0.631044 + outer loop + vertex -699.168 166.362 51.9045 + vertex -699.104 169.619 52.7774 + vertex -700.574 173.597 51.9771 + endloop + endfacet + facet normal -0.70029 -0.175054 0.692062 + outer loop + vertex -697.494 165.748 53.4269 + vertex -699.104 169.619 52.7774 + vertex -698.166 164.999 52.558 + endloop + endfacet + facet normal -0.696578 -0.172789 0.696364 + outer loop + vertex -698.28 170.759 53.8851 + vertex -699.104 169.619 52.7774 + vertex -697.494 165.748 53.4269 + endloop + endfacet + facet normal -0.71714 -0.174043 0.674848 + outer loop + vertex -696.483 166.047 54.5792 + vertex -698.28 170.759 53.8851 + vertex -697.494 165.748 53.4269 + endloop + endfacet + facet normal -0.724137 -0.177971 0.666297 + outer loop + vertex -697.149 170.734 55.1068 + vertex -698.28 170.759 53.8851 + vertex -696.483 166.047 54.5792 + endloop + endfacet + facet normal -0.726931 -0.12951 0.674387 + outer loop + vertex -698.28 170.759 53.8851 + vertex -699.921 176.427 53.2039 + vertex -699.104 169.619 52.7774 + endloop + endfacet + facet normal -0.720343 -0.129164 0.681485 + outer loop + vertex -699.921 176.427 53.2039 + vertex -700.574 173.597 51.9771 + vertex -699.104 169.619 52.7774 + endloop + endfacet + facet normal -0.723104 -0.127871 0.6788 + outer loop + vertex -698.751 176.545 54.4732 + vertex -699.921 176.427 53.2039 + vertex -698.28 170.759 53.8851 + endloop + endfacet + facet normal -0.849913 -0.172702 -0.497817 + outer loop + vertex -692.317 171.436 282.021 + vertex -691.454 171.723 280.448 + vertex -691.48 166.879 282.173 + endloop + endfacet + facet normal -0.875784 -0.126392 -0.465863 + outer loop + vertex -691.454 171.723 280.448 + vertex -691.37 177.473 278.73 + vertex -690.634 172.043 278.82 + endloop + endfacet + facet normal -0.893571 -0.12821 -0.430224 + outer loop + vertex -691.37 177.473 278.73 + vertex -690.555 176.871 277.217 + vertex -690.634 172.043 278.82 + endloop + endfacet + facet normal -0.888957 -0.131138 -0.438815 + outer loop + vertex -690.634 172.043 278.82 + vertex -690.555 176.871 277.217 + vertex -689.861 172.41 277.144 + endloop + endfacet + facet normal -0.896126 -0.132502 -0.423558 + outer loop + vertex -690.555 176.871 277.217 + vertex -689.882 178.188 275.38 + vertex -689.861 172.41 277.144 + endloop + endfacet + facet normal -0.902346 -0.128788 -0.411321 + outer loop + vertex -689.861 172.41 277.144 + vertex -689.882 178.188 275.38 + vertex -689.134 172.802 275.426 + endloop + endfacet + facet normal -0.91837 -0.130693 -0.373519 + outer loop + vertex -689.882 178.188 275.38 + vertex -689.155 177.618 273.792 + vertex -689.134 172.802 275.426 + endloop + endfacet + facet normal -0.91373 -0.134081 -0.383562 + outer loop + vertex -689.134 172.802 275.426 + vertex -689.155 177.618 273.792 + vertex -688.459 173.21 273.675 + endloop + endfacet + facet normal -0.917174 -0.134852 -0.374975 + outer loop + vertex -689.155 177.618 273.792 + vertex -688.588 178.977 271.916 + vertex -688.459 173.21 273.675 + endloop + endfacet + facet normal -0.924867 -0.129693 -0.357494 + outer loop + vertex -688.459 173.21 273.675 + vertex -688.588 178.977 271.916 + vertex -687.833 173.627 271.904 + endloop + endfacet + facet normal -0.935747 -0.1313 -0.327318 + outer loop + vertex -688.588 178.977 271.916 + vertex -687.945 178.456 270.287 + vertex -687.833 173.627 271.904 + endloop + endfacet + facet normal -0.932625 -0.133836 -0.33511 + outer loop + vertex -687.833 173.627 271.904 + vertex -687.945 178.456 270.287 + vertex -687.256 174.045 270.133 + endloop + endfacet + facet normal -0.933487 -0.134057 -0.332612 + outer loop + vertex -687.945 178.456 270.287 + vertex -687.476 179.823 268.421 + vertex -687.256 174.045 270.133 + endloop + endfacet + facet normal -0.941355 -0.128274 -0.312083 + outer loop + vertex -687.256 174.045 270.133 + vertex -687.476 179.823 268.421 + vertex -686.728 174.456 268.371 + endloop + endfacet + facet normal -0.950781 -0.129873 -0.281334 + outer loop + vertex -687.476 179.823 268.421 + vertex -686.917 179.268 266.788 + vertex -686.728 174.456 268.371 + endloop + endfacet + facet normal -0.947087 -0.133242 -0.292016 + outer loop + vertex -686.728 174.456 268.371 + vertex -686.917 179.268 266.788 + vertex -686.245 174.85 266.625 + endloop + endfacet + facet normal -0.947237 -0.133283 -0.291509 + outer loop + vertex -686.917 179.268 266.788 + vertex -686.538 180.595 264.95 + vertex -686.245 174.85 266.625 + endloop + endfacet + facet normal -0.953428 -0.128207 -0.273017 + outer loop + vertex -686.245 174.85 266.625 + vertex -686.538 180.595 264.95 + vertex -685.801 175.22 264.898 + endloop + endfacet + facet normal -0.961649 -0.129633 -0.241716 + outer loop + vertex -686.538 180.595 264.95 + vertex -686.052 179.973 263.35 + vertex -685.801 175.22 264.898 + endloop + endfacet + facet normal -0.956967 -0.134425 -0.257185 + outer loop + vertex -685.801 175.22 264.898 + vertex -686.052 179.973 263.35 + vertex -685.394 175.59 263.191 + endloop + endfacet + facet normal -0.956148 -0.134187 -0.260335 + outer loop + vertex -686.052 179.973 263.35 + vertex -685.752 181.359 261.531 + vertex -685.394 175.59 263.191 + endloop + endfacet + facet normal -0.962554 -0.12838 -0.238764 + outer loop + vertex -685.394 175.59 263.191 + vertex -685.752 181.359 261.531 + vertex -685.025 176.021 261.473 + endloop + endfacet + facet normal -0.970224 -0.129801 -0.204491 + outer loop + vertex -685.752 181.359 261.531 + vertex -685.341 180.893 259.881 + vertex -685.025 176.021 261.473 + endloop + endfacet + facet normal -0.965478 -0.135387 -0.222535 + outer loop + vertex -685.025 176.021 261.473 + vertex -685.341 180.893 259.881 + vertex -684.687 176.586 259.661 + endloop + endfacet + facet normal -0.963216 -0.134527 -0.232631 + outer loop + vertex -685.341 180.893 259.881 + vertex -685.106 182.794 257.807 + vertex -684.687 176.586 259.661 + endloop + endfacet + facet normal -0.968635 -0.128868 -0.21246 + outer loop + vertex -684.687 176.586 259.661 + vertex -685.106 182.794 257.807 + vertex -684.322 177.194 257.632 + endloop + endfacet + facet normal -0.97107 -0.12958 -0.200582 + outer loop + vertex -685.106 182.794 257.807 + vertex -684.627 183.353 255.129 + vertex -684.322 177.194 257.632 + endloop + endfacet + facet normal -0.967693 -0.134551 -0.213228 + outer loop + vertex -684.322 177.194 257.632 + vertex -684.627 183.353 255.129 + vertex -683.806 176.714 255.591 + endloop + endfacet + facet normal -0.973867 -0.133274 -0.183902 + outer loop + vertex -684.627 183.353 255.129 + vertex -683.781 181.363 252.09 + vertex -683.806 176.714 255.591 + endloop + endfacet + facet normal -0.974738 -0.129826 0.181746 + outer loop + vertex -684.173 178.605 88.2759 + vertex -685.047 182.949 86.6921 + vertex -684.388 177.42 86.2753 + endloop + endfacet + facet normal -0.968441 -0.131343 0.211829 + outer loop + vertex -685.047 182.949 86.6921 + vertex -685.214 181.268 84.8885 + vertex -684.388 177.42 86.2753 + endloop + endfacet + facet normal -0.974865 -0.130197 0.180798 + outer loop + vertex -684.728 183.003 88.4491 + vertex -685.047 182.949 86.6921 + vertex -684.173 178.605 88.2759 + endloop + endfacet + facet normal -0.968743 -0.13061 0.210899 + outer loop + vertex -684.728 183.003 88.4491 + vertex -684.173 178.605 88.2759 + vertex -683.977 181.229 90.8002 + endloop + endfacet + facet normal -0.971081 -0.138048 0.194794 + outer loop + vertex -684.388 177.42 86.2753 + vertex -685.214 181.268 84.8885 + vertex -684.661 176.683 84.3919 + endloop + endfacet + facet normal -0.970453 -0.13829 0.197729 + outer loop + vertex -685.214 181.268 84.8885 + vertex -685.645 181.572 82.9854 + vertex -684.661 176.683 84.3919 + endloop + endfacet + facet normal -0.967943 -0.133455 0.21278 + outer loop + vertex -684.661 176.683 84.3919 + vertex -685.645 181.572 82.9854 + vertex -684.989 176.163 82.5741 + endloop + endfacet + facet normal -0.958395 -0.135233 0.251378 + outer loop + vertex -685.645 181.572 82.9854 + vertex -685.902 180.175 81.2521 + vertex -684.989 176.163 82.5741 + endloop + endfacet + facet normal -0.960611 -0.139341 0.240439 + outer loop + vertex -684.989 176.163 82.5741 + vertex -685.902 180.175 81.2521 + vertex -685.373 175.722 80.7849 + endloop + endfacet + facet normal -0.958815 -0.139839 0.247221 + outer loop + vertex -685.902 180.175 81.2521 + vertex -686.446 180.63 79.3993 + vertex -685.373 175.722 80.7849 + endloop + endfacet + facet normal -0.955918 -0.13545 0.260525 + outer loop + vertex -685.373 175.722 80.7849 + vertex -686.446 180.63 79.3993 + vertex -685.797 175.296 79.01 + endloop + endfacet + facet normal -0.946494 -0.136626 0.292375 + outer loop + vertex -686.446 180.63 79.3993 + vertex -686.779 179.297 77.698 + vertex -685.797 175.296 79.01 + endloop + endfacet + facet normal -0.949729 -0.141762 0.279138 + outer loop + vertex -685.797 175.296 79.01 + vertex -686.779 179.297 77.698 + vertex -686.25 174.852 77.2402 + endloop + endfacet + facet normal -0.948174 -0.142099 0.284209 + outer loop + vertex -686.779 179.297 77.698 + vertex -687.395 179.71 75.85 + vertex -686.25 174.852 77.2402 + endloop + endfacet + facet normal -0.945134 -0.137975 0.296117 + outer loop + vertex -686.25 174.852 77.2402 + vertex -687.395 179.71 75.85 + vertex -686.739 174.395 75.4689 + endloop + endfacet + facet normal -0.934331 -0.138942 0.328209 + outer loop + vertex -687.395 179.71 75.85 + vertex -687.79 178.363 74.1549 + vertex -686.739 174.395 75.4689 + endloop + endfacet + facet normal -0.938074 -0.144329 0.314938 + outer loop + vertex -686.739 174.395 75.4689 + vertex -687.79 178.363 74.1549 + vertex -687.268 173.957 73.691 + endloop + endfacet + facet normal -0.936168 -0.144678 0.320403 + outer loop + vertex -687.79 178.363 74.1549 + vertex -688.491 178.815 72.3132 + vertex -687.268 173.957 73.691 + endloop + endfacet + facet normal -0.93107 -0.138542 0.337513 + outer loop + vertex -687.268 173.957 73.691 + vertex -688.491 178.815 72.3132 + vertex -687.853 173.528 71.9014 + endloop + endfacet + facet normal -0.918827 -0.139531 0.369172 + outer loop + vertex -688.491 178.815 72.3132 + vertex -688.974 177.535 70.6266 + vertex -687.853 173.528 71.9014 + endloop + endfacet + facet normal -0.921826 -0.143235 0.360167 + outer loop + vertex -687.853 173.528 71.9014 + vertex -688.974 177.535 70.6266 + vertex -688.485 173.121 70.1212 + endloop + endfacet + facet normal -0.919917 -0.143564 0.364886 + outer loop + vertex -688.974 177.535 70.6266 + vertex -689.762 178.053 68.8432 + vertex -688.485 173.121 70.1212 + endloop + endfacet + facet normal -0.913217 -0.136935 0.383775 + outer loop + vertex -688.485 173.121 70.1212 + vertex -689.762 178.053 68.8432 + vertex -689.161 172.728 68.3742 + endloop + endfacet + facet normal -0.899947 -0.13806 0.413564 + outer loop + vertex -689.762 178.053 68.8432 + vertex -690.315 176.831 67.2329 + vertex -689.161 172.728 68.3742 + endloop + endfacet + facet normal -0.902176 -0.140254 0.407931 + outer loop + vertex -689.161 172.728 68.3742 + vertex -690.315 176.831 67.2329 + vertex -689.86 172.371 66.7039 + endloop + endfacet + facet normal -0.898034 -0.140879 0.416759 + outer loop + vertex -690.315 176.831 67.2329 + vertex -691.165 177.416 65.5986 + vertex -689.86 172.371 66.7039 + endloop + endfacet + facet normal -0.8909 -0.135354 0.433562 + outer loop + vertex -689.86 172.371 66.7039 + vertex -691.165 177.416 65.5986 + vertex -690.581 172.044 65.122 + endloop + endfacet + facet normal -0.871747 -0.136551 0.470543 + outer loop + vertex -691.165 177.416 65.5986 + vertex -691.773 176.237 64.129 + vertex -690.581 172.044 65.122 + endloop + endfacet + facet normal -0.87533 -0.139354 0.46301 + outer loop + vertex -690.581 172.044 65.122 + vertex -691.773 176.237 64.129 + vertex -691.329 171.751 63.6183 + endloop + endfacet + facet normal -0.86801 -0.140149 0.476358 + outer loop + vertex -691.773 176.237 64.129 + vertex -692.708 176.877 62.6142 + vertex -691.329 171.751 63.6183 + endloop + endfacet + facet normal -0.861 -0.13555 0.49021 + outer loop + vertex -691.329 171.751 63.6183 + vertex -692.708 176.877 62.6142 + vertex -692.119 171.488 62.1595 + endloop + endfacet + facet normal -0.837213 -0.136274 0.529625 + outer loop + vertex -692.708 176.877 62.6142 + vertex -693.407 175.726 61.2136 + vertex -692.119 171.488 62.1595 + endloop + endfacet + facet normal -0.842511 -0.139996 0.52017 + outer loop + vertex -692.119 171.488 62.1595 + vertex -693.407 175.726 61.2136 + vertex -692.975 171.238 60.7046 + endloop + endfacet + facet normal -0.830758 -0.140944 0.538494 + outer loop + vertex -693.407 175.726 61.2136 + vertex -694.489 176.392 59.7184 + vertex -692.975 171.238 60.7046 + endloop + endfacet + facet normal -0.823903 -0.136731 0.54999 + outer loop + vertex -692.975 171.238 60.7046 + vertex -694.489 176.392 59.7184 + vertex -693.91 170.988 59.2424 + endloop + endfacet + facet normal -0.797462 -0.137208 0.587561 + outer loop + vertex -694.489 176.392 59.7184 + vertex -695.321 175.269 58.3268 + vertex -693.91 170.988 59.2424 + endloop + endfacet + facet normal -0.800523 -0.139211 0.582909 + outer loop + vertex -693.91 170.988 59.2424 + vertex -695.321 175.269 58.3268 + vertex -694.925 170.777 57.7976 + endloop + endfacet + facet normal -0.787026 -0.140128 0.600795 + outer loop + vertex -695.321 175.269 58.3268 + vertex -696.54 176.081 56.9193 + vertex -694.925 170.777 57.7976 + endloop + endfacet + facet normal -0.775753 -0.134074 0.616629 + outer loop + vertex -694.925 170.777 57.7976 + vertex -696.54 176.081 56.9193 + vertex -696.013 170.672 56.4058 + endloop + endfacet + facet normal -0.74003 -0.178231 0.648529 + outer loop + vertex -695.359 166.094 55.8746 + vertex -697.149 170.734 55.1068 + vertex -696.483 166.047 54.5792 + endloop + endfacet + facet normal -0.74665 -0.134548 0.651468 + outer loop + vertex -696.54 176.081 56.9193 + vertex -697.494 175.207 55.645 + vertex -696.013 170.672 56.4058 + endloop + endfacet + facet normal -0.729324 -0.127701 0.672145 + outer loop + vertex -697.149 170.734 55.1068 + vertex -698.751 176.545 54.4732 + vertex -698.28 170.759 53.8851 + endloop + endfacet + facet normal -0.764049 -0.0959244 0.637987 + outer loop + vertex -697.494 175.207 55.645 + vertex -696.54 176.081 56.9193 + vertex -698.531 182.701 55.5298 + endloop + endfacet + facet normal -0.767762 -0.0973332 0.633299 + outer loop + vertex -699.921 176.427 53.2039 + vertex -701.296 184.076 52.7132 + vertex -700.574 173.597 51.9771 + endloop + endfacet + facet normal -0.742282 -0.097661 0.662933 + outer loop + vertex -701.296 184.076 52.7132 + vertex -701.876 184.136 52.0728 + vertex -700.574 173.597 51.9771 + endloop + endfacet + facet normal -0.69545 -0.0923307 0.712618 + outer loop + vertex -700.574 173.597 51.9771 + vertex -701.876 184.136 52.0728 + vertex -701.278 173.95 51.3364 + endloop + endfacet + facet normal -0.547361 -0.0922557 0.831796 + outer loop + vertex -701.876 184.136 52.0728 + vertex -702.146 183.439 51.8173 + vertex -701.278 173.95 51.3364 + endloop + endfacet + facet normal -0.526279 -0.0910167 0.845427 + outer loop + vertex -701.278 173.95 51.3364 + vertex -702.146 183.439 51.8173 + vertex -701.471 174.014 51.2229 + endloop + endfacet + facet normal 0.200312 -0.0473752 0.978586 + outer loop + vertex -702.146 183.439 51.8173 + vertex -702.229 181.86 51.7577 + vertex -701.471 174.014 51.2229 + endloop + endfacet + facet normal 0.135703 -0.0543386 0.989258 + outer loop + vertex -701.471 174.014 51.2229 + vertex -702.229 181.86 51.7577 + vertex -701.719 174.553 51.2864 + endloop + endfacet + facet normal 0.0828548 -0.0419054 0.99568 + outer loop + vertex -702.146 183.439 51.8173 + vertex -702.554 189.892 52.1229 + vertex -702.229 181.86 51.7577 + endloop + endfacet + facet normal 0.131822 -0.0385649 0.990523 + outer loop + vertex -702.459 193.519 52.2513 + vertex -702.554 189.892 52.1229 + vertex -702.146 183.439 51.8173 + endloop + endfacet + facet normal -0.217966 -0.0288153 0.975531 + outer loop + vertex -702.554 189.892 52.1229 + vertex -702.459 193.519 52.2513 + vertex -702.631 198.288 52.3538 + endloop + endfacet + facet normal 0.464674 -0.0201195 0.885253 + outer loop + vertex -702.631 198.288 52.3538 + vertex -702.631 191.956 52.2097 + vertex -702.554 189.892 52.1229 + endloop + endfacet + facet normal 0.490501 -0.0185762 0.871243 + outer loop + vertex -702.631 191.956 52.2097 + vertex -702.508 185.736 52.0082 + vertex -702.554 189.892 52.1229 + endloop + endfacet + facet normal -0.875247 -0.0110333 0.48355 + outer loop + vertex -702.631 191.956 52.2097 + vertex -702.631 198.288 52.3538 + vertex -702.724 196.696 52.1496 + endloop + endfacet + facet normal -0.60975 -0.0529531 0.790823 + outer loop + vertex -701.876 184.136 52.0728 + vertex -702.459 193.519 52.2513 + vertex -702.146 183.439 51.8173 + endloop + endfacet + facet normal -0.647222 -0.0547026 0.760336 + outer loop + vertex -702.093 193.908 52.591 + vertex -702.459 193.519 52.2513 + vertex -701.876 184.136 52.0728 + endloop + endfacet + facet normal -0.672322 -0.0134982 0.740136 + outer loop + vertex -702.459 193.519 52.2513 + vertex -702.093 193.908 52.591 + vertex -702.294 207.259 52.6513 + endloop + endfacet + facet normal -0.742715 -0.0519064 0.667593 + outer loop + vertex -701.296 184.076 52.7132 + vertex -702.093 193.908 52.591 + vertex -701.876 184.136 52.0728 + endloop + endfacet + facet normal -0.77822 -0.0553064 0.625551 + outer loop + vertex -701.412 191.163 53.195 + vertex -702.093 193.908 52.591 + vertex -701.296 184.076 52.7132 + endloop + endfacet + facet normal -0.710678 -0.0214793 0.703189 + outer loop + vertex -701.412 191.163 53.195 + vertex -701.571 200.377 53.3158 + vertex -702.093 193.908 52.591 + endloop + endfacet + facet normal -0.685803 -0.00180764 0.727785 + outer loop + vertex -701.23 213.035 53.6685 + vertex -702.294 207.259 52.6513 + vertex -701.571 200.377 53.3158 + endloop + endfacet + facet normal -0.716327 0.00911259 0.697705 + outer loop + vertex -701.23 213.035 53.6685 + vertex -701.779 225.153 52.947 + vertex -702.294 207.259 52.6513 + endloop + endfacet + facet normal -0.737544 0.0119427 0.675193 + outer loop + vertex -701.779 225.153 52.947 + vertex -701.382 243.692 53.052 + vertex -701.987 234.424 52.5558 + endloop + endfacet + facet normal -0.762371 0.015073 0.646965 + outer loop + vertex -701.828 242.221 52.5609 + vertex -701.987 234.424 52.5558 + vertex -701.382 243.692 53.052 + endloop + endfacet + facet normal -0.771314 0.00170236 0.636453 + outer loop + vertex -699.857 266.164 54.7117 + vertex -701.178 262.44 53.1201 + vertex -699.868 248.041 54.747 + endloop + endfacet + facet normal -0.676823 0.00611845 0.73612 + outer loop + vertex -701.626 255.247 52.6193 + vertex -701.655 263.709 52.5217 + vertex -702.073 253.97 52.2185 + endloop + endfacet + facet normal -0.694932 0.000759826 0.719075 + outer loop + vertex -701.655 263.709 52.5217 + vertex -701.624 274.247 52.5407 + vertex -702.024 267.608 52.1613 + endloop + endfacet + facet normal -0.769673 0.000272043 0.638438 + outer loop + vertex -699.857 266.164 54.7117 + vertex -701.211 280.439 53.0735 + vertex -701.178 262.44 53.1201 + endloop + endfacet + facet normal -0.781701 -0.00256592 0.623649 + outer loop + vertex -699.95 283.586 54.667 + vertex -701.211 280.439 53.0735 + vertex -699.857 266.164 54.7117 + endloop + endfacet + facet normal -0.723614 -0.000250882 0.690205 + outer loop + vertex -701.624 274.247 52.5407 + vertex -701.666 283.148 52.4997 + vertex -701.973 282.105 52.1775 + endloop + endfacet + facet normal -0.720105 -0.00241431 0.69386 + outer loop + vertex -701.666 283.148 52.4997 + vertex -701.693 291.526 52.501 + vertex -701.973 282.105 52.1775 + endloop + endfacet + facet normal -0.781562 -0.00270914 0.623822 + outer loop + vertex -699.95 283.586 54.667 + vertex -701.222 296.393 53.1285 + vertex -701.211 280.439 53.0735 + endloop + endfacet + facet normal -0.79208 -0.005367 0.610394 + outer loop + vertex -700.084 300.707 54.6433 + vertex -701.222 296.393 53.1285 + vertex -699.95 283.586 54.667 + endloop + endfacet + facet normal -0.746872 -0.00296515 0.664962 + outer loop + vertex -701.693 291.526 52.501 + vertex -701.75 304.759 52.4964 + vertex -702.049 296.559 52.1243 + endloop + endfacet + facet normal -0.792997 -0.00470832 0.609208 + outer loop + vertex -700.084 300.707 54.6433 + vertex -701.385 313.001 53.0449 + vertex -701.222 296.393 53.1285 + endloop + endfacet + facet normal -0.805618 -0.00823188 0.592378 + outer loop + vertex -700.268 317.757 54.6297 + vertex -701.385 313.001 53.0449 + vertex -700.084 300.707 54.6433 + endloop + endfacet + facet normal -0.760129 -0.00395019 0.649761 + outer loop + vertex -701.75 304.759 52.4964 + vertex -701.795 313.77 52.4985 + vertex -702.059 311.647 52.1769 + endloop + endfacet + facet normal -0.755595 -0.00531018 0.655017 + outer loop + vertex -701.795 313.77 52.4985 + vertex -701.826 322.083 52.5304 + vertex -702.059 311.647 52.1769 + endloop + endfacet + facet normal -0.807591 -0.00687672 0.589702 + outer loop + vertex -700.268 317.757 54.6297 + vertex -701.533 330.52 53.0462 + vertex -701.385 313.001 53.0449 + endloop + endfacet + facet normal -0.820684 -0.0104592 0.571286 + outer loop + vertex -700.555 334.858 54.5303 + vertex -701.533 330.52 53.0462 + vertex -700.268 317.757 54.6297 + endloop + endfacet + facet normal -0.770842 -0.00615444 0.636996 + outer loop + vertex -701.826 322.083 52.5304 + vertex -701.915 332.714 52.5256 + vertex -702.15 325.534 52.1715 + endloop + endfacet + facet normal -0.792876 -0.0093984 0.60931 + outer loop + vertex -701.915 332.714 52.5256 + vertex -701.943 340.361 52.6067 + vertex -702.188 340.663 52.2923 + endloop + endfacet + facet normal -0.82265 -0.0090544 0.568476 + outer loop + vertex -700.555 334.858 54.5303 + vertex -701.836 348.368 52.8917 + vertex -701.533 330.52 53.0462 + endloop + endfacet + facet normal -0.828383 -0.0106185 0.560061 + outer loop + vertex -701.089 352.05 54.0675 + vertex -701.836 348.368 52.8917 + vertex -700.555 334.858 54.5303 + endloop + endfacet + facet normal -0.854187 -0.0125022 0.519816 + outer loop + vertex -701.089 352.05 54.0675 + vertex -700.555 334.858 54.5303 + vertex -699.596 340.878 56.2519 + endloop + endfacet + facet normal -0.863785 -0.0169599 0.503575 + outer loop + vertex -699.596 340.878 56.2519 + vertex -699.932 354.095 56.12 + vertex -701.089 352.05 54.0675 + endloop + endfacet + facet normal -0.860429 -0.0242931 0.508992 + outer loop + vertex -701.635 368.792 53.943 + vertex -701.089 352.05 54.0675 + vertex -699.932 354.095 56.12 + endloop + endfacet + facet normal -0.887236 -0.034654 0.460012 + outer loop + vertex -699.932 354.095 56.12 + vertex -700.342 368.985 56.4521 + vertex -701.635 368.792 53.943 + endloop + endfacet + facet normal -0.885248 -0.0614162 0.461046 + outer loop + vertex -703.357 386.656 53.016 + vertex -701.635 368.792 53.943 + vertex -700.342 368.985 56.4521 + endloop + endfacet + facet normal -0.883225 -0.0602906 0.465059 + outer loop + vertex -701.478 386.658 56.5844 + vertex -703.357 386.656 53.016 + vertex -700.342 368.985 56.4521 + endloop + endfacet + facet normal -0.854126 -0.0555074 0.517096 + outer loop + vertex -703.357 386.656 53.016 + vertex -703.461 386.656 52.8438 + vertex -701.635 368.792 53.943 + endloop + endfacet + facet normal -0.877149 -0.0250577 0.479564 + outer loop + vertex -701.635 368.792 53.943 + vertex -702.165 365.618 52.8077 + vertex -701.089 352.05 54.0675 + endloop + endfacet + facet normal -0.850179 -0.0149898 0.52628 + outer loop + vertex -699.108 330.883 56.7551 + vertex -699.596 340.878 56.2519 + vertex -700.555 334.858 54.5303 + endloop + endfacet + facet normal -0.850682 -0.0156394 0.525447 + outer loop + vertex -699.131 322.949 56.4825 + vertex -699.108 330.883 56.7551 + vertex -700.555 334.858 54.5303 + endloop + endfacet + facet normal -0.838215 -0.010905 0.54523 + outer loop + vertex -700.555 334.858 54.5303 + vertex -700.268 317.757 54.6297 + vertex -699.131 322.949 56.4825 + endloop + endfacet + facet normal -0.83431 -0.013863 0.551121 + outer loop + vertex -698.755 314.154 56.8297 + vertex -699.131 322.949 56.4825 + vertex -700.268 317.757 54.6297 + endloop + endfacet + facet normal -0.833618 -0.0129197 0.55219 + outer loop + vertex -698.848 306.138 56.5019 + vertex -698.755 314.154 56.8297 + vertex -700.268 317.757 54.6297 + endloop + endfacet + facet normal -0.821138 -0.00841699 0.570668 + outer loop + vertex -700.268 317.757 54.6297 + vertex -700.084 300.707 54.6433 + vertex -698.848 306.138 56.5019 + endloop + endfacet + facet normal -0.81805 -0.0106191 0.575049 + outer loop + vertex -698.513 296.981 56.8094 + vertex -698.848 306.138 56.5019 + vertex -700.084 300.707 54.6433 + endloop + endfacet + facet normal -0.817175 -0.00951672 0.576311 + outer loop + vertex -698.658 288.698 56.4676 + vertex -698.513 296.981 56.8094 + vertex -700.084 300.707 54.6433 + endloop + endfacet + facet normal -0.804983 -0.00549179 0.593272 + outer loop + vertex -700.084 300.707 54.6433 + vertex -699.95 283.586 54.667 + vertex -698.658 288.698 56.4676 + endloop + endfacet + facet normal -0.802769 -0.00709986 0.596248 + outer loop + vertex -698.333 279.259 56.7927 + vertex -698.658 288.698 56.4676 + vertex -699.95 283.586 54.667 + endloop + endfacet + facet normal -0.801738 -0.00602832 0.597646 + outer loop + vertex -698.489 270.908 56.4991 + vertex -698.333 279.259 56.7927 + vertex -699.95 283.586 54.667 + endloop + endfacet + facet normal -0.790665 -0.00264302 0.612243 + outer loop + vertex -699.95 283.586 54.667 + vertex -699.857 266.164 54.7117 + vertex -698.489 270.908 56.4991 + endloop + endfacet + facet normal -0.788496 -0.00431723 0.615025 + outer loop + vertex -698.2 261.474 56.8033 + vertex -698.489 270.908 56.4991 + vertex -699.857 266.164 54.7117 + endloop + endfacet + facet normal -0.785689 -0.00172265 0.61862 + outer loop + vertex -698.401 253.311 56.5245 + vertex -698.2 261.474 56.8033 + vertex -699.857 266.164 54.7117 + endloop + endfacet + facet normal -0.77385 0.00169787 0.633367 + outer loop + vertex -699.857 266.164 54.7117 + vertex -699.868 248.041 54.747 + vertex -698.401 253.311 56.5245 + endloop + endfacet + facet normal -0.772906 0.00104642 0.63452 + outer loop + vertex -698.156 243.929 56.8386 + vertex -698.401 253.311 56.5245 + vertex -699.868 248.041 54.747 + endloop + endfacet + facet normal -0.769541 0.00451315 0.638582 + outer loop + vertex -698.462 235.325 56.5305 + vertex -698.156 243.929 56.8386 + vertex -699.868 248.041 54.747 + endloop + endfacet + facet normal -0.758528 0.00755552 0.651597 + outer loop + vertex -699.868 248.041 54.747 + vertex -700.123 228.073 54.6817 + vertex -698.462 235.325 56.5305 + endloop + endfacet + facet normal -0.76093 0.00882487 0.648774 + outer loop + vertex -698.255 225.804 56.9026 + vertex -698.462 235.325 56.5305 + vertex -700.123 228.073 54.6817 + endloop + endfacet + facet normal -0.760775 0.00912482 0.648951 + outer loop + vertex -698.486 217.617 56.7472 + vertex -698.255 225.804 56.9026 + vertex -700.123 228.073 54.6817 + endloop + endfacet + facet normal -0.76804 0.00629265 0.64037 + outer loop + vertex -698.486 217.617 56.7472 + vertex -700.123 228.073 54.6817 + vertex -699.738 212.23 55.2992 + endloop + endfacet + facet normal -0.768377 0.00648018 0.639964 + outer loop + vertex -698.238 208.888 57.1333 + vertex -698.486 217.617 56.7472 + vertex -699.738 212.23 55.2992 + endloop + endfacet + facet normal -0.778934 -0.00532732 0.627084 + outer loop + vertex -698.238 208.888 57.1333 + vertex -699.738 212.23 55.2992 + vertex -698.608 201.816 56.6139 + endloop + endfacet + facet normal -0.756114 0.000601529 0.65444 + outer loop + vertex -698.608 201.816 56.6139 + vertex -699.738 212.23 55.2992 + vertex -700.307 202.276 54.6505 + endloop + endfacet + facet normal -0.758869 -0.0252982 0.650752 + outer loop + vertex -698.608 201.816 56.6139 + vertex -700.307 202.276 54.6505 + vertex -698.698 192.447 56.1445 + endloop + endfacet + facet normal -0.739535 -0.0187739 0.672856 + outer loop + vertex -698.698 192.447 56.1445 + vertex -700.307 202.276 54.6505 + vertex -700.397 192.301 54.2729 + endloop + endfacet + facet normal -0.737126 -0.0551014 0.673505 + outer loop + vertex -698.698 192.447 56.1445 + vertex -700.397 192.301 54.2729 + vertex -698.531 182.701 55.5298 + endloop + endfacet + facet normal -0.720244 -0.0494035 0.69196 + outer loop + vertex -698.531 182.701 55.5298 + vertex -700.397 192.301 54.2729 + vertex -700.281 183.931 53.7967 + endloop + endfacet + facet normal -0.79232 -0.00817658 0.610051 + outer loop + vertex -701.943 340.361 52.6067 + vertex -702.025 345.574 52.5705 + vertex -702.188 340.663 52.2923 + endloop + endfacet + facet normal -0.786905 -0.0087512 0.617012 + outer loop + vertex -702.025 345.574 52.5705 + vertex -702.081 349.461 52.5532 + vertex -702.188 340.663 52.2923 + endloop + endfacet + facet normal -0.811179 -0.0103743 0.584706 + outer loop + vertex -702.081 349.461 52.5532 + vertex -702.114 353.565 52.5811 + vertex -702.325 355.157 52.3158 + endloop + endfacet + facet normal -0.808016 -0.00922404 0.589089 + outer loop + vertex -702.114 353.565 52.5811 + vertex -702.164 358.073 52.582 + vertex -702.325 355.157 52.3158 + endloop + endfacet + facet normal -0.824874 -0.0129615 0.565168 + outer loop + vertex -701.089 352.05 54.0675 + vertex -702.165 365.618 52.8077 + vertex -701.836 348.368 52.8917 + endloop + endfacet + facet normal -0.814179 -0.00810548 0.580558 + outer loop + vertex -702.164 358.073 52.582 + vertex -702.283 364.292 52.5033 + vertex -702.325 355.157 52.3158 + endloop + endfacet + facet normal -0.655957 -0.00699694 0.754766 + outer loop + vertex -702.283 364.292 52.5033 + vertex -702.347 369.244 52.4929 + vertex -702.609 370.322 52.2758 + endloop + endfacet + facet normal -0.69981 -0.0258616 0.713861 + outer loop + vertex -702.347 369.244 52.4929 + vertex -702.543 374.838 52.5041 + vertex -702.609 370.322 52.2758 + endloop + endfacet + facet normal -0.840251 -0.0527022 0.53963 + outer loop + vertex -701.635 368.792 53.943 + vertex -703.461 386.656 52.8438 + vertex -702.165 365.618 52.8077 + endloop + endfacet + facet normal -0.629565 -0.0300458 0.776367 + outer loop + vertex -702.543 374.838 52.5041 + vertex -702.875 381.06 52.4755 + vertex -702.609 370.322 52.2758 + endloop + endfacet + facet normal -0.704009 -0.0112792 0.710101 + outer loop + vertex -702.609 370.322 52.2758 + vertex -702.325 355.157 52.3158 + vertex -702.283 364.292 52.5033 + endloop + endfacet + facet normal -0.792104 -0.00848981 0.610327 + outer loop + vertex -702.325 355.157 52.3158 + vertex -702.188 340.663 52.2923 + vertex -702.081 349.461 52.5532 + endloop + endfacet + facet normal -0.760431 -0.00710611 0.64938 + outer loop + vertex -702.188 340.663 52.2923 + vertex -702.15 325.534 52.1715 + vertex -701.915 332.714 52.5256 + endloop + endfacet + facet normal -0.764468 -0.00476063 0.644644 + outer loop + vertex -702.15 325.534 52.1715 + vertex -702.059 311.647 52.1769 + vertex -701.826 322.083 52.5304 + endloop + endfacet + facet normal -0.748577 -0.00281588 0.663042 + outer loop + vertex -702.059 311.647 52.1769 + vertex -702.049 296.559 52.1243 + vertex -701.75 304.759 52.4964 + endloop + endfacet + facet normal -0.736292 -0.00134233 0.676662 + outer loop + vertex -702.049 296.559 52.1243 + vertex -701.973 282.105 52.1775 + vertex -701.693 291.526 52.501 + endloop + endfacet + facet normal -0.702702 0.00166178 0.711483 + outer loop + vertex -701.973 282.105 52.1775 + vertex -702.024 267.608 52.1613 + vertex -701.624 274.247 52.5407 + endloop + endfacet + facet normal -0.668534 0.00552799 0.743661 + outer loop + vertex -702.024 267.608 52.1613 + vertex -702.073 253.97 52.2185 + vertex -701.655 263.709 52.5217 + endloop + endfacet + facet normal -0.626127 0.00927876 0.779666 + outer loop + vertex -702.073 253.97 52.2185 + vertex -702.3 239.542 52.2084 + vertex -701.778 247.845 52.5285 + endloop + endfacet + facet normal -0.651065 0.0117218 0.758931 + outer loop + vertex -702.3 239.542 52.2084 + vertex -702.575 224.518 52.2042 + vertex -701.987 234.424 52.5558 + endloop + endfacet + facet normal -0.666667 0.013134 0.74524 + outer loop + vertex -702.167 226.41 52.536 + vertex -701.987 234.424 52.5558 + vertex -702.575 224.518 52.2042 + endloop + endfacet + facet normal -0.665144 0.0125653 0.74661 + outer loop + vertex -702.353 218.141 52.5097 + vertex -702.167 226.41 52.536 + vertex -702.575 224.518 52.2042 + endloop + endfacet + facet normal -0.705977 0.0136048 0.708104 + outer loop + vertex -702.167 226.41 52.536 + vertex -702.353 218.141 52.5097 + vertex -701.779 225.153 52.947 + endloop + endfacet + facet normal -0.705208 0.0140894 0.70886 + outer loop + vertex -701.987 234.424 52.5558 + vertex -702.167 226.41 52.536 + vertex -701.779 225.153 52.947 + endloop + endfacet + facet normal -0.712695 0.0087424 0.701419 + outer loop + vertex -702.575 224.518 52.2042 + vertex -702.765 209.668 52.1965 + vertex -702.353 218.141 52.5097 + endloop + endfacet + facet normal -0.788182 0.0155993 0.615244 + outer loop + vertex -702.512 210.985 52.4866 + vertex -702.353 218.141 52.5097 + vertex -702.765 209.668 52.1965 + endloop + endfacet + facet normal -0.765016 0.00482383 0.643994 + outer loop + vertex -702.595 205.36 52.4302 + vertex -702.512 210.985 52.4866 + vertex -702.765 209.668 52.1965 + endloop + endfacet + facet normal -0.595379 0.000723115 0.803445 + outer loop + vertex -702.512 210.985 52.4866 + vertex -702.595 205.36 52.4302 + vertex -702.294 207.259 52.6513 + endloop + endfacet + facet normal -0.506514 0.00851658 0.86219 + outer loop + vertex -702.353 218.141 52.5097 + vertex -702.512 210.985 52.4866 + vertex -702.294 207.259 52.6513 + endloop + endfacet + facet normal -0.654104 0.00635019 0.756378 + outer loop + vertex -702.294 207.259 52.6513 + vertex -701.779 225.153 52.947 + vertex -702.353 218.141 52.5097 + endloop + endfacet + facet normal -0.571816 -0.0709388 0.817309 + outer loop + vertex -702.872 176.925 50.7282 + vertex -702.782 186.172 51.5936 + vertex -703.385 184.078 50.9901 + endloop + endfacet +endsolid diff --git a/noether_examples/meshes/outputs/output_22.stl b/noether_examples/meshes/outputs/output_22.stl new file mode 100644 index 00000000..026d12f2 --- /dev/null +++ b/noether_examples/meshes/outputs/output_22.stl @@ -0,0 +1,6057 @@ +solid ascii + facet normal 0.940719 -0.0617504 -0.333518 + outer loop + vertex 688.375 185.808 269.442 + vertex 689.152 193.334 270.241 + vertex 689.5 184.908 272.783 + endloop + endfacet + facet normal 0.941812 -0.0608227 -0.330592 + outer loop + vertex 689.5 184.908 272.783 + vertex 689.152 193.334 270.241 + vertex 690.157 194.286 272.928 + endloop + endfacet + facet normal 0.940579 -0.0412647 -0.337058 + outer loop + vertex 689.152 193.334 270.241 + vertex 689.229 202.379 269.347 + vertex 690.157 194.286 272.928 + endloop + endfacet + facet normal 0.948164 -0.0311872 -0.316249 + outer loop + vertex 690.157 194.286 272.928 + vertex 689.229 202.379 269.347 + vertex 690.45 203.415 272.906 + endloop + endfacet + facet normal 0.947094 -0.0149411 -0.320608 + outer loop + vertex 689.229 202.379 269.347 + vertex 689.416 210.642 269.515 + vertex 690.45 203.415 272.906 + endloop + endfacet + facet normal 0.953059 -0.00570016 -0.302731 + outer loop + vertex 690.45 203.415 272.906 + vertex 689.416 210.642 269.515 + vertex 690.482 212.124 272.844 + endloop + endfacet + facet normal 0.952549 -0.00162209 -0.304382 + outer loop + vertex 689.416 210.642 269.515 + vertex 689.16 219.992 268.664 + vertex 690.482 212.124 272.844 + endloop + endfacet + facet normal 0.95821 0.00913775 -0.28592 + outer loop + vertex 690.482 212.124 272.844 + vertex 689.16 219.992 268.664 + vertex 690.386 220.619 272.794 + endloop + endfacet + facet normal 0.958198 0.00937734 -0.285952 + outer loop + vertex 689.16 219.992 268.664 + vertex 689.262 228.594 269.288 + vertex 690.386 220.619 272.794 + endloop + endfacet + facet normal 0.956999 0.00742971 -0.289998 + outer loop + vertex 690.386 220.619 272.794 + vertex 689.262 228.594 269.288 + vertex 690.282 229.411 272.675 + endloop + endfacet + facet normal 0.958071 -0.0088441 -0.286394 + outer loop + vertex 689.262 228.594 269.288 + vertex 689.041 238.851 268.233 + vertex 690.282 229.411 272.675 + endloop + endfacet + facet normal 0.960509 -0.00467244 -0.27821 + outer loop + vertex 690.282 229.411 272.675 + vertex 689.041 238.851 268.233 + vertex 690.313 239.102 272.62 + endloop + endfacet + facet normal 0.960569 -0.0162761 -0.277564 + outer loop + vertex 689.041 238.851 268.233 + vertex 689.302 251.575 268.39 + vertex 690.313 239.102 272.62 + endloop + endfacet + facet normal 0.959839 -0.0171698 -0.280024 + outer loop + vertex 690.313 239.102 272.62 + vertex 689.302 251.575 268.39 + vertex 690.738 248.586 273.495 + endloop + endfacet + facet normal 0.95819 -0.0263239 -0.284921 + outer loop + vertex 689.302 251.575 268.39 + vertex 690.361 265.3 270.681 + vertex 690.738 248.586 273.495 + endloop + endfacet + facet normal 0.945811 -0.0330202 -0.323034 + outer loop + vertex 691.743 253.322 275.952 + vertex 690.738 248.586 273.495 + vertex 690.361 265.3 270.681 + endloop + endfacet + facet normal 0.954988 -0.020048 -0.295965 + outer loop + vertex 691.952 261.547 276.071 + vertex 691.743 253.322 275.952 + vertex 690.361 265.3 270.681 + endloop + endfacet + facet normal 0.954844 -0.0207133 -0.296385 + outer loop + vertex 691.952 261.547 276.071 + vertex 690.361 265.3 270.681 + vertex 691.925 271.221 275.306 + endloop + endfacet + facet normal 0.957857 -0.0298649 -0.285689 + outer loop + vertex 690.361 265.3 270.681 + vertex 690.93 284.797 270.552 + vertex 691.925 271.221 275.306 + endloop + endfacet + facet normal 0.96017 -0.027039 -0.278105 + outer loop + vertex 692.363 279.731 275.991 + vertex 691.925 271.221 275.306 + vertex 690.93 284.797 270.552 + endloop + endfacet + facet normal 0.960439 -0.0260654 -0.277269 + outer loop + vertex 692.363 279.731 275.991 + vertex 690.93 284.797 270.552 + vertex 692.419 289.12 275.302 + endloop + endfacet + facet normal 0.961997 -0.0334896 -0.271 + outer loop + vertex 690.93 284.797 270.552 + vertex 691.477 302.385 270.318 + vertex 692.419 289.12 275.302 + endloop + endfacet + facet normal 0.96413 -0.0305814 -0.263662 + outer loop + vertex 692.84 297.226 275.903 + vertex 692.419 289.12 275.302 + vertex 691.477 302.385 270.318 + endloop + endfacet + facet normal 0.963772 -0.0319192 -0.26481 + outer loop + vertex 692.84 297.226 275.903 + vertex 691.477 302.385 270.318 + vertex 692.897 307.226 274.903 + endloop + endfacet + facet normal 0.96567 -0.0402163 -0.256638 + outer loop + vertex 691.477 302.385 270.318 + vertex 691.893 319.149 269.257 + vertex 692.897 307.226 274.903 + endloop + endfacet + facet normal 0.965541 -0.040441 -0.25709 + outer loop + vertex 693.449 319.462 275.055 + vertex 692.897 307.226 274.903 + vertex 691.893 319.149 269.257 + endloop + endfacet + facet normal 0.965398 -0.0455375 -0.256776 + outer loop + vertex 691.893 319.149 269.257 + vertex 692.66 334.359 269.445 + vertex 693.449 319.462 275.055 + endloop + endfacet + facet normal 0.961911 -0.0502158 -0.268709 + outer loop + vertex 693.449 319.462 275.055 + vertex 692.66 334.359 269.445 + vertex 694.723 332.752 277.13 + endloop + endfacet + facet normal 0.962242 -0.0469473 -0.268115 + outer loop + vertex 692.66 334.359 269.445 + vertex 693.525 350.836 269.663 + vertex 694.723 332.752 277.13 + endloop + endfacet + facet normal 0.968413 -0.037612 -0.246498 + outer loop + vertex 694.723 332.752 277.13 + vertex 693.525 350.836 269.663 + vertex 695.193 351.916 276.051 + endloop + endfacet + facet normal 0.968289 -0.0578784 -0.243037 + outer loop + vertex 693.525 350.836 269.663 + vertex 694.586 368.527 269.68 + vertex 695.193 351.916 276.051 + endloop + endfacet + facet normal 0.970548 -0.0545774 -0.234646 + outer loop + vertex 695.193 351.916 276.051 + vertex 694.586 368.527 269.68 + vertex 696.17 368.893 276.147 + endloop + endfacet + facet normal 0.969132 -0.0811838 -0.232792 + outer loop + vertex 694.586 368.527 269.68 + vertex 696.156 386.593 269.914 + vertex 696.17 368.893 276.147 + endloop + endfacet + facet normal 0.975733 -0.0720194 -0.206779 + outer loop + vertex 696.17 368.893 276.147 + vertex 696.156 386.593 269.914 + vertex 697.594 386.626 276.689 + endloop + endfacet + facet normal 0.936646 -0.0171581 -0.349858 + outer loop + vertex 691.941 244.42 276.919 + vertex 690.738 248.586 273.495 + vertex 691.743 253.322 275.952 + endloop + endfacet + facet normal 0.94036 -0.00805167 -0.340085 + outer loop + vertex 691.684 237.704 276.368 + vertex 690.738 248.586 273.495 + vertex 691.941 244.42 276.919 + endloop + endfacet + facet normal 0.937893 -0.0100334 -0.346779 + outer loop + vertex 690.313 239.102 272.62 + vertex 690.738 248.586 273.495 + vertex 691.684 237.704 276.368 + endloop + endfacet + facet normal 0.939031 -0.00102157 -0.343832 + outer loop + vertex 691.612 229.058 276.197 + vertex 690.313 239.102 272.62 + vertex 691.684 237.704 276.368 + endloop + endfacet + facet normal 0.93534 -0.00501696 -0.353714 + outer loop + vertex 690.282 229.411 272.675 + vertex 690.313 239.102 272.62 + vertex 691.612 229.058 276.197 + endloop + endfacet + facet normal 0.935718 0.00665885 -0.352685 + outer loop + vertex 691.699 220.382 276.264 + vertex 690.282 229.411 272.675 + vertex 691.612 229.058 276.197 + endloop + endfacet + facet normal 0.935435 0.00631379 -0.353441 + outer loop + vertex 690.386 220.619 272.794 + vertex 690.282 229.411 272.675 + vertex 691.699 220.382 276.264 + endloop + endfacet + facet normal 0.935481 0.0093025 -0.353254 + outer loop + vertex 691.805 211.973 276.323 + vertex 690.386 220.619 272.794 + vertex 691.699 220.382 276.264 + endloop + endfacet + facet normal 0.934816 0.0084683 -0.355031 + outer loop + vertex 690.482 212.124 272.844 + vertex 690.386 220.619 272.794 + vertex 691.805 211.973 276.323 + endloop + endfacet + facet normal 0.934695 -0.00221083 -0.355445 + outer loop + vertex 691.777 203.377 276.303 + vertex 690.482 212.124 272.844 + vertex 691.805 211.973 276.323 + endloop + endfacet + facet normal 0.931404 -0.00605641 -0.363937 + outer loop + vertex 690.45 203.415 272.906 + vertex 690.482 212.124 272.844 + vertex 691.777 203.377 276.303 + endloop + endfacet + facet normal 0.930995 -0.0272682 -0.364012 + outer loop + vertex 691.475 194.187 276.219 + vertex 690.45 203.415 272.906 + vertex 691.777 203.377 276.303 + endloop + endfacet + facet normal 0.927566 -0.0306599 -0.372399 + outer loop + vertex 690.157 194.286 272.928 + vertex 690.45 203.415 272.906 + vertex 691.475 194.187 276.219 + endloop + endfacet + facet normal 0.926164 -0.0578707 -0.372654 + outer loop + vertex 690.813 184.439 276.087 + vertex 690.157 194.286 272.928 + vertex 691.475 194.187 276.219 + endloop + endfacet + facet normal 0.924861 -0.0589384 -0.375711 + outer loop + vertex 689.5 184.908 272.783 + vertex 690.157 194.286 272.928 + vertex 690.813 184.439 276.087 + endloop + endfacet + facet normal 0.951705 -0.0381522 -0.304634 + outer loop + vertex 689.152 193.334 270.241 + vertex 688.248 196.733 266.99 + vertex 689.229 202.379 269.347 + endloop + endfacet + facet normal 0.952582 -0.0395279 -0.301703 + outer loop + vertex 689.229 202.379 269.347 + vertex 688.248 196.733 266.99 + vertex 687.813 212.315 263.574 + endloop + endfacet + facet normal 0.96415 -0.016466 -0.264848 + outer loop + vertex 689.416 210.642 269.515 + vertex 689.229 202.379 269.347 + vertex 687.813 212.315 263.574 + endloop + endfacet + facet normal 0.96565 0.00279315 -0.259832 + outer loop + vertex 689.416 210.642 269.515 + vertex 687.813 212.315 263.574 + vertex 689.16 219.992 268.664 + endloop + endfacet + facet normal 0.969497 -0.00772667 -0.244982 + outer loop + vertex 687.813 212.315 263.574 + vertex 687.95 233.672 263.444 + vertex 689.16 219.992 268.664 + endloop + endfacet + facet normal 0.976453 0.00406359 -0.215692 + outer loop + vertex 689.262 228.594 269.288 + vertex 689.16 219.992 268.664 + vertex 687.95 233.672 263.444 + endloop + endfacet + facet normal 0.975396 -0.00168695 -0.220452 + outer loop + vertex 689.262 228.594 269.288 + vertex 687.95 233.672 263.444 + vertex 689.041 238.851 268.233 + endloop + endfacet + facet normal 0.9776 -0.0116783 -0.210148 + outer loop + vertex 687.95 233.672 263.444 + vertex 687.934 251.482 262.38 + vertex 689.041 238.851 268.233 + endloop + endfacet + facet normal 0.974962 -0.017262 -0.221699 + outer loop + vertex 689.302 251.575 268.39 + vertex 689.041 238.851 268.233 + vertex 687.934 251.482 262.38 + endloop + endfacet + facet normal 0.974788 -0.0268685 -0.221511 + outer loop + vertex 687.934 251.482 262.38 + vertex 688.418 267.164 262.608 + vertex 689.302 251.575 268.39 + endloop + endfacet + facet normal 0.969832 -0.0344976 -0.241323 + outer loop + vertex 689.302 251.575 268.39 + vertex 688.418 267.164 262.608 + vertex 690.361 265.3 270.681 + endloop + endfacet + facet normal 0.969739 -0.0355507 -0.241543 + outer loop + vertex 688.418 267.164 262.608 + vertex 689.128 283.871 262.999 + vertex 690.361 265.3 270.681 + endloop + endfacet + facet normal 0.973085 -0.0299311 -0.228495 + outer loop + vertex 690.361 265.3 270.681 + vertex 689.128 283.871 262.999 + vertex 690.93 284.797 270.552 + endloop + endfacet + facet normal 0.973022 -0.0395187 -0.227304 + outer loop + vertex 689.128 283.871 262.999 + vertex 689.832 301.267 262.99 + vertex 690.93 284.797 270.552 + endloop + endfacet + facet normal 0.976278 -0.0331775 -0.213965 + outer loop + vertex 690.93 284.797 270.552 + vertex 689.832 301.267 262.99 + vertex 691.477 302.385 270.318 + endloop + endfacet + facet normal 0.976221 -0.0433361 -0.212402 + outer loop + vertex 689.832 301.267 262.99 + vertex 690.53 318.121 262.755 + vertex 691.477 302.385 270.318 + endloop + endfacet + facet normal 0.979211 -0.0369326 -0.199453 + outer loop + vertex 691.477 302.385 270.318 + vertex 690.53 318.121 262.755 + vertex 691.893 319.149 269.257 + endloop + endfacet + facet normal 0.979103 -0.0472741 -0.197795 + outer loop + vertex 690.53 318.121 262.755 + vertex 691.283 334.51 262.566 + vertex 691.893 319.149 269.257 + endloop + endfacet + facet normal 0.979253 -0.0469737 -0.19712 + outer loop + vertex 691.893 319.149 269.257 + vertex 691.283 334.51 262.566 + vertex 692.66 334.359 269.445 + endloop + endfacet + facet normal 0.978995 -0.0518782 -0.197176 + outer loop + vertex 691.283 334.51 262.566 + vertex 692.167 351.048 262.603 + vertex 692.66 334.359 269.445 + endloop + endfacet + facet normal 0.98054 -0.0489401 -0.190121 + outer loop + vertex 692.66 334.359 269.445 + vertex 692.167 351.048 262.603 + vertex 693.525 350.836 269.663 + endloop + endfacet + facet normal 0.979667 -0.0633001 -0.190385 + outer loop + vertex 692.167 351.048 262.603 + vertex 693.318 368.392 262.762 + vertex 693.525 350.836 269.663 + endloop + endfacet + facet normal 0.982106 -0.0587669 -0.178926 + outer loop + vertex 693.525 350.836 269.663 + vertex 693.318 368.392 262.762 + vertex 694.586 368.527 269.68 + endloop + endfacet + facet normal 0.979787 -0.0915648 -0.17786 + outer loop + vertex 693.318 368.392 262.762 + vertex 695.086 386.556 263.152 + vertex 694.586 368.527 269.68 + endloop + endfacet + facet normal 0.984336 -0.0835117 -0.155269 + outer loop + vertex 694.586 368.527 269.68 + vertex 695.086 386.556 263.152 + vertex 696.156 386.593 269.914 + endloop + endfacet + facet normal 0.962172 -0.0324223 -0.270508 + outer loop + vertex 687.346 197.028 263.746 + vertex 687.813 212.315 263.574 + vertex 688.248 196.733 266.99 + endloop + endfacet + facet normal 0.960551 -0.0566773 -0.272268 + outer loop + vertex 687.394 186.875 266.028 + vertex 687.346 197.028 263.746 + vertex 688.248 196.733 266.99 + endloop + endfacet + facet normal 0.955023 -0.0543198 -0.291515 + outer loop + vertex 687.394 186.875 266.028 + vertex 688.248 196.733 266.99 + vertex 688.375 185.808 269.442 + endloop + endfacet + facet normal 0.96672 -0.0517663 -0.250546 + outer loop + vertex 686.55 187.836 262.574 + vertex 687.346 197.028 263.746 + vertex 687.394 186.875 266.028 + endloop + endfacet + facet normal 0.971249 -0.0545575 -0.231732 + outer loop + vertex 686.55 187.836 262.574 + vertex 686.612 200.041 259.96 + vertex 687.346 197.028 263.746 + endloop + endfacet + facet normal 0.977045 -0.0493424 -0.20724 + outer loop + vertex 685.856 188.937 259.039 + vertex 686.612 200.041 259.96 + vertex 686.55 187.836 262.574 + endloop + endfacet + facet normal 0.982137 -0.0518754 -0.180875 + outer loop + vertex 685.856 188.937 259.039 + vertex 685.904 199.292 256.334 + vertex 686.612 200.041 259.96 + endloop + endfacet + facet normal 0.982221 -0.03236 -0.184921 + outer loop + vertex 685.904 199.292 256.334 + vertex 686.095 214.002 254.772 + vertex 686.612 200.041 259.96 + endloop + endfacet + facet normal 0.979425 -0.0374372 -0.198304 + outer loop + vertex 686.095 214.002 254.772 + vertex 687.813 212.315 263.574 + vertex 686.612 200.041 259.96 + endloop + endfacet + facet normal 0.980932 -0.013014 -0.193916 + outer loop + vertex 686.095 214.002 254.772 + vertex 686.53 233.006 255.699 + vertex 687.813 212.315 263.574 + endloop + endfacet + facet normal 0.983699 -0.00742076 -0.17967 + outer loop + vertex 687.813 212.315 263.574 + vertex 686.53 233.006 255.699 + vertex 687.95 233.672 263.444 + endloop + endfacet + facet normal 0.983726 -0.0123637 -0.17925 + outer loop + vertex 686.53 233.006 255.699 + vertex 686.756 251.033 255.692 + vertex 687.95 233.672 263.444 + endloop + endfacet + facet normal 0.984895 -0.00944533 -0.172896 + outer loop + vertex 687.95 233.672 263.444 + vertex 686.756 251.033 255.692 + vertex 687.934 251.482 262.38 + endloop + endfacet + facet normal 0.984818 -0.0242531 -0.171889 + outer loop + vertex 686.756 251.033 255.692 + vertex 687.137 267.805 255.51 + vertex 687.934 251.482 262.38 + endloop + endfacet + facet normal 0.983279 -0.0277351 -0.179983 + outer loop + vertex 687.934 251.482 262.38 + vertex 687.137 267.805 255.51 + vertex 688.418 267.164 262.608 + endloop + endfacet + facet normal 0.982841 -0.0368698 -0.18073 + outer loop + vertex 687.137 267.805 255.51 + vertex 687.763 284.333 255.542 + vertex 688.418 267.164 262.608 + endloop + endfacet + facet normal 0.982548 -0.0374828 -0.182192 + outer loop + vertex 688.418 267.164 262.608 + vertex 687.763 284.333 255.542 + vertex 689.128 283.871 262.999 + endloop + endfacet + facet normal 0.982181 -0.0446116 -0.182567 + outer loop + vertex 687.763 284.333 255.542 + vertex 688.538 301.169 255.598 + vertex 689.128 283.871 262.999 + endloop + endfacet + facet normal 0.984316 -0.0399461 -0.171832 + outer loop + vertex 689.128 283.871 262.999 + vertex 688.538 301.169 255.598 + vertex 689.832 301.267 262.99 + endloop + endfacet + facet normal 0.983955 -0.048656 -0.171653 + outer loop + vertex 688.538 301.169 255.598 + vertex 689.367 317.983 255.584 + vertex 689.832 301.267 262.99 + endloop + endfacet + facet normal 0.986331 -0.0430126 -0.159065 + outer loop + vertex 689.832 301.267 262.99 + vertex 689.367 317.983 255.584 + vertex 690.53 318.121 262.755 + endloop + endfacet + facet normal 0.985946 -0.0517989 -0.158833 + outer loop + vertex 689.367 317.983 255.584 + vertex 690.231 334.597 255.531 + vertex 690.53 318.121 262.755 + endloop + endfacet + facet normal 0.987835 -0.0471031 -0.148202 + outer loop + vertex 690.53 318.121 262.755 + vertex 690.231 334.597 255.531 + vertex 691.283 334.51 262.566 + endloop + endfacet + facet normal 0.987389 -0.0555625 -0.14824 + outer loop + vertex 690.231 334.597 255.531 + vertex 691.166 351.292 255.5 + vertex 691.283 334.51 262.566 + endloop + endfacet + facet normal 0.988611 -0.0525186 -0.141031 + outer loop + vertex 691.283 334.51 262.566 + vertex 691.166 351.292 255.5 + vertex 692.167 351.048 262.603 + endloop + endfacet + facet normal 0.987574 -0.068509 -0.141435 + outer loop + vertex 691.166 351.292 255.5 + vertex 692.374 368.509 255.594 + vertex 692.167 351.048 262.603 + endloop + endfacet + facet normal 0.989238 -0.0644762 -0.13134 + outer loop + vertex 692.167 351.048 262.603 + vertex 692.374 368.509 255.594 + vertex 693.318 368.392 262.762 + endloop + endfacet + facet normal 0.986378 -0.0987899 -0.131527 + outer loop + vertex 692.374 368.509 255.594 + vertex 694.252 386.515 256.158 + vertex 693.318 368.392 262.762 + endloop + endfacet + facet normal 0.988662 -0.093729 -0.117316 + outer loop + vertex 693.318 368.392 262.762 + vertex 694.252 386.515 256.158 + vertex 695.086 386.556 263.152 + endloop + endfacet + facet normal 0.991048 -0.10065 -0.0877068 + outer loop + vertex 692.374 368.509 255.594 + vertex 693.58 386.47 248.615 + vertex 694.252 386.515 256.158 + endloop + endfacet + facet normal 0.990097 -0.103401 -0.0949519 + outer loop + vertex 691.701 368.726 248.346 + vertex 693.58 386.47 248.615 + vertex 692.374 368.509 255.594 + endloop + endfacet + facet normal 0.992431 -0.104101 -0.0651389 + outer loop + vertex 691.701 368.726 248.346 + vertex 693.089 386.426 241.196 + vertex 693.58 386.47 248.615 + endloop + endfacet + facet normal 0.991837 -0.106231 -0.0705254 + outer loop + vertex 691.217 369 241.115 + vertex 693.089 386.426 241.196 + vertex 691.701 368.726 248.346 + endloop + endfacet + facet normal 0.994933 -0.0726911 -0.069461 + outer loop + vertex 690.456 351.705 248.313 + vertex 691.217 369 241.115 + vertex 691.701 368.726 248.346 + endloop + endfacet + facet normal 0.99212 -0.072422 -0.102241 + outer loop + vertex 690.456 351.705 248.313 + vertex 691.701 368.726 248.346 + vertex 691.166 351.292 255.5 + endloop + endfacet + facet normal 0.994113 -0.0759191 -0.0773038 + outer loop + vertex 689.93 352.226 241.047 + vertex 691.217 369 241.115 + vertex 690.456 351.705 248.313 + endloop + endfacet + facet normal 0.995257 -0.0603855 -0.0762713 + outer loop + vertex 689.446 335.076 248.305 + vertex 689.93 352.226 241.047 + vertex 690.456 351.705 248.313 + endloop + endfacet + facet normal 0.99191 -0.0601648 -0.11178 + outer loop + vertex 689.446 335.076 248.305 + vertex 690.456 351.705 248.313 + vertex 690.231 334.597 255.531 + endloop + endfacet + facet normal 0.994564 -0.0631327 -0.0828093 + outer loop + vertex 688.883 335.77 241.01 + vertex 689.93 352.226 241.047 + vertex 689.446 335.076 248.305 + endloop + endfacet + facet normal 0.995 -0.0566904 -0.08223 + outer loop + vertex 688.501 318.515 248.284 + vertex 688.883 335.77 241.01 + vertex 689.446 335.076 248.305 + endloop + endfacet + facet normal 0.990963 -0.0564105 -0.121701 + outer loop + vertex 688.501 318.515 248.284 + vertex 689.446 335.076 248.305 + vertex 689.367 317.983 255.584 + endloop + endfacet + facet normal 0.994323 -0.059265 -0.0883733 + outer loop + vertex 687.903 319.377 240.98 + vertex 688.883 335.77 241.01 + vertex 688.501 318.515 248.284 + endloop + endfacet + facet normal 0.994738 -0.0530107 -0.0876689 + outer loop + vertex 687.613 301.891 248.268 + vertex 687.903 319.377 240.98 + vertex 688.501 318.515 248.284 + endloop + endfacet + facet normal 0.9901 -0.0527224 -0.130084 + outer loop + vertex 687.613 301.891 248.268 + vertex 688.501 318.515 248.284 + vertex 688.538 301.169 255.598 + endloop + endfacet + facet normal 0.990563 -0.0451768 -0.129399 + outer loop + vertex 687.763 284.333 255.542 + vertex 687.613 301.891 248.268 + vertex 688.538 301.169 255.598 + endloop + endfacet + facet normal 0.989738 -0.0474209 -0.134799 + outer loop + vertex 686.821 285.293 248.291 + vertex 687.613 301.891 248.268 + vertex 687.763 284.333 255.542 + endloop + endfacet + facet normal 0.990345 -0.0372437 -0.13353 + outer loop + vertex 687.137 267.805 255.51 + vertex 686.821 285.293 248.291 + vertex 687.763 284.333 255.542 + endloop + endfacet + facet normal 0.990263 -0.0374695 -0.134074 + outer loop + vertex 686.206 268.735 248.372 + vertex 686.821 285.293 248.291 + vertex 687.137 267.805 255.51 + endloop + endfacet + facet normal 0.990907 -0.0239647 -0.132399 + outer loop + vertex 686.756 251.033 255.692 + vertex 686.206 268.735 248.372 + vertex 687.137 267.805 255.51 + endloop + endfacet + facet normal 0.990488 -0.0251681 -0.135277 + outer loop + vertex 685.777 251.83 248.38 + vertex 686.206 268.735 248.372 + vertex 686.756 251.033 255.692 + endloop + endfacet + facet normal 0.990911 -0.0124341 -0.133945 + outer loop + vertex 686.53 233.006 255.699 + vertex 685.777 251.83 248.38 + vertex 686.756 251.033 255.692 + endloop + endfacet + facet normal 0.990036 -0.0148364 -0.140034 + outer loop + vertex 685.461 234.155 248.019 + vertex 685.777 251.83 248.38 + vertex 686.53 233.006 255.699 + endloop + endfacet + facet normal 0.989999 -0.0158444 -0.140179 + outer loop + vertex 686.095 214.002 254.772 + vertex 685.461 234.155 248.019 + vertex 686.53 233.006 255.699 + endloop + endfacet + facet normal 0.990925 -0.013652 -0.133724 + outer loop + vertex 685.098 215.714 247.212 + vertex 685.461 234.155 248.019 + vertex 686.095 214.002 254.772 + endloop + endfacet + facet normal 0.99003 -0.0307156 -0.13747 + outer loop + vertex 685.098 215.714 247.212 + vertex 686.095 214.002 254.772 + vertex 685.417 202.236 252.518 + endloop + endfacet + facet normal 0.990556 -0.0293114 -0.133935 + outer loop + vertex 684.93 201.247 249.135 + vertex 685.098 215.714 247.212 + vertex 685.417 202.236 252.518 + endloop + endfacet + facet normal 0.990525 -0.0502474 -0.127808 + outer loop + vertex 684.845 191.878 252.155 + vertex 684.93 201.247 249.135 + vertex 685.417 202.236 252.518 + endloop + endfacet + facet normal 0.98556 -0.0487685 -0.162153 + outer loop + vertex 684.845 191.878 252.155 + vertex 685.417 202.236 252.518 + vertex 685.362 191.261 255.487 + endloop + endfacet + facet normal 0.985259 -0.0492225 -0.163836 + outer loop + vertex 685.362 191.261 255.487 + vertex 685.417 202.236 252.518 + vertex 685.904 199.292 256.334 + endloop + endfacet + facet normal 0.988604 -0.0542911 -0.14041 + outer loop + vertex 684.362 192.407 248.551 + vertex 684.93 201.247 249.135 + vertex 684.845 191.878 252.155 + endloop + endfacet + facet normal 0.990572 -0.0554167 -0.125288 + outer loop + vertex 684.362 192.407 248.551 + vertex 684.589 203.964 245.234 + vertex 684.93 201.247 249.135 + endloop + endfacet + facet normal 0.992505 -0.0513253 -0.110902 + outer loop + vertex 683.993 193.408 244.783 + vertex 684.589 203.964 245.234 + vertex 684.362 192.407 248.551 + endloop + endfacet + facet normal 0.994702 -0.0524094 -0.0884362 + outer loop + vertex 683.993 193.408 244.783 + vertex 684.237 203.087 241.795 + vertex 684.589 203.964 245.234 + endloop + endfacet + facet normal 0.995114 -0.0272305 -0.0949006 + outer loop + vertex 684.237 203.087 241.795 + vertex 684.448 217.462 239.881 + vertex 684.589 203.964 245.234 + endloop + endfacet + facet normal 0.995126 -0.0271875 -0.0947924 + outer loop + vertex 684.448 217.462 239.881 + vertex 685.098 215.714 247.212 + vertex 684.589 203.964 245.234 + endloop + endfacet + facet normal 0.995722 -0.0130492 -0.0914743 + outer loop + vertex 684.448 217.462 239.881 + vertex 684.755 235.737 240.623 + vertex 685.098 215.714 247.212 + endloop + endfacet + facet normal 0.997689 -0.0140977 -0.0664714 + outer loop + vertex 684.448 217.462 239.881 + vertex 684.288 237.301 233.28 + vertex 684.755 235.737 240.623 + endloop + endfacet + facet normal 0.997631 -0.0160707 -0.0668878 + outer loop + vertex 684.288 237.301 233.28 + vertex 684.595 254.732 233.666 + vertex 684.755 235.737 240.623 + endloop + endfacet + facet normal 0.997547 -0.0164912 -0.0680343 + outer loop + vertex 684.755 235.737 240.623 + vertex 684.595 254.732 233.666 + vertex 685.072 253.248 241.017 + endloop + endfacet + facet normal 0.995028 -0.0157627 -0.0983378 + outer loop + vertex 684.755 235.737 240.623 + vertex 685.072 253.248 241.017 + vertex 685.461 234.155 248.019 + endloop + endfacet + facet normal 0.997132 -0.027977 -0.0703259 + outer loop + vertex 684.595 254.732 233.666 + vertex 685.07 271.464 233.752 + vertex 685.072 253.248 241.017 + endloop + endfacet + facet normal 0.997329 -0.0269978 -0.067871 + outer loop + vertex 685.072 253.248 241.017 + vertex 685.07 271.464 233.752 + vertex 685.533 270.076 241.099 + endloop + endfacet + facet normal 0.994582 -0.0267634 -0.100453 + outer loop + vertex 685.072 253.248 241.017 + vertex 685.533 270.076 241.099 + vertex 685.777 251.83 248.38 + endloop + endfacet + facet normal 0.996664 -0.0411258 -0.0704984 + outer loop + vertex 685.07 271.464 233.752 + vertex 685.741 287.811 233.696 + vertex 685.533 270.076 241.099 + endloop + endfacet + facet normal 0.996939 -0.0397951 -0.0673029 + outer loop + vertex 685.533 270.076 241.099 + vertex 685.741 287.811 233.696 + vertex 686.186 286.548 241.036 + endloop + endfacet + facet normal 0.994259 -0.0398114 -0.0993198 + outer loop + vertex 685.533 270.076 241.099 + vertex 686.186 286.548 241.036 + vertex 686.206 268.735 248.372 + endloop + endfacet + facet normal 0.996288 -0.0511773 -0.0692217 + outer loop + vertex 685.741 287.811 233.696 + vertex 686.57 304.035 233.637 + vertex 686.186 286.548 241.036 + endloop + endfacet + facet normal 0.996688 -0.0492707 -0.0646951 + outer loop + vertex 686.186 286.548 241.036 + vertex 686.57 304.035 233.637 + vertex 686.994 302.96 240.982 + endloop + endfacet + facet normal 0.994205 -0.0492505 -0.0955581 + outer loop + vertex 686.186 286.548 241.036 + vertex 686.994 302.96 240.982 + vertex 686.821 285.293 248.291 + endloop + endfacet + facet normal 0.996215 -0.0568348 -0.0657744 + outer loop + vertex 686.57 304.035 233.637 + vertex 687.494 320.24 233.627 + vertex 686.994 302.96 240.982 + endloop + endfacet + facet normal 0.996557 -0.055184 -0.0618729 + outer loop + vertex 686.994 302.96 240.982 + vertex 687.494 320.24 233.627 + vertex 687.903 319.377 240.98 + endloop + endfacet + facet normal 0.996198 -0.0606922 -0.0624991 + outer loop + vertex 687.494 320.24 233.627 + vertex 688.483 336.438 233.652 + vertex 687.903 319.377 240.98 + endloop + endfacet + facet normal 0.997167 -0.0607792 -0.0443061 + outer loop + vertex 687.494 320.24 233.627 + vertex 688.183 336.971 226.18 + vertex 688.483 336.438 233.652 + endloop + endfacet + facet normal 0.996822 -0.0659673 -0.0446624 + outer loop + vertex 688.183 336.971 226.18 + vertex 689.25 353.07 226.217 + vertex 688.483 336.438 233.652 + endloop + endfacet + facet normal 0.996914 -0.0654104 -0.043407 + outer loop + vertex 688.483 336.438 233.652 + vertex 689.25 353.07 226.217 + vertex 689.552 352.711 233.693 + endloop + endfacet + facet normal 0.996054 -0.0653119 -0.0600872 + outer loop + vertex 688.483 336.438 233.652 + vertex 689.552 352.711 233.693 + vertex 688.883 335.77 241.01 + endloop + endfacet + facet normal 0.995859 -0.0795323 -0.0440429 + outer loop + vertex 689.25 353.07 226.217 + vertex 690.562 369.447 226.313 + vertex 689.552 352.711 233.693 + endloop + endfacet + facet normal 0.99615 -0.0778809 -0.0402583 + outer loop + vertex 689.552 352.711 233.693 + vertex 690.562 369.447 226.313 + vertex 690.85 369.259 233.792 + endloop + endfacet + facet normal 0.995383 -0.0777241 -0.0563218 + outer loop + vertex 689.552 352.711 233.693 + vertex 690.85 369.259 233.792 + vertex 689.93 352.226 241.047 + endloop + endfacet + facet normal 0.993068 -0.110173 -0.0409508 + outer loop + vertex 690.562 369.447 226.313 + vertex 692.448 386.348 226.575 + vertex 690.85 369.259 233.792 + endloop + endfacet + facet normal 0.993377 -0.108671 -0.0373252 + outer loop + vertex 690.85 369.259 233.792 + vertex 692.448 386.348 226.575 + vertex 692.74 386.388 234.231 + endloop + endfacet + facet normal 0.992688 -0.10818 -0.0535436 + outer loop + vertex 690.85 369.259 233.792 + vertex 692.74 386.388 234.231 + vertex 691.217 369 241.115 + endloop + endfacet + facet normal 0.993463 -0.110403 -0.02901 + outer loop + vertex 690.562 369.447 226.313 + vertex 692.225 386.314 219.067 + vertex 692.448 386.348 226.575 + endloop + endfacet + facet normal 0.993101 -0.112345 -0.033614 + outer loop + vertex 690.317 369.565 218.67 + vertex 692.225 386.314 219.067 + vertex 690.562 369.447 226.313 + endloop + endfacet + facet normal 0.993357 -0.11261 -0.0236848 + outer loop + vertex 690.317 369.565 218.67 + vertex 692.027 386.282 210.918 + vertex 692.225 386.314 219.067 + endloop + endfacet + facet normal 0.993195 -0.11357 -0.0257914 + outer loop + vertex 690.127 369.661 210.949 + vertex 692.027 386.282 210.918 + vertex 690.317 369.565 218.67 + endloop + endfacet + facet normal 0.996483 -0.0798319 -0.0254524 + outer loop + vertex 689.015 353.332 218.602 + vertex 690.127 369.661 210.949 + vertex 690.317 369.565 218.67 + endloop + endfacet + facet normal 0.996248 -0.0797794 -0.0335439 + outer loop + vertex 689.015 353.332 218.602 + vertex 690.317 369.565 218.67 + vertex 689.25 353.07 226.217 + endloop + endfacet + facet normal 0.996339 -0.0808738 -0.0276962 + outer loop + vertex 688.817 353.547 210.872 + vertex 690.127 369.661 210.949 + vertex 689.015 353.332 218.602 + endloop + endfacet + facet normal 0.9974 -0.0666838 -0.027329 + outer loop + vertex 687.947 337.38 218.563 + vertex 688.817 353.547 210.872 + vertex 689.015 353.332 218.602 + endloop + endfacet + facet normal 0.997181 -0.0666518 -0.0344682 + outer loop + vertex 687.947 337.38 218.563 + vertex 689.015 353.332 218.602 + vertex 688.183 336.971 226.18 + endloop + endfacet + facet normal 0.997518 -0.0615426 -0.034204 + outer loop + vertex 687.194 320.957 226.154 + vertex 687.947 337.38 218.563 + vertex 688.183 336.971 226.18 + endloop + endfacet + facet normal 0.997416 -0.0622831 -0.0358164 + outer loop + vertex 686.957 321.536 218.539 + vertex 687.947 337.38 218.563 + vertex 687.194 320.957 226.154 + endloop + endfacet + facet normal 0.997674 -0.0581848 -0.0355129 + outer loop + vertex 686.261 304.952 226.168 + vertex 686.957 321.536 218.539 + vertex 687.194 320.957 226.154 + endloop + endfacet + facet normal 0.997133 -0.0581644 -0.0484015 + outer loop + vertex 686.261 304.952 226.168 + vertex 687.194 320.957 226.154 + vertex 686.57 304.035 233.637 + endloop + endfacet + facet normal 0.997601 -0.058718 -0.0366787 + outer loop + vertex 686.025 305.695 218.556 + vertex 686.957 321.536 218.539 + vertex 686.261 304.952 226.168 + endloop + endfacet + facet normal 0.99799 -0.05212 -0.036047 + outer loop + vertex 685.425 288.899 226.234 + vertex 686.025 305.695 218.556 + vertex 686.261 304.952 226.168 + endloop + endfacet + facet normal 0.997397 -0.0521456 -0.0498068 + outer loop + vertex 685.425 288.899 226.234 + vertex 686.261 304.952 226.168 + vertex 685.741 287.811 233.696 + endloop + endfacet + facet normal 0.9979 -0.0527915 -0.0375229 + outer loop + vertex 685.187 289.798 218.632 + vertex 686.025 305.695 218.556 + vertex 685.425 288.899 226.234 + endloop + endfacet + facet normal 0.998456 -0.0420738 -0.0362729 + outer loop + vertex 684.745 272.687 226.301 + vertex 685.187 289.798 218.632 + vertex 685.425 288.899 226.234 + endloop + endfacet + facet normal 0.997833 -0.0421074 -0.0505557 + outer loop + vertex 684.745 272.687 226.301 + vertex 685.425 288.899 226.234 + vertex 685.07 271.464 233.752 + endloop + endfacet + facet normal 0.998384 -0.0426493 -0.0375608 + outer loop + vertex 684.503 273.722 218.708 + vertex 685.187 289.798 218.632 + vertex 684.745 272.687 226.301 + endloop + endfacet + facet normal 0.998956 -0.0285464 -0.0356568 + outer loop + vertex 684.267 256.055 226.223 + vertex 684.503 273.722 218.708 + vertex 684.745 272.687 226.301 + endloop + endfacet + facet normal 0.998387 -0.0284666 -0.0491181 + outer loop + vertex 684.267 256.055 226.223 + vertex 684.745 272.687 226.301 + vertex 684.595 254.732 233.666 + endloop + endfacet + facet normal 0.998892 -0.0291096 -0.0369831 + outer loop + vertex 684.019 257.216 218.632 + vertex 684.503 273.722 218.708 + vertex 684.267 256.055 226.223 + endloop + endfacet + facet normal 0.999239 -0.0169642 -0.0351362 + outer loop + vertex 683.959 238.725 225.842 + vertex 684.019 257.216 218.632 + vertex 684.267 256.055 226.223 + endloop + endfacet + facet normal 0.998736 -0.0166849 -0.047423 + outer loop + vertex 683.959 238.725 225.842 + vertex 684.267 256.055 226.223 + vertex 684.288 237.301 233.28 + endloop + endfacet + facet normal 0.998806 -0.0137738 -0.0468687 + outer loop + vertex 684.004 219.112 232.572 + vertex 683.959 238.725 225.842 + vertex 684.288 237.301 233.28 + endloop + endfacet + facet normal 0.998893 -0.013185 -0.0451534 + outer loop + vertex 683.687 220.601 225.111 + vertex 683.959 238.725 225.842 + vertex 684.004 219.112 232.572 + endloop + endfacet + facet normal 0.998562 -0.0249097 -0.0474789 + outer loop + vertex 683.687 220.601 225.111 + vertex 684.004 219.112 232.572 + vertex 683.621 207.435 230.646 + endloop + endfacet + facet normal 0.998542 -0.0250495 -0.0478117 + outer loop + vertex 683.429 206.411 227.154 + vertex 683.687 220.601 225.111 + vertex 683.621 207.435 230.646 + endloop + endfacet + facet normal 0.99783 -0.052517 -0.0397236 + outer loop + vertex 683.049 196.906 230.198 + vertex 683.429 206.411 227.154 + vertex 683.621 207.435 230.646 + endloop + endfacet + facet normal 0.996867 -0.0516043 -0.0599514 + outer loop + vertex 683.049 196.906 230.198 + vertex 683.621 207.435 230.646 + vertex 683.229 196.093 233.882 + endloop + endfacet + facet normal 0.995889 -0.0549994 -0.0719702 + outer loop + vertex 683.229 196.093 233.882 + vertex 683.621 207.435 230.646 + vertex 683.76 204.825 234.552 + endloop + endfacet + facet normal 0.995998 -0.0551302 -0.070351 + outer loop + vertex 683.229 196.093 233.882 + vertex 683.76 204.825 234.552 + vertex 683.438 195.259 237.495 + endloop + endfacet + facet normal 0.996754 -0.0523321 -0.0611729 + outer loop + vertex 683.438 195.259 237.495 + vertex 683.76 204.825 234.552 + vertex 684.019 205.802 237.937 + endloop + endfacet + facet normal 0.995187 -0.0513105 -0.0834863 + outer loop + vertex 683.438 195.259 237.495 + vertex 684.019 205.802 237.937 + vertex 683.695 194.373 241.105 + endloop + endfacet + facet normal 0.994042 -0.0543303 -0.0944947 + outer loop + vertex 683.695 194.373 241.105 + vertex 684.019 205.802 237.937 + vertex 684.237 203.087 241.795 + endloop + endfacet + facet normal 0.997287 -0.0265969 -0.0686456 + outer loop + vertex 683.76 204.825 234.552 + vertex 684.004 219.112 232.572 + vertex 684.019 205.802 237.937 + endloop + endfacet + facet normal 0.997468 -0.0256591 -0.0663192 + outer loop + vertex 684.004 219.112 232.572 + vertex 684.448 217.462 239.881 + vertex 684.019 205.802 237.937 + endloop + endfacet + facet normal 0.997206 -0.0557109 -0.0497742 + outer loop + vertex 682.906 197.704 226.424 + vertex 683.429 206.411 227.154 + vertex 683.049 196.906 230.198 + endloop + endfacet + facet normal 0.996852 -0.0550811 -0.0570311 + outer loop + vertex 682.906 197.704 226.424 + vertex 683.337 208.957 223.09 + vertex 683.429 206.411 227.154 + endloop + endfacet + facet normal 0.997681 -0.0514234 -0.0445795 + outer loop + vertex 682.774 198.474 222.585 + vertex 683.337 208.957 223.09 + vertex 682.906 197.704 226.424 + endloop + endfacet + facet normal 0.998229 -0.0522267 -0.0284905 + outer loop + vertex 682.774 198.474 222.585 + vertex 683.177 207.886 219.471 + vertex 683.337 208.957 223.09 + endloop + endfacet + facet normal 0.999022 -0.0247232 -0.0366702 + outer loop + vertex 683.177 207.886 219.471 + vertex 683.451 221.956 217.442 + vertex 683.337 208.957 223.09 + endloop + endfacet + facet normal 0.999102 -0.0239673 -0.0349288 + outer loop + vertex 683.451 221.956 217.442 + vertex 683.687 220.601 225.111 + vertex 683.337 208.957 223.09 + endloop + endfacet + facet normal 0.999367 -0.0131778 -0.0330306 + outer loop + vertex 683.451 221.956 217.442 + vertex 683.714 239.973 218.224 + vertex 683.687 220.601 225.111 + endloop + endfacet + facet normal 0.999552 -0.0134541 -0.0267271 + outer loop + vertex 683.451 221.956 217.442 + vertex 683.522 241.068 210.483 + vertex 683.714 239.973 218.224 + endloop + endfacet + facet normal 0.999482 -0.0171165 -0.0272434 + outer loop + vertex 683.522 241.068 210.483 + vertex 683.827 258.208 210.903 + vertex 683.714 239.973 218.224 + endloop + endfacet + facet normal 0.999489 -0.0170317 -0.027032 + outer loop + vertex 683.714 239.973 218.224 + vertex 683.827 258.208 210.903 + vertex 684.019 257.216 218.632 + endloop + endfacet + facet normal 0.999162 -0.0292778 -0.0285955 + outer loop + vertex 683.827 258.208 210.903 + vertex 684.31 274.611 210.989 + vertex 684.019 257.216 218.632 + endloop + endfacet + facet normal 0.999322 -0.0293154 -0.0222781 + outer loop + vertex 683.827 258.208 210.903 + vertex 684.158 275.347 203.201 + vertex 684.31 274.611 210.989 + endloop + endfacet + facet normal 0.998781 -0.043358 -0.0235941 + outer loop + vertex 684.158 275.347 203.201 + vertex 684.844 291.193 203.122 + vertex 684.31 274.611 210.989 + endloop + endfacet + facet normal 0.998803 -0.0431236 -0.0230985 + outer loop + vertex 684.31 274.611 210.989 + vertex 684.844 291.193 203.122 + vertex 684.997 290.557 210.91 + endloop + endfacet + facet normal 0.998621 -0.0431494 -0.0299188 + outer loop + vertex 684.31 274.611 210.989 + vertex 684.997 290.557 210.91 + vertex 684.503 273.722 218.708 + endloop + endfacet + facet normal 0.998273 -0.0536506 -0.0239476 + outer loop + vertex 684.844 291.193 203.122 + vertex 685.683 306.841 203.041 + vertex 684.997 290.557 210.91 + endloop + endfacet + facet normal 0.998308 -0.0533048 -0.0232288 + outer loop + vertex 684.997 290.557 210.91 + vertex 685.683 306.841 203.041 + vertex 685.836 306.315 210.829 + endloop + endfacet + facet normal 0.998132 -0.0533291 -0.0298121 + outer loop + vertex 684.997 290.557 210.91 + vertex 685.836 306.315 210.829 + vertex 685.187 289.798 218.632 + endloop + endfacet + facet normal 0.997944 -0.0595763 -0.0236451 + outer loop + vertex 685.683 306.841 203.041 + vertex 686.613 322.429 203.019 + vertex 685.836 306.315 210.829 + endloop + endfacet + facet normal 0.997991 -0.0591379 -0.022736 + outer loop + vertex 685.836 306.315 210.829 + vertex 686.613 322.429 203.019 + vertex 686.766 322.017 210.807 + endloop + endfacet + facet normal 0.997825 -0.059137 -0.0291144 + outer loop + vertex 685.836 306.315 210.829 + vertex 686.766 322.017 210.807 + vertex 686.025 305.695 218.556 + endloop + endfacet + facet normal 0.997757 -0.0628973 -0.0229304 + outer loop + vertex 686.613 322.429 203.019 + vertex 687.597 338.032 203.037 + vertex 686.766 322.017 210.807 + endloop + endfacet + facet normal 0.99778 -0.0626873 -0.0224951 + outer loop + vertex 686.766 322.017 210.807 + vertex 687.597 338.032 203.037 + vertex 687.754 337.727 210.83 + endloop + endfacet + facet normal 0.997628 -0.0626692 -0.0284812 + outer loop + vertex 686.766 322.017 210.807 + vertex 687.754 337.727 210.83 + vertex 686.957 321.536 218.539 + endloop + endfacet + facet normal 0.997476 -0.0672925 -0.0226695 + outer loop + vertex 687.597 338.032 203.037 + vertex 688.658 353.743 203.075 + vertex 687.754 337.727 210.83 + endloop + endfacet + facet normal 0.99751 -0.0669915 -0.0220438 + outer loop + vertex 687.754 337.727 210.83 + vertex 688.658 353.743 203.075 + vertex 688.817 353.547 210.872 + endloop + endfacet + facet normal 0.996446 -0.0812078 -0.0223799 + outer loop + vertex 688.658 353.743 203.075 + vertex 689.965 369.745 203.182 + vertex 688.817 353.547 210.872 + endloop + endfacet + facet normal 0.99657 -0.0812628 -0.0156657 + outer loop + vertex 688.658 353.743 203.075 + vertex 689.848 369.83 195.334 + vertex 689.965 369.745 203.182 + endloop + endfacet + facet normal 0.993182 -0.115473 -0.0159852 + outer loop + vertex 689.848 369.83 195.334 + vertex 691.76 386.239 195.596 + vertex 689.965 369.745 203.182 + endloop + endfacet + facet normal 0.993254 -0.114992 -0.0149229 + outer loop + vertex 689.965 369.745 203.182 + vertex 691.76 386.239 195.596 + vertex 691.883 386.259 203.587 + endloop + endfacet + facet normal 0.993143 -0.114804 -0.0220527 + outer loop + vertex 689.965 369.745 203.182 + vertex 691.883 386.259 203.587 + vertex 690.127 369.661 210.949 + endloop + endfacet + facet normal 0.993244 -0.115568 -0.0104721 + outer loop + vertex 689.848 369.83 195.334 + vertex 691.674 386.225 187.557 + vertex 691.76 386.239 195.596 + endloop + endfacet + facet normal 0.993098 -0.116601 -0.012685 + outer loop + vertex 689.756 369.892 187.568 + vertex 691.674 386.225 187.557 + vertex 689.848 369.83 195.334 + endloop + endfacet + facet normal 0.996556 -0.0819831 -0.0124499 + outer loop + vertex 688.538 353.915 195.273 + vertex 689.756 369.892 187.568 + vertex 689.848 369.83 195.334 + endloop + endfacet + facet normal 0.996547 -0.0820621 -0.0126152 + outer loop + vertex 688.45 354.042 187.506 + vertex 689.756 369.892 187.568 + vertex 688.538 353.915 195.273 + endloop + endfacet + facet normal 0.997631 -0.0676656 -0.0123912 + outer loop + vertex 687.478 338.284 195.244 + vertex 688.45 354.042 187.506 + vertex 688.538 353.915 195.273 + endloop + endfacet + facet normal 0.997555 -0.0676507 -0.0175141 + outer loop + vertex 687.478 338.284 195.244 + vertex 688.538 353.915 195.273 + vertex 687.597 338.032 203.037 + endloop + endfacet + facet normal 0.997622 -0.0677583 -0.0125812 + outer loop + vertex 687.392 338.469 187.478 + vertex 688.45 354.042 187.506 + vertex 687.478 338.284 195.244 + endloop + endfacet + facet normal 0.997918 -0.0632823 -0.0124775 + outer loop + vertex 686.493 322.765 195.226 + vertex 687.392 338.469 187.478 + vertex 687.478 338.284 195.244 + endloop + endfacet + facet normal 0.997832 -0.0632705 -0.0181027 + outer loop + vertex 686.493 322.765 195.226 + vertex 687.478 338.284 195.244 + vertex 686.613 322.429 203.019 + endloop + endfacet + facet normal 0.997899 -0.0634877 -0.012896 + outer loop + vertex 686.408 323.008 187.459 + vertex 687.392 338.469 187.478 + vertex 686.493 322.765 195.226 + endloop + endfacet + facet normal 0.99813 -0.0597684 -0.0127826 + outer loop + vertex 685.565 307.259 195.248 + vertex 686.408 323.008 187.459 + vertex 686.493 322.765 195.226 + endloop + endfacet + facet normal 0.998043 -0.0597711 -0.018348 + outer loop + vertex 685.565 307.259 195.248 + vertex 686.493 322.765 195.226 + vertex 685.683 306.841 203.041 + endloop + endfacet + facet normal 0.998107 -0.0600352 -0.0133245 + outer loop + vertex 685.48 307.562 187.479 + vertex 686.408 323.008 187.459 + vertex 685.565 307.259 195.248 + endloop + endfacet + facet normal 0.998463 -0.0538585 -0.0130879 + outer loop + vertex 684.727 291.694 195.329 + vertex 685.48 307.562 187.479 + vertex 685.565 307.259 195.248 + endloop + endfacet + facet normal 0.998375 -0.0538822 -0.0185473 + outer loop + vertex 684.727 291.694 195.329 + vertex 685.565 307.259 195.248 + vertex 684.844 291.193 203.122 + endloop + endfacet + facet normal 0.998455 -0.0539493 -0.0132722 + outer loop + vertex 684.643 292.051 187.562 + vertex 685.48 307.562 187.479 + vertex 684.727 291.694 195.329 + endloop + endfacet + facet normal 0.998969 -0.0435619 -0.0127996 + outer loop + vertex 684.04 275.926 195.411 + vertex 684.643 292.051 187.562 + vertex 684.727 291.694 195.329 + endloop + endfacet + facet normal 0.99888 -0.0435872 -0.0184025 + outer loop + vertex 684.04 275.926 195.411 + vertex 684.727 291.694 195.329 + vertex 684.158 275.347 203.201 + endloop + endfacet + facet normal 0.999412 -0.0295636 -0.0173676 + outer loop + vertex 683.674 259.036 203.118 + vertex 684.04 275.926 195.411 + vertex 684.158 275.347 203.201 + endloop + endfacet + facet normal 0.999391 -0.0298661 -0.0180316 + outer loop + vertex 683.554 259.693 195.338 + vertex 684.04 275.926 195.411 + vertex 683.674 259.036 203.118 + endloop + endfacet + facet normal 0.999705 -0.0173839 -0.0169824 + outer loop + vertex 683.371 241.979 202.706 + vertex 683.554 259.693 195.338 + vertex 683.674 259.036 203.118 + endloop + endfacet + facet normal 0.99962 -0.0172735 -0.0214956 + outer loop + vertex 683.371 241.979 202.706 + vertex 683.674 259.036 203.118 + vertex 683.522 241.068 210.483 + endloop + endfacet + facet normal 0.999688 -0.0134242 -0.021046 + outer loop + vertex 683.264 223.114 209.671 + vertex 683.371 241.979 202.706 + vertex 683.522 241.068 210.483 + endloop + endfacet + facet normal 0.999717 -0.013007 -0.0199155 + outer loop + vertex 683.122 224.076 201.913 + vertex 683.371 241.979 202.706 + vertex 683.264 223.114 209.671 + endloop + endfacet + facet normal 0.999502 -0.0233648 -0.0211957 + outer loop + vertex 683.122 224.076 201.913 + vertex 683.264 223.114 209.671 + vertex 682.947 211.483 207.561 + endloop + endfacet + facet normal 0.999428 -0.0243677 -0.0234342 + outer loop + vertex 682.832 210.212 203.944 + vertex 683.122 224.076 201.913 + vertex 682.947 211.483 207.561 + endloop + endfacet + facet normal 0.998551 -0.0520519 -0.0136806 + outer loop + vertex 682.395 201.029 207.039 + vertex 682.832 210.212 203.944 + vertex 682.947 211.483 207.561 + endloop + endfacet + facet normal 0.998309 -0.0513633 -0.0272176 + outer loop + vertex 682.395 201.029 207.039 + vertex 682.947 211.483 207.561 + vertex 682.472 200.48 210.901 + endloop + endfacet + facet normal 0.997661 -0.055279 -0.0402094 + outer loop + vertex 682.472 200.48 210.901 + vertex 682.947 211.483 207.561 + vertex 682.985 209.17 211.678 + endloop + endfacet + facet normal 0.997892 -0.0559478 -0.0328858 + outer loop + vertex 682.472 200.48 210.901 + vertex 682.985 209.17 211.678 + vertex 682.567 199.869 214.806 + endloop + endfacet + facet normal 0.998466 -0.0516338 -0.0199794 + outer loop + vertex 682.567 199.869 214.806 + vertex 682.985 209.17 211.678 + vertex 683.118 210.326 215.333 + endloop + endfacet + facet normal 0.998161 -0.0509704 -0.0328182 + outer loop + vertex 682.567 199.869 214.806 + vertex 683.118 210.326 215.333 + vertex 682.661 199.196 218.711 + endloop + endfacet + facet normal 0.997377 -0.0551893 -0.0468246 + outer loop + vertex 682.661 199.196 218.711 + vertex 683.118 210.326 215.333 + vertex 683.177 207.886 219.471 + endloop + endfacet + facet normal 0.999297 -0.0241181 -0.0287167 + outer loop + vertex 682.985 209.17 211.678 + vertex 683.264 223.114 209.671 + vertex 683.118 210.326 215.333 + endloop + endfacet + facet normal 0.999341 -0.0236103 -0.0275687 + outer loop + vertex 683.264 223.114 209.671 + vertex 683.451 221.956 217.442 + vertex 683.118 210.326 215.333 + endloop + endfacet + facet normal 0.9982 -0.0552672 -0.0232702 + outer loop + vertex 682.333 201.521 203.2 + vertex 682.832 210.212 203.944 + vertex 682.395 201.029 207.039 + endloop + endfacet + facet normal 0.997995 -0.0544923 -0.0321858 + outer loop + vertex 682.333 201.521 203.2 + vertex 682.819 212.408 199.825 + vertex 682.832 210.212 203.944 + endloop + endfacet + facet normal 0.998483 -0.0509866 -0.0208072 + outer loop + vertex 682.275 201.96 199.317 + vertex 682.819 212.408 199.825 + vertex 682.333 201.521 203.2 + endloop + endfacet + facet normal 0.998639 -0.0516583 -0.0071635 + outer loop + vertex 682.275 201.96 199.317 + vertex 682.722 211.051 196.159 + vertex 682.819 212.408 199.825 + endloop + endfacet + facet normal 0.999563 -0.0238572 -0.0174762 + outer loop + vertex 682.722 211.051 196.159 + vertex 683.015 224.815 194.133 + vertex 682.819 212.408 199.825 + endloop + endfacet + facet normal 0.999606 -0.0231401 -0.0159118 + outer loop + vertex 683.015 224.815 194.133 + vertex 683.122 224.076 201.913 + vertex 682.819 212.408 199.825 + endloop + endfacet + facet normal 0.999807 -0.0127747 -0.0149302 + outer loop + vertex 683.015 224.815 194.133 + vertex 683.255 242.675 194.93 + vertex 683.122 224.076 201.913 + endloop + endfacet + facet normal 0.999855 -0.0129478 -0.0110691 + outer loop + vertex 683.015 224.815 194.133 + vertex 683.176 243.171 187.167 + vertex 683.255 242.675 194.93 + endloop + endfacet + facet normal 0.999791 -0.0170111 -0.011328 + outer loop + vertex 683.176 243.171 187.167 + vertex 683.469 260.15 187.575 + vertex 683.255 242.675 194.93 + endloop + endfacet + facet normal 0.999781 -0.0172359 -0.0118624 + outer loop + vertex 683.255 242.675 194.93 + vertex 683.469 260.15 187.575 + vertex 683.554 259.693 195.338 + endloop + endfacet + facet normal 0.999478 -0.0297406 -0.0125953 + outer loop + vertex 683.469 260.15 187.575 + vertex 683.952 276.346 187.647 + vertex 683.554 259.693 195.338 + endloop + endfacet + facet normal 0.999529 -0.0297648 -0.00747223 + outer loop + vertex 683.469 260.15 187.575 + vertex 683.902 276.589 179.903 + vertex 683.952 276.346 187.647 + endloop + endfacet + facet normal 0.999008 -0.0438208 -0.00790964 + outer loop + vertex 683.902 276.589 179.903 + vertex 684.589 292.271 179.818 + vertex 683.952 276.346 187.647 + endloop + endfacet + facet normal 0.999 -0.0439617 -0.00819691 + outer loop + vertex 683.952 276.346 187.647 + vertex 684.589 292.271 179.818 + vertex 684.643 292.051 187.562 + endloop + endfacet + facet normal 0.998492 -0.0542339 -0.00848412 + outer loop + vertex 684.589 292.271 179.818 + vertex 685.428 307.742 179.737 + vertex 684.643 292.051 187.562 + endloop + endfacet + facet normal 0.998526 -0.0542051 -0.00266025 + outer loop + vertex 684.589 292.271 179.818 + vertex 685.411 307.803 172.01 + vertex 685.428 307.742 179.737 + endloop + endfacet + facet normal 0.998181 -0.0602354 -0.00270713 + outer loop + vertex 685.411 307.803 172.01 + vertex 686.34 323.203 171.992 + vertex 685.428 307.742 179.737 + endloop + endfacet + facet normal 0.998183 -0.060198 -0.00263209 + outer loop + vertex 685.428 307.742 179.737 + vertex 686.34 323.203 171.992 + vertex 686.358 323.153 179.719 + endloop + endfacet + facet normal 0.998154 -0.0602025 -0.00800362 + outer loop + vertex 685.428 307.742 179.737 + vertex 686.358 323.153 179.719 + vertex 685.48 307.562 187.479 + endloop + endfacet + facet normal 0.997966 -0.0636979 -0.00265444 + outer loop + vertex 686.34 323.203 171.992 + vertex 687.325 338.622 172.017 + vertex 686.358 323.153 179.719 + endloop + endfacet + facet normal 0.997973 -0.0635956 -0.00244795 + outer loop + vertex 686.358 323.153 179.719 + vertex 687.325 338.622 172.017 + vertex 687.341 338.582 179.741 + endloop + endfacet + facet normal 0.997946 -0.0635865 -0.00772354 + outer loop + vertex 686.358 323.153 179.719 + vertex 687.341 338.582 179.741 + vertex 686.408 323.008 187.459 + endloop + endfacet + facet normal 0.997676 -0.0680872 -0.00247094 + outer loop + vertex 687.325 338.622 172.017 + vertex 688.385 354.157 172.046 + vertex 687.341 338.582 179.741 + endloop + endfacet + facet normal 0.997683 -0.0679962 -0.0022858 + outer loop + vertex 687.341 338.582 179.741 + vertex 688.385 354.157 172.046 + vertex 688.4 354.123 179.769 + endloop + endfacet + facet normal 0.997657 -0.0679846 -0.0076067 + outer loop + vertex 687.341 338.582 179.741 + vertex 688.4 354.123 179.769 + vertex 687.392 338.469 187.478 + endloop + endfacet + facet normal 0.996595 -0.0824241 -0.00234708 + outer loop + vertex 688.385 354.157 172.046 + vertex 689.692 369.96 172.107 + vertex 688.4 354.123 179.769 + endloop + endfacet + facet normal 0.996597 -0.0823946 -0.00228561 + outer loop + vertex 688.4 354.123 179.769 + vertex 689.692 369.96 172.107 + vertex 689.708 369.938 179.858 + endloop + endfacet + facet normal 0.996575 -0.0823646 -0.00731741 + outer loop + vertex 688.4 354.123 179.769 + vertex 689.708 369.938 179.858 + vertex 688.45 354.042 187.506 + endloop + endfacet + facet normal 0.993115 -0.117122 -0.00237854 + outer loop + vertex 689.692 369.96 172.107 + vertex 691.61 386.215 172.389 + vertex 689.708 369.938 179.858 + endloop + endfacet + facet normal 0.993129 -0.117002 -0.00211417 + outer loop + vertex 689.708 369.938 179.858 + vertex 691.61 386.215 172.389 + vertex 691.627 386.218 180.208 + endloop + endfacet + facet normal 0.99312 -0.116898 -0.00692594 + outer loop + vertex 689.708 369.938 179.858 + vertex 691.627 386.218 180.208 + vertex 689.756 369.892 187.568 + endloop + endfacet + facet normal 0.993106 -0.1172 0.00215001 + outer loop + vertex 689.692 369.96 172.107 + vertex 691.627 386.218 164.477 + vertex 691.61 386.215 172.389 + endloop + endfacet + facet normal 0.993128 -0.117003 0.00257518 + outer loop + vertex 689.712 369.963 164.37 + vertex 691.627 386.218 164.477 + vertex 689.692 369.96 172.107 + endloop + endfacet + facet normal 0.993108 -0.117026 0.00639192 + outer loop + vertex 689.712 369.963 164.37 + vertex 691.678 386.226 156.792 + vertex 691.627 386.218 164.477 + endloop + endfacet + facet normal 0.9931 -0.117108 0.00621183 + outer loop + vertex 689.758 369.941 156.645 + vertex 691.678 386.226 156.792 + vertex 689.712 369.963 164.37 + endloop + endfacet + facet normal 0.996564 -0.0825933 0.0061314 + outer loop + vertex 688.402 354.144 164.324 + vertex 689.758 369.941 156.645 + vertex 689.712 369.963 164.37 + endloop + endfacet + facet normal 0.996581 -0.0825835 0.0023078 + outer loop + vertex 688.402 354.144 164.324 + vertex 689.712 369.963 164.37 + vertex 688.385 354.157 172.046 + endloop + endfacet + facet normal 0.996599 -0.0820982 0.00715583 + outer loop + vertex 688.452 354.086 156.592 + vertex 689.758 369.941 156.645 + vertex 688.402 354.144 164.324 + endloop + endfacet + facet normal 0.997662 -0.0679782 0.00705657 + outer loop + vertex 687.342 338.594 164.294 + vertex 688.452 354.086 156.592 + vertex 688.402 354.144 164.324 + endloop + endfacet + facet normal 0.997684 -0.067971 0.00253876 + outer loop + vertex 687.342 338.594 164.294 + vertex 688.402 354.144 164.324 + vertex 687.325 338.622 172.017 + endloop + endfacet + facet normal 0.997671 -0.0678012 0.00741399 + outer loop + vertex 687.393 338.496 156.563 + vertex 688.452 354.086 156.592 + vertex 687.342 338.594 164.294 + endloop + endfacet + facet normal 0.997944 -0.0636695 0.00736332 + outer loop + vertex 686.358 323.159 164.269 + vertex 687.393 338.496 156.563 + vertex 687.342 338.594 164.294 + endloop + endfacet + facet normal 0.997968 -0.0636635 0.00260904 + outer loop + vertex 686.358 323.159 164.269 + vertex 687.342 338.594 164.294 + vertex 686.34 323.203 171.992 + endloop + endfacet + facet normal 0.997953 -0.0634765 0.0077486 + outer loop + vertex 686.409 323.024 156.54 + vertex 687.393 338.496 156.563 + vertex 686.358 323.159 164.269 + endloop + endfacet + facet normal 0.99816 -0.0601417 0.0076915 + outer loop + vertex 685.429 307.747 164.286 + vertex 686.409 323.024 156.54 + vertex 686.358 323.159 164.269 + endloop + endfacet + facet normal 0.998186 -0.0601487 0.00275109 + outer loop + vertex 685.429 307.747 164.286 + vertex 686.358 323.159 164.269 + vertex 685.411 307.803 172.01 + endloop + endfacet + facet normal 0.998526 -0.054199 0.00270839 + outer loop + vertex 684.572 292.342 172.09 + vertex 685.429 307.747 164.286 + vertex 685.411 307.803 172.01 + endloop + endfacet + facet normal 0.998522 -0.0542976 0.00251335 + outer loop + vertex 684.588 292.279 164.366 + vertex 685.429 307.747 164.286 + vertex 684.572 292.342 172.09 + endloop + endfacet + facet normal 0.99903 -0.0439772 0.00242963 + outer loop + vertex 683.882 276.678 172.175 + vertex 684.588 292.279 164.366 + vertex 684.572 292.342 172.09 + endloop + endfacet + facet normal 0.999027 -0.0440068 -0.00303967 + outer loop + vertex 683.882 276.678 172.175 + vertex 684.572 292.342 172.09 + vertex 683.902 276.589 179.903 + endloop + endfacet + facet normal 0.999551 -0.029823 -0.00287761 + outer loop + vertex 683.419 260.423 179.833 + vertex 683.882 276.678 172.175 + vertex 683.902 276.589 179.903 + endloop + endfacet + facet normal 0.999549 -0.02987 -0.00297754 + outer loop + vertex 683.399 260.524 172.112 + vertex 683.882 276.678 172.175 + vertex 683.419 260.423 179.833 + endloop + endfacet + facet normal 0.99985 -0.0170883 -0.0028097 + outer loop + vertex 683.128 243.478 179.438 + vertex 683.399 260.524 172.112 + vertex 683.419 260.423 179.833 + endloop + endfacet + facet normal 0.999832 -0.0169942 -0.00682634 + outer loop + vertex 683.128 243.478 179.438 + vertex 683.419 260.423 179.833 + vertex 683.176 243.171 187.167 + endloop + endfacet + facet normal 0.999897 -0.0127147 -0.00665663 + outer loop + vertex 682.944 225.344 186.351 + vertex 683.128 243.478 179.438 + vertex 683.176 243.171 187.167 + endloop + endfacet + facet normal 0.999907 -0.012367 -0.00574447 + outer loop + vertex 682.903 225.638 178.653 + vertex 683.128 243.478 179.438 + vertex 682.944 225.344 186.351 + endloop + endfacet + facet normal 0.999728 -0.0224932 -0.00613078 + outer loop + vertex 682.903 225.638 178.653 + vertex 682.944 225.344 186.351 + vertex 682.667 213.62 184.209 + endloop + endfacet + facet normal 0.999701 -0.0232186 -0.00770081 + outer loop + vertex 682.603 212.049 180.632 + vertex 682.903 225.638 178.653 + vertex 682.667 213.62 184.209 + endloop + endfacet + facet normal 0.998568 -0.0532191 0.00548927 + outer loop + vertex 682.111 203.124 183.625 + vertex 682.603 212.049 180.632 + vertex 682.667 213.62 184.209 + endloop + endfacet + facet normal 0.998592 -0.0524883 -0.00765248 + outer loop + vertex 682.111 203.124 183.625 + vertex 682.667 213.62 184.209 + vertex 682.128 202.903 187.463 + endloop + endfacet + facet normal 0.998116 -0.0570217 -0.0226611 + outer loop + vertex 682.128 202.903 187.463 + vertex 682.667 213.62 184.209 + vertex 682.648 211.67 188.296 + endloop + endfacet + facet normal 0.99824 -0.0580129 -0.0123051 + outer loop + vertex 682.128 202.903 187.463 + vertex 682.648 211.67 188.296 + vertex 682.161 202.638 191.392 + endloop + endfacet + facet normal 0.998567 -0.0535159 0.000866532 + outer loop + vertex 682.161 202.638 191.392 + vertex 682.648 211.67 188.296 + vertex 682.723 213.123 191.979 + endloop + endfacet + facet normal 0.998463 -0.0524617 -0.0178473 + outer loop + vertex 682.161 202.638 191.392 + vertex 682.723 213.123 191.979 + vertex 682.216 202.33 195.367 + endloop + endfacet + facet normal 0.99809 -0.055411 -0.0272995 + outer loop + vertex 682.216 202.33 195.367 + vertex 682.723 213.123 191.979 + vertex 682.722 211.051 196.159 + endloop + endfacet + facet normal 0.999669 -0.0231881 -0.0111257 + outer loop + vertex 682.648 211.67 188.296 + vertex 682.944 225.344 186.351 + vertex 682.723 213.123 191.979 + endloop + endfacet + facet normal 0.999677 -0.0230169 -0.0107538 + outer loop + vertex 682.944 225.344 186.351 + vertex 683.015 224.815 194.133 + vertex 682.723 213.123 191.979 + endloop + endfacet + facet normal 0.998352 -0.0570641 -0.00601431 + outer loop + vertex 682.097 203.277 179.841 + vertex 682.603 212.049 180.632 + vertex 682.111 203.124 183.625 + endloop + endfacet + facet normal 0.998283 -0.0560761 -0.0169186 + outer loop + vertex 682.097 203.277 179.841 + vertex 682.636 213.862 176.583 + vertex 682.603 212.049 180.632 + endloop + endfacet + facet normal 0.998649 -0.0518605 -0.00316191 + outer loop + vertex 682.089 203.361 176.031 + vertex 682.636 213.862 176.583 + vertex 682.097 203.277 179.841 + endloop + endfacet + facet normal 0.998567 -0.0525518 0.0100728 + outer loop + vertex 682.089 203.361 176.031 + vertex 682.584 212.176 172.972 + vertex 682.636 213.862 176.583 + endloop + endfacet + facet normal 0.999725 -0.0231692 -0.00366313 + outer loop + vertex 682.584 212.176 172.972 + vertex 682.89 225.713 170.955 + vertex 682.636 213.862 176.583 + endloop + endfacet + facet normal 0.999749 -0.0223429 -0.00192196 + outer loop + vertex 682.89 225.713 170.955 + vertex 682.903 225.638 178.653 + vertex 682.636 213.862 176.583 + endloop + endfacet + facet normal 0.999922 -0.012364 -0.00182507 + outer loop + vertex 682.89 225.713 170.955 + vertex 683.112 243.562 171.723 + vertex 682.903 225.638 178.653 + endloop + endfacet + facet normal 0.999918 -0.0125465 0.00241725 + outer loop + vertex 682.89 225.713 170.955 + vertex 683.129 243.455 163.995 + vertex 683.112 243.562 171.723 + endloop + endfacet + facet normal 0.999852 -0.0169991 0.002479 + outer loop + vertex 683.129 243.455 163.995 + vertex 683.417 260.431 164.387 + vertex 683.112 243.562 171.723 + endloop + endfacet + facet normal 0.999853 -0.0169713 0.00254295 + outer loop + vertex 683.112 243.562 171.723 + vertex 683.417 260.431 164.387 + vertex 683.399 260.524 172.112 + endloop + endfacet + facet normal 0.99956 -0.0295488 0.00269387 + outer loop + vertex 683.417 260.431 164.387 + vertex 683.895 276.612 164.454 + vertex 683.399 260.524 172.112 + endloop + endfacet + facet normal 0.999536 -0.0295673 0.00731038 + outer loop + vertex 683.417 260.431 164.387 + vertex 683.945 276.383 156.726 + vertex 683.895 276.612 164.454 + endloop + endfacet + facet normal 0.999004 -0.0439447 0.00773308 + outer loop + vertex 683.945 276.383 156.726 + vertex 684.636 292.081 156.639 + vertex 683.895 276.612 164.454 + endloop + endfacet + facet normal 0.998999 -0.0441122 0.00740121 + outer loop + vertex 683.895 276.612 164.454 + vertex 684.636 292.081 156.639 + vertex 684.588 292.279 164.366 + endloop + endfacet + facet normal 0.998498 -0.0542422 0.00765718 + outer loop + vertex 684.636 292.081 156.639 + vertex 685.479 307.578 156.558 + vertex 684.588 292.279 164.366 + endloop + endfacet + facet normal 0.998445 -0.0542118 0.0129535 + outer loop + vertex 684.636 292.081 156.639 + vertex 685.564 307.292 148.817 + vertex 685.479 307.578 156.558 + endloop + endfacet + facet normal 0.998119 -0.0598704 0.0131589 + outer loop + vertex 685.564 307.292 148.817 + vertex 686.494 322.795 148.798 + vertex 685.479 307.578 156.558 + endloop + endfacet + facet normal 0.998111 -0.0601145 0.0126793 + outer loop + vertex 685.479 307.578 156.558 + vertex 686.494 322.795 148.798 + vertex 686.409 323.024 156.54 + endloop + endfacet + facet normal 0.99791 -0.0633377 0.0127723 + outer loop + vertex 686.494 322.795 148.798 + vertex 687.479 338.329 148.817 + vertex 686.409 323.024 156.54 + endloop + endfacet + facet normal 0.997841 -0.0633391 0.0173731 + outer loop + vertex 686.494 322.795 148.798 + vertex 687.599 338.092 141.058 + vertex 687.479 338.329 148.817 + endloop + endfacet + facet normal 0.997581 -0.0672733 0.0174896 + outer loop + vertex 687.599 338.092 141.058 + vertex 688.661 353.838 141.081 + vertex 687.479 338.329 148.817 + endloop + endfacet + facet normal 0.997572 -0.06757 0.0168933 + outer loop + vertex 687.479 338.329 148.817 + vertex 688.661 353.838 141.081 + vertex 688.539 353.985 148.845 + endloop + endfacet + facet normal 0.997636 -0.0675666 0.0125736 + outer loop + vertex 687.479 338.329 148.817 + vertex 688.539 353.985 148.845 + vertex 687.393 338.496 156.563 + endloop + endfacet + facet normal 0.99653 -0.0814469 0.0171397 + outer loop + vertex 688.661 353.838 141.081 + vertex 689.968 369.846 141.154 + vertex 688.539 353.985 148.845 + endloop + endfacet + facet normal 0.996509 -0.0819012 0.0161989 + outer loop + vertex 688.539 353.985 148.845 + vertex 689.968 369.846 141.154 + vertex 689.847 369.904 148.914 + endloop + endfacet + facet normal 0.996566 -0.0818887 0.012261 + outer loop + vertex 688.539 353.985 148.845 + vertex 689.847 369.904 148.914 + vertex 688.452 354.086 156.592 + endloop + endfacet + facet normal 0.993128 -0.115876 0.0163994 + outer loop + vertex 689.968 369.846 141.154 + vertex 691.878 386.258 141.451 + vertex 689.847 369.904 148.914 + endloop + endfacet + facet normal 0.993072 -0.116565 0.0148749 + outer loop + vertex 689.847 369.904 148.914 + vertex 691.878 386.258 141.451 + vertex 691.762 386.239 149.08 + endloop + endfacet + facet normal 0.993114 -0.11654 0.0119256 + outer loop + vertex 689.847 369.904 148.914 + vertex 691.762 386.239 149.08 + vertex 689.758 369.941 156.645 + endloop + endfacet + facet normal 0.993072 -0.115921 0.019224 + outer loop + vertex 689.968 369.846 141.154 + vertex 692.033 386.283 133.586 + vertex 691.878 386.258 141.451 + endloop + endfacet + facet normal 0.99315 -0.114836 0.0216009 + outer loop + vertex 690.129 369.77 133.362 + vertex 692.033 386.283 133.586 + vertex 689.968 369.846 141.154 + endloop + endfacet + facet normal 0.993097 -0.11486 0.0237736 + outer loop + vertex 690.129 369.77 133.362 + vertex 692.227 386.314 125.633 + vertex 692.033 386.283 133.586 + endloop + endfacet + facet normal 0.993158 -0.113863 0.0259225 + outer loop + vertex 690.318 369.667 125.648 + vertex 692.227 386.314 125.633 + vertex 690.129 369.77 133.362 + endloop + endfacet + facet normal 0.996388 -0.0809727 0.0255623 + outer loop + vertex 688.819 353.646 133.323 + vertex 690.318 369.667 125.648 + vertex 690.129 369.77 133.362 + endloop + endfacet + facet normal 0.996466 -0.0809713 0.0223526 + outer loop + vertex 688.819 353.646 133.323 + vertex 690.129 369.77 133.362 + vertex 688.661 353.838 141.081 + endloop + endfacet + facet normal 0.996415 -0.0799134 0.0277787 + outer loop + vertex 689.015 353.406 125.613 + vertex 690.318 369.667 125.648 + vertex 688.819 353.646 133.323 + endloop + endfacet + facet normal 0.997391 -0.0667919 0.0273943 + outer loop + vertex 687.758 337.787 133.305 + vertex 689.015 353.406 125.613 + vertex 688.819 353.646 133.323 + endloop + endfacet + facet normal 0.997502 -0.0667941 0.0230014 + outer loop + vertex 687.758 337.787 133.305 + vertex 688.819 353.646 133.323 + vertex 687.599 338.092 141.058 + endloop + endfacet + facet normal 0.997753 -0.0629732 0.0228564 + outer loop + vertex 686.614 322.473 141.042 + vertex 687.758 337.787 133.305 + vertex 687.599 338.092 141.058 + endloop + endfacet + facet normal 0.997758 -0.0627207 0.0233568 + outer loop + vertex 686.769 322.056 133.29 + vertex 687.758 337.787 133.305 + vertex 686.614 322.473 141.042 + endloop + endfacet + facet normal 0.997952 -0.0596136 0.0231936 + outer loop + vertex 685.683 306.889 141.064 + vertex 686.769 322.056 133.29 + vertex 686.614 322.473 141.042 + endloop + endfacet + facet normal 0.998051 -0.0596262 0.0184259 + outer loop + vertex 685.683 306.889 141.064 + vertex 686.614 322.473 141.042 + vertex 685.564 307.292 148.817 + endloop + endfacet + facet normal 0.998375 -0.0540128 0.0181393 + outer loop + vertex 684.721 291.742 148.899 + vertex 685.683 306.889 141.064 + vertex 685.564 307.292 148.817 + endloop + endfacet + facet normal 0.99838 -0.0537849 0.0185806 + outer loop + vertex 684.839 291.263 141.146 + vertex 685.683 306.889 141.064 + vertex 684.721 291.742 148.899 + endloop + endfacet + facet normal 0.998884 -0.0436846 0.0179642 + outer loop + vertex 684.03 275.988 148.984 + vertex 684.839 291.263 141.146 + vertex 684.721 291.742 148.899 + endloop + endfacet + facet normal 0.998956 -0.0437133 0.0132388 + outer loop + vertex 684.03 275.988 148.984 + vertex 684.721 291.742 148.899 + vertex 683.945 276.383 156.726 + endloop + endfacet + facet normal 0.999486 -0.0295027 0.0125198 + outer loop + vertex 683.467 260.168 156.654 + vertex 684.03 275.988 148.984 + vertex 683.945 276.383 156.726 + endloop + endfacet + facet normal 0.999486 -0.0296722 0.0121702 + outer loop + vertex 683.549 259.74 148.917 + vertex 684.03 275.988 148.984 + vertex 683.467 260.168 156.654 + endloop + endfacet + facet normal 0.999789 -0.0170609 0.0114746 + outer loop + vertex 683.182 243.153 156.254 + vertex 683.549 259.74 148.917 + vertex 683.467 260.168 156.654 + endloop + endfacet + facet normal 0.999829 -0.0169654 0.00738608 + outer loop + vertex 683.182 243.153 156.254 + vertex 683.467 260.168 156.654 + vertex 683.129 243.455 163.995 + endloop + endfacet + facet normal 0.999896 -0.012479 0.00721154 + outer loop + vertex 682.912 225.577 163.195 + vertex 683.182 243.153 156.254 + vertex 683.129 243.455 163.995 + endloop + endfacet + facet normal 0.999896 -0.0123886 0.00744042 + outer loop + vertex 682.965 225.226 155.45 + vertex 683.182 243.153 156.254 + vertex 682.912 225.577 163.195 + endloop + endfacet + facet normal 0.999713 -0.0226006 0.00790191 + outer loop + vertex 682.965 225.226 155.45 + vertex 682.912 225.577 163.195 + vertex 682.66 213.659 161.03 + endloop + endfacet + facet normal 0.999705 -0.0235314 0.00597197 + outer loop + vertex 682.637 211.77 157.396 + vertex 682.965 225.226 155.45 + vertex 682.66 213.659 161.03 + endloop + endfacet + facet normal 0.998388 -0.0526838 0.0211379 + outer loop + vertex 682.117 203.122 160.409 + vertex 682.637 211.77 157.396 + vertex 682.66 213.659 161.03 + endloop + endfacet + facet normal 0.998633 -0.0518422 0.00663571 + outer loop + vertex 682.117 203.122 160.409 + vertex 682.66 213.659 161.03 + vertex 682.098 203.263 164.297 + endloop + endfacet + facet normal 0.998445 -0.0555101 -0.0050682 + outer loop + vertex 682.098 203.263 164.297 + vertex 682.66 213.659 161.03 + vertex 682.593 212.08 165.155 + endloop + endfacet + facet normal 0.998389 -0.056505 0.00518373 + outer loop + vertex 682.098 203.263 164.297 + vertex 682.593 212.08 165.155 + vertex 682.083 203.349 168.219 + endloop + endfacet + facet normal 0.998481 -0.0527807 0.0158142 + outer loop + vertex 682.083 203.349 168.219 + vertex 682.593 212.08 165.155 + vertex 682.629 213.864 168.83 + endloop + endfacet + facet normal 0.998655 -0.0518526 -0.00029918 + outer loop + vertex 682.083 203.349 168.219 + vertex 682.629 213.864 168.83 + vertex 682.086 203.383 172.148 + endloop + endfacet + facet normal 0.998394 -0.0554343 -0.0116566 + outer loop + vertex 682.086 203.383 172.148 + vertex 682.629 213.864 168.83 + vertex 682.584 212.176 172.972 + endloop + endfacet + facet normal 0.999725 -0.0234148 0.0015505 + outer loop + vertex 682.593 212.08 165.155 + vertex 682.912 225.577 163.195 + vertex 682.629 213.864 168.83 + endloop + endfacet + facet normal 0.999739 -0.0226013 0.00324226 + outer loop + vertex 682.912 225.577 163.195 + vertex 682.89 225.713 170.955 + vertex 682.629 213.864 168.83 + endloop + endfacet + facet normal 0.998349 -0.0565561 0.0100175 + outer loop + vertex 682.144 202.925 156.556 + vertex 682.637 211.77 157.396 + vertex 682.117 203.122 160.409 + endloop + endfacet + facet normal 0.998439 -0.0558182 0.00219925 + outer loop + vertex 682.144 202.925 156.556 + vertex 682.728 213.245 153.323 + vertex 682.637 211.77 157.396 + endloop + endfacet + facet normal 0.998543 -0.0520542 0.0142342 + outer loop + vertex 682.186 202.675 152.719 + vertex 682.728 213.245 153.323 + vertex 682.144 202.925 156.556 + endloop + endfacet + facet normal 0.998253 -0.0527478 0.0266227 + outer loop + vertex 682.186 202.675 152.719 + vertex 682.719 211.245 149.716 + vertex 682.728 213.245 153.323 + endloop + endfacet + facet normal 0.999671 -0.0234396 0.0103718 + outer loop + vertex 682.719 211.245 149.716 + vertex 683.054 224.663 147.736 + vertex 682.728 213.245 153.323 + endloop + endfacet + facet normal 0.99967 -0.0220969 0.0131158 + outer loop + vertex 683.054 224.663 147.736 + vertex 682.965 225.226 155.45 + vertex 682.728 213.245 153.323 + endloop + endfacet + facet normal 0.999847 -0.0123479 0.0124056 + outer loop + vertex 683.054 224.663 147.736 + vertex 683.267 242.665 148.522 + vertex 682.965 225.226 155.45 + endloop + endfacet + facet normal 0.999778 -0.0125442 0.0169232 + outer loop + vertex 683.054 224.663 147.736 + vertex 683.389 241.945 140.773 + vertex 683.267 242.665 148.522 + endloop + endfacet + facet normal 0.999713 -0.0166007 0.0172991 + outer loop + vertex 683.389 241.945 140.773 + vertex 683.667 259.115 141.169 + vertex 683.267 242.665 148.522 + endloop + endfacet + facet normal 0.999719 -0.0168993 0.0166314 + outer loop + vertex 683.267 242.665 148.522 + vertex 683.667 259.115 141.169 + vertex 683.549 259.74 148.917 + endloop + endfacet + facet normal 0.999409 -0.0294874 0.017641 + outer loop + vertex 683.667 259.115 141.169 + vertex 684.148 275.438 141.233 + vertex 683.549 259.74 148.917 + endloop + endfacet + facet normal 0.999308 -0.0295039 0.022639 + outer loop + vertex 683.667 259.115 141.169 + vertex 684.302 274.708 133.482 + vertex 684.148 275.438 141.233 + endloop + endfacet + facet normal 0.998784 -0.0431197 0.02391 + outer loop + vertex 684.302 274.708 133.482 + vertex 684.991 290.639 133.397 + vertex 684.148 275.438 141.233 + endloop + endfacet + facet normal 0.998785 -0.0435312 0.0231119 + outer loop + vertex 684.148 275.438 141.233 + vertex 684.991 290.639 133.397 + vertex 684.839 291.263 141.146 + endloop + endfacet + facet normal 0.99828 -0.053523 0.0239055 + outer loop + vertex 684.991 290.639 133.397 + vertex 685.837 306.368 133.314 + vertex 684.839 291.263 141.146 + endloop + endfacet + facet normal 0.998115 -0.0534815 0.0301145 + outer loop + vertex 684.991 290.639 133.397 + vertex 686.034 305.715 125.6 + vertex 685.837 306.368 133.314 + endloop + endfacet + facet normal 0.997801 -0.0588161 0.030558 + outer loop + vertex 686.034 305.715 125.6 + vertex 686.968 321.541 125.579 + vertex 685.837 306.368 133.314 + endloop + endfacet + facet normal 0.997801 -0.0592712 0.0296652 + outer loop + vertex 685.837 306.368 133.314 + vertex 686.968 321.541 125.579 + vertex 686.769 322.056 133.29 + endloop + endfacet + facet normal 0.997625 -0.062074 0.0298478 + outer loop + vertex 686.968 321.541 125.579 + vertex 687.955 337.408 125.593 + vertex 686.769 322.056 133.29 + endloop + endfacet + facet normal 0.997407 -0.0620661 0.0364374 + outer loop + vertex 686.968 321.541 125.579 + vertex 688.205 336.958 117.97 + vertex 687.955 337.408 125.593 + endloop + endfacet + facet normal 0.997205 -0.0651267 0.0366114 + outer loop + vertex 688.205 336.958 117.97 + vertex 689.26 353.125 117.994 + vertex 687.955 337.408 125.593 + endloop + endfacet + facet normal 0.997213 -0.0661308 0.034536 + outer loop + vertex 687.955 337.408 125.593 + vertex 689.26 353.125 117.994 + vertex 689.015 353.406 125.613 + endloop + endfacet + facet normal 0.996258 -0.0790322 0.0349807 + outer loop + vertex 689.26 353.125 117.994 + vertex 690.561 369.552 118.054 + vertex 689.015 353.406 125.613 + endloop + endfacet + facet normal 0.996091 -0.0790355 0.0394459 + outer loop + vertex 689.26 353.125 117.994 + vertex 690.847 369.407 110.544 + vertex 690.561 369.552 118.054 + endloop + endfacet + facet normal 0.993053 -0.110679 0.0399395 + outer loop + vertex 690.847 369.407 110.544 + vertex 692.732 386.387 110.727 + vertex 690.561 369.552 118.054 + endloop + endfacet + facet normal 0.993026 -0.111894 0.0371397 + outer loop + vertex 690.561 369.552 118.054 + vertex 692.732 386.387 110.727 + vertex 692.447 386.348 118.233 + endloop + endfacet + facet normal 0.993159 -0.11187 0.033484 + outer loop + vertex 690.561 369.552 118.054 + vertex 692.447 386.348 118.233 + vertex 690.318 369.667 125.648 + endloop + endfacet + facet normal 0.992627 -0.110733 0.0492856 + outer loop + vertex 690.847 369.407 110.544 + vertex 693.11 386.429 103.207 + vertex 692.732 386.387 110.727 + endloop + endfacet + facet normal 0.992619 -0.109567 0.0519887 + outer loop + vertex 691.217 369.255 103.159 + vertex 693.11 386.429 103.207 + vertex 690.847 369.407 110.544 + endloop + endfacet + facet normal 0.99567 -0.0774099 0.051477 + outer loop + vertex 689.558 352.79 110.494 + vertex 691.217 369.255 103.159 + vertex 690.847 369.407 110.544 + endloop + endfacet + facet normal 0.995608 -0.0759521 0.0547352 + outer loop + vertex 689.936 352.437 103.125 + vertex 691.217 369.255 103.159 + vertex 689.558 352.79 110.494 + endloop + endfacet + facet normal 0.996511 -0.0634844 0.0541837 + outer loop + vertex 688.517 336.428 110.46 + vertex 689.936 352.437 103.125 + vertex 689.558 352.79 110.494 + endloop + endfacet + facet normal 0.996926 -0.0634935 0.0459056 + outer loop + vertex 688.517 336.428 110.46 + vertex 689.558 352.79 110.494 + vertex 688.205 336.958 117.97 + endloop + endfacet + facet normal 0.997078 -0.06118 0.0457487 + outer loop + vertex 687.222 320.917 117.947 + vertex 688.517 336.428 110.46 + vertex 688.205 336.958 117.97 + endloop + endfacet + facet normal 0.997019 -0.0596111 0.048989 + outer loop + vertex 687.549 320.203 110.424 + vertex 688.517 336.428 110.46 + vertex 687.222 320.917 117.947 + endloop + endfacet + facet normal 0.997123 -0.057972 0.0488381 + outer loop + vertex 686.292 304.919 117.958 + vertex 687.549 320.203 110.424 + vertex 687.222 320.917 117.947 + endloop + endfacet + facet normal 0.997531 -0.0580019 0.0395872 + outer loop + vertex 686.292 304.919 117.958 + vertex 687.222 320.917 117.947 + vertex 686.034 305.715 125.6 + endloop + endfacet + facet normal 0.997836 -0.0528842 0.0390645 + outer loop + vertex 685.19 289.847 125.679 + vertex 686.292 304.919 117.958 + vertex 686.034 305.715 125.6 + endloop + endfacet + facet normal 0.997828 -0.052531 0.0397527 + outer loop + vertex 685.445 288.894 118.028 + vertex 686.292 304.919 117.958 + vertex 685.19 289.847 125.679 + endloop + endfacet + facet normal 0.998333 -0.042943 0.0385752 + outer loop + vertex 684.497 273.789 125.759 + vertex 685.445 288.894 118.028 + vertex 685.19 289.847 125.679 + endloop + endfacet + facet normal 0.998615 -0.0429965 0.0303262 + outer loop + vertex 684.497 273.789 125.759 + vertex 685.19 289.847 125.679 + vertex 684.302 274.708 133.482 + endloop + endfacet + facet normal 0.999156 -0.0293817 0.028719 + outer loop + vertex 683.821 258.284 133.416 + vertex 684.497 273.789 125.759 + vertex 684.302 274.708 133.482 + endloop + endfacet + facet normal 0.999149 -0.0291471 0.0291934 + outer loop + vertex 684.016 257.238 125.687 + vertex 684.497 273.789 125.759 + vertex 683.821 258.284 133.416 + endloop + endfacet + facet normal 0.999478 -0.0168993 0.0275445 + outer loop + vertex 683.54 241.023 133.016 + vertex 684.016 257.238 125.687 + vertex 683.821 258.284 133.416 + endloop + endfacet + facet normal 0.99963 -0.0167601 0.0214359 + outer loop + vertex 683.54 241.023 133.016 + vertex 683.821 258.284 133.416 + vertex 683.389 241.945 140.773 + endloop + endfacet + facet normal 0.999701 -0.0126262 0.0209458 + outer loop + vertex 683.177 223.873 139.996 + vertex 683.54 241.023 133.016 + vertex 683.389 241.945 140.773 + endloop + endfacet + facet normal 0.999701 -0.012639 0.0209144 + outer loop + vertex 683.327 222.821 132.204 + vertex 683.54 241.023 133.016 + vertex 683.177 223.873 139.996 + endloop + endfacet + facet normal 0.999489 -0.0228903 0.0222941 + outer loop + vertex 683.327 222.821 132.204 + vertex 683.177 223.873 139.996 + vertex 682.945 211.687 137.866 + endloop + endfacet + facet normal 0.999496 -0.0232016 0.0216824 + outer loop + vertex 682.973 209.452 134.194 + vertex 683.327 222.821 132.204 + vertex 682.945 211.687 137.866 + endloop + endfacet + facet normal 0.997821 -0.0527328 0.0396455 + outer loop + vertex 682.407 201.066 137.287 + vertex 682.973 209.452 134.194 + vertex 682.945 211.687 137.866 + endloop + endfacet + facet normal 0.99837 -0.0518948 0.0237425 + outer loop + vertex 682.407 201.066 137.287 + vertex 682.945 211.687 137.866 + vertex 682.34 201.556 141.175 + endloop + endfacet + facet normal 0.998373 -0.0557655 0.0118926 + outer loop + vertex 682.34 201.556 141.175 + vertex 682.945 211.687 137.866 + vertex 682.828 210.476 141.999 + endloop + endfacet + facet normal 0.998132 -0.0567469 0.0226514 + outer loop + vertex 682.34 201.556 141.175 + vertex 682.828 210.476 141.999 + vertex 682.277 201.987 145.031 + endloop + endfacet + facet normal 0.998042 -0.0529229 0.0333431 + outer loop + vertex 682.277 201.987 145.031 + vertex 682.828 210.476 141.999 + vertex 682.819 212.588 145.627 + endloop + endfacet + facet normal 0.998498 -0.0520365 0.0171596 + outer loop + vertex 682.277 201.987 145.031 + vertex 682.819 212.588 145.627 + vertex 682.23 202.361 148.877 + endloop + endfacet + facet normal 0.998439 -0.0555023 0.00624472 + outer loop + vertex 682.23 202.361 148.877 + vertex 682.819 212.588 145.627 + vertex 682.719 211.245 149.716 + endloop + endfacet + facet normal 0.99959 -0.0235676 0.0162587 + outer loop + vertex 682.828 210.476 141.999 + vertex 683.177 223.873 139.996 + vertex 682.819 212.588 145.627 + endloop + endfacet + facet normal 0.999579 -0.0226197 0.0181577 + outer loop + vertex 683.177 223.873 139.996 + vertex 683.054 224.663 147.736 + vertex 682.819 212.588 145.627 + endloop + endfacet + facet normal 0.997973 -0.0567372 0.0288181 + outer loop + vertex 682.489 200.516 133.369 + vertex 682.973 209.452 134.194 + vertex 682.407 201.066 137.287 + endloop + endfacet + facet normal 0.998303 -0.0556696 0.0170615 + outer loop + vertex 682.489 200.516 133.369 + vertex 683.104 210.536 130.04 + vertex 682.973 209.452 134.194 + endloop + endfacet + facet normal 0.998222 -0.0511777 0.0305663 + outer loop + vertex 682.577 199.9 129.446 + vertex 683.104 210.536 130.04 + vertex 682.489 200.516 133.369 + endloop + endfacet + facet normal 0.997692 -0.0518902 0.0437968 + outer loop + vertex 682.577 199.9 129.446 + vertex 683.142 208.174 126.378 + vertex 683.104 210.536 130.04 + endloop + endfacet + facet normal 0.999369 -0.0242235 0.025977 + outer loop + vertex 683.142 208.174 126.378 + vertex 683.517 221.562 124.456 + vertex 683.104 210.536 130.04 + endloop + endfacet + facet normal 0.999334 -0.0230491 0.0282933 + outer loop + vertex 683.517 221.562 124.456 + vertex 683.327 222.821 132.204 + vertex 683.104 210.536 130.04 + endloop + endfacet + facet normal 0.99956 -0.0129813 0.026662 + outer loop + vertex 683.517 221.562 124.456 + vertex 683.733 239.869 125.28 + vertex 683.327 222.821 132.204 + endloop + endfacet + facet normal 0.999315 -0.0133328 0.0345304 + outer loop + vertex 683.517 221.562 124.456 + vertex 683.979 238.591 117.663 + vertex 683.733 239.869 125.28 + endloop + endfacet + facet normal 0.999235 -0.0171243 0.0351636 + outer loop + vertex 683.979 238.591 117.663 + vertex 684.264 256.053 118.051 + vertex 683.733 239.869 125.28 + endloop + endfacet + facet normal 0.999234 -0.0171159 0.0351824 + outer loop + vertex 683.733 239.869 125.28 + vertex 684.264 256.053 118.051 + vertex 684.016 257.238 125.687 + endloop + endfacet + facet normal 0.998885 -0.0292494 0.0370551 + outer loop + vertex 684.264 256.053 118.051 + vertex 684.75 272.703 118.111 + vertex 684.016 257.238 125.687 + endloop + endfacet + facet normal 0.998445 -0.0292736 0.04745 + outer loop + vertex 684.264 256.053 118.051 + vertex 685.074 271.597 110.604 + vertex 684.75 272.703 118.111 + endloop + endfacet + facet normal 0.997864 -0.0427389 0.0494075 + outer loop + vertex 685.074 271.597 110.604 + vertex 685.777 287.879 110.5 + vertex 684.75 272.703 118.111 + endloop + endfacet + facet normal 0.997856 -0.0425963 0.0496907 + outer loop + vertex 684.75 272.703 118.111 + vertex 685.777 287.879 110.5 + vertex 685.445 288.894 118.028 + endloop + endfacet + facet normal 0.997343 -0.0520658 0.0509448 + outer loop + vertex 685.777 287.879 110.5 + vertex 686.624 304.036 110.424 + vertex 685.445 288.894 118.028 + endloop + endfacet + facet normal 0.996641 -0.0519712 0.0632933 + outer loop + vertex 685.777 287.879 110.5 + vertex 687.05 303.219 103.044 + vertex 686.624 304.036 110.424 + endloop + endfacet + facet normal 0.996394 -0.0560236 0.0637276 + outer loop + vertex 687.05 303.219 103.044 + vertex 687.966 319.499 103.035 + vertex 686.624 304.036 110.424 + endloop + endfacet + facet normal 0.996468 -0.0570218 0.0616522 + outer loop + vertex 686.624 304.036 110.424 + vertex 687.966 319.499 103.035 + vertex 687.549 320.203 110.424 + endloop + endfacet + facet normal 0.996401 -0.0580728 0.0617487 + outer loop + vertex 687.966 319.499 103.035 + vertex 688.918 335.887 103.081 + vertex 687.549 320.203 110.424 + endloop + endfacet + facet normal 0.995473 -0.058057 0.0752474 + outer loop + vertex 687.966 319.499 103.035 + vertex 689.44 335.425 95.8274 + vertex 688.918 335.887 103.081 + endloop + endfacet + facet normal 0.995409 -0.0590783 0.0753078 + outer loop + vertex 689.44 335.425 95.8274 + vertex 690.427 352.111 95.8611 + vertex 688.918 335.887 103.081 + endloop + endfacet + facet normal 0.995648 -0.0614201 0.0700955 + outer loop + vertex 688.918 335.887 103.081 + vertex 690.427 352.111 95.8611 + vertex 689.936 352.437 103.125 + endloop + endfacet + facet normal 0.994776 -0.0737405 0.0705897 + outer loop + vertex 690.427 352.111 95.8611 + vertex 691.685 369.099 95.8816 + vertex 689.936 352.437 103.125 + endloop + endfacet + facet normal 0.993071 -0.0736396 0.0915769 + outer loop + vertex 690.427 352.111 95.8611 + vertex 692.341 368.981 88.6751 + vertex 691.685 369.099 95.8816 + endloop + endfacet + facet normal 0.989941 -0.107612 0.0918471 + outer loop + vertex 692.341 368.981 88.6751 + vertex 694.248 386.514 88.6611 + vertex 691.685 369.099 95.8816 + endloop + endfacet + facet normal 0.990117 -0.109265 0.0879223 + outer loop + vertex 691.685 369.099 95.8816 + vertex 694.248 386.514 88.6611 + vertex 693.6 386.471 95.907 + endloop + endfacet + facet normal 0.991794 -0.109418 0.0661255 + outer loop + vertex 691.685 369.099 95.8816 + vertex 693.6 386.471 95.907 + vertex 691.217 369.255 103.159 + endloop + endfacet + facet normal 0.987316 -0.107306 0.117012 + outer loop + vertex 692.341 368.981 88.6751 + vertex 695.089 386.556 81.6064 + vertex 694.248 386.514 88.6611 + endloop + endfacet + facet normal 0.986315 -0.102168 0.129399 + outer loop + vertex 693.266 368.855 81.5274 + vertex 695.089 386.556 81.6064 + vertex 692.341 368.981 88.6751 + endloop + endfacet + facet normal 0.989087 -0.0707992 0.129207 + outer loop + vertex 691.116 351.858 88.6725 + vertex 693.266 368.855 81.5274 + vertex 692.341 368.981 88.6751 + endloop + endfacet + facet normal 0.988106 -0.0667564 0.138529 + outer loop + vertex 692.095 351.519 81.5223 + vertex 693.266 368.855 81.5274 + vertex 691.116 351.858 88.6725 + endloop + endfacet + facet normal 0.988815 -0.0562642 0.138129 + outer loop + vertex 690.159 335.06 88.6819 + vertex 692.095 351.519 81.5223 + vertex 691.116 351.858 88.6725 + endloop + endfacet + facet normal 0.993094 -0.0565278 0.102807 + outer loop + vertex 690.159 335.06 88.6819 + vertex 691.116 351.858 88.6725 + vertex 689.44 335.425 95.8274 + endloop + endfacet + facet normal 0.993134 -0.0558627 0.102778 + outer loop + vertex 688.515 318.949 95.8059 + vertex 690.159 335.06 88.6819 + vertex 689.44 335.425 95.8274 + endloop + endfacet + facet normal 0.992715 -0.0535365 0.107942 + outer loop + vertex 689.262 318.478 88.7068 + vertex 690.159 335.06 88.6819 + vertex 688.515 318.949 95.8059 + endloop + endfacet + facet normal 0.992654 -0.0545266 0.108001 + outer loop + vertex 687.612 302.586 95.8418 + vertex 689.262 318.478 88.7068 + vertex 688.515 318.949 95.8059 + endloop + endfacet + facet normal 0.995088 -0.0547166 0.0825021 + outer loop + vertex 687.612 302.586 95.8418 + vertex 688.515 318.949 95.8059 + vertex 687.05 303.219 103.044 + endloop + endfacet + facet normal 0.995293 -0.0513095 0.082219 + outer loop + vertex 686.205 286.978 103.143 + vertex 687.612 302.586 95.8418 + vertex 687.05 303.219 103.044 + endloop + endfacet + facet normal 0.995036 -0.0493093 0.0864457 + outer loop + vertex 686.792 286.201 95.944 + vertex 687.612 302.586 95.8418 + vertex 686.205 286.978 103.143 + endloop + endfacet + facet normal 0.995462 -0.0414929 0.085637 + outer loop + vertex 685.511 270.592 103.266 + vertex 686.792 286.201 95.944 + vertex 686.205 286.978 103.143 + endloop + endfacet + facet normal 0.997008 -0.0417132 0.0650758 + outer loop + vertex 685.511 270.592 103.266 + vertex 686.205 286.978 103.143 + vertex 685.074 271.597 110.604 + endloop + endfacet + facet normal 0.997556 -0.029348 0.0634144 + outer loop + vertex 684.584 254.876 110.576 + vertex 685.511 270.592 103.266 + vertex 685.074 271.597 110.604 + endloop + endfacet + facet normal 0.997381 -0.0277696 0.0667857 + outer loop + vertex 685.043 253.698 103.233 + vertex 685.511 270.592 103.266 + vertex 684.584 254.876 110.576 + endloop + endfacet + facet normal 0.997738 -0.0168985 0.0650633 + outer loop + vertex 684.31 237.291 110.208 + vertex 685.043 253.698 103.233 + vertex 684.584 254.876 110.576 + endloop + endfacet + facet normal 0.998745 -0.0165412 0.0472655 + outer loop + vertex 684.31 237.291 110.208 + vertex 684.584 254.876 110.576 + vertex 683.979 238.591 117.663 + endloop + endfacet + facet normal 0.99881 -0.0137727 0.0467855 + outer loop + vertex 683.762 220.162 116.865 + vertex 684.31 237.291 110.208 + vertex 683.979 238.591 117.663 + endloop + endfacet + facet normal 0.998713 -0.0128882 0.0490534 + outer loop + vertex 684.109 218.712 109.427 + vertex 684.31 237.291 110.208 + vertex 683.762 220.162 116.865 + endloop + endfacet + facet normal 0.998379 -0.0246126 0.0513234 + outer loop + vertex 684.109 218.712 109.427 + vertex 683.762 220.162 116.865 + vertex 683.56 207.65 114.791 + endloop + endfacet + facet normal 0.998488 -0.0260261 0.0484198 + outer loop + vertex 683.665 205.143 111.289 + vertex 684.109 218.712 109.427 + vertex 683.56 207.65 114.791 + endloop + endfacet + facet normal 0.996407 -0.0519353 0.0669035 + outer loop + vertex 683.038 196.909 114.236 + vertex 683.665 205.143 111.289 + vertex 683.56 207.65 114.791 + endloop + endfacet + facet normal 0.997428 -0.0511237 0.0502432 + outer loop + vertex 683.038 196.909 114.236 + vertex 683.56 207.65 114.791 + vertex 682.891 197.712 117.973 + endloop + endfacet + facet normal 0.99777 -0.0552312 0.0374853 + outer loop + vertex 682.891 197.712 117.973 + vertex 683.56 207.65 114.791 + vertex 683.359 206.71 118.755 + endloop + endfacet + facet normal 0.997529 -0.0556839 0.0428399 + outer loop + vertex 682.891 197.712 117.973 + vertex 683.359 206.71 118.755 + vertex 682.772 198.478 121.734 + endloop + endfacet + facet normal 0.997256 -0.0521518 0.0525452 + outer loop + vertex 682.772 198.478 121.734 + vertex 683.359 206.71 118.755 + vertex 683.3 209.158 122.312 + endloop + endfacet + facet normal 0.997985 -0.0513611 0.037258 + outer loop + vertex 682.772 198.478 121.734 + vertex 683.3 209.158 122.312 + vertex 682.667 199.214 125.559 + endloop + endfacet + facet normal 0.998151 -0.0552821 0.0252805 + outer loop + vertex 682.667 199.214 125.559 + vertex 683.3 209.158 122.312 + vertex 683.142 208.174 126.378 + endloop + endfacet + facet normal 0.999106 -0.025141 0.0339854 + outer loop + vertex 683.359 206.71 118.755 + vertex 683.762 220.162 116.865 + vertex 683.3 209.158 122.312 + endloop + endfacet + facet normal 0.999044 -0.0238138 0.0366612 + outer loop + vertex 683.762 220.162 116.865 + vertex 683.517 221.562 124.456 + vertex 683.3 209.158 122.312 + endloop + endfacet + facet normal 0.996796 -0.0551847 0.0579067 + outer loop + vertex 683.209 196.08 110.494 + vertex 683.665 205.143 111.289 + vertex 683.038 196.909 114.236 + endloop + endfacet + facet normal 0.996954 -0.0549668 0.0553306 + outer loop + vertex 683.209 196.08 110.494 + vertex 683.934 206.071 107.354 + vertex 683.665 205.143 111.289 + endloop + endfacet + facet normal 0.99636 -0.0508009 0.0684475 + outer loop + vertex 683.423 195.244 106.757 + vertex 683.934 206.071 107.354 + vertex 683.209 196.08 110.494 + endloop + endfacet + facet normal 0.994665 -0.0518627 0.0891688 + outer loop + vertex 683.423 195.244 106.757 + vertex 684.115 203.564 103.878 + vertex 683.934 206.071 107.354 + endloop + endfacet + facet normal 0.997053 -0.0274046 0.0716489 + outer loop + vertex 684.115 203.564 103.878 + vertex 684.62 217.172 102.054 + vertex 683.934 206.071 107.354 + endloop + endfacet + facet normal 0.996875 -0.025987 0.0745949 + outer loop + vertex 684.62 217.172 102.054 + vertex 684.109 218.712 109.427 + vertex 683.934 206.071 107.354 + endloop + endfacet + facet normal 0.997339 -0.0125235 0.0718154 + outer loop + vertex 684.62 217.172 102.054 + vertex 684.798 235.914 102.849 + vertex 684.109 218.712 109.427 + endloop + endfacet + facet normal 0.994469 -0.013866 0.104109 + outer loop + vertex 684.62 217.172 102.054 + vertex 685.55 234.131 95.4354 + vertex 684.798 235.914 102.849 + endloop + endfacet + facet normal 0.994501 -0.0130257 0.10391 + outer loop + vertex 685.55 234.131 95.4354 + vertex 685.741 252.234 95.8758 + vertex 684.798 235.914 102.849 + endloop + endfacet + facet normal 0.995107 -0.0157844 0.0975353 + outer loop + vertex 684.798 235.914 102.849 + vertex 685.741 252.234 95.8758 + vertex 685.043 253.698 103.233 + endloop + endfacet + facet normal 0.99479 -0.0238739 0.0991141 + outer loop + vertex 685.741 252.234 95.8758 + vertex 686.143 269.529 96.0087 + vertex 685.043 253.698 103.233 + endloop + endfacet + facet normal 0.990664 -0.0240476 0.134185 + outer loop + vertex 685.741 252.234 95.8758 + vertex 687.107 267.836 88.5858 + vertex 686.143 269.529 96.0087 + endloop + endfacet + facet normal 0.990143 -0.0329145 0.136138 + outer loop + vertex 687.107 267.836 88.5858 + vertex 687.658 285.135 88.7574 + vertex 686.143 269.529 96.0087 + endloop + endfacet + facet normal 0.991396 -0.0381046 0.12523 + outer loop + vertex 686.143 269.529 96.0087 + vertex 687.658 285.135 88.7574 + vertex 686.792 286.201 95.944 + endloop + endfacet + facet normal 0.991036 -0.0441585 0.126085 + outer loop + vertex 687.658 285.135 88.7574 + vertex 688.407 301.932 88.7527 + vertex 686.792 286.201 95.944 + endloop + endfacet + facet normal 0.984884 -0.0438726 0.167569 + outer loop + vertex 687.658 285.135 88.7574 + vertex 689.566 300.695 81.6186 + vertex 688.407 301.932 88.7527 + endloop + endfacet + facet normal 0.984784 -0.04525 0.167791 + outer loop + vertex 689.566 300.695 81.6186 + vertex 690.343 317.661 81.6346 + vertex 688.407 301.932 88.7527 + endloop + endfacet + facet normal 0.986364 -0.0504887 0.156645 + outer loop + vertex 688.407 301.932 88.7527 + vertex 690.343 317.661 81.6346 + vertex 689.262 318.478 88.7068 + endloop + endfacet + facet normal 0.986467 -0.0489443 0.156482 + outer loop + vertex 690.343 317.661 81.6346 + vertex 691.187 334.495 81.5766 + vertex 689.262 318.478 88.7068 + endloop + endfacet + facet normal 0.976914 -0.0482872 0.208105 + outer loop + vertex 690.343 317.661 81.6346 + vertex 692.651 333.188 74.4048 + vertex 691.187 334.495 81.5766 + endloop + endfacet + facet normal 0.977111 -0.0459212 0.207714 + outer loop + vertex 692.651 333.188 74.4048 + vertex 693.481 350.689 74.3668 + vertex 691.187 334.495 81.5766 + endloop + endfacet + facet normal 0.979314 -0.0516021 0.195655 + outer loop + vertex 691.187 334.495 81.5766 + vertex 693.481 350.689 74.3668 + vertex 692.095 351.519 81.5223 + endloop + endfacet + facet normal 0.978752 -0.058928 0.196396 + outer loop + vertex 693.481 350.689 74.3668 + vertex 694.541 368.529 74.4393 + vertex 692.095 351.519 81.5223 + endloop + endfacet + facet normal 0.968224 -0.0584929 0.243148 + outer loop + vertex 693.481 350.689 74.3668 + vertex 696.199 367.664 67.627 + vertex 694.541 368.529 74.4393 + endloop + endfacet + facet normal 0.966444 -0.0770008 0.245064 + outer loop + vertex 696.199 367.664 67.627 + vertex 697.665 386.627 67.804 + vertex 694.541 368.529 74.4393 + endloop + endfacet + facet normal 0.973743 -0.0917184 0.208357 + outer loop + vertex 694.541 368.529 74.4393 + vertex 697.665 386.627 67.804 + vertex 696.184 386.594 74.7094 + endloop + endfacet + facet normal 0.979305 -0.0918061 0.180368 + outer loop + vertex 694.541 368.529 74.4393 + vertex 696.184 386.594 74.7094 + vertex 693.266 368.855 81.5274 + endloop + endfacet + facet normal 0.963987 -0.0506967 0.261074 + outer loop + vertex 695.378 348.945 67.0244 + vertex 696.199 367.664 67.627 + vertex 693.481 350.689 74.3668 + endloop + endfacet + facet normal 0.96457 -0.0452126 0.259922 + outer loop + vertex 692.651 333.188 74.4048 + vertex 695.378 348.945 67.0244 + vertex 693.481 350.689 74.3668 + endloop + endfacet + facet normal 0.960951 -0.037943 0.274105 + outer loop + vertex 694.611 330.735 67.1909 + vertex 695.378 348.945 67.0244 + vertex 692.651 333.188 74.4048 + endloop + endfacet + facet normal 0.960492 -0.0415113 0.275194 + outer loop + vertex 691.887 315.974 74.4728 + vertex 694.611 330.735 67.1909 + vertex 692.651 333.188 74.4048 + endloop + endfacet + facet normal 0.956549 -0.0336656 0.289622 + outer loop + vertex 693.994 313.468 67.2233 + vertex 694.611 330.735 67.1909 + vertex 691.887 315.974 74.4728 + endloop + endfacet + facet normal 0.95601 -0.0377843 0.290889 + outer loop + vertex 691.234 298.429 74.341 + vertex 693.994 313.468 67.2233 + vertex 691.887 315.974 74.4728 + endloop + endfacet + facet normal 0.952025 -0.0306191 0.304484 + outer loop + vertex 693.491 295.81 67.0191 + vertex 693.994 313.468 67.2233 + vertex 691.234 298.429 74.341 + endloop + endfacet + facet normal 0.951212 -0.0365711 0.306362 + outer loop + vertex 690.636 279.444 73.9296 + vertex 693.491 295.81 67.0191 + vertex 691.234 298.429 74.341 + endloop + endfacet + facet normal 0.946312 -0.0291391 0.321939 + outer loop + vertex 693.079 277.283 66.5549 + vertex 693.491 295.81 67.0191 + vertex 690.636 279.444 73.9296 + endloop + endfacet + facet normal 0.9441 -0.0466651 0.32634 + outer loop + vertex 693.079 277.283 66.5549 + vertex 690.636 279.444 73.9296 + vertex 690.727 267.309 71.9318 + endloop + endfacet + facet normal 0.941985 -0.0426096 0.332939 + outer loop + vertex 691.768 264.066 68.5704 + vertex 693.079 277.283 66.5549 + vertex 690.727 267.309 71.9318 + endloop + endfacet + facet normal 0.946805 -0.0282395 0.320567 + outer loop + vertex 690.516 256.921 71.639 + vertex 691.768 264.066 68.5704 + vertex 690.727 267.309 71.9318 + endloop + endfacet + facet normal 0.961464 -0.0272124 0.273583 + outer loop + vertex 690.516 256.921 71.639 + vertex 690.727 267.309 71.9318 + vertex 689.39 258.838 75.7891 + endloop + endfacet + facet normal 0.962633 -0.0190708 0.270138 + outer loop + vertex 689.475 249.891 74.8543 + vertex 690.516 256.921 71.639 + vertex 689.39 258.838 75.7891 + endloop + endfacet + facet normal 0.959124 -0.012808 0.282695 + outer loop + vertex 690.461 247.662 71.4057 + vertex 690.516 256.921 71.639 + vertex 689.475 249.891 74.8543 + endloop + endfacet + facet normal 0.960573 -0.00488074 0.277986 + outer loop + vertex 689.258 240.433 75.4357 + vertex 690.461 247.662 71.4057 + vertex 689.475 249.891 74.8543 + endloop + endfacet + facet normal 0.961251 -0.0063234 0.275601 + outer loop + vertex 690.42 238.84 71.3495 + vertex 690.461 247.662 71.4057 + vertex 689.258 240.433 75.4357 + endloop + endfacet + facet normal 0.961169 -0.00707317 0.275869 + outer loop + vertex 689.407 232.077 74.7032 + vertex 690.42 238.84 71.3495 + vertex 689.258 240.433 75.4357 + endloop + endfacet + facet normal 0.958046 -0.00127747 0.286613 + outer loop + vertex 690.398 230.232 71.3829 + vertex 690.42 238.84 71.3495 + vertex 689.407 232.077 74.7032 + endloop + endfacet + facet normal 0.958395 0.00101459 0.285443 + outer loop + vertex 689.228 222.853 75.3362 + vertex 690.398 230.232 71.3829 + vertex 689.407 232.077 74.7032 + endloop + endfacet + facet normal 0.957437 0.0028728 0.288628 + outer loop + vertex 690.417 221.652 71.4064 + vertex 690.398 230.232 71.3829 + vertex 689.228 222.853 75.3362 + endloop + endfacet + facet normal 0.956876 -0.00371537 0.290471 + outer loop + vertex 689.43 214.69 74.5693 + vertex 690.417 221.652 71.4064 + vertex 689.228 222.853 75.3362 + endloop + endfacet + facet normal 0.953202 0.00219068 0.302325 + outer loop + vertex 690.454 213.013 71.3504 + vertex 690.417 221.652 71.4064 + vertex 689.43 214.69 74.5693 + endloop + endfacet + facet normal 0.951515 -0.00873086 0.307479 + outer loop + vertex 689.233 205.776 74.9231 + vertex 690.454 213.013 71.3504 + vertex 689.43 214.69 74.5693 + endloop + endfacet + facet normal 0.950971 -0.00779861 0.309181 + outer loop + vertex 690.422 203.899 71.2201 + vertex 690.454 213.013 71.3504 + vertex 689.233 205.776 74.9231 + endloop + endfacet + facet normal 0.946847 -0.0319422 0.320094 + outer loop + vertex 689.096 195.545 74.3088 + vertex 690.422 203.899 71.2201 + vertex 689.233 205.776 74.9231 + endloop + endfacet + facet normal 0.957564 -0.0300784 0.286648 + outer loop + vertex 689.096 195.545 74.3088 + vertex 689.233 205.776 74.9231 + vertex 688.004 197.114 78.1205 + endloop + endfacet + facet normal 0.953022 -0.0587421 0.297149 + outer loop + vertex 687.667 186.448 77.0941 + vertex 689.096 195.545 74.3088 + vertex 688.004 197.114 78.1205 + endloop + endfacet + facet normal 0.963739 -0.0556015 0.260989 + outer loop + vertex 687.667 186.448 77.0941 + vertex 688.004 197.114 78.1205 + vertex 686.745 187.351 80.6889 + endloop + endfacet + facet normal 0.967017 -0.0595321 0.247656 + outer loop + vertex 686.745 187.351 80.6889 + vertex 688.004 197.114 78.1205 + vertex 687.076 196.734 81.6517 + endloop + endfacet + facet normal 0.973979 -0.0568767 0.219385 + outer loop + vertex 686.745 187.351 80.6889 + vertex 687.076 196.734 81.6517 + vertex 685.997 188.507 84.3114 + endloop + endfacet + facet normal 0.973349 -0.0558076 0.222436 + outer loop + vertex 685.997 188.507 84.3114 + vertex 687.076 196.734 81.6517 + vertex 686.462 199.782 85.1035 + endloop + endfacet + facet normal 0.980606 -0.0537219 0.188484 + outer loop + vertex 685.997 188.507 84.3114 + vertex 686.462 199.782 85.1035 + vertex 685.325 189.587 88.1153 + endloop + endfacet + facet normal 0.982216 -0.0567067 0.178988 + outer loop + vertex 685.325 189.587 88.1153 + vertex 686.462 199.782 85.1035 + vertex 685.719 199.544 89.1054 + endloop + endfacet + facet normal 0.984561 -0.0555087 0.166004 + outer loop + vertex 685.325 189.587 88.1153 + vertex 685.719 199.544 89.1054 + vertex 684.788 191.51 91.9457 + endloop + endfacet + facet normal 0.984625 -0.0556684 0.165573 + outer loop + vertex 684.788 191.51 91.9457 + vertex 685.719 199.544 89.1054 + vertex 685.297 202.603 92.6438 + endloop + endfacet + facet normal 0.989672 -0.0538415 0.132856 + outer loop + vertex 684.788 191.51 91.9457 + vertex 685.297 202.603 92.6438 + vertex 684.349 192.738 95.7103 + endloop + endfacet + facet normal 0.990616 -0.0565534 0.124424 + outer loop + vertex 684.349 192.738 95.7103 + vertex 685.297 202.603 92.6438 + vertex 684.768 201.959 96.5641 + endloop + endfacet + facet normal 0.99218 -0.0554573 0.111819 + outer loop + vertex 684.349 192.738 95.7103 + vertex 684.768 201.959 96.5641 + vertex 683.985 193.642 99.3893 + endloop + endfacet + facet normal 0.991463 -0.0528905 0.119176 + outer loop + vertex 683.985 193.642 99.3893 + vertex 684.768 201.959 96.5641 + vertex 684.491 204.508 100 + endloop + endfacet + facet normal 0.994116 -0.0516666 0.0952012 + outer loop + vertex 683.985 193.642 99.3893 + vertex 684.491 204.508 100 + vertex 683.675 194.433 103.053 + endloop + endfacet + facet normal 0.995009 -0.0554462 0.0829674 + outer loop + vertex 683.675 194.433 103.053 + vertex 684.491 204.508 100 + vertex 684.115 203.564 103.878 + endloop + endfacet + facet normal 0.994143 -0.0313587 0.103421 + outer loop + vertex 684.768 201.959 96.5641 + vertex 685.387 215.33 94.6745 + vertex 684.491 204.508 100 + endloop + endfacet + facet normal 0.993521 -0.0279955 0.110151 + outer loop + vertex 685.387 215.33 94.6745 + vertex 684.62 217.172 102.054 + vertex 684.491 204.508 100 + endloop + endfacet + facet normal 0.991226 -0.0275711 0.129268 + outer loop + vertex 684.768 201.959 96.5641 + vertex 685.297 202.603 92.6438 + vertex 685.387 215.33 94.6745 + endloop + endfacet + facet normal 0.987314 -0.0317415 0.155576 + outer loop + vertex 686.487 212.811 87.1798 + vertex 685.387 215.33 94.6745 + vertex 685.297 202.603 92.6438 + endloop + endfacet + facet normal 0.98866 -0.0133219 0.149582 + outer loop + vertex 686.487 212.811 87.1798 + vertex 686.637 231.558 87.8566 + vertex 685.387 215.33 94.6745 + endloop + endfacet + facet normal 0.989059 -0.014521 0.146801 + outer loop + vertex 685.387 215.33 94.6745 + vertex 686.637 231.558 87.8566 + vertex 685.55 234.131 95.4354 + endloop + endfacet + facet normal 0.989263 -0.0112417 0.145716 + outer loop + vertex 686.637 231.558 87.8566 + vertex 686.783 249.939 88.2844 + vertex 685.55 234.131 95.4354 + endloop + endfacet + facet normal 0.983397 -0.0120178 0.181069 + outer loop + vertex 686.637 231.558 87.8566 + vertex 688.179 246.424 80.468 + vertex 686.783 249.939 88.2844 + endloop + endfacet + facet normal 0.982754 -0.01872 0.183968 + outer loop + vertex 688.179 246.424 80.468 + vertex 688.504 264.994 80.6192 + vertex 686.783 249.939 88.2844 + endloop + endfacet + facet normal 0.983456 -0.0208496 0.179943 + outer loop + vertex 686.783 249.939 88.2844 + vertex 688.504 264.994 80.6192 + vertex 687.107 267.836 88.5858 + endloop + endfacet + facet normal 0.982587 -0.0305937 0.183266 + outer loop + vertex 688.504 264.994 80.6192 + vertex 688.926 283.101 81.3786 + vertex 687.107 267.836 88.5858 + endloop + endfacet + facet normal 0.98199 -0.00804881 0.188761 + outer loop + vertex 688.087 228.229 80.1691 + vertex 688.179 246.424 80.468 + vertex 686.637 231.558 87.8566 + endloop + endfacet + facet normal 0.98137 -0.014779 0.191558 + outer loop + vertex 686.487 212.811 87.1798 + vertex 688.087 228.229 80.1691 + vertex 686.637 231.558 87.8566 + endloop + endfacet + facet normal 0.979578 -0.0103936 0.200794 + outer loop + vertex 687.986 209.981 79.7182 + vertex 688.087 228.229 80.1691 + vertex 686.487 212.811 87.1798 + endloop + endfacet + facet normal 0.977126 -0.0352299 0.209722 + outer loop + vertex 687.986 209.981 79.7182 + vertex 686.487 212.811 87.1798 + vertex 686.462 199.782 85.1035 + endloop + endfacet + facet normal 0.988253 -0.0355694 0.14863 + outer loop + vertex 685.719 199.544 89.1054 + vertex 686.487 212.811 87.1798 + vertex 685.297 202.603 92.6438 + endloop + endfacet + facet normal 0.983063 -0.0306151 0.180695 + outer loop + vertex 685.719 199.544 89.1054 + vertex 686.462 199.782 85.1035 + vertex 686.487 212.811 87.1798 + endloop + endfacet + facet normal 0.977729 -0.0369752 0.206587 + outer loop + vertex 687.076 196.734 81.6517 + vertex 687.986 209.981 79.7182 + vertex 686.462 199.782 85.1035 + endloop + endfacet + facet normal 0.967532 -0.0297938 0.250988 + outer loop + vertex 687.076 196.734 81.6517 + vertex 688.004 197.114 78.1205 + vertex 687.986 209.981 79.7182 + endloop + endfacet + facet normal 0.952266 -0.0578291 0.299743 + outer loop + vertex 688.728 185.384 73.5185 + vertex 689.096 195.545 74.3088 + vertex 687.667 186.448 77.0941 + endloop + endfacet + facet normal 0.939961 -0.0601982 0.335931 + outer loop + vertex 688.728 185.384 73.5185 + vertex 690.286 194.345 70.7653 + vertex 689.096 195.545 74.3088 + endloop + endfacet + facet normal 0.938218 -0.0583085 0.341096 + outer loop + vertex 689.934 184.528 70.0541 + vertex 690.286 194.345 70.7653 + vertex 688.728 185.384 73.5185 + endloop + endfacet + facet normal 0.959756 -0.0332654 0.278857 + outer loop + vertex 688.004 197.114 78.1205 + vertex 689.233 205.776 74.9231 + vertex 687.986 209.981 79.7182 + endloop + endfacet + facet normal 0.965359 -0.010892 0.260697 + outer loop + vertex 689.43 214.69 74.5693 + vertex 687.986 209.981 79.7182 + vertex 689.233 205.776 74.9231 + endloop + endfacet + facet normal 0.963228 -0.00151154 0.26868 + outer loop + vertex 689.43 214.69 74.5693 + vertex 689.228 222.853 75.3362 + vertex 687.986 209.981 79.7182 + endloop + endfacet + facet normal 0.970269 -0.0113543 0.241762 + outer loop + vertex 688.087 228.229 80.1691 + vertex 687.986 209.981 79.7182 + vertex 689.228 222.853 75.3362 + endloop + endfacet + facet normal 0.972508 -0.00286813 0.232851 + outer loop + vertex 689.407 232.077 74.7032 + vertex 688.087 228.229 80.1691 + vertex 689.228 222.853 75.3362 + endloop + endfacet + facet normal 0.972542 -0.00308679 0.232705 + outer loop + vertex 689.407 232.077 74.7032 + vertex 689.258 240.433 75.4357 + vertex 688.087 228.229 80.1691 + endloop + endfacet + facet normal 0.975587 -0.00852071 0.219449 + outer loop + vertex 688.179 246.424 80.468 + vertex 688.087 228.229 80.1691 + vertex 689.258 240.433 75.4357 + endloop + endfacet + facet normal 0.975513 -0.0088012 0.219767 + outer loop + vertex 689.475 249.891 74.8543 + vertex 688.179 246.424 80.468 + vertex 689.258 240.433 75.4357 + endloop + endfacet + facet normal 0.976067 -0.013397 0.217057 + outer loop + vertex 689.475 249.891 74.8543 + vertex 689.39 258.838 75.7891 + vertex 688.179 246.424 80.468 + endloop + endfacet + facet normal 0.978909 -0.018811 0.203428 + outer loop + vertex 688.504 264.994 80.6192 + vertex 688.179 246.424 80.468 + vertex 689.39 258.838 75.7891 + endloop + endfacet + facet normal 0.977146 -0.0250726 0.211086 + outer loop + vertex 689.67 267.719 75.5466 + vertex 688.504 264.994 80.6192 + vertex 689.39 258.838 75.7891 + endloop + endfacet + facet normal 0.979097 -0.0536359 0.196193 + outer loop + vertex 689.67 267.719 75.5466 + vertex 690.636 279.444 73.9296 + vertex 688.504 264.994 80.6192 + endloop + endfacet + facet normal 0.970518 -0.0326417 0.238806 + outer loop + vertex 688.504 264.994 80.6192 + vertex 690.636 279.444 73.9296 + vertex 688.926 283.101 81.3786 + endloop + endfacet + facet normal 0.970061 -0.035731 0.240218 + outer loop + vertex 690.636 279.444 73.9296 + vertex 691.234 298.429 74.341 + vertex 688.926 283.101 81.3786 + endloop + endfacet + facet normal 0.971335 -0.0385144 0.234574 + outer loop + vertex 688.926 283.101 81.3786 + vertex 691.234 298.429 74.341 + vertex 689.566 300.695 81.6186 + endloop + endfacet + facet normal 0.971398 -0.0379328 0.234407 + outer loop + vertex 691.234 298.429 74.341 + vertex 691.887 315.974 74.4728 + vertex 689.566 300.695 81.6186 + endloop + endfacet + facet normal 0.944597 -0.0290526 0.326944 + outer loop + vertex 690.286 194.345 70.7653 + vertex 690.422 203.899 71.2201 + vertex 689.096 195.545 74.3088 + endloop + endfacet + facet normal 0.939239 -0.00101042 0.343261 + outer loop + vertex 690.398 230.232 71.3829 + vertex 691.675 237.688 67.9105 + vertex 690.42 238.84 71.3495 + endloop + endfacet + facet normal 0.938831 -0.00469069 0.344345 + outer loop + vertex 691.675 237.688 67.9105 + vertex 691.719 246.355 67.909 + vertex 690.42 238.84 71.3495 + endloop + endfacet + facet normal 0.93836 0.000257253 0.34566 + outer loop + vertex 691.656 229.153 67.9693 + vertex 691.675 237.688 67.9105 + vertex 690.398 230.232 71.3829 + endloop + endfacet + facet normal 0.938635 0.00298559 0.344899 + outer loop + vertex 690.417 221.652 71.4064 + vertex 691.656 229.153 67.9693 + vertex 690.398 230.232 71.3829 + endloop + endfacet + facet normal 0.936619 0.00579358 0.3503 + outer loop + vertex 691.693 220.596 68.0124 + vertex 691.656 229.153 67.9693 + vertex 690.417 221.652 71.4064 + endloop + endfacet + facet normal 0.936225 0.00179909 0.351395 + outer loop + vertex 690.454 213.013 71.3504 + vertex 691.693 220.596 68.0124 + vertex 690.417 221.652 71.4064 + endloop + endfacet + facet normal 0.934271 0.00438141 0.356537 + outer loop + vertex 691.739 211.89 67.9988 + vertex 691.693 220.596 68.0124 + vertex 690.454 213.013 71.3504 + endloop + endfacet + facet normal 0.932806 -0.00846512 0.360279 + outer loop + vertex 690.422 203.899 71.2201 + vertex 691.739 211.89 67.9988 + vertex 690.454 213.013 71.3504 + endloop + endfacet + facet normal 0.930793 -0.00603005 0.365497 + outer loop + vertex 691.74 202.934 67.8486 + vertex 691.739 211.89 67.9988 + vertex 690.422 203.899 71.2201 + endloop + endfacet + facet normal 0.927916 -0.030935 0.371504 + outer loop + vertex 690.286 194.345 70.7653 + vertex 691.74 202.934 67.8486 + vertex 690.422 203.899 71.2201 + endloop + endfacet + facet normal 0.925226 -0.0281481 0.37837 + outer loop + vertex 691.619 193.619 67.4513 + vertex 691.74 202.934 67.8486 + vertex 690.286 194.345 70.7653 + endloop + endfacet + facet normal 0.921343 -0.0608098 0.383964 + outer loop + vertex 689.934 184.528 70.0541 + vertex 691.619 193.619 67.4513 + vertex 690.286 194.345 70.7653 + endloop + endfacet + facet normal 0.918467 -0.058208 0.39119 + outer loop + vertex 691.294 183.891 66.765 + vertex 691.619 193.619 67.4513 + vertex 689.934 184.528 70.0541 + endloop + endfacet + facet normal 0.940183 -0.00663712 0.340604 + outer loop + vertex 690.42 238.84 71.3495 + vertex 691.719 246.355 67.909 + vertex 690.461 247.662 71.4057 + endloop + endfacet + facet normal 0.939631 -0.0109453 0.342015 + outer loop + vertex 691.719 246.355 67.909 + vertex 691.751 255.381 68.1088 + vertex 690.461 247.662 71.4057 + endloop + endfacet + facet normal 0.913652 -0.0122754 0.406312 + outer loop + vertex 691.719 246.355 67.909 + vertex 693.218 254.697 64.79 + vertex 691.751 255.381 68.1088 + endloop + endfacet + facet normal 0.913191 -0.0173814 0.40716 + outer loop + vertex 693.218 254.697 64.79 + vertex 693.217 264.521 65.2125 + vertex 691.751 255.381 68.1088 + endloop + endfacet + facet normal 0.919107 -0.0227048 0.393353 + outer loop + vertex 691.751 255.381 68.1088 + vertex 693.217 264.521 65.2125 + vertex 691.768 264.066 68.5704 + endloop + endfacet + facet normal 0.919315 -0.0313144 0.392275 + outer loop + vertex 691.768 264.066 68.5704 + vertex 693.217 264.521 65.2125 + vertex 693.079 277.283 66.5549 + endloop + endfacet + facet normal 0.905386 -0.0347143 0.423168 + outer loop + vertex 693.217 264.521 65.2125 + vertex 695.018 273.376 62.0861 + vertex 693.079 277.283 66.5549 + endloop + endfacet + facet normal 0.910247 -0.021269 0.41352 + outer loop + vertex 695.41 282.562 61.694 + vertex 693.079 277.283 66.5549 + vertex 695.018 273.376 62.0861 + endloop + endfacet + facet normal 0.909647 -0.0197204 0.414914 + outer loop + vertex 695.41 282.562 61.694 + vertex 695.242 290.973 62.4636 + vertex 693.079 277.283 66.5549 + endloop + endfacet + facet normal 0.921882 -0.0302077 0.386292 + outer loop + vertex 693.491 295.81 67.0191 + vertex 693.079 277.283 66.5549 + vertex 695.242 290.973 62.4636 + endloop + endfacet + facet normal 0.924512 -0.0237212 0.380414 + outer loop + vertex 695.693 300.565 61.9654 + vertex 693.491 295.81 67.0191 + vertex 695.242 290.973 62.4636 + endloop + endfacet + facet normal 0.924129 -0.0224753 0.381419 + outer loop + vertex 695.693 300.565 61.9654 + vertex 695.598 308.675 62.6727 + vertex 693.491 295.81 67.0191 + endloop + endfacet + facet normal 0.93209 -0.0307042 0.360923 + outer loop + vertex 693.994 313.468 67.2233 + vertex 693.491 295.81 67.0191 + vertex 695.598 308.675 62.6727 + endloop + endfacet + facet normal 0.932954 -0.0284639 0.358868 + outer loop + vertex 696.103 317.616 62.0701 + vertex 693.994 313.468 67.2233 + vertex 695.598 308.675 62.6727 + endloop + endfacet + facet normal 0.932251 -0.0255716 0.360908 + outer loop + vertex 696.103 317.616 62.0701 + vertex 696.084 325.504 62.6778 + vertex 693.994 313.468 67.2233 + endloop + endfacet + facet normal 0.938299 -0.0329107 0.344255 + outer loop + vertex 694.611 330.735 67.1909 + vertex 693.994 313.468 67.2233 + vertex 696.084 325.504 62.6778 + endloop + endfacet + facet normal 0.939455 -0.0300775 0.341349 + outer loop + vertex 696.634 334.747 61.9771 + vertex 694.611 330.735 67.1909 + vertex 696.084 325.504 62.6778 + endloop + endfacet + facet normal 0.938409 -0.0253289 0.344597 + outer loop + vertex 696.634 334.747 61.9771 + vertex 696.615 343.489 62.6732 + vertex 694.611 330.735 67.1909 + endloop + endfacet + facet normal 0.948076 -0.0370189 0.315882 + outer loop + vertex 695.378 348.945 67.0244 + vertex 694.611 330.735 67.1909 + vertex 696.615 343.489 62.6732 + endloop + endfacet + facet normal 0.950042 -0.0322437 0.310453 + outer loop + vertex 697.005 352.48 62.4122 + vertex 695.378 348.945 67.0244 + vertex 696.615 343.489 62.6732 + endloop + endfacet + facet normal 0.954332 -0.0565324 0.29335 + outer loop + vertex 697.005 352.48 62.4122 + vertex 698.069 365.616 61.4815 + vertex 695.378 348.945 67.0244 + endloop + endfacet + facet normal 0.950496 -0.051565 0.306428 + outer loop + vertex 695.378 348.945 67.0244 + vertex 698.069 365.616 61.4815 + vertex 696.199 367.664 67.627 + endloop + endfacet + facet normal 0.948386 -0.0652219 0.310338 + outer loop + vertex 698.069 365.616 61.4815 + vertex 699.309 386.648 62.1142 + vertex 696.199 367.664 67.627 + endloop + endfacet + facet normal 0.957973 -0.0766386 0.27643 + outer loop + vertex 696.199 367.664 67.627 + vertex 699.309 386.648 62.1142 + vertex 697.665 386.627 67.804 + endloop + endfacet + facet normal 0.888228 -0.0185633 0.459027 + outer loop + vertex 694.948 263.406 61.8183 + vertex 695.018 273.376 62.0861 + vertex 693.217 264.521 65.2125 + endloop + endfacet + facet normal 0.888067 -0.0196272 0.459295 + outer loop + vertex 693.218 254.697 64.79 + vertex 694.948 263.406 61.8183 + vertex 693.217 264.521 65.2125 + endloop + endfacet + facet normal 0.879165 -0.0120348 0.476366 + outer loop + vertex 694.898 254.175 61.6757 + vertex 694.948 263.406 61.8183 + vertex 693.218 254.697 64.79 + endloop + endfacet + facet normal 0.879371 -0.0094446 0.476044 + outer loop + vertex 693.176 245.742 64.6907 + vertex 694.898 254.175 61.6757 + vertex 693.218 254.697 64.79 + endloop + endfacet + facet normal 0.874917 -0.00560471 0.48424 + outer loop + vertex 694.849 245.457 61.6648 + vertex 694.898 254.175 61.6757 + vertex 693.176 245.742 64.6907 + endloop + endfacet + facet normal 0.875026 -0.00312583 0.484066 + outer loop + vertex 693.132 237.152 64.7149 + vertex 694.849 245.457 61.6648 + vertex 693.176 245.742 64.6907 + endloop + endfacet + facet normal 0.872352 -0.000806278 0.488877 + outer loop + vertex 694.827 236.901 61.6894 + vertex 694.849 245.457 61.6648 + vertex 693.132 237.152 64.7149 + endloop + endfacet + facet normal 0.872494 0.00332972 0.488614 + outer loop + vertex 693.136 228.625 64.7652 + vertex 694.827 236.901 61.6894 + vertex 693.132 237.152 64.7149 + endloop + endfacet + facet normal 0.871441 0.0042394 0.490482 + outer loop + vertex 694.855 228.301 61.714 + vertex 694.827 236.901 61.6894 + vertex 693.136 228.625 64.7652 + endloop + endfacet + facet normal 0.871567 0.00738005 0.49022 + outer loop + vertex 693.187 220.029 64.8043 + vertex 694.855 228.301 61.714 + vertex 693.136 228.625 64.7652 + endloop + endfacet + facet normal 0.870088 0.00865015 0.492821 + outer loop + vertex 694.915 219.632 61.7596 + vertex 694.855 228.301 61.714 + vertex 693.187 220.029 64.8043 + endloop + endfacet + facet normal 0.869958 0.00602755 0.493089 + outer loop + vertex 693.245 211.338 64.8076 + vertex 694.915 219.632 61.7596 + vertex 693.187 220.029 64.8043 + endloop + endfacet + facet normal 0.868495 0.00726092 0.495644 + outer loop + vertex 694.966 210.894 61.7979 + vertex 694.915 219.632 61.7596 + vertex 693.245 211.338 64.8076 + endloop + endfacet + facet normal 0.867655 -0.0060713 0.49713 + outer loop + vertex 693.252 202.438 64.6878 + vertex 694.966 210.894 61.7979 + vertex 693.245 211.338 64.8076 + endloop + endfacet + facet normal 0.866492 -0.00514049 0.499164 + outer loop + vertex 694.968 202.005 61.7042 + vertex 694.966 210.894 61.7979 + vertex 693.252 202.438 64.6878 + endloop + endfacet + facet normal 0.86456 -0.0298765 0.501641 + outer loop + vertex 693.14 193.14 64.3262 + vertex 694.968 202.005 61.7042 + vertex 693.252 202.438 64.6878 + endloop + endfacet + facet normal 0.862223 -0.0281811 0.505744 + outer loop + vertex 694.863 192.711 61.3649 + vertex 694.968 202.005 61.7042 + vertex 693.14 193.14 64.3262 + endloop + endfacet + facet normal 0.858813 -0.0614657 0.508588 + outer loop + vertex 692.819 183.369 63.6871 + vertex 694.863 192.711 61.3649 + vertex 693.14 193.14 64.3262 + endloop + endfacet + facet normal 0.855306 -0.0591703 0.514734 + outer loop + vertex 694.548 182.916 60.7619 + vertex 694.863 192.711 61.3649 + vertex 692.819 183.369 63.6871 + endloop + endfacet + facet normal 0.910348 -0.00890058 0.413749 + outer loop + vertex 693.176 245.742 64.6907 + vertex 693.218 254.697 64.79 + vertex 691.719 246.355 67.909 + endloop + endfacet + facet normal 0.910687 -0.0045372 0.413072 + outer loop + vertex 691.675 237.688 67.9105 + vertex 693.176 245.742 64.6907 + vertex 691.719 246.355 67.909 + endloop + endfacet + facet normal 0.909715 -0.0034976 0.415219 + outer loop + vertex 693.132 237.152 64.7149 + vertex 693.176 245.742 64.6907 + vertex 691.675 237.688 67.9105 + endloop + endfacet + facet normal 0.909992 0.000797324 0.414626 + outer loop + vertex 691.656 229.153 67.9693 + vertex 693.132 237.152 64.7149 + vertex 691.675 237.688 67.9105 + endloop + endfacet + facet normal 0.907991 0.00293755 0.418979 + outer loop + vertex 693.136 228.625 64.7652 + vertex 693.132 237.152 64.7149 + vertex 691.656 229.153 67.9693 + endloop + endfacet + facet normal 0.908172 0.00601512 0.418555 + outer loop + vertex 691.693 220.596 68.0124 + vertex 693.136 228.625 64.7652 + vertex 691.656 229.153 67.9693 + endloop + endfacet + facet normal 0.906969 0.00727481 0.421134 + outer loop + vertex 693.187 220.029 64.8043 + vertex 693.136 228.625 64.7652 + vertex 691.693 220.596 68.0124 + endloop + endfacet + facet normal 0.906773 0.0041344 0.421598 + outer loop + vertex 691.739 211.89 67.9988 + vertex 693.187 220.029 64.8043 + vertex 691.693 220.596 68.0124 + endloop + endfacet + facet normal 0.904697 0.00623534 0.42601 + outer loop + vertex 693.245 211.338 64.8076 + vertex 693.187 220.029 64.8043 + vertex 691.739 211.89 67.9988 + endloop + endfacet + facet normal 0.903803 -0.00707972 0.427891 + outer loop + vertex 691.74 202.934 67.8486 + vertex 693.245 211.338 64.8076 + vertex 691.739 211.89 67.9988 + endloop + endfacet + facet normal 0.901782 -0.00517264 0.432161 + outer loop + vertex 693.252 202.438 64.6878 + vertex 693.245 211.338 64.8076 + vertex 691.74 202.934 67.8486 + endloop + endfacet + facet normal 0.899841 -0.0302412 0.435168 + outer loop + vertex 691.619 193.619 67.4513 + vertex 693.252 202.438 64.6878 + vertex 691.74 202.934 67.8486 + endloop + endfacet + facet normal 0.897081 -0.0279077 0.440983 + outer loop + vertex 693.14 193.14 64.3262 + vertex 693.252 202.438 64.6878 + vertex 691.619 193.619 67.4513 + endloop + endfacet + facet normal 0.89372 -0.0611396 0.444439 + outer loop + vertex 691.294 183.891 66.765 + vertex 693.14 193.14 64.3262 + vertex 691.619 193.619 67.4513 + endloop + endfacet + facet normal 0.890536 -0.058747 0.451103 + outer loop + vertex 692.819 183.369 63.6871 + vertex 693.14 193.14 64.3262 + vertex 691.294 183.891 66.765 + endloop + endfacet + facet normal 0.941882 -0.0140403 0.33565 + outer loop + vertex 690.461 247.662 71.4057 + vertex 691.751 255.381 68.1088 + vertex 690.516 256.921 71.639 + endloop + endfacet + facet normal 0.958867 -0.0225326 0.28296 + outer loop + vertex 689.39 258.838 75.7891 + vertex 690.727 267.309 71.9318 + vertex 689.67 267.719 75.5466 + endloop + endfacet + facet normal 0.940992 -0.0197983 0.33785 + outer loop + vertex 691.751 255.381 68.1088 + vertex 691.768 264.066 68.5704 + vertex 690.516 256.921 71.639 + endloop + endfacet + facet normal 0.957824 -0.0396908 0.2846 + outer loop + vertex 689.67 267.719 75.5466 + vertex 690.727 267.309 71.9318 + vertex 690.636 279.444 73.9296 + endloop + endfacet + facet normal 0.974558 -0.042353 0.220098 + outer loop + vertex 691.887 315.974 74.4728 + vertex 692.651 333.188 74.4048 + vertex 690.343 317.661 81.6346 + endloop + endfacet + facet normal 0.974327 -0.0448211 0.22063 + outer loop + vertex 689.566 300.695 81.6186 + vertex 691.887 315.974 74.4728 + vertex 690.343 317.661 81.6346 + endloop + endfacet + facet normal 0.983023 -0.0381875 0.179463 + outer loop + vertex 688.926 283.101 81.3786 + vertex 689.566 300.695 81.6186 + vertex 687.658 285.135 88.7574 + endloop + endfacet + facet normal 0.983448 -0.0331176 0.178138 + outer loop + vertex 687.107 267.836 88.5858 + vertex 688.926 283.101 81.3786 + vertex 687.658 285.135 88.7574 + endloop + endfacet + facet normal 0.989662 -0.0203225 0.14197 + outer loop + vertex 686.783 249.939 88.2844 + vertex 687.107 267.836 88.5858 + vertex 685.741 252.234 95.8758 + endloop + endfacet + facet normal 0.990045 -0.0138581 0.140068 + outer loop + vertex 685.55 234.131 95.4354 + vertex 686.783 249.939 88.2844 + vertex 685.741 252.234 95.8758 + endloop + endfacet + facet normal 0.994232 -0.0129334 0.106466 + outer loop + vertex 685.387 215.33 94.6745 + vertex 685.55 234.131 95.4354 + vertex 684.62 217.172 102.054 + endloop + endfacet + facet normal 0.995589 -0.0248259 0.0904758 + outer loop + vertex 684.115 203.564 103.878 + vertex 684.491 204.508 100 + vertex 684.62 217.172 102.054 + endloop + endfacet + facet normal 0.995286 -0.0551699 0.0797611 + outer loop + vertex 683.675 194.433 103.053 + vertex 684.115 203.564 103.878 + vertex 683.423 195.244 106.757 + endloop + endfacet + facet normal 0.997744 -0.0240448 0.0626801 + outer loop + vertex 683.665 205.143 111.289 + vertex 683.934 206.071 107.354 + vertex 684.109 218.712 109.427 + endloop + endfacet + facet normal 0.998707 -0.0235761 0.0450377 + outer loop + vertex 683.359 206.71 118.755 + vertex 683.56 207.65 114.791 + vertex 683.762 220.162 116.865 + endloop + endfacet + facet normal 0.99754 -0.0137032 0.0687516 + outer loop + vertex 684.109 218.712 109.427 + vertex 684.798 235.914 102.849 + vertex 684.31 237.291 110.208 + endloop + endfacet + facet normal 0.997499 -0.0152018 0.0690293 + outer loop + vertex 684.798 235.914 102.849 + vertex 685.043 253.698 103.233 + vertex 684.31 237.291 110.208 + endloop + endfacet + facet normal 0.995492 -0.0277648 0.0906944 + outer loop + vertex 685.043 253.698 103.233 + vertex 686.143 269.529 96.0087 + vertex 685.511 270.592 103.266 + endloop + endfacet + facet normal 0.995 -0.0383731 0.0922064 + outer loop + vertex 686.143 269.529 96.0087 + vertex 686.792 286.201 95.944 + vertex 685.511 270.592 103.266 + endloop + endfacet + facet normal 0.992067 -0.0489776 0.115775 + outer loop + vertex 686.792 286.201 95.944 + vertex 688.407 301.932 88.7527 + vertex 687.612 302.586 95.8418 + endloop + endfacet + facet normal 0.991952 -0.0508901 0.115938 + outer loop + vertex 688.407 301.932 88.7527 + vertex 689.262 318.478 88.7068 + vertex 687.612 302.586 95.8418 + endloop + endfacet + facet normal 0.987669 -0.0532046 0.147237 + outer loop + vertex 689.262 318.478 88.7068 + vertex 691.187 334.495 81.5766 + vertex 690.159 335.06 88.6819 + endloop + endfacet + facet normal 0.987733 -0.0522056 0.147167 + outer loop + vertex 691.187 334.495 81.5766 + vertex 692.095 351.519 81.5223 + vertex 690.159 335.06 88.6819 + endloop + endfacet + facet normal 0.981504 -0.0663226 0.179588 + outer loop + vertex 692.095 351.519 81.5223 + vertex 694.541 368.529 74.4393 + vertex 693.266 368.855 81.5274 + endloop + endfacet + facet normal 0.982565 -0.101898 0.155507 + outer loop + vertex 693.266 368.855 81.5274 + vertex 696.184 386.594 74.7094 + vertex 695.089 386.556 81.6064 + endloop + endfacet + facet normal 0.992691 -0.0710523 0.0975495 + outer loop + vertex 691.116 351.858 88.6725 + vertex 692.341 368.981 88.6751 + vertex 690.427 352.111 95.8611 + endloop + endfacet + facet normal 0.993514 -0.0590102 0.0972043 + outer loop + vertex 689.44 335.425 95.8274 + vertex 691.116 351.858 88.6725 + vertex 690.427 352.111 95.8611 + endloop + endfacet + facet normal 0.995235 -0.0559507 0.0798527 + outer loop + vertex 688.515 318.949 95.8059 + vertex 689.44 335.425 95.8274 + vertex 687.966 319.499 103.035 + endloop + endfacet + facet normal 0.995235 -0.0559495 0.0798526 + outer loop + vertex 687.05 303.219 103.044 + vertex 688.515 318.949 95.8059 + vertex 687.966 319.499 103.035 + endloop + endfacet + facet normal 0.996603 -0.0514866 0.0642838 + outer loop + vertex 686.205 286.978 103.143 + vertex 687.05 303.219 103.044 + vertex 685.777 287.879 110.5 + endloop + endfacet + facet normal 0.997089 -0.042617 0.0632252 + outer loop + vertex 685.074 271.597 110.604 + vertex 686.205 286.978 103.143 + vertex 685.777 287.879 110.5 + endloop + endfacet + facet normal 0.99845 -0.0293475 0.0472963 + outer loop + vertex 684.584 254.876 110.576 + vertex 685.074 271.597 110.604 + vertex 684.264 256.053 118.051 + endloop + endfacet + facet normal 0.998817 -0.0173455 0.0454234 + outer loop + vertex 683.979 238.591 117.663 + vertex 684.584 254.876 110.576 + vertex 684.264 256.053 118.051 + endloop + endfacet + facet normal 0.999309 -0.013256 0.0347225 + outer loop + vertex 683.762 220.162 116.865 + vertex 683.979 238.591 117.663 + vertex 683.517 221.562 124.456 + endloop + endfacet + facet normal 0.999183 -0.0231979 0.0330838 + outer loop + vertex 683.142 208.174 126.378 + vertex 683.3 209.158 122.312 + vertex 683.517 221.562 124.456 + endloop + endfacet + facet normal 0.997892 -0.055961 0.0328556 + outer loop + vertex 682.667 199.214 125.559 + vertex 683.142 208.174 126.378 + vertex 682.577 199.9 129.446 + endloop + endfacet + facet normal 0.999414 -0.0225979 0.025723 + outer loop + vertex 682.973 209.452 134.194 + vertex 683.104 210.536 130.04 + vertex 683.327 222.821 132.204 + endloop + endfacet + facet normal 0.999508 -0.0227679 0.0215919 + outer loop + vertex 682.828 210.476 141.999 + vertex 682.945 211.687 137.866 + vertex 683.177 223.873 139.996 + endloop + endfacet + facet normal 0.999556 -0.0129023 0.0268562 + outer loop + vertex 683.327 222.821 132.204 + vertex 683.733 239.869 125.28 + vertex 683.54 241.023 133.016 + endloop + endfacet + facet normal 0.999479 -0.016939 0.0274566 + outer loop + vertex 683.733 239.869 125.28 + vertex 684.016 257.238 125.687 + vertex 683.54 241.023 133.016 + endloop + endfacet + facet normal 0.998882 -0.0291742 0.0372082 + outer loop + vertex 684.016 257.238 125.687 + vertex 684.75 272.703 118.111 + vertex 684.497 273.789 125.759 + endloop + endfacet + facet normal 0.998324 -0.0426707 0.0391063 + outer loop + vertex 684.75 272.703 118.111 + vertex 685.445 288.894 118.028 + vertex 684.497 273.789 125.759 + endloop + endfacet + facet normal 0.997362 -0.0524609 0.050161 + outer loop + vertex 685.445 288.894 118.028 + vertex 686.624 304.036 110.424 + vertex 686.292 304.919 117.958 + endloop + endfacet + facet normal 0.997083 -0.057057 0.0506879 + outer loop + vertex 686.624 304.036 110.424 + vertex 687.549 320.203 110.424 + vertex 686.292 304.919 117.958 + endloop + endfacet + facet normal 0.996506 -0.0596013 0.0585038 + outer loop + vertex 687.549 320.203 110.424 + vertex 688.918 335.887 103.081 + vertex 688.517 336.428 110.46 + endloop + endfacet + facet normal 0.996387 -0.0614354 0.0586318 + outer loop + vertex 688.918 335.887 103.081 + vertex 689.936 352.437 103.125 + vertex 688.517 336.428 110.46 + endloop + endfacet + facet normal 0.994953 -0.0759242 0.0656092 + outer loop + vertex 689.936 352.437 103.125 + vertex 691.685 369.099 95.8816 + vertex 691.217 369.255 103.159 + endloop + endfacet + facet normal 0.991798 -0.109515 0.0658948 + outer loop + vertex 691.217 369.255 103.159 + vertex 693.6 386.471 95.907 + vertex 693.11 386.429 103.207 + endloop + endfacet + facet normal 0.996072 -0.0774157 0.0429818 + outer loop + vertex 689.558 352.79 110.494 + vertex 690.847 369.407 110.544 + vertex 689.26 353.125 117.994 + endloop + endfacet + facet normal 0.996973 -0.0651203 0.0424688 + outer loop + vertex 688.205 336.958 117.97 + vertex 689.558 352.79 110.494 + vertex 689.26 353.125 117.994 + endloop + endfacet + facet normal 0.997394 -0.0611888 0.0382129 + outer loop + vertex 687.222 320.917 117.947 + vertex 688.205 336.958 117.97 + vertex 686.968 321.541 125.579 + endloop + endfacet + facet normal 0.997546 -0.0587911 0.0380217 + outer loop + vertex 686.034 305.715 125.6 + vertex 687.222 320.917 117.947 + vertex 686.968 321.541 125.579 + endloop + endfacet + facet normal 0.998111 -0.0529379 0.0311652 + outer loop + vertex 685.19 289.847 125.679 + vertex 686.034 305.715 125.6 + vertex 684.991 290.639 133.397 + endloop + endfacet + facet normal 0.998616 -0.043079 0.0301663 + outer loop + vertex 684.302 274.708 133.482 + vertex 685.19 289.847 125.679 + vertex 684.991 290.639 133.397 + endloop + endfacet + facet normal 0.999306 -0.0293627 0.0229253 + outer loop + vertex 683.821 258.284 133.416 + vertex 684.302 274.708 133.482 + vertex 683.667 259.115 141.169 + endloop + endfacet + facet normal 0.999628 -0.016698 0.0215738 + outer loop + vertex 683.389 241.945 140.773 + vertex 683.821 258.284 133.416 + vertex 683.667 259.115 141.169 + endloop + endfacet + facet normal 0.999776 -0.0124629 0.0171248 + outer loop + vertex 683.177 223.873 139.996 + vertex 683.389 241.945 140.773 + vertex 683.054 224.663 147.736 + endloop + endfacet + facet normal 0.999601 -0.0224406 0.01713 + outer loop + vertex 682.719 211.245 149.716 + vertex 682.819 212.588 145.627 + vertex 683.054 224.663 147.736 + endloop + endfacet + facet normal 0.998276 -0.0564265 0.0161276 + outer loop + vertex 682.23 202.361 148.877 + vertex 682.719 211.245 149.716 + vertex 682.186 202.675 152.719 + endloop + endfacet + facet normal 0.999648 -0.022317 0.0143586 + outer loop + vertex 682.637 211.77 157.396 + vertex 682.728 213.245 153.323 + vertex 682.965 225.226 155.45 + endloop + endfacet + facet normal 0.999717 -0.0225403 0.00756968 + outer loop + vertex 682.593 212.08 165.155 + vertex 682.66 213.659 161.03 + vertex 682.912 225.577 163.195 + endloop + endfacet + facet normal 0.999851 -0.0125841 0.0118112 + outer loop + vertex 682.965 225.226 155.45 + vertex 683.267 242.665 148.522 + vertex 683.182 243.153 156.254 + endloop + endfacet + facet normal 0.999786 -0.0167949 0.012076 + outer loop + vertex 683.267 242.665 148.522 + vertex 683.549 259.74 148.917 + vertex 683.182 243.153 156.254 + endloop + endfacet + facet normal 0.999411 -0.0296906 0.0172258 + outer loop + vertex 683.549 259.74 148.917 + vertex 684.148 275.438 141.233 + vertex 684.03 275.988 148.984 + endloop + endfacet + facet normal 0.998885 -0.0435623 0.0182027 + outer loop + vertex 684.148 275.438 141.233 + vertex 684.839 291.263 141.146 + vertex 684.03 275.988 148.984 + endloop + endfacet + facet normal 0.998279 -0.0537537 0.0234605 + outer loop + vertex 684.839 291.263 141.146 + vertex 685.837 306.368 133.314 + vertex 685.683 306.889 141.064 + endloop + endfacet + facet normal 0.997956 -0.0592895 0.0238265 + outer loop + vertex 685.837 306.368 133.314 + vertex 686.769 322.056 133.29 + vertex 685.683 306.889 141.064 + endloop + endfacet + facet normal 0.997622 -0.062717 0.028565 + outer loop + vertex 686.769 322.056 133.29 + vertex 687.955 337.408 125.593 + vertex 687.758 337.787 133.305 + endloop + endfacet + facet normal 0.997397 -0.0661358 0.0287274 + outer loop + vertex 687.955 337.408 125.593 + vertex 689.015 353.406 125.613 + vertex 687.758 337.787 133.305 + endloop + endfacet + facet normal 0.996252 -0.0799121 0.0330999 + outer loop + vertex 689.015 353.406 125.613 + vertex 690.561 369.552 118.054 + vertex 690.318 369.667 125.648 + endloop + endfacet + facet normal 0.993074 -0.113851 0.0290043 + outer loop + vertex 690.318 369.667 125.648 + vertex 692.447 386.348 118.233 + vertex 692.227 386.314 125.633 + endloop + endfacet + facet normal 0.996448 -0.0814592 0.0213421 + outer loop + vertex 688.661 353.838 141.081 + vertex 690.129 369.77 133.362 + vertex 689.968 369.846 141.154 + endloop + endfacet + facet normal 0.997491 -0.0672738 0.0220351 + outer loop + vertex 687.599 338.092 141.058 + vertex 688.819 353.646 133.323 + vertex 688.661 353.838 141.081 + endloop + endfacet + facet normal 0.997851 -0.0629743 0.0180955 + outer loop + vertex 686.614 322.473 141.042 + vertex 687.599 338.092 141.058 + vertex 686.494 322.795 148.798 + endloop + endfacet + facet normal 0.998045 -0.0598598 0.0179691 + outer loop + vertex 685.564 307.292 148.817 + vertex 686.614 322.473 141.042 + vertex 686.494 322.795 148.798 + endloop + endfacet + facet normal 0.99845 -0.0540422 0.0132837 + outer loop + vertex 684.721 291.742 148.899 + vertex 685.564 307.292 148.817 + vertex 684.636 292.081 156.639 + endloop + endfacet + facet normal 0.998953 -0.0439139 0.0128448 + outer loop + vertex 683.945 276.383 156.726 + vertex 684.721 291.742 148.899 + vertex 684.636 292.081 156.639 + endloop + endfacet + facet normal 0.999537 -0.0294819 0.00748837 + outer loop + vertex 683.467 260.168 156.654 + vertex 683.945 276.383 156.726 + vertex 683.417 260.431 164.387 + endloop + endfacet + facet normal 0.999829 -0.0171046 0.00706918 + outer loop + vertex 683.129 243.455 163.995 + vertex 683.467 260.168 156.654 + vertex 683.417 260.431 164.387 + endloop + endfacet + facet normal 0.99992 -0.0122935 0.00306223 + outer loop + vertex 682.912 225.577 163.195 + vertex 683.129 243.455 163.995 + vertex 682.89 225.713 170.955 + endloop + endfacet + facet normal 0.999749 -0.02235 0.00183988 + outer loop + vertex 682.584 212.176 172.972 + vertex 682.629 213.864 168.83 + vertex 682.89 225.713 170.955 + endloop + endfacet + facet normal 0.998406 -0.056423 -0.00110752 + outer loop + vertex 682.086 203.383 172.148 + vertex 682.584 212.176 172.972 + vertex 682.089 203.361 176.031 + endloop + endfacet + facet normal 0.999748 -0.0223619 -0.00181371 + outer loop + vertex 682.603 212.049 180.632 + vertex 682.636 213.862 176.583 + vertex 682.903 225.638 178.653 + endloop + endfacet + facet normal 0.999728 -0.0224852 -0.00617477 + outer loop + vertex 682.648 211.67 188.296 + vertex 682.667 213.62 184.209 + vertex 682.944 225.344 186.351 + endloop + endfacet + facet normal 0.999919 -0.0125218 -0.00223317 + outer loop + vertex 682.903 225.638 178.653 + vertex 683.112 243.562 171.723 + vertex 683.128 243.478 179.438 + endloop + endfacet + facet normal 0.999855 -0.0168609 -0.00228044 + outer loop + vertex 683.112 243.562 171.723 + vertex 683.399 260.524 172.112 + vertex 683.128 243.478 179.438 + endloop + endfacet + facet normal 0.999551 -0.0298896 0.00197739 + outer loop + vertex 683.399 260.524 172.112 + vertex 683.895 276.612 164.454 + vertex 683.882 276.678 172.175 + endloop + endfacet + facet normal 0.999023 -0.0441429 0.00209805 + outer loop + vertex 683.895 276.612 164.454 + vertex 684.588 292.279 164.366 + vertex 683.882 276.678 172.175 + endloop + endfacet + facet normal 0.998497 -0.05427 0.00760262 + outer loop + vertex 684.588 292.279 164.366 + vertex 685.479 307.578 156.558 + vertex 685.429 307.747 164.286 + endloop + endfacet + facet normal 0.998161 -0.0601231 0.00772813 + outer loop + vertex 685.479 307.578 156.558 + vertex 686.409 323.024 156.54 + vertex 685.429 307.747 164.286 + endloop + endfacet + facet normal 0.997905 -0.0634803 0.0124889 + outer loop + vertex 686.409 323.024 156.54 + vertex 687.479 338.329 148.817 + vertex 687.393 338.496 156.563 + endloop + endfacet + facet normal 0.997625 -0.067807 0.0120897 + outer loop + vertex 687.393 338.496 156.563 + vertex 688.539 353.985 148.845 + vertex 688.452 354.086 156.592 + endloop + endfacet + facet normal 0.996553 -0.08211 0.0118029 + outer loop + vertex 688.452 354.086 156.592 + vertex 689.847 369.904 148.914 + vertex 689.758 369.941 156.645 + endloop + endfacet + facet normal 0.993058 -0.117143 0.0106103 + outer loop + vertex 689.758 369.941 156.645 + vertex 691.762 386.239 149.08 + vertex 691.678 386.226 156.792 + endloop + endfacet + facet normal 0.996592 -0.0824431 0.00259892 + outer loop + vertex 688.385 354.157 172.046 + vertex 689.712 369.963 164.37 + vertex 689.692 369.96 172.107 + endloop + endfacet + facet normal 0.997676 -0.0680961 0.00228533 + outer loop + vertex 687.325 338.622 172.017 + vertex 688.402 354.144 164.324 + vertex 688.385 354.157 172.046 + endloop + endfacet + facet normal 0.997966 -0.0637061 0.00252358 + outer loop + vertex 686.34 323.203 171.992 + vertex 687.342 338.594 164.294 + vertex 687.325 338.622 172.017 + endloop + endfacet + facet normal 0.998181 -0.0602296 0.00259003 + outer loop + vertex 685.411 307.803 172.01 + vertex 686.358 323.159 164.269 + vertex 686.34 323.203 171.992 + endloop + endfacet + facet normal 0.998525 -0.0542272 -0.00270423 + outer loop + vertex 684.572 292.342 172.09 + vertex 685.411 307.803 172.01 + vertex 684.589 292.271 179.818 + endloop + endfacet + facet normal 0.999037 -0.0437934 -0.00260837 + outer loop + vertex 683.902 276.589 179.903 + vertex 684.572 292.342 172.09 + vertex 684.589 292.271 179.818 + endloop + endfacet + facet normal 0.999527 -0.0298021 -0.00755218 + outer loop + vertex 683.419 260.423 179.833 + vertex 683.902 276.589 179.903 + vertex 683.469 260.15 187.575 + endloop + endfacet + facet normal 0.999828 -0.0171133 -0.00710662 + outer loop + vertex 683.176 243.171 187.167 + vertex 683.419 260.423 179.833 + vertex 683.469 260.15 187.575 + endloop + endfacet + facet normal 0.999871 -0.0125594 -0.0100452 + outer loop + vertex 682.944 225.344 186.351 + vertex 683.176 243.171 187.167 + vertex 683.015 224.815 194.133 + endloop + endfacet + facet normal 0.999674 -0.0229353 -0.0111968 + outer loop + vertex 682.722 211.051 196.159 + vertex 682.723 213.123 191.979 + vertex 683.015 224.815 194.133 + endloop + endfacet + facet normal 0.998226 -0.056085 -0.0199634 + outer loop + vertex 682.216 202.33 195.367 + vertex 682.722 211.051 196.159 + vertex 682.275 201.96 199.317 + endloop + endfacet + facet normal 0.99961 -0.0232113 -0.0155145 + outer loop + vertex 682.832 210.212 203.944 + vertex 682.819 212.408 199.825 + vertex 683.122 224.076 201.913 + endloop + endfacet + facet normal 0.999485 -0.023183 -0.0221952 + outer loop + vertex 682.985 209.17 211.678 + vertex 682.947 211.483 207.561 + vertex 683.264 223.114 209.671 + endloop + endfacet + facet normal 0.999785 -0.0131807 -0.016012 + outer loop + vertex 683.122 224.076 201.913 + vertex 683.255 242.675 194.93 + vertex 683.371 241.979 202.706 + endloop + endfacet + facet normal 0.999719 -0.0171269 -0.0163641 + outer loop + vertex 683.255 242.675 194.93 + vertex 683.554 259.693 195.338 + vertex 683.371 241.979 202.706 + endloop + endfacet + facet normal 0.99947 -0.0298915 -0.0129225 + outer loop + vertex 683.554 259.693 195.338 + vertex 683.952 276.346 187.647 + vertex 684.04 275.926 195.411 + endloop + endfacet + facet normal 0.998938 -0.0439887 -0.0136787 + outer loop + vertex 683.952 276.346 187.647 + vertex 684.643 292.051 187.562 + vertex 684.04 275.926 195.411 + endloop + endfacet + facet normal 0.998514 -0.0539236 -0.00785981 + outer loop + vertex 684.643 292.051 187.562 + vertex 685.428 307.742 179.737 + vertex 685.48 307.562 187.479 + endloop + endfacet + facet normal 0.998167 -0.0600314 -0.00765834 + outer loop + vertex 685.48 307.562 187.479 + vertex 686.358 323.153 179.719 + vertex 686.408 323.008 187.459 + endloop + endfacet + facet normal 0.997953 -0.0634977 -0.00754343 + outer loop + vertex 686.408 323.008 187.459 + vertex 687.341 338.582 179.741 + vertex 687.392 338.469 187.478 + endloop + endfacet + facet normal 0.997675 -0.0677715 -0.0071717 + outer loop + vertex 687.392 338.469 187.478 + vertex 688.4 354.123 179.769 + vertex 688.45 354.042 187.506 + endloop + endfacet + facet normal 0.996602 -0.0820898 -0.00674184 + outer loop + vertex 688.45 354.042 187.506 + vertex 689.708 369.938 179.858 + vertex 689.756 369.892 187.568 + endloop + endfacet + facet normal 0.993159 -0.116604 -0.00626462 + outer loop + vertex 689.756 369.892 187.568 + vertex 691.627 386.218 180.208 + vertex 691.674 386.225 187.557 + endloop + endfacet + facet normal 0.996488 -0.0819597 -0.0171263 + outer loop + vertex 688.538 353.915 195.273 + vertex 689.848 369.83 195.334 + vertex 688.658 353.743 203.075 + endloop + endfacet + facet normal 0.99759 -0.0673142 -0.0168215 + outer loop + vertex 687.597 338.032 203.037 + vertex 688.538 353.915 195.273 + vertex 688.658 353.743 203.075 + endloop + endfacet + facet normal 0.997868 -0.062911 -0.0173657 + outer loop + vertex 686.613 322.429 203.019 + vertex 687.478 338.284 195.244 + vertex 687.597 338.032 203.037 + endloop + endfacet + facet normal 0.998062 -0.0595751 -0.0179468 + outer loop + vertex 685.683 306.841 203.041 + vertex 686.493 322.765 195.226 + vertex 686.613 322.429 203.019 + endloop + endfacet + facet normal 0.998398 -0.0536266 -0.0180237 + outer loop + vertex 684.844 291.193 203.122 + vertex 685.565 307.259 195.248 + vertex 685.683 306.841 203.041 + endloop + endfacet + facet normal 0.998901 -0.0433349 -0.0178772 + outer loop + vertex 684.158 275.347 203.201 + vertex 684.727 291.694 195.329 + vertex 684.844 291.193 203.122 + endloop + endfacet + facet normal 0.999305 -0.029533 -0.0227629 + outer loop + vertex 683.674 259.036 203.118 + vertex 684.158 275.347 203.201 + vertex 683.827 258.208 210.903 + endloop + endfacet + facet normal 0.999621 -0.0172608 -0.0214647 + outer loop + vertex 683.522 241.068 210.483 + vertex 683.674 259.036 203.118 + vertex 683.827 258.208 210.903 + endloop + endfacet + facet normal 0.999574 -0.0131976 -0.0260224 + outer loop + vertex 683.264 223.114 209.671 + vertex 683.522 241.068 210.483 + vertex 683.451 221.956 217.442 + endloop + endfacet + facet normal 0.999327 -0.0235023 -0.0281619 + outer loop + vertex 683.177 207.886 219.471 + vertex 683.118 210.326 215.333 + vertex 683.451 221.956 217.442 + endloop + endfacet + facet normal 0.997658 -0.0558463 -0.0395011 + outer loop + vertex 682.661 199.196 218.711 + vertex 683.177 207.886 219.471 + vertex 682.774 198.474 222.585 + endloop + endfacet + facet normal 0.999026 -0.0235485 -0.0373285 + outer loop + vertex 683.429 206.411 227.154 + vertex 683.337 208.957 223.09 + vertex 683.687 220.601 225.111 + endloop + endfacet + facet normal 0.998379 -0.02424 -0.051504 + outer loop + vertex 683.76 204.825 234.552 + vertex 683.621 207.435 230.646 + vertex 684.004 219.112 232.572 + endloop + endfacet + facet normal 0.999319 -0.0136292 -0.0343005 + outer loop + vertex 683.687 220.601 225.111 + vertex 683.714 239.973 218.224 + vertex 683.959 238.725 225.842 + endloop + endfacet + facet normal 0.999251 -0.0168429 -0.034825 + outer loop + vertex 683.714 239.973 218.224 + vertex 684.019 257.216 218.632 + vertex 683.959 238.725 225.842 + endloop + endfacet + facet normal 0.999174 -0.0291577 -0.0283216 + outer loop + vertex 684.019 257.216 218.632 + vertex 684.31 274.611 210.989 + vertex 684.503 273.722 218.708 + endloop + endfacet + facet normal 0.998677 -0.04262 -0.0287724 + outer loop + vertex 684.503 273.722 218.708 + vertex 684.997 290.557 210.91 + vertex 685.187 289.798 218.632 + endloop + endfacet + facet normal 0.998197 -0.0527646 -0.0286115 + outer loop + vertex 685.187 289.798 218.632 + vertex 685.836 306.315 210.829 + vertex 686.025 305.695 218.556 + endloop + endfacet + facet normal 0.997875 -0.058725 -0.0282417 + outer loop + vertex 686.025 305.695 218.556 + vertex 686.766 322.017 210.807 + vertex 686.957 321.536 218.539 + endloop + endfacet + facet normal 0.997672 -0.0623116 -0.0277256 + outer loop + vertex 686.957 321.536 218.539 + vertex 687.754 337.727 210.83 + vertex 687.947 337.38 218.563 + endloop + endfacet + facet normal 0.997364 -0.0669661 -0.0279263 + outer loop + vertex 687.754 337.727 210.83 + vertex 688.817 353.547 210.872 + vertex 687.947 337.38 218.563 + endloop + endfacet + facet normal 0.996484 -0.0809139 -0.0217552 + outer loop + vertex 688.817 353.547 210.872 + vertex 689.965 369.745 203.182 + vertex 690.127 369.661 210.949 + endloop + endfacet + facet normal 0.993343 -0.113575 -0.0192326 + outer loop + vertex 690.127 369.661 210.949 + vertex 691.883 386.259 203.587 + vertex 692.027 386.282 210.918 + endloop + endfacet + facet normal 0.996271 -0.0796287 -0.0332112 + outer loop + vertex 689.25 353.07 226.217 + vertex 690.317 369.565 218.67 + vertex 690.562 369.447 226.313 + endloop + endfacet + facet normal 0.997269 -0.0660236 -0.0331021 + outer loop + vertex 688.183 336.971 226.18 + vertex 689.015 353.332 218.602 + vertex 689.25 353.07 226.217 + endloop + endfacet + facet normal 0.99705 -0.0614947 -0.0459243 + outer loop + vertex 687.194 320.957 226.154 + vertex 688.183 336.971 226.18 + vertex 687.494 320.24 233.627 + endloop + endfacet + facet normal 0.997344 -0.0568864 -0.0454939 + outer loop + vertex 686.57 304.035 233.637 + vertex 687.194 320.957 226.154 + vertex 687.494 320.24 233.627 + endloop + endfacet + facet normal 0.997557 -0.0511635 -0.0475595 + outer loop + vertex 685.741 287.811 233.696 + vertex 686.261 304.952 226.168 + vertex 686.57 304.035 233.637 + endloop + endfacet + facet normal 0.99799 -0.0411046 -0.0482228 + outer loop + vertex 685.07 271.464 233.752 + vertex 685.425 288.899 226.234 + vertex 685.741 287.811 233.696 + endloop + endfacet + facet normal 0.998437 -0.0281262 -0.0482872 + outer loop + vertex 684.595 254.732 233.666 + vertex 684.745 272.687 226.301 + vertex 685.07 271.464 233.752 + endloop + endfacet + facet normal 0.998757 -0.0165309 -0.0470138 + outer loop + vertex 684.288 237.301 233.28 + vertex 684.267 256.055 226.223 + vertex 684.595 254.732 233.666 + endloop + endfacet + facet normal 0.997895 -0.0131114 -0.0635121 + outer loop + vertex 684.004 219.112 232.572 + vertex 684.288 237.301 233.28 + vertex 684.448 217.462 239.881 + endloop + endfacet + facet normal 0.996987 -0.0244238 -0.0736226 + outer loop + vertex 684.237 203.087 241.795 + vertex 684.019 205.802 237.937 + vertex 684.448 217.462 239.881 + endloop + endfacet + facet normal 0.994026 -0.0543156 -0.0946676 + outer loop + vertex 683.695 194.373 241.105 + vertex 684.237 203.087 241.795 + vertex 683.993 193.408 244.783 + endloop + endfacet + facet normal 0.994173 -0.0254714 -0.104743 + outer loop + vertex 684.93 201.247 249.135 + vertex 684.589 203.964 245.234 + vertex 685.098 215.714 247.212 + endloop + endfacet + facet normal 0.995046 -0.0152864 -0.0982375 + outer loop + vertex 685.098 215.714 247.212 + vertex 684.755 235.737 240.623 + vertex 685.461 234.155 248.019 + endloop + endfacet + facet normal 0.995024 -0.0157779 -0.0983791 + outer loop + vertex 685.461 234.155 248.019 + vertex 685.072 253.248 241.017 + vertex 685.777 251.83 248.38 + endloop + endfacet + facet normal 0.994993 -0.0252622 -0.0967043 + outer loop + vertex 685.777 251.83 248.38 + vertex 685.533 270.076 241.099 + vertex 686.206 268.735 248.372 + endloop + endfacet + facet normal 0.994908 -0.037446 -0.0935773 + outer loop + vertex 686.206 268.735 248.372 + vertex 686.186 286.548 241.036 + vertex 686.821 285.293 248.291 + endloop + endfacet + facet normal 0.994663 -0.047595 -0.0915456 + outer loop + vertex 686.821 285.293 248.291 + vertex 686.994 302.96 240.982 + vertex 687.613 301.891 248.268 + endloop + endfacet + facet normal 0.99418 -0.0550567 -0.0926 + outer loop + vertex 686.994 302.96 240.982 + vertex 687.903 319.377 240.98 + vertex 687.613 301.891 248.268 + endloop + endfacet + facet normal 0.996452 -0.0594457 -0.0595768 + outer loop + vertex 687.903 319.377 240.98 + vertex 688.483 336.438 233.652 + vertex 688.883 335.77 241.01 + endloop + endfacet + facet normal 0.996453 -0.0633147 -0.0554272 + outer loop + vertex 688.883 335.77 241.01 + vertex 689.552 352.711 233.693 + vertex 689.93 352.226 241.047 + endloop + endfacet + facet normal 0.995711 -0.0761408 -0.0525632 + outer loop + vertex 689.93 352.226 241.047 + vertex 690.85 369.259 233.792 + vertex 691.217 369 241.115 + endloop + endfacet + facet normal 0.993102 -0.106466 -0.049125 + outer loop + vertex 691.217 369 241.115 + vertex 692.74 386.388 234.231 + vertex 693.089 386.426 241.196 + endloop + endfacet + facet normal 0.993147 -0.0691581 -0.0942097 + outer loop + vertex 691.166 351.292 255.5 + vertex 691.701 368.726 248.346 + vertex 692.374 368.509 255.594 + endloop + endfacet + facet normal 0.993279 -0.0558041 -0.101402 + outer loop + vertex 690.231 334.597 255.531 + vertex 690.456 351.705 248.313 + vertex 691.166 351.292 255.5 + endloop + endfacet + facet normal 0.992427 -0.0519857 -0.111294 + outer loop + vertex 689.367 317.983 255.584 + vertex 689.446 335.076 248.305 + vertex 690.231 334.597 255.531 + endloop + endfacet + facet normal 0.991417 -0.0489791 -0.121214 + outer loop + vertex 688.538 301.169 255.598 + vertex 688.501 318.515 248.284 + vertex 689.367 317.983 255.584 + endloop + endfacet + facet normal 0.988529 -0.0285531 -0.148309 + outer loop + vertex 685.904 199.292 256.334 + vertex 685.417 202.236 252.518 + vertex 686.095 214.002 254.772 + endloop + endfacet + facet normal 0.984487 -0.0486715 -0.16857 + outer loop + vertex 685.362 191.261 255.487 + vertex 685.904 199.292 256.334 + vertex 685.856 188.937 259.039 + endloop + endfacet + facet normal 0.976104 -0.0322245 -0.214902 + outer loop + vertex 687.346 197.028 263.746 + vertex 686.612 200.041 259.96 + vertex 687.813 212.315 263.574 + endloop + endfacet + facet normal 0.942718 -0.062578 -0.327668 + outer loop + vertex 688.375 185.808 269.442 + vertex 688.248 196.733 266.99 + vertex 689.152 193.334 270.241 + endloop + endfacet +endsolid diff --git a/noether_examples/meshes/outputs/output_23.stl b/noether_examples/meshes/outputs/output_23.stl new file mode 100644 index 00000000..856f2b18 --- /dev/null +++ b/noether_examples/meshes/outputs/output_23.stl @@ -0,0 +1,6057 @@ +solid ascii + facet normal -0.941486 -0.0608814 -0.331509 + outer loop + vertex -690.158 194.295 272.926 + vertex -689.15 193.321 270.242 + vertex -689.5 184.908 272.782 + endloop + endfacet + facet normal -0.940803 -0.0614614 -0.333336 + outer loop + vertex -689.5 184.908 272.782 + vertex -689.15 193.321 270.242 + vertex -688.375 185.815 269.44 + endloop + endfacet + facet normal -0.942933 -0.0623482 -0.327094 + outer loop + vertex -689.15 193.321 270.242 + vertex -688.246 196.722 266.989 + vertex -688.375 185.815 269.44 + endloop + endfacet + facet normal -0.955039 -0.0542036 -0.291482 + outer loop + vertex -688.375 185.815 269.44 + vertex -688.246 196.722 266.989 + vertex -687.393 186.872 266.025 + endloop + endfacet + facet normal -0.960677 -0.0566147 -0.271837 + outer loop + vertex -688.246 196.722 266.989 + vertex -687.346 197.019 263.745 + vertex -687.393 186.872 266.025 + endloop + endfacet + facet normal -0.966804 -0.0517304 -0.250229 + outer loop + vertex -687.393 186.872 266.025 + vertex -687.346 197.019 263.745 + vertex -686.551 187.831 262.573 + endloop + endfacet + facet normal -0.971401 -0.0545706 -0.231091 + outer loop + vertex -687.346 197.019 263.745 + vertex -686.616 200.038 259.962 + vertex -686.551 187.831 262.573 + endloop + endfacet + facet normal -0.976999 -0.0495357 -0.207409 + outer loop + vertex -686.551 187.831 262.573 + vertex -686.616 200.038 259.962 + vertex -685.859 188.941 259.047 + endloop + endfacet + facet normal -0.982117 -0.0520677 -0.180929 + outer loop + vertex -686.616 200.038 259.962 + vertex -685.91 199.29 256.345 + vertex -685.859 188.941 259.047 + endloop + endfacet + facet normal -0.984628 -0.0486401 -0.167753 + outer loop + vertex -685.859 188.941 259.047 + vertex -685.91 199.29 256.345 + vertex -685.368 191.261 255.495 + endloop + endfacet + facet normal -0.985253 -0.0490894 -0.163908 + outer loop + vertex -685.91 199.29 256.345 + vertex -685.422 202.234 252.532 + vertex -685.368 191.261 255.495 + endloop + endfacet + facet normal -0.985177 -0.049204 -0.164334 + outer loop + vertex -685.368 191.261 255.495 + vertex -685.422 202.234 252.532 + vertex -684.84 191.875 252.147 + endloop + endfacet + facet normal -0.99053 -0.0508723 -0.127524 + outer loop + vertex -685.422 202.234 252.532 + vertex -684.935 201.248 249.146 + vertex -684.84 191.875 252.147 + endloop + endfacet + facet normal -0.988714 -0.0546816 -0.139479 + outer loop + vertex -684.84 191.875 252.147 + vertex -684.935 201.248 249.146 + vertex -684.357 192.403 248.516 + endloop + endfacet + facet normal -0.990363 -0.0556927 -0.126807 + outer loop + vertex -684.935 201.248 249.146 + vertex -684.588 203.963 245.244 + vertex -684.357 192.403 248.516 + endloop + endfacet + facet normal -0.992488 -0.0512818 -0.111074 + outer loop + vertex -684.357 192.403 248.516 + vertex -684.588 203.963 245.244 + vertex -683.986 193.422 244.728 + endloop + endfacet + facet normal -0.99485 -0.0526125 -0.0866391 + outer loop + vertex -684.588 203.963 245.244 + vertex -684.243 203.095 241.805 + vertex -683.986 193.422 244.728 + endloop + endfacet + facet normal -0.994059 -0.054824 -0.0940263 + outer loop + vertex -683.986 193.422 244.728 + vertex -684.243 203.095 241.805 + vertex -683.692 194.394 241.049 + endloop + endfacet + facet normal -0.993899 -0.0546599 -0.0957996 + outer loop + vertex -684.243 203.095 241.805 + vertex -684.021 205.797 237.958 + vertex -683.692 194.394 241.049 + endloop + endfacet + facet normal -0.995153 -0.0514441 -0.0838037 + outer loop + vertex -683.692 194.394 241.049 + vertex -684.021 205.797 237.958 + vertex -683.434 195.274 237.447 + endloop + endfacet + facet normal -0.996853 -0.0527344 -0.0591849 + outer loop + vertex -684.021 205.797 237.958 + vertex -683.769 204.825 234.579 + vertex -683.434 195.274 237.447 + endloop + endfacet + facet normal -0.996048 -0.055706 -0.0691775 + outer loop + vertex -683.434 195.274 237.447 + vertex -683.769 204.825 234.579 + vertex -683.229 196.102 233.838 + endloop + endfacet + facet normal -0.995723 -0.0552731 -0.074034 + outer loop + vertex -683.769 204.825 234.579 + vertex -683.623 207.425 230.677 + vertex -683.229 196.102 233.838 + endloop + endfacet + facet normal -0.996898 -0.0513072 -0.0596809 + outer loop + vertex -683.229 196.102 233.838 + vertex -683.623 207.425 230.677 + vertex -683.051 196.915 230.155 + endloop + endfacet + facet normal -0.997831 -0.0523398 -0.0399157 + outer loop + vertex -683.623 207.425 230.677 + vertex -683.43 206.404 227.179 + vertex -683.051 196.915 230.155 + endloop + endfacet + facet normal -0.99706 -0.0561436 -0.0521433 + outer loop + vertex -683.051 196.915 230.155 + vertex -683.43 206.404 227.179 + vertex -682.898 197.711 226.375 + endloop + endfacet + facet normal -0.996833 -0.0557035 -0.0567513 + outer loop + vertex -683.43 206.404 227.179 + vertex -683.341 208.95 223.119 + vertex -682.898 197.711 226.375 + endloop + endfacet + facet normal -0.997721 -0.0518196 -0.0432223 + outer loop + vertex -682.898 197.711 226.375 + vertex -683.341 208.95 223.119 + vertex -682.772 198.482 222.536 + endloop + endfacet + facet normal -0.998185 -0.0526211 -0.0293014 + outer loop + vertex -683.341 208.95 223.119 + vertex -683.178 207.879 219.493 + vertex -682.772 198.482 222.536 + endloop + endfacet + facet normal -0.997709 -0.0555937 -0.0385455 + outer loop + vertex -682.772 198.482 222.536 + vertex -683.178 207.879 219.493 + vertex -682.662 199.205 218.661 + endloop + endfacet + facet normal -0.99746 -0.0549271 -0.0453388 + outer loop + vertex -683.178 207.879 219.493 + vertex -683.125 210.326 215.364 + vertex -682.662 199.205 218.661 + endloop + endfacet + facet normal -0.998072 -0.0516973 -0.0343567 + outer loop + vertex -682.662 199.205 218.661 + vertex -683.125 210.326 215.364 + vertex -682.563 199.877 214.754 + endloop + endfacet + facet normal -0.998421 -0.0525635 -0.0198376 + outer loop + vertex -683.125 210.326 215.364 + vertex -682.991 209.169 211.702 + vertex -682.563 199.877 214.754 + endloop + endfacet + facet normal -0.997916 -0.0563519 -0.031444 + outer loop + vertex -682.563 199.877 214.754 + vertex -682.991 209.169 211.702 + vertex -682.474 200.489 210.85 + endloop + endfacet + facet normal -0.997622 -0.0553951 -0.0410117 + outer loop + vertex -682.991 209.169 211.702 + vertex -682.95 211.48 207.591 + vertex -682.474 200.489 210.85 + endloop + endfacet + facet normal -0.998271 -0.0516078 -0.0281439 + outer loop + vertex -682.474 200.489 210.85 + vertex -682.95 211.48 207.591 + vertex -682.393 201.033 206.99 + endloop + endfacet + facet normal -0.998524 -0.0524238 -0.0141954 + outer loop + vertex -682.95 211.48 207.591 + vertex -682.832 210.207 203.969 + vertex -682.393 201.033 206.99 + endloop + endfacet + facet normal -0.998112 -0.0560234 -0.0251871 + outer loop + vertex -682.393 201.033 206.99 + vertex -682.832 210.207 203.969 + vertex -682.324 201.515 203.152 + endloop + endfacet + facet normal -0.997899 -0.0551875 -0.0339421 + outer loop + vertex -682.832 210.207 203.969 + vertex -682.813 212.392 199.851 + vertex -682.324 201.515 203.152 + endloop + endfacet + facet normal -0.998462 -0.051296 -0.0210362 + outer loop + vertex -682.324 201.515 203.152 + vertex -682.813 212.392 199.851 + vertex -682.264 201.952 199.267 + endloop + endfacet + facet normal -0.998616 -0.0520623 -0.00747613 + outer loop + vertex -682.813 212.392 199.851 + vertex -682.714 211.033 196.174 + vertex -682.264 201.952 199.267 + endloop + endfacet + facet normal -0.998295 -0.0555778 -0.0178424 + outer loop + vertex -682.264 201.952 199.267 + vertex -682.714 211.033 196.174 + vertex -682.215 202.338 195.32 + endloop + endfacet + facet normal -0.998147 -0.0547064 -0.0266319 + outer loop + vertex -682.714 211.033 196.174 + vertex -682.717 213.11 191.998 + vertex -682.215 202.338 195.32 + endloop + endfacet + facet normal -0.998525 -0.0516643 -0.0167105 + outer loop + vertex -682.215 202.338 195.32 + vertex -682.717 213.11 191.998 + vertex -682.165 202.655 191.365 + endloop + endfacet + facet normal -0.99861 -0.0527043 0.000408635 + outer loop + vertex -682.717 213.11 191.998 + vertex -682.642 211.653 188.314 + vertex -682.165 202.655 191.365 + endloop + endfacet + facet normal -0.998239 -0.0576143 -0.0141272 + outer loop + vertex -682.165 202.655 191.365 + vertex -682.642 211.653 188.314 + vertex -682.124 202.903 187.463 + endloop + endfacet + facet normal -0.998141 -0.0568468 -0.0219604 + outer loop + vertex -682.642 211.653 188.314 + vertex -682.663 213.602 184.227 + vertex -682.124 202.903 187.463 + endloop + endfacet + facet normal -0.998561 -0.0528964 -0.00882933 + outer loop + vertex -682.124 202.903 187.463 + vertex -682.663 213.602 184.227 + vertex -682.101 203.104 183.634 + endloop + endfacet + facet normal -0.998535 -0.053746 0.00624042 + outer loop + vertex -682.663 213.602 184.227 + vertex -682.601 212.035 180.643 + vertex -682.101 203.104 183.634 + endloop + endfacet + facet normal -0.99835 -0.0572627 -0.004289 + outer loop + vertex -682.101 203.104 183.634 + vertex -682.601 212.035 180.643 + vertex -682.094 203.261 179.846 + endloop + endfacet + facet normal -0.99828 -0.0560992 -0.0170545 + outer loop + vertex -682.601 212.035 180.643 + vertex -682.634 213.854 176.584 + vertex -682.094 203.261 179.846 + endloop + endfacet + facet normal -0.998648 -0.0518706 -0.00326206 + outer loop + vertex -682.094 203.261 179.846 + vertex -682.634 213.854 176.584 + vertex -682.087 203.358 176.03 + endloop + endfacet + facet normal -0.998551 -0.052629 0.0112074 + outer loop + vertex -682.634 213.854 176.584 + vertex -682.586 212.179 172.97 + vertex -682.087 203.358 176.03 + endloop + endfacet + facet normal -0.998366 -0.0571235 -0.00177839 + outer loop + vertex -682.087 203.358 176.03 + vertex -682.586 212.179 172.97 + vertex -682.081 203.383 172.145 + endloop + endfacet + facet normal -0.998352 -0.0561938 -0.0116822 + outer loop + vertex -682.586 212.179 172.97 + vertex -682.632 213.868 168.828 + vertex -682.081 203.383 172.145 + endloop + endfacet + facet normal -0.998635 -0.0522153 0.000942703 + outer loop + vertex -682.081 203.383 172.145 + vertex -682.632 213.868 168.828 + vertex -682.083 203.349 168.216 + endloop + endfacet + facet normal -0.998486 -0.053007 0.0146947 + outer loop + vertex -682.632 213.868 168.828 + vertex -682.592 212.079 165.152 + vertex -682.083 203.349 168.216 + endloop + endfacet + facet normal -0.998393 -0.0564631 0.00483204 + outer loop + vertex -682.083 203.349 168.216 + vertex -682.592 212.079 165.152 + vertex -682.097 203.262 164.295 + endloop + endfacet + facet normal -0.998446 -0.0555049 -0.0050569 + outer loop + vertex -682.592 212.079 165.152 + vertex -682.659 213.659 161.028 + vertex -682.097 203.262 164.295 + endloop + endfacet + facet normal -0.998638 -0.0516914 0.00711281 + outer loop + vertex -682.097 203.262 164.295 + vertex -682.659 213.659 161.028 + vertex -682.117 203.119 160.408 + endloop + endfacet + facet normal -0.998378 -0.0525498 0.0219165 + outer loop + vertex -682.659 213.659 161.028 + vertex -682.639 211.77 157.395 + vertex -682.117 203.119 160.408 + endloop + endfacet + facet normal -0.998343 -0.0566549 0.0101216 + outer loop + vertex -682.117 203.119 160.408 + vertex -682.639 211.77 157.395 + vertex -682.145 202.923 156.555 + endloop + endfacet + facet normal -0.998441 -0.0558107 0.00117424 + outer loop + vertex -682.639 211.77 157.395 + vertex -682.726 213.239 153.32 + vertex -682.145 202.923 156.555 + endloop + endfacet + facet normal -0.998553 -0.0523837 0.0121243 + outer loop + vertex -682.145 202.923 156.555 + vertex -682.726 213.239 153.32 + vertex -682.178 202.667 152.717 + endloop + endfacet + facet normal -0.998173 -0.053296 0.0284522 + outer loop + vertex -682.726 213.239 153.32 + vertex -682.722 211.243 149.716 + vertex -682.178 202.667 152.717 + endloop + endfacet + facet normal -0.998214 -0.057036 0.0177714 + outer loop + vertex -682.178 202.667 152.717 + vertex -682.722 211.243 149.716 + vertex -682.229 202.362 148.88 + endloop + endfacet + facet normal -0.99841 -0.0559926 0.00657646 + outer loop + vertex -682.722 211.243 149.716 + vertex -682.825 212.596 145.632 + vertex -682.229 202.362 148.88 + endloop + endfacet + facet normal -0.998464 -0.0520811 0.0189121 + outer loop + vertex -682.229 202.362 148.88 + vertex -682.825 212.596 145.632 + vertex -682.283 201.999 145.036 + endloop + endfacet + facet normal -0.99798 -0.0529648 0.035076 + outer loop + vertex -682.825 212.596 145.632 + vertex -682.84 210.495 142.01 + vertex -682.283 201.999 145.036 + endloop + endfacet + facet normal -0.998092 -0.0571272 0.023412 + outer loop + vertex -682.283 201.999 145.036 + vertex -682.84 210.495 142.01 + vertex -682.349 201.572 141.182 + endloop + endfacet + facet normal -0.998369 -0.0560027 0.0111311 + outer loop + vertex -682.84 210.495 142.01 + vertex -682.955 211.711 137.882 + vertex -682.349 201.572 141.182 + endloop + endfacet + facet normal -0.998382 -0.0526058 0.0215695 + outer loop + vertex -682.349 201.572 141.182 + vertex -682.955 211.711 137.882 + vertex -682.407 201.065 137.287 + endloop + endfacet + facet normal -0.997793 -0.0535635 0.0392502 + outer loop + vertex -682.955 211.711 137.882 + vertex -682.979 209.471 134.208 + vertex -682.407 201.065 137.287 + endloop + endfacet + facet normal -0.997949 -0.0581642 0.0267201 + outer loop + vertex -682.407 201.065 137.287 + vertex -682.979 209.471 134.208 + vertex -682.479 200.495 133.345 + endloop + endfacet + facet normal -0.998192 -0.0573422 0.0180228 + outer loop + vertex -682.979 209.471 134.208 + vertex -683.116 210.553 130.052 + vertex -682.479 200.495 133.345 + endloop + endfacet + facet normal -0.998086 -0.0525877 0.0325253 + outer loop + vertex -682.479 200.495 133.345 + vertex -683.116 210.553 130.052 + vertex -682.576 199.887 129.397 + endloop + endfacet + facet normal -0.997625 -0.0532498 0.0436817 + outer loop + vertex -683.116 210.553 130.052 + vertex -683.151 208.191 126.385 + vertex -682.576 199.887 129.397 + endloop + endfacet + facet normal -0.997772 -0.0558905 0.0364304 + outer loop + vertex -682.576 199.887 129.397 + vertex -683.151 208.191 126.385 + vertex -682.68 199.221 125.501 + endloop + endfacet + facet normal -0.998185 -0.0547866 0.0250012 + outer loop + vertex -683.151 208.191 126.385 + vertex -683.306 209.174 122.331 + vertex -682.68 199.221 125.501 + endloop + endfacet + facet normal -0.998043 -0.0514029 0.0355977 + outer loop + vertex -682.68 199.221 125.501 + vertex -683.306 209.174 122.331 + vertex -682.779 198.483 121.683 + endloop + endfacet + facet normal -0.997194 -0.0524417 0.0534183 + outer loop + vertex -683.306 209.174 122.331 + vertex -683.367 206.721 118.778 + vertex -682.779 198.483 121.683 + endloop + endfacet + facet normal -0.997501 -0.0562107 0.0427915 + outer loop + vertex -682.779 198.483 121.683 + vertex -683.367 206.721 118.778 + vertex -682.896 197.704 117.927 + endloop + endfacet + facet normal -0.99784 -0.0555066 0.0351446 + outer loop + vertex -683.367 206.721 118.778 + vertex -683.559 207.651 114.822 + vertex -682.896 197.704 117.927 + endloop + endfacet + facet normal -0.997495 -0.0512247 0.048788 + outer loop + vertex -682.896 197.704 117.927 + vertex -683.559 207.651 114.822 + vertex -683.037 196.896 114.192 + endloop + endfacet + facet normal -0.996357 -0.0522594 0.0673863 + outer loop + vertex -683.559 207.651 114.822 + vertex -683.664 205.149 111.317 + vertex -683.037 196.896 114.192 + endloop + endfacet + facet normal -0.996713 -0.0550573 0.0594303 + outer loop + vertex -683.037 196.896 114.192 + vertex -683.664 205.149 111.317 + vertex -683.214 196.067 110.449 + endloop + endfacet + facet normal -0.99695 -0.0547089 0.055665 + outer loop + vertex -683.664 205.149 111.317 + vertex -683.935 206.076 107.385 + vertex -683.214 196.067 110.449 + endloop + endfacet + facet normal -0.996416 -0.0510653 0.0674421 + outer loop + vertex -683.214 196.067 110.449 + vertex -683.935 206.076 107.385 + vertex -683.425 195.231 106.709 + endloop + endfacet + facet normal -0.994602 -0.0523605 0.0895841 + outer loop + vertex -683.935 206.076 107.385 + vertex -684.117 203.569 103.902 + vertex -683.425 195.231 106.709 + endloop + endfacet + facet normal -0.9952 -0.0554109 0.0806694 + outer loop + vertex -683.425 195.231 106.709 + vertex -684.117 203.569 103.902 + vertex -683.68 194.422 103.004 + endloop + endfacet + facet normal -0.995026 -0.0555981 0.0826597 + outer loop + vertex -684.117 203.569 103.902 + vertex -684.491 204.514 100.027 + vertex -683.68 194.422 103.004 + endloop + endfacet + facet normal -0.994184 -0.0521104 0.094253 + outer loop + vertex -683.68 194.422 103.004 + vertex -684.491 204.514 100.027 + vertex -683.986 193.626 99.3368 + endloop + endfacet + facet normal -0.991489 -0.0535329 0.118676 + outer loop + vertex -684.491 204.514 100.027 + vertex -684.766 201.963 96.5815 + vertex -683.986 193.626 99.3368 + endloop + endfacet + facet normal -0.992129 -0.0557606 0.112116 + outer loop + vertex -683.986 193.626 99.3368 + vertex -684.766 201.963 96.5815 + vertex -684.351 192.72 95.66 + endloop + endfacet + facet normal -0.990741 -0.0568137 0.123305 + outer loop + vertex -684.766 201.963 96.5815 + vertex -685.29 202.597 92.6608 + vertex -684.351 192.72 95.66 + endloop + endfacet + facet normal -0.989637 -0.0537139 0.133167 + outer loop + vertex -684.351 192.72 95.66 + vertex -685.29 202.597 92.6608 + vertex -684.789 191.496 91.9078 + endloop + endfacet + facet normal -0.984649 -0.0556771 0.165431 + outer loop + vertex -685.29 202.597 92.6608 + vertex -685.711 199.535 89.1234 + vertex -684.789 191.496 91.9078 + endloop + endfacet + facet normal -0.984589 -0.055531 0.165833 + outer loop + vertex -684.789 191.496 91.9078 + vertex -685.711 199.535 89.1234 + vertex -685.322 189.567 88.0997 + endloop + endfacet + facet normal -0.982157 -0.0568162 0.179272 + outer loop + vertex -685.711 199.535 89.1234 + vertex -686.454 199.782 85.1315 + vertex -685.322 189.567 88.0997 + endloop + endfacet + facet normal -0.980547 -0.0538865 0.188741 + outer loop + vertex -685.322 189.567 88.0997 + vertex -686.454 199.782 85.1315 + vertex -685.989 188.491 84.3272 + endloop + endfacet + facet normal -0.973346 -0.0559874 0.222401 + outer loop + vertex -686.454 199.782 85.1315 + vertex -687.069 196.732 81.675 + vertex -685.989 188.491 84.3272 + endloop + endfacet + facet normal -0.974085 -0.0572363 0.218822 + outer loop + vertex -685.989 188.491 84.3272 + vertex -687.069 196.732 81.675 + vertex -686.735 187.337 80.7046 + endloop + endfacet + facet normal -0.96703 -0.0599484 0.247507 + outer loop + vertex -687.069 196.732 81.675 + vertex -688 197.108 78.1278 + vertex -686.735 187.337 80.7046 + endloop + endfacet + facet normal -0.963498 -0.0557068 0.261857 + outer loop + vertex -686.735 187.337 80.7046 + vertex -688 197.108 78.1278 + vertex -687.663 186.444 77.0972 + endloop + endfacet + facet normal -0.952937 -0.0588094 0.29741 + outer loop + vertex -688 197.108 78.1278 + vertex -689.096 195.545 74.3064 + vertex -687.663 186.444 77.0972 + endloop + endfacet + facet normal -0.952146 -0.0578545 0.300118 + outer loop + vertex -687.663 186.444 77.0972 + vertex -689.096 195.545 74.3064 + vertex -688.728 185.387 73.5159 + endloop + endfacet + facet normal -0.939782 -0.0602321 0.336425 + outer loop + vertex -689.096 195.545 74.3064 + vertex -690.288 194.348 70.7627 + vertex -688.728 185.387 73.5159 + endloop + endfacet + facet normal -0.938235 -0.0585542 0.341009 + outer loop + vertex -688.728 185.387 73.5159 + vertex -690.288 194.348 70.7627 + vertex -689.934 184.529 70.0518 + endloop + endfacet + facet normal -0.944419 -0.029072 0.327456 + outer loop + vertex -689.096 195.545 74.3064 + vertex -690.424 203.903 71.2175 + vertex -690.288 194.348 70.7627 + endloop + endfacet + facet normal -0.946782 -0.0321031 0.320271 + outer loop + vertex -689.234 205.778 74.9234 + vertex -690.424 203.903 71.2175 + vertex -689.096 195.545 74.3064 + endloop + endfacet + facet normal -0.950971 -0.00752772 0.309187 + outer loop + vertex -689.234 205.778 74.9234 + vertex -690.454 213.013 71.3473 + vertex -690.424 203.903 71.2175 + endloop + endfacet + facet normal -0.951796 -0.00894427 0.306603 + outer loop + vertex -689.432 214.693 74.569 + vertex -690.454 213.013 71.3473 + vertex -689.234 205.778 74.9234 + endloop + endfacet + facet normal -0.953506 0.0021335 0.301367 + outer loop + vertex -689.432 214.693 74.569 + vertex -690.417 221.655 71.4037 + vertex -690.454 213.013 71.3473 + endloop + endfacet + facet normal -0.957052 -0.00358395 0.289895 + outer loop + vertex -689.23 222.856 75.3371 + vertex -690.417 221.655 71.4037 + vertex -689.432 214.693 74.569 + endloop + endfacet + facet normal -0.957617 0.00309437 0.288026 + outer loop + vertex -689.23 222.856 75.3371 + vertex -690.397 230.23 71.379 + vertex -690.417 221.655 71.4037 + endloop + endfacet + facet normal -0.958626 0.00113114 0.284666 + outer loop + vertex -689.408 232.075 74.7001 + vertex -690.397 230.23 71.379 + vertex -689.23 222.856 75.3371 + endloop + endfacet + facet normal -0.958174 -0.0018362 0.28618 + outer loop + vertex -689.408 232.075 74.7001 + vertex -690.422 238.844 71.3488 + vertex -690.397 230.23 71.379 + endloop + endfacet + facet normal -0.939438 -0.00158282 0.342715 + outer loop + vertex -690.422 238.844 71.3488 + vertex -691.675 237.69 67.9093 + vertex -690.397 230.23 71.379 + endloop + endfacet + facet normal -0.938014 0.000466945 0.346598 + outer loop + vertex -690.397 230.23 71.379 + vertex -691.675 237.69 67.9093 + vertex -691.658 229.157 67.9681 + endloop + endfacet + facet normal -0.93829 0.00321555 0.345835 + outer loop + vertex -690.397 230.23 71.379 + vertex -691.658 229.157 67.9681 + vertex -690.417 221.655 71.4037 + endloop + endfacet + facet normal -0.936684 0.00544919 0.350132 + outer loop + vertex -690.417 221.655 71.4037 + vertex -691.658 229.157 67.9681 + vertex -691.692 220.596 68.0095 + endloop + endfacet + facet normal -0.936316 0.00173457 0.351153 + outer loop + vertex -690.417 221.655 71.4037 + vertex -691.692 220.596 68.0095 + vertex -690.454 213.013 71.3473 + endloop + endfacet + facet normal -0.934057 0.00471774 0.357093 + outer loop + vertex -690.454 213.013 71.3473 + vertex -691.692 220.596 68.0095 + vertex -691.741 211.894 67.9969 + endloop + endfacet + facet normal -0.93259 -0.00820342 0.360843 + outer loop + vertex -690.454 213.013 71.3473 + vertex -691.741 211.894 67.9969 + vertex -690.424 203.903 71.2175 + endloop + endfacet + facet normal -0.930878 -0.00613367 0.365279 + outer loop + vertex -690.424 203.903 71.2175 + vertex -691.741 211.894 67.9969 + vertex -691.741 202.937 67.8472 + endloop + endfacet + facet normal -0.928012 -0.0309225 0.371264 + outer loop + vertex -690.424 203.903 71.2175 + vertex -691.741 202.937 67.8472 + vertex -690.288 194.348 70.7627 + endloop + endfacet + facet normal -0.925173 -0.027982 0.378512 + outer loop + vertex -690.288 194.348 70.7627 + vertex -691.741 202.937 67.8472 + vertex -691.621 193.624 67.4518 + endloop + endfacet + facet normal -0.921245 -0.0610655 0.38416 + outer loop + vertex -690.288 194.348 70.7627 + vertex -691.621 193.624 67.4518 + vertex -689.934 184.529 70.0518 + endloop + endfacet + facet normal -0.918201 -0.0583173 0.391798 + outer loop + vertex -689.934 184.529 70.0518 + vertex -691.621 193.624 67.4518 + vertex -691.296 183.891 66.764 + endloop + endfacet + facet normal -0.939119 -0.00446089 0.343564 + outer loop + vertex -690.422 238.844 71.3488 + vertex -691.718 246.35 67.9056 + vertex -691.675 237.69 67.9093 + endloop + endfacet + facet normal -0.940576 -0.00656717 0.339521 + outer loop + vertex -690.463 247.665 71.4058 + vertex -691.718 246.35 67.9056 + vertex -690.422 238.844 71.3488 + endloop + endfacet + facet normal -0.960998 -0.00625481 0.276484 + outer loop + vertex -689.258 240.43 75.432 + vertex -690.463 247.665 71.4058 + vertex -690.422 238.844 71.3488 + endloop + endfacet + facet normal -0.960482 -0.00516245 0.278293 + outer loop + vertex -689.477 249.89 74.8519 + vertex -690.463 247.665 71.4058 + vertex -689.258 240.43 75.432 + endloop + endfacet + facet normal -0.959176 -0.0123253 0.282542 + outer loop + vertex -689.477 249.89 74.8519 + vertex -690.515 256.914 71.6342 + vertex -690.463 247.665 71.4058 + endloop + endfacet + facet normal -0.941831 -0.0135439 0.335813 + outer loop + vertex -690.515 256.914 71.6342 + vertex -691.75 255.377 68.1071 + vertex -690.463 247.665 71.4058 + endloop + endfacet + facet normal -0.940817 -0.0201046 0.338317 + outer loop + vertex -690.515 256.914 71.6342 + vertex -691.77 264.067 68.5704 + vertex -691.75 255.377 68.1071 + endloop + endfacet + facet normal -0.919176 -0.0229817 0.393175 + outer loop + vertex -691.77 264.067 68.5704 + vertex -693.217 264.522 65.2134 + vertex -691.75 255.377 68.1071 + endloop + endfacet + facet normal -0.913046 -0.0174716 0.407483 + outer loop + vertex -691.75 255.377 68.1071 + vertex -693.217 264.522 65.2134 + vertex -693.217 254.698 64.7908 + endloop + endfacet + facet normal -0.913502 -0.0123932 0.406645 + outer loop + vertex -691.75 255.377 68.1071 + vertex -693.217 254.698 64.7908 + vertex -691.718 246.35 67.9056 + endloop + endfacet + facet normal -0.910118 -0.0089466 0.414253 + outer loop + vertex -691.718 246.35 67.9056 + vertex -693.217 254.698 64.7908 + vertex -693.176 245.745 64.6896 + endloop + endfacet + facet normal -0.910476 -0.0042906 0.413539 + outer loop + vertex -691.718 246.35 67.9056 + vertex -693.176 245.745 64.6896 + vertex -691.675 237.69 67.9093 + endloop + endfacet + facet normal -0.909669 -0.00342825 0.41532 + outer loop + vertex -691.675 237.69 67.9093 + vertex -693.176 245.745 64.6896 + vertex -693.132 237.155 64.7143 + endloop + endfacet + facet normal -0.909953 0.000993174 0.414709 + outer loop + vertex -691.675 237.69 67.9093 + vertex -693.132 237.155 64.7143 + vertex -691.658 229.157 67.9681 + endloop + endfacet + facet normal -0.908035 0.0030444 0.418882 + outer loop + vertex -691.658 229.157 67.9681 + vertex -693.132 237.155 64.7143 + vertex -693.137 228.627 64.7643 + endloop + endfacet + facet normal -0.90819 0.00566627 0.41852 + outer loop + vertex -691.658 229.157 67.9681 + vertex -693.137 228.627 64.7643 + vertex -691.692 220.596 68.0095 + endloop + endfacet + facet normal -0.906788 0.00713342 0.421527 + outer loop + vertex -691.692 220.596 68.0095 + vertex -693.137 228.627 64.7643 + vertex -693.187 220.033 64.8029 + endloop + endfacet + facet normal -0.906623 0.00447016 0.421918 + outer loop + vertex -691.692 220.596 68.0095 + vertex -693.187 220.033 64.8029 + vertex -691.741 211.894 67.9969 + endloop + endfacet + facet normal -0.904782 0.00633151 0.425827 + outer loop + vertex -691.741 211.894 67.9969 + vertex -693.187 220.033 64.8029 + vertex -693.246 211.341 64.8061 + endloop + endfacet + facet normal -0.903873 -0.00717744 0.427741 + outer loop + vertex -691.741 211.894 67.9969 + vertex -693.246 211.341 64.8061 + vertex -691.741 202.937 67.8472 + endloop + endfacet + facet normal -0.901833 -0.00525183 0.432052 + outer loop + vertex -691.741 202.937 67.8472 + vertex -693.246 211.341 64.8061 + vertex -693.252 202.438 64.6859 + endloop + endfacet + facet normal -0.899906 -0.0300566 0.435048 + outer loop + vertex -691.741 202.937 67.8472 + vertex -693.252 202.438 64.6859 + vertex -691.621 193.624 67.4518 + endloop + endfacet + facet normal -0.897335 -0.0278799 0.440468 + outer loop + vertex -691.621 193.624 67.4518 + vertex -693.252 202.438 64.6859 + vertex -693.14 193.14 64.3251 + endloop + endfacet + facet normal -0.893945 -0.0611955 0.44398 + outer loop + vertex -691.621 193.624 67.4518 + vertex -693.14 193.14 64.3251 + vertex -691.296 183.891 66.764 + endloop + endfacet + facet normal -0.890684 -0.0587437 0.450812 + outer loop + vertex -691.296 183.891 66.764 + vertex -693.14 193.14 64.3251 + vertex -692.819 183.37 63.6868 + endloop + endfacet + facet normal -0.919372 -0.0311484 0.392153 + outer loop + vertex -691.77 264.067 68.5704 + vertex -693.079 277.289 66.5515 + vertex -693.217 264.522 65.2134 + endloop + endfacet + facet normal -0.905453 -0.0345361 0.42304 + outer loop + vertex -695.018 273.375 62.0804 + vertex -693.217 264.522 65.2134 + vertex -693.079 277.289 66.5515 + endloop + endfacet + facet normal -0.910067 -0.0217967 0.413888 + outer loop + vertex -695.414 282.561 61.6948 + vertex -695.018 273.375 62.0804 + vertex -693.079 277.289 66.5515 + endloop + endfacet + facet normal -0.909094 -0.0192867 0.416145 + outer loop + vertex -695.414 282.561 61.6948 + vertex -693.079 277.289 66.5515 + vertex -695.244 290.981 62.4549 + endloop + endfacet + facet normal -0.922293 -0.03061 0.385277 + outer loop + vertex -693.079 277.289 66.5515 + vertex -693.501 295.806 67.0112 + vertex -695.244 290.981 62.4549 + endloop + endfacet + facet normal -0.92504 -0.0238062 0.379123 + outer loop + vertex -695.698 300.585 61.9524 + vertex -695.244 290.981 62.4549 + vertex -693.501 295.806 67.0112 + endloop + endfacet + facet normal -0.924657 -0.022562 0.380132 + outer loop + vertex -695.698 300.585 61.9524 + vertex -693.501 295.806 67.0112 + vertex -695.602 308.688 62.6646 + endloop + endfacet + facet normal -0.931982 -0.0301273 0.361251 + outer loop + vertex -693.501 295.806 67.0112 + vertex -693.988 313.436 67.2268 + vertex -695.602 308.688 62.6646 + endloop + endfacet + facet normal -0.932972 -0.0275268 0.358895 + outer loop + vertex -696.095 317.613 62.0685 + vertex -695.602 308.688 62.6646 + vertex -693.988 313.436 67.2268 + endloop + endfacet + facet normal -0.932624 -0.0261042 0.359904 + outer loop + vertex -696.095 317.613 62.0685 + vertex -693.988 313.436 67.2268 + vertex -696.066 325.434 62.7122 + endloop + endfacet + facet normal -0.938232 -0.0328951 0.344439 + outer loop + vertex -693.988 313.436 67.2268 + vertex -694.592 330.631 67.222 + vertex -696.066 325.434 62.7122 + endloop + endfacet + facet normal -0.939491 -0.029793 0.341275 + outer loop + vertex -696.607 334.634 62.0257 + vertex -696.066 325.434 62.7122 + vertex -694.592 330.631 67.222 + endloop + endfacet + facet normal -0.938776 -0.0265396 0.343504 + outer loop + vertex -696.607 334.634 62.0257 + vertex -694.592 330.631 67.222 + vertex -696.611 343.488 62.6979 + endloop + endfacet + facet normal -0.947637 -0.0371952 0.317177 + outer loop + vertex -694.592 330.631 67.222 + vertex -695.372 348.928 67.0364 + vertex -696.611 343.488 62.6979 + endloop + endfacet + facet normal -0.949439 -0.0328398 0.31223 + outer loop + vertex -697.026 352.647 62.3979 + vertex -696.611 343.488 62.6979 + vertex -695.372 348.928 67.0364 + endloop + endfacet + facet normal -0.953837 -0.0562717 0.295006 + outer loop + vertex -695.372 348.928 67.0364 + vertex -698.141 366.116 61.363 + vertex -697.026 352.647 62.3979 + endloop + endfacet + facet normal -0.950357 -0.0518129 0.306817 + outer loop + vertex -696.205 367.695 67.6274 + vertex -698.141 366.116 61.363 + vertex -695.372 348.928 67.0364 + endloop + endfacet + facet normal -0.948603 -0.0652677 0.309667 + outer loop + vertex -696.205 367.695 67.6274 + vertex -699.309 386.648 62.1142 + vertex -698.141 366.116 61.363 + endloop + endfacet + facet normal -0.957986 -0.0764714 0.276434 + outer loop + vertex -697.665 386.627 67.804 + vertex -699.309 386.648 62.1142 + vertex -696.205 367.695 67.6274 + endloop + endfacet + facet normal -0.888736 -0.0187493 0.458036 + outer loop + vertex -694.946 263.399 61.8115 + vertex -693.217 264.522 65.2134 + vertex -695.018 273.375 62.0804 + endloop + endfacet + facet normal -0.888598 -0.0196576 0.458265 + outer loop + vertex -693.217 264.522 65.2134 + vertex -694.946 263.399 61.8115 + vertex -693.217 254.698 64.7908 + endloop + endfacet + facet normal -0.878623 -0.0111286 0.477387 + outer loop + vertex -693.217 254.698 64.7908 + vertex -694.946 263.399 61.8115 + vertex -694.901 254.182 61.6805 + endloop + endfacet + facet normal -0.87875 -0.00951131 0.477187 + outer loop + vertex -693.217 254.698 64.7908 + vertex -694.901 254.182 61.6805 + vertex -693.176 245.745 64.6896 + endloop + endfacet + facet normal -0.874777 -0.00609476 0.484488 + outer loop + vertex -693.176 245.745 64.6896 + vertex -694.901 254.182 61.6805 + vertex -694.85 245.462 61.6628 + endloop + endfacet + facet normal -0.874909 -0.00305352 0.484277 + outer loop + vertex -693.176 245.745 64.6896 + vertex -694.85 245.462 61.6628 + vertex -693.132 237.155 64.7143 + endloop + endfacet + facet normal -0.872459 -0.000926981 0.488686 + outer loop + vertex -693.132 237.155 64.7143 + vertex -694.85 245.462 61.6628 + vertex -694.828 236.906 61.6851 + endloop + endfacet + facet normal -0.872607 0.00342982 0.488411 + outer loop + vertex -693.132 237.155 64.7143 + vertex -694.828 236.906 61.6851 + vertex -693.137 228.627 64.7643 + endloop + endfacet + facet normal -0.871652 0.00425591 0.490107 + outer loop + vertex -693.137 228.627 64.7643 + vertex -694.828 236.906 61.6851 + vertex -694.855 228.303 61.7124 + endloop + endfacet + facet normal -0.871772 0.00723758 0.489858 + outer loop + vertex -693.137 228.627 64.7643 + vertex -694.855 228.303 61.7124 + vertex -693.187 220.033 64.8029 + endloop + endfacet + facet normal -0.869498 0.00918822 0.493851 + outer loop + vertex -693.187 220.033 64.8029 + vertex -694.855 228.303 61.7124 + vertex -694.917 219.626 61.7645 + endloop + endfacet + facet normal -0.869342 0.0061147 0.494174 + outer loop + vertex -693.187 220.033 64.8029 + vertex -694.917 219.626 61.7645 + vertex -693.246 211.341 64.8061 + endloop + endfacet + facet normal -0.868671 0.00667996 0.495345 + outer loop + vertex -693.246 211.341 64.8061 + vertex -694.917 219.626 61.7645 + vertex -694.968 210.9 61.7934 + endloop + endfacet + facet normal -0.867865 -0.00614734 0.496762 + outer loop + vertex -693.246 211.341 64.8061 + vertex -694.968 210.9 61.7934 + vertex -693.252 202.438 64.6859 + endloop + endfacet + facet normal -0.866454 -0.0050168 0.499232 + outer loop + vertex -693.252 202.438 64.6859 + vertex -694.968 210.9 61.7934 + vertex -694.968 202.005 61.7036 + endloop + endfacet + facet normal -0.864513 -0.0298618 0.501723 + outer loop + vertex -693.252 202.438 64.6859 + vertex -694.968 202.005 61.7036 + vertex -693.14 193.14 64.3251 + endloop + endfacet + facet normal -0.862116 -0.0281239 0.505929 + outer loop + vertex -693.14 193.14 64.3251 + vertex -694.968 202.005 61.7036 + vertex -694.865 192.713 61.3634 + endloop + endfacet + facet normal -0.858712 -0.0614781 0.508757 + outer loop + vertex -693.14 193.14 64.3251 + vertex -694.865 192.713 61.3634 + vertex -692.819 183.37 63.6868 + endloop + endfacet + facet normal -0.85514 -0.0591399 0.515013 + outer loop + vertex -692.819 183.37 63.6868 + vertex -694.865 192.713 61.3634 + vertex -694.549 182.915 60.7613 + endloop + endfacet + facet normal -0.946392 -0.0281611 0.32179 + outer loop + vertex -690.725 267.311 71.9277 + vertex -691.77 264.067 68.5704 + vertex -690.515 256.914 71.6342 + endloop + endfacet + facet normal -0.961699 -0.0270859 0.272767 + outer loop + vertex -689.392 258.834 75.784 + vertex -690.725 267.311 71.9277 + vertex -690.515 256.914 71.6342 + endloop + endfacet + facet normal -0.958764 -0.0218032 0.283365 + outer loop + vertex -689.666 267.726 75.5412 + vertex -690.725 267.311 71.9277 + vertex -689.392 258.834 75.784 + endloop + endfacet + facet normal -0.95763 -0.040337 0.285163 + outer loop + vertex -689.666 267.726 75.5412 + vertex -690.641 279.451 73.9238 + vertex -690.725 267.311 71.9277 + endloop + endfacet + facet normal -0.944206 -0.0471378 0.325964 + outer loop + vertex -690.641 279.451 73.9238 + vertex -693.079 277.289 66.5515 + vertex -690.725 267.311 71.9277 + endloop + endfacet + facet normal -0.94643 -0.0295784 0.32155 + outer loop + vertex -690.641 279.451 73.9238 + vertex -693.501 295.806 67.0112 + vertex -693.079 277.289 66.5515 + endloop + endfacet + facet normal -0.950965 -0.0364609 0.307143 + outer loop + vertex -691.236 298.422 74.3337 + vertex -693.501 295.806 67.0112 + vertex -690.641 279.451 73.9238 + endloop + endfacet + facet normal -0.951847 -0.0299889 0.305103 + outer loop + vertex -691.236 298.422 74.3337 + vertex -693.988 313.436 67.2268 + vertex -693.501 295.806 67.0112 + endloop + endfacet + facet normal -0.956032 -0.0374992 0.290856 + outer loop + vertex -691.879 315.926 74.4796 + vertex -693.988 313.436 67.2268 + vertex -691.236 298.422 74.3337 + endloop + endfacet + facet normal -0.956544 -0.0335544 0.289651 + outer loop + vertex -691.879 315.926 74.4796 + vertex -694.592 330.631 67.222 + vertex -693.988 313.436 67.2268 + endloop + endfacet + facet normal -0.960565 -0.0415611 0.274932 + outer loop + vertex -692.638 333.103 74.4215 + vertex -694.592 330.631 67.222 + vertex -691.879 315.926 74.4796 + endloop + endfacet + facet normal -0.961 -0.0382042 0.273897 + outer loop + vertex -692.638 333.103 74.4215 + vertex -695.372 348.928 67.0364 + vertex -694.592 330.631 67.222 + endloop + endfacet + facet normal -0.964605 -0.0454259 0.259757 + outer loop + vertex -693.475 350.623 74.3807 + vertex -695.372 348.928 67.0364 + vertex -692.638 333.103 74.4215 + endloop + endfacet + facet normal -0.964023 -0.0509725 0.260887 + outer loop + vertex -693.475 350.623 74.3807 + vertex -696.205 367.695 67.6274 + vertex -695.372 348.928 67.0364 + endloop + endfacet + facet normal -0.968222 -0.0586757 0.243112 + outer loop + vertex -694.541 368.5 74.4462 + vertex -696.205 367.695 67.6274 + vertex -693.475 350.623 74.3807 + endloop + endfacet + facet normal -0.978694 -0.0591304 0.196627 + outer loop + vertex -692.091 351.485 81.5268 + vertex -694.541 368.5 74.4462 + vertex -693.475 350.623 74.3807 + endloop + endfacet + facet normal -0.979262 -0.0518307 0.195857 + outer loop + vertex -692.091 351.485 81.5268 + vertex -693.475 350.623 74.3807 + vertex -691.178 334.452 81.5835 + endloop + endfacet + facet normal -0.987902 -0.0524599 0.145934 + outer loop + vertex -690.162 335.055 88.6814 + vertex -692.091 351.485 81.5268 + vertex -691.178 334.452 81.5835 + endloop + endfacet + facet normal -0.987844 -0.0533648 0.146003 + outer loop + vertex -690.162 335.055 88.6814 + vertex -691.178 334.452 81.5835 + vertex -689.263 318.479 88.7046 + endloop + endfacet + facet normal -0.992658 -0.0536784 0.108392 + outer loop + vertex -688.514 318.96 95.8018 + vertex -690.162 335.055 88.6814 + vertex -689.263 318.479 88.7046 + endloop + endfacet + facet normal -0.99262 -0.054297 0.10843 + outer loop + vertex -688.514 318.96 95.8018 + vertex -689.263 318.479 88.7046 + vertex -687.615 302.602 95.8377 + endloop + endfacet + facet normal -0.995076 -0.0544884 0.0827918 + outer loop + vertex -687.05 303.227 103.04 + vertex -688.514 318.96 95.8018 + vertex -687.615 302.602 95.8377 + endloop + endfacet + facet normal -0.995261 -0.0514111 0.0825394 + outer loop + vertex -687.05 303.227 103.04 + vertex -687.615 302.602 95.8377 + vertex -686.203 286.985 103.137 + endloop + endfacet + facet normal -0.996589 -0.0515881 0.0644185 + outer loop + vertex -685.774 287.879 110.494 + vertex -687.05 303.227 103.04 + vertex -686.203 286.985 103.137 + endloop + endfacet + facet normal -0.99709 -0.0424249 0.0633349 + outer loop + vertex -685.774 287.879 110.494 + vertex -686.203 286.985 103.137 + vertex -685.074 271.595 110.599 + endloop + endfacet + facet normal -0.997873 -0.0425481 0.0493946 + outer loop + vertex -684.75 272.698 118.107 + vertex -685.774 287.879 110.494 + vertex -685.074 271.595 110.599 + endloop + endfacet + facet normal -0.998444 -0.0292771 0.0474692 + outer loop + vertex -684.75 272.698 118.107 + vertex -685.074 271.595 110.599 + vertex -684.264 256.049 118.053 + endloop + endfacet + facet normal -0.998891 -0.0292563 0.0368786 + outer loop + vertex -684.017 257.232 125.686 + vertex -684.75 272.698 118.107 + vertex -684.264 256.049 118.053 + endloop + endfacet + facet normal -0.999244 -0.0169723 0.0349862 + outer loop + vertex -684.017 257.232 125.686 + vertex -684.264 256.049 118.053 + vertex -683.736 239.871 125.295 + endloop + endfacet + facet normal -0.999479 -0.0168086 0.027545 + outer loop + vertex -683.542 241.021 133.019 + vertex -684.017 257.232 125.686 + vertex -683.736 239.871 125.295 + endloop + endfacet + facet normal -0.999559 -0.0125384 0.0269115 + outer loop + vertex -683.542 241.021 133.019 + vertex -683.736 239.871 125.295 + vertex -683.335 222.843 132.226 + endloop + endfacet + facet normal -0.999689 -0.0123118 0.0216848 + outer loop + vertex -683.179 223.874 140 + vertex -683.542 241.021 133.019 + vertex -683.335 222.843 132.226 + endloop + endfacet + facet normal -0.999482 -0.022473 0.0230284 + outer loop + vertex -683.179 223.874 140 + vertex -683.335 222.843 132.226 + vertex -682.955 211.711 137.882 + endloop + endfacet + facet normal -0.999695 -0.0124532 0.0213379 + outer loop + vertex -683.388 241.953 140.775 + vertex -683.542 241.021 133.019 + vertex -683.179 223.874 140 + endloop + endfacet + facet normal -0.999774 -0.0122826 0.0173347 + outer loop + vertex -683.055 224.66 147.735 + vertex -683.388 241.953 140.775 + vertex -683.179 223.874 140 + endloop + endfacet + facet normal -0.999584 -0.0222747 0.0183472 + outer loop + vertex -683.055 224.66 147.735 + vertex -683.179 223.874 140 + vertex -682.825 212.596 145.632 + endloop + endfacet + facet normal -0.999781 -0.0125062 0.0167795 + outer loop + vertex -683.267 242.662 148.519 + vertex -683.388 241.953 140.775 + vertex -683.055 224.66 147.735 + endloop + endfacet + facet normal -0.999845 -0.0123233 0.0125611 + outer loop + vertex -682.965 225.22 155.446 + vertex -683.267 242.662 148.519 + vertex -683.055 224.66 147.735 + endloop + endfacet + facet normal -0.999663 -0.0223182 0.0132854 + outer loop + vertex -682.965 225.22 155.446 + vertex -683.055 224.66 147.735 + vertex -682.726 213.239 153.32 + endloop + endfacet + facet normal -0.99985 -0.0125979 0.0118699 + outer loop + vertex -683.181 243.159 156.254 + vertex -683.267 242.662 148.519 + vertex -682.965 225.22 155.446 + endloop + endfacet + facet normal -0.999894 -0.0124084 0.0076491 + outer loop + vertex -682.91 225.573 163.19 + vertex -683.181 243.159 156.254 + vertex -682.965 225.22 155.446 + endloop + endfacet + facet normal -0.999712 -0.0225831 0.00811073 + outer loop + vertex -682.91 225.573 163.19 + vertex -682.965 225.22 155.446 + vertex -682.659 213.659 161.028 + endloop + endfacet + facet normal -0.999895 -0.0126594 0.00701278 + outer loop + vertex -683.131 243.453 163.991 + vertex -683.181 243.159 156.254 + vertex -682.91 225.573 163.19 + endloop + endfacet + facet normal -0.999919 -0.012455 0.00244271 + outer loop + vertex -682.893 225.719 170.955 + vertex -683.131 243.453 163.991 + vertex -682.91 225.573 163.19 + endloop + endfacet + facet normal -0.999745 -0.0224484 0.00263027 + outer loop + vertex -682.893 225.719 170.955 + vertex -682.91 225.573 163.19 + vertex -682.632 213.868 168.828 + endloop + endfacet + facet normal -0.999919 -0.0124605 0.00242861 + outer loop + vertex -683.113 243.559 171.721 + vertex -683.131 243.453 163.991 + vertex -682.893 225.719 170.955 + endloop + endfacet + facet normal -0.999924 -0.0123095 -0.00109393 + outer loop + vertex -682.9 225.629 178.661 + vertex -683.113 243.559 171.721 + vertex -682.893 225.719 170.955 + endloop + endfacet + facet normal -0.999748 -0.0224321 -0.00121174 + outer loop + vertex -682.9 225.629 178.661 + vertex -682.893 225.719 170.955 + vertex -682.634 213.854 176.584 + endloop + endfacet + facet normal -0.999917 -0.0126882 -0.00207254 + outer loop + vertex -683.128 243.467 179.441 + vertex -683.113 243.559 171.721 + vertex -682.9 225.629 178.661 + endloop + endfacet + facet normal -0.999907 -0.0125434 -0.00538013 + outer loop + vertex -682.938 225.327 186.375 + vertex -683.128 243.467 179.441 + vertex -682.9 225.629 178.661 + endloop + endfacet + facet normal -0.999732 -0.0224243 -0.00576623 + outer loop + vertex -682.938 225.327 186.375 + vertex -682.9 225.629 178.661 + vertex -682.663 213.602 184.227 + endloop + endfacet + facet normal -0.999894 -0.0130123 -0.00660708 + outer loop + vertex -683.175 243.162 187.182 + vertex -683.128 243.467 179.441 + vertex -682.938 225.327 186.375 + endloop + endfacet + facet normal -0.999867 -0.0128563 -0.01005 + outer loop + vertex -683.01 224.797 194.17 + vertex -683.175 243.162 187.182 + vertex -682.938 225.327 186.375 + endloop + endfacet + facet normal -0.999677 -0.0230324 -0.0107405 + outer loop + vertex -683.01 224.797 194.17 + vertex -682.938 225.327 186.375 + vertex -682.717 213.11 191.998 + endloop + endfacet + facet normal -0.999847 -0.0133392 -0.0113197 + outer loop + vertex -683.257 242.662 194.952 + vertex -683.175 243.162 187.182 + vertex -683.01 224.797 194.17 + endloop + endfacet + facet normal -0.999794 -0.0131582 -0.0154416 + outer loop + vertex -683.12 224.062 201.961 + vertex -683.257 242.662 194.952 + vertex -683.01 224.797 194.17 + endloop + endfacet + facet normal -0.999593 -0.0233564 -0.0164003 + outer loop + vertex -683.12 224.062 201.961 + vertex -683.01 224.797 194.17 + vertex -682.813 212.392 199.851 + endloop + endfacet + facet normal -0.999781 -0.0134034 -0.0160924 + outer loop + vertex -683.373 241.965 202.729 + vertex -683.257 242.662 194.952 + vertex -683.12 224.062 201.961 + endloop + endfacet + facet normal -0.999703 -0.0132136 -0.0204881 + outer loop + vertex -683.267 223.113 209.724 + vertex -683.373 241.965 202.729 + vertex -683.12 224.062 201.961 + endloop + endfacet + facet normal -0.999495 -0.0231958 -0.021705 + outer loop + vertex -683.267 223.113 209.724 + vertex -683.12 224.062 201.961 + vertex -682.95 211.48 207.591 + endloop + endfacet + facet normal -0.999688 -0.0134257 -0.0210598 + outer loop + vertex -683.524 241.061 210.508 + vertex -683.373 241.965 202.729 + vertex -683.267 223.113 209.724 + endloop + endfacet + facet normal -0.999577 -0.0132121 -0.0259094 + outer loop + vertex -683.453 221.94 217.49 + vertex -683.524 241.061 210.508 + vertex -683.267 223.113 209.724 + endloop + endfacet + facet normal -0.999355 -0.0231814 -0.0274093 + outer loop + vertex -683.453 221.94 217.49 + vertex -683.267 223.113 209.724 + vertex -683.125 210.326 215.364 + endloop + endfacet + facet normal -0.999552 -0.0135101 -0.0267259 + outer loop + vertex -683.717 239.971 218.252 + vertex -683.524 241.061 210.508 + vertex -683.453 221.94 217.49 + endloop + endfacet + facet normal -0.99936 -0.0132322 -0.0332307 + outer loop + vertex -683.69 220.591 225.162 + vertex -683.717 239.971 218.252 + vertex -683.453 221.94 217.49 + endloop + endfacet + facet normal -0.999101 -0.0238089 -0.0350829 + outer loop + vertex -683.69 220.591 225.162 + vertex -683.453 221.94 217.49 + vertex -683.341 208.95 223.119 + endloop + endfacet + facet normal -0.999311 -0.0136857 -0.034503 + outer loop + vertex -683.962 238.711 225.866 + vertex -683.717 239.971 218.252 + vertex -683.69 220.591 225.162 + endloop + endfacet + facet normal -0.998883 -0.0132581 -0.0453451 + outer loop + vertex -684.008 219.097 232.618 + vertex -683.962 238.711 225.866 + vertex -683.69 220.591 225.162 + endloop + endfacet + facet normal -0.998548 -0.025043 -0.0476913 + outer loop + vertex -684.008 219.097 232.618 + vertex -683.69 220.591 225.162 + vertex -683.623 207.425 230.677 + endloop + endfacet + facet normal -0.9988 -0.0138201 -0.0469771 + outer loop + vertex -684.293 237.297 233.306 + vertex -683.962 238.711 225.866 + vertex -684.008 219.097 232.618 + endloop + endfacet + facet normal -0.99786 -0.0131602 -0.0640465 + outer loop + vertex -684.455 217.459 239.917 + vertex -684.293 237.297 233.306 + vertex -684.008 219.097 232.618 + endloop + endfacet + facet normal -0.997424 -0.0259233 -0.066884 + outer loop + vertex -684.455 217.459 239.917 + vertex -684.008 219.097 232.618 + vertex -684.021 205.797 237.958 + endloop + endfacet + facet normal -0.997666 -0.0140832 -0.0668113 + outer loop + vertex -684.761 235.73 240.638 + vertex -684.293 237.297 233.306 + vertex -684.455 217.459 239.917 + endloop + endfacet + facet normal -0.995709 -0.0130727 -0.0916117 + outer loop + vertex -685.106 215.713 247.234 + vertex -684.761 235.73 240.638 + vertex -684.455 217.459 239.917 + endloop + endfacet + facet normal -0.995087 -0.0276987 -0.0950471 + outer loop + vertex -685.106 215.713 247.234 + vertex -684.455 217.459 239.917 + vertex -684.588 203.963 245.244 + endloop + endfacet + facet normal -0.995083 -0.0151486 -0.0978784 + outer loop + vertex -685.464 234.157 248.026 + vertex -684.761 235.73 240.638 + vertex -685.106 215.713 247.234 + endloop + endfacet + facet normal -0.990949 -0.0135359 -0.133557 + outer loop + vertex -686.099 214.004 254.781 + vertex -685.464 234.157 248.026 + vertex -685.106 215.713 247.234 + endloop + endfacet + facet normal -0.990048 -0.0307404 -0.137333 + outer loop + vertex -686.099 214.004 254.781 + vertex -685.106 215.713 247.234 + vertex -685.422 202.234 252.532 + endloop + endfacet + facet normal -0.990035 -0.0157041 -0.13994 + outer loop + vertex -686.531 233.008 255.7 + vertex -685.464 234.157 248.026 + vertex -686.099 214.004 254.781 + endloop + endfacet + facet normal -0.990077 -0.0145541 -0.139774 + outer loop + vertex -686.531 233.008 255.7 + vertex -685.774 251.837 248.38 + vertex -685.464 234.157 248.026 + endloop + endfacet + facet normal -0.995074 -0.0154788 -0.0979226 + outer loop + vertex -685.774 251.837 248.38 + vertex -685.072 253.254 241.019 + vertex -685.464 234.157 248.026 + endloop + endfacet + facet normal -0.994623 -0.0267496 -0.10005 + outer loop + vertex -685.774 251.837 248.38 + vertex -685.532 270.078 241.096 + vertex -685.072 253.254 241.019 + endloop + endfacet + facet normal -0.997345 -0.0269714 -0.0676487 + outer loop + vertex -685.532 270.078 241.096 + vertex -685.071 271.464 233.746 + vertex -685.072 253.254 241.019 + endloop + endfacet + facet normal -0.997149 -0.0279459 -0.0700886 + outer loop + vertex -685.072 253.254 241.019 + vertex -685.071 271.464 233.746 + vertex -684.597 254.732 233.669 + endloop + endfacet + facet normal -0.997571 -0.01619 -0.067752 + outer loop + vertex -685.072 253.254 241.019 + vertex -684.597 254.732 233.669 + vertex -684.761 235.73 240.638 + endloop + endfacet + facet normal -0.998431 -0.0280823 -0.048448 + outer loop + vertex -685.071 271.464 233.746 + vertex -684.744 272.691 226.296 + vertex -684.597 254.732 233.669 + endloop + endfacet + facet normal -0.998392 -0.0283463 -0.0490919 + outer loop + vertex -684.597 254.732 233.669 + vertex -684.744 272.691 226.296 + vertex -684.268 256.051 226.224 + endloop + endfacet + facet normal -0.99876 -0.0164337 -0.0469977 + outer loop + vertex -684.597 254.732 233.669 + vertex -684.268 256.051 226.224 + vertex -684.293 237.297 233.306 + endloop + endfacet + facet normal -0.998957 -0.0284201 -0.0357406 + outer loop + vertex -684.744 272.691 226.296 + vertex -684.502 273.727 218.701 + vertex -684.268 256.051 226.224 + endloop + endfacet + facet normal -0.998879 -0.0290956 -0.0373301 + outer loop + vertex -684.268 256.051 226.224 + vertex -684.502 273.727 218.701 + vertex -684.019 257.224 218.637 + endloop + endfacet + facet normal -0.999229 -0.0168841 -0.0354546 + outer loop + vertex -684.268 256.051 226.224 + vertex -684.019 257.224 218.637 + vertex -683.962 238.711 225.866 + endloop + endfacet + facet normal -0.999182 -0.0291405 -0.0280261 + outer loop + vertex -684.502 273.727 218.701 + vertex -684.311 274.611 210.979 + vertex -684.019 257.224 218.637 + endloop + endfacet + facet normal -0.999163 -0.0293504 -0.0285036 + outer loop + vertex -684.019 257.224 218.637 + vertex -684.311 274.611 210.979 + vertex -683.827 258.214 210.906 + endloop + endfacet + facet normal -0.999495 -0.0168917 -0.0269162 + outer loop + vertex -684.019 257.224 218.637 + vertex -683.827 258.214 210.906 + vertex -683.717 239.971 218.252 + endloop + endfacet + facet normal -0.999321 -0.0293831 -0.0222284 + outer loop + vertex -684.311 274.611 210.979 + vertex -684.159 275.348 203.192 + vertex -683.827 258.214 210.906 + endloop + endfacet + facet normal -0.999299 -0.0296579 -0.0228399 + outer loop + vertex -683.827 258.214 210.906 + vertex -684.159 275.348 203.192 + vertex -683.674 259.045 203.121 + endloop + endfacet + facet normal -0.999622 -0.0171477 -0.0215106 + outer loop + vertex -683.827 258.214 210.906 + vertex -683.674 259.045 203.121 + vertex -683.524 241.061 210.508 + endloop + endfacet + facet normal -0.999405 -0.0296841 -0.0175506 + outer loop + vertex -684.159 275.348 203.192 + vertex -684.04 275.931 195.404 + vertex -683.674 259.045 203.121 + endloop + endfacet + facet normal -0.999398 -0.0297894 -0.0177815 + outer loop + vertex -683.674 259.045 203.121 + vertex -684.04 275.931 195.404 + vertex -683.555 259.695 195.34 + endloop + endfacet + facet normal -0.999711 -0.0172499 -0.0167392 + outer loop + vertex -683.674 259.045 203.121 + vertex -683.555 259.695 195.34 + vertex -683.373 241.965 202.729 + endloop + endfacet + facet normal -0.999475 -0.0298117 -0.0127166 + outer loop + vertex -684.04 275.931 195.404 + vertex -683.953 276.348 187.64 + vertex -683.555 259.695 195.34 + endloop + endfacet + facet normal -0.999472 -0.0298592 -0.0128196 + outer loop + vertex -683.555 259.695 195.34 + vertex -683.953 276.348 187.64 + vertex -683.469 260.16 187.579 + endloop + endfacet + facet normal -0.999779 -0.0172191 -0.0120646 + outer loop + vertex -683.555 259.695 195.34 + vertex -683.469 260.16 187.579 + vertex -683.257 242.662 194.952 + endloop + endfacet + facet normal -0.999524 -0.0298799 -0.00772772 + outer loop + vertex -683.953 276.348 187.64 + vertex -683.901 276.596 179.898 + vertex -683.469 260.16 187.579 + endloop + endfacet + facet normal -0.999524 -0.0298716 -0.00771006 + outer loop + vertex -683.469 260.16 187.579 + vertex -683.901 276.596 179.898 + vertex -683.418 260.437 179.836 + endloop + endfacet + facet normal -0.999827 -0.0171056 -0.00725566 + outer loop + vertex -683.469 260.16 187.579 + vertex -683.418 260.437 179.836 + vertex -683.175 243.162 187.182 + endloop + endfacet + facet normal -0.999549 -0.0298915 -0.00273162 + outer loop + vertex -683.901 276.596 179.898 + vertex -683.883 276.682 172.171 + vertex -683.418 260.437 179.836 + endloop + endfacet + facet normal -0.999551 -0.0298365 -0.00261488 + outer loop + vertex -683.418 260.437 179.836 + vertex -683.883 276.682 172.171 + vertex -683.4 260.527 172.109 + endloop + endfacet + facet normal -0.999853 -0.0169952 -0.00246531 + outer loop + vertex -683.418 260.437 179.836 + vertex -683.4 260.527 172.109 + vertex -683.128 243.467 179.441 + endloop + endfacet + facet normal -0.999552 -0.0298549 0.00215048 + outer loop + vertex -683.883 276.682 172.171 + vertex -683.897 276.612 164.45 + vertex -683.4 260.527 172.109 + endloop + endfacet + facet normal -0.999556 -0.0296981 0.00248005 + outer loop + vertex -683.4 260.527 172.109 + vertex -683.897 276.612 164.45 + vertex -683.417 260.439 164.385 + endloop + endfacet + facet normal -0.999854 -0.0169496 0.00233501 + outer loop + vertex -683.4 260.527 172.109 + vertex -683.417 260.439 164.385 + vertex -683.113 243.559 171.721 + endloop + endfacet + facet normal -0.999532 -0.0297166 0.0072691 + outer loop + vertex -683.897 276.612 164.45 + vertex -683.946 276.38 156.723 + vertex -683.417 260.439 164.385 + endloop + endfacet + facet normal -0.999534 -0.0295492 0.00761754 + outer loop + vertex -683.417 260.439 164.385 + vertex -683.946 276.38 156.723 + vertex -683.468 260.17 156.652 + endloop + endfacet + facet normal -0.99983 -0.0169913 0.0071816 + outer loop + vertex -683.417 260.439 164.385 + vertex -683.468 260.17 156.652 + vertex -683.131 243.453 163.991 + endloop + endfacet + facet normal -0.999487 -0.0295685 0.0123439 + outer loop + vertex -683.946 276.38 156.723 + vertex -684.03 275.988 148.982 + vertex -683.468 260.17 156.652 + endloop + endfacet + facet normal -0.999486 -0.0296826 0.0121086 + outer loop + vertex -683.468 260.17 156.652 + vertex -684.03 275.988 148.982 + vertex -683.549 259.739 148.915 + endloop + endfacet + facet normal -0.999789 -0.0170916 0.0114104 + outer loop + vertex -683.468 260.17 156.652 + vertex -683.549 259.739 148.915 + vertex -683.181 243.159 156.254 + endloop + endfacet + facet normal -0.999408 -0.029702 0.0173735 + outer loop + vertex -684.03 275.988 148.982 + vertex -684.149 275.434 141.231 + vertex -683.549 259.739 148.915 + endloop + endfacet + facet normal -0.999407 -0.0295953 0.0175913 + outer loop + vertex -683.549 259.739 148.915 + vertex -684.149 275.434 141.231 + vertex -683.666 259.113 141.166 + endloop + endfacet + facet normal -0.99972 -0.0168717 0.0165682 + outer loop + vertex -683.549 259.739 148.915 + vertex -683.666 259.113 141.166 + vertex -683.267 242.662 148.519 + endloop + endfacet + facet normal -0.999319 -0.0296103 0.0220294 + outer loop + vertex -684.149 275.434 141.231 + vertex -684.298 274.713 133.481 + vertex -683.666 259.113 141.166 + endloop + endfacet + facet normal -0.999309 -0.0290305 0.0232057 + outer loop + vertex -683.666 259.113 141.166 + vertex -684.298 274.713 133.481 + vertex -683.822 258.273 133.411 + endloop + endfacet + facet normal -0.999621 -0.0167158 0.0218788 + outer loop + vertex -683.666 259.113 141.166 + vertex -683.822 258.273 133.411 + vertex -683.388 241.953 140.775 + endloop + endfacet + facet normal -0.999161 -0.0290504 0.0288714 + outer loop + vertex -684.298 274.713 133.481 + vertex -684.494 273.789 125.757 + vertex -683.822 258.273 133.411 + endloop + endfacet + facet normal -0.999158 -0.0289531 0.0290684 + outer loop + vertex -683.822 258.273 133.411 + vertex -684.494 273.789 125.757 + vertex -684.017 257.232 125.686 + endloop + endfacet + facet normal -0.998609 -0.0429869 0.0305236 + outer loop + vertex -684.298 274.713 133.481 + vertex -685.188 289.847 125.676 + vertex -684.494 273.789 125.757 + endloop + endfacet + facet normal -0.998328 -0.0429339 0.0386986 + outer loop + vertex -685.188 289.847 125.676 + vertex -685.444 288.892 118.025 + vertex -684.494 273.789 125.757 + endloop + endfacet + facet normal -0.998317 -0.0425933 0.0393626 + outer loop + vertex -684.494 273.789 125.757 + vertex -685.444 288.892 118.025 + vertex -684.75 272.698 118.107 + endloop + endfacet + facet normal -0.997816 -0.0526496 0.0398933 + outer loop + vertex -685.188 289.847 125.676 + vertex -686.292 304.919 117.958 + vertex -685.444 288.892 118.025 + endloop + endfacet + facet normal -0.997371 -0.0525844 0.0498625 + outer loop + vertex -686.292 304.919 117.958 + vertex -686.622 304.036 110.421 + vertex -685.444 288.892 118.025 + endloop + endfacet + facet normal -0.99735 -0.0521539 0.0507167 + outer loop + vertex -685.444 288.892 118.025 + vertex -686.622 304.036 110.421 + vertex -685.774 287.879 110.494 + endloop + endfacet + facet normal -0.997093 -0.057153 0.0503857 + outer loop + vertex -686.292 304.919 117.958 + vertex -687.549 320.204 110.423 + vertex -686.622 304.036 110.421 + endloop + endfacet + facet normal -0.996451 -0.0571178 0.0618369 + outer loop + vertex -687.549 320.204 110.423 + vertex -687.968 319.509 103.034 + vertex -686.622 304.036 110.421 + endloop + endfacet + facet normal -0.996377 -0.0561313 0.0638901 + outer loop + vertex -686.622 304.036 110.421 + vertex -687.968 319.509 103.034 + vertex -687.05 303.227 103.04 + endloop + endfacet + facet normal -0.996393 -0.058031 0.0619195 + outer loop + vertex -687.549 320.204 110.423 + vertex -688.919 335.891 103.079 + vertex -687.968 319.509 103.034 + endloop + endfacet + facet normal -0.995467 -0.0580145 0.0753625 + outer loop + vertex -688.919 335.891 103.079 + vertex -689.441 335.435 95.8258 + vertex -687.968 319.509 103.034 + endloop + endfacet + facet normal -0.995258 -0.0561606 0.0794157 + outer loop + vertex -687.968 319.509 103.034 + vertex -689.441 335.435 95.8258 + vertex -688.514 318.96 95.8018 + endloop + endfacet + facet normal -0.995377 -0.0594383 0.0754456 + outer loop + vertex -688.919 335.891 103.079 + vertex -690.435 352.123 95.8604 + vertex -689.441 335.435 95.8258 + endloop + endfacet + facet normal -0.993638 -0.0593768 0.0956947 + outer loop + vertex -690.435 352.123 95.8604 + vertex -691.111 351.851 88.6719 + vertex -689.441 335.435 95.8258 + endloop + endfacet + facet normal -0.99309 -0.0561024 0.103081 + outer loop + vertex -689.441 335.435 95.8258 + vertex -691.111 351.851 88.6719 + vertex -690.162 335.055 88.6814 + endloop + endfacet + facet normal -0.992819 -0.0712913 0.0960675 + outer loop + vertex -690.435 352.123 95.8604 + vertex -692.341 368.981 88.6745 + vertex -691.111 351.851 88.6719 + endloop + endfacet + facet normal -0.989147 -0.0710327 0.12862 + outer loop + vertex -692.341 368.981 88.6745 + vertex -693.26 368.84 81.5269 + vertex -691.111 351.851 88.6719 + endloop + endfacet + facet normal -0.98807 -0.0665872 0.138867 + outer loop + vertex -691.111 351.851 88.6719 + vertex -693.26 368.84 81.5269 + vertex -692.091 351.485 81.5268 + endloop + endfacet + facet normal -0.986361 -0.102378 0.128883 + outer loop + vertex -692.341 368.981 88.6745 + vertex -695.089 386.556 81.6064 + vertex -693.26 368.84 81.5269 + endloop + endfacet + facet normal -0.982545 -0.102104 0.155502 + outer loop + vertex -695.089 386.556 81.6064 + vertex -696.184 386.594 74.7094 + vertex -693.26 368.84 81.5269 + endloop + endfacet + facet normal -0.979115 -0.0915444 0.18153 + outer loop + vertex -693.26 368.84 81.5269 + vertex -696.184 386.594 74.7094 + vertex -694.541 368.5 74.4462 + endloop + endfacet + facet normal -0.973767 -0.0914491 0.208363 + outer loop + vertex -696.184 386.594 74.7094 + vertex -697.665 386.627 67.804 + vertex -694.541 368.5 74.4462 + endloop + endfacet + facet normal -0.987317 -0.107302 0.117012 + outer loop + vertex -694.248 386.514 88.6611 + vertex -695.089 386.556 81.6064 + vertex -692.341 368.981 88.6745 + endloop + endfacet + facet normal -0.989964 -0.107609 0.0916004 + outer loop + vertex -691.687 369.101 95.8811 + vertex -694.248 386.514 88.6611 + vertex -692.341 368.981 88.6745 + endloop + endfacet + facet normal -0.990128 -0.109157 0.087924 + outer loop + vertex -693.6 386.471 95.907 + vertex -694.248 386.514 88.6611 + vertex -691.687 369.101 95.8811 + endloop + endfacet + facet normal -0.991756 -0.109305 0.0668827 + outer loop + vertex -691.213 369.252 103.158 + vertex -693.6 386.471 95.907 + vertex -691.687 369.101 95.8811 + endloop + endfacet + facet normal -0.994949 -0.0752976 0.0663847 + outer loop + vertex -691.213 369.252 103.158 + vertex -691.687 369.101 95.8811 + vertex -689.943 352.444 103.125 + endloop + endfacet + facet normal -0.995636 -0.0753271 0.0550906 + outer loop + vertex -689.562 352.794 110.495 + vertex -691.213 369.252 103.158 + vertex -689.943 352.444 103.125 + endloop + endfacet + facet normal -0.996481 -0.0636155 0.0545784 + outer loop + vertex -689.562 352.794 110.495 + vertex -689.943 352.444 103.125 + vertex -688.519 336.432 110.461 + endloop + endfacet + facet normal -0.996898 -0.0636246 0.0463278 + outer loop + vertex -688.204 336.954 117.968 + vertex -689.562 352.794 110.495 + vertex -688.519 336.432 110.461 + endloop + endfacet + facet normal -0.997062 -0.06112 0.0461604 + outer loop + vertex -688.204 336.954 117.968 + vertex -688.519 336.432 110.461 + vertex -687.222 320.917 117.947 + endloop + endfacet + facet normal -0.997401 -0.0611299 0.0381405 + outer loop + vertex -686.968 321.541 125.579 + vertex -688.204 336.954 117.968 + vertex -687.222 320.917 117.947 + endloop + endfacet + facet normal -0.997549 -0.0587877 0.0379538 + outer loop + vertex -686.968 321.541 125.579 + vertex -687.222 320.917 117.947 + vertex -686.035 305.714 125.6 + endloop + endfacet + facet normal -0.997796 -0.0588118 0.0307226 + outer loop + vertex -685.836 306.368 133.314 + vertex -686.968 321.541 125.579 + vertex -686.035 305.714 125.6 + endloop + endfacet + facet normal -0.998119 -0.0533232 0.0302651 + outer loop + vertex -685.836 306.368 133.314 + vertex -686.035 305.714 125.6 + vertex -684.993 290.637 133.397 + endloop + endfacet + facet normal -0.998279 -0.0533631 0.02433 + outer loop + vertex -684.838 291.265 141.146 + vertex -685.836 306.368 133.314 + vertex -684.993 290.637 133.397 + endloop + endfacet + facet normal -0.998783 -0.0433363 0.0235269 + outer loop + vertex -684.838 291.265 141.146 + vertex -684.993 290.637 133.397 + vertex -684.149 275.434 141.231 + endloop + endfacet + facet normal -0.998275 -0.053846 0.0233982 + outer loop + vertex -685.682 306.89 141.063 + vertex -685.836 306.368 133.314 + vertex -684.838 291.265 141.146 + endloop + endfacet + facet normal -0.998378 -0.053878 0.0184047 + outer loop + vertex -684.72 291.743 148.898 + vertex -685.682 306.89 141.063 + vertex -684.838 291.265 141.146 + endloop + endfacet + facet normal -0.998888 -0.0436556 0.0177827 + outer loop + vertex -684.72 291.743 148.898 + vertex -684.838 291.265 141.146 + vertex -684.03 275.988 148.982 + endloop + endfacet + facet normal -0.998375 -0.0540089 0.0181512 + outer loop + vertex -685.563 307.293 148.817 + vertex -685.682 306.89 141.063 + vertex -684.72 291.743 148.898 + endloop + endfacet + facet normal -0.998456 -0.0540407 0.0128664 + outer loop + vertex -684.639 292.079 156.638 + vertex -685.563 307.293 148.817 + vertex -684.72 291.743 148.898 + endloop + endfacet + facet normal -0.998954 -0.043999 0.0124355 + outer loop + vertex -684.639 292.079 156.638 + vertex -684.72 291.743 148.898 + vertex -683.946 276.38 156.723 + endloop + endfacet + facet normal -0.998456 -0.0540487 0.0128508 + outer loop + vertex -685.479 307.579 156.557 + vertex -685.563 307.293 148.817 + vertex -684.639 292.079 156.638 + endloop + endfacet + facet normal -0.998504 -0.0540763 0.00803353 + outer loop + vertex -684.588 292.281 164.364 + vertex -685.479 307.579 156.557 + vertex -684.639 292.079 156.638 + endloop + endfacet + facet normal -0.999002 -0.0439872 0.00777274 + outer loop + vertex -684.588 292.281 164.364 + vertex -684.639 292.079 156.638 + vertex -683.897 276.612 164.45 + endloop + endfacet + facet normal -0.998498 -0.0542497 0.00769294 + outer loop + vertex -685.429 307.748 164.285 + vertex -685.479 307.579 156.557 + vertex -684.588 292.281 164.364 + endloop + endfacet + facet normal -0.998523 -0.0542777 0.00246626 + outer loop + vertex -684.572 292.345 172.086 + vertex -685.429 307.748 164.285 + vertex -684.588 292.281 164.364 + endloop + endfacet + facet normal -0.99903 -0.0439662 0.00238257 + outer loop + vertex -684.572 292.345 172.086 + vertex -684.588 292.281 164.364 + vertex -683.883 276.682 172.171 + endloop + endfacet + facet normal -0.998528 -0.054167 0.00268539 + outer loop + vertex -685.411 307.805 172.007 + vertex -685.429 307.748 164.285 + vertex -684.572 292.345 172.086 + endloop + endfacet + facet normal -0.998526 -0.0541949 -0.00278541 + outer loop + vertex -684.59 292.271 179.813 + vertex -685.411 307.805 172.007 + vertex -684.572 292.345 172.086 + endloop + endfacet + facet normal -0.999032 -0.0438966 -0.0026889 + outer loop + vertex -684.59 292.271 179.813 + vertex -684.572 292.345 172.086 + vertex -683.901 276.596 179.898 + endloop + endfacet + facet normal -0.998523 -0.0542571 -0.00290941 + outer loop + vertex -685.43 307.741 179.735 + vertex -685.411 307.805 172.007 + vertex -684.59 292.271 179.813 + endloop + endfacet + facet normal -0.998492 -0.054282 -0.00816685 + outer loop + vertex -684.641 292.056 187.555 + vertex -685.43 307.741 179.735 + vertex -684.59 292.271 179.813 + endloop + endfacet + facet normal -0.99901 -0.04378 -0.0078787 + outer loop + vertex -684.641 292.056 187.555 + vertex -684.59 292.271 179.813 + vertex -683.953 276.348 187.64 + endloop + endfacet + facet normal -0.998506 -0.0540852 -0.00777072 + outer loop + vertex -685.48 307.561 187.477 + vertex -685.43 307.741 179.735 + vertex -684.641 292.056 187.555 + endloop + endfacet + facet normal -0.998448 -0.0541095 -0.0131893 + outer loop + vertex -684.725 291.701 195.323 + vertex -685.48 307.561 187.477 + vertex -684.641 292.056 187.555 + endloop + endfacet + facet normal -0.998975 -0.0434414 -0.0127074 + outer loop + vertex -684.725 291.701 195.323 + vertex -684.641 292.056 187.555 + vertex -684.04 275.931 195.404 + endloop + endfacet + facet normal -0.998456 -0.054008 -0.0129833 + outer loop + vertex -685.565 307.26 195.245 + vertex -685.48 307.561 187.477 + vertex -684.725 291.701 195.323 + endloop + endfacet + facet normal -0.998364 -0.0540318 -0.018699 + outer loop + vertex -684.843 291.197 203.115 + vertex -685.565 307.26 195.245 + vertex -684.725 291.701 195.323 + endloop + endfacet + facet normal -0.998904 -0.0431943 -0.0180058 + outer loop + vertex -684.843 291.197 203.115 + vertex -684.725 291.701 195.323 + vertex -684.159 275.348 203.192 + endloop + endfacet + facet normal -0.998393 -0.0537193 -0.0180586 + outer loop + vertex -685.684 306.841 203.038 + vertex -685.565 307.26 195.245 + vertex -684.843 291.197 203.115 + endloop + endfacet + facet normal -0.998261 -0.0537429 -0.0242271 + outer loop + vertex -684.998 290.556 210.902 + vertex -685.684 306.841 203.038 + vertex -684.843 291.197 203.115 + endloop + endfacet + facet normal -0.998796 -0.0431397 -0.0233649 + outer loop + vertex -684.998 290.556 210.902 + vertex -684.843 291.197 203.115 + vertex -684.311 274.611 210.979 + endloop + endfacet + facet normal -0.99832 -0.0531676 -0.0230306 + outer loop + vertex -685.835 306.318 210.826 + vertex -685.684 306.841 203.038 + vertex -684.998 290.556 210.902 + endloop + endfacet + facet normal -0.998149 -0.0531899 -0.0294808 + outer loop + vertex -685.186 289.801 218.626 + vertex -685.835 306.318 210.826 + vertex -684.998 290.556 210.902 + endloop + endfacet + facet normal -0.998686 -0.0426276 -0.0284609 + outer loop + vertex -685.186 289.801 218.626 + vertex -684.998 290.556 210.902 + vertex -684.502 273.727 218.701 + endloop + endfacet + facet normal -0.998189 -0.0528466 -0.0287507 + outer loop + vertex -686.025 305.695 218.553 + vertex -685.835 306.318 210.826 + vertex -685.186 289.801 218.626 + endloop + endfacet + facet normal -0.997898 -0.0528714 -0.0374779 + outer loop + vertex -685.424 288.902 226.23 + vertex -686.025 305.695 218.553 + vertex -685.186 289.801 218.626 + endloop + endfacet + facet normal -0.998461 -0.0420087 -0.0362122 + outer loop + vertex -685.424 288.902 226.23 + vertex -685.186 289.801 218.626 + vertex -684.744 272.691 226.296 + endloop + endfacet + facet normal -0.997981 -0.0522519 -0.0361164 + outer loop + vertex -686.262 304.951 226.165 + vertex -686.025 305.695 218.553 + vertex -685.424 288.902 226.23 + endloop + endfacet + facet normal -0.997382 -0.0522761 -0.0499732 + outer loop + vertex -685.74 287.814 233.693 + vertex -686.262 304.951 226.165 + vertex -685.424 288.902 226.23 + endloop + endfacet + facet normal -0.997987 -0.041027 -0.0483581 + outer loop + vertex -685.74 287.814 233.693 + vertex -685.424 288.902 226.23 + vertex -685.071 271.464 233.746 + endloop + endfacet + facet normal -0.99758 -0.0510598 -0.0471904 + outer loop + vertex -686.568 304.038 233.636 + vertex -686.262 304.951 226.165 + vertex -685.74 287.814 233.693 + endloop + endfacet + facet normal -0.996303 -0.0510714 -0.0690732 + outer loop + vertex -686.185 286.551 241.034 + vertex -686.568 304.038 233.636 + vertex -685.74 287.814 233.693 + endloop + endfacet + facet normal -0.99695 -0.039755 -0.067165 + outer loop + vertex -686.185 286.551 241.034 + vertex -685.74 287.814 233.693 + vertex -685.532 270.078 241.096 + endloop + endfacet + facet normal -0.994285 -0.0397677 -0.0990756 + outer loop + vertex -686.203 268.735 248.369 + vertex -686.185 286.551 241.034 + vertex -685.532 270.078 241.096 + endloop + endfacet + facet normal -0.994801 -0.0378948 -0.0945272 + outer loop + vertex -686.826 285.296 248.289 + vertex -686.185 286.551 241.034 + vertex -686.203 268.735 248.369 + endloop + endfacet + facet normal -0.990259 -0.0379128 -0.133975 + outer loop + vertex -687.133 267.802 255.508 + vertex -686.826 285.296 248.289 + vertex -686.203 268.735 248.369 + endloop + endfacet + facet normal -0.990934 -0.0238233 -0.132221 + outer loop + vertex -687.133 267.802 255.508 + vertex -686.203 268.735 248.369 + vertex -686.754 251.033 255.689 + endloop + endfacet + facet normal -0.990445 -0.0252269 -0.135579 + outer loop + vertex -686.754 251.033 255.689 + vertex -686.203 268.735 248.369 + vertex -685.774 251.837 248.38 + endloop + endfacet + facet normal -0.990327 -0.0377262 -0.133525 + outer loop + vertex -687.767 284.336 255.541 + vertex -686.826 285.296 248.289 + vertex -687.133 267.802 255.508 + endloop + endfacet + facet normal -0.989783 -0.0468513 -0.134663 + outer loop + vertex -687.767 284.336 255.541 + vertex -687.609 301.886 248.267 + vertex -686.826 285.296 248.289 + endloop + endfacet + facet normal -0.994749 -0.0470269 -0.0908957 + outer loop + vertex -687.609 301.886 248.267 + vertex -686.994 302.96 240.981 + vertex -686.826 285.296 248.289 + endloop + endfacet + facet normal -0.994224 -0.0551828 -0.0920538 + outer loop + vertex -687.609 301.886 248.267 + vertex -687.904 319.375 240.979 + vertex -686.994 302.96 240.981 + endloop + endfacet + facet normal -0.996535 -0.0553079 -0.0621259 + outer loop + vertex -687.904 319.375 240.979 + vertex -687.494 320.24 233.627 + vertex -686.994 302.96 240.981 + endloop + endfacet + facet normal -0.996189 -0.056968 -0.06605 + outer loop + vertex -686.994 302.96 240.981 + vertex -687.494 320.24 233.627 + vertex -686.568 304.038 233.636 + endloop + endfacet + facet normal -0.997332 -0.0570211 -0.0455797 + outer loop + vertex -687.494 320.24 233.627 + vertex -687.194 320.958 226.154 + vertex -686.568 304.038 233.636 + endloop + endfacet + facet normal -0.997044 -0.0615396 -0.0460023 + outer loop + vertex -687.494 320.24 233.627 + vertex -688.183 336.971 226.18 + vertex -687.194 320.958 226.154 + endloop + endfacet + facet normal -0.997514 -0.0615879 -0.0342314 + outer loop + vertex -688.183 336.971 226.18 + vertex -687.947 337.38 218.563 + vertex -687.194 320.958 226.154 + endloop + endfacet + facet normal -0.997418 -0.062285 -0.0357494 + outer loop + vertex -687.194 320.958 226.154 + vertex -687.947 337.38 218.563 + vertex -686.957 321.536 218.538 + endloop + endfacet + facet normal -0.99768 -0.0581212 -0.0354416 + outer loop + vertex -687.194 320.958 226.154 + vertex -686.957 321.536 218.538 + vertex -686.262 304.951 226.165 + endloop + endfacet + facet normal -0.99767 -0.0623135 -0.0277802 + outer loop + vertex -687.947 337.38 218.563 + vertex -687.753 337.728 210.829 + vertex -686.957 321.536 218.538 + endloop + endfacet + facet normal -0.997628 -0.0626595 -0.0285113 + outer loop + vertex -686.957 321.536 218.538 + vertex -687.753 337.728 210.829 + vertex -686.766 322.018 210.806 + endloop + endfacet + facet normal -0.997874 -0.0587209 -0.0282716 + outer loop + vertex -686.957 321.536 218.538 + vertex -686.766 322.018 210.806 + vertex -686.025 305.695 218.553 + endloop + endfacet + facet normal -0.997783 -0.0626785 -0.0223917 + outer loop + vertex -687.753 337.728 210.829 + vertex -687.598 338.032 203.037 + vertex -686.766 322.018 210.806 + endloop + endfacet + facet normal -0.997756 -0.0629216 -0.0228957 + outer loop + vertex -686.766 322.018 210.806 + vertex -687.598 338.032 203.037 + vertex -686.613 322.43 203.017 + endloop + endfacet + facet normal -0.997989 -0.0591858 -0.0227029 + outer loop + vertex -686.766 322.018 210.806 + vertex -686.613 322.43 203.017 + vertex -685.835 306.318 210.826 + endloop + endfacet + facet normal -0.997868 -0.0629357 -0.0173029 + outer loop + vertex -687.598 338.032 203.037 + vertex -687.478 338.285 195.243 + vertex -686.613 322.43 203.017 + endloop + endfacet + facet normal -0.997826 -0.0633564 -0.0181657 + outer loop + vertex -686.613 322.43 203.017 + vertex -687.478 338.285 195.243 + vertex -686.493 322.767 195.224 + endloop + endfacet + facet normal -0.998063 -0.0595466 -0.0180047 + outer loop + vertex -686.613 322.43 203.017 + vertex -686.493 322.767 195.224 + vertex -685.684 306.841 203.038 + endloop + endfacet + facet normal -0.997912 -0.0633689 -0.0124814 + outer loop + vertex -687.478 338.285 195.243 + vertex -687.393 338.47 187.478 + vertex -686.493 322.767 195.224 + endloop + endfacet + facet normal -0.997895 -0.0635616 -0.012874 + outer loop + vertex -686.493 322.767 195.224 + vertex -687.393 338.47 187.478 + vertex -686.408 323.009 187.458 + endloop + endfacet + facet normal -0.998133 -0.059726 -0.012757 + outer loop + vertex -686.493 322.767 195.224 + vertex -686.408 323.009 187.458 + vertex -685.565 307.26 195.245 + endloop + endfacet + facet normal -0.997949 -0.063572 -0.0075704 + outer loop + vertex -687.393 338.47 187.478 + vertex -687.342 338.582 179.74 + vertex -686.408 323.009 187.458 + endloop + endfacet + facet normal -0.997942 -0.063656 -0.00774082 + outer loop + vertex -686.408 323.009 187.458 + vertex -687.342 338.582 179.74 + vertex -686.357 323.154 179.718 + endloop + endfacet + facet normal -0.998172 -0.0599457 -0.00767275 + outer loop + vertex -686.408 323.009 187.458 + vertex -686.357 323.154 179.718 + vertex -685.48 307.561 187.477 + endloop + endfacet + facet normal -0.997968 -0.0636656 -0.00239937 + outer loop + vertex -687.342 338.582 179.74 + vertex -687.326 338.624 172.017 + vertex -686.357 323.154 179.718 + endloop + endfacet + facet normal -0.997964 -0.0637326 -0.00253452 + outer loop + vertex -686.357 323.154 179.718 + vertex -687.326 338.624 172.017 + vertex -686.341 323.203 171.992 + endloop + endfacet + facet normal -0.998192 -0.0600573 -0.0025116 + outer loop + vertex -686.357 323.154 179.718 + vertex -686.341 323.203 171.992 + vertex -685.43 307.741 179.735 + endloop + endfacet + facet normal -0.997963 -0.0637407 0.00250821 + outer loop + vertex -687.326 338.624 172.017 + vertex -687.343 338.595 164.294 + vertex -686.341 323.203 171.992 + endloop + endfacet + facet normal -0.997965 -0.0637083 0.0025732 + outer loop + vertex -686.341 323.203 171.992 + vertex -687.343 338.595 164.294 + vertex -686.358 323.16 164.269 + endloop + endfacet + facet normal -0.998179 -0.0602748 0.00255444 + outer loop + vertex -686.341 323.203 171.992 + vertex -686.358 323.16 164.269 + vertex -685.411 307.805 172.007 + endloop + endfacet + facet normal -0.99794 -0.0637146 0.00743648 + outer loop + vertex -687.343 338.595 164.294 + vertex -687.395 338.497 156.562 + vertex -686.358 323.16 164.269 + endloop + endfacet + facet normal -0.997946 -0.0636056 0.00765419 + outer loop + vertex -686.358 323.16 164.269 + vertex -687.395 338.497 156.562 + vertex -686.409 323.024 156.54 + endloop + endfacet + facet normal -0.998159 -0.0601807 0.00759564 + outer loop + vertex -686.358 323.16 164.269 + vertex -686.409 323.024 156.54 + vertex -685.429 307.748 164.285 + endloop + endfacet + facet normal -0.9979 -0.0636094 0.0122129 + outer loop + vertex -687.395 338.497 156.562 + vertex -687.479 338.329 148.817 + vertex -686.409 323.024 156.54 + endloop + endfacet + facet normal -0.997914 -0.0632491 0.0129289 + outer loop + vertex -686.409 323.024 156.54 + vertex -687.479 338.329 148.817 + vertex -686.494 322.796 148.797 + endloop + endfacet + facet normal -0.998112 -0.0600594 0.0128369 + outer loop + vertex -686.409 323.024 156.54 + vertex -686.494 322.796 148.797 + vertex -685.479 307.579 156.557 + endloop + endfacet + facet normal -0.997842 -0.0632505 0.0176132 + outer loop + vertex -687.479 338.329 148.817 + vertex -687.601 338.093 141.058 + vertex -686.494 322.796 148.797 + endloop + endfacet + facet normal -0.997847 -0.0630979 0.0179153 + outer loop + vertex -686.494 322.796 148.797 + vertex -687.601 338.093 141.058 + vertex -686.613 322.473 141.041 + endloop + endfacet + facet normal -0.998044 -0.0599332 0.0177866 + outer loop + vertex -686.494 322.796 148.797 + vertex -686.613 322.473 141.041 + vertex -685.563 307.293 148.817 + endloop + endfacet + facet normal -0.997751 -0.063097 0.0226118 + outer loop + vertex -687.601 338.093 141.058 + vertex -687.757 337.785 133.304 + vertex -686.613 322.473 141.041 + endloop + endfacet + facet normal -0.997759 -0.0626607 0.0234764 + outer loop + vertex -686.613 322.473 141.041 + vertex -687.757 337.785 133.304 + vertex -686.769 322.056 133.29 + endloop + endfacet + facet normal -0.997951 -0.0595875 0.0233149 + outer loop + vertex -686.613 322.473 141.041 + vertex -686.769 322.056 133.29 + vertex -685.682 306.89 141.063 + endloop + endfacet + facet normal -0.997624 -0.0626568 0.0286466 + outer loop + vertex -687.757 337.785 133.304 + vertex -687.955 337.407 125.593 + vertex -686.769 322.056 133.29 + endloop + endfacet + facet normal -0.997626 -0.0620469 0.0298633 + outer loop + vertex -686.769 322.056 133.29 + vertex -687.955 337.407 125.593 + vertex -686.968 321.541 125.579 + endloop + endfacet + facet normal -0.997391 -0.0661895 0.0288138 + outer loop + vertex -687.757 337.785 133.304 + vertex -689.016 353.406 125.613 + vertex -687.955 337.407 125.593 + endloop + endfacet + facet normal -0.997215 -0.0661849 0.0343649 + outer loop + vertex -689.016 353.406 125.613 + vertex -689.26 353.123 117.993 + vertex -687.955 337.407 125.593 + endloop + endfacet + facet normal -0.997208 -0.0651614 0.0364802 + outer loop + vertex -687.955 337.407 125.593 + vertex -689.26 353.123 117.993 + vertex -688.204 336.954 117.968 + endloop + endfacet + facet normal -0.996261 -0.0790758 0.0348135 + outer loop + vertex -689.016 353.406 125.613 + vertex -690.561 369.552 118.054 + vertex -689.26 353.123 117.993 + endloop + endfacet + facet normal -0.996092 -0.0790792 0.039323 + outer loop + vertex -690.561 369.552 118.054 + vertex -690.846 369.406 110.543 + vertex -689.26 353.123 117.993 + endloop + endfacet + facet normal -0.996068 -0.0771276 0.0435832 + outer loop + vertex -689.26 353.123 117.993 + vertex -690.846 369.406 110.543 + vertex -689.562 352.794 110.495 + endloop + endfacet + facet normal -0.993053 -0.110725 0.0398236 + outer loop + vertex -690.561 369.552 118.054 + vertex -692.732 386.387 110.727 + vertex -690.846 369.406 110.543 + endloop + endfacet + facet normal -0.992622 -0.110779 0.0492851 + outer loop + vertex -692.732 386.387 110.727 + vertex -693.11 386.429 103.207 + vertex -690.846 369.406 110.543 + endloop + endfacet + facet normal -0.992615 -0.109777 0.0516085 + outer loop + vertex -690.846 369.406 110.543 + vertex -693.11 386.429 103.207 + vertex -691.213 369.252 103.158 + endloop + endfacet + facet normal -0.993026 -0.111889 0.0371397 + outer loop + vertex -692.447 386.348 118.233 + vertex -692.732 386.387 110.727 + vertex -690.561 369.552 118.054 + endloop + endfacet + facet normal -0.993171 -0.111863 0.0331316 + outer loop + vertex -690.321 369.669 125.649 + vertex -692.447 386.348 118.233 + vertex -690.561 369.552 118.054 + endloop + endfacet + facet normal -0.993093 -0.113688 0.0290057 + outer loop + vertex -692.227 386.314 125.633 + vertex -692.447 386.348 118.233 + vertex -690.321 369.669 125.649 + endloop + endfacet + facet normal -0.993147 -0.113696 0.0270482 + outer loop + vertex -690.122 369.764 133.36 + vertex -692.227 386.314 125.633 + vertex -690.321 369.669 125.649 + endloop + endfacet + facet normal -0.996403 -0.0804225 0.0267206 + outer loop + vertex -690.122 369.764 133.36 + vertex -690.321 369.669 125.649 + vertex -688.822 353.648 133.324 + endloop + endfacet + facet normal -0.9965 -0.0804214 0.0228223 + outer loop + vertex -688.66 353.836 141.081 + vertex -690.122 369.764 133.36 + vertex -688.822 353.648 133.324 + endloop + endfacet + facet normal -0.997489 -0.0671441 0.0225209 + outer loop + vertex -688.66 353.836 141.081 + vertex -688.822 353.648 133.324 + vertex -687.601 338.093 141.058 + endloop + endfacet + facet normal -0.996454 -0.0816658 0.0202465 + outer loop + vertex -689.971 369.848 141.154 + vertex -690.122 369.764 133.36 + vertex -688.66 353.836 141.081 + endloop + endfacet + facet normal -0.996517 -0.0816557 0.0168995 + outer loop + vertex -688.54 353.986 148.845 + vertex -689.971 369.848 141.154 + vertex -688.66 353.836 141.081 + endloop + endfacet + facet normal -0.997568 -0.0676817 0.0166459 + outer loop + vertex -688.54 353.986 148.845 + vertex -688.66 353.836 141.081 + vertex -687.479 338.329 148.817 + endloop + endfacet + facet normal -0.996507 -0.0818725 0.0164505 + outer loop + vertex -689.847 369.905 148.914 + vertex -689.971 369.848 141.154 + vertex -688.54 353.986 148.845 + endloop + endfacet + facet normal -0.996567 -0.0818597 0.012381 + outer loop + vertex -688.452 354.086 156.593 + vertex -689.847 369.905 148.914 + vertex -688.54 353.986 148.845 + endloop + endfacet + facet normal -0.99763 -0.0677215 0.0122114 + outer loop + vertex -688.452 354.086 156.593 + vertex -688.54 353.986 148.845 + vertex -687.395 338.497 156.562 + endloop + endfacet + facet normal -0.996542 -0.0822864 0.0114975 + outer loop + vertex -689.761 369.943 156.646 + vertex -689.847 369.905 148.914 + vertex -688.452 354.086 156.593 + endloop + endfacet + facet normal -0.996587 -0.082274 0.00669734 + outer loop + vertex -688.405 354.147 164.324 + vertex -689.761 369.943 156.646 + vertex -688.452 354.086 156.593 + endloop + endfacet + facet normal -0.997653 -0.0681575 0.00659275 + outer loop + vertex -688.405 354.147 164.324 + vertex -688.452 354.086 156.593 + vertex -687.343 338.595 164.294 + endloop + endfacet + facet normal -0.996606 -0.0819955 0.00727362 + outer loop + vertex -689.706 369.958 164.369 + vertex -689.761 369.943 156.646 + vertex -688.405 354.147 164.324 + endloop + endfacet + facet normal -0.996629 -0.081985 0.00285298 + outer loop + vertex -688.384 354.156 172.046 + vertex -689.706 369.958 164.369 + vertex -688.405 354.147 164.324 + endloop + endfacet + facet normal -0.997682 -0.0679958 0.00283819 + outer loop + vertex -688.384 354.156 172.046 + vertex -688.405 354.147 164.324 + vertex -687.326 338.624 172.017 + endloop + endfacet + facet normal -0.996577 -0.0826547 0.00146544 + outer loop + vertex -689.695 369.962 172.107 + vertex -689.706 369.958 164.369 + vertex -688.384 354.156 172.046 + endloop + endfacet + facet normal -0.996576 -0.0826377 -0.00286623 + outer loop + vertex -688.404 354.125 179.77 + vertex -689.695 369.962 172.107 + vertex -688.384 354.156 172.046 + endloop + endfacet + facet normal -0.997669 -0.0681774 -0.00281114 + outer loop + vertex -688.404 354.125 179.77 + vertex -688.384 354.156 172.046 + vertex -687.342 338.582 179.74 + endloop + endfacet + facet normal -0.996615 -0.0821878 -0.00192983 + outer loop + vertex -689.708 369.937 179.858 + vertex -689.695 369.962 172.107 + vertex -688.404 354.125 179.77 + endloop + endfacet + facet normal -0.996595 -0.082158 -0.00700813 + outer loop + vertex -688.451 354.043 187.506 + vertex -689.708 369.937 179.858 + vertex -688.404 354.125 179.77 + endloop + endfacet + facet normal -0.997676 -0.0677878 -0.00686178 + outer loop + vertex -688.451 354.043 187.506 + vertex -688.404 354.125 179.77 + vertex -687.393 338.47 187.478 + endloop + endfacet + facet normal -0.99659 -0.0822052 -0.00710708 + outer loop + vertex -689.759 369.894 187.569 + vertex -689.708 369.937 179.858 + vertex -688.451 354.043 187.506 + endloop + endfacet + facet normal -0.996541 -0.0821802 -0.0123806 + outer loop + vertex -688.537 353.914 195.273 + vertex -689.759 369.894 187.569 + vertex -688.451 354.043 187.506 + endloop + endfacet + facet normal -0.997641 -0.0675624 -0.0121506 + outer loop + vertex -688.537 353.914 195.273 + vertex -688.451 354.043 187.506 + vertex -687.478 338.285 195.243 + endloop + endfacet + facet normal -0.996573 -0.0818837 -0.0117605 + outer loop + vertex -689.846 369.828 195.333 + vertex -689.759 369.894 187.569 + vertex -688.537 353.914 195.273 + endloop + endfacet + facet normal -0.996493 -0.081856 -0.0173551 + outer loop + vertex -688.659 353.744 203.075 + vertex -689.846 369.828 195.333 + vertex -688.537 353.914 195.273 + endloop + endfacet + facet normal -0.997583 -0.0673567 -0.0170555 + outer loop + vertex -688.659 353.744 203.075 + vertex -688.537 353.914 195.273 + vertex -687.598 338.032 203.037 + endloop + endfacet + facet normal -0.996551 -0.0813582 -0.0163121 + outer loop + vertex -689.967 369.747 203.182 + vertex -689.846 369.828 195.333 + vertex -688.659 353.744 203.075 + endloop + endfacet + facet normal -0.996436 -0.0813073 -0.0224766 + outer loop + vertex -688.819 353.548 210.872 + vertex -689.967 369.747 203.182 + vertex -688.659 353.744 203.075 + endloop + endfacet + facet normal -0.997498 -0.0671317 -0.0221426 + outer loop + vertex -688.819 353.548 210.872 + vertex -688.659 353.744 203.075 + vertex -687.753 337.728 210.829 + endloop + endfacet + facet normal -0.996546 -0.0804381 -0.0206291 + outer loop + vertex -690.121 369.657 210.948 + vertex -689.967 369.747 203.182 + vertex -688.819 353.548 210.872 + endloop + endfacet + facet normal -0.996394 -0.0803951 -0.0271329 + outer loop + vertex -689.012 353.331 218.602 + vertex -690.121 369.657 210.948 + vertex -688.819 353.548 210.872 + endloop + endfacet + facet normal -0.997425 -0.0665302 -0.0267683 + outer loop + vertex -689.012 353.331 218.602 + vertex -688.819 353.548 210.872 + vertex -687.947 337.38 218.563 + endloop + endfacet + facet normal -0.996398 -0.0803628 -0.0270633 + outer loop + vertex -690.323 369.568 218.67 + vertex -690.121 369.657 210.948 + vertex -689.012 353.331 218.602 + endloop + endfacet + facet normal -0.996176 -0.080314 -0.0344071 + outer loop + vertex -689.254 353.071 226.217 + vertex -690.323 369.568 218.67 + vertex -689.012 353.331 218.602 + endloop + endfacet + facet normal -0.997225 -0.0662551 -0.033962 + outer loop + vertex -689.254 353.071 226.217 + vertex -689.012 353.331 218.602 + vertex -688.183 336.971 226.18 + endloop + endfacet + facet normal -0.9968 -0.0662017 -0.044805 + outer loop + vertex -688.484 336.438 233.651 + vertex -689.254 353.071 226.217 + vertex -688.183 336.971 226.18 + endloop + endfacet + facet normal -0.996981 -0.0650964 -0.0423132 + outer loop + vertex -689.548 352.711 233.693 + vertex -689.254 353.071 226.217 + vertex -688.484 336.438 233.651 + endloop + endfacet + facet normal -0.9961 -0.0649943 -0.0596632 + outer loop + vertex -688.881 335.772 241.01 + vertex -689.548 352.711 233.693 + vertex -688.484 336.438 233.651 + endloop + endfacet + facet normal -0.99649 -0.0592309 -0.0591626 + outer loop + vertex -688.881 335.772 241.01 + vertex -688.484 336.438 233.651 + vertex -687.904 319.375 240.979 + endloop + endfacet + facet normal -0.994361 -0.0590492 -0.0880922 + outer loop + vertex -688.5 318.514 248.284 + vertex -688.881 335.772 241.01 + vertex -687.904 319.375 240.979 + endloop + endfacet + facet normal -0.994964 -0.0567562 -0.0826202 + outer loop + vertex -689.447 335.078 248.305 + vertex -688.881 335.772 241.01 + vertex -688.5 318.514 248.284 + endloop + endfacet + facet normal -0.990975 -0.056479 -0.121571 + outer loop + vertex -689.366 317.982 255.583 + vertex -689.447 335.078 248.305 + vertex -688.5 318.514 248.284 + endloop + endfacet + facet normal -0.99145 -0.0486995 -0.12106 + outer loop + vertex -689.366 317.982 255.583 + vertex -688.5 318.514 248.284 + vertex -688.542 301.171 255.598 + endloop + endfacet + facet normal -0.984031 -0.0483811 -0.171296 + outer loop + vertex -689.833 301.263 262.989 + vertex -689.366 317.982 255.583 + vertex -688.542 301.171 255.598 + endloop + endfacet + facet normal -0.984392 -0.039648 -0.171468 + outer loop + vertex -689.833 301.263 262.989 + vertex -688.542 301.171 255.598 + vertex -689.134 283.87 262.998 + endloop + endfacet + facet normal -0.982151 -0.0445479 -0.182745 + outer loop + vertex -689.134 283.87 262.998 + vertex -688.542 301.171 255.598 + vertex -687.767 284.336 255.541 + endloop + endfacet + facet normal -0.982509 -0.0376064 -0.182377 + outer loop + vertex -689.134 283.87 262.998 + vertex -687.767 284.336 255.541 + vertex -688.422 267.165 262.607 + endloop + endfacet + facet normal -0.982638 -0.0373373 -0.181735 + outer loop + vertex -688.422 267.165 262.607 + vertex -687.767 284.336 255.541 + vertex -687.133 267.802 255.508 + endloop + endfacet + facet normal -0.98308 -0.0281956 -0.180996 + outer loop + vertex -688.422 267.165 262.607 + vertex -687.133 267.802 255.508 + vertex -687.93 251.477 262.38 + endloop + endfacet + facet normal -0.984889 -0.0241101 -0.1715 + outer loop + vertex -687.93 251.477 262.38 + vertex -687.133 267.802 255.508 + vertex -686.754 251.033 255.689 + endloop + endfacet + facet normal -0.984966 -0.00927008 -0.172499 + outer loop + vertex -687.93 251.477 262.38 + vertex -686.754 251.033 255.689 + vertex -687.949 233.674 263.444 + endloop + endfacet + facet normal -0.983755 -0.0123009 -0.179097 + outer loop + vertex -687.949 233.674 263.444 + vertex -686.754 251.033 255.689 + vertex -686.531 233.008 255.7 + endloop + endfacet + facet normal -0.983727 -0.00731913 -0.17952 + outer loop + vertex -687.949 233.674 263.444 + vertex -686.531 233.008 255.7 + vertex -687.813 212.319 263.573 + endloop + endfacet + facet normal -0.980969 -0.0128993 -0.193735 + outer loop + vertex -687.813 212.319 263.573 + vertex -686.531 233.008 255.7 + vertex -686.099 214.004 254.781 + endloop + endfacet + facet normal -0.979468 -0.0372925 -0.19812 + outer loop + vertex -687.813 212.319 263.573 + vertex -686.099 214.004 254.781 + vertex -686.616 200.038 259.962 + endloop + endfacet + facet normal -0.986259 -0.0430883 -0.159488 + outer loop + vertex -690.531 318.124 262.754 + vertex -689.366 317.982 255.583 + vertex -689.833 301.263 262.989 + endloop + endfacet + facet normal -0.985865 -0.0520682 -0.159246 + outer loop + vertex -690.531 318.124 262.754 + vertex -690.235 334.603 255.53 + vertex -689.366 317.982 255.583 + endloop + endfacet + facet normal -0.988034 -0.0466648 -0.147009 + outer loop + vertex -691.277 334.504 262.567 + vertex -690.235 334.603 255.53 + vertex -690.531 318.124 262.754 + endloop + endfacet + facet normal -0.987577 -0.0553495 -0.147064 + outer loop + vertex -691.277 334.504 262.567 + vertex -691.166 351.293 255.499 + vertex -690.235 334.603 255.53 + endloop + endfacet + facet normal -0.993322 -0.0555843 -0.101105 + outer loop + vertex -691.166 351.293 255.499 + vertex -690.457 351.707 248.314 + vertex -690.235 334.603 255.53 + endloop + endfacet + facet normal -0.991871 -0.0602067 -0.112106 + outer loop + vertex -690.235 334.603 255.53 + vertex -690.457 351.707 248.314 + vertex -689.447 335.078 248.305 + endloop + endfacet + facet normal -0.995307 -0.0604352 -0.0755699 + outer loop + vertex -690.457 351.707 248.314 + vertex -689.938 352.23 241.048 + vertex -689.447 335.078 248.305 + endloop + endfacet + facet normal -0.994204 -0.0754662 -0.076572 + outer loop + vertex -690.457 351.707 248.314 + vertex -691.216 369.001 241.115 + vertex -689.938 352.23 241.048 + endloop + endfacet + facet normal -0.99576 -0.0756822 -0.0522862 + outer loop + vertex -691.216 369.001 241.115 + vertex -690.851 369.259 233.792 + vertex -689.938 352.23 241.048 + endloop + endfacet + facet normal -0.995273 -0.0780179 -0.0578297 + outer loop + vertex -689.938 352.23 241.048 + vertex -690.851 369.259 233.792 + vertex -689.548 352.711 233.693 + endloop + endfacet + facet normal -0.996102 -0.0781848 -0.0408484 + outer loop + vertex -690.851 369.259 233.792 + vertex -690.559 369.446 226.313 + vertex -689.548 352.711 233.693 + endloop + endfacet + facet normal -0.993024 -0.110359 -0.0415312 + outer loop + vertex -690.851 369.259 233.792 + vertex -692.448 386.348 226.575 + vertex -690.559 369.446 226.313 + endloop + endfacet + facet normal -0.993442 -0.1106 -0.0290084 + outer loop + vertex -692.448 386.348 226.575 + vertex -692.225 386.314 219.067 + vertex -690.559 369.446 226.313 + endloop + endfacet + facet normal -0.993179 -0.112019 -0.0323713 + outer loop + vertex -690.559 369.446 226.313 + vertex -692.225 386.314 219.067 + vertex -690.323 369.568 218.67 + endloop + endfacet + facet normal -0.993398 -0.112249 -0.0236872 + outer loop + vertex -692.225 386.314 219.067 + vertex -692.027 386.282 210.918 + vertex -690.323 369.568 218.67 + endloop + endfacet + facet normal -0.993383 -0.108617 -0.0373257 + outer loop + vertex -692.74 386.388 234.231 + vertex -692.448 386.348 226.575 + vertex -690.851 369.259 233.792 + endloop + endfacet + facet normal -0.992708 -0.108133 -0.0532793 + outer loop + vertex -691.216 369.001 241.115 + vertex -692.74 386.388 234.231 + vertex -690.851 369.259 233.792 + endloop + endfacet + facet normal -0.993096 -0.106522 -0.0491244 + outer loop + vertex -693.089 386.426 241.196 + vertex -692.74 386.388 234.231 + vertex -691.216 369.001 241.115 + endloop + endfacet + facet normal -0.991872 -0.106294 -0.0699436 + outer loop + vertex -691.696 368.723 248.345 + vertex -693.089 386.426 241.196 + vertex -691.216 369.001 241.115 + endloop + endfacet + facet normal -0.992401 -0.104394 -0.0651352 + outer loop + vertex -693.58 386.47 248.615 + vertex -693.089 386.426 241.196 + vertex -691.696 368.723 248.345 + endloop + endfacet + facet normal -0.989936 -0.103656 -0.096346 + outer loop + vertex -692.379 368.514 255.594 + vertex -693.58 386.47 248.615 + vertex -691.696 368.723 248.345 + endloop + endfacet + facet normal -0.992988 -0.0694623 -0.0956522 + outer loop + vertex -692.379 368.514 255.594 + vertex -691.696 368.723 248.345 + vertex -691.166 351.293 255.499 + endloop + endfacet + facet normal -0.987713 -0.0688451 -0.140295 + outer loop + vertex -692.157 351.041 262.601 + vertex -692.379 368.514 255.594 + vertex -691.166 351.293 255.499 + endloop + endfacet + facet normal -0.989256 -0.0650971 -0.1309 + outer loop + vertex -693.32 368.395 262.762 + vertex -692.379 368.514 255.594 + vertex -692.157 351.041 262.601 + endloop + endfacet + facet normal -0.986461 -0.0985367 -0.131092 + outer loop + vertex -693.32 368.395 262.762 + vertex -694.252 386.515 256.158 + vertex -692.379 368.514 255.594 + endloop + endfacet + facet normal -0.988671 -0.0936304 -0.117318 + outer loop + vertex -695.086 386.556 263.152 + vertex -694.252 386.515 256.158 + vertex -693.32 368.395 262.762 + endloop + endfacet + facet normal -0.991076 -0.100376 -0.0877108 + outer loop + vertex -694.252 386.515 256.158 + vertex -693.58 386.47 248.615 + vertex -692.379 368.514 255.594 + endloop + endfacet + facet normal -0.995005 -0.0722844 -0.068844 + outer loop + vertex -691.696 368.723 248.345 + vertex -691.216 369.001 241.115 + vertex -690.457 351.707 248.314 + endloop + endfacet + facet normal -0.99218 -0.0720185 -0.101939 + outer loop + vertex -691.166 351.293 255.499 + vertex -691.696 368.723 248.345 + vertex -690.457 351.707 248.314 + endloop + endfacet + facet normal -0.988789 -0.0523084 -0.139859 + outer loop + vertex -692.157 351.041 262.601 + vertex -691.166 351.293 255.499 + vertex -691.277 334.504 262.567 + endloop + endfacet + facet normal -0.989943 -0.0529687 -0.131174 + outer loop + vertex -688.542 301.171 255.598 + vertex -688.5 318.514 248.284 + vertex -687.609 301.886 248.267 + endloop + endfacet + facet normal -0.992374 -0.0522569 -0.111638 + outer loop + vertex -690.235 334.603 255.53 + vertex -689.447 335.078 248.305 + vertex -689.366 317.982 255.583 + endloop + endfacet + facet normal -0.994494 -0.0636572 -0.0832396 + outer loop + vertex -689.447 335.078 248.305 + vertex -689.938 352.23 241.048 + vertex -688.881 335.772 241.01 + endloop + endfacet + facet normal -0.996334 -0.0638346 -0.0569573 + outer loop + vertex -689.938 352.23 241.048 + vertex -689.548 352.711 233.693 + vertex -688.881 335.772 241.01 + endloop + endfacet + facet normal -0.995941 -0.0791007 -0.0429474 + outer loop + vertex -689.548 352.711 233.693 + vertex -690.559 369.446 226.313 + vertex -689.254 353.071 226.217 + endloop + endfacet + facet normal -0.996347 -0.0791976 -0.0319425 + outer loop + vertex -690.559 369.446 226.313 + vertex -690.323 369.568 218.67 + vertex -689.254 353.071 226.217 + endloop + endfacet + facet normal -0.993112 -0.113925 -0.0273631 + outer loop + vertex -690.323 369.568 218.67 + vertex -692.027 386.282 210.918 + vertex -690.121 369.657 210.948 + endloop + endfacet + facet normal -0.993302 -0.113932 -0.0192307 + outer loop + vertex -692.027 386.282 210.918 + vertex -691.883 386.259 203.587 + vertex -690.121 369.657 210.948 + endloop + endfacet + facet normal -0.993181 -0.114686 -0.0209585 + outer loop + vertex -690.121 369.657 210.948 + vertex -691.883 386.259 203.587 + vertex -689.967 369.747 203.182 + endloop + endfacet + facet normal -0.993271 -0.114844 -0.0149235 + outer loop + vertex -691.883 386.259 203.587 + vertex -691.76 386.239 195.596 + vertex -689.967 369.747 203.182 + endloop + endfacet + facet normal -0.993156 -0.115609 -0.0166152 + outer loop + vertex -689.967 369.747 203.182 + vertex -691.76 386.239 195.596 + vertex -689.846 369.828 195.333 + endloop + endfacet + facet normal -0.993227 -0.115716 -0.0104717 + outer loop + vertex -691.76 386.239 195.596 + vertex -691.674 386.225 187.557 + vertex -689.846 369.828 195.333 + endloop + endfacet + facet normal -0.993126 -0.116436 -0.0120137 + outer loop + vertex -689.846 369.828 195.333 + vertex -691.674 386.225 187.557 + vertex -689.759 369.894 187.569 + endloop + endfacet + facet normal -0.993178 -0.116438 -0.00626492 + outer loop + vertex -691.674 386.225 187.557 + vertex -691.627 386.218 180.208 + vertex -689.759 369.894 187.569 + endloop + endfacet + facet normal -0.993118 -0.116889 -0.0072801 + outer loop + vertex -689.759 369.894 187.569 + vertex -691.627 386.218 180.208 + vertex -689.708 369.937 179.858 + endloop + endfacet + facet normal -0.993129 -0.117001 -0.00211417 + outer loop + vertex -691.627 386.218 180.208 + vertex -691.61 386.215 172.389 + vertex -689.708 369.937 179.858 + endloop + endfacet + facet normal -0.993134 -0.116965 -0.00203326 + outer loop + vertex -689.708 369.937 179.858 + vertex -691.61 386.215 172.389 + vertex -689.695 369.962 172.107 + endloop + endfacet + facet normal -0.993125 -0.117036 0.00215011 + outer loop + vertex -691.61 386.215 172.389 + vertex -691.627 386.218 164.477 + vertex -689.695 369.962 172.107 + endloop + endfacet + facet normal -0.99309 -0.117349 0.00147507 + outer loop + vertex -689.695 369.962 172.107 + vertex -691.627 386.218 164.477 + vertex -689.706 369.958 164.369 + endloop + endfacet + facet normal -0.993067 -0.117379 0.00639127 + outer loop + vertex -691.627 386.218 164.477 + vertex -691.678 386.226 156.792 + vertex -689.706 369.958 164.369 + endloop + endfacet + facet normal -0.993111 -0.116951 0.00732095 + outer loop + vertex -689.706 369.958 164.369 + vertex -691.678 386.226 156.792 + vertex -689.761 369.943 156.646 + endloop + endfacet + facet normal -0.993078 -0.116977 0.0106108 + outer loop + vertex -691.678 386.226 156.792 + vertex -691.762 386.239 149.08 + vertex -689.761 369.943 156.646 + endloop + endfacet + facet normal -0.993121 -0.116511 0.0116276 + outer loop + vertex -689.761 369.943 156.646 + vertex -691.762 386.239 149.08 + vertex -689.847 369.905 148.914 + endloop + endfacet + facet normal -0.993075 -0.116538 0.014875 + outer loop + vertex -691.762 386.239 149.08 + vertex -691.878 386.258 141.451 + vertex -689.847 369.905 148.914 + endloop + endfacet + facet normal -0.99314 -0.115739 0.0166431 + outer loop + vertex -689.847 369.905 148.914 + vertex -691.878 386.258 141.451 + vertex -689.971 369.848 141.154 + endloop + endfacet + facet normal -0.993089 -0.11578 0.0192248 + outer loop + vertex -691.878 386.258 141.451 + vertex -692.033 386.283 133.586 + vertex -689.971 369.848 141.154 + endloop + endfacet + facet normal -0.993132 -0.115179 0.0205422 + outer loop + vertex -689.971 369.848 141.154 + vertex -692.033 386.283 133.586 + vertex -690.122 369.764 133.36 + endloop + endfacet + facet normal -0.996411 -0.0800473 0.0275054 + outer loop + vertex -688.822 353.648 133.324 + vertex -690.321 369.669 125.649 + vertex -689.016 353.406 125.613 + endloop + endfacet + facet normal -0.993056 -0.115214 0.0237712 + outer loop + vertex -692.033 386.283 133.586 + vertex -692.227 386.314 125.633 + vertex -690.122 369.764 133.36 + endloop + endfacet + facet normal -0.996253 -0.0800463 0.0327388 + outer loop + vertex -690.321 369.669 125.649 + vertex -690.561 369.552 118.054 + vertex -689.016 353.406 125.613 + endloop + endfacet + facet normal -0.997383 -0.0670223 0.0271211 + outer loop + vertex -688.822 353.648 133.324 + vertex -689.016 353.406 125.613 + vertex -687.757 337.785 133.304 + endloop + endfacet + facet normal -0.997492 -0.0670241 0.0227626 + outer loop + vertex -687.601 338.093 141.058 + vertex -688.822 353.648 133.324 + vertex -687.757 337.785 133.304 + endloop + endfacet + facet normal -0.997586 -0.0671436 0.0177275 + outer loop + vertex -687.479 338.329 148.817 + vertex -688.66 353.836 141.081 + vertex -687.601 338.093 141.058 + endloop + endfacet + facet normal -0.997631 -0.0676782 0.0122986 + outer loop + vertex -687.395 338.497 156.562 + vertex -688.54 353.986 148.845 + vertex -687.479 338.329 148.817 + endloop + endfacet + facet normal -0.997677 -0.0677156 0.00748514 + outer loop + vertex -687.343 338.595 164.294 + vertex -688.452 354.086 156.593 + vertex -687.395 338.497 156.562 + endloop + endfacet + facet normal -0.997672 -0.0681509 0.00252392 + outer loop + vertex -687.326 338.624 172.017 + vertex -688.405 354.147 164.324 + vertex -687.343 338.595 164.294 + endloop + endfacet + facet normal -0.997683 -0.067986 -0.00242193 + outer loop + vertex -687.342 338.582 179.74 + vertex -688.384 354.156 172.046 + vertex -687.326 338.624 172.017 + endloop + endfacet + facet normal -0.997645 -0.0681664 -0.00763477 + outer loop + vertex -687.393 338.47 187.478 + vertex -688.404 354.125 179.77 + vertex -687.342 338.582 179.74 + endloop + endfacet + facet normal -0.997621 -0.0677738 -0.0125836 + outer loop + vertex -687.478 338.285 195.243 + vertex -688.451 354.043 187.506 + vertex -687.393 338.47 187.478 + endloop + endfacet + facet normal -0.997564 -0.0675473 -0.0174477 + outer loop + vertex -687.598 338.032 203.037 + vertex -688.537 353.914 195.273 + vertex -687.478 338.285 195.243 + endloop + endfacet + facet normal -0.997475 -0.067336 -0.0225674 + outer loop + vertex -687.753 337.728 210.829 + vertex -688.659 353.744 203.075 + vertex -687.598 338.032 203.037 + endloop + endfacet + facet normal -0.997353 -0.0671062 -0.0279874 + outer loop + vertex -687.947 337.38 218.563 + vertex -688.819 353.548 210.872 + vertex -687.753 337.728 210.829 + endloop + endfacet + facet normal -0.997191 -0.0664958 -0.0344853 + outer loop + vertex -688.183 336.971 226.18 + vertex -689.012 353.331 218.602 + vertex -687.947 337.38 218.563 + endloop + endfacet + facet normal -0.997157 -0.0608476 -0.0444371 + outer loop + vertex -688.484 336.438 233.651 + vertex -688.183 336.971 226.18 + vertex -687.494 320.24 233.627 + endloop + endfacet + facet normal -0.996178 -0.0607598 -0.062747 + outer loop + vertex -687.904 319.375 240.979 + vertex -688.484 336.438 233.651 + vertex -687.494 320.24 233.627 + endloop + endfacet + facet normal -0.994744 -0.0532701 -0.0874425 + outer loop + vertex -688.5 318.514 248.284 + vertex -687.904 319.375 240.979 + vertex -687.609 301.886 248.267 + endloop + endfacet + facet normal -0.990426 -0.0451071 -0.130469 + outer loop + vertex -688.542 301.171 255.598 + vertex -687.609 301.886 248.267 + vertex -687.767 284.336 255.541 + endloop + endfacet + facet normal -0.994116 -0.0493152 -0.0964407 + outer loop + vertex -686.826 285.296 248.289 + vertex -686.994 302.96 240.981 + vertex -686.185 286.551 241.034 + endloop + endfacet + facet normal -0.996668 -0.0493385 -0.0649583 + outer loop + vertex -686.994 302.96 240.981 + vertex -686.568 304.038 233.636 + vertex -686.185 286.551 241.034 + endloop + endfacet + facet normal -0.997155 -0.0580999 -0.0480339 + outer loop + vertex -686.568 304.038 233.636 + vertex -687.194 320.958 226.154 + vertex -686.262 304.951 226.165 + endloop + endfacet + facet normal -0.997599 -0.0587128 -0.0367354 + outer loop + vertex -686.262 304.951 226.165 + vertex -686.957 321.536 218.538 + vertex -686.025 305.695 218.553 + endloop + endfacet + facet normal -0.997818 -0.059184 -0.0292526 + outer loop + vertex -686.025 305.695 218.553 + vertex -686.766 322.018 210.806 + vertex -685.835 306.318 210.826 + endloop + endfacet + facet normal -0.99795 -0.059547 -0.0234521 + outer loop + vertex -685.835 306.318 210.826 + vertex -686.613 322.43 203.017 + vertex -685.684 306.841 203.038 + endloop + endfacet + facet normal -0.998046 -0.0597281 -0.0183764 + outer loop + vertex -685.684 306.841 203.038 + vertex -686.493 322.767 195.224 + vertex -685.565 307.26 195.245 + endloop + endfacet + facet normal -0.998114 -0.0599489 -0.0132099 + outer loop + vertex -685.565 307.26 195.245 + vertex -686.408 323.009 187.458 + vertex -685.48 307.561 187.477 + endloop + endfacet + facet normal -0.998163 -0.0600617 -0.00790689 + outer loop + vertex -685.48 307.561 187.477 + vertex -686.357 323.154 179.718 + vertex -685.43 307.741 179.735 + endloop + endfacet + facet normal -0.998177 -0.0602802 -0.00295839 + outer loop + vertex -685.43 307.741 179.735 + vertex -686.341 323.203 171.992 + vertex -685.411 307.805 172.007 + endloop + endfacet + facet normal -0.998183 -0.0601873 0.00272869 + outer loop + vertex -685.411 307.805 172.007 + vertex -686.358 323.16 164.269 + vertex -685.429 307.748 164.285 + endloop + endfacet + facet normal -0.998164 -0.0600683 0.007818 + outer loop + vertex -685.429 307.748 164.285 + vertex -686.409 323.024 156.54 + vertex -685.479 307.579 156.557 + endloop + endfacet + facet normal -0.998116 -0.0599436 0.0130646 + outer loop + vertex -685.479 307.579 156.557 + vertex -686.494 322.796 148.797 + vertex -685.563 307.293 148.817 + endloop + endfacet + facet normal -0.998052 -0.0596006 0.0184372 + outer loop + vertex -685.563 307.293 148.817 + vertex -686.613 322.473 141.041 + vertex -685.682 306.89 141.063 + endloop + endfacet + facet normal -0.997954 -0.0593581 0.0237629 + outer loop + vertex -685.682 306.89 141.063 + vertex -686.769 322.056 133.29 + vertex -685.836 306.368 133.314 + endloop + endfacet + facet normal -0.998117 -0.0531053 0.0306864 + outer loop + vertex -684.993 290.637 133.397 + vertex -686.035 305.714 125.6 + vertex -685.188 289.847 125.676 + endloop + endfacet + facet normal -0.997796 -0.0593398 0.0296869 + outer loop + vertex -686.769 322.056 133.29 + vertex -686.968 321.541 125.579 + vertex -685.836 306.368 133.314 + endloop + endfacet + facet normal -0.997533 -0.0579507 0.0396141 + outer loop + vertex -686.035 305.714 125.6 + vertex -687.222 320.917 117.947 + vertex -686.292 304.919 117.958 + endloop + endfacet + facet normal -0.997413 -0.062039 0.0363016 + outer loop + vertex -687.955 337.407 125.593 + vertex -688.204 336.954 117.968 + vertex -686.968 321.541 125.579 + endloop + endfacet + facet normal -0.99701 -0.0597446 0.0490019 + outer loop + vertex -687.222 320.917 117.947 + vertex -688.519 336.432 110.461 + vertex -687.549 320.204 110.423 + endloop + endfacet + facet normal -0.996944 -0.0651544 0.0430935 + outer loop + vertex -689.26 353.123 117.993 + vertex -689.562 352.794 110.495 + vertex -688.204 336.954 117.968 + endloop + endfacet + facet normal -0.996374 -0.0618346 0.058445 + outer loop + vertex -688.519 336.432 110.461 + vertex -689.943 352.444 103.125 + vertex -688.919 335.891 103.079 + endloop + endfacet + facet normal -0.995712 -0.0771217 0.0510821 + outer loop + vertex -690.846 369.406 110.543 + vertex -691.213 369.252 103.158 + vertex -689.562 352.794 110.495 + endloop + endfacet + facet normal -0.994797 -0.0734483 0.0706002 + outer loop + vertex -689.943 352.444 103.125 + vertex -691.687 369.101 95.8811 + vertex -690.435 352.123 95.8604 + endloop + endfacet + facet normal -0.991775 -0.109725 0.065892 + outer loop + vertex -693.11 386.429 103.207 + vertex -693.6 386.471 95.907 + vertex -691.213 369.252 103.158 + endloop + endfacet + facet normal -0.993117 -0.0733496 0.0913176 + outer loop + vertex -691.687 369.101 95.8811 + vertex -692.341 368.981 88.6745 + vertex -690.435 352.123 95.8604 + endloop + endfacet + facet normal -0.99562 -0.0618202 0.0701411 + outer loop + vertex -689.943 352.444 103.125 + vertex -690.435 352.123 95.8604 + vertex -688.919 335.891 103.079 + endloop + endfacet + facet normal -0.99651 -0.0597363 0.0582987 + outer loop + vertex -688.519 336.432 110.461 + vertex -688.919 335.891 103.079 + vertex -687.549 320.204 110.423 + endloop + endfacet + facet normal -0.997126 -0.0579205 0.0488342 + outer loop + vertex -687.222 320.917 117.947 + vertex -687.549 320.204 110.423 + vertex -686.292 304.919 117.958 + endloop + endfacet + facet normal -0.997826 -0.0530492 0.0391143 + outer loop + vertex -686.035 305.714 125.6 + vertex -686.292 304.919 117.958 + vertex -685.188 289.847 125.676 + endloop + endfacet + facet normal -0.998616 -0.0434086 0.0297067 + outer loop + vertex -684.993 290.637 133.397 + vertex -685.188 289.847 125.676 + vertex -684.298 274.713 133.481 + endloop + endfacet + facet normal -0.998784 -0.0434499 0.0233064 + outer loop + vertex -684.149 275.434 141.231 + vertex -684.993 290.637 133.397 + vertex -684.298 274.713 133.481 + endloop + endfacet + facet normal -0.998891 -0.0433687 0.0183423 + outer loop + vertex -684.03 275.988 148.982 + vertex -684.838 291.265 141.146 + vertex -684.149 275.434 141.231 + endloop + endfacet + facet normal -0.99896 -0.0436841 0.0130543 + outer loop + vertex -683.946 276.38 156.723 + vertex -684.72 291.743 148.898 + vertex -684.03 275.988 148.982 + endloop + endfacet + facet normal -0.999001 -0.0440268 0.00769422 + outer loop + vertex -683.897 276.612 164.45 + vertex -684.639 292.079 156.638 + vertex -683.946 276.38 156.723 + endloop + endfacet + facet normal -0.999028 -0.0440187 0.00227753 + outer loop + vertex -683.883 276.682 172.171 + vertex -684.588 292.281 164.364 + vertex -683.897 276.612 164.45 + endloop + endfacet + facet normal -0.999028 -0.0439946 -0.00288682 + outer loop + vertex -683.901 276.596 179.898 + vertex -684.572 292.345 172.086 + vertex -683.883 276.682 172.171 + endloop + endfacet + facet normal -0.999001 -0.0439251 -0.00817466 + outer loop + vertex -683.953 276.348 187.64 + vertex -684.59 292.271 179.813 + vertex -683.901 276.596 179.898 + endloop + endfacet + facet normal -0.998949 -0.0438074 -0.0134613 + outer loop + vertex -684.04 275.931 195.404 + vertex -684.641 292.056 187.555 + vertex -683.953 276.348 187.64 + endloop + endfacet + facet normal -0.998882 -0.0434674 -0.0185749 + outer loop + vertex -684.159 275.348 203.192 + vertex -684.725 291.701 195.323 + vertex -684.04 275.931 195.404 + endloop + endfacet + facet normal -0.998789 -0.043216 -0.0235264 + outer loop + vertex -684.311 274.611 210.979 + vertex -684.843 291.197 203.115 + vertex -684.159 275.348 203.192 + endloop + endfacet + facet normal -0.998629 -0.0431625 -0.0296189 + outer loop + vertex -684.502 273.727 218.701 + vertex -684.998 290.556 210.902 + vertex -684.311 274.611 210.979 + endloop + endfacet + facet normal -0.99838 -0.0426576 -0.0376645 + outer loop + vertex -684.744 272.691 226.296 + vertex -685.186 289.801 218.626 + vertex -684.502 273.727 218.701 + endloop + endfacet + facet normal -0.997828 -0.0420415 -0.0507192 + outer loop + vertex -685.071 271.464 233.746 + vertex -685.424 288.902 226.23 + vertex -684.744 272.691 226.296 + endloop + endfacet + facet normal -0.996684 -0.0410447 -0.0702627 + outer loop + vertex -685.532 270.078 241.096 + vertex -685.74 287.814 233.693 + vertex -685.071 271.464 233.746 + endloop + endfacet + facet normal -0.995013 -0.0253165 -0.0964744 + outer loop + vertex -686.203 268.735 248.369 + vertex -685.532 270.078 241.096 + vertex -685.774 251.837 248.38 + endloop + endfacet + facet normal -0.990874 -0.0123635 -0.134221 + outer loop + vertex -686.754 251.033 255.689 + vertex -685.774 251.837 248.38 + vertex -686.531 233.008 255.7 + endloop + endfacet + facet normal -0.995071 -0.0154888 -0.0979496 + outer loop + vertex -685.464 234.157 248.026 + vertex -685.072 253.254 241.019 + vertex -684.761 235.73 240.638 + endloop + endfacet + facet normal -0.99761 -0.015993 -0.0672159 + outer loop + vertex -684.761 235.73 240.638 + vertex -684.597 254.732 233.669 + vertex -684.293 237.297 233.306 + endloop + endfacet + facet normal -0.998733 -0.0166262 -0.0475074 + outer loop + vertex -684.293 237.297 233.306 + vertex -684.268 256.051 226.224 + vertex -683.962 238.711 225.866 + endloop + endfacet + facet normal -0.999248 -0.0167071 -0.035001 + outer loop + vertex -683.962 238.711 225.866 + vertex -684.019 257.224 218.637 + vertex -683.717 239.971 218.252 + endloop + endfacet + facet normal -0.999485 -0.017013 -0.0272174 + outer loop + vertex -683.717 239.971 218.252 + vertex -683.827 258.214 210.906 + vertex -683.524 241.061 210.508 + endloop + endfacet + facet normal -0.999622 -0.0171393 -0.0214901 + outer loop + vertex -683.524 241.061 210.508 + vertex -683.674 259.045 203.121 + vertex -683.373 241.965 202.729 + endloop + endfacet + facet normal -0.999719 -0.0171187 -0.0164243 + outer loop + vertex -683.373 241.965 202.729 + vertex -683.555 259.695 195.34 + vertex -683.257 242.662 194.952 + endloop + endfacet + facet normal -0.999789 -0.0170045 -0.0115549 + outer loop + vertex -683.257 242.662 194.952 + vertex -683.469 260.16 187.579 + vertex -683.175 243.162 187.182 + endloop + endfacet + facet normal -0.999834 -0.0168948 -0.00675971 + outer loop + vertex -683.175 243.162 187.182 + vertex -683.418 260.437 179.836 + vertex -683.128 243.467 179.441 + endloop + endfacet + facet normal -0.999856 -0.0168477 -0.00212214 + outer loop + vertex -683.128 243.467 179.441 + vertex -683.4 260.527 172.109 + vertex -683.113 243.559 171.721 + endloop + endfacet + facet normal -0.999854 -0.0168827 0.00248896 + outer loop + vertex -683.113 243.559 171.721 + vertex -683.417 260.439 164.385 + vertex -683.131 243.453 163.991 + endloop + endfacet + facet normal -0.99983 -0.0169932 0.00717731 + outer loop + vertex -683.131 243.453 163.991 + vertex -683.468 260.17 156.652 + vertex -683.181 243.159 156.254 + endloop + endfacet + facet normal -0.999786 -0.01677 0.0121369 + outer loop + vertex -683.181 243.159 156.254 + vertex -683.549 259.739 148.915 + vertex -683.267 242.662 148.519 + endloop + endfacet + facet normal -0.999715 -0.0166096 0.0171544 + outer loop + vertex -683.267 242.662 148.519 + vertex -683.666 259.113 141.166 + vertex -683.388 241.953 140.775 + endloop + endfacet + facet normal -0.999621 -0.0167286 0.0218502 + outer loop + vertex -683.388 241.953 140.775 + vertex -683.822 258.273 133.411 + vertex -683.542 241.021 133.019 + endloop + endfacet + facet normal -0.999567 -0.0126877 0.0265453 + outer loop + vertex -683.335 222.843 132.226 + vertex -683.736 239.871 125.295 + vertex -683.525 221.58 124.491 + endloop + endfacet + facet normal -0.999342 -0.0228036 0.028191 + outer loop + vertex -683.335 222.843 132.226 + vertex -683.525 221.58 124.491 + vertex -683.116 210.553 130.052 + endloop + endfacet + facet normal -0.999336 -0.0130144 0.0340383 + outer loop + vertex -683.736 239.871 125.295 + vertex -683.978 238.604 117.691 + vertex -683.525 221.58 124.491 + endloop + endfacet + facet normal -0.999339 -0.0130538 0.0339398 + outer loop + vertex -683.525 221.58 124.491 + vertex -683.978 238.604 117.691 + vertex -683.764 220.17 116.912 + endloop + endfacet + facet normal -0.999069 -0.0238556 0.035941 + outer loop + vertex -683.525 221.58 124.491 + vertex -683.764 220.17 116.912 + vertex -683.306 209.174 122.331 + endloop + endfacet + facet normal -0.998807 -0.0135948 0.0468985 + outer loop + vertex -683.978 238.604 117.691 + vertex -684.31 237.291 110.236 + vertex -683.764 220.17 116.912 + endloop + endfacet + facet normal -0.998735 -0.0129343 0.0485866 + outer loop + vertex -683.764 220.17 116.912 + vertex -684.31 237.291 110.236 + vertex -684.106 218.72 109.48 + endloop + endfacet + facet normal -0.998395 -0.0248539 0.0508969 + outer loop + vertex -683.764 220.17 116.912 + vertex -684.106 218.72 109.48 + vertex -683.559 207.651 114.822 + endloop + endfacet + facet normal -0.997544 -0.0137389 0.068676 + outer loop + vertex -684.31 237.291 110.236 + vertex -684.798 235.92 102.879 + vertex -684.106 218.72 109.48 + endloop + endfacet + facet normal -0.997336 -0.0125096 0.0718574 + outer loop + vertex -684.106 218.72 109.48 + vertex -684.798 235.92 102.879 + vertex -684.619 217.179 102.103 + endloop + endfacet + facet normal -0.996876 -0.0258986 0.0746218 + outer loop + vertex -684.106 218.72 109.48 + vertex -684.619 217.179 102.103 + vertex -683.935 206.076 107.385 + endloop + endfacet + facet normal -0.994506 -0.0138041 0.103764 + outer loop + vertex -684.798 235.92 102.879 + vertex -685.547 234.142 95.4644 + vertex -684.619 217.179 102.103 + endloop + endfacet + facet normal -0.994278 -0.0128997 0.106043 + outer loop + vertex -684.619 217.179 102.103 + vertex -685.547 234.142 95.4644 + vertex -685.382 215.342 94.718 + endloop + endfacet + facet normal -0.993568 -0.02798 0.109721 + outer loop + vertex -684.619 217.179 102.103 + vertex -685.382 215.342 94.718 + vertex -684.491 204.514 100.027 + endloop + endfacet + facet normal -0.989 -0.0144879 0.147207 + outer loop + vertex -685.547 234.142 95.4644 + vertex -686.639 231.552 87.8731 + vertex -685.382 215.342 94.718 + endloop + endfacet + facet normal -0.988712 -0.0136219 0.149205 + outer loop + vertex -685.382 215.342 94.718 + vertex -686.639 231.552 87.8731 + vertex -686.481 212.807 87.208 + endloop + endfacet + facet normal -0.987346 -0.0322082 0.155278 + outer loop + vertex -685.382 215.342 94.718 + vertex -686.481 212.807 87.208 + vertex -685.29 202.597 92.6608 + endloop + endfacet + facet normal -0.981404 -0.015056 0.191361 + outer loop + vertex -686.639 231.552 87.8731 + vertex -688.089 228.223 80.1741 + vertex -686.481 212.807 87.208 + endloop + endfacet + facet normal -0.979593 -0.0105999 0.200713 + outer loop + vertex -686.481 212.807 87.208 + vertex -688.089 228.223 80.1741 + vertex -687.983 209.972 79.7283 + endloop + endfacet + facet normal -0.977141 -0.035407 0.209622 + outer loop + vertex -686.481 212.807 87.208 + vertex -687.983 209.972 79.7283 + vertex -686.454 199.782 85.1315 + endloop + endfacet + facet normal -0.982068 -0.00784057 0.188366 + outer loop + vertex -686.639 231.552 87.8731 + vertex -688.177 246.431 80.4699 + vertex -688.089 228.223 80.1741 + endloop + endfacet + facet normal -0.983481 -0.0118378 0.180626 + outer loop + vertex -686.784 249.939 88.2855 + vertex -688.177 246.431 80.4699 + vertex -686.639 231.552 87.8731 + endloop + endfacet + facet normal -0.982831 -0.0186369 0.183562 + outer loop + vertex -686.784 249.939 88.2855 + vertex -688.503 265.003 80.6134 + vertex -688.177 246.431 80.4699 + endloop + endfacet + facet normal -0.983495 -0.0206539 0.17975 + outer loop + vertex -687.107 267.847 88.5789 + vertex -688.503 265.003 80.6134 + vertex -686.784 249.939 88.2855 + endloop + endfacet + facet normal -0.989586 -0.0201536 0.142525 + outer loop + vertex -685.737 252.248 95.8833 + vertex -687.107 267.847 88.5789 + vertex -686.784 249.939 88.2855 + endloop + endfacet + facet normal -0.989972 -0.0136586 0.140604 + outer loop + vertex -685.737 252.248 95.8833 + vertex -686.784 249.939 88.2855 + vertex -685.547 234.142 95.4644 + endloop + endfacet + facet normal -0.99072 -0.0243781 0.133716 + outer loop + vertex -686.147 269.531 96.0002 + vertex -687.107 267.847 88.5789 + vertex -685.737 252.248 95.8833 + endloop + endfacet + facet normal -0.994788 -0.0242399 0.0990459 + outer loop + vertex -685.04 253.705 103.239 + vertex -686.147 269.531 96.0002 + vertex -685.737 252.248 95.8833 + endloop + endfacet + facet normal -0.995129 -0.0155328 0.0973532 + outer loop + vertex -685.04 253.705 103.239 + vertex -685.737 252.248 95.8833 + vertex -684.798 235.92 102.879 + endloop + endfacet + facet normal -0.995432 -0.0278159 0.0913271 + outer loop + vertex -685.51 270.596 103.261 + vertex -686.147 269.531 96.0002 + vertex -685.04 253.705 103.239 + endloop + endfacet + facet normal -0.997398 -0.0278391 0.066495 + outer loop + vertex -684.583 254.871 110.579 + vertex -685.51 270.596 103.261 + vertex -685.04 253.705 103.239 + endloop + endfacet + facet normal -0.99776 -0.0167681 0.0647594 + outer loop + vertex -684.583 254.871 110.579 + vertex -685.04 253.705 103.239 + vertex -684.31 237.291 110.236 + endloop + endfacet + facet normal -0.997564 -0.029347 0.0632757 + outer loop + vertex -685.074 271.595 110.599 + vertex -685.51 270.596 103.261 + vertex -684.583 254.871 110.579 + endloop + endfacet + facet normal -0.994948 -0.0382599 0.0928179 + outer loop + vertex -685.51 270.596 103.261 + vertex -686.794 286.213 95.9365 + vertex -686.147 269.531 96.0002 + endloop + endfacet + facet normal -0.991413 -0.0379992 0.125124 + outer loop + vertex -686.794 286.213 95.9365 + vertex -687.66 285.15 88.7487 + vertex -686.147 269.531 96.0002 + endloop + endfacet + facet normal -0.991061 -0.0439574 0.125963 + outer loop + vertex -686.794 286.213 95.9365 + vertex -688.406 301.948 88.7473 + vertex -687.66 285.15 88.7487 + endloop + endfacet + facet normal -0.984823 -0.0436771 0.167978 + outer loop + vertex -688.406 301.948 88.7473 + vertex -689.567 300.695 81.613 + vertex -687.66 285.15 88.7487 + endloop + endfacet + facet normal -0.982896 -0.0378138 0.180236 + outer loop + vertex -687.66 285.15 88.7487 + vertex -689.567 300.695 81.613 + vertex -688.935 283.102 81.3679 + endloop + endfacet + facet normal -0.983283 -0.0332191 0.179028 + outer loop + vertex -687.66 285.15 88.7487 + vertex -688.935 283.102 81.3679 + vertex -687.107 267.847 88.5789 + endloop + endfacet + facet normal -0.971321 -0.0381566 0.234688 + outer loop + vertex -689.567 300.695 81.613 + vertex -691.236 298.422 74.3337 + vertex -688.935 283.102 81.3679 + endloop + endfacet + facet normal -0.970155 -0.0356088 0.239856 + outer loop + vertex -688.935 283.102 81.3679 + vertex -691.236 298.422 74.3337 + vertex -690.641 279.451 73.9238 + endloop + endfacet + facet normal -0.970523 -0.0331272 0.238723 + outer loop + vertex -688.935 283.102 81.3679 + vertex -690.641 279.451 73.9238 + vertex -688.503 265.003 80.6134 + endloop + endfacet + facet normal -0.979232 -0.0545349 0.195273 + outer loop + vertex -688.503 265.003 80.6134 + vertex -690.641 279.451 73.9238 + vertex -689.666 267.726 75.5412 + endloop + endfacet + facet normal -0.97718 -0.0243461 0.211011 + outer loop + vertex -689.666 267.726 75.5412 + vertex -689.392 258.834 75.784 + vertex -688.503 265.003 80.6134 + endloop + endfacet + facet normal -0.978766 -0.0187245 0.204122 + outer loop + vertex -688.177 246.431 80.4699 + vertex -688.503 265.003 80.6134 + vertex -689.392 258.834 75.784 + endloop + endfacet + facet normal -0.975974 -0.0134062 0.217475 + outer loop + vertex -689.477 249.89 74.8519 + vertex -688.177 246.431 80.4699 + vertex -689.392 258.834 75.784 + endloop + endfacet + facet normal -0.975454 -0.0090826 0.220017 + outer loop + vertex -689.477 249.89 74.8519 + vertex -689.258 240.43 75.432 + vertex -688.177 246.431 80.4699 + endloop + endfacet + facet normal -0.975658 -0.00830936 0.21914 + outer loop + vertex -688.089 228.223 80.1741 + vertex -688.177 246.431 80.4699 + vertex -689.258 240.43 75.432 + endloop + endfacet + facet normal -0.972602 -0.00284145 0.232461 + outer loop + vertex -689.408 232.075 74.7001 + vertex -688.089 228.223 80.1741 + vertex -689.258 240.43 75.432 + endloop + endfacet + facet normal -0.972586 -0.00274168 0.232527 + outer loop + vertex -689.408 232.075 74.7001 + vertex -689.23 222.856 75.3371 + vertex -688.089 228.223 80.1741 + endloop + endfacet + facet normal -0.970269 -0.0115481 0.241752 + outer loop + vertex -687.983 209.972 79.7283 + vertex -688.089 228.223 80.1741 + vertex -689.23 222.856 75.3371 + endloop + endfacet + facet normal -0.963077 -0.00148962 0.269221 + outer loop + vertex -689.432 214.693 74.569 + vertex -687.983 209.972 79.7283 + vertex -689.23 222.856 75.3371 + endloop + endfacet + facet normal -0.965253 -0.0110524 0.261083 + outer loop + vertex -689.432 214.693 74.569 + vertex -689.234 205.778 74.9234 + vertex -687.983 209.972 79.7283 + endloop + endfacet + facet normal -0.959655 -0.0334532 0.279182 + outer loop + vertex -689.234 205.778 74.9234 + vertex -688 197.108 78.1278 + vertex -687.983 209.972 79.7283 + endloop + endfacet + facet normal -0.971383 -0.037593 0.234526 + outer loop + vertex -689.567 300.695 81.613 + vertex -691.879 315.926 74.4796 + vertex -691.236 298.422 74.3337 + endloop + endfacet + facet normal -0.974456 -0.044837 0.220055 + outer loop + vertex -690.341 317.631 81.6353 + vertex -691.879 315.926 74.4796 + vertex -689.567 300.695 81.613 + endloop + endfacet + facet normal -0.974688 -0.0423734 0.219518 + outer loop + vertex -690.341 317.631 81.6353 + vertex -692.638 333.103 74.4215 + vertex -691.879 315.926 74.4796 + endloop + endfacet + facet normal -0.976901 -0.0479604 0.20824 + outer loop + vertex -691.178 334.452 81.5835 + vertex -692.638 333.103 74.4215 + vertex -690.341 317.631 81.6353 + endloop + endfacet + facet normal -0.984709 -0.0452374 0.168233 + outer loop + vertex -688.406 301.948 88.7473 + vertex -690.341 317.631 81.6353 + vertex -689.567 300.695 81.613 + endloop + endfacet + facet normal -0.986363 -0.0507309 0.156569 + outer loop + vertex -689.263 318.479 88.7046 + vertex -690.341 317.631 81.6353 + vertex -688.406 301.948 88.7473 + endloop + endfacet + facet normal -0.992138 -0.0490055 0.115156 + outer loop + vertex -687.615 302.602 95.8377 + vertex -688.406 301.948 88.7473 + vertex -686.794 286.213 95.9365 + endloop + endfacet + facet normal -0.99542 -0.0414243 0.0861536 + outer loop + vertex -686.203 286.985 103.137 + vertex -686.794 286.213 95.9365 + vertex -685.51 270.596 103.261 + endloop + endfacet + facet normal -0.990212 -0.0330148 0.13561 + outer loop + vertex -686.147 269.531 96.0002 + vertex -687.66 285.15 88.7487 + vertex -687.107 267.847 88.5789 + endloop + endfacet + facet normal -0.982561 -0.031105 0.183318 + outer loop + vertex -687.107 267.847 88.5789 + vertex -688.935 283.102 81.3679 + vertex -688.503 265.003 80.6134 + endloop + endfacet + facet normal -0.98921 -0.0111084 0.146084 + outer loop + vertex -685.547 234.142 95.4644 + vertex -686.784 249.939 88.2855 + vertex -686.639 231.552 87.8731 + endloop + endfacet + facet normal -0.994542 -0.0128491 0.103538 + outer loop + vertex -684.798 235.92 102.879 + vertex -685.737 252.248 95.8833 + vertex -685.547 234.142 95.4644 + endloop + endfacet + facet normal -0.99751 -0.0149891 0.0689068 + outer loop + vertex -684.31 237.291 110.236 + vertex -685.04 253.705 103.239 + vertex -684.798 235.92 102.879 + endloop + endfacet + facet normal -0.998741 -0.0164448 0.0473974 + outer loop + vertex -683.978 238.604 117.691 + vertex -684.583 254.871 110.579 + vertex -684.31 237.291 110.236 + endloop + endfacet + facet normal -0.998818 -0.0173093 0.0454266 + outer loop + vertex -684.264 256.049 118.053 + vertex -684.583 254.871 110.579 + vertex -683.978 238.604 117.691 + endloop + endfacet + facet normal -0.999481 -0.0168534 0.0274461 + outer loop + vertex -683.822 258.273 133.411 + vertex -684.017 257.232 125.686 + vertex -683.542 241.021 133.019 + endloop + endfacet + facet normal -0.999251 -0.0170937 0.0347156 + outer loop + vertex -683.736 239.871 125.295 + vertex -684.264 256.049 118.053 + vertex -683.978 238.604 117.691 + endloop + endfacet + facet normal -0.998879 -0.028981 0.0374391 + outer loop + vertex -684.494 273.789 125.757 + vertex -684.75 272.698 118.107 + vertex -684.017 257.232 125.686 + endloop + endfacet + facet normal -0.998449 -0.0293539 0.0473096 + outer loop + vertex -684.264 256.049 118.053 + vertex -685.074 271.595 110.599 + vertex -684.583 254.871 110.579 + endloop + endfacet + facet normal -0.997871 -0.0425234 0.0494436 + outer loop + vertex -685.444 288.892 118.025 + vertex -685.774 287.879 110.494 + vertex -684.75 272.698 118.107 + endloop + endfacet + facet normal -0.997021 -0.0416526 0.0649173 + outer loop + vertex -685.074 271.595 110.599 + vertex -686.203 286.985 103.137 + vertex -685.51 270.596 103.261 + endloop + endfacet + facet normal -0.996626 -0.0520576 0.0634581 + outer loop + vertex -686.622 304.036 110.421 + vertex -687.05 303.227 103.04 + vertex -685.774 287.879 110.494 + endloop + endfacet + facet normal -0.99499 -0.0493182 0.0869649 + outer loop + vertex -686.203 286.985 103.137 + vertex -687.615 302.602 95.8377 + vertex -686.794 286.213 95.9365 + endloop + endfacet + facet normal -0.995264 -0.0560625 0.0794087 + outer loop + vertex -687.968 319.509 103.034 + vertex -688.514 318.96 95.8018 + vertex -687.05 303.227 103.04 + endloop + endfacet + facet normal -0.99201 -0.0511301 0.115338 + outer loop + vertex -687.615 302.602 95.8377 + vertex -689.263 318.479 88.7046 + vertex -688.406 301.948 88.7473 + endloop + endfacet + facet normal -0.993091 -0.0560731 0.103079 + outer loop + vertex -689.441 335.435 95.8258 + vertex -690.162 335.055 88.6814 + vertex -688.514 318.96 95.8018 + endloop + endfacet + facet normal -0.986508 -0.0485981 0.156336 + outer loop + vertex -689.263 318.479 88.7046 + vertex -691.178 334.452 81.5835 + vertex -690.341 317.631 81.6353 + endloop + endfacet + facet normal -0.988799 -0.0558396 0.138415 + outer loop + vertex -691.111 351.851 88.6719 + vertex -692.091 351.485 81.5268 + vertex -690.162 335.055 88.6814 + endloop + endfacet + facet normal -0.977055 -0.0461405 0.207929 + outer loop + vertex -691.178 334.452 81.5835 + vertex -693.475 350.623 74.3807 + vertex -692.638 333.103 74.4215 + endloop + endfacet + facet normal -0.981311 -0.0661319 0.180707 + outer loop + vertex -693.26 368.84 81.5269 + vertex -694.541 368.5 74.4462 + vertex -692.091 351.485 81.5268 + endloop + endfacet + facet normal -0.966515 -0.0768346 0.244837 + outer loop + vertex -694.541 368.5 74.4462 + vertex -697.665 386.627 67.804 + vertex -696.205 367.695 67.6274 + endloop + endfacet + facet normal -0.941653 -0.0422459 0.333925 + outer loop + vertex -691.77 264.067 68.5704 + vertex -690.725 267.311 71.9277 + vertex -693.079 277.289 66.5515 + endloop + endfacet + facet normal -0.962867 -0.0189323 0.26931 + outer loop + vertex -689.392 258.834 75.784 + vertex -690.515 256.914 71.6342 + vertex -689.477 249.89 74.8519 + endloop + endfacet + facet normal -0.940002 -0.011024 0.340991 + outer loop + vertex -690.463 247.665 71.4058 + vertex -691.75 255.377 68.1071 + vertex -691.718 246.35 67.9056 + endloop + endfacet + facet normal -0.960924 -0.00692937 0.276725 + outer loop + vertex -689.258 240.43 75.432 + vertex -690.422 238.844 71.3488 + vertex -689.408 232.075 74.7001 + endloop + endfacet + facet normal -0.957447 -0.0302421 0.287019 + outer loop + vertex -689.096 195.545 74.3064 + vertex -688 197.108 78.1278 + vertex -689.234 205.778 74.9234 + endloop + endfacet + facet normal -0.967568 -0.029916 0.250835 + outer loop + vertex -687.069 196.732 81.675 + vertex -687.983 209.972 79.7283 + vertex -688 197.108 78.1278 + endloop + endfacet + facet normal -0.977734 -0.0371305 0.206539 + outer loop + vertex -687.069 196.732 81.675 + vertex -686.454 199.782 85.1315 + vertex -687.983 209.972 79.7283 + endloop + endfacet + facet normal -0.982992 -0.0308613 0.181035 + outer loop + vertex -685.711 199.535 89.1234 + vertex -686.481 212.807 87.208 + vertex -686.454 199.782 85.1315 + endloop + endfacet + facet normal -0.988235 -0.0358341 0.148683 + outer loop + vertex -685.711 199.535 89.1234 + vertex -685.29 202.597 92.6608 + vertex -686.481 212.807 87.208 + endloop + endfacet + facet normal -0.991374 -0.027846 0.128072 + outer loop + vertex -684.766 201.963 96.5815 + vertex -685.382 215.342 94.718 + vertex -685.29 202.597 92.6608 + endloop + endfacet + facet normal -0.994223 -0.0315253 0.1026 + outer loop + vertex -684.766 201.963 96.5815 + vertex -684.491 204.514 100.027 + vertex -685.382 215.342 94.718 + endloop + endfacet + facet normal -0.995612 -0.0248046 0.0902263 + outer loop + vertex -684.117 203.569 103.902 + vertex -684.619 217.179 102.103 + vertex -684.491 204.514 100.027 + endloop + endfacet + facet normal -0.997054 -0.0273097 0.0716786 + outer loop + vertex -684.117 203.569 103.902 + vertex -683.935 206.076 107.385 + vertex -684.619 217.179 102.103 + endloop + endfacet + facet normal -0.997728 -0.023978 0.0629628 + outer loop + vertex -683.664 205.149 111.317 + vertex -684.106 218.72 109.48 + vertex -683.935 206.076 107.385 + endloop + endfacet + facet normal -0.998479 -0.025939 0.0486571 + outer loop + vertex -683.664 205.149 111.317 + vertex -683.559 207.651 114.822 + vertex -684.106 218.72 109.48 + endloop + endfacet + facet normal -0.998811 -0.0234952 0.042719 + outer loop + vertex -683.367 206.721 118.778 + vertex -683.764 220.17 116.912 + vertex -683.559 207.651 114.822 + endloop + endfacet + facet normal -0.999108 -0.0246744 0.0342828 + outer loop + vertex -683.367 206.721 118.778 + vertex -683.306 209.174 122.331 + vertex -683.764 220.17 116.912 + endloop + endfacet + facet normal -0.999195 -0.0232897 0.0326763 + outer loop + vertex -683.151 208.191 126.385 + vertex -683.525 221.58 124.491 + vertex -683.306 209.174 122.331 + endloop + endfacet + facet normal -0.999388 -0.0243677 0.0250934 + outer loop + vertex -683.151 208.191 126.385 + vertex -683.116 210.553 130.052 + vertex -683.525 221.58 124.491 + endloop + endfacet + facet normal -0.999377 -0.0226129 0.0271091 + outer loop + vertex -682.979 209.471 134.208 + vertex -683.335 222.843 132.226 + vertex -683.116 210.553 130.052 + endloop + endfacet + facet normal -0.999504 -0.0235289 0.0209518 + outer loop + vertex -682.979 209.471 134.208 + vertex -682.955 211.711 137.882 + vertex -683.335 222.843 132.226 + endloop + endfacet + facet normal -0.999531 -0.0221449 0.0211394 + outer loop + vertex -682.84 210.495 142.01 + vertex -683.179 223.874 140 + vertex -682.955 211.711 137.882 + endloop + endfacet + facet normal -0.999589 -0.0226909 0.0175141 + outer loop + vertex -682.84 210.495 142.01 + vertex -682.825 212.596 145.632 + vertex -683.179 223.874 140 + endloop + endfacet + facet normal -0.999595 -0.022181 0.0178083 + outer loop + vertex -682.722 211.243 149.716 + vertex -683.055 224.66 147.735 + vertex -682.825 212.596 145.632 + endloop + endfacet + facet normal -0.999665 -0.0230808 0.0117261 + outer loop + vertex -682.722 211.243 149.716 + vertex -682.726 213.239 153.32 + vertex -683.055 224.66 147.735 + endloop + endfacet + facet normal -0.999663 -0.0223151 0.0132679 + outer loop + vertex -682.639 211.77 157.395 + vertex -682.965 225.22 155.446 + vertex -682.726 213.239 153.32 + endloop + endfacet + facet normal -0.999707 -0.0232697 0.00668859 + outer loop + vertex -682.639 211.77 157.395 + vertex -682.659 213.659 161.028 + vertex -682.965 225.22 155.446 + endloop + endfacet + facet normal -0.999718 -0.0224929 0.00761258 + outer loop + vertex -682.592 212.079 165.152 + vertex -682.91 225.573 163.19 + vertex -682.659 213.659 161.028 + endloop + endfacet + facet normal -0.999723 -0.0235504 0.000341492 + outer loop + vertex -682.592 212.079 165.152 + vertex -682.632 213.868 168.828 + vertex -682.91 225.573 163.19 + endloop + endfacet + facet normal -0.999748 -0.0223596 0.00213508 + outer loop + vertex -682.586 212.179 172.97 + vertex -682.893 225.719 170.955 + vertex -682.632 213.868 168.828 + endloop + endfacet + facet normal -0.999731 -0.0230514 -0.0025182 + outer loop + vertex -682.586 212.179 172.97 + vertex -682.634 213.854 176.584 + vertex -682.893 225.719 170.955 + endloop + endfacet + facet normal -0.999749 -0.0223111 -0.00189763 + outer loop + vertex -682.601 212.035 180.643 + vertex -682.9 225.629 178.661 + vertex -682.634 213.854 176.584 + endloop + endfacet + facet normal -0.999708 -0.0230814 -0.00718715 + outer loop + vertex -682.601 212.035 180.643 + vertex -682.663 213.602 184.227 + vertex -682.9 225.629 178.661 + endloop + endfacet + facet normal -0.999732 -0.0224623 -0.00555849 + outer loop + vertex -682.642 211.653 188.314 + vertex -682.938 225.327 186.375 + vertex -682.663 213.602 184.227 + endloop + endfacet + facet normal -0.999666 -0.0232683 -0.0112534 + outer loop + vertex -682.642 211.653 188.314 + vertex -682.717 213.11 191.998 + vertex -682.938 225.327 186.375 + endloop + endfacet + facet normal -0.999676 -0.0230097 -0.0108625 + outer loop + vertex -682.714 211.033 196.174 + vertex -683.01 224.797 194.17 + vertex -682.717 213.11 191.998 + endloop + endfacet + facet normal -0.999552 -0.0240259 -0.0178638 + outer loop + vertex -682.714 211.033 196.174 + vertex -682.813 212.392 199.851 + vertex -683.01 224.797 194.17 + endloop + endfacet + facet normal -0.999585 -0.023246 -0.0170096 + outer loop + vertex -682.832 210.207 203.969 + vertex -683.12 224.062 201.961 + vertex -682.813 212.392 199.851 + endloop + endfacet + facet normal -0.999415 -0.0242722 -0.0241132 + outer loop + vertex -682.832 210.207 203.969 + vertex -682.95 211.48 207.591 + vertex -683.12 224.062 201.961 + endloop + endfacet + facet normal -0.999475 -0.022991 -0.0228187 + outer loop + vertex -682.991 209.169 211.702 + vertex -683.267 223.113 209.724 + vertex -682.95 211.48 207.591 + endloop + endfacet + facet normal -0.999296 -0.0238561 -0.0289404 + outer loop + vertex -682.991 209.169 211.702 + vertex -683.125 210.326 215.364 + vertex -683.267 223.113 209.724 + endloop + endfacet + facet normal -0.999373 -0.023324 -0.0266324 + outer loop + vertex -683.178 207.879 219.493 + vertex -683.453 221.94 217.49 + vertex -683.125 210.326 215.364 + endloop + endfacet + facet normal -0.998986 -0.0248694 -0.0375322 + outer loop + vertex -683.178 207.879 219.493 + vertex -683.341 208.95 223.119 + vertex -683.453 221.94 217.49 + endloop + endfacet + facet normal -0.999052 -0.0235362 -0.0366289 + outer loop + vertex -683.43 206.404 227.179 + vertex -683.69 220.591 225.162 + vertex -683.341 208.95 223.119 + endloop + endfacet + facet normal -0.998536 -0.0251289 -0.0478964 + outer loop + vertex -683.43 206.404 227.179 + vertex -683.623 207.425 230.677 + vertex -683.69 220.591 225.162 + endloop + endfacet + facet normal -0.998285 -0.0240927 -0.0533532 + outer loop + vertex -683.769 204.825 234.579 + vertex -684.008 219.097 232.618 + vertex -683.623 207.425 230.677 + endloop + endfacet + facet normal -0.99742 -0.025945 -0.0669382 + outer loop + vertex -683.769 204.825 234.579 + vertex -684.021 205.797 237.958 + vertex -684.008 219.097 232.618 + endloop + endfacet + facet normal -0.996893 -0.0245677 -0.0748329 + outer loop + vertex -684.243 203.095 241.805 + vertex -684.455 217.459 239.917 + vertex -684.021 205.797 237.958 + endloop + endfacet + facet normal -0.995286 -0.0269515 -0.0931587 + outer loop + vertex -684.243 203.095 241.805 + vertex -684.588 203.963 245.244 + vertex -684.455 217.459 239.917 + endloop + endfacet + facet normal -0.994001 -0.0257443 -0.106301 + outer loop + vertex -684.935 201.248 249.146 + vertex -685.106 215.713 247.234 + vertex -684.588 203.963 245.244 + endloop + endfacet + facet normal -0.990574 -0.0293385 -0.133798 + outer loop + vertex -684.935 201.248 249.146 + vertex -685.422 202.234 252.532 + vertex -685.106 215.713 247.234 + endloop + endfacet + facet normal -0.988508 -0.0285277 -0.148451 + outer loop + vertex -685.91 199.29 256.345 + vertex -686.099 214.004 254.781 + vertex -685.422 202.234 252.532 + endloop + endfacet + facet normal -0.982202 -0.0323339 -0.185025 + outer loop + vertex -685.91 199.29 256.345 + vertex -686.616 200.038 259.962 + vertex -686.099 214.004 254.781 + endloop + endfacet + facet normal -0.976255 -0.032248 -0.214212 + outer loop + vertex -687.346 197.019 263.745 + vertex -687.813 212.319 263.573 + vertex -686.616 200.038 259.962 + endloop + endfacet + facet normal -0.962293 -0.0324513 -0.270073 + outer loop + vertex -687.346 197.019 263.745 + vertex -688.246 196.722 266.989 + vertex -687.813 212.319 263.573 + endloop + endfacet + facet normal -0.952558 -0.0396629 -0.30176 + outer loop + vertex -688.246 196.722 266.989 + vertex -689.229 202.39 269.345 + vertex -687.813 212.319 263.573 + endloop + endfacet + facet normal -0.9641 -0.0166574 -0.265018 + outer loop + vertex -689.416 210.611 269.511 + vertex -687.813 212.319 263.573 + vertex -689.229 202.39 269.345 + endloop + endfacet + facet normal -0.965679 0.00326369 -0.259717 + outer loop + vertex -689.416 210.611 269.511 + vertex -689.157 220.01 268.667 + vertex -687.813 212.319 263.573 + endloop + endfacet + facet normal -0.969662 -0.007621 -0.244332 + outer loop + vertex -687.949 233.674 263.444 + vertex -687.813 212.319 263.573 + vertex -689.157 220.01 268.667 + endloop + endfacet + facet normal -0.97604 0.0031726 -0.217569 + outer loop + vertex -689.267 228.588 269.281 + vertex -687.949 233.674 263.444 + vertex -689.157 220.01 268.667 + endloop + endfacet + facet normal -0.975153 -0.0015996 -0.221527 + outer loop + vertex -689.267 228.588 269.281 + vertex -689.045 238.854 268.23 + vertex -687.949 233.674 263.444 + endloop + endfacet + facet normal -0.97737 -0.0115916 -0.21122 + outer loop + vertex -687.93 251.477 262.38 + vertex -687.949 233.674 263.444 + vertex -689.045 238.854 268.23 + endloop + endfacet + facet normal -0.974824 -0.0169647 -0.222328 + outer loop + vertex -689.302 251.574 268.39 + vertex -687.93 251.477 262.38 + vertex -689.045 238.854 268.23 + endloop + endfacet + facet normal -0.974637 -0.0273367 -0.222117 + outer loop + vertex -689.302 251.574 268.39 + vertex -688.422 267.165 262.607 + vertex -687.93 251.477 262.38 + endloop + endfacet + facet normal -0.970014 -0.0344513 -0.240595 + outer loop + vertex -690.358 265.296 270.681 + vertex -688.422 267.165 262.607 + vertex -689.302 251.574 268.39 + endloop + endfacet + facet normal -0.969904 -0.0356998 -0.240857 + outer loop + vertex -690.358 265.296 270.681 + vertex -689.134 283.87 262.998 + vertex -688.422 267.165 262.607 + endloop + endfacet + facet normal -0.973332 -0.0299241 -0.22744 + outer loop + vertex -690.927 284.793 270.551 + vertex -689.134 283.87 262.998 + vertex -690.358 265.296 270.681 + endloop + endfacet + facet normal -0.97327 -0.0392297 -0.226288 + outer loop + vertex -690.927 284.793 270.551 + vertex -689.833 301.263 262.989 + vertex -689.134 283.87 262.998 + endloop + endfacet + facet normal -0.976211 -0.0334926 -0.214219 + outer loop + vertex -691.479 302.384 270.316 + vertex -689.833 301.263 262.989 + vertex -690.927 284.793 270.551 + endloop + endfacet + facet normal -0.976155 -0.0434102 -0.21269 + outer loop + vertex -691.479 302.384 270.316 + vertex -690.531 318.124 262.754 + vertex -689.833 301.263 262.989 + endloop + endfacet + facet normal -0.979175 -0.0369532 -0.199629 + outer loop + vertex -691.896 319.151 269.255 + vertex -690.531 318.124 262.754 + vertex -691.479 302.384 270.316 + endloop + endfacet + facet normal -0.979073 -0.0468408 -0.198045 + outer loop + vertex -691.896 319.151 269.255 + vertex -691.277 334.504 262.567 + vertex -690.531 318.124 262.754 + endloop + endfacet + facet normal -0.979156 -0.0466753 -0.197673 + outer loop + vertex -692.659 334.358 269.445 + vertex -691.277 334.504 262.567 + vertex -691.896 319.151 269.255 + endloop + endfacet + facet normal -0.978895 -0.0516611 -0.197726 + outer loop + vertex -692.659 334.358 269.445 + vertex -692.157 351.041 262.601 + vertex -691.277 334.504 262.567 + endloop + endfacet + facet normal -0.98032 -0.048961 -0.191249 + outer loop + vertex -693.524 350.836 269.663 + vertex -692.157 351.041 262.601 + vertex -692.659 334.358 269.445 + endloop + endfacet + facet normal -0.979411 -0.063877 -0.191506 + outer loop + vertex -693.524 350.836 269.663 + vertex -693.32 368.395 262.762 + vertex -692.157 351.041 262.601 + endloop + endfacet + facet normal -0.982147 -0.058807 -0.178688 + outer loop + vertex -694.587 368.528 269.679 + vertex -693.32 368.395 262.762 + vertex -693.524 350.836 269.663 + endloop + endfacet + facet normal -0.979836 -0.0914739 -0.177637 + outer loop + vertex -694.587 368.528 269.679 + vertex -695.086 386.556 263.152 + vertex -693.32 368.395 262.762 + endloop + endfacet + facet normal -0.984337 -0.0835002 -0.155269 + outer loop + vertex -696.156 386.593 269.914 + vertex -695.086 386.556 263.152 + vertex -694.587 368.528 269.679 + endloop + endfacet + facet normal -0.951742 -0.0383879 -0.304488 + outer loop + vertex -689.15 193.321 270.242 + vertex -689.229 202.39 269.345 + vertex -688.246 196.722 266.989 + endloop + endfacet + facet normal -0.940217 -0.0416043 -0.338026 + outer loop + vertex -690.158 194.295 272.926 + vertex -689.229 202.39 269.345 + vertex -689.15 193.321 270.242 + endloop + endfacet + facet normal -0.948165 -0.0310617 -0.316258 + outer loop + vertex -690.451 203.43 272.907 + vertex -689.229 202.39 269.345 + vertex -690.158 194.295 272.926 + endloop + endfacet + facet normal -0.947112 -0.0151468 -0.320544 + outer loop + vertex -690.451 203.43 272.907 + vertex -689.416 210.611 269.511 + vertex -689.229 202.39 269.345 + endloop + endfacet + facet normal -0.953069 -0.00584846 -0.302696 + outer loop + vertex -690.483 212.124 272.841 + vertex -689.416 210.611 269.511 + vertex -690.451 203.43 272.907 + endloop + endfacet + facet normal -0.952466 -0.00113722 -0.304642 + outer loop + vertex -690.483 212.124 272.841 + vertex -689.157 220.01 268.667 + vertex -689.416 210.611 269.511 + endloop + endfacet + facet normal -0.958022 0.00937884 -0.286541 + outer loop + vertex -690.386 220.623 272.795 + vertex -689.157 220.01 268.667 + vertex -690.483 212.124 272.841 + endloop + endfacet + facet normal -0.958074 0.0083357 -0.286401 + outer loop + vertex -690.386 220.623 272.795 + vertex -689.267 228.588 269.281 + vertex -689.157 220.01 268.667 + endloop + endfacet + facet normal -0.957341 0.00714301 -0.288872 + outer loop + vertex -690.284 229.414 272.675 + vertex -689.267 228.588 269.281 + vertex -690.386 220.623 272.795 + endloop + endfacet + facet normal -0.958379 -0.00850046 -0.285374 + outer loop + vertex -690.284 229.414 272.675 + vertex -689.045 238.854 268.23 + vertex -689.267 228.588 269.281 + endloop + endfacet + facet normal -0.960839 -0.00427007 -0.277075 + outer loop + vertex -690.312 239.1 272.623 + vertex -689.045 238.854 268.23 + vertex -690.284 229.414 272.675 + endloop + endfacet + facet normal -0.960899 -0.0160039 -0.276435 + outer loop + vertex -690.312 239.1 272.623 + vertex -689.302 251.574 268.39 + vertex -689.045 238.854 268.23 + endloop + endfacet + facet normal -0.959634 -0.0175543 -0.280702 + outer loop + vertex -690.741 248.582 273.495 + vertex -689.302 251.574 268.39 + vertex -690.312 239.1 272.623 + endloop + endfacet + facet normal -0.958095 -0.0260768 -0.285263 + outer loop + vertex -689.302 251.574 268.39 + vertex -690.741 248.582 273.495 + vertex -690.358 265.296 270.681 + endloop + endfacet + facet normal -0.946338 -0.0324565 -0.321546 + outer loop + vertex -690.741 248.582 273.495 + vertex -691.738 253.326 275.952 + vertex -690.358 265.296 270.681 + endloop + endfacet + facet normal -0.954396 -0.0210706 -0.2978 + outer loop + vertex -691.957 261.539 276.071 + vertex -690.358 265.296 270.681 + vertex -691.738 253.326 275.952 + endloop + endfacet + facet normal -0.954538 -0.0204223 -0.29739 + outer loop + vertex -691.957 261.539 276.071 + vertex -691.926 271.219 275.306 + vertex -690.358 265.296 270.681 + endloop + endfacet + facet normal -0.957655 -0.0298569 -0.286364 + outer loop + vertex -690.927 284.793 270.551 + vertex -690.358 265.296 270.681 + vertex -691.926 271.219 275.306 + endloop + endfacet + facet normal -0.959734 -0.0273273 -0.279579 + outer loop + vertex -692.367 279.722 275.988 + vertex -690.927 284.793 270.551 + vertex -691.926 271.219 275.306 + endloop + endfacet + facet normal -0.960247 -0.0254741 -0.277987 + outer loop + vertex -692.367 279.722 275.988 + vertex -692.417 289.119 275.303 + vertex -690.927 284.793 270.551 + endloop + endfacet + facet normal -0.962 -0.033805 -0.27095 + outer loop + vertex -691.479 302.384 270.316 + vertex -690.927 284.793 270.551 + vertex -692.417 289.119 275.303 + endloop + endfacet + facet normal -0.964099 -0.0309438 -0.263734 + outer loop + vertex -692.842 297.227 275.902 + vertex -691.479 302.384 270.316 + vertex -692.417 289.119 275.303 + endloop + endfacet + facet normal -0.963935 -0.0315577 -0.26426 + outer loop + vertex -692.842 297.227 275.902 + vertex -692.895 307.226 274.904 + vertex -691.479 302.384 270.316 + endloop + endfacet + facet normal -0.965902 -0.0401757 -0.255772 + outer loop + vertex -691.896 319.151 269.255 + vertex -691.479 302.384 270.316 + vertex -692.895 307.226 274.904 + endloop + endfacet + facet normal -0.965896 -0.0401853 -0.255792 + outer loop + vertex -693.445 319.458 275.058 + vertex -691.896 319.151 269.255 + vertex -692.895 307.226 274.904 + endloop + endfacet + facet normal -0.965752 -0.0452812 -0.255483 + outer loop + vertex -693.445 319.458 275.058 + vertex -692.659 334.358 269.445 + vertex -691.896 319.151 269.255 + endloop + endfacet + facet normal -0.961823 -0.0505655 -0.268961 + outer loop + vertex -694.723 332.755 277.129 + vertex -692.659 334.358 269.445 + vertex -693.445 319.458 275.058 + endloop + endfacet + facet normal -0.962185 -0.04699 -0.268313 + outer loop + vertex -694.723 332.755 277.129 + vertex -693.524 350.836 269.663 + vertex -692.659 334.358 269.445 + endloop + endfacet + facet normal -0.968344 -0.0376808 -0.246759 + outer loop + vertex -695.194 351.924 276.049 + vertex -693.524 350.836 269.663 + vertex -694.723 332.755 277.129 + endloop + endfacet + facet normal -0.968225 -0.0579106 -0.243282 + outer loop + vertex -695.194 351.924 276.049 + vertex -694.587 368.528 269.679 + vertex -693.524 350.836 269.663 + endloop + endfacet + facet normal -0.970549 -0.0545151 -0.234653 + outer loop + vertex -696.171 368.896 276.146 + vertex -694.587 368.528 269.679 + vertex -695.194 351.924 276.049 + endloop + endfacet + facet normal -0.969134 -0.0811711 -0.232789 + outer loop + vertex -696.171 368.896 276.146 + vertex -696.156 386.593 269.914 + vertex -694.587 368.528 269.679 + endloop + endfacet + facet normal -0.975734 -0.0720079 -0.20678 + outer loop + vertex -697.594 386.626 276.689 + vertex -696.156 386.593 269.914 + vertex -696.171 368.896 276.146 + endloop + endfacet + facet normal -0.936895 -0.0161323 -0.349237 + outer loop + vertex -691.946 244.416 276.92 + vertex -691.738 253.326 275.952 + vertex -690.741 248.582 273.495 + endloop + endfacet + facet normal -0.939782 -0.00906519 -0.341655 + outer loop + vertex -691.946 244.416 276.92 + vertex -690.741 248.582 273.495 + vertex -691.681 237.702 276.369 + endloop + endfacet + facet normal -0.937969 -0.0105172 -0.346559 + outer loop + vertex -691.681 237.702 276.369 + vertex -690.741 248.582 273.495 + vertex -690.312 239.1 272.623 + endloop + endfacet + facet normal -0.939191 -0.00083634 -0.343393 + outer loop + vertex -691.681 237.702 276.369 + vertex -690.312 239.1 272.623 + vertex -691.611 229.059 276.199 + endloop + endfacet + facet normal -0.935724 -0.00460076 -0.352703 + outer loop + vertex -691.611 229.059 276.199 + vertex -690.312 239.1 272.623 + vertex -690.284 229.414 272.675 + endloop + endfacet + facet normal -0.936098 0.00707667 -0.351668 + outer loop + vertex -691.611 229.059 276.199 + vertex -690.284 229.414 272.675 + vertex -691.701 220.387 276.264 + endloop + endfacet + facet normal -0.935214 0.00599745 -0.354033 + outer loop + vertex -691.701 220.387 276.264 + vertex -690.284 229.414 272.675 + vertex -690.386 220.623 272.795 + endloop + endfacet + facet normal -0.935264 0.00930445 -0.353827 + outer loop + vertex -691.701 220.387 276.264 + vertex -690.386 220.623 272.795 + vertex -691.806 211.968 276.32 + endloop + endfacet + facet normal -0.934811 0.00873715 -0.355037 + outer loop + vertex -691.806 211.968 276.32 + vertex -690.386 220.623 272.795 + vertex -690.483 212.124 272.841 + endloop + endfacet + facet normal -0.934678 -0.00248695 -0.355488 + outer loop + vertex -691.806 211.968 276.32 + vertex -690.483 212.124 272.841 + vertex -691.777 203.373 276.303 + endloop + endfacet + facet normal -0.931475 -0.00622947 -0.363751 + outer loop + vertex -691.777 203.373 276.303 + vertex -690.483 212.124 272.841 + vertex -690.451 203.43 272.907 + endloop + endfacet + facet normal -0.931029 -0.0272248 -0.363928 + outer loop + vertex -691.777 203.373 276.303 + vertex -690.451 203.43 272.907 + vertex -691.475 194.181 276.218 + endloop + endfacet + facet normal -0.927689 -0.0305218 -0.372105 + outer loop + vertex -691.475 194.181 276.218 + vertex -690.451 203.43 272.907 + vertex -690.158 194.295 272.926 + endloop + endfacet + facet normal -0.92624 -0.0578496 -0.37247 + outer loop + vertex -691.475 194.181 276.218 + vertex -690.158 194.295 272.926 + vertex -690.813 184.437 276.086 + endloop + endfacet + facet normal -0.924797 -0.05903 -0.375853 + outer loop + vertex -690.813 184.437 276.086 + vertex -690.158 194.295 272.926 + vertex -689.5 184.908 272.782 + endloop + endfacet +endsolid diff --git a/noether_examples/meshes/outputs/output_24.stl b/noether_examples/meshes/outputs/output_24.stl new file mode 100644 index 00000000..d5f3521a --- /dev/null +++ b/noether_examples/meshes/outputs/output_24.stl @@ -0,0 +1,295171 @@ +solid ascii + facet normal 0.0353965 -0.54557 -0.837318 + outer loop + vertex 846.058 241.496 296.852 + vertex 846.506 242.011 296.536 + vertex 846.449 240.972 297.21 + endloop + endfacet + facet normal 0.067332 -0.586583 -0.807085 + outer loop + vertex 846.599 242.436 296.234 + vertex 847.118 241.824 296.723 + vertex 846.506 242.011 296.536 + endloop + endfacet + facet normal 0.0878141 -0.545818 -0.833289 + outer loop + vertex 847.118 241.824 296.723 + vertex 846.449 240.972 297.21 + vertex 846.506 242.011 296.536 + endloop + endfacet + facet normal -0.0025996 -0.454007 -0.890994 + outer loop + vertex 843.158 237.85 298.873 + vertex 842.599 238.697 298.443 + vertex 844.934 239.343 298.107 + endloop + endfacet + facet normal 0.0195989 -0.516132 -0.856285 + outer loop + vertex 844.934 239.343 298.107 + vertex 842.599 238.697 298.443 + vertex 844.592 239.663 297.906 + endloop + endfacet + facet normal 0.0287169 -0.508926 -0.860331 + outer loop + vertex 844.592 239.663 297.906 + vertex 845.477 240.539 297.417 + vertex 844.934 239.343 298.107 + endloop + endfacet + facet normal 0.0577708 -0.533396 -0.843891 + outer loop + vertex 846.058 241.496 296.852 + vertex 846.449 240.972 297.21 + vertex 845.477 240.539 297.417 + endloop + endfacet + facet normal 0.04686 -0.514719 -0.856078 + outer loop + vertex 846.449 240.972 297.21 + vertex 844.934 239.343 298.107 + vertex 845.477 240.539 297.417 + endloop + endfacet + facet normal 0.476274 -0.414588 -0.775423 + outer loop + vertex 695.335 145.151 297.141 + vertex 696.146 145.275 297.572 + vertex 695.168 144.035 297.634 + endloop + endfacet + facet normal 0.474334 -0.383451 -0.792447 + outer loop + vertex 697.241 145.863 297.944 + vertex 697.309 144.808 298.495 + vertex 696.146 145.275 297.572 + endloop + endfacet + facet normal 0.462842 -0.40465 -0.788693 + outer loop + vertex 697.309 144.808 298.495 + vertex 695.168 144.035 297.634 + vertex 696.146 145.275 297.572 + endloop + endfacet + facet normal 0.464125 -0.386491 -0.797002 + outer loop + vertex 697.241 145.863 297.944 + vertex 698.556 146.159 298.566 + vertex 697.309 144.808 298.495 + endloop + endfacet + facet normal 0.441131 -0.40137 -0.802687 + outer loop + vertex 694.555 145.144 296.69 + vertex 694.499 144.774 296.844 + vertex 694 143.917 296.999 + endloop + endfacet + facet normal 0.455417 -0.411431 -0.789506 + outer loop + vertex 694.789 144.761 297.018 + vertex 694.194 143.749 297.202 + vertex 694.499 144.774 296.844 + endloop + endfacet + facet normal 0.465982 -0.412261 -0.78288 + outer loop + vertex 694.194 143.749 297.202 + vertex 694 143.917 296.999 + vertex 694.499 144.774 296.844 + endloop + endfacet + facet normal 0.468267 -0.417059 -0.778966 + outer loop + vertex 694.194 143.749 297.202 + vertex 694.789 144.761 297.018 + vertex 695.168 144.035 297.634 + endloop + endfacet + facet normal 0.471029 -0.415095 -0.77835 + outer loop + vertex 695.168 144.035 297.634 + vertex 694.789 144.761 297.018 + vertex 695.335 145.151 297.141 + endloop + endfacet + facet normal 0.462432 -0.414436 -0.783836 + outer loop + vertex 694.268 144.767 296.713 + vertex 694.368 144.871 296.717 + vertex 693.897 143.916 296.944 + endloop + endfacet + facet normal 0.496988 -0.416257 -0.761402 + outer loop + vertex 694.555 145.144 296.69 + vertex 694 143.917 296.999 + vertex 694.368 144.871 296.717 + endloop + endfacet + facet normal 0.429808 -0.40399 -0.807501 + outer loop + vertex 694 143.917 296.999 + vertex 693.897 143.916 296.944 + vertex 694.368 144.871 296.717 + endloop + endfacet + facet normal -0.2002 -0.5261 -0.826522 + outer loop + vertex 842.39 244.152 295.267 + vertex 841.059 245.386 294.804 + vertex 842.66 244.445 295.015 + endloop + endfacet + facet normal -0.186016 -0.505544 -0.84251 + outer loop + vertex 842.66 244.445 295.015 + vertex 841.059 245.386 294.804 + vertex 841.357 245.715 294.541 + endloop + endfacet + facet normal -0.107268 -0.576785 -0.809822 + outer loop + vertex 843.872 243.151 295.783 + vertex 842.39 244.152 295.267 + vertex 844.129 243.495 295.505 + endloop + endfacet + facet normal -0.111964 -0.586449 -0.80221 + outer loop + vertex 844.129 243.495 295.505 + vertex 842.39 244.152 295.267 + vertex 842.66 244.445 295.015 + endloop + endfacet + facet normal -0.2017 -0.676653 -0.708137 + outer loop + vertex 844.129 243.495 295.505 + vertex 842.66 244.445 295.015 + vertex 844.198 243.649 295.337 + endloop + endfacet + facet normal -0.147008 -0.602046 -0.784812 + outer loop + vertex 844.198 243.649 295.337 + vertex 842.66 244.445 295.015 + vertex 842.748 244.64 294.849 + endloop + endfacet + facet normal -0.255504 -0.557288 -0.79003 + outer loop + vertex 842.66 244.445 295.015 + vertex 841.357 245.715 294.541 + vertex 842.748 244.64 294.849 + endloop + endfacet + facet normal -0.184408 -0.484033 -0.855398 + outer loop + vertex 842.748 244.64 294.849 + vertex 841.357 245.715 294.541 + vertex 841.448 245.983 294.37 + endloop + endfacet + facet normal -0.0303041 -0.564662 -0.824765 + outer loop + vertex 845.265 242.263 296.34 + vertex 843.872 243.151 295.783 + vertex 845.548 242.737 296.006 + endloop + endfacet + facet normal -0.0455355 -0.6087 -0.792092 + outer loop + vertex 845.548 242.737 296.006 + vertex 843.872 243.151 295.783 + vertex 844.129 243.495 295.505 + endloop + endfacet + facet normal 0.0232661 -0.538202 -0.842495 + outer loop + vertex 846.058 241.496 296.852 + vertex 845.265 242.263 296.34 + vertex 846.506 242.011 296.536 + endloop + endfacet + facet normal 0.0100162 -0.581079 -0.813786 + outer loop + vertex 846.506 242.011 296.536 + vertex 845.265 242.263 296.34 + vertex 845.548 242.737 296.006 + endloop + endfacet + facet normal 0.0115097 -0.579773 -0.814697 + outer loop + vertex 846.506 242.011 296.536 + vertex 845.548 242.737 296.006 + vertex 846.599 242.436 296.234 + endloop + endfacet + facet normal -0.0221012 -0.65326 -0.756811 + outer loop + vertex 846.599 242.436 296.234 + vertex 845.548 242.737 296.006 + vertex 845.642 242.955 295.815 + endloop + endfacet + facet normal -0.0714679 -0.639586 -0.76539 + outer loop + vertex 845.548 242.737 296.006 + vertex 844.129 243.495 295.505 + vertex 845.642 242.955 295.815 + endloop + endfacet + facet normal -0.109373 -0.707302 -0.698399 + outer loop + vertex 845.642 242.955 295.815 + vertex 844.129 243.495 295.505 + vertex 844.198 243.649 295.337 + endloop + endfacet + facet normal -0.230411 -0.82904 -0.509513 + outer loop + vertex 845.642 242.955 295.815 + vertex 844.198 243.649 295.337 + vertex 845.489 243.087 295.668 + endloop + endfacet + facet normal -0.145003 -0.727672 -0.670423 + outer loop + vertex 845.489 243.087 295.668 + vertex 844.198 243.649 295.337 + vertex 844 243.836 295.177 + endloop + endfacet + facet normal 0.0597635 -0.559006 -0.827007 + outer loop + vertex 846.599 242.436 296.234 + vertex 845.642 242.955 295.815 + vertex 846.805 242.562 296.164 + endloop + endfacet + facet normal -0.0744059 -0.776902 -0.62521 + outer loop + vertex 846.805 242.562 296.164 + vertex 845.642 242.955 295.815 + vertex 845.489 243.087 295.668 + endloop + endfacet + facet normal -0.378002 -0.613558 -0.693297 + outer loop + vertex 842.748 244.64 294.849 + vertex 841.448 245.983 294.37 + vertex 842.575 244.933 294.684 + endloop + endfacet + facet normal -0.143213 -0.421835 -0.895291 + outer loop + vertex 842.575 244.933 294.684 + vertex 841.448 245.983 294.37 + vertex 841.285 246.367 294.214 + endloop + endfacet + facet normal -0.398716 -0.802513 -0.443845 + outer loop + vertex 844.198 243.649 295.337 + vertex 842.748 244.64 294.849 + vertex 844 243.836 295.177 + endloop + endfacet + facet normal -0.132863 -0.545008 -0.827837 + outer loop + vertex 844 243.836 295.177 + vertex 842.748 244.64 294.849 + vertex 842.575 244.933 294.684 + endloop + endfacet + facet normal -0.215961 -0.410534 -0.885902 + outer loop + vertex 839.539 240.136 297.983 + vertex 838 242.435 297.293 + vertex 840.515 241.68 297.029 + endloop + endfacet + facet normal -0.228735 -0.46351 -0.85606 + outer loop + vertex 840.515 241.68 297.029 + vertex 838 242.435 297.293 + vertex 839.346 243.616 296.294 + endloop + endfacet + facet normal -0.11237 -0.431198 -0.895233 + outer loop + vertex 840.872 239.081 298.324 + vertex 839.539 240.136 297.983 + vertex 841.852 240.101 297.709 + endloop + endfacet + facet normal -0.11061 -0.470621 -0.875375 + outer loop + vertex 841.852 240.101 297.709 + vertex 839.539 240.136 297.983 + vertex 840.515 241.68 297.029 + endloop + endfacet + facet normal -0.0993588 -0.463338 -0.880594 + outer loop + vertex 841.852 240.101 297.709 + vertex 840.515 241.68 297.029 + vertex 842.768 241.436 296.903 + endloop + endfacet + facet normal -0.103184 -0.513603 -0.851801 + outer loop + vertex 842.768 241.436 296.903 + vertex 840.515 241.68 297.029 + vertex 841.412 242.814 296.237 + endloop + endfacet + facet normal -0.198812 -0.450807 -0.870199 + outer loop + vertex 840.515 241.68 297.029 + vertex 839.346 243.616 296.294 + vertex 841.412 242.814 296.237 + endloop + endfacet + facet normal -0.228674 -0.531691 -0.815483 + outer loop + vertex 841.412 242.814 296.237 + vertex 839.346 243.616 296.294 + vertex 840.445 244.042 295.708 + endloop + endfacet + facet normal -0.0281629 -0.502309 -0.864229 + outer loop + vertex 842.768 241.436 296.903 + vertex 843.943 240.258 297.55 + vertex 841.852 240.101 297.709 + endloop + endfacet + facet normal -0.0468286 -0.481951 -0.874946 + outer loop + vertex 840.872 239.081 298.324 + vertex 841.852 240.101 297.709 + vertex 842.599 238.697 298.443 + endloop + endfacet + facet normal 0.0117617 -0.504037 -0.863602 + outer loop + vertex 844.592 239.663 297.906 + vertex 842.599 238.697 298.443 + vertex 843.943 240.258 297.55 + endloop + endfacet + facet normal -0.0312721 -0.475795 -0.879 + outer loop + vertex 841.852 240.101 297.709 + vertex 843.943 240.258 297.55 + vertex 842.599 238.697 298.443 + endloop + endfacet + facet normal -0.0202806 -0.49643 -0.86784 + outer loop + vertex 843.943 240.258 297.55 + vertex 842.768 241.436 296.903 + vertex 844.739 241.43 296.861 + endloop + endfacet + facet normal -0.0200047 -0.525672 -0.850452 + outer loop + vertex 844.739 241.43 296.861 + vertex 842.768 241.436 296.903 + vertex 843.432 242.482 296.241 + endloop + endfacet + facet normal 0.0167658 -0.499948 -0.865893 + outer loop + vertex 844.592 239.663 297.906 + vertex 843.943 240.258 297.55 + vertex 845.477 240.539 297.417 + endloop + endfacet + facet normal 0.0208091 -0.517156 -0.855638 + outer loop + vertex 845.477 240.539 297.417 + vertex 843.943 240.258 297.55 + vertex 844.739 241.43 296.861 + endloop + endfacet + facet normal 0.0202875 -0.517476 -0.855457 + outer loop + vertex 845.477 240.539 297.417 + vertex 844.739 241.43 296.861 + vertex 846.058 241.496 296.852 + endloop + endfacet + facet normal 0.0214981 -0.539506 -0.841707 + outer loop + vertex 846.058 241.496 296.852 + vertex 844.739 241.43 296.861 + vertex 845.265 242.263 296.34 + endloop + endfacet + facet normal -0.0163711 -0.522396 -0.852546 + outer loop + vertex 844.739 241.43 296.861 + vertex 843.432 242.482 296.241 + vertex 845.265 242.263 296.34 + endloop + endfacet + facet normal -0.0213941 -0.554969 -0.831596 + outer loop + vertex 845.265 242.263 296.34 + vertex 843.432 242.482 296.241 + vertex 843.872 243.151 295.783 + endloop + endfacet + facet normal -0.160115 -0.494408 -0.854356 + outer loop + vertex 841.412 242.814 296.237 + vertex 840.445 244.042 295.708 + vertex 842.016 243.607 295.665 + endloop + endfacet + facet normal -0.158017 -0.486342 -0.859362 + outer loop + vertex 842.016 243.607 295.665 + vertex 840.445 244.042 295.708 + vertex 840.685 244.823 295.221 + endloop + endfacet + facet normal -0.0797151 -0.496571 -0.864328 + outer loop + vertex 842.768 241.436 296.903 + vertex 841.412 242.814 296.237 + vertex 843.432 242.482 296.241 + endloop + endfacet + facet normal -0.0866708 -0.53859 -0.838098 + outer loop + vertex 843.432 242.482 296.241 + vertex 841.412 242.814 296.237 + vertex 842.016 243.607 295.665 + endloop + endfacet + facet normal -0.0757984 -0.528657 -0.845444 + outer loop + vertex 843.432 242.482 296.241 + vertex 842.016 243.607 295.665 + vertex 843.872 243.151 295.783 + endloop + endfacet + facet normal -0.0820387 -0.550323 -0.830912 + outer loop + vertex 843.872 243.151 295.783 + vertex 842.016 243.607 295.665 + vertex 842.39 244.152 295.267 + endloop + endfacet + facet normal -0.17407 -0.499908 -0.848405 + outer loop + vertex 842.016 243.607 295.665 + vertex 840.685 244.823 295.221 + vertex 842.39 244.152 295.267 + endloop + endfacet + facet normal -0.17722 -0.507559 -0.843195 + outer loop + vertex 842.39 244.152 295.267 + vertex 840.685 244.823 295.221 + vertex 841.059 245.386 294.804 + endloop + endfacet + facet normal -0.163843 -0.365093 -0.91644 + outer loop + vertex 838.919 238.066 299.056 + vertex 834.993 238.132 299.731 + vertex 836.668 240.491 298.492 + endloop + endfacet + facet normal -0.101351 -0.308897 -0.94568 + outer loop + vertex 836.859 232.735 301.221 + vertex 836.458 235.303 300.425 + vertex 840.387 236.105 299.742 + endloop + endfacet + facet normal -0.0816841 -0.383358 -0.919981 + outer loop + vertex 840.387 236.105 299.742 + vertex 836.458 235.303 300.425 + vertex 838.919 238.066 299.056 + endloop + endfacet + facet normal -0.08664 -0.386456 -0.918229 + outer loop + vertex 840.387 236.105 299.742 + vertex 838.919 238.066 299.056 + vertex 842.599 238.697 298.443 + endloop + endfacet + facet normal -0.0548373 -0.512407 -0.85699 + outer loop + vertex 842.599 238.697 298.443 + vertex 838.919 238.066 299.056 + vertex 840.872 239.081 298.324 + endloop + endfacet + facet normal -0.207992 -0.406347 -0.889731 + outer loop + vertex 838 242.435 297.293 + vertex 839.539 240.136 297.983 + vertex 836.668 240.491 298.492 + endloop + endfacet + facet normal -0.111819 -0.430615 -0.895582 + outer loop + vertex 840.872 239.081 298.324 + vertex 838.919 238.066 299.056 + vertex 839.539 240.136 297.983 + endloop + endfacet + facet normal -0.20774 -0.400282 -0.892535 + outer loop + vertex 838.919 238.066 299.056 + vertex 836.668 240.491 298.492 + vertex 839.539 240.136 297.983 + endloop + endfacet + facet normal -0.0897759 -0.225948 -0.969994 + outer loop + vertex 832.035 227.616 302.999 + vertex 831.457 229.831 302.536 + vertex 834.165 230.304 302.175 + endloop + endfacet + facet normal -0.0825485 -0.261072 -0.961783 + outer loop + vertex 834.165 230.304 302.175 + vertex 831.457 229.831 302.536 + vertex 833.89 232.556 301.588 + endloop + endfacet + facet normal -0.102588 -0.262885 -0.959358 + outer loop + vertex 834.165 230.304 302.175 + vertex 833.89 232.556 301.588 + vertex 836.859 232.735 301.221 + endloop + endfacet + facet normal -0.0982089 -0.308545 -0.946126 + outer loop + vertex 836.859 232.735 301.221 + vertex 833.89 232.556 301.588 + vertex 836.458 235.303 300.425 + endloop + endfacet + facet normal -0.0611681 -0.165003 -0.984395 + outer loop + vertex 825.801 221.293 304.591 + vertex 825.264 223.545 304.247 + vertex 828.968 224.396 303.874 + endloop + endfacet + facet normal -0.0537415 -0.195086 -0.979313 + outer loop + vertex 828.968 224.396 303.874 + vertex 825.264 223.545 304.247 + vertex 828.82 226.824 303.399 + endloop + endfacet + facet normal -0.0733106 -0.195996 -0.97786 + outer loop + vertex 828.968 224.396 303.874 + vertex 828.82 226.824 303.399 + vertex 832.035 227.616 302.999 + endloop + endfacet + facet normal -0.0666622 -0.220562 -0.973092 + outer loop + vertex 832.035 227.616 302.999 + vertex 828.82 226.824 303.399 + vertex 831.457 229.831 302.536 + endloop + endfacet + facet normal -0.0344391 -0.158982 -0.986681 + outer loop + vertex 825.801 221.293 304.591 + vertex 820.384 218.221 305.275 + vertex 825.264 223.545 304.247 + endloop + endfacet + facet normal 0.513343 -0.293107 -0.806577 + outer loop + vertex 699.083 150.282 297.152 + vertex 698.37 150.922 296.467 + vertex 700.143 155.099 296.077 + endloop + endfacet + facet normal 0.504413 -0.293234 -0.812146 + outer loop + vertex 697.54 150.775 296.004 + vertex 699.191 155.811 295.211 + vertex 698.37 150.922 296.467 + endloop + endfacet + facet normal 0.513856 -0.293289 -0.806185 + outer loop + vertex 699.191 155.811 295.211 + vertex 700.143 155.099 296.077 + vertex 698.37 150.922 296.467 + endloop + endfacet + facet normal 0.487713 -0.337635 -0.805071 + outer loop + vertex 696.213 147.176 296.71 + vertex 697.54 150.775 296.004 + vertex 697.07 147.56 297.068 + endloop + endfacet + facet normal 0.503094 -0.336846 -0.795884 + outer loop + vertex 697.07 147.56 297.068 + vertex 697.54 150.775 296.004 + vertex 698.37 150.922 296.467 + endloop + endfacet + facet normal 0.479575 -0.376697 -0.792532 + outer loop + vertex 695.335 145.151 297.141 + vertex 696.213 147.176 296.71 + vertex 696.146 145.275 297.572 + endloop + endfacet + facet normal 0.495155 -0.373555 -0.784396 + outer loop + vertex 696.146 145.275 297.572 + vertex 696.213 147.176 296.71 + vertex 697.07 147.56 297.068 + endloop + endfacet + facet normal 0.46923 -0.367207 -0.803108 + outer loop + vertex 696.146 145.275 297.572 + vertex 697.07 147.56 297.068 + vertex 697.241 145.863 297.944 + endloop + endfacet + facet normal 0.482637 -0.362777 -0.797154 + outer loop + vertex 697.241 145.863 297.944 + vertex 697.07 147.56 297.068 + vertex 698.098 147.768 297.596 + endloop + endfacet + facet normal 0.483105 -0.331692 -0.810302 + outer loop + vertex 697.07 147.56 297.068 + vertex 698.37 150.922 296.467 + vertex 698.098 147.768 297.596 + endloop + endfacet + facet normal 0.482544 -0.331754 -0.810611 + outer loop + vertex 698.098 147.768 297.596 + vertex 698.37 150.922 296.467 + vertex 699.083 150.282 297.152 + endloop + endfacet + facet normal 0.47229 -0.328997 -0.817743 + outer loop + vertex 698.098 147.768 297.596 + vertex 699.083 150.282 297.152 + vertex 699.332 148.114 298.169 + endloop + endfacet + facet normal 0.490043 -0.323137 -0.809593 + outer loop + vertex 699.332 148.114 298.169 + vertex 699.083 150.282 297.152 + vertex 700.364 151.131 297.589 + endloop + endfacet + facet normal 0.463982 -0.356872 -0.810779 + outer loop + vertex 697.241 145.863 297.944 + vertex 698.098 147.768 297.596 + vertex 698.556 146.159 298.566 + endloop + endfacet + facet normal 0.473854 -0.351924 -0.807225 + outer loop + vertex 698.556 146.159 298.566 + vertex 698.098 147.768 297.596 + vertex 699.332 148.114 298.169 + endloop + endfacet + facet normal 0.475335 -0.2901 -0.830601 + outer loop + vertex 699.083 150.282 297.152 + vertex 700.143 155.099 296.077 + vertex 700.364 151.131 297.589 + endloop + endfacet + facet normal 0.488988 -0.286753 -0.82381 + outer loop + vertex 700.143 155.099 296.077 + vertex 702.164 155.367 297.183 + vertex 700.364 151.131 297.589 + endloop + endfacet + facet normal 0.531722 -0.306447 -0.789532 + outer loop + vertex 696.787 149.785 295.931 + vertex 696.732 150.314 295.689 + vertex 698.354 154.922 294.993 + endloop + endfacet + facet normal 0.464069 -0.300895 -0.833128 + outer loop + vertex 696.438 149.727 295.737 + vertex 698.034 154.577 294.875 + vertex 696.732 150.314 295.689 + endloop + endfacet + facet normal 0.616018 -0.325219 -0.717464 + outer loop + vertex 698.034 154.577 294.875 + vertex 698.354 154.922 294.993 + vertex 696.732 150.314 295.689 + endloop + endfacet + facet normal 0.530394 -0.361771 -0.766684 + outer loop + vertex 695.392 147.049 296.277 + vertex 696.438 149.727 295.737 + vertex 695.436 146.918 296.37 + endloop + endfacet + facet normal 0.651047 -0.380112 -0.657003 + outer loop + vertex 695.436 146.918 296.37 + vertex 696.438 149.727 295.737 + vertex 696.732 150.314 295.689 + endloop + endfacet + facet normal 0.525094 -0.394008 -0.754343 + outer loop + vertex 694.555 145.144 296.69 + vertex 695.392 147.049 296.277 + vertex 694.499 144.774 296.844 + endloop + endfacet + facet normal 0.488891 -0.386684 -0.78196 + outer loop + vertex 694.499 144.774 296.844 + vertex 695.392 147.049 296.277 + vertex 695.436 146.918 296.37 + endloop + endfacet + facet normal 0.463469 -0.379705 -0.800638 + outer loop + vertex 694.499 144.774 296.844 + vertex 695.436 146.918 296.37 + vertex 694.789 144.761 297.018 + endloop + endfacet + facet normal 0.453 -0.378521 -0.807163 + outer loop + vertex 694.789 144.761 297.018 + vertex 695.436 146.918 296.37 + vertex 695.676 146.95 296.49 + endloop + endfacet + facet normal 0.455744 -0.338874 -0.823081 + outer loop + vertex 695.436 146.918 296.37 + vertex 696.732 150.314 295.689 + vertex 695.676 146.95 296.49 + endloop + endfacet + facet normal 0.439079 -0.336057 -0.833232 + outer loop + vertex 695.676 146.95 296.49 + vertex 696.732 150.314 295.689 + vertex 696.787 149.785 295.931 + endloop + endfacet + facet normal 0.451407 -0.378135 -0.808236 + outer loop + vertex 694.789 144.761 297.018 + vertex 695.676 146.95 296.49 + vertex 695.335 145.151 297.141 + endloop + endfacet + facet normal 0.482641 -0.377543 -0.790265 + outer loop + vertex 695.335 145.151 297.141 + vertex 695.676 146.95 296.49 + vertex 696.213 147.176 296.71 + endloop + endfacet + facet normal 0.530887 -0.34727 -0.773022 + outer loop + vertex 697.54 150.775 296.004 + vertex 696.213 147.176 296.71 + vertex 696.787 149.785 295.931 + endloop + endfacet + facet normal 0.476626 -0.345843 -0.80822 + outer loop + vertex 696.787 149.785 295.931 + vertex 696.213 147.176 296.71 + vertex 695.676 146.95 296.49 + endloop + endfacet + facet normal 0.467982 -0.294957 -0.833063 + outer loop + vertex 696.787 149.785 295.931 + vertex 698.354 154.922 294.993 + vertex 697.54 150.775 296.004 + endloop + endfacet + facet normal 0.52389 -0.297418 -0.798174 + outer loop + vertex 697.54 150.775 296.004 + vertex 698.354 154.922 294.993 + vertex 699.191 155.811 295.211 + endloop + endfacet + facet normal -0.240974 -0.130231 -0.961754 + outer loop + vertex 693.994 144.203 296.858 + vertex 694.664 145.715 296.486 + vertex 694.268 144.767 296.713 + endloop + endfacet + facet normal 0.261503 -0.326781 -0.908202 + outer loop + vertex 694.268 144.767 296.713 + vertex 694.664 145.715 296.486 + vertex 695.083 146.575 296.297 + endloop + endfacet + facet normal 0.149866 -0.281077 -0.947911 + outer loop + vertex 694.664 145.715 296.486 + vertex 695.787 148.34 295.885 + vertex 695.083 146.575 296.297 + endloop + endfacet + facet normal 0.849682 -0.414869 -0.325459 + outer loop + vertex 695.083 146.575 296.297 + vertex 695.787 148.34 295.885 + vertex 696.376 149.745 295.633 + endloop + endfacet + facet normal 0.491592 -0.366188 -0.790091 + outer loop + vertex 695.083 146.575 296.297 + vertex 696.376 149.745 295.633 + vertex 695.35 147.085 296.227 + endloop + endfacet + facet normal 0.892932 -0.393315 -0.219034 + outer loop + vertex 695.35 147.085 296.227 + vertex 696.376 149.745 295.633 + vertex 696.636 150.37 295.572 + endloop + endfacet + facet normal 0.429331 -0.381722 -0.818513 + outer loop + vertex 694.268 144.767 296.713 + vertex 695.083 146.575 296.297 + vertex 694.368 144.871 296.717 + endloop + endfacet + facet normal 0.651743 -0.427695 -0.626346 + outer loop + vertex 694.368 144.871 296.717 + vertex 695.083 146.575 296.297 + vertex 695.35 147.085 296.227 + endloop + endfacet + facet normal 0.419044 -0.369375 -0.829436 + outer loop + vertex 694.368 144.871 296.717 + vertex 695.35 147.085 296.227 + vertex 694.555 145.144 296.69 + endloop + endfacet + facet normal 0.543317 -0.39865 -0.73884 + outer loop + vertex 694.555 145.144 296.69 + vertex 695.35 147.085 296.227 + vertex 695.392 147.049 296.277 + endloop + endfacet + facet normal 0.566602 -0.368896 -0.736802 + outer loop + vertex 695.35 147.085 296.227 + vertex 696.636 150.37 295.572 + vertex 695.392 147.049 296.277 + endloop + endfacet + facet normal 0.52666 -0.360911 -0.769658 + outer loop + vertex 695.392 147.049 296.277 + vertex 696.636 150.37 295.572 + vertex 696.438 149.727 295.737 + endloop + endfacet + facet normal 0.909035 -0.341616 -0.238651 + outer loop + vertex 696.438 149.727 295.737 + vertex 696.636 150.37 295.572 + vertex 698.034 154.577 294.875 + endloop + endfacet + facet normal 0.698389 -0.351826 -0.623274 + outer loop + vertex 696.376 149.745 295.633 + vertex 697.909 154.201 294.835 + vertex 696.636 150.37 295.572 + endloop + endfacet + facet normal 0.948509 -0.316635 -0.00855074 + outer loop + vertex 697.909 154.201 294.835 + vertex 698.034 154.577 294.875 + vertex 696.636 150.37 295.572 + endloop + endfacet + facet normal -0.520292 -0.303438 -0.798262 + outer loop + vertex 839.312 249.539 293.555 + vertex 839.001 249.737 293.682 + vertex 837.577 253.454 293.197 + endloop + endfacet + facet normal -0.513198 -0.298092 -0.804841 + outer loop + vertex 839.019 248.918 293.974 + vertex 837.371 252.269 293.783 + vertex 839.001 249.737 293.682 + endloop + endfacet + facet normal -0.521622 -0.303815 -0.79725 + outer loop + vertex 837.371 252.269 293.783 + vertex 837.577 253.454 293.197 + vertex 839.001 249.737 293.682 + endloop + endfacet + facet normal -0.36751 -0.350731 -0.86135 + outer loop + vertex 839.927 247.016 294.361 + vertex 839.019 248.918 293.974 + vertex 840.208 247.386 294.09 + endloop + endfacet + facet normal -0.329593 -0.323249 -0.887062 + outer loop + vertex 840.208 247.386 294.09 + vertex 839.019 248.918 293.974 + vertex 839.001 249.737 293.682 + endloop + endfacet + facet normal -0.283089 -0.429543 -0.857528 + outer loop + vertex 841.059 245.386 294.804 + vertex 839.927 247.016 294.361 + vertex 841.357 245.715 294.541 + endloop + endfacet + facet normal -0.275582 -0.422134 -0.863631 + outer loop + vertex 841.357 245.715 294.541 + vertex 839.927 247.016 294.361 + vertex 840.208 247.386 294.09 + endloop + endfacet + facet normal -0.304389 -0.437248 -0.846263 + outer loop + vertex 841.357 245.715 294.541 + vertex 840.208 247.386 294.09 + vertex 841.448 245.983 294.37 + endloop + endfacet + facet normal -0.262192 -0.405802 -0.875546 + outer loop + vertex 841.448 245.983 294.37 + vertex 840.208 247.386 294.09 + vertex 840.277 247.691 293.929 + endloop + endfacet + facet normal -0.407048 -0.355138 -0.84154 + outer loop + vertex 840.208 247.386 294.09 + vertex 839.001 249.737 293.682 + vertex 840.277 247.691 293.929 + endloop + endfacet + facet normal -0.564786 -0.436491 -0.700352 + outer loop + vertex 840.277 247.691 293.929 + vertex 839.001 249.737 293.682 + vertex 839.312 249.539 293.555 + endloop + endfacet + facet normal -0.730227 -0.479589 -0.486583 + outer loop + vertex 840.277 247.691 293.929 + vertex 839.312 249.539 293.555 + vertex 840.22 247.886 293.821 + endloop + endfacet + facet normal -0.660815 -0.248943 0.708061 + outer loop + vertex 840.22 247.886 293.821 + vertex 839.312 249.539 293.555 + vertex 839.76 248.627 293.653 + endloop + endfacet + facet normal -0.423642 -0.487594 -0.7634 + outer loop + vertex 841.448 245.983 294.37 + vertex 840.277 247.691 293.929 + vertex 841.285 246.367 294.214 + endloop + endfacet + facet normal -0.492142 -0.524905 -0.694457 + outer loop + vertex 841.285 246.367 294.214 + vertex 840.277 247.691 293.929 + vertex 840.22 247.886 293.821 + endloop + endfacet + facet normal -0.504824 -0.294085 -0.811583 + outer loop + vertex 836.864 245.76 296.381 + vertex 835.259 250.125 295.798 + vertex 837.565 247.869 295.181 + endloop + endfacet + facet normal -0.491689 -0.276817 -0.8256 + outer loop + vertex 837.565 247.869 295.181 + vertex 835.259 250.125 295.798 + vertex 836.353 251.617 294.646 + endloop + endfacet + facet normal -0.289016 -0.430497 -0.855068 + outer loop + vertex 840.445 244.042 295.708 + vertex 839.346 243.616 296.294 + vertex 839.026 245.357 295.525 + endloop + endfacet + facet normal -0.400437 -0.349077 -0.847228 + outer loop + vertex 837.565 247.869 295.181 + vertex 839.026 245.357 295.525 + vertex 836.864 245.76 296.381 + endloop + endfacet + facet normal -0.336765 -0.354244 -0.872411 + outer loop + vertex 838 242.435 297.293 + vertex 836.864 245.76 296.381 + vertex 839.346 243.616 296.294 + endloop + endfacet + facet normal -0.400434 -0.430538 -0.808882 + outer loop + vertex 839.026 245.357 295.525 + vertex 839.346 243.616 296.294 + vertex 836.864 245.76 296.381 + endloop + endfacet + facet normal -0.425474 -0.361243 -0.829744 + outer loop + vertex 839.026 245.357 295.525 + vertex 837.565 247.869 295.181 + vertex 839.432 246.47 294.833 + endloop + endfacet + facet normal -0.419625 -0.351685 -0.836799 + outer loop + vertex 839.432 246.47 294.833 + vertex 837.565 247.869 295.181 + vertex 838.325 248.881 294.375 + endloop + endfacet + facet normal -0.296253 -0.437464 -0.849034 + outer loop + vertex 840.445 244.042 295.708 + vertex 839.026 245.357 295.525 + vertex 840.685 244.823 295.221 + endloop + endfacet + facet normal -0.29368 -0.425513 -0.855973 + outer loop + vertex 840.685 244.823 295.221 + vertex 839.026 245.357 295.525 + vertex 839.432 246.47 294.833 + endloop + endfacet + facet normal -0.301761 -0.430417 -0.850695 + outer loop + vertex 840.685 244.823 295.221 + vertex 839.432 246.47 294.833 + vertex 841.059 245.386 294.804 + endloop + endfacet + facet normal -0.310656 -0.444044 -0.840427 + outer loop + vertex 841.059 245.386 294.804 + vertex 839.432 246.47 294.833 + vertex 839.927 247.016 294.361 + endloop + endfacet + facet normal -0.414228 -0.349862 -0.840245 + outer loop + vertex 839.432 246.47 294.833 + vertex 838.325 248.881 294.375 + vertex 839.927 247.016 294.361 + endloop + endfacet + facet normal -0.447195 -0.378401 -0.81045 + outer loop + vertex 839.927 247.016 294.361 + vertex 838.325 248.881 294.375 + vertex 839.019 248.918 293.974 + endloop + endfacet + facet normal -0.468748 -0.278141 -0.838399 + outer loop + vertex 839.019 248.918 293.974 + vertex 838.325 248.881 294.375 + vertex 837.371 252.269 293.783 + endloop + endfacet + facet normal -0.499491 -0.278585 -0.820304 + outer loop + vertex 837.565 247.869 295.181 + vertex 836.353 251.617 294.646 + vertex 838.325 248.881 294.375 + endloop + endfacet + facet normal -0.506873 -0.28456 -0.813699 + outer loop + vertex 836.353 251.617 294.646 + vertex 837.371 252.269 293.783 + vertex 838.325 248.881 294.375 + endloop + endfacet + facet normal -0.374555 -0.232274 -0.89764 + outer loop + vertex 833.384 241.639 299.093 + vertex 832.016 246.074 298.516 + vertex 835.103 243.876 297.796 + endloop + endfacet + facet normal -0.384131 -0.248479 -0.889214 + outer loop + vertex 835.103 243.876 297.796 + vertex 832.016 246.074 298.516 + vertex 833.814 248.216 297.141 + endloop + endfacet + facet normal -0.269611 -0.290816 -0.918006 + outer loop + vertex 834.993 238.132 299.731 + vertex 833.384 241.639 299.093 + vertex 836.668 240.491 298.492 + endloop + endfacet + facet normal -0.276015 -0.314185 -0.908352 + outer loop + vertex 836.668 240.491 298.492 + vertex 833.384 241.639 299.093 + vertex 835.103 243.876 297.796 + endloop + endfacet + facet normal -0.318627 -0.329828 -0.888645 + outer loop + vertex 836.668 240.491 298.492 + vertex 835.103 243.876 297.796 + vertex 838 242.435 297.293 + endloop + endfacet + facet normal -0.327725 -0.35231 -0.876627 + outer loop + vertex 838 242.435 297.293 + vertex 835.103 243.876 297.796 + vertex 836.864 245.76 296.381 + endloop + endfacet + facet normal -0.423319 -0.257032 -0.868755 + outer loop + vertex 835.103 243.876 297.796 + vertex 833.814 248.216 297.141 + vertex 836.864 245.76 296.381 + endloop + endfacet + facet normal -0.434603 -0.274436 -0.857791 + outer loop + vertex 836.864 245.76 296.381 + vertex 833.814 248.216 297.141 + vertex 835.259 250.125 295.798 + endloop + endfacet + facet normal -0.268209 -0.186258 -0.945184 + outer loop + vertex 829.376 237.002 301.315 + vertex 828.728 240.876 300.735 + vertex 831.55 239.203 300.264 + endloop + endfacet + facet normal -0.272316 -0.193956 -0.942457 + outer loop + vertex 831.55 239.203 300.264 + vertex 828.728 240.876 300.735 + vertex 830.171 243.516 299.775 + endloop + endfacet + facet normal -0.195632 -0.206245 -0.958745 + outer loop + vertex 830.478 232.981 301.955 + vertex 829.376 237.002 301.315 + vertex 832.838 235.601 300.909 + endloop + endfacet + facet normal -0.20977 -0.244677 -0.946641 + outer loop + vertex 832.838 235.601 300.909 + vertex 829.376 237.002 301.315 + vertex 831.55 239.203 300.264 + endloop + endfacet + facet normal -0.223249 -0.248754 -0.942487 + outer loop + vertex 832.838 235.601 300.909 + vertex 831.55 239.203 300.264 + vertex 834.993 238.132 299.731 + endloop + endfacet + facet normal -0.230152 -0.275505 -0.933342 + outer loop + vertex 834.993 238.132 299.731 + vertex 831.55 239.203 300.264 + vertex 833.384 241.639 299.093 + endloop + endfacet + facet normal -0.317069 -0.206361 -0.925679 + outer loop + vertex 831.55 239.203 300.264 + vertex 830.171 243.516 299.775 + vertex 833.384 241.639 299.093 + endloop + endfacet + facet normal -0.323629 -0.219525 -0.920365 + outer loop + vertex 833.384 241.639 299.093 + vertex 830.171 243.516 299.775 + vertex 832.016 246.074 298.516 + endloop + endfacet + facet normal -0.199465 -0.113259 -0.973338 + outer loop + vertex 823.578 230.96 303.404 + vertex 822.192 237.932 302.877 + vertex 826.666 234.572 302.351 + endloop + endfacet + facet normal -0.220336 -0.142361 -0.964979 + outer loop + vertex 826.666 234.572 302.351 + vertex 822.192 237.932 302.877 + vertex 825.938 240.288 301.674 + endloop + endfacet + facet normal -0.142505 -0.138884 -0.980002 + outer loop + vertex 825.415 226.96 303.704 + vertex 823.578 230.96 303.404 + vertex 827.931 230.038 302.902 + endloop + endfacet + facet normal -0.146434 -0.159451 -0.976285 + outer loop + vertex 827.931 230.038 302.902 + vertex 823.578 230.96 303.404 + vertex 826.666 234.572 302.351 + endloop + endfacet + facet normal -0.170076 -0.165456 -0.971441 + outer loop + vertex 827.931 230.038 302.902 + vertex 826.666 234.572 302.351 + vertex 830.478 232.981 301.955 + endloop + endfacet + facet normal -0.185016 -0.203754 -0.961381 + outer loop + vertex 830.478 232.981 301.955 + vertex 826.666 234.572 302.351 + vertex 829.376 237.002 301.315 + endloop + endfacet + facet normal -0.238167 -0.144097 -0.960475 + outer loop + vertex 826.666 234.572 302.351 + vertex 825.938 240.288 301.674 + vertex 829.376 237.002 301.315 + endloop + endfacet + facet normal -0.277652 -0.187395 -0.942227 + outer loop + vertex 829.376 237.002 301.315 + vertex 825.938 240.288 301.674 + vertex 828.728 240.876 300.735 + endloop + endfacet + facet normal -0.163068 -0.10659 -0.98084 + outer loop + vertex 822.192 237.932 302.877 + vertex 823.578 230.96 303.404 + vertex 818.007 233.487 304.056 + endloop + endfacet + facet normal -0.15848 -0.096 -0.982684 + outer loop + vertex 820.202 225.35 304.497 + vertex 818.007 233.487 304.056 + vertex 823.578 230.96 303.404 + endloop + endfacet + facet normal 0.555774 -0.181476 -0.811284 + outer loop + vertex 700.776 161.871 294.429 + vertex 701.958 168.594 293.735 + vertex 701.878 161.706 295.22 + endloop + endfacet + facet normal 0.560274 -0.180888 -0.808314 + outer loop + vertex 701.878 161.706 295.22 + vertex 701.958 168.594 293.735 + vertex 703.049 168.497 294.513 + endloop + endfacet + facet normal 0.544984 -0.246037 -0.801535 + outer loop + vertex 699.191 155.811 295.211 + vertex 700.776 161.871 294.429 + vertex 700.143 155.099 296.077 + endloop + endfacet + facet normal 0.540955 -0.246304 -0.804178 + outer loop + vertex 700.143 155.099 296.077 + vertex 700.776 161.871 294.429 + vertex 701.878 161.706 295.22 + endloop + endfacet + facet normal 0.490482 -0.2375 -0.838463 + outer loop + vertex 700.143 155.099 296.077 + vertex 701.878 161.706 295.22 + vertex 702.164 155.367 297.183 + endloop + endfacet + facet normal 0.507729 -0.233845 -0.829173 + outer loop + vertex 702.164 155.367 297.183 + vertex 701.878 161.706 295.22 + vertex 703.758 161.929 296.308 + endloop + endfacet + facet normal 0.508731 -0.175593 -0.842829 + outer loop + vertex 701.878 161.706 295.22 + vertex 703.049 168.497 294.513 + vertex 703.758 161.929 296.308 + endloop + endfacet + facet normal 0.532379 -0.169369 -0.829389 + outer loop + vertex 703.758 161.929 296.308 + vertex 703.049 168.497 294.513 + vertex 704.826 168.673 295.617 + endloop + endfacet + facet normal 0.546383 -0.197356 -0.813951 + outer loop + vertex 699.855 161.345 293.922 + vertex 701.161 168.012 293.181 + vertex 700.197 161.863 294.026 + endloop + endfacet + facet normal 0.748097 -0.203914 -0.631483 + outer loop + vertex 700.197 161.863 294.026 + vertex 701.161 168.012 293.181 + vertex 701.419 168.574 293.306 + endloop + endfacet + facet normal 0.571056 -0.263165 -0.777585 + outer loop + vertex 698.034 154.577 294.875 + vertex 699.855 161.345 293.922 + vertex 698.354 154.922 294.993 + endloop + endfacet + facet normal 0.629081 -0.268702 -0.729421 + outer loop + vertex 698.354 154.922 294.993 + vertex 699.855 161.345 293.922 + vertex 700.197 161.863 294.026 + endloop + endfacet + facet normal 0.479563 -0.244775 -0.842677 + outer loop + vertex 698.354 154.922 294.993 + vertex 700.197 161.863 294.026 + vertex 699.191 155.811 295.211 + endloop + endfacet + facet normal 0.555736 -0.24782 -0.793563 + outer loop + vertex 699.191 155.811 295.211 + vertex 700.197 161.863 294.026 + vertex 700.776 161.871 294.429 + endloop + endfacet + facet normal 0.562765 -0.188733 -0.804783 + outer loop + vertex 700.197 161.863 294.026 + vertex 701.419 168.574 293.306 + vertex 700.776 161.871 294.429 + endloop + endfacet + facet normal 0.615267 -0.187239 -0.76576 + outer loop + vertex 700.776 161.871 294.429 + vertex 701.419 168.574 293.306 + vertex 701.958 168.594 293.735 + endloop + endfacet + facet normal 0.931959 -0.288264 -0.219901 + outer loop + vertex 697.909 154.201 294.835 + vertex 699.622 160.432 293.931 + vertex 698.034 154.577 294.875 + endloop + endfacet + facet normal 0.96417 -0.245192 0.101282 + outer loop + vertex 698.034 154.577 294.875 + vertex 699.622 160.432 293.931 + vertex 699.855 161.345 293.922 + endloop + endfacet + facet normal 0.871048 -0.226431 -0.435895 + outer loop + vertex 699.622 160.432 293.931 + vertex 700.944 166.865 293.229 + vertex 699.855 161.345 293.922 + endloop + endfacet + facet normal 0.978947 -0.18119 0.0939785 + outer loop + vertex 699.855 161.345 293.922 + vertex 700.944 166.865 293.229 + vertex 701.161 168.012 293.181 + endloop + endfacet + facet normal -0.772311 -0.221876 -0.595237 + outer loop + vertex 835.771 257.729 293.253 + vertex 834.56 263.219 292.778 + vertex 835.968 258.507 292.707 + endloop + endfacet + facet normal -0.860636 -0.250542 -0.443322 + outer loop + vertex 835.968 258.507 292.707 + vertex 834.56 263.219 292.778 + vertex 835.145 261.907 292.383 + endloop + endfacet + facet normal -0.626849 -0.255306 -0.736124 + outer loop + vertex 837.371 252.269 293.783 + vertex 835.771 257.729 293.253 + vertex 837.577 253.454 293.197 + endloop + endfacet + facet normal -0.696192 -0.285604 -0.658595 + outer loop + vertex 837.577 253.454 293.197 + vertex 835.771 257.729 293.253 + vertex 835.968 258.507 292.707 + endloop + endfacet + facet normal -0.591474 -0.180919 -0.785765 + outer loop + vertex 834.081 255.132 295.232 + vertex 833.092 260.398 294.764 + vertex 835.14 256.561 294.106 + endloop + endfacet + facet normal -0.593808 -0.182531 -0.783629 + outer loop + vertex 835.14 256.561 294.106 + vertex 833.092 260.398 294.764 + vertex 833.661 262.952 293.738 + endloop + endfacet + facet normal -0.548718 -0.220256 -0.806471 + outer loop + vertex 835.259 250.125 295.798 + vertex 834.081 255.132 295.232 + vertex 836.353 251.617 294.646 + endloop + endfacet + facet normal -0.552567 -0.223324 -0.802992 + outer loop + vertex 836.353 251.617 294.646 + vertex 834.081 255.132 295.232 + vertex 835.14 256.561 294.106 + endloop + endfacet + facet normal -0.543531 -0.221823 -0.809549 + outer loop + vertex 836.353 251.617 294.646 + vertex 835.14 256.561 294.106 + vertex 837.371 252.269 293.783 + endloop + endfacet + facet normal -0.586166 -0.246837 -0.771674 + outer loop + vertex 837.371 252.269 293.783 + vertex 835.14 256.561 294.106 + vertex 835.771 257.729 293.253 + endloop + endfacet + facet normal -0.644875 -0.191823 -0.739825 + outer loop + vertex 835.14 256.561 294.106 + vertex 833.661 262.952 293.738 + vertex 835.771 257.729 293.253 + endloop + endfacet + facet normal -0.683503 -0.211244 -0.698713 + outer loop + vertex 835.771 257.729 293.253 + vertex 833.661 262.952 293.738 + vertex 834.56 263.219 292.778 + endloop + endfacet + facet normal -0.50963 -0.151369 -0.846974 + outer loop + vertex 830.924 251.477 297.967 + vertex 830.195 256.985 297.422 + vertex 832.682 253.411 296.564 + endloop + endfacet + facet normal -0.522493 -0.162722 -0.836972 + outer loop + vertex 832.682 253.411 296.564 + vertex 830.195 256.985 297.422 + vertex 831.481 259.688 296.093 + endloop + endfacet + facet normal -0.453087 -0.180231 -0.873057 + outer loop + vertex 832.016 246.074 298.516 + vertex 830.924 251.477 297.967 + vertex 833.814 248.216 297.141 + endloop + endfacet + facet normal -0.469366 -0.197818 -0.86056 + outer loop + vertex 833.814 248.216 297.141 + vertex 830.924 251.477 297.967 + vertex 832.682 253.411 296.564 + endloop + endfacet + facet normal -0.50845 -0.203679 -0.836656 + outer loop + vertex 833.814 248.216 297.141 + vertex 832.682 253.411 296.564 + vertex 835.259 250.125 295.798 + endloop + endfacet + facet normal -0.520837 -0.215895 -0.825905 + outer loop + vertex 835.259 250.125 295.798 + vertex 832.682 253.411 296.564 + vertex 834.081 255.132 295.232 + endloop + endfacet + facet normal -0.563157 -0.168406 -0.809008 + outer loop + vertex 832.682 253.411 296.564 + vertex 831.481 259.688 296.093 + vertex 834.081 255.132 295.232 + endloop + endfacet + facet normal -0.57798 -0.179304 -0.796109 + outer loop + vertex 834.081 255.132 295.232 + vertex 831.481 259.688 296.093 + vertex 833.092 260.398 294.764 + endloop + endfacet + facet normal -0.380691 -0.115996 -0.917398 + outer loop + vertex 826.733 245.504 300.698 + vertex 824.846 253.07 300.524 + vertex 828.787 249.129 299.387 + endloop + endfacet + facet normal -0.386716 -0.123014 -0.913957 + outer loop + vertex 828.787 249.129 299.387 + vertex 824.846 253.07 300.524 + vertex 827.779 256.214 298.86 + endloop + endfacet + facet normal -0.337851 -0.153119 -0.928661 + outer loop + vertex 828.728 240.876 300.735 + vertex 826.733 245.504 300.698 + vertex 830.171 243.516 299.775 + endloop + endfacet + facet normal -0.334793 -0.146847 -0.930779 + outer loop + vertex 830.171 243.516 299.775 + vertex 826.733 245.504 300.698 + vertex 828.787 249.129 299.387 + endloop + endfacet + facet normal -0.395371 -0.159964 -0.904485 + outer loop + vertex 830.171 243.516 299.775 + vertex 828.787 249.129 299.387 + vertex 832.016 246.074 298.516 + endloop + endfacet + facet normal -0.405931 -0.173164 -0.897348 + outer loop + vertex 832.016 246.074 298.516 + vertex 828.787 249.129 299.387 + vertex 830.924 251.477 297.967 + endloop + endfacet + facet normal -0.446221 -0.129362 -0.885524 + outer loop + vertex 828.787 249.129 299.387 + vertex 827.779 256.214 298.86 + vertex 830.924 251.477 297.967 + endloop + endfacet + facet normal -0.470515 -0.14845 -0.869815 + outer loop + vertex 830.924 251.477 297.967 + vertex 827.779 256.214 298.86 + vertex 830.195 256.985 297.422 + endloop + endfacet + facet normal -0.290866 -0.133013 -0.947473 + outer loop + vertex 828.728 240.876 300.735 + vertex 825.938 240.288 301.674 + vertex 826.733 245.504 300.698 + endloop + endfacet + facet normal -0.301926 -0.097067 -0.948377 + outer loop + vertex 824.846 253.07 300.524 + vertex 826.733 245.504 300.698 + vertex 821.716 247.263 302.115 + endloop + endfacet + facet normal -0.251815 -0.0915259 -0.963438 + outer loop + vertex 822.192 237.932 302.877 + vertex 821.716 247.263 302.115 + vertex 825.938 240.288 301.674 + endloop + endfacet + facet normal -0.311149 -0.128822 -0.94159 + outer loop + vertex 826.733 245.504 300.698 + vertex 825.938 240.288 301.674 + vertex 821.716 247.263 302.115 + endloop + endfacet + facet normal -0.198526 -0.072301 -0.977425 + outer loop + vertex 818.007 233.487 304.056 + vertex 816.582 243.045 303.638 + vertex 822.192 237.932 302.877 + endloop + endfacet + facet normal -0.214326 -0.0903601 -0.972574 + outer loop + vertex 822.192 237.932 302.877 + vertex 816.582 243.045 303.638 + vertex 821.716 247.263 302.115 + endloop + endfacet + facet normal 0.582314 -0.0665663 -0.810234 + outer loop + vertex 702.747 175.782 293.265 + vertex 703.332 182.634 293.123 + vertex 703.854 175.688 294.068 + endloop + endfacet + facet normal 0.596094 -0.0641847 -0.800345 + outer loop + vertex 703.854 175.688 294.068 + vertex 703.332 182.634 293.123 + vertex 704.564 184.032 293.928 + endloop + endfacet + facet normal 0.569856 -0.115701 -0.813559 + outer loop + vertex 701.958 168.594 293.735 + vertex 702.747 175.782 293.265 + vertex 703.049 168.497 294.513 + endloop + endfacet + facet normal 0.577085 -0.114553 -0.80861 + outer loop + vertex 703.049 168.497 294.513 + vertex 702.747 175.782 293.265 + vertex 703.854 175.688 294.068 + endloop + endfacet + facet normal 0.532611 -0.111453 -0.83899 + outer loop + vertex 703.049 168.497 294.513 + vertex 703.854 175.688 294.068 + vertex 704.826 168.673 295.617 + endloop + endfacet + facet normal 0.543734 -0.108419 -0.832225 + outer loop + vertex 704.826 168.673 295.617 + vertex 703.854 175.688 294.068 + vertex 705.584 175.819 295.182 + endloop + endfacet + facet normal 0.543388 -0.0603201 -0.837312 + outer loop + vertex 703.854 175.688 294.068 + vertex 704.564 184.032 293.928 + vertex 705.584 175.819 295.182 + endloop + endfacet + facet normal 0.526604 -0.0639898 -0.847699 + outer loop + vertex 705.584 175.819 295.182 + vertex 704.564 184.032 293.928 + vertex 706.271 182.758 295.085 + endloop + endfacet + facet normal 0.73533 -0.0726024 -0.673809 + outer loop + vertex 701.983 174.855 292.669 + vertex 702.489 182.864 292.358 + vertex 702.203 175.842 292.802 + endloop + endfacet + facet normal 0.813104 -0.0697129 -0.577929 + outer loop + vertex 702.203 175.842 292.802 + vertex 702.489 182.864 292.358 + vertex 702.775 184.261 292.592 + endloop + endfacet + facet normal 0.652275 -0.134272 -0.745995 + outer loop + vertex 701.161 168.012 293.181 + vertex 701.983 174.855 292.669 + vertex 701.419 168.574 293.306 + endloop + endfacet + facet normal 0.864889 -0.126905 -0.485656 + outer loop + vertex 701.419 168.574 293.306 + vertex 701.983 174.855 292.669 + vertex 702.203 175.842 292.802 + endloop + endfacet + facet normal 0.620165 -0.12062 -0.775143 + outer loop + vertex 701.419 168.574 293.306 + vertex 702.203 175.842 292.802 + vertex 701.958 168.594 293.735 + endloop + endfacet + facet normal 0.635177 -0.119571 -0.763055 + outer loop + vertex 701.958 168.594 293.735 + vertex 702.203 175.842 292.802 + vertex 702.747 175.782 293.265 + endloop + endfacet + facet normal 0.642252 -0.0627267 -0.763923 + outer loop + vertex 702.203 175.842 292.802 + vertex 702.775 184.261 292.592 + vertex 702.747 175.782 293.265 + endloop + endfacet + facet normal 0.579391 -0.0663604 -0.812344 + outer loop + vertex 702.747 175.782 293.265 + vertex 702.775 184.261 292.592 + vertex 703.332 182.634 293.123 + endloop + endfacet + facet normal 0.608464 -0.147399 -0.779773 + outer loop + vertex 700.944 166.865 293.229 + vertex 701.81 173.074 292.731 + vertex 701.161 168.012 293.181 + endloop + endfacet + facet normal 0.864077 -0.0663996 0.498962 + outer loop + vertex 701.161 168.012 293.181 + vertex 701.81 173.074 292.731 + vertex 701.983 174.855 292.669 + endloop + endfacet + facet normal 0.748606 -0.0957366 -0.656066 + outer loop + vertex 701.81 173.074 292.731 + vertex 702.35 179.562 292.401 + vertex 701.983 174.855 292.669 + endloop + endfacet + facet normal 0.772331 -0.0242238 0.634758 + outer loop + vertex 701.983 174.855 292.669 + vertex 702.35 179.562 292.401 + vertex 702.489 182.864 292.358 + endloop + endfacet + facet normal -0.697854 -0.160452 -0.698036 + outer loop + vertex 834.56 263.219 292.778 + vertex 833.661 262.952 293.738 + vertex 832.27 272.12 293.021 + endloop + endfacet + facet normal -0.631682 -0.163689 -0.757749 + outer loop + vertex 833.092 260.398 294.764 + vertex 830.505 267.966 295.286 + vertex 833.661 262.952 293.738 + endloop + endfacet + facet normal -0.621801 -0.154363 -0.767812 + outer loop + vertex 830.505 267.966 295.286 + vertex 832.27 272.12 293.021 + vertex 833.661 262.952 293.738 + endloop + endfacet + facet normal -0.590231 -0.147042 -0.793729 + outer loop + vertex 833.092 260.398 294.764 + vertex 831.481 259.688 296.093 + vertex 830.505 267.966 295.286 + endloop + endfacet + facet normal -0.543913 -0.147199 -0.82613 + outer loop + vertex 830.195 256.985 297.422 + vertex 827.566 264.648 297.787 + vertex 831.481 259.688 296.093 + endloop + endfacet + facet normal -0.541556 -0.144658 -0.828125 + outer loop + vertex 827.566 264.648 297.787 + vertex 830.505 267.966 295.286 + vertex 831.481 259.688 296.093 + endloop + endfacet + facet normal -0.478521 -0.122701 -0.869461 + outer loop + vertex 830.195 256.985 297.422 + vertex 827.779 256.214 298.86 + vertex 827.566 264.648 297.787 + endloop + endfacet + facet normal -0.410625 -0.0968373 -0.906648 + outer loop + vertex 824.846 253.07 300.524 + vertex 823.574 262.418 300.102 + vertex 827.779 256.214 298.86 + endloop + endfacet + facet normal -0.444974 -0.124071 -0.886907 + outer loop + vertex 823.574 262.418 300.102 + vertex 827.566 264.648 297.787 + vertex 827.779 256.214 298.86 + endloop + endfacet + facet normal -0.331679 -0.0787644 -0.940099 + outer loop + vertex 821.716 247.263 302.115 + vertex 819.685 258.403 301.898 + vertex 824.846 253.07 300.524 + endloop + endfacet + facet normal -0.3408 -0.0886644 -0.935945 + outer loop + vertex 824.846 253.07 300.524 + vertex 819.685 258.403 301.898 + vertex 823.574 262.418 300.102 + endloop + endfacet + facet normal -0.241102 -0.0564284 -0.968858 + outer loop + vertex 816.582 243.045 303.638 + vertex 815.172 253.774 303.364 + vertex 821.716 247.263 302.115 + endloop + endfacet + facet normal -0.248262 -0.0640641 -0.966572 + outer loop + vertex 821.716 247.263 302.115 + vertex 815.172 253.774 303.364 + vertex 819.685 258.403 301.898 + endloop + endfacet + facet normal 0.544327 -0.0317014 -0.838274 + outer loop + vertex 706.271 182.758 295.085 + vertex 704.564 184.032 293.928 + vertex 705.956 194.059 294.452 + endloop + endfacet + facet normal 0.571237 -0.0308466 -0.820205 + outer loop + vertex 703.332 182.634 293.123 + vertex 703.606 193.796 292.894 + vertex 704.564 184.032 293.928 + endloop + endfacet + facet normal 0.555138 -0.0335783 -0.83108 + outer loop + vertex 703.606 193.796 292.894 + vertex 705.956 194.059 294.452 + vertex 704.564 184.032 293.928 + endloop + endfacet + facet normal 0.639351 -0.031452 -0.768271 + outer loop + vertex 703.332 182.634 293.123 + vertex 702.775 184.261 292.592 + vertex 703.606 193.796 292.894 + endloop + endfacet + facet normal 0.721074 -0.0317217 -0.692131 + outer loop + vertex 702.489 182.864 292.358 + vertex 702.77 194.16 292.133 + vertex 702.775 184.261 292.592 + endloop + endfacet + facet normal 0.66411 -0.0342872 -0.746848 + outer loop + vertex 702.77 194.16 292.133 + vertex 703.606 193.796 292.894 + vertex 702.775 184.261 292.592 + endloop + endfacet + facet normal -0.644112 -0.136613 -0.752634 + outer loop + vertex 830.505 267.966 295.286 + vertex 828.378 279.559 295.001 + vertex 832.27 272.12 293.021 + endloop + endfacet + facet normal -0.634021 -0.128699 -0.762531 + outer loop + vertex 832.27 272.12 293.021 + vertex 828.378 279.559 295.001 + vertex 829.857 284.111 293.004 + endloop + endfacet + facet normal -0.560407 -0.121297 -0.819287 + outer loop + vertex 827.566 264.648 297.787 + vertex 825.769 276.013 297.334 + vertex 830.505 267.966 295.286 + endloop + endfacet + facet normal -0.562941 -0.123308 -0.817247 + outer loop + vertex 830.505 267.966 295.286 + vertex 825.769 276.013 297.334 + vertex 828.378 279.559 295.001 + endloop + endfacet + facet normal -0.45843 -0.0964296 -0.883484 + outer loop + vertex 823.574 262.418 300.102 + vertex 822.204 272.703 299.69 + vertex 827.566 264.648 297.787 + endloop + endfacet + facet normal -0.475031 -0.10994 -0.873074 + outer loop + vertex 827.566 264.648 297.787 + vertex 822.204 272.703 299.69 + vertex 825.769 276.013 297.334 + endloop + endfacet + facet normal -0.356498 -0.0714944 -0.931557 + outer loop + vertex 819.685 258.403 301.898 + vertex 818.049 269.049 301.707 + vertex 823.574 262.418 300.102 + endloop + endfacet + facet normal -0.372425 -0.0865924 -0.924014 + outer loop + vertex 823.574 262.418 300.102 + vertex 818.049 269.049 301.707 + vertex 822.204 272.703 299.69 + endloop + endfacet + facet normal -0.262847 -0.0489014 -0.963598 + outer loop + vertex 815.172 253.774 303.364 + vertex 813.479 264.815 303.266 + vertex 819.685 258.403 301.898 + endloop + endfacet + facet normal -0.272696 -0.0591395 -0.960281 + outer loop + vertex 819.685 258.403 301.898 + vertex 813.479 264.815 303.266 + vertex 818.049 269.049 301.707 + endloop + endfacet + facet normal 0.553417 -0.00753401 -0.83287 + outer loop + vertex 703.606 193.796 292.894 + vertex 704.029 208.605 293.041 + vertex 705.956 194.059 294.452 + endloop + endfacet + facet normal 0.533544 -0.0114108 -0.845695 + outer loop + vertex 705.956 194.059 294.452 + vertex 704.029 208.605 293.041 + vertex 706.447 209.264 294.557 + endloop + endfacet + facet normal 0.671639 -0.00448882 -0.740865 + outer loop + vertex 702.77 194.16 292.133 + vertex 702.784 207.453 292.066 + vertex 703.606 193.796 292.894 + endloop + endfacet + facet normal 0.622266 -0.00999842 -0.782742 + outer loop + vertex 703.606 193.796 292.894 + vertex 702.784 207.453 292.066 + vertex 704.029 208.605 293.041 + endloop + endfacet + facet normal -0.625842 -0.133917 -0.768367 + outer loop + vertex 828.378 279.559 295.001 + vertex 826.311 289.991 294.867 + vertex 829.857 284.111 293.004 + endloop + endfacet + facet normal -0.629415 -0.137181 -0.764865 + outer loop + vertex 829.857 284.111 293.004 + vertex 826.311 289.991 294.867 + vertex 827.755 294.09 292.943 + endloop + endfacet + facet normal -0.565386 -0.120658 -0.815954 + outer loop + vertex 825.769 276.013 297.334 + vertex 823.823 286.612 297.114 + vertex 828.378 279.559 295.001 + endloop + endfacet + facet normal -0.568063 -0.123052 -0.813734 + outer loop + vertex 828.378 279.559 295.001 + vertex 823.823 286.612 297.114 + vertex 826.311 289.991 294.867 + endloop + endfacet + facet normal -0.481005 -0.101874 -0.870779 + outer loop + vertex 822.204 272.703 299.69 + vertex 820.365 283.218 299.476 + vertex 825.769 276.013 297.334 + endloop + endfacet + facet normal -0.486688 -0.10727 -0.866965 + outer loop + vertex 825.769 276.013 297.334 + vertex 820.365 283.218 299.476 + vertex 823.823 286.612 297.114 + endloop + endfacet + facet normal -0.379885 -0.076904 -0.921831 + outer loop + vertex 818.049 269.049 301.707 + vertex 816.22 279.539 301.586 + vertex 822.204 272.703 299.69 + endloop + endfacet + facet normal -0.389653 -0.0868335 -0.916859 + outer loop + vertex 822.204 272.703 299.69 + vertex 816.22 279.539 301.586 + vertex 820.365 283.218 299.476 + endloop + endfacet + facet normal -0.278389 -0.0525341 -0.959031 + outer loop + vertex 813.479 264.815 303.266 + vertex 811.583 275.529 303.229 + vertex 818.049 269.049 301.707 + endloop + endfacet + facet normal -0.286171 -0.0609548 -0.956238 + outer loop + vertex 818.049 269.049 301.707 + vertex 811.583 275.529 303.229 + vertex 816.22 279.539 301.586 + endloop + endfacet + facet normal 0.530587 0.00386762 -0.847622 + outer loop + vertex 704.029 208.605 293.041 + vertex 703.976 222.787 293.072 + vertex 706.447 209.264 294.557 + endloop + endfacet + facet normal 0.530574 0.00386429 -0.84763 + outer loop + vertex 706.447 209.264 294.557 + vertex 703.976 222.787 293.072 + vertex 706.321 223.646 294.544 + endloop + endfacet + facet normal 0.612819 0.00651315 -0.790196 + outer loop + vertex 702.784 207.453 292.066 + vertex 702.596 221.718 292.038 + vertex 704.029 208.605 293.041 + endloop + endfacet + facet normal 0.597937 0.00401958 -0.801533 + outer loop + vertex 704.029 208.605 293.041 + vertex 702.596 221.718 292.038 + vertex 703.976 222.787 293.072 + endloop + endfacet + facet normal -0.612517 -0.148538 -0.776376 + outer loop + vertex 826.311 289.991 294.867 + vertex 824.133 299.235 294.817 + vertex 827.755 294.09 292.943 + endloop + endfacet + facet normal -0.620171 -0.156742 -0.768648 + outer loop + vertex 827.755 294.09 292.943 + vertex 824.133 299.235 294.817 + vertex 825.457 302.454 293.092 + endloop + endfacet + facet normal -0.558667 -0.13322 -0.818623 + outer loop + vertex 823.823 286.612 297.114 + vertex 821.647 296.26 297.029 + vertex 826.311 289.991 294.867 + endloop + endfacet + facet normal -0.562203 -0.136897 -0.81559 + outer loop + vertex 826.311 289.991 294.867 + vertex 821.647 296.26 297.029 + vertex 824.133 299.235 294.817 + endloop + endfacet + facet normal -0.483183 -0.111807 -0.868351 + outer loop + vertex 820.365 283.218 299.476 + vertex 818.215 293.118 299.397 + vertex 823.823 286.612 297.114 + endloop + endfacet + facet normal -0.488599 -0.117822 -0.864517 + outer loop + vertex 823.823 286.612 297.114 + vertex 818.215 293.118 299.397 + vertex 821.647 296.26 297.029 + endloop + endfacet + facet normal -0.389211 -0.0874079 -0.916992 + outer loop + vertex 816.22 279.539 301.586 + vertex 814.053 289.6 301.547 + vertex 820.365 283.218 299.476 + endloop + endfacet + facet normal -0.393812 -0.0927685 -0.914498 + outer loop + vertex 820.365 283.218 299.476 + vertex 814.053 289.6 301.547 + vertex 818.215 293.118 299.397 + endloop + endfacet + facet normal -0.287122 -0.0597685 -0.956027 + outer loop + vertex 811.583 275.529 303.229 + vertex 809.413 285.796 303.239 + vertex 816.22 279.539 301.586 + endloop + endfacet + facet normal -0.293075 -0.066844 -0.95375 + outer loop + vertex 816.22 279.539 301.586 + vertex 809.413 285.796 303.239 + vertex 814.053 289.6 301.547 + endloop + endfacet + facet normal 0.529011 0.00972661 -0.848559 + outer loop + vertex 703.976 222.787 293.072 + vertex 703.686 236.206 293.045 + vertex 706.321 223.646 294.544 + endloop + endfacet + facet normal 0.538846 0.0125362 -0.842311 + outer loop + vertex 706.321 223.646 294.544 + vertex 703.686 236.206 293.045 + vertex 705.981 237.281 294.529 + endloop + endfacet + facet normal 0.594 0.0118505 -0.804378 + outer loop + vertex 702.596 221.718 292.038 + vertex 702.449 234.308 292.114 + vertex 703.976 222.787 293.072 + endloop + endfacet + facet normal 0.590321 0.0111372 -0.807092 + outer loop + vertex 703.976 222.787 293.072 + vertex 702.449 234.308 292.114 + vertex 703.686 236.206 293.045 + endloop + endfacet + facet normal -0.602243 -0.170177 -0.779963 + outer loop + vertex 824.133 299.235 294.817 + vertex 821.745 307.767 294.799 + vertex 825.457 302.454 293.092 + endloop + endfacet + facet normal -0.614214 -0.182464 -0.767755 + outer loop + vertex 825.457 302.454 293.092 + vertex 821.745 307.767 294.799 + vertex 823.288 310.537 292.906 + endloop + endfacet + facet normal -0.550663 -0.150588 -0.821032 + outer loop + vertex 821.647 296.26 297.029 + vertex 819.232 305.203 297.009 + vertex 824.133 299.235 294.817 + endloop + endfacet + facet normal -0.556672 -0.157494 -0.815667 + outer loop + vertex 824.133 299.235 294.817 + vertex 819.232 305.203 297.009 + vertex 821.745 307.767 294.799 + endloop + endfacet + facet normal -0.481249 -0.127876 -0.867206 + outer loop + vertex 818.215 293.118 299.397 + vertex 815.771 302.37 299.389 + vertex 821.647 296.26 297.029 + endloop + endfacet + facet normal -0.485391 -0.133054 -0.864113 + outer loop + vertex 821.647 296.26 297.029 + vertex 815.771 302.37 299.389 + vertex 819.232 305.203 297.009 + endloop + endfacet + facet normal -0.389258 -0.0989522 -0.915799 + outer loop + vertex 814.053 289.6 301.547 + vertex 811.599 299.133 301.559 + vertex 818.215 293.118 299.397 + endloop + endfacet + facet normal -0.393731 -0.104794 -0.913233 + outer loop + vertex 818.215 293.118 299.397 + vertex 811.599 299.133 301.559 + vertex 815.771 302.37 299.389 + endloop + endfacet + facet normal -0.290331 -0.070448 -0.95433 + outer loop + vertex 809.413 285.796 303.239 + vertex 806.954 295.599 303.263 + vertex 814.053 289.6 301.547 + endloop + endfacet + facet normal -0.293207 -0.074184 -0.953166 + outer loop + vertex 814.053 289.6 301.547 + vertex 806.954 295.599 303.263 + vertex 811.599 299.133 301.559 + endloop + endfacet + facet normal 0.539428 0.0108115 -0.841962 + outer loop + vertex 703.686 236.206 293.045 + vertex 703.394 249.351 293.027 + vertex 705.981 237.281 294.529 + endloop + endfacet + facet normal 0.55069 0.0141432 -0.83459 + outer loop + vertex 705.981 237.281 294.529 + vertex 703.394 249.351 293.027 + vertex 705.64 250.636 294.53 + endloop + endfacet + facet normal 0.591813 0.00963851 -0.806018 + outer loop + vertex 702.449 234.308 292.114 + vertex 702.102 246.89 292.01 + vertex 703.686 236.206 293.045 + endloop + endfacet + facet normal 0.603884 0.0123028 -0.796977 + outer loop + vertex 703.686 236.206 293.045 + vertex 702.102 246.89 292.01 + vertex 703.394 249.351 293.027 + endloop + endfacet + facet normal -0.603037 -0.192969 -0.774021 + outer loop + vertex 821.745 307.767 294.799 + vertex 819.074 316.062 294.812 + vertex 823.288 310.537 292.906 + endloop + endfacet + facet normal -0.608647 -0.199326 -0.767996 + outer loop + vertex 823.288 310.537 292.906 + vertex 819.074 316.062 294.812 + vertex 820.347 318.739 293.108 + endloop + endfacet + facet normal -0.547277 -0.170008 -0.819503 + outer loop + vertex 819.232 305.203 297.009 + vertex 816.558 313.774 297.017 + vertex 821.745 307.767 294.799 + endloop + endfacet + facet normal -0.552861 -0.176747 -0.814313 + outer loop + vertex 821.745 307.767 294.799 + vertex 816.558 313.774 297.017 + vertex 819.074 316.062 294.812 + endloop + endfacet + facet normal -0.478059 -0.143973 -0.866448 + outer loop + vertex 815.771 302.37 299.389 + vertex 813.076 311.235 299.403 + vertex 819.232 305.203 297.009 + endloop + endfacet + facet normal -0.482383 -0.149725 -0.863069 + outer loop + vertex 819.232 305.203 297.009 + vertex 813.076 311.235 299.403 + vertex 816.558 313.774 297.017 + endloop + endfacet + facet normal -0.388785 -0.112016 -0.914494 + outer loop + vertex 811.599 299.133 301.559 + vertex 808.901 308.296 301.584 + vertex 815.771 302.37 299.389 + endloop + endfacet + facet normal -0.393191 -0.118107 -0.91184 + outer loop + vertex 815.771 302.37 299.389 + vertex 808.901 308.296 301.584 + vertex 813.076 311.235 299.403 + endloop + endfacet + facet normal -0.290319 -0.0782505 -0.953725 + outer loop + vertex 806.954 295.599 303.263 + vertex 804.277 305.073 303.301 + vertex 811.599 299.133 301.559 + endloop + endfacet + facet normal -0.29471 -0.0842079 -0.951869 + outer loop + vertex 811.599 299.133 301.559 + vertex 804.277 305.073 303.301 + vertex 808.901 308.296 301.584 + endloop + endfacet + facet normal 0.553036 0.00831654 -0.833116 + outer loop + vertex 703.394 249.351 293.027 + vertex 703.214 262.739 293.041 + vertex 705.64 250.636 294.53 + endloop + endfacet + facet normal 0.564714 0.0116306 -0.825205 + outer loop + vertex 705.64 250.636 294.53 + vertex 703.214 262.739 293.041 + vertex 705.376 264.089 294.539 + endloop + endfacet + facet normal 0.609292 0.0077835 -0.792908 + outer loop + vertex 702.102 246.89 292.01 + vertex 702.031 259.488 292.079 + vertex 703.394 249.351 293.027 + endloop + endfacet + facet normal 0.615696 0.00910992 -0.787931 + outer loop + vertex 703.394 249.351 293.027 + vertex 702.031 259.488 292.079 + vertex 703.214 262.739 293.041 + endloop + endfacet + facet normal -0.596001 -0.209848 -0.775078 + outer loop + vertex 819.074 316.062 294.812 + vertex 816.182 324.195 294.834 + vertex 820.347 318.739 293.108 + endloop + endfacet + facet normal -0.608422 -0.22364 -0.761452 + outer loop + vertex 820.347 318.739 293.108 + vertex 816.182 324.195 294.834 + vertex 817.657 326.562 292.96 + endloop + endfacet + facet normal -0.54607 -0.186522 -0.816711 + outer loop + vertex 816.558 313.774 297.017 + vertex 813.674 322.157 297.03 + vertex 819.074 316.062 294.812 + endloop + endfacet + facet normal -0.552288 -0.194212 -0.810715 + outer loop + vertex 819.074 316.062 294.812 + vertex 813.674 322.157 297.03 + vertex 816.182 324.195 294.834 + endloop + endfacet + facet normal -0.477587 -0.157509 -0.864351 + outer loop + vertex 813.076 311.235 299.403 + vertex 810.188 319.908 299.419 + vertex 816.558 313.774 297.017 + endloop + endfacet + facet normal -0.482909 -0.164724 -0.860038 + outer loop + vertex 816.558 313.774 297.017 + vertex 810.188 319.908 299.419 + vertex 813.674 322.157 297.03 + endloop + endfacet + facet normal -0.389723 -0.123598 -0.9126 + outer loop + vertex 808.901 308.296 301.584 + vertex 806.011 317.269 301.603 + vertex 813.076 311.235 299.403 + endloop + endfacet + facet normal -0.394004 -0.129586 -0.909928 + outer loop + vertex 813.076 311.235 299.403 + vertex 806.011 317.269 301.603 + vertex 810.188 319.908 299.419 + endloop + endfacet + facet normal -0.291532 -0.0890514 -0.952407 + outer loop + vertex 804.277 305.073 303.301 + vertex 801.403 314.363 303.312 + vertex 808.901 308.296 301.584 + endloop + endfacet + facet normal -0.294276 -0.0927839 -0.951206 + outer loop + vertex 808.901 308.296 301.584 + vertex 801.403 314.363 303.312 + vertex 806.011 317.269 301.603 + endloop + endfacet + facet normal 0.567668 0.00472138 -0.823244 + outer loop + vertex 703.214 262.739 293.041 + vertex 703.143 276.614 293.071 + vertex 705.376 264.089 294.539 + endloop + endfacet + facet normal 0.579388 0.00777533 -0.815015 + outer loop + vertex 705.376 264.089 294.539 + vertex 703.143 276.614 293.071 + vertex 705.222 277.715 294.56 + endloop + endfacet + facet normal 0.627574 0.00201246 -0.778554 + outer loop + vertex 702.031 259.488 292.079 + vertex 701.929 273.295 292.033 + vertex 703.214 262.739 293.041 + endloop + endfacet + facet normal 0.642394 0.00498161 -0.766358 + outer loop + vertex 703.214 262.739 293.041 + vertex 701.929 273.295 292.033 + vertex 703.143 276.614 293.071 + endloop + endfacet + facet normal -0.603534 -0.228598 -0.763865 + outer loop + vertex 816.182 324.195 294.834 + vertex 813.151 332.172 294.842 + vertex 817.657 326.562 292.96 + endloop + endfacet + facet normal -0.610662 -0.237109 -0.75556 + outer loop + vertex 817.657 326.562 292.96 + vertex 813.151 332.172 294.842 + vertex 814.354 334.525 293.13 + endloop + endfacet + facet normal -0.547655 -0.201408 -0.812101 + outer loop + vertex 813.674 322.157 297.03 + vertex 810.632 330.376 297.043 + vertex 816.182 324.195 294.834 + endloop + endfacet + facet normal -0.554412 -0.209891 -0.805341 + outer loop + vertex 816.182 324.195 294.834 + vertex 810.632 330.376 297.043 + vertex 813.151 332.172 294.842 + endloop + endfacet + facet normal -0.479388 -0.170977 -0.860787 + outer loop + vertex 810.188 319.908 299.419 + vertex 807.141 328.423 299.424 + vertex 813.674 322.157 297.03 + endloop + endfacet + facet normal -0.48452 -0.177971 -0.856485 + outer loop + vertex 813.674 322.157 297.03 + vertex 807.141 328.423 299.424 + vertex 810.632 330.376 297.043 + endloop + endfacet + facet normal -0.391854 -0.13331 -0.910318 + outer loop + vertex 806.011 317.269 301.603 + vertex 802.985 326.111 301.611 + vertex 810.188 319.908 299.419 + endloop + endfacet + facet normal -0.397983 -0.141826 -0.906363 + outer loop + vertex 810.188 319.908 299.419 + vertex 802.985 326.111 301.611 + vertex 807.141 328.423 299.424 + endloop + endfacet + facet normal -0.292786 -0.0952732 -0.95142 + outer loop + vertex 801.403 314.363 303.312 + vertex 798.402 323.54 303.317 + vertex 806.011 317.269 301.603 + endloop + endfacet + facet normal -0.296907 -0.100779 -0.949574 + outer loop + vertex 806.011 317.269 301.603 + vertex 798.402 323.54 303.317 + vertex 802.985 326.111 301.611 + endloop + endfacet + facet normal 0.581371 0.00215963 -0.813635 + outer loop + vertex 703.143 276.614 293.071 + vertex 703.113 290.657 293.087 + vertex 705.222 277.715 294.56 + endloop + endfacet + facet normal 0.595988 0.0057552 -0.802973 + outer loop + vertex 705.222 277.715 294.56 + vertex 703.113 290.657 293.087 + vertex 705.104 291.349 294.57 + endloop + endfacet + facet normal 0.650409 -6.80091e-05 -0.759584 + outer loop + vertex 701.929 273.295 292.033 + vertex 701.988 288.203 292.082 + vertex 703.143 276.614 293.071 + endloop + endfacet + facet normal 0.663781 0.0022596 -0.747924 + outer loop + vertex 703.143 276.614 293.071 + vertex 701.988 288.203 292.082 + vertex 703.113 290.657 293.087 + endloop + endfacet + facet normal -0.603351 -0.24361 -0.759356 + outer loop + vertex 813.151 332.172 294.842 + vertex 810.014 339.974 294.831 + vertex 814.354 334.525 293.13 + endloop + endfacet + facet normal -0.617411 -0.260102 -0.742395 + outer loop + vertex 814.354 334.525 293.13 + vertex 810.014 339.974 294.831 + vertex 811.403 342.095 292.933 + endloop + endfacet + facet normal -0.551422 -0.21496 -0.806056 + outer loop + vertex 810.632 330.376 297.043 + vertex 807.505 338.393 297.045 + vertex 813.151 332.172 294.842 + endloop + endfacet + facet normal -0.560359 -0.226381 -0.796712 + outer loop + vertex 813.151 332.172 294.842 + vertex 807.505 338.393 297.045 + vertex 810.014 339.974 294.831 + endloop + endfacet + facet normal -0.483061 -0.180849 -0.856706 + outer loop + vertex 807.141 328.423 299.424 + vertex 804.013 336.745 299.432 + vertex 810.632 330.376 297.043 + endloop + endfacet + facet normal -0.490688 -0.19126 -0.850085 + outer loop + vertex 810.632 330.376 297.043 + vertex 804.013 336.745 299.432 + vertex 807.505 338.393 297.045 + endloop + endfacet + facet normal -0.39764 -0.142487 -0.90641 + outer loop + vertex 802.985 326.111 301.611 + vertex 799.869 334.779 301.615 + vertex 807.141 328.423 299.424 + endloop + endfacet + facet normal -0.403856 -0.151028 -0.90227 + outer loop + vertex 807.141 328.423 299.424 + vertex 799.869 334.779 301.615 + vertex 804.013 336.745 299.432 + endloop + endfacet + facet normal -0.296478 -0.101575 -0.949623 + outer loop + vertex 798.402 323.54 303.317 + vertex 795.314 332.567 303.315 + vertex 802.985 326.111 301.611 + endloop + endfacet + facet normal -0.301241 -0.107812 -0.947434 + outer loop + vertex 802.985 326.111 301.611 + vertex 795.314 332.567 303.315 + vertex 799.869 334.779 301.615 + endloop + endfacet + facet normal 0.597293 -3.18251e-05 -0.802023 + outer loop + vertex 703.113 290.657 293.087 + vertex 703.106 304.279 293.082 + vertex 705.104 291.349 294.57 + endloop + endfacet + facet normal 0.615953 0.00449173 -0.78777 + outer loop + vertex 705.104 291.349 294.57 + vertex 703.106 304.279 293.082 + vertex 704.985 304.88 294.554 + endloop + endfacet + facet normal 0.669646 -0.00257868 -0.742676 + outer loop + vertex 701.988 288.203 292.082 + vertex 702.001 302.826 292.042 + vertex 703.113 290.657 293.087 + endloop + endfacet + facet normal 0.685036 4.4517e-05 -0.728509 + outer loop + vertex 703.113 290.657 293.087 + vertex 702.001 302.826 292.042 + vertex 703.106 304.279 293.082 + endloop + endfacet + facet normal -0.615771 -0.261846 -0.743144 + outer loop + vertex 810.014 339.974 294.831 + vertex 806.828 347.56 294.798 + vertex 811.403 342.095 292.933 + endloop + endfacet + facet normal -0.623974 -0.272365 -0.732444 + outer loop + vertex 811.403 342.095 292.933 + vertex 806.828 347.56 294.798 + vertex 807.91 349.688 293.085 + endloop + endfacet + facet normal -0.558736 -0.229359 -0.797 + outer loop + vertex 807.505 338.393 297.045 + vertex 804.329 346.193 297.027 + vertex 810.014 339.974 294.831 + endloop + endfacet + facet normal -0.568615 -0.242229 -0.786131 + outer loop + vertex 810.014 339.974 294.831 + vertex 804.329 346.193 297.027 + vertex 806.828 347.56 294.798 + endloop + endfacet + facet normal -0.490308 -0.192107 -0.850114 + outer loop + vertex 804.013 336.745 299.432 + vertex 800.84 344.849 299.43 + vertex 807.505 338.393 297.045 + endloop + endfacet + facet normal -0.500194 -0.205626 -0.841144 + outer loop + vertex 807.505 338.393 297.045 + vertex 800.84 344.849 299.43 + vertex 804.329 346.193 297.027 + endloop + endfacet + facet normal -0.403884 -0.150966 -0.902267 + outer loop + vertex 799.869 334.779 301.615 + vertex 796.696 343.241 301.62 + vertex 804.013 336.745 299.432 + endloop + endfacet + facet normal -0.411455 -0.16125 -0.897053 + outer loop + vertex 804.013 336.745 299.432 + vertex 796.696 343.241 301.62 + vertex 800.84 344.849 299.43 + endloop + endfacet + facet normal -0.301717 -0.106803 -0.947396 + outer loop + vertex 795.314 332.567 303.315 + vertex 792.173 341.403 303.32 + vertex 799.869 334.779 301.615 + endloop + endfacet + facet normal -0.308134 -0.11504 -0.944362 + outer loop + vertex 799.869 334.779 301.615 + vertex 792.173 341.403 303.32 + vertex 796.696 343.241 301.62 + endloop + endfacet + facet normal 0.617196 -0.0017527 -0.786807 + outer loop + vertex 703.106 304.279 293.082 + vertex 703.085 317.601 293.036 + vertex 704.985 304.88 294.554 + endloop + endfacet + facet normal 0.635157 0.00265201 -0.772378 + outer loop + vertex 704.985 304.88 294.554 + vertex 703.085 317.601 293.036 + vertex 704.889 318.329 294.522 + endloop + endfacet + facet normal 0.687278 -0.00317769 -0.726388 + outer loop + vertex 702.001 302.826 292.042 + vertex 702.081 315.809 292.062 + vertex 703.106 304.279 293.082 + endloop + endfacet + facet normal 0.697605 -0.00138361 -0.716481 + outer loop + vertex 703.106 304.279 293.082 + vertex 702.081 315.809 292.062 + vertex 703.085 317.601 293.036 + endloop + endfacet + facet normal -0.622322 -0.273881 -0.733284 + outer loop + vertex 806.828 347.56 294.798 + vertex 803.62 354.91 294.775 + vertex 807.91 349.688 293.085 + endloop + endfacet + facet normal -0.633306 -0.287711 -0.718433 + outer loop + vertex 807.91 349.688 293.085 + vertex 803.62 354.91 294.775 + vertex 804.866 356.444 293.062 + endloop + endfacet + facet normal -0.569071 -0.241315 -0.786082 + outer loop + vertex 804.329 346.193 297.027 + vertex 801.15 353.816 296.987 + vertex 806.828 347.56 294.798 + endloop + endfacet + facet normal -0.579858 -0.255464 -0.773629 + outer loop + vertex 806.828 347.56 294.798 + vertex 801.15 353.816 296.987 + vertex 803.62 354.91 294.775 + endloop + endfacet + facet normal -0.501033 -0.203486 -0.841166 + outer loop + vertex 800.84 344.849 299.43 + vertex 797.646 352.786 299.412 + vertex 804.329 346.193 297.027 + endloop + endfacet + facet normal -0.511353 -0.217481 -0.831397 + outer loop + vertex 804.329 346.193 297.027 + vertex 797.646 352.786 299.412 + vertex 801.15 353.816 296.987 + endloop + endfacet + facet normal -0.412554 -0.158418 -0.897052 + outer loop + vertex 796.696 343.241 301.62 + vertex 793.502 351.542 301.623 + vertex 800.84 344.849 299.43 + endloop + endfacet + facet normal -0.422869 -0.172141 -0.889691 + outer loop + vertex 800.84 344.849 299.43 + vertex 793.502 351.542 301.623 + vertex 797.646 352.786 299.412 + endloop + endfacet + facet normal -0.309317 -0.112099 -0.944329 + outer loop + vertex 792.173 341.403 303.32 + vertex 788.996 350.089 303.329 + vertex 796.696 343.241 301.62 + endloop + endfacet + facet normal -0.316951 -0.12161 -0.940613 + outer loop + vertex 796.696 343.241 301.62 + vertex 788.996 350.089 303.329 + vertex 793.502 351.542 301.623 + endloop + endfacet + facet normal 0.63653 -0.00306172 -0.771246 + outer loop + vertex 703.085 317.601 293.036 + vertex 703.094 330.941 292.99 + vertex 704.889 318.329 294.522 + endloop + endfacet + facet normal 0.656933 0.00194283 -0.753946 + outer loop + vertex 704.889 318.329 294.522 + vertex 703.094 330.941 292.99 + vertex 704.812 331.771 294.489 + endloop + endfacet + facet normal 0.701676 -0.00584389 -0.712473 + outer loop + vertex 702.081 315.809 292.062 + vertex 702.081 329.305 291.951 + vertex 703.085 317.601 293.036 + endloop + endfacet + facet normal 0.718333 -0.00285941 -0.695694 + outer loop + vertex 703.085 317.601 293.036 + vertex 702.081 329.305 291.951 + vertex 703.094 330.941 292.99 + endloop + endfacet + facet normal -0.637263 -0.282777 -0.716892 + outer loop + vertex 803.62 354.91 294.775 + vertex 800.385 362.212 294.771 + vertex 804.866 356.444 293.062 + endloop + endfacet + facet normal -0.648765 -0.296463 -0.700867 + outer loop + vertex 804.866 356.444 293.062 + vertex 800.385 362.212 294.771 + vertex 801.718 363.697 292.908 + endloop + endfacet + facet normal -0.581927 -0.250763 -0.773614 + outer loop + vertex 801.15 353.816 296.987 + vertex 797.919 361.383 296.966 + vertex 803.62 354.91 294.775 + endloop + endfacet + facet normal -0.590873 -0.26225 -0.762951 + outer loop + vertex 803.62 354.91 294.775 + vertex 797.919 361.383 296.966 + vertex 800.385 362.212 294.771 + endloop + endfacet + facet normal -0.513104 -0.212197 -0.831683 + outer loop + vertex 797.646 352.786 299.412 + vertex 794.446 360.663 299.377 + vertex 801.15 353.816 296.987 + endloop + endfacet + facet normal -0.523528 -0.22596 -0.821499 + outer loop + vertex 801.15 353.816 296.987 + vertex 794.446 360.663 299.377 + vertex 797.919 361.383 296.966 + endloop + endfacet + facet normal -0.424842 -0.165978 -0.889922 + outer loop + vertex 793.502 351.542 301.623 + vertex 790.304 359.785 301.612 + vertex 797.646 352.786 299.412 + endloop + endfacet + facet normal -0.436931 -0.181464 -0.881001 + outer loop + vertex 797.646 352.786 299.412 + vertex 790.304 359.785 301.612 + vertex 794.446 360.663 299.377 + endloop + endfacet + facet normal -0.318668 -0.116382 -0.940695 + outer loop + vertex 788.996 350.089 303.329 + vertex 785.802 358.73 303.342 + vertex 793.502 351.542 301.623 + endloop + endfacet + facet normal -0.329211 -0.128939 -0.935412 + outer loop + vertex 793.502 351.542 301.623 + vertex 785.802 358.73 303.342 + vertex 790.304 359.785 301.612 + endloop + endfacet + facet normal 0.658088 -0.00226869 -0.752938 + outer loop + vertex 703.094 330.941 292.99 + vertex 703.163 344.361 293.01 + vertex 704.812 331.771 294.489 + endloop + endfacet + facet normal 0.679686 0.00284424 -0.733498 + outer loop + vertex 704.812 331.771 294.489 + vertex 703.163 344.361 293.01 + vertex 704.771 345.239 294.503 + endloop + endfacet + facet normal 0.720086 -0.00510676 -0.693866 + outer loop + vertex 702.081 329.305 291.951 + vertex 702.236 342.492 292.015 + vertex 703.094 330.941 292.99 + endloop + endfacet + facet normal 0.734345 -0.00277347 -0.67877 + outer loop + vertex 703.094 330.941 292.99 + vertex 702.236 342.492 292.015 + vertex 703.163 344.361 293.01 + endloop + endfacet + facet normal -0.65899 -0.282528 -0.697072 + outer loop + vertex 800.385 362.212 294.771 + vertex 796.995 369.687 294.946 + vertex 801.718 363.697 292.908 + endloop + endfacet + facet normal -0.663036 -0.28776 -0.69107 + outer loop + vertex 801.718 363.697 292.908 + vertex 796.995 369.687 294.946 + vertex 798.147 371.015 293.287 + endloop + endfacet + facet normal -0.596071 -0.248373 -0.763552 + outer loop + vertex 797.919 361.383 296.966 + vertex 794.618 369.029 297.056 + vertex 800.385 362.212 294.771 + endloop + endfacet + facet normal -0.601383 -0.255004 -0.757174 + outer loop + vertex 800.385 362.212 294.771 + vertex 794.618 369.029 297.056 + vertex 796.995 369.687 294.946 + endloop + endfacet + facet normal -0.527027 -0.213101 -0.822697 + outer loop + vertex 794.446 360.663 299.377 + vertex 791.218 368.592 299.391 + vertex 797.919 361.383 296.966 + endloop + endfacet + facet normal -0.532871 -0.220459 -0.816974 + outer loop + vertex 797.919 361.383 296.966 + vertex 791.218 368.592 299.391 + vertex 794.618 369.029 297.056 + endloop + endfacet + facet normal -0.439693 -0.170499 -0.881816 + outer loop + vertex 790.304 359.785 301.612 + vertex 787.123 368.074 301.595 + vertex 794.446 360.663 299.377 + endloop + endfacet + facet normal -0.44834 -0.180978 -0.87535 + outer loop + vertex 794.446 360.663 299.377 + vertex 787.123 368.074 301.595 + vertex 791.218 368.592 299.391 + endloop + endfacet + facet normal -0.331526 -0.11973 -0.935818 + outer loop + vertex 785.802 358.73 303.342 + vertex 782.632 367.419 303.353 + vertex 790.304 359.785 301.612 + endloop + endfacet + facet normal -0.344198 -0.133953 -0.929292 + outer loop + vertex 790.304 359.785 301.612 + vertex 782.632 367.419 303.353 + vertex 787.123 368.074 301.595 + endloop + endfacet + facet normal 0.680616 -0.000316033 -0.73264 + outer loop + vertex 703.163 344.361 293.01 + vertex 703.276 358.044 293.109 + vertex 704.771 345.239 294.503 + endloop + endfacet + facet normal 0.696965 0.00328336 -0.717098 + outer loop + vertex 704.771 345.239 294.503 + vertex 703.276 358.044 293.109 + vertex 704.796 358.786 294.59 + endloop + endfacet + facet normal 0.736158 -0.00472557 -0.676793 + outer loop + vertex 702.236 342.492 292.015 + vertex 702.374 355.855 292.072 + vertex 703.163 344.361 293.01 + endloop + endfacet + facet normal 0.756256 -0.00150651 -0.654274 + outer loop + vertex 703.163 344.361 293.01 + vertex 702.374 355.855 292.072 + vertex 703.276 358.044 293.109 + endloop + endfacet + facet normal -0.682277 -0.260922 -0.682947 + outer loop + vertex 796.995 369.687 294.946 + vertex 793.907 377.108 295.196 + vertex 798.147 371.015 293.287 + endloop + endfacet + facet normal -0.706424 -0.289316 -0.645957 + outer loop + vertex 798.147 371.015 293.287 + vertex 793.907 377.108 295.196 + vertex 795.644 376.905 293.386 + endloop + endfacet + facet normal -0.612297 -0.221414 -0.758991 + outer loop + vertex 794.618 369.029 297.056 + vertex 791.399 376.857 297.369 + vertex 796.995 369.687 294.946 + endloop + endfacet + facet normal -0.623122 -0.23417 -0.746246 + outer loop + vertex 796.995 369.687 294.946 + vertex 791.399 376.857 297.369 + vertex 793.907 377.108 295.196 + endloop + endfacet + facet normal -0.539724 -0.18728 -0.820746 + outer loop + vertex 791.218 368.592 299.391 + vertex 788.071 376.675 299.616 + vertex 794.618 369.029 297.056 + endloop + endfacet + facet normal -0.542259 -0.190239 -0.818391 + outer loop + vertex 794.618 369.029 297.056 + vertex 788.071 376.675 299.616 + vertex 791.399 376.857 297.369 + endloop + endfacet + facet normal -0.453454 -0.152474 -0.878141 + outer loop + vertex 787.123 368.074 301.595 + vertex 784.087 376.498 301.701 + vertex 791.218 368.592 299.391 + endloop + endfacet + facet normal -0.452919 -0.151881 -0.87852 + outer loop + vertex 791.218 368.592 299.391 + vertex 784.087 376.498 301.701 + vertex 788.071 376.675 299.616 + endloop + endfacet + facet normal -0.348068 -0.111482 -0.930817 + outer loop + vertex 782.632 367.419 303.353 + vertex 779.639 376.24 303.416 + vertex 787.123 368.074 301.595 + endloop + endfacet + facet normal -0.35161 -0.115124 -0.929041 + outer loop + vertex 787.123 368.074 301.595 + vertex 779.639 376.24 303.416 + vertex 784.087 376.498 301.701 + endloop + endfacet + facet normal 0.700211 -0.00981316 -0.713868 + outer loop + vertex 703.276 358.044 293.109 + vertex 703.544 372.199 293.177 + vertex 704.796 358.786 294.59 + endloop + endfacet + facet normal 0.721265 -0.00561225 -0.692636 + outer loop + vertex 704.796 358.786 294.59 + vertex 703.544 372.199 293.177 + vertex 704.959 372.526 294.648 + endloop + endfacet + facet normal 0.762682 -0.00772951 -0.646728 + outer loop + vertex 702.374 355.855 292.072 + vertex 702.616 370.124 292.186 + vertex 703.276 358.044 293.109 + endloop + endfacet + facet normal 0.74108 -0.0107918 -0.67133 + outer loop + vertex 703.276 358.044 293.109 + vertex 702.616 370.124 292.186 + vertex 703.544 372.199 293.177 + endloop + endfacet + facet normal -0.552735 -0.103715 -0.826878 + outer loop + vertex 788.071 376.675 299.616 + vertex 785.521 385.03 300.273 + vertex 791.399 376.857 297.369 + endloop + endfacet + facet normal -0.577635 -0.129032 -0.806033 + outer loop + vertex 791.399 376.857 297.369 + vertex 785.521 385.03 300.273 + vertex 789.072 384.933 297.743 + endloop + endfacet + facet normal -0.459861 -0.0723699 -0.885037 + outer loop + vertex 784.087 376.498 301.701 + vertex 781.619 385.131 302.277 + vertex 788.071 376.675 299.616 + endloop + endfacet + facet normal -0.457218 -0.0698591 -0.886606 + outer loop + vertex 788.071 376.675 299.616 + vertex 781.619 385.131 302.277 + vertex 785.521 385.03 300.273 + endloop + endfacet + facet normal -0.356986 -0.0477993 -0.932886 + outer loop + vertex 779.639 376.24 303.416 + vertex 777.328 385.236 303.839 + vertex 784.087 376.498 301.701 + endloop + endfacet + facet normal -0.342661 -0.0352748 -0.938797 + outer loop + vertex 784.087 376.498 301.701 + vertex 777.328 385.236 303.839 + vertex 781.619 385.131 302.277 + endloop + endfacet + facet normal 0.72503 -0.046642 -0.687136 + outer loop + vertex 703.544 372.199 293.177 + vertex 703.778 386.654 292.443 + vertex 704.959 372.526 294.648 + endloop + endfacet + facet normal 0.818358 -0.0212263 -0.574316 + outer loop + vertex 704.959 372.526 294.648 + vertex 703.778 386.654 292.443 + vertex 705.335 386.645 294.662 + endloop + endfacet + facet normal 0.775558 -0.0461608 -0.629586 + outer loop + vertex 702.616 370.124 292.186 + vertex 703.672 386.655 292.275 + vertex 703.544 372.199 293.177 + endloop + endfacet + facet normal 0.844732 -0.04078 -0.533634 + outer loop + vertex 703.544 372.199 293.177 + vertex 703.672 386.655 292.275 + vertex 703.778 386.654 292.443 + endloop + endfacet + facet normal 0.176259 -0.525256 -0.832489 + outer loop + vertex 846.47 242.81 295.937 + vertex 848.339 242.413 296.583 + vertex 846.805 242.562 296.164 + endloop + endfacet + facet normal 0.0655149 -0.564747 -0.822659 + outer loop + vertex 844.958 243.361 295.438 + vertex 846.47 242.81 295.937 + vertex 845.489 243.087 295.668 + endloop + endfacet + facet normal -0.021734 -0.514248 -0.857366 + outer loop + vertex 843.478 244.257 294.938 + vertex 844.958 243.361 295.438 + vertex 844 243.836 295.177 + endloop + endfacet + facet normal -0.0367122 -0.394333 -0.918234 + outer loop + vertex 842.086 245.523 294.45 + vertex 843.478 244.257 294.938 + vertex 842.575 244.933 294.684 + endloop + endfacet + facet normal -0.0660268 -0.325773 -0.94314 + outer loop + vertex 840.829 247.067 294.005 + vertex 842.086 245.523 294.45 + vertex 841.285 246.367 294.214 + endloop + endfacet + facet normal 0.039902 -0.190163 -0.980941 + outer loop + vertex 839.743 248.777 293.629 + vertex 840.829 247.067 294.005 + vertex 840.22 247.886 293.821 + endloop + endfacet + facet normal -0.398977 -0.31016 -0.862913 + outer loop + vertex 838.56 251.455 293.214 + vertex 839.743 248.777 293.629 + vertex 839.312 249.539 293.555 + endloop + endfacet + facet normal -0.617799 -0.309692 -0.722783 + outer loop + vertex 836.974 255.767 292.721 + vertex 838.56 251.455 293.214 + vertex 837.577 253.454 293.197 + endloop + endfacet + facet normal -0.788709 -0.292559 -0.540691 + outer loop + vertex 835.811 259.508 292.394 + vertex 836.974 255.767 292.721 + vertex 835.968 258.507 292.707 + endloop + endfacet + facet normal -0.787752 -0.221348 -0.57485 + outer loop + vertex 835.199 262.269 292.17 + vertex 835.811 259.508 292.394 + vertex 835.145 261.907 292.383 + endloop + endfacet + facet normal -0.834698 -0.181838 -0.519822 + outer loop + vertex 834.329 266.491 292.09 + vertex 835.199 262.269 292.17 + vertex 835.145 261.907 292.383 + endloop + endfacet + facet normal -0.729811 -0.1569 -0.6654 + outer loop + vertex 833.468 271.309 291.899 + vertex 834.329 266.491 292.09 + vertex 832.27 272.12 293.021 + endloop + endfacet + facet normal -0.727091 -0.145075 -0.671038 + outer loop + vertex 832.921 275.117 291.668 + vertex 833.468 271.309 291.899 + vertex 832.27 272.12 293.021 + endloop + endfacet + facet normal -0.738425 -0.137686 -0.660129 + outer loop + vertex 831.833 279.308 292.01 + vertex 832.921 275.117 291.668 + vertex 832.27 272.12 293.021 + endloop + endfacet + facet normal -0.704875 -0.146504 -0.694038 + outer loop + vertex 831.133 284.839 291.553 + vertex 831.833 279.308 292.01 + vertex 829.857 284.111 293.004 + endloop + endfacet + facet normal -0.705062 -0.146006 -0.693952 + outer loop + vertex 829.812 290.581 291.688 + vertex 831.133 284.839 291.553 + vertex 829.857 284.111 293.004 + endloop + endfacet + facet normal -0.68358 -0.14474 -0.71538 + outer loop + vertex 828.825 295.009 291.735 + vertex 829.812 290.581 291.688 + vertex 827.755 294.09 292.943 + endloop + endfacet + facet normal -0.667937 -0.173821 -0.723634 + outer loop + vertex 827.591 299.755 291.734 + vertex 828.825 295.009 291.735 + vertex 827.755 294.09 292.943 + endloop + endfacet + facet normal -0.679687 -0.179614 -0.711171 + outer loop + vertex 825.918 305.42 291.903 + vertex 827.591 299.755 291.734 + vertex 825.457 302.454 293.092 + endloop + endfacet + facet normal -0.680881 -0.212445 -0.700906 + outer loop + vertex 824.908 310.209 291.432 + vertex 825.918 305.42 291.903 + vertex 823.288 310.537 292.906 + endloop + endfacet + facet normal -0.680531 -0.220819 -0.698654 + outer loop + vertex 822.795 315.971 291.669 + vertex 824.908 310.209 291.432 + vertex 823.288 310.537 292.906 + endloop + endfacet + facet normal -0.671089 -0.22641 -0.705959 + outer loop + vertex 820.645 321.484 291.944 + vertex 822.795 315.971 291.669 + vertex 820.347 318.739 293.108 + endloop + endfacet + facet normal -0.67493 -0.258979 -0.690941 + outer loop + vertex 819.337 326.094 291.494 + vertex 820.645 321.484 291.944 + vertex 817.657 326.562 292.96 + endloop + endfacet + facet normal -0.674831 -0.262559 -0.689685 + outer loop + vertex 816.928 331.691 291.721 + vertex 819.337 326.094 291.494 + vertex 817.657 326.562 292.96 + endloop + endfacet + facet normal -0.672868 -0.268121 -0.689464 + outer loop + vertex 814.52 337.135 291.954 + vertex 816.928 331.691 291.721 + vertex 814.354 334.525 293.13 + endloop + endfacet + facet normal -0.684358 -0.298794 -0.665114 + outer loop + vertex 813.004 341.678 291.472 + vertex 814.52 337.135 291.954 + vertex 811.403 342.095 292.933 + endloop + endfacet + facet normal -0.684109 -0.301967 -0.663936 + outer loop + vertex 810.37 347.212 291.669 + vertex 813.004 341.678 291.472 + vertex 811.403 342.095 292.933 + endloop + endfacet + facet normal -0.686827 -0.305494 -0.659501 + outer loop + vertex 807.73 352.568 291.939 + vertex 810.37 347.212 291.669 + vertex 807.91 349.688 293.085 + endloop + endfacet + facet normal -0.694074 -0.32675 -0.641479 + outer loop + vertex 805.348 358.244 291.624 + vertex 807.73 352.568 291.939 + vertex 804.866 356.444 293.062 + endloop + endfacet + facet normal -0.720106 -0.336427 -0.606848 + outer loop + vertex 802.971 363.748 291.394 + vertex 805.348 358.244 291.624 + vertex 801.718 363.697 292.908 + endloop + endfacet + facet normal -0.723798 -0.32351 -0.609474 + outer loop + vertex 800.721 367.764 291.934 + vertex 802.971 363.748 291.394 + vertex 801.718 363.697 292.908 + endloop + endfacet + facet normal -0.730832 -0.329828 -0.597577 + outer loop + vertex 798.366 373.204 291.811 + vertex 800.721 367.764 291.934 + vertex 798.147 371.015 293.287 + endloop + endfacet + facet normal -0.755557 -0.310069 -0.577054 + outer loop + vertex 795.662 379.876 291.767 + vertex 798.366 373.204 291.811 + vertex 795.644 376.905 293.386 + endloop + endfacet + facet normal -0.777231 -0.196354 -0.597793 + outer loop + vertex 794.163 384.78 292.105 + vertex 795.662 379.876 291.767 + vertex 792.003 384.848 294.891 + endloop + endfacet + facet normal 0.846531 -0.0731332 -0.527293 + outer loop + vertex 702.301 378.618 291.189 + vertex 703.566 386.655 292.105 + vertex 703.672 386.655 292.275 + endloop + endfacet + facet normal 0.688839 -0.0592736 -0.722487 + outer loop + vertex 702.213 372.174 291.634 + vertex 702.301 378.618 291.189 + vertex 702.616 370.124 292.186 + endloop + endfacet + facet normal 0.775723 -0.0175498 -0.630829 + outer loop + vertex 702.251 369.534 291.754 + vertex 702.213 372.174 291.634 + vertex 702.616 370.124 292.186 + endloop + endfacet + facet normal 0.767978 -0.00571659 -0.64045 + outer loop + vertex 702.232 365.181 291.77 + vertex 702.251 369.534 291.754 + vertex 702.616 370.124 292.186 + endloop + endfacet + facet normal 0.83333 -0.00517415 -0.552752 + outer loop + vertex 701.974 359.37 291.436 + vertex 702.232 365.181 291.77 + vertex 702.374 355.855 292.072 + endloop + endfacet + facet normal 0.820348 -0.0100925 -0.571775 + outer loop + vertex 701.951 354.374 291.491 + vertex 701.974 359.37 291.436 + vertex 702.374 355.855 292.072 + endloop + endfacet + facet normal 0.817508 -0.00767809 -0.575865 + outer loop + vertex 701.955 350.149 291.553 + vertex 701.951 354.374 291.491 + vertex 702.374 355.855 292.072 + endloop + endfacet + facet normal 0.804072 -0.00635372 -0.594498 + outer loop + vertex 701.829 345.872 291.427 + vertex 701.955 350.149 291.553 + vertex 702.236 342.492 292.015 + endloop + endfacet + facet normal 0.800272 -0.00769724 -0.599587 + outer loop + vertex 701.707 339.177 291.352 + vertex 701.829 345.872 291.427 + vertex 702.236 342.492 292.015 + endloop + endfacet + facet normal 0.779278 -0.00854694 -0.62662 + outer loop + vertex 701.647 332.857 291.362 + vertex 701.707 339.177 291.352 + vertex 702.081 329.305 291.951 + endloop + endfacet + facet normal 0.787121 -0.00595745 -0.61677 + outer loop + vertex 701.616 329.809 291.352 + vertex 701.647 332.857 291.362 + vertex 702.081 329.305 291.951 + endloop + endfacet + facet normal 0.787474 -0.00510575 -0.616327 + outer loop + vertex 701.547 323.811 291.314 + vertex 701.616 329.809 291.352 + vertex 702.081 329.305 291.951 + endloop + endfacet + facet normal 0.778754 -0.00661967 -0.627294 + outer loop + vertex 701.551 317.435 291.386 + vertex 701.547 323.811 291.314 + vertex 702.081 315.809 292.062 + endloop + endfacet + facet normal 0.779879 -0.00567521 -0.625905 + outer loop + vertex 701.601 312.357 291.495 + vertex 701.551 317.435 291.386 + vertex 702.081 315.809 292.062 + endloop + endfacet + facet normal 0.788591 -0.00226093 -0.614913 + outer loop + vertex 701.364 307.164 291.209 + vertex 701.601 312.357 291.495 + vertex 702.001 302.826 292.042 + endloop + endfacet + facet normal 0.774244 -0.0078092 -0.632839 + outer loop + vertex 701.466 302.283 291.394 + vertex 701.364 307.164 291.209 + vertex 702.001 302.826 292.042 + endloop + endfacet + facet normal 0.77315 -0.00510026 -0.634203 + outer loop + vertex 701.524 297.246 291.506 + vertex 701.466 302.283 291.394 + vertex 702.001 302.826 292.042 + endloop + endfacet + facet normal 0.766611 -0.00153122 -0.64211 + outer loop + vertex 701.238 290.426 291.181 + vertex 701.524 297.246 291.506 + vertex 701.988 288.203 292.082 + endloop + endfacet + facet normal 0.761825 -0.00543716 -0.64776 + outer loop + vertex 701.376 282.147 291.413 + vertex 701.238 290.426 291.181 + vertex 701.988 288.203 292.082 + endloop + endfacet + facet normal 0.74543 -0.000102759 -0.666584 + outer loop + vertex 701.101 274.048 291.106 + vertex 701.376 282.147 291.413 + vertex 701.929 273.295 292.033 + endloop + endfacet + facet normal 0.744515 -0.00235793 -0.667602 + outer loop + vertex 701.324 265.8 291.385 + vertex 701.101 274.048 291.106 + vertex 701.929 273.295 292.033 + endloop + endfacet + facet normal 0.719968 0.00424978 -0.693995 + outer loop + vertex 701.251 255.431 291.245 + vertex 701.324 265.8 291.385 + vertex 702.031 259.488 292.079 + endloop + endfacet + facet normal 0.687701 0.00350501 -0.725986 + outer loop + vertex 701.352 247.846 291.304 + vertex 701.251 255.431 291.245 + vertex 702.102 246.89 292.01 + endloop + endfacet + facet normal 0.691263 0.00884454 -0.72255 + outer loop + vertex 701.579 241.961 291.449 + vertex 701.352 247.846 291.304 + vertex 702.102 246.89 292.01 + endloop + endfacet + facet normal 0.687313 0.015014 -0.726206 + outer loop + vertex 701.588 233.046 291.274 + vertex 701.579 241.961 291.449 + vertex 702.449 234.308 292.114 + endloop + endfacet + facet normal 0.687199 0.012168 -0.726368 + outer loop + vertex 701.743 225.147 291.288 + vertex 701.588 233.046 291.274 + vertex 702.596 221.718 292.038 + endloop + endfacet + facet normal 0.688047 0.0125563 -0.725557 + outer loop + vertex 701.906 216.962 291.301 + vertex 701.743 225.147 291.288 + vertex 702.596 221.718 292.038 + endloop + endfacet + facet normal 0.729447 0.0123416 -0.683926 + outer loop + vertex 702.146 209.56 291.423 + vertex 701.906 216.962 291.301 + vertex 702.784 207.453 292.066 + endloop + endfacet + facet normal 0.717893 0.00511858 -0.696134 + outer loop + vertex 702.346 203.86 291.587 + vertex 702.146 209.56 291.423 + vertex 702.784 207.453 292.066 + endloop + endfacet + facet normal 0.815689 0.00310446 -0.578482 + outer loop + vertex 702.403 197.882 291.635 + vertex 702.346 203.86 291.587 + vertex 702.77 194.16 292.133 + endloop + endfacet + facet normal 0.902164 0.0314637 -0.430245 + outer loop + vertex 702.743 193.164 292.003 + vertex 702.403 197.882 291.635 + vertex 702.77 194.16 292.133 + endloop + endfacet + facet normal 0.997454 -0.0183741 -0.0688993 + outer loop + vertex 702.646 187.288 292.165 + vertex 702.743 193.164 292.003 + vertex 702.77 194.16 292.133 + endloop + endfacet + facet normal 0.492008 -0.0453512 -0.869409 + outer loop + vertex 702.354 181.278 292.314 + vertex 702.646 187.288 292.165 + vertex 702.35 179.562 292.401 + endloop + endfacet + facet normal 0.148234 -0.0505989 -0.987657 + outer loop + vertex 702.085 176.437 292.521 + vertex 702.354 181.278 292.314 + vertex 702.35 179.562 292.401 + endloop + endfacet + facet normal 0.0023637 -0.0624523 -0.998045 + outer loop + vertex 701.491 171.048 292.857 + vertex 702.085 176.437 292.521 + vertex 701.81 173.074 292.731 + endloop + endfacet + facet normal 0.657515 -0.151635 -0.738025 + outer loop + vertex 700.71 165.451 293.312 + vertex 701.491 171.048 292.857 + vertex 700.944 166.865 293.229 + endloop + endfacet + facet normal 0.719471 -0.0707025 0.690915 + outer loop + vertex 700.023 161.795 293.653 + vertex 700.71 165.451 293.312 + vertex 699.622 160.432 293.931 + endloop + endfacet + facet normal 0.882676 -0.170086 0.438124 + outer loop + vertex 698.862 157.326 294.256 + vertex 700.023 161.795 293.653 + vertex 699.622 160.432 293.931 + endloop + endfacet + facet normal 0.717424 -0.33226 -0.612296 + outer loop + vertex 697.162 152.031 295.137 + vertex 698.862 157.326 294.256 + vertex 697.909 154.201 294.835 + endloop + endfacet + facet normal 0.057615 -0.21888 -0.974049 + outer loop + vertex 695.565 147.948 295.96 + vertex 697.162 152.031 295.137 + vertex 695.787 148.34 295.885 + endloop + endfacet + facet normal -0.358964 -0.0741562 -0.930401 + outer loop + vertex 693.645 143.512 297.054 + vertex 695.565 147.948 295.96 + vertex 694.664 145.715 296.486 + endloop + endfacet + facet normal 0.453891 -0.511408 -0.729688 + outer loop + vertex 696.323 144.017 298.366 + vertex 693.645 143.512 297.054 + vertex 695.168 144.035 297.634 + endloop + endfacet + facet normal 0.26947 -0.188406 -0.944399 + outer loop + vertex 716.291 152.469 303.505 + vertex 710.332 150.037 302.29 + vertex 713.446 152.976 302.592 + endloop + endfacet + facet normal 0.188174 -0.124359 -0.974231 + outer loop + vertex 726.341 156.605 305.069 + vertex 721.204 154.832 304.303 + vertex 724.239 157.553 304.542 + endloop + endfacet + facet normal 0.13556 -0.106267 -0.985054 + outer loop + vertex 738.379 162.823 306.185 + vertex 732.798 159.632 305.761 + vertex 734.433 163.225 305.598 + endloop + endfacet + facet normal 0.112976 -0.0927653 -0.989258 + outer loop + vertex 744.116 165.181 306.619 + vertex 738.379 162.823 306.185 + vertex 740.612 166.916 306.056 + endloop + endfacet + facet normal -0.00407045 -0.0763376 -0.997074 + outer loop + vertex 812.005 207.978 306.589 + vertex 806.507 203.292 306.97 + vertex 807.79 207.965 306.607 + endloop + endfacet + facet normal -0.0198272 -0.0927547 -0.995492 + outer loop + vertex 816.764 212.409 306.081 + vertex 812.005 207.978 306.589 + vertex 813.54 212.922 306.098 + endloop + endfacet + facet normal -0.000439531 -0.137163 -0.990548 + outer loop + vertex 820.248 214.592 305.778 + vertex 816.764 212.409 306.081 + vertex 820.384 218.221 305.275 + endloop + endfacet + facet normal -0.0293094 -0.136043 -0.990269 + outer loop + vertex 824.508 218.6 305.101 + vertex 820.248 214.592 305.778 + vertex 820.384 218.221 305.275 + endloop + endfacet + facet normal -0.0321505 -0.171025 -0.984742 + outer loop + vertex 828.209 222.127 304.368 + vertex 824.508 218.6 305.101 + vertex 825.801 221.293 304.591 + endloop + endfacet + facet normal -0.0529242 -0.195268 -0.979321 + outer loop + vertex 831.667 225.337 303.541 + vertex 828.209 222.127 304.368 + vertex 828.968 224.396 303.874 + endloop + endfacet + facet normal -0.085739 -0.21732 -0.972328 + outer loop + vertex 835.212 229.457 302.307 + vertex 831.667 225.337 303.541 + vertex 832.035 227.616 302.999 + endloop + endfacet + facet normal -0.0694316 -0.282087 -0.956873 + outer loop + vertex 839.574 233.255 300.871 + vertex 835.212 229.457 302.307 + vertex 836.859 232.735 301.221 + endloop + endfacet + facet normal -0.0441687 -0.356913 -0.933093 + outer loop + vertex 843.374 237.315 299.138 + vertex 839.574 233.255 300.871 + vertex 840.387 236.105 299.742 + endloop + endfacet + facet normal 0.0728854 -0.496115 -0.865192 + outer loop + vertex 846.2 240.098 297.781 + vertex 843.374 237.315 299.138 + vertex 844.934 239.343 298.107 + endloop + endfacet + facet normal 0.192029 -0.585006 -0.787967 + outer loop + vertex 848.339 242.413 296.583 + vertex 846.2 240.098 297.781 + vertex 847.118 241.824 296.723 + endloop + endfacet + facet normal -0.686752 -0.196465 -0.699838 + outer loop + vertex 789.072 384.933 297.743 + vertex 792.003 384.848 294.891 + vertex 793.907 377.108 295.196 + endloop + endfacet + facet normal 0.130211 -0.567497 -0.813014 + outer loop + vertex 846.449 240.972 297.21 + vertex 847.118 241.824 296.723 + vertex 846.2 240.098 297.781 + endloop + endfacet + facet normal 0.0782266 -0.580226 -0.81069 + outer loop + vertex 847.118 241.824 296.723 + vertex 846.599 242.436 296.234 + vertex 846.805 242.562 296.164 + endloop + endfacet + facet normal 0.00368599 -0.450709 -0.892663 + outer loop + vertex 842.599 238.697 298.443 + vertex 843.158 237.85 298.873 + vertex 840.387 236.105 299.742 + endloop + endfacet + facet normal -0.0094026 -0.447564 -0.894202 + outer loop + vertex 843.158 237.85 298.873 + vertex 844.934 239.343 298.107 + vertex 843.374 237.315 299.138 + endloop + endfacet + facet normal 0.128623 -0.5673 -0.813404 + outer loop + vertex 844.934 239.343 298.107 + vertex 846.449 240.972 297.21 + vertex 846.2 240.098 297.781 + endloop + endfacet + facet normal 0.469086 -0.462314 -0.752479 + outer loop + vertex 695.168 144.035 297.634 + vertex 697.309 144.808 298.495 + vertex 696.323 144.017 298.366 + endloop + endfacet + facet normal 0.413486 -0.469658 -0.780032 + outer loop + vertex 694 143.917 296.999 + vertex 694.194 143.749 297.202 + vertex 693.645 143.512 297.054 + endloop + endfacet + facet normal 0.451815 -0.697534 -0.556157 + outer loop + vertex 694.194 143.749 297.202 + vertex 695.168 144.035 297.634 + vertex 693.645 143.512 297.054 + endloop + endfacet + facet normal 0.252322 -0.3544 -0.900408 + outer loop + vertex 694.268 144.767 296.713 + vertex 693.897 143.916 296.944 + vertex 693.994 144.203 296.858 + endloop + endfacet + facet normal 0.414984 -0.47077 -0.778565 + outer loop + vertex 693.897 143.916 296.944 + vertex 694 143.917 296.999 + vertex 693.645 143.512 297.054 + endloop + endfacet + facet normal -0.41603 -0.902071 -0.114836 + outer loop + vertex 845.489 243.087 295.668 + vertex 844 243.836 295.177 + vertex 844.958 243.361 295.438 + endloop + endfacet + facet normal 0.0171897 -0.663365 -0.748099 + outer loop + vertex 846.805 242.562 296.164 + vertex 845.489 243.087 295.668 + vertex 846.47 242.81 295.937 + endloop + endfacet + facet normal -0.533038 -0.654926 -0.53567 + outer loop + vertex 842.575 244.933 294.684 + vertex 841.285 246.367 294.214 + vertex 842.086 245.523 294.45 + endloop + endfacet + facet normal -0.528465 -0.80616 -0.266139 + outer loop + vertex 844 243.836 295.177 + vertex 842.575 244.933 294.684 + vertex 843.478 244.257 294.938 + endloop + endfacet + facet normal -0.0524954 -0.354701 -0.933505 + outer loop + vertex 836.859 232.735 301.221 + vertex 840.387 236.105 299.742 + vertex 839.574 233.255 300.871 + endloop + endfacet + facet normal -0.07201 -0.239479 -0.968227 + outer loop + vertex 832.035 227.616 302.999 + vertex 834.165 230.304 302.175 + vertex 835.212 229.457 302.307 + endloop + endfacet + facet normal -0.0969294 -0.268752 -0.95832 + outer loop + vertex 834.165 230.304 302.175 + vertex 836.859 232.735 301.221 + vertex 835.212 229.457 302.307 + endloop + endfacet + facet normal -0.0193489 -0.206282 -0.978301 + outer loop + vertex 825.801 221.293 304.591 + vertex 828.968 224.396 303.874 + vertex 828.209 222.127 304.368 + endloop + endfacet + facet normal -0.0419532 -0.224687 -0.973527 + outer loop + vertex 828.968 224.396 303.874 + vertex 832.035 227.616 302.999 + vertex 831.667 225.337 303.541 + endloop + endfacet + facet normal -0.0255662 -0.17412 -0.984392 + outer loop + vertex 820.384 218.221 305.275 + vertex 825.801 221.293 304.591 + vertex 824.508 218.6 305.101 + endloop + endfacet + facet normal -0.0245281 -0.122387 -0.992179 + outer loop + vertex 813.54 212.922 306.098 + vertex 820.384 218.221 305.275 + vertex 816.764 212.409 306.081 + endloop + endfacet + facet normal -0.0039979 -0.0976394 -0.995214 + outer loop + vertex 807.79 207.965 306.607 + vertex 813.54 212.922 306.098 + vertex 812.005 207.978 306.589 + endloop + endfacet + facet normal 0.135703 -0.10503 -0.985167 + outer loop + vertex 734.433 163.225 305.598 + vertex 740.612 166.916 306.056 + vertex 738.379 162.823 306.185 + endloop + endfacet + facet normal 0.159637 -0.117009 -0.980217 + outer loop + vertex 729.047 159.877 305.121 + vertex 734.433 163.225 305.598 + vertex 732.798 159.632 305.761 + endloop + endfacet + facet normal -0.514965 0.016859 -0.857046 + outer loop + vertex 694.664 145.715 296.486 + vertex 693.994 144.203 296.858 + vertex 693.645 143.512 297.054 + endloop + endfacet + facet normal 0.25063 -0.316622 -0.914842 + outer loop + vertex 695.787 148.34 295.885 + vertex 694.664 145.715 296.486 + vertex 695.565 147.948 295.96 + endloop + endfacet + facet normal 0.415649 -0.326865 -0.848761 + outer loop + vertex 696.376 149.745 295.633 + vertex 695.787 148.34 295.885 + vertex 697.162 152.031 295.137 + endloop + endfacet + facet normal 0.945325 -0.326085 -0.0053518 + outer loop + vertex 697.909 154.201 294.835 + vertex 696.376 149.745 295.633 + vertex 697.162 152.031 295.137 + endloop + endfacet + facet normal -0.793787 -0.394075 -0.463257 + outer loop + vertex 839.312 249.539 293.555 + vertex 837.577 253.454 293.197 + vertex 838.56 251.455 293.214 + endloop + endfacet + facet normal 0.135477 -0.139072 -0.980971 + outer loop + vertex 840.22 247.886 293.821 + vertex 839.76 248.627 293.653 + vertex 839.743 248.777 293.629 + endloop + endfacet + facet normal -0.127812 -0.167669 -0.977523 + outer loop + vertex 839.76 248.627 293.653 + vertex 839.312 249.539 293.555 + vertex 839.743 248.777 293.629 + endloop + endfacet + facet normal -0.53354 -0.542193 -0.649124 + outer loop + vertex 841.285 246.367 294.214 + vertex 840.22 247.886 293.821 + vertex 840.829 247.067 294.005 + endloop + endfacet + facet normal 0.791475 -0.131099 0.596976 + outer loop + vertex 699.622 160.432 293.931 + vertex 697.909 154.201 294.835 + vertex 698.862 157.326 294.256 + endloop + endfacet + facet normal 0.780425 -0.0928671 0.618314 + outer loop + vertex 700.944 166.865 293.229 + vertex 699.622 160.432 293.931 + vertex 700.71 165.451 293.312 + endloop + endfacet + facet normal -0.900816 -0.251743 -0.353775 + outer loop + vertex 835.968 258.507 292.707 + vertex 835.145 261.907 292.383 + vertex 835.811 259.508 292.394 + endloop + endfacet + facet normal -0.792887 -0.17842 -0.582663 + outer loop + vertex 835.145 261.907 292.383 + vertex 834.56 263.219 292.778 + vertex 834.329 266.491 292.09 + endloop + endfacet + facet normal -0.838897 -0.310509 -0.447031 + outer loop + vertex 837.577 253.454 293.197 + vertex 835.968 258.507 292.707 + vertex 836.974 255.767 292.721 + endloop + endfacet + facet normal 0.701254 -0.153635 -0.696161 + outer loop + vertex 701.81 173.074 292.731 + vertex 700.944 166.865 293.229 + vertex 701.491 171.048 292.857 + endloop + endfacet + facet normal 0.987666 -0.0888354 -0.128937 + outer loop + vertex 702.35 179.562 292.401 + vertex 701.81 173.074 292.731 + vertex 702.085 176.437 292.521 + endloop + endfacet + facet normal 0.976616 -0.0437884 -0.210483 + outer loop + vertex 702.489 182.864 292.358 + vertex 702.35 179.562 292.401 + vertex 702.646 187.288 292.165 + endloop + endfacet + facet normal -0.773021 -0.182266 -0.607633 + outer loop + vertex 834.56 263.219 292.778 + vertex 832.27 272.12 293.021 + vertex 834.329 266.491 292.09 + endloop + endfacet + facet normal 0.9134 -0.014641 0.4068 + outer loop + vertex 702.77 194.16 292.133 + vertex 702.489 182.864 292.358 + vertex 702.646 187.288 292.165 + endloop + endfacet + facet normal -0.696714 -0.141228 -0.70331 + outer loop + vertex 832.27 272.12 293.021 + vertex 829.857 284.111 293.004 + vertex 831.833 279.308 292.01 + endloop + endfacet + facet normal 0.752649 -0.0041573 -0.658409 + outer loop + vertex 702.784 207.453 292.066 + vertex 702.77 194.16 292.133 + vertex 702.346 203.86 291.587 + endloop + endfacet + facet normal -0.688012 -0.149189 -0.710198 + outer loop + vertex 829.857 284.111 293.004 + vertex 827.755 294.09 292.943 + vertex 829.812 290.581 291.688 + endloop + endfacet + facet normal 0.703945 0.00787288 -0.710211 + outer loop + vertex 702.596 221.718 292.038 + vertex 702.784 207.453 292.066 + vertex 701.906 216.962 291.301 + endloop + endfacet + facet normal -0.674906 -0.172696 -0.717411 + outer loop + vertex 827.755 294.09 292.943 + vertex 825.457 302.454 293.092 + vertex 827.591 299.755 291.734 + endloop + endfacet + facet normal 0.689263 0.0124842 -0.724403 + outer loop + vertex 702.449 234.308 292.114 + vertex 702.596 221.718 292.038 + vertex 701.588 233.046 291.274 + endloop + endfacet + facet normal -0.653364 -0.192155 -0.732251 + outer loop + vertex 825.457 302.454 293.092 + vertex 823.288 310.537 292.906 + vertex 825.918 305.42 291.903 + endloop + endfacet + facet normal 0.674202 0.0124625 -0.738442 + outer loop + vertex 702.102 246.89 292.01 + vertex 702.449 234.308 292.114 + vertex 701.579 241.961 291.449 + endloop + endfacet + facet normal -0.668559 -0.222242 -0.709674 + outer loop + vertex 823.288 310.537 292.906 + vertex 820.347 318.739 293.108 + vertex 822.795 315.971 291.669 + endloop + endfacet + facet normal 0.710969 0.00786992 -0.70318 + outer loop + vertex 702.031 259.488 292.079 + vertex 702.102 246.89 292.01 + vertex 701.251 255.431 291.245 + endloop + endfacet + facet normal -0.648023 -0.236544 -0.723957 + outer loop + vertex 820.347 318.739 293.108 + vertex 817.657 326.562 292.96 + vertex 820.645 321.484 291.944 + endloop + endfacet + facet normal 0.714032 0.00291278 -0.700107 + outer loop + vertex 701.929 273.295 292.033 + vertex 702.031 259.488 292.079 + vertex 701.324 265.8 291.385 + endloop + endfacet + facet normal -0.669876 -0.26298 -0.69434 + outer loop + vertex 817.657 326.562 292.96 + vertex 814.354 334.525 293.13 + vertex 816.928 331.691 291.721 + endloop + endfacet + facet normal 0.74104 -0.000718323 -0.67146 + outer loop + vertex 701.988 288.203 292.082 + vertex 701.929 273.295 292.033 + vertex 701.376 282.147 291.413 + endloop + endfacet + facet normal -0.657391 -0.274627 -0.701725 + outer loop + vertex 814.354 334.525 293.13 + vertex 811.403 342.095 292.933 + vertex 814.52 337.135 291.954 + endloop + endfacet + facet normal 0.759692 -0.0024062 -0.650278 + outer loop + vertex 702.001 302.826 292.042 + vertex 701.988 288.203 292.082 + vertex 701.524 297.246 291.506 + endloop + endfacet + facet normal -0.685165 -0.301916 -0.662869 + outer loop + vertex 811.403 342.095 292.933 + vertex 807.91 349.688 293.085 + vertex 810.37 347.212 291.669 + endloop + endfacet + facet normal 0.774566 -0.00385738 -0.632482 + outer loop + vertex 702.081 315.809 292.062 + vertex 702.001 302.826 292.042 + vertex 701.601 312.357 291.495 + endloop + endfacet + facet normal -0.678556 -0.307921 -0.666894 + outer loop + vertex 807.91 349.688 293.085 + vertex 804.866 356.444 293.062 + vertex 807.73 352.568 291.939 + endloop + endfacet + facet normal 0.787261 -0.00505345 -0.616599 + outer loop + vertex 702.081 329.305 291.951 + vertex 702.081 315.809 292.062 + vertex 701.547 323.811 291.314 + endloop + endfacet + facet normal -0.703709 -0.318906 -0.634895 + outer loop + vertex 804.866 356.444 293.062 + vertex 801.718 363.697 292.908 + vertex 805.348 358.244 291.624 + endloop + endfacet + facet normal 0.797364 -0.00645752 -0.603464 + outer loop + vertex 702.236 342.492 292.015 + vertex 702.081 329.305 291.951 + vertex 701.707 339.177 291.352 + endloop + endfacet + facet normal -0.72699 -0.323394 -0.605724 + outer loop + vertex 801.718 363.697 292.908 + vertex 798.147 371.015 293.287 + vertex 800.721 367.764 291.934 + endloop + endfacet + facet normal 0.80836 -0.00584435 -0.588659 + outer loop + vertex 702.374 355.855 292.072 + vertex 702.236 342.492 292.015 + vertex 701.955 350.149 291.553 + endloop + endfacet + facet normal -0.756608 -0.311836 -0.574719 + outer loop + vertex 798.147 371.015 293.287 + vertex 795.644 376.905 293.386 + vertex 798.366 373.204 291.811 + endloop + endfacet + facet normal -0.717559 -0.202722 -0.666343 + outer loop + vertex 795.644 376.905 293.386 + vertex 793.907 377.108 295.196 + vertex 792.003 384.848 294.891 + endloop + endfacet + facet normal -0.638931 -0.14907 -0.754682 + outer loop + vertex 793.907 377.108 295.196 + vertex 791.399 376.857 297.369 + vertex 789.072 384.933 297.743 + endloop + endfacet + facet normal 0.781932 -0.00824251 -0.623309 + outer loop + vertex 702.616 370.124 292.186 + vertex 702.374 355.855 292.072 + vertex 702.232 365.181 291.77 + endloop + endfacet + facet normal 0.771609 -0.0458823 -0.63444 + outer loop + vertex 703.672 386.655 292.275 + vertex 702.616 370.124 292.186 + vertex 702.301 378.618 291.189 + endloop + endfacet + facet normal 0.170443 -0.547628 -0.819178 + outer loop + vertex 846.805 242.562 296.164 + vertex 848.339 242.413 296.583 + vertex 847.118 241.824 296.723 + endloop + endfacet + facet normal -0.81261 -0.275208 -0.513738 + outer loop + vertex 795.662 379.876 291.767 + vertex 795.644 376.905 293.386 + vertex 792.003 384.848 294.891 + endloop + endfacet + facet normal -0.000932818 -0.444843 -0.895608 + outer loop + vertex 843.374 237.315 299.138 + vertex 840.387 236.105 299.742 + vertex 843.158 237.85 298.873 + endloop + endfacet + facet normal 0.0874805 -0.312333 -0.945936 + outer loop + vertex 693.994 144.203 296.858 + vertex 693.897 143.916 296.944 + vertex 693.645 143.512 297.054 + endloop + endfacet + facet normal 0.116771 -0.692623 -0.711785 + outer loop + vertex 847.704 243.393 295.536 + vertex 848.244 243.41 295.608 + vertex 847.411 243.114 295.759 + endloop + endfacet + facet normal 0.091744 -0.693976 -0.714129 + outer loop + vertex 846.946 242.961 295.848 + vertex 847.411 243.114 295.759 + vertex 847.871 242.944 295.984 + endloop + endfacet + facet normal 0.194034 -0.705037 -0.68211 + outer loop + vertex 848.72 243.646 295.499 + vertex 847.871 242.944 295.984 + vertex 848.244 243.41 295.608 + endloop + endfacet + facet normal 0.106911 -0.674483 -0.730509 + outer loop + vertex 847.411 243.114 295.759 + vertex 848.244 243.41 295.608 + vertex 847.871 242.944 295.984 + endloop + endfacet + facet normal -0.267879 -0.55377 -0.788403 + outer loop + vertex 841.775 246.461 293.965 + vertex 842 246.906 293.576 + vertex 843.151 245.157 294.413 + endloop + endfacet + facet normal -0.230984 -0.539641 -0.809589 + outer loop + vertex 843.151 245.157 294.413 + vertex 842 246.906 293.576 + vertex 843.428 245.636 294.015 + endloop + endfacet + facet normal -0.322469 -0.565707 -0.75894 + outer loop + vertex 841.591 246.347 294.128 + vertex 841.775 246.461 293.965 + vertex 842.951 244.953 294.589 + endloop + endfacet + facet normal -0.21248 -0.510694 -0.833093 + outer loop + vertex 842.951 244.953 294.589 + vertex 841.775 246.461 293.965 + vertex 843.151 245.157 294.413 + endloop + endfacet + facet normal -0.128408 -0.572739 -0.809618 + outer loop + vertex 842.951 244.953 294.589 + vertex 843.151 245.157 294.413 + vertex 844.398 243.931 295.083 + endloop + endfacet + facet normal -0.0732986 -0.5344 -0.842047 + outer loop + vertex 844.398 243.931 295.083 + vertex 843.151 245.157 294.413 + vertex 844.655 244.157 294.917 + endloop + endfacet + facet normal -0.125546 -0.590457 -0.797244 + outer loop + vertex 843.151 245.157 294.413 + vertex 843.428 245.636 294.015 + vertex 844.655 244.157 294.917 + endloop + endfacet + facet normal -0.117322 -0.586271 -0.801575 + outer loop + vertex 844.655 244.157 294.917 + vertex 843.428 245.636 294.015 + vertex 845.085 244.538 294.576 + endloop + endfacet + facet normal -0.367342 -0.565269 -0.7386 + outer loop + vertex 841.305 246.535 294.126 + vertex 841.591 246.347 294.128 + vertex 842.638 245.067 294.587 + endloop + endfacet + facet normal -0.154533 -0.443011 -0.883097 + outer loop + vertex 842.638 245.067 294.587 + vertex 841.591 246.347 294.128 + vertex 842.951 244.953 294.589 + endloop + endfacet + facet normal -0.215321 -0.606947 -0.765018 + outer loop + vertex 842.638 245.067 294.587 + vertex 842.951 244.953 294.589 + vertex 844.075 243.931 295.084 + endloop + endfacet + facet normal -0.00264262 -0.437841 -0.899048 + outer loop + vertex 844.075 243.931 295.084 + vertex 842.951 244.953 294.589 + vertex 844.398 243.931 295.083 + endloop + endfacet + facet normal -0.00256511 -0.555276 -0.831662 + outer loop + vertex 844.075 243.931 295.084 + vertex 844.398 243.931 295.083 + vertex 845.547 243.187 295.576 + endloop + endfacet + facet normal 0.052075 -0.494623 -0.867546 + outer loop + vertex 845.547 243.187 295.576 + vertex 844.398 243.931 295.083 + vertex 845.84 243.25 295.558 + endloop + endfacet + facet normal 0.076499 -0.590809 -0.803176 + outer loop + vertex 845.547 243.187 295.576 + vertex 845.84 243.25 295.558 + vertex 846.935 242.814 295.983 + endloop + endfacet + facet normal 0.0170987 -0.675593 -0.737076 + outer loop + vertex 846.935 242.814 295.983 + vertex 845.84 243.25 295.558 + vertex 846.946 242.961 295.848 + endloop + endfacet + facet normal -0.0472279 -0.63671 -0.769656 + outer loop + vertex 844.655 244.157 294.917 + vertex 845.085 244.538 294.576 + vertex 846.17 243.432 295.423 + endloop + endfacet + facet normal -0.135269 -0.683196 -0.717597 + outer loop + vertex 846.17 243.432 295.423 + vertex 845.085 244.538 294.576 + vertex 846.098 243.722 295.161 + endloop + endfacet + facet normal -0.00903352 -0.584715 -0.811188 + outer loop + vertex 844.398 243.931 295.083 + vertex 844.655 244.157 294.917 + vertex 845.84 243.25 295.558 + endloop + endfacet + facet normal -0.00746516 -0.583366 -0.812175 + outer loop + vertex 845.84 243.25 295.558 + vertex 844.655 244.157 294.917 + vertex 846.17 243.432 295.423 + endloop + endfacet + facet normal 0.0370917 -0.634363 -0.772145 + outer loop + vertex 845.84 243.25 295.558 + vertex 846.17 243.432 295.423 + vertex 846.946 242.961 295.848 + endloop + endfacet + facet normal 0.0534048 -0.61831 -0.784118 + outer loop + vertex 846.946 242.961 295.848 + vertex 846.17 243.432 295.423 + vertex 847.411 243.114 295.759 + endloop + endfacet + facet normal 0.00576872 -0.670475 -0.74191 + outer loop + vertex 846.098 243.722 295.161 + vertex 846.88 243.445 295.417 + vertex 846.17 243.432 295.423 + endloop + endfacet + facet normal 0.0647664 -0.664299 -0.744656 + outer loop + vertex 847.704 243.393 295.536 + vertex 847.411 243.114 295.759 + vertex 846.88 243.445 295.417 + endloop + endfacet + facet normal 0.00689163 -0.71253 -0.701608 + outer loop + vertex 847.411 243.114 295.759 + vertex 846.17 243.432 295.423 + vertex 846.88 243.445 295.417 + endloop + endfacet + facet normal -0.574389 -0.336809 -0.746081 + outer loop + vertex 839.739 250.283 292.905 + vertex 839.318 250.57 293.099 + vertex 838.614 254.073 292.059 + endloop + endfacet + facet normal -0.55088 -0.319621 -0.770956 + outer loop + vertex 839.235 250.134 293.339 + vertex 837.911 254.021 292.673 + vertex 839.318 250.57 293.099 + endloop + endfacet + facet normal -0.605486 -0.335785 -0.721551 + outer loop + vertex 837.911 254.021 292.673 + vertex 838.614 254.073 292.059 + vertex 839.318 250.57 293.099 + endloop + endfacet + facet normal -0.0922821 -0.237681 -0.96695 + outer loop + vertex 839.398 249.502 293.479 + vertex 839.235 250.134 293.339 + vertex 840.141 248.206 293.726 + endloop + endfacet + facet normal -0.251857 -0.303093 -0.919077 + outer loop + vertex 840.141 248.206 293.726 + vertex 839.235 250.134 293.339 + vertex 840.335 248.127 293.699 + endloop + endfacet + facet normal -0.287251 -0.407589 -0.866809 + outer loop + vertex 840.141 248.206 293.726 + vertex 840.335 248.127 293.699 + vertex 841.305 246.535 294.126 + endloop + endfacet + facet normal -0.251776 -0.390935 -0.885313 + outer loop + vertex 841.305 246.535 294.126 + vertex 840.335 248.127 293.699 + vertex 841.591 246.347 294.128 + endloop + endfacet + facet normal -0.603939 -0.431224 -0.670301 + outer loop + vertex 839.318 250.57 293.099 + vertex 839.739 250.283 292.905 + vertex 840.529 248.162 293.556 + endloop + endfacet + facet normal -0.52622 -0.422944 -0.737707 + outer loop + vertex 840.529 248.162 293.556 + vertex 839.739 250.283 292.905 + vertex 840.756 248.494 293.204 + endloop + endfacet + facet normal -0.415975 -0.376643 -0.82771 + outer loop + vertex 839.235 250.134 293.339 + vertex 839.318 250.57 293.099 + vertex 840.335 248.127 293.699 + endloop + endfacet + facet normal -0.496398 -0.396485 -0.772262 + outer loop + vertex 840.335 248.127 293.699 + vertex 839.318 250.57 293.099 + vertex 840.529 248.162 293.556 + endloop + endfacet + facet normal -0.453421 -0.498053 -0.739157 + outer loop + vertex 840.335 248.127 293.699 + vertex 840.529 248.162 293.556 + vertex 841.591 246.347 294.128 + endloop + endfacet + facet normal -0.397407 -0.479013 -0.782697 + outer loop + vertex 841.591 246.347 294.128 + vertex 840.529 248.162 293.556 + vertex 841.775 246.461 293.965 + endloop + endfacet + facet normal -0.43472 -0.498485 -0.750021 + outer loop + vertex 840.529 248.162 293.556 + vertex 840.756 248.494 293.204 + vertex 841.775 246.461 293.965 + endloop + endfacet + facet normal -0.388448 -0.487293 -0.782083 + outer loop + vertex 841.775 246.461 293.965 + vertex 840.756 248.494 293.204 + vertex 842 246.906 293.576 + endloop + endfacet + facet normal -0.452175 -0.189226 -0.871626 + outer loop + vertex 835.611 260.758 292.176 + vertex 835.472 263.309 291.695 + vertex 836.346 258.535 292.278 + endloop + endfacet + facet normal -0.620119 -0.205976 -0.756985 + outer loop + vertex 836.346 258.535 292.278 + vertex 835.472 263.309 291.695 + vertex 836.927 258.94 291.692 + endloop + endfacet + facet normal -0.584274 -0.26967 -0.765442 + outer loop + vertex 836.346 258.535 292.278 + vertex 836.927 258.94 291.692 + vertex 837.911 254.021 292.673 + endloop + endfacet + facet normal -0.621853 -0.271065 -0.734727 + outer loop + vertex 837.911 254.021 292.673 + vertex 836.927 258.94 291.692 + vertex 838.614 254.073 292.059 + endloop + endfacet + facet normal 0.0406377 -0.714222 -0.698738 + outer loop + vertex 849.062 245.859 293.423 + vertex 849.056 246.929 292.329 + vertex 849.371 245.711 293.593 + endloop + endfacet + facet normal 0.124764 -0.734451 -0.667095 + outer loop + vertex 849.677 245.899 293.443 + vertex 849.371 245.711 293.593 + vertex 850.077 247.903 291.312 + endloop + endfacet + facet normal 0.00156237 -0.723281 -0.690552 + outer loop + vertex 849.412 248.296 290.899 + vertex 850.077 247.903 291.312 + vertex 849.056 246.929 292.329 + endloop + endfacet + facet normal -0.00416368 -0.720402 -0.693545 + outer loop + vertex 849.371 245.711 293.593 + vertex 849.056 246.929 292.329 + vertex 850.077 247.903 291.312 + endloop + endfacet + facet normal 0.109866 -0.683467 -0.721666 + outer loop + vertex 848.404 244.486 294.65 + vertex 848.813 245.166 294.068 + vertex 848.826 244.317 294.874 + endloop + endfacet + facet normal 0.0629799 -0.691486 -0.719639 + outer loop + vertex 849.062 245.859 293.423 + vertex 849.371 245.711 293.593 + vertex 848.813 245.166 294.068 + endloop + endfacet + facet normal 0.0544454 -0.687054 -0.724563 + outer loop + vertex 849.371 245.711 293.593 + vertex 848.826 244.317 294.874 + vertex 848.813 245.166 294.068 + endloop + endfacet + facet normal 0.118787 -0.670418 -0.732413 + outer loop + vertex 847.704 243.393 295.536 + vertex 848.14 243.854 295.185 + vertex 848.244 243.41 295.608 + endloop + endfacet + facet normal 0.120743 -0.670254 -0.732243 + outer loop + vertex 848.404 244.486 294.65 + vertex 848.826 244.317 294.874 + vertex 848.14 243.854 295.185 + endloop + endfacet + facet normal 0.120514 -0.67006 -0.732459 + outer loop + vertex 848.826 244.317 294.874 + vertex 848.244 243.41 295.608 + vertex 848.14 243.854 295.185 + endloop + endfacet + facet normal 0.179257 -0.685834 -0.705336 + outer loop + vertex 848.244 243.41 295.608 + vertex 848.826 244.317 294.874 + vertex 848.72 243.646 295.499 + endloop + endfacet + facet normal 0.160949 -0.686475 -0.709118 + outer loop + vertex 848.72 243.646 295.499 + vertex 848.826 244.317 294.874 + vertex 849.247 244.728 294.571 + endloop + endfacet + facet normal 0.197384 -0.703996 -0.682224 + outer loop + vertex 848.826 244.317 294.874 + vertex 849.371 245.711 293.593 + vertex 849.247 244.728 294.571 + endloop + endfacet + facet normal 0.0928531 -0.708307 -0.699771 + outer loop + vertex 849.247 244.728 294.571 + vertex 849.371 245.711 293.593 + vertex 849.677 245.899 293.443 + endloop + endfacet + facet normal -0.31424 -0.60332 -0.732979 + outer loop + vertex 843.465 249.493 291.101 + vertex 844.049 250.494 290.026 + vertex 844.865 248.356 291.436 + endloop + endfacet + facet normal -0.302279 -0.602503 -0.738659 + outer loop + vertex 844.865 248.356 291.436 + vertex 844.049 250.494 290.026 + vertex 845.443 249.386 290.359 + endloop + endfacet + facet normal -0.294472 -0.587789 -0.753519 + outer loop + vertex 842.886 248.51 292.093 + vertex 843.465 249.493 291.101 + vertex 844.324 247.327 292.454 + endloop + endfacet + facet normal -0.297238 -0.588069 -0.752213 + outer loop + vertex 844.324 247.327 292.454 + vertex 843.465 249.493 291.101 + vertex 844.865 248.356 291.436 + endloop + endfacet + facet normal -0.172306 -0.645622 -0.743964 + outer loop + vertex 844.324 247.327 292.454 + vertex 844.865 248.356 291.436 + vertex 845.819 246.572 292.763 + endloop + endfacet + facet normal -0.159457 -0.642728 -0.749316 + outer loop + vertex 845.819 246.572 292.763 + vertex 844.865 248.356 291.436 + vertex 846.348 247.599 291.77 + endloop + endfacet + facet normal -0.174597 -0.662992 -0.727982 + outer loop + vertex 844.865 248.356 291.436 + vertex 845.443 249.386 290.359 + vertex 846.348 247.599 291.77 + endloop + endfacet + facet normal -0.16609 -0.661396 -0.731416 + outer loop + vertex 846.348 247.599 291.77 + vertex 845.443 249.386 290.359 + vertex 846.927 248.643 290.694 + endloop + endfacet + facet normal -0.270338 -0.575568 -0.771777 + outer loop + vertex 842.371 247.612 292.943 + vertex 842.886 248.51 292.093 + vertex 843.84 246.37 293.355 + endloop + endfacet + facet normal -0.283074 -0.577628 -0.765646 + outer loop + vertex 843.84 246.37 293.355 + vertex 842.886 248.51 292.093 + vertex 844.324 247.327 292.454 + endloop + endfacet + facet normal -0.260947 -0.564234 -0.783292 + outer loop + vertex 842 246.906 293.576 + vertex 842.371 247.612 292.943 + vertex 843.428 245.636 294.015 + endloop + endfacet + facet normal -0.25559 -0.56286 -0.786043 + outer loop + vertex 843.428 245.636 294.015 + vertex 842.371 247.612 292.943 + vertex 843.84 246.37 293.355 + endloop + endfacet + facet normal -0.145257 -0.614905 -0.775108 + outer loop + vertex 843.428 245.636 294.015 + vertex 843.84 246.37 293.355 + vertex 845.085 244.538 294.576 + endloop + endfacet + facet normal -0.14442 -0.614601 -0.775505 + outer loop + vertex 845.085 244.538 294.576 + vertex 843.84 246.37 293.355 + vertex 845.501 245.398 293.816 + endloop + endfacet + facet normal -0.159855 -0.632583 -0.757816 + outer loop + vertex 843.84 246.37 293.355 + vertex 844.324 247.327 292.454 + vertex 845.501 245.398 293.816 + endloop + endfacet + facet normal -0.163806 -0.633723 -0.756017 + outer loop + vertex 845.501 245.398 293.816 + vertex 844.324 247.327 292.454 + vertex 845.819 246.572 292.763 + endloop + endfacet + facet normal -0.0482698 -0.658496 -0.751035 + outer loop + vertex 847.242 246.19 293.007 + vertex 846.827 245.268 293.842 + vertex 845.819 246.572 292.763 + endloop + endfacet + facet normal -0.0488966 -0.648386 -0.75974 + outer loop + vertex 846.711 244.482 294.52 + vertex 845.501 245.398 293.816 + vertex 846.827 245.268 293.842 + endloop + endfacet + facet normal -0.0501476 -0.659277 -0.750226 + outer loop + vertex 845.501 245.398 293.816 + vertex 845.819 246.572 292.763 + vertex 846.827 245.268 293.842 + endloop + endfacet + facet normal -0.0261763 -0.630599 -0.775667 + outer loop + vertex 846.711 244.482 294.52 + vertex 846.255 244.095 294.85 + vertex 845.501 245.398 293.816 + endloop + endfacet + facet normal -0.0542659 -0.62592 -0.777997 + outer loop + vertex 846.098 243.722 295.161 + vertex 845.085 244.538 294.576 + vertex 846.255 244.095 294.85 + endloop + endfacet + facet normal -0.0640713 -0.642785 -0.763362 + outer loop + vertex 845.085 244.538 294.576 + vertex 845.501 245.398 293.816 + vertex 846.255 244.095 294.85 + endloop + endfacet + facet normal 0.0190889 -0.661688 -0.749536 + outer loop + vertex 846.255 244.095 294.85 + vertex 846.711 244.482 294.52 + vertex 847.287 243.821 295.118 + endloop + endfacet + facet normal 0.0400798 -0.651047 -0.757978 + outer loop + vertex 847.287 243.821 295.118 + vertex 846.711 244.482 294.52 + vertex 847.63 244.414 294.627 + endloop + endfacet + facet normal 0.0215734 -0.64563 -0.763346 + outer loop + vertex 846.098 243.722 295.161 + vertex 846.255 244.095 294.85 + vertex 846.88 243.445 295.417 + endloop + endfacet + facet normal 0.0289219 -0.641436 -0.766631 + outer loop + vertex 846.88 243.445 295.417 + vertex 846.255 244.095 294.85 + vertex 847.287 243.821 295.118 + endloop + endfacet + facet normal 0.0649152 -0.663517 -0.745339 + outer loop + vertex 846.88 243.445 295.417 + vertex 847.287 243.821 295.118 + vertex 847.704 243.393 295.536 + endloop + endfacet + facet normal 0.0836038 -0.652755 -0.752942 + outer loop + vertex 847.704 243.393 295.536 + vertex 847.287 243.821 295.118 + vertex 848.14 243.854 295.185 + endloop + endfacet + facet normal 0.0832773 -0.663819 -0.743242 + outer loop + vertex 847.287 243.821 295.118 + vertex 847.63 244.414 294.627 + vertex 848.14 243.854 295.185 + endloop + endfacet + facet normal 0.0831819 -0.663871 -0.743207 + outer loop + vertex 848.14 243.854 295.185 + vertex 847.63 244.414 294.627 + vertex 848.404 244.486 294.65 + endloop + endfacet + facet normal 0.0276235 -0.677849 -0.734682 + outer loop + vertex 846.827 245.268 293.842 + vertex 847.242 246.19 293.007 + vertex 847.982 245.162 293.984 + endloop + endfacet + facet normal 0.0277495 -0.677798 -0.734724 + outer loop + vertex 847.982 245.162 293.984 + vertex 847.242 246.19 293.007 + vertex 848.435 245.992 293.235 + endloop + endfacet + facet normal 0.0392071 -0.656081 -0.753671 + outer loop + vertex 846.711 244.482 294.52 + vertex 846.827 245.268 293.842 + vertex 847.63 244.414 294.627 + endloop + endfacet + facet normal 0.0311187 -0.66049 -0.75019 + outer loop + vertex 847.63 244.414 294.627 + vertex 846.827 245.268 293.842 + vertex 847.982 245.162 293.984 + endloop + endfacet + facet normal 0.083752 -0.672494 -0.735348 + outer loop + vertex 847.63 244.414 294.627 + vertex 847.982 245.162 293.984 + vertex 848.404 244.486 294.65 + endloop + endfacet + facet normal 0.0779356 -0.674732 -0.733936 + outer loop + vertex 848.404 244.486 294.65 + vertex 847.982 245.162 293.984 + vertex 848.813 245.166 294.068 + endloop + endfacet + facet normal 0.0765298 -0.690477 -0.719295 + outer loop + vertex 847.982 245.162 293.984 + vertex 848.435 245.992 293.235 + vertex 848.813 245.166 294.068 + endloop + endfacet + facet normal 0.0696252 -0.692443 -0.718105 + outer loop + vertex 848.813 245.166 294.068 + vertex 848.435 245.992 293.235 + vertex 849.062 245.859 293.423 + endloop + endfacet + facet normal -0.060732 -0.69969 -0.71186 + outer loop + vertex 846.348 247.599 291.77 + vertex 846.927 248.643 290.694 + vertex 847.798 247.164 292.074 + endloop + endfacet + facet normal -0.0607921 -0.699706 -0.71184 + outer loop + vertex 847.798 247.164 292.074 + vertex 846.927 248.643 290.694 + vertex 848.351 248.266 290.943 + endloop + endfacet + facet normal -0.0569978 -0.678838 -0.732073 + outer loop + vertex 845.819 246.572 292.763 + vertex 846.348 247.599 291.77 + vertex 847.242 246.19 293.007 + endloop + endfacet + facet normal -0.0488488 -0.676268 -0.735035 + outer loop + vertex 847.242 246.19 293.007 + vertex 846.348 247.599 291.77 + vertex 847.798 247.164 292.074 + endloop + endfacet + facet normal 0.0591687 -0.713513 -0.698139 + outer loop + vertex 849.062 245.859 293.423 + vertex 848.435 245.992 293.235 + vertex 849.056 246.929 292.329 + endloop + endfacet + facet normal 0.0208481 -0.697828 -0.715962 + outer loop + vertex 847.242 246.19 293.007 + vertex 847.798 247.164 292.074 + vertex 848.435 245.992 293.235 + endloop + endfacet + facet normal 0.0146169 -0.699625 -0.714361 + outer loop + vertex 847.798 247.164 292.074 + vertex 849.056 246.929 292.329 + vertex 848.435 245.992 293.235 + endloop + endfacet + facet normal 0.00751985 -0.717861 -0.696146 + outer loop + vertex 847.798 247.164 292.074 + vertex 848.351 248.266 290.943 + vertex 849.056 246.929 292.329 + endloop + endfacet + facet normal -0.00870226 -0.721979 -0.691861 + outer loop + vertex 849.056 246.929 292.329 + vertex 848.351 248.266 290.943 + vertex 849.412 248.296 290.899 + endloop + endfacet + facet normal -0.608579 -0.375308 -0.699125 + outer loop + vertex 841.672 253.452 289.631 + vertex 840.94 252.911 290.558 + vertex 840.555 257 288.698 + endloop + endfacet + facet normal -0.626196 -0.351613 -0.695878 + outer loop + vertex 840.525 251.547 291.622 + vertex 839.486 255.235 290.692 + vertex 840.94 252.911 290.558 + endloop + endfacet + facet normal -0.646132 -0.365579 -0.669974 + outer loop + vertex 839.486 255.235 290.692 + vertex 840.555 257 288.698 + vertex 840.94 252.911 290.558 + endloop + endfacet + facet normal -0.59722 -0.349961 -0.721703 + outer loop + vertex 840.525 251.547 291.622 + vertex 839.937 251.26 292.247 + vertex 839.486 255.235 290.692 + endloop + endfacet + facet normal -0.628499 -0.342251 -0.698465 + outer loop + vertex 839.739 250.283 292.905 + vertex 838.614 254.073 292.059 + vertex 839.937 251.26 292.247 + endloop + endfacet + facet normal -0.631536 -0.343457 -0.695126 + outer loop + vertex 838.614 254.073 292.059 + vertex 839.486 255.235 290.692 + vertex 839.937 251.26 292.247 + endloop + endfacet + facet normal -0.553975 -0.425365 -0.715665 + outer loop + vertex 839.937 251.26 292.247 + vertex 840.525 251.547 291.622 + vertex 841.1 249.135 292.61 + endloop + endfacet + facet normal -0.502864 -0.427707 -0.751129 + outer loop + vertex 841.1 249.135 292.61 + vertex 840.525 251.547 291.622 + vertex 841.592 249.989 291.794 + endloop + endfacet + facet normal -0.49904 -0.41164 -0.762569 + outer loop + vertex 839.739 250.283 292.905 + vertex 839.937 251.26 292.247 + vertex 840.756 248.494 293.204 + endloop + endfacet + facet normal -0.521271 -0.412806 -0.746905 + outer loop + vertex 840.756 248.494 293.204 + vertex 839.937 251.26 292.247 + vertex 841.1 249.135 292.61 + endloop + endfacet + facet normal -0.403695 -0.496102 -0.768709 + outer loop + vertex 840.756 248.494 293.204 + vertex 841.1 249.135 292.61 + vertex 842 246.906 293.576 + endloop + endfacet + facet normal -0.387252 -0.493753 -0.778617 + outer loop + vertex 842 246.906 293.576 + vertex 841.1 249.135 292.61 + vertex 842.371 247.612 292.943 + endloop + endfacet + facet normal -0.400084 -0.501887 -0.766839 + outer loop + vertex 841.1 249.135 292.61 + vertex 841.592 249.989 291.794 + vertex 842.371 247.612 292.943 + endloop + endfacet + facet normal -0.395429 -0.501613 -0.769428 + outer loop + vertex 842.371 247.612 292.943 + vertex 841.592 249.989 291.794 + vertex 842.886 248.51 292.093 + endloop + endfacet + facet normal -0.557769 -0.445822 -0.700098 + outer loop + vertex 840.94 252.911 290.558 + vertex 841.672 253.452 289.631 + vertex 842.177 250.955 290.819 + endloop + endfacet + facet normal -0.537568 -0.448409 -0.714107 + outer loop + vertex 842.177 250.955 290.819 + vertex 841.672 253.452 289.631 + vertex 842.771 251.947 289.748 + endloop + endfacet + facet normal -0.505592 -0.429273 -0.748399 + outer loop + vertex 840.525 251.547 291.622 + vertex 840.94 252.911 290.558 + vertex 841.592 249.989 291.794 + endloop + endfacet + facet normal -0.522254 -0.428342 -0.73741 + outer loop + vertex 841.592 249.989 291.794 + vertex 840.94 252.911 290.558 + vertex 842.177 250.955 290.819 + endloop + endfacet + facet normal -0.411231 -0.512309 -0.753942 + outer loop + vertex 841.592 249.989 291.794 + vertex 842.177 250.955 290.819 + vertex 842.886 248.51 292.093 + endloop + endfacet + facet normal -0.417391 -0.512322 -0.75054 + outer loop + vertex 842.886 248.51 292.093 + vertex 842.177 250.955 290.819 + vertex 843.465 249.493 291.101 + endloop + endfacet + facet normal -0.437006 -0.525627 -0.729892 + outer loop + vertex 842.177 250.955 290.819 + vertex 842.771 251.947 289.748 + vertex 843.465 249.493 291.101 + endloop + endfacet + facet normal -0.439466 -0.525541 -0.728475 + outer loop + vertex 843.465 249.493 291.101 + vertex 842.771 251.947 289.748 + vertex 844.049 250.494 290.026 + endloop + endfacet + facet normal -0.770813 -0.240998 -0.589718 + outer loop + vertex 836.242 265.283 290.242 + vertex 837.322 265.34 288.806 + vertex 837.756 259.799 290.503 + endloop + endfacet + facet normal -0.752611 -0.246019 -0.61078 + outer loop + vertex 837.756 259.799 290.503 + vertex 837.322 265.34 288.806 + vertex 838.741 261.243 288.708 + endloop + endfacet + facet normal -0.694458 -0.230791 -0.681516 + outer loop + vertex 835.472 263.309 291.695 + vertex 836.242 265.283 290.242 + vertex 836.927 258.94 291.692 + endloop + endfacet + facet normal -0.713053 -0.228525 -0.662821 + outer loop + vertex 836.927 258.94 291.692 + vertex 836.242 265.283 290.242 + vertex 837.756 259.799 290.503 + endloop + endfacet + facet normal -0.676531 -0.285782 -0.678701 + outer loop + vertex 836.927 258.94 291.692 + vertex 837.756 259.799 290.503 + vertex 838.614 254.073 292.059 + endloop + endfacet + facet normal -0.679108 -0.285499 -0.676241 + outer loop + vertex 838.614 254.073 292.059 + vertex 837.756 259.799 290.503 + vertex 839.486 255.235 290.692 + endloop + endfacet + facet normal -0.715659 -0.297509 -0.631918 + outer loop + vertex 837.756 259.799 290.503 + vertex 838.741 261.243 288.708 + vertex 839.486 255.235 290.692 + endloop + endfacet + facet normal -0.704605 -0.299845 -0.643136 + outer loop + vertex 839.486 255.235 290.692 + vertex 838.741 261.243 288.708 + vertex 840.555 257 288.698 + endloop + endfacet + facet normal -0.775927 -0.216305 -0.592579 + outer loop + vertex 837.322 265.34 288.806 + vertex 836.242 265.283 290.242 + vertex 836.338 273.421 287.145 + endloop + endfacet + facet normal -0.748767 -0.177938 -0.638503 + outer loop + vertex 835.472 263.309 291.695 + vertex 834.4 272.21 290.471 + vertex 836.242 265.283 290.242 + endloop + endfacet + facet normal -0.813754 -0.198264 -0.546348 + outer loop + vertex 834.4 272.21 290.471 + vertex 836.338 273.421 287.145 + vertex 836.242 265.283 290.242 + endloop + endfacet + facet normal -0.842102 -0.166163 -0.513082 + outer loop + vertex 832.617 281.913 290.256 + vertex 834.375 282.703 287.113 + vertex 834.4 272.21 290.471 + endloop + endfacet + facet normal -0.821462 -0.17555 -0.54257 + outer loop + vertex 834.4 272.21 290.471 + vertex 834.375 282.703 287.113 + vertex 836.338 273.421 287.145 + endloop + endfacet + facet normal -0.848362 -0.169806 -0.501445 + outer loop + vertex 831.073 290.476 289.967 + vertex 832.596 291.3 287.113 + vertex 832.617 281.913 290.256 + endloop + endfacet + facet normal -0.840037 -0.173952 -0.513886 + outer loop + vertex 832.617 281.913 290.256 + vertex 832.596 291.3 287.113 + vertex 834.375 282.703 287.113 + endloop + endfacet + facet normal -0.83843 -0.195877 -0.508593 + outer loop + vertex 829.198 297.905 290.198 + vertex 830.73 299.339 287.12 + vertex 831.073 290.476 289.967 + endloop + endfacet + facet normal -0.841029 -0.194736 -0.504726 + outer loop + vertex 831.073 290.476 289.967 + vertex 830.73 299.339 287.12 + vertex 832.596 291.3 287.113 + endloop + endfacet + facet normal -0.828673 -0.223365 -0.513233 + outer loop + vertex 826.829 306.795 290.154 + vertex 828.552 307.377 287.118 + vertex 829.198 297.905 290.198 + endloop + endfacet + facet normal -0.826779 -0.22412 -0.515953 + outer loop + vertex 829.198 297.905 290.198 + vertex 828.552 307.377 287.118 + vertex 830.73 299.339 287.12 + endloop + endfacet + facet normal -0.823239 -0.25256 -0.50842 + outer loop + vertex 824.399 315.208 289.908 + vertex 826.06 315.497 287.075 + vertex 826.829 306.795 290.154 + endloop + endfacet + facet normal -0.819369 -0.254141 -0.513855 + outer loop + vertex 826.829 306.795 290.154 + vertex 826.06 315.497 287.075 + vertex 828.552 307.377 287.118 + endloop + endfacet + facet normal -0.808541 -0.287728 -0.513297 + outer loop + vertex 821.515 322.865 290.159 + vertex 823.299 323.329 287.09 + vertex 824.399 315.208 289.908 + endloop + endfacet + facet normal -0.813632 -0.285954 -0.506195 + outer loop + vertex 824.399 315.208 289.908 + vertex 823.299 323.329 287.09 + vertex 826.06 315.497 287.075 + endloop + endfacet + facet normal -0.807178 -0.308981 -0.502985 + outer loop + vertex 818.576 330.905 289.937 + vertex 820.303 330.991 287.112 + vertex 821.515 322.865 290.159 + endloop + endfacet + facet normal -0.80044 -0.311419 -0.512167 + outer loop + vertex 821.515 322.865 290.159 + vertex 820.303 330.991 287.112 + vertex 823.299 323.329 287.09 + endloop + endfacet + facet normal -0.802329 -0.333786 -0.494829 + outer loop + vertex 815.308 338.41 290.173 + vertex 817.111 338.592 287.127 + vertex 818.576 330.905 289.937 + endloop + endfacet + facet normal -0.79935 -0.334739 -0.498989 + outer loop + vertex 818.576 330.905 289.937 + vertex 817.111 338.592 287.127 + vertex 820.303 330.991 287.112 + endloop + endfacet + facet normal -0.808023 -0.349733 -0.474115 + outer loop + vertex 812.009 346.355 289.935 + vertex 813.741 346.186 287.109 + vertex 815.308 338.41 290.173 + endloop + endfacet + facet normal -0.795342 -0.354192 -0.491914 + outer loop + vertex 815.308 338.41 290.173 + vertex 813.741 346.186 287.109 + vertex 817.111 338.592 287.127 + endloop + endfacet + facet normal -0.802873 -0.37183 -0.46598 + outer loop + vertex 808.328 354.023 290.159 + vertex 810.213 353.76 287.12 + vertex 812.009 346.355 289.935 + endloop + endfacet + facet normal -0.80113 -0.372379 -0.468535 + outer loop + vertex 812.009 346.355 289.935 + vertex 810.213 353.76 287.12 + vertex 813.741 346.186 287.109 + endloop + endfacet + facet normal -0.813452 -0.379199 -0.441026 + outer loop + vertex 804.694 362.161 289.864 + vertex 806.573 361.345 287.1 + vertex 808.328 354.023 290.159 + endloop + endfacet + facet normal -0.798896 -0.384641 -0.462403 + outer loop + vertex 808.328 354.023 290.159 + vertex 806.573 361.345 287.1 + vertex 810.213 353.76 287.12 + endloop + endfacet + facet normal -0.820291 -0.385536 -0.422475 + outer loop + vertex 801.157 369.425 290.103 + vertex 802.968 368.884 287.08 + vertex 804.694 362.161 289.864 + endloop + endfacet + facet normal -0.811196 -0.389044 -0.436585 + outer loop + vertex 804.694 362.161 289.864 + vertex 802.968 368.884 287.08 + vertex 806.573 361.345 287.1 + endloop + endfacet + facet normal -0.8275 -0.361235 -0.42983 + outer loop + vertex 798.175 376.417 289.967 + vertex 799.582 376.503 287.186 + vertex 801.157 369.425 290.103 + endloop + endfacet + facet normal -0.826916 -0.361482 -0.430745 + outer loop + vertex 801.157 369.425 290.103 + vertex 799.582 376.503 287.186 + vertex 802.968 368.884 287.08 + endloop + endfacet + facet normal -0.0622344 -0.770095 -0.634886 + outer loop + vertex 850.338 250.704 288.158 + vertex 850.815 251.776 286.812 + vertex 850.83 250.366 288.52 + endloop + endfacet + facet normal -0.0601666 -0.790039 -0.610096 + outer loop + vertex 851.086 252.956 285.256 + vertex 851.593 252.5 285.797 + vertex 850.815 251.776 286.812 + endloop + endfacet + facet normal -0.110093 -0.767106 -0.632003 + outer loop + vertex 851.593 252.5 285.797 + vertex 850.83 250.366 288.52 + vertex 850.815 251.776 286.812 + endloop + endfacet + facet normal -0.0179671 -0.738703 -0.673792 + outer loop + vertex 849.412 248.296 290.899 + vertex 849.977 249.458 289.609 + vertex 850.077 247.903 291.312 + endloop + endfacet + facet normal -0.035576 -0.753907 -0.656017 + outer loop + vertex 850.338 250.704 288.158 + vertex 850.83 250.366 288.52 + vertex 849.977 249.458 289.609 + endloop + endfacet + facet normal -0.0704906 -0.738523 -0.670533 + outer loop + vertex 850.83 250.366 288.52 + vertex 850.077 247.903 291.312 + vertex 849.977 249.458 289.609 + endloop + endfacet + facet normal -0.368124 -0.68213 -0.631809 + outer loop + vertex 845.592 253.596 286.323 + vertex 846.04 254.653 284.921 + vertex 846.984 252.617 286.569 + endloop + endfacet + facet normal -0.364896 -0.68214 -0.633669 + outer loop + vertex 846.984 252.617 286.569 + vertex 846.04 254.653 284.921 + vertex 847.419 253.716 285.135 + endloop + endfacet + facet normal -0.354691 -0.664184 -0.658068 + outer loop + vertex 845.114 252.542 287.644 + vertex 845.592 253.596 286.323 + vertex 846.512 251.516 287.926 + endloop + endfacet + facet normal -0.350385 -0.66411 -0.660446 + outer loop + vertex 846.512 251.516 287.926 + vertex 845.592 253.596 286.323 + vertex 846.984 252.617 286.569 + endloop + endfacet + facet normal -0.198803 -0.726164 -0.658151 + outer loop + vertex 846.512 251.516 287.926 + vertex 846.984 252.617 286.569 + vertex 847.984 250.887 288.176 + endloop + endfacet + facet normal -0.200298 -0.726383 -0.657456 + outer loop + vertex 847.984 250.887 288.176 + vertex 846.984 252.617 286.569 + vertex 848.444 252.014 286.79 + endloop + endfacet + facet normal -0.210997 -0.74381 -0.634213 + outer loop + vertex 846.984 252.617 286.569 + vertex 847.419 253.716 285.135 + vertex 848.444 252.014 286.79 + endloop + endfacet + facet normal -0.213978 -0.744194 -0.632762 + outer loop + vertex 848.444 252.014 286.79 + vertex 847.419 253.716 285.135 + vertex 848.856 253.134 285.334 + endloop + endfacet + facet normal -0.339731 -0.645811 -0.683748 + outer loop + vertex 844.601 251.505 288.878 + vertex 845.114 252.542 287.644 + vertex 845.999 250.436 289.193 + endloop + endfacet + facet normal -0.335465 -0.645665 -0.685988 + outer loop + vertex 845.999 250.436 289.193 + vertex 845.114 252.542 287.644 + vertex 846.512 251.516 287.926 + endloop + endfacet + facet normal -0.327563 -0.625203 -0.708395 + outer loop + vertex 844.049 250.494 290.026 + vertex 844.601 251.505 288.878 + vertex 845.443 249.386 290.359 + endloop + endfacet + facet normal -0.316806 -0.624667 -0.71374 + outer loop + vertex 845.443 249.386 290.359 + vertex 844.601 251.505 288.878 + vertex 845.999 250.436 289.193 + endloop + endfacet + facet normal -0.18397 -0.685129 -0.704807 + outer loop + vertex 845.443 249.386 290.359 + vertex 845.999 250.436 289.193 + vertex 846.927 248.643 290.694 + endloop + endfacet + facet normal -0.175489 -0.683704 -0.708345 + outer loop + vertex 846.927 248.643 290.694 + vertex 845.999 250.436 289.193 + vertex 847.481 249.749 289.489 + endloop + endfacet + facet normal -0.192012 -0.707261 -0.680378 + outer loop + vertex 845.999 250.436 289.193 + vertex 846.512 251.516 287.926 + vertex 847.481 249.749 289.489 + endloop + endfacet + facet normal -0.18612 -0.70633 -0.682977 + outer loop + vertex 847.481 249.749 289.489 + vertex 846.512 251.516 287.926 + vertex 847.984 250.887 288.176 + endloop + endfacet + facet normal -0.0801992 -0.738096 -0.669913 + outer loop + vertex 847.481 249.749 289.489 + vertex 847.984 250.887 288.176 + vertex 848.872 249.443 289.66 + endloop + endfacet + facet normal -0.0837501 -0.73891 -0.66858 + outer loop + vertex 848.872 249.443 289.66 + vertex 847.984 250.887 288.176 + vertex 849.356 250.616 288.303 + endloop + endfacet + facet normal -0.0693696 -0.718794 -0.691753 + outer loop + vertex 846.927 248.643 290.694 + vertex 847.481 249.749 289.489 + vertex 848.351 248.266 290.943 + endloop + endfacet + facet normal -0.0736917 -0.719832 -0.690226 + outer loop + vertex 848.351 248.266 290.943 + vertex 847.481 249.749 289.489 + vertex 848.872 249.443 289.66 + endloop + endfacet + facet normal -0.00772935 -0.735337 -0.677657 + outer loop + vertex 848.351 248.266 290.943 + vertex 848.872 249.443 289.66 + vertex 849.412 248.296 290.899 + endloop + endfacet + facet normal -0.0208353 -0.738032 -0.674443 + outer loop + vertex 849.412 248.296 290.899 + vertex 848.872 249.443 289.66 + vertex 849.977 249.458 289.609 + endloop + endfacet + facet normal -0.0198672 -0.752872 -0.657867 + outer loop + vertex 848.872 249.443 289.66 + vertex 849.356 250.616 288.303 + vertex 849.977 249.458 289.609 + endloop + endfacet + facet normal -0.0291188 -0.754864 -0.655234 + outer loop + vertex 849.977 249.458 289.609 + vertex 849.356 250.616 288.303 + vertex 850.338 250.704 288.158 + endloop + endfacet + facet normal -0.0972542 -0.775494 -0.62382 + outer loop + vertex 848.444 252.014 286.79 + vertex 848.856 253.134 285.334 + vertex 849.786 251.765 286.891 + endloop + endfacet + facet normal -0.104455 -0.776967 -0.620815 + outer loop + vertex 849.786 251.765 286.891 + vertex 848.856 253.134 285.334 + vertex 850.17 252.886 285.423 + endloop + endfacet + facet normal -0.0895528 -0.757813 -0.646297 + outer loop + vertex 847.984 250.887 288.176 + vertex 848.444 252.014 286.79 + vertex 849.356 250.616 288.303 + endloop + endfacet + facet normal -0.0924765 -0.758456 -0.645129 + outer loop + vertex 849.356 250.616 288.303 + vertex 848.444 252.014 286.79 + vertex 849.786 251.765 286.891 + endloop + endfacet + facet normal -0.024643 -0.771823 -0.63536 + outer loop + vertex 849.356 250.616 288.303 + vertex 849.786 251.765 286.891 + vertex 850.338 250.704 288.158 + endloop + endfacet + facet normal -0.0405315 -0.774788 -0.63092 + outer loop + vertex 850.338 250.704 288.158 + vertex 849.786 251.765 286.891 + vertex 850.815 251.776 286.812 + endloop + endfacet + facet normal -0.0389929 -0.78913 -0.612987 + outer loop + vertex 849.786 251.765 286.891 + vertex 850.17 252.886 285.423 + vertex 850.815 251.776 286.812 + endloop + endfacet + facet normal -0.050509 -0.791284 -0.609359 + outer loop + vertex 850.815 251.776 286.812 + vertex 850.17 252.886 285.423 + vertex 851.086 252.956 285.256 + endloop + endfacet + facet normal -0.720705 -0.404955 -0.562668 + outer loop + vertex 843.727 257.396 284.704 + vertex 843.105 256.833 285.906 + vertex 842.583 260.875 283.666 + endloop + endfacet + facet normal -0.718011 -0.395253 -0.572918 + outer loop + vertex 842.765 255.421 287.306 + vertex 841.616 258.936 286.322 + vertex 843.105 256.833 285.906 + endloop + endfacet + facet normal -0.725065 -0.403131 -0.55836 + outer loop + vertex 841.616 258.936 286.322 + vertex 842.583 260.875 283.666 + vertex 843.105 256.833 285.906 + endloop + endfacet + facet normal -0.66879 -0.395077 -0.629789 + outer loop + vertex 842.765 255.421 287.306 + vertex 842.087 254.87 288.372 + vertex 841.616 258.936 286.322 + endloop + endfacet + facet normal -0.663788 -0.378489 -0.645083 + outer loop + vertex 841.672 253.452 289.631 + vertex 840.555 257 288.698 + vertex 842.087 254.87 288.372 + endloop + endfacet + facet normal -0.677847 -0.392143 -0.62189 + outer loop + vertex 840.555 257 288.698 + vertex 841.616 258.936 286.322 + vertex 842.087 254.87 288.372 + endloop + endfacet + facet normal -0.612364 -0.47246 -0.633871 + outer loop + vertex 842.087 254.87 288.372 + vertex 842.765 255.421 287.306 + vertex 843.33 252.939 288.61 + endloop + endfacet + facet normal -0.600078 -0.47486 -0.643751 + outer loop + vertex 843.33 252.939 288.61 + vertex 842.765 255.421 287.306 + vertex 843.843 253.931 287.4 + endloop + endfacet + facet normal -0.551846 -0.457513 -0.697243 + outer loop + vertex 841.672 253.452 289.631 + vertex 842.087 254.87 288.372 + vertex 842.771 251.947 289.748 + endloop + endfacet + facet normal -0.576095 -0.454707 -0.679231 + outer loop + vertex 842.771 251.947 289.748 + vertex 842.087 254.87 288.372 + vertex 843.33 252.939 288.61 + endloop + endfacet + facet normal -0.464288 -0.542022 -0.700463 + outer loop + vertex 842.771 251.947 289.748 + vertex 843.33 252.939 288.61 + vertex 844.049 250.494 290.026 + endloop + endfacet + facet normal -0.463793 -0.542052 -0.700768 + outer loop + vertex 844.049 250.494 290.026 + vertex 843.33 252.939 288.61 + vertex 844.601 251.505 288.878 + endloop + endfacet + facet normal -0.491072 -0.559997 -0.667272 + outer loop + vertex 843.33 252.939 288.61 + vertex 843.843 253.931 287.4 + vertex 844.601 251.505 288.878 + endloop + endfacet + facet normal -0.483807 -0.560627 -0.672033 + outer loop + vertex 844.601 251.505 288.878 + vertex 843.843 253.931 287.4 + vertex 845.114 252.542 287.644 + endloop + endfacet + facet normal -0.660094 -0.488697 -0.570483 + outer loop + vertex 843.105 256.833 285.906 + vertex 843.727 257.396 284.704 + vertex 844.326 254.943 286.113 + endloop + endfacet + facet normal -0.647817 -0.49206 -0.581558 + outer loop + vertex 844.326 254.943 286.113 + vertex 843.727 257.396 284.704 + vertex 844.784 255.958 284.743 + endloop + endfacet + facet normal -0.608378 -0.480122 -0.631949 + outer loop + vertex 842.765 255.421 287.306 + vertex 843.105 256.833 285.906 + vertex 843.843 253.931 287.4 + endloop + endfacet + facet normal -0.632883 -0.475559 -0.610985 + outer loop + vertex 843.843 253.931 287.4 + vertex 843.105 256.833 285.906 + vertex 844.326 254.943 286.113 + endloop + endfacet + facet normal -0.50607 -0.575756 -0.642182 + outer loop + vertex 843.843 253.931 287.4 + vertex 844.326 254.943 286.113 + vertex 845.114 252.542 287.644 + endloop + endfacet + facet normal -0.505996 -0.575764 -0.642234 + outer loop + vertex 845.114 252.542 287.644 + vertex 844.326 254.943 286.113 + vertex 845.592 253.596 286.323 + endloop + endfacet + facet normal -0.525709 -0.589732 -0.613063 + outer loop + vertex 844.326 254.943 286.113 + vertex 844.784 255.958 284.743 + vertex 845.592 253.596 286.323 + endloop + endfacet + facet normal -0.526179 -0.589666 -0.612724 + outer loop + vertex 845.592 253.596 286.323 + vertex 844.784 255.958 284.743 + vertex 846.04 254.653 284.921 + endloop + endfacet + facet normal -0.816763 -0.265787 -0.512109 + outer loop + vertex 838.2 267.937 286.45 + vertex 839.354 268.755 284.185 + vertex 839.792 263.065 286.439 + endloop + endfacet + facet normal -0.8178 -0.265309 -0.5107 + outer loop + vertex 839.792 263.065 286.439 + vertex 839.354 268.755 284.185 + vertex 840.793 264.971 283.846 + endloop + endfacet + facet normal -0.778929 -0.256059 -0.572453 + outer loop + vertex 837.322 265.34 288.806 + vertex 838.2 267.937 286.45 + vertex 838.741 261.243 288.708 + endloop + endfacet + facet normal -0.783137 -0.254666 -0.567311 + outer loop + vertex 838.741 261.243 288.708 + vertex 838.2 267.937 286.45 + vertex 839.792 263.065 286.439 + endloop + endfacet + facet normal -0.739296 -0.314784 -0.595275 + outer loop + vertex 838.741 261.243 288.708 + vertex 839.792 263.065 286.439 + vertex 840.555 257 288.698 + endloop + endfacet + facet normal -0.746106 -0.31284 -0.587757 + outer loop + vertex 840.555 257 288.698 + vertex 839.792 263.065 286.439 + vertex 841.616 258.936 286.322 + endloop + endfacet + facet normal -0.775546 -0.327196 -0.53988 + outer loop + vertex 839.792 263.065 286.439 + vertex 840.793 264.971 283.846 + vertex 841.616 258.936 286.322 + endloop + endfacet + facet normal -0.789472 -0.321983 -0.522553 + outer loop + vertex 841.616 258.936 286.322 + vertex 840.793 264.971 283.846 + vertex 842.583 260.875 283.666 + endloop + endfacet + facet normal -0.827913 -0.238127 -0.507796 + outer loop + vertex 839.354 268.755 284.185 + vertex 838.2 267.937 286.45 + vertex 838.25 276.409 282.396 + endloop + endfacet + facet normal -0.817812 -0.20975 -0.5359 + outer loop + vertex 837.322 265.34 288.806 + vertex 836.338 273.421 287.145 + vertex 838.2 267.937 286.45 + endloop + endfacet + facet normal -0.846049 -0.22606 -0.482802 + outer loop + vertex 836.338 273.421 287.145 + vertex 838.25 276.409 282.396 + vertex 838.2 267.937 286.45 + endloop + endfacet + facet normal -0.870391 -0.1856 -0.45604 + outer loop + vertex 834.375 282.703 287.113 + vertex 836.2 285.136 282.641 + vertex 836.338 273.421 287.145 + endloop + endfacet + facet normal -0.863644 -0.189744 -0.467029 + outer loop + vertex 836.338 273.421 287.145 + vertex 836.2 285.136 282.641 + vertex 838.25 276.409 282.396 + endloop + endfacet + facet normal -0.875553 -0.181302 -0.447814 + outer loop + vertex 832.596 291.3 287.113 + vertex 834.317 293.595 282.817 + vertex 834.375 282.703 287.113 + endloop + endfacet + facet normal -0.870909 -0.184334 -0.455563 + outer loop + vertex 834.375 282.703 287.113 + vertex 834.317 293.595 282.817 + vertex 836.2 285.136 282.641 + endloop + endfacet + facet normal -0.870764 -0.201688 -0.448432 + outer loop + vertex 830.73 299.339 287.12 + vertex 832.38 301.694 282.857 + vertex 832.596 291.3 287.113 + endloop + endfacet + facet normal -0.865806 -0.204891 -0.456508 + outer loop + vertex 832.596 291.3 287.113 + vertex 832.38 301.694 282.857 + vertex 834.317 293.595 282.817 + endloop + endfacet + facet normal -0.858555 -0.232714 -0.456867 + outer loop + vertex 828.552 307.377 287.118 + vertex 830.22 309.586 282.858 + vertex 830.73 299.339 287.12 + endloop + endfacet + facet normal -0.8561 -0.234187 -0.460705 + outer loop + vertex 830.73 299.339 287.12 + vertex 830.22 309.586 282.858 + vertex 832.38 301.694 282.857 + endloop + endfacet + facet normal -0.849996 -0.26324 -0.456301 + outer loop + vertex 826.06 315.497 287.075 + vertex 827.75 317.39 282.835 + vertex 828.552 307.377 287.118 + endloop + endfacet + facet normal -0.841869 -0.267823 -0.468538 + outer loop + vertex 828.552 307.377 287.118 + vertex 827.75 317.39 282.835 + vertex 830.22 309.586 282.858 + endloop + endfacet + facet normal -0.839495 -0.295164 -0.456208 + outer loop + vertex 823.299 323.329 287.09 + vertex 824.998 325.037 282.858 + vertex 826.06 315.497 287.075 + endloop + endfacet + facet normal -0.833251 -0.298523 -0.465378 + outer loop + vertex 826.06 315.497 287.075 + vertex 824.998 325.037 282.858 + vertex 827.75 317.39 282.835 + endloop + endfacet + facet normal -0.832525 -0.324147 -0.449255 + outer loop + vertex 820.303 330.991 287.112 + vertex 821.998 332.532 282.86 + vertex 823.299 323.329 287.09 + endloop + endfacet + facet normal -0.822812 -0.329207 -0.463253 + outer loop + vertex 823.299 323.329 287.09 + vertex 821.998 332.532 282.86 + vertex 824.998 325.037 282.858 + endloop + endfacet + facet normal -0.829703 -0.347606 -0.436764 + outer loop + vertex 817.111 338.592 287.127 + vertex 818.796 339.926 282.864 + vertex 820.303 330.991 287.112 + endloop + endfacet + facet normal -0.817688 -0.353817 -0.454092 + outer loop + vertex 820.303 330.991 287.112 + vertex 818.796 339.926 282.864 + vertex 821.998 332.532 282.86 + endloop + endfacet + facet normal -0.827901 -0.368478 -0.422852 + outer loop + vertex 813.741 346.186 287.109 + vertex 815.424 347.28 282.86 + vertex 817.111 338.592 287.127 + endloop + endfacet + facet normal -0.816219 -0.374568 -0.43987 + outer loop + vertex 817.111 338.592 287.127 + vertex 815.424 347.28 282.86 + vertex 818.796 339.926 282.864 + endloop + endfacet + facet normal -0.828238 -0.385096 -0.407091 + outer loop + vertex 810.213 353.76 287.12 + vertex 811.912 354.58 282.889 + vertex 813.741 346.186 287.109 + endloop + endfacet + facet normal -0.81668 -0.391205 -0.424255 + outer loop + vertex 813.741 346.186 287.109 + vertex 811.912 354.58 282.889 + vertex 815.424 347.28 282.86 + endloop + endfacet + facet normal -0.831011 -0.399854 -0.386702 + outer loop + vertex 806.573 361.345 287.1 + vertex 808.289 361.836 282.904 + vertex 810.213 353.76 287.12 + endloop + endfacet + facet normal -0.817545 -0.407294 -0.407103 + outer loop + vertex 810.213 353.76 287.12 + vertex 808.289 361.836 282.904 + vertex 811.912 354.58 282.889 + endloop + endfacet + facet normal -0.841104 -0.403142 -0.360582 + outer loop + vertex 802.968 368.884 287.08 + vertex 804.654 369.095 282.912 + vertex 806.573 361.345 287.1 + endloop + endfacet + facet normal -0.825083 -0.412798 -0.385793 + outer loop + vertex 806.573 361.345 287.1 + vertex 804.654 369.095 282.912 + vertex 808.289 361.836 282.904 + endloop + endfacet + facet normal -0.860571 -0.377681 -0.341722 + outer loop + vertex 799.582 376.503 287.186 + vertex 801.245 376.574 282.922 + vertex 802.968 368.884 287.08 + endloop + endfacet + facet normal -0.848172 -0.386183 -0.362583 + outer loop + vertex 802.968 368.884 287.08 + vertex 801.245 376.574 282.922 + vertex 804.654 369.095 282.912 + endloop + endfacet + facet normal -0.881672 -0.29448 -0.368695 + outer loop + vertex 796.398 384.702 288.252 + vertex 798.384 384.625 283.564 + vertex 799.582 376.503 287.186 + endloop + endfacet + facet normal -0.890527 -0.288302 -0.351914 + outer loop + vertex 799.582 376.503 287.186 + vertex 798.384 384.625 283.564 + vertex 801.245 376.574 282.922 + endloop + endfacet + facet normal -0.0871084 -0.834161 -0.544598 + outer loop + vertex 851.735 255.209 282.001 + vertex 852.111 256.251 280.345 + vertex 852.299 254.921 282.352 + endloop + endfacet + facet normal -0.0790028 -0.848107 -0.523902 + outer loop + vertex 852.285 257.33 278.572 + vertex 852.87 257.186 278.717 + vertex 852.111 256.251 280.345 + endloop + endfacet + facet normal -0.131262 -0.831999 -0.539026 + outer loop + vertex 852.87 257.186 278.717 + vertex 852.299 254.921 282.352 + vertex 852.111 256.251 280.345 + endloop + endfacet + facet normal -0.090796 -0.801483 -0.591084 + outer loop + vertex 851.086 252.956 285.256 + vertex 851.512 254.029 283.736 + vertex 851.593 252.5 285.797 + endloop + endfacet + facet normal -0.0663506 -0.820965 -0.567111 + outer loop + vertex 851.735 255.209 282.001 + vertex 852.299 254.921 282.352 + vertex 851.512 254.029 283.736 + endloop + endfacet + facet normal -0.127602 -0.798924 -0.58774 + outer loop + vertex 852.299 254.921 282.352 + vertex 851.593 252.5 285.797 + vertex 851.512 254.029 283.736 + endloop + endfacet + facet normal -0.425649 -0.726203 -0.539863 + outer loop + vertex 847.257 257.821 280.292 + vertex 847.608 258.835 278.653 + vertex 848.565 256.936 280.453 + endloop + endfacet + facet normal -0.429403 -0.725794 -0.537435 + outer loop + vertex 848.565 256.936 280.453 + vertex 847.608 258.835 278.653 + vertex 848.893 257.963 278.803 + endloop + endfacet + facet normal -0.407893 -0.716995 -0.56528 + outer loop + vertex 846.876 256.776 281.893 + vertex 847.257 257.821 280.292 + vertex 848.209 255.882 282.066 + endloop + endfacet + facet normal -0.416469 -0.716284 -0.559903 + outer loop + vertex 848.209 255.882 282.066 + vertex 847.257 257.821 280.292 + vertex 848.565 256.936 280.453 + endloop + endfacet + facet normal -0.247783 -0.785111 -0.56763 + outer loop + vertex 848.209 255.882 282.066 + vertex 848.565 256.936 280.453 + vertex 849.586 255.327 282.232 + endloop + endfacet + facet normal -0.255173 -0.785528 -0.563767 + outer loop + vertex 849.586 255.327 282.232 + vertex 848.565 256.936 280.453 + vertex 849.913 256.387 280.607 + endloop + endfacet + facet normal -0.261011 -0.795238 -0.547238 + outer loop + vertex 848.565 256.936 280.453 + vertex 848.893 257.963 278.803 + vertex 849.913 256.387 280.607 + endloop + endfacet + facet normal -0.271169 -0.795574 -0.541783 + outer loop + vertex 849.913 256.387 280.607 + vertex 848.893 257.963 278.803 + vertex 850.214 257.417 278.944 + endloop + endfacet + facet normal -0.394698 -0.707811 -0.585847 + outer loop + vertex 846.47 255.721 283.441 + vertex 846.876 256.776 281.893 + vertex 847.826 254.808 283.631 + endloop + endfacet + facet normal -0.39925 -0.707554 -0.583067 + outer loop + vertex 847.826 254.808 283.631 + vertex 846.876 256.776 281.893 + vertex 848.209 255.882 282.066 + endloop + endfacet + facet normal -0.377268 -0.695312 -0.611727 + outer loop + vertex 846.04 254.653 284.921 + vertex 846.47 255.721 283.441 + vertex 847.419 253.716 285.135 + endloop + endfacet + facet normal -0.383014 -0.695155 -0.608325 + outer loop + vertex 847.419 253.716 285.135 + vertex 846.47 255.721 283.441 + vertex 847.826 254.808 283.631 + endloop + endfacet + facet normal -0.22299 -0.759201 -0.611464 + outer loop + vertex 847.419 253.716 285.135 + vertex 847.826 254.808 283.631 + vertex 848.856 253.134 285.334 + endloop + endfacet + facet normal -0.228219 -0.759752 -0.608845 + outer loop + vertex 848.856 253.134 285.334 + vertex 847.826 254.808 283.631 + vertex 849.233 254.241 283.811 + endloop + endfacet + facet normal -0.236298 -0.773287 -0.58838 + outer loop + vertex 847.826 254.808 283.631 + vertex 848.209 255.882 282.066 + vertex 849.233 254.241 283.811 + endloop + endfacet + facet normal -0.240955 -0.773659 -0.585997 + outer loop + vertex 849.233 254.241 283.811 + vertex 848.209 255.882 282.066 + vertex 849.586 255.327 282.232 + endloop + endfacet + facet normal -0.120082 -0.805196 -0.580724 + outer loop + vertex 849.233 254.241 283.811 + vertex 849.586 255.327 282.232 + vertex 850.518 253.999 283.881 + endloop + endfacet + facet normal -0.128391 -0.806522 -0.577094 + outer loop + vertex 850.518 253.999 283.881 + vertex 849.586 255.327 282.232 + vertex 850.845 255.095 282.276 + endloop + endfacet + facet normal -0.108407 -0.791149 -0.60194 + outer loop + vertex 848.856 253.134 285.334 + vertex 849.233 254.241 283.811 + vertex 850.17 252.886 285.423 + endloop + endfacet + facet normal -0.11678 -0.792675 -0.598355 + outer loop + vertex 850.17 252.886 285.423 + vertex 849.233 254.241 283.811 + vertex 850.518 253.999 283.881 + endloop + endfacet + facet normal -0.0461839 -0.805076 -0.59137 + outer loop + vertex 850.17 252.886 285.423 + vertex 850.518 253.999 283.881 + vertex 851.086 252.956 285.256 + endloop + endfacet + facet normal -0.0611364 -0.80734 -0.58691 + outer loop + vertex 851.086 252.956 285.256 + vertex 850.518 253.999 283.881 + vertex 851.512 254.029 283.736 + endloop + endfacet + facet normal -0.0585027 -0.818731 -0.571189 + outer loop + vertex 850.518 253.999 283.881 + vertex 850.845 255.095 282.276 + vertex 851.512 254.029 283.736 + endloop + endfacet + facet normal -0.0699403 -0.820544 -0.567288 + outer loop + vertex 851.512 254.029 283.736 + vertex 850.845 255.095 282.276 + vertex 851.735 255.209 282.001 + endloop + endfacet + facet normal -0.142605 -0.829731 -0.539638 + outer loop + vertex 849.913 256.387 280.607 + vertex 850.214 257.417 278.944 + vertex 851.147 256.167 280.62 + endloop + endfacet + facet normal -0.154082 -0.831133 -0.534299 + outer loop + vertex 851.147 256.167 280.62 + vertex 850.214 257.417 278.944 + vertex 851.421 257.204 278.927 + endloop + endfacet + facet normal -0.131113 -0.818049 -0.560005 + outer loop + vertex 849.586 255.327 282.232 + vertex 849.913 256.387 280.607 + vertex 850.845 255.095 282.276 + endloop + endfacet + facet normal -0.140584 -0.819378 -0.555748 + outer loop + vertex 850.845 255.095 282.276 + vertex 849.913 256.387 280.607 + vertex 851.147 256.167 280.62 + endloop + endfacet + facet normal -0.0631283 -0.832631 -0.550218 + outer loop + vertex 850.845 255.095 282.276 + vertex 851.147 256.167 280.62 + vertex 851.735 255.209 282.001 + endloop + endfacet + facet normal -0.0817777 -0.835102 -0.543983 + outer loop + vertex 851.735 255.209 282.001 + vertex 851.147 256.167 280.62 + vertex 852.111 256.251 280.345 + endloop + endfacet + facet normal -0.0769676 -0.844511 -0.529979 + outer loop + vertex 851.147 256.167 280.62 + vertex 851.421 257.204 278.927 + vertex 852.111 256.251 280.345 + endloop + endfacet + facet normal -0.0916883 -0.846619 -0.524241 + outer loop + vertex 852.111 256.251 280.345 + vertex 851.421 257.204 278.927 + vertex 852.285 257.33 278.572 + endloop + endfacet + facet normal -0.789483 -0.416545 -0.450784 + outer loop + vertex 845.402 261.344 278.656 + vertex 844.866 260.778 280.117 + vertex 844.239 264.652 277.636 + endloop + endfacet + facet normal -0.790348 -0.406845 -0.458069 + outer loop + vertex 844.609 259.378 281.803 + vertex 843.461 262.789 280.755 + vertex 844.866 260.778 280.117 + endloop + endfacet + facet normal -0.794212 -0.413667 -0.445093 + outer loop + vertex 843.461 262.789 280.755 + vertex 844.239 264.652 277.636 + vertex 844.866 260.778 280.117 + endloop + endfacet + facet normal -0.759992 -0.410654 -0.503762 + outer loop + vertex 844.609 259.378 281.803 + vertex 844.026 258.807 283.149 + vertex 843.461 262.789 280.755 + endloop + endfacet + facet normal -0.759649 -0.402333 -0.510942 + outer loop + vertex 843.727 257.396 284.704 + vertex 842.583 260.875 283.666 + vertex 844.026 258.807 283.149 + endloop + endfacet + facet normal -0.764212 -0.408469 -0.499132 + outer loop + vertex 842.583 260.875 283.666 + vertex 843.461 262.789 280.755 + vertex 844.026 258.807 283.149 + endloop + endfacet + facet normal -0.695536 -0.501606 -0.514414 + outer loop + vertex 844.026 258.807 283.149 + vertex 844.609 259.378 281.803 + vertex 845.228 256.989 283.296 + endloop + endfacet + facet normal -0.677927 -0.507776 -0.531581 + outer loop + vertex 845.228 256.989 283.296 + vertex 844.609 259.378 281.803 + vertex 845.651 258.016 281.777 + endloop + endfacet + facet normal -0.652026 -0.494958 -0.57435 + outer loop + vertex 843.727 257.396 284.704 + vertex 844.026 258.807 283.149 + vertex 844.784 255.958 284.743 + endloop + endfacet + facet normal -0.672426 -0.489613 -0.555089 + outer loop + vertex 844.784 255.958 284.743 + vertex 844.026 258.807 283.149 + vertex 845.228 256.989 283.296 + endloop + endfacet + facet normal -0.538887 -0.59911 -0.592173 + outer loop + vertex 844.784 255.958 284.743 + vertex 845.228 256.989 283.296 + vertex 846.04 254.653 284.921 + endloop + endfacet + facet normal -0.542146 -0.598559 -0.58975 + outer loop + vertex 846.04 254.653 284.921 + vertex 845.228 256.989 283.296 + vertex 846.47 255.721 283.441 + endloop + endfacet + facet normal -0.555618 -0.609054 -0.565987 + outer loop + vertex 845.228 256.989 283.296 + vertex 845.651 258.016 281.777 + vertex 846.47 255.721 283.441 + endloop + endfacet + facet normal -0.561541 -0.607854 -0.561415 + outer loop + vertex 846.47 255.721 283.441 + vertex 845.651 258.016 281.777 + vertex 846.876 256.776 281.893 + endloop + endfacet + facet normal -0.72346 -0.511688 -0.463445 + outer loop + vertex 844.866 260.778 280.117 + vertex 845.402 261.344 278.656 + vertex 846.048 259.034 280.197 + endloop + endfacet + facet normal -0.707322 -0.518518 -0.480453 + outer loop + vertex 846.048 259.034 280.197 + vertex 845.402 261.344 278.656 + vertex 846.418 260.032 278.575 + endloop + endfacet + facet normal -0.680327 -0.509704 -0.526647 + outer loop + vertex 844.609 259.378 281.803 + vertex 844.866 260.778 280.117 + vertex 845.651 258.016 281.777 + endloop + endfacet + facet normal -0.705638 -0.501324 -0.500749 + outer loop + vertex 845.651 258.016 281.777 + vertex 844.866 260.778 280.117 + vertex 846.048 259.034 280.197 + endloop + endfacet + facet normal -0.572035 -0.616332 -0.541212 + outer loop + vertex 845.651 258.016 281.777 + vertex 846.048 259.034 280.197 + vertex 846.876 256.776 281.893 + endloop + endfacet + facet normal -0.574869 -0.615674 -0.538954 + outer loop + vertex 846.876 256.776 281.893 + vertex 846.048 259.034 280.197 + vertex 847.257 257.821 280.292 + endloop + endfacet + facet normal -0.585107 -0.624211 -0.517697 + outer loop + vertex 846.048 259.034 280.197 + vertex 846.418 260.032 278.575 + vertex 847.257 257.821 280.292 + endloop + endfacet + facet normal -0.592849 -0.62218 -0.511296 + outer loop + vertex 847.257 257.821 280.292 + vertex 846.418 260.032 278.575 + vertex 847.608 258.835 278.653 + endloop + endfacet + facet normal -0.870813 -0.276149 -0.406726 + outer loop + vertex 840.14 271.549 281.182 + vertex 841.15 272.402 278.439 + vertex 841.711 266.852 281.006 + endloop + endfacet + facet normal -0.876536 -0.272215 -0.396968 + outer loop + vertex 841.711 266.852 281.006 + vertex 841.15 272.402 278.439 + vertex 842.526 268.657 277.97 + endloop + endfacet + facet normal -0.835838 -0.27538 -0.47491 + outer loop + vertex 839.354 268.755 284.185 + vertex 840.14 271.549 281.182 + vertex 840.793 264.971 283.846 + endloop + endfacet + facet normal -0.850723 -0.267715 -0.452327 + outer loop + vertex 840.793 264.971 283.846 + vertex 840.14 271.549 281.182 + vertex 841.711 266.852 281.006 + endloop + endfacet + facet normal -0.810271 -0.332828 -0.482376 + outer loop + vertex 840.793 264.971 283.846 + vertex 841.711 266.852 281.006 + vertex 842.583 260.875 283.666 + endloop + endfacet + facet normal -0.824054 -0.326267 -0.463125 + outer loop + vertex 842.583 260.875 283.666 + vertex 841.711 266.852 281.006 + vertex 843.461 262.789 280.755 + endloop + endfacet + facet normal -0.840586 -0.335731 -0.425087 + outer loop + vertex 841.711 266.852 281.006 + vertex 842.526 268.657 277.97 + vertex 843.461 262.789 280.755 + endloop + endfacet + facet normal -0.850801 -0.32978 -0.409124 + outer loop + vertex 843.461 262.789 280.755 + vertex 842.526 268.657 277.97 + vertex 844.239 264.652 277.636 + endloop + endfacet + facet normal -0.882756 -0.24441 -0.401255 + outer loop + vertex 841.15 272.402 278.439 + vertex 840.14 271.549 281.182 + vertex 839.946 279.8 276.582 + endloop + endfacet + facet normal -0.868798 -0.228066 -0.439518 + outer loop + vertex 839.354 268.755 284.185 + vertex 838.25 276.409 282.396 + vertex 840.14 271.549 281.182 + endloop + endfacet + facet normal -0.883556 -0.24369 -0.39993 + outer loop + vertex 838.25 276.409 282.396 + vertex 839.946 279.8 276.582 + vertex 840.14 271.549 281.182 + endloop + endfacet + facet normal -0.900508 -0.20069 -0.385757 + outer loop + vertex 836.2 285.136 282.641 + vertex 837.907 288.269 277.027 + vertex 838.25 276.409 282.396 + endloop + endfacet + facet normal -0.903965 -0.197783 -0.379115 + outer loop + vertex 838.25 276.409 282.396 + vertex 837.907 288.269 277.027 + vertex 839.946 279.8 276.582 + endloop + endfacet + facet normal -0.903536 -0.193111 -0.382531 + outer loop + vertex 834.317 293.595 282.817 + vertex 836.013 296.572 277.31 + vertex 836.2 285.136 282.641 + endloop + endfacet + facet normal -0.903584 -0.19307 -0.38244 + outer loop + vertex 836.2 285.136 282.641 + vertex 836.013 296.572 277.31 + vertex 837.907 288.269 277.027 + endloop + endfacet + facet normal -0.896666 -0.212608 -0.388313 + outer loop + vertex 832.38 301.694 282.857 + vertex 834.055 304.591 277.403 + vertex 834.317 293.595 282.817 + endloop + endfacet + facet normal -0.895072 -0.214 -0.391217 + outer loop + vertex 834.317 293.595 282.817 + vertex 834.055 304.591 277.403 + vertex 836.013 296.572 277.31 + endloop + endfacet + facet normal -0.88711 -0.24269 -0.392604 + outer loop + vertex 830.22 309.586 282.858 + vertex 831.88 312.372 277.386 + vertex 832.38 301.694 282.857 + endloop + endfacet + facet normal -0.881566 -0.247296 -0.402102 + outer loop + vertex 832.38 301.694 282.857 + vertex 831.88 312.372 277.386 + vertex 834.055 304.591 277.403 + endloop + endfacet + facet normal -0.874849 -0.278047 -0.396648 + outer loop + vertex 827.75 317.39 282.835 + vertex 829.413 319.969 277.36 + vertex 830.22 309.586 282.858 + endloop + endfacet + facet normal -0.868147 -0.283283 -0.407519 + outer loop + vertex 830.22 309.586 282.858 + vertex 829.413 319.969 277.36 + vertex 831.88 312.372 277.386 + endloop + endfacet + facet normal -0.86536 -0.310289 -0.39354 + outer loop + vertex 824.998 325.037 282.858 + vertex 826.655 327.392 277.356 + vertex 827.75 317.39 282.835 + endloop + endfacet + facet normal -0.855169 -0.317882 -0.409435 + outer loop + vertex 827.75 317.39 282.835 + vertex 826.655 327.392 277.356 + vertex 829.413 319.969 277.36 + endloop + endfacet + facet normal -0.855216 -0.342205 -0.389232 + outer loop + vertex 821.998 332.532 282.86 + vertex 823.65 334.651 277.367 + vertex 824.998 325.037 282.858 + endloop + endfacet + facet normal -0.8453 -0.34938 -0.404231 + outer loop + vertex 824.998 325.037 282.858 + vertex 823.65 334.651 277.367 + vertex 826.655 327.392 277.356 + endloop + endfacet + facet normal -0.849309 -0.367549 -0.378922 + outer loop + vertex 818.796 339.926 282.864 + vertex 820.438 341.797 277.369 + vertex 821.998 332.532 282.86 + endloop + endfacet + facet normal -0.837215 -0.376187 -0.396932 + outer loop + vertex 821.998 332.532 282.86 + vertex 820.438 341.797 277.369 + vertex 823.65 334.651 277.367 + endloop + endfacet + facet normal -0.845689 -0.388038 -0.366384 + outer loop + vertex 815.424 347.28 282.86 + vertex 817.062 348.885 277.38 + vertex 818.796 339.926 282.864 + endloop + endfacet + facet normal -0.833737 -0.39661 -0.384166 + outer loop + vertex 818.796 339.926 282.864 + vertex 817.062 348.885 277.38 + vertex 820.438 341.797 277.369 + endloop + endfacet + facet normal -0.845653 -0.405455 -0.347099 + outer loop + vertex 811.912 354.58 282.889 + vertex 813.54 355.907 277.371 + vertex 815.424 347.28 282.86 + endloop + endfacet + facet normal -0.830225 -0.416769 -0.370177 + outer loop + vertex 815.424 347.28 282.86 + vertex 813.54 355.907 277.371 + vertex 817.062 348.885 277.38 + endloop + endfacet + facet normal -0.844979 -0.421153 -0.329607 + outer loop + vertex 808.289 361.836 282.904 + vertex 809.921 362.856 277.417 + vertex 811.912 354.58 282.889 + endloop + endfacet + facet normal -0.83203 -0.431009 -0.349223 + outer loop + vertex 811.912 354.58 282.889 + vertex 809.921 362.856 277.417 + vertex 813.54 355.907 277.371 + endloop + endfacet + facet normal -0.851681 -0.426206 -0.30494 + outer loop + vertex 804.654 369.095 282.912 + vertex 806.265 369.764 277.478 + vertex 808.289 361.836 282.904 + endloop + endfacet + facet normal -0.835461 -0.439323 -0.330151 + outer loop + vertex 808.289 361.836 282.904 + vertex 806.265 369.764 277.478 + vertex 809.921 362.856 277.417 + endloop + endfacet + facet normal -0.874363 -0.398228 -0.277317 + outer loop + vertex 801.245 376.574 282.922 + vertex 802.836 376.857 277.498 + vertex 804.654 369.095 282.912 + endloop + endfacet + facet normal -0.8577 -0.413772 -0.305195 + outer loop + vertex 804.654 369.095 282.912 + vertex 802.836 376.857 277.498 + vertex 806.265 369.764 277.478 + endloop + endfacet + facet normal -0.913008 -0.302529 -0.273665 + outer loop + vertex 798.384 384.625 283.564 + vertex 800.151 384.545 277.757 + vertex 801.245 376.574 282.922 + endloop + endfacet + facet normal -0.908539 -0.307713 -0.282611 + outer loop + vertex 801.245 376.574 282.922 + vertex 800.151 384.545 277.757 + vertex 802.836 376.857 277.498 + endloop + endfacet + facet normal -0.0894525 -0.87902 -0.468317 + outer loop + vertex 852.7 259.229 275.177 + vertex 852.967 260.052 273.581 + vertex 853.21 258.963 275.578 + endloop + endfacet + facet normal -0.0922911 -0.886866 -0.452715 + outer loop + vertex 853.039 260.951 271.805 + vertex 853.568 260.563 272.456 + vertex 852.967 260.052 273.581 + endloop + endfacet + facet normal -0.120838 -0.877674 -0.463775 + outer loop + vertex 853.568 260.563 272.456 + vertex 853.21 258.963 275.578 + vertex 852.967 260.052 273.581 + endloop + endfacet + facet normal -0.0869987 -0.859734 -0.503278 + outer loop + vertex 852.285 257.33 278.572 + vertex 852.593 258.261 276.929 + vertex 852.87 257.186 278.717 + endloop + endfacet + facet normal -0.0718469 -0.871261 -0.485534 + outer loop + vertex 852.7 259.229 275.177 + vertex 853.21 258.963 275.578 + vertex 852.593 258.261 276.929 + endloop + endfacet + facet normal -0.114412 -0.859189 -0.498702 + outer loop + vertex 853.21 258.963 275.578 + vertex 852.87 257.186 278.717 + vertex 852.593 258.261 276.929 + endloop + endfacet + facet normal -0.478279 -0.752296 -0.453101 + outer loop + vertex 848.482 261.682 273.581 + vertex 848.72 262.564 271.866 + vertex 849.712 260.841 273.681 + endloop + endfacet + facet normal -0.486919 -0.750561 -0.446731 + outer loop + vertex 849.712 260.841 273.681 + vertex 848.72 262.564 271.866 + vertex 849.932 261.731 271.944 + endloop + endfacet + facet normal -0.46685 -0.748467 -0.471007 + outer loop + vertex 848.219 260.77 275.292 + vertex 848.482 261.682 273.581 + vertex 849.465 259.917 275.412 + endloop + endfacet + facet normal -0.47375 -0.74721 -0.466089 + outer loop + vertex 849.465 259.917 275.412 + vertex 848.482 261.682 273.581 + vertex 849.712 260.841 273.681 + endloop + endfacet + facet normal -0.304214 -0.821821 -0.481729 + outer loop + vertex 849.465 259.917 275.412 + vertex 849.712 260.841 273.681 + vertex 850.743 259.383 275.516 + endloop + endfacet + facet normal -0.311326 -0.821595 -0.477554 + outer loop + vertex 850.743 259.383 275.516 + vertex 849.712 260.841 273.681 + vertex 850.971 260.311 273.771 + endloop + endfacet + facet normal -0.31485 -0.827748 -0.464437 + outer loop + vertex 849.712 260.841 273.681 + vertex 849.932 261.731 271.944 + vertex 850.971 260.311 273.771 + endloop + endfacet + facet normal -0.32249 -0.827389 -0.459813 + outer loop + vertex 850.971 260.311 273.771 + vertex 849.932 261.731 271.944 + vertex 851.169 261.204 272.025 + endloop + endfacet + facet normal -0.452007 -0.74201 -0.495087 + outer loop + vertex 847.928 259.818 276.985 + vertex 848.219 260.77 275.292 + vertex 849.192 258.956 277.123 + endloop + endfacet + facet normal -0.459788 -0.740781 -0.489732 + outer loop + vertex 849.192 258.956 277.123 + vertex 848.219 260.77 275.292 + vertex 849.465 259.917 275.412 + endloop + endfacet + facet normal -0.438122 -0.735167 -0.51728 + outer loop + vertex 847.608 258.835 278.653 + vertex 847.928 259.818 276.985 + vertex 848.893 257.963 278.803 + endloop + endfacet + facet normal -0.444794 -0.734277 -0.512831 + outer loop + vertex 848.893 257.963 278.803 + vertex 847.928 259.818 276.985 + vertex 849.192 258.956 277.123 + endloop + endfacet + facet normal -0.276882 -0.805007 -0.52469 + outer loop + vertex 848.893 257.963 278.803 + vertex 849.192 258.956 277.123 + vertex 850.214 257.417 278.944 + endloop + endfacet + facet normal -0.285832 -0.805092 -0.519737 + outer loop + vertex 850.214 257.417 278.944 + vertex 849.192 258.956 277.123 + vertex 850.492 258.414 277.247 + endloop + endfacet + facet normal -0.290863 -0.813475 -0.503644 + outer loop + vertex 849.192 258.956 277.123 + vertex 849.465 259.917 275.412 + vertex 850.492 258.414 277.247 + endloop + endfacet + facet normal -0.299294 -0.813375 -0.498842 + outer loop + vertex 850.492 258.414 277.247 + vertex 849.465 259.917 275.412 + vertex 850.743 259.383 275.516 + endloop + endfacet + facet normal -0.168243 -0.849492 -0.500058 + outer loop + vertex 850.492 258.414 277.247 + vertex 850.743 259.383 275.516 + vertex 851.677 258.198 277.215 + endloop + endfacet + facet normal -0.179569 -0.850433 -0.494488 + outer loop + vertex 851.677 258.198 277.215 + vertex 850.743 259.383 275.516 + vertex 851.904 259.157 275.483 + endloop + endfacet + facet normal -0.155508 -0.840411 -0.519159 + outer loop + vertex 850.214 257.417 278.944 + vertex 850.492 258.414 277.247 + vertex 851.421 257.204 278.927 + endloop + endfacet + facet normal -0.16717 -0.841607 -0.513567 + outer loop + vertex 851.421 257.204 278.927 + vertex 850.492 258.414 277.247 + vertex 851.677 258.198 277.215 + endloop + endfacet + facet normal -0.0842941 -0.856225 -0.50968 + outer loop + vertex 851.421 257.204 278.927 + vertex 851.677 258.198 277.215 + vertex 852.285 257.33 278.572 + endloop + endfacet + facet normal -0.098484 -0.857855 -0.504367 + outer loop + vertex 852.285 257.33 278.572 + vertex 851.677 258.198 277.215 + vertex 852.593 258.261 276.929 + endloop + endfacet + facet normal -0.0939818 -0.86568 -0.491697 + outer loop + vertex 851.677 258.198 277.215 + vertex 851.904 259.157 275.483 + vertex 852.593 258.261 276.929 + endloop + endfacet + facet normal -0.108876 -0.867351 -0.485643 + outer loop + vertex 852.593 258.261 276.929 + vertex 851.904 259.157 275.483 + vertex 852.7 259.229 275.177 + endloop + endfacet + facet normal -0.189978 -0.86516 -0.464119 + outer loop + vertex 850.971 260.311 273.771 + vertex 851.169 261.204 272.025 + vertex 852.105 260.073 273.75 + endloop + endfacet + facet normal -0.200482 -0.865656 -0.458745 + outer loop + vertex 852.105 260.073 273.75 + vertex 851.169 261.204 272.025 + vertex 852.278 260.949 272.021 + endloop + endfacet + facet normal -0.180702 -0.858423 -0.480059 + outer loop + vertex 850.743 259.383 275.516 + vertex 850.971 260.311 273.771 + vertex 851.904 259.157 275.483 + endloop + endfacet + facet normal -0.188892 -0.858949 -0.475948 + outer loop + vertex 851.904 259.157 275.483 + vertex 850.971 260.311 273.771 + vertex 852.105 260.073 273.75 + endloop + endfacet + facet normal -0.103859 -0.874273 -0.474195 + outer loop + vertex 851.904 259.157 275.483 + vertex 852.105 260.073 273.75 + vertex 852.7 259.229 275.177 + endloop + endfacet + facet normal -0.114083 -0.875051 -0.470393 + outer loop + vertex 852.7 259.229 275.177 + vertex 852.105 260.073 273.75 + vertex 852.967 260.052 273.581 + endloop + endfacet + facet normal -0.111844 -0.881843 -0.458088 + outer loop + vertex 852.105 260.073 273.75 + vertex 852.278 260.949 272.021 + vertex 852.967 260.052 273.581 + endloop + endfacet + facet normal -0.126765 -0.882909 -0.452108 + outer loop + vertex 852.967 260.052 273.581 + vertex 852.278 260.949 272.021 + vertex 853.039 260.951 271.805 + endloop + endfacet + facet normal -0.83399 -0.422088 -0.35539 + outer loop + vertex 846.633 264.968 272.007 + vertex 846.211 264.489 273.565 + vertex 845.46 268.098 271.042 + endloop + endfacet + facet normal -0.837222 -0.414996 -0.356144 + outer loop + vertex 846.075 263.218 275.367 + vertex 844.903 266.428 274.381 + vertex 846.211 264.489 273.565 + endloop + endfacet + facet normal -0.838321 -0.418661 -0.349199 + outer loop + vertex 844.903 266.428 274.381 + vertex 845.46 268.098 271.042 + vertex 846.211 264.489 273.565 + endloop + endfacet + facet normal -0.815305 -0.420026 -0.398568 + outer loop + vertex 846.075 263.218 275.367 + vertex 845.6 262.692 276.893 + vertex 844.903 266.428 274.381 + endloop + endfacet + facet normal -0.815397 -0.412047 -0.406627 + outer loop + vertex 845.402 261.344 278.656 + vertex 844.239 264.652 277.636 + vertex 845.6 262.692 276.893 + endloop + endfacet + facet normal -0.817937 -0.418183 -0.395098 + outer loop + vertex 844.239 264.652 277.636 + vertex 844.903 266.428 274.381 + vertex 845.6 262.692 276.893 + endloop + endfacet + facet normal -0.749413 -0.518327 -0.411969 + outer loop + vertex 845.6 262.692 276.893 + vertex 846.075 263.218 275.367 + vertex 846.755 261 276.921 + endloop + endfacet + facet normal -0.735229 -0.525393 -0.428254 + outer loop + vertex 846.755 261 276.921 + vertex 846.075 263.218 275.367 + vertex 847.061 261.936 275.246 + endloop + endfacet + facet normal -0.708698 -0.519794 -0.477034 + outer loop + vertex 845.402 261.344 278.656 + vertex 845.6 262.692 276.893 + vertex 846.418 260.032 278.575 + endloop + endfacet + facet normal -0.735188 -0.509217 -0.447434 + outer loop + vertex 846.418 260.032 278.575 + vertex 845.6 262.692 276.893 + vertex 846.755 261 276.921 + endloop + endfacet + facet normal -0.601922 -0.629869 -0.490871 + outer loop + vertex 846.418 260.032 278.575 + vertex 846.755 261 276.921 + vertex 847.608 258.835 278.653 + endloop + endfacet + facet normal -0.606754 -0.628453 -0.48672 + outer loop + vertex 847.608 258.835 278.653 + vertex 846.755 261 276.921 + vertex 847.928 259.818 276.985 + endloop + endfacet + facet normal -0.614662 -0.635272 -0.467569 + outer loop + vertex 846.755 261 276.921 + vertex 847.061 261.936 275.246 + vertex 847.928 259.818 276.985 + endloop + endfacet + facet normal -0.619793 -0.633626 -0.463007 + outer loop + vertex 847.928 259.818 276.985 + vertex 847.061 261.936 275.246 + vertex 848.219 260.77 275.292 + endloop + endfacet + facet normal -0.768425 -0.523052 -0.368699 + outer loop + vertex 846.211 264.489 273.565 + vertex 846.633 264.968 272.007 + vertex 847.34 262.839 273.554 + endloop + endfacet + facet normal -0.758496 -0.528697 -0.381003 + outer loop + vertex 847.34 262.839 273.554 + vertex 846.633 264.968 272.007 + vertex 847.591 263.703 271.855 + endloop + endfacet + facet normal -0.735736 -0.525927 -0.426725 + outer loop + vertex 846.075 263.218 275.367 + vertex 846.211 264.489 273.565 + vertex 847.061 261.936 275.246 + endloop + endfacet + facet normal -0.757809 -0.515591 -0.399864 + outer loop + vertex 847.061 261.936 275.246 + vertex 846.211 264.489 273.565 + vertex 847.34 262.839 273.554 + endloop + endfacet + facet normal -0.626802 -0.639855 -0.44464 + outer loop + vertex 847.061 261.936 275.246 + vertex 847.34 262.839 273.554 + vertex 848.219 260.77 275.292 + endloop + endfacet + facet normal -0.634687 -0.637092 -0.437362 + outer loop + vertex 848.219 260.77 275.292 + vertex 847.34 262.839 273.554 + vertex 848.482 261.682 273.581 + endloop + endfacet + facet normal -0.640304 -0.642263 -0.421318 + outer loop + vertex 847.34 262.839 273.554 + vertex 847.591 263.703 271.855 + vertex 848.482 261.682 273.581 + endloop + endfacet + facet normal -0.642848 -0.64131 -0.418889 + outer loop + vertex 848.482 261.682 273.581 + vertex 847.591 263.703 271.855 + vertex 848.72 262.564 271.866 + endloop + endfacet + facet normal -0.9122 -0.255685 -0.320182 + outer loop + vertex 831.88 312.372 277.386 + vertex 833.339 315.125 271.031 + vertex 834.055 304.591 277.403 + endloop + endfacet + facet normal -0.908382 -0.25989 -0.327564 + outer loop + vertex 834.055 304.591 277.403 + vertex 833.339 315.125 271.031 + vertex 835.512 307.488 271.063 + endloop + endfacet + facet normal -0.899012 -0.293015 -0.325453 + outer loop + vertex 829.413 319.969 277.36 + vertex 830.88 322.543 270.991 + vertex 831.88 312.372 277.386 + endloop + endfacet + facet normal -0.894023 -0.298154 -0.334406 + outer loop + vertex 831.88 312.372 277.386 + vertex 830.88 322.543 270.991 + vertex 833.339 315.125 271.031 + endloop + endfacet + facet normal -0.886629 -0.329528 -0.324499 + outer loop + vertex 826.655 327.392 277.356 + vertex 828.118 329.743 270.974 + vertex 829.413 319.969 277.36 + endloop + endfacet + facet normal -0.878195 -0.337702 -0.33872 + outer loop + vertex 829.413 319.969 277.36 + vertex 828.118 329.743 270.974 + vertex 830.88 322.543 270.991 + endloop + endfacet + facet normal -0.875856 -0.362162 -0.318928 + outer loop + vertex 823.65 334.651 277.367 + vertex 825.104 336.761 270.979 + vertex 826.655 327.392 277.356 + endloop + endfacet + facet normal -0.865776 -0.371574 -0.335208 + outer loop + vertex 826.655 327.392 277.356 + vertex 825.104 336.761 270.979 + vertex 828.118 329.743 270.974 + endloop + endfacet + facet normal -0.866975 -0.389587 -0.310768 + outer loop + vertex 820.438 341.797 277.369 + vertex 821.89 343.657 270.988 + vertex 823.65 334.651 277.367 + endloop + endfacet + facet normal -0.856809 -0.398906 -0.326729 + outer loop + vertex 823.65 334.651 277.367 + vertex 821.89 343.657 270.988 + vertex 825.104 336.761 270.979 + endloop + endfacet + facet normal -0.862639 -0.410513 -0.295523 + outer loop + vertex 817.062 348.885 277.38 + vertex 818.501 350.467 270.979 + vertex 820.438 341.797 277.369 + endloop + endfacet + facet normal -0.849141 -0.422896 -0.316416 + outer loop + vertex 820.438 341.797 277.369 + vertex 818.501 350.467 270.979 + vertex 821.89 343.657 270.988 + endloop + endfacet + facet normal -0.857511 -0.430342 -0.281925 + outer loop + vertex 813.54 355.907 277.371 + vertex 814.984 357.22 270.975 + vertex 817.062 348.885 277.38 + endloop + endfacet + facet normal -0.846179 -0.440889 -0.29933 + outer loop + vertex 817.062 348.885 277.38 + vertex 814.984 357.22 270.975 + vertex 818.501 350.467 270.979 + endloop + endfacet + facet normal -0.85601 -0.444063 -0.264678 + outer loop + vertex 809.921 362.856 277.417 + vertex 811.365 363.894 271.005 + vertex 813.54 355.907 277.371 + endloop + endfacet + facet normal -0.843416 -0.45605 -0.284021 + outer loop + vertex 813.54 355.907 277.371 + vertex 811.365 363.894 271.005 + vertex 814.984 357.22 270.975 + endloop + endfacet + facet normal -0.858041 -0.452027 -0.243799 + outer loop + vertex 806.265 369.764 277.478 + vertex 807.697 370.496 271.08 + vertex 809.921 362.856 277.417 + endloop + endfacet + facet normal -0.844022 -0.465966 -0.265524 + outer loop + vertex 809.921 362.856 277.417 + vertex 807.697 370.496 271.08 + vertex 811.365 363.894 271.005 + endloop + endfacet + facet normal -0.878989 -0.424314 -0.217569 + outer loop + vertex 802.836 376.857 277.498 + vertex 804.217 377.22 271.21 + vertex 806.265 369.764 277.478 + endloop + endfacet + facet normal -0.863221 -0.442045 -0.243815 + outer loop + vertex 806.265 369.764 277.478 + vertex 804.217 377.22 271.21 + vertex 807.697 370.496 271.08 + endloop + endfacet + facet normal -0.927945 -0.317424 -0.195348 + outer loop + vertex 800.151 384.545 277.757 + vertex 801.523 384.472 271.36 + vertex 802.836 376.857 277.498 + endloop + endfacet + facet normal -0.915812 -0.335637 -0.220537 + outer loop + vertex 802.836 376.857 277.498 + vertex 801.523 384.472 271.36 + vertex 804.217 377.22 271.21 + endloop + endfacet + facet normal -0.136562 -0.906458 -0.399605 + outer loop + vertex 853.292 262.6 268.272 + vertex 853.484 263.353 266.499 + vertex 853.842 262.361 268.628 + endloop + endfacet + facet normal -0.147576 -0.91104 -0.385003 + outer loop + vertex 853.499 264.163 264.577 + vertex 854.048 264.028 264.686 + vertex 853.484 263.353 266.499 + endloop + endfacet + facet normal -0.177084 -0.903096 -0.391227 + outer loop + vertex 854.048 264.028 264.686 + vertex 853.842 262.361 268.628 + vertex 853.484 263.353 266.499 + endloop + endfacet + facet normal -0.117933 -0.892538 -0.43528 + outer loop + vertex 853.039 260.951 271.805 + vertex 853.252 261.738 270.133 + vertex 853.568 260.563 272.456 + endloop + endfacet + facet normal -0.120802 -0.899703 -0.419454 + outer loop + vertex 853.292 262.6 268.272 + vertex 853.842 262.361 268.628 + vertex 853.252 261.738 270.133 + endloop + endfacet + facet normal -0.155197 -0.889923 -0.428894 + outer loop + vertex 853.842 262.361 268.628 + vertex 853.568 260.563 272.456 + vertex 853.252 261.738 270.133 + endloop + endfacet + facet normal -0.524198 -0.766038 -0.372024 + outer loop + vertex 849.292 264.983 266.691 + vertex 849.447 265.748 264.899 + vertex 850.457 264.157 266.751 + endloop + endfacet + facet normal -0.527329 -0.765104 -0.369515 + outer loop + vertex 850.457 264.157 266.751 + vertex 849.447 265.748 264.899 + vertex 850.597 264.925 264.961 + endloop + endfacet + facet normal -0.50974 -0.764922 -0.393776 + outer loop + vertex 849.121 264.201 268.432 + vertex 849.292 264.983 266.691 + vertex 850.302 263.383 268.492 + endloop + endfacet + facet normal -0.520666 -0.761998 -0.385053 + outer loop + vertex 850.302 263.383 268.492 + vertex 849.292 264.983 266.691 + vertex 850.457 264.157 266.751 + endloop + endfacet + facet normal -0.349538 -0.844211 -0.406362 + outer loop + vertex 850.302 263.383 268.492 + vertex 850.457 264.157 266.751 + vertex 851.499 262.847 268.577 + endloop + endfacet + facet normal -0.355209 -0.843603 -0.402692 + outer loop + vertex 851.499 262.847 268.577 + vertex 850.457 264.157 266.751 + vertex 851.634 263.621 266.836 + endloop + endfacet + facet normal -0.357861 -0.847671 -0.39165 + outer loop + vertex 850.457 264.157 266.751 + vertex 850.597 264.925 264.961 + vertex 851.634 263.621 266.836 + endloop + endfacet + facet normal -0.367745 -0.846361 -0.385275 + outer loop + vertex 851.634 263.621 266.836 + vertex 850.597 264.925 264.961 + vertex 851.758 264.383 265.043 + endloop + endfacet + facet normal -0.50355 -0.761133 -0.408796 + outer loop + vertex 848.932 263.403 270.151 + vertex 849.121 264.201 268.432 + vertex 850.129 262.577 270.216 + endloop + endfacet + facet normal -0.506036 -0.760531 -0.406842 + outer loop + vertex 850.129 262.577 270.216 + vertex 849.121 264.201 268.432 + vertex 850.302 263.383 268.492 + endloop + endfacet + facet normal -0.491986 -0.75646 -0.43095 + outer loop + vertex 848.72 262.564 271.866 + vertex 848.932 263.403 270.151 + vertex 849.932 261.731 271.944 + endloop + endfacet + facet normal -0.498408 -0.755037 -0.426038 + outer loop + vertex 849.932 261.731 271.944 + vertex 848.932 263.403 270.151 + vertex 850.129 262.577 270.216 + endloop + endfacet + facet normal -0.326249 -0.833952 -0.445067 + outer loop + vertex 849.932 261.731 271.944 + vertex 850.129 262.577 270.216 + vertex 851.169 261.204 272.025 + endloop + endfacet + facet normal -0.335298 -0.833361 -0.439414 + outer loop + vertex 851.169 261.204 272.025 + vertex 850.129 262.577 270.216 + vertex 851.345 262.044 270.297 + endloop + endfacet + facet normal -0.33849 -0.838712 -0.426599 + outer loop + vertex 850.129 262.577 270.216 + vertex 850.302 263.383 268.492 + vertex 851.345 262.044 270.297 + endloop + endfacet + facet normal -0.345698 -0.838107 -0.421983 + outer loop + vertex 851.345 262.044 270.297 + vertex 850.302 263.383 268.492 + vertex 851.499 262.847 268.577 + endloop + endfacet + facet normal -0.210399 -0.878555 -0.428804 + outer loop + vertex 851.345 262.044 270.297 + vertex 851.499 262.847 268.577 + vertex 852.429 261.782 270.302 + endloop + endfacet + facet normal -0.221144 -0.878688 -0.423088 + outer loop + vertex 852.429 261.782 270.302 + vertex 851.499 262.847 268.577 + vertex 852.566 262.578 268.578 + endloop + endfacet + facet normal -0.20202 -0.872519 -0.444857 + outer loop + vertex 851.169 261.204 272.025 + vertex 851.345 262.044 270.297 + vertex 852.278 260.949 272.021 + endloop + endfacet + facet normal -0.208932 -0.872724 -0.441248 + outer loop + vertex 852.278 260.949 272.021 + vertex 851.345 262.044 270.297 + vertex 852.429 261.782 270.302 + endloop + endfacet + facet normal -0.123734 -0.888693 -0.441492 + outer loop + vertex 852.278 260.949 272.021 + vertex 852.429 261.782 270.302 + vertex 853.039 260.951 271.805 + endloop + endfacet + facet normal -0.137485 -0.88927 -0.436231 + outer loop + vertex 853.039 260.951 271.805 + vertex 852.429 261.782 270.302 + vertex 853.252 261.738 270.133 + endloop + endfacet + facet normal -0.135316 -0.895488 -0.424018 + outer loop + vertex 852.429 261.782 270.302 + vertex 852.566 262.578 268.578 + vertex 853.252 261.738 270.133 + endloop + endfacet + facet normal -0.148834 -0.896014 -0.41834 + outer loop + vertex 853.252 261.738 270.133 + vertex 852.566 262.578 268.578 + vertex 853.292 262.6 268.272 + endloop + endfacet + facet normal -0.233034 -0.889059 -0.394042 + outer loop + vertex 851.634 263.621 266.836 + vertex 851.758 264.383 265.043 + vertex 852.686 263.355 266.815 + endloop + endfacet + facet normal -0.243607 -0.888743 -0.388319 + outer loop + vertex 852.686 263.355 266.815 + vertex 851.758 264.383 265.043 + vertex 852.796 264.12 264.995 + endloop + endfacet + facet normal -0.222567 -0.884285 -0.410492 + outer loop + vertex 851.499 262.847 268.577 + vertex 851.634 263.621 266.836 + vertex 852.566 262.578 268.578 + endloop + endfacet + facet normal -0.232036 -0.88421 -0.405378 + outer loop + vertex 852.566 262.578 268.578 + vertex 851.634 263.621 266.836 + vertex 852.686 263.355 266.815 + endloop + endfacet + facet normal -0.143944 -0.901934 -0.40718 + outer loop + vertex 852.566 262.578 268.578 + vertex 852.686 263.355 266.815 + vertex 853.292 262.6 268.272 + endloop + endfacet + facet normal -0.160576 -0.902164 -0.400394 + outer loop + vertex 853.292 262.6 268.272 + vertex 852.686 263.355 266.815 + vertex 853.484 263.353 266.499 + endloop + endfacet + facet normal -0.156782 -0.907035 -0.390777 + outer loop + vertex 852.686 263.355 266.815 + vertex 852.796 264.12 264.995 + vertex 853.484 263.353 266.499 + endloop + endfacet + facet normal -0.172721 -0.907214 -0.383576 + outer loop + vertex 853.484 263.353 266.499 + vertex 852.796 264.12 264.995 + vertex 853.499 264.163 264.577 + endloop + endfacet + facet normal -0.864805 -0.419394 -0.276082 + outer loop + vertex 847.464 268.116 265.12 + vertex 847.131 267.725 266.757 + vertex 846.309 271.171 264.097 + endloop + endfacet + facet normal -0.867219 -0.415508 -0.27438 + outer loop + vertex 847.089 266.587 268.614 + vertex 845.922 269.671 267.63 + vertex 847.131 267.725 266.757 + endloop + endfacet + facet normal -0.867412 -0.416758 -0.271862 + outer loop + vertex 845.922 269.671 267.63 + vertex 846.309 271.171 264.097 + vertex 847.131 267.725 266.757 + endloop + endfacet + facet normal -0.851748 -0.421439 -0.311312 + outer loop + vertex 847.089 266.587 268.614 + vertex 846.719 266.17 270.191 + vertex 845.922 269.671 267.63 + endloop + endfacet + facet normal -0.852207 -0.416838 -0.31621 + outer loop + vertex 846.633 264.968 272.007 + vertex 845.46 268.098 271.042 + vertex 846.719 266.17 270.191 + endloop + endfacet + facet normal -0.852979 -0.420338 -0.309422 + outer loop + vertex 845.46 268.098 271.042 + vertex 845.922 269.671 267.63 + vertex 846.719 266.17 270.191 + endloop + endfacet + facet normal -0.78925 -0.522076 -0.323298 + outer loop + vertex 846.719 266.17 270.191 + vertex 847.089 266.587 268.614 + vertex 847.816 264.533 270.155 + endloop + endfacet + facet normal -0.775848 -0.530725 -0.341161 + outer loop + vertex 847.816 264.533 270.155 + vertex 847.089 266.587 268.614 + vertex 848.02 265.332 268.448 + endloop + endfacet + facet normal -0.757425 -0.527423 -0.38488 + outer loop + vertex 846.633 264.968 272.007 + vertex 846.719 266.17 270.191 + vertex 847.591 263.703 271.855 + endloop + endfacet + facet normal -0.780086 -0.51524 -0.354956 + outer loop + vertex 847.591 263.703 271.855 + vertex 846.719 266.17 270.191 + vertex 847.816 264.533 270.155 + endloop + endfacet + facet normal -0.648449 -0.646701 -0.401611 + outer loop + vertex 847.591 263.703 271.855 + vertex 847.816 264.533 270.155 + vertex 848.72 262.564 271.866 + endloop + endfacet + facet normal -0.6539 -0.644527 -0.396232 + outer loop + vertex 848.72 262.564 271.866 + vertex 847.816 264.533 270.155 + vertex 848.932 263.403 270.151 + endloop + endfacet + facet normal -0.658064 -0.648685 -0.382309 + outer loop + vertex 847.816 264.533 270.155 + vertex 848.02 265.332 268.448 + vertex 848.932 263.403 270.151 + endloop + endfacet + facet normal -0.667491 -0.644641 -0.372684 + outer loop + vertex 848.932 263.403 270.151 + vertex 848.02 265.332 268.448 + vertex 849.121 264.201 268.432 + endloop + endfacet + facet normal -0.80168 -0.523729 -0.288127 + outer loop + vertex 847.131 267.725 266.757 + vertex 847.464 268.116 265.12 + vertex 848.204 266.106 266.714 + endloop + endfacet + facet normal -0.790826 -0.531671 -0.303184 + outer loop + vertex 848.204 266.106 266.714 + vertex 847.464 268.116 265.12 + vertex 848.373 266.871 264.93 + endloop + endfacet + facet normal -0.775498 -0.530266 -0.342668 + outer loop + vertex 847.089 266.587 268.614 + vertex 847.131 267.725 266.757 + vertex 848.02 265.332 268.448 + endloop + endfacet + facet normal -0.794728 -0.518388 -0.315725 + outer loop + vertex 848.02 265.332 268.448 + vertex 847.131 267.725 266.757 + vertex 848.204 266.106 266.714 + endloop + endfacet + facet normal -0.670855 -0.648081 -0.360479 + outer loop + vertex 848.02 265.332 268.448 + vertex 848.204 266.106 266.714 + vertex 849.121 264.201 268.432 + endloop + endfacet + facet normal -0.674361 -0.646465 -0.356819 + outer loop + vertex 849.121 264.201 268.432 + vertex 848.204 266.106 266.714 + vertex 849.292 264.983 266.691 + endloop + endfacet + facet normal -0.677844 -0.650122 -0.343322 + outer loop + vertex 848.204 266.106 266.714 + vertex 848.373 266.871 264.93 + vertex 849.292 264.983 266.691 + endloop + endfacet + facet normal -0.685871 -0.646115 -0.334838 + outer loop + vertex 849.292 264.983 266.691 + vertex 848.373 266.871 264.93 + vertex 849.447 265.748 264.899 + endloop + endfacet + facet normal -0.931512 -0.266143 -0.2479 + outer loop + vertex 833.339 315.125 271.031 + vertex 834.468 317.569 264.162 + vertex 835.512 307.488 271.063 + endloop + endfacet + facet normal -0.929574 -0.268876 -0.252185 + outer loop + vertex 835.512 307.488 271.063 + vertex 834.468 317.569 264.162 + vertex 836.622 310.073 264.215 + endloop + endfacet + facet normal -0.918717 -0.305879 -0.249795 + outer loop + vertex 830.88 322.543 270.991 + vertex 832.005 324.793 264.097 + vertex 833.339 315.125 271.031 + endloop + endfacet + facet normal -0.912776 -0.313605 -0.261709 + outer loop + vertex 833.339 315.125 271.031 + vertex 832.005 324.793 264.097 + vertex 834.468 317.569 264.162 + endloop + endfacet + facet normal -0.903663 -0.347262 -0.250602 + outer loop + vertex 828.118 329.743 270.974 + vertex 829.246 331.787 264.074 + vertex 830.88 322.543 270.991 + endloop + endfacet + facet normal -0.897351 -0.354904 -0.262305 + outer loop + vertex 830.88 322.543 270.991 + vertex 829.246 331.787 264.074 + vertex 832.005 324.793 264.097 + endloop + endfacet + facet normal -0.890581 -0.382289 -0.246417 + outer loop + vertex 825.104 336.761 270.979 + vertex 826.23 338.584 264.079 + vertex 828.118 329.743 270.974 + endloop + endfacet + facet normal -0.882666 -0.391378 -0.260238 + outer loop + vertex 828.118 329.743 270.974 + vertex 826.23 338.584 264.079 + vertex 829.246 331.787 264.074 + endloop + endfacet + facet normal -0.880771 -0.410194 -0.236607 + outer loop + vertex 821.89 343.657 270.988 + vertex 823.009 345.234 264.087 + vertex 825.104 336.761 270.979 + endloop + endfacet + facet normal -0.870694 -0.421454 -0.253514 + outer loop + vertex 825.104 336.761 270.979 + vertex 823.009 345.234 264.087 + vertex 826.23 338.584 264.079 + endloop + endfacet + facet normal -0.871988 -0.434153 -0.226161 + outer loop + vertex 818.501 350.467 270.979 + vertex 819.626 351.799 264.087 + vertex 821.89 343.657 270.988 + endloop + endfacet + facet normal -0.862583 -0.444549 -0.241511 + outer loop + vertex 821.89 343.657 270.988 + vertex 819.626 351.799 264.087 + vertex 823.009 345.234 264.087 + endloop + endfacet + facet normal -0.866953 -0.451656 -0.210713 + outer loop + vertex 814.984 357.22 270.975 + vertex 816.104 358.29 264.074 + vertex 818.501 350.467 270.979 + endloop + endfacet + facet normal -0.855354 -0.464525 -0.229317 + outer loop + vertex 818.501 350.467 270.979 + vertex 816.104 358.29 264.074 + vertex 819.626 351.799 264.087 + endloop + endfacet + facet normal -0.862627 -0.466868 -0.194702 + outer loop + vertex 811.365 363.894 271.005 + vertex 812.487 364.712 264.076 + vertex 814.984 357.22 270.975 + endloop + endfacet + facet normal -0.851408 -0.479526 -0.212508 + outer loop + vertex 814.984 357.22 270.975 + vertex 812.487 364.712 264.076 + vertex 816.104 358.29 264.074 + endloop + endfacet + facet normal -0.860838 -0.476283 -0.179198 + outer loop + vertex 807.697 370.496 271.08 + vertex 808.823 371.074 264.133 + vertex 811.365 363.894 271.005 + endloop + endfacet + facet normal -0.85068 -0.48807 -0.195271 + outer loop + vertex 811.365 363.894 271.005 + vertex 808.823 371.074 264.133 + vertex 812.487 364.712 264.076 + endloop + endfacet + facet normal -0.877939 -0.451286 -0.159884 + outer loop + vertex 804.217 377.22 271.21 + vertex 805.321 377.521 264.297 + vertex 807.697 370.496 271.08 + endloop + endfacet + facet normal -0.866392 -0.466083 -0.17925 + outer loop + vertex 807.697 370.496 271.08 + vertex 805.321 377.521 264.297 + vertex 808.823 371.074 264.133 + endloop + endfacet + facet normal -0.929579 -0.342488 -0.136326 + outer loop + vertex 801.523 384.472 271.36 + vertex 802.509 384.408 264.801 + vertex 804.217 377.22 271.21 + endloop + endfacet + facet normal -0.917588 -0.36286 -0.162371 + outer loop + vertex 804.217 377.22 271.21 + vertex 802.509 384.408 264.801 + vertex 805.321 377.521 264.297 + endloop + endfacet + facet normal -0.175457 -0.923543 -0.341004 + outer loop + vertex 853.645 265.616 260.831 + vertex 853.777 266.256 259.031 + vertex 854.119 265.377 261.236 + endloop + endfacet + facet normal -0.175546 -0.927622 -0.329699 + outer loop + vertex 853.745 266.965 257.054 + vertex 854.275 266.632 257.707 + vertex 853.777 266.256 259.031 + endloop + endfacet + facet normal -0.198381 -0.920627 -0.336291 + outer loop + vertex 854.275 266.632 257.707 + vertex 854.119 265.377 261.236 + vertex 853.777 266.256 259.031 + endloop + endfacet + facet normal -0.152183 -0.916853 -0.36908 + outer loop + vertex 853.499 264.163 264.577 + vertex 853.66 264.864 262.77 + vertex 854.048 264.028 264.686 + endloop + endfacet + facet normal -0.160956 -0.920458 -0.356161 + outer loop + vertex 853.645 265.616 260.831 + vertex 854.119 265.377 261.236 + vertex 853.66 264.864 262.77 + endloop + endfacet + facet normal -0.184954 -0.913971 -0.361177 + outer loop + vertex 854.119 265.377 261.236 + vertex 854.048 264.028 264.686 + vertex 853.66 264.864 262.77 + endloop + endfacet + facet normal -0.557733 -0.771082 -0.30719 + outer loop + vertex 849.827 267.992 259.193 + vertex 849.929 268.687 257.265 + vertex 850.94 267.167 259.246 + endloop + endfacet + facet normal -0.56357 -0.768727 -0.302405 + outer loop + vertex 850.94 267.167 259.246 + vertex 849.929 268.687 257.265 + vertex 851.028 267.863 257.31 + endloop + endfacet + facet normal -0.552342 -0.76977 -0.319956 + outer loop + vertex 849.715 267.266 261.134 + vertex 849.827 267.992 259.193 + vertex 850.839 266.437 261.19 + endloop + endfacet + facet normal -0.555398 -0.768591 -0.317491 + outer loop + vertex 850.839 266.437 261.19 + vertex 849.827 267.992 259.193 + vertex 850.94 267.167 259.246 + endloop + endfacet + facet normal -0.390013 -0.855195 -0.341367 + outer loop + vertex 850.839 266.437 261.19 + vertex 850.94 267.167 259.246 + vertex 851.976 265.891 261.259 + endloop + endfacet + facet normal -0.397496 -0.85366 -0.336543 + outer loop + vertex 851.976 265.891 261.259 + vertex 850.94 267.167 259.246 + vertex 852.062 266.62 259.306 + endloop + endfacet + facet normal -0.399469 -0.856605 -0.326577 + outer loop + vertex 850.94 267.167 259.246 + vertex 851.028 267.863 257.31 + vertex 852.062 266.62 259.306 + endloop + endfacet + facet normal -0.407268 -0.854867 -0.321457 + outer loop + vertex 852.062 266.62 259.306 + vertex 851.028 267.863 257.31 + vertex 852.132 267.315 257.37 + endloop + endfacet + facet normal -0.539702 -0.76955 -0.341344 + outer loop + vertex 849.588 266.508 263.044 + vertex 849.715 267.266 261.134 + vertex 850.724 265.684 263.105 + endloop + endfacet + facet normal -0.549016 -0.766218 -0.333905 + outer loop + vertex 850.724 265.684 263.105 + vertex 849.715 267.266 261.134 + vertex 850.839 266.437 261.19 + endloop + endfacet + facet normal -0.530986 -0.769169 -0.355573 + outer loop + vertex 849.447 265.748 264.899 + vertex 849.588 266.508 263.044 + vertex 850.597 264.925 264.961 + endloop + endfacet + facet normal -0.537403 -0.76706 -0.350453 + outer loop + vertex 850.597 264.925 264.961 + vertex 849.588 266.508 263.044 + vertex 850.724 265.684 263.105 + endloop + endfacet + facet normal -0.370555 -0.850548 -0.373172 + outer loop + vertex 850.597 264.925 264.961 + vertex 850.724 265.684 263.105 + vertex 851.758 264.383 265.043 + endloop + endfacet + facet normal -0.377649 -0.849411 -0.368623 + outer loop + vertex 851.758 264.383 265.043 + vertex 850.724 265.684 263.105 + vertex 851.873 265.14 263.181 + endloop + endfacet + facet normal -0.380021 -0.852927 -0.357909 + outer loop + vertex 850.724 265.684 263.105 + vertex 850.839 266.437 261.19 + vertex 851.873 265.14 263.181 + endloop + endfacet + facet normal -0.387559 -0.851543 -0.353089 + outer loop + vertex 851.873 265.14 263.181 + vertex 850.839 266.437 261.19 + vertex 851.976 265.891 261.259 + endloop + endfacet + facet normal -0.253859 -0.896361 -0.363446 + outer loop + vertex 851.873 265.14 263.181 + vertex 851.976 265.891 261.259 + vertex 852.894 264.879 263.112 + endloop + endfacet + facet normal -0.265592 -0.895487 -0.35716 + outer loop + vertex 852.894 264.879 263.112 + vertex 851.976 265.891 261.259 + vertex 852.98 265.62 261.19 + endloop + endfacet + facet normal -0.244202 -0.892977 -0.378096 + outer loop + vertex 851.758 264.383 265.043 + vertex 851.873 265.14 263.181 + vertex 852.796 264.12 264.995 + endloop + endfacet + facet normal -0.253521 -0.89249 -0.37308 + outer loop + vertex 852.796 264.12 264.995 + vertex 851.873 265.14 263.181 + vertex 852.894 264.879 263.112 + endloop + endfacet + facet normal -0.168077 -0.911175 -0.376179 + outer loop + vertex 852.796 264.12 264.995 + vertex 852.894 264.879 263.112 + vertex 853.499 264.163 264.577 + endloop + endfacet + facet normal -0.183717 -0.910861 -0.369568 + outer loop + vertex 853.499 264.163 264.577 + vertex 852.894 264.879 263.112 + vertex 853.66 264.864 262.77 + endloop + endfacet + facet normal -0.179917 -0.915093 -0.360881 + outer loop + vertex 852.894 264.879 263.112 + vertex 852.98 265.62 261.19 + vertex 853.66 264.864 262.77 + endloop + endfacet + facet normal -0.196222 -0.914577 -0.353619 + outer loop + vertex 853.66 264.864 262.77 + vertex 852.98 265.62 261.19 + vertex 853.645 265.616 260.831 + endloop + endfacet + facet normal -0.276641 -0.90129 -0.333386 + outer loop + vertex 852.062 266.62 259.306 + vertex 852.132 267.315 257.37 + vertex 853.047 266.336 259.257 + endloop + endfacet + facet normal -0.287976 -0.899999 -0.327218 + outer loop + vertex 853.047 266.336 259.257 + vertex 852.132 267.315 257.37 + vertex 853.101 267.017 257.338 + endloop + endfacet + facet normal -0.265919 -0.899085 -0.347756 + outer loop + vertex 851.976 265.891 261.259 + vertex 852.062 266.62 259.306 + vertex 852.98 265.62 261.19 + endloop + endfacet + facet normal -0.27617 -0.89811 -0.34224 + outer loop + vertex 852.98 265.62 261.19 + vertex 852.062 266.62 259.306 + vertex 853.047 266.336 259.257 + endloop + endfacet + facet normal -0.192519 -0.918002 -0.346711 + outer loop + vertex 852.98 265.62 261.19 + vertex 853.047 266.336 259.257 + vertex 853.645 265.616 260.831 + endloop + endfacet + facet normal -0.206482 -0.917109 -0.340994 + outer loop + vertex 853.645 265.616 260.831 + vertex 853.047 266.336 259.257 + vertex 853.777 266.256 259.031 + endloop + endfacet + facet normal -0.204179 -0.920834 -0.332229 + outer loop + vertex 853.047 266.336 259.257 + vertex 853.101 267.017 257.338 + vertex 853.777 266.256 259.031 + endloop + endfacet + facet normal -0.218109 -0.919795 -0.326199 + outer loop + vertex 853.777 266.256 259.031 + vertex 853.101 267.017 257.338 + vertex 853.745 266.965 257.054 + endloop + endfacet + facet normal -0.885637 -0.412104 -0.21405 + outer loop + vertex 848.043 271.039 257.568 + vertex 847.768 270.698 259.362 + vertex 846.907 273.974 256.62 + endloop + endfacet + facet normal -0.887049 -0.410223 -0.211804 + outer loop + vertex 847.781 269.615 261.407 + vertex 846.633 272.616 260.4 + vertex 847.768 270.698 259.362 + endloop + endfacet + facet normal -0.887047 -0.410368 -0.211534 + outer loop + vertex 846.633 272.616 260.4 + vertex 846.907 273.974 256.62 + vertex 847.768 270.698 259.362 + endloop + endfacet + facet normal -0.876865 -0.416068 -0.240821 + outer loop + vertex 847.781 269.615 261.407 + vertex 847.479 269.238 263.157 + vertex 846.633 272.616 260.4 + endloop + endfacet + facet normal -0.87765 -0.413156 -0.242965 + outer loop + vertex 847.464 268.116 265.12 + vertex 846.309 271.171 264.097 + vertex 847.479 269.238 263.157 + endloop + endfacet + facet normal -0.877781 -0.415031 -0.239269 + outer loop + vertex 846.309 271.171 264.097 + vertex 846.633 272.616 260.4 + vertex 847.479 269.238 263.157 + endloop + endfacet + facet normal -0.816785 -0.518715 -0.252581 + outer loop + vertex 847.479 269.238 263.157 + vertex 847.781 269.615 261.407 + vertex 848.526 267.627 263.081 + endloop + endfacet + facet normal -0.805505 -0.528125 -0.268784 + outer loop + vertex 848.526 267.627 263.081 + vertex 847.781 269.615 261.407 + vertex 848.667 268.38 261.179 + endloop + endfacet + facet normal -0.789709 -0.529961 -0.309032 + outer loop + vertex 847.464 268.116 265.12 + vertex 847.479 269.238 263.157 + vertex 848.373 266.871 264.93 + endloop + endfacet + facet normal -0.811691 -0.514246 -0.276965 + outer loop + vertex 848.373 266.871 264.93 + vertex 847.479 269.238 263.157 + vertex 848.526 267.627 263.081 + endloop + endfacet + facet normal -0.688921 -0.64938 -0.322016 + outer loop + vertex 848.373 266.871 264.93 + vertex 848.526 267.627 263.081 + vertex 849.447 265.748 264.899 + endloop + endfacet + facet normal -0.692807 -0.64728 -0.317878 + outer loop + vertex 849.447 265.748 264.899 + vertex 848.526 267.627 263.081 + vertex 849.588 266.508 263.044 + endloop + endfacet + facet normal -0.694857 -0.649529 -0.308685 + outer loop + vertex 848.526 267.627 263.081 + vertex 848.667 268.38 261.179 + vertex 849.588 266.508 263.044 + endloop + endfacet + facet normal -0.699912 -0.646638 -0.303288 + outer loop + vertex 849.588 266.508 263.044 + vertex 848.667 268.38 261.179 + vertex 849.715 267.266 261.134 + endloop + endfacet + facet normal -0.826833 -0.515608 -0.224711 + outer loop + vertex 847.768 270.698 259.362 + vertex 848.043 271.039 257.568 + vertex 848.791 269.109 259.244 + endloop + endfacet + facet normal -0.817935 -0.523747 -0.238057 + outer loop + vertex 848.791 269.109 259.244 + vertex 848.043 271.039 257.568 + vertex 848.906 269.805 257.32 + endloop + endfacet + facet normal -0.804744 -0.526617 -0.273973 + outer loop + vertex 847.781 269.615 261.407 + vertex 847.768 270.698 259.362 + vertex 848.667 268.38 261.179 + endloop + endfacet + facet normal -0.823234 -0.511722 -0.245817 + outer loop + vertex 848.667 268.38 261.179 + vertex 847.768 270.698 259.362 + vertex 848.791 269.109 259.244 + endloop + endfacet + facet normal -0.702641 -0.649737 -0.290064 + outer loop + vertex 848.667 268.38 261.179 + vertex 848.791 269.109 259.244 + vertex 849.715 267.266 261.134 + endloop + endfacet + facet normal -0.709613 -0.645478 -0.282501 + outer loop + vertex 849.715 267.266 261.134 + vertex 848.791 269.109 259.244 + vertex 849.827 267.992 259.193 + endloop + endfacet + facet normal -0.710814 -0.646879 -0.276209 + outer loop + vertex 848.791 269.109 259.244 + vertex 848.906 269.805 257.32 + vertex 849.827 267.992 259.193 + endloop + endfacet + facet normal -0.716868 -0.643019 -0.269495 + outer loop + vertex 849.827 267.992 259.193 + vertex 848.906 269.805 257.32 + vertex 849.929 268.687 257.265 + endloop + endfacet + facet normal -0.944791 -0.272748 -0.1816 + outer loop + vertex 834.468 317.569 264.162 + vertex 835.243 319.657 256.995 + vertex 836.622 310.073 264.215 + endloop + endfacet + facet normal -0.94233 -0.277046 -0.187774 + outer loop + vertex 836.622 310.073 264.215 + vertex 835.243 319.657 256.995 + vertex 837.389 312.309 257.066 + endloop + endfacet + facet normal -0.929607 -0.318656 -0.185175 + outer loop + vertex 832.005 324.793 264.097 + vertex 832.781 326.703 256.917 + vertex 834.468 317.569 264.162 + endloop + endfacet + facet normal -0.925237 -0.325528 -0.194856 + outer loop + vertex 834.468 317.569 264.162 + vertex 832.781 326.703 256.917 + vertex 835.243 319.657 256.995 + endloop + endfacet + facet normal -0.200399 -0.935613 -0.290634 + outer loop + vertex 853.79 268.252 253.163 + vertex 853.882 268.817 251.28 + vertex 854.337 268.027 253.509 + endloop + endfacet + facet normal -0.203473 -0.938041 -0.280495 + outer loop + vertex 853.821 269.417 249.317 + vertex 854.346 269.271 249.424 + vertex 853.882 268.817 251.28 + endloop + endfacet + facet normal -0.224855 -0.931979 -0.284353 + outer loop + vertex 854.346 269.271 249.424 + vertex 854.337 268.027 253.509 + vertex 853.882 268.817 251.28 + endloop + endfacet + facet normal -0.194651 -0.928952 -0.314894 + outer loop + vertex 853.745 266.965 257.054 + vertex 853.844 267.577 255.187 + vertex 854.275 266.632 257.707 + endloop + endfacet + facet normal -0.189514 -0.932941 -0.306115 + outer loop + vertex 853.79 268.252 253.163 + vertex 854.337 268.027 253.509 + vertex 853.844 267.577 255.187 + endloop + endfacet + facet normal -0.212048 -0.926457 -0.310988 + outer loop + vertex 854.337 268.027 253.509 + vertex 854.275 266.632 257.707 + vertex 853.844 267.577 255.187 + endloop + endfacet + facet normal -0.587509 -0.770131 -0.248459 + outer loop + vertex 850.139 270.531 251.695 + vertex 850.176 271.116 249.793 + vertex 851.194 269.719 251.716 + endloop + endfacet + facet normal -0.594636 -0.766659 -0.242161 + outer loop + vertex 851.194 269.719 251.716 + vertex 850.176 271.116 249.793 + vertex 851.226 270.281 249.858 + endloop + endfacet + facet normal -0.580002 -0.770986 -0.263015 + outer loop + vertex 850.092 269.938 253.537 + vertex 850.139 270.531 251.695 + vertex 851.158 269.127 253.564 + endloop + endfacet + facet normal -0.585908 -0.768288 -0.257769 + outer loop + vertex 851.158 269.127 253.564 + vertex 850.139 270.531 251.695 + vertex 851.194 269.719 251.716 + endloop + endfacet + facet normal -0.423964 -0.860002 -0.28399 + outer loop + vertex 851.158 269.127 253.564 + vertex 851.194 269.719 251.716 + vertex 852.228 268.584 253.609 + endloop + endfacet + facet normal -0.427724 -0.859011 -0.281341 + outer loop + vertex 852.228 268.584 253.609 + vertex 851.194 269.719 251.716 + vertex 852.254 269.18 251.751 + endloop + endfacet + facet normal -0.429775 -0.862192 -0.268177 + outer loop + vertex 851.194 269.719 251.716 + vertex 851.226 270.281 249.858 + vertex 852.254 269.18 251.751 + endloop + endfacet + facet normal -0.431289 -0.861767 -0.267108 + outer loop + vertex 852.254 269.18 251.751 + vertex 851.226 270.281 249.858 + vertex 852.276 269.746 249.888 + endloop + endfacet + facet normal -0.575483 -0.770044 -0.275411 + outer loop + vertex 850.02 269.333 255.379 + vertex 850.092 269.938 253.537 + vertex 851.102 268.51 255.416 + endloop + endfacet + facet normal -0.578144 -0.768875 -0.273094 + outer loop + vertex 851.102 268.51 255.416 + vertex 850.092 269.938 253.537 + vertex 851.158 269.127 253.564 + endloop + endfacet + facet normal -0.565914 -0.771249 -0.291404 + outer loop + vertex 849.929 268.687 257.265 + vertex 850.02 269.333 255.379 + vertex 851.028 267.863 257.31 + endloop + endfacet + facet normal -0.573593 -0.767993 -0.284917 + outer loop + vertex 851.028 267.863 257.31 + vertex 850.02 269.333 255.379 + vertex 851.102 268.51 255.416 + endloop + endfacet + facet normal -0.409601 -0.85823 -0.309303 + outer loop + vertex 851.028 267.863 257.31 + vertex 851.102 268.51 255.416 + vertex 852.132 267.315 257.37 + endloop + endfacet + facet normal -0.412839 -0.85746 -0.307125 + outer loop + vertex 852.132 267.315 257.37 + vertex 851.102 268.51 255.416 + vertex 852.188 267.968 255.473 + endloop + endfacet + facet normal -0.414439 -0.85975 -0.298447 + outer loop + vertex 851.102 268.51 255.416 + vertex 851.158 269.127 253.564 + vertex 852.188 267.968 255.473 + endloop + endfacet + facet normal -0.422446 -0.857752 -0.292917 + outer loop + vertex 852.188 267.968 255.473 + vertex 851.158 269.127 253.564 + vertex 852.228 268.584 253.609 + endloop + endfacet + facet normal -0.297447 -0.904489 -0.305655 + outer loop + vertex 852.188 267.968 255.473 + vertex 852.228 268.584 253.609 + vertex 853.136 267.669 255.434 + endloop + endfacet + facet normal -0.304427 -0.903498 -0.301687 + outer loop + vertex 853.136 267.669 255.434 + vertex 852.228 268.584 253.609 + vertex 853.162 268.291 253.544 + endloop + endfacet + facet normal -0.288548 -0.902748 -0.31904 + outer loop + vertex 852.132 267.315 257.37 + vertex 852.188 267.968 255.473 + vertex 853.101 267.017 257.338 + endloop + endfacet + facet normal -0.296916 -0.901666 -0.314387 + outer loop + vertex 853.101 267.017 257.338 + vertex 852.188 267.968 255.473 + vertex 853.136 267.669 255.434 + endloop + endfacet + facet normal -0.215625 -0.922535 -0.320055 + outer loop + vertex 853.101 267.017 257.338 + vertex 853.136 267.669 255.434 + vertex 853.745 266.965 257.054 + endloop + endfacet + facet normal -0.229616 -0.921171 -0.314199 + outer loop + vertex 853.745 266.965 257.054 + vertex 853.136 267.669 255.434 + vertex 853.844 267.577 255.187 + endloop + endfacet + facet normal -0.227604 -0.923963 -0.30739 + outer loop + vertex 853.136 267.669 255.434 + vertex 853.162 268.291 253.544 + vertex 853.844 267.577 255.187 + endloop + endfacet + facet normal -0.240884 -0.922607 -0.301281 + outer loop + vertex 853.844 267.577 255.187 + vertex 853.162 268.291 253.544 + vertex 853.79 268.252 253.163 + endloop + endfacet + facet normal -0.314032 -0.907316 -0.279574 + outer loop + vertex 852.254 269.18 251.751 + vertex 852.276 269.746 249.888 + vertex 853.183 268.888 251.655 + endloop + endfacet + facet normal -0.320611 -0.906212 -0.27566 + outer loop + vertex 853.183 268.888 251.655 + vertex 852.276 269.746 249.888 + vertex 853.202 269.456 249.766 + endloop + endfacet + facet normal -0.304645 -0.905751 -0.294631 + outer loop + vertex 852.228 268.584 253.609 + vertex 852.254 269.18 251.751 + vertex 853.162 268.291 253.544 + endloop + endfacet + facet normal -0.314067 -0.9043 -0.289143 + outer loop + vertex 853.162 268.291 253.544 + vertex 852.254 269.18 251.751 + vertex 853.183 268.888 251.655 + endloop + endfacet + facet normal -0.237255 -0.925574 -0.294995 + outer loop + vertex 853.162 268.291 253.544 + vertex 853.183 268.888 251.655 + vertex 853.79 268.252 253.163 + endloop + endfacet + facet normal -0.249201 -0.924143 -0.289583 + outer loop + vertex 853.79 268.252 253.163 + vertex 853.183 268.888 251.655 + vertex 853.882 268.817 251.28 + endloop + endfacet + facet normal -0.245167 -0.927751 -0.281375 + outer loop + vertex 853.183 268.888 251.655 + vertex 853.202 269.456 249.766 + vertex 853.882 268.817 251.28 + endloop + endfacet + facet normal -0.257451 -0.926265 -0.275232 + outer loop + vertex 853.882 268.817 251.28 + vertex 853.202 269.456 249.766 + vertex 853.821 269.417 249.317 + endloop + endfacet + facet normal -0.90295 -0.400854 -0.154911 + outer loop + vertex 848.366 273.478 250.123 + vertex 848.178 273.226 251.872 + vertex 847.227 276.413 249.171 + endloop + endfacet + facet normal -0.902032 -0.402046 -0.157156 + outer loop + vertex 848.254 272.293 253.823 + vertex 847.12 275.204 252.884 + vertex 848.178 273.226 251.872 + endloop + endfacet + facet normal -0.902017 -0.402204 -0.156832 + outer loop + vertex 847.12 275.204 252.884 + vertex 847.227 276.413 249.171 + vertex 848.178 273.226 251.872 + endloop + endfacet + facet normal -0.893171 -0.408539 -0.187991 + outer loop + vertex 848.254 272.293 253.823 + vertex 848.007 272.037 255.555 + vertex 847.12 275.204 252.884 + endloop + endfacet + facet normal -0.894764 -0.406319 -0.185209 + outer loop + vertex 848.043 271.039 257.568 + vertex 846.907 273.974 256.62 + vertex 848.007 272.037 255.555 + endloop + endfacet + facet normal -0.894756 -0.406441 -0.184978 + outer loop + vertex 846.907 273.974 256.62 + vertex 847.12 275.204 252.884 + vertex 848.007 272.037 255.555 + endloop + endfacet + facet normal -0.836388 -0.512213 -0.195177 + outer loop + vertex 848.007 272.037 255.555 + vertex 848.254 272.293 253.823 + vertex 849.008 270.448 255.433 + endloop + endfacet + facet normal -0.827587 -0.520887 -0.209231 + outer loop + vertex 849.008 270.448 255.433 + vertex 848.254 272.293 253.823 + vertex 849.096 271.048 253.594 + endloop + endfacet + facet normal -0.817252 -0.522083 -0.243985 + outer loop + vertex 848.043 271.039 257.568 + vertex 848.007 272.037 255.555 + vertex 848.906 269.805 257.32 + endloop + endfacet + facet normal -0.833002 -0.508288 -0.218521 + outer loop + vertex 848.906 269.805 257.32 + vertex 848.007 272.037 255.555 + vertex 849.008 270.448 255.433 + endloop + endfacet + facet normal -0.718733 -0.64525 -0.258988 + outer loop + vertex 848.906 269.805 257.32 + vertex 849.008 270.448 255.433 + vertex 849.929 268.687 257.265 + endloop + endfacet + facet normal -0.722298 -0.642885 -0.254921 + outer loop + vertex 849.929 268.687 257.265 + vertex 849.008 270.448 255.433 + vertex 850.02 269.333 255.379 + endloop + endfacet + facet normal -0.723989 -0.644915 -0.244794 + outer loop + vertex 849.008 270.448 255.433 + vertex 849.096 271.048 253.594 + vertex 850.02 269.333 255.379 + endloop + endfacet + facet normal -0.728662 -0.641709 -0.239293 + outer loop + vertex 850.02 269.333 255.379 + vertex 849.096 271.048 253.594 + vertex 850.092 269.938 253.537 + endloop + endfacet + facet normal -0.845998 -0.507307 -0.164096 + outer loop + vertex 848.178 273.226 251.872 + vertex 848.366 273.478 250.123 + vertex 849.156 271.631 251.765 + endloop + endfacet + facet normal -0.837067 -0.516919 -0.179203 + outer loop + vertex 849.156 271.631 251.765 + vertex 848.366 273.478 250.123 + vertex 849.186 272.247 249.847 + endloop + endfacet + facet normal -0.826899 -0.519151 -0.216148 + outer loop + vertex 848.254 272.293 253.823 + vertex 848.178 273.226 251.872 + vertex 849.096 271.048 253.594 + endloop + endfacet + facet normal -0.84303 -0.503862 -0.18821 + outer loop + vertex 849.096 271.048 253.594 + vertex 848.178 273.226 251.872 + vertex 849.156 271.631 251.765 + endloop + endfacet + facet normal -0.730238 -0.64365 -0.229055 + outer loop + vertex 849.096 271.048 253.594 + vertex 849.156 271.631 251.765 + vertex 850.092 269.938 253.537 + endloop + endfacet + facet normal -0.733415 -0.641389 -0.225216 + outer loop + vertex 850.092 269.938 253.537 + vertex 849.156 271.631 251.765 + vertex 850.139 270.531 251.695 + endloop + endfacet + facet normal -0.734416 -0.642741 -0.217985 + outer loop + vertex 849.156 271.631 251.765 + vertex 849.186 272.247 249.847 + vertex 850.139 270.531 251.695 + endloop + endfacet + facet normal -0.740358 -0.638305 -0.210801 + outer loop + vertex 850.139 270.531 251.695 + vertex 849.186 272.247 249.847 + vertex 850.176 271.116 249.793 + endloop + endfacet + facet normal -0.204875 -0.947667 -0.244853 + outer loop + vertex 853.83 270.436 245.62 + vertex 853.902 270.883 243.828 + vertex 854.289 270.243 245.985 + endloop + endfacet + facet normal -0.172648 -0.955306 -0.239963 + outer loop + vertex 853.82 271.397 241.844 + vertex 854.335 271.168 242.384 + vertex 853.902 270.883 243.828 + endloop + endfacet + facet normal -0.19828 -0.948684 -0.24634 + outer loop + vertex 854.335 271.168 242.384 + vertex 854.289 270.243 245.985 + vertex 853.902 270.883 243.828 + endloop + endfacet + facet normal -0.20754 -0.941537 -0.265396 + outer loop + vertex 853.821 269.417 249.317 + vertex 853.901 269.908 247.514 + vertex 854.346 269.271 249.424 + endloop + endfacet + facet normal -0.195029 -0.946611 -0.256694 + outer loop + vertex 853.83 270.436 245.62 + vertex 854.289 270.243 245.985 + vertex 853.901 269.908 247.514 + endloop + endfacet + facet normal -0.220708 -0.939581 -0.261677 + outer loop + vertex 854.289 270.243 245.985 + vertex 854.346 269.271 249.424 + vertex 853.901 269.908 247.514 + endloop + endfacet + facet normal -0.626682 -0.747953 -0.218715 + outer loop + vertex 850.22 272.7 244.508 + vertex 850.291 273.166 242.71 + vertex 851.244 271.9 244.309 + endloop + endfacet + facet normal -0.647402 -0.736227 -0.197081 + outer loop + vertex 851.244 271.9 244.309 + vertex 850.291 273.166 242.71 + vertex 851.228 272.434 242.367 + endloop + endfacet + facet normal -0.564794 -0.777576 -0.276376 + outer loop + vertex 850.45 271.85 246.429 + vertex 850.22 272.7 244.508 + vertex 851.269 271.332 246.212 + endloop + endfacet + facet normal -0.62675 -0.748912 -0.215211 + outer loop + vertex 851.269 271.332 246.212 + vertex 850.22 272.7 244.508 + vertex 851.244 271.9 244.309 + endloop + endfacet + facet normal -0.445332 -0.859569 -0.250641 + outer loop + vertex 851.269 271.332 246.212 + vertex 851.244 271.9 244.309 + vertex 852.296 270.828 246.116 + endloop + endfacet + facet normal -0.474598 -0.850155 -0.22802 + outer loop + vertex 852.296 270.828 246.116 + vertex 851.244 271.9 244.309 + vertex 852.298 271.342 244.197 + endloop + endfacet + facet normal -0.474551 -0.849729 -0.229701 + outer loop + vertex 851.244 271.9 244.309 + vertex 851.228 272.434 242.367 + vertex 852.298 271.342 244.197 + endloop + endfacet + facet normal -0.497333 -0.841406 -0.211415 + outer loop + vertex 852.298 271.342 244.197 + vertex 851.228 272.434 242.367 + vertex 852.303 271.822 242.272 + endloop + endfacet + facet normal -0.591333 -0.778717 -0.209582 + outer loop + vertex 850.261 271.597 247.903 + vertex 850.45 271.85 246.429 + vertex 851.274 270.789 248.046 + endloop + endfacet + facet normal -0.563016 -0.792835 -0.233293 + outer loop + vertex 851.274 270.789 248.046 + vertex 850.45 271.85 246.429 + vertex 851.269 271.332 246.212 + endloop + endfacet + facet normal -0.598269 -0.769727 -0.222698 + outer loop + vertex 850.176 271.116 249.793 + vertex 850.261 271.597 247.903 + vertex 851.226 270.281 249.858 + endloop + endfacet + facet normal -0.585943 -0.776109 -0.23308 + outer loop + vertex 851.226 270.281 249.858 + vertex 850.261 271.597 247.903 + vertex 851.274 270.789 248.046 + endloop + endfacet + facet normal -0.433213 -0.864785 -0.253917 + outer loop + vertex 851.226 270.281 249.858 + vertex 851.274 270.789 248.046 + vertex 852.276 269.746 249.888 + endloop + endfacet + facet normal -0.429299 -0.865918 -0.256685 + outer loop + vertex 852.276 269.746 249.888 + vertex 851.274 270.789 248.046 + vertex 852.289 270.296 248.013 + endloop + endfacet + facet normal -0.429417 -0.866248 -0.255371 + outer loop + vertex 851.274 270.789 248.046 + vertex 851.269 271.332 246.212 + vertex 852.289 270.296 248.013 + endloop + endfacet + facet normal -0.445607 -0.861487 -0.243464 + outer loop + vertex 852.289 270.296 248.013 + vertex 851.269 271.332 246.212 + vertex 852.296 270.828 246.116 + endloop + endfacet + facet normal -0.330768 -0.908274 -0.256185 + outer loop + vertex 852.289 270.296 248.013 + vertex 852.296 270.828 246.116 + vertex 853.218 269.996 247.877 + endloop + endfacet + facet normal -0.343764 -0.905675 -0.248153 + outer loop + vertex 853.218 269.996 247.877 + vertex 852.296 270.828 246.116 + vertex 853.23 270.508 245.99 + endloop + endfacet + facet normal -0.320361 -0.908487 -0.268365 + outer loop + vertex 852.276 269.746 249.888 + vertex 852.289 270.296 248.013 + vertex 853.202 269.456 249.766 + endloop + endfacet + facet normal -0.33104 -0.90655 -0.261878 + outer loop + vertex 853.202 269.456 249.766 + vertex 852.289 270.296 248.013 + vertex 853.218 269.996 247.877 + endloop + endfacet + facet normal -0.252324 -0.929831 -0.267857 + outer loop + vertex 853.202 269.456 249.766 + vertex 853.218 269.996 247.877 + vertex 853.821 269.417 249.317 + endloop + endfacet + facet normal -0.259956 -0.928766 -0.264229 + outer loop + vertex 853.821 269.417 249.317 + vertex 853.218 269.996 247.877 + vertex 853.901 269.908 247.514 + endloop + endfacet + facet normal -0.255489 -0.932602 -0.25491 + outer loop + vertex 853.218 269.996 247.877 + vertex 853.23 270.508 245.99 + vertex 853.901 269.908 247.514 + endloop + endfacet + facet normal -0.265936 -0.931086 -0.249713 + outer loop + vertex 853.901 269.908 247.514 + vertex 853.23 270.508 245.99 + vertex 853.83 270.436 245.62 + endloop + endfacet + facet normal -0.356004 -0.90643 -0.227257 + outer loop + vertex 852.298 271.342 244.197 + vertex 852.303 271.822 242.272 + vertex 853.233 271 244.097 + endloop + endfacet + facet normal -0.360811 -0.905269 -0.224283 + outer loop + vertex 853.233 271 244.097 + vertex 852.303 271.822 242.272 + vertex 853.229 271.475 242.186 + endloop + endfacet + facet normal -0.343577 -0.907106 -0.243135 + outer loop + vertex 852.296 270.828 246.116 + vertex 852.298 271.342 244.197 + vertex 853.23 270.508 245.99 + endloop + endfacet + facet normal -0.356103 -0.904328 -0.235333 + outer loop + vertex 853.23 270.508 245.99 + vertex 852.298 271.342 244.197 + vertex 853.233 271 244.097 + endloop + endfacet + facet normal -0.262061 -0.933992 -0.242865 + outer loop + vertex 853.23 270.508 245.99 + vertex 853.233 271 244.097 + vertex 853.83 270.436 245.62 + endloop + endfacet + facet normal -0.260151 -0.934301 -0.243727 + outer loop + vertex 853.83 270.436 245.62 + vertex 853.233 271 244.097 + vertex 853.902 270.883 243.828 + endloop + endfacet + facet normal -0.256386 -0.938149 -0.232685 + outer loop + vertex 853.233 271 244.097 + vertex 853.229 271.475 242.186 + vertex 853.902 270.883 243.828 + endloop + endfacet + facet normal -0.257965 -0.937899 -0.231948 + outer loop + vertex 853.902 270.883 243.828 + vertex 853.229 271.475 242.186 + vertex 853.82 271.397 241.844 + endloop + endfacet + facet normal -0.908749 -0.396228 -0.131067 + outer loop + vertex 847.129 277.927 245.478 + vertex 847.274 278.736 242.027 + vertex 848.33 275.284 245.141 + endloop + endfacet + facet normal -0.887747 -0.426912 -0.172195 + outer loop + vertex 848.33 275.284 245.141 + vertex 847.274 278.736 242.027 + vertex 848.946 275.248 242.056 + endloop + endfacet + facet normal -0.907964 -0.394598 -0.141048 + outer loop + vertex 848.33 275.284 245.141 + vertex 848.21 274.564 247.93 + vertex 847.129 277.927 245.478 + endloop + endfacet + facet normal -0.909118 -0.395448 -0.130866 + outer loop + vertex 848.366 273.478 250.123 + vertex 847.227 276.413 249.171 + vertex 848.21 274.564 247.93 + endloop + endfacet + facet normal -0.909788 -0.391949 -0.136609 + outer loop + vertex 847.227 276.413 249.171 + vertex 847.129 277.927 245.478 + vertex 848.21 274.564 247.93 + endloop + endfacet + facet normal -0.852527 -0.496008 -0.164846 + outer loop + vertex 848.21 274.564 247.93 + vertex 848.33 275.284 245.141 + vertex 849.232 272.878 247.715 + endloop + endfacet + facet normal -0.842065 -0.508416 -0.18011 + outer loop + vertex 849.232 272.878 247.715 + vertex 848.33 275.284 245.141 + vertex 849.509 273.164 245.611 + endloop + endfacet + facet normal -0.836156 -0.512934 -0.194272 + outer loop + vertex 848.366 273.478 250.123 + vertex 848.21 274.564 247.93 + vertex 849.186 272.247 249.847 + endloop + endfacet + facet normal -0.852479 -0.495911 -0.165384 + outer loop + vertex 849.186 272.247 249.847 + vertex 848.21 274.564 247.93 + vertex 849.232 272.878 247.715 + endloop + endfacet + facet normal -0.741095 -0.639207 -0.20541 + outer loop + vertex 849.186 272.247 249.847 + vertex 849.232 272.878 247.715 + vertex 850.176 271.116 249.793 + endloop + endfacet + facet normal -0.750694 -0.631393 -0.194425 + outer loop + vertex 850.176 271.116 249.793 + vertex 849.232 272.878 247.715 + vertex 850.261 271.597 247.903 + endloop + endfacet + facet normal -0.752782 -0.631707 -0.185107 + outer loop + vertex 849.232 272.878 247.715 + vertex 849.509 273.164 245.611 + vertex 850.261 271.597 247.903 + endloop + endfacet + facet normal -0.730847 -0.650894 -0.205426 + outer loop + vertex 850.261 271.597 247.903 + vertex 849.509 273.164 245.611 + vertex 850.45 271.85 246.429 + endloop + endfacet + facet normal -0.733846 -0.649358 -0.199512 + outer loop + vertex 850.45 271.85 246.429 + vertex 849.509 273.164 245.611 + vertex 850.22 272.7 244.508 + endloop + endfacet + facet normal -0.799355 -0.573204 -0.180192 + outer loop + vertex 850.291 273.166 242.71 + vertex 850.22 272.7 244.508 + vertex 848.946 275.248 242.056 + endloop + endfacet + facet normal -0.846379 -0.507025 -0.162997 + outer loop + vertex 848.33 275.284 245.141 + vertex 848.946 275.248 242.056 + vertex 849.509 273.164 245.611 + endloop + endfacet + facet normal -0.760061 -0.605994 -0.234688 + outer loop + vertex 850.22 272.7 244.508 + vertex 849.509 273.164 245.611 + vertex 848.946 275.248 242.056 + endloop + endfacet + facet normal -0.176272 -0.961139 -0.212461 + outer loop + vertex 853.769 272.355 237.836 + vertex 853.799 272.766 235.954 + vertex 854.259 272.22 238.043 + endloop + endfacet + facet normal -0.174989 -0.963562 -0.202306 + outer loop + vertex 853.693 273.199 233.985 + vertex 854.104 273.026 234.453 + vertex 853.799 272.766 235.954 + endloop + endfacet + facet normal -0.199932 -0.957828 -0.206382 + outer loop + vertex 854.104 273.026 234.453 + vertex 854.259 272.22 238.043 + vertex 853.799 272.766 235.954 + endloop + endfacet + facet normal -0.183744 -0.955782 -0.229607 + outer loop + vertex 853.82 271.397 241.844 + vertex 853.875 271.849 239.916 + vertex 854.335 271.168 242.384 + endloop + endfacet + facet normal -0.170612 -0.959375 -0.224703 + outer loop + vertex 853.769 272.355 237.836 + vertex 854.259 272.22 238.043 + vertex 853.875 271.849 239.916 + endloop + endfacet + facet normal -0.190989 -0.954752 -0.227973 + outer loop + vertex 854.259 272.22 238.043 + vertex 854.335 271.168 242.384 + vertex 853.875 271.849 239.916 + endloop + endfacet + facet normal -0.703852 -0.698346 -0.130022 + outer loop + vertex 850.093 274.908 236.689 + vertex 850.224 275.116 234.864 + vertex 851.218 273.793 236.591 + endloop + endfacet + facet normal -0.685228 -0.712398 -0.151498 + outer loop + vertex 851.218 273.793 236.591 + vertex 850.224 275.116 234.864 + vertex 851.17 274.262 234.6 + endloop + endfacet + facet normal -0.674351 -0.714873 -0.184954 + outer loop + vertex 850.285 274.196 238.745 + vertex 850.093 274.908 236.689 + vertex 851.239 273.358 238.505 + endloop + endfacet + facet normal -0.702707 -0.695397 -0.150421 + outer loop + vertex 851.239 273.358 238.505 + vertex 850.093 274.908 236.689 + vertex 851.218 273.793 236.591 + endloop + endfacet + facet normal -0.517945 -0.835329 -0.184279 + outer loop + vertex 851.239 273.358 238.505 + vertex 851.218 273.793 236.591 + vertex 852.299 272.714 238.443 + endloop + endfacet + facet normal -0.519893 -0.834477 -0.182645 + outer loop + vertex 852.299 272.714 238.443 + vertex 851.218 273.793 236.591 + vertex 852.27 273.155 236.509 + endloop + endfacet + facet normal -0.519833 -0.834183 -0.184151 + outer loop + vertex 851.218 273.793 236.591 + vertex 851.17 274.262 234.6 + vertex 852.27 273.155 236.509 + endloop + endfacet + facet normal -0.529573 -0.829805 -0.176001 + outer loop + vertex 852.27 273.155 236.509 + vertex 851.17 274.262 234.6 + vertex 852.242 273.596 234.516 + endloop + endfacet + facet normal -0.685573 -0.71118 -0.155601 + outer loop + vertex 850.105 273.959 240.618 + vertex 850.285 274.196 238.745 + vertex 851.236 272.912 240.425 + endloop + endfacet + facet normal -0.67403 -0.719273 -0.168316 + outer loop + vertex 851.236 272.912 240.425 + vertex 850.285 274.196 238.745 + vertex 851.239 273.358 238.505 + endloop + endfacet + facet normal -0.649219 -0.728572 -0.218397 + outer loop + vertex 850.291 273.166 242.71 + vertex 850.105 273.959 240.618 + vertex 851.228 272.434 242.367 + endloop + endfacet + facet normal -0.685069 -0.706802 -0.176385 + outer loop + vertex 851.228 272.434 242.367 + vertex 850.105 273.959 240.618 + vertex 851.236 272.912 240.425 + endloop + endfacet + facet normal -0.497433 -0.841966 -0.208935 + outer loop + vertex 851.228 272.434 242.367 + vertex 851.236 272.912 240.425 + vertex 852.303 271.822 242.272 + endloop + endfacet + facet normal -0.507929 -0.837765 -0.200393 + outer loop + vertex 852.303 271.822 242.272 + vertex 851.236 272.912 240.425 + vertex 852.307 272.279 240.355 + endloop + endfacet + facet normal -0.508183 -0.838708 -0.195753 + outer loop + vertex 851.236 272.912 240.425 + vertex 851.239 273.358 238.505 + vertex 852.307 272.279 240.355 + endloop + endfacet + facet normal -0.517745 -0.834652 -0.18787 + outer loop + vertex 852.307 272.279 240.355 + vertex 851.239 273.358 238.505 + vertex 852.299 272.714 238.443 + endloop + endfacet + facet normal -0.361799 -0.909336 -0.205449 + outer loop + vertex 852.307 272.279 240.355 + vertex 852.299 272.714 238.443 + vertex 853.218 271.939 240.254 + endloop + endfacet + facet normal -0.356119 -0.91078 -0.208948 + outer loop + vertex 853.218 271.939 240.254 + vertex 852.299 272.714 238.443 + vertex 853.199 272.394 238.305 + endloop + endfacet + facet normal -0.360794 -0.907133 -0.216648 + outer loop + vertex 852.303 271.822 242.272 + vertex 852.307 272.279 240.355 + vertex 853.229 271.475 242.186 + endloop + endfacet + facet normal -0.36202 -0.906824 -0.215895 + outer loop + vertex 853.229 271.475 242.186 + vertex 852.307 272.279 240.355 + vertex 853.218 271.939 240.254 + endloop + endfacet + facet normal -0.254114 -0.940721 -0.224655 + outer loop + vertex 853.229 271.475 242.186 + vertex 853.218 271.939 240.254 + vertex 853.82 271.397 241.844 + endloop + endfacet + facet normal -0.246064 -0.94202 -0.228146 + outer loop + vertex 853.82 271.397 241.844 + vertex 853.218 271.939 240.254 + vertex 853.875 271.849 239.916 + endloop + endfacet + facet normal -0.241443 -0.945561 -0.218221 + outer loop + vertex 853.218 271.939 240.254 + vertex 853.199 272.394 238.305 + vertex 853.875 271.849 239.916 + endloop + endfacet + facet normal -0.242712 -0.945373 -0.217625 + outer loop + vertex 853.875 271.849 239.916 + vertex 853.199 272.394 238.305 + vertex 853.769 272.355 237.836 + endloop + endfacet + facet normal -0.35888 -0.912427 -0.196679 + outer loop + vertex 852.27 273.155 236.509 + vertex 852.242 273.596 234.516 + vertex 853.168 272.838 236.343 + endloop + endfacet + facet normal -0.368627 -0.909816 -0.190656 + outer loop + vertex 853.168 272.838 236.343 + vertex 852.242 273.596 234.516 + vertex 853.143 273.258 234.385 + endloop + endfacet + facet normal -0.355732 -0.9123 -0.202887 + outer loop + vertex 852.299 272.714 238.443 + vertex 852.27 273.155 236.509 + vertex 853.199 272.394 238.305 + endloop + endfacet + facet normal -0.359257 -0.911405 -0.200686 + outer loop + vertex 853.199 272.394 238.305 + vertex 852.27 273.155 236.509 + vertex 853.168 272.838 236.343 + endloop + endfacet + facet normal -0.237372 -0.948249 -0.2109 + outer loop + vertex 853.199 272.394 238.305 + vertex 853.168 272.838 236.343 + vertex 853.769 272.355 237.836 + endloop + endfacet + facet normal -0.237993 -0.948155 -0.21062 + outer loop + vertex 853.769 272.355 237.836 + vertex 853.168 272.838 236.343 + vertex 853.799 272.766 235.954 + endloop + endfacet + facet normal -0.232635 -0.951498 -0.201329 + outer loop + vertex 853.168 272.838 236.343 + vertex 853.143 273.258 234.385 + vertex 853.799 272.766 235.954 + endloop + endfacet + facet normal -0.245235 -0.949556 -0.195456 + outer loop + vertex 853.799 272.766 235.954 + vertex 853.143 273.258 234.385 + vertex 853.693 273.199 233.985 + endloop + endfacet + facet normal -0.898715 -0.426643 -0.101422 + outer loop + vertex 847.411 279.512 238.292 + vertex 847.421 280.438 234.307 + vertex 848.955 276.385 237.769 + endloop + endfacet + facet normal -0.905628 -0.415421 -0.0852219 + outer loop + vertex 848.955 276.385 237.769 + vertex 847.421 280.438 234.307 + vertex 848.884 277.341 233.853 + endloop + endfacet + facet normal -0.894628 -0.4298 -0.12212 + outer loop + vertex 847.274 278.736 242.027 + vertex 847.411 279.512 238.292 + vertex 848.946 275.248 242.056 + endloop + endfacet + facet normal -0.898287 -0.424267 -0.11436 + outer loop + vertex 848.946 275.248 242.056 + vertex 847.411 279.512 238.292 + vertex 848.955 276.385 237.769 + endloop + endfacet + facet normal -0.814178 -0.561157 -0.149054 + outer loop + vertex 850.285 274.196 238.745 + vertex 850.105 273.959 240.618 + vertex 848.955 276.385 237.769 + endloop + endfacet + facet normal -0.810059 -0.568549 -0.143377 + outer loop + vertex 850.291 273.166 242.71 + vertex 848.946 275.248 242.056 + vertex 850.105 273.959 240.618 + endloop + endfacet + facet normal -0.812809 -0.562652 -0.150879 + outer loop + vertex 848.946 275.248 242.056 + vertex 848.955 276.385 237.769 + vertex 850.105 273.959 240.618 + endloop + endfacet + facet normal -0.824798 -0.552091 -0.122083 + outer loop + vertex 850.224 275.116 234.864 + vertex 850.093 274.908 236.689 + vertex 848.884 277.341 233.853 + endloop + endfacet + facet normal -0.825472 -0.55268 -0.114633 + outer loop + vertex 850.285 274.196 238.745 + vertex 848.955 276.385 237.769 + vertex 850.093 274.908 236.689 + endloop + endfacet + facet normal -0.826586 -0.549976 -0.119506 + outer loop + vertex 848.955 276.385 237.769 + vertex 848.884 277.341 233.853 + vertex 850.093 274.908 236.689 + endloop + endfacet + facet normal -0.199831 -0.964586 -0.172166 + outer loop + vertex 853.596 273.947 230.211 + vertex 853.611 274.28 228.331 + vertex 854.093 273.686 231.097 + endloop + endfacet + facet normal -0.167253 -0.971553 -0.167662 + outer loop + vertex 853.496 274.657 226.258 + vertex 854.05 274.464 226.823 + vertex 853.611 274.28 228.331 + endloop + endfacet + facet normal -0.191242 -0.966003 -0.173967 + outer loop + vertex 854.05 274.464 226.823 + vertex 854.093 273.686 231.097 + vertex 853.611 274.28 228.331 + endloop + endfacet + facet normal -0.188135 -0.963444 -0.190738 + outer loop + vertex 853.693 273.199 233.985 + vertex 853.718 273.547 232.199 + vertex 854.104 273.026 234.453 + endloop + endfacet + facet normal -0.180838 -0.966277 -0.183322 + outer loop + vertex 853.596 273.947 230.211 + vertex 854.093 273.686 231.097 + vertex 853.718 273.547 232.199 + endloop + endfacet + facet normal -0.198119 -0.961851 -0.188657 + outer loop + vertex 854.093 273.686 231.097 + vertex 854.104 273.026 234.453 + vertex 853.718 273.547 232.199 + endloop + endfacet + facet normal -0.535519 -0.827222 -0.170066 + outer loop + vertex 852.455 274.185 231.019 + vertex 851.431 275.003 230.264 + vertex 852.147 274.783 229.078 + endloop + endfacet + facet normal -0.651253 -0.744961 -0.144579 + outer loop + vertex 852.152 275.133 227.254 + vertex 852.147 274.783 229.078 + vertex 850.654 276.548 226.71 + endloop + endfacet + facet normal -0.693869 -0.703409 -0.154146 + outer loop + vertex 850.011 276.498 229.836 + vertex 850.654 276.548 226.71 + vertex 851.431 275.003 230.264 + endloop + endfacet + facet normal -0.588477 -0.780574 -0.210711 + outer loop + vertex 852.147 274.783 229.078 + vertex 851.431 275.003 230.264 + vertex 850.654 276.548 226.71 + endloop + endfacet + facet normal -0.708244 -0.68927 -0.152637 + outer loop + vertex 849.956 275.935 232.632 + vertex 850.011 276.498 229.836 + vertex 851.159 274.747 232.415 + endloop + endfacet + facet normal -0.68935 -0.703952 -0.171022 + outer loop + vertex 851.159 274.747 232.415 + vertex 850.011 276.498 229.836 + vertex 851.431 275.003 230.264 + endloop + endfacet + facet normal -0.686166 -0.705715 -0.17647 + outer loop + vertex 850.224 275.116 234.864 + vertex 849.956 275.935 232.632 + vertex 851.17 274.262 234.6 + endloop + endfacet + facet normal -0.708302 -0.689923 -0.149379 + outer loop + vertex 851.17 274.262 234.6 + vertex 849.956 275.935 232.632 + vertex 851.159 274.747 232.415 + endloop + endfacet + facet normal -0.52937 -0.828831 -0.181126 + outer loop + vertex 851.17 274.262 234.6 + vertex 851.159 274.747 232.415 + vertex 852.242 273.596 234.516 + endloop + endfacet + facet normal -0.543362 -0.822063 -0.170205 + outer loop + vertex 852.242 273.596 234.516 + vertex 851.159 274.747 232.415 + vertex 852.294 273.968 232.553 + endloop + endfacet + facet normal -0.543981 -0.822356 -0.16678 + outer loop + vertex 851.159 274.747 232.415 + vertex 851.431 275.003 230.264 + vertex 852.294 273.968 232.553 + endloop + endfacet + facet normal -0.533717 -0.827759 -0.173093 + outer loop + vertex 852.294 273.968 232.553 + vertex 851.431 275.003 230.264 + vertex 852.455 274.185 231.019 + endloop + endfacet + facet normal -0.372197 -0.912796 -0.168143 + outer loop + vertex 852.294 273.968 232.553 + vertex 852.455 274.185 231.019 + vertex 853.144 273.63 232.507 + endloop + endfacet + facet normal -0.352416 -0.918482 -0.179423 + outer loop + vertex 853.144 273.63 232.507 + vertex 852.455 274.185 231.019 + vertex 853.082 274.021 230.629 + endloop + endfacet + facet normal -0.368149 -0.911656 -0.182617 + outer loop + vertex 852.242 273.596 234.516 + vertex 852.294 273.968 232.553 + vertex 853.143 273.258 234.385 + endloop + endfacet + facet normal -0.371967 -0.910545 -0.180414 + outer loop + vertex 853.143 273.258 234.385 + vertex 852.294 273.968 232.553 + vertex 853.144 273.63 232.507 + endloop + endfacet + facet normal -0.240547 -0.952132 -0.18863 + outer loop + vertex 853.143 273.258 234.385 + vertex 853.144 273.63 232.507 + vertex 853.693 273.199 233.985 + endloop + endfacet + facet normal -0.239022 -0.952389 -0.189273 + outer loop + vertex 853.693 273.199 233.985 + vertex 853.144 273.63 232.507 + vertex 853.718 273.547 232.199 + endloop + endfacet + facet normal -0.239442 -0.952112 -0.190133 + outer loop + vertex 853.144 273.63 232.507 + vertex 853.082 274.021 230.629 + vertex 853.718 273.547 232.199 + endloop + endfacet + facet normal -0.276006 -0.945401 -0.173312 + outer loop + vertex 853.718 273.547 232.199 + vertex 853.082 274.021 230.629 + vertex 853.596 273.947 230.211 + endloop + endfacet + facet normal -0.454412 -0.874614 -0.168994 + outer loop + vertex 852.147 274.783 229.078 + vertex 852.152 275.133 227.254 + vertex 852.992 274.418 228.698 + endloop + endfacet + facet normal -0.482584 -0.863416 -0.147057 + outer loop + vertex 852.992 274.418 228.698 + vertex 852.152 275.133 227.254 + vertex 852.919 274.791 226.75 + endloop + endfacet + facet normal -0.372563 -0.901832 -0.21885 + outer loop + vertex 852.455 274.185 231.019 + vertex 852.147 274.783 229.078 + vertex 853.082 274.021 230.629 + endloop + endfacet + facet normal -0.451549 -0.877877 -0.159485 + outer loop + vertex 853.082 274.021 230.629 + vertex 852.147 274.783 229.078 + vertex 852.992 274.418 228.698 + endloop + endfacet + facet normal -0.281541 -0.942389 -0.180659 + outer loop + vertex 853.082 274.021 230.629 + vertex 852.992 274.418 228.698 + vertex 853.596 273.947 230.211 + endloop + endfacet + facet normal -0.308423 -0.936291 -0.168033 + outer loop + vertex 853.596 273.947 230.211 + vertex 852.992 274.418 228.698 + vertex 853.611 274.28 228.331 + endloop + endfacet + facet normal -0.308211 -0.936434 -0.167622 + outer loop + vertex 852.992 274.418 228.698 + vertex 852.919 274.791 226.75 + vertex 853.611 274.28 228.331 + endloop + endfacet + facet normal -0.342024 -0.927647 -0.149968 + outer loop + vertex 853.611 274.28 228.331 + vertex 852.919 274.791 226.75 + vertex 853.496 274.657 226.258 + endloop + endfacet + facet normal -0.909684 -0.411358 -0.0570947 + outer loop + vertex 847.419 281.109 230.463 + vertex 847.568 281.187 227.521 + vertex 848.652 278.416 230.204 + endloop + endfacet + facet normal -0.886946 -0.449598 -0.105776 + outer loop + vertex 848.652 278.416 230.204 + vertex 847.568 281.187 227.521 + vertex 848.697 279.117 226.848 + endloop + endfacet + facet normal -0.905836 -0.417425 -0.072229 + outer loop + vertex 847.421 280.438 234.307 + vertex 847.419 281.109 230.463 + vertex 848.884 277.341 233.853 + endloop + endfacet + facet normal -0.90957 -0.410721 -0.0631657 + outer loop + vertex 848.884 277.341 233.853 + vertex 847.419 281.109 230.463 + vertex 848.652 278.416 230.204 + endloop + endfacet + facet normal -0.820838 -0.556596 -0.128164 + outer loop + vertex 850.011 276.498 229.836 + vertex 849.956 275.935 232.632 + vertex 848.652 278.416 230.204 + endloop + endfacet + facet normal -0.831538 -0.546315 -0.100425 + outer loop + vertex 850.224 275.116 234.864 + vertex 848.884 277.341 233.853 + vertex 849.956 275.935 232.632 + endloop + endfacet + facet normal -0.833411 -0.542245 -0.106751 + outer loop + vertex 848.884 277.341 233.853 + vertex 848.652 278.416 230.204 + vertex 849.956 275.935 232.632 + endloop + endfacet + facet normal -0.820854 -0.556778 -0.127271 + outer loop + vertex 848.652 278.416 230.204 + vertex 848.697 279.117 226.848 + vertex 850.011 276.498 229.836 + endloop + endfacet + facet normal -0.788122 -0.591077 -0.171729 + outer loop + vertex 850.011 276.498 229.836 + vertex 848.697 279.117 226.848 + vertex 850.654 276.548 226.71 + endloop + endfacet + facet normal -0.154011 -0.976125 -0.153168 + outer loop + vertex 853.448 275.282 222.417 + vertex 853.482 275.562 220.602 + vertex 853.91 275.171 222.659 + endloop + endfacet + facet normal -0.153931 -0.976892 -0.148279 + outer loop + vertex 853.379 275.874 218.654 + vertex 853.829 275.742 219.055 + vertex 853.482 275.562 220.602 + endloop + endfacet + facet normal -0.165236 -0.974694 -0.150561 + outer loop + vertex 853.829 275.742 219.055 + vertex 853.91 275.171 222.659 + vertex 853.482 275.562 220.602 + endloop + endfacet + facet normal -0.178057 -0.971413 -0.15701 + outer loop + vertex 853.496 274.657 226.258 + vertex 853.541 274.951 224.387 + vertex 854.05 274.464 226.823 + endloop + endfacet + facet normal -0.152101 -0.975866 -0.15669 + outer loop + vertex 853.448 275.282 222.417 + vertex 853.91 275.171 222.659 + vertex 853.541 274.951 224.387 + endloop + endfacet + facet normal -0.167298 -0.972909 -0.159559 + outer loop + vertex 853.91 275.171 222.659 + vertex 854.05 274.464 226.823 + vertex 853.541 274.951 224.387 + endloop + endfacet + facet normal -0.69229 -0.713115 -0.110459 + outer loop + vertex 852.014 276.419 219.459 + vertex 851.853 276.297 221.259 + vertex 850.535 278.015 218.428 + endloop + endfacet + facet normal -0.69472 -0.713589 -0.0903091 + outer loop + vertex 852.061 275.835 223.309 + vertex 850.584 277.388 222.4 + vertex 851.853 276.297 221.259 + endloop + endfacet + facet normal -0.700067 -0.706624 -0.102901 + outer loop + vertex 850.584 277.388 222.4 + vertex 850.535 278.015 218.428 + vertex 851.853 276.297 221.259 + endloop + endfacet + facet normal -0.68204 -0.720842 -0.123324 + outer loop + vertex 852.061 275.835 223.309 + vertex 851.901 275.666 225.179 + vertex 850.584 277.388 222.4 + endloop + endfacet + facet normal -0.660954 -0.742213 -0.110726 + outer loop + vertex 852.152 275.133 227.254 + vertex 850.654 276.548 226.71 + vertex 851.901 275.666 225.179 + endloop + endfacet + facet normal -0.674389 -0.726734 -0.130602 + outer loop + vertex 850.654 276.548 226.71 + vertex 850.584 277.388 222.4 + vertex 851.901 275.666 225.179 + endloop + endfacet + facet normal -0.518841 -0.846308 -0.120692 + outer loop + vertex 851.901 275.666 225.179 + vertex 852.061 275.835 223.309 + vertex 852.889 275.112 224.818 + endloop + endfacet + facet normal -0.504866 -0.853105 -0.131613 + outer loop + vertex 852.889 275.112 224.818 + vertex 852.061 275.835 223.309 + vertex 852.867 275.419 222.914 + endloop + endfacet + facet normal -0.489022 -0.85728 -0.161026 + outer loop + vertex 852.152 275.133 227.254 + vertex 851.901 275.666 225.179 + vertex 852.919 274.791 226.75 + endloop + endfacet + facet normal -0.521262 -0.84309 -0.132236 + outer loop + vertex 852.919 274.791 226.75 + vertex 851.901 275.666 225.179 + vertex 852.889 275.112 224.818 + endloop + endfacet + facet normal -0.341402 -0.92801 -0.149138 + outer loop + vertex 852.919 274.791 226.75 + vertex 852.889 275.112 224.818 + vertex 853.496 274.657 226.258 + endloop + endfacet + facet normal -0.33131 -0.930823 -0.154281 + outer loop + vertex 853.496 274.657 226.258 + vertex 852.889 275.112 224.818 + vertex 853.541 274.951 224.387 + endloop + endfacet + facet normal -0.326915 -0.933618 -0.146573 + outer loop + vertex 852.889 275.112 224.818 + vertex 852.867 275.419 222.914 + vertex 853.541 274.951 224.387 + endloop + endfacet + facet normal -0.338426 -0.930473 -0.140315 + outer loop + vertex 853.541 274.951 224.387 + vertex 852.867 275.419 222.914 + vertex 853.448 275.282 222.417 + endloop + endfacet + facet normal -0.523341 -0.845716 -0.104299 + outer loop + vertex 851.853 276.297 221.259 + vertex 852.014 276.419 219.459 + vertex 852.847 275.71 221.026 + endloop + endfacet + facet normal -0.500022 -0.85738 -0.121978 + outer loop + vertex 852.847 275.71 221.026 + vertex 852.014 276.419 219.459 + vertex 852.818 275.999 219.118 + endloop + endfacet + facet normal -0.50754 -0.85015 -0.140174 + outer loop + vertex 852.061 275.835 223.309 + vertex 851.853 276.297 221.259 + vertex 852.867 275.419 222.914 + endloop + endfacet + facet normal -0.525621 -0.841556 -0.124523 + outer loop + vertex 852.867 275.419 222.914 + vertex 851.853 276.297 221.259 + vertex 852.847 275.71 221.026 + endloop + endfacet + facet normal -0.338383 -0.930497 -0.140258 + outer loop + vertex 852.867 275.419 222.914 + vertex 852.847 275.71 221.026 + vertex 853.448 275.282 222.417 + endloop + endfacet + facet normal -0.31949 -0.935641 -0.150006 + outer loop + vertex 853.448 275.282 222.417 + vertex 852.847 275.71 221.026 + vertex 853.482 275.562 220.602 + endloop + endfacet + facet normal -0.312111 -0.940055 -0.137418 + outer loop + vertex 852.847 275.71 221.026 + vertex 852.818 275.999 219.118 + vertex 853.482 275.562 220.602 + endloop + endfacet + facet normal -0.320094 -0.937971 -0.133229 + outer loop + vertex 853.482 275.562 220.602 + vertex 852.818 275.999 219.118 + vertex 853.379 275.874 218.654 + endloop + endfacet + facet normal -0.901318 -0.426287 -0.0768448 + outer loop + vertex 847.276 282.85 223.8 + vertex 847.343 283.366 220.157 + vertex 848.748 279.859 223.124 + endloop + endfacet + facet normal -0.905441 -0.419225 -0.0665444 + outer loop + vertex 848.748 279.859 223.124 + vertex 847.343 283.366 220.157 + vertex 848.687 280.625 219.129 + endloop + endfacet + facet normal -0.887501 -0.442623 -0.12817 + outer loop + vertex 847.568 281.187 227.521 + vertex 847.276 282.85 223.8 + vertex 848.697 279.117 226.848 + endloop + endfacet + facet normal -0.901482 -0.421959 -0.0963406 + outer loop + vertex 848.697 279.117 226.848 + vertex 847.276 282.85 223.8 + vertex 848.748 279.859 223.124 + endloop + endfacet + facet normal -0.792141 -0.596416 -0.129615 + outer loop + vertex 848.697 279.117 226.848 + vertex 848.748 279.859 223.124 + vertex 850.654 276.548 226.71 + endloop + endfacet + facet normal -0.812426 -0.574644 -0.0987301 + outer loop + vertex 850.654 276.548 226.71 + vertex 848.748 279.859 223.124 + vertex 850.584 277.388 222.4 + endloop + endfacet + facet normal -0.812373 -0.57488 -0.0977907 + outer loop + vertex 848.748 279.859 223.124 + vertex 848.687 280.625 219.129 + vertex 850.584 277.388 222.4 + endloop + endfacet + facet normal -0.823462 -0.561911 -0.0785283 + outer loop + vertex 850.584 277.388 222.4 + vertex 848.687 280.625 219.129 + vertex 850.535 278.015 218.428 + endloop + endfacet + facet normal -0.160011 -0.978879 -0.127251 + outer loop + vertex 853.302 276.441 214.717 + vertex 853.336 276.686 212.792 + vertex 853.793 276.305 215.141 + endloop + endfacet + facet normal -0.172599 -0.977467 -0.121522 + outer loop + vertex 853.242 276.958 210.731 + vertex 853.676 276.827 211.167 + vertex 853.336 276.686 212.792 + endloop + endfacet + facet normal -0.179866 -0.975982 -0.122913 + outer loop + vertex 853.676 276.827 211.167 + vertex 853.793 276.305 215.141 + vertex 853.336 276.686 212.792 + endloop + endfacet + facet normal -0.161493 -0.976922 -0.139794 + outer loop + vertex 853.379 275.874 218.654 + vertex 853.409 276.138 216.771 + vertex 853.829 275.742 219.055 + endloop + endfacet + facet normal -0.152144 -0.978903 -0.136388 + outer loop + vertex 853.302 276.441 214.717 + vertex 853.793 276.305 215.141 + vertex 853.409 276.138 216.771 + endloop + endfacet + facet normal -0.164764 -0.976473 -0.139114 + outer loop + vertex 853.793 276.305 215.141 + vertex 853.829 275.742 219.055 + vertex 853.409 276.138 216.771 + endloop + endfacet + facet normal -0.697236 -0.710515 -0.0950283 + outer loop + vertex 851.891 277.502 211.568 + vertex 851.734 277.408 213.424 + vertex 850.445 279.056 210.552 + endloop + endfacet + facet normal -0.708828 -0.701769 -0.0712897 + outer loop + vertex 851.95 276.974 215.542 + vertex 850.486 278.56 214.492 + vertex 851.734 277.408 213.424 + endloop + endfacet + facet normal -0.712426 -0.697113 -0.0805205 + outer loop + vertex 850.486 278.56 214.492 + vertex 850.445 279.056 210.552 + vertex 851.734 277.408 213.424 + endloop + endfacet + facet normal -0.697448 -0.70974 -0.0991749 + outer loop + vertex 851.95 276.974 215.542 + vertex 851.795 276.87 217.377 + vertex 850.486 278.56 214.492 + endloop + endfacet + facet normal -0.705355 -0.704506 -0.078394 + outer loop + vertex 852.014 276.419 219.459 + vertex 850.535 278.015 218.428 + vertex 851.795 276.87 217.377 + endloop + endfacet + facet normal -0.709013 -0.699679 -0.0880361 + outer loop + vertex 850.535 278.015 218.428 + vertex 850.486 278.56 214.492 + vertex 851.795 276.87 217.377 + endloop + endfacet + facet normal -0.520336 -0.848988 -0.0920325 + outer loop + vertex 851.795 276.87 217.377 + vertex 851.95 276.974 215.542 + vertex 852.776 276.292 217.169 + endloop + endfacet + facet normal -0.491565 -0.863515 -0.112721 + outer loop + vertex 852.776 276.292 217.169 + vertex 851.95 276.974 215.542 + vertex 852.738 276.572 215.189 + endloop + endfacet + facet normal -0.502718 -0.854292 -0.132135 + outer loop + vertex 852.014 276.419 219.459 + vertex 851.795 276.87 217.377 + vertex 852.818 275.999 219.118 + endloop + endfacet + facet normal -0.522739 -0.844626 -0.115542 + outer loop + vertex 852.818 275.999 219.118 + vertex 851.795 276.87 217.377 + vertex 852.776 276.292 217.169 + endloop + endfacet + facet normal -0.32057 -0.937717 -0.133874 + outer loop + vertex 852.818 275.999 219.118 + vertex 852.776 276.292 217.169 + vertex 853.379 275.874 218.654 + endloop + endfacet + facet normal -0.314144 -0.939443 -0.13697 + outer loop + vertex 853.379 275.874 218.654 + vertex 852.776 276.292 217.169 + vertex 853.409 276.138 216.771 + endloop + endfacet + facet normal -0.308861 -0.94254 -0.127367 + outer loop + vertex 852.776 276.292 217.169 + vertex 852.738 276.572 215.189 + vertex 853.409 276.138 216.771 + endloop + endfacet + facet normal -0.319848 -0.939594 -0.121902 + outer loop + vertex 853.409 276.138 216.771 + vertex 852.738 276.572 215.189 + vertex 853.302 276.441 214.717 + endloop + endfacet + facet normal -0.517693 -0.851139 -0.0869249 + outer loop + vertex 851.734 277.408 213.424 + vertex 851.891 277.502 211.568 + vertex 852.705 276.841 213.192 + endloop + endfacet + facet normal -0.493491 -0.8635 -0.104086 + outer loop + vertex 852.705 276.841 213.192 + vertex 851.891 277.502 211.568 + vertex 852.679 277.096 211.196 + endloop + endfacet + facet normal -0.495294 -0.859619 -0.125452 + outer loop + vertex 851.95 276.974 215.542 + vertex 851.734 277.408 213.424 + vertex 852.738 276.572 215.189 + endloop + endfacet + facet normal -0.520073 -0.847564 -0.105641 + outer loop + vertex 852.738 276.572 215.189 + vertex 851.734 277.408 213.424 + vertex 852.705 276.841 213.192 + endloop + endfacet + facet normal -0.319444 -0.939802 -0.12136 + outer loop + vertex 852.738 276.572 215.189 + vertex 852.705 276.841 213.192 + vertex 853.302 276.441 214.717 + endloop + endfacet + facet normal -0.31118 -0.942069 -0.125191 + outer loop + vertex 853.302 276.441 214.717 + vertex 852.705 276.841 213.192 + vertex 853.336 276.686 212.792 + endloop + endfacet + facet normal -0.306587 -0.944629 -0.116968 + outer loop + vertex 852.705 276.841 213.192 + vertex 852.679 277.096 211.196 + vertex 853.336 276.686 212.792 + endloop + endfacet + facet normal -0.321299 -0.940583 -0.109867 + outer loop + vertex 853.336 276.686 212.792 + vertex 852.679 277.096 211.196 + vertex 853.242 276.958 210.731 + endloop + endfacet + facet normal -0.918099 -0.395177 -0.0304771 + outer loop + vertex 847.064 284.839 215.911 + vertex 847.243 284.722 212.03 + vertex 848.642 281.231 215.143 + endloop + endfacet + facet normal -0.911968 -0.407549 -0.0471072 + outer loop + vertex 848.642 281.231 215.143 + vertex 847.243 284.722 212.03 + vertex 848.615 281.749 211.188 + endloop + endfacet + facet normal -0.906704 -0.413342 -0.0838827 + outer loop + vertex 847.343 283.366 220.157 + vertex 847.064 284.839 215.911 + vertex 848.687 280.625 219.129 + endloop + endfacet + facet normal -0.918853 -0.391523 -0.0491746 + outer loop + vertex 848.687 280.625 219.129 + vertex 847.064 284.839 215.911 + vertex 848.642 281.231 215.143 + endloop + endfacet + facet normal -0.823324 -0.562426 -0.0762509 + outer loop + vertex 848.687 280.625 219.129 + vertex 848.642 281.231 215.143 + vertex 850.535 278.015 218.428 + endloop + endfacet + facet normal -0.828675 -0.55575 -0.0666327 + outer loop + vertex 850.535 278.015 218.428 + vertex 848.642 281.231 215.143 + vertex 850.486 278.56 214.492 + endloop + endfacet + facet normal -0.828701 -0.555656 -0.0670933 + outer loop + vertex 848.642 281.231 215.143 + vertex 848.615 281.749 211.188 + vertex 850.486 278.56 214.492 + endloop + endfacet + facet normal -0.832121 -0.551241 -0.060894 + outer loop + vertex 850.486 278.56 214.492 + vertex 848.615 281.749 211.188 + vertex 850.445 279.056 210.552 + endloop + endfacet + facet normal -0.197704 -0.975183 -0.099655 + outer loop + vertex 853.179 277.412 206.835 + vertex 853.216 277.595 204.973 + vertex 853.621 277.257 207.481 + endloop + endfacet + facet normal -0.192481 -0.976493 -0.0970141 + outer loop + vertex 853.115 277.822 202.894 + vertex 853.581 277.664 203.556 + vertex 853.216 277.595 204.973 + endloop + endfacet + facet normal -0.200828 -0.974604 -0.0990723 + outer loop + vertex 853.581 277.664 203.556 + vertex 853.621 277.257 207.481 + vertex 853.216 277.595 204.973 + endloop + endfacet + facet normal -0.179742 -0.977051 -0.114299 + outer loop + vertex 853.242 276.958 210.731 + vertex 853.277 277.17 208.864 + vertex 853.676 276.827 211.167 + endloop + endfacet + facet normal -0.186627 -0.976526 -0.107552 + outer loop + vertex 853.179 277.412 206.835 + vertex 853.621 277.257 207.481 + vertex 853.277 277.17 208.864 + endloop + endfacet + facet normal -0.19902 -0.97375 -0.110466 + outer loop + vertex 853.621 277.257 207.481 + vertex 853.676 276.827 211.167 + vertex 853.277 277.17 208.864 + endloop + endfacet + facet normal -0.702081 -0.707766 -0.0784171 + outer loop + vertex 851.804 278.402 203.65 + vertex 851.645 278.354 205.506 + vertex 850.384 279.92 202.659 + endloop + endfacet + facet normal -0.711472 -0.700359 -0.057485 + outer loop + vertex 851.851 277.972 207.61 + vertex 850.414 279.514 206.614 + vertex 851.645 278.354 205.506 + endloop + endfacet + facet normal -0.715073 -0.695914 -0.066138 + outer loop + vertex 850.414 279.514 206.614 + vertex 850.384 279.92 202.659 + vertex 851.645 278.354 205.506 + endloop + endfacet + facet normal -0.700834 -0.708236 -0.0850464 + outer loop + vertex 851.851 277.972 207.61 + vertex 851.687 277.913 209.459 + vertex 850.414 279.514 206.614 + endloop + endfacet + facet normal -0.707865 -0.703024 -0.068445 + outer loop + vertex 851.891 277.502 211.568 + vertex 850.445 279.056 210.552 + vertex 851.687 277.913 209.459 + endloop + endfacet + facet normal -0.710773 -0.699347 -0.0755939 + outer loop + vertex 850.445 279.056 210.552 + vertex 850.414 279.514 206.614 + vertex 851.687 277.913 209.459 + endloop + endfacet + facet normal -0.520662 -0.850584 -0.0736023 + outer loop + vertex 851.687 277.913 209.459 + vertex 851.851 277.972 207.61 + vertex 852.655 277.341 209.217 + endloop + endfacet + facet normal -0.493364 -0.864852 -0.0928548 + outer loop + vertex 852.655 277.341 209.217 + vertex 851.851 277.972 207.61 + vertex 852.626 277.569 207.245 + endloop + endfacet + facet normal -0.49819 -0.858849 -0.119103 + outer loop + vertex 851.891 277.502 211.568 + vertex 851.687 277.913 209.459 + vertex 852.679 277.096 211.196 + endloop + endfacet + facet normal -0.524103 -0.845967 -0.0982637 + outer loop + vertex 852.679 277.096 211.196 + vertex 851.687 277.913 209.459 + vertex 852.655 277.341 209.217 + endloop + endfacet + facet normal -0.323059 -0.939697 -0.112259 + outer loop + vertex 852.679 277.096 211.196 + vertex 852.655 277.341 209.217 + vertex 853.242 276.958 210.731 + endloop + endfacet + facet normal -0.322018 -0.939997 -0.112738 + outer loop + vertex 853.242 276.958 210.731 + vertex 852.655 277.341 209.217 + vertex 853.277 277.17 208.864 + endloop + endfacet + facet normal -0.317933 -0.942348 -0.104398 + outer loop + vertex 852.655 277.341 209.217 + vertex 852.626 277.569 207.245 + vertex 853.277 277.17 208.864 + endloop + endfacet + facet normal -0.336386 -0.936856 -0.0956288 + outer loop + vertex 853.277 277.17 208.864 + vertex 852.626 277.569 207.245 + vertex 853.179 277.412 206.835 + endloop + endfacet + facet normal -0.526417 -0.84758 -0.0670297 + outer loop + vertex 851.645 278.354 205.506 + vertex 851.804 278.402 203.65 + vertex 852.599 277.78 205.274 + endloop + endfacet + facet normal -0.504963 -0.859237 -0.0819957 + outer loop + vertex 852.599 277.78 205.274 + vertex 851.804 278.402 203.65 + vertex 852.57 277.986 203.293 + endloop + endfacet + facet normal -0.497984 -0.8605 -0.10748 + outer loop + vertex 851.851 277.972 207.61 + vertex 851.645 278.354 205.506 + vertex 852.626 277.569 207.245 + endloop + endfacet + facet normal -0.528625 -0.844777 -0.083109 + outer loop + vertex 852.626 277.569 207.245 + vertex 851.645 278.354 205.506 + vertex 852.599 277.78 205.274 + endloop + endfacet + facet normal -0.336347 -0.936877 -0.0955679 + outer loop + vertex 852.626 277.569 207.245 + vertex 852.599 277.78 205.274 + vertex 853.179 277.412 206.835 + endloop + endfacet + facet normal -0.329321 -0.939046 -0.0986895 + outer loop + vertex 853.179 277.412 206.835 + vertex 852.599 277.78 205.274 + vertex 853.216 277.595 204.973 + endloop + endfacet + facet normal -0.326985 -0.940436 -0.0930669 + outer loop + vertex 852.599 277.78 205.274 + vertex 852.57 277.986 203.293 + vertex 853.216 277.595 204.973 + endloop + endfacet + facet normal -0.344382 -0.934964 -0.085107 + outer loop + vertex 853.216 277.595 204.973 + vertex 852.57 277.986 203.293 + vertex 853.115 277.822 202.894 + endloop + endfacet + facet normal -0.921267 -0.388294 -0.0222194 + outer loop + vertex 847.016 285.933 207.825 + vertex 847.224 285.65 204.117 + vertex 848.597 282.212 207.265 + endloop + endfacet + facet normal -0.914652 -0.402227 -0.0403167 + outer loop + vertex 848.597 282.212 207.265 + vertex 847.224 285.65 204.117 + vertex 848.585 282.634 203.333 + endloop + endfacet + facet normal -0.912994 -0.402499 -0.0666054 + outer loop + vertex 847.243 284.722 212.03 + vertex 847.016 285.933 207.825 + vertex 848.615 281.749 211.188 + endloop + endfacet + facet normal -0.921734 -0.385604 -0.0414285 + outer loop + vertex 848.615 281.749 211.188 + vertex 847.016 285.933 207.825 + vertex 848.597 282.212 207.265 + endloop + endfacet + facet normal -0.832149 -0.551146 -0.0613739 + outer loop + vertex 848.615 281.749 211.188 + vertex 848.597 282.212 207.265 + vertex 850.445 279.056 210.552 + endloop + endfacet + facet normal -0.834532 -0.548002 -0.0570147 + outer loop + vertex 850.445 279.056 210.552 + vertex 848.597 282.212 207.265 + vertex 850.414 279.514 206.614 + endloop + endfacet + facet normal -0.834481 -0.548162 -0.0562104 + outer loop + vertex 848.597 282.212 207.265 + vertex 848.585 282.634 203.333 + vertex 850.414 279.514 206.614 + endloop + endfacet + facet normal -0.838107 -0.543253 -0.0495215 + outer loop + vertex 850.414 279.514 206.614 + vertex 848.585 282.634 203.333 + vertex 850.384 279.92 202.659 + endloop + endfacet + facet normal -0.226724 -0.971142 -0.0740179 + outer loop + vertex 853.056 278.182 198.904 + vertex 853.101 278.318 196.992 + vertex 853.483 278.035 199.525 + endloop + endfacet + facet normal -0.211652 -0.974723 -0.0715405 + outer loop + vertex 853.018 278.49 194.893 + vertex 853.48 278.356 195.344 + vertex 853.101 278.318 196.992 + endloop + endfacet + facet normal -0.224453 -0.971639 -0.0744157 + outer loop + vertex 853.48 278.356 195.344 + vertex 853.483 278.035 199.525 + vertex 853.101 278.318 196.992 + endloop + endfacet + facet normal -0.205592 -0.974731 -0.0873594 + outer loop + vertex 853.115 277.822 202.894 + vertex 853.149 277.984 201 + vertex 853.581 277.664 203.556 + endloop + endfacet + facet normal -0.21515 -0.973096 -0.0824282 + outer loop + vertex 853.056 278.182 198.904 + vertex 853.483 278.035 199.525 + vertex 853.149 277.984 201 + endloop + endfacet + facet normal -0.222612 -0.971277 -0.0840533 + outer loop + vertex 853.483 278.035 199.525 + vertex 853.581 277.664 203.556 + vertex 853.149 277.984 201 + endloop + endfacet + facet normal -0.712414 -0.699225 -0.059582 + outer loop + vertex 851.731 279.097 195.689 + vertex 851.571 279.101 197.549 + vertex 850.336 280.604 194.691 + endloop + endfacet + facet normal -0.719313 -0.693459 -0.0412646 + outer loop + vertex 851.768 278.772 199.667 + vertex 850.36 280.29 198.68 + vertex 851.571 279.101 197.549 + endloop + endfacet + facet normal -0.722943 -0.689116 -0.0497202 + outer loop + vertex 850.36 280.29 198.68 + vertex 850.336 280.604 194.691 + vertex 851.571 279.101 197.549 + endloop + endfacet + facet normal -0.709513 -0.701448 -0.0675463 + outer loop + vertex 851.768 278.772 199.667 + vertex 851.604 278.757 201.534 + vertex 850.36 280.29 198.68 + endloop + endfacet + facet normal -0.712926 -0.699446 -0.0501165 + outer loop + vertex 851.804 278.402 203.65 + vertex 850.384 279.92 202.659 + vertex 851.604 278.757 201.534 + endloop + endfacet + facet normal -0.717269 -0.694185 -0.060263 + outer loop + vertex 850.384 279.92 202.659 + vertex 850.36 280.29 198.68 + vertex 851.604 278.757 201.534 + endloop + endfacet + facet normal -0.533856 -0.843896 -0.0532623 + outer loop + vertex 851.604 278.757 201.534 + vertex 851.768 278.772 199.667 + vertex 852.547 278.175 201.304 + endloop + endfacet + facet normal -0.508233 -0.858312 -0.0707156 + outer loop + vertex 852.547 278.175 201.304 + vertex 851.768 278.772 199.667 + vertex 852.527 278.352 199.312 + endloop + endfacet + facet normal -0.509145 -0.855368 -0.0954794 + outer loop + vertex 851.804 278.402 203.65 + vertex 851.604 278.757 201.534 + vertex 852.57 277.986 203.293 + endloop + endfacet + facet normal -0.536767 -0.840497 -0.073797 + outer loop + vertex 852.57 277.986 203.293 + vertex 851.604 278.757 201.534 + vertex 852.547 278.175 201.304 + endloop + endfacet + facet normal -0.344288 -0.935012 -0.0849585 + outer loop + vertex 852.57 277.986 203.293 + vertex 852.547 278.175 201.304 + vertex 853.115 277.822 202.894 + endloop + endfacet + facet normal -0.340665 -0.936196 -0.086513 + outer loop + vertex 853.115 277.822 202.894 + vertex 852.547 278.175 201.304 + vertex 853.149 277.984 201 + endloop + endfacet + facet normal -0.33769 -0.937891 -0.0795403 + outer loop + vertex 852.547 278.175 201.304 + vertex 852.527 278.352 199.312 + vertex 853.149 277.984 201 + endloop + endfacet + facet normal -0.353761 -0.932526 -0.0724472 + outer loop + vertex 853.149 277.984 201 + vertex 852.527 278.352 199.312 + vertex 853.056 278.182 198.904 + endloop + endfacet + facet normal -0.538615 -0.841385 -0.0443333 + outer loop + vertex 851.571 279.101 197.549 + vertex 851.731 279.097 195.689 + vertex 852.501 278.518 197.322 + endloop + endfacet + facet normal -0.517407 -0.853724 -0.0587077 + outer loop + vertex 852.501 278.518 197.322 + vertex 851.731 279.097 195.689 + vertex 852.48 278.668 195.335 + endloop + endfacet + facet normal -0.512852 -0.854212 -0.0854656 + outer loop + vertex 851.768 278.772 199.667 + vertex 851.571 279.101 197.549 + vertex 852.527 278.352 199.312 + endloop + endfacet + facet normal -0.541377 -0.838396 -0.0632781 + outer loop + vertex 852.527 278.352 199.312 + vertex 851.571 279.101 197.549 + vertex 852.501 278.518 197.322 + endloop + endfacet + facet normal -0.354499 -0.932159 -0.0735571 + outer loop + vertex 852.527 278.352 199.312 + vertex 852.501 278.518 197.322 + vertex 853.056 278.182 198.904 + endloop + endfacet + facet normal -0.352895 -0.932713 -0.0742377 + outer loop + vertex 853.056 278.182 198.904 + vertex 852.501 278.518 197.322 + vertex 853.101 278.318 196.992 + endloop + endfacet + facet normal -0.349324 -0.934634 -0.0665796 + outer loop + vertex 852.501 278.518 197.322 + vertex 852.48 278.668 195.335 + vertex 853.101 278.318 196.992 + endloop + endfacet + facet normal -0.359233 -0.931177 -0.0621344 + outer loop + vertex 853.101 278.318 196.992 + vertex 852.48 278.668 195.335 + vertex 853.018 278.49 194.893 + endloop + endfacet + facet normal -0.923689 -0.383016 -0.00988544 + outer loop + vertex 847.008 286.754 199.917 + vertex 847.211 286.361 196.194 + vertex 848.57 283 199.373 + endloop + endfacet + facet normal -0.916996 -0.397881 -0.028463 + outer loop + vertex 848.57 283 199.373 + vertex 847.211 286.361 196.194 + vertex 848.556 283.317 195.385 + endloop + endfacet + facet normal -0.915513 -0.398172 -0.0574128 + outer loop + vertex 847.224 285.65 204.117 + vertex 847.008 286.754 199.917 + vertex 848.585 282.634 203.333 + endloop + endfacet + facet normal -0.924382 -0.380158 -0.0315914 + outer loop + vertex 848.585 282.634 203.333 + vertex 847.008 286.754 199.917 + vertex 848.57 283 199.373 + endloop + endfacet + facet normal -0.837928 -0.543751 -0.0470371 + outer loop + vertex 848.585 282.634 203.333 + vertex 848.57 283 199.373 + vertex 850.384 279.92 202.659 + endloop + endfacet + facet normal -0.838786 -0.542562 -0.0454491 + outer loop + vertex 850.384 279.92 202.659 + vertex 848.57 283 199.373 + vertex 850.36 280.29 198.68 + endloop + endfacet + facet normal -0.838376 -0.543599 -0.0403335 + outer loop + vertex 848.57 283 199.373 + vertex 848.556 283.317 195.385 + vertex 850.36 280.29 198.68 + endloop + endfacet + facet normal -0.839962 -0.541354 -0.0374026 + outer loop + vertex 850.36 280.29 198.68 + vertex 848.556 283.317 195.385 + vertex 850.336 280.604 194.691 + endloop + endfacet + facet normal -0.223709 -0.973209 -0.0530824 + outer loop + vertex 852.993 278.756 190.852 + vertex 853.049 278.847 188.961 + vertex 853.41 278.644 191.154 + endloop + endfacet + facet normal -0.219249 -0.974455 -0.0486522 + outer loop + vertex 852.967 278.967 186.921 + vertex 853.382 278.848 187.441 + vertex 853.049 278.847 188.961 + endloop + endfacet + facet normal -0.232235 -0.971295 -0.0514995 + outer loop + vertex 853.382 278.848 187.441 + vertex 853.41 278.644 191.154 + vertex 853.049 278.847 188.961 + endloop + endfacet + facet normal -0.217937 -0.973808 -0.0648194 + outer loop + vertex 853.018 278.49 194.893 + vertex 853.067 278.609 192.94 + vertex 853.48 278.356 195.344 + endloop + endfacet + facet normal -0.218087 -0.974012 -0.0611477 + outer loop + vertex 852.993 278.756 190.852 + vertex 853.41 278.644 191.154 + vertex 853.067 278.609 192.94 + endloop + endfacet + facet normal -0.227625 -0.971713 -0.0629341 + outer loop + vertex 853.41 278.644 191.154 + vertex 853.48 278.356 195.344 + vertex 853.067 278.609 192.94 + endloop + endfacet + facet normal -0.711544 -0.701176 -0.045348 + outer loop + vertex 851.678 279.595 187.699 + vertex 851.514 279.641 189.573 + vertex 850.293 281.067 186.683 + endloop + endfacet + facet normal -0.724464 -0.688899 -0.0238951 + outer loop + vertex 851.699 279.372 191.705 + vertex 850.313 280.865 190.693 + vertex 851.514 279.641 189.573 + endloop + endfacet + facet normal -0.727458 -0.685457 -0.0308688 + outer loop + vertex 850.313 280.865 190.693 + vertex 850.293 281.067 186.683 + vertex 851.514 279.641 189.573 + endloop + endfacet + facet normal -0.713786 -0.698393 -0.0525065 + outer loop + vertex 851.699 279.372 191.705 + vertex 851.536 279.399 193.572 + vertex 850.313 280.865 190.693 + endloop + endfacet + facet normal -0.722827 -0.690307 -0.0315845 + outer loop + vertex 851.731 279.097 195.689 + vertex 850.336 280.604 194.691 + vertex 851.536 279.399 193.572 + endloop + endfacet + facet normal -0.726682 -0.685773 -0.0405992 + outer loop + vertex 850.336 280.604 194.691 + vertex 850.313 280.865 190.693 + vertex 851.536 279.399 193.572 + endloop + endfacet + facet normal -0.543246 -0.838818 -0.0356201 + outer loop + vertex 851.536 279.399 193.572 + vertex 851.699 279.372 191.705 + vertex 852.463 278.808 193.339 + endloop + endfacet + facet normal -0.518751 -0.853336 -0.0521009 + outer loop + vertex 852.463 278.808 193.339 + vertex 851.699 279.372 191.705 + vertex 852.453 278.937 191.336 + endloop + endfacet + facet normal -0.521903 -0.849886 -0.0728694 + outer loop + vertex 851.731 279.097 195.689 + vertex 851.536 279.399 193.572 + vertex 852.48 278.668 195.335 + endloop + endfacet + facet normal -0.546081 -0.83598 -0.0541612 + outer loop + vertex 852.48 278.668 195.335 + vertex 851.536 279.399 193.572 + vertex 852.463 278.808 193.339 + endloop + endfacet + facet normal -0.359401 -0.931097 -0.0623702 + outer loop + vertex 852.48 278.668 195.335 + vertex 852.463 278.808 193.339 + vertex 853.018 278.49 194.893 + endloop + endfacet + facet normal -0.351474 -0.933884 -0.0657695 + outer loop + vertex 853.018 278.49 194.893 + vertex 852.463 278.808 193.339 + vertex 853.067 278.609 192.94 + endloop + endfacet + facet normal -0.347242 -0.93596 -0.0583276 + outer loop + vertex 852.463 278.808 193.339 + vertex 852.453 278.937 191.336 + vertex 853.067 278.609 192.94 + endloop + endfacet + facet normal -0.3585 -0.932012 -0.0532092 + outer loop + vertex 853.067 278.609 192.94 + vertex 852.453 278.937 191.336 + vertex 852.993 278.756 190.852 + endloop + endfacet + facet normal -0.540703 -0.840781 -0.0269711 + outer loop + vertex 851.514 279.641 189.573 + vertex 851.678 279.595 187.699 + vertex 852.445 279.05 189.336 + endloop + endfacet + facet normal -0.521283 -0.852448 -0.0399568 + outer loop + vertex 852.445 279.05 189.336 + vertex 851.678 279.595 187.699 + vertex 852.435 279.149 187.347 + endloop + endfacet + facet normal -0.522001 -0.8507 -0.061841 + outer loop + vertex 851.699 279.372 191.705 + vertex 851.514 279.641 189.573 + vertex 852.453 278.937 191.336 + endloop + endfacet + facet normal -0.543644 -0.838094 -0.0452771 + outer loop + vertex 852.453 278.937 191.336 + vertex 851.514 279.641 189.573 + vertex 852.445 279.05 189.336 + endloop + endfacet + facet normal -0.357064 -0.932667 -0.0513625 + outer loop + vertex 852.453 278.937 191.336 + vertex 852.445 279.05 189.336 + vertex 852.993 278.756 190.852 + endloop + endfacet + facet normal -0.348718 -0.935615 -0.0549541 + outer loop + vertex 852.993 278.756 190.852 + vertex 852.445 279.05 189.336 + vertex 853.049 278.847 188.961 + endloop + endfacet + facet normal -0.343454 -0.938084 -0.045143 + outer loop + vertex 852.445 279.05 189.336 + vertex 852.435 279.149 187.347 + vertex 853.049 278.847 188.961 + endloop + endfacet + facet normal -0.352757 -0.934817 -0.0409922 + outer loop + vertex 853.049 278.847 188.961 + vertex 852.435 279.149 187.347 + vertex 852.967 278.967 186.921 + endloop + endfacet + facet normal -0.925114 -0.379669 -0.00408861 + outer loop + vertex 846.997 287.359 191.948 + vertex 847.208 286.885 188.189 + vertex 848.545 283.593 191.381 + endloop + endfacet + facet normal -0.919743 -0.392056 -0.0191173 + outer loop + vertex 848.545 283.593 191.381 + vertex 847.208 286.885 188.189 + vertex 848.533 283.817 187.371 + endloop + endfacet + facet normal -0.918108 -0.393604 -0.0464099 + outer loop + vertex 847.211 286.361 196.194 + vertex 846.997 287.359 191.948 + vertex 848.556 283.317 195.385 + endloop + endfacet + facet normal -0.925887 -0.377073 -0.0234441 + outer loop + vertex 848.556 283.317 195.385 + vertex 846.997 287.359 191.948 + vertex 848.545 283.593 191.381 + endloop + endfacet + facet normal -0.839757 -0.541832 -0.0350115 + outer loop + vertex 848.556 283.317 195.385 + vertex 848.545 283.593 191.381 + vertex 850.336 280.604 194.691 + endloop + endfacet + facet normal -0.842333 -0.538107 -0.0302535 + outer loop + vertex 850.336 280.604 194.691 + vertex 848.545 283.593 191.381 + vertex 850.313 280.865 190.693 + endloop + endfacet + facet normal -0.842089 -0.538636 -0.0275286 + outer loop + vertex 848.545 283.593 191.381 + vertex 848.533 283.817 187.371 + vertex 850.313 280.865 190.693 + endloop + endfacet + facet normal -0.844686 -0.53478 -0.0227122 + outer loop + vertex 850.313 280.865 190.693 + vertex 848.533 283.817 187.371 + vertex 850.293 281.067 186.683 + endloop + endfacet + facet normal -0.213754 -0.976468 -0.0286222 + outer loop + vertex 852.945 279.121 182.951 + vertex 852.992 279.167 181.013 + vertex 853.393 279.008 183.452 + endloop + endfacet + facet normal -0.22031 -0.975131 -0.0241623 + outer loop + vertex 852.918 279.236 178.899 + vertex 853.329 279.132 179.358 + vertex 852.992 279.167 181.013 + endloop + endfacet + facet normal -0.228799 -0.973128 -0.0259339 + outer loop + vertex 853.329 279.132 179.358 + vertex 853.393 279.008 183.452 + vertex 852.992 279.167 181.013 + endloop + endfacet + facet normal -0.231081 -0.972165 -0.0386837 + outer loop + vertex 852.967 278.967 186.921 + vertex 853.019 279.03 185.029 + vertex 853.382 278.848 187.441 + endloop + endfacet + facet normal -0.206681 -0.977773 -0.0352516 + outer loop + vertex 852.945 279.121 182.951 + vertex 853.393 279.008 183.452 + vertex 853.019 279.03 185.029 + endloop + endfacet + facet normal -0.225134 -0.973519 -0.0396804 + outer loop + vertex 853.393 279.008 183.452 + vertex 853.382 278.848 187.441 + vertex 853.019 279.03 185.029 + endloop + endfacet + facet normal -0.720101 -0.693335 -0.0272185 + outer loop + vertex 851.636 279.884 179.723 + vertex 851.468 279.986 181.585 + vertex 850.268 281.346 178.699 + endloop + endfacet + facet normal -0.725255 -0.688426 -0.00865346 + outer loop + vertex 851.655 279.763 183.708 + vertex 850.277 281.227 182.682 + vertex 851.468 279.986 181.585 + endloop + endfacet + facet normal -0.729564 -0.683657 -0.0187201 + outer loop + vertex 850.277 281.227 182.682 + vertex 850.268 281.346 178.699 + vertex 851.468 279.986 181.585 + endloop + endfacet + facet normal -0.716485 -0.696847 -0.0324644 + outer loop + vertex 851.655 279.763 183.708 + vertex 851.49 279.846 185.57 + vertex 850.277 281.227 182.682 + endloop + endfacet + facet normal -0.721975 -0.6917 -0.0174099 + outer loop + vertex 851.678 279.595 187.699 + vertex 850.293 281.067 186.683 + vertex 851.49 279.846 185.57 + endloop + endfacet + facet normal -0.725131 -0.688168 -0.0246818 + outer loop + vertex 850.293 281.067 186.683 + vertex 850.277 281.227 182.682 + vertex 851.49 279.846 185.57 + endloop + endfacet + facet normal -0.54895 -0.835777 -0.0114638 + outer loop + vertex 851.49 279.846 185.57 + vertex 851.655 279.763 183.708 + vertex 852.42 279.238 185.361 + endloop + endfacet + facet normal -0.522316 -0.852258 -0.0290252 + outer loop + vertex 852.42 279.238 185.361 + vertex 851.655 279.763 183.708 + vertex 852.403 279.315 183.371 + endloop + endfacet + facet normal -0.525519 -0.849112 -0.0532778 + outer loop + vertex 851.678 279.595 187.699 + vertex 851.49 279.846 185.57 + vertex 852.435 279.149 187.347 + endloop + endfacet + facet normal -0.552062 -0.833153 -0.0329026 + outer loop + vertex 852.435 279.149 187.347 + vertex 851.49 279.846 185.57 + vertex 852.42 279.238 185.361 + endloop + endfacet + facet normal -0.351371 -0.935424 -0.0389958 + outer loop + vertex 852.435 279.149 187.347 + vertex 852.42 279.238 185.361 + vertex 852.967 278.967 186.921 + endloop + endfacet + facet normal -0.347238 -0.936893 -0.0407017 + outer loop + vertex 852.967 278.967 186.921 + vertex 852.42 279.238 185.361 + vertex 853.019 279.03 185.029 + endloop + endfacet + facet normal -0.343952 -0.938377 -0.0338374 + outer loop + vertex 852.42 279.238 185.361 + vertex 852.403 279.315 183.371 + vertex 853.019 279.03 185.029 + endloop + endfacet + facet normal -0.357721 -0.933413 -0.0278637 + outer loop + vertex 853.019 279.03 185.029 + vertex 852.403 279.315 183.371 + vertex 852.945 279.121 182.951 + endloop + endfacet + facet normal -0.549805 -0.835283 -0.00411084 + outer loop + vertex 851.468 279.986 181.585 + vertex 851.636 279.884 179.723 + vertex 852.394 279.377 181.376 + endloop + endfacet + facet normal -0.525105 -0.850798 -0.0201909 + outer loop + vertex 852.394 279.377 181.376 + vertex 851.636 279.884 179.723 + vertex 852.387 279.429 179.368 + endloop + endfacet + facet normal -0.526627 -0.849011 -0.0429441 + outer loop + vertex 851.655 279.763 183.708 + vertex 851.468 279.986 181.585 + vertex 852.403 279.315 183.371 + endloop + endfacet + facet normal -0.552679 -0.833068 -0.0233264 + outer loop + vertex 852.403 279.315 183.371 + vertex 851.468 279.986 181.585 + vertex 852.394 279.377 181.376 + endloop + endfacet + facet normal -0.357392 -0.933553 -0.0273741 + outer loop + vertex 852.403 279.315 183.371 + vertex 852.394 279.377 181.376 + vertex 852.945 279.121 182.951 + endloop + endfacet + facet normal -0.348534 -0.936783 -0.0309961 + outer loop + vertex 852.945 279.121 182.951 + vertex 852.394 279.377 181.376 + vertex 852.992 279.167 181.013 + endloop + endfacet + facet normal -0.344357 -0.938555 -0.0230804 + outer loop + vertex 852.394 279.377 181.376 + vertex 852.387 279.429 179.368 + vertex 852.992 279.167 181.013 + endloop + endfacet + facet normal -0.356204 -0.934234 -0.0180321 + outer loop + vertex 852.992 279.167 181.013 + vertex 852.387 279.429 179.368 + vertex 852.918 279.236 178.899 + endloop + endfacet + facet normal -0.926263 -0.376841 0.00521081 + outer loop + vertex 846.989 287.767 183.942 + vertex 847.201 287.194 180.188 + vertex 848.524 283.986 183.362 + endloop + endfacet + facet normal -0.921001 -0.389439 -0.00971993 + outer loop + vertex 848.524 283.986 183.362 + vertex 847.201 287.194 180.188 + vertex 848.517 284.102 179.369 + endloop + endfacet + facet normal -0.920746 -0.388757 -0.0331041 + outer loop + vertex 847.208 286.885 188.189 + vertex 846.989 287.767 183.942 + vertex 848.533 283.817 187.371 + endloop + endfacet + facet normal -0.927194 -0.374335 -0.0135849 + outer loop + vertex 848.533 283.817 187.371 + vertex 846.989 287.767 183.942 + vertex 848.524 283.986 183.362 + endloop + endfacet + facet normal -0.844485 -0.535184 -0.0205869 + outer loop + vertex 848.533 283.817 187.371 + vertex 848.524 283.986 183.362 + vertex 850.293 281.067 186.683 + endloop + endfacet + facet normal -0.84587 -0.533086 -0.0180054 + outer loop + vertex 850.293 281.067 186.683 + vertex 848.524 283.986 183.362 + vertex 850.277 281.227 182.682 + endloop + endfacet + facet normal -0.845485 -0.533814 -0.0140564 + outer loop + vertex 848.524 283.986 183.362 + vertex 848.517 284.102 179.369 + vertex 850.277 281.227 182.682 + endloop + endfacet + facet normal -0.845533 -0.533741 -0.0139682 + outer loop + vertex 850.277 281.227 182.682 + vertex 848.517 284.102 179.369 + vertex 850.268 281.346 178.699 + endloop + endfacet + facet normal -0.220835 -0.975304 -0.00383338 + outer loop + vertex 852.911 279.295 174.827 + vertex 852.978 279.288 172.893 + vertex 853.36 279.192 175.272 + endloop + endfacet + facet normal -0.222551 -0.97492 -0.00168306 + outer loop + vertex 852.911 279.307 170.848 + vertex 853.315 279.214 171.288 + vertex 852.978 279.288 172.893 + endloop + endfacet + facet normal -0.227306 -0.97382 -0.00273328 + outer loop + vertex 853.315 279.214 171.288 + vertex 853.36 279.192 175.272 + vertex 852.978 279.288 172.893 + endloop + endfacet + facet normal -0.229061 -0.973282 -0.0158825 + outer loop + vertex 852.918 279.236 178.899 + vertex 852.977 279.254 176.939 + vertex 853.329 279.132 179.358 + endloop + endfacet + facet normal -0.212655 -0.977048 -0.0124849 + outer loop + vertex 852.911 279.295 174.827 + vertex 853.36 279.192 175.272 + vertex 852.977 279.254 176.939 + endloop + endfacet + facet normal -0.227775 -0.973581 -0.0160848 + outer loop + vertex 853.36 279.192 175.272 + vertex 853.329 279.132 179.358 + vertex 852.977 279.254 176.939 + endloop + endfacet + facet normal -0.720336 -0.693497 -0.0133342 + outer loop + vertex 851.626 279.971 171.724 + vertex 851.452 280.116 173.588 + vertex 850.258 281.41 170.782 + endloop + endfacet + facet normal -0.727723 -0.685833 0.00723798 + outer loop + vertex 851.629 279.951 175.716 + vertex 850.259 281.394 174.722 + vertex 851.452 280.116 173.588 + endloop + endfacet + facet normal -0.732119 -0.681172 -0.00264192 + outer loop + vertex 850.259 281.394 174.722 + vertex 850.258 281.41 170.782 + vertex 851.452 280.116 173.588 + endloop + endfacet + facet normal -0.719092 -0.694693 -0.0175347 + outer loop + vertex 851.629 279.951 175.716 + vertex 851.457 280.081 177.592 + vertex 850.259 281.394 174.722 + endloop + endfacet + facet normal -0.729292 -0.6842 -0.00190353 + outer loop + vertex 851.636 279.884 179.723 + vertex 850.268 281.346 178.699 + vertex 851.457 280.081 177.592 + endloop + endfacet + facet normal -0.731328 -0.681994 -0.00661373 + outer loop + vertex 850.268 281.346 178.699 + vertex 850.259 281.394 174.722 + vertex 851.457 280.081 177.592 + endloop + endfacet + facet normal -0.550038 -0.835104 0.00771331 + outer loop + vertex 851.457 280.081 177.592 + vertex 851.629 279.951 175.716 + vertex 852.382 279.47 177.349 + endloop + endfacet + facet normal -0.522528 -0.852562 -0.0101096 + outer loop + vertex 852.382 279.47 177.349 + vertex 851.629 279.951 175.716 + vertex 852.375 279.498 175.324 + endloop + endfacet + facet normal -0.529584 -0.847585 -0.0337764 + outer loop + vertex 851.636 279.884 179.723 + vertex 851.457 280.081 177.592 + vertex 852.387 279.429 179.368 + endloop + endfacet + facet normal -0.554196 -0.832246 -0.0152593 + outer loop + vertex 852.387 279.429 179.368 + vertex 851.457 280.081 177.592 + vertex 852.382 279.47 177.349 + endloop + endfacet + facet normal -0.356049 -0.934297 -0.0178302 + outer loop + vertex 852.387 279.429 179.368 + vertex 852.382 279.47 177.349 + vertex 852.918 279.236 178.899 + endloop + endfacet + facet normal -0.352406 -0.935648 -0.0192936 + outer loop + vertex 852.918 279.236 178.899 + vertex 852.382 279.47 177.349 + vertex 852.977 279.254 176.939 + endloop + endfacet + facet normal -0.347935 -0.937444 -0.0118541 + outer loop + vertex 852.382 279.47 177.349 + vertex 852.375 279.498 175.324 + vertex 852.977 279.254 176.939 + endloop + endfacet + facet normal -0.359193 -0.933237 -0.00701812 + outer loop + vertex 852.977 279.254 176.939 + vertex 852.375 279.498 175.324 + vertex 852.911 279.295 174.827 + endloop + endfacet + facet normal -0.54492 -0.838366 0.0142879 + outer loop + vertex 851.452 280.116 173.588 + vertex 851.626 279.971 171.724 + vertex 852.374 279.512 173.309 + endloop + endfacet + facet normal -0.520715 -0.853729 -0.00159026 + outer loop + vertex 852.374 279.512 173.309 + vertex 851.626 279.971 171.724 + vertex 852.377 279.514 171.325 + endloop + endfacet + facet normal -0.527054 -0.849541 -0.0222238 + outer loop + vertex 851.629 279.951 175.716 + vertex 851.452 280.116 173.588 + vertex 852.375 279.498 175.324 + endloop + endfacet + facet normal -0.549169 -0.835693 -0.00552709 + outer loop + vertex 852.375 279.498 175.324 + vertex 851.452 280.116 173.588 + vertex 852.374 279.512 173.309 + endloop + endfacet + facet normal -0.358635 -0.933456 -0.00632801 + outer loop + vertex 852.375 279.498 175.324 + vertex 852.374 279.512 173.309 + vertex 852.911 279.295 174.827 + endloop + endfacet + facet normal -0.353176 -0.935518 -0.00855501 + outer loop + vertex 852.911 279.295 174.827 + vertex 852.374 279.512 173.309 + vertex 852.978 279.288 172.893 + endloop + endfacet + facet normal -0.348882 -0.937166 -0.00143054 + outer loop + vertex 852.374 279.512 173.309 + vertex 852.377 279.514 171.325 + vertex 852.978 279.288 172.893 + endloop + endfacet + facet normal -0.359304 -0.933215 0.00313262 + outer loop + vertex 852.978 279.288 172.893 + vertex 852.377 279.514 171.325 + vertex 852.911 279.307 170.848 + endloop + endfacet + facet normal -0.9268 -0.37526 0.0148765 + outer loop + vertex 846.984 287.967 175.982 + vertex 847.195 287.298 172.278 + vertex 848.512 284.17 175.401 + endloop + endfacet + facet normal -0.921257 -0.388952 -0.0011757 + outer loop + vertex 848.512 284.17 175.401 + vertex 847.195 287.298 172.278 + vertex 848.51 284.187 171.469 + endloop + endfacet + facet normal -0.922094 -0.38625 -0.0235116 + outer loop + vertex 847.201 287.194 180.188 + vertex 846.984 287.967 175.982 + vertex 848.517 284.102 179.369 + endloop + endfacet + facet normal -0.927962 -0.372637 -0.00532862 + outer loop + vertex 848.517 284.102 179.369 + vertex 846.984 287.967 175.982 + vertex 848.512 284.17 175.401 + endloop + endfacet + facet normal -0.844952 -0.534779 -0.00818628 + outer loop + vertex 848.517 284.102 179.369 + vertex 848.512 284.17 175.401 + vertex 850.268 281.346 178.699 + endloop + endfacet + facet normal -0.846907 -0.531722 -0.00452782 + outer loop + vertex 850.268 281.346 178.699 + vertex 848.512 284.17 175.401 + vertex 850.259 281.394 174.722 + endloop + endfacet + facet normal -0.846618 -0.532198 -0.00184 + outer loop + vertex 848.512 284.17 175.401 + vertex 848.51 284.187 171.469 + vertex 850.259 281.394 174.722 + endloop + endfacet + facet normal -0.846518 -0.532357 -0.00203075 + outer loop + vertex 850.259 281.394 174.722 + vertex 848.51 284.187 171.469 + vertex 850.258 281.41 170.782 + endloop + endfacet + facet normal -0.23407 -0.972011 0.0201386 + outer loop + vertex 852.91 279.265 167.097 + vertex 852.964 279.214 165.281 + vertex 853.318 279.179 167.678 + endloop + endfacet + facet normal -0.219737 -0.975291 0.0228663 + outer loop + vertex 852.902 279.181 163.286 + vertex 853.354 279.089 163.676 + vertex 852.964 279.214 165.281 + endloop + endfacet + facet normal -0.231621 -0.972605 0.0197693 + outer loop + vertex 853.354 279.089 163.676 + vertex 853.318 279.179 167.678 + vertex 852.964 279.214 165.281 + endloop + endfacet + facet normal -0.232936 -0.972456 0.00836004 + outer loop + vertex 852.911 279.307 170.848 + vertex 852.974 279.276 169.039 + vertex 853.315 279.214 171.288 + endloop + endfacet + facet normal -0.224464 -0.974395 0.0130534 + outer loop + vertex 852.91 279.265 167.097 + vertex 853.318 279.179 167.678 + vertex 852.974 279.276 169.039 + endloop + endfacet + facet normal -0.238586 -0.971077 0.00925448 + outer loop + vertex 853.318 279.179 167.678 + vertex 853.315 279.214 171.288 + vertex 852.974 279.276 169.039 + endloop + endfacet + facet normal -0.720233 -0.693721 0.00398688 + outer loop + vertex 851.627 279.872 164.067 + vertex 851.455 280.06 165.834 + vertex 850.262 281.283 163.089 + endloop + endfacet + facet normal -0.7281 -0.685031 0.0245314 + outer loop + vertex 851.63 279.947 167.851 + vertex 850.259 281.37 166.913 + vertex 851.455 280.06 165.834 + endloop + endfacet + facet normal -0.732235 -0.680889 0.0149182 + outer loop + vertex 850.259 281.37 166.913 + vertex 850.262 281.283 163.089 + vertex 851.455 280.06 165.834 + endloop + endfacet + facet normal -0.718388 -0.69562 -0.00571277 + outer loop + vertex 851.63 279.947 167.851 + vertex 851.454 280.114 169.652 + vertex 850.259 281.37 166.913 + endloop + endfacet + facet normal -0.729139 -0.684231 0.0135852 + outer loop + vertex 851.626 279.971 171.724 + vertex 850.258 281.41 170.782 + vertex 851.454 280.114 169.652 + endloop + endfacet + facet normal -0.732112 -0.681149 0.00690373 + outer loop + vertex 850.258 281.41 170.782 + vertex 850.259 281.37 166.913 + vertex 851.454 280.114 169.652 + endloop + endfacet + facet normal -0.544749 -0.838242 0.0244677 + outer loop + vertex 851.454 280.114 169.652 + vertex 851.63 279.947 167.851 + vertex 852.379 279.505 169.389 + endloop + endfacet + facet normal -0.523825 -0.851763 0.0103891 + outer loop + vertex 852.379 279.505 169.389 + vertex 851.63 279.947 167.851 + vertex 852.376 279.483 167.495 + endloop + endfacet + facet normal -0.525741 -0.850517 -0.0147262 + outer loop + vertex 851.626 279.971 171.724 + vertex 851.454 280.114 169.652 + vertex 852.377 279.514 171.325 + endloop + endfacet + facet normal -0.549085 -0.83576 0.00344398 + outer loop + vertex 852.377 279.514 171.325 + vertex 851.454 280.114 169.652 + vertex 852.379 279.505 169.389 + endloop + endfacet + facet normal -0.358517 -0.933514 0.00414405 + outer loop + vertex 852.377 279.514 171.325 + vertex 852.379 279.505 169.389 + vertex 852.911 279.307 170.848 + endloop + endfacet + facet normal -0.356756 -0.934191 0.00340926 + outer loop + vertex 852.911 279.307 170.848 + vertex 852.379 279.505 169.389 + vertex 852.974 279.276 169.039 + endloop + endfacet + facet normal -0.352782 -0.93564 0.0111036 + outer loop + vertex 852.379 279.505 169.389 + vertex 852.376 279.483 167.495 + vertex 852.974 279.276 169.039 + endloop + endfacet + facet normal -0.367385 -0.929904 0.0175307 + outer loop + vertex 852.974 279.276 169.039 + vertex 852.376 279.483 167.495 + vertex 852.91 279.265 167.097 + endloop + endfacet + facet normal -0.548032 -0.835689 0.035853 + outer loop + vertex 851.455 280.06 165.834 + vertex 851.627 279.872 164.067 + vertex 852.371 279.45 165.617 + endloop + endfacet + facet normal -0.526309 -0.850021 0.0215225 + outer loop + vertex 852.371 279.45 165.617 + vertex 851.627 279.872 164.067 + vertex 852.369 279.404 163.728 + endloop + endfacet + facet normal -0.528128 -0.849162 -0.00205024 + outer loop + vertex 851.63 279.947 167.851 + vertex 851.455 280.06 165.834 + vertex 852.376 279.483 167.495 + endloop + endfacet + facet normal -0.551554 -0.833981 0.0162221 + outer loop + vertex 852.376 279.483 167.495 + vertex 851.455 280.06 165.834 + vertex 852.371 279.45 165.617 + endloop + endfacet + facet normal -0.367483 -0.929868 0.0173796 + outer loop + vertex 852.376 279.483 167.495 + vertex 852.371 279.45 165.617 + vertex 852.91 279.265 167.097 + endloop + endfacet + facet normal -0.362163 -0.931991 0.0151758 + outer loop + vertex 852.91 279.265 167.097 + vertex 852.371 279.45 165.617 + vertex 852.964 279.214 165.281 + endloop + endfacet + facet normal -0.358089 -0.933396 0.0233495 + outer loop + vertex 852.371 279.45 165.617 + vertex 852.369 279.404 163.728 + vertex 852.964 279.214 165.281 + endloop + endfacet + facet normal -0.365907 -0.930267 0.0267317 + outer loop + vertex 852.964 279.214 165.281 + vertex 852.369 279.404 163.728 + vertex 852.902 279.181 163.286 + endloop + endfacet + facet normal -0.927127 -0.373764 0.0271103 + outer loop + vertex 846.987 287.97 168.144 + vertex 847.191 287.201 164.516 + vertex 848.509 284.154 167.585 + endloop + endfacet + facet normal -0.920313 -0.391121 0.00695149 + outer loop + vertex 848.509 284.154 167.585 + vertex 847.191 287.201 164.516 + vertex 848.513 284.077 163.736 + endloop + endfacet + facet normal -0.922528 -0.385591 -0.0161697 + outer loop + vertex 847.195 287.298 172.278 + vertex 846.987 287.97 168.144 + vertex 848.51 284.187 171.469 + endloop + endfacet + facet normal -0.928667 -0.370898 0.00335735 + outer loop + vertex 848.51 284.187 171.469 + vertex 846.987 287.97 168.144 + vertex 848.509 284.154 167.585 + endloop + endfacet + facet normal -0.845754 -0.533552 0.00473725 + outer loop + vertex 848.51 284.187 171.469 + vertex 848.509 284.154 167.585 + vertex 850.258 281.41 170.782 + endloop + endfacet + facet normal -0.846055 -0.533068 0.0053167 + outer loop + vertex 850.258 281.41 170.782 + vertex 848.509 284.154 167.585 + vertex 850.259 281.37 166.913 + endloop + endfacet + facet normal -0.845531 -0.533836 0.00985909 + outer loop + vertex 848.509 284.154 167.585 + vertex 848.513 284.077 163.736 + vertex 850.259 281.37 166.913 + endloop + endfacet + facet normal -0.846379 -0.532457 0.0115 + outer loop + vertex 850.259 281.37 166.913 + vertex 848.513 284.077 163.736 + vertex 850.262 281.283 163.089 + endloop + endfacet + facet normal -0.231959 -0.971891 0.0402718 + outer loop + vertex 852.922 279.054 159.383 + vertex 853.001 278.959 157.531 + vertex 853.333 278.967 159.635 + endloop + endfacet + facet normal -0.219053 -0.974679 0.0449087 + outer loop + vertex 852.948 278.879 155.529 + vertex 853.349 278.809 155.989 + vertex 853.001 278.959 157.531 + endloop + endfacet + facet normal -0.235535 -0.971008 0.0408322 + outer loop + vertex 853.349 278.809 155.989 + vertex 853.333 278.967 159.635 + vertex 853.001 278.959 157.531 + endloop + endfacet + facet normal -0.225086 -0.973896 0.029388 + outer loop + vertex 852.902 279.181 163.286 + vertex 852.973 279.108 161.404 + vertex 853.354 279.089 163.676 + endloop + endfacet + facet normal -0.226988 -0.973382 0.0316689 + outer loop + vertex 852.922 279.054 159.383 + vertex 853.333 278.967 159.635 + vertex 852.973 279.108 161.404 + endloop + endfacet + facet normal -0.23199 -0.972238 0.0305602 + outer loop + vertex 853.333 278.967 159.635 + vertex 853.354 279.089 163.676 + vertex 852.973 279.108 161.404 + endloop + endfacet + facet normal -0.712919 -0.700966 0.0198047 + outer loop + vertex 851.655 279.58 156.33 + vertex 851.471 279.82 158.162 + vertex 850.278 280.952 155.325 + endloop + endfacet + facet normal -0.727292 -0.68545 0.0347101 + outer loop + vertex 851.635 279.75 160.238 + vertex 850.269 281.149 159.237 + vertex 851.471 279.82 158.162 + endloop + endfacet + facet normal -0.728157 -0.684629 0.032725 + outer loop + vertex 850.269 281.149 159.237 + vertex 850.278 280.952 155.325 + vertex 851.471 279.82 158.162 + endloop + endfacet + facet normal -0.719286 -0.694627 0.010948 + outer loop + vertex 851.635 279.75 160.238 + vertex 851.453 279.967 162.034 + vertex 850.269 281.149 159.237 + endloop + endfacet + facet normal -0.72893 -0.683918 0.0302791 + outer loop + vertex 851.627 279.872 164.067 + vertex 850.262 281.283 163.089 + vertex 851.453 279.967 162.034 + endloop + endfacet + facet normal -0.73229 -0.680626 0.0223714 + outer loop + vertex 850.262 281.283 163.089 + vertex 850.269 281.149 159.237 + vertex 851.453 279.967 162.034 + endloop + endfacet + facet normal -0.549205 -0.83447 0.0451034 + outer loop + vertex 851.453 279.967 162.034 + vertex 851.635 279.75 160.238 + vertex 852.372 279.35 161.812 + endloop + endfacet + facet normal -0.520279 -0.853578 0.0267218 + outer loop + vertex 852.372 279.35 161.812 + vertex 851.635 279.75 160.238 + vertex 852.385 279.282 159.876 + endloop + endfacet + facet normal -0.53157 -0.846995 0.00582585 + outer loop + vertex 851.627 279.872 164.067 + vertex 851.453 279.967 162.034 + vertex 852.369 279.404 163.728 + endloop + endfacet + facet normal -0.553437 -0.832589 0.022439 + outer loop + vertex 852.369 279.404 163.728 + vertex 851.453 279.967 162.034 + vertex 852.372 279.35 161.812 + endloop + endfacet + facet normal -0.366812 -0.929946 0.0254793 + outer loop + vertex 852.369 279.404 163.728 + vertex 852.372 279.35 161.812 + vertex 852.902 279.181 163.286 + endloop + endfacet + facet normal -0.359877 -0.932724 0.0226679 + outer loop + vertex 852.902 279.181 163.286 + vertex 852.372 279.35 161.812 + vertex 852.973 279.108 161.404 + endloop + endfacet + facet normal -0.355082 -0.934331 0.0306963 + outer loop + vertex 852.372 279.35 161.812 + vertex 852.385 279.282 159.876 + vertex 852.973 279.108 161.404 + endloop + endfacet + facet normal -0.362708 -0.931283 0.0339767 + outer loop + vertex 852.973 279.108 161.404 + vertex 852.385 279.282 159.876 + vertex 852.922 279.054 159.383 + endloop + endfacet + facet normal -0.543791 -0.837435 0.0547123 + outer loop + vertex 851.471 279.82 158.162 + vertex 851.655 279.58 156.33 + vertex 852.397 279.203 157.926 + endloop + endfacet + facet normal -0.518705 -0.854057 0.039134 + outer loop + vertex 852.397 279.203 157.926 + vertex 851.655 279.58 156.33 + vertex 852.41 279.105 155.97 + endloop + endfacet + facet normal -0.525189 -0.850885 0.0130805 + outer loop + vertex 851.635 279.75 160.238 + vertex 851.471 279.82 158.162 + vertex 852.385 279.282 159.876 + endloop + endfacet + facet normal -0.548685 -0.835474 0.0304576 + outer loop + vertex 852.385 279.282 159.876 + vertex 851.471 279.82 158.162 + vertex 852.397 279.203 157.926 + endloop + endfacet + facet normal -0.361505 -0.931695 0.0354777 + outer loop + vertex 852.385 279.282 159.876 + vertex 852.397 279.203 157.926 + vertex 852.922 279.054 159.383 + endloop + endfacet + facet normal -0.355464 -0.934105 0.0330539 + outer loop + vertex 852.922 279.054 159.383 + vertex 852.397 279.203 157.926 + vertex 853.001 278.959 157.531 + endloop + endfacet + facet normal -0.348863 -0.936121 0.0444029 + outer loop + vertex 852.397 279.203 157.926 + vertex 852.41 279.105 155.97 + vertex 853.001 278.959 157.531 + endloop + endfacet + facet normal -0.354856 -0.933744 0.046895 + outer loop + vertex 853.001 278.959 157.531 + vertex 852.41 279.105 155.97 + vertex 852.948 278.879 155.529 + endloop + endfacet + facet normal -0.926024 -0.375652 0.0369441 + outer loop + vertex 846.986 287.773 160.413 + vertex 847.191 286.909 156.776 + vertex 848.516 283.948 159.883 + endloop + endfacet + facet normal -0.919151 -0.39354 0.016961 + outer loop + vertex 848.516 283.948 159.883 + vertex 847.191 286.909 156.776 + vertex 848.52 283.771 155.989 + endloop + endfacet + facet normal -0.921643 -0.387958 -0.00796566 + outer loop + vertex 847.191 287.201 164.516 + vertex 846.986 287.773 160.413 + vertex 848.513 284.077 163.736 + endloop + endfacet + facet normal -0.927814 -0.37286 0.0116654 + outer loop + vertex 848.513 284.077 163.736 + vertex 846.986 287.773 160.413 + vertex 848.516 283.948 159.883 + endloop + endfacet + facet normal -0.845725 -0.533344 0.0170981 + outer loop + vertex 848.513 284.077 163.736 + vertex 848.516 283.948 159.883 + vertex 850.262 281.283 163.089 + endloop + endfacet + facet normal -0.845698 -0.53339 0.0170453 + outer loop + vertex 850.262 281.283 163.089 + vertex 848.516 283.948 159.883 + vertex 850.269 281.149 159.237 + endloop + endfacet + facet normal -0.844916 -0.534384 0.0234736 + outer loop + vertex 848.516 283.948 159.883 + vertex 848.52 283.771 155.989 + vertex 850.269 281.149 159.237 + endloop + endfacet + facet normal -0.845613 -0.53322 0.0247882 + outer loop + vertex 850.269 281.149 159.237 + vertex 848.52 283.771 155.989 + vertex 850.278 280.952 155.325 + endloop + endfacet + facet normal -0.214816 -0.974476 0.0651965 + outer loop + vertex 852.966 278.646 151.56 + vertex 853.048 278.5 149.64 + vertex 853.421 278.579 152.05 + endloop + endfacet + facet normal -0.206596 -0.975983 0.0690961 + outer loop + vertex 853.003 278.363 147.568 + vertex 853.411 278.309 148.04 + vertex 853.048 278.5 149.64 + endloop + endfacet + facet normal -0.219428 -0.973402 0.0658751 + outer loop + vertex 853.411 278.309 148.04 + vertex 853.421 278.579 152.05 + vertex 853.048 278.5 149.64 + endloop + endfacet + facet normal -0.22853 -0.972062 0.053574 + outer loop + vertex 852.948 278.879 155.529 + vertex 853.019 278.757 153.634 + vertex 853.349 278.809 155.989 + endloop + endfacet + facet normal -0.206954 -0.976654 0.0575946 + outer loop + vertex 852.966 278.646 151.56 + vertex 853.421 278.579 152.05 + vertex 853.019 278.757 153.634 + endloop + endfacet + facet normal -0.223796 -0.973197 0.052936 + outer loop + vertex 853.421 278.579 152.05 + vertex 853.349 278.809 155.989 + vertex 853.019 278.757 153.634 + endloop + endfacet + facet normal -0.713273 -0.700053 0.0341691 + outer loop + vertex 851.684 279.082 148.396 + vertex 851.496 279.364 150.256 + vertex 850.302 280.441 147.411 + endloop + endfacet + facet normal -0.721275 -0.690354 0.0563345 + outer loop + vertex 851.664 279.361 152.372 + vertex 850.287 280.718 151.373 + vertex 851.496 279.364 150.256 + endloop + endfacet + facet normal -0.726452 -0.685734 0.0451258 + outer loop + vertex 850.287 280.718 151.373 + vertex 850.302 280.441 147.411 + vertex 851.496 279.364 150.256 + endloop + endfacet + facet normal -0.71239 -0.701168 0.0293935 + outer loop + vertex 851.664 279.361 152.372 + vertex 851.484 279.622 154.226 + vertex 850.287 280.718 151.373 + endloop + endfacet + facet normal -0.72139 -0.691071 0.044921 + outer loop + vertex 851.655 279.58 156.33 + vertex 850.278 280.952 155.325 + vertex 851.484 279.622 154.226 + endloop + endfacet + facet normal -0.724036 -0.688653 0.039091 + outer loop + vertex 850.278 280.952 155.325 + vertex 850.287 280.718 151.373 + vertex 851.484 279.622 154.226 + endloop + endfacet + facet normal -0.542386 -0.837608 0.0650459 + outer loop + vertex 851.484 279.622 154.226 + vertex 851.664 279.361 152.372 + vertex 852.412 279.003 153.997 + endloop + endfacet + facet normal -0.51887 -0.853345 0.050758 + outer loop + vertex 852.412 279.003 153.997 + vertex 851.664 279.361 152.372 + vertex 852.42 278.88 152.011 + endloop + endfacet + facet normal -0.523577 -0.851592 0.025642 + outer loop + vertex 851.655 279.58 156.33 + vertex 851.484 279.622 154.226 + vertex 852.41 279.105 155.97 + endloop + endfacet + facet normal -0.546918 -0.836101 0.0426165 + outer loop + vertex 852.41 279.105 155.97 + vertex 851.484 279.622 154.226 + vertex 852.412 279.003 153.997 + endloop + endfacet + facet normal -0.354173 -0.933956 0.0478345 + outer loop + vertex 852.41 279.105 155.97 + vertex 852.412 279.003 153.997 + vertex 852.948 278.879 155.529 + endloop + endfacet + facet normal -0.350892 -0.935257 0.0465812 + outer loop + vertex 852.948 278.879 155.529 + vertex 852.412 279.003 153.997 + vertex 853.019 278.757 153.634 + endloop + endfacet + facet normal -0.345469 -0.936718 0.0566606 + outer loop + vertex 852.412 279.003 153.997 + vertex 852.42 278.88 152.011 + vertex 853.019 278.757 153.634 + endloop + endfacet + facet normal -0.351445 -0.934345 0.0590449 + outer loop + vertex 853.019 278.757 153.634 + vertex 852.42 278.88 152.011 + vertex 852.966 278.646 151.56 + endloop + endfacet + facet normal -0.535683 -0.841218 0.0734591 + outer loop + vertex 851.496 279.364 150.256 + vertex 851.684 279.082 148.396 + vertex 852.43 278.748 150.014 + endloop + endfacet + facet normal -0.509767 -0.858357 0.057975 + outer loop + vertex 852.43 278.748 150.014 + vertex 851.684 279.082 148.396 + vertex 852.448 278.603 148.022 + endloop + endfacet + facet normal -0.522686 -0.851567 0.0404033 + outer loop + vertex 851.664 279.361 152.372 + vertex 851.496 279.364 150.256 + vertex 852.42 278.88 152.011 + endloop + endfacet + facet normal -0.540164 -0.8399 0.0528233 + outer loop + vertex 852.42 278.88 152.011 + vertex 851.496 279.364 150.256 + vertex 852.43 278.748 150.014 + endloop + endfacet + facet normal -0.350742 -0.934548 0.0600003 + outer loop + vertex 852.42 278.88 152.011 + vertex 852.43 278.748 150.014 + vertex 852.966 278.646 151.56 + endloop + endfacet + facet normal -0.342507 -0.937789 0.0569299 + outer loop + vertex 852.966 278.646 151.56 + vertex 852.43 278.748 150.014 + vertex 853.048 278.5 149.64 + endloop + endfacet + facet normal -0.337835 -0.93893 0.0654104 + outer loop + vertex 852.43 278.748 150.014 + vertex 852.448 278.603 148.022 + vertex 853.048 278.5 149.64 + endloop + endfacet + facet normal -0.34806 -0.934896 0.0694601 + outer loop + vertex 853.048 278.5 149.64 + vertex 852.448 278.603 148.022 + vertex 853.003 278.363 147.568 + endloop + endfacet + facet normal -0.924396 -0.378841 0.0444085 + outer loop + vertex 846.982 287.377 152.612 + vertex 847.193 286.428 148.913 + vertex 848.526 283.544 152.055 + endloop + endfacet + facet normal -0.918399 -0.394713 0.0272913 + outer loop + vertex 848.526 283.544 152.055 + vertex 847.193 286.428 148.913 + vertex 848.529 283.264 148.102 + endloop + endfacet + facet normal -0.9206 -0.3905 0.00238518 + outer loop + vertex 847.191 286.909 156.776 + vertex 846.982 287.377 152.612 + vertex 848.52 283.771 155.989 + endloop + endfacet + facet normal -0.926344 -0.376128 0.020352 + outer loop + vertex 848.52 283.771 155.989 + vertex 846.982 287.377 152.612 + vertex 848.526 283.544 152.055 + endloop + endfacet + facet normal -0.844991 -0.533962 0.0295778 + outer loop + vertex 848.52 283.771 155.989 + vertex 848.526 283.544 152.055 + vertex 850.278 280.952 155.325 + endloop + endfacet + facet normal -0.845043 -0.533875 0.029674 + outer loop + vertex 850.278 280.952 155.325 + vertex 848.526 283.544 152.055 + vertex 850.287 280.718 151.373 + endloop + endfacet + facet normal -0.843997 -0.535053 0.0372548 + outer loop + vertex 848.526 283.544 152.055 + vertex 848.529 283.264 148.102 + vertex 850.287 280.718 151.373 + endloop + endfacet + facet normal -0.842429 -0.537712 0.0343427 + outer loop + vertex 850.287 280.718 151.373 + vertex 848.529 283.264 148.102 + vertex 850.302 280.441 147.411 + endloop + endfacet + facet normal -0.22102 -0.971094 0.0901517 + outer loop + vertex 853.033 278.037 143.667 + vertex 853.108 277.845 141.79 + vertex 853.448 278.003 144.325 + endloop + endfacet + facet normal -0.195977 -0.975885 0.0961315 + outer loop + vertex 853.066 277.647 139.694 + vertex 853.505 277.626 140.368 + vertex 853.108 277.845 141.79 + endloop + endfacet + facet normal -0.216966 -0.972052 0.0896673 + outer loop + vertex 853.505 277.626 140.368 + vertex 853.448 278.003 144.325 + vertex 853.108 277.845 141.79 + endloop + endfacet + facet normal -0.21534 -0.973503 0.0769439 + outer loop + vertex 853.003 278.363 147.568 + vertex 853.082 278.198 145.702 + vertex 853.411 278.309 148.04 + endloop + endfacet + facet normal -0.208414 -0.974596 0.0820139 + outer loop + vertex 853.033 278.037 143.667 + vertex 853.448 278.003 144.325 + vertex 853.082 278.198 145.702 + endloop + endfacet + facet normal -0.222498 -0.971818 0.077873 + outer loop + vertex 853.448 278.003 144.325 + vertex 853.411 278.309 148.04 + vertex 853.082 278.198 145.702 + endloop + endfacet + facet normal -0.705325 -0.707123 0.0499293 + outer loop + vertex 851.74 278.396 140.464 + vertex 851.552 278.716 142.329 + vertex 850.341 279.722 139.476 + endloop + endfacet + facet normal -0.715175 -0.695282 0.0714649 + outer loop + vertex 851.716 278.764 144.437 + vertex 850.319 280.099 143.45 + vertex 851.552 278.716 142.329 + endloop + endfacet + facet normal -0.719817 -0.691425 0.0616078 + outer loop + vertex 850.319 280.099 143.45 + vertex 850.341 279.722 139.476 + vertex 851.552 278.716 142.329 + endloop + endfacet + facet normal -0.706008 -0.706912 0.0427574 + outer loop + vertex 851.716 278.764 144.437 + vertex 851.523 279.068 146.289 + vertex 850.319 280.099 143.45 + endloop + endfacet + facet normal -0.721404 -0.689952 0.0595237 + outer loop + vertex 851.684 279.082 148.396 + vertex 850.302 280.441 147.411 + vertex 851.523 279.068 146.289 + endloop + endfacet + facet normal -0.722816 -0.688727 0.0564897 + outer loop + vertex 850.302 280.441 147.411 + vertex 850.319 280.099 143.45 + vertex 851.523 279.068 146.289 + endloop + endfacet + facet normal -0.533069 -0.841999 0.0829121 + outer loop + vertex 851.523 279.068 146.289 + vertex 851.716 278.764 144.437 + vertex 852.467 278.446 146.044 + endloop + endfacet + facet normal -0.510764 -0.856904 0.0695326 + outer loop + vertex 852.467 278.446 146.044 + vertex 851.716 278.764 144.437 + vertex 852.485 278.276 144.075 + endloop + endfacet + facet normal -0.514786 -0.856143 0.0448777 + outer loop + vertex 851.684 279.082 148.396 + vertex 851.523 279.068 146.289 + vertex 852.448 278.603 148.022 + endloop + endfacet + facet normal -0.537873 -0.840793 0.0613091 + outer loop + vertex 852.448 278.603 148.022 + vertex 851.523 279.068 146.289 + vertex 852.467 278.446 146.044 + endloop + endfacet + facet normal -0.347187 -0.935131 0.0706508 + outer loop + vertex 852.448 278.603 148.022 + vertex 852.467 278.446 146.044 + vertex 853.003 278.363 147.568 + endloop + endfacet + facet normal -0.341277 -0.937467 0.068446 + outer loop + vertex 853.003 278.363 147.568 + vertex 852.467 278.446 146.044 + vertex 853.082 278.198 145.702 + endloop + endfacet + facet normal -0.336303 -0.938507 0.0781318 + outer loop + vertex 852.467 278.446 146.044 + vertex 852.485 278.276 144.075 + vertex 853.082 278.198 145.702 + endloop + endfacet + facet normal -0.346758 -0.934349 0.0821669 + outer loop + vertex 853.082 278.198 145.702 + vertex 852.485 278.276 144.075 + vertex 853.033 278.037 143.667 + endloop + endfacet + facet normal -0.53204 -0.841856 0.0906193 + outer loop + vertex 851.552 278.716 142.329 + vertex 851.74 278.396 140.464 + vertex 852.5 278.092 142.099 + endloop + endfacet + facet normal -0.515299 -0.8532 0.0807319 + outer loop + vertex 852.5 278.092 142.099 + vertex 851.74 278.396 140.464 + vertex 852.513 277.895 140.101 + endloop + endfacet + facet normal -0.514548 -0.855397 0.0594648 + outer loop + vertex 851.716 278.764 144.437 + vertex 851.552 278.716 142.329 + vertex 852.485 278.276 144.075 + endloop + endfacet + facet normal -0.535582 -0.841209 0.0742889 + outer loop + vertex 852.485 278.276 144.075 + vertex 851.552 278.716 142.329 + vertex 852.5 278.092 142.099 + endloop + endfacet + facet normal -0.345227 -0.934713 0.0844375 + outer loop + vertex 852.485 278.276 144.075 + vertex 852.5 278.092 142.099 + vertex 853.033 278.037 143.667 + endloop + endfacet + facet normal -0.338408 -0.937418 0.0820257 + outer loop + vertex 853.033 278.037 143.667 + vertex 852.5 278.092 142.099 + vertex 853.108 277.845 141.79 + endloop + endfacet + facet normal -0.334446 -0.938075 0.0903372 + outer loop + vertex 852.5 278.092 142.099 + vertex 852.513 277.895 140.101 + vertex 853.108 277.845 141.79 + endloop + endfacet + facet normal -0.347519 -0.932839 0.0950916 + outer loop + vertex 853.108 277.845 141.79 + vertex 852.513 277.895 140.101 + vertex 853.066 277.647 139.694 + endloop + endfacet + facet normal -0.923638 -0.379417 0.0541743 + outer loop + vertex 846.983 286.796 144.712 + vertex 847.194 285.752 140.991 + vertex 848.533 282.941 144.143 + endloop + endfacet + facet normal -0.916529 -0.398511 0.0341267 + outer loop + vertex 848.533 282.941 144.143 + vertex 847.194 285.752 140.991 + vertex 848.546 282.572 140.175 + endloop + endfacet + facet normal -0.920127 -0.391445 0.0117005 + outer loop + vertex 847.193 286.428 148.913 + vertex 846.983 286.796 144.712 + vertex 848.529 283.264 148.102 + endloop + endfacet + facet normal -0.925861 -0.376698 0.0296792 + outer loop + vertex 848.529 283.264 148.102 + vertex 846.983 286.796 144.712 + vertex 848.533 282.941 144.143 + endloop + endfacet + facet normal -0.841172 -0.539052 0.0430525 + outer loop + vertex 848.529 283.264 148.102 + vertex 848.533 282.941 144.143 + vertex 850.302 280.441 147.411 + endloop + endfacet + facet normal -0.841158 -0.539075 0.043027 + outer loop + vertex 850.302 280.441 147.411 + vertex 848.533 282.941 144.143 + vertex 850.319 280.099 143.45 + endloop + endfacet + facet normal -0.840489 -0.539744 0.0474913 + outer loop + vertex 848.533 282.941 144.143 + vertex 848.546 282.572 140.175 + vertex 850.319 280.099 143.45 + endloop + endfacet + facet normal -0.840025 -0.540539 0.0466391 + outer loop + vertex 850.319 280.099 143.45 + vertex 848.546 282.572 140.175 + vertex 850.341 279.722 139.476 + endloop + endfacet + facet normal -0.212927 -0.970567 0.112528 + outer loop + vertex 853.1 277.206 135.652 + vertex 853.183 276.966 133.734 + vertex 853.512 277.19 136.296 + endloop + endfacet + facet normal -0.193629 -0.974004 0.117579 + outer loop + vertex 853.149 276.722 131.658 + vertex 853.621 276.685 132.131 + vertex 853.183 276.966 133.734 + endloop + endfacet + facet normal -0.210994 -0.971013 0.112319 + outer loop + vertex 853.621 276.685 132.131 + vertex 853.512 277.19 136.296 + vertex 853.183 276.966 133.734 + endloop + endfacet + facet normal -0.204741 -0.973496 0.101918 + outer loop + vertex 853.066 277.647 139.694 + vertex 853.141 277.43 137.771 + vertex 853.505 277.626 140.368 + endloop + endfacet + facet normal -0.204209 -0.973074 0.106893 + outer loop + vertex 853.1 277.206 135.652 + vertex 853.512 277.19 136.296 + vertex 853.141 277.43 137.771 + endloop + endfacet + facet normal -0.21666 -0.970757 0.103385 + outer loop + vertex 853.512 277.19 136.296 + vertex 853.505 277.626 140.368 + vertex 853.141 277.43 137.771 + endloop + endfacet + facet normal -0.700252 -0.710329 0.0712803 + outer loop + vertex 851.812 277.496 132.469 + vertex 851.614 277.877 134.325 + vertex 850.4 278.792 131.519 + endloop + endfacet + facet normal -0.709355 -0.699701 0.0850527 + outer loop + vertex 851.778 277.969 136.446 + vertex 850.368 279.281 135.481 + vertex 851.614 277.877 134.325 + endloop + endfacet + facet normal -0.711708 -0.697871 0.0802971 + outer loop + vertex 850.368 279.281 135.481 + vertex 850.4 278.792 131.519 + vertex 851.614 277.877 134.325 + endloop + endfacet + facet normal -0.701819 -0.709797 0.0603189 + outer loop + vertex 851.778 277.969 136.446 + vertex 851.58 278.324 138.333 + vertex 850.368 279.281 135.481 + endloop + endfacet + facet normal -0.713929 -0.695963 0.0770726 + outer loop + vertex 851.74 278.396 140.464 + vertex 850.341 279.722 139.476 + vertex 851.58 278.324 138.333 + endloop + endfacet + facet normal -0.716447 -0.693931 0.0718585 + outer loop + vertex 850.341 279.722 139.476 + vertex 850.368 279.281 135.481 + vertex 851.58 278.324 138.333 + endloop + endfacet + facet normal -0.534852 -0.838757 0.102078 + outer loop + vertex 851.58 278.324 138.333 + vertex 851.778 277.969 136.446 + vertex 852.53 277.688 138.087 + endloop + endfacet + facet normal -0.51342 -0.853433 0.0897344 + outer loop + vertex 852.53 277.688 138.087 + vertex 851.778 277.969 136.446 + vertex 852.549 277.465 136.07 + endloop + endfacet + facet normal -0.520214 -0.851346 0.0677272 + outer loop + vertex 851.74 278.396 140.464 + vertex 851.58 278.324 138.333 + vertex 852.513 277.895 140.101 + endloop + endfacet + facet normal -0.539691 -0.837931 0.0812677 + outer loop + vertex 852.513 277.895 140.101 + vertex 851.58 278.324 138.333 + vertex 852.53 277.688 138.087 + endloop + endfacet + facet normal -0.349219 -0.932459 0.0925532 + outer loop + vertex 852.513 277.895 140.101 + vertex 852.53 277.688 138.087 + vertex 853.066 277.647 139.694 + endloop + endfacet + facet normal -0.34714 -0.933306 0.0918385 + outer loop + vertex 853.066 277.647 139.694 + vertex 852.53 277.688 138.087 + vertex 853.141 277.43 137.771 + endloop + endfacet + facet normal -0.343092 -0.933943 0.100192 + outer loop + vertex 852.53 277.688 138.087 + vertex 852.549 277.465 136.07 + vertex 853.141 277.43 137.771 + endloop + endfacet + facet normal -0.356761 -0.928269 0.105064 + outer loop + vertex 853.141 277.43 137.771 + vertex 852.549 277.465 136.07 + vertex 853.1 277.206 135.652 + endloop + endfacet + facet normal -0.533493 -0.83791 0.11529 + outer loop + vertex 851.614 277.877 134.325 + vertex 851.812 277.496 132.469 + vertex 852.567 277.235 134.071 + endloop + endfacet + facet normal -0.509017 -0.854809 0.101007 + outer loop + vertex 852.567 277.235 134.071 + vertex 851.812 277.496 132.469 + vertex 852.589 276.989 132.103 + endloop + endfacet + facet normal -0.518497 -0.851614 0.0769077 + outer loop + vertex 851.778 277.969 136.446 + vertex 851.614 277.877 134.325 + vertex 852.549 277.465 136.07 + endloop + endfacet + facet normal -0.539307 -0.837126 0.0914754 + outer loop + vertex 852.549 277.465 136.07 + vertex 851.614 277.877 134.325 + vertex 852.567 277.235 134.071 + endloop + endfacet + facet normal -0.357758 -0.928049 0.103611 + outer loop + vertex 852.549 277.465 136.07 + vertex 852.567 277.235 134.071 + vertex 853.1 277.206 135.652 + endloop + endfacet + facet normal -0.351667 -0.930605 0.101509 + outer loop + vertex 853.1 277.206 135.652 + vertex 852.567 277.235 134.071 + vertex 853.183 276.966 133.734 + endloop + endfacet + facet normal -0.346074 -0.931448 0.112418 + outer loop + vertex 852.567 277.235 134.071 + vertex 852.589 276.989 132.103 + vertex 853.183 276.966 133.734 + endloop + endfacet + facet normal -0.352752 -0.928637 0.114891 + outer loop + vertex 853.183 276.966 133.734 + vertex 852.589 276.989 132.103 + vertex 853.149 276.722 131.658 + endloop + endfacet + facet normal -0.920238 -0.385925 0.0649948 + outer loop + vertex 846.989 285.983 136.757 + vertex 847.216 284.809 133.001 + vertex 848.562 282.139 136.191 + endloop + endfacet + facet normal -0.913495 -0.404136 0.0469124 + outer loop + vertex 848.562 282.139 136.191 + vertex 847.216 284.809 133.001 + vertex 848.585 281.623 132.201 + endloop + endfacet + facet normal -0.917904 -0.396154 0.0226744 + outer loop + vertex 847.194 285.752 140.991 + vertex 846.989 285.983 136.757 + vertex 848.546 282.572 140.175 + endloop + endfacet + facet normal -0.922938 -0.383065 0.0380316 + outer loop + vertex 848.546 282.572 140.175 + vertex 846.989 285.983 136.757 + vertex 848.562 282.139 136.191 + endloop + endfacet + facet normal -0.838627 -0.54186 0.0556144 + outer loop + vertex 848.546 282.572 140.175 + vertex 848.562 282.139 136.191 + vertex 850.341 279.722 139.476 + endloop + endfacet + facet normal -0.837949 -0.543031 0.054385 + outer loop + vertex 850.341 279.722 139.476 + vertex 848.562 282.139 136.191 + vertex 850.368 279.281 135.481 + endloop + endfacet + facet normal -0.836109 -0.544635 0.0655233 + outer loop + vertex 848.562 282.139 136.191 + vertex 848.585 281.623 132.201 + vertex 850.368 279.281 135.481 + endloop + endfacet + facet normal -0.833534 -0.549097 0.0609373 + outer loop + vertex 850.368 279.281 135.481 + vertex 848.585 281.623 132.201 + vertex 850.4 278.792 131.519 + endloop + endfacet + facet normal -0.204557 -0.969299 0.136438 + outer loop + vertex 853.216 276.201 127.756 + vertex 853.314 275.925 125.944 + vertex 853.655 276.148 128.042 + endloop + endfacet + facet normal -0.194481 -0.970652 0.141464 + outer loop + vertex 853.275 275.65 124.006 + vertex 853.709 275.63 124.46 + vertex 853.314 275.925 125.944 + endloop + endfacet + facet normal -0.209165 -0.968226 0.137071 + outer loop + vertex 853.709 275.63 124.46 + vertex 853.655 276.148 128.042 + vertex 853.314 275.925 125.944 + endloop + endfacet + facet normal -0.200835 -0.971622 0.124962 + outer loop + vertex 853.149 276.722 131.658 + vertex 853.247 276.458 129.765 + vertex 853.621 276.685 132.131 + endloop + endfacet + facet normal -0.198988 -0.971676 0.127472 + outer loop + vertex 853.216 276.201 127.756 + vertex 853.655 276.148 128.042 + vertex 853.247 276.458 129.765 + endloop + endfacet + facet normal -0.205817 -0.970491 0.125642 + outer loop + vertex 853.655 276.148 128.042 + vertex 853.621 276.685 132.131 + vertex 853.247 276.458 129.765 + endloop + endfacet + facet normal -0.680275 -0.727415 0.0899616 + outer loop + vertex 851.901 276.429 124.772 + vertex 851.694 276.843 126.559 + vertex 850.479 277.632 123.747 + endloop + endfacet + facet normal -0.697509 -0.709052 0.103573 + outer loop + vertex 851.851 276.987 128.6 + vertex 850.437 278.236 127.626 + vertex 851.694 276.843 126.559 + endloop + endfacet + facet normal -0.697886 -0.708794 0.102792 + outer loop + vertex 850.437 278.236 127.626 + vertex 850.479 277.632 123.747 + vertex 851.694 276.843 126.559 + endloop + endfacet + facet normal -0.690249 -0.719121 0.0801289 + outer loop + vertex 851.851 276.987 128.6 + vertex 851.649 277.382 130.404 + vertex 850.437 278.236 127.626 + endloop + endfacet + facet normal -0.707031 -0.700871 0.0942714 + outer loop + vertex 851.812 277.496 132.469 + vertex 850.4 278.792 131.519 + vertex 851.649 277.382 130.404 + endloop + endfacet + facet normal -0.707478 -0.700542 0.093356 + outer loop + vertex 850.4 278.792 131.519 + vertex 850.437 278.236 127.626 + vertex 851.649 277.382 130.404 + endloop + endfacet + facet normal -0.527329 -0.840423 0.124952 + outer loop + vertex 851.649 277.382 130.404 + vertex 851.851 276.987 128.6 + vertex 852.61 276.743 130.158 + endloop + endfacet + facet normal -0.499964 -0.859202 0.108668 + outer loop + vertex 852.61 276.743 130.158 + vertex 851.851 276.987 128.6 + vertex 852.641 276.481 128.235 + endloop + endfacet + facet normal -0.514332 -0.853129 0.0873728 + outer loop + vertex 851.812 277.496 132.469 + vertex 851.649 277.382 130.404 + vertex 852.589 276.989 132.103 + endloop + endfacet + facet normal -0.533183 -0.839968 0.100849 + outer loop + vertex 852.589 276.989 132.103 + vertex 851.649 277.382 130.404 + vertex 852.61 276.743 130.158 + endloop + endfacet + facet normal -0.353398 -0.928501 0.113996 + outer loop + vertex 852.589 276.989 132.103 + vertex 852.61 276.743 130.158 + vertex 853.149 276.722 131.658 + endloop + endfacet + facet normal -0.347267 -0.931083 0.111758 + outer loop + vertex 853.149 276.722 131.658 + vertex 852.61 276.743 130.158 + vertex 853.247 276.458 129.765 + endloop + endfacet + facet normal -0.341877 -0.931911 0.121089 + outer loop + vertex 852.61 276.743 130.158 + vertex 852.641 276.481 128.235 + vertex 853.247 276.458 129.765 + endloop + endfacet + facet normal -0.349639 -0.928614 0.124212 + outer loop + vertex 853.247 276.458 129.765 + vertex 852.641 276.481 128.235 + vertex 853.216 276.201 127.756 + endloop + endfacet + facet normal -0.514929 -0.846282 0.136583 + outer loop + vertex 851.694 276.843 126.559 + vertex 851.901 276.429 124.772 + vertex 852.672 276.211 126.327 + endloop + endfacet + facet normal -0.490375 -0.86292 0.122072 + outer loop + vertex 852.672 276.211 126.327 + vertex 851.901 276.429 124.772 + vertex 852.698 275.927 124.429 + endloop + endfacet + facet normal -0.503646 -0.858186 0.0992807 + outer loop + vertex 851.851 276.987 128.6 + vertex 851.694 276.843 126.559 + vertex 852.641 276.481 128.235 + endloop + endfacet + facet normal -0.52088 -0.846307 0.111576 + outer loop + vertex 852.641 276.481 128.235 + vertex 851.694 276.843 126.559 + vertex 852.672 276.211 126.327 + endloop + endfacet + facet normal -0.348186 -0.928902 0.126126 + outer loop + vertex 852.641 276.481 128.235 + vertex 852.672 276.211 126.327 + vertex 853.216 276.201 127.756 + endloop + endfacet + facet normal -0.341063 -0.931907 0.123392 + outer loop + vertex 853.216 276.201 127.756 + vertex 852.672 276.211 126.327 + vertex 853.314 275.925 125.944 + endloop + endfacet + facet normal -0.334717 -0.932658 0.134587 + outer loop + vertex 852.672 276.211 126.327 + vertex 852.698 275.927 124.429 + vertex 853.314 275.925 125.944 + endloop + endfacet + facet normal -0.344355 -0.928565 0.138512 + outer loop + vertex 853.314 275.925 125.944 + vertex 852.698 275.927 124.429 + vertex 853.275 275.65 124.006 + endloop + endfacet + facet normal -0.916798 -0.391256 0.079997 + outer loop + vertex 847.033 284.845 128.705 + vertex 847.292 283.487 125.026 + vertex 848.622 281.028 128.247 + endloop + endfacet + facet normal -0.909732 -0.41048 0.0624003 + outer loop + vertex 848.622 281.028 128.247 + vertex 847.292 283.487 125.026 + vertex 848.664 280.344 124.355 + endloop + endfacet + facet normal -0.914967 -0.401948 0.0356781 + outer loop + vertex 847.216 284.809 133.001 + vertex 847.033 284.845 128.705 + vertex 848.585 281.623 132.201 + endloop + endfacet + facet normal -0.919914 -0.388935 0.0498667 + outer loop + vertex 848.585 281.623 132.201 + vertex 847.033 284.845 128.705 + vertex 848.622 281.028 128.247 + endloop + endfacet + facet normal -0.831139 -0.55097 0.0751014 + outer loop + vertex 848.585 281.623 132.201 + vertex 848.622 281.028 128.247 + vertex 850.4 278.792 131.519 + endloop + endfacet + facet normal -0.829007 -0.554659 0.0714205 + outer loop + vertex 850.4 278.792 131.519 + vertex 848.622 281.028 128.247 + vertex 850.437 278.236 127.626 + endloop + endfacet + facet normal -0.825994 -0.556611 0.0889807 + outer loop + vertex 848.622 281.028 128.247 + vertex 848.664 280.344 124.355 + vertex 850.437 278.236 127.626 + endloop + endfacet + facet normal -0.820106 -0.566691 0.0792923 + outer loop + vertex 850.437 278.236 127.626 + vertex 848.664 280.344 124.355 + vertex 850.479 277.632 123.747 + endloop + endfacet + facet normal -0.191466 -0.968099 0.161633 + outer loop + vertex 853.323 275.045 120.202 + vertex 853.421 274.707 118.296 + vertex 853.822 275.006 120.562 + endloop + endfacet + facet normal -0.213366 -0.962962 0.164861 + outer loop + vertex 853.391 274.366 116.263 + vertex 853.866 274.273 116.336 + vertex 853.421 274.707 118.296 + endloop + endfacet + facet normal -0.213427 -0.962951 0.164844 + outer loop + vertex 853.866 274.273 116.336 + vertex 853.822 275.006 120.562 + vertex 853.421 274.707 118.296 + endloop + endfacet + facet normal -0.202338 -0.967897 0.149111 + outer loop + vertex 853.275 275.65 124.006 + vertex 853.363 275.351 122.182 + vertex 853.709 275.63 124.46 + endloop + endfacet + facet normal -0.186102 -0.970394 0.15395 + outer loop + vertex 853.323 275.045 120.202 + vertex 853.822 275.006 120.562 + vertex 853.363 275.351 122.182 + endloop + endfacet + facet normal -0.2017 -0.968043 0.149032 + outer loop + vertex 853.822 275.006 120.562 + vertex 853.709 275.63 124.46 + vertex 853.363 275.351 122.182 + endloop + endfacet + facet normal -0.652982 -0.748996 0.112338 + outer loop + vertex 851.983 275.18 117.095 + vertex 851.777 275.628 118.882 + vertex 850.573 276.228 115.888 + endloop + endfacet + facet normal -0.67963 -0.723005 0.123962 + outer loop + vertex 851.938 275.83 120.943 + vertex 850.524 276.97 119.839 + vertex 851.777 275.628 118.882 + endloop + endfacet + facet normal -0.677996 -0.723939 0.12741 + outer loop + vertex 850.524 276.97 119.839 + vertex 850.573 276.228 115.888 + vertex 851.777 275.628 118.882 + endloop + endfacet + facet normal -0.671212 -0.734278 0.101536 + outer loop + vertex 851.938 275.83 120.943 + vertex 851.737 276.259 122.723 + vertex 850.524 276.97 119.839 + endloop + endfacet + facet normal -0.688354 -0.716333 0.114176 + outer loop + vertex 851.901 276.429 124.772 + vertex 850.479 277.632 123.747 + vertex 851.737 276.259 122.723 + endloop + endfacet + facet normal -0.688734 -0.716093 0.113386 + outer loop + vertex 850.479 277.632 123.747 + vertex 850.524 276.97 119.839 + vertex 851.737 276.259 122.723 + endloop + endfacet + facet normal -0.50959 -0.847751 0.147097 + outer loop + vertex 851.737 276.259 122.723 + vertex 851.938 275.83 120.943 + vertex 852.716 275.638 122.533 + endloop + endfacet + facet normal -0.485416 -0.864061 0.133302 + outer loop + vertex 852.716 275.638 122.533 + vertex 851.938 275.83 120.943 + vertex 852.73 275.337 120.631 + endloop + endfacet + facet normal -0.494652 -0.862001 0.110786 + outer loop + vertex 851.901 276.429 124.772 + vertex 851.737 276.259 122.723 + vertex 852.698 275.927 124.429 + endloop + endfacet + facet normal -0.514423 -0.848442 0.124561 + outer loop + vertex 852.698 275.927 124.429 + vertex 851.737 276.259 122.723 + vertex 852.716 275.638 122.533 + endloop + endfacet + facet normal -0.344443 -0.928552 0.138383 + outer loop + vertex 852.698 275.927 124.429 + vertex 852.716 275.638 122.533 + vertex 853.275 275.65 124.006 + endloop + endfacet + facet normal -0.33919 -0.930776 0.136408 + outer loop + vertex 853.275 275.65 124.006 + vertex 852.716 275.638 122.533 + vertex 853.363 275.351 122.182 + endloop + endfacet + facet normal -0.334641 -0.931112 0.145074 + outer loop + vertex 852.716 275.638 122.533 + vertex 852.73 275.337 120.631 + vertex 853.363 275.351 122.182 + endloop + endfacet + facet normal -0.347644 -0.925497 0.150331 + outer loop + vertex 853.363 275.351 122.182 + vertex 852.73 275.337 120.631 + vertex 853.323 275.045 120.202 + endloop + endfacet + facet normal -0.505032 -0.849156 0.154518 + outer loop + vertex 851.777 275.628 118.882 + vertex 851.983 275.18 117.095 + vertex 852.757 275.016 118.723 + endloop + endfacet + facet normal -0.482258 -0.864418 0.142156 + outer loop + vertex 852.757 275.016 118.723 + vertex 851.983 275.18 117.095 + vertex 852.79 274.679 116.787 + endloop + endfacet + facet normal -0.489194 -0.863488 0.122794 + outer loop + vertex 851.938 275.83 120.943 + vertex 851.777 275.628 118.882 + vertex 852.73 275.337 120.631 + endloop + endfacet + facet normal -0.508724 -0.850174 0.135663 + outer loop + vertex 852.73 275.337 120.631 + vertex 851.777 275.628 118.882 + vertex 852.757 275.016 118.723 + endloop + endfacet + facet normal -0.347491 -0.925518 0.150557 + outer loop + vertex 852.73 275.337 120.631 + vertex 852.757 275.016 118.723 + vertex 853.323 275.045 120.202 + endloop + endfacet + facet normal -0.338531 -0.92937 0.147202 + outer loop + vertex 853.323 275.045 120.202 + vertex 852.757 275.016 118.723 + vertex 853.421 274.707 118.296 + endloop + endfacet + facet normal -0.333026 -0.929898 0.156151 + outer loop + vertex 852.757 275.016 118.723 + vertex 852.79 274.679 116.787 + vertex 853.421 274.707 118.296 + endloop + endfacet + facet normal -0.343504 -0.925345 0.16044 + outer loop + vertex 853.421 274.707 118.296 + vertex 852.79 274.679 116.787 + vertex 853.391 274.366 116.263 + endloop + endfacet + facet normal -0.907104 -0.410923 0.0911324 + outer loop + vertex 847.125 283.274 121.103 + vertex 847.2 282.158 116.819 + vertex 848.691 279.65 120.356 + endloop + endfacet + facet normal -0.901381 -0.425929 0.0780834 + outer loop + vertex 848.691 279.65 120.356 + vertex 847.2 282.158 116.819 + vertex 848.748 278.785 116.295 + endloop + endfacet + facet normal -0.909914 -0.410276 0.0610689 + outer loop + vertex 847.292 283.487 125.026 + vertex 847.125 283.274 121.103 + vertex 848.664 280.344 124.355 + endloop + endfacet + facet normal -0.911088 -0.407142 0.0644476 + outer loop + vertex 848.664 280.344 124.355 + vertex 847.125 283.274 121.103 + vertex 848.691 279.65 120.356 + endloop + endfacet + facet normal -0.817665 -0.568132 0.0930051 + outer loop + vertex 848.664 280.344 124.355 + vertex 848.691 279.65 120.356 + vertex 850.479 277.632 123.747 + endloop + endfacet + facet normal -0.814274 -0.573795 0.0878464 + outer loop + vertex 850.479 277.632 123.747 + vertex 848.691 279.65 120.356 + vertex 850.524 276.97 119.839 + endloop + endfacet + facet normal -0.810194 -0.575512 0.111229 + outer loop + vertex 848.691 279.65 120.356 + vertex 848.748 278.785 116.295 + vertex 850.524 276.97 119.839 + endloop + endfacet + facet normal -0.802133 -0.588632 0.100469 + outer loop + vertex 850.524 276.97 119.839 + vertex 848.748 278.785 116.295 + vertex 850.573 276.228 115.888 + endloop + endfacet + facet normal -0.203046 -0.959837 0.193612 + outer loop + vertex 853.494 273.598 112.275 + vertex 853.597 273.191 110.368 + vertex 853.945 273.507 112.296 + endloop + endfacet + facet normal -0.187008 -0.961614 0.200812 + outer loop + vertex 853.554 272.783 108.37 + vertex 853.943 272.808 108.855 + vertex 853.597 273.191 110.368 + endloop + endfacet + facet normal -0.210194 -0.958093 0.194619 + outer loop + vertex 853.943 272.808 108.855 + vertex 853.945 273.507 112.296 + vertex 853.597 273.191 110.368 + endloop + endfacet + facet normal -0.214614 -0.960746 0.175808 + outer loop + vertex 853.391 274.366 116.263 + vertex 853.514 273.981 114.31 + vertex 853.866 274.273 116.336 + endloop + endfacet + facet normal -0.202965 -0.961942 0.182954 + outer loop + vertex 853.494 273.598 112.275 + vertex 853.945 273.507 112.296 + vertex 853.514 273.981 114.31 + endloop + endfacet + facet normal -0.225234 -0.958044 0.177263 + outer loop + vertex 853.945 273.507 112.296 + vertex 853.866 274.273 116.336 + vertex 853.514 273.981 114.31 + endloop + endfacet + facet normal -0.551475 -0.812009 0.191093 + outer loop + vertex 852.025 273.485 108.992 + vertex 851.942 274.053 111.164 + vertex 850.889 274.307 109.209 + endloop + endfacet + facet normal -0.693933 -0.693157 0.194909 + outer loop + vertex 849.996 275.172 109.105 + vertex 850.889 274.307 109.209 + vertex 850.591 275.326 111.769 + endloop + endfacet + facet normal -0.633472 -0.754202 0.172893 + outer loop + vertex 852.07 274.405 113.172 + vertex 850.591 275.326 111.769 + vertex 851.942 274.053 111.164 + endloop + endfacet + facet normal -0.610927 -0.757487 0.230178 + outer loop + vertex 850.889 274.307 109.209 + vertex 851.942 274.053 111.164 + vertex 850.591 275.326 111.769 + endloop + endfacet + facet normal -0.615378 -0.775759 0.139675 + outer loop + vertex 852.07 274.405 113.172 + vertex 851.837 274.914 114.972 + vertex 850.591 275.326 111.769 + endloop + endfacet + facet normal -0.664237 -0.734692 0.1379 + outer loop + vertex 851.983 275.18 117.095 + vertex 850.573 276.228 115.888 + vertex 851.837 274.914 114.972 + endloop + endfacet + facet normal -0.653874 -0.739644 0.159293 + outer loop + vertex 850.573 276.228 115.888 + vertex 850.591 275.326 111.769 + vertex 851.837 274.914 114.972 + endloop + endfacet + facet normal -0.485374 -0.855767 0.179095 + outer loop + vertex 851.837 274.914 114.972 + vertex 852.07 274.405 113.172 + vertex 852.838 274.315 114.823 + endloop + endfacet + facet normal -0.457541 -0.873712 0.165176 + outer loop + vertex 852.838 274.315 114.823 + vertex 852.07 274.405 113.172 + vertex 852.894 273.913 112.853 + endloop + endfacet + facet normal -0.482423 -0.864402 0.141697 + outer loop + vertex 851.983 275.18 117.095 + vertex 851.837 274.914 114.972 + vertex 852.79 274.679 116.787 + endloop + endfacet + facet normal -0.491596 -0.858274 0.147308 + outer loop + vertex 852.79 274.679 116.787 + vertex 851.837 274.914 114.972 + vertex 852.838 274.315 114.823 + endloop + endfacet + facet normal -0.341092 -0.925715 0.163427 + outer loop + vertex 852.79 274.679 116.787 + vertex 852.838 274.315 114.823 + vertex 853.391 274.366 116.263 + endloop + endfacet + facet normal -0.336304 -0.927775 0.161659 + outer loop + vertex 853.391 274.366 116.263 + vertex 852.838 274.315 114.823 + vertex 853.514 273.981 114.31 + endloop + endfacet + facet normal -0.322817 -0.929126 0.180318 + outer loop + vertex 852.838 274.315 114.823 + vertex 852.894 273.913 112.853 + vertex 853.514 273.981 114.31 + endloop + endfacet + facet normal -0.317841 -0.931229 0.178299 + outer loop + vertex 853.514 273.981 114.31 + vertex 852.894 273.913 112.853 + vertex 853.494 273.598 112.275 + endloop + endfacet + facet normal -0.429349 -0.877676 0.21294 + outer loop + vertex 851.942 274.053 111.164 + vertex 852.025 273.485 108.992 + vertex 852.922 273.486 110.807 + endloop + endfacet + facet normal -0.38774 -0.901466 0.192397 + outer loop + vertex 852.922 273.486 110.807 + vertex 852.025 273.485 108.992 + vertex 852.977 273.025 108.756 + endloop + endfacet + facet normal -0.450956 -0.873743 0.182239 + outer loop + vertex 852.07 274.405 113.172 + vertex 851.942 274.053 111.164 + vertex 852.894 273.913 112.853 + endloop + endfacet + facet normal -0.442999 -0.878809 0.177334 + outer loop + vertex 852.894 273.913 112.853 + vertex 851.942 274.053 111.164 + vertex 852.922 273.486 110.807 + endloop + endfacet + facet normal -0.306854 -0.932515 0.190411 + outer loop + vertex 852.894 273.913 112.853 + vertex 852.922 273.486 110.807 + vertex 853.494 273.598 112.275 + endloop + endfacet + facet normal -0.290307 -0.938988 0.184456 + outer loop + vertex 853.494 273.598 112.275 + vertex 852.922 273.486 110.807 + vertex 853.597 273.191 110.368 + endloop + endfacet + facet normal -0.277676 -0.938812 0.203787 + outer loop + vertex 852.922 273.486 110.807 + vertex 852.977 273.025 108.756 + vertex 853.597 273.191 110.368 + endloop + endfacet + facet normal -0.263444 -0.943957 0.198853 + outer loop + vertex 853.597 273.191 110.368 + vertex 852.977 273.025 108.756 + vertex 853.554 272.783 108.37 + endloop + endfacet + facet normal -0.893368 -0.438383 0.0985653 + outer loop + vertex 847.264 281.123 112.68 + vertex 847.29 280.166 108.665 + vertex 848.805 277.884 112.25 + endloop + endfacet + facet normal -0.896851 -0.429526 0.105672 + outer loop + vertex 848.805 277.884 112.25 + vertex 847.29 280.166 108.665 + vertex 848.865 276.78 108.269 + endloop + endfacet + facet normal -0.89932 -0.427295 0.0929702 + outer loop + vertex 847.2 282.158 116.819 + vertex 847.264 281.123 112.68 + vertex 848.748 278.785 116.295 + endloop + endfacet + facet normal -0.895245 -0.437443 0.0847354 + outer loop + vertex 848.748 278.785 116.295 + vertex 847.264 281.123 112.68 + vertex 848.805 277.884 112.25 + endloop + endfacet + facet normal -0.798879 -0.589409 0.119957 + outer loop + vertex 848.748 278.785 116.295 + vertex 848.805 277.884 112.25 + vertex 850.573 276.228 115.888 + endloop + endfacet + facet normal -0.802534 -0.583487 0.12443 + outer loop + vertex 850.573 276.228 115.888 + vertex 848.805 277.884 112.25 + vertex 850.591 275.326 111.769 + endloop + endfacet + facet normal -0.797263 -0.584653 0.150173 + outer loop + vertex 848.805 277.884 112.25 + vertex 848.865 276.78 108.269 + vertex 850.591 275.326 111.769 + endloop + endfacet + facet normal -0.847976 -0.483464 0.217254 + outer loop + vertex 850.591 275.326 111.769 + vertex 848.865 276.78 108.269 + vertex 849.996 275.172 109.105 + endloop + endfacet + facet normal -0.205056 -0.951564 0.229081 + outer loop + vertex 853.559 271.936 104.587 + vertex 853.615 271.473 102.717 + vertex 854.018 272.042 105.44 + endloop + endfacet + facet normal -0.179483 -0.954609 0.237711 + outer loop + vertex 853.537 270.966 100.62 + vertex 854.049 271.001 101.146 + vertex 853.615 271.473 102.717 + endloop + endfacet + facet normal -0.206503 -0.951217 0.229223 + outer loop + vertex 854.049 271.001 101.146 + vertex 854.018 272.042 105.44 + vertex 853.615 271.473 102.717 + endloop + endfacet + facet normal -0.197675 -0.957688 0.209184 + outer loop + vertex 853.554 272.783 108.37 + vertex 853.629 272.377 106.583 + vertex 853.943 272.808 108.855 + endloop + endfacet + facet normal -0.18319 -0.958556 0.218202 + outer loop + vertex 853.559 271.936 104.587 + vertex 854.018 272.042 105.44 + vertex 853.629 272.377 106.583 + endloop + endfacet + facet normal -0.205344 -0.955915 0.209905 + outer loop + vertex 854.018 272.042 105.44 + vertex 853.943 272.808 108.855 + vertex 853.629 272.377 106.583 + endloop + endfacet + facet normal -0.689017 -0.696161 0.201534 + outer loop + vertex 849.923 273.881 103.198 + vertex 850.089 273.189 101.373 + vertex 851.049 272.73 103.071 + endloop + endfacet + facet normal -0.669088 -0.720098 0.183792 + outer loop + vertex 851.049 272.73 103.071 + vertex 850.089 273.189 101.373 + vertex 851.035 272.25 101.142 + endloop + endfacet + facet normal -0.679037 -0.718953 0.148376 + outer loop + vertex 850.083 274.168 105.319 + vertex 849.923 273.881 103.198 + vertex 851.044 273.203 105.041 + endloop + endfacet + facet normal -0.69576 -0.698841 0.165948 + outer loop + vertex 851.044 273.203 105.041 + vertex 849.923 273.881 103.198 + vertex 851.049 272.73 103.071 + endloop + endfacet + facet normal -0.513084 -0.834925 0.199111 + outer loop + vertex 851.044 273.203 105.041 + vertex 851.049 272.73 103.071 + vertex 852.105 272.52 104.91 + endloop + endfacet + facet normal -0.513752 -0.834408 0.199553 + outer loop + vertex 852.105 272.52 104.91 + vertex 851.049 272.73 103.071 + vertex 852.093 272.063 102.97 + endloop + endfacet + facet normal -0.511718 -0.832914 0.210712 + outer loop + vertex 851.049 272.73 103.071 + vertex 851.035 272.25 101.142 + vertex 852.093 272.063 102.97 + endloop + endfacet + facet normal -0.511753 -0.832887 0.210735 + outer loop + vertex 852.093 272.063 102.97 + vertex 851.035 272.25 101.142 + vertex 852.074 271.591 101.058 + endloop + endfacet + facet normal -0.700505 -0.690151 0.181613 + outer loop + vertex 849.881 274.865 107.188 + vertex 850.083 274.168 105.319 + vertex 850.998 273.702 107.078 + endloop + endfacet + facet normal -0.675756 -0.719328 0.161001 + outer loop + vertex 850.998 273.702 107.078 + vertex 850.083 274.168 105.319 + vertex 851.044 273.203 105.041 + endloop + endfacet + facet normal -0.696551 -0.700739 0.154212 + outer loop + vertex 849.996 275.172 109.105 + vertex 849.881 274.865 107.188 + vertex 850.889 274.307 109.209 + endloop + endfacet + facet normal -0.704154 -0.691667 0.16051 + outer loop + vertex 850.889 274.307 109.209 + vertex 849.881 274.865 107.188 + vertex 850.998 273.702 107.078 + endloop + endfacet + facet normal -0.548698 -0.811156 0.202377 + outer loop + vertex 850.889 274.307 109.209 + vertex 850.998 273.702 107.078 + vertex 852.025 273.485 108.992 + endloop + endfacet + facet normal -0.520591 -0.833578 0.184748 + outer loop + vertex 852.025 273.485 108.992 + vertex 850.998 273.702 107.078 + vertex 852.085 272.986 106.908 + endloop + endfacet + facet normal -0.518948 -0.832888 0.19233 + outer loop + vertex 850.998 273.702 107.078 + vertex 851.044 273.203 105.041 + vertex 852.085 272.986 106.908 + endloop + endfacet + facet normal -0.514923 -0.835977 0.189727 + outer loop + vertex 852.085 272.986 106.908 + vertex 851.044 273.203 105.041 + vertex 852.105 272.52 104.91 + endloop + endfacet + facet normal -0.366016 -0.907109 0.207813 + outer loop + vertex 852.085 272.986 106.908 + vertex 852.105 272.52 104.91 + vertex 852.999 272.583 106.762 + endloop + endfacet + facet normal -0.362522 -0.908881 0.206186 + outer loop + vertex 852.999 272.583 106.762 + vertex 852.105 272.52 104.91 + vertex 852.992 272.145 104.817 + endloop + endfacet + facet normal -0.384144 -0.900308 0.204645 + outer loop + vertex 852.025 273.485 108.992 + vertex 852.085 272.986 106.908 + vertex 852.977 273.025 108.756 + endloop + endfacet + facet normal -0.368341 -0.908539 0.197184 + outer loop + vertex 852.977 273.025 108.756 + vertex 852.085 272.986 106.908 + vertex 852.999 272.583 106.762 + endloop + endfacet + facet normal -0.258452 -0.943761 0.206196 + outer loop + vertex 852.977 273.025 108.756 + vertex 852.999 272.583 106.762 + vertex 853.554 272.783 108.37 + endloop + endfacet + facet normal -0.251917 -0.945956 0.204217 + outer loop + vertex 853.554 272.783 108.37 + vertex 852.999 272.583 106.762 + vertex 853.629 272.377 106.583 + endloop + endfacet + facet normal -0.248762 -0.94467 0.213811 + outer loop + vertex 852.999 272.583 106.762 + vertex 852.992 272.145 104.817 + vertex 853.629 272.377 106.583 + endloop + endfacet + facet normal -0.258952 -0.941191 0.217034 + outer loop + vertex 853.629 272.377 106.583 + vertex 852.992 272.145 104.817 + vertex 853.559 271.936 104.587 + endloop + endfacet + facet normal -0.362302 -0.904036 0.226838 + outer loop + vertex 852.093 272.063 102.97 + vertex 852.074 271.591 101.058 + vertex 852.976 271.689 102.89 + endloop + endfacet + facet normal -0.362582 -0.903891 0.226968 + outer loop + vertex 852.976 271.689 102.89 + vertex 852.074 271.591 101.058 + vertex 852.959 271.212 100.961 + endloop + endfacet + facet normal -0.360862 -0.90732 0.215752 + outer loop + vertex 852.105 272.52 104.91 + vertex 852.093 272.063 102.97 + vertex 852.992 272.145 104.817 + endloop + endfacet + facet normal -0.363907 -0.905765 0.217166 + outer loop + vertex 852.992 272.145 104.817 + vertex 852.093 272.063 102.97 + vertex 852.976 271.689 102.89 + endloop + endfacet + facet normal -0.255633 -0.940353 0.224472 + outer loop + vertex 852.992 272.145 104.817 + vertex 852.976 271.689 102.89 + vertex 853.559 271.936 104.587 + endloop + endfacet + facet normal -0.256416 -0.940085 0.224702 + outer loop + vertex 853.559 271.936 104.587 + vertex 852.976 271.689 102.89 + vertex 853.615 271.473 102.717 + endloop + endfacet + facet normal -0.253222 -0.938541 0.234561 + outer loop + vertex 852.976 271.689 102.89 + vertex 852.959 271.212 100.961 + vertex 853.615 271.473 102.717 + endloop + endfacet + facet normal -0.258699 -0.936604 0.23632 + outer loop + vertex 853.615 271.473 102.717 + vertex 852.959 271.212 100.961 + vertex 853.537 270.966 100.62 + endloop + endfacet + facet normal -0.89844 -0.422839 0.118371 + outer loop + vertex 847.26 279.244 104.73 + vertex 847.193 278.297 100.84 + vertex 848.779 275.881 104.247 + endloop + endfacet + facet normal -0.897917 -0.424306 0.117088 + outer loop + vertex 848.779 275.881 104.247 + vertex 847.193 278.297 100.84 + vertex 848.743 274.867 100.298 + endloop + endfacet + facet normal -0.896586 -0.429619 0.107522 + outer loop + vertex 847.29 280.166 108.665 + vertex 847.26 279.244 104.73 + vertex 848.865 276.78 108.269 + endloop + endfacet + facet normal -0.899204 -0.422508 0.113659 + outer loop + vertex 848.865 276.78 108.269 + vertex 847.26 279.244 104.73 + vertex 848.779 275.881 104.247 + endloop + endfacet + facet normal -0.824291 -0.553853 0.117435 + outer loop + vertex 850.083 274.168 105.319 + vertex 849.881 274.865 107.188 + vertex 848.779 275.881 104.247 + endloop + endfacet + facet normal -0.842053 -0.522395 0.134354 + outer loop + vertex 849.996 275.172 109.105 + vertex 848.865 276.78 108.269 + vertex 849.881 274.865 107.188 + endloop + endfacet + facet normal -0.841872 -0.522565 0.134825 + outer loop + vertex 848.865 276.78 108.269 + vertex 848.779 275.881 104.247 + vertex 849.881 274.865 107.188 + endloop + endfacet + facet normal -0.814299 -0.56338 0.139716 + outer loop + vertex 850.089 273.189 101.373 + vertex 849.923 273.881 103.198 + vertex 848.743 274.867 100.298 + endloop + endfacet + facet normal -0.827533 -0.544695 0.136001 + outer loop + vertex 850.083 274.168 105.319 + vertex 848.779 275.881 104.247 + vertex 849.923 273.881 103.198 + endloop + endfacet + facet normal -0.822904 -0.548491 0.148276 + outer loop + vertex 848.779 275.881 104.247 + vertex 848.743 274.867 100.298 + vertex 849.923 273.881 103.198 + endloop + endfacet + facet normal -0.192476 -0.944191 0.267313 + outer loop + vertex 853.532 269.924 96.6937 + vertex 853.582 269.403 94.8899 + vertex 854.029 269.872 96.8684 + endloop + endfacet + facet normal -0.20031 -0.93962 0.27747 + outer loop + vertex 853.489 268.866 93.0037 + vertex 853.925 268.898 93.427 + vertex 853.582 269.403 94.8899 + endloop + endfacet + facet normal -0.220252 -0.936801 0.271831 + outer loop + vertex 853.925 268.898 93.427 + vertex 854.029 269.872 96.8684 + vertex 853.582 269.403 94.8899 + endloop + endfacet + facet normal -0.190959 -0.949607 0.24856 + outer loop + vertex 853.537 270.966 100.62 + vertex 853.604 270.451 98.7028 + vertex 854.049 271.001 101.146 + endloop + endfacet + facet normal -0.188731 -0.94822 0.255461 + outer loop + vertex 853.532 269.924 96.6937 + vertex 854.029 269.872 96.8684 + vertex 853.604 270.451 98.7028 + endloop + endfacet + facet normal -0.20661 -0.945798 0.250555 + outer loop + vertex 854.029 269.872 96.8684 + vertex 854.049 271.001 101.146 + vertex 853.604 270.451 98.7028 + endloop + endfacet + facet normal -0.643553 -0.719804 0.260235 + outer loop + vertex 849.889 271.673 95.6147 + vertex 849.896 270.921 93.5525 + vertex 850.987 270.617 95.4103 + endloop + endfacet + facet normal -0.618376 -0.748076 0.24082 + outer loop + vertex 850.987 270.617 95.4103 + vertex 849.896 270.921 93.5525 + vertex 850.968 270.006 93.4626 + endloop + endfacet + facet normal -0.654145 -0.722135 0.224978 + outer loop + vertex 850.067 272.107 97.5275 + vertex 849.889 271.673 95.6147 + vertex 851.017 271.191 97.3484 + endloop + endfacet + facet normal -0.653382 -0.72306 0.224224 + outer loop + vertex 851.017 271.191 97.3484 + vertex 849.889 271.673 95.6147 + vertex 850.987 270.617 95.4103 + endloop + endfacet + facet normal -0.486223 -0.83581 0.254969 + outer loop + vertex 851.017 271.191 97.3484 + vertex 850.987 270.617 95.4103 + vertex 852.055 270.559 97.2566 + endloop + endfacet + facet normal -0.472134 -0.846365 0.246488 + outer loop + vertex 852.055 270.559 97.2566 + vertex 850.987 270.617 95.4103 + vertex 852.039 270.013 95.3495 + endloop + endfacet + facet normal -0.468194 -0.841753 0.268787 + outer loop + vertex 850.987 270.617 95.4103 + vertex 850.968 270.006 93.4626 + vertex 852.039 270.013 95.3495 + endloop + endfacet + facet normal -0.451031 -0.854073 0.259095 + outer loop + vertex 852.039 270.013 95.3495 + vertex 850.968 270.006 93.4626 + vertex 852.009 269.452 93.4492 + endloop + endfacet + facet normal -0.677911 -0.698796 0.228301 + outer loop + vertex 849.896 272.848 99.2871 + vertex 850.067 272.107 97.5275 + vertex 851.024 271.736 99.234 + endloop + endfacet + facet normal -0.657565 -0.72307 0.211608 + outer loop + vertex 851.024 271.736 99.234 + vertex 850.067 272.107 97.5275 + vertex 851.017 271.191 97.3484 + endloop + endfacet + facet normal -0.670189 -0.720152 0.179521 + outer loop + vertex 850.089 273.189 101.373 + vertex 849.896 272.848 99.2871 + vertex 851.035 272.25 101.142 + endloop + endfacet + facet normal -0.684027 -0.703339 0.193446 + outer loop + vertex 851.035 272.25 101.142 + vertex 849.896 272.848 99.2871 + vertex 851.024 271.736 99.234 + endloop + endfacet + facet normal -0.508909 -0.830431 0.226709 + outer loop + vertex 851.035 272.25 101.142 + vertex 851.024 271.736 99.234 + vertex 852.074 271.591 101.058 + endloop + endfacet + facet normal -0.504113 -0.834176 0.223652 + outer loop + vertex 852.074 271.591 101.058 + vertex 851.024 271.736 99.234 + vertex 852.064 271.087 99.158 + endloop + endfacet + facet normal -0.50077 -0.830994 0.242235 + outer loop + vertex 851.024 271.736 99.234 + vertex 851.017 271.191 97.3484 + vertex 852.064 271.087 99.158 + endloop + endfacet + facet normal -0.490046 -0.839266 0.235559 + outer loop + vertex 852.064 271.087 99.158 + vertex 851.017 271.191 97.3484 + vertex 852.055 270.559 97.2566 + endloop + endfacet + facet normal -0.3488 -0.90256 0.252437 + outer loop + vertex 852.064 271.087 99.158 + vertex 852.055 270.559 97.2566 + vertex 852.95 270.71 99.032 + endloop + endfacet + facet normal -0.337306 -0.908377 0.247136 + outer loop + vertex 852.95 270.71 99.032 + vertex 852.055 270.559 97.2566 + vertex 852.946 270.192 97.1215 + endloop + endfacet + facet normal -0.359994 -0.901361 0.240734 + outer loop + vertex 852.074 271.591 101.058 + vertex 852.064 271.087 99.158 + vertex 852.959 271.212 100.961 + endloop + endfacet + facet normal -0.352184 -0.905391 0.237136 + outer loop + vertex 852.959 271.212 100.961 + vertex 852.064 271.087 99.158 + vertex 852.95 270.71 99.032 + endloop + endfacet + facet normal -0.253507 -0.935897 0.244605 + outer loop + vertex 852.959 271.212 100.961 + vertex 852.95 270.71 99.032 + vertex 853.537 270.966 100.62 + endloop + endfacet + facet normal -0.249156 -0.937419 0.243242 + outer loop + vertex 853.537 270.966 100.62 + vertex 852.95 270.71 99.032 + vertex 853.604 270.451 98.7028 + endloop + endfacet + facet normal -0.242975 -0.936063 0.254458 + outer loop + vertex 852.95 270.71 99.032 + vertex 852.946 270.192 97.1215 + vertex 853.604 270.451 98.7028 + endloop + endfacet + facet normal -0.242406 -0.936266 0.254255 + outer loop + vertex 853.604 270.451 98.7028 + vertex 852.946 270.192 97.1215 + vertex 853.532 269.924 96.6937 + endloop + endfacet + facet normal -0.319973 -0.907328 0.272715 + outer loop + vertex 852.039 270.013 95.3495 + vertex 852.009 269.452 93.4492 + vertex 852.934 269.661 95.2285 + endloop + endfacet + facet normal -0.313337 -0.910557 0.26964 + outer loop + vertex 852.934 269.661 95.2285 + vertex 852.009 269.452 93.4492 + vertex 852.906 269.115 93.3529 + endloop + endfacet + facet normal -0.333799 -0.905429 0.262254 + outer loop + vertex 852.055 270.559 97.2566 + vertex 852.039 270.013 95.3495 + vertex 852.946 270.192 97.1215 + endloop + endfacet + facet normal -0.323329 -0.910602 0.257415 + outer loop + vertex 852.946 270.192 97.1215 + vertex 852.039 270.013 95.3495 + vertex 852.934 269.661 95.2285 + endloop + endfacet + facet normal -0.235048 -0.935489 0.263843 + outer loop + vertex 852.946 270.192 97.1215 + vertex 852.934 269.661 95.2285 + vertex 853.532 269.924 96.6937 + endloop + endfacet + facet normal -0.23455 -0.935662 0.263671 + outer loop + vertex 853.532 269.924 96.6937 + vertex 852.934 269.661 95.2285 + vertex 853.582 269.403 94.8899 + endloop + endfacet + facet normal -0.227873 -0.933995 0.275187 + outer loop + vertex 852.934 269.661 95.2285 + vertex 852.906 269.115 93.3529 + vertex 853.582 269.403 94.8899 + endloop + endfacet + facet normal -0.232697 -0.932272 0.276986 + outer loop + vertex 853.582 269.403 94.8899 + vertex 852.906 269.115 93.3529 + vertex 853.489 268.866 93.0037 + endloop + endfacet + facet normal -0.88963 -0.422722 0.172811 + outer loop + vertex 847.123 277.189 96.9699 + vertex 847.063 275.749 93.1335 + vertex 848.662 273.666 96.273 + endloop + endfacet + facet normal -0.904733 -0.365814 0.218261 + outer loop + vertex 848.662 273.666 96.273 + vertex 847.063 275.749 93.1335 + vertex 848.082 273.598 93.7518 + endloop + endfacet + facet normal -0.894164 -0.425927 0.138047 + outer loop + vertex 847.193 278.297 100.84 + vertex 847.123 277.189 96.9699 + vertex 848.743 274.867 100.298 + endloop + endfacet + facet normal -0.896235 -0.419779 0.143346 + outer loop + vertex 848.743 274.867 100.298 + vertex 847.123 277.189 96.9699 + vertex 848.662 273.666 96.273 + endloop + endfacet + facet normal -0.795564 -0.582185 0.167742 + outer loop + vertex 850.067 272.107 97.5275 + vertex 849.896 272.848 99.2871 + vertex 848.662 273.666 96.273 + endloop + endfacet + facet normal -0.818473 -0.550186 0.165518 + outer loop + vertex 850.089 273.189 101.373 + vertex 848.743 274.867 100.298 + vertex 849.896 272.848 99.2871 + endloop + endfacet + facet normal -0.811946 -0.554665 0.181909 + outer loop + vertex 848.743 274.867 100.298 + vertex 848.662 273.666 96.273 + vertex 849.896 272.848 99.2871 + endloop + endfacet + facet normal -0.759039 -0.612496 0.220701 + outer loop + vertex 849.896 270.921 93.5525 + vertex 849.889 271.673 95.6147 + vertex 848.856 272.289 93.7737 + endloop + endfacet + facet normal -0.843273 -0.495773 0.207605 + outer loop + vertex 848.082 273.598 93.7518 + vertex 848.856 272.289 93.7737 + vertex 848.662 273.666 96.273 + endloop + endfacet + facet normal -0.80279 -0.560909 0.202263 + outer loop + vertex 850.067 272.107 97.5275 + vertex 848.662 273.666 96.273 + vertex 849.889 271.673 95.6147 + endloop + endfacet + facet normal -0.785202 -0.566145 0.250874 + outer loop + vertex 848.856 272.289 93.7737 + vertex 849.889 271.673 95.6147 + vertex 848.662 273.666 96.273 + endloop + endfacet + facet normal -0.207423 -0.926286 0.314594 + outer loop + vertex 853.411 267.716 89.3436 + vertex 853.43 267.089 87.5102 + vertex 853.942 267.844 90.0725 + endloop + endfacet + facet normal -0.175601 -0.929335 0.324808 + outer loop + vertex 853.289 266.417 85.511 + vertex 853.835 266.447 85.8936 + vertex 853.43 267.089 87.5102 + endloop + endfacet + facet normal -0.209559 -0.925717 0.314854 + outer loop + vertex 853.835 266.447 85.8936 + vertex 853.942 267.844 90.0725 + vertex 853.43 267.089 87.5102 + endloop + endfacet + facet normal -0.213659 -0.932656 0.290693 + outer loop + vertex 853.489 268.866 93.0037 + vertex 853.526 268.317 91.269 + vertex 853.925 268.898 93.427 + endloop + endfacet + facet normal -0.189325 -0.934071 0.302766 + outer loop + vertex 853.411 267.716 89.3436 + vertex 853.942 267.844 90.0725 + vertex 853.526 268.317 91.269 + endloop + endfacet + facet normal -0.219029 -0.93122 0.291299 + outer loop + vertex 853.942 267.844 90.0725 + vertex 853.925 268.898 93.427 + vertex 853.526 268.317 91.269 + endloop + endfacet + facet normal -0.586264 -0.754201 0.295762 + outer loop + vertex 849.724 269.008 87.8373 + vertex 849.615 268.375 86.0086 + vertex 850.766 268.195 87.8295 + endloop + endfacet + facet normal -0.582713 -0.757966 0.293143 + outer loop + vertex 850.766 268.195 87.8295 + vertex 849.615 268.375 86.0086 + vertex 850.669 267.558 85.9903 + endloop + endfacet + facet normal -0.592026 -0.75544 0.280743 + outer loop + vertex 849.817 269.623 89.688 + vertex 849.724 269.008 87.8373 + vertex 850.854 268.807 89.6804 + endloop + endfacet + facet normal -0.58946 -0.758133 0.278874 + outer loop + vertex 850.854 268.807 89.6804 + vertex 849.724 269.008 87.8373 + vertex 850.766 268.195 87.8295 + endloop + endfacet + facet normal -0.428668 -0.851475 0.302051 + outer loop + vertex 850.854 268.807 89.6804 + vertex 850.766 268.195 87.8295 + vertex 851.895 268.29 89.6999 + endloop + endfacet + facet normal -0.425725 -0.85354 0.300379 + outer loop + vertex 851.895 268.29 89.6999 + vertex 850.766 268.195 87.8295 + vertex 851.818 267.673 87.8392 + endloop + endfacet + facet normal -0.423563 -0.848879 0.316226 + outer loop + vertex 850.766 268.195 87.8295 + vertex 850.669 267.558 85.9903 + vertex 851.818 267.673 87.8392 + endloop + endfacet + facet normal -0.419386 -0.851842 0.313816 + outer loop + vertex 851.818 267.673 87.8392 + vertex 850.669 267.558 85.9903 + vertex 851.734 267.033 85.9877 + endloop + endfacet + facet normal -0.599547 -0.754223 0.267752 + outer loop + vertex 849.878 270.247 91.5846 + vertex 849.817 269.623 89.688 + vertex 850.926 269.404 91.5533 + endloop + endfacet + facet normal -0.594952 -0.759008 0.264458 + outer loop + vertex 850.926 269.404 91.5533 + vertex 849.817 269.623 89.688 + vertex 850.854 268.807 89.6804 + endloop + endfacet + facet normal -0.614074 -0.744979 0.260613 + outer loop + vertex 849.896 270.921 93.5525 + vertex 849.878 270.247 91.5846 + vertex 850.968 270.006 93.4626 + endloop + endfacet + facet normal -0.602441 -0.757242 0.252287 + outer loop + vertex 850.968 270.006 93.4626 + vertex 849.878 270.247 91.5846 + vertex 850.926 269.404 91.5533 + endloop + endfacet + facet normal -0.448371 -0.849531 0.277959 + outer loop + vertex 850.968 270.006 93.4626 + vertex 850.926 269.404 91.5533 + vertex 852.009 269.452 93.4492 + endloop + endfacet + facet normal -0.436906 -0.857518 0.271616 + outer loop + vertex 852.009 269.452 93.4492 + vertex 850.926 269.404 91.5533 + vertex 851.96 268.881 91.5677 + endloop + endfacet + facet normal -0.434891 -0.853068 0.288348 + outer loop + vertex 850.926 269.404 91.5533 + vertex 850.854 268.807 89.6804 + vertex 851.96 268.881 91.5677 + endloop + endfacet + facet normal -0.430627 -0.856028 0.285966 + outer loop + vertex 851.96 268.881 91.5677 + vertex 850.854 268.807 89.6804 + vertex 851.895 268.29 89.6999 + endloop + endfacet + facet normal -0.30479 -0.904905 0.297069 + outer loop + vertex 851.96 268.881 91.5677 + vertex 851.895 268.29 89.6999 + vertex 852.862 268.552 91.4906 + endloop + endfacet + facet normal -0.304003 -0.905291 0.296701 + outer loop + vertex 852.862 268.552 91.4906 + vertex 851.895 268.29 89.6999 + vertex 852.804 267.961 89.6269 + endloop + endfacet + facet normal -0.310618 -0.907277 0.283486 + outer loop + vertex 852.009 269.452 93.4492 + vertex 851.96 268.881 91.5677 + vertex 852.906 269.115 93.3529 + endloop + endfacet + facet normal -0.307494 -0.908794 0.28203 + outer loop + vertex 852.906 269.115 93.3529 + vertex 851.96 268.881 91.5677 + vertex 852.862 268.552 91.4906 + endloop + endfacet + facet normal -0.226242 -0.9309 0.286776 + outer loop + vertex 852.906 269.115 93.3529 + vertex 852.862 268.552 91.4906 + vertex 853.489 268.866 93.0037 + endloop + endfacet + facet normal -0.232767 -0.9286 0.289002 + outer loop + vertex 853.489 268.866 93.0037 + vertex 852.862 268.552 91.4906 + vertex 853.526 268.317 91.269 + endloop + endfacet + facet normal -0.227881 -0.926027 0.300906 + outer loop + vertex 852.862 268.552 91.4906 + vertex 852.804 267.961 89.6269 + vertex 853.526 268.317 91.269 + endloop + endfacet + facet normal -0.231871 -0.924567 0.302344 + outer loop + vertex 853.526 268.317 91.269 + vertex 852.804 267.961 89.6269 + vertex 853.411 267.716 89.3436 + endloop + endfacet + facet normal -0.296429 -0.898311 0.324296 + outer loop + vertex 851.818 267.673 87.8392 + vertex 851.734 267.033 85.9877 + vertex 852.743 267.339 87.759 + endloop + endfacet + facet normal -0.292044 -0.900507 0.322176 + outer loop + vertex 852.743 267.339 87.759 + vertex 851.734 267.033 85.9877 + vertex 852.674 266.693 85.8893 + endloop + endfacet + facet normal -0.30142 -0.901338 0.311023 + outer loop + vertex 851.895 268.29 89.6999 + vertex 851.818 267.673 87.8392 + vertex 852.804 267.961 89.6269 + endloop + endfacet + facet normal -0.299168 -0.902454 0.30996 + outer loop + vertex 852.804 267.961 89.6269 + vertex 851.818 267.673 87.8392 + vertex 852.743 267.339 87.759 + endloop + endfacet + facet normal -0.225416 -0.922225 0.314148 + outer loop + vertex 852.804 267.961 89.6269 + vertex 852.743 267.339 87.759 + vertex 853.411 267.716 89.3436 + endloop + endfacet + facet normal -0.223004 -0.923087 0.313337 + outer loop + vertex 853.411 267.716 89.3436 + vertex 852.743 267.339 87.759 + vertex 853.43 267.089 87.5102 + endloop + endfacet + facet normal -0.217235 -0.920015 0.326162 + outer loop + vertex 852.743 267.339 87.759 + vertex 852.674 266.693 85.8893 + vertex 853.43 267.089 87.5102 + endloop + endfacet + facet normal -0.213618 -0.921342 0.324801 + outer loop + vertex 853.43 267.089 87.5102 + vertex 852.674 266.693 85.8893 + vertex 853.289 266.417 85.511 + endloop + endfacet + facet normal -0.893848 -0.406894 0.188343 + outer loop + vertex 847.838 270.957 86.4113 + vertex 847.79 271.866 88.1481 + vertex 846.613 273.278 85.6116 + endloop + endfacet + facet normal -0.899225 -0.396663 0.184534 + outer loop + vertex 848.031 272.245 90.1369 + vertex 846.843 274.553 89.306 + vertex 847.79 271.866 88.1481 + endloop + endfacet + facet normal -0.896098 -0.399439 0.193537 + outer loop + vertex 846.843 274.553 89.306 + vertex 846.613 273.278 85.6116 + vertex 847.79 271.866 88.1481 + endloop + endfacet + facet normal -0.899848 -0.406013 0.159457 + outer loop + vertex 848.031 272.245 90.1369 + vertex 847.924 273.189 91.9349 + vertex 846.843 274.553 89.306 + endloop + endfacet + facet normal -0.908854 -0.383051 0.165092 + outer loop + vertex 848.082 273.598 93.7518 + vertex 847.063 275.749 93.1335 + vertex 847.924 273.189 91.9349 + endloop + endfacet + facet normal -0.906315 -0.385731 0.17264 + outer loop + vertex 847.063 275.749 93.1335 + vertex 846.843 274.553 89.306 + vertex 847.924 273.189 91.9349 + endloop + endfacet + facet normal -0.842379 -0.496202 0.210192 + outer loop + vertex 847.924 273.189 91.9349 + vertex 848.031 272.245 90.1369 + vertex 848.884 271.479 91.7447 + endloop + endfacet + facet normal -0.83479 -0.513823 0.197766 + outer loop + vertex 848.884 271.479 91.7447 + vertex 848.031 272.245 90.1369 + vertex 848.841 270.805 89.8143 + endloop + endfacet + facet normal -0.846901 -0.498287 0.185657 + outer loop + vertex 848.082 273.598 93.7518 + vertex 847.924 273.189 91.9349 + vertex 848.856 272.289 93.7737 + endloop + endfacet + facet normal -0.847644 -0.496564 0.186877 + outer loop + vertex 848.856 272.289 93.7737 + vertex 847.924 273.189 91.9349 + vertex 848.884 271.479 91.7447 + endloop + endfacet + facet normal -0.755438 -0.61194 0.234186 + outer loop + vertex 848.856 272.289 93.7737 + vertex 848.884 271.479 91.7447 + vertex 849.896 270.921 93.5525 + endloop + endfacet + facet normal -0.744167 -0.629908 0.222333 + outer loop + vertex 849.896 270.921 93.5525 + vertex 848.884 271.479 91.7447 + vertex 849.878 270.247 91.5846 + endloop + endfacet + facet normal -0.740792 -0.628947 0.235909 + outer loop + vertex 848.884 271.479 91.7447 + vertex 848.841 270.805 89.8143 + vertex 849.878 270.247 91.5846 + endloop + endfacet + facet normal -0.737724 -0.633769 0.232593 + outer loop + vertex 849.878 270.247 91.5846 + vertex 848.841 270.805 89.8143 + vertex 849.817 269.623 89.688 + endloop + endfacet + facet normal -0.831333 -0.501505 0.239538 + outer loop + vertex 847.79 271.866 88.1481 + vertex 847.838 270.957 86.4113 + vertex 848.753 270.173 87.9466 + endloop + endfacet + facet normal -0.826513 -0.51356 0.230503 + outer loop + vertex 848.753 270.173 87.9466 + vertex 847.838 270.957 86.4113 + vertex 848.638 269.538 86.1171 + endloop + endfacet + facet normal -0.834425 -0.513911 0.199074 + outer loop + vertex 848.031 272.245 90.1369 + vertex 847.79 271.866 88.1481 + vertex 848.841 270.805 89.8143 + endloop + endfacet + facet normal -0.838984 -0.502268 0.209364 + outer loop + vertex 848.841 270.805 89.8143 + vertex 847.79 271.866 88.1481 + vertex 848.753 270.173 87.9466 + endloop + endfacet + facet normal -0.733852 -0.632262 0.248406 + outer loop + vertex 848.841 270.805 89.8143 + vertex 848.753 270.173 87.9466 + vertex 849.817 269.623 89.688 + endloop + endfacet + facet normal -0.732962 -0.633682 0.247413 + outer loop + vertex 849.817 269.623 89.688 + vertex 848.753 270.173 87.9466 + vertex 849.724 269.008 87.8373 + endloop + endfacet + facet normal -0.728471 -0.631621 0.265302 + outer loop + vertex 848.753 270.173 87.9466 + vertex 848.638 269.538 86.1171 + vertex 849.724 269.008 87.8373 + endloop + endfacet + facet normal -0.726319 -0.635106 0.262871 + outer loop + vertex 849.724 269.008 87.8373 + vertex 848.638 269.538 86.1171 + vertex 849.615 268.375 86.0086 + endloop + endfacet + facet normal -0.172893 -0.914907 0.364765 + outer loop + vertex 853.132 265.085 81.8718 + vertex 853.116 264.418 80.1897 + vertex 853.624 265.185 82.3545 + endloop + endfacet + facet normal -0.138393 -0.915373 0.378073 + outer loop + vertex 852.924 263.674 78.3195 + vertex 853.502 263.895 79.0648 + vertex 853.116 264.418 80.1897 + endloop + endfacet + facet normal -0.174963 -0.914393 0.365068 + outer loop + vertex 853.502 263.895 79.0648 + vertex 853.624 265.185 82.3545 + vertex 853.116 264.418 80.1897 + endloop + endfacet + facet normal -0.18538 -0.92262 0.338241 + outer loop + vertex 853.289 266.417 85.511 + vertex 853.296 265.769 83.7479 + vertex 853.835 266.447 85.8936 + endloop + endfacet + facet normal -0.156936 -0.923408 0.35027 + outer loop + vertex 853.132 265.085 81.8718 + vertex 853.624 265.185 82.3545 + vertex 853.296 265.769 83.7479 + endloop + endfacet + facet normal -0.195108 -0.920014 0.339863 + outer loop + vertex 853.624 265.185 82.3545 + vertex 853.835 266.447 85.8936 + vertex 853.296 265.769 83.7479 + endloop + endfacet + facet normal -0.550791 -0.753098 0.359822 + outer loop + vertex 849.227 266.3 80.5561 + vertex 849.066 265.552 78.7435 + vertex 850.321 265.48 80.5143 + endloop + endfacet + facet normal -0.544881 -0.759481 0.355377 + outer loop + vertex 850.321 265.48 80.5143 + vertex 849.066 265.552 78.7435 + vertex 850.171 264.734 78.6906 + endloop + endfacet + facet normal -0.55871 -0.755616 0.341888 + outer loop + vertex 849.37 267.015 82.369 + vertex 849.227 266.3 80.5561 + vertex 850.452 266.2 82.3372 + endloop + endfacet + facet normal -0.555793 -0.758744 0.339707 + outer loop + vertex 850.452 266.2 82.3372 + vertex 849.227 266.3 80.5561 + vertex 850.321 265.48 80.5143 + endloop + endfacet + facet normal -0.39628 -0.843825 0.36183 + outer loop + vertex 850.452 266.2 82.3372 + vertex 850.321 265.48 80.5143 + vertex 851.547 265.679 82.32 + endloop + endfacet + facet normal -0.390251 -0.848167 0.358214 + outer loop + vertex 851.547 265.679 82.32 + vertex 850.321 265.48 80.5143 + vertex 851.432 264.96 80.4928 + endloop + endfacet + facet normal -0.386966 -0.841893 0.376129 + outer loop + vertex 850.321 265.48 80.5143 + vertex 850.171 264.734 78.6906 + vertex 851.432 264.96 80.4928 + endloop + endfacet + facet normal -0.381099 -0.846146 0.372559 + outer loop + vertex 851.432 264.96 80.4928 + vertex 850.171 264.734 78.6906 + vertex 851.292 264.217 78.6634 + endloop + endfacet + facet normal -0.56998 -0.752718 0.329453 + outer loop + vertex 849.498 267.714 84.1879 + vertex 849.37 267.015 82.369 + vertex 850.566 266.893 84.1608 + endloop + endfacet + facet normal -0.562813 -0.760375 0.324146 + outer loop + vertex 850.566 266.893 84.1608 + vertex 849.37 267.015 82.369 + vertex 850.452 266.2 82.3372 + endloop + endfacet + facet normal -0.579053 -0.753645 0.310995 + outer loop + vertex 849.615 268.375 86.0086 + vertex 849.498 267.714 84.1879 + vertex 850.669 267.558 85.9903 + endloop + endfacet + facet normal -0.57476 -0.758224 0.30781 + outer loop + vertex 850.669 267.558 85.9903 + vertex 849.498 267.714 84.1879 + vertex 850.566 266.893 84.1608 + endloop + endfacet + facet normal -0.416755 -0.846593 0.331052 + outer loop + vertex 850.669 267.558 85.9903 + vertex 850.566 266.893 84.1608 + vertex 851.734 267.033 85.9877 + endloop + endfacet + facet normal -0.410767 -0.850869 0.327554 + outer loop + vertex 851.734 267.033 85.9877 + vertex 850.566 266.893 84.1608 + vertex 851.646 266.368 84.1496 + endloop + endfacet + facet normal -0.407638 -0.844847 0.346502 + outer loop + vertex 850.566 266.893 84.1608 + vertex 850.452 266.2 82.3372 + vertex 851.646 266.368 84.1496 + endloop + endfacet + facet normal -0.399768 -0.85049 0.341838 + outer loop + vertex 851.646 266.368 84.1496 + vertex 850.452 266.2 82.3372 + vertex 851.547 265.679 82.32 + endloop + endfacet + facet normal -0.276837 -0.894264 0.351643 + outer loop + vertex 851.646 266.368 84.1496 + vertex 851.547 265.679 82.32 + vertex 852.595 266.029 84.0356 + endloop + endfacet + facet normal -0.270708 -0.897355 0.348527 + outer loop + vertex 852.595 266.029 84.0356 + vertex 851.547 265.679 82.32 + vertex 852.507 265.345 82.207 + endloop + endfacet + facet normal -0.288679 -0.895782 0.337993 + outer loop + vertex 851.734 267.033 85.9877 + vertex 851.646 266.368 84.1496 + vertex 852.674 266.693 85.8893 + endloop + endfacet + facet normal -0.280882 -0.899706 0.334117 + outer loop + vertex 852.674 266.693 85.8893 + vertex 851.646 266.368 84.1496 + vertex 852.595 266.029 84.0356 + endloop + endfacet + facet normal -0.204529 -0.918767 0.337692 + outer loop + vertex 852.674 266.693 85.8893 + vertex 852.595 266.029 84.0356 + vertex 853.289 266.417 85.511 + endloop + endfacet + facet normal -0.202686 -0.919429 0.337 + outer loop + vertex 853.289 266.417 85.511 + vertex 852.595 266.029 84.0356 + vertex 853.296 265.769 83.7479 + endloop + endfacet + facet normal -0.195208 -0.915537 0.35169 + outer loop + vertex 852.595 266.029 84.0356 + vertex 852.507 265.345 82.207 + vertex 853.296 265.769 83.7479 + endloop + endfacet + facet normal -0.19313 -0.916304 0.350838 + outer loop + vertex 853.296 265.769 83.7479 + vertex 852.507 265.345 82.207 + vertex 853.132 265.085 81.8718 + endloop + endfacet + facet normal -0.254793 -0.889046 0.380365 + outer loop + vertex 851.432 264.96 80.4928 + vertex 851.292 264.217 78.6634 + vertex 852.407 264.638 80.3944 + endloop + endfacet + facet normal -0.250835 -0.891049 0.378303 + outer loop + vertex 852.407 264.638 80.3944 + vertex 851.292 264.217 78.6634 + vertex 852.277 263.904 78.5785 + endloop + endfacet + facet normal -0.266342 -0.891147 0.367314 + outer loop + vertex 851.547 265.679 82.32 + vertex 851.432 264.96 80.4928 + vertex 852.507 265.345 82.207 + endloop + endfacet + facet normal -0.25851 -0.895095 0.363286 + outer loop + vertex 852.507 265.345 82.207 + vertex 851.432 264.96 80.4928 + vertex 852.407 264.638 80.3944 + endloop + endfacet + facet normal -0.183434 -0.912404 0.365884 + outer loop + vertex 852.507 265.345 82.207 + vertex 852.407 264.638 80.3944 + vertex 853.132 265.085 81.8718 + endloop + endfacet + facet normal -0.179524 -0.913782 0.364381 + outer loop + vertex 853.132 265.085 81.8718 + vertex 852.407 264.638 80.3944 + vertex 853.116 264.418 80.1897 + endloop + endfacet + facet normal -0.173441 -0.908627 0.379887 + outer loop + vertex 852.407 264.638 80.3944 + vertex 852.277 263.904 78.5785 + vertex 853.116 264.418 80.1897 + endloop + endfacet + facet normal -0.171444 -0.909345 0.379076 + outer loop + vertex 853.116 264.418 80.1897 + vertex 852.277 263.904 78.5785 + vertex 852.924 263.674 78.3195 + endloop + endfacet + facet normal -0.879487 -0.407323 0.246149 + outer loop + vertex 847.231 268.19 79.2118 + vertex 847.239 269.196 80.9036 + vertex 845.951 270.505 78.4687 + endloop + endfacet + facet normal -0.885034 -0.397701 0.24197 + outer loop + vertex 847.561 269.631 82.798 + vertex 846.312 271.933 82.0131 + vertex 847.239 269.196 80.9036 + endloop + endfacet + facet normal -0.881404 -0.400142 0.251025 + outer loop + vertex 846.312 271.933 82.0131 + vertex 845.951 270.505 78.4687 + vertex 847.239 269.196 80.9036 + endloop + endfacet + facet normal -0.886955 -0.406473 0.219296 + outer loop + vertex 847.561 269.631 82.798 + vertex 847.545 270.583 84.4983 + vertex 846.312 271.933 82.0131 + endloop + endfacet + facet normal -0.892383 -0.397222 0.214165 + outer loop + vertex 847.838 270.957 86.4113 + vertex 846.613 273.278 85.6116 + vertex 847.545 270.583 84.4983 + endloop + endfacet + facet normal -0.888805 -0.399948 0.223759 + outer loop + vertex 846.613 273.278 85.6116 + vertex 846.312 271.933 82.0131 + vertex 847.545 270.583 84.4983 + endloop + endfacet + facet normal -0.823092 -0.498763 0.271581 + outer loop + vertex 847.545 270.583 84.4983 + vertex 847.561 269.631 82.798 + vertex 848.511 268.885 84.3057 + endloop + endfacet + facet normal -0.81648 -0.516102 0.25884 + outer loop + vertex 848.511 268.885 84.3057 + vertex 847.561 269.631 82.798 + vertex 848.372 268.197 82.4977 + endloop + endfacet + facet normal -0.827561 -0.513428 0.227014 + outer loop + vertex 847.838 270.957 86.4113 + vertex 847.545 270.583 84.4983 + vertex 848.638 269.538 86.1171 + endloop + endfacet + facet normal -0.83231 -0.500277 0.238711 + outer loop + vertex 848.638 269.538 86.1171 + vertex 847.545 270.583 84.4983 + vertex 848.511 268.885 84.3057 + endloop + endfacet + facet normal -0.722128 -0.633073 0.278835 + outer loop + vertex 848.638 269.538 86.1171 + vertex 848.511 268.885 84.3057 + vertex 849.615 268.375 86.0086 + endloop + endfacet + facet normal -0.720643 -0.635503 0.277145 + outer loop + vertex 849.615 268.375 86.0086 + vertex 848.511 268.885 84.3057 + vertex 849.498 267.714 84.1879 + endloop + endfacet + facet normal -0.715503 -0.633019 0.295537 + outer loop + vertex 848.511 268.885 84.3057 + vertex 848.372 268.197 82.4977 + vertex 849.498 267.714 84.1879 + endloop + endfacet + facet normal -0.714457 -0.634754 0.294344 + outer loop + vertex 849.498 267.714 84.1879 + vertex 848.372 268.197 82.4977 + vertex 849.37 267.015 82.369 + endloop + endfacet + facet normal -0.810068 -0.502387 0.302319 + outer loop + vertex 847.239 269.196 80.9036 + vertex 847.231 268.19 79.2118 + vertex 848.221 267.485 80.6936 + endloop + endfacet + facet normal -0.80453 -0.517493 0.291432 + outer loop + vertex 848.221 267.485 80.6936 + vertex 847.231 268.19 79.2118 + vertex 848.05 266.736 78.8912 + endloop + endfacet + facet normal -0.816904 -0.516073 0.257558 + outer loop + vertex 847.561 269.631 82.798 + vertex 847.239 269.196 80.9036 + vertex 848.372 268.197 82.4977 + endloop + endfacet + facet normal -0.820926 -0.504378 0.267739 + outer loop + vertex 848.372 268.197 82.4977 + vertex 847.239 269.196 80.9036 + vertex 848.221 267.485 80.6936 + endloop + endfacet + facet normal -0.710067 -0.632657 0.309112 + outer loop + vertex 848.372 268.197 82.4977 + vertex 848.221 267.485 80.6936 + vertex 849.37 267.015 82.369 + endloop + endfacet + facet normal -0.707862 -0.636358 0.306562 + outer loop + vertex 849.37 267.015 82.369 + vertex 848.221 267.485 80.6936 + vertex 849.227 266.3 80.5561 + endloop + endfacet + facet normal -0.700618 -0.632875 0.32955 + outer loop + vertex 848.221 267.485 80.6936 + vertex 848.05 266.736 78.8912 + vertex 849.227 266.3 80.5561 + endloop + endfacet + facet normal -0.697197 -0.638662 0.325617 + outer loop + vertex 849.227 266.3 80.5561 + vertex 848.05 266.736 78.8912 + vertex 849.066 265.552 78.7435 + endloop + endfacet + facet normal -0.128291 -0.895979 0.425162 + outer loop + vertex 852.634 262.082 74.6179 + vertex 852.56 261.249 72.8399 + vertex 853.234 262.224 75.0984 + endloop + endfacet + facet normal -0.0911247 -0.893637 0.439442 + outer loop + vertex 852.285 260.352 70.9595 + vertex 852.873 260.388 71.1556 + vertex 852.56 261.249 72.8399 + endloop + endfacet + facet normal -0.145323 -0.891805 0.428446 + outer loop + vertex 852.873 260.388 71.1556 + vertex 853.234 262.224 75.0984 + vertex 852.56 261.249 72.8399 + endloop + endfacet + facet normal -0.16072 -0.905596 0.39251 + outer loop + vertex 852.924 263.674 78.3195 + vertex 852.876 262.923 76.5667 + vertex 853.502 263.895 79.0648 + endloop + endfacet + facet normal -0.109743 -0.907521 0.405416 + outer loop + vertex 852.634 262.082 74.6179 + vertex 853.234 262.224 75.0984 + vertex 852.876 262.923 76.5667 + endloop + endfacet + facet normal -0.159837 -0.905812 0.392372 + outer loop + vertex 853.234 262.224 75.0984 + vertex 853.502 263.895 79.0648 + vertex 852.876 262.923 76.5667 + endloop + endfacet + facet normal -0.50444 -0.745117 0.43628 + outer loop + vertex 848.464 263.125 73.3495 + vertex 848.22 262.261 71.593 + vertex 849.603 262.307 73.2702 + endloop + endfacet + facet normal -0.500596 -0.749477 0.433231 + outer loop + vertex 849.603 262.307 73.2702 + vertex 848.22 262.261 71.593 + vertex 849.372 261.442 71.5068 + endloop + endfacet + facet normal -0.517331 -0.747584 0.416516 + outer loop + vertex 848.685 263.966 75.1327 + vertex 848.464 263.125 73.3495 + vertex 849.812 263.144 75.0582 + endloop + endfacet + facet normal -0.512075 -0.753444 0.412434 + outer loop + vertex 849.812 263.144 75.0582 + vertex 848.464 263.125 73.3495 + vertex 849.603 262.307 73.2702 + endloop + endfacet + facet normal -0.355309 -0.829996 0.429956 + outer loop + vertex 849.812 263.144 75.0582 + vertex 849.603 262.307 73.2702 + vertex 850.96 262.638 75.029 + endloop + endfacet + facet normal -0.348074 -0.835398 0.425387 + outer loop + vertex 850.96 262.638 75.029 + vertex 849.603 262.307 73.2702 + vertex 850.767 261.807 73.2388 + endloop + endfacet + facet normal -0.342875 -0.824833 0.449541 + outer loop + vertex 849.603 262.307 73.2702 + vertex 849.372 261.442 71.5068 + vertex 850.767 261.807 73.2388 + endloop + endfacet + facet normal -0.334654 -0.831063 0.444231 + outer loop + vertex 850.767 261.807 73.2388 + vertex 849.372 261.442 71.5068 + vertex 850.554 260.946 71.4692 + endloop + endfacet + facet normal -0.530333 -0.749643 0.395957 + outer loop + vertex 848.886 264.775 76.9337 + vertex 848.685 263.966 75.1327 + vertex 850.002 263.95 76.8676 + endloop + endfacet + facet normal -0.524865 -0.755675 0.391755 + outer loop + vertex 850.002 263.95 76.8676 + vertex 848.685 263.966 75.1327 + vertex 849.812 263.144 75.0582 + endloop + endfacet + facet normal -0.539119 -0.753099 0.377085 + outer loop + vertex 849.066 265.552 78.7435 + vertex 848.886 264.775 76.9337 + vertex 850.171 264.734 78.6906 + endloop + endfacet + facet normal -0.536354 -0.756112 0.374993 + outer loop + vertex 850.171 264.734 78.6906 + vertex 848.886 264.775 76.9337 + vertex 850.002 263.95 76.8676 + endloop + endfacet + facet normal -0.376689 -0.837775 0.395269 + outer loop + vertex 850.171 264.734 78.6906 + vertex 850.002 263.95 76.8676 + vertex 851.292 264.217 78.6634 + endloop + endfacet + facet normal -0.36975 -0.842839 0.391034 + outer loop + vertex 851.292 264.217 78.6634 + vertex 850.002 263.95 76.8676 + vertex 851.137 263.439 76.8398 + endloop + endfacet + facet normal -0.365853 -0.835241 0.410517 + outer loop + vertex 850.002 263.95 76.8676 + vertex 849.812 263.144 75.0582 + vertex 851.137 263.439 76.8398 + endloop + endfacet + facet normal -0.360085 -0.839492 0.40693 + outer loop + vertex 851.137 263.439 76.8398 + vertex 849.812 263.144 75.0582 + vertex 850.96 262.638 75.029 + endloop + endfacet + facet normal -0.234927 -0.880071 0.412655 + outer loop + vertex 851.137 263.439 76.8398 + vertex 850.96 262.638 75.029 + vertex 852.137 263.136 76.7624 + endloop + endfacet + facet normal -0.228197 -0.883507 0.409073 + outer loop + vertex 852.137 263.136 76.7624 + vertex 850.96 262.638 75.029 + vertex 851.977 262.337 74.9465 + endloop + endfacet + facet normal -0.246769 -0.883592 0.397958 + outer loop + vertex 851.292 264.217 78.6634 + vertex 851.137 263.439 76.8398 + vertex 852.277 263.904 78.5785 + endloop + endfacet + facet normal -0.238698 -0.887682 0.393757 + outer loop + vertex 852.277 263.904 78.5785 + vertex 851.137 263.439 76.8398 + vertex 852.137 263.136 76.7624 + endloop + endfacet + facet normal -0.163253 -0.904113 0.394878 + outer loop + vertex 852.277 263.904 78.5785 + vertex 852.137 263.136 76.7624 + vertex 852.924 263.674 78.3195 + endloop + endfacet + facet normal -0.157459 -0.906112 0.392642 + outer loop + vertex 852.924 263.674 78.3195 + vertex 852.137 263.136 76.7624 + vertex 852.876 262.923 76.5667 + endloop + endfacet + facet normal -0.151171 -0.89973 0.40943 + outer loop + vertex 852.137 263.136 76.7624 + vertex 851.977 262.337 74.9465 + vertex 852.876 262.923 76.5667 + endloop + endfacet + facet normal -0.146254 -0.90149 0.407339 + outer loop + vertex 852.876 262.923 76.5667 + vertex 851.977 262.337 74.9465 + vertex 852.634 262.082 74.6179 + endloop + endfacet + facet normal -0.210666 -0.86899 0.447745 + outer loop + vertex 850.767 261.807 73.2388 + vertex 850.554 260.946 71.4692 + vertex 851.804 261.505 73.1418 + endloop + endfacet + facet normal -0.203897 -0.872578 0.443885 + outer loop + vertex 851.804 261.505 73.1418 + vertex 850.554 260.946 71.4692 + vertex 851.608 260.642 71.3542 + endloop + endfacet + facet normal -0.223844 -0.874566 0.43015 + outer loop + vertex 850.96 262.638 75.029 + vertex 850.767 261.807 73.2388 + vertex 851.977 262.337 74.9465 + endloop + endfacet + facet normal -0.215598 -0.878838 0.42563 + outer loop + vertex 851.977 262.337 74.9465 + vertex 850.767 261.807 73.2388 + vertex 851.804 261.505 73.1418 + endloop + endfacet + facet normal -0.134748 -0.894971 0.425287 + outer loop + vertex 851.977 262.337 74.9465 + vertex 851.804 261.505 73.1418 + vertex 852.634 262.082 74.6179 + endloop + endfacet + facet normal -0.134152 -0.895181 0.425034 + outer loop + vertex 852.634 262.082 74.6179 + vertex 851.804 261.505 73.1418 + vertex 852.56 261.249 72.8399 + endloop + endfacet + facet normal -0.124679 -0.887985 0.442649 + outer loop + vertex 851.804 261.505 73.1418 + vertex 851.608 260.642 71.3542 + vertex 852.56 261.249 72.8399 + endloop + endfacet + facet normal -0.122756 -0.888717 0.441716 + outer loop + vertex 852.56 261.249 72.8399 + vertex 851.608 260.642 71.3542 + vertex 852.285 260.352 70.9595 + endloop + endfacet + facet normal -0.856125 -0.410199 0.314304 + outer loop + vertex 846.346 264.999 72.1681 + vertex 846.422 266.102 73.8166 + vertex 844.985 267.365 71.5489 + endloop + endfacet + facet normal -0.863521 -0.398689 0.308833 + outer loop + vertex 846.83 266.645 75.6577 + vertex 845.51 268.97 74.9695 + vertex 846.422 266.102 73.8166 + endloop + endfacet + facet normal -0.857999 -0.401547 0.32031 + outer loop + vertex 845.51 268.97 74.9695 + vertex 844.985 267.365 71.5489 + vertex 846.422 266.102 73.8166 + endloop + endfacet + facet normal -0.868296 -0.410291 0.278788 + outer loop + vertex 846.83 266.645 75.6577 + vertex 846.87 267.702 77.3371 + vertex 845.51 268.97 74.9695 + endloop + endfacet + facet normal -0.876389 -0.397197 0.272354 + outer loop + vertex 847.231 268.19 79.2118 + vertex 845.951 270.505 78.4687 + vertex 846.87 267.702 77.3371 + endloop + endfacet + facet normal -0.870689 -0.400582 0.285366 + outer loop + vertex 845.951 270.505 78.4687 + vertex 845.51 268.97 74.9695 + vertex 846.87 267.702 77.3371 + endloop + endfacet + facet normal -0.796529 -0.503031 0.335413 + outer loop + vertex 846.87 267.702 77.3371 + vertex 846.83 266.645 75.6577 + vertex 847.863 265.968 77.0969 + endloop + endfacet + facet normal -0.791075 -0.518829 0.324065 + outer loop + vertex 847.863 265.968 77.0969 + vertex 846.83 266.645 75.6577 + vertex 847.656 265.17 75.3127 + endloop + endfacet + facet normal -0.805075 -0.517475 0.289954 + outer loop + vertex 847.231 268.19 79.2118 + vertex 846.87 267.702 77.3371 + vertex 848.05 266.736 78.8912 + endloop + endfacet + facet normal -0.808945 -0.505305 0.300456 + outer loop + vertex 848.05 266.736 78.8912 + vertex 846.87 267.702 77.3371 + vertex 847.863 265.968 77.0969 + endloop + endfacet + facet normal -0.691071 -0.635695 0.343966 + outer loop + vertex 848.05 266.736 78.8912 + vertex 847.863 265.968 77.0969 + vertex 849.066 265.552 78.7435 + endloop + endfacet + facet normal -0.689882 -0.637731 0.342582 + outer loop + vertex 849.066 265.552 78.7435 + vertex 847.863 265.968 77.0969 + vertex 848.886 264.775 76.9337 + endloop + endfacet + facet normal -0.68256 -0.634263 0.363074 + outer loop + vertex 847.863 265.968 77.0969 + vertex 847.656 265.17 75.3127 + vertex 848.886 264.775 76.9337 + endloop + endfacet + facet normal -0.681488 -0.636139 0.361803 + outer loop + vertex 848.886 264.775 76.9337 + vertex 847.656 265.17 75.3127 + vertex 848.685 263.966 75.1327 + endloop + endfacet + facet normal -0.780486 -0.502175 0.372374 + outer loop + vertex 846.422 266.102 73.8166 + vertex 846.346 264.999 72.1681 + vertex 847.427 264.337 73.5411 + endloop + endfacet + facet normal -0.776328 -0.515559 0.362649 + outer loop + vertex 847.427 264.337 73.5411 + vertex 846.346 264.999 72.1681 + vertex 847.177 263.487 71.7982 + endloop + endfacet + facet normal -0.789499 -0.518837 0.327872 + outer loop + vertex 846.83 266.645 75.6577 + vertex 846.422 266.102 73.8166 + vertex 847.656 265.17 75.3127 + endloop + endfacet + facet normal -0.793557 -0.504575 0.340104 + outer loop + vertex 847.656 265.17 75.3127 + vertex 846.422 266.102 73.8166 + vertex 847.427 264.337 73.5411 + endloop + endfacet + facet normal -0.672794 -0.632098 0.384448 + outer loop + vertex 847.656 265.17 75.3127 + vertex 847.427 264.337 73.5411 + vertex 848.685 263.966 75.1327 + endloop + endfacet + facet normal -0.671212 -0.634934 0.382535 + outer loop + vertex 848.685 263.966 75.1327 + vertex 847.427 264.337 73.5411 + vertex 848.464 263.125 73.3495 + endloop + endfacet + facet normal -0.662973 -0.631079 0.402747 + outer loop + vertex 847.427 264.337 73.5411 + vertex 847.177 263.487 71.7982 + vertex 848.464 263.125 73.3495 + endloop + endfacet + facet normal -0.662677 -0.631629 0.402373 + outer loop + vertex 848.464 263.125 73.3495 + vertex 847.177 263.487 71.7982 + vertex 848.22 262.261 71.593 + endloop + endfacet + facet normal -0.0767682 -0.867527 0.49143 + outer loop + vertex 851.857 258.563 67.5112 + vertex 851.707 257.674 65.9185 + vertex 852.437 258.739 67.9128 + endloop + endfacet + facet normal -0.0529903 -0.861075 0.505709 + outer loop + vertex 851.343 256.669 64.1701 + vertex 852.031 257.022 64.8424 + vertex 851.707 257.674 65.9185 + endloop + endfacet + facet normal -0.0928467 -0.863746 0.495301 + outer loop + vertex 852.031 257.022 64.8424 + vertex 852.437 258.739 67.9128 + vertex 851.707 257.674 65.9185 + endloop + endfacet + facet normal -0.0983222 -0.882976 0.459006 + outer loop + vertex 852.285 260.352 70.9595 + vertex 852.175 259.49 69.2783 + vertex 852.873 260.388 71.1556 + endloop + endfacet + facet normal -0.0600078 -0.879349 0.472382 + outer loop + vertex 851.857 258.563 67.5112 + vertex 852.437 258.739 67.9128 + vertex 852.175 259.49 69.2783 + endloop + endfacet + facet normal -0.1121 -0.879519 0.462471 + outer loop + vertex 852.437 258.739 67.9128 + vertex 852.873 260.388 71.1556 + vertex 852.175 259.49 69.2783 + endloop + endfacet + facet normal -0.45507 -0.723027 0.519753 + outer loop + vertex 847.351 259.527 66.496 + vertex 847.01 258.562 64.854 + vertex 848.538 258.674 66.3489 + endloop + endfacet + facet normal -0.452312 -0.72658 0.5172 + outer loop + vertex 848.538 258.674 66.3489 + vertex 847.01 258.562 64.854 + vertex 848.209 257.689 64.6764 + endloop + endfacet + facet normal -0.467702 -0.731228 0.496548 + outer loop + vertex 847.665 260.461 68.1658 + vertex 847.351 259.527 66.496 + vertex 848.841 259.628 68.0476 + endloop + endfacet + facet normal -0.465764 -0.733618 0.494842 + outer loop + vertex 848.841 259.628 68.0476 + vertex 847.351 259.527 66.496 + vertex 848.538 258.674 66.3489 + endloop + endfacet + facet normal -0.302556 -0.807094 0.507011 + outer loop + vertex 848.841 259.628 68.0476 + vertex 848.538 258.674 66.3489 + vertex 850.062 259.126 67.9771 + endloop + endfacet + facet normal -0.296307 -0.812172 0.502572 + outer loop + vertex 850.062 259.126 67.9771 + vertex 848.538 258.674 66.3489 + vertex 849.778 258.164 66.2557 + endloop + endfacet + facet normal -0.288942 -0.798842 0.527601 + outer loop + vertex 848.538 258.674 66.3489 + vertex 848.209 257.689 64.6764 + vertex 849.778 258.164 66.2557 + endloop + endfacet + facet normal -0.28178 -0.804862 0.5223 + outer loop + vertex 849.778 258.164 66.2557 + vertex 848.209 257.689 64.6764 + vertex 849.465 257.174 64.5609 + endloop + endfacet + facet normal -0.480727 -0.734782 0.478537 + outer loop + vertex 847.955 261.379 69.8673 + vertex 847.665 260.461 68.1658 + vertex 849.119 260.553 69.768 + endloop + endfacet + facet normal -0.476213 -0.740157 0.474751 + outer loop + vertex 849.119 260.553 69.768 + vertex 847.665 260.461 68.1658 + vertex 848.841 259.628 68.0476 + endloop + endfacet + facet normal -0.49323 -0.741411 0.455011 + outer loop + vertex 848.22 262.261 71.593 + vertex 847.955 261.379 69.8673 + vertex 849.372 261.442 71.5068 + endloop + endfacet + facet normal -0.490175 -0.744959 0.452509 + outer loop + vertex 849.372 261.442 71.5068 + vertex 847.955 261.379 69.8673 + vertex 849.119 260.553 69.768 + endloop + endfacet + facet normal -0.329384 -0.820277 0.467603 + outer loop + vertex 849.372 261.442 71.5068 + vertex 849.119 260.553 69.768 + vertex 850.554 260.946 71.4692 + endloop + endfacet + facet normal -0.322885 -0.825297 0.463282 + outer loop + vertex 850.554 260.946 71.4692 + vertex 849.119 260.553 69.768 + vertex 850.318 260.054 69.7152 + endloop + endfacet + facet normal -0.316744 -0.813175 0.488282 + outer loop + vertex 849.119 260.553 69.768 + vertex 848.841 259.628 68.0476 + vertex 850.318 260.054 69.7152 + endloop + endfacet + facet normal -0.308968 -0.819317 0.482968 + outer loop + vertex 850.318 260.054 69.7152 + vertex 848.841 259.628 68.0476 + vertex 850.062 259.126 67.9771 + endloop + endfacet + facet normal -0.186027 -0.855065 0.484001 + outer loop + vertex 850.318 260.054 69.7152 + vertex 850.062 259.126 67.9771 + vertex 851.399 259.749 69.5907 + endloop + endfacet + facet normal -0.179186 -0.858881 0.479807 + outer loop + vertex 851.399 259.749 69.5907 + vertex 850.062 259.126 67.9771 + vertex 851.153 258.824 67.8435 + endloop + endfacet + facet normal -0.198624 -0.86249 0.465468 + outer loop + vertex 850.554 260.946 71.4692 + vertex 850.318 260.054 69.7152 + vertex 851.608 260.642 71.3542 + endloop + endfacet + facet normal -0.191779 -0.86621 0.461412 + outer loop + vertex 851.608 260.642 71.3542 + vertex 850.318 260.054 69.7152 + vertex 851.399 259.749 69.5907 + endloop + endfacet + facet normal -0.109374 -0.881482 0.459377 + outer loop + vertex 851.608 260.642 71.3542 + vertex 851.399 259.749 69.5907 + vertex 852.285 260.352 70.9595 + endloop + endfacet + facet normal -0.108696 -0.881736 0.45905 + outer loop + vertex 852.285 260.352 70.9595 + vertex 851.399 259.749 69.5907 + vertex 852.175 259.49 69.2783 + endloop + endfacet + facet normal -0.0990352 -0.87365 0.476369 + outer loop + vertex 851.399 259.749 69.5907 + vertex 851.153 258.824 67.8435 + vertex 852.175 259.49 69.2783 + endloop + endfacet + facet normal -0.0991302 -0.873612 0.476419 + outer loop + vertex 852.175 259.49 69.2783 + vertex 851.153 258.824 67.8435 + vertex 851.857 258.563 67.5112 + endloop + endfacet + facet normal -0.15991 -0.839151 0.51986 + outer loop + vertex 849.778 258.164 66.2557 + vertex 849.465 257.174 64.5609 + vertex 850.894 257.873 66.128 + endloop + endfacet + facet normal -0.152924 -0.843245 0.515317 + outer loop + vertex 850.894 257.873 66.128 + vertex 849.465 257.174 64.5609 + vertex 850.601 256.889 64.4321 + endloop + endfacet + facet normal -0.173294 -0.847381 0.501912 + outer loop + vertex 850.062 259.126 67.9771 + vertex 849.778 258.164 66.2557 + vertex 851.153 258.824 67.8435 + endloop + endfacet + facet normal -0.165777 -0.851665 0.497177 + outer loop + vertex 851.153 258.824 67.8435 + vertex 849.778 258.164 66.2557 + vertex 850.894 257.873 66.128 + endloop + endfacet + facet normal -0.08823 -0.865485 0.493104 + outer loop + vertex 851.153 258.824 67.8435 + vertex 850.894 257.873 66.128 + vertex 851.857 258.563 67.5112 + endloop + endfacet + facet normal -0.0854541 -0.866558 0.491707 + outer loop + vertex 851.857 258.563 67.5112 + vertex 850.894 257.873 66.128 + vertex 851.707 257.674 65.9185 + endloop + endfacet + facet normal -0.0782456 -0.856523 0.510142 + outer loop + vertex 850.894 257.873 66.128 + vertex 850.601 256.889 64.4321 + vertex 851.707 257.674 65.9185 + endloop + endfacet + facet normal -0.0750099 -0.857832 0.508427 + outer loop + vertex 851.707 257.674 65.9185 + vertex 850.601 256.889 64.4321 + vertex 851.343 256.669 64.1701 + endloop + endfacet + facet normal -0.819232 -0.407247 0.403745 + outer loop + vertex 845.09 261.461 65.545 + vertex 845.254 262.657 67.0849 + vertex 843.622 263.932 65.0583 + endloop + endfacet + facet normal -0.830456 -0.395299 0.392532 + outer loop + vertex 845.769 263.269 68.7902 + vertex 844.358 265.685 68.2376 + vertex 845.254 262.657 67.0849 + endloop + endfacet + facet normal -0.820302 -0.398891 0.409865 + outer loop + vertex 844.358 265.685 68.2376 + vertex 843.622 263.932 65.0583 + vertex 845.254 262.657 67.0849 + endloop + endfacet + facet normal -0.83995 -0.409064 0.356582 + outer loop + vertex 845.769 263.269 68.7902 + vertex 845.888 264.419 70.3881 + vertex 844.358 265.685 68.2376 + endloop + endfacet + facet normal -0.849127 -0.397364 0.347973 + outer loop + vertex 846.346 264.999 72.1681 + vertex 844.985 267.365 71.5489 + vertex 845.888 264.419 70.3881 + endloop + endfacet + facet normal -0.841417 -0.400736 0.362531 + outer loop + vertex 844.985 267.365 71.5489 + vertex 844.358 265.685 68.2376 + vertex 845.888 264.419 70.3881 + endloop + endfacet + facet normal -0.761553 -0.497991 0.41478 + outer loop + vertex 845.888 264.419 70.3881 + vertex 845.769 263.269 68.7902 + vertex 846.904 262.61 70.0825 + endloop + endfacet + facet normal -0.75815 -0.510888 0.405219 + outer loop + vertex 846.904 262.61 70.0825 + vertex 845.769 263.269 68.7902 + vertex 846.607 261.717 68.4012 + endloop + endfacet + facet normal -0.774214 -0.515511 0.367207 + outer loop + vertex 846.346 264.999 72.1681 + vertex 845.888 264.419 70.3881 + vertex 847.177 263.487 71.7982 + endloop + endfacet + facet normal -0.777588 -0.501094 0.379818 + outer loop + vertex 847.177 263.487 71.7982 + vertex 845.888 264.419 70.3881 + vertex 846.904 262.61 70.0825 + endloop + endfacet + facet normal -0.653078 -0.627153 0.424463 + outer loop + vertex 847.177 263.487 71.7982 + vertex 846.904 262.61 70.0825 + vertex 848.22 262.261 71.593 + endloop + endfacet + facet normal -0.651523 -0.630143 0.422418 + outer loop + vertex 848.22 262.261 71.593 + vertex 846.904 262.61 70.0825 + vertex 847.955 261.379 69.8673 + endloop + endfacet + facet normal -0.641023 -0.625169 0.445257 + outer loop + vertex 846.904 262.61 70.0825 + vertex 846.607 261.717 68.4012 + vertex 847.955 261.379 69.8673 + endloop + endfacet + facet normal -0.641678 -0.623848 0.446164 + outer loop + vertex 847.955 261.379 69.8673 + vertex 846.607 261.717 68.4012 + vertex 847.665 260.461 68.1658 + endloop + endfacet + facet normal -0.73895 -0.491611 0.46073 + outer loop + vertex 845.254 262.657 67.0849 + vertex 845.09 261.461 65.545 + vertex 846.285 260.793 66.7481 + endloop + endfacet + facet normal -0.736466 -0.503704 0.451552 + outer loop + vertex 846.285 260.793 66.7481 + vertex 845.09 261.461 65.545 + vertex 845.936 259.854 65.1317 + endloop + endfacet + facet normal -0.755071 -0.510712 0.411147 + outer loop + vertex 845.769 263.269 68.7902 + vertex 845.254 262.657 67.0849 + vertex 846.607 261.717 68.4012 + endloop + endfacet + facet normal -0.757699 -0.49547 0.424737 + outer loop + vertex 846.607 261.717 68.4012 + vertex 845.254 262.657 67.0849 + vertex 846.285 260.793 66.7481 + endloop + endfacet + facet normal -0.630496 -0.618666 0.46875 + outer loop + vertex 846.607 261.717 68.4012 + vertex 846.285 260.793 66.7481 + vertex 847.665 260.461 68.1658 + endloop + endfacet + facet normal -0.628666 -0.622549 0.466059 + outer loop + vertex 847.665 260.461 68.1658 + vertex 846.285 260.793 66.7481 + vertex 847.351 259.527 66.496 + endloop + endfacet + facet normal -0.615565 -0.61647 0.490963 + outer loop + vertex 846.285 260.793 66.7481 + vertex 845.936 259.854 65.1317 + vertex 847.351 259.527 66.496 + endloop + endfacet + facet normal -0.61536 -0.61693 0.490641 + outer loop + vertex 847.351 259.527 66.496 + vertex 845.936 259.854 65.1317 + vertex 847.01 258.562 64.854 + endloop + endfacet + facet normal -0.0677712 -0.821647 0.565954 + outer loop + vertex 850.686 254.563 60.7778 + vertex 850.433 253.496 59.1985 + vertex 851.376 254.836 61.2563 + endloop + endfacet + facet normal -0.0363 -0.810932 0.584014 + outer loop + vertex 849.909 252.311 57.52 + vertex 850.575 252.475 57.7895 + vertex 850.433 253.496 59.1985 + endloop + endfacet + facet normal -0.106789 -0.810181 0.57637 + outer loop + vertex 850.575 252.475 57.7895 + vertex 851.376 254.836 61.2563 + vertex 850.433 253.496 59.1985 + endloop + endfacet + facet normal -0.0809434 -0.84627 0.52657 + outer loop + vertex 851.343 256.669 64.1701 + vertex 851.134 255.682 62.552 + vertex 852.031 257.022 64.8424 + endloop + endfacet + facet normal -0.0430016 -0.840094 0.540734 + outer loop + vertex 850.686 254.563 60.7778 + vertex 851.376 254.836 61.2563 + vertex 851.134 255.682 62.552 + endloop + endfacet + facet normal -0.0995395 -0.841471 0.531055 + outer loop + vertex 851.376 254.836 61.2563 + vertex 852.031 257.022 64.8424 + vertex 851.134 255.682 62.552 + endloop + endfacet + facet normal -0.390095 -0.691189 0.608345 + outer loop + vertex 845.818 255.535 60.1572 + vertex 845.362 254.494 58.6815 + vertex 847.061 254.607 59.9002 + endloop + endfacet + facet normal -0.389652 -0.691921 0.607796 + outer loop + vertex 847.061 254.607 59.9002 + vertex 845.362 254.494 58.6815 + vertex 846.622 253.537 58.3998 + endloop + endfacet + facet normal -0.408736 -0.698843 0.586987 + outer loop + vertex 846.245 256.565 61.6812 + vertex 845.818 255.535 60.1572 + vertex 847.47 255.652 61.4465 + endloop + endfacet + facet normal -0.405159 -0.704322 0.582903 + outer loop + vertex 847.47 255.652 61.4465 + vertex 845.818 255.535 60.1572 + vertex 847.061 254.607 59.9002 + endloop + endfacet + facet normal -0.243188 -0.772745 0.58628 + outer loop + vertex 847.47 255.652 61.4465 + vertex 847.061 254.607 59.9002 + vertex 848.766 255.119 61.2822 + endloop + endfacet + facet normal -0.23879 -0.777013 0.582434 + outer loop + vertex 848.766 255.119 61.2822 + vertex 847.061 254.607 59.9002 + vertex 848.38 254.059 59.7091 + endloop + endfacet + facet normal -0.227814 -0.759844 0.608882 + outer loop + vertex 847.061 254.607 59.9002 + vertex 846.622 253.537 58.3998 + vertex 848.38 254.059 59.7091 + endloop + endfacet + facet normal -0.222751 -0.765086 0.604174 + outer loop + vertex 848.38 254.059 59.7091 + vertex 846.622 253.537 58.3998 + vertex 847.963 252.977 58.185 + endloop + endfacet + facet normal -0.425155 -0.707719 0.564249 + outer loop + vertex 846.642 257.576 63.2485 + vertex 846.245 256.565 61.6812 + vertex 847.852 256.684 63.0415 + endloop + endfacet + facet normal -0.422761 -0.711156 0.561721 + outer loop + vertex 847.852 256.684 63.0415 + vertex 846.245 256.565 61.6812 + vertex 847.47 255.652 61.4465 + endloop + endfacet + facet normal -0.441308 -0.716228 0.540615 + outer loop + vertex 847.01 258.562 64.854 + vertex 846.642 257.576 63.2485 + vertex 848.209 257.689 64.6764 + endloop + endfacet + facet normal -0.438618 -0.719878 0.537951 + outer loop + vertex 848.209 257.689 64.6764 + vertex 846.642 257.576 63.2485 + vertex 847.852 256.684 63.0415 + endloop + endfacet + facet normal -0.274144 -0.791573 0.54613 + outer loop + vertex 848.209 257.689 64.6764 + vertex 847.852 256.684 63.0415 + vertex 849.465 257.174 64.5609 + endloop + endfacet + facet normal -0.268342 -0.796652 0.541608 + outer loop + vertex 849.465 257.174 64.5609 + vertex 847.852 256.684 63.0415 + vertex 849.125 256.161 62.9016 + endloop + endfacet + facet normal -0.259126 -0.781272 0.567863 + outer loop + vertex 847.852 256.684 63.0415 + vertex 847.47 255.652 61.4465 + vertex 849.125 256.161 62.9016 + endloop + endfacet + facet normal -0.2523 -0.787519 0.56228 + outer loop + vertex 849.125 256.161 62.9016 + vertex 847.47 255.652 61.4465 + vertex 848.766 255.119 61.2822 + endloop + endfacet + facet normal -0.133206 -0.819949 0.556723 + outer loop + vertex 849.125 256.161 62.9016 + vertex 848.766 255.119 61.2822 + vertex 850.283 255.875 62.7584 + endloop + endfacet + facet normal -0.125148 -0.825037 0.551046 + outer loop + vertex 850.283 255.875 62.7584 + vertex 848.766 255.119 61.2822 + vertex 849.946 254.827 61.1124 + endloop + endfacet + facet normal -0.147199 -0.830385 0.537394 + outer loop + vertex 849.465 257.174 64.5609 + vertex 849.125 256.161 62.9016 + vertex 850.601 256.889 64.4321 + endloop + endfacet + facet normal -0.139875 -0.834827 0.532445 + outer loop + vertex 850.601 256.889 64.4321 + vertex 849.125 256.161 62.9016 + vertex 850.283 255.875 62.7584 + endloop + endfacet + facet normal -0.0657459 -0.847805 0.526217 + outer loop + vertex 850.601 256.889 64.4321 + vertex 850.283 255.875 62.7584 + vertex 851.343 256.669 64.1701 + endloop + endfacet + facet normal -0.064685 -0.848231 0.525661 + outer loop + vertex 851.343 256.669 64.1701 + vertex 850.283 255.875 62.7584 + vertex 851.134 255.682 62.552 + endloop + endfacet + facet normal -0.0574686 -0.836707 0.544627 + outer loop + vertex 850.283 255.875 62.7584 + vertex 849.946 254.827 61.1124 + vertex 851.134 255.682 62.552 + endloop + endfacet + facet normal -0.0534261 -0.838461 0.542336 + outer loop + vertex 851.134 255.682 62.552 + vertex 849.946 254.827 61.1124 + vertex 850.686 254.563 60.7778 + endloop + endfacet + facet normal -0.103661 -0.797349 0.594549 + outer loop + vertex 848.38 254.059 59.7091 + vertex 847.963 252.977 58.185 + vertex 849.574 253.751 59.5042 + endloop + endfacet + facet normal -0.100195 -0.799847 0.591782 + outer loop + vertex 849.574 253.751 59.5042 + vertex 847.963 252.977 58.185 + vertex 849.174 252.647 57.9443 + endloop + endfacet + facet normal -0.117941 -0.809751 0.574799 + outer loop + vertex 848.766 255.119 61.2822 + vertex 848.38 254.059 59.7091 + vertex 849.946 254.827 61.1124 + endloop + endfacet + facet normal -0.112029 -0.813715 0.570366 + outer loop + vertex 849.946 254.827 61.1124 + vertex 848.38 254.059 59.7091 + vertex 849.574 253.751 59.5042 + endloop + endfacet + facet normal -0.0401157 -0.826139 0.562036 + outer loop + vertex 849.946 254.827 61.1124 + vertex 849.574 253.751 59.5042 + vertex 850.686 254.563 60.7778 + endloop + endfacet + facet normal -0.0435804 -0.82458 0.564065 + outer loop + vertex 850.686 254.563 60.7778 + vertex 849.574 253.751 59.5042 + vertex 850.433 253.496 59.1985 + endloop + endfacet + facet normal -0.0330425 -0.811789 0.583015 + outer loop + vertex 849.574 253.751 59.5042 + vertex 849.174 252.647 57.9443 + vertex 850.433 253.496 59.1985 + endloop + endfacet + facet normal -0.033873 -0.811363 0.58356 + outer loop + vertex 850.433 253.496 59.1985 + vertex 849.174 252.647 57.9443 + vertex 849.909 252.311 57.52 + endloop + endfacet + facet normal -0.7538 -0.404256 0.518038 + outer loop + vertex 843.384 257.606 59.505 + vertex 843.654 258.902 60.9087 + vertex 841.802 260.126 59.1687 + endloop + endfacet + facet normal -0.775542 -0.389725 0.496637 + outer loop + vertex 844.299 259.577 62.445 + vertex 842.771 262.086 62.0275 + vertex 843.654 258.902 60.9087 + endloop + endfacet + facet normal -0.754052 -0.39393 0.52557 + outer loop + vertex 842.771 262.086 62.0275 + vertex 841.802 260.126 59.1687 + vertex 843.654 258.902 60.9087 + endloop + endfacet + facet normal -0.790813 -0.405357 0.458586 + outer loop + vertex 844.299 259.577 62.445 + vertex 844.514 260.827 63.9224 + vertex 842.771 262.086 62.0275 + endloop + endfacet + facet normal -0.807388 -0.393066 0.440027 + outer loop + vertex 845.09 261.461 65.545 + vertex 843.622 263.932 65.0583 + vertex 844.514 260.827 63.9224 + endloop + endfacet + facet normal -0.791433 -0.397409 0.464435 + outer loop + vertex 843.622 263.932 65.0583 + vertex 842.771 262.086 62.0275 + vertex 844.514 260.827 63.9224 + endloop + endfacet + facet normal -0.709324 -0.483559 0.512865 + outer loop + vertex 844.514 260.827 63.9224 + vertex 844.299 259.577 62.445 + vertex 845.561 258.898 63.5514 + endloop + endfacet + facet normal -0.70731 -0.497999 0.501707 + outer loop + vertex 845.561 258.898 63.5514 + vertex 844.299 259.577 62.445 + vertex 845.156 257.921 62.0102 + endloop + endfacet + facet normal -0.73337 -0.503439 0.456855 + outer loop + vertex 845.09 261.461 65.545 + vertex 844.514 260.827 63.9224 + vertex 845.936 259.854 65.1317 + endloop + endfacet + facet normal -0.734752 -0.489116 0.470006 + outer loop + vertex 845.936 259.854 65.1317 + vertex 844.514 260.827 63.9224 + vertex 845.561 258.898 63.5514 + endloop + endfacet + facet normal -0.602889 -0.611299 0.512678 + outer loop + vertex 845.936 259.854 65.1317 + vertex 845.561 258.898 63.5514 + vertex 847.01 258.562 64.854 + endloop + endfacet + facet normal -0.603064 -0.61087 0.512983 + outer loop + vertex 847.01 258.562 64.854 + vertex 845.561 258.898 63.5514 + vertex 846.642 257.576 63.2485 + endloop + endfacet + facet normal -0.588038 -0.604241 0.537685 + outer loop + vertex 845.561 258.898 63.5514 + vertex 845.156 257.921 62.0102 + vertex 846.642 257.576 63.2485 + endloop + endfacet + facet normal -0.588351 -0.60339 0.538297 + outer loop + vertex 846.642 257.576 63.2485 + vertex 845.156 257.921 62.0102 + vertex 846.245 256.565 61.6812 + endloop + endfacet + facet normal -0.670894 -0.47613 0.568508 + outer loop + vertex 843.654 258.902 60.9087 + vertex 843.384 257.606 59.505 + vertex 844.72 256.921 60.508 + endloop + endfacet + facet normal -0.670061 -0.488298 0.559092 + outer loop + vertex 844.72 256.921 60.508 + vertex 843.384 257.606 59.505 + vertex 844.25 255.896 59.0491 + endloop + endfacet + facet normal -0.700313 -0.497146 0.512257 + outer loop + vertex 844.299 259.577 62.445 + vertex 843.654 258.902 60.9087 + vertex 845.156 257.921 62.0102 + endloop + endfacet + facet normal -0.700592 -0.483307 0.524962 + outer loop + vertex 845.156 257.921 62.0102 + vertex 843.654 258.902 60.9087 + vertex 844.72 256.921 60.508 + endloop + endfacet + facet normal -0.572163 -0.596376 0.562996 + outer loop + vertex 845.156 257.921 62.0102 + vertex 844.72 256.921 60.508 + vertex 846.245 256.565 61.6812 + endloop + endfacet + facet normal -0.572284 -0.596005 0.563266 + outer loop + vertex 846.245 256.565 61.6812 + vertex 844.72 256.921 60.508 + vertex 845.818 255.535 60.1572 + endloop + endfacet + facet normal -0.552731 -0.587535 0.591009 + outer loop + vertex 844.72 256.921 60.508 + vertex 844.25 255.896 59.0491 + vertex 845.818 255.535 60.1572 + endloop + endfacet + facet normal -0.551568 -0.591591 0.588042 + outer loop + vertex 845.818 255.535 60.1572 + vertex 844.25 255.896 59.0491 + vertex 845.362 254.494 58.6815 + endloop + endfacet + facet normal -0.847075 -0.266799 0.459654 + outer loop + vertex 840.138 272.058 63.5828 + vertex 839.472 269.486 60.8625 + vertex 841.386 266.874 62.873 + endloop + endfacet + facet normal -0.846502 -0.264588 0.461982 + outer loop + vertex 841.386 266.874 62.873 + vertex 839.472 269.486 60.8625 + vertex 840.433 264.967 60.0347 + endloop + endfacet + facet normal -0.876376 -0.271612 0.397735 + outer loop + vertex 841.238 273.124 66.7336 + vertex 840.138 272.058 63.5828 + vertex 842.248 268.658 65.9094 + endloop + endfacet + facet normal -0.874931 -0.265975 0.404664 + outer loop + vertex 842.248 268.658 65.9094 + vertex 840.138 272.058 63.5828 + vertex 841.386 266.874 62.873 + endloop + endfacet + facet normal -0.843761 -0.322501 0.429023 + outer loop + vertex 842.248 268.658 65.9094 + vertex 841.386 266.874 62.873 + vertex 843.622 263.932 65.0583 + endloop + endfacet + facet normal -0.843264 -0.32003 0.431841 + outer loop + vertex 843.622 263.932 65.0583 + vertex 841.386 266.874 62.873 + vertex 842.771 262.086 62.0275 + endloop + endfacet + facet normal -0.81169 -0.320833 0.488084 + outer loop + vertex 841.386 266.874 62.873 + vertex 840.433 264.967 60.0347 + vertex 842.771 262.086 62.0275 + endloop + endfacet + facet normal -0.810665 -0.317189 0.492151 + outer loop + vertex 842.771 262.086 62.0275 + vertex 840.433 264.967 60.0347 + vertex 841.802 260.126 59.1687 + endloop + endfacet + facet normal 0.0927708 -0.76303 0.63967 + outer loop + vertex 848.227 247.681 51.8203 + vertex 848.913 248.025 52.1311 + vertex 848.627 248.738 53.0231 + endloop + endfacet + facet normal 0.0114048 -0.768117 0.640208 + outer loop + vertex 848.942 249.863 54.3672 + vertex 848.627 248.738 53.0231 + vertex 849.633 249.83 54.3155 + endloop + endfacet + facet normal 0.0106076 -0.772516 0.634907 + outer loop + vertex 849.094 247.752 51.7966 + vertex 849.633 249.83 54.3155 + vertex 848.913 248.025 52.1311 + endloop + endfacet + facet normal 0.0322226 -0.775636 0.630358 + outer loop + vertex 848.627 248.738 53.0231 + vertex 848.913 248.025 52.1311 + vertex 849.633 249.83 54.3155 + endloop + endfacet + facet normal -0.0521612 -0.79022 0.610599 + outer loop + vertex 849.909 252.311 57.52 + vertex 849.551 251.12 55.9477 + vertex 850.575 252.475 57.7895 + endloop + endfacet + facet normal 0.00915138 -0.784297 0.620318 + outer loop + vertex 848.942 249.863 54.3672 + vertex 849.633 249.83 54.3155 + vertex 849.551 251.12 55.9477 + endloop + endfacet + facet normal -0.07028 -0.784335 0.616343 + outer loop + vertex 849.633 249.83 54.3155 + vertex 850.575 252.475 57.7895 + vertex 849.551 251.12 55.9477 + endloop + endfacet + facet normal -0.309582 -0.635455 0.707358 + outer loop + vertex 843.807 251.297 54.611 + vertex 843.233 250.246 53.416 + vertex 845.096 250.269 54.2516 + endloop + endfacet + facet normal -0.308471 -0.638645 0.704967 + outer loop + vertex 845.096 250.269 54.2516 + vertex 843.233 250.246 53.416 + vertex 844.517 249.165 52.9986 + endloop + endfacet + facet normal -0.331082 -0.652147 0.681975 + outer loop + vertex 844.354 252.36 55.8936 + vertex 843.807 251.297 54.611 + vertex 845.644 251.369 55.5721 + endloop + endfacet + facet normal -0.330749 -0.652919 0.681397 + outer loop + vertex 845.644 251.369 55.5721 + vertex 843.807 251.297 54.611 + vertex 845.096 250.269 54.2516 + endloop + endfacet + facet normal -0.183561 -0.716336 0.673178 + outer loop + vertex 845.644 251.369 55.5721 + vertex 845.096 250.269 54.2516 + vertex 847.002 250.745 55.2784 + endloop + endfacet + facet normal -0.183062 -0.71703 0.672574 + outer loop + vertex 847.002 250.745 55.2784 + vertex 845.096 250.269 54.2516 + vertex 846.452 249.581 53.8871 + endloop + endfacet + facet normal -0.168501 -0.699782 0.694199 + outer loop + vertex 845.096 250.269 54.2516 + vertex 844.517 249.165 52.9986 + vertex 846.452 249.581 53.8871 + endloop + endfacet + facet normal -0.169292 -0.698482 0.695315 + outer loop + vertex 846.452 249.581 53.8871 + vertex 844.517 249.165 52.9986 + vertex 845.902 248.366 52.5329 + endloop + endfacet + facet normal -0.352192 -0.666476 0.657092 + outer loop + vertex 844.872 253.429 57.2549 + vertex 844.354 252.36 55.8936 + vertex 846.15 252.458 56.9557 + endloop + endfacet + facet normal -0.350856 -0.669156 0.655081 + outer loop + vertex 846.15 252.458 56.9557 + vertex 844.354 252.36 55.8936 + vertex 845.644 251.369 55.5721 + endloop + endfacet + facet normal -0.372932 -0.677588 0.633873 + outer loop + vertex 845.362 254.494 58.6815 + vertex 844.872 253.429 57.2549 + vertex 846.622 253.537 58.3998 + endloop + endfacet + facet normal -0.37038 -0.682204 0.63041 + outer loop + vertex 846.622 253.537 58.3998 + vertex 844.872 253.429 57.2549 + vertex 846.15 252.458 56.9557 + endloop + endfacet + facet normal -0.211991 -0.748555 0.628272 + outer loop + vertex 846.622 253.537 58.3998 + vertex 846.15 252.458 56.9557 + vertex 847.963 252.977 58.185 + endloop + endfacet + facet normal -0.209377 -0.75148 0.62565 + outer loop + vertex 847.963 252.977 58.185 + vertex 846.15 252.458 56.9557 + vertex 847.504 251.877 56.71 + endloop + endfacet + facet normal -0.19744 -0.733939 0.649885 + outer loop + vertex 846.15 252.458 56.9557 + vertex 845.644 251.369 55.5721 + vertex 847.504 251.877 56.71 + endloop + endfacet + facet normal -0.19702 -0.734455 0.649429 + outer loop + vertex 847.504 251.877 56.71 + vertex 845.644 251.369 55.5721 + vertex 847.002 250.745 55.2784 + endloop + endfacet + facet normal -0.0818674 -0.767804 0.635432 + outer loop + vertex 847.504 251.877 56.71 + vertex 847.002 250.745 55.2784 + vertex 848.716 251.499 56.4104 + endloop + endfacet + facet normal -0.0826374 -0.767129 0.636148 + outer loop + vertex 848.716 251.499 56.4104 + vertex 847.002 250.745 55.2784 + vertex 848.207 250.31 54.91 + endloop + endfacet + facet normal -0.0916568 -0.78435 0.61351 + outer loop + vertex 847.963 252.977 58.185 + vertex 847.504 251.877 56.71 + vertex 849.174 252.647 57.9443 + endloop + endfacet + facet normal -0.0921917 -0.783927 0.61397 + outer loop + vertex 849.174 252.647 57.9443 + vertex 847.504 251.877 56.71 + vertex 848.716 251.499 56.4104 + endloop + endfacet + facet normal -0.0170843 -0.798181 0.602176 + outer loop + vertex 849.174 252.647 57.9443 + vertex 848.716 251.499 56.4104 + vertex 849.909 252.311 57.52 + endloop + endfacet + facet normal -0.0245926 -0.794113 0.607272 + outer loop + vertex 849.909 252.311 57.52 + vertex 848.716 251.499 56.4104 + vertex 849.551 251.12 55.9477 + endloop + endfacet + facet normal -0.0101753 -0.781925 0.623289 + outer loop + vertex 848.716 251.499 56.4104 + vertex 848.207 250.31 54.91 + vertex 849.551 251.12 55.9477 + endloop + endfacet + facet normal -0.0129867 -0.780107 0.625512 + outer loop + vertex 849.551 251.12 55.9477 + vertex 848.207 250.31 54.91 + vertex 848.942 249.863 54.3672 + endloop + endfacet + facet normal -0.0565629 -0.731693 0.679284 + outer loop + vertex 846.452 249.581 53.8871 + vertex 845.902 248.366 52.5329 + vertex 847.689 249.081 53.452 + endloop + endfacet + facet normal -0.0546353 -0.733794 0.677171 + outer loop + vertex 847.689 249.081 53.452 + vertex 845.902 248.366 52.5329 + vertex 847.225 247.783 52.0079 + endloop + endfacet + facet normal -0.0705741 -0.750992 0.656528 + outer loop + vertex 847.002 250.745 55.2784 + vertex 846.452 249.581 53.8871 + vertex 848.207 250.31 54.91 + endloop + endfacet + facet normal -0.0715961 -0.749988 0.657565 + outer loop + vertex 848.207 250.31 54.91 + vertex 846.452 249.581 53.8871 + vertex 847.689 249.081 53.452 + endloop + endfacet + facet normal 0.00828496 -0.766047 0.642731 + outer loop + vertex 848.207 250.31 54.91 + vertex 847.689 249.081 53.452 + vertex 848.942 249.863 54.3672 + endloop + endfacet + facet normal 0.0114214 -0.768119 0.640205 + outer loop + vertex 848.942 249.863 54.3672 + vertex 847.689 249.081 53.452 + vertex 848.627 248.738 53.0231 + endloop + endfacet + facet normal 0.0292204 -0.748016 0.663038 + outer loop + vertex 847.689 249.081 53.452 + vertex 847.225 247.783 52.0079 + vertex 848.627 248.738 53.0231 + endloop + endfacet + facet normal 0.0445109 -0.757724 0.651055 + outer loop + vertex 848.627 248.738 53.0231 + vertex 847.225 247.783 52.0079 + vertex 848.227 247.681 51.8203 + endloop + endfacet + facet normal -0.67393 -0.377592 0.635015 + outer loop + vertex 841.238 253.504 54.3202 + vertex 841.589 254.829 55.4804 + vertex 839.669 256.258 54.2926 + endloop + endfacet + facet normal -0.688383 -0.376159 0.620188 + outer loop + vertex 842.349 255.548 56.7601 + vertex 840.747 258.135 56.5515 + vertex 841.589 254.829 55.4804 + endloop + endfacet + facet normal -0.673872 -0.377337 0.635227 + outer loop + vertex 840.747 258.135 56.5515 + vertex 839.669 256.258 54.2926 + vertex 841.589 254.829 55.4804 + endloop + endfacet + facet normal -0.713736 -0.395234 0.578249 + outer loop + vertex 842.349 255.548 56.7601 + vertex 842.67 256.886 58.0711 + vertex 840.747 258.135 56.5515 + endloop + endfacet + facet normal -0.733574 -0.386046 0.559318 + outer loop + vertex 843.384 257.606 59.505 + vertex 841.802 260.126 59.1687 + vertex 842.67 256.886 58.0711 + endloop + endfacet + facet normal -0.71335 -0.388696 0.583135 + outer loop + vertex 841.802 260.126 59.1687 + vertex 840.747 258.135 56.5515 + vertex 842.67 256.886 58.0711 + endloop + endfacet + facet normal -0.624635 -0.464865 0.62748 + outer loop + vertex 842.67 256.886 58.0711 + vertex 842.349 255.548 56.7601 + vertex 843.749 254.85 57.6368 + endloop + endfacet + facet normal -0.62482 -0.476856 0.61823 + outer loop + vertex 843.749 254.85 57.6368 + vertex 842.349 255.548 56.7601 + vertex 843.219 253.795 56.2877 + endloop + endfacet + facet normal -0.659525 -0.486644 0.572892 + outer loop + vertex 843.384 257.606 59.505 + vertex 842.67 256.886 58.0711 + vertex 844.25 255.896 59.0491 + endloop + endfacet + facet normal -0.658668 -0.473747 0.584568 + outer loop + vertex 844.25 255.896 59.0491 + vertex 842.67 256.886 58.0711 + vertex 843.749 254.85 57.6368 + endloop + endfacet + facet normal -0.52884 -0.581482 0.618228 + outer loop + vertex 844.25 255.896 59.0491 + vertex 843.749 254.85 57.6368 + vertex 845.362 254.494 58.6815 + endloop + endfacet + facet normal -0.528366 -0.583373 0.616851 + outer loop + vertex 845.362 254.494 58.6815 + vertex 843.749 254.85 57.6368 + vertex 844.872 253.429 57.2549 + endloop + endfacet + facet normal -0.504795 -0.572578 0.646016 + outer loop + vertex 843.749 254.85 57.6368 + vertex 843.219 253.795 56.2877 + vertex 844.872 253.429 57.2549 + endloop + endfacet + facet normal -0.50415 -0.57572 0.643723 + outer loop + vertex 844.872 253.429 57.2549 + vertex 843.219 253.795 56.2877 + vertex 844.354 252.36 55.8936 + endloop + endfacet + facet normal -0.572592 -0.449025 0.685941 + outer loop + vertex 841.589 254.829 55.4804 + vertex 841.238 253.504 54.3202 + vertex 842.668 252.742 55.0149 + endloop + endfacet + facet normal -0.574114 -0.459273 0.677836 + outer loop + vertex 842.668 252.742 55.0149 + vertex 841.238 253.504 54.3202 + vertex 842.102 251.722 53.845 + endloop + endfacet + facet normal -0.613489 -0.474698 0.631105 + outer loop + vertex 842.349 255.548 56.7601 + vertex 841.589 254.829 55.4804 + vertex 843.219 253.795 56.2877 + endloop + endfacet + facet normal -0.610701 -0.459563 0.644861 + outer loop + vertex 843.219 253.795 56.2877 + vertex 841.589 254.829 55.4804 + vertex 842.668 252.742 55.0149 + endloop + endfacet + facet normal -0.478386 -0.563517 0.673495 + outer loop + vertex 843.219 253.795 56.2877 + vertex 842.668 252.742 55.0149 + vertex 844.354 252.36 55.8936 + endloop + endfacet + facet normal -0.478163 -0.564968 0.672437 + outer loop + vertex 844.354 252.36 55.8936 + vertex 842.668 252.742 55.0149 + vertex 843.807 251.297 54.611 + endloop + endfacet + facet normal -0.452376 -0.552387 0.70016 + outer loop + vertex 842.668 252.742 55.0149 + vertex 842.102 251.722 53.845 + vertex 843.807 251.297 54.611 + endloop + endfacet + facet normal -0.452518 -0.550631 0.70145 + outer loop + vertex 843.807 251.297 54.611 + vertex 842.102 251.722 53.845 + vertex 843.233 250.246 53.416 + endloop + endfacet + facet normal -0.786904 -0.257842 0.560624 + outer loop + vertex 838.317 268.214 58.2946 + vertex 837.56 265.74 56.095 + vertex 839.406 263.019 57.4344 + endloop + endfacet + facet normal -0.78534 -0.255085 0.564068 + outer loop + vertex 839.406 263.019 57.4344 + vertex 837.56 265.74 56.095 + vertex 838.363 261.28 55.1947 + endloop + endfacet + facet normal -0.822477 -0.266866 0.502309 + outer loop + vertex 839.472 269.486 60.8625 + vertex 838.317 268.214 58.2946 + vertex 840.433 264.967 60.0347 + endloop + endfacet + facet normal -0.817657 -0.256781 0.515267 + outer loop + vertex 840.433 264.967 60.0347 + vertex 838.317 268.214 58.2946 + vertex 839.406 263.019 57.4344 + endloop + endfacet + facet normal -0.776807 -0.316926 0.544178 + outer loop + vertex 840.433 264.967 60.0347 + vertex 839.406 263.019 57.4344 + vertex 841.802 260.126 59.1687 + endloop + endfacet + facet normal -0.774911 -0.312072 0.549658 + outer loop + vertex 841.802 260.126 59.1687 + vertex 839.406 263.019 57.4344 + vertex 840.747 258.135 56.5515 + endloop + endfacet + facet normal -0.745686 -0.31119 0.589163 + outer loop + vertex 839.406 263.019 57.4344 + vertex 838.363 261.28 55.1947 + vertex 840.747 258.135 56.5515 + endloop + endfacet + facet normal -0.739284 -0.300534 0.60261 + outer loop + vertex 840.747 258.135 56.5515 + vertex 838.363 261.28 55.1947 + vertex 839.669 256.258 54.2926 + endloop + endfacet + facet normal -0.822366 -0.216393 0.526202 + outer loop + vertex 837.56 265.74 56.095 + vertex 838.317 268.214 58.2946 + vertex 836.31 270.931 56.2752 + endloop + endfacet + facet normal -0.843595 -0.221318 0.489249 + outer loop + vertex 839.472 269.486 60.8625 + vertex 837.6 274.838 60.0558 + vertex 838.317 268.214 58.2946 + endloop + endfacet + facet normal -0.826001 -0.226563 0.516131 + outer loop + vertex 837.6 274.838 60.0558 + vertex 836.31 270.931 56.2752 + vertex 838.317 268.214 58.2946 + endloop + endfacet + facet normal -0.856986 -0.191714 0.478351 + outer loop + vertex 835.889 284.17 60.7303 + vertex 834.697 279.187 56.5964 + vertex 837.6 274.838 60.0558 + endloop + endfacet + facet normal -0.855069 -0.185909 0.48404 + outer loop + vertex 837.6 274.838 60.0558 + vertex 834.697 279.187 56.5964 + vertex 836.31 270.931 56.2752 + endloop + endfacet + facet normal -0.86791 -0.181088 0.462535 + outer loop + vertex 834.2 293.291 61.1309 + vertex 832.508 289.696 56.5496 + vertex 835.889 284.17 60.7303 + endloop + endfacet + facet normal -0.866995 -0.178462 0.465265 + outer loop + vertex 835.889 284.17 60.7303 + vertex 832.508 289.696 56.5496 + vertex 834.697 279.187 56.5964 + endloop + endfacet + facet normal -0.871309 -0.200623 0.447852 + outer loop + vertex 832.275 301.744 61.1726 + vertex 831.237 298.102 57.5227 + vertex 834.2 293.291 61.1309 + endloop + endfacet + facet normal -0.865994 -0.184727 0.464683 + outer loop + vertex 834.2 293.291 61.1309 + vertex 831.237 298.102 57.5227 + vertex 832.508 289.696 56.5496 + endloop + endfacet + facet normal -0.852277 -0.230726 0.469456 + outer loop + vertex 829.927 310.016 60.9752 + vertex 828.416 306.454 56.4819 + vertex 832.275 301.744 61.1726 + endloop + endfacet + facet normal -0.851965 -0.229127 0.470804 + outer loop + vertex 832.275 301.744 61.1726 + vertex 828.416 306.454 56.4819 + vertex 831.237 298.102 57.5227 + endloop + endfacet + facet normal -0.841191 -0.264727 0.471506 + outer loop + vertex 827.412 318.026 60.9858 + vertex 825.794 315.659 56.7705 + vertex 829.927 310.016 60.9752 + endloop + endfacet + facet normal -0.838021 -0.253847 0.482993 + outer loop + vertex 829.927 310.016 60.9752 + vertex 825.794 315.659 56.7705 + vertex 828.416 306.454 56.4819 + endloop + endfacet + facet normal -0.833615 -0.296939 0.46574 + outer loop + vertex 824.859 325.388 61.1096 + vertex 823.178 323.637 56.9852 + vertex 827.412 318.026 60.9858 + endloop + endfacet + facet normal -0.830326 -0.285145 0.478801 + outer loop + vertex 827.412 318.026 60.9858 + vertex 823.178 323.637 56.9852 + vertex 825.794 315.659 56.7705 + endloop + endfacet + facet normal -0.831192 -0.331683 0.446214 + outer loop + vertex 822.066 332.393 61.1145 + vertex 821.23 329.773 57.6087 + vertex 824.859 325.388 61.1096 + endloop + endfacet + facet normal -0.827054 -0.31028 0.46873 + outer loop + vertex 824.859 325.388 61.1096 + vertex 821.23 329.773 57.6087 + vertex 823.178 323.637 56.9852 + endloop + endfacet + facet normal -0.819113 -0.358105 0.448124 + outer loop + vertex 818.814 339.678 60.9918 + vertex 818.156 336.209 57.0159 + vertex 822.066 332.393 61.1145 + endloop + endfacet + facet normal -0.818621 -0.348985 0.456145 + outer loop + vertex 822.066 332.393 61.1145 + vertex 818.156 336.209 57.0159 + vertex 821.23 329.773 57.6087 + endloop + endfacet + facet normal -0.815786 -0.375417 0.439949 + outer loop + vertex 815.227 347.38 60.9117 + vertex 814.474 344.151 56.7604 + vertex 818.814 339.678 60.9918 + endloop + endfacet + facet normal -0.814807 -0.363201 0.451857 + outer loop + vertex 818.814 339.678 60.9918 + vertex 814.474 344.151 56.7604 + vertex 818.156 336.209 57.0159 + endloop + endfacet + facet normal -0.816241 -0.388874 0.427233 + outer loop + vertex 811.741 354.832 61.0357 + vertex 810.146 353.102 56.4125 + vertex 815.227 347.38 60.9117 + endloop + endfacet + facet normal -0.814676 -0.376799 0.440823 + outer loop + vertex 815.227 347.38 60.9117 + vertex 810.146 353.102 56.4125 + vertex 814.474 344.151 56.7604 + endloop + endfacet + facet normal -0.823615 -0.404591 0.397447 + outer loop + vertex 808.335 361.82 61.0915 + vertex 807.588 359.799 57.4864 + vertex 811.741 354.832 61.0357 + endloop + endfacet + facet normal -0.820378 -0.381541 0.425917 + outer loop + vertex 811.741 354.832 61.0357 + vertex 807.588 359.799 57.4864 + vertex 810.146 353.102 56.4125 + endloop + endfacet + facet normal -0.825406 -0.413387 0.384468 + outer loop + vertex 804.705 368.964 60.9798 + vertex 804.103 366.462 56.9975 + vertex 808.335 361.82 61.0915 + endloop + endfacet + facet normal -0.825096 -0.402447 0.396551 + outer loop + vertex 808.335 361.82 61.0915 + vertex 804.103 366.462 56.9975 + vertex 807.588 359.799 57.4864 + endloop + endfacet + facet normal -0.840523 -0.393094 0.372824 + outer loop + vertex 801.069 376.705 60.9438 + vertex 800.283 374.516 56.863 + vertex 804.705 368.964 60.9798 + endloop + endfacet + facet normal -0.840468 -0.392471 0.373605 + outer loop + vertex 804.705 368.964 60.9798 + vertex 800.283 374.516 56.863 + vertex 804.103 366.462 56.9975 + endloop + endfacet + facet normal -0.875753 -0.308354 0.371449 + outer loop + vertex 798.325 384.627 61.051 + vertex 796.267 384.707 56.2643 + vertex 801.069 376.705 60.9438 + endloop + endfacet + facet normal -0.880063 -0.326554 0.344749 + outer loop + vertex 801.069 376.705 60.9438 + vertex 796.267 384.707 56.2643 + vertex 800.283 374.516 56.863 + endloop + endfacet + facet normal 0.15027 -0.701275 0.696873 + outer loop + vertex 846.829 244.111 48.2047 + vertex 846.724 243.612 47.7254 + vertex 847.446 244.309 48.2712 + endloop + endfacet + facet normal 0.154868 -0.696746 0.700401 + outer loop + vertex 846.526 243.244 47.403 + vertex 847 243.43 47.4828 + vertex 846.724 243.612 47.7254 + endloop + endfacet + facet normal 0.149501 -0.700901 0.697415 + outer loop + vertex 847 243.43 47.4828 + vertex 847.446 244.309 48.2712 + vertex 846.724 243.612 47.7254 + endloop + endfacet + facet normal 0.132286 -0.71387 0.68767 + outer loop + vertex 847.421 245.378 49.3871 + vertex 847.2 244.757 48.7855 + vertex 847.999 245.561 49.4668 + endloop + endfacet + facet normal 0.153176 -0.707864 0.68954 + outer loop + vertex 846.829 244.111 48.2047 + vertex 847.446 244.309 48.2712 + vertex 847.2 244.757 48.7855 + endloop + endfacet + facet normal 0.134217 -0.714721 0.686411 + outer loop + vertex 847.446 244.309 48.2712 + vertex 847.999 245.561 49.4668 + vertex 847.2 244.757 48.7855 + endloop + endfacet + facet normal 0.112731 -0.711796 0.693281 + outer loop + vertex 847.999 245.561 49.4668 + vertex 847.446 244.309 48.2712 + vertex 848.021 245.05 48.9381 + endloop + endfacet + facet normal 0.113784 -0.71214 0.692755 + outer loop + vertex 848.021 245.05 48.9381 + vertex 847.446 244.309 48.2712 + vertex 847.536 243.959 47.8967 + endloop + endfacet + facet normal 0.158001 -0.702283 0.694143 + outer loop + vertex 847.446 244.309 48.2712 + vertex 847 243.43 47.4828 + vertex 847.536 243.959 47.8967 + endloop + endfacet + facet normal 0.136598 -0.692064 0.708793 + outer loop + vertex 847.536 243.959 47.8967 + vertex 847 243.43 47.4828 + vertex 847.269 243.485 47.4846 + endloop + endfacet + facet normal 0.134471 -0.744923 0.653458 + outer loop + vertex 848.192 246.968 51.0032 + vertex 847.854 246.092 50.0751 + vertex 848.588 246.844 50.7807 + endloop + endfacet + facet normal 0.139632 -0.729239 0.669861 + outer loop + vertex 847.421 245.378 49.3871 + vertex 847.999 245.561 49.4668 + vertex 847.854 246.092 50.0751 + endloop + endfacet + facet normal 0.110485 -0.735542 0.668409 + outer loop + vertex 847.999 245.561 49.4668 + vertex 848.588 246.844 50.7807 + vertex 847.854 246.092 50.0751 + endloop + endfacet + facet normal 0.0813433 -0.752643 0.653385 + outer loop + vertex 848.227 247.681 51.8203 + vertex 848.192 246.968 51.0032 + vertex 848.913 248.025 52.1311 + endloop + endfacet + facet normal 0.120008 -0.761484 0.636977 + outer loop + vertex 848.913 248.025 52.1311 + vertex 848.192 246.968 51.0032 + vertex 848.588 246.844 50.7807 + endloop + endfacet + facet normal 0.0581492 -0.758414 0.649174 + outer loop + vertex 848.913 248.025 52.1311 + vertex 848.588 246.844 50.7807 + vertex 849.094 247.752 51.7966 + endloop + endfacet + facet normal -0.022788 -0.739594 0.672667 + outer loop + vertex 849.094 247.752 51.7966 + vertex 848.588 246.844 50.7807 + vertex 848.561 246.35 50.2364 + endloop + endfacet + facet normal 0.125743 -0.737525 0.66351 + outer loop + vertex 848.588 246.844 50.7807 + vertex 847.999 245.561 49.4668 + vertex 848.561 246.35 50.2364 + endloop + endfacet + facet normal 0.0526931 -0.71664 0.69545 + outer loop + vertex 848.561 246.35 50.2364 + vertex 847.999 245.561 49.4668 + vertex 848.021 245.05 48.9381 + endloop + endfacet + facet normal -0.24162 -0.5805 0.777586 + outer loop + vertex 841.572 247.469 50.5647 + vertex 841.197 246.891 50.0167 + vertex 842.835 246.156 49.9768 + endloop + endfacet + facet normal -0.231699 -0.55939 0.795863 + outer loop + vertex 842.835 246.156 49.9768 + vertex 841.197 246.891 50.0167 + vertex 842.415 245.554 49.4314 + endloop + endfacet + facet normal -0.244839 -0.593842 0.766424 + outer loop + vertex 842.076 248.275 51.3499 + vertex 841.572 247.469 50.5647 + vertex 843.369 247.022 50.7921 + endloop + endfacet + facet normal -0.243007 -0.581354 0.776514 + outer loop + vertex 843.369 247.022 50.7921 + vertex 841.572 247.469 50.5647 + vertex 842.835 246.156 49.9768 + endloop + endfacet + facet normal -0.112668 -0.643467 0.757136 + outer loop + vertex 843.369 247.022 50.7921 + vertex 842.835 246.156 49.9768 + vertex 844.832 245.991 50.1339 + endloop + endfacet + facet normal -0.112543 -0.635696 0.763691 + outer loop + vertex 844.832 245.991 50.1339 + vertex 842.835 246.156 49.9768 + vertex 844.244 245.067 49.2783 + endloop + endfacet + facet normal -0.102365 -0.627674 0.771717 + outer loop + vertex 842.835 246.156 49.9768 + vertex 842.415 245.554 49.4314 + vertex 844.244 245.067 49.2783 + endloop + endfacet + facet normal -0.0948566 -0.605309 0.790319 + outer loop + vertex 844.244 245.067 49.2783 + vertex 842.415 245.554 49.4314 + vertex 843.638 244.518 48.7845 + endloop + endfacet + facet normal -0.262303 -0.606968 0.750192 + outer loop + vertex 842.646 249.226 52.3193 + vertex 842.076 248.275 51.3499 + vertex 843.939 248.055 51.8239 + endloop + endfacet + facet normal -0.262434 -0.605335 0.751464 + outer loop + vertex 843.939 248.055 51.8239 + vertex 842.076 248.275 51.3499 + vertex 843.369 247.022 50.7921 + endloop + endfacet + facet normal -0.285344 -0.620884 0.730125 + outer loop + vertex 843.233 250.246 53.416 + vertex 842.646 249.226 52.3193 + vertex 844.517 249.165 52.9986 + endloop + endfacet + facet normal -0.284881 -0.622792 0.728679 + outer loop + vertex 844.517 249.165 52.9986 + vertex 842.646 249.226 52.3193 + vertex 843.939 248.055 51.8239 + endloop + endfacet + facet normal -0.15138 -0.680209 0.717217 + outer loop + vertex 844.517 249.165 52.9986 + vertex 843.939 248.055 51.8239 + vertex 845.902 248.366 52.5329 + endloop + endfacet + facet normal -0.150158 -0.682828 0.714981 + outer loop + vertex 845.902 248.366 52.5329 + vertex 843.939 248.055 51.8239 + vertex 845.446 247.11 51.2378 + endloop + endfacet + facet normal -0.129773 -0.663741 0.736619 + outer loop + vertex 843.939 248.055 51.8239 + vertex 843.369 247.022 50.7921 + vertex 845.446 247.11 51.2378 + endloop + endfacet + facet normal -0.130874 -0.65887 0.740784 + outer loop + vertex 845.446 247.11 51.2378 + vertex 843.369 247.022 50.7921 + vertex 844.832 245.991 50.1339 + endloop + endfacet + facet normal -0.0214682 -0.708052 0.705834 + outer loop + vertex 846.218 245.802 49.9866 + vertex 846.313 246.404 50.593 + vertex 844.832 245.991 50.1339 + endloop + endfacet + facet normal -0.0462235 -0.703816 0.708877 + outer loop + vertex 846.639 246.961 51.1671 + vertex 845.446 247.11 51.2378 + vertex 846.313 246.404 50.593 + endloop + endfacet + facet normal -0.0298079 -0.693599 0.719744 + outer loop + vertex 845.446 247.11 51.2378 + vertex 844.832 245.991 50.1339 + vertex 846.313 246.404 50.593 + endloop + endfacet + facet normal -0.0348626 -0.711297 0.702026 + outer loop + vertex 845.902 248.366 52.5329 + vertex 845.446 247.11 51.2378 + vertex 847.225 247.783 52.0079 + endloop + endfacet + facet normal -0.0451905 -0.698217 0.714458 + outer loop + vertex 847.225 247.783 52.0079 + vertex 845.446 247.11 51.2378 + vertex 846.639 246.961 51.1671 + endloop + endfacet + facet normal 0.0466428 -0.730183 0.681658 + outer loop + vertex 846.639 246.961 51.1671 + vertex 847.397 246.943 51.0967 + vertex 847.225 247.783 52.0079 + endloop + endfacet + facet normal 0.0995539 -0.751779 0.651857 + outer loop + vertex 848.192 246.968 51.0032 + vertex 848.227 247.681 51.8203 + vertex 847.397 246.943 51.0967 + endloop + endfacet + facet normal 0.053225 -0.729317 0.682102 + outer loop + vertex 848.227 247.681 51.8203 + vertex 847.225 247.783 52.0079 + vertex 847.397 246.943 51.0967 + endloop + endfacet + facet normal 0.0589847 -0.713234 0.698439 + outer loop + vertex 846.313 246.404 50.593 + vertex 846.218 245.802 49.9866 + vertex 847.228 246.239 50.3471 + endloop + endfacet + facet normal 0.0648644 -0.720343 0.690578 + outer loop + vertex 847.228 246.239 50.3471 + vertex 846.218 245.802 49.9866 + vertex 846.907 245.573 49.6827 + endloop + endfacet + facet normal 0.0466472 -0.730147 0.681696 + outer loop + vertex 846.639 246.961 51.1671 + vertex 846.313 246.404 50.593 + vertex 847.397 246.943 51.0967 + endloop + endfacet + facet normal 0.0498973 -0.733297 0.678075 + outer loop + vertex 847.397 246.943 51.0967 + vertex 846.313 246.404 50.593 + vertex 847.228 246.239 50.3471 + endloop + endfacet + facet normal 0.101117 -0.736157 0.669215 + outer loop + vertex 847.397 246.943 51.0967 + vertex 847.228 246.239 50.3471 + vertex 848.192 246.968 51.0032 + endloop + endfacet + facet normal 0.112913 -0.743096 0.65959 + outer loop + vertex 848.192 246.968 51.0032 + vertex 847.228 246.239 50.3471 + vertex 847.854 246.092 50.0751 + endloop + endfacet + facet normal 0.121698 -0.729853 0.672684 + outer loop + vertex 847.228 246.239 50.3471 + vertex 846.907 245.573 49.6827 + vertex 847.854 246.092 50.0751 + endloop + endfacet + facet normal 0.115702 -0.724264 0.679746 + outer loop + vertex 847.854 246.092 50.0751 + vertex 846.907 245.573 49.6827 + vertex 847.421 245.378 49.3871 + endloop + endfacet + facet normal -0.00658935 -0.665606 0.746275 + outer loop + vertex 844.814 243.793 48.1487 + vertex 845.089 244.263 48.5706 + vertex 843.638 244.518 48.7845 + endloop + endfacet + facet normal -0.00113324 -0.661395 0.750037 + outer loop + vertex 845.592 244.692 48.949 + vertex 844.244 245.067 49.2783 + vertex 845.089 244.263 48.5706 + endloop + endfacet + facet normal -0.0062147 -0.664385 0.747365 + outer loop + vertex 844.244 245.067 49.2783 + vertex 843.638 244.518 48.7845 + vertex 845.089 244.263 48.5706 + endloop + endfacet + facet normal -0.00975171 -0.678629 0.734416 + outer loop + vertex 845.592 244.692 48.949 + vertex 845.73 245.257 49.4729 + vertex 844.244 245.067 49.2783 + endloop + endfacet + facet normal -0.0144115 -0.678546 0.734416 + outer loop + vertex 846.218 245.802 49.9866 + vertex 844.832 245.991 50.1339 + vertex 845.73 245.257 49.4729 + endloop + endfacet + facet normal -0.0104238 -0.675911 0.736909 + outer loop + vertex 844.832 245.991 50.1339 + vertex 844.244 245.067 49.2783 + vertex 845.73 245.257 49.4729 + endloop + endfacet + facet normal 0.0736482 -0.687767 0.722186 + outer loop + vertex 845.73 245.257 49.4729 + vertex 845.592 244.692 48.949 + vertex 846.586 244.955 49.099 + endloop + endfacet + facet normal 0.0768137 -0.695352 0.714553 + outer loop + vertex 846.586 244.955 49.099 + vertex 845.592 244.692 48.949 + vertex 846.276 244.364 48.5566 + endloop + endfacet + facet normal 0.0684378 -0.715626 0.695123 + outer loop + vertex 846.218 245.802 49.9866 + vertex 845.73 245.257 49.4729 + vertex 846.907 245.573 49.6827 + endloop + endfacet + facet normal 0.062528 -0.702678 0.708755 + outer loop + vertex 846.907 245.573 49.6827 + vertex 845.73 245.257 49.4729 + vertex 846.586 244.955 49.099 + endloop + endfacet + facet normal 0.123945 -0.71506 0.687988 + outer loop + vertex 846.907 245.573 49.6827 + vertex 846.586 244.955 49.099 + vertex 847.421 245.378 49.3871 + endloop + endfacet + facet normal 0.122013 -0.712957 0.690511 + outer loop + vertex 847.421 245.378 49.3871 + vertex 846.586 244.955 49.099 + vertex 847.2 244.757 48.7855 + endloop + endfacet + facet normal 0.127598 -0.705743 0.696883 + outer loop + vertex 846.586 244.955 49.099 + vertex 846.276 244.364 48.5566 + vertex 847.2 244.757 48.7855 + endloop + endfacet + facet normal 0.124986 -0.702046 0.701078 + outer loop + vertex 847.2 244.757 48.7855 + vertex 846.276 244.364 48.5566 + vertex 846.829 244.111 48.2047 + endloop + endfacet + facet normal 0.0703127 -0.688526 0.721795 + outer loop + vertex 845.089 244.263 48.5706 + vertex 844.814 243.793 48.1487 + vertex 845.998 243.817 48.0559 + endloop + endfacet + facet normal 0.0701011 -0.692377 0.718123 + outer loop + vertex 845.998 243.817 48.0559 + vertex 844.814 243.793 48.1487 + vertex 845.886 243.374 47.6396 + endloop + endfacet + facet normal 0.0680053 -0.704285 0.706653 + outer loop + vertex 845.592 244.692 48.949 + vertex 845.089 244.263 48.5706 + vertex 846.276 244.364 48.5566 + endloop + endfacet + facet normal 0.067094 -0.691807 0.718959 + outer loop + vertex 846.276 244.364 48.5566 + vertex 845.089 244.263 48.5706 + vertex 845.998 243.817 48.0559 + endloop + endfacet + facet normal 0.123755 -0.703295 0.700043 + outer loop + vertex 846.276 244.364 48.5566 + vertex 845.998 243.817 48.0559 + vertex 846.829 244.111 48.2047 + endloop + endfacet + facet normal 0.122462 -0.700948 0.70262 + outer loop + vertex 846.829 244.111 48.2047 + vertex 845.998 243.817 48.0559 + vertex 846.724 243.612 47.7254 + endloop + endfacet + facet normal 0.125849 -0.695955 0.706972 + outer loop + vertex 845.998 243.817 48.0559 + vertex 845.886 243.374 47.6396 + vertex 846.724 243.612 47.7254 + endloop + endfacet + facet normal 0.12378 -0.690678 0.71249 + outer loop + vertex 846.724 243.612 47.7254 + vertex 845.886 243.374 47.6396 + vertex 846.526 243.244 47.403 + endloop + endfacet + facet normal -0.61782 -0.332646 0.712492 + outer loop + vertex 839.277 250.428 51.0172 + vertex 839.491 251.37 51.643 + vertex 838.005 253.756 51.4686 + endloop + endfacet + facet normal -0.605523 -0.338184 0.720399 + outer loop + vertex 840.147 251.701 52.3498 + vertex 838.698 254.735 52.5557 + vertex 839.491 251.37 51.643 + endloop + endfacet + facet normal -0.625632 -0.338205 0.702995 + outer loop + vertex 838.698 254.735 52.5557 + vertex 838.005 253.756 51.4686 + vertex 839.491 251.37 51.643 + endloop + endfacet + facet normal -0.640052 -0.352134 0.682887 + outer loop + vertex 840.147 251.701 52.3498 + vertex 840.483 252.902 53.2843 + vertex 838.698 254.735 52.5557 + endloop + endfacet + facet normal -0.642511 -0.359272 0.676834 + outer loop + vertex 841.238 253.504 54.3202 + vertex 839.669 256.258 54.2926 + vertex 840.483 252.902 53.2843 + endloop + endfacet + facet normal -0.644201 -0.359209 0.675259 + outer loop + vertex 839.669 256.258 54.2926 + vertex 838.698 254.735 52.5557 + vertex 840.483 252.902 53.2843 + endloop + endfacet + facet normal -0.523835 -0.426855 0.737151 + outer loop + vertex 840.483 252.902 53.2843 + vertex 840.147 251.701 52.3498 + vertex 841.532 250.754 52.786 + endloop + endfacet + facet normal -0.527209 -0.435156 0.729857 + outer loop + vertex 841.532 250.754 52.786 + vertex 840.147 251.701 52.3498 + vertex 840.98 249.869 51.8599 + endloop + endfacet + facet normal -0.570182 -0.458405 0.681731 + outer loop + vertex 841.238 253.504 54.3202 + vertex 840.483 252.902 53.2843 + vertex 842.102 251.722 53.845 + endloop + endfacet + facet normal -0.561892 -0.437321 0.702159 + outer loop + vertex 842.102 251.722 53.845 + vertex 840.483 252.902 53.2843 + vertex 841.532 250.754 52.786 + endloop + endfacet + facet normal -0.429408 -0.539544 0.724225 + outer loop + vertex 842.102 251.722 53.845 + vertex 841.532 250.754 52.786 + vertex 843.233 250.246 53.416 + endloop + endfacet + facet normal -0.429322 -0.535257 0.727449 + outer loop + vertex 843.233 250.246 53.416 + vertex 841.532 250.754 52.786 + vertex 842.646 249.226 52.3193 + endloop + endfacet + facet normal -0.408691 -0.52586 0.745951 + outer loop + vertex 841.532 250.754 52.786 + vertex 840.98 249.869 51.8599 + vertex 842.646 249.226 52.3193 + endloop + endfacet + facet normal -0.407724 -0.520106 0.750501 + outer loop + vertex 842.646 249.226 52.3193 + vertex 840.98 249.869 51.8599 + vertex 842.076 248.275 51.3499 + endloop + endfacet + facet normal -0.487071 -0.403595 0.774514 + outer loop + vertex 839.491 251.37 51.643 + vertex 839.277 250.428 51.0172 + vertex 840.488 249.116 51.0953 + endloop + endfacet + facet normal -0.500494 -0.416929 0.758733 + outer loop + vertex 840.488 249.116 51.0953 + vertex 839.277 250.428 51.0172 + vertex 840.112 248.561 50.5422 + endloop + endfacet + facet normal -0.546459 -0.439394 0.712962 + outer loop + vertex 840.147 251.701 52.3498 + vertex 839.491 251.37 51.643 + vertex 840.98 249.869 51.8599 + endloop + endfacet + facet normal -0.524333 -0.412837 0.744742 + outer loop + vertex 840.98 249.869 51.8599 + vertex 839.491 251.37 51.643 + vertex 840.488 249.116 51.0953 + endloop + endfacet + facet normal -0.394553 -0.514515 0.761316 + outer loop + vertex 840.98 249.869 51.8599 + vertex 840.488 249.116 51.0953 + vertex 842.076 248.275 51.3499 + endloop + endfacet + facet normal -0.390934 -0.505254 0.769343 + outer loop + vertex 842.076 248.275 51.3499 + vertex 840.488 249.116 51.0953 + vertex 841.572 247.469 50.5647 + endloop + endfacet + facet normal -0.389018 -0.50447 0.770827 + outer loop + vertex 840.488 249.116 51.0953 + vertex 840.112 248.561 50.5422 + vertex 841.572 247.469 50.5647 + endloop + endfacet + facet normal -0.381157 -0.493733 0.781631 + outer loop + vertex 841.572 247.469 50.5647 + vertex 840.112 248.561 50.5422 + vertex 841.197 246.891 50.0167 + endloop + endfacet + facet normal -0.751239 -0.237247 0.615916 + outer loop + vertex 836.411 265.502 54.3729 + vertex 835.782 263.946 53.0064 + vertex 837.402 259.903 53.4252 + endloop + endfacet + facet normal -0.736527 -0.229232 0.636381 + outer loop + vertex 837.402 259.903 53.4252 + vertex 835.782 263.946 53.0064 + vertex 836.685 258.959 52.2548 + endloop + endfacet + facet normal -0.787676 -0.254866 0.560901 + outer loop + vertex 837.56 265.74 56.095 + vertex 836.411 265.502 54.3729 + vertex 838.363 261.28 55.1947 + endloop + endfacet + facet normal -0.764754 -0.236814 0.599224 + outer loop + vertex 838.363 261.28 55.1947 + vertex 836.411 265.502 54.3729 + vertex 837.402 259.903 53.4252 + endloop + endfacet + facet normal -0.721165 -0.299762 0.624551 + outer loop + vertex 838.363 261.28 55.1947 + vertex 837.402 259.903 53.4252 + vertex 839.669 256.258 54.2926 + endloop + endfacet + facet normal -0.707379 -0.285993 0.646392 + outer loop + vertex 839.669 256.258 54.2926 + vertex 837.402 259.903 53.4252 + vertex 838.698 254.735 52.5557 + endloop + endfacet + facet normal -0.697267 -0.28534 0.657571 + outer loop + vertex 837.402 259.903 53.4252 + vertex 836.685 258.959 52.2548 + vertex 838.698 254.735 52.5557 + endloop + endfacet + facet normal -0.679242 -0.275127 0.680394 + outer loop + vertex 838.698 254.735 52.5557 + vertex 836.685 258.959 52.2548 + vertex 838.005 253.756 51.4686 + endloop + endfacet + facet normal 0.117547 -0.646059 0.754182 + outer loop + vertex 845.714 242.989 47.3039 + vertex 845.786 242.895 47.2123 + vertex 846.66 243.089 47.2424 + endloop + endfacet + facet normal 0.117093 -0.64591 0.754381 + outer loop + vertex 845.588 242.845 47.2006 + vertex 846.468 242.803 47.0284 + vertex 845.786 242.895 47.2123 + endloop + endfacet + facet normal 0.117334 -0.64522 0.754933 + outer loop + vertex 846.468 242.803 47.0284 + vertex 846.66 243.089 47.2424 + vertex 845.786 242.895 47.2123 + endloop + endfacet + facet normal -0.0980317 0.593878 -0.79856 + outer loop + vertex 846.526 243.244 47.403 + vertex 846.011 243.123 47.3761 + vertex 847 243.43 47.4828 + endloop + endfacet + facet normal 0.12857 -0.653972 0.745514 + outer loop + vertex 847.269 243.485 47.4846 + vertex 847 243.43 47.4828 + vertex 846.66 243.089 47.2424 + endloop + endfacet + facet normal 0.118206 -0.659553 0.742306 + outer loop + vertex 845.714 242.989 47.3039 + vertex 846.66 243.089 47.2424 + vertex 846.011 243.123 47.3761 + endloop + endfacet + facet normal 0.120458 -0.649555 0.750712 + outer loop + vertex 847 243.43 47.4828 + vertex 846.011 243.123 47.3761 + vertex 846.66 243.089 47.2424 + endloop + endfacet + facet normal -0.768415 -0.514459 -0.380618 + outer loop + vertex 840.861 246.426 49.5579 + vertex 840.81 246.496 49.5659 + vertex 842.095 245.032 48.9511 + endloop + endfacet + facet normal -0.708341 -0.687937 0.158098 + outer loop + vertex 842.095 245.032 48.9511 + vertex 840.81 246.496 49.5659 + vertex 842.052 245.074 48.9439 + endloop + endfacet + facet normal -0.631488 -0.702968 0.327198 + outer loop + vertex 840.89 246.41 49.5778 + vertex 840.861 246.426 49.5579 + vertex 842.11 245.04 48.9891 + endloop + endfacet + facet normal -0.606783 -0.700555 0.375548 + outer loop + vertex 842.11 245.04 48.9891 + vertex 840.861 246.426 49.5579 + vertex 842.095 245.032 48.9511 + endloop + endfacet + facet normal -0.460249 -0.818962 0.342742 + outer loop + vertex 842.11 245.04 48.9891 + vertex 842.095 245.032 48.9511 + vertex 843.442 244.015 48.3309 + endloop + endfacet + facet normal -0.397694 -0.800509 0.448358 + outer loop + vertex 843.442 244.015 48.3309 + vertex 842.095 245.032 48.9511 + vertex 843.439 243.986 48.2763 + endloop + endfacet + facet normal -0.666238 -0.710976 -0.225033 + outer loop + vertex 842.095 245.032 48.9511 + vertex 842.052 245.074 48.9439 + vertex 843.439 243.986 48.2763 + endloop + endfacet + facet normal -0.440527 -0.805133 0.397109 + outer loop + vertex 843.439 243.986 48.2763 + vertex 842.052 245.074 48.9439 + vertex 843.405 243.994 48.2543 + endloop + endfacet + facet normal -0.279605 -0.580525 0.76473 + outer loop + vertex 840.969 246.534 49.7015 + vertex 840.89 246.41 49.5778 + vertex 842.173 245.196 49.1259 + endloop + endfacet + facet normal -0.266265 -0.570862 0.776673 + outer loop + vertex 842.173 245.196 49.1259 + vertex 840.89 246.41 49.5778 + vertex 842.11 245.04 48.9891 + endloop + endfacet + facet normal -0.229431 -0.558029 0.797474 + outer loop + vertex 841.197 246.891 50.0167 + vertex 840.969 246.534 49.7015 + vertex 842.415 245.554 49.4314 + endloop + endfacet + facet normal -0.217898 -0.544467 0.809985 + outer loop + vertex 842.415 245.554 49.4314 + vertex 840.969 246.534 49.7015 + vertex 842.173 245.196 49.1259 + endloop + endfacet + facet normal -0.0975552 -0.607323 0.788443 + outer loop + vertex 842.415 245.554 49.4314 + vertex 842.173 245.196 49.1259 + vertex 843.638 244.518 48.7845 + endloop + endfacet + facet normal -0.110611 -0.626852 0.771247 + outer loop + vertex 843.638 244.518 48.7845 + vertex 842.173 245.196 49.1259 + vertex 843.459 244.184 48.4877 + endloop + endfacet + facet normal -0.111982 -0.62792 0.770179 + outer loop + vertex 842.173 245.196 49.1259 + vertex 842.11 245.04 48.9891 + vertex 843.459 244.184 48.4877 + endloop + endfacet + facet normal -0.150135 -0.665308 0.731317 + outer loop + vertex 843.459 244.184 48.4877 + vertex 842.11 245.04 48.9891 + vertex 843.442 244.015 48.3309 + endloop + endfacet + facet normal -0.0113632 -0.680456 0.732701 + outer loop + vertex 843.459 244.184 48.4877 + vertex 843.442 244.015 48.3309 + vertex 844.767 243.479 47.8536 + endloop + endfacet + facet normal -0.0185115 -0.689999 0.723573 + outer loop + vertex 844.767 243.479 47.8536 + vertex 843.442 244.015 48.3309 + vertex 844.76 243.321 47.7021 + endloop + endfacet + facet normal -0.00420087 -0.663436 0.748221 + outer loop + vertex 843.638 244.518 48.7845 + vertex 843.459 244.184 48.4877 + vertex 844.814 243.793 48.1487 + endloop + endfacet + facet normal -0.0148077 -0.683902 0.729424 + outer loop + vertex 844.814 243.793 48.1487 + vertex 843.459 244.184 48.4877 + vertex 844.767 243.479 47.8536 + endloop + endfacet + facet normal 0.124764 -0.688806 0.714129 + outer loop + vertex 846.526 243.244 47.403 + vertex 845.886 243.374 47.6396 + vertex 846.011 243.123 47.3761 + endloop + endfacet + facet normal 0.0727679 -0.689081 0.721022 + outer loop + vertex 844.814 243.793 48.1487 + vertex 844.767 243.479 47.8536 + vertex 845.886 243.374 47.6396 + endloop + endfacet + facet normal 0.0678937 -0.706705 0.704243 + outer loop + vertex 844.767 243.479 47.8536 + vertex 846.011 243.123 47.3761 + vertex 845.886 243.374 47.6396 + endloop + endfacet + facet normal 0.0784569 -0.690153 0.719398 + outer loop + vertex 844.767 243.479 47.8536 + vertex 844.76 243.321 47.7021 + vertex 846.011 243.123 47.3761 + endloop + endfacet + facet normal 0.100055 -0.633056 0.767612 + outer loop + vertex 846.011 243.123 47.3761 + vertex 844.76 243.321 47.7021 + vertex 845.714 242.989 47.3039 + endloop + endfacet + facet normal -0.37025 -0.891932 0.259561 + outer loop + vertex 843.439 243.986 48.2763 + vertex 843.405 243.994 48.2543 + vertex 844.729 243.267 47.644 + endloop + endfacet + facet normal -0.0830722 -0.725066 0.68365 + outer loop + vertex 844.729 243.267 47.644 + vertex 843.405 243.994 48.2543 + vertex 844.686 243.243 47.6136 + endloop + endfacet + facet normal -0.227975 -0.854694 0.466397 + outer loop + vertex 843.442 244.015 48.3309 + vertex 843.439 243.986 48.2763 + vertex 844.76 243.321 47.7021 + endloop + endfacet + facet normal -0.0595629 -0.717066 0.694456 + outer loop + vertex 844.76 243.321 47.7021 + vertex 843.439 243.986 48.2763 + vertex 844.729 243.267 47.644 + endloop + endfacet + facet normal 0.0224578 -0.740654 0.671511 + outer loop + vertex 844.76 243.321 47.7021 + vertex 844.729 243.267 47.644 + vertex 845.714 242.989 47.3039 + endloop + endfacet + facet normal 0.0654127 -0.670788 0.738759 + outer loop + vertex 845.714 242.989 47.3039 + vertex 844.729 243.267 47.644 + vertex 845.786 242.895 47.2123 + endloop + endfacet + facet normal -0.016083 -0.77626 0.630207 + outer loop + vertex 844.729 243.267 47.644 + vertex 844.686 243.243 47.6136 + vertex 845.786 242.895 47.2123 + endloop + endfacet + facet normal 0.101976 -0.59565 0.796745 + outer loop + vertex 845.786 242.895 47.2123 + vertex 844.686 243.243 47.6136 + vertex 845.588 242.845 47.2006 + endloop + endfacet + facet normal 0.475205 0.313257 -0.822223 + outer loop + vertex 838.843 250.03 50.4708 + vertex 838.708 250.358 50.5185 + vertex 837.661 253.074 50.9479 + endloop + endfacet + facet normal -0.530546 -0.316686 0.786277 + outer loop + vertex 838.902 249.949 50.4841 + vertex 837.707 253.273 51.0167 + vertex 838.708 250.358 50.5185 + endloop + endfacet + facet normal -0.281751 -0.254904 0.925008 + outer loop + vertex 837.707 253.273 51.0167 + vertex 837.661 253.074 50.9479 + vertex 838.708 250.358 50.5185 + endloop + endfacet + facet normal -0.639174 -0.340266 0.689692 + outer loop + vertex 838.902 249.949 50.4841 + vertex 838.87 250.511 50.732 + vertex 837.707 253.273 51.0167 + endloop + endfacet + facet normal -0.587046 -0.324826 0.741529 + outer loop + vertex 839.277 250.428 51.0172 + vertex 838.005 253.756 51.4686 + vertex 838.87 250.511 50.732 + endloop + endfacet + facet normal -0.591584 -0.32518 0.737758 + outer loop + vertex 838.005 253.756 51.4686 + vertex 837.707 253.273 51.0167 + vertex 838.87 250.511 50.732 + endloop + endfacet + facet normal -0.444784 -0.382221 0.809984 + outer loop + vertex 838.87 250.511 50.732 + vertex 838.902 249.949 50.4841 + vertex 839.884 248.233 50.2137 + endloop + endfacet + facet normal -0.525356 -0.417518 0.741404 + outer loop + vertex 839.884 248.233 50.2137 + vertex 838.902 249.949 50.4841 + vertex 839.789 248.114 50.0793 + endloop + endfacet + facet normal -0.575545 -0.43383 0.69321 + outer loop + vertex 839.277 250.428 51.0172 + vertex 838.87 250.511 50.732 + vertex 840.112 248.561 50.5422 + endloop + endfacet + facet normal -0.514881 -0.401461 0.757447 + outer loop + vertex 840.112 248.561 50.5422 + vertex 838.87 250.511 50.732 + vertex 839.884 248.233 50.2137 + endloop + endfacet + facet normal -0.394454 -0.499187 0.771504 + outer loop + vertex 840.112 248.561 50.5422 + vertex 839.884 248.233 50.2137 + vertex 841.197 246.891 50.0167 + endloop + endfacet + facet normal -0.36504 -0.474719 0.800867 + outer loop + vertex 841.197 246.891 50.0167 + vertex 839.884 248.233 50.2137 + vertex 840.969 246.534 49.7015 + endloop + endfacet + facet normal -0.431552 -0.50178 0.749653 + outer loop + vertex 839.884 248.233 50.2137 + vertex 839.789 248.114 50.0793 + vertex 840.969 246.534 49.7015 + endloop + endfacet + facet normal -0.41541 -0.49322 0.764309 + outer loop + vertex 840.969 246.534 49.7015 + vertex 839.789 248.114 50.0793 + vertex 840.89 246.41 49.5778 + endloop + endfacet + facet normal 0.649947 0.157048 0.743575 + outer loop + vertex 838.708 250.358 50.5185 + vertex 838.843 250.03 50.4708 + vertex 839.761 248.148 50.0656 + endloop + endfacet + facet normal 0.729505 0.464179 -0.502354 + outer loop + vertex 839.761 248.148 50.0656 + vertex 838.843 250.03 50.4708 + vertex 839.717 248.242 50.0888 + endloop + endfacet + facet normal -0.904143 -0.421223 -0.0713872 + outer loop + vertex 838.902 249.949 50.4841 + vertex 838.708 250.358 50.5185 + vertex 839.789 248.114 50.0793 + endloop + endfacet + facet normal -0.772108 -0.457889 0.440667 + outer loop + vertex 839.789 248.114 50.0793 + vertex 838.708 250.358 50.5185 + vertex 839.761 248.148 50.0656 + endloop + endfacet + facet normal -0.79523 -0.572477 0.199697 + outer loop + vertex 839.789 248.114 50.0793 + vertex 839.761 248.148 50.0656 + vertex 840.89 246.41 49.5778 + endloop + endfacet + facet normal -0.664532 -0.567849 0.485741 + outer loop + vertex 840.89 246.41 49.5778 + vertex 839.761 248.148 50.0656 + vertex 840.861 246.426 49.5579 + endloop + endfacet + facet normal -0.263894 0.113723 -0.957824 + outer loop + vertex 839.761 248.148 50.0656 + vertex 839.717 248.242 50.0888 + vertex 840.861 246.426 49.5579 + endloop + endfacet + facet normal -0.724508 -0.569871 0.387731 + outer loop + vertex 840.861 246.426 49.5579 + vertex 839.717 248.242 50.0888 + vertex 840.81 246.496 49.5659 + endloop + endfacet + facet normal -0.499366 -0.196581 0.843795 + outer loop + vertex 835.14 264.204 52.3539 + vertex 835.082 262.578 51.9405 + vertex 836.313 258.315 51.6757 + endloop + endfacet + facet normal -0.495219 -0.19555 0.846474 + outer loop + vertex 836.313 258.315 51.6757 + vertex 835.082 262.578 51.9405 + vertex 836.331 257.368 51.468 + endloop + endfacet + facet normal -0.73757 -0.229238 0.63517 + outer loop + vertex 835.782 263.946 53.0064 + vertex 835.14 264.204 52.3539 + vertex 836.685 258.959 52.2548 + endloop + endfacet + facet normal -0.693176 -0.217146 0.68728 + outer loop + vertex 836.685 258.959 52.2548 + vertex 835.14 264.204 52.3539 + vertex 836.313 258.315 51.6757 + endloop + endfacet + facet normal -0.643502 -0.271399 0.715715 + outer loop + vertex 836.685 258.959 52.2548 + vertex 836.313 258.315 51.6757 + vertex 838.005 253.756 51.4686 + endloop + endfacet + facet normal -0.644078 -0.271586 0.715126 + outer loop + vertex 838.005 253.756 51.4686 + vertex 836.313 258.315 51.6757 + vertex 837.707 253.273 51.0167 + endloop + endfacet + facet normal -0.319344 -0.209128 0.924275 + outer loop + vertex 836.313 258.315 51.6757 + vertex 836.331 257.368 51.468 + vertex 837.707 253.273 51.0167 + endloop + endfacet + facet normal -0.374394 -0.224897 0.899584 + outer loop + vertex 837.707 253.273 51.0167 + vertex 836.331 257.368 51.468 + vertex 837.661 253.074 50.9479 + endloop + endfacet + facet normal -0.658278 -0.1632 0.734872 + outer loop + vertex 835.082 262.578 51.9405 + vertex 835.14 264.204 52.3539 + vertex 833.803 269.794 52.3972 + endloop + endfacet + facet normal -0.736108 -0.186262 0.650731 + outer loop + vertex 835.782 263.946 53.0064 + vertex 834.425 271.895 53.7464 + vertex 835.14 264.204 52.3539 + endloop + endfacet + facet normal -0.751031 -0.184609 0.633934 + outer loop + vertex 834.425 271.895 53.7464 + vertex 833.803 269.794 52.3972 + vertex 835.14 264.204 52.3539 + endloop + endfacet + facet normal -0.804078 -0.163536 0.571589 + outer loop + vertex 832.446 282.916 54.1154 + vertex 832.335 278.69 52.7506 + vertex 834.425 271.895 53.7464 + endloop + endfacet + facet normal -0.784651 -0.153297 0.600685 + outer loop + vertex 834.425 271.895 53.7464 + vertex 832.335 278.69 52.7506 + vertex 833.803 269.794 52.3972 + endloop + endfacet + facet normal -0.826239 -0.168223 0.537615 + outer loop + vertex 830.705 290.707 53.8774 + vertex 830.819 287.084 52.9189 + vertex 832.446 282.916 54.1154 + endloop + endfacet + facet normal -0.815377 -0.15847 0.556819 + outer loop + vertex 832.446 282.916 54.1154 + vertex 830.819 287.084 52.9189 + vertex 832.335 278.69 52.7506 + endloop + endfacet + facet normal -0.824788 -0.19379 0.531198 + outer loop + vertex 829.225 298.691 54.4932 + vertex 829.028 295.162 52.8991 + vertex 830.705 290.707 53.8774 + endloop + endfacet + facet normal -0.801689 -0.176325 0.571143 + outer loop + vertex 830.705 290.707 53.8774 + vertex 829.028 295.162 52.8991 + vertex 830.819 287.084 52.9189 + endloop + endfacet + facet normal -0.808851 -0.213422 0.547915 + outer loop + vertex 826.605 306.821 53.7914 + vertex 826.792 303.757 52.8741 + vertex 829.225 298.691 54.4932 + endloop + endfacet + facet normal -0.803188 -0.207323 0.558485 + outer loop + vertex 829.225 298.691 54.4932 + vertex 826.792 303.757 52.8741 + vertex 829.028 295.162 52.8991 + endloop + endfacet + facet normal -0.79144 -0.245019 0.55999 + outer loop + vertex 824.706 313.647 54.094 + vertex 824.525 311.412 52.8603 + vertex 826.605 306.821 53.7914 + endloop + endfacet + facet normal -0.767806 -0.226321 0.599377 + outer loop + vertex 826.605 306.821 53.7914 + vertex 824.525 311.412 52.8603 + vertex 826.792 303.757 52.8741 + endloop + endfacet + facet normal -0.779376 -0.266385 0.567108 + outer loop + vertex 822.032 321.814 54.2558 + vertex 821.83 319.363 52.8268 + vertex 824.706 313.647 54.094 + endloop + endfacet + facet normal -0.770906 -0.258824 0.581991 + outer loop + vertex 824.706 313.647 54.094 + vertex 821.83 319.363 52.8268 + vertex 824.525 311.412 52.8603 + endloop + endfacet + facet normal -0.778288 -0.297502 0.552955 + outer loop + vertex 818.917 330.705 54.6545 + vertex 818.981 327.453 52.9943 + vertex 822.032 321.814 54.2558 + endloop + endfacet + facet normal -0.759587 -0.279723 0.587182 + outer loop + vertex 822.032 321.814 54.2558 + vertex 818.981 327.453 52.9943 + vertex 821.83 319.363 52.8268 + endloop + endfacet + facet normal -0.772794 -0.322794 0.546437 + outer loop + vertex 814.837 339.817 54.2675 + vertex 815.573 335.751 52.9065 + vertex 818.917 330.705 54.6545 + endloop + endfacet + facet normal -0.761309 -0.306555 0.571343 + outer loop + vertex 818.917 330.705 54.6545 + vertex 815.573 335.751 52.9065 + vertex 818.981 327.453 52.9943 + endloop + endfacet + facet normal -0.774053 -0.343368 0.531921 + outer loop + vertex 811.108 347.92 54.0716 + vertex 812.103 343.865 52.9021 + vertex 814.837 339.817 54.2675 + endloop + endfacet + facet normal -0.761671 -0.325427 0.560317 + outer loop + vertex 814.837 339.817 54.2675 + vertex 812.103 343.865 52.9021 + vertex 815.573 335.751 52.9065 + endloop + endfacet + facet normal -0.770254 -0.350786 0.532595 + outer loop + vertex 807.785 354.744 53.7605 + vertex 808.566 351.545 52.7832 + vertex 811.108 347.92 54.0716 + endloop + endfacet + facet normal -0.766236 -0.344477 0.542418 + outer loop + vertex 811.108 347.92 54.0716 + vertex 808.566 351.545 52.7832 + vertex 812.103 343.865 52.9021 + endloop + endfacet + facet normal -0.778555 -0.367286 0.508875 + outer loop + vertex 805.012 361.719 54.5527 + vertex 805.203 359.116 52.9657 + vertex 807.785 354.744 53.7605 + endloop + endfacet + facet normal -0.7629 -0.35196 0.542317 + outer loop + vertex 807.785 354.744 53.7605 + vertex 805.203 359.116 52.9657 + vertex 808.566 351.545 52.7832 + endloop + endfacet + facet normal -0.78394 -0.366184 0.501346 + outer loop + vertex 800.626 370.833 54.3508 + vertex 801.489 367.1 52.9729 + vertex 805.012 361.719 54.5527 + endloop + endfacet + facet normal -0.782879 -0.364685 0.504088 + outer loop + vertex 805.012 361.719 54.5527 + vertex 801.489 367.1 52.9729 + vertex 805.203 359.116 52.9657 + endloop + endfacet + facet normal -0.789948 -0.338795 0.511078 + outer loop + vertex 796.947 379.133 54.1665 + vertex 797.617 375.655 52.8961 + vertex 800.626 370.833 54.3508 + endloop + endfacet + facet normal -0.804947 -0.360064 0.471609 + outer loop + vertex 800.626 370.833 54.3508 + vertex 797.617 375.655 52.8961 + vertex 801.489 367.1 52.9729 + endloop + endfacet + facet normal -0.807622 -0.257645 0.530439 + outer loop + vertex 794.393 384.772 53.016 + vertex 794.278 384.776 52.8438 + vertex 796.947 379.133 54.1665 + endloop + endfacet + facet normal -0.860444 -0.312654 0.402348 + outer loop + vertex 796.947 379.133 54.1665 + vertex 794.278 384.776 52.8438 + vertex 797.617 375.655 52.8961 + endloop + endfacet + facet normal 0.12912 -0.584576 0.800999 + outer loop + vertex 845.588 242.845 47.2006 + vertex 845.658 242.721 47.099 + vertex 846.468 242.803 47.0284 + endloop + endfacet + facet normal 0.168747 -0.575969 0.799865 + outer loop + vertex 845.559 242.636 47.0584 + vertex 846.23 242.522 46.8347 + vertex 845.658 242.721 47.099 + endloop + endfacet + facet normal 0.130763 -0.634532 0.761754 + outer loop + vertex 846.23 242.522 46.8347 + vertex 846.468 242.803 47.0284 + vertex 845.658 242.721 47.099 + endloop + endfacet + facet normal -0.0828918 -0.480109 0.873284 + outer loop + vertex 840.805 246.259 49.4309 + vertex 841.085 245.787 49.1978 + vertex 842.083 244.871 48.789 + endloop + endfacet + facet normal -0.351069 -0.673052 0.650962 + outer loop + vertex 842.083 244.871 48.789 + vertex 841.085 245.787 49.1978 + vertex 842.318 244.557 48.5916 + endloop + endfacet + facet normal 0.0303849 -0.51603 0.856031 + outer loop + vertex 842.083 244.871 48.789 + vertex 842.318 244.557 48.5916 + vertex 843.418 243.817 48.1064 + endloop + endfacet + facet normal -0.111339 -0.655253 0.74716 + outer loop + vertex 843.418 243.817 48.1064 + vertex 842.318 244.557 48.5916 + vertex 843.477 243.68 47.9946 + endloop + endfacet + facet normal -0.0842146 -0.468285 0.879555 + outer loop + vertex 840.755 246.476 49.5414 + vertex 840.805 246.259 49.4309 + vertex 842.016 245.054 48.9051 + endloop + endfacet + facet normal -0.241837 -0.58171 0.776614 + outer loop + vertex 842.016 245.054 48.9051 + vertex 840.805 246.259 49.4309 + vertex 842.083 244.871 48.789 + endloop + endfacet + facet normal -0.175918 -0.519474 0.836182 + outer loop + vertex 840.81 246.496 49.5659 + vertex 840.755 246.476 49.5414 + vertex 842.052 245.074 48.9439 + endloop + endfacet + facet normal -0.368311 -0.63187 0.681973 + outer loop + vertex 842.052 245.074 48.9439 + vertex 840.755 246.476 49.5414 + vertex 842.016 245.054 48.9051 + endloop + endfacet + facet normal -0.259946 -0.729432 0.632738 + outer loop + vertex 842.052 245.074 48.9439 + vertex 842.016 245.054 48.9051 + vertex 843.405 243.994 48.2543 + endloop + endfacet + facet normal -0.212166 -0.698155 0.683787 + outer loop + vertex 843.405 243.994 48.2543 + vertex 842.016 245.054 48.9051 + vertex 843.379 243.956 48.2077 + endloop + endfacet + facet normal 0.00065149 -0.535865 0.844304 + outer loop + vertex 842.016 245.054 48.9051 + vertex 842.083 244.871 48.789 + vertex 843.379 243.956 48.2077 + endloop + endfacet + facet normal -0.0638902 -0.59833 0.798699 + outer loop + vertex 843.379 243.956 48.2077 + vertex 842.083 244.871 48.789 + vertex 843.418 243.817 48.1064 + endloop + endfacet + facet normal 0.0614668 -0.575288 0.815638 + outer loop + vertex 843.379 243.956 48.2077 + vertex 843.418 243.817 48.1064 + vertex 844.649 243.178 47.563 + endloop + endfacet + facet normal 0.0599569 -0.577164 0.814425 + outer loop + vertex 844.649 243.178 47.563 + vertex 843.418 243.817 48.1064 + vertex 844.67 243.056 47.4752 + endloop + endfacet + facet normal -0.105538 -0.743513 0.660341 + outer loop + vertex 843.405 243.994 48.2543 + vertex 843.379 243.956 48.2077 + vertex 844.686 243.243 47.6136 + endloop + endfacet + facet normal 0.0182378 -0.61996 0.784422 + outer loop + vertex 844.686 243.243 47.6136 + vertex 843.379 243.956 48.2077 + vertex 844.649 243.178 47.563 + endloop + endfacet + facet normal 0.0703564 -0.637044 0.76761 + outer loop + vertex 844.686 243.243 47.6136 + vertex 844.649 243.178 47.563 + vertex 845.588 242.845 47.2006 + endloop + endfacet + facet normal 0.0943095 -0.59926 0.79498 + outer loop + vertex 845.588 242.845 47.2006 + vertex 844.649 243.178 47.563 + vertex 845.658 242.721 47.099 + endloop + endfacet + facet normal 0.117868 -0.567465 0.814918 + outer loop + vertex 844.649 243.178 47.563 + vertex 844.67 243.056 47.4752 + vertex 845.658 242.721 47.099 + endloop + endfacet + facet normal 0.130475 -0.545133 0.828134 + outer loop + vertex 845.658 242.721 47.099 + vertex 844.67 243.056 47.4752 + vertex 845.559 242.636 47.0584 + endloop + endfacet + facet normal 0.0104789 -0.628288 0.77791 + outer loop + vertex 843.418 243.817 48.1064 + vertex 843.477 243.68 47.9946 + vertex 844.67 243.056 47.4752 + endloop + endfacet + facet normal 0.0213093 -0.615703 0.78769 + outer loop + vertex 844.67 243.056 47.4752 + vertex 843.477 243.68 47.9946 + vertex 844.832 242.899 47.3475 + endloop + endfacet + facet normal 0.139924 -0.532033 0.835082 + outer loop + vertex 844.67 243.056 47.4752 + vertex 844.832 242.899 47.3475 + vertex 845.559 242.636 47.0584 + endloop + endfacet + facet normal -0.472794 -0.625523 -0.620634 + outer loop + vertex 845.559 242.636 47.0584 + vertex 844.832 242.899 47.3475 + vertex 845.869 242.544 46.9149 + endloop + endfacet + facet normal -0.278838 -0.25383 0.926185 + outer loop + vertex 838.694 250.088 50.4603 + vertex 838.631 250.482 50.5493 + vertex 837.62 253.004 50.9363 + endloop + endfacet + facet normal 0.207658 -0.0723044 0.975526 + outer loop + vertex 838.843 250.03 50.4708 + vertex 837.661 253.074 50.9479 + vertex 838.631 250.482 50.5493 + endloop + endfacet + facet normal -0.0125877 -0.15656 0.987588 + outer loop + vertex 837.661 253.074 50.9479 + vertex 837.62 253.004 50.9363 + vertex 838.631 250.482 50.5493 + endloop + endfacet + facet normal -0.0482934 -0.227623 0.972551 + outer loop + vertex 838.631 250.482 50.5493 + vertex 838.694 250.088 50.4603 + vertex 839.649 248.272 50.0827 + endloop + endfacet + facet normal -0.272701 -0.331312 0.903253 + outer loop + vertex 839.649 248.272 50.0827 + vertex 838.694 250.088 50.4603 + vertex 839.695 247.964 49.9834 + endloop + endfacet + facet normal -0.837272 -0.313879 -0.447722 + outer loop + vertex 838.843 250.03 50.4708 + vertex 838.631 250.482 50.5493 + vertex 839.717 248.242 50.0888 + endloop + endfacet + facet normal -0.215534 -0.295837 0.930605 + outer loop + vertex 839.717 248.242 50.0888 + vertex 838.631 250.482 50.5493 + vertex 839.649 248.272 50.0827 + endloop + endfacet + facet normal -0.267498 -0.426346 0.864103 + outer loop + vertex 839.717 248.242 50.0888 + vertex 839.649 248.272 50.0827 + vertex 840.81 246.496 49.5659 + endloop + endfacet + facet normal -0.236024 -0.41061 0.880734 + outer loop + vertex 840.81 246.496 49.5659 + vertex 839.649 248.272 50.0827 + vertex 840.755 246.476 49.5414 + endloop + endfacet + facet normal -0.0421203 -0.311916 0.949176 + outer loop + vertex 839.649 248.272 50.0827 + vertex 839.695 247.964 49.9834 + vertex 840.755 246.476 49.5414 + endloop + endfacet + facet normal -0.354755 -0.489272 0.79672 + outer loop + vertex 840.755 246.476 49.5414 + vertex 839.695 247.964 49.9834 + vertex 840.805 246.259 49.4309 + endloop + endfacet + facet normal -0.0495484 -0.240939 0.969275 + outer loop + vertex 838.694 250.088 50.4603 + vertex 839 249.158 50.2447 + vertex 839.695 247.964 49.9834 + endloop + endfacet + facet normal -0.4767 -0.443517 0.75898 + outer loop + vertex 839.695 247.964 49.9834 + vertex 839 249.158 50.2447 + vertex 839.873 247.468 49.8055 + endloop + endfacet + facet normal -0.109917 -0.370508 0.922303 + outer loop + vertex 839.695 247.964 49.9834 + vertex 839.873 247.468 49.8055 + vertex 840.805 246.259 49.4309 + endloop + endfacet + facet normal -0.568474 -0.609543 0.552534 + outer loop + vertex 840.805 246.259 49.4309 + vertex 839.873 247.468 49.8055 + vertex 841.085 245.787 49.1978 + endloop + endfacet + facet normal 0.34677 -0.00188498 0.937948 + outer loop + vertex 835.082 262.578 51.9405 + vertex 835.613 259.724 51.7384 + vertex 836.331 257.368 51.468 + endloop + endfacet + facet normal 0.328239 -0.00829499 0.944558 + outer loop + vertex 836.331 257.368 51.468 + vertex 835.613 259.724 51.7384 + vertex 836.493 256.529 51.4044 + endloop + endfacet + facet normal 0.361737 -0.000903125 0.93228 + outer loop + vertex 836.331 257.368 51.468 + vertex 836.493 256.529 51.4044 + vertex 837.661 253.074 50.9479 + endloop + endfacet + facet normal -0.0362274 -0.142929 0.98907 + outer loop + vertex 837.661 253.074 50.9479 + vertex 836.493 256.529 51.4044 + vertex 837.62 253.004 50.9363 + endloop + endfacet + facet normal -0.844833 -0.224767 -0.485527 + outer loop + vertex 795.662 379.876 291.767 + vertex 794.163 384.78 292.105 + vertex 796.398 384.702 288.252 + endloop + endfacet + facet normal -0.805994 -0.329944 -0.491437 + outer loop + vertex 798.366 373.204 291.811 + vertex 795.662 379.876 291.767 + vertex 798.175 376.417 289.967 + endloop + endfacet + facet normal -0.786914 -0.352062 -0.506772 + outer loop + vertex 800.721 367.764 291.934 + vertex 798.366 373.204 291.811 + vertex 801.157 369.425 290.103 + endloop + endfacet + facet normal -0.775215 -0.364905 -0.515642 + outer loop + vertex 802.971 363.748 291.394 + vertex 800.721 367.764 291.934 + vertex 801.157 369.425 290.103 + endloop + endfacet + facet normal -0.782392 -0.359241 -0.508732 + outer loop + vertex 805.348 358.244 291.624 + vertex 802.971 363.748 291.394 + vertex 804.694 362.161 289.864 + endloop + endfacet + facet normal -0.763199 -0.350288 -0.542979 + outer loop + vertex 807.73 352.568 291.939 + vertex 805.348 358.244 291.624 + vertex 808.328 354.023 290.159 + endloop + endfacet + facet normal -0.763943 -0.3494 -0.542503 + outer loop + vertex 810.37 347.212 291.669 + vertex 807.73 352.568 291.939 + vertex 808.328 354.023 290.159 + endloop + endfacet + facet normal -0.761485 -0.342844 -0.55009 + outer loop + vertex 813.004 341.678 291.472 + vertex 810.37 347.212 291.669 + vertex 812.009 346.355 289.935 + endloop + endfacet + facet normal -0.76392 -0.314557 -0.563453 + outer loop + vertex 814.52 337.135 291.954 + vertex 813.004 341.678 291.472 + vertex 815.308 338.41 290.173 + endloop + endfacet + facet normal -0.76432 -0.313992 -0.563226 + outer loop + vertex 816.928 331.691 291.721 + vertex 814.52 337.135 291.954 + vertex 815.308 338.41 290.173 + endloop + endfacet + facet normal -0.762709 -0.305219 -0.570189 + outer loop + vertex 819.337 326.094 291.494 + vertex 816.928 331.691 291.721 + vertex 818.576 330.905 289.937 + endloop + endfacet + facet normal -0.764029 -0.273831 -0.584188 + outer loop + vertex 820.645 321.484 291.944 + vertex 819.337 326.094 291.494 + vertex 821.515 322.865 290.159 + endloop + endfacet + facet normal -0.766757 -0.269871 -0.582455 + outer loop + vertex 822.795 315.971 291.669 + vertex 820.645 321.484 291.944 + vertex 821.515 322.865 290.159 + endloop + endfacet + facet normal -0.767145 -0.25716 -0.587671 + outer loop + vertex 824.908 310.209 291.432 + vertex 822.795 315.971 291.669 + vertex 824.399 315.208 289.908 + endloop + endfacet + facet normal -0.782146 -0.222123 -0.582158 + outer loop + vertex 825.918 305.42 291.903 + vertex 824.908 310.209 291.432 + vertex 826.829 306.795 290.154 + endloop + endfacet + facet normal -0.786513 -0.215094 -0.578906 + outer loop + vertex 827.591 299.755 291.734 + vertex 825.918 305.42 291.903 + vertex 826.829 306.795 290.154 + endloop + endfacet + facet normal -0.789487 -0.205408 -0.578375 + outer loop + vertex 828.825 295.009 291.735 + vertex 827.591 299.755 291.734 + vertex 829.198 297.905 290.198 + endloop + endfacet + facet normal -0.825311 -0.17821 -0.53582 + outer loop + vertex 829.812 290.581 291.688 + vertex 828.825 295.009 291.735 + vertex 829.198 297.905 290.198 + endloop + endfacet + facet normal -0.799618 -0.17055 -0.57578 + outer loop + vertex 831.133 284.839 291.553 + vertex 829.812 290.581 291.688 + vertex 831.073 290.476 289.967 + endloop + endfacet + facet normal -0.801293 -0.149237 -0.57936 + outer loop + vertex 831.833 279.308 292.01 + vertex 831.133 284.839 291.553 + vertex 832.617 281.913 290.256 + endloop + endfacet + facet normal -0.793091 -0.157742 -0.588323 + outer loop + vertex 832.921 275.117 291.668 + vertex 831.833 279.308 292.01 + vertex 832.617 281.913 290.256 + endloop + endfacet + facet normal -0.782215 -0.14898 -0.604933 + outer loop + vertex 833.468 271.309 291.899 + vertex 832.921 275.117 291.668 + vertex 834.4 272.21 290.471 + endloop + endfacet + facet normal -0.775829 -0.16291 -0.609549 + outer loop + vertex 834.329 266.491 292.09 + vertex 833.468 271.309 291.899 + vertex 834.4 272.21 290.471 + endloop + endfacet + facet normal -0.675024 -0.152787 -0.721802 + outer loop + vertex 835.199 262.269 292.17 + vertex 834.329 266.491 292.09 + vertex 835.472 263.309 291.695 + endloop + endfacet + facet normal -0.812537 -0.22387 -0.538206 + outer loop + vertex 835.811 259.508 292.394 + vertex 835.199 262.269 292.17 + vertex 835.611 260.758 292.176 + endloop + endfacet + facet normal -0.633001 -0.260602 -0.728969 + outer loop + vertex 836.974 255.767 292.721 + vertex 835.811 259.508 292.394 + vertex 836.346 258.535 292.278 + endloop + endfacet + facet normal -0.611895 -0.308167 -0.728435 + outer loop + vertex 838.56 251.455 293.214 + vertex 836.974 255.767 292.721 + vertex 837.911 254.021 292.673 + endloop + endfacet + facet normal -0.802346 -0.272432 0.531057 + outer loop + vertex 839.743 248.777 293.629 + vertex 838.56 251.455 293.214 + vertex 839.398 249.502 293.479 + endloop + endfacet + facet normal -0.546608 -0.495283 -0.675215 + outer loop + vertex 840.829 247.067 294.005 + vertex 839.743 248.777 293.629 + vertex 840.141 248.206 293.726 + endloop + endfacet + facet normal -0.484911 -0.582731 -0.652139 + outer loop + vertex 842.086 245.523 294.45 + vertex 840.829 247.067 294.005 + vertex 841.305 246.535 294.126 + endloop + endfacet + facet normal -0.43707 -0.699096 -0.565893 + outer loop + vertex 843.478 244.257 294.938 + vertex 842.086 245.523 294.45 + vertex 842.638 245.067 294.587 + endloop + endfacet + facet normal -0.318102 -0.804848 -0.50103 + outer loop + vertex 844.958 243.361 295.438 + vertex 843.478 244.257 294.938 + vertex 844.075 243.931 295.084 + endloop + endfacet + facet normal -0.102056 -0.806491 -0.582372 + outer loop + vertex 846.47 242.81 295.937 + vertex 844.958 243.361 295.438 + vertex 845.547 243.187 295.576 + endloop + endfacet + facet normal 0.0720004 -0.7434 -0.664961 + outer loop + vertex 848.339 242.413 296.583 + vertex 846.47 242.81 295.937 + vertex 846.935 242.814 295.983 + endloop + endfacet + facet normal 0.0894731 -0.672944 -0.734263 + outer loop + vertex 849.386 244.797 294.526 + vertex 848.339 242.413 296.583 + vertex 848.72 243.646 295.499 + endloop + endfacet + facet normal -0.224898 -0.651899 -0.724188 + outer loop + vertex 850.212 247.179 292.125 + vertex 849.386 244.797 294.526 + vertex 849.677 245.899 293.443 + endloop + endfacet + facet normal -0.0254838 -0.748783 -0.662325 + outer loop + vertex 851.276 250.431 288.408 + vertex 850.212 247.179 292.125 + vertex 850.077 247.903 291.312 + endloop + endfacet + facet normal -0.173181 -0.761536 -0.624557 + outer loop + vertex 852.294 253.651 284.199 + vertex 851.276 250.431 288.408 + vertex 851.593 252.5 285.797 + endloop + endfacet + facet normal -0.107163 -0.819048 -0.563628 + outer loop + vertex 852.994 256.161 280.418 + vertex 852.294 253.651 284.199 + vertex 852.299 254.921 282.352 + endloop + endfacet + facet normal -0.0957005 -0.855659 -0.508614 + outer loop + vertex 853.697 258.903 275.672 + vertex 852.994 256.161 280.418 + vertex 852.87 257.186 278.717 + endloop + endfacet + facet normal -0.0816807 -0.887006 -0.454475 + outer loop + vertex 854.177 261.427 270.661 + vertex 853.697 258.903 275.672 + vertex 853.568 260.563 272.456 + endloop + endfacet + facet normal -0.0724341 -0.910866 -0.406297 + outer loop + vertex 854.427 263.327 266.357 + vertex 854.177 261.427 270.661 + vertex 853.842 262.361 268.628 + endloop + endfacet + facet normal -0.0852534 -0.92557 -0.368853 + outer loop + vertex 854.671 265.327 261.282 + vertex 854.427 263.327 266.357 + vertex 854.048 264.028 264.686 + endloop + endfacet + facet normal -0.0719625 -0.939445 -0.335059 + outer loop + vertex 854.948 267.359 255.524 + vertex 854.671 265.327 261.282 + vertex 854.275 266.632 257.707 + endloop + endfacet + facet normal -0.0562298 -0.952681 -0.298726 + outer loop + vertex 854.856 268.75 251.106 + vertex 854.948 267.359 255.524 + vertex 854.337 268.027 253.509 + endloop + endfacet + facet normal -0.0728624 -0.958666 -0.275046 + outer loop + vertex 854.9 270.194 246.061 + vertex 854.856 268.75 251.106 + vertex 854.346 269.271 249.424 + endloop + endfacet + facet normal -0.0662599 -0.967018 -0.245937 + outer loop + vertex 854.881 271.773 239.857 + vertex 854.9 270.194 246.061 + vertex 854.335 271.168 242.384 + endloop + endfacet + facet normal -0.0722461 -0.973963 -0.214885 + outer loop + vertex 854.574 272.901 234.85 + vertex 854.881 271.773 239.857 + vertex 854.259 272.22 238.043 + endloop + endfacet + facet normal -0.0481877 -0.978887 -0.198643 + outer loop + vertex 854.622 273.829 230.264 + vertex 854.574 272.901 234.85 + vertex 854.093 273.686 231.097 + endloop + endfacet + facet normal 0.0120762 -0.982954 -0.183454 + outer loop + vertex 854.523 274.44 226.982 + vertex 854.622 273.829 230.264 + vertex 854.05 274.464 226.823 + endloop + endfacet + facet normal 0.00742945 -0.985416 -0.170002 + outer loop + vertex 854.428 274.989 223.797 + vertex 854.523 274.44 226.982 + vertex 854.05 274.464 226.823 + endloop + endfacet + facet normal 0.00332074 -0.987191 -0.159506 + outer loop + vertex 854.218 275.515 220.537 + vertex 854.428 274.989 223.797 + vertex 853.91 275.171 222.659 + endloop + endfacet + facet normal -0.00312553 -0.988636 -0.150295 + outer loop + vertex 854.168 275.928 217.824 + vertex 854.218 275.515 220.537 + vertex 853.829 275.742 219.055 + endloop + endfacet + facet normal 0.00406169 -0.990154 -0.139921 + outer loop + vertex 854.257 276.33 214.98 + vertex 854.168 275.928 217.824 + vertex 853.793 276.305 215.141 + endloop + endfacet + facet normal 0.00778168 -0.991564 -0.12938 + outer loop + vertex 854.053 276.665 212.4 + vertex 854.257 276.33 214.98 + vertex 853.793 276.305 215.141 + endloop + endfacet + facet normal -0.0338931 -0.992153 -0.120346 + outer loop + vertex 853.988 276.999 209.664 + vertex 854.053 276.665 212.4 + vertex 853.676 276.827 211.167 + endloop + endfacet + facet normal -0.0381169 -0.993108 -0.110832 + outer loop + vertex 854.01 277.383 206.215 + vertex 853.988 276.999 209.664 + vertex 853.621 277.257 207.481 + endloop + endfacet + facet normal -0.0246942 -0.99457 -0.1011 + outer loop + vertex 853.93 277.66 203.51 + vertex 854.01 277.383 206.215 + vertex 853.581 277.664 203.556 + endloop + endfacet + facet normal -0.0234555 -0.995518 -0.0916141 + outer loop + vertex 853.839 277.844 201.539 + vertex 853.93 277.66 203.51 + vertex 853.581 277.664 203.556 + endloop + endfacet + facet normal -0.0478819 -0.995122 -0.086257 + outer loop + vertex 853.892 278.135 198.149 + vertex 853.839 277.844 201.539 + vertex 853.483 278.035 199.525 + endloop + endfacet + facet normal -0.033356 -0.996721 -0.0737183 + outer loop + vertex 853.854 278.353 195.213 + vertex 853.892 278.135 198.149 + vertex 853.48 278.356 195.344 + endloop + endfacet + facet normal -0.0312397 -0.997221 -0.0676369 + outer loop + vertex 853.838 278.562 192.139 + vertex 853.854 278.353 195.213 + vertex 853.48 278.356 195.344 + endloop + endfacet + facet normal -0.0619718 -0.996526 -0.0556305 + outer loop + vertex 853.712 278.747 188.966 + vertex 853.838 278.562 192.139 + vertex 853.41 278.644 191.154 + endloop + endfacet + facet normal -0.0776505 -0.995794 -0.0486371 + outer loop + vertex 853.703 278.883 186.206 + vertex 853.712 278.747 188.966 + vertex 853.382 278.848 187.441 + endloop + endfacet + facet normal -0.0372841 -0.99846 -0.0410683 + outer loop + vertex 853.825 278.998 183.306 + vertex 853.703 278.883 186.206 + vertex 853.393 279.008 183.452 + endloop + endfacet + facet normal -0.0329711 -0.999058 -0.0282157 + outer loop + vertex 853.664 279.075 180.739 + vertex 853.825 278.998 183.306 + vertex 853.393 279.008 183.452 + endloop + endfacet + facet normal -0.0739206 -0.997005 -0.0227512 + outer loop + vertex 853.652 279.139 177.979 + vertex 853.664 279.075 180.739 + vertex 853.329 279.132 179.358 + endloop + endfacet + facet normal -0.0411715 -0.999039 -0.0150476 + outer loop + vertex 853.785 279.177 175.091 + vertex 853.652 279.139 177.979 + vertex 853.36 279.192 175.272 + endloop + endfacet + facet normal -0.0362787 -0.999335 -0.00352489 + outer loop + vertex 853.644 279.191 172.54 + vertex 853.785 279.177 175.091 + vertex 853.36 279.192 175.272 + endloop + endfacet + facet normal -0.0788392 -0.996883 0.00292148 + outer loop + vertex 853.63 279.185 169.829 + vertex 853.644 279.191 172.54 + vertex 853.315 279.214 171.288 + endloop + endfacet + facet normal -0.0634377 -0.997915 0.0119091 + outer loop + vertex 853.726 279.138 166.455 + vertex 853.63 279.185 169.829 + vertex 853.318 279.179 167.678 + endloop + endfacet + facet normal -0.042654 -0.998814 0.0234978 + outer loop + vertex 853.724 279.07 163.548 + vertex 853.726 279.138 166.455 + vertex 853.354 279.089 163.676 + endloop + endfacet + facet normal -0.0401479 -0.998722 0.0307149 + outer loop + vertex 853.739 278.978 160.568 + vertex 853.724 279.07 163.548 + vertex 853.354 279.089 163.676 + endloop + endfacet + facet normal -0.0670634 -0.996914 0.0408163 + outer loop + vertex 853.659 278.856 157.459 + vertex 853.739 278.978 160.568 + vertex 853.333 278.967 159.635 + endloop + endfacet + facet normal -0.0793337 -0.99569 0.0480442 + outer loop + vertex 853.688 278.722 154.737 + vertex 853.659 278.856 157.459 + vertex 853.349 278.809 155.989 + endloop + endfacet + facet normal -0.0343185 -0.997804 0.0566435 + outer loop + vertex 853.852 278.553 151.858 + vertex 853.688 278.722 154.737 + vertex 853.421 278.579 152.05 + endloop + endfacet + facet normal -0.0291445 -0.997243 0.0682412 + outer loop + vertex 853.732 278.382 149.309 + vertex 853.852 278.553 151.858 + vertex 853.421 278.579 152.05 + endloop + endfacet + facet normal -0.0686755 -0.994872 0.0742585 + outer loop + vertex 853.745 278.175 146.544 + vertex 853.732 278.382 149.309 + vertex 853.411 278.309 148.04 + endloop + endfacet + facet normal -0.0495993 -0.995272 0.0835073 + outer loop + vertex 853.862 277.877 143.06 + vertex 853.745 278.175 146.544 + vertex 853.448 278.003 144.325 + endloop + endfacet + facet normal -0.0126687 -0.995445 0.0944878 + outer loop + vertex 853.856 277.619 140.341 + vertex 853.862 277.877 143.06 + vertex 853.505 277.626 140.368 + endloop + endfacet + facet normal -0.011914 -0.994529 0.103774 + outer loop + vertex 853.821 277.41 138.335 + vertex 853.856 277.619 140.341 + vertex 853.505 277.626 140.368 + endloop + endfacet + facet normal -0.0172722 -0.99384 0.109469 + outer loop + vertex 853.967 277.035 134.952 + vertex 853.821 277.41 138.335 + vertex 853.512 277.19 136.296 + endloop + endfacet + facet normal 0.016908 -0.992524 0.120873 + outer loop + vertex 854.014 276.678 132.014 + vertex 853.967 277.035 134.952 + vertex 853.621 276.685 132.131 + endloop + endfacet + facet normal 0.0197619 -0.99126 0.130433 + outer loop + vertex 854.075 276.283 129.008 + vertex 854.014 276.678 132.014 + vertex 853.621 276.685 132.131 + endloop + endfacet + facet normal -0.00670068 -0.98999 0.140977 + outer loop + vertex 854.029 275.842 125.908 + vertex 854.075 276.283 129.008 + vertex 853.655 276.148 128.042 + endloop + endfacet + facet normal -0.0145911 -0.988832 0.148316 + outer loop + vertex 854.093 275.44 123.234 + vertex 854.029 275.842 125.908 + vertex 853.709 275.63 124.46 + endloop + endfacet + facet normal 0.0119872 -0.987182 0.159145 + outer loop + vertex 854.301 274.995 120.458 + vertex 854.093 275.44 123.234 + vertex 853.822 275.006 120.562 + endloop + endfacet + facet normal 0.0152259 -0.984655 0.173845 + outer loop + vertex 854.224 274.493 117.619 + vertex 854.301 274.995 120.458 + vertex 853.822 275.006 120.562 + endloop + endfacet + facet normal -0.0467921 -0.982313 0.181307 + outer loop + vertex 854.374 273.728 113.517 + vertex 854.224 274.493 117.619 + vertex 853.866 274.273 116.336 + endloop + endfacet + facet normal -0.0650833 -0.977558 0.200361 + outer loop + vertex 854.327 272.801 108.976 + vertex 854.374 273.728 113.517 + vertex 853.945 273.507 112.296 + endloop + endfacet + facet normal -0.0635798 -0.974625 0.214623 + outer loop + vertex 854.576 271.702 104.062 + vertex 854.327 272.801 108.976 + vertex 854.018 272.042 105.44 + endloop + endfacet + facet normal -0.0551716 -0.968447 0.243038 + outer loop + vertex 854.645 270.29 98.4504 + vertex 854.576 271.702 104.062 + vertex 854.049 271.001 101.146 + endloop + endfacet + facet normal -0.0584863 -0.959252 0.276432 + outer loop + vertex 854.423 268.905 93.5975 + vertex 854.645 270.29 98.4504 + vertex 854.029 269.872 96.8684 + endloop + endfacet + facet normal -0.065757 -0.952988 0.295786 + outer loop + vertex 854.527 267.326 88.5334 + vertex 854.423 268.905 93.5975 + vertex 853.942 267.844 90.0725 + endloop + endfacet + facet normal -0.0800253 -0.939261 0.333745 + outer loop + vertex 854.197 265.247 82.6019 + vertex 854.527 267.326 88.5334 + vertex 853.835 266.447 85.8936 + endloop + endfacet + facet normal -0.0702368 -0.927084 0.368216 + outer loop + vertex 853.867 263.201 77.389 + vertex 854.197 265.247 82.6019 + vertex 853.502 263.895 79.0648 + endloop + endfacet + facet normal -0.0554132 -0.9127 0.404855 + outer loop + vertex 853.496 261.245 72.9269 + vertex 853.867 263.201 77.389 + vertex 853.234 262.224 75.0984 + endloop + endfacet + facet normal -0.0646113 -0.889364 0.452611 + outer loop + vertex 852.889 258.696 67.8324 + vertex 853.496 261.245 72.9269 + vertex 852.873 260.388 71.1556 + endloop + endfacet + facet normal -0.0885204 -0.858059 0.505864 + outer loop + vertex 852.084 256.069 63.2361 + vertex 852.889 258.696 67.8324 + vertex 852.031 257.022 64.8424 + endloop + endfacet + facet normal -0.0968858 -0.82888 0.550973 + outer loop + vertex 851.315 253.689 59.5201 + vertex 852.084 256.069 63.2361 + vertex 851.376 254.836 61.2563 + endloop + endfacet + facet normal -0.0738438 -0.801354 0.593615 + outer loop + vertex 850.449 251.195 56.0451 + vertex 851.315 253.689 59.5201 + vertex 850.575 252.475 57.7895 + endloop + endfacet + facet normal -0.0327039 -0.777023 0.628622 + outer loop + vertex 849.558 248.713 52.9314 + vertex 850.449 251.195 56.0451 + vertex 849.633 249.83 54.3155 + endloop + endfacet + facet normal -0.382649 -0.621936 0.683209 + outer loop + vertex 848.634 246.294 50.2113 + vertex 849.558 248.713 52.9314 + vertex 849.094 247.752 51.7966 + endloop + endfacet + facet normal -0.632897 -0.379344 0.674937 + outer loop + vertex 847.56 243.901 47.8596 + vertex 848.634 246.294 50.2113 + vertex 848.021 245.05 48.9381 + endloop + endfacet + facet normal 0.229376 -0.722201 0.652543 + outer loop + vertex 847.08 242.431 46.4005 + vertex 847.56 243.901 47.8596 + vertex 846.468 242.803 47.0284 + endloop + endfacet + facet normal -0.395764 -0.315932 -0.862298 + outer loop + vertex 845.267 242.711 47.1302 + vertex 847.08 242.431 46.4005 + vertex 845.869 242.544 46.9149 + endloop + endfacet + facet normal -0.537619 -0.697325 -0.474029 + outer loop + vertex 843.753 243.421 47.8027 + vertex 845.267 242.711 47.1302 + vertex 844.832 242.899 47.3475 + endloop + endfacet + facet normal -0.309532 -0.757867 0.574306 + outer loop + vertex 841.886 244.871 48.7091 + vertex 843.753 243.421 47.8027 + vertex 843.477 243.68 47.9946 + endloop + endfacet + facet normal -0.791248 -0.556544 -0.253348 + outer loop + vertex 840.218 246.859 49.5507 + vertex 841.886 244.871 48.7091 + vertex 841.085 245.787 49.1978 + endloop + endfacet + facet normal -0.856517 -0.512086 0.0643953 + outer loop + vertex 839.124 248.76 50.1115 + vertex 840.218 246.859 49.5507 + vertex 839.873 247.468 49.8055 + endloop + endfacet + facet normal -0.792501 -0.400185 0.460211 + outer loop + vertex 838.096 251.363 50.6063 + vertex 839.124 248.76 50.1115 + vertex 839 249.158 50.2447 + endloop + endfacet + facet normal -0.830401 -0.331101 0.448115 + outer loop + vertex 836.673 255.808 51.252 + vertex 838.096 251.363 50.6063 + vertex 837.62 253.004 50.9363 + endloop + endfacet + facet normal -0.887499 -0.295483 0.353602 + outer loop + vertex 835.766 259.032 51.6708 + vertex 836.673 255.808 51.252 + vertex 836.493 256.529 51.4044 + endloop + endfacet + facet normal -0.76862 -0.228463 0.597518 + outer loop + vertex 835.074 261.965 51.9017 + vertex 835.766 259.032 51.6708 + vertex 835.613 259.724 51.7384 + endloop + endfacet + facet normal -0.116266 -0.0611944 0.991331 + outer loop + vertex 834.304 265.728 52.0438 + vertex 835.074 261.965 51.9017 + vertex 835.082 262.578 51.9405 + endloop + endfacet + facet normal -0.711536 -0.147528 0.686988 + outer loop + vertex 833.343 270.095 51.9852 + vertex 834.304 265.728 52.0438 + vertex 833.803 269.794 52.3972 + endloop + endfacet + facet normal -0.709994 -0.141169 0.689912 + outer loop + vertex 832.606 274.612 52.152 + vertex 833.343 270.095 51.9852 + vertex 833.803 269.794 52.3972 + endloop + endfacet + facet normal -0.749706 -0.144652 0.645768 + outer loop + vertex 831.556 279.661 52.0636 + vertex 832.606 274.612 52.152 + vertex 832.335 278.69 52.7506 + endloop + endfacet + facet normal -0.748599 -0.142522 0.647524 + outer loop + vertex 830.87 284.433 52.3204 + vertex 831.556 279.661 52.0636 + vertex 832.335 278.69 52.7506 + endloop + endfacet + facet normal -0.753048 -0.158632 0.638556 + outer loop + vertex 829.511 290.687 52.2721 + vertex 830.87 284.433 52.3204 + vertex 830.819 287.084 52.9189 + endloop + endfacet + facet normal -0.768929 -0.169429 0.616476 + outer loop + vertex 828.485 295.498 52.3138 + vertex 829.511 290.687 52.2721 + vertex 829.028 295.162 52.8991 + endloop + endfacet + facet normal -0.772606 -0.199191 0.602829 + outer loop + vertex 827.275 300.164 52.3057 + vertex 828.485 295.498 52.3138 + vertex 829.028 295.162 52.8991 + endloop + endfacet + facet normal -0.746309 -0.200792 0.63459 + outer loop + vertex 826.046 304.777 52.3192 + vertex 827.275 300.164 52.3057 + vertex 826.792 303.757 52.8741 + endloop + endfacet + facet normal -0.765103 -0.233287 0.600162 + outer loop + vertex 824.598 309.419 52.2779 + vertex 826.046 304.777 52.3192 + vertex 826.792 303.757 52.8741 + endloop + endfacet + facet normal -0.706673 -0.222226 0.671736 + outer loop + vertex 822.847 315.174 52.34 + vertex 824.598 309.419 52.2779 + vertex 824.525 311.412 52.8603 + endloop + endfacet + facet normal -0.707406 -0.248654 0.661625 + outer loop + vertex 820.969 319.942 52.1238 + vertex 822.847 315.174 52.34 + vertex 821.83 319.363 52.8268 + endloop + endfacet + facet normal -0.709445 -0.259388 0.65529 + outer loop + vertex 818.975 325.637 52.2193 + vertex 820.969 319.942 52.1238 + vertex 821.83 319.363 52.8268 + endloop + endfacet + facet normal -0.712713 -0.273569 0.64591 + outer loop + vertex 816.928 331.276 52.3489 + vertex 818.975 325.637 52.2193 + vertex 818.981 327.453 52.9943 + endloop + endfacet + facet normal -0.718395 -0.295955 0.629539 + outer loop + vertex 814.828 335.916 52.1336 + vertex 816.928 331.276 52.3489 + vertex 815.573 335.751 52.9065 + endloop + endfacet + facet normal -0.717489 -0.303191 0.627124 + outer loop + vertex 812.543 341.501 52.2202 + vertex 814.828 335.916 52.1336 + vertex 815.573 335.751 52.9065 + endloop + endfacet + facet normal -0.719305 -0.31289 0.620242 + outer loop + vertex 810.224 347.04 52.325 + vertex 812.543 341.501 52.2202 + vertex 812.103 343.865 52.9021 + endloop + endfacet + facet normal -0.717837 -0.326745 0.614774 + outer loop + vertex 808.016 351.546 52.142 + vertex 810.224 347.04 52.325 + vertex 808.566 351.545 52.7832 + endloop + endfacet + facet normal -0.717134 -0.329424 0.614165 + outer loop + vertex 805.587 357.094 52.2804 + vertex 808.016 351.546 52.142 + vertex 808.566 351.545 52.7832 + endloop + endfacet + facet normal -0.731949 -0.339118 0.590974 + outer loop + vertex 803.176 362.617 52.4643 + vertex 805.587 357.094 52.2804 + vertex 805.203 359.116 52.9657 + endloop + endfacet + facet normal -0.733913 -0.34281 0.58639 + outer loop + vertex 800.894 367.155 52.2616 + vertex 803.176 362.617 52.4643 + vertex 801.489 367.1 52.9729 + endloop + endfacet + facet normal -0.736541 -0.331747 0.589451 + outer loop + vertex 798.292 372.764 52.1664 + vertex 800.894 367.155 52.2616 + vertex 801.489 367.1 52.9729 + endloop + endfacet + facet normal -0.768018 -0.319469 0.555057 + outer loop + vertex 795.142 379.773 51.8409 + vertex 798.292 372.764 52.1664 + vertex 797.617 375.655 52.8961 + endloop + endfacet + facet normal -0.806127 -0.246884 0.537781 + outer loop + vertex 794.163 384.78 52.6728 + vertex 795.142 379.773 51.8409 + vertex 794.278 384.776 52.8438 + endloop + endfacet + facet normal -0.833762 -0.280708 0.475441 + outer loop + vertex 796.267 384.707 56.2643 + vertex 794.393 384.772 53.016 + vertex 796.947 379.133 54.1665 + endloop + endfacet + facet normal 0.0945319 -0.675833 -0.730967 + outer loop + vertex 846.946 242.961 295.848 + vertex 847.871 242.944 295.984 + vertex 846.935 242.814 295.983 + endloop + endfacet + facet normal 0.151108 -0.678494 -0.718896 + outer loop + vertex 847.871 242.944 295.984 + vertex 848.72 243.646 295.499 + vertex 848.339 242.413 296.583 + endloop + endfacet + facet normal -0.042645 -0.334093 -0.941575 + outer loop + vertex 841.305 246.535 294.126 + vertex 842.638 245.067 294.587 + vertex 842.086 245.523 294.45 + endloop + endfacet + facet normal 0.0155385 -0.384141 -0.923144 + outer loop + vertex 842.638 245.067 294.587 + vertex 844.075 243.931 295.084 + vertex 843.478 244.257 294.938 + endloop + endfacet + facet normal 0.0837358 -0.42919 -0.899324 + outer loop + vertex 844.075 243.931 295.084 + vertex 845.547 243.187 295.576 + vertex 844.958 243.361 295.438 + endloop + endfacet + facet normal 0.0852655 -0.571997 -0.815812 + outer loop + vertex 845.547 243.187 295.576 + vertex 846.935 242.814 295.983 + vertex 846.47 242.81 295.937 + endloop + endfacet + facet normal -0.393548 -0.283784 -0.874406 + outer loop + vertex 837.911 254.021 292.673 + vertex 839.235 250.134 293.339 + vertex 838.56 251.455 293.214 + endloop + endfacet + facet normal -0.427571 -0.299149 -0.853049 + outer loop + vertex 839.235 250.134 293.339 + vertex 839.398 249.502 293.479 + vertex 838.56 251.455 293.214 + endloop + endfacet + facet normal -0.161466 -0.273764 -0.948147 + outer loop + vertex 839.398 249.502 293.479 + vertex 840.141 248.206 293.726 + vertex 839.743 248.777 293.629 + endloop + endfacet + facet normal -0.052772 -0.267134 -0.962213 + outer loop + vertex 840.141 248.206 293.726 + vertex 841.305 246.535 294.126 + vertex 840.829 247.067 294.005 + endloop + endfacet + facet normal -0.635893 -0.176542 -0.751314 + outer loop + vertex 835.472 263.309 291.695 + vertex 835.611 260.758 292.176 + vertex 835.199 262.269 292.17 + endloop + endfacet + facet normal -0.586471 -0.229296 -0.776837 + outer loop + vertex 835.611 260.758 292.176 + vertex 836.346 258.535 292.278 + vertex 835.811 259.508 292.394 + endloop + endfacet + facet normal -0.503034 -0.246992 -0.828222 + outer loop + vertex 836.346 258.535 292.278 + vertex 837.911 254.021 292.673 + vertex 836.974 255.767 292.721 + endloop + endfacet + facet normal 0.103823 -0.734278 -0.670863 + outer loop + vertex 849.677 245.899 293.443 + vertex 850.077 247.903 291.312 + vertex 850.212 247.179 292.125 + endloop + endfacet + facet normal 0.0927168 -0.673808 -0.733066 + outer loop + vertex 848.72 243.646 295.499 + vertex 849.247 244.728 294.571 + vertex 849.386 244.797 294.526 + endloop + endfacet + facet normal 0.125182 -0.711836 -0.691099 + outer loop + vertex 849.247 244.728 294.571 + vertex 849.677 245.899 293.443 + vertex 849.386 244.797 294.526 + endloop + endfacet + facet normal -0.726869 -0.178687 -0.663124 + outer loop + vertex 834.4 272.21 290.471 + vertex 835.472 263.309 291.695 + vertex 834.329 266.491 292.09 + endloop + endfacet + facet normal -0.790223 -0.158377 -0.592 + outer loop + vertex 832.617 281.913 290.256 + vertex 834.4 272.21 290.471 + vertex 832.921 275.117 291.668 + endloop + endfacet + facet normal -0.813796 -0.165448 -0.557103 + outer loop + vertex 831.073 290.476 289.967 + vertex 832.617 281.913 290.256 + vertex 831.133 284.839 291.553 + endloop + endfacet + facet normal -0.798089 -0.183672 -0.573863 + outer loop + vertex 829.198 297.905 290.198 + vertex 831.073 290.476 289.967 + vertex 829.812 290.581 291.688 + endloop + endfacet + facet normal -0.792461 -0.213997 -0.571149 + outer loop + vertex 826.829 306.795 290.154 + vertex 829.198 297.905 290.198 + vertex 827.591 299.755 291.734 + endloop + endfacet + facet normal -0.801729 -0.247392 -0.544084 + outer loop + vertex 824.399 315.208 289.908 + vertex 826.829 306.795 290.154 + vertex 824.908 310.209 291.432 + endloop + endfacet + facet normal -0.767045 -0.269844 -0.582088 + outer loop + vertex 821.515 322.865 290.159 + vertex 824.399 315.208 289.908 + vertex 822.795 315.971 291.669 + endloop + endfacet + facet normal -0.781148 -0.300684 -0.547172 + outer loop + vertex 818.576 330.905 289.937 + vertex 821.515 322.865 290.159 + vertex 819.337 326.094 291.494 + endloop + endfacet + facet normal -0.762299 -0.314118 -0.565888 + outer loop + vertex 815.308 338.41 290.173 + vertex 818.576 330.905 289.937 + vertex 816.928 331.691 291.721 + endloop + endfacet + facet normal -0.778728 -0.339177 -0.527771 + outer loop + vertex 812.009 346.355 289.935 + vertex 815.308 338.41 290.173 + vertex 813.004 341.678 291.472 + endloop + endfacet + facet normal -0.761097 -0.349427 -0.546472 + outer loop + vertex 808.328 354.023 290.159 + vertex 812.009 346.355 289.935 + vertex 810.37 347.212 291.669 + endloop + endfacet + facet normal -0.771569 -0.363442 -0.522102 + outer loop + vertex 804.694 362.161 289.864 + vertex 808.328 354.023 290.159 + vertex 805.348 358.244 291.624 + endloop + endfacet + facet normal -0.783051 -0.364716 -0.5038 + outer loop + vertex 801.157 369.425 290.103 + vertex 804.694 362.161 289.864 + vertex 802.971 363.748 291.394 + endloop + endfacet + facet normal -0.85456 -0.274574 -0.440836 + outer loop + vertex 799.582 376.503 287.186 + vertex 798.175 376.417 289.967 + vertex 796.398 384.702 288.252 + endloop + endfacet + facet normal -0.782996 -0.343976 -0.518265 + outer loop + vertex 798.175 376.417 289.967 + vertex 801.157 369.425 290.103 + vertex 798.366 373.204 291.811 + endloop + endfacet + facet normal -0.0434025 -0.780418 -0.62375 + outer loop + vertex 850.83 250.366 288.52 + vertex 851.593 252.5 285.797 + vertex 851.276 250.431 288.408 + endloop + endfacet + facet normal -0.0606557 -0.740343 -0.669487 + outer loop + vertex 850.077 247.903 291.312 + vertex 850.83 250.366 288.52 + vertex 851.276 250.431 288.408 + endloop + endfacet + facet normal 0.0760613 -0.85159 -0.518661 + outer loop + vertex 852.299 254.921 282.352 + vertex 852.87 257.186 278.717 + vertex 852.994 256.161 280.418 + endloop + endfacet + facet normal 0.0616763 -0.82245 -0.565483 + outer loop + vertex 851.593 252.5 285.797 + vertex 852.299 254.921 282.352 + vertex 852.294 253.651 284.199 + endloop + endfacet + facet normal -0.019836 -0.88879 -0.457886 + outer loop + vertex 853.21 258.963 275.578 + vertex 853.568 260.563 272.456 + vertex 853.697 258.903 275.672 + endloop + endfacet + facet normal -0.0106452 -0.869718 -0.493434 + outer loop + vertex 852.87 257.186 278.717 + vertex 853.21 258.963 275.578 + vertex 853.697 258.903 275.672 + endloop + endfacet + facet normal 0.0116652 -0.921164 -0.389 + outer loop + vertex 853.842 262.361 268.628 + vertex 854.048 264.028 264.686 + vertex 854.427 263.327 266.357 + endloop + endfacet + facet normal 0.0393718 -0.905599 -0.422304 + outer loop + vertex 853.568 260.563 272.456 + vertex 853.842 262.361 268.628 + vertex 854.177 261.427 270.661 + endloop + endfacet + facet normal -0.0568256 -0.939832 -0.336877 + outer loop + vertex 854.119 265.377 261.236 + vertex 854.275 266.632 257.707 + vertex 854.671 265.327 261.282 + endloop + endfacet + facet normal -0.0535534 -0.929622 -0.364603 + outer loop + vertex 854.048 264.028 264.686 + vertex 854.119 265.377 261.236 + vertex 854.671 265.327 261.282 + endloop + endfacet + facet normal -0.0168868 -0.956464 -0.29136 + outer loop + vertex 854.337 268.027 253.509 + vertex 854.346 269.271 249.424 + vertex 854.856 268.75 251.106 + endloop + endfacet + facet normal 0.00249392 -0.948991 -0.315294 + outer loop + vertex 854.275 266.632 257.707 + vertex 854.337 268.027 253.509 + vertex 854.948 267.359 255.524 + endloop + endfacet + facet normal -0.0454879 -0.967377 -0.249225 + outer loop + vertex 854.289 270.243 245.985 + vertex 854.335 271.168 242.384 + vertex 854.9 270.194 246.061 + endloop + endfacet + facet normal -0.0423506 -0.961689 -0.270851 + outer loop + vertex 854.346 269.271 249.424 + vertex 854.289 270.243 245.985 + vertex 854.9 270.194 246.061 + endloop + endfacet + facet normal -0.0767728 -0.973539 -0.21524 + outer loop + vertex 854.259 272.22 238.043 + vertex 854.104 273.026 234.453 + vertex 854.574 272.901 234.85 + endloop + endfacet + facet normal -0.0113533 -0.971874 -0.23523 + outer loop + vertex 854.335 271.168 242.384 + vertex 854.259 272.22 238.043 + vertex 854.881 271.773 239.857 + endloop + endfacet + facet normal -0.0158368 -0.983728 -0.178962 + outer loop + vertex 854.093 273.686 231.097 + vertex 854.05 274.464 226.823 + vertex 854.622 273.829 230.264 + endloop + endfacet + facet normal -0.0973243 -0.976582 -0.191873 + outer loop + vertex 854.104 273.026 234.453 + vertex 854.093 273.686 231.097 + vertex 854.574 272.901 234.85 + endloop + endfacet + facet normal 0.0222959 -0.987382 -0.15678 + outer loop + vertex 853.91 275.171 222.659 + vertex 853.829 275.742 219.055 + vertex 854.218 275.515 220.537 + endloop + endfacet + facet normal 0.022793 -0.985507 -0.168098 + outer loop + vertex 854.05 274.464 226.823 + vertex 853.91 275.171 222.659 + vertex 854.428 274.989 223.797 + endloop + endfacet + facet normal -0.00129688 -0.991483 -0.130231 + outer loop + vertex 853.793 276.305 215.141 + vertex 853.676 276.827 211.167 + vertex 854.053 276.665 212.4 + endloop + endfacet + facet normal 0.0248135 -0.989452 -0.142722 + outer loop + vertex 853.829 275.742 219.055 + vertex 853.793 276.305 215.141 + vertex 854.168 275.928 217.824 + endloop + endfacet + facet normal -0.0124371 -0.994595 -0.103083 + outer loop + vertex 853.621 277.257 207.481 + vertex 853.581 277.664 203.556 + vertex 854.01 277.383 206.215 + endloop + endfacet + facet normal -0.010186 -0.99325 -0.115545 + outer loop + vertex 853.676 276.827 211.167 + vertex 853.621 277.257 207.481 + vertex 853.988 276.999 209.664 + endloop + endfacet + facet normal -0.0146048 -0.996963 -0.0764906 + outer loop + vertex 853.483 278.035 199.525 + vertex 853.48 278.356 195.344 + vertex 853.892 278.135 198.149 + endloop + endfacet + facet normal -0.0201788 -0.995628 -0.0912039 + outer loop + vertex 853.581 277.664 203.556 + vertex 853.483 278.035 199.525 + vertex 853.839 277.844 201.539 + endloop + endfacet + facet normal -0.0519619 -0.997173 -0.0542817 + outer loop + vertex 853.41 278.644 191.154 + vertex 853.382 278.848 187.441 + vertex 853.712 278.747 188.966 + endloop + endfacet + facet normal -0.0337875 -0.997119 -0.0679148 + outer loop + vertex 853.48 278.356 195.344 + vertex 853.41 278.644 191.154 + vertex 853.838 278.562 192.139 + endloop + endfacet + facet normal -0.0462017 -0.998496 -0.0295249 + outer loop + vertex 853.393 279.008 183.452 + vertex 853.329 279.132 179.358 + vertex 853.664 279.075 180.739 + endloop + endfacet + facet normal -0.0448906 -0.998183 -0.0401992 + outer loop + vertex 853.382 278.848 187.441 + vertex 853.393 279.008 183.452 + vertex 853.703 278.883 186.206 + endloop + endfacet + facet normal -0.0492809 -0.998773 -0.00487636 + outer loop + vertex 853.36 279.192 175.272 + vertex 853.315 279.214 171.288 + vertex 853.644 279.191 172.54 + endloop + endfacet + facet normal -0.0410522 -0.999043 -0.0150605 + outer loop + vertex 853.329 279.132 179.358 + vertex 853.36 279.192 175.272 + vertex 853.652 279.139 177.979 + endloop + endfacet + facet normal -0.0328209 -0.999215 0.0221876 + outer loop + vertex 853.318 279.179 167.678 + vertex 853.354 279.089 163.676 + vertex 853.726 279.138 166.455 + endloop + endfacet + facet normal -0.0478451 -0.998808 0.00964569 + outer loop + vertex 853.315 279.214 171.288 + vertex 853.318 279.179 167.678 + vertex 853.63 279.185 169.829 + endloop + endfacet + facet normal -0.054143 -0.997616 0.0427907 + outer loop + vertex 853.333 278.967 159.635 + vertex 853.349 278.809 155.989 + vertex 853.659 278.856 157.459 + endloop + endfacet + facet normal -0.0429851 -0.998614 0.0303599 + outer loop + vertex 853.354 279.089 163.676 + vertex 853.333 278.967 159.635 + vertex 853.739 278.978 160.568 + endloop + endfacet + facet normal -0.0396277 -0.996964 0.0670301 + outer loop + vertex 853.421 278.579 152.05 + vertex 853.411 278.309 148.04 + vertex 853.732 278.382 149.309 + endloop + endfacet + facet normal -0.0444249 -0.997349 0.057625 + outer loop + vertex 853.349 278.809 155.989 + vertex 853.421 278.579 152.05 + vertex 853.688 278.722 154.737 + endloop + endfacet + facet normal -0.0151314 -0.995381 0.0948085 + outer loop + vertex 853.448 278.003 144.325 + vertex 853.505 277.626 140.368 + vertex 853.862 277.877 143.06 + endloop + endfacet + facet normal -0.0357111 -0.996016 0.081708 + outer loop + vertex 853.411 278.309 148.04 + vertex 853.448 278.003 144.325 + vertex 853.745 278.175 146.544 + endloop + endfacet + facet normal 0.0168583 -0.992524 0.12088 + outer loop + vertex 853.512 277.19 136.296 + vertex 853.621 276.685 132.131 + vertex 853.967 277.035 134.952 + endloop + endfacet + facet normal 0.00423704 -0.994329 0.106261 + outer loop + vertex 853.505 277.626 140.368 + vertex 853.512 277.19 136.296 + vertex 853.821 277.41 138.335 + endloop + endfacet + facet normal 0.00785777 -0.989622 0.143477 + outer loop + vertex 853.655 276.148 128.042 + vertex 853.709 275.63 124.46 + vertex 854.029 275.842 125.908 + endloop + endfacet + facet normal 0.0184 -0.991312 0.130242 + outer loop + vertex 853.621 276.685 132.131 + vertex 853.655 276.148 128.042 + vertex 854.075 276.283 129.008 + endloop + endfacet + facet normal -0.0075083 -0.985269 0.170845 + outer loop + vertex 853.822 275.006 120.562 + vertex 853.866 274.273 116.336 + vertex 854.224 274.493 117.619 + endloop + endfacet + facet normal 0.0186777 -0.987187 0.158468 + outer loop + vertex 853.709 275.63 124.46 + vertex 853.822 275.006 120.562 + vertex 854.093 275.44 123.234 + endloop + endfacet + facet normal -0.0813985 -0.976752 0.198315 + outer loop + vertex 853.945 273.507 112.296 + vertex 853.943 272.808 108.855 + vertex 854.327 272.801 108.976 + endloop + endfacet + facet normal -0.0213922 -0.982338 0.18589 + outer loop + vertex 853.866 274.273 116.336 + vertex 853.945 273.507 112.296 + vertex 854.374 273.728 113.517 + endloop + endfacet + facet normal -0.00996864 -0.971782 0.23567 + outer loop + vertex 854.018 272.042 105.44 + vertex 854.049 271.001 101.146 + vertex 854.576 271.702 104.062 + endloop + endfacet + facet normal -0.0869936 -0.972464 0.216206 + outer loop + vertex 853.943 272.808 108.855 + vertex 854.018 272.042 105.44 + vertex 854.327 272.801 108.976 + endloop + endfacet + facet normal -0.0793295 -0.958535 0.273711 + outer loop + vertex 854.029 269.872 96.8684 + vertex 853.925 268.898 93.427 + vertex 854.423 268.905 93.5975 + endloop + endfacet + facet normal 0.00143487 -0.966905 0.255133 + outer loop + vertex 854.049 271.001 101.146 + vertex 854.029 269.872 96.8684 + vertex 854.645 270.29 98.4504 + endloop + endfacet + facet normal -0.005267 -0.948347 0.317192 + outer loop + vertex 853.942 267.844 90.0725 + vertex 853.835 266.447 85.8936 + vertex 854.527 267.326 88.5334 + endloop + endfacet + facet normal -0.0877807 -0.950508 0.298042 + outer loop + vertex 853.925 268.898 93.427 + vertex 853.942 267.844 90.0725 + vertex 854.423 268.905 93.5975 + endloop + endfacet + facet normal -0.0575556 -0.928699 0.366341 + outer loop + vertex 853.624 265.185 82.3545 + vertex 853.502 263.895 79.0648 + vertex 854.197 265.247 82.6019 + endloop + endfacet + facet normal -0.044099 -0.94011 0.338005 + outer loop + vertex 853.835 266.447 85.8936 + vertex 853.624 265.185 82.3545 + vertex 854.197 265.247 82.6019 + endloop + endfacet + facet normal 0.0622164 -0.907015 0.416478 + outer loop + vertex 853.234 262.224 75.0984 + vertex 852.873 260.388 71.1556 + vertex 853.496 261.245 72.9269 + endloop + endfacet + facet normal 0.024534 -0.921881 0.386695 + outer loop + vertex 853.502 263.895 79.0648 + vertex 853.234 262.224 75.0984 + vertex 853.867 263.201 77.389 + endloop + endfacet + facet normal 0.00425187 -0.873027 0.487653 + outer loop + vertex 852.437 258.739 67.9128 + vertex 852.031 257.022 64.8424 + vertex 852.889 258.696 67.8324 + endloop + endfacet + facet normal -0.00349721 -0.891102 0.453789 + outer loop + vertex 852.873 260.388 71.1556 + vertex 852.437 258.739 67.9128 + vertex 852.889 258.696 67.8324 + endloop + endfacet + facet normal 0.0864605 -0.832648 0.547011 + outer loop + vertex 851.376 254.836 61.2563 + vertex 850.575 252.475 57.7895 + vertex 851.315 253.689 59.5201 + endloop + endfacet + facet normal 0.0657936 -0.857351 0.510511 + outer loop + vertex 852.031 257.022 64.8424 + vertex 851.376 254.836 61.2563 + vertex 852.084 256.069 63.2361 + endloop + endfacet + facet normal 0.0879127 -0.777613 0.622566 + outer loop + vertex 849.633 249.83 54.3155 + vertex 849.094 247.752 51.7966 + vertex 849.558 248.713 52.9314 + endloop + endfacet + facet normal 0.110685 -0.804928 0.582957 + outer loop + vertex 850.575 252.475 57.7895 + vertex 849.633 249.83 54.3155 + vertex 850.449 251.195 56.0451 + endloop + endfacet + facet normal -0.799081 -0.212047 0.562589 + outer loop + vertex 837.56 265.74 56.095 + vertex 836.31 270.931 56.2752 + vertex 836.411 265.502 54.3729 + endloop + endfacet + facet normal -0.820371 -0.181396 0.542298 + outer loop + vertex 836.31 270.931 56.2752 + vertex 834.697 279.187 56.5964 + vertex 834.425 271.895 53.7464 + endloop + endfacet + facet normal -0.845112 -0.173725 0.505574 + outer loop + vertex 834.697 279.187 56.5964 + vertex 832.508 289.696 56.5496 + vertex 832.446 282.916 54.1154 + endloop + endfacet + facet normal -0.834756 -0.186197 0.518183 + outer loop + vertex 832.508 289.696 56.5496 + vertex 831.237 298.102 57.5227 + vertex 829.225 298.691 54.4932 + endloop + endfacet + facet normal -0.832048 -0.217478 0.510294 + outer loop + vertex 831.237 298.102 57.5227 + vertex 828.416 306.454 56.4819 + vertex 829.225 298.691 54.4932 + endloop + endfacet + facet normal -0.817307 -0.249094 0.519578 + outer loop + vertex 828.416 306.454 56.4819 + vertex 825.794 315.659 56.7705 + vertex 824.706 313.647 54.094 + endloop + endfacet + facet normal -0.805152 -0.278102 0.523823 + outer loop + vertex 825.794 315.659 56.7705 + vertex 823.178 323.637 56.9852 + vertex 822.032 321.814 54.2558 + endloop + endfacet + facet normal -0.794147 -0.305579 0.525311 + outer loop + vertex 823.178 323.637 56.9852 + vertex 821.23 329.773 57.6087 + vertex 818.917 330.705 54.6545 + endloop + endfacet + facet normal -0.79097 -0.330356 0.515005 + outer loop + vertex 821.23 329.773 57.6087 + vertex 818.156 336.209 57.0159 + vertex 818.917 330.705 54.6545 + endloop + endfacet + facet normal -0.793657 -0.351969 0.496213 + outer loop + vertex 818.156 336.209 57.0159 + vertex 814.474 344.151 56.7604 + vertex 814.837 339.817 54.2675 + endloop + endfacet + facet normal -0.795554 -0.365917 0.482906 + outer loop + vertex 814.474 344.151 56.7604 + vertex 810.146 353.102 56.4125 + vertex 811.108 347.92 54.0716 + endloop + endfacet + facet normal -0.804025 -0.380293 0.457079 + outer loop + vertex 810.146 353.102 56.4125 + vertex 807.588 359.799 57.4864 + vertex 805.012 361.719 54.5527 + endloop + endfacet + facet normal -0.803538 -0.38709 0.452203 + outer loop + vertex 807.588 359.799 57.4864 + vertex 804.103 366.462 56.9975 + vertex 805.012 361.719 54.5527 + endloop + endfacet + facet normal -0.812719 -0.378143 0.443279 + outer loop + vertex 804.103 366.462 56.9975 + vertex 800.283 374.516 56.863 + vertex 800.626 370.833 54.3508 + endloop + endfacet + facet normal -0.811503 -0.289987 0.507317 + outer loop + vertex 800.283 374.516 56.863 + vertex 796.267 384.707 56.2643 + vertex 796.947 379.133 54.1665 + endloop + endfacet + facet normal -0.281501 -0.59424 0.753416 + outer loop + vertex 848.021 245.05 48.9381 + vertex 847.536 243.959 47.8967 + vertex 847.56 243.901 47.8596 + endloop + endfacet + facet normal -0.188316 -0.581012 0.791809 + outer loop + vertex 847.536 243.959 47.8967 + vertex 847.269 243.485 47.4846 + vertex 847.56 243.901 47.8596 + endloop + endfacet + facet normal -0.272804 -0.667288 0.69304 + outer loop + vertex 849.094 247.752 51.7966 + vertex 848.561 246.35 50.2364 + vertex 848.634 246.294 50.2113 + endloop + endfacet + facet normal -0.234771 -0.636475 0.734699 + outer loop + vertex 848.561 246.35 50.2364 + vertex 848.021 245.05 48.9381 + vertex 848.634 246.294 50.2113 + endloop + endfacet + facet normal -0.79222 -0.189272 0.580141 + outer loop + vertex 835.782 263.946 53.0064 + vertex 836.411 265.502 54.3729 + vertex 834.425 271.895 53.7464 + endloop + endfacet + facet normal -0.0185155 -0.591767 0.805896 + outer loop + vertex 846.66 243.089 47.2424 + vertex 846.468 242.803 47.0284 + vertex 847.56 243.901 47.8596 + endloop + endfacet + facet normal -0.220712 0.733078 -0.643337 + outer loop + vertex 847.269 243.485 47.4846 + vertex 846.66 243.089 47.2424 + vertex 847.56 243.901 47.8596 + endloop + endfacet + facet normal -0.398651 -0.128145 0.908106 + outer loop + vertex 835.082 262.578 51.9405 + vertex 833.803 269.794 52.3972 + vertex 834.304 265.728 52.0438 + endloop + endfacet + facet normal -0.842718 -0.168457 0.51132 + outer loop + vertex 832.446 282.916 54.1154 + vertex 834.425 271.895 53.7464 + vertex 834.697 279.187 56.5964 + endloop + endfacet + facet normal -0.728131 -0.146709 0.669553 + outer loop + vertex 833.803 269.794 52.3972 + vertex 832.335 278.69 52.7506 + vertex 832.606 274.612 52.152 + endloop + endfacet + facet normal -0.84549 -0.17352 0.505013 + outer loop + vertex 830.705 290.707 53.8774 + vertex 832.446 282.916 54.1154 + vertex 832.508 289.696 56.5496 + endloop + endfacet + facet normal -0.777453 -0.152687 0.610126 + outer loop + vertex 832.335 278.69 52.7506 + vertex 830.819 287.084 52.9189 + vertex 830.87 284.433 52.3204 + endloop + endfacet + facet normal -0.845585 -0.195002 0.496952 + outer loop + vertex 829.225 298.691 54.4932 + vertex 830.705 290.707 53.8774 + vertex 832.508 289.696 56.5496 + endloop + endfacet + facet normal -0.770578 -0.169322 0.614442 + outer loop + vertex 830.819 287.084 52.9189 + vertex 829.028 295.162 52.8991 + vertex 829.511 290.687 52.2721 + endloop + endfacet + facet normal -0.822865 -0.220011 0.523916 + outer loop + vertex 826.605 306.821 53.7914 + vertex 829.225 298.691 54.4932 + vertex 828.416 306.454 56.4819 + endloop + endfacet + facet normal -0.772788 -0.199287 0.602564 + outer loop + vertex 829.028 295.162 52.8991 + vertex 826.792 303.757 52.8741 + vertex 827.275 300.164 52.3057 + endloop + endfacet + facet normal -0.818567 -0.250654 0.516837 + outer loop + vertex 824.706 313.647 54.094 + vertex 826.605 306.821 53.7914 + vertex 828.416 306.454 56.4819 + endloop + endfacet + facet normal -0.73213 -0.21567 0.64612 + outer loop + vertex 826.792 303.757 52.8741 + vertex 824.525 311.412 52.8603 + vertex 824.598 309.419 52.2779 + endloop + endfacet + facet normal -0.801938 -0.273062 0.531349 + outer loop + vertex 822.032 321.814 54.2558 + vertex 824.706 313.647 54.094 + vertex 825.794 315.659 56.7705 + endloop + endfacet + facet normal -0.756038 -0.253695 0.603362 + outer loop + vertex 824.525 311.412 52.8603 + vertex 821.83 319.363 52.8268 + vertex 822.847 315.174 52.34 + endloop + endfacet + facet normal -0.790741 -0.300973 0.533051 + outer loop + vertex 818.917 330.705 54.6545 + vertex 822.032 321.814 54.2558 + vertex 823.178 323.637 56.9852 + endloop + endfacet + facet normal -0.725046 -0.26853 0.634193 + outer loop + vertex 821.83 319.363 52.8268 + vertex 818.981 327.453 52.9943 + vertex 818.975 325.637 52.2193 + endloop + endfacet + facet normal -0.788866 -0.331212 0.517677 + outer loop + vertex 814.837 339.817 54.2675 + vertex 818.917 330.705 54.6545 + vertex 818.156 336.209 57.0159 + endloop + endfacet + facet normal -0.745761 -0.299922 0.594885 + outer loop + vertex 818.981 327.453 52.9943 + vertex 815.573 335.751 52.9065 + vertex 816.928 331.276 52.3489 + endloop + endfacet + facet normal -0.792469 -0.352673 0.49761 + outer loop + vertex 811.108 347.92 54.0716 + vertex 814.837 339.817 54.2675 + vertex 814.474 344.151 56.7604 + endloop + endfacet + facet normal -0.729287 -0.311552 0.609159 + outer loop + vertex 815.573 335.751 52.9065 + vertex 812.103 343.865 52.9021 + vertex 812.543 341.501 52.2202 + endloop + endfacet + facet normal -0.796122 -0.365681 0.482149 + outer loop + vertex 807.785 354.744 53.7605 + vertex 811.108 347.92 54.0716 + vertex 810.146 353.102 56.4125 + endloop + endfacet + facet normal -0.740553 -0.332002 0.584257 + outer loop + vertex 812.103 343.865 52.9021 + vertex 808.566 351.545 52.7832 + vertex 810.224 347.04 52.325 + endloop + endfacet + facet normal -0.79583 -0.370733 0.478761 + outer loop + vertex 805.012 361.719 54.5527 + vertex 807.785 354.744 53.7605 + vertex 810.146 353.102 56.4125 + endloop + endfacet + facet normal -0.731512 -0.339202 0.591466 + outer loop + vertex 808.566 351.545 52.7832 + vertex 805.203 359.116 52.9657 + vertex 805.587 357.094 52.2804 + endloop + endfacet + facet normal -0.813653 -0.38188 0.438334 + outer loop + vertex 800.626 370.833 54.3508 + vertex 805.012 361.719 54.5527 + vertex 804.103 366.462 56.9975 + endloop + endfacet + facet normal -0.73731 -0.343554 0.581674 + outer loop + vertex 805.203 359.116 52.9657 + vertex 801.489 367.1 52.9729 + vertex 803.176 362.617 52.4643 + endloop + endfacet + facet normal -0.83514 -0.360959 0.415029 + outer loop + vertex 796.947 379.133 54.1665 + vertex 800.626 370.833 54.3508 + vertex 800.283 374.516 56.863 + endloop + endfacet + facet normal -0.725431 -0.322853 0.607878 + outer loop + vertex 801.489 367.1 52.9729 + vertex 797.617 375.655 52.8961 + vertex 798.292 372.764 52.1664 + endloop + endfacet + facet normal -0.705182 -0.254332 0.661841 + outer loop + vertex 797.617 375.655 52.8961 + vertex 794.278 384.776 52.8438 + vertex 795.142 379.773 51.8409 + endloop + endfacet + facet normal 0.269235 -0.689721 0.672158 + outer loop + vertex 846.468 242.803 47.0284 + vertex 846.23 242.522 46.8347 + vertex 847.08 242.431 46.4005 + endloop + endfacet + facet normal 0.111619 -0.709022 0.696297 + outer loop + vertex 846.23 242.522 46.8347 + vertex 845.559 242.636 47.0584 + vertex 845.869 242.544 46.9149 + endloop + endfacet + facet normal -0.237806 -0.61085 0.755189 + outer loop + vertex 842.318 244.557 48.5916 + vertex 841.085 245.787 49.1978 + vertex 841.886 244.871 48.7091 + endloop + endfacet + facet normal -0.564189 -0.818497 0.108415 + outer loop + vertex 843.477 243.68 47.9946 + vertex 842.318 244.557 48.5916 + vertex 841.886 244.871 48.7091 + endloop + endfacet + facet normal 0.108785 -0.515479 0.849969 + outer loop + vertex 844.832 242.899 47.3475 + vertex 843.477 243.68 47.9946 + vertex 843.753 243.421 47.8027 + endloop + endfacet + facet normal 0.070459 -0.681929 0.728017 + outer loop + vertex 845.869 242.544 46.9149 + vertex 844.832 242.899 47.3475 + vertex 845.267 242.711 47.1302 + endloop + endfacet + facet normal -0.417694 -0.294085 0.859678 + outer loop + vertex 838.694 250.088 50.4603 + vertex 837.62 253.004 50.9363 + vertex 838.096 251.363 50.6063 + endloop + endfacet + facet normal -0.600809 -0.362964 0.71224 + outer loop + vertex 839 249.158 50.2447 + vertex 838.694 250.088 50.4603 + vertex 838.096 251.363 50.6063 + endloop + endfacet + facet normal -0.314594 -0.387706 0.866438 + outer loop + vertex 839.873 247.468 49.8055 + vertex 839 249.158 50.2447 + vertex 839.124 248.76 50.1115 + endloop + endfacet + facet normal -0.298824 -0.50752 0.808163 + outer loop + vertex 841.085 245.787 49.1978 + vertex 839.873 247.468 49.8055 + vertex 840.218 246.859 49.5507 + endloop + endfacet + facet normal 0.0378177 -0.0635791 0.99726 + outer loop + vertex 835.613 259.724 51.7384 + vertex 835.082 262.578 51.9405 + vertex 835.074 261.965 51.9017 + endloop + endfacet + facet normal 0.126785 -0.0685081 0.989562 + outer loop + vertex 836.493 256.529 51.4044 + vertex 835.613 259.724 51.7384 + vertex 835.766 259.032 51.6708 + endloop + endfacet + facet normal -0.70563 -0.310202 0.637072 + outer loop + vertex 837.62 253.004 50.9363 + vertex 836.493 256.529 51.4044 + vertex 836.673 255.808 51.252 + endloop + endfacet + facet normal -0.784333 -0.282575 -0.552244 + outer loop + vertex 795.662 379.876 291.767 + vertex 796.398 384.702 288.252 + vertex 798.175 376.417 289.967 + endloop + endfacet + facet normal 0.0986152 -0.705468 -0.701848 + outer loop + vertex 848.339 242.413 296.583 + vertex 846.935 242.814 295.983 + vertex 847.871 242.944 295.984 + endloop + endfacet + facet normal -0.0245552 -0.986914 0.159364 + outer loop + vertex 845.869 242.544 46.9149 + vertex 847.08 242.431 46.4005 + vertex 846.23 242.522 46.8347 + endloop + endfacet + facet normal -0.820598 -0.202571 0.5344 + outer loop + vertex 836.411 265.502 54.3729 + vertex 836.31 270.931 56.2752 + vertex 834.425 271.895 53.7464 + endloop + endfacet + facet normal -0.119085 -0.692016 -0.711993 + outer loop + vertex -847.669 243.341 295.586 + vertex -847.403 243.068 295.807 + vertex -848.239 243.372 295.651 + endloop + endfacet + facet normal -0.152156 -0.68011 -0.717147 + outer loop + vertex -848.772 243.781 295.377 + vertex -848.239 243.372 295.651 + vertex -848.033 243.023 295.939 + endloop + endfacet + facet normal -0.0983267 -0.698196 -0.709122 + outer loop + vertex -846.948 242.928 295.882 + vertex -848.033 243.023 295.939 + vertex -847.403 243.068 295.807 + endloop + endfacet + facet normal -0.10602 -0.668509 -0.736108 + outer loop + vertex -848.239 243.372 295.651 + vertex -847.403 243.068 295.807 + vertex -848.033 243.023 295.939 + endloop + endfacet + facet normal -0.0406066 -0.714265 -0.698696 + outer loop + vertex -849.058 245.842 293.445 + vertex -849.392 245.739 293.569 + vertex -849.06 246.914 292.35 + endloop + endfacet + facet normal 0.00196064 -0.723499 -0.690323 + outer loop + vertex -849.406 248.292 290.905 + vertex -849.06 246.914 292.35 + vertex -850.073 247.865 291.35 + endloop + endfacet + facet normal -0.132777 -0.735887 -0.663959 + outer loop + vertex -849.773 246.137 293.205 + vertex -850.073 247.865 291.35 + vertex -849.392 245.739 293.569 + endloop + endfacet + facet normal 0.00635878 -0.721253 -0.692643 + outer loop + vertex -849.06 246.914 292.35 + vertex -849.392 245.739 293.569 + vertex -850.073 247.865 291.35 + endloop + endfacet + facet normal -0.0564432 -0.690174 -0.721439 + outer loop + vertex -849.058 245.842 293.445 + vertex -848.801 245.139 294.097 + vertex -849.392 245.739 293.569 + endloop + endfacet + facet normal -0.105479 -0.682581 -0.723158 + outer loop + vertex -848.378 244.45 294.686 + vertex -848.828 244.306 294.887 + vertex -848.801 245.139 294.097 + endloop + endfacet + facet normal -0.049177 -0.686534 -0.725433 + outer loop + vertex -848.828 244.306 294.887 + vertex -849.392 245.739 293.569 + vertex -848.801 245.139 294.097 + endloop + endfacet + facet normal -0.0534028 -0.702151 -0.710022 + outer loop + vertex -849.773 246.137 293.205 + vertex -849.392 245.739 293.569 + vertex -849.362 244.951 294.346 + endloop + endfacet + facet normal -0.131395 -0.698606 -0.703338 + outer loop + vertex -849.362 244.951 294.346 + vertex -849.392 245.739 293.569 + vertex -848.828 244.306 294.887 + endloop + endfacet + facet normal -0.0935823 -0.684105 -0.723355 + outer loop + vertex -849.362 244.951 294.346 + vertex -848.828 244.306 294.887 + vertex -848.772 243.781 295.377 + endloop + endfacet + facet normal -0.155221 -0.682282 -0.714421 + outer loop + vertex -848.772 243.781 295.377 + vertex -848.828 244.306 294.887 + vertex -848.239 243.372 295.651 + endloop + endfacet + facet normal -0.114097 -0.670089 -0.733459 + outer loop + vertex -848.378 244.45 294.686 + vertex -848.107 243.81 295.229 + vertex -848.828 244.306 294.887 + endloop + endfacet + facet normal -0.120207 -0.670709 -0.731915 + outer loop + vertex -847.669 243.341 295.586 + vertex -848.239 243.372 295.651 + vertex -848.107 243.81 295.229 + endloop + endfacet + facet normal -0.116072 -0.671717 -0.731658 + outer loop + vertex -848.239 243.372 295.651 + vertex -848.828 244.306 294.887 + vertex -848.107 243.81 295.229 + endloop + endfacet + facet normal 0.0634334 -0.789422 -0.610564 + outer loop + vertex -851.085 252.966 285.247 + vertex -850.816 251.784 286.803 + vertex -851.592 252.497 285.801 + endloop + endfacet + facet normal 0.065868 -0.76915 -0.635665 + outer loop + vertex -850.331 250.715 288.146 + vertex -850.827 250.354 288.532 + vertex -850.816 251.784 286.803 + endloop + endfacet + facet normal 0.11361 -0.765984 -0.632741 + outer loop + vertex -850.827 250.354 288.532 + vertex -851.592 252.497 285.801 + vertex -850.816 251.784 286.803 + endloop + endfacet + facet normal 0.0385447 -0.753586 -0.656219 + outer loop + vertex -850.331 250.715 288.146 + vertex -849.98 249.454 289.615 + vertex -850.827 250.354 288.532 + endloop + endfacet + facet normal 0.0213961 -0.737695 -0.674795 + outer loop + vertex -849.406 248.292 290.905 + vertex -850.073 247.865 291.35 + vertex -849.98 249.454 289.615 + endloop + endfacet + facet normal 0.0754105 -0.737214 -0.671438 + outer loop + vertex -850.073 247.865 291.35 + vertex -850.827 250.354 288.532 + vertex -849.98 249.454 289.615 + endloop + endfacet + facet normal 0.0778775 -0.848464 -0.523493 + outer loop + vertex -852.287 257.329 278.574 + vertex -852.112 256.253 280.344 + vertex -852.87 257.189 278.714 + endloop + endfacet + facet normal 0.0883995 -0.834262 -0.544236 + outer loop + vertex -851.742 255.211 282.003 + vertex -852.297 254.929 282.344 + vertex -852.112 256.253 280.344 + endloop + endfacet + facet normal 0.131118 -0.832119 -0.538875 + outer loop + vertex -852.297 254.929 282.344 + vertex -852.87 257.189 278.714 + vertex -852.112 256.253 280.344 + endloop + endfacet + facet normal 0.0673469 -0.820735 -0.567325 + outer loop + vertex -851.742 255.211 282.003 + vertex -851.511 254.037 283.729 + vertex -852.297 254.929 282.344 + endloop + endfacet + facet normal 0.095029 -0.800812 -0.591328 + outer loop + vertex -851.085 252.966 285.247 + vertex -851.592 252.497 285.801 + vertex -851.511 254.037 283.729 + endloop + endfacet + facet normal 0.129495 -0.798324 -0.58814 + outer loop + vertex -851.592 252.497 285.801 + vertex -852.297 254.929 282.344 + vertex -851.511 254.037 283.729 + endloop + endfacet + facet normal 0.0916684 -0.886895 -0.452785 + outer loop + vertex -853.041 260.949 271.807 + vertex -852.966 260.051 273.581 + vertex -853.569 260.562 272.458 + endloop + endfacet + facet normal 0.0898637 -0.879026 -0.468228 + outer loop + vertex -852.705 259.225 275.183 + vertex -853.205 258.965 275.574 + vertex -852.966 260.051 273.581 + endloop + endfacet + facet normal 0.120111 -0.877716 -0.463884 + outer loop + vertex -853.205 258.965 275.574 + vertex -853.569 260.562 272.458 + vertex -852.966 260.051 273.581 + endloop + endfacet + facet normal 0.0725797 -0.871366 -0.485235 + outer loop + vertex -852.705 259.225 275.183 + vertex -852.592 258.262 276.929 + vertex -853.205 258.965 275.574 + endloop + endfacet + facet normal 0.0855184 -0.859958 -0.503149 + outer loop + vertex -852.287 257.329 278.574 + vertex -852.87 257.189 278.714 + vertex -852.592 258.262 276.929 + endloop + endfacet + facet normal 0.114963 -0.859398 -0.498215 + outer loop + vertex -852.87 257.189 278.714 + vertex -853.205 258.965 275.574 + vertex -852.592 258.262 276.929 + endloop + endfacet + facet normal 0.14933 -0.910676 -0.385189 + outer loop + vertex -853.5 264.162 264.579 + vertex -853.487 263.351 266.501 + vertex -854.045 264.03 264.68 + endloop + endfacet + facet normal 0.135442 -0.906545 -0.399789 + outer loop + vertex -853.294 262.598 268.274 + vertex -853.845 262.358 268.631 + vertex -853.487 263.351 266.501 + endloop + endfacet + facet normal 0.177759 -0.903042 -0.391046 + outer loop + vertex -853.845 262.358 268.631 + vertex -854.045 264.03 264.68 + vertex -853.487 263.351 266.501 + endloop + endfacet + facet normal 0.119612 -0.899783 -0.419622 + outer loop + vertex -853.294 262.598 268.274 + vertex -853.251 261.738 270.13 + vertex -853.845 262.358 268.631 + endloop + endfacet + facet normal 0.117852 -0.892686 -0.434998 + outer loop + vertex -853.041 260.949 271.807 + vertex -853.569 260.562 272.458 + vertex -853.251 261.738 270.13 + endloop + endfacet + facet normal 0.153098 -0.89026 -0.428951 + outer loop + vertex -853.569 260.562 272.458 + vertex -853.845 262.358 268.631 + vertex -853.251 261.738 270.13 + endloop + endfacet + facet normal 0.175623 -0.927606 -0.329702 + outer loop + vertex -853.741 266.967 257.05 + vertex -853.78 266.255 259.033 + vertex -854.274 266.634 257.702 + endloop + endfacet + facet normal 0.176244 -0.923398 -0.34099 + outer loop + vertex -853.646 265.616 260.833 + vertex -854.117 265.378 261.234 + vertex -853.78 266.255 259.033 + endloop + endfacet + facet normal 0.198979 -0.920479 -0.336341 + outer loop + vertex -854.117 265.378 261.234 + vertex -854.274 266.634 257.702 + vertex -853.78 266.255 259.033 + endloop + endfacet + facet normal 0.161933 -0.920352 -0.355993 + outer loop + vertex -853.646 265.616 260.833 + vertex -853.657 264.865 262.768 + vertex -854.117 265.378 261.234 + endloop + endfacet + facet normal 0.153698 -0.916546 -0.369215 + outer loop + vertex -853.5 264.162 264.579 + vertex -854.045 264.03 264.68 + vertex -853.657 264.865 262.768 + endloop + endfacet + facet normal 0.186829 -0.913581 -0.3612 + outer loop + vertex -854.045 264.03 264.68 + vertex -854.117 265.378 261.234 + vertex -853.657 264.865 262.768 + endloop + endfacet + facet normal 0.202943 -0.938149 -0.280518 + outer loop + vertex -853.821 269.417 249.316 + vertex -853.885 268.815 251.284 + vertex -854.345 269.271 249.424 + endloop + endfacet + facet normal 0.200043 -0.935726 -0.290517 + outer loop + vertex -853.789 268.252 253.163 + vertex -854.334 268.03 253.502 + vertex -853.885 268.815 251.284 + endloop + endfacet + facet normal 0.224309 -0.932118 -0.284327 + outer loop + vertex -854.334 268.03 253.502 + vertex -854.345 269.271 249.424 + vertex -853.885 268.815 251.284 + endloop + endfacet + facet normal 0.189378 -0.933041 -0.305892 + outer loop + vertex -853.789 268.252 253.163 + vertex -853.845 267.576 255.19 + vertex -854.334 268.03 253.502 + endloop + endfacet + facet normal 0.194494 -0.928958 -0.314976 + outer loop + vertex -853.741 266.967 257.05 + vertex -854.274 266.634 257.702 + vertex -853.845 267.576 255.19 + endloop + endfacet + facet normal 0.21279 -0.926328 -0.310866 + outer loop + vertex -854.274 266.634 257.702 + vertex -854.334 268.03 253.502 + vertex -853.845 267.576 255.19 + endloop + endfacet + facet normal 0.171002 -0.955539 -0.240216 + outer loop + vertex -853.822 271.395 241.845 + vertex -853.905 270.881 243.831 + vertex -854.338 271.166 242.389 + endloop + endfacet + facet normal 0.202485 -0.94814 -0.24501 + outer loop + vertex -853.834 270.433 245.625 + vertex -854.285 270.245 245.979 + vertex -853.905 270.881 243.831 + endloop + endfacet + facet normal 0.195988 -0.949131 -0.246454 + outer loop + vertex -854.285 270.245 245.979 + vertex -854.338 271.166 242.389 + vertex -853.905 270.881 243.831 + endloop + endfacet + facet normal 0.192886 -0.947057 -0.256668 + outer loop + vertex -853.834 270.433 245.625 + vertex -853.904 269.905 247.52 + vertex -854.285 270.245 245.979 + endloop + endfacet + facet normal 0.207042 -0.941667 -0.265324 + outer loop + vertex -853.821 269.417 249.316 + vertex -854.345 269.271 249.424 + vertex -853.904 269.905 247.52 + endloop + endfacet + facet normal 0.219858 -0.939767 -0.261727 + outer loop + vertex -854.345 269.271 249.424 + vertex -854.285 270.245 245.979 + vertex -853.904 269.905 247.52 + endloop + endfacet + facet normal 0.174971 -0.963531 -0.202467 + outer loop + vertex -853.691 273.2 233.983 + vertex -853.8 272.765 235.956 + vertex -854.109 273.023 234.459 + endloop + endfacet + facet normal 0.176226 -0.961181 -0.21231 + outer loop + vertex -853.769 272.355 237.837 + vertex -854.255 272.222 238.037 + vertex -853.8 272.765 235.956 + endloop + endfacet + facet normal 0.199086 -0.957983 -0.20648 + outer loop + vertex -854.255 272.222 238.037 + vertex -854.109 273.023 234.459 + vertex -853.8 272.765 235.956 + endloop + endfacet + facet normal 0.170742 -0.959404 -0.224481 + outer loop + vertex -853.769 272.355 237.837 + vertex -853.872 271.851 239.913 + vertex -854.255 272.222 238.037 + endloop + endfacet + facet normal 0.181699 -0.956012 -0.230274 + outer loop + vertex -853.822 271.395 241.845 + vertex -854.338 271.166 242.389 + vertex -853.872 271.851 239.913 + endloop + endfacet + facet normal 0.192186 -0.954531 -0.227892 + outer loop + vertex -854.338 271.166 242.389 + vertex -854.255 272.222 238.037 + vertex -853.872 271.851 239.913 + endloop + endfacet + facet normal 0.164326 -0.972218 -0.166704 + outer loop + vertex -853.5 274.654 226.259 + vertex -853.611 274.28 228.33 + vertex -854.051 274.464 226.824 + endloop + endfacet + facet normal 0.204055 -0.963842 -0.171376 + outer loop + vertex -853.591 273.95 230.21 + vertex -854.093 273.686 231.096 + vertex -853.611 274.28 228.33 + endloop + endfacet + facet normal 0.191801 -0.965895 -0.173949 + outer loop + vertex -854.093 273.686 231.096 + vertex -854.051 274.464 226.824 + vertex -853.611 274.28 228.33 + endloop + endfacet + facet normal 0.182578 -0.965798 -0.184117 + outer loop + vertex -853.591 273.95 230.21 + vertex -853.719 273.546 232.2 + vertex -854.093 273.686 231.096 + endloop + endfacet + facet normal 0.18858 -0.963409 -0.190477 + outer loop + vertex -853.691 273.2 233.983 + vertex -854.109 273.023 234.459 + vertex -853.719 273.546 232.2 + endloop + endfacet + facet normal 0.197373 -0.962008 -0.188637 + outer loop + vertex -854.109 273.023 234.459 + vertex -854.093 273.686 231.096 + vertex -853.719 273.546 232.2 + endloop + endfacet + facet normal 0.152038 -0.977145 -0.148567 + outer loop + vertex -853.381 275.872 218.656 + vertex -853.484 275.56 220.603 + vertex -853.829 275.742 219.055 + endloop + endfacet + facet normal 0.156333 -0.975981 -0.151729 + outer loop + vertex -853.445 275.285 222.414 + vertex -853.908 275.173 222.654 + vertex -853.484 275.56 220.603 + endloop + endfacet + facet normal 0.161671 -0.975301 -0.150498 + outer loop + vertex -853.908 275.173 222.654 + vertex -853.829 275.742 219.055 + vertex -853.484 275.56 220.603 + endloop + endfacet + facet normal 0.153524 -0.9756 -0.156958 + outer loop + vertex -853.445 275.285 222.414 + vertex -853.54 274.952 224.388 + vertex -853.908 275.173 222.654 + endloop + endfacet + facet normal 0.17251 -0.97214 -0.158697 + outer loop + vertex -853.5 274.654 226.259 + vertex -854.051 274.464 226.824 + vertex -853.54 274.952 224.388 + endloop + endfacet + facet normal 0.168237 -0.972723 -0.15971 + outer loop + vertex -854.051 274.464 226.824 + vertex -853.908 275.173 222.654 + vertex -853.54 274.952 224.388 + endloop + endfacet + facet normal 0.172846 -0.977304 -0.122479 + outer loop + vertex -853.24 276.959 210.729 + vertex -853.339 276.683 212.794 + vertex -853.676 276.827 211.169 + endloop + endfacet + facet normal 0.158515 -0.979144 -0.127083 + outer loop + vertex -853.304 276.439 214.718 + vertex -853.792 276.305 215.142 + vertex -853.339 276.683 212.794 + endloop + endfacet + facet normal 0.176576 -0.976548 -0.123185 + outer loop + vertex -853.792 276.305 215.142 + vertex -853.676 276.827 211.169 + vertex -853.339 276.683 212.794 + endloop + endfacet + facet normal 0.151822 -0.979171 -0.13481 + outer loop + vertex -853.304 276.439 214.718 + vertex -853.405 276.141 216.769 + vertex -853.792 276.305 215.142 + endloop + endfacet + facet normal 0.158584 -0.977192 -0.141233 + outer loop + vertex -853.381 275.872 218.656 + vertex -853.829 275.742 219.055 + vertex -853.405 276.141 216.769 + endloop + endfacet + facet normal 0.170174 -0.975589 -0.138806 + outer loop + vertex -853.829 275.742 219.055 + vertex -853.792 276.305 215.142 + vertex -853.405 276.141 216.769 + endloop + endfacet + facet normal 0.193435 -0.976354 -0.0965235 + outer loop + vertex -853.114 277.821 202.891 + vertex -853.216 277.595 204.973 + vertex -853.58 277.662 203.561 + endloop + endfacet + facet normal 0.196388 -0.975441 -0.0997292 + outer loop + vertex -853.182 277.411 206.838 + vertex -853.62 277.257 207.481 + vertex -853.216 277.595 204.973 + endloop + endfacet + facet normal 0.202094 -0.974383 -0.0986668 + outer loop + vertex -853.62 277.257 207.481 + vertex -853.58 277.662 203.561 + vertex -853.216 277.595 204.973 + endloop + endfacet + facet normal 0.185649 -0.976733 -0.107365 + outer loop + vertex -853.182 277.411 206.838 + vertex -853.275 277.171 208.864 + vertex -853.62 277.257 207.481 + endloop + endfacet + facet normal 0.181073 -0.976819 -0.114181 + outer loop + vertex -853.24 276.959 210.729 + vertex -853.676 276.827 211.169 + vertex -853.275 277.171 208.864 + endloop + endfacet + facet normal 0.199225 -0.973697 -0.11056 + outer loop + vertex -853.676 276.827 211.169 + vertex -853.62 277.257 207.481 + vertex -853.275 277.171 208.864 + endloop + endfacet + facet normal 0.210093 -0.975065 -0.0714732 + outer loop + vertex -853.019 278.489 194.894 + vertex -853.1 278.318 196.991 + vertex -853.479 278.357 195.339 + endloop + endfacet + facet normal 0.224542 -0.971595 -0.0747279 + outer loop + vertex -853.058 278.18 198.903 + vertex -853.485 278.033 199.533 + vertex -853.1 278.318 196.991 + endloop + endfacet + facet normal 0.2246 -0.971582 -0.0747178 + outer loop + vertex -853.485 278.033 199.533 + vertex -853.479 278.357 195.339 + vertex -853.1 278.318 196.991 + endloop + endfacet + facet normal 0.214483 -0.973285 -0.0819386 + outer loop + vertex -853.058 278.18 198.903 + vertex -853.148 277.984 200.997 + vertex -853.485 278.033 199.533 + endloop + endfacet + facet normal 0.205605 -0.974701 -0.0876612 + outer loop + vertex -853.114 277.821 202.891 + vertex -853.58 277.662 203.561 + vertex -853.148 277.984 200.997 + endloop + endfacet + facet normal 0.224103 -0.970932 -0.0840724 + outer loop + vertex -853.58 277.662 203.561 + vertex -853.485 278.033 199.533 + vertex -853.148 277.984 200.997 + endloop + endfacet + facet normal 0.215221 -0.975395 -0.0477859 + outer loop + vertex -852.973 278.963 186.927 + vertex -853.047 278.847 188.958 + vertex -853.38 278.848 187.438 + endloop + endfacet + facet normal 0.223045 -0.973339 -0.0534957 + outer loop + vertex -852.994 278.756 190.851 + vertex -853.414 278.643 191.158 + vertex -853.047 278.847 188.958 + endloop + endfacet + facet normal 0.232871 -0.971135 -0.0516523 + outer loop + vertex -853.414 278.643 191.158 + vertex -853.38 278.848 187.438 + vertex -853.047 278.847 188.958 + endloop + endfacet + facet normal 0.218047 -0.974056 -0.0605895 + outer loop + vertex -852.994 278.756 190.851 + vertex -853.065 278.61 192.939 + vertex -853.414 278.643 191.158 + endloop + endfacet + facet normal 0.215792 -0.97425 -0.0653534 + outer loop + vertex -853.019 278.489 194.894 + vertex -853.479 278.357 195.339 + vertex -853.065 278.61 192.939 + endloop + endfacet + facet normal 0.229222 -0.971351 -0.0627309 + outer loop + vertex -853.479 278.357 195.339 + vertex -853.414 278.643 191.158 + vertex -853.065 278.61 192.939 + endloop + endfacet + facet normal 0.216554 -0.975995 -0.0232048 + outer loop + vertex -852.92 279.233 178.9 + vertex -852.991 279.168 181.01 + vertex -853.33 279.132 179.352 + endloop + endfacet + facet normal 0.216429 -0.975877 -0.028673 + outer loop + vertex -852.944 279.121 182.949 + vertex -853.395 279.006 183.462 + vertex -852.991 279.168 181.01 + endloop + endfacet + facet normal 0.230545 -0.972711 -0.0261357 + outer loop + vertex -853.395 279.006 183.462 + vertex -853.33 279.132 179.352 + vertex -852.991 279.168 181.01 + endloop + endfacet + facet normal 0.209483 -0.977183 -0.0350784 + outer loop + vertex -852.944 279.121 182.949 + vertex -853.019 279.03 185.028 + vertex -853.395 279.006 183.462 + endloop + endfacet + facet normal 0.224792 -0.973596 -0.0397429 + outer loop + vertex -852.973 278.963 186.927 + vertex -853.38 278.848 187.438 + vertex -853.019 279.03 185.028 + endloop + endfacet + facet normal 0.227048 -0.973088 -0.039366 + outer loop + vertex -853.38 278.848 187.438 + vertex -853.395 279.006 183.462 + vertex -853.019 279.03 185.028 + endloop + endfacet + facet normal 0.217927 -0.975965 -0.000775715 + outer loop + vertex -852.916 279.303 170.849 + vertex -852.978 279.287 172.894 + vertex -853.315 279.213 171.291 + endloop + endfacet + facet normal 0.219803 -0.975537 -0.00384346 + outer loop + vertex -852.911 279.295 174.827 + vertex -853.36 279.192 175.272 + vertex -852.978 279.287 172.894 + endloop + endfacet + facet normal 0.226589 -0.973987 -0.00269101 + outer loop + vertex -853.36 279.192 175.272 + vertex -853.315 279.213 171.291 + vertex -852.978 279.287 172.894 + endloop + endfacet + facet normal 0.211169 -0.977364 -0.0129604 + outer loop + vertex -852.911 279.295 174.827 + vertex -852.98 279.252 176.94 + vertex -853.36 279.192 175.272 + endloop + endfacet + facet normal 0.22411 -0.974432 -0.0160213 + outer loop + vertex -852.92 279.233 178.9 + vertex -853.33 279.132 179.352 + vertex -852.98 279.252 176.94 + endloop + endfacet + facet normal 0.22412 -0.97443 -0.0160197 + outer loop + vertex -853.33 279.132 179.352 + vertex -853.36 279.192 175.272 + vertex -852.98 279.252 176.94 + endloop + endfacet + facet normal 0.222958 -0.974573 0.022283 + outer loop + vertex -852.899 279.183 163.281 + vertex -852.966 279.214 165.28 + vertex -853.357 279.087 163.684 + endloop + endfacet + facet normal 0.240444 -0.97043 0.0212689 + outer loop + vertex -852.904 279.269 167.091 + vertex -853.318 279.179 167.676 + vertex -852.966 279.214 165.28 + endloop + endfacet + facet normal 0.231767 -0.972566 0.0199641 + outer loop + vertex -853.318 279.179 167.676 + vertex -853.357 279.087 163.684 + vertex -852.966 279.214 165.28 + endloop + endfacet + facet normal 0.227845 -0.973625 0.0118676 + outer loop + vertex -852.904 279.269 167.091 + vertex -852.974 279.276 169.039 + vertex -853.318 279.179 167.676 + endloop + endfacet + facet normal 0.226303 -0.97403 0.00719685 + outer loop + vertex -852.916 279.303 170.849 + vertex -853.315 279.213 171.291 + vertex -852.974 279.276 169.039 + endloop + endfacet + facet normal 0.23821 -0.971171 0.00908114 + outer loop + vertex -853.315 279.213 171.291 + vertex -853.318 279.179 167.676 + vertex -852.974 279.276 169.039 + endloop + endfacet + facet normal 0.217478 -0.975002 0.0455554 + outer loop + vertex -852.949 278.876 155.528 + vertex -852.999 278.959 157.525 + vertex -853.352 278.808 155.996 + endloop + endfacet + facet normal 0.229996 -0.972365 0.0400945 + outer loop + vertex -852.922 279.053 159.382 + vertex -853.335 278.966 159.635 + vertex -852.999 278.959 157.525 + endloop + endfacet + facet normal 0.235585 -0.970989 0.0409805 + outer loop + vertex -853.335 278.966 159.635 + vertex -853.352 278.808 155.996 + vertex -852.999 278.959 157.525 + endloop + endfacet + facet normal 0.225242 -0.973782 0.0318583 + outer loop + vertex -852.922 279.053 159.382 + vertex -852.974 279.107 161.401 + vertex -853.335 278.966 159.635 + endloop + endfacet + facet normal 0.229453 -0.972855 0.0300785 + outer loop + vertex -852.899 279.183 163.281 + vertex -853.357 279.087 163.684 + vertex -852.974 279.107 161.401 + endloop + endfacet + facet normal 0.23159 -0.972337 0.0304425 + outer loop + vertex -853.357 279.087 163.684 + vertex -853.335 278.966 159.635 + vertex -852.974 279.107 161.401 + endloop + endfacet + facet normal 0.205319 -0.97626 0.0689911 + outer loop + vertex -853.001 278.362 147.567 + vertex -853.048 278.499 149.642 + vertex -853.41 278.31 148.037 + endloop + endfacet + facet normal 0.210301 -0.975472 0.0650292 + outer loop + vertex -852.969 278.645 151.564 + vertex -853.418 278.58 152.045 + vertex -853.048 278.499 149.642 + endloop + endfacet + facet normal 0.217203 -0.97389 0.0660377 + outer loop + vertex -853.418 278.58 152.045 + vertex -853.41 278.31 148.037 + vertex -853.048 278.499 149.642 + endloop + endfacet + facet normal 0.204004 -0.977196 0.0589155 + outer loop + vertex -852.969 278.645 151.564 + vertex -853.016 278.759 153.633 + vertex -853.418 278.58 152.045 + endloop + endfacet + facet normal 0.22476 -0.97302 0.052107 + outer loop + vertex -852.949 278.876 155.528 + vertex -853.352 278.808 155.996 + vertex -853.016 278.759 153.633 + endloop + endfacet + facet normal 0.227351 -0.972399 0.0524626 + outer loop + vertex -853.352 278.808 155.996 + vertex -853.418 278.58 152.045 + vertex -853.016 278.759 153.633 + endloop + endfacet + facet normal 0.195141 -0.976156 0.0950804 + outer loop + vertex -853.066 277.647 139.694 + vertex -853.112 277.842 141.793 + vertex -853.506 277.625 140.373 + endloop + endfacet + facet normal 0.215918 -0.97221 0.090484 + outer loop + vertex -853.036 278.034 143.668 + vertex -853.448 278.003 144.325 + vertex -853.112 277.842 141.793 + endloop + endfacet + facet normal 0.211807 -0.973159 0.0899997 + outer loop + vertex -853.448 278.003 144.325 + vertex -853.506 277.625 140.373 + vertex -853.112 277.842 141.793 + endloop + endfacet + facet normal 0.204359 -0.975364 0.083085 + outer loop + vertex -853.036 278.034 143.668 + vertex -853.082 278.197 145.703 + vertex -853.448 278.003 144.325 + endloop + endfacet + facet normal 0.21421 -0.973748 0.0769948 + outer loop + vertex -853.001 278.362 147.567 + vertex -853.41 278.31 148.037 + vertex -853.082 278.197 145.703 + endloop + endfacet + facet normal 0.221821 -0.971965 0.0779767 + outer loop + vertex -853.41 278.31 148.037 + vertex -853.448 278.003 144.325 + vertex -853.082 278.197 145.703 + endloop + endfacet + facet normal 0.187741 -0.975164 0.117507 + outer loop + vertex -853.152 276.72 131.662 + vertex -853.186 276.963 133.736 + vertex -853.619 276.686 132.124 + endloop + endfacet + facet normal 0.220154 -0.968784 0.113975 + outer loop + vertex -853.097 277.209 135.651 + vertex -853.511 277.19 136.296 + vertex -853.186 276.963 133.736 + endloop + endfacet + facet normal 0.205039 -0.972283 0.112361 + outer loop + vertex -853.511 277.19 136.296 + vertex -853.619 276.686 132.124 + vertex -853.186 276.963 133.736 + endloop + endfacet + facet normal 0.207757 -0.972431 0.105897 + outer loop + vertex -853.097 277.209 135.651 + vertex -853.14 277.43 137.77 + vertex -853.511 277.19 136.296 + endloop + endfacet + facet normal 0.205208 -0.973421 0.101689 + outer loop + vertex -853.066 277.647 139.694 + vertex -853.506 277.625 140.373 + vertex -853.14 277.43 137.77 + endloop + endfacet + facet normal 0.217347 -0.970625 0.103186 + outer loop + vertex -853.506 277.625 140.373 + vertex -853.511 277.19 136.296 + vertex -853.14 277.43 137.77 + endloop + endfacet + facet normal 0.195196 -0.970623 0.140673 + outer loop + vertex -853.273 275.65 124.002 + vertex -853.317 275.923 125.945 + vertex -853.71 275.629 124.46 + endloop + endfacet + facet normal 0.204188 -0.969292 0.137038 + outer loop + vertex -853.216 276.201 127.756 + vertex -853.655 276.149 128.043 + vertex -853.317 275.923 125.945 + endloop + endfacet + facet normal 0.206401 -0.968781 0.13734 + outer loop + vertex -853.655 276.149 128.043 + vertex -853.71 275.629 124.46 + vertex -853.317 275.923 125.945 + endloop + endfacet + facet normal 0.198822 -0.971586 0.128416 + outer loop + vertex -853.216 276.201 127.756 + vertex -853.243 276.461 129.765 + vertex -853.655 276.149 128.043 + endloop + endfacet + facet normal 0.193806 -0.973199 0.123783 + outer loop + vertex -853.152 276.72 131.662 + vertex -853.619 276.686 132.124 + vertex -853.243 276.461 129.765 + endloop + endfacet + facet normal 0.208482 -0.969902 0.125803 + outer loop + vertex -853.619 276.686 132.124 + vertex -853.655 276.149 128.043 + vertex -853.243 276.461 129.765 + endloop + endfacet + facet normal 0.215412 -0.962651 0.164012 + outer loop + vertex -853.388 274.366 116.257 + vertex -853.423 274.706 118.299 + vertex -853.869 274.273 116.345 + endloop + endfacet + facet normal 0.195386 -0.967204 0.1623 + outer loop + vertex -853.32 275.045 120.196 + vertex -853.823 275.006 120.566 + vertex -853.423 274.706 118.299 + endloop + endfacet + facet normal 0.212504 -0.963165 0.164789 + outer loop + vertex -853.823 275.006 120.566 + vertex -853.869 274.273 116.345 + vertex -853.423 274.706 118.299 + endloop + endfacet + facet normal 0.188907 -0.969972 0.153195 + outer loop + vertex -853.32 275.045 120.196 + vertex -853.364 275.35 122.18 + vertex -853.823 275.006 120.566 + endloop + endfacet + facet normal 0.204159 -0.967473 0.149384 + outer loop + vertex -853.273 275.65 124.002 + vertex -853.71 275.629 124.46 + vertex -853.364 275.35 122.18 + endloop + endfacet + facet normal 0.201838 -0.968004 0.149097 + outer loop + vertex -853.71 275.629 124.46 + vertex -853.823 275.006 120.566 + vertex -853.364 275.35 122.18 + endloop + endfacet + facet normal 0.185988 -0.961845 0.200655 + outer loop + vertex -853.554 272.782 108.37 + vertex -853.597 273.19 110.366 + vertex -853.945 272.808 108.856 + endloop + endfacet + facet normal 0.201422 -0.960196 0.193526 + outer loop + vertex -853.494 273.596 112.273 + vertex -853.948 273.507 112.301 + vertex -853.597 273.19 110.366 + endloop + endfacet + facet normal 0.208686 -0.958435 0.194559 + outer loop + vertex -853.948 273.507 112.301 + vertex -853.945 272.808 108.856 + vertex -853.597 273.19 110.366 + endloop + endfacet + facet normal 0.20122 -0.962174 0.183663 + outer loop + vertex -853.494 273.596 112.273 + vertex -853.511 273.981 114.304 + vertex -853.948 273.507 112.301 + endloop + endfacet + facet normal 0.217105 -0.960181 0.175834 + outer loop + vertex -853.388 274.366 116.257 + vertex -853.869 274.273 116.345 + vertex -853.511 273.981 114.304 + endloop + endfacet + facet normal 0.226432 -0.957787 0.177125 + outer loop + vertex -853.869 274.273 116.345 + vertex -853.948 273.507 112.301 + vertex -853.511 273.981 114.304 + endloop + endfacet + facet normal 0.178523 -0.954809 0.237635 + outer loop + vertex -853.533 270.967 100.615 + vertex -853.613 271.474 102.714 + vertex -854.052 271.003 101.148 + endloop + endfacet + facet normal 0.202712 -0.952122 0.228848 + outer loop + vertex -853.559 271.936 104.587 + vertex -854.018 272.043 105.438 + vertex -853.613 271.474 102.714 + endloop + endfacet + facet normal 0.205353 -0.951493 0.22911 + outer loop + vertex -854.018 272.043 105.438 + vertex -854.052 271.003 101.148 + vertex -853.613 271.474 102.714 + endloop + endfacet + facet normal 0.182029 -0.958704 0.218525 + outer loop + vertex -853.559 271.936 104.587 + vertex -853.628 272.378 106.582 + vertex -854.018 272.043 105.438 + endloop + endfacet + facet normal 0.196324 -0.958057 0.208765 + outer loop + vertex -853.554 272.782 108.37 + vertex -853.945 272.808 108.856 + vertex -853.628 272.378 106.582 + endloop + endfacet + facet normal 0.205612 -0.955913 0.209654 + outer loop + vertex -853.945 272.808 108.856 + vertex -854.018 272.043 105.438 + vertex -853.628 272.378 106.582 + endloop + endfacet + facet normal 0.196123 -0.940531 0.277376 + outer loop + vertex -853.482 268.866 92.9974 + vertex -853.587 269.404 94.8951 + vertex -853.93 268.902 93.4333 + endloop + endfacet + facet normal 0.18901 -0.944772 0.267735 + outer loop + vertex -853.528 269.924 96.6892 + vertex -854.029 269.874 96.8638 + vertex -853.587 269.404 94.8951 + endloop + endfacet + facet normal 0.215286 -0.93791 0.271988 + outer loop + vertex -854.029 269.874 96.8638 + vertex -853.93 268.902 93.4333 + vertex -853.587 269.404 94.8951 + endloop + endfacet + facet normal 0.185123 -0.948951 0.255385 + outer loop + vertex -853.528 269.924 96.6892 + vertex -853.607 270.452 98.7066 + vertex -854.029 269.874 96.8638 + endloop + endfacet + facet normal 0.190407 -0.949641 0.248853 + outer loop + vertex -853.533 270.967 100.615 + vertex -854.052 271.003 101.148 + vertex -853.607 270.452 98.7066 + endloop + endfacet + facet normal 0.203234 -0.946546 0.250491 + outer loop + vertex -854.052 271.003 101.148 + vertex -854.029 269.874 96.8638 + vertex -853.607 270.452 98.7066 + endloop + endfacet + facet normal 0.16847 -0.930716 0.32463 + outer loop + vertex -853.289 266.419 85.5093 + vertex -853.435 267.091 87.5124 + vertex -853.839 266.453 85.8922 + endloop + endfacet + facet normal 0.201585 -0.927532 0.314718 + outer loop + vertex -853.411 267.717 89.3429 + vertex -853.946 267.85 90.077 + vertex -853.435 267.091 87.5124 + endloop + endfacet + facet normal 0.202419 -0.927316 0.31482 + outer loop + vertex -853.946 267.85 90.077 + vertex -853.839 266.453 85.8922 + vertex -853.435 267.091 87.5124 + endloop + endfacet + facet normal 0.183369 -0.935242 0.302817 + outer loop + vertex -853.411 267.717 89.3429 + vertex -853.526 268.318 91.2684 + vertex -853.946 267.85 90.077 + endloop + endfacet + facet normal 0.209664 -0.933558 0.290708 + outer loop + vertex -853.482 268.866 92.9974 + vertex -853.93 268.902 93.4333 + vertex -853.526 268.318 91.2684 + endloop + endfacet + facet normal 0.213447 -0.932564 0.291145 + outer loop + vertex -853.93 268.902 93.4333 + vertex -853.946 267.85 90.077 + vertex -853.526 268.318 91.2684 + endloop + endfacet + facet normal 0.132477 -0.916392 0.377724 + outer loop + vertex -852.924 263.677 78.3169 + vertex -853.123 264.421 80.1907 + vertex -853.508 263.9 79.0612 + endloop + endfacet + facet normal 0.164841 -0.916447 0.364626 + outer loop + vertex -853.132 265.087 81.8694 + vertex -853.632 265.191 82.3563 + vertex -853.123 264.421 80.1907 + endloop + endfacet + facet normal 0.168309 -0.91561 0.365143 + outer loop + vertex -853.632 265.191 82.3563 + vertex -853.508 263.9 79.0612 + vertex -853.123 264.421 80.1907 + endloop + endfacet + facet normal 0.149203 -0.924669 0.350324 + outer loop + vertex -853.132 265.087 81.8694 + vertex -853.295 265.771 83.7449 + vertex -853.632 265.191 82.3563 + endloop + endfacet + facet normal 0.178403 -0.923969 0.338309 + outer loop + vertex -853.289 266.419 85.5093 + vertex -853.839 266.453 85.8922 + vertex -853.295 265.771 83.7449 + endloop + endfacet + facet normal 0.187269 -0.921656 0.339824 + outer loop + vertex -853.839 266.453 85.8922 + vertex -853.632 265.191 82.3563 + vertex -853.295 265.771 83.7449 + endloop + endfacet + facet normal 0.0971371 -0.892514 0.440436 + outer loop + vertex -852.29 260.355 70.9601 + vertex -852.571 261.254 72.8447 + vertex -852.865 260.386 71.1518 + endloop + endfacet + facet normal 0.127361 -0.896217 0.42494 + outer loop + vertex -852.644 262.086 74.6206 + vertex -853.235 262.227 75.0957 + vertex -852.571 261.254 72.8447 + endloop + endfacet + facet normal 0.152211 -0.890087 0.429624 + outer loop + vertex -853.235 262.227 75.0957 + vertex -852.865 260.386 71.1518 + vertex -852.571 261.254 72.8447 + endloop + endfacet + facet normal 0.109334 -0.90738 0.405842 + outer loop + vertex -852.644 262.086 74.6206 + vertex -852.879 262.927 76.5649 + vertex -853.235 262.227 75.0957 + endloop + endfacet + facet normal 0.154837 -0.906689 0.392352 + outer loop + vertex -852.924 263.677 78.3169 + vertex -853.508 263.9 79.0612 + vertex -852.879 262.927 76.5649 + endloop + endfacet + facet normal 0.159003 -0.905683 0.393009 + outer loop + vertex -853.508 263.9 79.0612 + vertex -853.235 262.227 75.0957 + vertex -852.879 262.927 76.5649 + endloop + endfacet + facet normal 0.0601989 -0.859954 0.50681 + outer loop + vertex -851.348 256.671 64.1713 + vertex -851.718 257.677 65.9233 + vertex -852.027 257.02 64.8444 + endloop + endfacet + facet normal 0.0820297 -0.866882 0.491717 + outer loop + vertex -851.867 258.566 67.5156 + vertex -852.431 258.738 67.9122 + vertex -851.718 257.677 65.9233 + endloop + endfacet + facet normal 0.101748 -0.862182 0.496276 + outer loop + vertex -852.431 258.738 67.9122 + vertex -852.027 257.02 64.8444 + vertex -851.718 257.677 65.9233 + endloop + endfacet + facet normal 0.0653581 -0.878584 0.473095 + outer loop + vertex -851.867 258.566 67.5156 + vertex -852.184 259.494 69.2828 + vertex -852.431 258.738 67.9122 + endloop + endfacet + facet normal 0.103912 -0.882302 0.459071 + outer loop + vertex -852.29 260.355 70.9601 + vertex -852.865 260.386 71.1518 + vertex -852.184 259.494 69.2828 + endloop + endfacet + facet normal 0.120115 -0.878179 0.463006 + outer loop + vertex -852.865 260.386 71.1518 + vertex -852.431 258.738 67.9122 + vertex -852.184 259.494 69.2828 + endloop + endfacet + facet normal 0.0359577 -0.810686 0.584376 + outer loop + vertex -849.907 252.305 57.5136 + vertex -850.437 253.495 59.1965 + vertex -850.584 252.474 57.7897 + endloop + endfacet + facet normal 0.0765842 -0.82011 0.567058 + outer loop + vertex -850.699 254.566 60.7805 + vertex -851.368 254.83 61.2527 + vertex -850.437 253.495 59.1965 + endloop + endfacet + facet normal 0.110892 -0.809911 0.575975 + outer loop + vertex -851.368 254.83 61.2527 + vertex -850.584 252.474 57.7897 + vertex -850.437 253.495 59.1965 + endloop + endfacet + facet normal 0.051509 -0.83881 0.541983 + outer loop + vertex -850.699 254.566 60.7805 + vertex -851.142 255.685 62.5553 + vertex -851.368 254.83 61.2527 + endloop + endfacet + facet normal 0.0873378 -0.845546 0.526711 + outer loop + vertex -851.348 256.671 64.1713 + vertex -852.027 257.02 64.8444 + vertex -851.142 255.685 62.5553 + endloop + endfacet + facet normal 0.110612 -0.839408 0.532127 + outer loop + vertex -852.027 257.02 64.8444 + vertex -851.368 254.83 61.2527 + vertex -851.142 255.685 62.5553 + endloop + endfacet + facet normal -0.098577 -0.763434 0.638319 + outer loop + vertex -848.227 247.669 51.8063 + vertex -848.623 248.728 53.0126 + vertex -848.925 248.032 52.1329 + endloop + endfacet + facet normal -0.0422995 -0.777337 0.62766 + outer loop + vertex -849.117 247.826 51.8654 + vertex -848.925 248.032 52.1329 + vertex -849.644 249.842 54.3267 + endloop + endfacet + facet normal -0.0136585 -0.767956 0.640357 + outer loop + vertex -848.95 249.859 54.3608 + vertex -849.644 249.842 54.3267 + vertex -848.623 248.728 53.0126 + endloop + endfacet + facet normal -0.0387059 -0.776878 0.62846 + outer loop + vertex -848.925 248.032 52.1329 + vertex -848.623 248.728 53.0126 + vertex -849.644 249.842 54.3267 + endloop + endfacet + facet normal -0.0122188 -0.785109 0.619237 + outer loop + vertex -848.95 249.859 54.3608 + vertex -849.55 251.114 55.941 + vertex -849.644 249.842 54.3267 + endloop + endfacet + facet normal 0.0515913 -0.79045 0.610349 + outer loop + vertex -849.907 252.305 57.5136 + vertex -850.584 252.474 57.7897 + vertex -849.55 251.114 55.941 + endloop + endfacet + facet normal 0.0663592 -0.785661 0.615088 + outer loop + vertex -850.584 252.474 57.7897 + vertex -849.644 249.842 54.3267 + vertex -849.55 251.114 55.941 + endloop + endfacet + facet normal -0.140031 -0.691142 0.709023 + outer loop + vertex -846.551 243.313 47.4701 + vertex -846.75 243.672 47.7803 + vertex -847.029 243.497 47.5544 + endloop + endfacet + facet normal -0.146089 -0.69961 0.699431 + outer loop + vertex -846.842 244.144 48.2335 + vertex -847.48 244.432 48.3876 + vertex -846.75 243.672 47.7803 + endloop + endfacet + facet normal -0.135469 -0.694862 0.706268 + outer loop + vertex -847.48 244.432 48.3876 + vertex -847.029 243.497 47.5544 + vertex -846.75 243.672 47.7803 + endloop + endfacet + facet normal -0.118864 -0.685152 0.718636 + outer loop + vertex -847.244 243.376 47.4041 + vertex -847.029 243.497 47.5544 + vertex -847.609 244.165 48.096 + endloop + endfacet + facet normal -0.148383 -0.696943 0.701608 + outer loop + vertex -847.609 244.165 48.096 + vertex -847.029 243.497 47.5544 + vertex -847.48 244.432 48.3876 + endloop + endfacet + facet normal -0.111125 -0.709082 0.696314 + outer loop + vertex -847.609 244.165 48.096 + vertex -847.48 244.432 48.3876 + vertex -848.094 245.277 49.1505 + endloop + endfacet + facet normal -0.122726 -0.71254 0.690815 + outer loop + vertex -848.094 245.277 49.1505 + vertex -847.48 244.432 48.3876 + vertex -848.023 245.641 49.5389 + endloop + endfacet + facet normal -0.151785 -0.707392 0.690332 + outer loop + vertex -846.842 244.144 48.2335 + vertex -847.211 244.783 48.8068 + vertex -847.48 244.432 48.3876 + endloop + endfacet + facet normal -0.136808 -0.714561 0.686066 + outer loop + vertex -847.423 245.381 49.3877 + vertex -848.023 245.641 49.5389 + vertex -847.211 244.783 48.8068 + endloop + endfacet + facet normal -0.136411 -0.714398 0.686315 + outer loop + vertex -848.023 245.641 49.5389 + vertex -847.48 244.432 48.3876 + vertex -847.211 244.783 48.8068 + endloop + endfacet + facet normal -0.149137 -0.731184 0.665679 + outer loop + vertex -847.423 245.381 49.3877 + vertex -847.859 246.095 50.0741 + vertex -848.023 245.641 49.5389 + endloop + endfacet + facet normal -0.145747 -0.746343 0.649407 + outer loop + vertex -848.193 246.959 50.9915 + vertex -848.604 246.885 50.8146 + vertex -847.859 246.095 50.0741 + endloop + endfacet + facet normal -0.122984 -0.738038 0.663457 + outer loop + vertex -848.604 246.885 50.8146 + vertex -848.023 245.641 49.5389 + vertex -847.859 246.095 50.0741 + endloop + endfacet + facet normal -0.0711593 -0.720947 0.689327 + outer loop + vertex -848.094 245.277 49.1505 + vertex -848.023 245.641 49.5389 + vertex -848.598 246.482 50.3583 + endloop + endfacet + facet normal -0.152348 -0.741484 0.653445 + outer loop + vertex -848.598 246.482 50.3583 + vertex -848.023 245.641 49.5389 + vertex -848.604 246.885 50.8146 + endloop + endfacet + facet normal -0.0187342 -0.749195 0.662085 + outer loop + vertex -848.598 246.482 50.3583 + vertex -848.604 246.885 50.8146 + vertex -849.117 247.826 51.8654 + endloop + endfacet + facet normal -0.0805627 -0.761586 0.643037 + outer loop + vertex -849.117 247.826 51.8654 + vertex -848.604 246.885 50.8146 + vertex -848.925 248.032 52.1329 + endloop + endfacet + facet normal -0.134973 -0.763529 0.63151 + outer loop + vertex -848.604 246.885 50.8146 + vertex -848.193 246.959 50.9915 + vertex -848.925 248.032 52.1329 + endloop + endfacet + facet normal -0.0863764 -0.752799 0.652558 + outer loop + vertex -848.925 248.032 52.1329 + vertex -848.193 246.959 50.9915 + vertex -848.227 247.669 51.8063 + endloop + endfacet + facet normal -0.106644 -0.671901 0.732923 + outer loop + vertex -845.637 242.846 47.1945 + vertex -845.808 242.875 47.1963 + vertex -846.314 242.597 46.8679 + endloop + endfacet + facet normal -0.129064 -0.657053 0.742714 + outer loop + vertex -845.745 242.985 47.3044 + vertex -846.575 242.878 47.0655 + vertex -845.808 242.875 47.1963 + endloop + endfacet + facet normal -0.130227 -0.648841 0.749698 + outer loop + vertex -846.575 242.878 47.0655 + vertex -846.314 242.597 46.8679 + vertex -845.808 242.875 47.1963 + endloop + endfacet + facet normal 0.0693159 0.560345 -0.825354 + outer loop + vertex -846.551 243.313 47.4701 + vertex -847.029 243.497 47.5544 + vertex -846.034 243.145 47.399 + endloop + endfacet + facet normal -0.126276 -0.664629 0.736425 + outer loop + vertex -845.745 242.985 47.3044 + vertex -846.034 243.145 47.399 + vertex -846.575 242.878 47.0655 + endloop + endfacet + facet normal -0.132514 -0.672559 0.728082 + outer loop + vertex -847.244 243.376 47.4041 + vertex -846.575 242.878 47.0655 + vertex -847.029 243.497 47.5544 + endloop + endfacet + facet normal -0.122136 -0.668968 0.733188 + outer loop + vertex -846.034 243.145 47.399 + vertex -847.029 243.497 47.5544 + vertex -846.575 242.878 47.0655 + endloop + endfacet + facet normal -0.159822 -0.605425 0.779691 + outer loop + vertex -845.695 242.663 47.0393 + vertex -845.738 242.732 47.0839 + vertex -846.272 242.474 46.7745 + endloop + endfacet + facet normal -0.14571 -0.617805 0.772713 + outer loop + vertex -845.637 242.846 47.1945 + vertex -846.314 242.597 46.8679 + vertex -845.738 242.732 47.0839 + endloop + endfacet + facet normal -0.140494 -0.628193 0.765268 + outer loop + vertex -846.314 242.597 46.8679 + vertex -846.272 242.474 46.7745 + vertex -845.738 242.732 47.0839 + endloop + endfacet + facet normal 0.236446 -0.540343 -0.807541 + outer loop + vertex -843.427 245.641 294.008 + vertex -842.006 246.915 293.571 + vertex -843.15 245.167 294.406 + endloop + endfacet + facet normal 0.267815 -0.552256 -0.789487 + outer loop + vertex -843.15 245.167 294.406 + vertex -842.006 246.915 293.571 + vertex -841.779 246.47 293.96 + endloop + endfacet + facet normal 0.119697 -0.588514 -0.799577 + outer loop + vertex -845.081 244.547 294.565 + vertex -843.427 245.641 294.008 + vertex -844.648 244.163 294.913 + endloop + endfacet + facet normal 0.128498 -0.592937 -0.79493 + outer loop + vertex -844.648 244.163 294.913 + vertex -843.427 245.641 294.008 + vertex -843.15 245.167 294.406 + endloop + endfacet + facet normal 0.0741209 -0.535325 -0.841388 + outer loop + vertex -844.648 244.163 294.913 + vertex -843.15 245.167 294.406 + vertex -844.391 243.934 295.081 + endloop + endfacet + facet normal 0.133092 -0.575671 -0.806778 + outer loop + vertex -844.391 243.934 295.081 + vertex -843.15 245.167 294.406 + vertex -842.95 244.968 294.581 + endloop + endfacet + facet normal 0.216963 -0.512776 -0.830655 + outer loop + vertex -843.15 245.167 294.406 + vertex -841.779 246.47 293.96 + vertex -842.95 244.968 294.581 + endloop + endfacet + facet normal 0.313329 -0.561232 -0.766057 + outer loop + vertex -842.95 244.968 294.581 + vertex -841.779 246.47 293.96 + vertex -841.594 246.347 294.126 + endloop + endfacet + facet normal 0.1315 -0.680605 -0.720753 + outer loop + vertex -846.082 243.73 295.154 + vertex -845.081 244.547 294.565 + vertex -846.148 243.417 295.438 + endloop + endfacet + facet normal 0.0492241 -0.639075 -0.767568 + outer loop + vertex -846.148 243.417 295.438 + vertex -845.081 244.547 294.565 + vertex -844.648 244.163 294.913 + endloop + endfacet + facet normal -0.069019 -0.667271 -0.741611 + outer loop + vertex -847.669 243.341 295.586 + vertex -846.854 243.42 295.439 + vertex -847.403 243.068 295.807 + endloop + endfacet + facet normal -0.00468193 -0.670843 -0.741585 + outer loop + vertex -846.082 243.73 295.154 + vertex -846.148 243.417 295.438 + vertex -846.854 243.42 295.439 + endloop + endfacet + facet normal -0.00481458 -0.718757 -0.695245 + outer loop + vertex -846.148 243.417 295.438 + vertex -847.403 243.068 295.807 + vertex -846.854 243.42 295.439 + endloop + endfacet + facet normal -0.0602412 -0.615488 -0.785841 + outer loop + vertex -847.403 243.068 295.807 + vertex -846.148 243.417 295.438 + vertex -846.948 242.928 295.882 + endloop + endfacet + facet normal -0.0425366 -0.63287 -0.773088 + outer loop + vertex -846.948 242.928 295.882 + vertex -846.148 243.417 295.438 + vertex -845.827 243.222 295.58 + endloop + endfacet + facet normal 0.00538714 -0.582682 -0.812683 + outer loop + vertex -846.148 243.417 295.438 + vertex -844.648 244.163 294.913 + vertex -845.827 243.222 295.58 + endloop + endfacet + facet normal 0.00889404 -0.585579 -0.810567 + outer loop + vertex -845.827 243.222 295.58 + vertex -844.648 244.163 294.913 + vertex -844.391 243.934 295.081 + endloop + endfacet + facet normal -0.059126 -0.489777 -0.86984 + outer loop + vertex -845.827 243.222 295.58 + vertex -844.391 243.934 295.081 + vertex -845.542 243.162 295.594 + endloop + endfacet + facet normal 0.00268028 -0.556214 -0.831035 + outer loop + vertex -845.542 243.162 295.594 + vertex -844.391 243.934 295.081 + vertex -844.074 243.936 295.081 + endloop + endfacet + facet normal -0.0379327 -0.642471 -0.76537 + outer loop + vertex -846.948 242.928 295.882 + vertex -845.827 243.222 295.58 + vertex -846.949 242.749 296.033 + endloop + endfacet + facet normal -0.0814542 -0.581503 -0.809456 + outer loop + vertex -846.949 242.749 296.033 + vertex -845.827 243.222 295.58 + vertex -845.542 243.162 295.594 + endloop + endfacet + facet normal 0.14886 -0.439129 -0.886006 + outer loop + vertex -842.95 244.968 294.581 + vertex -841.594 246.347 294.126 + vertex -842.642 245.073 294.581 + endloop + endfacet + facet normal 0.392045 -0.578168 -0.715558 + outer loop + vertex -842.642 245.073 294.581 + vertex -841.594 246.347 294.126 + vertex -841.307 246.544 294.123 + endloop + endfacet + facet normal 0.00180065 -0.437446 -0.899243 + outer loop + vertex -844.391 243.934 295.081 + vertex -842.95 244.968 294.581 + vertex -844.074 243.936 295.081 + endloop + endfacet + facet normal 0.2026 -0.596661 -0.776498 + outer loop + vertex -844.074 243.936 295.081 + vertex -842.95 244.968 294.581 + vertex -842.642 245.073 294.581 + endloop + endfacet + facet normal 0.303297 -0.602755 -0.738036 + outer loop + vertex -845.446 249.391 290.356 + vertex -844.051 250.497 290.026 + vertex -844.871 248.364 291.43 + endloop + endfacet + facet normal 0.314795 -0.603561 -0.732542 + outer loop + vertex -844.871 248.364 291.43 + vertex -844.051 250.497 290.026 + vertex -843.47 249.496 291.1 + endloop + endfacet + facet normal 0.166298 -0.661494 -0.73128 + outer loop + vertex -846.928 248.649 290.689 + vertex -845.446 249.391 290.356 + vertex -846.352 247.607 291.763 + endloop + endfacet + facet normal 0.175539 -0.663234 -0.727535 + outer loop + vertex -846.352 247.607 291.763 + vertex -845.446 249.391 290.356 + vertex -844.871 248.364 291.43 + endloop + endfacet + facet normal 0.160313 -0.642882 -0.749001 + outer loop + vertex -846.352 247.607 291.763 + vertex -844.871 248.364 291.43 + vertex -845.828 246.589 292.749 + endloop + endfacet + facet normal 0.173209 -0.645809 -0.743592 + outer loop + vertex -845.828 246.589 292.749 + vertex -844.871 248.364 291.43 + vertex -844.334 247.342 292.443 + endloop + endfacet + facet normal 0.297951 -0.588308 -0.751743 + outer loop + vertex -844.871 248.364 291.43 + vertex -843.47 249.496 291.1 + vertex -844.334 247.342 292.443 + endloop + endfacet + facet normal 0.29175 -0.587653 -0.754682 + outer loop + vertex -844.334 247.342 292.443 + vertex -843.47 249.496 291.1 + vertex -842.889 248.511 292.092 + endloop + endfacet + facet normal 0.0605817 -0.699744 -0.71182 + outer loop + vertex -848.349 248.268 290.943 + vertex -846.928 248.649 290.689 + vertex -847.797 247.165 292.075 + endloop + endfacet + facet normal 0.0607054 -0.699777 -0.711778 + outer loop + vertex -847.797 247.165 292.075 + vertex -846.928 248.649 290.689 + vertex -846.352 247.607 291.763 + endloop + endfacet + facet normal 0.00916614 -0.722609 -0.691197 + outer loop + vertex -849.406 248.292 290.905 + vertex -848.349 248.268 290.943 + vertex -849.06 246.914 292.35 + endloop + endfacet + facet normal -0.00875228 -0.718082 -0.695904 + outer loop + vertex -849.06 246.914 292.35 + vertex -848.349 248.268 290.943 + vertex -847.797 247.165 292.075 + endloop + endfacet + facet normal -0.0211785 -0.698215 -0.715575 + outer loop + vertex -847.242 246.197 293.003 + vertex -848.431 245.975 293.254 + vertex -847.797 247.165 292.075 + endloop + endfacet + facet normal -0.0609511 -0.713552 -0.697946 + outer loop + vertex -849.058 245.842 293.445 + vertex -849.06 246.914 292.35 + vertex -848.431 245.975 293.254 + endloop + endfacet + facet normal -0.0164611 -0.699554 -0.714391 + outer loop + vertex -849.06 246.914 292.35 + vertex -847.797 247.165 292.075 + vertex -848.431 245.975 293.254 + endloop + endfacet + facet normal 0.0486355 -0.676567 -0.734773 + outer loop + vertex -847.797 247.165 292.075 + vertex -846.352 247.607 291.763 + vertex -847.242 246.197 293.003 + endloop + endfacet + facet normal 0.0571329 -0.679227 -0.731701 + outer loop + vertex -847.242 246.197 293.003 + vertex -846.352 247.607 291.763 + vertex -845.828 246.589 292.749 + endloop + endfacet + facet normal 0.049133 -0.647309 -0.760642 + outer loop + vertex -846.71 244.488 294.514 + vertex -846.83 245.276 293.835 + vertex -845.509 245.421 293.797 + endloop + endfacet + facet normal 0.047727 -0.658052 -0.751459 + outer loop + vertex -847.242 246.197 293.003 + vertex -845.828 246.589 292.749 + vertex -846.83 245.276 293.835 + endloop + endfacet + facet normal 0.0507413 -0.659291 -0.750174 + outer loop + vertex -845.828 246.589 292.749 + vertex -845.509 245.421 293.797 + vertex -846.83 245.276 293.835 + endloop + endfacet + facet normal -0.0290704 -0.677678 -0.734784 + outer loop + vertex -848.431 245.975 293.254 + vertex -847.242 246.197 293.003 + vertex -847.971 245.147 293.999 + endloop + endfacet + facet normal -0.0293895 -0.677553 -0.734886 + outer loop + vertex -847.971 245.147 293.999 + vertex -847.242 246.197 293.003 + vertex -846.83 245.276 293.835 + endloop + endfacet + facet normal -0.0715315 -0.692425 -0.717935 + outer loop + vertex -849.058 245.842 293.445 + vertex -848.431 245.975 293.254 + vertex -848.801 245.139 294.097 + endloop + endfacet + facet normal -0.0780003 -0.690626 -0.718993 + outer loop + vertex -848.801 245.139 294.097 + vertex -848.431 245.975 293.254 + vertex -847.971 245.147 293.999 + endloop + endfacet + facet normal -0.0798293 -0.675358 -0.733157 + outer loop + vertex -848.801 245.139 294.097 + vertex -847.971 245.147 293.999 + vertex -848.378 244.45 294.686 + endloop + endfacet + facet normal -0.0873109 -0.672625 -0.734815 + outer loop + vertex -848.378 244.45 294.686 + vertex -847.971 245.147 293.999 + vertex -847.619 244.393 294.648 + endloop + endfacet + facet normal -0.0334864 -0.66058 -0.750009 + outer loop + vertex -847.971 245.147 293.999 + vertex -846.83 245.276 293.835 + vertex -847.619 244.393 294.648 + endloop + endfacet + facet normal -0.0431833 -0.655531 -0.753933 + outer loop + vertex -847.619 244.393 294.648 + vertex -846.83 245.276 293.835 + vertex -846.71 244.488 294.514 + endloop + endfacet + facet normal -0.0440916 -0.651593 -0.757287 + outer loop + vertex -847.619 244.393 294.648 + vertex -846.71 244.488 294.514 + vertex -847.266 243.799 295.139 + endloop + endfacet + facet normal -0.0202896 -0.66282 -0.748504 + outer loop + vertex -847.266 243.799 295.139 + vertex -846.71 244.488 294.514 + vertex -846.247 244.106 294.839 + endloop + endfacet + facet normal -0.0870852 -0.665381 -0.741407 + outer loop + vertex -848.378 244.45 294.686 + vertex -847.619 244.393 294.648 + vertex -848.107 243.81 295.229 + endloop + endfacet + facet normal -0.088043 -0.664899 -0.741726 + outer loop + vertex -848.107 243.81 295.229 + vertex -847.619 244.393 294.648 + vertex -847.266 243.799 295.139 + endloop + endfacet + facet normal -0.0888269 -0.655281 -0.750144 + outer loop + vertex -848.107 243.81 295.229 + vertex -847.266 243.799 295.139 + vertex -847.669 243.341 295.586 + endloop + endfacet + facet normal -0.0694677 -0.665502 -0.743156 + outer loop + vertex -847.669 243.341 295.586 + vertex -847.266 243.799 295.139 + vertex -846.854 243.42 295.439 + endloop + endfacet + facet normal -0.0315604 -0.642293 -0.765809 + outer loop + vertex -847.266 243.799 295.139 + vertex -846.247 244.106 294.839 + vertex -846.854 243.42 295.439 + endloop + endfacet + facet normal -0.0213903 -0.647646 -0.761641 + outer loop + vertex -846.854 243.42 295.439 + vertex -846.247 244.106 294.839 + vertex -846.082 243.73 295.154 + endloop + endfacet + facet normal 0.054762 -0.627136 -0.776982 + outer loop + vertex -846.082 243.73 295.154 + vertex -846.247 244.106 294.839 + vertex -845.081 244.547 294.565 + endloop + endfacet + facet normal 0.0263161 -0.629903 -0.776228 + outer loop + vertex -846.71 244.488 294.514 + vertex -845.509 245.421 293.797 + vertex -846.247 244.106 294.839 + endloop + endfacet + facet normal 0.0630309 -0.641342 -0.764662 + outer loop + vertex -845.509 245.421 293.797 + vertex -845.081 244.547 294.565 + vertex -846.247 244.106 294.839 + endloop + endfacet + facet normal 0.281137 -0.577968 -0.766104 + outer loop + vertex -844.334 247.342 292.443 + vertex -842.889 248.511 292.092 + vertex -843.848 246.385 293.343 + endloop + endfacet + facet normal 0.272991 -0.57662 -0.770055 + outer loop + vertex -843.848 246.385 293.343 + vertex -842.889 248.511 292.092 + vertex -842.378 247.62 292.939 + endloop + endfacet + facet normal 0.164478 -0.63354 -0.756025 + outer loop + vertex -845.828 246.589 292.749 + vertex -844.334 247.342 292.443 + vertex -845.509 245.421 293.797 + endloop + endfacet + facet normal 0.159786 -0.632178 -0.758168 + outer loop + vertex -845.509 245.421 293.797 + vertex -844.334 247.342 292.443 + vertex -843.848 246.385 293.343 + endloop + endfacet + facet normal 0.143398 -0.612846 -0.777082 + outer loop + vertex -845.509 245.421 293.797 + vertex -843.848 246.385 293.343 + vertex -845.081 244.547 294.565 + endloop + endfacet + facet normal 0.143352 -0.612829 -0.777104 + outer loop + vertex -845.081 244.547 294.565 + vertex -843.848 246.385 293.343 + vertex -843.427 245.641 294.008 + endloop + endfacet + facet normal 0.254213 -0.560257 -0.788345 + outer loop + vertex -843.848 246.385 293.343 + vertex -842.378 247.62 292.939 + vertex -843.427 245.641 294.008 + endloop + endfacet + facet normal 0.263953 -0.562732 -0.783365 + outer loop + vertex -843.427 245.641 294.008 + vertex -842.378 247.62 292.939 + vertex -842.006 246.915 293.571 + endloop + endfacet + facet normal 0.365478 -0.68101 -0.634548 + outer loop + vertex -847.419 253.717 285.135 + vertex -846.042 254.656 284.922 + vertex -846.983 252.616 286.568 + endloop + endfacet + facet normal 0.365184 -0.681011 -0.634716 + outer loop + vertex -846.983 252.616 286.568 + vertex -846.042 254.656 284.922 + vertex -845.591 253.59 286.325 + endloop + endfacet + facet normal 0.21478 -0.743952 -0.632775 + outer loop + vertex -848.856 253.136 285.331 + vertex -847.419 253.717 285.135 + vertex -848.444 252.018 286.786 + endloop + endfacet + facet normal 0.209974 -0.743328 -0.635118 + outer loop + vertex -848.444 252.018 286.786 + vertex -847.419 253.717 285.135 + vertex -846.983 252.616 286.568 + endloop + endfacet + facet normal 0.199769 -0.726537 -0.657446 + outer loop + vertex -848.444 252.018 286.786 + vertex -846.983 252.616 286.568 + vertex -847.984 250.891 288.171 + endloop + endfacet + facet normal 0.201206 -0.726748 -0.656775 + outer loop + vertex -847.984 250.891 288.171 + vertex -846.983 252.616 286.568 + vertex -846.512 251.522 287.923 + endloop + endfacet + facet normal 0.350116 -0.665574 -0.659113 + outer loop + vertex -846.983 252.616 286.568 + vertex -845.591 253.59 286.325 + vertex -846.512 251.522 287.923 + endloop + endfacet + facet normal 0.356067 -0.665676 -0.655814 + outer loop + vertex -846.512 251.522 287.923 + vertex -845.591 253.59 286.325 + vertex -845.115 252.544 287.645 + endloop + endfacet + facet normal 0.10335 -0.777342 -0.620531 + outer loop + vertex -850.171 252.893 285.416 + vertex -848.856 253.136 285.331 + vertex -849.79 251.772 286.885 + endloop + endfacet + facet normal 0.0959677 -0.775812 -0.623623 + outer loop + vertex -849.79 251.772 286.885 + vertex -848.856 253.136 285.331 + vertex -848.444 252.018 286.786 + endloop + endfacet + facet normal 0.0501352 -0.791146 -0.609569 + outer loop + vertex -851.085 252.966 285.247 + vertex -850.171 252.893 285.416 + vertex -850.816 251.784 286.803 + endloop + endfacet + facet normal 0.0394181 -0.789142 -0.612945 + outer loop + vertex -850.816 251.784 286.803 + vertex -850.171 252.893 285.416 + vertex -849.79 251.772 286.885 + endloop + endfacet + facet normal 0.0410367 -0.774636 -0.631074 + outer loop + vertex -850.816 251.784 286.803 + vertex -849.79 251.772 286.885 + vertex -850.331 250.715 288.146 + endloop + endfacet + facet normal 0.0251638 -0.77173 -0.635452 + outer loop + vertex -850.331 250.715 288.146 + vertex -849.79 251.772 286.885 + vertex -849.355 250.624 288.295 + endloop + endfacet + facet normal 0.0912379 -0.758598 -0.645139 + outer loop + vertex -849.79 251.772 286.885 + vertex -848.444 252.018 286.786 + vertex -849.355 250.624 288.295 + endloop + endfacet + facet normal 0.0886759 -0.758031 -0.646162 + outer loop + vertex -849.355 250.624 288.295 + vertex -848.444 252.018 286.786 + vertex -847.984 250.891 288.171 + endloop + endfacet + facet normal 0.0829406 -0.738961 -0.668623 + outer loop + vertex -849.355 250.624 288.295 + vertex -847.984 250.891 288.171 + vertex -848.875 249.444 289.659 + endloop + endfacet + facet normal 0.0793063 -0.738126 -0.669986 + outer loop + vertex -848.875 249.444 289.659 + vertex -847.984 250.891 288.171 + vertex -847.479 249.753 289.485 + endloop + endfacet + facet normal 0.0297495 -0.754862 -0.655209 + outer loop + vertex -850.331 250.715 288.146 + vertex -849.355 250.624 288.295 + vertex -849.98 249.454 289.615 + endloop + endfacet + facet normal 0.0194793 -0.752661 -0.65812 + outer loop + vertex -849.98 249.454 289.615 + vertex -849.355 250.624 288.295 + vertex -848.875 249.444 289.659 + endloop + endfacet + facet normal 0.0202748 -0.737963 -0.674537 + outer loop + vertex -849.98 249.454 289.615 + vertex -848.875 249.444 289.659 + vertex -849.406 248.292 290.905 + endloop + endfacet + facet normal 0.00838061 -0.735571 -0.677396 + outer loop + vertex -849.406 248.292 290.905 + vertex -848.875 249.444 289.659 + vertex -848.349 248.268 290.943 + endloop + endfacet + facet normal 0.0728786 -0.720293 -0.689831 + outer loop + vertex -848.875 249.444 289.659 + vertex -847.479 249.753 289.485 + vertex -848.349 248.268 290.943 + endloop + endfacet + facet normal 0.069595 -0.719507 -0.690989 + outer loop + vertex -848.349 248.268 290.943 + vertex -847.479 249.753 289.485 + vertex -846.928 248.649 290.689 + endloop + endfacet + facet normal 0.334868 -0.645122 -0.686791 + outer loop + vertex -846.512 251.522 287.923 + vertex -845.115 252.544 287.645 + vertex -846 250.439 289.19 + endloop + endfacet + facet normal 0.338763 -0.645259 -0.684749 + outer loop + vertex -846 250.439 289.19 + vertex -845.115 252.544 287.645 + vertex -844.602 251.504 288.879 + endloop + endfacet + facet normal 0.187614 -0.705534 -0.683391 + outer loop + vertex -847.984 250.891 288.171 + vertex -846.512 251.522 287.923 + vertex -847.479 249.753 289.485 + endloop + endfacet + facet normal 0.192259 -0.706264 -0.681342 + outer loop + vertex -847.479 249.753 289.485 + vertex -846.512 251.522 287.923 + vertex -846 250.439 289.19 + endloop + endfacet + facet normal 0.176755 -0.684122 -0.707626 + outer loop + vertex -847.479 249.753 289.485 + vertex -846 250.439 289.19 + vertex -846.928 248.649 290.689 + endloop + endfacet + facet normal 0.184294 -0.685389 -0.70447 + outer loop + vertex -846.928 248.649 290.689 + vertex -846 250.439 289.19 + vertex -845.446 249.391 290.356 + endloop + endfacet + facet normal 0.317019 -0.625074 -0.71329 + outer loop + vertex -846 250.439 289.19 + vertex -844.602 251.504 288.879 + vertex -845.446 249.391 290.356 + endloop + endfacet + facet normal 0.328687 -0.625663 -0.707468 + outer loop + vertex -845.446 249.391 290.356 + vertex -844.602 251.504 288.879 + vertex -844.051 250.497 290.026 + endloop + endfacet + facet normal 0.433212 -0.724821 -0.535689 + outer loop + vertex -848.893 257.959 278.805 + vertex -847.609 258.838 278.654 + vertex -848.565 256.937 280.454 + endloop + endfacet + facet normal 0.424124 -0.725822 -0.541574 + outer loop + vertex -848.565 256.937 280.454 + vertex -847.609 258.838 278.654 + vertex -847.257 257.82 280.293 + endloop + endfacet + facet normal 0.269995 -0.795877 -0.541926 + outer loop + vertex -850.215 257.415 278.945 + vertex -848.893 257.959 278.805 + vertex -849.915 256.384 280.609 + endloop + endfacet + facet normal 0.26294 -0.795646 -0.54572 + outer loop + vertex -849.915 256.384 280.609 + vertex -848.893 257.959 278.805 + vertex -848.565 256.937 280.454 + endloop + endfacet + facet normal 0.256426 -0.784912 -0.564055 + outer loop + vertex -849.915 256.384 280.609 + vertex -848.565 256.937 280.454 + vertex -849.587 255.324 282.234 + endloop + endfacet + facet normal 0.24854 -0.784471 -0.568184 + outer loop + vertex -849.587 255.324 282.234 + vertex -848.565 256.937 280.454 + vertex -848.208 255.881 282.067 + endloop + endfacet + facet normal 0.415452 -0.716418 -0.560486 + outer loop + vertex -848.565 256.937 280.454 + vertex -847.257 257.82 280.293 + vertex -848.208 255.881 282.067 + endloop + endfacet + facet normal 0.407672 -0.71706 -0.565358 + outer loop + vertex -848.208 255.881 282.067 + vertex -847.257 257.82 280.293 + vertex -846.876 256.775 281.895 + endloop + endfacet + facet normal 0.15429 -0.83144 -0.533762 + outer loop + vertex -851.427 257.198 278.933 + vertex -850.215 257.415 278.945 + vertex -851.146 256.169 280.618 + endloop + endfacet + facet normal 0.141336 -0.82985 -0.539789 + outer loop + vertex -851.146 256.169 280.618 + vertex -850.215 257.415 278.945 + vertex -849.915 256.384 280.609 + endloop + endfacet + facet normal 0.0893944 -0.847126 -0.52382 + outer loop + vertex -852.287 257.329 278.574 + vertex -851.427 257.198 278.933 + vertex -852.112 256.253 280.344 + endloop + endfacet + facet normal 0.0758603 -0.84517 -0.529086 + outer loop + vertex -852.112 256.253 280.344 + vertex -851.427 257.198 278.933 + vertex -851.146 256.169 280.618 + endloop + endfacet + facet normal 0.0807486 -0.835601 -0.54337 + outer loop + vertex -852.112 256.253 280.344 + vertex -851.146 256.169 280.618 + vertex -851.742 255.211 282.003 + endloop + endfacet + facet normal 0.0616248 -0.833013 -0.54981 + outer loop + vertex -851.742 255.211 282.003 + vertex -851.146 256.169 280.618 + vertex -850.844 255.099 282.273 + endloop + endfacet + facet normal 0.139465 -0.819772 -0.555449 + outer loop + vertex -851.146 256.169 280.618 + vertex -849.915 256.384 280.609 + vertex -850.844 255.099 282.273 + endloop + endfacet + facet normal 0.129009 -0.818287 -0.560146 + outer loop + vertex -850.844 255.099 282.273 + vertex -849.915 256.384 280.609 + vertex -849.587 255.324 282.234 + endloop + endfacet + facet normal 0.126552 -0.807319 -0.576386 + outer loop + vertex -850.844 255.099 282.273 + vertex -849.587 255.324 282.234 + vertex -850.519 254.005 283.876 + endloop + endfacet + facet normal 0.118557 -0.806026 -0.579885 + outer loop + vertex -850.519 254.005 283.876 + vertex -849.587 255.324 282.234 + vertex -849.233 254.241 283.811 + endloop + endfacet + facet normal 0.0684495 -0.820604 -0.567384 + outer loop + vertex -851.742 255.211 282.003 + vertex -850.844 255.099 282.273 + vertex -851.511 254.037 283.729 + endloop + endfacet + facet normal 0.0588162 -0.819067 -0.570675 + outer loop + vertex -851.511 254.037 283.729 + vertex -850.844 255.099 282.273 + vertex -850.519 254.005 283.876 + endloop + endfacet + facet normal 0.0615647 -0.807495 -0.586653 + outer loop + vertex -851.511 254.037 283.729 + vertex -850.519 254.005 283.876 + vertex -851.085 252.966 285.247 + endloop + endfacet + facet normal 0.0456616 -0.805087 -0.591396 + outer loop + vertex -851.085 252.966 285.247 + vertex -850.519 254.005 283.876 + vertex -850.171 252.893 285.416 + endloop + endfacet + facet normal 0.115209 -0.792925 -0.598329 + outer loop + vertex -850.519 254.005 283.876 + vertex -849.233 254.241 283.811 + vertex -850.171 252.893 285.416 + endloop + endfacet + facet normal 0.107158 -0.791438 -0.601784 + outer loop + vertex -850.171 252.893 285.416 + vertex -849.233 254.241 283.811 + vertex -848.856 253.136 285.331 + endloop + endfacet + facet normal 0.399114 -0.707698 -0.582985 + outer loop + vertex -848.208 255.881 282.067 + vertex -846.876 256.775 281.895 + vertex -847.826 254.807 283.633 + endloop + endfacet + facet normal 0.392487 -0.708064 -0.587025 + outer loop + vertex -847.826 254.807 283.633 + vertex -846.876 256.775 281.895 + vertex -846.47 255.716 283.443 + endloop + endfacet + facet normal 0.242113 -0.773726 -0.585431 + outer loop + vertex -849.587 255.324 282.234 + vertex -848.208 255.881 282.067 + vertex -849.233 254.241 283.811 + endloop + endfacet + facet normal 0.236525 -0.77328 -0.588297 + outer loop + vertex -849.233 254.241 283.811 + vertex -848.208 255.881 282.067 + vertex -847.826 254.807 283.633 + endloop + endfacet + facet normal 0.228475 -0.759715 -0.608796 + outer loop + vertex -849.233 254.241 283.811 + vertex -847.826 254.807 283.633 + vertex -848.856 253.136 285.331 + endloop + endfacet + facet normal 0.223923 -0.759234 -0.611083 + outer loop + vertex -848.856 253.136 285.331 + vertex -847.826 254.807 283.633 + vertex -847.419 253.717 285.135 + endloop + endfacet + facet normal 0.381573 -0.696161 -0.608081 + outer loop + vertex -847.826 254.807 283.633 + vertex -846.47 255.716 283.443 + vertex -847.419 253.717 285.135 + endloop + endfacet + facet normal 0.37977 -0.69621 -0.609152 + outer loop + vertex -847.419 253.717 285.135 + vertex -846.47 255.716 283.443 + vertex -846.042 254.656 284.922 + endloop + endfacet + facet normal 0.485396 -0.751237 -0.447252 + outer loop + vertex -849.932 261.733 271.943 + vertex -848.719 262.563 271.865 + vertex -849.712 260.841 273.681 + endloop + endfacet + facet normal 0.480724 -0.75218 -0.450699 + outer loop + vertex -849.712 260.841 273.681 + vertex -848.719 262.563 271.865 + vertex -848.483 261.685 273.582 + endloop + endfacet + facet normal 0.323844 -0.827111 -0.459361 + outer loop + vertex -851.168 261.204 272.024 + vertex -849.932 261.733 271.943 + vertex -850.971 260.311 273.771 + endloop + endfacet + facet normal 0.31482 -0.827541 -0.464827 + outer loop + vertex -850.971 260.311 273.771 + vertex -849.932 261.733 271.943 + vertex -849.712 260.841 273.681 + endloop + endfacet + facet normal 0.31121 -0.821245 -0.478231 + outer loop + vertex -850.971 260.311 273.771 + vertex -849.712 260.841 273.681 + vertex -850.744 259.379 275.519 + endloop + endfacet + facet normal 0.303769 -0.821478 -0.482596 + outer loop + vertex -850.744 259.379 275.519 + vertex -849.712 260.841 273.681 + vertex -849.464 259.915 275.412 + endloop + endfacet + facet normal 0.47515 -0.745938 -0.4667 + outer loop + vertex -849.712 260.841 273.681 + vertex -848.483 261.685 273.582 + vertex -849.464 259.915 275.412 + endloop + endfacet + facet normal 0.467478 -0.747341 -0.472172 + outer loop + vertex -849.464 259.915 275.412 + vertex -848.483 261.685 273.582 + vertex -848.219 260.77 275.292 + endloop + endfacet + facet normal 0.201037 -0.865789 -0.458251 + outer loop + vertex -852.28 260.947 272.023 + vertex -851.168 261.204 272.024 + vertex -852.106 260.072 273.751 + endloop + endfacet + facet normal 0.190129 -0.865278 -0.463838 + outer loop + vertex -852.106 260.072 273.751 + vertex -851.168 261.204 272.024 + vertex -850.971 260.311 273.771 + endloop + endfacet + facet normal 0.125162 -0.883059 -0.452263 + outer loop + vertex -853.041 260.949 271.807 + vertex -852.28 260.947 272.023 + vertex -852.966 260.051 273.581 + endloop + endfacet + facet normal 0.111967 -0.882116 -0.457532 + outer loop + vertex -852.966 260.051 273.581 + vertex -852.28 260.947 272.023 + vertex -852.106 260.072 273.751 + endloop + endfacet + facet normal 0.114302 -0.875129 -0.470196 + outer loop + vertex -852.966 260.051 273.581 + vertex -852.106 260.072 273.751 + vertex -852.705 259.225 275.183 + endloop + endfacet + facet normal 0.10353 -0.8743 -0.474216 + outer loop + vertex -852.705 259.225 275.183 + vertex -852.106 260.072 273.751 + vertex -851.905 259.156 275.484 + endloop + endfacet + facet normal 0.189001 -0.858903 -0.475987 + outer loop + vertex -852.106 260.072 273.751 + vertex -850.971 260.311 273.771 + vertex -851.905 259.156 275.484 + endloop + endfacet + facet normal 0.179346 -0.858279 -0.480825 + outer loop + vertex -851.905 259.156 275.484 + vertex -850.971 260.311 273.771 + vertex -850.744 259.379 275.519 + endloop + endfacet + facet normal 0.178296 -0.850749 -0.494406 + outer loop + vertex -851.905 259.156 275.484 + vertex -850.744 259.379 275.519 + vertex -851.675 258.198 277.215 + endloop + endfacet + facet normal 0.168504 -0.849936 -0.499214 + outer loop + vertex -851.675 258.198 277.215 + vertex -850.744 259.379 275.519 + vertex -850.489 258.415 277.246 + endloop + endfacet + facet normal 0.108342 -0.867528 -0.485445 + outer loop + vertex -852.705 259.225 275.183 + vertex -851.905 259.156 275.484 + vertex -852.592 258.262 276.929 + endloop + endfacet + facet normal 0.0934297 -0.865851 -0.4915 + outer loop + vertex -852.592 258.262 276.929 + vertex -851.905 259.156 275.484 + vertex -851.675 258.198 277.215 + endloop + endfacet + facet normal 0.0979704 -0.857946 -0.504312 + outer loop + vertex -852.592 258.262 276.929 + vertex -851.675 258.198 277.215 + vertex -852.287 257.329 278.574 + endloop + endfacet + facet normal 0.0823427 -0.856116 -0.510181 + outer loop + vertex -852.287 257.329 278.574 + vertex -851.675 258.198 277.215 + vertex -851.427 257.198 278.933 + endloop + endfacet + facet normal 0.167321 -0.841381 -0.513889 + outer loop + vertex -851.675 258.198 277.215 + vertex -850.489 258.415 277.246 + vertex -851.427 257.198 278.933 + endloop + endfacet + facet normal 0.15571 -0.84018 -0.519472 + outer loop + vertex -851.427 257.198 278.933 + vertex -850.489 258.415 277.246 + vertex -850.215 257.415 278.945 + endloop + endfacet + facet normal 0.461188 -0.740512 -0.488823 + outer loop + vertex -849.464 259.915 275.412 + vertex -848.219 260.77 275.292 + vertex -849.191 258.956 277.123 + endloop + endfacet + facet normal 0.454263 -0.741621 -0.493602 + outer loop + vertex -849.191 258.956 277.123 + vertex -848.219 260.77 275.292 + vertex -847.928 259.82 276.986 + endloop + endfacet + facet normal 0.299222 -0.813733 -0.498302 + outer loop + vertex -850.744 259.379 275.519 + vertex -849.464 259.915 275.412 + vertex -850.489 258.415 277.246 + endloop + endfacet + facet normal 0.291295 -0.813833 -0.502816 + outer loop + vertex -850.489 258.415 277.246 + vertex -849.464 259.915 275.412 + vertex -849.191 258.956 277.123 + endloop + endfacet + facet normal 0.285998 -0.804982 -0.519816 + outer loop + vertex -850.489 258.415 277.246 + vertex -849.191 258.956 277.123 + vertex -850.215 257.415 278.945 + endloop + endfacet + facet normal 0.275419 -0.804874 -0.525664 + outer loop + vertex -850.215 257.415 278.945 + vertex -849.191 258.956 277.123 + vertex -848.893 257.959 278.805 + endloop + endfacet + facet normal 0.446219 -0.733005 -0.513412 + outer loop + vertex -849.191 258.956 277.123 + vertex -847.928 259.82 276.986 + vertex -848.893 257.959 278.805 + endloop + endfacet + facet normal 0.4415 -0.733645 -0.516567 + outer loop + vertex -848.893 257.959 278.805 + vertex -847.928 259.82 276.986 + vertex -847.609 258.838 278.654 + endloop + endfacet + facet normal 0.529254 -0.764688 -0.367617 + outer loop + vertex -850.597 264.921 264.962 + vertex -849.447 265.747 264.899 + vertex -850.457 264.158 266.751 + endloop + endfacet + facet normal 0.52267 -0.766657 -0.372899 + outer loop + vertex -850.457 264.158 266.751 + vertex -849.447 265.747 264.899 + vertex -849.292 264.982 266.691 + endloop + endfacet + facet normal 0.365918 -0.847403 -0.384724 + outer loop + vertex -851.761 264.38 265.046 + vertex -850.597 264.921 264.962 + vertex -851.634 263.623 266.836 + endloop + endfacet + facet normal 0.357877 -0.848466 -0.38991 + outer loop + vertex -851.634 263.623 266.836 + vertex -850.597 264.921 264.962 + vertex -850.457 264.158 266.751 + endloop + endfacet + facet normal 0.354538 -0.843338 -0.403837 + outer loop + vertex -851.634 263.623 266.836 + vertex -850.457 264.158 266.751 + vertex -851.499 262.846 268.576 + endloop + endfacet + facet normal 0.350458 -0.843775 -0.406477 + outer loop + vertex -851.499 262.846 268.576 + vertex -850.457 264.158 266.751 + vertex -850.302 263.384 268.492 + endloop + endfacet + facet normal 0.519256 -0.76274 -0.385487 + outer loop + vertex -850.457 264.158 266.751 + vertex -849.292 264.982 266.691 + vertex -850.302 263.384 268.492 + endloop + endfacet + facet normal 0.513155 -0.764385 -0.390367 + outer loop + vertex -850.302 263.384 268.492 + vertex -849.292 264.982 266.691 + vertex -849.122 264.206 268.433 + endloop + endfacet + facet normal 0.242315 -0.888963 -0.388624 + outer loop + vertex -852.794 264.123 264.991 + vertex -851.761 264.38 265.046 + vertex -852.684 263.357 266.811 + endloop + endfacet + facet normal 0.234017 -0.889213 -0.393111 + outer loop + vertex -852.684 263.357 266.811 + vertex -851.761 264.38 265.046 + vertex -851.634 263.623 266.836 + endloop + endfacet + facet normal 0.173348 -0.907001 -0.383797 + outer loop + vertex -853.5 264.162 264.579 + vertex -852.794 264.123 264.991 + vertex -853.487 263.351 266.501 + endloop + endfacet + facet normal 0.157353 -0.906819 -0.391048 + outer loop + vertex -853.487 263.351 266.501 + vertex -852.794 264.123 264.991 + vertex -852.684 263.357 266.811 + endloop + endfacet + facet normal 0.161018 -0.901981 -0.400628 + outer loop + vertex -853.487 263.351 266.501 + vertex -852.684 263.357 266.811 + vertex -853.294 262.598 268.274 + endloop + endfacet + facet normal 0.145499 -0.90177 -0.406991 + outer loop + vertex -853.294 262.598 268.274 + vertex -852.684 263.357 266.811 + vertex -852.563 262.581 268.574 + endloop + endfacet + facet normal 0.232989 -0.884039 -0.405204 + outer loop + vertex -852.684 263.357 266.811 + vertex -851.634 263.623 266.836 + vertex -852.563 262.581 268.574 + endloop + endfacet + facet normal 0.221079 -0.884133 -0.411623 + outer loop + vertex -852.563 262.581 268.574 + vertex -851.634 263.623 266.836 + vertex -851.499 262.846 268.576 + endloop + endfacet + facet normal 0.219759 -0.878722 -0.423738 + outer loop + vertex -852.563 262.581 268.574 + vertex -851.499 262.846 268.576 + vertex -852.428 261.782 270.3 + endloop + endfacet + facet normal 0.212678 -0.87864 -0.427505 + outer loop + vertex -852.428 261.782 270.3 + vertex -851.499 262.846 268.576 + vertex -851.343 262.048 270.295 + endloop + endfacet + facet normal 0.15035 -0.895707 -0.418454 + outer loop + vertex -853.294 262.598 268.274 + vertex -852.563 262.581 268.574 + vertex -853.251 261.738 270.13 + endloop + endfacet + facet normal 0.135465 -0.895132 -0.424721 + outer loop + vertex -853.251 261.738 270.13 + vertex -852.563 262.581 268.574 + vertex -852.428 261.782 270.3 + endloop + endfacet + facet normal 0.13747 -0.889426 -0.435917 + outer loop + vertex -853.251 261.738 270.13 + vertex -852.428 261.782 270.3 + vertex -853.041 260.949 271.807 + endloop + endfacet + facet normal 0.122167 -0.888765 -0.441783 + outer loop + vertex -853.041 260.949 271.807 + vertex -852.428 261.782 270.3 + vertex -852.28 260.947 272.023 + endloop + endfacet + facet normal 0.211025 -0.872164 -0.441359 + outer loop + vertex -852.428 261.782 270.3 + vertex -851.343 262.048 270.295 + vertex -852.28 260.947 272.023 + endloop + endfacet + facet normal 0.202445 -0.871913 -0.445853 + outer loop + vertex -852.28 260.947 272.023 + vertex -851.343 262.048 270.295 + vertex -851.168 261.204 272.024 + endloop + endfacet + facet normal 0.508387 -0.758749 -0.407239 + outer loop + vertex -850.302 263.384 268.492 + vertex -849.122 264.206 268.433 + vertex -850.128 262.575 270.215 + endloop + endfacet + facet normal 0.50165 -0.760373 -0.41253 + outer loop + vertex -850.128 262.575 270.215 + vertex -849.122 264.206 268.433 + vertex -848.931 263.4 270.15 + endloop + endfacet + facet normal 0.346914 -0.838159 -0.420881 + outer loop + vertex -851.499 262.846 268.576 + vertex -850.302 263.384 268.492 + vertex -851.343 262.048 270.295 + endloop + endfacet + facet normal 0.336441 -0.839038 -0.427578 + outer loop + vertex -851.343 262.048 270.295 + vertex -850.302 263.384 268.492 + vertex -850.128 262.575 270.215 + endloop + endfacet + facet normal 0.333262 -0.833655 -0.440404 + outer loop + vertex -851.343 262.048 270.295 + vertex -850.128 262.575 270.215 + vertex -851.168 261.204 272.024 + endloop + endfacet + facet normal 0.327808 -0.834011 -0.44381 + outer loop + vertex -851.168 261.204 272.024 + vertex -850.128 262.575 270.215 + vertex -849.932 261.733 271.943 + endloop + endfacet + facet normal 0.497898 -0.75592 -0.425068 + outer loop + vertex -850.128 262.575 270.215 + vertex -848.931 263.4 270.15 + vertex -849.932 261.733 271.943 + endloop + endfacet + facet normal 0.490765 -0.757499 -0.430518 + outer loop + vertex -849.932 261.733 271.943 + vertex -848.931 263.4 270.15 + vertex -848.719 262.563 271.865 + endloop + endfacet + facet normal 0.565529 -0.767208 -0.302604 + outer loop + vertex -851.027 267.863 257.309 + vertex -849.93 268.69 257.266 + vertex -850.939 267.165 259.245 + endloop + endfacet + facet normal 0.559169 -0.769785 -0.307833 + outer loop + vertex -850.939 267.165 259.245 + vertex -849.93 268.69 257.266 + vertex -849.827 267.993 259.193 + endloop + endfacet + facet normal 0.408469 -0.854642 -0.320531 + outer loop + vertex -852.134 267.311 257.372 + vertex -851.027 267.863 257.309 + vertex -852.062 266.619 259.308 + endloop + endfacet + facet normal 0.398037 -0.856965 -0.327379 + outer loop + vertex -852.062 266.619 259.308 + vertex -851.027 267.863 257.309 + vertex -850.939 267.165 259.245 + endloop + endfacet + facet normal 0.396181 -0.854217 -0.33668 + outer loop + vertex -852.062 266.619 259.308 + vertex -850.939 267.165 259.245 + vertex -851.975 265.891 261.258 + endloop + endfacet + facet normal 0.38915 -0.855653 -0.341204 + outer loop + vertex -851.975 265.891 261.258 + vertex -850.939 267.165 259.245 + vertex -850.839 266.435 261.191 + endloop + endfacet + facet normal 0.557126 -0.767602 -0.316856 + outer loop + vertex -850.939 267.165 259.245 + vertex -849.827 267.993 259.193 + vertex -850.839 266.435 261.191 + endloop + endfacet + facet normal 0.551606 -0.769733 -0.321313 + outer loop + vertex -850.839 266.435 261.191 + vertex -849.827 267.993 259.193 + vertex -849.715 267.264 261.133 + endloop + endfacet + facet normal 0.284627 -0.900819 -0.327891 + outer loop + vertex -853.099 267.019 257.336 + vertex -852.134 267.311 257.372 + vertex -853.051 266.333 259.261 + endloop + endfacet + facet normal 0.276309 -0.901752 -0.332411 + outer loop + vertex -853.051 266.333 259.261 + vertex -852.134 267.311 257.372 + vertex -852.062 266.619 259.308 + endloop + endfacet + facet normal 0.219506 -0.919551 -0.32595 + outer loop + vertex -853.741 266.967 257.05 + vertex -853.099 267.019 257.336 + vertex -853.78 266.255 259.033 + endloop + endfacet + facet normal 0.203301 -0.920752 -0.332994 + outer loop + vertex -853.78 266.255 259.033 + vertex -853.099 267.019 257.336 + vertex -853.051 266.333 259.261 + endloop + endfacet + facet normal 0.205438 -0.917339 -0.341004 + outer loop + vertex -853.78 266.255 259.033 + vertex -853.051 266.333 259.261 + vertex -853.646 265.616 260.833 + endloop + endfacet + facet normal 0.191841 -0.918206 -0.346547 + outer loop + vertex -853.646 265.616 260.833 + vertex -853.051 266.333 259.261 + vertex -852.982 265.619 261.193 + endloop + endfacet + facet normal 0.275757 -0.898258 -0.342185 + outer loop + vertex -853.051 266.333 259.261 + vertex -852.062 266.619 259.308 + vertex -852.982 265.619 261.193 + endloop + endfacet + facet normal 0.265584 -0.899221 -0.347659 + outer loop + vertex -852.982 265.619 261.193 + vertex -852.062 266.619 259.308 + vertex -851.975 265.891 261.258 + endloop + endfacet + facet normal 0.265214 -0.895574 -0.357222 + outer loop + vertex -852.982 265.619 261.193 + vertex -851.975 265.891 261.258 + vertex -852.897 264.876 263.117 + endloop + endfacet + facet normal 0.255078 -0.896332 -0.362664 + outer loop + vertex -852.897 264.876 263.117 + vertex -851.975 265.891 261.258 + vertex -851.872 265.143 263.18 + endloop + endfacet + facet normal 0.195659 -0.914699 -0.353615 + outer loop + vertex -853.646 265.616 260.833 + vertex -852.982 265.619 261.193 + vertex -853.657 264.865 262.768 + endloop + endfacet + facet normal 0.179004 -0.915223 -0.361004 + outer loop + vertex -853.657 264.865 262.768 + vertex -852.982 265.619 261.193 + vertex -852.897 264.876 263.117 + endloop + endfacet + facet normal 0.182891 -0.911014 -0.369601 + outer loop + vertex -853.657 264.865 262.768 + vertex -852.897 264.876 263.117 + vertex -853.5 264.162 264.579 + endloop + endfacet + facet normal 0.168397 -0.911306 -0.375718 + outer loop + vertex -853.5 264.162 264.579 + vertex -852.897 264.876 263.117 + vertex -852.794 264.123 264.991 + endloop + endfacet + facet normal 0.254644 -0.892274 -0.372832 + outer loop + vertex -852.897 264.876 263.117 + vertex -851.872 265.143 263.18 + vertex -852.794 264.123 264.991 + endloop + endfacet + facet normal 0.242794 -0.89289 -0.379207 + outer loop + vertex -852.794 264.123 264.991 + vertex -851.872 265.143 263.18 + vertex -851.761 264.38 265.046 + endloop + endfacet + facet normal 0.548677 -0.766617 -0.333544 + outer loop + vertex -850.839 266.435 261.191 + vertex -849.715 267.264 261.133 + vertex -850.724 265.683 263.105 + endloop + endfacet + facet normal 0.542655 -0.768788 -0.338366 + outer loop + vertex -850.724 265.683 263.105 + vertex -849.715 267.264 261.133 + vertex -849.589 266.512 263.044 + endloop + endfacet + facet normal 0.386798 -0.852129 -0.352512 + outer loop + vertex -851.975 265.891 261.258 + vertex -850.839 266.435 261.191 + vertex -851.872 265.143 263.18 + endloop + endfacet + facet normal 0.378964 -0.853563 -0.357515 + outer loop + vertex -851.872 265.143 263.18 + vertex -850.839 266.435 261.191 + vertex -850.724 265.683 263.105 + endloop + endfacet + facet normal 0.376333 -0.849619 -0.369488 + outer loop + vertex -851.872 265.143 263.18 + vertex -850.724 265.683 263.105 + vertex -851.761 264.38 265.046 + endloop + endfacet + facet normal 0.368268 -0.850891 -0.374651 + outer loop + vertex -851.761 264.38 265.046 + vertex -850.724 265.683 263.105 + vertex -850.597 264.921 264.962 + endloop + endfacet + facet normal 0.539422 -0.765303 -0.351192 + outer loop + vertex -850.724 265.683 263.105 + vertex -849.589 266.512 263.044 + vertex -850.597 264.921 264.962 + endloop + endfacet + facet normal 0.532018 -0.767742 -0.357112 + outer loop + vertex -850.597 264.921 264.962 + vertex -849.589 266.512 263.044 + vertex -849.447 265.747 264.899 + endloop + endfacet + facet normal 0.592799 -0.767983 -0.24247 + outer loop + vertex -851.226 270.281 249.857 + vertex -850.175 271.113 249.793 + vertex -851.194 269.719 251.716 + endloop + endfacet + facet normal 0.587724 -0.770452 -0.24695 + outer loop + vertex -851.194 269.719 251.716 + vertex -850.175 271.113 249.793 + vertex -850.139 270.53 251.695 + endloop + endfacet + facet normal 0.430614 -0.861942 -0.267634 + outer loop + vertex -852.273 269.749 249.886 + vertex -851.226 270.281 249.857 + vertex -852.254 269.18 251.751 + endloop + endfacet + facet normal 0.429951 -0.862127 -0.268102 + outer loop + vertex -852.254 269.18 251.751 + vertex -851.226 270.281 249.857 + vertex -851.194 269.719 251.716 + endloop + endfacet + facet normal 0.427964 -0.859052 -0.280849 + outer loop + vertex -852.254 269.18 251.751 + vertex -851.194 269.719 251.716 + vertex -852.225 268.587 253.607 + endloop + endfacet + facet normal 0.424001 -0.8601 -0.283639 + outer loop + vertex -852.225 268.587 253.607 + vertex -851.194 269.719 251.716 + vertex -851.157 269.128 253.563 + endloop + endfacet + facet normal 0.585912 -0.768371 -0.257515 + outer loop + vertex -851.194 269.719 251.716 + vertex -850.139 270.53 251.695 + vertex -851.157 269.128 253.563 + endloop + endfacet + facet normal 0.581384 -0.770447 -0.261539 + outer loop + vertex -851.157 269.128 253.563 + vertex -850.139 270.53 251.695 + vertex -850.092 269.94 253.537 + endloop + endfacet + facet normal 0.322269 -0.905707 -0.275387 + outer loop + vertex -853.202 269.455 249.765 + vertex -852.273 269.749 249.886 + vertex -853.181 268.889 251.653 + endloop + endfacet + facet normal 0.314149 -0.907075 -0.280224 + outer loop + vertex -853.181 268.889 251.653 + vertex -852.273 269.749 249.886 + vertex -852.254 269.18 251.751 + endloop + endfacet + facet normal 0.256686 -0.92648 -0.275221 + outer loop + vertex -853.821 269.417 249.316 + vertex -853.202 269.455 249.765 + vertex -853.885 268.815 251.284 + endloop + endfacet + facet normal 0.244708 -0.92792 -0.281216 + outer loop + vertex -853.885 268.815 251.284 + vertex -853.202 269.455 249.765 + vertex -853.181 268.889 251.653 + endloop + endfacet + facet normal 0.248705 -0.924284 -0.289559 + outer loop + vertex -853.885 268.815 251.284 + vertex -853.181 268.889 251.653 + vertex -853.789 268.252 253.163 + endloop + endfacet + facet normal 0.236268 -0.925764 -0.295192 + outer loop + vertex -853.789 268.252 253.163 + vertex -853.181 268.889 251.653 + vertex -853.164 268.289 253.547 + endloop + endfacet + facet normal 0.314201 -0.904274 -0.289079 + outer loop + vertex -853.181 268.889 251.653 + vertex -852.254 269.18 251.751 + vertex -853.164 268.289 253.547 + endloop + endfacet + facet normal 0.306109 -0.905526 -0.293802 + outer loop + vertex -853.164 268.289 253.547 + vertex -852.254 269.18 251.751 + vertex -852.225 268.587 253.607 + endloop + endfacet + facet normal 0.305823 -0.903034 -0.301665 + outer loop + vertex -853.164 268.289 253.547 + vertex -852.225 268.587 253.607 + vertex -853.139 267.666 255.437 + endloop + endfacet + facet normal 0.295914 -0.904429 -0.307316 + outer loop + vertex -853.139 267.666 255.437 + vertex -852.225 268.587 253.607 + vertex -852.188 267.965 255.473 + endloop + endfacet + facet normal 0.239753 -0.922947 -0.301143 + outer loop + vertex -853.789 268.252 253.163 + vertex -853.164 268.289 253.547 + vertex -853.845 267.576 255.19 + endloop + endfacet + facet normal 0.225573 -0.924379 -0.307638 + outer loop + vertex -853.845 267.576 255.19 + vertex -853.164 268.289 253.547 + vertex -853.139 267.666 255.437 + endloop + endfacet + facet normal 0.227595 -0.921598 -0.314416 + outer loop + vertex -853.845 267.576 255.19 + vertex -853.139 267.666 255.437 + vertex -853.741 266.967 257.05 + endloop + endfacet + facet normal 0.216646 -0.922673 -0.318967 + outer loop + vertex -853.741 266.967 257.05 + vertex -853.139 267.666 255.437 + vertex -853.099 267.019 257.336 + endloop + endfacet + facet normal 0.295505 -0.902357 -0.313734 + outer loop + vertex -853.139 267.666 255.437 + vertex -852.188 267.965 255.473 + vertex -853.099 267.019 257.336 + endloop + endfacet + facet normal 0.285177 -0.903673 -0.319451 + outer loop + vertex -853.099 267.019 257.336 + vertex -852.188 267.965 255.473 + vertex -852.134 267.311 257.372 + endloop + endfacet + facet normal 0.579322 -0.76811 -0.27275 + outer loop + vertex -851.157 269.128 253.563 + vertex -850.092 269.94 253.537 + vertex -851.102 268.512 255.416 + endloop + endfacet + facet normal 0.575911 -0.769612 -0.275723 + outer loop + vertex -851.102 268.512 255.416 + vertex -850.092 269.94 253.537 + vertex -850.02 269.335 255.379 + endloop + endfacet + facet normal 0.422217 -0.857432 -0.294182 + outer loop + vertex -852.225 268.587 253.607 + vertex -851.157 269.128 253.563 + vertex -852.188 267.965 255.473 + endloop + endfacet + facet normal 0.416626 -0.858829 -0.298051 + outer loop + vertex -852.188 267.965 255.473 + vertex -851.157 269.128 253.563 + vertex -851.102 268.512 255.416 + endloop + endfacet + facet normal 0.414998 -0.856513 -0.306859 + outer loop + vertex -852.188 267.965 255.473 + vertex -851.102 268.512 255.416 + vertex -852.134 267.311 257.372 + endloop + endfacet + facet normal 0.410535 -0.857579 -0.309871 + outer loop + vertex -852.134 267.311 257.372 + vertex -851.102 268.512 255.416 + vertex -851.027 267.863 257.309 + endloop + endfacet + facet normal 0.573981 -0.767515 -0.285425 + outer loop + vertex -851.102 268.512 255.416 + vertex -850.02 269.335 255.379 + vertex -851.027 267.863 257.309 + endloop + endfacet + facet normal 0.568125 -0.770008 -0.290381 + outer loop + vertex -851.027 267.863 257.309 + vertex -850.02 269.335 255.379 + vertex -849.93 268.69 257.266 + endloop + endfacet + facet normal 0.64249 -0.739631 -0.200381 + outer loop + vertex -851.229 272.439 242.37 + vertex -850.289 273.163 242.708 + vertex -851.244 271.9 244.309 + endloop + endfacet + facet normal 0.627399 -0.748118 -0.216076 + outer loop + vertex -851.244 271.9 244.309 + vertex -850.289 273.163 242.708 + vertex -850.221 272.701 244.509 + endloop + endfacet + facet normal 0.501621 -0.838882 -0.211316 + outer loop + vertex -852.3 271.823 242.27 + vertex -851.229 272.439 242.37 + vertex -852.299 271.339 244.197 + endloop + endfacet + facet normal 0.476178 -0.848234 -0.231847 + outer loop + vertex -852.299 271.339 244.197 + vertex -851.229 272.439 242.37 + vertex -851.244 271.9 244.309 + endloop + endfacet + facet normal 0.476318 -0.849474 -0.22697 + outer loop + vertex -852.299 271.339 244.197 + vertex -851.244 271.9 244.309 + vertex -852.295 270.828 246.115 + endloop + endfacet + facet normal 0.44764 -0.858794 -0.249183 + outer loop + vertex -852.295 270.828 246.115 + vertex -851.244 271.9 244.309 + vertex -851.269 271.335 246.212 + endloop + endfacet + facet normal 0.627435 -0.748663 -0.214078 + outer loop + vertex -851.244 271.9 244.309 + vertex -850.221 272.701 244.509 + vertex -851.269 271.335 246.212 + endloop + endfacet + facet normal 0.565247 -0.77755 -0.275521 + outer loop + vertex -851.269 271.335 246.212 + vertex -850.221 272.701 244.509 + vertex -850.451 271.853 246.429 + endloop + endfacet + facet normal 0.361828 -0.904915 -0.224075 + outer loop + vertex -853.229 271.473 242.184 + vertex -852.3 271.823 242.27 + vertex -853.232 270.999 244.094 + endloop + endfacet + facet normal 0.355226 -0.906507 -0.228167 + outer loop + vertex -853.232 270.999 244.094 + vertex -852.3 271.823 242.27 + vertex -852.299 271.339 244.197 + endloop + endfacet + facet normal 0.256101 -0.938348 -0.232198 + outer loop + vertex -853.822 271.395 241.845 + vertex -853.229 271.473 242.184 + vertex -853.905 270.881 243.831 + endloop + endfacet + facet normal 0.255226 -0.938485 -0.232607 + outer loop + vertex -853.905 270.881 243.831 + vertex -853.229 271.473 242.184 + vertex -853.232 270.999 244.094 + endloop + endfacet + facet normal 0.258948 -0.9346 -0.24386 + outer loop + vertex -853.905 270.881 243.831 + vertex -853.232 270.999 244.094 + vertex -853.834 270.433 245.625 + endloop + endfacet + facet normal 0.26264 -0.934005 -0.242189 + outer loop + vertex -853.834 270.433 245.625 + vertex -853.232 270.999 244.094 + vertex -853.227 270.509 245.987 + endloop + endfacet + facet normal 0.355324 -0.904751 -0.234883 + outer loop + vertex -853.232 270.999 244.094 + vertex -852.299 271.339 244.197 + vertex -853.227 270.509 245.987 + endloop + endfacet + facet normal 0.343714 -0.907331 -0.242098 + outer loop + vertex -853.227 270.509 245.987 + vertex -852.299 271.339 244.197 + vertex -852.295 270.828 246.115 + endloop + endfacet + facet normal 0.343941 -0.905704 -0.2478 + outer loop + vertex -853.227 270.509 245.987 + vertex -852.295 270.828 246.115 + vertex -853.215 269.998 247.875 + endloop + endfacet + facet normal 0.328632 -0.90875 -0.257246 + outer loop + vertex -853.215 269.998 247.875 + vertex -852.295 270.828 246.115 + vertex -852.288 270.294 248.012 + endloop + endfacet + facet normal 0.266593 -0.930969 -0.249449 + outer loop + vertex -853.834 270.433 245.625 + vertex -853.227 270.509 245.987 + vertex -853.904 269.905 247.52 + endloop + endfacet + facet normal 0.256516 -0.932437 -0.254482 + outer loop + vertex -853.904 269.905 247.52 + vertex -853.227 270.509 245.987 + vertex -853.215 269.998 247.875 + endloop + endfacet + facet normal 0.261002 -0.92847 -0.264237 + outer loop + vertex -853.904 269.905 247.52 + vertex -853.215 269.998 247.875 + vertex -853.821 269.417 249.316 + endloop + endfacet + facet normal 0.252028 -0.929721 -0.268516 + outer loop + vertex -853.821 269.417 249.316 + vertex -853.215 269.998 247.875 + vertex -853.202 269.455 249.765 + endloop + endfacet + facet normal 0.328904 -0.907125 -0.262576 + outer loop + vertex -853.215 269.998 247.875 + vertex -852.288 270.294 248.012 + vertex -853.202 269.455 249.765 + endloop + endfacet + facet normal 0.321999 -0.908377 -0.266771 + outer loop + vertex -853.202 269.455 249.765 + vertex -852.288 270.294 248.012 + vertex -852.273 269.749 249.886 + endloop + endfacet + facet normal 0.563606 -0.791726 -0.235623 + outer loop + vertex -851.269 271.335 246.212 + vertex -850.451 271.853 246.429 + vertex -851.272 270.787 248.045 + endloop + endfacet + facet normal 0.593267 -0.776922 -0.210775 + outer loop + vertex -851.272 270.787 248.045 + vertex -850.451 271.853 246.429 + vertex -850.262 271.598 247.903 + endloop + endfacet + facet normal 0.447838 -0.860188 -0.243961 + outer loop + vertex -852.295 270.828 246.115 + vertex -851.269 271.335 246.212 + vertex -852.288 270.294 248.012 + endloop + endfacet + facet normal 0.42879 -0.865785 -0.257982 + outer loop + vertex -852.288 270.294 248.012 + vertex -851.269 271.335 246.212 + vertex -851.272 270.787 248.045 + endloop + endfacet + facet normal 0.429019 -0.866425 -0.25544 + outer loop + vertex -852.288 270.294 248.012 + vertex -851.272 270.787 248.045 + vertex -852.273 269.749 249.886 + endloop + endfacet + facet normal 0.432743 -0.865346 -0.252806 + outer loop + vertex -852.273 269.749 249.886 + vertex -851.272 270.787 248.045 + vertex -851.226 270.281 249.857 + endloop + endfacet + facet normal 0.588537 -0.774637 -0.231434 + outer loop + vertex -851.272 270.787 248.045 + vertex -850.262 271.598 247.903 + vertex -851.226 270.281 249.857 + endloop + endfacet + facet normal 0.596045 -0.77075 -0.22511 + outer loop + vertex -851.226 270.281 249.857 + vertex -850.262 271.598 247.903 + vertex -850.175 271.113 249.793 + endloop + endfacet + facet normal 0.685363 -0.712875 -0.148617 + outer loop + vertex -851.17 274.256 234.6 + vertex -850.223 275.112 234.863 + vertex -851.219 273.794 236.591 + endloop + endfacet + facet normal 0.702914 -0.699594 -0.128376 + outer loop + vertex -851.219 273.794 236.591 + vertex -850.223 275.112 234.863 + vertex -850.093 274.908 236.689 + endloop + endfacet + facet normal 0.527421 -0.831323 -0.175296 + outer loop + vertex -852.243 273.593 234.517 + vertex -851.17 274.256 234.6 + vertex -852.271 273.155 236.509 + endloop + endfacet + facet normal 0.520819 -0.834298 -0.180819 + outer loop + vertex -852.271 273.155 236.509 + vertex -851.17 274.256 234.6 + vertex -851.219 273.794 236.591 + endloop + endfacet + facet normal 0.520783 -0.834122 -0.18173 + outer loop + vertex -852.271 273.155 236.509 + vertex -851.219 273.794 236.591 + vertex -852.299 272.717 238.442 + endloop + endfacet + facet normal 0.517295 -0.835649 -0.184654 + outer loop + vertex -852.299 272.717 238.442 + vertex -851.219 273.794 236.591 + vertex -851.239 273.359 238.505 + endloop + endfacet + facet normal 0.701652 -0.696333 -0.151013 + outer loop + vertex -851.219 273.794 236.591 + vertex -850.093 274.908 236.689 + vertex -851.239 273.359 238.505 + endloop + endfacet + facet normal 0.670323 -0.717613 -0.18894 + outer loop + vertex -851.239 273.359 238.505 + vertex -850.093 274.908 236.689 + vertex -850.283 274.19 238.742 + endloop + endfacet + facet normal 0.367583 -0.910355 -0.190097 + outer loop + vertex -853.147 273.255 234.389 + vertex -852.243 273.593 234.517 + vertex -853.167 272.839 236.342 + endloop + endfacet + facet normal 0.358718 -0.91273 -0.195567 + outer loop + vertex -853.167 272.839 236.342 + vertex -852.243 273.593 234.517 + vertex -852.271 273.155 236.509 + endloop + endfacet + facet normal 0.243056 -0.950063 -0.195713 + outer loop + vertex -853.691 273.2 233.983 + vertex -853.147 273.255 234.389 + vertex -853.8 272.765 235.956 + endloop + endfacet + facet normal 0.233307 -0.951562 -0.200243 + outer loop + vertex -853.8 272.765 235.956 + vertex -853.147 273.255 234.389 + vertex -853.167 272.839 236.342 + endloop + endfacet + facet normal 0.239113 -0.947909 -0.21046 + outer loop + vertex -853.8 272.765 235.956 + vertex -853.167 272.839 236.342 + vertex -853.769 272.355 237.837 + endloop + endfacet + facet normal 0.237813 -0.948106 -0.211046 + outer loop + vertex -853.769 272.355 237.837 + vertex -853.167 272.839 236.342 + vertex -853.2 272.394 238.306 + endloop + endfacet + facet normal 0.359213 -0.911414 -0.200724 + outer loop + vertex -853.167 272.839 236.342 + vertex -852.271 273.155 236.509 + vertex -853.2 272.394 238.306 + endloop + endfacet + facet normal 0.357656 -0.911812 -0.201696 + outer loop + vertex -853.2 272.394 238.306 + vertex -852.271 273.155 236.509 + vertex -852.299 272.717 238.442 + endloop + endfacet + facet normal 0.358115 -0.909942 -0.209186 + outer loop + vertex -853.2 272.394 238.306 + vertex -852.299 272.717 238.442 + vertex -853.217 271.939 240.252 + endloop + endfacet + facet normal 0.362658 -0.908782 -0.206383 + outer loop + vertex -853.217 271.939 240.252 + vertex -852.299 272.717 238.442 + vertex -852.304 272.281 240.352 + endloop + endfacet + facet normal 0.242924 -0.945351 -0.217482 + outer loop + vertex -853.769 272.355 237.837 + vertex -853.2 272.394 238.306 + vertex -853.872 271.851 239.913 + endloop + endfacet + facet normal 0.240527 -0.945705 -0.218605 + outer loop + vertex -853.872 271.851 239.913 + vertex -853.2 272.394 238.306 + vertex -853.217 271.939 240.252 + endloop + endfacet + facet normal 0.245245 -0.94211 -0.228657 + outer loop + vertex -853.872 271.851 239.913 + vertex -853.217 271.939 240.252 + vertex -853.822 271.395 241.845 + endloop + endfacet + facet normal 0.252596 -0.940936 -0.225466 + outer loop + vertex -853.822 271.395 241.845 + vertex -853.217 271.939 240.252 + vertex -853.229 271.473 242.184 + endloop + endfacet + facet normal 0.362855 -0.906354 -0.21647 + outer loop + vertex -853.217 271.939 240.252 + vertex -852.304 272.281 240.352 + vertex -853.229 271.473 242.184 + endloop + endfacet + facet normal 0.361824 -0.906614 -0.217105 + outer loop + vertex -853.229 271.473 242.184 + vertex -852.304 272.281 240.352 + vertex -852.3 271.823 242.27 + endloop + endfacet + facet normal 0.669987 -0.722725 -0.169666 + outer loop + vertex -851.239 273.359 238.505 + vertex -850.283 274.19 238.742 + vertex -851.235 272.912 240.424 + endloop + endfacet + facet normal 0.684086 -0.712909 -0.15423 + outer loop + vertex -851.235 272.912 240.424 + vertex -850.283 274.19 238.742 + vertex -850.103 273.957 240.617 + endloop + endfacet + facet normal 0.517048 -0.834807 -0.189101 + outer loop + vertex -852.299 272.717 238.442 + vertex -851.239 273.359 238.505 + vertex -852.304 272.281 240.352 + endloop + endfacet + facet normal 0.508315 -0.838502 -0.19629 + outer loop + vertex -852.304 272.281 240.352 + vertex -851.239 273.359 238.505 + vertex -851.235 272.912 240.424 + endloop + endfacet + facet normal 0.508069 -0.837563 -0.200885 + outer loop + vertex -852.304 272.281 240.352 + vertex -851.235 272.912 240.424 + vertex -852.3 271.823 242.27 + endloop + endfacet + facet normal 0.501817 -0.840089 -0.205985 + outer loop + vertex -852.3 271.823 242.27 + vertex -851.235 272.912 240.424 + vertex -851.229 272.439 242.37 + endloop + endfacet + facet normal 0.683621 -0.708635 -0.174635 + outer loop + vertex -851.235 272.912 240.424 + vertex -850.103 273.957 240.617 + vertex -851.229 272.439 242.37 + endloop + endfacet + facet normal 0.644177 -0.732391 -0.220545 + outer loop + vertex -851.229 272.439 242.37 + vertex -850.103 273.957 240.617 + vertex -850.289 273.163 242.708 + endloop + endfacet + facet normal 0.533785 -0.828647 -0.168578 + outer loop + vertex -852.452 274.188 231.018 + vertex -852.147 274.779 229.077 + vertex -851.428 275.001 230.264 + endloop + endfacet + facet normal 0.696802 -0.700647 -0.153496 + outer loop + vertex -850.012 276.502 229.836 + vertex -851.428 275.001 230.264 + vertex -850.654 276.549 226.71 + endloop + endfacet + facet normal 0.651598 -0.744436 -0.145724 + outer loop + vertex -852.153 275.131 227.253 + vertex -850.654 276.549 226.71 + vertex -852.147 274.779 229.077 + endloop + endfacet + facet normal 0.589356 -0.779731 -0.211372 + outer loop + vertex -851.428 275.001 230.264 + vertex -852.147 274.779 229.077 + vertex -850.654 276.549 226.71 + endloop + endfacet + facet normal 0.480561 -0.864536 -0.147098 + outer loop + vertex -852.918 274.791 226.749 + vertex -852.153 275.131 227.253 + vertex -852.994 274.417 228.698 + endloop + endfacet + facet normal 0.450432 -0.876387 -0.170463 + outer loop + vertex -852.994 274.417 228.698 + vertex -852.153 275.131 227.253 + vertex -852.147 274.779 229.077 + endloop + endfacet + facet normal 0.34409 -0.927057 -0.148884 + outer loop + vertex -853.5 274.654 226.259 + vertex -852.918 274.791 226.749 + vertex -853.611 274.28 228.33 + endloop + endfacet + facet normal 0.308335 -0.936399 -0.167589 + outer loop + vertex -853.611 274.28 228.33 + vertex -852.918 274.791 226.749 + vertex -852.994 274.417 228.698 + endloop + endfacet + facet normal 0.308387 -0.936364 -0.167688 + outer loop + vertex -853.611 274.28 228.33 + vertex -852.994 274.417 228.698 + vertex -853.591 273.95 230.21 + endloop + endfacet + facet normal 0.278446 -0.943125 -0.181612 + outer loop + vertex -853.591 273.95 230.21 + vertex -852.994 274.417 228.698 + vertex -853.083 274.019 230.63 + endloop + endfacet + facet normal 0.447491 -0.879733 -0.160695 + outer loop + vertex -852.994 274.417 228.698 + vertex -852.147 274.779 229.077 + vertex -853.083 274.019 230.63 + endloop + endfacet + facet normal 0.373721 -0.902018 -0.216094 + outer loop + vertex -853.083 274.019 230.63 + vertex -852.147 274.779 229.077 + vertex -852.452 274.188 231.018 + endloop + endfacet + facet normal 0.355255 -0.917389 -0.179418 + outer loop + vertex -853.083 274.019 230.63 + vertex -852.452 274.188 231.018 + vertex -853.143 273.628 232.508 + endloop + endfacet + facet normal 0.373836 -0.912011 -0.168769 + outer loop + vertex -853.143 273.628 232.508 + vertex -852.452 274.188 231.018 + vertex -852.291 273.97 232.552 + endloop + endfacet + facet normal 0.272803 -0.946149 -0.1743 + outer loop + vertex -853.591 273.95 230.21 + vertex -853.083 274.019 230.63 + vertex -853.719 273.546 232.2 + endloop + endfacet + facet normal 0.237534 -0.952515 -0.190505 + outer loop + vertex -853.719 273.546 232.2 + vertex -853.083 274.019 230.63 + vertex -853.143 273.628 232.508 + endloop + endfacet + facet normal 0.236909 -0.952926 -0.189223 + outer loop + vertex -853.719 273.546 232.2 + vertex -853.143 273.628 232.508 + vertex -853.691 273.2 233.983 + endloop + endfacet + facet normal 0.238104 -0.952728 -0.188722 + outer loop + vertex -853.691 273.2 233.983 + vertex -853.143 273.628 232.508 + vertex -853.147 273.255 234.389 + endloop + endfacet + facet normal 0.3736 -0.909967 -0.179953 + outer loop + vertex -853.143 273.628 232.508 + vertex -852.291 273.97 232.552 + vertex -853.147 273.255 234.389 + endloop + endfacet + facet normal 0.367217 -0.911825 -0.18365 + outer loop + vertex -853.147 273.255 234.389 + vertex -852.291 273.97 232.552 + vertex -852.243 273.593 234.517 + endloop + endfacet + facet normal 0.692689 -0.701169 -0.168946 + outer loop + vertex -851.428 275.001 230.264 + vertex -850.012 276.502 229.836 + vertex -851.158 274.749 232.414 + endloop + endfacet + facet normal 0.708527 -0.68879 -0.153486 + outer loop + vertex -851.158 274.749 232.414 + vertex -850.012 276.502 229.836 + vertex -849.957 275.937 232.631 + endloop + endfacet + facet normal 0.530865 -0.829512 -0.173473 + outer loop + vertex -852.452 274.188 231.018 + vertex -851.428 275.001 230.264 + vertex -852.291 273.97 232.552 + endloop + endfacet + facet normal 0.545382 -0.821876 -0.164553 + outer loop + vertex -852.291 273.97 232.552 + vertex -851.428 275.001 230.264 + vertex -851.158 274.749 232.414 + endloop + endfacet + facet normal 0.54428 -0.821357 -0.17068 + outer loop + vertex -852.291 273.97 232.552 + vertex -851.158 274.749 232.414 + vertex -852.243 273.593 234.517 + endloop + endfacet + facet normal 0.527065 -0.829641 -0.184116 + outer loop + vertex -852.243 273.593 234.517 + vertex -851.158 274.749 232.414 + vertex -851.17 274.256 234.6 + endloop + endfacet + facet normal 0.708565 -0.689206 -0.151431 + outer loop + vertex -851.158 274.749 232.414 + vertex -849.957 275.937 232.631 + vertex -851.17 274.256 234.6 + endloop + endfacet + facet normal 0.686465 -0.704922 -0.178468 + outer loop + vertex -851.17 274.256 234.6 + vertex -849.957 275.937 232.631 + vertex -850.223 275.112 234.863 + endloop + endfacet + facet normal 0.696351 -0.711873 -0.0912739 + outer loop + vertex -852.059 275.833 223.307 + vertex -851.853 276.297 221.259 + vertex -850.585 277.391 222.401 + endloop + endfacet + facet normal 0.693562 -0.711982 -0.109784 + outer loop + vertex -852.016 276.416 219.46 + vertex -850.535 278.017 218.428 + vertex -851.853 276.297 221.259 + endloop + endfacet + facet normal 0.701083 -0.705681 -0.102455 + outer loop + vertex -850.535 278.017 218.428 + vertex -850.585 277.391 222.401 + vertex -851.853 276.297 221.259 + endloop + endfacet + facet normal 0.498448 -0.858379 -0.12139 + outer loop + vertex -852.819 275.997 219.119 + vertex -852.016 276.416 219.46 + vertex -852.847 275.712 221.025 + endloop + endfacet + facet normal 0.522609 -0.846311 -0.103134 + outer loop + vertex -852.847 275.712 221.025 + vertex -852.016 276.416 219.46 + vertex -851.853 276.297 221.259 + endloop + endfacet + facet normal 0.319276 -0.938217 -0.133459 + outer loop + vertex -853.381 275.872 218.656 + vertex -852.819 275.997 219.119 + vertex -853.484 275.56 220.603 + endloop + endfacet + facet normal 0.313968 -0.939607 -0.136245 + outer loop + vertex -853.484 275.56 220.603 + vertex -852.819 275.997 219.119 + vertex -852.847 275.712 221.025 + endloop + endfacet + facet normal 0.321385 -0.935145 -0.149048 + outer loop + vertex -853.484 275.56 220.603 + vertex -852.847 275.712 221.025 + vertex -853.445 275.285 222.414 + endloop + endfacet + facet normal 0.335471 -0.931317 -0.141804 + outer loop + vertex -853.445 275.285 222.414 + vertex -852.847 275.712 221.025 + vertex -852.868 275.416 222.913 + endloop + endfacet + facet normal 0.525165 -0.841674 -0.125644 + outer loop + vertex -852.847 275.712 221.025 + vertex -851.853 276.297 221.259 + vertex -852.868 275.416 222.913 + endloop + endfacet + facet normal 0.506414 -0.85054 -0.141871 + outer loop + vertex -852.868 275.416 222.913 + vertex -851.853 276.297 221.259 + vertex -852.059 275.833 223.307 + endloop + endfacet + facet normal 0.503237 -0.854067 -0.131617 + outer loop + vertex -852.868 275.416 222.913 + vertex -852.059 275.833 223.307 + vertex -852.887 275.112 224.816 + endloop + endfacet + facet normal 0.520828 -0.845484 -0.117878 + outer loop + vertex -852.887 275.112 224.816 + vertex -852.059 275.833 223.307 + vertex -851.899 275.67 225.179 + endloop + endfacet + facet normal 0.334726 -0.931732 -0.140834 + outer loop + vertex -853.445 275.285 222.414 + vertex -852.868 275.416 222.913 + vertex -853.54 274.952 224.388 + endloop + endfacet + facet normal 0.32486 -0.934398 -0.146169 + outer loop + vertex -853.54 274.952 224.388 + vertex -852.868 275.416 222.913 + vertex -852.887 275.112 224.816 + endloop + endfacet + facet normal 0.330176 -0.931015 -0.155547 + outer loop + vertex -853.54 274.952 224.388 + vertex -852.887 275.112 224.816 + vertex -853.5 274.654 226.259 + endloop + endfacet + facet normal 0.34383 -0.92721 -0.148533 + outer loop + vertex -853.5 274.654 226.259 + vertex -852.887 275.112 224.816 + vertex -852.918 274.791 226.749 + endloop + endfacet + facet normal 0.523683 -0.841712 -0.131443 + outer loop + vertex -852.887 275.112 224.816 + vertex -851.899 275.67 225.179 + vertex -852.918 274.791 226.749 + endloop + endfacet + facet normal 0.488074 -0.857386 -0.163317 + outer loop + vertex -852.918 274.791 226.749 + vertex -851.899 275.67 225.179 + vertex -852.153 275.131 227.253 + endloop + endfacet + facet normal 0.661261 -0.741744 -0.112025 + outer loop + vertex -852.153 275.131 227.253 + vertex -851.899 275.67 225.179 + vertex -850.654 276.549 226.71 + endloop + endfacet + facet normal 0.685046 -0.718398 -0.120898 + outer loop + vertex -852.059 275.833 223.307 + vertex -850.585 277.391 222.401 + vertex -851.899 275.67 225.179 + endloop + endfacet + facet normal 0.67424 -0.726766 -0.131194 + outer loop + vertex -850.585 277.391 222.401 + vertex -850.654 276.549 226.71 + vertex -851.899 275.67 225.179 + endloop + endfacet + facet normal 0.707713 -0.702774 -0.0724605 + outer loop + vertex -851.949 276.976 215.542 + vertex -851.733 277.411 213.424 + vertex -850.484 278.558 214.491 + endloop + endfacet + facet normal 0.693728 -0.713827 -0.0958822 + outer loop + vertex -851.891 277.506 211.568 + vertex -850.444 279.049 210.551 + vertex -851.733 277.411 213.424 + endloop + endfacet + facet normal 0.710612 -0.699036 -0.0798716 + outer loop + vertex -850.444 279.049 210.551 + vertex -850.484 278.558 214.491 + vertex -851.733 277.411 213.424 + endloop + endfacet + facet normal 0.496242 -0.861734 -0.105631 + outer loop + vertex -852.677 277.099 211.196 + vertex -851.891 277.506 211.568 + vertex -852.706 276.839 213.192 + endloop + endfacet + facet normal 0.520874 -0.849078 -0.0880712 + outer loop + vertex -852.706 276.839 213.192 + vertex -851.891 277.506 211.568 + vertex -851.733 277.411 213.424 + endloop + endfacet + facet normal 0.325224 -0.939209 -0.110072 + outer loop + vertex -853.24 276.959 210.729 + vertex -852.677 277.099 211.196 + vertex -853.339 276.683 212.794 + endloop + endfacet + facet normal 0.306641 -0.944343 -0.119108 + outer loop + vertex -853.339 276.683 212.794 + vertex -852.677 277.099 211.196 + vertex -852.706 276.839 213.192 + endloop + endfacet + facet normal 0.310026 -0.942442 -0.125251 + outer loop + vertex -853.339 276.683 212.794 + vertex -852.706 276.839 213.192 + vertex -853.304 276.439 214.718 + endloop + endfacet + facet normal 0.321387 -0.939316 -0.119982 + outer loop + vertex -853.304 276.439 214.718 + vertex -852.706 276.839 213.192 + vertex -852.737 276.573 215.188 + endloop + endfacet + facet normal 0.52293 -0.845957 -0.104409 + outer loop + vertex -852.706 276.839 213.192 + vertex -851.733 277.411 213.424 + vertex -852.737 276.573 215.188 + endloop + endfacet + facet normal 0.495654 -0.859293 -0.12626 + outer loop + vertex -852.737 276.573 215.188 + vertex -851.733 277.411 213.424 + vertex -851.949 276.976 215.542 + endloop + endfacet + facet normal 0.492107 -0.863026 -0.114091 + outer loop + vertex -852.737 276.573 215.188 + vertex -851.949 276.976 215.542 + vertex -852.778 276.288 217.17 + endloop + endfacet + facet normal 0.52314 -0.847303 -0.0916574 + outer loop + vertex -852.778 276.288 217.17 + vertex -851.949 276.976 215.542 + vertex -851.794 276.873 217.376 + endloop + endfacet + facet normal 0.321803 -0.939102 -0.120545 + outer loop + vertex -853.304 276.439 214.718 + vertex -852.737 276.573 215.188 + vertex -853.405 276.141 216.769 + endloop + endfacet + facet normal 0.303464 -0.943983 -0.129638 + outer loop + vertex -853.405 276.141 216.769 + vertex -852.737 276.573 215.188 + vertex -852.778 276.288 217.17 + endloop + endfacet + facet normal 0.308222 -0.94124 -0.138084 + outer loop + vertex -853.405 276.141 216.769 + vertex -852.778 276.288 217.17 + vertex -853.381 275.872 218.656 + endloop + endfacet + facet normal 0.318906 -0.938414 -0.132957 + outer loop + vertex -853.381 275.872 218.656 + vertex -852.778 276.288 217.17 + vertex -852.819 275.997 219.119 + endloop + endfacet + facet normal 0.525398 -0.843138 -0.114347 + outer loop + vertex -852.778 276.288 217.17 + vertex -851.794 276.873 217.376 + vertex -852.819 275.997 219.119 + endloop + endfacet + facet normal 0.501794 -0.85455 -0.13397 + outer loop + vertex -852.819 275.997 219.119 + vertex -851.794 276.873 217.376 + vertex -852.016 276.416 219.46 + endloop + endfacet + facet normal 0.706037 -0.703744 -0.0790965 + outer loop + vertex -852.016 276.416 219.46 + vertex -851.794 276.873 217.376 + vertex -850.535 278.017 218.428 + endloop + endfacet + facet normal 0.696987 -0.710261 -0.0986865 + outer loop + vertex -851.949 276.976 215.542 + vertex -850.484 278.558 214.491 + vertex -851.794 276.873 217.376 + endloop + endfacet + facet normal 0.709065 -0.699748 -0.087063 + outer loop + vertex -850.484 278.558 214.491 + vertex -850.535 278.017 218.428 + vertex -851.794 276.873 217.376 + endloop + endfacet + facet normal 0.7118 -0.700068 -0.0569654 + outer loop + vertex -851.851 277.974 207.61 + vertex -851.645 278.356 205.506 + vertex -850.415 279.516 206.614 + endloop + endfacet + facet normal 0.706457 -0.703599 -0.076593 + outer loop + vertex -851.805 278.396 203.65 + vertex -850.386 279.929 202.659 + vertex -851.645 278.356 205.506 + endloop + endfacet + facet normal 0.716135 -0.6947 -0.0673931 + outer loop + vertex -850.386 279.929 202.659 + vertex -850.415 279.516 206.614 + vertex -851.645 278.356 205.506 + endloop + endfacet + facet normal 0.501253 -0.861392 -0.0821541 + outer loop + vertex -852.569 277.986 203.292 + vertex -851.805 278.396 203.65 + vertex -852.599 277.779 205.275 + endloop + endfacet + facet normal 0.527022 -0.847419 -0.0642507 + outer loop + vertex -852.599 277.779 205.275 + vertex -851.805 278.396 203.65 + vertex -851.645 278.356 205.506 + endloop + endfacet + facet normal 0.345187 -0.934715 -0.0845865 + outer loop + vertex -853.114 277.821 202.891 + vertex -852.569 277.986 203.292 + vertex -853.216 277.595 204.973 + endloop + endfacet + facet normal 0.32656 -0.940579 -0.0931173 + outer loop + vertex -853.216 277.595 204.973 + vertex -852.569 277.986 203.292 + vertex -852.599 277.779 205.275 + endloop + endfacet + facet normal 0.328828 -0.939232 -0.0985689 + outer loop + vertex -853.216 277.595 204.973 + vertex -852.599 277.779 205.275 + vertex -853.182 277.411 206.838 + endloop + endfacet + facet normal 0.335479 -0.937183 -0.0956098 + outer loop + vertex -853.182 277.411 206.838 + vertex -852.599 277.779 205.275 + vertex -852.628 277.568 207.247 + endloop + endfacet + facet normal 0.529568 -0.84422 -0.0827687 + outer loop + vertex -852.599 277.779 205.275 + vertex -851.645 278.356 205.506 + vertex -852.628 277.568 207.247 + endloop + endfacet + facet normal 0.499557 -0.859681 -0.106727 + outer loop + vertex -852.628 277.568 207.247 + vertex -851.645 278.356 205.506 + vertex -851.851 277.974 207.61 + endloop + endfacet + facet normal 0.495196 -0.863814 -0.0927685 + outer loop + vertex -852.628 277.568 207.247 + vertex -851.851 277.974 207.61 + vertex -852.654 277.342 209.216 + endloop + endfacet + facet normal 0.519857 -0.850922 -0.0753708 + outer loop + vertex -852.654 277.342 209.216 + vertex -851.851 277.974 207.61 + vertex -851.688 277.91 209.459 + endloop + endfacet + facet normal 0.335562 -0.937141 -0.0957386 + outer loop + vertex -853.182 277.411 206.838 + vertex -852.628 277.568 207.247 + vertex -853.275 277.171 208.864 + endloop + endfacet + facet normal 0.318039 -0.942353 -0.104026 + outer loop + vertex -853.275 277.171 208.864 + vertex -852.628 277.568 207.247 + vertex -852.654 277.342 209.216 + endloop + endfacet + facet normal 0.322252 -0.939929 -0.112639 + outer loop + vertex -853.275 277.171 208.864 + vertex -852.654 277.342 209.216 + vertex -853.24 276.959 210.729 + endloop + endfacet + facet normal 0.325881 -0.938876 -0.110965 + outer loop + vertex -853.24 276.959 210.729 + vertex -852.654 277.342 209.216 + vertex -852.677 277.099 211.196 + endloop + endfacet + facet normal 0.522956 -0.846785 -0.097328 + outer loop + vertex -852.654 277.342 209.216 + vertex -851.688 277.91 209.459 + vertex -852.677 277.099 211.196 + endloop + endfacet + facet normal 0.499527 -0.85848 -0.116121 + outer loop + vertex -852.677 277.099 211.196 + vertex -851.688 277.91 209.459 + vertex -851.891 277.506 211.568 + endloop + endfacet + facet normal 0.7053 -0.705724 -0.0671281 + outer loop + vertex -851.891 277.506 211.568 + vertex -851.688 277.91 209.459 + vertex -850.444 279.049 210.551 + endloop + endfacet + facet normal 0.700463 -0.708452 -0.0862937 + outer loop + vertex -851.851 277.974 207.61 + vertex -850.415 279.516 206.614 + vertex -851.688 277.91 209.459 + endloop + endfacet + facet normal 0.709582 -0.700334 -0.0776295 + outer loop + vertex -850.415 279.516 206.614 + vertex -850.444 279.049 210.551 + vertex -851.688 277.91 209.459 + endloop + endfacet + facet normal 0.716387 -0.696515 -0.0407017 + outer loop + vertex -851.766 278.778 199.667 + vertex -851.572 279.102 197.549 + vertex -850.359 280.283 198.68 + endloop + endfacet + facet normal 0.707929 -0.703671 -0.0606919 + outer loop + vertex -851.729 279.104 195.689 + vertex -850.334 280.593 194.69 + vertex -851.572 279.102 197.549 + endloop + endfacet + facet normal 0.720134 -0.692077 -0.0493606 + outer loop + vertex -850.334 280.593 194.69 + vertex -850.359 280.283 198.68 + vertex -851.572 279.102 197.549 + endloop + endfacet + facet normal 0.523254 -0.850184 -0.0582387 + outer loop + vertex -852.481 278.665 195.335 + vertex -851.729 279.104 195.689 + vertex -852.501 278.517 197.321 + endloop + endfacet + facet normal 0.54009 -0.84031 -0.0467159 + outer loop + vertex -852.501 278.517 197.321 + vertex -851.729 279.104 195.689 + vertex -851.572 279.102 197.549 + endloop + endfacet + facet normal 0.356742 -0.932124 -0.0622916 + outer loop + vertex -853.019 278.489 194.894 + vertex -852.481 278.665 195.335 + vertex -853.1 278.318 196.991 + endloop + endfacet + facet normal 0.347596 -0.935292 -0.0663743 + outer loop + vertex -853.1 278.318 196.991 + vertex -852.481 278.665 195.335 + vertex -852.501 278.517 197.321 + endloop + endfacet + facet normal 0.351516 -0.933193 -0.0747404 + outer loop + vertex -853.1 278.318 196.991 + vertex -852.501 278.517 197.321 + vertex -853.058 278.18 198.903 + endloop + endfacet + facet normal 0.355194 -0.931924 -0.0731757 + outer loop + vertex -853.058 278.18 198.903 + vertex -852.501 278.517 197.321 + vertex -852.525 278.352 199.311 + endloop + endfacet + facet normal 0.542475 -0.837695 -0.0631537 + outer loop + vertex -852.501 278.517 197.321 + vertex -851.572 279.102 197.549 + vertex -852.525 278.352 199.311 + endloop + endfacet + facet normal 0.517334 -0.851773 -0.0827548 + outer loop + vertex -852.525 278.352 199.311 + vertex -851.572 279.102 197.549 + vertex -851.766 278.778 199.667 + endloop + endfacet + facet normal 0.513531 -0.855162 -0.0705962 + outer loop + vertex -852.525 278.352 199.311 + vertex -851.766 278.778 199.667 + vertex -852.547 278.174 201.303 + endloop + endfacet + facet normal 0.535493 -0.842713 -0.05552 + outer loop + vertex -852.547 278.174 201.303 + vertex -851.766 278.778 199.667 + vertex -851.603 278.758 201.533 + endloop + endfacet + facet normal 0.354472 -0.932284 -0.0720791 + outer loop + vertex -853.058 278.18 198.903 + vertex -852.525 278.352 199.311 + vertex -853.148 277.984 200.997 + endloop + endfacet + facet normal 0.336551 -0.93826 -0.0800072 + outer loop + vertex -853.148 277.984 200.997 + vertex -852.525 278.352 199.311 + vertex -852.547 278.174 201.303 + endloop + endfacet + facet normal 0.33949 -0.936595 -0.086813 + outer loop + vertex -853.148 277.984 200.997 + vertex -852.547 278.174 201.303 + vertex -853.114 277.821 202.891 + endloop + endfacet + facet normal 0.345077 -0.93477 -0.0844148 + outer loop + vertex -853.114 277.821 202.891 + vertex -852.547 278.174 201.303 + vertex -852.569 277.986 203.292 + endloop + endfacet + facet normal 0.538011 -0.839738 -0.0733697 + outer loop + vertex -852.547 278.174 201.303 + vertex -851.603 278.758 201.533 + vertex -852.569 277.986 203.292 + endloop + endfacet + facet normal 0.506301 -0.856741 -0.0982534 + outer loop + vertex -852.569 277.986 203.292 + vertex -851.603 278.758 201.533 + vertex -851.805 278.396 203.65 + endloop + endfacet + facet normal 0.716272 -0.695975 -0.0507271 + outer loop + vertex -851.805 278.396 203.65 + vertex -851.603 278.758 201.533 + vertex -850.386 279.929 202.659 + endloop + endfacet + facet normal 0.705748 -0.705097 -0.0689823 + outer loop + vertex -851.766 278.778 199.667 + vertex -850.359 280.283 198.68 + vertex -851.603 278.758 201.533 + endloop + endfacet + facet normal 0.718835 -0.692862 -0.0567355 + outer loop + vertex -850.359 280.283 198.68 + vertex -850.386 279.929 202.659 + vertex -851.603 278.758 201.533 + endloop + endfacet + facet normal 0.723889 -0.689457 -0.0251833 + outer loop + vertex -851.697 279.374 191.705 + vertex -851.512 279.647 189.572 + vertex -850.312 280.865 190.693 + endloop + endfacet + facet normal 0.713901 -0.698968 -0.0423055 + outer loop + vertex -851.68 279.588 187.7 + vertex -850.293 281.067 186.683 + vertex -851.512 279.647 189.572 + endloop + endfacet + facet normal 0.72638 -0.686596 -0.0309612 + outer loop + vertex -850.293 281.067 186.683 + vertex -850.312 280.865 190.693 + vertex -851.512 279.647 189.572 + endloop + endfacet + facet normal 0.514376 -0.856547 -0.0417682 + outer loop + vertex -852.432 279.154 187.346 + vertex -851.68 279.588 187.7 + vertex -852.446 279.048 189.336 + endloop + endfacet + facet normal 0.543323 -0.839222 -0.0225232 + outer loop + vertex -852.446 279.048 189.336 + vertex -851.68 279.588 187.7 + vertex -851.512 279.647 189.572 + endloop + endfacet + facet normal 0.359097 -0.932438 -0.0401042 + outer loop + vertex -852.973 278.963 186.927 + vertex -852.432 279.154 187.346 + vertex -853.047 278.847 188.958 + endloop + endfacet + facet normal 0.343103 -0.938107 -0.047285 + outer loop + vertex -853.047 278.847 188.958 + vertex -852.432 279.154 187.346 + vertex -852.446 279.048 189.336 + endloop + endfacet + facet normal 0.347393 -0.936095 -0.055173 + outer loop + vertex -853.047 278.847 188.958 + vertex -852.446 279.048 189.336 + vertex -852.994 278.756 190.851 + endloop + endfacet + facet normal 0.353726 -0.933877 -0.0524506 + outer loop + vertex -852.994 278.756 190.851 + vertex -852.446 279.048 189.336 + vertex -852.454 278.933 191.337 + endloop + endfacet + facet normal 0.547061 -0.835831 -0.0459453 + outer loop + vertex -852.446 279.048 189.336 + vertex -851.512 279.647 189.572 + vertex -852.454 278.933 191.337 + endloop + endfacet + facet normal 0.525176 -0.848671 -0.0628335 + outer loop + vertex -852.454 278.933 191.337 + vertex -851.512 279.647 189.572 + vertex -851.697 279.374 191.705 + endloop + endfacet + facet normal 0.521422 -0.851749 -0.051413 + outer loop + vertex -852.454 278.933 191.337 + vertex -851.697 279.374 191.705 + vertex -852.463 278.807 193.339 + endloop + endfacet + facet normal 0.544905 -0.837744 -0.0355484 + outer loop + vertex -852.463 278.807 193.339 + vertex -851.697 279.374 191.705 + vertex -851.535 279.4 193.571 + endloop + endfacet + facet normal 0.354287 -0.933624 -0.0531655 + outer loop + vertex -852.994 278.756 190.851 + vertex -852.454 278.933 191.337 + vertex -853.065 278.61 192.939 + endloop + endfacet + facet normal 0.34466 -0.936964 -0.0575061 + outer loop + vertex -853.065 278.61 192.939 + vertex -852.454 278.933 191.337 + vertex -852.463 278.807 193.339 + endloop + endfacet + facet normal 0.349548 -0.934588 -0.0660354 + outer loop + vertex -853.065 278.61 192.939 + vertex -852.463 278.807 193.339 + vertex -853.019 278.489 194.894 + endloop + endfacet + facet normal 0.3571 -0.931953 -0.0627954 + outer loop + vertex -853.019 278.489 194.894 + vertex -852.463 278.807 193.339 + vertex -852.481 278.665 195.335 + endloop + endfacet + facet normal 0.54774 -0.834896 -0.0541245 + outer loop + vertex -852.463 278.807 193.339 + vertex -851.535 279.4 193.571 + vertex -852.481 278.665 195.335 + endloop + endfacet + facet normal 0.527014 -0.846947 -0.0702617 + outer loop + vertex -852.481 278.665 195.335 + vertex -851.535 279.4 193.571 + vertex -851.729 279.104 195.689 + endloop + endfacet + facet normal 0.718956 -0.694346 -0.0313908 + outer loop + vertex -851.729 279.104 195.689 + vertex -851.535 279.4 193.571 + vertex -850.334 280.593 194.69 + endloop + endfacet + facet normal 0.713808 -0.698397 -0.0521519 + outer loop + vertex -851.697 279.374 191.705 + vertex -850.312 280.865 190.693 + vertex -851.535 279.4 193.571 + endloop + endfacet + facet normal 0.723903 -0.688569 -0.0428596 + outer loop + vertex -850.312 280.865 190.693 + vertex -850.334 280.593 194.69 + vertex -851.535 279.4 193.571 + endloop + endfacet + facet normal 0.726803 -0.68679 -0.00875896 + outer loop + vertex -851.655 279.759 183.708 + vertex -851.468 279.984 181.585 + vertex -850.276 281.231 182.683 + endloop + endfacet + facet normal 0.719219 -0.694261 -0.0269432 + outer loop + vertex -851.639 279.879 179.724 + vertex -850.266 281.342 178.698 + vertex -851.468 279.984 181.585 + endloop + endfacet + facet normal 0.730309 -0.682906 -0.0169781 + outer loop + vertex -850.266 281.342 178.698 + vertex -850.276 281.231 182.683 + vertex -851.468 279.984 181.585 + endloop + endfacet + facet normal 0.521367 -0.853095 -0.0201184 + outer loop + vertex -852.387 279.43 179.368 + vertex -851.639 279.879 179.724 + vertex -852.392 279.38 181.374 + endloop + endfacet + facet normal 0.547628 -0.836716 -0.00317781 + outer loop + vertex -852.392 279.38 181.374 + vertex -851.639 279.879 179.724 + vertex -851.468 279.984 181.585 + endloop + endfacet + facet normal 0.359119 -0.933135 -0.0171095 + outer loop + vertex -852.92 279.233 178.9 + vertex -852.387 279.43 179.368 + vertex -852.991 279.168 181.01 + endloop + endfacet + facet normal 0.34607 -0.937935 -0.022672 + outer loop + vertex -852.991 279.168 181.01 + vertex -852.387 279.43 179.368 + vertex -852.392 279.38 181.374 + endloop + endfacet + facet normal 0.350458 -0.936067 -0.0309609 + outer loop + vertex -852.991 279.168 181.01 + vertex -852.392 279.38 181.374 + vertex -852.944 279.121 182.949 + endloop + endfacet + facet normal 0.359575 -0.932719 -0.0272185 + outer loop + vertex -852.944 279.121 182.949 + vertex -852.392 279.38 181.374 + vertex -852.403 279.317 183.371 + endloop + endfacet + facet normal 0.550662 -0.834407 -0.0231526 + outer loop + vertex -852.392 279.38 181.374 + vertex -851.468 279.984 181.585 + vertex -852.403 279.317 183.371 + endloop + endfacet + facet normal 0.522618 -0.851422 -0.0441702 + outer loop + vertex -852.403 279.317 183.371 + vertex -851.468 279.984 181.585 + vertex -851.655 279.759 183.708 + endloop + endfacet + facet normal 0.517979 -0.854891 -0.0293206 + outer loop + vertex -852.403 279.317 183.371 + vertex -851.655 279.759 183.708 + vertex -852.418 279.24 185.36 + endloop + endfacet + facet normal 0.546019 -0.837701 -0.0109804 + outer loop + vertex -852.418 279.24 185.36 + vertex -851.655 279.759 183.708 + vertex -851.49 279.842 185.57 + endloop + endfacet + facet normal 0.359906 -0.932577 -0.0277094 + outer loop + vertex -852.944 279.121 182.949 + vertex -852.403 279.317 183.371 + vertex -853.019 279.03 185.028 + endloop + endfacet + facet normal 0.345768 -0.937709 -0.0338534 + outer loop + vertex -853.019 279.03 185.028 + vertex -852.403 279.317 183.371 + vertex -852.418 279.24 185.36 + endloop + endfacet + facet normal 0.349364 -0.936072 -0.0413967 + outer loop + vertex -853.019 279.03 185.028 + vertex -852.418 279.24 185.36 + vertex -852.973 278.963 186.927 + endloop + endfacet + facet normal 0.357648 -0.933086 -0.037934 + outer loop + vertex -852.973 278.963 186.927 + vertex -852.418 279.24 185.36 + vertex -852.432 279.154 187.346 + endloop + endfacet + facet normal 0.549161 -0.83509 -0.0323446 + outer loop + vertex -852.418 279.24 185.36 + vertex -851.49 279.842 185.57 + vertex -852.432 279.154 187.346 + endloop + endfacet + facet normal 0.518809 -0.853092 -0.055418 + outer loop + vertex -852.432 279.154 187.346 + vertex -851.49 279.842 185.57 + vertex -851.68 279.588 187.7 + endloop + endfacet + facet normal 0.722977 -0.690642 -0.0178077 + outer loop + vertex -851.68 279.588 187.7 + vertex -851.49 279.842 185.57 + vertex -850.293 281.067 186.683 + endloop + endfacet + facet normal 0.718076 -0.695201 -0.0325895 + outer loop + vertex -851.655 279.759 183.708 + vertex -850.276 281.231 182.683 + vertex -851.49 279.842 185.57 + endloop + endfacet + facet normal 0.726192 -0.687029 -0.0252445 + outer loop + vertex -850.276 281.231 182.683 + vertex -850.293 281.067 186.683 + vertex -851.49 279.842 185.57 + endloop + endfacet + facet normal 0.726282 -0.687362 0.00692281 + outer loop + vertex -851.628 279.955 175.716 + vertex -851.449 280.122 173.588 + vertex -850.259 281.392 174.722 + endloop + endfacet + facet normal 0.720565 -0.693296 -0.0112698 + outer loop + vertex -851.626 279.97 171.724 + vertex -850.256 281.408 170.782 + vertex -851.449 280.122 173.588 + endloop + endfacet + facet normal 0.730436 -0.682977 -0.00234493 + outer loop + vertex -850.256 281.408 170.782 + vertex -850.259 281.392 174.722 + vertex -851.449 280.122 173.588 + endloop + endfacet + facet normal 0.521236 -0.853412 -0.00129577 + outer loop + vertex -852.377 279.511 171.324 + vertex -851.626 279.97 171.724 + vertex -852.374 279.51 173.309 + endloop + endfacet + facet normal 0.548561 -0.835944 0.0166715 + outer loop + vertex -852.374 279.51 173.309 + vertex -851.626 279.97 171.724 + vertex -851.449 280.122 173.588 + endloop + endfacet + facet normal 0.357947 -0.933734 0.003831 + outer loop + vertex -852.916 279.303 170.849 + vertex -852.377 279.511 171.324 + vertex -852.978 279.287 172.894 + endloop + endfacet + facet normal 0.346619 -0.938005 -0.00111803 + outer loop + vertex -852.978 279.287 172.894 + vertex -852.377 279.511 171.324 + vertex -852.374 279.51 173.309 + endloop + endfacet + facet normal 0.351088 -0.936304 -0.00852512 + outer loop + vertex -852.978 279.287 172.894 + vertex -852.374 279.51 173.309 + vertex -852.911 279.295 174.827 + endloop + endfacet + facet normal 0.355399 -0.93469 -0.00676993 + outer loop + vertex -852.911 279.295 174.827 + vertex -852.374 279.51 173.309 + vertex -852.376 279.495 175.324 + endloop + endfacet + facet normal 0.553355 -0.832925 -0.00584647 + outer loop + vertex -852.374 279.51 173.309 + vertex -851.449 280.122 173.588 + vertex -852.376 279.495 175.324 + endloop + endfacet + facet normal 0.532417 -0.846201 -0.0218185 + outer loop + vertex -852.376 279.495 175.324 + vertex -851.449 280.122 173.588 + vertex -851.628 279.955 175.716 + endloop + endfacet + facet normal 0.527622 -0.849433 -0.00885945 + outer loop + vertex -852.376 279.495 175.324 + vertex -851.628 279.955 175.716 + vertex -852.379 279.472 177.346 + endloop + endfacet + facet normal 0.55014 -0.835052 0.00576794 + outer loop + vertex -852.379 279.472 177.346 + vertex -851.628 279.955 175.716 + vertex -851.457 280.081 177.592 + endloop + endfacet + facet normal 0.355911 -0.934491 -0.00740073 + outer loop + vertex -852.911 279.295 174.827 + vertex -852.376 279.495 175.324 + vertex -852.98 279.252 176.94 + endloop + endfacet + facet normal 0.349665 -0.936821 -0.0100863 + outer loop + vertex -852.98 279.252 176.94 + vertex -852.376 279.495 175.324 + vertex -852.379 279.472 177.346 + endloop + endfacet + facet normal 0.355288 -0.934551 -0.0196314 + outer loop + vertex -852.98 279.252 176.94 + vertex -852.379 279.472 177.346 + vertex -852.92 279.233 178.9 + endloop + endfacet + facet normal 0.359682 -0.932904 -0.0178463 + outer loop + vertex -852.92 279.233 178.9 + vertex -852.379 279.472 177.346 + vertex -852.387 279.43 179.368 + endloop + endfacet + facet normal 0.553921 -0.832436 -0.0148976 + outer loop + vertex -852.379 279.472 177.346 + vertex -851.457 280.081 177.592 + vertex -852.387 279.43 179.368 + endloop + endfacet + facet normal 0.526485 -0.849443 -0.0355013 + outer loop + vertex -852.387 279.43 179.368 + vertex -851.457 280.081 177.592 + vertex -851.639 279.879 179.724 + endloop + endfacet + facet normal 0.728004 -0.685568 -0.00277576 + outer loop + vertex -851.639 279.879 179.724 + vertex -851.457 280.081 177.592 + vertex -850.266 281.342 178.698 + endloop + endfacet + facet normal 0.717285 -0.696528 -0.0187256 + outer loop + vertex -851.628 279.955 175.716 + vertex -850.259 281.392 174.722 + vertex -851.457 280.081 177.592 + endloop + endfacet + facet normal 0.730011 -0.683395 -0.00741413 + outer loop + vertex -850.259 281.392 174.722 + vertex -850.266 281.342 178.698 + vertex -851.457 280.081 177.592 + endloop + endfacet + facet normal 0.725211 -0.688128 0.0234259 + outer loop + vertex -851.629 279.949 167.85 + vertex -851.454 280.065 165.834 + vertex -850.258 281.361 166.912 + endloop + endfacet + facet normal 0.720336 -0.6936 0.00596431 + outer loop + vertex -851.627 279.87 164.066 + vertex -850.26 281.281 163.089 + vertex -851.454 280.065 165.834 + endloop + endfacet + facet normal 0.729268 -0.684084 0.0140619 + outer loop + vertex -850.26 281.281 163.089 + vertex -850.258 281.361 166.912 + vertex -851.454 280.065 165.834 + endloop + endfacet + facet normal 0.525361 -0.850614 0.0212407 + outer loop + vertex -852.37 279.402 163.728 + vertex -851.627 279.87 164.066 + vertex -852.373 279.448 165.617 + endloop + endfacet + facet normal 0.550802 -0.833768 0.0380558 + outer loop + vertex -852.373 279.448 165.617 + vertex -851.627 279.87 164.066 + vertex -851.454 280.065 165.834 + endloop + endfacet + facet normal 0.363452 -0.931241 0.0263009 + outer loop + vertex -852.899 279.183 163.281 + vertex -852.37 279.402 163.728 + vertex -852.966 279.214 165.28 + endloop + endfacet + facet normal 0.3558 -0.934279 0.022994 + outer loop + vertex -852.966 279.214 165.28 + vertex -852.37 279.402 163.728 + vertex -852.373 279.448 165.617 + endloop + endfacet + facet normal 0.359256 -0.9331 0.0160827 + outer loop + vertex -852.966 279.214 165.28 + vertex -852.373 279.448 165.617 + vertex -852.904 279.269 167.091 + endloop + endfacet + facet normal 0.363 -0.931623 0.0176118 + outer loop + vertex -852.904 279.269 167.091 + vertex -852.373 279.448 165.617 + vertex -852.378 279.481 167.496 + endloop + endfacet + facet normal 0.55468 -0.831903 0.0163483 + outer loop + vertex -852.373 279.448 165.617 + vertex -851.454 280.065 165.834 + vertex -852.378 279.481 167.496 + endloop + endfacet + facet normal 0.530489 -0.847687 -0.00264784 + outer loop + vertex -852.378 279.481 167.496 + vertex -851.454 280.065 165.834 + vertex -851.629 279.949 167.85 + endloop + endfacet + facet normal 0.52607 -0.85038 0.0102272 + outer loop + vertex -852.378 279.481 167.496 + vertex -851.629 279.949 167.85 + vertex -852.377 279.504 169.388 + endloop + endfacet + facet normal 0.548042 -0.836076 0.025054 + outer loop + vertex -852.377 279.504 169.388 + vertex -851.629 279.949 167.85 + vertex -851.451 280.119 169.652 + endloop + endfacet + facet normal 0.363684 -0.931375 0.0165912 + outer loop + vertex -852.904 279.269 167.091 + vertex -852.378 279.481 167.496 + vertex -852.974 279.276 169.039 + endloop + endfacet + facet normal 0.351666 -0.936057 0.0113237 + outer loop + vertex -852.974 279.276 169.039 + vertex -852.378 279.481 167.496 + vertex -852.377 279.504 169.388 + endloop + endfacet + facet normal 0.356248 -0.934388 0.00240542 + outer loop + vertex -852.974 279.276 169.039 + vertex -852.377 279.504 169.388 + vertex -852.916 279.303 170.849 + endloop + endfacet + facet normal 0.358359 -0.933578 0.00329488 + outer loop + vertex -852.916 279.303 170.849 + vertex -852.377 279.504 169.388 + vertex -852.377 279.511 171.324 + endloop + endfacet + facet normal 0.552595 -0.833445 0.00291214 + outer loop + vertex -852.377 279.504 169.388 + vertex -851.451 280.119 169.652 + vertex -852.377 279.511 171.324 + endloop + endfacet + facet normal 0.527227 -0.849555 -0.0169872 + outer loop + vertex -852.377 279.511 171.324 + vertex -851.451 280.119 169.652 + vertex -851.626 279.97 171.724 + endloop + endfacet + facet normal 0.728112 -0.685357 0.0118201 + outer loop + vertex -851.626 279.97 171.724 + vertex -851.451 280.119 169.652 + vertex -850.256 281.408 170.782 + endloop + endfacet + facet normal 0.716129 -0.697953 -0.00462071 + outer loop + vertex -851.629 279.949 167.85 + vertex -850.258 281.361 166.912 + vertex -851.451 280.119 169.652 + endloop + endfacet + facet normal 0.729869 -0.683541 0.00789093 + outer loop + vertex -850.258 281.361 166.912 + vertex -850.256 281.408 170.782 + vertex -851.451 280.119 169.652 + endloop + endfacet + facet normal 0.727045 -0.685597 0.0369136 + outer loop + vertex -851.633 279.752 160.237 + vertex -851.468 279.815 158.161 + vertex -850.267 281.147 159.237 + endloop + endfacet + facet normal 0.71386 -0.700049 0.0183077 + outer loop + vertex -851.651 279.581 156.328 + vertex -850.276 280.957 155.325 + vertex -851.468 279.815 158.161 + endloop + endfacet + facet normal 0.729388 -0.683373 0.031544 + outer loop + vertex -850.276 280.957 155.325 + vertex -850.267 281.147 159.237 + vertex -851.468 279.815 158.161 + endloop + endfacet + facet normal 0.519915 -0.853379 0.0378566 + outer loop + vertex -852.407 279.105 155.968 + vertex -851.651 279.581 156.328 + vertex -852.4 279.196 157.927 + endloop + endfacet + facet normal 0.543768 -0.83757 0.0528401 + outer loop + vertex -852.4 279.196 157.927 + vertex -851.651 279.581 156.328 + vertex -851.468 279.815 158.161 + endloop + endfacet + facet normal 0.35486 -0.933724 0.0472599 + outer loop + vertex -852.949 278.876 155.528 + vertex -852.407 279.105 155.968 + vertex -852.999 278.959 157.525 + endloop + endfacet + facet normal 0.343201 -0.938305 0.0423996 + outer loop + vertex -852.999 278.959 157.525 + vertex -852.407 279.105 155.968 + vertex -852.4 279.196 157.927 + endloop + endfacet + facet normal 0.348608 -0.936674 0.0333803 + outer loop + vertex -852.999 278.959 157.525 + vertex -852.4 279.196 157.927 + vertex -852.922 279.053 159.382 + endloop + endfacet + facet normal 0.35606 -0.933756 0.0363399 + outer loop + vertex -852.922 279.053 159.382 + vertex -852.4 279.196 157.927 + vertex -852.384 279.277 159.874 + endloop + endfacet + facet normal 0.548162 -0.83581 0.0306508 + outer loop + vertex -852.4 279.196 157.927 + vertex -851.468 279.815 158.161 + vertex -852.384 279.277 159.874 + endloop + endfacet + facet normal 0.528711 -0.848647 0.0162215 + outer loop + vertex -852.384 279.277 159.874 + vertex -851.468 279.815 158.161 + vertex -851.633 279.752 160.237 + endloop + endfacet + facet normal 0.524536 -0.850932 0.027866 + outer loop + vertex -852.384 279.277 159.874 + vertex -851.633 279.752 160.237 + vertex -852.372 279.349 161.812 + endloop + endfacet + facet normal 0.550131 -0.833906 0.0442354 + outer loop + vertex -852.372 279.349 161.812 + vertex -851.633 279.752 160.237 + vertex -851.452 279.967 162.034 + endloop + endfacet + facet normal 0.357831 -0.933162 0.0341347 + outer loop + vertex -852.922 279.053 159.382 + vertex -852.384 279.277 159.874 + vertex -852.974 279.107 161.401 + endloop + endfacet + facet normal 0.353031 -0.935062 0.0320706 + outer loop + vertex -852.974 279.107 161.401 + vertex -852.384 279.277 159.874 + vertex -852.372 279.349 161.812 + endloop + endfacet + facet normal 0.358257 -0.93333 0.023394 + outer loop + vertex -852.974 279.107 161.401 + vertex -852.372 279.349 161.812 + vertex -852.899 279.183 163.281 + endloop + endfacet + facet normal 0.363911 -0.93108 0.0256774 + outer loop + vertex -852.899 279.183 163.281 + vertex -852.372 279.349 161.812 + vertex -852.37 279.402 163.728 + endloop + endfacet + facet normal 0.554131 -0.83212 0.0227004 + outer loop + vertex -852.372 279.349 161.812 + vertex -851.452 279.967 162.034 + vertex -852.37 279.402 163.728 + endloop + endfacet + facet normal 0.530818 -0.847471 0.00494373 + outer loop + vertex -852.37 279.402 163.728 + vertex -851.452 279.967 162.034 + vertex -851.627 279.87 164.066 + endloop + endfacet + facet normal 0.728207 -0.684709 0.0298005 + outer loop + vertex -851.627 279.87 164.066 + vertex -851.452 279.967 162.034 + vertex -850.26 281.281 163.089 + endloop + endfacet + facet normal 0.718226 -0.695727 0.0107368 + outer loop + vertex -851.633 279.752 160.237 + vertex -850.267 281.147 159.237 + vertex -851.452 279.967 162.034 + endloop + endfacet + facet normal 0.731406 -0.681577 0.0222879 + outer loop + vertex -850.267 281.147 159.237 + vertex -850.26 281.281 163.089 + vertex -851.452 279.967 162.034 + endloop + endfacet + facet normal 0.723831 -0.687787 0.0549358 + outer loop + vertex -851.663 279.357 152.371 + vertex -851.496 279.364 150.256 + vertex -850.287 280.725 151.373 + endloop + endfacet + facet normal 0.709085 -0.704301 0.0340418 + outer loop + vertex -851.682 279.087 148.396 + vertex -850.299 280.431 147.411 + vertex -851.496 279.364 150.256 + endloop + endfacet + facet normal 0.726737 -0.685192 0.0486302 + outer loop + vertex -850.299 280.431 147.411 + vertex -850.287 280.725 151.373 + vertex -851.496 279.364 150.256 + endloop + endfacet + facet normal 0.515172 -0.855089 0.0584832 + outer loop + vertex -852.45 278.598 148.023 + vertex -851.682 279.087 148.396 + vertex -852.43 278.746 150.015 + endloop + endfacet + facet normal 0.536813 -0.840664 0.0715257 + outer loop + vertex -852.43 278.746 150.015 + vertex -851.682 279.087 148.396 + vertex -851.496 279.364 150.256 + endloop + endfacet + facet normal 0.343189 -0.936691 0.069514 + outer loop + vertex -853.001 278.362 147.567 + vertex -852.45 278.598 148.023 + vertex -853.048 278.499 149.642 + endloop + endfacet + facet normal 0.335502 -0.93969 0.0664883 + outer loop + vertex -853.048 278.499 149.642 + vertex -852.45 278.598 148.023 + vertex -852.43 278.746 150.015 + endloop + endfacet + facet normal 0.340828 -0.938408 0.0567991 + outer loop + vertex -853.048 278.499 149.642 + vertex -852.43 278.746 150.015 + vertex -852.969 278.645 151.564 + endloop + endfacet + facet normal 0.352323 -0.933882 0.0610894 + outer loop + vertex -852.969 278.645 151.564 + vertex -852.43 278.746 150.015 + vertex -852.418 278.881 152.01 + endloop + endfacet + facet normal 0.5407 -0.839511 0.0535324 + outer loop + vertex -852.43 278.746 150.015 + vertex -851.496 279.364 150.256 + vertex -852.418 278.881 152.01 + endloop + endfacet + facet normal 0.519205 -0.853791 0.038308 + outer loop + vertex -852.418 278.881 152.01 + vertex -851.496 279.364 150.256 + vertex -851.663 279.357 152.371 + endloop + endfacet + facet normal 0.515361 -0.855587 0.0487294 + outer loop + vertex -852.418 278.881 152.01 + vertex -851.663 279.357 152.371 + vertex -852.415 278.996 153.998 + endloop + endfacet + facet normal 0.542872 -0.837256 0.0655151 + outer loop + vertex -852.415 278.996 153.998 + vertex -851.663 279.357 152.371 + vertex -851.481 279.62 154.225 + endloop + endfacet + facet normal 0.353166 -0.93364 0.0599213 + outer loop + vertex -852.969 278.645 151.564 + vertex -852.418 278.881 152.01 + vertex -853.016 278.759 153.633 + endloop + endfacet + facet normal 0.337903 -0.93964 0.0538457 + outer loop + vertex -853.016 278.759 153.633 + vertex -852.418 278.881 152.01 + vertex -852.415 278.996 153.998 + endloop + endfacet + facet normal 0.342308 -0.938469 0.0458419 + outer loop + vertex -853.016 278.759 153.633 + vertex -852.415 278.996 153.998 + vertex -852.949 278.876 155.528 + endloop + endfacet + facet normal 0.352971 -0.934303 0.0498924 + outer loop + vertex -852.949 278.876 155.528 + vertex -852.415 278.996 153.998 + vertex -852.407 279.105 155.968 + endloop + endfacet + facet normal 0.547224 -0.835846 0.0436663 + outer loop + vertex -852.415 278.996 153.998 + vertex -851.481 279.62 154.225 + vertex -852.407 279.105 155.968 + endloop + endfacet + facet normal 0.523934 -0.851339 0.0267181 + outer loop + vertex -852.407 279.105 155.968 + vertex -851.481 279.62 154.225 + vertex -851.651 279.581 156.328 + endloop + endfacet + facet normal 0.723089 -0.689236 0.0457832 + outer loop + vertex -851.651 279.581 156.328 + vertex -851.481 279.62 154.225 + vertex -850.276 280.957 155.325 + endloop + endfacet + facet normal 0.715326 -0.698191 0.0289436 + outer loop + vertex -851.663 279.357 152.371 + vertex -850.287 280.725 151.373 + vertex -851.481 279.62 154.225 + endloop + endfacet + facet normal 0.726476 -0.686124 0.03829 + outer loop + vertex -850.287 280.725 151.373 + vertex -850.276 280.957 155.325 + vertex -851.481 279.62 154.225 + endloop + endfacet + facet normal 0.716074 -0.694719 0.0678439 + outer loop + vertex -851.715 278.757 144.436 + vertex -851.549 278.723 142.329 + vertex -850.319 280.1 143.451 + endloop + endfacet + facet normal 0.708438 -0.703732 0.0536387 + outer loop + vertex -851.74 278.389 140.464 + vertex -850.339 279.723 139.476 + vertex -851.549 278.723 142.329 + endloop + endfacet + facet normal 0.718822 -0.692423 0.0620087 + outer loop + vertex -850.339 279.723 139.476 + vertex -850.319 280.1 143.451 + vertex -851.549 278.723 142.329 + endloop + endfacet + facet normal 0.510741 -0.85594 0.0806809 + outer loop + vertex -852.513 277.893 140.1 + vertex -851.74 278.389 140.464 + vertex -852.498 278.09 142.097 + endloop + endfacet + facet normal 0.535883 -0.838878 0.0954622 + outer loop + vertex -852.498 278.09 142.097 + vertex -851.74 278.389 140.464 + vertex -851.549 278.723 142.329 + endloop + endfacet + facet normal 0.345963 -0.933485 0.0944233 + outer loop + vertex -853.066 277.647 139.694 + vertex -852.513 277.893 140.1 + vertex -853.112 277.842 141.793 + endloop + endfacet + facet normal 0.334244 -0.938167 0.0901343 + outer loop + vertex -853.112 277.842 141.793 + vertex -852.513 277.893 140.1 + vertex -852.498 278.09 142.097 + endloop + endfacet + facet normal 0.338051 -0.937553 0.0819558 + outer loop + vertex -853.112 277.842 141.793 + vertex -852.498 278.09 142.097 + vertex -853.036 278.034 143.668 + endloop + endfacet + facet normal 0.34717 -0.933923 0.0852072 + outer loop + vertex -853.036 278.034 143.668 + vertex -852.498 278.09 142.097 + vertex -852.483 278.276 144.074 + endloop + endfacet + facet normal 0.540402 -0.838076 0.0747878 + outer loop + vertex -852.498 278.09 142.097 + vertex -851.549 278.723 142.329 + vertex -852.483 278.276 144.074 + endloop + endfacet + facet normal 0.511606 -0.857496 0.0544027 + outer loop + vertex -852.483 278.276 144.074 + vertex -851.549 278.723 142.329 + vertex -851.715 278.757 144.436 + endloop + endfacet + facet normal 0.505977 -0.859756 0.0693342 + outer loop + vertex -852.483 278.276 144.074 + vertex -851.715 278.757 144.436 + vertex -852.466 278.445 146.044 + endloop + endfacet + facet normal 0.535735 -0.839882 0.0871011 + outer loop + vertex -852.466 278.445 146.044 + vertex -851.715 278.757 144.436 + vertex -851.521 279.073 146.288 + endloop + endfacet + facet normal 0.348619 -0.933579 0.0830313 + outer loop + vertex -853.036 278.034 143.668 + vertex -852.483 278.276 144.074 + vertex -853.082 278.197 145.703 + endloop + endfacet + facet normal 0.334629 -0.939148 0.0776222 + outer loop + vertex -853.082 278.197 145.703 + vertex -852.483 278.276 144.074 + vertex -852.466 278.445 146.044 + endloop + endfacet + facet normal 0.339323 -0.938179 0.0684176 + outer loop + vertex -853.082 278.197 145.703 + vertex -852.466 278.445 146.044 + vertex -853.001 278.362 147.567 + endloop + endfacet + facet normal 0.34299 -0.936744 0.0697826 + outer loop + vertex -853.001 278.362 147.567 + vertex -852.466 278.445 146.044 + vertex -852.45 278.598 148.023 + endloop + endfacet + facet normal 0.541657 -0.838422 0.0604607 + outer loop + vertex -852.466 278.445 146.044 + vertex -851.521 279.073 146.288 + vertex -852.45 278.598 148.023 + endloop + endfacet + facet normal 0.520254 -0.852822 0.0450536 + outer loop + vertex -852.45 278.598 148.023 + vertex -851.521 279.073 146.288 + vertex -851.682 279.087 148.396 + endloop + endfacet + facet normal 0.717236 -0.69432 0.0591005 + outer loop + vertex -851.682 279.087 148.396 + vertex -851.521 279.073 146.288 + vertex -850.299 280.431 147.411 + endloop + endfacet + facet normal 0.709027 -0.703704 0.0456179 + outer loop + vertex -851.715 278.757 144.436 + vertex -850.319 280.1 143.451 + vertex -851.521 279.073 146.288 + endloop + endfacet + facet normal 0.719542 -0.692331 0.054187 + outer loop + vertex -850.319 280.1 143.451 + vertex -850.299 280.431 147.411 + vertex -851.521 279.073 146.288 + endloop + endfacet + facet normal 0.711768 -0.697236 0.0851296 + outer loop + vertex -851.775 277.967 136.446 + vertex -851.615 277.872 134.325 + vertex -850.367 279.288 135.482 + endloop + endfacet + facet normal 0.700091 -0.710614 0.0699941 + outer loop + vertex -851.811 277.495 132.469 + vertex -850.399 278.793 131.52 + vertex -851.615 277.872 134.325 + endloop + endfacet + facet normal 0.713853 -0.695608 0.0808902 + outer loop + vertex -850.399 278.793 131.52 + vertex -850.367 279.288 135.482 + vertex -851.615 277.872 134.325 + endloop + endfacet + facet normal 0.508859 -0.854983 0.10033 + outer loop + vertex -852.585 276.992 132.102 + vertex -851.811 277.495 132.469 + vertex -852.569 277.232 134.071 + endloop + endfacet + facet normal 0.531921 -0.839106 0.113844 + outer loop + vertex -852.569 277.232 134.071 + vertex -851.811 277.495 132.469 + vertex -851.615 277.872 134.325 + endloop + endfacet + facet normal 0.356188 -0.927353 0.114658 + outer loop + vertex -853.152 276.72 131.662 + vertex -852.585 276.992 132.102 + vertex -853.186 276.963 133.736 + endloop + endfacet + facet normal 0.346389 -0.931502 0.110986 + outer loop + vertex -853.186 276.963 133.736 + vertex -852.585 276.992 132.102 + vertex -852.569 277.232 134.071 + endloop + endfacet + facet normal 0.350432 -0.9309 0.103063 + outer loop + vertex -853.186 276.963 133.736 + vertex -852.569 277.232 134.071 + vertex -853.097 277.209 135.651 + endloop + endfacet + facet normal 0.354166 -0.929344 0.104333 + outer loop + vertex -853.097 277.209 135.651 + vertex -852.569 277.232 134.071 + vertex -852.551 277.464 136.071 + endloop + endfacet + facet normal 0.537218 -0.838396 0.0921294 + outer loop + vertex -852.569 277.232 134.071 + vertex -851.615 277.872 134.325 + vertex -852.551 277.464 136.071 + endloop + endfacet + facet normal 0.516049 -0.853059 0.0773597 + outer loop + vertex -852.551 277.464 136.071 + vertex -851.615 277.872 134.325 + vertex -851.775 277.967 136.446 + endloop + endfacet + facet normal 0.511443 -0.854689 0.0890707 + outer loop + vertex -852.551 277.464 136.071 + vertex -851.775 277.967 136.446 + vertex -852.528 277.688 138.086 + endloop + endfacet + facet normal 0.534517 -0.838938 0.102349 + outer loop + vertex -852.528 277.688 138.086 + vertex -851.775 277.967 136.446 + vertex -851.576 278.324 138.332 + endloop + endfacet + facet normal 0.354125 -0.929354 0.104392 + outer loop + vertex -853.097 277.209 135.651 + vertex -852.551 277.464 136.071 + vertex -853.14 277.43 137.77 + endloop + endfacet + facet normal 0.341424 -0.934587 0.0998852 + outer loop + vertex -853.14 277.43 137.77 + vertex -852.551 277.464 136.071 + vertex -852.528 277.688 138.086 + endloop + endfacet + facet normal 0.345306 -0.933983 0.091869 + outer loop + vertex -853.14 277.43 137.77 + vertex -852.528 277.688 138.086 + vertex -853.066 277.647 139.694 + endloop + endfacet + facet normal 0.347228 -0.933205 0.0925314 + outer loop + vertex -853.066 277.647 139.694 + vertex -852.528 277.688 138.086 + vertex -852.513 277.893 140.1 + endloop + endfacet + facet normal 0.539394 -0.838109 0.0814132 + outer loop + vertex -852.528 277.688 138.086 + vertex -851.576 278.324 138.332 + vertex -852.513 277.893 140.1 + endloop + endfacet + facet normal 0.516506 -0.853777 0.0654655 + outer loop + vertex -852.513 277.893 140.1 + vertex -851.576 278.324 138.332 + vertex -851.74 278.389 140.464 + endloop + endfacet + facet normal 0.715414 -0.694565 0.0759174 + outer loop + vertex -851.74 278.389 140.464 + vertex -851.576 278.324 138.332 + vertex -850.339 279.723 139.476 + endloop + endfacet + facet normal 0.704063 -0.707629 0.0596299 + outer loop + vertex -851.775 277.967 136.446 + vertex -850.367 279.288 135.482 + vertex -851.576 278.324 138.332 + endloop + endfacet + facet normal 0.717953 -0.692498 0.0706407 + outer loop + vertex -850.367 279.288 135.482 + vertex -850.339 279.723 139.476 + vertex -851.576 278.324 138.332 + endloop + endfacet + facet normal 0.695369 -0.711093 0.103966 + outer loop + vertex -851.85 276.991 128.599 + vertex -851.694 276.845 126.559 + vertex -850.437 278.23 127.625 + endloop + endfacet + facet normal 0.681448 -0.726305 0.0900522 + outer loop + vertex -851.901 276.429 124.771 + vertex -850.481 277.635 123.747 + vertex -851.694 276.845 126.559 + endloop + endfacet + facet normal 0.696719 -0.710173 0.101179 + outer loop + vertex -850.481 277.635 123.747 + vertex -850.437 278.23 127.625 + vertex -851.694 276.845 126.559 + endloop + endfacet + facet normal 0.491147 -0.862612 0.121145 + outer loop + vertex -852.695 275.929 124.427 + vertex -851.901 276.429 124.771 + vertex -852.674 276.208 126.327 + endloop + endfacet + facet normal 0.517152 -0.844926 0.136578 + outer loop + vertex -852.674 276.208 126.327 + vertex -851.901 276.429 124.771 + vertex -851.694 276.845 126.559 + endloop + endfacet + facet normal 0.345421 -0.928233 0.138084 + outer loop + vertex -853.273 275.65 124.002 + vertex -852.695 275.929 124.427 + vertex -853.317 275.923 125.945 + endloop + endfacet + facet normal 0.333796 -0.933171 0.133312 + outer loop + vertex -853.317 275.923 125.945 + vertex -852.695 275.929 124.427 + vertex -852.674 276.208 126.327 + endloop + endfacet + facet normal 0.33909 -0.932553 0.123945 + outer loop + vertex -853.317 275.923 125.945 + vertex -852.674 276.208 126.327 + vertex -853.216 276.201 127.756 + endloop + endfacet + facet normal 0.348445 -0.928615 0.127518 + outer loop + vertex -853.216 276.201 127.756 + vertex -852.674 276.208 126.327 + vertex -852.64 276.483 128.235 + endloop + endfacet + facet normal 0.522894 -0.844959 0.112362 + outer loop + vertex -852.674 276.208 126.327 + vertex -851.694 276.845 126.559 + vertex -852.64 276.483 128.235 + endloop + endfacet + facet normal 0.505496 -0.85702 0.0999459 + outer loop + vertex -852.64 276.483 128.235 + vertex -851.694 276.845 126.559 + vertex -851.85 276.991 128.599 + endloop + endfacet + facet normal 0.50277 -0.857783 0.106915 + outer loop + vertex -852.64 276.483 128.235 + vertex -851.85 276.991 128.599 + vertex -852.613 276.738 130.159 + endloop + endfacet + facet normal 0.53036 -0.838731 0.123486 + outer loop + vertex -852.613 276.738 130.159 + vertex -851.85 276.991 128.599 + vertex -851.647 277.385 130.403 + endloop + endfacet + facet normal 0.350458 -0.928219 0.124859 + outer loop + vertex -853.216 276.201 127.756 + vertex -852.64 276.483 128.235 + vertex -853.243 276.461 129.765 + endloop + endfacet + facet normal 0.336765 -0.933991 0.119374 + outer loop + vertex -853.243 276.461 129.765 + vertex -852.64 276.483 128.235 + vertex -852.613 276.738 130.159 + endloop + endfacet + facet normal 0.341573 -0.933259 0.111155 + outer loop + vertex -853.243 276.461 129.765 + vertex -852.613 276.738 130.159 + vertex -853.152 276.72 131.662 + endloop + endfacet + facet normal 0.355169 -0.927564 0.116101 + outer loop + vertex -853.152 276.72 131.662 + vertex -852.613 276.738 130.159 + vertex -852.585 276.992 132.102 + endloop + endfacet + facet normal 0.535545 -0.838337 0.101898 + outer loop + vertex -852.613 276.738 130.159 + vertex -851.647 277.385 130.403 + vertex -852.585 276.992 132.102 + endloop + endfacet + facet normal 0.514225 -0.853266 0.0866634 + outer loop + vertex -852.585 276.992 132.102 + vertex -851.647 277.385 130.403 + vertex -851.811 277.495 132.469 + endloop + endfacet + facet normal 0.707142 -0.700808 0.0939009 + outer loop + vertex -851.811 277.495 132.469 + vertex -851.647 277.385 130.403 + vertex -850.399 278.793 131.52 + endloop + endfacet + facet normal 0.68791 -0.721365 0.0800758 + outer loop + vertex -851.85 276.991 128.599 + vertex -850.437 278.23 127.625 + vertex -851.647 277.385 130.403 + endloop + endfacet + facet normal 0.706844 -0.701027 0.0945102 + outer loop + vertex -850.437 278.23 127.625 + vertex -850.399 278.793 131.52 + vertex -851.647 277.385 130.403 + endloop + endfacet + facet normal 0.678531 -0.723862 0.124976 + outer loop + vertex -851.936 275.832 120.942 + vertex -851.777 275.626 118.882 + vertex -850.523 276.967 119.839 + endloop + endfacet + facet normal 0.650813 -0.750838 0.112629 + outer loop + vertex -851.983 275.18 117.095 + vertex -850.572 276.222 115.888 + vertex -851.777 275.626 118.882 + endloop + endfacet + facet normal 0.676938 -0.724766 0.128332 + outer loop + vertex -850.572 276.222 115.888 + vertex -850.523 276.967 119.839 + vertex -851.777 275.626 118.882 + endloop + endfacet + facet normal 0.481747 -0.864706 0.14214 + outer loop + vertex -852.79 274.679 116.786 + vertex -851.983 275.18 117.095 + vertex -852.757 275.016 118.723 + endloop + endfacet + facet normal 0.504035 -0.849799 0.154242 + outer loop + vertex -852.757 275.016 118.723 + vertex -851.983 275.18 117.095 + vertex -851.777 275.626 118.882 + endloop + endfacet + facet normal 0.343265 -0.925505 0.160031 + outer loop + vertex -853.388 274.366 116.257 + vertex -852.79 274.679 116.786 + vertex -853.423 274.706 118.299 + endloop + endfacet + facet normal 0.333469 -0.929763 0.15601 + outer loop + vertex -853.423 274.706 118.299 + vertex -852.79 274.679 116.786 + vertex -852.757 275.016 118.723 + endloop + endfacet + facet normal 0.338493 -0.929292 0.147777 + outer loop + vertex -853.423 274.706 118.299 + vertex -852.757 275.016 118.723 + vertex -853.32 275.045 120.196 + endloop + endfacet + facet normal 0.344228 -0.926839 0.14992 + outer loop + vertex -853.32 275.045 120.196 + vertex -852.757 275.016 118.723 + vertex -852.733 275.334 120.632 + endloop + endfacet + facet normal 0.507769 -0.850817 0.135208 + outer loop + vertex -852.757 275.016 118.723 + vertex -851.777 275.626 118.882 + vertex -852.733 275.334 120.632 + endloop + endfacet + facet normal 0.491263 -0.862096 0.124306 + outer loop + vertex -852.733 275.334 120.632 + vertex -851.777 275.626 118.882 + vertex -851.936 275.832 120.942 + endloop + endfacet + facet normal 0.488118 -0.862561 0.133152 + outer loop + vertex -852.733 275.334 120.632 + vertex -851.936 275.832 120.942 + vertex -852.716 275.636 122.532 + endloop + endfacet + facet normal 0.511036 -0.847016 0.146306 + outer loop + vertex -852.716 275.636 122.532 + vertex -851.936 275.832 120.942 + vertex -851.736 276.261 122.723 + endloop + endfacet + facet normal 0.34414 -0.926852 0.150046 + outer loop + vertex -853.32 275.045 120.196 + vertex -852.733 275.334 120.632 + vertex -853.364 275.35 122.18 + endloop + endfacet + facet normal 0.33296 -0.931643 0.145533 + outer loop + vertex -853.364 275.35 122.18 + vertex -852.733 275.334 120.632 + vertex -852.716 275.636 122.532 + endloop + endfacet + facet normal 0.337595 -0.931308 0.136727 + outer loop + vertex -853.364 275.35 122.18 + vertex -852.716 275.636 122.532 + vertex -853.273 275.65 124.002 + endloop + endfacet + facet normal 0.344562 -0.928365 0.139338 + outer loop + vertex -853.273 275.65 124.002 + vertex -852.716 275.636 122.532 + vertex -852.695 275.929 124.427 + endloop + endfacet + facet normal 0.515593 -0.847663 0.125024 + outer loop + vertex -852.716 275.636 122.532 + vertex -851.736 276.261 122.723 + vertex -852.695 275.929 124.427 + endloop + endfacet + facet normal 0.495108 -0.861744 0.11075 + outer loop + vertex -852.695 275.929 124.427 + vertex -851.736 276.261 122.723 + vertex -851.901 276.429 124.771 + endloop + endfacet + facet normal 0.689518 -0.71519 0.114316 + outer loop + vertex -851.901 276.429 124.771 + vertex -851.736 276.261 122.723 + vertex -850.481 277.635 123.747 + endloop + endfacet + facet normal 0.66975 -0.735597 0.101646 + outer loop + vertex -851.936 275.832 120.942 + vertex -850.523 276.967 119.839 + vertex -851.736 276.261 122.723 + endloop + endfacet + facet normal 0.689274 -0.715345 0.114822 + outer loop + vertex -850.523 276.967 119.839 + vertex -850.481 277.635 123.747 + vertex -851.736 276.261 122.723 + endloop + endfacet + facet normal 0.547509 -0.81485 0.190402 + outer loop + vertex -852.023 273.488 108.991 + vertex -850.889 274.3 109.209 + vertex -851.943 274.049 111.166 + endloop + endfacet + facet normal 0.635303 -0.752643 0.172971 + outer loop + vertex -852.066 274.406 113.169 + vertex -851.943 274.049 111.166 + vertex -850.59 275.33 111.768 + endloop + endfacet + facet normal 0.698369 -0.688544 0.195419 + outer loop + vertex -849.997 275.176 109.106 + vertex -850.59 275.33 111.768 + vertex -850.889 274.3 109.209 + endloop + endfacet + facet normal 0.611901 -0.755947 0.23264 + outer loop + vertex -851.943 274.049 111.166 + vertex -850.889 274.3 109.209 + vertex -850.59 275.33 111.768 + endloop + endfacet + facet normal 0.390364 -0.900372 0.192213 + outer loop + vertex -852.978 273.023 108.755 + vertex -852.023 273.488 108.991 + vertex -852.923 273.485 110.807 + endloop + endfacet + facet normal 0.428649 -0.878437 0.211206 + outer loop + vertex -852.923 273.485 110.807 + vertex -852.023 273.488 108.991 + vertex -851.943 274.049 111.166 + endloop + endfacet + facet normal 0.262199 -0.944332 0.198715 + outer loop + vertex -853.554 272.782 108.37 + vertex -852.978 273.023 108.755 + vertex -853.597 273.19 110.366 + endloop + endfacet + facet normal 0.277206 -0.938921 0.20392 + outer loop + vertex -853.597 273.19 110.366 + vertex -852.978 273.023 108.755 + vertex -852.923 273.485 110.807 + endloop + endfacet + facet normal 0.290166 -0.93907 0.184257 + outer loop + vertex -853.597 273.19 110.366 + vertex -852.923 273.485 110.807 + vertex -853.494 273.596 112.273 + endloop + endfacet + facet normal 0.307464 -0.9323 0.190482 + outer loop + vertex -853.494 273.596 112.273 + vertex -852.923 273.485 110.807 + vertex -852.893 273.913 112.853 + endloop + endfacet + facet normal 0.441594 -0.879484 0.177488 + outer loop + vertex -852.923 273.485 110.807 + vertex -851.943 274.049 111.166 + vertex -852.893 273.913 112.853 + endloop + endfacet + facet normal 0.450948 -0.873539 0.183237 + outer loop + vertex -852.893 273.913 112.853 + vertex -851.943 274.049 111.166 + vertex -852.066 274.406 113.169 + endloop + endfacet + facet normal 0.458096 -0.873545 0.164521 + outer loop + vertex -852.893 273.913 112.853 + vertex -852.066 274.406 113.169 + vertex -852.838 274.313 114.824 + endloop + endfacet + facet normal 0.486818 -0.854974 0.178962 + outer loop + vertex -852.838 274.313 114.824 + vertex -852.066 274.406 113.169 + vertex -851.836 274.915 114.97 + endloop + endfacet + facet normal 0.318119 -0.931046 0.178756 + outer loop + vertex -853.494 273.596 112.273 + vertex -852.893 273.913 112.853 + vertex -853.511 273.981 114.304 + endloop + endfacet + facet normal 0.320813 -0.92991 0.17985 + outer loop + vertex -853.511 273.981 114.304 + vertex -852.893 273.913 112.853 + vertex -852.838 274.313 114.824 + endloop + endfacet + facet normal 0.33376 -0.928596 0.162216 + outer loop + vertex -853.511 273.981 114.304 + vertex -852.838 274.313 114.824 + vertex -853.388 274.366 116.257 + endloop + endfacet + facet normal 0.339685 -0.92606 0.164396 + outer loop + vertex -853.388 274.366 116.257 + vertex -852.838 274.313 114.824 + vertex -852.79 274.679 116.786 + endloop + endfacet + facet normal 0.492846 -0.857452 0.147913 + outer loop + vertex -852.838 274.313 114.824 + vertex -851.836 274.915 114.97 + vertex -852.79 274.679 116.786 + endloop + endfacet + facet normal 0.482049 -0.864675 0.141301 + outer loop + vertex -852.79 274.679 116.786 + vertex -851.836 274.915 114.97 + vertex -851.983 275.18 117.095 + endloop + endfacet + facet normal 0.661945 -0.736778 0.137793 + outer loop + vertex -851.983 275.18 117.095 + vertex -851.836 274.915 114.97 + vertex -850.572 276.222 115.888 + endloop + endfacet + facet normal 0.617164 -0.77436 0.139556 + outer loop + vertex -852.066 274.406 113.169 + vertex -850.59 275.33 111.768 + vertex -851.836 274.915 114.97 + endloop + endfacet + facet normal 0.652357 -0.741362 0.157519 + outer loop + vertex -850.59 275.33 111.768 + vertex -850.572 276.222 115.888 + vertex -851.836 274.915 114.97 + endloop + endfacet + facet normal 0.671722 -0.717744 0.183396 + outer loop + vertex -851.034 272.251 101.141 + vertex -850.09 273.194 101.375 + vertex -851.048 272.73 103.071 + endloop + endfacet + facet normal 0.686632 -0.699892 0.196694 + outer loop + vertex -851.048 272.73 103.071 + vertex -850.09 273.194 101.375 + vertex -849.921 273.872 103.196 + endloop + endfacet + facet normal 0.513337 -0.831864 0.21092 + outer loop + vertex -852.073 271.588 101.057 + vertex -851.034 272.251 101.141 + vertex -852.093 272.06 102.969 + endloop + endfacet + facet normal 0.51297 -0.832152 0.210678 + outer loop + vertex -852.093 272.06 102.969 + vertex -851.034 272.251 101.141 + vertex -851.048 272.73 103.071 + endloop + endfacet + facet normal 0.514855 -0.833528 0.200389 + outer loop + vertex -852.093 272.06 102.969 + vertex -851.048 272.73 103.071 + vertex -852.102 272.521 104.909 + endloop + endfacet + facet normal 0.512776 -0.835137 0.199014 + outer loop + vertex -852.102 272.521 104.909 + vertex -851.048 272.73 103.071 + vertex -851.044 273.202 105.04 + endloop + endfacet + facet normal 0.692231 -0.702151 0.166733 + outer loop + vertex -851.048 272.73 103.071 + vertex -849.921 273.872 103.196 + vertex -851.044 273.202 105.04 + endloop + endfacet + facet normal 0.677846 -0.719378 0.151725 + outer loop + vertex -851.044 273.202 105.04 + vertex -849.921 273.872 103.196 + vertex -850.083 274.167 105.319 + endloop + endfacet + facet normal 0.361272 -0.904229 0.227712 + outer loop + vertex -852.963 271.209 100.964 + vertex -852.073 271.588 101.057 + vertex -852.977 271.689 102.891 + endloop + endfacet + facet normal 0.36031 -0.904725 0.227265 + outer loop + vertex -852.977 271.689 102.891 + vertex -852.073 271.588 101.057 + vertex -852.093 272.06 102.969 + endloop + endfacet + facet normal 0.254042 -0.937856 0.236409 + outer loop + vertex -853.533 270.967 100.615 + vertex -852.963 271.209 100.964 + vertex -853.613 271.474 102.714 + endloop + endfacet + facet normal 0.251319 -0.938807 0.235542 + outer loop + vertex -853.613 271.474 102.714 + vertex -852.963 271.209 100.964 + vertex -852.977 271.689 102.891 + endloop + endfacet + facet normal 0.254969 -0.940529 0.22449 + outer loop + vertex -853.613 271.474 102.714 + vertex -852.977 271.689 102.891 + vertex -853.559 271.936 104.587 + endloop + endfacet + facet normal 0.253423 -0.941055 0.224036 + outer loop + vertex -853.559 271.936 104.587 + vertex -852.977 271.689 102.891 + vertex -852.995 272.143 104.818 + endloop + endfacet + facet normal 0.362004 -0.906578 0.216955 + outer loop + vertex -852.977 271.689 102.891 + vertex -852.093 272.06 102.969 + vertex -852.995 272.143 104.818 + endloop + endfacet + facet normal 0.362173 -0.906492 0.217034 + outer loop + vertex -852.995 272.143 104.818 + vertex -852.093 272.06 102.969 + vertex -852.102 272.521 104.909 + endloop + endfacet + facet normal 0.364089 -0.908328 0.205861 + outer loop + vertex -852.995 272.143 104.818 + vertex -852.102 272.521 104.909 + vertex -853.001 272.581 106.762 + endloop + endfacet + facet normal 0.366632 -0.907034 0.207053 + outer loop + vertex -853.001 272.581 106.762 + vertex -852.102 272.521 104.909 + vertex -852.083 272.985 106.907 + endloop + endfacet + facet normal 0.256449 -0.941808 0.217331 + outer loop + vertex -853.559 271.936 104.587 + vertex -852.995 272.143 104.818 + vertex -853.628 272.378 106.582 + endloop + endfacet + facet normal 0.245508 -0.945501 0.213901 + outer loop + vertex -853.628 272.378 106.582 + vertex -852.995 272.143 104.818 + vertex -853.001 272.581 106.762 + endloop + endfacet + facet normal 0.248772 -0.946823 0.204056 + outer loop + vertex -853.628 272.378 106.582 + vertex -853.001 272.581 106.762 + vertex -853.554 272.782 108.37 + endloop + endfacet + facet normal 0.256895 -0.944118 0.206511 + outer loop + vertex -853.554 272.782 108.37 + vertex -853.001 272.581 106.762 + vertex -852.978 273.023 108.755 + endloop + endfacet + facet normal 0.368752 -0.908349 0.197294 + outer loop + vertex -853.001 272.581 106.762 + vertex -852.083 272.985 106.907 + vertex -852.978 273.023 108.755 + endloop + endfacet + facet normal 0.386424 -0.8991 0.205659 + outer loop + vertex -852.978 273.023 108.755 + vertex -852.083 272.985 106.907 + vertex -852.023 273.488 108.991 + endloop + endfacet + facet normal 0.674949 -0.719685 0.162783 + outer loop + vertex -851.044 273.202 105.04 + vertex -850.083 274.167 105.319 + vertex -850.998 273.707 107.08 + endloop + endfacet + facet normal 0.697518 -0.693222 0.181418 + outer loop + vertex -850.998 273.707 107.08 + vertex -850.083 274.167 105.319 + vertex -849.879 274.861 107.188 + endloop + endfacet + facet normal 0.514697 -0.836231 0.189223 + outer loop + vertex -852.102 272.521 104.909 + vertex -851.044 273.202 105.04 + vertex -852.083 272.985 106.907 + endloop + endfacet + facet normal 0.521693 -0.830843 0.193745 + outer loop + vertex -852.083 272.985 106.907 + vertex -851.044 273.202 105.04 + vertex -850.998 273.707 107.08 + endloop + endfacet + facet normal 0.523507 -0.831593 0.185455 + outer loop + vertex -852.083 272.985 106.907 + vertex -850.998 273.707 107.08 + vertex -852.023 273.488 108.991 + endloop + endfacet + facet normal 0.545356 -0.814197 0.199173 + outer loop + vertex -852.023 273.488 108.991 + vertex -850.998 273.707 107.08 + vertex -850.889 274.3 109.209 + endloop + endfacet + facet normal 0.701532 -0.694909 0.157969 + outer loop + vertex -850.998 273.707 107.08 + vertex -849.879 274.861 107.188 + vertex -850.889 274.3 109.209 + endloop + endfacet + facet normal 0.700923 -0.695638 0.157463 + outer loop + vertex -850.889 274.3 109.209 + vertex -849.879 274.861 107.188 + vertex -849.997 275.176 109.106 + endloop + endfacet + facet normal 0.618522 -0.747412 0.242499 + outer loop + vertex -850.969 270.001 93.4621 + vertex -849.896 270.919 93.5524 + vertex -850.987 270.619 95.4109 + endloop + endfacet + facet normal 0.642361 -0.720662 0.260803 + outer loop + vertex -850.987 270.619 95.4109 + vertex -849.896 270.919 93.5524 + vertex -849.889 271.671 95.6146 + endloop + endfacet + facet normal 0.449547 -0.85451 0.26023 + outer loop + vertex -852.012 269.449 93.4512 + vertex -850.969 270.001 93.4621 + vertex -852.038 270.014 95.3486 + endloop + endfacet + facet normal 0.468352 -0.841021 0.270795 + outer loop + vertex -852.038 270.014 95.3486 + vertex -850.969 270.001 93.4621 + vertex -850.987 270.619 95.4109 + endloop + endfacet + facet normal 0.472719 -0.846085 0.246326 + outer loop + vertex -852.038 270.014 95.3486 + vertex -850.987 270.619 95.4109 + vertex -852.053 270.56 97.2552 + endloop + endfacet + facet normal 0.48535 -0.836635 0.253926 + outer loop + vertex -852.053 270.56 97.2552 + vertex -850.987 270.619 95.4109 + vertex -851.016 271.19 97.3479 + endloop + endfacet + facet normal 0.652582 -0.724068 0.2233 + outer loop + vertex -850.987 270.619 95.4109 + vertex -849.889 271.671 95.6146 + vertex -851.016 271.19 97.3479 + endloop + endfacet + facet normal 0.653562 -0.722884 0.224266 + outer loop + vertex -851.016 271.19 97.3479 + vertex -849.889 271.671 95.6146 + vertex -850.066 272.104 97.5271 + endloop + endfacet + facet normal 0.310674 -0.911513 0.269492 + outer loop + vertex -852.909 269.115 93.355 + vertex -852.012 269.449 93.4512 + vertex -852.934 269.66 95.2286 + endloop + endfacet + facet normal 0.320444 -0.906774 0.274001 + outer loop + vertex -852.934 269.66 95.2286 + vertex -852.012 269.449 93.4512 + vertex -852.038 270.014 95.3486 + endloop + endfacet + facet normal 0.232076 -0.932404 0.277061 + outer loop + vertex -853.482 268.866 92.9974 + vertex -852.909 269.115 93.355 + vertex -853.587 269.404 94.8951 + endloop + endfacet + facet normal 0.226519 -0.934384 0.274983 + outer loop + vertex -853.587 269.404 94.8951 + vertex -852.909 269.115 93.355 + vertex -852.934 269.66 95.2286 + endloop + endfacet + facet normal 0.232903 -0.936047 0.263764 + outer loop + vertex -853.587 269.404 94.8951 + vertex -852.934 269.66 95.2286 + vertex -853.528 269.924 96.6892 + endloop + endfacet + facet normal 0.233365 -0.935888 0.263923 + outer loop + vertex -853.528 269.924 96.6892 + vertex -852.934 269.66 95.2286 + vertex -852.945 270.191 97.1206 + endloop + endfacet + facet normal 0.324095 -0.910365 0.257289 + outer loop + vertex -852.934 269.66 95.2286 + vertex -852.038 270.014 95.3486 + vertex -852.945 270.191 97.1206 + endloop + endfacet + facet normal 0.33464 -0.905144 0.262167 + outer loop + vertex -852.945 270.191 97.1206 + vertex -852.038 270.014 95.3486 + vertex -852.053 270.56 97.2552 + endloop + endfacet + facet normal 0.338107 -0.908065 0.247185 + outer loop + vertex -852.945 270.191 97.1206 + vertex -852.053 270.56 97.2552 + vertex -852.951 270.71 99.0331 + endloop + endfacet + facet normal 0.346742 -0.903703 0.251181 + outer loop + vertex -852.951 270.71 99.0331 + vertex -852.053 270.56 97.2552 + vertex -852.063 271.085 99.157 + endloop + endfacet + facet normal 0.2408 -0.936655 0.254349 + outer loop + vertex -853.528 269.924 96.6892 + vertex -852.945 270.191 97.1206 + vertex -853.607 270.452 98.7066 + endloop + endfacet + facet normal 0.241459 -0.936421 0.254586 + outer loop + vertex -853.607 270.452 98.7066 + vertex -852.945 270.191 97.1206 + vertex -852.951 270.71 99.0331 + endloop + endfacet + facet normal 0.247548 -0.937796 0.243432 + outer loop + vertex -853.607 270.452 98.7066 + vertex -852.951 270.71 99.0331 + vertex -853.533 270.967 100.615 + endloop + endfacet + facet normal 0.249174 -0.937233 0.243939 + outer loop + vertex -853.533 270.967 100.615 + vertex -852.951 270.71 99.0331 + vertex -852.963 271.209 100.964 + endloop + endfacet + facet normal 0.349921 -0.90641 0.236592 + outer loop + vertex -852.951 270.71 99.0331 + vertex -852.063 271.085 99.157 + vertex -852.963 271.209 100.964 + endloop + endfacet + facet normal 0.358875 -0.901807 0.240736 + outer loop + vertex -852.963 271.209 100.964 + vertex -852.063 271.085 99.157 + vertex -852.073 271.588 101.057 + endloop + endfacet + facet normal 0.656803 -0.723768 0.21159 + outer loop + vertex -851.016 271.19 97.3479 + vertex -850.066 272.104 97.5271 + vertex -851.022 271.736 99.2335 + endloop + endfacet + facet normal 0.677613 -0.698986 0.228601 + outer loop + vertex -851.022 271.736 99.2335 + vertex -850.066 272.104 97.5271 + vertex -849.895 272.846 99.2869 + endloop + endfacet + facet normal 0.489193 -0.840088 0.234399 + outer loop + vertex -852.053 270.56 97.2552 + vertex -851.016 271.19 97.3479 + vertex -852.063 271.085 99.157 + endloop + endfacet + facet normal 0.501444 -0.830646 0.242034 + outer loop + vertex -852.063 271.085 99.157 + vertex -851.016 271.19 97.3479 + vertex -851.022 271.736 99.2335 + endloop + endfacet + facet normal 0.504792 -0.833819 0.223454 + outer loop + vertex -852.063 271.085 99.157 + vertex -851.022 271.736 99.2335 + vertex -852.073 271.588 101.057 + endloop + endfacet + facet normal 0.510445 -0.829389 0.227067 + outer loop + vertex -852.073 271.588 101.057 + vertex -851.022 271.736 99.2335 + vertex -851.034 272.251 101.141 + endloop + endfacet + facet normal 0.683678 -0.703486 0.194146 + outer loop + vertex -851.022 271.736 99.2335 + vertex -849.895 272.846 99.2869 + vertex -851.034 272.251 101.141 + endloop + endfacet + facet normal 0.671985 -0.717756 0.182382 + outer loop + vertex -851.034 272.251 101.141 + vertex -849.895 272.846 99.2869 + vertex -850.09 273.194 101.375 + endloop + endfacet + facet normal 0.580544 -0.759705 0.292944 + outer loop + vertex -850.669 267.557 85.9903 + vertex -849.615 268.369 86.0075 + vertex -850.766 268.192 87.8291 + endloop + endfacet + facet normal 0.583991 -0.756075 0.295475 + outer loop + vertex -850.766 268.192 87.8291 + vertex -849.615 268.369 86.0075 + vertex -849.724 269 87.8352 + endloop + endfacet + facet normal 0.421013 -0.850742 0.31462 + outer loop + vertex -851.736 267.029 85.9885 + vertex -850.669 267.557 85.9903 + vertex -851.817 267.673 87.8387 + endloop + endfacet + facet normal 0.422753 -0.849507 0.315623 + outer loop + vertex -851.817 267.673 87.8387 + vertex -850.669 267.557 85.9903 + vertex -850.766 268.192 87.8291 + endloop + endfacet + facet normal 0.424776 -0.853871 0.300782 + outer loop + vertex -851.817 267.673 87.8387 + vertex -850.766 268.192 87.8291 + vertex -851.895 268.29 89.6997 + endloop + endfacet + facet normal 0.427536 -0.851938 0.302348 + outer loop + vertex -851.895 268.29 89.6997 + vertex -850.766 268.192 87.8291 + vertex -850.855 268.805 89.68 + endloop + endfacet + facet normal 0.58699 -0.759825 0.279479 + outer loop + vertex -850.766 268.192 87.8291 + vertex -849.724 269 87.8352 + vertex -850.855 268.805 89.68 + endloop + endfacet + facet normal 0.591002 -0.75563 0.282382 + outer loop + vertex -850.855 268.805 89.68 + vertex -849.724 269 87.8352 + vertex -849.817 269.619 89.6873 + endloop + endfacet + facet normal 0.288458 -0.901636 0.32225 + outer loop + vertex -852.671 266.693 85.8861 + vertex -851.736 267.029 85.9885 + vertex -852.743 267.339 87.758 + endloop + endfacet + facet normal 0.295455 -0.898153 0.325619 + outer loop + vertex -852.743 267.339 87.758 + vertex -851.736 267.029 85.9885 + vertex -851.817 267.673 87.8387 + endloop + endfacet + facet normal 0.211415 -0.921854 0.324789 + outer loop + vertex -853.289 266.419 85.5093 + vertex -852.671 266.693 85.8861 + vertex -853.435 267.091 87.5124 + endloop + endfacet + facet normal 0.21458 -0.920697 0.325993 + outer loop + vertex -853.435 267.091 87.5124 + vertex -852.671 266.693 85.8861 + vertex -852.743 267.339 87.758 + endloop + endfacet + facet normal 0.220234 -0.9238 0.313193 + outer loop + vertex -853.435 267.091 87.5124 + vertex -852.743 267.339 87.758 + vertex -853.411 267.717 89.3429 + endloop + endfacet + facet normal 0.223438 -0.922664 0.314272 + outer loop + vertex -853.411 267.717 89.3429 + vertex -852.743 267.339 87.758 + vertex -852.807 267.961 89.6287 + endloop + endfacet + facet normal 0.298415 -0.902628 0.31018 + outer loop + vertex -852.743 267.339 87.758 + vertex -851.817 267.673 87.8387 + vertex -852.807 267.961 89.6287 + endloop + endfacet + facet normal 0.300867 -0.901413 0.31134 + outer loop + vertex -852.807 267.961 89.6287 + vertex -851.817 267.673 87.8387 + vertex -851.895 268.29 89.6997 + endloop + endfacet + facet normal 0.303515 -0.905538 0.296446 + outer loop + vertex -852.807 267.961 89.6287 + vertex -851.895 268.29 89.6997 + vertex -852.863 268.552 91.4913 + endloop + endfacet + facet normal 0.303758 -0.905419 0.29656 + outer loop + vertex -852.863 268.552 91.4913 + vertex -851.895 268.29 89.6997 + vertex -851.96 268.88 91.5669 + endloop + endfacet + facet normal 0.229998 -0.925012 0.302414 + outer loop + vertex -853.411 267.717 89.3429 + vertex -852.807 267.961 89.6287 + vertex -853.526 268.318 91.2684 + endloop + endfacet + facet normal 0.225486 -0.92665 0.300792 + outer loop + vertex -853.526 268.318 91.2684 + vertex -852.807 267.961 89.6287 + vertex -852.863 268.552 91.4913 + endloop + endfacet + facet normal 0.230424 -0.929241 0.288819 + outer loop + vertex -853.526 268.318 91.2684 + vertex -852.863 268.552 91.4913 + vertex -853.482 268.866 92.9974 + endloop + endfacet + facet normal 0.225252 -0.931049 0.287069 + outer loop + vertex -853.482 268.866 92.9974 + vertex -852.863 268.552 91.4913 + vertex -852.909 269.115 93.355 + endloop + endfacet + facet normal 0.306273 -0.909086 0.282417 + outer loop + vertex -852.863 268.552 91.4913 + vertex -851.96 268.88 91.5669 + vertex -852.909 269.115 93.355 + endloop + endfacet + facet normal 0.307988 -0.908257 0.283218 + outer loop + vertex -852.909 269.115 93.355 + vertex -851.96 268.88 91.5669 + vertex -852.012 269.449 93.4512 + endloop + endfacet + facet normal 0.594068 -0.759385 0.265364 + outer loop + vertex -850.855 268.805 89.68 + vertex -849.817 269.619 89.6873 + vertex -850.925 269.404 91.5531 + endloop + endfacet + facet normal 0.597322 -0.75601 0.267684 + outer loop + vertex -850.925 269.404 91.5531 + vertex -849.817 269.619 89.6873 + vertex -849.879 270.242 91.5835 + endloop + endfacet + facet normal 0.42958 -0.856708 0.285503 + outer loop + vertex -851.895 268.29 89.6997 + vertex -850.855 268.805 89.68 + vertex -851.96 268.88 91.5669 + endloop + endfacet + facet normal 0.436081 -0.852195 0.289132 + outer loop + vertex -851.96 268.88 91.5669 + vertex -850.855 268.805 89.68 + vertex -850.925 269.404 91.5531 + endloop + endfacet + facet normal 0.438247 -0.856933 0.271303 + outer loop + vertex -851.96 268.88 91.5669 + vertex -850.925 269.404 91.5531 + vertex -852.012 269.449 93.4512 + endloop + endfacet + facet normal 0.447315 -0.850613 0.276345 + outer loop + vertex -852.012 269.449 93.4512 + vertex -850.925 269.404 91.5531 + vertex -850.969 270.001 93.4621 + endloop + endfacet + facet normal 0.600365 -0.759216 0.251302 + outer loop + vertex -850.925 269.404 91.5531 + vertex -849.879 270.242 91.5835 + vertex -850.969 270.001 93.4621 + endloop + endfacet + facet normal 0.614406 -0.744451 0.261339 + outer loop + vertex -850.969 270.001 93.4621 + vertex -849.879 270.242 91.5835 + vertex -849.896 270.919 93.5524 + endloop + endfacet + facet normal 0.544056 -0.759408 0.356794 + outer loop + vertex -850.173 264.727 78.6905 + vertex -849.067 265.544 78.7426 + vertex -850.323 265.477 80.5151 + endloop + endfacet + facet normal 0.54894 -0.754148 0.360453 + outer loop + vertex -850.323 265.477 80.5151 + vertex -849.067 265.544 78.7426 + vertex -849.228 266.293 80.5555 + endloop + endfacet + facet normal 0.379787 -0.845815 0.374646 + outer loop + vertex -851.296 264.211 78.6642 + vertex -850.173 264.727 78.6905 + vertex -851.432 264.96 80.493 + endloop + endfacet + facet normal 0.384861 -0.842147 0.377718 + outer loop + vertex -851.432 264.96 80.493 + vertex -850.173 264.727 78.6905 + vertex -850.323 265.477 80.5151 + endloop + endfacet + facet normal 0.388625 -0.849349 0.35718 + outer loop + vertex -851.432 264.96 80.493 + vertex -850.323 265.477 80.5151 + vertex -851.547 265.676 82.3197 + endloop + endfacet + facet normal 0.396214 -0.843899 0.36173 + outer loop + vertex -851.547 265.676 82.3197 + vertex -850.323 265.477 80.5151 + vertex -850.452 266.197 82.3367 + endloop + endfacet + facet normal 0.554053 -0.759982 0.339783 + outer loop + vertex -850.323 265.477 80.5151 + vertex -849.228 266.293 80.5555 + vertex -850.452 266.197 82.3367 + endloop + endfacet + facet normal 0.559429 -0.754221 0.343787 + outer loop + vertex -850.452 266.197 82.3367 + vertex -849.228 266.293 80.5555 + vertex -849.371 267.014 82.3695 + endloop + endfacet + facet normal 0.245548 -0.892391 0.378609 + outer loop + vertex -852.28 263.904 78.5783 + vertex -851.296 264.211 78.6642 + vertex -852.409 264.639 80.3943 + endloop + endfacet + facet normal 0.25341 -0.888444 0.382688 + outer loop + vertex -852.409 264.639 80.3943 + vertex -851.296 264.211 78.6642 + vertex -851.432 264.96 80.493 + endloop + endfacet + facet normal 0.166577 -0.910314 0.378921 + outer loop + vertex -852.924 263.677 78.3169 + vertex -852.28 263.904 78.5783 + vertex -853.123 264.421 80.1907 + endloop + endfacet + facet normal 0.169357 -0.909326 0.380058 + outer loop + vertex -853.123 264.421 80.1907 + vertex -852.28 263.904 78.5783 + vertex -852.409 264.639 80.3943 + endloop + endfacet + facet normal 0.175577 -0.914703 0.363992 + outer loop + vertex -853.123 264.421 80.1907 + vertex -852.409 264.639 80.3943 + vertex -853.132 265.087 81.8694 + endloop + endfacet + facet normal 0.179314 -0.913404 0.36543 + outer loop + vertex -853.132 265.087 81.8694 + vertex -852.409 264.639 80.3943 + vertex -852.512 265.345 82.209 + endloop + endfacet + facet normal 0.257723 -0.895475 0.362909 + outer loop + vertex -852.409 264.639 80.3943 + vertex -851.432 264.96 80.493 + vertex -852.512 265.345 82.209 + endloop + endfacet + facet normal 0.264068 -0.892288 0.366184 + outer loop + vertex -852.512 265.345 82.209 + vertex -851.432 264.96 80.493 + vertex -851.547 265.676 82.3197 + endloop + endfacet + facet normal 0.268063 -0.898084 0.348693 + outer loop + vertex -852.512 265.345 82.209 + vertex -851.547 265.676 82.3197 + vertex -852.599 266.029 84.0376 + endloop + endfacet + facet normal 0.274893 -0.894656 0.352172 + outer loop + vertex -852.599 266.029 84.0376 + vertex -851.547 265.676 82.3197 + vertex -851.645 266.365 84.1481 + endloop + endfacet + facet normal 0.188761 -0.917148 0.351012 + outer loop + vertex -853.132 265.087 81.8694 + vertex -852.512 265.345 82.209 + vertex -853.295 265.771 83.7449 + endloop + endfacet + facet normal 0.190797 -0.916407 0.351844 + outer loop + vertex -853.295 265.771 83.7449 + vertex -852.512 265.345 82.209 + vertex -852.599 266.029 84.0376 + endloop + endfacet + facet normal 0.198539 -0.920363 0.33692 + outer loop + vertex -853.295 265.771 83.7449 + vertex -852.599 266.029 84.0376 + vertex -853.289 266.419 85.5093 + endloop + endfacet + facet normal 0.202015 -0.919128 0.338221 + outer loop + vertex -853.289 266.419 85.5093 + vertex -852.599 266.029 84.0376 + vertex -852.671 266.693 85.8861 + endloop + endfacet + facet normal 0.278912 -0.900213 0.334403 + outer loop + vertex -852.599 266.029 84.0376 + vertex -851.645 266.365 84.1481 + vertex -852.671 266.693 85.8861 + endloop + endfacet + facet normal 0.285156 -0.897094 0.337502 + outer loop + vertex -852.671 266.693 85.8861 + vertex -851.645 266.365 84.1481 + vertex -851.736 267.029 85.9885 + endloop + endfacet + facet normal 0.564185 -0.759694 0.323358 + outer loop + vertex -850.452 266.197 82.3367 + vertex -849.371 267.014 82.3695 + vertex -850.566 266.889 84.1594 + endloop + endfacet + facet normal 0.568226 -0.755388 0.326357 + outer loop + vertex -850.566 266.889 84.1594 + vertex -849.371 267.014 82.3695 + vertex -849.498 267.703 84.1856 + endloop + endfacet + facet normal 0.399628 -0.850433 0.342142 + outer loop + vertex -851.547 265.676 82.3197 + vertex -850.452 266.197 82.3367 + vertex -851.645 266.365 84.1481 + endloop + endfacet + facet normal 0.406352 -0.845623 0.346122 + outer loop + vertex -851.645 266.365 84.1481 + vertex -850.452 266.197 82.3367 + vertex -850.566 266.889 84.1594 + endloop + endfacet + facet normal 0.40945 -0.851605 0.327291 + outer loop + vertex -851.645 266.365 84.1481 + vertex -850.566 266.889 84.1594 + vertex -851.736 267.029 85.9885 + endloop + endfacet + facet normal 0.418282 -0.845288 0.332458 + outer loop + vertex -851.736 267.029 85.9885 + vertex -850.566 266.889 84.1594 + vertex -850.669 267.557 85.9903 + endloop + endfacet + facet normal 0.571844 -0.7596 0.309843 + outer loop + vertex -850.566 266.889 84.1594 + vertex -849.498 267.703 84.1856 + vertex -850.669 267.557 85.9903 + endloop + endfacet + facet normal 0.576405 -0.754763 0.313193 + outer loop + vertex -850.669 267.557 85.9903 + vertex -849.498 267.703 84.1856 + vertex -849.615 268.369 86.0075 + endloop + endfacet + facet normal 0.50742 -0.745895 0.431469 + outer loop + vertex -849.373 261.438 71.5065 + vertex -848.221 262.273 71.5951 + vertex -849.604 262.3 73.2693 + endloop + endfacet + facet normal 0.509067 -0.744001 0.432798 + outer loop + vertex -849.604 262.3 73.2693 + vertex -848.221 262.273 71.5951 + vertex -848.463 263.127 73.3494 + endloop + endfacet + facet normal 0.33506 -0.830972 0.444094 + outer loop + vertex -850.557 260.94 71.4688 + vertex -849.373 261.438 71.5065 + vertex -850.771 261.8 73.239 + endloop + endfacet + facet normal 0.342368 -0.82543 0.448831 + outer loop + vertex -850.771 261.8 73.239 + vertex -849.373 261.438 71.5065 + vertex -849.604 262.3 73.2693 + endloop + endfacet + facet normal 0.34723 -0.835391 0.426091 + outer loop + vertex -850.771 261.8 73.239 + vertex -849.604 262.3 73.2693 + vertex -850.964 262.633 75.0294 + endloop + endfacet + facet normal 0.35293 -0.831147 0.429692 + outer loop + vertex -850.964 262.633 75.0294 + vertex -849.604 262.3 73.2693 + vertex -849.814 263.136 75.0577 + endloop + endfacet + facet normal 0.515884 -0.751341 0.411523 + outer loop + vertex -849.604 262.3 73.2693 + vertex -848.463 263.127 73.3494 + vertex -849.814 263.136 75.0577 + endloop + endfacet + facet normal 0.520422 -0.746235 0.415084 + outer loop + vertex -849.814 263.136 75.0577 + vertex -848.463 263.127 73.3494 + vertex -848.686 263.964 75.1327 + endloop + endfacet + facet normal 0.200022 -0.873499 0.443837 + outer loop + vertex -851.613 260.64 71.3547 + vertex -850.557 260.94 71.4688 + vertex -851.806 261.503 73.1401 + endloop + endfacet + facet normal 0.206481 -0.870108 0.447524 + outer loop + vertex -851.806 261.503 73.1401 + vertex -850.557 260.94 71.4688 + vertex -850.771 261.8 73.239 + endloop + endfacet + facet normal 0.117891 -0.889248 0.441973 + outer loop + vertex -852.29 260.355 70.9601 + vertex -851.613 260.64 71.3547 + vertex -852.571 261.254 72.8447 + endloop + endfacet + facet normal 0.118983 -0.888837 0.442506 + outer loop + vertex -852.571 261.254 72.8447 + vertex -851.613 260.64 71.3547 + vertex -851.806 261.503 73.1401 + endloop + endfacet + facet normal 0.128148 -0.896113 0.424924 + outer loop + vertex -852.571 261.254 72.8447 + vertex -851.806 261.503 73.1401 + vertex -852.644 262.086 74.6206 + endloop + endfacet + facet normal 0.130183 -0.895404 0.425798 + outer loop + vertex -852.644 262.086 74.6206 + vertex -851.806 261.503 73.1401 + vertex -851.98 262.337 74.946 + endloop + endfacet + facet normal 0.21122 -0.879574 0.426305 + outer loop + vertex -851.806 261.503 73.1401 + vertex -850.771 261.8 73.239 + vertex -851.98 262.337 74.946 + endloop + endfacet + facet normal 0.219666 -0.875243 0.430926 + outer loop + vertex -851.98 262.337 74.946 + vertex -850.771 261.8 73.239 + vertex -850.964 262.633 75.0294 + endloop + endfacet + facet normal 0.224097 -0.884395 0.409421 + outer loop + vertex -851.98 262.337 74.946 + vertex -850.964 262.633 75.0294 + vertex -852.139 263.137 76.7622 + endloop + endfacet + facet normal 0.231581 -0.880609 0.413398 + outer loop + vertex -852.139 263.137 76.7622 + vertex -850.964 262.633 75.0294 + vertex -851.138 263.437 76.8396 + endloop + endfacet + facet normal 0.141708 -0.902147 0.407492 + outer loop + vertex -852.644 262.086 74.6206 + vertex -851.98 262.337 74.946 + vertex -852.879 262.927 76.5649 + endloop + endfacet + facet normal 0.146831 -0.900336 0.409677 + outer loop + vertex -852.879 262.927 76.5649 + vertex -851.98 262.337 74.946 + vertex -852.139 263.137 76.7622 + endloop + endfacet + facet normal 0.153307 -0.906923 0.392413 + outer loop + vertex -852.879 262.927 76.5649 + vertex -852.139 263.137 76.7622 + vertex -852.924 263.677 78.3169 + endloop + endfacet + facet normal 0.158482 -0.905163 0.394415 + outer loop + vertex -852.924 263.677 78.3169 + vertex -852.139 263.137 76.7622 + vertex -852.28 263.904 78.5783 + endloop + endfacet + facet normal 0.235543 -0.888679 0.393406 + outer loop + vertex -852.139 263.137 76.7622 + vertex -851.138 263.437 76.8396 + vertex -852.28 263.904 78.5783 + endloop + endfacet + facet normal 0.241827 -0.885528 0.396687 + outer loop + vertex -852.28 263.904 78.5783 + vertex -851.138 263.437 76.8396 + vertex -851.296 264.211 78.6642 + endloop + endfacet + facet normal 0.527196 -0.75345 0.39291 + outer loop + vertex -849.814 263.136 75.0577 + vertex -848.686 263.964 75.1327 + vertex -850.002 263.948 76.8679 + endloop + endfacet + facet normal 0.530699 -0.749571 0.395604 + outer loop + vertex -850.002 263.948 76.8679 + vertex -848.686 263.964 75.1327 + vertex -848.887 264.773 76.9342 + endloop + endfacet + facet normal 0.357465 -0.840279 0.407614 + outer loop + vertex -850.964 262.633 75.0294 + vertex -849.814 263.136 75.0577 + vertex -851.138 263.437 76.8396 + endloop + endfacet + facet normal 0.365245 -0.834564 0.41243 + outer loop + vertex -851.138 263.437 76.8396 + vertex -849.814 263.136 75.0577 + vertex -850.002 263.948 76.8679 + endloop + endfacet + facet normal 0.369765 -0.843362 0.38989 + outer loop + vertex -851.138 263.437 76.8396 + vertex -850.002 263.948 76.8679 + vertex -851.296 264.211 78.6642 + endloop + endfacet + facet normal 0.376093 -0.838748 0.393772 + outer loop + vertex -851.296 264.211 78.6642 + vertex -850.002 263.948 76.8679 + vertex -850.173 264.727 78.6905 + endloop + endfacet + facet normal 0.537011 -0.75634 0.37359 + outer loop + vertex -850.002 263.948 76.8679 + vertex -848.887 264.773 76.9342 + vertex -850.173 264.727 78.6905 + endloop + endfacet + facet normal 0.539178 -0.753979 0.375238 + outer loop + vertex -850.173 264.727 78.6905 + vertex -848.887 264.773 76.9342 + vertex -849.067 265.544 78.7426 + endloop + endfacet + facet normal 0.457256 -0.725432 0.514456 + outer loop + vertex -848.207 257.698 64.6761 + vertex -847.004 258.58 64.8507 + vertex -848.538 258.675 66.3471 + endloop + endfacet + facet normal 0.460238 -0.721539 0.517265 + outer loop + vertex -848.538 258.675 66.3471 + vertex -847.004 258.58 64.8507 + vertex -847.346 259.539 66.492 + endloop + endfacet + facet normal 0.288212 -0.80282 0.521932 + outer loop + vertex -849.464 257.171 64.5595 + vertex -848.207 257.698 64.6761 + vertex -849.78 258.16 66.255 + endloop + endfacet + facet normal 0.292303 -0.79934 0.52499 + outer loop + vertex -849.78 258.16 66.255 + vertex -848.207 257.698 64.6761 + vertex -848.538 258.675 66.3471 + endloop + endfacet + facet normal 0.298962 -0.811354 0.502321 + outer loop + vertex -849.78 258.16 66.255 + vertex -848.538 258.675 66.3471 + vertex -850.061 259.121 67.975 + endloop + endfacet + facet normal 0.306577 -0.805117 0.507737 + outer loop + vertex -850.061 259.121 67.975 + vertex -848.538 258.675 66.3471 + vertex -848.841 259.632 68.0477 + endloop + endfacet + facet normal 0.46975 -0.730935 0.495044 + outer loop + vertex -848.538 258.675 66.3471 + vertex -847.346 259.539 66.492 + vertex -848.841 259.632 68.0477 + endloop + endfacet + facet normal 0.471807 -0.728369 0.496867 + outer loop + vertex -848.841 259.632 68.0477 + vertex -847.346 259.539 66.492 + vertex -847.662 260.475 68.1651 + endloop + endfacet + facet normal 0.152599 -0.843372 0.515206 + outer loop + vertex -850.604 256.887 64.4315 + vertex -849.464 257.171 64.5595 + vertex -850.897 257.87 66.1274 + endloop + endfacet + facet normal 0.15891 -0.839671 0.519327 + outer loop + vertex -850.897 257.87 66.1274 + vertex -849.464 257.171 64.5595 + vertex -849.78 258.16 66.255 + endloop + endfacet + facet normal 0.0714768 -0.858257 0.508218 + outer loop + vertex -851.348 256.671 64.1713 + vertex -850.604 256.887 64.4315 + vertex -851.718 257.677 65.9233 + endloop + endfacet + facet normal 0.07417 -0.857176 0.509655 + outer loop + vertex -851.718 257.677 65.9233 + vertex -850.604 256.887 64.4315 + vertex -850.897 257.87 66.1274 + endloop + endfacet + facet normal 0.0809436 -0.867004 0.491683 + outer loop + vertex -851.718 257.677 65.9233 + vertex -850.897 257.87 66.1274 + vertex -851.867 258.566 67.5156 + endloop + endfacet + facet normal 0.0830682 -0.866191 0.49276 + outer loop + vertex -851.867 258.566 67.5156 + vertex -850.897 257.87 66.1274 + vertex -851.16 258.821 67.8445 + endloop + endfacet + facet normal 0.164591 -0.851839 0.497273 + outer loop + vertex -850.897 257.87 66.1274 + vertex -849.78 258.16 66.255 + vertex -851.16 258.821 67.8445 + endloop + endfacet + facet normal 0.171852 -0.847707 0.501857 + outer loop + vertex -851.16 258.821 67.8445 + vertex -849.78 258.16 66.255 + vertex -850.061 259.121 67.975 + endloop + endfacet + facet normal 0.177604 -0.859195 0.479834 + outer loop + vertex -851.16 258.821 67.8445 + vertex -850.061 259.121 67.975 + vertex -851.399 259.745 69.588 + endloop + endfacet + facet normal 0.182738 -0.856347 0.482988 + outer loop + vertex -851.399 259.745 69.588 + vertex -850.061 259.121 67.975 + vertex -850.32 260.047 69.7144 + endloop + endfacet + facet normal 0.0938233 -0.874421 0.476009 + outer loop + vertex -851.867 258.566 67.5156 + vertex -851.16 258.821 67.8445 + vertex -852.184 259.494 69.2828 + endloop + endfacet + facet normal 0.0945251 -0.874144 0.476379 + outer loop + vertex -852.184 259.494 69.2828 + vertex -851.16 258.821 67.8445 + vertex -851.399 259.745 69.588 + endloop + endfacet + facet normal 0.103867 -0.882307 0.459071 + outer loop + vertex -852.184 259.494 69.2828 + vertex -851.399 259.745 69.588 + vertex -852.29 260.355 70.9601 + endloop + endfacet + facet normal 0.10464 -0.88202 0.459446 + outer loop + vertex -852.29 260.355 70.9601 + vertex -851.399 259.745 69.588 + vertex -851.613 260.64 71.3547 + endloop + endfacet + facet normal 0.188124 -0.866768 0.461868 + outer loop + vertex -851.399 259.745 69.588 + vertex -850.32 260.047 69.7144 + vertex -851.613 260.64 71.3547 + endloop + endfacet + facet normal 0.19473 -0.863206 0.465786 + outer loop + vertex -851.613 260.64 71.3547 + vertex -850.32 260.047 69.7144 + vertex -850.557 260.94 71.4688 + endloop + endfacet + facet normal 0.481183 -0.738134 0.472886 + outer loop + vertex -848.841 259.632 68.0477 + vertex -847.662 260.475 68.1651 + vertex -849.119 260.552 69.7677 + endloop + endfacet + facet normal 0.485779 -0.732588 0.476795 + outer loop + vertex -849.119 260.552 69.7677 + vertex -847.662 260.475 68.1651 + vertex -847.954 261.39 69.8673 + endloop + endfacet + facet normal 0.313529 -0.818085 0.482116 + outer loop + vertex -850.061 259.121 67.975 + vertex -848.841 259.632 68.0477 + vertex -850.32 260.047 69.7144 + endloop + endfacet + facet normal 0.320309 -0.812674 0.486789 + outer loop + vertex -850.32 260.047 69.7144 + vertex -848.841 259.632 68.0477 + vertex -849.119 260.552 69.7677 + endloop + endfacet + facet normal 0.326081 -0.823935 0.463467 + outer loop + vertex -850.32 260.047 69.7144 + vertex -849.119 260.552 69.7677 + vertex -850.557 260.94 71.4688 + endloop + endfacet + facet normal 0.330091 -0.820821 0.466147 + outer loop + vertex -850.557 260.94 71.4688 + vertex -849.119 260.552 69.7677 + vertex -849.373 261.438 71.5065 + endloop + endfacet + facet normal 0.4953 -0.742716 0.450612 + outer loop + vertex -849.119 260.552 69.7677 + vertex -847.954 261.39 69.8673 + vertex -849.373 261.438 71.5065 + endloop + endfacet + facet normal 0.499648 -0.737584 0.454227 + outer loop + vertex -849.373 261.438 71.5065 + vertex -847.954 261.39 69.8673 + vertex -848.221 262.273 71.5951 + endloop + endfacet + facet normal 0.390337 -0.692746 0.606416 + outer loop + vertex -846.617 253.551 58.3991 + vertex -845.354 254.503 58.6736 + vertex -847.057 254.614 59.8968 + endloop + endfacet + facet normal 0.394381 -0.686008 0.611438 + outer loop + vertex -847.057 254.614 59.8968 + vertex -845.354 254.503 58.6736 + vertex -845.812 255.559 60.1538 + endloop + endfacet + facet normal 0.229367 -0.763087 0.604226 + outer loop + vertex -847.959 252.978 58.1846 + vertex -846.617 253.551 58.3991 + vertex -848.379 254.058 59.7085 + endloop + endfacet + facet normal 0.232847 -0.759432 0.607491 + outer loop + vertex -848.379 254.058 59.7085 + vertex -846.617 253.551 58.3991 + vertex -847.057 254.614 59.8968 + endloop + endfacet + facet normal 0.243083 -0.775404 0.582803 + outer loop + vertex -848.379 254.058 59.7085 + vertex -847.057 254.614 59.8968 + vertex -848.766 255.119 61.2821 + endloop + endfacet + facet normal 0.249111 -0.769485 0.588078 + outer loop + vertex -848.766 255.119 61.2821 + vertex -847.057 254.614 59.8968 + vertex -847.466 255.665 61.4459 + endloop + endfacet + facet normal 0.410894 -0.700249 0.583796 + outer loop + vertex -847.057 254.614 59.8968 + vertex -845.812 255.559 60.1538 + vertex -847.466 255.665 61.4459 + endloop + endfacet + facet normal 0.413159 -0.696728 0.586404 + outer loop + vertex -847.466 255.665 61.4459 + vertex -845.812 255.559 60.1538 + vertex -846.239 256.588 61.6775 + endloop + endfacet + facet normal 0.101853 -0.799583 0.591856 + outer loop + vertex -849.172 252.644 57.942 + vertex -847.959 252.978 58.1846 + vertex -849.58 253.748 59.5039 + endloop + endfacet + facet normal 0.104857 -0.7974 0.594271 + outer loop + vertex -849.58 253.748 59.5039 + vertex -847.959 252.978 58.1846 + vertex -848.379 254.058 59.7085 + endloop + endfacet + facet normal 0.0332071 -0.811178 0.583856 + outer loop + vertex -849.907 252.305 57.5136 + vertex -849.172 252.644 57.942 + vertex -850.437 253.495 59.1965 + endloop + endfacet + facet normal 0.0309317 -0.812346 0.582354 + outer loop + vertex -850.437 253.495 59.1965 + vertex -849.172 252.644 57.942 + vertex -849.58 253.748 59.5039 + endloop + endfacet + facet normal 0.0410543 -0.824605 0.564217 + outer loop + vertex -850.437 253.495 59.1965 + vertex -849.58 253.748 59.5039 + vertex -850.699 254.566 60.7805 + endloop + endfacet + facet normal 0.0377494 -0.826091 0.56227 + outer loop + vertex -850.699 254.566 60.7805 + vertex -849.58 253.748 59.5039 + vertex -849.945 254.826 61.112 + endloop + endfacet + facet normal 0.112967 -0.813299 0.570774 + outer loop + vertex -849.58 253.748 59.5039 + vertex -848.379 254.058 59.7085 + vertex -849.945 254.826 61.112 + endloop + endfacet + facet normal 0.118777 -0.809398 0.575123 + outer loop + vertex -849.945 254.826 61.112 + vertex -848.379 254.058 59.7085 + vertex -848.766 255.119 61.2821 + endloop + endfacet + facet normal 0.126139 -0.824947 0.550955 + outer loop + vertex -849.945 254.826 61.112 + vertex -848.766 255.119 61.2821 + vertex -850.286 255.873 62.7582 + endloop + endfacet + facet normal 0.133649 -0.820192 0.556258 + outer loop + vertex -850.286 255.873 62.7582 + vertex -848.766 255.119 61.2821 + vertex -849.125 256.159 62.9007 + endloop + endfacet + facet normal 0.051102 -0.838874 0.541922 + outer loop + vertex -850.699 254.566 60.7805 + vertex -849.945 254.826 61.112 + vertex -851.142 255.685 62.5553 + endloop + endfacet + facet normal 0.0547968 -0.837272 0.544034 + outer loop + vertex -851.142 255.685 62.5553 + vertex -849.945 254.826 61.112 + vertex -850.286 255.873 62.7582 + endloop + endfacet + facet normal 0.0617185 -0.848649 0.525344 + outer loop + vertex -851.142 255.685 62.5553 + vertex -850.286 255.873 62.7582 + vertex -851.348 256.671 64.1713 + endloop + endfacet + facet normal 0.0624688 -0.848349 0.525739 + outer loop + vertex -851.348 256.671 64.1713 + vertex -850.286 255.873 62.7582 + vertex -850.604 256.887 64.4315 + endloop + endfacet + facet normal 0.14019 -0.834832 0.532355 + outer loop + vertex -850.286 255.873 62.7582 + vertex -849.125 256.159 62.9007 + vertex -850.604 256.887 64.4315 + endloop + endfacet + facet normal 0.146994 -0.830699 0.536966 + outer loop + vertex -850.604 256.887 64.4315 + vertex -849.125 256.159 62.9007 + vertex -849.464 257.171 64.5595 + endloop + endfacet + facet normal 0.428026 -0.709753 0.559504 + outer loop + vertex -847.466 255.665 61.4459 + vertex -846.239 256.588 61.6775 + vertex -847.85 256.69 63.0389 + endloop + endfacet + facet normal 0.431798 -0.704241 0.563556 + outer loop + vertex -847.85 256.69 63.0389 + vertex -846.239 256.588 61.6775 + vertex -846.637 257.599 63.2455 + endloop + endfacet + facet normal 0.259178 -0.785584 0.561859 + outer loop + vertex -848.766 255.119 61.2821 + vertex -847.466 255.665 61.4459 + vertex -849.125 256.159 62.9007 + endloop + endfacet + facet normal 0.264051 -0.781061 0.56588 + outer loop + vertex -849.125 256.159 62.9007 + vertex -847.466 255.665 61.4459 + vertex -847.85 256.69 63.0389 + endloop + endfacet + facet normal 0.272726 -0.795462 0.541167 + outer loop + vertex -849.125 256.159 62.9007 + vertex -847.85 256.69 63.0389 + vertex -849.464 257.171 64.5595 + endloop + endfacet + facet normal 0.28008 -0.788949 0.546913 + outer loop + vertex -849.464 257.171 64.5595 + vertex -847.85 256.69 63.0389 + vertex -848.207 257.698 64.6761 + endloop + endfacet + facet normal 0.444965 -0.715985 0.537933 + outer loop + vertex -847.85 256.69 63.0389 + vertex -846.637 257.599 63.2455 + vertex -848.207 257.698 64.6761 + endloop + endfacet + facet normal 0.445872 -0.714735 0.538843 + outer loop + vertex -848.207 257.698 64.6761 + vertex -846.637 257.599 63.2455 + vertex -847.004 258.58 64.8507 + endloop + endfacet + facet normal 0.309554 -0.635843 0.707021 + outer loop + vertex -844.516 249.16 52.9971 + vertex -843.227 250.246 53.4091 + vertex -845.095 250.272 54.2506 + endloop + endfacet + facet normal 0.31049 -0.633164 0.709013 + outer loop + vertex -845.095 250.272 54.2506 + vertex -843.227 250.246 53.4091 + vertex -843.802 251.303 54.6049 + endloop + endfacet + facet normal 0.167783 -0.699551 0.694606 + outer loop + vertex -845.903 248.37 52.5367 + vertex -844.516 249.16 52.9971 + vertex -846.458 249.579 53.8876 + endloop + endfacet + facet normal 0.169258 -0.697128 0.696681 + outer loop + vertex -846.458 249.579 53.8876 + vertex -844.516 249.16 52.9971 + vertex -845.095 250.272 54.2506 + endloop + endfacet + facet normal 0.185149 -0.716009 0.673091 + outer loop + vertex -846.458 249.579 53.8876 + vertex -845.095 250.272 54.2506 + vertex -847.001 250.745 55.2782 + endloop + endfacet + facet normal 0.185327 -0.71576 0.673307 + outer loop + vertex -847.001 250.745 55.2782 + vertex -845.095 250.272 54.2506 + vertex -845.64 251.371 55.5689 + endloop + endfacet + facet normal 0.333047 -0.651912 0.681242 + outer loop + vertex -845.095 250.272 54.2506 + vertex -843.802 251.303 54.6049 + vertex -845.64 251.371 55.5689 + endloop + endfacet + facet normal 0.333196 -0.651564 0.681502 + outer loop + vertex -845.64 251.371 55.5689 + vertex -843.802 251.303 54.6049 + vertex -844.346 252.364 55.8853 + endloop + endfacet + facet normal 0.0556334 -0.732992 0.677959 + outer loop + vertex -847.229 247.774 52.0007 + vertex -845.903 248.37 52.5367 + vertex -847.689 249.077 53.4478 + endloop + endfacet + facet normal 0.0559294 -0.732666 0.678286 + outer loop + vertex -847.689 249.077 53.4478 + vertex -845.903 248.37 52.5367 + vertex -846.458 249.579 53.8876 + endloop + endfacet + facet normal -0.0467223 -0.757994 0.650586 + outer loop + vertex -848.227 247.669 51.8063 + vertex -847.229 247.774 52.0007 + vertex -848.623 248.728 53.0126 + endloop + endfacet + facet normal -0.0299657 -0.747404 0.663694 + outer loop + vertex -848.623 248.728 53.0126 + vertex -847.229 247.774 52.0007 + vertex -847.689 249.077 53.4478 + endloop + endfacet + facet normal -0.0116391 -0.767735 0.640662 + outer loop + vertex -848.623 248.728 53.0126 + vertex -847.689 249.077 53.4478 + vertex -848.95 249.859 54.3608 + endloop + endfacet + facet normal -0.00976372 -0.766488 0.642185 + outer loop + vertex -848.95 249.859 54.3608 + vertex -847.689 249.077 53.4478 + vertex -848.21 250.306 54.9065 + endloop + endfacet + facet normal 0.0706244 -0.750337 0.657272 + outer loop + vertex -847.689 249.077 53.4478 + vertex -846.458 249.579 53.8876 + vertex -848.21 250.306 54.9065 + endloop + endfacet + facet normal 0.0705035 -0.750456 0.657149 + outer loop + vertex -848.21 250.306 54.9065 + vertex -846.458 249.579 53.8876 + vertex -847.001 250.745 55.2782 + endloop + endfacet + facet normal 0.0828551 -0.766891 0.636407 + outer loop + vertex -848.21 250.306 54.9065 + vertex -847.001 250.745 55.2782 + vertex -848.724 251.498 56.4094 + endloop + endfacet + facet normal 0.0812612 -0.768297 0.634915 + outer loop + vertex -848.724 251.498 56.4094 + vertex -847.001 250.745 55.2782 + vertex -847.505 251.875 56.7092 + endloop + endfacet + facet normal 0.0116438 -0.780703 0.624793 + outer loop + vertex -848.95 249.859 54.3608 + vertex -848.21 250.306 54.9065 + vertex -849.55 251.114 55.941 + endloop + endfacet + facet normal 0.00975379 -0.781924 0.623298 + outer loop + vertex -849.55 251.114 55.941 + vertex -848.21 250.306 54.9065 + vertex -848.724 251.498 56.4094 + endloop + endfacet + facet normal 0.0246628 -0.794238 0.607107 + outer loop + vertex -849.55 251.114 55.941 + vertex -848.724 251.498 56.4094 + vertex -849.907 252.305 57.5136 + endloop + endfacet + facet normal 0.0168665 -0.798444 0.601832 + outer loop + vertex -849.907 252.305 57.5136 + vertex -848.724 251.498 56.4094 + vertex -849.172 252.644 57.942 + endloop + endfacet + facet normal 0.091603 -0.784547 0.613266 + outer loop + vertex -848.724 251.498 56.4094 + vertex -847.505 251.875 56.7092 + vertex -849.172 252.644 57.942 + endloop + endfacet + facet normal 0.0929175 -0.783508 0.614395 + outer loop + vertex -849.172 252.644 57.942 + vertex -847.505 251.875 56.7092 + vertex -847.959 252.978 58.1846 + endloop + endfacet + facet normal 0.351488 -0.66744 0.656491 + outer loop + vertex -845.64 251.371 55.5689 + vertex -844.346 252.364 55.8853 + vertex -846.146 252.467 56.9537 + endloop + endfacet + facet normal 0.353361 -0.663687 0.659284 + outer loop + vertex -846.146 252.467 56.9537 + vertex -844.346 252.364 55.8853 + vertex -844.866 253.442 57.2493 + endloop + endfacet + facet normal 0.198884 -0.734081 0.649284 + outer loop + vertex -847.001 250.745 55.2782 + vertex -845.64 251.371 55.5689 + vertex -847.505 251.875 56.7092 + endloop + endfacet + facet normal 0.201334 -0.731044 0.65195 + outer loop + vertex -847.505 251.875 56.7092 + vertex -845.64 251.371 55.5689 + vertex -846.146 252.467 56.9537 + endloop + endfacet + facet normal 0.214029 -0.749592 0.626342 + outer loop + vertex -847.505 251.875 56.7092 + vertex -846.146 252.467 56.9537 + vertex -847.959 252.978 58.1846 + endloop + endfacet + facet normal 0.217701 -0.745436 0.630025 + outer loop + vertex -847.959 252.978 58.1846 + vertex -846.146 252.467 56.9537 + vertex -846.617 253.551 58.3991 + endloop + endfacet + facet normal 0.372329 -0.680159 0.63147 + outer loop + vertex -846.146 252.467 56.9537 + vertex -844.866 253.442 57.2493 + vertex -846.617 253.551 58.3991 + endloop + endfacet + facet normal 0.373488 -0.678063 0.633038 + outer loop + vertex -846.617 253.551 58.3991 + vertex -844.866 253.442 57.2493 + vertex -845.354 254.503 58.6736 + endloop + endfacet + facet normal 0.229899 -0.558686 0.796879 + outer loop + vertex -842.41 245.538 49.4252 + vertex -841.193 246.879 50.0141 + vertex -842.835 246.151 49.9774 + endloop + endfacet + facet normal 0.237328 -0.574746 0.783162 + outer loop + vertex -842.835 246.151 49.9774 + vertex -841.193 246.879 50.0141 + vertex -841.575 247.474 50.5669 + endloop + endfacet + facet normal 0.0925197 -0.608672 0.788009 + outer loop + vertex -843.633 244.507 48.7727 + vertex -842.41 245.538 49.4252 + vertex -844.24 245.053 49.2658 + endloop + endfacet + facet normal 0.0988423 -0.627409 0.772391 + outer loop + vertex -844.24 245.053 49.2658 + vertex -842.41 245.538 49.4252 + vertex -842.835 246.151 49.9774 + endloop + endfacet + facet normal 0.111517 -0.637251 0.762545 + outer loop + vertex -844.24 245.053 49.2658 + vertex -842.835 246.151 49.9774 + vertex -844.831 245.987 50.1325 + endloop + endfacet + facet normal 0.111642 -0.644925 0.756048 + outer loop + vertex -844.831 245.987 50.1325 + vertex -842.835 246.151 49.9774 + vertex -843.367 247.017 50.7947 + endloop + endfacet + facet normal 0.246801 -0.580542 0.775926 + outer loop + vertex -842.835 246.151 49.9774 + vertex -841.575 247.474 50.5669 + vertex -843.367 247.017 50.7947 + endloop + endfacet + facet normal 0.248256 -0.590064 0.76824 + outer loop + vertex -843.367 247.017 50.7947 + vertex -841.575 247.474 50.5669 + vertex -842.078 248.284 51.3514 + endloop + endfacet + facet normal -0.000809523 -0.660923 0.750454 + outer loop + vertex -845.583 244.668 48.9253 + vertex -845.081 244.239 48.5479 + vertex -844.24 245.053 49.2658 + endloop + endfacet + facet normal 0.00767194 -0.666762 0.745231 + outer loop + vertex -844.811 243.788 48.1411 + vertex -843.633 244.507 48.7727 + vertex -845.081 244.239 48.5479 + endloop + endfacet + facet normal 0.00729803 -0.665609 0.746265 + outer loop + vertex -843.633 244.507 48.7727 + vertex -844.24 245.053 49.2658 + vertex -845.081 244.239 48.5479 + endloop + endfacet + facet normal -0.0694037 -0.692413 0.718156 + outer loop + vertex -845.901 243.404 47.6659 + vertex -844.811 243.788 48.1411 + vertex -846.002 243.817 48.0548 + endloop + endfacet + facet normal -0.0694976 -0.690293 0.720185 + outer loop + vertex -846.002 243.817 48.0548 + vertex -844.811 243.788 48.1411 + vertex -845.081 244.239 48.5479 + endloop + endfacet + facet normal -0.120171 -0.686855 0.716791 + outer loop + vertex -846.551 243.313 47.4701 + vertex -845.901 243.404 47.6659 + vertex -846.75 243.672 47.7803 + endloop + endfacet + facet normal -0.124248 -0.695778 0.707429 + outer loop + vertex -846.75 243.672 47.7803 + vertex -845.901 243.404 47.6659 + vertex -846.002 243.817 48.0548 + endloop + endfacet + facet normal -0.122311 -0.699476 0.704112 + outer loop + vertex -846.75 243.672 47.7803 + vertex -846.002 243.817 48.0548 + vertex -846.842 244.144 48.2335 + endloop + endfacet + facet normal -0.124171 -0.702454 0.700814 + outer loop + vertex -846.842 244.144 48.2335 + vertex -846.002 243.817 48.0548 + vertex -846.272 244.353 48.5433 + endloop + endfacet + facet normal -0.0685806 -0.691285 0.71932 + outer loop + vertex -846.002 243.817 48.0548 + vertex -845.081 244.239 48.5479 + vertex -846.272 244.353 48.5433 + endloop + endfacet + facet normal -0.0697006 -0.703533 0.707236 + outer loop + vertex -846.272 244.353 48.5433 + vertex -845.081 244.239 48.5479 + vertex -845.583 244.668 48.9253 + endloop + endfacet + facet normal -0.076876 -0.695982 0.713932 + outer loop + vertex -846.272 244.353 48.5433 + vertex -845.583 244.668 48.9253 + vertex -846.581 244.937 49.0794 + endloop + endfacet + facet normal -0.074075 -0.689389 0.720594 + outer loop + vertex -846.581 244.937 49.0794 + vertex -845.583 244.668 48.9253 + vertex -845.724 245.237 49.455 + endloop + endfacet + facet normal -0.124765 -0.701739 0.701425 + outer loop + vertex -846.842 244.144 48.2335 + vertex -846.272 244.353 48.5433 + vertex -847.211 244.783 48.8068 + endloop + endfacet + facet normal -0.128612 -0.706663 0.695763 + outer loop + vertex -847.211 244.783 48.8068 + vertex -846.272 244.353 48.5433 + vertex -846.581 244.937 49.0794 + endloop + endfacet + facet normal -0.124255 -0.713498 0.689551 + outer loop + vertex -847.211 244.783 48.8068 + vertex -846.581 244.937 49.0794 + vertex -847.423 245.381 49.3877 + endloop + endfacet + facet normal -0.126654 -0.715962 0.686555 + outer loop + vertex -847.423 245.381 49.3877 + vertex -846.581 244.937 49.0794 + vertex -846.905 245.553 49.6627 + endloop + endfacet + facet normal -0.0637387 -0.703238 0.708091 + outer loop + vertex -846.581 244.937 49.0794 + vertex -845.724 245.237 49.455 + vertex -846.905 245.553 49.6627 + endloop + endfacet + facet normal -0.0702847 -0.717667 0.692831 + outer loop + vertex -846.905 245.553 49.6627 + vertex -845.724 245.237 49.455 + vertex -846.216 245.783 49.9707 + endloop + endfacet + facet normal 0.0143418 -0.679707 0.733344 + outer loop + vertex -846.216 245.783 49.9707 + vertex -845.724 245.237 49.455 + vertex -844.831 245.987 50.1325 + endloop + endfacet + facet normal 0.00917405 -0.68026 0.732914 + outer loop + vertex -845.583 244.668 48.9253 + vertex -844.24 245.053 49.2658 + vertex -845.724 245.237 49.455 + endloop + endfacet + facet normal 0.00998146 -0.67691 0.735998 + outer loop + vertex -844.24 245.053 49.2658 + vertex -844.831 245.987 50.1325 + vertex -845.724 245.237 49.455 + endloop + endfacet + facet normal 0.0444444 -0.703964 0.708844 + outer loop + vertex -846.637 246.958 51.1656 + vertex -846.312 246.397 50.5884 + vertex -845.446 247.11 51.2414 + endloop + endfacet + facet normal 0.0214977 -0.7072 0.706687 + outer loop + vertex -846.216 245.783 49.9707 + vertex -844.831 245.987 50.1325 + vertex -846.312 246.397 50.5884 + endloop + endfacet + facet normal 0.0288583 -0.694367 0.719043 + outer loop + vertex -844.831 245.987 50.1325 + vertex -845.446 247.11 51.2414 + vertex -846.312 246.397 50.5884 + endloop + endfacet + facet normal -0.0679712 -0.720694 0.689913 + outer loop + vertex -846.905 245.553 49.6627 + vertex -846.216 245.783 49.9707 + vertex -847.227 246.224 50.3319 + endloop + endfacet + facet normal -0.0610852 -0.712424 0.699086 + outer loop + vertex -847.227 246.224 50.3319 + vertex -846.216 245.783 49.9707 + vertex -846.312 246.397 50.5884 + endloop + endfacet + facet normal -0.119243 -0.725047 0.678297 + outer loop + vertex -847.423 245.381 49.3877 + vertex -846.905 245.553 49.6627 + vertex -847.859 246.095 50.0741 + endloop + endfacet + facet normal -0.124798 -0.730006 0.67195 + outer loop + vertex -847.859 246.095 50.0741 + vertex -846.905 245.553 49.6627 + vertex -847.227 246.224 50.3319 + endloop + endfacet + facet normal -0.116229 -0.744019 0.657971 + outer loop + vertex -847.859 246.095 50.0741 + vertex -847.227 246.224 50.3319 + vertex -848.193 246.959 50.9915 + endloop + endfacet + facet normal -0.102953 -0.736278 0.668802 + outer loop + vertex -848.193 246.959 50.9915 + vertex -847.227 246.224 50.3319 + vertex -847.397 246.932 51.0851 + endloop + endfacet + facet normal -0.0511552 -0.733433 0.677834 + outer loop + vertex -847.227 246.224 50.3319 + vertex -846.312 246.397 50.5884 + vertex -847.397 246.932 51.0851 + endloop + endfacet + facet normal -0.0473931 -0.729741 0.682079 + outer loop + vertex -847.397 246.932 51.0851 + vertex -846.312 246.397 50.5884 + vertex -846.637 246.958 51.1656 + endloop + endfacet + facet normal -0.101409 -0.752036 0.651274 + outer loop + vertex -848.193 246.959 50.9915 + vertex -847.397 246.932 51.0851 + vertex -848.227 247.669 51.8063 + endloop + endfacet + facet normal -0.0472089 -0.730998 0.680745 + outer loop + vertex -846.637 246.958 51.1656 + vertex -847.229 247.774 52.0007 + vertex -847.397 246.932 51.0851 + endloop + endfacet + facet normal -0.0556647 -0.729895 0.681289 + outer loop + vertex -847.229 247.774 52.0007 + vertex -848.227 247.669 51.8063 + vertex -847.397 246.932 51.0851 + endloop + endfacet + facet normal 0.0435066 -0.699046 0.713752 + outer loop + vertex -846.637 246.958 51.1656 + vertex -845.446 247.11 51.2414 + vertex -847.229 247.774 52.0007 + endloop + endfacet + facet normal 0.0350081 -0.709973 0.703358 + outer loop + vertex -847.229 247.774 52.0007 + vertex -845.446 247.11 51.2414 + vertex -845.903 248.37 52.5367 + endloop + endfacet + facet normal 0.266508 -0.601858 0.752822 + outer loop + vertex -843.367 247.017 50.7947 + vertex -842.078 248.284 51.3514 + vertex -843.939 248.054 51.8266 + endloop + endfacet + facet normal 0.266313 -0.604477 0.75079 + outer loop + vertex -843.939 248.054 51.8266 + vertex -842.078 248.284 51.3514 + vertex -842.645 249.234 52.3174 + endloop + endfacet + facet normal 0.12948 -0.659984 0.740038 + outer loop + vertex -844.831 245.987 50.1325 + vertex -843.367 247.017 50.7947 + vertex -845.446 247.11 51.2414 + endloop + endfacet + facet normal 0.128862 -0.662688 0.737725 + outer loop + vertex -845.446 247.11 51.2414 + vertex -843.367 247.017 50.7947 + vertex -843.939 248.054 51.8266 + endloop + endfacet + facet normal 0.149188 -0.681775 0.716189 + outer loop + vertex -845.446 247.11 51.2414 + vertex -843.939 248.054 51.8266 + vertex -845.903 248.37 52.5367 + endloop + endfacet + facet normal 0.149651 -0.680788 0.71703 + outer loop + vertex -845.903 248.37 52.5367 + vertex -843.939 248.054 51.8266 + vertex -844.516 249.16 52.9971 + endloop + endfacet + facet normal 0.28923 -0.620509 0.728913 + outer loop + vertex -843.939 248.054 51.8266 + vertex -842.645 249.234 52.3174 + vertex -844.516 249.16 52.9971 + endloop + endfacet + facet normal 0.289304 -0.620197 0.729149 + outer loop + vertex -844.516 249.16 52.9971 + vertex -842.645 249.234 52.3174 + vertex -843.227 250.246 53.4091 + endloop + endfacet + facet normal 0.62816 -0.698448 0.342907 + outer loop + vertex -842.038 245.072 48.9458 + vertex -840.803 246.485 49.5606 + vertex -842.088 245.028 48.948 + endloop + endfacet + facet normal 0.774078 -0.605969 -0.183317 + outer loop + vertex -842.088 245.028 48.948 + vertex -840.803 246.485 49.5606 + vertex -840.859 246.416 49.5514 + endloop + endfacet + facet normal 0.506712 -0.821522 0.261426 + outer loop + vertex -843.4 244.019 48.276 + vertex -842.038 245.072 48.9458 + vertex -843.44 243.998 48.2893 + endloop + endfacet + facet normal 0.64672 -0.745181 -0.162661 + outer loop + vertex -843.44 243.998 48.2893 + vertex -842.038 245.072 48.9458 + vertex -842.088 245.028 48.948 + endloop + endfacet + facet normal 0.379501 -0.797914 0.468308 + outer loop + vertex -843.44 243.998 48.2893 + vertex -842.088 245.028 48.948 + vertex -843.441 244.026 48.3369 + endloop + endfacet + facet normal 0.448578 -0.82097 0.35325 + outer loop + vertex -843.441 244.026 48.3369 + vertex -842.088 245.028 48.948 + vertex -842.106 245.033 48.9827 + endloop + endfacet + facet normal 0.589916 -0.698595 0.404925 + outer loop + vertex -842.088 245.028 48.948 + vertex -840.859 246.416 49.5514 + vertex -842.106 245.033 48.9827 + endloop + endfacet + facet normal 0.680603 -0.701186 0.212411 + outer loop + vertex -842.106 245.033 48.9827 + vertex -840.859 246.416 49.5514 + vertex -840.887 246.395 49.5723 + endloop + endfacet + facet normal 0.110372 -0.750779 0.651267 + outer loop + vertex -844.715 243.277 47.6436 + vertex -843.4 244.019 48.276 + vertex -844.752 243.297 47.6725 + endloop + endfacet + facet normal 0.461961 -0.88652 0.0259531 + outer loop + vertex -844.752 243.297 47.6725 + vertex -843.4 244.019 48.276 + vertex -843.44 243.998 48.2893 + endloop + endfacet + facet normal -0.095964 -0.612402 0.7847 + outer loop + vertex -845.637 242.846 47.1945 + vertex -844.715 243.277 47.6436 + vertex -845.808 242.875 47.1963 + endloop + endfacet + facet normal 0.0472026 -0.797719 0.601179 + outer loop + vertex -845.808 242.875 47.1963 + vertex -844.715 243.277 47.6436 + vertex -844.752 243.297 47.6725 + endloop + endfacet + facet normal -0.054634 -0.684598 0.72687 + outer loop + vertex -845.808 242.875 47.1963 + vertex -844.752 243.297 47.6725 + vertex -845.745 242.985 47.3044 + endloop + endfacet + facet normal -0.0246197 -0.729263 0.68379 + outer loop + vertex -845.745 242.985 47.3044 + vertex -844.752 243.297 47.6725 + vertex -844.777 243.348 47.727 + endloop + endfacet + facet normal 0.0509834 -0.7114 0.700935 + outer loop + vertex -844.752 243.297 47.6725 + vertex -843.44 243.998 48.2893 + vertex -844.777 243.348 47.727 + endloop + endfacet + facet normal 0.202486 -0.844901 0.495118 + outer loop + vertex -844.777 243.348 47.727 + vertex -843.44 243.998 48.2893 + vertex -843.441 244.026 48.3369 + endloop + endfacet + facet normal 0.0185566 -0.688814 0.7247 + outer loop + vertex -844.777 243.348 47.727 + vertex -843.441 244.026 48.3369 + vertex -844.775 243.493 47.8646 + endloop + endfacet + facet normal 0.0162248 -0.685665 0.727736 + outer loop + vertex -844.775 243.493 47.8646 + vertex -843.441 244.026 48.3369 + vertex -843.455 244.178 48.4805 + endloop + endfacet + facet normal -0.0979943 -0.632366 0.768447 + outer loop + vertex -845.745 242.985 47.3044 + vertex -844.777 243.348 47.727 + vertex -846.034 243.145 47.399 + endloop + endfacet + facet normal -0.0774948 -0.686181 0.723291 + outer loop + vertex -846.034 243.145 47.399 + vertex -844.777 243.348 47.727 + vertex -844.775 243.493 47.8646 + endloop + endfacet + facet normal -0.0728919 -0.687689 0.722337 + outer loop + vertex -844.811 243.788 48.1411 + vertex -845.901 243.404 47.6659 + vertex -844.775 243.493 47.8646 + endloop + endfacet + facet normal -0.122696 -0.680613 0.722296 + outer loop + vertex -846.551 243.313 47.4701 + vertex -846.034 243.145 47.399 + vertex -845.901 243.404 47.6659 + endloop + endfacet + facet normal -0.0704091 -0.697797 0.712827 + outer loop + vertex -846.034 243.145 47.399 + vertex -844.775 243.493 47.8646 + vertex -845.901 243.404 47.6659 + endloop + endfacet + facet normal 0.0143495 -0.683726 0.729598 + outer loop + vertex -844.775 243.493 47.8646 + vertex -843.455 244.178 48.4805 + vertex -844.811 243.788 48.1411 + endloop + endfacet + facet normal 0.00367278 -0.663101 0.748521 + outer loop + vertex -844.811 243.788 48.1411 + vertex -843.455 244.178 48.4805 + vertex -843.633 244.507 48.7727 + endloop + endfacet + facet normal 0.26547 -0.573225 0.775203 + outer loop + vertex -842.106 245.033 48.9827 + vertex -840.887 246.395 49.5723 + vertex -842.171 245.188 49.1192 + endloop + endfacet + facet normal 0.248293 -0.560524 0.79004 + outer loop + vertex -842.171 245.188 49.1192 + vertex -840.887 246.395 49.5723 + vertex -840.974 246.538 49.7013 + endloop + endfacet + facet normal 0.1548 -0.670415 0.725659 + outer loop + vertex -843.441 244.026 48.3369 + vertex -842.106 245.033 48.9827 + vertex -843.455 244.178 48.4805 + endloop + endfacet + facet normal 0.113922 -0.630598 0.767703 + outer loop + vertex -843.455 244.178 48.4805 + vertex -842.106 245.033 48.9827 + vertex -842.171 245.188 49.1192 + endloop + endfacet + facet normal 0.108917 -0.626702 0.77161 + outer loop + vertex -843.455 244.178 48.4805 + vertex -842.171 245.188 49.1192 + vertex -843.633 244.507 48.7727 + endloop + endfacet + facet normal 0.100957 -0.614935 0.782088 + outer loop + vertex -843.633 244.507 48.7727 + vertex -842.171 245.188 49.1192 + vertex -842.41 245.538 49.4252 + endloop + endfacet + facet normal 0.227374 -0.548332 0.804757 + outer loop + vertex -842.171 245.188 49.1192 + vertex -840.974 246.538 49.7013 + vertex -842.41 245.538 49.4252 + endloop + endfacet + facet normal 0.243707 -0.566857 0.786943 + outer loop + vertex -842.41 245.538 49.4252 + vertex -840.974 246.538 49.7013 + vertex -841.193 246.879 50.0141 + endloop + endfacet + facet normal 0.201543 -0.736563 0.645644 + outer loop + vertex -843.531 243.696 47.9921 + vertex -842.315 244.555 48.5923 + vertex -843.437 243.834 48.1195 + endloop + endfacet + facet normal -0.0147061 -0.531987 0.846625 + outer loop + vertex -843.437 243.834 48.1195 + vertex -842.315 244.555 48.5923 + vertex -842.06 244.868 48.7935 + endloop + endfacet + facet normal 0.416113 -0.706427 0.572548 + outer loop + vertex -842.315 244.555 48.5923 + vertex -841.066 245.779 49.1949 + vertex -842.06 244.868 48.7935 + endloop + endfacet + facet normal 0.0955895 -0.486951 0.868183 + outer loop + vertex -842.06 244.868 48.7935 + vertex -841.066 245.779 49.1949 + vertex -840.782 246.25 49.4279 + endloop + endfacet + facet normal 0.0377865 -0.795099 0.605301 + outer loop + vertex -845.943 242.517 46.8635 + vertex -844.953 242.915 47.3248 + vertex -845.695 242.663 47.0393 + endloop + endfacet + facet normal -0.0982977 -0.604727 0.790343 + outer loop + vertex -845.695 242.663 47.0393 + vertex -844.953 242.915 47.3248 + vertex -844.767 243.087 47.4795 + endloop + endfacet + facet normal 0.0440444 -0.694217 0.718417 + outer loop + vertex -844.953 242.915 47.3248 + vertex -843.531 243.696 47.9921 + vertex -844.767 243.087 47.4795 + endloop + endfacet + facet normal 0.0456831 -0.696002 0.716585 + outer loop + vertex -844.767 243.087 47.4795 + vertex -843.531 243.696 47.9921 + vertex -843.437 243.834 48.1195 + endloop + endfacet + facet normal -0.004812 -0.646049 0.763281 + outer loop + vertex -844.767 243.087 47.4795 + vertex -843.437 243.834 48.1195 + vertex -844.702 243.211 47.5849 + endloop + endfacet + facet normal -0.0403234 -0.602751 0.79691 + outer loop + vertex -844.702 243.211 47.5849 + vertex -843.437 243.834 48.1195 + vertex -843.376 243.975 48.2294 + endloop + endfacet + facet normal -0.110708 -0.588518 0.800869 + outer loop + vertex -845.695 242.663 47.0393 + vertex -844.767 243.087 47.4795 + vertex -845.738 242.732 47.0839 + endloop + endfacet + facet normal -0.0931029 -0.615906 0.782299 + outer loop + vertex -845.738 242.732 47.0839 + vertex -844.767 243.087 47.4795 + vertex -844.702 243.211 47.5849 + endloop + endfacet + facet normal -0.0451434 -0.673243 0.738042 + outer loop + vertex -845.738 242.732 47.0839 + vertex -844.702 243.211 47.5849 + vertex -845.637 242.846 47.1945 + endloop + endfacet + facet normal -0.0471385 -0.670586 0.740333 + outer loop + vertex -845.637 242.846 47.1945 + vertex -844.702 243.211 47.5849 + vertex -844.715 243.277 47.6436 + endloop + endfacet + facet normal 0.0189737 -0.664015 0.747479 + outer loop + vertex -844.702 243.211 47.5849 + vertex -843.376 243.975 48.2294 + vertex -844.715 243.277 47.6436 + endloop + endfacet + facet normal 0.0615186 -0.708409 0.703116 + outer loop + vertex -844.715 243.277 47.6436 + vertex -843.376 243.975 48.2294 + vertex -843.4 244.019 48.276 + endloop + endfacet + facet normal 0.237788 -0.578212 0.780466 + outer loop + vertex -842.06 244.868 48.7935 + vertex -840.782 246.25 49.4279 + vertex -841.993 245.053 48.9099 + endloop + endfacet + facet normal 0.0765901 -0.460174 0.884519 + outer loop + vertex -841.993 245.053 48.9099 + vertex -840.782 246.25 49.4279 + vertex -840.739 246.467 49.537 + endloop + endfacet + facet normal 0.10745 -0.639123 0.761562 + outer loop + vertex -843.437 243.834 48.1195 + vertex -842.06 244.868 48.7935 + vertex -843.376 243.975 48.2294 + endloop + endfacet + facet normal -0.00108647 -0.532765 0.846262 + outer loop + vertex -843.376 243.975 48.2294 + vertex -842.06 244.868 48.7935 + vertex -841.993 245.053 48.9099 + endloop + endfacet + facet normal 0.167178 -0.670616 0.722721 + outer loop + vertex -843.376 243.975 48.2294 + vertex -841.993 245.053 48.9099 + vertex -843.4 244.019 48.276 + endloop + endfacet + facet normal 0.222675 -0.711598 0.666367 + outer loop + vertex -843.4 244.019 48.276 + vertex -841.993 245.053 48.9099 + vertex -842.038 245.072 48.9458 + endloop + endfacet + facet normal 0.319232 -0.60617 0.728456 + outer loop + vertex -841.993 245.053 48.9099 + vertex -840.739 246.467 49.537 + vertex -842.038 245.072 48.9458 + endloop + endfacet + facet normal 0.16622 -0.512092 0.842693 + outer loop + vertex -842.038 245.072 48.9458 + vertex -840.739 246.467 49.537 + vertex -840.803 246.485 49.5606 + endloop + endfacet + facet normal 0.54243 -0.31916 -0.777114 + outer loop + vertex -839.236 250.135 293.339 + vertex -839.322 250.578 293.098 + vertex -837.907 254.008 292.676 + endloop + endfacet + facet normal 0.582969 -0.336984 -0.739316 + outer loop + vertex -839.738 250.274 292.908 + vertex -838.617 254.077 292.059 + vertex -839.322 250.578 293.098 + endloop + endfacet + facet normal 0.599453 -0.336432 -0.726271 + outer loop + vertex -838.617 254.077 292.059 + vertex -837.907 254.008 292.676 + vertex -839.322 250.578 293.098 + endloop + endfacet + facet normal 0.524074 -0.424042 -0.738603 + outer loop + vertex -840.76 248.495 293.204 + vertex -839.738 250.274 292.908 + vertex -840.533 248.163 293.556 + endloop + endfacet + facet normal 0.616403 -0.433844 -0.657136 + outer loop + vertex -840.533 248.163 293.556 + vertex -839.738 250.274 292.908 + vertex -839.322 250.578 293.098 + endloop + endfacet + facet normal 0.386218 -0.486658 -0.783581 + outer loop + vertex -842.006 246.915 293.571 + vertex -840.76 248.495 293.204 + vertex -841.779 246.47 293.96 + endloop + endfacet + facet normal 0.433889 -0.498329 -0.750605 + outer loop + vertex -841.779 246.47 293.96 + vertex -840.76 248.495 293.204 + vertex -840.533 248.163 293.556 + endloop + endfacet + facet normal 0.390475 -0.475411 -0.788361 + outer loop + vertex -841.779 246.47 293.96 + vertex -840.533 248.163 293.556 + vertex -841.594 246.347 294.126 + endloop + endfacet + facet normal 0.450373 -0.495983 -0.742405 + outer loop + vertex -841.594 246.347 294.126 + vertex -840.533 248.163 293.556 + vertex -840.337 248.126 293.7 + endloop + endfacet + facet normal 0.493591 -0.394605 -0.77502 + outer loop + vertex -840.533 248.163 293.556 + vertex -839.322 250.578 293.098 + vertex -840.337 248.126 293.7 + endloop + endfacet + facet normal 0.410783 -0.374169 -0.831417 + outer loop + vertex -840.337 248.126 293.7 + vertex -839.322 250.578 293.098 + vertex -839.236 250.135 293.339 + endloop + endfacet + facet normal 0.248237 -0.301166 -0.920694 + outer loop + vertex -840.337 248.126 293.7 + vertex -839.236 250.135 293.339 + vertex -840.143 248.2 293.727 + endloop + endfacet + facet normal 0.0898616 -0.236312 -0.967513 + outer loop + vertex -840.143 248.2 293.727 + vertex -839.236 250.135 293.339 + vertex -839.398 249.498 293.48 + endloop + endfacet + facet normal 0.266881 -0.398648 -0.877414 + outer loop + vertex -841.594 246.347 294.126 + vertex -840.337 248.126 293.7 + vertex -841.307 246.544 294.123 + endloop + endfacet + facet normal 0.281064 -0.405337 -0.869888 + outer loop + vertex -841.307 246.544 294.123 + vertex -840.337 248.126 293.7 + vertex -840.143 248.2 293.727 + endloop + endfacet + facet normal 0.626513 -0.352393 -0.695198 + outer loop + vertex -840.526 251.546 291.625 + vertex -840.939 252.907 290.562 + vertex -839.484 255.228 290.698 + endloop + endfacet + facet normal 0.610255 -0.375124 -0.697762 + outer loop + vertex -841.67 253.445 289.634 + vertex -840.553 256.996 288.702 + vertex -840.939 252.907 290.562 + endloop + endfacet + facet normal 0.645752 -0.365918 -0.670156 + outer loop + vertex -840.553 256.996 288.702 + vertex -839.484 255.228 290.698 + vertex -840.939 252.907 290.562 + endloop + endfacet + facet normal 0.536307 -0.44956 -0.714332 + outer loop + vertex -842.772 251.945 289.751 + vertex -841.67 253.445 289.634 + vertex -842.178 250.952 290.822 + endloop + endfacet + facet normal 0.558791 -0.4467 -0.698722 + outer loop + vertex -842.178 250.952 290.822 + vertex -841.67 253.445 289.634 + vertex -840.939 252.907 290.562 + endloop + endfacet + facet normal 0.439535 -0.526174 -0.727977 + outer loop + vertex -844.051 250.497 290.026 + vertex -842.772 251.945 289.751 + vertex -843.47 249.496 291.1 + endloop + endfacet + facet normal 0.436126 -0.526285 -0.729944 + outer loop + vertex -843.47 249.496 291.1 + vertex -842.772 251.945 289.751 + vertex -842.178 250.952 290.822 + endloop + endfacet + facet normal 0.415335 -0.512018 -0.751887 + outer loop + vertex -843.47 249.496 291.1 + vertex -842.178 250.952 290.822 + vertex -842.889 248.511 292.092 + endloop + endfacet + facet normal 0.412406 -0.512007 -0.753505 + outer loop + vertex -842.889 248.511 292.092 + vertex -842.178 250.952 290.822 + vertex -841.594 249.987 291.797 + endloop + endfacet + facet normal 0.522448 -0.428771 -0.737023 + outer loop + vertex -842.178 250.952 290.822 + vertex -840.939 252.907 290.562 + vertex -841.594 249.987 291.797 + endloop + endfacet + facet normal 0.506548 -0.429651 -0.747535 + outer loop + vertex -841.594 249.987 291.797 + vertex -840.939 252.907 290.562 + vertex -840.526 251.546 291.625 + endloop + endfacet + facet normal 0.504233 -0.428321 -0.749861 + outer loop + vertex -841.594 249.987 291.797 + vertex -840.526 251.546 291.625 + vertex -841.105 249.139 292.61 + endloop + endfacet + facet normal 0.552743 -0.426182 -0.716131 + outer loop + vertex -841.105 249.139 292.61 + vertex -840.526 251.546 291.625 + vertex -839.938 251.258 292.249 + endloop + endfacet + facet normal 0.398228 -0.502366 -0.767491 + outer loop + vertex -842.889 248.511 292.092 + vertex -841.594 249.987 291.797 + vertex -842.378 247.62 292.939 + endloop + endfacet + facet normal 0.401562 -0.502567 -0.76562 + outer loop + vertex -842.378 247.62 292.939 + vertex -841.594 249.987 291.797 + vertex -841.105 249.139 292.61 + endloop + endfacet + facet normal 0.387315 -0.49347 -0.778765 + outer loop + vertex -842.378 247.62 292.939 + vertex -841.105 249.139 292.61 + vertex -842.006 246.915 293.571 + endloop + endfacet + facet normal 0.401338 -0.495507 -0.770325 + outer loop + vertex -842.006 246.915 293.571 + vertex -841.105 249.139 292.61 + vertex -840.76 248.495 293.204 + endloop + endfacet + facet normal 0.518392 -0.412855 -0.748879 + outer loop + vertex -841.105 249.139 292.61 + vertex -839.938 251.258 292.249 + vertex -840.76 248.495 293.204 + endloop + endfacet + facet normal 0.494485 -0.411524 -0.765593 + outer loop + vertex -840.76 248.495 293.204 + vertex -839.938 251.258 292.249 + vertex -839.738 250.274 292.908 + endloop + endfacet + facet normal 0.626522 -0.341205 -0.700749 + outer loop + vertex -839.738 250.274 292.908 + vertex -839.938 251.258 292.249 + vertex -838.617 254.077 292.059 + endloop + endfacet + facet normal 0.596185 -0.350618 -0.72224 + outer loop + vertex -840.526 251.546 291.625 + vertex -839.484 255.228 290.698 + vertex -839.938 251.258 292.249 + endloop + endfacet + facet normal 0.632854 -0.343705 -0.693803 + outer loop + vertex -839.484 255.228 290.698 + vertex -838.617 254.077 292.059 + vertex -839.938 251.258 292.249 + endloop + endfacet + facet normal 0.719115 -0.395298 -0.5715 + outer loop + vertex -842.765 255.421 287.308 + vertex -843.104 256.83 285.907 + vertex -841.616 258.936 286.323 + endloop + endfacet + facet normal 0.723248 -0.403312 -0.560581 + outer loop + vertex -843.725 257.389 284.705 + vertex -842.584 260.877 283.667 + vertex -843.104 256.83 285.907 + endloop + endfacet + facet normal 0.725464 -0.40238 -0.558383 + outer loop + vertex -842.584 260.877 283.667 + vertex -841.616 258.936 286.323 + vertex -843.104 256.83 285.907 + endloop + endfacet + facet normal 0.644305 -0.494051 -0.583767 + outer loop + vertex -844.785 255.958 284.745 + vertex -843.725 257.389 284.705 + vertex -844.325 254.939 286.115 + endloop + endfacet + facet normal 0.661191 -0.489445 -0.568569 + outer loop + vertex -844.325 254.939 286.115 + vertex -843.725 257.389 284.705 + vertex -843.104 256.83 285.907 + endloop + endfacet + facet normal 0.523594 -0.588861 -0.615705 + outer loop + vertex -846.042 254.656 284.922 + vertex -844.785 255.958 284.745 + vertex -845.591 253.59 286.325 + endloop + endfacet + facet normal 0.525622 -0.588578 -0.614245 + outer loop + vertex -845.591 253.59 286.325 + vertex -844.785 255.958 284.745 + vertex -844.325 254.939 286.115 + endloop + endfacet + facet normal 0.508341 -0.576359 -0.639844 + outer loop + vertex -845.591 253.59 286.325 + vertex -844.325 254.939 286.115 + vertex -845.115 252.544 287.645 + endloop + endfacet + facet normal 0.506319 -0.576585 -0.641241 + outer loop + vertex -845.115 252.544 287.645 + vertex -844.325 254.939 286.115 + vertex -843.844 253.93 287.402 + endloop + endfacet + facet normal 0.633425 -0.476064 -0.61003 + outer loop + vertex -844.325 254.939 286.115 + vertex -843.104 256.83 285.907 + vertex -843.844 253.93 287.402 + endloop + endfacet + facet normal 0.609288 -0.480579 -0.630724 + outer loop + vertex -843.844 253.93 287.402 + vertex -843.104 256.83 285.907 + vertex -842.765 255.421 287.308 + endloop + endfacet + facet normal 0.599299 -0.474244 -0.64493 + outer loop + vertex -843.844 253.93 287.402 + vertex -842.765 255.421 287.308 + vertex -843.329 252.935 288.612 + endloop + endfacet + facet normal 0.614121 -0.471347 -0.632998 + outer loop + vertex -843.329 252.935 288.612 + vertex -842.765 255.421 287.308 + vertex -842.088 254.871 288.375 + endloop + endfacet + facet normal 0.482601 -0.56041 -0.67308 + outer loop + vertex -845.115 252.544 287.645 + vertex -843.844 253.93 287.402 + vertex -844.602 251.504 288.879 + endloop + endfacet + facet normal 0.489435 -0.559828 -0.668615 + outer loop + vertex -844.602 251.504 288.879 + vertex -843.844 253.93 287.402 + vertex -843.329 252.935 288.612 + endloop + endfacet + facet normal 0.463999 -0.543024 -0.699878 + outer loop + vertex -844.602 251.504 288.879 + vertex -843.329 252.935 288.612 + vertex -844.051 250.497 290.026 + endloop + endfacet + facet normal 0.464697 -0.542982 -0.699448 + outer loop + vertex -844.051 250.497 290.026 + vertex -843.329 252.935 288.612 + vertex -842.772 251.945 289.751 + endloop + endfacet + facet normal 0.57844 -0.45394 -0.677751 + outer loop + vertex -843.329 252.935 288.612 + vertex -842.088 254.871 288.375 + vertex -842.772 251.945 289.751 + endloop + endfacet + facet normal 0.548486 -0.457387 -0.699972 + outer loop + vertex -842.772 251.945 289.751 + vertex -842.088 254.871 288.375 + vertex -841.67 253.445 289.634 + endloop + endfacet + facet normal 0.661487 -0.378094 -0.647673 + outer loop + vertex -841.67 253.445 289.634 + vertex -842.088 254.871 288.375 + vertex -840.553 256.996 288.702 + endloop + endfacet + facet normal 0.669536 -0.395177 -0.628932 + outer loop + vertex -842.765 255.421 287.308 + vertex -841.616 258.936 286.323 + vertex -842.088 254.871 288.375 + endloop + endfacet + facet normal 0.676644 -0.392875 -0.622738 + outer loop + vertex -841.616 258.936 286.323 + vertex -840.553 256.996 288.702 + vertex -842.088 254.871 288.375 + endloop + endfacet + facet normal 0.790803 -0.40723 -0.45694 + outer loop + vertex -844.61 259.379 281.804 + vertex -844.866 260.776 280.116 + vertex -843.46 262.789 280.756 + endloop + endfacet + facet normal 0.788422 -0.417162 -0.452069 + outer loop + vertex -845.402 261.345 278.656 + vertex -844.238 264.651 277.636 + vertex -844.866 260.776 280.116 + endloop + endfacet + facet normal 0.794375 -0.413547 -0.444912 + outer loop + vertex -844.238 264.651 277.636 + vertex -843.46 262.789 280.756 + vertex -844.866 260.776 280.116 + endloop + endfacet + facet normal 0.710406 -0.51727 -0.477237 + outer loop + vertex -846.416 260.027 278.574 + vertex -845.402 261.345 278.656 + vertex -846.049 259.034 280.198 + endloop + endfacet + facet normal 0.722191 -0.512261 -0.464788 + outer loop + vertex -846.049 259.034 280.198 + vertex -845.402 261.345 278.656 + vertex -844.866 260.776 280.116 + endloop + endfacet + facet normal 0.588186 -0.624495 -0.513851 + outer loop + vertex -847.609 258.838 278.654 + vertex -846.416 260.027 278.574 + vertex -847.257 257.82 280.293 + endloop + endfacet + facet normal 0.586693 -0.624885 -0.515082 + outer loop + vertex -847.257 257.82 280.293 + vertex -846.416 260.027 278.574 + vertex -846.049 259.034 280.198 + endloop + endfacet + facet normal 0.57525 -0.615372 -0.538893 + outer loop + vertex -847.257 257.82 280.293 + vertex -846.049 259.034 280.198 + vertex -846.876 256.775 281.895 + endloop + endfacet + facet normal 0.572496 -0.616013 -0.541088 + outer loop + vertex -846.876 256.775 281.895 + vertex -846.049 259.034 280.198 + vertex -845.651 258.015 281.778 + endloop + endfacet + facet normal 0.704832 -0.502166 -0.50104 + outer loop + vertex -846.049 259.034 280.198 + vertex -844.866 260.776 280.116 + vertex -845.651 258.015 281.778 + endloop + endfacet + facet normal 0.681024 -0.510059 -0.525401 + outer loop + vertex -845.651 258.015 281.778 + vertex -844.866 260.776 280.116 + vertex -844.61 259.379 281.804 + endloop + endfacet + facet normal 0.677763 -0.507444 -0.532107 + outer loop + vertex -845.651 258.015 281.778 + vertex -844.61 259.379 281.804 + vertex -845.228 256.987 283.298 + endloop + endfacet + facet normal 0.695939 -0.501073 -0.514387 + outer loop + vertex -845.228 256.987 283.298 + vertex -844.61 259.379 281.804 + vertex -844.026 258.808 283.15 + endloop + endfacet + facet normal 0.561437 -0.607102 -0.562331 + outer loop + vertex -846.876 256.775 281.895 + vertex -845.651 258.015 281.778 + vertex -846.47 255.716 283.443 + endloop + endfacet + facet normal 0.556161 -0.608172 -0.566402 + outer loop + vertex -846.47 255.716 283.443 + vertex -845.651 258.015 281.778 + vertex -845.228 256.987 283.298 + endloop + endfacet + facet normal 0.544426 -0.599081 -0.587113 + outer loop + vertex -846.47 255.716 283.443 + vertex -845.228 256.987 283.298 + vertex -846.042 254.656 284.922 + endloop + endfacet + facet normal 0.538624 -0.60007 -0.591439 + outer loop + vertex -846.042 254.656 284.922 + vertex -845.228 256.987 283.298 + vertex -844.785 255.958 284.745 + endloop + endfacet + facet normal 0.673432 -0.489427 -0.554031 + outer loop + vertex -845.228 256.987 283.298 + vertex -844.026 258.808 283.15 + vertex -844.785 255.958 284.745 + endloop + endfacet + facet normal 0.647395 -0.496193 -0.578509 + outer loop + vertex -844.785 255.958 284.745 + vertex -844.026 258.808 283.15 + vertex -843.725 257.389 284.705 + endloop + endfacet + facet normal 0.758946 -0.400871 -0.513131 + outer loop + vertex -843.725 257.389 284.705 + vertex -844.026 258.808 283.15 + vertex -842.584 260.877 283.667 + endloop + endfacet + facet normal 0.759662 -0.411144 -0.50386 + outer loop + vertex -844.61 259.379 281.804 + vertex -843.46 262.789 280.756 + vertex -844.026 258.808 283.15 + endloop + endfacet + facet normal 0.76467 -0.408551 -0.498363 + outer loop + vertex -843.46 262.789 280.756 + vertex -842.584 260.877 283.667 + vertex -844.026 258.808 283.15 + endloop + endfacet + facet normal 0.837828 -0.414782 -0.354964 + outer loop + vertex -846.076 263.221 275.367 + vertex -846.211 264.49 273.565 + vertex -844.905 266.43 274.381 + endloop + endfacet + facet normal 0.83446 -0.421411 -0.35509 + outer loop + vertex -846.632 264.968 272.007 + vertex -845.461 268.101 271.042 + vertex -846.211 264.49 273.565 + endloop + endfacet + facet normal 0.838787 -0.417983 -0.348893 + outer loop + vertex -845.461 268.101 271.042 + vertex -844.905 266.43 274.381 + vertex -846.211 264.49 273.565 + endloop + endfacet + facet normal 0.75656 -0.529016 -0.384394 + outer loop + vertex -847.592 263.706 271.856 + vertex -846.632 264.968 272.007 + vertex -847.339 262.835 273.553 + endloop + endfacet + facet normal 0.769518 -0.521684 -0.368358 + outer loop + vertex -847.339 262.835 273.553 + vertex -846.632 264.968 272.007 + vertex -846.211 264.49 273.565 + endloop + endfacet + facet normal 0.645685 -0.640196 -0.416222 + outer loop + vertex -848.719 262.563 271.865 + vertex -847.592 263.706 271.856 + vertex -848.483 261.685 273.582 + endloop + endfacet + facet normal 0.636125 -0.643766 -0.425336 + outer loop + vertex -848.483 261.685 273.582 + vertex -847.592 263.706 271.856 + vertex -847.339 262.835 273.553 + endloop + endfacet + facet normal 0.631136 -0.639163 -0.439476 + outer loop + vertex -848.483 261.685 273.582 + vertex -847.339 262.835 273.553 + vertex -848.219 260.77 275.292 + endloop + endfacet + facet normal 0.626224 -0.640871 -0.44399 + outer loop + vertex -848.219 260.77 275.292 + vertex -847.339 262.835 273.553 + vertex -847.061 261.934 275.245 + endloop + endfacet + facet normal 0.759271 -0.514482 -0.398518 + outer loop + vertex -847.339 262.835 273.553 + vertex -846.211 264.49 273.565 + vertex -847.061 261.934 275.245 + endloop + endfacet + facet normal 0.737839 -0.524594 -0.424729 + outer loop + vertex -847.061 261.934 275.245 + vertex -846.211 264.49 273.565 + vertex -846.076 263.221 275.367 + endloop + endfacet + facet normal 0.736919 -0.523626 -0.427512 + outer loop + vertex -847.061 261.934 275.245 + vertex -846.076 263.221 275.367 + vertex -846.754 260.998 276.921 + endloop + endfacet + facet normal 0.749777 -0.517208 -0.412712 + outer loop + vertex -846.754 260.998 276.921 + vertex -846.076 263.221 275.367 + vertex -845.6 262.693 276.893 + endloop + endfacet + facet normal 0.619353 -0.634765 -0.462034 + outer loop + vertex -848.219 260.77 275.292 + vertex -847.061 261.934 275.245 + vertex -847.928 259.82 276.986 + endloop + endfacet + facet normal 0.612587 -0.63693 -0.468035 + outer loop + vertex -847.928 259.82 276.986 + vertex -847.061 261.934 275.245 + vertex -846.754 260.998 276.921 + endloop + endfacet + facet normal 0.604784 -0.630193 -0.486923 + outer loop + vertex -847.928 259.82 276.986 + vertex -846.754 260.998 276.921 + vertex -847.609 258.838 278.654 + endloop + endfacet + facet normal 0.597394 -0.632332 -0.493231 + outer loop + vertex -847.609 258.838 278.654 + vertex -846.754 260.998 276.921 + vertex -846.416 260.027 278.574 + endloop + endfacet + facet normal 0.735415 -0.508014 -0.448426 + outer loop + vertex -846.754 260.998 276.921 + vertex -845.6 262.693 276.893 + vertex -846.416 260.027 278.574 + endloop + endfacet + facet normal 0.710977 -0.517798 -0.475813 + outer loop + vertex -846.416 260.027 278.574 + vertex -845.6 262.693 276.893 + vertex -845.402 261.345 278.656 + endloop + endfacet + facet normal 0.814926 -0.412603 -0.407006 + outer loop + vertex -845.402 261.345 278.656 + vertex -845.6 262.693 276.893 + vertex -844.238 264.651 277.636 + endloop + endfacet + facet normal 0.814879 -0.420061 -0.399402 + outer loop + vertex -846.076 263.221 275.367 + vertex -844.905 266.43 274.381 + vertex -845.6 262.693 276.893 + endloop + endfacet + facet normal 0.817311 -0.418362 -0.396202 + outer loop + vertex -844.905 266.43 274.381 + vertex -844.238 264.651 277.636 + vertex -845.6 262.693 276.893 + endloop + endfacet + facet normal 0.866445 -0.416779 -0.274895 + outer loop + vertex -847.09 266.591 268.615 + vertex -847.132 267.729 266.758 + vertex -845.922 269.669 267.63 + endloop + endfacet + facet normal 0.865648 -0.419069 -0.273924 + outer loop + vertex -847.463 268.115 265.12 + vertex -846.308 271.17 264.097 + vertex -847.132 267.729 266.758 + endloop + endfacet + facet normal 0.866642 -0.418063 -0.272314 + outer loop + vertex -846.308 271.17 264.097 + vertex -845.922 269.669 267.63 + vertex -847.132 267.729 266.758 + endloop + endfacet + facet normal 0.790432 -0.532077 -0.303498 + outer loop + vertex -848.373 266.871 264.93 + vertex -847.463 268.115 265.12 + vertex -848.204 266.105 266.714 + endloop + endfacet + facet normal 0.803222 -0.522686 -0.285715 + outer loop + vertex -848.204 266.105 266.714 + vertex -847.463 268.115 265.12 + vertex -847.132 267.729 266.758 + endloop + endfacet + facet normal 0.685719 -0.645972 -0.335425 + outer loop + vertex -849.447 265.747 264.899 + vertex -848.373 266.871 264.93 + vertex -849.292 264.982 266.691 + endloop + endfacet + facet normal 0.678205 -0.649721 -0.343367 + outer loop + vertex -849.292 264.982 266.691 + vertex -848.373 266.871 264.93 + vertex -848.204 266.105 266.714 + endloop + endfacet + facet normal 0.67549 -0.646873 -0.353933 + outer loop + vertex -849.292 264.982 266.691 + vertex -848.204 266.105 266.714 + vertex -849.122 264.206 268.433 + endloop + endfacet + facet normal 0.668839 -0.649942 -0.360873 + outer loop + vertex -849.122 264.206 268.433 + vertex -848.204 266.105 266.714 + vertex -848.02 265.331 268.447 + endloop + endfacet + facet normal 0.795871 -0.517046 -0.315043 + outer loop + vertex -848.204 266.105 266.714 + vertex -847.132 267.729 266.758 + vertex -848.02 265.331 268.447 + endloop + endfacet + facet normal 0.777143 -0.528678 -0.341391 + outer loop + vertex -848.02 265.331 268.447 + vertex -847.132 267.729 266.758 + vertex -847.09 266.591 268.615 + endloop + endfacet + facet normal 0.77747 -0.529108 -0.33998 + outer loop + vertex -848.02 265.331 268.447 + vertex -847.09 266.591 268.615 + vertex -847.817 264.534 270.155 + endloop + endfacet + facet normal 0.787463 -0.522676 -0.326669 + outer loop + vertex -847.817 264.534 270.155 + vertex -847.09 266.591 268.615 + vertex -846.718 266.167 270.19 + endloop + endfacet + facet normal 0.66446 -0.645453 -0.376673 + outer loop + vertex -849.122 264.206 268.433 + vertex -848.02 265.331 268.447 + vertex -848.931 263.4 270.15 + endloop + endfacet + facet normal 0.660003 -0.647357 -0.381216 + outer loop + vertex -848.931 263.4 270.15 + vertex -848.02 265.331 268.447 + vertex -847.817 264.534 270.155 + endloop + endfacet + facet normal 0.65587 -0.64323 -0.395082 + outer loop + vertex -848.931 263.4 270.15 + vertex -847.817 264.534 270.155 + vertex -848.719 262.563 271.865 + endloop + endfacet + facet normal 0.650912 -0.645224 -0.399999 + outer loop + vertex -848.719 262.563 271.865 + vertex -847.817 264.534 270.155 + vertex -847.592 263.706 271.856 + endloop + endfacet + facet normal 0.779387 -0.51665 -0.354441 + outer loop + vertex -847.817 264.534 270.155 + vertex -846.718 266.167 270.19 + vertex -847.592 263.706 271.856 + endloop + endfacet + facet normal 0.7565 -0.528944 -0.384611 + outer loop + vertex -847.592 263.706 271.856 + vertex -846.718 266.167 270.19 + vertex -846.632 264.968 272.007 + endloop + endfacet + facet normal 0.853229 -0.415969 -0.314596 + outer loop + vertex -846.632 264.968 272.007 + vertex -846.718 266.167 270.19 + vertex -845.461 268.101 271.042 + endloop + endfacet + facet normal 0.849708 -0.423126 -0.314582 + outer loop + vertex -847.09 266.591 268.615 + vertex -845.922 269.669 267.63 + vertex -846.718 266.167 270.19 + endloop + endfacet + facet normal 0.853967 -0.419329 -0.308063 + outer loop + vertex -845.922 269.669 267.63 + vertex -845.461 268.101 271.042 + vertex -846.718 266.167 270.19 + endloop + endfacet + facet normal 0.887446 -0.409804 -0.210952 + outer loop + vertex -847.781 269.618 261.409 + vertex -847.768 270.699 259.363 + vertex -846.635 272.619 260.402 + endloop + endfacet + facet normal 0.886599 -0.411194 -0.211806 + outer loop + vertex -848.041 271.036 257.566 + vertex -846.906 273.972 256.62 + vertex -847.768 270.699 259.363 + endloop + endfacet + facet normal 0.88744 -0.410153 -0.210299 + outer loop + vertex -846.906 273.972 256.62 + vertex -846.635 272.619 260.402 + vertex -847.768 270.699 259.363 + endloop + endfacet + facet normal 0.816215 -0.525879 -0.239258 + outer loop + vertex -848.906 269.806 257.321 + vertex -848.041 271.036 257.566 + vertex -848.791 269.109 259.244 + endloop + endfacet + facet normal 0.827489 -0.515567 -0.222378 + outer loop + vertex -848.791 269.109 259.244 + vertex -848.041 271.036 257.566 + vertex -847.768 270.699 259.363 + endloop + endfacet + facet normal 0.716073 -0.643469 -0.270532 + outer loop + vertex -849.93 268.69 257.266 + vertex -848.906 269.806 257.321 + vertex -849.827 267.993 259.193 + endloop + endfacet + facet normal 0.710351 -0.647106 -0.276868 + outer loop + vertex -849.827 267.993 259.193 + vertex -848.906 269.806 257.321 + vertex -848.791 269.109 259.244 + endloop + endfacet + facet normal 0.709029 -0.645564 -0.283768 + outer loop + vertex -849.827 267.993 259.193 + vertex -848.791 269.109 259.244 + vertex -849.715 267.264 261.133 + endloop + endfacet + facet normal 0.703676 -0.648833 -0.289578 + outer loop + vertex -849.715 267.264 261.133 + vertex -848.791 269.109 259.244 + vertex -848.667 268.38 261.179 + endloop + endfacet + facet normal 0.823576 -0.511319 -0.245512 + outer loop + vertex -848.791 269.109 259.244 + vertex -847.768 270.699 259.363 + vertex -848.667 268.38 261.179 + endloop + endfacet + facet normal 0.805715 -0.52575 -0.272782 + outer loop + vertex -848.667 268.38 261.179 + vertex -847.768 270.699 259.363 + vertex -847.781 269.618 261.409 + endloop + endfacet + facet normal 0.806298 -0.526907 -0.268799 + outer loop + vertex -848.667 268.38 261.179 + vertex -847.781 269.618 261.409 + vertex -848.526 267.626 263.081 + endloop + endfacet + facet normal 0.815965 -0.518864 -0.254914 + outer loop + vertex -848.526 267.626 263.081 + vertex -847.781 269.618 261.409 + vertex -847.478 269.236 263.157 + endloop + endfacet + facet normal 0.701409 -0.646255 -0.300634 + outer loop + vertex -849.715 267.264 261.133 + vertex -848.667 268.38 261.179 + vertex -849.589 266.512 263.044 + endloop + endfacet + facet normal 0.69295 -0.651098 -0.309664 + outer loop + vertex -849.589 266.512 263.044 + vertex -848.667 268.38 261.179 + vertex -848.526 267.626 263.081 + endloop + endfacet + facet normal 0.690616 -0.64853 -0.320091 + outer loop + vertex -849.589 266.512 263.044 + vertex -848.526 267.626 263.081 + vertex -849.447 265.747 264.899 + endloop + endfacet + facet normal 0.688945 -0.649428 -0.321866 + outer loop + vertex -849.447 265.747 264.899 + vertex -848.526 267.626 263.081 + vertex -848.373 266.871 264.93 + endloop + endfacet + facet normal 0.81133 -0.514801 -0.276991 + outer loop + vertex -848.526 267.626 263.081 + vertex -847.478 269.236 263.157 + vertex -848.373 266.871 264.93 + endloop + endfacet + facet normal 0.789386 -0.530474 -0.308978 + outer loop + vertex -848.373 266.871 264.93 + vertex -847.478 269.236 263.157 + vertex -847.463 268.115 265.12 + endloop + endfacet + facet normal 0.877736 -0.413166 -0.242638 + outer loop + vertex -847.463 268.115 265.12 + vertex -847.478 269.236 263.157 + vertex -846.308 271.17 264.097 + endloop + endfacet + facet normal 0.876197 -0.41624 -0.242946 + outer loop + vertex -847.781 269.618 261.409 + vertex -846.635 272.619 260.402 + vertex -847.478 269.236 263.157 + endloop + endfacet + facet normal 0.877824 -0.414405 -0.240195 + outer loop + vertex -846.635 272.619 260.402 + vertex -846.308 271.17 264.097 + vertex -847.478 269.236 263.157 + endloop + endfacet + facet normal 0.902147 -0.402353 -0.155701 + outer loop + vertex -848.255 272.295 253.823 + vertex -848.177 273.224 251.872 + vertex -847.12 275.204 252.884 + endloop + endfacet + facet normal 0.902621 -0.401043 -0.15633 + outer loop + vertex -848.367 273.479 250.123 + vertex -847.227 276.415 249.171 + vertex -848.177 273.224 251.872 + endloop + endfacet + facet normal 0.902212 -0.401634 -0.157173 + outer loop + vertex -847.227 276.415 249.171 + vertex -847.12 275.204 252.884 + vertex -848.177 273.224 251.872 + endloop + endfacet + facet normal 0.837853 -0.515646 -0.179197 + outer loop + vertex -849.185 272.245 249.847 + vertex -848.367 273.479 250.123 + vertex -849.155 271.629 251.764 + endloop + endfacet + facet normal 0.845834 -0.507065 -0.165681 + outer loop + vertex -849.155 271.629 251.764 + vertex -848.367 273.479 250.123 + vertex -848.177 273.224 251.872 + endloop + endfacet + facet normal 0.741295 -0.637749 -0.209184 + outer loop + vertex -850.175 271.113 249.793 + vertex -849.185 272.245 249.847 + vertex -850.139 270.53 251.695 + endloop + endfacet + facet normal 0.733421 -0.643631 -0.218709 + outer loop + vertex -850.139 270.53 251.695 + vertex -849.185 272.245 249.847 + vertex -849.155 271.629 251.764 + endloop + endfacet + facet normal 0.73263 -0.642563 -0.224423 + outer loop + vertex -850.139 270.53 251.695 + vertex -849.155 271.629 251.764 + vertex -850.092 269.94 253.537 + endloop + endfacet + facet normal 0.728012 -0.645838 -0.229983 + outer loop + vertex -850.092 269.94 253.537 + vertex -849.155 271.629 251.764 + vertex -849.095 271.046 253.592 + endloop + endfacet + facet normal 0.843013 -0.503791 -0.188475 + outer loop + vertex -849.155 271.629 251.764 + vertex -848.177 273.224 251.872 + vertex -849.095 271.046 253.592 + endloop + endfacet + facet normal 0.828712 -0.517415 -0.21335 + outer loop + vertex -849.095 271.046 253.592 + vertex -848.177 273.224 251.872 + vertex -848.255 272.295 253.823 + endloop + endfacet + facet normal 0.829311 -0.51896 -0.20718 + outer loop + vertex -849.095 271.046 253.592 + vertex -848.255 272.295 253.823 + vertex -849.008 270.448 255.433 + endloop + endfacet + facet normal 0.836101 -0.512249 -0.196304 + outer loop + vertex -849.008 270.448 255.433 + vertex -848.255 272.295 253.823 + vertex -848.006 272.037 255.555 + endloop + endfacet + facet normal 0.726412 -0.643878 -0.240305 + outer loop + vertex -850.092 269.94 253.537 + vertex -849.095 271.046 253.592 + vertex -850.02 269.335 255.379 + endloop + endfacet + facet normal 0.723852 -0.645631 -0.243308 + outer loop + vertex -850.02 269.335 255.379 + vertex -849.095 271.046 253.592 + vertex -849.008 270.448 255.433 + endloop + endfacet + facet normal 0.722001 -0.643407 -0.254445 + outer loop + vertex -850.02 269.335 255.379 + vertex -849.008 270.448 255.433 + vertex -849.93 268.69 257.266 + endloop + endfacet + facet normal 0.718154 -0.645959 -0.258829 + outer loop + vertex -849.93 268.69 257.266 + vertex -849.008 270.448 255.433 + vertex -848.906 269.806 257.321 + endloop + endfacet + facet normal 0.832909 -0.508549 -0.218265 + outer loop + vertex -849.008 270.448 255.433 + vertex -848.006 272.037 255.555 + vertex -848.906 269.806 257.321 + endloop + endfacet + facet normal 0.815368 -0.523838 -0.246514 + outer loop + vertex -848.906 269.806 257.321 + vertex -848.006 272.037 255.555 + vertex -848.041 271.036 257.566 + endloop + endfacet + facet normal 0.894564 -0.40614 -0.186563 + outer loop + vertex -848.041 271.036 257.566 + vertex -848.006 272.037 255.555 + vertex -846.906 273.972 256.62 + endloop + endfacet + facet normal 0.892561 -0.409384 -0.189049 + outer loop + vertex -848.255 272.295 253.823 + vertex -847.12 275.204 252.884 + vertex -848.006 272.037 255.555 + endloop + endfacet + facet normal 0.894523 -0.406795 -0.18533 + outer loop + vertex -847.12 275.204 252.884 + vertex -846.906 273.972 256.62 + vertex -848.006 272.037 255.555 + endloop + endfacet + facet normal 0.887793 -0.427004 -0.171729 + outer loop + vertex -848.944 275.244 242.057 + vertex -847.273 278.73 242.028 + vertex -848.329 275.282 245.142 + endloop + endfacet + facet normal 0.909269 -0.395524 -0.129577 + outer loop + vertex -848.329 275.282 245.142 + vertex -847.273 278.73 242.028 + vertex -847.13 277.929 245.478 + endloop + endfacet + facet normal 0.733407 -0.649984 -0.199084 + outer loop + vertex -850.451 271.853 246.429 + vertex -850.221 272.701 244.509 + vertex -849.51 273.165 245.611 + endloop + endfacet + facet normal 0.845976 -0.507886 -0.162409 + outer loop + vertex -848.329 275.282 245.142 + vertex -849.51 273.165 245.611 + vertex -848.944 275.244 242.057 + endloop + endfacet + facet normal 0.800147 -0.572899 -0.177627 + outer loop + vertex -850.289 273.163 242.708 + vertex -848.944 275.244 242.057 + vertex -850.221 272.701 244.509 + endloop + endfacet + facet normal 0.759503 -0.606928 -0.234082 + outer loop + vertex -849.51 273.165 245.611 + vertex -850.221 272.701 244.509 + vertex -848.944 275.244 242.057 + endloop + endfacet + facet normal 0.841919 -0.509203 -0.178561 + outer loop + vertex -849.51 273.165 245.611 + vertex -848.329 275.282 245.142 + vertex -849.234 272.883 247.715 + endloop + endfacet + facet normal 0.851904 -0.497355 -0.164006 + outer loop + vertex -849.234 272.883 247.715 + vertex -848.329 275.282 245.142 + vertex -848.21 274.566 247.93 + endloop + endfacet + facet normal 0.729571 -0.651941 -0.206636 + outer loop + vertex -850.451 271.853 246.429 + vertex -849.51 273.165 245.611 + vertex -850.262 271.598 247.903 + endloop + endfacet + facet normal 0.754697 -0.629936 -0.183338 + outer loop + vertex -850.262 271.598 247.903 + vertex -849.51 273.165 245.611 + vertex -849.234 272.883 247.715 + endloop + endfacet + facet normal 0.751854 -0.629515 -0.196027 + outer loop + vertex -850.262 271.598 247.903 + vertex -849.234 272.883 247.715 + vertex -850.175 271.113 249.793 + endloop + endfacet + facet normal 0.741468 -0.63796 -0.207923 + outer loop + vertex -850.175 271.113 249.793 + vertex -849.234 272.883 247.715 + vertex -849.185 272.245 249.847 + endloop + endfacet + facet normal 0.851536 -0.496605 -0.168136 + outer loop + vertex -849.234 272.883 247.715 + vertex -848.21 274.566 247.93 + vertex -849.185 272.245 249.847 + endloop + endfacet + facet normal 0.836958 -0.511765 -0.1939 + outer loop + vertex -849.185 272.245 249.847 + vertex -848.21 274.566 247.93 + vertex -848.367 273.479 250.123 + endloop + endfacet + facet normal 0.90912 -0.395372 -0.131078 + outer loop + vertex -848.367 273.479 250.123 + vertex -848.21 274.566 247.93 + vertex -847.227 276.415 249.171 + endloop + endfacet + facet normal 0.90847 -0.393856 -0.139855 + outer loop + vertex -848.329 275.282 245.142 + vertex -847.13 277.929 245.478 + vertex -848.21 274.566 247.93 + endloop + endfacet + facet normal 0.909773 -0.39196 -0.136679 + outer loop + vertex -847.13 277.929 245.478 + vertex -847.227 276.415 249.171 + vertex -848.21 274.566 247.93 + endloop + endfacet + facet normal 0.905591 -0.415617 -0.0846553 + outer loop + vertex -848.884 277.341 233.853 + vertex -847.421 280.437 234.308 + vertex -848.956 276.387 237.771 + endloop + endfacet + facet normal 0.899233 -0.425983 -0.099593 + outer loop + vertex -848.956 276.387 237.771 + vertex -847.421 280.437 234.308 + vertex -847.415 279.519 238.292 + endloop + endfacet + facet normal 0.826714 -0.55053 -0.116022 + outer loop + vertex -850.283 274.19 238.742 + vertex -850.093 274.908 236.689 + vertex -848.956 276.387 237.771 + endloop + endfacet + facet normal 0.825973 -0.550679 -0.120502 + outer loop + vertex -850.223 275.112 234.863 + vertex -848.884 277.341 233.853 + vertex -850.093 274.908 236.689 + endloop + endfacet + facet normal 0.827298 -0.549104 -0.118585 + outer loop + vertex -848.884 277.341 233.853 + vertex -848.956 276.387 237.771 + vertex -850.093 274.908 236.689 + endloop + endfacet + facet normal 0.809979 -0.568602 -0.143618 + outer loop + vertex -850.289 273.163 242.708 + vertex -850.103 273.957 240.617 + vertex -848.944 275.244 242.057 + endloop + endfacet + facet normal 0.816391 -0.558295 -0.147691 + outer loop + vertex -850.283 274.19 238.742 + vertex -848.956 276.387 237.771 + vertex -850.103 273.957 240.617 + endloop + endfacet + facet normal 0.813092 -0.561912 -0.152109 + outer loop + vertex -848.956 276.387 237.771 + vertex -848.944 275.244 242.057 + vertex -850.103 273.957 240.617 + endloop + endfacet + facet normal 0.898712 -0.423107 -0.115314 + outer loop + vertex -848.956 276.387 237.771 + vertex -847.415 279.519 238.292 + vertex -848.944 275.244 242.057 + endloop + endfacet + facet normal 0.894307 -0.429744 -0.12464 + outer loop + vertex -848.944 275.244 242.057 + vertex -847.415 279.519 238.292 + vertex -847.273 278.73 242.028 + endloop + endfacet + facet normal 0.885207 -0.452695 -0.107124 + outer loop + vertex -848.7 279.119 226.848 + vertex -847.563 281.182 227.522 + vertex -848.653 278.416 230.204 + endloop + endfacet + facet normal 0.909864 -0.41132 -0.054435 + outer loop + vertex -848.653 278.416 230.204 + vertex -847.563 281.182 227.522 + vertex -847.42 281.109 230.463 + endloop + endfacet + facet normal 0.788738 -0.590552 -0.170704 + outer loop + vertex -850.654 276.549 226.71 + vertex -848.7 279.119 226.848 + vertex -850.012 276.502 229.836 + endloop + endfacet + facet normal 0.820059 -0.557732 -0.128215 + outer loop + vertex -850.012 276.502 229.836 + vertex -848.7 279.119 226.848 + vertex -848.653 278.416 230.204 + endloop + endfacet + facet normal 0.831606 -0.545849 -0.102374 + outer loop + vertex -850.223 275.112 234.863 + vertex -849.957 275.937 232.631 + vertex -848.884 277.341 233.853 + endloop + endfacet + facet normal 0.820042 -0.557546 -0.129123 + outer loop + vertex -850.012 276.502 229.836 + vertex -848.653 278.416 230.204 + vertex -849.957 275.937 232.631 + endloop + endfacet + facet normal 0.833004 -0.542801 -0.107106 + outer loop + vertex -848.653 278.416 230.204 + vertex -848.884 277.341 233.853 + vertex -849.957 275.937 232.631 + endloop + endfacet + facet normal 0.909709 -0.410399 -0.0632574 + outer loop + vertex -848.653 278.416 230.204 + vertex -847.42 281.109 230.463 + vertex -848.884 277.341 233.853 + endloop + endfacet + facet normal 0.905781 -0.417449 -0.0727886 + outer loop + vertex -848.884 277.341 233.853 + vertex -847.42 281.109 230.463 + vertex -847.421 280.437 234.308 + endloop + endfacet + facet normal 0.906199 -0.417746 -0.0655091 + outer loop + vertex -848.687 280.623 219.129 + vertex -847.347 283.368 220.157 + vertex -848.75 279.86 223.124 + endloop + endfacet + facet normal 0.900147 -0.42807 -0.0805746 + outer loop + vertex -848.75 279.86 223.124 + vertex -847.347 283.368 220.157 + vertex -847.27 282.845 223.8 + endloop + endfacet + facet normal 0.822984 -0.562629 -0.0784005 + outer loop + vertex -850.535 278.017 218.428 + vertex -848.687 280.623 219.129 + vertex -850.585 277.391 222.401 + endloop + endfacet + facet normal 0.812228 -0.575208 -0.0970616 + outer loop + vertex -850.585 277.391 222.401 + vertex -848.687 280.623 219.129 + vertex -848.75 279.86 223.124 + endloop + endfacet + facet normal 0.812354 -0.574653 -0.0992729 + outer loop + vertex -850.585 277.391 222.401 + vertex -848.75 279.86 223.124 + vertex -850.654 276.549 226.71 + endloop + endfacet + facet normal 0.79268 -0.595784 -0.129228 + outer loop + vertex -850.654 276.549 226.71 + vertex -848.75 279.86 223.124 + vertex -848.7 279.119 226.848 + endloop + endfacet + facet normal 0.900262 -0.424504 -0.096568 + outer loop + vertex -848.75 279.86 223.124 + vertex -847.27 282.845 223.8 + vertex -848.7 279.119 226.848 + endloop + endfacet + facet normal 0.885765 -0.445747 -0.129342 + outer loop + vertex -848.7 279.119 226.848 + vertex -847.27 282.845 223.8 + vertex -847.563 281.182 227.522 + endloop + endfacet + facet normal 0.912336 -0.406645 -0.0477752 + outer loop + vertex -848.616 281.755 211.188 + vertex -847.247 284.727 212.031 + vertex -848.642 281.232 215.143 + endloop + endfacet + facet normal 0.917713 -0.39585 -0.0332392 + outer loop + vertex -848.642 281.232 215.143 + vertex -847.247 284.727 212.031 + vertex -847.059 284.837 215.911 + endloop + endfacet + facet normal 0.833546 -0.549188 -0.0599397 + outer loop + vertex -850.444 279.049 210.551 + vertex -848.616 281.755 211.188 + vertex -850.484 278.558 214.491 + endloop + endfacet + facet normal 0.829142 -0.554892 -0.0679517 + outer loop + vertex -850.484 278.558 214.491 + vertex -848.616 281.755 211.188 + vertex -848.642 281.232 215.143 + endloop + endfacet + facet normal 0.829013 -0.555362 -0.0656601 + outer loop + vertex -850.484 278.558 214.491 + vertex -848.642 281.232 215.143 + vertex -850.535 278.017 218.428 + endloop + endfacet + facet normal 0.82288 -0.563017 -0.0766838 + outer loop + vertex -850.535 278.017 218.428 + vertex -848.642 281.232 215.143 + vertex -848.687 280.623 219.129 + endloop + endfacet + facet normal 0.918353 -0.39264 -0.0496064 + outer loop + vertex -848.642 281.232 215.143 + vertex -847.059 284.837 215.911 + vertex -848.687 280.623 219.129 + endloop + endfacet + facet normal 0.907356 -0.41246 -0.0811289 + outer loop + vertex -848.687 280.623 219.129 + vertex -847.059 284.837 215.911 + vertex -847.347 283.368 220.157 + endloop + endfacet + facet normal 0.914595 -0.402435 -0.0395311 + outer loop + vertex -848.582 282.626 203.333 + vertex -847.22 285.645 204.117 + vertex -848.596 282.21 207.265 + endloop + endfacet + facet normal 0.921893 -0.386956 -0.0194503 + outer loop + vertex -848.596 282.21 207.265 + vertex -847.22 285.645 204.117 + vertex -847.019 285.938 207.825 + endloop + endfacet + facet normal 0.836031 -0.546307 -0.0509969 + outer loop + vertex -850.386 279.929 202.659 + vertex -848.582 282.626 203.333 + vertex -850.415 279.516 206.614 + endloop + endfacet + facet normal 0.833635 -0.549531 -0.055392 + outer loop + vertex -850.415 279.516 206.614 + vertex -848.582 282.626 203.333 + vertex -848.596 282.21 207.265 + endloop + endfacet + facet normal 0.833847 -0.548859 -0.0587681 + outer loop + vertex -850.415 279.516 206.614 + vertex -848.596 282.21 207.265 + vertex -850.444 279.049 210.551 + endloop + endfacet + facet normal 0.833514 -0.549298 -0.0593782 + outer loop + vertex -850.444 279.049 210.551 + vertex -848.596 282.21 207.265 + vertex -848.616 281.755 211.188 + endloop + endfacet + facet normal 0.922423 -0.384128 -0.039775 + outer loop + vertex -848.596 282.21 207.265 + vertex -847.019 285.938 207.825 + vertex -848.616 281.755 211.188 + endloop + endfacet + facet normal 0.913301 -0.401873 -0.0661761 + outer loop + vertex -848.616 281.755 211.188 + vertex -847.019 285.938 207.825 + vertex -847.247 284.727 212.031 + endloop + endfacet + facet normal 0.917713 -0.396137 -0.0296199 + outer loop + vertex -848.557 283.323 195.386 + vertex -847.216 286.37 196.193 + vertex -848.569 282.999 199.374 + endloop + endfacet + facet normal 0.923666 -0.382974 -0.0131343 + outer loop + vertex -848.569 282.999 199.374 + vertex -847.216 286.37 196.193 + vertex -847.005 286.752 199.919 + endloop + endfacet + facet normal 0.841763 -0.538598 -0.0366969 + outer loop + vertex -850.334 280.593 194.69 + vertex -848.557 283.323 195.386 + vertex -850.359 280.283 198.68 + endloop + endfacet + facet normal 0.839043 -0.542461 -0.04175 + outer loop + vertex -850.359 280.283 198.68 + vertex -848.557 283.323 195.386 + vertex -848.569 282.999 199.374 + endloop + endfacet + facet normal 0.839104 -0.542307 -0.0425117 + outer loop + vertex -850.359 280.283 198.68 + vertex -848.569 282.999 199.374 + vertex -850.386 279.929 202.659 + endloop + endfacet + facet normal 0.835852 -0.546807 -0.0485142 + outer loop + vertex -850.386 279.929 202.659 + vertex -848.569 282.999 199.374 + vertex -848.582 282.626 203.333 + endloop + endfacet + facet normal 0.92425 -0.380396 -0.0325608 + outer loop + vertex -848.569 282.999 199.374 + vertex -847.005 286.752 199.919 + vertex -848.582 282.626 203.333 + endloop + endfacet + facet normal 0.915524 -0.398068 -0.0579477 + outer loop + vertex -848.582 282.626 203.333 + vertex -847.005 286.752 199.919 + vertex -847.22 285.645 204.117 + endloop + endfacet + facet normal 0.919147 -0.393541 -0.0171568 + outer loop + vertex -848.531 283.812 187.37 + vertex -847.203 286.879 188.191 + vertex -848.547 283.6 191.382 + endloop + endfacet + facet normal 0.924934 -0.380127 -0.000935952 + outer loop + vertex -848.547 283.6 191.382 + vertex -847.203 286.879 188.191 + vertex -846.999 287.365 191.949 + endloop + endfacet + facet normal 0.844034 -0.535805 -0.0228156 + outer loop + vertex -850.293 281.067 186.683 + vertex -848.531 283.812 187.37 + vertex -850.312 280.865 190.693 + endloop + endfacet + facet normal 0.842819 -0.537613 -0.0250708 + outer loop + vertex -850.312 280.865 190.693 + vertex -848.531 283.812 187.37 + vertex -848.547 283.6 191.382 + endloop + endfacet + facet normal 0.843426 -0.536301 -0.0318322 + outer loop + vertex -850.312 280.865 190.693 + vertex -848.547 283.6 191.382 + vertex -850.334 280.593 194.69 + endloop + endfacet + facet normal 0.841633 -0.538904 -0.0351659 + outer loop + vertex -850.334 280.593 194.69 + vertex -848.547 283.6 191.382 + vertex -848.557 283.323 195.386 + endloop + endfacet + facet normal 0.925877 -0.377076 -0.0237739 + outer loop + vertex -848.547 283.6 191.382 + vertex -846.999 287.365 191.949 + vertex -848.557 283.323 195.386 + endloop + endfacet + facet normal 0.918666 -0.392451 -0.0451191 + outer loop + vertex -848.557 283.323 195.386 + vertex -846.999 287.365 191.949 + vertex -847.216 286.37 196.193 + endloop + endfacet + facet normal 0.921012 -0.389439 -0.00864193 + outer loop + vertex -848.516 284.103 179.37 + vertex -847.201 287.195 180.188 + vertex -848.526 283.99 183.361 + endloop + endfacet + facet normal 0.925859 -0.377836 0.00510241 + outer loop + vertex -848.526 283.99 183.361 + vertex -847.201 287.195 180.188 + vertex -846.989 287.766 183.941 + endloop + endfacet + facet normal 0.846062 -0.532938 -0.0125179 + outer loop + vertex -850.266 281.342 178.698 + vertex -848.516 284.103 179.37 + vertex -850.276 281.231 182.683 + endloop + endfacet + facet normal 0.845854 -0.533259 -0.0129065 + outer loop + vertex -850.276 281.231 182.683 + vertex -848.516 284.103 179.37 + vertex -848.526 283.99 183.361 + endloop + endfacet + facet normal 0.846388 -0.53225 -0.0183837 + outer loop + vertex -850.276 281.231 182.683 + vertex -848.526 283.99 183.361 + vertex -850.293 281.067 186.683 + endloop + endfacet + facet normal 0.84403 -0.535813 -0.0227735 + outer loop + vertex -850.293 281.067 186.683 + vertex -848.526 283.99 183.361 + vertex -848.531 283.812 187.37 + endloop + endfacet + facet normal 0.926863 -0.375079 -0.0155122 + outer loop + vertex -848.526 283.99 183.361 + vertex -846.989 287.766 183.941 + vertex -848.531 283.812 187.37 + endloop + endfacet + facet normal 0.920426 -0.389358 -0.0348715 + outer loop + vertex -848.531 283.812 187.37 + vertex -846.989 287.766 183.941 + vertex -847.203 286.879 188.191 + endloop + endfacet + facet normal 0.920984 -0.389601 -0.000137578 + outer loop + vertex -848.509 284.188 171.47 + vertex -847.193 287.297 172.279 + vertex -848.514 284.175 175.402 + endloop + endfacet + facet normal 0.92663 -0.375625 0.0162245 + outer loop + vertex -848.514 284.175 175.402 + vertex -847.193 287.297 172.279 + vertex -846.986 287.969 175.982 + endloop + endfacet + facet normal 0.846791 -0.531923 -0.00161968 + outer loop + vertex -850.256 281.408 170.782 + vertex -848.509 284.188 171.47 + vertex -850.259 281.392 174.722 + endloop + endfacet + facet normal 0.84728 -0.531146 -0.000688223 + outer loop + vertex -850.259 281.392 174.722 + vertex -848.509 284.188 171.47 + vertex -848.514 284.175 175.402 + endloop + endfacet + facet normal 0.847774 -0.530331 -0.00529589 + outer loop + vertex -850.259 281.392 174.722 + vertex -848.514 284.175 175.402 + vertex -850.266 281.342 178.698 + endloop + endfacet + facet normal 0.845723 -0.533543 -0.00914656 + outer loop + vertex -850.266 281.342 178.698 + vertex -848.514 284.175 175.402 + vertex -848.516 284.103 179.37 + endloop + endfacet + facet normal 0.927924 -0.372717 -0.00620282 + outer loop + vertex -848.514 284.175 175.402 + vertex -846.986 287.969 175.982 + vertex -848.516 284.103 179.37 + endloop + endfacet + facet normal 0.922222 -0.385925 -0.0238527 + outer loop + vertex -848.516 284.103 179.37 + vertex -846.986 287.969 175.982 + vertex -847.201 287.195 180.188 + endloop + endfacet + facet normal 0.921307 -0.388737 0.00875648 + outer loop + vertex -848.511 284.076 163.736 + vertex -847.196 287.208 164.515 + vertex -848.511 284.161 167.586 + endloop + endfacet + facet normal 0.926589 -0.375286 0.0243671 + outer loop + vertex -848.511 284.161 167.586 + vertex -847.196 287.208 164.515 + vertex -846.984 287.969 168.147 + endloop + endfacet + facet normal 0.846453 -0.532353 0.0108138 + outer loop + vertex -850.26 281.281 163.089 + vertex -848.511 284.076 163.736 + vertex -850.258 281.361 166.912 + endloop + endfacet + facet normal 0.847014 -0.531437 0.0119055 + outer loop + vertex -850.258 281.361 166.912 + vertex -848.511 284.076 163.736 + vertex -848.511 284.161 167.586 + endloop + endfacet + facet normal 0.847704 -0.530435 0.00595484 + outer loop + vertex -850.258 281.361 166.912 + vertex -848.511 284.161 167.586 + vertex -850.256 281.408 170.782 + endloop + endfacet + facet normal 0.846255 -0.532768 0.00315424 + outer loop + vertex -850.256 281.408 170.782 + vertex -848.511 284.161 167.586 + vertex -848.509 284.188 171.47 + endloop + endfacet + facet normal 0.928006 -0.37256 0.00201023 + outer loop + vertex -848.511 284.161 167.586 + vertex -846.984 287.969 168.147 + vertex -848.509 284.188 171.47 + endloop + endfacet + facet normal 0.922337 -0.386057 -0.0159538 + outer loop + vertex -848.509 284.188 171.47 + vertex -846.984 287.969 168.147 + vertex -847.193 287.297 172.279 + endloop + endfacet + facet normal 0.919151 -0.393532 0.0171624 + outer loop + vertex -848.52 283.771 155.99 + vertex -847.191 286.91 156.776 + vertex -848.516 283.951 159.883 + endloop + endfacet + facet normal 0.925769 -0.376336 0.0363661 + outer loop + vertex -848.516 283.951 159.883 + vertex -847.191 286.91 156.776 + vertex -846.983 287.772 160.415 + endloop + endfacet + facet normal 0.845571 -0.533325 0.023954 + outer loop + vertex -850.276 280.957 155.325 + vertex -848.52 283.771 155.99 + vertex -850.267 281.147 159.237 + endloop + endfacet + facet normal 0.845428 -0.533564 0.023684 + outer loop + vertex -850.267 281.147 159.237 + vertex -848.52 283.771 155.99 + vertex -848.516 283.951 159.883 + endloop + endfacet + facet normal 0.846249 -0.532519 0.016926 + outer loop + vertex -850.267 281.147 159.237 + vertex -848.516 283.951 159.883 + vertex -850.26 281.281 163.089 + endloop + endfacet + facet normal 0.845836 -0.533199 0.0161344 + outer loop + vertex -850.26 281.281 163.089 + vertex -848.516 283.951 159.883 + vertex -848.511 284.076 163.736 + endloop + endfacet + facet normal 0.927566 -0.373503 0.010835 + outer loop + vertex -848.516 283.951 159.883 + vertex -846.983 287.772 160.415 + vertex -848.511 284.076 163.736 + endloop + endfacet + facet normal 0.922566 -0.385806 -0.005155 + outer loop + vertex -848.511 284.076 163.736 + vertex -846.983 287.772 160.415 + vertex -847.196 287.208 164.515 + endloop + endfacet + facet normal 0.919405 -0.392329 0.0278034 + outer loop + vertex -848.526 283.26 148.102 + vertex -847.196 286.435 148.913 + vertex -848.524 283.544 152.056 + endloop + endfacet + facet normal 0.924853 -0.377836 0.043435 + outer loop + vertex -848.524 283.544 152.056 + vertex -847.196 286.435 148.913 + vertex -846.983 287.381 152.613 + endloop + endfacet + facet normal 0.84259 -0.537264 0.0372826 + outer loop + vertex -850.299 280.431 147.411 + vertex -848.526 283.26 148.102 + vertex -850.287 280.725 151.373 + endloop + endfacet + facet normal 0.843071 -0.536445 0.0381764 + outer loop + vertex -850.287 280.725 151.373 + vertex -848.526 283.26 148.102 + vertex -848.524 283.544 152.056 + endloop + endfacet + facet normal 0.844329 -0.535034 0.0291029 + outer loop + vertex -850.287 280.725 151.373 + vertex -848.524 283.544 152.056 + vertex -850.276 280.957 155.325 + endloop + endfacet + facet normal 0.84479 -0.534258 0.0299645 + outer loop + vertex -850.276 280.957 155.325 + vertex -848.524 283.544 152.056 + vertex -848.52 283.771 155.99 + endloop + endfacet + facet normal 0.926683 -0.375273 0.0206908 + outer loop + vertex -848.524 283.544 152.056 + vertex -846.983 287.381 152.613 + vertex -848.52 283.771 155.99 + endloop + endfacet + facet normal 0.92067 -0.390337 0.00185268 + outer loop + vertex -848.52 283.771 155.99 + vertex -846.983 287.381 152.613 + vertex -847.191 286.91 156.776 + endloop + endfacet + facet normal 0.917186 -0.396903 0.0351846 + outer loop + vertex -848.543 282.57 140.176 + vertex -847.196 285.755 140.991 + vertex -848.534 282.942 144.144 + endloop + endfacet + facet normal 0.923751 -0.379202 0.0537637 + outer loop + vertex -848.534 282.942 144.144 + vertex -847.196 285.755 140.991 + vertex -846.984 286.797 144.711 + endloop + endfacet + facet normal 0.839428 -0.541429 0.0470642 + outer loop + vertex -850.339 279.723 139.476 + vertex -848.543 282.57 140.176 + vertex -850.319 280.1 143.451 + endloop + endfacet + facet normal 0.840366 -0.53982 0.0487869 + outer loop + vertex -850.319 280.1 143.451 + vertex -848.543 282.57 140.176 + vertex -848.534 282.942 144.144 + endloop + endfacet + facet normal 0.841563 -0.538618 0.0407753 + outer loop + vertex -850.319 280.1 143.451 + vertex -848.534 282.942 144.144 + vertex -850.299 280.431 147.411 + endloop + endfacet + facet normal 0.841974 -0.537917 0.0415362 + outer loop + vertex -850.299 280.431 147.411 + vertex -848.534 282.942 144.144 + vertex -848.526 283.26 148.102 + endloop + endfacet + facet normal 0.926029 -0.376384 0.0283983 + outer loop + vertex -848.534 282.942 144.144 + vertex -846.984 286.797 144.711 + vertex -848.526 283.26 148.102 + endloop + endfacet + facet normal 0.921069 -0.38919 0.0127899 + outer loop + vertex -848.526 283.26 148.102 + vertex -846.984 286.797 144.711 + vertex -847.196 286.435 148.913 + endloop + endfacet + facet normal 0.914473 -0.402112 0.045222 + outer loop + vertex -848.585 281.628 132.202 + vertex -847.222 284.818 133 + vertex -848.558 282.138 136.193 + endloop + endfacet + facet normal 0.921143 -0.384065 0.0631612 + outer loop + vertex -848.558 282.138 136.193 + vertex -847.222 284.818 133 + vertex -846.992 285.987 136.756 + endloop + endfacet + facet normal 0.833899 -0.548474 0.061551 + outer loop + vertex -850.399 278.793 131.52 + vertex -848.585 281.628 132.202 + vertex -850.367 279.288 135.482 + endloop + endfacet + facet normal 0.835352 -0.545961 0.0641331 + outer loop + vertex -850.367 279.288 135.482 + vertex -848.585 281.628 132.202 + vertex -848.558 282.138 136.193 + endloop + endfacet + facet normal 0.837076 -0.544448 0.0536759 + outer loop + vertex -850.367 279.288 135.482 + vertex -848.558 282.138 136.193 + vertex -850.339 279.723 139.476 + endloop + endfacet + facet normal 0.838103 -0.542677 0.0555355 + outer loop + vertex -850.339 279.723 139.476 + vertex -848.558 282.138 136.193 + vertex -848.543 282.57 140.176 + endloop + endfacet + facet normal 0.923656 -0.381363 0.0377144 + outer loop + vertex -848.558 282.138 136.193 + vertex -846.992 285.987 136.756 + vertex -848.543 282.57 140.176 + endloop + endfacet + facet normal 0.918703 -0.394307 0.0225341 + outer loop + vertex -848.543 282.57 140.176 + vertex -846.992 285.987 136.756 + vertex -847.196 285.755 140.991 + endloop + endfacet + facet normal 0.909364 -0.411183 0.0631244 + outer loop + vertex -848.662 280.341 124.355 + vertex -847.288 283.483 125.027 + vertex -848.622 281.028 128.248 + endloop + endfacet + facet normal 0.916956 -0.390457 0.0820653 + outer loop + vertex -848.622 281.028 128.248 + vertex -847.288 283.483 125.027 + vertex -847.035 284.85 128.706 + endloop + endfacet + facet normal 0.8193 -0.568037 0.0779804 + outer loop + vertex -850.481 277.635 123.747 + vertex -848.662 280.341 124.355 + vertex -850.437 278.23 127.625 + endloop + endfacet + facet normal 0.826336 -0.55601 0.0895639 + outer loop + vertex -850.437 278.23 127.625 + vertex -848.662 280.341 124.355 + vertex -848.622 281.028 128.248 + endloop + endfacet + facet normal 0.829344 -0.554071 0.0720764 + outer loop + vertex -850.437 278.23 127.625 + vertex -848.622 281.028 128.248 + vertex -850.399 278.793 131.52 + endloop + endfacet + facet normal 0.831486 -0.550353 0.0757795 + outer loop + vertex -850.399 278.793 131.52 + vertex -848.622 281.028 128.248 + vertex -848.585 281.628 132.202 + endloop + endfacet + facet normal 0.920272 -0.388026 0.0503449 + outer loop + vertex -848.622 281.028 128.248 + vertex -847.035 284.85 128.706 + vertex -848.585 281.628 132.202 + endloop + endfacet + facet normal 0.91557 -0.400471 0.0367895 + outer loop + vertex -848.585 281.628 132.202 + vertex -847.035 284.85 128.706 + vertex -847.222 284.818 133 + endloop + endfacet + facet normal 0.901587 -0.425629 0.077335 + outer loop + vertex -848.748 278.786 116.295 + vertex -847.201 282.159 116.819 + vertex -848.69 279.648 120.356 + endloop + endfacet + facet normal 0.907444 -0.410264 0.0907097 + outer loop + vertex -848.69 279.648 120.356 + vertex -847.201 282.159 116.819 + vertex -847.125 283.275 121.104 + endloop + endfacet + facet normal 0.803193 -0.58713 0.100796 + outer loop + vertex -850.572 276.222 115.888 + vertex -848.748 278.786 116.295 + vertex -850.523 276.967 119.839 + endloop + endfacet + facet normal 0.810402 -0.575371 0.11044 + outer loop + vertex -850.523 276.967 119.839 + vertex -848.748 278.786 116.295 + vertex -848.69 279.648 120.356 + endloop + endfacet + facet normal 0.8141 -0.573819 0.0892904 + outer loop + vertex -850.523 276.967 119.839 + vertex -848.69 279.648 120.356 + vertex -850.481 277.635 123.747 + endloop + endfacet + facet normal 0.81661 -0.569631 0.0931029 + outer loop + vertex -850.481 277.635 123.747 + vertex -848.69 279.648 120.356 + vertex -848.662 280.341 124.355 + endloop + endfacet + facet normal 0.911394 -0.406499 0.064193 + outer loop + vertex -848.69 279.648 120.356 + vertex -847.125 283.275 121.104 + vertex -848.662 280.341 124.355 + endloop + endfacet + facet normal 0.909833 -0.410657 0.0597023 + outer loop + vertex -848.662 280.341 124.355 + vertex -847.125 283.275 121.104 + vertex -847.288 283.483 125.027 + endloop + endfacet + facet normal 0.896401 -0.430418 0.105854 + outer loop + vertex -848.865 276.779 108.269 + vertex -847.289 280.159 108.664 + vertex -848.805 277.883 112.25 + endloop + endfacet + facet normal 0.893405 -0.438039 0.09975 + outer loop + vertex -848.805 277.883 112.25 + vertex -847.289 280.159 108.664 + vertex -847.265 281.123 112.68 + endloop + endfacet + facet normal 0.847124 -0.485164 0.216787 + outer loop + vertex -849.997 275.176 109.106 + vertex -848.865 276.779 108.269 + vertex -850.59 275.33 111.768 + endloop + endfacet + facet normal 0.796629 -0.585477 0.150331 + outer loop + vertex -850.59 275.33 111.768 + vertex -848.865 276.779 108.269 + vertex -848.805 277.883 112.25 + endloop + endfacet + facet normal 0.802254 -0.584211 0.122827 + outer loop + vertex -850.59 275.33 111.768 + vertex -848.805 277.883 112.25 + vertex -850.572 276.222 115.888 + endloop + endfacet + facet normal 0.799981 -0.587895 0.120041 + outer loop + vertex -850.572 276.222 115.888 + vertex -848.805 277.883 112.25 + vertex -848.748 278.786 116.295 + endloop + endfacet + facet normal 0.895416 -0.43704 0.085004 + outer loop + vertex -848.805 277.883 112.25 + vertex -847.265 281.123 112.68 + vertex -848.748 278.786 116.295 + endloop + endfacet + facet normal 0.899411 -0.427079 0.0930824 + outer loop + vertex -848.748 278.786 116.295 + vertex -847.265 281.123 112.68 + vertex -847.201 282.159 116.819 + endloop + endfacet + facet normal 0.898535 -0.423408 0.115584 + outer loop + vertex -848.745 274.868 100.298 + vertex -847.198 278.3 100.841 + vertex -848.778 275.876 104.246 + endloop + endfacet + facet normal 0.899377 -0.421045 0.117657 + outer loop + vertex -848.778 275.876 104.246 + vertex -847.198 278.3 100.841 + vertex -847.263 279.247 104.73 + endloop + endfacet + facet normal 0.827257 -0.544393 0.138859 + outer loop + vertex -850.083 274.167 105.319 + vertex -849.921 273.872 103.196 + vertex -848.778 275.876 104.246 + endloop + endfacet + facet normal 0.813074 -0.566254 0.135154 + outer loop + vertex -850.09 273.194 101.375 + vertex -848.745 274.868 100.298 + vertex -849.921 273.872 103.196 + endloop + endfacet + facet normal 0.824393 -0.546742 0.146453 + outer loop + vertex -848.745 274.868 100.298 + vertex -848.778 275.876 104.246 + vertex -849.921 273.872 103.196 + endloop + endfacet + facet normal 0.841474 -0.522469 0.137648 + outer loop + vertex -849.997 275.176 109.106 + vertex -849.879 274.861 107.188 + vertex -848.865 276.779 108.269 + endloop + endfacet + facet normal 0.823361 -0.555425 0.116533 + outer loop + vertex -850.083 274.167 105.319 + vertex -848.778 275.876 104.246 + vertex -849.879 274.861 107.188 + endloop + endfacet + facet normal 0.842372 -0.521631 0.135317 + outer loop + vertex -848.778 275.876 104.246 + vertex -848.865 276.779 108.269 + vertex -849.879 274.861 107.188 + endloop + endfacet + facet normal 0.899982 -0.42078 0.113919 + outer loop + vertex -848.778 275.876 104.246 + vertex -847.263 279.247 104.73 + vertex -848.865 276.779 108.269 + endloop + endfacet + facet normal 0.896437 -0.430405 0.105601 + outer loop + vertex -848.865 276.779 108.269 + vertex -847.263 279.247 104.73 + vertex -847.289 280.159 108.664 + endloop + endfacet + facet normal 0.905034 -0.364507 0.219199 + outer loop + vertex -848.082 273.595 93.7516 + vertex -847.062 275.753 93.1334 + vertex -848.664 273.666 96.2732 + endloop + endfacet + facet normal 0.889267 -0.423967 0.171631 + outer loop + vertex -848.664 273.666 96.2732 + vertex -847.062 275.753 93.1334 + vertex -847.121 277.184 96.9685 + endloop + endfacet + facet normal 0.758274 -0.613266 0.221192 + outer loop + vertex -849.896 270.919 93.5524 + vertex -848.856 272.284 93.7732 + vertex -849.889 271.671 95.6146 + endloop + endfacet + facet normal 0.803566 -0.560122 0.201359 + outer loop + vertex -850.066 272.104 97.5271 + vertex -849.889 271.671 95.6146 + vertex -848.664 273.666 96.2732 + endloop + endfacet + facet normal 0.843437 -0.495051 0.208661 + outer loop + vertex -848.082 273.595 93.7516 + vertex -848.664 273.666 96.2732 + vertex -848.856 272.284 93.7732 + endloop + endfacet + facet normal 0.785187 -0.565602 0.252143 + outer loop + vertex -849.889 271.671 95.6146 + vertex -848.856 272.284 93.7732 + vertex -848.664 273.666 96.2732 + endloop + endfacet + facet normal 0.818467 -0.549429 0.168047 + outer loop + vertex -850.09 273.194 101.375 + vertex -849.895 272.846 99.2869 + vertex -848.745 274.868 100.298 + endloop + endfacet + facet normal 0.796465 -0.581076 0.167316 + outer loop + vertex -850.066 272.104 97.5271 + vertex -848.664 273.666 96.2732 + vertex -849.895 272.846 99.2869 + endloop + endfacet + facet normal 0.813029 -0.553152 0.18168 + outer loop + vertex -848.664 273.666 96.2732 + vertex -848.745 274.868 100.298 + vertex -849.895 272.846 99.2869 + endloop + endfacet + facet normal 0.895466 -0.421214 0.143941 + outer loop + vertex -848.664 273.666 96.2732 + vertex -847.121 277.184 96.9685 + vertex -848.745 274.868 100.298 + endloop + endfacet + facet normal 0.894082 -0.425328 0.140404 + outer loop + vertex -848.745 274.868 100.298 + vertex -847.121 277.184 96.9685 + vertex -847.198 278.3 100.841 + endloop + endfacet + facet normal 0.89989 -0.395718 0.183317 + outer loop + vertex -848.031 272.244 90.1369 + vertex -847.791 271.869 88.1487 + vertex -846.841 274.564 89.3064 + endloop + endfacet + facet normal 0.894556 -0.405217 0.188594 + outer loop + vertex -847.837 270.956 86.4101 + vertex -846.61 273.294 85.6113 + vertex -847.791 271.869 88.1487 + endloop + endfacet + facet normal 0.896496 -0.39874 0.193135 + outer loop + vertex -846.61 273.294 85.6113 + vertex -846.841 274.564 89.3064 + vertex -847.791 271.869 88.1487 + endloop + endfacet + facet normal 0.82646 -0.514616 0.228327 + outer loop + vertex -848.64 269.539 86.1185 + vertex -847.837 270.956 86.4101 + vertex -848.754 270.166 87.9448 + endloop + endfacet + facet normal 0.832496 -0.49948 0.239729 + outer loop + vertex -848.754 270.166 87.9448 + vertex -847.837 270.956 86.4101 + vertex -847.791 271.869 88.1487 + endloop + endfacet + facet normal 0.7287 -0.632921 0.261547 + outer loop + vertex -849.615 268.369 86.0075 + vertex -848.64 269.539 86.1185 + vertex -849.724 269 87.8352 + endloop + endfacet + facet normal 0.729486 -0.631644 0.262444 + outer loop + vertex -849.724 269 87.8352 + vertex -848.64 269.539 86.1185 + vertex -848.754 270.166 87.9448 + endloop + endfacet + facet normal 0.732934 -0.633218 0.248683 + outer loop + vertex -849.724 269 87.8352 + vertex -848.754 270.166 87.9448 + vertex -849.817 269.619 89.6873 + endloop + endfacet + facet normal 0.733804 -0.631828 0.249651 + outer loop + vertex -849.817 269.619 89.6873 + vertex -848.754 270.166 87.9448 + vertex -848.842 270.802 89.8145 + endloop + endfacet + facet normal 0.840086 -0.500201 0.209892 + outer loop + vertex -848.754 270.166 87.9448 + vertex -847.791 271.869 88.1487 + vertex -848.842 270.802 89.8145 + endloop + endfacet + facet normal 0.834737 -0.513926 0.197724 + outer loop + vertex -848.842 270.802 89.8145 + vertex -847.791 271.869 88.1487 + vertex -848.031 272.244 90.1369 + endloop + endfacet + facet normal 0.834876 -0.513892 0.197223 + outer loop + vertex -848.842 270.802 89.8145 + vertex -848.031 272.244 90.1369 + vertex -848.884 271.475 91.7445 + endloop + endfacet + facet normal 0.84222 -0.496864 0.209264 + outer loop + vertex -848.884 271.475 91.7445 + vertex -848.031 272.244 90.1369 + vertex -847.923 273.184 91.9341 + endloop + endfacet + facet normal 0.738135 -0.633502 0.232016 + outer loop + vertex -849.817 269.619 89.6873 + vertex -848.842 270.802 89.8145 + vertex -849.879 270.242 91.5835 + endloop + endfacet + facet normal 0.741118 -0.628809 0.23525 + outer loop + vertex -849.879 270.242 91.5835 + vertex -848.842 270.802 89.8145 + vertex -848.884 271.475 91.7445 + endloop + endfacet + facet normal 0.744166 -0.629671 0.223008 + outer loop + vertex -849.879 270.242 91.5835 + vertex -848.884 271.475 91.7445 + vertex -849.896 270.919 93.5524 + endloop + endfacet + facet normal 0.754805 -0.612724 0.234177 + outer loop + vertex -849.896 270.919 93.5524 + vertex -848.884 271.475 91.7445 + vertex -848.856 272.284 93.7732 + endloop + endfacet + facet normal 0.847272 -0.497217 0.186832 + outer loop + vertex -848.884 271.475 91.7445 + vertex -847.923 273.184 91.9341 + vertex -848.856 272.284 93.7732 + endloop + endfacet + facet normal 0.847112 -0.497586 0.18657 + outer loop + vertex -848.856 272.284 93.7732 + vertex -847.923 273.184 91.9341 + vertex -848.082 273.595 93.7516 + endloop + endfacet + facet normal 0.909253 -0.381787 0.165825 + outer loop + vertex -848.082 273.595 93.7516 + vertex -847.923 273.184 91.9341 + vertex -847.062 275.753 93.1334 + endloop + endfacet + facet normal 0.900519 -0.405178 0.157788 + outer loop + vertex -848.031 272.244 90.1369 + vertex -846.841 274.564 89.3064 + vertex -847.923 273.184 91.9341 + endloop + endfacet + facet normal 0.907268 -0.383886 0.171746 + outer loop + vertex -846.841 274.564 89.3064 + vertex -847.062 275.753 93.1334 + vertex -847.923 273.184 91.9341 + endloop + endfacet + facet normal 0.885561 -0.396244 0.242429 + outer loop + vertex -847.561 269.64 82.799 + vertex -847.236 269.207 80.9025 + vertex -846.308 271.96 82.0136 + endloop + endfacet + facet normal 0.879953 -0.406654 0.245591 + outer loop + vertex -847.228 268.202 79.2105 + vertex -845.944 270.532 78.4677 + vertex -847.236 269.207 80.9025 + endloop + endfacet + facet normal 0.882085 -0.398579 0.251118 + outer loop + vertex -845.944 270.532 78.4677 + vertex -846.308 271.96 82.0136 + vertex -847.236 269.207 80.9025 + endloop + endfacet + facet normal 0.805653 -0.517608 0.288108 + outer loop + vertex -848.051 266.743 78.8927 + vertex -847.228 268.202 79.2105 + vertex -848.221 267.481 80.6917 + endloop + endfacet + facet normal 0.811975 -0.500208 0.300813 + outer loop + vertex -848.221 267.481 80.6917 + vertex -847.228 268.202 79.2105 + vertex -847.236 269.207 80.9025 + endloop + endfacet + facet normal 0.701422 -0.634538 0.324607 + outer loop + vertex -849.067 265.544 78.7426 + vertex -848.051 266.743 78.8927 + vertex -849.228 266.293 80.5555 + endloop + endfacet + facet normal 0.702338 -0.632972 0.32568 + outer loop + vertex -849.228 266.293 80.5555 + vertex -848.051 266.743 78.8927 + vertex -848.221 267.481 80.6917 + endloop + endfacet + facet normal 0.707781 -0.635597 0.308323 + outer loop + vertex -849.228 266.293 80.5555 + vertex -848.221 267.481 80.6917 + vertex -849.371 267.014 82.3695 + endloop + endfacet + facet normal 0.70963 -0.632488 0.310457 + outer loop + vertex -849.371 267.014 82.3695 + vertex -848.221 267.481 80.6917 + vertex -848.373 268.197 82.4976 + endloop + endfacet + facet normal 0.822177 -0.502054 0.268265 + outer loop + vertex -848.221 267.481 80.6917 + vertex -847.236 269.207 80.9025 + vertex -848.373 268.197 82.4976 + endloop + endfacet + facet normal 0.818121 -0.514022 0.257797 + outer loop + vertex -848.373 268.197 82.4976 + vertex -847.236 269.207 80.9025 + vertex -847.561 269.64 82.799 + endloop + endfacet + facet normal 0.81823 -0.514014 0.257467 + outer loop + vertex -848.373 268.197 82.4976 + vertex -847.561 269.64 82.799 + vertex -848.511 268.882 84.3052 + endloop + endfacet + facet normal 0.824601 -0.49713 0.26999 + outer loop + vertex -848.511 268.882 84.3052 + vertex -847.561 269.64 82.799 + vertex -847.545 270.59 84.4984 + endloop + endfacet + facet normal 0.715377 -0.635237 0.291051 + outer loop + vertex -849.371 267.014 82.3695 + vertex -848.373 268.197 82.4976 + vertex -849.498 267.703 84.1856 + endloop + endfacet + facet normal 0.717989 -0.630887 0.294065 + outer loop + vertex -849.498 267.703 84.1856 + vertex -848.373 268.197 82.4976 + vertex -848.511 268.882 84.3052 + endloop + endfacet + facet normal 0.722472 -0.633017 0.278073 + outer loop + vertex -849.498 267.703 84.1856 + vertex -848.511 268.882 84.3052 + vertex -849.615 268.369 86.0075 + endloop + endfacet + facet normal 0.723908 -0.630647 0.279718 + outer loop + vertex -849.615 268.369 86.0075 + vertex -848.511 268.882 84.3052 + vertex -848.64 269.539 86.1185 + endloop + endfacet + facet normal 0.833127 -0.498512 0.239552 + outer loop + vertex -848.511 268.882 84.3052 + vertex -847.545 270.59 84.4984 + vertex -848.64 269.539 86.1185 + endloop + endfacet + facet normal 0.827366 -0.514503 0.225283 + outer loop + vertex -848.64 269.539 86.1185 + vertex -847.545 270.59 84.4984 + vertex -847.837 270.956 86.4101 + endloop + endfacet + facet normal 0.893166 -0.396257 0.212684 + outer loop + vertex -847.837 270.956 86.4101 + vertex -847.545 270.59 84.4984 + vertex -846.61 273.294 85.6113 + endloop + endfacet + facet normal 0.887638 -0.405563 0.218215 + outer loop + vertex -847.561 269.64 82.799 + vertex -846.308 271.96 82.0136 + vertex -847.545 270.59 84.4984 + endloop + endfacet + facet normal 0.889458 -0.399092 0.222689 + outer loop + vertex -846.308 271.96 82.0136 + vertex -846.61 273.294 85.6113 + vertex -847.545 270.59 84.4984 + endloop + endfacet + facet normal 0.864622 -0.398475 0.306018 + outer loop + vertex -846.823 266.663 75.6551 + vertex -846.417 266.134 73.8167 + vertex -845.504 268.998 74.9691 + endloop + endfacet + facet normal 0.855563 -0.409439 0.316813 + outer loop + vertex -846.337 265.021 72.1642 + vertex -844.983 267.375 71.549 + vertex -846.417 266.134 73.8167 + endloop + endfacet + facet normal 0.857107 -0.402373 0.321658 + outer loop + vertex -844.983 267.375 71.549 + vertex -845.504 268.998 74.9691 + vertex -846.417 266.134 73.8167 + endloop + endfacet + facet normal 0.776655 -0.515875 0.361498 + outer loop + vertex -847.173 263.506 71.7972 + vertex -846.337 265.021 72.1642 + vertex -847.423 264.35 73.5397 + endloop + endfacet + facet normal 0.78177 -0.499204 0.373672 + outer loop + vertex -847.423 264.35 73.5397 + vertex -846.337 265.021 72.1642 + vertex -846.417 266.134 73.8167 + endloop + endfacet + facet normal 0.665329 -0.630805 0.399279 + outer loop + vertex -848.221 262.273 71.5951 + vertex -847.173 263.506 71.7972 + vertex -848.463 263.127 73.3494 + endloop + endfacet + facet normal 0.666229 -0.629116 0.40044 + outer loop + vertex -848.463 263.127 73.3494 + vertex -847.173 263.506 71.7972 + vertex -847.423 264.35 73.5397 + endloop + endfacet + facet normal 0.674109 -0.632793 0.380987 + outer loop + vertex -848.463 263.127 73.3494 + vertex -847.423 264.35 73.5397 + vertex -848.686 263.964 75.1327 + endloop + endfacet + facet normal 0.675168 -0.630874 0.382291 + outer loop + vertex -848.686 263.964 75.1327 + vertex -847.423 264.35 73.5397 + vertex -847.653 265.177 75.3111 + endloop + endfacet + facet normal 0.796292 -0.501824 0.337774 + outer loop + vertex -847.423 264.35 73.5397 + vertex -846.417 266.134 73.8167 + vertex -847.653 265.177 75.3111 + endloop + endfacet + facet normal 0.791944 -0.517418 0.324196 + outer loop + vertex -847.653 265.177 75.3111 + vertex -846.417 266.134 73.8167 + vertex -846.823 266.663 75.6551 + endloop + endfacet + facet normal 0.792163 -0.517417 0.323662 + outer loop + vertex -847.653 265.177 75.3111 + vertex -846.823 266.663 75.6551 + vertex -847.862 265.974 77.0965 + endloop + endfacet + facet normal 0.79815 -0.49979 0.336402 + outer loop + vertex -847.862 265.974 77.0965 + vertex -846.823 266.663 75.6551 + vertex -846.867 267.726 77.3377 + endloop + endfacet + facet normal 0.683271 -0.634647 0.361059 + outer loop + vertex -848.686 263.964 75.1327 + vertex -847.653 265.177 75.3111 + vertex -848.887 264.773 76.9342 + endloop + endfacet + facet normal 0.684433 -0.632599 0.362452 + outer loop + vertex -848.887 264.773 76.9342 + vertex -847.653 265.177 75.3111 + vertex -847.862 265.974 77.0965 + endloop + endfacet + facet normal 0.692305 -0.636318 0.340312 + outer loop + vertex -848.887 264.773 76.9342 + vertex -847.862 265.974 77.0965 + vertex -849.067 265.544 78.7426 + endloop + endfacet + facet normal 0.695067 -0.631531 0.343583 + outer loop + vertex -849.067 265.544 78.7426 + vertex -847.862 265.974 77.0965 + vertex -848.051 266.743 78.8927 + endloop + endfacet + facet normal 0.810982 -0.502116 0.300312 + outer loop + vertex -847.862 265.974 77.0965 + vertex -846.867 267.726 77.3377 + vertex -848.051 266.743 78.8927 + endloop + endfacet + facet normal 0.80612 -0.517592 0.286825 + outer loop + vertex -848.051 266.743 78.8927 + vertex -846.867 267.726 77.3377 + vertex -847.228 268.202 79.2105 + endloop + endfacet + facet normal 0.877081 -0.3973 0.269966 + outer loop + vertex -847.228 268.202 79.2105 + vertex -846.867 267.726 77.3377 + vertex -845.944 270.532 78.4677 + endloop + endfacet + facet normal 0.868712 -0.408312 0.280394 + outer loop + vertex -846.823 266.663 75.6551 + vertex -845.504 268.998 74.9691 + vertex -846.867 267.726 77.3377 + endloop + endfacet + facet normal 0.870443 -0.401246 0.285183 + outer loop + vertex -845.504 268.998 74.9691 + vertex -845.944 270.532 78.4677 + vertex -846.867 267.726 77.3377 + endloop + endfacet + facet normal 0.827926 -0.398631 0.394502 + outer loop + vertex -845.763 263.296 68.7882 + vertex -845.25 262.672 67.0836 + vertex -844.363 265.658 68.2388 + endloop + endfacet + facet normal 0.815383 -0.411579 0.407128 + outer loop + vertex -845.086 261.475 65.5438 + vertex -843.64 263.867 65.0653 + vertex -845.25 262.672 67.0836 + endloop + endfacet + facet normal 0.816671 -0.40262 0.413456 + outer loop + vertex -843.64 263.867 65.0653 + vertex -844.363 265.658 68.2388 + vertex -845.25 262.672 67.0836 + endloop + endfacet + facet normal 0.733613 -0.507202 0.452281 + outer loop + vertex -845.93 259.886 65.1306 + vertex -845.086 261.475 65.5438 + vertex -846.278 260.823 66.7461 + endloop + endfacet + facet normal 0.736505 -0.493594 0.462521 + outer loop + vertex -846.278 260.823 66.7461 + vertex -845.086 261.475 65.5438 + vertex -845.25 262.672 67.0836 + endloop + endfacet + facet normal 0.619907 -0.614506 0.487952 + outer loop + vertex -847.004 258.58 64.8507 + vertex -845.93 259.886 65.1306 + vertex -847.346 259.539 66.492 + endloop + endfacet + facet normal 0.620653 -0.612785 0.489167 + outer loop + vertex -847.346 259.539 66.492 + vertex -845.93 259.886 65.1306 + vertex -846.278 260.823 66.7461 + endloop + endfacet + facet normal 0.63296 -0.618391 0.465784 + outer loop + vertex -847.346 259.539 66.492 + vertex -846.278 260.823 66.7461 + vertex -847.662 260.475 68.1651 + endloop + endfacet + facet normal 0.633165 -0.617947 0.466093 + outer loop + vertex -847.662 260.475 68.1651 + vertex -846.278 260.823 66.7461 + vertex -846.6 261.739 68.3972 + endloop + endfacet + facet normal 0.756834 -0.497779 0.423578 + outer loop + vertex -846.278 260.823 66.7461 + vertex -845.25 262.672 67.0836 + vertex -846.6 261.739 68.3972 + endloop + endfacet + facet normal 0.754783 -0.509562 0.413096 + outer loop + vertex -846.6 261.739 68.3972 + vertex -845.25 262.672 67.0836 + vertex -845.763 263.296 68.7882 + endloop + endfacet + facet normal 0.759198 -0.509807 0.404617 + outer loop + vertex -846.6 261.739 68.3972 + vertex -845.763 263.296 68.7882 + vertex -846.898 262.63 70.0794 + endloop + endfacet + facet normal 0.762866 -0.495697 0.415114 + outer loop + vertex -846.898 262.63 70.0794 + vertex -845.763 263.296 68.7882 + vertex -845.883 264.451 70.3886 + endloop + endfacet + facet normal 0.643575 -0.622803 0.44489 + outer loop + vertex -847.662 260.475 68.1651 + vertex -846.6 261.739 68.3972 + vertex -847.954 261.39 69.8673 + endloop + endfacet + facet normal 0.643202 -0.623563 0.444365 + outer loop + vertex -847.954 261.39 69.8673 + vertex -846.6 261.739 68.3972 + vertex -846.898 262.63 70.0794 + endloop + endfacet + facet normal 0.653357 -0.628415 0.422159 + outer loop + vertex -847.954 261.39 69.8673 + vertex -846.898 262.63 70.0794 + vertex -848.221 262.273 71.5951 + endloop + endfacet + facet normal 0.654698 -0.625813 0.423943 + outer loop + vertex -848.221 262.273 71.5951 + vertex -846.898 262.63 70.0794 + vertex -847.173 263.506 71.7972 + endloop + endfacet + facet normal 0.7794 -0.498801 0.379121 + outer loop + vertex -846.898 262.63 70.0794 + vertex -845.883 264.451 70.3886 + vertex -847.173 263.506 71.7972 + endloop + endfacet + facet normal 0.775466 -0.515845 0.364083 + outer loop + vertex -847.173 263.506 71.7972 + vertex -845.883 264.451 70.3886 + vertex -846.337 265.021 72.1642 + endloop + endfacet + facet normal 0.849618 -0.398544 0.345416 + outer loop + vertex -846.337 265.021 72.1642 + vertex -845.883 264.451 70.3886 + vertex -844.983 267.375 71.549 + endloop + endfacet + facet normal 0.836977 -0.411967 0.360213 + outer loop + vertex -845.763 263.296 68.7882 + vertex -844.363 265.658 68.2388 + vertex -845.883 264.451 70.3886 + endloop + endfacet + facet normal 0.838576 -0.40338 0.366162 + outer loop + vertex -844.363 265.658 68.2388 + vertex -844.983 267.375 71.549 + vertex -845.883 264.451 70.3886 + endloop + endfacet + facet normal 0.769395 -0.395663 0.50148 + outer loop + vertex -844.303 259.578 62.4488 + vertex -843.663 258.877 60.9144 + vertex -842.797 261.987 62.0394 + endloop + endfacet + facet normal 0.749239 -0.408783 0.521093 + outer loop + vertex -843.392 257.583 59.5098 + vertex -841.833 260.03 59.1874 + vertex -843.663 258.877 60.9144 + endloop + endfacet + facet normal 0.749617 -0.399611 0.527622 + outer loop + vertex -841.833 260.03 59.1874 + vertex -842.797 261.987 62.0394 + vertex -843.663 258.877 60.9144 + endloop + endfacet + facet normal 0.664886 -0.494138 0.560137 + outer loop + vertex -844.247 255.908 59.0471 + vertex -843.392 257.583 59.5098 + vertex -844.714 256.93 60.503 + endloop + endfacet + facet normal 0.66602 -0.480206 0.570807 + outer loop + vertex -844.714 256.93 60.503 + vertex -843.392 257.583 59.5098 + vertex -843.663 258.877 60.9144 + endloop + endfacet + facet normal 0.549725 -0.590144 0.591213 + outer loop + vertex -845.354 254.503 58.6736 + vertex -844.247 255.908 59.0471 + vertex -845.812 255.559 60.1538 + endloop + endfacet + facet normal 0.549594 -0.590591 0.590888 + outer loop + vertex -845.812 255.559 60.1538 + vertex -844.247 255.908 59.0471 + vertex -844.714 256.93 60.503 + endloop + endfacet + facet normal 0.568626 -0.598945 0.563852 + outer loop + vertex -845.812 255.559 60.1538 + vertex -844.714 256.93 60.503 + vertex -846.239 256.588 61.6775 + endloop + endfacet + facet normal 0.569344 -0.596788 0.565413 + outer loop + vertex -846.239 256.588 61.6775 + vertex -844.714 256.93 60.503 + vertex -845.15 257.939 62.0062 + endloop + endfacet + facet normal 0.695416 -0.487098 0.52833 + outer loop + vertex -844.714 256.93 60.503 + vertex -843.663 258.877 60.9144 + vertex -845.15 257.939 62.0062 + endloop + endfacet + facet normal 0.695049 -0.498912 0.517681 + outer loop + vertex -845.15 257.939 62.0062 + vertex -843.663 258.877 60.9144 + vertex -844.303 259.578 62.4488 + endloop + endfacet + facet normal 0.704676 -0.500028 0.503393 + outer loop + vertex -845.15 257.939 62.0062 + vertex -844.303 259.578 62.4488 + vertex -845.554 258.921 63.5477 + endloop + endfacet + facet normal 0.706515 -0.4876 0.512915 + outer loop + vertex -845.554 258.921 63.5477 + vertex -844.303 259.578 62.4488 + vertex -844.516 260.82 63.9239 + endloop + endfacet + facet normal 0.586969 -0.604473 0.538591 + outer loop + vertex -846.239 256.588 61.6775 + vertex -845.15 257.939 62.0062 + vertex -846.637 257.599 63.2455 + endloop + endfacet + facet normal 0.587114 -0.604081 0.538873 + outer loop + vertex -846.637 257.599 63.2455 + vertex -845.15 257.939 62.0062 + vertex -845.554 258.921 63.5477 + endloop + endfacet + facet normal 0.603568 -0.611367 0.511797 + outer loop + vertex -846.637 257.599 63.2455 + vertex -845.554 258.921 63.5477 + vertex -847.004 258.58 64.8507 + endloop + endfacet + facet normal 0.604982 -0.607871 0.514286 + outer loop + vertex -847.004 258.58 64.8507 + vertex -845.554 258.921 63.5477 + vertex -845.93 259.886 65.1306 + endloop + endfacet + facet normal 0.730002 -0.492662 0.473688 + outer loop + vertex -845.554 258.921 63.5477 + vertex -844.516 260.82 63.9239 + vertex -845.93 259.886 65.1306 + endloop + endfacet + facet normal 0.728479 -0.506746 0.461006 + outer loop + vertex -845.93 259.886 65.1306 + vertex -844.516 260.82 63.9239 + vertex -845.086 261.475 65.5438 + endloop + endfacet + facet normal 0.803603 -0.397242 0.443195 + outer loop + vertex -845.086 261.475 65.5438 + vertex -844.516 260.82 63.9239 + vertex -843.64 263.867 65.0653 + endloop + endfacet + facet normal 0.785536 -0.4126 0.461188 + outer loop + vertex -844.303 259.578 62.4488 + vertex -842.797 261.987 62.0394 + vertex -844.516 260.82 63.9239 + endloop + endfacet + facet normal 0.78659 -0.401924 0.468757 + outer loop + vertex -842.797 261.987 62.0394 + vertex -843.64 263.867 65.0653 + vertex -844.516 260.82 63.9239 + endloop + endfacet + facet normal 0.684753 -0.379638 0.622084 + outer loop + vertex -842.359 255.531 56.7689 + vertex -841.599 254.808 55.4907 + vertex -840.776 258.072 56.5769 + endloop + endfacet + facet normal 0.673715 -0.379887 0.633873 + outer loop + vertex -841.242 253.498 54.3268 + vertex -839.695 256.239 54.3249 + vertex -841.599 254.808 55.4907 + endloop + endfacet + facet normal 0.673884 -0.380616 0.633255 + outer loop + vertex -839.695 256.239 54.3249 + vertex -840.776 258.072 56.5769 + vertex -841.599 254.808 55.4907 + endloop + endfacet + facet normal 0.569785 -0.464044 0.678239 + outer loop + vertex -842.101 251.738 53.8441 + vertex -841.242 253.498 54.3268 + vertex -842.667 252.753 55.0135 + endloop + endfacet + facet normal 0.568449 -0.454596 0.685717 + outer loop + vertex -842.667 252.753 55.0135 + vertex -841.242 253.498 54.3268 + vertex -841.599 254.808 55.4907 + endloop + endfacet + facet normal 0.454471 -0.547627 0.702539 + outer loop + vertex -843.227 250.246 53.4091 + vertex -842.101 251.738 53.8441 + vertex -843.802 251.303 54.6049 + endloop + endfacet + facet normal 0.454118 -0.552405 0.699018 + outer loop + vertex -843.802 251.303 54.6049 + vertex -842.101 251.738 53.8441 + vertex -842.667 252.753 55.0135 + endloop + endfacet + facet normal 0.479529 -0.564614 0.671761 + outer loop + vertex -843.802 251.303 54.6049 + vertex -842.667 252.753 55.0135 + vertex -844.346 252.364 55.8853 + endloop + endfacet + facet normal 0.479812 -0.562707 0.673158 + outer loop + vertex -844.346 252.364 55.8853 + vertex -842.667 252.753 55.0135 + vertex -843.219 253.806 56.2867 + endloop + endfacet + facet normal 0.605218 -0.464578 0.646435 + outer loop + vertex -842.667 252.753 55.0135 + vertex -841.599 254.808 55.4907 + vertex -843.219 253.806 56.2867 + endloop + endfacet + facet normal 0.60784 -0.479575 0.632882 + outer loop + vertex -843.219 253.806 56.2867 + vertex -841.599 254.808 55.4907 + vertex -842.359 255.531 56.7689 + endloop + endfacet + facet normal 0.619432 -0.481716 0.619882 + outer loop + vertex -843.219 253.806 56.2867 + vertex -842.359 255.531 56.7689 + vertex -843.748 254.862 57.636 + endloop + endfacet + facet normal 0.61939 -0.470518 0.628465 + outer loop + vertex -843.748 254.862 57.636 + vertex -842.359 255.531 56.7689 + vertex -842.684 256.857 58.0817 + endloop + endfacet + facet normal 0.503883 -0.573859 0.645591 + outer loop + vertex -844.346 252.364 55.8853 + vertex -843.219 253.806 56.2867 + vertex -844.866 253.442 57.2493 + endloop + endfacet + facet normal 0.50404 -0.573092 0.646149 + outer loop + vertex -844.866 253.442 57.2493 + vertex -843.219 253.806 56.2867 + vertex -843.748 254.862 57.636 + endloop + endfacet + facet normal 0.528425 -0.584113 0.6161 + outer loop + vertex -844.866 253.442 57.2493 + vertex -843.748 254.862 57.636 + vertex -845.354 254.503 58.6736 + endloop + endfacet + facet normal 0.529164 -0.581145 0.618269 + outer loop + vertex -845.354 254.503 58.6736 + vertex -843.748 254.862 57.636 + vertex -844.247 255.908 59.0471 + endloop + endfacet + facet normal 0.653074 -0.479095 0.586483 + outer loop + vertex -843.748 254.862 57.636 + vertex -842.684 256.857 58.0817 + vertex -844.247 255.908 59.0471 + endloop + endfacet + facet normal 0.653787 -0.492442 0.574512 + outer loop + vertex -844.247 255.908 59.0471 + vertex -842.684 256.857 58.0817 + vertex -843.392 257.583 59.5098 + endloop + endfacet + facet normal 0.729783 -0.391165 0.56072 + outer loop + vertex -843.392 257.583 59.5098 + vertex -842.684 256.857 58.0817 + vertex -841.833 260.03 59.1874 + endloop + endfacet + facet normal 0.710884 -0.399169 0.579058 + outer loop + vertex -842.359 255.531 56.7689 + vertex -840.776 258.072 56.5769 + vertex -842.684 256.857 58.0817 + endloop + endfacet + facet normal 0.710615 -0.393803 0.583049 + outer loop + vertex -840.776 258.072 56.5769 + vertex -841.833 260.03 59.1874 + vertex -842.684 256.857 58.0817 + endloop + endfacet + facet normal 0.603744 -0.33964 0.721206 + outer loop + vertex -840.149 251.722 52.3569 + vertex -839.491 251.391 51.6499 + vertex -838.72 254.758 52.5901 + endloop + endfacet + facet normal 0.619944 -0.33604 0.709046 + outer loop + vertex -839.28 250.46 51.024 + vertex -838.007 253.786 51.4874 + vertex -839.491 251.391 51.6499 + endloop + endfacet + facet normal 0.624757 -0.33942 0.703187 + outer loop + vertex -838.007 253.786 51.4874 + vertex -838.72 254.758 52.5901 + vertex -839.491 251.391 51.6499 + endloop + endfacet + facet normal 0.504543 -0.415066 0.757071 + outer loop + vertex -840.111 248.569 50.5415 + vertex -839.28 250.46 51.024 + vertex -840.483 249.121 51.0919 + endloop + endfacet + facet normal 0.494086 -0.405048 0.769295 + outer loop + vertex -840.483 249.121 51.0919 + vertex -839.28 250.46 51.024 + vertex -839.491 251.391 51.6499 + endloop + endfacet + facet normal 0.378419 -0.487614 0.786786 + outer loop + vertex -841.193 246.879 50.0141 + vertex -840.111 248.569 50.5415 + vertex -841.575 247.474 50.5669 + endloop + endfacet + facet normal 0.390792 -0.504545 0.76988 + outer loop + vertex -841.575 247.474 50.5669 + vertex -840.111 248.569 50.5415 + vertex -840.483 249.121 51.0919 + endloop + endfacet + facet normal 0.389942 -0.504192 0.770542 + outer loop + vertex -841.575 247.474 50.5669 + vertex -840.483 249.121 51.0919 + vertex -842.078 248.284 51.3514 + endloop + endfacet + facet normal 0.393436 -0.513272 0.762732 + outer loop + vertex -842.078 248.284 51.3514 + vertex -840.483 249.121 51.0919 + vertex -840.976 249.879 51.8564 + endloop + endfacet + facet normal 0.523092 -0.412017 0.746067 + outer loop + vertex -840.483 249.121 51.0919 + vertex -839.491 251.391 51.6499 + vertex -840.976 249.879 51.8564 + endloop + endfacet + facet normal 0.5459 -0.43884 0.713731 + outer loop + vertex -840.976 249.879 51.8564 + vertex -839.491 251.391 51.6499 + vertex -840.149 251.722 52.3569 + endloop + endfacet + facet normal 0.525849 -0.434579 0.731179 + outer loop + vertex -840.976 249.879 51.8564 + vertex -840.149 251.722 52.3569 + vertex -841.53 250.769 52.7841 + endloop + endfacet + facet normal 0.523523 -0.428982 0.736137 + outer loop + vertex -841.53 250.769 52.7841 + vertex -840.149 251.722 52.3569 + vertex -840.492 252.918 53.2978 + endloop + endfacet + facet normal 0.408154 -0.519604 0.750615 + outer loop + vertex -842.078 248.284 51.3514 + vertex -840.976 249.879 51.8564 + vertex -842.645 249.234 52.3174 + endloop + endfacet + facet normal 0.408892 -0.523978 0.747165 + outer loop + vertex -842.645 249.234 52.3174 + vertex -840.976 249.879 51.8564 + vertex -841.53 250.769 52.7841 + endloop + endfacet + facet normal 0.43239 -0.534636 0.726088 + outer loop + vertex -842.645 249.234 52.3174 + vertex -841.53 250.769 52.7841 + vertex -843.227 250.246 53.4091 + endloop + endfacet + facet normal 0.432469 -0.537304 0.724068 + outer loop + vertex -843.227 250.246 53.4091 + vertex -841.53 250.769 52.7841 + vertex -842.101 251.738 53.8441 + endloop + endfacet + facet normal 0.560136 -0.438684 0.702712 + outer loop + vertex -841.53 250.769 52.7841 + vertex -840.492 252.918 53.2978 + vertex -842.101 251.738 53.8441 + endloop + endfacet + facet normal 0.570325 -0.464161 0.677705 + outer loop + vertex -842.101 251.738 53.8441 + vertex -840.492 252.918 53.2978 + vertex -841.242 253.498 54.3268 + endloop + endfacet + facet normal 0.643516 -0.362811 0.673985 + outer loop + vertex -841.242 253.498 54.3268 + vertex -840.492 252.918 53.2978 + vertex -839.695 256.239 54.3249 + endloop + endfacet + facet normal 0.639642 -0.35357 0.682529 + outer loop + vertex -840.149 251.722 52.3569 + vertex -838.72 254.758 52.5901 + vertex -840.492 252.918 53.2978 + endloop + endfacet + facet normal 0.645139 -0.362733 0.672473 + outer loop + vertex -838.72 254.758 52.5901 + vertex -839.695 256.239 54.3249 + vertex -840.492 252.918 53.2978 + endloop + endfacet + facet normal 0.465771 -0.302551 0.831577 + outer loop + vertex -838.907 249.971 50.4868 + vertex -838.709 250.366 50.5194 + vertex -837.705 253.309 51.0279 + endloop + endfacet + facet normal -0.193514 0.224439 -0.955081 + outer loop + vertex -838.846 250.03 50.4682 + vertex -837.668 253.09 50.9485 + vertex -838.709 250.366 50.5194 + endloop + endfacet + facet normal 0.33446 -0.270086 0.902879 + outer loop + vertex -837.668 253.09 50.9485 + vertex -837.705 253.309 51.0279 + vertex -838.709 250.366 50.5194 + endloop + endfacet + facet normal -0.186926 0.292701 -0.937755 + outer loop + vertex -839.72 248.234 50.0819 + vertex -838.846 250.03 50.4682 + vertex -839.762 248.141 50.0613 + endloop + endfacet + facet normal -0.628395 0.13985 0.76522 + outer loop + vertex -839.762 248.141 50.0613 + vertex -838.846 250.03 50.4682 + vertex -838.709 250.366 50.5194 + endloop + endfacet + facet normal 0.548487 -0.531822 0.645235 + outer loop + vertex -840.803 246.485 49.5606 + vertex -839.72 248.234 50.0819 + vertex -840.859 246.416 49.5514 + endloop + endfacet + facet normal 0.360351 0.0461485 -0.931675 + outer loop + vertex -840.859 246.416 49.5514 + vertex -839.72 248.234 50.0819 + vertex -839.762 248.141 50.0613 + endloop + endfacet + facet normal 0.719797 -0.573374 0.391325 + outer loop + vertex -840.859 246.416 49.5514 + vertex -839.762 248.141 50.0613 + vertex -840.887 246.395 49.5723 + endloop + endfacet + facet normal 0.781661 -0.572772 0.246857 + outer loop + vertex -840.887 246.395 49.5723 + vertex -839.762 248.141 50.0613 + vertex -839.789 248.111 50.0759 + endloop + endfacet + facet normal 0.762597 -0.455539 0.459271 + outer loop + vertex -839.762 248.141 50.0613 + vertex -838.709 250.366 50.5194 + vertex -839.789 248.111 50.0759 + endloop + endfacet + facet normal 0.873009 -0.453419 0.179629 + outer loop + vertex -839.789 248.111 50.0759 + vertex -838.709 250.366 50.5194 + vertex -838.907 249.971 50.4868 + endloop + endfacet + facet normal 0.526267 -0.413541 0.742985 + outer loop + vertex -839.789 248.111 50.0759 + vertex -838.907 249.971 50.4868 + vertex -839.883 248.236 50.2124 + endloop + endfacet + facet normal 0.449239 -0.380539 0.808316 + outer loop + vertex -839.883 248.236 50.2124 + vertex -838.907 249.971 50.4868 + vertex -838.876 250.545 50.7399 + endloop + endfacet + facet normal 0.383853 -0.477685 0.790237 + outer loop + vertex -840.887 246.395 49.5723 + vertex -839.789 248.111 50.0759 + vertex -840.974 246.538 49.7013 + endloop + endfacet + facet normal 0.426064 -0.500752 0.75347 + outer loop + vertex -840.974 246.538 49.7013 + vertex -839.789 248.111 50.0759 + vertex -839.883 248.236 50.2124 + endloop + endfacet + facet normal 0.379839 -0.481923 0.789603 + outer loop + vertex -840.974 246.538 49.7013 + vertex -839.883 248.236 50.2124 + vertex -841.193 246.879 50.0141 + endloop + endfacet + facet normal 0.395042 -0.494359 0.774306 + outer loop + vertex -841.193 246.879 50.0141 + vertex -839.883 248.236 50.2124 + vertex -840.111 248.569 50.5415 + endloop + endfacet + facet normal 0.514814 -0.397953 0.759342 + outer loop + vertex -839.883 248.236 50.2124 + vertex -838.876 250.545 50.7399 + vertex -840.111 248.569 50.5415 + endloop + endfacet + facet normal 0.578672 -0.431125 0.692293 + outer loop + vertex -840.111 248.569 50.5415 + vertex -838.876 250.545 50.7399 + vertex -839.28 250.46 51.024 + endloop + endfacet + facet normal 0.589224 -0.328352 0.738241 + outer loop + vertex -839.28 250.46 51.024 + vertex -838.876 250.545 50.7399 + vertex -838.007 253.786 51.4874 + endloop + endfacet + facet normal 0.632953 -0.340656 0.695215 + outer loop + vertex -838.907 249.971 50.4868 + vertex -837.705 253.309 51.0279 + vertex -838.876 250.545 50.7399 + endloop + endfacet + facet normal 0.595887 -0.32885 0.732651 + outer loop + vertex -837.705 253.309 51.0279 + vertex -838.007 253.786 51.4874 + vertex -838.876 250.545 50.7399 + endloop + endfacet + facet normal 0.603757 -0.615091 0.507091 + outer loop + vertex -841.066 245.779 49.1949 + vertex -839.862 247.461 49.802 + vertex -840.782 246.25 49.4279 + endloop + endfacet + facet normal 0.12087 -0.375536 0.918892 + outer loop + vertex -840.782 246.25 49.4279 + vertex -839.862 247.461 49.802 + vertex -839.685 247.955 49.9805 + endloop + endfacet + facet normal 0.482281 -0.445759 0.754125 + outer loop + vertex -839.862 247.461 49.802 + vertex -838.993 249.151 50.2452 + vertex -839.685 247.955 49.9805 + endloop + endfacet + facet normal 0.0191104 -0.226594 0.973802 + outer loop + vertex -839.685 247.955 49.9805 + vertex -838.993 249.151 50.2452 + vertex -838.699 250.078 50.4551 + endloop + endfacet + facet normal 0.253921 -0.321875 0.912097 + outer loop + vertex -839.685 247.955 49.9805 + vertex -838.699 250.078 50.4551 + vertex -839.646 248.263 50.0782 + endloop + endfacet + facet normal 0.0533065 -0.229541 0.971838 + outer loop + vertex -839.646 248.263 50.0782 + vertex -838.699 250.078 50.4551 + vertex -838.634 250.477 50.5457 + endloop + endfacet + facet normal 0.32863 -0.475829 0.815836 + outer loop + vertex -840.782 246.25 49.4279 + vertex -839.685 247.955 49.9805 + vertex -840.739 246.467 49.537 + endloop + endfacet + facet normal 0.0330829 -0.306843 0.951185 + outer loop + vertex -840.739 246.467 49.537 + vertex -839.685 247.955 49.9805 + vertex -839.646 248.263 50.0782 + endloop + endfacet + facet normal 0.215805 -0.399812 0.89083 + outer loop + vertex -840.739 246.467 49.537 + vertex -839.646 248.263 50.0782 + vertex -840.803 246.485 49.5606 + endloop + endfacet + facet normal 0.196028 -0.389586 0.899887 + outer loop + vertex -840.803 246.485 49.5606 + vertex -839.646 248.263 50.0782 + vertex -839.72 248.234 50.0819 + endloop + endfacet + facet normal 0.152473 -0.270383 0.950602 + outer loop + vertex -839.646 248.263 50.0782 + vertex -838.634 250.477 50.5457 + vertex -839.72 248.234 50.0819 + endloop + endfacet + facet normal 0.882895 -0.366752 -0.29324 + outer loop + vertex -839.72 248.234 50.0819 + vertex -838.634 250.477 50.5457 + vertex -838.846 250.03 50.4682 + endloop + endfacet + facet normal -0.183199 -0.0832296 0.979546 + outer loop + vertex -838.846 250.03 50.4682 + vertex -838.634 250.477 50.5457 + vertex -837.668 253.09 50.9485 + endloop + endfacet + facet normal 0.283378 -0.255756 0.924276 + outer loop + vertex -838.699 250.078 50.4551 + vertex -837.623 253.001 50.9341 + vertex -838.634 250.477 50.5457 + endloop + endfacet + facet normal 0.0107841 -0.156255 0.987658 + outer loop + vertex -837.623 253.001 50.9341 + vertex -837.668 253.09 50.9485 + vertex -838.634 250.477 50.5457 + endloop + endfacet + facet normal 0.621311 -0.206601 -0.755836 + outer loop + vertex -836.925 258.938 291.693 + vertex -835.474 263.313 291.69 + vertex -836.35 258.542 292.274 + endloop + endfacet + facet normal 0.453424 -0.189881 -0.870834 + outer loop + vertex -836.35 258.542 292.274 + vertex -835.474 263.313 291.69 + vertex -835.612 260.759 292.175 + endloop + endfacet + facet normal 0.61699 -0.270316 -0.739089 + outer loop + vertex -838.617 254.077 292.059 + vertex -836.925 258.938 291.693 + vertex -837.907 254.008 292.676 + endloop + endfacet + facet normal 0.586444 -0.269194 -0.763949 + outer loop + vertex -837.907 254.008 292.676 + vertex -836.925 258.938 291.693 + vertex -836.35 258.542 292.274 + endloop + endfacet + facet normal 0.752445 -0.246176 -0.61092 + outer loop + vertex -838.741 261.242 288.709 + vertex -837.322 265.34 288.806 + vertex -837.757 259.799 290.503 + endloop + endfacet + facet normal 0.770473 -0.24121 -0.590075 + outer loop + vertex -837.757 259.799 290.503 + vertex -837.322 265.34 288.806 + vertex -836.241 265.28 290.243 + endloop + endfacet + facet normal 0.704779 -0.299606 -0.643058 + outer loop + vertex -840.553 256.996 288.702 + vertex -838.741 261.242 288.709 + vertex -839.484 255.228 290.698 + endloop + endfacet + facet normal 0.715764 -0.297276 -0.631909 + outer loop + vertex -839.484 255.228 290.698 + vertex -838.741 261.242 288.709 + vertex -837.757 259.799 290.503 + endloop + endfacet + facet normal 0.680293 -0.285715 -0.674958 + outer loop + vertex -839.484 255.228 290.698 + vertex -837.757 259.799 290.503 + vertex -838.617 254.077 292.059 + endloop + endfacet + facet normal 0.675634 -0.286225 -0.679407 + outer loop + vertex -838.617 254.077 292.059 + vertex -837.757 259.799 290.503 + vertex -836.925 258.938 291.693 + endloop + endfacet + facet normal 0.712436 -0.228631 -0.663448 + outer loop + vertex -837.757 259.799 290.503 + vertex -836.241 265.28 290.243 + vertex -836.925 258.938 291.693 + endloop + endfacet + facet normal 0.694458 -0.230819 -0.681506 + outer loop + vertex -836.925 258.938 291.693 + vertex -836.241 265.28 290.243 + vertex -835.474 263.313 291.69 + endloop + endfacet + facet normal 0.817732 -0.26535 -0.510788 + outer loop + vertex -840.794 264.971 283.846 + vertex -839.354 268.755 284.185 + vertex -839.792 263.064 286.44 + endloop + endfacet + facet normal 0.816764 -0.265796 -0.512103 + outer loop + vertex -839.792 263.064 286.44 + vertex -839.354 268.755 284.185 + vertex -838.2 267.936 286.451 + endloop + endfacet + facet normal 0.789101 -0.322198 -0.52298 + outer loop + vertex -842.584 260.877 283.667 + vertex -840.794 264.971 283.846 + vertex -841.616 258.936 286.323 + endloop + endfacet + facet normal 0.775402 -0.327323 -0.54001 + outer loop + vertex -841.616 258.936 286.323 + vertex -840.794 264.971 283.846 + vertex -839.792 263.064 286.44 + endloop + endfacet + facet normal 0.745676 -0.312832 -0.588306 + outer loop + vertex -841.616 258.936 286.323 + vertex -839.792 263.064 286.44 + vertex -840.553 256.996 288.702 + endloop + endfacet + facet normal 0.739636 -0.314559 -0.594971 + outer loop + vertex -840.553 256.996 288.702 + vertex -839.792 263.064 286.44 + vertex -838.741 261.242 288.709 + endloop + endfacet + facet normal 0.783248 -0.254718 -0.567134 + outer loop + vertex -839.792 263.064 286.44 + vertex -838.2 267.936 286.451 + vertex -838.741 261.242 288.709 + endloop + endfacet + facet normal 0.778769 -0.256203 -0.572607 + outer loop + vertex -838.741 261.242 288.709 + vertex -838.2 267.936 286.451 + vertex -837.322 265.34 288.806 + endloop + endfacet + facet normal 0.876578 -0.272057 -0.396983 + outer loop + vertex -842.526 268.658 277.971 + vertex -841.153 272.402 278.438 + vertex -841.712 266.853 281.006 + endloop + endfacet + facet normal 0.870391 -0.27631 -0.407519 + outer loop + vertex -841.712 266.853 281.006 + vertex -841.153 272.402 278.438 + vertex -840.138 271.549 281.183 + endloop + endfacet + facet normal 0.851161 -0.329285 -0.408773 + outer loop + vertex -844.238 264.651 277.636 + vertex -842.526 268.658 277.971 + vertex -843.46 262.789 280.756 + endloop + endfacet + facet normal 0.84077 -0.335345 -0.425029 + outer loop + vertex -843.46 262.789 280.756 + vertex -842.526 268.658 277.971 + vertex -841.712 266.853 281.006 + endloop + endfacet + facet normal 0.824607 -0.326106 -0.462254 + outer loop + vertex -843.46 262.789 280.756 + vertex -841.712 266.853 281.006 + vertex -842.584 260.877 283.667 + endloop + endfacet + facet normal 0.809966 -0.333081 -0.482713 + outer loop + vertex -842.584 260.877 283.667 + vertex -841.712 266.853 281.006 + vertex -840.794 264.971 283.846 + endloop + endfacet + facet normal 0.850483 -0.267931 -0.452651 + outer loop + vertex -841.712 266.853 281.006 + vertex -840.138 271.549 281.183 + vertex -840.794 264.971 283.846 + endloop + endfacet + facet normal 0.835838 -0.275463 -0.474862 + outer loop + vertex -840.794 264.971 283.846 + vertex -840.138 271.549 281.183 + vertex -839.354 268.755 284.185 + endloop + endfacet + facet normal 0.848239 -0.262552 0.459953 + outer loop + vertex -840.467 264.832 60.0458 + vertex -839.485 269.435 60.8618 + vertex -841.432 266.692 62.8875 + endloop + endfacet + facet normal 0.849028 -0.265404 0.45685 + outer loop + vertex -841.432 266.692 62.8875 + vertex -839.485 269.435 60.8618 + vertex -840.165 271.946 63.5858 + endloop + endfacet + facet normal 0.810023 -0.31846 0.492388 + outer loop + vertex -841.833 260.03 59.1874 + vertex -840.467 264.832 60.0458 + vertex -842.797 261.987 62.0394 + endloop + endfacet + facet normal 0.811322 -0.323216 0.487122 + outer loop + vertex -842.797 261.987 62.0394 + vertex -840.467 264.832 60.0458 + vertex -841.432 266.692 62.8875 + endloop + endfacet + facet normal 0.841026 -0.322345 0.434475 + outer loop + vertex -842.797 261.987 62.0394 + vertex -841.432 266.692 62.8875 + vertex -843.64 263.867 65.0653 + endloop + endfacet + facet normal 0.841559 -0.325216 0.431292 + outer loop + vertex -843.64 263.867 65.0653 + vertex -841.432 266.692 62.8875 + vertex -842.287 268.502 65.9198 + endloop + endfacet + facet normal 0.875262 -0.2648 0.404718 + outer loop + vertex -841.432 266.692 62.8875 + vertex -840.165 271.946 63.5858 + vertex -842.287 268.502 65.9198 + endloop + endfacet + facet normal 0.877097 -0.271854 0.395976 + outer loop + vertex -842.287 268.502 65.9198 + vertex -840.165 271.946 63.5858 + vertex -841.283 272.94 66.7435 + endloop + endfacet + facet normal 0.790104 -0.24825 0.560453 + outer loop + vertex -838.371 261.247 55.2062 + vertex -837.45 266.007 56.0157 + vertex -839.416 262.961 57.439 + endloop + endfacet + facet normal 0.792291 -0.251869 0.555731 + outer loop + vertex -839.416 262.961 57.439 + vertex -837.45 266.007 56.0157 + vertex -838.218 268.462 58.2234 + endloop + endfacet + facet normal 0.740384 -0.30149 0.600779 + outer loop + vertex -839.695 256.239 54.3249 + vertex -838.371 261.247 55.2062 + vertex -840.776 258.072 56.5769 + endloop + endfacet + facet normal 0.746276 -0.31132 0.588347 + outer loop + vertex -840.776 258.072 56.5769 + vertex -838.371 261.247 55.2062 + vertex -839.416 262.961 57.439 + endloop + endfacet + facet normal 0.775684 -0.312447 0.548353 + outer loop + vertex -840.776 258.072 56.5769 + vertex -839.416 262.961 57.439 + vertex -841.833 260.03 59.1874 + endloop + endfacet + facet normal 0.777923 -0.318172 0.541851 + outer loop + vertex -841.833 260.03 59.1874 + vertex -839.416 262.961 57.439 + vertex -840.467 264.832 60.0458 + endloop + endfacet + facet normal 0.821326 -0.251933 0.511813 + outer loop + vertex -839.416 262.961 57.439 + vertex -838.218 268.462 58.2234 + vertex -840.467 264.832 60.0458 + endloop + endfacet + facet normal 0.827736 -0.264379 0.494932 + outer loop + vertex -840.467 264.832 60.0458 + vertex -838.218 268.462 58.2234 + vertex -839.485 269.435 60.8618 + endloop + endfacet + facet normal 0.733976 -0.232326 0.638203 + outer loop + vertex -836.7 258.907 52.2799 + vertex -835.786 263.629 52.9471 + vertex -837.416 259.841 53.4426 + endloop + endfacet + facet normal 0.737258 -0.234331 0.633672 + outer loop + vertex -837.416 259.841 53.4426 + vertex -835.786 263.629 52.9471 + vertex -836.318 265.49 54.2544 + endloop + endfacet + facet normal 0.676122 -0.278089 0.682294 + outer loop + vertex -838.007 253.786 51.4874 + vertex -836.7 258.907 52.2799 + vertex -838.72 254.758 52.5901 + endloop + endfacet + facet normal 0.694405 -0.28872 0.659122 + outer loop + vertex -838.72 254.758 52.5901 + vertex -836.7 258.907 52.2799 + vertex -837.416 259.841 53.4426 + endloop + endfacet + facet normal 0.707206 -0.289629 0.644961 + outer loop + vertex -838.72 254.758 52.5901 + vertex -837.416 259.841 53.4426 + vertex -839.695 256.239 54.3249 + endloop + endfacet + facet normal 0.71766 -0.300326 0.628306 + outer loop + vertex -839.695 256.239 54.3249 + vertex -837.416 259.841 53.4426 + vertex -838.371 261.247 55.2062 + endloop + endfacet + facet normal 0.763881 -0.234827 0.601117 + outer loop + vertex -837.416 259.841 53.4426 + vertex -836.318 265.49 54.2544 + vertex -838.371 261.247 55.2062 + endloop + endfacet + facet normal 0.77999 -0.248643 0.574275 + outer loop + vertex -838.371 261.247 55.2062 + vertex -836.318 265.49 54.2544 + vertex -837.45 266.007 56.0157 + endloop + endfacet + facet normal 0.530292 -0.202761 0.823212 + outer loop + vertex -836.335 257.412 51.4819 + vertex -835.088 262.591 51.9541 + vertex -836.321 258.332 51.6995 + endloop + endfacet + facet normal 0.513994 -0.198715 0.83446 + outer loop + vertex -836.321 258.332 51.6995 + vertex -835.088 262.591 51.9541 + vertex -835.154 263.957 52.3202 + endloop + endfacet + facet normal 0.433198 -0.240765 0.868546 + outer loop + vertex -837.668 253.09 50.9485 + vertex -836.335 257.412 51.4819 + vertex -837.705 253.309 51.0279 + endloop + endfacet + facet normal 0.358176 -0.220007 0.907363 + outer loop + vertex -837.705 253.309 51.0279 + vertex -836.335 257.412 51.4819 + vertex -836.321 258.332 51.6995 + endloop + endfacet + facet normal 0.64872 -0.273697 0.710107 + outer loop + vertex -837.705 253.309 51.0279 + vertex -836.321 258.332 51.6995 + vertex -838.007 253.786 51.4874 + endloop + endfacet + facet normal 0.656153 -0.27609 0.702309 + outer loop + vertex -838.007 253.786 51.4874 + vertex -836.321 258.332 51.6995 + vertex -836.7 258.907 52.2799 + endloop + endfacet + facet normal 0.702091 -0.220376 0.677128 + outer loop + vertex -836.321 258.332 51.6995 + vertex -835.154 263.957 52.3202 + vertex -836.7 258.907 52.2799 + endloop + endfacet + facet normal 0.743247 -0.23258 0.627288 + outer loop + vertex -836.7 258.907 52.2799 + vertex -835.154 263.957 52.3202 + vertex -835.786 263.629 52.9471 + endloop + endfacet + facet normal 0.0364579 -0.143412 0.988991 + outer loop + vertex -837.623 253.001 50.9341 + vertex -836.494 256.549 51.4068 + vertex -837.668 253.09 50.9485 + endloop + endfacet + facet normal -0.28144 -0.0315604 0.95906 + outer loop + vertex -837.668 253.09 50.9485 + vertex -836.494 256.549 51.4068 + vertex -836.335 257.412 51.4819 + endloop + endfacet + facet normal -0.204934 -0.0472603 0.977634 + outer loop + vertex -836.494 256.549 51.4068 + vertex -835.62 259.755 51.745 + vertex -836.335 257.412 51.4819 + endloop + endfacet + facet normal -0.311789 -0.0115495 0.950081 + outer loop + vertex -836.335 257.412 51.4819 + vertex -835.62 259.755 51.745 + vertex -835.088 262.591 51.9541 + endloop + endfacet + facet normal 0.74884 -0.177932 -0.638418 + outer loop + vertex -835.474 263.313 291.69 + vertex -836.241 265.28 290.243 + vertex -834.399 272.206 290.472 + endloop + endfacet + facet normal 0.775619 -0.216458 -0.592926 + outer loop + vertex -837.322 265.34 288.806 + vertex -836.338 273.42 287.143 + vertex -836.241 265.28 290.243 + endloop + endfacet + facet normal 0.813779 -0.19825 -0.546315 + outer loop + vertex -836.338 273.42 287.143 + vertex -834.399 272.206 290.472 + vertex -836.241 265.28 290.243 + endloop + endfacet + facet normal 0.817693 -0.209867 -0.536036 + outer loop + vertex -837.322 265.34 288.806 + vertex -838.2 267.936 286.451 + vertex -836.338 273.42 287.143 + endloop + endfacet + facet normal 0.827945 -0.238056 -0.507776 + outer loop + vertex -839.354 268.755 284.185 + vertex -838.249 276.408 282.399 + vertex -838.2 267.936 286.451 + endloop + endfacet + facet normal 0.845891 -0.226126 -0.483047 + outer loop + vertex -838.249 276.408 282.399 + vertex -836.338 273.42 287.143 + vertex -838.2 267.936 286.451 + endloop + endfacet + facet normal 0.86891 -0.227996 -0.439332 + outer loop + vertex -839.354 268.755 284.185 + vertex -840.138 271.549 281.183 + vertex -838.249 276.408 282.399 + endloop + endfacet + facet normal 0.882283 -0.244734 -0.402096 + outer loop + vertex -841.153 272.402 278.438 + vertex -839.947 279.8 276.581 + vertex -840.138 271.549 281.183 + endloop + endfacet + facet normal 0.883587 -0.243562 -0.399939 + outer loop + vertex -839.947 279.8 276.581 + vertex -838.249 276.408 282.399 + vertex -840.138 271.549 281.183 + endloop + endfacet + facet normal 0.846473 -0.216681 0.486346 + outer loop + vertex -839.485 269.435 60.8618 + vertex -838.218 268.462 58.2234 + vertex -837.452 275.472 60.0141 + endloop + endfacet + facet normal 0.82813 -0.208728 0.520223 + outer loop + vertex -837.45 266.007 56.0157 + vertex -835.698 272.542 55.8492 + vertex -838.218 268.462 58.2234 + endloop + endfacet + facet normal 0.833778 -0.22037 0.506212 + outer loop + vertex -835.698 272.542 55.8492 + vertex -837.452 275.472 60.0141 + vertex -838.218 268.462 58.2234 + endloop + endfacet + facet normal 0.738791 -0.18347 0.64848 + outer loop + vertex -835.786 263.629 52.9471 + vertex -835.154 263.957 52.3202 + vertex -834.417 270.497 53.3315 + endloop + endfacet + facet normal 0.662189 -0.163857 0.731202 + outer loop + vertex -835.088 262.591 51.9541 + vertex -833.804 269.618 52.3662 + vertex -835.154 263.957 52.3202 + endloop + endfacet + facet normal 0.745706 -0.183037 0.64064 + outer loop + vertex -833.804 269.618 52.3662 + vertex -834.417 270.497 53.3315 + vertex -835.154 263.957 52.3202 + endloop + endfacet + facet normal 0.821498 -0.175525 -0.542524 + outer loop + vertex -836.338 273.42 287.143 + vertex -834.376 282.706 287.111 + vertex -834.399 272.206 290.472 + endloop + endfacet + facet normal 0.843009 -0.165716 -0.511737 + outer loop + vertex -834.399 272.206 290.472 + vertex -834.376 282.706 287.111 + vertex -832.618 281.897 290.269 + endloop + endfacet + facet normal 0.863536 -0.189732 -0.467234 + outer loop + vertex -838.249 276.408 282.399 + vertex -836.2 285.134 282.643 + vertex -836.338 273.42 287.143 + endloop + endfacet + facet normal 0.870349 -0.185551 -0.456139 + outer loop + vertex -836.338 273.42 287.143 + vertex -836.2 285.134 282.643 + vertex -834.376 282.706 287.111 + endloop + endfacet + facet normal 0.904096 -0.197392 -0.379008 + outer loop + vertex -839.947 279.8 276.581 + vertex -837.908 288.269 277.035 + vertex -838.249 276.408 282.399 + endloop + endfacet + facet normal 0.90026 -0.200614 -0.386375 + outer loop + vertex -838.249 276.408 282.399 + vertex -837.908 288.269 277.035 + vertex -836.2 285.134 282.643 + endloop + endfacet + facet normal 0.855756 -0.178123 0.48575 + outer loop + vertex -835.698 272.542 55.8492 + vertex -834.154 282.184 56.6644 + vertex -837.452 275.472 60.0141 + endloop + endfacet + facet normal 0.863206 -0.190972 0.467339 + outer loop + vertex -837.452 275.472 60.0141 + vertex -834.154 282.184 56.6644 + vertex -835.769 284.96 60.7824 + endloop + endfacet + facet normal 0.765847 -0.151682 0.624876 + outer loop + vertex -833.804 269.618 52.3662 + vertex -832.412 278.127 52.726 + vertex -834.417 270.497 53.3315 + endloop + endfacet + facet normal 0.800947 -0.164817 0.575604 + outer loop + vertex -834.417 270.497 53.3315 + vertex -832.412 278.127 52.726 + vertex -833.024 279.844 54.0692 + endloop + endfacet + facet normal 0.840839 -0.173839 -0.51261 + outer loop + vertex -834.376 282.706 287.111 + vertex -832.597 291.3 287.114 + vertex -832.618 281.897 290.269 + endloop + endfacet + facet normal 0.847939 -0.170294 -0.501996 + outer loop + vertex -832.618 281.897 290.269 + vertex -832.597 291.3 287.114 + vertex -831.074 290.479 289.965 + endloop + endfacet + facet normal 0.870764 -0.184537 -0.455758 + outer loop + vertex -836.2 285.134 282.643 + vertex -834.318 293.595 282.813 + vertex -834.376 282.706 287.111 + endloop + endfacet + facet normal 0.875963 -0.181139 -0.447077 + outer loop + vertex -834.376 282.706 287.111 + vertex -834.318 293.595 282.813 + vertex -832.597 291.3 287.114 + endloop + endfacet + facet normal 0.903073 -0.193664 -0.383346 + outer loop + vertex -837.908 288.269 277.035 + vertex -836.012 296.57 277.307 + vertex -836.2 285.134 282.643 + endloop + endfacet + facet normal 0.903501 -0.193288 -0.382525 + outer loop + vertex -836.2 285.134 282.643 + vertex -836.012 296.57 277.307 + vertex -834.318 293.595 282.813 + endloop + endfacet + facet normal 0.868558 -0.179719 0.461853 + outer loop + vertex -834.154 282.184 56.6644 + vertex -832.436 291.182 56.9355 + vertex -835.769 284.96 60.7824 + endloop + endfacet + facet normal 0.87092 -0.185071 0.455243 + outer loop + vertex -835.769 284.96 60.7824 + vertex -832.436 291.182 56.9355 + vertex -834.02 293.852 61.0521 + endloop + endfacet + facet normal 0.807477 -0.157023 0.568616 + outer loop + vertex -832.412 278.127 52.726 + vertex -831.016 286.312 53.0034 + vertex -833.024 279.844 54.0692 + endloop + endfacet + facet normal 0.824532 -0.16693 0.540631 + outer loop + vertex -833.024 279.844 54.0692 + vertex -831.016 286.312 53.0034 + vertex -831.407 288.703 54.3384 + endloop + endfacet + facet normal 0.840628 -0.195126 -0.505243 + outer loop + vertex -832.597 291.3 287.114 + vertex -830.73 299.343 287.114 + vertex -831.074 290.479 289.965 + endloop + endfacet + facet normal 0.839038 -0.195826 -0.50761 + outer loop + vertex -831.074 290.479 289.965 + vertex -830.73 299.343 287.114 + vertex -829.202 297.898 290.197 + endloop + endfacet + facet normal 0.866467 -0.20418 -0.455572 + outer loop + vertex -834.318 293.595 282.813 + vertex -832.383 301.694 282.863 + vertex -832.597 291.3 287.114 + endloop + endfacet + facet normal 0.869957 -0.201928 -0.449889 + outer loop + vertex -832.597 291.3 287.114 + vertex -832.383 301.694 282.863 + vertex -830.73 299.343 287.114 + endloop + endfacet + facet normal 0.894957 -0.214362 -0.391282 + outer loop + vertex -836.012 296.57 277.307 + vertex -834.052 304.589 277.396 + vertex -834.318 293.595 282.813 + endloop + endfacet + facet normal 0.897597 -0.212051 -0.386463 + outer loop + vertex -834.318 293.595 282.813 + vertex -834.052 304.589 277.396 + vertex -832.383 301.694 282.863 + endloop + endfacet + facet normal 0.865179 -0.197349 0.460998 + outer loop + vertex -832.436 291.182 56.9355 + vertex -830.488 299.701 56.9269 + vertex -834.02 293.852 61.0521 + endloop + endfacet + facet normal 0.866777 -0.201814 0.456035 + outer loop + vertex -834.02 293.852 61.0521 + vertex -830.488 299.701 56.9269 + vertex -832.087 302.236 61.0881 + endloop + endfacet + facet normal 0.813397 -0.176396 0.554319 + outer loop + vertex -831.016 286.312 53.0034 + vertex -829.138 294.759 52.9356 + vertex -831.407 288.703 54.3384 + endloop + endfacet + facet normal 0.823597 -0.184376 0.536371 + outer loop + vertex -831.407 288.703 54.3384 + vertex -829.138 294.759 52.9356 + vertex -829.481 297.283 54.3301 + endloop + endfacet + facet normal 0.827283 -0.224236 -0.515094 + outer loop + vertex -830.73 299.343 287.114 + vertex -828.551 307.382 287.114 + vertex -829.202 297.898 290.197 + endloop + endfacet + facet normal 0.830312 -0.223024 -0.510727 + outer loop + vertex -829.202 297.898 290.197 + vertex -828.551 307.382 287.114 + vertex -826.839 306.771 290.164 + endloop + endfacet + facet normal 0.854672 -0.235658 -0.462602 + outer loop + vertex -832.383 301.694 282.863 + vertex -830.216 309.584 282.847 + vertex -830.73 299.343 287.114 + endloop + endfacet + facet normal 0.859263 -0.232903 -0.455437 + outer loop + vertex -830.73 299.343 287.114 + vertex -830.216 309.584 282.847 + vertex -828.551 307.382 287.114 + endloop + endfacet + facet normal 0.882632 -0.246597 -0.400188 + outer loop + vertex -834.052 304.589 277.396 + vertex -831.881 312.37 277.39 + vertex -832.383 301.694 282.863 + endloop + endfacet + facet normal 0.885714 -0.244037 -0.394913 + outer loop + vertex -832.383 301.694 282.863 + vertex -831.881 312.37 277.39 + vertex -830.216 309.584 282.847 + endloop + endfacet + facet normal 0.908249 -0.259305 -0.328397 + outer loop + vertex -835.514 307.489 271.066 + vertex -833.343 315.13 271.034 + vertex -834.052 304.589 277.396 + endloop + endfacet + facet normal 0.91232 -0.254827 -0.320525 + outer loop + vertex -834.052 304.589 277.396 + vertex -833.343 315.13 271.034 + vertex -831.881 312.37 277.39 + endloop + endfacet + facet normal 0.929646 -0.269273 -0.251496 + outer loop + vertex -836.62 310.07 264.213 + vertex -834.464 317.564 264.159 + vertex -835.514 307.489 271.066 + endloop + endfacet + facet normal 0.932137 -0.265744 -0.24597 + outer loop + vertex -835.514 307.489 271.066 + vertex -834.464 317.564 264.159 + vertex -833.343 315.13 271.034 + endloop + endfacet + facet normal 0.941372 -0.278877 -0.189859 + outer loop + vertex -837.395 312.317 257.07 + vertex -835.238 319.65 256.992 + vertex -836.62 310.07 264.213 + endloop + endfacet + facet normal 0.944699 -0.273098 -0.181555 + outer loop + vertex -836.62 310.07 264.213 + vertex -835.238 319.65 256.992 + vertex -834.464 317.564 264.159 + endloop + endfacet + facet normal 0.855123 -0.226256 0.466446 + outer loop + vertex -830.488 299.701 56.9269 + vertex -828.299 307.892 56.8867 + vertex -832.087 302.236 61.0881 + endloop + endfacet + facet normal 0.855711 -0.228132 0.464451 + outer loop + vertex -832.087 302.236 61.0881 + vertex -828.299 307.892 56.8867 + vertex -829.941 310.208 61.0494 + endloop + endfacet + facet normal 0.800546 -0.202737 0.563936 + outer loop + vertex -829.138 294.759 52.9356 + vertex -826.9 303.398 52.8649 + vertex -829.481 297.283 54.3301 + endloop + endfacet + facet normal 0.808683 -0.209597 0.549637 + outer loop + vertex -829.481 297.283 54.3301 + vertex -826.9 303.398 52.8649 + vertex -827.285 305.58 54.2638 + endloop + endfacet + facet normal 0.820787 -0.25411 -0.511603 + outer loop + vertex -828.551 307.382 287.114 + vertex -826.061 315.497 287.078 + vertex -826.839 306.771 290.164 + endloop + endfacet + facet normal 0.82129 -0.253905 -0.510897 + outer loop + vertex -826.839 306.771 290.164 + vertex -826.061 315.497 287.078 + vertex -824.393 315.234 289.89 + endloop + endfacet + facet normal 0.843016 -0.267225 -0.466814 + outer loop + vertex -830.216 309.584 282.847 + vertex -827.749 317.388 282.834 + vertex -828.551 307.382 287.114 + endloop + endfacet + facet normal 0.850508 -0.262985 -0.455495 + outer loop + vertex -828.551 307.382 287.114 + vertex -827.749 317.388 282.834 + vertex -826.061 315.497 287.078 + endloop + endfacet + facet normal 0.867522 -0.282822 -0.409167 + outer loop + vertex -831.881 312.37 277.39 + vertex -829.415 319.966 277.368 + vertex -830.216 309.584 282.847 + endloop + endfacet + facet normal 0.874798 -0.277163 -0.397378 + outer loop + vertex -830.216 309.584 282.847 + vertex -829.415 319.966 277.368 + vertex -827.749 317.388 282.834 + endloop + endfacet + facet normal 0.893302 -0.299187 -0.335409 + outer loop + vertex -833.343 315.13 271.034 + vertex -830.878 322.54 270.99 + vertex -831.881 312.37 277.39 + endloop + endfacet + facet normal 0.899392 -0.292916 -0.324491 + outer loop + vertex -831.881 312.37 277.39 + vertex -830.878 322.54 270.99 + vertex -829.415 319.966 277.368 + endloop + endfacet + facet normal 0.913776 -0.312501 -0.25953 + outer loop + vertex -834.464 317.564 264.159 + vertex -832.008 324.796 264.098 + vertex -833.343 315.13 271.034 + endloop + endfacet + facet normal 0.91806 -0.30692 -0.250928 + outer loop + vertex -833.343 315.13 271.034 + vertex -832.008 324.796 264.098 + vertex -830.878 322.54 270.99 + endloop + endfacet + facet normal 0.925902 -0.323949 -0.194326 + outer loop + vertex -835.238 319.65 256.992 + vertex -832.784 326.707 256.918 + vertex -834.464 317.564 264.159 + endloop + endfacet + facet normal 0.930055 -0.317397 -0.185089 + outer loop + vertex -834.464 317.564 264.159 + vertex -832.784 326.707 256.918 + vertex -832.008 324.796 264.098 + endloop + endfacet + facet normal 0.841967 -0.256358 0.474734 + outer loop + vertex -828.299 307.892 56.8867 + vertex -825.984 315.76 57.0305 + vertex -829.941 310.208 61.0494 + endloop + endfacet + facet normal 0.8436 -0.261794 0.468832 + outer loop + vertex -829.941 310.208 61.0494 + vertex -825.984 315.76 57.0305 + vertex -827.67 317.657 61.122 + endloop + endfacet + facet normal 0.785353 -0.229848 0.574796 + outer loop + vertex -826.9 303.398 52.8649 + vertex -824.646 311.198 52.9042 + vertex -827.285 305.58 54.2638 + endloop + endfacet + facet normal 0.797889 -0.24114 0.552472 + outer loop + vertex -827.285 305.58 54.2638 + vertex -824.646 311.198 52.9042 + vertex -824.815 313.827 54.295 + endloop + endfacet + facet normal 0.812288 -0.285642 -0.508525 + outer loop + vertex -826.061 315.497 287.078 + vertex -823.298 323.325 287.094 + vertex -824.393 315.234 289.89 + endloop + endfacet + facet normal 0.809219 -0.286704 -0.512801 + outer loop + vertex -824.393 315.234 289.89 + vertex -823.298 323.325 287.094 + vertex -821.519 322.854 290.165 + endloop + endfacet + facet normal 0.83325 -0.299367 -0.464837 + outer loop + vertex -827.749 317.388 282.834 + vertex -824.993 325.041 282.845 + vertex -826.061 315.497 287.078 + endloop + endfacet + facet normal 0.840211 -0.295607 -0.454602 + outer loop + vertex -826.061 315.497 287.078 + vertex -824.993 325.041 282.845 + vertex -823.298 323.325 287.094 + endloop + endfacet + facet normal 0.854428 -0.318367 -0.410605 + outer loop + vertex -829.415 319.966 277.368 + vertex -826.654 327.389 277.358 + vertex -827.749 317.388 282.834 + endloop + endfacet + facet normal 0.864659 -0.310775 -0.394695 + outer loop + vertex -827.749 317.388 282.834 + vertex -826.654 327.389 277.358 + vertex -824.993 325.041 282.845 + endloop + endfacet + facet normal 0.878847 -0.337111 -0.337616 + outer loop + vertex -830.878 322.54 270.99 + vertex -828.12 329.744 270.977 + vertex -829.415 319.966 277.368 + endloop + endfacet + facet normal 0.886135 -0.330044 -0.325325 + outer loop + vertex -829.415 319.966 277.368 + vertex -828.12 329.744 270.977 + vertex -826.654 327.389 277.358 + endloop + endfacet + facet normal 0.896786 -0.355552 -0.263357 + outer loop + vertex -832.008 324.796 264.098 + vertex -829.244 331.785 264.073 + vertex -830.878 322.54 270.99 + endloop + endfacet + facet normal 0.904148 -0.346643 -0.24971 + outer loop + vertex -830.878 322.54 270.99 + vertex -829.244 331.785 264.073 + vertex -828.12 329.744 270.977 + endloop + endfacet + facet normal 0.834605 -0.280766 0.473924 + outer loop + vertex -825.984 315.76 57.0305 + vertex -824.18 322.023 57.563 + vertex -827.67 317.657 61.122 + endloop + endfacet + facet normal 0.839529 -0.303897 0.450375 + outer loop + vertex -827.67 317.657 61.122 + vertex -824.18 322.023 57.563 + vertex -825.05 324.848 61.0904 + endloop + endfacet + facet normal 0.76965 -0.259324 0.583429 + outer loop + vertex -824.646 311.198 52.9042 + vertex -821.82 319.529 52.8784 + vertex -824.815 313.827 54.295 + endloop + endfacet + facet normal 0.783021 -0.272371 0.559188 + outer loop + vertex -824.815 313.827 54.295 + vertex -821.82 319.529 52.8784 + vertex -821.905 322.859 54.6198 + endloop + endfacet + facet normal 0.800849 -0.311133 -0.5117 + outer loop + vertex -823.298 323.325 287.094 + vertex -820.301 330.987 287.127 + vertex -821.519 322.854 290.165 + endloop + endfacet + facet normal 0.807207 -0.308844 -0.503022 + outer loop + vertex -821.519 322.854 290.165 + vertex -820.301 330.987 287.127 + vertex -818.577 330.896 289.948 + endloop + endfacet + facet normal 0.824064 -0.32857 -0.461475 + outer loop + vertex -824.993 325.041 282.845 + vertex -821.994 332.534 282.867 + vertex -823.298 323.325 287.094 + endloop + endfacet + facet normal 0.832914 -0.323949 -0.448677 + outer loop + vertex -823.298 323.325 287.094 + vertex -821.994 332.534 282.867 + vertex -820.301 330.987 287.127 + endloop + endfacet + facet normal 0.844947 -0.349163 -0.405153 + outer loop + vertex -826.654 327.389 277.358 + vertex -823.647 334.654 277.369 + vertex -824.993 325.041 282.845 + endloop + endfacet + facet normal 0.855659 -0.341427 -0.38894 + outer loop + vertex -824.993 325.041 282.845 + vertex -823.647 334.654 277.369 + vertex -821.994 332.534 282.867 + endloop + endfacet + facet normal 0.865353 -0.371859 -0.335983 + outer loop + vertex -828.12 329.744 270.977 + vertex -825.103 336.762 270.98 + vertex -826.654 327.389 277.358 + endloop + endfacet + facet normal 0.87584 -0.362081 -0.319064 + outer loop + vertex -826.654 327.389 277.358 + vertex -825.103 336.762 270.98 + vertex -823.647 334.654 277.369 + endloop + endfacet + facet normal 0.883234 -0.390701 -0.259327 + outer loop + vertex -829.244 331.785 264.073 + vertex -826.233 338.587 264.08 + vertex -828.12 329.744 270.977 + endloop + endfacet + facet normal 0.890276 -0.382607 -0.247023 + outer loop + vertex -828.12 329.744 270.977 + vertex -826.233 338.587 264.08 + vertex -825.103 336.762 270.98 + endloop + endfacet + facet normal 0.822569 -0.327368 0.464985 + outer loop + vertex -824.18 322.023 57.563 + vertex -821.125 328.754 56.8963 + vertex -825.05 324.848 61.0904 + endloop + endfacet + facet normal 0.823041 -0.333273 0.459927 + outer loop + vertex -825.05 324.848 61.0904 + vertex -821.125 328.754 56.8963 + vertex -821.839 332.491 60.8837 + endloop + endfacet + facet normal 0.763538 -0.283784 0.580066 + outer loop + vertex -821.82 319.529 52.8784 + vertex -818.797 327.862 52.9768 + vertex -821.905 322.859 54.6198 + endloop + endfacet + facet normal 0.778793 -0.303467 0.548989 + outer loop + vertex -821.905 322.859 54.6198 + vertex -818.797 327.862 52.9768 + vertex -817.984 332.034 54.1296 + endloop + endfacet + facet normal 0.799246 -0.334961 -0.499006 + outer loop + vertex -820.301 330.987 287.127 + vertex -817.112 338.588 287.132 + vertex -818.577 330.896 289.948 + endloop + endfacet + facet normal 0.803218 -0.333685 -0.493453 + outer loop + vertex -818.577 330.896 289.948 + vertex -817.112 338.588 287.132 + vertex -815.32 338.382 290.189 + endloop + endfacet + facet normal 0.818173 -0.353424 -0.453524 + outer loop + vertex -821.994 332.534 282.867 + vertex -818.794 339.926 282.879 + vertex -820.301 330.987 287.127 + endloop + endfacet + facet normal 0.829363 -0.347639 -0.437383 + outer loop + vertex -820.301 330.987 287.127 + vertex -818.794 339.926 282.879 + vertex -817.112 338.588 287.132 + endloop + endfacet + facet normal 0.837498 -0.375776 -0.396723 + outer loop + vertex -823.647 334.654 277.369 + vertex -820.434 341.802 277.381 + vertex -821.994 332.534 282.867 + endloop + endfacet + facet normal 0.849583 -0.367143 -0.378702 + outer loop + vertex -821.994 332.534 282.867 + vertex -820.434 341.802 277.381 + vertex -818.794 339.926 282.879 + endloop + endfacet + facet normal 0.85653 -0.399324 -0.326952 + outer loop + vertex -825.103 336.762 270.98 + vertex -821.884 343.658 270.99 + vertex -823.647 334.654 277.369 + endloop + endfacet + facet normal 0.86739 -0.389363 -0.309889 + outer loop + vertex -823.647 334.654 277.369 + vertex -821.884 343.658 270.99 + vertex -820.434 341.802 277.381 + endloop + endfacet + facet normal 0.870229 -0.422024 -0.254161 + outer loop + vertex -826.233 338.587 264.08 + vertex -823.007 345.236 264.088 + vertex -825.103 336.762 270.98 + endloop + endfacet + facet normal 0.880449 -0.410632 -0.237047 + outer loop + vertex -825.103 336.762 270.98 + vertex -823.007 345.236 264.088 + vertex -821.884 343.658 270.99 + endloop + endfacet + facet normal 0.814425 -0.343324 0.467804 + outer loop + vertex -821.125 328.754 56.8963 + vertex -816.949 337.849 56.3016 + vertex -821.839 332.491 60.8837 + endloop + endfacet + facet normal 0.815705 -0.351951 0.459081 + outer loop + vertex -821.839 332.491 60.8837 + vertex -816.949 337.849 56.3016 + vertex -818.452 340.387 60.9181 + endloop + endfacet + facet normal 0.760479 -0.306402 0.57253 + outer loop + vertex -818.797 327.862 52.9768 + vertex -815.461 335.783 52.7846 + vertex -817.984 332.034 54.1296 + endloop + endfacet + facet normal 0.767374 -0.316355 0.557724 + outer loop + vertex -817.984 332.034 54.1296 + vertex -815.461 335.783 52.7846 + vertex -814.817 338.889 53.6604 + endloop + endfacet + facet normal 0.79603 -0.354411 -0.490642 + outer loop + vertex -817.112 338.588 287.132 + vertex -813.757 346.169 287.098 + vertex -815.32 338.382 290.189 + endloop + endfacet + facet normal 0.806136 -0.35083 -0.476512 + outer loop + vertex -815.32 338.382 290.189 + vertex -813.757 346.169 287.098 + vertex -812.018 346.367 289.896 + endloop + endfacet + facet normal 0.815995 -0.37433 -0.440488 + outer loop + vertex -818.794 339.926 282.879 + vertex -815.435 347.267 282.863 + vertex -817.112 338.588 287.132 + endloop + endfacet + facet normal 0.827801 -0.368165 -0.423319 + outer loop + vertex -817.112 338.588 287.132 + vertex -815.435 347.267 282.863 + vertex -813.757 346.169 287.098 + endloop + endfacet + facet normal 0.833238 -0.397604 -0.38422 + outer loop + vertex -820.434 341.802 277.381 + vertex -817.06 348.879 277.376 + vertex -818.794 339.926 282.879 + endloop + endfacet + facet normal 0.846434 -0.388097 -0.364595 + outer loop + vertex -818.794 339.926 282.879 + vertex -817.06 348.879 277.376 + vertex -815.435 347.267 282.863 + endloop + endfacet + facet normal 0.849752 -0.422372 -0.315475 + outer loop + vertex -821.884 343.658 270.99 + vertex -818.498 350.47 270.99 + vertex -820.434 341.802 277.381 + endloop + endfacet + facet normal 0.861919 -0.411211 -0.29665 + outer loop + vertex -820.434 341.802 277.381 + vertex -818.498 350.47 270.99 + vertex -817.06 348.879 277.376 + endloop + endfacet + facet normal 0.862221 -0.445017 -0.24194 + outer loop + vertex -823.007 345.236 264.088 + vertex -819.618 351.799 264.09 + vertex -821.884 343.658 270.99 + endloop + endfacet + facet normal 0.872483 -0.433668 -0.225181 + outer loop + vertex -821.884 343.658 270.99 + vertex -819.618 351.799 264.09 + vertex -818.498 350.47 270.99 + endloop + endfacet + facet normal 0.814621 -0.353678 0.459678 + outer loop + vertex -816.949 337.849 56.3016 + vertex -813.601 346.421 56.9632 + vertex -818.452 340.387 60.9181 + endloop + endfacet + facet normal 0.818665 -0.370801 0.438514 + outer loop + vertex -818.452 340.387 60.9181 + vertex -813.601 346.421 56.9632 + vertex -815.278 347.687 61.1649 + endloop + endfacet + facet normal 0.750482 -0.318825 0.578901 + outer loop + vertex -815.461 335.783 52.7846 + vertex -812.34 343.243 52.8468 + vertex -814.817 338.889 53.6604 + endloop + endfacet + facet normal 0.770989 -0.337784 0.539887 + outer loop + vertex -814.817 338.889 53.6604 + vertex -812.34 343.243 52.8468 + vertex -812.328 345.332 54.137 + endloop + endfacet + facet normal 0.799372 -0.373405 -0.470715 + outer loop + vertex -813.757 346.169 287.098 + vertex -810.241 353.752 287.054 + vertex -812.018 346.367 289.896 + endloop + endfacet + facet normal 0.80263 -0.372364 -0.465973 + outer loop + vertex -812.018 346.367 289.896 + vertex -810.241 353.752 287.054 + vertex -808.347 354.038 290.088 + endloop + endfacet + facet normal 0.815848 -0.392305 -0.424839 + outer loop + vertex -815.435 347.267 282.863 + vertex -811.938 354.563 282.84 + vertex -813.757 346.169 287.098 + endloop + endfacet + facet normal 0.827519 -0.386093 -0.407609 + outer loop + vertex -813.757 346.169 287.098 + vertex -811.938 354.563 282.84 + vertex -810.241 353.752 287.054 + endloop + endfacet + facet normal 0.83109 -0.416597 -0.368424 + outer loop + vertex -817.06 348.879 277.376 + vertex -813.557 355.885 277.353 + vertex -815.435 347.267 282.863 + endloop + endfacet + facet normal 0.845253 -0.406151 -0.347259 + outer loop + vertex -815.435 347.267 282.863 + vertex -813.557 355.885 277.353 + vertex -811.938 354.563 282.84 + endloop + endfacet + facet normal 0.845813 -0.440855 -0.300411 + outer loop + vertex -818.498 350.47 270.99 + vertex -814.988 357.211 270.981 + vertex -817.06 348.879 277.376 + endloop + endfacet + facet normal 0.857827 -0.429685 -0.281965 + outer loop + vertex -817.06 348.879 277.376 + vertex -814.988 357.211 270.981 + vertex -813.557 355.885 277.353 + endloop + endfacet + facet normal 0.855719 -0.464322 -0.228364 + outer loop + vertex -819.618 351.799 264.09 + vertex -816.099 358.289 264.082 + vertex -818.498 350.47 270.99 + endloop + endfacet + facet normal 0.867009 -0.45177 -0.210238 + outer loop + vertex -818.498 350.47 270.99 + vertex -816.099 358.289 264.082 + vertex -814.988 357.211 270.981 + endloop + endfacet + facet normal 0.818703 -0.370724 0.438507 + outer loop + vertex -813.601 346.421 56.9632 + vertex -811.202 352.523 57.6435 + vertex -815.278 347.687 61.1649 + endloop + endfacet + facet normal 0.822369 -0.3948 0.409685 + outer loop + vertex -815.278 347.687 61.1649 + vertex -811.202 352.523 57.6435 + vertex -811.967 354.58 61.1618 + endloop + endfacet + facet normal 0.763998 -0.342153 0.547027 + outer loop + vertex -812.34 343.243 52.8468 + vertex -808.863 351.103 52.9078 + vertex -812.328 345.332 54.137 + endloop + endfacet + facet normal 0.775912 -0.354706 0.521675 + outer loop + vertex -812.328 345.332 54.137 + vertex -808.863 351.103 52.9078 + vertex -808.74 353.976 54.6772 + endloop + endfacet + facet normal 0.798965 -0.384312 -0.462558 + outer loop + vertex -810.241 353.752 287.054 + vertex -806.569 361.358 287.079 + vertex -808.347 354.038 290.088 + endloop + endfacet + facet normal 0.812814 -0.37928 -0.442131 + outer loop + vertex -808.347 354.038 290.088 + vertex -806.569 361.358 287.079 + vertex -804.706 362.148 289.825 + endloop + endfacet + facet normal 0.817456 -0.406994 -0.40758 + outer loop + vertex -811.938 354.563 282.84 + vertex -808.298 361.857 282.859 + vertex -810.241 353.752 287.054 + endloop + endfacet + facet normal 0.830588 -0.399823 -0.387641 + outer loop + vertex -810.241 353.752 287.054 + vertex -808.298 361.857 282.859 + vertex -806.569 361.358 287.079 + endloop + endfacet + facet normal 0.832074 -0.430845 -0.349322 + outer loop + vertex -813.557 355.885 277.353 + vertex -809.949 362.84 277.37 + vertex -811.938 354.563 282.84 + endloop + endfacet + facet normal 0.845047 -0.420972 -0.329664 + outer loop + vertex -811.938 354.563 282.84 + vertex -809.949 362.84 277.37 + vertex -808.298 361.857 282.859 + endloop + endfacet + facet normal 0.842597 -0.457384 -0.284305 + outer loop + vertex -814.988 357.211 270.981 + vertex -811.378 363.862 270.978 + vertex -813.557 355.885 277.353 + endloop + endfacet + facet normal 0.856764 -0.44387 -0.262555 + outer loop + vertex -813.557 355.885 277.353 + vertex -811.378 363.862 270.978 + vertex -809.949 362.84 277.37 + endloop + endfacet + facet normal 0.851731 -0.479152 -0.212058 + outer loop + vertex -816.099 358.289 264.082 + vertex -812.492 364.703 264.08 + vertex -814.988 357.211 270.981 + endloop + endfacet + facet normal 0.861825 -0.46778 -0.196061 + outer loop + vertex -814.988 357.211 270.981 + vertex -812.492 364.703 264.08 + vertex -811.378 363.862 270.978 + endloop + endfacet + facet normal 0.818426 -0.400424 0.412116 + outer loop + vertex -811.202 352.523 57.6435 + vertex -807.608 359.19 56.9849 + vertex -811.967 354.58 61.1618 + endloop + endfacet + facet normal 0.818752 -0.409525 0.402411 + outer loop + vertex -811.967 354.58 61.1618 + vertex -807.608 359.19 56.9849 + vertex -808.187 361.914 60.935 + endloop + endfacet + facet normal 0.772033 -0.357077 0.525795 + outer loop + vertex -808.863 351.103 52.9078 + vertex -805.17 359.287 53.0425 + vertex -808.74 353.976 54.6772 + endloop + endfacet + facet normal 0.778547 -0.366482 0.509466 + outer loop + vertex -808.74 353.976 54.6772 + vertex -805.17 359.287 53.0425 + vertex -804.146 363.103 54.2227 + endloop + endfacet + facet normal 0.811255 -0.386052 -0.439124 + outer loop + vertex -806.569 361.358 287.079 + vertex -802.878 368.809 287.345 + vertex -804.706 362.148 289.825 + endloop + endfacet + facet normal 0.818076 -0.383873 -0.428244 + outer loop + vertex -804.706 362.148 289.825 + vertex -802.878 368.809 287.345 + vertex -801.201 369.177 290.219 + endloop + endfacet + facet normal 0.825315 -0.411349 -0.386843 + outer loop + vertex -808.298 361.857 282.859 + vertex -804.509 369.285 283.042 + vertex -806.569 361.358 287.079 + endloop + endfacet + facet normal 0.840097 -0.403057 -0.363018 + outer loop + vertex -806.569 361.358 287.079 + vertex -804.509 369.285 283.042 + vertex -802.878 368.809 287.345 + endloop + endfacet + facet normal 0.835374 -0.439543 -0.33008 + outer loop + vertex -809.949 362.84 277.37 + vertex -806.249 369.812 277.451 + vertex -808.298 361.857 282.859 + endloop + endfacet + facet normal 0.851405 -0.426667 -0.305066 + outer loop + vertex -808.298 361.857 282.859 + vertex -806.249 369.812 277.451 + vertex -804.509 369.285 283.042 + endloop + endfacet + facet normal 0.845463 -0.46459 -0.263341 + outer loop + vertex -811.378 363.862 270.978 + vertex -807.717 370.484 271.049 + vertex -809.949 362.84 277.37 + endloop + endfacet + facet normal 0.857714 -0.452394 -0.244268 + outer loop + vertex -809.949 362.84 277.37 + vertex -807.717 370.484 271.049 + vertex -806.249 369.812 277.451 + endloop + endfacet + facet normal 0.850449 -0.487907 -0.196678 + outer loop + vertex -812.492 364.703 264.08 + vertex -808.836 371.057 264.122 + vertex -811.378 363.862 270.978 + endloop + endfacet + facet normal 0.861923 -0.474597 -0.178456 + outer loop + vertex -811.378 363.862 270.978 + vertex -808.836 371.057 264.122 + vertex -807.717 370.484 271.049 + endloop + endfacet + facet normal 0.824976 -0.401482 0.397777 + outer loop + vertex -807.608 359.19 56.9849 + vertex -802.896 368.231 56.3377 + vertex -808.187 361.914 60.935 + endloop + endfacet + facet normal 0.826 -0.411415 0.385308 + outer loop + vertex -808.187 361.914 60.935 + vertex -802.896 368.231 56.3377 + vertex -804.338 369.577 60.8658 + endloop + endfacet + facet normal 0.779532 -0.366316 0.508077 + outer loop + vertex -805.17 359.287 53.0425 + vertex -801.333 367.198 52.8591 + vertex -804.146 363.103 54.2227 + endloop + endfacet + facet normal 0.774915 -0.359133 0.520125 + outer loop + vertex -804.146 363.103 54.2227 + vertex -801.333 367.198 52.8591 + vertex -800.574 370.091 53.726 + endloop + endfacet + facet normal 0.825322 -0.359278 -0.435617 + outer loop + vertex -802.878 368.809 287.345 + vertex -799.755 375.007 288.152 + vertex -801.201 369.177 290.219 + endloop + endfacet + facet normal 0.825243 -0.359304 -0.435746 + outer loop + vertex -801.201 369.177 290.219 + vertex -799.755 375.007 288.152 + vertex -798.233 376.104 290.129 + endloop + endfacet + facet normal 0.85098 -0.378214 -0.364399 + outer loop + vertex -804.509 369.285 283.042 + vertex -800.497 377.539 283.847 + vertex -802.878 368.809 287.345 + endloop + endfacet + facet normal 0.848275 -0.379468 -0.369368 + outer loop + vertex -802.878 368.809 287.345 + vertex -800.497 377.539 283.847 + vertex -799.755 375.007 288.152 + endloop + endfacet + facet normal 0.857522 -0.413732 -0.305748 + outer loop + vertex -806.249 369.812 277.451 + vertex -802.693 377.05 277.629 + vertex -804.509 369.285 283.042 + endloop + endfacet + facet normal 0.874362 -0.398041 -0.277587 + outer loop + vertex -804.509 369.285 283.042 + vertex -802.693 377.05 277.629 + vertex -800.497 377.539 283.847 + endloop + endfacet + facet normal 0.862879 -0.442388 -0.244403 + outer loop + vertex -807.717 370.484 271.049 + vertex -804.209 377.245 271.2 + vertex -806.249 369.812 277.451 + endloop + endfacet + facet normal 0.877727 -0.425773 -0.219802 + outer loop + vertex -806.249 369.812 277.451 + vertex -804.209 377.245 271.2 + vertex -802.693 377.05 277.629 + endloop + endfacet + facet normal 0.866475 -0.466218 -0.178498 + outer loop + vertex -808.836 371.057 264.122 + vertex -805.332 377.51 264.28 + vertex -807.717 370.484 271.049 + endloop + endfacet + facet normal 0.877628 -0.45194 -0.159747 + outer loop + vertex -807.717 370.484 271.049 + vertex -805.332 377.51 264.28 + vertex -804.209 377.245 271.2 + endloop + endfacet + facet normal 0.843266 -0.378964 0.381168 + outer loop + vertex -802.896 368.231 56.3377 + vertex -799.208 376.75 56.6465 + vertex -804.338 369.577 60.8658 + endloop + endfacet + facet normal 0.845822 -0.392463 0.361328 + outer loop + vertex -804.338 369.577 60.8658 + vertex -799.208 376.75 56.6465 + vertex -800.885 377.096 60.95 + endloop + endfacet + facet normal 0.797463 -0.355314 0.487652 + outer loop + vertex -801.333 367.198 52.8591 + vertex -797.771 375.097 52.7894 + vertex -800.574 370.091 53.726 + endloop + endfacet + facet normal 0.782651 -0.340804 0.520873 + outer loop + vertex -800.574 370.091 53.726 + vertex -797.771 375.097 52.7894 + vertex -797.939 376.566 54.0027 + endloop + endfacet + facet normal 0.906027 -0.302189 -0.296307 + outer loop + vertex -802.693 377.05 277.629 + vertex -800.151 384.545 277.757 + vertex -800.497 377.539 283.847 + endloop + endfacet + facet normal 0.918184 -0.284689 -0.275484 + outer loop + vertex -800.497 377.539 283.847 + vertex -800.151 384.545 277.757 + vertex -798.384 384.625 283.564 + endloop + endfacet + facet normal 0.914793 -0.334921 -0.225793 + outer loop + vertex -804.209 377.245 271.2 + vertex -801.523 384.472 271.36 + vertex -802.693 377.05 277.629 + endloop + endfacet + facet normal 0.929713 -0.311928 -0.195791 + outer loop + vertex -802.693 377.05 277.629 + vertex -801.523 384.472 271.36 + vertex -800.151 384.545 277.757 + endloop + endfacet + facet normal 0.9174 -0.363143 -0.1628 + outer loop + vertex -805.332 377.51 264.28 + vertex -802.509 384.408 264.801 + vertex -804.209 377.245 271.2 + endloop + endfacet + facet normal 0.929612 -0.342397 -0.136332 + outer loop + vertex -804.209 377.245 271.2 + vertex -802.509 384.408 264.801 + vertex -801.523 384.472 271.36 + endloop + endfacet + facet normal 0.878127 -0.306898 0.367025 + outer loop + vertex -799.208 376.75 56.6465 + vertex -796.267 384.707 56.2643 + vertex -800.885 377.096 60.95 + endloop + endfacet + facet normal 0.877246 -0.30319 0.372177 + outer loop + vertex -800.885 377.096 60.95 + vertex -796.267 384.707 56.2643 + vertex -798.325 384.627 61.051 + endloop + endfacet + facet normal 0.825345 -0.300506 0.478018 + outer loop + vertex -797.771 375.097 52.7894 + vertex -794.278 384.776 52.8438 + vertex -797.939 376.566 54.0027 + endloop + endfacet + facet normal 0.801881 -0.283262 0.52607 + outer loop + vertex -797.939 376.566 54.0027 + vertex -794.278 384.776 52.8438 + vertex -794.393 384.772 53.016 + endloop + endfacet + facet normal -0.0945259 -0.692481 -0.715216 + outer loop + vertex -846.477 242.734 295.985 + vertex -848.286 242.207 296.733 + vertex -846.949 242.749 296.033 + endloop + endfacet + facet normal 0.0669085 -0.74806 -0.66025 + outer loop + vertex -844.961 243.343 295.448 + vertex -846.477 242.734 295.985 + vertex -845.542 243.162 295.594 + endloop + endfacet + facet normal 0.306825 -0.788959 -0.532356 + outer loop + vertex -843.481 244.267 294.932 + vertex -844.961 243.343 295.448 + vertex -844.074 243.936 295.081 + endloop + endfacet + facet normal 0.483589 -0.720314 -0.497282 + outer loop + vertex -842.086 245.541 294.444 + vertex -843.481 244.267 294.932 + vertex -842.642 245.073 294.581 + endloop + endfacet + facet normal 0.474149 -0.579529 -0.662819 + outer loop + vertex -840.831 247.07 294.004 + vertex -842.086 245.541 294.444 + vertex -841.307 246.544 294.123 + endloop + endfacet + facet normal 0.573454 -0.506468 -0.643926 + outer loop + vertex -839.744 248.776 293.63 + vertex -840.831 247.07 294.004 + vertex -840.143 248.2 293.727 + endloop + endfacet + facet normal 0.785758 -0.259602 0.561419 + outer loop + vertex -838.561 251.457 293.214 + vertex -839.744 248.776 293.63 + vertex -839.398 249.498 293.48 + endloop + endfacet + facet normal 0.622124 -0.311009 -0.718495 + outer loop + vertex -836.976 255.768 292.721 + vertex -838.561 251.457 293.214 + vertex -837.907 254.008 292.676 + endloop + endfacet + facet normal 0.629477 -0.25998 -0.732236 + outer loop + vertex -835.812 259.509 292.393 + vertex -836.976 255.768 292.721 + vertex -836.35 258.542 292.274 + endloop + endfacet + facet normal 0.810275 -0.224149 -0.541491 + outer loop + vertex -835.199 262.267 292.169 + vertex -835.812 259.509 292.393 + vertex -835.612 260.759 292.175 + endloop + endfacet + facet normal 0.675447 -0.152556 -0.721456 + outer loop + vertex -834.332 266.499 292.085 + vertex -835.199 262.267 292.169 + vertex -835.474 263.313 291.69 + endloop + endfacet + facet normal 0.775754 -0.163186 -0.609571 + outer loop + vertex -833.471 271.312 291.893 + vertex -834.332 266.499 292.085 + vertex -834.399 272.206 290.472 + endloop + endfacet + facet normal 0.7821 -0.14933 -0.604996 + outer loop + vertex -832.921 275.126 291.662 + vertex -833.471 271.312 291.893 + vertex -834.399 272.206 290.472 + endloop + endfacet + facet normal 0.792864 -0.15673 -0.588899 + outer loop + vertex -831.839 279.306 292.007 + vertex -832.921 275.126 291.662 + vertex -832.618 281.897 290.269 + endloop + endfacet + facet normal 0.799707 -0.149666 -0.581436 + outer loop + vertex -831.133 284.844 291.552 + vertex -831.839 279.306 292.007 + vertex -832.618 281.897 290.269 + endloop + endfacet + facet normal 0.801301 -0.169968 -0.573609 + outer loop + vertex -829.822 290.566 291.689 + vertex -831.133 284.844 291.552 + vertex -831.074 290.479 289.965 + endloop + endfacet + facet normal 0.820589 -0.179711 -0.542529 + outer loop + vertex -828.818 295.036 291.726 + vertex -829.822 290.566 291.689 + vertex -829.202 297.898 290.197 + endloop + endfacet + facet normal 0.789909 -0.203104 -0.578613 + outer loop + vertex -827.604 299.74 291.732 + vertex -828.818 295.036 291.726 + vertex -829.202 297.898 290.197 + endloop + endfacet + facet normal 0.785589 -0.214877 -0.580239 + outer loop + vertex -825.932 305.409 291.897 + vertex -827.604 299.74 291.732 + vertex -826.839 306.771 290.164 + endloop + endfacet + facet normal 0.780525 -0.22302 -0.583989 + outer loop + vertex -824.91 310.212 291.428 + vertex -825.932 305.409 291.897 + vertex -826.839 306.771 290.164 + endloop + endfacet + facet normal 0.769936 -0.258 -0.58364 + outer loop + vertex -822.804 315.965 291.664 + vertex -824.91 310.212 291.428 + vertex -824.393 315.234 289.89 + endloop + endfacet + facet normal 0.7676 -0.269624 -0.581458 + outer loop + vertex -820.66 321.466 291.943 + vertex -822.804 315.965 291.664 + vertex -821.519 322.854 290.165 + endloop + endfacet + facet normal 0.764127 -0.274628 -0.583686 + outer loop + vertex -819.339 326.097 291.493 + vertex -820.66 321.466 291.943 + vertex -821.519 322.854 290.165 + endloop + endfacet + facet normal 0.761723 -0.304948 -0.571652 + outer loop + vertex -816.923 331.705 291.721 + vertex -819.339 326.097 291.493 + vertex -818.577 330.896 289.948 + endloop + endfacet + facet normal 0.762663 -0.313029 -0.566002 + outer loop + vertex -814.509 337.148 291.963 + vertex -816.923 331.705 291.721 + vertex -815.32 338.382 290.189 + endloop + endfacet + facet normal 0.762078 -0.313874 -0.566322 + outer loop + vertex -813.009 341.674 291.474 + vertex -814.509 337.148 291.963 + vertex -815.32 338.382 290.189 + endloop + endfacet + facet normal 0.765264 -0.344464 -0.543798 + outer loop + vertex -810.396 347.183 291.661 + vertex -813.009 341.674 291.474 + vertex -812.018 346.367 289.896 + endloop + endfacet + facet normal 0.76443 -0.352359 -0.539898 + outer loop + vertex -807.73 352.601 291.899 + vertex -810.396 347.183 291.661 + vertex -808.347 354.038 290.088 + endloop + endfacet + facet normal 0.764315 -0.352499 -0.53997 + outer loop + vertex -805.355 358.293 291.546 + vertex -807.73 352.601 291.899 + vertex -808.347 354.038 290.088 + endloop + endfacet + facet normal 0.781638 -0.359193 -0.509924 + outer loop + vertex -802.995 363.747 291.321 + vertex -805.355 358.293 291.546 + vertex -804.706 362.148 289.825 + endloop + endfacet + facet normal 0.770289 -0.36112 -0.525592 + outer loop + vertex -800.73 367.791 291.863 + vertex -802.995 363.747 291.321 + vertex -801.201 369.177 290.219 + endloop + endfacet + facet normal 0.780981 -0.348675 -0.518164 + outer loop + vertex -798.386 373.16 291.782 + vertex -800.73 367.791 291.863 + vertex -801.201 369.177 290.219 + endloop + endfacet + facet normal 0.798411 -0.325847 -0.506324 + outer loop + vertex -795.673 379.842 291.76 + vertex -798.386 373.16 291.782 + vertex -798.233 376.104 290.129 + endloop + endfacet + facet normal 0.844897 -0.224434 -0.485571 + outer loop + vertex -794.163 384.78 292.105 + vertex -795.673 379.842 291.76 + vertex -796.398 384.702 288.252 + endloop + endfacet + facet normal 0.806117 -0.246932 0.537773 + outer loop + vertex -795.203 379.625 51.8645 + vertex -794.163 384.78 52.6728 + vertex -794.278 384.776 52.8438 + endloop + endfacet + facet normal 0.753911 -0.309171 0.579682 + outer loop + vertex -798.333 372.62 52.2001 + vertex -795.203 379.625 51.8645 + vertex -797.771 375.097 52.7894 + endloop + endfacet + facet normal 0.724577 -0.327097 0.606626 + outer loop + vertex -800.818 367.229 52.2612 + vertex -798.333 372.62 52.2001 + vertex -801.333 367.198 52.8591 + endloop + endfacet + facet normal 0.721705 -0.338915 0.603555 + outer loop + vertex -803.047 362.811 52.4446 + vertex -800.818 367.229 52.2612 + vertex -801.333 367.198 52.8591 + endloop + endfacet + facet normal 0.734013 -0.342847 0.586243 + outer loop + vertex -805.522 357.223 52.2764 + vertex -803.047 362.811 52.4446 + vertex -805.17 359.287 53.0425 + endloop + endfacet + facet normal 0.72586 -0.334272 0.601157 + outer loop + vertex -807.984 351.611 52.1292 + vertex -805.522 357.223 52.2764 + vertex -808.863 351.103 52.9078 + endloop + endfacet + facet normal 0.725684 -0.330201 0.603614 + outer loop + vertex -810.284 346.94 52.338 + vertex -807.984 351.611 52.1292 + vertex -808.863 351.103 52.9078 + endloop + endfacet + facet normal 0.709915 -0.30763 0.633549 + outer loop + vertex -812.562 341.457 52.2286 + vertex -810.284 346.94 52.338 + vertex -812.34 343.243 52.8468 + endloop + endfacet + facet normal 0.700092 -0.293927 0.650752 + outer loop + vertex -814.811 335.939 52.1562 + vertex -812.562 341.457 52.2286 + vertex -815.461 335.783 52.7846 + endloop + endfacet + facet normal 0.700605 -0.288489 0.652631 + outer loop + vertex -816.91 331.343 52.3771 + vertex -814.811 335.939 52.1562 + vertex -815.461 335.783 52.7846 + endloop + endfacet + facet normal 0.711682 -0.274484 0.646659 + outer loop + vertex -818.969 325.687 52.2429 + vertex -816.91 331.343 52.3771 + vertex -818.797 327.862 52.9768 + endloop + endfacet + facet normal 0.712417 -0.262598 0.650772 + outer loop + vertex -820.969 319.932 52.1102 + vertex -818.969 325.687 52.2429 + vertex -821.82 319.529 52.8784 + endloop + endfacet + facet normal 0.711803 -0.252264 0.655514 + outer loop + vertex -822.852 315.14 52.3101 + vertex -820.969 319.932 52.1102 + vertex -821.82 319.529 52.8784 + endloop + endfacet + facet normal 0.717113 -0.227138 0.658907 + outer loop + vertex -824.596 309.389 52.2258 + vertex -822.852 315.14 52.3101 + vertex -824.646 311.198 52.9042 + endloop + endfacet + facet normal 0.77569 -0.235922 0.585359 + outer loop + vertex -826.001 304.834 52.2519 + vertex -824.596 309.389 52.2258 + vertex -826.9 303.398 52.8649 + endloop + endfacet + facet normal 0.750218 -0.200951 0.629914 + outer loop + vertex -827.224 300.295 52.2601 + vertex -826.001 304.834 52.2519 + vertex -826.9 303.398 52.8649 + endloop + endfacet + facet normal 0.796056 -0.205817 0.569152 + outer loop + vertex -828.433 295.729 52.3003 + vertex -827.224 300.295 52.2601 + vertex -829.138 294.759 52.9356 + endloop + endfacet + facet normal 0.778048 -0.169249 0.604976 + outer loop + vertex -829.49 290.836 52.2909 + vertex -828.433 295.729 52.3003 + vertex -829.138 294.759 52.9356 + endloop + endfacet + facet normal 0.765168 -0.159871 0.623666 + outer loop + vertex -830.863 284.487 52.3478 + vertex -829.49 290.836 52.2909 + vertex -831.016 286.312 53.0034 + endloop + endfacet + facet normal 0.744713 -0.142651 0.651961 + outer loop + vertex -831.521 279.821 52.0783 + vertex -830.863 284.487 52.3478 + vertex -832.412 278.127 52.726 + endloop + endfacet + facet normal 0.746678 -0.144721 0.649251 + outer loop + vertex -832.597 274.694 52.1734 + vertex -831.521 279.821 52.0783 + vertex -832.412 278.127 52.726 + endloop + endfacet + facet normal 0.706085 -0.141517 0.693842 + outer loop + vertex -833.326 270.215 52.0017 + vertex -832.597 274.694 52.1734 + vertex -833.804 269.618 52.3662 + endloop + endfacet + facet normal 0.710132 -0.148138 0.688308 + outer loop + vertex -834.299 265.79 52.0535 + vertex -833.326 270.215 52.0017 + vertex -833.804 269.618 52.3662 + endloop + endfacet + facet normal 0.147127 -0.0669232 0.986851 + outer loop + vertex -835.073 262.016 51.9129 + vertex -834.299 265.79 52.0535 + vertex -835.088 262.591 51.9541 + endloop + endfacet + facet normal 0.681336 -0.216701 0.699157 + outer loop + vertex -835.769 259.047 51.6715 + vertex -835.073 262.016 51.9129 + vertex -835.62 259.755 51.745 + endloop + endfacet + facet normal 0.876968 -0.294519 0.379719 + outer loop + vertex -836.677 255.8 51.2491 + vertex -835.769 259.047 51.6715 + vertex -836.494 256.549 51.4068 + endloop + endfacet + facet normal 0.819924 -0.329762 0.467954 + outer loop + vertex -838.099 251.35 50.6045 + vertex -836.677 255.8 51.2491 + vertex -837.623 253.001 50.9341 + endloop + endfacet + facet normal 0.831148 -0.401101 0.385111 + outer loop + vertex -839.122 248.755 50.1097 + vertex -838.099 251.35 50.6045 + vertex -838.993 249.151 50.2452 + endloop + endfacet + facet normal 0.869055 -0.494575 -0.0117974 + outer loop + vertex -840.209 246.858 49.5491 + vertex -839.122 248.755 50.1097 + vertex -839.862 247.461 49.802 + endloop + endfacet + facet normal 0.76601 -0.46194 -0.447035 + outer loop + vertex -841.901 244.872 48.7024 + vertex -840.209 246.858 49.5491 + vertex -841.066 245.779 49.1949 + endloop + endfacet + facet normal 0.319598 -0.773637 0.547122 + outer loop + vertex -843.832 243.42 47.7771 + vertex -841.901 244.872 48.7024 + vertex -843.531 243.696 47.9921 + endloop + endfacet + facet normal 0.121017 -0.798263 0.590027 + outer loop + vertex -845.324 242.676 47.0767 + vertex -843.832 243.42 47.7771 + vertex -844.953 242.915 47.3248 + endloop + endfacet + facet normal 0.0618214 -0.878341 0.47402 + outer loop + vertex -846.708 242.159 46.2995 + vertex -845.324 242.676 47.0767 + vertex -845.943 242.517 46.8635 + endloop + endfacet + facet normal -0.116844 -0.695075 0.709379 + outer loop + vertex -847.794 244.315 48.2335 + vertex -846.708 242.159 46.2995 + vertex -847.244 243.376 47.4041 + endloop + endfacet + facet normal 0.334982 -0.593396 0.731894 + outer loop + vertex -848.682 246.477 50.3927 + vertex -847.794 244.315 48.2335 + vertex -848.094 245.277 49.1505 + endloop + endfacet + facet normal 0.461905 -0.581859 0.669391 + outer loop + vertex -849.567 248.772 52.9978 + vertex -848.682 246.477 50.3927 + vertex -849.117 247.826 51.8654 + endloop + endfacet + facet normal 0.0478755 -0.776415 0.628401 + outer loop + vertex -850.442 251.193 56.0564 + vertex -849.567 248.772 52.9978 + vertex -849.644 249.842 54.3267 + endloop + endfacet + facet normal 0.109456 -0.795067 0.596563 + outer loop + vertex -851.303 253.67 59.5155 + vertex -850.442 251.193 56.0564 + vertex -850.584 252.474 57.7897 + endloop + endfacet + facet normal 0.135863 -0.82169 0.553505 + outer loop + vertex -852.065 256.046 63.2291 + vertex -851.303 253.67 59.5155 + vertex -851.368 254.83 61.2527 + endloop + endfacet + facet normal 0.136755 -0.84975 0.50914 + outer loop + vertex -852.864 258.683 67.8459 + vertex -852.065 256.046 63.2291 + vertex -852.027 257.02 64.8444 + endloop + endfacet + facet normal 0.0998079 -0.884513 0.455715 + outer loop + vertex -853.481 261.229 72.922 + vertex -852.864 258.683 67.8459 + vertex -852.865 260.386 71.1518 + endloop + endfacet + facet normal 0.0811969 -0.909274 0.408202 + outer loop + vertex -853.863 263.202 77.394 + vertex -853.481 261.229 72.922 + vertex -853.235 262.227 75.0957 + endloop + endfacet + facet normal 0.0823614 -0.925575 0.369497 + outer loop + vertex -854.2 265.254 82.6085 + vertex -853.863 263.202 77.394 + vertex -853.508 263.9 79.0612 + endloop + endfacet + facet normal 0.076238 -0.939333 0.334427 + outer loop + vertex -854.535 267.332 88.5223 + vertex -854.2 265.254 82.6085 + vertex -853.839 266.453 85.8922 + endloop + endfacet + facet normal 0.0575486 -0.953585 0.295574 + outer loop + vertex -854.426 268.911 93.5945 + vertex -854.535 267.332 88.5223 + vertex -853.946 267.85 90.077 + endloop + endfacet + facet normal 0.0549061 -0.959638 0.275825 + outer loop + vertex -854.645 270.297 98.4601 + vertex -854.426 268.911 93.5945 + vertex -854.029 269.874 96.8638 + endloop + endfacet + facet normal 0.0511116 -0.968712 0.242866 + outer loop + vertex -854.577 271.705 104.063 + vertex -854.645 270.297 98.4601 + vertex -854.052 271.003 101.148 + endloop + endfacet + facet normal 0.0606408 -0.974855 0.214429 + outer loop + vertex -854.328 272.803 108.981 + vertex -854.577 271.705 104.063 + vertex -854.018 272.043 105.438 + endloop + endfacet + facet normal 0.058047 -0.977928 0.200717 + outer loop + vertex -854.377 273.728 113.504 + vertex -854.328 272.803 108.981 + vertex -853.948 273.507 112.301 + endloop + endfacet + facet normal 0.0418191 -0.98258 0.181075 + outer loop + vertex -854.225 274.494 117.622 + vertex -854.377 273.728 113.504 + vertex -853.869 274.273 116.345 + endloop + endfacet + facet normal -0.0210351 -0.984505 0.17409 + outer loop + vertex -854.303 274.995 120.45 + vertex -854.225 274.494 117.622 + vertex -853.823 275.006 120.566 + endloop + endfacet + facet normal -0.017233 -0.987182 0.158664 + outer loop + vertex -854.089 275.441 123.245 + vertex -854.303 274.995 120.45 + vertex -853.823 275.006 120.566 + endloop + endfacet + facet normal 0.0143654 -0.988786 0.148646 + outer loop + vertex -854.029 275.842 125.909 + vertex -854.089 275.441 123.245 + vertex -853.71 275.629 124.46 + endloop + endfacet + facet normal 0.00335455 -0.989922 0.141573 + outer loop + vertex -854.079 276.284 128.999 + vertex -854.029 275.842 125.909 + vertex -853.655 276.149 128.043 + endloop + endfacet + facet normal -0.0159865 -0.991405 0.129845 + outer loop + vertex -854.015 276.678 132.016 + vertex -854.079 276.284 128.999 + vertex -853.619 276.686 132.124 + endloop + endfacet + facet normal -0.0135436 -0.992559 0.121007 + outer loop + vertex -853.968 277.035 134.949 + vertex -854.015 276.678 132.016 + vertex -853.619 276.686 132.124 + endloop + endfacet + facet normal 0.017234 -0.993896 0.108965 + outer loop + vertex -853.818 277.41 138.342 + vertex -853.968 277.035 134.949 + vertex -853.511 277.19 136.296 + endloop + endfacet + facet normal 0.00784197 -0.994504 0.104407 + outer loop + vertex -853.856 277.619 140.338 + vertex -853.818 277.41 138.342 + vertex -853.506 277.625 140.373 + endloop + endfacet + facet normal 0.00888574 -0.995525 0.0940759 + outer loop + vertex -853.86 277.876 143.066 + vertex -853.856 277.619 140.338 + vertex -853.506 277.625 140.373 + endloop + endfacet + facet normal 0.0501381 -0.995218 0.0838276 + outer loop + vertex -853.746 278.175 146.541 + vertex -853.86 277.876 143.066 + vertex -853.448 278.003 144.325 + endloop + endfacet + facet normal 0.0669697 -0.99496 0.0746362 + outer loop + vertex -853.735 278.383 149.303 + vertex -853.746 278.175 146.541 + vertex -853.41 278.31 148.037 + endloop + endfacet + facet normal 0.0285582 -0.997257 0.0682794 + outer loop + vertex -853.855 278.554 151.85 + vertex -853.735 278.383 149.303 + vertex -853.418 278.58 152.045 + endloop + endfacet + facet normal 0.0339223 -0.997836 0.0563289 + outer loop + vertex -853.689 278.723 154.738 + vertex -853.855 278.554 151.85 + vertex -853.418 278.58 152.045 + endloop + endfacet + facet normal 0.0754539 -0.996007 0.0477158 + outer loop + vertex -853.658 278.855 157.461 + vertex -853.689 278.723 154.738 + vertex -853.352 278.808 155.996 + endloop + endfacet + facet normal 0.0613493 -0.997247 0.0416496 + outer loop + vertex -853.744 278.979 160.555 + vertex -853.658 278.855 157.461 + vertex -853.335 278.966 159.635 + endloop + endfacet + facet normal 0.0377135 -0.998842 0.0298838 + outer loop + vertex -853.723 279.07 163.553 + vertex -853.744 278.979 160.555 + vertex -853.357 279.087 163.684 + endloop + endfacet + facet normal 0.0398689 -0.99892 0.0238628 + outer loop + vertex -853.728 279.139 166.453 + vertex -853.723 279.07 163.553 + vertex -853.357 279.087 163.684 + endloop + endfacet + facet normal 0.0616113 -0.998028 0.0120345 + outer loop + vertex -853.632 279.185 169.825 + vertex -853.728 279.139 166.453 + vertex -853.318 279.179 167.676 + endloop + endfacet + facet normal 0.0760022 -0.997105 0.00249631 + outer loop + vertex -853.643 279.191 172.539 + vertex -853.632 279.185 169.825 + vertex -853.315 279.213 171.291 + endloop + endfacet + facet normal 0.0360927 -0.999342 -0.00356864 + outer loop + vertex -853.785 279.177 175.091 + vertex -853.643 279.191 172.539 + vertex -853.36 279.192 175.272 + endloop + endfacet + facet normal 0.0409694 -0.999047 -0.0150511 + outer loop + vertex -853.653 279.139 177.981 + vertex -853.785 279.177 175.091 + vertex -853.36 279.192 175.272 + endloop + endfacet + facet normal 0.0743115 -0.996975 -0.0227787 + outer loop + vertex -853.663 279.075 180.738 + vertex -853.653 279.139 177.981 + vertex -853.33 279.132 179.352 + endloop + endfacet + facet normal 0.0357191 -0.998941 -0.0289863 + outer loop + vertex -853.821 278.995 183.319 + vertex -853.663 279.075 180.738 + vertex -853.395 279.006 183.462 + endloop + endfacet + facet normal 0.0395119 -0.998407 -0.0402752 + outer loop + vertex -853.703 278.883 186.204 + vertex -853.821 278.995 183.319 + vertex -853.395 279.006 183.462 + endloop + endfacet + facet normal 0.0773985 -0.995836 -0.0481657 + outer loop + vertex -853.715 278.749 188.957 + vertex -853.703 278.883 186.204 + vertex -853.38 278.848 187.438 + endloop + endfacet + facet normal 0.0581584 -0.996727 -0.0561424 + outer loop + vertex -853.839 278.563 192.138 + vertex -853.715 278.749 188.957 + vertex -853.414 278.643 191.158 + endloop + endfacet + facet normal 0.0284773 -0.997334 -0.0671879 + outer loop + vertex -853.857 278.355 195.208 + vertex -853.839 278.563 192.138 + vertex -853.479 278.357 195.339 + endloop + endfacet + facet normal 0.0308967 -0.996769 -0.074143 + outer loop + vertex -853.893 278.135 198.149 + vertex -853.857 278.355 195.208 + vertex -853.479 278.357 195.339 + endloop + endfacet + facet normal 0.0434852 -0.995325 -0.0862436 + outer loop + vertex -853.838 277.844 201.538 + vertex -853.893 278.135 198.149 + vertex -853.485 278.033 199.533 + endloop + endfacet + facet normal 0.0161786 -0.995678 -0.0914532 + outer loop + vertex -853.932 277.663 203.498 + vertex -853.838 277.844 201.538 + vertex -853.58 277.662 203.561 + endloop + endfacet + facet normal 0.0180197 -0.994658 -0.101641 + outer loop + vertex -854.01 277.383 206.215 + vertex -853.932 277.663 203.498 + vertex -853.58 277.662 203.561 + endloop + endfacet + facet normal 0.0376494 -0.993154 -0.110581 + outer loop + vertex -853.99 277.001 209.658 + vertex -854.01 277.383 206.215 + vertex -853.62 277.257 207.481 + endloop + endfacet + facet normal 0.0338301 -0.992058 -0.12115 + outer loop + vertex -854.051 276.663 212.407 + vertex -853.99 277.001 209.658 + vertex -853.676 276.827 211.169 + endloop + endfacet + facet normal -0.00870487 -0.991604 -0.129018 + outer loop + vertex -854.256 276.331 214.976 + vertex -854.051 276.663 212.407 + vertex -853.792 276.305 215.142 + endloop + endfacet + facet normal -0.004682 -0.990134 -0.140043 + outer loop + vertex -854.166 275.927 217.83 + vertex -854.256 276.331 214.976 + vertex -853.792 276.305 215.142 + endloop + endfacet + facet normal 0.00379739 -0.988648 -0.1502 + outer loop + vertex -854.219 275.515 220.536 + vertex -854.166 275.927 217.83 + vertex -853.829 275.742 219.055 + endloop + endfacet + facet normal 0.000245088 -0.987213 -0.159406 + outer loop + vertex -854.426 274.988 223.801 + vertex -854.219 275.515 220.536 + vertex -853.908 275.173 222.654 + endloop + endfacet + facet normal -0.00908189 -0.985451 -0.169717 + outer loop + vertex -854.525 274.442 226.978 + vertex -854.426 274.988 223.801 + vertex -854.051 274.464 226.824 + endloop + endfacet + facet normal -0.0137071 -0.982912 -0.183564 + outer loop + vertex -854.622 273.829 230.264 + vertex -854.525 274.442 226.978 + vertex -854.051 274.464 226.824 + endloop + endfacet + facet normal 0.0473318 -0.978939 -0.198588 + outer loop + vertex -854.574 272.903 234.845 + vertex -854.622 273.829 230.264 + vertex -854.093 273.686 231.096 + endloop + endfacet + facet normal 0.0718925 -0.973999 -0.214841 + outer loop + vertex -854.883 271.774 239.856 + vertex -854.574 272.903 234.845 + vertex -854.255 272.222 238.037 + endloop + endfacet + facet normal 0.0643694 -0.967117 -0.24605 + outer loop + vertex -854.9 270.195 246.059 + vertex -854.883 271.774 239.856 + vertex -854.338 271.166 242.389 + endloop + endfacet + facet normal 0.0735084 -0.958566 -0.275224 + outer loop + vertex -854.854 268.749 251.109 + vertex -854.9 270.195 246.059 + vertex -854.345 269.271 249.424 + endloop + endfacet + facet normal 0.0580357 -0.952618 -0.29858 + outer loop + vertex -854.948 267.358 255.527 + vertex -854.854 268.749 251.109 + vertex -854.334 268.03 253.502 + endloop + endfacet + facet normal 0.0731919 -0.939299 -0.335201 + outer loop + vertex -854.668 265.324 261.287 + vertex -854.948 267.358 255.527 + vertex -854.274 266.634 257.702 + endloop + endfacet + facet normal 0.0855851 -0.925569 -0.368779 + outer loop + vertex -854.427 263.324 266.365 + vertex -854.668 265.324 261.287 + vertex -854.045 264.03 264.68 + endloop + endfacet + facet normal 0.0727028 -0.910764 -0.406477 + outer loop + vertex -854.179 261.427 270.658 + vertex -854.427 263.324 266.365 + vertex -853.845 262.358 268.631 + endloop + endfacet + facet normal 0.0819845 -0.88712 -0.454199 + outer loop + vertex -853.698 258.905 275.671 + vertex -854.179 261.427 270.658 + vertex -853.569 260.562 272.458 + endloop + endfacet + facet normal 0.0932611 -0.856233 -0.508102 + outer loop + vertex -852.995 256.171 280.408 + vertex -853.698 258.905 275.671 + vertex -852.87 257.189 278.714 + endloop + endfacet + facet normal 0.107079 -0.818939 -0.563802 + outer loop + vertex -852.29 253.649 284.205 + vertex -852.995 256.171 280.408 + vertex -852.297 254.929 282.344 + endloop + endfacet + facet normal 0.18841 -0.755307 -0.627704 + outer loop + vertex -851.25 250.349 288.488 + vertex -852.29 253.649 284.205 + vertex -851.592 252.497 285.801 + endloop + endfacet + facet normal 0.126051 -0.722932 -0.679323 + outer loop + vertex -850.063 246.709 292.582 + vertex -851.25 250.349 288.488 + vertex -850.073 247.865 291.35 + endloop + endfacet + facet normal 0.567656 -0.459396 -0.683171 + outer loop + vertex -849.156 244.251 294.988 + vertex -850.063 246.709 292.582 + vertex -849.362 244.951 294.346 + endloop + endfacet + facet normal -0.119058 -0.673652 -0.729396 + outer loop + vertex -848.286 242.207 296.733 + vertex -849.156 244.251 294.988 + vertex -848.033 243.023 295.939 + endloop + endfacet + facet normal 0.885883 -0.278864 -0.370737 + outer loop + vertex -798.384 384.625 283.564 + vertex -796.398 384.702 288.252 + vertex -800.497 377.539 283.847 + endloop + endfacet + facet normal 0.832717 -0.284942 0.474753 + outer loop + vertex -794.393 384.772 53.016 + vertex -796.267 384.707 56.2643 + vertex -799.208 376.75 56.6465 + endloop + endfacet + facet normal 0.31591 0.744377 0.588306 + outer loop + vertex -848.772 243.781 295.377 + vertex -848.033 243.023 295.939 + vertex -849.156 244.251 294.988 + endloop + endfacet + facet normal -0.0959585 -0.639827 -0.762504 + outer loop + vertex -848.033 243.023 295.939 + vertex -846.948 242.928 295.882 + vertex -846.949 242.749 296.033 + endloop + endfacet + facet normal 0.0317103 -0.728793 -0.683999 + outer loop + vertex -850.073 247.865 291.35 + vertex -849.773 246.137 293.205 + vertex -850.063 246.709 292.582 + endloop + endfacet + facet normal 0.54619 -0.474869 -0.690055 + outer loop + vertex -849.773 246.137 293.205 + vertex -849.362 244.951 294.346 + vertex -850.063 246.709 292.582 + endloop + endfacet + facet normal -0.121632 -0.689762 -0.713747 + outer loop + vertex -849.362 244.951 294.346 + vertex -848.772 243.781 295.377 + vertex -849.156 244.251 294.988 + endloop + endfacet + facet normal 0.0751242 -0.774231 -0.628429 + outer loop + vertex -851.592 252.497 285.801 + vertex -850.827 250.354 288.532 + vertex -851.25 250.349 288.488 + endloop + endfacet + facet normal 0.0790895 -0.736503 -0.671794 + outer loop + vertex -850.827 250.354 288.532 + vertex -850.073 247.865 291.35 + vertex -851.25 250.349 288.488 + endloop + endfacet + facet normal -0.0781711 -0.851778 -0.518038 + outer loop + vertex -852.87 257.189 278.714 + vertex -852.297 254.929 282.344 + vertex -852.995 256.171 280.408 + endloop + endfacet + facet normal -0.0643935 -0.822271 -0.565442 + outer loop + vertex -852.297 254.929 282.344 + vertex -851.592 252.497 285.801 + vertex -852.29 253.649 284.205 + endloop + endfacet + facet normal 0.0179865 -0.888926 -0.457698 + outer loop + vertex -853.569 260.562 272.458 + vertex -853.205 258.965 275.574 + vertex -853.698 258.905 275.671 + endloop + endfacet + facet normal 0.00879617 -0.870034 -0.492913 + outer loop + vertex -853.205 258.965 275.574 + vertex -852.87 257.189 278.714 + vertex -853.698 258.905 275.671 + endloop + endfacet + facet normal -0.0121617 -0.921119 -0.389091 + outer loop + vertex -854.045 264.03 264.68 + vertex -853.845 262.358 268.631 + vertex -854.427 263.324 266.365 + endloop + endfacet + facet normal -0.0380839 -0.905614 -0.42239 + outer loop + vertex -853.845 262.358 268.631 + vertex -853.569 260.562 272.458 + vertex -854.179 261.427 270.658 + endloop + endfacet + facet normal 0.0586152 -0.939697 -0.336949 + outer loop + vertex -854.274 266.634 257.702 + vertex -854.117 265.378 261.234 + vertex -854.668 265.324 261.287 + endloop + endfacet + facet normal 0.0549498 -0.929519 -0.364658 + outer loop + vertex -854.117 265.378 261.234 + vertex -854.045 264.03 264.68 + vertex -854.668 265.324 261.287 + endloop + endfacet + facet normal 0.0185836 -0.956492 -0.291167 + outer loop + vertex -854.345 269.271 249.424 + vertex -854.334 268.03 253.502 + vertex -854.854 268.749 251.109 + endloop + endfacet + facet normal -0.00119488 -0.948974 -0.315351 + outer loop + vertex -854.334 268.03 253.502 + vertex -854.274 266.634 257.702 + vertex -854.948 267.358 255.527 + endloop + endfacet + facet normal 0.0459894 -0.967424 -0.248948 + outer loop + vertex -854.338 271.166 242.389 + vertex -854.285 270.245 245.979 + vertex -854.9 270.195 246.059 + endloop + endfacet + facet normal 0.0426561 -0.96164 -0.270978 + outer loop + vertex -854.285 270.245 245.979 + vertex -854.345 269.271 249.424 + vertex -854.9 270.195 246.059 + endloop + endfacet + facet normal 0.0748966 -0.97372 -0.215082 + outer loop + vertex -854.109 273.023 234.459 + vertex -854.255 272.222 238.037 + vertex -854.574 272.903 234.845 + endloop + endfacet + facet normal 0.010302 -0.971808 -0.235549 + outer loop + vertex -854.255 272.222 238.037 + vertex -854.338 271.166 242.389 + vertex -854.883 271.774 239.856 + endloop + endfacet + facet normal 0.0151424 -0.983746 -0.178927 + outer loop + vertex -854.051 274.464 226.824 + vertex -854.093 273.686 231.096 + vertex -854.622 273.829 230.264 + endloop + endfacet + facet normal 0.0947623 -0.9768 -0.192046 + outer loop + vertex -854.093 273.686 231.096 + vertex -854.109 273.023 234.459 + vertex -854.574 272.903 234.845 + endloop + endfacet + facet normal -0.0204243 -0.987481 -0.156408 + outer loop + vertex -853.829 275.742 219.055 + vertex -853.908 275.173 222.654 + vertex -854.219 275.515 220.536 + endloop + endfacet + facet normal -0.0201648 -0.98552 -0.168354 + outer loop + vertex -853.908 275.173 222.654 + vertex -854.051 274.464 226.824 + vertex -854.426 274.988 223.801 + endloop + endfacet + facet normal 0.00373892 -0.991483 -0.13018 + outer loop + vertex -853.676 276.827 211.169 + vertex -853.792 276.305 215.142 + vertex -854.051 276.663 212.407 + endloop + endfacet + facet normal -0.0240649 -0.98948 -0.142653 + outer loop + vertex -853.792 276.305 215.142 + vertex -853.829 275.742 219.055 + vertex -854.166 275.927 217.83 + endloop + endfacet + facet normal 0.0115253 -0.994647 -0.10269 + outer loop + vertex -853.58 277.662 203.561 + vertex -853.62 277.257 207.481 + vertex -854.01 277.383 206.215 + endloop + endfacet + facet normal 0.00725114 -0.993251 -0.115761 + outer loop + vertex -853.62 277.257 207.481 + vertex -853.676 276.827 211.169 + vertex -853.99 277.001 209.658 + endloop + endfacet + facet normal 0.0116669 -0.996964 -0.0769913 + outer loop + vertex -853.479 278.357 195.339 + vertex -853.485 278.033 199.533 + vertex -853.893 278.135 198.149 + endloop + endfacet + facet normal 0.0149494 -0.995711 -0.0912998 + outer loop + vertex -853.485 278.033 199.533 + vertex -853.58 277.662 203.561 + vertex -853.838 277.844 201.538 + endloop + endfacet + facet normal 0.0478545 -0.997352 -0.0547635 + outer loop + vertex -853.38 278.848 187.438 + vertex -853.414 278.643 191.158 + vertex -853.715 278.749 188.957 + endloop + endfacet + facet normal 0.0318876 -0.997205 -0.0675629 + outer loop + vertex -853.414 278.643 191.158 + vertex -853.479 278.357 195.339 + vertex -853.839 278.563 192.138 + endloop + endfacet + facet normal 0.0450483 -0.998537 -0.0298944 + outer loop + vertex -853.33 279.132 179.352 + vertex -853.395 279.006 183.462 + vertex -853.663 279.075 180.738 + endloop + endfacet + facet normal 0.0447105 -0.998212 -0.0396831 + outer loop + vertex -853.395 279.006 183.462 + vertex -853.38 278.848 187.438 + vertex -853.703 278.883 186.204 + endloop + endfacet + facet normal 0.0482396 -0.998824 -0.00482607 + outer loop + vertex -853.315 279.213 171.291 + vertex -853.36 279.192 175.272 + vertex -853.643 279.191 172.539 + endloop + endfacet + facet normal 0.0413538 -0.999032 -0.0150092 + outer loop + vertex -853.36 279.192 175.272 + vertex -853.33 279.132 179.352 + vertex -853.653 279.139 177.981 + endloop + endfacet + facet normal 0.030316 -0.999285 0.0225905 + outer loop + vertex -853.357 279.087 163.684 + vertex -853.318 279.179 167.676 + vertex -853.728 279.139 166.453 + endloop + endfacet + facet normal 0.0439533 -0.998989 0.00945327 + outer loop + vertex -853.318 279.179 167.676 + vertex -853.315 279.213 171.291 + vertex -853.632 279.185 169.825 + endloop + endfacet + facet normal 0.0525245 -0.997694 0.0429819 + outer loop + vertex -853.352 278.808 155.996 + vertex -853.335 278.966 159.635 + vertex -853.658 278.855 157.461 + endloop + endfacet + facet normal 0.0354705 -0.998915 0.0301636 + outer loop + vertex -853.335 278.966 159.635 + vertex -853.357 279.087 163.684 + vertex -853.744 278.979 160.555 + endloop + endfacet + facet normal 0.0376069 -0.997029 0.0672185 + outer loop + vertex -853.41 278.31 148.037 + vertex -853.418 278.58 152.045 + vertex -853.735 278.383 149.303 + endloop + endfacet + facet normal 0.0410564 -0.997528 0.0570304 + outer loop + vertex -853.418 278.58 152.045 + vertex -853.352 278.808 155.996 + vertex -853.689 278.723 154.738 + endloop + endfacet + facet normal 0.0160804 -0.995347 0.0950067 + outer loop + vertex -853.506 277.625 140.373 + vertex -853.448 278.003 144.325 + vertex -853.86 277.876 143.066 + endloop + endfacet + facet normal 0.0351527 -0.996022 0.0818752 + outer loop + vertex -853.448 278.003 144.325 + vertex -853.41 278.31 148.037 + vertex -853.746 278.175 146.541 + endloop + endfacet + facet normal -0.0173608 -0.992557 0.120535 + outer loop + vertex -853.619 276.686 132.124 + vertex -853.511 277.19 136.296 + vertex -853.968 277.035 134.949 + endloop + endfacet + facet normal -0.00275515 -0.99436 0.10602 + outer loop + vertex -853.511 277.19 136.296 + vertex -853.506 277.625 140.373 + vertex -853.818 277.41 138.342 + endloop + endfacet + facet normal -0.00884912 -0.989587 0.143661 + outer loop + vertex -853.71 275.629 124.46 + vertex -853.655 276.149 128.043 + vertex -854.029 275.842 125.909 + endloop + endfacet + facet normal -0.0216595 -0.991192 0.130653 + outer loop + vertex -853.655 276.149 128.043 + vertex -853.619 276.686 132.124 + vertex -854.079 276.284 128.999 + endloop + endfacet + facet normal 0.00353271 -0.985286 0.170878 + outer loop + vertex -853.869 274.273 116.345 + vertex -853.823 275.006 120.566 + vertex -854.225 274.494 117.622 + endloop + endfacet + facet normal -0.0182184 -0.98718 0.158566 + outer loop + vertex -853.823 275.006 120.566 + vertex -853.71 275.629 124.46 + vertex -854.089 275.441 123.245 + endloop + endfacet + facet normal 0.0784654 -0.977018 0.198188 + outer loop + vertex -853.945 272.808 108.856 + vertex -853.948 273.507 112.301 + vertex -854.328 272.803 108.981 + endloop + endfacet + facet normal 0.0143422 -0.982451 0.185968 + outer loop + vertex -853.948 273.507 112.301 + vertex -853.869 274.273 116.345 + vertex -854.377 273.728 113.504 + endloop + endfacet + facet normal 0.00671318 -0.971824 0.235614 + outer loop + vertex -854.052 271.003 101.148 + vertex -854.018 272.043 105.438 + vertex -854.577 271.705 104.063 + endloop + endfacet + facet normal 0.0841952 -0.972748 0.216037 + outer loop + vertex -854.018 272.043 105.438 + vertex -853.945 272.808 108.856 + vertex -854.328 272.803 108.981 + endloop + endfacet + facet normal 0.0702042 -0.95921 0.273839 + outer loop + vertex -853.93 268.902 93.4333 + vertex -854.029 269.874 96.8638 + vertex -854.426 268.911 93.5945 + endloop + endfacet + facet normal -0.00475463 -0.966998 0.254739 + outer loop + vertex -854.029 269.874 96.8638 + vertex -854.052 271.003 101.148 + vertex -854.645 270.297 98.4601 + endloop + endfacet + facet normal -0.00255961 -0.948537 0.316656 + outer loop + vertex -853.839 266.453 85.8922 + vertex -853.946 267.85 90.077 + vertex -854.535 267.332 88.5223 + endloop + endfacet + facet normal 0.0781185 -0.951447 0.297734 + outer loop + vertex -853.946 267.85 90.077 + vertex -853.93 268.902 93.4333 + vertex -854.426 268.911 93.5945 + endloop + endfacet + facet normal 0.0591912 -0.928667 0.366161 + outer loop + vertex -853.508 263.9 79.0612 + vertex -853.632 265.191 82.3563 + vertex -854.2 265.254 82.6085 + endloop + endfacet + facet normal 0.0454411 -0.940027 0.33806 + outer loop + vertex -853.632 265.191 82.3563 + vertex -853.839 266.453 85.8922 + vertex -854.2 265.254 82.6085 + endloop + endfacet + facet normal -0.0333353 -0.906888 0.420051 + outer loop + vertex -852.865 260.386 71.1518 + vertex -853.235 262.227 75.0957 + vertex -853.481 261.229 72.922 + endloop + endfacet + facet normal -0.0120288 -0.921602 0.38795 + outer loop + vertex -853.235 262.227 75.0957 + vertex -853.508 263.9 79.0612 + vertex -853.863 263.202 77.394 + endloop + endfacet + facet normal 0.0341498 -0.870049 0.491782 + outer loop + vertex -852.027 257.02 64.8444 + vertex -852.431 258.738 67.9122 + vertex -852.864 258.683 67.8459 + endloop + endfacet + facet normal 0.0416679 -0.888186 0.45759 + outer loop + vertex -852.431 258.738 67.9122 + vertex -852.865 260.386 71.1518 + vertex -852.864 258.683 67.8459 + endloop + endfacet + facet normal -0.0560285 -0.83142 0.552812 + outer loop + vertex -850.584 252.474 57.7897 + vertex -851.368 254.83 61.2527 + vertex -851.303 253.67 59.5155 + endloop + endfacet + facet normal -0.0281188 -0.855738 0.516644 + outer loop + vertex -851.368 254.83 61.2527 + vertex -852.027 257.02 64.8444 + vertex -852.065 256.046 63.2291 + endloop + endfacet + facet normal -0.0664606 -0.77883 0.623704 + outer loop + vertex -849.117 247.826 51.8654 + vertex -849.644 249.842 54.3267 + vertex -849.567 248.772 52.9978 + endloop + endfacet + facet normal -0.0887102 -0.804491 0.587303 + outer loop + vertex -849.644 249.842 54.3267 + vertex -850.584 252.474 57.7897 + vertex -850.442 251.193 56.0564 + endloop + endfacet + facet normal 0.0392874 -0.648549 0.760159 + outer loop + vertex -847.244 243.376 47.4041 + vertex -847.609 244.165 48.096 + vertex -847.794 244.315 48.2335 + endloop + endfacet + facet normal -0.0284578 -0.694469 0.71896 + outer loop + vertex -847.609 244.165 48.096 + vertex -848.094 245.277 49.1505 + vertex -847.794 244.315 48.2335 + endloop + endfacet + facet normal 0.331131 -0.595407 0.732013 + outer loop + vertex -848.094 245.277 49.1505 + vertex -848.598 246.482 50.3583 + vertex -848.682 246.477 50.3927 + endloop + endfacet + facet normal 0.31693 -0.650879 0.689863 + outer loop + vertex -848.598 246.482 50.3583 + vertex -849.117 247.826 51.8654 + vertex -848.682 246.477 50.3927 + endloop + endfacet + facet normal -0.222839 -0.691131 0.687518 + outer loop + vertex -846.314 242.597 46.8679 + vertex -846.575 242.878 47.0655 + vertex -846.708 242.159 46.2995 + endloop + endfacet + facet normal -0.174228 -0.702656 0.689868 + outer loop + vertex -846.575 242.878 47.0655 + vertex -847.244 243.376 47.4041 + vertex -846.708 242.159 46.2995 + endloop + endfacet + facet normal -0.10404 -0.688746 0.717499 + outer loop + vertex -845.695 242.663 47.0393 + vertex -846.272 242.474 46.7745 + vertex -845.943 242.517 46.8635 + endloop + endfacet + facet normal -0.306415 -0.639145 0.70541 + outer loop + vertex -846.272 242.474 46.7745 + vertex -846.314 242.597 46.8679 + vertex -846.708 242.159 46.2995 + endloop + endfacet + facet normal -0.0991755 -0.412349 -0.905612 + outer loop + vertex -845.542 243.162 295.594 + vertex -844.074 243.936 295.081 + vertex -844.961 243.343 295.448 + endloop + endfacet + facet normal -0.10173 -0.540065 -0.835452 + outer loop + vertex -846.949 242.749 296.033 + vertex -845.542 243.162 295.594 + vertex -846.477 242.734 295.985 + endloop + endfacet + facet normal 0.0596562 -0.34556 -0.936498 + outer loop + vertex -842.642 245.073 294.581 + vertex -841.307 246.544 294.123 + vertex -842.086 245.541 294.444 + endloop + endfacet + facet normal -0.0170028 -0.384442 -0.922992 + outer loop + vertex -844.074 243.936 295.081 + vertex -842.642 245.073 294.581 + vertex -843.481 244.267 294.932 + endloop + endfacet + facet normal 0.628012 -0.753781 -0.193431 + outer loop + vertex -842.315 244.555 48.5923 + vertex -843.531 243.696 47.9921 + vertex -841.901 244.872 48.7024 + endloop + endfacet + facet normal 0.335143 -0.668704 0.663712 + outer loop + vertex -841.066 245.779 49.1949 + vertex -842.315 244.555 48.5923 + vertex -841.901 244.872 48.7024 + endloop + endfacet + facet normal -0.100372 -0.636431 0.764776 + outer loop + vertex -844.953 242.915 47.3248 + vertex -845.943 242.517 46.8635 + vertex -845.324 242.676 47.0767 + endloop + endfacet + facet normal -0.0873653 -0.550416 0.830307 + outer loop + vertex -843.531 243.696 47.9921 + vertex -844.953 242.915 47.3248 + vertex -843.832 243.42 47.7771 + endloop + endfacet + facet normal 0.398305 -0.285854 -0.871573 + outer loop + vertex -839.236 250.135 293.339 + vertex -837.907 254.008 292.676 + vertex -838.561 251.457 293.214 + endloop + endfacet + facet normal 0.172521 -0.279388 -0.944552 + outer loop + vertex -840.143 248.2 293.727 + vertex -839.398 249.498 293.48 + vertex -839.744 248.776 293.63 + endloop + endfacet + facet normal 0.421442 -0.296298 -0.857085 + outer loop + vertex -839.398 249.498 293.48 + vertex -839.236 250.135 293.339 + vertex -838.561 251.457 293.214 + endloop + endfacet + facet normal 0.0572283 -0.269838 -0.961203 + outer loop + vertex -841.307 246.544 294.123 + vertex -840.143 248.2 293.727 + vertex -840.831 247.07 294.004 + endloop + endfacet + facet normal 0.324896 -0.518018 0.791265 + outer loop + vertex -839.862 247.461 49.802 + vertex -841.066 245.779 49.1949 + vertex -840.209 246.858 49.5491 + endloop + endfacet + facet normal 0.353174 -0.403032 0.844294 + outer loop + vertex -838.993 249.151 50.2452 + vertex -839.862 247.461 49.802 + vertex -839.122 248.755 50.1097 + endloop + endfacet + facet normal 0.542375 -0.345803 0.76567 + outer loop + vertex -838.699 250.078 50.4551 + vertex -838.993 249.151 50.2452 + vertex -838.099 251.35 50.6045 + endloop + endfacet + facet normal 0.391205 -0.287259 0.874323 + outer loop + vertex -837.623 253.001 50.9341 + vertex -838.699 250.078 50.4551 + vertex -838.099 251.35 50.6045 + endloop + endfacet + facet normal 0.584681 -0.229408 -0.778152 + outer loop + vertex -836.35 258.542 292.274 + vertex -835.612 260.759 292.175 + vertex -835.812 259.509 292.393 + endloop + endfacet + facet normal 0.635158 -0.177064 -0.751813 + outer loop + vertex -835.612 260.759 292.175 + vertex -835.474 263.313 291.69 + vertex -835.199 262.267 292.169 + endloop + endfacet + facet normal 0.506965 -0.247367 -0.825709 + outer loop + vertex -837.907 254.008 292.676 + vertex -836.35 258.542 292.274 + vertex -836.976 255.768 292.721 + endloop + endfacet + facet normal 0.785358 -0.189436 0.589344 + outer loop + vertex -836.318 265.49 54.2544 + vertex -835.786 263.629 52.9471 + vertex -834.417 270.497 53.3315 + endloop + endfacet + facet normal 0.796794 -0.199047 0.570526 + outer loop + vertex -837.45 266.007 56.0157 + vertex -836.318 265.49 54.2544 + vertex -835.698 272.542 55.8492 + endloop + endfacet + facet normal 0.689308 -0.306829 0.656286 + outer loop + vertex -836.494 256.549 51.4068 + vertex -837.623 253.001 50.9341 + vertex -836.677 255.8 51.2491 + endloop + endfacet + facet normal -0.0268031 -0.0976419 0.994861 + outer loop + vertex -835.62 259.755 51.745 + vertex -836.494 256.549 51.4068 + vertex -835.769 259.047 51.6715 + endloop + endfacet + facet normal -0.00971116 -0.0717031 0.997379 + outer loop + vertex -835.088 262.591 51.9541 + vertex -835.62 259.755 51.745 + vertex -835.073 262.016 51.9129 + endloop + endfacet + facet normal 0.727696 -0.178637 -0.662229 + outer loop + vertex -835.474 263.313 291.69 + vertex -834.399 272.206 290.472 + vertex -834.332 266.499 292.085 + endloop + endfacet + facet normal 0.393872 -0.125356 0.910577 + outer loop + vertex -833.804 269.618 52.3662 + vertex -835.088 262.591 51.9541 + vertex -834.299 265.79 52.0535 + endloop + endfacet + facet normal 0.789165 -0.157539 -0.593633 + outer loop + vertex -834.399 272.206 290.472 + vertex -832.618 281.897 290.269 + vertex -832.921 275.126 291.662 + endloop + endfacet + facet normal 0.83356 -0.177723 0.523061 + outer loop + vertex -834.154 282.184 56.6644 + vertex -835.698 272.542 55.8492 + vertex -833.024 279.844 54.0692 + endloop + endfacet + facet normal 0.726348 -0.147188 0.671382 + outer loop + vertex -832.412 278.127 52.726 + vertex -833.804 269.618 52.3662 + vertex -832.597 274.694 52.1734 + endloop + endfacet + facet normal 0.818253 -0.165419 0.550544 + outer loop + vertex -834.417 270.497 53.3315 + vertex -833.024 279.844 54.0692 + vertex -835.698 272.542 55.8492 + endloop + endfacet + facet normal 0.812487 -0.165933 -0.558866 + outer loop + vertex -832.618 281.897 290.269 + vertex -831.074 290.479 289.965 + vertex -831.133 284.844 291.552 + endloop + endfacet + facet normal 0.845677 -0.176609 0.503626 + outer loop + vertex -832.436 291.182 56.9355 + vertex -834.154 282.184 56.6644 + vertex -831.407 288.703 54.3384 + endloop + endfacet + facet normal 0.778367 -0.153418 0.608775 + outer loop + vertex -831.016 286.312 53.0034 + vertex -832.412 278.127 52.726 + vertex -830.863 284.487 52.3478 + endloop + endfacet + facet normal 0.838923 -0.16885 0.517395 + outer loop + vertex -833.024 279.844 54.0692 + vertex -831.407 288.703 54.3384 + vertex -834.154 282.184 56.6644 + endloop + endfacet + facet normal 0.79961 -0.183866 -0.57168 + outer loop + vertex -831.074 290.479 289.965 + vertex -829.202 297.898 290.197 + vertex -829.822 290.566 291.689 + endloop + endfacet + facet normal 0.841466 -0.191883 0.50509 + outer loop + vertex -830.488 299.701 56.9269 + vertex -832.436 291.182 56.9355 + vertex -829.481 297.283 54.3301 + endloop + endfacet + facet normal 0.781247 -0.168874 0.600945 + outer loop + vertex -829.138 294.759 52.9356 + vertex -831.016 286.312 53.0034 + vertex -829.49 290.836 52.2909 + endloop + endfacet + facet normal 0.838553 -0.187758 0.511446 + outer loop + vertex -831.407 288.703 54.3384 + vertex -829.481 297.283 54.3301 + vertex -832.436 291.182 56.9355 + endloop + endfacet + facet normal 0.793486 -0.213439 -0.569934 + outer loop + vertex -829.202 297.898 290.197 + vertex -826.839 306.771 290.164 + vertex -827.604 299.74 291.732 + endloop + endfacet + facet normal 0.829471 -0.219168 0.513755 + outer loop + vertex -828.299 307.892 56.8867 + vertex -830.488 299.701 56.9269 + vertex -827.285 305.58 54.2638 + endloop + endfacet + facet normal 0.779697 -0.197087 0.594331 + outer loop + vertex -826.9 303.398 52.8649 + vertex -829.138 294.759 52.9356 + vertex -827.224 300.295 52.2601 + endloop + endfacet + facet normal 0.826527 -0.214552 0.520404 + outer loop + vertex -829.481 297.283 54.3301 + vertex -827.285 305.58 54.2638 + vertex -830.488 299.701 56.9269 + endloop + endfacet + facet normal 0.801081 -0.249143 -0.544239 + outer loop + vertex -826.839 306.771 290.164 + vertex -824.393 315.234 289.89 + vertex -824.91 310.212 291.428 + endloop + endfacet + facet normal 0.814277 -0.249119 0.524302 + outer loop + vertex -825.984 315.76 57.0305 + vertex -828.299 307.892 56.8867 + vertex -824.815 313.827 54.295 + endloop + endfacet + facet normal 0.741388 -0.217446 0.634871 + outer loop + vertex -824.646 311.198 52.9042 + vertex -826.9 303.398 52.8649 + vertex -824.596 309.389 52.2258 + endloop + endfacet + facet normal 0.811824 -0.24523 0.52991 + outer loop + vertex -827.285 305.58 54.2638 + vertex -824.815 313.827 54.295 + vertex -828.299 307.892 56.8867 + endloop + endfacet + facet normal 0.76972 -0.269428 -0.57874 + outer loop + vertex -824.393 315.234 289.89 + vertex -821.519 322.854 290.165 + vertex -822.804 315.965 291.664 + endloop + endfacet + facet normal 0.796848 -0.275317 0.537805 + outer loop + vertex -824.18 322.023 57.563 + vertex -825.984 315.76 57.0305 + vertex -821.905 322.859 54.6198 + endloop + endfacet + facet normal 0.760222 -0.256083 0.597063 + outer loop + vertex -821.82 319.529 52.8784 + vertex -824.646 311.198 52.9042 + vertex -822.852 315.14 52.3101 + endloop + endfacet + facet normal 0.797544 -0.276227 0.536304 + outer loop + vertex -824.815 313.827 54.295 + vertex -821.905 322.859 54.6198 + vertex -825.984 315.76 57.0305 + endloop + endfacet + facet normal 0.780665 -0.30035 -0.548043 + outer loop + vertex -821.519 322.854 290.165 + vertex -818.577 330.896 289.948 + vertex -819.339 326.097 291.493 + endloop + endfacet + facet normal 0.793042 -0.30796 0.525591 + outer loop + vertex -821.125 328.754 56.8963 + vertex -824.18 322.023 57.563 + vertex -821.905 322.859 54.6198 + endloop + endfacet + facet normal 0.725904 -0.27075 0.632265 + outer loop + vertex -818.797 327.862 52.9768 + vertex -821.82 319.529 52.8784 + vertex -818.969 325.687 52.2429 + endloop + endfacet + facet normal 0.789734 -0.309165 0.529846 + outer loop + vertex -821.905 322.859 54.6198 + vertex -817.984 332.034 54.1296 + vertex -821.125 328.754 56.8963 + endloop + endfacet + facet normal 0.761414 -0.313105 -0.567638 + outer loop + vertex -818.577 330.896 289.948 + vertex -815.32 338.382 290.189 + vertex -816.923 331.705 291.721 + endloop + endfacet + facet normal 0.794511 -0.331502 0.508782 + outer loop + vertex -816.949 337.849 56.3016 + vertex -821.125 328.754 56.8963 + vertex -817.984 332.034 54.1296 + endloop + endfacet + facet normal 0.739252 -0.296685 0.604553 + outer loop + vertex -815.461 335.783 52.7846 + vertex -818.797 327.862 52.9768 + vertex -816.91 331.343 52.3771 + endloop + endfacet + facet normal 0.793669 -0.331776 0.509916 + outer loop + vertex -817.984 332.034 54.1296 + vertex -814.817 338.889 53.6604 + vertex -816.949 337.849 56.3016 + endloop + endfacet + facet normal 0.778903 -0.341388 -0.526084 + outer loop + vertex -815.32 338.382 290.189 + vertex -812.018 346.367 289.896 + vertex -813.009 341.674 291.474 + endloop + endfacet + facet normal 0.796685 -0.349265 0.493262 + outer loop + vertex -813.601 346.421 56.9632 + vertex -816.949 337.849 56.3016 + vertex -812.328 345.332 54.137 + endloop + endfacet + facet normal 0.718238 -0.305719 0.625036 + outer loop + vertex -812.34 343.243 52.8468 + vertex -815.461 335.783 52.7846 + vertex -812.562 341.457 52.2286 + endloop + endfacet + facet normal 0.792336 -0.343396 0.504265 + outer loop + vertex -814.817 338.889 53.6604 + vertex -812.328 345.332 54.137 + vertex -816.949 337.849 56.3016 + endloop + endfacet + facet normal 0.764651 -0.352354 -0.539588 + outer loop + vertex -812.018 346.367 289.896 + vertex -808.347 354.038 290.088 + vertex -810.396 347.183 291.661 + endloop + endfacet + facet normal 0.796212 -0.366649 0.481265 + outer loop + vertex -811.202 352.523 57.6435 + vertex -813.601 346.421 56.9632 + vertex -808.74 353.976 54.6772 + endloop + endfacet + facet normal 0.742392 -0.332864 0.581425 + outer loop + vertex -808.863 351.103 52.9078 + vertex -812.34 343.243 52.8468 + vertex -810.284 346.94 52.338 + endloop + endfacet + facet normal 0.791259 -0.359392 0.494719 + outer loop + vertex -812.328 345.332 54.137 + vertex -808.74 353.976 54.6772 + vertex -813.601 346.421 56.9632 + endloop + endfacet + facet normal 0.771182 -0.3632 -0.522842 + outer loop + vertex -808.347 354.038 290.088 + vertex -804.706 362.148 289.825 + vertex -805.355 358.293 291.546 + endloop + endfacet + facet normal 0.794455 -0.381537 0.472515 + outer loop + vertex -807.608 359.19 56.9849 + vertex -811.202 352.523 57.6435 + vertex -808.74 353.976 54.6772 + endloop + endfacet + facet normal 0.736871 -0.342151 0.583055 + outer loop + vertex -805.17 359.287 53.0425 + vertex -808.863 351.103 52.9078 + vertex -805.522 357.223 52.2764 + endloop + endfacet + facet normal 0.799846 -0.379413 0.465072 + outer loop + vertex -808.74 353.976 54.6772 + vertex -804.146 363.103 54.2227 + vertex -807.608 359.19 56.9849 + endloop + endfacet + facet normal 0.781933 -0.361383 -0.50792 + outer loop + vertex -804.706 362.148 289.825 + vertex -801.201 369.177 290.219 + vertex -802.995 363.747 291.321 + endloop + endfacet + facet normal 0.800856 -0.384522 0.4591 + outer loop + vertex -802.896 368.231 56.3377 + vertex -807.608 359.19 56.9849 + vertex -804.146 363.103 54.2227 + endloop + endfacet + facet normal 0.732898 -0.341839 0.588223 + outer loop + vertex -801.333 367.198 52.8591 + vertex -805.17 359.287 53.0425 + vertex -803.047 362.811 52.4446 + endloop + endfacet + facet normal 0.808823 -0.381636 0.447391 + outer loop + vertex -804.146 363.103 54.2227 + vertex -800.574 370.091 53.726 + vertex -802.896 368.231 56.3377 + endloop + endfacet + facet normal 0.775557 -0.339272 -0.532359 + outer loop + vertex -801.201 369.177 290.219 + vertex -798.233 376.104 290.129 + vertex -798.386 373.16 291.782 + endloop + endfacet + facet normal 0.829559 -0.282218 -0.481856 + outer loop + vertex -798.233 376.104 290.129 + vertex -799.755 375.007 288.152 + vertex -796.398 384.702 288.252 + endloop + endfacet + facet normal 0.891991 -0.30537 -0.33332 + outer loop + vertex -799.755 375.007 288.152 + vertex -800.497 377.539 283.847 + vertex -796.398 384.702 288.252 + endloop + endfacet + facet normal 0.826094 -0.373023 0.422402 + outer loop + vertex -799.208 376.75 56.6465 + vertex -802.896 368.231 56.3377 + vertex -797.939 376.566 54.0027 + endloop + endfacet + facet normal 0.70379 -0.311741 0.638355 + outer loop + vertex -797.771 375.097 52.7894 + vertex -801.333 367.198 52.8591 + vertex -798.333 372.62 52.2001 + endloop + endfacet + facet normal 0.80984 -0.349739 0.471001 + outer loop + vertex -800.574 370.091 53.726 + vertex -797.939 376.566 54.0027 + vertex -802.896 368.231 56.3377 + endloop + endfacet + facet normal 0.689997 -0.252792 0.678233 + outer loop + vertex -794.278 384.776 52.8438 + vertex -797.771 375.097 52.7894 + vertex -795.203 379.625 51.8645 + endloop + endfacet + facet normal 0.847076 -0.314535 0.428404 + outer loop + vertex -797.939 376.566 54.0027 + vertex -794.393 384.772 53.016 + vertex -799.208 376.75 56.6465 + endloop + endfacet + facet normal -0.108124 -0.676301 -0.728647 + outer loop + vertex -846.949 242.749 296.033 + vertex -848.286 242.207 296.733 + vertex -848.033 243.023 295.939 + endloop + endfacet + facet normal 0.777105 -0.287999 -0.559611 + outer loop + vertex -795.673 379.842 291.76 + vertex -798.233 376.104 290.129 + vertex -796.398 384.702 288.252 + endloop + endfacet + facet normal -0.0524467 -0.809255 0.585112 + outer loop + vertex -846.708 242.159 46.2995 + vertex -845.943 242.517 46.8635 + vertex -846.272 242.474 46.7745 + endloop + endfacet + facet normal 0.798948 -0.19859 0.567666 + outer loop + vertex -836.318 265.49 54.2544 + vertex -834.417 270.497 53.3315 + vertex -835.698 272.542 55.8492 + endloop + endfacet + facet normal -0.077143 -0.591808 -0.802379 + outer loop + vertex -846.581 242.412 296.237 + vertex -846.49 241.989 296.54 + vertex -847.211 242.02 296.586 + endloop + endfacet + facet normal -0.0426472 -0.555736 -0.830264 + outer loop + vertex -845.987 241.448 296.876 + vertex -846.609 240.976 297.224 + vertex -846.49 241.989 296.54 + endloop + endfacet + facet normal -0.0772395 -0.551782 -0.830404 + outer loop + vertex -846.609 240.976 297.224 + vertex -847.211 242.02 296.586 + vertex -846.49 241.989 296.54 + endloop + endfacet + facet normal 0.187823 -0.50771 -0.840805 + outer loop + vertex -841.363 245.723 294.539 + vertex -841.069 245.393 294.804 + vertex -842.664 244.454 295.015 + endloop + endfacet + facet normal 0.203826 -0.530824 -0.822606 + outer loop + vertex -842.664 244.454 295.015 + vertex -841.069 245.393 294.804 + vertex -842.398 244.161 295.27 + endloop + endfacet + facet normal 0.185895 -0.483594 -0.855324 + outer loop + vertex -841.451 245.995 294.366 + vertex -841.363 245.723 294.539 + vertex -842.755 244.646 294.846 + endloop + endfacet + facet normal 0.264573 -0.564341 -0.781997 + outer loop + vertex -842.755 244.646 294.846 + vertex -841.363 245.723 294.539 + vertex -842.664 244.454 295.015 + endloop + endfacet + facet normal 0.156726 -0.61057 -0.7763 + outer loop + vertex -842.755 244.646 294.846 + vertex -842.664 244.454 295.015 + vertex -844.195 243.643 295.343 + endloop + endfacet + facet normal 0.201565 -0.670088 -0.71439 + outer loop + vertex -844.195 243.643 295.343 + vertex -842.664 244.454 295.015 + vertex -844.12 243.485 295.513 + endloop + endfacet + facet normal 0.118161 -0.588741 -0.799638 + outer loop + vertex -842.664 244.454 295.015 + vertex -842.398 244.161 295.27 + vertex -844.12 243.485 295.513 + endloop + endfacet + facet normal 0.111884 -0.57633 -0.809522 + outer loop + vertex -844.12 243.485 295.513 + vertex -842.398 244.161 295.27 + vertex -843.863 243.154 295.784 + endloop + endfacet + facet normal 0.15875 -0.434523 -0.88656 + outer loop + vertex -841.288 246.37 294.211 + vertex -841.451 245.995 294.366 + vertex -842.578 244.948 294.678 + endloop + endfacet + facet normal 0.370916 -0.607956 -0.702005 + outer loop + vertex -842.578 244.948 294.678 + vertex -841.451 245.995 294.366 + vertex -842.755 244.646 294.846 + endloop + endfacet + facet normal 0.125008 -0.537219 -0.834128 + outer loop + vertex -842.578 244.948 294.678 + vertex -842.755 244.646 294.846 + vertex -844.002 243.841 295.177 + endloop + endfacet + facet normal 0.372495 -0.782607 -0.498772 + outer loop + vertex -844.002 243.841 295.177 + vertex -842.755 244.646 294.846 + vertex -844.195 243.643 295.343 + endloop + endfacet + facet normal 0.141574 -0.714251 -0.685421 + outer loop + vertex -844.002 243.841 295.177 + vertex -844.195 243.643 295.343 + vertex -845.483 243.059 295.686 + endloop + endfacet + facet normal 0.210707 -0.796762 -0.566369 + outer loop + vertex -845.483 243.059 295.686 + vertex -844.195 243.643 295.343 + vertex -845.622 242.917 295.834 + endloop + endfacet + facet normal 0.0572297 -0.746637 -0.662766 + outer loop + vertex -845.483 243.059 295.686 + vertex -845.622 242.917 295.834 + vertex -846.811 242.51 296.19 + endloop + endfacet + facet normal -0.0629366 -0.546452 -0.835122 + outer loop + vertex -846.811 242.51 296.19 + vertex -845.622 242.917 295.834 + vertex -846.581 242.412 296.237 + endloop + endfacet + facet normal 0.0515362 -0.608688 -0.791734 + outer loop + vertex -844.12 243.485 295.513 + vertex -843.863 243.154 295.784 + vertex -845.514 242.705 296.022 + endloop + endfacet + facet normal 0.0352416 -0.565805 -0.823785 + outer loop + vertex -845.514 242.705 296.022 + vertex -843.863 243.154 295.784 + vertex -845.207 242.246 296.351 + endloop + endfacet + facet normal 0.114409 -0.70068 -0.704243 + outer loop + vertex -844.195 243.643 295.343 + vertex -844.12 243.485 295.513 + vertex -845.622 242.917 295.834 + endloop + endfacet + facet normal 0.0779306 -0.638747 -0.76546 + outer loop + vertex -845.622 242.917 295.834 + vertex -844.12 243.485 295.513 + vertex -845.514 242.705 296.022 + endloop + endfacet + facet normal 0.0279089 -0.655159 -0.754975 + outer loop + vertex -845.622 242.917 295.834 + vertex -845.514 242.705 296.022 + vertex -846.581 242.412 296.237 + endloop + endfacet + facet normal -0.00340792 -0.583103 -0.812391 + outer loop + vertex -846.581 242.412 296.237 + vertex -845.514 242.705 296.022 + vertex -846.49 241.989 296.54 + endloop + endfacet + facet normal -0.00325255 -0.583243 -0.812291 + outer loop + vertex -845.514 242.705 296.022 + vertex -845.207 242.246 296.351 + vertex -846.49 241.989 296.54 + endloop + endfacet + facet normal -0.0165227 -0.538887 -0.842216 + outer loop + vertex -846.49 241.989 296.54 + vertex -845.207 242.246 296.351 + vertex -845.987 241.448 296.876 + endloop + endfacet + facet normal 0.51302 -0.299146 -0.804563 + outer loop + vertex -839.019 248.916 293.976 + vertex -839.001 249.735 293.683 + vertex -837.373 252.261 293.783 + endloop + endfacet + facet normal 0.513224 -0.301813 -0.803436 + outer loop + vertex -839.312 249.542 293.557 + vertex -837.578 253.45 293.197 + vertex -839.001 249.735 293.683 + endloop + endfacet + facet normal 0.51961 -0.303629 -0.798633 + outer loop + vertex -837.578 253.45 293.197 + vertex -837.373 252.261 293.783 + vertex -839.001 249.735 293.683 + endloop + endfacet + facet normal 0.651903 -0.243405 0.718176 + outer loop + vertex -839.761 248.627 293.654 + vertex -839.312 249.542 293.557 + vertex -840.22 247.894 293.822 + endloop + endfacet + facet normal 0.709401 -0.474399 -0.521244 + outer loop + vertex -840.22 247.894 293.822 + vertex -839.312 249.542 293.557 + vertex -840.278 247.691 293.927 + endloop + endfacet + facet normal 0.461907 -0.509374 -0.726072 + outer loop + vertex -840.22 247.894 293.822 + vertex -840.278 247.691 293.927 + vertex -841.288 246.37 294.211 + endloop + endfacet + facet normal 0.443975 -0.499493 -0.743904 + outer loop + vertex -841.288 246.37 294.211 + vertex -840.278 247.691 293.927 + vertex -841.451 245.995 294.366 + endloop + endfacet + facet normal 0.3318 -0.324253 -0.885872 + outer loop + vertex -839.001 249.735 293.683 + vertex -839.019 248.916 293.976 + vertex -840.211 247.388 294.089 + endloop + endfacet + facet normal 0.376135 -0.356563 -0.855211 + outer loop + vertex -840.211 247.388 294.089 + vertex -839.019 248.916 293.976 + vertex -839.929 247.022 294.366 + endloop + endfacet + facet normal 0.556211 -0.432205 -0.709808 + outer loop + vertex -839.312 249.542 293.557 + vertex -839.001 249.735 293.683 + vertex -840.278 247.691 293.927 + endloop + endfacet + facet normal 0.411148 -0.357001 -0.838753 + outer loop + vertex -840.278 247.691 293.927 + vertex -839.001 249.735 293.683 + vertex -840.211 247.388 294.089 + endloop + endfacet + facet normal 0.263954 -0.408559 -0.873732 + outer loop + vertex -840.278 247.691 293.927 + vertex -840.211 247.388 294.089 + vertex -841.451 245.995 294.366 + endloop + endfacet + facet normal 0.304509 -0.439011 -0.845307 + outer loop + vertex -841.451 245.995 294.366 + vertex -840.211 247.388 294.089 + vertex -841.363 245.723 294.539 + endloop + endfacet + facet normal 0.284668 -0.428568 -0.857493 + outer loop + vertex -840.211 247.388 294.089 + vertex -839.929 247.022 294.366 + vertex -841.363 245.723 294.539 + endloop + endfacet + facet normal 0.287151 -0.431033 -0.855427 + outer loop + vertex -841.363 245.723 294.539 + vertex -839.929 247.022 294.366 + vertex -841.069 245.393 294.804 + endloop + endfacet + facet normal 0.858979 -0.249996 -0.44683 + outer loop + vertex -835.146 261.909 292.382 + vertex -834.563 263.215 292.773 + vertex -835.969 258.505 292.706 + endloop + endfacet + facet normal 0.774967 -0.222853 -0.591407 + outer loop + vertex -835.969 258.505 292.706 + vertex -834.563 263.215 292.773 + vertex -835.769 257.732 293.259 + endloop + endfacet + facet normal 0.700581 -0.286559 -0.653506 + outer loop + vertex -835.969 258.505 292.706 + vertex -835.769 257.732 293.259 + vertex -837.578 253.45 293.197 + endloop + endfacet + facet normal 0.62711 -0.254312 -0.736247 + outer loop + vertex -837.578 253.45 293.197 + vertex -835.769 257.732 293.259 + vertex -837.373 252.261 293.783 + endloop + endfacet + facet normal -0.016359 -0.51101 -0.859419 + outer loop + vertex -844.473 239.503 297.985 + vertex -842.526 238.534 298.524 + vertex -844.798 239.017 298.28 + endloop + endfacet + facet normal -0.00221642 -0.45906 -0.888402 + outer loop + vertex -844.798 239.017 298.28 + vertex -842.526 238.534 298.524 + vertex -843.03 237.464 299.078 + endloop + endfacet + facet normal -0.0675372 -0.532749 -0.843574 + outer loop + vertex -845.987 241.448 296.876 + vertex -845.411 240.433 297.471 + vertex -846.609 240.976 297.224 + endloop + endfacet + facet normal -0.0281938 -0.505043 -0.862634 + outer loop + vertex -844.473 239.503 297.985 + vertex -844.798 239.017 298.28 + vertex -845.411 240.433 297.471 + endloop + endfacet + facet normal -0.0561984 -0.513507 -0.856243 + outer loop + vertex -844.798 239.017 298.28 + vertex -846.609 240.976 297.224 + vertex -845.411 240.433 297.471 + endloop + endfacet + facet normal 0.230278 -0.46268 -0.856095 + outer loop + vertex -839.377 243.654 296.279 + vertex -838.027 242.491 297.27 + vertex -840.54 241.746 296.997 + endloop + endfacet + facet normal 0.217316 -0.407758 -0.886853 + outer loop + vertex -840.54 241.746 296.997 + vertex -838.027 242.491 297.27 + vertex -839.553 240.188 297.955 + endloop + endfacet + facet normal 0.229847 -0.536903 -0.81173 + outer loop + vertex -840.471 244.066 295.696 + vertex -839.377 243.654 296.279 + vertex -841.438 242.862 296.219 + endloop + endfacet + facet normal 0.197709 -0.448656 -0.871561 + outer loop + vertex -841.438 242.862 296.219 + vertex -839.377 243.654 296.279 + vertex -840.54 241.746 296.997 + endloop + endfacet + facet normal 0.105351 -0.510328 -0.853503 + outer loop + vertex -841.438 242.862 296.219 + vertex -840.54 241.746 296.997 + vertex -842.757 241.485 296.879 + endloop + endfacet + facet normal 0.101022 -0.460601 -0.88184 + outer loop + vertex -842.757 241.485 296.879 + vertex -840.54 241.746 296.997 + vertex -841.833 240.132 297.692 + endloop + endfacet + facet normal 0.112728 -0.467748 -0.876644 + outer loop + vertex -840.54 241.746 296.997 + vertex -839.553 240.188 297.955 + vertex -841.833 240.132 297.692 + endloop + endfacet + facet normal 0.114022 -0.428693 -0.896226 + outer loop + vertex -841.833 240.132 297.692 + vertex -839.553 240.188 297.955 + vertex -840.855 239.075 298.322 + endloop + endfacet + facet normal 0.156305 -0.48815 -0.858649 + outer loop + vertex -840.702 244.833 295.218 + vertex -840.471 244.066 295.696 + vertex -842.033 243.63 295.659 + endloop + endfacet + facet normal 0.158812 -0.497644 -0.852719 + outer loop + vertex -842.033 243.63 295.659 + vertex -840.471 244.066 295.696 + vertex -841.438 242.862 296.219 + endloop + endfacet + facet normal 0.175749 -0.508268 -0.843076 + outer loop + vertex -841.069 245.393 294.804 + vertex -840.702 244.833 295.218 + vertex -842.398 244.161 295.27 + endloop + endfacet + facet normal 0.173476 -0.502816 -0.846807 + outer loop + vertex -842.398 244.161 295.27 + vertex -840.702 244.833 295.218 + vertex -842.033 243.63 295.659 + endloop + endfacet + facet normal 0.0866949 -0.55035 -0.830421 + outer loop + vertex -842.398 244.161 295.27 + vertex -842.033 243.63 295.659 + vertex -843.863 243.154 295.784 + endloop + endfacet + facet normal 0.0808356 -0.531207 -0.843377 + outer loop + vertex -843.863 243.154 295.784 + vertex -842.033 243.63 295.659 + vertex -843.424 242.51 296.232 + endloop + endfacet + facet normal 0.0901455 -0.539564 -0.837105 + outer loop + vertex -842.033 243.63 295.659 + vertex -841.438 242.862 296.219 + vertex -843.424 242.51 296.232 + endloop + endfacet + facet normal 0.081823 -0.493681 -0.865785 + outer loop + vertex -843.424 242.51 296.232 + vertex -841.438 242.862 296.219 + vertex -842.757 241.485 296.879 + endloop + endfacet + facet normal 0.0235779 -0.522922 -0.852054 + outer loop + vertex -843.424 242.51 296.232 + vertex -842.757 241.485 296.879 + vertex -844.677 241.421 296.865 + endloop + endfacet + facet normal 0.0226953 -0.492598 -0.869961 + outer loop + vertex -844.677 241.421 296.865 + vertex -842.757 241.485 296.879 + vertex -843.858 240.223 297.565 + endloop + endfacet + facet normal 0.0274949 -0.557885 -0.829462 + outer loop + vertex -843.863 243.154 295.784 + vertex -843.424 242.51 296.232 + vertex -845.207 242.246 296.351 + endloop + endfacet + facet normal 0.0202667 -0.520149 -0.853835 + outer loop + vertex -845.207 242.246 296.351 + vertex -843.424 242.51 296.232 + vertex -844.677 241.421 296.865 + endloop + endfacet + facet normal -0.0179603 -0.537884 -0.842827 + outer loop + vertex -845.207 242.246 296.351 + vertex -844.677 241.421 296.865 + vertex -845.987 241.448 296.876 + endloop + endfacet + facet normal -0.0175801 -0.512986 -0.858217 + outer loop + vertex -845.987 241.448 296.876 + vertex -844.677 241.421 296.865 + vertex -845.411 240.433 297.471 + endloop + endfacet + facet normal -0.0173742 -0.513099 -0.858153 + outer loop + vertex -844.677 241.421 296.865 + vertex -843.858 240.223 297.565 + vertex -845.411 240.433 297.471 + endloop + endfacet + facet normal -0.0142002 -0.494486 -0.86907 + outer loop + vertex -845.411 240.433 297.471 + vertex -843.858 240.223 297.565 + vertex -844.473 239.503 297.985 + endloop + endfacet + facet normal 0.0317752 -0.498525 -0.866293 + outer loop + vertex -842.757 241.485 296.879 + vertex -841.833 240.132 297.692 + vertex -843.858 240.223 297.565 + endloop + endfacet + facet normal -0.00805044 -0.49846 -0.866875 + outer loop + vertex -844.473 239.503 297.985 + vertex -843.858 240.223 297.565 + vertex -842.526 238.534 298.524 + endloop + endfacet + facet normal 0.0485825 -0.47783 -0.877108 + outer loop + vertex -840.855 239.075 298.322 + vertex -842.526 238.534 298.524 + vertex -841.833 240.132 297.692 + endloop + endfacet + facet normal 0.0338046 -0.473111 -0.880354 + outer loop + vertex -843.858 240.223 297.565 + vertex -841.833 240.132 297.692 + vertex -842.526 238.534 298.524 + endloop + endfacet + facet normal 0.491297 -0.277968 -0.825446 + outer loop + vertex -836.352 251.609 294.65 + vertex -835.261 250.116 295.802 + vertex -837.569 247.867 295.186 + endloop + endfacet + facet normal 0.504501 -0.295395 -0.811308 + outer loop + vertex -837.569 247.867 295.186 + vertex -835.261 250.116 295.802 + vertex -836.88 245.773 296.377 + endloop + endfacet + facet normal 0.501287 -0.280246 -0.818641 + outer loop + vertex -837.569 247.867 295.186 + vertex -838.325 248.875 294.378 + vertex -836.352 251.609 294.65 + endloop + endfacet + facet normal 0.468493 -0.279174 -0.838198 + outer loop + vertex -839.019 248.916 293.976 + vertex -837.373 252.261 293.783 + vertex -838.325 248.875 294.378 + endloop + endfacet + facet normal 0.508136 -0.285805 -0.812474 + outer loop + vertex -837.373 252.261 293.783 + vertex -836.352 251.609 294.65 + vertex -838.325 248.875 294.378 + endloop + endfacet + facet normal 0.420699 -0.35399 -0.835286 + outer loop + vertex -838.325 248.875 294.378 + vertex -837.569 247.867 295.186 + vertex -839.439 246.471 294.836 + endloop + endfacet + facet normal 0.427499 -0.365186 -0.826973 + outer loop + vertex -839.439 246.471 294.836 + vertex -837.569 247.867 295.186 + vertex -839.046 245.367 295.527 + endloop + endfacet + facet normal 0.446109 -0.380882 -0.809886 + outer loop + vertex -839.019 248.916 293.976 + vertex -838.325 248.875 294.378 + vertex -839.929 247.022 294.366 + endloop + endfacet + facet normal 0.411764 -0.35094 -0.841006 + outer loop + vertex -839.929 247.022 294.366 + vertex -838.325 248.875 294.378 + vertex -839.439 246.471 294.836 + endloop + endfacet + facet normal 0.309204 -0.442747 -0.841646 + outer loop + vertex -839.929 247.022 294.366 + vertex -839.439 246.471 294.836 + vertex -841.069 245.393 294.804 + endloop + endfacet + facet normal 0.301682 -0.43112 -0.850367 + outer loop + vertex -841.069 245.393 294.804 + vertex -839.439 246.471 294.836 + vertex -840.702 244.833 295.218 + endloop + endfacet + facet normal 0.297007 -0.428239 -0.853462 + outer loop + vertex -839.439 246.471 294.836 + vertex -839.046 245.367 295.527 + vertex -840.702 244.833 295.218 + endloop + endfacet + facet normal 0.299161 -0.438323 -0.847571 + outer loop + vertex -840.702 244.833 295.218 + vertex -839.046 245.367 295.527 + vertex -840.471 244.066 295.696 + endloop + endfacet + facet normal 0.29195 -0.431222 -0.853706 + outer loop + vertex -840.471 244.066 295.696 + vertex -839.046 245.367 295.527 + vertex -839.377 243.654 296.279 + endloop + endfacet + facet normal 0.335459 -0.354755 -0.872706 + outer loop + vertex -838.027 242.491 297.27 + vertex -839.377 243.654 296.279 + vertex -836.88 245.773 296.377 + endloop + endfacet + facet normal 0.398512 -0.350852 -0.847402 + outer loop + vertex -837.569 247.867 295.186 + vertex -836.88 245.773 296.377 + vertex -839.046 245.367 295.527 + endloop + endfacet + facet normal 0.398648 -0.432168 -0.808895 + outer loop + vertex -839.377 243.654 296.279 + vertex -839.046 245.367 295.527 + vertex -836.88 245.773 296.377 + endloop + endfacet + facet normal 0.594093 -0.182285 -0.78347 + outer loop + vertex -833.659 262.952 293.74 + vertex -833.092 260.392 294.765 + vertex -835.14 256.554 294.106 + endloop + endfacet + facet normal 0.592746 -0.181355 -0.784705 + outer loop + vertex -835.14 256.554 294.106 + vertex -833.092 260.392 294.765 + vertex -834.079 255.125 295.237 + endloop + endfacet + facet normal 0.684516 -0.212345 -0.697386 + outer loop + vertex -834.563 263.215 292.773 + vertex -833.659 262.952 293.74 + vertex -835.769 257.732 293.259 + endloop + endfacet + facet normal 0.64209 -0.191047 -0.742443 + outer loop + vertex -835.769 257.732 293.259 + vertex -833.659 262.952 293.74 + vertex -835.14 256.554 294.106 + endloop + endfacet + facet normal 0.583489 -0.245163 -0.774232 + outer loop + vertex -835.769 257.732 293.259 + vertex -835.14 256.554 294.106 + vertex -837.373 252.261 293.783 + endloop + endfacet + facet normal 0.544989 -0.222574 -0.808362 + outer loop + vertex -837.373 252.261 293.783 + vertex -835.14 256.554 294.106 + vertex -836.352 251.609 294.65 + endloop + endfacet + facet normal 0.553748 -0.224017 -0.801985 + outer loop + vertex -835.14 256.554 294.106 + vertex -834.079 255.125 295.237 + vertex -836.352 251.609 294.65 + endloop + endfacet + facet normal 0.549364 -0.22052 -0.805959 + outer loop + vertex -836.352 251.609 294.65 + vertex -834.079 255.125 295.237 + vertex -835.261 250.116 295.802 + endloop + endfacet + facet normal 0.631485 -0.163754 -0.757899 + outer loop + vertex -833.092 260.392 294.765 + vertex -833.659 262.952 293.74 + vertex -830.501 267.963 295.288 + endloop + endfacet + facet normal 0.698997 -0.160604 -0.696857 + outer loop + vertex -834.563 263.215 292.773 + vertex -832.272 272.125 293.017 + vertex -833.659 262.952 293.74 + endloop + endfacet + facet normal 0.621695 -0.154503 -0.76787 + outer loop + vertex -832.272 272.125 293.017 + vertex -830.501 267.963 295.288 + vertex -833.659 262.952 293.74 + endloop + endfacet + facet normal 0.633419 -0.128388 -0.763084 + outer loop + vertex -829.865 284.119 292.997 + vertex -828.374 279.563 295.001 + vertex -832.272 272.125 293.017 + endloop + endfacet + facet normal 0.644025 -0.13672 -0.752688 + outer loop + vertex -832.272 272.125 293.017 + vertex -828.374 279.563 295.001 + vertex -830.501 267.963 295.288 + endloop + endfacet + facet normal 0.63026 -0.137808 -0.764055 + outer loop + vertex -827.751 294.108 292.939 + vertex -826.315 290.001 294.865 + vertex -829.865 284.119 292.997 + endloop + endfacet + facet normal 0.625505 -0.133457 -0.768721 + outer loop + vertex -829.865 284.119 292.997 + vertex -826.315 290.001 294.865 + vertex -828.374 279.563 295.001 + endloop + endfacet + facet normal 0.619491 -0.155997 -0.769348 + outer loop + vertex -825.468 302.459 293.084 + vertex -824.125 299.246 294.818 + vertex -827.751 294.108 292.939 + endloop + endfacet + facet normal 0.613199 -0.149233 -0.775704 + outer loop + vertex -827.751 294.108 292.939 + vertex -824.125 299.246 294.818 + vertex -826.315 290.001 294.865 + endloop + endfacet + facet normal 0.614389 -0.183752 -0.767308 + outer loop + vertex -823.269 310.564 292.905 + vertex -821.735 307.775 294.801 + vertex -825.468 302.459 293.084 + endloop + endfacet + facet normal 0.601032 -0.169972 -0.780941 + outer loop + vertex -825.468 302.459 293.084 + vertex -821.735 307.775 294.801 + vertex -824.125 299.246 294.818 + endloop + endfacet + facet normal 0.610278 -0.199564 -0.766639 + outer loop + vertex -820.341 318.751 293.104 + vertex -819.082 316.06 294.807 + vertex -823.269 310.564 292.905 + endloop + endfacet + facet normal 0.604488 -0.192991 -0.772883 + outer loop + vertex -823.269 310.564 292.905 + vertex -819.082 316.06 294.807 + vertex -821.735 307.775 294.801 + endloop + endfacet + facet normal 0.609433 -0.223662 -0.760636 + outer loop + vertex -817.651 326.575 292.959 + vertex -816.19 324.194 294.829 + vertex -820.341 318.751 293.104 + endloop + endfacet + facet normal 0.597352 -0.210232 -0.773934 + outer loop + vertex -820.341 318.751 293.104 + vertex -816.19 324.194 294.829 + vertex -819.082 316.06 294.807 + endloop + endfacet + facet normal 0.609792 -0.23595 -0.756625 + outer loop + vertex -814.35 334.532 293.137 + vertex -813.141 332.179 294.846 + vertex -817.651 326.575 292.959 + endloop + endfacet + facet normal 0.604046 -0.229072 -0.763318 + outer loop + vertex -817.651 326.575 292.959 + vertex -813.141 332.179 294.846 + vertex -816.19 324.194 294.829 + endloop + endfacet + facet normal 0.617917 -0.260347 -0.741888 + outer loop + vertex -811.387 342.107 292.947 + vertex -810.016 339.97 294.839 + vertex -814.35 334.532 293.137 + endloop + endfacet + facet normal 0.602597 -0.242355 -0.760356 + outer loop + vertex -814.35 334.532 293.137 + vertex -810.016 339.97 294.839 + vertex -813.141 332.179 294.846 + endloop + endfacet + facet normal 0.625477 -0.273234 -0.730836 + outer loop + vertex -807.905 349.695 293.091 + vertex -806.825 347.552 294.816 + vertex -811.387 342.107 292.947 + endloop + endfacet + facet normal 0.616569 -0.261764 -0.742511 + outer loop + vertex -811.387 342.107 292.947 + vertex -806.825 347.552 294.816 + vertex -810.016 339.97 294.839 + endloop + endfacet + facet normal 0.637266 -0.291283 -0.713474 + outer loop + vertex -804.864 356.474 293.039 + vertex -803.625 354.904 294.786 + vertex -807.905 349.695 293.091 + endloop + endfacet + facet normal 0.624052 -0.274539 -0.731565 + outer loop + vertex -807.905 349.695 293.091 + vertex -803.625 354.904 294.786 + vertex -806.825 347.552 294.816 + endloop + endfacet + facet normal 0.653946 -0.301109 -0.694038 + outer loop + vertex -801.719 363.757 292.843 + vertex -800.375 362.24 294.767 + vertex -804.864 356.474 293.039 + endloop + endfacet + facet normal 0.641485 -0.286085 -0.711795 + outer loop + vertex -804.864 356.474 293.039 + vertex -800.375 362.24 294.767 + vertex -803.625 354.904 294.786 + endloop + endfacet + facet normal 0.667979 -0.290659 -0.68507 + outer loop + vertex -798.135 371.09 293.226 + vertex -796.993 369.727 294.918 + vertex -801.719 363.757 292.843 + endloop + endfacet + facet normal 0.664753 -0.286397 -0.689986 + outer loop + vertex -801.719 363.757 292.843 + vertex -796.993 369.727 294.918 + vertex -800.375 362.24 294.767 + endloop + endfacet + facet normal 0.708064 -0.2885 -0.644526 + outer loop + vertex -795.643 376.949 293.341 + vertex -793.904 377.141 295.166 + vertex -798.135 371.09 293.226 + endloop + endfacet + facet normal 0.687469 -0.263811 -0.676602 + outer loop + vertex -798.135 371.09 293.226 + vertex -793.904 377.141 295.166 + vertex -796.993 369.727 294.918 + endloop + endfacet + facet normal 0.16277 -0.365047 -0.91665 + outer loop + vertex -836.684 240.528 298.473 + vertex -834.993 238.137 299.725 + vertex -838.898 238.012 299.082 + endloop + endfacet + facet normal 0.114644 -0.429299 -0.895857 + outer loop + vertex -840.855 239.075 298.322 + vertex -839.553 240.188 297.955 + vertex -838.898 238.012 299.082 + endloop + endfacet + facet normal 0.208602 -0.403222 -0.891009 + outer loop + vertex -838.027 242.491 297.27 + vertex -836.684 240.528 298.473 + vertex -839.553 240.188 297.955 + endloop + endfacet + facet normal 0.208468 -0.399467 -0.89273 + outer loop + vertex -836.684 240.528 298.473 + vertex -838.898 238.012 299.082 + vertex -839.553 240.188 297.955 + endloop + endfacet + facet normal 0.0595516 -0.505605 -0.860707 + outer loop + vertex -840.855 239.075 298.322 + vertex -838.898 238.012 299.082 + vertex -842.526 238.534 298.524 + endloop + endfacet + facet normal 0.0835974 -0.396005 -0.914435 + outer loop + vertex -842.526 238.534 298.524 + vertex -838.898 238.012 299.082 + vertex -840.336 235.842 299.89 + endloop + endfacet + facet normal 0.0732568 -0.390382 -0.917734 + outer loop + vertex -838.898 238.012 299.082 + vertex -836.438 235.18 300.482 + vertex -840.336 235.842 299.89 + endloop + endfacet + facet normal 0.0895311 -0.317949 -0.943871 + outer loop + vertex -840.336 235.842 299.89 + vertex -836.438 235.18 300.482 + vertex -836.859 232.569 301.322 + endloop + endfacet + facet normal 0.382636 -0.247745 -0.890063 + outer loop + vertex -833.821 248.224 297.144 + vertex -832.027 246.076 298.512 + vertex -835.121 243.911 297.785 + endloop + endfacet + facet normal 0.373213 -0.23148 -0.898404 + outer loop + vertex -835.121 243.911 297.785 + vertex -832.027 246.076 298.512 + vertex -833.399 241.673 299.077 + endloop + endfacet + facet normal 0.435655 -0.27576 -0.856832 + outer loop + vertex -835.261 250.116 295.802 + vertex -833.821 248.224 297.144 + vertex -836.88 245.773 296.377 + endloop + endfacet + facet normal 0.423516 -0.256896 -0.868699 + outer loop + vertex -836.88 245.773 296.377 + vertex -833.821 248.224 297.144 + vertex -835.121 243.911 297.785 + endloop + endfacet + facet normal 0.327767 -0.353046 -0.876315 + outer loop + vertex -836.88 245.773 296.377 + vertex -835.121 243.911 297.785 + vertex -838.027 242.491 297.27 + endloop + endfacet + facet normal 0.317779 -0.327734 -0.889723 + outer loop + vertex -838.027 242.491 297.27 + vertex -835.121 243.911 297.785 + vertex -836.684 240.528 298.473 + endloop + endfacet + facet normal 0.27604 -0.31236 -0.908974 + outer loop + vertex -835.121 243.911 297.785 + vertex -833.399 241.673 299.077 + vertex -836.684 240.528 298.473 + endloop + endfacet + facet normal 0.269955 -0.29004 -0.918151 + outer loop + vertex -836.684 240.528 298.473 + vertex -833.399 241.673 299.077 + vertex -834.993 238.137 299.725 + endloop + endfacet + facet normal 0.522044 -0.162609 -0.837274 + outer loop + vertex -831.479 259.683 296.099 + vertex -830.192 256.97 297.428 + vertex -832.684 253.399 296.568 + endloop + endfacet + facet normal 0.509973 -0.151929 -0.846667 + outer loop + vertex -832.684 253.399 296.568 + vertex -830.192 256.97 297.428 + vertex -830.927 251.469 297.973 + endloop + endfacet + facet normal 0.578636 -0.179683 -0.795546 + outer loop + vertex -833.092 260.392 294.765 + vertex -831.479 259.683 296.099 + vertex -834.079 255.125 295.237 + endloop + endfacet + facet normal 0.563289 -0.168398 -0.808918 + outer loop + vertex -834.079 255.125 295.237 + vertex -831.479 259.683 296.099 + vertex -832.684 253.399 296.568 + endloop + endfacet + facet normal 0.520661 -0.216007 -0.825986 + outer loop + vertex -834.079 255.125 295.237 + vertex -832.684 253.399 296.568 + vertex -835.261 250.116 295.802 + endloop + endfacet + facet normal 0.509323 -0.204804 -0.83585 + outer loop + vertex -835.261 250.116 295.802 + vertex -832.684 253.399 296.568 + vertex -833.821 248.224 297.144 + endloop + endfacet + facet normal 0.469433 -0.198759 -0.860307 + outer loop + vertex -832.684 253.399 296.568 + vertex -830.927 251.469 297.973 + vertex -833.821 248.224 297.144 + endloop + endfacet + facet normal 0.451842 -0.179615 -0.873829 + outer loop + vertex -833.821 248.224 297.144 + vertex -830.927 251.469 297.973 + vertex -832.027 246.076 298.512 + endloop + endfacet + facet normal 0.543799 -0.146894 -0.826259 + outer loop + vertex -830.192 256.97 297.428 + vertex -831.479 259.683 296.099 + vertex -827.57 264.637 297.791 + endloop + endfacet + facet normal 0.590872 -0.147416 -0.793183 + outer loop + vertex -833.092 260.392 294.765 + vertex -830.501 267.963 295.288 + vertex -831.479 259.683 296.099 + endloop + endfacet + facet normal 0.542075 -0.145035 -0.82772 + outer loop + vertex -830.501 267.963 295.288 + vertex -827.57 264.637 297.791 + vertex -831.479 259.683 296.099 + endloop + endfacet + facet normal 0.56346 -0.123535 -0.816855 + outer loop + vertex -828.374 279.563 295.001 + vertex -825.769 276.01 297.336 + vertex -830.501 267.963 295.288 + endloop + endfacet + facet normal 0.561039 -0.121615 -0.818807 + outer loop + vertex -830.501 267.963 295.288 + vertex -825.769 276.01 297.336 + vertex -827.57 264.637 297.791 + endloop + endfacet + facet normal 0.567801 -0.122669 -0.813975 + outer loop + vertex -826.315 290.001 294.865 + vertex -823.819 286.612 297.116 + vertex -828.374 279.563 295.001 + endloop + endfacet + facet normal 0.565864 -0.120935 -0.815581 + outer loop + vertex -828.374 279.563 295.001 + vertex -823.819 286.612 297.116 + vertex -825.769 276.01 297.336 + endloop + endfacet + facet normal 0.562887 -0.13751 -0.815015 + outer loop + vertex -824.125 299.246 294.818 + vertex -821.65 296.265 297.03 + vertex -826.315 290.001 294.865 + endloop + endfacet + facet normal 0.558403 -0.132839 -0.818865 + outer loop + vertex -826.315 290.001 294.865 + vertex -821.65 296.265 297.03 + vertex -823.819 286.612 297.116 + endloop + endfacet + facet normal 0.556862 -0.157665 -0.815504 + outer loop + vertex -821.735 307.775 294.801 + vertex -819.227 305.204 297.01 + vertex -824.125 299.246 294.818 + endloop + endfacet + facet normal 0.55127 -0.151228 -0.820507 + outer loop + vertex -824.125 299.246 294.818 + vertex -819.227 305.204 297.01 + vertex -821.65 296.265 297.03 + endloop + endfacet + facet normal 0.553337 -0.176575 -0.814026 + outer loop + vertex -819.082 316.06 294.807 + vertex -816.563 313.776 297.015 + vertex -821.735 307.775 294.801 + endloop + endfacet + facet normal 0.547718 -0.169804 -0.81925 + outer loop + vertex -821.735 307.775 294.801 + vertex -816.563 313.776 297.015 + vertex -819.227 305.204 297.01 + endloop + endfacet + facet normal 0.550977 -0.193644 -0.811743 + outer loop + vertex -816.19 324.194 294.829 + vertex -813.664 322.158 297.029 + vertex -819.082 316.06 294.807 + endloop + endfacet + facet normal 0.545884 -0.187331 -0.81665 + outer loop + vertex -819.082 316.06 294.807 + vertex -813.664 322.158 297.029 + vertex -816.563 313.776 297.015 + endloop + endfacet + facet normal 0.554552 -0.210091 -0.805191 + outer loop + vertex -813.141 332.179 294.846 + vertex -810.636 330.378 297.041 + vertex -816.19 324.194 294.829 + endloop + endfacet + facet normal 0.546731 -0.200274 -0.813004 + outer loop + vertex -816.19 324.194 294.829 + vertex -810.636 330.378 297.041 + vertex -813.664 322.158 297.029 + endloop + endfacet + facet normal 0.559505 -0.225096 -0.797675 + outer loop + vertex -810.016 339.97 294.839 + vertex -807.505 338.392 297.046 + vertex -813.141 332.179 294.846 + endloop + endfacet + facet normal 0.551621 -0.215031 -0.8059 + outer loop + vertex -813.141 332.179 294.846 + vertex -807.505 338.392 297.046 + vertex -810.636 330.378 297.041 + endloop + endfacet + facet normal 0.568096 -0.241501 -0.78673 + outer loop + vertex -806.825 347.552 294.816 + vertex -804.331 346.187 297.036 + vertex -810.016 339.97 294.839 + endloop + endfacet + facet normal 0.557842 -0.228156 -0.797971 + outer loop + vertex -810.016 339.97 294.839 + vertex -804.331 346.187 297.036 + vertex -807.505 338.392 297.046 + endloop + endfacet + facet normal 0.579723 -0.255417 -0.773746 + outer loop + vertex -803.625 354.904 294.786 + vertex -801.151 353.806 297.003 + vertex -806.825 347.552 294.816 + endloop + endfacet + facet normal 0.568494 -0.240704 -0.786687 + outer loop + vertex -806.825 347.552 294.816 + vertex -801.151 353.806 297.003 + vertex -804.331 346.187 297.036 + endloop + endfacet + facet normal 0.592742 -0.26462 -0.760679 + outer loop + vertex -800.375 362.24 294.767 + vertex -797.92 361.377 296.981 + vertex -803.625 354.904 294.786 + endloop + endfacet + facet normal 0.581848 -0.250593 -0.773729 + outer loop + vertex -803.625 354.904 294.786 + vertex -797.92 361.377 296.981 + vertex -801.151 353.806 297.003 + endloop + endfacet + facet normal 0.604734 -0.257996 -0.753482 + outer loop + vertex -796.993 369.727 294.918 + vertex -794.605 369.046 297.068 + vertex -800.375 362.24 294.767 + endloop + endfacet + facet normal 0.598373 -0.249988 -0.76122 + outer loop + vertex -800.375 362.24 294.767 + vertex -794.605 369.046 297.068 + vertex -797.92 361.377 296.981 + endloop + endfacet + facet normal 0.6264 -0.236152 -0.74287 + outer loop + vertex -793.904 377.141 295.166 + vertex -791.397 376.873 297.365 + vertex -796.993 369.727 294.918 + endloop + endfacet + facet normal 0.616059 -0.223821 -0.755232 + outer loop + vertex -796.993 369.727 294.918 + vertex -791.397 376.873 297.365 + vertex -794.605 369.046 297.068 + endloop + endfacet + facet normal 0.687007 -0.194405 -0.700162 + outer loop + vertex -792.003 384.848 294.891 + vertex -789.072 384.933 297.743 + vertex -793.904 377.141 295.166 + endloop + endfacet + facet normal 0.642857 -0.150176 -0.751121 + outer loop + vertex -793.904 377.141 295.166 + vertex -789.072 384.933 297.743 + vertex -791.397 376.873 297.365 + endloop + endfacet + facet normal 0.0846119 -0.317365 -0.944521 + outer loop + vertex -836.438 235.18 300.482 + vertex -833.869 232.451 301.63 + vertex -836.859 232.569 301.322 + endloop + endfacet + facet normal 0.0879249 -0.270571 -0.958677 + outer loop + vertex -836.859 232.569 301.322 + vertex -833.869 232.451 301.63 + vertex -834.173 230.161 302.248 + endloop + endfacet + facet normal 0.0689202 -0.268611 -0.96078 + outer loop + vertex -833.869 232.451 301.63 + vertex -831.452 229.725 302.565 + vertex -834.173 230.161 302.248 + endloop + endfacet + facet normal 0.0751642 -0.235604 -0.968938 + outer loop + vertex -834.173 230.161 302.248 + vertex -831.452 229.725 302.565 + vertex -832.079 227.514 303.054 + endloop + endfacet + facet normal 0.27362 -0.19289 -0.942298 + outer loop + vertex -830.185 243.54 299.767 + vertex -828.737 240.934 300.721 + vertex -831.556 239.258 300.245 + endloop + endfacet + facet normal 0.26816 -0.182682 -0.945895 + outer loop + vertex -831.556 239.258 300.245 + vertex -828.737 240.934 300.721 + vertex -829.365 237.054 301.292 + endloop + endfacet + facet normal 0.324744 -0.21916 -0.92006 + outer loop + vertex -832.027 246.076 298.512 + vertex -830.185 243.54 299.767 + vertex -833.399 241.673 299.077 + endloop + endfacet + facet normal 0.317834 -0.205195 -0.925676 + outer loop + vertex -833.399 241.673 299.077 + vertex -830.185 243.54 299.767 + vertex -831.556 239.258 300.245 + endloop + endfacet + facet normal 0.230906 -0.2752 -0.933246 + outer loop + vertex -833.399 241.673 299.077 + vertex -831.556 239.258 300.245 + vertex -834.993 238.137 299.725 + endloop + endfacet + facet normal 0.223307 -0.247479 -0.942809 + outer loop + vertex -834.993 238.137 299.725 + vertex -831.556 239.258 300.245 + vertex -832.826 235.594 300.906 + endloop + endfacet + facet normal 0.20814 -0.243056 -0.947418 + outer loop + vertex -831.556 239.258 300.245 + vertex -829.365 237.054 301.292 + vertex -832.826 235.594 300.906 + endloop + endfacet + facet normal 0.19352 -0.205243 -0.959388 + outer loop + vertex -832.826 235.594 300.906 + vertex -829.365 237.054 301.292 + vertex -830.44 232.999 301.943 + endloop + endfacet + facet normal 0.387321 -0.123229 -0.913672 + outer loop + vertex -827.785 256.196 298.866 + vertex -824.856 253.066 300.53 + vertex -828.796 249.129 299.391 + endloop + endfacet + facet normal 0.380636 -0.115432 -0.917492 + outer loop + vertex -828.796 249.129 299.391 + vertex -824.856 253.066 300.53 + vertex -826.744 245.527 300.696 + endloop + endfacet + facet normal 0.471388 -0.149015 -0.869245 + outer loop + vertex -830.192 256.97 297.428 + vertex -827.785 256.196 298.866 + vertex -830.927 251.469 297.973 + endloop + endfacet + facet normal 0.446756 -0.129625 -0.885216 + outer loop + vertex -830.927 251.469 297.973 + vertex -827.785 256.196 298.866 + vertex -828.796 249.129 299.391 + endloop + endfacet + facet normal 0.407117 -0.172793 -0.896883 + outer loop + vertex -830.927 251.469 297.973 + vertex -828.796 249.129 299.391 + vertex -832.027 246.076 298.512 + endloop + endfacet + facet normal 0.396342 -0.15929 -0.904179 + outer loop + vertex -832.027 246.076 298.512 + vertex -828.796 249.129 299.391 + vertex -830.185 243.54 299.767 + endloop + endfacet + facet normal 0.335461 -0.145948 -0.93068 + outer loop + vertex -828.796 249.129 299.391 + vertex -826.744 245.527 300.696 + vertex -830.185 243.54 299.767 + endloop + endfacet + facet normal 0.338371 -0.151929 -0.928667 + outer loop + vertex -830.185 243.54 299.767 + vertex -826.744 245.527 300.696 + vertex -828.737 240.934 300.721 + endloop + endfacet + facet normal 0.411168 -0.0970479 -0.906379 + outer loop + vertex -824.856 253.066 300.53 + vertex -827.785 256.196 298.866 + vertex -823.583 262.407 300.108 + endloop + endfacet + facet normal 0.479555 -0.122904 -0.868862 + outer loop + vertex -830.192 256.97 297.428 + vertex -827.57 264.637 297.791 + vertex -827.785 256.196 298.866 + endloop + endfacet + facet normal 0.445588 -0.124296 -0.886568 + outer loop + vertex -827.57 264.637 297.791 + vertex -823.583 262.407 300.108 + vertex -827.785 256.196 298.866 + endloop + endfacet + facet normal 0.475167 -0.110188 -0.872969 + outer loop + vertex -825.769 276.01 297.336 + vertex -822.207 272.694 299.693 + vertex -827.57 264.637 297.791 + endloop + endfacet + facet normal 0.458911 -0.0969546 -0.883177 + outer loop + vertex -827.57 264.637 297.791 + vertex -822.207 272.694 299.693 + vertex -823.583 262.407 300.108 + endloop + endfacet + facet normal 0.487738 -0.107615 -0.866332 + outer loop + vertex -823.819 286.612 297.116 + vertex -820.372 283.221 299.479 + vertex -825.769 276.01 297.336 + endloop + endfacet + facet normal 0.481479 -0.101679 -0.870539 + outer loop + vertex -825.769 276.01 297.336 + vertex -820.372 283.221 299.479 + vertex -822.207 272.694 299.693 + endloop + endfacet + facet normal 0.487754 -0.117372 -0.865055 + outer loop + vertex -821.65 296.265 297.03 + vertex -818.208 293.114 299.398 + vertex -823.819 286.612 297.116 + endloop + endfacet + facet normal 0.483687 -0.112851 -0.867935 + outer loop + vertex -823.819 286.612 297.116 + vertex -818.208 293.114 299.398 + vertex -820.372 283.221 299.479 + endloop + endfacet + facet normal 0.485523 -0.133506 -0.86397 + outer loop + vertex -819.227 305.204 297.01 + vertex -815.772 302.372 299.39 + vertex -821.65 296.265 297.03 + endloop + endfacet + facet normal 0.480525 -0.127256 -0.867699 + outer loop + vertex -821.65 296.265 297.03 + vertex -815.772 302.372 299.39 + vertex -818.208 293.114 299.398 + endloop + endfacet + facet normal 0.483265 -0.149745 -0.862573 + outer loop + vertex -816.563 313.776 297.015 + vertex -813.084 311.239 299.404 + vertex -819.227 305.204 297.01 + endloop + endfacet + facet normal 0.478691 -0.143671 -0.866149 + outer loop + vertex -819.227 305.204 297.01 + vertex -813.084 311.239 299.404 + vertex -815.772 302.372 299.39 + endloop + endfacet + facet normal 0.483174 -0.165573 -0.859726 + outer loop + vertex -813.664 322.158 297.029 + vertex -810.189 319.908 299.416 + vertex -816.563 313.776 297.015 + endloop + endfacet + facet normal 0.477913 -0.158431 -0.864002 + outer loop + vertex -816.563 313.776 297.015 + vertex -810.189 319.908 299.416 + vertex -813.084 311.239 299.404 + endloop + endfacet + facet normal 0.485286 -0.177581 -0.856132 + outer loop + vertex -810.636 330.378 297.041 + vertex -807.144 328.424 299.425 + vertex -813.664 322.158 297.029 + endloop + endfacet + facet normal 0.480259 -0.170738 -0.860349 + outer loop + vertex -813.664 322.158 297.029 + vertex -807.144 328.424 299.425 + vertex -810.189 319.908 299.416 + endloop + endfacet + facet normal 0.490742 -0.191213 -0.850065 + outer loop + vertex -807.505 338.392 297.046 + vertex -804.015 336.746 299.431 + vertex -810.636 330.378 297.041 + endloop + endfacet + facet normal 0.483437 -0.181232 -0.856413 + outer loop + vertex -810.636 330.378 297.041 + vertex -804.015 336.746 299.431 + vertex -807.144 328.424 299.425 + endloop + endfacet + facet normal 0.4986 -0.204096 -0.842462 + outer loop + vertex -804.331 346.187 297.036 + vertex -800.835 344.848 299.43 + vertex -807.505 338.392 297.046 + endloop + endfacet + facet normal 0.490147 -0.192539 -0.850109 + outer loop + vertex -807.505 338.392 297.046 + vertex -800.835 344.848 299.43 + vertex -804.015 336.746 299.431 + endloop + endfacet + facet normal 0.51077 -0.216799 -0.831933 + outer loop + vertex -801.151 353.806 297.003 + vertex -797.65 352.781 299.419 + vertex -804.331 346.187 297.036 + endloop + endfacet + facet normal 0.499562 -0.201627 -0.842487 + outer loop + vertex -804.331 346.187 297.036 + vertex -797.65 352.781 299.419 + vertex -800.835 344.848 299.43 + endloop + endfacet + facet normal 0.523315 -0.225756 -0.821691 + outer loop + vertex -797.92 361.377 296.981 + vertex -794.449 360.652 299.391 + vertex -801.151 353.806 297.003 + endloop + endfacet + facet normal 0.512516 -0.211512 -0.83222 + outer loop + vertex -801.151 353.806 297.003 + vertex -794.449 360.652 299.391 + vertex -797.65 352.781 299.419 + endloop + endfacet + facet normal 0.533253 -0.221216 -0.81652 + outer loop + vertex -794.605 369.046 297.068 + vertex -791.219 368.584 299.404 + vertex -797.92 361.377 296.981 + endloop + endfacet + facet normal 0.52678 -0.213064 -0.822865 + outer loop + vertex -797.92 361.377 296.981 + vertex -791.219 368.584 299.404 + vertex -794.449 360.652 299.391 + endloop + endfacet + facet normal 0.54364 -0.191788 -0.817112 + outer loop + vertex -791.397 376.873 297.365 + vertex -788.069 376.681 299.624 + vertex -794.605 369.046 297.068 + endloop + endfacet + facet normal 0.540332 -0.187921 -0.8202 + outer loop + vertex -794.605 369.046 297.068 + vertex -788.069 376.681 299.624 + vertex -791.219 368.584 299.404 + endloop + endfacet + facet normal 0.577649 -0.128791 -0.806061 + outer loop + vertex -789.072 384.933 297.743 + vertex -785.521 385.03 300.273 + vertex -791.397 376.873 297.365 + endloop + endfacet + facet normal 0.554401 -0.105081 -0.825589 + outer loop + vertex -791.397 376.873 297.365 + vertex -785.521 385.03 300.273 + vertex -788.069 376.681 299.624 + endloop + endfacet + facet normal 0.0534131 -0.230044 -0.971713 + outer loop + vertex -831.452 229.725 302.565 + vertex -828.854 226.694 303.426 + vertex -832.079 227.514 303.054 + endloop + endfacet + facet normal 0.0591957 -0.209268 -0.976065 + outer loop + vertex -832.079 227.514 303.054 + vertex -828.854 226.694 303.426 + vertex -829.091 224.269 303.931 + endloop + endfacet + facet normal 0.0425986 -0.207883 -0.977226 + outer loop + vertex -828.854 226.694 303.426 + vertex -825.374 223.387 304.281 + vertex -829.091 224.269 303.931 + endloop + endfacet + facet normal 0.050223 -0.177936 -0.98276 + outer loop + vertex -829.091 224.269 303.931 + vertex -825.374 223.387 304.281 + vertex -825.971 221.17 304.652 + endloop + endfacet + facet normal 0.220666 -0.139411 -0.965335 + outer loop + vertex -825.933 240.348 301.659 + vertex -822.171 237.985 302.86 + vertex -826.638 234.619 302.325 + endloop + endfacet + facet normal 0.201018 -0.112097 -0.973153 + outer loop + vertex -826.638 234.619 302.325 + vertex -822.171 237.985 302.86 + vertex -823.543 230.996 303.382 + endloop + endfacet + facet normal 0.27714 -0.183725 -0.943101 + outer loop + vertex -828.737 240.934 300.721 + vertex -825.933 240.348 301.659 + vertex -829.365 237.054 301.292 + endloop + endfacet + facet normal 0.238091 -0.141044 -0.960947 + outer loop + vertex -829.365 237.054 301.292 + vertex -825.933 240.348 301.659 + vertex -826.638 234.619 302.325 + endloop + endfacet + facet normal 0.183217 -0.202917 -0.961902 + outer loop + vertex -829.365 237.054 301.292 + vertex -826.638 234.619 302.325 + vertex -830.44 232.999 301.943 + endloop + endfacet + facet normal 0.168056 -0.164981 -0.971874 + outer loop + vertex -830.44 232.999 301.943 + vertex -826.638 234.619 302.325 + vertex -827.9 230.015 302.888 + endloop + endfacet + facet normal 0.146478 -0.159598 -0.976254 + outer loop + vertex -826.638 234.619 302.325 + vertex -823.543 230.996 303.382 + vertex -827.9 230.015 302.888 + endloop + endfacet + facet normal 0.142658 -0.140911 -0.97969 + outer loop + vertex -827.9 230.015 302.888 + vertex -823.543 230.996 303.382 + vertex -825.42 226.89 303.699 + endloop + endfacet + facet normal 0.289832 -0.130973 -0.948074 + outer loop + vertex -828.737 240.934 300.721 + vertex -826.744 245.527 300.696 + vertex -825.933 240.348 301.659 + endloop + endfacet + facet normal 0.251438 -0.0895928 -0.963718 + outer loop + vertex -822.171 237.985 302.86 + vertex -825.933 240.348 301.659 + vertex -821.718 247.287 302.114 + endloop + endfacet + facet normal 0.301355 -0.0962692 -0.94864 + outer loop + vertex -824.856 253.066 300.53 + vertex -821.718 247.287 302.114 + vertex -826.744 245.527 300.696 + endloop + endfacet + facet normal 0.310192 -0.126692 -0.942194 + outer loop + vertex -825.933 240.348 301.659 + vertex -826.744 245.527 300.696 + vertex -821.718 247.287 302.114 + endloop + endfacet + facet normal 0.340395 -0.0887393 -0.936086 + outer loop + vertex -823.583 262.407 300.108 + vertex -819.689 258.397 301.904 + vertex -824.856 253.066 300.53 + endloop + endfacet + facet normal 0.330636 -0.0781384 -0.940518 + outer loop + vertex -824.856 253.066 300.53 + vertex -819.689 258.397 301.904 + vertex -821.718 247.287 302.114 + endloop + endfacet + facet normal 0.371591 -0.0869316 -0.924318 + outer loop + vertex -822.207 272.694 299.693 + vertex -818.048 269.034 301.709 + vertex -823.583 262.407 300.108 + endloop + endfacet + facet normal 0.355763 -0.0719029 -0.931806 + outer loop + vertex -823.583 262.407 300.108 + vertex -818.048 269.034 301.709 + vertex -819.689 258.397 301.904 + endloop + endfacet + facet normal 0.388863 -0.086489 -0.917227 + outer loop + vertex -820.372 283.221 299.479 + vertex -816.219 279.53 301.587 + vertex -822.207 272.694 299.693 + endloop + endfacet + facet normal 0.379372 -0.0768409 -0.922048 + outer loop + vertex -822.207 272.694 299.693 + vertex -816.219 279.53 301.587 + vertex -818.048 269.034 301.709 + endloop + endfacet + facet normal 0.394713 -0.0937636 -0.914008 + outer loop + vertex -818.208 293.114 299.398 + vertex -814.058 289.602 301.551 + vertex -820.372 283.221 299.479 + endloop + endfacet + facet normal 0.388678 -0.0867292 -0.917283 + outer loop + vertex -820.372 283.221 299.479 + vertex -814.058 289.602 301.551 + vertex -816.219 279.53 301.587 + endloop + endfacet + facet normal 0.393862 -0.104494 -0.913211 + outer loop + vertex -815.772 302.372 299.39 + vertex -811.599 299.132 301.56 + vertex -818.208 293.114 299.398 + endloop + endfacet + facet normal 0.390264 -0.0997988 -0.915278 + outer loop + vertex -818.208 293.114 299.398 + vertex -811.599 299.132 301.56 + vertex -814.058 289.602 301.551 + endloop + endfacet + facet normal 0.393576 -0.117796 -0.911714 + outer loop + vertex -813.084 311.239 299.404 + vertex -808.905 308.297 301.588 + vertex -815.772 302.372 299.39 + endloop + endfacet + facet normal 0.389042 -0.111529 -0.914444 + outer loop + vertex -815.772 302.372 299.39 + vertex -808.905 308.297 301.588 + vertex -811.599 299.132 301.56 + endloop + endfacet + facet normal 0.393945 -0.130325 -0.909848 + outer loop + vertex -810.189 319.908 299.416 + vertex -806.012 317.269 301.602 + vertex -813.084 311.239 299.404 + endloop + endfacet + facet normal 0.38955 -0.124169 -0.912597 + outer loop + vertex -813.084 311.239 299.404 + vertex -806.012 317.269 301.602 + vertex -808.905 308.297 301.588 + endloop + endfacet + facet normal 0.396627 -0.14079 -0.907119 + outer loop + vertex -807.144 328.424 299.425 + vertex -802.98 326.11 301.605 + vertex -810.189 319.908 299.416 + endloop + endfacet + facet normal 0.391787 -0.134063 -0.910236 + outer loop + vertex -810.189 319.908 299.416 + vertex -802.98 326.11 301.605 + vertex -806.012 317.269 301.602 + endloop + endfacet + facet normal 0.40324 -0.151038 -0.902544 + outer loop + vertex -804.015 336.746 299.431 + vertex -799.865 334.778 301.614 + vertex -807.144 328.424 299.425 + endloop + endfacet + facet normal 0.396276 -0.141467 -0.907167 + outer loop + vertex -807.144 328.424 299.425 + vertex -799.865 334.778 301.614 + vertex -802.98 326.11 301.605 + endloop + endfacet + facet normal 0.411424 -0.161652 -0.896995 + outer loop + vertex -800.835 344.848 299.43 + vertex -796.696 343.241 301.617 + vertex -804.015 336.746 299.431 + endloop + endfacet + facet normal 0.403382 -0.150726 -0.902532 + outer loop + vertex -804.015 336.746 299.431 + vertex -796.696 343.241 301.617 + vertex -799.865 334.778 301.614 + endloop + endfacet + facet normal 0.42146 -0.170341 -0.890705 + outer loop + vertex -797.65 352.781 299.419 + vertex -793.499 351.541 301.62 + vertex -800.835 344.848 299.43 + endloop + endfacet + facet normal 0.412614 -0.158587 -0.896995 + outer loop + vertex -800.835 344.848 299.43 + vertex -793.499 351.541 301.62 + vertex -796.696 343.241 301.617 + endloop + endfacet + facet normal 0.434514 -0.179966 -0.882502 + outer loop + vertex -794.449 360.652 299.391 + vertex -790.301 359.786 301.609 + vertex -797.65 352.781 299.419 + endloop + endfacet + facet normal 0.423058 -0.165323 -0.890893 + outer loop + vertex -797.65 352.781 299.419 + vertex -790.301 359.786 301.609 + vertex -793.499 351.541 301.62 + endloop + endfacet + facet normal 0.447134 -0.180543 -0.876057 + outer loop + vertex -791.219 368.584 299.404 + vertex -787.122 368.071 301.601 + vertex -794.449 360.652 299.391 + endloop + endfacet + facet normal 0.437321 -0.168682 -0.883344 + outer loop + vertex -794.449 360.652 299.391 + vertex -787.122 368.071 301.601 + vertex -790.301 359.786 301.609 + endloop + endfacet + facet normal 0.452373 -0.152105 -0.878762 + outer loop + vertex -788.069 376.681 299.624 + vertex -784.088 376.486 301.707 + vertex -791.219 368.584 299.404 + endloop + endfacet + facet normal 0.452225 -0.151941 -0.878867 + outer loop + vertex -791.219 368.584 299.404 + vertex -784.088 376.486 301.707 + vertex -787.122 368.071 301.601 + endloop + endfacet + facet normal 0.457209 -0.0706865 -0.886546 + outer loop + vertex -785.521 385.03 300.273 + vertex -781.619 385.131 302.277 + vertex -788.069 376.681 299.624 + endloop + endfacet + facet normal 0.459573 -0.072932 -0.885141 + outer loop + vertex -788.069 376.681 299.624 + vertex -781.619 385.131 302.277 + vertex -784.088 376.486 301.707 + endloop + endfacet + facet normal 0.0241326 -0.171267 -0.984929 + outer loop + vertex -825.971 221.17 304.652 + vertex -825.374 223.387 304.281 + vertex -820.546 218.151 305.31 + endloop + endfacet + facet normal 0.164256 -0.10545 -0.980765 + outer loop + vertex -822.171 237.985 302.86 + vertex -817.992 233.503 304.042 + vertex -823.543 230.996 303.382 + endloop + endfacet + facet normal 0.161279 -0.0985376 -0.981977 + outer loop + vertex -817.992 233.503 304.042 + vertex -820.246 225.284 304.496 + vertex -823.543 230.996 303.382 + endloop + endfacet + facet normal 0.21494 -0.0885265 -0.972607 + outer loop + vertex -821.718 247.287 302.114 + vertex -816.573 243.072 303.634 + vertex -822.171 237.985 302.86 + endloop + endfacet + facet normal 0.199903 -0.0712772 -0.97722 + outer loop + vertex -822.171 237.985 302.86 + vertex -816.573 243.072 303.634 + vertex -817.992 233.503 304.042 + endloop + endfacet + facet normal 0.248869 -0.063701 -0.96644 + outer loop + vertex -819.689 258.397 301.904 + vertex -815.179 253.78 303.369 + vertex -821.718 247.287 302.114 + endloop + endfacet + facet normal 0.241048 -0.0553423 -0.968934 + outer loop + vertex -821.718 247.287 302.114 + vertex -815.179 253.78 303.369 + vertex -816.573 243.072 303.634 + endloop + endfacet + facet normal 0.272338 -0.0595514 -0.960357 + outer loop + vertex -818.048 269.034 301.709 + vertex -813.479 264.805 303.267 + vertex -819.689 258.397 301.904 + endloop + endfacet + facet normal 0.262591 -0.0494064 -0.963642 + outer loop + vertex -819.689 258.397 301.904 + vertex -813.479 264.805 303.267 + vertex -815.179 253.78 303.369 + endloop + endfacet + facet normal 0.287446 -0.0612164 -0.955839 + outer loop + vertex -816.219 279.53 301.587 + vertex -811.594 275.524 303.235 + vertex -818.048 269.034 301.709 + endloop + endfacet + facet normal 0.27887 -0.0519646 -0.958922 + outer loop + vertex -818.048 269.034 301.709 + vertex -811.594 275.524 303.235 + vertex -813.479 264.805 303.267 + endloop + endfacet + facet normal 0.292417 -0.0662108 -0.953996 + outer loop + vertex -814.058 289.602 301.551 + vertex -809.413 285.791 303.239 + vertex -816.219 279.53 301.587 + endloop + endfacet + facet normal 0.28782 -0.0607494 -0.955756 + outer loop + vertex -816.219 279.53 301.587 + vertex -809.413 285.791 303.239 + vertex -811.594 275.524 303.235 + endloop + endfacet + facet normal 0.293132 -0.0746904 -0.95315 + outer loop + vertex -811.599 299.132 301.56 + vertex -806.955 295.598 303.265 + vertex -814.058 289.602 301.551 + endloop + endfacet + facet normal 0.289527 -0.0700045 -0.954606 + outer loop + vertex -814.058 289.602 301.551 + vertex -806.955 295.598 303.265 + vertex -809.413 285.791 303.239 + endloop + endfacet + facet normal 0.293383 -0.0833033 -0.952359 + outer loop + vertex -808.905 308.297 301.588 + vertex -804.273 305.07 303.298 + vertex -811.599 299.132 301.56 + endloop + endfacet + facet normal 0.290139 -0.0789005 -0.953727 + outer loop + vertex -811.599 299.132 301.56 + vertex -804.273 305.07 303.298 + vertex -806.955 295.598 303.265 + endloop + endfacet + facet normal 0.294024 -0.0933017 -0.951233 + outer loop + vertex -806.012 317.269 301.602 + vertex -801.403 314.363 303.312 + vertex -808.905 308.297 301.588 + endloop + endfacet + facet normal 0.290221 -0.0881258 -0.952893 + outer loop + vertex -808.905 308.297 301.588 + vertex -801.403 314.363 303.312 + vertex -804.273 305.07 303.298 + endloop + endfacet + facet normal 0.29725 -0.101626 -0.949376 + outer loop + vertex -802.98 326.11 301.605 + vertex -798.401 323.54 303.314 + vertex -806.012 317.269 301.602 + endloop + endfacet + facet normal 0.292689 -0.0955318 -0.951424 + outer loop + vertex -806.012 317.269 301.602 + vertex -798.401 323.54 303.314 + vertex -801.403 314.363 303.312 + endloop + endfacet + facet normal 0.302691 -0.107802 -0.946973 + outer loop + vertex -799.865 334.778 301.614 + vertex -795.317 332.565 303.32 + vertex -802.98 326.11 301.605 + endloop + endfacet + facet normal 0.297549 -0.10107 -0.949342 + outer loop + vertex -802.98 326.11 301.605 + vertex -795.317 332.565 303.32 + vertex -798.401 323.54 303.314 + endloop + endfacet + facet normal 0.308365 -0.115124 -0.944276 + outer loop + vertex -796.696 343.241 301.617 + vertex -792.173 341.403 303.319 + vertex -799.865 334.778 301.614 + endloop + endfacet + facet normal 0.302679 -0.107827 -0.946974 + outer loop + vertex -799.865 334.778 301.614 + vertex -792.173 341.403 303.319 + vertex -795.317 332.565 303.32 + endloop + endfacet + facet normal 0.317354 -0.121886 -0.940441 + outer loop + vertex -793.499 351.541 301.62 + vertex -788.996 350.089 303.328 + vertex -796.696 343.241 301.617 + endloop + endfacet + facet normal 0.309554 -0.112165 -0.944243 + outer loop + vertex -796.696 343.241 301.617 + vertex -788.996 350.089 303.328 + vertex -792.173 341.403 303.319 + endloop + endfacet + facet normal 0.329734 -0.12918 -0.935194 + outer loop + vertex -790.301 359.786 301.609 + vertex -785.802 358.728 303.342 + vertex -793.499 351.541 301.62 + endloop + endfacet + facet normal 0.319114 -0.116529 -0.940525 + outer loop + vertex -793.499 351.541 301.62 + vertex -785.802 358.728 303.342 + vertex -788.996 350.089 303.328 + endloop + endfacet + facet normal 0.343856 -0.132872 -0.929574 + outer loop + vertex -787.122 368.071 301.601 + vertex -782.634 367.418 303.354 + vertex -790.301 359.786 301.609 + endloop + endfacet + facet normal 0.332122 -0.119704 -0.93561 + outer loop + vertex -790.301 359.786 301.609 + vertex -782.634 367.418 303.354 + vertex -785.802 358.728 303.342 + endloop + endfacet + facet normal 0.350954 -0.114783 -0.929331 + outer loop + vertex -784.088 376.486 301.707 + vertex -779.641 376.241 303.417 + vertex -787.122 368.071 301.601 + endloop + endfacet + facet normal 0.347562 -0.1113 -0.931028 + outer loop + vertex -787.122 368.071 301.601 + vertex -779.641 376.241 303.417 + vertex -782.634 367.418 303.354 + endloop + endfacet + facet normal 0.342668 -0.0360026 -0.938766 + outer loop + vertex -781.619 385.131 302.277 + vertex -777.328 385.236 303.839 + vertex -784.088 376.486 301.707 + endloop + endfacet + facet normal 0.356148 -0.0477702 -0.933208 + outer loop + vertex -784.088 376.486 301.707 + vertex -777.328 385.236 303.839 + vertex -779.641 376.241 303.417 + endloop + endfacet + facet normal -0.471355 -0.383316 -0.794288 + outer loop + vertex -697.133 145.768 297.945 + vertex -695.963 144.945 297.649 + vertex -697.182 144.719 298.481 + endloop + endfacet + facet normal -0.493518 -0.428093 -0.757084 + outer loop + vertex -695.137 144.483 297.371 + vertex -695.068 143.908 297.651 + vertex -695.963 144.945 297.649 + endloop + endfacet + facet normal -0.464085 -0.402762 -0.788928 + outer loop + vertex -695.068 143.908 297.651 + vertex -697.182 144.719 298.481 + vertex -695.963 144.945 297.649 + endloop + endfacet + facet normal -0.462254 -0.38584 -0.798404 + outer loop + vertex -697.133 145.768 297.945 + vertex -697.182 144.719 298.481 + vertex -698.498 146.168 298.542 + endloop + endfacet + facet normal -0.496325 -0.293587 -0.816987 + outer loop + vertex -697.271 150.265 296.048 + vertex -698.318 150.81 296.488 + vertex -699.161 155.716 295.238 + endloop + endfacet + facet normal -0.501951 -0.292842 -0.813811 + outer loop + vertex -699.105 150.336 297.144 + vertex -700.155 155.096 296.079 + vertex -698.318 150.81 296.488 + endloop + endfacet + facet normal -0.504351 -0.2937 -0.812016 + outer loop + vertex -700.155 155.096 296.079 + vertex -699.161 155.716 295.238 + vertex -698.318 150.81 296.488 + endloop + endfacet + facet normal -0.473922 -0.290562 -0.831247 + outer loop + vertex -699.105 150.336 297.144 + vertex -700.374 151.187 297.57 + vertex -700.155 155.096 296.079 + endloop + endfacet + facet normal -0.490382 -0.286518 -0.823063 + outer loop + vertex -702.153 155.39 297.167 + vertex -700.155 155.096 296.079 + vertex -700.374 151.187 297.57 + endloop + endfacet + facet normal -0.489283 -0.324325 -0.809578 + outer loop + vertex -700.374 151.187 297.57 + vertex -699.105 150.336 297.144 + vertex -699.327 148.182 298.142 + endloop + endfacet + facet normal -0.468685 -0.330842 -0.819071 + outer loop + vertex -699.327 148.182 298.142 + vertex -699.105 150.336 297.144 + vertex -698.061 147.758 297.588 + endloop + endfacet + facet normal -0.471564 -0.354802 -0.807306 + outer loop + vertex -699.327 148.182 298.142 + vertex -698.061 147.758 297.588 + vertex -698.498 146.168 298.542 + endloop + endfacet + facet normal -0.460403 -0.360272 -0.811315 + outer loop + vertex -698.498 146.168 298.542 + vertex -698.061 147.758 297.588 + vertex -697.133 145.768 297.945 + endloop + endfacet + facet normal -0.510523 -0.34439 -0.787884 + outer loop + vertex -698.318 150.81 296.488 + vertex -697.271 150.265 296.048 + vertex -696.9 147.25 297.126 + endloop + endfacet + facet normal -0.473485 -0.347506 -0.809352 + outer loop + vertex -696.9 147.25 297.126 + vertex -697.271 150.265 296.048 + vertex -695.803 146.204 296.933 + endloop + endfacet + facet normal -0.477134 -0.333253 -0.813195 + outer loop + vertex -699.105 150.336 297.144 + vertex -698.318 150.81 296.488 + vertex -698.061 147.758 297.588 + endloop + endfacet + facet normal -0.471375 -0.333884 -0.816289 + outer loop + vertex -698.061 147.758 297.588 + vertex -698.318 150.81 296.488 + vertex -696.9 147.25 297.126 + endloop + endfacet + facet normal -0.478336 -0.366267 -0.79815 + outer loop + vertex -698.061 147.758 297.588 + vertex -696.9 147.25 297.126 + vertex -697.133 145.768 297.945 + endloop + endfacet + facet normal -0.465252 -0.371312 -0.803535 + outer loop + vertex -697.133 145.768 297.945 + vertex -696.9 147.25 297.126 + vertex -695.963 144.945 297.649 + endloop + endfacet + facet normal -0.498639 -0.379391 -0.779372 + outer loop + vertex -696.9 147.25 297.126 + vertex -695.803 146.204 296.933 + vertex -695.963 144.945 297.649 + endloop + endfacet + facet normal -0.480328 -0.386303 -0.787436 + outer loop + vertex -695.963 144.945 297.649 + vertex -695.803 146.204 296.933 + vertex -695.137 144.483 297.371 + endloop + endfacet + facet normal -0.560942 -0.181315 -0.807756 + outer loop + vertex -703.057 168.483 294.515 + vertex -701.968 168.582 293.737 + vertex -701.893 161.713 295.227 + endloop + endfacet + facet normal -0.551034 -0.182617 -0.814256 + outer loop + vertex -701.893 161.713 295.227 + vertex -701.968 168.582 293.737 + vertex -700.79 161.854 294.448 + endloop + endfacet + facet normal -0.532295 -0.170301 -0.829252 + outer loop + vertex -704.818 168.662 295.609 + vertex -703.057 168.483 294.515 + vertex -703.752 161.948 296.303 + endloop + endfacet + facet normal -0.509984 -0.176153 -0.841954 + outer loop + vertex -703.752 161.948 296.303 + vertex -703.057 168.483 294.515 + vertex -701.893 161.713 295.227 + endloop + endfacet + facet normal -0.509339 -0.233327 -0.828331 + outer loop + vertex -703.752 161.948 296.303 + vertex -701.893 161.713 295.227 + vertex -702.153 155.39 297.167 + endloop + endfacet + facet normal -0.491301 -0.237068 -0.838107 + outer loop + vertex -702.153 155.39 297.167 + vertex -701.893 161.713 295.227 + vertex -700.155 155.096 296.079 + endloop + endfacet + facet normal -0.53768 -0.245203 -0.806707 + outer loop + vertex -701.893 161.713 295.227 + vertex -700.79 161.854 294.448 + vertex -700.155 155.096 296.079 + endloop + endfacet + facet normal -0.53265 -0.245512 -0.809943 + outer loop + vertex -700.155 155.096 296.079 + vertex -700.79 161.854 294.448 + vertex -699.161 155.716 295.238 + endloop + endfacet + facet normal -0.594331 -0.0640615 -0.801665 + outer loop + vertex -704.578 184.008 293.936 + vertex -703.347 182.612 293.136 + vertex -703.862 175.662 294.073 + endloop + endfacet + facet normal -0.581726 -0.0662113 -0.810685 + outer loop + vertex -703.862 175.662 294.073 + vertex -703.347 182.612 293.136 + vertex -702.754 175.762 293.269 + endloop + endfacet + facet normal -0.527965 -0.0638372 -0.846863 + outer loop + vertex -706.282 182.773 295.092 + vertex -704.578 184.008 293.936 + vertex -705.59 175.821 295.185 + endloop + endfacet + facet normal -0.544063 -0.0603236 -0.836873 + outer loop + vertex -705.59 175.821 295.185 + vertex -704.578 184.008 293.936 + vertex -703.862 175.662 294.073 + endloop + endfacet + facet normal -0.544968 -0.108037 -0.831467 + outer loop + vertex -705.59 175.821 295.185 + vertex -703.862 175.662 294.073 + vertex -704.818 168.662 295.609 + endloop + endfacet + facet normal -0.532419 -0.111429 -0.839115 + outer loop + vertex -704.818 168.662 295.609 + vertex -703.862 175.662 294.073 + vertex -703.057 168.483 294.515 + endloop + endfacet + facet normal -0.576267 -0.114507 -0.8092 + outer loop + vertex -703.862 175.662 294.073 + vertex -702.754 175.762 293.269 + vertex -703.057 168.483 294.515 + endloop + endfacet + facet normal -0.570691 -0.115392 -0.813017 + outer loop + vertex -703.057 168.483 294.515 + vertex -702.754 175.762 293.269 + vertex -701.968 168.582 293.737 + endloop + endfacet + facet normal -0.569684 -0.0310882 -0.821275 + outer loop + vertex -703.347 182.612 293.136 + vertex -704.578 184.008 293.936 + vertex -703.613 193.786 292.897 + endloop + endfacet + facet normal -0.54509 -0.0317004 -0.837778 + outer loop + vertex -706.282 182.773 295.092 + vertex -705.959 194.055 294.455 + vertex -704.578 184.008 293.936 + endloop + endfacet + facet normal -0.555549 -0.0334974 -0.830809 + outer loop + vertex -705.959 194.055 294.455 + vertex -703.613 193.786 292.897 + vertex -704.578 184.008 293.936 + endloop + endfacet + facet normal -0.53401 -0.0114049 -0.845401 + outer loop + vertex -706.445 209.266 294.557 + vertex -704.044 208.582 293.049 + vertex -705.959 194.055 294.455 + endloop + endfacet + facet normal -0.553784 -0.00756152 -0.832626 + outer loop + vertex -705.959 194.055 294.455 + vertex -704.044 208.582 293.049 + vertex -703.613 193.786 292.897 + endloop + endfacet + facet normal -0.530267 0.00359801 -0.847823 + outer loop + vertex -706.34 223.634 294.552 + vertex -703.987 222.779 293.077 + vertex -706.445 209.266 294.557 + endloop + endfacet + facet normal -0.530942 0.00376712 -0.8474 + outer loop + vertex -706.445 209.266 294.557 + vertex -703.987 222.779 293.077 + vertex -704.044 208.582 293.049 + endloop + endfacet + facet normal -0.538545 0.012478 -0.842505 + outer loop + vertex -705.998 237.276 294.535 + vertex -703.701 236.196 293.051 + vertex -706.34 223.634 294.552 + endloop + endfacet + facet normal -0.528665 0.00965324 -0.848776 + outer loop + vertex -706.34 223.634 294.552 + vertex -703.701 236.196 293.051 + vertex -703.987 222.779 293.077 + endloop + endfacet + facet normal -0.550756 0.0144532 -0.834541 + outer loop + vertex -705.636 250.643 294.528 + vertex -703.396 249.362 293.027 + vertex -705.998 237.276 294.535 + endloop + endfacet + facet normal -0.539053 0.0109779 -0.8422 + outer loop + vertex -705.998 237.276 294.535 + vertex -703.396 249.362 293.027 + vertex -703.701 236.196 293.051 + endloop + endfacet + facet normal -0.563996 0.0115124 -0.825697 + outer loop + vertex -705.382 264.088 294.542 + vertex -703.208 262.753 293.038 + vertex -705.636 250.643 294.528 + endloop + endfacet + facet normal -0.553175 0.00844192 -0.833023 + outer loop + vertex -705.636 250.643 294.528 + vertex -703.208 262.753 293.038 + vertex -703.396 249.362 293.027 + endloop + endfacet + facet normal -0.579108 0.00790423 -0.815213 + outer loop + vertex -705.222 277.714 294.56 + vertex -703.139 276.621 293.07 + vertex -705.382 264.088 294.542 + endloop + endfacet + facet normal -0.566865 0.00470493 -0.823797 + outer loop + vertex -705.382 264.088 294.542 + vertex -703.139 276.621 293.07 + vertex -703.208 262.753 293.038 + endloop + endfacet + facet normal -0.597397 0.00593865 -0.801923 + outer loop + vertex -705.096 291.353 294.567 + vertex -703.124 290.644 293.093 + vertex -705.222 277.714 294.56 + endloop + endfacet + facet normal -0.581189 0.0019649 -0.813766 + outer loop + vertex -705.222 277.714 294.56 + vertex -703.124 290.644 293.093 + vertex -703.139 276.621 293.07 + endloop + endfacet + facet normal -0.615205 0.00414946 -0.788356 + outer loop + vertex -704.989 304.881 294.555 + vertex -703.103 304.283 293.08 + vertex -705.096 291.353 294.567 + endloop + endfacet + facet normal -0.59874 0.000163624 -0.800943 + outer loop + vertex -705.096 291.353 294.567 + vertex -703.103 304.283 293.08 + vertex -703.124 290.644 293.093 + endloop + endfacet + facet normal -0.635384 0.00276507 -0.772192 + outer loop + vertex -704.89 318.331 294.522 + vertex -703.09 317.6 293.038 + vertex -704.989 304.881 294.555 + endloop + endfacet + facet normal -0.616397 -0.00188582 -0.787433 + outer loop + vertex -704.989 304.881 294.555 + vertex -703.09 317.6 293.038 + vertex -703.103 304.283 293.08 + endloop + endfacet + facet normal -0.658465 0.00227662 -0.752608 + outer loop + vertex -704.801 331.776 294.484 + vertex -703.101 330.936 292.994 + vertex -704.89 318.331 294.522 + endloop + endfacet + facet normal -0.636785 -0.00303432 -0.771035 + outer loop + vertex -704.89 318.331 294.522 + vertex -703.101 330.936 292.994 + vertex -703.09 317.6 293.038 + endloop + endfacet + facet normal -0.678083 0.00230694 -0.734982 + outer loop + vertex -704.783 345.232 294.51 + vertex -703.153 344.369 293.003 + vertex -704.801 331.776 294.484 + endloop + endfacet + facet normal -0.659674 -0.00205047 -0.751549 + outer loop + vertex -704.801 331.776 294.484 + vertex -703.153 344.369 293.003 + vertex -703.101 330.936 292.994 + endloop + endfacet + facet normal -0.696465 0.0034541 -0.717583 + outer loop + vertex -704.796 358.789 294.588 + vertex -703.275 358.042 293.109 + vertex -704.783 345.232 294.51 + endloop + endfacet + facet normal -0.678869 -0.000440171 -0.734259 + outer loop + vertex -704.783 345.232 294.51 + vertex -703.275 358.042 293.109 + vertex -703.153 344.369 293.003 + endloop + endfacet + facet normal -0.723577 -0.00539506 -0.690222 + outer loop + vertex -704.955 372.527 294.648 + vertex -703.55 372.197 293.177 + vertex -704.796 358.789 294.588 + endloop + endfacet + facet normal -0.699852 -0.0101267 -0.714216 + outer loop + vertex -704.796 358.789 294.588 + vertex -703.55 372.197 293.177 + vertex -703.275 358.042 293.109 + endloop + endfacet + facet normal -0.818354 -0.0214371 -0.574314 + outer loop + vertex -705.335 386.645 294.662 + vertex -703.778 386.654 292.443 + vertex -704.955 372.527 294.648 + endloop + endfacet + facet normal -0.727379 -0.0462422 -0.684676 + outer loop + vertex -704.955 372.527 294.648 + vertex -703.778 386.654 292.443 + vertex -703.55 372.197 293.177 + endloop + endfacet + facet normal -0.479367 -0.417575 -0.771906 + outer loop + vertex -694.929 144.979 296.991 + vertex -694.531 144.833 296.823 + vertex -694.181 143.754 297.189 + endloop + endfacet + facet normal -0.432713 -0.400396 -0.80774 + outer loop + vertex -694.539 145.106 296.692 + vertex -693.983 143.897 296.993 + vertex -694.531 144.833 296.823 + endloop + endfacet + facet normal -0.469443 -0.416597 -0.778505 + outer loop + vertex -693.983 143.897 296.993 + vertex -694.181 143.754 297.189 + vertex -694.531 144.833 296.823 + endloop + endfacet + facet normal -0.412948 -0.438456 -0.798267 + outer loop + vertex -695.137 144.483 297.371 + vertex -694.929 144.979 296.991 + vertex -695.068 143.908 297.651 + endloop + endfacet + facet normal -0.475833 -0.415916 -0.774982 + outer loop + vertex -695.068 143.908 297.651 + vertex -694.929 144.979 296.991 + vertex -694.181 143.754 297.189 + endloop + endfacet + facet normal -0.276306 -0.253229 -0.927109 + outer loop + vertex -696.482 149.782 295.721 + vertex -696.901 150.707 295.594 + vertex -698.054 154.587 294.878 + endloop + endfacet + facet normal -0.409941 -0.26989 -0.871268 + outer loop + vertex -697.088 150.776 295.661 + vertex -698.39 155.007 294.962 + vertex -696.901 150.707 295.594 + endloop + endfacet + facet normal -0.579063 -0.311172 -0.753563 + outer loop + vertex -698.39 155.007 294.962 + vertex -698.054 154.587 294.878 + vertex -696.901 150.707 295.594 + endloop + endfacet + facet normal -0.558457 -0.308176 -0.770165 + outer loop + vertex -699.161 155.716 295.238 + vertex -698.39 155.007 294.962 + vertex -697.271 150.265 296.048 + endloop + endfacet + facet normal -0.632939 -0.311689 -0.708688 + outer loop + vertex -697.271 150.265 296.048 + vertex -698.39 155.007 294.962 + vertex -697.088 150.776 295.661 + endloop + endfacet + facet normal -0.566212 -0.360321 -0.741332 + outer loop + vertex -697.088 150.776 295.661 + vertex -696.093 147.996 296.251 + vertex -697.271 150.265 296.048 + endloop + endfacet + facet normal -0.586672 -0.369102 -0.720819 + outer loop + vertex -697.271 150.265 296.048 + vertex -696.093 147.996 296.251 + vertex -695.803 146.204 296.933 + endloop + endfacet + facet normal -0.493539 -0.388984 -0.777888 + outer loop + vertex -695.137 144.483 297.371 + vertex -695.803 146.204 296.933 + vertex -694.929 144.979 296.991 + endloop + endfacet + facet normal -0.478327 -0.378797 -0.792285 + outer loop + vertex -694.929 144.979 296.991 + vertex -695.803 146.204 296.933 + vertex -696.093 147.996 296.251 + endloop + endfacet + facet normal -0.602584 -0.370869 -0.706646 + outer loop + vertex -696.901 150.707 295.594 + vertex -696.482 149.782 295.721 + vertex -695.56 147.17 296.306 + endloop + endfacet + facet normal -0.42145 -0.337182 -0.841836 + outer loop + vertex -695.56 147.17 296.306 + vertex -696.482 149.782 295.721 + vertex -695.399 147.048 296.274 + endloop + endfacet + facet normal -0.422585 -0.330672 -0.843847 + outer loop + vertex -697.088 150.776 295.661 + vertex -696.901 150.707 295.594 + vertex -696.093 147.996 296.251 + endloop + endfacet + facet normal -0.426981 -0.331378 -0.841353 + outer loop + vertex -696.093 147.996 296.251 + vertex -696.901 150.707 295.594 + vertex -695.56 147.17 296.306 + endloop + endfacet + facet normal -0.522882 -0.387844 -0.75906 + outer loop + vertex -696.093 147.996 296.251 + vertex -695.56 147.17 296.306 + vertex -694.929 144.979 296.991 + endloop + endfacet + facet normal -0.475339 -0.384279 -0.791444 + outer loop + vertex -694.929 144.979 296.991 + vertex -695.56 147.17 296.306 + vertex -694.531 144.833 296.823 + endloop + endfacet + facet normal -0.444967 -0.375667 -0.812945 + outer loop + vertex -695.56 147.17 296.306 + vertex -695.399 147.048 296.274 + vertex -694.531 144.833 296.823 + endloop + endfacet + facet normal -0.497489 -0.387172 -0.776275 + outer loop + vertex -694.531 144.833 296.823 + vertex -695.399 147.048 296.274 + vertex -694.539 145.106 296.692 + endloop + endfacet + facet normal -0.744366 -0.203973 -0.635857 + outer loop + vertex -701.424 168.56 293.317 + vertex -701.161 167.994 293.191 + vertex -700.201 161.833 294.043 + endloop + endfacet + facet normal -0.553758 -0.198187 -0.808748 + outer loop + vertex -700.201 161.833 294.043 + vertex -701.161 167.994 293.191 + vertex -699.859 161.321 293.934 + endloop + endfacet + facet normal -0.604748 -0.18776 -0.773968 + outer loop + vertex -701.968 168.582 293.737 + vertex -701.424 168.56 293.317 + vertex -700.79 161.854 294.448 + endloop + endfacet + facet normal -0.561335 -0.189006 -0.805717 + outer loop + vertex -700.79 161.854 294.448 + vertex -701.424 168.56 293.317 + vertex -700.201 161.833 294.043 + endloop + endfacet + facet normal -0.555137 -0.249364 -0.793499 + outer loop + vertex -700.79 161.854 294.448 + vertex -700.201 161.833 294.043 + vertex -699.161 155.716 295.238 + endloop + endfacet + facet normal -0.519998 -0.24805 -0.817357 + outer loop + vertex -699.161 155.716 295.238 + vertex -700.201 161.833 294.043 + vertex -698.39 155.007 294.962 + endloop + endfacet + facet normal -0.629391 -0.265353 -0.73038 + outer loop + vertex -700.201 161.833 294.043 + vertex -699.859 161.321 293.934 + vertex -698.39 155.007 294.962 + endloop + endfacet + facet normal -0.52301 -0.254142 -0.813556 + outer loop + vertex -698.39 155.007 294.962 + vertex -699.859 161.321 293.934 + vertex -698.054 154.587 294.878 + endloop + endfacet + facet normal -0.815335 -0.0706911 -0.574658 + outer loop + vertex -702.781 184.244 292.597 + vertex -702.489 182.868 292.353 + vertex -702.206 175.831 292.818 + endloop + endfacet + facet normal -0.745177 -0.0736893 -0.662783 + outer loop + vertex -702.206 175.831 292.818 + vertex -702.489 182.868 292.353 + vertex -701.98 174.846 292.672 + endloop + endfacet + facet normal -0.580278 -0.0661063 -0.811731 + outer loop + vertex -703.347 182.612 293.136 + vertex -702.781 184.244 292.597 + vertex -702.754 175.762 293.269 + endloop + endfacet + facet normal -0.630171 -0.0632615 -0.773875 + outer loop + vertex -702.754 175.762 293.269 + vertex -702.781 184.244 292.597 + vertex -702.206 175.831 292.818 + endloop + endfacet + facet normal -0.622808 -0.11852 -0.773346 + outer loop + vertex -702.754 175.762 293.269 + vertex -702.206 175.831 292.818 + vertex -701.968 168.582 293.737 + endloop + endfacet + facet normal -0.609529 -0.119398 -0.783721 + outer loop + vertex -701.968 168.582 293.737 + vertex -702.206 175.831 292.818 + vertex -701.424 168.56 293.317 + endloop + endfacet + facet normal -0.863031 -0.126404 -0.48908 + outer loop + vertex -702.206 175.831 292.818 + vertex -701.98 174.846 292.672 + vertex -701.424 168.56 293.317 + endloop + endfacet + facet normal -0.648833 -0.134149 -0.749013 + outer loop + vertex -701.424 168.56 293.317 + vertex -701.98 174.846 292.672 + vertex -701.161 167.994 293.191 + endloop + endfacet + facet normal -0.725181 -0.0314989 -0.687838 + outer loop + vertex -702.489 182.868 292.353 + vertex -702.781 184.244 292.597 + vertex -702.772 194.159 292.134 + endloop + endfacet + facet normal -0.638822 -0.0316061 -0.768705 + outer loop + vertex -703.347 182.612 293.136 + vertex -703.613 193.786 292.897 + vertex -702.781 184.244 292.597 + endloop + endfacet + facet normal -0.662939 -0.0343623 -0.747884 + outer loop + vertex -703.613 193.786 292.897 + vertex -702.772 194.159 292.134 + vertex -702.781 184.244 292.597 + endloop + endfacet + facet normal -0.621211 -0.0100307 -0.783579 + outer loop + vertex -704.044 208.582 293.049 + vertex -702.788 207.427 292.068 + vertex -703.613 193.786 292.897 + endloop + endfacet + facet normal -0.670637 -0.00450156 -0.741772 + outer loop + vertex -703.613 193.786 292.897 + vertex -702.788 207.427 292.068 + vertex -702.772 194.159 292.134 + endloop + endfacet + facet normal -0.597229 0.00394375 -0.802061 + outer loop + vertex -703.987 222.779 293.077 + vertex -702.6 221.72 292.038 + vertex -704.044 208.582 293.049 + endloop + endfacet + facet normal -0.61185 0.00640603 -0.790948 + outer loop + vertex -704.044 208.582 293.049 + vertex -702.6 221.72 292.038 + vertex -702.788 207.427 292.068 + endloop + endfacet + facet normal -0.58932 0.011027 -0.807824 + outer loop + vertex -703.701 236.196 293.051 + vertex -702.454 234.305 292.115 + vertex -703.987 222.779 293.077 + endloop + endfacet + facet normal -0.593329 0.0118064 -0.804874 + outer loop + vertex -703.987 222.779 293.077 + vertex -702.454 234.305 292.115 + vertex -702.6 221.72 292.038 + endloop + endfacet + facet normal -0.604524 0.012573 -0.796487 + outer loop + vertex -703.396 249.362 293.027 + vertex -702.108 246.878 292.011 + vertex -703.701 236.196 293.051 + endloop + endfacet + facet normal -0.590799 0.00952636 -0.806762 + outer loop + vertex -703.701 236.196 293.051 + vertex -702.108 246.878 292.011 + vertex -702.454 234.305 292.115 + endloop + endfacet + facet normal -0.617805 0.00931134 -0.786276 + outer loop + vertex -703.208 262.753 293.038 + vertex -702.04 259.466 292.082 + vertex -703.396 249.362 293.027 + endloop + endfacet + facet normal -0.610339 0.00776411 -0.792102 + outer loop + vertex -703.396 249.362 293.027 + vertex -702.04 259.466 292.082 + vertex -702.108 246.878 292.011 + endloop + endfacet + facet normal -0.642265 0.00495171 -0.766467 + outer loop + vertex -703.139 276.621 293.07 + vertex -701.927 273.304 292.033 + vertex -703.208 262.753 293.038 + endloop + endfacet + facet normal -0.629569 0.00241308 -0.77694 + outer loop + vertex -703.208 262.753 293.038 + vertex -701.927 273.304 292.033 + vertex -702.04 259.466 292.082 + endloop + endfacet + facet normal -0.662176 0.00194422 -0.749346 + outer loop + vertex -703.124 290.644 293.093 + vertex -701.988 288.208 292.083 + vertex -703.139 276.621 293.07 + endloop + endfacet + facet normal -0.650313 -0.000112385 -0.759666 + outer loop + vertex -703.139 276.621 293.07 + vertex -701.988 288.208 292.083 + vertex -701.927 273.304 292.033 + endloop + endfacet + facet normal -0.68586 0.000368305 -0.727733 + outer loop + vertex -703.103 304.283 293.08 + vertex -702.001 302.812 292.041 + vertex -703.124 290.644 293.093 + endloop + endfacet + facet normal -0.667778 -0.00273773 -0.744355 + outer loop + vertex -703.124 290.644 293.093 + vertex -702.001 302.812 292.041 + vertex -701.988 288.208 292.083 + endloop + endfacet + facet normal -0.696786 -0.00159067 -0.717277 + outer loop + vertex -703.09 317.6 293.038 + vertex -702.082 315.813 292.063 + vertex -703.103 304.283 293.08 + endloop + endfacet + facet normal -0.688279 -0.00306439 -0.725439 + outer loop + vertex -703.103 304.283 293.08 + vertex -702.082 315.813 292.063 + vertex -702.001 302.812 292.041 + endloop + endfacet + facet normal -0.717141 -0.0028528 -0.696922 + outer loop + vertex -703.101 330.936 292.994 + vertex -702.081 329.311 291.952 + vertex -703.09 317.6 293.038 + endloop + endfacet + facet normal -0.700623 -0.00581428 -0.713508 + outer loop + vertex -703.09 317.6 293.038 + vertex -702.081 329.311 291.952 + vertex -702.082 315.813 292.063 + endloop + endfacet + facet normal -0.735894 -0.00239475 -0.677092 + outer loop + vertex -703.153 344.369 293.003 + vertex -702.236 342.488 292.014 + vertex -703.101 330.936 292.994 + endloop + endfacet + facet normal -0.718946 -0.00518792 -0.695046 + outer loop + vertex -703.101 330.936 292.994 + vertex -702.236 342.488 292.014 + vertex -702.081 329.311 291.952 + endloop + endfacet + facet normal -0.756639 -0.00175758 -0.653831 + outer loop + vertex -703.275 358.042 293.109 + vertex -702.373 355.853 292.07 + vertex -703.153 344.369 293.003 + endloop + endfacet + facet normal -0.738074 -0.00471433 -0.674704 + outer loop + vertex -703.153 344.369 293.003 + vertex -702.373 355.853 292.07 + vertex -702.236 342.488 292.014 + endloop + endfacet + facet normal -0.738185 -0.0110613 -0.674507 + outer loop + vertex -703.55 372.197 293.177 + vertex -702.613 370.124 292.186 + vertex -703.275 358.042 293.109 + endloop + endfacet + facet normal -0.762664 -0.00759887 -0.64675 + outer loop + vertex -703.275 358.042 293.109 + vertex -702.613 370.124 292.186 + vertex -702.373 355.853 292.07 + endloop + endfacet + facet normal -0.844744 -0.040428 -0.533641 + outer loop + vertex -703.778 386.654 292.443 + vertex -703.672 386.655 292.275 + vertex -703.55 372.197 293.177 + endloop + endfacet + facet normal -0.772303 -0.046053 -0.633582 + outer loop + vertex -703.55 372.197 293.177 + vertex -703.672 386.655 292.275 + vertex -702.613 370.124 292.186 + endloop + endfacet + facet normal -0.485319 -0.415076 -0.769531 + outer loop + vertex -694.539 145.106 296.692 + vertex -694.352 144.831 296.722 + vertex -693.983 143.897 296.993 + endloop + endfacet + facet normal -0.446539 -0.412043 -0.794244 + outer loop + vertex -694.267 144.751 296.716 + vertex -693.89 143.909 296.941 + vertex -694.352 144.831 296.722 + endloop + endfacet + facet normal -0.410441 -0.399953 -0.819497 + outer loop + vertex -693.89 143.909 296.941 + vertex -693.983 143.897 296.993 + vertex -694.352 144.831 296.722 + endloop + endfacet + facet normal -0.642634 -0.344031 -0.684591 + outer loop + vertex -696.355 149.694 295.649 + vertex -696.62 150.309 295.589 + vertex -697.89 154.148 294.853 + endloop + endfacet + facet normal -0.712542 -0.340899 -0.613247 + outer loop + vertex -696.482 149.782 295.721 + vertex -698.054 154.587 294.878 + vertex -696.62 150.309 295.589 + endloop + endfacet + facet normal -0.927914 -0.337459 -0.158423 + outer loop + vertex -698.054 154.587 294.878 + vertex -697.89 154.148 294.853 + vertex -696.62 150.309 295.589 + endloop + endfacet + facet normal -0.856519 -0.401309 -0.32454 + outer loop + vertex -696.62 150.309 295.589 + vertex -696.355 149.694 295.649 + vertex -695.323 147.012 296.243 + endloop + endfacet + facet normal -0.478257 -0.361145 -0.800528 + outer loop + vertex -695.323 147.012 296.243 + vertex -696.355 149.694 295.649 + vertex -695.072 146.539 296.306 + endloop + endfacet + facet normal -0.325109 -0.309504 -0.893595 + outer loop + vertex -696.482 149.782 295.721 + vertex -696.62 150.309 295.589 + vertex -695.399 147.048 296.274 + endloop + endfacet + facet normal -0.497272 -0.352751 -0.792646 + outer loop + vertex -695.399 147.048 296.274 + vertex -696.62 150.309 295.589 + vertex -695.323 147.012 296.243 + endloop + endfacet + facet normal -0.505247 -0.389297 -0.770177 + outer loop + vertex -695.399 147.048 296.274 + vertex -695.323 147.012 296.243 + vertex -694.539 145.106 296.692 + endloop + endfacet + facet normal -0.393616 -0.361105 -0.845381 + outer loop + vertex -694.539 145.106 296.692 + vertex -695.323 147.012 296.243 + vertex -694.352 144.831 296.722 + endloop + endfacet + facet normal -0.639445 -0.425447 -0.640395 + outer loop + vertex -695.323 147.012 296.243 + vertex -695.072 146.539 296.306 + vertex -694.352 144.831 296.722 + endloop + endfacet + facet normal -0.416294 -0.37705 -0.827365 + outer loop + vertex -694.352 144.831 296.722 + vertex -695.072 146.539 296.306 + vertex -694.267 144.751 296.716 + endloop + endfacet + facet normal -0.875883 -0.409383 -0.25541 + outer loop + vertex -696.355 149.694 295.649 + vertex -695.783 148.32 295.891 + vertex -695.072 146.539 296.306 + endloop + endfacet + facet normal -0.143892 -0.278697 -0.949538 + outer loop + vertex -695.072 146.539 296.306 + vertex -695.783 148.32 295.891 + vertex -694.663 145.715 296.486 + endloop + endfacet + facet normal -0.220954 -0.311362 -0.924247 + outer loop + vertex -695.072 146.539 296.306 + vertex -694.663 145.715 296.486 + vertex -694.267 144.751 296.716 + endloop + endfacet + facet normal 0.183784 -0.156033 -0.970503 + outer loop + vertex -694.267 144.751 296.716 + vertex -694.663 145.715 296.486 + vertex -693.994 144.208 296.855 + endloop + endfacet + facet normal -0.978084 -0.197989 -0.0644392 + outer loop + vertex -701.161 167.994 293.191 + vertex -700.928 166.825 293.245 + vertex -699.859 161.321 293.934 + endloop + endfacet + facet normal -0.83911 -0.224977 -0.495257 + outer loop + vertex -699.859 161.321 293.934 + vertex -700.928 166.825 293.245 + vertex -699.617 160.402 293.942 + endloop + endfacet + facet normal -0.966523 -0.254389 0.0334488 + outer loop + vertex -699.859 161.321 293.934 + vertex -699.617 160.402 293.942 + vertex -698.054 154.587 294.878 + endloop + endfacet + facet normal -0.860597 -0.297808 -0.413139 + outer loop + vertex -698.054 154.587 294.878 + vertex -699.617 160.402 293.942 + vertex -697.89 154.148 294.853 + endloop + endfacet + facet normal -0.773409 -0.0238821 0.633457 + outer loop + vertex -702.489 182.868 292.353 + vertex -702.347 179.562 292.401 + vertex -701.98 174.846 292.672 + endloop + endfacet + facet normal -0.758936 -0.0961877 -0.644022 + outer loop + vertex -701.98 174.846 292.672 + vertex -702.347 179.562 292.401 + vertex -701.807 173.069 292.734 + endloop + endfacet + facet normal -0.875032 -0.068296 0.479224 + outer loop + vertex -701.98 174.846 292.672 + vertex -701.807 173.069 292.734 + vertex -701.161 167.994 293.191 + endloop + endfacet + facet normal -0.510643 -0.141228 -0.848115 + outer loop + vertex -701.161 167.994 293.191 + vertex -701.807 173.069 292.734 + vertex -700.928 166.825 293.245 + endloop + endfacet + facet normal 0.777295 -0.195922 -0.597852 + outer loop + vertex -795.673 379.842 291.76 + vertex -794.163 384.78 292.105 + vertex -792.003 384.848 294.891 + endloop + endfacet + facet normal 0.754988 -0.308449 -0.578665 + outer loop + vertex -798.386 373.16 291.782 + vertex -795.673 379.842 291.76 + vertex -795.643 376.949 293.341 + endloop + endfacet + facet normal 0.731451 -0.328249 -0.59769 + outer loop + vertex -800.73 367.791 291.863 + vertex -798.386 373.16 291.782 + vertex -798.135 371.09 293.226 + endloop + endfacet + facet normal 0.725615 -0.325267 -0.60637 + outer loop + vertex -802.995 363.747 291.321 + vertex -800.73 367.791 291.863 + vertex -801.719 363.757 292.843 + endloop + endfacet + facet normal 0.722379 -0.337431 -0.60358 + outer loop + vertex -805.355 358.293 291.546 + vertex -802.995 363.747 291.321 + vertex -801.719 363.757 292.843 + endloop + endfacet + facet normal 0.699432 -0.33121 -0.63332 + outer loop + vertex -807.73 352.601 291.899 + vertex -805.355 358.293 291.546 + vertex -804.864 356.474 293.039 + endloop + endfacet + facet normal 0.688744 -0.31006 -0.655358 + outer loop + vertex -810.396 347.183 291.661 + vertex -807.73 352.601 291.899 + vertex -807.905 349.695 293.091 + endloop + endfacet + facet normal 0.684036 -0.301837 -0.664071 + outer loop + vertex -813.009 341.674 291.474 + vertex -810.396 347.183 291.661 + vertex -811.387 342.107 292.947 + endloop + endfacet + facet normal 0.684263 -0.298765 -0.665225 + outer loop + vertex -814.509 337.148 291.963 + vertex -813.009 341.674 291.474 + vertex -811.387 342.107 292.947 + endloop + endfacet + facet normal 0.673834 -0.268185 -0.688495 + outer loop + vertex -816.923 331.705 291.721 + vertex -814.509 337.148 291.963 + vertex -814.35 334.532 293.137 + endloop + endfacet + facet normal 0.673913 -0.262302 -0.69068 + outer loop + vertex -819.339 326.097 291.493 + vertex -816.923 331.705 291.721 + vertex -817.651 326.575 292.959 + endloop + endfacet + facet normal 0.673982 -0.259389 -0.691712 + outer loop + vertex -820.66 321.466 291.943 + vertex -819.339 326.097 291.493 + vertex -817.651 326.575 292.959 + endloop + endfacet + facet normal 0.668683 -0.224629 -0.708806 + outer loop + vertex -822.804 315.965 291.664 + vertex -820.66 321.466 291.943 + vertex -820.341 318.751 293.104 + endloop + endfacet + facet normal 0.678114 -0.219544 -0.7014 + outer loop + vertex -824.91 310.212 291.428 + vertex -822.804 315.965 291.664 + vertex -823.269 310.564 292.905 + endloop + endfacet + facet normal 0.678336 -0.212921 -0.703225 + outer loop + vertex -825.932 305.409 291.897 + vertex -824.91 310.212 291.428 + vertex -823.269 310.564 292.905 + endloop + endfacet + facet normal 0.679344 -0.179712 -0.711474 + outer loop + vertex -827.604 299.74 291.732 + vertex -825.932 305.409 291.897 + vertex -825.468 302.459 293.084 + endloop + endfacet + facet normal 0.670755 -0.172208 -0.72141 + outer loop + vertex -828.818 295.036 291.726 + vertex -827.604 299.74 291.732 + vertex -827.751 294.108 292.939 + endloop + endfacet + facet normal 0.684084 -0.147596 -0.714314 + outer loop + vertex -829.822 290.566 291.689 + vertex -828.818 295.036 291.726 + vertex -827.751 294.108 292.939 + endloop + endfacet + facet normal 0.706468 -0.145384 -0.692652 + outer loop + vertex -831.133 284.844 291.552 + vertex -829.822 290.566 291.689 + vertex -829.865 284.119 292.997 + endloop + endfacet + facet normal 0.705908 -0.146875 -0.692908 + outer loop + vertex -831.839 279.306 292.007 + vertex -831.133 284.844 291.552 + vertex -829.865 284.119 292.997 + endloop + endfacet + facet normal 0.739968 -0.137305 -0.658479 + outer loop + vertex -832.921 275.126 291.662 + vertex -831.839 279.306 292.007 + vertex -832.272 272.125 293.017 + endloop + endfacet + facet normal 0.727507 -0.145434 -0.67051 + outer loop + vertex -833.471 271.312 291.893 + vertex -832.921 275.126 291.662 + vertex -832.272 272.125 293.017 + endloop + endfacet + facet normal 0.730228 -0.157243 -0.664862 + outer loop + vertex -834.332 266.499 292.085 + vertex -833.471 271.312 291.893 + vertex -832.272 272.125 293.017 + endloop + endfacet + facet normal 0.839343 -0.181999 -0.512231 + outer loop + vertex -835.199 262.267 292.169 + vertex -834.332 266.499 292.085 + vertex -835.146 261.909 292.382 + endloop + endfacet + facet normal 0.792172 -0.222315 -0.568366 + outer loop + vertex -835.812 259.509 292.393 + vertex -835.199 262.267 292.169 + vertex -835.146 261.909 292.382 + endloop + endfacet + facet normal 0.786049 -0.292292 -0.544694 + outer loop + vertex -836.976 255.768 292.721 + vertex -835.812 259.509 292.393 + vertex -835.969 258.505 292.706 + endloop + endfacet + facet normal 0.612611 -0.30856 -0.727666 + outer loop + vertex -838.561 251.457 293.214 + vertex -836.976 255.768 292.721 + vertex -837.578 253.45 293.197 + endloop + endfacet + facet normal 0.415353 -0.315657 -0.853137 + outer loop + vertex -839.744 248.776 293.63 + vertex -838.561 251.457 293.214 + vertex -839.312 249.542 293.557 + endloop + endfacet + facet normal -0.0134042 -0.205824 -0.978497 + outer loop + vertex -840.831 247.07 294.004 + vertex -839.744 248.776 293.63 + vertex -840.22 247.894 293.822 + endloop + endfacet + facet normal 0.0500885 -0.313857 -0.948148 + outer loop + vertex -842.086 245.541 294.444 + vertex -840.831 247.07 294.004 + vertex -841.288 246.37 294.211 + endloop + endfacet + facet normal 0.0373846 -0.393168 -0.918706 + outer loop + vertex -843.481 244.267 294.932 + vertex -842.086 245.541 294.444 + vertex -842.578 244.948 294.678 + endloop + endfacet + facet normal 0.0366057 -0.531327 -0.846376 + outer loop + vertex -844.961 243.343 295.448 + vertex -843.481 244.267 294.932 + vertex -844.002 243.841 295.177 + endloop + endfacet + facet normal -0.053647 -0.581619 -0.811691 + outer loop + vertex -846.477 242.734 295.985 + vertex -844.961 243.343 295.448 + vertex -845.483 243.059 295.686 + endloop + endfacet + facet normal -0.224242 -0.455064 -0.861761 + outer loop + vertex -848.286 242.207 296.733 + vertex -846.477 242.734 295.985 + vertex -846.811 242.51 296.19 + endloop + endfacet + facet normal -0.18472 -0.570422 -0.80031 + outer loop + vertex -845.914 239.558 298.075 + vertex -848.286 242.207 296.733 + vertex -846.609 240.976 297.224 + endloop + endfacet + facet normal -0.0883614 -0.507831 -0.856913 + outer loop + vertex -843.232 236.928 299.357 + vertex -845.914 239.558 298.075 + vertex -844.798 239.017 298.28 + endloop + endfacet + facet normal 0.0358137 -0.361931 -0.931517 + outer loop + vertex -839.593 233.414 300.862 + vertex -843.232 236.928 299.357 + vertex -840.336 235.842 299.89 + endloop + endfacet + facet normal 0.0753463 -0.278021 -0.957615 + outer loop + vertex -835.279 229.581 302.314 + vertex -839.593 233.414 300.862 + vertex -836.859 232.569 301.322 + endloop + endfacet + facet normal 0.0863748 -0.214657 -0.972863 + outer loop + vertex -831.731 225.614 303.504 + vertex -835.279 229.581 302.314 + vertex -832.079 227.514 303.054 + endloop + endfacet + facet normal 0.0556828 -0.201049 -0.977997 + outer loop + vertex -828.283 222.218 304.399 + vertex -831.731 225.614 303.504 + vertex -829.091 224.269 303.931 + endloop + endfacet + facet normal 0.0293931 -0.172754 -0.984526 + outer loop + vertex -824.514 218.826 305.107 + vertex -828.283 222.218 304.399 + vertex -825.971 221.17 304.652 + endloop + endfacet + facet normal 0.0271259 -0.138367 -0.990009 + outer loop + vertex -820.245 214.913 305.77 + vertex -824.514 218.826 305.107 + vertex -820.546 218.151 305.31 + endloop + endfacet + facet normal -0.00476876 -0.141323 -0.989952 + outer loop + vertex -816.891 212.536 306.094 + vertex -820.245 214.913 305.77 + vertex -820.546 218.151 305.31 + endloop + endfacet + facet normal 0.0171325 -0.0923692 -0.995577 + outer loop + vertex -812.043 208.211 306.578 + vertex -816.891 212.536 306.094 + vertex -813.698 212.836 306.121 + endloop + endfacet + facet normal 0.00621695 -0.0735784 -0.99727 + outer loop + vertex -806.511 203.529 306.958 + vertex -812.043 208.211 306.578 + vertex -807.942 207.852 306.63 + endloop + endfacet + facet normal -0.112242 -0.0984205 -0.988795 + outer loop + vertex -738.709 163.01 306.258 + vertex -744.4 165.535 306.652 + vertex -740.856 166.721 306.132 + endloop + endfacet + facet normal -0.136896 -0.111686 -0.984269 + outer loop + vertex -733.169 159.983 305.831 + vertex -738.709 163.01 306.258 + vertex -734.711 163.095 305.692 + endloop + endfacet + facet normal -0.186683 -0.124028 -0.97456 + outer loop + vertex -721.425 154.915 304.384 + vertex -726.637 156.878 305.133 + vertex -724.544 157.56 304.645 + endloop + endfacet + facet normal -0.266315 -0.176729 -0.947546 + outer loop + vertex -710.716 150.329 302.364 + vertex -716.102 152.467 303.479 + vertex -713.704 152.987 302.708 + endloop + endfacet + facet normal -0.444327 -0.414143 -0.794392 + outer loop + vertex -696.135 143.944 298.3 + vertex -698.453 144.787 299.156 + vertex -697.182 144.719 298.481 + endloop + endfacet + facet normal -0.431887 -0.594403 -0.67835 + outer loop + vertex -693.615 143.55 297.04 + vertex -696.135 143.944 298.3 + vertex -695.068 143.908 297.651 + endloop + endfacet + facet normal 0.254932 -0.121989 -0.959233 + outer loop + vertex -695.568 147.948 295.961 + vertex -693.615 143.55 297.04 + vertex -694.663 145.715 296.486 + endloop + endfacet + facet normal -0.0636225 -0.22084 -0.973233 + outer loop + vertex -697.155 152.01 295.143 + vertex -695.568 147.948 295.961 + vertex -695.783 148.32 295.891 + endloop + endfacet + facet normal -0.7454 -0.334793 -0.576448 + outer loop + vertex -698.851 157.302 294.264 + vertex -697.155 152.01 295.143 + vertex -697.89 154.148 294.853 + endloop + endfacet + facet normal -0.914155 -0.188547 0.358847 + outer loop + vertex -700.012 161.78 293.659 + vertex -698.851 157.302 294.264 + vertex -699.617 160.402 293.942 + endloop + endfacet + facet normal -0.752028 -0.0814766 0.654076 + outer loop + vertex -700.708 165.441 293.316 + vertex -700.012 161.78 293.659 + vertex -699.617 160.402 293.942 + endloop + endfacet + facet normal -0.815282 -0.158453 -0.556964 + outer loop + vertex -701.485 171.039 292.861 + vertex -700.708 165.441 293.316 + vertex -700.928 166.825 293.245 + endloop + endfacet + facet normal -0.0111299 -0.06387 -0.997896 + outer loop + vertex -702.079 176.432 292.522 + vertex -701.485 171.039 292.861 + vertex -701.807 173.069 292.734 + endloop + endfacet + facet normal -0.156963 -0.0515378 -0.986259 + outer loop + vertex -702.359 181.29 292.313 + vertex -702.079 176.432 292.522 + vertex -702.347 179.562 292.401 + endloop + endfacet + facet normal -0.543874 -0.0465969 -0.837872 + outer loop + vertex -702.643 187.289 292.164 + vertex -702.359 181.29 292.313 + vertex -702.347 179.562 292.401 + endloop + endfacet + facet normal -0.99766 -0.0189233 -0.0657039 + outer loop + vertex -702.744 193.169 292.004 + vertex -702.643 187.289 292.164 + vertex -702.772 194.159 292.134 + endloop + endfacet + facet normal -0.898922 0.0325211 -0.4369 + outer loop + vertex -702.393 197.865 291.63 + vertex -702.744 193.169 292.004 + vertex -702.772 194.159 292.134 + endloop + endfacet + facet normal -0.804989 0.00166452 -0.593287 + outer loop + vertex -702.351 203.88 291.59 + vertex -702.393 197.865 291.63 + vertex -702.772 194.159 292.134 + endloop + endfacet + facet normal -0.717462 0.00544642 -0.696576 + outer loop + vertex -702.147 209.566 291.425 + vertex -702.351 203.88 291.59 + vertex -702.788 207.427 292.068 + endloop + endfacet + facet normal -0.728552 0.0122793 -0.68488 + outer loop + vertex -701.904 216.953 291.298 + vertex -702.147 209.566 291.425 + vertex -702.788 207.427 292.068 + endloop + endfacet + facet normal -0.686957 0.0124857 -0.72659 + outer loop + vertex -701.743 225.146 291.287 + vertex -701.904 216.953 291.298 + vertex -702.6 221.72 292.038 + endloop + endfacet + facet normal -0.685779 0.0119452 -0.727712 + outer loop + vertex -701.585 233.047 291.268 + vertex -701.743 225.146 291.287 + vertex -702.6 221.72 292.038 + endloop + endfacet + facet normal -0.686724 0.0152477 -0.726758 + outer loop + vertex -701.577 241.964 291.448 + vertex -701.585 233.047 291.268 + vertex -702.454 234.305 292.115 + endloop + endfacet + facet normal -0.685968 0.0092329 -0.727573 + outer loop + vertex -701.352 247.864 291.31 + vertex -701.577 241.964 291.448 + vertex -702.108 246.878 292.011 + endloop + endfacet + facet normal -0.681248 0.0024375 -0.732049 + outer loop + vertex -701.246 255.426 291.237 + vertex -701.352 247.864 291.31 + vertex -702.108 246.878 292.011 + endloop + endfacet + facet normal -0.717235 0.00473488 -0.696815 + outer loop + vertex -701.323 265.814 291.387 + vertex -701.246 255.426 291.237 + vertex -702.04 259.466 292.082 + endloop + endfacet + facet normal -0.74674 -0.00283429 -0.665109 + outer loop + vertex -701.095 274.035 291.095 + vertex -701.323 265.814 291.387 + vertex -701.927 273.304 292.033 + endloop + endfacet + facet normal -0.747898 0.000146189 -0.663814 + outer loop + vertex -701.377 282.151 291.415 + vertex -701.095 274.035 291.095 + vertex -701.927 273.304 292.033 + endloop + endfacet + facet normal -0.761676 -0.00539974 -0.647936 + outer loop + vertex -701.243 290.426 291.188 + vertex -701.377 282.151 291.415 + vertex -701.988 288.208 292.083 + endloop + endfacet + facet normal -0.766361 -0.00159183 -0.642408 + outer loop + vertex -701.526 297.247 291.51 + vertex -701.243 290.426 291.188 + vertex -701.988 288.208 292.083 + endloop + endfacet + facet normal -0.771647 -0.00510978 -0.63603 + outer loop + vertex -701.465 302.291 291.394 + vertex -701.526 297.247 291.51 + vertex -702.001 302.812 292.041 + endloop + endfacet + facet normal -0.772835 -0.00816343 -0.634554 + outer loop + vertex -701.362 307.156 291.207 + vertex -701.465 302.291 291.394 + vertex -702.001 302.812 292.041 + endloop + endfacet + facet normal -0.78832 -0.00218379 -0.615261 + outer loop + vertex -701.602 312.357 291.496 + vertex -701.362 307.156 291.207 + vertex -702.001 302.812 292.041 + endloop + endfacet + facet normal -0.77969 -0.00554052 -0.626142 + outer loop + vertex -701.553 317.443 291.389 + vertex -701.602 312.357 291.496 + vertex -702.082 315.813 292.063 + endloop + endfacet + facet normal -0.778445 -0.00657931 -0.627679 + outer loop + vertex -701.55 323.81 291.319 + vertex -701.553 317.443 291.389 + vertex -702.082 315.813 292.063 + endloop + endfacet + facet normal -0.786607 -0.00494226 -0.617434 + outer loop + vertex -701.621 329.81 291.361 + vertex -701.55 323.81 291.319 + vertex -702.081 329.311 291.952 + endloop + endfacet + facet normal -0.785648 -0.00724471 -0.618631 + outer loop + vertex -701.643 332.854 291.355 + vertex -701.621 329.81 291.361 + vertex -702.081 329.311 291.952 + endloop + endfacet + facet normal -0.782664 -0.00824752 -0.62239 + outer loop + vertex -701.708 339.177 291.352 + vertex -701.643 332.854 291.355 + vertex -702.081 329.311 291.952 + endloop + endfacet + facet normal -0.7992 -0.00730057 -0.601021 + outer loop + vertex -701.83 345.874 291.433 + vertex -701.708 339.177 291.352 + vertex -702.236 342.488 292.014 + endloop + endfacet + facet normal -0.802181 -0.00626187 -0.597049 + outer loop + vertex -701.956 350.156 291.557 + vertex -701.83 345.874 291.433 + vertex -702.236 342.488 292.014 + endloop + endfacet + facet normal -0.819567 -0.00839209 -0.572922 + outer loop + vertex -701.95 354.36 291.487 + vertex -701.956 350.156 291.557 + vertex -702.373 355.853 292.07 + endloop + endfacet + facet normal -0.821072 -0.0096695 -0.570743 + outer loop + vertex -701.976 359.375 291.44 + vertex -701.95 354.36 291.487 + vertex -702.373 355.853 292.07 + endloop + endfacet + facet normal -0.832845 -0.00525271 -0.553481 + outer loop + vertex -702.232 365.182 291.77 + vertex -701.976 359.375 291.44 + vertex -702.373 355.853 292.07 + endloop + endfacet + facet normal -0.768996 -0.00548928 -0.639229 + outer loop + vertex -702.253 369.542 291.758 + vertex -702.232 365.182 291.77 + vertex -702.613 370.124 292.186 + endloop + endfacet + facet normal -0.778454 -0.0200417 -0.627382 + outer loop + vertex -702.219 372.165 291.631 + vertex -702.253 369.542 291.758 + vertex -702.613 370.124 292.186 + endloop + endfacet + facet normal -0.70209 -0.0571628 -0.70979 + outer loop + vertex -702.303 378.625 291.194 + vertex -702.219 372.165 291.631 + vertex -702.613 370.124 292.186 + endloop + endfacet + facet normal -0.846515 -0.0733828 -0.527284 + outer loop + vertex -703.566 386.655 292.105 + vertex -702.303 378.625 291.194 + vertex -703.672 386.655 292.275 + endloop + endfacet + facet normal -0.0845711 -0.584175 -0.80721 + outer loop + vertex -846.581 242.412 296.237 + vertex -847.211 242.02 296.586 + vertex -846.811 242.51 296.19 + endloop + endfacet + facet normal -0.209947 -0.595021 -0.775804 + outer loop + vertex -847.211 242.02 296.586 + vertex -846.609 240.976 297.224 + vertex -848.286 242.207 296.733 + endloop + endfacet + facet normal 0.501598 -0.644152 -0.577466 + outer loop + vertex -841.288 246.37 294.211 + vertex -842.578 244.948 294.678 + vertex -842.086 245.541 294.444 + endloop + endfacet + facet normal 0.530087 -0.803836 -0.269918 + outer loop + vertex -842.578 244.948 294.678 + vertex -844.002 243.841 295.177 + vertex -843.481 244.267 294.932 + endloop + endfacet + facet normal 0.427303 -0.894487 -0.131548 + outer loop + vertex -844.002 243.841 295.177 + vertex -845.483 243.059 295.686 + vertex -844.961 243.343 295.448 + endloop + endfacet + facet normal -0.00112717 -0.674648 -0.738139 + outer loop + vertex -845.483 243.059 295.686 + vertex -846.811 242.51 296.19 + vertex -846.477 242.734 295.985 + endloop + endfacet + facet normal 0.790219 -0.393902 -0.469462 + outer loop + vertex -837.578 253.45 293.197 + vertex -839.312 249.542 293.557 + vertex -838.561 251.457 293.214 + endloop + endfacet + facet normal 0.145537 -0.174903 -0.97377 + outer loop + vertex -839.312 249.542 293.557 + vertex -839.761 248.627 293.654 + vertex -839.744 248.776 293.63 + endloop + endfacet + facet normal -0.125363 -0.146125 -0.981291 + outer loop + vertex -839.761 248.627 293.654 + vertex -840.22 247.894 293.822 + vertex -839.744 248.776 293.63 + endloop + endfacet + facet normal 0.540415 -0.543112 -0.642636 + outer loop + vertex -840.22 247.894 293.822 + vertex -841.288 246.37 294.211 + vertex -840.831 247.07 294.004 + endloop + endfacet + facet normal 0.791006 -0.178145 -0.585298 + outer loop + vertex -834.563 263.215 292.773 + vertex -835.146 261.909 292.382 + vertex -834.332 266.499 292.085 + endloop + endfacet + facet normal 0.900354 -0.251286 -0.355272 + outer loop + vertex -835.146 261.909 292.382 + vertex -835.969 258.505 292.706 + vertex -835.812 259.509 292.393 + endloop + endfacet + facet normal 0.836038 -0.31018 -0.452581 + outer loop + vertex -835.969 258.505 292.706 + vertex -837.578 253.45 293.197 + vertex -836.976 255.768 292.721 + endloop + endfacet + facet normal -0.00328739 -0.460022 -0.887901 + outer loop + vertex -844.798 239.017 298.28 + vertex -843.03 237.464 299.078 + vertex -843.232 236.928 299.357 + endloop + endfacet + facet normal -0.00725782 -0.457175 -0.889347 + outer loop + vertex -843.03 237.464 299.078 + vertex -842.526 238.534 298.524 + vertex -840.336 235.842 299.89 + endloop + endfacet + facet normal -0.115396 -0.551857 -0.825917 + outer loop + vertex -846.609 240.976 297.224 + vertex -844.798 239.017 298.28 + vertex -845.914 239.558 298.075 + endloop + endfacet + facet normal 0.772009 -0.181785 -0.609062 + outer loop + vertex -832.272 272.125 293.017 + vertex -834.563 263.215 292.773 + vertex -834.332 266.499 292.085 + endloop + endfacet + facet normal 0.696799 -0.141006 -0.70327 + outer loop + vertex -829.865 284.119 292.997 + vertex -832.272 272.125 293.017 + vertex -831.839 279.306 292.007 + endloop + endfacet + facet normal 0.685743 -0.149249 -0.712377 + outer loop + vertex -827.751 294.108 292.939 + vertex -829.865 284.119 292.997 + vertex -829.822 290.566 291.689 + endloop + endfacet + facet normal 0.673754 -0.171712 -0.718728 + outer loop + vertex -825.468 302.459 293.084 + vertex -827.751 294.108 292.939 + vertex -827.604 299.74 291.732 + endloop + endfacet + facet normal 0.651435 -0.193059 -0.733731 + outer loop + vertex -823.269 310.564 292.905 + vertex -825.468 302.459 293.084 + vertex -825.932 305.409 291.897 + endloop + endfacet + facet normal 0.666453 -0.220984 -0.712044 + outer loop + vertex -820.341 318.751 293.104 + vertex -823.269 310.564 292.905 + vertex -822.804 315.965 291.664 + endloop + endfacet + facet normal 0.644945 -0.235248 -0.727121 + outer loop + vertex -817.651 326.575 292.959 + vertex -820.341 318.751 293.104 + vertex -820.66 321.466 291.943 + endloop + endfacet + facet normal 0.670596 -0.262583 -0.693795 + outer loop + vertex -814.35 334.532 293.137 + vertex -817.651 326.575 292.959 + vertex -816.923 331.705 291.721 + endloop + endfacet + facet normal 0.657739 -0.274907 -0.701289 + outer loop + vertex -811.387 342.107 292.947 + vertex -814.35 334.532 293.137 + vertex -814.509 337.148 291.963 + endloop + endfacet + facet normal 0.6849 -0.301786 -0.663202 + outer loop + vertex -807.905 349.695 293.091 + vertex -811.387 342.107 292.947 + vertex -810.396 347.183 291.661 + endloop + endfacet + facet normal 0.683593 -0.311647 -0.659982 + outer loop + vertex -804.864 356.474 293.039 + vertex -807.905 349.695 293.091 + vertex -807.73 352.601 291.899 + endloop + endfacet + facet normal 0.709132 -0.323136 -0.626669 + outer loop + vertex -801.719 363.757 292.843 + vertex -804.864 356.474 293.039 + vertex -805.355 358.293 291.546 + endloop + endfacet + facet normal 0.729559 -0.325101 -0.601708 + outer loop + vertex -798.135 371.09 293.226 + vertex -801.719 363.757 292.843 + vertex -800.73 367.791 291.863 + endloop + endfacet + facet normal 0.719551 -0.201163 -0.664665 + outer loop + vertex -793.904 377.141 295.166 + vertex -795.643 376.949 293.341 + vertex -792.003 384.848 294.891 + endloop + endfacet + facet normal 0.756115 -0.310273 -0.576213 + outer loop + vertex -795.643 376.949 293.341 + vertex -798.135 371.09 293.226 + vertex -798.386 373.16 291.782 + endloop + endfacet + facet normal 0.045997 -0.359075 -0.932174 + outer loop + vertex -840.336 235.842 299.89 + vertex -836.859 232.569 301.322 + vertex -839.593 233.414 300.862 + endloop + endfacet + facet normal 0.0859262 -0.272644 -0.95827 + outer loop + vertex -836.859 232.569 301.322 + vertex -834.173 230.161 302.248 + vertex -835.279 229.581 302.314 + endloop + endfacet + facet normal 0.0685159 -0.240636 -0.968194 + outer loop + vertex -834.173 230.161 302.248 + vertex -832.079 227.514 303.054 + vertex -835.279 229.581 302.314 + endloop + endfacet + facet normal 0.0440063 -0.222668 -0.973901 + outer loop + vertex -832.079 227.514 303.054 + vertex -829.091 224.269 303.931 + vertex -831.731 225.614 303.504 + endloop + endfacet + facet normal 0.00718117 -0.219607 -0.975562 + outer loop + vertex -829.091 224.269 303.931 + vertex -825.971 221.17 304.652 + vertex -828.283 222.218 304.399 + endloop + endfacet + facet normal 0.0199943 -0.178445 -0.983747 + outer loop + vertex -825.971 221.17 304.652 + vertex -820.546 218.151 305.31 + vertex -824.514 218.826 305.107 + endloop + endfacet + facet normal 0.0202036 -0.12534 -0.991908 + outer loop + vertex -820.546 218.151 305.31 + vertex -813.698 212.836 306.121 + vertex -816.891 212.536 306.094 + endloop + endfacet + facet normal 0.00414207 -0.0969879 -0.995277 + outer loop + vertex -813.698 212.836 306.121 + vertex -807.942 207.852 306.63 + vertex -812.043 208.211 306.578 + endloop + endfacet + facet normal -0.136865 -0.112508 -0.98418 + outer loop + vertex -740.856 166.721 306.132 + vertex -734.711 163.095 305.692 + vertex -738.709 163.01 306.258 + endloop + endfacet + facet normal -0.160151 -0.122994 -0.9794 + outer loop + vertex -734.711 163.095 305.692 + vertex -729.376 159.849 305.227 + vertex -733.169 159.983 305.831 + endloop + endfacet + facet normal -0.471805 -0.461335 -0.751379 + outer loop + vertex -697.182 144.719 298.481 + vertex -695.068 143.908 297.651 + vertex -696.135 143.944 298.3 + endloop + endfacet + facet normal -0.387229 -0.513189 -0.765957 + outer loop + vertex -694.181 143.754 297.189 + vertex -693.983 143.897 296.993 + vertex -693.615 143.55 297.04 + endloop + endfacet + facet normal -0.407948 -0.738145 -0.537328 + outer loop + vertex -695.068 143.908 297.651 + vertex -694.181 143.754 297.189 + vertex -693.615 143.55 297.04 + endloop + endfacet + facet normal -0.921579 -0.0155434 0.38788 + outer loop + vertex -702.489 182.868 292.353 + vertex -702.772 194.159 292.134 + vertex -702.643 187.289 292.164 + endloop + endfacet + facet normal -0.753204 -0.00418431 -0.657773 + outer loop + vertex -702.772 194.159 292.134 + vertex -702.788 207.427 292.068 + vertex -702.351 203.88 291.59 + endloop + endfacet + facet normal -0.702917 0.00777051 -0.71123 + outer loop + vertex -702.788 207.427 292.068 + vertex -702.6 221.72 292.038 + vertex -701.904 216.953 291.298 + endloop + endfacet + facet normal -0.688878 0.0124226 -0.724771 + outer loop + vertex -702.6 221.72 292.038 + vertex -702.454 234.305 292.115 + vertex -701.585 233.047 291.268 + endloop + endfacet + facet normal -0.671627 0.012297 -0.740787 + outer loop + vertex -702.454 234.305 292.115 + vertex -702.108 246.878 292.011 + vertex -701.577 241.964 291.448 + endloop + endfacet + facet normal -0.709717 0.00780727 -0.704444 + outer loop + vertex -702.108 246.878 292.011 + vertex -702.04 259.466 292.082 + vertex -701.246 255.426 291.237 + endloop + endfacet + facet normal -0.711003 0.00333433 -0.703181 + outer loop + vertex -702.04 259.466 292.082 + vertex -701.927 273.304 292.033 + vertex -701.323 265.814 291.387 + endloop + endfacet + facet normal -0.741295 -0.000779336 -0.671179 + outer loop + vertex -701.927 273.304 292.033 + vertex -701.988 288.208 292.083 + vertex -701.377 282.151 291.415 + endloop + endfacet + facet normal -0.758764 -0.00254805 -0.651361 + outer loop + vertex -701.988 288.208 292.083 + vertex -702.001 302.812 292.041 + vertex -701.526 297.247 291.51 + endloop + endfacet + facet normal -0.77446 -0.00375375 -0.632612 + outer loop + vertex -702.001 302.812 292.041 + vertex -702.082 315.813 292.063 + vertex -701.602 312.357 291.496 + endloop + endfacet + facet normal -0.786939 -0.00502302 -0.617011 + outer loop + vertex -702.082 315.813 292.063 + vertex -702.081 329.311 291.952 + vertex -701.55 323.81 291.319 + endloop + endfacet + facet normal -0.7974 -0.00653478 -0.603416 + outer loop + vertex -702.081 329.311 291.952 + vertex -702.236 342.488 292.014 + vertex -701.708 339.177 291.352 + endloop + endfacet + facet normal -0.806399 -0.00576808 -0.591344 + outer loop + vertex -702.236 342.488 292.014 + vertex -702.373 355.853 292.07 + vertex -701.956 350.156 291.557 + endloop + endfacet + facet normal -0.783783 -0.0081629 -0.620981 + outer loop + vertex -702.373 355.853 292.07 + vertex -702.613 370.124 292.186 + vertex -702.232 365.182 291.77 + endloop + endfacet + facet normal -0.770917 -0.0459551 -0.635276 + outer loop + vertex -702.613 370.124 292.186 + vertex -703.672 386.655 292.275 + vertex -702.303 378.625 291.194 + endloop + endfacet + facet normal -0.375 -0.502028 -0.779322 + outer loop + vertex -693.983 143.897 296.993 + vertex -693.89 143.909 296.941 + vertex -693.615 143.55 297.04 + endloop + endfacet + facet normal -0.19035 -0.332121 -0.92383 + outer loop + vertex -693.89 143.909 296.941 + vertex -694.267 144.751 296.716 + vertex -693.994 144.208 296.855 + endloop + endfacet + facet normal -0.946261 -0.322828 0.0193181 + outer loop + vertex -696.355 149.694 295.649 + vertex -697.89 154.148 294.853 + vertex -697.155 152.01 295.143 + endloop + endfacet + facet normal -0.484158 -0.343115 -0.8049 + outer loop + vertex -695.783 148.32 295.891 + vertex -696.355 149.694 295.649 + vertex -697.155 152.01 295.143 + endloop + endfacet + facet normal -0.243807 -0.314324 -0.917474 + outer loop + vertex -694.663 145.715 296.486 + vertex -695.783 148.32 295.891 + vertex -695.568 147.948 295.961 + endloop + endfacet + facet normal 0.262245 -0.118069 -0.957751 + outer loop + vertex -693.994 144.208 296.855 + vertex -694.663 145.715 296.486 + vertex -693.615 143.55 297.04 + endloop + endfacet + facet normal -0.784943 -0.0937714 0.612431 + outer loop + vertex -699.617 160.402 293.942 + vertex -700.928 166.825 293.245 + vertex -700.708 165.441 293.316 + endloop + endfacet + facet normal -0.812328 -0.141915 0.56567 + outer loop + vertex -697.89 154.148 294.853 + vertex -699.617 160.402 293.942 + vertex -698.851 157.302 294.264 + endloop + endfacet + facet normal -0.961759 -0.0451372 -0.270151 + outer loop + vertex -702.347 179.562 292.401 + vertex -702.489 182.868 292.353 + vertex -702.643 187.289 292.164 + endloop + endfacet + facet normal -0.9764 -0.0912888 -0.195726 + outer loop + vertex -701.807 173.069 292.734 + vertex -702.347 179.562 292.401 + vertex -702.079 176.432 292.522 + endloop + endfacet + facet normal -0.7251 -0.156897 -0.670532 + outer loop + vertex -700.928 166.825 293.245 + vertex -701.807 173.069 292.734 + vertex -701.485 171.039 292.861 + endloop + endfacet + facet normal 0.812303 -0.273239 -0.51527 + outer loop + vertex -795.673 379.842 291.76 + vertex -792.003 384.848 294.891 + vertex -795.643 376.949 293.341 + endloop + endfacet + facet normal -0.203373 -0.510089 -0.835732 + outer loop + vertex -848.286 242.207 296.733 + vertex -846.811 242.51 296.19 + vertex -847.211 242.02 296.586 + endloop + endfacet + facet normal -0.00828454 -0.458528 -0.888641 + outer loop + vertex -840.336 235.842 299.89 + vertex -843.232 236.928 299.357 + vertex -843.03 237.464 299.078 + endloop + endfacet + facet normal -0.0297326 -0.286234 -0.957698 + outer loop + vertex -693.615 143.55 297.04 + vertex -693.89 143.909 296.941 + vertex -693.994 144.208 296.855 + endloop + endfacet + facet normal -0.291878 0.939053 0.181621 + outer loop + vertex 475.436 61.4147 33.7978 + vertex 477.51 61.9646 34.2887 + vertex 485.671 64.1481 36.1137 + endloop + endfacet + facet normal -0.216586 0.959597 -0.179624 + outer loop + vertex 485.671 64.1481 36.1137 + vertex 477.51 61.9646 34.2887 + vertex 486.476 64.3793 36.378 + endloop + endfacet + facet normal -0.165164 0.922724 -0.348284 + outer loop + vertex 488.918 65.0131 36.8652 + vertex 485.671 64.1481 36.1137 + vertex 491.348 65.7219 37.5908 + endloop + endfacet + facet normal -0.152931 0.911056 -0.38287 + outer loop + vertex 491.348 65.7219 37.5908 + vertex 485.671 64.1481 36.1137 + vertex 492.311 66.0124 37.8978 + endloop + endfacet + facet normal -0.113074 0.87393 -0.472716 + outer loop + vertex 491.348 65.7219 37.5908 + vertex 492.311 66.0124 37.8978 + vertex 495.666 66.9795 38.883 + endloop + endfacet + facet normal -0.243104 0.964503 -0.103122 + outer loop + vertex 485.671 64.1481 36.1137 + vertex 486.476 64.3793 36.378 + vertex 492.311 66.0124 37.8978 + endloop + endfacet + facet normal 0.0698485 -0.801825 0.593463 + outer loop + vertex 486.476 64.3793 36.378 + vertex 493.602 66.3397 38.1879 + vertex 492.311 66.0124 37.8978 + endloop + endfacet + facet normal 0.258202 -0.94356 -0.207426 + outer loop + vertex 455.726 56.4918 30.7316 + vertex 457.797 57.0039 30.9799 + vertex 465.831 58.9622 32.0723 + endloop + endfacet + facet normal -0.196486 0.947275 -0.253108 + outer loop + vertex 465.831 58.9622 32.0723 + vertex 457.797 57.0039 30.9799 + vertex 467.757 59.4532 32.4149 + endloop + endfacet + facet normal 0.205211 -0.954835 0.214893 + outer loop + vertex 465.831 58.9622 32.0723 + vertex 467.757 59.4532 32.4149 + vertex 475.436 61.4147 33.7978 + endloop + endfacet + facet normal -0.216412 0.962502 -0.163574 + outer loop + vertex 475.436 61.4147 33.7978 + vertex 467.757 59.4532 32.4149 + vertex 477.51 61.9646 34.2887 + endloop + endfacet + facet normal -0.181143 0.918246 -0.352151 + outer loop + vertex 443.016 53.4939 29.451 + vertex 438.118 52.4137 29.1534 + vertex 447.006 54.421 29.8162 + endloop + endfacet + facet normal -0.189174 0.935775 -0.297555 + outer loop + vertex 447.006 54.421 29.8162 + vertex 438.118 52.4137 29.1534 + vertex 447.569 54.5606 29.8971 + endloop + endfacet + facet normal -0.198106 0.946654 -0.254168 + outer loop + vertex 447.006 54.421 29.8162 + vertex 447.569 54.5606 29.8971 + vertex 455.726 56.4918 30.7316 + endloop + endfacet + facet normal -0.148758 0.848106 -0.508514 + outer loop + vertex 455.726 56.4918 30.7316 + vertex 447.569 54.5606 29.8971 + vertex 457.797 57.0039 30.9799 + endloop + endfacet + facet normal 0.240794 0.966036 0.093773 + outer loop + vertex -459.252 57.3218 31.1494 + vertex -457.759 56.9626 31.0152 + vertex -449.926 55.1035 30.0549 + endloop + endfacet + facet normal 0.245494 0.958124 0.147417 + outer loop + vertex -449.926 55.1035 30.0549 + vertex -457.759 56.9626 31.0152 + vertex -447.71 54.5661 29.8582 + endloop + endfacet + facet normal 0.118598 0.128536 0.984588 + outer loop + vertex -449.926 55.1035 30.0549 + vertex -447.71 54.5661 29.8582 + vertex -442.216 53.336 29.3569 + endloop + endfacet + facet normal 0.224252 0.971763 0.0733957 + outer loop + vertex -442.216 53.336 29.3569 + vertex -447.71 54.5661 29.8582 + vertex -436.418 52.0254 28.9949 + endloop + endfacet + facet normal 0.221699 0.963396 -0.150721 + outer loop + vertex -477.697 62.0049 34.2463 + vertex -476.819 61.7914 34.1733 + vertex -468.678 59.6628 32.5424 + endloop + endfacet + facet normal 0.214727 0.95979 -0.180818 + outer loop + vertex -468.678 59.6628 32.5424 + vertex -476.819 61.7914 34.1733 + vertex -467.704 59.4382 32.5067 + endloop + endfacet + facet normal 0.216702 0.964053 -0.153757 + outer loop + vertex -468.678 59.6628 32.5424 + vertex -467.704 59.4382 32.5067 + vertex -459.252 57.3218 31.1494 + endloop + endfacet + facet normal 0.220278 0.966096 -0.13467 + outer loop + vertex -459.252 57.3218 31.1494 + vertex -467.704 59.4382 32.5067 + vertex -457.759 56.9626 31.0152 + endloop + endfacet + facet normal 0.325869 0.170286 0.929953 + outer loop + vertex -493.304 66.3152 38.2216 + vertex -495.612 66.9797 38.9089 + vertex -490.68 65.5499 37.4423 + endloop + endfacet + facet normal 0.383651 0.68775 0.616288 + outer loop + vertex -493.304 66.3152 38.2216 + vertex -490.68 65.5499 37.4423 + vertex -489.875 65.3234 37.1941 + endloop + endfacet + facet normal 0.250681 0.96565 -0.0684081 + outer loop + vertex -489.875 65.3234 37.1941 + vertex -490.68 65.5499 37.4423 + vertex -484.901 63.939 35.8805 + endloop + endfacet + facet normal 0.226724 0.963682 -0.141117 + outer loop + vertex -484.901 63.939 35.8805 + vertex -483.383 63.5375 35.5779 + vertex -477.697 62.0049 34.2463 + endloop + endfacet + facet normal 0.219659 0.960974 -0.168165 + outer loop + vertex -477.697 62.0049 34.2463 + vertex -483.383 63.5375 35.5779 + vertex -476.819 61.7914 34.1733 + endloop + endfacet + facet normal 0.0321294 -0.711495 0.701956 + outer loop + vertex 478.255 62.0725 34.4059 + vertex 478.725 61.9417 34.2519 + vertex 487.028 64.4231 36.3869 + endloop + endfacet + facet normal 0.0859582 -0.79934 0.594698 + outer loop + vertex 487.028 64.4231 36.3869 + vertex 478.725 61.9417 34.2519 + vertex 487.422 64.2611 36.1122 + endloop + endfacet + facet normal -0.05928 -0.518152 0.853232 + outer loop + vertex 477.51 61.9646 34.2887 + vertex 478.255 62.0725 34.4059 + vertex 486.476 64.3793 36.378 + endloop + endfacet + facet normal 0.0480145 -0.742381 0.668255 + outer loop + vertex 486.476 64.3793 36.378 + vertex 478.255 62.0725 34.4059 + vertex 487.028 64.4231 36.3869 + endloop + endfacet + facet normal 0.0508127 -0.770904 0.634922 + outer loop + vertex 486.476 64.3793 36.378 + vertex 487.028 64.4231 36.3869 + vertex 493.602 66.3397 38.1879 + endloop + endfacet + facet normal 0.0791705 -0.804831 0.5882 + outer loop + vertex 487.028 64.4231 36.3869 + vertex 487.422 64.2611 36.1122 + vertex 492.642 65.9224 37.6828 + endloop + endfacet + facet normal 0.033919 -0.619367 0.784368 + outer loop + vertex 458.786 57.1809 31.0433 + vertex 459.082 57.0225 30.9054 + vertex 468.625 59.5892 32.5195 + endloop + endfacet + facet normal 0.0251257 -0.597453 0.80151 + outer loop + vertex 468.625 59.5892 32.5195 + vertex 459.082 57.0225 30.9054 + vertex 468.93 59.4196 32.3835 + endloop + endfacet + facet normal 0.0955857 -0.763139 0.639126 + outer loop + vertex 457.797 57.0039 30.9799 + vertex 458.786 57.1809 31.0433 + vertex 467.757 59.4532 32.4149 + endloop + endfacet + facet normal -0.0644118 -0.31691 0.946266 + outer loop + vertex 467.757 59.4532 32.4149 + vertex 458.786 57.1809 31.0433 + vertex 468.625 59.5892 32.5195 + endloop + endfacet + facet normal -0.00756097 -0.578958 0.815322 + outer loop + vertex 467.757 59.4532 32.4149 + vertex 468.625 59.5892 32.5195 + vertex 477.51 61.9646 34.2887 + endloop + endfacet + facet normal -0.10183 -0.320503 0.941758 + outer loop + vertex 477.51 61.9646 34.2887 + vertex 468.625 59.5892 32.5195 + vertex 478.255 62.0725 34.4059 + endloop + endfacet + facet normal 0.00583243 -0.619143 0.785257 + outer loop + vertex 468.625 59.5892 32.5195 + vertex 468.93 59.4196 32.3835 + vertex 478.255 62.0725 34.4059 + endloop + endfacet + facet normal 0.0419873 -0.69488 0.717899 + outer loop + vertex 478.255 62.0725 34.4059 + vertex 468.93 59.4196 32.3835 + vertex 478.725 61.9417 34.2519 + endloop + endfacet + facet normal 0.104235 -0.680768 0.725045 + outer loop + vertex 436.495 51.9602 29.048 + vertex 439.386 52.5083 29.147 + vertex 448.549 54.7652 29.9488 + endloop + endfacet + facet normal 0.0784564 -0.601084 0.795326 + outer loop + vertex 448.549 54.7652 29.9488 + vertex 439.386 52.5083 29.147 + vertex 449.067 54.704 29.8514 + endloop + endfacet + facet normal -0.133195 0.254464 0.957866 + outer loop + vertex 438.118 52.4137 29.1534 + vertex 436.495 51.9602 29.048 + vertex 447.569 54.5606 29.8971 + endloop + endfacet + facet normal 0.101846 -0.672943 0.732649 + outer loop + vertex 447.569 54.5606 29.8971 + vertex 436.495 51.9602 29.048 + vertex 448.549 54.7652 29.9488 + endloop + endfacet + facet normal 0.153807 -0.859728 0.487043 + outer loop + vertex 447.569 54.5606 29.8971 + vertex 448.549 54.7652 29.9488 + vertex 457.797 57.0039 30.9799 + endloop + endfacet + facet normal 0.0561257 -0.599563 0.798357 + outer loop + vertex 457.797 57.0039 30.9799 + vertex 448.549 54.7652 29.9488 + vertex 458.786 57.1809 31.0433 + endloop + endfacet + facet normal 0.0686725 -0.638375 0.766656 + outer loop + vertex 448.549 54.7652 29.9488 + vertex 449.067 54.704 29.8514 + vertex 458.786 57.1809 31.0433 + endloop + endfacet + facet normal 0.053826 -0.596536 0.800779 + outer loop + vertex 458.786 57.1809 31.0433 + vertex 449.067 54.704 29.8514 + vertex 459.082 57.0225 30.9054 + endloop + endfacet + facet normal 0.0457074 -0.405877 0.912784 + outer loop + vertex 439.386 52.5083 29.147 + vertex 436.495 51.9602 29.048 + vertex 423.32 48.659 28.2398 + endloop + endfacet + facet normal -0.00547091 -0.207619 0.978194 + outer loop + vertex 438.118 52.4137 29.1534 + vertex 420.155 48.3883 28.1985 + vertex 436.495 51.9602 29.048 + endloop + endfacet + facet normal 0.01149 -0.280808 0.959695 + outer loop + vertex 420.155 48.3883 28.1985 + vertex 423.32 48.659 28.2398 + vertex 436.495 51.9602 29.048 + endloop + endfacet + facet normal -8.18953e-05 -0.149923 0.988698 + outer loop + vertex 420.155 48.3883 28.1985 + vertex 401.396 44.0313 27.5363 + vertex 423.32 48.659 28.2398 + endloop + endfacet + facet normal 0.00383178 -0.13371 0.991013 + outer loop + vertex -421.839 48.8353 28.2616 + vertex -422.542 48.681 28.2435 + vertex -403.558 44.9696 27.6694 + endloop + endfacet + facet normal 0.00414279 -0.206006 0.978542 + outer loop + vertex -436.418 52.0254 28.9949 + vertex -435.232 51.6491 28.9107 + vertex -421.839 48.8353 28.2616 + endloop + endfacet + facet normal -0.0253322 -0.321109 0.946704 + outer loop + vertex -438.079 52.0699 28.9772 + vertex -422.542 48.681 28.2435 + vertex -435.232 51.6491 28.9107 + endloop + endfacet + facet normal 0.0119884 -0.170228 0.985332 + outer loop + vertex -422.542 48.681 28.2435 + vertex -421.839 48.8353 28.2616 + vertex -435.232 51.6491 28.9107 + endloop + endfacet + facet normal -0.0785682 -0.670923 0.737353 + outer loop + vertex -457.457 56.8203 30.9233 + vertex -458.001 56.7366 30.789 + vertex -446.73 54.2803 29.7551 + endloop + endfacet + facet normal -0.0581168 -0.601938 0.796425 + outer loop + vertex -446.73 54.2803 29.7551 + vertex -458.001 56.7366 30.789 + vertex -447.548 54.2705 29.688 + endloop + endfacet + facet normal -0.0609476 -0.629511 0.774598 + outer loop + vertex -457.759 56.9626 31.0152 + vertex -457.457 56.8203 30.9233 + vertex -447.71 54.5661 29.8582 + endloop + endfacet + facet normal 0.124247 0.0694823 0.989816 + outer loop + vertex -447.71 54.5661 29.8582 + vertex -457.457 56.8203 30.9233 + vertex -446.73 54.2803 29.7551 + endloop + endfacet + facet normal -0.0188224 -0.395635 0.918215 + outer loop + vertex -447.71 54.5661 29.8582 + vertex -446.73 54.2803 29.7551 + vertex -436.418 52.0254 28.9949 + endloop + endfacet + facet normal 0.0794769 0.0275013 0.996457 + outer loop + vertex -436.418 52.0254 28.9949 + vertex -446.73 54.2803 29.7551 + vertex -435.232 51.6491 28.9107 + endloop + endfacet + facet normal -0.0622982 -0.541335 0.838496 + outer loop + vertex -446.73 54.2803 29.7551 + vertex -447.548 54.2705 29.688 + vertex -435.232 51.6491 28.9107 + endloop + endfacet + facet normal -0.0570082 -0.520477 0.851971 + outer loop + vertex -435.232 51.6491 28.9107 + vertex -447.548 54.2705 29.688 + vertex -438.079 52.0699 28.9772 + endloop + endfacet + facet normal -0.0850391 -0.777127 0.623572 + outer loop + vertex -477.57 61.945 34.3258 + vertex -478.513 61.9648 34.2219 + vertex -467.876 59.4158 32.4958 + endloop + endfacet + facet normal -0.0791414 -0.763931 0.640427 + outer loop + vertex -467.876 59.4158 32.4958 + vertex -478.513 61.9648 34.2219 + vertex -468.475 59.33 32.3195 + endloop + endfacet + facet normal 0.253783 0.342323 0.90466 + outer loop + vertex -476.819 61.7914 34.1733 + vertex -477.57 61.945 34.3258 + vertex -467.704 59.4382 32.5067 + endloop + endfacet + facet normal 0.017093 -0.542292 0.840016 + outer loop + vertex -467.704 59.4382 32.5067 + vertex -477.57 61.945 34.3258 + vertex -467.876 59.4158 32.4958 + endloop + endfacet + facet normal 0.0084524 -0.490917 0.871166 + outer loop + vertex -467.704 59.4382 32.5067 + vertex -467.876 59.4158 32.4958 + vertex -457.759 56.9626 31.0152 + endloop + endfacet + facet normal -0.0173471 -0.568111 0.822769 + outer loop + vertex -457.759 56.9626 31.0152 + vertex -467.876 59.4158 32.4958 + vertex -457.457 56.8203 30.9233 + endloop + endfacet + facet normal -0.086825 -0.747527 0.658532 + outer loop + vertex -467.876 59.4158 32.4958 + vertex -468.475 59.33 32.3195 + vertex -457.457 56.8203 30.9233 + endloop + endfacet + facet normal -0.0685201 -0.697585 0.713218 + outer loop + vertex -457.457 56.8203 30.9233 + vertex -468.475 59.33 32.3195 + vertex -458.001 56.7366 30.789 + endloop + endfacet + facet normal 0.279873 0.951937 0.124449 + outer loop + vertex -483.383 63.5375 35.5779 + vertex -485.426 64.0725 36.0812 + vertex -476.819 61.7914 34.1733 + endloop + endfacet + facet normal 0.13296 -0.290795 0.947502 + outer loop + vertex -476.819 61.7914 34.1733 + vertex -485.426 64.0725 36.0812 + vertex -477.57 61.945 34.3258 + endloop + endfacet + facet normal -0.086341 -0.804123 0.58816 + outer loop + vertex -485.426 64.0725 36.0812 + vertex -486.915 64.3013 36.1755 + vertex -477.57 61.945 34.3258 + endloop + endfacet + facet normal -0.0826454 -0.797208 0.598021 + outer loop + vertex -477.57 61.945 34.3258 + vertex -486.915 64.3013 36.1755 + vertex -478.513 61.9648 34.2219 + endloop + endfacet + facet normal 0.0717787 -0.760207 0.645704 + outer loop + vertex 479.368 61.6586 33.8723 + vertex 480.296 61.2224 33.2557 + vertex 488.351 64.043 35.6811 + endloop + endfacet + facet normal 0.0976683 -0.794399 0.599493 + outer loop + vertex 488.351 64.043 35.6811 + vertex 480.296 61.2224 33.2557 + vertex 489.356 63.4992 34.7968 + endloop + endfacet + facet normal 0.0589388 -0.749706 0.659142 + outer loop + vertex 478.725 61.9417 34.2519 + vertex 479.368 61.6586 33.8723 + vertex 487.422 64.2611 36.1122 + endloop + endfacet + facet normal 0.0908577 -0.796111 0.59829 + outer loop + vertex 487.422 64.2611 36.1122 + vertex 479.368 61.6586 33.8723 + vertex 488.351 64.043 35.6811 + endloop + endfacet + facet normal 0.0838068 -0.804852 0.587528 + outer loop + vertex 487.422 64.2611 36.1122 + vertex 488.351 64.043 35.6811 + vertex 493.162 65.8142 37.4211 + endloop + endfacet + facet normal 0.0847424 -0.802914 0.590041 + outer loop + vertex 488.351 64.043 35.6811 + vertex 489.356 63.4992 34.7968 + vertex 495.261 65.9457 37.2777 + endloop + endfacet + facet normal 0.112757 -0.828475 0.548557 + outer loop + vertex 495.261 65.9457 37.2777 + vertex 489.356 63.4992 34.7968 + vertex 494.718 64.8605 35.7505 + endloop + endfacet + facet normal 0.0259932 -0.586973 0.809189 + outer loop + vertex 459.146 56.5989 30.6023 + vertex 459.49 56.0328 30.1806 + vertex 469.261 59.0579 32.061 + endloop + endfacet + facet normal 0.0645623 -0.668892 0.740551 + outer loop + vertex 469.261 59.0579 32.061 + vertex 459.49 56.0328 30.1806 + vertex 470.029 58.6167 31.5957 + endloop + endfacet + facet normal 0.0189256 -0.579949 0.814433 + outer loop + vertex 459.082 57.0225 30.9054 + vertex 459.146 56.5989 30.6023 + vertex 468.93 59.4196 32.3835 + endloop + endfacet + facet normal 0.0454158 -0.641248 0.765989 + outer loop + vertex 468.93 59.4196 32.3835 + vertex 459.146 56.5989 30.6023 + vertex 469.261 59.0579 32.061 + endloop + endfacet + facet normal 0.0237583 -0.653027 0.756962 + outer loop + vertex 468.93 59.4196 32.3835 + vertex 469.261 59.0579 32.061 + vertex 478.725 61.9417 34.2519 + endloop + endfacet + facet normal 0.0700785 -0.738999 0.670052 + outer loop + vertex 478.725 61.9417 34.2519 + vertex 469.261 59.0579 32.061 + vertex 479.368 61.6586 33.8723 + endloop + endfacet + facet normal 0.0462842 -0.685748 0.726366 + outer loop + vertex 469.261 59.0579 32.061 + vertex 470.029 58.6167 31.5957 + vertex 479.368 61.6586 33.8723 + endloop + endfacet + facet normal 0.0840575 -0.749521 0.656622 + outer loop + vertex 479.368 61.6586 33.8723 + vertex 470.029 58.6167 31.5957 + vertex 480.296 61.2224 33.2557 + endloop + endfacet + facet normal 0.0610566 -0.517521 0.853489 + outer loop + vertex 437.659 51.7337 28.842 + vertex 439.54 51.6396 28.6504 + vertex 449.128 54.3187 29.5889 + endloop + endfacet + facet normal 0.0551812 -0.500223 0.864136 + outer loop + vertex 449.128 54.3187 29.5889 + vertex 439.54 51.6396 28.6504 + vertex 449.025 53.6462 29.2062 + endloop + endfacet + facet normal 0.0302746 -0.423903 0.905202 + outer loop + vertex 439.386 52.5083 29.147 + vertex 437.659 51.7337 28.842 + vertex 449.067 54.704 29.8514 + endloop + endfacet + facet normal 0.0708098 -0.553886 0.829576 + outer loop + vertex 449.067 54.704 29.8514 + vertex 437.659 51.7337 28.842 + vertex 449.128 54.3187 29.5889 + endloop + endfacet + facet normal 0.0419433 -0.557953 0.828812 + outer loop + vertex 449.067 54.704 29.8514 + vertex 449.128 54.3187 29.5889 + vertex 459.082 57.0225 30.9054 + endloop + endfacet + facet normal 0.0486808 -0.576384 0.815727 + outer loop + vertex 459.082 57.0225 30.9054 + vertex 449.128 54.3187 29.5889 + vertex 459.146 56.5989 30.6023 + endloop + endfacet + facet normal 0.0254913 -0.497371 0.867164 + outer loop + vertex 449.128 54.3187 29.5889 + vertex 449.025 53.6462 29.2062 + vertex 459.146 56.5989 30.6023 + endloop + endfacet + facet normal 0.0550544 -0.574739 0.816483 + outer loop + vertex 459.146 56.5989 30.6023 + vertex 449.025 53.6462 29.2062 + vertex 459.49 56.0328 30.1806 + endloop + endfacet + facet normal 0.0676433 -0.455463 0.887681 + outer loop + vertex 439.54 51.6396 28.6504 + vertex 437.659 51.7337 28.842 + vertex 423.485 47.6475 27.8255 + endloop + endfacet + facet normal 0.070311 -0.497248 0.864755 + outer loop + vertex 439.386 52.5083 29.147 + vertex 423.32 48.659 28.2398 + vertex 437.659 51.7337 28.842 + endloop + endfacet + facet normal 0.0410642 -0.373029 0.926911 + outer loop + vertex 423.32 48.659 28.2398 + vertex 423.485 47.6475 27.8255 + vertex 437.659 51.7337 28.842 + endloop + endfacet + facet normal 0.0532583 -0.371102 0.927064 + outer loop + vertex 423.32 48.659 28.2398 + vertex 402.271 43.2734 27.2932 + vertex 423.485 47.6475 27.8255 + endloop + endfacet + facet normal -0.0458486 -0.355922 0.93339 + outer loop + vertex -422.542 48.681 28.2435 + vertex -422.859 47.8667 27.9174 + vertex -401.603 44.1527 27.5453 + endloop + endfacet + facet normal -0.0513915 -0.430698 0.901032 + outer loop + vertex -438.079 52.0699 28.9772 + vertex -436.673 51.3393 28.7082 + vertex -422.542 48.681 28.2435 + endloop + endfacet + facet normal -0.0517005 -0.412747 0.909377 + outer loop + vertex -438.89 51.1666 28.5038 + vertex -422.859 47.8667 27.9174 + vertex -436.673 51.3393 28.7082 + endloop + endfacet + facet normal -0.0368827 -0.359088 0.932575 + outer loop + vertex -422.859 47.8667 27.9174 + vertex -422.542 48.681 28.2435 + vertex -436.673 51.3393 28.7082 + endloop + endfacet + facet normal -0.0595759 -0.589948 0.805241 + outer loop + vertex -458.933 56.5588 30.5551 + vertex -459.837 56.1595 30.1957 + vertex -448.458 54.0884 29.5201 + endloop + endfacet + facet normal -0.0389041 -0.496567 0.867126 + outer loop + vertex -448.458 54.0884 29.5201 + vertex -459.837 56.1595 30.1957 + vertex -449.01 53.5826 29.2058 + endloop + endfacet + facet normal -0.0702338 -0.63952 0.76556 + outer loop + vertex -458.001 56.7366 30.789 + vertex -458.933 56.5588 30.5551 + vertex -447.548 54.2705 29.688 + endloop + endfacet + facet normal -0.0455899 -0.544241 0.837689 + outer loop + vertex -447.548 54.2705 29.688 + vertex -458.933 56.5588 30.5551 + vertex -448.458 54.0884 29.5201 + endloop + endfacet + facet normal -0.0551151 -0.513697 0.856199 + outer loop + vertex -447.548 54.2705 29.688 + vertex -448.458 54.0884 29.5201 + vertex -438.079 52.0699 28.9772 + endloop + endfacet + facet normal -0.0283474 -0.392979 0.91911 + outer loop + vertex -438.079 52.0699 28.9772 + vertex -448.458 54.0884 29.5201 + vertex -436.673 51.3393 28.7082 + endloop + endfacet + facet normal -0.0529627 -0.484884 0.872973 + outer loop + vertex -448.458 54.0884 29.5201 + vertex -449.01 53.5826 29.2058 + vertex -436.673 51.3393 28.7082 + endloop + endfacet + facet normal -0.0466766 -0.454037 0.88976 + outer loop + vertex -436.673 51.3393 28.7082 + vertex -449.01 53.5826 29.2058 + vertex -438.89 51.1666 28.5038 + endloop + endfacet + facet normal -0.0868553 -0.769227 0.633045 + outer loop + vertex -478.936 61.5965 33.6794 + vertex -477.907 60.793 32.8443 + vertex -468.994 59.0401 31.9372 + endloop + endfacet + facet normal -0.066734 -0.704802 0.706258 + outer loop + vertex -468.994 59.0401 31.9372 + vertex -477.907 60.793 32.8443 + vertex -469.933 58.658 31.4672 + endloop + endfacet + facet normal -0.0919663 -0.788998 0.607474 + outer loop + vertex -478.513 61.9648 34.2219 + vertex -478.936 61.5965 33.6794 + vertex -468.475 59.33 32.3195 + endloop + endfacet + facet normal -0.0745727 -0.743183 0.66492 + outer loop + vertex -468.475 59.33 32.3195 + vertex -478.936 61.5965 33.6794 + vertex -468.994 59.0401 31.9372 + endloop + endfacet + facet normal -0.0839802 -0.735727 0.672051 + outer loop + vertex -468.475 59.33 32.3195 + vertex -468.994 59.0401 31.9372 + vertex -458.001 56.7366 30.789 + endloop + endfacet + facet normal -0.0609493 -0.662823 0.746291 + outer loop + vertex -458.001 56.7366 30.789 + vertex -468.994 59.0401 31.9372 + vertex -458.933 56.5588 30.5551 + endloop + endfacet + facet normal -0.073768 -0.696615 0.713642 + outer loop + vertex -468.994 59.0401 31.9372 + vertex -469.933 58.658 31.4672 + vertex -458.933 56.5588 30.5551 + endloop + endfacet + facet normal -0.0493518 -0.604167 0.795328 + outer loop + vertex -458.933 56.5588 30.5551 + vertex -469.933 58.658 31.4672 + vertex -459.837 56.1595 30.1957 + endloop + endfacet + facet normal -0.0986323 -0.822737 0.5598 + outer loop + vertex -486.915 64.3013 36.1755 + vertex -487.815 64.0779 35.6886 + vertex -478.513 61.9648 34.2219 + endloop + endfacet + facet normal -0.0847445 -0.792369 0.604127 + outer loop + vertex -478.513 61.9648 34.2219 + vertex -487.815 64.0779 35.6886 + vertex -478.936 61.5965 33.6794 + endloop + endfacet + facet normal -0.0907049 -0.802275 0.590023 + outer loop + vertex -487.815 64.0779 35.6886 + vertex -487.946 63.1348 34.386 + vertex -478.936 61.5965 33.6794 + endloop + endfacet + facet normal -0.0808122 -0.766164 0.637544 + outer loop + vertex -478.936 61.5965 33.6794 + vertex -487.946 63.1348 34.386 + vertex -477.907 60.793 32.8443 + endloop + endfacet + facet normal -0.100509 -0.81852 0.565618 + outer loop + vertex -495.913 64.6951 35.2162 + vertex -495.01 65.5909 36.6731 + vertex -499.669 66.038 36.4921 + endloop + endfacet + facet normal 0.0766368 -0.749791 0.657222 + outer loop + vertex 480.296 61.2224 33.2557 + vertex 481.176 60.4783 32.3042 + vertex 489.356 63.4992 34.7968 + endloop + endfacet + facet normal 0.0890016 -0.782411 0.61637 + outer loop + vertex 494.718 64.8605 35.7505 + vertex 489.356 63.4992 34.7968 + vertex 491.293 62.4588 33.1963 + endloop + endfacet + facet normal 0.0787817 -0.715254 0.69441 + outer loop + vertex 480.635 59.1985 31.0473 + vertex 491.293 62.4588 33.1963 + vertex 481.176 60.4783 32.3042 + endloop + endfacet + facet normal 0.0971371 -0.776609 0.622449 + outer loop + vertex 489.356 63.4992 34.7968 + vertex 481.176 60.4783 32.3042 + vertex 491.293 62.4588 33.1963 + endloop + endfacet + facet normal 0.0555207 -0.610725 0.789894 + outer loop + vertex 460.742 55.5306 29.7453 + vertex 463.094 55.3434 29.4353 + vertex 471.175 58.1069 31.004 + endloop + endfacet + facet normal 0.0749789 -0.649001 0.757084 + outer loop + vertex 471.175 58.1069 31.004 + vertex 463.094 55.3434 29.4353 + vertex 471.6 57.1979 30.1826 + endloop + endfacet + facet normal 0.0388863 -0.597306 0.80107 + outer loop + vertex 459.49 56.0328 30.1806 + vertex 460.742 55.5306 29.7453 + vertex 470.029 58.6167 31.5957 + endloop + endfacet + facet normal 0.0782767 -0.675277 0.733399 + outer loop + vertex 470.029 58.6167 31.5957 + vertex 460.742 55.5306 29.7453 + vertex 471.175 58.1069 31.004 + endloop + endfacet + facet normal 0.0606066 -0.695144 0.716311 + outer loop + vertex 470.029 58.6167 31.5957 + vertex 471.175 58.1069 31.004 + vertex 480.296 61.2224 33.2557 + endloop + endfacet + facet normal 0.0897848 -0.742568 0.663726 + outer loop + vertex 480.296 61.2224 33.2557 + vertex 471.175 58.1069 31.004 + vertex 481.176 60.4783 32.3042 + endloop + endfacet + facet normal 0.0571713 -0.654475 0.753919 + outer loop + vertex 471.175 58.1069 31.004 + vertex 471.6 57.1979 30.1826 + vertex 481.176 60.4783 32.3042 + endloop + endfacet + facet normal 0.0927531 -0.71734 0.690522 + outer loop + vertex 481.176 60.4783 32.3042 + vertex 471.6 57.1979 30.1826 + vertex 480.635 59.1985 31.0473 + endloop + endfacet + facet normal 0.0351292 -0.380898 0.923949 + outer loop + vertex 436.833 50.1054 28.1002 + vertex 437.307 48.7568 27.5262 + vertex 449.302 52.7899 28.7328 + endloop + endfacet + facet normal 0.0522673 -0.425708 0.90335 + outer loop + vertex 449.302 52.7899 28.7328 + vertex 437.307 48.7568 27.5262 + vertex 452.172 52.3598 28.364 + endloop + endfacet + facet normal 0.0254969 -0.377011 0.925858 + outer loop + vertex 439.54 51.6396 28.6504 + vertex 436.833 50.1054 28.1002 + vertex 449.025 53.6462 29.2062 + endloop + endfacet + facet normal 0.0562793 -0.469099 0.88135 + outer loop + vertex 449.025 53.6462 29.2062 + vertex 436.833 50.1054 28.1002 + vertex 449.302 52.7899 28.7328 + endloop + endfacet + facet normal 0.0269939 -0.47701 0.878483 + outer loop + vertex 449.025 53.6462 29.2062 + vertex 449.302 52.7899 28.7328 + vertex 459.49 56.0328 30.1806 + endloop + endfacet + facet normal 0.0615319 -0.561665 0.825073 + outer loop + vertex 459.49 56.0328 30.1806 + vertex 449.302 52.7899 28.7328 + vertex 460.742 55.5306 29.7453 + endloop + endfacet + facet normal 0.0392595 -0.486362 0.872875 + outer loop + vertex 449.302 52.7899 28.7328 + vertex 452.172 52.3598 28.364 + vertex 460.742 55.5306 29.7453 + endloop + endfacet + facet normal 0.0668328 -0.54478 0.835911 + outer loop + vertex 460.742 55.5306 29.7453 + vertex 452.172 52.3598 28.364 + vertex 463.094 55.3434 29.4353 + endloop + endfacet + facet normal 0.0532433 -0.375161 0.925429 + outer loop + vertex 437.307 48.7568 27.5262 + vertex 436.833 50.1054 28.1002 + vertex 420.687 45.2771 27.0718 + endloop + endfacet + facet normal 0.0606506 -0.430045 0.900768 + outer loop + vertex 439.54 51.6396 28.6504 + vertex 423.485 47.6475 27.8255 + vertex 436.833 50.1054 28.1002 + endloop + endfacet + facet normal 0.0453752 -0.35095 0.935294 + outer loop + vertex 423.485 47.6475 27.8255 + vertex 420.687 45.2771 27.0718 + vertex 436.833 50.1054 28.1002 + endloop + endfacet + facet normal 0.0568373 -0.362837 0.930118 + outer loop + vertex 423.485 47.6475 27.8255 + vertex 401.901 41.5466 26.7645 + vertex 420.687 45.2771 27.0718 + endloop + endfacet + facet normal -0.0498642 -0.3633 0.930337 + outer loop + vertex -422.859 47.8667 27.9174 + vertex -423.66 46.3141 27.2682 + vertex -401.156 43.1257 27.2293 + endloop + endfacet + facet normal -0.0525172 -0.416409 0.907659 + outer loop + vertex -438.89 51.1666 28.5038 + vertex -436.71 49.8179 28.0112 + vertex -422.859 47.8667 27.9174 + endloop + endfacet + facet normal -0.0559016 -0.402003 0.91393 + outer loop + vertex -438.188 49.1233 27.6152 + vertex -423.66 46.3141 27.2682 + vertex -436.71 49.8179 28.0112 + endloop + endfacet + facet normal -0.0451895 -0.365457 0.929731 + outer loop + vertex -423.66 46.3141 27.2682 + vertex -422.859 47.8667 27.9174 + vertex -436.71 49.8179 28.0112 + endloop + endfacet + facet normal -0.0578734 -0.530084 0.845968 + outer loop + vertex -460.426 55.4352 29.67 + vertex -460.394 54.2876 28.9531 + vertex -449.003 52.6925 28.7329 + endloop + endfacet + facet normal -0.0451916 -0.44613 0.893826 + outer loop + vertex -449.003 52.6925 28.7329 + vertex -460.394 54.2876 28.9531 + vertex -448.091 51.3049 28.0864 + endloop + endfacet + facet normal -0.0564895 -0.555928 0.829309 + outer loop + vertex -459.837 56.1595 30.1957 + vertex -460.426 55.4352 29.67 + vertex -449.01 53.5826 29.2058 + endloop + endfacet + facet normal -0.0402322 -0.469016 0.882273 + outer loop + vertex -449.01 53.5826 29.2058 + vertex -460.426 55.4352 29.67 + vertex -449.003 52.6925 28.7329 + endloop + endfacet + facet normal -0.0507635 -0.468848 0.881819 + outer loop + vertex -449.01 53.5826 29.2058 + vertex -449.003 52.6925 28.7329 + vertex -438.89 51.1666 28.5038 + endloop + endfacet + facet normal -0.0393352 -0.398297 0.916413 + outer loop + vertex -438.89 51.1666 28.5038 + vertex -449.003 52.6925 28.7329 + vertex -436.71 49.8179 28.0112 + endloop + endfacet + facet normal -0.052911 -0.450081 0.891419 + outer loop + vertex -449.003 52.6925 28.7329 + vertex -448.091 51.3049 28.0864 + vertex -436.71 49.8179 28.0112 + endloop + endfacet + facet normal -0.0482398 -0.415189 0.908455 + outer loop + vertex -436.71 49.8179 28.0112 + vertex -448.091 51.3049 28.0864 + vertex -438.188 49.1233 27.6152 + endloop + endfacet + facet normal -0.0820045 -0.714086 0.695238 + outer loop + vertex -480.607 60.6128 32.3321 + vertex -480.541 59.5917 31.2912 + vertex -471.006 58.0824 30.8657 + endloop + endfacet + facet normal -0.0659737 -0.634029 0.77049 + outer loop + vertex -471.006 58.0824 30.8657 + vertex -480.541 59.5917 31.2912 + vertex -471.896 57.185 30.051 + endloop + endfacet + facet normal -0.0793549 -0.732504 0.676122 + outer loop + vertex -477.907 60.793 32.8443 + vertex -480.607 60.6128 32.3321 + vertex -469.933 58.658 31.4672 + endloop + endfacet + facet normal -0.0612821 -0.664279 0.744968 + outer loop + vertex -469.933 58.658 31.4672 + vertex -480.607 60.6128 32.3321 + vertex -471.006 58.0824 30.8657 + endloop + endfacet + facet normal -0.0681428 -0.657304 0.750538 + outer loop + vertex -469.933 58.658 31.4672 + vertex -471.006 58.0824 30.8657 + vertex -459.837 56.1595 30.1957 + endloop + endfacet + facet normal -0.0470823 -0.561349 0.826239 + outer loop + vertex -459.837 56.1595 30.1957 + vertex -471.006 58.0824 30.8657 + vertex -460.426 55.4352 29.67 + endloop + endfacet + facet normal -0.0706323 -0.631166 0.772425 + outer loop + vertex -471.006 58.0824 30.8657 + vertex -471.896 57.185 30.051 + vertex -460.426 55.4352 29.67 + endloop + endfacet + facet normal -0.0527665 -0.530131 0.846272 + outer loop + vertex -460.426 55.4352 29.67 + vertex -471.896 57.185 30.051 + vertex -460.394 54.2876 28.9531 + endloop + endfacet + facet normal -0.0968716 -0.814469 0.572063 + outer loop + vertex -499.669 66.038 36.4921 + vertex -499.207 64.4115 34.2547 + vertex -495.913 64.6951 35.2162 + endloop + endfacet + facet normal -0.108012 -0.790314 0.603106 + outer loop + vertex -495.913 64.6951 35.2162 + vertex -499.207 64.4115 34.2547 + vertex -491.507 62.008 32.4841 + endloop + endfacet + facet normal 0.0793392 -0.716313 0.693254 + outer loop + vertex 480.635 59.1985 31.0473 + vertex 484.121 58.7158 30.1496 + vertex 491.293 62.4588 33.1963 + endloop + endfacet + facet normal 0.104409 -0.682945 0.722969 + outer loop + vertex 485.998 57.5369 28.7649 + vertex 494.407 60.3919 30.2473 + vertex 484.121 58.7158 30.1496 + endloop + endfacet + facet normal 0.116269 -0.751444 0.649472 + outer loop + vertex 494.407 60.3919 30.2473 + vertex 491.293 62.4588 33.1963 + vertex 484.121 58.7158 30.1496 + endloop + endfacet + facet normal 0.0491464 -0.476822 0.877625 + outer loop + vertex 460.322 53.4605 28.4937 + vertex 460.081 51.4179 27.3974 + vertex 472.375 55.9966 29.1966 + endloop + endfacet + facet normal 0.0925317 -0.569424 0.816819 + outer loop + vertex 472.375 55.9966 29.1966 + vertex 460.081 51.4179 27.3974 + vertex 475.391 54.9854 28.15 + endloop + endfacet + facet normal 0.0273545 -0.479029 0.877373 + outer loop + vertex 463.094 55.3434 29.4353 + vertex 460.322 53.4605 28.4937 + vertex 471.6 57.1979 30.1826 + endloop + endfacet + facet normal 0.0800834 -0.601018 0.795213 + outer loop + vertex 471.6 57.1979 30.1826 + vertex 460.322 53.4605 28.4937 + vertex 472.375 55.9966 29.1966 + endloop + endfacet + facet normal 0.059479 -0.610103 0.790087 + outer loop + vertex 471.6 57.1979 30.1826 + vertex 472.375 55.9966 29.1966 + vertex 480.635 59.1985 31.0473 + endloop + endfacet + facet normal 0.0960185 -0.672075 0.734231 + outer loop + vertex 480.635 59.1985 31.0473 + vertex 472.375 55.9966 29.1966 + vertex 484.121 58.7158 30.1496 + endloop + endfacet + facet normal 0.0745922 -0.601071 0.795707 + outer loop + vertex 472.375 55.9966 29.1966 + vertex 475.391 54.9854 28.15 + vertex 484.121 58.7158 30.1496 + endloop + endfacet + facet normal 0.118891 -0.670678 0.732159 + outer loop + vertex 484.121 58.7158 30.1496 + vertex 475.391 54.9854 28.15 + vertex 485.998 57.5369 28.7649 + endloop + endfacet + facet normal 0.0552981 -0.510519 0.858086 + outer loop + vertex 463.094 55.3434 29.4353 + vertex 452.172 52.3598 28.364 + vertex 460.322 53.4605 28.4937 + endloop + endfacet + facet normal 0.0723404 -0.478274 0.875226 + outer loop + vertex 460.081 51.4179 27.3974 + vertex 460.322 53.4605 28.4937 + vertex 442.499 47.9975 26.9815 + endloop + endfacet + facet normal 0.0408074 -0.382964 0.922862 + outer loop + vertex 437.307 48.7568 27.5262 + vertex 442.499 47.9975 26.9815 + vertex 452.172 52.3598 28.364 + endloop + endfacet + facet normal 0.0355953 -0.372791 0.927232 + outer loop + vertex 460.322 53.4605 28.4937 + vertex 452.172 52.3598 28.364 + vertex 442.499 47.9975 26.9815 + endloop + endfacet + facet normal 0.0485316 -0.341467 0.93864 + outer loop + vertex 437.307 48.7568 27.5262 + vertex 421.295 43.2573 26.3534 + vertex 442.499 47.9975 26.9815 + endloop + endfacet + facet normal -0.0527584 -0.386589 0.920742 + outer loop + vertex -438.188 49.1233 27.6152 + vertex -444.945 48.9213 27.1433 + vertex -423.66 46.3141 27.2682 + endloop + endfacet + facet normal -0.0621357 -0.506234 0.860155 + outer loop + vertex -460.394 54.2876 28.9531 + vertex -459.5 52.7068 28.0873 + vertex -448.091 51.3049 28.0864 + endloop + endfacet + facet normal -0.0504659 -0.424351 0.90409 + outer loop + vertex -438.188 49.1233 27.6152 + vertex -448.091 51.3049 28.0864 + vertex -444.945 48.9213 27.1433 + endloop + endfacet + facet normal -0.074622 -0.501836 0.861738 + outer loop + vertex -460.026 51.6468 27.4245 + vertex -444.945 48.9213 27.1433 + vertex -459.5 52.7068 28.0873 + endloop + endfacet + facet normal -0.0523205 -0.42638 0.90303 + outer loop + vertex -448.091 51.3049 28.0864 + vertex -459.5 52.7068 28.0873 + vertex -444.945 48.9213 27.1433 + endloop + endfacet + facet normal -0.0950676 -0.660064 0.74517 + outer loop + vertex -483.395 58.8501 30.2513 + vertex -483.481 57.0769 28.6697 + vertex -472.131 55.8303 29.0136 + endloop + endfacet + facet normal -0.0874094 -0.570648 0.816529 + outer loop + vertex -472.131 55.8303 29.0136 + vertex -483.481 57.0769 28.6697 + vertex -470.756 53.9706 27.8611 + endloop + endfacet + facet normal -0.0863706 -0.683675 0.724658 + outer loop + vertex -480.541 59.5917 31.2912 + vertex -483.395 58.8501 30.2513 + vertex -471.896 57.185 30.051 + endloop + endfacet + facet normal -0.0727491 -0.598413 0.797878 + outer loop + vertex -471.896 57.185 30.051 + vertex -483.395 58.8501 30.2513 + vertex -472.131 55.8303 29.0136 + endloop + endfacet + facet normal -0.0745128 -0.59814 0.79792 + outer loop + vertex -471.896 57.185 30.051 + vertex -472.131 55.8303 29.0136 + vertex -460.394 54.2876 28.9531 + endloop + endfacet + facet normal -0.062111 -0.506224 0.860163 + outer loop + vertex -460.394 54.2876 28.9531 + vertex -472.131 55.8303 29.0136 + vertex -459.5 52.7068 28.0873 + endloop + endfacet + facet normal -0.0801691 -0.567229 0.819649 + outer loop + vertex -472.131 55.8303 29.0136 + vertex -470.756 53.9706 27.8611 + vertex -459.5 52.7068 28.0873 + endloop + endfacet + facet normal -0.0737106 -0.502203 0.861603 + outer loop + vertex -459.5 52.7068 28.0873 + vertex -470.756 53.9706 27.8611 + vertex -460.026 51.6468 27.4245 + endloop + endfacet + facet normal -0.104105 -0.784168 0.611753 + outer loop + vertex -499.207 64.4115 34.2547 + vertex -500.731 62.179 31.1337 + vertex -491.507 62.008 32.4841 + endloop + endfacet + facet normal -0.111582 -0.73477 0.669076 + outer loop + vertex -491.507 62.008 32.4841 + vertex -500.731 62.179 31.1337 + vertex -494.601 59.756 29.4951 + endloop + endfacet + facet normal 0.111193 -0.618453 0.777915 + outer loop + vertex 480.637 54.8526 27.3971 + vertex 490.345 57.1735 27.8547 + vertex 485.998 57.5369 28.7649 + endloop + endfacet + facet normal 0.133332 -0.694182 0.707342 + outer loop + vertex 498.754 59.0275 28.089 + vertex 494.407 60.3919 30.2473 + vertex 490.345 57.1735 27.8547 + endloop + endfacet + facet normal 0.0979595 -0.670438 0.73547 + outer loop + vertex 494.407 60.3919 30.2473 + vertex 485.998 57.5369 28.7649 + vertex 490.345 57.1735 27.8547 + endloop + endfacet + facet normal 0.0986125 -0.601061 0.793096 + outer loop + vertex 485.998 57.5369 28.7649 + vertex 475.391 54.9854 28.15 + vertex 480.637 54.8526 27.3971 + endloop + endfacet + facet normal 0.0683134 -0.477922 0.875742 + outer loop + vertex 460.081 51.4179 27.3974 + vertex 465.341 50.0635 26.248 + vertex 475.391 54.9854 28.15 + endloop + endfacet + facet normal 0.106208 -0.539621 0.835182 + outer loop + vertex 465.341 50.0635 26.248 + vertex 480.637 54.8526 27.3971 + vertex 475.391 54.9854 28.15 + endloop + endfacet + facet normal 0.0508601 -0.374037 0.926018 + outer loop + vertex 442.499 47.9975 26.9815 + vertex 443.233 45.1594 25.7948 + vertex 460.081 51.4179 27.3974 + endloop + endfacet + facet normal 0.0803897 -0.44482 0.892005 + outer loop + vertex 460.081 51.4179 27.3974 + vertex 443.233 45.1594 25.7948 + vertex 465.341 50.0635 26.248 + endloop + endfacet + facet normal 0.0643025 -0.370761 0.9265 + outer loop + vertex 442.499 47.9975 26.9815 + vertex 422.546 40.7962 25.4845 + vertex 443.233 45.1594 25.7948 + endloop + endfacet + facet normal -0.0739077 -0.498112 0.863957 + outer loop + vertex -460.026 51.6468 27.4245 + vertex -464.73 50.9506 26.6207 + vertex -444.945 48.9213 27.1433 + endloop + endfacet + facet normal -0.0733134 -0.500555 0.862595 + outer loop + vertex -460.026 51.6468 27.4245 + vertex -470.756 53.9706 27.8611 + vertex -464.73 50.9506 26.6207 + endloop + endfacet + facet normal -0.0969892 -0.603385 0.79153 + outer loop + vertex -483.481 57.0769 28.6697 + vertex -481.934 54.9868 27.266 + vertex -470.756 53.9706 27.8611 + endloop + endfacet + facet normal -0.0931432 -0.531604 0.841856 + outer loop + vertex -481.934 54.9868 27.266 + vertex -464.73 50.9506 26.6207 + vertex -470.756 53.9706 27.8611 + endloop + endfacet + facet normal -0.153556 -0.725431 0.670948 + outer loop + vertex -504.176 60.3871 28.4078 + vertex -502.596 59.8707 28.211 + vertex -500.731 62.179 31.1337 + endloop + endfacet + facet normal -0.125593 -0.681294 0.721155 + outer loop + vertex -499.569 58.4364 27.3833 + vertex -494.601 59.756 29.4951 + vertex -502.596 59.8707 28.211 + endloop + endfacet + facet normal -0.116698 -0.741821 0.660366 + outer loop + vertex -494.601 59.756 29.4951 + vertex -500.731 62.179 31.1337 + vertex -502.596 59.8707 28.211 + endloop + endfacet + facet normal 0.128346 -0.555814 0.821339 + outer loop + vertex 500.915 57.5424 26.4517 + vertex 502.016 55.9528 25.204 + vertex 504.853 58.0385 26.1721 + endloop + endfacet + facet normal 0.130578 -0.557999 0.819504 + outer loop + vertex 504.853 58.0385 26.1721 + vertex 502.016 55.9528 25.204 + vertex 505.429 56.5289 25.0524 + endloop + endfacet + facet normal 0.137579 -0.636496 0.75891 + outer loop + vertex 498.754 59.0275 28.089 + vertex 500.915 57.5424 26.4517 + vertex 503.546 59.472 27.5931 + endloop + endfacet + facet normal 0.13392 -0.633415 0.762136 + outer loop + vertex 503.546 59.472 27.5931 + vertex 500.915 57.5424 26.4517 + vertex 504.853 58.0385 26.1721 + endloop + endfacet + facet normal 0.103209 -0.512091 0.852708 + outer loop + vertex 481.517 53.2182 26.2483 + vertex 485.33 52.4095 25.3011 + vertex 493.333 55.9809 26.4773 + endloop + endfacet + facet normal 0.116573 -0.536475 0.835826 + outer loop + vertex 493.333 55.9809 26.4773 + vertex 485.33 52.4095 25.3011 + vertex 494.79 54.3891 25.2523 + endloop + endfacet + facet normal 0.0896559 -0.539993 0.836881 + outer loop + vertex 480.637 54.8526 27.3971 + vertex 481.517 53.2182 26.2483 + vertex 490.345 57.1735 27.8547 + endloop + endfacet + facet normal 0.124928 -0.599809 0.79033 + outer loop + vertex 490.345 57.1735 27.8547 + vertex 481.517 53.2182 26.2483 + vertex 493.333 55.9809 26.4773 + endloop + endfacet + facet normal 0.113935 -0.615373 0.779958 + outer loop + vertex 490.345 57.1735 27.8547 + vertex 493.333 55.9809 26.4773 + vertex 498.754 59.0275 28.089 + endloop + endfacet + facet normal 0.134222 -0.639374 0.75709 + outer loop + vertex 498.754 59.0275 28.089 + vertex 493.333 55.9809 26.4773 + vertex 500.915 57.5424 26.4517 + endloop + endfacet + facet normal 0.113699 -0.538438 0.834959 + outer loop + vertex 493.333 55.9809 26.4773 + vertex 494.79 54.3891 25.2523 + vertex 500.915 57.5424 26.4517 + endloop + endfacet + facet normal 0.126036 -0.557042 0.820865 + outer loop + vertex 500.915 57.5424 26.4517 + vertex 494.79 54.3891 25.2523 + vertex 502.016 55.9528 25.204 + endloop + endfacet + facet normal 0.11342 -0.482473 0.868536 + outer loop + vertex 485.33 52.4095 25.3011 + vertex 481.517 53.2182 26.2483 + vertex 468.001 47.275 24.7119 + endloop + endfacet + facet normal 0.104094 -0.533825 0.839164 + outer loop + vertex 480.637 54.8526 27.3971 + vertex 465.341 50.0635 26.248 + vertex 481.517 53.2182 26.2483 + endloop + endfacet + facet normal 0.081864 -0.419848 0.903895 + outer loop + vertex 465.341 50.0635 26.248 + vertex 468.001 47.275 24.7119 + vertex 481.517 53.2182 26.2483 + endloop + endfacet + facet normal 0.0580253 -0.348035 0.935684 + outer loop + vertex 443.233 45.1594 25.7948 + vertex 445.012 42.3002 24.621 + vertex 465.341 50.0635 26.248 + endloop + endfacet + facet normal 0.0864793 -0.416151 0.905174 + outer loop + vertex 465.341 50.0635 26.248 + vertex 445.012 42.3002 24.621 + vertex 468.001 47.275 24.7119 + endloop + endfacet + facet normal 0.0662131 -0.343418 0.936846 + outer loop + vertex 443.233 45.1594 25.7948 + vertex 423.295 37.6988 24.4692 + vertex 445.012 42.3002 24.621 + endloop + endfacet + facet normal -0.0951003 -0.539143 0.836828 + outer loop + vertex -481.934 54.9868 27.266 + vertex -482.146 52.9277 25.9153 + vertex -464.73 50.9506 26.6207 + endloop + endfacet + facet normal -0.0979784 -0.466971 0.878828 + outer loop + vertex -484.967 51.5735 24.8812 + vertex -467.684 48.2303 25.0317 + vertex -482.146 52.9277 25.9153 + endloop + endfacet + facet normal -0.112183 -0.616662 0.779194 + outer loop + vertex -491.888 57.5954 27.8973 + vertex -493.342 56.1996 26.5834 + vertex -481.934 54.9868 27.266 + endloop + endfacet + facet normal -0.107197 -0.537595 0.836361 + outer loop + vertex -481.934 54.9868 27.266 + vertex -493.342 56.1996 26.5834 + vertex -482.146 52.9277 25.9153 + endloop + endfacet + facet normal -0.107077 -0.537234 0.836609 + outer loop + vertex -493.342 56.1996 26.5834 + vertex -495.458 54.463 25.1974 + vertex -482.146 52.9277 25.9153 + endloop + endfacet + facet normal -0.100848 -0.462535 0.880847 + outer loop + vertex -482.146 52.9277 25.9153 + vertex -495.458 54.463 25.1974 + vertex -484.967 51.5735 24.8812 + endloop + endfacet + facet normal -0.118103 -0.607091 0.785806 + outer loop + vertex -505.364 58.7765 26.6572 + vertex -506.25 57.2172 25.3194 + vertex -504.629 58.2229 26.3399 + endloop + endfacet + facet normal -0.185376 -0.536645 0.823194 + outer loop + vertex -504.629 58.2229 26.3399 + vertex -506.25 57.2172 25.3194 + vertex -505.78 56.6818 25.0761 + endloop + endfacet + facet normal -0.133594 -0.682505 0.718567 + outer loop + vertex -504.176 60.3871 28.4078 + vertex -505.364 58.7765 26.6572 + vertex -502.596 59.8707 28.211 + endloop + endfacet + facet normal -0.163893 -0.645179 0.746246 + outer loop + vertex -502.596 59.8707 28.211 + vertex -505.364 58.7765 26.6572 + vertex -504.629 58.2229 26.3399 + endloop + endfacet + facet normal -0.121385 -0.675798 0.727023 + outer loop + vertex -502.596 59.8707 28.211 + vertex -504.629 58.2229 26.3399 + vertex -499.569 58.4364 27.3833 + endloop + endfacet + facet normal -0.135967 -0.606294 0.783531 + outer loop + vertex -499.569 58.4364 27.3833 + vertex -504.629 58.2229 26.3399 + vertex -501.639 56.9495 25.8734 + endloop + endfacet + facet normal -0.118666 -0.575148 0.809397 + outer loop + vertex -504.629 58.2229 26.3399 + vertex -505.78 56.6818 25.0761 + vertex -501.639 56.9495 25.8734 + endloop + endfacet + facet normal -0.131575 -0.505159 0.852937 + outer loop + vertex -501.639 56.9495 25.8734 + vertex -505.78 56.6818 25.0761 + vertex -503.242 55.6375 24.8491 + endloop + endfacet + facet normal -0.409663 -0.546376 0.730513 + outer loop + vertex -504.513 60.146 28.0383 + vertex -505.036 58.8712 26.7915 + vertex -504.176 60.3871 28.4078 + endloop + endfacet + facet normal 0.0861032 0.703394 -0.705566 + outer loop + vertex -504.176 60.3871 28.4078 + vertex -505.036 58.8712 26.7915 + vertex -505.364 58.7765 26.6572 + endloop + endfacet + facet normal 0.139922 0.616089 -0.775149 + outer loop + vertex -505.036 58.8712 26.7915 + vertex -505.744 57.5523 25.6156 + vertex -505.364 58.7765 26.6572 + endloop + endfacet + facet normal 0.0211228 0.644062 -0.764682 + outer loop + vertex -505.364 58.7765 26.6572 + vertex -505.744 57.5523 25.6156 + vertex -506.25 57.2172 25.3194 + endloop + endfacet + facet normal 0.115717 -0.452994 0.883972 + outer loop + vertex 502.016 55.9528 25.204 + vertex 502.813 54.3019 24.2537 + vertex 505.429 56.5289 25.0524 + endloop + endfacet + facet normal 0.117225 -0.45443 0.883035 + outer loop + vertex 505.429 56.5289 25.0524 + vertex 502.813 54.3019 24.2537 + vertex 506.158 55.279 24.3123 + endloop + endfacet + facet normal 0.0916048 -0.41546 0.904987 + outer loop + vertex 485.33 52.4095 25.3011 + vertex 483.095 49.7144 24.2901 + vertex 494.79 54.3891 25.2523 + endloop + endfacet + facet normal 0.0999766 -0.434383 0.895163 + outer loop + vertex 494.79 54.3891 25.2523 + vertex 483.095 49.7144 24.2901 + vertex 495.05 52.3356 24.2267 + endloop + endfacet + facet normal 0.0999887 -0.434381 0.895162 + outer loop + vertex 494.79 54.3891 25.2523 + vertex 495.05 52.3356 24.2267 + vertex 502.016 55.9528 25.204 + endloop + endfacet + facet normal 0.112083 -0.454556 0.883638 + outer loop + vertex 502.016 55.9528 25.204 + vertex 495.05 52.3356 24.2267 + vertex 502.813 54.3019 24.2537 + endloop + endfacet + facet normal 0.0925227 -0.41608 0.904609 + outer loop + vertex 485.33 52.4095 25.3011 + vertex 468.001 47.275 24.7119 + vertex 483.095 49.7144 24.2901 + endloop + endfacet + facet normal -0.0814819 -0.379769 0.921486 + outer loop + vertex -484.967 51.5735 24.8812 + vertex -482.609 49.1371 24.0856 + vertex -467.684 48.2303 25.0317 + endloop + endfacet + facet normal -0.0898301 -0.424724 0.900855 + outer loop + vertex -495.458 54.463 25.1974 + vertex -492.781 52.0239 24.3143 + vertex -484.967 51.5735 24.8812 + endloop + endfacet + facet normal -0.0888533 -0.385853 0.918272 + outer loop + vertex -484.967 51.5735 24.8812 + vertex -492.781 52.0239 24.3143 + vertex -482.609 49.1371 24.0856 + endloop + endfacet + facet normal -0.101862 -0.484244 0.868983 + outer loop + vertex -506.25 57.2172 25.3194 + vertex -506.726 55.5448 24.3316 + vertex -505.78 56.6818 25.0761 + endloop + endfacet + facet normal -0.181825 -0.428292 0.885159 + outer loop + vertex -505.78 56.6818 25.0761 + vertex -506.726 55.5448 24.3316 + vertex -505.89 54.8194 24.1524 + endloop + endfacet + facet normal -0.100027 -0.437344 0.893714 + outer loop + vertex -505.78 56.6818 25.0761 + vertex -505.89 54.8194 24.1524 + vertex -503.242 55.6375 24.8491 + endloop + endfacet + facet normal -0.111127 -0.410924 0.904872 + outer loop + vertex -503.242 55.6375 24.8491 + vertex -505.89 54.8194 24.1524 + vertex -501.071 53.3366 24.0708 + endloop + endfacet + facet normal 0.162344 0.50452 -0.848 + outer loop + vertex -505.744 57.5523 25.6156 + vertex -506.076 56.0029 24.6302 + vertex -506.25 57.2172 25.3194 + endloop + endfacet + facet normal 0.0467259 0.498113 -0.865852 + outer loop + vertex -506.25 57.2172 25.3194 + vertex -506.076 56.0029 24.6302 + vertex -506.726 55.5448 24.3316 + endloop + endfacet + facet normal 0.0768818 -0.326498 0.942066 + outer loop + vertex 486.269 24.9811 17.4299 + vertex 495.592 27.6126 17.5811 + vertex 489.333 28.8599 18.5242 + endloop + endfacet + facet normal 0.0798818 -0.328684 0.941056 + outer loop + vertex 503.689 29.0724 17.4036 + vertex 501.75 31.5916 18.4482 + vertex 495.592 27.6126 17.5811 + endloop + endfacet + facet normal 0.0772633 -0.324961 0.942566 + outer loop + vertex 501.75 31.5916 18.4482 + vertex 489.333 28.8599 18.5242 + vertex 495.592 27.6126 17.5811 + endloop + endfacet + facet normal 0.0744215 -0.321812 0.943874 + outer loop + vertex 465.552 20.0477 17.4166 + vertex 476.699 23.0845 17.5731 + vertex 470.997 24.5992 18.5392 + endloop + endfacet + facet normal 0.0790983 -0.328045 0.941345 + outer loop + vertex 486.269 24.9811 17.4299 + vertex 489.333 28.8599 18.5242 + vertex 476.699 23.0845 17.5731 + endloop + endfacet + facet normal 0.0750742 -0.319765 0.944518 + outer loop + vertex 489.333 28.8599 18.5242 + vertex 470.997 24.5992 18.5392 + vertex 476.699 23.0845 17.5731 + endloop + endfacet + facet normal 0.0716868 -0.32138 0.944233 + outer loop + vertex 444.032 15.1512 17.4116 + vertex 455.552 18.1628 17.562 + vertex 450.121 19.8126 18.5359 + endloop + endfacet + facet normal 0.0743653 -0.321751 0.9439 + outer loop + vertex 465.552 20.0477 17.4166 + vertex 470.997 24.5992 18.5392 + vertex 455.552 18.1628 17.562 + endloop + endfacet + facet normal 0.0728175 -0.318236 0.945211 + outer loop + vertex 470.997 24.5992 18.5392 + vertex 450.121 19.8126 18.5359 + vertex 455.552 18.1628 17.562 + endloop + endfacet + facet normal 0.0685918 -0.323523 0.943731 + outer loop + vertex 422.681 10.5179 17.4069 + vertex 434.032 13.365 17.5579 + vertex 428.556 15.029 18.5263 + endloop + endfacet + facet normal 0.0710977 -0.320679 0.944516 + outer loop + vertex 444.032 15.1512 17.4116 + vertex 450.121 19.8126 18.5359 + vertex 434.032 13.365 17.5579 + endloop + endfacet + facet normal 0.0702952 -0.318783 0.945217 + outer loop + vertex 450.121 19.8126 18.5359 + vertex 428.556 15.029 18.5263 + vertex 434.032 13.365 17.5579 + endloop + endfacet + facet normal 0.0659631 -0.326704 0.942822 + outer loop + vertex 401.867 6.23075 17.4081 + vertex 412.929 8.88724 17.5547 + vertex 407.221 10.5286 18.5228 + endloop + endfacet + facet normal 0.0683538 -0.323241 0.943845 + outer loop + vertex 422.681 10.5179 17.4069 + vertex 428.556 15.029 18.5263 + vertex 412.929 8.88724 17.5547 + endloop + endfacet + facet normal 0.0676909 -0.321648 0.944437 + outer loop + vertex 428.556 15.029 18.5263 + vertex 407.221 10.5286 18.5228 + vertex 412.929 8.88724 17.5547 + endloop + endfacet + facet normal 0.062852 -0.328158 0.942529 + outer loop + vertex 380.716 2.10553 17.4097 + vertex 392.006 4.6853 17.555 + vertex 386.007 6.31119 18.5211 + endloop + endfacet + facet normal 0.0651065 -0.325739 0.943215 + outer loop + vertex 401.867 6.23075 17.4081 + vertex 407.221 10.5286 18.5228 + vertex 392.006 4.6853 17.555 + endloop + endfacet + facet normal 0.064285 -0.323724 0.943965 + outer loop + vertex 407.221 10.5286 18.5228 + vertex 386.007 6.31119 18.5211 + vertex 392.006 4.6853 17.555 + endloop + endfacet + facet normal 0.0596313 -0.329351 0.942323 + outer loop + vertex 359.285 -1.87262 17.4075 + vertex 370.622 0.608308 17.5573 + vertex 364.839 2.32503 18.5232 + endloop + endfacet + facet normal 0.0623776 -0.327619 0.942748 + outer loop + vertex 380.716 2.10553 17.4097 + vertex 386.007 6.31119 18.5211 + vertex 370.622 0.608308 17.5573 + endloop + endfacet + facet normal 0.0612469 -0.324749 0.943815 + outer loop + vertex 386.007 6.31119 18.5211 + vertex 364.839 2.32503 18.5232 + vertex 370.622 0.608308 17.5573 + endloop + endfacet + facet normal 0.0564438 -0.328041 0.942976 + outer loop + vertex 338.599 -5.53393 17.409 + vertex 349.534 -3.22323 17.5583 + vertex 344.036 -1.39791 18.5225 + endloop + endfacet + facet normal 0.0602945 -0.330144 0.942003 + outer loop + vertex 359.285 -1.87262 17.4075 + vertex 364.839 2.32503 18.5232 + vertex 349.534 -3.22323 17.5583 + endloop + endfacet + facet normal 0.0579683 -0.324116 0.94424 + outer loop + vertex 364.839 2.32503 18.5232 + vertex 344.036 -1.39791 18.5225 + vertex 349.534 -3.22323 17.5583 + endloop + endfacet + facet normal 0.0532156 -0.328161 0.943122 + outer loop + vertex 318.054 -8.96954 17.4064 + vertex 329.031 -6.75748 17.5567 + vertex 323.327 -4.9113 18.521 + endloop + endfacet + facet normal 0.0565156 -0.328126 0.942942 + outer loop + vertex 338.599 -5.53393 17.409 + vertex 344.036 -1.39791 18.5225 + vertex 329.031 -6.75748 17.5567 + endloop + endfacet + facet normal 0.0548667 -0.323797 0.944534 + outer loop + vertex 344.036 -1.39791 18.5225 + vertex 323.327 -4.9113 18.521 + vertex 329.031 -6.75748 17.5567 + endloop + endfacet + facet normal 0.0501117 -0.327477 0.943529 + outer loop + vertex 296.88 -12.3115 17.4079 + vertex 308.186 -10.1521 17.5568 + vertex 302.304 -8.27867 18.5195 + endloop + endfacet + facet normal 0.0537801 -0.328822 0.942859 + outer loop + vertex 318.054 -8.96954 17.4064 + vertex 323.327 -4.9113 18.521 + vertex 308.186 -10.1521 17.5568 + endloop + endfacet + facet normal 0.0517019 -0.323197 0.944918 + outer loop + vertex 323.327 -4.9113 18.521 + vertex 302.304 -8.27867 18.5195 + vertex 308.186 -10.1521 17.5568 + endloop + endfacet + facet normal 0.0471765 -0.326788 0.943919 + outer loop + vertex 275.495 -15.479 17.4096 + vertex 286.845 -13.4204 17.555 + vertex 281.1 -11.4709 18.5171 + endloop + endfacet + facet normal 0.0500114 -0.327355 0.943577 + outer loop + vertex 296.88 -12.3115 17.4079 + vertex 302.304 -8.27867 18.5195 + vertex 286.845 -13.4204 17.555 + endloop + endfacet + facet normal 0.0485605 -0.323271 0.945059 + outer loop + vertex 302.304 -8.27867 18.5195 + vertex 281.1 -11.4709 18.5171 + vertex 286.845 -13.4204 17.555 + endloop + endfacet + facet normal 0.0440836 -0.327545 0.943807 + outer loop + vertex 254.425 -18.3897 17.4095 + vertex 265.608 -16.4665 17.5546 + vertex 259.988 -14.4447 18.5187 + endloop + endfacet + facet normal 0.0463866 -0.32579 0.944304 + outer loop + vertex 275.495 -15.479 17.4096 + vertex 281.1 -11.4709 18.5171 + vertex 265.608 -16.4665 17.5546 + endloop + endfacet + facet normal 0.045673 -0.32372 0.94505 + outer loop + vertex 281.1 -11.4709 18.5171 + vertex 259.988 -14.4447 18.5187 + vertex 265.608 -16.4665 17.5546 + endloop + endfacet + facet normal 0.040039 -0.327404 0.944036 + outer loop + vertex 233.461 -21.0657 17.4067 + vertex 244.628 -19.2663 17.5571 + vertex 238.954 -17.1913 18.5174 + endloop + endfacet + facet normal 0.0434645 -0.326757 0.944108 + outer loop + vertex 254.425 -18.3897 17.4095 + vertex 259.988 -14.4447 18.5187 + vertex 244.628 -19.2663 17.5571 + endloop + endfacet + facet normal 0.0420638 -0.322593 0.945603 + outer loop + vertex 259.988 -14.4447 18.5187 + vertex 238.954 -17.1913 18.5174 + vertex 244.628 -19.2663 17.5571 + endloop + endfacet + facet normal 0.0372942 -0.32711 0.94425 + outer loop + vertex 212.344 -23.5483 17.4112 + vertex 223.59 -21.8504 17.5552 + vertex 217.854 -19.727 18.5173 + endloop + endfacet + facet normal 0.0402509 -0.327675 0.943933 + outer loop + vertex 233.461 -21.0657 17.4067 + vertex 238.954 -17.1913 18.5174 + vertex 223.59 -21.8504 17.5552 + endloop + endfacet + facet normal 0.0388642 -0.323417 0.945458 + outer loop + vertex 238.954 -17.1913 18.5174 + vertex 217.854 -19.727 18.5173 + vertex 223.59 -21.8504 17.5552 + endloop + endfacet + facet normal 0.033612 -0.327812 0.944145 + outer loop + vertex 191.088 -25.8144 17.4105 + vertex 202.408 -24.2328 17.5566 + vertex 196.626 -22.0511 18.52 + endloop + endfacet + facet normal 0.0362765 -0.325787 0.944747 + outer loop + vertex 212.344 -23.5483 17.4112 + vertex 217.854 -19.727 18.5173 + vertex 202.408 -24.2328 17.5566 + endloop + endfacet + facet normal 0.0355236 -0.323388 0.9456 + outer loop + vertex 217.854 -19.727 18.5173 + vertex 196.626 -22.0511 18.52 + vertex 202.408 -24.2328 17.5566 + endloop + endfacet + facet normal 0.0299113 -0.327121 0.944509 + outer loop + vertex 169.598 -27.865 17.4118 + vertex 181.055 -26.3981 17.557 + vertex 175.214 -24.1542 18.5191 + endloop + endfacet + facet normal 0.0327998 -0.326735 0.944547 + outer loop + vertex 191.088 -25.8144 17.4105 + vertex 196.626 -22.0511 18.52 + vertex 181.055 -26.3981 17.557 + endloop + endfacet + facet normal 0.0316929 -0.323058 0.945848 + outer loop + vertex 196.626 -22.0511 18.52 + vertex 175.214 -24.1542 18.5191 + vertex 181.055 -26.3981 17.557 + endloop + endfacet + facet normal 0.0260068 -0.326741 0.944756 + outer loop + vertex 147.943 -29.6812 17.4119 + vertex 159.462 -28.342 17.558 + vertex 153.665 -26.0259 18.5186 + endloop + endfacet + facet normal 0.0289641 -0.32583 0.944985 + outer loop + vertex 169.598 -27.865 17.4118 + vertex 175.214 -24.1542 18.5191 + vertex 159.462 -28.342 17.558 + endloop + endfacet + facet normal 0.0279788 -0.3224 0.94619 + outer loop + vertex 175.214 -24.1542 18.5191 + vertex 153.665 -26.0259 18.5186 + vertex 159.462 -28.342 17.558 + endloop + endfacet + facet normal 0.0221815 -0.327598 0.944557 + outer loop + vertex 126.452 -31.2288 17.4109 + vertex 137.87 -30.034 17.5571 + vertex 132.171 -27.6438 18.5199 + endloop + endfacet + facet normal 0.0250199 -0.325349 0.945263 + outer loop + vertex 147.943 -29.6812 17.4119 + vertex 153.665 -26.0259 18.5186 + vertex 137.87 -30.034 17.5571 + endloop + endfacet + facet normal 0.0243718 -0.322993 0.946087 + outer loop + vertex 153.665 -26.0259 18.5186 + vertex 132.171 -27.6438 18.5199 + vertex 137.87 -30.034 17.5571 + endloop + endfacet + facet normal 0.0179256 -0.328642 0.944285 + outer loop + vertex 105.17 -32.4975 17.4071 + vertex 116.486 -31.4516 17.5563 + vertex 110.805 -28.9926 18.52 + endloop + endfacet + facet normal 0.0210824 -0.326021 0.945127 + outer loop + vertex 126.452 -31.2288 17.4109 + vertex 132.171 -27.6438 18.5199 + vertex 116.486 -31.4516 17.5563 + endloop + endfacet + facet normal 0.0204257 -0.323536 0.945995 + outer loop + vertex 132.171 -27.6438 18.5199 + vertex 110.805 -28.9926 18.52 + vertex 116.486 -31.4516 17.5563 + endloop + endfacet + facet normal 0.0136249 -0.32738 0.944795 + outer loop + vertex 83.8549 -33.5117 17.4088 + vertex 95.2284 -32.6045 17.5591 + vertex 89.424 -30.0767 18.5187 + endloop + endfacet + facet normal 0.0179749 -0.328713 0.944259 + outer loop + vertex 105.17 -32.4975 17.4071 + vertex 110.805 -28.9926 18.52 + vertex 95.2284 -32.6045 17.5591 + endloop + endfacet + facet normal 0.0162713 -0.321989 0.946603 + outer loop + vertex 110.805 -28.9926 18.52 + vertex 89.424 -30.0767 18.5187 + vertex 95.2284 -32.6045 17.5591 + endloop + endfacet + facet normal 0.0102348 -0.328631 0.944403 + outer loop + vertex 62.1471 -34.2791 17.4108 + vertex 73.7236 -33.4983 17.5571 + vertex 67.8424 -30.9103 18.5213 + endloop + endfacet + facet normal 0.0133963 -0.327047 0.944913 + outer loop + vertex 83.8549 -33.5117 17.4088 + vertex 89.424 -30.0767 18.5187 + vertex 73.7236 -33.4983 17.5571 + endloop + endfacet + facet normal 0.0126227 -0.323813 0.946037 + outer loop + vertex 89.424 -30.0767 18.5187 + vertex 67.8424 -30.9103 18.5213 + vertex 73.7236 -33.4983 17.5571 + endloop + endfacet + facet normal 0.00681114 -0.328782 0.944381 + outer loop + vertex 40.469 -34.803 17.4107 + vertex 51.9662 -34.1488 17.5555 + vertex 46.2419 -31.497 18.52 + endloop + endfacet + facet normal 0.00924707 -0.327136 0.944932 + outer loop + vertex 62.1471 -34.2791 17.4108 + vertex 67.8424 -30.9103 18.5213 + vertex 51.9662 -34.1488 17.5555 + endloop + endfacet + facet normal 0.00877071 -0.325019 0.945667 + outer loop + vertex 67.8424 -30.9103 18.5213 + vertex 46.2419 -31.497 18.52 + vertex 51.9662 -34.1488 17.5555 + endloop + endfacet + facet normal 0.00305863 -0.328908 0.944357 + outer loop + vertex 19.1034 -35.091 17.4097 + vertex 30.473 -34.563 17.5568 + vertex 24.7785 -31.8505 18.52 + endloop + endfacet + facet normal 0.00594734 -0.327433 0.944856 + outer loop + vertex 40.469 -34.803 17.4107 + vertex 46.2419 -31.497 18.52 + vertex 30.473 -34.563 17.5568 + endloop + endfacet + facet normal 0.00534358 -0.324632 0.945825 + outer loop + vertex 46.2419 -31.497 18.52 + vertex 24.7785 -31.8505 18.52 + vertex 30.473 -34.563 17.5568 + endloop + endfacet + facet normal -0.00041962 -0.328397 0.94454 + outer loop + vertex -2.30445 -35.1684 17.4098 + vertex 9.09258 -34.7531 17.5592 + vertex 3.39386 -31.9867 18.5185 + endloop + endfacet + facet normal 0.00300807 -0.328829 0.944385 + outer loop + vertex 19.1034 -35.091 17.4097 + vertex 24.7785 -31.8505 18.52 + vertex 9.09258 -34.7531 17.5592 + endloop + endfacet + facet normal 0.00200057 -0.323943 0.946074 + outer loop + vertex 24.7785 -31.8505 18.52 + vertex 3.39386 -31.9867 18.5185 + vertex 9.09258 -34.7531 17.5592 + endloop + endfacet + facet normal -0.00306585 -0.329605 0.944114 + outer loop + vertex -23.4664 -35.0509 17.4096 + vertex -12.2403 -34.7361 17.556 + vertex -17.8405 -31.9212 18.5205 + endloop + endfacet + facet normal -0.000393865 -0.328438 0.944525 + outer loop + vertex -2.30445 -35.1684 17.4098 + vertex 3.39386 -31.9867 18.5185 + vertex -12.2403 -34.7361 17.556 + endloop + endfacet + facet normal -0.000916874 -0.325785 0.945443 + outer loop + vertex 3.39386 -31.9867 18.5185 + vertex -17.8405 -31.9212 18.5205 + vertex -12.2403 -34.7361 17.556 + endloop + endfacet + facet normal -0.0067068 -0.328306 0.944548 + outer loop + vertex -44.553 -34.7239 17.4098 + vertex -33.2829 -34.5268 17.5584 + vertex -39.0658 -31.6422 18.52 + endloop + endfacet + facet normal -0.00327095 -0.329277 0.944228 + outer loop + vertex -23.4664 -35.0509 17.4096 + vertex -17.8405 -31.9212 18.5205 + vertex -33.2829 -34.5268 17.5584 + endloop + endfacet + facet normal -0.00428353 -0.323953 0.946063 + outer loop + vertex -17.8405 -31.9212 18.5205 + vertex -39.0658 -31.6422 18.52 + vertex -33.2829 -34.5268 17.5584 + endloop + endfacet + facet normal -0.0103515 -0.328794 0.944345 + outer loop + vertex -66.3674 -34.1422 17.4077 + vertex -54.7051 -34.0814 17.5568 + vertex -60.6381 -31.129 18.5197 + endloop + endfacet + facet normal -0.00707071 -0.327729 0.944745 + outer loop + vertex -44.553 -34.7239 17.4098 + vertex -39.0658 -31.6422 18.52 + vertex -54.7051 -34.0814 17.5568 + endloop + endfacet + facet normal -0.007722 -0.324052 0.946008 + outer loop + vertex -39.0658 -31.6422 18.52 + vertex -60.6381 -31.129 18.5197 + vertex -54.7051 -34.0814 17.5568 + endloop + endfacet + facet normal -0.0141283 -0.328463 0.944411 + outer loop + vertex -88.1317 -33.3253 17.4072 + vertex -76.6182 -33.3884 17.5576 + vertex -82.2434 -30.3803 18.5196 + endloop + endfacet + facet normal -0.0103759 -0.328753 0.944359 + outer loop + vertex -66.3674 -34.1422 17.4077 + vertex -60.6381 -31.129 18.5197 + vertex -76.6182 -33.3884 17.5576 + endloop + endfacet + facet normal -0.0112159 -0.323569 0.946138 + outer loop + vertex -60.6381 -31.129 18.5197 + vertex -82.2434 -30.3803 18.5196 + vertex -76.6182 -33.3884 17.5576 + endloop + endfacet + facet normal -0.0182323 -0.327058 0.944828 + outer loop + vertex -109.163 -32.285 17.4082 + vertex -97.9759 -32.473 17.559 + vertex -103.551 -29.3903 18.5185 + endloop + endfacet + facet normal -0.0139158 -0.328839 0.944283 + outer loop + vertex -88.1317 -33.3253 17.4072 + vertex -82.2434 -30.3803 18.5196 + vertex -97.9759 -32.473 17.559 + endloop + endfacet + facet normal -0.0150002 -0.321793 0.946691 + outer loop + vertex -82.2434 -30.3803 18.5196 + vertex -103.551 -29.3903 18.5185 + vertex -97.9759 -32.473 17.559 + endloop + endfacet + facet normal -0.0225024 -0.327468 0.944594 + outer loop + vertex -130.562 -30.9483 17.4081 + vertex -119.097 -31.2982 17.5599 + vertex -124.946 -28.1297 18.519 + endloop + endfacet + facet normal -0.0180818 -0.327317 0.944742 + outer loop + vertex -109.163 -32.285 17.4082 + vertex -103.551 -29.3903 18.5185 + vertex -119.097 -31.2982 17.5599 + endloop + endfacet + facet normal -0.0189182 -0.321496 0.946722 + outer loop + vertex -103.551 -29.3903 18.5185 + vertex -124.946 -28.1297 18.519 + vertex -119.097 -31.2982 17.5599 + endloop + endfacet + facet normal -0.025726 -0.326761 0.944757 + outer loop + vertex -152.255 -29.3418 17.4118 + vertex -140.741 -29.8241 17.5585 + vertex -146.476 -26.5988 18.5179 + endloop + endfacet + facet normal -0.0222583 -0.327898 0.944451 + outer loop + vertex -130.562 -30.9483 17.4081 + vertex -124.946 -28.1297 18.519 + vertex -140.741 -29.8241 17.5585 + endloop + endfacet + facet normal -0.0229703 -0.322335 0.946347 + outer loop + vertex -124.946 -28.1297 18.519 + vertex -146.476 -26.5988 18.5179 + vertex -140.741 -29.8241 17.5585 + endloop + endfacet + facet normal -0.0300366 -0.32827 0.944106 + outer loop + vertex -173.57 -27.5038 17.408 + vertex -162.226 -28.1117 17.5576 + vertex -167.893 -24.8236 18.5206 + endloop + endfacet + facet normal -0.0263528 -0.325596 0.945142 + outer loop + vertex -152.255 -29.3418 17.4118 + vertex -146.476 -26.5988 18.5179 + vertex -162.226 -28.1117 17.5576 + endloop + endfacet + facet normal -0.0266554 -0.323004 0.946022 + outer loop + vertex -146.476 -26.5988 18.5179 + vertex -167.893 -24.8236 18.5206 + vertex -162.226 -28.1117 17.5576 + endloop + endfacet + facet normal -0.0337743 -0.327923 0.944101 + outer loop + vertex -195.05 -25.4034 17.4092 + vertex -183.586 -26.1541 17.5586 + vertex -189.293 -22.7984 18.52 + endloop + endfacet + facet normal -0.0300418 -0.328261 0.944109 + outer loop + vertex -173.57 -27.5038 17.408 + vertex -167.893 -24.8236 18.5206 + vertex -183.586 -26.1541 17.5586 + endloop + endfacet + facet normal -0.0305947 -0.32303 0.945894 + outer loop + vertex -167.893 -24.8236 18.5206 + vertex -189.293 -22.7984 18.52 + vertex -183.586 -26.1541 17.5586 + endloop + endfacet + facet normal -0.0370352 -0.326783 0.944373 + outer loop + vertex -216.263 -23.1055 17.411 + vertex -205.032 -23.9493 17.5595 + vertex -210.507 -20.5585 18.5181 + endloop + endfacet + facet normal -0.0336087 -0.328244 0.943995 + outer loop + vertex -195.05 -25.4034 17.4092 + vertex -189.293 -22.7984 18.52 + vertex -205.032 -23.9493 17.5595 + endloop + endfacet + facet normal -0.0341431 -0.322555 0.945935 + outer loop + vertex -189.293 -22.7984 18.52 + vertex -210.507 -20.5585 18.5181 + vertex -205.032 -23.9493 17.5595 + endloop + endfacet + facet normal -0.0407269 -0.328197 0.943731 + outer loop + vertex -237.021 -20.6305 17.4084 + vertex -225.941 -21.5779 17.5571 + vertex -231.521 -18.115 18.5206 + endloop + endfacet + facet normal -0.0372512 -0.326356 0.944513 + outer loop + vertex -216.263 -23.1055 17.411 + vertex -210.507 -20.5585 18.5181 + vertex -225.941 -21.5779 17.5571 + endloop + endfacet + facet normal -0.0375014 -0.323488 0.945489 + outer loop + vertex -210.507 -20.5585 18.5181 + vertex -231.521 -18.115 18.5206 + vertex -225.941 -21.5779 17.5571 + endloop + endfacet + facet normal -0.0443835 -0.327203 0.943911 + outer loop + vertex -258.464 -17.8428 17.4081 + vertex -246.96 -18.9672 17.5593 + vertex -252.84 -15.4014 18.5189 + endloop + endfacet + facet normal -0.0406318 -0.328379 0.943672 + outer loop + vertex -237.021 -20.6305 17.4084 + vertex -231.521 -18.115 18.5206 + vertex -246.96 -18.9672 17.5593 + endloop + endfacet + facet normal -0.0410979 -0.32228 0.945752 + outer loop + vertex -231.521 -18.115 18.5206 + vertex -252.84 -15.4014 18.5189 + vertex -246.96 -18.9672 17.5593 + endloop + endfacet + facet normal -0.0476321 -0.327856 0.943526 + outer loop + vertex -280.325 -14.78 17.4081 + vertex -268.708 -16.0352 17.5584 + vertex -274.425 -12.4349 18.5208 + endloop + endfacet + facet normal -0.0440239 -0.327925 0.943677 + outer loop + vertex -258.464 -17.8428 17.4081 + vertex -252.84 -15.4014 18.5189 + vertex -268.708 -16.0352 17.5584 + endloop + endfacet + facet normal -0.0443179 -0.323077 0.945334 + outer loop + vertex -252.84 -15.4014 18.5189 + vertex -274.425 -12.4349 18.5208 + vertex -268.708 -16.0352 17.5584 + endloop + endfacet + facet normal -0.0503529 -0.327173 0.943622 + outer loop + vertex -301.588 -11.5935 17.4108 + vertex -290.32 -12.9059 17.5571 + vertex -295.742 -9.29401 18.5201 + endloop + endfacet + facet normal -0.0474749 -0.328199 0.943415 + outer loop + vertex -280.325 -14.78 17.4081 + vertex -274.425 -12.4349 18.5208 + vertex -290.32 -12.9059 17.5571 + endloop + endfacet + facet normal -0.0477082 -0.32357 0.945001 + outer loop + vertex -274.425 -12.4349 18.5208 + vertex -295.742 -9.29401 18.5201 + vertex -290.32 -12.9059 17.5571 + endloop + endfacet + facet normal -0.0533807 -0.326462 0.943702 + outer loop + vertex -322.308 -8.28338 17.4118 + vertex -311.279 -9.66654 17.5572 + vertex -316.663 -6.00707 18.5186 + endloop + endfacet + facet normal -0.0506669 -0.326482 0.943845 + outer loop + vertex -301.588 -11.5935 17.4108 + vertex -295.742 -9.29401 18.5201 + vertex -311.279 -9.66654 17.5572 + endloop + endfacet + facet normal -0.0508221 -0.323043 0.945019 + outer loop + vertex -295.742 -9.29401 18.5201 + vertex -316.663 -6.00707 18.5186 + vertex -311.279 -9.66654 17.5572 + endloop + endfacet + facet normal -0.0568712 -0.327085 0.943282 + outer loop + vertex -342.944 -4.78771 17.4095 + vertex -331.934 -6.27471 17.5577 + vertex -337.402 -2.54927 18.5198 + endloop + endfacet + facet normal -0.0536807 -0.325818 0.943907 + outer loop + vertex -322.308 -8.28338 17.4118 + vertex -316.663 -6.00707 18.5186 + vertex -331.934 -6.27471 17.5577 + endloop + endfacet + facet normal -0.0537915 -0.322976 0.944877 + outer loop + vertex -316.663 -6.00707 18.5186 + vertex -337.402 -2.54927 18.5198 + vertex -331.934 -6.27471 17.5577 + endloop + endfacet + facet normal -0.0596033 -0.32654 0.943302 + outer loop + vertex -363.716 -1.07479 17.4095 + vertex -352.639 -2.67494 17.5555 + vertex -358.168 1.11683 18.5187 + endloop + endfacet + facet normal -0.057009 -0.32679 0.943376 + outer loop + vertex -342.944 -4.78771 17.4095 + vertex -337.402 -2.54927 18.5198 + vertex -352.639 -2.67494 17.5555 + endloop + endfacet + facet normal -0.0571152 -0.32324 0.944592 + outer loop + vertex -337.402 -2.54927 18.5198 + vertex -358.168 1.11683 18.5187 + vertex -352.639 -2.67494 17.5555 + endloop + endfacet + facet normal -0.0628535 -0.325794 0.943349 + outer loop + vertex -384.779 2.89793 17.408 + vertex -373.514 1.15139 17.5554 + vertex -379.144 5.02749 18.5189 + endloop + endfacet + facet normal -0.0599671 -0.325747 0.943553 + outer loop + vertex -363.716 -1.07479 17.4095 + vertex -358.168 1.11683 18.5187 + vertex -373.514 1.15139 17.5554 + endloop + endfacet + facet normal -0.0600377 -0.322067 0.944811 + outer loop + vertex -358.168 1.11683 18.5187 + vertex -379.144 5.02749 18.5189 + vertex -373.514 1.15139 17.5554 + endloop + endfacet + facet normal -0.0659112 -0.326167 0.943011 + outer loop + vertex -406.31 7.17932 17.4101 + vertex -394.811 5.27211 17.5541 + vertex -400.364 9.18913 18.5208 + endloop + endfacet + facet normal -0.0631798 -0.325053 0.943583 + outer loop + vertex -384.779 2.89793 17.408 + vertex -379.144 5.02749 18.5189 + vertex -394.811 5.27211 17.5541 + endloop + endfacet + facet normal -0.0631929 -0.322658 0.944404 + outer loop + vertex -379.144 5.02749 18.5189 + vertex -400.364 9.18913 18.5208 + vertex -394.811 5.27211 17.5541 + endloop + endfacet + facet normal -0.0682355 -0.326453 0.942747 + outer loop + vertex -427.385 11.5676 17.4253 + vertex -416.232 9.62893 17.5612 + vertex -421.417 13.496 18.525 + endloop + endfacet + facet normal -0.0660666 -0.325776 0.943136 + outer loop + vertex -406.31 7.17932 17.4101 + vertex -400.364 9.18913 18.5208 + vertex -416.232 9.62893 17.5612 + endloop + endfacet + facet normal -0.066053 -0.323793 0.943819 + outer loop + vertex -400.364 9.18913 18.5208 + vertex -421.417 13.496 18.525 + vertex -416.232 9.62893 17.5612 + endloop + endfacet + facet normal -0.0724847 -0.324604 0.943069 + outer loop + vertex -447.591 15.895 17.4016 + vertex -436.812 13.9738 17.5688 + vertex -442.32 17.9395 18.5104 + endloop + endfacet + facet normal -0.0686765 -0.325297 0.943115 + outer loop + vertex -427.385 11.5676 17.4253 + vertex -421.417 13.496 18.525 + vertex -436.812 13.9738 17.5688 + endloop + endfacet + facet normal -0.0686218 -0.319704 0.945029 + outer loop + vertex -421.417 13.496 18.525 + vertex -442.32 17.9395 18.5104 + vertex -436.812 13.9738 17.5688 + endloop + endfacet + facet normal -0.0768982 -0.325676 0.942349 + outer loop + vertex -469.158 20.7675 17.3577 + vertex -457.487 18.4791 17.5192 + vertex -464.105 22.904 18.5084 + endloop + endfacet + facet normal -0.073156 -0.323121 0.943526 + outer loop + vertex -447.591 15.895 17.4016 + vertex -442.32 17.9395 18.5104 + vertex -457.487 18.4791 17.5192 + endloop + endfacet + facet normal -0.0731212 -0.320491 0.944425 + outer loop + vertex -442.32 17.9395 18.5104 + vertex -464.105 22.904 18.5084 + vertex -457.487 18.4791 17.5192 + endloop + endfacet + facet normal -0.0737305 -0.316722 0.945648 + outer loop + vertex -490.969 26.3302 17.5444 + vertex -479.976 23.8726 17.5784 + vertex -486.535 28.6287 18.6599 + endloop + endfacet + facet normal -0.0752412 -0.329038 0.941314 + outer loop + vertex -469.158 20.7675 17.3577 + vertex -464.105 22.904 18.5084 + vertex -479.976 23.8726 17.5784 + endloop + endfacet + facet normal -0.0747943 -0.318067 0.945113 + outer loop + vertex -464.105 22.904 18.5084 + vertex -486.535 28.6287 18.6599 + vertex -479.976 23.8726 17.5784 + endloop + endfacet + facet normal -0.0750694 -0.328072 0.941665 + outer loop + vertex -508.771 30.3684 17.3915 + vertex -507.346 30.1575 17.4316 + vertex -506.714 33.1492 18.5243 + endloop + endfacet + facet normal -0.0862655 -0.351127 0.932345 + outer loop + vertex -503.866 28.6332 17.1795 + vertex -501.423 30.7835 18.2155 + vertex -507.346 30.1575 17.4316 + endloop + endfacet + facet normal -0.0902562 -0.324791 0.941469 + outer loop + vertex -501.423 30.7835 18.2155 + vertex -506.714 33.1492 18.5243 + vertex -507.346 30.1575 17.4316 + endloop + endfacet + facet normal 0.11985 -0.559859 0.819874 + outer loop + vertex 504.402 27.173 16.4254 + vertex 504.568 25.6192 15.3401 + vertex 507.895 27.6453 16.2373 + endloop + endfacet + facet normal 0.14215 -0.586508 0.797372 + outer loop + vertex 507.895 27.6453 16.2373 + vertex 504.568 25.6192 15.3401 + vertex 508.17 26.462 15.318 + endloop + endfacet + facet normal 0.088176 -0.429731 0.898641 + outer loop + vertex 503.689 29.0724 17.4036 + vertex 504.402 27.173 16.4254 + vertex 507.709 29.0161 16.9823 + endloop + endfacet + facet normal 0.109972 -0.463051 0.879483 + outer loop + vertex 507.709 29.0161 16.9823 + vertex 504.402 27.173 16.4254 + vertex 507.895 27.6453 16.2373 + endloop + endfacet + facet normal 0.129537 -0.5382 0.832803 + outer loop + vertex 488.007 23.5066 16.5443 + vertex 488.661 21.8245 15.3555 + vertex 497.43 25.7686 16.5404 + endloop + endfacet + facet normal 0.130952 -0.540776 0.830911 + outer loop + vertex 497.43 25.7686 16.5404 + vertex 488.661 21.8245 15.3555 + vertex 497.864 24.0507 15.354 + endloop + endfacet + facet normal 0.103752 -0.419386 0.90186 + outer loop + vertex 486.269 24.9811 17.4299 + vertex 488.007 23.5066 16.5443 + vertex 495.592 27.6126 17.5811 + endloop + endfacet + facet normal 0.09931 -0.412147 0.905689 + outer loop + vertex 495.592 27.6126 17.5811 + vertex 488.007 23.5066 16.5443 + vertex 497.43 25.7686 16.5404 + endloop + endfacet + facet normal 0.0948087 -0.41593 0.904441 + outer loop + vertex 495.592 27.6126 17.5811 + vertex 497.43 25.7686 16.5404 + vertex 503.689 29.0724 17.4036 + endloop + endfacet + facet normal 0.100543 -0.425468 0.899371 + outer loop + vertex 503.689 29.0724 17.4036 + vertex 497.43 25.7686 16.5404 + vertex 504.402 27.173 16.4254 + endloop + endfacet + facet normal 0.123036 -0.54273 0.830847 + outer loop + vertex 497.43 25.7686 16.5404 + vertex 497.864 24.0507 15.354 + vertex 504.402 27.173 16.4254 + endloop + endfacet + facet normal 0.132263 -0.558053 0.819197 + outer loop + vertex 504.402 27.173 16.4254 + vertex 497.864 24.0507 15.354 + vertex 504.568 25.6192 15.3401 + endloop + endfacet + facet normal 0.126658 -0.536423 0.834391 + outer loop + vertex 466.895 18.4465 16.5236 + vertex 467.396 16.7215 15.3386 + vertex 477.637 20.9947 16.5313 + endloop + endfacet + facet normal 0.127571 -0.538245 0.833077 + outer loop + vertex 477.637 20.9947 16.5313 + vertex 467.396 16.7215 15.3386 + vertex 478.148 19.2751 15.3419 + endloop + endfacet + facet normal 0.101324 -0.418431 0.902579 + outer loop + vertex 465.552 20.0477 17.4166 + vertex 466.895 18.4465 16.5236 + vertex 476.699 23.0845 17.5731 + endloop + endfacet + facet normal 0.0964045 -0.409117 0.907375 + outer loop + vertex 476.699 23.0845 17.5731 + vertex 466.895 18.4465 16.5236 + vertex 477.637 20.9947 16.5313 + endloop + endfacet + facet normal 0.094786 -0.409779 0.907247 + outer loop + vertex 476.699 23.0845 17.5731 + vertex 477.637 20.9947 16.5313 + vertex 486.269 24.9811 17.4299 + endloop + endfacet + facet normal 0.10108 -0.421989 0.900949 + outer loop + vertex 486.269 24.9811 17.4299 + vertex 477.637 20.9947 16.5313 + vertex 488.007 23.5066 16.5443 + endloop + endfacet + facet normal 0.129213 -0.537787 0.83312 + outer loop + vertex 477.637 20.9947 16.5313 + vertex 478.148 19.2751 15.3419 + vertex 488.007 23.5066 16.5443 + endloop + endfacet + facet normal 0.129443 -0.538232 0.832797 + outer loop + vertex 488.007 23.5066 16.5443 + vertex 478.148 19.2751 15.3419 + vertex 488.661 21.8245 15.3555 + endloop + endfacet + facet normal 0.122113 -0.543691 0.830355 + outer loop + vertex 445.504 13.5873 16.5225 + vertex 446.217 11.9371 15.3371 + vertex 456.182 15.9821 16.5202 + endloop + endfacet + facet normal 0.120415 -0.540239 0.832852 + outer loop + vertex 456.182 15.9821 16.5202 + vertex 446.217 11.9371 15.3371 + vertex 456.749 14.2826 15.3359 + endloop + endfacet + facet normal 0.0981329 -0.420433 0.902001 + outer loop + vertex 444.032 15.1512 17.4116 + vertex 445.504 13.5873 16.5225 + vertex 455.552 18.1628 17.562 + endloop + endfacet + facet normal 0.0916041 -0.407586 0.908561 + outer loop + vertex 455.552 18.1628 17.562 + vertex 445.504 13.5873 16.5225 + vertex 456.182 15.9821 16.5202 + endloop + endfacet + facet normal 0.0901077 -0.408001 0.908524 + outer loop + vertex 455.552 18.1628 17.562 + vertex 456.182 15.9821 16.5202 + vertex 465.552 20.0477 17.4166 + endloop + endfacet + facet normal 0.0967255 -0.421716 0.901554 + outer loop + vertex 465.552 20.0477 17.4166 + vertex 456.182 15.9821 16.5202 + vertex 466.895 18.4465 16.5236 + endloop + endfacet + facet normal 0.12378 -0.539229 0.833013 + outer loop + vertex 456.182 15.9821 16.5202 + vertex 456.749 14.2826 15.3359 + vertex 466.895 18.4465 16.5236 + endloop + endfacet + facet normal 0.122899 -0.537448 0.834294 + outer loop + vertex 466.895 18.4465 16.5236 + vertex 456.749 14.2826 15.3359 + vertex 467.396 16.7215 15.3386 + endloop + endfacet + facet normal 0.117311 -0.54797 0.828231 + outer loop + vertex 424.31 9.00394 16.5215 + vertex 425.209 7.40987 15.3395 + vertex 434.852 11.2589 16.5202 + endloop + endfacet + facet normal 0.116141 -0.545574 0.829976 + outer loop + vertex 434.852 11.2589 16.5202 + vertex 425.209 7.40987 15.3395 + vertex 435.702 9.64484 15.3403 + endloop + endfacet + facet normal 0.0945632 -0.424765 0.900351 + outer loop + vertex 422.681 10.5179 17.4069 + vertex 424.31 9.00394 16.5215 + vertex 434.032 13.365 17.5579 + endloop + endfacet + facet normal 0.0883134 -0.41235 0.906735 + outer loop + vertex 434.032 13.365 17.5579 + vertex 424.31 9.00394 16.5215 + vertex 434.852 11.2589 16.5202 + endloop + endfacet + facet normal 0.0870014 -0.412819 0.906649 + outer loop + vertex 434.032 13.365 17.5579 + vertex 434.852 11.2589 16.5202 + vertex 444.032 15.1512 17.4116 + endloop + endfacet + facet normal 0.0926575 -0.424761 0.900551 + outer loop + vertex 444.032 15.1512 17.4116 + vertex 434.852 11.2589 16.5202 + vertex 445.504 13.5873 16.5225 + endloop + endfacet + facet normal 0.118831 -0.544429 0.830347 + outer loop + vertex 434.852 11.2589 16.5202 + vertex 435.702 9.64484 15.3403 + vertex 445.504 13.5873 16.5225 + endloop + endfacet + facet normal 0.119022 -0.544819 0.830064 + outer loop + vertex 445.504 13.5873 16.5225 + vertex 435.702 9.64484 15.3403 + vertex 446.217 11.9371 15.3371 + endloop + endfacet + facet normal 0.111519 -0.548354 0.828777 + outer loop + vertex 403.614 4.73992 16.5212 + vertex 404.505 3.13659 15.3406 + vertex 413.915 6.83452 16.5211 + endloop + endfacet + facet normal 0.111734 -0.548798 0.828454 + outer loop + vertex 413.915 6.83452 16.5211 + vertex 404.505 3.13659 15.3406 + vertex 414.821 5.23871 15.3417 + endloop + endfacet + facet normal 0.0909292 -0.428251 0.899073 + outer loop + vertex 401.867 6.23075 17.4081 + vertex 403.614 4.73992 16.5212 + vertex 412.929 8.88724 17.5547 + endloop + endfacet + facet normal 0.0844922 -0.415442 0.905687 + outer loop + vertex 412.929 8.88724 17.5547 + vertex 403.614 4.73992 16.5212 + vertex 413.915 6.83452 16.5211 + endloop + endfacet + facet normal 0.0832778 -0.415962 0.905561 + outer loop + vertex 412.929 8.88724 17.5547 + vertex 413.915 6.83452 16.5211 + vertex 422.681 10.5179 17.4069 + endloop + endfacet + facet normal 0.0895412 -0.42923 0.898746 + outer loop + vertex 422.681 10.5179 17.4069 + vertex 413.915 6.83452 16.5211 + vertex 424.31 9.00394 16.5215 + endloop + endfacet + facet normal 0.114261 -0.547663 0.82886 + outer loop + vertex 413.915 6.83452 16.5211 + vertex 414.821 5.23871 15.3417 + vertex 424.31 9.00394 16.5215 + endloop + endfacet + facet normal 0.114931 -0.549037 0.827858 + outer loop + vertex 424.31 9.00394 16.5215 + vertex 414.821 5.23871 15.3417 + vertex 425.209 7.40987 15.3395 + endloop + endfacet + facet normal 0.106259 -0.548198 0.829571 + outer loop + vertex 382.582 0.61689 16.5249 + vertex 383.512 -0.992717 15.3421 + vertex 393.211 2.67407 16.5229 + endloop + endfacet + facet normal 0.106436 -0.548578 0.829297 + outer loop + vertex 393.211 2.67407 16.5229 + vertex 383.512 -0.992717 15.3421 + vertex 394.125 1.06735 15.3428 + endloop + endfacet + facet normal 0.0860151 -0.427139 0.900085 + outer loop + vertex 380.716 2.10553 17.4097 + vertex 382.582 0.61689 16.5249 + vertex 392.006 4.6853 17.555 + endloop + endfacet + facet normal 0.0807519 -0.416348 0.905612 + outer loop + vertex 392.006 4.6853 17.555 + vertex 382.582 0.61689 16.5249 + vertex 393.211 2.67407 16.5229 + endloop + endfacet + facet normal 0.0788945 -0.417316 0.905331 + outer loop + vertex 392.006 4.6853 17.555 + vertex 393.211 2.67407 16.5229 + vertex 401.867 6.23075 17.4081 + endloop + endfacet + facet normal 0.0861042 -0.432872 0.897334 + outer loop + vertex 401.867 6.23075 17.4081 + vertex 393.211 2.67407 16.5229 + vertex 403.614 4.73992 16.5212 + endloop + endfacet + facet normal 0.108854 -0.547496 0.829698 + outer loop + vertex 393.211 2.67407 16.5229 + vertex 394.125 1.06735 15.3428 + vertex 403.614 4.73992 16.5212 + endloop + endfacet + facet normal 0.109654 -0.549173 0.828483 + outer loop + vertex 403.614 4.73992 16.5212 + vertex 394.125 1.06735 15.3428 + vertex 404.505 3.13659 15.3406 + endloop + endfacet + facet normal 0.100328 -0.544359 0.832831 + outer loop + vertex 360.978 -3.41328 16.5221 + vertex 361.861 -5.05258 15.3442 + vertex 371.767 -1.42362 16.5229 + endloop + endfacet + facet normal 0.102324 -0.548782 0.82968 + outer loop + vertex 371.767 -1.42362 16.5229 + vertex 361.861 -5.05258 15.3442 + vertex 372.688 -3.04074 15.3397 + endloop + endfacet + facet normal 0.0816954 -0.427633 0.900253 + outer loop + vertex 359.285 -1.87262 17.4075 + vertex 360.978 -3.41328 16.5221 + vertex 370.622 0.608308 17.5573 + endloop + endfacet + facet normal 0.0769355 -0.417542 0.905395 + outer loop + vertex 370.622 0.608308 17.5573 + vertex 360.978 -3.41328 16.5221 + vertex 371.767 -1.42362 16.5229 + endloop + endfacet + facet normal 0.0752861 -0.418352 0.905159 + outer loop + vertex 370.622 0.608308 17.5573 + vertex 371.767 -1.42362 16.5229 + vertex 380.716 2.10553 17.4097 + endloop + endfacet + facet normal 0.081324 -0.431923 0.898237 + outer loop + vertex 380.716 2.10553 17.4097 + vertex 371.767 -1.42362 16.5229 + vertex 382.582 0.61689 16.5249 + endloop + endfacet + facet normal 0.103301 -0.548347 0.829846 + outer loop + vertex 371.767 -1.42362 16.5229 + vertex 372.688 -3.04074 15.3397 + vertex 382.582 0.61689 16.5249 + endloop + endfacet + facet normal 0.10375 -0.54933 0.829139 + outer loop + vertex 382.582 0.61689 16.5249 + vertex 372.688 -3.04074 15.3397 + vertex 383.512 -0.992717 15.3421 + endloop + endfacet + facet normal 0.0955153 -0.546432 0.832039 + outer loop + vertex 340.164 -7.1153 16.5227 + vertex 340.922 -8.78155 15.3415 + vertex 350.439 -5.31567 16.5251 + endloop + endfacet + facet normal 0.0963576 -0.548294 0.830716 + outer loop + vertex 350.439 -5.31567 16.5251 + vertex 340.922 -8.78155 15.3415 + vertex 351.239 -6.96781 15.3419 + endloop + endfacet + facet normal 0.0780422 -0.42752 0.900631 + outer loop + vertex 338.599 -5.53393 17.409 + vertex 340.164 -7.1153 16.5227 + vertex 349.534 -3.22323 17.5583 + endloop + endfacet + facet normal 0.0726789 -0.41614 0.906391 + outer loop + vertex 349.534 -3.22323 17.5583 + vertex 340.164 -7.1153 16.5227 + vertex 350.439 -5.31567 16.5251 + endloop + endfacet + facet normal 0.0717056 -0.416515 0.906297 + outer loop + vertex 349.534 -3.22323 17.5583 + vertex 350.439 -5.31567 16.5251 + vertex 359.285 -1.87262 17.4075 + endloop + endfacet + facet normal 0.0780431 -0.430928 0.899005 + outer loop + vertex 359.285 -1.87262 17.4075 + vertex 350.439 -5.31567 16.5251 + vertex 360.978 -3.41328 16.5221 + endloop + endfacet + facet normal 0.0990244 -0.547264 0.831081 + outer loop + vertex 350.439 -5.31567 16.5251 + vertex 351.239 -6.96781 15.3419 + vertex 360.978 -3.41328 16.5221 + endloop + endfacet + facet normal 0.0981341 -0.545291 0.832483 + outer loop + vertex 360.978 -3.41328 16.5221 + vertex 351.239 -6.96781 15.3419 + vertex 361.861 -5.05258 15.3442 + endloop + endfacet + facet normal 0.0902332 -0.546243 0.832752 + outer loop + vertex 319.751 -10.5467 16.5223 + vertex 320.556 -12.2125 15.3423 + vertex 330.005 -8.85036 16.524 + endloop + endfacet + facet normal 0.0915927 -0.549303 0.830588 + outer loop + vertex 330.005 -8.85036 16.524 + vertex 320.556 -12.2125 15.3423 + vertex 330.765 -10.5142 15.3398 + endloop + endfacet + facet normal 0.0735546 -0.42627 0.9016 + outer loop + vertex 318.054 -8.96954 17.4064 + vertex 319.751 -10.5467 16.5223 + vertex 329.031 -6.75748 17.5567 + endloop + endfacet + facet normal 0.0686135 -0.415627 0.906943 + outer loop + vertex 329.031 -6.75748 17.5567 + vertex 319.751 -10.5467 16.5223 + vertex 330.005 -8.85036 16.524 + endloop + endfacet + facet normal 0.0672204 -0.416197 0.906786 + outer loop + vertex 329.031 -6.75748 17.5567 + vertex 330.005 -8.85036 16.524 + vertex 338.599 -5.53393 17.409 + endloop + endfacet + facet normal 0.0737233 -0.431054 0.899309 + outer loop + vertex 338.599 -5.53393 17.409 + vertex 330.005 -8.85036 16.524 + vertex 340.164 -7.1153 16.5227 + endloop + endfacet + facet normal 0.093774 -0.548508 0.83087 + outer loop + vertex 330.005 -8.85036 16.524 + vertex 330.765 -10.5142 15.3398 + vertex 340.164 -7.1153 16.5227 + endloop + endfacet + facet normal 0.0932164 -0.547271 0.831748 + outer loop + vertex 340.164 -7.1153 16.5227 + vertex 330.765 -10.5142 15.3398 + vertex 340.922 -8.78155 15.3415 + endloop + endfacet + facet normal 0.0851256 -0.547352 0.832562 + outer loop + vertex 298.623 -13.8947 16.5225 + vertex 299.471 -15.5585 15.3419 + vertex 309.292 -12.2322 16.5245 + endloop + endfacet + facet normal 0.0863232 -0.550181 0.830572 + outer loop + vertex 309.292 -12.2322 16.5245 + vertex 299.471 -15.5585 15.3419 + vertex 310.119 -13.8905 15.3401 + endloop + endfacet + facet normal 0.0697343 -0.427316 0.901409 + outer loop + vertex 296.88 -12.3115 17.4079 + vertex 298.623 -13.8947 16.5225 + vertex 308.186 -10.1521 17.5568 + endloop + endfacet + facet normal 0.0646191 -0.415829 0.907144 + outer loop + vertex 308.186 -10.1521 17.5568 + vertex 298.623 -13.8947 16.5225 + vertex 309.292 -12.2322 16.5245 + endloop + endfacet + facet normal 0.063711 -0.416248 0.907016 + outer loop + vertex 308.186 -10.1521 17.5568 + vertex 309.292 -12.2322 16.5245 + vertex 318.054 -8.96954 17.4064 + endloop + endfacet + facet normal 0.0694728 -0.429881 0.900209 + outer loop + vertex 318.054 -8.96954 17.4064 + vertex 309.292 -12.2322 16.5245 + vertex 319.751 -10.5467 16.5223 + endloop + endfacet + facet normal 0.0886975 -0.549256 0.830934 + outer loop + vertex 309.292 -12.2322 16.5245 + vertex 310.119 -13.8905 15.3401 + vertex 319.751 -10.5467 16.5223 + endloop + endfacet + facet normal 0.0877947 -0.547174 0.832402 + outer loop + vertex 319.751 -10.5467 16.5223 + vertex 310.119 -13.8905 15.3401 + vertex 320.556 -12.2125 15.3423 + endloop + endfacet + facet normal 0.0799704 -0.547651 0.832876 + outer loop + vertex 277.154 -17.0897 16.523 + vertex 277.964 -18.7669 15.3424 + vertex 287.879 -15.5221 16.524 + endloop + endfacet + facet normal 0.0810461 -0.550271 0.831044 + outer loop + vertex 287.879 -15.5221 16.524 + vertex 277.964 -18.7669 15.3424 + vertex 288.703 -17.1883 15.3403 + endloop + endfacet + facet normal 0.0660921 -0.428074 0.901324 + outer loop + vertex 275.495 -15.479 17.4096 + vertex 277.154 -17.0897 16.523 + vertex 286.845 -13.4204 17.555 + endloop + endfacet + facet normal 0.060638 -0.415434 0.9076 + outer loop + vertex 286.845 -13.4204 17.555 + vertex 277.154 -17.0897 16.523 + vertex 287.879 -15.5221 16.524 + endloop + endfacet + facet normal 0.0592789 -0.416016 0.907423 + outer loop + vertex 286.845 -13.4204 17.555 + vertex 287.879 -15.5221 16.524 + vertex 296.88 -12.3115 17.4079 + endloop + endfacet + facet normal 0.0654339 -0.431196 0.899882 + outer loop + vertex 296.88 -12.3115 17.4079 + vertex 287.879 -15.5221 16.524 + vertex 298.623 -13.8947 16.5225 + endloop + endfacet + facet normal 0.0833284 -0.549394 0.831398 + outer loop + vertex 287.879 -15.5221 16.524 + vertex 288.703 -17.1883 15.3403 + vertex 298.623 -13.8947 16.5225 + endloop + endfacet + facet normal 0.0828542 -0.548253 0.832198 + outer loop + vertex 298.623 -13.8947 16.5225 + vertex 288.703 -17.1883 15.3403 + vertex 299.471 -15.5585 15.3419 + endloop + endfacet + facet normal 0.0751045 -0.549395 0.832181 + outer loop + vertex 256.045 -20.0241 16.5257 + vertex 256.821 -21.7097 15.3428 + vertex 266.544 -18.5913 16.524 + endloop + endfacet + facet normal 0.0748916 -0.54887 0.832546 + outer loop + vertex 266.544 -18.5913 16.524 + vertex 256.821 -21.7097 15.3428 + vertex 267.333 -20.2746 15.3433 + endloop + endfacet + facet normal 0.0616851 -0.426754 0.902261 + outer loop + vertex 254.425 -18.3897 17.4095 + vertex 256.045 -20.0241 16.5257 + vertex 265.608 -16.4665 17.5546 + endloop + endfacet + facet normal 0.0568191 -0.415307 0.907905 + outer loop + vertex 265.608 -16.4665 17.5546 + vertex 256.045 -20.0241 16.5257 + vertex 266.544 -18.5913 16.524 + endloop + endfacet + facet normal 0.0548656 -0.416059 0.907681 + outer loop + vertex 265.608 -16.4665 17.5546 + vertex 266.544 -18.5913 16.524 + vertex 275.495 -15.479 17.4096 + endloop + endfacet + facet normal 0.0612559 -0.432168 0.89971 + outer loop + vertex 275.495 -15.479 17.4096 + vertex 266.544 -18.5913 16.524 + vertex 277.154 -17.0897 16.523 + endloop + endfacet + facet normal 0.0776262 -0.547873 0.832952 + outer loop + vertex 266.544 -18.5913 16.524 + vertex 267.333 -20.2746 15.3433 + vertex 277.154 -17.0897 16.523 + endloop + endfacet + facet normal 0.0778591 -0.548444 0.832554 + outer loop + vertex 277.154 -17.0897 16.523 + vertex 267.333 -20.2746 15.3433 + vertex 277.964 -18.7669 15.3424 + endloop + endfacet + facet normal 0.068967 -0.548884 0.833048 + outer loop + vertex 235.124 -22.7103 16.5236 + vertex 235.923 -24.402 15.3428 + vertex 245.593 -21.3937 16.5245 + endloop + endfacet + facet normal 0.0696096 -0.550508 0.831923 + outer loop + vertex 245.593 -21.3937 16.5245 + vertex 235.923 -24.402 15.3428 + vertex 246.376 -23.0814 15.3421 + endloop + endfacet + facet normal 0.0566808 -0.427196 0.902381 + outer loop + vertex 233.461 -21.0657 17.4067 + vertex 235.124 -22.7103 16.5236 + vertex 244.628 -19.2663 17.5571 + endloop + endfacet + facet normal 0.0523454 -0.41677 0.907504 + outer loop + vertex 244.628 -19.2663 17.5571 + vertex 235.124 -22.7103 16.5236 + vertex 245.593 -21.3937 16.5245 + endloop + endfacet + facet normal 0.0510111 -0.417295 0.907338 + outer loop + vertex 244.628 -19.2663 17.5571 + vertex 245.593 -21.3937 16.5245 + vertex 254.425 -18.3897 17.4095 + endloop + endfacet + facet normal 0.0563812 -0.431084 0.900548 + outer loop + vertex 254.425 -18.3897 17.4095 + vertex 245.593 -21.3937 16.5245 + vertex 256.045 -20.0241 16.5257 + endloop + endfacet + facet normal 0.0719293 -0.549677 0.832275 + outer loop + vertex 245.593 -21.3937 16.5245 + vertex 246.376 -23.0814 15.3421 + vertex 256.045 -20.0241 16.5257 + endloop + endfacet + facet normal 0.0722281 -0.550422 0.831757 + outer loop + vertex 256.045 -20.0241 16.5257 + vertex 246.376 -23.0814 15.3421 + vertex 256.821 -21.7097 15.3428 + endloop + endfacet + facet normal 0.0636808 -0.549656 0.832961 + outer loop + vertex 214.02 -25.2066 16.5267 + vertex 214.824 -26.9042 15.3451 + vertex 224.599 -23.983 16.5254 + endloop + endfacet + facet normal 0.0641068 -0.550771 0.832191 + outer loop + vertex 224.599 -23.983 16.5254 + vertex 214.824 -26.9042 15.3451 + vertex 225.405 -25.6755 15.3431 + endloop + endfacet + facet normal 0.053016 -0.427688 0.902371 + outer loop + vertex 212.344 -23.5483 17.4112 + vertex 214.02 -25.2066 16.5267 + vertex 223.59 -21.8504 17.5552 + endloop + endfacet + facet normal 0.0482013 -0.415747 0.908202 + outer loop + vertex 223.59 -21.8504 17.5552 + vertex 214.02 -25.2066 16.5267 + vertex 224.599 -23.983 16.5254 + endloop + endfacet + facet normal 0.0467582 -0.416336 0.908008 + outer loop + vertex 223.59 -21.8504 17.5552 + vertex 224.599 -23.983 16.5254 + vertex 233.461 -21.0657 17.4067 + endloop + endfacet + facet normal 0.0522517 -0.430876 0.900897 + outer loop + vertex 233.461 -21.0657 17.4067 + vertex 224.599 -23.983 16.5254 + vertex 235.124 -22.7103 16.5236 + endloop + endfacet + facet normal 0.0666271 -0.549854 0.832599 + outer loop + vertex 224.599 -23.983 16.5254 + vertex 225.405 -25.6755 15.3431 + vertex 235.124 -22.7103 16.5236 + endloop + endfacet + facet normal 0.0665858 -0.549748 0.832673 + outer loop + vertex 235.124 -22.7103 16.5236 + vertex 225.405 -25.6755 15.3431 + vertex 235.923 -24.402 15.3428 + endloop + endfacet + facet normal 0.0575243 -0.549649 0.833413 + outer loop + vertex 192.758 -27.4899 16.525 + vertex 193.542 -29.1983 15.3442 + vertex 203.402 -26.3755 16.5253 + endloop + endfacet + facet normal 0.05824 -0.551591 0.832079 + outer loop + vertex 203.402 -26.3755 16.5253 + vertex 193.542 -29.1983 15.3442 + vertex 204.19 -28.0763 15.3426 + endloop + endfacet + facet normal 0.0482505 -0.428703 0.902156 + outer loop + vertex 191.088 -25.8144 17.4105 + vertex 192.758 -27.4899 16.525 + vertex 202.408 -24.2328 17.5566 + endloop + endfacet + facet normal 0.0436153 -0.416804 0.907949 + outer loop + vertex 202.408 -24.2328 17.5566 + vertex 192.758 -27.4899 16.525 + vertex 203.402 -26.3755 16.5253 + endloop + endfacet + facet normal 0.0420482 -0.417429 0.907736 + outer loop + vertex 202.408 -24.2328 17.5566 + vertex 203.402 -26.3755 16.5253 + vertex 212.344 -23.5483 17.4112 + endloop + endfacet + facet normal 0.0474658 -0.43229 0.900484 + outer loop + vertex 212.344 -23.5483 17.4112 + vertex 203.402 -26.3755 16.5253 + vertex 214.02 -25.2066 16.5267 + endloop + endfacet + facet normal 0.0605206 -0.550791 0.832446 + outer loop + vertex 203.402 -26.3755 16.5253 + vertex 204.19 -28.0763 15.3426 + vertex 214.02 -25.2066 16.5267 + endloop + endfacet + facet normal 0.0605214 -0.550793 0.832445 + outer loop + vertex 214.02 -25.2066 16.5267 + vertex 204.19 -28.0763 15.3426 + vertex 214.824 -26.9042 15.3451 + endloop + endfacet + facet normal 0.0517385 -0.551086 0.832843 + outer loop + vertex 171.297 -29.5576 16.5261 + vertex 172.091 -31.2706 15.3433 + vertex 182.06 -28.5499 16.5243 + endloop + endfacet + facet normal 0.0520838 -0.552061 0.832175 + outer loop + vertex 182.06 -28.5499 16.5243 + vertex 172.091 -31.2706 15.3433 + vertex 182.844 -30.2587 15.3416 + endloop + endfacet + facet normal 0.0434356 -0.428592 0.902454 + outer loop + vertex 169.598 -27.865 17.4118 + vertex 171.297 -29.5576 16.5261 + vertex 181.055 -26.3981 17.557 + endloop + endfacet + facet normal 0.0392334 -0.417385 0.907882 + outer loop + vertex 181.055 -26.3981 17.557 + vertex 171.297 -29.5576 16.5261 + vertex 182.06 -28.5499 16.5243 + endloop + endfacet + facet normal 0.0375733 -0.418048 0.907648 + outer loop + vertex 181.055 -26.3981 17.557 + vertex 182.06 -28.5499 16.5243 + vertex 191.088 -25.8144 17.4105 + endloop + endfacet + facet normal 0.0428556 -0.433109 0.900322 + outer loop + vertex 191.088 -25.8144 17.4105 + vertex 182.06 -28.5499 16.5243 + vertex 192.758 -27.4899 16.525 + endloop + endfacet + facet normal 0.0545621 -0.551206 0.832583 + outer loop + vertex 182.06 -28.5499 16.5243 + vertex 182.844 -30.2587 15.3416 + vertex 192.758 -27.4899 16.525 + endloop + endfacet + facet normal 0.0543925 -0.550737 0.832905 + outer loop + vertex 192.758 -27.4899 16.525 + vertex 182.844 -30.2587 15.3416 + vertex 193.542 -29.1983 15.3442 + endloop + endfacet + facet normal 0.0454556 -0.553033 0.831918 + outer loop + vertex 149.623 -31.3941 16.5261 + vertex 150.422 -33.1111 15.341 + vertex 160.464 -30.5053 16.5246 + endloop + endfacet + facet normal 0.0447485 -0.550952 0.833336 + outer loop + vertex 160.464 -30.5053 16.5246 + vertex 150.422 -33.1111 15.341 + vertex 161.273 -32.2248 15.3443 + endloop + endfacet + facet normal 0.0384333 -0.429007 0.902483 + outer loop + vertex 147.943 -29.6812 17.4119 + vertex 149.623 -31.3941 16.5261 + vertex 159.462 -28.342 17.558 + endloop + endfacet + facet normal 0.0343747 -0.417758 0.907908 + outer loop + vertex 159.462 -28.342 17.558 + vertex 149.623 -31.3941 16.5261 + vertex 160.464 -30.5053 16.5246 + endloop + endfacet + facet normal 0.032782 -0.418386 0.907678 + outer loop + vertex 159.462 -28.342 17.558 + vertex 160.464 -30.5053 16.5246 + vertex 169.598 -27.865 17.4118 + endloop + endfacet + facet normal 0.037776 -0.433244 0.900485 + outer loop + vertex 169.598 -27.865 17.4118 + vertex 160.464 -30.5053 16.5246 + vertex 171.297 -29.5576 16.5261 + endloop + endfacet + facet normal 0.0479835 -0.549821 0.833903 + outer loop + vertex 160.464 -30.5053 16.5246 + vertex 161.273 -32.2248 15.3443 + vertex 171.297 -29.5576 16.5261 + endloop + endfacet + facet normal 0.0487775 -0.552113 0.832342 + outer loop + vertex 171.297 -29.5576 16.5261 + vertex 161.273 -32.2248 15.3443 + vertex 172.091 -31.2706 15.3433 + endloop + endfacet + facet normal 0.0384149 -0.551501 0.833289 + outer loop + vertex 128.088 -32.9627 16.5247 + vertex 128.873 -34.6941 15.3425 + vertex 138.82 -32.214 16.5254 + endloop + endfacet + facet normal 0.0387117 -0.552401 0.832679 + outer loop + vertex 138.82 -32.214 16.5254 + vertex 128.873 -34.6941 15.3425 + vertex 139.616 -33.94 15.3434 + endloop + endfacet + facet normal 0.0334033 -0.429677 0.902365 + outer loop + vertex 126.452 -31.2288 17.4109 + vertex 128.088 -32.9627 16.5247 + vertex 137.87 -30.034 17.5571 + endloop + endfacet + facet normal 0.0290426 -0.41722 0.908341 + outer loop + vertex 137.87 -30.034 17.5571 + vertex 128.088 -32.9627 16.5247 + vertex 138.82 -32.214 16.5254 + endloop + endfacet + facet normal 0.0277198 -0.41771 0.908158 + outer loop + vertex 137.87 -30.034 17.5571 + vertex 138.82 -32.214 16.5254 + vertex 147.943 -29.6812 17.4119 + endloop + endfacet + facet normal 0.032841 -0.433495 0.900557 + outer loop + vertex 147.943 -29.6812 17.4119 + vertex 138.82 -32.214 16.5254 + vertex 149.623 -31.3941 16.5261 + endloop + endfacet + facet normal 0.0417908 -0.551354 0.833224 + outer loop + vertex 138.82 -32.214 16.5254 + vertex 139.616 -33.94 15.3434 + vertex 149.623 -31.3941 16.5261 + endloop + endfacet + facet normal 0.0426737 -0.55399 0.831429 + outer loop + vertex 149.623 -31.3941 16.5261 + vertex 139.616 -33.94 15.3434 + vertex 150.422 -33.1111 15.341 + endloop + endfacet + facet normal 0.0318564 -0.553478 0.832255 + outer loop + vertex 106.811 -34.2575 16.5268 + vertex 107.581 -35.9946 15.3421 + vertex 117.427 -33.6462 16.527 + endloop + endfacet + facet normal 0.0317511 -0.553148 0.832477 + outer loop + vertex 117.427 -33.6462 16.527 + vertex 107.581 -35.9946 15.3421 + vertex 118.208 -35.3814 15.3443 + endloop + endfacet + facet normal 0.0275033 -0.426529 0.904056 + outer loop + vertex 105.17 -32.4975 17.4071 + vertex 106.811 -34.2575 16.5268 + vertex 116.486 -31.4516 17.5563 + endloop + endfacet + facet normal 0.0239435 -0.416073 0.909016 + outer loop + vertex 116.486 -31.4516 17.5563 + vertex 106.811 -34.2575 16.5268 + vertex 117.427 -33.6462 16.527 + endloop + endfacet + facet normal 0.0225768 -0.416569 0.908824 + outer loop + vertex 116.486 -31.4516 17.5563 + vertex 117.427 -33.6462 16.527 + vertex 126.452 -31.2288 17.4109 + endloop + endfacet + facet normal 0.0280131 -0.43384 0.900555 + outer loop + vertex 126.452 -31.2288 17.4109 + vertex 117.427 -33.6462 16.527 + vertex 128.088 -32.9627 16.5247 + endloop + endfacet + facet normal 0.0355671 -0.551895 0.833155 + outer loop + vertex 117.427 -33.6462 16.527 + vertex 118.208 -35.3814 15.3443 + vertex 128.088 -32.9627 16.5247 + endloop + endfacet + facet normal 0.0357303 -0.552396 0.832816 + outer loop + vertex 128.088 -32.9627 16.5247 + vertex 118.208 -35.3814 15.3443 + vertex 128.873 -34.6941 15.3425 + endloop + endfacet + facet normal 0.0248788 -0.551832 0.833584 + outer loop + vertex 85.5398 -35.2848 16.5244 + vertex 86.3175 -37.0349 15.3426 + vertex 96.2011 -34.8028 16.5253 + endloop + endfacet + facet normal 0.024854 -0.551751 0.833639 + outer loop + vertex 96.2011 -34.8028 16.5253 + vertex 86.3175 -37.0349 15.3426 + vertex 96.9788 -36.5507 15.3453 + endloop + endfacet + facet normal 0.0222981 -0.429179 0.902944 + outer loop + vertex 83.8549 -33.5117 17.4088 + vertex 85.5398 -35.2848 16.5244 + vertex 95.2284 -32.6045 17.5591 + endloop + endfacet + facet normal 0.0188519 -0.418654 0.90795 + outer loop + vertex 95.2284 -32.6045 17.5591 + vertex 85.5398 -35.2848 16.5244 + vertex 96.2011 -34.8028 16.5253 + endloop + endfacet + facet normal 0.0183884 -0.418826 0.90788 + outer loop + vertex 95.2284 -32.6045 17.5591 + vertex 96.2011 -34.8028 16.5253 + vertex 105.17 -32.4975 17.4071 + endloop + endfacet + facet normal 0.0220058 -0.430732 0.902212 + outer loop + vertex 105.17 -32.4975 17.4071 + vertex 96.2011 -34.8028 16.5253 + vertex 106.811 -34.2575 16.5268 + endloop + endfacet + facet normal 0.0281804 -0.550678 0.834242 + outer loop + vertex 96.2011 -34.8028 16.5253 + vertex 96.9788 -36.5507 15.3453 + vertex 106.811 -34.2575 16.5268 + endloop + endfacet + facet normal 0.0293174 -0.554296 0.831803 + outer loop + vertex 106.811 -34.2575 16.5268 + vertex 96.9788 -36.5507 15.3453 + vertex 107.581 -35.9946 15.3421 + endloop + endfacet + facet normal 0.018646 -0.551376 0.834048 + outer loop + vertex 63.8608 -36.0721 16.527 + vertex 64.6749 -37.832 15.3453 + vertex 74.7591 -35.7073 16.5245 + endloop + endfacet + facet normal 0.0188752 -0.55217 0.833518 + outer loop + vertex 74.7591 -35.7073 16.5245 + vertex 64.6749 -37.832 15.3453 + vertex 75.5575 -37.4628 15.3435 + endloop + endfacet + facet normal 0.017493 -0.428555 0.903346 + outer loop + vertex 62.1471 -34.2791 17.4108 + vertex 63.8608 -36.0721 16.527 + vertex 73.7236 -33.4983 17.5571 + endloop + endfacet + facet normal 0.0141973 -0.417935 0.908366 + outer loop + vertex 73.7236 -33.4983 17.5571 + vertex 63.8608 -36.0721 16.527 + vertex 74.7591 -35.7073 16.5245 + endloop + endfacet + facet normal 0.0127365 -0.418507 0.908124 + outer loop + vertex 73.7236 -33.4983 17.5571 + vertex 74.7591 -35.7073 16.5245 + vertex 83.8549 -33.5117 17.4088 + endloop + endfacet + facet normal 0.0169907 -0.433298 0.901091 + outer loop + vertex 83.8549 -33.5117 17.4088 + vertex 74.7591 -35.7073 16.5245 + vertex 85.5398 -35.2848 16.5244 + endloop + endfacet + facet normal 0.0216145 -0.551277 0.834042 + outer loop + vertex 74.7591 -35.7073 16.5245 + vertex 75.5575 -37.4628 15.3435 + vertex 85.5398 -35.2848 16.5244 + endloop + endfacet + facet normal 0.022049 -0.552738 0.833064 + outer loop + vertex 85.5398 -35.2848 16.5244 + vertex 75.5575 -37.4628 15.3435 + vertex 86.3175 -37.0349 15.3426 + endloop + endfacet + facet normal 0.0127421 -0.551266 0.834232 + outer loop + vertex 42.0965 -36.6157 16.5269 + vertex 42.8717 -38.3858 15.3454 + vertex 52.927 -36.37 16.5238 + endloop + endfacet + facet normal 0.0127647 -0.551348 0.834178 + outer loop + vertex 52.927 -36.37 16.5238 + vertex 42.8717 -38.3858 15.3454 + vertex 53.7321 -38.1366 15.3438 + endloop + endfacet + facet normal 0.0130171 -0.428758 0.903326 + outer loop + vertex 40.469 -34.803 17.4107 + vertex 42.0965 -36.6157 16.5269 + vertex 51.9662 -34.1488 17.5555 + endloop + endfacet + facet normal 0.00973428 -0.41778 0.908496 + outer loop + vertex 51.9662 -34.1488 17.5555 + vertex 42.0965 -36.6157 16.5269 + vertex 52.927 -36.37 16.5238 + endloop + endfacet + facet normal 0.00755424 -0.418564 0.908156 + outer loop + vertex 51.9662 -34.1488 17.5555 + vertex 52.927 -36.37 16.5238 + vertex 62.1471 -34.2791 17.4108 + endloop + endfacet + facet normal 0.0115399 -0.433199 0.901224 + outer loop + vertex 62.1471 -34.2791 17.4108 + vertex 52.927 -36.37 16.5238 + vertex 63.8608 -36.0721 16.527 + endloop + endfacet + facet normal 0.0147613 -0.550701 0.834572 + outer loop + vertex 52.927 -36.37 16.5238 + vertex 53.7321 -38.1366 15.3438 + vertex 63.8608 -36.0721 16.527 + endloop + endfacet + facet normal 0.0152655 -0.552491 0.833379 + outer loop + vertex 63.8608 -36.0721 16.527 + vertex 53.7321 -38.1366 15.3438 + vertex 64.6749 -37.832 15.3453 + endloop + endfacet + facet normal 0.00612407 -0.548478 0.836142 + outer loop + vertex 20.7436 -36.9163 16.5228 + vertex 21.5217 -38.7018 15.3459 + vertex 31.3879 -36.7949 16.5245 + endloop + endfacet + facet normal 0.00715089 -0.552249 0.833648 + outer loop + vertex 31.3879 -36.7949 16.5245 + vertex 21.5217 -38.7018 15.3459 + vertex 32.1446 -38.5688 15.3429 + endloop + endfacet + facet normal 0.00833921 -0.430933 0.902345 + outer loop + vertex 19.1034 -35.091 17.4097 + vertex 20.7436 -36.9163 16.5228 + vertex 30.473 -34.563 17.5568 + endloop + endfacet + facet normal 0.00462663 -0.418216 0.908336 + outer loop + vertex 30.473 -34.563 17.5568 + vertex 20.7436 -36.9163 16.5228 + vertex 31.3879 -36.7949 16.5245 + endloop + endfacet + facet normal 0.00321969 -0.418693 0.908122 + outer loop + vertex 30.473 -34.563 17.5568 + vertex 31.3879 -36.7949 16.5245 + vertex 40.469 -34.803 17.4107 + endloop + endfacet + facet normal 0.00705124 -0.433128 0.901305 + outer loop + vertex 40.469 -34.803 17.4107 + vertex 31.3879 -36.7949 16.5245 + vertex 42.0965 -36.6157 16.5269 + endloop + endfacet + facet normal 0.00904972 -0.551679 0.834008 + outer loop + vertex 31.3879 -36.7949 16.5245 + vertex 32.1446 -38.5688 15.3429 + vertex 42.0965 -36.6157 16.5269 + endloop + endfacet + facet normal 0.00923537 -0.552353 0.833559 + outer loop + vertex 42.0965 -36.6157 16.5269 + vertex 32.1446 -38.5688 15.3429 + vertex 42.8717 -38.3858 15.3454 + endloop + endfacet + facet normal 0.000953507 -0.552367 0.833601 + outer loop + vertex -0.648795 -37.0101 16.5246 + vertex 0.15622 -38.7937 15.3418 + vertex 10.0733 -36.9908 16.5252 + endloop + endfacet + facet normal 0.000686893 -0.551345 0.834277 + outer loop + vertex 10.0733 -36.9908 16.5252 + vertex 0.15622 -38.7937 15.3418 + vertex 10.8735 -38.7752 15.3452 + endloop + endfacet + facet normal 0.00384592 -0.430384 0.902638 + outer loop + vertex -2.30445 -35.1684 17.4098 + vertex -0.648795 -37.0101 16.5246 + vertex 9.09258 -34.7531 17.5592 + endloop + endfacet + facet normal 0.000709565 -0.419247 0.907872 + outer loop + vertex 9.09258 -34.7531 17.5592 + vertex -0.648795 -37.0101 16.5246 + vertex 10.0733 -36.9908 16.5252 + endloop + endfacet + facet normal -0.00060774 -0.419722 0.907652 + outer loop + vertex 9.09258 -34.7531 17.5592 + vertex 10.0733 -36.9908 16.5252 + vertex 19.1034 -35.091 17.4097 + endloop + endfacet + facet normal 0.00322915 -0.434669 0.900584 + outer loop + vertex 19.1034 -35.091 17.4097 + vertex 10.0733 -36.9908 16.5252 + vertex 20.7436 -36.9163 16.5228 + endloop + endfacet + facet normal 0.00402112 -0.550299 0.834958 + outer loop + vertex 10.0733 -36.9908 16.5252 + vertex 10.8735 -38.7752 15.3452 + vertex 20.7436 -36.9163 16.5228 + endloop + endfacet + facet normal 0.00373091 -0.549212 0.835674 + outer loop + vertex 20.7436 -36.9163 16.5228 + vertex 10.8735 -38.7752 15.3452 + vertex 21.5217 -38.7018 15.3459 + endloop + endfacet + facet normal -0.00439587 -0.550666 0.834714 + outer loop + vertex -21.8891 -36.906 16.5236 + vertex -21.1417 -38.7005 15.3437 + vertex -11.3245 -36.9856 16.5268 + endloop + endfacet + facet normal -0.00371481 -0.553344 0.832944 + outer loop + vertex -11.3245 -36.9856 16.5268 + vertex -21.1417 -38.7005 15.3437 + vertex -10.5438 -38.772 15.3434 + endloop + endfacet + facet normal 0.000313696 -0.43076 0.902466 + outer loop + vertex -23.4664 -35.0509 17.4096 + vertex -21.8891 -36.906 16.5236 + vertex -12.2403 -34.7361 17.556 + endloop + endfacet + facet normal -0.00341194 -0.417209 0.908804 + outer loop + vertex -12.2403 -34.7361 17.556 + vertex -21.8891 -36.906 16.5236 + vertex -11.3245 -36.9856 16.5268 + endloop + endfacet + facet normal -0.00480532 -0.417675 0.908584 + outer loop + vertex -12.2403 -34.7361 17.556 + vertex -11.3245 -36.9856 16.5268 + vertex -2.30445 -35.1684 17.4098 + endloop + endfacet + facet normal -0.000816712 -0.433794 0.901012 + outer loop + vertex -2.30445 -35.1684 17.4098 + vertex -11.3245 -36.9856 16.5268 + vertex -0.648795 -37.0101 16.5246 + endloop + endfacet + facet normal -0.00110307 -0.552555 0.833476 + outer loop + vertex -11.3245 -36.9856 16.5268 + vertex -10.5438 -38.772 15.3434 + vertex -0.648795 -37.0101 16.5246 + endloop + endfacet + facet normal -0.000994392 -0.552978 0.833196 + outer loop + vertex -0.648795 -37.0101 16.5246 + vertex -10.5438 -38.772 15.3434 + vertex 0.15622 -38.7937 15.3418 + endloop + endfacet + facet normal -0.00956147 -0.548991 0.835774 + outer loop + vertex -42.8821 -36.5998 16.5239 + vertex -42.1258 -38.4059 15.3462 + vertex -32.3566 -36.7822 16.5245 + endloop + endfacet + facet normal -0.00911272 -0.55082 0.834574 + outer loop + vertex -32.3566 -36.7822 16.5245 + vertex -42.1258 -38.4059 15.3462 + vertex -31.6254 -38.581 15.3453 + endloop + endfacet + facet normal -0.00437254 -0.430228 0.902709 + outer loop + vertex -44.553 -34.7239 17.4098 + vertex -42.8821 -36.5998 16.5239 + vertex -33.2829 -34.5268 17.5584 + endloop + endfacet + facet normal -0.00731582 -0.419177 0.907875 + outer loop + vertex -33.2829 -34.5268 17.5584 + vertex -42.8821 -36.5998 16.5239 + vertex -32.3566 -36.7822 16.5245 + endloop + endfacet + facet normal -0.00864868 -0.419624 0.907657 + outer loop + vertex -33.2829 -34.5268 17.5584 + vertex -32.3566 -36.7822 16.5245 + vertex -23.4664 -35.0509 17.4096 + endloop + endfacet + facet normal -0.00506142 -0.434473 0.900671 + outer loop + vertex -23.4664 -35.0509 17.4096 + vertex -32.3566 -36.7822 16.5245 + vertex -21.8891 -36.906 16.5236 + endloop + endfacet + facet normal -0.00643333 -0.550071 0.835093 + outer loop + vertex -32.3566 -36.7822 16.5245 + vertex -31.6254 -38.581 15.3453 + vertex -21.8891 -36.906 16.5236 + endloop + endfacet + facet normal -0.00615612 -0.551173 0.834369 + outer loop + vertex -21.8891 -36.906 16.5236 + vertex -31.6254 -38.581 15.3453 + vertex -21.1417 -38.7005 15.3437 + endloop + endfacet + facet normal -0.0160465 -0.552135 0.8336 + outer loop + vertex -64.6235 -36.0425 16.5244 + vertex -63.792 -37.852 15.3419 + vertex -53.6229 -36.3588 16.5267 + endloop + endfacet + facet normal -0.0158031 -0.553223 0.832883 + outer loop + vertex -53.6229 -36.3588 16.5267 + vertex -63.792 -37.852 15.3419 + vertex -52.8324 -38.1624 15.3437 + endloop + endfacet + facet normal -0.00930933 -0.428516 0.903486 + outer loop + vertex -66.3674 -34.1422 17.4077 + vertex -64.6235 -36.0425 16.5244 + vertex -54.7051 -34.0814 17.5568 + endloop + endfacet + facet normal -0.0121735 -0.416872 0.908884 + outer loop + vertex -54.7051 -34.0814 17.5568 + vertex -64.6235 -36.0425 16.5244 + vertex -53.6229 -36.3588 16.5267 + endloop + endfacet + facet normal -0.0132614 -0.417294 0.908675 + outer loop + vertex -54.7051 -34.0814 17.5568 + vertex -53.6229 -36.3588 16.5267 + vertex -44.553 -34.7239 17.4098 + endloop + endfacet + facet normal -0.00950326 -0.43394 0.900892 + outer loop + vertex -44.553 -34.7239 17.4098 + vertex -53.6229 -36.3588 16.5267 + vertex -42.8821 -36.5998 16.5239 + endloop + endfacet + facet normal -0.0121736 -0.552142 0.833661 + outer loop + vertex -53.6229 -36.3588 16.5267 + vertex -52.8324 -38.1624 15.3437 + vertex -42.8821 -36.5998 16.5239 + endloop + endfacet + facet normal -0.0127023 -0.549892 0.835139 + outer loop + vertex -42.8821 -36.5998 16.5239 + vertex -52.8324 -38.1624 15.3437 + vertex -42.1258 -38.4059 15.3462 + endloop + endfacet + facet normal -0.0216791 -0.55402 0.832221 + outer loop + vertex -86.5649 -35.2417 16.5276 + vertex -85.8067 -37.0523 15.342 + vertex -75.6753 -35.67 16.5261 + endloop + endfacet + facet normal -0.0219939 -0.552545 0.833193 + outer loop + vertex -75.6753 -35.67 16.5261 + vertex -85.8067 -37.0523 15.342 + vertex -74.8614 -37.4845 15.3443 + endloop + endfacet + facet normal -0.0141425 -0.426655 0.904304 + outer loop + vertex -88.1317 -33.3253 17.4072 + vertex -86.5649 -35.2417 16.5276 + vertex -76.6182 -33.3884 17.5576 + endloop + endfacet + facet normal -0.0162973 -0.417452 0.908553 + outer loop + vertex -76.6182 -33.3884 17.5576 + vertex -86.5649 -35.2417 16.5276 + vertex -75.6753 -35.67 16.5261 + endloop + endfacet + facet normal -0.0174536 -0.41784 0.908353 + outer loop + vertex -76.6182 -33.3884 17.5576 + vertex -75.6753 -35.67 16.5261 + vertex -66.3674 -34.1422 17.4077 + endloop + endfacet + facet normal -0.0144335 -0.43234 0.901595 + outer loop + vertex -66.3674 -34.1422 17.4077 + vertex -75.6753 -35.67 16.5261 + vertex -64.6235 -36.0425 16.5244 + endloop + endfacet + facet normal -0.0184591 -0.551476 0.833987 + outer loop + vertex -75.6753 -35.67 16.5261 + vertex -74.8614 -37.4845 15.3443 + vertex -64.6235 -36.0425 16.5244 + endloop + endfacet + facet normal -0.0181729 -0.552797 0.833118 + outer loop + vertex -64.6235 -36.0425 16.5244 + vertex -74.8614 -37.4845 15.3443 + vertex -63.792 -37.852 15.3419 + endloop + endfacet + facet normal -0.0287593 -0.551179 0.833891 + outer loop + vertex -107.579 -34.2188 16.5247 + vertex -106.872 -36.0424 15.3437 + vertex -97.1606 -34.7602 16.5262 + endloop + endfacet + facet normal -0.0281537 -0.554036 0.832016 + outer loop + vertex -97.1606 -34.7602 16.5262 + vertex -106.872 -36.0424 15.3437 + vertex -96.4534 -36.574 15.3422 + endloop + endfacet + facet normal -0.0193784 -0.428562 0.903305 + outer loop + vertex -109.163 -32.285 17.4082 + vertex -107.579 -34.2188 16.5247 + vertex -97.9759 -32.473 17.559 + endloop + endfacet + facet normal -0.0218449 -0.41791 0.908226 + outer loop + vertex -97.9759 -32.473 17.559 + vertex -107.579 -34.2188 16.5247 + vertex -97.1606 -34.7602 16.5262 + endloop + endfacet + facet normal -0.022193 -0.41801 0.908171 + outer loop + vertex -97.9759 -32.473 17.559 + vertex -97.1606 -34.7602 16.5262 + vertex -88.1317 -33.3253 17.4072 + endloop + endfacet + facet normal -0.0196771 -0.430332 0.902456 + outer loop + vertex -88.1317 -33.3253 17.4072 + vertex -97.1606 -34.7602 16.5262 + vertex -86.5649 -35.2417 16.5276 + endloop + endfacet + facet normal -0.0252558 -0.553291 0.832605 + outer loop + vertex -97.1606 -34.7602 16.5262 + vertex -96.4534 -36.574 15.3422 + vertex -86.5649 -35.2417 16.5276 + endloop + endfacet + facet normal -0.0249076 -0.55492 0.831531 + outer loop + vertex -86.5649 -35.2417 16.5276 + vertex -96.4534 -36.574 15.3422 + vertex -85.8067 -37.0523 15.342 + endloop + endfacet + facet normal -0.036033 -0.549624 0.834635 + outer loop + vertex -128.835 -32.9092 16.5241 + vertex -128.011 -34.7532 15.3453 + vertex -118.081 -33.6097 16.527 + endloop + endfacet + facet normal -0.0351989 -0.553946 0.831808 + outer loop + vertex -118.081 -33.6097 16.527 + vertex -128.011 -34.7532 15.3453 + vertex -117.327 -35.4358 15.3428 + endloop + endfacet + facet normal -0.0250541 -0.429134 0.902893 + outer loop + vertex -130.562 -30.9483 17.4081 + vertex -128.835 -32.9092 16.5241 + vertex -119.097 -31.2982 17.5599 + endloop + endfacet + facet normal -0.0274709 -0.417869 0.908092 + outer loop + vertex -119.097 -31.2982 17.5599 + vertex -128.835 -32.9092 16.5241 + vertex -118.081 -33.6097 16.527 + endloop + endfacet + facet normal -0.0276416 -0.417929 0.908059 + outer loop + vertex -119.097 -31.2982 17.5599 + vertex -118.081 -33.6097 16.527 + vertex -109.163 -32.285 17.4082 + endloop + endfacet + facet normal -0.024867 -0.432201 0.901434 + outer loop + vertex -109.163 -32.285 17.4082 + vertex -118.081 -33.6097 16.527 + vertex -107.579 -34.2188 16.5247 + endloop + endfacet + facet normal -0.0318923 -0.553052 0.832536 + outer loop + vertex -118.081 -33.6097 16.527 + vertex -117.327 -35.4358 15.3428 + vertex -107.579 -34.2188 16.5247 + endloop + endfacet + facet normal -0.0321011 -0.55203 0.833206 + outer loop + vertex -107.579 -34.2188 16.5247 + vertex -117.327 -35.4358 15.3428 + vertex -106.872 -36.0424 15.3437 + endloop + endfacet + facet normal -0.0423751 -0.552184 0.832645 + outer loop + vertex -150.637 -31.3111 16.5247 + vertex -149.867 -33.1539 15.3419 + vertex -139.742 -32.1441 16.5268 + endloop + endfacet + facet normal -0.042176 -0.553313 0.831905 + outer loop + vertex -139.742 -32.1441 16.5268 + vertex -149.867 -33.1539 15.3419 + vertex -138.932 -33.9848 15.3436 + endloop + endfacet + facet normal -0.0295317 -0.430603 0.902058 + outer loop + vertex -152.255 -29.3418 17.4118 + vertex -150.637 -31.3111 16.5247 + vertex -140.741 -29.8241 17.5585 + endloop + endfacet + facet normal -0.0321026 -0.417652 0.90804 + outer loop + vertex -140.741 -29.8241 17.5585 + vertex -150.637 -31.3111 16.5247 + vertex -139.742 -32.1441 16.5268 + endloop + endfacet + facet normal -0.0327337 -0.417869 0.907917 + outer loop + vertex -140.741 -29.8241 17.5585 + vertex -139.742 -32.1441 16.5268 + vertex -130.562 -30.9483 17.4081 + endloop + endfacet + facet normal -0.0301313 -0.432756 0.901008 + outer loop + vertex -130.562 -30.9483 17.4081 + vertex -139.742 -32.1441 16.5268 + vertex -128.835 -32.9092 16.5241 + endloop + endfacet + facet normal -0.038531 -0.552268 0.832776 + outer loop + vertex -139.742 -32.1441 16.5268 + vertex -138.932 -33.9848 15.3436 + vertex -128.835 -32.9092 16.5241 + endloop + endfacet + facet normal -0.0388625 -0.550456 0.833959 + outer loop + vertex -128.835 -32.9092 16.5241 + vertex -138.932 -33.9848 15.3436 + vertex -128.011 -34.7532 15.3453 + endloop + endfacet + facet normal -0.0486195 -0.547598 0.835328 + outer loop + vertex -171.962 -29.496 16.523 + vertex -171.233 -31.3561 15.346 + vertex -161.353 -30.4342 16.5254 + endloop + endfacet + facet normal -0.047814 -0.552313 0.832265 + outer loop + vertex -161.353 -30.4342 16.5254 + vertex -171.233 -31.3561 15.346 + vertex -160.632 -32.2787 15.3428 + endloop + endfacet + facet normal -0.0348948 -0.429138 0.902565 + outer loop + vertex -173.57 -27.5038 17.408 + vertex -171.962 -29.496 16.523 + vertex -162.226 -28.1117 17.5576 + endloop + endfacet + facet normal -0.037127 -0.417455 0.907939 + outer loop + vertex -162.226 -28.1117 17.5576 + vertex -171.962 -29.496 16.523 + vertex -161.353 -30.4342 16.5254 + endloop + endfacet + facet normal -0.0382736 -0.417795 0.907735 + outer loop + vertex -162.226 -28.1117 17.5576 + vertex -161.353 -30.4342 16.5254 + vertex -152.255 -29.3418 17.4118 + endloop + endfacet + facet normal -0.0355021 -0.434556 0.899945 + outer loop + vertex -152.255 -29.3418 17.4118 + vertex -161.353 -30.4342 16.5254 + vertex -150.637 -31.3111 16.5247 + endloop + endfacet + facet normal -0.0450862 -0.551633 0.832868 + outer loop + vertex -161.353 -30.4342 16.5254 + vertex -160.632 -32.2787 15.3428 + vertex -150.637 -31.3111 16.5247 + endloop + endfacet + facet normal -0.0448729 -0.552857 0.832067 + outer loop + vertex -150.637 -31.3111 16.5247 + vertex -160.632 -32.2787 15.3428 + vertex -149.867 -33.1539 15.3419 + endloop + endfacet + facet normal -0.0552717 -0.549856 0.833429 + outer loop + vertex -193.393 -27.419 16.5246 + vertex -192.594 -29.2894 15.3436 + vertex -182.614 -28.4991 16.5269 + endloop + endfacet + facet normal -0.0550074 -0.551547 0.832328 + outer loop + vertex -182.614 -28.4991 16.5269 + vertex -192.594 -29.2894 15.3436 + vertex -181.852 -30.3593 15.3446 + endloop + endfacet + facet normal -0.039842 -0.428849 0.902497 + outer loop + vertex -195.05 -25.4034 17.4092 + vertex -193.393 -27.419 16.5246 + vertex -183.586 -26.1541 17.5586 + endloop + endfacet + facet normal -0.0419637 -0.416888 0.907989 + outer loop + vertex -183.586 -26.1541 17.5586 + vertex -193.393 -27.419 16.5246 + vertex -182.614 -28.4991 16.5269 + endloop + endfacet + facet normal -0.0425548 -0.417082 0.907872 + outer loop + vertex -183.586 -26.1541 17.5586 + vertex -182.614 -28.4991 16.5269 + vertex -173.57 -27.5038 17.408 + endloop + endfacet + facet normal -0.0401537 -0.432559 0.900711 + outer loop + vertex -173.57 -27.5038 17.408 + vertex -182.614 -28.4991 16.5269 + vertex -171.962 -29.496 16.523 + endloop + endfacet + facet normal -0.0512229 -0.550564 0.83322 + outer loop + vertex -182.614 -28.4991 16.5269 + vertex -181.852 -30.3593 15.3446 + vertex -171.962 -29.496 16.523 + endloop + endfacet + facet normal -0.0515889 -0.548341 0.834662 + outer loop + vertex -171.962 -29.496 16.523 + vertex -181.852 -30.3593 15.3446 + vertex -171.233 -31.3561 15.346 + endloop + endfacet + facet normal -0.0608202 -0.54996 0.832973 + outer loop + vertex -214.746 -25.1212 16.5248 + vertex -214.022 -26.9905 15.3434 + vertex -204.154 -26.2905 16.5261 + endloop + endfacet + facet normal -0.0603551 -0.55308 0.830939 + outer loop + vertex -204.154 -26.2905 16.5261 + vertex -214.022 -26.9905 15.3434 + vertex -203.381 -28.1552 15.3411 + endloop + endfacet + facet normal -0.0442125 -0.429804 0.901839 + outer loop + vertex -216.263 -23.1055 17.411 + vertex -214.746 -25.1212 16.5248 + vertex -205.032 -23.9493 17.5595 + endloop + endfacet + facet normal -0.0462429 -0.417835 0.907345 + outer loop + vertex -205.032 -23.9493 17.5595 + vertex -214.746 -25.1212 16.5248 + vertex -204.154 -26.2905 16.5261 + endloop + endfacet + facet normal -0.047257 -0.418132 0.907156 + outer loop + vertex -205.032 -23.9493 17.5595 + vertex -204.154 -26.2905 16.5261 + vertex -195.05 -25.4034 17.4092 + endloop + endfacet + facet normal -0.0452235 -0.432414 0.90054 + outer loop + vertex -195.05 -25.4034 17.4092 + vertex -204.154 -26.2905 16.5261 + vertex -193.393 -27.419 16.5246 + endloop + endfacet + facet normal -0.0578178 -0.552421 0.831558 + outer loop + vertex -204.154 -26.2905 16.5261 + vertex -203.381 -28.1552 15.3411 + vertex -193.393 -27.419 16.5246 + endloop + endfacet + facet normal -0.0580897 -0.55062 0.832732 + outer loop + vertex -193.393 -27.419 16.5246 + vertex -203.381 -28.1552 15.3411 + vertex -192.594 -29.2894 15.3436 + endloop + endfacet + facet normal -0.0663085 -0.550856 0.831962 + outer loop + vertex -235.432 -22.6802 16.5279 + vertex -234.757 -24.5498 15.3438 + vertex -225.119 -23.9251 16.5255 + endloop + endfacet + facet normal -0.066148 -0.551966 0.831239 + outer loop + vertex -225.119 -23.9251 16.5255 + vertex -234.757 -24.5498 15.3438 + vertex -224.445 -25.7888 15.3416 + endloop + endfacet + facet normal -0.0485316 -0.425788 0.903521 + outer loop + vertex -237.021 -20.6305 17.4084 + vertex -235.432 -22.6802 16.5279 + vertex -225.941 -21.5779 17.5571 + endloop + endfacet + facet normal -0.0500709 -0.416492 0.90776 + outer loop + vertex -225.941 -21.5779 17.5571 + vertex -235.432 -22.6802 16.5279 + vertex -225.119 -23.9251 16.5255 + endloop + endfacet + facet normal -0.0521283 -0.417048 0.907388 + outer loop + vertex -225.941 -21.5779 17.5571 + vertex -225.119 -23.9251 16.5255 + vertex -216.263 -23.1055 17.411 + endloop + endfacet + facet normal -0.0498832 -0.433223 0.899905 + outer loop + vertex -216.263 -23.1055 17.411 + vertex -225.119 -23.9251 16.5255 + vertex -214.746 -25.1212 16.5248 + endloop + endfacet + facet normal -0.0635119 -0.551386 0.831829 + outer loop + vertex -225.119 -23.9251 16.5255 + vertex -224.445 -25.7888 15.3416 + vertex -214.746 -25.1212 16.5248 + endloop + endfacet + facet normal -0.0636236 -0.550633 0.83232 + outer loop + vertex -214.746 -25.1212 16.5248 + vertex -224.445 -25.7888 15.3416 + vertex -214.022 -26.9905 15.3434 + endloop + endfacet + facet normal -0.0726291 -0.549898 0.832068 + outer loop + vertex -256.749 -19.923 16.5244 + vertex -255.973 -21.8152 15.3416 + vertex -245.946 -21.3481 16.5255 + endloop + endfacet + facet normal -0.0726513 -0.549718 0.832185 + outer loop + vertex -245.946 -21.3481 16.5255 + vertex -255.973 -21.8152 15.3416 + vertex -245.211 -23.2331 15.3445 + endloop + endfacet + facet normal -0.0536499 -0.427592 0.902379 + outer loop + vertex -258.464 -17.8428 17.4081 + vertex -256.749 -19.923 16.5244 + vertex -246.96 -18.9672 17.5593 + endloop + endfacet + facet normal -0.0551485 -0.417333 0.907079 + outer loop + vertex -246.96 -18.9672 17.5593 + vertex -256.749 -19.923 16.5244 + vertex -245.946 -21.3481 16.5255 + endloop + endfacet + facet normal -0.0561322 -0.41766 0.906868 + outer loop + vertex -246.96 -18.9672 17.5593 + vertex -245.946 -21.3481 16.5255 + vertex -237.021 -20.6305 17.4084 + endloop + endfacet + facet normal -0.0546287 -0.429592 0.901369 + outer loop + vertex -237.021 -20.6305 17.4084 + vertex -245.946 -21.3481 16.5255 + vertex -235.432 -22.6802 16.5279 + endloop + endfacet + facet normal -0.0697451 -0.549027 0.832889 + outer loop + vertex -245.946 -21.3481 16.5255 + vertex -245.211 -23.2331 15.3445 + vertex -235.432 -22.6802 16.5279 + endloop + endfacet + facet normal -0.0694066 -0.551531 0.831262 + outer loop + vertex -235.432 -22.6802 16.5279 + vertex -245.211 -23.2331 15.3445 + vertex -234.757 -24.5498 15.3438 + endloop + endfacet + facet normal -0.0777801 -0.545622 0.834414 + outer loop + vertex -278.725 -16.8604 16.523 + vertex -277.964 -18.769 15.3459 + vertex -267.733 -18.4229 16.5259 + endloop + endfacet + facet normal -0.0772082 -0.550887 0.831001 + outer loop + vertex -267.733 -18.4229 16.5259 + vertex -277.964 -18.769 15.3459 + vertex -266.957 -20.3176 15.3419 + endloop + endfacet + facet normal -0.0579369 -0.428219 0.901816 + outer loop + vertex -280.325 -14.78 17.4081 + vertex -278.725 -16.8604 16.523 + vertex -268.708 -16.0352 17.5584 + endloop + endfacet + facet normal -0.059452 -0.416544 0.907169 + outer loop + vertex -268.708 -16.0352 17.5584 + vertex -278.725 -16.8604 16.523 + vertex -267.733 -18.4229 16.5259 + endloop + endfacet + facet normal -0.0602422 -0.416795 0.907002 + outer loop + vertex -268.708 -16.0352 17.5584 + vertex -267.733 -18.4229 16.5259 + vertex -258.464 -17.8428 17.4081 + endloop + endfacet + facet normal -0.0587325 -0.430964 0.900456 + outer loop + vertex -258.464 -17.8428 17.4081 + vertex -267.733 -18.4229 16.5259 + vertex -256.749 -19.923 16.5244 + endloop + endfacet + facet normal -0.075047 -0.550349 0.831555 + outer loop + vertex -267.733 -18.4229 16.5259 + vertex -266.957 -20.3176 15.3419 + vertex -256.749 -19.923 16.5244 + endloop + endfacet + facet normal -0.0750297 -0.550501 0.831456 + outer loop + vertex -256.749 -19.923 16.5244 + vertex -266.957 -20.3176 15.3419 + vertex -255.973 -21.8152 15.3416 + endloop + endfacet + facet normal -0.0832527 -0.545065 0.83425 + outer loop + vertex -300.089 -13.6726 16.5232 + vertex -299.391 -15.5808 15.3461 + vertex -289.519 -15.2816 16.5267 + endloop + endfacet + facet normal -0.0827926 -0.549342 0.831486 + outer loop + vertex -289.519 -15.2816 16.5267 + vertex -299.391 -15.5808 15.3461 + vertex -288.807 -17.1794 15.3438 + endloop + endfacet + facet normal -0.0616835 -0.429198 0.901102 + outer loop + vertex -301.588 -11.5935 17.4108 + vertex -300.089 -13.6726 16.5232 + vertex -290.32 -12.9059 17.5571 + endloop + endfacet + facet normal -0.0634824 -0.415028 0.907591 + outer loop + vertex -290.32 -12.9059 17.5571 + vertex -300.089 -13.6726 16.5232 + vertex -289.519 -15.2816 16.5267 + endloop + endfacet + facet normal -0.0643329 -0.415246 0.907432 + outer loop + vertex -290.32 -12.9059 17.5571 + vertex -289.519 -15.2816 16.5267 + vertex -280.325 -14.78 17.4081 + endloop + endfacet + facet normal -0.0627581 -0.431187 0.900077 + outer loop + vertex -280.325 -14.78 17.4081 + vertex -289.519 -15.2816 16.5267 + vertex -278.725 -16.8604 16.523 + endloop + endfacet + facet normal -0.0799709 -0.548713 0.832177 + outer loop + vertex -289.519 -15.2816 16.5267 + vertex -288.807 -17.1794 15.3438 + vertex -278.725 -16.8604 16.523 + endloop + endfacet + facet normal -0.0802387 -0.546218 0.833791 + outer loop + vertex -278.725 -16.8604 16.523 + vertex -288.807 -17.1794 15.3438 + vertex -277.964 -18.769 15.3459 + endloop + endfacet + facet normal -0.0889381 -0.549056 0.83104 + outer loop + vertex -320.782 -10.3824 16.5244 + vertex -320.085 -12.287 15.3408 + vertex -310.478 -12.0494 16.5259 + endloop + endfacet + facet normal -0.0889949 -0.548514 0.831392 + outer loop + vertex -310.478 -12.0494 16.5259 + vertex -320.085 -12.287 15.3408 + vertex -309.784 -13.9531 15.3442 + endloop + endfacet + facet normal -0.0656321 -0.42863 0.901093 + outer loop + vertex -322.308 -8.28338 17.4118 + vertex -320.782 -10.3824 16.5244 + vertex -311.279 -9.66654 17.5572 + endloop + endfacet + facet normal -0.0673047 -0.415254 0.907212 + outer loop + vertex -311.279 -9.66654 17.5572 + vertex -320.782 -10.3824 16.5244 + vertex -310.478 -12.0494 16.5259 + endloop + endfacet + facet normal -0.0689611 -0.415673 0.906896 + outer loop + vertex -311.279 -9.66654 17.5572 + vertex -310.478 -12.0494 16.5259 + vertex -301.588 -11.5935 17.4108 + endloop + endfacet + facet normal -0.0673303 -0.432435 0.899148 + outer loop + vertex -301.588 -11.5935 17.4108 + vertex -310.478 -12.0494 16.5259 + vertex -300.089 -13.6726 16.5232 + endloop + endfacet + facet normal -0.0853653 -0.547742 0.832281 + outer loop + vertex -310.478 -12.0494 16.5259 + vertex -309.784 -13.9531 15.3442 + vertex -300.089 -13.6726 16.5232 + endloop + endfacet + facet normal -0.0855983 -0.545572 0.833681 + outer loop + vertex -300.089 -13.6726 16.5232 + vertex -309.784 -13.9531 15.3442 + vertex -299.391 -15.5808 15.3461 + endloop + endfacet + facet normal -0.0937297 -0.546907 0.83193 + outer loop + vertex -341.395 -6.90761 16.5246 + vertex -340.693 -8.82467 15.3434 + vertex -331.071 -8.67479 16.5261 + endloop + endfacet + facet normal -0.0934543 -0.549796 0.830055 + outer loop + vertex -331.071 -8.67479 16.5261 + vertex -340.693 -8.82467 15.3434 + vertex -330.37 -10.5821 15.3416 + endloop + endfacet + facet normal -0.0698439 -0.427311 0.901403 + outer loop + vertex -342.944 -4.78771 17.4095 + vertex -341.395 -6.90761 16.5246 + vertex -331.934 -6.27471 17.5577 + endloop + endfacet + facet normal -0.0712336 -0.415411 0.90684 + outer loop + vertex -331.934 -6.27471 17.5577 + vertex -341.395 -6.90761 16.5246 + vertex -331.071 -8.67479 16.5261 + endloop + endfacet + facet normal -0.073046 -0.415903 0.90647 + outer loop + vertex -331.934 -6.27471 17.5577 + vertex -331.071 -8.67479 16.5261 + vertex -322.308 -8.28338 17.4118 + endloop + endfacet + facet normal -0.0715693 -0.43206 0.899 + outer loop + vertex -322.308 -8.28338 17.4118 + vertex -331.071 -8.67479 16.5261 + vertex -320.782 -10.3824 16.5244 + endloop + endfacet + facet normal -0.0910366 -0.549284 0.830662 + outer loop + vertex -331.071 -8.67479 16.5261 + vertex -330.37 -10.5821 15.3416 + vertex -320.782 -10.3824 16.5244 + endloop + endfacet + facet normal -0.0910152 -0.549496 0.830524 + outer loop + vertex -320.782 -10.3824 16.5244 + vertex -330.37 -10.5821 15.3416 + vertex -320.085 -12.287 15.3408 + endloop + endfacet + facet normal -0.0990485 -0.547361 0.831014 + outer loop + vertex -362.174 -3.20943 16.5237 + vertex -361.5 -5.12647 15.3414 + vertex -351.76 -5.09002 16.5263 + endloop + endfacet + facet normal -0.0990128 -0.547793 0.830734 + outer loop + vertex -351.76 -5.09002 16.5263 + vertex -361.5 -5.12647 15.3414 + vertex -351.07 -7.00739 15.3442 + endloop + endfacet + facet normal -0.0735755 -0.427107 0.901203 + outer loop + vertex -363.716 -1.07479 17.4095 + vertex -362.174 -3.20943 16.5237 + vertex -352.639 -2.67494 17.5555 + endloop + endfacet + facet normal -0.0749677 -0.413903 0.907229 + outer loop + vertex -352.639 -2.67494 17.5555 + vertex -362.174 -3.20943 16.5237 + vertex -351.76 -5.09002 16.5263 + endloop + endfacet + facet normal -0.0766434 -0.414363 0.906879 + outer loop + vertex -352.639 -2.67494 17.5555 + vertex -351.76 -5.09002 16.5263 + vertex -342.944 -4.78771 17.4095 + endloop + endfacet + facet normal -0.0753443 -0.430507 0.899437 + outer loop + vertex -342.944 -4.78771 17.4095 + vertex -351.76 -5.09002 16.5263 + vertex -341.395 -6.90761 16.5246 + endloop + endfacet + facet normal -0.0958093 -0.547138 0.831541 + outer loop + vertex -351.76 -5.09002 16.5263 + vertex -351.07 -7.00739 15.3442 + vertex -341.395 -6.90761 16.5246 + endloop + endfacet + facet normal -0.0957911 -0.547342 0.831409 + outer loop + vertex -341.395 -6.90761 16.5246 + vertex -351.07 -7.00739 15.3442 + vertex -340.693 -8.82467 15.3434 + endloop + endfacet + facet normal -0.104191 -0.546888 0.830697 + outer loop + vertex -383.192 0.732197 16.5225 + vertex -382.518 -1.19283 15.3397 + vertex -372.628 -1.27719 16.5246 + endloop + endfacet + facet normal -0.10419 -0.546904 0.830687 + outer loop + vertex -372.628 -1.27719 16.5246 + vertex -382.518 -1.19283 15.3397 + vertex -371.962 -3.1984 15.3432 + endloop + endfacet + facet normal -0.0777818 -0.425612 0.901557 + outer loop + vertex -384.779 2.89793 17.408 + vertex -383.192 0.732197 16.5225 + vertex -373.514 1.15139 17.5554 + endloop + endfacet + facet normal -0.0788754 -0.413724 0.906979 + outer loop + vertex -373.514 1.15139 17.5554 + vertex -383.192 0.732197 16.5225 + vertex -372.628 -1.27719 16.5246 + endloop + endfacet + facet normal -0.0806146 -0.414201 0.906609 + outer loop + vertex -373.514 1.15139 17.5554 + vertex -372.628 -1.27719 16.5246 + vertex -363.716 -1.07479 17.4095 + endloop + endfacet + facet normal -0.0794969 -0.430504 0.899081 + outer loop + vertex -363.716 -1.07479 17.4095 + vertex -372.628 -1.27719 16.5246 + vertex -362.174 -3.20943 16.5237 + endloop + endfacet + facet normal -0.100899 -0.546269 0.831511 + outer loop + vertex -372.628 -1.27719 16.5246 + vertex -371.962 -3.1984 15.3432 + vertex -362.174 -3.20943 16.5237 + endloop + endfacet + facet normal -0.100788 -0.547705 0.830579 + outer loop + vertex -362.174 -3.20943 16.5237 + vertex -371.962 -3.1984 15.3432 + vertex -361.5 -5.12647 15.3414 + endloop + endfacet + facet normal -0.108805 -0.54208 0.833253 + outer loop + vertex -404.757 5.00239 16.5196 + vertex -404.025 3.04411 15.3412 + vertex -393.911 2.82654 16.5203 + endloop + endfacet + facet normal -0.108636 -0.545217 0.831226 + outer loop + vertex -393.911 2.82654 16.5203 + vertex -404.025 3.04411 15.3412 + vertex -393.204 0.885545 15.3396 + endloop + endfacet + facet normal -0.0820953 -0.42695 0.900541 + outer loop + vertex -406.31 7.17932 17.4101 + vertex -404.757 5.00239 16.5196 + vertex -394.811 5.27211 17.5541 + endloop + endfacet + facet normal -0.0830779 -0.413815 0.906562 + outer loop + vertex -394.811 5.27211 17.5541 + vertex -404.757 5.00239 16.5196 + vertex -393.911 2.82654 16.5203 + endloop + endfacet + facet normal -0.0848467 -0.414303 0.906176 + outer loop + vertex -394.811 5.27211 17.5541 + vertex -393.911 2.82654 16.5203 + vertex -384.779 2.89793 17.408 + endloop + endfacet + facet normal -0.084057 -0.429271 0.899256 + outer loop + vertex -384.779 2.89793 17.408 + vertex -393.911 2.82654 16.5203 + vertex -383.192 0.732197 16.5225 + endloop + endfacet + facet normal -0.106616 -0.544805 0.831758 + outer loop + vertex -393.911 2.82654 16.5203 + vertex -393.204 0.885545 15.3396 + vertex -383.192 0.732197 16.5225 + endloop + endfacet + facet normal -0.106461 -0.547328 0.830119 + outer loop + vertex -383.192 0.732197 16.5225 + vertex -393.204 0.885545 15.3396 + vertex -382.518 -1.19283 15.3397 + endloop + endfacet + facet normal -0.113352 -0.544418 0.83112 + outer loop + vertex -426.071 9.42761 16.5409 + vertex -425.479 7.4915 15.3534 + vertex -415.542 7.21481 16.5275 + endloop + endfacet + facet normal -0.113279 -0.545916 0.830146 + outer loop + vertex -415.542 7.21481 16.5275 + vertex -425.479 7.4915 15.3534 + vertex -414.863 5.26954 15.3409 + endloop + endfacet + facet normal -0.084788 -0.424576 0.901413 + outer loop + vertex -427.385 11.5676 17.4253 + vertex -426.071 9.42761 16.5409 + vertex -416.232 9.62893 17.5612 + endloop + endfacet + facet normal -0.085589 -0.412765 0.906807 + outer loop + vertex -416.232 9.62893 17.5612 + vertex -426.071 9.42761 16.5409 + vertex -415.542 7.21481 16.5275 + endloop + endfacet + facet normal -0.0882376 -0.413308 0.906306 + outer loop + vertex -416.232 9.62893 17.5612 + vertex -415.542 7.21481 16.5275 + vertex -406.31 7.17932 17.4101 + endloop + endfacet + facet normal -0.0875609 -0.430037 0.898555 + outer loop + vertex -406.31 7.17932 17.4101 + vertex -415.542 7.21481 16.5275 + vertex -404.757 5.00239 16.5196 + endloop + endfacet + facet normal -0.111305 -0.545541 0.83066 + outer loop + vertex -415.542 7.21481 16.5275 + vertex -414.863 5.26954 15.3409 + vertex -404.757 5.00239 16.5196 + endloop + endfacet + facet normal -0.111447 -0.542638 0.83254 + outer loop + vertex -404.757 5.00239 16.5196 + vertex -414.863 5.26954 15.3409 + vertex -404.025 3.04411 15.3412 + endloop + endfacet + facet normal -0.119386 -0.548245 0.827753 + outer loop + vertex -446.157 13.7475 16.5324 + vertex -445.738 11.8719 15.3506 + vertex -436.233 11.6052 16.5448 + endloop + endfacet + facet normal -0.119527 -0.545628 0.829459 + outer loop + vertex -436.233 11.6052 16.5448 + vertex -445.738 11.8719 15.3506 + vertex -435.748 9.69697 15.3594 + endloop + endfacet + facet normal -0.0896361 -0.424499 0.900981 + outer loop + vertex -447.591 15.895 17.4016 + vertex -446.157 13.7475 16.5324 + vertex -436.812 13.9738 17.5688 + endloop + endfacet + facet normal -0.0904428 -0.413719 0.905901 + outer loop + vertex -436.812 13.9738 17.5688 + vertex -446.157 13.7475 16.5324 + vertex -436.233 11.6052 16.5448 + endloop + endfacet + facet normal -0.091879 -0.41396 0.905646 + outer loop + vertex -436.812 13.9738 17.5688 + vertex -436.233 11.6052 16.5448 + vertex -427.385 11.5676 17.4253 + endloop + endfacet + facet normal -0.0913055 -0.427702 0.899297 + outer loop + vertex -427.385 11.5676 17.4253 + vertex -436.233 11.6052 16.5448 + vertex -426.071 9.42761 16.5409 + endloop + endfacet + facet normal -0.116526 -0.545275 0.830119 + outer loop + vertex -436.233 11.6052 16.5448 + vertex -435.748 9.69697 15.3594 + vertex -426.071 9.42761 16.5409 + endloop + endfacet + facet normal -0.116544 -0.544921 0.830349 + outer loop + vertex -426.071 9.42761 16.5409 + vertex -435.748 9.69697 15.3594 + vertex -425.479 7.4915 15.3534 + endloop + endfacet + facet normal -0.126863 -0.550656 0.825035 + outer loop + vertex -467.027 18.3982 16.4624 + vertex -466.272 16.4566 15.2826 + vertex -456.304 15.9691 16.49 + endloop + endfacet + facet normal -0.126873 -0.550354 0.825235 + outer loop + vertex -456.304 15.9691 16.49 + vertex -466.272 16.4566 15.2826 + vertex -455.78 14.0861 15.3146 + endloop + endfacet + facet normal -0.09603 -0.426283 0.899478 + outer loop + vertex -469.158 20.7675 17.3577 + vertex -467.027 18.3982 16.4624 + vertex -457.487 18.4791 17.5192 + endloop + endfacet + facet normal -0.0966254 -0.416281 0.904087 + outer loop + vertex -457.487 18.4791 17.5192 + vertex -467.027 18.3982 16.4624 + vertex -456.304 15.9691 16.49 + endloop + endfacet + facet normal -0.0980941 -0.416809 0.903686 + outer loop + vertex -457.487 18.4791 17.5192 + vertex -456.304 15.9691 16.49 + vertex -447.591 15.895 17.4016 + endloop + endfacet + facet normal -0.0976174 -0.428687 0.898164 + outer loop + vertex -447.591 15.895 17.4016 + vertex -456.304 15.9691 16.49 + vertex -446.157 13.7475 16.5324 + endloop + endfacet + facet normal -0.12387 -0.549966 0.82595 + outer loop + vertex -456.304 15.9691 16.49 + vertex -455.78 14.0861 15.3146 + vertex -446.157 13.7475 16.5324 + endloop + endfacet + facet normal -0.123933 -0.548664 0.826806 + outer loop + vertex -446.157 13.7475 16.5324 + vertex -455.78 14.0861 15.3146 + vertex -445.738 11.8719 15.3506 + endloop + endfacet + facet normal -0.125759 -0.52653 0.840803 + outer loop + vertex -489.174 23.9585 16.669 + vertex -488.122 21.8361 15.4972 + vertex -478.269 21.1081 16.5149 + endloop + endfacet + facet normal -0.125881 -0.542309 0.830696 + outer loop + vertex -478.269 21.1081 16.5149 + vertex -488.122 21.8361 15.4972 + vertex -477.26 19.0534 15.3265 + endloop + endfacet + facet normal -0.0936621 -0.406389 0.908887 + outer loop + vertex -490.969 26.3302 17.5444 + vertex -489.174 23.9585 16.669 + vertex -479.976 23.8726 17.5784 + endloop + endfacet + facet normal -0.0936313 -0.40728 0.908491 + outer loop + vertex -479.976 23.8726 17.5784 + vertex -489.174 23.9585 16.669 + vertex -478.269 21.1081 16.5149 + endloop + endfacet + facet normal -0.0991914 -0.410012 0.90667 + outer loop + vertex -479.976 23.8726 17.5784 + vertex -478.269 21.1081 16.5149 + vertex -469.158 20.7675 17.3577 + endloop + endfacet + facet normal -0.0990892 -0.428509 0.898087 + outer loop + vertex -469.158 20.7675 17.3577 + vertex -478.269 21.1081 16.5149 + vertex -467.027 18.3982 16.4624 + endloop + endfacet + facet normal -0.126908 -0.542609 0.830343 + outer loop + vertex -478.269 21.1081 16.5149 + vertex -477.26 19.0534 15.3265 + vertex -467.027 18.3982 16.4624 + endloop + endfacet + facet normal -0.126834 -0.55065 0.825044 + outer loop + vertex -467.027 18.3982 16.4624 + vertex -477.26 19.0534 15.3265 + vertex -466.272 16.4566 15.2826 + endloop + endfacet + facet normal -0.0950161 -0.386018 0.917585 + outer loop + vertex -497.31 28.3684 17.7452 + vertex -498.065 26.5078 16.8843 + vertex -490.969 26.3302 17.5444 + endloop + endfacet + facet normal -0.0946962 -0.407027 0.908494 + outer loop + vertex -490.969 26.3302 17.5444 + vertex -498.065 26.5078 16.8843 + vertex -489.174 23.9585 16.669 + endloop + endfacet + facet normal -0.122138 -0.498498 0.858244 + outer loop + vertex -498.065 26.5078 16.8843 + vertex -497.488 24.4702 15.7829 + vertex -489.174 23.9585 16.669 + endloop + endfacet + facet normal -0.122068 -0.525394 0.842058 + outer loop + vertex -489.174 23.9585 16.669 + vertex -497.488 24.4702 15.7829 + vertex -488.122 21.8361 15.4972 + endloop + endfacet + facet normal -0.141832 -0.525693 0.838767 + outer loop + vertex -509.027 28.6913 16.5767 + vertex -509.076 26.9646 15.4863 + vertex -507.809 28.0371 16.3727 + endloop + endfacet + facet normal -0.111874 -0.551211 0.826832 + outer loop + vertex -507.809 28.0371 16.3727 + vertex -509.076 26.9646 15.4863 + vertex -507.834 26.2364 15.1688 + endloop + endfacet + facet normal -0.0881909 -0.424362 0.901188 + outer loop + vertex -508.771 30.3684 17.3915 + vertex -509.027 28.6913 16.5767 + vertex -507.346 30.1575 17.4316 + endloop + endfacet + facet normal -0.0810176 -0.43111 0.898655 + outer loop + vertex -507.346 30.1575 17.4316 + vertex -509.027 28.6913 16.5767 + vertex -507.809 28.0371 16.3727 + endloop + endfacet + facet normal -0.119975 -0.422481 0.898396 + outer loop + vertex -507.346 30.1575 17.4316 + vertex -507.809 28.0371 16.3727 + vertex -503.866 28.6332 17.1795 + endloop + endfacet + facet normal -0.111251 -0.457964 0.881982 + outer loop + vertex -503.866 28.6332 17.1795 + vertex -507.809 28.0371 16.3727 + vertex -504.119 26.6045 16.0943 + endloop + endfacet + facet normal -0.150661 -0.54798 0.822812 + outer loop + vertex -507.809 28.0371 16.3727 + vertex -507.834 26.2364 15.1688 + vertex -504.119 26.6045 16.0943 + endloop + endfacet + facet normal -0.1397 -0.589746 0.795414 + outer loop + vertex -504.119 26.6045 16.0943 + vertex -507.834 26.2364 15.1688 + vertex -504.07 24.8752 14.8207 + endloop + endfacet + facet normal 0.832262 0.116945 -0.541907 + outer loop + vertex -508.85 29.6765 17.1207 + vertex -508.998 28.8698 16.7186 + vertex -508.771 30.3684 17.3915 + endloop + endfacet + facet normal 0.990094 -0.137428 -0.0287761 + outer loop + vertex -508.771 30.3684 17.3915 + vertex -508.998 28.8698 16.7186 + vertex -509.027 28.6913 16.5767 + endloop + endfacet + facet normal 0.616848 0.426252 -0.661671 + outer loop + vertex -508.998 28.8698 16.7186 + vertex -508.923 27.4308 15.8615 + vertex -509.027 28.6913 16.5767 + endloop + endfacet + facet normal 0.443429 0.469677 -0.763396 + outer loop + vertex -509.027 28.6913 16.5767 + vertex -508.923 27.4308 15.8615 + vertex -509.076 26.9646 15.4863 + endloop + endfacet + facet normal 0.187101 -0.819084 0.542305 + outer loop + vertex 504.518 24.2547 13.9972 + vertex 504.387 23.1392 12.3576 + vertex 508.039 25.0002 13.9085 + endloop + endfacet + facet normal 0.19383 -0.824016 0.53238 + outer loop + vertex 508.039 25.0002 13.9085 + vertex 504.387 23.1392 12.3576 + vertex 507.938 23.8779 12.2081 + endloop + endfacet + facet normal 0.166877 -0.694715 0.699659 + outer loop + vertex 504.568 25.6192 15.3401 + vertex 504.518 24.2547 13.9972 + vertex 508.17 26.462 15.318 + endloop + endfacet + facet normal 0.164285 -0.692253 0.702707 + outer loop + vertex 508.17 26.462 15.318 + vertex 504.518 24.2547 13.9972 + vertex 508.039 25.0002 13.9085 + endloop + endfacet + facet normal 0.201549 -0.825585 0.527055 + outer loop + vertex 488.732 20.368 13.9234 + vertex 488.691 19.3007 12.2671 + vertex 497.866 22.6195 13.9573 + endloop + endfacet + facet normal 0.198504 -0.821208 0.53499 + outer loop + vertex 497.866 22.6195 13.9573 + vertex 488.691 19.3007 12.2671 + vertex 497.817 21.5442 12.3248 + endloop + endfacet + facet normal 0.166361 -0.687237 0.707128 + outer loop + vertex 488.661 21.8245 15.3555 + vertex 488.732 20.368 13.9234 + vertex 497.864 24.0507 15.354 + endloop + endfacet + facet normal 0.167096 -0.68851 0.705714 + outer loop + vertex 497.864 24.0507 15.354 + vertex 488.732 20.368 13.9234 + vertex 497.866 22.6195 13.9573 + endloop + endfacet + facet normal 0.162669 -0.68903 0.706241 + outer loop + vertex 497.864 24.0507 15.354 + vertex 497.866 22.6195 13.9573 + vertex 504.568 25.6192 15.3401 + endloop + endfacet + facet normal 0.166577 -0.694745 0.699701 + outer loop + vertex 504.568 25.6192 15.3401 + vertex 497.866 22.6195 13.9573 + vertex 504.518 24.2547 13.9972 + endloop + endfacet + facet normal 0.198642 -0.821186 0.534972 + outer loop + vertex 497.866 22.6195 13.9573 + vertex 497.817 21.5442 12.3248 + vertex 504.518 24.2547 13.9972 + endloop + endfacet + facet normal 0.19588 -0.817988 0.540857 + outer loop + vertex 504.518 24.2547 13.9972 + vertex 497.817 21.5442 12.3248 + vertex 504.387 23.1392 12.3576 + endloop + endfacet + facet normal 0.196578 -0.831034 0.520327 + outer loop + vertex 467.513 15.2787 13.9113 + vertex 467.487 14.2325 12.2499 + vertex 478.266 17.8226 13.9114 + endloop + endfacet + facet normal 0.194475 -0.827601 0.526551 + outer loop + vertex 478.266 17.8226 13.9114 + vertex 467.487 14.2325 12.2499 + vertex 478.242 16.7581 12.2475 + endloop + endfacet + facet normal 0.16298 -0.687181 0.707968 + outer loop + vertex 467.396 16.7215 15.3386 + vertex 467.513 15.2787 13.9113 + vertex 478.148 19.2751 15.3419 + endloop + endfacet + facet normal 0.162187 -0.685663 0.709621 + outer loop + vertex 478.148 19.2751 15.3419 + vertex 467.513 15.2787 13.9113 + vertex 478.266 17.8226 13.9114 + endloop + endfacet + facet normal 0.165239 -0.68518 0.709383 + outer loop + vertex 478.148 19.2751 15.3419 + vertex 478.266 17.8226 13.9114 + vertex 488.661 21.8245 15.3555 + endloop + endfacet + facet normal 0.166345 -0.687239 0.70713 + outer loop + vertex 488.661 21.8245 15.3555 + vertex 478.266 17.8226 13.9114 + vertex 488.732 20.368 13.9234 + endloop + endfacet + facet normal 0.200454 -0.826627 0.525838 + outer loop + vertex 478.266 17.8226 13.9114 + vertex 478.242 16.7581 12.2475 + vertex 488.732 20.368 13.9234 + endloop + endfacet + facet normal 0.199957 -0.825842 0.52726 + outer loop + vertex 488.732 20.368 13.9234 + vertex 478.242 16.7581 12.2475 + vertex 488.691 19.3007 12.2671 + endloop + endfacet + facet normal 0.184859 -0.832289 0.522611 + outer loop + vertex 446.516 10.5486 13.917 + vertex 446.549 9.51864 12.265 + vertex 456.942 12.8627 13.9141 + endloop + endfacet + facet normal 0.184467 -0.831644 0.523774 + outer loop + vertex 456.942 12.8627 13.9141 + vertex 446.549 9.51864 12.265 + vertex 456.937 11.82 12.2604 + endloop + endfacet + facet normal 0.153791 -0.690166 0.70712 + outer loop + vertex 446.217 11.9371 15.3371 + vertex 446.516 10.5486 13.917 + vertex 456.749 14.2826 15.3359 + endloop + endfacet + facet normal 0.15305 -0.688728 0.708682 + outer loop + vertex 456.749 14.2826 15.3359 + vertex 446.516 10.5486 13.917 + vertex 456.942 12.8627 13.9141 + endloop + endfacet + facet normal 0.157404 -0.687942 0.708491 + outer loop + vertex 456.749 14.2826 15.3359 + vertex 456.942 12.8627 13.9141 + vertex 467.396 16.7215 15.3386 + endloop + endfacet + facet normal 0.157454 -0.68804 0.708385 + outer loop + vertex 467.396 16.7215 15.3386 + vertex 456.942 12.8627 13.9141 + vertex 467.513 15.2787 13.9113 + endloop + endfacet + facet normal 0.190026 -0.830756 0.523196 + outer loop + vertex 456.942 12.8627 13.9141 + vertex 456.937 11.82 12.2604 + vertex 467.513 15.2787 13.9113 + endloop + endfacet + facet normal 0.190764 -0.831965 0.521002 + outer loop + vertex 467.513 15.2787 13.9113 + vertex 456.937 11.82 12.2604 + vertex 467.487 14.2325 12.2499 + endloop + endfacet + facet normal 0.177429 -0.832974 0.524093 + outer loop + vertex 425.626 6.05489 13.9188 + vertex 425.686 5.02805 12.2665 + vertex 436.086 8.28311 13.919 + endloop + endfacet + facet normal 0.176801 -0.831921 0.525975 + outer loop + vertex 436.086 8.28311 13.919 + vertex 425.686 5.02805 12.2665 + vertex 436.149 7.25368 12.2697 + endloop + endfacet + facet normal 0.147705 -0.693708 0.704949 + outer loop + vertex 425.209 7.40987 15.3395 + vertex 425.626 6.05489 13.9188 + vertex 435.702 9.64484 15.3403 + endloop + endfacet + facet normal 0.147796 -0.693887 0.704753 + outer loop + vertex 435.702 9.64484 15.3403 + vertex 425.626 6.05489 13.9188 + vertex 436.086 8.28311 13.919 + endloop + endfacet + facet normal 0.15129 -0.693019 0.704866 + outer loop + vertex 435.702 9.64484 15.3403 + vertex 436.086 8.28311 13.919 + vertex 446.217 11.9371 15.3371 + endloop + endfacet + facet normal 0.150224 -0.690942 0.707129 + outer loop + vertex 446.217 11.9371 15.3371 + vertex 436.086 8.28311 13.919 + vertex 446.516 10.5486 13.917 + endloop + endfacet + facet normal 0.180667 -0.831258 0.525709 + outer loop + vertex 436.086 8.28311 13.919 + vertex 436.149 7.25368 12.2697 + vertex 446.516 10.5486 13.917 + endloop + endfacet + facet normal 0.181616 -0.832831 0.522885 + outer loop + vertex 446.516 10.5486 13.917 + vertex 436.149 7.25368 12.2697 + vertex 446.549 9.51864 12.265 + endloop + endfacet + facet normal 0.170239 -0.833337 0.525897 + outer loop + vertex 404.846 1.75645 13.9193 + vertex 404.833 0.709606 12.2648 + vertex 415.211 3.8747 13.9205 + endloop + endfacet + facet normal 0.169843 -0.832663 0.527092 + outer loop + vertex 415.211 3.8747 13.9205 + vertex 404.833 0.709606 12.2648 + vertex 415.243 2.83535 12.2685 + endloop + endfacet + facet normal 0.141147 -0.693082 0.706906 + outer loop + vertex 404.505 3.13659 15.3406 + vertex 404.846 1.75645 13.9193 + vertex 414.821 5.23871 15.3417 + endloop + endfacet + facet normal 0.141835 -0.694448 0.705425 + outer loop + vertex 414.821 5.23871 15.3417 + vertex 404.846 1.75645 13.9193 + vertex 415.211 3.8747 13.9205 + endloop + endfacet + facet normal 0.145128 -0.693639 0.705552 + outer loop + vertex 414.821 5.23871 15.3417 + vertex 415.211 3.8747 13.9205 + vertex 425.209 7.40987 15.3395 + endloop + endfacet + facet normal 0.145458 -0.694289 0.704844 + outer loop + vertex 425.209 7.40987 15.3395 + vertex 415.211 3.8747 13.9205 + vertex 425.626 6.05489 13.9188 + endloop + endfacet + facet normal 0.174252 -0.831973 0.526742 + outer loop + vertex 415.211 3.8747 13.9205 + vertex 415.243 2.83535 12.2685 + vertex 425.626 6.05489 13.9188 + endloop + endfacet + facet normal 0.17508 -0.83337 0.524254 + outer loop + vertex 425.626 6.05489 13.9188 + vertex 415.243 2.83535 12.2685 + vertex 425.686 5.02805 12.2665 + endloop + endfacet + facet normal 0.162019 -0.833142 0.528795 + outer loop + vertex 383.809 -2.39225 13.92 + vertex 383.737 -3.45679 12.265 + vertex 394.428 -0.326538 13.921 + endloop + endfacet + facet normal 0.162692 -0.834334 0.526706 + outer loop + vertex 394.428 -0.326538 13.921 + vertex 383.737 -3.45679 12.265 + vertex 394.373 -1.38288 12.2647 + endloop + endfacet + facet normal 0.134307 -0.692119 0.709178 + outer loop + vertex 383.512 -0.992717 15.3421 + vertex 383.809 -2.39225 13.92 + vertex 394.125 1.06735 15.3428 + endloop + endfacet + facet normal 0.134748 -0.693032 0.708201 + outer loop + vertex 394.125 1.06735 15.3428 + vertex 383.809 -2.39225 13.92 + vertex 394.428 -0.326538 13.921 + endloop + endfacet + facet normal 0.138166 -0.692324 0.708236 + outer loop + vertex 394.125 1.06735 15.3428 + vertex 394.428 -0.326538 13.921 + vertex 404.505 3.13659 15.3406 + endloop + endfacet + facet normal 0.138802 -0.693608 0.706854 + outer loop + vertex 404.505 3.13659 15.3406 + vertex 394.428 -0.326538 13.921 + vertex 404.846 1.75645 13.9193 + endloop + endfacet + facet normal 0.166806 -0.833816 0.526238 + outer loop + vertex 394.428 -0.326538 13.921 + vertex 394.373 -1.38288 12.2647 + vertex 404.846 1.75645 13.9193 + endloop + endfacet + facet normal 0.166809 -0.83382 0.52623 + outer loop + vertex 404.846 1.75645 13.9193 + vertex 394.373 -1.38288 12.2647 + vertex 404.833 0.709606 12.2648 + endloop + endfacet + facet normal 0.15521 -0.835399 0.527274 + outer loop + vertex 362.159 -6.45782 13.9213 + vertex 362.089 -7.51688 12.264 + vertex 372.995 -4.44569 13.9196 + endloop + endfacet + facet normal 0.155378 -0.835707 0.526737 + outer loop + vertex 372.995 -4.44569 13.9196 + vertex 362.089 -7.51688 12.264 + vertex 372.919 -5.50383 12.2632 + endloop + endfacet + facet normal 0.128879 -0.691961 0.710338 + outer loop + vertex 361.861 -5.05258 15.3442 + vertex 362.159 -6.45782 13.9213 + vertex 372.688 -3.04074 15.3397 + endloop + endfacet + facet normal 0.12842 -0.690977 0.711379 + outer loop + vertex 372.688 -3.04074 15.3397 + vertex 362.159 -6.45782 13.9213 + vertex 372.995 -4.44569 13.9196 + endloop + endfacet + facet normal 0.130497 -0.690555 0.71141 + outer loop + vertex 372.688 -3.04074 15.3397 + vertex 372.995 -4.44569 13.9196 + vertex 383.512 -0.992717 15.3421 + endloop + endfacet + facet normal 0.131502 -0.692685 0.70915 + outer loop + vertex 383.512 -0.992717 15.3421 + vertex 372.995 -4.44569 13.9196 + vertex 383.809 -2.39225 13.92 + endloop + endfacet + facet normal 0.158598 -0.835342 0.526356 + outer loop + vertex 372.995 -4.44569 13.9196 + vertex 372.919 -5.50383 12.2632 + vertex 383.809 -2.39225 13.92 + endloop + endfacet + facet normal 0.157664 -0.833649 0.529312 + outer loop + vertex 383.809 -2.39225 13.92 + vertex 372.919 -5.50383 12.2632 + vertex 383.737 -3.45679 12.265 + endloop + endfacet + facet normal 0.147186 -0.834307 0.531289 + outer loop + vertex 341.178 -10.1963 13.9194 + vertex 341.116 -11.2602 12.2661 + vertex 351.521 -8.37282 13.9176 + endloop + endfacet + facet normal 0.146911 -0.833808 0.532147 + outer loop + vertex 351.521 -8.37282 13.9176 + vertex 341.116 -11.2602 12.2661 + vertex 351.458 -9.43865 12.2648 + endloop + endfacet + facet normal 0.12173 -0.692603 0.710974 + outer loop + vertex 340.922 -8.78155 15.3415 + vertex 341.178 -10.1963 13.9194 + vertex 351.239 -6.96781 15.3419 + endloop + endfacet + facet normal 0.122533 -0.694309 0.709169 + outer loop + vertex 351.239 -6.96781 15.3419 + vertex 341.178 -10.1963 13.9194 + vertex 351.521 -8.37282 13.9176 + endloop + endfacet + facet normal 0.124948 -0.693851 0.709196 + outer loop + vertex 351.239 -6.96781 15.3419 + vertex 351.521 -8.37282 13.9176 + vertex 361.861 -5.05258 15.3442 + endloop + endfacet + facet normal 0.124472 -0.692832 0.710275 + outer loop + vertex 361.861 -5.05258 15.3442 + vertex 351.521 -8.37282 13.9176 + vertex 362.159 -6.45782 13.9213 + endloop + endfacet + facet normal 0.149851 -0.833488 0.53183 + outer loop + vertex 351.521 -8.37282 13.9176 + vertex 351.458 -9.43865 12.2648 + vertex 362.159 -6.45782 13.9213 + endloop + endfacet + facet normal 0.151144 -0.835853 0.527736 + outer loop + vertex 362.159 -6.45782 13.9213 + vertex 351.458 -9.43865 12.2648 + vertex 362.089 -7.51688 12.264 + endloop + endfacet + facet normal 0.139409 -0.836077 0.530604 + outer loop + vertex 320.806 -13.6284 13.9202 + vertex 320.738 -14.6897 12.266 + vertex 331.011 -11.9289 13.9171 + endloop + endfacet + facet normal 0.139029 -0.83538 0.531799 + outer loop + vertex 331.011 -11.9289 13.9171 + vertex 320.738 -14.6897 12.266 + vertex 330.948 -12.9916 12.264 + endloop + endfacet + facet normal 0.115583 -0.69369 0.71094 + outer loop + vertex 320.556 -12.2125 15.3423 + vertex 320.806 -13.6284 13.9202 + vertex 330.765 -10.5142 15.3398 + endloop + endfacet + facet normal 0.115844 -0.694253 0.710347 + outer loop + vertex 330.765 -10.5142 15.3398 + vertex 320.806 -13.6284 13.9202 + vertex 331.011 -11.9289 13.9171 + endloop + endfacet + facet normal 0.11824 -0.693843 0.710353 + outer loop + vertex 330.765 -10.5142 15.3398 + vertex 331.011 -11.9289 13.9171 + vertex 340.922 -8.78155 15.3415 + endloop + endfacet + facet normal 0.117971 -0.693269 0.710958 + outer loop + vertex 340.922 -8.78155 15.3415 + vertex 331.011 -11.9289 13.9171 + vertex 341.178 -10.1963 13.9194 + endloop + endfacet + facet normal 0.142173 -0.835059 0.531473 + outer loop + vertex 331.011 -11.9289 13.9171 + vertex 330.948 -12.9916 12.264 + vertex 341.178 -10.1963 13.9194 + endloop + endfacet + facet normal 0.142058 -0.834849 0.531833 + outer loop + vertex 341.178 -10.1963 13.9194 + vertex 330.948 -12.9916 12.264 + vertex 341.116 -11.2602 12.2661 + endloop + endfacet + facet normal 0.132059 -0.83873 0.528292 + outer loop + vertex 299.739 -16.9775 13.922 + vertex 299.658 -18.0337 12.2653 + vertex 310.379 -15.3048 13.918 + endloop + endfacet + facet normal 0.132007 -0.83863 0.528464 + outer loop + vertex 310.379 -15.3048 13.918 + vertex 299.658 -18.0337 12.2653 + vertex 310.306 -16.3592 12.263 + endloop + endfacet + facet normal 0.108648 -0.692819 0.71288 + outer loop + vertex 299.471 -15.5585 15.3419 + vertex 299.739 -16.9775 13.922 + vertex 310.119 -13.8905 15.3401 + endloop + endfacet + facet normal 0.109491 -0.694735 0.710884 + outer loop + vertex 310.119 -13.8905 15.3401 + vertex 299.739 -16.9775 13.922 + vertex 310.379 -15.3048 13.918 + endloop + endfacet + facet normal 0.111489 -0.694392 0.710908 + outer loop + vertex 310.119 -13.8905 15.3401 + vertex 310.379 -15.3048 13.918 + vertex 320.556 -12.2125 15.3423 + endloop + endfacet + facet normal 0.111486 -0.694386 0.710914 + outer loop + vertex 320.556 -12.2125 15.3423 + vertex 310.379 -15.3048 13.918 + vertex 320.806 -13.6284 13.9202 + endloop + endfacet + facet normal 0.134676 -0.83838 0.528188 + outer loop + vertex 310.379 -15.3048 13.918 + vertex 310.306 -16.3592 12.263 + vertex 320.806 -13.6284 13.9202 + endloop + endfacet + facet normal 0.133746 -0.836628 0.531192 + outer loop + vertex 320.806 -13.6284 13.9202 + vertex 310.306 -16.3592 12.263 + vertex 320.738 -14.6897 12.266 + endloop + endfacet + facet normal 0.123954 -0.841388 0.526024 + outer loop + vertex 278.221 -20.1869 13.9213 + vertex 278.138 -21.2358 12.2631 + vertex 288.964 -18.6058 13.9187 + endloop + endfacet + facet normal 0.122712 -0.838924 0.530234 + outer loop + vertex 288.964 -18.6058 13.9187 + vertex 278.138 -21.2358 12.2631 + vertex 288.884 -19.6634 12.2639 + endloop + endfacet + facet normal 0.102203 -0.694354 0.712339 + outer loop + vertex 277.964 -18.7669 15.3424 + vertex 278.221 -20.1869 13.9213 + vertex 288.703 -17.1883 15.3403 + endloop + endfacet + facet normal 0.102441 -0.694912 0.71176 + outer loop + vertex 288.703 -17.1883 15.3403 + vertex 278.221 -20.1869 13.9213 + vertex 288.964 -18.6058 13.9187 + endloop + endfacet + facet normal 0.105004 -0.694484 0.711804 + outer loop + vertex 288.703 -17.1883 15.3403 + vertex 288.964 -18.6058 13.9187 + vertex 299.471 -15.5585 15.3419 + endloop + endfacet + facet normal 0.104586 -0.693515 0.71281 + outer loop + vertex 299.471 -15.5585 15.3419 + vertex 288.964 -18.6058 13.9187 + vertex 299.739 -16.9775 13.922 + endloop + endfacet + facet normal 0.126567 -0.838599 0.529841 + outer loop + vertex 288.964 -18.6058 13.9187 + vertex 288.884 -19.6634 12.2639 + vertex 299.739 -16.9775 13.922 + endloop + endfacet + facet normal 0.126866 -0.839188 0.528838 + outer loop + vertex 299.739 -16.9775 13.922 + vertex 288.884 -19.6634 12.2639 + vertex 299.658 -18.0337 12.2653 + endloop + endfacet + facet normal 0.114689 -0.84025 0.52993 + outer loop + vertex 257.07 -23.1281 13.9191 + vertex 256.996 -24.1822 12.2638 + vertex 267.583 -21.6926 13.9199 + endloop + endfacet + facet normal 0.115028 -0.840927 0.528782 + outer loop + vertex 267.583 -21.6926 13.9199 + vertex 256.996 -24.1822 12.2638 + vertex 267.506 -22.7445 12.2638 + endloop + endfacet + facet normal 0.0950998 -0.696849 0.710885 + outer loop + vertex 256.821 -21.7097 15.3428 + vertex 257.07 -23.1281 13.9191 + vertex 267.333 -20.2746 15.3433 + endloop + endfacet + facet normal 0.0950933 -0.696834 0.710901 + outer loop + vertex 267.333 -20.2746 15.3433 + vertex 257.07 -23.1281 13.9191 + vertex 267.583 -21.6926 13.9199 + endloop + endfacet + facet normal 0.0988096 -0.696246 0.71097 + outer loop + vertex 267.333 -20.2746 15.3433 + vertex 267.583 -21.6926 13.9199 + vertex 277.964 -18.7669 15.3424 + endloop + endfacet + facet normal 0.0982786 -0.694994 0.712268 + outer loop + vertex 277.964 -18.7669 15.3424 + vertex 267.583 -21.6926 13.9199 + vertex 278.221 -20.1869 13.9213 + endloop + endfacet + facet normal 0.118915 -0.840622 0.528407 + outer loop + vertex 267.583 -21.6926 13.9199 + vertex 267.506 -22.7445 12.2638 + vertex 278.221 -20.1869 13.9213 + endloop + endfacet + facet normal 0.119483 -0.841751 0.526477 + outer loop + vertex 278.221 -20.1869 13.9213 + vertex 267.506 -22.7445 12.2638 + vertex 278.138 -21.2358 12.2631 + endloop + endfacet + facet normal 0.106102 -0.841575 0.529617 + outer loop + vertex 236.175 -25.8228 13.92 + vertex 236.1 -26.8745 12.264 + vertex 246.629 -24.5044 13.9208 + endloop + endfacet + facet normal 0.106031 -0.841428 0.529864 + outer loop + vertex 246.629 -24.5044 13.9208 + vertex 236.1 -26.8745 12.264 + vertex 246.554 -25.5568 12.2645 + endloop + endfacet + facet normal 0.088111 -0.697015 0.711622 + outer loop + vertex 235.923 -24.402 15.3428 + vertex 236.175 -25.8228 13.92 + vertex 246.376 -23.0814 15.3421 + endloop + endfacet + facet normal 0.0877407 -0.696117 0.712547 + outer loop + vertex 246.376 -23.0814 15.3421 + vertex 236.175 -25.8228 13.92 + vertex 246.629 -24.5044 13.9208 + endloop + endfacet + facet normal 0.0912987 -0.695571 0.712633 + outer loop + vertex 246.376 -23.0814 15.3421 + vertex 246.629 -24.5044 13.9208 + vertex 256.821 -21.7097 15.3428 + endloop + endfacet + facet normal 0.0920318 -0.697324 0.710823 + outer loop + vertex 256.821 -21.7097 15.3428 + vertex 246.629 -24.5044 13.9208 + vertex 257.07 -23.1281 13.9191 + endloop + endfacet + facet normal 0.110951 -0.841075 0.529418 + outer loop + vertex 246.629 -24.5044 13.9208 + vertex 246.554 -25.5568 12.2645 + vertex 257.07 -23.1281 13.9191 + endloop + endfacet + facet normal 0.110691 -0.840553 0.530301 + outer loop + vertex 257.07 -23.1281 13.9191 + vertex 246.554 -25.5568 12.2645 + vertex 256.996 -24.1822 12.2638 + endloop + endfacet + facet normal 0.0974975 -0.840444 0.533055 + outer loop + vertex 215.068 -28.3236 13.9198 + vertex 214.991 -29.3812 12.2664 + vertex 225.658 -27.0953 13.9196 + endloop + endfacet + facet normal 0.0985585 -0.842685 0.529309 + outer loop + vertex 225.658 -27.0953 13.9196 + vertex 214.991 -29.3812 12.2664 + vertex 225.579 -28.1447 12.2634 + endloop + endfacet + facet normal 0.0813227 -0.69922 0.710266 + outer loop + vertex 214.824 -26.9042 15.3451 + vertex 215.068 -28.3236 13.9198 + vertex 225.405 -25.6755 15.3431 + endloop + endfacet + facet normal 0.0810376 -0.698504 0.711003 + outer loop + vertex 225.405 -25.6755 15.3431 + vertex 215.068 -28.3236 13.9198 + vertex 225.658 -27.0953 13.9196 + endloop + endfacet + facet normal 0.0845298 -0.697986 0.711105 + outer loop + vertex 225.405 -25.6755 15.3431 + vertex 225.658 -27.0953 13.9196 + vertex 235.923 -24.402 15.3428 + endloop + endfacet + facet normal 0.0843653 -0.69758 0.711523 + outer loop + vertex 235.923 -24.402 15.3428 + vertex 225.658 -27.0953 13.9196 + vertex 236.175 -25.8228 13.92 + endloop + endfacet + facet normal 0.101901 -0.842472 0.529015 + outer loop + vertex 225.658 -27.0953 13.9196 + vertex 225.579 -28.1447 12.2634 + vertex 236.175 -25.8228 13.92 + endloop + endfacet + facet normal 0.101615 -0.841878 0.530015 + outer loop + vertex 236.175 -25.8228 13.92 + vertex 225.579 -28.1447 12.2634 + vertex 236.1 -26.8745 12.264 + endloop + endfacet + facet normal 0.0885027 -0.842759 0.530965 + outer loop + vertex 193.77 -30.6223 13.9194 + vertex 193.682 -31.6746 12.2639 + vertex 204.433 -29.5021 13.9202 + endloop + endfacet + facet normal 0.0885935 -0.842957 0.530635 + outer loop + vertex 204.433 -29.5021 13.9202 + vertex 193.682 -31.6746 12.2639 + vertex 204.348 -30.5535 12.2641 + endloop + endfacet + facet normal 0.0738011 -0.699435 0.710876 + outer loop + vertex 193.542 -29.1983 15.3442 + vertex 193.77 -30.6223 13.9194 + vertex 204.19 -28.0763 15.3426 + endloop + endfacet + facet normal 0.0732911 -0.698106 0.712233 + outer loop + vertex 204.19 -28.0763 15.3426 + vertex 193.77 -30.6223 13.9194 + vertex 204.433 -29.5021 13.9202 + endloop + endfacet + facet normal 0.0767338 -0.697627 0.71234 + outer loop + vertex 204.19 -28.0763 15.3426 + vertex 204.433 -29.5021 13.9202 + vertex 214.824 -26.9042 15.3451 + endloop + endfacet + facet normal 0.0775657 -0.699758 0.710157 + outer loop + vertex 214.824 -26.9042 15.3451 + vertex 204.433 -29.5021 13.9202 + vertex 215.068 -28.3236 13.9198 + endloop + endfacet + facet normal 0.093398 -0.842698 0.530224 + outer loop + vertex 204.433 -29.5021 13.9202 + vertex 204.348 -30.5535 12.2641 + vertex 215.068 -28.3236 13.9198 + endloop + endfacet + facet normal 0.0924882 -0.840741 0.53348 + outer loop + vertex 215.068 -28.3236 13.9198 + vertex 204.348 -30.5535 12.2641 + vertex 214.991 -29.3812 12.2664 + endloop + endfacet + facet normal 0.0786983 -0.843019 0.532095 + outer loop + vertex 172.321 -32.698 13.9194 + vertex 172.228 -33.7511 12.2647 + vertex 183.08 -31.692 13.9219 + endloop + endfacet + facet normal 0.0801015 -0.846183 0.526837 + outer loop + vertex 183.08 -31.692 13.9219 + vertex 172.228 -33.7511 12.2647 + vertex 182.982 -32.734 12.2633 + endloop + endfacet + facet normal 0.0659266 -0.699372 0.711711 + outer loop + vertex 172.091 -31.2706 15.3433 + vertex 172.321 -32.698 13.9194 + vertex 182.844 -30.2587 15.3416 + endloop + endfacet + facet normal 0.0649847 -0.696817 0.714299 + outer loop + vertex 182.844 -30.2587 15.3416 + vertex 172.321 -32.698 13.9194 + vertex 183.08 -31.692 13.9219 + endloop + endfacet + facet normal 0.0688517 -0.696311 0.71443 + outer loop + vertex 182.844 -30.2587 15.3416 + vertex 183.08 -31.692 13.9219 + vertex 193.542 -29.1983 15.3442 + endloop + endfacet + facet normal 0.0702062 -0.699909 0.710773 + outer loop + vertex 193.542 -29.1983 15.3442 + vertex 183.08 -31.692 13.9219 + vertex 193.77 -30.6223 13.9194 + endloop + endfacet + facet normal 0.0847791 -0.845979 0.526433 + outer loop + vertex 183.08 -31.692 13.9219 + vertex 182.982 -32.734 12.2633 + vertex 193.77 -30.6223 13.9194 + endloop + endfacet + facet normal 0.0834359 -0.843006 0.531393 + outer loop + vertex 193.77 -30.6223 13.9194 + vertex 182.982 -32.734 12.2633 + vertex 193.682 -31.6746 12.2639 + endloop + endfacet + facet normal 0.0700563 -0.84666 0.527502 + outer loop + vertex 150.672 -34.5482 13.9222 + vertex 150.576 -35.5896 12.2635 + vertex 161.509 -33.6527 13.9204 + endloop + endfacet + facet normal 0.0693775 -0.845075 0.530128 + outer loop + vertex 161.509 -33.6527 13.9204 + vertex 150.576 -35.5896 12.2635 + vertex 161.414 -34.6996 12.2639 + endloop + endfacet + facet normal 0.0566675 -0.69643 0.715384 + outer loop + vertex 150.422 -33.1111 15.341 + vertex 150.672 -34.5482 13.9222 + vertex 161.273 -32.2248 15.3443 + endloop + endfacet + facet normal 0.0579777 -0.700129 0.711659 + outer loop + vertex 161.273 -32.2248 15.3443 + vertex 150.672 -34.5482 13.9222 + vertex 161.509 -33.6527 13.9204 + endloop + endfacet + facet normal 0.0617792 -0.699651 0.711809 + outer loop + vertex 161.273 -32.2248 15.3443 + vertex 161.509 -33.6527 13.9204 + vertex 172.091 -31.2706 15.3433 + endloop + endfacet + facet normal 0.0618641 -0.699886 0.711571 + outer loop + vertex 172.091 -31.2706 15.3433 + vertex 161.509 -33.6527 13.9204 + vertex 172.321 -32.698 13.9194 + endloop + endfacet + facet normal 0.0746503 -0.844889 0.529708 + outer loop + vertex 161.509 -33.6527 13.9204 + vertex 161.414 -34.6996 12.2639 + vertex 172.321 -32.698 13.9194 + endloop + endfacet + facet normal 0.0739207 -0.843207 0.532482 + outer loop + vertex 172.321 -32.698 13.9194 + vertex 161.414 -34.6996 12.2639 + vertex 172.228 -33.7511 12.2647 + endloop + endfacet + facet normal 0.0590448 -0.845793 0.530234 + outer loop + vertex 129.115 -36.1259 13.9194 + vertex 129.026 -37.1703 12.2634 + vertex 139.863 -35.374 13.9221 + endloop + endfacet + facet normal 0.0588903 -0.845422 0.530842 + outer loop + vertex 139.863 -35.374 13.9221 + vertex 129.026 -37.1703 12.2634 + vertex 139.768 -36.4211 12.2649 + endloop + endfacet + facet normal 0.0490773 -0.699921 0.712533 + outer loop + vertex 128.873 -34.6941 15.3425 + vertex 129.115 -36.1259 13.9194 + vertex 139.616 -33.94 15.3434 + endloop + endfacet + facet normal 0.0487209 -0.698886 0.713572 + outer loop + vertex 139.616 -33.94 15.3434 + vertex 129.115 -36.1259 13.9194 + vertex 139.863 -35.374 13.9221 + endloop + endfacet + facet normal 0.0537149 -0.69827 0.713816 + outer loop + vertex 139.616 -33.94 15.3434 + vertex 139.863 -35.374 13.9221 + vertex 150.422 -33.1111 15.341 + endloop + endfacet + facet normal 0.0532258 -0.696868 0.715221 + outer loop + vertex 150.422 -33.1111 15.341 + vertex 139.863 -35.374 13.9221 + vertex 150.672 -34.5482 13.9222 + endloop + endfacet + facet normal 0.064564 -0.84527 0.530424 + outer loop + vertex 139.863 -35.374 13.9221 + vertex 139.768 -36.4211 12.2649 + vertex 150.672 -34.5482 13.9222 + endloop + endfacet + facet normal 0.0652158 -0.846813 0.527878 + outer loop + vertex 150.672 -34.5482 13.9222 + vertex 139.768 -36.4211 12.2649 + vertex 150.576 -35.5896 12.2635 + endloop + endfacet + facet normal 0.048724 -0.843249 0.535311 + outer loop + vertex 107.818 -37.4288 13.919 + vertex 107.732 -38.4828 12.2666 + vertex 118.445 -36.8137 13.9206 + endloop + endfacet + facet normal 0.0498984 -0.84614 0.53062 + outer loop + vertex 118.445 -36.8137 13.9206 + vertex 107.732 -38.4828 12.2666 + vertex 118.354 -37.8579 12.2641 + endloop + endfacet + facet normal 0.0402727 -0.700415 0.712599 + outer loop + vertex 107.581 -35.9946 15.3421 + vertex 107.818 -37.4288 13.919 + vertex 118.208 -35.3814 15.3443 + endloop + endfacet + facet normal 0.0404644 -0.700988 0.712024 + outer loop + vertex 118.208 -35.3814 15.3443 + vertex 107.818 -37.4288 13.919 + vertex 118.445 -36.8137 13.9206 + endloop + endfacet + facet normal 0.0452502 -0.700441 0.712274 + outer loop + vertex 118.208 -35.3814 15.3443 + vertex 118.445 -36.8137 13.9206 + vertex 128.873 -34.6941 15.3425 + endloop + endfacet + facet normal 0.0452285 -0.700378 0.712338 + outer loop + vertex 128.873 -34.6941 15.3425 + vertex 118.445 -36.8137 13.9206 + vertex 129.115 -36.1259 13.9194 + endloop + endfacet + facet normal 0.0545985 -0.846048 0.530303 + outer loop + vertex 118.445 -36.8137 13.9206 + vertex 118.354 -37.8579 12.2641 + vertex 129.115 -36.1259 13.9194 + endloop + endfacet + facet normal 0.0545374 -0.8459 0.530546 + outer loop + vertex 129.115 -36.1259 13.9194 + vertex 118.354 -37.8579 12.2641 + vertex 129.026 -37.1703 12.2634 + endloop + endfacet + facet normal 0.0382443 -0.846258 0.531398 + outer loop + vertex 86.5378 -38.4711 13.9191 + vertex 86.4393 -39.5151 12.2635 + vertex 97.2056 -37.9871 13.922 + endloop + endfacet + facet normal 0.038662 -0.847324 0.529668 + outer loop + vertex 97.2056 -37.9871 13.922 + vertex 86.4393 -39.5151 12.2635 + vertex 97.1094 -39.0278 12.2642 + endloop + endfacet + facet normal 0.0316708 -0.701166 0.712294 + outer loop + vertex 86.3175 -37.0349 15.3426 + vertex 86.5378 -38.4711 13.9191 + vertex 96.9788 -36.5507 15.3453 + endloop + endfacet + facet normal 0.0316032 -0.700955 0.712505 + outer loop + vertex 96.9788 -36.5507 15.3453 + vertex 86.5378 -38.4711 13.9191 + vertex 97.2056 -37.9871 13.922 + endloop + endfacet + facet normal 0.0369451 -0.700399 0.712795 + outer loop + vertex 96.9788 -36.5507 15.3453 + vertex 97.2056 -37.9871 13.922 + vertex 107.581 -35.9946 15.3421 + endloop + endfacet + facet normal 0.0370673 -0.70077 0.712423 + outer loop + vertex 107.581 -35.9946 15.3421 + vertex 97.2056 -37.9871 13.922 + vertex 107.818 -37.4288 13.919 + endloop + endfacet + facet normal 0.0447236 -0.847267 0.529281 + outer loop + vertex 97.2056 -37.9871 13.922 + vertex 97.1094 -39.0278 12.2642 + vertex 107.818 -37.4288 13.919 + endloop + endfacet + facet normal 0.043151 -0.843333 0.535656 + outer loop + vertex 107.818 -37.4288 13.919 + vertex 97.1094 -39.0278 12.2642 + vertex 107.732 -38.4828 12.2666 + endloop + endfacet + facet normal 0.0283301 -0.846554 0.531548 + outer loop + vertex 64.898 -39.2691 13.9196 + vertex 64.7916 -40.3125 12.2635 + vertex 75.7781 -38.904 13.9211 + endloop + endfacet + facet normal 0.028085 -0.845894 0.532611 + outer loop + vertex 75.7781 -38.904 13.9211 + vertex 64.7916 -40.3125 12.2635 + vertex 75.6726 -39.9499 12.2655 + endloop + endfacet + facet normal 0.023945 -0.702231 0.711547 + outer loop + vertex 64.6749 -37.832 15.3453 + vertex 64.898 -39.2691 13.9196 + vertex 75.5575 -37.4628 15.3435 + endloop + endfacet + facet normal 0.0234019 -0.700434 0.713334 + outer loop + vertex 75.5575 -37.4628 15.3435 + vertex 64.898 -39.2691 13.9196 + vertex 75.7781 -38.904 13.9211 + endloop + endfacet + facet normal 0.0278963 -0.700003 0.713594 + outer loop + vertex 75.5575 -37.4628 15.3435 + vertex 75.7781 -38.904 13.9211 + vertex 86.3175 -37.0349 15.3426 + endloop + endfacet + facet normal 0.0283605 -0.701493 0.712112 + outer loop + vertex 86.3175 -37.0349 15.3426 + vertex 75.7781 -38.904 13.9211 + vertex 86.5378 -38.4711 13.9191 + endloop + endfacet + facet normal 0.0341373 -0.845908 0.532234 + outer loop + vertex 75.7781 -38.904 13.9211 + vertex 75.6726 -39.9499 12.2655 + vertex 86.5378 -38.4711 13.9191 + endloop + endfacet + facet normal 0.0342769 -0.846274 0.531644 + outer loop + vertex 86.5378 -38.4711 13.9191 + vertex 75.6726 -39.9499 12.2655 + vertex 86.4393 -39.5151 12.2635 + endloop + endfacet + facet normal 0.0195108 -0.846738 0.531652 + outer loop + vertex 43.1018 -39.829 13.9215 + vertex 43.0041 -40.8715 12.2648 + vertex 53.9695 -39.5792 13.9206 + endloop + endfacet + facet normal 0.0194875 -0.846673 0.531756 + outer loop + vertex 53.9695 -39.5792 13.9206 + vertex 43.0041 -40.8715 12.2648 + vertex 53.868 -40.6219 12.264 + endloop + endfacet + facet normal 0.0161781 -0.700905 0.713071 + outer loop + vertex 42.8717 -38.3858 15.3454 + vertex 43.1018 -39.829 13.9215 + vertex 53.7321 -38.1366 15.3438 + endloop + endfacet + facet normal 0.0161735 -0.70089 0.713086 + outer loop + vertex 53.7321 -38.1366 15.3438 + vertex 43.1018 -39.829 13.9215 + vertex 53.9695 -39.5792 13.9206 + endloop + endfacet + facet normal 0.0194045 -0.700579 0.713311 + outer loop + vertex 53.7321 -38.1366 15.3438 + vertex 53.9695 -39.5792 13.9206 + vertex 64.6749 -37.832 15.3453 + endloop + endfacet + facet normal 0.0200016 -0.702601 0.711303 + outer loop + vertex 64.6749 -37.832 15.3453 + vertex 53.9695 -39.5792 13.9206 + vertex 64.898 -39.2691 13.9196 + endloop + endfacet + facet normal 0.0240744 -0.846715 0.531501 + outer loop + vertex 53.9695 -39.5792 13.9206 + vertex 53.868 -40.6219 12.264 + vertex 64.898 -39.2691 13.9196 + endloop + endfacet + facet normal 0.0240052 -0.846525 0.531807 + outer loop + vertex 64.898 -39.2691 13.9196 + vertex 53.868 -40.6219 12.264 + vertex 64.7916 -40.3125 12.2635 + endloop + endfacet + facet normal 0.0101897 -0.847526 0.530656 + outer loop + vertex 21.7322 -40.1434 13.9195 + vertex 21.6289 -41.1816 12.2633 + vertex 32.3671 -40.0149 13.9204 + endloop + endfacet + facet normal 0.00991679 -0.846759 0.531884 + outer loop + vertex 32.3671 -40.0149 13.9204 + vertex 21.6289 -41.1816 12.2633 + vertex 32.2684 -41.0565 12.2642 + endloop + endfacet + facet normal 0.00900064 -0.702669 0.71146 + outer loop + vertex 21.5217 -38.7018 15.3459 + vertex 21.7322 -40.1434 13.9195 + vertex 32.1446 -38.5688 15.3429 + endloop + endfacet + facet normal 0.00839907 -0.700568 0.713536 + outer loop + vertex 32.1446 -38.5688 15.3429 + vertex 21.7322 -40.1434 13.9195 + vertex 32.3671 -40.0149 13.9204 + endloop + endfacet + facet normal 0.0117862 -0.700279 0.713772 + outer loop + vertex 32.1446 -38.5688 15.3429 + vertex 32.3671 -40.0149 13.9204 + vertex 42.8717 -38.3858 15.3454 + endloop + endfacet + facet normal 0.012075 -0.701278 0.712786 + outer loop + vertex 42.8717 -38.3858 15.3454 + vertex 32.3671 -40.0149 13.9204 + vertex 43.1018 -39.829 13.9215 + endloop + endfacet + facet normal 0.0146145 -0.846836 0.531652 + outer loop + vertex 32.3671 -40.0149 13.9204 + vertex 32.2684 -41.0565 12.2642 + vertex 43.1018 -39.829 13.9215 + endloop + endfacet + facet normal 0.0145578 -0.846678 0.531906 + outer loop + vertex 43.1018 -39.829 13.9215 + vertex 32.2684 -41.0565 12.2642 + vertex 43.0041 -40.8715 12.2648 + endloop + endfacet + facet normal 0.00241616 -0.846707 0.532054 + outer loop + vertex 0.406534 -40.2493 13.9222 + vertex 0.307027 -41.2904 12.2658 + vertex 11.0981 -40.22 13.9203 + endloop + endfacet + facet normal 0.0023529 -0.846522 0.532348 + outer loop + vertex 11.0981 -40.22 13.9203 + vertex 0.307027 -41.2904 12.2658 + vertex 10.9936 -41.2618 12.2642 + endloop + endfacet + facet normal 0.000978551 -0.698119 0.715981 + outer loop + vertex 0.15622 -38.7937 15.3418 + vertex 0.406534 -40.2493 13.9222 + vertex 10.8735 -38.7752 15.3452 + endloop + endfacet + facet normal 0.00205332 -0.702038 0.712136 + outer loop + vertex 10.8735 -38.7752 15.3452 + vertex 0.406534 -40.2493 13.9222 + vertex 11.0981 -40.22 13.9203 + endloop + endfacet + facet normal 0.00479056 -0.701816 0.712342 + outer loop + vertex 10.8735 -38.7752 15.3452 + vertex 11.0981 -40.22 13.9203 + vertex 21.5217 -38.7018 15.3459 + endloop + endfacet + facet normal 0.00511611 -0.702975 0.711196 + outer loop + vertex 21.5217 -38.7018 15.3459 + vertex 11.0981 -40.22 13.9203 + vertex 21.7322 -40.1434 13.9195 + endloop + endfacet + facet normal 0.00613884 -0.846617 0.532168 + outer loop + vertex 11.0981 -40.22 13.9203 + vertex 10.9936 -41.2618 12.2642 + vertex 21.7322 -40.1434 13.9195 + endloop + endfacet + facet normal 0.00642996 -0.847447 0.530841 + outer loop + vertex 21.7322 -40.1434 13.9195 + vertex 10.9936 -41.2618 12.2642 + vertex 21.6289 -41.1816 12.2633 + endloop + endfacet + facet normal -0.00530835 -0.845319 0.534236 + outer loop + vertex -20.914 -40.1518 13.9208 + vertex -21.0059 -41.1967 12.2665 + vertex -10.3007 -40.2196 13.919 + endloop + endfacet + facet normal -0.00502054 -0.846177 0.532879 + outer loop + vertex -10.3007 -40.2196 13.919 + vertex -21.0059 -41.1967 12.2665 + vertex -10.3916 -41.2614 12.2638 + endloop + endfacet + facet normal -0.00471124 -0.700458 0.713678 + outer loop + vertex -21.1417 -38.7005 15.3437 + vertex -20.914 -40.1518 13.9208 + vertex -10.5438 -38.772 15.3434 + endloop + endfacet + facet normal -0.00436169 -0.701764 0.712396 + outer loop + vertex -10.5438 -38.772 15.3434 + vertex -20.914 -40.1518 13.9208 + vertex -10.3007 -40.2196 13.919 + endloop + endfacet + facet normal -0.00131412 -0.70151 0.712659 + outer loop + vertex -10.5438 -38.772 15.3434 + vertex -10.3007 -40.2196 13.919 + vertex 0.15622 -38.7937 15.3418 + endloop + endfacet + facet normal -0.00215434 -0.698393 0.715711 + outer loop + vertex 0.15622 -38.7937 15.3418 + vertex -10.3007 -40.2196 13.919 + vertex 0.406534 -40.2493 13.9222 + endloop + endfacet + facet normal -0.00250948 -0.846247 0.532785 + outer loop + vertex -10.3007 -40.2196 13.919 + vertex -10.3916 -41.2614 12.2638 + vertex 0.406534 -40.2493 13.9222 + endloop + endfacet + facet normal -0.00239824 -0.846576 0.532262 + outer loop + vertex 0.406534 -40.2493 13.9222 + vertex -10.3916 -41.2614 12.2638 + vertex 0.307027 -41.2904 12.2658 + endloop + endfacet + facet normal -0.0143258 -0.847579 0.530475 + outer loop + vertex -41.9431 -39.8532 13.9199 + vertex -42.0556 -40.8881 12.2634 + vertex -31.4248 -40.0306 13.9205 + endloop + endfacet + facet normal -0.0146487 -0.846594 0.532037 + outer loop + vertex -31.4248 -40.0306 13.9205 + vertex -42.0556 -40.8881 12.2634 + vertex -31.5253 -41.0697 12.2643 + endloop + endfacet + facet normal -0.0116551 -0.70261 0.711479 + outer loop + vertex -42.1258 -38.4059 15.3462 + vertex -41.9431 -39.8532 13.9199 + vertex -31.6254 -38.581 15.3453 + endloop + endfacet + facet normal -0.0118765 -0.701756 0.712319 + outer loop + vertex -31.6254 -38.581 15.3453 + vertex -41.9431 -39.8532 13.9199 + vertex -31.4248 -40.0306 13.9205 + endloop + endfacet + facet normal -0.00788663 -0.701503 0.712623 + outer loop + vertex -31.6254 -38.581 15.3453 + vertex -31.4248 -40.0306 13.9205 + vertex -21.1417 -38.7005 15.3437 + endloop + endfacet + facet normal -0.00809581 -0.700713 0.713397 + outer loop + vertex -21.1417 -38.7005 15.3437 + vertex -31.4248 -40.0306 13.9205 + vertex -20.914 -40.1518 13.9208 + endloop + endfacet + facet normal -0.00977428 -0.846778 0.531856 + outer loop + vertex -31.4248 -40.0306 13.9205 + vertex -31.5253 -41.0697 12.2643 + vertex -20.914 -40.1518 13.9208 + endloop + endfacet + facet normal -0.0103134 -0.84516 0.534414 + outer loop + vertex -20.914 -40.1518 13.9208 + vertex -31.5253 -41.0697 12.2643 + vertex -21.0059 -41.1967 12.2665 + endloop + endfacet + facet normal -0.0240166 -0.846264 0.532223 + outer loop + vertex -63.5634 -39.3091 13.9196 + vertex -63.6783 -40.3469 12.2642 + vertex -52.629 -39.6181 13.9215 + endloop + endfacet + facet normal -0.0238933 -0.846671 0.53158 + outer loop + vertex -52.629 -39.6181 13.9215 + vertex -63.6783 -40.3469 12.2642 + vertex -52.7489 -40.6549 12.2648 + endloop + endfacet + facet normal -0.019941 -0.699995 0.713869 + outer loop + vertex -63.792 -37.852 15.3419 + vertex -63.5634 -39.3091 13.9196 + vertex -52.8324 -38.1624 15.3437 + endloop + endfacet + facet normal -0.0199173 -0.700095 0.713772 + outer loop + vertex -52.8324 -38.1624 15.3437 + vertex -63.5634 -39.3091 13.9196 + vertex -52.629 -39.6181 13.9215 + endloop + endfacet + facet normal -0.0160853 -0.69987 0.714089 + outer loop + vertex -52.8324 -38.1624 15.3437 + vertex -52.629 -39.6181 13.9215 + vertex -42.1258 -38.4059 15.3462 + endloop + endfacet + facet normal -0.0153551 -0.702812 0.71121 + outer loop + vertex -42.1258 -38.4059 15.3462 + vertex -52.629 -39.6181 13.9215 + vertex -41.9431 -39.8532 13.9199 + endloop + endfacet + facet normal -0.018553 -0.846941 0.531363 + outer loop + vertex -52.629 -39.6181 13.9215 + vertex -52.7489 -40.6549 12.2648 + vertex -41.9431 -39.8532 13.9199 + endloop + endfacet + facet normal -0.0184083 -0.847398 0.530639 + outer loop + vertex -41.9431 -39.8532 13.9199 + vertex -52.7489 -40.6549 12.2648 + vertex -42.0556 -40.8881 12.2634 + endloop + endfacet + facet normal -0.0335695 -0.845452 0.532996 + outer loop + vertex -85.5659 -38.5108 13.9192 + vertex -85.6609 -39.5504 12.2643 + vertex -74.6149 -38.9438 13.9221 + endloop + endfacet + facet normal -0.0328787 -0.847823 0.52926 + outer loop + vertex -74.6149 -38.9438 13.9221 + vertex -85.6609 -39.5504 12.2643 + vertex -74.7233 -39.9749 12.2636 + endloop + endfacet + facet normal -0.0278047 -0.700368 0.71324 + outer loop + vertex -85.8067 -37.0523 15.342 + vertex -85.5659 -38.5108 13.9192 + vertex -74.8614 -37.4845 15.3443 + endloop + endfacet + facet normal -0.0278688 -0.700084 0.713517 + outer loop + vertex -74.8614 -37.4845 15.3443 + vertex -85.5659 -38.5108 13.9192 + vertex -74.6149 -38.9438 13.9221 + endloop + endfacet + facet normal -0.023078 -0.699755 0.71401 + outer loop + vertex -74.8614 -37.4845 15.3443 + vertex -74.6149 -38.9438 13.9221 + vertex -63.792 -37.852 15.3419 + endloop + endfacet + facet normal -0.022978 -0.700193 0.713584 + outer loop + vertex -63.792 -37.852 15.3419 + vertex -74.6149 -38.9438 13.9221 + vertex -63.5634 -39.3091 13.9196 + endloop + endfacet + facet normal -0.0279075 -0.848097 0.529106 + outer loop + vertex -74.6149 -38.9438 13.9221 + vertex -74.7233 -39.9749 12.2636 + vertex -63.5634 -39.3091 13.9196 + endloop + endfacet + facet normal -0.0285178 -0.846022 0.532384 + outer loop + vertex -63.5634 -39.3091 13.9196 + vertex -74.7233 -39.9749 12.2636 + vertex -63.6783 -40.3469 12.2642 + endloop + endfacet + facet normal -0.0431925 -0.847921 0.528361 + outer loop + vertex -106.675 -37.506 13.9233 + vertex -106.783 -38.5345 12.264 + vertex -96.2355 -38.0384 13.9223 + endloop + endfacet + facet normal -0.0438309 -0.845752 0.531773 + outer loop + vertex -96.2355 -38.0384 13.9223 + vertex -106.783 -38.5345 12.264 + vertex -96.3319 -39.075 12.2658 + endloop + endfacet + facet normal -0.0355388 -0.698459 0.714767 + outer loop + vertex -106.872 -36.0424 15.3437 + vertex -106.675 -37.506 13.9233 + vertex -96.4534 -36.574 15.3422 + endloop + endfacet + facet normal -0.0355499 -0.698409 0.714815 + outer loop + vertex -96.4534 -36.574 15.3422 + vertex -106.675 -37.506 13.9233 + vertex -96.2355 -38.0384 13.9223 + endloop + endfacet + facet normal -0.0313464 -0.698186 0.71523 + outer loop + vertex -96.4534 -36.574 15.3422 + vertex -96.2355 -38.0384 13.9223 + vertex -85.8067 -37.0523 15.342 + endloop + endfacet + facet normal -0.0308086 -0.70056 0.712928 + outer loop + vertex -85.8067 -37.0523 15.342 + vertex -96.2355 -38.0384 13.9223 + vertex -85.5659 -38.5108 13.9192 + endloop + endfacet + facet normal -0.0373074 -0.846148 0.53164 + outer loop + vertex -96.2355 -38.0384 13.9223 + vertex -96.3319 -39.075 12.2658 + vertex -85.5659 -38.5108 13.9192 + endloop + endfacet + facet normal -0.0375775 -0.845227 0.533085 + outer loop + vertex -85.5659 -38.5108 13.9192 + vertex -96.3319 -39.075 12.2658 + vertex -85.6609 -39.5504 12.2643 + endloop + endfacet + facet normal -0.054556 -0.845116 0.531792 + outer loop + vertex -127.798 -36.2094 13.919 + vertex -127.909 -37.244 12.2634 + vertex -117.127 -36.8973 13.9205 + endloop + endfacet + facet normal -0.0546286 -0.844849 0.532208 + outer loop + vertex -117.127 -36.8973 13.9205 + vertex -127.909 -37.244 12.2634 + vertex -117.238 -37.933 12.2649 + endloop + endfacet + facet normal -0.0447102 -0.702367 0.710409 + outer loop + vertex -128.011 -34.7532 15.3453 + vertex -127.798 -36.2094 13.919 + vertex -117.327 -35.4358 15.3428 + endloop + endfacet + facet normal -0.04522 -0.699893 0.712814 + outer loop + vertex -117.327 -35.4358 15.3428 + vertex -127.798 -36.2094 13.919 + vertex -117.127 -36.8973 13.9205 + endloop + endfacet + facet normal -0.0406596 -0.699711 0.713268 + outer loop + vertex -117.327 -35.4358 15.3428 + vertex -117.127 -36.8973 13.9205 + vertex -106.872 -36.0424 15.3437 + endloop + endfacet + facet normal -0.0408827 -0.698686 0.71426 + outer loop + vertex -106.872 -36.0424 15.3437 + vertex -117.127 -36.8973 13.9205 + vertex -106.675 -37.506 13.9233 + endloop + endfacet + facet normal -0.0493695 -0.845241 0.532099 + outer loop + vertex -117.127 -36.8973 13.9205 + vertex -117.238 -37.933 12.2649 + vertex -106.675 -37.506 13.9233 + endloop + endfacet + facet normal -0.0487091 -0.847544 0.528486 + outer loop + vertex -106.675 -37.506 13.9233 + vertex -117.238 -37.933 12.2649 + vertex -106.783 -38.5345 12.264 + endloop + endfacet + facet normal -0.0639836 -0.842303 0.535193 + outer loop + vertex -149.638 -34.6206 13.9191 + vertex -149.74 -35.6628 12.2667 + vertex -138.693 -35.4509 13.9209 + endloop + endfacet + facet normal -0.0634564 -0.8444 0.531941 + outer loop + vertex -138.693 -35.4509 13.9209 + vertex -149.74 -35.6628 12.2667 + vertex -138.799 -36.486 12.2651 + endloop + endfacet + facet normal -0.053269 -0.699542 0.712604 + outer loop + vertex -149.867 -33.1539 15.3419 + vertex -149.638 -34.6206 13.9191 + vertex -138.932 -33.9848 15.3436 + endloop + endfacet + facet normal -0.0532071 -0.69987 0.712285 + outer loop + vertex -138.932 -33.9848 15.3436 + vertex -149.638 -34.6206 13.9191 + vertex -138.693 -35.4509 13.9209 + endloop + endfacet + facet normal -0.0493434 -0.699686 0.712745 + outer loop + vertex -138.932 -33.9848 15.3436 + vertex -138.693 -35.4509 13.9209 + vertex -128.011 -34.7532 15.3453 + endloop + endfacet + facet normal -0.0487876 -0.702537 0.709973 + outer loop + vertex -128.011 -34.7532 15.3453 + vertex -138.693 -35.4509 13.9209 + vertex -127.798 -36.2094 13.919 + endloop + endfacet + facet normal -0.0587226 -0.844783 0.531877 + outer loop + vertex -138.693 -35.4509 13.9209 + vertex -138.799 -36.486 12.2651 + vertex -127.798 -36.2094 13.919 + endloop + endfacet + facet normal -0.0587211 -0.844789 0.531868 + outer loop + vertex -127.798 -36.2094 13.919 + vertex -138.799 -36.486 12.2651 + vertex -127.909 -37.244 12.2634 + endloop + endfacet + facet normal -0.0744436 -0.843893 0.531322 + outer loop + vertex -171.058 -32.8151 13.9194 + vertex -171.178 -33.8469 12.2638 + vertex -160.428 -33.7507 13.9228 + endloop + endfacet + facet normal -0.0740792 -0.845354 0.529045 + outer loop + vertex -160.428 -33.7507 13.9228 + vertex -171.178 -33.8469 12.2638 + vertex -160.541 -34.7787 12.2644 + endloop + endfacet + facet normal -0.0608379 -0.701544 0.710025 + outer loop + vertex -171.233 -31.3561 15.346 + vertex -171.058 -32.8151 13.9194 + vertex -160.632 -32.2787 15.3428 + endloop + endfacet + facet normal -0.0616067 -0.697352 0.714077 + outer loop + vertex -160.632 -32.2787 15.3428 + vertex -171.058 -32.8151 13.9194 + vertex -160.428 -33.7507 13.9228 + endloop + endfacet + facet normal -0.0566184 -0.6972 0.714637 + outer loop + vertex -160.632 -32.2787 15.3428 + vertex -160.428 -33.7507 13.9228 + vertex -149.867 -33.1539 15.3419 + endloop + endfacet + facet normal -0.0561603 -0.699662 0.712263 + outer loop + vertex -149.867 -33.1539 15.3419 + vertex -160.428 -33.7507 13.9228 + vertex -149.638 -34.6206 13.9191 + endloop + endfacet + facet normal -0.0680133 -0.845909 0.528973 + outer loop + vertex -160.428 -33.7507 13.9228 + vertex -160.541 -34.7787 12.2644 + vertex -149.638 -34.6206 13.9191 + endloop + endfacet + facet normal -0.0690222 -0.841878 0.535236 + outer loop + vertex -149.638 -34.6206 13.9191 + vertex -160.541 -34.7787 12.2644 + vertex -149.74 -35.6628 12.2667 + endloop + endfacet + facet normal -0.08399 -0.843438 0.530621 + outer loop + vertex -192.372 -30.7611 13.9196 + vertex -192.489 -31.7909 12.2642 + vertex -181.66 -31.8269 13.921 + endloop + endfacet + facet normal -0.084352 -0.841887 0.533021 + outer loop + vertex -181.66 -31.8269 13.921 + vertex -192.489 -31.7909 12.2642 + vertex -181.784 -32.862 12.2666 + endloop + endfacet + facet normal -0.0696898 -0.699086 0.711633 + outer loop + vertex -192.594 -29.2894 15.3436 + vertex -192.372 -30.7611 13.9196 + vertex -181.852 -30.3593 15.3446 + endloop + endfacet + facet normal -0.0696652 -0.699232 0.711492 + outer loop + vertex -181.852 -30.3593 15.3446 + vertex -192.372 -30.7611 13.9196 + vertex -181.66 -31.8269 13.921 + endloop + endfacet + facet normal -0.0657296 -0.699155 0.711943 + outer loop + vertex -181.852 -30.3593 15.3446 + vertex -181.66 -31.8269 13.921 + vertex -171.233 -31.3561 15.346 + endloop + endfacet + facet normal -0.0652921 -0.701618 0.709555 + outer loop + vertex -171.233 -31.3561 15.346 + vertex -181.66 -31.8269 13.921 + vertex -171.058 -32.8151 13.9194 + endloop + endfacet + facet normal -0.0784515 -0.842495 0.532961 + outer loop + vertex -181.66 -31.8269 13.921 + vertex -181.784 -32.862 12.2666 + vertex -171.058 -32.8151 13.9194 + endloop + endfacet + facet normal -0.0782011 -0.843525 0.531366 + outer loop + vertex -171.058 -32.8151 13.9194 + vertex -181.784 -32.862 12.2666 + vertex -171.178 -33.8469 12.2638 + endloop + endfacet + facet normal -0.0922446 -0.844139 0.528129 + outer loop + vertex -213.799 -28.4719 13.923 + vertex -213.903 -29.4982 12.2644 + vertex -203.139 -29.6379 13.9213 + endloop + endfacet + facet normal -0.0922046 -0.844315 0.527854 + outer loop + vertex -203.139 -29.6379 13.9213 + vertex -213.903 -29.4982 12.2644 + vertex -203.246 -30.6627 12.2634 + endloop + endfacet + facet normal -0.076025 -0.696018 0.713988 + outer loop + vertex -214.022 -26.9905 15.3434 + vertex -213.799 -28.4719 13.923 + vertex -203.381 -28.1552 15.3411 + endloop + endfacet + facet normal -0.0760176 -0.696064 0.713944 + outer loop + vertex -203.381 -28.1552 15.3411 + vertex -213.799 -28.4719 13.923 + vertex -203.139 -29.6379 13.9213 + endloop + endfacet + facet normal -0.0733466 -0.695978 0.714308 + outer loop + vertex -203.381 -28.1552 15.3411 + vertex -203.139 -29.6379 13.9213 + vertex -192.594 -29.2894 15.3436 + endloop + endfacet + facet normal -0.0728264 -0.699173 0.711234 + outer loop + vertex -192.594 -29.2894 15.3436 + vertex -203.139 -29.6379 13.9213 + vertex -192.372 -30.7611 13.9196 + endloop + endfacet + facet normal -0.0880417 -0.844756 0.527859 + outer loop + vertex -203.139 -29.6379 13.9213 + vertex -203.246 -30.6627 12.2634 + vertex -192.372 -30.7611 13.9196 + endloop + endfacet + facet normal -0.0884495 -0.842968 0.530643 + outer loop + vertex -192.372 -30.7611 13.9196 + vertex -203.246 -30.6627 12.2634 + vertex -192.489 -31.7909 12.2642 + endloop + endfacet + facet normal -0.100584 -0.840942 0.531694 + outer loop + vertex -234.591 -26.023 13.9216 + vertex -234.713 -27.0547 12.2667 + vertex -224.256 -27.261 13.9186 + endloop + endfacet + facet normal -0.100803 -0.83996 0.533203 + outer loop + vertex -224.256 -27.261 13.9186 + vertex -234.713 -27.0547 12.2667 + vertex -224.363 -28.2976 12.2654 + endloop + endfacet + facet normal -0.0835984 -0.696989 0.712192 + outer loop + vertex -234.757 -24.5498 15.3438 + vertex -234.591 -26.023 13.9216 + vertex -224.445 -25.7888 15.3416 + endloop + endfacet + facet normal -0.0834223 -0.698106 0.711118 + outer loop + vertex -224.445 -25.7888 15.3416 + vertex -234.591 -26.023 13.9216 + vertex -224.256 -27.261 13.9186 + endloop + endfacet + facet normal -0.080604 -0.698082 0.711467 + outer loop + vertex -224.445 -25.7888 15.3416 + vertex -224.256 -27.261 13.9186 + vertex -214.022 -26.9905 15.3434 + endloop + endfacet + facet normal -0.0809163 -0.696132 0.713339 + outer loop + vertex -214.022 -26.9905 15.3434 + vertex -224.256 -27.261 13.9186 + vertex -213.799 -28.4719 13.923 + endloop + endfacet + facet normal -0.097538 -0.840332 0.533224 + outer loop + vertex -224.256 -27.261 13.9186 + vertex -224.363 -28.2976 12.2654 + vertex -213.799 -28.4719 13.923 + endloop + endfacet + facet normal -0.0967895 -0.843644 0.528106 + outer loop + vertex -213.799 -28.4719 13.923 + vertex -224.363 -28.2976 12.2654 + vertex -213.903 -29.4982 12.2644 + endloop + endfacet + facet normal -0.110657 -0.840691 0.530089 + outer loop + vertex -255.785 -23.2926 13.9189 + vertex -255.918 -24.3189 12.2634 + vertex -245.048 -24.705 13.9204 + endloop + endfacet + facet normal -0.110621 -0.840871 0.52981 + outer loop + vertex -245.048 -24.705 13.9204 + vertex -255.918 -24.3189 12.2634 + vertex -245.18 -25.731 12.2644 + endloop + endfacet + facet normal -0.0919927 -0.696751 0.71139 + outer loop + vertex -255.973 -21.8152 15.3416 + vertex -255.785 -23.2926 13.9189 + vertex -245.211 -23.2331 15.3445 + endloop + endfacet + facet normal -0.091869 -0.697664 0.71051 + outer loop + vertex -245.211 -23.2331 15.3445 + vertex -255.785 -23.2926 13.9189 + vertex -245.048 -24.705 13.9204 + endloop + endfacet + facet normal -0.0878216 -0.697687 0.710999 + outer loop + vertex -245.211 -23.2331 15.3445 + vertex -245.048 -24.705 13.9204 + vertex -234.757 -24.5498 15.3438 + endloop + endfacet + facet normal -0.0879262 -0.696981 0.711679 + outer loop + vertex -234.757 -24.5498 15.3438 + vertex -245.048 -24.705 13.9204 + vertex -234.591 -26.023 13.9216 + endloop + endfacet + facet normal -0.106116 -0.841452 0.52981 + outer loop + vertex -245.048 -24.705 13.9204 + vertex -245.18 -25.731 12.2644 + vertex -234.591 -26.023 13.9216 + endloop + endfacet + facet normal -0.106375 -0.840238 0.531681 + outer loop + vertex -234.591 -26.023 13.9216 + vertex -245.18 -25.731 12.2644 + vertex -234.713 -27.0547 12.2667 + endloop + endfacet + facet normal -0.118648 -0.838526 0.531787 + outer loop + vertex -277.769 -20.2471 13.921 + vertex -277.899 -21.2777 12.2669 + vertex -266.751 -21.8051 13.9225 + endloop + endfacet + facet normal -0.118296 -0.840465 0.528795 + outer loop + vertex -266.751 -21.8051 13.9225 + vertex -277.899 -21.2777 12.2669 + vertex -266.887 -22.8287 12.2652 + endloop + endfacet + facet normal -0.0978617 -0.697368 0.71 + outer loop + vertex -277.964 -18.769 15.3459 + vertex -277.769 -20.2471 13.921 + vertex -266.957 -20.3176 15.3419 + endloop + endfacet + facet normal -0.0982516 -0.694114 0.713129 + outer loop + vertex -266.957 -20.3176 15.3419 + vertex -277.769 -20.2471 13.921 + vertex -266.751 -21.8051 13.9225 + endloop + endfacet + facet normal -0.0946098 -0.694096 0.713638 + outer loop + vertex -266.957 -20.3176 15.3419 + vertex -266.751 -21.8051 13.9225 + vertex -255.973 -21.8152 15.3416 + endloop + endfacet + facet normal -0.0942767 -0.696752 0.71109 + outer loop + vertex -255.973 -21.8152 15.3416 + vertex -266.751 -21.8051 13.9225 + vertex -255.785 -23.2926 13.9189 + endloop + endfacet + facet normal -0.11391 -0.841063 0.528807 + outer loop + vertex -266.751 -21.8051 13.9225 + vertex -266.887 -22.8287 12.2652 + vertex -255.785 -23.2926 13.9189 + endloop + endfacet + facet normal -0.114066 -0.840239 0.530082 + outer loop + vertex -255.785 -23.2926 13.9189 + vertex -266.887 -22.8287 12.2652 + vertex -255.918 -24.3189 12.2634 + endloop + endfacet + facet normal -0.126656 -0.839917 0.527729 + outer loop + vertex -299.212 -17.0615 13.9214 + vertex -299.339 -18.0835 12.2642 + vertex -288.619 -18.66 13.9197 + endloop + endfacet + facet normal -0.126608 -0.840174 0.527331 + outer loop + vertex -288.619 -18.66 13.9197 + vertex -299.339 -18.0835 12.2642 + vertex -288.745 -19.6806 12.2635 + endloop + endfacet + facet normal -0.104981 -0.696074 0.710253 + outer loop + vertex -299.391 -15.5808 15.3461 + vertex -299.212 -17.0615 13.9214 + vertex -288.807 -17.1794 15.3438 + endloop + endfacet + facet normal -0.104955 -0.696295 0.71004 + outer loop + vertex -288.807 -17.1794 15.3438 + vertex -299.212 -17.0615 13.9214 + vertex -288.619 -18.66 13.9197 + endloop + endfacet + facet normal -0.102218 -0.696314 0.710421 + outer loop + vertex -288.807 -17.1794 15.3438 + vertex -288.619 -18.66 13.9197 + vertex -277.964 -18.769 15.3459 + endloop + endfacet + facet normal -0.102094 -0.69736 0.709413 + outer loop + vertex -277.964 -18.769 15.3459 + vertex -288.619 -18.66 13.9197 + vertex -277.769 -20.2471 13.921 + endloop + endfacet + facet normal -0.123038 -0.840679 0.527371 + outer loop + vertex -288.619 -18.66 13.9197 + vertex -288.745 -19.6806 12.2635 + vertex -277.769 -20.2471 13.921 + endloop + endfacet + facet normal -0.123552 -0.837843 0.531747 + outer loop + vertex -277.769 -20.2471 13.921 + vertex -288.745 -19.6806 12.2635 + vertex -277.899 -21.2777 12.2669 + endloop + endfacet + facet normal -0.134255 -0.837159 0.530226 + outer loop + vertex -319.892 -13.7799 13.9215 + vertex -320.016 -14.8082 12.2666 + vertex -309.602 -15.4318 13.9188 + endloop + endfacet + facet normal -0.134386 -0.836441 0.531325 + outer loop + vertex -309.602 -15.4318 13.9188 + vertex -320.016 -14.8082 12.2666 + vertex -309.726 -16.4623 12.2652 + endloop + endfacet + facet normal -0.112199 -0.692223 0.712909 + outer loop + vertex -320.085 -12.287 15.3408 + vertex -319.892 -13.7799 13.9215 + vertex -309.784 -13.9531 15.3442 + endloop + endfacet + facet normal -0.111666 -0.696742 0.708577 + outer loop + vertex -309.784 -13.9531 15.3442 + vertex -319.892 -13.7799 13.9215 + vertex -309.602 -15.4318 13.9188 + endloop + endfacet + facet normal -0.109258 -0.696776 0.708919 + outer loop + vertex -309.784 -13.9531 15.3442 + vertex -309.602 -15.4318 13.9188 + vertex -299.391 -15.5808 15.3461 + endloop + endfacet + facet normal -0.109348 -0.69602 0.709647 + outer loop + vertex -299.391 -15.5808 15.3461 + vertex -309.602 -15.4318 13.9188 + vertex -299.212 -17.0615 13.9214 + endloop + endfacet + facet normal -0.131398 -0.836883 0.531377 + outer loop + vertex -309.602 -15.4318 13.9188 + vertex -309.726 -16.4623 12.2652 + vertex -299.212 -17.0615 13.9214 + endloop + endfacet + facet normal -0.130952 -0.839292 0.527674 + outer loop + vertex -299.212 -17.0615 13.9214 + vertex -309.726 -16.4623 12.2652 + vertex -299.339 -18.0835 12.2642 + endloop + endfacet + facet normal -0.142583 -0.837741 0.527125 + outer loop + vertex -340.516 -10.3147 13.922 + vertex -340.651 -11.3344 12.2648 + vertex -330.182 -12.0741 13.9212 + endloop + endfacet + facet normal -0.142483 -0.838321 0.526229 + outer loop + vertex -330.182 -12.0741 13.9212 + vertex -340.651 -11.3344 12.2648 + vertex -330.31 -13.0926 12.2637 + endloop + endfacet + facet normal -0.117814 -0.692759 0.71148 + outer loop + vertex -340.693 -8.82467 15.3434 + vertex -340.516 -10.3147 13.922 + vertex -330.37 -10.5821 15.3416 + endloop + endfacet + facet normal -0.117841 -0.692506 0.711723 + outer loop + vertex -330.37 -10.5821 15.3416 + vertex -340.516 -10.3147 13.922 + vertex -330.182 -12.0741 13.9212 + endloop + endfacet + facet normal -0.114738 -0.692553 0.712184 + outer loop + vertex -330.37 -10.5821 15.3416 + vertex -330.182 -12.0741 13.9212 + vertex -320.085 -12.287 15.3408 + endloop + endfacet + facet normal -0.114779 -0.692193 0.712527 + outer loop + vertex -320.085 -12.287 15.3408 + vertex -330.182 -12.0741 13.9212 + vertex -319.892 -13.7799 13.9215 + endloop + endfacet + facet normal -0.139087 -0.838852 0.526291 + outer loop + vertex -330.182 -12.0741 13.9212 + vertex -330.31 -13.0926 12.2637 + vertex -319.892 -13.7799 13.9215 + endloop + endfacet + facet normal -0.139532 -0.836361 0.530124 + outer loop + vertex -319.892 -13.7799 13.9215 + vertex -330.31 -13.0926 12.2637 + vertex -320.016 -14.8082 12.2666 + endloop + endfacet + facet normal -0.150059 -0.83678 0.526576 + outer loop + vertex -361.342 -6.61786 13.9217 + vertex -361.492 -7.63392 12.2645 + vertex -350.91 -8.49001 13.9196 + endloop + endfacet + facet normal -0.150126 -0.836361 0.527222 + outer loop + vertex -350.91 -8.49001 13.9196 + vertex -361.492 -7.63392 12.2645 + vertex -351.05 -9.50891 12.2635 + endloop + endfacet + facet normal -0.1248 -0.690962 0.712037 + outer loop + vertex -361.5 -5.12647 15.3414 + vertex -361.342 -6.61786 13.9217 + vertex -351.07 -7.00739 15.3442 + endloop + endfacet + facet normal -0.124473 -0.694414 0.708728 + outer loop + vertex -351.07 -7.00739 15.3442 + vertex -361.342 -6.61786 13.9217 + vertex -350.91 -8.49001 13.9196 + endloop + endfacet + facet normal -0.121572 -0.694502 0.709145 + outer loop + vertex -351.07 -7.00739 15.3442 + vertex -350.91 -8.49001 13.9196 + vertex -340.693 -8.82467 15.3434 + endloop + endfacet + facet normal -0.121757 -0.692674 0.710899 + outer loop + vertex -340.693 -8.82467 15.3434 + vertex -350.91 -8.49001 13.9196 + vertex -340.516 -10.3147 13.922 + endloop + endfacet + facet normal -0.147027 -0.836876 0.527277 + outer loop + vertex -350.91 -8.49001 13.9196 + vertex -351.05 -9.50891 12.2635 + vertex -340.516 -10.3147 13.922 + endloop + endfacet + facet normal -0.147002 -0.837026 0.527046 + outer loop + vertex -340.516 -10.3147 13.922 + vertex -351.05 -9.50891 12.2635 + vertex -340.651 -11.3344 12.2648 + endloop + endfacet + facet normal -0.158036 -0.835892 0.525652 + outer loop + vertex -382.38 -2.68159 13.9205 + vertex -382.547 -3.69199 12.2635 + vertex -371.829 -4.67752 13.9189 + endloop + endfacet + facet normal -0.158119 -0.83533 0.52652 + outer loop + vertex -371.829 -4.67752 13.9189 + vertex -382.547 -3.69199 12.2635 + vertex -371.982 -5.69219 12.263 + endloop + endfacet + facet normal -0.131405 -0.690343 0.711449 + outer loop + vertex -382.518 -1.19283 15.3397 + vertex -382.38 -2.68159 13.9205 + vertex -371.962 -3.1984 15.3432 + endloop + endfacet + facet normal -0.131125 -0.693771 0.708158 + outer loop + vertex -371.962 -3.1984 15.3432 + vertex -382.38 -2.68159 13.9205 + vertex -371.829 -4.67752 13.9189 + endloop + endfacet + facet normal -0.127754 -0.69392 0.708628 + outer loop + vertex -371.962 -3.1984 15.3432 + vertex -371.829 -4.67752 13.9189 + vertex -361.5 -5.12647 15.3414 + endloop + endfacet + facet normal -0.128026 -0.690855 0.711567 + outer loop + vertex -361.5 -5.12647 15.3414 + vertex -371.829 -4.67752 13.9189 + vertex -361.342 -6.61786 13.9217 + endloop + endfacet + facet normal -0.154818 -0.835915 0.526572 + outer loop + vertex -371.829 -4.67752 13.9189 + vertex -371.982 -5.69219 12.263 + vertex -361.342 -6.61786 13.9217 + endloop + endfacet + facet normal -0.154811 -0.83596 0.526503 + outer loop + vertex -361.342 -6.61786 13.9217 + vertex -371.982 -5.69219 12.263 + vertex -361.492 -7.63392 12.2645 + endloop + endfacet + facet normal -0.166171 -0.831886 0.529484 + outer loop + vertex -403.869 1.56001 13.9153 + vertex -404.027 0.540121 12.2634 + vertex -393.065 -0.597142 13.9168 + endloop + endfacet + facet normal -0.165822 -0.834599 0.525307 + outer loop + vertex -393.065 -0.597142 13.9168 + vertex -404.027 0.540121 12.2634 + vertex -393.234 -1.60552 12.2613 + endloop + endfacet + facet normal -0.138269 -0.693676 0.706891 + outer loop + vertex -404.025 3.04411 15.3412 + vertex -403.869 1.56001 13.9153 + vertex -393.204 0.885545 15.3396 + endloop + endfacet + facet normal -0.138351 -0.692434 0.708092 + outer loop + vertex -393.204 0.885545 15.3396 + vertex -403.869 1.56001 13.9153 + vertex -393.065 -0.597142 13.9168 + endloop + endfacet + facet normal -0.134715 -0.692605 0.708625 + outer loop + vertex -393.204 0.885545 15.3396 + vertex -393.065 -0.597142 13.9168 + vertex -382.518 -1.19283 15.3397 + endloop + endfacet + facet normal -0.134892 -0.690186 0.710948 + outer loop + vertex -382.518 -1.19283 15.3397 + vertex -393.065 -0.597142 13.9168 + vertex -382.38 -2.68159 13.9205 + endloop + endfacet + facet normal -0.1631 -0.835113 0.525342 + outer loop + vertex -393.065 -0.597142 13.9168 + vertex -393.234 -1.60552 12.2613 + vertex -382.38 -2.68159 13.9205 + endloop + endfacet + facet normal -0.163122 -0.834952 0.525592 + outer loop + vertex -382.38 -2.68159 13.9205 + vertex -393.234 -1.60552 12.2613 + vertex -382.547 -3.69199 12.2635 + endloop + endfacet + facet normal -0.173894 -0.830962 0.528453 + outer loop + vertex -425.317 5.99163 13.9257 + vertex -425.436 4.96364 12.2698 + vertex -414.681 3.76268 13.9207 + endloop + endfacet + facet normal -0.173608 -0.833259 0.524918 + outer loop + vertex -414.681 3.76268 13.9207 + vertex -425.436 4.96364 12.2698 + vertex -414.824 2.7486 12.2635 + endloop + endfacet + facet normal -0.14367 -0.690438 0.708981 + outer loop + vertex -425.479 7.4915 15.3534 + vertex -425.317 5.99163 13.9257 + vertex -414.863 5.26954 15.3409 + endloop + endfacet + facet normal -0.143824 -0.687888 0.711425 + outer loop + vertex -414.863 5.26954 15.3409 + vertex -425.317 5.99163 13.9257 + vertex -414.681 3.76268 13.9207 + endloop + endfacet + facet normal -0.141286 -0.687978 0.711846 + outer loop + vertex -414.863 5.26954 15.3409 + vertex -414.681 3.76268 13.9207 + vertex -404.025 3.04411 15.3412 + endloop + endfacet + facet normal -0.140947 -0.69356 0.706477 + outer loop + vertex -404.025 3.04411 15.3412 + vertex -414.681 3.76268 13.9207 + vertex -403.869 1.56001 13.9153 + endloop + endfacet + facet normal -0.16965 -0.834003 0.525031 + outer loop + vertex -414.681 3.76268 13.9207 + vertex -414.824 2.7486 12.2635 + vertex -403.869 1.56001 13.9153 + endloop + endfacet + facet normal -0.170001 -0.831163 0.529404 + outer loop + vertex -403.869 1.56001 13.9153 + vertex -414.824 2.7486 12.2635 + vertex -404.027 0.540121 12.2634 + endloop + endfacet + facet normal -0.181439 -0.828647 0.529551 + outer loop + vertex -445.725 10.4037 13.9252 + vertex -445.869 9.37619 12.2681 + vertex -435.641 8.20072 13.9332 + endloop + endfacet + facet normal -0.181641 -0.827112 0.531876 + outer loop + vertex -435.641 8.20072 13.9332 + vertex -445.869 9.37619 12.2681 + vertex -435.756 7.16175 12.2781 + endloop + endfacet + facet normal -0.150693 -0.689277 0.708653 + outer loop + vertex -445.738 11.8719 15.3506 + vertex -445.725 10.4037 13.9252 + vertex -435.748 9.69697 15.3594 + endloop + endfacet + facet normal -0.150797 -0.687723 0.710139 + outer loop + vertex -435.748 9.69697 15.3594 + vertex -445.725 10.4037 13.9252 + vertex -435.641 8.20072 13.9332 + endloop + endfacet + facet normal -0.147335 -0.687954 0.710642 + outer loop + vertex -435.748 9.69697 15.3594 + vertex -435.641 8.20072 13.9332 + vertex -425.479 7.4915 15.3534 + endloop + endfacet + facet normal -0.147185 -0.69028 0.708414 + outer loop + vertex -425.479 7.4915 15.3534 + vertex -435.641 8.20072 13.9332 + vertex -425.317 5.99163 13.9257 + endloop + endfacet + facet normal -0.176784 -0.828016 0.532106 + outer loop + vertex -435.641 8.20072 13.9332 + vertex -435.756 7.16175 12.2781 + vertex -425.317 5.99163 13.9257 + endloop + endfacet + facet normal -0.176468 -0.830488 0.528345 + outer loop + vertex -425.317 5.99163 13.9257 + vertex -435.756 7.16175 12.2781 + vertex -425.436 4.96364 12.2698 + endloop + endfacet + facet normal -0.190813 -0.834382 0.517104 + outer loop + vertex -466.328 15.0398 13.8611 + vertex -466.625 14.0808 12.2038 + vertex -455.855 12.6622 13.8894 + endloop + endfacet + facet normal -0.191181 -0.831113 0.522207 + outer loop + vertex -455.855 12.6622 13.8894 + vertex -466.625 14.0808 12.2038 + vertex -456.072 11.67 12.2308 + endloop + endfacet + facet normal -0.159411 -0.696058 0.700066 + outer loop + vertex -466.272 16.4566 15.2826 + vertex -466.328 15.0398 13.8611 + vertex -455.78 14.0861 15.3146 + endloop + endfacet + facet normal -0.159493 -0.694225 0.701864 + outer loop + vertex -455.78 14.0861 15.3146 + vertex -466.328 15.0398 13.8611 + vertex -455.855 12.6622 13.8894 + endloop + endfacet + facet normal -0.155698 -0.694753 0.702194 + outer loop + vertex -455.78 14.0861 15.3146 + vertex -455.855 12.6622 13.8894 + vertex -445.738 11.8719 15.3506 + endloop + endfacet + facet normal -0.15607 -0.68872 0.70803 + outer loop + vertex -445.738 11.8719 15.3506 + vertex -455.855 12.6622 13.8894 + vertex -445.725 10.4037 13.9252 + endloop + endfacet + facet normal -0.187355 -0.831975 0.522222 + outer loop + vertex -455.855 12.6622 13.8894 + vertex -456.072 11.67 12.2308 + vertex -445.725 10.4037 13.9252 + endloop + endfacet + facet normal -0.187949 -0.827348 0.529311 + outer loop + vertex -445.725 10.4037 13.9252 + vertex -456.072 11.67 12.2308 + vertex -445.869 9.37619 12.2681 + endloop + endfacet + facet normal -0.193091 -0.808072 0.556539 + outer loop + vertex -488.023 20.2694 14.0469 + vertex -487.981 19.1326 12.4105 + vertex -477.173 17.5775 13.9028 + endloop + endfacet + facet normal -0.191764 -0.829431 0.524663 + outer loop + vertex -477.173 17.5775 13.9028 + vertex -487.981 19.1326 12.4105 + vertex -477.437 16.5964 12.255 + endloop + endfacet + facet normal -0.161855 -0.675875 0.719024 + outer loop + vertex -488.122 21.8361 15.4972 + vertex -488.023 20.2694 14.0469 + vertex -477.26 19.0534 15.3265 + endloop + endfacet + facet normal -0.161841 -0.690081 0.705404 + outer loop + vertex -477.26 19.0534 15.3265 + vertex -488.023 20.2694 14.0469 + vertex -477.173 17.5775 13.9028 + endloop + endfacet + facet normal -0.160293 -0.690209 0.705633 + outer loop + vertex -477.26 19.0534 15.3265 + vertex -477.173 17.5775 13.9028 + vertex -466.272 16.4566 15.2826 + endloop + endfacet + facet normal -0.16017 -0.695956 0.699994 + outer loop + vertex -466.272 16.4566 15.2826 + vertex -477.173 17.5775 13.9028 + vertex -466.328 15.0398 13.8611 + endloop + endfacet + facet normal -0.19206 -0.829359 0.524668 + outer loop + vertex -477.173 17.5775 13.9028 + vertex -477.437 16.5964 12.255 + vertex -466.328 15.0398 13.8611 + endloop + endfacet + facet normal -0.191645 -0.834174 0.517133 + outer loop + vertex -466.328 15.0398 13.8611 + vertex -477.437 16.5964 12.255 + vertex -466.625 14.0808 12.2038 + endloop + endfacet + facet normal -0.157737 -0.642243 0.750095 + outer loop + vertex -497.488 24.4702 15.7829 + vertex -497.429 22.8281 14.3893 + vertex -488.122 21.8361 15.4972 + endloop + endfacet + facet normal -0.15773 -0.67619 0.719645 + outer loop + vertex -488.122 21.8361 15.4972 + vertex -497.429 22.8281 14.3893 + vertex -488.023 20.2694 14.0469 + endloop + endfacet + facet normal -0.196488 -0.798517 0.569002 + outer loop + vertex -497.429 22.8281 14.3893 + vertex -498.433 21.7224 12.4911 + vertex -488.023 20.2694 14.0469 + endloop + endfacet + facet normal -0.195847 -0.807656 0.55618 + outer loop + vertex -488.023 20.2694 14.0469 + vertex -498.433 21.7224 12.4911 + vertex -487.981 19.1326 12.4105 + endloop + endfacet + facet normal -0.256141 -0.795984 0.548453 + outer loop + vertex -509.085 25.4487 14.1221 + vertex -509.186 24.33 12.4512 + vertex -507.974 24.8266 13.7381 + endloop + endfacet + facet normal -0.194162 -0.8398 0.506989 + outer loop + vertex -507.974 24.8266 13.7381 + vertex -509.186 24.33 12.4512 + vertex -508.285 23.9025 12.0882 + endloop + endfacet + facet normal -0.197757 -0.655062 0.729236 + outer loop + vertex -509.076 26.9646 15.4863 + vertex -509.085 25.4487 14.1221 + vertex -507.834 26.2364 15.1688 + endloop + endfacet + facet normal -0.147938 -0.69721 0.701436 + outer loop + vertex -507.834 26.2364 15.1688 + vertex -509.085 25.4487 14.1221 + vertex -507.974 24.8266 13.7381 + endloop + endfacet + facet normal -0.185205 -0.690884 0.698841 + outer loop + vertex -507.834 26.2364 15.1688 + vertex -507.974 24.8266 13.7381 + vertex -504.07 24.8752 14.8207 + endloop + endfacet + facet normal -0.171732 -0.738178 0.652381 + outer loop + vertex -504.07 24.8752 14.8207 + vertex -507.974 24.8266 13.7381 + vertex -504.566 23.6448 13.298 + endloop + endfacet + facet normal -0.222906 -0.831996 0.508032 + outer loop + vertex -507.974 24.8266 13.7381 + vertex -508.285 23.9025 12.0882 + vertex -504.566 23.6448 13.298 + endloop + endfacet + facet normal -0.205646 -0.870717 0.446724 + outer loop + vertex -504.566 23.6448 13.298 + vertex -508.285 23.9025 12.0882 + vertex -505.582 23.0852 11.7392 + endloop + endfacet + facet normal 0.0217751 0.62249 -0.782324 + outer loop + vertex -508.923 27.4308 15.8615 + vertex -508.894 25.8204 14.5809 + vertex -509.076 26.9646 15.4863 + endloop + endfacet + facet normal 0.440702 0.599001 -0.668565 + outer loop + vertex -509.076 26.9646 15.4863 + vertex -508.894 25.8204 14.5809 + vertex -509.085 25.4487 14.1221 + endloop + endfacet + facet normal -0.0167637 0.780302 -0.625179 + outer loop + vertex -508.894 25.8204 14.5809 + vertex -508.933 24.5402 12.9841 + vertex -509.085 25.4487 14.1221 + endloop + endfacet + facet normal 0.47681 0.716784 -0.508795 + outer loop + vertex -509.085 25.4487 14.1221 + vertex -508.933 24.5402 12.9841 + vertex -509.186 24.33 12.4512 + endloop + endfacet + facet normal 0.215224 -0.976531 0.00805226 + outer loop + vertex 504.262 22.4811 10.5033 + vertex 504.121 22.4343 8.57552 + vertex 508.034 23.3097 10.1604 + endloop + endfacet + facet normal 0.252498 -0.963282 -0.0912848 + outer loop + vertex 508.034 23.3097 10.1604 + vertex 504.121 22.4343 8.57552 + vertex 507.778 23.4462 8.01297 + endloop + endfacet + facet normal 0.20599 -0.926509 0.31488 + outer loop + vertex 504.387 23.1392 12.3576 + vertex 504.262 22.4811 10.5033 + vertex 507.938 23.8779 12.2081 + endloop + endfacet + facet normal 0.229918 -0.934951 0.270191 + outer loop + vertex 507.938 23.8779 12.2081 + vertex 504.262 22.4811 10.5033 + vertex 508.034 23.3097 10.1604 + endloop + endfacet + facet normal 0.236857 -0.97151 0.00822327 + outer loop + vertex 488.637 18.6993 10.4569 + vertex 488.456 18.6395 8.62432 + vertex 497.711 20.9119 10.5211 + endloop + endfacet + facet normal 0.233986 -0.971973 0.0227831 + outer loop + vertex 497.711 20.9119 10.5211 + vertex 488.456 18.6395 8.62432 + vertex 497.538 20.8272 8.68027 + endloop + endfacet + facet normal 0.22586 -0.926462 0.30109 + outer loop + vertex 488.691 19.3007 12.2671 + vertex 488.637 18.6993 10.4569 + vertex 497.817 21.5442 12.3248 + endloop + endfacet + facet normal 0.223113 -0.923936 0.310744 + outer loop + vertex 497.817 21.5442 12.3248 + vertex 488.637 18.6993 10.4569 + vertex 497.711 20.9119 10.5211 + endloop + endfacet + facet normal 0.222764 -0.924005 0.310789 + outer loop + vertex 497.817 21.5442 12.3248 + vertex 497.711 20.9119 10.5211 + vertex 504.387 23.1392 12.3576 + endloop + endfacet + facet normal 0.222068 -0.923518 0.31273 + outer loop + vertex 504.387 23.1392 12.3576 + vertex 497.711 20.9119 10.5211 + vertex 504.262 22.4811 10.5033 + endloop + endfacet + facet normal 0.232947 -0.97222 0.022892 + outer loop + vertex 497.711 20.9119 10.5211 + vertex 497.538 20.8272 8.68027 + vertex 504.262 22.4811 10.5033 + endloop + endfacet + facet normal 0.237245 -0.971429 0.00632293 + outer loop + vertex 504.262 22.4811 10.5033 + vertex 497.538 20.8272 8.68027 + vertex 504.121 22.4343 8.57552 + endloop + endfacet + facet normal 0.2289 -0.973394 -0.0104598 + outer loop + vertex 467.409 13.6531 10.4284 + vertex 467.249 13.6353 8.57695 + vertex 478.167 16.1831 10.4234 + endloop + endfacet + facet normal 0.22783 -0.973694 -0.0037192 + outer loop + vertex 478.167 16.1831 10.4234 + vertex 467.249 13.6353 8.57695 + vertex 477.993 16.1494 8.57845 + endloop + endfacet + facet normal 0.219057 -0.932493 0.287177 + outer loop + vertex 467.487 14.2325 12.2499 + vertex 467.409 13.6531 10.4284 + vertex 478.242 16.7581 12.2475 + endloop + endfacet + facet normal 0.219537 -0.932995 0.285172 + outer loop + vertex 478.242 16.7581 12.2475 + vertex 467.409 13.6531 10.4284 + vertex 478.167 16.1831 10.4234 + endloop + endfacet + facet normal 0.226152 -0.931628 0.284471 + outer loop + vertex 478.242 16.7581 12.2475 + vertex 478.167 16.1831 10.4234 + vertex 488.691 19.3007 12.2671 + endloop + endfacet + facet normal 0.221887 -0.927293 0.301485 + outer loop + vertex 488.691 19.3007 12.2671 + vertex 478.167 16.1831 10.4234 + vertex 488.637 18.6993 10.4569 + endloop + endfacet + facet normal 0.233681 -0.972304 -0.00429576 + outer loop + vertex 478.167 16.1831 10.4234 + vertex 477.993 16.1494 8.57845 + vertex 488.637 18.6993 10.4569 + endloop + endfacet + facet normal 0.231489 -0.972798 0.00879752 + outer loop + vertex 488.637 18.6993 10.4569 + vertex 477.993 16.1494 8.57845 + vertex 488.456 18.6395 8.62432 + endloop + endfacet + facet normal 0.217094 -0.976126 -0.00687785 + outer loop + vertex 446.46 8.94597 10.4519 + vertex 446.304 8.92437 8.60779 + vertex 456.854 11.2576 10.4432 + endloop + endfacet + facet normal 0.215998 -0.976394 -0.000234099 + outer loop + vertex 456.854 11.2576 10.4432 + vertex 446.304 8.92437 8.60779 + vertex 456.699 11.2238 8.59422 + endloop + endfacet + facet normal 0.207412 -0.9357 0.285385 + outer loop + vertex 446.549 9.51864 12.265 + vertex 446.46 8.94597 10.4519 + vertex 456.937 11.82 12.2604 + endloop + endfacet + facet normal 0.208621 -0.936948 0.280366 + outer loop + vertex 456.937 11.82 12.2604 + vertex 446.46 8.94597 10.4519 + vertex 456.854 11.2576 10.4432 + endloop + endfacet + facet normal 0.21428 -0.93585 0.279766 + outer loop + vertex 456.937 11.82 12.2604 + vertex 456.854 11.2576 10.4432 + vertex 467.487 14.2325 12.2499 + endloop + endfacet + facet normal 0.212334 -0.933827 0.287891 + outer loop + vertex 467.487 14.2325 12.2499 + vertex 456.854 11.2576 10.4432 + vertex 467.409 13.6531 10.4284 + endloop + endfacet + facet normal 0.221318 -0.975201 -0.000701312 + outer loop + vertex 456.854 11.2576 10.4432 + vertex 456.699 11.2238 8.59422 + vertex 467.409 13.6531 10.4284 + endloop + endfacet + facet normal 0.222809 -0.974812 -0.00991986 + outer loop + vertex 467.409 13.6531 10.4284 + vertex 456.699 11.2238 8.59422 + vertex 467.249 13.6353 8.57695 + endloop + endfacet + facet normal 0.208606 -0.977999 0.00126103 + outer loop + vertex 425.567 4.44913 10.452 + vertex 425.379 4.40665 8.60616 + vertex 436.047 6.68453 10.4534 + endloop + endfacet + facet normal 0.209146 -0.977882 -0.0019974 + outer loop + vertex 436.047 6.68453 10.4534 + vertex 425.379 4.40665 8.60616 + vertex 435.878 6.65219 8.609 + endloop + endfacet + facet normal 0.199283 -0.937277 0.286004 + outer loop + vertex 425.686 5.02805 12.2665 + vertex 425.567 4.44913 10.452 + vertex 436.149 7.25368 12.2697 + endloop + endfacet + facet normal 0.200057 -0.938096 0.282761 + outer loop + vertex 436.149 7.25368 12.2697 + vertex 425.567 4.44913 10.452 + vertex 436.047 6.68453 10.4534 + endloop + endfacet + facet normal 0.204267 -0.937331 0.282286 + outer loop + vertex 436.149 7.25368 12.2697 + vertex 436.047 6.68453 10.4534 + vertex 446.549 9.51864 12.265 + endloop + endfacet + facet normal 0.203419 -0.936445 0.285816 + outer loop + vertex 446.549 9.51864 12.265 + vertex 436.047 6.68453 10.4534 + vertex 446.46 8.94597 10.4519 + endloop + endfacet + facet normal 0.212232 -0.977217 -0.00229151 + outer loop + vertex 436.047 6.68453 10.4534 + vertex 435.878 6.65219 8.609 + vertex 446.46 8.94597 10.4519 + endloop + endfacet + facet normal 0.212931 -0.977046 -0.00651589 + outer loop + vertex 446.46 8.94597 10.4519 + vertex 435.878 6.65219 8.609 + vertex 446.304 8.92437 8.60779 + endloop + endfacet + facet normal 0.200262 -0.979719 0.00672911 + outer loop + vertex 404.663 0.120132 10.4497 + vertex 404.447 0.0631902 8.60219 + vertex 415.096 2.25265 10.4509 + endloop + endfacet + facet normal 0.201927 -0.979395 -0.0032419 + outer loop + vertex 415.096 2.25265 10.4509 + vertex 404.447 0.0631902 8.60219 + vertex 414.891 2.21662 8.6058 + endloop + endfacet + facet normal 0.191563 -0.938608 0.286911 + outer loop + vertex 404.833 0.709606 12.2648 + vertex 404.663 0.120132 10.4497 + vertex 415.243 2.83535 12.2685 + endloop + endfacet + facet normal 0.1919 -0.938972 0.285494 + outer loop + vertex 415.243 2.83535 12.2685 + vertex 404.663 0.120132 10.4497 + vertex 415.096 2.25265 10.4509 + endloop + endfacet + facet normal 0.197029 -0.938118 0.284806 + outer loop + vertex 415.243 2.83535 12.2685 + vertex 415.096 2.25265 10.4509 + vertex 425.686 5.02805 12.2665 + endloop + endfacet + facet normal 0.196668 -0.937732 0.286321 + outer loop + vertex 425.686 5.02805 12.2665 + vertex 415.096 2.25265 10.4509 + vertex 425.567 4.44913 10.452 + endloop + endfacet + facet normal 0.20529 -0.978694 -0.00362824 + outer loop + vertex 415.096 2.25265 10.4509 + vertex 414.891 2.21662 8.6058 + vertex 425.567 4.44913 10.452 + endloop + endfacet + facet normal 0.204407 -0.978884 0.00170916 + outer loop + vertex 425.567 4.44913 10.452 + vertex 414.891 2.21662 8.6058 + vertex 425.379 4.40665 8.60616 + endloop + endfacet + facet normal 0.190806 -0.981627 -0.000742444 + outer loop + vertex 383.532 -4.05285 10.4475 + vertex 383.304 -4.0957 8.60149 + vertex 394.183 -1.98247 10.4481 + endloop + endfacet + facet normal 0.19056 -0.981675 0.000764008 + outer loop + vertex 394.183 -1.98247 10.4481 + vertex 383.304 -4.0957 8.60149 + vertex 393.959 -2.02742 8.6016 + endloop + endfacet + facet normal 0.183293 -0.940028 0.287664 + outer loop + vertex 383.737 -3.45679 12.265 + vertex 383.532 -4.05285 10.4475 + vertex 394.373 -1.38288 12.2647 + endloop + endfacet + facet normal 0.182538 -0.939174 0.290916 + outer loop + vertex 394.373 -1.38288 12.2647 + vertex 383.532 -4.05285 10.4475 + vertex 394.183 -1.98247 10.4481 + endloop + endfacet + facet normal 0.187731 -0.938397 0.290117 + outer loop + vertex 394.373 -1.38288 12.2647 + vertex 394.183 -1.98247 10.4481 + vertex 404.833 0.709606 12.2648 + endloop + endfacet + facet normal 0.18838 -0.939112 0.287372 + outer loop + vertex 404.833 0.709606 12.2648 + vertex 394.183 -1.98247 10.4481 + vertex 404.663 0.120132 10.4497 + endloop + endfacet + facet normal 0.196718 -0.98046 -1.31821e-05 + outer loop + vertex 394.183 -1.98247 10.4481 + vertex 393.959 -2.02742 8.6016 + vertex 404.663 0.120132 10.4497 + endloop + endfacet + facet normal 0.195496 -0.980677 0.00731711 + outer loop + vertex 404.663 0.120132 10.4497 + vertex 393.959 -2.02742 8.6016 + vertex 404.447 0.0631902 8.60219 + endloop + endfacet + facet normal 0.182221 -0.983256 -0.00158205 + outer loop + vertex 361.887 -8.11721 10.4478 + vertex 361.661 -8.15606 8.60017 + vertex 372.714 -6.11074 10.4479 + endloop + endfacet + facet normal 0.182348 -0.983231 -0.00236972 + outer loop + vertex 372.714 -6.11074 10.4479 + vertex 361.661 -8.15606 8.60017 + vertex 372.486 -6.14853 8.6014 + endloop + endfacet + facet normal 0.174837 -0.940485 0.29141 + outer loop + vertex 362.089 -7.51688 12.264 + vertex 361.887 -8.11721 10.4478 + vertex 372.919 -5.50383 12.2632 + endloop + endfacet + facet normal 0.174141 -0.939665 0.294457 + outer loop + vertex 372.919 -5.50383 12.2632 + vertex 361.887 -8.11721 10.4478 + vertex 372.714 -6.11074 10.4479 + endloop + endfacet + facet normal 0.177673 -0.939179 0.293896 + outer loop + vertex 372.919 -5.50383 12.2632 + vertex 372.714 -6.11074 10.4479 + vertex 383.737 -3.45679 12.265 + endloop + endfacet + facet normal 0.178941 -0.940654 0.288359 + outer loop + vertex 383.737 -3.45679 12.265 + vertex 372.714 -6.11074 10.4479 + vertex 383.532 -4.05285 10.4475 + endloop + endfacet + facet normal 0.186868 -0.982381 -0.00294461 + outer loop + vertex 372.714 -6.11074 10.4479 + vertex 372.486 -6.14853 8.6014 + vertex 383.532 -4.05285 10.4475 + endloop + endfacet + facet normal 0.186424 -0.982469 -0.000182482 + outer loop + vertex 383.532 -4.05285 10.4475 + vertex 372.486 -6.14853 8.6014 + vertex 383.304 -4.0957 8.60149 + endloop + endfacet + facet normal 0.172618 -0.984973 0.00566654 + outer loop + vertex 340.93 -11.8393 10.4479 + vertex 340.72 -11.8868 8.60021 + vertex 351.266 -10.0279 10.4475 + endloop + endfacet + facet normal 0.173852 -0.98477 -0.00158185 + outer loop + vertex 351.266 -10.0279 10.4475 + vertex 340.72 -11.8868 8.60021 + vertex 351.052 -10.0629 8.60157 + endloop + endfacet + facet normal 0.166345 -0.944331 0.283844 + outer loop + vertex 341.116 -11.2602 12.2661 + vertex 340.93 -11.8393 10.4479 + vertex 351.458 -9.43865 12.2648 + endloop + endfacet + facet normal 0.165298 -0.94315 0.288349 + outer loop + vertex 351.458 -9.43865 12.2648 + vertex 340.93 -11.8393 10.4479 + vertex 351.266 -10.0279 10.4475 + endloop + endfacet + facet normal 0.170399 -0.942473 0.287591 + outer loop + vertex 351.458 -9.43865 12.2648 + vertex 351.266 -10.0279 10.4475 + vertex 362.089 -7.51688 12.264 + endloop + endfacet + facet normal 0.169325 -0.941227 0.292269 + outer loop + vertex 362.089 -7.51688 12.264 + vertex 351.266 -10.0279 10.4475 + vertex 361.887 -8.11721 10.4478 + endloop + endfacet + facet normal 0.177064 -0.984197 -0.00196616 + outer loop + vertex 351.266 -10.0279 10.4475 + vertex 351.052 -10.0629 8.60157 + vertex 361.887 -8.11721 10.4478 + endloop + endfacet + facet normal 0.17689 -0.98423 -0.000910432 + outer loop + vertex 361.887 -8.11721 10.4478 + vertex 351.052 -10.0629 8.60157 + vertex 361.661 -8.15606 8.60017 + endloop + endfacet + facet normal 0.163304 -0.986574 -0.00193142 + outer loop + vertex 320.546 -15.2713 10.4469 + vertex 320.34 -15.3017 8.60089 + vertex 330.763 -13.5802 10.4476 + endloop + endfacet + facet normal 0.162705 -0.986674 0.0015409 + outer loop + vertex 330.763 -13.5802 10.4476 + vertex 320.34 -15.3017 8.60089 + vertex 330.56 -13.6164 8.60076 + endloop + endfacet + facet normal 0.157268 -0.945328 0.285695 + outer loop + vertex 320.738 -14.6897 12.266 + vertex 320.546 -15.2713 10.4469 + vertex 330.948 -12.9916 12.264 + endloop + endfacet + facet normal 0.156267 -0.944185 0.28999 + outer loop + vertex 330.948 -12.9916 12.264 + vertex 320.546 -15.2713 10.4469 + vertex 330.763 -13.5802 10.4476 + endloop + endfacet + facet normal 0.160634 -0.943643 0.289369 + outer loop + vertex 330.948 -12.9916 12.264 + vertex 330.763 -13.5802 10.4476 + vertex 341.116 -11.2602 12.2661 + endloop + endfacet + facet normal 0.161777 -0.944928 0.2845 + outer loop + vertex 341.116 -11.2602 12.2661 + vertex 330.763 -13.5802 10.4476 + vertex 340.93 -11.8393 10.4479 + endloop + endfacet + facet normal 0.168756 -0.985657 0.000857711 + outer loop + vertex 330.763 -13.5802 10.4476 + vertex 330.56 -13.6164 8.60076 + vertex 340.93 -11.8393 10.4479 + endloop + endfacet + facet normal 0.167823 -0.985797 0.00623353 + outer loop + vertex 340.93 -11.8393 10.4479 + vertex 330.56 -13.6164 8.60076 + vertex 340.72 -11.8868 8.60021 + endloop + endfacet + facet normal 0.154584 -0.987961 -0.00600798 + outer loop + vertex 299.463 -18.6206 10.4477 + vertex 299.246 -18.6433 8.60152 + vertex 310.119 -16.9532 10.4477 + endloop + endfacet + facet normal 0.153741 -0.988111 -0.000902501 + outer loop + vertex 310.119 -16.9532 10.4477 + vertex 299.246 -18.6433 8.60152 + vertex 309.906 -16.9847 8.59995 + endloop + endfacet + facet normal 0.148779 -0.945605 0.289303 + outer loop + vertex 299.658 -18.0337 12.2653 + vertex 299.463 -18.6206 10.4477 + vertex 310.306 -16.3592 12.263 + endloop + endfacet + facet normal 0.147766 -0.944372 0.293815 + outer loop + vertex 310.306 -16.3592 12.263 + vertex 299.463 -18.6206 10.4477 + vertex 310.119 -16.9532 10.4477 + endloop + endfacet + facet normal 0.150998 -0.944002 0.293361 + outer loop + vertex 310.306 -16.3592 12.263 + vertex 310.119 -16.9532 10.4477 + vertex 320.738 -14.6897 12.266 + endloop + endfacet + facet normal 0.152598 -0.94589 0.286366 + outer loop + vertex 320.738 -14.6897 12.266 + vertex 310.119 -16.9532 10.4477 + vertex 320.546 -15.2713 10.4469 + endloop + endfacet + facet normal 0.159248 -0.987237 -0.00155271 + outer loop + vertex 310.119 -16.9532 10.4477 + vertex 309.906 -16.9847 8.59995 + vertex 320.546 -15.2713 10.4469 + endloop + endfacet + facet normal 0.159233 -0.98724 -0.00146714 + outer loop + vertex 320.546 -15.2713 10.4469 + vertex 309.906 -16.9847 8.59995 + vertex 320.34 -15.3017 8.60089 + endloop + endfacet + facet normal 0.144617 -0.989488 -0.000454651 + outer loop + vertex 277.942 -21.8196 10.4472 + vertex 277.729 -21.8499 8.60069 + vertex 288.688 -20.2491 10.447 + endloop + endfacet + facet normal 0.144528 -0.989501 8.91145e-05 + outer loop + vertex 288.688 -20.2491 10.447 + vertex 277.729 -21.8499 8.60069 + vertex 288.472 -20.2808 8.6 + endloop + endfacet + facet normal 0.138555 -0.947083 0.289546 + outer loop + vertex 278.138 -21.2358 12.2631 + vertex 277.942 -21.8196 10.4472 + vertex 288.884 -19.6634 12.2639 + endloop + endfacet + facet normal 0.138396 -0.946885 0.290269 + outer loop + vertex 288.884 -19.6634 12.2639 + vertex 277.942 -21.8196 10.4472 + vertex 288.688 -20.2491 10.447 + endloop + endfacet + facet normal 0.143113 -0.946389 0.289598 + outer loop + vertex 288.884 -19.6634 12.2639 + vertex 288.688 -20.2491 10.447 + vertex 299.658 -18.0337 12.2653 + endloop + endfacet + facet normal 0.142995 -0.946243 0.290131 + outer loop + vertex 299.658 -18.0337 12.2653 + vertex 288.688 -20.2491 10.447 + vertex 299.463 -18.6206 10.4477 + endloop + endfacet + facet normal 0.149443 -0.98877 -0.000497918 + outer loop + vertex 288.688 -20.2491 10.447 + vertex 288.472 -20.2808 8.6 + vertex 299.463 -18.6206 10.4477 + endloop + endfacet + facet normal 0.150261 -0.988631 -0.0054913 + outer loop + vertex 299.463 -18.6206 10.4477 + vertex 288.472 -20.2808 8.6 + vertex 299.246 -18.6433 8.60152 + endloop + endfacet + facet normal 0.134514 -0.990907 -0.00291732 + outer loop + vertex 256.805 -24.761 10.4469 + vertex 256.601 -24.7834 8.60171 + vertex 267.311 -23.3349 10.4483 + endloop + endfacet + facet normal 0.134339 -0.990934 -0.00187983 + outer loop + vertex 267.311 -23.3349 10.4483 + vertex 256.601 -24.7834 8.60171 + vertex 267.102 -23.3597 8.60039 + endloop + endfacet + facet normal 0.129758 -0.948614 0.288606 + outer loop + vertex 256.996 -24.1822 12.2638 + vertex 256.805 -24.761 10.4469 + vertex 267.506 -22.7445 12.2638 + endloop + endfacet + facet normal 0.128523 -0.947073 0.294169 + outer loop + vertex 267.506 -22.7445 12.2638 + vertex 256.805 -24.761 10.4469 + vertex 267.311 -23.3349 10.4483 + endloop + endfacet + facet normal 0.134334 -0.946516 0.293365 + outer loop + vertex 267.506 -22.7445 12.2638 + vertex 267.311 -23.3349 10.4483 + vertex 278.138 -21.2358 12.2631 + endloop + endfacet + facet normal 0.13507 -0.947436 0.290036 + outer loop + vertex 278.138 -21.2358 12.2631 + vertex 267.311 -23.3349 10.4483 + vertex 277.942 -21.8196 10.4472 + endloop + endfacet + facet normal 0.141104 -0.989991 -0.00265899 + outer loop + vertex 267.311 -23.3349 10.4483 + vertex 267.102 -23.3597 8.60039 + vertex 277.942 -21.8196 10.4472 + endloop + endfacet + facet normal 0.140659 -0.990058 1.18164e-05 + outer loop + vertex 277.942 -21.8196 10.4472 + vertex 267.102 -23.3597 8.60039 + vertex 277.729 -21.8499 8.60069 + endloop + endfacet + facet normal 0.124737 -0.992185 -0.0030166 + outer loop + vertex 235.906 -27.451 10.447 + vertex 235.701 -27.4713 8.60165 + vertex 246.363 -26.1364 10.4471 + endloop + endfacet + facet normal 0.124444 -0.992226 -0.00129632 + outer loop + vertex 246.363 -26.1364 10.4471 + vertex 235.701 -27.4713 8.60165 + vertex 246.158 -26.1598 8.60011 + endloop + endfacet + facet normal 0.119718 -0.949918 0.288657 + outer loop + vertex 236.1 -26.8745 12.264 + vertex 235.906 -27.451 10.447 + vertex 246.554 -25.5568 12.2645 + endloop + endfacet + facet normal 0.119363 -0.949471 0.290271 + outer loop + vertex 246.554 -25.5568 12.2645 + vertex 235.906 -27.451 10.447 + vertex 246.363 -26.1364 10.4471 + endloop + endfacet + facet normal 0.124948 -0.948979 0.289527 + outer loop + vertex 246.554 -25.5568 12.2645 + vertex 246.363 -26.1364 10.4471 + vertex 256.996 -24.1822 12.2638 + endloop + endfacet + facet normal 0.125011 -0.949057 0.289245 + outer loop + vertex 256.996 -24.1822 12.2638 + vertex 246.363 -26.1364 10.4471 + vertex 256.805 -24.761 10.4469 + endloop + endfacet + facet normal 0.130587 -0.991435 -0.00198894 + outer loop + vertex 246.363 -26.1364 10.4471 + vertex 246.158 -26.1598 8.60011 + vertex 256.805 -24.761 10.4469 + endloop + endfacet + facet normal 0.130671 -0.991423 -0.00248451 + outer loop + vertex 256.805 -24.761 10.4469 + vertex 246.158 -26.1598 8.60011 + vertex 256.601 -24.7834 8.60171 + endloop + endfacet + facet normal 0.115494 -0.993278 -0.00776389 + outer loop + vertex 214.791 -29.9576 10.448 + vertex 214.581 -29.9676 8.60256 + vertex 225.384 -28.7259 10.4471 + endloop + endfacet + facet normal 0.114535 -0.993417 -0.00205651 + outer loop + vertex 225.384 -28.7259 10.4471 + vertex 214.581 -29.9676 8.60256 + vertex 225.176 -28.746 8.60155 + endloop + endfacet + facet normal 0.111114 -0.950803 0.289183 + outer loop + vertex 214.991 -29.3812 12.2664 + vertex 214.791 -29.9576 10.448 + vertex 225.579 -28.1447 12.2634 + endloop + endfacet + facet normal 0.110484 -0.949982 0.292109 + outer loop + vertex 225.579 -28.1447 12.2634 + vertex 214.791 -29.9576 10.448 + vertex 225.384 -28.7259 10.4471 + endloop + endfacet + facet normal 0.114642 -0.949658 0.291559 + outer loop + vertex 225.579 -28.1447 12.2634 + vertex 225.384 -28.7259 10.4471 + vertex 236.1 -26.8745 12.264 + endloop + endfacet + facet normal 0.115142 -0.950299 0.289265 + outer loop + vertex 236.1 -26.8745 12.264 + vertex 225.384 -28.7259 10.4471 + vertex 235.906 -27.451 10.447 + endloop + endfacet + facet normal 0.120279 -0.992736 -0.00271031 + outer loop + vertex 225.384 -28.7259 10.4471 + vertex 225.176 -28.746 8.60155 + vertex 235.906 -27.451 10.447 + endloop + endfacet + facet normal 0.120245 -0.992741 -0.00251049 + outer loop + vertex 235.906 -27.451 10.447 + vertex 225.176 -28.746 8.60155 + vertex 235.701 -27.4713 8.60165 + endloop + endfacet + facet normal 0.104443 -0.994526 -0.00310093 + outer loop + vertex 193.483 -32.2504 10.4469 + vertex 193.273 -32.2667 8.60072 + vertex 204.15 -31.1302 10.4472 + endloop + endfacet + facet normal 0.103987 -0.994579 -0.000386132 + outer loop + vertex 204.15 -31.1302 10.4472 + vertex 193.273 -32.2667 8.60072 + vertex 203.939 -31.1515 8.60026 + endloop + endfacet + facet normal 0.100018 -0.951593 0.290632 + outer loop + vertex 193.682 -31.6746 12.2639 + vertex 193.483 -32.2504 10.4469 + vertex 204.348 -30.5535 12.2641 + endloop + endfacet + facet normal 0.099913 -0.951453 0.291126 + outer loop + vertex 204.348 -30.5535 12.2641 + vertex 193.483 -32.2504 10.4469 + vertex 204.15 -31.1302 10.4472 + endloop + endfacet + facet normal 0.1047 -0.951129 0.290502 + outer loop + vertex 204.348 -30.5535 12.2641 + vertex 204.15 -31.1302 10.4472 + vertex 214.991 -29.3812 12.2664 + endloop + endfacet + facet normal 0.104802 -0.951264 0.290023 + outer loop + vertex 214.991 -29.3812 12.2664 + vertex 204.15 -31.1302 10.4472 + vertex 214.791 -29.9576 10.448 + endloop + endfacet + facet normal 0.109531 -0.993983 -0.00102474 + outer loop + vertex 204.15 -31.1302 10.4472 + vertex 203.939 -31.1515 8.60026 + vertex 214.791 -29.9576 10.448 + endloop + endfacet + facet normal 0.110567 -0.993843 -0.00720154 + outer loop + vertex 214.791 -29.9576 10.448 + vertex 203.939 -31.1515 8.60026 + vertex 214.581 -29.9676 8.60256 + endloop + endfacet + facet normal 0.0932836 -0.995636 -0.00250947 + outer loop + vertex 172.027 -34.3241 10.4476 + vertex 171.816 -34.3392 8.60031 + vertex 182.783 -33.3163 10.4475 + endloop + endfacet + facet normal 0.0930042 -0.995665 -0.000834549 + outer loop + vertex 182.783 -33.3163 10.4475 + vertex 171.816 -34.3392 8.60031 + vertex 182.573 -33.3344 8.59991 + endloop + endfacet + facet normal 0.0901388 -0.952643 0.290425 + outer loop + vertex 172.228 -33.7511 12.2647 + vertex 172.027 -34.3241 10.4476 + vertex 182.982 -32.734 12.2633 + endloop + endfacet + facet normal 0.0891273 -0.951239 0.295298 + outer loop + vertex 182.982 -32.734 12.2633 + vertex 172.027 -34.3241 10.4476 + vertex 182.783 -33.3163 10.4475 + endloop + endfacet + facet normal 0.094138 -0.950954 0.294659 + outer loop + vertex 182.982 -32.734 12.2633 + vertex 182.783 -33.3163 10.4475 + vertex 193.682 -31.6746 12.2639 + endloop + endfacet + facet normal 0.0948428 -0.951918 0.291301 + outer loop + vertex 193.682 -31.6746 12.2639 + vertex 182.783 -33.3163 10.4475 + vertex 193.483 -32.2504 10.4469 + endloop + endfacet + facet normal 0.0991263 -0.995074 -0.00153697 + outer loop + vertex 182.783 -33.3163 10.4475 + vertex 182.573 -33.3344 8.59991 + vertex 193.483 -32.2504 10.4469 + endloop + endfacet + facet normal 0.0992893 -0.995055 -0.00251091 + outer loop + vertex 193.483 -32.2504 10.4469 + vertex 182.573 -33.3344 8.59991 + vertex 193.273 -32.2667 8.60072 + endloop + endfacet + facet normal 0.0826051 -0.996569 -0.00509914 + outer loop + vertex 150.373 -36.1701 10.4483 + vertex 150.16 -36.1783 8.60038 + vertex 161.211 -35.2717 10.447 + endloop + endfacet + facet normal 0.082035 -0.996628 -0.00165821 + outer loop + vertex 161.211 -35.2717 10.447 + vertex 150.16 -36.1783 8.60038 + vertex 161 -35.286 8.60081 + endloop + endfacet + facet normal 0.0781729 -0.952075 0.295705 + outer loop + vertex 150.576 -35.5896 12.2635 + vertex 150.373 -36.1701 10.4483 + vertex 161.414 -34.6996 12.2639 + endloop + endfacet + facet normal 0.0790572 -0.953343 0.291354 + outer loop + vertex 161.414 -34.6996 12.2639 + vertex 150.373 -36.1701 10.4483 + vertex 161.211 -35.2717 10.447 + endloop + endfacet + facet normal 0.0835799 -0.953132 0.290783 + outer loop + vertex 161.414 -34.6996 12.2639 + vertex 161.211 -35.2717 10.447 + vertex 172.228 -33.7511 12.2647 + endloop + endfacet + facet normal 0.0834796 -0.952991 0.291273 + outer loop + vertex 172.228 -33.7511 12.2647 + vertex 161.211 -35.2717 10.447 + vertex 172.027 -34.3241 10.4476 + endloop + endfacet + facet normal 0.0872809 -0.996181 -0.00226088 + outer loop + vertex 161.211 -35.2717 10.447 + vertex 161 -35.286 8.60081 + vertex 172.027 -34.3241 10.4476 + endloop + endfacet + facet normal 0.0872063 -0.996189 -0.00181172 + outer loop + vertex 172.027 -34.3241 10.4476 + vertex 161 -35.286 8.60081 + vertex 171.816 -34.3392 8.60031 + endloop + endfacet + facet normal 0.0705832 -0.997493 -0.00503842 + outer loop + vertex 128.822 -37.7468 10.4478 + vertex 128.614 -37.7522 8.60074 + vertex 139.564 -36.9867 10.447 + endloop + endfacet + facet normal 0.0695225 -0.99758 0.00128866 + outer loop + vertex 139.564 -36.9867 10.447 + vertex 128.614 -37.7522 8.60074 + vertex 139.352 -37.0039 8.59998 + endloop + endfacet + facet normal 0.0664355 -0.953136 0.295158 + outer loop + vertex 129.026 -37.1703 12.2634 + vertex 128.822 -37.7468 10.4478 + vertex 139.768 -36.4211 12.2649 + endloop + endfacet + facet normal 0.0675847 -0.954804 0.289452 + outer loop + vertex 139.768 -36.4211 12.2649 + vertex 128.822 -37.7468 10.4478 + vertex 139.564 -36.9867 10.447 + endloop + endfacet + facet normal 0.0734762 -0.954589 0.288722 + outer loop + vertex 139.768 -36.4211 12.2649 + vertex 139.564 -36.9867 10.447 + vertex 150.576 -35.5896 12.2635 + endloop + endfacet + facet normal 0.0719079 -0.952325 0.296489 + outer loop + vertex 150.576 -35.5896 12.2635 + vertex 139.564 -36.9867 10.447 + vertex 150.373 -36.1701 10.4483 + endloop + endfacet + facet normal 0.0753312 -0.997158 0.000617756 + outer loop + vertex 139.564 -36.9867 10.447 + vertex 139.352 -37.0039 8.59998 + vertex 150.373 -36.1701 10.4483 + endloop + endfacet + facet normal 0.0761597 -0.997086 -0.00435548 + outer loop + vertex 150.373 -36.1701 10.4483 + vertex 139.352 -37.0039 8.59998 + vertex 150.16 -36.1783 8.60038 + endloop + endfacet + facet normal 0.058732 -0.998273 -0.00142819 + outer loop + vertex 107.526 -39.0481 10.448 + vertex 107.319 -39.0577 8.6001 + vertex 118.152 -38.423 10.4473 + endloop + endfacet + facet normal 0.0582431 -0.998301 0.00144902 + outer loop + vertex 118.152 -38.423 10.4473 + vertex 107.319 -39.0577 8.6001 + vertex 117.944 -38.4377 8.60038 + endloop + endfacet + facet normal 0.0562576 -0.955202 0.29056 + outer loop + vertex 107.732 -38.4828 12.2666 + vertex 107.526 -39.0481 10.448 + vertex 118.354 -37.8579 12.2641 + endloop + endfacet + facet normal 0.0562135 -0.955137 0.29078 + outer loop + vertex 118.354 -37.8579 12.2641 + vertex 107.526 -39.0481 10.448 + vertex 118.152 -38.423 10.4473 + endloop + endfacet + facet normal 0.0615527 -0.955002 0.290143 + outer loop + vertex 118.354 -37.8579 12.2641 + vertex 118.152 -38.423 10.4473 + vertex 129.026 -37.1703 12.2634 + endloop + endfacet + facet normal 0.0603981 -0.953311 0.29589 + outer loop + vertex 129.026 -37.1703 12.2634 + vertex 118.152 -38.423 10.4473 + vertex 128.822 -37.7468 10.4478 + endloop + endfacet + facet normal 0.0632438 -0.997998 0.000885501 + outer loop + vertex 118.152 -38.423 10.4473 + vertex 117.944 -38.4377 8.60038 + vertex 128.822 -37.7468 10.4478 + endloop + endfacet + facet normal 0.0641218 -0.997933 -0.00430828 + outer loop + vertex 128.822 -37.7468 10.4478 + vertex 117.944 -38.4377 8.60038 + vertex 128.614 -37.7522 8.60074 + endloop + endfacet + facet normal 0.0466057 -0.998911 -0.00214393 + outer loop + vertex 86.2375 -40.0889 10.4484 + vertex 86.0267 -40.0948 8.60016 + vertex 96.9062 -39.5911 10.4476 + endloop + endfacet + facet normal 0.0462043 -0.998932 0.000225587 + outer loop + vertex 96.9062 -39.5911 10.4476 + vertex 86.0267 -40.0948 8.60016 + vertex 96.6974 -39.6012 8.60072 + endloop + endfacet + facet normal 0.043548 -0.953971 0.296721 + outer loop + vertex 86.4393 -39.5151 12.2635 + vertex 86.2375 -40.0889 10.4484 + vertex 97.1094 -39.0278 12.2642 + endloop + endfacet + facet normal 0.0446053 -0.955581 0.291333 + outer loop + vertex 97.1094 -39.0278 12.2642 + vertex 86.2375 -40.0889 10.4484 + vertex 96.9062 -39.5911 10.4476 + endloop + endfacet + facet normal 0.0489615 -0.955522 0.290827 + outer loop + vertex 97.1094 -39.0278 12.2642 + vertex 96.9062 -39.5911 10.4476 + vertex 107.732 -38.4828 12.2666 + endloop + endfacet + facet normal 0.04884 -0.955341 0.29144 + outer loop + vertex 107.732 -38.4828 12.2666 + vertex 96.9062 -39.5911 10.4476 + vertex 107.526 -39.0481 10.448 + endloop + endfacet + facet normal 0.0510668 -0.998695 -0.00032564 + outer loop + vertex 96.9062 -39.5911 10.4476 + vertex 96.6974 -39.6012 8.60072 + vertex 107.526 -39.0481 10.448 + endloop + endfacet + facet normal 0.051108 -0.998693 -0.000568082 + outer loop + vertex 107.526 -39.0481 10.448 + vertex 96.6974 -39.6012 8.60072 + vertex 107.319 -39.0577 8.6001 + endloop + endfacet + facet normal 0.0334313 -0.999438 -0.00255959 + outer loop + vertex 64.5816 -40.8734 10.447 + vertex 64.3728 -40.8756 8.60158 + vertex 75.4631 -40.5094 10.4472 + endloop + endfacet + facet normal 0.0330744 -0.999453 -0.000412237 + outer loop + vertex 75.4631 -40.5094 10.4472 + vertex 64.3728 -40.8756 8.60158 + vertex 75.2539 -40.5156 8.60059 + endloop + endfacet + facet normal 0.0317995 -0.956034 0.291526 + outer loop + vertex 64.7916 -40.3125 12.2635 + vertex 64.5816 -40.8734 10.447 + vertex 75.6726 -39.9499 12.2655 + endloop + endfacet + facet normal 0.0319838 -0.956325 0.29055 + outer loop + vertex 75.6726 -39.9499 12.2655 + vertex 64.5816 -40.8734 10.447 + vertex 75.4631 -40.5094 10.4472 + endloop + endfacet + facet normal 0.0386757 -0.956313 0.289776 + outer loop + vertex 75.6726 -39.9499 12.2655 + vertex 75.4631 -40.5094 10.4472 + vertex 86.4393 -39.5151 12.2635 + endloop + endfacet + facet normal 0.037199 -0.954015 0.297441 + outer loop + vertex 86.4393 -39.5151 12.2635 + vertex 75.4631 -40.5094 10.4472 + vertex 86.2375 -40.0889 10.4484 + endloop + endfacet + facet normal 0.0389969 -0.999239 -0.00108385 + outer loop + vertex 75.4631 -40.5094 10.4472 + vertex 75.2539 -40.5156 8.60059 + vertex 86.2375 -40.0889 10.4484 + endloop + endfacet + facet normal 0.0390297 -0.999237 -0.00127893 + outer loop + vertex 86.2375 -40.0889 10.4484 + vertex 75.2539 -40.5156 8.60059 + vertex 86.0267 -40.0948 8.60016 + endloop + endfacet + facet normal 0.0225062 -0.999739 -0.00383707 + outer loop + vertex 42.7979 -41.4284 10.447 + vertex 42.589 -41.426 8.60158 + vertex 53.6581 -41.1839 10.4471 + endloop + endfacet + facet normal 0.0221518 -0.999753 -0.00170937 + outer loop + vertex 53.6581 -41.1839 10.4471 + vertex 42.589 -41.426 8.60158 + vertex 53.4474 -41.1854 8.60083 + endloop + endfacet + facet normal 0.0219949 -0.956598 0.290578 + outer loop + vertex 43.0041 -40.8715 12.2648 + vertex 42.7979 -41.4284 10.447 + vertex 53.868 -40.6219 12.264 + endloop + endfacet + facet normal 0.0215155 -0.955823 0.293155 + outer loop + vertex 53.868 -40.6219 12.264 + vertex 42.7979 -41.4284 10.447 + vertex 53.6581 -41.1839 10.4471 + endloop + endfacet + facet normal 0.0270912 -0.955874 0.292526 + outer loop + vertex 53.868 -40.6219 12.264 + vertex 53.6581 -41.1839 10.4471 + vertex 64.7916 -40.3125 12.2635 + endloop + endfacet + facet normal 0.0271792 -0.956015 0.292055 + outer loop + vertex 64.7916 -40.3125 12.2635 + vertex 53.6581 -41.1839 10.4471 + vertex 64.5816 -40.8734 10.447 + endloop + endfacet + facet normal 0.0284144 -0.999593 -0.00242401 + outer loop + vertex 53.6581 -41.1839 10.4471 + vertex 53.4474 -41.1854 8.60083 + vertex 64.5816 -40.8734 10.447 + endloop + endfacet + facet normal 0.0283415 -0.999596 -0.00198349 + outer loop + vertex 64.5816 -40.8734 10.447 + vertex 53.4474 -41.1854 8.60083 + vertex 64.3728 -40.8756 8.60158 + endloop + endfacet + facet normal 0.011631 -0.999932 0.000103766 + outer loop + vertex 21.4227 -41.7381 10.4473 + vertex 21.2162 -41.7407 8.60069 + vertex 32.0639 -41.6143 10.447 + endloop + endfacet + facet normal 0.011552 -0.999933 0.000568064 + outer loop + vertex 32.0639 -41.6143 10.447 + vertex 21.2162 -41.7407 8.60069 + vertex 31.8549 -41.6178 8.59994 + endloop + endfacet + facet normal 0.011226 -0.956415 0.291796 + outer loop + vertex 21.6289 -41.1816 12.2633 + vertex 21.4227 -41.7381 10.4473 + vertex 32.2684 -41.0565 12.2642 + endloop + endfacet + facet normal 0.01113 -0.956259 0.29231 + outer loop + vertex 32.2684 -41.0565 12.2642 + vertex 21.4227 -41.7381 10.4473 + vertex 32.0639 -41.6143 10.447 + endloop + endfacet + facet normal 0.0164623 -0.956356 0.29174 + outer loop + vertex 32.2684 -41.0565 12.2642 + vertex 32.0639 -41.6143 10.447 + vertex 43.0041 -40.8715 12.2648 + endloop + endfacet + facet normal 0.0165684 -0.956527 0.291172 + outer loop + vertex 43.0041 -40.8715 12.2648 + vertex 32.0639 -41.6143 10.447 + vertex 42.7979 -41.4284 10.447 + endloop + endfacet + facet normal 0.0173199 -0.99985 -8.47212e-05 + outer loop + vertex 32.0639 -41.6143 10.447 + vertex 31.8549 -41.6178 8.59994 + vertex 42.7979 -41.4284 10.447 + endloop + endfacet + facet normal 0.0178643 -0.999835 -0.00331176 + outer loop + vertex 42.7979 -41.4284 10.447 + vertex 31.8549 -41.6178 8.59994 + vertex 42.589 -41.426 8.60158 + endloop + endfacet + facet normal 0.00250342 -0.99999 -0.00364048 + outer loop + vertex 0.0951561 -41.8435 10.4473 + vertex -0.113945 -41.8373 8.60078 + vertex 10.784 -41.8168 10.448 + endloop + endfacet + facet normal 0.00136194 -0.999994 0.00309378 + outer loop + vertex 10.784 -41.8168 10.448 + vertex -0.113945 -41.8373 8.60078 + vertex 10.5756 -41.8228 8.60021 + endloop + endfacet + facet normal 0.00261099 -0.95681 0.290701 + outer loop + vertex 0.307027 -41.2904 12.2658 + vertex 0.0951561 -41.8435 10.4473 + vertex 10.9936 -41.2618 12.2642 + endloop + endfacet + facet normal 0.00237475 -0.956418 0.291992 + outer loop + vertex 10.9936 -41.2618 12.2642 + vertex 0.0951561 -41.8435 10.4473 + vertex 10.784 -41.8168 10.448 + endloop + endfacet + facet normal 0.00723353 -0.956552 0.291473 + outer loop + vertex 10.9936 -41.2618 12.2642 + vertex 10.784 -41.8168 10.448 + vertex 21.6289 -41.1816 12.2633 + endloop + endfacet + facet normal 0.0070921 -0.95632 0.292236 + outer loop + vertex 21.6289 -41.1816 12.2633 + vertex 10.784 -41.8168 10.448 + vertex 21.4227 -41.7381 10.4473 + endloop + endfacet + facet normal 0.00739393 -0.99997 0.00241361 + outer loop + vertex 10.784 -41.8168 10.448 + vertex 10.5756 -41.8228 8.60021 + vertex 21.4227 -41.7381 10.4473 + endloop + endfacet + facet normal 0.00771262 -0.99997 0.000542079 + outer loop + vertex 21.4227 -41.7381 10.4473 + vertex 10.5756 -41.8228 8.60021 + vertex 21.2162 -41.7407 8.60069 + endloop + endfacet + facet normal -0.00687541 -0.999976 -0.000339893 + outer loop + vertex -21.2113 -41.7414 10.4471 + vertex -21.4185 -41.7394 8.6004 + vertex -10.5982 -41.8144 10.4475 + endloop + endfacet + facet normal -0.00738364 -0.999969 0.00263766 + outer loop + vertex -10.5982 -41.8144 10.4475 + vertex -21.4185 -41.7394 8.6004 + vertex -10.8081 -41.8177 8.60012 + endloop + endfacet + facet normal -0.00576403 -0.957788 0.287416 + outer loop + vertex -21.0059 -41.1967 12.2665 + vertex -21.2113 -41.7414 10.4471 + vertex -10.3916 -41.2614 12.2638 + endloop + endfacet + facet normal -0.00658513 -0.956413 0.291943 + outer loop + vertex -10.3916 -41.2614 12.2638 + vertex -21.2113 -41.7414 10.4471 + vertex -10.5982 -41.8144 10.4475 + endloop + endfacet + facet normal -0.00265162 -0.956555 0.291539 + outer loop + vertex -10.3916 -41.2614 12.2638 + vertex -10.5982 -41.8144 10.4475 + vertex 0.307027 -41.2904 12.2658 + endloop + endfacet + facet normal -0.00260037 -0.956641 0.291257 + outer loop + vertex 0.307027 -41.2904 12.2658 + vertex -10.5982 -41.8144 10.4475 + vertex 0.0951561 -41.8435 10.4473 + endloop + endfacet + facet normal -0.00272256 -0.999994 0.00210798 + outer loop + vertex -10.5982 -41.8144 10.4475 + vertex -10.8081 -41.8177 8.60012 + vertex 0.0951561 -41.8435 10.4473 + endloop + endfacet + facet normal -0.00183184 -0.999993 -0.00314957 + outer loop + vertex 0.0951561 -41.8435 10.4473 + vertex -10.8081 -41.8177 8.60012 + vertex -0.113945 -41.8373 8.60078 + endloop + endfacet + facet normal -0.0175557 -0.999844 -0.0019396 + outer loop + vertex -42.2614 -41.4377 10.4474 + vertex -42.467 -41.4305 8.60177 + vertex -31.729 -41.6226 10.4475 + endloop + endfacet + facet normal -0.0171218 -0.999843 -0.0044639 + outer loop + vertex -31.729 -41.6226 10.4475 + vertex -42.467 -41.4305 8.60177 + vertex -31.9335 -41.6109 8.60193 + endloop + endfacet + facet normal -0.0165234 -0.956481 0.291327 + outer loop + vertex -42.0556 -40.8881 12.2634 + vertex -42.2614 -41.4377 10.4474 + vertex -31.5253 -41.0697 12.2643 + endloop + endfacet + facet normal -0.0167902 -0.956023 0.292811 + outer loop + vertex -31.5253 -41.0697 12.2643 + vertex -42.2614 -41.4377 10.4474 + vertex -31.729 -41.6226 10.4475 + endloop + endfacet + facet normal -0.0116029 -0.956256 0.2923 + outer loop + vertex -31.5253 -41.0697 12.2643 + vertex -31.729 -41.6226 10.4475 + vertex -21.0059 -41.1967 12.2665 + endloop + endfacet + facet normal -0.010808 -0.957591 0.287927 + outer loop + vertex -21.0059 -41.1967 12.2665 + vertex -31.729 -41.6226 10.4475 + vertex -21.2113 -41.7414 10.4471 + endloop + endfacet + facet normal -0.0112964 -0.999923 -0.00510988 + outer loop + vertex -31.729 -41.6226 10.4475 + vertex -31.9335 -41.6109 8.60193 + vertex -21.2113 -41.7414 10.4471 + endloop + endfacet + facet normal -0.0122206 -0.999925 0.00025987 + outer loop + vertex -21.2113 -41.7414 10.4471 + vertex -31.9335 -41.6109 8.60193 + vertex -21.4185 -41.7394 8.6004 + endloop + endfacet + facet normal -0.0288335 -0.999583 -0.00143418 + outer loop + vertex -63.8928 -40.89 10.4476 + vertex -64.1053 -40.8812 8.60158 + vertex -52.96 -41.2053 10.4479 + endloop + endfacet + facet normal -0.0289393 -0.999581 -0.000795161 + outer loop + vertex -52.96 -41.2053 10.4479 + vertex -64.1053 -40.8812 8.60158 + vertex -53.1703 -41.1978 8.60029 + endloop + endfacet + facet normal -0.0269859 -0.956874 0.289248 + outer loop + vertex -63.6783 -40.3469 12.2642 + vertex -63.8928 -40.89 10.4476 + vertex -52.7489 -40.6549 12.2648 + endloop + endfacet + facet normal -0.0275788 -0.955793 0.292743 + outer loop + vertex -52.7489 -40.6549 12.2648 + vertex -63.8928 -40.89 10.4476 + vertex -52.96 -41.2053 10.4479 + endloop + endfacet + facet normal -0.0208122 -0.95617 0.292071 + outer loop + vertex -52.7489 -40.6549 12.2648 + vertex -52.96 -41.2053 10.4479 + vertex -42.0556 -40.8881 12.2634 + endloop + endfacet + facet normal -0.0207546 -0.956271 0.291743 + outer loop + vertex -42.0556 -40.8881 12.2634 + vertex -52.96 -41.2053 10.4479 + vertex -42.2614 -41.4377 10.4474 + endloop + endfacet + facet normal -0.021713 -0.999763 -0.00161827 + outer loop + vertex -52.96 -41.2053 10.4479 + vertex -53.1703 -41.1978 8.60029 + vertex -42.2614 -41.4377 10.4474 + endloop + endfacet + facet normal -0.0217375 -0.999763 -0.00147338 + outer loop + vertex -42.2614 -41.4377 10.4474 + vertex -53.1703 -41.1978 8.60029 + vertex -42.467 -41.4305 8.60177 + endloop + endfacet + facet normal -0.0392963 -0.999218 0.00438532 + outer loop + vertex -85.8677 -40.0911 10.4474 + vertex -86.0821 -40.0908 8.60043 + vertex -74.9363 -40.521 10.448 + endloop + endfacet + facet normal -0.0389953 -0.999236 0.00256579 + outer loop + vertex -74.9363 -40.521 10.448 + vertex -86.0821 -40.0908 8.60043 + vertex -75.1507 -40.5174 8.60081 + endloop + endfacet + facet normal -0.0371167 -0.956627 0.28894 + outer loop + vertex -85.6609 -39.5504 12.2643 + vertex -85.8677 -40.0911 10.4474 + vertex -74.7233 -39.9749 12.2636 + endloop + endfacet + facet normal -0.037602 -0.955722 0.29186 + outer loop + vertex -74.7233 -39.9749 12.2636 + vertex -85.8677 -40.0911 10.4474 + vertex -74.9363 -40.521 10.448 + endloop + endfacet + facet normal -0.0322101 -0.956079 0.291335 + outer loop + vertex -74.7233 -39.9749 12.2636 + vertex -74.9363 -40.521 10.448 + vertex -63.6783 -40.3469 12.2642 + endloop + endfacet + facet normal -0.0319455 -0.956571 0.289743 + outer loop + vertex -63.6783 -40.3469 12.2642 + vertex -74.9363 -40.521 10.448 + vertex -63.8928 -40.89 10.4476 + endloop + endfacet + facet normal -0.033389 -0.999441 0.00191466 + outer loop + vertex -74.9363 -40.521 10.448 + vertex -75.1507 -40.5174 8.60081 + vertex -63.8928 -40.89 10.4476 + endloop + endfacet + facet normal -0.0329174 -0.999458 -0.000963512 + outer loop + vertex -63.8928 -40.89 10.4476 + vertex -75.1507 -40.5174 8.60081 + vertex -64.1053 -40.8812 8.60158 + endloop + endfacet + facet normal -0.051677 -0.998654 -0.00447102 + outer loop + vertex -106.985 -39.0766 10.4471 + vertex -107.182 -39.0581 8.60247 + vertex -96.5346 -39.6173 10.4474 + endloop + endfacet + facet normal -0.051896 -0.998647 -0.003205 + outer loop + vertex -96.5346 -39.6173 10.4474 + vertex -107.182 -39.0581 8.60247 + vertex -96.7365 -39.6009 8.60132 + endloop + endfacet + facet normal -0.0494699 -0.955566 0.290597 + outer loop + vertex -106.783 -38.5345 12.264 + vertex -106.985 -39.0766 10.4471 + vertex -96.3319 -39.075 12.2658 + endloop + endfacet + facet normal -0.0494582 -0.955587 0.290529 + outer loop + vertex -96.3319 -39.075 12.2658 + vertex -106.985 -39.0766 10.4471 + vertex -96.5346 -39.6173 10.4474 + endloop + endfacet + facet normal -0.0425509 -0.956106 0.289914 + outer loop + vertex -96.3319 -39.075 12.2658 + vertex -96.5346 -39.6173 10.4474 + vertex -85.6609 -39.5504 12.2643 + endloop + endfacet + facet normal -0.0424706 -0.956254 0.289439 + outer loop + vertex -85.6609 -39.5504 12.2643 + vertex -96.5346 -39.6173 10.4474 + vertex -85.8677 -40.0911 10.4474 + endloop + endfacet + facet normal -0.0443716 -0.999007 -0.00403093 + outer loop + vertex -96.5346 -39.6173 10.4474 + vertex -96.7365 -39.6009 8.60132 + vertex -85.8677 -40.0911 10.4474 + endloop + endfacet + facet normal -0.0459284 -0.998931 0.00515509 + outer loop + vertex -85.8677 -40.0911 10.4474 + vertex -96.7365 -39.6009 8.60132 + vertex -86.0821 -40.0908 8.60043 + endloop + endfacet + facet normal -0.0645201 -0.997916 -0.000316988 + outer loop + vertex -128.121 -37.7847 10.4468 + vertex -128.325 -37.7709 8.60027 + vertex -117.446 -38.4749 10.4471 + endloop + endfacet + facet normal -0.0641726 -0.997936 -0.00237177 + outer loop + vertex -117.446 -38.4749 10.4471 + vertex -128.325 -37.7709 8.60027 + vertex -117.646 -38.4576 8.60042 + endloop + endfacet + facet normal -0.0616844 -0.954627 0.291344 + outer loop + vertex -127.909 -37.244 12.2634 + vertex -128.121 -37.7847 10.4468 + vertex -117.238 -37.933 12.2649 + endloop + endfacet + facet normal -0.0617247 -0.954549 0.291592 + outer loop + vertex -117.238 -37.933 12.2649 + vertex -128.121 -37.7847 10.4468 + vertex -117.446 -38.4749 10.4471 + endloop + endfacet + facet normal -0.0549198 -0.955147 0.290995 + outer loop + vertex -117.238 -37.933 12.2649 + vertex -117.446 -38.4749 10.4471 + vertex -106.783 -38.5345 12.264 + endloop + endfacet + facet normal -0.0549327 -0.955123 0.291072 + outer loop + vertex -106.783 -38.5345 12.264 + vertex -117.446 -38.4749 10.4471 + vertex -106.985 -39.0766 10.4471 + endloop + endfacet + facet normal -0.0574189 -0.998345 -0.00310944 + outer loop + vertex -117.446 -38.4749 10.4471 + vertex -117.646 -38.4576 8.60042 + vertex -106.985 -39.0766 10.4471 + endloop + endfacet + facet normal -0.0572878 -0.99835 -0.00386746 + outer loop + vertex -106.985 -39.0766 10.4471 + vertex -117.646 -38.4576 8.60042 + vertex -107.182 -39.0581 8.60247 + endloop + endfacet + facet normal -0.0751911 -0.997154 -0.00556999 + outer loop + vertex -149.954 -36.1983 10.4474 + vertex -150.164 -36.1721 8.60162 + vertex -139.015 -37.0231 10.447 + endloop + endfacet + facet normal -0.0761442 -0.997097 0.000214465 + outer loop + vertex -139.015 -37.0231 10.447 + vertex -150.164 -36.1721 8.60162 + vertex -139.227 -37.0074 8.60006 + endloop + endfacet + facet normal -0.0717752 -0.954515 0.289396 + outer loop + vertex -149.74 -35.6628 12.2667 + vertex -149.954 -36.1983 10.4474 + vertex -138.799 -36.486 12.2651 + endloop + endfacet + facet normal -0.07194 -0.954179 0.290461 + outer loop + vertex -138.799 -36.486 12.2651 + vertex -149.954 -36.1983 10.4474 + vertex -139.015 -37.0231 10.447 + endloop + endfacet + facet normal -0.0664112 -0.95473 0.289967 + outer loop + vertex -138.799 -36.486 12.2651 + vertex -139.015 -37.0231 10.447 + vertex -127.909 -37.244 12.2634 + endloop + endfacet + facet normal -0.0666975 -0.954155 0.291788 + outer loop + vertex -127.909 -37.244 12.2634 + vertex -139.015 -37.0231 10.447 + vertex -128.121 -37.7847 10.4468 + endloop + endfacet + facet normal -0.069739 -0.997565 -0.00052407 + outer loop + vertex -139.015 -37.0231 10.447 + vertex -139.227 -37.0074 8.60006 + vertex -128.121 -37.7847 10.4468 + endloop + endfacet + facet normal -0.0698718 -0.997556 0.000278259 + outer loop + vertex -128.121 -37.7847 10.4468 + vertex -139.227 -37.0074 8.60006 + vertex -128.325 -37.7709 8.60027 + endloop + endfacet + facet normal -0.0876845 -0.996145 -0.00247356 + outer loop + vertex -171.39 -34.3797 10.4474 + vertex -171.593 -34.3573 8.60223 + vertex -160.752 -35.3162 10.4473 + endloop + endfacet + facet normal -0.088182 -0.996104 0.000470879 + outer loop + vertex -160.752 -35.3162 10.4473 + vertex -171.593 -34.3573 8.60223 + vertex -160.962 -35.2984 8.60006 + endloop + endfacet + facet normal -0.0835423 -0.953545 0.289435 + outer loop + vertex -171.178 -33.8469 12.2638 + vertex -171.39 -34.3797 10.4474 + vertex -160.541 -34.7787 12.2644 + endloop + endfacet + facet normal -0.0838737 -0.952868 0.291562 + outer loop + vertex -160.541 -34.7787 12.2644 + vertex -171.39 -34.3797 10.4474 + vertex -160.752 -35.3162 10.4473 + endloop + endfacet + facet normal -0.0781074 -0.953504 0.291083 + outer loop + vertex -160.541 -34.7787 12.2644 + vertex -160.752 -35.3162 10.4473 + vertex -149.74 -35.6628 12.2667 + endloop + endfacet + facet normal -0.0779288 -0.953869 0.289932 + outer loop + vertex -149.74 -35.6628 12.2667 + vertex -160.752 -35.3162 10.4473 + vertex -149.954 -36.1983 10.4474 + endloop + endfacet + facet normal -0.0814229 -0.99668 -0.000304852 + outer loop + vertex -160.752 -35.3162 10.4473 + vertex -160.962 -35.2984 8.60006 + vertex -149.954 -36.1983 10.4474 + endloop + endfacet + facet normal -0.0806489 -0.99673 -0.004942 + outer loop + vertex -149.954 -36.1983 10.4474 + vertex -160.962 -35.2984 8.60006 + vertex -150.164 -36.1721 8.60162 + endloop + endfacet + facet normal -0.0985955 -0.99512 -0.00394392 + outer loop + vertex -192.706 -32.3306 10.448 + vertex -192.913 -32.3028 8.60036 + vertex -182.003 -33.3911 10.4472 + endloop + endfacet + facet normal -0.0994098 -0.995046 0.000909829 + outer loop + vertex -182.003 -33.3911 10.4472 + vertex -192.913 -32.3028 8.60036 + vertex -182.206 -33.3724 8.60018 + endloop + endfacet + facet normal -0.0952198 -0.951049 0.294006 + outer loop + vertex -192.489 -31.7909 12.2642 + vertex -192.706 -32.3306 10.448 + vertex -181.784 -32.862 12.2666 + endloop + endfacet + facet normal -0.0943833 -0.952828 0.288463 + outer loop + vertex -181.784 -32.862 12.2666 + vertex -192.706 -32.3306 10.448 + vertex -182.003 -33.3911 10.4472 + endloop + endfacet + facet normal -0.0884841 -0.953545 0.287962 + outer loop + vertex -181.784 -32.862 12.2666 + vertex -182.003 -33.3911 10.4472 + vertex -171.178 -33.8469 12.2638 + endloop + endfacet + facet normal -0.0887785 -0.95294 0.289867 + outer loop + vertex -171.178 -33.8469 12.2638 + vertex -182.003 -33.3911 10.4472 + vertex -171.39 -34.3797 10.4474 + endloop + endfacet + facet normal -0.0927559 -0.995689 0.000169646 + outer loop + vertex -182.003 -33.3911 10.4472 + vertex -182.206 -33.3724 8.60018 + vertex -171.39 -34.3797 10.4474 + endloop + endfacet + facet normal -0.0923968 -0.99572 -0.00195065 + outer loop + vertex -171.39 -34.3797 10.4474 + vertex -182.206 -33.3724 8.60018 + vertex -171.593 -34.3573 8.60223 + endloop + endfacet + facet normal -0.109339 -0.994001 -0.00269618 + outer loop + vertex -214.113 -30.0294 10.447 + vertex -214.316 -30.002 8.6009 + vertex -203.462 -31.201 10.4476 + endloop + endfacet + facet normal -0.10951 -0.993984 -0.00168167 + outer loop + vertex -203.462 -31.201 10.4476 + vertex -214.316 -30.002 8.6009 + vertex -203.669 -31.175 8.6004 + endloop + endfacet + facet normal -0.103925 -0.951359 0.290026 + outer loop + vertex -213.903 -29.4982 12.2644 + vertex -214.113 -30.0294 10.447 + vertex -203.246 -30.6627 12.2634 + endloop + endfacet + facet normal -0.104523 -0.950054 0.29406 + outer loop + vertex -203.246 -30.6627 12.2634 + vertex -214.113 -30.0294 10.447 + vertex -203.462 -31.201 10.4476 + endloop + endfacet + facet normal -0.0997287 -0.950688 0.293678 + outer loop + vertex -203.246 -30.6627 12.2634 + vertex -203.462 -31.201 10.4476 + vertex -192.489 -31.7909 12.2642 + endloop + endfacet + facet normal -0.099833 -0.950459 0.294382 + outer loop + vertex -192.489 -31.7909 12.2642 + vertex -203.462 -31.201 10.4476 + vertex -192.706 -32.3306 10.448 + endloop + endfacet + facet normal -0.104452 -0.994527 -0.00225765 + outer loop + vertex -203.462 -31.201 10.4476 + vertex -203.669 -31.175 8.6004 + vertex -192.706 -32.3306 10.448 + endloop + endfacet + facet normal -0.104278 -0.994543 -0.00329853 + outer loop + vertex -192.706 -32.3306 10.448 + vertex -203.669 -31.175 8.6004 + vertex -192.913 -32.3028 8.60036 + endloop + endfacet + facet normal -0.120045 -0.992754 0.00542431 + outer loop + vertex -234.925 -27.5727 10.4481 + vertex -235.119 -27.5593 8.60034 + vertex -224.569 -28.8249 10.4475 + endloop + endfacet + facet normal -0.119154 -0.992876 0.000254695 + outer loop + vertex -224.569 -28.8249 10.4475 + vertex -235.119 -27.5593 8.60034 + vertex -224.768 -28.8015 8.60043 + endloop + endfacet + facet normal -0.114272 -0.951853 0.284461 + outer loop + vertex -234.713 -27.0547 12.2667 + vertex -234.925 -27.5727 10.4481 + vertex -224.363 -28.2976 12.2654 + endloop + endfacet + facet normal -0.114919 -0.950478 0.288764 + outer loop + vertex -224.363 -28.2976 12.2654 + vertex -234.925 -27.5727 10.4481 + vertex -224.569 -28.8249 10.4475 + endloop + endfacet + facet normal -0.109167 -0.951283 0.288345 + outer loop + vertex -224.363 -28.2976 12.2654 + vertex -224.569 -28.8249 10.4475 + vertex -213.903 -29.4982 12.2644 + endloop + endfacet + facet normal -0.109483 -0.950607 0.290448 + outer loop + vertex -213.903 -29.4982 12.2644 + vertex -224.569 -28.8249 10.4475 + vertex -214.113 -30.0294 10.447 + endloop + endfacet + facet normal -0.11443 -0.993431 -0.00026222 + outer loop + vertex -224.569 -28.8249 10.4475 + vertex -224.768 -28.8015 8.60043 + vertex -214.113 -30.0294 10.447 + endloop + endfacet + facet normal -0.114105 -0.993466 -0.00216266 + outer loop + vertex -214.113 -30.0294 10.447 + vertex -224.768 -28.8015 8.60043 + vertex -214.316 -30.002 8.6009 + endloop + endfacet + facet normal -0.130882 -0.991392 0.00351703 + outer loop + vertex -256.136 -24.8431 10.4473 + vertex -256.338 -24.823 8.60016 + vertex -245.393 -26.2615 10.4474 + endloop + endfacet + facet normal -0.129945 -0.991519 -0.00213634 + outer loop + vertex -245.393 -26.2615 10.4474 + vertex -256.338 -24.823 8.60016 + vertex -245.592 -26.2314 8.60104 + endloop + endfacet + facet normal -0.12484 -0.949162 0.288975 + outer loop + vertex -255.918 -24.3189 12.2634 + vertex -256.136 -24.8431 10.4473 + vertex -245.18 -25.731 12.2644 + endloop + endfacet + facet normal -0.125199 -0.948328 0.291545 + outer loop + vertex -245.18 -25.731 12.2644 + vertex -256.136 -24.8431 10.4473 + vertex -245.393 -26.2615 10.4474 + endloop + endfacet + facet normal -0.120088 -0.949104 0.291171 + outer loop + vertex -245.18 -25.731 12.2644 + vertex -245.393 -26.2615 10.4474 + vertex -234.713 -27.0547 12.2667 + endloop + endfacet + facet normal -0.119159 -0.951143 0.284829 + outer loop + vertex -234.713 -27.0547 12.2667 + vertex -245.393 -26.2615 10.4474 + vertex -234.925 -27.5727 10.4481 + endloop + endfacet + facet normal -0.124289 -0.992242 -0.00275715 + outer loop + vertex -245.393 -26.2615 10.4474 + vertex -245.592 -26.2314 8.60104 + vertex -234.925 -27.5727 10.4481 + endloop + endfacet + facet normal -0.125785 -0.992039 0.00603375 + outer loop + vertex -234.925 -27.5727 10.4481 + vertex -245.592 -26.2314 8.60104 + vertex -235.119 -27.5593 8.60034 + endloop + endfacet + facet normal -0.140144 -0.990121 -0.00454172 + outer loop + vertex -278.121 -21.794 10.4474 + vertex -278.325 -21.7567 8.6025 + vertex -267.11 -23.3525 10.4474 + endloop + endfacet + facet normal -0.140211 -0.990113 -0.00412476 + outer loop + vertex -267.11 -23.3525 10.4474 + vertex -278.325 -21.7567 8.6025 + vertex -267.317 -23.3156 8.60201 + endloop + endfacet + facet normal -0.133617 -0.948992 0.285587 + outer loop + vertex -277.899 -21.2777 12.2669 + vertex -278.121 -21.794 10.4474 + vertex -266.887 -22.8287 12.2652 + endloop + endfacet + facet normal -0.134141 -0.947714 0.289558 + outer loop + vertex -266.887 -22.8287 12.2652 + vertex -278.121 -21.794 10.4474 + vertex -267.11 -23.3525 10.4474 + endloop + endfacet + facet normal -0.128824 -0.948575 0.289152 + outer loop + vertex -266.887 -22.8287 12.2652 + vertex -267.11 -23.3525 10.4474 + vertex -255.918 -24.3189 12.2634 + endloop + endfacet + facet normal -0.128841 -0.948536 0.289276 + outer loop + vertex -255.918 -24.3189 12.2634 + vertex -267.11 -23.3525 10.4474 + vertex -256.136 -24.8431 10.4473 + endloop + endfacet + facet normal -0.134595 -0.990889 -0.00476945 + outer loop + vertex -267.11 -23.3525 10.4474 + vertex -267.317 -23.3156 8.60201 + vertex -256.136 -24.8431 10.4473 + endloop + endfacet + facet normal -0.136031 -0.990696 0.00408791 + outer loop + vertex -256.136 -24.8431 10.4473 + vertex -267.317 -23.3156 8.60201 + vertex -256.338 -24.823 8.60016 + endloop + endfacet + facet normal -0.150109 -0.988669 0.000966918 + outer loop + vertex -299.556 -18.6063 10.4481 + vertex -299.756 -18.5777 8.60028 + vertex -288.967 -20.2139 10.448 + endloop + endfacet + facet normal -0.149129 -0.988806 -0.00487648 + outer loop + vertex -288.967 -20.2139 10.448 + vertex -299.756 -18.5777 8.60028 + vertex -289.166 -20.1747 8.60134 + endloop + endfacet + facet normal -0.142654 -0.946512 0.289421 + outer loop + vertex -299.339 -18.0835 12.2642 + vertex -299.556 -18.6063 10.4481 + vertex -288.745 -19.6806 12.2635 + endloop + endfacet + facet normal -0.143422 -0.944642 0.295097 + outer loop + vertex -288.745 -19.6806 12.2635 + vertex -299.556 -18.6063 10.4481 + vertex -288.967 -20.2139 10.448 + endloop + endfacet + facet normal -0.139311 -0.945349 0.294801 + outer loop + vertex -288.745 -19.6806 12.2635 + vertex -288.967 -20.2139 10.448 + vertex -277.899 -21.2777 12.2669 + endloop + endfacet + facet normal -0.13813 -0.948244 0.285925 + outer loop + vertex -277.899 -21.2777 12.2669 + vertex -288.967 -20.2139 10.448 + vertex -278.121 -21.794 10.4474 + endloop + endfacet + facet normal -0.144163 -0.989539 -0.00542766 + outer loop + vertex -288.967 -20.2139 10.448 + vertex -289.166 -20.1747 8.60134 + vertex -278.121 -21.794 10.4474 + endloop + endfacet + facet normal -0.144388 -0.989513 -0.00406095 + outer loop + vertex -278.121 -21.794 10.4474 + vertex -289.166 -20.1747 8.60134 + vertex -278.325 -21.7567 8.6025 + endloop + endfacet + facet normal -0.159109 -0.987256 0.00320079 + outer loop + vertex -320.235 -15.3189 10.4476 + vertex -320.435 -15.2927 8.6002 + vertex -309.941 -16.9779 10.448 + endloop + endfacet + facet normal -0.158754 -0.987318 0.00112888 + outer loop + vertex -309.941 -16.9779 10.448 + vertex -320.435 -15.2927 8.6002 + vertex -310.138 -16.9482 8.60088 + endloop + endfacet + facet normal -0.152136 -0.946648 0.2841 + outer loop + vertex -320.016 -14.8082 12.2666 + vertex -320.235 -15.3189 10.4476 + vertex -309.726 -16.4623 12.2652 + endloop + endfacet + facet normal -0.152454 -0.9459 0.286411 + outer loop + vertex -309.726 -16.4623 12.2652 + vertex -320.235 -15.3189 10.4476 + vertex -309.941 -16.9779 10.448 + endloop + endfacet + facet normal -0.147747 -0.946743 0.286092 + outer loop + vertex -309.726 -16.4623 12.2652 + vertex -309.941 -16.9779 10.448 + vertex -299.339 -18.0835 12.2642 + endloop + endfacet + facet normal -0.148257 -0.945533 0.289806 + outer loop + vertex -299.339 -18.0835 12.2642 + vertex -309.941 -16.9779 10.448 + vertex -299.556 -18.6063 10.4481 + endloop + endfacet + facet normal -0.154901 -0.98793 0.000707218 + outer loop + vertex -309.941 -16.9779 10.448 + vertex -310.138 -16.9482 8.60088 + vertex -299.556 -18.6063 10.4481 + endloop + endfacet + facet normal -0.155038 -0.987907 0.00151274 + outer loop + vertex -299.556 -18.6063 10.4481 + vertex -310.138 -16.9482 8.60088 + vertex -299.756 -18.5777 8.60028 + endloop + endfacet + facet normal -0.168583 -0.985684 -0.00254843 + outer loop + vertex -340.875 -11.8493 10.4469 + vertex -341.08 -11.8095 8.60008 + vertex -330.529 -13.6187 10.4479 + endloop + endfacet + facet normal -0.1681 -0.985755 -0.00537258 + outer loop + vertex -330.529 -13.6187 10.4479 + vertex -341.08 -11.8095 8.60008 + vertex -330.732 -13.5741 8.60065 + endloop + endfacet + facet normal -0.160529 -0.944309 0.287248 + outer loop + vertex -340.651 -11.3344 12.2648 + vertex -340.875 -11.8493 10.4469 + vertex -330.31 -13.0926 12.2637 + endloop + endfacet + facet normal -0.161235 -0.94256 0.292547 + outer loop + vertex -330.31 -13.0926 12.2637 + vertex -340.875 -11.8493 10.4469 + vertex -330.529 -13.6187 10.4479 + endloop + endfacet + facet normal -0.157287 -0.943307 0.292287 + outer loop + vertex -330.31 -13.0926 12.2637 + vertex -330.529 -13.6187 10.4479 + vertex -320.016 -14.8082 12.2666 + endloop + endfacet + facet normal -0.156213 -0.945899 0.284381 + outer loop + vertex -320.016 -14.8082 12.2666 + vertex -330.529 -13.6187 10.4479 + vertex -320.235 -15.3189 10.4476 + endloop + endfacet + facet normal -0.162944 -0.986617 -0.00595871 + outer loop + vertex -330.529 -13.6187 10.4479 + vertex -330.732 -13.5741 8.60065 + vertex -320.235 -15.3189 10.4476 + endloop + endfacet + facet normal -0.164618 -0.98635 0.00380971 + outer loop + vertex -320.235 -15.3189 10.4476 + vertex -330.732 -13.5741 8.60065 + vertex -320.435 -15.2927 8.6002 + endloop + endfacet + facet normal -0.176645 -0.984275 0.000301843 + outer loop + vertex -361.724 -8.14407 10.4472 + vertex -361.936 -8.10658 8.5997 + vertex -351.277 -10.019 10.4474 + endloop + endfacet + facet normal -0.176938 -0.98422 0.00204974 + outer loop + vertex -351.277 -10.019 10.4474 + vertex -361.936 -8.10658 8.5997 + vertex -351.484 -9.98547 8.60012 + endloop + endfacet + facet normal -0.169307 -0.943062 0.286303 + outer loop + vertex -361.492 -7.63392 12.2645 + vertex -361.724 -8.14407 10.4472 + vertex -351.05 -9.50891 12.2635 + endloop + endfacet + facet normal -0.169272 -0.94315 0.286033 + outer loop + vertex -351.05 -9.50891 12.2635 + vertex -361.724 -8.14407 10.4472 + vertex -351.277 -10.019 10.4474 + endloop + endfacet + facet normal -0.165725 -0.943854 0.285788 + outer loop + vertex -351.05 -9.50891 12.2635 + vertex -351.277 -10.019 10.4474 + vertex -340.651 -11.3344 12.2648 + endloop + endfacet + facet normal -0.165964 -0.943255 0.28762 + outer loop + vertex -340.651 -11.3344 12.2648 + vertex -351.277 -10.019 10.4474 + vertex -340.875 -11.8493 10.4469 + endloop + endfacet + facet normal -0.173301 -0.984867 0.00162895 + outer loop + vertex -351.277 -10.019 10.4474 + vertex -351.484 -9.98547 8.60012 + vertex -340.875 -11.8493 10.4469 + endloop + endfacet + facet normal -0.172675 -0.984977 -0.0020791 + outer loop + vertex -340.875 -11.8493 10.4469 + vertex -351.484 -9.98547 8.60012 + vertex -341.08 -11.8095 8.60008 + endloop + endfacet + facet normal -0.186623 -0.982427 0.00302052 + outer loop + vertex -382.786 -4.1944 10.4462 + vertex -382.998 -4.15975 8.59937 + vertex -372.216 -6.20229 10.4467 + endloop + endfacet + facet normal -0.18574 -0.982596 -0.00231821 + outer loop + vertex -372.216 -6.20229 10.4467 + vertex -382.998 -4.15975 8.59937 + vertex -372.431 -6.1573 8.59999 + endloop + endfacet + facet normal -0.17835 -0.942127 0.28388 + outer loop + vertex -382.547 -3.69199 12.2635 + vertex -382.786 -4.1944 10.4462 + vertex -371.982 -5.69219 12.263 + endloop + endfacet + facet normal -0.178771 -0.941009 0.287304 + outer loop + vertex -371.982 -5.69219 12.263 + vertex -382.786 -4.1944 10.4462 + vertex -372.216 -6.20229 10.4467 + endloop + endfacet + facet normal -0.174391 -0.941924 0.286997 + outer loop + vertex -371.982 -5.69219 12.263 + vertex -372.216 -6.20229 10.4467 + vertex -361.492 -7.63392 12.2645 + endloop + endfacet + facet normal -0.174348 -0.942035 0.286657 + outer loop + vertex -361.492 -7.63392 12.2645 + vertex -372.216 -6.20229 10.4467 + vertex -361.724 -8.14407 10.4472 + endloop + endfacet + facet normal -0.181974 -0.983299 -0.0027737 + outer loop + vertex -372.216 -6.20229 10.4467 + vertex -372.431 -6.1573 8.59999 + vertex -361.724 -8.14407 10.4472 + endloop + endfacet + facet normal -0.182605 -0.983186 0.00100796 + outer loop + vertex -361.724 -8.14407 10.4472 + vertex -372.431 -6.1573 8.59999 + vertex -361.936 -8.10658 8.5997 + endloop + endfacet + facet normal -0.196407 -0.980522 -0.00104733 + outer loop + vertex -404.263 0.0411153 10.4454 + vertex -404.45 0.080527 8.60116 + vertex -393.473 -2.1203 10.446 + endloop + endfacet + facet normal -0.196164 -0.980568 -0.0025478 + outer loop + vertex -393.473 -2.1203 10.446 + vertex -404.45 0.080527 8.60116 + vertex -393.679 -2.07431 8.59929 + endloop + endfacet + facet normal -0.186991 -0.940844 0.282572 + outer loop + vertex -404.027 0.540121 12.2634 + vertex -404.263 0.0411153 10.4454 + vertex -393.234 -1.60552 12.2613 + endloop + endfacet + facet normal -0.187939 -0.938153 0.290771 + outer loop + vertex -393.234 -1.60552 12.2613 + vertex -404.263 0.0411153 10.4454 + vertex -393.473 -2.1203 10.446 + endloop + endfacet + facet normal -0.183417 -0.939145 0.290457 + outer loop + vertex -393.234 -1.60552 12.2613 + vertex -393.473 -2.1203 10.446 + vertex -382.547 -3.69199 12.2635 + endloop + endfacet + facet normal -0.182671 -0.941205 0.284192 + outer loop + vertex -382.547 -3.69199 12.2635 + vertex -393.473 -2.1203 10.446 + vertex -382.786 -4.1944 10.4462 + endloop + endfacet + facet normal -0.190523 -0.981678 -0.00320447 + outer loop + vertex -393.473 -2.1203 10.446 + vertex -393.679 -2.07431 8.59929 + vertex -382.786 -4.1944 10.4462 + endloop + endfacet + facet normal -0.191636 -0.981459 0.00361502 + outer loop + vertex -382.786 -4.1944 10.4462 + vertex -393.679 -2.07431 8.59929 + vertex -382.998 -4.15975 8.59937 + endloop + endfacet + facet normal -0.204335 -0.978863 0.00856737 + outer loop + vertex -425.626 4.44451 10.453 + vertex -425.769 4.45823 8.60553 + vertex -415.042 2.2351 10.4474 + endloop + endfacet + facet normal -0.203351 -0.979103 0.00254571 + outer loop + vertex -415.042 2.2351 10.4474 + vertex -425.769 4.45823 8.60553 + vertex -415.208 2.26484 8.60111 + endloop + endfacet + facet normal -0.195484 -0.93739 0.288247 + outer loop + vertex -425.436 4.96364 12.2698 + vertex -425.626 4.44451 10.453 + vertex -414.824 2.7486 12.2635 + endloop + endfacet + facet normal -0.195513 -0.937307 0.288496 + outer loop + vertex -414.824 2.7486 12.2635 + vertex -425.626 4.44451 10.453 + vertex -415.042 2.2351 10.4474 + endloop + endfacet + facet normal -0.19188 -0.938121 0.28829 + outer loop + vertex -414.824 2.7486 12.2635 + vertex -415.042 2.2351 10.4474 + vertex -404.027 0.540121 12.2634 + endloop + endfacet + facet normal -0.19126 -0.939897 0.282868 + outer loop + vertex -404.027 0.540121 12.2634 + vertex -415.042 2.2351 10.4474 + vertex -404.263 0.0411153 10.4454 + endloop + endfacet + facet normal -0.199456 -0.979904 0.00218202 + outer loop + vertex -415.042 2.2351 10.4474 + vertex -415.208 2.26484 8.60111 + vertex -404.263 0.0411153 10.4454 + endloop + endfacet + facet normal -0.198978 -0.980004 -0.000775719 + outer loop + vertex -404.263 0.0411153 10.4454 + vertex -415.208 2.26484 8.60111 + vertex -404.45 0.080527 8.60116 + endloop + endfacet + facet normal -0.214022 -0.976829 0.000246962 + outer loop + vertex -446.007 8.84624 10.4487 + vertex -446.087 8.86327 8.60326 + vertex -435.916 6.63531 10.4581 + endloop + endfacet + facet normal -0.214664 -0.97668 0.00394631 + outer loop + vertex -435.916 6.63531 10.4581 + vertex -446.087 8.86327 8.60326 + vertex -436.022 6.65106 8.61037 + endloop + endfacet + facet normal -0.205112 -0.935395 0.288036 + outer loop + vertex -445.869 9.37619 12.2681 + vertex -446.007 8.84624 10.4487 + vertex -435.756 7.16175 12.2781 + endloop + endfacet + facet normal -0.205176 -0.935222 0.288554 + outer loop + vertex -435.756 7.16175 12.2781 + vertex -446.007 8.84624 10.4487 + vertex -435.916 6.63531 10.4581 + endloop + endfacet + facet normal -0.19925 -0.936545 0.288416 + outer loop + vertex -435.756 7.16175 12.2781 + vertex -435.916 6.63531 10.4581 + vertex -425.436 4.96364 12.2698 + endloop + endfacet + facet normal -0.199248 -0.93655 0.288399 + outer loop + vertex -425.436 4.96364 12.2698 + vertex -435.916 6.63531 10.4581 + vertex -425.626 4.44451 10.453 + endloop + endfacet + facet normal -0.208231 -0.978073 0.00356668 + outer loop + vertex -435.916 6.63531 10.4581 + vertex -436.022 6.65106 8.61037 + vertex -425.626 4.44451 10.453 + endloop + endfacet + facet normal -0.209136 -0.977846 0.00894702 + outer loop + vertex -425.626 4.44451 10.453 + vertex -436.022 6.65106 8.61037 + vertex -425.769 4.45823 8.60553 + endloop + endfacet + facet normal -0.223565 -0.974684 0.00298547 + outer loop + vertex -466.821 13.5817 10.3864 + vertex -466.866 13.5865 8.54373 + vertex -456.214 11.149 10.4154 + endloop + endfacet + facet normal -0.223226 -0.974766 0.000951694 + outer loop + vertex -456.214 11.149 10.4154 + vertex -466.866 13.5865 8.54373 + vertex -456.271 11.1603 8.57424 + endloop + endfacet + facet normal -0.214463 -0.935749 0.279963 + outer loop + vertex -466.625 14.0808 12.2038 + vertex -466.821 13.5817 10.3864 + vertex -456.072 11.67 12.2308 + endloop + endfacet + facet normal -0.215029 -0.934109 0.284961 + outer loop + vertex -456.072 11.67 12.2308 + vertex -466.821 13.5817 10.3864 + vertex -456.214 11.149 10.4154 + endloop + endfacet + facet normal -0.211255 -0.934984 0.284916 + outer loop + vertex -456.072 11.67 12.2308 + vertex -456.214 11.149 10.4154 + vertex -445.869 9.37619 12.2681 + endloop + endfacet + facet normal -0.211643 -0.933919 0.288102 + outer loop + vertex -445.869 9.37619 12.2681 + vertex -456.214 11.149 10.4154 + vertex -446.007 8.84624 10.4487 + endloop + endfacet + facet normal -0.220083 -0.975481 0.000849018 + outer loop + vertex -456.214 11.149 10.4154 + vertex -456.271 11.1603 8.57424 + vertex -446.007 8.84624 10.4487 + endloop + endfacet + facet normal -0.220026 -0.975494 0.000519105 + outer loop + vertex -446.007 8.84624 10.4487 + vertex -456.271 11.1603 8.57424 + vertex -446.087 8.86327 8.60326 + endloop + endfacet + facet normal -0.229504 -0.973126 0.0188209 + outer loop + vertex -488.052 18.5499 10.6513 + vertex -488.556 18.632 8.74816 + vertex -477.713 16.1075 10.437 + endloop + endfacet + facet normal -0.227371 -0.973799 0.00411847 + outer loop + vertex -477.713 16.1075 10.437 + vertex -488.556 18.632 8.74816 + vertex -477.822 16.1251 8.57712 + endloop + endfacet + facet normal -0.217584 -0.923905 0.314733 + outer loop + vertex -487.981 19.1326 12.4105 + vertex -488.052 18.5499 10.6513 + vertex -477.437 16.5964 12.255 + endloop + endfacet + facet normal -0.214874 -0.934455 0.283942 + outer loop + vertex -477.437 16.5964 12.255 + vertex -488.052 18.5499 10.6513 + vertex -477.713 16.1075 10.437 + endloop + endfacet + facet normal -0.216013 -0.934164 0.284036 + outer loop + vertex -477.437 16.5964 12.255 + vertex -477.713 16.1075 10.437 + vertex -466.625 14.0808 12.2038 + endloop + endfacet + facet normal -0.21561 -0.935472 0.280009 + outer loop + vertex -466.625 14.0808 12.2038 + vertex -477.713 16.1075 10.437 + vertex -466.821 13.5817 10.3864 + endloop + endfacet + facet normal -0.225861 -0.974151 0.00402659 + outer loop + vertex -477.713 16.1075 10.437 + vertex -477.822 16.1251 8.57712 + vertex -466.821 13.5817 10.3864 + endloop + endfacet + facet normal -0.225708 -0.97419 0.00303939 + outer loop + vertex -466.821 13.5817 10.3864 + vertex -477.822 16.1251 8.57712 + vertex -466.866 13.5865 8.54373 + endloop + endfacet + facet normal -0.221016 -0.903354 0.367565 + outer loop + vertex -498.433 21.7224 12.4911 + vertex -495.922 20.4996 10.9952 + vertex -487.981 19.1326 12.4105 + endloop + endfacet + facet normal -0.215241 -0.924427 0.314812 + outer loop + vertex -487.981 19.1326 12.4105 + vertex -495.922 20.4996 10.9952 + vertex -488.052 18.5499 10.6513 + endloop + endfacet + facet normal -0.236728 -0.968733 0.0742678 + outer loop + vertex -495.922 20.4996 10.9952 + vertex -497.415 20.7289 9.23036 + vertex -488.052 18.5499 10.6513 + endloop + endfacet + facet normal -0.229338 -0.973166 0.018775 + outer loop + vertex -488.052 18.5499 10.6513 + vertex -497.415 20.7289 9.23036 + vertex -488.556 18.632 8.74816 + endloop + endfacet + facet normal -0.293866 -0.955782 -0.0111215 + outer loop + vertex -509.252 23.7374 10.5604 + vertex -509.208 23.7462 8.64512 + vertex -508.169 23.4072 10.3078 + endloop + endfacet + facet normal -0.228463 -0.97198 -0.0553193 + outer loop + vertex -508.169 23.4072 10.3078 + vertex -509.208 23.7462 8.64512 + vertex -507.967 23.4672 8.41956 + endloop + endfacet + facet normal -0.310291 -0.903975 0.294192 + outer loop + vertex -509.186 24.33 12.4512 + vertex -509.252 23.7374 10.5604 + vertex -508.285 23.9025 12.0882 + endloop + endfacet + facet normal -0.229312 -0.941501 0.246967 + outer loop + vertex -508.285 23.9025 12.0882 + vertex -509.252 23.7374 10.5604 + vertex -508.169 23.4072 10.3078 + endloop + endfacet + facet normal -0.251707 -0.936508 0.244122 + outer loop + vertex -508.285 23.9025 12.0882 + vertex -508.169 23.4072 10.3078 + vertex -505.582 23.0852 11.7392 + endloop + endfacet + facet normal -0.226468 -0.954404 0.194488 + outer loop + vertex -505.582 23.0852 11.7392 + vertex -508.169 23.4072 10.3078 + vertex -503.574 22.2904 10.1776 + endloop + endfacet + facet normal -0.237312 -0.969807 -0.0561968 + outer loop + vertex -508.169 23.4072 10.3078 + vertex -507.967 23.4672 8.41956 + vertex -503.574 22.2904 10.1776 + endloop + endfacet + facet normal -0.227485 -0.970395 -0.0811454 + outer loop + vertex -503.574 22.2904 10.1776 + vertex -507.967 23.4672 8.41956 + vertex -504.588 22.7145 7.94895 + endloop + endfacet + facet normal 0.00804849 0.928908 -0.370224 + outer loop + vertex -508.933 24.5402 12.9841 + vertex -508.948 23.701 10.8783 + vertex -509.186 24.33 12.4512 + endloop + endfacet + facet normal 0.402786 0.869281 -0.286556 + outer loop + vertex -509.186 24.33 12.4512 + vertex -508.948 23.701 10.8783 + vertex -509.252 23.7374 10.5604 + endloop + endfacet + facet normal 0.137182 0.990378 -0.018238 + outer loop + vertex -508.948 23.701 10.8783 + vertex -509.03 23.6746 8.82407 + vertex -509.252 23.7374 10.5604 + endloop + endfacet + facet normal 0.361225 0.932394 0.012548 + outer loop + vertex -509.252 23.7374 10.5604 + vertex -509.03 23.6746 8.82407 + vertex -509.208 23.7462 8.64512 + endloop + endfacet + facet normal 0.167948 -0.755757 -0.63295 + outer loop + vertex 504.118 23.0943 6.78518 + vertex 504.371 24.4227 5.26613 + vertex 507.802 24.3468 6.26721 + endloop + endfacet + facet normal 0.183757 -0.706534 -0.683406 + outer loop + vertex 507.802 24.3468 6.26721 + vertex 504.371 24.4227 5.26613 + vertex 507.961 25.7682 4.84033 + endloop + endfacet + facet normal 0.20207 -0.918799 -0.339081 + outer loop + vertex 504.121 22.4343 8.57552 + vertex 504.118 23.0943 6.78518 + vertex 507.778 23.4462 8.01297 + endloop + endfacet + facet normal 0.231982 -0.865754 -0.443457 + outer loop + vertex 507.778 23.4462 8.01297 + vertex 504.118 23.0943 6.78518 + vertex 507.802 24.3468 6.26721 + endloop + endfacet + facet normal 0.188082 -0.771771 -0.60745 + outer loop + vertex 488.299 19.1917 6.90846 + vertex 488.528 20.4319 5.40367 + vertex 497.452 21.393 6.94559 + endloop + endfacet + facet normal 0.18799 -0.772633 -0.606381 + outer loop + vertex 497.452 21.393 6.94559 + vertex 488.528 20.4319 5.40367 + vertex 497.721 22.6547 5.42143 + endloop + endfacet + facet normal 0.223945 -0.921594 -0.317039 + outer loop + vertex 488.456 18.6395 8.62432 + vertex 488.299 19.1917 6.90846 + vertex 497.538 20.8272 8.68027 + endloop + endfacet + facet normal 0.223344 -0.923366 -0.312272 + outer loop + vertex 497.538 20.8272 8.68027 + vertex 488.299 19.1917 6.90846 + vertex 497.452 21.393 6.94559 + endloop + endfacet + facet normal 0.220597 -0.924002 -0.312343 + outer loop + vertex 497.538 20.8272 8.68027 + vertex 497.452 21.393 6.94559 + vertex 504.121 22.4343 8.57552 + endloop + endfacet + facet normal 0.22516 -0.914047 -0.337373 + outer loop + vertex 504.121 22.4343 8.57552 + vertex 497.452 21.393 6.94559 + vertex 504.118 23.0943 6.78518 + endloop + endfacet + facet normal 0.182649 -0.77296 -0.607595 + outer loop + vertex 497.452 21.393 6.94559 + vertex 497.721 22.6547 5.42143 + vertex 504.118 23.0943 6.78518 + endloop + endfacet + facet normal 0.185979 -0.754766 -0.629079 + outer loop + vertex 504.118 23.0943 6.78518 + vertex 497.721 22.6547 5.42143 + vertex 504.371 24.4227 5.26613 + endloop + endfacet + facet normal 0.180905 -0.77472 -0.605874 + outer loop + vertex 467.05 14.2068 6.83982 + vertex 467.093 15.4113 5.31249 + vertex 477.795 16.7078 6.8503 + endloop + endfacet + facet normal 0.181079 -0.771779 -0.609563 + outer loop + vertex 477.795 16.7078 6.8503 + vertex 467.093 15.4113 5.31249 + vertex 477.936 17.9344 5.33898 + endloop + endfacet + facet normal 0.215325 -0.92006 -0.327299 + outer loop + vertex 467.249 13.6353 8.57695 + vertex 467.05 14.2068 6.83982 + vertex 477.993 16.1494 8.57845 + endloop + endfacet + facet normal 0.214878 -0.921872 -0.322458 + outer loop + vertex 477.993 16.1494 8.57845 + vertex 467.05 14.2068 6.83982 + vertex 477.795 16.7078 6.8503 + endloop + endfacet + facet normal 0.22049 -0.920478 -0.322651 + outer loop + vertex 477.993 16.1494 8.57845 + vertex 477.795 16.7078 6.8503 + vertex 488.456 18.6395 8.62432 + endloop + endfacet + facet normal 0.219928 -0.922578 -0.316989 + outer loop + vertex 488.456 18.6395 8.62432 + vertex 477.795 16.7078 6.8503 + vertex 488.299 19.1917 6.90846 + endloop + endfacet + facet normal 0.185771 -0.771309 -0.608746 + outer loop + vertex 477.795 16.7078 6.8503 + vertex 477.936 17.9344 5.33898 + vertex 488.299 19.1917 6.90846 + endloop + endfacet + facet normal 0.185728 -0.771946 -0.607951 + outer loop + vertex 488.299 19.1917 6.90846 + vertex 477.936 17.9344 5.33898 + vertex 488.528 20.4319 5.40367 + endloop + endfacet + facet normal 0.172176 -0.774098 -0.609202 + outer loop + vertex 446.163 9.48856 6.86991 + vertex 446.249 10.7063 5.34688 + vertex 456.529 11.8047 6.85653 + endloop + endfacet + facet normal 0.172109 -0.774971 -0.60811 + outer loop + vertex 456.529 11.8047 6.85653 + vertex 446.249 10.7063 5.34688 + vertex 456.567 13.0123 5.32859 + endloop + endfacet + facet normal 0.204442 -0.926028 -0.317296 + outer loop + vertex 446.304 8.92437 8.60779 + vertex 446.163 9.48856 6.86991 + vertex 456.699 11.2238 8.59422 + endloop + endfacet + facet normal 0.205569 -0.921929 -0.328312 + outer loop + vertex 456.699 11.2238 8.59422 + vertex 446.163 9.48856 6.86991 + vertex 456.529 11.8047 6.85653 + endloop + endfacet + facet normal 0.209966 -0.920906 -0.328401 + outer loop + vertex 456.699 11.2238 8.59422 + vertex 456.529 11.8047 6.85653 + vertex 467.249 13.6353 8.57695 + endloop + endfacet + facet normal 0.209842 -0.921393 -0.327111 + outer loop + vertex 467.249 13.6353 8.57695 + vertex 456.529 11.8047 6.85653 + vertex 467.05 14.2068 6.83982 + endloop + endfacet + facet normal 0.175859 -0.774498 -0.60764 + outer loop + vertex 456.529 11.8047 6.85653 + vertex 456.567 13.0123 5.32859 + vertex 467.05 14.2068 6.83982 + endloop + endfacet + facet normal 0.1758 -0.775377 -0.606535 + outer loop + vertex 467.05 14.2068 6.83982 + vertex 456.567 13.0123 5.32859 + vertex 467.093 15.4113 5.31249 + endloop + endfacet + facet normal 0.166855 -0.780554 -0.602407 + outer loop + vertex 425.247 4.98062 6.87247 + vertex 425.399 6.18982 5.34777 + vertex 435.751 7.22439 6.87458 + endloop + endfacet + facet normal 0.167052 -0.77828 -0.605288 + outer loop + vertex 435.751 7.22439 6.87458 + vertex 425.399 6.18982 5.34777 + vertex 435.887 8.43787 5.35161 + endloop + endfacet + facet normal 0.198118 -0.925917 -0.321601 + outer loop + vertex 425.379 4.40665 8.60616 + vertex 425.247 4.98062 6.87247 + vertex 435.878 6.65219 8.609 + endloop + endfacet + facet normal 0.197964 -0.926457 -0.320137 + outer loop + vertex 435.878 6.65219 8.609 + vertex 425.247 4.98062 6.87247 + vertex 435.751 7.22439 6.87458 + endloop + endfacet + facet normal 0.201693 -0.92565 -0.320144 + outer loop + vertex 435.878 6.65219 8.609 + vertex 435.751 7.22439 6.87458 + vertex 446.304 8.92437 8.60779 + endloop + endfacet + facet normal 0.201391 -0.926706 -0.317267 + outer loop + vertex 446.304 8.92437 8.60779 + vertex 435.751 7.22439 6.87458 + vertex 446.163 9.48856 6.86991 + endloop + endfacet + facet normal 0.168946 -0.778109 -0.604983 + outer loop + vertex 435.751 7.22439 6.87458 + vertex 435.887 8.43787 5.35161 + vertex 446.163 9.48856 6.86991 + endloop + endfacet + facet normal 0.169254 -0.774414 -0.60962 + outer loop + vertex 446.163 9.48856 6.86991 + vertex 435.887 8.43787 5.35161 + vertex 446.249 10.7063 5.34688 + endloop + endfacet + facet normal 0.159422 -0.778633 -0.60689 + outer loop + vertex 404.296 0.63499 6.86621 + vertex 404.436 1.84974 5.34457 + vertex 414.743 2.77307 6.86746 + endloop + endfacet + facet normal 0.159388 -0.778978 -0.606455 + outer loop + vertex 414.743 2.77307 6.86746 + vertex 404.436 1.84974 5.34457 + vertex 414.891 3.98843 5.34508 + endloop + endfacet + facet normal 0.19128 -0.927221 -0.321983 + outer loop + vertex 404.447 0.0631902 8.60219 + vertex 404.296 0.63499 6.86621 + vertex 414.891 2.21662 8.6058 + endloop + endfacet + facet normal 0.190397 -0.930158 -0.313935 + outer loop + vertex 414.891 2.21662 8.6058 + vertex 404.296 0.63499 6.86621 + vertex 414.743 2.77307 6.86746 + endloop + endfacet + facet normal 0.19408 -0.929375 -0.313998 + outer loop + vertex 414.891 2.21662 8.6058 + vertex 414.743 2.77307 6.86746 + vertex 425.379 4.40665 8.60616 + endloop + endfacet + facet normal 0.194895 -0.926607 -0.321584 + outer loop + vertex 425.379 4.40665 8.60616 + vertex 414.743 2.77307 6.86746 + vertex 425.247 4.98062 6.87247 + endloop + endfacet + facet normal 0.163926 -0.778608 -0.605721 + outer loop + vertex 414.743 2.77307 6.86746 + vertex 414.891 3.98843 5.34508 + vertex 425.247 4.98062 6.87247 + endloop + endfacet + facet normal 0.163725 -0.780816 -0.602927 + outer loop + vertex 425.247 4.98062 6.87247 + vertex 414.891 3.98843 5.34508 + vertex 425.399 6.18982 5.34777 + endloop + endfacet + facet normal 0.151586 -0.781581 -0.605105 + outer loop + vertex 383.163 -3.52217 6.86694 + vertex 383.33 -2.31004 5.34311 + vertex 393.811 -1.45599 6.86573 + endloop + endfacet + facet normal 0.151661 -0.780849 -0.606031 + outer loop + vertex 393.811 -1.45599 6.86573 + vertex 383.33 -2.31004 5.34311 + vertex 393.959 -0.245138 5.34247 + endloop + endfacet + facet normal 0.180413 -0.929386 -0.322014 + outer loop + vertex 383.304 -4.0957 8.60149 + vertex 383.163 -3.52217 6.86694 + vertex 393.959 -2.02742 8.6016 + endloop + endfacet + facet normal 0.180343 -0.929619 -0.321378 + outer loop + vertex 393.959 -2.02742 8.6016 + vertex 383.163 -3.52217 6.86694 + vertex 393.811 -1.45599 6.86573 + endloop + endfacet + facet normal 0.185142 -0.928645 -0.321466 + outer loop + vertex 393.959 -2.02742 8.6016 + vertex 393.811 -1.45599 6.86573 + vertex 404.447 0.0631902 8.60219 + endloop + endfacet + facet normal 0.185188 -0.928495 -0.321875 + outer loop + vertex 404.447 0.0631902 8.60219 + vertex 393.811 -1.45599 6.86573 + vertex 404.296 0.63499 6.86621 + endloop + endfacet + facet normal 0.155695 -0.780545 -0.605399 + outer loop + vertex 393.811 -1.45599 6.86573 + vertex 393.959 -0.245138 5.34247 + vertex 404.296 0.63499 6.86621 + endloop + endfacet + facet normal 0.155858 -0.77892 -0.607447 + outer loop + vertex 404.296 0.63499 6.86621 + vertex 393.959 -0.245138 5.34247 + vertex 404.436 1.84974 5.34457 + endloop + endfacet + facet normal 0.144777 -0.779502 -0.609439 + outer loop + vertex 361.514 -7.58531 6.86368 + vertex 361.694 -6.36325 5.34336 + vertex 372.342 -5.57603 6.86594 + endloop + endfacet + facet normal 0.144217 -0.784743 -0.60281 + outer loop + vertex 372.342 -5.57603 6.86594 + vertex 361.694 -6.36325 5.34336 + vertex 372.514 -4.37119 5.33861 + endloop + endfacet + facet normal 0.172752 -0.931293 -0.320701 + outer loop + vertex 361.661 -8.15606 8.60017 + vertex 361.514 -7.58531 6.86368 + vertex 372.486 -6.14853 8.6014 + endloop + endfacet + facet normal 0.172834 -0.931022 -0.321444 + outer loop + vertex 372.486 -6.14853 8.6014 + vertex 361.514 -7.58531 6.86368 + vertex 372.342 -5.57603 6.86594 + endloop + endfacet + facet normal 0.176528 -0.930305 -0.321513 + outer loop + vertex 372.486 -6.14853 8.6014 + vertex 372.342 -5.57603 6.86594 + vertex 383.304 -4.0957 8.60149 + endloop + endfacet + facet normal 0.176576 -0.930144 -0.321951 + outer loop + vertex 383.304 -4.0957 8.60149 + vertex 372.342 -5.57603 6.86594 + vertex 383.163 -3.52217 6.86694 + endloop + endfacet + facet normal 0.148947 -0.784447 -0.602044 + outer loop + vertex 372.342 -5.57603 6.86594 + vertex 372.514 -4.37119 5.33861 + vertex 383.163 -3.52217 6.86694 + endloop + endfacet + facet normal 0.149226 -0.781739 -0.605489 + outer loop + vertex 383.163 -3.52217 6.86694 + vertex 372.514 -4.37119 5.33861 + vertex 383.33 -2.31004 5.34311 + endloop + endfacet + facet normal 0.137708 -0.781331 -0.608735 + outer loop + vertex 340.59 -11.3082 6.86343 + vertex 340.743 -10.0953 5.3414 + vertex 350.909 -9.49096 6.86531 + endloop + endfacet + facet normal 0.13732 -0.784321 -0.604965 + outer loop + vertex 350.909 -9.49096 6.86531 + vertex 340.743 -10.0953 5.3414 + vertex 351.058 -8.28818 5.33973 + endloop + endfacet + facet normal 0.164584 -0.932031 -0.322848 + outer loop + vertex 340.72 -11.8868 8.60021 + vertex 340.59 -11.3082 6.86343 + vertex 351.052 -10.0629 8.60157 + endloop + endfacet + facet normal 0.164329 -0.932794 -0.320767 + outer loop + vertex 351.052 -10.0629 8.60157 + vertex 340.59 -11.3082 6.86343 + vertex 350.909 -9.49096 6.86531 + endloop + endfacet + facet normal 0.167498 -0.932207 -0.320834 + outer loop + vertex 351.052 -10.0629 8.60157 + vertex 350.909 -9.49096 6.86531 + vertex 361.661 -8.15606 8.60017 + endloop + endfacet + facet normal 0.167469 -0.932298 -0.320585 + outer loop + vertex 361.661 -8.15606 8.60017 + vertex 350.909 -9.49096 6.86531 + vertex 361.514 -7.58531 6.86368 + endloop + endfacet + facet normal 0.140796 -0.784101 -0.604452 + outer loop + vertex 350.909 -9.49096 6.86531 + vertex 351.058 -8.28818 5.33973 + vertex 361.514 -7.58531 6.86368 + endloop + endfacet + facet normal 0.14131 -0.779696 -0.610005 + outer loop + vertex 361.514 -7.58531 6.86368 + vertex 351.058 -8.28818 5.33973 + vertex 361.694 -6.36325 5.34336 + endloop + endfacet + facet normal 0.129459 -0.785094 -0.605696 + outer loop + vertex 320.23 -14.7189 6.86638 + vertex 320.418 -13.5113 5.3414 + vertex 330.444 -13.0333 6.8646 + endloop + endfacet + facet normal 0.129533 -0.784586 -0.606338 + outer loop + vertex 330.444 -13.0333 6.8646 + vertex 320.418 -13.5113 5.3414 + vertex 330.606 -11.828 5.33962 + endloop + endfacet + facet normal 0.153953 -0.933627 -0.32348 + outer loop + vertex 320.34 -15.3017 8.60089 + vertex 320.23 -14.7189 6.86638 + vertex 330.56 -13.6164 8.60076 + endloop + endfacet + facet normal 0.153999 -0.933495 -0.323837 + outer loop + vertex 330.56 -13.6164 8.60076 + vertex 320.23 -14.7189 6.86638 + vertex 330.444 -13.0333 6.8646 + endloop + endfacet + facet normal 0.158763 -0.932681 -0.323883 + outer loop + vertex 330.56 -13.6164 8.60076 + vertex 330.444 -13.0333 6.8646 + vertex 340.72 -11.8868 8.60021 + endloop + endfacet + facet normal 0.158619 -0.933096 -0.322756 + outer loop + vertex 340.72 -11.8868 8.60021 + vertex 330.444 -13.0333 6.8646 + vertex 340.59 -11.3082 6.86343 + endloop + endfacet + facet normal 0.133301 -0.784387 -0.605779 + outer loop + vertex 330.444 -13.0333 6.8646 + vertex 330.606 -11.828 5.33962 + vertex 340.59 -11.3082 6.86343 + endloop + endfacet + facet normal 0.133695 -0.781566 -0.609327 + outer loop + vertex 340.59 -11.3082 6.86343 + vertex 330.606 -11.828 5.33962 + vertex 340.743 -10.0953 5.3414 + endloop + endfacet + facet normal 0.123007 -0.78419 -0.608207 + outer loop + vertex 299.116 -18.0731 6.86344 + vertex 299.316 -16.8603 5.34013 + vertex 309.788 -16.4006 6.86538 + endloop + endfacet + facet normal 0.12253 -0.78758 -0.603908 + outer loop + vertex 309.788 -16.4006 6.86538 + vertex 299.316 -16.8603 5.34013 + vertex 309.988 -15.1982 5.33784 + endloop + endfacet + facet normal 0.145705 -0.936762 -0.318192 + outer loop + vertex 299.246 -18.6433 8.60152 + vertex 299.116 -18.0731 6.86344 + vertex 309.906 -16.9847 8.59995 + endloop + endfacet + facet normal 0.146502 -0.934436 -0.324603 + outer loop + vertex 309.906 -16.9847 8.59995 + vertex 299.116 -18.0731 6.86344 + vertex 309.788 -16.4006 6.86538 + endloop + endfacet + facet normal 0.150637 -0.93376 -0.324655 + outer loop + vertex 309.906 -16.9847 8.59995 + vertex 309.788 -16.4006 6.86538 + vertex 320.34 -15.3017 8.60089 + endloop + endfacet + facet normal 0.150485 -0.934202 -0.323452 + outer loop + vertex 320.34 -15.3017 8.60089 + vertex 309.788 -16.4006 6.86538 + vertex 320.23 -14.7189 6.86638 + endloop + endfacet + facet normal 0.126873 -0.787422 -0.603216 + outer loop + vertex 309.788 -16.4006 6.86538 + vertex 309.988 -15.1982 5.33784 + vertex 320.23 -14.7189 6.86638 + endloop + endfacet + facet normal 0.127192 -0.78519 -0.606052 + outer loop + vertex 320.23 -14.7189 6.86638 + vertex 309.988 -15.1982 5.33784 + vertex 320.418 -13.5113 5.3414 + endloop + endfacet + facet normal 0.11529 -0.784596 -0.609194 + outer loop + vertex 277.596 -21.2752 6.86404 + vertex 277.78 -20.0667 5.34246 + vertex 288.34 -19.6975 6.86543 + endloop + endfacet + facet normal 0.114981 -0.786688 -0.606549 + outer loop + vertex 288.34 -19.6975 6.86543 + vertex 277.78 -20.0667 5.34246 + vertex 288.526 -18.4945 5.34054 + endloop + endfacet + facet normal 0.136875 -0.937249 -0.32067 + outer loop + vertex 277.729 -21.8499 8.60069 + vertex 277.596 -21.2752 6.86404 + vertex 288.472 -20.2808 8.6 + endloop + endfacet + facet normal 0.137433 -0.935646 -0.325083 + outer loop + vertex 288.472 -20.2808 8.6 + vertex 277.596 -21.2752 6.86404 + vertex 288.34 -19.6975 6.86543 + endloop + endfacet + facet normal 0.142141 -0.934904 -0.325192 + outer loop + vertex 288.472 -20.2808 8.6 + vertex 288.34 -19.6975 6.86543 + vertex 299.246 -18.6433 8.60152 + endloop + endfacet + facet normal 0.141259 -0.937476 -0.318095 + outer loop + vertex 299.246 -18.6433 8.60152 + vertex 288.34 -19.6975 6.86543 + vertex 299.116 -18.0731 6.86344 + endloop + endfacet + facet normal 0.118458 -0.786571 -0.606031 + outer loop + vertex 288.34 -19.6975 6.86543 + vertex 288.526 -18.4945 5.34054 + vertex 299.116 -18.0731 6.86344 + endloop + endfacet + facet normal 0.118777 -0.784327 -0.608871 + outer loop + vertex 299.116 -18.0731 6.86344 + vertex 288.526 -18.4945 5.34054 + vertex 299.316 -16.8603 5.34013 + endloop + endfacet + facet normal 0.107551 -0.790784 -0.602572 + outer loop + vertex 256.483 -24.2012 6.86648 + vertex 256.655 -23.0132 5.33806 + vertex 266.978 -22.7731 6.86553 + endloop + endfacet + facet normal 0.108149 -0.787169 -0.60718 + outer loop + vertex 266.978 -22.7731 6.86553 + vertex 256.655 -23.0132 5.33806 + vertex 267.154 -21.5734 5.34137 + endloop + endfacet + facet normal 0.12709 -0.937756 -0.323205 + outer loop + vertex 256.601 -24.7834 8.60171 + vertex 256.483 -24.2012 6.86648 + vertex 267.102 -23.3597 8.60039 + endloop + endfacet + facet normal 0.127444 -0.936795 -0.325843 + outer loop + vertex 267.102 -23.3597 8.60039 + vertex 256.483 -24.2012 6.86648 + vertex 266.978 -22.7731 6.86553 + endloop + endfacet + facet normal 0.132985 -0.935983 -0.325962 + outer loop + vertex 267.102 -23.3597 8.60039 + vertex 266.978 -22.7731 6.86553 + vertex 277.729 -21.8499 8.60069 + endloop + endfacet + facet normal 0.132281 -0.93795 -0.320549 + outer loop + vertex 277.729 -21.8499 8.60069 + vertex 266.978 -22.7731 6.86553 + vertex 277.596 -21.2752 6.86404 + endloop + endfacet + facet normal 0.110956 -0.787081 -0.606788 + outer loop + vertex 266.978 -22.7731 6.86553 + vertex 267.154 -21.5734 5.34137 + vertex 277.596 -21.2752 6.86404 + endloop + endfacet + facet normal 0.111323 -0.78472 -0.609772 + outer loop + vertex 277.596 -21.2752 6.86404 + vertex 267.154 -21.5734 5.34137 + vertex 277.78 -20.0667 5.34246 + endloop + endfacet + facet normal 0.0991974 -0.791572 -0.602971 + outer loop + vertex 235.593 -26.8883 6.86619 + vertex 235.792 -25.6992 5.33792 + vertex 246.045 -25.5772 6.86453 + endloop + endfacet + facet normal 0.100145 -0.786233 -0.609761 + outer loop + vertex 246.045 -25.5772 6.86453 + vertex 235.792 -25.6992 5.33792 + vertex 246.24 -24.3717 5.34215 + endloop + endfacet + facet normal 0.117736 -0.939114 -0.322804 + outer loop + vertex 235.701 -27.4713 8.60165 + vertex 235.593 -26.8883 6.86619 + vertex 246.158 -26.1598 8.60011 + endloop + endfacet + facet normal 0.117746 -0.939088 -0.322876 + outer loop + vertex 246.158 -26.1598 8.60011 + vertex 235.593 -26.8883 6.86619 + vertex 246.045 -25.5772 6.86453 + endloop + endfacet + facet normal 0.123716 -0.93828 -0.322993 + outer loop + vertex 246.158 -26.1598 8.60011 + vertex 246.045 -25.5772 6.86453 + vertex 256.601 -24.7834 8.60171 + endloop + endfacet + facet normal 0.123735 -0.938228 -0.323136 + outer loop + vertex 256.601 -24.7834 8.60171 + vertex 246.045 -25.5772 6.86453 + vertex 256.483 -24.2012 6.86648 + endloop + endfacet + facet normal 0.103744 -0.786165 -0.609247 + outer loop + vertex 246.045 -25.5772 6.86453 + vertex 246.24 -24.3717 5.34215 + vertex 256.483 -24.2012 6.86648 + endloop + endfacet + facet normal 0.102923 -0.790922 -0.603199 + outer loop + vertex 256.483 -24.2012 6.86648 + vertex 246.24 -24.3717 5.34215 + vertex 256.655 -23.0132 5.33806 + endloop + endfacet + facet normal 0.0912006 -0.786589 -0.610704 + outer loop + vertex 214.466 -29.3974 6.86317 + vertex 214.685 -28.1904 5.34123 + vertex 225.065 -28.1691 6.8639 + endloop + endfacet + facet normal 0.0910431 -0.787449 -0.609618 + outer loop + vertex 225.065 -28.1691 6.8639 + vertex 214.685 -28.1904 5.34123 + vertex 225.28 -26.9648 5.34038 + endloop + endfacet + facet normal 0.108633 -0.94248 -0.316118 + outer loop + vertex 214.581 -29.9676 8.60256 + vertex 214.466 -29.3974 6.86317 + vertex 225.176 -28.746 8.60155 + endloop + endfacet + facet normal 0.109108 -0.941284 -0.319498 + outer loop + vertex 225.176 -28.746 8.60155 + vertex 214.466 -29.3974 6.86317 + vertex 225.065 -28.1691 6.8639 + endloop + endfacet + facet normal 0.113942 -0.940675 -0.319605 + outer loop + vertex 225.176 -28.746 8.60155 + vertex 225.065 -28.1691 6.8639 + vertex 235.701 -27.4713 8.60165 + endloop + endfacet + facet normal 0.11438 -0.93955 -0.322742 + outer loop + vertex 235.701 -27.4713 8.60165 + vertex 225.065 -28.1691 6.8639 + vertex 235.593 -26.8883 6.86619 + endloop + endfacet + facet normal 0.0959336 -0.78742 -0.608906 + outer loop + vertex 225.065 -28.1691 6.8639 + vertex 225.28 -26.9648 5.34038 + vertex 235.593 -26.8883 6.86619 + endloop + endfacet + facet normal 0.0951712 -0.791631 -0.603542 + outer loop + vertex 235.593 -26.8883 6.86619 + vertex 225.28 -26.9648 5.34038 + vertex 235.792 -25.6992 5.33792 + endloop + endfacet + facet normal 0.0834658 -0.791974 -0.604823 + outer loop + vertex 193.16 -31.6842 6.86474 + vertex 193.362 -30.4967 5.33783 + vertex 203.829 -30.5612 6.86672 + endloop + endfacet + facet normal 0.083533 -0.791626 -0.605269 + outer loop + vertex 203.829 -30.5612 6.86672 + vertex 193.362 -30.4967 5.33783 + vertex 204.035 -29.3718 5.33943 + endloop + endfacet + facet normal 0.0984229 -0.941492 -0.322345 + outer loop + vertex 193.273 -32.2667 8.60072 + vertex 193.16 -31.6842 6.86474 + vertex 203.939 -31.1515 8.60026 + endloop + endfacet + facet normal 0.0989984 -0.940046 -0.326363 + outer loop + vertex 203.939 -31.1515 8.60026 + vertex 193.16 -31.6842 6.86474 + vertex 203.829 -30.5612 6.86672 + endloop + endfacet + facet normal 0.104579 -0.939396 -0.326494 + outer loop + vertex 203.939 -31.1515 8.60026 + vertex 203.829 -30.5612 6.86672 + vertex 214.581 -29.9676 8.60256 + endloop + endfacet + facet normal 0.103088 -0.943152 -0.315971 + outer loop + vertex 214.581 -29.9676 8.60256 + vertex 203.829 -30.5612 6.86672 + vertex 214.466 -29.3974 6.86317 + endloop + endfacet + facet normal 0.0864118 -0.791619 -0.604874 + outer loop + vertex 203.829 -30.5612 6.86672 + vertex 204.035 -29.3718 5.33943 + vertex 214.466 -29.3974 6.86317 + endloop + endfacet + facet normal 0.087357 -0.786594 -0.61126 + outer loop + vertex 214.466 -29.3974 6.86317 + vertex 204.035 -29.3718 5.33943 + vertex 214.685 -28.1904 5.34123 + endloop + endfacet + facet normal 0.0742579 -0.789277 -0.60953 + outer loop + vertex 171.702 -33.7546 6.86387 + vertex 171.915 -32.5588 5.34141 + vertex 182.461 -32.7436 6.86537 + endloop + endfacet + facet normal 0.0738959 -0.791072 -0.607243 + outer loop + vertex 182.461 -32.7436 6.86537 + vertex 171.915 -32.5588 5.34141 + vertex 182.667 -31.5536 5.34016 + endloop + endfacet + facet normal 0.0880074 -0.9423 -0.322995 + outer loop + vertex 171.816 -34.3392 8.60031 + vertex 171.702 -33.7546 6.86387 + vertex 182.573 -33.3344 8.59991 + endloop + endfacet + facet normal 0.0884879 -0.941119 -0.326289 + outer loop + vertex 182.573 -33.3344 8.59991 + vertex 171.702 -33.7546 6.86387 + vertex 182.461 -32.7436 6.86537 + endloop + endfacet + facet normal 0.0938747 -0.940544 -0.326443 + outer loop + vertex 182.573 -33.3344 8.59991 + vertex 182.461 -32.7436 6.86537 + vertex 193.273 -32.2667 8.60072 + endloop + endfacet + facet normal 0.093261 -0.942066 -0.322201 + outer loop + vertex 193.273 -32.2667 8.60072 + vertex 182.461 -32.7436 6.86537 + vertex 193.16 -31.6842 6.86474 + endloop + endfacet + facet normal 0.0782952 -0.791093 -0.606664 + outer loop + vertex 182.461 -32.7436 6.86537 + vertex 182.667 -31.5536 5.34016 + vertex 193.16 -31.6842 6.86474 + endloop + endfacet + facet normal 0.07812 -0.791976 -0.605534 + outer loop + vertex 193.16 -31.6842 6.86474 + vertex 182.667 -31.5536 5.34016 + vertex 193.362 -30.4967 5.33783 + endloop + endfacet + facet normal 0.0647539 -0.792528 -0.606387 + outer loop + vertex 150.047 -35.5879 6.86543 + vertex 150.257 -34.4033 5.33977 + vertex 160.886 -34.7016 6.86459 + endloop + endfacet + facet normal 0.0652547 -0.790162 -0.609415 + outer loop + vertex 160.886 -34.7016 6.86459 + vertex 150.257 -34.4033 5.33977 + vertex 161.102 -33.509 5.34144 + endloop + endfacet + facet normal 0.0775737 -0.942274 -0.325732 + outer loop + vertex 150.16 -36.1783 8.60038 + vertex 150.047 -35.5879 6.86543 + vertex 161 -35.286 8.60081 + endloop + endfacet + facet normal 0.0771105 -0.943384 -0.322615 + outer loop + vertex 161 -35.286 8.60081 + vertex 150.047 -35.5879 6.86543 + vertex 160.886 -34.7016 6.86459 + endloop + endfacet + facet normal 0.0825235 -0.942864 -0.322797 + outer loop + vertex 161 -35.286 8.60081 + vertex 160.886 -34.7016 6.86459 + vertex 171.816 -34.3392 8.60031 + endloop + endfacet + facet normal 0.0825272 -0.942855 -0.322822 + outer loop + vertex 171.816 -34.3392 8.60031 + vertex 160.886 -34.7016 6.86459 + vertex 171.702 -33.7546 6.86387 + endloop + endfacet + facet normal 0.0691448 -0.79022 -0.608909 + outer loop + vertex 160.886 -34.7016 6.86459 + vertex 161.102 -33.509 5.34144 + vertex 171.702 -33.7546 6.86387 + endloop + endfacet + facet normal 0.0693498 -0.789225 -0.610176 + outer loop + vertex 171.702 -33.7546 6.86387 + vertex 161.102 -33.509 5.34144 + vertex 171.915 -32.5588 5.34141 + endloop + endfacet + facet normal 0.0551789 -0.792729 -0.607072 + outer loop + vertex 128.507 -37.1635 6.86534 + vertex 128.72 -35.9809 5.34051 + vertex 139.238 -36.4154 6.86394 + endloop + endfacet + facet normal 0.0558774 -0.789645 -0.611015 + outer loop + vertex 139.238 -36.4154 6.86394 + vertex 128.72 -35.9809 5.34051 + vertex 139.456 -35.2226 5.34229 + endloop + endfacet + facet normal 0.0657442 -0.943698 -0.324209 + outer loop + vertex 128.614 -37.7522 8.60074 + vertex 128.507 -37.1635 6.86534 + vertex 139.352 -37.0039 8.59998 + endloop + endfacet + facet normal 0.0657403 -0.943707 -0.324184 + outer loop + vertex 139.352 -37.0039 8.59998 + vertex 128.507 -37.1635 6.86534 + vertex 139.238 -36.4154 6.86394 + endloop + endfacet + facet normal 0.0720534 -0.943167 -0.324415 + outer loop + vertex 139.352 -37.0039 8.59998 + vertex 139.238 -36.4154 6.86394 + vertex 150.16 -36.1783 8.60038 + endloop + endfacet + facet normal 0.0722249 -0.942763 -0.325549 + outer loop + vertex 150.16 -36.1783 8.60038 + vertex 139.238 -36.4154 6.86394 + vertex 150.047 -35.5879 6.86543 + endloop + endfacet + facet normal 0.0605495 -0.789752 -0.61043 + outer loop + vertex 139.238 -36.4154 6.86394 + vertex 139.456 -35.2226 5.34229 + vertex 150.047 -35.5879 6.86543 + endloop + endfacet + facet normal 0.0599612 -0.792447 -0.606986 + outer loop + vertex 150.047 -35.5879 6.86543 + vertex 139.456 -35.2226 5.34229 + vertex 150.257 -34.4033 5.33977 + endloop + endfacet + facet normal 0.0454462 -0.791717 -0.609195 + outer loop + vertex 107.22 -38.4605 6.86539 + vertex 107.448 -37.2756 5.34247 + vertex 117.841 -37.8498 6.86407 + endloop + endfacet + facet normal 0.0456374 -0.790929 -0.610203 + outer loop + vertex 117.841 -37.8498 6.86407 + vertex 107.448 -37.2756 5.34247 + vertex 118.065 -36.6623 5.34149 + endloop + endfacet + facet normal 0.0550336 -0.943143 -0.327799 + outer loop + vertex 107.319 -39.0577 8.6001 + vertex 107.22 -38.4605 6.86539 + vertex 117.944 -38.4377 8.60038 + endloop + endfacet + facet normal 0.0542832 -0.944793 -0.323139 + outer loop + vertex 117.944 -38.4377 8.60038 + vertex 107.22 -38.4605 6.86539 + vertex 117.841 -37.8498 6.86407 + endloop + endfacet + facet normal 0.0606883 -0.944327 -0.323362 + outer loop + vertex 117.944 -38.4377 8.60038 + vertex 117.841 -37.8498 6.86407 + vertex 128.614 -37.7522 8.60074 + endloop + endfacet + facet normal 0.0607947 -0.944089 -0.324036 + outer loop + vertex 128.614 -37.7522 8.60074 + vertex 117.841 -37.8498 6.86407 + vertex 128.507 -37.1635 6.86534 + endloop + endfacet + facet normal 0.0509835 -0.791103 -0.609555 + outer loop + vertex 117.841 -37.8498 6.86407 + vertex 118.065 -36.6623 5.34149 + vertex 128.507 -37.1635 6.86534 + endloop + endfacet + facet normal 0.0506285 -0.792613 -0.607619 + outer loop + vertex 128.507 -37.1635 6.86534 + vertex 118.065 -36.6623 5.34149 + vertex 128.72 -35.9809 5.34051 + endloop + endfacet + facet normal 0.0359422 -0.792461 -0.608862 + outer loop + vertex 85.9216 -39.4993 6.86442 + vertex 86.1462 -38.3181 5.3403 + vertex 96.5937 -39.0147 6.86378 + endloop + endfacet + facet normal 0.0362316 -0.791321 -0.610326 + outer loop + vertex 96.5937 -39.0147 6.86378 + vertex 86.1462 -38.3181 5.3403 + vertex 96.8205 -37.8296 5.34066 + endloop + endfacet + facet normal 0.0436881 -0.944161 -0.326575 + outer loop + vertex 86.0267 -40.0948 8.60016 + vertex 85.9216 -39.4993 6.86442 + vertex 96.6974 -39.6012 8.60072 + endloop + endfacet + facet normal 0.0429209 -0.945797 -0.32191 + outer loop + vertex 96.6974 -39.6012 8.60072 + vertex 85.9216 -39.4993 6.86442 + vertex 96.5937 -39.0147 6.86378 + endloop + endfacet + facet normal 0.0483651 -0.945462 -0.322121 + outer loop + vertex 96.6974 -39.6012 8.60072 + vertex 96.5937 -39.0147 6.86378 + vertex 107.319 -39.0577 8.6001 + endloop + endfacet + facet normal 0.0492604 -0.94353 -0.327604 + outer loop + vertex 107.319 -39.0577 8.6001 + vertex 96.5937 -39.0147 6.86378 + vertex 107.22 -38.4605 6.86539 + endloop + endfacet + facet normal 0.0413756 -0.791533 -0.609725 + outer loop + vertex 96.5937 -39.0147 6.86378 + vertex 96.8205 -37.8296 5.34066 + vertex 107.22 -38.4605 6.86539 + endloop + endfacet + facet normal 0.041368 -0.791563 -0.609686 + outer loop + vertex 107.22 -38.4605 6.86539 + vertex 96.8205 -37.8296 5.34066 + vertex 107.448 -37.2756 5.34247 + endloop + endfacet + facet normal 0.0261669 -0.793467 -0.60805 + outer loop + vertex 64.2703 -40.284 6.86636 + vertex 64.5015 -39.1076 5.3413 + vertex 75.1497 -39.9239 6.86464 + endloop + endfacet + facet normal 0.0262441 -0.793172 -0.608432 + outer loop + vertex 75.1497 -39.9239 6.86464 + vertex 64.5015 -39.1076 5.3413 + vertex 75.3762 -38.7463 5.33932 + endloop + endfacet + facet normal 0.0312581 -0.945461 -0.324231 + outer loop + vertex 64.3728 -40.8756 8.60158 + vertex 64.2703 -40.284 6.86636 + vertex 75.2539 -40.5156 8.60059 + endloop + endfacet + facet normal 0.0312436 -0.945492 -0.324143 + outer loop + vertex 75.2539 -40.5156 8.60059 + vertex 64.2703 -40.284 6.86636 + vertex 75.1497 -39.9239 6.86464 + endloop + endfacet + facet normal 0.0369063 -0.945205 -0.324385 + outer loop + vertex 75.2539 -40.5156 8.60059 + vertex 75.1497 -39.9239 6.86464 + vertex 86.0267 -40.0948 8.60016 + endloop + endfacet + facet normal 0.037224 -0.94453 -0.32631 + outer loop + vertex 86.0267 -40.0948 8.60016 + vertex 75.1497 -39.9239 6.86464 + vertex 85.9216 -39.4993 6.86442 + endloop + endfacet + facet normal 0.0312616 -0.793417 -0.607875 + outer loop + vertex 75.1497 -39.9239 6.86464 + vertex 75.3762 -38.7463 5.33932 + vertex 85.9216 -39.4993 6.86442 + endloop + endfacet + facet normal 0.0315581 -0.792267 -0.609358 + outer loop + vertex 85.9216 -39.4993 6.86442 + vertex 75.3762 -38.7463 5.33932 + vertex 86.1462 -38.3181 5.3403 + endloop + endfacet + facet normal 0.0169139 -0.79548 -0.605743 + outer loop + vertex 42.4771 -40.8334 6.86616 + vertex 42.6821 -39.6658 5.3385 + vertex 53.3357 -40.6001 6.86301 + endloop + endfacet + facet normal 0.0180479 -0.791329 -0.611124 + outer loop + vertex 53.3357 -40.6001 6.86301 + vertex 42.6821 -39.6658 5.3385 + vertex 53.5642 -39.4183 5.33946 + endloop + endfacet + facet normal 0.0209324 -0.945727 -0.324288 + outer loop + vertex 42.589 -41.426 8.60158 + vertex 42.4771 -40.8334 6.86616 + vertex 53.4474 -41.1854 8.60083 + endloop + endfacet + facet normal 0.0202542 -0.947107 -0.320279 + outer loop + vertex 53.4474 -41.1854 8.60083 + vertex 42.4771 -40.8334 6.86616 + vertex 53.3357 -40.6001 6.86301 + endloop + endfacet + facet normal 0.0268673 -0.94683 -0.320611 + outer loop + vertex 53.4474 -41.1854 8.60083 + vertex 53.3357 -40.6001 6.86301 + vertex 64.3728 -40.8756 8.60158 + endloop + endfacet + facet normal 0.0274413 -0.945637 -0.324065 + outer loop + vertex 64.3728 -40.8756 8.60158 + vertex 53.3357 -40.6001 6.86301 + vertex 64.2703 -40.284 6.86636 + endloop + endfacet + facet normal 0.0230756 -0.791612 -0.610588 + outer loop + vertex 53.3357 -40.6001 6.86301 + vertex 53.5642 -39.4183 5.33946 + vertex 64.2703 -40.284 6.86636 + endloop + endfacet + facet normal 0.0226344 -0.793277 -0.608439 + outer loop + vertex 64.2703 -40.284 6.86636 + vertex 53.5642 -39.4183 5.33946 + vertex 64.5015 -39.1076 5.3413 + endloop + endfacet + facet normal 0.00886257 -0.791632 -0.610934 + outer loop + vertex 21.1125 -41.1458 6.86538 + vertex 21.3267 -39.9689 5.34343 + vertex 31.7415 -41.0255 6.86371 + endloop + endfacet + facet normal 0.00896263 -0.791286 -0.61138 + outer loop + vertex 31.7415 -41.0255 6.86371 + vertex 21.3267 -39.9689 5.34343 + vertex 31.9457 -39.8463 5.34041 + endloop + endfacet + facet normal 0.0109028 -0.945707 -0.324838 + outer loop + vertex 21.2162 -41.7407 8.60069 + vertex 21.1125 -41.1458 6.86538 + vertex 31.8549 -41.6178 8.59994 + endloop + endfacet + facet normal 0.0106566 -0.946187 -0.323444 + outer loop + vertex 31.8549 -41.6178 8.59994 + vertex 21.1125 -41.1458 6.86538 + vertex 31.7415 -41.0255 6.86371 + endloop + endfacet + facet normal 0.016951 -0.945979 -0.323785 + outer loop + vertex 31.8549 -41.6178 8.59994 + vertex 31.7415 -41.0255 6.86371 + vertex 42.589 -41.426 8.60158 + endloop + endfacet + facet normal 0.017003 -0.945875 -0.324085 + outer loop + vertex 42.589 -41.426 8.60158 + vertex 31.7415 -41.0255 6.86371 + vertex 42.4771 -40.8334 6.86616 + endloop + endfacet + facet normal 0.014307 -0.791583 -0.610894 + outer loop + vertex 31.7415 -41.0255 6.86371 + vertex 31.9457 -39.8463 5.34041 + vertex 42.4771 -40.8334 6.86616 + endloop + endfacet + facet normal 0.0132632 -0.795288 -0.606086 + outer loop + vertex 42.4771 -40.8334 6.86616 + vertex 31.9457 -39.8463 5.34041 + vertex 42.6821 -39.6658 5.3385 + endloop + endfacet + facet normal 0.00146531 -0.792008 -0.610508 + outer loop + vertex -0.210019 -41.2435 6.86449 + vertex 0.0367514 -40.0689 5.34125 + vertex 10.4775 -41.2232 6.86379 + endloop + endfacet + facet normal 0.00141416 -0.792179 -0.610287 + outer loop + vertex 10.4775 -41.2232 6.86379 + vertex 0.0367514 -40.0689 5.34125 + vertex 10.7069 -40.0487 5.33977 + endloop + endfacet + facet normal 0.00127128 -0.946176 -0.323651 + outer loop + vertex -0.113945 -41.8373 8.60078 + vertex -0.210019 -41.2435 6.86449 + vertex 10.5756 -41.8228 8.60021 + endloop + endfacet + facet normal 0.00177493 -0.94521 -0.326458 + outer loop + vertex 10.5756 -41.8228 8.60021 + vertex -0.210019 -41.2435 6.86449 + vertex 10.4775 -41.2232 6.86379 + endloop + endfacet + facet normal 0.00730403 -0.94509 -0.326729 + outer loop + vertex 10.5756 -41.8228 8.60021 + vertex 10.4775 -41.2232 6.86379 + vertex 21.2162 -41.7407 8.60069 + endloop + endfacet + facet normal 0.00693088 -0.945813 -0.324637 + outer loop + vertex 21.2162 -41.7407 8.60069 + vertex 10.4775 -41.2232 6.86379 + vertex 21.1125 -41.1458 6.86538 + endloop + endfacet + facet normal 0.00585773 -0.79249 -0.609857 + outer loop + vertex 10.4775 -41.2232 6.86379 + vertex 10.7069 -40.0487 5.33977 + vertex 21.1125 -41.1458 6.86538 + endloop + endfacet + facet normal 0.00616052 -0.791464 -0.611185 + outer loop + vertex 21.1125 -41.1458 6.86538 + vertex 10.7069 -40.0487 5.33977 + vertex 21.3267 -39.9689 5.34343 + endloop + endfacet + facet normal -0.00575598 -0.793483 -0.608565 + outer loop + vertex -21.5186 -41.141 6.86542 + vertex -21.2921 -39.973 5.34041 + vertex -10.9059 -41.2173 6.86454 + endloop + endfacet + facet normal -0.00566607 -0.793194 -0.608942 + outer loop + vertex -10.9059 -41.2173 6.86454 + vertex -21.2921 -39.973 5.34041 + vertex -10.6663 -40.0481 5.33932 + endloop + endfacet + facet normal -0.00698948 -0.945453 -0.325683 + outer loop + vertex -21.4185 -41.7394 8.6004 + vertex -21.5186 -41.141 6.86542 + vertex -10.8081 -41.8177 8.60012 + endloop + endfacet + facet normal -0.00682304 -0.945142 -0.326589 + outer loop + vertex -10.8081 -41.8177 8.60012 + vertex -21.5186 -41.141 6.86542 + vertex -10.9059 -41.2173 6.86454 + endloop + endfacet + facet normal -0.00171151 -0.945073 -0.326854 + outer loop + vertex -10.8081 -41.8177 8.60012 + vertex -10.9059 -41.2173 6.86454 + vertex -0.113945 -41.8373 8.60078 + endloop + endfacet + facet normal -0.00232228 -0.946235 -0.323472 + outer loop + vertex -0.113945 -41.8373 8.60078 + vertex -10.9059 -41.2173 6.86454 + vertex -0.210019 -41.2435 6.86449 + endloop + endfacet + facet normal -0.00194892 -0.793488 -0.608583 + outer loop + vertex -10.9059 -41.2173 6.86454 + vertex -10.6663 -40.0481 5.33932 + vertex -0.210019 -41.2435 6.86449 + endloop + endfacet + facet normal -0.00143018 -0.791782 -0.610803 + outer loop + vertex -0.210019 -41.2435 6.86449 + vertex -10.6663 -40.0481 5.33932 + vertex 0.0367514 -40.0689 5.34125 + endloop + endfacet + facet normal -0.0135517 -0.790502 -0.612309 + outer loop + vertex -42.5679 -40.8422 6.86395 + vertex -42.3457 -39.6675 5.34252 + vertex -32.0388 -41.0225 6.86369 + endloop + endfacet + facet normal -0.0134342 -0.790138 -0.612781 + outer loop + vertex -32.0388 -41.0225 6.86369 + vertex -42.3457 -39.6675 5.34252 + vertex -31.8174 -39.8466 5.3426 + endloop + endfacet + facet normal -0.0162182 -0.947359 -0.319762 + outer loop + vertex -42.467 -41.4305 8.60177 + vertex -42.5679 -40.8422 6.86395 + vertex -31.9335 -41.6109 8.60193 + endloop + endfacet + facet normal -0.0162309 -0.947382 -0.319695 + outer loop + vertex -31.9335 -41.6109 8.60193 + vertex -42.5679 -40.8422 6.86395 + vertex -32.0388 -41.0225 6.86369 + endloop + endfacet + facet normal -0.0116248 -0.947358 -0.319966 + outer loop + vertex -31.9335 -41.6109 8.60193 + vertex -32.0388 -41.0225 6.86369 + vertex -21.4185 -41.7394 8.6004 + endloop + endfacet + facet normal -0.0105956 -0.945487 -0.325487 + outer loop + vertex -21.4185 -41.7394 8.6004 + vertex -32.0388 -41.0225 6.86369 + vertex -21.5186 -41.141 6.86542 + endloop + endfacet + facet normal -0.00880301 -0.790506 -0.612391 + outer loop + vertex -32.0388 -41.0225 6.86369 + vertex -31.8174 -39.8466 5.3426 + vertex -21.5186 -41.141 6.86542 + endloop + endfacet + facet normal -0.00965347 -0.793179 -0.608912 + outer loop + vertex -21.5186 -41.141 6.86542 + vertex -31.8174 -39.8466 5.3426 + vertex -21.2921 -39.973 5.34041 + endloop + endfacet + facet normal -0.0215943 -0.791711 -0.610514 + outer loop + vertex -64.2074 -40.291 6.86348 + vertex -63.9568 -39.1233 5.34038 + vertex -53.2689 -40.5915 6.86621 + endloop + endfacet + facet normal -0.0226885 -0.795075 -0.606086 + outer loop + vertex -53.2689 -40.5915 6.86621 + vertex -63.9568 -39.1233 5.34038 + vertex -53.0357 -39.4339 5.33896 + endloop + endfacet + facet normal -0.0274558 -0.947038 -0.319946 + outer loop + vertex -64.1053 -40.8812 8.60158 + vertex -64.2074 -40.291 6.86348 + vertex -53.1703 -41.1978 8.60029 + endloop + endfacet + facet normal -0.0258507 -0.944109 -0.328617 + outer loop + vertex -53.1703 -41.1978 8.60029 + vertex -64.2074 -40.291 6.86348 + vertex -53.2689 -40.5915 6.86621 + endloop + endfacet + facet normal -0.0204827 -0.944132 -0.32893 + outer loop + vertex -53.1703 -41.1978 8.60029 + vertex -53.2689 -40.5915 6.86621 + vertex -42.467 -41.4305 8.60177 + endloop + endfacet + facet normal -0.0222626 -0.947355 -0.31941 + outer loop + vertex -42.467 -41.4305 8.60177 + vertex -53.2689 -40.5915 6.86621 + vertex -42.5679 -40.8422 6.86395 + endloop + endfacet + facet normal -0.0187637 -0.79543 -0.605756 + outer loop + vertex -53.2689 -40.5915 6.86621 + vertex -53.0357 -39.4339 5.33896 + vertex -42.5679 -40.8422 6.86395 + endloop + endfacet + facet normal -0.0170649 -0.790211 -0.612597 + outer loop + vertex -42.5679 -40.8422 6.86395 + vertex -53.0357 -39.4339 5.33896 + vertex -42.3457 -39.6675 5.34252 + endloop + endfacet + facet normal -0.0313458 -0.792661 -0.608856 + outer loop + vertex -86.1866 -39.4821 6.86564 + vertex -85.9585 -38.3206 5.34171 + vertex -75.257 -39.9136 6.86473 + endloop + endfacet + facet normal -0.0312972 -0.792517 -0.609046 + outer loop + vertex -75.257 -39.9136 6.86473 + vertex -85.9585 -38.3206 5.34171 + vertex -75.0098 -38.752 5.34047 + endloop + endfacet + facet normal -0.0368148 -0.943656 -0.328875 + outer loop + vertex -86.0821 -40.0908 8.60043 + vertex -86.1866 -39.4821 6.86564 + vertex -75.1507 -40.5174 8.60081 + endloop + endfacet + facet normal -0.0373197 -0.944562 -0.326205 + outer loop + vertex -75.1507 -40.5174 8.60081 + vertex -86.1866 -39.4821 6.86564 + vertex -75.257 -39.9136 6.86473 + endloop + endfacet + facet normal -0.0310896 -0.944646 -0.326615 + outer loop + vertex -75.1507 -40.5174 8.60081 + vertex -75.257 -39.9136 6.86473 + vertex -64.1053 -40.8812 8.60158 + endloop + endfacet + facet normal -0.0323791 -0.946986 -0.319639 + outer loop + vertex -64.1053 -40.8812 8.60158 + vertex -75.257 -39.9136 6.86473 + vertex -64.2074 -40.291 6.86348 + endloop + endfacet + facet normal -0.0271506 -0.792939 -0.608696 + outer loop + vertex -75.257 -39.9136 6.86473 + vertex -75.0098 -38.752 5.34047 + vertex -64.2074 -40.291 6.86348 + endloop + endfacet + facet normal -0.0265866 -0.791218 -0.610956 + outer loop + vertex -64.2074 -40.291 6.86348 + vertex -75.0098 -38.752 5.34047 + vertex -63.9568 -39.1233 5.34038 + endloop + endfacet + facet normal -0.0403608 -0.793529 -0.607193 + outer loop + vertex -107.279 -38.4694 6.86406 + vertex -107.075 -37.312 5.33793 + vertex -96.8425 -39.0014 6.86553 + endloop + endfacet + facet normal -0.0399147 -0.792301 -0.608823 + outer loop + vertex -96.8425 -39.0014 6.86553 + vertex -107.075 -37.312 5.33793 + vertex -96.6361 -37.8406 5.34143 + endloop + endfacet + facet normal -0.0492384 -0.946844 -0.317903 + outer loop + vertex -107.182 -39.0581 8.60247 + vertex -107.279 -38.4694 6.86406 + vertex -96.7365 -39.6009 8.60132 + endloop + endfacet + facet normal -0.0481216 -0.945009 -0.323485 + outer loop + vertex -96.7365 -39.6009 8.60132 + vertex -107.279 -38.4694 6.86406 + vertex -96.8425 -39.0014 6.86553 + endloop + endfacet + facet normal -0.0434818 -0.945123 -0.323808 + outer loop + vertex -96.7365 -39.6009 8.60132 + vertex -96.8425 -39.0014 6.86553 + vertex -86.0821 -40.0908 8.60043 + endloop + endfacet + facet normal -0.0425673 -0.943548 -0.328491 + outer loop + vertex -86.0821 -40.0908 8.60043 + vertex -96.8425 -39.0014 6.86553 + vertex -86.1866 -39.4821 6.86564 + endloop + endfacet + facet normal -0.0357585 -0.792699 -0.608563 + outer loop + vertex -96.8425 -39.0014 6.86553 + vertex -96.6361 -37.8406 5.34143 + vertex -86.1866 -39.4821 6.86564 + endloop + endfacet + facet normal -0.0355976 -0.792239 -0.609171 + outer loop + vertex -86.1866 -39.4821 6.86564 + vertex -96.6361 -37.8406 5.34143 + vertex -85.9585 -38.3206 5.34171 + endloop + endfacet + facet normal -0.0505872 -0.789577 -0.611563 + outer loop + vertex -128.409 -37.1713 6.86392 + vertex -128.14 -36.0108 5.34338 + vertex -117.728 -37.8566 6.86526 + endloop + endfacet + facet normal -0.0512763 -0.791434 -0.609101 + outer loop + vertex -117.728 -37.8566 6.86526 + vertex -128.14 -36.0108 5.34338 + vertex -117.491 -36.6994 5.34157 + endloop + endfacet + facet normal -0.0607237 -0.944374 -0.323218 + outer loop + vertex -128.325 -37.7709 8.60027 + vertex -128.409 -37.1713 6.86392 + vertex -117.646 -38.4576 8.60042 + endloop + endfacet + facet normal -0.0605364 -0.944067 -0.324151 + outer loop + vertex -117.646 -38.4576 8.60042 + vertex -128.409 -37.1713 6.86392 + vertex -117.728 -37.8566 6.86526 + endloop + endfacet + facet normal -0.0541247 -0.944321 -0.324542 + outer loop + vertex -117.646 -38.4576 8.60042 + vertex -117.728 -37.8566 6.86526 + vertex -107.182 -39.0581 8.60247 + endloop + endfacet + facet normal -0.0555515 -0.946636 -0.317482 + outer loop + vertex -107.182 -39.0581 8.60247 + vertex -117.728 -37.8566 6.86526 + vertex -107.279 -38.4694 6.86406 + endloop + endfacet + facet normal -0.0465153 -0.79198 -0.608772 + outer loop + vertex -117.728 -37.8566 6.86526 + vertex -117.491 -36.6994 5.34157 + vertex -107.279 -38.4694 6.86406 + endloop + endfacet + facet normal -0.0468508 -0.792882 -0.607571 + outer loop + vertex -107.279 -38.4694 6.86406 + vertex -117.491 -36.6994 5.34157 + vertex -107.075 -37.312 5.33793 + endloop + endfacet + facet normal -0.0600927 -0.790996 -0.608863 + outer loop + vertex -150.272 -35.5689 6.86577 + vertex -150.029 -34.4148 5.34253 + vertex -139.319 -36.4008 6.86557 + endloop + endfacet + facet normal -0.0608213 -0.792933 -0.606265 + outer loop + vertex -139.319 -36.4008 6.86557 + vertex -150.029 -34.4148 5.34253 + vertex -139.057 -35.2537 5.33896 + endloop + endfacet + facet normal -0.0720983 -0.943509 -0.323408 + outer loop + vertex -150.164 -36.1721 8.60162 + vertex -150.272 -35.5689 6.86577 + vertex -139.227 -37.0074 8.60006 + endloop + endfacet + facet normal -0.0716109 -0.942707 -0.325846 + outer loop + vertex -139.227 -37.0074 8.60006 + vertex -150.272 -35.5689 6.86577 + vertex -139.319 -36.4008 6.86557 + endloop + endfacet + facet normal -0.0660427 -0.942978 -0.326237 + outer loop + vertex -139.227 -37.0074 8.60006 + vertex -139.319 -36.4008 6.86557 + vertex -128.325 -37.7709 8.60027 + endloop + endfacet + facet normal -0.0667195 -0.944101 -0.322835 + outer loop + vertex -128.325 -37.7709 8.60027 + vertex -139.319 -36.4008 6.86557 + vertex -128.409 -37.1713 6.86392 + endloop + endfacet + facet normal -0.0561302 -0.793544 -0.605919 + outer loop + vertex -139.319 -36.4008 6.86557 + vertex -139.057 -35.2537 5.33896 + vertex -128.409 -37.1713 6.86392 + endloop + endfacet + facet normal -0.0544739 -0.78908 -0.611871 + outer loop + vertex -128.409 -37.1713 6.86392 + vertex -139.057 -35.2537 5.33896 + vertex -128.14 -36.0108 5.34338 + endloop + endfacet + facet normal -0.0689524 -0.790827 -0.608143 + outer loop + vertex -171.7 -33.763 6.86327 + vertex -171.495 -32.6084 5.33859 + vertex -161.073 -34.691 6.86509 + endloop + endfacet + facet normal -0.0685946 -0.789925 -0.609355 + outer loop + vertex -161.073 -34.691 6.86509 + vertex -171.495 -32.6084 5.33859 + vertex -160.861 -33.534 5.34145 + endloop + endfacet + facet normal -0.0836795 -0.944512 -0.317641 + outer loop + vertex -171.593 -34.3573 8.60223 + vertex -171.7 -33.763 6.86327 + vertex -160.962 -35.2984 8.60006 + endloop + endfacet + facet normal -0.0822241 -0.942255 -0.324644 + outer loop + vertex -160.962 -35.2984 8.60006 + vertex -171.7 -33.763 6.86327 + vertex -161.073 -34.691 6.86509 + endloop + endfacet + facet normal -0.0762216 -0.942588 -0.325143 + outer loop + vertex -160.962 -35.2984 8.60006 + vertex -161.073 -34.691 6.86509 + vertex -150.164 -36.1721 8.60162 + endloop + endfacet + facet normal -0.076649 -0.943275 -0.323044 + outer loop + vertex -150.164 -36.1721 8.60162 + vertex -161.073 -34.691 6.86509 + vertex -150.272 -35.5689 6.86577 + endloop + endfacet + facet normal -0.0642096 -0.790453 -0.609148 + outer loop + vertex -161.073 -34.691 6.86509 + vertex -160.861 -33.534 5.34145 + vertex -150.272 -35.5689 6.86577 + endloop + endfacet + facet normal -0.0642167 -0.790471 -0.609123 + outer loop + vertex -150.272 -35.5689 6.86577 + vertex -160.861 -33.534 5.34145 + vertex -150.029 -34.4148 5.34253 + endloop + endfacet + facet normal -0.0791914 -0.790577 -0.607221 + outer loop + vertex -192.993 -31.6948 6.86549 + vertex -192.73 -30.55 5.34069 + vertex -182.295 -32.7654 6.86419 + endloop + endfacet + facet normal -0.0786783 -0.789324 -0.608914 + outer loop + vertex -182.295 -32.7654 6.86419 + vertex -192.73 -30.55 5.34069 + vertex -182.061 -31.6131 5.34025 + endloop + endfacet + facet normal -0.0940053 -0.940895 -0.325392 + outer loop + vertex -192.913 -32.3028 8.60036 + vertex -192.993 -31.6948 6.86549 + vertex -182.206 -33.3724 8.60018 + endloop + endfacet + facet normal -0.0942354 -0.941248 -0.324303 + outer loop + vertex -182.206 -33.3724 8.60018 + vertex -192.993 -31.6948 6.86549 + vertex -182.295 -32.7654 6.86419 + endloop + endfacet + facet normal -0.0873249 -0.941734 -0.324826 + outer loop + vertex -182.206 -33.3724 8.60018 + vertex -182.295 -32.7654 6.86419 + vertex -171.593 -34.3573 8.60223 + endloop + endfacet + facet normal -0.0889264 -0.944179 -0.317204 + outer loop + vertex -171.593 -34.3573 8.60223 + vertex -182.295 -32.7654 6.86419 + vertex -171.7 -33.763 6.86327 + endloop + endfacet + facet normal -0.0744261 -0.789903 -0.608698 + outer loop + vertex -182.295 -32.7654 6.86419 + vertex -182.061 -31.6131 5.34025 + vertex -171.7 -33.763 6.86327 + endloop + endfacet + facet normal -0.0745239 -0.790144 -0.608373 + outer loop + vertex -171.7 -33.763 6.86327 + vertex -182.061 -31.6131 5.34025 + vertex -171.495 -32.6084 5.33859 + endloop + endfacet + facet normal -0.0870831 -0.790098 -0.606763 + outer loop + vertex -214.406 -29.3972 6.86481 + vertex -214.155 -28.2537 5.33974 + vertex -203.755 -30.5705 6.86395 + endloop + endfacet + facet normal -0.0856779 -0.786763 -0.61128 + outer loop + vertex -203.755 -30.5705 6.86395 + vertex -214.155 -28.2537 5.33974 + vertex -203.477 -29.4195 5.34354 + endloop + endfacet + facet normal -0.103678 -0.94091 -0.322395 + outer loop + vertex -214.316 -30.002 8.6009 + vertex -214.406 -29.3972 6.86481 + vertex -203.669 -31.175 8.6004 + endloop + endfacet + facet normal -0.103672 -0.940901 -0.322423 + outer loop + vertex -203.669 -31.175 8.6004 + vertex -214.406 -29.3972 6.86481 + vertex -203.755 -30.5705 6.86395 + endloop + endfacet + facet normal -0.0986975 -0.941304 -0.32281 + outer loop + vertex -203.669 -31.175 8.6004 + vertex -203.755 -30.5705 6.86395 + vertex -192.913 -32.3028 8.60036 + endloop + endfacet + facet normal -0.0982163 -0.940571 -0.325084 + outer loop + vertex -192.913 -32.3028 8.60036 + vertex -203.755 -30.5705 6.86395 + vertex -192.993 -31.6948 6.86549 + endloop + endfacet + facet normal -0.0821643 -0.787314 -0.611053 + outer loop + vertex -203.755 -30.5705 6.86395 + vertex -203.477 -29.4195 5.34354 + vertex -192.993 -31.6948 6.86549 + endloop + endfacet + facet normal -0.0832615 -0.78997 -0.607466 + outer loop + vertex -192.993 -31.6948 6.86549 + vertex -203.477 -29.4195 5.34354 + vertex -192.73 -30.55 5.34069 + endloop + endfacet + facet normal -0.0946009 -0.789382 -0.60657 + outer loop + vertex -235.196 -26.9485 6.86398 + vertex -234.957 -25.8052 5.33872 + vertex -224.85 -28.1903 6.86646 + endloop + endfacet + facet normal -0.0941093 -0.788272 -0.608088 + outer loop + vertex -224.85 -28.1903 6.86646 + vertex -234.957 -25.8052 5.33872 + vertex -224.61 -27.0441 5.34342 + endloop + endfacet + facet normal -0.112673 -0.93889 -0.325255 + outer loop + vertex -235.119 -27.5593 8.60034 + vertex -235.196 -26.9485 6.86398 + vertex -224.768 -28.8015 8.60043 + endloop + endfacet + facet normal -0.112601 -0.938787 -0.325577 + outer loop + vertex -224.768 -28.8015 8.60043 + vertex -235.196 -26.9485 6.86398 + vertex -224.85 -28.1903 6.86646 + endloop + endfacet + facet normal -0.107859 -0.939214 -0.325952 + outer loop + vertex -224.768 -28.8015 8.60043 + vertex -224.85 -28.1903 6.86646 + vertex -214.316 -30.002 8.6009 + endloop + endfacet + facet normal -0.10873 -0.940481 -0.321984 + outer loop + vertex -214.316 -30.002 8.6009 + vertex -224.85 -28.1903 6.86646 + vertex -214.406 -29.3972 6.86481 + endloop + endfacet + facet normal -0.0912365 -0.788706 -0.607962 + outer loop + vertex -224.85 -28.1903 6.86646 + vertex -224.61 -27.0441 5.34342 + vertex -214.406 -29.3972 6.86481 + endloop + endfacet + facet normal -0.091546 -0.78942 -0.606989 + outer loop + vertex -214.406 -29.3972 6.86481 + vertex -224.61 -27.0441 5.34342 + vertex -214.155 -28.2537 5.33974 + endloop + endfacet + facet normal -0.103386 -0.789354 -0.605171 + outer loop + vertex -256.418 -24.2109 6.86466 + vertex -256.143 -23.0767 5.33816 + vertex -245.663 -25.6209 6.86633 + endloop + endfacet + facet normal -0.102631 -0.78765 -0.607515 + outer loop + vertex -245.663 -25.6209 6.86633 + vertex -256.143 -23.0767 5.33816 + vertex -245.398 -24.4799 5.34234 + endloop + endfacet + facet normal -0.122862 -0.937677 -0.325063 + outer loop + vertex -256.338 -24.823 8.60016 + vertex -256.418 -24.2109 6.86466 + vertex -245.592 -26.2314 8.60104 + endloop + endfacet + facet normal -0.122878 -0.9377 -0.324992 + outer loop + vertex -245.592 -26.2314 8.60104 + vertex -256.418 -24.2109 6.86466 + vertex -245.663 -25.6209 6.86633 + endloop + endfacet + facet normal -0.118968 -0.9381 -0.325292 + outer loop + vertex -245.592 -26.2314 8.60104 + vertex -245.663 -25.6209 6.86633 + vertex -235.119 -27.5593 8.60034 + endloop + endfacet + facet normal -0.119089 -0.938272 -0.324753 + outer loop + vertex -235.119 -27.5593 8.60034 + vertex -245.663 -25.6209 6.86633 + vertex -235.196 -26.9485 6.86398 + endloop + endfacet + facet normal -0.1001 -0.788071 -0.607391 + outer loop + vertex -245.663 -25.6209 6.86633 + vertex -245.398 -24.4799 5.34234 + vertex -235.196 -26.9485 6.86398 + endloop + endfacet + facet normal -0.100292 -0.7885 -0.606803 + outer loop + vertex -235.196 -26.9485 6.86398 + vertex -245.398 -24.4799 5.34234 + vertex -234.957 -25.8052 5.33872 + endloop + endfacet + facet normal -0.110973 -0.78549 -0.608844 + outer loop + vertex -278.43 -21.1551 6.86392 + vertex -278.181 -20.0093 5.3403 + vertex -267.411 -22.712 6.86414 + endloop + endfacet + facet normal -0.111127 -0.785835 -0.60837 + outer loop + vertex -267.411 -22.712 6.86414 + vertex -278.181 -20.0093 5.3403 + vertex -267.142 -21.5703 5.34014 + endloop + endfacet + facet normal -0.133 -0.93909 -0.316893 + outer loop + vertex -278.325 -21.7567 8.6025 + vertex -278.43 -21.1551 6.86392 + vertex -267.317 -23.3156 8.60201 + endloop + endfacet + facet normal -0.132602 -0.938523 -0.318733 + outer loop + vertex -267.317 -23.3156 8.60201 + vertex -278.43 -21.1551 6.86392 + vertex -267.411 -22.712 6.86414 + endloop + endfacet + facet normal -0.128975 -0.938915 -0.319067 + outer loop + vertex -267.317 -23.3156 8.60201 + vertex -267.411 -22.712 6.86414 + vertex -256.338 -24.823 8.60016 + endloop + endfacet + facet normal -0.127765 -0.937163 -0.324656 + outer loop + vertex -256.338 -24.823 8.60016 + vertex -267.411 -22.712 6.86414 + vertex -256.418 -24.2109 6.86466 + endloop + endfacet + facet normal -0.107211 -0.786518 -0.608189 + outer loop + vertex -267.411 -22.712 6.86414 + vertex -267.142 -21.5703 5.34014 + vertex -256.418 -24.2109 6.86466 + endloop + endfacet + facet normal -0.108103 -0.788535 -0.605414 + outer loop + vertex -256.418 -24.2109 6.86466 + vertex -267.142 -21.5703 5.34014 + vertex -256.143 -23.0767 5.33816 + endloop + endfacet + facet normal -0.119455 -0.784377 -0.608673 + outer loop + vertex -299.837 -17.9586 6.8655 + vertex -299.6 -16.8135 5.34338 + vertex -289.266 -19.5674 6.86415 + endloop + endfacet + facet normal -0.119204 -0.783843 -0.60941 + outer loop + vertex -289.266 -19.5674 6.86415 + vertex -299.6 -16.8135 5.34338 + vertex -289.031 -18.4192 5.34139 + endloop + endfacet + facet normal -0.140905 -0.93449 -0.326915 + outer loop + vertex -299.756 -18.5777 8.60028 + vertex -299.837 -17.9586 6.8655 + vertex -289.166 -20.1747 8.60134 + endloop + endfacet + facet normal -0.142621 -0.936838 -0.319364 + outer loop + vertex -289.166 -20.1747 8.60134 + vertex -299.837 -17.9586 6.8655 + vertex -289.266 -19.5674 6.86415 + endloop + endfacet + facet normal -0.136767 -0.937516 -0.319935 + outer loop + vertex -289.166 -20.1747 8.60134 + vertex -289.266 -19.5674 6.86415 + vertex -278.325 -21.7567 8.6025 + endloop + endfacet + facet normal -0.137536 -0.938588 -0.316445 + outer loop + vertex -278.325 -21.7567 8.6025 + vertex -289.266 -19.5674 6.86415 + vertex -278.43 -21.1551 6.86392 + endloop + endfacet + facet normal -0.114973 -0.784561 -0.609299 + outer loop + vertex -289.266 -19.5674 6.86415 + vertex -289.031 -18.4192 5.34139 + vertex -278.43 -21.1551 6.86392 + endloop + endfacet + facet normal -0.115077 -0.784788 -0.608987 + outer loop + vertex -278.43 -21.1551 6.86392 + vertex -289.031 -18.4192 5.34139 + vertex -278.181 -20.0093 5.3403 + endloop + endfacet + facet normal -0.12616 -0.7827 -0.609479 + outer loop + vertex -320.505 -14.6763 6.86365 + vertex -320.239 -13.5334 5.34105 + vertex -310.213 -16.3358 6.8645 + endloop + endfacet + facet normal -0.127003 -0.784419 -0.607089 + outer loop + vertex -310.213 -16.3358 6.8645 + vertex -320.239 -13.5334 5.34105 + vertex -309.969 -15.1952 5.33969 + endloop + endfacet + facet normal -0.150096 -0.933608 -0.325343 + outer loop + vertex -320.435 -15.2927 8.6002 + vertex -320.505 -14.6763 6.86365 + vertex -310.138 -16.9482 8.60088 + endloop + endfacet + facet normal -0.150631 -0.934311 -0.32307 + outer loop + vertex -310.138 -16.9482 8.60088 + vertex -320.505 -14.6763 6.86365 + vertex -310.213 -16.3358 6.8645 + endloop + endfacet + facet normal -0.146724 -0.934813 -0.323415 + outer loop + vertex -310.138 -16.9482 8.60088 + vertex -310.213 -16.3358 6.8645 + vertex -299.756 -18.5777 8.60028 + endloop + endfacet + facet normal -0.146017 -0.933866 -0.326454 + outer loop + vertex -299.756 -18.5777 8.60028 + vertex -310.213 -16.3358 6.8645 + vertex -299.837 -17.9586 6.8655 + endloop + endfacet + facet normal -0.122737 -0.785183 -0.606978 + outer loop + vertex -310.213 -16.3358 6.8645 + vertex -309.969 -15.1952 5.33969 + vertex -299.837 -17.9586 6.8655 + endloop + endfacet + facet normal -0.122126 -0.783914 -0.60874 + outer loop + vertex -299.837 -17.9586 6.8655 + vertex -309.969 -15.1952 5.33969 + vertex -299.6 -16.8135 5.34338 + endloop + endfacet + facet normal -0.133351 -0.782577 -0.608104 + outer loop + vertex -341.153 -11.1956 6.86357 + vertex -340.876 -10.059 5.33999 + vertex -330.802 -12.9606 6.86497 + endloop + endfacet + facet normal -0.134051 -0.783977 -0.606144 + outer loop + vertex -330.802 -12.9606 6.86497 + vertex -340.876 -10.059 5.33999 + vertex -330.531 -11.8271 5.33914 + endloop + endfacet + facet normal -0.159072 -0.932916 -0.323053 + outer loop + vertex -341.08 -11.8095 8.60008 + vertex -341.153 -11.1956 6.86357 + vertex -330.732 -13.5741 8.60065 + endloop + endfacet + facet normal -0.15901 -0.932835 -0.323318 + outer loop + vertex -330.732 -13.5741 8.60065 + vertex -341.153 -11.1956 6.86357 + vertex -330.802 -12.9606 6.86497 + endloop + endfacet + facet normal -0.155776 -0.933281 -0.323606 + outer loop + vertex -330.732 -13.5741 8.60065 + vertex -330.802 -12.9606 6.86497 + vertex -320.435 -15.2927 8.6002 + endloop + endfacet + facet normal -0.155476 -0.932891 -0.324871 + outer loop + vertex -320.435 -15.2927 8.6002 + vertex -330.802 -12.9606 6.86497 + vertex -320.505 -14.6763 6.86365 + endloop + endfacet + facet normal -0.130806 -0.784608 -0.606037 + outer loop + vertex -330.802 -12.9606 6.86497 + vertex -330.531 -11.8271 5.33914 + vertex -320.505 -14.6763 6.86365 + endloop + endfacet + facet normal -0.129542 -0.782061 -0.609589 + outer loop + vertex -320.505 -14.6763 6.86365 + vertex -330.531 -11.8271 5.33914 + vertex -320.239 -13.5334 5.34105 + endloop + endfacet + facet normal -0.141446 -0.78392 -0.604535 + outer loop + vertex -362.016 -7.48105 6.8649 + vertex -361.744 -6.35376 5.33942 + vertex -351.561 -9.36691 6.86415 + endloop + endfacet + facet normal -0.140055 -0.781175 -0.608399 + outer loop + vertex -351.561 -9.36691 6.86415 + vertex -361.744 -6.35376 5.33942 + vertex -351.28 -8.23161 5.34184 + endloop + endfacet + facet normal -0.167162 -0.929913 -0.327594 + outer loop + vertex -361.936 -8.10658 8.5997 + vertex -362.016 -7.48105 6.8649 + vertex -351.484 -9.98547 8.60012 + endloop + endfacet + facet normal -0.167942 -0.930921 -0.324317 + outer loop + vertex -351.484 -9.98547 8.60012 + vertex -362.016 -7.48105 6.8649 + vertex -351.561 -9.36691 6.86415 + endloop + endfacet + facet normal -0.163317 -0.93159 -0.324759 + outer loop + vertex -351.484 -9.98547 8.60012 + vertex -351.561 -9.36691 6.86415 + vertex -341.08 -11.8095 8.60008 + endloop + endfacet + facet normal -0.163825 -0.932245 -0.322615 + outer loop + vertex -341.08 -11.8095 8.60008 + vertex -351.561 -9.36691 6.86415 + vertex -341.153 -11.1956 6.86357 + endloop + endfacet + facet normal -0.137391 -0.781717 -0.608312 + outer loop + vertex -351.561 -9.36691 6.86415 + vertex -351.28 -8.23161 5.34184 + vertex -341.153 -11.1956 6.86357 + endloop + endfacet + facet normal -0.137417 -0.781767 -0.60824 + outer loop + vertex -341.153 -11.1956 6.86357 + vertex -351.28 -8.23161 5.34184 + vertex -340.876 -10.059 5.33999 + endloop + endfacet + facet normal -0.148673 -0.783455 -0.603402 + outer loop + vertex -383.077 -3.54052 6.86402 + vertex -382.789 -2.42186 5.3405 + vertex -372.516 -5.54419 6.86341 + endloop + endfacet + facet normal -0.146987 -0.780173 -0.60805 + outer loop + vertex -372.516 -5.54419 6.86341 + vertex -382.789 -2.42186 5.3405 + vertex -372.234 -4.4125 5.34324 + endloop + endfacet + facet normal -0.17572 -0.929685 -0.323742 + outer loop + vertex -382.998 -4.15975 8.59937 + vertex -383.077 -3.54052 6.86402 + vertex -372.431 -6.1573 8.59999 + endloop + endfacet + facet normal -0.176616 -0.930823 -0.319962 + outer loop + vertex -372.431 -6.1573 8.59999 + vertex -383.077 -3.54052 6.86402 + vertex -372.516 -5.54419 6.86341 + endloop + endfacet + facet normal -0.172991 -0.931375 -0.320335 + outer loop + vertex -372.431 -6.1573 8.59999 + vertex -372.516 -5.54419 6.86341 + vertex -361.936 -8.10658 8.5997 + endloop + endfacet + facet normal -0.171365 -0.929295 -0.327177 + outer loop + vertex -361.936 -8.10658 8.5997 + vertex -372.516 -5.54419 6.86341 + vertex -362.016 -7.48105 6.8649 + endloop + endfacet + facet normal -0.143937 -0.780812 -0.60796 + outer loop + vertex -372.516 -5.54419 6.86341 + vertex -372.234 -4.4125 5.34324 + vertex -362.016 -7.48105 6.8649 + endloop + endfacet + facet normal -0.145139 -0.783166 -0.604636 + outer loop + vertex -362.016 -7.48105 6.8649 + vertex -372.234 -4.4125 5.34324 + vertex -361.744 -6.35376 5.33942 + endloop + endfacet + facet normal -0.154851 -0.781004 -0.605024 + outer loop + vertex -404.486 0.668628 6.8637 + vertex -404.119 1.77276 5.34433 + vertex -393.734 -1.4651 6.86603 + endloop + endfacet + facet normal -0.15714 -0.785386 -0.598728 + outer loop + vertex -393.734 -1.4651 6.86603 + vertex -404.119 1.77276 5.34433 + vertex -393.42 -0.364106 5.33941 + endloop + endfacet + facet normal -0.186455 -0.931765 -0.311526 + outer loop + vertex -404.45 0.080527 8.60116 + vertex -404.486 0.668628 6.8637 + vertex -393.679 -2.07431 8.59929 + endloop + endfacet + facet normal -0.184295 -0.929072 -0.320719 + outer loop + vertex -393.679 -2.07431 8.59929 + vertex -404.486 0.668628 6.8637 + vertex -393.734 -1.4651 6.86603 + endloop + endfacet + facet normal -0.181496 -0.929536 -0.32097 + outer loop + vertex -393.679 -2.07431 8.59929 + vertex -393.734 -1.4651 6.86603 + vertex -382.998 -4.15975 8.59937 + endloop + endfacet + facet normal -0.180965 -0.928863 -0.32321 + outer loop + vertex -382.998 -4.15975 8.59937 + vertex -393.734 -1.4651 6.86603 + vertex -383.077 -3.54052 6.86402 + endloop + endfacet + facet normal -0.153247 -0.786276 -0.598569 + outer loop + vertex -393.734 -1.4651 6.86603 + vertex -393.42 -0.364106 5.33941 + vertex -383.077 -3.54052 6.86402 + endloop + endfacet + facet normal -0.15147 -0.782852 -0.603489 + outer loop + vertex -383.077 -3.54052 6.86402 + vertex -393.42 -0.364106 5.33941 + vertex -382.789 -2.42186 5.3405 + endloop + endfacet + facet normal -0.163803 -0.783948 -0.598827 + outer loop + vertex -425.744 5.05433 6.87086 + vertex -425.392 6.14925 5.34117 + vertex -415.21 2.85661 6.86629 + endloop + endfacet + facet normal -0.162727 -0.781958 -0.601715 + outer loop + vertex -415.21 2.85661 6.86629 + vertex -425.392 6.14925 5.34117 + vertex -414.832 3.95108 5.34188 + endloop + endfacet + facet normal -0.192694 -0.92714 -0.321372 + outer loop + vertex -425.769 4.45823 8.60553 + vertex -425.744 5.05433 6.87086 + vertex -415.208 2.26484 8.60111 + endloop + endfacet + facet normal -0.193843 -0.928534 -0.316623 + outer loop + vertex -415.208 2.26484 8.60111 + vertex -425.744 5.05433 6.87086 + vertex -415.21 2.85661 6.86629 + endloop + endfacet + facet normal -0.188718 -0.929478 -0.316948 + outer loop + vertex -415.208 2.26484 8.60111 + vertex -415.21 2.85661 6.86629 + vertex -404.45 0.080527 8.60116 + endloop + endfacet + facet normal -0.190065 -0.931132 -0.311237 + outer loop + vertex -404.45 0.080527 8.60116 + vertex -415.21 2.85661 6.86629 + vertex -404.486 0.668628 6.8637 + endloop + endfacet + facet normal -0.159848 -0.782694 -0.60153 + outer loop + vertex -415.21 2.85661 6.86629 + vertex -414.832 3.95108 5.34188 + vertex -404.486 0.668628 6.8637 + endloop + endfacet + facet normal -0.158479 -0.780103 -0.605247 + outer loop + vertex -404.486 0.668628 6.8637 + vertex -414.832 3.95108 5.34188 + vertex -404.119 1.77276 5.34433 + endloop + endfacet + facet normal -0.171206 -0.777812 -0.604728 + outer loop + vertex -446.074 9.45569 6.86941 + vertex -445.836 10.5909 5.34198 + vertex -436.002 7.23665 6.87224 + endloop + endfacet + facet normal -0.170128 -0.775907 -0.607474 + outer loop + vertex -436.002 7.23665 6.87224 + vertex -445.836 10.5909 5.34198 + vertex -435.689 8.36199 5.34711 + endloop + endfacet + facet normal -0.203305 -0.926032 -0.318011 + outer loop + vertex -446.087 8.86327 8.60326 + vertex -446.074 9.45569 6.86941 + vertex -436.022 6.65106 8.61037 + endloop + endfacet + facet normal -0.204157 -0.926995 -0.314644 + outer loop + vertex -436.022 6.65106 8.61037 + vertex -446.074 9.45569 6.86941 + vertex -436.002 7.23665 6.87224 + endloop + endfacet + facet normal -0.198647 -0.928087 -0.314949 + outer loop + vertex -436.022 6.65106 8.61037 + vertex -436.002 7.23665 6.87224 + vertex -425.769 4.45823 8.60553 + endloop + endfacet + facet normal -0.19711 -0.926291 -0.321143 + outer loop + vertex -425.769 4.45823 8.60553 + vertex -436.002 7.23665 6.87224 + vertex -425.744 5.05433 6.87086 + endloop + endfacet + facet normal -0.165395 -0.777038 -0.607336 + outer loop + vertex -436.002 7.23665 6.87224 + vertex -435.689 8.36199 5.34711 + vertex -425.744 5.05433 6.87086 + endloop + endfacet + facet normal -0.168563 -0.782754 -0.599068 + outer loop + vertex -425.744 5.05433 6.87086 + vertex -435.689 8.36199 5.34711 + vertex -425.392 6.14925 5.34117 + endloop + endfacet + facet normal -0.17632 -0.772015 -0.610659 + outer loop + vertex -466.872 14.1943 6.82348 + vertex -466.766 15.3658 5.31191 + vertex -456.269 11.7552 6.84558 + endloop + endfacet + facet normal -0.177442 -0.774043 -0.607759 + outer loop + vertex -456.269 11.7552 6.84558 + vertex -466.766 15.3658 5.31191 + vertex -456.097 12.9086 5.32629 + endloop + endfacet + facet normal -0.210216 -0.92205 -0.325011 + outer loop + vertex -466.866 13.5865 8.54373 + vertex -466.872 14.1943 6.82348 + vertex -456.271 11.1603 8.57424 + endloop + endfacet + facet normal -0.211898 -0.924023 -0.318246 + outer loop + vertex -456.271 11.1603 8.57424 + vertex -466.872 14.1943 6.82348 + vertex -456.269 11.7552 6.84558 + endloop + endfacet + facet normal -0.2077 -0.924876 -0.318535 + outer loop + vertex -456.271 11.1603 8.57424 + vertex -456.269 11.7552 6.84558 + vertex -446.087 8.86327 8.60326 + endloop + endfacet + facet normal -0.207904 -0.925107 -0.317731 + outer loop + vertex -446.087 8.86327 8.60326 + vertex -456.269 11.7552 6.84558 + vertex -446.074 9.45569 6.86941 + endloop + endfacet + facet normal -0.173339 -0.774855 -0.607909 + outer loop + vertex -456.269 11.7552 6.84558 + vertex -456.097 12.9086 5.32629 + vertex -446.074 9.45569 6.86941 + endloop + endfacet + facet normal -0.174596 -0.777075 -0.604707 + outer loop + vertex -446.074 9.45569 6.86941 + vertex -456.097 12.9086 5.32629 + vertex -445.836 10.5909 5.34198 + endloop + endfacet + facet normal -0.187385 -0.792056 -0.580977 + outer loop + vertex -488.379 19.1099 6.96533 + vertex -488.189 20.1649 5.46573 + vertex -477.779 16.689 6.84685 + endloop + endfacet + facet normal -0.17743 -0.773273 -0.608743 + outer loop + vertex -477.779 16.689 6.84685 + vertex -488.189 20.1649 5.46573 + vertex -477.747 17.87 5.33726 + endloop + endfacet + facet normal -0.22292 -0.935836 -0.27298 + outer loop + vertex -488.556 18.632 8.74816 + vertex -488.379 19.1099 6.96533 + vertex -477.822 16.1251 8.57712 + endloop + endfacet + facet normal -0.215126 -0.926912 -0.307499 + outer loop + vertex -477.822 16.1251 8.57712 + vertex -488.379 19.1099 6.96533 + vertex -477.779 16.689 6.84685 + endloop + endfacet + facet normal -0.215672 -0.926793 -0.307474 + outer loop + vertex -477.822 16.1251 8.57712 + vertex -477.779 16.689 6.84685 + vertex -466.866 13.5865 8.54373 + endloop + endfacet + facet normal -0.211536 -0.921783 -0.324912 + outer loop + vertex -466.866 13.5865 8.54373 + vertex -477.779 16.689 6.84685 + vertex -466.872 14.1943 6.82348 + endloop + endfacet + facet normal -0.17815 -0.773163 -0.608672 + outer loop + vertex -477.779 16.689 6.84685 + vertex -477.747 17.87 5.33726 + vertex -466.872 14.1943 6.82348 + endloop + endfacet + facet normal -0.177434 -0.771819 -0.610584 + outer loop + vertex -466.872 14.1943 6.82348 + vertex -477.747 17.87 5.33726 + vertex -466.766 15.3658 5.31191 + endloop + endfacet + facet normal -0.23591 -0.939481 -0.248441 + outer loop + vertex -497.415 20.7289 9.23036 + vertex -498.682 21.6159 7.07943 + vertex -488.556 18.632 8.74816 + endloop + endfacet + facet normal -0.230213 -0.934001 -0.273211 + outer loop + vertex -488.556 18.632 8.74816 + vertex -498.682 21.6159 7.07943 + vertex -488.379 19.1099 6.96533 + endloop + endfacet + facet normal -0.207079 -0.827578 -0.52176 + outer loop + vertex -498.682 21.6159 7.07943 + vertex -496.127 21.8349 5.71802 + vertex -488.379 19.1099 6.96533 + endloop + endfacet + facet normal -0.185208 -0.792527 -0.581032 + outer loop + vertex -488.379 19.1099 6.96533 + vertex -496.127 21.8349 5.71802 + vertex -488.189 20.1649 5.46573 + endloop + endfacet + facet normal -0.271684 -0.778198 -0.566212 + outer loop + vertex -509.14 24.3512 6.87087 + vertex -509.133 25.4154 5.4049 + vertex -508.248 24.1989 6.65228 + endloop + endfacet + facet normal -0.161694 -0.761382 -0.627816 + outer loop + vertex -508.248 24.1989 6.65228 + vertex -509.133 25.4154 5.4049 + vertex -508.138 25.3556 5.22112 + endloop + endfacet + facet normal -0.262728 -0.910091 -0.320482 + outer loop + vertex -509.208 23.7462 8.64512 + vertex -509.14 24.3512 6.87087 + vertex -507.967 23.4672 8.41956 + endloop + endfacet + facet normal -0.238478 -0.910111 -0.338861 + outer loop + vertex -507.967 23.4672 8.41956 + vertex -509.14 24.3512 6.87087 + vertex -508.248 24.1989 6.65228 + endloop + endfacet + facet normal -0.249169 -0.908173 -0.336357 + outer loop + vertex -507.967 23.4672 8.41956 + vertex -508.248 24.1989 6.65228 + vertex -504.588 22.7145 7.94895 + endloop + endfacet + facet normal -0.211457 -0.884549 -0.415763 + outer loop + vertex -504.588 22.7145 7.94895 + vertex -508.248 24.1989 6.65228 + vertex -505.648 23.7195 6.34974 + endloop + endfacet + facet normal -0.211294 -0.752163 -0.624184 + outer loop + vertex -508.248 24.1989 6.65228 + vertex -508.138 25.3556 5.22112 + vertex -505.648 23.7195 6.34974 + endloop + endfacet + facet normal -0.167449 -0.719668 -0.673824 + outer loop + vertex -505.648 23.7195 6.34974 + vertex -508.138 25.3556 5.22112 + vertex -503.71 24.4119 5.12868 + endloop + endfacet + facet normal 0.0745239 0.949235 0.305614 + outer loop + vertex -509.03 23.6746 8.82407 + vertex -508.93 24.2552 6.99646 + vertex -509.208 23.7462 8.64512 + endloop + endfacet + facet normal 0.227892 0.918858 0.322125 + outer loop + vertex -509.208 23.7462 8.64512 + vertex -508.93 24.2552 6.99646 + vertex -509.14 24.3512 6.87087 + endloop + endfacet + facet normal 0.0301622 0.81768 0.574882 + outer loop + vertex -508.93 24.2552 6.99646 + vertex -508.846 25.3324 5.45995 + vertex -509.14 24.3512 6.87087 + endloop + endfacet + facet normal 0.12057 0.803082 0.583543 + outer loop + vertex -509.14 24.3512 6.87087 + vertex -508.846 25.3324 5.45995 + vertex -509.133 25.4154 5.4049 + endloop + endfacet + facet normal 0.0809106 -0.431137 -0.898651 + outer loop + vertex 504.751 26.1786 4.05734 + vertex 505.653 28.1259 3.20425 + vertex 508.018 27.0966 3.91103 + endloop + endfacet + facet normal 0.0703214 -0.449783 -0.890365 + outer loop + vertex 508.018 27.0966 3.91103 + vertex 505.653 28.1259 3.20425 + vertex 508.543 28.0281 3.48188 + endloop + endfacet + facet normal 0.12215 -0.580632 -0.804951 + outer loop + vertex 504.371 24.4227 5.26613 + vertex 504.751 26.1786 4.05734 + vertex 507.961 25.7682 4.84033 + endloop + endfacet + facet normal 0.124552 -0.572383 -0.810472 + outer loop + vertex 507.961 25.7682 4.84033 + vertex 504.751 26.1786 4.05734 + vertex 508.018 27.0966 3.91103 + endloop + endfacet + facet normal 0.108334 -0.437167 -0.892832 + outer loop + vertex 489.384 22.3058 4.1463 + vertex 490.714 24.4779 3.24409 + vertex 498.352 24.5025 4.15881 + endloop + endfacet + facet normal 0.109244 -0.420083 -0.900886 + outer loop + vertex 498.352 24.5025 4.15881 + vertex 490.714 24.4779 3.24409 + vertex 498.34 26.7968 3.08761 + endloop + endfacet + facet normal 0.145705 -0.596292 -0.789434 + outer loop + vertex 488.528 20.4319 5.40367 + vertex 489.384 22.3058 4.1463 + vertex 497.721 22.6547 5.42143 + endloop + endfacet + facet normal 0.146035 -0.591643 -0.792864 + outer loop + vertex 497.721 22.6547 5.42143 + vertex 489.384 22.3058 4.1463 + vertex 498.352 24.5025 4.15881 + endloop + endfacet + facet normal 0.13844 -0.590539 -0.795046 + outer loop + vertex 497.721 22.6547 5.42143 + vertex 498.352 24.5025 4.15881 + vertex 504.371 24.4227 5.26613 + endloop + endfacet + facet normal 0.139688 -0.581856 -0.801206 + outer loop + vertex 504.371 24.4227 5.26613 + vertex 498.352 24.5025 4.15881 + vertex 504.751 26.1786 4.05734 + endloop + endfacet + facet normal 0.0958864 -0.420721 -0.902108 + outer loop + vertex 498.352 24.5025 4.15881 + vertex 498.34 26.7968 3.08761 + vertex 504.751 26.1786 4.05734 + endloop + endfacet + facet normal 0.0934384 -0.435483 -0.895334 + outer loop + vertex 504.751 26.1786 4.05734 + vertex 498.34 26.7968 3.08761 + vertex 505.653 28.1259 3.20425 + endloop + endfacet + facet normal 0.103056 -0.432649 -0.895653 + outer loop + vertex 467.807 17.2737 4.05616 + vertex 469.574 19.525 3.17198 + vertex 478.776 19.8147 4.09084 + endloop + endfacet + facet normal 0.103334 -0.414507 -0.90416 + outer loop + vertex 478.776 19.8147 4.09084 + vertex 469.574 19.525 3.17198 + vertex 479.728 22.286 3.06671 + endloop + endfacet + facet normal 0.139213 -0.589913 -0.795376 + outer loop + vertex 467.093 15.4113 5.31249 + vertex 467.807 17.2737 4.05616 + vertex 477.936 17.9344 5.33898 + endloop + endfacet + facet normal 0.139209 -0.590083 -0.79525 + outer loop + vertex 477.936 17.9344 5.33898 + vertex 467.807 17.2737 4.05616 + vertex 478.776 19.8147 4.09084 + endloop + endfacet + facet normal 0.144242 -0.59119 -0.793529 + outer loop + vertex 477.936 17.9344 5.33898 + vertex 478.776 19.8147 4.09084 + vertex 488.528 20.4319 5.40367 + endloop + endfacet + facet normal 0.144068 -0.595929 -0.790008 + outer loop + vertex 488.528 20.4319 5.40367 + vertex 478.776 19.8147 4.09084 + vertex 489.384 22.3058 4.1463 + endloop + endfacet + facet normal 0.101973 -0.41412 -0.904492 + outer loop + vertex 478.776 19.8147 4.09084 + vertex 479.728 22.286 3.06671 + vertex 489.384 22.3058 4.1463 + endloop + endfacet + facet normal 0.100993 -0.433725 -0.895367 + outer loop + vertex 489.384 22.3058 4.1463 + vertex 479.728 22.286 3.06671 + vertex 490.714 24.4779 3.24409 + endloop + endfacet + facet normal 0.0960304 -0.432998 -0.896265 + outer loop + vertex 446.78 12.5084 4.07606 + vertex 448.24 14.691 3.178 + vertex 457.143 14.8368 4.06144 + endloop + endfacet + facet normal 0.096589 -0.414375 -0.904966 + outer loop + vertex 457.143 14.8368 4.06144 + vertex 448.24 14.691 3.178 + vertex 458.093 17.3105 3.0302 + endloop + endfacet + facet normal 0.13201 -0.596991 -0.791312 + outer loop + vertex 446.249 10.7063 5.34688 + vertex 446.78 12.5084 4.07606 + vertex 456.567 13.0123 5.32859 + endloop + endfacet + facet normal 0.132175 -0.593213 -0.794121 + outer loop + vertex 456.567 13.0123 5.32859 + vertex 446.78 12.5084 4.07606 + vertex 457.143 14.8368 4.06144 + endloop + endfacet + facet normal 0.13405 -0.593458 -0.793623 + outer loop + vertex 456.567 13.0123 5.32859 + vertex 457.143 14.8368 4.06144 + vertex 467.093 15.4113 5.31249 + endloop + endfacet + facet normal 0.134205 -0.589019 -0.796897 + outer loop + vertex 467.093 15.4113 5.31249 + vertex 457.143 14.8368 4.06144 + vertex 467.807 17.2737 4.05616 + endloop + endfacet + facet normal 0.0940788 -0.413658 -0.905559 + outer loop + vertex 457.143 14.8368 4.06144 + vertex 458.093 17.3105 3.0302 + vertex 467.807 17.2737 4.05616 + endloop + endfacet + facet normal 0.0934 -0.426619 -0.899596 + outer loop + vertex 467.807 17.2737 4.05616 + vertex 458.093 17.3105 3.0302 + vertex 469.574 19.525 3.17198 + endloop + endfacet + facet normal 0.0928443 -0.43484 -0.895709 + outer loop + vertex 426.051 8.01621 4.0904 + vertex 427.497 10.1721 3.19369 + vertex 436.478 10.2489 4.08734 + endloop + endfacet + facet normal 0.0936393 -0.413885 -0.9055 + outer loop + vertex 436.478 10.2489 4.08734 + vertex 427.497 10.1721 3.19369 + vertex 437.182 12.6675 3.05469 + endloop + endfacet + facet normal 0.127375 -0.592856 -0.795171 + outer loop + vertex 425.399 6.18982 5.34777 + vertex 426.051 8.01621 4.0904 + vertex 435.887 8.43787 5.35161 + endloop + endfacet + facet normal 0.127244 -0.59536 -0.793319 + outer loop + vertex 435.887 8.43787 5.35161 + vertex 426.051 8.01621 4.0904 + vertex 436.478 10.2489 4.08734 + endloop + endfacet + facet normal 0.130059 -0.595753 -0.792567 + outer loop + vertex 435.887 8.43787 5.35161 + vertex 436.478 10.2489 4.08734 + vertex 446.249 10.7063 5.34688 + endloop + endfacet + facet normal 0.130009 -0.596758 -0.791819 + outer loop + vertex 446.249 10.7063 5.34688 + vertex 436.478 10.2489 4.08734 + vertex 446.78 12.5084 4.07606 + endloop + endfacet + facet normal 0.0895932 -0.413045 -0.906293 + outer loop + vertex 436.478 10.2489 4.08734 + vertex 437.182 12.6675 3.05469 + vertex 446.78 12.5084 4.07606 + endloop + endfacet + facet normal 0.0885423 -0.42908 -0.898916 + outer loop + vertex 446.78 12.5084 4.07606 + vertex 437.182 12.6675 3.05469 + vertex 448.24 14.691 3.178 + endloop + endfacet + facet normal 0.0890135 -0.434764 -0.896134 + outer loop + vertex 405.073 3.66123 4.08604 + vertex 406.536 5.80432 3.19164 + vertex 415.544 5.80625 4.0855 + endloop + endfacet + facet normal 0.0899194 -0.415134 -0.905306 + outer loop + vertex 415.544 5.80625 4.0855 + vertex 406.536 5.80432 3.19164 + vertex 416.306 8.22255 3.05311 + endloop + endfacet + facet normal 0.121721 -0.594807 -0.7946 + outer loop + vertex 404.436 1.84974 5.34457 + vertex 405.073 3.66123 4.08604 + vertex 414.891 3.98843 5.34508 + endloop + endfacet + facet normal 0.12174 -0.5945 -0.794827 + outer loop + vertex 414.891 3.98843 5.34508 + vertex 405.073 3.66123 4.08604 + vertex 415.544 5.80625 4.0855 + endloop + endfacet + facet normal 0.124851 -0.595016 -0.793957 + outer loop + vertex 414.891 3.98843 5.34508 + vertex 415.544 5.80625 4.0855 + vertex 425.399 6.18982 5.34777 + endloop + endfacet + facet normal 0.124993 -0.592467 -0.795839 + outer loop + vertex 425.399 6.18982 5.34777 + vertex 415.544 5.80625 4.0855 + vertex 426.051 8.01621 4.0904 + endloop + endfacet + facet normal 0.0876335 -0.414611 -0.905769 + outer loop + vertex 415.544 5.80625 4.0855 + vertex 416.306 8.22255 3.05311 + vertex 426.051 8.01621 4.0904 + endloop + endfacet + facet normal 0.0864458 -0.431487 -0.897968 + outer loop + vertex 426.051 8.01621 4.0904 + vertex 416.306 8.22255 3.05311 + vertex 427.497 10.1721 3.19369 + endloop + endfacet + facet normal 0.084358 -0.433356 -0.897266 + outer loop + vertex 384.012 -0.504847 4.07996 + vertex 385.522 1.63413 3.1889 + vertex 394.598 1.55684 4.07947 + endloop + endfacet + facet normal 0.0853691 -0.414689 -0.90595 + outer loop + vertex 394.598 1.55684 4.07947 + vertex 385.522 1.63413 3.1889 + vertex 395.336 3.96013 3.04897 + endloop + endfacet + facet normal 0.11623 -0.59853 -0.792624 + outer loop + vertex 383.33 -2.31004 5.34311 + vertex 384.012 -0.504847 4.07996 + vertex 393.959 -0.245138 5.34247 + endloop + endfacet + facet normal 0.116309 -0.597384 -0.793476 + outer loop + vertex 393.959 -0.245138 5.34247 + vertex 384.012 -0.504847 4.07996 + vertex 394.598 1.55684 4.07947 + endloop + endfacet + facet normal 0.119711 -0.597941 -0.79255 + outer loop + vertex 393.959 -0.245138 5.34247 + vertex 394.598 1.55684 4.07947 + vertex 404.436 1.84974 5.34457 + endloop + endfacet + facet normal 0.119935 -0.594518 -0.795087 + outer loop + vertex 404.436 1.84974 5.34457 + vertex 394.598 1.55684 4.07947 + vertex 405.073 3.66123 4.08604 + endloop + endfacet + facet normal 0.0838077 -0.41434 -0.906255 + outer loop + vertex 394.598 1.55684 4.07947 + vertex 395.336 3.96013 3.04897 + vertex 405.073 3.66123 4.08604 + endloop + endfacet + facet normal 0.0824573 -0.431257 -0.898453 + outer loop + vertex 405.073 3.66123 4.08604 + vertex 395.336 3.96013 3.04897 + vertex 406.536 5.80432 3.19164 + endloop + endfacet + facet normal 0.0817505 -0.437943 -0.895278 + outer loop + vertex 362.432 -4.55487 4.0803 + vertex 364.081 -2.41312 3.18317 + vertex 373.254 -2.54327 4.08444 + endloop + endfacet + facet normal 0.0829038 -0.418857 -0.90426 + outer loop + vertex 373.254 -2.54327 4.08444 + vertex 364.081 -2.41312 3.18317 + vertex 374.132 -0.133205 3.04863 + endloop + endfacet + facet normal 0.109914 -0.598882 -0.793259 + outer loop + vertex 361.694 -6.36325 5.34336 + vertex 362.432 -4.55487 4.0803 + vertex 372.514 -4.37119 5.33861 + endloop + endfacet + facet normal 0.110402 -0.592278 -0.798134 + outer loop + vertex 372.514 -4.37119 5.33861 + vertex 362.432 -4.55487 4.0803 + vertex 373.254 -2.54327 4.08444 + endloop + endfacet + facet normal 0.113314 -0.592872 -0.797284 + outer loop + vertex 372.514 -4.37119 5.33861 + vertex 373.254 -2.54327 4.08444 + vertex 383.33 -2.31004 5.34311 + endloop + endfacet + facet normal 0.112963 -0.597938 -0.793542 + outer loop + vertex 383.33 -2.31004 5.34311 + vertex 373.254 -2.54327 4.08444 + vertex 384.012 -0.504847 4.07996 + endloop + endfacet + facet normal 0.0787728 -0.417733 -0.905149 + outer loop + vertex 373.254 -2.54327 4.08444 + vertex 374.132 -0.133205 3.04863 + vertex 384.012 -0.504847 4.07996 + endloop + endfacet + facet normal 0.0777477 -0.429674 -0.899631 + outer loop + vertex 384.012 -0.504847 4.07996 + vertex 374.132 -0.133205 3.04863 + vertex 385.522 1.63413 3.1889 + endloop + endfacet + facet normal 0.0765012 -0.437285 -0.896063 + outer loop + vertex 341.4 -8.30191 4.08336 + vertex 342.937 -6.19683 3.18728 + vertex 351.769 -6.48194 4.08045 + endloop + endfacet + facet normal 0.0781664 -0.416339 -0.905843 + outer loop + vertex 351.769 -6.48194 4.08045 + vertex 342.937 -6.19683 3.18728 + vertex 352.742 -4.05794 3.05028 + endloop + endfacet + facet normal 0.104376 -0.596465 -0.795823 + outer loop + vertex 340.743 -10.0953 5.3414 + vertex 341.4 -8.30191 4.08336 + vertex 351.058 -8.28818 5.33973 + endloop + endfacet + facet normal 0.104409 -0.59612 -0.796077 + outer loop + vertex 351.058 -8.28818 5.33973 + vertex 341.4 -8.30191 4.08336 + vertex 351.769 -6.48194 4.08045 + endloop + endfacet + facet normal 0.10829 -0.596886 -0.794984 + outer loop + vertex 351.058 -8.28818 5.33973 + vertex 351.769 -6.48194 4.08045 + vertex 361.694 -6.36325 5.34336 + endloop + endfacet + facet normal 0.108155 -0.598523 -0.793771 + outer loop + vertex 361.694 -6.36325 5.34336 + vertex 351.769 -6.48194 4.08045 + vertex 362.432 -4.55487 4.0803 + endloop + endfacet + facet normal 0.0750571 -0.415388 -0.906542 + outer loop + vertex 351.769 -6.48194 4.08045 + vertex 352.742 -4.05794 3.05028 + vertex 362.432 -4.55487 4.0803 + endloop + endfacet + facet normal 0.0733101 -0.432798 -0.898505 + outer loop + vertex 362.432 -4.55487 4.0803 + vertex 352.742 -4.05794 3.05028 + vertex 364.081 -2.41312 3.18317 + endloop + endfacet + facet normal 0.0727599 -0.441014 -0.894546 + outer loop + vertex 321.079 -11.7243 4.08418 + vertex 322.508 -9.65994 3.18265 + vertex 331.246 -10.0409 4.08117 + endloop + endfacet + facet normal 0.0748616 -0.418148 -0.905289 + outer loop + vertex 331.246 -10.0409 4.08117 + vertex 322.508 -9.65994 3.18265 + vertex 332.009 -7.66739 3.04799 + endloop + endfacet + facet normal 0.0984539 -0.596695 -0.796406 + outer loop + vertex 320.418 -13.5113 5.3414 + vertex 321.079 -11.7243 4.08418 + vertex 330.606 -11.828 5.33962 + endloop + endfacet + facet normal 0.0984986 -0.596281 -0.79671 + outer loop + vertex 330.606 -11.828 5.33962 + vertex 321.079 -11.7243 4.08418 + vertex 331.246 -10.0409 4.08117 + endloop + endfacet + facet normal 0.102169 -0.596927 -0.795763 + outer loop + vertex 330.606 -11.828 5.33962 + vertex 331.246 -10.0409 4.08117 + vertex 340.743 -10.0953 5.3414 + endloop + endfacet + facet normal 0.102256 -0.596083 -0.796385 + outer loop + vertex 340.743 -10.0953 5.3414 + vertex 331.246 -10.0409 4.08117 + vertex 341.4 -8.30191 4.08336 + endloop + endfacet + facet normal 0.0716769 -0.417388 -0.905897 + outer loop + vertex 331.246 -10.0409 4.08117 + vertex 332.009 -7.66739 3.04799 + vertex 341.4 -8.30191 4.08336 + endloop + endfacet + facet normal 0.0697778 -0.43341 -0.898492 + outer loop + vertex 341.4 -8.30191 4.08336 + vertex 332.009 -7.66739 3.04799 + vertex 342.937 -6.19683 3.18728 + endloop + endfacet + facet normal 0.0683146 -0.43697 -0.896878 + outer loop + vertex 300.066 -15.0671 4.08076 + vertex 301.639 -12.9862 3.18669 + vertex 310.699 -13.403 4.07992 + endloop + endfacet + facet normal 0.0700709 -0.417894 -0.90579 + outer loop + vertex 310.699 -13.403 4.07992 + vertex 301.639 -12.9862 3.18669 + vertex 311.459 -11.0386 3.04779 + endloop + endfacet + facet normal 0.0929627 -0.597999 -0.796088 + outer loop + vertex 299.316 -16.8603 5.34013 + vertex 300.066 -15.0671 4.08076 + vertex 309.988 -15.1982 5.33784 + endloop + endfacet + facet normal 0.0931896 -0.595869 -0.797657 + outer loop + vertex 309.988 -15.1982 5.33784 + vertex 300.066 -15.0671 4.08076 + vertex 310.699 -13.403 4.07992 + endloop + endfacet + facet normal 0.096757 -0.596601 -0.796684 + outer loop + vertex 309.988 -15.1982 5.33784 + vertex 310.699 -13.403 4.07992 + vertex 320.418 -13.5113 5.3414 + endloop + endfacet + facet normal 0.0967801 -0.596384 -0.796843 + outer loop + vertex 320.418 -13.5113 5.3414 + vertex 310.699 -13.403 4.07992 + vertex 321.079 -11.7243 4.08418 + endloop + endfacet + facet normal 0.0678724 -0.417367 -0.9062 + outer loop + vertex 310.699 -13.403 4.07992 + vertex 311.459 -11.0386 3.04779 + vertex 321.079 -11.7243 4.08418 + endloop + endfacet + facet normal 0.0654817 -0.437067 -0.897042 + outer loop + vertex 321.079 -11.7243 4.08418 + vertex 311.459 -11.0386 3.04779 + vertex 322.508 -9.65994 3.18265 + endloop + endfacet + facet normal 0.0641797 -0.437401 -0.896974 + outer loop + vertex 278.521 -18.2865 4.08215 + vertex 280.166 -16.212 3.18827 + vertex 289.282 -16.7056 4.08121 + endloop + endfacet + facet normal 0.0660992 -0.41819 -0.905951 + outer loop + vertex 289.282 -16.7056 4.08121 + vertex 280.166 -16.212 3.18827 + vertex 290.214 -14.3226 3.04919 + endloop + endfacet + facet normal 0.0875796 -0.599616 -0.795481 + outer loop + vertex 277.78 -20.0667 5.34246 + vertex 278.521 -18.2865 4.08215 + vertex 288.526 -18.4945 5.34054 + endloop + endfacet + facet normal 0.0877716 -0.597929 -0.796729 + outer loop + vertex 288.526 -18.4945 5.34054 + vertex 278.521 -18.2865 4.08215 + vertex 289.282 -16.7056 4.08121 + endloop + endfacet + facet normal 0.0906343 -0.598572 -0.795925 + outer loop + vertex 288.526 -18.4945 5.34054 + vertex 289.282 -16.7056 4.08121 + vertex 299.316 -16.8603 5.34013 + endloop + endfacet + facet normal 0.0907491 -0.597509 -0.79671 + outer loop + vertex 299.316 -16.8603 5.34013 + vertex 289.282 -16.7056 4.08121 + vertex 300.066 -15.0671 4.08076 + endloop + endfacet + facet normal 0.0633755 -0.417373 -0.906523 + outer loop + vertex 289.282 -16.7056 4.08121 + vertex 290.214 -14.3226 3.04919 + vertex 300.066 -15.0671 4.08076 + endloop + endfacet + facet normal 0.0614562 -0.432856 -0.899366 + outer loop + vertex 300.066 -15.0671 4.08076 + vertex 290.214 -14.3226 3.04919 + vertex 301.639 -12.9862 3.18669 + endloop + endfacet + facet normal 0.0592772 -0.438061 -0.896989 + outer loop + vertex 257.369 -21.2364 4.08283 + vertex 258.949 -19.1903 3.188 + vertex 267.867 -19.8066 4.07831 + endloop + endfacet + facet normal 0.0616674 -0.417401 -0.906627 + outer loop + vertex 267.867 -19.8066 4.07831 + vertex 258.949 -19.1903 3.188 + vertex 268.818 -17.4279 3.04792 + endloop + endfacet + facet normal 0.0821064 -0.596843 -0.798146 + outer loop + vertex 256.655 -23.0132 5.33806 + vertex 257.369 -21.2364 4.08283 + vertex 267.154 -21.5734 5.34137 + endloop + endfacet + facet normal 0.0815413 -0.601208 -0.794921 + outer loop + vertex 267.154 -21.5734 5.34137 + vertex 257.369 -21.2364 4.08283 + vertex 267.867 -19.8066 4.07831 + endloop + endfacet + facet normal 0.0854409 -0.602039 -0.793882 + outer loop + vertex 267.154 -21.5734 5.34137 + vertex 267.867 -19.8066 4.07831 + vertex 277.78 -20.0667 5.34246 + endloop + endfacet + facet normal 0.0857821 -0.599218 -0.795977 + outer loop + vertex 277.78 -20.0667 5.34246 + vertex 267.867 -19.8066 4.07831 + vertex 278.521 -18.2865 4.08215 + endloop + endfacet + facet normal 0.0597982 -0.416823 -0.907019 + outer loop + vertex 267.867 -19.8066 4.07831 + vertex 268.818 -17.4279 3.04792 + vertex 278.521 -18.2865 4.08215 + endloop + endfacet + facet normal 0.0575423 -0.433206 -0.899456 + outer loop + vertex 278.521 -18.2865 4.08215 + vertex 268.818 -17.4279 3.04792 + vertex 280.166 -16.212 3.18827 + endloop + endfacet + facet normal 0.0550651 -0.439001 -0.896798 + outer loop + vertex 236.522 -23.9289 4.08201 + vertex 238.072 -21.9052 3.18652 + vertex 246.942 -22.6155 4.07887 + endloop + endfacet + facet normal 0.0576268 -0.418853 -0.906224 + outer loop + vertex 246.942 -22.6155 4.07887 + vertex 238.072 -21.9052 3.18652 + vertex 247.811 -20.2627 3.0467 + endloop + endfacet + facet normal 0.0762623 -0.597666 -0.79811 + outer loop + vertex 235.792 -25.6992 5.33792 + vertex 236.522 -23.9289 4.08201 + vertex 246.24 -24.3717 5.34215 + endloop + endfacet + facet normal 0.075645 -0.602029 -0.794883 + outer loop + vertex 246.24 -24.3717 5.34215 + vertex 236.522 -23.9289 4.08201 + vertex 246.942 -22.6155 4.07887 + endloop + endfacet + facet normal 0.0782844 -0.602593 -0.794199 + outer loop + vertex 246.24 -24.3717 5.34215 + vertex 246.942 -22.6155 4.07887 + vertex 256.655 -23.0132 5.33806 + endloop + endfacet + facet normal 0.079158 -0.596205 -0.79892 + outer loop + vertex 256.655 -23.0132 5.33806 + vertex 246.942 -22.6155 4.07887 + vertex 257.369 -21.2364 4.08283 + endloop + endfacet + facet normal 0.0556683 -0.418296 -0.906603 + outer loop + vertex 246.942 -22.6155 4.07887 + vertex 247.811 -20.2627 3.0467 + vertex 257.369 -21.2364 4.08283 + endloop + endfacet + facet normal 0.0532279 -0.434345 -0.899172 + outer loop + vertex 257.369 -21.2364 4.08283 + vertex 247.811 -20.2627 3.0467 + vertex 258.949 -19.1903 3.188 + endloop + endfacet + facet normal 0.0507915 -0.441273 -0.895934 + outer loop + vertex 215.447 -26.4313 4.08338 + vertex 217.041 -24.4228 3.18456 + vertex 226.025 -25.2067 4.07995 + endloop + endfacet + facet normal 0.0539249 -0.417884 -0.906898 + outer loop + vertex 226.025 -25.2067 4.07995 + vertex 217.041 -24.4228 3.18456 + vertex 226.894 -22.8622 3.05131 + endloop + endfacet + facet normal 0.0693347 -0.59992 -0.79705 + outer loop + vertex 214.685 -28.1904 5.34123 + vertex 215.447 -26.4313 4.08338 + vertex 225.28 -26.9648 5.34038 + endloop + endfacet + facet normal 0.0692527 -0.60047 -0.796643 + outer loop + vertex 225.28 -26.9648 5.34038 + vertex 215.447 -26.4313 4.08338 + vertex 226.025 -25.2067 4.07995 + endloop + endfacet + facet normal 0.0721931 -0.601157 -0.795863 + outer loop + vertex 225.28 -26.9648 5.34038 + vertex 226.025 -25.2067 4.07995 + vertex 235.792 -25.6992 5.33792 + endloop + endfacet + facet normal 0.0728144 -0.596887 -0.799015 + outer loop + vertex 235.792 -25.6992 5.33792 + vertex 226.025 -25.2067 4.07995 + vertex 236.522 -23.9289 4.08201 + endloop + endfacet + facet normal 0.0509419 -0.417027 -0.907465 + outer loop + vertex 226.025 -25.2067 4.07995 + vertex 226.894 -22.8622 3.05131 + vertex 236.522 -23.9289 4.08201 + endloop + endfacet + facet normal 0.0480995 -0.434756 -0.899263 + outer loop + vertex 236.522 -23.9289 4.08201 + vertex 226.894 -22.8622 3.05131 + vertex 238.072 -21.9052 3.18652 + endloop + endfacet + facet normal 0.0461809 -0.439973 -0.896823 + outer loop + vertex 194.122 -28.7406 4.08181 + vertex 195.738 -26.744 3.18548 + vertex 204.796 -27.6172 4.08029 + endloop + endfacet + facet normal 0.0493674 -0.417628 -0.907276 + outer loop + vertex 204.796 -27.6172 4.08029 + vertex 195.738 -26.744 3.18548 + vertex 205.705 -25.2772 3.05263 + endloop + endfacet + facet normal 0.0632091 -0.598537 -0.798597 + outer loop + vertex 193.362 -30.4967 5.33783 + vertex 194.122 -28.7406 4.08181 + vertex 204.035 -29.3718 5.33943 + endloop + endfacet + facet normal 0.0630145 -0.599774 -0.797684 + outer loop + vertex 204.035 -29.3718 5.33943 + vertex 194.122 -28.7406 4.08181 + vertex 204.796 -27.6172 4.08029 + endloop + endfacet + facet normal 0.0667666 -0.600689 -0.79669 + outer loop + vertex 204.035 -29.3718 5.33943 + vertex 204.796 -27.6172 4.08029 + vertex 214.685 -28.1904 5.34123 + endloop + endfacet + facet normal 0.0669708 -0.599348 -0.797682 + outer loop + vertex 214.685 -28.1904 5.34123 + vertex 204.796 -27.6172 4.08029 + vertex 215.447 -26.4313 4.08338 + endloop + endfacet + facet normal 0.0466767 -0.41681 -0.907794 + outer loop + vertex 204.796 -27.6172 4.08029 + vertex 205.705 -25.2772 3.05263 + vertex 215.447 -26.4313 4.08338 + endloop + endfacet + facet normal 0.0433639 -0.436579 -0.89862 + outer loop + vertex 215.447 -26.4313 4.08338 + vertex 205.705 -25.2772 3.05263 + vertex 217.041 -24.4228 3.18456 + endloop + endfacet + facet normal 0.0414764 -0.437969 -0.898033 + outer loop + vertex 172.669 -30.8261 4.07915 + vertex 174.299 -28.8426 3.18704 + vertex 183.419 -29.8116 4.08084 + endloop + endfacet + facet normal 0.0443735 -0.418917 -0.90694 + outer loop + vertex 183.419 -29.8116 4.08084 + vertex 174.299 -28.8426 3.18704 + vertex 184.328 -27.4841 3.05025 + endloop + endfacet + facet normal 0.0563626 -0.603786 -0.795151 + outer loop + vertex 171.915 -32.5588 5.34141 + vertex 172.669 -30.8261 4.07915 + vertex 182.667 -31.5536 5.34016 + endloop + endfacet + facet normal 0.05684 -0.600922 -0.797284 + outer loop + vertex 182.667 -31.5536 5.34016 + vertex 172.669 -30.8261 4.07915 + vertex 183.419 -29.8116 4.08084 + endloop + endfacet + facet normal 0.0592597 -0.601516 -0.79666 + outer loop + vertex 182.667 -31.5536 5.34016 + vertex 183.419 -29.8116 4.08084 + vertex 193.362 -30.4967 5.33783 + endloop + endfacet + facet normal 0.0598764 -0.597717 -0.799468 + outer loop + vertex 193.362 -30.4967 5.33783 + vertex 183.419 -29.8116 4.08084 + vertex 194.122 -28.7406 4.08181 + endloop + endfacet + facet normal 0.0419213 -0.418164 -0.907404 + outer loop + vertex 183.419 -29.8116 4.08084 + vertex 184.328 -27.4841 3.05025 + vertex 194.122 -28.7406 4.08181 + endloop + endfacet + facet normal 0.0388919 -0.435261 -0.899464 + outer loop + vertex 194.122 -28.7406 4.08181 + vertex 184.328 -27.4841 3.05025 + vertex 195.738 -26.744 3.18548 + endloop + endfacet + facet normal 0.0362107 -0.440277 -0.897131 + outer loop + vertex 151.042 -32.67 4.0823 + vertex 152.708 -30.7087 3.18701 + vertex 161.87 -31.7774 4.08132 + endloop + endfacet + facet normal 0.0396593 -0.41905 -0.907096 + outer loop + vertex 161.87 -31.7774 4.08132 + vertex 152.708 -30.7087 3.18701 + vertex 162.814 -29.4589 3.05151 + endloop + endfacet + facet normal 0.0496942 -0.601117 -0.797615 + outer loop + vertex 150.257 -34.4033 5.33977 + vertex 151.042 -32.67 4.0823 + vertex 161.102 -33.509 5.34144 + endloop + endfacet + facet normal 0.0495466 -0.601953 -0.796993 + outer loop + vertex 161.102 -33.509 5.34144 + vertex 151.042 -32.67 4.0823 + vertex 161.87 -31.7774 4.08132 + endloop + endfacet + facet normal 0.0529701 -0.602829 -0.79611 + outer loop + vertex 161.102 -33.509 5.34144 + vertex 161.87 -31.7774 4.08132 + vertex 171.915 -32.5588 5.34141 + endloop + endfacet + facet normal 0.0529511 -0.60294 -0.796027 + outer loop + vertex 171.915 -32.5588 5.34141 + vertex 161.87 -31.7774 4.08132 + vertex 172.669 -30.8261 4.07915 + endloop + endfacet + facet normal 0.0366448 -0.418079 -0.907671 + outer loop + vertex 161.87 -31.7774 4.08132 + vertex 162.814 -29.4589 3.05151 + vertex 172.669 -30.8261 4.07915 + endloop + endfacet + facet normal 0.0338633 -0.432951 -0.900781 + outer loop + vertex 172.669 -30.8261 4.07915 + vertex 162.814 -29.4589 3.05151 + vertex 174.299 -28.8426 3.18704 + endloop + endfacet + facet normal 0.031704 -0.439826 -0.897523 + outer loop + vertex 129.483 -34.2679 4.07796 + vertex 131.146 -32.3234 3.18384 + vertex 140.23 -33.5014 4.08199 + endloop + endfacet + facet normal 0.0350737 -0.420702 -0.906521 + outer loop + vertex 140.23 -33.5014 4.08199 + vertex 131.146 -32.3234 3.18384 + vertex 141.215 -31.1934 3.04899 + endloop + endfacet + facet normal 0.04287 -0.60506 -0.795025 + outer loop + vertex 128.72 -35.9809 5.34051 + vertex 129.483 -34.2679 4.07796 + vertex 139.456 -35.2226 5.34229 + endloop + endfacet + facet normal 0.0432922 -0.602845 -0.796683 + outer loop + vertex 139.456 -35.2226 5.34229 + vertex 129.483 -34.2679 4.07796 + vertex 140.23 -33.5014 4.08199 + endloop + endfacet + facet normal 0.0455823 -0.603448 -0.796099 + outer loop + vertex 139.456 -35.2226 5.34229 + vertex 140.23 -33.5014 4.08199 + vertex 150.257 -34.4033 5.33977 + endloop + endfacet + facet normal 0.0461799 -0.600187 -0.798525 + outer loop + vertex 150.257 -34.4033 5.33977 + vertex 140.23 -33.5014 4.08199 + vertex 151.042 -32.67 4.0823 + endloop + endfacet + facet normal 0.0323074 -0.419762 -0.907059 + outer loop + vertex 140.23 -33.5014 4.08199 + vertex 141.215 -31.1934 3.04899 + vertex 151.042 -32.67 4.0823 + endloop + endfacet + facet normal 0.0291737 -0.435483 -0.899724 + outer loop + vertex 151.042 -32.67 4.0823 + vertex 141.215 -31.1934 3.04899 + vertex 152.708 -30.7087 3.18701 + endloop + endfacet + facet normal 0.0260794 -0.436973 -0.899096 + outer loop + vertex 108.202 -35.5766 4.07828 + vertex 109.829 -33.6505 3.18935 + vertex 118.83 -34.9499 4.08197 + endloop + endfacet + facet normal 0.0291948 -0.42065 -0.906753 + outer loop + vertex 118.83 -34.9499 4.08197 + vertex 109.829 -33.6505 3.18935 + vertex 119.781 -32.6568 3.04881 + endloop + endfacet + facet normal 0.0349673 -0.606532 -0.79429 + outer loop + vertex 107.448 -37.2756 5.34247 + vertex 108.202 -35.5766 4.07828 + vertex 118.065 -36.6623 5.34149 + endloop + endfacet + facet normal 0.0358031 -0.602478 -0.797332 + outer loop + vertex 118.065 -36.6623 5.34149 + vertex 108.202 -35.5766 4.07828 + vertex 118.83 -34.9499 4.08197 + endloop + endfacet + facet normal 0.0384983 -0.603193 -0.796665 + outer loop + vertex 118.065 -36.6623 5.34149 + vertex 118.83 -34.9499 4.08197 + vertex 128.72 -35.9809 5.34051 + endloop + endfacet + facet normal 0.0383613 -0.603881 -0.796151 + outer loop + vertex 128.72 -35.9809 5.34051 + vertex 118.83 -34.9499 4.08197 + vertex 129.483 -34.2679 4.07796 + endloop + endfacet + facet normal 0.0265321 -0.419768 -0.907244 + outer loop + vertex 118.83 -34.9499 4.08197 + vertex 119.781 -32.6568 3.04881 + vertex 129.483 -34.2679 4.07796 + endloop + endfacet + facet normal 0.0234346 -0.434139 -0.900541 + outer loop + vertex 129.483 -34.2679 4.07796 + vertex 119.781 -32.6568 3.04881 + vertex 131.146 -32.3234 3.18384 + endloop + endfacet + facet normal 0.0202355 -0.440577 -0.897487 + outer loop + vertex 86.9154 -36.6154 4.08228 + vertex 88.5293 -34.7173 3.18693 + vertex 97.5866 -36.125 4.08216 + endloop + endfacet + facet normal 0.0240439 -0.42174 -0.906398 + outer loop + vertex 97.5866 -36.125 4.08216 + vertex 88.5293 -34.7173 3.18693 + vertex 98.4941 -33.8479 3.04672 + endloop + endfacet + facet normal 0.0275765 -0.602042 -0.797988 + outer loop + vertex 86.1462 -38.3181 5.3403 + vertex 86.9154 -36.6154 4.08228 + vertex 96.8205 -37.8296 5.34066 + endloop + endfacet + facet normal 0.0276425 -0.601738 -0.798215 + outer loop + vertex 96.8205 -37.8296 5.34066 + vertex 86.9154 -36.6154 4.08228 + vertex 97.5866 -36.125 4.08216 + endloop + endfacet + facet normal 0.03156 -0.6028 -0.797268 + outer loop + vertex 96.8205 -37.8296 5.34066 + vertex 97.5866 -36.125 4.08216 + vertex 107.448 -37.2756 5.34247 + endloop + endfacet + facet normal 0.0309896 -0.605483 -0.795255 + outer loop + vertex 107.448 -37.2756 5.34247 + vertex 97.5866 -36.125 4.08216 + vertex 108.202 -35.5766 4.07828 + endloop + endfacet + facet normal 0.0214127 -0.420899 -0.906855 + outer loop + vertex 97.5866 -36.125 4.08216 + vertex 98.4941 -33.8479 3.04672 + vertex 108.202 -35.5766 4.07828 + endloop + endfacet + facet normal 0.0188712 -0.432064 -0.901646 + outer loop + vertex 108.202 -35.5766 4.07828 + vertex 98.4941 -33.8479 3.04672 + vertex 109.829 -33.6505 3.18935 + endloop + endfacet + facet normal 0.0150758 -0.439295 -0.898216 + outer loop + vertex 65.295 -37.4188 4.07992 + vertex 66.9653 -35.5352 3.18674 + vertex 76.1561 -37.0482 4.08096 + endloop + endfacet + facet normal 0.019145 -0.419967 -0.907337 + outer loop + vertex 76.1561 -37.0482 4.08096 + vertex 66.9653 -35.5352 3.18674 + vertex 77.0771 -34.7772 3.04926 + endloop + endfacet + facet normal 0.0199332 -0.60427 -0.79653 + outer loop + vertex 64.5015 -39.1076 5.3413 + vertex 65.295 -37.4188 4.07992 + vertex 75.3762 -38.7463 5.33932 + endloop + endfacet + facet normal 0.0205951 -0.601333 -0.798733 + outer loop + vertex 75.3762 -38.7463 5.33932 + vertex 65.295 -37.4188 4.07992 + vertex 76.1561 -37.0482 4.08096 + endloop + endfacet + facet normal 0.0240215 -0.602297 -0.797911 + outer loop + vertex 75.3762 -38.7463 5.33932 + vertex 76.1561 -37.0482 4.08096 + vertex 86.1462 -38.3181 5.3403 + endloop + endfacet + facet normal 0.0242785 -0.601136 -0.798778 + outer loop + vertex 86.1462 -38.3181 5.3403 + vertex 76.1561 -37.0482 4.08096 + vertex 86.9154 -36.6154 4.08228 + endloop + endfacet + facet normal 0.0169757 -0.419257 -0.907709 + outer loop + vertex 76.1561 -37.0482 4.08096 + vertex 77.0771 -34.7772 3.04926 + vertex 86.9154 -36.6154 4.08228 + endloop + endfacet + facet normal 0.0130957 -0.435692 -0.900001 + outer loop + vertex 86.9154 -36.6154 4.08228 + vertex 77.0771 -34.7772 3.04926 + vertex 88.5293 -34.7173 3.18693 + endloop + endfacet + facet normal 0.0100559 -0.438491 -0.898679 + outer loop + vertex 43.4766 -37.9765 4.08102 + vertex 45.1818 -36.1106 3.18966 + vertex 54.3691 -37.727 4.08116 + endloop + endfacet + facet normal 0.0140597 -0.42044 -0.907211 + outer loop + vertex 54.3691 -37.727 4.08116 + vertex 45.1818 -36.1106 3.18966 + vertex 55.3747 -35.4664 3.04907 + endloop + endfacet + facet normal 0.0137413 -0.601218 -0.798967 + outer loop + vertex 42.6821 -39.6658 5.3385 + vertex 43.4766 -37.9765 4.08102 + vertex 53.5642 -39.4183 5.33946 + endloop + endfacet + facet normal 0.0137783 -0.601062 -0.799084 + outer loop + vertex 53.5642 -39.4183 5.33946 + vertex 43.4766 -37.9765 4.08102 + vertex 54.3691 -37.727 4.08116 + endloop + endfacet + facet normal 0.0172359 -0.602084 -0.798246 + outer loop + vertex 53.5642 -39.4183 5.33946 + vertex 54.3691 -37.727 4.08116 + vertex 64.5015 -39.1076 5.3413 + endloop + endfacet + facet normal 0.0169331 -0.603403 -0.797257 + outer loop + vertex 64.5015 -39.1076 5.3413 + vertex 54.3691 -37.727 4.08116 + vertex 65.295 -37.4188 4.07992 + endloop + endfacet + facet normal 0.0117348 -0.419599 -0.907634 + outer loop + vertex 54.3691 -37.727 4.08116 + vertex 55.3747 -35.4664 3.04907 + vertex 65.295 -37.4188 4.07992 + endloop + endfacet + facet normal 0.00812034 -0.434316 -0.900724 + outer loop + vertex 65.295 -37.4188 4.07992 + vertex 55.3747 -35.4664 3.04907 + vertex 66.9653 -35.5352 3.18674 + endloop + endfacet + facet normal 0.00581403 -0.439164 -0.898388 + outer loop + vertex 22.0632 -38.3014 4.07934 + vertex 23.6993 -36.4537 3.18674 + vertex 32.7088 -38.1655 4.0818 + endloop + endfacet + facet normal 0.00997221 -0.421631 -0.906712 + outer loop + vertex 32.7088 -38.1655 4.0818 + vertex 23.6993 -36.4537 3.18674 + vertex 33.7029 -35.9186 3.04791 + endloop + endfacet + facet normal 0.00677077 -0.605993 -0.795441 + outer loop + vertex 21.3267 -39.9689 5.34343 + vertex 22.0632 -38.3014 4.07934 + vertex 31.9457 -39.8463 5.34041 + endloop + endfacet + facet normal 0.00786536 -0.601662 -0.798712 + outer loop + vertex 31.9457 -39.8463 5.34041 + vertex 22.0632 -38.3014 4.07934 + vertex 32.7088 -38.1655 4.0818 + endloop + endfacet + facet normal 0.00998388 -0.602265 -0.798234 + outer loop + vertex 31.9457 -39.8463 5.34041 + vertex 32.7088 -38.1655 4.0818 + vertex 42.6821 -39.6658 5.3385 + endloop + endfacet + facet normal 0.0104756 -0.600257 -0.799739 + outer loop + vertex 42.6821 -39.6658 5.3385 + vertex 32.7088 -38.1655 4.0818 + vertex 43.4766 -37.9765 4.08102 + endloop + endfacet + facet normal 0.00731621 -0.420673 -0.907183 + outer loop + vertex 32.7088 -38.1655 4.0818 + vertex 33.7029 -35.9186 3.04791 + vertex 43.4766 -37.9765 4.08102 + endloop + endfacet + facet normal 0.00386793 -0.433918 -0.900944 + outer loop + vertex 43.4766 -37.9765 4.08102 + vertex 33.7029 -35.9186 3.04791 + vertex 45.1818 -36.1106 3.18966 + endloop + endfacet + facet normal 0.000812861 -0.443771 -0.89614 + outer loop + vertex 0.836247 -38.4003 4.08313 + vertex 2.47798 -36.5798 3.1831 + vertex 11.4733 -38.3771 4.08128 + endloop + endfacet + facet normal 0.00658573 -0.420451 -0.907291 + outer loop + vertex 11.4733 -38.3771 4.08128 + vertex 2.47798 -36.5798 3.1831 + vertex 12.4078 -36.1396 3.05119 + endloop + endfacet + facet normal 0.00102911 -0.602352 -0.79823 + outer loop + vertex 0.0367514 -40.0689 5.34125 + vertex 0.836247 -38.4003 4.08313 + vertex 10.7069 -40.0487 5.33977 + endloop + endfacet + facet normal 0.00117471 -0.601799 -0.798647 + outer loop + vertex 10.7069 -40.0487 5.33977 + vertex 0.836247 -38.4003 4.08313 + vertex 11.4733 -38.3771 4.08128 + endloop + endfacet + facet normal 0.00480688 -0.602854 -0.797837 + outer loop + vertex 10.7069 -40.0487 5.33977 + vertex 11.4733 -38.3771 4.08128 + vertex 21.3267 -39.9689 5.34343 + endloop + endfacet + facet normal 0.00418076 -0.605277 -0.796004 + outer loop + vertex 21.3267 -39.9689 5.34343 + vertex 11.4733 -38.3771 4.08128 + vertex 22.0632 -38.3014 4.07934 + endloop + endfacet + facet normal 0.00282989 -0.419165 -0.907906 + outer loop + vertex 11.4733 -38.3771 4.08128 + vertex 12.4078 -36.1396 3.05119 + vertex 22.0632 -38.3014 4.07934 + endloop + endfacet + facet normal -0.00126246 -0.434095 -0.900866 + outer loop + vertex 22.0632 -38.3014 4.07934 + vertex 12.4078 -36.1396 3.05119 + vertex 23.6993 -36.4537 3.18674 + endloop + endfacet + facet normal -0.00300086 -0.440666 -0.897666 + outer loop + vertex -20.5059 -38.3122 4.08079 + vertex -18.8411 -36.4995 3.1854 + vertex -9.85727 -38.3831 4.08002 + endloop + endfacet + facet normal 0.00223074 -0.420324 -0.907372 + outer loop + vertex -9.85727 -38.3831 4.08002 + vertex -18.8411 -36.4995 3.1854 + vertex -8.8623 -36.1543 3.05003 + endloop + endfacet + facet normal -0.00434166 -0.602974 -0.797749 + outer loop + vertex -21.2921 -39.973 5.34041 + vertex -20.5059 -38.3122 4.08079 + vertex -10.6663 -40.0481 5.33932 + endloop + endfacet + facet normal -0.00406838 -0.601973 -0.798506 + outer loop + vertex -10.6663 -40.0481 5.33932 + vertex -20.5059 -38.3122 4.08079 + vertex -9.85727 -38.3831 4.08002 + endloop + endfacet + facet normal -0.00102909 -0.602918 -0.797802 + outer loop + vertex -10.6663 -40.0481 5.33932 + vertex -9.85727 -38.3831 4.08002 + vertex 0.0367514 -40.0689 5.34125 + endloop + endfacet + facet normal -0.000734606 -0.601814 -0.798636 + outer loop + vertex 0.0367514 -40.0689 5.34125 + vertex -9.85727 -38.3831 4.08002 + vertex 0.836247 -38.4003 4.08313 + endloop + endfacet + facet normal -0.000409775 -0.419353 -0.907823 + outer loop + vertex -9.85727 -38.3831 4.08002 + vertex -8.8623 -36.1543 3.05003 + vertex 0.836247 -38.4003 4.08313 + endloop + endfacet + facet normal -0.00592144 -0.438878 -0.898527 + outer loop + vertex 0.836247 -38.4003 4.08313 + vertex -8.8623 -36.1543 3.05003 + vertex 2.47798 -36.5798 3.1831 + endloop + endfacet + facet normal -0.00733548 -0.440939 -0.897507 + outer loop + vertex -41.6084 -38.0199 4.08038 + vertex -40.0216 -36.2217 3.18398 + vertex -31.0674 -38.1945 4.08 + endloop + endfacet + facet normal -0.00165009 -0.419738 -0.907644 + outer loop + vertex -31.0674 -38.1945 4.08 + vertex -40.0216 -36.2217 3.18398 + vertex -30.1343 -35.9708 3.04999 + endloop + endfacet + facet normal -0.0102867 -0.605175 -0.796026 + outer loop + vertex -42.3457 -39.6675 5.34252 + vertex -41.6084 -38.0199 4.08038 + vertex -31.8174 -39.8466 5.3426 + endloop + endfacet + facet normal -0.0100373 -0.6043 -0.796694 + outer loop + vertex -31.8174 -39.8466 5.3426 + vertex -41.6084 -38.0199 4.08038 + vertex -31.0674 -38.1945 4.08 + endloop + endfacet + facet normal -0.00743308 -0.605061 -0.796144 + outer loop + vertex -31.8174 -39.8466 5.3426 + vertex -31.0674 -38.1945 4.08 + vertex -21.2921 -39.973 5.34041 + endloop + endfacet + facet normal -0.00665202 -0.602271 -0.798264 + outer loop + vertex -21.2921 -39.973 5.34041 + vertex -31.0674 -38.1945 4.08 + vertex -20.5059 -38.3122 4.08079 + endloop + endfacet + facet normal -0.00459814 -0.418715 -0.908106 + outer loop + vertex -31.0674 -38.1945 4.08 + vertex -30.1343 -35.9708 3.04999 + vertex -20.5059 -38.3122 4.08079 + endloop + endfacet + facet normal -0.00960857 -0.435757 -0.900013 + outer loop + vertex -20.5059 -38.3122 4.08079 + vertex -30.1343 -35.9708 3.04999 + vertex -18.8411 -36.4995 3.1854 + endloop + endfacet + facet normal -0.0121427 -0.443388 -0.896247 + outer loop + vertex -63.1296 -37.4809 4.08221 + vertex -61.4472 -35.7092 3.18291 + vertex -52.2603 -37.7808 4.08327 + endloop + endfacet + facet normal -0.00630771 -0.422 -0.906574 + outer loop + vertex -52.2603 -37.7808 4.08327 + vertex -61.4472 -35.7092 3.18291 + vertex -51.3698 -35.5715 3.0487 + endloop + endfacet + facet normal -0.0172386 -0.602548 -0.797897 + outer loop + vertex -63.9568 -39.1233 5.34038 + vertex -63.1296 -37.4809 4.08221 + vertex -53.0357 -39.4339 5.33896 + endloop + endfacet + facet normal -0.0164686 -0.599873 -0.799926 + outer loop + vertex -53.0357 -39.4339 5.33896 + vertex -63.1296 -37.4809 4.08221 + vertex -52.2603 -37.7808 4.08327 + endloop + endfacet + facet normal -0.0128673 -0.600981 -0.79916 + outer loop + vertex -53.0357 -39.4339 5.33896 + vertex -52.2603 -37.7808 4.08327 + vertex -42.3457 -39.6675 5.34252 + endloop + endfacet + facet normal -0.0137794 -0.604161 -0.796743 + outer loop + vertex -42.3457 -39.6675 5.34252 + vertex -52.2603 -37.7808 4.08327 + vertex -41.6084 -38.0199 4.08038 + endloop + endfacet + facet normal -0.00969448 -0.420867 -0.907071 + outer loop + vertex -52.2603 -37.7808 4.08327 + vertex -51.3698 -35.5715 3.0487 + vertex -41.6084 -38.0199 4.08038 + endloop + endfacet + facet normal -0.0142536 -0.435995 -0.899836 + outer loop + vertex -41.6084 -38.0199 4.08038 + vertex -51.3698 -35.5715 3.0487 + vertex -40.0216 -36.2217 3.18398 + endloop + endfacet + facet normal -0.0172348 -0.440711 -0.897483 + outer loop + vertex -85.1277 -36.6895 4.0824 + vertex -83.3561 -34.9358 3.18719 + vertex -74.1588 -37.1165 4.08141 + endloop + endfacet + facet normal -0.0113568 -0.420007 -0.90745 + outer loop + vertex -74.1588 -37.1165 4.08141 + vertex -83.3561 -34.9358 3.18719 + vertex -73.0858 -34.92 3.05135 + endloop + endfacet + facet normal -0.0238633 -0.60331 -0.79715 + outer loop + vertex -85.9585 -38.3206 5.34171 + vertex -85.1277 -36.6895 4.0824 + vertex -75.0098 -38.752 5.34047 + endloop + endfacet + facet normal -0.0235082 -0.602122 -0.798058 + outer loop + vertex -75.0098 -38.752 5.34047 + vertex -85.1277 -36.6895 4.0824 + vertex -74.1588 -37.1165 4.08141 + endloop + endfacet + facet normal -0.0202724 -0.60323 -0.79731 + outer loop + vertex -75.0098 -38.752 5.34047 + vertex -74.1588 -37.1165 4.08141 + vertex -63.9568 -39.1233 5.34038 + endloop + endfacet + facet normal -0.0198254 -0.601693 -0.798482 + outer loop + vertex -63.9568 -39.1233 5.34038 + vertex -74.1588 -37.1165 4.08141 + vertex -63.1296 -37.4809 4.08221 + endloop + endfacet + facet normal -0.0137809 -0.419021 -0.907872 + outer loop + vertex -74.1588 -37.1165 4.08141 + vertex -73.0858 -34.92 3.05135 + vertex -63.1296 -37.4809 4.08221 + endloop + endfacet + facet normal -0.0195215 -0.437726 -0.898896 + outer loop + vertex -63.1296 -37.4809 4.08221 + vertex -73.0858 -34.92 3.05135 + vertex -61.4472 -35.7092 3.18291 + endloop + endfacet + facet normal -0.0219769 -0.440382 -0.897541 + outer loop + vertex -106.353 -35.6817 4.07886 + vertex -104.752 -33.9375 3.18386 + vertex -95.865 -36.2118 4.08216 + endloop + endfacet + facet normal -0.016046 -0.420925 -0.906954 + outer loop + vertex -95.865 -36.2118 4.08216 + vertex -104.752 -33.9375 3.18386 + vertex -94.8208 -34.0257 3.04909 + endloop + endfacet + facet normal -0.0302413 -0.602515 -0.797534 + outer loop + vertex -107.075 -37.312 5.33793 + vertex -106.353 -35.6817 4.07886 + vertex -96.6361 -37.8406 5.34143 + endloop + endfacet + facet normal -0.030196 -0.602374 -0.797642 + outer loop + vertex -96.6361 -37.8406 5.34143 + vertex -106.353 -35.6817 4.07886 + vertex -95.865 -36.2118 4.08216 + endloop + endfacet + facet normal -0.0271016 -0.603353 -0.797013 + outer loop + vertex -96.6361 -37.8406 5.34143 + vertex -95.865 -36.2118 4.08216 + vertex -85.9585 -38.3206 5.34171 + endloop + endfacet + facet normal -0.0267828 -0.602326 -0.797801 + outer loop + vertex -85.9585 -38.3206 5.34171 + vertex -95.865 -36.2118 4.08216 + vertex -85.1277 -36.6895 4.0824 + endloop + endfacet + facet normal -0.0186621 -0.41988 -0.907388 + outer loop + vertex -95.865 -36.2118 4.08216 + vertex -94.8208 -34.0257 3.04909 + vertex -85.1277 -36.6895 4.0824 + endloop + endfacet + facet normal -0.0237235 -0.435402 -0.899923 + outer loop + vertex -85.1277 -36.6895 4.0824 + vertex -94.8208 -34.0257 3.04909 + vertex -83.3561 -34.9358 3.18719 + endloop + endfacet + facet normal -0.0275678 -0.441344 -0.896915 + outer loop + vertex -127.35 -34.4055 4.0794 + vertex -125.749 -32.6838 3.18299 + vertex -116.753 -35.0767 4.08393 + endloop + endfacet + facet normal -0.021416 -0.4218 -0.906436 + outer loop + vertex -116.753 -35.0767 4.08393 + vertex -125.749 -32.6838 3.18299 + vertex -115.905 -32.8952 3.04879 + endloop + endfacet + facet normal -0.0393274 -0.606144 -0.794382 + outer loop + vertex -128.14 -36.0108 5.34338 + vertex -127.35 -34.4055 4.0794 + vertex -117.491 -36.6994 5.34157 + endloop + endfacet + facet normal -0.0377449 -0.601374 -0.798076 + outer loop + vertex -117.491 -36.6994 5.34157 + vertex -127.35 -34.4055 4.0794 + vertex -116.753 -35.0767 4.08393 + endloop + endfacet + facet normal -0.0356899 -0.60201 -0.797691 + outer loop + vertex -117.491 -36.6994 5.34157 + vertex -116.753 -35.0767 4.08393 + vertex -107.075 -37.312 5.33793 + endloop + endfacet + facet normal -0.0353506 -0.600983 -0.798479 + outer loop + vertex -107.075 -37.312 5.33793 + vertex -116.753 -35.0767 4.08393 + vertex -106.353 -35.6817 4.07886 + endloop + endfacet + facet normal -0.0249129 -0.420653 -0.90688 + outer loop + vertex -116.753 -35.0767 4.08393 + vertex -115.905 -32.8952 3.04879 + vertex -106.353 -35.6817 4.07886 + endloop + endfacet + facet normal -0.0297119 -0.434609 -0.900129 + outer loop + vertex -106.353 -35.6817 4.07886 + vertex -115.905 -32.8952 3.04879 + vertex -104.752 -33.9375 3.18386 + endloop + endfacet + facet normal -0.0336106 -0.440386 -0.897179 + outer loop + vertex -149.186 -32.8134 4.08298 + vertex -147.431 -31.1214 3.18672 + vertex -138.212 -33.6454 4.08027 + endloop + endfacet + facet normal -0.0267076 -0.418879 -0.907649 + outer loop + vertex -138.212 -33.6454 4.08027 + vertex -147.431 -31.1214 3.18672 + vertex -137.223 -31.4784 3.05109 + endloop + endfacet + facet normal -0.0463135 -0.602366 -0.796876 + outer loop + vertex -150.029 -34.4148 5.34253 + vertex -149.186 -32.8134 4.08298 + vertex -139.057 -35.2537 5.33896 + endloop + endfacet + facet normal -0.0457374 -0.600655 -0.798199 + outer loop + vertex -139.057 -35.2537 5.33896 + vertex -149.186 -32.8134 4.08298 + vertex -138.212 -33.6454 4.08027 + endloop + endfacet + facet normal -0.0414384 -0.602192 -0.797275 + outer loop + vertex -139.057 -35.2537 5.33896 + vertex -138.212 -33.6454 4.08027 + vertex -128.14 -36.0108 5.34338 + endloop + endfacet + facet normal -0.0424101 -0.605118 -0.795005 + outer loop + vertex -128.14 -36.0108 5.34338 + vertex -138.212 -33.6454 4.08027 + vertex -127.35 -34.4055 4.0794 + endloop + endfacet + facet normal -0.0293154 -0.417871 -0.908033 + outer loop + vertex -138.212 -33.6454 4.08027 + vertex -137.223 -31.4784 3.05109 + vertex -127.35 -34.4055 4.0794 + endloop + endfacet + facet normal -0.0354032 -0.435418 -0.899532 + outer loop + vertex -127.35 -34.4055 4.0794 + vertex -137.223 -31.4784 3.05109 + vertex -125.749 -32.6838 3.18299 + endloop + endfacet + facet normal -0.0389309 -0.439508 -0.897395 + outer loop + vertex -170.737 -31.0014 4.08204 + vertex -169.072 -29.3208 3.18671 + vertex -160.077 -31.9377 4.07815 + endloop + endfacet + facet normal -0.0320126 -0.419123 -0.907365 + outer loop + vertex -160.077 -31.9377 4.07815 + vertex -169.072 -29.3208 3.18671 + vertex -159.004 -29.7864 3.04658 + endloop + endfacet + facet normal -0.0519953 -0.599812 -0.79845 + outer loop + vertex -171.495 -32.6084 5.33859 + vertex -170.737 -31.0014 4.08204 + vertex -160.861 -33.534 5.34145 + endloop + endfacet + facet normal -0.0532943 -0.603464 -0.795608 + outer loop + vertex -160.861 -33.534 5.34145 + vertex -170.737 -31.0014 4.08204 + vertex -160.077 -31.9377 4.07815 + endloop + endfacet + facet normal -0.0491068 -0.604882 -0.7948 + outer loop + vertex -160.861 -33.534 5.34145 + vertex -160.077 -31.9377 4.07815 + vertex -150.029 -34.4148 5.34253 + endloop + endfacet + facet normal -0.0480276 -0.601749 -0.79724 + outer loop + vertex -150.029 -34.4148 5.34253 + vertex -160.077 -31.9377 4.07815 + vertex -149.186 -32.8134 4.08298 + endloop + endfacet + facet normal -0.0332531 -0.418599 -0.907562 + outer loop + vertex -160.077 -31.9377 4.07815 + vertex -159.004 -29.7864 3.04658 + vertex -149.186 -32.8134 4.08298 + endloop + endfacet + facet normal -0.0393524 -0.435554 -0.899302 + outer loop + vertex -149.186 -32.8134 4.08298 + vertex -159.004 -29.7864 3.04658 + vertex -147.431 -31.1214 3.18672 + endloop + endfacet + facet normal -0.0442298 -0.442936 -0.895462 + outer loop + vertex -191.909 -28.9627 4.0831 + vertex -190.248 -27.3087 3.18289 + vertex -181.297 -30.0183 4.08108 + endloop + endfacet + facet normal -0.0358421 -0.419126 -0.90722 + outer loop + vertex -181.297 -30.0183 4.08108 + vertex -190.248 -27.3087 3.18289 + vertex -180.34 -27.8712 3.05135 + endloop + endfacet + facet normal -0.059887 -0.600665 -0.797255 + outer loop + vertex -192.73 -30.55 5.34069 + vertex -191.909 -28.9627 4.0831 + vertex -182.061 -31.6131 5.34025 + endloop + endfacet + facet normal -0.0599054 -0.600715 -0.797216 + outer loop + vertex -182.061 -31.6131 5.34025 + vertex -191.909 -28.9627 4.0831 + vertex -181.297 -30.0183 4.08108 + endloop + endfacet + facet normal -0.0568081 -0.601757 -0.796656 + outer loop + vertex -182.061 -31.6131 5.34025 + vertex -181.297 -30.0183 4.08108 + vertex -171.495 -32.6084 5.33859 + endloop + endfacet + facet normal -0.0556591 -0.598601 -0.799111 + outer loop + vertex -171.495 -32.6084 5.33859 + vertex -181.297 -30.0183 4.08108 + vertex -170.737 -31.0014 4.08204 + endloop + endfacet + facet normal -0.0388332 -0.417986 -0.907623 + outer loop + vertex -181.297 -30.0183 4.08108 + vertex -180.34 -27.8712 3.05135 + vertex -170.737 -31.0014 4.08204 + endloop + endfacet + facet normal -0.0450969 -0.434535 -0.899525 + outer loop + vertex -170.737 -31.0014 4.08204 + vertex -180.34 -27.8712 3.05135 + vertex -169.072 -29.3208 3.18671 + endloop + endfacet + facet normal -0.0484542 -0.441265 -0.896068 + outer loop + vertex -213.316 -26.6764 4.08111 + vertex -211.586 -25.042 3.18271 + vertex -202.634 -27.8477 4.08026 + endloop + endfacet + facet normal -0.0405628 -0.41953 -0.906835 + outer loop + vertex -202.634 -27.8477 4.08026 + vertex -211.586 -25.042 3.18271 + vertex -201.573 -25.7225 3.04965 + endloop + endfacet + facet normal -0.0653235 -0.60093 -0.796628 + outer loop + vertex -214.155 -28.2537 5.33974 + vertex -213.316 -26.6764 4.08111 + vertex -203.477 -29.4195 5.34354 + endloop + endfacet + facet normal -0.066208 -0.603259 -0.794793 + outer loop + vertex -203.477 -29.4195 5.34354 + vertex -213.316 -26.6764 4.08111 + vertex -202.634 -27.8477 4.08026 + endloop + endfacet + facet normal -0.063766 -0.604171 -0.794299 + outer loop + vertex -203.477 -29.4195 5.34354 + vertex -202.634 -27.8477 4.08026 + vertex -192.73 -30.55 5.34069 + endloop + endfacet + facet normal -0.0621526 -0.599844 -0.797699 + outer loop + vertex -192.73 -30.55 5.34069 + vertex -202.634 -27.8477 4.08026 + vertex -191.909 -28.9627 4.0831 + endloop + endfacet + facet normal -0.0432576 -0.418382 -0.90724 + outer loop + vertex -202.634 -27.8477 4.08026 + vertex -201.573 -25.7225 3.04965 + vertex -191.909 -28.9627 4.0831 + endloop + endfacet + facet normal -0.050731 -0.437636 -0.89772 + outer loop + vertex -191.909 -28.9627 4.0831 + vertex -201.573 -25.7225 3.04965 + vertex -190.248 -27.3087 3.18289 + endloop + endfacet + facet normal -0.052342 -0.437808 -0.897544 + outer loop + vertex -234.206 -24.2249 4.07881 + vertex -232.607 -22.5842 3.1853 + vertex -223.828 -25.4703 4.08111 + endloop + endfacet + facet normal -0.0452027 -0.418985 -0.906867 + outer loop + vertex -223.828 -25.4703 4.08111 + vertex -232.607 -22.5842 3.1853 + vertex -222.816 -23.3477 3.04998 + endloop + endfacet + facet normal -0.0715715 -0.600759 -0.79622 + outer loop + vertex -234.957 -25.8052 5.33872 + vertex -234.206 -24.2249 4.07881 + vertex -224.61 -27.0441 5.34342 + endloop + endfacet + facet normal -0.0720708 -0.602013 -0.795227 + outer loop + vertex -224.61 -27.0441 5.34342 + vertex -234.206 -24.2249 4.07881 + vertex -223.828 -25.4703 4.08111 + endloop + endfacet + facet normal -0.0700144 -0.60274 -0.79486 + outer loop + vertex -224.61 -27.0441 5.34342 + vertex -223.828 -25.4703 4.08111 + vertex -214.155 -28.2537 5.33974 + endloop + endfacet + facet normal -0.0687999 -0.59963 -0.797315 + outer loop + vertex -214.155 -28.2537 5.33974 + vertex -223.828 -25.4703 4.08111 + vertex -213.316 -26.6764 4.08111 + endloop + endfacet + facet normal -0.0479441 -0.417861 -0.907245 + outer loop + vertex -223.828 -25.4703 4.08111 + vertex -222.816 -23.3477 3.04998 + vertex -213.316 -26.6764 4.08111 + endloop + endfacet + facet normal -0.0550964 -0.435555 -0.898474 + outer loop + vertex -213.316 -26.6764 4.08111 + vertex -222.816 -23.3477 3.04998 + vertex -211.586 -25.042 3.18271 + endloop + endfacet + facet normal -0.0579603 -0.438252 -0.896981 + outer loop + vertex -255.306 -21.5055 4.08323 + vertex -253.657 -19.8913 3.18802 + vertex -244.624 -22.9119 4.08009 + endloop + endfacet + facet normal -0.0502868 -0.418244 -0.906941 + outer loop + vertex -244.624 -22.9119 4.08009 + vertex -253.657 -19.8913 3.18802 + vertex -243.753 -20.7803 3.04882 + endloop + endfacet + facet normal -0.0776125 -0.596654 -0.798737 + outer loop + vertex -256.143 -23.0767 5.33816 + vertex -255.306 -21.5055 4.08323 + vertex -245.398 -24.4799 5.34234 + endloop + endfacet + facet normal -0.0793577 -0.601009 -0.795292 + outer loop + vertex -245.398 -24.4799 5.34234 + vertex -255.306 -21.5055 4.08323 + vertex -244.624 -22.9119 4.08009 + endloop + endfacet + facet normal -0.0766804 -0.601963 -0.794834 + outer loop + vertex -245.398 -24.4799 5.34234 + vertex -244.624 -22.9119 4.08009 + vertex -234.957 -25.8052 5.33872 + endloop + endfacet + facet normal -0.0756347 -0.599365 -0.796895 + outer loop + vertex -234.957 -25.8052 5.33872 + vertex -244.624 -22.9119 4.08009 + vertex -234.206 -24.2249 4.07881 + endloop + endfacet + facet normal -0.0527129 -0.41738 -0.907202 + outer loop + vertex -244.624 -22.9119 4.08009 + vertex -243.753 -20.7803 3.04882 + vertex -234.206 -24.2249 4.07881 + endloop + endfacet + facet normal -0.0589817 -0.432511 -0.899697 + outer loop + vertex -234.206 -24.2249 4.07881 + vertex -243.753 -20.7803 3.04882 + vertex -232.607 -22.5842 3.1853 + endloop + endfacet + facet normal -0.0613414 -0.436348 -0.897685 + outer loop + vertex -277.316 -18.4578 4.08001 + vertex -275.504 -16.8772 3.18786 + vertex -266.272 -20.0144 4.08199 + endloop + endfacet + facet normal -0.0551707 -0.420456 -0.905634 + outer loop + vertex -266.272 -20.0144 4.08199 + vertex -275.504 -16.8772 3.18786 + vertex -265.222 -17.9205 3.04588 + endloop + endfacet + facet normal -0.0847579 -0.599332 -0.796001 + outer loop + vertex -278.181 -20.0093 5.3403 + vertex -277.316 -18.4578 4.08001 + vertex -267.142 -21.5703 5.34014 + endloop + endfacet + facet normal -0.0841033 -0.597712 -0.797287 + outer loop + vertex -267.142 -21.5703 5.34014 + vertex -277.316 -18.4578 4.08001 + vertex -266.272 -20.0144 4.08199 + endloop + endfacet + facet normal -0.0821121 -0.59851 -0.796896 + outer loop + vertex -267.142 -21.5703 5.34014 + vertex -266.272 -20.0144 4.08199 + vertex -256.143 -23.0767 5.33816 + endloop + endfacet + facet normal -0.08087 -0.595405 -0.799345 + outer loop + vertex -256.143 -23.0767 5.33816 + vertex -266.272 -20.0144 4.08199 + vertex -255.306 -21.5055 4.08323 + endloop + endfacet + facet normal -0.0569637 -0.41968 -0.905883 + outer loop + vertex -266.272 -20.0144 4.08199 + vertex -265.222 -17.9205 3.04588 + vertex -255.306 -21.5055 4.08323 + endloop + endfacet + facet normal -0.0629338 -0.434103 -0.898662 + outer loop + vertex -255.306 -21.5055 4.08323 + vertex -265.222 -17.9205 3.04588 + vertex -253.657 -19.8913 3.18802 + endloop + endfacet + facet normal -0.0651869 -0.434723 -0.898202 + outer loop + vertex -298.828 -15.2641 4.07818 + vertex -297.096 -13.6843 3.18786 + vertex -288.204 -16.8648 4.08189 + endloop + endfacet + facet normal -0.0588266 -0.419138 -0.906015 + outer loop + vertex -288.204 -16.8648 4.08189 + vertex -297.096 -13.6843 3.18786 + vertex -287.057 -14.7908 3.0479 + endloop + endfacet + facet normal -0.0916204 -0.602061 -0.793176 + outer loop + vertex -299.6 -16.8135 5.34338 + vertex -298.828 -15.2641 4.07818 + vertex -289.031 -18.4192 5.34139 + endloop + endfacet + facet normal -0.089786 -0.59775 -0.796638 + outer loop + vertex -289.031 -18.4192 5.34139 + vertex -298.828 -15.2641 4.07818 + vertex -288.204 -16.8648 4.08189 + endloop + endfacet + facet normal -0.0877967 -0.59852 -0.796283 + outer loop + vertex -289.031 -18.4192 5.34139 + vertex -288.204 -16.8648 4.08189 + vertex -278.181 -20.0093 5.3403 + endloop + endfacet + facet normal -0.0876527 -0.598172 -0.79656 + outer loop + vertex -278.181 -20.0093 5.3403 + vertex -288.204 -16.8648 4.08189 + vertex -277.316 -18.4578 4.08001 + endloop + endfacet + facet normal -0.0613054 -0.417957 -0.906396 + outer loop + vertex -288.204 -16.8648 4.08189 + vertex -287.057 -14.7908 3.0479 + vertex -277.316 -18.4578 4.08001 + endloop + endfacet + facet normal -0.066955 -0.43111 -0.899812 + outer loop + vertex -277.316 -18.4578 4.08001 + vertex -287.057 -14.7908 3.0479 + vertex -275.504 -16.8772 3.18786 + endloop + endfacet + facet normal -0.0713237 -0.440195 -0.895065 + outer loop + vertex -319.45 -11.9819 4.08284 + vertex -317.832 -10.4136 3.18265 + vertex -309.191 -13.64 4.08082 + endloop + endfacet + facet normal -0.0620079 -0.418337 -0.906173 + outer loop + vertex -309.191 -13.64 4.08082 + vertex -317.832 -10.4136 3.18265 + vertex -308.171 -11.555 3.04848 + endloop + endfacet + facet normal -0.0966661 -0.596773 -0.796567 + outer loop + vertex -320.239 -13.5334 5.34105 + vertex -319.45 -11.9819 4.08284 + vertex -309.969 -15.1952 5.33969 + endloop + endfacet + facet normal -0.0965805 -0.59658 -0.796721 + outer loop + vertex -309.969 -15.1952 5.33969 + vertex -319.45 -11.9819 4.08284 + vertex -309.191 -13.64 4.08082 + endloop + endfacet + facet normal -0.0930287 -0.5979 -0.796154 + outer loop + vertex -309.969 -15.1952 5.33969 + vertex -309.191 -13.64 4.08082 + vertex -299.6 -16.8135 5.34338 + endloop + endfacet + facet normal -0.094401 -0.60104 -0.793624 + outer loop + vertex -299.6 -16.8135 5.34338 + vertex -309.191 -13.64 4.08082 + vertex -298.828 -15.2641 4.07818 + endloop + endfacet + facet normal -0.0655581 -0.416823 -0.906621 + outer loop + vertex -309.191 -13.64 4.08082 + vertex -308.171 -11.555 3.04848 + vertex -298.828 -15.2641 4.07818 + endloop + endfacet + facet normal -0.0712124 -0.429322 -0.90034 + outer loop + vertex -298.828 -15.2641 4.07818 + vertex -308.171 -11.555 3.04848 + vertex -297.096 -13.6843 3.18786 + endloop + endfacet + facet normal -0.0749413 -0.437892 -0.895899 + outer loop + vertex -340.046 -8.52045 4.08255 + vertex -338.391 -6.97036 3.18646 + vertex -329.721 -10.2821 4.0799 + endloop + endfacet + facet normal -0.066071 -0.417472 -0.906285 + outer loop + vertex -329.721 -10.2821 4.0799 + vertex -338.391 -6.97036 3.18646 + vertex -328.744 -8.20048 3.04983 + endloop + endfacet + facet normal -0.101933 -0.595976 -0.796507 + outer loop + vertex -340.876 -10.059 5.33999 + vertex -340.046 -8.52045 4.08255 + vertex -330.531 -11.8271 5.33914 + endloop + endfacet + facet normal -0.10186 -0.595816 -0.796635 + outer loop + vertex -330.531 -11.8271 5.33914 + vertex -340.046 -8.52045 4.08255 + vertex -329.721 -10.2821 4.0799 + endloop + endfacet + facet normal -0.0988268 -0.596998 -0.796132 + outer loop + vertex -330.531 -11.8271 5.33914 + vertex -329.721 -10.2821 4.0799 + vertex -320.239 -13.5334 5.34105 + endloop + endfacet + facet normal -0.0984257 -0.596107 -0.79685 + outer loop + vertex -320.239 -13.5334 5.34105 + vertex -329.721 -10.2821 4.0799 + vertex -319.45 -11.9819 4.08284 + endloop + endfacet + facet normal -0.0686547 -0.416407 -0.906583 + outer loop + vertex -329.721 -10.2821 4.0799 + vertex -328.744 -8.20048 3.04983 + vertex -319.45 -11.9819 4.08284 + endloop + endfacet + facet normal -0.0773331 -0.435131 -0.89704 + outer loop + vertex -319.45 -11.9819 4.08284 + vertex -328.744 -8.20048 3.04983 + vertex -317.832 -10.4136 3.18265 + endloop + endfacet + facet normal -0.0790689 -0.438322 -0.895333 + outer loop + vertex -360.889 -4.83134 4.08213 + vertex -359.177 -3.31163 3.18694 + vertex -350.447 -6.70805 4.07878 + endloop + endfacet + facet normal -0.0704784 -0.418862 -0.90531 + outer loop + vertex -350.447 -6.70805 4.07878 + vertex -359.177 -3.31163 3.18694 + vertex -349.419 -4.65047 3.0467 + endloop + endfacet + facet normal -0.106915 -0.596757 -0.795267 + outer loop + vertex -361.744 -6.35376 5.33942 + vertex -360.889 -4.83134 4.08213 + vertex -351.28 -8.23161 5.34184 + endloop + endfacet + facet normal -0.107894 -0.598883 -0.793535 + outer loop + vertex -351.28 -8.23161 5.34184 + vertex -360.889 -4.83134 4.08213 + vertex -350.447 -6.70805 4.07878 + endloop + endfacet + facet normal -0.105498 -0.599852 -0.793125 + outer loop + vertex -351.28 -8.23161 5.34184 + vertex -350.447 -6.70805 4.07878 + vertex -340.876 -10.059 5.33999 + endloop + endfacet + facet normal -0.103449 -0.595369 -0.796765 + outer loop + vertex -340.876 -10.059 5.33999 + vertex -350.447 -6.70805 4.07878 + vertex -340.046 -8.52045 4.08255 + endloop + endfacet + facet normal -0.0725002 -0.417977 -0.90556 + outer loop + vertex -350.447 -6.70805 4.07878 + vertex -349.419 -4.65047 3.0467 + vertex -340.046 -8.52045 4.08255 + endloop + endfacet + facet normal -0.0798423 -0.433616 -0.897554 + outer loop + vertex -340.046 -8.52045 4.08255 + vertex -349.419 -4.65047 3.0467 + vertex -338.391 -6.97036 3.18646 + endloop + endfacet + facet normal -0.0824103 -0.438328 -0.895029 + outer loop + vertex -381.909 -0.92337 4.07991 + vertex -380.137 0.570453 3.1852 + vertex -371.38 -2.90631 4.08155 + endloop + endfacet + facet normal -0.0736387 -0.418824 -0.905076 + outer loop + vertex -371.38 -2.90631 4.08155 + vertex -380.137 0.570453 3.1852 + vertex -370.287 -0.871548 3.05104 + endloop + endfacet + facet normal -0.112948 -0.59995 -0.792025 + outer loop + vertex -382.789 -2.42186 5.3405 + vertex -381.909 -0.92337 4.07991 + vertex -372.234 -4.4125 5.34324 + endloop + endfacet + facet normal -0.112808 -0.599651 -0.792271 + outer loop + vertex -372.234 -4.4125 5.34324 + vertex -381.909 -0.92337 4.07991 + vertex -371.38 -2.90631 4.08155 + endloop + endfacet + facet normal -0.111361 -0.600258 -0.792016 + outer loop + vertex -372.234 -4.4125 5.34324 + vertex -371.38 -2.90631 4.08155 + vertex -361.744 -6.35376 5.33942 + endloop + endfacet + facet normal -0.109278 -0.595774 -0.795683 + outer loop + vertex -361.744 -6.35376 5.33942 + vertex -371.38 -2.90631 4.08155 + vertex -360.889 -4.83134 4.08213 + endloop + endfacet + facet normal -0.0765517 -0.417457 -0.905466 + outer loop + vertex -371.38 -2.90631 4.08155 + vertex -370.287 -0.871548 3.05104 + vertex -360.889 -4.83134 4.08213 + endloop + endfacet + facet normal -0.0842503 -0.433569 -0.897173 + outer loop + vertex -360.889 -4.83134 4.08213 + vertex -370.287 -0.871548 3.05104 + vertex -359.177 -3.31163 3.18694 + endloop + endfacet + facet normal -0.0860979 -0.434923 -0.896342 + outer loop + vertex -403.161 3.24562 4.0803 + vertex -401.307 4.72123 3.1862 + vertex -392.491 1.12769 4.08303 + endloop + endfacet + facet normal -0.0781202 -0.41758 -0.905276 + outer loop + vertex -392.491 1.12769 4.08303 + vertex -401.307 4.72123 3.1862 + vertex -391.335 3.14891 3.05099 + endloop + endfacet + facet normal -0.12027 -0.600343 -0.790647 + outer loop + vertex -404.119 1.77276 5.34433 + vertex -403.161 3.24562 4.0803 + vertex -393.42 -0.364106 5.33941 + endloop + endfacet + facet normal -0.118024 -0.595639 -0.794534 + outer loop + vertex -393.42 -0.364106 5.33941 + vertex -403.161 3.24562 4.0803 + vertex -392.491 1.12769 4.08303 + endloop + endfacet + facet normal -0.115441 -0.59682 -0.794027 + outer loop + vertex -393.42 -0.364106 5.33941 + vertex -392.491 1.12769 4.08303 + vertex -382.789 -2.42186 5.3405 + endloop + endfacet + facet normal -0.116245 -0.598521 -0.792628 + outer loop + vertex -382.789 -2.42186 5.3405 + vertex -392.491 1.12769 4.08303 + vertex -381.909 -0.92337 4.07991 + endloop + endfacet + facet normal -0.0809343 -0.416176 -0.905675 + outer loop + vertex -392.491 1.12769 4.08303 + vertex -391.335 3.14891 3.05099 + vertex -381.909 -0.92337 4.07991 + endloop + endfacet + facet normal -0.0887644 -0.432208 -0.897394 + outer loop + vertex -381.909 -0.92337 4.07991 + vertex -391.335 3.14891 3.05099 + vertex -380.137 0.570453 3.1852 + endloop + endfacet + facet normal -0.0904733 -0.43099 -0.89781 + outer loop + vertex -424.47 7.65852 4.0813 + vertex -422.691 9.15745 3.18247 + vertex -413.855 5.43079 4.08096 + endloop + endfacet + facet normal -0.0818007 -0.412688 -0.907192 + outer loop + vertex -413.855 5.43079 4.08096 + vertex -422.691 9.15745 3.18247 + vertex -412.656 7.46346 3.04826 + endloop + endfacet + facet normal -0.122891 -0.590644 -0.79752 + outer loop + vertex -425.392 6.14925 5.34117 + vertex -424.47 7.65852 4.0813 + vertex -414.832 3.95108 5.34188 + endloop + endfacet + facet normal -0.12478 -0.594483 -0.794368 + outer loop + vertex -414.832 3.95108 5.34188 + vertex -424.47 7.65852 4.0813 + vertex -413.855 5.43079 4.08096 + endloop + endfacet + facet normal -0.12106 -0.596282 -0.793595 + outer loop + vertex -414.832 3.95108 5.34188 + vertex -413.855 5.43079 4.08096 + vertex -404.119 1.77276 5.34433 + endloop + endfacet + facet normal -0.12251 -0.599282 -0.791108 + outer loop + vertex -404.119 1.77276 5.34433 + vertex -413.855 5.43079 4.08096 + vertex -403.161 3.24562 4.0803 + endloop + endfacet + facet normal -0.0841403 -0.411479 -0.907527 + outer loop + vertex -413.855 5.43079 4.08096 + vertex -412.656 7.46346 3.04826 + vertex -403.161 3.24562 4.0803 + endloop + endfacet + facet normal -0.0925652 -0.428327 -0.89887 + outer loop + vertex -403.161 3.24562 4.0803 + vertex -412.656 7.46346 3.04826 + vertex -401.307 4.72123 3.1862 + endloop + endfacet + facet normal -0.0932405 -0.426046 -0.899884 + outer loop + vertex -445.2 12.1676 4.07626 + vertex -443.76 13.7476 3.17913 + vertex -434.9 9.90168 4.08192 + endloop + endfacet + facet normal -0.0849053 -0.408894 -0.908623 + outer loop + vertex -434.9 9.90168 4.08192 + vertex -443.76 13.7476 3.17913 + vertex -433.967 12.0086 3.0466 + endloop + endfacet + facet normal -0.128894 -0.588626 -0.798064 + outer loop + vertex -445.836 10.5909 5.34198 + vertex -445.2 12.1676 4.07626 + vertex -435.689 8.36199 5.34711 + endloop + endfacet + facet normal -0.129196 -0.589219 -0.797577 + outer loop + vertex -435.689 8.36199 5.34711 + vertex -445.2 12.1676 4.07626 + vertex -434.9 9.90168 4.08192 + endloop + endfacet + facet normal -0.127254 -0.589998 -0.797314 + outer loop + vertex -435.689 8.36199 5.34711 + vertex -434.9 9.90168 4.08192 + vertex -425.392 6.14925 5.34117 + endloop + endfacet + facet normal -0.1267 -0.588897 -0.798215 + outer loop + vertex -425.392 6.14925 5.34117 + vertex -434.9 9.90168 4.08192 + vertex -424.47 7.65852 4.0813 + endloop + endfacet + facet normal -0.0877485 -0.407754 -0.908865 + outer loop + vertex -434.9 9.90168 4.08192 + vertex -433.967 12.0086 3.0466 + vertex -424.47 7.65852 4.0813 + endloop + endfacet + facet normal -0.0966199 -0.425017 -0.900014 + outer loop + vertex -424.47 7.65852 4.0813 + vertex -433.967 12.0086 3.0466 + vertex -422.691 9.15745 3.18247 + endloop + endfacet + facet normal -0.0974449 -0.426163 -0.899383 + outer loop + vertex -466.229 16.9704 4.06174 + vertex -464.742 18.5038 3.17396 + vertex -455.551 14.5118 4.06979 + endloop + endfacet + facet normal -0.0891846 -0.409106 -0.908118 + outer loop + vertex -455.551 14.5118 4.06979 + vertex -464.742 18.5038 3.17396 + vertex -454.891 16.6597 3.03734 + endloop + endfacet + facet normal -0.132752 -0.581136 -0.802906 + outer loop + vertex -466.766 15.3658 5.31191 + vertex -466.229 16.9704 4.06174 + vertex -456.097 12.9086 5.32629 + endloop + endfacet + facet normal -0.133581 -0.582787 -0.801571 + outer loop + vertex -456.097 12.9086 5.32629 + vertex -466.229 16.9704 4.06174 + vertex -455.551 14.5118 4.06979 + endloop + endfacet + facet normal -0.130611 -0.583675 -0.801414 + outer loop + vertex -456.097 12.9086 5.32629 + vertex -455.551 14.5118 4.06979 + vertex -445.836 10.5909 5.34198 + endloop + endfacet + facet normal -0.132517 -0.587408 -0.798368 + outer loop + vertex -445.836 10.5909 5.34198 + vertex -455.551 14.5118 4.06979 + vertex -445.2 12.1676 4.07626 + endloop + endfacet + facet normal -0.0918933 -0.408315 -0.908204 + outer loop + vertex -455.551 14.5118 4.06979 + vertex -454.891 16.6597 3.03734 + vertex -445.2 12.1676 4.07626 + endloop + endfacet + facet normal -0.0988553 -0.421742 -0.901311 + outer loop + vertex -445.2 12.1676 4.07626 + vertex -454.891 16.6597 3.03734 + vertex -443.76 13.7476 3.17913 + endloop + endfacet + facet normal -0.102937 -0.427773 -0.898006 + outer loop + vertex -488.158 21.9176 4.17031 + vertex -486.383 23.4873 3.21916 + vertex -477.306 19.5085 4.07402 + endloop + endfacet + facet normal -0.0926155 -0.40657 -0.908913 + outer loop + vertex -477.306 19.5085 4.07402 + vertex -486.383 23.4873 3.21916 + vertex -476.086 21.5375 3.04208 + endloop + endfacet + facet normal -0.138819 -0.587012 -0.797588 + outer loop + vertex -488.189 20.1649 5.46573 + vertex -488.158 21.9176 4.17031 + vertex -477.747 17.87 5.33726 + endloop + endfacet + facet normal -0.136246 -0.581652 -0.801946 + outer loop + vertex -477.747 17.87 5.33726 + vertex -488.158 21.9176 4.17031 + vertex -477.306 19.5085 4.07402 + endloop + endfacet + facet normal -0.134602 -0.582073 -0.801918 + outer loop + vertex -477.747 17.87 5.33726 + vertex -477.306 19.5085 4.07402 + vertex -466.766 15.3658 5.31191 + endloop + endfacet + facet normal -0.133969 -0.580775 -0.802965 + outer loop + vertex -466.766 15.3658 5.31191 + vertex -477.306 19.5085 4.07402 + vertex -466.229 16.9704 4.06174 + endloop + endfacet + facet normal -0.0939999 -0.405833 -0.909101 + outer loop + vertex -477.306 19.5085 4.07402 + vertex -476.086 21.5375 3.04208 + vertex -466.229 16.9704 4.06174 + endloop + endfacet + facet normal -0.102414 -0.422124 -0.900735 + outer loop + vertex -466.229 16.9704 4.06174 + vertex -476.086 21.5375 3.04208 + vertex -464.742 18.5038 3.17396 + endloop + endfacet + facet normal -0.155371 -0.622625 -0.766941 + outer loop + vertex -496.127 21.8349 5.71802 + vertex -497.357 23.7015 4.45198 + vertex -488.189 20.1649 5.46573 + endloop + endfacet + facet normal -0.138259 -0.587065 -0.797646 + outer loop + vertex -488.189 20.1649 5.46573 + vertex -497.357 23.7015 4.45198 + vertex -488.158 21.9176 4.17031 + endloop + endfacet + facet normal -0.111442 -0.433517 -0.894228 + outer loop + vertex -497.357 23.7015 4.45198 + vertex -497.201 26.3339 3.15632 + vertex -488.158 21.9176 4.17031 + endloop + endfacet + facet normal -0.106473 -0.424474 -0.899158 + outer loop + vertex -488.158 21.9176 4.17031 + vertex -497.201 26.3339 3.15632 + vertex -486.383 23.4873 3.21916 + endloop + endfacet + facet normal -0.105579 -0.446053 -0.888758 + outer loop + vertex -509.061 26.8619 4.23573 + vertex -508.799 28.8491 3.20724 + vertex -507.829 27.073 3.9834 + endloop + endfacet + facet normal -0.0534439 -0.424228 -0.903977 + outer loop + vertex -507.829 27.073 3.9834 + vertex -508.799 28.8491 3.20724 + vertex -507.091 29.2372 2.92417 + endloop + endfacet + facet normal -0.178961 -0.613067 -0.769494 + outer loop + vertex -509.133 25.4154 5.4049 + vertex -509.061 26.8619 4.23573 + vertex -508.138 25.3556 5.22112 + endloop + endfacet + facet normal -0.0683933 -0.575178 -0.815164 + outer loop + vertex -508.138 25.3556 5.22112 + vertex -509.061 26.8619 4.23573 + vertex -507.829 27.073 3.9834 + endloop + endfacet + facet normal -0.136971 -0.562823 -0.815149 + outer loop + vertex -508.138 25.3556 5.22112 + vertex -507.829 27.073 3.9834 + vertex -503.71 24.4119 5.12868 + endloop + endfacet + facet normal -0.115302 -0.537872 -0.835105 + outer loop + vertex -503.71 24.4119 5.12868 + vertex -507.829 27.073 3.9834 + vertex -504.242 26.7894 3.67079 + endloop + endfacet + facet normal -0.111153 -0.406071 -0.907056 + outer loop + vertex -507.829 27.073 3.9834 + vertex -507.091 29.2372 2.92417 + vertex -504.242 26.7894 3.67079 + endloop + endfacet + facet normal -0.0980267 -0.392999 -0.914299 + outer loop + vertex -504.242 26.7894 3.67079 + vertex -507.091 29.2372 2.92417 + vertex -504.196 28.5905 2.89175 + endloop + endfacet + facet normal 0.0540794 0.67477 0.736044 + outer loop + vertex -508.846 25.3324 5.45995 + vertex -508.934 26.4189 4.47028 + vertex -509.133 25.4154 5.4049 + endloop + endfacet + facet normal 0.548346 0.509069 0.663449 + outer loop + vertex -509.133 25.4154 5.4049 + vertex -508.934 26.4189 4.47028 + vertex -509.061 26.8619 4.23573 + endloop + endfacet + facet normal 0.182563 0.500548 0.84624 + outer loop + vertex -508.934 26.4189 4.47028 + vertex -508.869 27.7446 3.67214 + vertex -509.061 26.8619 4.23573 + endloop + endfacet + facet normal 0.800122 0.189043 0.569269 + outer loop + vertex -509.061 26.8619 4.23573 + vertex -508.869 27.7446 3.67214 + vertex -508.799 28.8491 3.20724 + endloop + endfacet + facet normal 0.0687326 -0.294487 -0.95318 + outer loop + vertex 505.653 28.1259 3.20425 + vertex 498.34 26.7968 3.08761 + vertex 500.423 30.5976 2.06347 + endloop + endfacet + facet normal 0.070929 -0.297525 -0.952076 + outer loop + vertex 490.714 24.4779 3.24409 + vertex 484.289 26.2533 2.21057 + vertex 498.34 26.7968 3.08761 + endloop + endfacet + facet normal 0.0708909 -0.295539 -0.952697 + outer loop + vertex 484.289 26.2533 2.21057 + vertex 500.423 30.5976 2.06347 + vertex 498.34 26.7968 3.08761 + endloop + endfacet + facet normal 0.0732992 -0.290163 -0.954166 + outer loop + vertex 490.714 24.4779 3.24409 + vertex 479.728 22.286 3.06671 + vertex 484.289 26.2533 2.21057 + endloop + endfacet + facet normal 0.0668395 -0.282305 -0.956993 + outer loop + vertex 469.574 19.525 3.17198 + vertex 463.907 21.461 2.20505 + vertex 479.728 22.286 3.06671 + endloop + endfacet + facet normal 0.0668761 -0.283325 -0.956689 + outer loop + vertex 463.907 21.461 2.20505 + vertex 484.289 26.2533 2.21057 + vertex 479.728 22.286 3.06671 + endloop + endfacet + facet normal 0.0664586 -0.283288 -0.956729 + outer loop + vertex 469.574 19.525 3.17198 + vertex 458.093 17.3105 3.0302 + vertex 463.907 21.461 2.20505 + endloop + endfacet + facet normal 0.0626232 -0.289446 -0.955144 + outer loop + vertex 448.24 14.691 3.178 + vertex 442.633 16.7005 2.20141 + vertex 458.093 17.3105 3.0302 + endloop + endfacet + facet normal 0.0623523 -0.277905 -0.958583 + outer loop + vertex 442.633 16.7005 2.20141 + vertex 463.907 21.461 2.20505 + vertex 458.093 17.3105 3.0302 + endloop + endfacet + facet normal 0.0633122 -0.28775 -0.95561 + outer loop + vertex 448.24 14.691 3.178 + vertex 437.182 12.6675 3.05469 + vertex 442.633 16.7005 2.20141 + endloop + endfacet + facet normal 0.0610387 -0.29011 -0.955045 + outer loop + vertex 427.497 10.1721 3.19369 + vertex 421.632 12.1845 2.20757 + vertex 437.182 12.6675 3.05469 + endloop + endfacet + facet normal 0.060961 -0.284792 -0.956649 + outer loop + vertex 421.632 12.1845 2.20757 + vertex 442.633 16.7005 2.20141 + vertex 437.182 12.6675 3.05469 + endloop + endfacet + facet normal 0.0620788 -0.287441 -0.955784 + outer loop + vertex 427.497 10.1721 3.19369 + vertex 416.306 8.22255 3.05311 + vertex 421.632 12.1845 2.20757 + endloop + endfacet + facet normal 0.0580294 -0.289174 -0.955516 + outer loop + vertex 406.536 5.80432 3.19164 + vertex 400.665 7.87045 2.20981 + vertex 416.306 8.22255 3.05311 + endloop + endfacet + facet normal 0.0579857 -0.282319 -0.957567 + outer loop + vertex 400.665 7.87045 2.20981 + vertex 421.632 12.1845 2.20757 + vertex 416.306 8.22255 3.05311 + endloop + endfacet + facet normal 0.0592815 -0.28603 -0.956385 + outer loop + vertex 406.536 5.80432 3.19164 + vertex 395.336 3.96013 3.04897 + vertex 400.665 7.87045 2.20981 + endloop + endfacet + facet normal 0.0549693 -0.289414 -0.955624 + outer loop + vertex 385.522 1.63413 3.1889 + vertex 379.622 3.74645 2.20979 + vertex 395.336 3.96013 3.04897 + endloop + endfacet + facet normal 0.0549896 -0.280582 -0.958254 + outer loop + vertex 379.622 3.74645 2.20979 + vertex 400.665 7.87045 2.20981 + vertex 395.336 3.96013 3.04897 + endloop + endfacet + facet normal 0.0562089 -0.286346 -0.956476 + outer loop + vertex 385.522 1.63413 3.1889 + vertex 374.132 -0.133205 3.04863 + vertex 379.622 3.74645 2.20979 + endloop + endfacet + facet normal 0.0525144 -0.287946 -0.956206 + outer loop + vertex 364.081 -2.41312 3.18317 + vertex 358.434 -0.200293 2.20672 + vertex 374.132 -0.133205 3.04863 + endloop + endfacet + facet normal 0.0525886 -0.281574 -0.958097 + outer loop + vertex 358.434 -0.200293 2.20672 + vertex 379.622 3.74645 2.20979 + vertex 374.132 -0.133205 3.04863 + endloop + endfacet + facet normal 0.0528624 -0.287155 -0.956424 + outer loop + vertex 364.081 -2.41312 3.18317 + vertex 352.742 -4.05794 3.05028 + vertex 358.434 -0.200293 2.20672 + endloop + endfacet + facet normal 0.0496977 -0.28905 -0.956023 + outer loop + vertex 342.937 -6.19683 3.18728 + vertex 337.43 -3.91025 2.20968 + vertex 352.742 -4.05794 3.05028 + endloop + endfacet + facet normal 0.0498544 -0.28302 -0.957817 + outer loop + vertex 337.43 -3.91025 2.20968 + vertex 358.434 -0.200293 2.20672 + vertex 352.742 -4.05794 3.05028 + endloop + endfacet + facet normal 0.0507789 -0.286722 -0.956667 + outer loop + vertex 342.937 -6.19683 3.18728 + vertex 332.009 -7.66739 3.04799 + vertex 337.43 -3.91025 2.20968 + endloop + endfacet + facet normal 0.0469658 -0.288578 -0.956304 + outer loop + vertex 322.508 -9.65994 3.18265 + vertex 316.723 -7.36522 2.20608 + vertex 332.009 -7.66739 3.04799 + endloop + endfacet + facet normal 0.0472058 -0.281925 -0.958274 + outer loop + vertex 316.723 -7.36522 2.20608 + vertex 337.43 -3.91025 2.20968 + vertex 332.009 -7.66739 3.04799 + endloop + endfacet + facet normal 0.0475249 -0.287318 -0.956656 + outer loop + vertex 322.508 -9.65994 3.18265 + vertex 311.459 -11.0386 3.04779 + vertex 316.723 -7.36522 2.20608 + endloop + endfacet + facet normal 0.0440793 -0.290418 -0.955884 + outer loop + vertex 301.639 -12.9862 3.18669 + vertex 295.766 -10.6571 2.20826 + vertex 311.459 -11.0386 3.04779 + endloop + endfacet + facet normal 0.044373 -0.283122 -0.958057 + outer loop + vertex 295.766 -10.6571 2.20826 + vertex 316.723 -7.36522 2.20608 + vertex 311.459 -11.0386 3.04779 + endloop + endfacet + facet normal 0.0451905 -0.287913 -0.95659 + outer loop + vertex 301.639 -12.9862 3.18669 + vertex 290.214 -14.3226 3.04919 + vertex 295.766 -10.6571 2.20826 + endloop + endfacet + facet normal 0.0415372 -0.291238 -0.955748 + outer loop + vertex 280.166 -16.212 3.18827 + vertex 274.517 -13.7949 2.20622 + vertex 290.214 -14.3226 3.04919 + endloop + endfacet + facet normal 0.04193 -0.283322 -0.958108 + outer loop + vertex 274.517 -13.7949 2.20622 + vertex 295.766 -10.6571 2.20826 + vertex 290.214 -14.3226 3.04919 + endloop + endfacet + facet normal 0.0427607 -0.288673 -0.956472 + outer loop + vertex 280.166 -16.212 3.18827 + vertex 268.818 -17.4279 3.04792 + vertex 274.517 -13.7949 2.20622 + endloop + endfacet + facet normal 0.038388 -0.290958 -0.955965 + outer loop + vertex 258.949 -19.1903 3.188 + vertex 253.371 -16.707 2.20817 + vertex 268.818 -17.4279 3.04792 + endloop + endfacet + facet normal 0.0388864 -0.283024 -0.958324 + outer loop + vertex 253.371 -16.707 2.20817 + vertex 274.517 -13.7949 2.20622 + vertex 268.818 -17.4279 3.04792 + endloop + endfacet + facet normal 0.0398655 -0.287972 -0.956809 + outer loop + vertex 258.949 -19.1903 3.188 + vertex 247.811 -20.2627 3.0467 + vertex 253.371 -16.707 2.20817 + endloop + endfacet + facet normal 0.0354632 -0.291656 -0.955866 + outer loop + vertex 238.072 -21.9052 3.18652 + vertex 232.386 -19.3801 2.2051 + vertex 247.811 -20.2627 3.0467 + endloop + endfacet + facet normal 0.0361319 -0.28255 -0.958572 + outer loop + vertex 232.386 -19.3801 2.2051 + vertex 253.371 -16.707 2.20817 + vertex 247.811 -20.2627 3.0467 + endloop + endfacet + facet normal 0.0363798 -0.289798 -0.956396 + outer loop + vertex 238.072 -21.9052 3.18652 + vertex 226.894 -22.8622 3.05131 + vertex 232.386 -19.3801 2.2051 + endloop + endfacet + facet normal 0.0328552 -0.289116 -0.95673 + outer loop + vertex 217.041 -24.4228 3.18456 + vertex 211.283 -21.8431 2.20724 + vertex 226.894 -22.8622 3.05131 + endloop + endfacet + facet normal 0.0331801 -0.285121 -0.957917 + outer loop + vertex 211.283 -21.8431 2.20724 + vertex 232.386 -19.3801 2.2051 + vertex 226.894 -22.8622 3.05131 + endloop + endfacet + facet normal 0.0329169 -0.288992 -0.956765 + outer loop + vertex 217.041 -24.4228 3.18456 + vertex 205.705 -25.2772 3.05263 + vertex 211.283 -21.8431 2.20724 + endloop + endfacet + facet normal 0.0299402 -0.290079 -0.956534 + outer loop + vertex 195.738 -26.744 3.18548 + vertex 189.974 -24.1033 2.20424 + vertex 205.705 -25.2772 3.05263 + endloop + endfacet + facet normal 0.0303843 -0.285181 -0.957992 + outer loop + vertex 189.974 -24.1033 2.20424 + vertex 211.283 -21.8431 2.20724 + vertex 205.705 -25.2772 3.05263 + endloop + endfacet + facet normal 0.0301287 -0.289707 -0.956641 + outer loop + vertex 195.738 -26.744 3.18548 + vertex 184.328 -27.4841 3.05025 + vertex 189.974 -24.1033 2.20424 + endloop + endfacet + facet normal 0.0262345 -0.290011 -0.956664 + outer loop + vertex 174.299 -28.8426 3.18704 + vertex 168.521 -26.1367 2.20831 + vertex 184.328 -27.4841 3.05025 + endloop + endfacet + facet normal 0.0267876 -0.284539 -0.95829 + outer loop + vertex 168.521 -26.1367 2.20831 + vertex 189.974 -24.1033 2.20424 + vertex 184.328 -27.4841 3.05025 + endloop + endfacet + facet normal 0.0267975 -0.288922 -0.956977 + outer loop + vertex 174.299 -28.8426 3.18704 + vertex 162.814 -29.4589 3.05151 + vertex 168.521 -26.1367 2.20831 + endloop + endfacet + facet normal 0.0231179 -0.290651 -0.95655 + outer loop + vertex 152.708 -30.7087 3.18701 + vertex 146.997 -27.9325 2.20546 + vertex 162.814 -29.4589 3.05151 + endloop + endfacet + facet normal 0.0238408 -0.28422 -0.958463 + outer loop + vertex 146.997 -27.9325 2.20546 + vertex 168.521 -26.1367 2.20831 + vertex 162.814 -29.4589 3.05151 + endloop + endfacet + facet normal 0.0237048 -0.289556 -0.956867 + outer loop + vertex 152.708 -30.7087 3.18701 + vertex 141.215 -31.1934 3.04899 + vertex 146.997 -27.9325 2.20546 + endloop + endfacet + facet normal 0.0195514 -0.288449 -0.957296 + outer loop + vertex 131.146 -32.3234 3.18384 + vertex 125.515 -29.4667 2.20804 + vertex 141.215 -31.1934 3.04899 + endloop + endfacet + facet normal 0.0201465 -0.28372 -0.958696 + outer loop + vertex 125.515 -29.4667 2.20804 + vertex 146.997 -27.9325 2.20546 + vertex 141.215 -31.1934 3.04899 + endloop + endfacet + facet normal 0.0198223 -0.287963 -0.957436 + outer loop + vertex 131.146 -32.3234 3.18384 + vertex 119.781 -32.6568 3.04881 + vertex 125.515 -29.4667 2.20804 + endloop + endfacet + facet normal 0.0156517 -0.292012 -0.956287 + outer loop + vertex 109.829 -33.6505 3.18935 + vertex 104.144 -30.7322 2.20518 + vertex 119.781 -32.6568 3.04881 + endloop + endfacet + facet normal 0.0168926 -0.283094 -0.958943 + outer loop + vertex 104.144 -30.7322 2.20518 + vertex 125.515 -29.4667 2.20804 + vertex 119.781 -32.6568 3.04881 + endloop + endfacet + facet normal 0.0170848 -0.289473 -0.957034 + outer loop + vertex 109.829 -33.6505 3.18935 + vertex 98.4941 -33.8479 3.04672 + vertex 104.144 -30.7322 2.20518 + endloop + endfacet + facet normal 0.0118973 -0.290647 -0.956756 + outer loop + vertex 88.5293 -34.7173 3.18693 + vertex 82.7385 -31.7325 2.20817 + vertex 98.4941 -33.8479 3.04672 + endloop + endfacet + facet normal 0.0130798 -0.282768 -0.959099 + outer loop + vertex 82.7385 -31.7325 2.20817 + vertex 104.144 -30.7322 2.20518 + vertex 98.4941 -33.8479 3.04672 + endloop + endfacet + facet normal 0.0130167 -0.288667 -0.957341 + outer loop + vertex 88.5293 -34.7173 3.18693 + vertex 77.0771 -34.7772 3.04926 + vertex 82.7385 -31.7325 2.20817 + endloop + endfacet + facet normal 0.00878497 -0.290725 -0.956766 + outer loop + vertex 66.9653 -35.5352 3.18674 + vertex 61.1787 -32.4862 2.20714 + vertex 77.0771 -34.7772 3.04926 + endloop + endfacet + facet normal 0.00995377 -0.283415 -0.958946 + outer loop + vertex 61.1787 -32.4862 2.20714 + vertex 82.7385 -31.7325 2.20817 + vertex 77.0771 -34.7772 3.04926 + endloop + endfacet + facet normal 0.00965252 -0.289222 -0.957213 + outer loop + vertex 66.9653 -35.5352 3.18674 + vertex 55.3747 -35.4664 3.04907 + vertex 61.1787 -32.4862 2.20714 + endloop + endfacet + facet normal 0.00534665 -0.293233 -0.956026 + outer loop + vertex 45.1818 -36.1106 3.18966 + vertex 39.5521 -33.0033 2.2051 + vertex 55.3747 -35.4664 3.04907 + endloop + endfacet + facet normal 0.006887 -0.284262 -0.958722 + outer loop + vertex 39.5521 -33.0033 2.2051 + vertex 61.1787 -32.4862 2.20714 + vertex 55.3747 -35.4664 3.04907 + endloop + endfacet + facet normal 0.0069554 -0.290573 -0.956828 + outer loop + vertex 45.1818 -36.1106 3.18966 + vertex 33.7029 -35.9186 3.04791 + vertex 39.5521 -33.0033 2.2051 + endloop + endfacet + facet normal 0.00236228 -0.292249 -0.956339 + outer loop + vertex 23.6993 -36.4537 3.18674 + vertex 18.1163 -33.2904 2.20626 + vertex 33.7029 -35.9186 3.04791 + endloop + endfacet + facet normal 0.00376134 -0.284681 -0.958615 + outer loop + vertex 18.1163 -33.2904 2.20626 + vertex 39.5521 -33.0033 2.2051 + vertex 33.7029 -35.9186 3.04791 + endloop + endfacet + facet normal 0.00340249 -0.290571 -0.956847 + outer loop + vertex 23.6993 -36.4537 3.18674 + vertex 12.4078 -36.1396 3.05119 + vertex 18.1163 -33.2904 2.20626 + endloop + endfacet + facet normal 0.000140571 -0.289965 -0.957037 + outer loop + vertex 2.47798 -36.5798 3.1831 + vertex -3.15577 -33.3618 2.20727 + vertex 12.4078 -36.1396 3.05119 + endloop + endfacet + facet normal 0.000913799 -0.285995 -0.958231 + outer loop + vertex -3.15577 -33.3618 2.20727 + vertex 18.1163 -33.2904 2.20626 + vertex 12.4078 -36.1396 3.05119 + endloop + endfacet + facet normal 0.000366712 -0.289602 -0.957147 + outer loop + vertex 2.47798 -36.5798 3.1831 + vertex -8.8623 -36.1543 3.05003 + vertex -3.15577 -33.3618 2.20727 + endloop + endfacet + facet normal -0.00291239 -0.290999 -0.956719 + outer loop + vertex -18.8411 -36.4995 3.1854 + vertex -24.4458 -33.2281 2.20741 + vertex -8.8623 -36.1543 3.05003 + endloop + endfacet + facet normal -0.00179908 -0.285543 -0.958364 + outer loop + vertex -24.4458 -33.2281 2.20741 + vertex -3.15577 -33.3618 2.20727 + vertex -8.8623 -36.1543 3.05003 + endloop + endfacet + facet normal -0.0020864 -0.289702 -0.957115 + outer loop + vertex -18.8411 -36.4995 3.1854 + vertex -30.1343 -35.9708 3.04999 + vertex -24.4458 -33.2281 2.20741 + endloop + endfacet + facet normal -0.00563057 -0.289329 -0.957213 + outer loop + vertex -40.0216 -36.2217 3.18398 + vertex -45.7508 -32.8819 2.20817 + vertex -30.1343 -35.9708 3.04999 + endloop + endfacet + facet normal -0.00466269 -0.284807 -0.958574 + outer loop + vertex -45.7508 -32.8819 2.20817 + vertex -24.4458 -33.2281 2.20741 + vertex -30.1343 -35.9708 3.04999 + endloop + endfacet + facet normal -0.00511724 -0.288521 -0.95746 + outer loop + vertex -40.0216 -36.2217 3.18398 + vertex -51.3698 -35.5715 3.0487 + vertex -45.7508 -32.8819 2.20817 + endloop + endfacet + facet normal -0.00878728 -0.289729 -0.957069 + outer loop + vertex -61.4472 -35.7092 3.18291 + vertex -67.229 -32.3032 2.20491 + vertex -51.3698 -35.5715 3.0487 + endloop + endfacet + facet normal -0.00750475 -0.283954 -0.958808 + outer loop + vertex -67.229 -32.3032 2.20491 + vertex -45.7508 -32.8819 2.20817 + vertex -51.3698 -35.5715 3.0487 + endloop + endfacet + facet normal -0.00883336 -0.2898 -0.957046 + outer loop + vertex -61.4472 -35.7092 3.18291 + vertex -73.0858 -34.92 3.05135 + vertex -67.229 -32.3032 2.20491 + endloop + endfacet + facet normal -0.0122101 -0.290206 -0.956886 + outer loop + vertex -83.3561 -34.9358 3.18719 + vertex -88.8819 -31.4726 2.2074 + vertex -73.0858 -34.92 3.05135 + endloop + endfacet + facet normal -0.0110522 -0.285267 -0.958384 + outer loop + vertex -88.8819 -31.4726 2.2074 + vertex -67.229 -32.3032 2.20491 + vertex -73.0858 -34.92 3.05135 + endloop + endfacet + facet normal -0.0114143 -0.289039 -0.957249 + outer loop + vertex -83.3561 -34.9358 3.18719 + vertex -94.8208 -34.0257 3.04909 + vertex -88.8819 -31.4726 2.2074 + endloop + endfacet + facet normal -0.0155533 -0.288349 -0.957399 + outer loop + vertex -104.752 -33.9375 3.18386 + vertex -110.285 -30.3961 2.20717 + vertex -94.8208 -34.0257 3.04909 + endloop + endfacet + facet normal -0.0142275 -0.28307 -0.958994 + outer loop + vertex -110.285 -30.3961 2.20717 + vertex -88.8819 -31.4726 2.2074 + vertex -94.8208 -34.0257 3.04909 + endloop + endfacet + facet normal -0.015318 -0.28801 -0.957505 + outer loop + vertex -104.752 -33.9375 3.18386 + vertex -115.905 -32.8952 3.04879 + vertex -110.285 -30.3961 2.20717 + endloop + endfacet + facet normal -0.0192409 -0.288174 -0.957385 + outer loop + vertex -125.749 -32.6838 3.18299 + vertex -131.55 -29.0577 2.20811 + vertex -115.905 -32.8952 3.04879 + endloop + endfacet + facet normal -0.0178439 -0.282833 -0.959003 + outer loop + vertex -131.55 -29.0577 2.20811 + vertex -110.285 -30.3961 2.20717 + vertex -115.905 -32.8952 3.04879 + endloop + endfacet + facet normal -0.0192747 -0.288224 -0.957369 + outer loop + vertex -125.749 -32.6838 3.18299 + vertex -137.223 -31.4784 3.05109 + vertex -131.55 -29.0577 2.20811 + endloop + endfacet + facet normal -0.0228735 -0.290649 -0.956556 + outer loop + vertex -147.431 -31.1214 3.18672 + vertex -153.071 -27.4473 2.20522 + vertex -137.223 -31.4784 3.05109 + endloop + endfacet + facet normal -0.021141 -0.284249 -0.958517 + outer loop + vertex -153.071 -27.4473 2.20522 + vertex -131.55 -29.0577 2.20811 + vertex -137.223 -31.4784 3.05109 + endloop + endfacet + facet normal -0.0217552 -0.289067 -0.957062 + outer loop + vertex -147.431 -31.1214 3.18672 + vertex -159.004 -29.7864 3.04658 + vertex -153.071 -27.4473 2.20522 + endloop + endfacet + facet normal -0.0267363 -0.290228 -0.956584 + outer loop + vertex -169.072 -29.3208 3.18671 + vertex -174.552 -25.591 2.20823 + vertex -159.004 -29.7864 3.04658 + endloop + endfacet + facet normal -0.0245586 -0.282624 -0.958916 + outer loop + vertex -174.552 -25.591 2.20823 + vertex -153.071 -27.4473 2.20522 + vertex -159.004 -29.7864 3.04658 + endloop + endfacet + facet normal -0.0256518 -0.28876 -0.957058 + outer loop + vertex -169.072 -29.3208 3.18671 + vertex -180.34 -27.8712 3.05135 + vertex -174.552 -25.591 2.20823 + endloop + endfacet + facet normal -0.0291109 -0.288962 -0.956898 + outer loop + vertex -190.248 -27.3087 3.18289 + vertex -195.792 -23.5117 2.20495 + vertex -180.34 -27.8712 3.05135 + endloop + endfacet + facet normal -0.0276673 -0.284135 -0.958385 + outer loop + vertex -195.792 -23.5117 2.20495 + vertex -174.552 -25.591 2.20823 + vertex -180.34 -27.8712 3.05135 + endloop + endfacet + facet normal -0.0292371 -0.289132 -0.956843 + outer loop + vertex -190.248 -27.3087 3.18289 + vertex -201.573 -25.7225 3.04965 + vertex -195.792 -23.5117 2.20495 + endloop + endfacet + facet normal -0.0323155 -0.288372 -0.956973 + outer loop + vertex -211.586 -25.042 3.18271 + vertex -217.022 -21.1948 2.20698 + vertex -201.573 -25.7225 3.04965 + endloop + endfacet + facet normal -0.031152 -0.284619 -0.958135 + outer loop + vertex -217.022 -21.1948 2.20698 + vertex -195.792 -23.5117 2.20495 + vertex -201.573 -25.7225 3.04965 + endloop + endfacet + facet normal -0.0321687 -0.288181 -0.957036 + outer loop + vertex -211.586 -25.042 3.18271 + vertex -222.816 -23.3477 3.04998 + vertex -217.022 -21.1948 2.20698 + endloop + endfacet + facet normal -0.0357399 -0.288791 -0.956725 + outer loop + vertex -232.607 -22.5842 3.1853 + vertex -238.173 -18.6591 2.20839 + vertex -222.816 -23.3477 3.04998 + endloop + endfacet + facet normal -0.0340639 -0.283591 -0.95834 + outer loop + vertex -238.173 -18.6591 2.20839 + vertex -217.022 -21.1948 2.20698 + vertex -222.816 -23.3477 3.04998 + endloop + endfacet + facet normal -0.0348247 -0.287592 -0.95712 + outer loop + vertex -232.607 -22.5842 3.1853 + vertex -243.753 -20.7803 3.04882 + vertex -238.173 -18.6591 2.20839 + endloop + endfacet + facet normal -0.03957 -0.291187 -0.955848 + outer loop + vertex -253.657 -19.8913 3.18802 + vertex -259.434 -15.8829 2.20601 + vertex -243.753 -20.7803 3.04882 + endloop + endfacet + facet normal -0.0368271 -0.282853 -0.958456 + outer loop + vertex -259.434 -15.8829 2.20601 + vertex -238.173 -18.6591 2.20839 + vertex -243.753 -20.7803 3.04882 + endloop + endfacet + facet normal -0.0373619 -0.288245 -0.956828 + outer loop + vertex -253.657 -19.8913 3.18802 + vertex -265.222 -17.9205 3.04588 + vertex -259.434 -15.8829 2.20601 + endloop + endfacet + facet normal -0.0427268 -0.291002 -0.955768 + outer loop + vertex -275.504 -16.8772 3.18786 + vertex -280.997 -12.8486 2.20686 + vertex -265.222 -17.9205 3.04588 + endloop + endfacet + facet normal -0.039744 -0.282183 -0.958537 + outer loop + vertex -280.997 -12.8486 2.20686 + vertex -259.434 -15.8829 2.20601 + vertex -265.222 -17.9205 3.04588 + endloop + endfacet + facet normal -0.0404432 -0.288124 -0.956739 + outer loop + vertex -275.504 -16.8772 3.18786 + vertex -287.057 -14.7908 3.0479 + vertex -280.997 -12.8486 2.20686 + endloop + endfacet + facet normal -0.04533 -0.290379 -0.955837 + outer loop + vertex -297.096 -13.6843 3.18786 + vertex -302.322 -9.64003 2.20706 + vertex -287.057 -14.7908 3.0479 + endloop + endfacet + facet normal -0.0425006 -0.282404 -0.958354 + outer loop + vertex -302.322 -9.64003 2.20706 + vertex -280.997 -12.8486 2.20686 + vertex -287.057 -14.7908 3.0479 + endloop + endfacet + facet normal -0.0433314 -0.287994 -0.956651 + outer loop + vertex -297.096 -13.6843 3.18786 + vertex -308.171 -11.555 3.04848 + vertex -302.322 -9.64003 2.20706 + endloop + endfacet + facet normal -0.0473326 -0.288217 -0.956394 + outer loop + vertex -317.832 -10.4136 3.18265 + vertex -323.131 -6.3091 2.20797 + vertex -308.171 -11.555 3.04848 + endloop + endfacet + facet normal -0.0452892 -0.282671 -0.958147 + outer loop + vertex -323.131 -6.3091 2.20797 + vertex -302.322 -9.64003 2.20706 + vertex -308.171 -11.555 3.04848 + endloop + endfacet + facet normal -0.0466442 -0.287395 -0.956676 + outer loop + vertex -317.832 -10.4136 3.18265 + vertex -328.744 -8.20048 3.04983 + vertex -323.131 -6.3091 2.20797 + endloop + endfacet + facet normal -0.050659 -0.291162 -0.955332 + outer loop + vertex -338.391 -6.97036 3.18646 + vertex -343.766 -2.81948 2.20641 + vertex -328.744 -8.20048 3.04983 + endloop + endfacet + facet normal -0.0479479 -0.283955 -0.957638 + outer loop + vertex -343.766 -2.81948 2.20641 + vertex -323.131 -6.3091 2.20797 + vertex -328.744 -8.20048 3.04983 + endloop + endfacet + facet normal -0.0486182 -0.288719 -0.956179 + outer loop + vertex -338.391 -6.97036 3.18646 + vertex -349.419 -4.65047 3.0467 + vertex -343.766 -2.81948 2.20641 + endloop + endfacet + facet normal -0.0536943 -0.291311 -0.95512 + outer loop + vertex -359.177 -3.31163 3.18694 + vertex -364.505 0.879802 2.20811 + vertex -349.419 -4.65047 3.0467 + endloop + endfacet + facet normal -0.0506066 -0.283279 -0.957701 + outer loop + vertex -364.505 0.879802 2.20811 + vertex -343.766 -2.81948 2.20641 + vertex -349.419 -4.65047 3.0467 + endloop + endfacet + facet normal -0.0517984 -0.289083 -0.955902 + outer loop + vertex -359.177 -3.31163 3.18694 + vertex -370.287 -0.871548 3.05104 + vertex -364.505 0.879802 2.20811 + endloop + endfacet + facet normal -0.0551129 -0.28752 -0.956188 + outer loop + vertex -380.137 0.570453 3.1852 + vertex -385.427 4.83448 2.2079 + vertex -370.287 -0.871548 3.05104 + endloop + endfacet + facet normal -0.0536286 -0.28376 -0.957395 + outer loop + vertex -385.427 4.83448 2.2079 + vertex -364.505 0.879802 2.20811 + vertex -370.287 -0.871548 3.05104 + endloop + endfacet + facet normal -0.0546085 -0.286941 -0.956391 + outer loop + vertex -380.137 0.570453 3.1852 + vertex -391.335 3.14891 3.05099 + vertex -385.427 4.83448 2.2079 + endloop + endfacet + facet normal -0.0579084 -0.284972 -0.956785 + outer loop + vertex -401.307 4.72123 3.1862 + vertex -406.662 9.10347 2.2051 + vertex -391.335 3.14891 3.05099 + endloop + endfacet + facet normal -0.0564306 -0.281333 -0.957949 + outer loop + vertex -406.662 9.10347 2.2051 + vertex -385.427 4.83448 2.2079 + vertex -391.335 3.14891 3.05099 + endloop + endfacet + facet normal -0.0569605 -0.283898 -0.957161 + outer loop + vertex -401.307 4.72123 3.1862 + vertex -412.656 7.46346 3.04826 + vertex -406.662 9.10347 2.2051 + endloop + endfacet + facet normal -0.0606518 -0.283455 -0.957065 + outer loop + vertex -422.691 9.15745 3.18247 + vertex -428.187 13.6619 2.19663 + vertex -412.656 7.46346 3.04826 + endloop + endfacet + facet normal -0.0586207 -0.27858 -0.958622 + outer loop + vertex -428.187 13.6619 2.19663 + vertex -406.662 9.10347 2.2051 + vertex -412.656 7.46346 3.04826 + endloop + endfacet + facet normal -0.0599278 -0.282635 -0.957354 + outer loop + vertex -422.691 9.15745 3.18247 + vertex -433.967 12.0086 3.0466 + vertex -428.187 13.6619 2.19663 + endloop + endfacet + facet normal -0.0636572 -0.285608 -0.95623 + outer loop + vertex -443.76 13.7476 3.17913 + vertex -449.474 18.3119 2.19625 + vertex -433.967 12.0086 3.0466 + endloop + endfacet + facet normal -0.0610007 -0.279345 -0.958251 + outer loop + vertex -449.474 18.3119 2.19625 + vertex -428.187 13.6619 2.19663 + vertex -433.967 12.0086 3.0466 + endloop + endfacet + facet normal -0.0620396 -0.283727 -0.956896 + outer loop + vertex -443.76 13.7476 3.17913 + vertex -454.891 16.6597 3.03734 + vertex -449.474 18.3119 2.19625 + endloop + endfacet + facet normal -0.0676062 -0.290408 -0.954512 + outer loop + vertex -464.742 18.5038 3.17396 + vertex -469.733 22.8017 2.21982 + vertex -454.891 16.6597 3.03734 + endloop + endfacet + facet normal -0.0632343 -0.280286 -0.957832 + outer loop + vertex -469.733 22.8017 2.21982 + vertex -449.474 18.3119 2.19625 + vertex -454.891 16.6597 3.03734 + endloop + endfacet + facet normal -0.0661366 -0.28883 -0.955093 + outer loop + vertex -464.742 18.5038 3.17396 + vertex -476.086 21.5375 3.04208 + vertex -469.733 22.8017 2.21982 + endloop + endfacet + facet normal -0.0714859 -0.290878 -0.954086 + outer loop + vertex -486.383 23.4873 3.21916 + vertex -488.557 27.2715 2.22832 + vertex -476.086 21.5375 3.04208 + endloop + endfacet + facet normal -0.0675694 -0.282747 -0.956812 + outer loop + vertex -488.557 27.2715 2.22832 + vertex -469.733 22.8017 2.21982 + vertex -476.086 21.5375 3.04208 + endloop + endfacet + facet normal -0.0695375 -0.263053 -0.962272 + outer loop + vertex -504.196 28.5905 2.89175 + vertex -507.091 29.2372 2.92417 + vertex -502.432 30.76 2.17118 + endloop + endfacet + facet normal -0.0887442 -0.301892 -0.949203 + outer loop + vertex -508.799 28.8491 3.20724 + vertex -507.897 31.8129 2.18027 + vertex -507.091 29.2372 2.92417 + endloop + endfacet + facet normal -0.0581855 -0.293753 -0.954109 + outer loop + vertex -507.897 31.8129 2.18027 + vertex -502.432 30.76 2.17118 + vertex -507.091 29.2372 2.92417 + endloop + endfacet + facet normal 0.0467718 -0.206796 -0.977266 + outer loop + vertex 484.289 26.2533 2.21057 + vertex 484.813 30.935 1.24497 + vertex 500.423 30.5976 2.06347 + endloop + endfacet + facet normal 0.0471769 -0.194247 -0.979817 + outer loop + vertex 500.423 30.5976 2.06347 + vertex 484.813 30.935 1.24497 + vertex 498.389 35.1798 1.05711 + endloop + endfacet + facet normal 0.0484248 -0.204826 -0.9776 + outer loop + vertex 463.907 21.461 2.20505 + vertex 465.962 26.3325 1.28617 + vertex 484.289 26.2533 2.21057 + endloop + endfacet + facet normal 0.048393 -0.206954 -0.977153 + outer loop + vertex 484.289 26.2533 2.21057 + vertex 465.962 26.3325 1.28617 + vertex 484.813 30.935 1.24497 + endloop + endfacet + facet normal 0.0461023 -0.205274 -0.977618 + outer loop + vertex 442.633 16.7005 2.20141 + vertex 444.831 21.5871 1.27901 + vertex 463.907 21.461 2.20505 + endloop + endfacet + facet normal 0.0461251 -0.203913 -0.977902 + outer loop + vertex 463.907 21.461 2.20505 + vertex 444.831 21.5871 1.27901 + vertex 465.962 26.3325 1.28617 + endloop + endfacet + facet normal 0.0439176 -0.205563 -0.977658 + outer loop + vertex 421.632 12.1845 2.20757 + vertex 423.498 16.9964 1.27961 + vertex 442.633 16.7005 2.20141 + endloop + endfacet + facet normal 0.0439482 -0.20436 -0.977909 + outer loop + vertex 442.633 16.7005 2.20141 + vertex 423.498 16.9964 1.27961 + vertex 444.831 21.5871 1.27901 + endloop + endfacet + facet normal 0.0422423 -0.205813 -0.977679 + outer loop + vertex 400.665 7.87045 2.20981 + vertex 402.448 12.6466 1.28142 + vertex 421.632 12.1845 2.20757 + endloop + endfacet + facet normal 0.0422713 -0.204963 -0.977856 + outer loop + vertex 421.632 12.1845 2.20757 + vertex 402.448 12.6466 1.28142 + vertex 423.498 16.9964 1.27961 + endloop + endfacet + facet normal 0.0403593 -0.20593 -0.977734 + outer loop + vertex 379.622 3.74645 2.20979 + vertex 381.484 8.51044 1.28324 + vertex 400.665 7.87045 2.20981 + endloop + endfacet + facet normal 0.0403926 -0.205164 -0.977894 + outer loop + vertex 400.665 7.87045 2.20981 + vertex 381.484 8.51044 1.28324 + vertex 402.448 12.6466 1.28142 + endloop + endfacet + facet normal 0.0385794 -0.206351 -0.977717 + outer loop + vertex 358.434 -0.200293 2.20672 + vertex 360.494 4.57401 1.28036 + vertex 379.622 3.74645 2.20979 + endloop + endfacet + facet normal 0.0386357 -0.205296 -0.977937 + outer loop + vertex 379.622 3.74645 2.20979 + vertex 360.494 4.57401 1.28036 + vertex 381.484 8.51044 1.28324 + endloop + endfacet + facet normal 0.0364675 -0.207244 -0.977609 + outer loop + vertex 337.43 -3.91025 2.20968 + vertex 339.515 0.843709 1.27968 + vertex 358.434 -0.200293 2.20672 + endloop + endfacet + facet normal 0.0365792 -0.205536 -0.977966 + outer loop + vertex 358.434 -0.200293 2.20672 + vertex 339.515 0.843709 1.27968 + vertex 360.494 4.57401 1.28036 + endloop + endfacet + facet normal 0.0346391 -0.206587 -0.977815 + outer loop + vertex 316.723 -7.36522 2.20608 + vertex 318.636 -2.66404 1.28059 + vertex 337.43 -3.91025 2.20968 + endloop + endfacet + facet normal 0.0346466 -0.20649 -0.977835 + outer loop + vertex 337.43 -3.91025 2.20968 + vertex 318.636 -2.66404 1.28059 + vertex 339.515 0.843709 1.27968 + endloop + endfacet + facet normal 0.0324138 -0.207 -0.977804 + outer loop + vertex 295.766 -10.6571 2.20826 + vertex 297.717 -5.97456 1.28163 + vertex 316.723 -7.36522 2.20608 + endloop + endfacet + facet normal 0.0325161 -0.205772 -0.97806 + outer loop + vertex 316.723 -7.36522 2.20608 + vertex 297.717 -5.97456 1.28163 + vertex 318.636 -2.66404 1.28059 + endloop + endfacet + facet normal 0.0307088 -0.207321 -0.977791 + outer loop + vertex 274.517 -13.7949 2.20622 + vertex 276.655 -9.10552 1.27906 + vertex 295.766 -10.6571 2.20826 + endloop + endfacet + facet normal 0.0307963 -0.206363 -0.977991 + outer loop + vertex 295.766 -10.6571 2.20826 + vertex 276.655 -9.10552 1.27906 + vertex 297.717 -5.97456 1.28163 + endloop + endfacet + facet normal 0.028496 -0.207584 -0.977802 + outer loop + vertex 253.371 -16.707 2.20817 + vertex 255.538 -12.0384 1.28018 + vertex 274.517 -13.7949 2.20622 + endloop + endfacet + facet normal 0.0286159 -0.206417 -0.978046 + outer loop + vertex 274.517 -13.7949 2.20622 + vertex 255.538 -12.0384 1.28018 + vertex 276.655 -9.10552 1.27906 + endloop + endfacet + facet normal 0.0265003 -0.206915 -0.978 + outer loop + vertex 232.386 -19.3801 2.2051 + vertex 234.476 -14.7465 1.28142 + vertex 253.371 -16.707 2.20817 + endloop + endfacet + facet normal 0.0265229 -0.206716 -0.978041 + outer loop + vertex 253.371 -16.707 2.20817 + vertex 234.476 -14.7465 1.28142 + vertex 255.538 -12.0384 1.28018 + endloop + endfacet + facet normal 0.0241688 -0.20793 -0.977845 + outer loop + vertex 211.283 -21.8431 2.20724 + vertex 213.387 -17.2336 1.27909 + vertex 232.386 -19.3801 2.2051 + endloop + endfacet + facet normal 0.0244043 -0.206018 -0.978244 + outer loop + vertex 232.386 -19.3801 2.2051 + vertex 213.387 -17.2336 1.27909 + vertex 234.476 -14.7465 1.28142 + endloop + endfacet + facet normal 0.0220905 -0.206963 -0.978099 + outer loop + vertex 189.974 -24.1033 2.20424 + vertex 192.123 -19.5115 1.28117 + vertex 211.283 -21.8431 2.20724 + endloop + endfacet + facet normal 0.0220822 -0.207026 -0.978086 + outer loop + vertex 211.283 -21.8431 2.20724 + vertex 192.123 -19.5115 1.28117 + vertex 213.387 -17.2336 1.27909 + endloop + endfacet + facet normal 0.0195646 -0.208373 -0.977854 + outer loop + vertex 168.521 -26.1367 2.20831 + vertex 170.73 -21.5675 1.27886 + vertex 189.974 -24.1033 2.20424 + endloop + endfacet + facet normal 0.0199026 -0.20599 -0.978352 + outer loop + vertex 189.974 -24.1033 2.20424 + vertex 170.73 -21.5675 1.27886 + vertex 192.123 -19.5115 1.28117 + endloop + endfacet + facet normal 0.0174606 -0.20772 -0.978032 + outer loop + vertex 146.997 -27.9325 2.20546 + vertex 149.262 -23.3853 1.28014 + vertex 168.521 -26.1367 2.20831 + endloop + endfacet + facet normal 0.0175056 -0.207426 -0.978094 + outer loop + vertex 168.521 -26.1367 2.20831 + vertex 149.262 -23.3853 1.28014 + vertex 170.73 -21.5675 1.27886 + endloop + endfacet + facet normal 0.0147207 -0.207776 -0.978066 + outer loop + vertex 125.515 -29.4667 2.20804 + vertex 127.803 -24.9465 1.28224 + vertex 146.997 -27.9325 2.20546 + endloop + endfacet + facet normal 0.0149289 -0.206519 -0.978329 + outer loop + vertex 146.997 -27.9325 2.20546 + vertex 127.803 -24.9465 1.28224 + vertex 149.262 -23.3853 1.28014 + endloop + endfacet + facet normal 0.0124436 -0.207923 -0.978066 + outer loop + vertex 104.144 -30.7322 2.20518 + vertex 106.398 -26.2413 1.27915 + vertex 125.515 -29.4667 2.20804 + endloop + endfacet + facet normal 0.0126486 -0.206777 -0.978306 + outer loop + vertex 125.515 -29.4667 2.20804 + vertex 106.398 -26.2413 1.27915 + vertex 127.803 -24.9465 1.28224 + endloop + endfacet + facet normal 0.00958565 -0.208051 -0.978071 + outer loop + vertex 82.7385 -31.7325 2.20817 + vertex 84.9549 -27.2731 1.2813 + vertex 104.144 -30.7322 2.20518 + endloop + endfacet + facet normal 0.00984665 -0.20668 -0.978359 + outer loop + vertex 104.144 -30.7322 2.20518 + vertex 84.9549 -27.2731 1.2813 + vertex 106.398 -26.2413 1.27915 + endloop + endfacet + facet normal 0.00733538 -0.208491 -0.977997 + outer loop + vertex 61.1787 -32.4862 2.20714 + vertex 63.4548 -28.0525 1.27903 + vertex 82.7385 -31.7325 2.20817 + endloop + endfacet + facet normal 0.00761199 -0.207115 -0.978287 + outer loop + vertex 82.7385 -31.7325 2.20817 + vertex 63.4548 -28.0525 1.27903 + vertex 84.9549 -27.2731 1.2813 + endloop + endfacet + facet normal 0.00506365 -0.207923 -0.978132 + outer loop + vertex 39.5521 -33.0033 2.2051 + vertex 41.9121 -28.594 1.28004 + vertex 61.1787 -32.4862 2.20714 + endloop + endfacet + facet normal 0.00516851 -0.207429 -0.978236 + outer loop + vertex 61.1787 -32.4862 2.20714 + vertex 41.9121 -28.594 1.28004 + vertex 63.4548 -28.0525 1.27903 + endloop + endfacet + facet normal 0.00273614 -0.208219 -0.978078 + outer loop + vertex 18.1163 -33.2904 2.20626 + vertex 20.4666 -28.9089 1.28007 + vertex 39.5521 -33.0033 2.2051 + endloop + endfacet + facet normal 0.00303579 -0.206886 -0.97836 + outer loop + vertex 39.5521 -33.0033 2.2051 + vertex 20.4666 -28.9089 1.28007 + vertex 41.9121 -28.594 1.28004 + endloop + endfacet + facet normal 0.00065149 -0.208081 -0.978111 + outer loop + vertex -3.15577 -33.3618 2.20727 + vertex -0.85661 -29.0069 1.28236 + vertex 18.1163 -33.2904 2.20626 + endloop + endfacet + facet normal 0.000847802 -0.20725 -0.978288 + outer loop + vertex 18.1163 -33.2904 2.20626 + vertex -0.85661 -29.0069 1.28236 + vertex 20.4666 -28.9089 1.28007 + endloop + endfacet + facet normal -0.00131704 -0.208743 -0.97797 + outer loop + vertex -24.4458 -33.2281 2.20741 + vertex -22.1314 -28.8945 1.27931 + vertex -3.15577 -33.3618 2.20727 + endloop + endfacet + facet normal -0.000954862 -0.20727 -0.978283 + outer loop + vertex -3.15577 -33.3618 2.20727 + vertex -22.1314 -28.8945 1.27931 + vertex -0.85661 -29.0069 1.28236 + endloop + endfacet + facet normal -0.00342026 -0.208312 -0.978056 + outer loop + vertex -45.7508 -32.8819 2.20817 + vertex -43.4779 -28.5679 1.28141 + vertex -24.4458 -33.2281 2.20741 + endloop + endfacet + facet normal -0.00327485 -0.207742 -0.978178 + outer loop + vertex -24.4458 -33.2281 2.20741 + vertex -43.4779 -28.5679 1.28141 + vertex -22.1314 -28.8945 1.27931 + endloop + endfacet + facet normal -0.00545987 -0.208163 -0.978079 + outer loop + vertex -67.229 -32.3032 2.20491 + vertex -64.8959 -28.0134 1.2789 + vertex -45.7508 -32.8819 2.20817 + endloop + endfacet + facet normal -0.00525423 -0.207386 -0.978245 + outer loop + vertex -45.7508 -32.8819 2.20817 + vertex -64.8959 -28.0134 1.2789 + vertex -43.4779 -28.5679 1.28141 + endloop + endfacet + facet normal -0.00809893 -0.208215 -0.97805 + outer loop + vertex -88.8819 -31.4726 2.2074 + vertex -86.4097 -27.2136 1.28022 + vertex -67.229 -32.3032 2.20491 + endloop + endfacet + facet normal -0.00775479 -0.206966 -0.978317 + outer loop + vertex -67.229 -32.3032 2.20491 + vertex -86.4097 -27.2136 1.28022 + vertex -64.8959 -28.0134 1.2789 + endloop + endfacet + facet normal -0.0104384 -0.207741 -0.978128 + outer loop + vertex -110.285 -30.3961 2.20717 + vertex -107.887 -26.1586 1.28159 + vertex -88.8819 -31.4726 2.2074 + endloop + endfacet + facet normal -0.0102314 -0.207027 -0.978282 + outer loop + vertex -88.8819 -31.4726 2.2074 + vertex -107.887 -26.1586 1.28159 + vertex -86.4097 -27.2136 1.28022 + endloop + endfacet + facet normal -0.0131667 -0.208507 -0.977932 + outer loop + vertex -131.55 -29.0577 2.20811 + vertex -129.258 -24.8449 1.27904 + vertex -110.285 -30.3961 2.20717 + endloop + endfacet + facet normal -0.0125816 -0.206577 -0.97835 + outer loop + vertex -110.285 -30.3961 2.20717 + vertex -129.258 -24.8449 1.27904 + vertex -107.887 -26.1586 1.28159 + endloop + endfacet + facet normal -0.0154086 -0.207678 -0.978076 + outer loop + vertex -153.071 -27.4473 2.20522 + vertex -150.66 -23.2693 1.2801 + vertex -131.55 -29.0577 2.20811 + endloop + endfacet + facet normal -0.0153163 -0.207383 -0.97814 + outer loop + vertex -131.55 -29.0577 2.20811 + vertex -150.66 -23.2693 1.2801 + vertex -129.258 -24.8449 1.27904 + endloop + endfacet + facet normal -0.0180932 -0.207778 -0.978009 + outer loop + vertex -174.552 -25.591 2.20823 + vertex -172.064 -21.4457 1.28155 + vertex -153.071 -27.4473 2.20522 + endloop + endfacet + facet normal -0.0176537 -0.206432 -0.978302 + outer loop + vertex -153.071 -27.4473 2.20522 + vertex -172.064 -21.4457 1.28155 + vertex -150.66 -23.2693 1.2801 + endloop + endfacet + facet normal -0.0201608 -0.207486 -0.97803 + outer loop + vertex -195.792 -23.5117 2.20495 + vertex -193.338 -19.3908 1.28014 + vertex -174.552 -25.591 2.20823 + endloop + endfacet + facet normal -0.019904 -0.206733 -0.978195 + outer loop + vertex -174.552 -25.591 2.20823 + vertex -193.338 -19.3908 1.28014 + vertex -172.064 -21.4457 1.28155 + endloop + endfacet + facet normal -0.0227943 -0.208017 -0.97786 + outer loop + vertex -217.022 -21.1948 2.20698 + vertex -214.536 -17.1035 1.27868 + vertex -195.792 -23.5117 2.20495 + endloop + endfacet + facet normal -0.0221956 -0.20632 -0.978233 + outer loop + vertex -195.792 -23.5117 2.20495 + vertex -214.536 -17.1035 1.27868 + vertex -193.338 -19.3908 1.28014 + endloop + endfacet + facet normal -0.0249679 -0.207711 -0.977871 + outer loop + vertex -238.173 -18.6591 2.20839 + vertex -235.764 -14.5793 1.28029 + vertex -217.022 -21.1948 2.20698 + endloop + endfacet + facet normal -0.0246781 -0.206915 -0.978048 + outer loop + vertex -217.022 -21.1948 2.20698 + vertex -235.764 -14.5793 1.28029 + vertex -214.536 -17.1035 1.27868 + endloop + endfacet + facet normal -0.0269001 -0.206847 -0.978003 + outer loop + vertex -259.434 -15.8829 2.20601 + vertex -257.057 -11.8204 1.28143 + vertex -238.173 -18.6591 2.20839 + endloop + endfacet + facet normal -0.0268277 -0.206653 -0.978046 + outer loop + vertex -238.173 -18.6591 2.20839 + vertex -257.057 -11.8204 1.28143 + vertex -235.764 -14.5793 1.28029 + endloop + endfacet + facet normal -0.0292056 -0.207283 -0.977845 + outer loop + vertex -280.997 -12.8486 2.20686 + vertex -278.411 -8.83541 1.27891 + vertex -259.434 -15.8829 2.20601 + endloop + endfacet + facet normal -0.0286594 -0.205854 -0.978163 + outer loop + vertex -259.434 -15.8829 2.20601 + vertex -278.411 -8.83541 1.27891 + vertex -257.057 -11.8204 1.28143 + endloop + endfacet + facet normal -0.0311048 -0.206665 -0.977917 + outer loop + vertex -302.322 -9.64003 2.20706 + vertex -299.671 -5.65721 1.28104 + vertex -280.997 -12.8486 2.20686 + endloop + endfacet + facet normal -0.0309264 -0.206214 -0.978018 + outer loop + vertex -280.997 -12.8486 2.20686 + vertex -299.671 -5.65721 1.28104 + vertex -278.411 -8.83541 1.27891 + endloop + endfacet + facet normal -0.0332304 -0.207332 -0.977706 + outer loop + vertex -323.131 -6.3091 2.20797 + vertex -320.607 -2.33218 1.27885 + vertex -302.322 -9.64003 2.20706 + endloop + endfacet + facet normal -0.0325698 -0.205725 -0.978068 + outer loop + vertex -302.322 -9.64003 2.20706 + vertex -320.607 -2.33218 1.27885 + vertex -299.671 -5.65721 1.28104 + endloop + endfacet + facet normal -0.0348897 -0.206748 -0.977772 + outer loop + vertex -343.766 -2.81948 2.20641 + vertex -341.308 1.13885 1.28171 + vertex -323.131 -6.3091 2.20797 + endloop + endfacet + facet normal -0.0347447 -0.206404 -0.97785 + outer loop + vertex -323.131 -6.3091 2.20797 + vertex -341.308 1.13885 1.28171 + vertex -320.607 -2.33218 1.27885 + endloop + endfacet + facet normal -0.0371015 -0.207555 -0.97752 + outer loop + vertex -364.505 0.879802 2.20811 + vertex -361.938 4.79045 1.28035 + vertex -343.766 -2.81948 2.20641 + endloop + endfacet + facet normal -0.0363718 -0.205859 -0.977905 + outer loop + vertex -343.766 -2.81948 2.20641 + vertex -361.938 4.79045 1.28035 + vertex -341.308 1.13885 1.28171 + endloop + endfacet + facet normal -0.0390699 -0.206742 -0.977615 + outer loop + vertex -385.427 4.83448 2.2079 + vertex -382.697 8.70089 1.28116 + vertex -364.505 0.879802 2.20811 + endloop + endfacet + facet normal -0.0389199 -0.206402 -0.977693 + outer loop + vertex -364.505 0.879802 2.20811 + vertex -382.697 8.70089 1.28116 + vertex -361.938 4.79045 1.28035 + endloop + endfacet + facet normal -0.0410734 -0.204955 -0.977909 + outer loop + vertex -406.662 9.10347 2.2051 + vertex -403.83 12.9625 1.27738 + vertex -385.427 4.83448 2.2079 + endloop + endfacet + facet normal -0.0412193 -0.205277 -0.977836 + outer loop + vertex -385.427 4.83448 2.2079 + vertex -403.83 12.9625 1.27738 + vertex -382.697 8.70089 1.28116 + endloop + endfacet + facet normal -0.0425257 -0.202618 -0.978334 + outer loop + vertex -428.187 13.6619 2.19663 + vertex -425.517 17.5796 1.26922 + vertex -406.662 9.10347 2.2051 + endloop + endfacet + facet normal -0.0429801 -0.203604 -0.978109 + outer loop + vertex -406.662 9.10347 2.2051 + vertex -425.517 17.5796 1.26922 + vertex -403.83 12.9625 1.27738 + endloop + endfacet + facet normal -0.0443402 -0.203074 -0.978159 + outer loop + vertex -449.474 18.3119 2.19625 + vertex -447.261 22.2865 1.27075 + vertex -428.187 13.6619 2.19663 + endloop + endfacet + facet normal -0.0437539 -0.201808 -0.978447 + outer loop + vertex -428.187 13.6619 2.19663 + vertex -447.261 22.2865 1.27075 + vertex -425.517 17.5796 1.26922 + endloop + endfacet + facet normal -0.047747 -0.210309 -0.976468 + outer loop + vertex -469.733 22.8017 2.21982 + vertex -467.427 26.5014 1.31025 + vertex -449.474 18.3119 2.19625 + endloop + endfacet + facet normal -0.0443586 -0.203064 -0.97816 + outer loop + vertex -449.474 18.3119 2.19625 + vertex -467.427 26.5014 1.31025 + vertex -447.261 22.2865 1.27075 + endloop + endfacet + facet normal -0.0532832 -0.22255 -0.973464 + outer loop + vertex -488.557 27.2715 2.22832 + vertex -482.588 29.3247 1.4322 + vertex -469.733 22.8017 2.21982 + endloop + endfacet + facet normal -0.0470918 -0.210704 -0.976415 + outer loop + vertex -469.733 22.8017 2.21982 + vertex -482.588 29.3247 1.4322 + vertex -467.427 26.5014 1.31025 + endloop + endfacet + facet normal -0.0412543 -0.205673 -0.977751 + outer loop + vertex -507.897 31.8129 2.18027 + vertex -505.881 35.4469 1.3308 + vertex -502.432 30.76 2.17118 + endloop + endfacet + facet normal -0.0415891 -0.205908 -0.977687 + outer loop + vertex -502.432 30.76 2.17118 + vertex -505.881 35.4469 1.3308 + vertex -496.639 34.1271 1.21564 + endloop + endfacet + facet normal 0.122074 -0.812973 0.569362 + outer loop + vertex 500.454 63.7901 33.1332 + vertex 499.375 65.9509 36.4498 + vertex 491.293 62.4588 33.1963 + endloop + endfacet + facet normal 0.135518 -0.77029 0.623128 + outer loop + vertex 503.135 61.4576 29.6666 + vertex 500.454 63.7901 33.1332 + vertex 494.407 60.3919 30.2473 + endloop + endfacet + facet normal 0.119367 -0.705171 0.698917 + outer loop + vertex 505.196 59.4283 27.2672 + vertex 503.135 61.4576 29.6666 + vertex 503.546 59.472 27.5931 + endloop + endfacet + facet normal 0.0389525 -0.624351 0.780172 + outer loop + vertex 506.267 57.0964 25.3476 + vertex 505.196 59.4283 27.2672 + vertex 504.853 58.0385 26.1721 + endloop + endfacet + facet normal -0.0470272 -0.4923 0.869154 + outer loop + vertex 506.835 54.6873 24.0138 + vertex 506.267 57.0964 25.3476 + vertex 506.158 55.279 24.3123 + endloop + endfacet + facet normal -0.557104 -0.0959753 0.824878 + outer loop + vertex 505.992 51.7297 23.1001 + vertex 506.835 54.6873 24.0138 + vertex 506.529 54.0004 23.7267 + endloop + endfacet + facet normal 0.0575286 -0.23338 0.970682 + outer loop + vertex 506.551 47.0265 21.9362 + vertex 505.992 51.7297 23.1001 + vertex 498.234 47.396 22.518 + endloop + endfacet + facet normal 0.0655623 -0.242985 0.967812 + outer loop + vertex 507.658 35.3077 19.1118 + vertex 505.761 40.6922 20.5922 + vertex 499.284 35.0522 19.615 + endloop + endfacet + facet normal 0.0826491 -0.301078 0.950011 + outer loop + vertex 507.791 31.0352 17.7462 + vertex 507.658 35.3077 19.1118 + vertex 501.75 31.5916 18.4482 + endloop + endfacet + facet normal 0.195387 -0.354018 0.914601 + outer loop + vertex 509.226 28.4228 16.4285 + vertex 507.791 31.0352 17.7462 + vertex 507.709 29.0161 16.9823 + endloop + endfacet + facet normal 0.162056 -0.550973 0.818637 + outer loop + vertex 509.412 26.4192 15.0432 + vertex 509.226 28.4228 16.4285 + vertex 508.17 26.462 15.318 + endloop + endfacet + facet normal 0.178912 -0.714243 0.676644 + outer loop + vertex 509.27 24.9242 13.5029 + vertex 509.412 26.4192 15.0432 + vertex 508.039 25.0002 13.9085 + endloop + endfacet + facet normal 0.19598 -0.851414 0.486504 + outer loop + vertex 509.196 23.9317 11.7953 + vertex 509.27 24.9242 13.5029 + vertex 507.938 23.8779 12.2081 + endloop + endfacet + facet normal 0.142469 -0.954537 0.261842 + outer loop + vertex 509.292 23.534 10.2934 + vertex 509.196 23.9317 11.7953 + vertex 508.034 23.3097 10.1604 + endloop + endfacet + facet normal 0.180846 -0.981957 -0.0552821 + outer loop + vertex 509.195 23.6025 8.75831 + vertex 509.292 23.534 10.2934 + vertex 508.034 23.3097 10.1604 + endloop + endfacet + facet normal 0.276071 -0.900513 -0.335947 + outer loop + vertex 509.172 24.2596 6.97821 + vertex 509.195 23.6025 8.75831 + vertex 507.778 23.4462 8.01297 + endloop + endfacet + facet normal 0.258076 -0.764228 -0.59106 + outer loop + vertex 509.214 25.4997 5.39314 + vertex 509.172 24.2596 6.97821 + vertex 507.802 24.3468 6.26721 + endloop + endfacet + facet normal 0.211877 -0.599622 -0.771726 + outer loop + vertex 509.171 27.208 4.05384 + vertex 509.214 25.4997 5.39314 + vertex 507.961 25.7682 4.84033 + endloop + endfacet + facet normal 0.403853 -0.294807 -0.86602 + outer loop + vertex 508.438 29.5567 2.9129 + vertex 509.171 27.208 4.05384 + vertex 508.543 28.0281 3.48188 + endloop + endfacet + facet normal 0.0605064 -0.308678 -0.94924 + outer loop + vertex 507.685 32.1149 2.03299 + vertex 508.438 29.5567 2.9129 + vertex 500.423 30.5976 2.06347 + endloop + endfacet + facet normal 0.0387425 -0.205083 -0.977977 + outer loop + vertex 507.098 34.852 1.43578 + vertex 507.685 32.1149 2.03299 + vertex 500.423 30.5976 2.06347 + endloop + endfacet + facet normal -0.0330299 -0.143407 -0.989113 + outer loop + vertex -509.269 35.1963 1.48026 + vertex -508.783 39.4702 0.84439 + vertex -505.881 35.4469 1.3308 + endloop + endfacet + facet normal 0.000753301 -0.202315 -0.97932 + outer loop + vertex -509.326 32.5063 2.03593 + vertex -509.269 35.1963 1.48026 + vertex -507.897 31.8129 2.18027 + endloop + endfacet + facet normal -0.047437 -0.296333 -0.953906 + outer loop + vertex -508.951 29.7198 2.88291 + vertex -509.326 32.5063 2.03593 + vertex -507.897 31.8129 2.18027 + endloop + endfacet + facet normal -0.265781 0.34818 0.898961 + outer loop + vertex -508.44 26.9019 4.12532 + vertex -508.951 29.7198 2.88291 + vertex -508.869 27.7446 3.67214 + endloop + endfacet + facet normal 0.0981491 0.629782 0.770546 + outer loop + vertex -508.463 25.236 5.48987 + vertex -508.44 26.9019 4.12532 + vertex -508.846 25.3324 5.45995 + endloop + endfacet + facet normal 0.211821 0.787705 0.578492 + outer loop + vertex -508.686 24.1074 7.10827 + vertex -508.463 25.236 5.48987 + vertex -508.93 24.2552 6.99646 + endloop + endfacet + facet normal 0.440256 0.845722 0.301546 + outer loop + vertex -508.783 23.5251 8.88255 + vertex -508.686 24.1074 7.10827 + vertex -509.03 23.6746 8.82407 + endloop + endfacet + facet normal 0.797936 0.602606 0.0127822 + outer loop + vertex -508.72 23.4109 10.3219 + vertex -508.783 23.5251 8.88255 + vertex -508.948 23.701 10.8783 + endloop + endfacet + facet normal 0.465992 0.848327 -0.251383 + outer loop + vertex -508.693 23.8672 11.9117 + vertex -508.72 23.4109 10.3219 + vertex -508.948 23.701 10.8783 + endloop + endfacet + facet normal 0.160059 0.851877 -0.498684 + outer loop + vertex -508.602 24.8527 13.6242 + vertex -508.693 23.8672 11.9117 + vertex -508.933 24.5402 12.9841 + endloop + endfacet + facet normal 0.052781 0.710067 -0.702153 + outer loop + vertex -508.544 26.3272 15.1198 + vertex -508.602 24.8527 13.6242 + vertex -508.894 25.8204 14.5809 + endloop + endfacet + facet normal -0.0595115 0.54263 -0.837861 + outer loop + vertex -508.626 28.4243 16.4838 + vertex -508.544 26.3272 15.1198 + vertex -508.923 27.4308 15.8615 + endloop + endfacet + facet normal -0.42938 0.347197 -0.833719 + outer loop + vertex -508.729 31.2422 17.7102 + vertex -508.626 28.4243 16.4838 + vertex -508.85 29.6765 17.1207 + endloop + endfacet + facet normal -0.0944924 -0.304771 0.947727 + outer loop + vertex -509.363 35.8267 19.1212 + vertex -508.729 31.2422 17.7102 + vertex -506.714 33.1492 18.5243 + endloop + endfacet + facet normal -0.0757387 -0.241938 0.967331 + outer loop + vertex -509.268 41.9962 20.6717 + vertex -509.363 35.8267 19.1212 + vertex -505.776 37.9755 19.9395 + endloop + endfacet + facet normal -0.0560004 -0.232655 0.970946 + outer loop + vertex -506.854 51.9309 23.0685 + vertex -508.767 47.7226 21.9498 + vertex -506.416 50.0813 22.6506 + endloop + endfacet + facet normal 0.18334 0.272325 -0.944577 + outer loop + vertex -505.856 54.4532 23.9895 + vertex -506.854 51.9309 23.0685 + vertex -506.523 54.3103 23.8188 + endloop + endfacet + facet normal 0.337015 0.400219 -0.852201 + outer loop + vertex -505.324 56.9938 25.3929 + vertex -505.856 54.4532 23.9895 + vertex -506.076 56.0029 24.6302 + endloop + endfacet + facet normal 0.325649 0.532277 -0.781431 + outer loop + vertex -504.614 59.3872 27.319 + vertex -505.324 56.9938 25.3929 + vertex -505.036 58.8712 26.7915 + endloop + endfacet + facet normal 0.854574 0.293027 -0.428764 + outer loop + vertex -504.152 61.7843 29.8788 + vertex -504.614 59.3872 27.319 + vertex -504.513 60.146 28.0383 + endloop + endfacet + facet normal -0.130587 -0.78668 0.603391 + outer loop + vertex -502.812 64.9071 34.2401 + vertex -504.152 61.7843 29.8788 + vertex -500.731 62.179 31.1337 + endloop + endfacet + facet normal -0.0948698 -0.830223 0.549299 + outer loop + vertex -501.789 67.029 37.6239 + vertex -502.812 64.9071 34.2401 + vertex -499.669 66.038 36.4921 + endloop + endfacet + facet normal -0.174616 -0.933271 0.31387 + outer loop + vertex -492.742 66.1796 38.1092 + vertex -498.556 67.9088 40.0162 + vertex -495.868 67.088 39.0706 + endloop + endfacet + facet normal -0.127752 -0.891728 0.434166 + outer loop + vertex -486.939 64.5184 36.4045 + vertex -492.742 66.1796 38.1092 + vertex -489.875 65.3234 37.1941 + endloop + endfacet + facet normal -0.00316493 -0.676872 0.736094 + outer loop + vertex -480.386 62.7394 34.7969 + vertex -486.939 64.5184 36.4045 + vertex -484.901 63.939 35.8805 + endloop + endfacet + facet normal 0.28104 0.362978 0.888405 + outer loop + vertex -472.834 60.7471 33.2218 + vertex -480.386 62.7394 34.7969 + vertex -477.697 62.0049 34.2463 + endloop + endfacet + facet normal 0.257082 0.965887 0.0311807 + outer loop + vertex -467.436 59.3423 32.2275 + vertex -472.834 60.7471 33.2218 + vertex -468.678 59.6628 32.5424 + endloop + endfacet + facet normal 0.222084 0.968815 -0.109889 + outer loop + vertex -462.275 58.0767 31.4994 + vertex -467.436 59.3423 32.2275 + vertex -468.678 59.6628 32.5424 + endloop + endfacet + facet normal 0.160972 0.19615 0.967271 + outer loop + vertex -453.731 56.0827 30.4819 + vertex -462.275 58.0767 31.4994 + vertex -459.252 57.3218 31.1494 + endloop + endfacet + facet normal -0.0472526 -0.547816 0.835263 + outer loop + vertex -444.401 54.0234 29.6591 + vertex -453.731 56.0827 30.4819 + vertex -449.926 55.1035 30.0549 + endloop + endfacet + facet normal -0.0688649 -0.576679 0.814064 + outer loop + vertex -437.14 52.3557 29.0919 + vertex -444.401 54.0234 29.6591 + vertex -442.216 53.336 29.3569 + endloop + endfacet + facet normal -0.0198013 -0.321236 0.946792 + outer loop + vertex -428.804 50.5731 28.6614 + vertex -437.14 52.3557 29.0919 + vertex -436.418 52.0254 28.9949 + endloop + endfacet + facet normal 0.0411889 -0.0643039 0.99708 + outer loop + vertex -422.084 49.0503 28.2856 + vertex -428.804 50.5731 28.6614 + vertex -421.839 48.8353 28.2616 + endloop + endfacet + facet normal 0.0231047 -0.084871 0.996124 + outer loop + vertex -418.729 48.3235 28.1459 + vertex -422.084 49.0503 28.2856 + vertex -421.839 48.8353 28.2616 + endloop + endfacet + facet normal 0.0758777 0.242377 0.96721 + outer loop + vertex -412.125 46.9935 27.9611 + vertex -418.729 48.3235 28.1459 + vertex -421.839 48.8353 28.2616 + endloop + endfacet + facet normal 0.015805 -0.0767986 0.996921 + outer loop + vertex -404.425 45.3821 27.7149 + vertex -412.125 46.9935 27.9611 + vertex -403.558 44.9696 27.6694 + endloop + endfacet + facet normal 0.00743597 -0.0531541 0.998559 + outer loop + vertex -385.049 41.4331 27.2949 + vertex -391.051 42.5967 27.4015 + vertex -382.442 40.7186 27.2374 + endloop + endfacet + facet normal 0.00999274 -0.00135757 0.999949 + outer loop + vertex -370.505 38.6079 27.1153 + vertex -375.78 39.6389 27.1694 + vertex -382.442 40.7186 27.2374 + endloop + endfacet + facet normal -0.0362012 -0.260742 0.964729 + outer loop + vertex -258.796 20.4014 26.8729 + vertex -267.195 21.5991 26.8814 + vertex -256.495 19.8582 26.8124 + endloop + endfacet + facet normal -0.0394302 -0.305535 0.951364 + outer loop + vertex -243.462 18.2724 26.8433 + vertex -248.762 18.9915 26.8545 + vertex -256.495 19.8582 26.8124 + endloop + endfacet + facet normal -0.0295805 -0.2773 0.960328 + outer loop + vertex -194.903 12.5865 26.8047 + vertex -202.746 13.4834 26.8221 + vertex -192.943 12.2057 26.7551 + endloop + endfacet + facet normal -0.022609 -0.239122 0.970726 + outer loop + vertex -179.626 11.0575 26.7824 + vertex -187.231 11.9129 26.816 + vertex -192.943 12.2057 26.7551 + endloop + endfacet + facet normal -0.0186525 -0.261998 0.964888 + outer loop + vertex -130.381 6.9229 26.7077 + vertex -138.309 7.57042 26.7303 + vertex -128.814 6.64642 26.6629 + endloop + endfacet + facet normal -0.00922319 -0.242743 0.970047 + outer loop + vertex -66.5924 3.52148 26.6272 + vertex -74.5067 3.89062 26.6443 + vertex -65.0777 3.2961 26.5852 + endloop + endfacet + facet normal -0.000626733 -0.219598 0.97559 + outer loop + vertex -5.80822 2.37814 26.6066 + vertex -12.5209 2.30094 26.5849 + vertex -1.9402 2.11842 26.5506 + endloop + endfacet + facet normal 0.000455878 -0.22301 0.974816 + outer loop + vertex 12.0453 2.2932 26.584 + vertex 5.43999 2.37828 26.6066 + vertex -1.9402 2.11842 26.5506 + endloop + endfacet + facet normal 0.00601153 -0.214697 0.976662 + outer loop + vertex 58.4402 3.33042 26.635 + vertex 51.3768 3.00336 26.6066 + vertex 61.3081 3.16554 26.5811 + endloop + endfacet + facet normal 0.0128705 -0.220922 0.975207 + outer loop + vertex 122.533 6.50114 26.7169 + vertex 114.869 5.91475 26.6852 + vertex 125.033 6.38388 26.6574 + endloop + endfacet + facet normal 0.0270256 -0.294975 0.955123 + outer loop + vertex 181.34 11.1912 26.7798 + vertex 175.874 10.6925 26.7805 + vertex 168.834 9.85913 26.7223 + endloop + endfacet + facet normal 0.0342118 -0.266749 0.963158 + outer loop + vertex 249.114 19.0404 26.8623 + vertex 243.278 18.237 26.8471 + vertex 252.699 19.3316 26.8156 + endloop + endfacet + facet normal 0.0407196 -0.291495 0.955705 + outer loop + vertex 266.564 21.5032 26.8872 + vertex 258.813 20.3897 26.8779 + vertex 252.699 19.3316 26.8156 + endloop + endfacet + facet normal 0.0194723 -0.155812 0.987595 + outer loop + vertex 376.225 39.7389 27.2099 + vertex 370.274 38.5862 27.1454 + vertex 378.74 40.0039 27.2021 + endloop + endfacet + facet normal 0.00823843 -0.116202 0.993191 + outer loop + vertex 390.482 42.4462 27.3905 + vertex 385.365 41.4854 27.3205 + vertex 378.74 40.0039 27.2021 + endloop + endfacet + facet normal -0.0647654 0.155673 0.985683 + outer loop + vertex 410.834 46.6771 27.8917 + vertex 403.197 45.0564 27.6459 + vertex 398.632 43.896 27.5293 + endloop + endfacet + facet normal -0.0731622 0.224297 0.971771 + outer loop + vertex 418.28 48.1905 28.103 + vertex 410.834 46.6771 27.8917 + vertex 420.155 48.3883 28.1985 + endloop + endfacet + facet normal -0.0559008 0.0483425 0.997265 + outer loop + vertex 421.784 48.9642 28.2619 + vertex 418.28 48.1905 28.103 + vertex 420.155 48.3883 28.1985 + endloop + endfacet + facet normal -0.108015 0.198275 0.974177 + outer loop + vertex 428.859 50.6223 28.7089 + vertex 421.784 48.9642 28.2619 + vertex 420.155 48.3883 28.1985 + endloop + endfacet + facet normal 0.0246986 -0.35914 0.932957 + outer loop + vertex 436.889 52.3992 29.1803 + vertex 428.859 50.6223 28.7089 + vertex 438.118 52.4137 29.1534 + endloop + endfacet + facet normal 0.0248396 -0.414019 0.909929 + outer loop + vertex 443.789 53.8676 29.6601 + vertex 436.889 52.3992 29.1803 + vertex 438.118 52.4137 29.1534 + endloop + endfacet + facet normal 0.0698232 -0.625089 0.777424 + outer loop + vertex 452.868 55.8647 30.4505 + vertex 443.789 53.8676 29.6601 + vertex 447.006 54.421 29.8162 + endloop + endfacet + facet normal 0.0791517 -0.685344 0.723905 + outer loop + vertex 461.055 57.7994 31.3869 + vertex 452.868 55.8647 30.4505 + vertex 455.726 56.4918 30.7316 + endloop + endfacet + facet normal -0.237369 0.971401 0.00597499 + outer loop + vertex 467.047 59.2584 32.1987 + vertex 461.055 57.7994 31.3869 + vertex 465.831 58.9622 32.0723 + endloop + endfacet + facet normal -0.216549 0.961275 -0.170458 + outer loop + vertex 472.256 60.5973 33.1312 + vertex 467.047 59.2584 32.1987 + vertex 465.831 58.9622 32.0723 + endloop + endfacet + facet normal -0.191679 -0.0535796 0.979994 + outer loop + vertex 480.327 62.7231 34.8259 + vertex 472.256 60.5973 33.1312 + vertex 475.436 61.4147 33.7978 + endloop + endfacet + facet normal 0.019584 -0.709771 0.70416 + outer loop + vertex 487.968 64.8045 36.7114 + vertex 480.327 62.7231 34.8259 + vertex 485.671 64.1481 36.1137 + endloop + endfacet + facet normal 0.123593 -0.885217 0.448459 + outer loop + vertex 493.585 66.4385 38.389 + vertex 487.968 64.8045 36.7114 + vertex 491.348 65.7219 37.5908 + endloop + endfacet + facet normal -0.26357 0.964269 0.0267529 + outer loop + vertex 475.436 61.4147 33.7978 + vertex 485.671 64.1481 36.1137 + vertex 480.327 62.7231 34.8259 + endloop + endfacet + facet normal 0.0914262 -0.826226 0.555871 + outer loop + vertex 485.671 64.1481 36.1137 + vertex 488.918 65.0131 36.8652 + vertex 487.968 64.8045 36.7114 + endloop + endfacet + facet normal 0.117847 -0.878311 0.463337 + outer loop + vertex 488.918 65.0131 36.8652 + vertex 491.348 65.7219 37.5908 + vertex 487.968 64.8045 36.7114 + endloop + endfacet + facet normal 0.123784 -0.885385 0.448075 + outer loop + vertex 491.348 65.7219 37.5908 + vertex 495.666 66.9795 38.883 + vertex 493.585 66.4385 38.389 + endloop + endfacet + facet normal -0.247711 0.9647 0.0894048 + outer loop + vertex 455.726 56.4918 30.7316 + vertex 465.831 58.9622 32.0723 + vertex 461.055 57.7994 31.3869 + endloop + endfacet + facet normal -0.237622 0.96976 -0.0556923 + outer loop + vertex 465.831 58.9622 32.0723 + vertex 475.436 61.4147 33.7978 + vertex 472.256 60.5973 33.1312 + endloop + endfacet + facet normal 0.0897227 -0.621237 0.778469 + outer loop + vertex 438.118 52.4137 29.1534 + vertex 443.016 53.4939 29.451 + vertex 443.789 53.8676 29.6601 + endloop + endfacet + facet normal 0.060264 -0.579485 0.812752 + outer loop + vertex 443.016 53.4939 29.451 + vertex 447.006 54.421 29.8162 + vertex 443.789 53.8676 29.6601 + endloop + endfacet + facet normal -0.0167815 -0.344298 0.93871 + outer loop + vertex 447.006 54.421 29.8162 + vertex 455.726 56.4918 30.7316 + vertex 452.868 55.8647 30.4505 + endloop + endfacet + facet normal 0.171547 0.251157 0.952624 + outer loop + vertex -459.252 57.3218 31.1494 + vertex -449.926 55.1035 30.0549 + vertex -453.731 56.0827 30.4819 + endloop + endfacet + facet normal -0.03291 -0.487988 0.87223 + outer loop + vertex -449.926 55.1035 30.0549 + vertex -442.216 53.336 29.3569 + vertex -444.401 54.0234 29.6591 + endloop + endfacet + facet normal -0.00741999 -0.296597 0.954974 + outer loop + vertex -442.216 53.336 29.3569 + vertex -436.418 52.0254 28.9949 + vertex -437.14 52.3557 29.0919 + endloop + endfacet + facet normal 0.259161 0.964752 0.0457077 + outer loop + vertex -477.697 62.0049 34.2463 + vertex -468.678 59.6628 32.5424 + vertex -472.834 60.7471 33.2218 + endloop + endfacet + facet normal 0.246558 0.968251 0.0412192 + outer loop + vertex -468.678 59.6628 32.5424 + vertex -459.252 57.3218 31.1494 + vertex -462.275 58.0767 31.4994 + endloop + endfacet + facet normal -0.129667 -0.893536 0.42986 + outer loop + vertex -493.304 66.3152 38.2216 + vertex -489.875 65.3234 37.1941 + vertex -492.742 66.1796 38.1092 + endloop + endfacet + facet normal 0.357674 0.713075 0.602987 + outer loop + vertex -489.875 65.3234 37.1941 + vertex -484.901 63.939 35.8805 + vertex -486.939 64.5184 36.4045 + endloop + endfacet + facet normal 0.214745 0.957429 -0.192909 + outer loop + vertex -484.901 63.939 35.8805 + vertex -490.68 65.5499 37.4423 + vertex -483.383 63.5375 35.5779 + endloop + endfacet + facet normal 0.295624 0.934825 0.196745 + outer loop + vertex -484.901 63.939 35.8805 + vertex -477.697 62.0049 34.2463 + vertex -480.386 62.7394 34.7969 + endloop + endfacet + facet normal -0.0152152 -0.165988 0.98601 + outer loop + vertex 420.155 48.3883 28.1985 + vertex 438.118 52.4137 29.1534 + vertex 428.859 50.6223 28.7089 + endloop + endfacet + facet normal -0.0460206 0.0720473 0.996339 + outer loop + vertex 398.632 43.896 27.5293 + vertex 420.155 48.3883 28.1985 + vertex 410.834 46.6771 27.8917 + endloop + endfacet + facet normal -0.0228342 0.0327256 0.999204 + outer loop + vertex 378.74 40.0039 27.2021 + vertex 398.632 43.896 27.5293 + vertex 390.482 42.4462 27.3905 + endloop + endfacet + facet normal 0.0147727 -0.127911 0.991676 + outer loop + vertex 357.703 36.0762 27.0089 + vertex 378.74 40.0039 27.2021 + vertex 370.274 38.5862 27.1454 + endloop + endfacet + facet normal 0.0350824 -0.255846 0.966081 + outer loop + vertex 252.699 19.3316 26.8156 + vertex 273.997 22.3044 26.8295 + vertex 266.564 21.5032 26.8872 + endloop + endfacet + facet normal 0.0393107 -0.31102 0.94959 + outer loop + vertex 230.843 16.5074 26.7954 + vertex 252.699 19.3316 26.8156 + vertex 243.278 18.237 26.8471 + endloop + endfacet + facet normal 0.0267839 -0.261387 0.964862 + outer loop + vertex 189.707 11.8744 26.7509 + vertex 210.28 14.0709 26.7748 + vertex 202.772 13.497 26.8278 + endloop + endfacet + facet normal 0.0284522 -0.308187 0.9509 + outer loop + vertex 168.834 9.85913 26.7223 + vertex 189.707 11.8744 26.7509 + vertex 181.34 11.1912 26.7798 + endloop + endfacet + facet normal 0.014391 -0.254351 0.967005 + outer loop + vertex 103.113 5.02051 26.625 + vertex 125.033 6.38388 26.6574 + vertex 114.869 5.91475 26.6852 + endloop + endfacet + facet normal 0.00697981 -0.276449 0.961003 + outer loop + vertex 39.8504 2.56187 26.5633 + vertex 61.3081 3.16554 26.5811 + vertex 51.3768 3.00336 26.6066 + endloop + endfacet + facet normal 0.00118639 -0.278703 0.960377 + outer loop + vertex -1.9402 2.11842 26.5506 + vertex 19.0324 2.21475 26.5526 + vertex 12.0453 2.2932 26.584 + endloop + endfacet + facet normal -0.00176221 -0.282363 0.959306 + outer loop + vertex -23.6617 2.26628 26.5542 + vertex -1.9402 2.11842 26.5506 + vertex -12.5209 2.30094 26.5849 + endloop + endfacet + facet normal -0.00885076 -0.236978 0.971475 + outer loop + vertex -87.2904 4.21883 26.6079 + vertex -65.0777 3.2961 26.5852 + vertex -74.5067 3.89062 26.6443 + endloop + endfacet + facet normal -0.0174363 -0.249738 0.968156 + outer loop + vertex -151.026 8.32088 26.6948 + vertex -128.814 6.64642 26.6629 + vertex -138.309 7.57042 26.7303 + endloop + endfacet + facet normal -0.0255837 -0.273844 0.961434 + outer loop + vertex -192.943 12.2057 26.7551 + vertex -171.583 10.0998 26.7237 + vertex -179.626 11.0575 26.7824 + endloop + endfacet + facet normal -0.0276177 -0.262461 0.964547 + outer loop + vertex -214.411 14.5503 26.7784 + vertex -192.943 12.2057 26.7551 + vertex -202.746 13.4834 26.8221 + endloop + endfacet + facet normal -0.0391241 -0.303002 0.952186 + outer loop + vertex -256.495 19.8582 26.8124 + vertex -235.281 17.0669 26.7958 + vertex -243.462 18.2724 26.8433 + endloop + endfacet + facet normal -0.0370435 -0.265863 0.963299 + outer loop + vertex -278.74 23.0138 26.8279 + vertex -256.495 19.8582 26.8124 + vertex -267.195 21.5991 26.8814 + endloop + endfacet + facet normal 0.00319914 -0.0397344 0.999205 + outer loop + vertex -382.442 40.7186 27.2374 + vertex -362.171 36.8731 27.0196 + vertex -370.505 38.6079 27.1153 + endloop + endfacet + facet normal 0.0369922 0.0825595 0.995899 + outer loop + vertex -403.558 44.9696 27.6694 + vertex -382.442 40.7186 27.2374 + vertex -391.051 42.5967 27.4015 + endloop + endfacet + facet normal 0.0182249 -0.0666544 0.99761 + outer loop + vertex -421.839 48.8353 28.2616 + vertex -403.558 44.9696 27.6694 + vertex -412.125 46.9935 27.9611 + endloop + endfacet + facet normal -0.000339673 -0.225504 0.974242 + outer loop + vertex -436.418 52.0254 28.9949 + vertex -421.839 48.8353 28.2616 + vertex -428.804 50.5731 28.6614 + endloop + endfacet + facet normal 0.0618418 -0.548375 0.833943 + outer loop + vertex -485.426 64.0725 36.0812 + vertex -483.383 63.5375 35.5779 + vertex -490.68 65.5499 37.4423 + endloop + endfacet + facet normal -0.0942003 -0.835779 0.540925 + outer loop + vertex -486.915 64.3013 36.1755 + vertex -485.426 64.0725 36.0812 + vertex -493.338 66.1627 37.9329 + endloop + endfacet + facet normal 0.111526 -0.828391 0.548936 + outer loop + vertex 495.261 65.9457 37.2777 + vertex 494.718 64.8605 35.7505 + vertex 499.375 65.9509 36.4498 + endloop + endfacet + facet normal -0.0947556 -0.82678 0.554488 + outer loop + vertex -487.815 64.0779 35.6886 + vertex -486.915 64.3013 36.1755 + vertex -493.409 65.8495 37.3743 + endloop + endfacet + facet normal -0.0880433 -0.802597 0.589988 + outer loop + vertex -487.946 63.1348 34.386 + vertex -487.815 64.0779 35.6886 + vertex -495.01 65.5909 36.6731 + endloop + endfacet + facet normal -0.074365 -0.750853 0.656269 + outer loop + vertex -477.907 60.793 32.8443 + vertex -487.946 63.1348 34.386 + vertex -480.607 60.6128 32.3321 + endloop + endfacet + facet normal -0.101273 -0.818224 0.56591 + outer loop + vertex -495.01 65.5909 36.6731 + vertex -495.913 64.6951 35.2162 + vertex -487.946 63.1348 34.386 + endloop + endfacet + facet normal 0.0911837 -0.783588 0.614552 + outer loop + vertex 494.718 64.8605 35.7505 + vertex 491.293 62.4588 33.1963 + vertex 499.375 65.9509 36.4498 + endloop + endfacet + facet normal -0.0817107 -0.714094 0.695265 + outer loop + vertex -480.541 59.5917 31.2912 + vertex -480.607 60.6128 32.3321 + vertex -491.507 62.008 32.4841 + endloop + endfacet + facet normal -0.114301 -0.814642 0.56859 + outer loop + vertex -499.207 64.4115 34.2547 + vertex -499.669 66.038 36.4921 + vertex -502.812 64.9071 34.2401 + endloop + endfacet + facet normal -0.0871807 -0.776924 0.62353 + outer loop + vertex -495.913 64.6951 35.2162 + vertex -491.507 62.008 32.4841 + vertex -487.946 63.1348 34.386 + endloop + endfacet + facet normal 0.113902 -0.753013 0.648072 + outer loop + vertex 491.293 62.4588 33.1963 + vertex 494.407 60.3919 30.2473 + vertex 500.454 63.7901 33.1332 + endloop + endfacet + facet normal -0.103558 -0.65927 0.74474 + outer loop + vertex -483.481 57.0769 28.6697 + vertex -483.395 58.8501 30.2513 + vertex -494.601 59.756 29.4951 + endloop + endfacet + facet normal -0.0769283 -0.699769 0.710215 + outer loop + vertex -483.395 58.8501 30.2513 + vertex -480.541 59.5917 31.2912 + vertex -491.507 62.008 32.4841 + endloop + endfacet + facet normal -0.110021 -0.782201 0.613234 + outer loop + vertex -500.731 62.179 31.1337 + vertex -499.207 64.4115 34.2547 + vertex -502.812 64.9071 34.2401 + endloop + endfacet + facet normal -0.10466 -0.73923 0.665271 + outer loop + vertex -491.507 62.008 32.4841 + vertex -494.601 59.756 29.4951 + vertex -483.395 58.8501 30.2513 + endloop + endfacet + facet normal 0.131952 -0.696063 0.705752 + outer loop + vertex 494.407 60.3919 30.2473 + vertex 498.754 59.0275 28.089 + vertex 503.135 61.4576 29.6666 + endloop + endfacet + facet normal -0.10973 -0.608863 0.785649 + outer loop + vertex -481.934 54.9868 27.266 + vertex -483.481 57.0769 28.6697 + vertex -491.888 57.5954 27.8973 + endloop + endfacet + facet normal -0.167301 -0.713448 0.680443 + outer loop + vertex -504.176 60.3871 28.4078 + vertex -500.731 62.179 31.1337 + vertex -504.152 61.7843 29.8788 + endloop + endfacet + facet normal -0.123081 -0.685322 0.717764 + outer loop + vertex -494.601 59.756 29.4951 + vertex -499.569 58.4364 27.3833 + vertex -491.888 57.5954 27.8973 + endloop + endfacet + facet normal 0.0973975 -0.568658 0.816787 + outer loop + vertex 504.853 58.0385 26.1721 + vertex 505.429 56.5289 25.0524 + vertex 506.267 57.0964 25.3476 + endloop + endfacet + facet normal 0.137439 -0.701659 0.699132 + outer loop + vertex 498.754 59.0275 28.089 + vertex 503.546 59.472 27.5931 + vertex 503.135 61.4576 29.6666 + endloop + endfacet + facet normal 0.133738 -0.633523 0.762078 + outer loop + vertex 503.546 59.472 27.5931 + vertex 504.853 58.0385 26.1721 + vertex 505.196 59.4283 27.2672 + endloop + endfacet + facet normal -0.119328 -0.611813 0.78195 + outer loop + vertex -493.342 56.1996 26.5834 + vertex -491.888 57.5954 27.8973 + vertex -499.569 58.4364 27.3833 + endloop + endfacet + facet normal -0.119598 -0.526209 0.841903 + outer loop + vertex -495.458 54.463 25.1974 + vertex -493.342 56.1996 26.5834 + vertex -501.639 56.9495 25.8734 + endloop + endfacet + facet normal -0.12231 -0.618156 0.776481 + outer loop + vertex -499.569 58.4364 27.3833 + vertex -501.639 56.9495 25.8734 + vertex -493.342 56.1996 26.5834 + endloop + endfacet + facet normal -0.116211 -0.519113 0.846769 + outer loop + vertex -501.639 56.9495 25.8734 + vertex -503.242 55.6375 24.8491 + vertex -495.458 54.463 25.1974 + endloop + endfacet + facet normal 0.0788839 0.680293 -0.728683 + outer loop + vertex -505.036 58.8712 26.7915 + vertex -504.513 60.146 28.0383 + vertex -504.614 59.3872 27.319 + endloop + endfacet + facet normal -0.233209 -0.703127 0.671733 + outer loop + vertex -504.513 60.146 28.0383 + vertex -504.176 60.3871 28.4078 + vertex -504.152 61.7843 29.8788 + endloop + endfacet + facet normal 0.300863 0.539683 -0.786272 + outer loop + vertex -505.744 57.5523 25.6156 + vertex -505.036 58.8712 26.7915 + vertex -505.324 56.9938 25.3929 + endloop + endfacet + facet normal 0.0742268 -0.281535 0.956676 + outer loop + vertex 506.529 54.0004 23.7267 + vertex 503.792 52.6169 23.5319 + vertex 505.992 51.7297 23.1001 + endloop + endfacet + facet normal 0.0302852 -0.4961 0.867737 + outer loop + vertex 505.429 56.5289 25.0524 + vertex 506.158 55.279 24.3123 + vertex 506.267 57.0964 25.3476 + endloop + endfacet + facet normal -0.0942867 -0.428756 0.898486 + outer loop + vertex -492.781 52.0239 24.3143 + vertex -495.458 54.463 25.1974 + vertex -501.071 53.3366 24.0708 + endloop + endfacet + facet normal -0.101555 -0.403413 0.909365 + outer loop + vertex -503.242 55.6375 24.8491 + vertex -501.071 53.3366 24.0708 + vertex -495.458 54.463 25.1974 + endloop + endfacet + facet normal 0.207501 0.492916 -0.844972 + outer loop + vertex -506.076 56.0029 24.6302 + vertex -505.744 57.5523 25.6156 + vertex -505.324 56.9938 25.3929 + endloop + endfacet + facet normal 0.147185 0.395698 -0.90651 + outer loop + vertex -506.523 54.3103 23.8188 + vertex -506.076 56.0029 24.6302 + vertex -505.856 54.4532 23.9895 + endloop + endfacet + facet normal 0.0668596 0.291589 -0.954204 + outer loop + vertex -506.816 53.3584 23.5074 + vertex -506.523 54.3103 23.8188 + vertex -506.854 51.9309 23.0685 + endloop + endfacet + facet normal 0.0791716 -0.270614 0.959427 + outer loop + vertex 503.792 52.6169 23.5319 + vertex 498.234 47.396 22.518 + vertex 505.992 51.7297 23.1001 + endloop + endfacet + facet normal -0.283512 -0.274832 0.918743 + outer loop + vertex -506.416 50.0813 22.6506 + vertex -506.816 53.3584 23.5074 + vertex -506.854 51.9309 23.0685 + endloop + endfacet + facet normal -0.0570602 -0.270698 0.960972 + outer loop + vertex -506.714 33.1492 18.5243 + vertex -505.776 37.9755 19.9395 + vertex -509.363 35.8267 19.1212 + endloop + endfacet + facet normal 0.0789919 -0.32931 0.940912 + outer loop + vertex 501.75 31.5916 18.4482 + vertex 503.689 29.0724 17.4036 + vertex 507.791 31.0352 17.7462 + endloop + endfacet + facet normal -0.0725265 -0.318758 0.945057 + outer loop + vertex -490.969 26.3302 17.5444 + vertex -486.535 28.6287 18.6599 + vertex -497.31 28.3684 17.7452 + endloop + endfacet + facet normal -0.0579306 -0.339578 0.938792 + outer loop + vertex -508.771 30.3684 17.3915 + vertex -506.714 33.1492 18.5243 + vertex -508.729 31.2422 17.7102 + endloop + endfacet + facet normal -0.0944932 -0.342872 0.934618 + outer loop + vertex -501.423 30.7835 18.2155 + vertex -503.866 28.6332 17.1795 + vertex -497.31 28.3684 17.7452 + endloop + endfacet + facet normal 0.21703 -0.566993 0.794618 + outer loop + vertex 507.895 27.6453 16.2373 + vertex 508.17 26.462 15.318 + vertex 509.226 28.4228 16.4285 + endloop + endfacet + facet normal 0.0925046 -0.355651 0.93003 + outer loop + vertex 503.689 29.0724 17.4036 + vertex 507.709 29.0161 16.9823 + vertex 507.791 31.0352 17.7462 + endloop + endfacet + facet normal 0.141338 -0.457836 0.87773 + outer loop + vertex 507.709 29.0161 16.9823 + vertex 507.895 27.6453 16.2373 + vertex 509.226 28.4228 16.4285 + endloop + endfacet + facet normal -0.0947692 -0.386112 0.917571 + outer loop + vertex -498.065 26.5078 16.8843 + vertex -497.31 28.3684 17.7452 + vertex -503.866 28.6332 17.1795 + endloop + endfacet + facet normal -0.120029 -0.498166 0.858734 + outer loop + vertex -497.488 24.4702 15.7829 + vertex -498.065 26.5078 16.8843 + vertex -504.119 26.6045 16.0943 + endloop + endfacet + facet normal -0.122317 -0.456271 0.881394 + outer loop + vertex -503.866 28.6332 17.1795 + vertex -504.119 26.6045 16.0943 + vertex -498.065 26.5078 16.8843 + endloop + endfacet + facet normal -0.152278 -0.588874 0.79375 + outer loop + vertex -504.119 26.6045 16.0943 + vertex -504.07 24.8752 14.8207 + vertex -497.488 24.4702 15.7829 + endloop + endfacet + facet normal -0.0250667 0.449649 -0.892854 + outer loop + vertex -508.998 28.8698 16.7186 + vertex -508.85 29.6765 17.1207 + vertex -508.626 28.4243 16.4838 + endloop + endfacet + facet normal -0.357532 -0.304648 0.882814 + outer loop + vertex -508.85 29.6765 17.1207 + vertex -508.771 30.3684 17.3915 + vertex -508.729 31.2422 17.7102 + endloop + endfacet + facet normal 0.0747114 0.513172 -0.855028 + outer loop + vertex -508.923 27.4308 15.8615 + vertex -508.998 28.8698 16.7186 + vertex -508.626 28.4243 16.4838 + endloop + endfacet + facet normal 0.12704 -0.83129 0.541127 + outer loop + vertex 508.039 25.0002 13.9085 + vertex 507.938 23.8779 12.2081 + vertex 509.27 24.9242 13.5029 + endloop + endfacet + facet normal 0.132556 -0.6941 0.707569 + outer loop + vertex 508.17 26.462 15.318 + vertex 508.039 25.0002 13.9085 + vertex 509.412 26.4192 15.0432 + endloop + endfacet + facet normal -0.149387 -0.642909 0.751233 + outer loop + vertex -497.429 22.8281 14.3893 + vertex -497.488 24.4702 15.7829 + vertex -504.07 24.8752 14.8207 + endloop + endfacet + facet normal -0.178517 -0.806246 0.564003 + outer loop + vertex -498.433 21.7224 12.4911 + vertex -497.429 22.8281 14.3893 + vertex -504.566 23.6448 13.298 + endloop + endfacet + facet normal -0.183952 -0.734404 0.653309 + outer loop + vertex -504.07 24.8752 14.8207 + vertex -504.566 23.6448 13.298 + vertex -497.429 22.8281 14.3893 + endloop + endfacet + facet normal -0.212647 -0.867308 0.450065 + outer loop + vertex -504.566 23.6448 13.298 + vertex -505.582 23.0852 11.7392 + vertex -498.433 21.7224 12.4911 + endloop + endfacet + facet normal 0.282597 0.6002 -0.748264 + outer loop + vertex -508.894 25.8204 14.5809 + vertex -508.923 27.4308 15.8615 + vertex -508.544 26.3272 15.1198 + endloop + endfacet + facet normal 0.442046 0.694488 -0.567699 + outer loop + vertex -508.933 24.5402 12.9841 + vertex -508.894 25.8204 14.5809 + vertex -508.602 24.8527 13.6242 + endloop + endfacet + facet normal 0.151096 -0.985228 -0.0806008 + outer loop + vertex 508.034 23.3097 10.1604 + vertex 507.778 23.4462 8.01297 + vertex 509.195 23.6025 8.75831 + endloop + endfacet + facet normal 0.129583 -0.953886 0.270757 + outer loop + vertex 507.938 23.8779 12.2081 + vertex 508.034 23.3097 10.1604 + vertex 509.196 23.9317 11.7953 + endloop + endfacet + facet normal -0.248374 -0.911368 0.328204 + outer loop + vertex -495.922 20.4996 10.9952 + vertex -498.433 21.7224 12.4911 + vertex -503.574 22.2904 10.1776 + endloop + endfacet + facet normal -0.234619 -0.969388 0.0723994 + outer loop + vertex -497.415 20.7289 9.23036 + vertex -495.922 20.4996 10.9952 + vertex -503.574 22.2904 10.1776 + endloop + endfacet + facet normal -0.205017 -0.953356 0.221542 + outer loop + vertex -505.582 23.0852 11.7392 + vertex -503.574 22.2904 10.1776 + vertex -498.433 21.7224 12.4911 + endloop + endfacet + facet normal -0.254929 -0.964597 -0.0675539 + outer loop + vertex -503.574 22.2904 10.1776 + vertex -504.588 22.7145 7.94895 + vertex -497.415 20.7289 9.23036 + endloop + endfacet + facet normal 0.676278 0.682724 -0.276652 + outer loop + vertex -508.948 23.701 10.8783 + vertex -508.933 24.5402 12.9841 + vertex -508.693 23.8672 11.9117 + endloop + endfacet + facet normal 0.522882 0.851808 -0.0318906 + outer loop + vertex -509.03 23.6746 8.82407 + vertex -508.948 23.701 10.8783 + vertex -508.783 23.5251 8.88255 + endloop + endfacet + facet normal 0.15204 -0.708624 -0.689011 + outer loop + vertex 507.802 24.3468 6.26721 + vertex 507.961 25.7682 4.84033 + vertex 509.214 25.4997 5.39314 + endloop + endfacet + facet normal 0.177408 -0.875594 -0.44929 + outer loop + vertex 507.778 23.4462 8.01297 + vertex 507.802 24.3468 6.26721 + vertex 509.172 24.2596 6.97821 + endloop + endfacet + facet normal -0.213642 -0.941064 -0.262213 + outer loop + vertex -498.682 21.6159 7.07943 + vertex -497.415 20.7289 9.23036 + vertex -504.588 22.7145 7.94895 + endloop + endfacet + facet normal -0.228172 -0.798753 -0.556715 + outer loop + vertex -496.127 21.8349 5.71802 + vertex -498.682 21.6159 7.07943 + vertex -503.71 24.4119 5.12868 + endloop + endfacet + facet normal -0.224627 -0.885178 -0.407433 + outer loop + vertex -504.588 22.7145 7.94895 + vertex -505.648 23.7195 6.34974 + vertex -498.682 21.6159 7.07943 + endloop + endfacet + facet normal -0.153003 -0.735586 -0.659927 + outer loop + vertex -505.648 23.7195 6.34974 + vertex -503.71 24.4119 5.12868 + vertex -498.682 21.6159 7.07943 + endloop + endfacet + facet normal 0.39065 0.870977 0.297978 + outer loop + vertex -508.93 24.2552 6.99646 + vertex -509.03 23.6746 8.82407 + vertex -508.686 24.1074 7.10827 + endloop + endfacet + facet normal 0.157537 0.804539 0.572625 + outer loop + vertex -508.846 25.3324 5.45995 + vertex -508.93 24.2552 6.99646 + vertex -508.463 25.236 5.48987 + endloop + endfacet + facet normal 0.153533 -0.483459 -0.861797 + outer loop + vertex 508.018 27.0966 3.91103 + vertex 508.543 28.0281 3.48188 + vertex 509.171 27.208 4.05384 + endloop + endfacet + facet normal 0.0783191 -0.343084 -0.936034 + outer loop + vertex 508.543 28.0281 3.48188 + vertex 505.653 28.1259 3.20425 + vertex 508.438 29.5567 2.9129 + endloop + endfacet + facet normal 0.155095 -0.570799 -0.806309 + outer loop + vertex 507.961 25.7682 4.84033 + vertex 508.018 27.0966 3.91103 + vertex 509.171 27.208 4.05384 + endloop + endfacet + facet normal -0.151375 -0.621273 -0.768834 + outer loop + vertex -497.357 23.7015 4.45198 + vertex -496.127 21.8349 5.71802 + vertex -503.71 24.4119 5.12868 + endloop + endfacet + facet normal -0.0935877 -0.435186 -0.895463 + outer loop + vertex -497.201 26.3339 3.15632 + vertex -497.357 23.7015 4.45198 + vertex -504.242 26.7894 3.67079 + endloop + endfacet + facet normal -0.0709224 -0.290589 -0.954216 + outer loop + vertex -486.383 23.4873 3.21916 + vertex -497.201 26.3339 3.15632 + vertex -488.557 27.2715 2.22832 + endloop + endfacet + facet normal -0.148673 -0.540888 -0.82785 + outer loop + vertex -503.71 24.4119 5.12868 + vertex -504.242 26.7894 3.67079 + vertex -497.357 23.7015 4.45198 + endloop + endfacet + facet normal -0.0922898 -0.393339 -0.914749 + outer loop + vertex -504.242 26.7894 3.67079 + vertex -504.196 28.5905 2.89175 + vertex -497.201 26.3339 3.15632 + endloop + endfacet + facet normal -0.131671 0.661717 0.738101 + outer loop + vertex -508.934 26.4189 4.47028 + vertex -508.846 25.3324 5.45995 + vertex -508.44 26.9019 4.12532 + endloop + endfacet + facet normal 0.098412 0.509748 0.854677 + outer loop + vertex -508.869 27.7446 3.67214 + vertex -508.934 26.4189 4.47028 + vertex -508.44 26.9019 4.12532 + endloop + endfacet + facet normal -0.185457 -0.371223 -0.909835 + outer loop + vertex -508.799 28.8491 3.20724 + vertex -508.869 27.7446 3.67214 + vertex -508.951 29.7198 2.88291 + endloop + endfacet + facet normal 0.0602208 -0.310426 -0.948688 + outer loop + vertex 505.653 28.1259 3.20425 + vertex 500.423 30.5976 2.06347 + vertex 508.438 29.5567 2.9129 + endloop + endfacet + facet normal -0.0527038 -0.275902 -0.95974 + outer loop + vertex -504.196 28.5905 2.89175 + vertex -502.432 30.76 2.17118 + vertex -497.201 26.3339 3.15632 + endloop + endfacet + facet normal 0.0510162 -0.340807 -0.938748 + outer loop + vertex -507.897 31.8129 2.18027 + vertex -508.799 28.8491 3.20724 + vertex -508.951 29.7198 2.88291 + endloop + endfacet + facet normal 0.035065 -0.199504 -0.97927 + outer loop + vertex 500.423 30.5976 2.06347 + vertex 498.389 35.1798 1.05711 + vertex 507.098 34.852 1.43578 + endloop + endfacet + facet normal -0.057312 -0.211688 -0.975655 + outer loop + vertex -482.588 29.3247 1.4322 + vertex -488.557 27.2715 2.22832 + vertex -496.639 34.1271 1.21564 + endloop + endfacet + facet normal -0.0273201 -0.213142 -0.976639 + outer loop + vertex -505.881 35.4469 1.3308 + vertex -507.897 31.8129 2.18027 + vertex -509.269 35.1963 1.48026 + endloop + endfacet + facet normal -0.0459459 -0.198777 -0.978967 + outer loop + vertex -502.432 30.76 2.17118 + vertex -496.639 34.1271 1.21564 + vertex -488.557 27.2715 2.22832 + endloop + endfacet + facet normal -0.0865 -0.823776 0.560277 + outer loop + vertex -485.426 64.0725 36.0812 + vertex -490.68 65.5499 37.4423 + vertex -493.338 66.1627 37.9329 + endloop + endfacet + facet normal -0.0902662 -0.773531 0.627297 + outer loop + vertex -480.607 60.6128 32.3321 + vertex -487.946 63.1348 34.386 + vertex -491.507 62.008 32.4841 + endloop + endfacet + facet normal -0.10866 -0.675649 0.729172 + outer loop + vertex -483.481 57.0769 28.6697 + vertex -494.601 59.756 29.4951 + vertex -491.888 57.5954 27.8973 + endloop + endfacet + facet normal -0.0730342 -0.308989 0.948257 + outer loop + vertex -486.535 28.6287 18.6599 + vertex -501.423 30.7835 18.2155 + vertex -497.31 28.3684 17.7452 + endloop + endfacet + facet normal -0.0702828 -0.295147 -0.952863 + outer loop + vertex -488.557 27.2715 2.22832 + vertex -497.201 26.3339 3.15632 + vertex -502.432 30.76 2.17118 + endloop + endfacet + facet normal 0.182505 -0.621183 0.762118 + outer loop + vertex 506.119 58.5975 26.3709 + vertex 507.286 59.423 26.7643 + vertex 505.377 60.3752 27.9975 + endloop + endfacet + facet normal 0.158546 -0.647526 0.745368 + outer loop + vertex 505.377 60.3752 27.9975 + vertex 507.286 59.423 26.7643 + vertex 506.813 61.0391 28.2689 + endloop + endfacet + facet normal 0.175613 -0.673329 0.718184 + outer loop + vertex 505.377 60.3752 27.9975 + vertex 506.813 61.0391 28.2689 + vertex 505.114 61.4706 29.0889 + endloop + endfacet + facet normal 0.135021 -0.733751 0.665866 + outer loop + vertex 505.114 61.4706 29.0889 + vertex 506.813 61.0391 28.2689 + vertex 506.407 62.4306 29.8845 + endloop + endfacet + facet normal 0.12799 -0.452832 0.882361 + outer loop + vertex 506.879 55.2957 24.2724 + vertex 507.903 55.7045 24.3338 + vertex 506.559 56.9305 25.158 + endloop + endfacet + facet normal 0.0944209 -0.482032 0.871051 + outer loop + vertex 506.559 56.9305 25.158 + vertex 507.903 55.7045 24.3338 + vertex 507.681 57.6073 25.4109 + endloop + endfacet + facet normal 0.150645 -0.55534 0.817865 + outer loop + vertex 506.559 56.9305 25.158 + vertex 507.681 57.6073 25.4109 + vertex 506.119 58.5975 26.3709 + endloop + endfacet + facet normal 0.133229 -0.573522 0.808283 + outer loop + vertex 506.119 58.5975 26.3709 + vertex 507.681 57.6073 25.4109 + vertex 507.286 59.423 26.7643 + endloop + endfacet + facet normal 0.106716 -0.252952 0.961575 + outer loop + vertex 508.244 50.7454 22.6461 + vertex 509.082 51.7825 22.826 + vertex 507.375 53.1213 23.3676 + endloop + endfacet + facet normal 0.074164 -0.291297 0.953754 + outer loop + vertex 507.375 53.1213 23.3676 + vertex 509.082 51.7825 22.826 + vertex 508.348 53.6985 23.4683 + endloop + endfacet + facet normal 0.117033 -0.358711 0.926083 + outer loop + vertex 507.375 53.1213 23.3676 + vertex 508.348 53.6985 23.4683 + vertex 506.879 55.2957 24.2724 + endloop + endfacet + facet normal 0.0951613 -0.376513 0.921511 + outer loop + vertex 506.879 55.2957 24.2724 + vertex 508.348 53.6985 23.4683 + vertex 507.903 55.7045 24.3338 + endloop + endfacet + facet normal 0.109029 -0.48623 0.867002 + outer loop + vertex 509.874 27.3951 15.6954 + vertex 510.967 28.0541 15.9276 + vertex 509.722 29.579 16.9394 + endloop + endfacet + facet normal 0.123201 -0.476851 0.870307 + outer loop + vertex 509.722 29.579 16.9394 + vertex 510.967 28.0541 15.9276 + vertex 511.021 30.1163 17.0499 + endloop + endfacet + facet normal 0.0763689 -0.374647 0.924017 + outer loop + vertex 509.722 29.579 16.9394 + vertex 511.021 30.1163 17.0499 + vertex 509.884 32.2471 18.0077 + endloop + endfacet + facet normal 0.0631057 -0.381004 0.922417 + outer loop + vertex 509.884 32.2471 18.0077 + vertex 511.021 30.1163 17.0499 + vertex 511.666 32.1383 17.8409 + endloop + endfacet + facet normal 0.202602 -0.793513 0.573837 + outer loop + vertex 509.793 24.4921 12.6077 + vertex 511.107 25.0885 12.9683 + vertex 509.848 25.6977 14.2552 + endloop + endfacet + facet normal 0.252536 -0.755398 0.604648 + outer loop + vertex 509.848 25.6977 14.2552 + vertex 511.107 25.0885 12.9683 + vertex 511.051 26.3501 14.5681 + endloop + endfacet + facet normal 0.15189 -0.640812 0.752522 + outer loop + vertex 509.848 25.6977 14.2552 + vertex 511.051 26.3501 14.5681 + vertex 509.874 27.3951 15.6954 + endloop + endfacet + facet normal 0.201057 -0.604868 0.770527 + outer loop + vertex 509.874 27.3951 15.6954 + vertex 511.051 26.3501 14.5681 + vertex 510.967 28.0541 15.9276 + endloop + endfacet + facet normal 0.282072 -0.958206 0.0477057 + outer loop + vertex 509.815 23.7382 9.09716 + vertex 511.229 24.164 9.28965 + vertex 509.784 23.8167 10.8606 + endloop + endfacet + facet normal 0.328444 -0.93979 0.0944443 + outer loop + vertex 509.784 23.8167 10.8606 + vertex 511.229 24.164 9.28965 + vertex 511.164 24.3305 11.1713 + endloop + endfacet + facet normal 0.257417 -0.901761 0.347223 + outer loop + vertex 509.784 23.8167 10.8606 + vertex 511.164 24.3305 11.1713 + vertex 509.793 24.4921 12.6077 + endloop + endfacet + facet normal 0.293979 -0.877297 0.379377 + outer loop + vertex 509.793 24.4921 12.6077 + vertex 511.164 24.3305 11.1713 + vertex 511.107 25.0885 12.9683 + endloop + endfacet + facet normal 0.211637 -0.805913 -0.552914 + outer loop + vertex 509.749 25.3787 5.71105 + vertex 510.958 25.6406 5.79199 + vertex 509.798 24.2725 7.3425 + endloop + endfacet + facet normal 0.241839 -0.810125 -0.534052 + outer loop + vertex 509.798 24.2725 7.3425 + vertex 510.958 25.6406 5.79199 + vertex 511.155 24.599 7.46132 + endloop + endfacet + facet normal 0.247891 -0.926117 -0.284354 + outer loop + vertex 509.798 24.2725 7.3425 + vertex 511.155 24.599 7.46132 + vertex 509.815 23.7382 9.09716 + endloop + endfacet + facet normal 0.309319 -0.922222 -0.232007 + outer loop + vertex 509.815 23.7382 9.09716 + vertex 511.155 24.599 7.46132 + vertex 511.229 24.164 9.28965 + endloop + endfacet + facet normal 0.267148 -0.49412 -0.827331 + outer loop + vertex 509.511 28.0565 3.6163 + vertex 510.53 29.0661 3.34258 + vertex 509.719 26.8895 4.38047 + endloop + endfacet + facet normal 0.155172 -0.471749 -0.867972 + outer loop + vertex 509.719 26.8895 4.38047 + vertex 510.53 29.0661 3.34258 + vertex 510.842 27.2532 4.38375 + endloop + endfacet + facet normal 0.210446 -0.643762 -0.735719 + outer loop + vertex 509.719 26.8895 4.38047 + vertex 510.842 27.2532 4.38375 + vertex 509.749 25.3787 5.71105 + endloop + endfacet + facet normal 0.188287 -0.638362 -0.746353 + outer loop + vertex 509.749 25.3787 5.71105 + vertex 510.842 27.2532 4.38375 + vertex 510.958 25.6406 5.79199 + endloop + endfacet + facet normal 0.170301 -0.804427 0.569117 + outer loop + vertex 506.214 64.1879 32.2029 + vertex 512.623 66.0971 32.984 + vertex 506.082 66.3319 35.273 + endloop + endfacet + facet normal 0.170767 -0.778349 0.604162 + outer loop + vertex 506.407 62.4306 29.8845 + vertex 510.03 63.7764 30.5942 + vertex 506.214 64.1879 32.2029 + endloop + endfacet + facet normal 0.174189 -0.794136 0.582243 + outer loop + vertex 514.58 64.6538 30.4297 + vertex 512.623 66.0971 32.984 + vertex 510.03 63.7764 30.5942 + endloop + endfacet + facet normal 0.163579 -0.790496 0.590218 + outer loop + vertex 512.623 66.0971 32.984 + vertex 506.214 64.1879 32.2029 + vertex 510.03 63.7764 30.5942 + endloop + endfacet + facet normal 0.161411 -0.674293 0.720608 + outer loop + vertex 510.154 60.2747 26.8866 + vertex 514.573 61.3424 26.8958 + vertex 509.758 61.9727 28.5642 + endloop + endfacet + facet normal 0.154645 -0.690063 0.707035 + outer loop + vertex 509.758 61.9727 28.5642 + vertex 514.573 61.3424 26.8958 + vertex 514.207 63.0592 28.6515 + endloop + endfacet + facet normal 0.160341 -0.647038 0.745408 + outer loop + vertex 507.286 59.423 26.7643 + vertex 510.154 60.2747 26.8866 + vertex 506.813 61.0391 28.2689 + endloop + endfacet + facet normal 0.14284 -0.678549 0.720533 + outer loop + vertex 506.813 61.0391 28.2689 + vertex 510.154 60.2747 26.8866 + vertex 509.758 61.9727 28.5642 + endloop + endfacet + facet normal 0.163508 -0.726837 0.667063 + outer loop + vertex 506.813 61.0391 28.2689 + vertex 509.758 61.9727 28.5642 + vertex 506.407 62.4306 29.8845 + endloop + endfacet + facet normal 0.151819 -0.748905 0.645052 + outer loop + vertex 506.407 62.4306 29.8845 + vertex 509.758 61.9727 28.5642 + vertex 510.03 63.7764 30.5942 + endloop + endfacet + facet normal 0.170044 -0.747874 0.641692 + outer loop + vertex 509.758 61.9727 28.5642 + vertex 514.207 63.0592 28.6515 + vertex 510.03 63.7764 30.5942 + endloop + endfacet + facet normal 0.167935 -0.751179 0.638379 + outer loop + vertex 510.03 63.7764 30.5942 + vertex 514.207 63.0592 28.6515 + vertex 514.58 64.6538 30.4297 + endloop + endfacet + facet normal 0.124485 -0.482373 0.867075 + outer loop + vertex 510.779 56.477 24.3608 + vertex 515.375 57.5834 24.3165 + vertex 510.611 58.4673 25.4921 + endloop + endfacet + facet normal 0.124153 -0.483438 0.86653 + outer loop + vertex 510.611 58.4673 25.4921 + vertex 515.375 57.5834 24.3165 + vertex 515.137 59.5618 25.4543 + endloop + endfacet + facet normal 0.120323 -0.478346 0.869889 + outer loop + vertex 507.903 55.7045 24.3338 + vertex 510.779 56.477 24.3608 + vertex 507.681 57.6073 25.4109 + endloop + endfacet + facet normal 0.117756 -0.48321 0.86755 + outer loop + vertex 507.681 57.6073 25.4109 + vertex 510.779 56.477 24.3608 + vertex 510.611 58.4673 25.4921 + endloop + endfacet + facet normal 0.145115 -0.570832 0.808141 + outer loop + vertex 507.681 57.6073 25.4109 + vertex 510.611 58.4673 25.4921 + vertex 507.286 59.423 26.7643 + endloop + endfacet + facet normal 0.138875 -0.582692 0.80074 + outer loop + vertex 507.286 59.423 26.7643 + vertex 510.611 58.4673 25.4921 + vertex 510.154 60.2747 26.8866 + endloop + endfacet + facet normal 0.147107 -0.580629 0.800768 + outer loop + vertex 510.611 58.4673 25.4921 + vertex 515.137 59.5618 25.4543 + vertex 510.154 60.2747 26.8866 + endloop + endfacet + facet normal 0.142169 -0.595249 0.790865 + outer loop + vertex 510.154 60.2747 26.8866 + vertex 515.137 59.5618 25.4543 + vertex 514.573 61.3424 26.8958 + endloop + endfacet + facet normal 0.084082 -0.283305 0.955337 + outer loop + vertex 511.755 52.1385 22.734 + vertex 514.958 53.329 22.8051 + vertex 510.881 54.3698 23.4726 + endloop + endfacet + facet normal 0.0803694 -0.29565 0.95191 + outer loop + vertex 510.881 54.3698 23.4726 + vertex 514.958 53.329 22.8051 + vertex 515.212 55.3985 23.4264 + endloop + endfacet + facet normal 0.0717401 -0.292196 0.953664 + outer loop + vertex 509.082 51.7825 22.826 + vertex 511.755 52.1385 22.734 + vertex 508.348 53.6985 23.4683 + endloop + endfacet + facet normal 0.0744197 -0.28699 0.955038 + outer loop + vertex 508.348 53.6985 23.4683 + vertex 511.755 52.1385 22.734 + vertex 510.881 54.3698 23.4726 + endloop + endfacet + facet normal 0.0980207 -0.375865 0.921476 + outer loop + vertex 508.348 53.6985 23.4683 + vertex 510.881 54.3698 23.4726 + vertex 507.903 55.7045 24.3338 + endloop + endfacet + facet normal 0.0941997 -0.382802 0.919015 + outer loop + vertex 507.903 55.7045 24.3338 + vertex 510.881 54.3698 23.4726 + vertex 510.779 56.477 24.3608 + endloop + endfacet + facet normal 0.100598 -0.382295 0.918548 + outer loop + vertex 510.881 54.3698 23.4726 + vertex 515.212 55.3985 23.4264 + vertex 510.779 56.477 24.3608 + endloop + endfacet + facet normal 0.100765 -0.381777 0.918745 + outer loop + vertex 510.779 56.477 24.3608 + vertex 515.212 55.3985 23.4264 + vertex 515.375 57.5834 24.3165 + endloop + endfacet + facet normal 0.0774747 -0.309622 0.947698 + outer loop + vertex 511.666 32.1383 17.8409 + vertex 514.716 33.2513 17.9552 + vertex 512.08 34.872 18.7002 + endloop + endfacet + facet normal 0.0799767 -0.303053 0.949612 + outer loop + vertex 518.998 33.9886 17.8299 + vertex 517.871 36.8235 18.8295 + vertex 514.716 33.2513 17.9552 + endloop + endfacet + facet normal 0.0812852 -0.3041 0.949166 + outer loop + vertex 517.871 36.8235 18.8295 + vertex 512.08 34.872 18.7002 + vertex 514.716 33.2513 17.9552 + endloop + endfacet + facet normal 0.122628 -0.481093 0.868051 + outer loop + vertex 513.638 28.7682 15.9422 + vertex 517.936 29.8063 15.9104 + vertex 513.808 30.7687 17.0271 + endloop + endfacet + facet normal 0.121302 -0.48468 0.86624 + outer loop + vertex 513.808 30.7687 17.0271 + vertex 517.936 29.8063 15.9104 + vertex 518.091 31.8105 17.0102 + endloop + endfacet + facet normal 0.122696 -0.476871 0.870368 + outer loop + vertex 510.967 28.0541 15.9276 + vertex 513.638 28.7682 15.9422 + vertex 511.021 30.1163 17.0499 + endloop + endfacet + facet normal 0.119727 -0.481073 0.868467 + outer loop + vertex 511.021 30.1163 17.0499 + vertex 513.638 28.7682 15.9422 + vertex 513.808 30.7687 17.0271 + endloop + endfacet + facet normal 0.098724 -0.389715 0.915629 + outer loop + vertex 511.021 30.1163 17.0499 + vertex 513.808 30.7687 17.0271 + vertex 511.666 32.1383 17.8409 + endloop + endfacet + facet normal 0.10488 -0.381689 0.918321 + outer loop + vertex 511.666 32.1383 17.8409 + vertex 513.808 30.7687 17.0271 + vertex 514.716 33.2513 17.9552 + endloop + endfacet + facet normal 0.0958468 -0.379147 0.920359 + outer loop + vertex 513.808 30.7687 17.0271 + vertex 518.091 31.8105 17.0102 + vertex 514.716 33.2513 17.9552 + endloop + endfacet + facet normal 0.0930716 -0.384404 0.918461 + outer loop + vertex 514.716 33.2513 17.9552 + vertex 518.091 31.8105 17.0102 + vertex 518.998 33.9886 17.8299 + endloop + endfacet + facet normal 0.191874 -0.762199 0.618254 + outer loop + vertex 513.965 25.8894 13.0412 + vertex 518.346 26.9675 13.0106 + vertex 513.794 27.1244 14.6168 + endloop + endfacet + facet normal 0.1919 -0.762136 0.618323 + outer loop + vertex 513.794 27.1244 14.6168 + vertex 518.346 26.9675 13.0106 + vertex 518.124 28.1862 14.5817 + endloop + endfacet + facet normal 0.199115 -0.766053 0.61116 + outer loop + vertex 511.107 25.0885 12.9683 + vertex 513.965 25.8894 13.0412 + vertex 511.051 26.3501 14.5681 + endloop + endfacet + facet normal 0.203479 -0.759731 0.61758 + outer loop + vertex 511.051 26.3501 14.5681 + vertex 513.965 25.8894 13.0412 + vertex 513.794 27.1244 14.6168 + endloop + endfacet + facet normal 0.158681 -0.610982 0.775578 + outer loop + vertex 511.051 26.3501 14.5681 + vertex 513.794 27.1244 14.6168 + vertex 510.967 28.0541 15.9276 + endloop + endfacet + facet normal 0.158948 -0.61056 0.775855 + outer loop + vertex 510.967 28.0541 15.9276 + vertex 513.794 27.1244 14.6168 + vertex 513.638 28.7682 15.9422 + endloop + endfacet + facet normal 0.156118 -0.611007 0.776078 + outer loop + vertex 513.794 27.1244 14.6168 + vertex 518.124 28.1862 14.5817 + vertex 513.638 28.7682 15.9422 + endloop + endfacet + facet normal 0.154454 -0.615779 0.772632 + outer loop + vertex 513.638 28.7682 15.9422 + vertex 518.124 28.1862 14.5817 + vertex 517.936 29.8063 15.9104 + endloop + endfacet + facet normal 0.239708 -0.965332 0.103318 + outer loop + vertex 514.21 24.9544 9.33736 + vertex 518.666 26.0579 9.30924 + vertex 514.095 25.1302 11.2478 + endloop + endfacet + facet normal 0.240125 -0.965111 0.104406 + outer loop + vertex 514.095 25.1302 11.2478 + vertex 518.666 26.0579 9.30924 + vertex 518.531 26.231 11.2197 + endloop + endfacet + facet normal 0.253734 -0.962705 0.0939097 + outer loop + vertex 511.229 24.164 9.28965 + vertex 514.21 24.9544 9.33736 + vertex 511.164 24.3305 11.1713 + endloop + endfacet + facet normal 0.259309 -0.960176 0.104029 + outer loop + vertex 511.164 24.3305 11.1713 + vertex 514.21 24.9544 9.33736 + vertex 514.095 25.1302 11.2478 + endloop + endfacet + facet normal 0.233716 -0.893191 0.384169 + outer loop + vertex 511.164 24.3305 11.1713 + vertex 514.095 25.1302 11.2478 + vertex 511.107 25.0885 12.9683 + endloop + endfacet + facet normal 0.238826 -0.887908 0.393169 + outer loop + vertex 511.107 25.0885 12.9683 + vertex 514.095 25.1302 11.2478 + vertex 513.965 25.8894 13.0412 + endloop + endfacet + facet normal 0.223721 -0.891622 0.393649 + outer loop + vertex 514.095 25.1302 11.2478 + vertex 518.531 26.231 11.2197 + vertex 513.965 25.8894 13.0412 + endloop + endfacet + facet normal 0.222552 -0.893343 0.390396 + outer loop + vertex 513.965 25.8894 13.0412 + vertex 518.531 26.231 11.2197 + vertex 518.346 26.9675 13.0106 + endloop + endfacet + facet normal 0.202015 -0.824874 -0.527989 + outer loop + vertex 513.814 26.3697 5.77012 + vertex 518.292 27.4967 5.72312 + vertex 514.134 25.3639 7.46421 + endloop + endfacet + facet normal 0.205144 -0.827113 -0.523258 + outer loop + vertex 514.134 25.3639 7.46421 + vertex 518.292 27.4967 5.72312 + vertex 518.662 26.5086 7.42996 + endloop + endfacet + facet normal 0.205048 -0.819307 -0.535436 + outer loop + vertex 510.958 25.6406 5.79199 + vertex 513.814 26.3697 5.77012 + vertex 511.155 24.599 7.46132 + endloop + endfacet + facet normal 0.211594 -0.82229 -0.528268 + outer loop + vertex 511.155 24.599 7.46132 + vertex 513.814 26.3697 5.77012 + vertex 514.134 25.3639 7.46421 + endloop + endfacet + facet normal 0.241954 -0.941674 -0.233898 + outer loop + vertex 511.155 24.599 7.46132 + vertex 514.134 25.3639 7.46421 + vertex 511.229 24.164 9.28965 + endloop + endfacet + facet normal 0.253433 -0.942839 -0.216394 + outer loop + vertex 511.229 24.164 9.28965 + vertex 514.134 25.3639 7.46421 + vertex 514.21 24.9544 9.33736 + endloop + endfacet + facet normal 0.237738 -0.946863 -0.216637 + outer loop + vertex 514.134 25.3639 7.46421 + vertex 518.662 26.5086 7.42996 + vertex 514.21 24.9544 9.33736 + endloop + endfacet + facet normal 0.232737 -0.945608 -0.227287 + outer loop + vertex 514.21 24.9544 9.33736 + vertex 518.662 26.5086 7.42996 + vertex 518.666 26.0579 9.30924 + endloop + endfacet + facet normal 0.0876187 -0.448426 -0.889515 + outer loop + vertex 513.546 30.287 3.17133 + vertex 516.931 30.6642 3.3146 + vertex 513.421 27.9217 4.35144 + endloop + endfacet + facet normal 0.111034 -0.47262 -0.874243 + outer loop + vertex 513.421 27.9217 4.35144 + vertex 516.931 30.6642 3.3146 + vertex 517.642 28.9873 4.31138 + endloop + endfacet + facet normal 0.142678 -0.474326 -0.868711 + outer loop + vertex 510.53 29.0661 3.34258 + vertex 513.546 30.287 3.17133 + vertex 510.842 27.2532 4.38375 + endloop + endfacet + facet normal 0.105114 -0.448408 -0.887627 + outer loop + vertex 510.842 27.2532 4.38375 + vertex 513.546 30.287 3.17133 + vertex 513.421 27.9217 4.35144 + endloop + endfacet + facet normal 0.157339 -0.643198 -0.74936 + outer loop + vertex 510.842 27.2532 4.38375 + vertex 513.421 27.9217 4.35144 + vertex 510.958 25.6406 5.79199 + endloop + endfacet + facet normal 0.158669 -0.644014 -0.748378 + outer loop + vertex 510.958 25.6406 5.79199 + vertex 513.421 27.9217 4.35144 + vertex 513.814 26.3697 5.77012 + endloop + endfacet + facet normal 0.155691 -0.644755 -0.748365 + outer loop + vertex 513.421 27.9217 4.35144 + vertex 517.642 28.9873 4.31138 + vertex 513.814 26.3697 5.77012 + endloop + endfacet + facet normal 0.153968 -0.643186 -0.75007 + outer loop + vertex 513.814 26.3697 5.77012 + vertex 517.642 28.9873 4.31138 + vertex 518.292 27.4967 5.72312 + endloop + endfacet + facet normal 0.0738195 -0.301375 -0.950644 + outer loop + vertex 516.931 30.6642 3.3146 + vertex 513.546 30.287 3.17133 + vertex 520.134 34.8191 2.24611 + endloop + endfacet + facet normal 0.0683261 -0.302159 -0.950806 + outer loop + vertex 510.53 29.0661 3.34258 + vertex 512.413 33.4434 2.08679 + vertex 513.546 30.287 3.17133 + endloop + endfacet + facet normal 0.0731591 -0.300483 -0.950977 + outer loop + vertex 512.413 33.4434 2.08679 + vertex 520.134 34.8191 2.24611 + vertex 513.546 30.287 3.17133 + endloop + endfacet + facet normal 0.0457864 -0.193829 -0.979966 + outer loop + vertex 512.75 38.6877 1.06526 + vertex 519.518 39.3254 1.25534 + vertex 512.413 33.4434 2.08679 + endloop + endfacet + facet normal 0.0570229 -0.206938 -0.976691 + outer loop + vertex 512.413 33.4434 2.08679 + vertex 519.518 39.3254 1.25534 + vertex 520.134 34.8191 2.24611 + endloop + endfacet + facet normal 0.179136 -0.791386 0.584481 + outer loop + vertex 514.58 64.6538 30.4297 + vertex 519.609 66.0929 30.837 + vertex 512.623 66.0971 32.984 + endloop + endfacet + facet normal 0.186253 -0.806083 0.56173 + outer loop + vertex 525.859 67.2902 30.4829 + vertex 522.487 68.4747 33.3006 + vertex 519.609 66.0929 30.837 + endloop + endfacet + facet normal 0.174991 -0.802075 0.571012 + outer loop + vertex 522.487 68.4747 33.3006 + vertex 512.623 66.0971 32.984 + vertex 519.609 66.0929 30.837 + endloop + endfacet + facet normal 0.174059 -0.69786 0.694763 + outer loop + vertex 519.945 62.6066 26.8418 + vertex 525.843 64.0263 26.7904 + vertex 519.54 64.3046 28.649 + endloop + endfacet + facet normal 0.170908 -0.707684 0.685547 + outer loop + vertex 519.54 64.3046 28.649 + vertex 525.843 64.0263 26.7904 + vertex 525.486 65.7101 28.6176 + endloop + endfacet + facet normal 0.168751 -0.686903 0.706886 + outer loop + vertex 514.573 61.3424 26.8958 + vertex 519.945 62.6066 26.8418 + vertex 514.207 63.0592 28.6515 + endloop + endfacet + facet normal 0.163875 -0.700307 0.694777 + outer loop + vertex 514.207 63.0592 28.6515 + vertex 519.945 62.6066 26.8418 + vertex 519.54 64.3046 28.649 + endloop + endfacet + facet normal 0.175676 -0.750957 0.636555 + outer loop + vertex 514.207 63.0592 28.6515 + vertex 519.54 64.3046 28.649 + vertex 514.58 64.6538 30.4297 + endloop + endfacet + facet normal 0.168884 -0.765769 0.620545 + outer loop + vertex 514.58 64.6538 30.4297 + vertex 519.54 64.3046 28.649 + vertex 519.609 66.0929 30.837 + endloop + endfacet + facet normal 0.183849 -0.763923 0.618564 + outer loop + vertex 519.54 64.3046 28.649 + vertex 525.486 65.7101 28.6176 + vertex 519.609 66.0929 30.837 + endloop + endfacet + facet normal 0.181916 -0.767944 0.61414 + outer loop + vertex 519.609 66.0929 30.837 + vertex 525.486 65.7101 28.6176 + vertex 525.859 67.2902 30.4829 + endloop + endfacet + facet normal 0.131197 -0.485303 0.864447 + outer loop + vertex 520.957 58.9364 24.2422 + vertex 526.876 60.4261 24.1803 + vertex 520.602 60.8692 25.3812 + endloop + endfacet + facet normal 0.130579 -0.488867 0.86253 + outer loop + vertex 520.602 60.8692 25.3812 + vertex 526.876 60.4261 24.1803 + vertex 526.458 62.3151 25.3142 + endloop + endfacet + facet normal 0.128531 -0.482761 0.866269 + outer loop + vertex 515.375 57.5834 24.3165 + vertex 520.957 58.9364 24.2422 + vertex 515.137 59.5618 25.4543 + endloop + endfacet + facet normal 0.127829 -0.485992 0.864564 + outer loop + vertex 515.137 59.5618 25.4543 + vertex 520.957 58.9364 24.2422 + vertex 520.602 60.8692 25.3812 + endloop + endfacet + facet normal 0.152284 -0.592309 0.791189 + outer loop + vertex 515.137 59.5618 25.4543 + vertex 520.602 60.8692 25.3812 + vertex 514.573 61.3424 26.8958 + endloop + endfacet + facet normal 0.149665 -0.60251 0.783953 + outer loop + vertex 514.573 61.3424 26.8958 + vertex 520.602 60.8692 25.3812 + vertex 519.945 62.6066 26.8418 + endloop + endfacet + facet normal 0.157138 -0.600046 0.784381 + outer loop + vertex 520.602 60.8692 25.3812 + vertex 526.458 62.3151 25.3142 + vertex 519.945 62.6066 26.8418 + endloop + endfacet + facet normal 0.154327 -0.612992 0.77487 + outer loop + vertex 519.945 62.6066 26.8418 + vertex 526.458 62.3151 25.3142 + vertex 525.843 64.0263 26.7904 + endloop + endfacet + facet normal 0.0816801 -0.280101 0.956489 + outer loop + vertex 520.645 54.2855 22.6525 + vertex 525.995 56.0232 22.7044 + vertex 520.768 56.7399 23.3607 + endloop + endfacet + facet normal 0.0806386 -0.28614 0.954788 + outer loop + vertex 520.768 56.7399 23.3607 + vertex 525.995 56.0232 22.7044 + vertex 526.761 58.2513 23.3075 + endloop + endfacet + facet normal 0.0752111 -0.295187 0.952475 + outer loop + vertex 514.958 53.329 22.8051 + vertex 520.645 54.2855 22.6525 + vertex 515.212 55.3985 23.4264 + endloop + endfacet + facet normal 0.0789225 -0.280036 0.95674 + outer loop + vertex 515.212 55.3985 23.4264 + vertex 520.645 54.2855 22.6525 + vertex 520.768 56.7399 23.3607 + endloop + endfacet + facet normal 0.103046 -0.381834 0.918468 + outer loop + vertex 515.212 55.3985 23.4264 + vertex 520.768 56.7399 23.3607 + vertex 515.375 57.5834 24.3165 + endloop + endfacet + facet normal 0.103882 -0.378123 0.919909 + outer loop + vertex 515.375 57.5834 24.3165 + vertex 520.768 56.7399 23.3607 + vertex 520.957 58.9364 24.2422 + endloop + endfacet + facet normal 0.103523 -0.37811 0.919954 + outer loop + vertex 520.768 56.7399 23.3607 + vertex 526.761 58.2513 23.3075 + vertex 520.957 58.9364 24.2422 + endloop + endfacet + facet normal 0.104061 -0.375133 0.921112 + outer loop + vertex 520.957 58.9364 24.2422 + vertex 526.761 58.2513 23.3075 + vertex 526.876 60.4261 24.1803 + endloop + endfacet + facet normal 0.076159 -0.304516 0.949457 + outer loop + vertex 518.998 33.9886 17.8299 + vertex 523.979 35.6799 17.9728 + vertex 517.871 36.8235 18.8295 + endloop + endfacet + facet normal 0.0782214 -0.297945 0.951373 + outer loop + vertex 529.941 36.8096 17.8364 + vertex 527.138 39.3759 18.8705 + vertex 523.979 35.6799 17.9728 + endloop + endfacet + facet normal 0.0777482 -0.297578 0.951526 + outer loop + vertex 527.138 39.3759 18.8705 + vertex 517.871 36.8235 18.8295 + vertex 523.979 35.6799 17.9728 + endloop + endfacet + facet normal 0.124173 -0.483012 0.866765 + outer loop + vertex 523.331 31.1519 15.8981 + vertex 529.244 32.6722 15.8982 + vertex 523.433 33.1663 17.0061 + endloop + endfacet + facet normal 0.123772 -0.485159 0.865622 + outer loop + vertex 523.433 33.1663 17.0061 + vertex 529.244 32.6722 15.8982 + vertex 529.303 34.669 17.0089 + endloop + endfacet + facet normal 0.122876 -0.484679 0.866018 + outer loop + vertex 517.936 29.8063 15.9104 + vertex 523.331 31.1519 15.8981 + vertex 518.091 31.8105 17.0102 + endloop + endfacet + facet normal 0.123267 -0.483031 0.866883 + outer loop + vertex 518.091 31.8105 17.0102 + vertex 523.331 31.1519 15.8981 + vertex 523.433 33.1663 17.0061 + endloop + endfacet + facet normal 0.0987426 -0.386251 0.917093 + outer loop + vertex 518.091 31.8105 17.0102 + vertex 523.433 33.1663 17.0061 + vertex 518.998 33.9886 17.8299 + endloop + endfacet + facet normal 0.101323 -0.376224 0.920972 + outer loop + vertex 518.998 33.9886 17.8299 + vertex 523.433 33.1663 17.0061 + vertex 523.979 35.6799 17.9728 + endloop + endfacet + facet normal 0.0956374 -0.375357 0.921933 + outer loop + vertex 523.433 33.1663 17.0061 + vertex 529.303 34.669 17.0089 + vertex 523.979 35.6799 17.9728 + endloop + endfacet + facet normal 0.0936211 -0.383121 0.918941 + outer loop + vertex 523.979 35.6799 17.9728 + vertex 529.303 34.669 17.0089 + vertex 529.941 36.8096 17.8364 + endloop + endfacet + facet normal 0.195968 -0.761028 0.618412 + outer loop + vertex 523.765 28.3045 12.9786 + vertex 529.644 29.8123 12.9711 + vertex 523.533 29.5279 14.5576 + endloop + endfacet + facet normal 0.194988 -0.764884 0.613947 + outer loop + vertex 523.533 29.5279 14.5576 + vertex 529.644 29.8123 12.9711 + vertex 529.424 31.032 14.5606 + endloop + endfacet + facet normal 0.191724 -0.762176 0.618329 + outer loop + vertex 518.346 26.9675 13.0106 + vertex 523.765 28.3045 12.9786 + vertex 518.124 28.1862 14.5817 + endloop + endfacet + facet normal 0.19178 -0.761989 0.618541 + outer loop + vertex 518.124 28.1862 14.5817 + vertex 523.765 28.3045 12.9786 + vertex 523.533 29.5279 14.5576 + endloop + endfacet + facet normal 0.15613 -0.615494 0.772522 + outer loop + vertex 518.124 28.1862 14.5817 + vertex 523.533 29.5279 14.5576 + vertex 517.936 29.8063 15.9104 + endloop + endfacet + facet normal 0.155727 -0.617236 0.771212 + outer loop + vertex 517.936 29.8063 15.9104 + vertex 523.533 29.5279 14.5576 + vertex 523.331 31.1519 15.8981 + endloop + endfacet + facet normal 0.157145 -0.616987 0.771124 + outer loop + vertex 523.533 29.5279 14.5576 + vertex 529.424 31.032 14.5606 + vertex 523.331 31.1519 15.8981 + endloop + endfacet + facet normal 0.157765 -0.613661 0.773648 + outer loop + vertex 523.331 31.1519 15.8981 + vertex 529.424 31.032 14.5606 + vertex 529.244 32.6722 15.8982 + endloop + endfacet + facet normal 0.246149 -0.963893 0.101594 + outer loop + vertex 524.104 27.4123 9.27459 + vertex 529.936 28.9004 9.26434 + vertex 523.959 27.5762 11.1825 + endloop + endfacet + facet normal 0.245309 -0.964416 0.0986156 + outer loop + vertex 523.959 27.5762 11.1825 + vertex 529.936 28.9004 9.26434 + vertex 529.81 29.0635 11.1728 + endloop + endfacet + facet normal 0.24099 -0.964891 0.104447 + outer loop + vertex 518.666 26.0579 9.30924 + vertex 524.104 27.4123 9.27459 + vertex 518.531 26.231 11.2197 + endloop + endfacet + facet normal 0.240002 -0.965477 0.10126 + outer loop + vertex 518.531 26.231 11.2197 + vertex 524.104 27.4123 9.27459 + vertex 523.959 27.5762 11.1825 + endloop + endfacet + facet normal 0.224013 -0.892978 0.390396 + outer loop + vertex 518.531 26.231 11.2197 + vertex 523.959 27.5762 11.1825 + vertex 518.346 26.9675 13.0106 + endloop + endfacet + facet normal 0.223065 -0.894734 0.386903 + outer loop + vertex 518.346 26.9675 13.0106 + vertex 523.959 27.5762 11.1825 + vertex 523.765 28.3045 12.9786 + endloop + endfacet + facet normal 0.227774 -0.893536 0.386926 + outer loop + vertex 523.959 27.5762 11.1825 + vertex 529.81 29.0635 11.1728 + vertex 523.765 28.3045 12.9786 + endloop + endfacet + facet normal 0.229002 -0.890954 0.392121 + outer loop + vertex 523.765 28.3045 12.9786 + vertex 529.81 29.0635 11.1728 + vertex 529.644 29.8123 12.9711 + endloop + endfacet + facet normal 0.210572 -0.822486 -0.528372 + outer loop + vertex 523.833 28.9022 5.69708 + vertex 529.752 30.4184 5.69576 + vertex 524.136 27.8852 7.40108 + endloop + endfacet + facet normal 0.206486 -0.81857 -0.53601 + outer loop + vertex 524.136 27.8852 7.40108 + vertex 529.752 30.4184 5.69576 + vertex 529.981 29.3657 7.39185 + endloop + endfacet + facet normal 0.207224 -0.826525 -0.523368 + outer loop + vertex 518.292 27.4967 5.72312 + vertex 523.833 28.9022 5.69708 + vertex 518.662 26.5086 7.42996 + endloop + endfacet + facet normal 0.204466 -0.824103 -0.52825 + outer loop + vertex 518.662 26.5086 7.42996 + vertex 523.833 28.9022 5.69708 + vertex 524.136 27.8852 7.40108 + endloop + endfacet + facet normal 0.236396 -0.944747 -0.227088 + outer loop + vertex 518.662 26.5086 7.42996 + vertex 524.136 27.8852 7.40108 + vertex 518.666 26.0579 9.30924 + endloop + endfacet + facet normal 0.233556 -0.943709 -0.234234 + outer loop + vertex 518.666 26.0579 9.30924 + vertex 524.136 27.8852 7.40108 + vertex 524.104 27.4123 9.27459 + endloop + endfacet + facet normal 0.238376 -0.942593 -0.233871 + outer loop + vertex 524.136 27.8852 7.40108 + vertex 529.981 29.3657 7.39185 + vertex 524.104 27.4123 9.27459 + endloop + endfacet + facet normal 0.240337 -0.943393 -0.22858 + outer loop + vertex 524.104 27.4123 9.27459 + vertex 529.981 29.3657 7.39185 + vertex 529.936 28.9004 9.26434 + endloop + endfacet + facet normal 0.104354 -0.446858 -0.888498 + outer loop + vertex 522.389 32.4546 3.15429 + vertex 527.766 33.425 3.29776 + vertex 523.076 30.3694 4.28373 + endloop + endfacet + facet normal 0.121502 -0.468794 -0.874911 + outer loop + vertex 523.076 30.3694 4.28373 + vertex 527.766 33.425 3.29776 + vertex 529.03 31.9058 4.28735 + endloop + endfacet + facet normal 0.127291 -0.466399 -0.875368 + outer loop + vertex 516.931 30.6642 3.3146 + vertex 522.389 32.4546 3.15429 + vertex 517.642 28.9873 4.31138 + endloop + endfacet + facet normal 0.108778 -0.445487 -0.888656 + outer loop + vertex 517.642 28.9873 4.31138 + vertex 522.389 32.4546 3.15429 + vertex 523.076 30.3694 4.28373 + endloop + endfacet + facet normal 0.159288 -0.641323 -0.750555 + outer loop + vertex 517.642 28.9873 4.31138 + vertex 523.076 30.3694 4.28373 + vertex 518.292 27.4967 5.72312 + endloop + endfacet + facet normal 0.159125 -0.641145 -0.750741 + outer loop + vertex 518.292 27.4967 5.72312 + vertex 523.076 30.3694 4.28373 + vertex 523.833 28.9022 5.69708 + endloop + endfacet + facet normal 0.165271 -0.638702 -0.751495 + outer loop + vertex 523.076 30.3694 4.28373 + vertex 529.03 31.9058 4.28735 + vertex 523.833 28.9022 5.69708 + endloop + endfacet + facet normal 0.162665 -0.635665 -0.754632 + outer loop + vertex 523.833 28.9022 5.69708 + vertex 529.03 31.9058 4.28735 + vertex 529.752 30.4184 5.69576 + endloop + endfacet + facet normal 0.0795413 -0.300198 -0.950555 + outer loop + vertex 527.766 33.425 3.29776 + vertex 522.389 32.4546 3.15429 + vertex 530.532 37.4155 2.26898 + endloop + endfacet + facet normal 0.0700525 -0.298757 -0.951755 + outer loop + vertex 516.931 30.6642 3.3146 + vertex 520.134 34.8191 2.24611 + vertex 522.389 32.4546 3.15429 + endloop + endfacet + facet normal 0.0755016 -0.293972 -0.952827 + outer loop + vertex 520.134 34.8191 2.24611 + vertex 530.532 37.4155 2.26898 + vertex 522.389 32.4546 3.15429 + endloop + endfacet + facet normal 0.0538137 -0.207395 -0.976776 + outer loop + vertex 519.518 39.3254 1.25534 + vertex 528.835 41.4761 1.31203 + vertex 520.134 34.8191 2.24611 + endloop + endfacet + facet normal 0.0539917 -0.20762 -0.976718 + outer loop + vertex 520.134 34.8191 2.24611 + vertex 528.835 41.4761 1.31203 + vertex 530.532 37.4155 2.26898 + endloop + endfacet + facet normal 0.193824 -0.799781 0.56814 + outer loop + vertex 525.859 67.2902 30.4829 + vertex 531.57 68.9258 30.837 + vertex 522.487 68.4747 33.3006 + endloop + endfacet + facet normal 0.202025 -0.814376 0.544039 + outer loop + vertex 538.34 70.3051 30.3876 + vertex 534.356 71.2697 33.311 + vertex 531.57 68.9258 30.837 + endloop + endfacet + facet normal 0.190428 -0.810705 0.55362 + outer loop + vertex 534.356 71.2697 33.311 + vertex 522.487 68.4747 33.3006 + vertex 531.57 68.9258 30.837 + endloop + endfacet + facet normal 0.187959 -0.713758 0.674701 + outer loop + vertex 531.909 65.5332 26.7365 + vertex 537.986 67.0784 26.678 + vertex 531.65 67.2058 28.578 + endloop + endfacet + facet normal 0.185643 -0.721126 0.667469 + outer loop + vertex 531.65 67.2058 28.578 + vertex 537.986 67.0784 26.678 + vertex 537.879 68.7521 28.5162 + endloop + endfacet + facet normal 0.181295 -0.705276 0.685359 + outer loop + vertex 525.843 64.0263 26.7904 + vertex 531.909 65.5332 26.7365 + vertex 525.486 65.7101 28.6176 + endloop + endfacet + facet normal 0.178027 -0.715837 0.675192 + outer loop + vertex 525.486 65.7101 28.6176 + vertex 531.909 65.5332 26.7365 + vertex 531.65 67.2058 28.578 + endloop + endfacet + facet normal 0.190166 -0.767538 0.612146 + outer loop + vertex 525.486 65.7101 28.6176 + vertex 531.65 67.2058 28.578 + vertex 525.859 67.2902 30.4829 + endloop + endfacet + facet normal 0.185814 -0.778579 0.599406 + outer loop + vertex 525.859 67.2902 30.4829 + vertex 531.65 67.2058 28.578 + vertex 531.57 68.9258 30.837 + endloop + endfacet + facet normal 0.198666 -0.776355 0.598168 + outer loop + vertex 531.65 67.2058 28.578 + vertex 537.879 68.7521 28.5162 + vertex 531.57 68.9258 30.837 + endloop + endfacet + facet normal 0.198047 -0.777727 0.596589 + outer loop + vertex 531.57 68.9258 30.837 + vertex 537.879 68.7521 28.5162 + vertex 538.34 70.3051 30.3876 + endloop + endfacet + facet normal 0.137526 -0.49279 0.859211 + outer loop + vertex 532.797 61.9673 24.1327 + vertex 538.637 63.5137 24.0849 + vertex 532.408 63.8314 25.2641 + endloop + endfacet + facet normal 0.136743 -0.497824 0.85643 + outer loop + vertex 532.408 63.8314 25.2641 + vertex 538.637 63.5137 24.0849 + vertex 538.332 65.3703 25.2128 + endloop + endfacet + facet normal 0.133963 -0.488076 0.862459 + outer loop + vertex 526.876 60.4261 24.1803 + vertex 532.797 61.9673 24.1327 + vertex 526.458 62.3151 25.3142 + endloop + endfacet + facet normal 0.133067 -0.493796 0.859336 + outer loop + vertex 526.458 62.3151 25.3142 + vertex 532.797 61.9673 24.1327 + vertex 532.408 63.8314 25.2641 + endloop + endfacet + facet normal 0.162099 -0.610516 0.775238 + outer loop + vertex 526.458 62.3151 25.3142 + vertex 532.408 63.8314 25.2641 + vertex 525.843 64.0263 26.7904 + endloop + endfacet + facet normal 0.160474 -0.618458 0.769258 + outer loop + vertex 525.843 64.0263 26.7904 + vertex 532.408 63.8314 25.2641 + vertex 531.909 65.5332 26.7365 + endloop + endfacet + facet normal 0.166861 -0.616658 0.769344 + outer loop + vertex 532.408 63.8314 25.2641 + vertex 538.332 65.3703 25.2128 + vertex 531.909 65.5332 26.7365 + endloop + endfacet + facet normal 0.165641 -0.62257 0.764833 + outer loop + vertex 531.909 65.5332 26.7365 + vertex 538.332 65.3703 25.2128 + vertex 537.986 67.0784 26.678 + endloop + endfacet + facet normal 0.0820546 -0.273491 0.958368 + outer loop + vertex 532.438 57.2829 22.5669 + vertex 537.974 59.1725 22.6321 + vertex 532.76 59.8257 23.2649 + endloop + endfacet + facet normal 0.0808115 -0.28132 0.956205 + outer loop + vertex 532.76 59.8257 23.2649 + vertex 537.974 59.1725 22.6321 + vertex 538.616 61.3902 23.2304 + endloop + endfacet + facet normal 0.0760841 -0.284786 0.955567 + outer loop + vertex 525.995 56.0232 22.7044 + vertex 532.438 57.2829 22.5669 + vertex 526.761 58.2513 23.3075 + endloop + endfacet + facet normal 0.0784865 -0.273148 0.958765 + outer loop + vertex 526.761 58.2513 23.3075 + vertex 532.438 57.2829 22.5669 + vertex 532.76 59.8257 23.2649 + endloop + endfacet + facet normal 0.104984 -0.375139 0.921004 + outer loop + vertex 526.761 58.2513 23.3075 + vertex 532.76 59.8257 23.2649 + vertex 526.876 60.4261 24.1803 + endloop + endfacet + facet normal 0.105006 -0.375006 0.921056 + outer loop + vertex 526.876 60.4261 24.1803 + vertex 532.76 59.8257 23.2649 + vertex 532.797 61.9673 24.1327 + endloop + endfacet + facet normal 0.105631 -0.374991 0.920991 + outer loop + vertex 532.76 59.8257 23.2649 + vertex 538.616 61.3902 23.2304 + vertex 532.797 61.9673 24.1327 + endloop + endfacet + facet normal 0.106087 -0.372122 0.922101 + outer loop + vertex 532.797 61.9673 24.1327 + vertex 538.616 61.3902 23.2304 + vertex 538.637 63.5137 24.0849 + endloop + endfacet + facet normal 0.0763879 -0.299776 0.950947 + outer loop + vertex 529.941 36.8096 17.8364 + vertex 535.445 38.6365 17.9702 + vertex 527.138 39.3759 18.8705 + endloop + endfacet + facet normal 0.0782757 -0.294769 0.952357 + outer loop + vertex 541.858 39.8851 17.8295 + vertex 538.25 42.2572 18.8603 + vertex 535.445 38.6365 17.9702 + endloop + endfacet + facet normal 0.077098 -0.293943 0.952708 + outer loop + vertex 538.25 42.2572 18.8603 + vertex 527.138 39.3759 18.8705 + vertex 535.445 38.6365 17.9702 + endloop + endfacet + facet normal 0.12649 -0.486733 0.864344 + outer loop + vertex 535.269 34.2389 15.9016 + vertex 541.255 35.8039 15.907 + vertex 535.304 36.2158 17.0098 + endloop + endfacet + facet normal 0.126937 -0.484082 0.865766 + outer loop + vertex 535.304 36.2158 17.0098 + vertex 541.255 35.8039 15.907 + vertex 541.34 37.7904 17.0053 + endloop + endfacet + facet normal 0.125638 -0.485087 0.865394 + outer loop + vertex 529.244 32.6722 15.8982 + vertex 535.269 34.2389 15.9016 + vertex 529.303 34.669 17.0089 + endloop + endfacet + facet normal 0.125346 -0.486789 0.864479 + outer loop + vertex 529.303 34.669 17.0089 + vertex 535.269 34.2389 15.9016 + vertex 535.304 36.2158 17.0098 + endloop + endfacet + facet normal 0.0989183 -0.384295 0.917896 + outer loop + vertex 529.303 34.669 17.0089 + vertex 535.304 36.2158 17.0098 + vertex 529.941 36.8096 17.8364 + endloop + endfacet + facet normal 0.101031 -0.371954 0.922737 + outer loop + vertex 529.941 36.8096 17.8364 + vertex 535.304 36.2158 17.0098 + vertex 535.445 38.6365 17.9702 + endloop + endfacet + facet normal 0.0977158 -0.371909 0.923112 + outer loop + vertex 535.304 36.2158 17.0098 + vertex 541.34 37.7904 17.0053 + vertex 535.445 38.6365 17.9702 + endloop + endfacet + facet normal 0.0950482 -0.384781 0.918101 + outer loop + vertex 535.445 38.6365 17.9702 + vertex 541.34 37.7904 17.0053 + vertex 541.858 39.8851 17.8295 + endloop + endfacet + facet normal 0.200378 -0.761934 0.615878 + outer loop + vertex 535.59 31.3677 12.9803 + vertex 541.481 32.9246 12.9899 + vertex 535.408 32.6014 14.5659 + endloop + endfacet + facet normal 0.20032 -0.762168 0.615607 + outer loop + vertex 535.408 32.6014 14.5659 + vertex 541.481 32.9246 12.9899 + vertex 541.339 34.1652 14.572 + endloop + endfacet + facet normal 0.198886 -0.763995 0.613804 + outer loop + vertex 529.644 29.8123 12.9711 + vertex 535.59 31.3677 12.9803 + vertex 529.424 31.032 14.5606 + endloop + endfacet + facet normal 0.199332 -0.762162 0.615935 + outer loop + vertex 529.424 31.032 14.5606 + vertex 535.59 31.3677 12.9803 + vertex 535.408 32.6014 14.5659 + endloop + endfacet + facet normal 0.160141 -0.61326 0.773477 + outer loop + vertex 529.424 31.032 14.5606 + vertex 535.408 32.6014 14.5659 + vertex 529.244 32.6722 15.8982 + endloop + endfacet + facet normal 0.159688 -0.615842 0.771517 + outer loop + vertex 529.244 32.6722 15.8982 + vertex 535.408 32.6014 14.5659 + vertex 535.269 34.2389 15.9016 + endloop + endfacet + facet normal 0.161504 -0.615562 0.771362 + outer loop + vertex 535.408 32.6014 14.5659 + vertex 541.339 34.1652 14.572 + vertex 535.269 34.2389 15.9016 + endloop + endfacet + facet normal 0.160997 -0.618386 0.769207 + outer loop + vertex 535.269 34.2389 15.9016 + vertex 541.339 34.1652 14.572 + vertex 541.255 35.8039 15.907 + endloop + endfacet + facet normal 0.252612 -0.962058 0.10311 + outer loop + vertex 535.831 30.4397 9.27178 + vertex 541.691 31.9793 9.28119 + vertex 535.73 30.6176 11.1794 + endloop + endfacet + facet normal 0.253988 -0.961149 0.108084 + outer loop + vertex 535.73 30.6176 11.1794 + vertex 541.691 31.9793 9.28119 + vertex 541.604 32.1708 11.189 + endloop + endfacet + facet normal 0.251275 -0.962852 0.0988767 + outer loop + vertex 529.936 28.9004 9.26434 + vertex 535.831 30.4397 9.27178 + vertex 529.81 29.0635 11.1728 + endloop + endfacet + facet normal 0.252439 -0.962104 0.103105 + outer loop + vertex 529.81 29.0635 11.1728 + vertex 535.831 30.4397 9.27178 + vertex 535.73 30.6176 11.1794 + endloop + endfacet + facet normal 0.233162 -0.889899 0.392065 + outer loop + vertex 529.81 29.0635 11.1728 + vertex 535.73 30.6176 11.1794 + vertex 529.644 29.8123 12.9711 + endloop + endfacet + facet normal 0.232529 -0.891281 0.389292 + outer loop + vertex 529.644 29.8123 12.9711 + vertex 535.73 30.6176 11.1794 + vertex 535.59 31.3677 12.9803 + endloop + endfacet + facet normal 0.234895 -0.890688 0.389229 + outer loop + vertex 535.73 30.6176 11.1794 + vertex 541.604 32.1708 11.189 + vertex 535.59 31.3677 12.9803 + endloop + endfacet + facet normal 0.234821 -0.890849 0.388906 + outer loop + vertex 535.59 31.3677 12.9803 + vertex 541.604 32.1708 11.189 + vertex 541.481 32.9246 12.9899 + endloop + endfacet + facet normal 0.214777 -0.814965 -0.538241 + outer loop + vertex 535.667 31.9594 5.71014 + vertex 541.498 33.4892 5.72072 + vertex 535.865 30.8951 7.40062 + endloop + endfacet + facet normal 0.216527 -0.81665 -0.534975 + outer loop + vertex 535.865 30.8951 7.40062 + vertex 541.498 33.4892 5.72072 + vertex 541.698 32.4349 7.41118 + endloop + endfacet + facet normal 0.214069 -0.816705 -0.53588 + outer loop + vertex 529.752 30.4184 5.69576 + vertex 535.667 31.9594 5.71014 + vertex 529.981 29.3657 7.39185 + endloop + endfacet + facet normal 0.212776 -0.815445 -0.538309 + outer loop + vertex 529.981 29.3657 7.39185 + vertex 535.667 31.9594 5.71014 + vertex 535.865 30.8951 7.40062 + endloop + endfacet + facet normal 0.245269 -0.942222 -0.228169 + outer loop + vertex 529.981 29.3657 7.39185 + vertex 535.865 30.8951 7.40062 + vertex 529.936 28.9004 9.26434 + endloop + endfacet + facet normal 0.246418 -0.942682 -0.225008 + outer loop + vertex 529.936 28.9004 9.26434 + vertex 535.865 30.8951 7.40062 + vertex 535.831 30.4397 9.27178 + endloop + endfacet + facet normal 0.249062 -0.942036 -0.224804 + outer loop + vertex 535.865 30.8951 7.40062 + vertex 541.698 32.4349 7.41118 + vertex 535.831 30.4397 9.27178 + endloop + endfacet + facet normal 0.247748 -0.941519 -0.228392 + outer loop + vertex 535.831 30.4397 9.27178 + vertex 541.698 32.4349 7.41118 + vertex 541.691 31.9793 9.28119 + endloop + endfacet + facet normal 0.110072 -0.447367 -0.887551 + outer loop + vertex 534.09 35.4847 3.16526 + vertex 539.733 36.5615 3.32232 + vertex 535.032 33.465 4.30002 + endloop + endfacet + facet normal 0.124288 -0.465407 -0.876327 + outer loop + vertex 535.032 33.465 4.30002 + vertex 539.733 36.5615 3.32232 + vertex 540.912 35.0103 4.31328 + endloop + endfacet + facet normal 0.131953 -0.461601 -0.877219 + outer loop + vertex 527.766 33.425 3.29776 + vertex 534.09 35.4847 3.16526 + vertex 529.03 31.9058 4.28735 + endloop + endfacet + facet normal 0.117312 -0.444328 -0.88815 + outer loop + vertex 529.03 31.9058 4.28735 + vertex 534.09 35.4847 3.16526 + vertex 535.032 33.465 4.30002 + endloop + endfacet + facet normal 0.16637 -0.634239 -0.755024 + outer loop + vertex 529.03 31.9058 4.28735 + vertex 535.032 33.465 4.30002 + vertex 529.752 30.4184 5.69576 + endloop + endfacet + facet normal 0.16737 -0.635417 -0.753812 + outer loop + vertex 529.752 30.4184 5.69576 + vertex 535.032 33.465 4.30002 + vertex 535.667 31.9594 5.71014 + endloop + endfacet + facet normal 0.168579 -0.634991 -0.753902 + outer loop + vertex 535.032 33.465 4.30002 + vertex 540.912 35.0103 4.31328 + vertex 535.667 31.9594 5.71014 + endloop + endfacet + facet normal 0.167679 -0.63394 -0.754986 + outer loop + vertex 535.667 31.9594 5.71014 + vertex 540.912 35.0103 4.31328 + vertex 541.498 33.4892 5.72072 + endloop + endfacet + facet normal 0.0843925 -0.303836 -0.948979 + outer loop + vertex 539.733 36.5615 3.32232 + vertex 534.09 35.4847 3.16526 + vertex 542.268 40.5268 2.27812 + endloop + endfacet + facet normal 0.0774075 -0.298871 -0.951149 + outer loop + vertex 527.766 33.425 3.29776 + vertex 530.532 37.4155 2.26898 + vertex 534.09 35.4847 3.16526 + endloop + endfacet + facet normal 0.0791982 -0.29593 -0.951921 + outer loop + vertex 530.532 37.4155 2.26898 + vertex 542.268 40.5268 2.27812 + vertex 534.09 35.4847 3.16526 + endloop + endfacet + facet normal 0.0554804 -0.207009 -0.976765 + outer loop + vertex 528.835 41.4761 1.31203 + vertex 540.129 44.4659 1.31987 + vertex 530.532 37.4155 2.26898 + endloop + endfacet + facet normal 0.0557296 -0.207337 -0.976681 + outer loop + vertex 530.532 37.4155 2.26898 + vertex 540.129 44.4659 1.31987 + vertex 542.268 40.5268 2.27812 + endloop + endfacet + facet normal 0.210166 -0.806548 0.55255 + outer loop + vertex 538.34 70.3051 30.3876 + vertex 544.121 72.0091 30.676 + vertex 534.356 71.2697 33.311 + endloop + endfacet + facet normal 0.219252 -0.818515 0.531 + outer loop + vertex 550.824 73.4636 30.1504 + vertex 546.945 74.3302 33.088 + vertex 544.121 72.0091 30.676 + endloop + endfacet + facet normal 0.207702 -0.814926 0.541068 + outer loop + vertex 546.945 74.3302 33.088 + vertex 534.356 71.2697 33.311 + vertex 544.121 72.0091 30.676 + endloop + endfacet + facet normal 0.201684 -0.722129 0.661705 + outer loop + vertex 544.017 68.6382 26.6003 + vertex 549.991 70.2114 26.4963 + vertex 544.057 70.32 28.4235 + endloop + endfacet + facet normal 0.200665 -0.72512 0.658738 + outer loop + vertex 544.057 70.32 28.4235 + vertex 549.991 70.2114 26.4963 + vertex 550.163 71.9058 28.309 + endloop + endfacet + facet normal 0.194706 -0.719561 0.666574 + outer loop + vertex 537.986 67.0784 26.678 + vertex 544.017 68.6382 26.6003 + vertex 537.879 68.7521 28.5162 + endloop + endfacet + facet normal 0.193497 -0.723252 0.662922 + outer loop + vertex 537.879 68.7521 28.5162 + vertex 544.017 68.6382 26.6003 + vertex 544.057 70.32 28.4235 + endloop + endfacet + facet normal 0.206202 -0.777371 0.594285 + outer loop + vertex 537.879 68.7521 28.5162 + vertex 544.057 70.32 28.4235 + vertex 538.34 70.3051 30.3876 + endloop + endfacet + facet normal 0.202617 -0.786222 0.583782 + outer loop + vertex 538.34 70.3051 30.3876 + vertex 544.057 70.32 28.4235 + vertex 544.121 72.0091 30.676 + endloop + endfacet + facet normal 0.214607 -0.784339 0.582028 + outer loop + vertex 544.057 70.32 28.4235 + vertex 550.163 71.9058 28.309 + vertex 544.121 72.0091 30.676 + endloop + endfacet + facet normal 0.21558 -0.782289 0.584422 + outer loop + vertex 544.121 72.0091 30.676 + vertex 550.163 71.9058 28.309 + vertex 550.824 73.4636 30.1504 + endloop + endfacet + facet normal 0.144243 -0.495016 0.856827 + outer loop + vertex 544.423 65.0554 24.0275 + vertex 550.206 66.6081 23.951 + vertex 544.219 66.9211 25.1395 + endloop + endfacet + facet normal 0.144143 -0.495632 0.856488 + outer loop + vertex 544.219 66.9211 25.1395 + vertex 550.206 66.6081 23.951 + vertex 550.078 68.4793 25.0554 + endloop + endfacet + facet normal 0.140936 -0.497009 0.856224 + outer loop + vertex 538.637 63.5137 24.0849 + vertex 544.423 65.0554 24.0275 + vertex 538.332 65.3703 25.2128 + endloop + endfacet + facet normal 0.141177 -0.495491 0.857063 + outer loop + vertex 538.332 65.3703 25.2128 + vertex 544.423 65.0554 24.0275 + vertex 544.219 66.9211 25.1395 + endloop + endfacet + facet normal 0.173048 -0.620858 0.764584 + outer loop + vertex 538.332 65.3703 25.2128 + vertex 544.219 66.9211 25.1395 + vertex 537.986 67.0784 26.678 + endloop + endfacet + facet normal 0.171838 -0.626483 0.760257 + outer loop + vertex 537.986 67.0784 26.678 + vertex 544.219 66.9211 25.1395 + vertex 544.017 68.6382 26.6003 + endloop + endfacet + facet normal 0.177292 -0.625478 0.759832 + outer loop + vertex 544.219 66.9211 25.1395 + vertex 550.078 68.4793 25.0554 + vertex 544.017 68.6382 26.6003 + endloop + endfacet + facet normal 0.177598 -0.624104 0.76089 + outer loop + vertex 544.017 68.6382 26.6003 + vertex 550.078 68.4793 25.0554 + vertex 549.991 70.2114 26.4963 + endloop + endfacet + facet normal 0.0853405 -0.268034 0.959622 + outer loop + vertex 544.242 60.4428 22.4948 + vertex 549.613 62.3183 22.541 + vertex 544.388 62.9433 23.1802 + endloop + endfacet + facet normal 0.0843055 -0.274817 0.957793 + outer loop + vertex 544.388 62.9433 23.1802 + vertex 549.613 62.3183 22.541 + vertex 550.146 64.4979 23.1194 + endloop + endfacet + facet normal 0.0778357 -0.280583 0.956668 + outer loop + vertex 537.974 59.1725 22.6321 + vertex 544.242 60.4428 22.4948 + vertex 538.616 61.3902 23.2304 + endloop + endfacet + facet normal 0.0804233 -0.267876 0.960091 + outer loop + vertex 538.616 61.3902 23.2304 + vertex 544.242 60.4428 22.4948 + vertex 544.388 62.9433 23.1802 + endloop + endfacet + facet normal 0.108124 -0.372057 0.921891 + outer loop + vertex 538.616 61.3902 23.2304 + vertex 544.388 62.9433 23.1802 + vertex 538.637 63.5137 24.0849 + endloop + endfacet + facet normal 0.108187 -0.371664 0.922042 + outer loop + vertex 538.637 63.5137 24.0849 + vertex 544.388 62.9433 23.1802 + vertex 544.423 65.0554 24.0275 + endloop + endfacet + facet normal 0.110057 -0.371615 0.921841 + outer loop + vertex 544.388 62.9433 23.1802 + vertex 550.146 64.4979 23.1194 + vertex 544.423 65.0554 24.0275 + endloop + endfacet + facet normal 0.110774 -0.367073 0.923573 + outer loop + vertex 544.423 65.0554 24.0275 + vertex 550.146 64.4979 23.1194 + vertex 550.206 66.6081 23.951 + endloop + endfacet + facet normal 0.0773885 -0.295986 0.952052 + outer loop + vertex 541.858 39.8851 17.8295 + vertex 547.383 41.7566 17.9622 + vertex 538.25 42.2572 18.8603 + endloop + endfacet + facet normal 0.0812665 -0.293907 0.952373 + outer loop + vertex 553.812 43.0705 17.8191 + vertex 550.064 45.3591 18.8453 + vertex 547.383 41.7566 17.9622 + endloop + endfacet + facet normal 0.0777631 -0.29155 0.95339 + outer loop + vertex 550.064 45.3591 18.8453 + vertex 538.25 42.2572 18.8603 + vertex 547.383 41.7566 17.9622 + endloop + endfacet + facet normal 0.13174 -0.486833 0.863503 + outer loop + vertex 547.185 37.3861 15.9025 + vertex 553.065 38.9735 15.9003 + vertex 547.322 39.3739 17.0024 + endloop + endfacet + facet normal 0.131459 -0.488459 0.862628 + outer loop + vertex 547.322 39.3739 17.0024 + vertex 553.065 38.9735 15.9003 + vertex 553.248 40.9681 17.002 + endloop + endfacet + facet normal 0.129787 -0.483996 0.865392 + outer loop + vertex 541.255 35.8039 15.907 + vertex 547.185 37.3861 15.9025 + vertex 541.34 37.7904 17.0053 + endloop + endfacet + facet normal 0.1293 -0.486861 0.863856 + outer loop + vertex 541.34 37.7904 17.0053 + vertex 547.185 37.3861 15.9025 + vertex 547.322 39.3739 17.0024 + endloop + endfacet + facet normal 0.102659 -0.386121 0.916718 + outer loop + vertex 541.34 37.7904 17.0053 + vertex 547.322 39.3739 17.0024 + vertex 541.858 39.8851 17.8295 + endloop + endfacet + facet normal 0.104528 -0.373949 0.92154 + outer loop + vertex 541.858 39.8851 17.8295 + vertex 547.322 39.3739 17.0024 + vertex 547.383 41.7566 17.9622 + endloop + endfacet + facet normal 0.100676 -0.374012 0.921943 + outer loop + vertex 547.322 39.3739 17.0024 + vertex 553.248 40.9681 17.002 + vertex 547.383 41.7566 17.9622 + endloop + endfacet + facet normal 0.0988054 -0.383441 0.918265 + outer loop + vertex 547.383 41.7566 17.9622 + vertex 553.248 40.9681 17.002 + vertex 553.812 43.0705 17.8191 + endloop + endfacet + facet normal 0.205028 -0.761434 0.614965 + outer loop + vertex 547.321 34.4885 12.9899 + vertex 553.148 36.0574 12.9897 + vertex 547.21 35.7353 14.5707 + endloop + endfacet + facet normal 0.205267 -0.76049 0.616052 + outer loop + vertex 547.21 35.7353 14.5707 + vertex 553.148 36.0574 12.9897 + vertex 553.052 37.3113 14.5696 + endloop + endfacet + facet normal 0.203897 -0.761428 0.615348 + outer loop + vertex 541.481 32.9246 12.9899 + vertex 547.321 34.4885 12.9899 + vertex 541.339 34.1652 14.572 + endloop + endfacet + facet normal 0.203836 -0.761671 0.615068 + outer loop + vertex 541.339 34.1652 14.572 + vertex 547.321 34.4885 12.9899 + vertex 547.21 35.7353 14.5707 + endloop + endfacet + facet normal 0.165393 -0.617791 0.768752 + outer loop + vertex 541.339 34.1652 14.572 + vertex 547.21 35.7353 14.5707 + vertex 541.255 35.8039 15.907 + endloop + endfacet + facet normal 0.1654 -0.617752 0.768782 + outer loop + vertex 541.255 35.8039 15.907 + vertex 547.21 35.7353 14.5707 + vertex 547.185 37.3861 15.9025 + endloop + endfacet + facet normal 0.166749 -0.617597 0.768615 + outer loop + vertex 547.21 35.7353 14.5707 + vertex 553.052 37.3113 14.5696 + vertex 547.185 37.3861 15.9025 + endloop + endfacet + facet normal 0.166854 -0.617033 0.769045 + outer loop + vertex 547.185 37.3861 15.9025 + vertex 553.052 37.3113 14.5696 + vertex 553.065 38.9735 15.9003 + endloop + endfacet + facet normal 0.258646 -0.95984 0.108669 + outer loop + vertex 547.519 33.5381 9.28461 + vertex 553.345 35.1079 9.2843 + vertex 547.438 33.732 11.1914 + endloop + endfacet + facet normal 0.258112 -0.960198 0.106758 + outer loop + vertex 547.438 33.732 11.1914 + vertex 553.345 35.1079 9.2843 + vertex 553.266 35.2986 11.1906 + endloop + endfacet + facet normal 0.256784 -0.9604 0.108136 + outer loop + vertex 541.691 31.9793 9.28119 + vertex 547.519 33.5381 9.28461 + vertex 541.604 32.1708 11.189 + endloop + endfacet + facet normal 0.256925 -0.960305 0.108643 + outer loop + vertex 541.604 32.1708 11.189 + vertex 547.519 33.5381 9.28461 + vertex 547.438 33.732 11.1914 + endloop + endfacet + facet normal 0.238009 -0.890053 0.38879 + outer loop + vertex 541.604 32.1708 11.189 + vertex 547.438 33.732 11.1914 + vertex 541.481 32.9246 12.9899 + endloop + endfacet + facet normal 0.238221 -0.889601 0.389694 + outer loop + vertex 541.481 32.9246 12.9899 + vertex 547.438 33.732 11.1914 + vertex 547.321 34.4885 12.9899 + endloop + endfacet + facet normal 0.239116 -0.889376 0.389658 + outer loop + vertex 547.438 33.732 11.1914 + vertex 553.266 35.2986 11.1906 + vertex 547.321 34.4885 12.9899 + endloop + endfacet + facet normal 0.239338 -0.8889 0.390606 + outer loop + vertex 547.321 34.4885 12.9899 + vertex 553.266 35.2986 11.1906 + vertex 553.148 36.0574 12.9897 + endloop + endfacet + facet normal 0.219097 -0.817121 -0.533207 + outer loop + vertex 547.282 35.0218 5.72595 + vertex 553.067 36.5714 5.72808 + vertex 547.508 33.9794 7.41584 + endloop + endfacet + facet normal 0.218382 -0.816448 -0.53453 + outer loop + vertex 547.508 33.9794 7.41584 + vertex 553.067 36.5714 5.72808 + vertex 553.32 35.5343 7.41544 + endloop + endfacet + facet normal 0.216832 -0.816576 -0.534965 + outer loop + vertex 541.498 33.4892 5.72072 + vertex 547.282 35.0218 5.72595 + vertex 541.698 32.4349 7.41118 + endloop + endfacet + facet normal 0.217761 -0.817458 -0.533238 + outer loop + vertex 541.698 32.4349 7.41118 + vertex 547.282 35.0218 5.72595 + vertex 547.508 33.9794 7.41584 + endloop + endfacet + facet normal 0.250329 -0.940876 -0.228225 + outer loop + vertex 541.698 32.4349 7.41118 + vertex 547.508 33.9794 7.41584 + vertex 541.691 31.9793 9.28119 + endloop + endfacet + facet normal 0.25192 -0.941486 -0.223918 + outer loop + vertex 541.691 31.9793 9.28119 + vertex 547.508 33.9794 7.41584 + vertex 547.519 33.5381 9.28461 + endloop + endfacet + facet normal 0.251858 -0.941502 -0.223922 + outer loop + vertex 547.508 33.9794 7.41584 + vertex 553.32 35.5343 7.41544 + vertex 547.519 33.5381 9.28461 + endloop + endfacet + facet normal 0.253889 -0.942249 -0.218419 + outer loop + vertex 547.519 33.5381 9.28461 + vertex 553.32 35.5343 7.41544 + vertex 553.345 35.1079 9.2843 + endloop + endfacet + facet normal 0.108068 -0.444749 -0.889112 + outer loop + vertex 545.91 38.6165 3.184 + vertex 551.412 39.6734 3.32413 + vertex 546.706 36.5421 4.31845 + endloop + endfacet + facet normal 0.123919 -0.464655 -0.876778 + outer loop + vertex 546.706 36.5421 4.31845 + vertex 551.412 39.6734 3.32413 + vertex 552.488 38.0868 4.31705 + endloop + endfacet + facet normal 0.133281 -0.459666 -0.878034 + outer loop + vertex 539.733 36.5615 3.32232 + vertex 545.91 38.6165 3.184 + vertex 540.912 35.0103 4.31328 + endloop + endfacet + facet normal 0.117487 -0.441395 -0.889588 + outer loop + vertex 540.912 35.0103 4.31328 + vertex 545.91 38.6165 3.184 + vertex 546.706 36.5421 4.31845 + endloop + endfacet + facet normal 0.168223 -0.633759 -0.755017 + outer loop + vertex 540.912 35.0103 4.31328 + vertex 546.706 36.5421 4.31845 + vertex 541.498 33.4892 5.72072 + endloop + endfacet + facet normal 0.168758 -0.634378 -0.754378 + outer loop + vertex 541.498 33.4892 5.72072 + vertex 546.706 36.5421 4.31845 + vertex 547.282 35.0218 5.72595 + endloop + endfacet + facet normal 0.169246 -0.634217 -0.754404 + outer loop + vertex 546.706 36.5421 4.31845 + vertex 552.488 38.0868 4.31705 + vertex 547.282 35.0218 5.72595 + endloop + endfacet + facet normal 0.170594 -0.635767 -0.752793 + outer loop + vertex 547.282 35.0218 5.72595 + vertex 552.488 38.0868 4.31705 + vertex 553.067 36.5714 5.72808 + endloop + endfacet + facet normal 0.0816386 -0.298974 -0.950763 + outer loop + vertex 551.412 39.6734 3.32413 + vertex 545.91 38.6165 3.184 + vertex 554.146 43.7575 2.27461 + endloop + endfacet + facet normal 0.0787387 -0.30062 -0.950488 + outer loop + vertex 539.733 36.5615 3.32232 + vertex 542.268 40.5268 2.27812 + vertex 545.91 38.6165 3.184 + endloop + endfacet + facet normal 0.0806174 -0.297439 -0.951331 + outer loop + vertex 542.268 40.5268 2.27812 + vertex 554.146 43.7575 2.27461 + vertex 545.91 38.6165 3.184 + endloop + endfacet + facet normal 0.0563815 -0.206992 -0.976717 + outer loop + vertex 540.129 44.4659 1.31987 + vertex 552.154 47.775 1.31275 + vertex 542.268 40.5268 2.27812 + endloop + endfacet + facet normal 0.0558017 -0.206227 -0.976912 + outer loop + vertex 542.268 40.5268 2.27812 + vertex 552.154 47.775 1.31275 + vertex 554.146 43.7575 2.27461 + endloop + endfacet + facet normal 0.228629 -0.809529 0.540732 + outer loop + vertex 550.824 73.4636 30.1504 + vertex 556.5 75.2115 30.3671 + vertex 546.945 74.3302 33.088 + endloop + endfacet + facet normal 0.236149 -0.818203 0.524192 + outer loop + vertex 563.01 76.7156 29.7823 + vertex 559.509 77.5717 32.6957 + vertex 556.5 75.2115 30.3671 + endloop + endfacet + facet normal 0.226938 -0.815129 0.532977 + outer loop + vertex 559.509 77.5717 32.6957 + vertex 546.945 74.3302 33.088 + vertex 556.5 75.2115 30.3671 + endloop + endfacet + facet normal 0.211999 -0.723075 0.657434 + outer loop + vertex 555.92 71.801 26.3735 + vertex 561.818 73.4085 26.2399 + vertex 556.199 73.5094 28.1625 + endloop + endfacet + facet normal 0.213738 -0.718145 0.662256 + outer loop + vertex 556.199 73.5094 28.1625 + vertex 561.818 73.4085 26.2399 + vertex 562.167 75.1302 27.9943 + endloop + endfacet + facet normal 0.207802 -0.724364 0.657354 + outer loop + vertex 549.991 70.2114 26.4963 + vertex 555.92 71.801 26.3735 + vertex 550.163 71.9058 28.309 + endloop + endfacet + facet normal 0.208147 -0.723381 0.658327 + outer loop + vertex 550.163 71.9058 28.309 + vertex 555.92 71.801 26.3735 + vertex 556.199 73.5094 28.1625 + endloop + endfacet + facet normal 0.221933 -0.782243 0.582102 + outer loop + vertex 550.163 71.9058 28.309 + vertex 556.199 73.5094 28.1625 + vertex 550.824 73.4636 30.1504 + endloop + endfacet + facet normal 0.220128 -0.78643 0.577124 + outer loop + vertex 550.824 73.4636 30.1504 + vertex 556.199 73.5094 28.1625 + vertex 556.5 75.2115 30.3671 + endloop + endfacet + facet normal 0.229521 -0.785314 0.57498 + outer loop + vertex 556.199 73.5094 28.1625 + vertex 562.167 75.1302 27.9943 + vertex 556.5 75.2115 30.3671 + endloop + endfacet + facet normal 0.23238 -0.779569 0.581611 + outer loop + vertex 556.5 75.2115 30.3671 + vertex 562.167 75.1302 27.9943 + vertex 563.01 76.7156 29.7823 + endloop + endfacet + facet normal 0.148234 -0.490326 0.858841 + outer loop + vertex 556.001 68.1785 23.867 + vertex 561.816 69.775 23.7749 + vertex 555.926 70.0572 24.9526 + endloop + endfacet + facet normal 0.14958 -0.481661 0.863498 + outer loop + vertex 555.926 70.0572 24.9526 + vertex 561.816 69.775 23.7749 + vertex 561.766 71.6581 24.834 + endloop + endfacet + facet normal 0.146618 -0.49532 0.856248 + outer loop + vertex 550.206 66.6081 23.951 + vertex 556.001 68.1785 23.867 + vertex 550.078 68.4793 25.0554 + endloop + endfacet + facet normal 0.147406 -0.490413 0.858934 + outer loop + vertex 550.078 68.4793 25.0554 + vertex 556.001 68.1785 23.867 + vertex 555.926 70.0572 24.9526 + endloop + endfacet + facet normal 0.181589 -0.623519 0.760427 + outer loop + vertex 550.078 68.4793 25.0554 + vertex 555.926 70.0572 24.9526 + vertex 549.991 70.2114 26.4963 + endloop + endfacet + facet normal 0.182206 -0.62077 0.762526 + outer loop + vertex 549.991 70.2114 26.4963 + vertex 555.926 70.0572 24.9526 + vertex 555.92 71.801 26.3735 + endloop + endfacet + facet normal 0.185542 -0.62037 0.762047 + outer loop + vertex 555.926 70.0572 24.9526 + vertex 561.766 71.6581 24.834 + vertex 555.92 71.801 26.3735 + endloop + endfacet + facet normal 0.18593 -0.618636 0.763361 + outer loop + vertex 555.92 71.801 26.3735 + vertex 561.766 71.6581 24.834 + vertex 561.818 73.4085 26.2399 + endloop + endfacet + facet normal 0.084958 -0.258472 0.962276 + outer loop + vertex 555.87 63.6065 22.3918 + vertex 561.243 65.5041 22.4272 + vertex 555.925 66.07 23.0487 + endloop + endfacet + facet normal 0.0846921 -0.260419 0.961774 + outer loop + vertex 555.925 66.07 23.0487 + vertex 561.243 65.5041 22.4272 + vertex 561.744 67.6738 22.9706 + endloop + endfacet + facet normal 0.0792033 -0.273764 0.95853 + outer loop + vertex 549.613 62.3183 22.541 + vertex 555.87 63.6065 22.3918 + vertex 550.146 64.4979 23.1194 + endloop + endfacet + facet normal 0.082092 -0.258474 0.962524 + outer loop + vertex 550.146 64.4979 23.1194 + vertex 555.87 63.6065 22.3918 + vertex 555.925 66.07 23.0487 + endloop + endfacet + facet normal 0.111158 -0.367066 0.923529 + outer loop + vertex 550.146 64.4979 23.1194 + vertex 555.925 66.07 23.0487 + vertex 550.206 66.6081 23.951 + endloop + endfacet + facet normal 0.111775 -0.363045 0.925043 + outer loop + vertex 550.206 66.6081 23.951 + vertex 555.925 66.07 23.0487 + vertex 556.001 68.1785 23.867 + endloop + endfacet + facet normal 0.112483 -0.363038 0.92496 + outer loop + vertex 555.925 66.07 23.0487 + vertex 561.744 67.6738 22.9706 + vertex 556.001 68.1785 23.867 + endloop + endfacet + facet normal 0.113134 -0.358582 0.926618 + outer loop + vertex 556.001 68.1785 23.867 + vertex 561.744 67.6738 22.9706 + vertex 561.816 69.775 23.7749 + endloop + endfacet + facet normal 0.0793526 -0.296723 0.951661 + outer loop + vertex 553.812 43.0705 17.8191 + vertex 559.242 44.961 17.9558 + vertex 550.064 45.3591 18.8453 + endloop + endfacet + facet normal 0.0825039 -0.29262 0.952663 + outer loop + vertex 565.538 46.289 17.8184 + vertex 561.946 48.5867 18.8353 + vertex 559.242 44.961 17.9558 + endloop + endfacet + facet normal 0.0797841 -0.290784 0.953456 + outer loop + vertex 561.946 48.5867 18.8353 + vertex 550.064 45.3591 18.8453 + vertex 559.242 44.961 17.9558 + endloop + endfacet + facet normal 0.134575 -0.485855 0.863617 + outer loop + vertex 558.905 40.5598 15.9045 + vertex 564.711 42.1622 15.9013 + vertex 559.117 42.5684 17.0014 + endloop + endfacet + facet normal 0.134396 -0.48686 0.863079 + outer loop + vertex 559.117 42.5684 17.0014 + vertex 564.711 42.1622 15.9013 + vertex 564.925 44.1706 17.0008 + endloop + endfacet + facet normal 0.132077 -0.488462 0.862531 + outer loop + vertex 553.065 38.9735 15.9003 + vertex 558.905 40.5598 15.9045 + vertex 553.248 40.9681 17.002 + endloop + endfacet + facet normal 0.132542 -0.485822 0.86395 + outer loop + vertex 553.248 40.9681 17.002 + vertex 558.905 40.5598 15.9045 + vertex 559.117 42.5684 17.0014 + endloop + endfacet + facet normal 0.104957 -0.384633 0.917083 + outer loop + vertex 553.248 40.9681 17.002 + vertex 559.117 42.5684 17.0014 + vertex 553.812 43.0705 17.8191 + endloop + endfacet + facet normal 0.106734 -0.3732 0.921591 + outer loop + vertex 553.812 43.0705 17.8191 + vertex 559.117 42.5684 17.0014 + vertex 559.242 44.961 17.9558 + endloop + endfacet + facet normal 0.103043 -0.373178 0.92202 + outer loop + vertex 559.117 42.5684 17.0014 + vertex 564.925 44.1706 17.0008 + vertex 559.242 44.961 17.9558 + endloop + endfacet + facet normal 0.100925 -0.38354 0.917993 + outer loop + vertex 559.242 44.961 17.9558 + vertex 564.925 44.1706 17.0008 + vertex 565.538 46.289 17.8184 + endloop + endfacet + facet normal 0.209268 -0.762536 0.612165 + outer loop + vertex 558.974 37.647 12.9863 + vertex 564.793 39.2428 12.985 + vertex 558.878 38.8936 14.5719 + endloop + endfacet + facet normal 0.209588 -0.76126 0.613641 + outer loop + vertex 558.878 38.8936 14.5719 + vertex 564.793 39.2428 12.985 + vertex 564.689 40.4921 14.5703 + endloop + endfacet + facet normal 0.207718 -0.760012 0.615821 + outer loop + vertex 553.148 36.0574 12.9897 + vertex 558.974 37.647 12.9863 + vertex 553.052 37.3113 14.5696 + endloop + endfacet + facet normal 0.206967 -0.762989 0.612383 + outer loop + vertex 553.052 37.3113 14.5696 + vertex 558.974 37.647 12.9863 + vertex 558.878 38.8936 14.5719 + endloop + endfacet + facet normal 0.167258 -0.616992 0.76899 + outer loop + vertex 553.052 37.3113 14.5696 + vertex 558.878 38.8936 14.5719 + vertex 553.065 38.9735 15.9003 + endloop + endfacet + facet normal 0.167178 -0.617417 0.768666 + outer loop + vertex 553.065 38.9735 15.9003 + vertex 558.878 38.8936 14.5719 + vertex 558.905 40.5598 15.9045 + endloop + endfacet + facet normal 0.169984 -0.617144 0.76827 + outer loop + vertex 558.878 38.8936 14.5719 + vertex 564.689 40.4921 14.5703 + vertex 558.905 40.5598 15.9045 + endloop + endfacet + facet normal 0.170296 -0.615477 0.769537 + outer loop + vertex 558.905 40.5598 15.9045 + vertex 564.689 40.4921 14.5703 + vertex 564.711 42.1622 15.9013 + endloop + endfacet + facet normal 0.263033 -0.958059 0.113739 + outer loop + vertex 559.175 36.6735 9.28296 + vertex 564.993 38.2705 9.28105 + vertex 559.096 36.8781 11.1897 + endloop + endfacet + facet normal 0.261369 -0.959205 0.107762 + outer loop + vertex 559.096 36.8781 11.1897 + vertex 564.993 38.2705 9.28105 + vertex 564.919 38.4647 11.1899 + endloop + endfacet + facet normal 0.257886 -0.960259 0.106754 + outer loop + vertex 553.345 35.1079 9.2843 + vertex 559.175 36.6735 9.28296 + vertex 553.266 35.2986 11.1906 + endloop + endfacet + facet normal 0.259821 -0.95894 0.1137 + outer loop + vertex 553.266 35.2986 11.1906 + vertex 559.175 36.6735 9.28296 + vertex 559.096 36.8781 11.1897 + endloop + endfacet + facet normal 0.240788 -0.888535 0.390547 + outer loop + vertex 553.266 35.2986 11.1906 + vertex 559.096 36.8781 11.1897 + vertex 553.148 36.0574 12.9897 + endloop + endfacet + facet normal 0.241958 -0.885989 0.395575 + outer loop + vertex 553.148 36.0574 12.9897 + vertex 559.096 36.8781 11.1897 + vertex 558.974 37.647 12.9863 + endloop + endfacet + facet normal 0.241444 -0.88612 0.395596 + outer loop + vertex 559.096 36.8781 11.1897 + vertex 564.919 38.4647 11.1899 + vertex 558.974 37.647 12.9863 + endloop + endfacet + facet normal 0.242482 -0.88382 0.40008 + outer loop + vertex 558.974 37.647 12.9863 + vertex 564.919 38.4647 11.1899 + vertex 564.793 39.2428 12.985 + endloop + endfacet + facet normal 0.224612 -0.815508 -0.533381 + outer loop + vertex 558.87 38.1405 5.72481 + vertex 564.683 39.7419 5.7241 + vertex 559.136 37.109 7.41407 + endloop + endfacet + facet normal 0.223647 -0.814613 -0.535152 + outer loop + vertex 559.136 37.109 7.41407 + vertex 564.683 39.7419 5.7241 + vertex 564.948 38.7048 7.41354 + endloop + endfacet + facet normal 0.220325 -0.81594 -0.534509 + outer loop + vertex 553.067 36.5714 5.72808 + vertex 558.87 38.1405 5.72481 + vertex 553.32 35.5343 7.41544 + endloop + endfacet + facet normal 0.220924 -0.8165 -0.533405 + outer loop + vertex 553.32 35.5343 7.41544 + vertex 558.87 38.1405 5.72481 + vertex 559.136 37.109 7.41407 + endloop + endfacet + facet normal 0.254966 -0.94197 -0.21837 + outer loop + vertex 553.32 35.5343 7.41544 + vertex 559.136 37.109 7.41407 + vertex 553.345 35.1079 9.2843 + endloop + endfacet + facet normal 0.252672 -0.941129 -0.224571 + outer loop + vertex 553.345 35.1079 9.2843 + vertex 559.136 37.109 7.41407 + vertex 559.175 36.6735 9.28296 + endloop + endfacet + facet normal 0.258033 -0.939725 -0.224356 + outer loop + vertex 559.136 37.109 7.41407 + vertex 564.948 38.7048 7.41354 + vertex 559.175 36.6735 9.28296 + endloop + endfacet + facet normal 0.257874 -0.939667 -0.224783 + outer loop + vertex 559.175 36.6735 9.28296 + vertex 564.948 38.7048 7.41354 + vertex 564.993 38.2705 9.28105 + endloop + endfacet + facet normal 0.110538 -0.439238 -0.891544 + outer loop + vertex 557.584 41.7778 3.17967 + vertex 563.091 42.8811 3.31893 + vertex 558.286 39.6561 4.31199 + endloop + endfacet + facet normal 0.126434 -0.459156 -0.879312 + outer loop + vertex 558.286 39.6561 4.31199 + vertex 563.091 42.8811 3.31893 + vertex 564.116 41.2673 4.30898 + endloop + endfacet + facet normal 0.135561 -0.457902 -0.878606 + outer loop + vertex 551.412 39.6734 3.32413 + vertex 557.584 41.7778 3.17967 + vertex 552.488 38.0868 4.31705 + endloop + endfacet + facet normal 0.117515 -0.437033 -0.891736 + outer loop + vertex 552.488 38.0868 4.31705 + vertex 557.584 41.7778 3.17967 + vertex 558.286 39.6561 4.31199 + endloop + endfacet + facet normal 0.17136 -0.635513 -0.752834 + outer loop + vertex 552.488 38.0868 4.31705 + vertex 558.286 39.6561 4.31199 + vertex 553.067 36.5714 5.72808 + endloop + endfacet + facet normal 0.171441 -0.635606 -0.752737 + outer loop + vertex 553.067 36.5714 5.72808 + vertex 558.286 39.6561 4.31199 + vertex 558.87 38.1405 5.72481 + endloop + endfacet + facet normal 0.174936 -0.634432 -0.752923 + outer loop + vertex 558.286 39.6561 4.31199 + vertex 564.116 41.2673 4.30898 + vertex 558.87 38.1405 5.72481 + endloop + endfacet + facet normal 0.174589 -0.634037 -0.753337 + outer loop + vertex 558.87 38.1405 5.72481 + vertex 564.116 41.2673 4.30898 + vertex 564.683 39.7419 5.7241 + endloop + endfacet + facet normal 0.083765 -0.298108 -0.95085 + outer loop + vertex 563.091 42.8811 3.31893 + vertex 557.584 41.7778 3.17967 + vertex 566.028 47.0627 2.26664 + endloop + endfacet + facet normal 0.079163 -0.29749 -0.951437 + outer loop + vertex 551.412 39.6734 3.32413 + vertex 554.146 43.7575 2.27461 + vertex 557.584 41.7778 3.17967 + endloop + endfacet + facet normal 0.0812223 -0.294289 -0.952259 + outer loop + vertex 554.146 43.7575 2.27461 + vertex 566.028 47.0627 2.26664 + vertex 557.584 41.7778 3.17967 + endloop + endfacet + facet normal 0.0569064 -0.205691 -0.976961 + outer loop + vertex 552.154 47.775 1.31275 + vertex 564.271 51.1735 1.30299 + vertex 554.146 43.7575 2.27461 + endloop + endfacet + facet normal 0.0563597 -0.204969 -0.977145 + outer loop + vertex 554.146 43.7575 2.27461 + vertex 564.271 51.1735 1.30299 + vertex 566.028 47.0627 2.26664 + endloop + endfacet + facet normal 0.244901 -0.8103 0.532388 + outer loop + vertex 563.01 76.7156 29.7823 + vertex 568.623 78.5104 29.9318 + vertex 559.509 77.5717 32.6957 + endloop + endfacet + facet normal 0.250675 -0.811506 0.527844 + outer loop + vertex 575.008 80.0621 29.2854 + vertex 571.923 80.9765 32.1562 + vertex 568.623 78.5104 29.9318 + endloop + endfacet + facet normal 0.245187 -0.809391 0.533639 + outer loop + vertex 571.923 80.9765 32.1562 + vertex 559.509 77.5717 32.6957 + vertex 568.623 78.5104 29.9318 + endloop + endfacet + facet normal 0.220828 -0.714487 0.663886 + outer loop + vertex 567.678 75.0356 26.078 + vertex 573.508 76.6759 25.9041 + vertex 568.093 76.7669 27.8031 + endloop + endfacet + facet normal 0.224019 -0.705336 0.672545 + outer loop + vertex 568.093 76.7669 27.8031 + vertex 573.508 76.6759 25.9041 + vertex 573.971 78.4192 27.5782 + endloop + endfacet + facet normal 0.217591 -0.717909 0.661257 + outer loop + vertex 561.818 73.4085 26.2399 + vertex 567.678 75.0356 26.078 + vertex 562.167 75.1302 27.9943 + endloop + endfacet + facet normal 0.218766 -0.714576 0.664472 + outer loop + vertex 562.167 75.1302 27.9943 + vertex 567.678 75.0356 26.078 + vertex 568.093 76.7669 27.8031 + endloop + endfacet + facet normal 0.234033 -0.779621 0.580878 + outer loop + vertex 562.167 75.1302 27.9943 + vertex 568.093 76.7669 27.8031 + vertex 563.01 76.7156 29.7823 + endloop + endfacet + facet normal 0.233903 -0.779914 0.580537 + outer loop + vertex 563.01 76.7156 29.7823 + vertex 568.093 76.7669 27.8031 + vertex 568.623 78.5104 29.9318 + endloop + endfacet + facet normal 0.241223 -0.77937 0.578269 + outer loop + vertex 568.093 76.7669 27.8031 + vertex 573.971 78.4192 27.5782 + vertex 568.623 78.5104 29.9318 + endloop + endfacet + facet normal 0.24659 -0.768785 0.590053 + outer loop + vertex 568.623 78.5104 29.9318 + vertex 573.971 78.4192 27.5782 + vertex 575.008 80.0621 29.2854 + endloop + endfacet + facet normal 0.149771 -0.476653 0.866239 + outer loop + vertex 567.649 71.4031 23.6713 + vertex 573.487 73.0513 23.5689 + vertex 567.601 73.2796 24.7122 + endloop + endfacet + facet normal 0.15132 -0.465539 0.871995 + outer loop + vertex 567.601 73.2796 24.7122 + vertex 573.487 73.0513 23.5689 + vertex 573.424 74.9226 24.579 + endloop + endfacet + facet normal 0.149761 -0.481644 0.863476 + outer loop + vertex 561.816 69.775 23.7749 + vertex 567.649 71.4031 23.6713 + vertex 561.766 71.6581 24.834 + endloop + endfacet + facet normal 0.150508 -0.476584 0.866149 + outer loop + vertex 561.766 71.6581 24.834 + vertex 567.649 71.4031 23.6713 + vertex 567.601 73.2796 24.7122 + endloop + endfacet + facet normal 0.18778 -0.618449 0.76306 + outer loop + vertex 561.766 71.6581 24.834 + vertex 567.601 73.2796 24.7122 + vertex 561.818 73.4085 26.2399 + endloop + endfacet + facet normal 0.190085 -0.607934 0.770898 + outer loop + vertex 561.818 73.4085 26.2399 + vertex 567.601 73.2796 24.7122 + vertex 567.678 75.0356 26.078 + endloop + endfacet + facet normal 0.189213 -0.608014 0.77105 + outer loop + vertex 567.601 73.2796 24.7122 + vertex 573.424 74.9226 24.579 + vertex 567.678 75.0356 26.078 + endloop + endfacet + facet normal 0.191381 -0.597656 0.778576 + outer loop + vertex 567.678 75.0356 26.078 + vertex 573.424 74.9226 24.579 + vertex 573.508 76.6759 25.9041 + endloop + endfacet + facet normal 0.0829264 -0.243431 0.966367 + outer loop + vertex 567.573 66.8424 22.2783 + vertex 572.985 68.7812 22.3023 + vertex 567.588 69.3004 22.8962 + endloop + endfacet + facet normal 0.0824893 -0.246986 0.965502 + outer loop + vertex 567.588 69.3004 22.8962 + vertex 572.985 68.7812 22.3023 + vertex 573.452 70.9517 22.8177 + endloop + endfacet + facet normal 0.0773962 -0.258986 0.962775 + outer loop + vertex 561.243 65.5041 22.4272 + vertex 567.573 66.8424 22.2783 + vertex 561.744 67.6738 22.9706 + endloop + endfacet + facet normal 0.0800628 -0.243472 0.966598 + outer loop + vertex 561.744 67.6738 22.9706 + vertex 567.573 66.8424 22.2783 + vertex 567.588 69.3004 22.8962 + endloop + endfacet + facet normal 0.1116 -0.358597 0.926797 + outer loop + vertex 561.744 67.6738 22.9706 + vertex 567.588 69.3004 22.8962 + vertex 561.816 69.775 23.7749 + endloop + endfacet + facet normal 0.113255 -0.346555 0.931168 + outer loop + vertex 561.816 69.775 23.7749 + vertex 567.588 69.3004 22.8962 + vertex 567.649 71.4031 23.6713 + endloop + endfacet + facet normal 0.110085 -0.346596 0.931532 + outer loop + vertex 567.588 69.3004 22.8962 + vertex 573.452 70.9517 22.8177 + vertex 567.649 71.4031 23.6713 + endloop + endfacet + facet normal 0.111398 -0.33645 0.935089 + outer loop + vertex 567.649 71.4031 23.6713 + vertex 573.452 70.9517 22.8177 + vertex 573.487 73.0513 23.5689 + endloop + endfacet + facet normal 0.0811969 -0.294462 0.952208 + outer loop + vertex 565.538 46.289 17.8184 + vertex 570.892 48.1987 17.9525 + vertex 561.946 48.5867 18.8353 + endloop + endfacet + facet normal 0.0843482 -0.2927 0.952477 + outer loop + vertex 577.094 49.545 17.817 + vertex 573.705 51.871 18.8319 + vertex 570.892 48.1987 17.9525 + endloop + endfacet + facet normal 0.0814716 -0.290703 0.953338 + outer loop + vertex 573.705 51.871 18.8319 + vertex 561.946 48.5867 18.8353 + vertex 570.892 48.1987 17.9525 + endloop + endfacet + facet normal 0.137346 -0.484962 0.863683 + outer loop + vertex 570.476 43.7642 15.9007 + vertex 576.206 45.3789 15.8961 + vertex 570.69 45.7796 16.9983 + endloop + endfacet + facet normal 0.137191 -0.485822 0.863224 + outer loop + vertex 570.69 45.7796 16.9983 + vertex 576.206 45.3789 15.8961 + vertex 576.415 47.3955 16.9977 + endloop + endfacet + facet normal 0.135388 -0.486877 0.862914 + outer loop + vertex 564.711 42.1622 15.9013 + vertex 570.476 43.7642 15.9007 + vertex 564.925 44.1706 17.0008 + endloop + endfacet + facet normal 0.135736 -0.484937 0.863951 + outer loop + vertex 564.925 44.1706 17.0008 + vertex 570.476 43.7642 15.9007 + vertex 570.69 45.7796 16.9983 + endloop + endfacet + facet normal 0.107865 -0.385006 0.916589 + outer loop + vertex 564.925 44.1706 17.0008 + vertex 570.69 45.7796 16.9983 + vertex 565.538 46.289 17.8184 + endloop + endfacet + facet normal 0.109861 -0.37265 0.921446 + outer loop + vertex 565.538 46.289 17.8184 + vertex 570.69 45.7796 16.9983 + vertex 570.892 48.1987 17.9525 + endloop + endfacet + facet normal 0.105215 -0.3725 0.922049 + outer loop + vertex 570.69 45.7796 16.9983 + vertex 576.415 47.3955 16.9977 + vertex 570.892 48.1987 17.9525 + endloop + endfacet + facet normal 0.103092 -0.382503 0.918185 + outer loop + vertex 570.892 48.1987 17.9525 + vertex 576.415 47.3955 16.9977 + vertex 577.094 49.545 17.817 + endloop + endfacet + facet normal 0.213646 -0.756874 0.617655 + outer loop + vertex 570.59 40.8444 12.9859 + vertex 576.355 42.4686 12.9818 + vertex 570.474 42.1016 14.5666 + endloop + endfacet + facet normal 0.212925 -0.759804 0.614297 + outer loop + vertex 570.474 42.1016 14.5666 + vertex 576.355 42.4686 12.9818 + vertex 576.223 43.7125 14.5661 + endloop + endfacet + facet normal 0.210206 -0.761136 0.613584 + outer loop + vertex 564.793 39.2428 12.985 + vertex 570.59 40.8444 12.9859 + vertex 564.689 40.4921 14.5703 + endloop + endfacet + facet normal 0.211137 -0.757392 0.617883 + outer loop + vertex 564.689 40.4921 14.5703 + vertex 570.59 40.8444 12.9859 + vertex 570.474 42.1016 14.5666 + endloop + endfacet + facet normal 0.171709 -0.615335 0.769336 + outer loop + vertex 564.689 40.4921 14.5703 + vertex 570.474 42.1016 14.5666 + vertex 564.711 42.1622 15.9013 + endloop + endfacet + facet normal 0.171454 -0.616702 0.768298 + outer loop + vertex 564.711 42.1622 15.9013 + vertex 570.474 42.1016 14.5666 + vertex 570.476 43.7642 15.9007 + endloop + endfacet + facet normal 0.172801 -0.616556 0.768114 + outer loop + vertex 570.474 42.1016 14.5666 + vertex 576.223 43.7125 14.5661 + vertex 570.476 43.7642 15.9007 + endloop + endfacet + facet normal 0.173417 -0.613228 0.770635 + outer loop + vertex 570.476 43.7642 15.9007 + vertex 576.223 43.7125 14.5661 + vertex 576.206 45.3789 15.8961 + endloop + endfacet + facet normal 0.26971 -0.956429 0.111808 + outer loop + vertex 570.789 39.8772 9.27932 + vertex 576.558 41.5038 9.27756 + vertex 570.717 40.0797 11.1866 + endloop + endfacet + facet normal 0.268506 -0.95726 0.107504 + outer loop + vertex 570.717 40.0797 11.1866 + vertex 576.558 41.5038 9.27756 + vertex 576.485 41.6975 11.1858 + endloop + endfacet + facet normal 0.265599 -0.958037 0.107807 + outer loop + vertex 564.993 38.2705 9.28105 + vertex 570.789 39.8772 9.27932 + vertex 564.919 38.4647 11.1899 + endloop + endfacet + facet normal 0.266709 -0.957273 0.111784 + outer loop + vertex 564.919 38.4647 11.1899 + vertex 570.789 39.8772 9.27932 + vertex 570.717 40.0797 11.1866 + endloop + endfacet + facet normal 0.24615 -0.882875 0.399927 + outer loop + vertex 564.919 38.4647 11.1899 + vertex 570.717 40.0797 11.1866 + vertex 564.793 39.2428 12.985 + endloop + endfacet + facet normal 0.244741 -0.886001 0.393831 + outer loop + vertex 564.793 39.2428 12.985 + vertex 570.717 40.0797 11.1866 + vertex 570.59 40.8444 12.9859 + endloop + endfacet + facet normal 0.248298 -0.885075 0.393688 + outer loop + vertex 570.717 40.0797 11.1866 + vertex 576.485 41.6975 11.1858 + vertex 570.59 40.8444 12.9859 + endloop + endfacet + facet normal 0.249104 -0.883289 0.397174 + outer loop + vertex 570.59 40.8444 12.9859 + vertex 576.485 41.6975 11.1858 + vertex 576.355 42.4686 12.9818 + endloop + endfacet + facet normal 0.231599 -0.812011 -0.535724 + outer loop + vertex 570.51 41.3621 5.7149 + vertex 576.336 43.025 5.71297 + vertex 570.751 40.3136 7.40815 + endloop + endfacet + facet normal 0.228474 -0.809125 -0.541402 + outer loop + vertex 570.751 40.3136 7.40815 + vertex 576.336 43.025 5.71297 + vertex 576.538 41.9499 7.40473 + endloop + endfacet + facet normal 0.225493 -0.814115 -0.535136 + outer loop + vertex 564.683 39.7419 5.7241 + vertex 570.51 41.3621 5.7149 + vertex 564.948 38.7048 7.41354 + endloop + endfacet + facet normal 0.22509 -0.813742 -0.535871 + outer loop + vertex 564.948 38.7048 7.41354 + vertex 570.51 41.3621 5.7149 + vertex 570.751 40.3136 7.40815 + endloop + endfacet + facet normal 0.260122 -0.939067 -0.224698 + outer loop + vertex 564.948 38.7048 7.41354 + vertex 570.751 40.3136 7.40815 + vertex 564.993 38.2705 9.28105 + endloop + endfacet + facet normal 0.260255 -0.939115 -0.224343 + outer loop + vertex 564.993 38.2705 9.28105 + vertex 570.751 40.3136 7.40815 + vertex 570.789 39.8772 9.27932 + endloop + endfacet + facet normal 0.265053 -0.937821 -0.224139 + outer loop + vertex 570.751 40.3136 7.40815 + vertex 576.538 41.9499 7.40473 + vertex 570.789 39.8772 9.27932 + endloop + endfacet + facet normal 0.264282 -0.937544 -0.226199 + outer loop + vertex 570.789 39.8772 9.27932 + vertex 576.538 41.9499 7.40473 + vertex 576.558 41.5038 9.27756 + endloop + endfacet + facet normal 0.114451 -0.438321 -0.891502 + outer loop + vertex 569.354 45.0611 3.1682 + vertex 574.904 46.2186 3.31158 + vertex 569.976 42.9134 4.30402 + endloop + endfacet + facet normal 0.130159 -0.458085 -0.879328 + outer loop + vertex 569.976 42.9134 4.30402 + vertex 574.904 46.2186 3.31158 + vertex 575.857 44.5906 4.30074 + endloop + endfacet + facet normal 0.136661 -0.453517 -0.880708 + outer loop + vertex 563.091 42.8811 3.31893 + vertex 569.354 45.0611 3.1682 + vertex 564.116 41.2673 4.30898 + endloop + endfacet + facet normal 0.121778 -0.436229 -0.891557 + outer loop + vertex 564.116 41.2673 4.30898 + vertex 569.354 45.0611 3.1682 + vertex 569.976 42.9134 4.30402 + endloop + endfacet + facet normal 0.177213 -0.63317 -0.753453 + outer loop + vertex 564.116 41.2673 4.30898 + vertex 569.976 42.9134 4.30402 + vertex 564.683 39.7419 5.7241 + endloop + endfacet + facet normal 0.173734 -0.629207 -0.757572 + outer loop + vertex 564.683 39.7419 5.7241 + vertex 569.976 42.9134 4.30402 + vertex 570.51 41.3621 5.7149 + endloop + endfacet + facet normal 0.178593 -0.627667 -0.757719 + outer loop + vertex 569.976 42.9134 4.30402 + vertex 575.857 44.5906 4.30074 + vertex 570.51 41.3621 5.7149 + endloop + endfacet + facet normal 0.179059 -0.628198 -0.757169 + outer loop + vertex 570.51 41.3621 5.7149 + vertex 575.857 44.5906 4.30074 + vertex 576.336 43.025 5.71297 + endloop + endfacet + facet normal 0.0872185 -0.300532 -0.949776 + outer loop + vertex 574.904 46.2186 3.31158 + vertex 569.354 45.0611 3.1682 + vertex 577.794 50.3552 2.26801 + endloop + endfacet + facet normal 0.0800348 -0.295754 -0.951905 + outer loop + vertex 563.091 42.8811 3.31893 + vertex 566.028 47.0627 2.26664 + vertex 569.354 45.0611 3.1682 + endloop + endfacet + facet normal 0.0820383 -0.292764 -0.952659 + outer loop + vertex 566.028 47.0627 2.26664 + vertex 577.794 50.3552 2.26801 + vertex 569.354 45.0611 3.1682 + endloop + endfacet + facet normal 0.056922 -0.204732 -0.977162 + outer loop + vertex 564.271 51.1735 1.30299 + vertex 576.113 54.4642 1.30337 + vertex 566.028 47.0627 2.26664 + endloop + endfacet + facet normal 0.0576895 -0.205744 -0.976904 + outer loop + vertex 566.028 47.0627 2.26664 + vertex 576.113 54.4642 1.30337 + vertex 577.794 50.3552 2.26801 + endloop + endfacet + facet normal 0.25889 -0.804566 0.534462 + outer loop + vertex 575.008 80.0621 29.2854 + vertex 580.694 81.9495 29.3722 + vertex 571.923 80.9765 32.1562 + endloop + endfacet + facet normal 0.261403 -0.801405 0.537976 + outer loop + vertex 587.069 83.5832 28.7083 + vertex 584.323 84.6077 31.569 + vertex 580.694 81.9495 29.3722 + endloop + endfacet + facet normal 0.260068 -0.800827 0.539481 + outer loop + vertex 584.323 84.6077 31.569 + vertex 571.923 80.9765 32.1562 + vertex 580.694 81.9495 29.3722 + endloop + endfacet + facet normal 0.224319 -0.693818 0.684323 + outer loop + vertex 579.311 78.3283 25.7152 + vertex 585.067 79.9902 25.5136 + vertex 579.858 80.0982 27.3306 + endloop + endfacet + facet normal 0.228553 -0.681002 0.695701 + outer loop + vertex 579.858 80.0982 27.3306 + vertex 585.067 79.9902 25.5136 + vertex 585.739 81.8117 27.0759 + endloop + endfacet + facet normal 0.22274 -0.70537 0.672934 + outer loop + vertex 573.508 76.6759 25.9041 + vertex 579.311 78.3283 25.7152 + vertex 573.971 78.4192 27.5782 + endloop + endfacet + facet normal 0.226639 -0.693827 0.683548 + outer loop + vertex 573.971 78.4192 27.5782 + vertex 579.311 78.3283 25.7152 + vertex 579.858 80.0982 27.3306 + endloop + endfacet + facet normal 0.244082 -0.768572 0.591372 + outer loop + vertex 573.971 78.4192 27.5782 + vertex 579.858 80.0982 27.3306 + vertex 575.008 80.0621 29.2854 + endloop + endfacet + facet normal 0.245194 -0.766049 0.594179 + outer loop + vertex 575.008 80.0621 29.2854 + vertex 579.858 80.0982 27.3306 + vertex 580.694 81.9495 29.3722 + endloop + endfacet + facet normal 0.248867 -0.766038 0.592664 + outer loop + vertex 579.858 80.0982 27.3306 + vertex 585.739 81.8117 27.0759 + vertex 580.694 81.9495 29.3722 + endloop + endfacet + facet normal 0.255975 -0.751997 0.607435 + outer loop + vertex 580.694 81.9495 29.3722 + vertex 585.739 81.8117 27.0759 + vertex 587.069 83.5832 28.7083 + endloop + endfacet + facet normal 0.145561 -0.449534 0.881324 + outer loop + vertex 579.309 74.7106 23.4669 + vertex 585.053 76.3605 23.3598 + vertex 579.216 76.5769 24.4343 + endloop + endfacet + facet normal 0.147756 -0.431957 0.889709 + outer loop + vertex 579.216 76.5769 24.4343 + vertex 585.053 76.3605 23.3598 + vertex 584.938 78.2258 24.2845 + endloop + endfacet + facet normal 0.148047 -0.465861 0.872385 + outer loop + vertex 573.487 73.0513 23.5689 + vertex 579.309 74.7106 23.4669 + vertex 573.424 74.9226 24.579 + endloop + endfacet + facet normal 0.150242 -0.449027 0.880796 + outer loop + vertex 573.424 74.9226 24.579 + vertex 579.309 74.7106 23.4669 + vertex 579.216 76.5769 24.4343 + endloop + endfacet + facet normal 0.190172 -0.597761 0.778792 + outer loop + vertex 573.424 74.9226 24.579 + vertex 579.216 76.5769 24.4343 + vertex 573.508 76.6759 25.9041 + endloop + endfacet + facet normal 0.192495 -0.586112 0.787032 + outer loop + vertex 573.508 76.6759 25.9041 + vertex 579.216 76.5769 24.4343 + vertex 579.311 78.3283 25.7152 + endloop + endfacet + facet normal 0.189572 -0.586345 0.787567 + outer loop + vertex 579.216 76.5769 24.4343 + vertex 584.938 78.2258 24.2845 + vertex 579.311 78.3283 25.7152 + endloop + endfacet + facet normal 0.192651 -0.570295 0.79853 + outer loop + vertex 579.311 78.3283 25.7152 + vertex 584.938 78.2258 24.2845 + vertex 585.067 79.9902 25.5136 + endloop + endfacet + facet normal 0.0790886 -0.226969 0.970685 + outer loop + vertex 579.25 70.1186 22.1595 + vertex 584.562 72.049 22.178 + vertex 579.305 72.6134 22.7383 + endloop + endfacet + facet normal 0.0787456 -0.229582 0.970099 + outer loop + vertex 579.305 72.6134 22.7383 + vertex 584.562 72.049 22.178 + vertex 585.06 74.255 22.6597 + endloop + endfacet + facet normal 0.074447 -0.2455 0.966534 + outer loop + vertex 572.985 68.7812 22.3023 + vertex 579.25 70.1186 22.1595 + vertex 573.452 70.9517 22.8177 + endloop + endfacet + facet normal 0.0775956 -0.226964 0.970807 + outer loop + vertex 573.452 70.9517 22.8177 + vertex 579.25 70.1186 22.1595 + vertex 579.305 72.6134 22.7383 + endloop + endfacet + facet normal 0.108218 -0.336521 0.935437 + outer loop + vertex 573.452 70.9517 22.8177 + vertex 579.305 72.6134 22.7383 + vertex 573.487 73.0513 23.5689 + endloop + endfacet + facet normal 0.109468 -0.326416 0.938866 + outer loop + vertex 573.487 73.0513 23.5689 + vertex 579.305 72.6134 22.7383 + vertex 579.309 74.7106 23.4669 + endloop + endfacet + facet normal 0.10598 -0.326534 0.939225 + outer loop + vertex 579.305 72.6134 22.7383 + vertex 585.06 74.255 22.6597 + vertex 579.309 74.7106 23.4669 + endloop + endfacet + facet normal 0.107621 -0.313407 0.943501 + outer loop + vertex 579.309 74.7106 23.4669 + vertex 585.06 74.255 22.6597 + vertex 585.053 76.3605 23.3598 + endloop + endfacet + facet normal 0.0822851 -0.295419 0.951818 + outer loop + vertex 577.094 49.545 17.817 + vertex 582.456 51.4914 17.9575 + vertex 573.705 51.871 18.8319 + endloop + endfacet + facet normal 0.0837036 -0.290886 0.953089 + outer loop + vertex 588.607 52.8581 17.8345 + vertex 585.187 55.1253 18.8268 + vertex 582.456 51.4914 17.9575 + endloop + endfacet + facet normal 0.0826697 -0.290182 0.953394 + outer loop + vertex 585.187 55.1253 18.8268 + vertex 573.705 51.871 18.8319 + vertex 582.456 51.4914 17.9575 + endloop + endfacet + facet normal 0.137522 -0.481978 0.865323 + outer loop + vertex 581.902 46.9923 15.904 + vertex 587.566 48.6263 15.914 + vertex 582.143 49.0329 17.0024 + endloop + endfacet + facet normal 0.137759 -0.480666 0.866015 + outer loop + vertex 582.143 49.0329 17.0024 + vertex 587.566 48.6263 15.914 + vertex 587.853 50.689 17.0132 + endloop + endfacet + facet normal 0.13639 -0.485811 0.863357 + outer loop + vertex 576.206 45.3789 15.8961 + vertex 581.902 46.9923 15.904 + vertex 576.415 47.3955 16.9977 + endloop + endfacet + facet normal 0.13708 -0.481967 0.8654 + outer loop + vertex 576.415 47.3955 16.9977 + vertex 581.902 46.9923 15.904 + vertex 582.143 49.0329 17.0024 + endloop + endfacet + facet normal 0.108998 -0.383887 0.916924 + outer loop + vertex 576.415 47.3955 16.9977 + vertex 582.143 49.0329 17.0024 + vertex 577.094 49.545 17.817 + endloop + endfacet + facet normal 0.11093 -0.372149 0.92152 + outer loop + vertex 577.094 49.545 17.817 + vertex 582.143 49.0329 17.0024 + vertex 582.456 51.4914 17.9575 + endloop + endfacet + facet normal 0.106083 -0.371807 0.922229 + outer loop + vertex 582.143 49.0329 17.0024 + vertex 587.853 50.689 17.0132 + vertex 582.456 51.4914 17.9575 + endloop + endfacet + facet normal 0.103566 -0.38345 0.917737 + outer loop + vertex 582.456 51.4914 17.9575 + vertex 587.853 50.689 17.0132 + vertex 588.607 52.8581 17.8345 + endloop + endfacet + facet normal 0.213828 -0.759279 0.614632 + outer loop + vertex 582.087 44.0918 12.9838 + vertex 587.756 45.6994 12.9975 + vertex 581.938 45.3324 14.5683 + endloop + endfacet + facet normal 0.21531 -0.753212 0.621541 + outer loop + vertex 581.938 45.3324 14.5683 + vertex 587.756 45.6994 12.9975 + vertex 587.589 46.9543 14.5762 + endloop + endfacet + facet normal 0.214852 -0.759393 0.614135 + outer loop + vertex 576.355 42.4686 12.9818 + vertex 582.087 44.0918 12.9838 + vertex 576.223 43.7125 14.5661 + endloop + endfacet + facet normal 0.214939 -0.759035 0.614546 + outer loop + vertex 576.223 43.7125 14.5661 + vertex 582.087 44.0918 12.9838 + vertex 581.938 45.3324 14.5683 + endloop + endfacet + facet normal 0.173542 -0.613213 0.770619 + outer loop + vertex 576.223 43.7125 14.5661 + vertex 581.938 45.3324 14.5683 + vertex 576.206 45.3789 15.8961 + endloop + endfacet + facet normal 0.173173 -0.615227 0.769095 + outer loop + vertex 576.206 45.3789 15.8961 + vertex 581.938 45.3324 14.5683 + vertex 581.902 46.9923 15.904 + endloop + endfacet + facet normal 0.175423 -0.614948 0.768808 + outer loop + vertex 581.938 45.3324 14.5683 + vertex 587.589 46.9543 14.5762 + vertex 581.902 46.9923 15.904 + endloop + endfacet + facet normal 0.175667 -0.613617 0.769815 + outer loop + vertex 581.902 46.9923 15.904 + vertex 587.589 46.9543 14.5762 + vertex 587.566 48.6263 15.914 + endloop + endfacet + facet normal 0.272562 -0.956654 0.102581 + outer loop + vertex 582.301 43.138 9.27895 + vertex 587.986 44.7584 9.28778 + vertex 582.223 43.3203 11.1882 + endloop + endfacet + facet normal 0.27188 -0.957103 0.100174 + outer loop + vertex 582.223 43.3203 11.1882 + vertex 587.986 44.7584 9.28778 + vertex 587.902 44.9345 11.1978 + endloop + endfacet + facet normal 0.272067 -0.95625 0.107539 + outer loop + vertex 576.558 41.5038 9.27756 + vertex 582.301 43.138 9.27895 + vertex 576.485 41.6975 11.1858 + endloop + endfacet + facet normal 0.270667 -0.957195 0.102555 + outer loop + vertex 576.485 41.6975 11.1858 + vertex 582.301 43.138 9.27895 + vertex 582.223 43.3203 11.1882 + endloop + endfacet + facet normal 0.249606 -0.883157 0.397153 + outer loop + vertex 576.485 41.6975 11.1858 + vertex 582.223 43.3203 11.1882 + vertex 576.355 42.4686 12.9818 + endloop + endfacet + facet normal 0.249832 -0.882652 0.398132 + outer loop + vertex 576.355 42.4686 12.9818 + vertex 582.223 43.3203 11.1882 + vertex 582.087 44.0918 12.9838 + endloop + endfacet + facet normal 0.250187 -0.882558 0.398118 + outer loop + vertex 582.223 43.3203 11.1882 + vertex 587.902 44.9345 11.1978 + vertex 582.087 44.0918 12.9838 + endloop + endfacet + facet normal 0.249651 -0.883746 0.395812 + outer loop + vertex 582.087 44.0918 12.9838 + vertex 587.902 44.9345 11.1978 + vertex 587.756 45.6994 12.9975 + endloop + endfacet + facet normal 0.231284 -0.807648 -0.542414 + outer loop + vertex 582.155 44.6891 5.70856 + vertex 587.908 46.3329 5.71425 + vertex 582.308 43.5947 7.40353 + endloop + endfacet + facet normal 0.230374 -0.806802 -0.544058 + outer loop + vertex 582.308 43.5947 7.40353 + vertex 587.908 46.3329 5.71425 + vertex 588.024 45.2223 7.41012 + endloop + endfacet + facet normal 0.230833 -0.808523 -0.541301 + outer loop + vertex 576.336 43.025 5.71297 + vertex 582.155 44.6891 5.70856 + vertex 576.538 41.9499 7.40473 + endloop + endfacet + facet normal 0.230178 -0.807915 -0.542486 + outer loop + vertex 576.538 41.9499 7.40473 + vertex 582.155 44.6891 5.70856 + vertex 582.308 43.5947 7.40353 + endloop + endfacet + facet normal 0.266985 -0.936813 -0.226054 + outer loop + vertex 576.538 41.9499 7.40473 + vertex 582.308 43.5947 7.40353 + vertex 576.558 41.5038 9.27756 + endloop + endfacet + facet normal 0.266576 -0.936665 -0.227146 + outer loop + vertex 576.558 41.5038 9.27756 + vertex 582.308 43.5947 7.40353 + vertex 582.301 43.138 9.27895 + endloop + endfacet + facet normal 0.26696 -0.936562 -0.22712 + outer loop + vertex 582.308 43.5947 7.40353 + vertex 588.024 45.2223 7.41012 + vertex 582.301 43.138 9.27895 + endloop + endfacet + facet normal 0.267389 -0.936716 -0.225977 + outer loop + vertex 582.301 43.138 9.27895 + vertex 588.024 45.2223 7.41012 + vertex 587.986 44.7584 9.28778 + endloop + endfacet + facet normal 0.115261 -0.438688 -0.891217 + outer loop + vertex 581.126 48.3972 3.16613 + vertex 586.537 49.5044 3.32092 + vertex 581.734 46.2689 4.29239 + endloop + endfacet + facet normal 0.131504 -0.459023 -0.878638 + outer loop + vertex 581.734 46.2689 4.29239 + vertex 586.537 49.5044 3.32092 + vertex 587.49 47.9014 4.301 + endloop + endfacet + facet normal 0.138342 -0.453865 -0.880266 + outer loop + vertex 574.904 46.2186 3.31158 + vertex 581.126 48.3972 3.16613 + vertex 575.857 44.5906 4.30074 + endloop + endfacet + facet normal 0.123356 -0.436398 -0.891258 + outer loop + vertex 575.857 44.5906 4.30074 + vertex 581.126 48.3972 3.16613 + vertex 581.734 46.2689 4.29239 + endloop + endfacet + facet normal 0.178376 -0.628401 -0.757162 + outer loop + vertex 575.857 44.5906 4.30074 + vertex 581.734 46.2689 4.29239 + vertex 576.336 43.025 5.71297 + endloop + endfacet + facet normal 0.179532 -0.629724 -0.755788 + outer loop + vertex 576.336 43.025 5.71297 + vertex 581.734 46.2689 4.29239 + vertex 582.155 44.6891 5.70856 + endloop + endfacet + facet normal 0.179721 -0.629672 -0.755786 + outer loop + vertex 581.734 46.2689 4.29239 + vertex 587.49 47.9014 4.301 + vertex 582.155 44.6891 5.70856 + endloop + endfacet + facet normal 0.181091 -0.631233 -0.754156 + outer loop + vertex 582.155 44.6891 5.70856 + vertex 587.49 47.9014 4.301 + vertex 587.908 46.3329 5.71425 + endloop + endfacet + facet normal 0.0893155 -0.303882 -0.948514 + outer loop + vertex 586.537 49.5044 3.32092 + vertex 581.126 48.3972 3.16613 + vertex 588.815 53.3329 2.30882 + endloop + endfacet + facet normal 0.0818039 -0.29714 -0.951323 + outer loop + vertex 574.904 46.2186 3.31158 + vertex 577.794 50.3552 2.26801 + vertex 581.126 48.3972 3.16613 + endloop + endfacet + facet normal 0.0832235 -0.294976 -0.951873 + outer loop + vertex 577.794 50.3552 2.26801 + vertex 588.815 53.3329 2.30882 + vertex 581.126 48.3972 3.16613 + endloop + endfacet + facet normal 0.0572271 -0.205931 -0.976892 + outer loop + vertex 576.113 54.4642 1.30337 + vertex 586.98 57.3274 1.33638 + vertex 577.794 50.3552 2.26801 + endloop + endfacet + facet normal 0.060316 -0.209863 -0.975868 + outer loop + vertex 577.794 50.3552 2.26801 + vertex 586.98 57.3274 1.33638 + vertex 588.815 53.3329 2.30882 + endloop + endfacet + facet normal 0.268376 -0.795898 0.542697 + outer loop + vertex 587.069 83.5832 28.7083 + vertex 592.665 85.5306 28.7972 + vertex 584.323 84.6077 31.569 + endloop + endfacet + facet normal 0.265563 -0.789306 0.5536 + outer loop + vertex 598.16 86.8985 28.1115 + vertex 596.406 88.3374 31.0043 + vertex 592.665 85.5306 28.7972 + endloop + endfacet + facet normal 0.26987 -0.791231 0.548747 + outer loop + vertex 596.406 88.3374 31.0043 + vertex 584.323 84.6077 31.569 + vertex 592.665 85.5306 28.7972 + endloop + endfacet + facet normal 0.222703 -0.668791 0.709311 + outer loop + vertex 590.657 81.6292 25.3081 + vertex 595.794 83.1426 25.1224 + vertex 591.49 83.5191 26.8288 + endloop + endfacet + facet normal 0.228123 -0.655381 0.720025 + outer loop + vertex 591.49 83.5191 26.8288 + vertex 595.794 83.1426 25.1224 + vertex 596.73 85.0767 26.5863 + endloop + endfacet + facet normal 0.22521 -0.68084 0.696949 + outer loop + vertex 585.067 79.9902 25.5136 + vertex 590.657 81.6292 25.3081 + vertex 585.739 81.8117 27.0759 + endloop + endfacet + facet normal 0.229113 -0.66946 0.706633 + outer loop + vertex 585.739 81.8117 27.0759 + vertex 590.657 81.6292 25.3081 + vertex 591.49 83.5191 26.8288 + endloop + endfacet + facet normal 0.249188 -0.750823 0.611694 + outer loop + vertex 585.739 81.8117 27.0759 + vertex 591.49 83.5191 26.8288 + vertex 587.069 83.5832 28.7083 + endloop + endfacet + facet normal 0.250523 -0.747892 0.614733 + outer loop + vertex 587.069 83.5832 28.7083 + vertex 591.49 83.5191 26.8288 + vertex 592.665 85.5306 28.7972 + endloop + endfacet + facet normal 0.250749 -0.747911 0.614617 + outer loop + vertex 591.49 83.5191 26.8288 + vertex 596.73 85.0767 26.5863 + vertex 592.665 85.5306 28.7972 + endloop + endfacet + facet normal 0.26074 -0.731794 0.629677 + outer loop + vertex 592.665 85.5306 28.7972 + vertex 596.73 85.0767 26.5863 + vertex 598.16 86.8985 28.1115 + endloop + endfacet + facet normal 0.139486 -0.415288 0.898933 + outer loop + vertex 590.576 77.9552 23.2523 + vertex 595.603 79.414 23.1462 + vertex 590.458 79.8285 24.1361 + endloop + endfacet + facet normal 0.14188 -0.400569 0.905215 + outer loop + vertex 590.458 79.8285 24.1361 + vertex 595.603 79.414 23.1462 + vertex 595.493 81.2967 23.9965 + endloop + endfacet + facet normal 0.142239 -0.43259 0.8903 + outer loop + vertex 585.053 76.3605 23.3598 + vertex 590.576 77.9552 23.2523 + vertex 584.938 78.2258 24.2845 + endloop + endfacet + facet normal 0.144579 -0.414711 0.898394 + outer loop + vertex 584.938 78.2258 24.2845 + vertex 590.576 77.9552 23.2523 + vertex 590.458 79.8285 24.1361 + endloop + endfacet + facet normal 0.187197 -0.570632 0.799585 + outer loop + vertex 584.938 78.2258 24.2845 + vertex 590.458 79.8285 24.1361 + vertex 585.067 79.9902 25.5136 + endloop + endfacet + facet normal 0.191187 -0.550259 0.812811 + outer loop + vertex 585.067 79.9902 25.5136 + vertex 590.458 79.8285 24.1361 + vertex 590.657 81.6292 25.3081 + endloop + endfacet + facet normal 0.183074 -0.550477 0.81453 + outer loop + vertex 590.458 79.8285 24.1361 + vertex 595.493 81.2967 23.9965 + vertex 590.657 81.6292 25.3081 + endloop + endfacet + facet normal 0.187031 -0.53355 0.82483 + outer loop + vertex 590.657 81.6292 25.3081 + vertex 595.493 81.2967 23.9965 + vertex 595.794 83.1426 25.1224 + endloop + endfacet + facet normal 0.0753499 -0.210971 0.974584 + outer loop + vertex 590.292 73.2528 22.0437 + vertex 595.012 75.0349 22.0646 + vertex 590.601 75.8432 22.5805 + endloop + endfacet + facet normal 0.0748522 -0.213376 0.974098 + outer loop + vertex 590.601 75.8432 22.5805 + vertex 595.012 75.0349 22.0646 + vertex 595.579 77.2763 22.512 + endloop + endfacet + facet normal 0.0706565 -0.227977 0.971099 + outer loop + vertex 584.562 72.049 22.178 + vertex 590.292 73.2528 22.0437 + vertex 585.06 74.255 22.6597 + endloop + endfacet + facet normal 0.0743543 -0.210872 0.974682 + outer loop + vertex 585.06 74.255 22.6597 + vertex 590.292 73.2528 22.0437 + vertex 590.601 75.8432 22.5805 + endloop + endfacet + facet normal 0.103344 -0.313562 0.943927 + outer loop + vertex 585.06 74.255 22.6597 + vertex 590.601 75.8432 22.5805 + vertex 585.053 76.3605 23.3598 + endloop + endfacet + facet normal 0.105159 -0.300283 0.948036 + outer loop + vertex 585.053 76.3605 23.3598 + vertex 590.601 75.8432 22.5805 + vertex 590.576 77.9552 23.2523 + endloop + endfacet + facet normal 0.0995913 -0.300517 0.948563 + outer loop + vertex 590.601 75.8432 22.5805 + vertex 595.579 77.2763 22.512 + vertex 590.576 77.9552 23.2523 + endloop + endfacet + facet normal 0.102537 -0.284003 0.953325 + outer loop + vertex 590.576 77.9552 23.2523 + vertex 595.579 77.2763 22.512 + vertex 595.603 79.414 23.1462 + endloop + endfacet + facet normal 0.0824662 -0.292573 0.95268 + outer loop + vertex 588.607 52.8581 17.8345 + vertex 593.624 54.7051 17.9674 + vertex 585.187 55.1253 18.8268 + endloop + endfacet + facet normal 0.0869959 -0.289185 0.953312 + outer loop + vertex 598.942 55.8121 17.8179 + vertex 595.365 58.0088 18.8107 + vertex 593.624 54.7051 17.9674 + endloop + endfacet + facet normal 0.0828913 -0.287263 0.954258 + outer loop + vertex 595.365 58.0088 18.8107 + vertex 585.187 55.1253 18.8268 + vertex 593.624 54.7051 17.9674 + endloop + endfacet + facet normal 0.142591 -0.482464 0.864231 + outer loop + vertex 593.07 50.2344 15.9268 + vertex 598.12 51.7177 15.9217 + vertex 593.406 52.3057 17.0277 + endloop + endfacet + facet normal 0.141855 -0.485447 0.862681 + outer loop + vertex 593.406 52.3057 17.0277 + vertex 598.12 51.7177 15.9217 + vertex 598.472 53.7701 17.0187 + endloop + endfacet + facet normal 0.138439 -0.480695 0.865891 + outer loop + vertex 587.566 48.6263 15.914 + vertex 593.07 50.2344 15.9268 + vertex 587.853 50.689 17.0132 + endloop + endfacet + facet normal 0.138142 -0.482204 0.865099 + outer loop + vertex 587.853 50.689 17.0132 + vertex 593.07 50.2344 15.9268 + vertex 593.406 52.3057 17.0277 + endloop + endfacet + facet normal 0.109725 -0.385061 0.916345 + outer loop + vertex 587.853 50.689 17.0132 + vertex 593.406 52.3057 17.0277 + vertex 588.607 52.8581 17.8345 + endloop + endfacet + facet normal 0.112228 -0.3712 0.921746 + outer loop + vertex 588.607 52.8581 17.8345 + vertex 593.406 52.3057 17.0277 + vertex 593.624 54.7051 17.9674 + endloop + endfacet + facet normal 0.1089 -0.371074 0.922196 + outer loop + vertex 593.406 52.3057 17.0277 + vertex 598.472 53.7701 17.0187 + vertex 593.624 54.7051 17.9674 + endloop + endfacet + facet normal 0.105605 -0.383415 0.917519 + outer loop + vertex 593.624 54.7051 17.9674 + vertex 598.472 53.7701 17.0187 + vertex 598.942 55.8121 17.8179 + endloop + endfacet + facet normal 0.221416 -0.753382 0.619185 + outer loop + vertex 593.221 47.2827 13.0053 + vertex 598.21 48.7451 13.0008 + vertex 593.057 48.5372 14.5905 + endloop + endfacet + facet normal 0.221836 -0.751987 0.620729 + outer loop + vertex 593.057 48.5372 14.5905 + vertex 598.21 48.7451 13.0008 + vertex 598.059 50.0096 14.5867 + endloop + endfacet + facet normal 0.21719 -0.752786 0.621402 + outer loop + vertex 587.756 45.6994 12.9975 + vertex 593.221 47.2827 13.0053 + vertex 587.589 46.9543 14.5762 + endloop + endfacet + facet normal 0.216767 -0.754442 0.61954 + outer loop + vertex 587.589 46.9543 14.5762 + vertex 593.221 47.2827 13.0053 + vertex 593.057 48.5372 14.5905 + endloop + endfacet + facet normal 0.175608 -0.613624 0.769823 + outer loop + vertex 587.589 46.9543 14.5762 + vertex 593.057 48.5372 14.5905 + vertex 587.566 48.6263 15.914 + endloop + endfacet + facet normal 0.176366 -0.609768 0.772708 + outer loop + vertex 587.566 48.6263 15.914 + vertex 593.057 48.5372 14.5905 + vertex 593.07 50.2344 15.9268 + endloop + endfacet + facet normal 0.179975 -0.609382 0.77218 + outer loop + vertex 593.057 48.5372 14.5905 + vertex 598.059 50.0096 14.5867 + vertex 593.07 50.2344 15.9268 + endloop + endfacet + facet normal 0.179887 -0.609743 0.771916 + outer loop + vertex 593.07 50.2344 15.9268 + vertex 598.059 50.0096 14.5867 + vertex 598.12 51.7177 15.9217 + endloop + endfacet + facet normal 0.281206 -0.952861 0.113927 + outer loop + vertex 593.482 46.3249 9.29712 + vertex 598.473 47.7968 9.28832 + vertex 593.372 46.5207 11.2058 + endloop + endfacet + facet normal 0.28009 -0.953596 0.11047 + outer loop + vertex 593.372 46.5207 11.2058 + vertex 598.473 47.7968 9.28832 + vertex 598.362 47.9853 11.1966 + endloop + endfacet + facet normal 0.272548 -0.956912 0.100186 + outer loop + vertex 587.986 44.7584 9.28778 + vertex 593.482 46.3249 9.29712 + vertex 587.902 44.9345 11.1978 + endloop + endfacet + facet normal 0.27652 -0.954246 0.113799 + outer loop + vertex 587.902 44.9345 11.1978 + vertex 593.482 46.3249 9.29712 + vertex 593.372 46.5207 11.2058 + endloop + endfacet + facet normal 0.255229 -0.882237 0.395622 + outer loop + vertex 587.902 44.9345 11.1978 + vertex 593.372 46.5207 11.2058 + vertex 587.756 45.6994 12.9975 + endloop + endfacet + facet normal 0.255097 -0.882517 0.395081 + outer loop + vertex 587.756 45.6994 12.9975 + vertex 593.372 46.5207 11.2058 + vertex 593.221 47.2827 13.0053 + endloop + endfacet + facet normal 0.259406 -0.881325 0.394937 + outer loop + vertex 593.372 46.5207 11.2058 + vertex 598.362 47.9853 11.1966 + vertex 593.221 47.2827 13.0053 + endloop + endfacet + facet normal 0.258965 -0.882159 0.393361 + outer loop + vertex 593.221 47.2827 13.0053 + vertex 598.362 47.9853 11.1966 + vertex 598.21 48.7451 13.0008 + endloop + endfacet + facet normal 0.236773 -0.809568 -0.537157 + outer loop + vertex 593.462 47.9171 5.72194 + vertex 598.514 49.3952 5.72109 + vertex 593.529 46.8077 7.42357 + endloop + endfacet + facet normal 0.236426 -0.809283 -0.53774 + outer loop + vertex 593.529 46.8077 7.42357 + vertex 598.514 49.3952 5.72109 + vertex 598.541 48.2758 7.41756 + endloop + endfacet + facet normal 0.230855 -0.806691 -0.544018 + outer loop + vertex 587.908 46.3329 5.71425 + vertex 593.462 47.9171 5.72194 + vertex 588.024 45.2223 7.41012 + endloop + endfacet + facet normal 0.234579 -0.810054 -0.537387 + outer loop + vertex 588.024 45.2223 7.41012 + vertex 593.462 47.9171 5.72194 + vertex 593.529 46.8077 7.42357 + endloop + endfacet + facet normal 0.270086 -0.935998 -0.225745 + outer loop + vertex 588.024 45.2223 7.41012 + vertex 593.529 46.8077 7.42357 + vertex 587.986 44.7584 9.28778 + endloop + endfacet + facet normal 0.266831 -0.93486 -0.234174 + outer loop + vertex 587.986 44.7584 9.28778 + vertex 593.529 46.8077 7.42357 + vertex 593.482 46.3249 9.29712 + endloop + endfacet + facet normal 0.27309 -0.933198 -0.233588 + outer loop + vertex 593.529 46.8077 7.42357 + vertex 598.541 48.2758 7.41756 + vertex 593.482 46.3249 9.29712 + endloop + endfacet + facet normal 0.274966 -0.933755 -0.229117 + outer loop + vertex 593.482 46.3249 9.29712 + vertex 598.541 48.2758 7.41756 + vertex 598.473 47.7968 9.28832 + endloop + endfacet + facet normal 0.118529 -0.45179 -0.884216 + outer loop + vertex 592.093 51.3894 3.20883 + vertex 596.862 52.3463 3.35926 + vertex 593.031 49.4703 4.31515 + endloop + endfacet + facet normal 0.141485 -0.476826 -0.867536 + outer loop + vertex 593.031 49.4703 4.31515 + vertex 596.862 52.3463 3.35926 + vertex 598.039 50.9504 4.31843 + endloop + endfacet + facet normal 0.137029 -0.45614 -0.879295 + outer loop + vertex 586.537 49.5044 3.32092 + vertex 592.093 51.3894 3.20883 + vertex 587.49 47.9014 4.301 + endloop + endfacet + facet normal 0.128896 -0.447223 -0.885086 + outer loop + vertex 587.49 47.9014 4.301 + vertex 592.093 51.3894 3.20883 + vertex 593.031 49.4703 4.31515 + endloop + endfacet + facet normal 0.180697 -0.631342 -0.754159 + outer loop + vertex 587.49 47.9014 4.301 + vertex 593.031 49.4703 4.31515 + vertex 587.908 46.3329 5.71425 + endloop + endfacet + facet normal 0.181328 -0.632042 -0.753421 + outer loop + vertex 587.908 46.3329 5.71425 + vertex 593.031 49.4703 4.31515 + vertex 593.462 47.9171 5.72194 + endloop + endfacet + facet normal 0.186821 -0.630484 -0.753384 + outer loop + vertex 593.031 49.4703 4.31515 + vertex 598.039 50.9504 4.31843 + vertex 593.462 47.9171 5.72194 + endloop + endfacet + facet normal 0.183303 -0.626941 -0.757196 + outer loop + vertex 593.462 47.9171 5.72194 + vertex 598.039 50.9504 4.31843 + vertex 598.514 49.3952 5.72109 + endloop + endfacet + facet normal 0.0927063 -0.313515 -0.945047 + outer loop + vertex 596.862 52.3463 3.35926 + vertex 592.093 51.3894 3.20883 + vertex 597.087 55.1227 2.46028 + endloop + endfacet + facet normal 0.0827664 -0.300433 -0.950205 + outer loop + vertex 586.537 49.5044 3.32092 + vertex 588.815 53.3329 2.30882 + vertex 592.093 51.3894 3.20883 + endloop + endfacet + facet normal 0.0824864 -0.300855 -0.950096 + outer loop + vertex 588.815 53.3329 2.30882 + vertex 597.087 55.1227 2.46028 + vertex 592.093 51.3894 3.20883 + endloop + endfacet + facet normal 0.0616962 -0.209241 -0.975916 + outer loop + vertex 586.98 57.3274 1.33638 + vertex 596.71 59.819 1.41729 + vertex 588.815 53.3329 2.30882 + endloop + endfacet + facet normal 0.063614 -0.211492 -0.975307 + outer loop + vertex 588.815 53.3329 2.30882 + vertex 596.71 59.819 1.41729 + vertex 597.087 55.1227 2.46028 + endloop + endfacet + facet normal 0.212521 -0.634379 0.743235 + outer loop + vertex 600.006 84.3582 24.9568 + vertex 602.899 85.1506 24.8059 + vertex 600.922 86.2635 26.321 + endloop + endfacet + facet normal 0.229501 -0.617084 0.752686 + outer loop + vertex 600.922 86.2635 26.321 + vertex 602.899 85.1506 24.8059 + vertex 603.711 86.9883 26.0648 + endloop + endfacet + facet normal 0.217188 -0.653754 0.724869 + outer loop + vertex 595.794 83.1426 25.1224 + vertex 600.006 84.3582 24.9568 + vertex 596.73 85.0767 26.5863 + endloop + endfacet + facet normal 0.226904 -0.636768 0.736913 + outer loop + vertex 596.73 85.0767 26.5863 + vertex 600.006 84.3582 24.9568 + vertex 600.922 86.2635 26.321 + endloop + endfacet + facet normal 0.246699 -0.728576 0.638996 + outer loop + vertex 596.73 85.0767 26.5863 + vertex 600.922 86.2635 26.321 + vertex 598.16 86.8985 28.1115 + endloop + endfacet + facet normal 0.252686 -0.720779 0.645467 + outer loop + vertex 598.16 86.8985 28.1115 + vertex 600.922 86.2635 26.321 + vertex 601.812 88.0714 27.9914 + endloop + endfacet + facet normal 0.246749 -0.720382 0.648201 + outer loop + vertex 600.922 86.2635 26.321 + vertex 603.711 86.9883 26.0648 + vertex 601.812 88.0714 27.9914 + endloop + endfacet + facet normal 0.277142 -0.69473 0.663734 + outer loop + vertex 601.812 88.0714 27.9914 + vertex 603.711 86.9883 26.0648 + vertex 604.573 88.5021 27.2895 + endloop + endfacet + facet normal 0.131187 -0.386349 0.912976 + outer loop + vertex 599.69 80.5891 23.0633 + vertex 602.514 81.3902 22.9964 + vertex 599.631 82.4907 23.8764 + endloop + endfacet + facet normal 0.136449 -0.375547 0.916704 + outer loop + vertex 599.631 82.4907 23.8764 + vertex 602.514 81.3902 22.9964 + vertex 602.502 83.2946 23.7784 + endloop + endfacet + facet normal 0.133804 -0.401425 0.906066 + outer loop + vertex 595.603 79.414 23.1462 + vertex 599.69 80.5891 23.0633 + vertex 595.493 81.2967 23.9965 + endloop + endfacet + facet normal 0.137804 -0.385824 0.912222 + outer loop + vertex 595.493 81.2967 23.9965 + vertex 599.69 80.5891 23.0633 + vertex 599.631 82.4907 23.8764 + endloop + endfacet + facet normal 0.177899 -0.533366 0.826966 + outer loop + vertex 595.493 81.2967 23.9965 + vertex 599.631 82.4907 23.8764 + vertex 595.794 83.1426 25.1224 + endloop + endfacet + facet normal 0.182762 -0.519506 0.834693 + outer loop + vertex 595.794 83.1426 25.1224 + vertex 599.631 82.4907 23.8764 + vertex 600.006 84.3582 24.9568 + endloop + endfacet + facet normal 0.173894 -0.519003 0.836897 + outer loop + vertex 599.631 82.4907 23.8764 + vertex 602.502 83.2946 23.7784 + vertex 600.006 84.3582 24.9568 + endloop + endfacet + facet normal 0.182496 -0.505747 0.843158 + outer loop + vertex 600.006 84.3582 24.9568 + vertex 602.502 83.2946 23.7784 + vertex 602.899 85.1506 24.8059 + endloop + endfacet + facet normal 0.0753118 -0.199242 0.977052 + outer loop + vertex 599.222 75.8643 21.9525 + vertex 602.216 77.1921 21.9925 + vertex 599.748 78.4861 22.4466 + endloop + endfacet + facet normal 0.0744436 -0.200809 0.976798 + outer loop + vertex 599.748 78.4861 22.4466 + vertex 602.216 77.1921 21.9925 + vertex 602.617 79.3295 22.4013 + endloop + endfacet + facet normal 0.0676634 -0.211734 0.974982 + outer loop + vertex 595.012 75.0349 22.0646 + vertex 599.222 75.8643 21.9525 + vertex 595.579 77.2763 22.512 + endloop + endfacet + facet normal 0.0730219 -0.198831 0.97731 + outer loop + vertex 595.579 77.2763 22.512 + vertex 599.222 75.8643 21.9525 + vertex 599.748 78.4861 22.4466 + endloop + endfacet + facet normal 0.0973967 -0.284096 0.953836 + outer loop + vertex 595.579 77.2763 22.512 + vertex 599.748 78.4861 22.4466 + vertex 595.603 79.414 23.1462 + endloop + endfacet + facet normal 0.0991711 -0.277497 0.955594 + outer loop + vertex 595.603 79.414 23.1462 + vertex 599.748 78.4861 22.4466 + vertex 599.69 80.5891 23.0633 + endloop + endfacet + facet normal 0.0966939 -0.277629 0.95581 + outer loop + vertex 599.748 78.4861 22.4466 + vertex 602.617 79.3295 22.4013 + vertex 599.69 80.5891 23.0633 + endloop + endfacet + facet normal 0.0996637 -0.271493 0.957266 + outer loop + vertex 599.69 80.5891 23.0633 + vertex 602.617 79.3295 22.4013 + vertex 602.514 81.3902 22.9964 + endloop + endfacet + facet normal 0.151052 -0.488322 0.859491 + outer loop + vertex 602.318 52.9266 15.8887 + vertex 605.288 53.7556 15.8378 + vertex 602.582 54.9237 16.977 + endloop + endfacet + facet normal 0.149419 -0.490933 0.858289 + outer loop + vertex 602.582 54.9237 16.977 + vertex 605.288 53.7556 15.8378 + vertex 605.394 55.6973 16.93 + endloop + endfacet + facet normal 0.146629 -0.48575 0.861712 + outer loop + vertex 598.12 51.7177 15.9217 + vertex 602.318 52.9266 15.8887 + vertex 598.472 53.7701 17.0187 + endloop + endfacet + facet normal 0.145742 -0.488167 0.860495 + outer loop + vertex 598.472 53.7701 17.0187 + vertex 602.318 52.9266 15.8887 + vertex 602.582 54.9237 16.977 + endloop + endfacet + facet normal 0.117416 -0.385265 0.915305 + outer loop + vertex 598.472 53.7701 17.0187 + vertex 602.582 54.9237 16.977 + vertex 598.942 55.8121 17.8179 + endloop + endfacet + facet normal 0.121428 -0.373095 0.919813 + outer loop + vertex 598.942 55.8121 17.8179 + vertex 602.582 54.9237 16.977 + vertex 602.26 57.1386 17.9179 + endloop + endfacet + facet normal 0.118178 -0.373652 0.92001 + outer loop + vertex 602.582 54.9237 16.977 + vertex 605.394 55.6973 16.93 + vertex 602.26 57.1386 17.9179 + endloop + endfacet + facet normal 0.109826 -0.388342 0.914948 + outer loop + vertex 602.26 57.1386 17.9179 + vertex 605.394 55.6973 16.93 + vertex 605.197 57.5912 17.7575 + endloop + endfacet + facet normal 0.235283 -0.754383 0.61282 + outer loop + vertex 602.31 49.9762 12.9627 + vertex 605.21 50.8461 12.9199 + vertex 602.198 51.2325 14.5519 + endloop + endfacet + facet normal 0.230781 -0.761159 0.606117 + outer loop + vertex 602.198 51.2325 14.5519 + vertex 605.21 50.8461 12.9199 + vertex 605.145 52.0887 14.5053 + endloop + endfacet + facet normal 0.230937 -0.749901 0.619933 + outer loop + vertex 598.21 48.7451 13.0008 + vertex 602.31 49.9762 12.9627 + vertex 598.059 50.0096 14.5867 + endloop + endfacet + facet normal 0.228447 -0.755899 0.613538 + outer loop + vertex 598.059 50.0096 14.5867 + vertex 602.31 49.9762 12.9627 + vertex 602.198 51.2325 14.5519 + endloop + endfacet + facet normal 0.186416 -0.609139 0.770843 + outer loop + vertex 598.059 50.0096 14.5867 + vertex 602.198 51.2325 14.5519 + vertex 598.12 51.7177 15.9217 + endloop + endfacet + facet normal 0.183636 -0.616903 0.765316 + outer loop + vertex 598.12 51.7177 15.9217 + vertex 602.198 51.2325 14.5519 + vertex 602.318 52.9266 15.8887 + endloop + endfacet + facet normal 0.191189 -0.616338 0.76392 + outer loop + vertex 602.198 51.2325 14.5519 + vertex 605.145 52.0887 14.5053 + vertex 602.318 52.9266 15.8887 + endloop + endfacet + facet normal 0.186975 -0.623141 0.759431 + outer loop + vertex 602.318 52.9266 15.8887 + vertex 605.145 52.0887 14.5053 + vertex 605.288 53.7556 15.8378 + endloop + endfacet + facet normal 0.30346 -0.947325 0.10241 + outer loop + vertex 602.554 49.0559 9.2436 + vertex 605.409 49.965 9.19315 + vertex 602.449 49.2291 11.1546 + endloop + endfacet + facet normal 0.296314 -0.95081 0.0903217 + outer loop + vertex 602.449 49.2291 11.1546 + vertex 605.409 49.965 9.19315 + vertex 605.316 50.1184 11.1115 + endloop + endfacet + facet normal 0.294126 -0.949315 0.110862 + outer loop + vertex 598.473 47.7968 9.28832 + vertex 602.554 49.0559 9.2436 + vertex 598.362 47.9853 11.1966 + endloop + endfacet + facet normal 0.290564 -0.951395 0.102077 + outer loop + vertex 598.362 47.9853 11.1966 + vertex 602.554 49.0559 9.2436 + vertex 602.449 49.2291 11.1546 + endloop + endfacet + facet normal 0.2714 -0.878611 0.392918 + outer loop + vertex 598.362 47.9853 11.1966 + vertex 602.449 49.2291 11.1546 + vertex 598.21 48.7451 13.0008 + endloop + endfacet + facet normal 0.268639 -0.882738 0.385496 + outer loop + vertex 598.21 48.7451 13.0008 + vertex 602.449 49.2291 11.1546 + vertex 602.31 49.9762 12.9627 + endloop + endfacet + facet normal 0.27872 -0.879798 0.385059 + outer loop + vertex 602.449 49.2291 11.1546 + vertex 605.316 50.1184 11.1115 + vertex 602.31 49.9762 12.9627 + endloop + endfacet + facet normal 0.27159 -0.88723 0.37291 + outer loop + vertex 602.31 49.9762 12.9627 + vertex 605.316 50.1184 11.1115 + vertex 605.21 50.8461 12.9199 + endloop + endfacet + facet normal 0.247334 -0.803219 -0.541909 + outer loop + vertex 602.603 50.6669 5.69649 + vertex 605.443 51.5742 5.64815 + vertex 602.619 49.5375 7.37797 + endloop + endfacet + facet normal 0.252187 -0.805346 -0.536488 + outer loop + vertex 602.619 49.5375 7.37797 + vertex 605.443 51.5742 5.64815 + vertex 605.434 50.4516 7.32892 + endloop + endfacet + facet normal 0.247721 -0.806848 -0.536312 + outer loop + vertex 598.514 49.3952 5.72109 + vertex 602.603 50.6669 5.69649 + vertex 598.541 48.2758 7.41756 + endloop + endfacet + facet normal 0.24348 -0.804046 -0.542427 + outer loop + vertex 598.541 48.2758 7.41756 + vertex 602.603 50.6669 5.69649 + vertex 602.619 49.5375 7.37797 + endloop + endfacet + facet normal 0.285745 -0.930796 -0.227967 + outer loop + vertex 598.541 48.2758 7.41756 + vertex 602.619 49.5375 7.37797 + vertex 598.473 47.7968 9.28832 + endloop + endfacet + facet normal 0.284608 -0.930584 -0.230242 + outer loop + vertex 598.473 47.7968 9.28832 + vertex 602.619 49.5375 7.37797 + vertex 602.554 49.0559 9.2436 + endloop + endfacet + facet normal 0.297061 -0.92702 -0.228885 + outer loop + vertex 602.619 49.5375 7.37797 + vertex 605.434 50.4516 7.32892 + vertex 602.554 49.0559 9.2436 + endloop + endfacet + facet normal 0.290877 -0.926698 -0.237953 + outer loop + vertex 602.554 49.0559 9.2436 + vertex 605.434 50.4516 7.32892 + vertex 605.409 49.965 9.19315 + endloop + endfacet + facet normal 0.126439 -0.439925 -0.889089 + outer loop + vertex 600.922 54.1335 3.17838 + vertex 604.145 54.8888 3.26299 + vertex 602.242 52.2684 4.289 + endloop + endfacet + facet normal 0.133386 -0.443813 -0.886137 + outer loop + vertex 602.242 52.2684 4.289 + vertex 604.145 54.8888 3.26299 + vertex 605.137 53.2103 4.25297 + endloop + endfacet + facet normal 0.164053 -0.460951 -0.87213 + outer loop + vertex 596.862 52.3463 3.35926 + vertex 600.922 54.1335 3.17838 + vertex 598.039 50.9504 4.31843 + endloop + endfacet + facet normal 0.13086 -0.437211 -0.889788 + outer loop + vertex 598.039 50.9504 4.31843 + vertex 600.922 54.1335 3.17838 + vertex 602.242 52.2684 4.289 + endloop + endfacet + facet normal 0.190589 -0.624736 -0.757219 + outer loop + vertex 598.039 50.9504 4.31843 + vertex 602.242 52.2684 4.289 + vertex 598.514 49.3952 5.72109 + endloop + endfacet + facet normal 0.18945 -0.62379 -0.758284 + outer loop + vertex 598.514 49.3952 5.72109 + vertex 602.242 52.2684 4.289 + vertex 602.603 50.6669 5.69649 + endloop + endfacet + facet normal 0.193224 -0.622811 -0.758137 + outer loop + vertex 602.242 52.2684 4.289 + vertex 605.137 53.2103 4.25297 + vertex 602.603 50.6669 5.69649 + endloop + endfacet + facet normal 0.18424 -0.617553 -0.764646 + outer loop + vertex 602.603 50.6669 5.69649 + vertex 605.137 53.2103 4.25297 + vertex 605.443 51.5742 5.64815 + endloop + endfacet + facet normal 0.282506 -0.752514 0.594906 + outer loop + vertex 604.573 88.5021 27.2895 + vertex 605.745 89.1004 27.4899 + vertex 603.773 89.7933 29.3028 + endloop + endfacet + facet normal 0.337393 -0.757129 0.559394 + outer loop + vertex 606.24 89.1546 27.2642 + vertex 606.531 91.0863 29.7032 + vertex 605.745 89.1004 27.4899 + endloop + endfacet + facet normal 0.272042 -0.762308 0.587265 + outer loop + vertex 606.531 91.0863 29.7032 + vertex 603.773 89.7933 29.3028 + vertex 605.745 89.1004 27.4899 + endloop + endfacet + facet normal 0.314992 -0.614456 0.723342 + outer loop + vertex 604.42 85.5711 24.6998 + vertex 604.911 85.8234 24.7006 + vertex 605.129 87.3572 25.9083 + endloop + endfacet + facet normal 0.281086 -0.61811 0.734119 + outer loop + vertex 605.129 87.3572 25.9083 + vertex 604.911 85.8234 24.7006 + vertex 605.562 87.5956 25.9434 + endloop + endfacet + facet normal 0.222918 -0.616086 0.755477 + outer loop + vertex 602.899 85.1506 24.8059 + vertex 604.42 85.5711 24.6998 + vertex 603.711 86.9883 26.0648 + endloop + endfacet + facet normal 0.241549 -0.607747 0.756504 + outer loop + vertex 603.711 86.9883 26.0648 + vertex 604.42 85.5711 24.6998 + vertex 605.129 87.3572 25.9083 + endloop + endfacet + facet normal 0.254479 -0.691667 0.675897 + outer loop + vertex 603.711 86.9883 26.0648 + vertex 605.129 87.3572 25.9083 + vertex 604.573 88.5021 27.2895 + endloop + endfacet + facet normal 0.240653 -0.697395 0.675075 + outer loop + vertex 604.573 88.5021 27.2895 + vertex 605.129 87.3572 25.9083 + vertex 605.745 89.1004 27.4899 + endloop + endfacet + facet normal 0.331528 -0.695427 0.637551 + outer loop + vertex 605.129 87.3572 25.9083 + vertex 605.562 87.5956 25.9434 + vertex 605.745 89.1004 27.4899 + endloop + endfacet + facet normal 0.361229 -0.689258 0.628042 + outer loop + vertex 605.745 89.1004 27.4899 + vertex 605.562 87.5956 25.9434 + vertex 606.24 89.1546 27.2642 + endloop + endfacet + facet normal 0.190864 -0.36613 0.91078 + outer loop + vertex 603.984 81.8249 22.9567 + vertex 604.345 82.1045 22.9934 + vertex 604.008 83.7359 23.7198 + endloop + endfacet + facet normal 0.188964 -0.366612 0.910982 + outer loop + vertex 604.008 83.7359 23.7198 + vertex 604.345 82.1045 22.9934 + vertex 604.465 84.0443 23.7492 + endloop + endfacet + facet normal 0.135906 -0.375578 0.916772 + outer loop + vertex 602.514 81.3902 22.9964 + vertex 603.984 81.8249 22.9567 + vertex 602.502 83.2946 23.7784 + endloop + endfacet + facet normal 0.143763 -0.368576 0.918414 + outer loop + vertex 602.502 83.2946 23.7784 + vertex 603.984 81.8249 22.9567 + vertex 604.008 83.7359 23.7198 + endloop + endfacet + facet normal 0.181022 -0.505643 0.843538 + outer loop + vertex 602.502 83.2946 23.7784 + vertex 604.008 83.7359 23.7198 + vertex 602.899 85.1506 24.8059 + endloop + endfacet + facet normal 0.196 -0.495806 0.846026 + outer loop + vertex 602.899 85.1506 24.8059 + vertex 604.008 83.7359 23.7198 + vertex 604.42 85.5711 24.6998 + endloop + endfacet + facet normal 0.285457 -0.500557 0.817286 + outer loop + vertex 604.008 83.7359 23.7198 + vertex 604.465 84.0443 23.7492 + vertex 604.42 85.5711 24.6998 + endloop + endfacet + facet normal 0.258551 -0.505141 0.823398 + outer loop + vertex 604.42 85.5711 24.6998 + vertex 604.465 84.0443 23.7492 + vertex 604.911 85.8234 24.7006 + endloop + endfacet + facet normal 0.0877114 -0.194323 0.977008 + outer loop + vertex 603.919 77.3945 21.9218 + vertex 604.654 78.0509 21.9864 + vertex 604.107 79.7792 22.3792 + endloop + endfacet + facet normal 0.0670139 -0.200942 0.977308 + outer loop + vertex 604.107 79.7792 22.3792 + vertex 604.654 78.0509 21.9864 + vertex 604.52 79.9723 22.3906 + endloop + endfacet + facet normal 0.0642193 -0.199095 0.977874 + outer loop + vertex 602.216 77.1921 21.9925 + vertex 603.919 77.3945 21.9218 + vertex 602.617 79.3295 22.4013 + endloop + endfacet + facet normal 0.0728508 -0.193418 0.978408 + outer loop + vertex 602.617 79.3295 22.4013 + vertex 603.919 77.3945 21.9218 + vertex 604.107 79.7792 22.3792 + endloop + endfacet + facet normal 0.096174 -0.271749 0.957551 + outer loop + vertex 602.617 79.3295 22.4013 + vertex 604.107 79.7792 22.3792 + vertex 602.514 81.3902 22.9964 + endloop + endfacet + facet normal 0.10414 -0.264345 0.958789 + outer loop + vertex 602.514 81.3902 22.9964 + vertex 604.107 79.7792 22.3792 + vertex 603.984 81.8249 22.9567 + endloop + endfacet + facet normal 0.097438 -0.264905 0.959339 + outer loop + vertex 604.107 79.7792 22.3792 + vertex 604.52 79.9723 22.3906 + vertex 603.984 81.8249 22.9567 + endloop + endfacet + facet normal 0.105649 -0.262467 0.95914 + outer loop + vertex 603.984 81.8249 22.9567 + vertex 604.52 79.9723 22.3906 + vertex 604.345 82.1045 22.9934 + endloop + endfacet + facet normal 0.0818663 -0.302351 0.949674 + outer loop + vertex 605.197 57.5912 17.7575 + vertex 606.039 58.4369 17.9542 + vertex 602.23 60.0924 18.8096 + endloop + endfacet + facet normal 0.0385895 -0.297749 0.953864 + outer loop + vertex 606.59 58.4387 17.9324 + vertex 605.337 61.7171 19.0065 + vertex 606.039 58.4369 17.9542 + endloop + endfacet + facet normal 0.0895405 -0.286823 0.95379 + outer loop + vertex 605.337 61.7171 19.0065 + vertex 602.23 60.0924 18.8096 + vertex 606.039 58.4369 17.9542 + endloop + endfacet + facet normal 0.104906 -0.491952 0.864279 + outer loop + vertex 606.854 54.229 15.8292 + vertex 607.252 54.5074 15.9394 + vertex 606.783 56.164 16.9393 + endloop + endfacet + facet normal 0.182318 -0.469736 0.863775 + outer loop + vertex 606.783 56.164 16.9393 + vertex 607.252 54.5074 15.9394 + vertex 606.987 56.4424 17.0476 + endloop + endfacet + facet normal 0.153074 -0.490809 0.857715 + outer loop + vertex 605.288 53.7556 15.8378 + vertex 606.854 54.229 15.8292 + vertex 605.394 55.6973 16.93 + endloop + endfacet + facet normal 0.157914 -0.486975 0.859022 + outer loop + vertex 605.394 55.6973 16.93 + vertex 606.854 54.229 15.8292 + vertex 606.783 56.164 16.9393 + endloop + endfacet + facet normal 0.12377 -0.386463 0.913963 + outer loop + vertex 605.394 55.6973 16.93 + vertex 606.783 56.164 16.9393 + vertex 605.197 57.5912 17.7575 + endloop + endfacet + facet normal 0.148855 -0.362148 0.920158 + outer loop + vertex 605.197 57.5912 17.7575 + vertex 606.783 56.164 16.9393 + vertex 606.039 58.4369 17.9542 + endloop + endfacet + facet normal 0.0497996 -0.393578 0.917942 + outer loop + vertex 606.783 56.164 16.9393 + vertex 606.987 56.4424 17.0476 + vertex 606.039 58.4369 17.9542 + endloop + endfacet + facet normal 0.0374334 -0.398715 0.916311 + outer loop + vertex 606.039 58.4369 17.9542 + vertex 606.987 56.4424 17.0476 + vertex 606.59 58.4387 17.9324 + endloop + endfacet + facet normal 0.101163 -0.779392 0.618316 + outer loop + vertex 606.807 51.3234 12.9356 + vertex 607.343 51.5102 13.0834 + vertex 606.797 52.5695 14.5079 + endloop + endfacet + facet normal 0.213229 -0.743128 0.634267 + outer loop + vertex 606.797 52.5695 14.5079 + vertex 607.343 51.5102 13.0834 + vertex 607.299 52.8162 14.6282 + endloop + endfacet + facet normal 0.22209 -0.762925 0.607142 + outer loop + vertex 605.21 50.8461 12.9199 + vertex 606.807 51.3234 12.9356 + vertex 605.145 52.0887 14.5053 + endloop + endfacet + facet normal 0.221247 -0.763613 0.606585 + outer loop + vertex 605.145 52.0887 14.5053 + vertex 606.807 51.3234 12.9356 + vertex 606.797 52.5695 14.5079 + endloop + endfacet + facet normal 0.180269 -0.623575 0.760695 + outer loop + vertex 605.145 52.0887 14.5053 + vertex 606.797 52.5695 14.5079 + vertex 605.288 53.7556 15.8378 + endloop + endfacet + facet normal 0.190252 -0.615504 0.764826 + outer loop + vertex 605.288 53.7556 15.8378 + vertex 606.797 52.5695 14.5079 + vertex 606.854 54.229 15.8292 + endloop + endfacet + facet normal 0.119479 -0.620933 0.774704 + outer loop + vertex 606.797 52.5695 14.5079 + vertex 607.299 52.8162 14.6282 + vertex 606.854 54.229 15.8292 + endloop + endfacet + facet normal 0.202426 -0.596494 0.776672 + outer loop + vertex 606.854 54.229 15.8292 + vertex 607.299 52.8162 14.6282 + vertex 607.252 54.5074 15.9394 + endloop + endfacet + facet normal 0.11564 -0.989786 0.0833719 + outer loop + vertex 606.974 50.4344 9.22217 + vertex 607.473 50.5088 9.41465 + vertex 606.908 50.5882 11.14 + endloop + endfacet + facet normal 0.220686 -0.968332 0.116751 + outer loop + vertex 606.908 50.5882 11.14 + vertex 607.473 50.5088 9.41465 + vertex 607.407 50.7226 11.3132 + endloop + endfacet + facet normal 0.284477 -0.954445 0.090041 + outer loop + vertex 605.409 49.965 9.19315 + vertex 606.974 50.4344 9.22217 + vertex 605.316 50.1184 11.1115 + endloop + endfacet + facet normal 0.280532 -0.955955 0.0863255 + outer loop + vertex 605.316 50.1184 11.1115 + vertex 606.974 50.4344 9.22217 + vertex 606.908 50.5882 11.14 + endloop + endfacet + facet normal 0.256338 -0.891423 0.373705 + outer loop + vertex 605.316 50.1184 11.1115 + vertex 606.908 50.5882 11.14 + vertex 605.21 50.8461 12.9199 + endloop + endfacet + facet normal 0.261699 -0.887916 0.378312 + outer loop + vertex 605.21 50.8461 12.9199 + vertex 606.908 50.5882 11.14 + vertex 606.807 51.3234 12.9356 + endloop + endfacet + facet normal 0.11467 -0.917039 0.381955 + outer loop + vertex 606.908 50.5882 11.14 + vertex 607.407 50.7226 11.3132 + vertex 606.807 51.3234 12.9356 + endloop + endfacet + facet normal 0.199707 -0.892557 0.404301 + outer loop + vertex 606.807 51.3234 12.9356 + vertex 607.407 50.7226 11.3132 + vertex 607.343 51.5102 13.0834 + endloop + endfacet + facet normal 0.0684845 -0.837828 -0.541622 + outer loop + vertex 606.925 51.9848 5.67475 + vertex 607.397 51.8939 5.87506 + vertex 606.974 50.9057 7.35005 + endloop + endfacet + facet normal 0.220351 -0.838439 -0.498463 + outer loop + vertex 606.974 50.9057 7.35005 + vertex 607.397 51.8939 5.87506 + vertex 607.462 50.913 7.55344 + endloop + endfacet + facet normal 0.233822 -0.809123 -0.539116 + outer loop + vertex 605.443 51.5742 5.64815 + vertex 606.925 51.9848 5.67475 + vertex 605.434 50.4516 7.32892 + endloop + endfacet + facet normal 0.246529 -0.811476 -0.529839 + outer loop + vertex 605.434 50.4516 7.32892 + vertex 606.925 51.9848 5.67475 + vertex 606.974 50.9057 7.35005 + endloop + endfacet + facet normal 0.277623 -0.930457 -0.239113 + outer loop + vertex 605.434 50.4516 7.32892 + vertex 606.974 50.9057 7.35005 + vertex 605.409 49.965 9.19315 + endloop + endfacet + facet normal 0.283169 -0.930038 -0.234188 + outer loop + vertex 605.409 49.965 9.19315 + vertex 606.974 50.9057 7.35005 + vertex 606.974 50.4344 9.22217 + endloop + endfacet + facet normal 0.115469 -0.963246 -0.242538 + outer loop + vertex 606.974 50.9057 7.35005 + vertex 607.462 50.913 7.55344 + vertex 606.974 50.4344 9.22217 + endloop + endfacet + facet normal 0.222611 -0.952431 -0.208133 + outer loop + vertex 606.974 50.4344 9.22217 + vertex 607.462 50.913 7.55344 + vertex 607.473 50.5088 9.41465 + endloop + endfacet + facet normal -0.0267889 -0.482755 -0.875346 + outer loop + vertex 605.824 55.7552 3.11042 + vertex 606.784 55.2765 3.34502 + vertex 606.692 53.6102 4.26684 + endloop + endfacet + facet normal 0.098361 -0.485879 -0.868474 + outer loop + vertex 606.692 53.6102 4.26684 + vertex 606.784 55.2765 3.34502 + vertex 607.234 53.3469 4.47549 + endloop + endfacet + facet normal 0.145167 -0.437585 -0.887382 + outer loop + vertex 604.145 54.8888 3.26299 + vertex 605.824 55.7552 3.11042 + vertex 605.137 53.2103 4.25297 + endloop + endfacet + facet normal 0.119408 -0.433292 -0.893308 + outer loop + vertex 605.137 53.2103 4.25297 + vertex 605.824 55.7552 3.11042 + vertex 606.692 53.6102 4.26684 + endloop + endfacet + facet normal 0.166678 -0.62153 -0.765453 + outer loop + vertex 605.137 53.2103 4.25297 + vertex 606.692 53.6102 4.26684 + vertex 605.443 51.5742 5.64815 + endloop + endfacet + facet normal 0.18742 -0.627594 -0.755645 + outer loop + vertex 605.443 51.5742 5.64815 + vertex 606.692 53.6102 4.26684 + vertex 606.925 51.9848 5.67475 + endloop + endfacet + facet normal -0.0289419 -0.656825 -0.753487 + outer loop + vertex 606.692 53.6102 4.26684 + vertex 607.234 53.3469 4.47549 + vertex 606.925 51.9848 5.67475 + endloop + endfacet + facet normal 0.175531 -0.672622 -0.718866 + outer loop + vertex 606.925 51.9848 5.67475 + vertex 607.234 53.3469 4.47549 + vertex 607.397 51.8939 5.87506 + endloop + endfacet + facet normal 0.0787512 -0.306919 -0.948472 + outer loop + vertex 606.784 55.2765 3.34502 + vertex 605.824 55.7552 3.11042 + vertex 606.004 58.4078 2.26695 + endloop + endfacet + facet normal 0.0670055 -0.297562 -0.952348 + outer loop + vertex 604.145 54.8888 3.26299 + vertex 602.908 58.2316 2.13151 + vertex 605.824 55.7552 3.11042 + endloop + endfacet + facet normal 0.0590036 -0.30612 -0.950163 + outer loop + vertex 602.908 58.2316 2.13151 + vertex 606.004 58.4078 2.26695 + vertex 605.824 55.7552 3.11042 + endloop + endfacet + facet normal 0.0356832 -0.198781 -0.979394 + outer loop + vertex 602.347 63.0779 1.12745 + vertex 604.987 62.684 1.30359 + vertex 602.908 58.2316 2.13151 + endloop + endfacet + facet normal 0.0545309 -0.2071 -0.976799 + outer loop + vertex 602.908 58.2316 2.13151 + vertex 604.987 62.684 1.30359 + vertex 606.004 58.4078 2.26695 + endloop + endfacet + facet normal -0.12644 0.600277 -0.789734 + outer loop + vertex 604.911 85.8234 24.7006 + vertex 604.966 86.1139 24.9126 + vertex 605.562 87.5956 25.9434 + endloop + endfacet + facet normal -0.742156 -0.154947 0.652071 + outer loop + vertex 605.562 87.5956 25.9434 + vertex 604.966 86.1139 24.9126 + vertex 605.775 88.065 26.2973 + endloop + endfacet + facet normal 0.843136 -0.510314 0.169413 + outer loop + vertex 605.562 87.5956 25.9434 + vertex 605.775 88.065 26.2973 + vertex 606.24 89.1546 27.2642 + endloop + endfacet + facet normal 0.72688 -0.602628 0.329371 + outer loop + vertex 606.24 89.1546 27.2642 + vertex 605.775 88.065 26.2973 + vertex 606.21 88.9774 27.0062 + endloop + endfacet + facet normal 0.0773242 0.357789 -0.930596 + outer loop + vertex 604.345 82.1045 22.9934 + vertex 604.227 82.6772 23.2039 + vertex 604.465 84.0443 23.7492 + endloop + endfacet + facet normal -0.396844 0.39874 -0.826753 + outer loop + vertex 604.465 84.0443 23.7492 + vertex 604.227 82.6772 23.2039 + vertex 604.492 84.4846 23.9487 + endloop + endfacet + facet normal 0.367922 0.365084 -0.855188 + outer loop + vertex 604.465 84.0443 23.7492 + vertex 604.492 84.4846 23.9487 + vertex 604.911 85.8234 24.7006 + endloop + endfacet + facet normal -0.695034 0.505037 -0.511728 + outer loop + vertex 604.911 85.8234 24.7006 + vertex 604.492 84.4846 23.9487 + vertex 604.966 86.1139 24.9126 + endloop + endfacet + facet normal -0.226818 -0.215688 0.949754 + outer loop + vertex 604.654 78.0509 21.9864 + vertex 604.839 77.6302 21.935 + vertex 604.52 79.9723 22.3906 + endloop + endfacet + facet normal -0.332149 0.136337 -0.933322 + outer loop + vertex 604.52 79.9723 22.3906 + vertex 604.839 77.6302 21.935 + vertex 604.371 80.2955 22.491 + endloop + endfacet + facet normal -0.0703102 0.266013 -0.961402 + outer loop + vertex 604.52 79.9723 22.3906 + vertex 604.371 80.2955 22.491 + vertex 604.345 82.1045 22.9934 + endloop + endfacet + facet normal -0.413025 0.238194 -0.879019 + outer loop + vertex 604.345 82.1045 22.9934 + vertex 604.371 80.2955 22.491 + vertex 604.227 82.6772 23.2039 + endloop + endfacet + facet normal -0.303557 0.441909 -0.844138 + outer loop + vertex 607.252 54.5074 15.9394 + vertex 606.987 54.7742 16.1742 + vertex 606.987 56.4424 17.0476 + endloop + endfacet + facet normal -0.23576 0.450725 -0.860967 + outer loop + vertex 606.987 56.4424 17.0476 + vertex 606.987 54.7742 16.1742 + vertex 606.727 56.581 17.1914 + endloop + endfacet + facet normal -0.314918 0.331607 -0.889305 + outer loop + vertex 606.987 56.4424 17.0476 + vertex 606.727 56.581 17.1914 + vertex 606.59 58.4387 17.9324 + endloop + endfacet + facet normal -0.994456 -0.0928498 0.049366 + outer loop + vertex 606.59 58.4387 17.9324 + vertex 606.727 56.581 17.1914 + vertex 606.633 57.9101 17.789 + endloop + endfacet + facet normal -0.70138 0.534442 -0.471633 + outer loop + vertex 607.343 51.5102 13.0834 + vertex 607.238 51.6375 13.3827 + vertex 607.299 52.8162 14.6282 + endloop + endfacet + facet normal -0.105393 0.724837 -0.680812 + outer loop + vertex 607.299 52.8162 14.6282 + vertex 607.238 51.6375 13.3827 + vertex 607.153 53.0465 14.8959 + endloop + endfacet + facet normal -0.454905 0.537659 -0.709919 + outer loop + vertex 607.299 52.8162 14.6282 + vertex 607.153 53.0465 14.8959 + vertex 607.252 54.5074 15.9394 + endloop + endfacet + facet normal -0.125733 0.582204 -0.803262 + outer loop + vertex 607.252 54.5074 15.9394 + vertex 607.153 53.0465 14.8959 + vertex 606.987 54.7742 16.1742 + endloop + endfacet + facet normal -0.900149 0.428238 -0.0796523 + outer loop + vertex 607.473 50.5088 9.41465 + vertex 607.388 50.3966 9.76728 + vertex 607.407 50.7226 11.3132 + endloop + endfacet + facet normal -0.579779 0.798597 -0.161555 + outer loop + vertex 607.407 50.7226 11.3132 + vertex 607.388 50.3966 9.76728 + vertex 607.318 50.7256 11.646 + endloop + endfacet + facet normal -0.859923 0.454104 -0.23307 + outer loop + vertex 607.407 50.7226 11.3132 + vertex 607.318 50.7256 11.646 + vertex 607.343 51.5102 13.0834 + endloop + endfacet + facet normal -0.278464 0.845049 -0.456454 + outer loop + vertex 607.343 51.5102 13.0834 + vertex 607.318 50.7256 11.646 + vertex 607.238 51.6375 13.3827 + endloop + endfacet + facet normal -0.876575 0.400074 0.267502 + outer loop + vertex 607.397 51.8939 5.87506 + vertex 607.341 51.4834 6.3027 + vertex 607.462 50.913 7.55344 + endloop + endfacet + facet normal -0.523811 0.754708 0.395018 + outer loop + vertex 607.462 50.913 7.55344 + vertex 607.341 51.4834 6.3027 + vertex 607.397 50.6657 7.94029 + endloop + endfacet + facet normal -0.921984 0.377245 0.0873605 + outer loop + vertex 607.462 50.913 7.55344 + vertex 607.397 50.6657 7.94029 + vertex 607.473 50.5088 9.41465 + endloop + endfacet + facet normal -0.584475 0.803163 0.115403 + outer loop + vertex 607.473 50.5088 9.41465 + vertex 607.397 50.6657 7.94029 + vertex 607.388 50.3966 9.76728 + endloop + endfacet + facet normal -0.916525 0.0204215 0.399457 + outer loop + vertex 606.784 55.2765 3.34502 + vertex 606.972 54.2088 3.83205 + vertex 607.234 53.3469 4.47549 + endloop + endfacet + facet normal -0.117627 0.570946 0.812517 + outer loop + vertex 607.234 53.3469 4.47549 + vertex 606.972 54.2088 3.83205 + vertex 607.197 52.7702 4.87537 + endloop + endfacet + facet normal -0.76734 0.397898 0.502858 + outer loop + vertex 607.234 53.3469 4.47549 + vertex 607.197 52.7702 4.87537 + vertex 607.397 51.8939 5.87506 + endloop + endfacet + facet normal -0.179762 0.721542 0.668628 + outer loop + vertex 607.397 51.8939 5.87506 + vertex 607.197 52.7702 4.87537 + vertex 607.341 51.4834 6.3027 + endloop + endfacet + facet normal 0.0670338 -0.198958 -0.977713 + outer loop + vertex 507.685 32.1149 2.03299 + vertex 507.098 34.852 1.43578 + vertex 512.413 33.4434 2.08679 + endloop + endfacet + facet normal 0.0947499 -0.298729 -0.949623 + outer loop + vertex 508.438 29.5567 2.9129 + vertex 507.685 32.1149 2.03299 + vertex 512.413 33.4434 2.08679 + endloop + endfacet + facet normal -0.0374778 -0.446065 -0.894216 + outer loop + vertex 509.171 27.208 4.05384 + vertex 508.438 29.5567 2.9129 + vertex 509.511 28.0565 3.6163 + endloop + endfacet + facet normal 0.111664 -0.61136 -0.783435 + outer loop + vertex 509.214 25.4997 5.39314 + vertex 509.171 27.208 4.05384 + vertex 509.719 26.8895 4.38047 + endloop + endfacet + facet normal 0.182754 -0.776683 -0.602797 + outer loop + vertex 509.172 24.2596 6.97821 + vertex 509.214 25.4997 5.39314 + vertex 509.749 25.3787 5.71105 + endloop + endfacet + facet normal 0.216893 -0.914887 -0.340497 + outer loop + vertex 509.195 23.6025 8.75831 + vertex 509.172 24.2596 6.97821 + vertex 509.798 24.2725 7.3425 + endloop + endfacet + facet normal 0.243888 -0.968028 -0.0586627 + outer loop + vertex 509.292 23.534 10.2934 + vertex 509.195 23.6025 8.75831 + vertex 509.815 23.7382 9.09716 + endloop + endfacet + facet normal 0.235073 -0.935776 0.262798 + outer loop + vertex 509.196 23.9317 11.7953 + vertex 509.292 23.534 10.2934 + vertex 509.784 23.8167 10.8606 + endloop + endfacet + facet normal 0.134926 -0.859149 0.493618 + outer loop + vertex 509.27 24.9242 13.5029 + vertex 509.196 23.9317 11.7953 + vertex 509.793 24.4921 12.6077 + endloop + endfacet + facet normal 0.0610938 -0.719071 0.692246 + outer loop + vertex 509.412 26.4192 15.0432 + vertex 509.27 24.9242 13.5029 + vertex 509.848 25.6977 14.2552 + endloop + endfacet + facet normal 0.0334914 -0.566292 0.823524 + outer loop + vertex 509.226 28.4228 16.4285 + vertex 509.412 26.4192 15.0432 + vertex 509.874 27.3951 15.6954 + endloop + endfacet + facet normal 0.0578056 -0.424117 0.90376 + outer loop + vertex 507.791 31.0352 17.7462 + vertex 509.226 28.4228 16.4285 + vertex 509.722 29.579 16.9394 + endloop + endfacet + facet normal 0.056195 -0.302386 0.951528 + outer loop + vertex 507.658 35.3077 19.1118 + vertex 507.791 31.0352 17.7462 + vertex 509.884 32.2471 18.0077 + endloop + endfacet + facet normal 0.0555636 -0.246441 0.967564 + outer loop + vertex 505.761 40.6922 20.5922 + vertex 507.658 35.3077 19.1118 + vertex 512.618 39.1607 19.8084 + endloop + endfacet + facet normal 0.0954574 -0.228427 0.96887 + outer loop + vertex 505.992 51.7297 23.1001 + vertex 506.551 47.0265 21.9362 + vertex 508.244 50.7454 22.6461 + endloop + endfacet + facet normal 0.153331 -0.331335 0.930971 + outer loop + vertex 506.835 54.6873 24.0138 + vertex 505.992 51.7297 23.1001 + vertex 507.375 53.1213 23.3676 + endloop + endfacet + facet normal 0.35452 -0.387473 0.850988 + outer loop + vertex 506.267 57.0964 25.3476 + vertex 506.835 54.6873 24.0138 + vertex 506.879 55.2957 24.2724 + endloop + endfacet + facet normal 0.31344 -0.513599 0.798731 + outer loop + vertex 505.196 59.4283 27.2672 + vertex 506.267 57.0964 25.3476 + vertex 506.119 58.5975 26.3709 + endloop + endfacet + facet normal 0.252889 -0.620696 0.742148 + outer loop + vertex 503.135 61.4576 29.6666 + vertex 505.196 59.4283 27.2672 + vertex 505.377 60.3752 27.9975 + endloop + endfacet + facet normal 0.154395 -0.760272 0.630991 + outer loop + vertex 500.454 63.7901 33.1332 + vertex 503.135 61.4576 29.6666 + vertex 506.214 64.1879 32.2029 + endloop + endfacet + facet normal 0.14634 -0.806403 0.572973 + outer loop + vertex 499.375 65.9509 36.4498 + vertex 500.454 63.7901 33.1332 + vertex 506.082 66.3319 35.273 + endloop + endfacet + facet normal 0.144863 -0.92391 0.354125 + outer loop + vertex 507.534 69.4992 40.521 + vertex 503.615 68.9543 40.7024 + vertex 506.457 69.0406 39.7648 + endloop + endfacet + facet normal 0.180433 -0.982697 -0.0418298 + outer loop + vertex 522.129 71.9823 40.0087 + vertex 517.287 71.0875 40.1429 + vertex 524.54 72.4415 39.6209 + endloop + endfacet + facet normal 0.213574 -0.954376 0.208692 + outer loop + vertex 534.272 74.7152 40.2144 + vertex 528.157 73.3329 40.1507 + vertex 536.904 75.1334 39.4336 + endloop + endfacet + facet normal 0.226369 -0.93863 0.26025 + outer loop + vertex 541.084 76.3403 40.1508 + vertex 534.272 74.7152 40.2144 + vertex 536.904 75.1334 39.4336 + endloop + endfacet + facet normal 0.23031 -0.952745 0.198076 + outer loop + vertex 547.623 77.8659 39.8848 + vertex 541.084 76.3403 40.1508 + vertex 549.947 78.2557 39.0584 + endloop + endfacet + facet normal 0.250958 -0.930561 0.266601 + outer loop + vertex 554.388 79.6388 39.7053 + vertex 547.623 77.8659 39.8848 + vertex 549.947 78.2557 39.0584 + endloop + endfacet + facet normal 0.255983 -0.938073 0.233436 + outer loop + vertex 560.755 81.2946 39.3771 + vertex 554.388 79.6388 39.7053 + vertex 562.956 81.6895 38.5507 + endloop + endfacet + facet normal 0.271483 -0.91975 0.283472 + outer loop + vertex 567.347 83.1508 39.087 + vertex 560.755 81.2946 39.3771 + vertex 562.956 81.6895 38.5507 + endloop + endfacet + facet normal 0.274399 -0.932353 0.235422 + outer loop + vertex 573.491 84.8492 38.6513 + vertex 567.347 83.1508 39.087 + vertex 575.664 85.313 37.9558 + endloop + endfacet + facet normal 0.286946 -0.913985 0.286868 + outer loop + vertex 579.711 86.6942 38.3082 + vertex 573.491 84.8492 38.6513 + vertex 575.664 85.313 37.9558 + endloop + endfacet + facet normal 0.303418 -0.906307 0.294186 + outer loop + vertex 595.822 91.5103 37.0237 + vertex 591.631 90.197 37.3007 + vertex 595.798 91.4215 36.7747 + endloop + endfacet + facet normal 0.306368 -0.807896 0.503431 + outer loop + vertex 608.22 92.6045 30.9375 + vertex 609.687 94.6868 33.3865 + vertex 607.664 93.5097 32.7286 + endloop + endfacet + facet normal 0.267403 -0.769222 0.580338 + outer loop + vertex 606.665 89.7983 27.9344 + vertex 608.22 92.6045 30.9375 + vertex 606.531 91.0863 29.7032 + endloop + endfacet + facet normal -0.865304 -0.0283761 0.500443 + outer loop + vertex 605.484 87.1402 25.7413 + vertex 606.665 89.7983 27.9344 + vertex 605.775 88.065 26.2973 + endloop + endfacet + facet normal -0.748415 -0.144824 0.647225 + outer loop + vertex 604.48 84.2362 23.9307 + vertex 605.484 87.1402 25.7413 + vertex 604.966 86.1139 24.9126 + endloop + endfacet + facet normal -0.766678 -0.164994 0.62047 + outer loop + vertex 604.173 81.3065 22.7723 + vertex 604.48 84.2362 23.9307 + vertex 604.227 82.6772 23.2039 + endloop + endfacet + facet normal -0.176972 -0.295843 0.9387 + outer loop + vertex 605.253 78.4326 22.0703 + vertex 604.173 81.3065 22.7723 + vertex 604.371 80.2955 22.491 + endloop + endfacet + facet normal 0.00194761 -0.167244 0.985914 + outer loop + vertex 606.365 74.1372 21.3394 + vertex 605.253 78.4326 22.0703 + vertex 604.839 77.6302 21.935 + endloop + endfacet + facet normal 0.0498532 -0.156988 0.986341 + outer loop + vertex 607.043 68.9257 20.4756 + vertex 606.365 74.1372 21.3394 + vertex 604.537 71.2998 20.9802 + endloop + endfacet + facet normal 0.0638474 -0.197403 0.978241 + outer loop + vertex 607.219 64.2499 19.5206 + vertex 607.043 68.9257 20.4756 + vertex 604.688 66.596 20.1593 + endloop + endfacet + facet normal 0.0808038 -0.255604 0.963399 + outer loop + vertex 607.141 59.7866 18.343 + vertex 607.219 64.2499 19.5206 + vertex 605.337 61.7171 19.0065 + endloop + endfacet + facet normal 0.339127 -0.349757 0.873306 + outer loop + vertex 606.694 57.1107 17.445 + vertex 607.141 59.7866 18.343 + vertex 606.633 57.9101 17.789 + endloop + endfacet + facet normal 0.997671 0.0674158 -0.0104233 + outer loop + vertex 606.811 55.2238 16.4809 + vertex 606.694 57.1107 17.445 + vertex 606.727 56.581 17.1914 + endloop + endfacet + facet normal 0.0248057 0.569924 -0.821323 + outer loop + vertex 607.027 53.4464 15.2541 + vertex 606.811 55.2238 16.4809 + vertex 606.987 54.7742 16.1742 + endloop + endfacet + facet normal 0.236063 0.688478 -0.685764 + outer loop + vertex 607.178 51.9227 13.7761 + vertex 607.027 53.4464 15.2541 + vertex 607.153 53.0465 14.8959 + endloop + endfacet + facet normal 0.706952 0.619977 -0.340364 + outer loop + vertex 607.29 50.8582 12.0699 + vertex 607.178 51.9227 13.7761 + vertex 607.238 51.6375 13.3827 + endloop + endfacet + facet normal 0.89612 0.437059 -0.0771275 + outer loop + vertex 607.365 50.3736 10.2009 + vertex 607.29 50.8582 12.0699 + vertex 607.318 50.7256 11.646 + endloop + endfacet + facet normal 0.711747 0.698444 0.074776 + outer loop + vertex 607.393 50.5475 8.31232 + vertex 607.365 50.3736 10.2009 + vertex 607.388 50.3966 9.76728 + endloop + endfacet + facet normal 0.442248 0.853279 0.276282 + outer loop + vertex 607.297 51.0689 6.85587 + vertex 607.393 50.5475 8.31232 + vertex 607.397 50.6657 7.94029 + endloop + endfacet + facet normal 0.173579 0.781498 0.599276 + outer loop + vertex 607.205 52.127 5.50285 + vertex 607.297 51.0689 6.85587 + vertex 607.341 51.4834 6.3027 + endloop + endfacet + facet normal 0.581355 0.571805 0.578849 + outer loop + vertex 606.941 53.7521 4.16221 + vertex 607.205 52.127 5.50285 + vertex 607.197 52.7702 4.87537 + endloop + endfacet + facet normal 0.61326 0.434646 0.659541 + outer loop + vertex 606.626 55.8598 3.066 + vertex 606.941 53.7521 4.16221 + vertex 606.972 54.2088 3.83205 + endloop + endfacet + facet normal 0.036853 -0.290809 -0.956071 + outer loop + vertex 607.203 58.4947 2.28677 + vertex 606.626 55.8598 3.066 + vertex 606.004 58.4078 2.26695 + endloop + endfacet + facet normal 0.031169 -0.207379 -0.977764 + outer loop + vertex 607.273 62.3069 1.48044 + vertex 607.203 58.4947 2.28677 + vertex 606.004 58.4078 2.26695 + endloop + endfacet + facet normal 0.180035 -0.622081 0.761973 + outer loop + vertex 506.119 58.5975 26.3709 + vertex 505.377 60.3752 27.9975 + vertex 505.196 59.4283 27.2672 + endloop + endfacet + facet normal 0.21381 -0.663212 0.717241 + outer loop + vertex 505.377 60.3752 27.9975 + vertex 505.114 61.4706 29.0889 + vertex 503.135 61.4576 29.6666 + endloop + endfacet + facet normal 0.185751 -0.76319 0.618901 + outer loop + vertex 505.114 61.4706 29.0889 + vertex 506.407 62.4306 29.8845 + vertex 503.135 61.4576 29.6666 + endloop + endfacet + facet normal 0.328921 -0.399102 0.855879 + outer loop + vertex 506.879 55.2957 24.2724 + vertex 506.559 56.9305 25.158 + vertex 506.267 57.0964 25.3476 + endloop + endfacet + facet normal 0.226241 -0.533346 0.815081 + outer loop + vertex 506.559 56.9305 25.158 + vertex 506.119 58.5975 26.3709 + vertex 506.267 57.0964 25.3476 + endloop + endfacet + facet normal 0.0788022 -0.263151 0.961531 + outer loop + vertex 508.244 50.7454 22.6461 + vertex 507.375 53.1213 23.3676 + vertex 505.992 51.7297 23.1001 + endloop + endfacet + facet normal -0.027551 -0.389395 0.920659 + outer loop + vertex 507.375 53.1213 23.3676 + vertex 506.879 55.2957 24.2724 + vertex 506.835 54.6873 24.0138 + endloop + endfacet + facet normal 0.218936 -0.471356 0.854336 + outer loop + vertex 509.874 27.3951 15.6954 + vertex 509.722 29.579 16.9394 + vertex 509.226 28.4228 16.4285 + endloop + endfacet + facet normal 0.102091 -0.375138 0.92133 + outer loop + vertex 509.722 29.579 16.9394 + vertex 509.884 32.2471 18.0077 + vertex 507.791 31.0352 17.7462 + endloop + endfacet + facet normal 0.0699637 -0.308758 0.948564 + outer loop + vertex 509.884 32.2471 18.0077 + vertex 511.666 32.1383 17.8409 + vertex 512.08 34.872 18.7002 + endloop + endfacet + facet normal 0.31086 -0.77198 0.554449 + outer loop + vertex 509.793 24.4921 12.6077 + vertex 509.848 25.6977 14.2552 + vertex 509.27 24.9242 13.5029 + endloop + endfacet + facet normal 0.286364 -0.622402 0.728431 + outer loop + vertex 509.848 25.6977 14.2552 + vertex 509.874 27.3951 15.6954 + vertex 509.412 26.4192 15.0432 + endloop + endfacet + facet normal 0.456256 -0.888567 0.0477358 + outer loop + vertex 509.815 23.7382 9.09716 + vertex 509.784 23.8167 10.8606 + vertex 509.292 23.534 10.2934 + endloop + endfacet + facet normal 0.361932 -0.87015 0.334431 + outer loop + vertex 509.784 23.8167 10.8606 + vertex 509.793 24.4921 12.6077 + vertex 509.196 23.9317 11.7953 + endloop + endfacet + facet normal 0.328329 -0.777109 -0.536938 + outer loop + vertex 509.749 25.3787 5.71105 + vertex 509.798 24.2725 7.3425 + vertex 509.172 24.2596 6.97821 + endloop + endfacet + facet normal 0.347019 -0.896261 -0.276214 + outer loop + vertex 509.798 24.2725 7.3425 + vertex 509.815 23.7382 9.09716 + vertex 509.195 23.6025 8.75831 + endloop + endfacet + facet normal 0.106331 -0.35882 -0.927331 + outer loop + vertex 510.53 29.0661 3.34258 + vertex 509.511 28.0565 3.6163 + vertex 508.438 29.5567 2.9129 + endloop + endfacet + facet normal 0.200876 -0.511331 -0.835577 + outer loop + vertex 509.511 28.0565 3.6163 + vertex 509.719 26.8895 4.38047 + vertex 509.171 27.208 4.05384 + endloop + endfacet + facet normal 0.286698 -0.629956 -0.721775 + outer loop + vertex 509.719 26.8895 4.38047 + vertex 509.749 25.3787 5.71105 + vertex 509.214 25.4997 5.39314 + endloop + endfacet + facet normal 0.167491 -0.930457 0.325878 + outer loop + vertex 506.457 69.0406 39.7648 + vertex 513.922 70.392 39.7872 + vertex 507.534 69.4992 40.521 + endloop + endfacet + facet normal 0.147916 -0.807843 0.570536 + outer loop + vertex 506.214 64.1879 32.2029 + vertex 506.082 66.3319 35.273 + vertex 500.454 63.7901 33.1332 + endloop + endfacet + facet normal 0.190235 -0.774709 0.603023 + outer loop + vertex 506.407 62.4306 29.8845 + vertex 506.214 64.1879 32.2029 + vertex 503.135 61.4576 29.6666 + endloop + endfacet + facet normal 0.117935 -0.320376 -0.939921 + outer loop + vertex 512.413 33.4434 2.08679 + vertex 510.53 29.0661 3.34258 + vertex 508.438 29.5567 2.9129 + endloop + endfacet + facet normal 0.0681797 -0.194969 -0.978437 + outer loop + vertex 512.75 38.6877 1.06526 + vertex 512.413 33.4434 2.08679 + vertex 507.098 34.852 1.43578 + endloop + endfacet + facet normal 0.190023 -0.975627 0.109741 + outer loop + vertex 513.922 70.392 39.7872 + vertex 524.54 72.4415 39.6209 + vertex 517.287 71.0875 40.1429 + endloop + endfacet + facet normal 0.212086 -0.962188 0.170919 + outer loop + vertex 524.54 72.4415 39.6209 + vertex 536.904 75.1334 39.4336 + vertex 528.157 73.3329 40.1507 + endloop + endfacet + facet normal 0.232745 -0.944304 0.232638 + outer loop + vertex 536.904 75.1334 39.4336 + vertex 549.947 78.2557 39.0584 + vertex 541.084 76.3403 40.1508 + endloop + endfacet + facet normal 0.256481 -0.936129 0.240583 + outer loop + vertex 549.947 78.2557 39.0584 + vertex 562.956 81.6895 38.5507 + vertex 554.388 79.6388 39.7053 + endloop + endfacet + facet normal 0.275982 -0.925034 0.261046 + outer loop + vertex 562.956 81.6895 38.5507 + vertex 575.664 85.313 37.9558 + vertex 567.347 83.1508 39.087 + endloop + endfacet + facet normal 0.2897 -0.91798 0.2709 + outer loop + vertex 575.664 85.313 37.9558 + vertex 587.426 88.8346 37.3104 + vertex 579.711 86.6942 38.3082 + endloop + endfacet + facet normal 0.300756 -0.926538 0.225996 + outer loop + vertex 587.426 88.8346 37.3104 + vertex 595.798 91.4215 36.7747 + vertex 591.631 90.197 37.3007 + endloop + endfacet + facet normal 0.270774 -0.786345 0.555286 + outer loop + vertex 596.406 88.3374 31.0043 + vertex 598.16 86.8985 28.1115 + vertex 601.812 88.0714 27.9914 + endloop + endfacet + facet normal 0.086918 -0.2893 0.953284 + outer loop + vertex 595.365 58.0088 18.8107 + vertex 598.942 55.8121 17.8179 + vertex 602.26 57.1386 17.9179 + endloop + endfacet + facet normal 0.0959853 -0.31366 -0.944672 + outer loop + vertex 596.862 52.3463 3.35926 + vertex 597.087 55.1227 2.46028 + vertex 600.922 54.1335 3.17838 + endloop + endfacet + facet normal 0.0581193 -0.211986 -0.975543 + outer loop + vertex 597.087 55.1227 2.46028 + vertex 596.71 59.819 1.41729 + vertex 602.908 58.2316 2.13151 + endloop + endfacet + facet normal 0.269225 -0.758497 0.593464 + outer loop + vertex 601.812 88.0714 27.9914 + vertex 604.573 88.5021 27.2895 + vertex 603.773 89.7933 29.3028 + endloop + endfacet + facet normal 0.0962562 -0.286747 0.953158 + outer loop + vertex 602.26 57.1386 17.9179 + vertex 605.197 57.5912 17.7575 + vertex 602.23 60.0924 18.8096 + endloop + endfacet + facet normal 0.0925907 -0.28833 -0.953044 + outer loop + vertex 604.145 54.8888 3.26299 + vertex 600.922 54.1335 3.17838 + vertex 602.908 58.2316 2.13151 + endloop + endfacet + facet normal 0.341789 -0.791752 0.50627 + outer loop + vertex 607.664 93.5097 32.7286 + vertex 606.531 91.0863 29.7032 + vertex 608.22 92.6045 30.9375 + endloop + endfacet + facet normal 0.253124 -0.77286 0.581907 + outer loop + vertex 606.531 91.0863 29.7032 + vertex 606.24 89.1546 27.2642 + vertex 606.665 89.7983 27.9344 + endloop + endfacet + facet normal 0.036548 -0.170673 0.98465 + outer loop + vertex 604.537 71.2998 20.9802 + vertex 604.688 66.596 20.1593 + vertex 607.043 68.9257 20.4756 + endloop + endfacet + facet normal 0.0277634 -0.301614 0.953026 + outer loop + vertex 605.337 61.7171 19.0065 + vertex 606.59 58.4387 17.9324 + vertex 607.141 59.7866 18.343 + endloop + endfacet + facet normal -0.969884 -0.188691 0.154015 + outer loop + vertex 606.784 55.2765 3.34502 + vertex 606.004 58.4078 2.26695 + vertex 606.626 55.8598 3.066 + endloop + endfacet + facet normal 0.0627028 -0.195507 -0.978696 + outer loop + vertex 602.347 63.0779 1.12745 + vertex 602.908 58.2316 2.13151 + vertex 596.71 59.819 1.41729 + endloop + endfacet + facet normal 0.0408788 -0.210339 -0.976773 + outer loop + vertex 606.004 58.4078 2.26695 + vertex 604.987 62.684 1.30359 + vertex 607.273 62.3069 1.48044 + endloop + endfacet + facet normal -0.724588 -0.172925 0.667135 + outer loop + vertex 605.775 88.065 26.2973 + vertex 604.966 86.1139 24.9126 + vertex 605.484 87.1402 25.7413 + endloop + endfacet + facet normal 0.40927 -0.77365 0.483698 + outer loop + vertex 606.24 89.1546 27.2642 + vertex 606.21 88.9774 27.0062 + vertex 606.665 89.7983 27.9344 + endloop + endfacet + facet normal -0.935694 0.288157 0.203573 + outer loop + vertex 606.21 88.9774 27.0062 + vertex 605.775 88.065 26.2973 + vertex 606.665 89.7983 27.9344 + endloop + endfacet + facet normal -0.959201 0.0241746 0.281689 + outer loop + vertex 604.492 84.4846 23.9487 + vertex 604.227 82.6772 23.2039 + vertex 604.48 84.2362 23.9307 + endloop + endfacet + facet normal -0.904593 0.0111931 0.426129 + outer loop + vertex 604.966 86.1139 24.9126 + vertex 604.492 84.4846 23.9487 + vertex 604.48 84.2362 23.9307 + endloop + endfacet + facet normal 0.0566261 -0.194347 0.979297 + outer loop + vertex 604.371 80.2955 22.491 + vertex 604.839 77.6302 21.935 + vertex 605.253 78.4326 22.0703 + endloop + endfacet + facet normal 0.146887 0.291749 -0.945149 + outer loop + vertex 604.227 82.6772 23.2039 + vertex 604.371 80.2955 22.491 + vertex 604.173 81.3065 22.7723 + endloop + endfacet + facet normal -0.396852 0.406216 -0.823102 + outer loop + vertex 606.727 56.581 17.1914 + vertex 606.987 54.7742 16.1742 + vertex 606.811 55.2238 16.4809 + endloop + endfacet + facet normal -0.0653115 -0.26621 0.9617 + outer loop + vertex 606.59 58.4387 17.9324 + vertex 606.633 57.9101 17.789 + vertex 607.141 59.7866 18.343 + endloop + endfacet + facet normal -0.943099 -0.189778 0.273035 + outer loop + vertex 606.633 57.9101 17.789 + vertex 606.727 56.581 17.1914 + vertex 606.694 57.1107 17.445 + endloop + endfacet + facet normal -0.822912 0.392031 -0.411252 + outer loop + vertex 607.153 53.0465 14.8959 + vertex 607.238 51.6375 13.3827 + vertex 607.178 51.9227 13.7761 + endloop + endfacet + facet normal -0.508612 0.479922 -0.714835 + outer loop + vertex 606.987 54.7742 16.1742 + vertex 607.153 53.0465 14.8959 + vertex 607.027 53.4464 15.2541 + endloop + endfacet + facet normal -0.996449 0.0682901 -0.0492532 + outer loop + vertex 607.318 50.7256 11.646 + vertex 607.388 50.3966 9.76728 + vertex 607.365 50.3736 10.2009 + endloop + endfacet + facet normal -0.99065 0.0967684 -0.0961734 + outer loop + vertex 607.238 51.6375 13.3827 + vertex 607.318 50.7256 11.646 + vertex 607.29 50.8582 12.0699 + endloop + endfacet + facet normal -0.88565 0.402431 0.231674 + outer loop + vertex 607.397 50.6657 7.94029 + vertex 607.341 51.4834 6.3027 + vertex 607.297 51.0689 6.85587 + endloop + endfacet + facet normal -0.999235 0.0391061 0.000786745 + outer loop + vertex 607.388 50.3966 9.76728 + vertex 607.397 50.6657 7.94029 + vertex 607.393 50.5475 8.31232 + endloop + endfacet + facet normal -0.213754 0.373927 0.90249 + outer loop + vertex 606.972 54.2088 3.83205 + vertex 606.784 55.2765 3.34502 + vertex 606.626 55.8598 3.066 + endloop + endfacet + facet normal -0.00855887 0.586206 0.810117 + outer loop + vertex 607.197 52.7702 4.87537 + vertex 606.972 54.2088 3.83205 + vertex 606.941 53.7521 4.16221 + endloop + endfacet + facet normal -0.6965 0.496622 0.517932 + outer loop + vertex 607.341 51.4834 6.3027 + vertex 607.197 52.7702 4.87537 + vertex 607.205 52.127 5.50285 + endloop + endfacet + facet normal 0.059012 -0.300492 0.951957 + outer loop + vertex 507.658 35.3077 19.1118 + vertex 509.884 32.2471 18.0077 + vertex 512.08 34.872 18.7002 + endloop + endfacet + facet normal 0.284675 -0.764542 0.578304 + outer loop + vertex 596.406 88.3374 31.0043 + vertex 601.812 88.0714 27.9914 + vertex 603.773 89.7933 29.3028 + endloop + endfacet + facet normal 0.0872826 -0.287069 0.953925 + outer loop + vertex 602.23 60.0924 18.8096 + vertex 595.365 58.0088 18.8107 + vertex 602.26 57.1386 17.9179 + endloop + endfacet + facet normal 0.10256 -0.29257 -0.950728 + outer loop + vertex 600.922 54.1335 3.17838 + vertex 597.087 55.1227 2.46028 + vertex 602.908 58.2316 2.13151 + endloop + endfacet + facet normal 0.255442 -0.746693 0.614166 + outer loop + vertex 609.585 93.0617 30.8265 + vertex 608.448 92.1982 30.2492 + vertex 609.504 90.6667 27.9482 + endloop + endfacet + facet normal 0.229817 -0.735648 0.637186 + outer loop + vertex 608.05 92.1642 30.3539 + vertex 607.076 89.4984 27.6271 + vertex 608.448 92.1982 30.2492 + endloop + endfacet + facet normal 0.273611 -0.738068 0.61676 + outer loop + vertex 607.076 89.4984 27.6271 + vertex 609.504 90.6667 27.9482 + vertex 608.448 92.1982 30.2492 + endloop + endfacet + facet normal 0.34574 -0.825899 0.445371 + outer loop + vertex 610.928 95.5395 33.9952 + vertex 609.595 94.1702 32.491 + vertex 610.651 94.9691 33.1526 + endloop + endfacet + facet normal 0.194385 -0.498786 0.844646 + outer loop + vertex 604.873 82.9957 23.2616 + vertex 607.043 84.316 23.5418 + vertex 605.65 85.7738 24.7233 + endloop + endfacet + facet normal 0.14777 -0.533652 0.832694 + outer loop + vertex 605.65 85.7738 24.7233 + vertex 607.043 84.316 23.5418 + vertex 608.074 87.2646 25.2486 + endloop + endfacet + facet normal 0.246275 -0.652819 0.716363 + outer loop + vertex 605.65 85.7738 24.7233 + vertex 608.074 87.2646 25.2486 + vertex 607.076 89.4984 27.6271 + endloop + endfacet + facet normal 0.223876 -0.661836 0.715439 + outer loop + vertex 607.076 89.4984 27.6271 + vertex 608.074 87.2646 25.2486 + vertex 609.504 90.6667 27.9482 + endloop + endfacet + facet normal 0.158043 -0.522304 0.837986 + outer loop + vertex 607.66 54.1164 15.5898 + vertex 609.584 55.0744 15.824 + vertex 607.451 55.9376 16.7643 + endloop + endfacet + facet normal 0.174224 -0.496082 0.850617 + outer loop + vertex 607.451 55.9376 16.7643 + vertex 609.584 55.0744 15.824 + vertex 609.378 57.0027 16.9908 + endloop + endfacet + facet normal 0.128465 -0.42315 0.896906 + outer loop + vertex 607.451 55.9376 16.7643 + vertex 609.378 57.0027 16.9908 + vertex 607.489 57.7308 17.6048 + endloop + endfacet + facet normal 0.147257 -0.386 0.91067 + outer loop + vertex 607.489 57.7308 17.6048 + vertex 609.378 57.0027 16.9908 + vertex 609.492 59.3042 17.9479 + endloop + endfacet + facet normal 0.242329 -0.779906 0.577082 + outer loop + vertex 608.008 51.3012 12.464 + vertex 609.996 52.1154 12.7296 + vertex 607.853 52.4989 14.1476 + endloop + endfacet + facet normal 0.2659 -0.750679 0.604796 + outer loop + vertex 607.853 52.4989 14.1476 + vertex 609.996 52.1154 12.7296 + vertex 609.818 53.3979 14.3996 + endloop + endfacet + facet normal 0.197141 -0.639218 0.743327 + outer loop + vertex 607.853 52.4989 14.1476 + vertex 609.818 53.3979 14.3996 + vertex 607.66 54.1164 15.5898 + endloop + endfacet + facet normal 0.213824 -0.615021 0.758965 + outer loop + vertex 607.66 54.1164 15.5898 + vertex 609.818 53.3979 14.3996 + vertex 609.584 55.0744 15.824 + endloop + endfacet + facet normal 0.274784 -0.961072 -0.0288772 + outer loop + vertex 608.147 50.7286 8.65495 + vertex 610.193 51.3044 8.95977 + vertex 608.089 50.6533 10.6123 + endloop + endfacet + facet normal 0.329259 -0.94304 0.047579 + outer loop + vertex 608.089 50.6533 10.6123 + vertex 610.193 51.3044 8.95977 + vertex 610.104 51.3706 10.8881 + endloop + endfacet + facet normal 0.27664 -0.903183 0.328224 + outer loop + vertex 608.089 50.6533 10.6123 + vertex 610.104 51.3706 10.8881 + vertex 608.008 51.3012 12.464 + endloop + endfacet + facet normal 0.308769 -0.87529 0.372195 + outer loop + vertex 608.008 51.3012 12.464 + vertex 610.104 51.3706 10.8881 + vertex 609.996 52.1154 12.7296 + endloop + endfacet + facet normal 0.190633 -0.71178 -0.676039 + outer loop + vertex 607.655 53.2149 4.77793 + vertex 609.723 53.28 5.29244 + vertex 607.897 51.5343 6.61573 + endloop + endfacet + facet normal 0.262221 -0.741937 -0.617065 + outer loop + vertex 607.897 51.5343 6.61573 + vertex 609.723 53.28 5.29244 + vertex 610.115 51.957 7.04965 + endloop + endfacet + facet normal 0.244678 -0.891168 -0.382036 + outer loop + vertex 607.897 51.5343 6.61573 + vertex 610.115 51.957 7.04965 + vertex 608.147 50.7286 8.65495 + endloop + endfacet + facet normal 0.300512 -0.898716 -0.319377 + outer loop + vertex 608.147 50.7286 8.65495 + vertex 610.115 51.957 7.04965 + vertex 610.193 51.3044 8.95977 + endloop + endfacet + facet normal 0.19427 -0.391634 -0.899379 + outer loop + vertex 606.835 56.445 2.8404 + vertex 608.323 57.2689 2.80296 + vertex 607.163 55.0505 3.5184 + endloop + endfacet + facet normal 0.178128 -0.385165 -0.905493 + outer loop + vertex 607.163 55.0505 3.5184 + vertex 608.323 57.2689 2.80296 + vertex 609.123 55.1809 3.84856 + endloop + endfacet + facet normal 0.175211 -0.524628 -0.833107 + outer loop + vertex 607.163 55.0505 3.5184 + vertex 609.123 55.1809 3.84856 + vertex 607.655 53.2149 4.77793 + endloop + endfacet + facet normal 0.218505 -0.545582 -0.809071 + outer loop + vertex 607.655 53.2149 4.77793 + vertex 609.123 55.1809 3.84856 + vertex 609.723 53.28 5.29244 + endloop + endfacet + facet normal 0.282724 -0.675838 0.680669 + outer loop + vertex 618.73 95.0761 28.6407 + vertex 616.25 94.1933 28.7943 + vertex 618.713 93.2028 26.7876 + endloop + endfacet + facet normal 0.3163 -0.709483 0.629753 + outer loop + vertex 614.027 94.1136 29.8207 + vertex 613.64 91.8435 27.4579 + vertex 616.25 94.1933 28.7943 + endloop + endfacet + facet normal 0.27297 -0.686493 0.673955 + outer loop + vertex 613.64 91.8435 27.4579 + vertex 618.713 93.2028 26.7876 + vertex 616.25 94.1933 28.7943 + endloop + endfacet + facet normal 0.304554 -0.711327 0.633451 + outer loop + vertex 614.027 94.1136 29.8207 + vertex 611.49 93.2718 30.0952 + vertex 613.64 91.8435 27.4579 + endloop + endfacet + facet normal 0.312217 -0.734543 0.602467 + outer loop + vertex 609.585 93.0617 30.8265 + vertex 609.504 90.6667 27.9482 + vertex 611.49 93.2718 30.0952 + endloop + endfacet + facet normal 0.281415 -0.728899 0.624109 + outer loop + vertex 609.504 90.6667 27.9482 + vertex 613.64 91.8435 27.4579 + vertex 611.49 93.2718 30.0952 + endloop + endfacet + facet normal 0.188609 -0.530531 0.826416 + outer loop + vertex 610.72 85.69 23.5985 + vertex 615.573 87.1794 23.447 + vertex 611.857 88.5958 25.2042 + endloop + endfacet + facet normal 0.202625 -0.507501 0.837488 + outer loop + vertex 611.857 88.5958 25.2042 + vertex 615.573 87.1794 23.447 + vertex 616.81 90.0554 24.8904 + endloop + endfacet + facet normal 0.189413 -0.540654 0.819644 + outer loop + vertex 607.043 84.316 23.5418 + vertex 610.72 85.69 23.5985 + vertex 608.074 87.2646 25.2486 + endloop + endfacet + facet normal 0.196865 -0.532129 0.823458 + outer loop + vertex 608.074 87.2646 25.2486 + vertex 610.72 85.69 23.5985 + vertex 611.857 88.5958 25.2042 + endloop + endfacet + facet normal 0.241723 -0.663488 0.708064 + outer loop + vertex 608.074 87.2646 25.2486 + vertex 611.857 88.5958 25.2042 + vertex 609.504 90.6667 27.9482 + endloop + endfacet + facet normal 0.268241 -0.644217 0.716262 + outer loop + vertex 609.504 90.6667 27.9482 + vertex 611.857 88.5958 25.2042 + vertex 613.64 91.8435 27.4579 + endloop + endfacet + facet normal 0.234438 -0.637762 0.733689 + outer loop + vertex 611.857 88.5958 25.2042 + vertex 616.81 90.0554 24.8904 + vertex 613.64 91.8435 27.4579 + endloop + endfacet + facet normal 0.262148 -0.609476 0.748209 + outer loop + vertex 613.64 91.8435 27.4579 + vertex 616.81 90.0554 24.8904 + vertex 618.713 93.2028 26.7876 + endloop + endfacet + facet normal 0.0912281 -0.295198 0.951071 + outer loop + vertex 609.492 59.3042 17.9479 + vertex 613.634 61.0744 18.1 + vertex 610.157 62.5215 18.8827 + endloop + endfacet + facet normal 0.0934578 -0.287581 0.953186 + outer loop + vertex 618.607 62.2351 17.9626 + vertex 616.662 64.8274 18.9354 + vertex 613.634 61.0744 18.1 + endloop + endfacet + facet normal 0.0944854 -0.288337 0.952856 + outer loop + vertex 616.662 64.8274 18.9354 + vertex 610.157 62.5215 18.8827 + vertex 613.634 61.0744 18.1 + endloop + endfacet + facet normal 0.147366 -0.482319 0.863511 + outer loop + vertex 613.078 56.3392 15.9255 + vertex 617.892 57.8351 15.9396 + vertex 612.985 58.439 17.1143 + endloop + endfacet + facet normal 0.148565 -0.477442 0.866012 + outer loop + vertex 612.985 58.439 17.1143 + vertex 617.892 57.8351 15.9396 + vertex 617.938 59.9802 17.1143 + endloop + endfacet + facet normal 0.155897 -0.499116 0.852396 + outer loop + vertex 609.584 55.0744 15.824 + vertex 613.078 56.3392 15.9255 + vertex 609.378 57.0027 16.9908 + endloop + endfacet + facet normal 0.161906 -0.480708 0.861804 + outer loop + vertex 609.378 57.0027 16.9908 + vertex 613.078 56.3392 15.9255 + vertex 612.985 58.439 17.1143 + endloop + endfacet + facet normal 0.122502 -0.386251 0.914223 + outer loop + vertex 609.378 57.0027 16.9908 + vertex 612.985 58.439 17.1143 + vertex 609.492 59.3042 17.9479 + endloop + endfacet + facet normal 0.12639 -0.374672 0.918502 + outer loop + vertex 609.492 59.3042 17.9479 + vertex 612.985 58.439 17.1143 + vertex 613.634 61.0744 18.1 + endloop + endfacet + facet normal 0.116034 -0.372903 0.920587 + outer loop + vertex 612.985 58.439 17.1143 + vertex 617.938 59.9802 17.1143 + vertex 613.634 61.0744 18.1 + endloop + endfacet + facet normal 0.113888 -0.379249 0.918259 + outer loop + vertex 613.634 61.0744 18.1 + vertex 617.938 59.9802 17.1143 + vertex 618.607 62.2351 17.9626 + endloop + endfacet + facet normal 0.231326 -0.75304 0.615971 + outer loop + vertex 613.513 53.3032 12.8343 + vertex 618.33 54.7828 12.8339 + vertex 613.307 54.606 14.5043 + endloop + endfacet + facet normal 0.230785 -0.754673 0.614172 + outer loop + vertex 613.307 54.606 14.5043 + vertex 618.33 54.7828 12.8339 + vertex 618.12 56.0797 14.5063 + endloop + endfacet + facet normal 0.237895 -0.757943 0.607394 + outer loop + vertex 609.996 52.1154 12.7296 + vertex 613.513 53.3032 12.8343 + vertex 609.818 53.3979 14.3996 + endloop + endfacet + facet normal 0.241401 -0.750486 0.61522 + outer loop + vertex 609.818 53.3979 14.3996 + vertex 613.513 53.3032 12.8343 + vertex 613.307 54.606 14.5043 + endloop + endfacet + facet normal 0.191775 -0.619798 0.760968 + outer loop + vertex 609.818 53.3979 14.3996 + vertex 613.307 54.606 14.5043 + vertex 609.584 55.0744 15.824 + endloop + endfacet + facet normal 0.196958 -0.606002 0.770694 + outer loop + vertex 609.584 55.0744 15.824 + vertex 613.307 54.606 14.5043 + vertex 613.078 56.3392 15.9255 + endloop + endfacet + facet normal 0.185894 -0.608257 0.771665 + outer loop + vertex 613.307 54.606 14.5043 + vertex 618.12 56.0797 14.5063 + vertex 613.078 56.3392 15.9255 + endloop + endfacet + facet normal 0.18629 -0.606708 0.772788 + outer loop + vertex 613.078 56.3392 15.9255 + vertex 618.12 56.0797 14.5063 + vertex 617.892 57.8351 15.9396 + endloop + endfacet + facet normal 0.297026 -0.952292 0.0701078 + outer loop + vertex 613.738 52.4208 9.06766 + vertex 618.557 53.9223 9.04764 + vertex 613.63 52.5286 10.9889 + endloop + endfacet + facet normal 0.29451 -0.953583 0.0627962 + outer loop + vertex 613.63 52.5286 10.9889 + vertex 618.557 53.9223 9.04764 + vertex 618.454 54.0178 10.9805 + endloop + endfacet + facet normal 0.298758 -0.953194 0.046518 + outer loop + vertex 610.193 51.3044 8.95977 + vertex 613.738 52.4208 9.06766 + vertex 610.104 51.3706 10.8881 + endloop + endfacet + facet normal 0.3094 -0.948309 0.0705798 + outer loop + vertex 610.104 51.3706 10.8881 + vertex 613.738 52.4208 9.06766 + vertex 613.63 52.5286 10.9889 + endloop + endfacet + facet normal 0.279681 -0.884214 0.374091 + outer loop + vertex 610.104 51.3706 10.8881 + vertex 613.63 52.5286 10.9889 + vertex 609.996 52.1154 12.7296 + endloop + endfacet + facet normal 0.284774 -0.87728 0.386371 + outer loop + vertex 609.996 52.1154 12.7296 + vertex 613.63 52.5286 10.9889 + vertex 613.513 53.3032 12.8343 + endloop + endfacet + facet normal 0.272609 -0.880824 0.387084 + outer loop + vertex 613.63 52.5286 10.9889 + vertex 618.454 54.0178 10.9805 + vertex 613.513 53.3032 12.8343 + endloop + endfacet + facet normal 0.271278 -0.88318 0.382625 + outer loop + vertex 613.513 53.3032 12.8343 + vertex 618.454 54.0178 10.9805 + vertex 618.33 54.7828 12.8339 + endloop + endfacet + facet normal 0.233561 -0.773557 -0.589117 + outer loop + vertex 613.351 54.1562 5.49751 + vertex 618.241 55.6379 5.49055 + vertex 613.697 52.9663 7.19713 + endloop + endfacet + facet normal 0.240533 -0.778993 -0.579062 + outer loop + vertex 613.697 52.9663 7.19713 + vertex 618.241 55.6379 5.49055 + vertex 618.549 54.4817 7.17423 + endloop + endfacet + facet normal 0.21746 -0.755857 -0.617569 + outer loop + vertex 609.723 53.28 5.29244 + vertex 613.351 54.1562 5.49751 + vertex 610.115 51.957 7.04965 + endloop + endfacet + facet normal 0.24153 -0.771153 -0.589056 + outer loop + vertex 610.115 51.957 7.04965 + vertex 613.351 54.1562 5.49751 + vertex 613.697 52.9663 7.19713 + endloop + endfacet + facet normal 0.269053 -0.907971 -0.321246 + outer loop + vertex 610.115 51.957 7.04965 + vertex 613.697 52.9663 7.19713 + vertex 610.193 51.3044 8.95977 + endloop + endfacet + facet normal 0.296487 -0.915066 -0.273404 + outer loop + vertex 610.193 51.3044 8.95977 + vertex 613.697 52.9663 7.19713 + vertex 613.738 52.4208 9.06766 + endloop + endfacet + facet normal 0.285489 -0.918344 -0.274117 + outer loop + vertex 613.697 52.9663 7.19713 + vertex 618.549 54.4817 7.17423 + vertex 613.738 52.4208 9.06766 + endloop + endfacet + facet normal 0.284956 -0.918164 -0.275274 + outer loop + vertex 613.738 52.4208 9.06766 + vertex 618.549 54.4817 7.17423 + vertex 618.557 53.9223 9.04764 + endloop + endfacet + facet normal 0.101371 -0.402864 -0.909629 + outer loop + vertex 612.213 58.4572 2.87753 + vertex 616.364 58.998 3.10056 + vertex 612.648 55.8808 4.06705 + endloop + endfacet + facet normal 0.124022 -0.425734 -0.896309 + outer loop + vertex 612.648 55.8808 4.06705 + vertex 616.364 58.998 3.10056 + vertex 617.465 57.235 4.09029 + endloop + endfacet + facet normal 0.139555 -0.400095 -0.905786 + outer loop + vertex 608.323 57.2689 2.80296 + vertex 612.213 58.4572 2.87753 + vertex 609.123 55.1809 3.84856 + endloop + endfacet + facet normal 0.134994 -0.39647 -0.908069 + outer loop + vertex 609.123 55.1809 3.84856 + vertex 612.213 58.4572 2.87753 + vertex 612.648 55.8808 4.06705 + endloop + endfacet + facet normal 0.162143 -0.563904 -0.809767 + outer loop + vertex 609.123 55.1809 3.84856 + vertex 612.648 55.8808 4.06705 + vertex 609.723 53.28 5.29244 + endloop + endfacet + facet normal 0.185233 -0.581565 -0.792131 + outer loop + vertex 609.723 53.28 5.29244 + vertex 612.648 55.8808 4.06705 + vertex 613.351 54.1562 5.49751 + endloop + endfacet + facet normal 0.169007 -0.587533 -0.791354 + outer loop + vertex 612.648 55.8808 4.06705 + vertex 617.465 57.235 4.09029 + vertex 613.351 54.1562 5.49751 + endloop + endfacet + facet normal 0.17997 -0.597603 -0.781333 + outer loop + vertex 613.351 54.1562 5.49751 + vertex 617.465 57.235 4.09029 + vertex 618.241 55.6379 5.49055 + endloop + endfacet + facet normal 0.0874254 -0.276255 -0.9571 + outer loop + vertex 616.364 58.998 3.10056 + vertex 612.213 58.4572 2.87753 + vertex 619.221 63.5947 2.03476 + endloop + endfacet + facet normal 0.0979207 -0.260338 -0.960539 + outer loop + vertex 608.323 57.2689 2.80296 + vertex 611.097 61.8438 1.84589 + vertex 612.213 58.4572 2.87753 + endloop + endfacet + facet normal 0.0797381 -0.26634 -0.960575 + outer loop + vertex 611.097 61.8438 1.84589 + vertex 619.221 63.5947 2.03476 + vertex 612.213 58.4572 2.87753 + endloop + endfacet + facet normal 0.0518417 -0.171804 -0.983766 + outer loop + vertex 610.646 66.7451 0.966109 + vertex 617.888 68.1798 1.09723 + vertex 611.097 61.8438 1.84589 + endloop + endfacet + facet normal 0.0621619 -0.182565 -0.981227 + outer loop + vertex 611.097 61.8438 1.84589 + vertex 617.888 68.1798 1.09723 + vertex 619.221 63.5947 2.03476 + endloop + endfacet + facet normal 0.270046 -0.592957 0.758602 + outer loop + vertex 629.897 98.2534 27.0624 + vertex 627.089 97.2468 27.2753 + vertex 629.839 96.422 25.6517 + endloop + endfacet + facet normal 0.287372 -0.639839 0.712758 + outer loop + vertex 624.302 96.687 27.8966 + vertex 624.285 94.8346 26.2405 + vertex 627.089 97.2468 27.2753 + endloop + endfacet + facet normal 0.255108 -0.616214 0.745118 + outer loop + vertex 624.285 94.8346 26.2405 + vertex 629.839 96.422 25.6517 + vertex 627.089 97.2468 27.2753 + endloop + endfacet + facet normal 0.276064 -0.641995 0.715284 + outer loop + vertex 624.302 96.687 27.8966 + vertex 621.417 95.6217 28.0538 + vertex 624.285 94.8346 26.2405 + endloop + endfacet + facet normal 0.28561 -0.675249 0.680048 + outer loop + vertex 618.73 95.0761 28.6407 + vertex 618.713 93.2028 26.7876 + vertex 621.417 95.6217 28.0538 + endloop + endfacet + facet normal 0.262682 -0.661391 0.702539 + outer loop + vertex 618.713 93.2028 26.7876 + vertex 624.285 94.8346 26.2405 + vertex 621.417 95.6217 28.0538 + endloop + endfacet + facet normal 0.16692 -0.464035 0.869948 + outer loop + vertex 621.147 88.8474 23.261 + vertex 626.855 90.6056 23.1037 + vertex 622.336 91.6961 24.5524 + endloop + endfacet + facet normal 0.179979 -0.429712 0.884847 + outer loop + vertex 622.336 91.6961 24.5524 + vertex 626.855 90.6056 23.1037 + vertex 627.949 93.3994 24.238 + endloop + endfacet + facet normal 0.17833 -0.501586 0.846528 + outer loop + vertex 615.573 87.1794 23.447 + vertex 621.147 88.8474 23.261 + vertex 616.81 90.0554 24.8904 + endloop + endfacet + facet normal 0.192412 -0.470658 0.86108 + outer loop + vertex 616.81 90.0554 24.8904 + vertex 621.147 88.8474 23.261 + vertex 622.336 91.6961 24.5524 + endloop + endfacet + facet normal 0.22489 -0.599133 0.768417 + outer loop + vertex 616.81 90.0554 24.8904 + vertex 622.336 91.6961 24.5524 + vertex 618.713 93.2028 26.7876 + endloop + endfacet + facet normal 0.244547 -0.572682 0.782453 + outer loop + vertex 618.713 93.2028 26.7876 + vertex 622.336 91.6961 24.5524 + vertex 624.285 94.8346 26.2405 + endloop + endfacet + facet normal 0.215549 -0.562974 0.797872 + outer loop + vertex 622.336 91.6961 24.5524 + vertex 627.949 93.3994 24.238 + vertex 624.285 94.8346 26.2405 + endloop + endfacet + facet normal 0.237662 -0.529497 0.81434 + outer loop + vertex 624.285 94.8346 26.2405 + vertex 627.949 93.3994 24.238 + vertex 629.839 96.422 25.6517 + endloop + endfacet + facet normal 0.0898899 -0.290101 0.952765 + outer loop + vertex 618.607 62.2351 17.9626 + vertex 623.786 64.2595 18.0904 + vertex 616.662 64.8274 18.9354 + endloop + endfacet + facet normal 0.0905037 -0.281053 0.955415 + outer loop + vertex 629.935 65.7618 17.9498 + vertex 626.552 68.133 18.9678 + vertex 623.786 64.2595 18.0904 + endloop + endfacet + facet normal 0.0908922 -0.281305 0.955304 + outer loop + vertex 626.552 68.133 18.9678 + vertex 616.662 64.8274 18.9354 + vertex 623.786 64.2595 18.0904 + endloop + endfacet + facet normal 0.14787 -0.477645 0.86602 + outer loop + vertex 623.558 59.5234 15.9077 + vertex 629.474 61.3226 15.8899 + vertex 623.556 61.6736 17.094 + endloop + endfacet + facet normal 0.148078 -0.476387 0.866677 + outer loop + vertex 623.556 61.6736 17.094 + vertex 629.474 61.3226 15.8899 + vertex 629.473 63.4899 17.0813 + endloop + endfacet + facet normal 0.147156 -0.47752 0.86621 + outer loop + vertex 617.892 57.8351 15.9396 + vertex 623.558 59.5234 15.9077 + vertex 617.938 59.9802 17.1143 + endloop + endfacet + facet normal 0.147122 -0.477699 0.866117 + outer loop + vertex 617.938 59.9802 17.1143 + vertex 623.558 59.5234 15.9077 + vertex 623.556 61.6736 17.094 + endloop + endfacet + facet normal 0.11789 -0.380112 0.917397 + outer loop + vertex 617.938 59.9802 17.1143 + vertex 623.556 61.6736 17.094 + vertex 618.607 62.2351 17.9626 + endloop + endfacet + facet normal 0.120395 -0.366239 0.922699 + outer loop + vertex 618.607 62.2351 17.9626 + vertex 623.556 61.6736 17.094 + vertex 623.786 64.2595 18.0904 + endloop + endfacet + facet normal 0.114328 -0.366028 0.923554 + outer loop + vertex 623.556 61.6736 17.094 + vertex 629.473 63.4899 17.0813 + vertex 623.786 64.2595 18.0904 + endloop + endfacet + facet normal 0.112577 -0.374688 0.920291 + outer loop + vertex 623.786 64.2595 18.0904 + vertex 629.473 63.4899 17.0813 + vertex 629.935 65.7618 17.9498 + endloop + endfacet + facet normal 0.233636 -0.752464 0.615802 + outer loop + vertex 623.94 56.4497 12.8031 + vertex 629.815 58.2539 12.7784 + vertex 623.747 57.756 14.4724 + endloop + endfacet + facet normal 0.232611 -0.756799 0.610858 + outer loop + vertex 623.747 57.756 14.4724 + vertex 629.815 58.2539 12.7784 + vertex 629.636 59.5475 14.4495 + endloop + endfacet + facet normal 0.227851 -0.755403 0.614369 + outer loop + vertex 618.33 54.7828 12.8339 + vertex 623.94 56.4497 12.8031 + vertex 618.12 56.0797 14.5063 + endloop + endfacet + facet normal 0.228286 -0.753772 0.616209 + outer loop + vertex 618.12 56.0797 14.5063 + vertex 623.94 56.4497 12.8031 + vertex 623.747 57.756 14.4724 + endloop + endfacet + facet normal 0.185465 -0.606872 0.772857 + outer loop + vertex 618.12 56.0797 14.5063 + vertex 623.747 57.756 14.4724 + vertex 617.892 57.8351 15.9396 + endloop + endfacet + facet normal 0.185347 -0.60747 0.772416 + outer loop + vertex 617.892 57.8351 15.9396 + vertex 623.747 57.756 14.4724 + vertex 623.558 59.5234 15.9077 + endloop + endfacet + facet normal 0.187675 -0.607039 0.772193 + outer loop + vertex 623.747 57.756 14.4724 + vertex 629.636 59.5475 14.4495 + vertex 623.558 59.5234 15.9077 + endloop + endfacet + facet normal 0.187405 -0.608582 0.771043 + outer loop + vertex 623.558 59.5234 15.9077 + vertex 629.636 59.5475 14.4495 + vertex 629.474 61.3226 15.8899 + endloop + endfacet + facet normal 0.293361 -0.954784 0.048231 + outer loop + vertex 624.163 55.6483 9.00216 + vertex 630.024 57.4479 8.98034 + vertex 624.07 55.7177 10.9442 + endloop + endfacet + facet normal 0.293389 -0.954771 0.0483293 + outer loop + vertex 624.07 55.7177 10.9442 + vertex 630.024 57.4479 8.98034 + vertex 629.944 57.5218 10.9233 + endloop + endfacet + facet normal 0.294128 -0.953702 0.0627818 + outer loop + vertex 618.557 53.9223 9.04764 + vertex 624.163 55.6483 9.00216 + vertex 618.454 54.0178 10.9805 + endloop + endfacet + facet normal 0.289671 -0.955917 0.048094 + outer loop + vertex 618.454 54.0178 10.9805 + vertex 624.163 55.6483 9.00216 + vertex 624.07 55.7177 10.9442 + endloop + endfacet + facet normal 0.269928 -0.883563 0.382694 + outer loop + vertex 618.454 54.0178 10.9805 + vertex 624.07 55.7177 10.9442 + vertex 618.33 54.7828 12.8339 + endloop + endfacet + facet normal 0.266585 -0.890289 0.369212 + outer loop + vertex 618.33 54.7828 12.8339 + vertex 624.07 55.7177 10.9442 + vertex 623.94 56.4497 12.8031 + endloop + endfacet + facet normal 0.27407 -0.888147 0.368892 + outer loop + vertex 624.07 55.7177 10.9442 + vertex 629.944 57.5218 10.9233 + vertex 623.94 56.4497 12.8031 + endloop + endfacet + facet normal 0.274187 -0.887896 0.369409 + outer loop + vertex 623.94 56.4497 12.8031 + vertex 629.944 57.5218 10.9233 + vertex 629.815 58.2539 12.7784 + endloop + endfacet + facet normal 0.243082 -0.773256 -0.58565 + outer loop + vertex 623.913 57.4525 5.42053 + vertex 629.807 59.3352 5.38142 + vertex 624.177 56.253 7.11386 + endloop + endfacet + facet normal 0.23825 -0.768808 -0.59344 + outer loop + vertex 624.177 56.253 7.11386 + vertex 629.807 59.3352 5.38142 + vertex 630.033 58.0887 7.08693 + endloop + endfacet + facet normal 0.241933 -0.77858 -0.579035 + outer loop + vertex 618.241 55.6379 5.49055 + vertex 623.913 57.4525 5.42053 + vertex 618.549 54.4817 7.17423 + endloop + endfacet + facet normal 0.237594 -0.774787 -0.585879 + outer loop + vertex 618.549 54.4817 7.17423 + vertex 623.913 57.4525 5.42053 + vertex 624.177 56.253 7.11386 + endloop + endfacet + facet normal 0.285967 -0.917874 -0.275191 + outer loop + vertex 618.549 54.4817 7.17423 + vertex 624.177 56.253 7.11386 + vertex 618.557 53.9223 9.04764 + endloop + endfacet + facet normal 0.279353 -0.915034 -0.290989 + outer loop + vertex 618.557 53.9223 9.04764 + vertex 624.177 56.253 7.11386 + vertex 624.163 55.6483 9.00216 + endloop + endfacet + facet normal 0.284986 -0.913468 -0.290446 + outer loop + vertex 624.177 56.253 7.11386 + vertex 630.033 58.0887 7.08693 + vertex 624.163 55.6483 9.00216 + endloop + endfacet + facet normal 0.278354 -0.910217 -0.306632 + outer loop + vertex 624.163 55.6483 9.00216 + vertex 630.033 58.0887 7.08693 + vertex 630.024 57.4479 8.98034 + endloop + endfacet + facet normal 0.113463 -0.406174 -0.906724 + outer loop + vertex 622.215 61.2507 2.92026 + vertex 627.809 62.6029 3.01452 + vertex 623.164 59.053 4.02343 + endloop + endfacet + facet normal 0.130372 -0.425161 -0.895679 + outer loop + vertex 623.164 59.053 4.02343 + vertex 627.809 62.6029 3.01452 + vertex 629.126 60.9897 3.97191 + endloop + endfacet + facet normal 0.134087 -0.420122 -0.897507 + outer loop + vertex 616.364 58.998 3.10056 + vertex 622.215 61.2507 2.92026 + vertex 617.465 57.235 4.09029 + endloop + endfacet + facet normal 0.118306 -0.404213 -0.906981 + outer loop + vertex 617.465 57.235 4.09029 + vertex 622.215 61.2507 2.92026 + vertex 623.164 59.053 4.02343 + endloop + endfacet + facet normal 0.181298 -0.597056 -0.781445 + outer loop + vertex 617.465 57.235 4.09029 + vertex 623.164 59.053 4.02343 + vertex 618.241 55.6379 5.49055 + endloop + endfacet + facet normal 0.181393 -0.597152 -0.781349 + outer loop + vertex 618.241 55.6379 5.49055 + vertex 623.164 59.053 4.02343 + vertex 623.913 57.4525 5.42053 + endloop + endfacet + facet normal 0.186549 -0.595067 -0.781725 + outer loop + vertex 623.164 59.053 4.02343 + vertex 629.126 60.9897 3.97191 + vertex 623.913 57.4525 5.42053 + endloop + endfacet + facet normal 0.183995 -0.592383 -0.784365 + outer loop + vertex 623.913 57.4525 5.42053 + vertex 629.126 60.9897 3.97191 + vertex 629.807 59.3352 5.38142 + endloop + endfacet + facet normal 0.0798408 -0.263272 -0.961412 + outer loop + vertex 627.809 62.6029 3.01452 + vertex 622.215 61.2507 2.92026 + vertex 630.215 66.9558 2.02235 + endloop + endfacet + facet normal 0.0737979 -0.268558 -0.960433 + outer loop + vertex 616.364 58.998 3.10056 + vertex 619.221 63.5947 2.03476 + vertex 622.215 61.2507 2.92026 + endloop + endfacet + facet normal 0.0790981 -0.262283 -0.961744 + outer loop + vertex 619.221 63.5947 2.03476 + vertex 630.215 66.9558 2.02235 + vertex 622.215 61.2507 2.92026 + endloop + endfacet + facet normal 0.0566123 -0.184185 -0.98126 + outer loop + vertex 617.888 68.1798 1.09723 + vertex 628.028 71.1152 1.13124 + vertex 619.221 63.5947 2.03476 + endloop + endfacet + facet normal 0.0544455 -0.181718 -0.981842 + outer loop + vertex 619.221 63.5947 2.03476 + vertex 628.028 71.1152 1.13124 + vertex 630.215 66.9558 2.02235 + endloop + endfacet + facet normal 0.221699 -0.532073 0.817158 + outer loop + vertex 634.988 97.6077 24.953 + vertex 639.877 99.0577 24.5705 + vertex 636.685 99.8059 25.9238 + endloop + endfacet + facet normal 0.23192 -0.509362 0.828712 + outer loop + vertex 636.685 99.8059 25.9238 + vertex 639.877 99.0577 24.5705 + vertex 641.019 101.135 25.5274 + endloop + endfacet + facet normal 0.24848 -0.545397 0.8005 + outer loop + vertex 636.685 99.8059 25.9238 + vertex 632.754 98.7522 26.426 + vertex 634.988 97.6077 24.953 + endloop + endfacet + facet normal 0.272323 -0.592611 0.758058 + outer loop + vertex 629.897 98.2534 27.0624 + vertex 629.839 96.422 25.6517 + vertex 632.754 98.7522 26.426 + endloop + endfacet + facet normal 0.236703 -0.55998 0.793974 + outer loop + vertex 629.839 96.422 25.6517 + vertex 634.988 97.6077 24.953 + vertex 632.754 98.7522 26.426 + endloop + endfacet + facet normal 0.14398 -0.378441 0.914359 + outer loop + vertex 632.45 92.35 22.9568 + vertex 638.027 94.1228 22.8123 + vertex 633.413 95.0201 23.9103 + endloop + endfacet + facet normal 0.154295 -0.341169 0.927252 + outer loop + vertex 633.413 95.0201 23.9103 + vertex 638.027 94.1228 22.8123 + vertex 638.723 96.6459 23.6249 + endloop + endfacet + facet normal 0.155393 -0.423235 0.892595 + outer loop + vertex 626.855 90.6056 23.1037 + vertex 632.45 92.35 22.9568 + vertex 627.949 93.3994 24.238 + endloop + endfacet + facet normal 0.168574 -0.384844 0.907457 + outer loop + vertex 627.949 93.3994 24.238 + vertex 632.45 92.35 22.9568 + vertex 633.413 95.0201 23.9103 + endloop + endfacet + facet normal 0.202997 -0.516131 0.832106 + outer loop + vertex 627.949 93.3994 24.238 + vertex 633.413 95.0201 23.9103 + vertex 629.839 96.422 25.6517 + endloop + endfacet + facet normal 0.225446 -0.47906 0.848337 + outer loop + vertex 629.839 96.422 25.6517 + vertex 633.413 95.0201 23.9103 + vertex 634.988 97.6077 24.953 + endloop + endfacet + facet normal 0.18847 -0.463581 0.865778 + outer loop + vertex 633.413 95.0201 23.9103 + vertex 638.723 96.6459 23.6249 + vertex 634.988 97.6077 24.953 + endloop + endfacet + facet normal 0.198648 -0.438717 0.876394 + outer loop + vertex 634.988 97.6077 24.953 + vertex 638.723 96.6459 23.6249 + vertex 639.877 99.0577 24.5705 + endloop + endfacet + facet normal 0.0879127 -0.284425 0.954659 + outer loop + vertex 629.935 65.7618 17.9498 + vertex 635.294 67.8977 18.0927 + vertex 626.552 68.133 18.9678 + endloop + endfacet + facet normal 0.090656 -0.275425 0.957039 + outer loop + vertex 641.521 69.4547 17.9509 + vertex 637.781 71.7835 18.9754 + vertex 635.294 67.8977 18.0927 + endloop + endfacet + facet normal 0.0884837 -0.274163 0.957604 + outer loop + vertex 637.781 71.7835 18.9754 + vertex 626.552 68.133 18.9678 + vertex 635.294 67.8977 18.0927 + endloop + endfacet + facet normal 0.153636 -0.475877 0.865989 + outer loop + vertex 635.329 63.164 15.8867 + vertex 641.019 65.0015 15.8871 + vertex 635.34 65.3363 17.0785 + endloop + endfacet + facet normal 0.153113 -0.478987 0.864366 + outer loop + vertex 635.34 65.3363 17.0785 + vertex 641.019 65.0015 15.8871 + vertex 641.083 67.1749 17.0802 + endloop + endfacet + facet normal 0.150234 -0.476229 0.866392 + outer loop + vertex 629.474 61.3226 15.8899 + vertex 635.329 63.164 15.8867 + vertex 629.473 63.4899 17.0813 + endloop + endfacet + facet normal 0.150253 -0.476114 0.866452 + outer loop + vertex 629.473 63.4899 17.0813 + vertex 635.329 63.164 15.8867 + vertex 635.34 65.3363 17.0785 + endloop + endfacet + facet normal 0.118614 -0.375498 0.919202 + outer loop + vertex 629.473 63.4899 17.0813 + vertex 635.34 65.3363 17.0785 + vertex 629.935 65.7618 17.9498 + endloop + endfacet + facet normal 0.120287 -0.363583 0.923763 + outer loop + vertex 629.935 65.7618 17.9498 + vertex 635.34 65.3363 17.0785 + vertex 635.294 67.8977 18.0927 + endloop + endfacet + facet normal 0.116222 -0.363825 0.924188 + outer loop + vertex 635.34 65.3363 17.0785 + vertex 641.083 67.1749 17.0802 + vertex 635.294 67.8977 18.0927 + endloop + endfacet + facet normal 0.114365 -0.373571 0.920525 + outer loop + vertex 635.294 67.8977 18.0927 + vertex 641.083 67.1749 17.0802 + vertex 641.521 69.4547 17.9509 + endloop + endfacet + facet normal 0.244125 -0.756625 0.606565 + outer loop + vertex 635.607 60.0868 12.7753 + vertex 641.231 61.9085 12.7843 + vertex 635.45 61.377 14.448 + endloop + endfacet + facet normal 0.244668 -0.754349 0.609176 + outer loop + vertex 635.45 61.377 14.448 + vertex 641.231 61.9085 12.7843 + vertex 641.092 63.2105 14.452 + endloop + endfacet + facet normal 0.239325 -0.755151 0.610304 + outer loop + vertex 629.815 58.2539 12.7784 + vertex 635.607 60.0868 12.7753 + vertex 629.636 59.5475 14.4495 + endloop + endfacet + facet normal 0.238674 -0.757953 0.607077 + outer loop + vertex 629.636 59.5475 14.4495 + vertex 635.607 60.0868 12.7753 + vertex 635.45 61.377 14.448 + endloop + endfacet + facet normal 0.191486 -0.607859 0.770611 + outer loop + vertex 629.636 59.5475 14.4495 + vertex 635.45 61.377 14.448 + vertex 629.474 61.3226 15.8899 + endloop + endfacet + facet normal 0.191518 -0.607673 0.770749 + outer loop + vertex 629.474 61.3226 15.8899 + vertex 635.45 61.377 14.448 + vertex 635.329 63.164 15.8867 + endloop + endfacet + facet normal 0.19662 -0.60683 0.770128 + outer loop + vertex 635.45 61.377 14.448 + vertex 641.092 63.2105 14.452 + vertex 635.329 63.164 15.8867 + endloop + endfacet + facet normal 0.196378 -0.608198 0.76911 + outer loop + vertex 635.329 63.164 15.8867 + vertex 641.092 63.2105 14.452 + vertex 641.019 65.0015 15.8871 + endloop + endfacet + facet normal 0.307233 -0.950606 0.0442331 + outer loop + vertex 635.804 59.2887 8.9836 + vertex 641.426 61.1062 8.99389 + vertex 635.733 59.3561 10.9234 + endloop + endfacet + facet normal 0.310561 -0.948927 0.055574 + outer loop + vertex 635.733 59.3561 10.9234 + vertex 641.426 61.1062 8.99389 + vertex 641.352 61.1954 10.93 + endloop + endfacet + facet normal 0.30307 -0.951728 0.0486101 + outer loop + vertex 630.024 57.4479 8.98034 + vertex 635.804 59.2887 8.9836 + vertex 629.944 57.5218 10.9233 + endloop + endfacet + facet normal 0.301766 -0.952362 0.0440953 + outer loop + vertex 629.944 57.5218 10.9233 + vertex 635.804 59.2887 8.9836 + vertex 635.733 59.3561 10.9234 + endloop + endfacet + facet normal 0.280726 -0.885977 0.369105 + outer loop + vertex 629.944 57.5218 10.9233 + vertex 635.733 59.3561 10.9234 + vertex 629.815 58.2539 12.7784 + endloop + endfacet + facet normal 0.280654 -0.886133 0.368784 + outer loop + vertex 629.815 58.2539 12.7784 + vertex 635.733 59.3561 10.9234 + vertex 635.607 60.0868 12.7753 + endloop + endfacet + facet normal 0.288835 -0.883672 0.368372 + outer loop + vertex 635.733 59.3561 10.9234 + vertex 641.352 61.1954 10.93 + vertex 635.607 60.0868 12.7753 + endloop + endfacet + facet normal 0.286964 -0.887662 0.36015 + outer loop + vertex 635.607 60.0868 12.7753 + vertex 641.352 61.1954 10.93 + vertex 641.231 61.9085 12.7843 + endloop + endfacet + facet normal 0.24719 -0.766355 -0.592956 + outer loop + vertex 635.583 61.1718 5.38325 + vertex 641.171 62.9634 5.3973 + vertex 635.792 59.9154 7.09432 + endloop + endfacet + facet normal 0.249468 -0.768379 -0.589372 + outer loop + vertex 635.792 59.9154 7.09432 + vertex 641.171 62.9634 5.3973 + vertex 641.394 61.7246 7.10694 + endloop + endfacet + facet normal 0.244173 -0.767232 -0.593073 + outer loop + vertex 629.807 59.3352 5.38142 + vertex 635.583 61.1718 5.38325 + vertex 630.033 58.0887 7.08693 + endloop + endfacet + facet normal 0.244107 -0.767171 -0.593178 + outer loop + vertex 630.033 58.0887 7.08693 + vertex 635.583 61.1718 5.38325 + vertex 635.792 59.9154 7.09432 + endloop + endfacet + facet normal 0.28824 -0.907467 -0.30565 + outer loop + vertex 630.033 58.0887 7.08693 + vertex 635.792 59.9154 7.09432 + vertex 630.024 57.4479 8.98034 + endloop + endfacet + facet normal 0.289345 -0.90801 -0.302981 + outer loop + vertex 630.024 57.4479 8.98034 + vertex 635.792 59.9154 7.09432 + vertex 635.804 59.2887 8.9836 + endloop + endfacet + facet normal 0.293522 -0.906794 -0.302603 + outer loop + vertex 635.792 59.9154 7.09432 + vertex 641.394 61.7246 7.10694 + vertex 635.804 59.2887 8.9836 + endloop + endfacet + facet normal 0.293736 -0.906895 -0.302095 + outer loop + vertex 635.804 59.2887 8.9836 + vertex 641.394 61.7246 7.10694 + vertex 641.426 61.1062 8.99389 + endloop + endfacet + facet normal 0.122199 -0.406718 -0.905344 + outer loop + vertex 634.001 65.0678 2.85511 + vertex 639.465 66.3951 2.99636 + vertex 634.969 62.8795 3.96876 + endloop + endfacet + facet normal 0.139072 -0.425252 -0.894327 + outer loop + vertex 634.969 62.8795 3.96876 + vertex 639.465 66.3951 2.99636 + vertex 640.596 64.6923 3.98184 + endloop + endfacet + facet normal 0.142659 -0.416448 -0.897897 + outer loop + vertex 627.809 62.6029 3.01452 + vertex 634.001 65.0678 2.85511 + vertex 629.126 60.9897 3.97191 + endloop + endfacet + facet normal 0.130002 -0.403458 -0.905716 + outer loop + vertex 629.126 60.9897 3.97191 + vertex 634.001 65.0678 2.85511 + vertex 634.969 62.8795 3.96876 + endloop + endfacet + facet normal 0.190395 -0.589985 -0.784645 + outer loop + vertex 629.126 60.9897 3.97191 + vertex 634.969 62.8795 3.96876 + vertex 629.807 59.3352 5.38142 + endloop + endfacet + facet normal 0.186606 -0.586013 -0.788522 + outer loop + vertex 629.807 59.3352 5.38142 + vertex 634.969 62.8795 3.96876 + vertex 635.583 61.1718 5.38325 + endloop + endfacet + facet normal 0.190214 -0.584767 -0.788585 + outer loop + vertex 634.969 62.8795 3.96876 + vertex 640.596 64.6923 3.98184 + vertex 635.583 61.1718 5.38325 + endloop + endfacet + facet normal 0.1891 -0.583625 -0.789698 + outer loop + vertex 635.583 61.1718 5.38325 + vertex 640.596 64.6923 3.98184 + vertex 641.171 62.9634 5.3973 + endloop + endfacet + facet normal 0.0895232 -0.266415 -0.959692 + outer loop + vertex 639.465 66.3951 2.99636 + vertex 634.001 65.0678 2.85511 + vertex 641.728 70.7192 2.00701 + endloop + endfacet + facet normal 0.0801036 -0.263404 -0.961354 + outer loop + vertex 627.809 62.6029 3.01452 + vertex 630.215 66.9558 2.02235 + vertex 634.001 65.0678 2.85511 + endloop + endfacet + facet normal 0.0830602 -0.25801 -0.962565 + outer loop + vertex 630.215 66.9558 2.02235 + vertex 641.728 70.7192 2.00701 + vertex 634.001 65.0678 2.85511 + endloop + endfacet + facet normal 0.0577819 -0.17999 -0.98197 + outer loop + vertex 628.028 71.1152 1.13124 + vertex 639.439 74.8135 1.12482 + vertex 630.215 66.9558 2.02235 + endloop + endfacet + facet normal 0.0573793 -0.17953 -0.982078 + outer loop + vertex 630.215 66.9558 2.02235 + vertex 639.439 74.8135 1.12482 + vertex 641.728 70.7192 2.00701 + endloop + endfacet + facet normal 0.19586 -0.45905 0.866552 + outer loop + vertex 644.943 100.651 24.2565 + vertex 650.231 102.318 23.9443 + vertex 645.973 102.679 25.0976 + endloop + endfacet + facet normal 0.204968 -0.415016 0.886425 + outer loop + vertex 645.973 102.679 25.0976 + vertex 650.231 102.318 23.9443 + vertex 651.414 104.385 24.6385 + endloop + endfacet + facet normal 0.209928 -0.502008 0.838999 + outer loop + vertex 639.877 99.0577 24.5705 + vertex 644.943 100.651 24.2565 + vertex 641.019 101.135 25.5274 + endloop + endfacet + facet normal 0.219885 -0.467064 0.856447 + outer loop + vertex 641.019 101.135 25.5274 + vertex 644.943 100.651 24.2565 + vertex 645.973 102.679 25.0976 + endloop + endfacet + facet normal 0.131946 -0.311562 0.941021 + outer loop + vertex 643.503 96.0539 22.712 + vertex 647.844 97.8864 22.71 + vertex 643.865 98.3539 23.4228 + endloop + endfacet + facet normal 0.132389 -0.308987 0.941807 + outer loop + vertex 643.865 98.3539 23.4228 + vertex 647.844 97.8864 22.71 + vertex 649.088 100.003 23.2294 + endloop + endfacet + facet normal 0.136081 -0.337495 0.931439 + outer loop + vertex 638.027 94.1228 22.8123 + vertex 643.503 96.0539 22.712 + vertex 638.723 96.6459 23.6249 + endloop + endfacet + facet normal 0.140713 -0.312455 0.939453 + outer loop + vertex 638.723 96.6459 23.6249 + vertex 643.503 96.0539 22.712 + vertex 643.865 98.3539 23.4228 + endloop + endfacet + facet normal 0.178238 -0.431968 0.884101 + outer loop + vertex 638.723 96.6459 23.6249 + vertex 643.865 98.3539 23.4228 + vertex 639.877 99.0577 24.5705 + endloop + endfacet + facet normal 0.184537 -0.41066 0.892919 + outer loop + vertex 639.877 99.0577 24.5705 + vertex 643.865 98.3539 23.4228 + vertex 644.943 100.651 24.2565 + endloop + endfacet + facet normal 0.160362 -0.402362 0.901326 + outer loop + vertex 643.865 98.3539 23.4228 + vertex 649.088 100.003 23.2294 + vertex 644.943 100.651 24.2565 + endloop + endfacet + facet normal 0.169425 -0.36612 0.915014 + outer loop + vertex 644.943 100.651 24.2565 + vertex 649.088 100.003 23.2294 + vertex 650.231 102.318 23.9443 + endloop + endfacet + facet normal 0.0891117 -0.277682 0.956531 + outer loop + vertex 641.521 69.4547 17.9509 + vertex 646.724 71.5967 18.088 + vertex 637.781 71.7835 18.9754 + endloop + endfacet + facet normal 0.0937573 -0.274881 0.956896 + outer loop + vertex 652.782 73.1638 17.9446 + vertex 649.189 75.5185 18.9731 + vertex 646.724 71.5967 18.088 + endloop + endfacet + facet normal 0.0893712 -0.272381 0.95803 + outer loop + vertex 649.189 75.5185 18.9731 + vertex 637.781 71.7835 18.9754 + vertex 646.724 71.5967 18.088 + endloop + endfacet + facet normal 0.160398 -0.479304 0.862867 + outer loop + vertex 646.584 66.8258 15.8889 + vertex 652.088 68.6645 15.887 + vertex 646.705 69.0088 17.0789 + endloop + endfacet + facet normal 0.160116 -0.480874 0.862046 + outer loop + vertex 646.705 69.0088 17.0789 + vertex 652.088 68.6645 15.887 + vertex 652.248 70.8514 17.0774 + endloop + endfacet + facet normal 0.15668 -0.478798 0.863831 + outer loop + vertex 641.019 65.0015 15.8871 + vertex 646.584 66.8258 15.8889 + vertex 641.083 67.1749 17.0802 + endloop + endfacet + facet normal 0.156568 -0.479434 0.863498 + outer loop + vertex 641.083 67.1749 17.0802 + vertex 646.584 66.8258 15.8889 + vertex 646.705 69.0088 17.0789 + endloop + endfacet + facet normal 0.122374 -0.374561 0.919091 + outer loop + vertex 641.083 67.1749 17.0802 + vertex 646.705 69.0088 17.0789 + vertex 641.521 69.4547 17.9509 + endloop + endfacet + facet normal 0.124368 -0.361247 0.924139 + outer loop + vertex 641.521 69.4547 17.9509 + vertex 646.705 69.0088 17.0789 + vertex 646.724 71.5967 18.088 + endloop + endfacet + facet normal 0.120411 -0.3614 0.924603 + outer loop + vertex 646.705 69.0088 17.0789 + vertex 652.248 70.8514 17.0774 + vertex 646.724 71.5967 18.088 + endloop + endfacet + facet normal 0.118153 -0.37253 0.920468 + outer loop + vertex 646.724 71.5967 18.088 + vertex 652.248 70.8514 17.0774 + vertex 652.782 73.1638 17.9446 + endloop + endfacet + facet normal 0.25175 -0.75289 0.608094 + outer loop + vertex 646.742 63.7348 12.7888 + vertex 652.228 65.5711 12.7912 + vertex 646.618 65.0382 14.4538 + endloop + endfacet + facet normal 0.251623 -0.753411 0.607501 + outer loop + vertex 646.618 65.0382 14.4538 + vertex 652.228 65.5711 12.7912 + vertex 652.103 66.8716 14.4556 + endloop + endfacet + facet normal 0.249123 -0.753271 0.608704 + outer loop + vertex 641.231 61.9085 12.7843 + vertex 646.742 63.7348 12.7888 + vertex 641.092 63.2105 14.452 + endloop + endfacet + facet normal 0.249059 -0.753537 0.6084 + outer loop + vertex 641.092 63.2105 14.452 + vertex 646.742 63.7348 12.7888 + vertex 646.618 65.0382 14.4538 + endloop + endfacet + facet normal 0.200715 -0.60754 0.768511 + outer loop + vertex 641.092 63.2105 14.452 + vertex 646.618 65.0382 14.4538 + vertex 641.019 65.0015 15.8871 + endloop + endfacet + facet normal 0.200068 -0.611048 0.765894 + outer loop + vertex 641.019 65.0015 15.8871 + vertex 646.618 65.0382 14.4538 + vertex 646.584 66.8258 15.8889 + endloop + endfacet + facet normal 0.203809 -0.610521 0.765327 + outer loop + vertex 646.618 65.0382 14.4538 + vertex 652.103 66.8716 14.4556 + vertex 646.584 66.8258 15.8889 + endloop + endfacet + facet normal 0.203948 -0.609776 0.765884 + outer loop + vertex 646.584 66.8258 15.8889 + vertex 652.103 66.8716 14.4556 + vertex 652.088 68.6645 15.887 + endloop + endfacet + facet normal 0.317248 -0.947024 0.0499987 + outer loop + vertex 646.948 62.9364 8.99992 + vertex 652.456 64.7816 9.00178 + vertex 646.871 63.013 10.9362 + endloop + endfacet + facet normal 0.317826 -0.946725 0.05194 + outer loop + vertex 646.871 63.013 10.9362 + vertex 652.456 64.7816 9.00178 + vertex 652.369 64.8586 10.9376 + endloop + endfacet + facet normal 0.31407 -0.947767 0.0556547 + outer loop + vertex 641.426 61.1062 8.99389 + vertex 646.948 62.9364 8.99992 + vertex 641.352 61.1954 10.93 + endloop + endfacet + facet normal 0.312352 -0.948657 0.0498698 + outer loop + vertex 641.352 61.1954 10.93 + vertex 646.948 62.9364 8.99992 + vertex 646.871 63.013 10.9362 + endloop + endfacet + facet normal 0.291464 -0.88629 0.359916 + outer loop + vertex 641.352 61.1954 10.93 + vertex 646.871 63.013 10.9362 + vertex 641.231 61.9085 12.7843 + endloop + endfacet + facet normal 0.292609 -0.883894 0.364844 + outer loop + vertex 641.231 61.9085 12.7843 + vertex 646.871 63.013 10.9362 + vertex 646.742 63.7348 12.7888 + endloop + endfacet + facet normal 0.296269 -0.882752 0.364654 + outer loop + vertex 646.871 63.013 10.9362 + vertex 652.369 64.8586 10.9376 + vertex 646.742 63.7348 12.7888 + endloop + endfacet + facet normal 0.295715 -0.883923 0.362259 + outer loop + vertex 646.742 63.7348 12.7888 + vertex 652.369 64.8586 10.9376 + vertex 652.228 65.5711 12.7912 + endloop + endfacet + facet normal 0.25684 -0.766463 -0.5887 + outer loop + vertex 646.653 64.765 5.40956 + vertex 652.137 66.5991 5.4145 + vertex 646.908 63.5408 7.11463 + endloop + endfacet + facet normal 0.254901 -0.764808 -0.591688 + outer loop + vertex 646.908 63.5408 7.11463 + vertex 652.137 66.5991 5.4145 + vertex 652.417 65.3771 7.11452 + endloop + endfacet + facet normal 0.253484 -0.767275 -0.589096 + outer loop + vertex 641.171 62.9634 5.3973 + vertex 646.653 64.765 5.40956 + vertex 641.394 61.7246 7.10694 + endloop + endfacet + facet normal 0.253619 -0.767392 -0.588886 + outer loop + vertex 641.394 61.7246 7.10694 + vertex 646.653 64.765 5.40956 + vertex 646.908 63.5408 7.11463 + endloop + endfacet + facet normal 0.298685 -0.905411 -0.301691 + outer loop + vertex 641.394 61.7246 7.10694 + vertex 646.908 63.5408 7.11463 + vertex 641.426 61.1062 8.99389 + endloop + endfacet + facet normal 0.300715 -0.906311 -0.296937 + outer loop + vertex 641.426 61.1062 8.99389 + vertex 646.908 63.5408 7.11463 + vertex 646.948 62.9364 8.99992 + endloop + endfacet + facet normal 0.301945 -0.905933 -0.296842 + outer loop + vertex 646.908 63.5408 7.11463 + vertex 652.417 65.3771 7.11452 + vertex 646.948 62.9364 8.99992 + endloop + endfacet + facet normal 0.303875 -0.90676 -0.292312 + outer loop + vertex 646.948 62.9364 8.99992 + vertex 652.417 65.3771 7.11452 + vertex 652.456 64.7816 9.00178 + endloop + endfacet + facet normal 0.123758 -0.404251 -0.906237 + outer loop + vertex 645.284 68.754 2.87341 + vertex 650.471 70.0176 3.01808 + vertex 646.072 66.4804 3.99534 + endloop + endfacet + facet normal 0.141113 -0.422775 -0.895181 + outer loop + vertex 646.072 66.4804 3.99534 + vertex 650.471 70.0176 3.01808 + vertex 651.536 68.2939 4.00003 + endloop + endfacet + facet normal 0.15068 -0.41834 -0.895705 + outer loop + vertex 639.465 66.3951 2.99636 + vertex 645.284 68.754 2.87341 + vertex 640.596 64.6923 3.98184 + endloop + endfacet + facet normal 0.133171 -0.401033 -0.906332 + outer loop + vertex 640.596 64.6923 3.98184 + vertex 645.284 68.754 2.87341 + vertex 646.072 66.4804 3.99534 + endloop + endfacet + facet normal 0.192168 -0.582611 -0.789706 + outer loop + vertex 640.596 64.6923 3.98184 + vertex 646.072 66.4804 3.99534 + vertex 641.171 62.9634 5.3973 + endloop + endfacet + facet normal 0.193763 -0.584207 -0.788136 + outer loop + vertex 641.171 62.9634 5.3973 + vertex 646.072 66.4804 3.99534 + vertex 646.653 64.765 5.40956 + endloop + endfacet + facet normal 0.194526 -0.583951 -0.788138 + outer loop + vertex 646.072 66.4804 3.99534 + vertex 651.536 68.2939 4.00003 + vertex 646.653 64.765 5.40956 + endloop + endfacet + facet normal 0.196708 -0.586112 -0.785989 + outer loop + vertex 646.653 64.765 5.40956 + vertex 651.536 68.2939 4.00003 + vertex 652.137 66.5991 5.4145 + endloop + endfacet + facet normal 0.0918998 -0.267414 -0.959189 + outer loop + vertex 650.471 70.0176 3.01808 + vertex 645.284 68.754 2.87341 + vertex 652.898 74.4497 2.01508 + endloop + endfacet + facet normal 0.0872963 -0.265363 -0.960188 + outer loop + vertex 639.465 66.3951 2.99636 + vertex 641.728 70.7192 2.00701 + vertex 645.284 68.754 2.87341 + endloop + endfacet + facet normal 0.0885961 -0.263219 -0.96066 + outer loop + vertex 641.728 70.7192 2.00701 + vertex 652.898 74.4497 2.01508 + vertex 645.284 68.754 2.87341 + endloop + endfacet + facet normal 0.0594456 -0.178393 -0.982162 + outer loop + vertex 639.439 74.8135 1.12482 + vertex 650.828 78.638 1.1195 + vertex 641.728 70.7192 2.00701 + endloop + endfacet + facet normal 0.0607842 -0.179891 -0.981807 + outer loop + vertex 641.728 70.7192 2.00701 + vertex 650.828 78.638 1.1195 + vertex 652.898 74.4497 2.01508 + endloop + endfacet + facet normal 0.1566 -0.360106 0.919674 + outer loop + vertex 655.563 104.044 23.6691 + vertex 660.793 105.821 23.4743 + vertex 656.734 106.115 24.2806 + endloop + endfacet + facet normal 0.159412 -0.34044 0.926654 + outer loop + vertex 656.734 106.115 24.2806 + vertex 660.793 105.821 23.4743 + vertex 661.787 107.844 24.0464 + endloop + endfacet + facet normal 0.176716 -0.402762 0.898084 + outer loop + vertex 650.231 102.318 23.9443 + vertex 655.563 104.044 23.6691 + vertex 651.414 104.385 24.6385 + endloop + endfacet + facet normal 0.182119 -0.371766 0.910287 + outer loop + vertex 651.414 104.385 24.6385 + vertex 655.563 104.044 23.6691 + vertex 656.734 106.115 24.2806 + endloop + endfacet + facet normal 0.0940012 -0.24229 0.965639 + outer loop + vertex 653.353 99.0957 22.5044 + vertex 658.544 100.944 22.4629 + vertex 654.469 101.674 23.0426 + endloop + endfacet + facet normal 0.0981256 -0.222678 0.969941 + outer loop + vertex 654.469 101.674 23.0426 + vertex 658.544 100.944 22.4629 + vertex 659.882 103.435 22.8994 + endloop + endfacet + facet normal 0.0996104 -0.292027 0.951209 + outer loop + vertex 647.844 97.8864 22.71 + vertex 653.353 99.0957 22.5044 + vertex 649.088 100.003 23.2294 + endloop + endfacet + facet normal 0.110675 -0.248795 0.962212 + outer loop + vertex 649.088 100.003 23.2294 + vertex 653.353 99.0957 22.5044 + vertex 654.469 101.674 23.0426 + endloop + endfacet + facet normal 0.142484 -0.355514 0.923747 + outer loop + vertex 649.088 100.003 23.2294 + vertex 654.469 101.674 23.0426 + vertex 650.231 102.318 23.9443 + endloop + endfacet + facet normal 0.150982 -0.317163 0.936276 + outer loop + vertex 650.231 102.318 23.9443 + vertex 654.469 101.674 23.0426 + vertex 655.563 104.044 23.6691 + endloop + endfacet + facet normal 0.12487 -0.307017 0.943477 + outer loop + vertex 654.469 101.674 23.0426 + vertex 659.882 103.435 22.8994 + vertex 655.563 104.044 23.6691 + endloop + endfacet + facet normal 0.13023 -0.279011 0.951416 + outer loop + vertex 655.563 104.044 23.6691 + vertex 659.882 103.435 22.8994 + vertex 660.793 105.821 23.4743 + endloop + endfacet + facet normal 0.0920252 -0.277294 0.956368 + outer loop + vertex 652.782 73.1638 17.9446 + vertex 657.907 75.3502 18.0854 + vertex 649.189 75.5185 18.9731 + endloop + endfacet + facet normal 0.0974528 -0.274838 0.956539 + outer loop + vertex 663.904 76.9811 17.9431 + vertex 660.458 79.3265 18.968 + vertex 657.907 75.3502 18.0854 + endloop + endfacet + facet normal 0.0922878 -0.271828 0.95791 + outer loop + vertex 660.458 79.3265 18.968 + vertex 649.189 75.5185 18.9731 + vertex 657.907 75.3502 18.0854 + endloop + endfacet + facet normal 0.164946 -0.481063 0.861029 + outer loop + vertex 657.583 70.5274 15.8871 + vertex 663.104 72.4271 15.8909 + vertex 657.767 72.7221 17.0781 + endloop + endfacet + facet normal 0.165547 -0.477564 0.86286 + outer loop + vertex 657.767 72.7221 17.0781 + vertex 663.104 72.4271 15.8909 + vertex 663.299 74.6373 17.0768 + endloop + endfacet + facet normal 0.162994 -0.480809 0.861542 + outer loop + vertex 652.088 68.6645 15.887 + vertex 657.583 70.5274 15.8871 + vertex 652.248 70.8514 17.0774 + endloop + endfacet + facet normal 0.162944 -0.481093 0.861394 + outer loop + vertex 652.248 70.8514 17.0774 + vertex 657.583 70.5274 15.8871 + vertex 657.767 72.7221 17.0781 + endloop + endfacet + facet normal 0.126592 -0.373858 0.918806 + outer loop + vertex 652.248 70.8514 17.0774 + vertex 657.767 72.7221 17.0781 + vertex 652.782 73.1638 17.9446 + endloop + endfacet + facet normal 0.12859 -0.360898 0.923698 + outer loop + vertex 652.782 73.1638 17.9446 + vertex 657.767 72.7221 17.0781 + vertex 657.907 75.3502 18.0854 + endloop + endfacet + facet normal 0.125169 -0.360896 0.924168 + outer loop + vertex 657.767 72.7221 17.0781 + vertex 663.299 74.6373 17.0768 + vertex 657.907 75.3502 18.0854 + endloop + endfacet + facet normal 0.122967 -0.371822 0.920123 + outer loop + vertex 657.907 75.3502 18.0854 + vertex 663.299 74.6373 17.0768 + vertex 663.904 76.9811 17.9431 + endloop + endfacet + facet normal 0.258889 -0.751799 0.606444 + outer loop + vertex 657.737 67.4393 12.7913 + vertex 663.291 69.3517 12.7911 + vertex 657.599 68.735 14.4566 + endloop + endfacet + facet normal 0.259019 -0.751222 0.607103 + outer loop + vertex 657.599 68.735 14.4566 + vertex 663.291 69.3517 12.7911 + vertex 663.136 70.6436 14.4558 + endloop + endfacet + facet normal 0.255169 -0.752548 0.607092 + outer loop + vertex 652.228 65.5711 12.7912 + vertex 657.737 67.4393 12.7913 + vertex 652.103 66.8716 14.4556 + endloop + endfacet + facet normal 0.255122 -0.752745 0.606868 + outer loop + vertex 652.103 66.8716 14.4556 + vertex 657.737 67.4393 12.7913 + vertex 657.599 68.735 14.4566 + endloop + endfacet + facet normal 0.206502 -0.609429 0.765476 + outer loop + vertex 652.103 66.8716 14.4556 + vertex 657.599 68.735 14.4566 + vertex 652.088 68.6645 15.887 + endloop + endfacet + facet normal 0.206536 -0.609241 0.765616 + outer loop + vertex 652.088 68.6645 15.887 + vertex 657.599 68.735 14.4566 + vertex 657.583 70.5274 15.8871 + endloop + endfacet + facet normal 0.20994 -0.608771 0.765064 + outer loop + vertex 657.599 68.735 14.4566 + vertex 663.136 70.6436 14.4558 + vertex 657.583 70.5274 15.8871 + endloop + endfacet + facet normal 0.209613 -0.610668 0.76364 + outer loop + vertex 657.583 70.5274 15.8871 + vertex 663.136 70.6436 14.4558 + vertex 663.104 72.4271 15.8909 + endloop + endfacet + facet normal 0.32359 -0.944619 0.0546245 + outer loop + vertex 657.992 66.6575 9.00035 + vertex 663.569 68.5677 8.99931 + vertex 657.893 66.7355 10.9371 + endloop + endfacet + facet normal 0.323729 -0.944544 0.0551023 + outer loop + vertex 657.893 66.7355 10.9371 + vertex 663.569 68.5677 8.99931 + vertex 663.461 68.644 10.937 + endloop + endfacet + facet normal 0.320475 -0.945827 0.0520235 + outer loop + vertex 652.456 64.7816 9.00178 + vertex 657.992 66.6575 9.00035 + vertex 652.369 64.8586 10.9376 + endloop + endfacet + facet normal 0.321215 -0.945435 0.0545357 + outer loop + vertex 652.369 64.8586 10.9376 + vertex 657.992 66.6575 9.00035 + vertex 657.893 66.7355 10.9371 + endloop + endfacet + facet normal 0.299895 -0.882594 0.362066 + outer loop + vertex 652.369 64.8586 10.9376 + vertex 657.893 66.7355 10.9371 + vertex 652.228 65.5711 12.7912 + endloop + endfacet + facet normal 0.299536 -0.883362 0.360486 + outer loop + vertex 652.228 65.5711 12.7912 + vertex 657.893 66.7355 10.9371 + vertex 657.737 67.4393 12.7913 + endloop + endfacet + facet normal 0.302442 -0.882418 0.360372 + outer loop + vertex 657.893 66.7355 10.9371 + vertex 663.461 68.644 10.937 + vertex 657.737 67.4393 12.7913 + endloop + endfacet + facet normal 0.303244 -0.880655 0.363992 + outer loop + vertex 657.737 67.4393 12.7913 + vertex 663.461 68.644 10.937 + vertex 663.291 69.3517 12.7911 + endloop + endfacet + facet normal 0.262592 -0.766589 -0.585992 + outer loop + vertex 657.67 68.4647 5.40995 + vertex 663.247 70.3778 5.40637 + vertex 657.955 67.2589 7.11491 + endloop + endfacet + facet normal 0.263379 -0.767253 -0.584769 + outer loop + vertex 657.955 67.2589 7.11491 + vertex 663.247 70.3778 5.40637 + vertex 663.535 69.1761 7.11261 + endloop + endfacet + facet normal 0.257177 -0.764132 -0.591576 + outer loop + vertex 652.137 66.5991 5.4145 + vertex 657.67 68.4647 5.40995 + vertex 652.417 65.3771 7.11452 + endloop + endfacet + facet normal 0.260737 -0.767153 -0.586082 + outer loop + vertex 652.417 65.3771 7.11452 + vertex 657.67 68.4647 5.40995 + vertex 657.955 67.2589 7.11491 + endloop + endfacet + facet normal 0.307746 -0.905551 -0.292009 + outer loop + vertex 652.417 65.3771 7.11452 + vertex 657.955 67.2589 7.11491 + vertex 652.456 64.7816 9.00178 + endloop + endfacet + facet normal 0.30657 -0.905052 -0.294782 + outer loop + vertex 652.456 64.7816 9.00178 + vertex 657.955 67.2589 7.11491 + vertex 657.992 66.6575 9.00035 + endloop + endfacet + facet normal 0.310427 -0.903837 -0.294472 + outer loop + vertex 657.955 67.2589 7.11491 + vertex 663.535 69.1761 7.11261 + vertex 657.992 66.6575 9.00035 + endloop + endfacet + facet normal 0.309405 -0.903397 -0.296887 + outer loop + vertex 657.992 66.6575 9.00035 + vertex 663.535 69.1761 7.11261 + vertex 663.569 68.5677 8.99931 + endloop + endfacet + facet normal 0.128205 -0.404328 -0.905584 + outer loop + vertex 656.264 72.4244 2.87717 + vertex 661.491 73.7606 3.0206 + vertex 657.04 70.1544 4.00057 + endloop + endfacet + facet normal 0.14507 -0.422217 -0.894811 + outer loop + vertex 657.04 70.1544 4.00057 + vertex 661.491 73.7606 3.0206 + vertex 662.597 72.0643 4.00035 + endloop + endfacet + facet normal 0.151437 -0.416983 -0.89621 + outer loop + vertex 650.471 70.0176 3.01808 + vertex 656.264 72.4244 2.87717 + vertex 651.536 68.2939 4.00003 + endloop + endfacet + facet normal 0.135873 -0.401726 -0.905624 + outer loop + vertex 651.536 68.2939 4.00003 + vertex 656.264 72.4244 2.87717 + vertex 657.04 70.1544 4.00057 + endloop + endfacet + facet normal 0.198029 -0.585652 -0.786 + outer loop + vertex 651.536 68.2939 4.00003 + vertex 657.04 70.1544 4.00057 + vertex 652.137 66.5991 5.4145 + endloop + endfacet + facet normal 0.196236 -0.583883 -0.787764 + outer loop + vertex 652.137 66.5991 5.4145 + vertex 657.04 70.1544 4.00057 + vertex 657.67 68.4647 5.40995 + endloop + endfacet + facet normal 0.20015 -0.582472 -0.787824 + outer loop + vertex 657.04 70.1544 4.00057 + vertex 662.597 72.0643 4.00035 + vertex 657.67 68.4647 5.40995 + endloop + endfacet + facet normal 0.19887 -0.581212 -0.789078 + outer loop + vertex 657.67 68.4647 5.40995 + vertex 662.597 72.0643 4.00035 + vertex 663.247 70.3778 5.40637 + endloop + endfacet + facet normal 0.0944337 -0.26646 -0.959209 + outer loop + vertex 661.491 73.7606 3.0206 + vertex 656.264 72.4244 2.87717 + vertex 663.98 78.2533 2.01758 + endloop + endfacet + facet normal 0.0866572 -0.264815 -0.960398 + outer loop + vertex 650.471 70.0176 3.01808 + vertex 652.898 74.4497 2.01508 + vertex 656.264 72.4244 2.87717 + endloop + endfacet + facet normal 0.0895843 -0.260356 -0.961348 + outer loop + vertex 652.898 74.4497 2.01508 + vertex 663.98 78.2533 2.01758 + vertex 656.264 72.4244 2.87717 + endloop + endfacet + facet normal 0.0616814 -0.179453 -0.981831 + outer loop + vertex 650.828 78.638 1.1195 + vertex 661.982 82.4706 1.1197 + vertex 652.898 74.4497 2.01508 + endloop + endfacet + facet normal 0.0619026 -0.179697 -0.981772 + outer loop + vertex 652.898 74.4497 2.01508 + vertex 661.982 82.4706 1.1197 + vertex 663.98 78.2533 2.01758 + endloop + endfacet + facet normal 0.130037 -0.31659 0.939607 + outer loop + vertex 665.985 107.66 23.3484 + vertex 671.228 109.548 23.2589 + vertex 666.857 109.634 23.8928 + endloop + endfacet + facet normal 0.130441 -0.310524 0.941573 + outer loop + vertex 666.857 109.634 23.8928 + vertex 671.228 109.548 23.2589 + vertex 672.092 111.505 23.7847 + endloop + endfacet + facet normal 0.140532 -0.332803 0.932466 + outer loop + vertex 660.793 105.821 23.4743 + vertex 665.985 107.66 23.3484 + vertex 661.787 107.844 24.0464 + endloop + endfacet + facet normal 0.141717 -0.320882 0.936456 + outer loop + vertex 661.787 107.844 24.0464 + vertex 665.985 107.66 23.3484 + vertex 666.857 109.634 23.8928 + endloop + endfacet + facet normal 0.0781768 -0.189909 0.978684 + outer loop + vertex 664.481 102.5 22.3242 + vertex 669.788 104.816 22.3497 + vertex 665.268 105.315 22.8075 + endloop + endfacet + facet normal 0.0785378 -0.187106 0.979195 + outer loop + vertex 665.268 105.315 22.8075 + vertex 669.788 104.816 22.3497 + vertex 670.634 107.245 22.7459 + endloop + endfacet + facet normal 0.0785408 -0.212854 0.973922 + outer loop + vertex 658.544 100.944 22.4629 + vertex 664.481 102.5 22.3242 + vertex 659.882 103.435 22.8994 + endloop + endfacet + facet normal 0.0834398 -0.191261 0.977986 + outer loop + vertex 659.882 103.435 22.8994 + vertex 664.481 102.5 22.3242 + vertex 665.268 105.315 22.8075 + endloop + endfacet + facet normal 0.111538 -0.272875 0.955562 + outer loop + vertex 659.882 103.435 22.8994 + vertex 665.268 105.315 22.8075 + vertex 660.793 105.821 23.4743 + endloop + endfacet + facet normal 0.114063 -0.256214 0.959867 + outer loop + vertex 660.793 105.821 23.4743 + vertex 665.268 105.315 22.8075 + vertex 665.985 107.66 23.3484 + endloop + endfacet + facet normal 0.102064 -0.253054 0.962053 + outer loop + vertex 665.268 105.315 22.8075 + vertex 670.634 107.245 22.7459 + vertex 665.985 107.66 23.3484 + endloop + endfacet + facet normal 0.103453 -0.241569 0.964853 + outer loop + vertex 665.985 107.66 23.3484 + vertex 670.634 107.245 22.7459 + vertex 671.228 109.548 23.2589 + endloop + endfacet + facet normal 0.0950556 -0.278058 0.95585 + outer loop + vertex 663.904 76.9811 17.9431 + vertex 669.076 79.2502 18.0888 + vertex 660.458 79.3265 18.968 + endloop + endfacet + facet normal 0.100426 -0.27357 0.956595 + outer loop + vertex 675.12 80.9752 17.9476 + vertex 671.665 83.2627 18.9645 + vertex 669.076 79.2502 18.0888 + endloop + endfacet + facet normal 0.0953374 -0.270586 0.957964 + outer loop + vertex 671.665 83.2627 18.9645 + vertex 660.458 79.3265 18.968 + vertex 669.076 79.2502 18.0888 + endloop + endfacet + facet normal 0.170107 -0.478381 0.861519 + outer loop + vertex 668.684 74.3892 15.889 + vertex 674.31 76.395 15.8918 + vertex 668.879 76.6006 17.0785 + endloop + endfacet + facet normal 0.170519 -0.475675 0.862935 + outer loop + vertex 668.879 76.6006 17.0785 + vertex 674.31 76.395 15.8918 + vertex 674.505 78.6175 17.0785 + endloop + endfacet + facet normal 0.168209 -0.477532 0.862362 + outer loop + vertex 663.104 72.4271 15.8909 + vertex 668.684 74.3892 15.889 + vertex 663.299 74.6373 17.0768 + endloop + endfacet + facet normal 0.168068 -0.478408 0.861904 + outer loop + vertex 663.299 74.6373 17.0768 + vertex 668.684 74.3892 15.889 + vertex 668.879 76.6006 17.0785 + endloop + endfacet + facet normal 0.131062 -0.373279 0.918415 + outer loop + vertex 663.299 74.6373 17.0768 + vertex 668.879 76.6006 17.0785 + vertex 663.904 76.9811 17.9431 + endloop + endfacet + facet normal 0.132702 -0.361752 0.922782 + outer loop + vertex 663.904 76.9811 17.9431 + vertex 668.879 76.6006 17.0785 + vertex 669.076 79.2502 18.0888 + endloop + endfacet + facet normal 0.12966 -0.361698 0.923235 + outer loop + vertex 668.879 76.6006 17.0785 + vertex 674.505 78.6175 17.0785 + vertex 669.076 79.2502 18.0888 + endloop + endfacet + facet normal 0.127706 -0.372207 0.919322 + outer loop + vertex 669.076 79.2502 18.0888 + vertex 674.505 78.6175 17.0785 + vertex 675.12 80.9752 17.9476 + endloop + endfacet + facet normal 0.267825 -0.750196 0.604546 + outer loop + vertex 668.899 71.3182 12.7891 + vertex 674.546 73.3336 12.7881 + vertex 668.726 72.6003 14.4565 + endloop + endfacet + facet normal 0.267729 -0.750666 0.604005 + outer loop + vertex 668.726 72.6003 14.4565 + vertex 674.546 73.3336 12.7881 + vertex 674.364 74.6108 14.4562 + endloop + endfacet + facet normal 0.263278 -0.750115 0.606641 + outer loop + vertex 663.291 69.3517 12.7911 + vertex 668.899 71.3182 12.7891 + vertex 663.136 70.6436 14.4558 + endloop + endfacet + facet normal 0.26298 -0.751503 0.605049 + outer loop + vertex 663.136 70.6436 14.4558 + vertex 668.899 71.3182 12.7891 + vertex 668.726 72.6003 14.4565 + endloop + endfacet + facet normal 0.213464 -0.610103 0.763025 + outer loop + vertex 663.136 70.6436 14.4558 + vertex 668.726 72.6003 14.4565 + vertex 663.104 72.4271 15.8909 + endloop + endfacet + facet normal 0.213881 -0.607518 0.764969 + outer loop + vertex 663.104 72.4271 15.8909 + vertex 668.726 72.6003 14.4565 + vertex 668.684 74.3892 15.889 + endloop + endfacet + facet normal 0.216546 -0.607112 0.764541 + outer loop + vertex 668.726 72.6003 14.4565 + vertex 674.364 74.6108 14.4562 + vertex 668.684 74.3892 15.889 + endloop + endfacet + facet normal 0.216398 -0.608092 0.763804 + outer loop + vertex 668.684 74.3892 15.889 + vertex 674.364 74.6108 14.4562 + vertex 674.31 76.395 15.8918 + endloop + endfacet + facet normal 0.33321 -0.941438 0.051626 + outer loop + vertex 669.187 70.5461 8.99917 + vertex 674.843 72.5479 8.99843 + vertex 669.077 70.6135 10.9359 + endloop + endfacet + facet normal 0.333964 -0.941021 0.0542853 + outer loop + vertex 669.077 70.6135 10.9359 + vertex 674.843 72.5479 8.99843 + vertex 674.73 72.6199 10.9369 + endloop + endfacet + facet normal 0.33165 -0.941773 0.0554311 + outer loop + vertex 663.569 68.5677 8.99931 + vertex 669.187 70.5461 8.99917 + vertex 663.461 68.644 10.937 + endloop + endfacet + facet normal 0.330527 -0.94239 0.0515074 + outer loop + vertex 663.461 68.644 10.937 + vertex 669.187 70.5461 8.99917 + vertex 669.077 70.6135 10.9359 + endloop + endfacet + facet normal 0.308338 -0.878959 0.363812 + outer loop + vertex 663.461 68.644 10.937 + vertex 669.077 70.6135 10.9359 + vertex 663.291 69.3517 12.7911 + endloop + endfacet + facet normal 0.308361 -0.878906 0.363919 + outer loop + vertex 663.291 69.3517 12.7911 + vertex 669.077 70.6135 10.9359 + vertex 668.899 71.3182 12.7891 + endloop + endfacet + facet normal 0.31149 -0.877845 0.363817 + outer loop + vertex 669.077 70.6135 10.9359 + vertex 674.73 72.6199 10.9369 + vertex 668.899 71.3182 12.7891 + endloop + endfacet + facet normal 0.312492 -0.875474 0.368639 + outer loop + vertex 668.899 71.3182 12.7891 + vertex 674.73 72.6199 10.9369 + vertex 674.546 73.3336 12.7881 + endloop + endfacet + facet normal 0.270915 -0.763246 -0.586567 + outer loop + vertex 668.862 72.3496 5.40791 + vertex 674.519 74.3597 5.40509 + vertex 669.154 71.143 7.11273 + endloop + endfacet + facet normal 0.27301 -0.765004 -0.583296 + outer loop + vertex 669.154 71.143 7.11273 + vertex 674.519 74.3597 5.40509 + vertex 674.808 73.1613 7.11213 + endloop + endfacet + facet normal 0.268995 -0.765514 -0.584491 + outer loop + vertex 663.247 70.3778 5.40637 + vertex 668.862 72.3496 5.40791 + vertex 663.535 69.1761 7.11261 + endloop + endfacet + facet normal 0.267553 -0.7643 -0.586737 + outer loop + vertex 663.535 69.1761 7.11261 + vertex 668.862 72.3496 5.40791 + vertex 669.154 71.143 7.11273 + endloop + endfacet + facet normal 0.315552 -0.90144 -0.296367 + outer loop + vertex 663.535 69.1761 7.11261 + vertex 669.154 71.143 7.11273 + vertex 663.569 68.5677 8.99931 + endloop + endfacet + facet normal 0.317769 -0.902381 -0.291086 + outer loop + vertex 663.569 68.5677 8.99931 + vertex 669.154 71.143 7.11273 + vertex 669.187 70.5461 8.99917 + endloop + endfacet + facet normal 0.321628 -0.90112 -0.290754 + outer loop + vertex 669.154 71.143 7.11273 + vertex 674.808 73.1613 7.11213 + vertex 669.187 70.5461 8.99917 + endloop + endfacet + facet normal 0.31841 -0.899749 -0.29844 + outer loop + vertex 669.187 70.5461 8.99917 + vertex 674.808 73.1613 7.11213 + vertex 674.843 72.5479 8.99843 + endloop + endfacet + facet normal 0.130425 -0.401 -0.906746 + outer loop + vertex 667.382 76.2741 2.88176 + vertex 672.704 77.7026 3.0155 + vertex 668.206 74.0215 3.99642 + endloop + endfacet + facet normal 0.150506 -0.42213 -0.893954 + outer loop + vertex 668.206 74.0215 3.99642 + vertex 672.704 77.7026 3.0155 + vertex 673.851 76.0332 3.99691 + endloop + endfacet + facet normal 0.15621 -0.415645 -0.896012 + outer loop + vertex 661.491 73.7606 3.0206 + vertex 667.382 76.2741 2.88176 + vertex 662.597 72.0643 4.00035 + endloop + endfacet + facet normal 0.138301 -0.398162 -0.90683 + outer loop + vertex 662.597 72.0643 4.00035 + vertex 667.382 76.2741 2.88176 + vertex 668.206 74.0215 3.99642 + endloop + endfacet + facet normal 0.20187 -0.580102 -0.789133 + outer loop + vertex 662.597 72.0643 4.00035 + vertex 668.206 74.0215 3.99642 + vertex 663.247 70.3778 5.40637 + endloop + endfacet + facet normal 0.205023 -0.583195 -0.786034 + outer loop + vertex 663.247 70.3778 5.40637 + vertex 668.206 74.0215 3.99642 + vertex 668.862 72.3496 5.40791 + endloop + endfacet + facet normal 0.207552 -0.58224 -0.786078 + outer loop + vertex 668.206 74.0215 3.99642 + vertex 673.851 76.0332 3.99691 + vertex 668.862 72.3496 5.40791 + endloop + endfacet + facet normal 0.205936 -0.58066 -0.78767 + outer loop + vertex 668.862 72.3496 5.40791 + vertex 673.851 76.0332 3.99691 + vertex 674.519 74.3597 5.40509 + endloop + endfacet + facet normal 0.0949088 -0.263708 -0.959922 + outer loop + vertex 672.704 77.7026 3.0155 + vertex 667.382 76.2741 2.88176 + vertex 675.161 82.2282 2.01517 + endloop + endfacet + facet normal 0.0901296 -0.264301 -0.960219 + outer loop + vertex 661.491 73.7606 3.0206 + vertex 663.98 78.2533 2.01758 + vertex 667.382 76.2741 2.88176 + endloop + endfacet + facet normal 0.0924496 -0.260652 -0.960996 + outer loop + vertex 663.98 78.2533 2.01758 + vertex 675.161 82.2282 2.01517 + vertex 667.382 76.2741 2.88176 + endloop + endfacet + facet normal 0.0637497 -0.17883 -0.981812 + outer loop + vertex 661.982 82.4706 1.1197 + vertex 673.105 86.4121 1.12403 + vertex 663.98 78.2533 2.01758 + endloop + endfacet + facet normal 0.0631126 -0.178136 -0.98198 + outer loop + vertex 663.98 78.2533 2.01758 + vertex 673.105 86.4121 1.12403 + vertex 675.161 82.2282 2.01517 + endloop + endfacet + facet normal 0.117003 -0.302111 0.946065 + outer loop + vertex 676.577 111.469 23.191 + vertex 682.04 113.486 23.1593 + vertex 677.366 113.41 23.7131 + endloop + endfacet + facet normal 0.117003 -0.302105 0.946067 + outer loop + vertex 677.366 113.41 23.7131 + vertex 682.04 113.486 23.1593 + vertex 682.595 115.379 23.6954 + endloop + endfacet + facet normal 0.122412 -0.307535 0.94363 + outer loop + vertex 671.228 109.548 23.2589 + vertex 676.577 111.469 23.191 + vertex 672.092 111.505 23.7847 + endloop + endfacet + facet normal 0.122588 -0.304027 0.944743 + outer loop + vertex 672.092 111.505 23.7847 + vertex 676.577 111.469 23.191 + vertex 677.366 113.41 23.7131 + endloop + endfacet + facet normal 0.0694216 -0.168489 0.983256 + outer loop + vertex 675.668 106.486 22.2545 + vertex 680.827 108.77 22.2817 + vertex 676.008 109.187 22.6933 + endloop + endfacet + facet normal 0.0688844 -0.173821 0.982365 + outer loop + vertex 676.008 109.187 22.6933 + vertex 680.827 108.77 22.2817 + vertex 681.598 111.197 22.6569 + endloop + endfacet + facet normal 0.0680364 -0.183682 0.980628 + outer loop + vertex 669.788 104.816 22.3497 + vertex 675.668 106.486 22.2545 + vertex 670.634 107.245 22.7459 + endloop + endfacet + facet normal 0.0705535 -0.168615 0.983154 + outer loop + vertex 670.634 107.245 22.7459 + vertex 675.668 106.486 22.2545 + vertex 676.008 109.187 22.6933 + endloop + endfacet + facet normal 0.0961619 -0.239944 0.966012 + outer loop + vertex 670.634 107.245 22.7459 + vertex 676.008 109.187 22.6933 + vertex 671.228 109.548 23.2589 + endloop + endfacet + facet normal 0.0966708 -0.235025 0.96717 + outer loop + vertex 671.228 109.548 23.2589 + vertex 676.008 109.187 22.6933 + vertex 676.577 111.469 23.191 + endloop + endfacet + facet normal 0.0902983 -0.233644 0.96812 + outer loop + vertex 676.008 109.187 22.6933 + vertex 681.598 111.197 22.6569 + vertex 676.577 111.469 23.191 + endloop + endfacet + facet normal 0.0905746 -0.230143 0.968933 + outer loop + vertex 676.577 111.469 23.191 + vertex 681.598 111.197 22.6569 + vertex 682.04 113.486 23.1593 + endloop + endfacet + facet normal 0.0989359 -0.275627 0.95616 + outer loop + vertex 675.12 80.9752 17.9476 + vertex 680.321 83.3199 18.0854 + vertex 671.665 83.2627 18.9645 + endloop + endfacet + facet normal 0.103413 -0.27432 0.956062 + outer loop + vertex 686.365 85.1182 17.9475 + vertex 682.884 87.3557 18.9661 + vertex 680.321 83.3199 18.0854 + endloop + endfacet + facet normal 0.0990211 -0.271789 0.957249 + outer loop + vertex 682.884 87.3557 18.9661 + vertex 671.665 83.2627 18.9645 + vertex 680.321 83.3199 18.0854 + endloop + endfacet + facet normal 0.175025 -0.476449 0.861605 + outer loop + vertex 679.963 78.453 15.8889 + vertex 685.594 80.5294 15.8932 + vertex 680.143 80.6709 17.0786 + endloop + endfacet + facet normal 0.175481 -0.473179 0.863312 + outer loop + vertex 680.143 80.6709 17.0786 + vertex 685.594 80.5294 15.8932 + vertex 685.769 82.7559 17.078 + endloop + endfacet + facet normal 0.173618 -0.475629 0.862342 + outer loop + vertex 674.31 76.395 15.8918 + vertex 679.963 78.453 15.8889 + vertex 674.505 78.6175 17.0785 + endloop + endfacet + facet normal 0.173496 -0.476481 0.861896 + outer loop + vertex 674.505 78.6175 17.0785 + vertex 679.963 78.453 15.8889 + vertex 680.143 80.6709 17.0786 + endloop + endfacet + facet normal 0.136072 -0.373721 0.917506 + outer loop + vertex 674.505 78.6175 17.0785 + vertex 680.143 80.6709 17.0786 + vertex 675.12 80.9752 17.9476 + endloop + endfacet + facet normal 0.137817 -0.359905 0.922754 + outer loop + vertex 675.12 80.9752 17.9476 + vertex 680.143 80.6709 17.0786 + vertex 680.321 83.3199 18.0854 + endloop + endfacet + facet normal 0.133489 -0.359863 0.923406 + outer loop + vertex 680.143 80.6709 17.0786 + vertex 685.769 82.7559 17.078 + vertex 680.321 83.3199 18.0854 + endloop + endfacet + facet normal 0.131482 -0.37151 0.919072 + outer loop + vertex 680.321 83.3199 18.0854 + vertex 685.769 82.7559 17.078 + vertex 686.365 85.1182 17.9475 + endloop + endfacet + facet normal 0.276975 -0.745506 0.606223 + outer loop + vertex 680.207 75.3758 12.7915 + vertex 685.855 77.4713 12.7883 + vertex 680.02 76.6606 14.4571 + endloop + endfacet + facet normal 0.276397 -0.748555 0.602719 + outer loop + vertex 680.02 76.6606 14.4571 + vertex 685.855 77.4713 12.7883 + vertex 685.664 78.7444 14.457 + endloop + endfacet + facet normal 0.270181 -0.749989 0.603754 + outer loop + vertex 674.546 73.3336 12.7881 + vertex 680.207 75.3758 12.7915 + vertex 674.364 74.6108 14.4562 + endloop + endfacet + facet normal 0.270715 -0.74727 0.606878 + outer loop + vertex 674.364 74.6108 14.4562 + vertex 680.207 75.3758 12.7915 + vertex 680.02 76.6606 14.4571 + endloop + endfacet + facet normal 0.220041 -0.607515 0.763222 + outer loop + vertex 674.364 74.6108 14.4562 + vertex 680.02 76.6606 14.4571 + vertex 674.31 76.395 15.8918 + endloop + endfacet + facet normal 0.220475 -0.604466 0.765514 + outer loop + vertex 674.31 76.395 15.8918 + vertex 680.02 76.6606 14.4571 + vertex 679.963 78.453 15.8889 + endloop + endfacet + facet normal 0.223045 -0.604051 0.765097 + outer loop + vertex 680.02 76.6606 14.4571 + vertex 685.664 78.7444 14.457 + vertex 679.963 78.453 15.8889 + endloop + endfacet + facet normal 0.222802 -0.605813 0.763773 + outer loop + vertex 679.963 78.453 15.8889 + vertex 685.664 78.7444 14.457 + vertex 685.594 80.5294 15.8932 + endloop + endfacet + facet normal 0.346768 -0.936384 0.0541921 + outer loop + vertex 680.506 74.6073 8.9982 + vertex 686.151 76.6977 8.99799 + vertex 680.394 74.6781 10.936 + endloop + endfacet + facet normal 0.345511 -0.937097 0.049713 + outer loop + vertex 680.394 74.6781 10.936 + vertex 686.151 76.6977 8.99799 + vertex 686.042 76.7604 10.9365 + endloop + endfacet + facet normal 0.341244 -0.938387 0.0546093 + outer loop + vertex 674.843 72.5479 8.99843 + vertex 680.506 74.6073 8.9982 + vertex 674.73 72.6199 10.9369 + endloop + endfacet + facet normal 0.341056 -0.938494 0.0539401 + outer loop + vertex 674.73 72.6199 10.9369 + vertex 680.506 74.6073 8.9982 + vertex 680.394 74.6781 10.936 + endloop + endfacet + facet normal 0.317564 -0.873719 0.368467 + outer loop + vertex 674.73 72.6199 10.9369 + vertex 680.394 74.6781 10.936 + vertex 674.546 73.3336 12.7881 + endloop + endfacet + facet normal 0.316168 -0.87708 0.36162 + outer loop + vertex 674.546 73.3336 12.7881 + vertex 680.394 74.6781 10.936 + vertex 680.207 75.3758 12.7915 + endloop + endfacet + facet normal 0.322531 -0.874843 0.361419 + outer loop + vertex 680.394 74.6781 10.936 + vertex 686.042 76.7604 10.9365 + vertex 680.207 75.3758 12.7915 + endloop + endfacet + facet normal 0.323739 -0.871891 0.367422 + outer loop + vertex 680.207 75.3758 12.7915 + vertex 686.042 76.7604 10.9365 + vertex 685.855 77.4713 12.7883 + endloop + endfacet + facet normal 0.279219 -0.758347 -0.589022 + outer loop + vertex 680.182 76.4248 5.40782 + vertex 685.837 78.5088 5.40507 + vertex 680.475 75.2107 7.10965 + endloop + endfacet + facet normal 0.282849 -0.761342 -0.583399 + outer loop + vertex 680.475 75.2107 7.10965 + vertex 685.837 78.5088 5.40507 + vertex 686.117 77.3048 7.11218 + endloop + endfacet + facet normal 0.278561 -0.763232 -0.582993 + outer loop + vertex 674.519 74.3597 5.40509 + vertex 680.182 76.4248 5.40782 + vertex 674.808 73.1613 7.11213 + endloop + endfacet + facet normal 0.274514 -0.759855 -0.589289 + outer loop + vertex 674.808 73.1613 7.11213 + vertex 680.182 76.4248 5.40782 + vertex 680.475 75.2107 7.10965 + endloop + endfacet + facet normal 0.324506 -0.897748 -0.297901 + outer loop + vertex 674.808 73.1613 7.11213 + vertex 680.475 75.2107 7.10965 + vertex 674.843 72.5479 8.99843 + endloop + endfacet + facet normal 0.326804 -0.898717 -0.292414 + outer loop + vertex 674.843 72.5479 8.99843 + vertex 680.475 75.2107 7.10965 + vertex 680.506 74.6073 8.9982 + endloop + endfacet + facet normal 0.332939 -0.896646 -0.291851 + outer loop + vertex 680.475 75.2107 7.10965 + vertex 686.117 77.3048 7.11218 + vertex 680.506 74.6073 8.9982 + endloop + endfacet + facet normal 0.331878 -0.896211 -0.294386 + outer loop + vertex 680.506 74.6073 8.9982 + vertex 686.117 77.3048 7.11218 + vertex 686.151 76.6977 8.99799 + endloop + endfacet + facet normal 0.138261 -0.401014 -0.905578 + outer loop + vertex 678.657 80.3193 2.87805 + vertex 684.015 81.8386 3.02331 + vertex 679.519 78.0895 3.99703 + endloop + endfacet + facet normal 0.153194 -0.416473 -0.896148 + outer loop + vertex 679.519 78.0895 3.99703 + vertex 684.015 81.8386 3.02331 + vertex 685.179 80.1779 3.99409 + endloop + endfacet + facet normal 0.161803 -0.415132 -0.895257 + outer loop + vertex 672.704 77.7026 3.0155 + vertex 678.657 80.3193 2.87805 + vertex 673.851 76.0332 3.99691 + endloop + endfacet + facet normal 0.144631 -0.39859 -0.905653 + outer loop + vertex 673.851 76.0332 3.99691 + vertex 678.657 80.3193 2.87805 + vertex 679.519 78.0895 3.99703 + endloop + endfacet + facet normal 0.210105 -0.579061 -0.787746 + outer loop + vertex 673.851 76.0332 3.99691 + vertex 679.519 78.0895 3.99703 + vertex 674.519 74.3597 5.40509 + endloop + endfacet + facet normal 0.212276 -0.581166 -0.785611 + outer loop + vertex 674.519 74.3597 5.40509 + vertex 679.519 78.0895 3.99703 + vertex 680.182 76.4248 5.40782 + endloop + endfacet + facet normal 0.213798 -0.580578 -0.785633 + outer loop + vertex 679.519 78.0895 3.99703 + vertex 685.179 80.1779 3.99409 + vertex 680.182 76.4248 5.40782 + endloop + endfacet + facet normal 0.213496 -0.580287 -0.785931 + outer loop + vertex 680.182 76.4248 5.40782 + vertex 685.179 80.1779 3.99409 + vertex 685.837 78.5088 5.40507 + endloop + endfacet + facet normal 0.101515 -0.26636 -0.958513 + outer loop + vertex 684.015 81.8386 3.02331 + vertex 678.657 80.3193 2.87805 + vertex 686.407 86.3791 2.0149 + endloop + endfacet + facet normal 0.0934218 -0.262977 -0.960268 + outer loop + vertex 672.704 77.7026 3.0155 + vertex 675.161 82.2282 2.01517 + vertex 678.657 80.3193 2.87805 + endloop + endfacet + facet normal 0.0956608 -0.259237 -0.961065 + outer loop + vertex 675.161 82.2282 2.01517 + vertex 686.407 86.3791 2.0149 + vertex 678.657 80.3193 2.87805 + endloop + endfacet + facet normal 0.064998 -0.177219 -0.982023 + outer loop + vertex 673.105 86.4121 1.12403 + vertex 684.275 90.52 1.12202 + vertex 675.161 82.2282 2.01517 + endloop + endfacet + facet normal 0.0656422 -0.177909 -0.981855 + outer loop + vertex 675.161 82.2282 2.01517 + vertex 684.275 90.52 1.12202 + vertex 686.407 86.3791 2.0149 + endloop + endfacet + facet normal 0.119682 -0.307614 0.943954 + outer loop + vertex 687.393 115.66 23.1936 + vertex 691.603 117.617 23.2975 + vertex 687.715 117.386 23.7154 + endloop + endfacet + facet normal 0.119899 -0.316892 0.940853 + outer loop + vertex 687.715 117.386 23.7154 + vertex 691.603 117.617 23.2975 + vertex 692.88 119.321 23.709 + endloop + endfacet + facet normal 0.116593 -0.302008 0.946149 + outer loop + vertex 682.04 113.486 23.1593 + vertex 687.393 115.66 23.1936 + vertex 682.595 115.379 23.6954 + endloop + endfacet + facet normal 0.11672 -0.307213 0.944456 + outer loop + vertex 682.595 115.379 23.6954 + vertex 687.393 115.66 23.1936 + vertex 687.715 117.386 23.7154 + endloop + endfacet + facet normal 0.0594579 -0.165144 0.984476 + outer loop + vertex 687.289 110.569 22.1981 + vertex 695.31 113.825 22.26 + vertex 687.709 113.517 22.6674 + endloop + endfacet + facet normal 0.0597581 -0.174772 0.982794 + outer loop + vertex 687.709 113.517 22.6674 + vertex 695.31 113.825 22.26 + vertex 693.678 116.415 22.8197 + endloop + endfacet + facet normal 0.0603727 -0.171271 0.983372 + outer loop + vertex 680.827 108.77 22.2817 + vertex 687.289 110.569 22.1981 + vertex 681.598 111.197 22.6569 + endloop + endfacet + facet normal 0.0611035 -0.165357 0.984339 + outer loop + vertex 681.598 111.197 22.6569 + vertex 687.289 110.569 22.1981 + vertex 687.709 113.517 22.6674 + endloop + endfacet + facet normal 0.0854061 -0.229293 0.969603 + outer loop + vertex 681.598 111.197 22.6569 + vertex 687.709 113.517 22.6674 + vertex 682.04 113.486 23.1593 + endloop + endfacet + facet normal 0.0854583 -0.22574 0.970432 + outer loop + vertex 682.04 113.486 23.1593 + vertex 687.709 113.517 22.6674 + vertex 687.393 115.66 23.1936 + endloop + endfacet + facet normal 0.0848606 -0.225836 0.970462 + outer loop + vertex 687.709 113.517 22.6674 + vertex 693.678 116.415 22.8197 + vertex 687.393 115.66 23.1936 + endloop + endfacet + facet normal 0.0859682 -0.236345 0.967859 + outer loop + vertex 687.393 115.66 23.1936 + vertex 693.678 116.415 22.8197 + vertex 691.603 117.617 23.2975 + endloop + endfacet + facet normal 0.102654 -0.275397 0.955834 + outer loop + vertex 686.365 85.1182 17.9475 + vertex 691.555 87.5317 18.0856 + vertex 682.884 87.3557 18.9661 + endloop + endfacet + facet normal 0.106937 -0.27313 0.956015 + outer loop + vertex 697.594 89.4151 17.9481 + vertex 694.107 91.612 18.9658 + vertex 691.555 87.5317 18.0856 + endloop + endfacet + facet normal 0.102694 -0.270723 0.957164 + outer loop + vertex 694.107 91.612 18.9658 + vertex 682.884 87.3557 18.9661 + vertex 691.555 87.5317 18.0856 + endloop + endfacet + facet normal 0.181438 -0.473491 0.861908 + outer loop + vertex 691.206 82.6481 15.891 + vertex 696.804 84.7977 15.8936 + vertex 691.38 84.8754 17.0781 + endloop + endfacet + facet normal 0.18176 -0.470971 0.86322 + outer loop + vertex 691.38 84.8754 17.0781 + vertex 696.804 84.7977 15.8936 + vertex 696.987 87.0369 17.0766 + endloop + endfacet + facet normal 0.178937 -0.473097 0.862647 + outer loop + vertex 685.594 80.5294 15.8932 + vertex 691.206 82.6481 15.891 + vertex 685.769 82.7559 17.078 + endloop + endfacet + facet normal 0.178876 -0.473558 0.862407 + outer loop + vertex 685.769 82.7559 17.078 + vertex 691.206 82.6481 15.891 + vertex 691.38 84.8754 17.0781 + endloop + endfacet + facet normal 0.14094 -0.373138 0.917008 + outer loop + vertex 685.769 82.7559 17.078 + vertex 691.38 84.8754 17.0781 + vertex 686.365 85.1182 17.9475 + endloop + endfacet + facet normal 0.142532 -0.359225 0.922302 + outer loop + vertex 686.365 85.1182 17.9475 + vertex 691.38 84.8754 17.0781 + vertex 691.555 87.5317 18.0856 + endloop + endfacet + facet normal 0.138694 -0.359198 0.922898 + outer loop + vertex 691.38 84.8754 17.0781 + vertex 696.987 87.0369 17.0766 + vertex 691.555 87.5317 18.0856 + endloop + endfacet + facet normal 0.136733 -0.371429 0.918338 + outer loop + vertex 691.555 87.5317 18.0856 + vertex 696.987 87.0369 17.0766 + vertex 697.594 89.4151 17.9481 + endloop + endfacet + facet normal 0.28681 -0.742779 0.604995 + outer loop + vertex 691.475 79.58 12.7907 + vertex 697.077 81.7416 12.7885 + vertex 691.279 80.8612 14.4566 + endloop + endfacet + facet normal 0.286286 -0.74571 0.601629 + outer loop + vertex 691.279 80.8612 14.4566 + vertex 697.077 81.7416 12.7885 + vertex 696.878 83.0116 14.4574 + endloop + endfacet + facet normal 0.2802 -0.747461 0.60232 + outer loop + vertex 685.855 77.4713 12.7883 + vertex 691.475 79.58 12.7907 + vertex 685.664 78.7444 14.457 + endloop + endfacet + facet normal 0.280739 -0.744562 0.605651 + outer loop + vertex 685.664 78.7444 14.457 + vertex 691.475 79.58 12.7907 + vertex 691.279 80.8612 14.4566 + endloop + endfacet + facet normal 0.228106 -0.604918 0.762917 + outer loop + vertex 685.664 78.7444 14.457 + vertex 691.279 80.8612 14.4566 + vertex 685.594 80.5294 15.8932 + endloop + endfacet + facet normal 0.22825 -0.603824 0.76374 + outer loop + vertex 685.594 80.5294 15.8932 + vertex 691.279 80.8612 14.4566 + vertex 691.206 82.6481 15.891 + endloop + endfacet + facet normal 0.231555 -0.603253 0.763196 + outer loop + vertex 691.279 80.8612 14.4566 + vertex 696.878 83.0116 14.4574 + vertex 691.206 82.6481 15.891 + endloop + endfacet + facet normal 0.231496 -0.603723 0.762842 + outer loop + vertex 691.206 82.6481 15.891 + vertex 696.878 83.0116 14.4574 + vertex 696.804 84.7977 15.8936 + endloop + endfacet + facet normal 0.3597 -0.931471 0.0545732 + outer loop + vertex 691.77 78.814 8.99824 + vertex 697.372 80.9772 8.99949 + vertex 691.661 78.8855 10.9358 + endloop + endfacet + facet normal 0.35721 -0.932907 0.0456774 + outer loop + vertex 691.661 78.8855 10.9358 + vertex 697.372 80.9772 8.99949 + vertex 697.267 81.0321 10.9371 + endloop + endfacet + facet normal 0.351984 -0.93467 0.0499979 + outer loop + vertex 686.151 76.6977 8.99799 + vertex 691.77 78.814 8.99824 + vertex 686.042 76.7604 10.9365 + endloop + endfacet + facet normal 0.35319 -0.933974 0.0543005 + outer loop + vertex 686.042 76.7604 10.9365 + vertex 691.77 78.814 8.99824 + vertex 691.661 78.8855 10.9358 + endloop + endfacet + facet normal 0.329033 -0.869989 0.367227 + outer loop + vertex 686.042 76.7604 10.9365 + vertex 691.661 78.8855 10.9358 + vertex 685.855 77.4713 12.7883 + endloop + endfacet + facet normal 0.327603 -0.873524 0.360044 + outer loop + vertex 685.855 77.4713 12.7883 + vertex 691.661 78.8855 10.9358 + vertex 691.475 79.58 12.7907 + endloop + endfacet + facet normal 0.333565 -0.871352 0.359832 + outer loop + vertex 691.661 78.8855 10.9358 + vertex 697.267 81.0321 10.9371 + vertex 691.475 79.58 12.7907 + endloop + endfacet + facet normal 0.334964 -0.867838 0.366955 + outer loop + vertex 691.475 79.58 12.7907 + vertex 697.267 81.0321 10.9371 + vertex 697.077 81.7416 12.7885 + endloop + endfacet + facet normal 0.292602 -0.758208 -0.58267 + outer loop + vertex 691.454 80.6274 5.40583 + vertex 697.048 82.7851 5.40727 + vertex 691.734 79.4243 7.11197 + endloop + endfacet + facet normal 0.289161 -0.755446 -0.587952 + outer loop + vertex 691.734 79.4243 7.11197 + vertex 697.048 82.7851 5.40727 + vertex 697.338 81.5711 7.1097 + endloop + endfacet + facet normal 0.286738 -0.76008 -0.583147 + outer loop + vertex 685.837 78.5088 5.40507 + vertex 691.454 80.6274 5.40583 + vertex 686.117 77.3048 7.11218 + endloop + endfacet + facet normal 0.286791 -0.760122 -0.583065 + outer loop + vertex 686.117 77.3048 7.11218 + vertex 691.454 80.6274 5.40583 + vertex 691.734 79.4243 7.11197 + endloop + endfacet + facet normal 0.337431 -0.894304 -0.293871 + outer loop + vertex 686.117 77.3048 7.11218 + vertex 691.734 79.4243 7.11197 + vertex 686.151 76.6977 8.99799 + endloop + endfacet + facet normal 0.336683 -0.894001 -0.295647 + outer loop + vertex 686.151 76.6977 8.99799 + vertex 691.734 79.4243 7.11197 + vertex 691.77 78.814 8.99824 + endloop + endfacet + facet normal 0.341688 -0.892255 -0.295177 + outer loop + vertex 691.734 79.4243 7.11197 + vertex 697.338 81.5711 7.1097 + vertex 691.77 78.814 8.99824 + endloop + endfacet + facet normal 0.345155 -0.89361 -0.286932 + outer loop + vertex 691.77 78.814 8.99824 + vertex 697.338 81.5711 7.1097 + vertex 697.372 80.9772 8.99949 + endloop + endfacet + facet normal 0.143428 -0.400799 -0.904869 + outer loop + vertex 689.941 84.5211 2.87483 + vertex 695.249 86.0972 3.01798 + vertex 690.803 82.2976 3.99636 + endloop + endfacet + facet normal 0.161471 -0.418985 -0.89352 + outer loop + vertex 690.803 82.2976 3.99636 + vertex 695.249 86.0972 3.01798 + vertex 696.396 84.4487 3.99835 + endloop + endfacet + facet normal 0.163179 -0.410148 -0.897302 + outer loop + vertex 684.015 81.8386 3.02331 + vertex 689.941 84.5211 2.87483 + vertex 685.179 80.1779 3.99409 + endloop + endfacet + facet normal 0.150414 -0.398115 -0.90492 + outer loop + vertex 685.179 80.1779 3.99409 + vertex 689.941 84.5211 2.87483 + vertex 690.803 82.2976 3.99636 + endloop + endfacet + facet normal 0.218325 -0.578424 -0.785977 + outer loop + vertex 685.179 80.1779 3.99409 + vertex 690.803 82.2976 3.99636 + vertex 685.837 78.5088 5.40507 + endloop + endfacet + facet normal 0.218216 -0.578321 -0.786083 + outer loop + vertex 685.837 78.5088 5.40507 + vertex 690.803 82.2976 3.99636 + vertex 691.454 80.6274 5.40583 + endloop + endfacet + facet normal 0.222135 -0.576807 -0.786098 + outer loop + vertex 690.803 82.2976 3.99636 + vertex 696.396 84.4487 3.99835 + vertex 691.454 80.6274 5.40583 + endloop + endfacet + facet normal 0.222996 -0.577613 -0.785262 + outer loop + vertex 691.454 80.6274 5.40583 + vertex 696.396 84.4487 3.99835 + vertex 697.048 82.7851 5.40727 + endloop + endfacet + facet normal 0.10412 -0.263513 -0.95902 + outer loop + vertex 695.249 86.0972 3.01798 + vertex 689.941 84.5211 2.87483 + vertex 697.582 90.6668 2.01568 + endloop + endfacet + facet normal 0.0951525 -0.263339 -0.959999 + outer loop + vertex 684.015 81.8386 3.02331 + vertex 686.407 86.3791 2.0149 + vertex 689.941 84.5211 2.87483 + endloop + endfacet + facet normal 0.0987336 -0.257137 -0.961318 + outer loop + vertex 686.407 86.3791 2.0149 + vertex 697.582 90.6668 2.01568 + vertex 689.941 84.5211 2.87483 + endloop + endfacet + facet normal 0.0676913 -0.176864 -0.981905 + outer loop + vertex 684.275 90.52 1.12202 + vertex 695.421 94.7805 1.12302 + vertex 686.407 86.3791 2.0149 + endloop + endfacet + facet normal 0.0680953 -0.177287 -0.981801 + outer loop + vertex 686.407 86.3791 2.0149 + vertex 695.421 94.7805 1.12302 + vertex 697.582 90.6668 2.01568 + endloop + endfacet + facet normal 0.107587 -0.282341 0.953262 + outer loop + vertex 696.957 119.135 23.1912 + vertex 701.974 121.181 23.2309 + vertex 698.112 121.274 23.6943 + endloop + endfacet + facet normal 0.10798 -0.275605 0.955187 + outer loop + vertex 698.112 121.274 23.6943 + vertex 701.974 121.181 23.2309 + vertex 703.314 123.305 23.6924 + endloop + endfacet + facet normal 0.106047 -0.307655 0.94557 + outer loop + vertex 691.603 117.617 23.2975 + vertex 696.957 119.135 23.1912 + vertex 692.88 119.321 23.709 + endloop + endfacet + facet normal 0.108151 -0.282612 0.953118 + outer loop + vertex 692.88 119.321 23.709 + vertex 696.957 119.135 23.1912 + vertex 698.112 121.274 23.6943 + endloop + endfacet + facet normal 0.0861722 -0.236017 0.967921 + outer loop + vertex 691.603 117.617 23.2975 + vertex 693.678 116.415 22.8197 + vertex 696.957 119.135 23.1912 + endloop + endfacet + facet normal 0.0746025 -0.201905 0.97656 + outer loop + vertex 701.974 121.181 23.2309 + vertex 696.957 119.135 23.1912 + vertex 703.948 118.756 22.5787 + endloop + endfacet + facet normal 0.0625217 -0.17306 0.982925 + outer loop + vertex 695.31 113.825 22.26 + vertex 703.948 118.756 22.5787 + vertex 693.678 116.415 22.8197 + endloop + endfacet + facet normal 0.0732109 -0.221024 0.972517 + outer loop + vertex 696.957 119.135 23.1912 + vertex 693.678 116.415 22.8197 + vertex 703.948 118.756 22.5787 + endloop + endfacet + facet normal 0.106083 -0.274364 0.955757 + outer loop + vertex 697.594 89.4151 17.9481 + vertex 702.764 91.9029 18.0884 + vertex 694.107 91.612 18.9658 + endloop + endfacet + facet normal 0.110563 -0.270461 0.956361 + outer loop + vertex 708.734 93.8547 17.9503 + vertex 705.232 96.0043 18.963 + vertex 702.764 91.9029 18.0884 + endloop + endfacet + facet normal 0.106053 -0.268004 0.957563 + outer loop + vertex 705.232 96.0043 18.963 + vertex 694.107 91.612 18.9658 + vertex 702.764 91.9029 18.0884 + endloop + endfacet + facet normal 0.190115 -0.472807 0.860413 + outer loop + vertex 702.403 86.9978 15.8921 + vertex 707.973 89.2329 15.8895 + vertex 702.588 89.2341 17.0802 + endloop + endfacet + facet normal 0.190102 -0.472916 0.860356 + outer loop + vertex 702.588 89.2341 17.0802 + vertex 707.973 89.2329 15.8895 + vertex 708.152 91.4683 17.0788 + endloop + endfacet + facet normal 0.185246 -0.470889 0.862524 + outer loop + vertex 696.804 84.7977 15.8936 + vertex 702.403 86.9978 15.8921 + vertex 696.987 87.0369 17.0766 + endloop + endfacet + facet normal 0.184997 -0.472938 0.861455 + outer loop + vertex 696.987 87.0369 17.0766 + vertex 702.403 86.9978 15.8921 + vertex 702.588 89.2341 17.0802 + endloop + endfacet + facet normal 0.145748 -0.37299 0.916317 + outer loop + vertex 696.987 87.0369 17.0766 + vertex 702.588 89.2341 17.0802 + vertex 697.594 89.4151 17.9481 + endloop + endfacet + facet normal 0.147278 -0.358061 0.922009 + outer loop + vertex 697.594 89.4151 17.9481 + vertex 702.588 89.2341 17.0802 + vertex 702.764 91.9029 18.0884 + endloop + endfacet + facet normal 0.143994 -0.358043 0.922535 + outer loop + vertex 702.588 89.2341 17.0802 + vertex 708.152 91.4683 17.0788 + vertex 702.764 91.9029 18.0884 + endloop + endfacet + facet normal 0.142205 -0.369943 0.918107 + outer loop + vertex 702.764 91.9029 18.0884 + vertex 708.152 91.4683 17.0788 + vertex 708.734 93.8547 17.9503 + endloop + endfacet + facet normal 0.297401 -0.739659 0.603702 + outer loop + vertex 702.672 83.9285 12.791 + vertex 708.237 86.1644 12.7891 + vertex 702.472 85.208 14.4571 + endloop + endfacet + facet normal 0.296846 -0.742989 0.599875 + outer loop + vertex 702.472 85.208 14.4571 + vertex 708.237 86.1644 12.7891 + vertex 708.039 87.4331 14.4584 + endloop + endfacet + facet normal 0.290715 -0.744383 0.601148 + outer loop + vertex 697.077 81.7416 12.7885 + vertex 702.672 83.9285 12.791 + vertex 696.878 83.0116 14.4574 + endloop + endfacet + facet normal 0.291204 -0.741546 0.604408 + outer loop + vertex 696.878 83.0116 14.4574 + vertex 702.672 83.9285 12.791 + vertex 702.472 85.208 14.4571 + endloop + endfacet + facet normal 0.236735 -0.6028 0.761964 + outer loop + vertex 696.878 83.0116 14.4574 + vertex 702.472 85.208 14.4571 + vertex 696.804 84.7977 15.8936 + endloop + endfacet + facet normal 0.236807 -0.602192 0.762422 + outer loop + vertex 696.804 84.7977 15.8936 + vertex 702.472 85.208 14.4571 + vertex 702.403 86.9978 15.8921 + endloop + endfacet + facet normal 0.240282 -0.601577 0.76182 + outer loop + vertex 702.472 85.208 14.4571 + vertex 708.039 87.4331 14.4584 + vertex 702.403 86.9978 15.8921 + endloop + endfacet + facet normal 0.240604 -0.598742 0.763949 + outer loop + vertex 702.403 86.9978 15.8921 + vertex 708.039 87.4331 14.4584 + vertex 707.973 89.2329 15.8895 + endloop + endfacet + facet normal 0.369067 -0.928181 0.0476397 + outer loop + vertex 702.966 83.1759 8.99984 + vertex 708.536 85.3906 8.99868 + vertex 702.862 83.234 10.9364 + endloop + endfacet + facet normal 0.370823 -0.927135 0.0539471 + outer loop + vertex 702.862 83.234 10.9364 + vertex 708.536 85.3906 8.99868 + vertex 708.428 85.4603 10.9372 + endloop + endfacet + facet normal 0.365381 -0.929719 0.046027 + outer loop + vertex 697.372 80.9772 8.99949 + vertex 702.966 83.1759 8.99984 + vertex 697.267 81.0321 10.9371 + endloop + endfacet + facet normal 0.365794 -0.929483 0.0475033 + outer loop + vertex 697.267 81.0321 10.9371 + vertex 702.966 83.1759 8.99984 + vertex 702.862 83.234 10.9364 + endloop + endfacet + facet normal 0.340731 -0.865688 0.366723 + outer loop + vertex 697.267 81.0321 10.9371 + vertex 702.862 83.234 10.9364 + vertex 697.077 81.7416 12.7885 + endloop + endfacet + facet normal 0.33949 -0.868875 0.36028 + outer loop + vertex 697.077 81.7416 12.7885 + vertex 702.862 83.234 10.9364 + vertex 702.672 83.9285 12.791 + endloop + endfacet + facet normal 0.346424 -0.866247 0.360009 + outer loop + vertex 702.862 83.234 10.9364 + vertex 708.428 85.4603 10.9372 + vertex 702.672 83.9285 12.791 + endloop + endfacet + facet normal 0.347284 -0.86401 0.364527 + outer loop + vertex 702.672 83.9285 12.791 + vertex 708.428 85.4603 10.9372 + vertex 708.237 86.1644 12.7891 + endloop + endfacet + facet normal 0.300609 -0.753839 -0.584261 + outer loop + vertex 702.634 84.9771 5.40769 + vertex 708.198 87.1982 5.40483 + vertex 702.927 83.7724 7.1128 + endloop + endfacet + facet normal 0.301189 -0.754291 -0.583379 + outer loop + vertex 702.927 83.7724 7.1128 + vertex 708.198 87.1982 5.40483 + vertex 708.493 85.9968 7.11066 + endloop + endfacet + facet normal 0.295681 -0.753265 -0.587507 + outer loop + vertex 697.048 82.7851 5.40727 + vertex 702.634 84.9771 5.40769 + vertex 697.338 81.5711 7.1097 + endloop + endfacet + facet normal 0.297674 -0.754844 -0.584467 + outer loop + vertex 697.338 81.5711 7.1097 + vertex 702.634 84.9771 5.40769 + vertex 702.927 83.7724 7.1128 + endloop + endfacet + facet normal 0.351301 -0.8914 -0.286345 + outer loop + vertex 697.338 81.5711 7.1097 + vertex 702.927 83.7724 7.1128 + vertex 697.372 80.9772 8.99949 + endloop + endfacet + facet normal 0.350176 -0.890976 -0.289029 + outer loop + vertex 697.372 80.9772 8.99949 + vertex 702.927 83.7724 7.1128 + vertex 702.966 83.1759 8.99984 + endloop + endfacet + facet normal 0.35519 -0.889143 -0.288556 + outer loop + vertex 702.927 83.7724 7.1128 + vertex 708.493 85.9968 7.11066 + vertex 702.966 83.1759 8.99984 + endloop + endfacet + facet normal 0.353172 -0.888386 -0.293326 + outer loop + vertex 702.966 83.1759 8.99984 + vertex 708.493 85.9968 7.11066 + vertex 708.536 85.3906 8.99868 + endloop + endfacet + facet normal 0.148284 -0.400369 -0.904277 + outer loop + vertex 701.102 88.8469 2.87647 + vertex 706.364 90.4835 3.01473 + vertex 701.973 86.6353 3.99843 + endloop + endfacet + facet normal 0.168082 -0.419801 -0.891917 + outer loop + vertex 701.973 86.6353 3.99843 + vertex 706.364 90.4835 3.01473 + vertex 707.523 88.8562 3.99903 + endloop + endfacet + facet normal 0.17205 -0.412296 -0.894657 + outer loop + vertex 695.249 86.0972 3.01798 + vertex 701.102 88.8469 2.87647 + vertex 696.396 84.4487 3.99835 + endloop + endfacet + facet normal 0.155839 -0.397412 -0.904311 + outer loop + vertex 696.396 84.4487 3.99835 + vertex 701.102 88.8469 2.87647 + vertex 701.973 86.6353 3.99843 + endloop + endfacet + facet normal 0.226029 -0.576427 -0.785266 + outer loop + vertex 696.396 84.4487 3.99835 + vertex 701.973 86.6353 3.99843 + vertex 697.048 82.7851 5.40727 + endloop + endfacet + facet normal 0.226441 -0.576808 -0.784867 + outer loop + vertex 697.048 82.7851 5.40727 + vertex 701.973 86.6353 3.99843 + vertex 702.634 84.9771 5.40769 + endloop + endfacet + facet normal 0.230286 -0.575279 -0.784871 + outer loop + vertex 701.973 86.6353 3.99843 + vertex 707.523 88.8562 3.99903 + vertex 702.634 84.9771 5.40769 + endloop + endfacet + facet normal 0.228625 -0.573765 -0.786463 + outer loop + vertex 702.634 84.9771 5.40769 + vertex 707.523 88.8562 3.99903 + vertex 708.198 87.1982 5.40483 + endloop + endfacet + facet normal 0.106193 -0.260361 -0.959654 + outer loop + vertex 706.364 90.4835 3.01473 + vertex 701.102 88.8469 2.87647 + vertex 708.618 95.0735 2.0188 + endloop + endfacet + facet normal 0.0996016 -0.261436 -0.960068 + outer loop + vertex 695.249 86.0972 3.01798 + vertex 697.582 90.6668 2.01568 + vertex 701.102 88.8469 2.87647 + endloop + endfacet + facet normal 0.102575 -0.256202 -0.961165 + outer loop + vertex 697.582 90.6668 2.01568 + vertex 708.618 95.0735 2.0188 + vertex 701.102 88.8469 2.87647 + endloop + endfacet + facet normal 0.0699882 -0.176302 -0.981845 + outer loop + vertex 695.421 94.7805 1.12302 + vertex 706.443 99.1643 1.12147 + vertex 697.582 90.6668 2.01568 + endloop + endfacet + facet normal 0.0711453 -0.177478 -0.98155 + outer loop + vertex 697.582 90.6668 2.01568 + vertex 706.443 99.1643 1.12147 + vertex 708.618 95.0735 2.0188 + endloop + endfacet + facet normal 0.109261 -0.259385 0.959573 + outer loop + vertex 707.71 123.06 23.1467 + vertex 712.788 125.567 23.2462 + vertex 708.477 125.439 23.7024 + endloop + endfacet + facet normal 0.109266 -0.265911 0.957785 + outer loop + vertex 708.477 125.439 23.7024 + vertex 712.788 125.567 23.2462 + vertex 713.614 127.619 23.7215 + endloop + endfacet + facet normal 0.10348 -0.273035 0.956422 + outer loop + vertex 701.974 121.181 23.2309 + vertex 707.71 123.06 23.1467 + vertex 703.314 123.305 23.6924 + endloop + endfacet + facet normal 0.104804 -0.258143 0.960405 + outer loop + vertex 703.314 123.305 23.6924 + vertex 707.71 123.06 23.1467 + vertex 708.477 125.439 23.7024 + endloop + endfacet + facet normal 0.078185 -0.197138 0.977253 + outer loop + vertex 712.788 125.567 23.2462 + vertex 707.71 123.06 23.1467 + vertex 715.91 123.662 22.6122 + endloop + endfacet + facet normal 0.0792679 -0.198213 0.976948 + outer loop + vertex 701.974 121.181 23.2309 + vertex 703.948 118.756 22.5787 + vertex 707.71 123.06 23.1467 + endloop + endfacet + facet normal 0.0781954 -0.197312 0.977217 + outer loop + vertex 703.948 118.756 22.5787 + vertex 715.91 123.662 22.6122 + vertex 707.71 123.06 23.1467 + endloop + endfacet + facet normal 0.109775 -0.271631 0.95612 + outer loop + vertex 708.734 93.8547 17.9503 + vertex 713.746 96.3652 18.0881 + vertex 705.232 96.0043 18.963 + endloop + endfacet + facet normal 0.115457 -0.270356 0.955812 + outer loop + vertex 719.518 98.3342 17.9477 + vertex 716.126 100.484 18.9656 + vertex 713.746 96.3652 18.0881 + endloop + endfacet + facet normal 0.109718 -0.267363 0.957329 + outer loop + vertex 716.126 100.484 18.9656 + vertex 705.232 96.0043 18.963 + vertex 713.746 96.3652 18.0881 + endloop + endfacet + facet normal 0.197319 -0.472893 0.858741 + outer loop + vertex 713.461 91.4747 15.8892 + vertex 718.838 93.7162 15.8882 + vertex 713.621 93.7044 17.0805 + endloop + endfacet + facet normal 0.197379 -0.472385 0.859007 + outer loop + vertex 713.621 93.7044 17.0805 + vertex 718.838 93.7162 15.8882 + vertex 718.976 95.9418 17.0802 + endloop + endfacet + facet normal 0.193195 -0.472823 0.859717 + outer loop + vertex 707.973 89.2329 15.8895 + vertex 713.461 91.4747 15.8892 + vertex 708.152 91.4683 17.0788 + endloop + endfacet + facet normal 0.193168 -0.473054 0.859597 + outer loop + vertex 708.152 91.4683 17.0788 + vertex 713.461 91.4747 15.8892 + vertex 713.621 93.7044 17.0805 + endloop + endfacet + facet normal 0.151609 -0.37146 0.915987 + outer loop + vertex 708.152 91.4683 17.0788 + vertex 713.621 93.7044 17.0805 + vertex 708.734 93.8547 17.9503 + endloop + endfacet + facet normal 0.153104 -0.356254 0.92176 + outer loop + vertex 708.734 93.8547 17.9503 + vertex 713.621 93.7044 17.0805 + vertex 713.746 96.3652 18.0881 + endloop + endfacet + facet normal 0.14889 -0.356309 0.922429 + outer loop + vertex 713.621 93.7044 17.0805 + vertex 718.976 95.9418 17.0802 + vertex 713.746 96.3652 18.0881 + endloop + endfacet + facet normal 0.147345 -0.366485 0.918683 + outer loop + vertex 713.746 96.3652 18.0881 + vertex 718.976 95.9418 17.0802 + vertex 719.518 98.3342 17.9477 + endloop + endfacet + facet normal 0.307959 -0.739412 0.59869 + outer loop + vertex 713.73 88.4045 12.7895 + vertex 719.121 90.6495 12.7893 + vertex 713.531 89.6738 14.4592 + endloop + endfacet + facet normal 0.307967 -0.739367 0.598743 + outer loop + vertex 713.531 89.6738 14.4592 + vertex 719.121 90.6495 12.7893 + vertex 718.919 91.9176 14.4588 + endloop + endfacet + facet normal 0.302247 -0.741318 0.599246 + outer loop + vertex 708.237 86.1644 12.7891 + vertex 713.73 88.4045 12.7895 + vertex 708.039 87.4331 14.4584 + endloop + endfacet + facet normal 0.302266 -0.741205 0.599376 + outer loop + vertex 708.039 87.4331 14.4584 + vertex 713.73 88.4045 12.7895 + vertex 713.531 89.6738 14.4592 + endloop + endfacet + facet normal 0.243891 -0.598158 0.763364 + outer loop + vertex 708.039 87.4331 14.4584 + vertex 713.531 89.6738 14.4592 + vertex 707.973 89.2329 15.8895 + endloop + endfacet + facet normal 0.243998 -0.597202 0.764078 + outer loop + vertex 707.973 89.2329 15.8895 + vertex 713.531 89.6738 14.4592 + vertex 713.461 91.4747 15.8892 + endloop + endfacet + facet normal 0.248435 -0.596394 0.763278 + outer loop + vertex 713.531 89.6738 14.4592 + vertex 718.919 91.9176 14.4588 + vertex 713.461 91.4747 15.8892 + endloop + endfacet + facet normal 0.248511 -0.595725 0.763776 + outer loop + vertex 713.461 91.4747 15.8892 + vertex 718.919 91.9176 14.4588 + vertex 718.838 93.7162 15.8882 + endloop + endfacet + facet normal 0.382056 -0.92299 0.0460789 + outer loop + vertex 714.022 87.6462 8.99971 + vertex 719.417 89.879 8.99872 + vertex 713.921 87.701 10.9379 + endloop + endfacet + facet normal 0.384231 -0.921673 0.0537222 + outer loop + vertex 713.921 87.701 10.9379 + vertex 719.417 89.879 8.99872 + vertex 719.311 89.948 10.937 + endloop + endfacet + facet normal 0.379695 -0.923516 0.0543099 + outer loop + vertex 708.536 85.3906 8.99868 + vertex 714.022 87.6462 8.99971 + vertex 708.428 85.4603 10.9372 + endloop + endfacet + facet normal 0.377334 -0.92494 0.045887 + outer loop + vertex 708.428 85.4603 10.9372 + vertex 714.022 87.6462 8.99971 + vertex 713.921 87.701 10.9379 + endloop + endfacet + facet normal 0.351738 -0.862288 0.364334 + outer loop + vertex 708.428 85.4603 10.9372 + vertex 713.921 87.701 10.9379 + vertex 708.237 86.1644 12.7891 + endloop + endfacet + facet normal 0.351666 -0.862477 0.363957 + outer loop + vertex 708.237 86.1644 12.7891 + vertex 713.921 87.701 10.9379 + vertex 713.73 88.4045 12.7895 + endloop + endfacet + facet normal 0.358485 -0.859798 0.363643 + outer loop + vertex 713.921 87.701 10.9379 + vertex 719.311 89.948 10.937 + vertex 713.73 88.4045 12.7895 + endloop + endfacet + facet normal 0.358295 -0.860293 0.362658 + outer loop + vertex 713.73 88.4045 12.7895 + vertex 719.311 89.948 10.937 + vertex 719.121 90.6495 12.7893 + endloop + endfacet + facet normal 0.311629 -0.748235 -0.585689 + outer loop + vertex 713.684 89.4483 5.40831 + vertex 719.075 91.6942 5.4072 + vertex 713.984 88.2408 7.11028 + endloop + endfacet + facet normal 0.312094 -0.74858 -0.585 + outer loop + vertex 713.984 88.2408 7.11028 + vertex 719.075 91.6942 5.4072 + vertex 719.371 90.4868 7.1102 + endloop + endfacet + facet normal 0.308658 -0.751686 -0.582837 + outer loop + vertex 708.198 87.1982 5.40483 + vertex 713.684 89.4483 5.40831 + vertex 708.493 85.9968 7.11066 + endloop + endfacet + facet normal 0.306507 -0.750047 -0.586074 + outer loop + vertex 708.493 85.9968 7.11066 + vertex 713.684 89.4483 5.40831 + vertex 713.984 88.2408 7.11028 + endloop + endfacet + facet normal 0.361763 -0.885197 -0.292497 + outer loop + vertex 708.493 85.9968 7.11066 + vertex 713.984 88.2408 7.11028 + vertex 708.536 85.3906 8.99868 + endloop + endfacet + facet normal 0.36439 -0.886134 -0.286333 + outer loop + vertex 708.536 85.3906 8.99868 + vertex 713.984 88.2408 7.11028 + vertex 714.022 87.6462 8.99971 + endloop + endfacet + facet normal 0.368753 -0.884468 -0.285899 + outer loop + vertex 713.984 88.2408 7.11028 + vertex 719.371 90.4868 7.1102 + vertex 714.022 87.6462 8.99971 + endloop + endfacet + facet normal 0.365601 -0.883387 -0.293196 + outer loop + vertex 714.022 87.6462 8.99971 + vertex 719.371 90.4868 7.1102 + vertex 719.417 89.879 8.99872 + endloop + endfacet + facet normal 0.155021 -0.397885 -0.904244 + outer loop + vertex 712.13 93.2941 2.87299 + vertex 717.283 94.9735 3.01736 + vertex 713.024 91.0941 3.99424 + endloop + endfacet + facet normal 0.174869 -0.416618 -0.892105 + outer loop + vertex 713.024 91.0941 3.99424 + vertex 717.283 94.9735 3.01736 + vertex 718.421 93.3482 3.99941 + endloop + endfacet + facet normal 0.17917 -0.412625 -0.893106 + outer loop + vertex 706.364 90.4835 3.01473 + vertex 712.13 93.2941 2.87299 + vertex 707.523 88.8562 3.99903 + endloop + endfacet + facet normal 0.16022 -0.395781 -0.90426 + outer loop + vertex 707.523 88.8562 3.99903 + vertex 712.13 93.2941 2.87299 + vertex 713.024 91.0941 3.99424 + endloop + endfacet + facet normal 0.232148 -0.572338 -0.786471 + outer loop + vertex 707.523 88.8562 3.99903 + vertex 713.024 91.0941 3.99424 + vertex 708.198 87.1982 5.40483 + endloop + endfacet + facet normal 0.237009 -0.576681 -0.781835 + outer loop + vertex 708.198 87.1982 5.40483 + vertex 713.024 91.0941 3.99424 + vertex 713.684 89.4483 5.40831 + endloop + endfacet + facet normal 0.240949 -0.57508 -0.78181 + outer loop + vertex 713.024 91.0941 3.99424 + vertex 718.421 93.3482 3.99941 + vertex 713.684 89.4483 5.40831 + endloop + endfacet + facet normal 0.238583 -0.573015 -0.784048 + outer loop + vertex 713.684 89.4483 5.40831 + vertex 718.421 93.3482 3.99941 + vertex 719.075 91.6942 5.4072 + endloop + endfacet + facet normal 0.112169 -0.261736 -0.958599 + outer loop + vertex 717.283 94.9735 3.01736 + vertex 712.13 93.2941 2.87299 + vertex 719.473 99.5868 2.01399 + endloop + endfacet + facet normal 0.102502 -0.258732 -0.960495 + outer loop + vertex 706.364 90.4835 3.01473 + vertex 708.618 95.0735 2.0188 + vertex 712.13 93.2941 2.87299 + endloop + endfacet + facet normal 0.105162 -0.253955 -0.961482 + outer loop + vertex 708.618 95.0735 2.0188 + vertex 719.473 99.5868 2.01399 + vertex 712.13 93.2941 2.87299 + endloop + endfacet + facet normal 0.0732553 -0.176366 -0.981595 + outer loop + vertex 706.443 99.1643 1.12147 + vertex 717.309 103.667 1.12342 + vertex 708.618 95.0735 2.0188 + endloop + endfacet + facet normal 0.0726429 -0.175762 -0.981749 + outer loop + vertex 708.618 95.0735 2.0188 + vertex 717.309 103.667 1.12342 + vertex 719.473 99.5868 2.01399 + endloop + endfacet + facet normal 0.114064 -0.258052 0.959374 + outer loop + vertex 718.414 127.597 23.1807 + vertex 723.213 130.108 23.2854 + vertex 718.742 129.844 23.7461 + endloop + endfacet + facet normal 0.114194 -0.262306 0.958204 + outer loop + vertex 718.742 129.844 23.7461 + vertex 723.213 130.108 23.2854 + vertex 723.913 132.129 23.7553 + endloop + endfacet + facet normal 0.10681 -0.265041 0.958303 + outer loop + vertex 712.788 125.567 23.2462 + vertex 718.414 127.597 23.1807 + vertex 713.614 127.619 23.7215 + endloop + endfacet + facet normal 0.107079 -0.257286 0.960384 + outer loop + vertex 713.614 127.619 23.7215 + vertex 718.414 127.597 23.1807 + vertex 718.742 129.844 23.7461 + endloop + endfacet + facet normal 0.0837572 -0.20082 0.976041 + outer loop + vertex 723.213 130.108 23.2854 + vertex 718.414 127.597 23.1807 + vertex 726.694 128.372 22.6295 + endloop + endfacet + facet normal 0.0809647 -0.192794 0.977893 + outer loop + vertex 712.788 125.567 23.2462 + vertex 715.91 123.662 22.6122 + vertex 718.414 127.597 23.1807 + endloop + endfacet + facet normal 0.0832271 -0.194167 0.977432 + outer loop + vertex 715.91 123.662 22.6122 + vertex 726.694 128.372 22.6295 + vertex 718.414 127.597 23.1807 + endloop + endfacet + facet normal 0.114819 -0.271275 0.955629 + outer loop + vertex 719.518 98.3342 17.9477 + vertex 724.417 100.888 18.0841 + vertex 716.126 100.484 18.9656 + endloop + endfacet + facet normal 0.11956 -0.268117 0.955939 + outer loop + vertex 730.144 102.939 17.9432 + vertex 726.858 105.088 18.9567 + vertex 724.417 100.888 18.0841 + endloop + endfacet + facet normal 0.114713 -0.26557 0.957243 + outer loop + vertex 726.858 105.088 18.9567 + vertex 716.126 100.484 18.9656 + vertex 724.417 100.888 18.0841 + endloop + endfacet + facet normal 0.204979 -0.467867 0.8597 + outer loop + vertex 724.127 95.9603 15.8913 + vertex 729.419 98.2682 15.8857 + vertex 724.266 98.2005 17.0774 + endloop + endfacet + facet normal 0.204692 -0.470544 0.858306 + outer loop + vertex 724.266 98.2005 17.0774 + vertex 729.419 98.2682 15.8857 + vertex 729.557 100.504 17.0787 + endloop + endfacet + facet normal 0.199854 -0.472268 0.8585 + outer loop + vertex 718.838 93.7162 15.8882 + vertex 724.127 95.9603 15.8913 + vertex 718.976 95.9418 17.0802 + endloop + endfacet + facet normal 0.200339 -0.468094 0.86067 + outer loop + vertex 718.976 95.9418 17.0802 + vertex 724.127 95.9603 15.8913 + vertex 724.266 98.2005 17.0774 + endloop + endfacet + facet normal 0.157616 -0.367976 0.916379 + outer loop + vertex 718.976 95.9418 17.0802 + vertex 724.266 98.2005 17.0774 + vertex 719.518 98.3342 17.9477 + endloop + endfacet + facet normal 0.158961 -0.354134 0.921586 + outer loop + vertex 719.518 98.3342 17.9477 + vertex 724.266 98.2005 17.0774 + vertex 724.417 100.888 18.0841 + endloop + endfacet + facet normal 0.153998 -0.354166 0.922416 + outer loop + vertex 724.266 98.2005 17.0774 + vertex 729.557 100.504 17.0787 + vertex 724.417 100.888 18.0841 + endloop + endfacet + facet normal 0.152689 -0.36313 0.919143 + outer loop + vertex 724.417 100.888 18.0841 + vertex 729.557 100.504 17.0787 + vertex 730.144 102.939 17.9432 + endloop + endfacet + facet normal 0.319954 -0.735127 0.597677 + outer loop + vertex 724.432 92.9086 12.7887 + vertex 729.734 95.2152 12.7875 + vertex 724.224 94.1749 14.4573 + endloop + endfacet + facet normal 0.319951 -0.735143 0.597659 + outer loop + vertex 724.224 94.1749 14.4573 + vertex 729.734 95.2152 12.7875 + vertex 729.519 96.4776 14.4552 + endloop + endfacet + facet normal 0.313759 -0.737507 0.598029 + outer loop + vertex 719.121 90.6495 12.7893 + vertex 724.432 92.9086 12.7887 + vertex 718.919 91.9176 14.4588 + endloop + endfacet + facet normal 0.31382 -0.737144 0.598445 + outer loop + vertex 718.919 91.9176 14.4588 + vertex 724.432 92.9086 12.7887 + vertex 724.224 94.1749 14.4573 + endloop + endfacet + facet normal 0.253308 -0.594818 0.762907 + outer loop + vertex 718.919 91.9176 14.4588 + vertex 724.224 94.1749 14.4573 + vertex 718.838 93.7162 15.8882 + endloop + endfacet + facet normal 0.253013 -0.597437 0.760955 + outer loop + vertex 718.838 93.7162 15.8882 + vertex 724.224 94.1749 14.4573 + vertex 724.127 95.9603 15.8913 + endloop + endfacet + facet normal 0.259562 -0.596132 0.759773 + outer loop + vertex 724.224 94.1749 14.4573 + vertex 729.519 96.4776 14.4552 + vertex 724.127 95.9603 15.8913 + endloop + endfacet + facet normal 0.259803 -0.593795 0.761518 + outer loop + vertex 724.127 95.9603 15.8913 + vertex 729.519 96.4776 14.4552 + vertex 729.419 98.2682 15.8857 + endloop + endfacet + facet normal 0.399186 -0.915404 0.0518296 + outer loop + vertex 724.726 92.1439 8.99838 + vertex 730.03 94.4566 8.99858 + vertex 724.623 92.2086 10.9367 + endloop + endfacet + facet normal 0.398233 -0.916002 0.048478 + outer loop + vertex 724.623 92.2086 10.9367 + vertex 730.03 94.4566 8.99858 + vertex 729.927 94.5147 10.9359 + endloop + endfacet + facet normal 0.391796 -0.918465 0.0540198 + outer loop + vertex 719.417 89.879 8.99872 + vertex 724.726 92.1439 8.99838 + vertex 719.311 89.948 10.937 + endloop + endfacet + facet normal 0.391081 -0.918913 0.0515149 + outer loop + vertex 719.311 89.948 10.937 + vertex 724.726 92.1439 8.99838 + vertex 724.623 92.2086 10.9367 + endloop + endfacet + facet normal 0.365007 -0.857605 0.36233 + outer loop + vertex 719.311 89.948 10.937 + vertex 724.623 92.2086 10.9367 + vertex 719.121 90.6495 12.7893 + endloop + endfacet + facet normal 0.364917 -0.85784 0.361864 + outer loop + vertex 719.121 90.6495 12.7893 + vertex 724.623 92.2086 10.9367 + vertex 724.432 92.9086 12.7887 + endloop + endfacet + facet normal 0.371778 -0.855038 0.361512 + outer loop + vertex 724.623 92.2086 10.9367 + vertex 729.927 94.5147 10.9359 + vertex 724.432 92.9086 12.7887 + endloop + endfacet + facet normal 0.371911 -0.854684 0.362213 + outer loop + vertex 724.432 92.9086 12.7887 + vertex 729.927 94.5147 10.9359 + vertex 729.734 95.2152 12.7875 + endloop + endfacet + facet normal 0.324876 -0.745987 -0.581343 + outer loop + vertex 724.383 93.9508 5.40633 + vertex 729.676 96.2556 5.40696 + vertex 724.677 92.7504 7.1113 + endloop + endfacet + facet normal 0.323455 -0.744975 -0.583429 + outer loop + vertex 724.677 92.7504 7.1113 + vertex 729.676 96.2556 5.40696 + vertex 729.98 95.0537 7.11035 + endloop + endfacet + facet normal 0.31735 -0.746697 -0.584579 + outer loop + vertex 719.075 91.6942 5.4072 + vertex 724.383 93.9508 5.40633 + vertex 719.371 90.4868 7.1102 + endloop + endfacet + facet normal 0.319224 -0.748052 -0.58182 + outer loop + vertex 719.371 90.4868 7.1102 + vertex 724.383 93.9508 5.40633 + vertex 724.677 92.7504 7.1113 + endloop + endfacet + facet normal 0.375295 -0.879636 -0.292224 + outer loop + vertex 719.371 90.4868 7.1102 + vertex 724.677 92.7504 7.1113 + vertex 719.417 89.879 8.99872 + endloop + endfacet + facet normal 0.375196 -0.879603 -0.29245 + outer loop + vertex 719.417 89.879 8.99872 + vertex 724.677 92.7504 7.1113 + vertex 724.726 92.1439 8.99838 + endloop + endfacet + facet normal 0.380982 -0.877308 -0.291862 + outer loop + vertex 724.677 92.7504 7.1113 + vertex 729.98 95.0537 7.11035 + vertex 724.726 92.1439 8.99838 + endloop + endfacet + facet normal 0.382846 -0.877905 -0.287597 + outer loop + vertex 724.726 92.1439 8.99838 + vertex 729.98 95.0537 7.11035 + vertex 730.03 94.4566 8.99858 + endloop + endfacet + facet normal 0.161686 -0.39616 -0.903833 + outer loop + vertex 722.898 97.8183 2.87479 + vertex 727.925 99.5359 3.02132 + vertex 723.74 95.6049 3.99563 + endloop + endfacet + facet normal 0.179512 -0.41248 -0.893105 + outer loop + vertex 723.74 95.6049 3.99563 + vertex 727.925 99.5359 3.02132 + vertex 729.029 97.9046 3.99662 + endloop + endfacet + facet normal 0.185087 -0.410056 -0.893083 + outer loop + vertex 717.283 94.9735 3.01736 + vertex 722.898 97.8183 2.87479 + vertex 718.421 93.3482 3.99941 + endloop + endfacet + facet normal 0.166621 -0.394251 -0.903772 + outer loop + vertex 718.421 93.3482 3.99941 + vertex 722.898 97.8183 2.87479 + vertex 723.74 95.6049 3.99563 + endloop + endfacet + facet normal 0.241968 -0.571646 -0.784011 + outer loop + vertex 718.421 93.3482 3.99941 + vertex 723.74 95.6049 3.99563 + vertex 719.075 91.6942 5.4072 + endloop + endfacet + facet normal 0.243428 -0.572895 -0.782646 + outer loop + vertex 719.075 91.6942 5.4072 + vertex 723.74 95.6049 3.99563 + vertex 724.383 93.9508 5.40633 + endloop + endfacet + facet normal 0.248369 -0.570896 -0.782554 + outer loop + vertex 723.74 95.6049 3.99563 + vertex 729.029 97.9046 3.99662 + vertex 724.383 93.9508 5.40633 + endloop + endfacet + facet normal 0.248835 -0.571288 -0.782119 + outer loop + vertex 724.383 93.9508 5.40633 + vertex 729.029 97.9046 3.99662 + vertex 729.676 96.2556 5.40696 + endloop + endfacet + facet normal 0.117369 -0.261822 -0.957953 + outer loop + vertex 727.925 99.5359 3.02132 + vertex 722.898 97.8183 2.87479 + vertex 730.168 104.225 2.01436 + endloop + endfacet + facet normal 0.107168 -0.259612 -0.959748 + outer loop + vertex 717.283 94.9735 3.01736 + vertex 719.473 99.5868 2.01399 + vertex 722.898 97.8183 2.87479 + endloop + endfacet + facet normal 0.110266 -0.254153 -0.960858 + outer loop + vertex 719.473 99.5868 2.01399 + vertex 730.168 104.225 2.01436 + vertex 722.898 97.8183 2.87479 + endloop + endfacet + facet normal 0.0752591 -0.174386 -0.981797 + outer loop + vertex 717.309 103.667 1.12342 + vertex 728.044 108.306 1.12227 + vertex 719.473 99.5868 2.01399 + endloop + endfacet + facet normal 0.0759617 -0.175058 -0.981623 + outer loop + vertex 719.473 99.5868 2.01399 + vertex 728.044 108.306 1.12227 + vertex 730.168 104.225 2.01436 + endloop + endfacet + facet normal 0.120434 -0.251858 0.960241 + outer loop + vertex 728.874 132.257 23.2034 + vertex 733.734 134.884 23.283 + vertex 729.109 134.464 23.753 + endloop + endfacet + facet normal 0.121098 -0.262454 0.957316 + outer loop + vertex 729.109 134.464 23.753 + vertex 733.734 134.884 23.283 + vertex 734.358 136.889 23.7537 + endloop + endfacet + facet normal 0.113346 -0.262051 0.958375 + outer loop + vertex 723.213 130.108 23.2854 + vertex 728.874 132.257 23.2034 + vertex 723.913 132.129 23.7553 + endloop + endfacet + facet normal 0.113389 -0.251354 0.96123 + outer loop + vertex 723.913 132.129 23.7553 + vertex 728.874 132.257 23.2034 + vertex 729.109 134.464 23.753 + endloop + endfacet + facet normal 0.0924034 -0.200473 0.975332 + outer loop + vertex 733.734 134.884 23.283 + vertex 728.874 132.257 23.2034 + vertex 737.252 133.211 22.6057 + endloop + endfacet + facet normal 0.0876105 -0.193522 0.977176 + outer loop + vertex 723.213 130.108 23.2854 + vertex 726.694 128.372 22.6295 + vertex 728.874 132.257 23.2034 + endloop + endfacet + facet normal 0.0919449 -0.195828 0.976318 + outer loop + vertex 726.694 128.372 22.6295 + vertex 737.252 133.211 22.6057 + vertex 728.874 132.257 23.2034 + endloop + endfacet + facet normal 0.119133 -0.268716 0.955824 + outer loop + vertex 730.144 102.939 17.9432 + vertex 735.129 105.627 18.0773 + vertex 726.858 105.088 18.9567 + endloop + endfacet + facet normal 0.123828 -0.264372 0.956438 + outer loop + vertex 740.939 107.825 17.9328 + vertex 737.598 109.896 18.9379 + vertex 735.129 105.627 18.0773 + endloop + endfacet + facet normal 0.118889 -0.261786 0.957775 + outer loop + vertex 737.598 109.896 18.9379 + vertex 726.858 105.088 18.9567 + vertex 735.129 105.627 18.0773 + endloop + endfacet + facet normal 0.213415 -0.465325 0.859027 + outer loop + vertex 734.768 100.64 15.887 + vertex 740.2 103.115 15.8786 + vertex 734.926 102.901 17.0725 + endloop + endfacet + facet normal 0.213338 -0.466315 0.858509 + outer loop + vertex 734.926 102.901 17.0725 + vertex 740.2 103.115 15.8786 + vertex 740.352 105.373 17.0668 + endloop + endfacet + facet normal 0.20832 -0.470357 0.857535 + outer loop + vertex 729.419 98.2682 15.8857 + vertex 734.768 100.64 15.887 + vertex 729.557 100.504 17.0787 + endloop + endfacet + facet normal 0.208771 -0.465538 0.860052 + outer loop + vertex 729.557 100.504 17.0787 + vertex 734.768 100.64 15.887 + vertex 734.926 102.901 17.0725 + endloop + endfacet + facet normal 0.163923 -0.364901 0.916503 + outer loop + vertex 729.557 100.504 17.0787 + vertex 734.926 102.901 17.0725 + vertex 730.144 102.939 17.9432 + endloop + endfacet + facet normal 0.164916 -0.351924 0.921386 + outer loop + vertex 730.144 102.939 17.9432 + vertex 734.926 102.901 17.0725 + vertex 735.129 105.627 18.0773 + endloop + endfacet + facet normal 0.16128 -0.351894 0.922041 + outer loop + vertex 734.926 102.901 17.0725 + vertex 740.352 105.373 17.0668 + vertex 735.129 105.627 18.0773 + endloop + endfacet + facet normal 0.160009 -0.362512 0.918141 + outer loop + vertex 735.129 105.627 18.0773 + vertex 740.352 105.373 17.0668 + vertex 740.939 107.825 17.9328 + endloop + endfacet + facet normal 0.331014 -0.732253 0.595177 + outer loop + vertex 735.095 97.5951 12.786 + vertex 740.524 100.05 12.7867 + vertex 734.873 98.8513 14.455 + endloop + endfacet + facet normal 0.331513 -0.728353 0.599668 + outer loop + vertex 734.873 98.8513 14.455 + vertex 740.524 100.05 12.7867 + vertex 740.301 101.318 14.4507 + endloop + endfacet + facet normal 0.325661 -0.733219 0.596938 + outer loop + vertex 729.734 95.2152 12.7875 + vertex 735.095 97.5951 12.786 + vertex 729.519 96.4776 14.4552 + endloop + endfacet + facet normal 0.325528 -0.734145 0.595872 + outer loop + vertex 729.519 96.4776 14.4552 + vertex 735.095 97.5951 12.786 + vertex 734.873 98.8513 14.455 + endloop + endfacet + facet normal 0.263014 -0.593141 0.760925 + outer loop + vertex 729.519 96.4776 14.4552 + vertex 734.873 98.8513 14.455 + vertex 729.419 98.2682 15.8857 + endloop + endfacet + facet normal 0.262975 -0.593581 0.760596 + outer loop + vertex 729.419 98.2682 15.8857 + vertex 734.873 98.8513 14.455 + vertex 734.768 100.64 15.887 + endloop + endfacet + facet normal 0.269743 -0.592168 0.759326 + outer loop + vertex 734.873 98.8513 14.455 + vertex 740.301 101.318 14.4507 + vertex 734.768 100.64 15.887 + endloop + endfacet + facet normal 0.269926 -0.589647 0.761221 + outer loop + vertex 734.768 100.64 15.887 + vertex 740.301 101.318 14.4507 + vertex 740.2 103.115 15.8786 + endloop + endfacet + facet normal 0.412463 -0.909909 0.0440495 + outer loop + vertex 735.394 96.843 8.99901 + vertex 740.83 99.3069 8.99772 + vertex 735.292 96.8903 10.9364 + endloop + endfacet + facet normal 0.413614 -0.909172 0.048256 + outer loop + vertex 735.292 96.8903 10.9364 + vertex 740.83 99.3069 8.99772 + vertex 740.725 99.3619 10.9337 + endloop + endfacet + facet normal 0.405947 -0.912594 0.0487835 + outer loop + vertex 730.03 94.4566 8.99858 + vertex 735.394 96.843 8.99901 + vertex 729.927 94.5147 10.9359 + endloop + endfacet + facet normal 0.404529 -0.91348 0.0437168 + outer loop + vertex 729.927 94.5147 10.9359 + vertex 735.394 96.843 8.99901 + vertex 735.292 96.8903 10.9364 + endloop + endfacet + facet normal 0.37744 -0.852381 0.361919 + outer loop + vertex 729.927 94.5147 10.9359 + vertex 735.292 96.8903 10.9364 + vertex 729.734 95.2152 12.7875 + endloop + endfacet + facet normal 0.377911 -0.851059 0.364529 + outer loop + vertex 729.734 95.2152 12.7875 + vertex 735.292 96.8903 10.9364 + vertex 735.095 97.5951 12.786 + endloop + endfacet + facet normal 0.385807 -0.847698 0.364089 + outer loop + vertex 735.292 96.8903 10.9364 + vertex 740.725 99.3619 10.9337 + vertex 735.095 97.5951 12.786 + endloop + endfacet + facet normal 0.384705 -0.850933 0.357652 + outer loop + vertex 735.095 97.5951 12.786 + vertex 740.725 99.3619 10.9337 + vertex 740.524 100.05 12.7867 + endloop + endfacet + facet normal 0.334207 -0.741177 -0.582204 + outer loop + vertex 735.029 98.6373 5.40926 + vertex 740.465 101.092 5.40467 + vertex 735.343 97.4416 7.11177 + endloop + endfacet + facet normal 0.335649 -0.742201 -0.580067 + outer loop + vertex 735.343 97.4416 7.11177 + vertex 740.465 101.092 5.40467 + vertex 740.78 99.902 7.11014 + endloop + endfacet + facet normal 0.330565 -0.742321 -0.582826 + outer loop + vertex 729.676 96.2556 5.40696 + vertex 735.029 98.6373 5.40926 + vertex 729.98 95.0537 7.11035 + endloop + endfacet + facet normal 0.330793 -0.742483 -0.582491 + outer loop + vertex 729.98 95.0537 7.11035 + vertex 735.029 98.6373 5.40926 + vertex 735.343 97.4416 7.11177 + endloop + endfacet + facet normal 0.389766 -0.875088 -0.286887 + outer loop + vertex 729.98 95.0537 7.11035 + vertex 735.343 97.4416 7.11177 + vertex 730.03 94.4566 8.99858 + endloop + endfacet + facet normal 0.389213 -0.874913 -0.288168 + outer loop + vertex 730.03 94.4566 8.99858 + vertex 735.343 97.4416 7.11177 + vertex 735.394 96.843 8.99901 + endloop + endfacet + facet normal 0.394747 -0.87262 -0.287593 + outer loop + vertex 735.343 97.4416 7.11177 + vertex 740.78 99.902 7.11014 + vertex 735.394 96.843 8.99901 + endloop + endfacet + facet normal 0.395605 -0.872891 -0.285585 + outer loop + vertex 735.394 96.843 8.99901 + vertex 740.78 99.902 7.11014 + vertex 740.83 99.3069 8.99772 + endloop + endfacet + facet normal 0.16553 -0.392263 -0.904837 + outer loop + vertex 733.526 102.482 2.87896 + vertex 738.623 104.316 3.01631 + vertex 734.367 100.268 3.99298 + endloop + endfacet + facet normal 0.188328 -0.412909 -0.891088 + outer loop + vertex 734.367 100.268 3.99298 + vertex 738.623 104.316 3.01631 + vertex 739.774 102.724 3.99751 + endloop + endfacet + facet normal 0.190594 -0.405514 -0.893998 + outer loop + vertex 727.925 99.5359 3.02132 + vertex 733.526 102.482 2.87896 + vertex 729.029 97.9046 3.99662 + endloop + endfacet + facet normal 0.171912 -0.38978 -0.90472 + outer loop + vertex 729.029 97.9046 3.99662 + vertex 733.526 102.482 2.87896 + vertex 734.367 100.268 3.99298 + endloop + endfacet + facet normal 0.2518 -0.570072 -0.782058 + outer loop + vertex 729.029 97.9046 3.99662 + vertex 734.367 100.268 3.99298 + vertex 729.676 96.2556 5.40696 + endloop + endfacet + facet normal 0.255314 -0.573019 -0.778758 + outer loop + vertex 729.676 96.2556 5.40696 + vertex 734.367 100.268 3.99298 + vertex 735.029 98.6373 5.40926 + endloop + endfacet + facet normal 0.260058 -0.571012 -0.778662 + outer loop + vertex 734.367 100.268 3.99298 + vertex 739.774 102.724 3.99751 + vertex 735.029 98.6373 5.40926 + endloop + endfacet + facet normal 0.255456 -0.567162 -0.782987 + outer loop + vertex 735.029 98.6373 5.40926 + vertex 739.774 102.724 3.99751 + vertex 740.465 101.092 5.40467 + endloop + endfacet + facet normal 0.118396 -0.257214 -0.959074 + outer loop + vertex 738.623 104.316 3.01631 + vertex 733.526 102.482 2.87896 + vertex 740.866 109.071 2.01807 + endloop + endfacet + facet normal 0.112183 -0.259604 -0.959177 + outer loop + vertex 727.925 99.5359 3.02132 + vertex 730.168 104.225 2.01436 + vertex 733.526 102.482 2.87896 + endloop + endfacet + facet normal 0.115376 -0.254008 -0.960296 + outer loop + vertex 730.168 104.225 2.01436 + vertex 740.866 109.071 2.01807 + vertex 733.526 102.482 2.87896 + endloop + endfacet + facet normal 0.0783152 -0.173841 -0.981655 + outer loop + vertex 728.044 108.306 1.12227 + vertex 738.721 113.123 1.12108 + vertex 730.168 104.225 2.01436 + endloop + endfacet + facet normal 0.0796331 -0.175075 -0.981329 + outer loop + vertex 730.168 104.225 2.01436 + vertex 738.721 113.123 1.12108 + vertex 740.866 109.071 2.01807 + endloop + endfacet + facet normal 0.138857 -0.263228 0.954688 + outer loop + vertex 739.467 137.16 23.1582 + vertex 744.32 139.86 23.1969 + vertex 739.699 139.401 23.7423 + endloop + endfacet + facet normal 0.139726 -0.276635 0.950763 + outer loop + vertex 739.699 139.401 23.7423 + vertex 744.32 139.86 23.1969 + vertex 744.997 141.934 23.7008 + endloop + endfacet + facet normal 0.125449 -0.263602 0.956439 + outer loop + vertex 733.734 134.884 23.283 + vertex 739.467 137.16 23.1582 + vertex 734.358 136.889 23.7537 + endloop + endfacet + facet normal 0.125424 -0.26238 0.956779 + outer loop + vertex 734.358 136.889 23.7537 + vertex 739.467 137.16 23.1582 + vertex 739.699 139.401 23.7423 + endloop + endfacet + facet normal 0.0997533 -0.193256 0.976064 + outer loop + vertex 744.32 139.86 23.1969 + vertex 739.467 137.16 23.1582 + vertex 747.694 138.2 22.5234 + endloop + endfacet + facet normal 0.0971248 -0.191123 0.976749 + outer loop + vertex 733.734 134.884 23.283 + vertex 737.252 133.211 22.6057 + vertex 739.467 137.16 23.1582 + endloop + endfacet + facet normal 0.0996672 -0.192476 0.976227 + outer loop + vertex 737.252 133.211 22.6057 + vertex 747.694 138.2 22.5234 + vertex 739.467 137.16 23.1582 + endloop + endfacet + facet normal 0.123822 -0.26438 0.956437 + outer loop + vertex 740.939 107.825 17.9328 + vertex 745.897 110.601 18.0582 + vertex 737.598 109.896 18.9379 + endloop + endfacet + facet normal 0.129105 -0.262078 0.956372 + outer loop + vertex 751.604 112.867 17.9087 + vertex 748.25 114.879 18.9129 + vertex 745.897 110.601 18.0582 + endloop + endfacet + facet normal 0.123542 -0.259316 0.957858 + outer loop + vertex 748.25 114.879 18.9129 + vertex 737.598 109.896 18.9379 + vertex 745.897 110.601 18.0582 + endloop + endfacet + facet normal 0.221191 -0.461755 0.858986 + outer loop + vertex 745.631 105.63 15.877 + vertex 750.993 108.178 15.8664 + vertex 745.764 107.892 17.0591 + endloop + endfacet + facet normal 0.221252 -0.460815 0.859475 + outer loop + vertex 745.764 107.892 17.0591 + vertex 750.993 108.178 15.8664 + vertex 751.094 110.43 17.0474 + endloop + endfacet + facet normal 0.21604 -0.46618 0.857906 + outer loop + vertex 740.2 103.115 15.8786 + vertex 745.631 105.63 15.877 + vertex 740.352 105.373 17.0668 + endloop + endfacet + facet normal 0.216326 -0.462037 0.860073 + outer loop + vertex 740.352 105.373 17.0668 + vertex 745.631 105.63 15.877 + vertex 745.764 107.892 17.0591 + endloop + endfacet + facet normal 0.170847 -0.364181 0.915524 + outer loop + vertex 740.352 105.373 17.0668 + vertex 745.764 107.892 17.0591 + vertex 740.939 107.825 17.9328 + endloop + endfacet + facet normal 0.17171 -0.348337 0.921508 + outer loop + vertex 740.939 107.825 17.9328 + vertex 745.764 107.892 17.0591 + vertex 745.897 110.601 18.0582 + endloop + endfacet + facet normal 0.167878 -0.348401 0.92219 + outer loop + vertex 745.764 107.892 17.0591 + vertex 751.094 110.43 17.0474 + vertex 745.897 110.601 18.0582 + endloop + endfacet + facet normal 0.166735 -0.35938 0.918175 + outer loop + vertex 745.897 110.601 18.0582 + vertex 751.094 110.43 17.0474 + vertex 751.604 112.867 17.9087 + endloop + endfacet + facet normal 0.343626 -0.725025 0.596875 + outer loop + vertex 745.967 102.575 12.7827 + vertex 751.344 105.122 12.7799 + vertex 745.741 103.839 14.4472 + endloop + endfacet + facet normal 0.343765 -0.723794 0.598287 + outer loop + vertex 745.741 103.839 14.4472 + vertex 751.344 105.122 12.7799 + vertex 751.115 106.386 14.4414 + endloop + endfacet + facet normal 0.33741 -0.726287 0.598884 + outer loop + vertex 740.524 100.05 12.7867 + vertex 745.967 102.575 12.7827 + vertex 740.301 101.318 14.4507 + endloop + endfacet + facet normal 0.337294 -0.727288 0.597734 + outer loop + vertex 740.301 101.318 14.4507 + vertex 745.967 102.575 12.7827 + vertex 745.741 103.839 14.4472 + endloop + endfacet + facet normal 0.273306 -0.588935 0.760565 + outer loop + vertex 740.301 101.318 14.4507 + vertex 745.741 103.839 14.4472 + vertex 740.2 103.115 15.8786 + endloop + endfacet + facet normal 0.273249 -0.589835 0.759888 + outer loop + vertex 740.2 103.115 15.8786 + vertex 745.741 103.839 14.4472 + vertex 745.631 105.63 15.877 + endloop + endfacet + facet normal 0.279761 -0.588418 0.758615 + outer loop + vertex 745.741 103.839 14.4472 + vertex 751.115 106.386 14.4414 + vertex 745.631 105.63 15.877 + endloop + endfacet + facet normal 0.27992 -0.585718 0.760644 + outer loop + vertex 745.631 105.63 15.877 + vertex 751.115 106.386 14.4414 + vertex 750.993 108.178 15.8664 + endloop + endfacet + facet normal 0.428259 -0.902089 0.0531909 + outer loop + vertex 746.275 101.826 8.99644 + vertex 751.651 104.378 8.99611 + vertex 746.167 101.889 10.9321 + endloop + endfacet + facet normal 0.425966 -0.903634 0.0447064 + outer loop + vertex 746.167 101.889 10.9321 + vertex 751.651 104.378 8.99611 + vertex 751.548 104.425 10.9314 + endloop + endfacet + facet normal 0.419374 -0.906518 0.0484927 + outer loop + vertex 740.83 99.3069 8.99772 + vertex 746.275 101.826 8.99644 + vertex 740.725 99.3619 10.9337 + endloop + endfacet + facet normal 0.420553 -0.905726 0.0528767 + outer loop + vertex 740.725 99.3619 10.9337 + vertex 746.275 101.826 8.99644 + vertex 746.167 101.889 10.9321 + endloop + endfacet + facet normal 0.393433 -0.847129 0.357187 + outer loop + vertex 740.725 99.3619 10.9337 + vertex 746.167 101.889 10.9321 + vertex 740.524 100.05 12.7867 + endloop + endfacet + facet normal 0.393378 -0.847294 0.356855 + outer loop + vertex 740.524 100.05 12.7867 + vertex 746.167 101.889 10.9321 + vertex 745.967 102.575 12.7827 + endloop + endfacet + facet normal 0.398398 -0.845066 0.35657 + outer loop + vertex 746.167 101.889 10.9321 + vertex 751.548 104.425 10.9314 + vertex 745.967 102.575 12.7827 + endloop + endfacet + facet normal 0.399194 -0.842636 0.3614 + outer loop + vertex 745.967 102.575 12.7827 + vertex 751.548 104.425 10.9314 + vertex 751.344 105.122 12.7799 + endloop + endfacet + facet normal 0.348889 -0.736032 -0.580115 + outer loop + vertex 745.912 103.627 5.40926 + vertex 751.299 106.179 5.41043 + vertex 746.226 102.435 7.11065 + endloop + endfacet + facet normal 0.346373 -0.734299 -0.583807 + outer loop + vertex 746.226 102.435 7.11065 + vertex 751.299 106.179 5.41043 + vertex 751.608 104.975 7.10871 + endloop + endfacet + facet normal 0.344275 -0.738833 -0.57931 + outer loop + vertex 740.465 101.092 5.40467 + vertex 745.912 103.627 5.40926 + vertex 740.78 99.902 7.11014 + endloop + endfacet + facet normal 0.343389 -0.738212 -0.580626 + outer loop + vertex 740.78 99.902 7.11014 + vertex 745.912 103.627 5.40926 + vertex 746.226 102.435 7.11065 + endloop + endfacet + facet normal 0.404287 -0.86921 -0.284652 + outer loop + vertex 740.78 99.902 7.11014 + vertex 746.226 102.435 7.11065 + vertex 740.83 99.3069 8.99772 + endloop + endfacet + facet normal 0.401655 -0.868389 -0.290817 + outer loop + vertex 740.83 99.3069 8.99772 + vertex 746.226 102.435 7.11065 + vertex 746.275 101.826 8.99644 + endloop + endfacet + facet normal 0.4084 -0.865492 -0.290058 + outer loop + vertex 746.226 102.435 7.11065 + vertex 751.608 104.975 7.10871 + vertex 746.275 101.826 8.99644 + endloop + endfacet + facet normal 0.41127 -0.866346 -0.283375 + outer loop + vertex 746.275 101.826 8.99644 + vertex 751.608 104.975 7.10871 + vertex 751.651 104.378 8.99611 + endloop + endfacet + facet normal 0.173072 -0.390652 -0.904122 + outer loop + vertex 744.314 107.416 2.87729 + vertex 749.455 109.37 3.01737 + vertex 745.229 105.24 3.99254 + endloop + endfacet + facet normal 0.193151 -0.408376 -0.892145 + outer loop + vertex 745.229 105.24 3.99254 + vertex 749.455 109.37 3.01737 + vertex 750.632 107.795 3.99308 + endloop + endfacet + facet normal 0.19919 -0.405654 -0.892058 + outer loop + vertex 738.623 104.316 3.01631 + vertex 744.314 107.416 2.87729 + vertex 739.774 102.724 3.99751 + endloop + endfacet + facet normal 0.178381 -0.38839 -0.904065 + outer loop + vertex 739.774 102.724 3.99751 + vertex 744.314 107.416 2.87729 + vertex 745.229 105.24 3.99254 + endloop + endfacet + facet normal 0.260054 -0.56516 -0.782922 + outer loop + vertex 739.774 102.724 3.99751 + vertex 745.229 105.24 3.99254 + vertex 740.465 101.092 5.40467 + endloop + endfacet + facet normal 0.265874 -0.569982 -0.777452 + outer loop + vertex 740.465 101.092 5.40467 + vertex 745.229 105.24 3.99254 + vertex 745.912 103.627 5.40926 + endloop + endfacet + facet normal 0.268908 -0.568643 -0.777389 + outer loop + vertex 745.229 105.24 3.99254 + vertex 750.632 107.795 3.99308 + vertex 745.912 103.627 5.40926 + endloop + endfacet + facet normal 0.270059 -0.569578 -0.776305 + outer loop + vertex 745.912 103.627 5.40926 + vertex 750.632 107.795 3.99308 + vertex 751.299 106.179 5.41043 + endloop + endfacet + facet normal 0.12367 -0.256738 -0.958536 + outer loop + vertex 749.455 109.37 3.01737 + vertex 744.314 107.416 2.87729 + vertex 751.585 114.136 2.01575 + endloop + endfacet + facet normal 0.116163 -0.256271 -0.9596 + outer loop + vertex 738.623 104.316 3.01631 + vertex 740.866 109.071 2.01807 + vertex 744.314 107.416 2.87729 + endloop + endfacet + facet normal 0.118655 -0.251567 -0.960539 + outer loop + vertex 740.866 109.071 2.01807 + vertex 751.585 114.136 2.01575 + vertex 744.314 107.416 2.87729 + endloop + endfacet + facet normal 0.0821834 -0.173731 -0.981358 + outer loop + vertex 738.721 113.123 1.12108 + vertex 749.383 118.146 1.12472 + vertex 740.866 109.071 2.01807 + endloop + endfacet + facet normal 0.0816385 -0.173233 -0.981491 + outer loop + vertex 740.866 109.071 2.01807 + vertex 749.383 118.146 1.12472 + vertex 751.585 114.136 2.01575 + endloop + endfacet + facet normal 0.152542 -0.269669 0.950794 + outer loop + vertex 749.844 142.153 23.0485 + vertex 754.429 144.866 23.0823 + vertex 750.124 144.454 23.656 + endloop + endfacet + facet normal 0.153493 -0.286799 0.945614 + outer loop + vertex 750.124 144.454 23.656 + vertex 754.429 144.866 23.0823 + vertex 755.114 146.996 23.6171 + endloop + endfacet + facet normal 0.14048 -0.27684 0.950592 + outer loop + vertex 744.32 139.86 23.1969 + vertex 749.844 142.153 23.0485 + vertex 744.997 141.934 23.7008 + endloop + endfacet + facet normal 0.140428 -0.268754 0.952917 + outer loop + vertex 744.997 141.934 23.7008 + vertex 749.844 142.153 23.0485 + vertex 750.124 144.454 23.656 + endloop + endfacet + facet normal 0.10508 -0.189776 0.976188 + outer loop + vertex 754.429 144.866 23.0823 + vertex 749.844 142.153 23.0485 + vertex 757.839 143.313 22.4133 + endloop + endfacet + facet normal 0.103497 -0.186052 0.977074 + outer loop + vertex 744.32 139.86 23.1969 + vertex 747.694 138.2 22.5234 + vertex 749.844 142.153 23.0485 + endloop + endfacet + facet normal 0.104679 -0.186662 0.976831 + outer loop + vertex 747.694 138.2 22.5234 + vertex 757.839 143.313 22.4133 + vertex 749.844 142.153 23.0485 + endloop + endfacet + facet normal 0.129342 -0.261717 0.956439 + outer loop + vertex 751.604 112.867 17.9087 + vertex 756.428 115.689 18.0287 + vertex 748.25 114.879 18.9129 + endloop + endfacet + facet normal 0.133499 -0.256382 0.957312 + outer loop + vertex 762.052 118.045 17.8753 + vertex 758.752 120.033 18.8679 + vertex 756.428 115.689 18.0287 + endloop + endfacet + facet normal 0.128818 -0.254118 0.958556 + outer loop + vertex 758.752 120.033 18.8679 + vertex 748.25 114.879 18.9129 + vertex 756.428 115.689 18.0287 + endloop + endfacet + facet normal 0.22981 -0.457253 0.859132 + outer loop + vertex 756.252 110.724 15.8607 + vertex 761.464 113.319 15.8473 + vertex 756.333 112.977 17.0376 + endloop + endfacet + facet normal 0.229909 -0.455392 0.860093 + outer loop + vertex 756.333 112.977 17.0376 + vertex 761.464 113.319 15.8473 + vertex 761.541 115.576 17.0216 + endloop + endfacet + facet normal 0.223925 -0.460625 0.858884 + outer loop + vertex 750.993 108.178 15.8664 + vertex 756.252 110.724 15.8607 + vertex 751.094 110.43 17.0474 + endloop + endfacet + facet normal 0.224106 -0.457708 0.860395 + outer loop + vertex 751.094 110.43 17.0474 + vertex 756.252 110.724 15.8607 + vertex 756.333 112.977 17.0376 + endloop + endfacet + facet normal 0.177036 -0.360672 0.915737 + outer loop + vertex 751.094 110.43 17.0474 + vertex 756.333 112.977 17.0376 + vertex 751.604 112.867 17.9087 + endloop + endfacet + facet normal 0.177836 -0.343142 0.922295 + outer loop + vertex 751.604 112.867 17.9087 + vertex 756.333 112.977 17.0376 + vertex 756.428 115.689 18.0287 + endloop + endfacet + facet normal 0.174139 -0.343255 0.922958 + outer loop + vertex 756.333 112.977 17.0376 + vertex 761.541 115.576 17.0216 + vertex 756.428 115.689 18.0287 + endloop + endfacet + facet normal 0.173175 -0.353589 0.919231 + outer loop + vertex 756.428 115.689 18.0287 + vertex 761.541 115.576 17.0216 + vertex 762.052 118.045 17.8753 + endloop + endfacet + facet normal 0.357176 -0.719479 0.59563 + outer loop + vertex 756.629 107.685 12.7746 + vertex 761.859 110.277 12.7697 + vertex 756.394 108.943 14.4349 + endloop + endfacet + facet normal 0.357219 -0.719065 0.596104 + outer loop + vertex 756.394 108.943 14.4349 + vertex 761.859 110.277 12.7697 + vertex 761.614 111.53 14.4281 + endloop + endfacet + facet normal 0.350502 -0.721337 0.597346 + outer loop + vertex 751.344 105.122 12.7799 + vertex 756.629 107.685 12.7746 + vertex 751.115 106.386 14.4414 + endloop + endfacet + facet normal 0.350428 -0.722001 0.596585 + outer loop + vertex 751.115 106.386 14.4414 + vertex 756.629 107.685 12.7746 + vertex 756.394 108.943 14.4349 + endloop + endfacet + facet normal 0.284162 -0.584762 0.759806 + outer loop + vertex 751.115 106.386 14.4414 + vertex 756.394 108.943 14.4349 + vertex 750.993 108.178 15.8664 + endloop + endfacet + facet normal 0.284136 -0.585212 0.759469 + outer loop + vertex 750.993 108.178 15.8664 + vertex 756.394 108.943 14.4349 + vertex 756.252 110.724 15.8607 + endloop + endfacet + facet normal 0.290349 -0.583743 0.75825 + outer loop + vertex 756.394 108.943 14.4349 + vertex 761.614 111.53 14.4281 + vertex 756.252 110.724 15.8607 + endloop + endfacet + facet normal 0.290544 -0.579784 0.761206 + outer loop + vertex 756.252 110.724 15.8607 + vertex 761.614 111.53 14.4281 + vertex 761.464 113.319 15.8473 + endloop + endfacet + facet normal 0.445195 -0.893884 0.0526579 + outer loop + vertex 756.939 106.928 8.99457 + vertex 762.171 109.533 8.99439 + vertex 756.833 106.989 10.9291 + endloop + endfacet + facet normal 0.442976 -0.895428 0.044508 + outer loop + vertex 756.833 106.989 10.9291 + vertex 762.171 109.533 8.99439 + vertex 762.068 109.578 10.9267 + endloop + endfacet + facet normal 0.433839 -0.899864 0.0450322 + outer loop + vertex 751.651 104.378 8.99611 + vertex 756.939 106.928 8.99457 + vertex 751.548 104.425 10.9314 + endloop + endfacet + facet normal 0.43582 -0.898514 0.0522898 + outer loop + vertex 751.548 104.425 10.9314 + vertex 756.939 106.928 8.99457 + vertex 756.833 106.989 10.9291 + endloop + endfacet + facet normal 0.407114 -0.839045 0.360919 + outer loop + vertex 751.548 104.425 10.9314 + vertex 756.833 106.989 10.9291 + vertex 751.344 105.122 12.7799 + endloop + endfacet + facet normal 0.407213 -0.838735 0.361525 + outer loop + vertex 751.344 105.122 12.7799 + vertex 756.833 106.989 10.9291 + vertex 756.629 107.685 12.7746 + endloop + endfacet + facet normal 0.413608 -0.835777 0.361117 + outer loop + vertex 756.833 106.989 10.9291 + vertex 762.068 109.578 10.9267 + vertex 756.629 107.685 12.7746 + endloop + endfacet + facet normal 0.413994 -0.834546 0.363515 + outer loop + vertex 756.629 107.685 12.7746 + vertex 762.068 109.578 10.9267 + vertex 761.859 110.277 12.7697 + endloop + endfacet + facet normal 0.362349 -0.733102 -0.575556 + outer loop + vertex 756.593 108.733 5.40602 + vertex 761.821 111.319 5.4042 + vertex 756.888 107.54 7.11075 + endloop + endfacet + facet normal 0.362692 -0.733324 -0.575057 + outer loop + vertex 756.888 107.54 7.11075 + vertex 761.821 111.319 5.4042 + vertex 762.121 110.13 7.10932 + endloop + endfacet + facet normal 0.352523 -0.731854 -0.583196 + outer loop + vertex 751.299 106.179 5.41043 + vertex 756.593 108.733 5.40602 + vertex 751.608 104.975 7.10871 + endloop + endfacet + facet normal 0.357396 -0.735104 -0.5761 + outer loop + vertex 751.608 104.975 7.10871 + vertex 756.593 108.733 5.40602 + vertex 756.888 107.54 7.11075 + endloop + endfacet + facet normal 0.419322 -0.862788 -0.282429 + outer loop + vertex 751.608 104.975 7.10871 + vertex 756.888 107.54 7.11075 + vertex 751.651 104.378 8.99611 + endloop + endfacet + facet normal 0.415322 -0.861657 -0.291643 + outer loop + vertex 751.651 104.378 8.99611 + vertex 756.888 107.54 7.11075 + vertex 756.939 106.928 8.99457 + endloop + endfacet + facet normal 0.424282 -0.85764 -0.290582 + outer loop + vertex 756.888 107.54 7.11075 + vertex 762.121 110.13 7.10932 + vertex 756.939 106.928 8.99457 + endloop + endfacet + facet normal 0.427574 -0.858527 -0.283041 + outer loop + vertex 756.939 106.928 8.99457 + vertex 762.121 110.13 7.10932 + vertex 762.171 109.533 8.99439 + endloop + endfacet + facet normal 0.181258 -0.388658 -0.903377 + outer loop + vertex 755.048 112.54 2.87879 + vertex 760.048 114.537 3.02303 + vertex 755.937 110.361 3.99462 + endloop + endfacet + facet normal 0.201765 -0.406037 -0.891305 + outer loop + vertex 755.937 110.361 3.99462 + vertex 760.048 114.537 3.02303 + vertex 761.168 112.954 3.99768 + endloop + endfacet + facet normal 0.204798 -0.400329 -0.893194 + outer loop + vertex 749.455 109.37 3.01737 + vertex 755.048 112.54 2.87879 + vertex 750.632 107.795 3.99308 + endloop + endfacet + facet normal 0.187088 -0.386207 -0.90324 + outer loop + vertex 750.632 107.795 3.99308 + vertex 755.048 112.54 2.87879 + vertex 755.937 110.361 3.99462 + endloop + endfacet + facet normal 0.274758 -0.567516 -0.776166 + outer loop + vertex 750.632 107.795 3.99308 + vertex 755.937 110.361 3.99462 + vertex 751.299 106.179 5.41043 + endloop + endfacet + facet normal 0.272057 -0.565371 -0.778679 + outer loop + vertex 751.299 106.179 5.41043 + vertex 755.937 110.361 3.99462 + vertex 756.593 108.733 5.40602 + endloop + endfacet + facet normal 0.279139 -0.562284 -0.778407 + outer loop + vertex 755.937 110.361 3.99462 + vertex 761.168 112.954 3.99768 + vertex 756.593 108.733 5.40602 + endloop + endfacet + facet normal 0.276965 -0.560593 -0.780401 + outer loop + vertex 756.593 108.733 5.40602 + vertex 761.168 112.954 3.99768 + vertex 761.821 111.319 5.4042 + endloop + endfacet + facet normal 0.130549 -0.257771 -0.957346 + outer loop + vertex 760.048 114.537 3.02303 + vertex 755.048 112.54 2.87879 + vertex 762.165 119.36 2.01316 + endloop + endfacet + facet normal 0.121214 -0.255761 -0.959111 + outer loop + vertex 749.455 109.37 3.01737 + vertex 751.585 114.136 2.01575 + vertex 755.048 112.54 2.87879 + endloop + endfacet + facet normal 0.123674 -0.250941 -0.960069 + outer loop + vertex 751.585 114.136 2.01575 + vertex 762.165 119.36 2.01316 + vertex 755.048 112.54 2.87879 + endloop + endfacet + facet normal 0.0842295 -0.171817 -0.981521 + outer loop + vertex 749.383 118.146 1.12472 + vertex 759.97 123.357 1.12108 + vertex 751.585 114.136 2.01575 + endloop + endfacet + facet normal 0.0848866 -0.172399 -0.981363 + outer loop + vertex 751.585 114.136 2.01575 + vertex 759.97 123.357 1.12108 + vertex 762.165 119.36 2.01316 + endloop + endfacet + facet normal 0.161022 -0.272921 0.948465 + outer loop + vertex 759.794 147.268 22.9509 + vertex 764.359 150.146 23.0039 + vertex 760.061 149.614 23.5805 + endloop + endfacet + facet normal 0.162068 -0.285628 0.944537 + outer loop + vertex 760.061 149.614 23.5805 + vertex 764.359 150.146 23.0039 + vertex 765.098 152.366 23.5485 + endloop + endfacet + facet normal 0.151313 -0.286229 0.946138 + outer loop + vertex 754.429 144.866 23.0823 + vertex 759.794 147.268 22.9509 + vertex 755.114 146.996 23.6171 + endloop + endfacet + facet normal 0.151093 -0.272277 0.950282 + outer loop + vertex 755.114 146.996 23.6171 + vertex 759.794 147.268 22.9509 + vertex 760.061 149.614 23.5805 + endloop + endfacet + facet normal 0.11399 -0.198764 0.973396 + outer loop + vertex 764.359 150.146 23.0039 + vertex 759.794 147.268 22.9509 + vertex 767.864 148.707 22.2998 + endloop + endfacet + facet normal 0.107054 -0.185686 0.97676 + outer loop + vertex 754.429 144.866 23.0823 + vertex 757.839 143.313 22.4133 + vertex 759.794 147.268 22.9509 + endloop + endfacet + facet normal 0.112279 -0.188125 0.975706 + outer loop + vertex 757.839 143.313 22.4133 + vertex 767.864 148.707 22.2998 + vertex 759.794 147.268 22.9509 + endloop + endfacet + facet normal 0.134284 -0.255184 0.957522 + outer loop + vertex 762.052 118.045 17.8753 + vertex 766.885 120.995 17.9838 + vertex 758.752 120.033 18.8679 + endloop + endfacet + facet normal 0.139654 -0.250899 0.957887 + outer loop + vertex 772.529 123.5 17.817 + vertex 769.186 125.413 18.8055 + vertex 766.885 120.995 17.9838 + endloop + endfacet + facet normal 0.133655 -0.24807 0.959478 + outer loop + vertex 769.186 125.413 18.8055 + vertex 758.752 120.033 18.8679 + vertex 766.885 120.995 17.9838 + endloop + endfacet + facet normal 0.23727 -0.450337 0.860755 + outer loop + vertex 766.691 115.977 15.8351 + vertex 771.955 118.72 15.8189 + vertex 766.775 118.251 17.0019 + endloop + endfacet + facet normal 0.237379 -0.446234 0.862859 + outer loop + vertex 766.775 118.251 17.0019 + vertex 771.955 118.72 15.8189 + vertex 772.034 121.005 16.9791 + endloop + endfacet + facet normal 0.233471 -0.455096 0.85929 + outer loop + vertex 761.464 113.319 15.8473 + vertex 766.691 115.977 15.8351 + vertex 761.541 115.576 17.0216 + endloop + endfacet + facet normal 0.233653 -0.450631 0.86159 + outer loop + vertex 761.541 115.576 17.0216 + vertex 766.691 115.977 15.8351 + vertex 766.775 118.251 17.0019 + endloop + endfacet + facet normal 0.184987 -0.355043 0.916365 + outer loop + vertex 761.541 115.576 17.0216 + vertex 766.775 118.251 17.0019 + vertex 762.052 118.045 17.8753 + endloop + endfacet + facet normal 0.185422 -0.337671 0.92282 + outer loop + vertex 762.052 118.045 17.8753 + vertex 766.775 118.251 17.0019 + vertex 766.885 120.995 17.9838 + endloop + endfacet + facet normal 0.180867 -0.337796 0.923678 + outer loop + vertex 766.775 118.251 17.0019 + vertex 772.034 121.005 16.9791 + vertex 766.885 120.995 17.9838 + endloop + endfacet + facet normal 0.180371 -0.345112 0.921067 + outer loop + vertex 766.885 120.995 17.9838 + vertex 772.034 121.005 16.9791 + vertex 772.529 123.5 17.817 + endloop + endfacet + facet normal 0.368778 -0.712301 0.597186 + outer loop + vertex 767.097 112.935 12.7636 + vertex 772.371 115.662 12.7597 + vertex 766.846 114.191 14.4173 + endloop + endfacet + facet normal 0.36916 -0.707197 0.602987 + outer loop + vertex 766.846 114.191 14.4173 + vertex 772.371 115.662 12.7597 + vertex 772.114 116.931 14.4055 + endloop + endfacet + facet normal 0.364153 -0.716402 0.595115 + outer loop + vertex 761.859 110.277 12.7697 + vertex 767.097 112.935 12.7636 + vertex 761.614 111.53 14.4281 + endloop + endfacet + facet normal 0.364368 -0.714029 0.597828 + outer loop + vertex 761.614 111.53 14.4281 + vertex 767.097 112.935 12.7636 + vertex 766.846 114.191 14.4173 + endloop + endfacet + facet normal 0.295783 -0.578511 0.760156 + outer loop + vertex 761.614 111.53 14.4281 + vertex 766.846 114.191 14.4173 + vertex 761.464 113.319 15.8473 + endloop + endfacet + facet normal 0.295798 -0.578095 0.760467 + outer loop + vertex 761.464 113.319 15.8473 + vertex 766.846 114.191 14.4173 + vertex 766.691 115.977 15.8351 + endloop + endfacet + facet normal 0.301615 -0.576647 0.759281 + outer loop + vertex 766.846 114.191 14.4173 + vertex 772.114 116.931 14.4055 + vertex 766.691 115.977 15.8351 + endloop + endfacet + facet normal 0.30166 -0.574516 0.760876 + outer loop + vertex 766.691 115.977 15.8351 + vertex 772.114 116.931 14.4055 + vertex 771.955 118.72 15.8189 + endloop + endfacet + facet normal 0.459202 -0.886778 0.052516 + outer loop + vertex 767.422 112.185 8.9916 + vertex 772.709 114.923 8.9896 + vertex 767.311 112.243 10.9236 + endloop + endfacet + facet normal 0.460109 -0.886095 0.0559961 + outer loop + vertex 767.311 112.243 10.9236 + vertex 772.709 114.923 8.9896 + vertex 772.592 114.984 10.918 + endloop + endfacet + facet normal 0.450417 -0.891693 0.044819 + outer loop + vertex 762.171 109.533 8.99439 + vertex 767.422 112.185 8.9916 + vertex 762.068 109.578 10.9267 + endloop + endfacet + facet normal 0.452408 -0.89028 0.0522312 + outer loop + vertex 762.068 109.578 10.9267 + vertex 767.422 112.185 8.9916 + vertex 767.311 112.243 10.9236 + endloop + endfacet + facet normal 0.422283 -0.830622 0.362966 + outer loop + vertex 762.068 109.578 10.9267 + vertex 767.311 112.243 10.9236 + vertex 761.859 110.277 12.7697 + endloop + endfacet + facet normal 0.422113 -0.831191 0.361858 + outer loop + vertex 761.859 110.277 12.7697 + vertex 767.311 112.243 10.9236 + vertex 767.097 112.935 12.7636 + endloop + endfacet + facet normal 0.429952 -0.82739 0.36134 + outer loop + vertex 767.311 112.243 10.9236 + vertex 772.592 114.984 10.918 + vertex 767.097 112.935 12.7636 + endloop + endfacet + facet normal 0.429296 -0.829677 0.356849 + outer loop + vertex 767.097 112.935 12.7636 + vertex 772.592 114.984 10.918 + vertex 772.371 115.662 12.7597 + endloop + endfacet + facet normal 0.376056 -0.724072 -0.578188 + outer loop + vertex 767.053 113.983 5.40892 + vertex 772.337 116.727 5.40976 + vertex 767.369 112.791 7.10795 + endloop + endfacet + facet normal 0.376246 -0.724194 -0.577912 + outer loop + vertex 767.369 112.791 7.10795 + vertex 772.337 116.727 5.40976 + vertex 772.657 115.538 7.10791 + endloop + endfacet + facet normal 0.372057 -0.729449 -0.574001 + outer loop + vertex 761.821 111.319 5.4042 + vertex 767.053 113.983 5.40892 + vertex 762.121 110.13 7.10932 + endloop + endfacet + facet normal 0.368596 -0.727235 -0.579022 + outer loop + vertex 762.121 110.13 7.10932 + vertex 767.053 113.983 5.40892 + vertex 767.369 112.791 7.10795 + endloop + endfacet + facet normal 0.433787 -0.85565 -0.282297 + outer loop + vertex 762.121 110.13 7.10932 + vertex 767.369 112.791 7.10795 + vertex 762.171 109.533 8.99439 + endloop + endfacet + facet normal 0.43177 -0.855124 -0.286946 + outer loop + vertex 762.171 109.533 8.99439 + vertex 767.369 112.791 7.10795 + vertex 767.422 112.185 8.9916 + endloop + endfacet + facet normal 0.441815 -0.850395 -0.285707 + outer loop + vertex 767.369 112.791 7.10795 + vertex 772.657 115.538 7.10791 + vertex 767.422 112.185 8.9916 + endloop + endfacet + facet normal 0.439982 -0.849912 -0.289941 + outer loop + vertex 767.422 112.185 8.9916 + vertex 772.657 115.538 7.10791 + vertex 772.709 114.923 8.9896 + endloop + endfacet + facet normal 0.18993 -0.388375 -0.901716 + outer loop + vertex 765.54 117.779 2.87333 + vertex 770.516 119.878 3.01735 + vertex 766.396 115.596 3.99388 + endloop + endfacet + facet normal 0.209948 -0.404943 -0.889912 + outer loop + vertex 766.396 115.596 3.99388 + vertex 770.516 119.878 3.01735 + vertex 771.661 118.324 3.99445 + endloop + endfacet + facet normal 0.211533 -0.39954 -0.891976 + outer loop + vertex 760.048 114.537 3.02303 + vertex 765.54 117.779 2.87333 + vertex 761.168 112.954 3.99768 + endloop + endfacet + facet normal 0.194624 -0.386447 -0.901543 + outer loop + vertex 761.168 112.954 3.99768 + vertex 765.54 117.779 2.87333 + vertex 766.396 115.596 3.99388 + endloop + endfacet + facet normal 0.281671 -0.558534 -0.780193 + outer loop + vertex 761.168 112.954 3.99768 + vertex 766.396 115.596 3.99388 + vertex 761.821 111.319 5.4042 + endloop + endfacet + facet normal 0.287432 -0.56295 -0.7749 + outer loop + vertex 761.821 111.319 5.4042 + vertex 766.396 115.596 3.99388 + vertex 767.053 113.983 5.40892 + endloop + endfacet + facet normal 0.290991 -0.561352 -0.774731 + outer loop + vertex 766.396 115.596 3.99388 + vertex 771.661 118.324 3.99445 + vertex 767.053 113.983 5.40892 + endloop + endfacet + facet normal 0.291991 -0.562111 -0.773803 + outer loop + vertex 767.053 113.983 5.40892 + vertex 771.661 118.324 3.99445 + vertex 772.337 116.727 5.40976 + endloop + endfacet + facet normal 0.134918 -0.254118 -0.957717 + outer loop + vertex 770.516 119.878 3.01735 + vertex 765.54 117.779 2.87333 + vertex 772.628 124.772 2.01637 + endloop + endfacet + facet normal 0.124678 -0.255485 -0.95874 + outer loop + vertex 760.048 114.537 3.02303 + vertex 762.165 119.36 2.01316 + vertex 765.54 117.779 2.87333 + endloop + endfacet + facet normal 0.128564 -0.247981 -0.960196 + outer loop + vertex 762.165 119.36 2.01316 + vertex 772.628 124.772 2.01637 + vertex 765.54 117.779 2.87333 + endloop + endfacet + facet normal 0.0880562 -0.170664 -0.981387 + outer loop + vertex 759.97 123.357 1.12108 + vertex 770.441 128.748 1.12313 + vertex 762.165 119.36 2.01316 + endloop + endfacet + facet normal 0.0889943 -0.171469 -0.981162 + outer loop + vertex 762.165 119.36 2.01316 + vertex 770.441 128.748 1.12313 + vertex 772.628 124.772 2.01637 + endloop + endfacet + facet normal 0.17421 -0.270557 0.94681 + outer loop + vertex 769.819 152.784 22.8558 + vertex 774.386 155.816 22.8821 + vertex 770.068 155.114 23.476 + endloop + endfacet + facet normal 0.175243 -0.27919 0.94411 + outer loop + vertex 770.068 155.114 23.476 + vertex 774.386 155.816 22.8821 + vertex 774.775 157.822 23.4031 + endloop + endfacet + facet normal 0.163824 -0.286103 0.94409 + outer loop + vertex 764.359 150.146 23.0039 + vertex 769.819 152.784 22.8558 + vertex 765.098 152.366 23.5485 + endloop + endfacet + facet normal 0.163108 -0.269946 0.94896 + outer loop + vertex 765.098 152.366 23.5485 + vertex 769.819 152.784 22.8558 + vertex 770.068 155.114 23.476 + endloop + endfacet + facet normal 0.128361 -0.201723 0.970995 + outer loop + vertex 774.386 155.816 22.8821 + vertex 769.819 152.784 22.8558 + vertex 777.958 154.509 22.1384 + endloop + endfacet + facet normal 0.118027 -0.18959 0.974744 + outer loop + vertex 764.359 150.146 23.0039 + vertex 767.864 148.707 22.2998 + vertex 769.819 152.784 22.8558 + endloop + endfacet + facet normal 0.12679 -0.193538 0.972865 + outer loop + vertex 767.864 148.707 22.2998 + vertex 777.958 154.509 22.1384 + vertex 769.819 152.784 22.8558 + endloop + endfacet + facet normal 0.139404 -0.251299 0.957818 + outer loop + vertex 772.529 123.5 17.817 + vertex 777.311 126.547 17.9206 + vertex 769.186 125.413 18.8055 + endloop + endfacet + facet normal 0.143691 -0.241735 0.959644 + outer loop + vertex 782.85 129.138 17.7438 + vertex 779.467 130.981 18.7146 + vertex 777.311 126.547 17.9206 + endloop + endfacet + facet normal 0.13808 -0.239265 0.961086 + outer loop + vertex 779.467 130.981 18.7146 + vertex 769.186 125.413 18.8055 + vertex 777.311 126.547 17.9206 + endloop + endfacet + facet normal 0.244791 -0.440984 0.863487 + outer loop + vertex 777.212 121.522 15.8006 + vertex 782.406 124.36 15.7775 + vertex 777.266 123.807 16.9524 + endloop + endfacet + facet normal 0.244826 -0.43658 0.865712 + outer loop + vertex 777.266 123.807 16.9524 + vertex 782.406 124.36 15.7775 + vertex 782.43 126.643 16.9222 + endloop + endfacet + facet normal 0.240731 -0.445952 0.862076 + outer loop + vertex 771.955 118.72 15.8189 + vertex 777.212 121.522 15.8006 + vertex 772.034 121.005 16.9791 + endloop + endfacet + facet normal 0.240805 -0.441357 0.864417 + outer loop + vertex 772.034 121.005 16.9791 + vertex 777.212 121.522 15.8006 + vertex 777.266 123.807 16.9524 + endloop + endfacet + facet normal 0.190138 -0.346246 0.918673 + outer loop + vertex 772.034 121.005 16.9791 + vertex 777.266 123.807 16.9524 + vertex 772.529 123.5 17.817 + endloop + endfacet + facet normal 0.19017 -0.329825 0.92469 + outer loop + vertex 772.529 123.5 17.817 + vertex 777.266 123.807 16.9524 + vertex 777.311 126.547 17.9206 + endloop + endfacet + facet normal 0.186642 -0.329999 0.925346 + outer loop + vertex 777.266 123.807 16.9524 + vertex 782.43 126.643 16.9222 + vertex 777.311 126.547 17.9206 + endloop + endfacet + facet normal 0.186372 -0.33546 0.923435 + outer loop + vertex 777.311 126.547 17.9206 + vertex 782.43 126.643 16.9222 + vertex 782.85 129.138 17.7438 + endloop + endfacet + facet normal 0.382531 -0.703954 0.59843 + outer loop + vertex 777.649 118.472 12.7485 + vertex 782.873 121.305 12.741 + vertex 777.383 119.727 14.3948 + endloop + endfacet + facet normal 0.382812 -0.698729 0.604345 + outer loop + vertex 777.383 119.727 14.3948 + vertex 782.873 121.305 12.741 + vertex 782.595 122.568 14.3783 + endloop + endfacet + facet normal 0.37628 -0.704358 0.601907 + outer loop + vertex 772.371 115.662 12.7597 + vertex 777.649 118.472 12.7485 + vertex 772.114 116.931 14.4055 + endloop + endfacet + facet normal 0.376144 -0.706571 0.599394 + outer loop + vertex 772.114 116.931 14.4055 + vertex 777.649 118.472 12.7485 + vertex 777.383 119.727 14.3948 + endloop + endfacet + facet normal 0.305836 -0.573458 0.760007 + outer loop + vertex 772.114 116.931 14.4055 + vertex 777.383 119.727 14.3948 + vertex 771.955 118.72 15.8189 + endloop + endfacet + facet normal 0.305883 -0.568813 0.763471 + outer loop + vertex 771.955 118.72 15.8189 + vertex 777.383 119.727 14.3948 + vertex 777.212 121.522 15.8006 + endloop + endfacet + facet normal 0.31167 -0.567305 0.762251 + outer loop + vertex 777.383 119.727 14.3948 + vertex 782.595 122.568 14.3783 + vertex 777.212 121.522 15.8006 + endloop + endfacet + facet normal 0.311674 -0.564202 0.764549 + outer loop + vertex 777.212 121.522 15.8006 + vertex 782.595 122.568 14.3783 + vertex 782.406 124.36 15.7775 + endloop + endfacet + facet normal 0.476697 -0.877376 0.0545099 + outer loop + vertex 777.996 117.734 8.98679 + vertex 783.229 120.577 8.98342 + vertex 777.876 117.788 10.913 + endloop + endfacet + facet normal 0.476173 -0.877785 0.0524643 + outer loop + vertex 777.876 117.788 10.913 + vertex 783.229 120.577 8.98342 + vertex 783.107 120.626 10.9071 + endloop + endfacet + facet normal 0.468723 -0.881545 0.0563714 + outer loop + vertex 772.709 114.923 8.9896 + vertex 777.996 117.734 8.98679 + vertex 772.592 114.984 10.918 + endloop + endfacet + facet normal 0.468142 -0.881996 0.0541034 + outer loop + vertex 772.592 114.984 10.918 + vertex 777.996 117.734 8.98679 + vertex 777.876 117.788 10.913 + endloop + endfacet + facet normal 0.438289 -0.825205 0.356285 + outer loop + vertex 772.592 114.984 10.918 + vertex 777.876 117.788 10.913 + vertex 772.371 115.662 12.7597 + endloop + endfacet + facet normal 0.438905 -0.822946 0.360723 + outer loop + vertex 772.371 115.662 12.7597 + vertex 777.876 117.788 10.913 + vertex 777.649 118.472 12.7485 + endloop + endfacet + facet normal 0.44507 -0.819808 0.360316 + outer loop + vertex 777.876 117.788 10.913 + vertex 783.107 120.626 10.9071 + vertex 777.649 118.472 12.7485 + endloop + endfacet + facet normal 0.445049 -0.819889 0.360159 + outer loop + vertex 777.649 118.472 12.7485 + vertex 783.107 120.626 10.9071 + vertex 782.873 121.305 12.741 + endloop + endfacet + facet normal 0.393415 -0.720855 -0.570607 + outer loop + vertex 777.64 119.526 5.40365 + vertex 782.873 122.377 5.40893 + vertex 777.95 118.346 7.10691 + endloop + endfacet + facet normal 0.390085 -0.718823 -0.575437 + outer loop + vertex 777.95 118.346 7.10691 + vertex 782.873 122.377 5.40893 + vertex 783.185 121.189 7.10522 + endloop + endfacet + facet normal 0.380539 -0.722338 -0.577424 + outer loop + vertex 772.337 116.727 5.40976 + vertex 777.64 119.526 5.40365 + vertex 772.657 115.538 7.10791 + endloop + endfacet + facet normal 0.384462 -0.724799 -0.571712 + outer loop + vertex 772.657 115.538 7.10791 + vertex 777.64 119.526 5.40365 + vertex 777.95 118.346 7.10691 + endloop + endfacet + facet normal 0.448684 -0.845736 -0.288814 + outer loop + vertex 772.657 115.538 7.10791 + vertex 777.95 118.346 7.10691 + vertex 772.709 114.923 8.9896 + endloop + endfacet + facet normal 0.449632 -0.84598 -0.286618 + outer loop + vertex 772.709 114.923 8.9896 + vertex 777.95 118.346 7.10691 + vertex 777.996 117.734 8.98679 + endloop + endfacet + facet normal 0.457198 -0.842262 -0.285595 + outer loop + vertex 777.95 118.346 7.10691 + vertex 783.185 121.189 7.10522 + vertex 777.996 117.734 8.98679 + endloop + endfacet + facet normal 0.457432 -0.842319 -0.285052 + outer loop + vertex 777.996 117.734 8.98679 + vertex 783.185 121.189 7.10522 + vertex 783.229 120.577 8.98342 + endloop + endfacet + facet normal 0.19725 -0.385424 -0.90141 + outer loop + vertex 776.036 123.272 2.87574 + vertex 781.031 125.493 3.01949 + vertex 776.952 121.126 3.99393 + endloop + endfacet + facet normal 0.218211 -0.402267 -0.889138 + outer loop + vertex 776.952 121.126 3.99393 + vertex 781.031 125.493 3.01949 + vertex 782.198 123.969 3.9954 + endloop + endfacet + facet normal 0.221333 -0.397054 -0.890708 + outer loop + vertex 770.516 119.878 3.01735 + vertex 776.036 123.272 2.87574 + vertex 771.661 118.324 3.99445 + endloop + endfacet + facet normal 0.202735 -0.38299 -0.901231 + outer loop + vertex 771.661 118.324 3.99445 + vertex 776.036 123.272 2.87574 + vertex 776.952 121.126 3.99393 + endloop + endfacet + facet normal 0.296501 -0.560025 -0.773602 + outer loop + vertex 771.661 118.324 3.99445 + vertex 776.952 121.126 3.99393 + vertex 772.337 116.727 5.40976 + endloop + endfacet + facet normal 0.293434 -0.557718 -0.776433 + outer loop + vertex 772.337 116.727 5.40976 + vertex 776.952 121.126 3.99393 + vertex 777.64 119.526 5.40365 + endloop + endfacet + facet normal 0.300584 -0.554353 -0.776107 + outer loop + vertex 776.952 121.126 3.99393 + vertex 782.198 123.969 3.9954 + vertex 777.64 119.526 5.40365 + endloop + endfacet + facet normal 0.304416 -0.557169 -0.772589 + outer loop + vertex 777.64 119.526 5.40365 + vertex 782.198 123.969 3.9954 + vertex 782.873 122.377 5.40893 + endloop + endfacet + facet normal 0.140142 -0.253328 -0.957176 + outer loop + vertex 781.031 125.493 3.01949 + vertex 776.036 123.272 2.87574 + vertex 783.037 130.401 2.01427 + endloop + endfacet + facet normal 0.130689 -0.2525 -0.958731 + outer loop + vertex 770.516 119.878 3.01735 + vertex 772.628 124.772 2.01637 + vertex 776.036 123.272 2.87574 + endloop + endfacet + facet normal 0.133377 -0.247 -0.959793 + outer loop + vertex 772.628 124.772 2.01637 + vertex 783.037 130.401 2.01427 + vertex 776.036 123.272 2.87574 + endloop + endfacet + facet normal 0.0915601 -0.17006 -0.981171 + outer loop + vertex 770.441 128.748 1.12313 + vertex 780.809 134.334 1.12243 + vertex 772.628 124.772 2.01637 + endloop + endfacet + facet normal 0.0919347 -0.170373 -0.981082 + outer loop + vertex 772.628 124.772 2.01637 + vertex 780.809 134.334 1.12243 + vertex 783.037 130.401 2.01427 + endloop + endfacet + facet normal 0.195208 -0.270559 0.942704 + outer loop + vertex 779.78 158.613 22.6867 + vertex 784.117 161.716 22.6793 + vertex 779.422 160.628 23.3392 + endloop + endfacet + facet normal 0.198181 -0.286655 0.937312 + outer loop + vertex 779.422 160.628 23.3392 + vertex 784.117 161.716 22.6793 + vertex 784.121 163.533 23.234 + endloop + endfacet + facet normal 0.179191 -0.279721 0.943211 + outer loop + vertex 774.386 155.816 22.8821 + vertex 779.78 158.613 22.6867 + vertex 774.775 157.822 23.4031 + endloop + endfacet + facet normal 0.178571 -0.274236 0.944938 + outer loop + vertex 774.775 157.822 23.4031 + vertex 779.78 158.613 22.6867 + vertex 779.422 160.628 23.3392 + endloop + endfacet + facet normal 0.146657 -0.202649 0.968207 + outer loop + vertex 784.117 161.716 22.6793 + vertex 779.78 158.613 22.6867 + vertex 788.237 160.799 21.8634 + endloop + endfacet + facet normal 0.133332 -0.189194 0.972845 + outer loop + vertex 774.386 155.816 22.8821 + vertex 777.958 154.509 22.1384 + vertex 779.78 158.613 22.6867 + endloop + endfacet + facet normal 0.144589 -0.193855 0.970317 + outer loop + vertex 777.958 154.509 22.1384 + vertex 788.237 160.799 21.8634 + vertex 779.78 158.613 22.6867 + endloop + endfacet + facet normal 0.143654 -0.241797 0.959634 + outer loop + vertex 782.85 129.138 17.7438 + vertex 787.483 132.24 17.8318 + vertex 779.467 130.981 18.7146 + endloop + endfacet + facet normal 0.146683 -0.231628 0.961682 + outer loop + vertex 792.886 134.902 17.6488 + vertex 789.516 136.703 18.5968 + vertex 787.483 132.24 17.8318 + endloop + endfacet + facet normal 0.142112 -0.229741 0.96282 + outer loop + vertex 789.516 136.703 18.5968 + vertex 779.467 130.981 18.7146 + vertex 787.483 132.24 17.8318 + endloop + endfacet + facet normal 0.252717 -0.43224 0.865623 + outer loop + vertex 787.513 127.219 15.7516 + vertex 792.549 130.109 15.7242 + vertex 787.508 129.498 16.8907 + endloop + endfacet + facet normal 0.252667 -0.424606 0.869407 + outer loop + vertex 787.508 129.498 16.8907 + vertex 792.549 130.109 15.7242 + vertex 792.521 132.395 16.8489 + endloop + endfacet + facet normal 0.248606 -0.436181 0.864836 + outer loop + vertex 782.406 124.36 15.7775 + vertex 787.513 127.219 15.7516 + vertex 782.43 126.643 16.9222 + endloop + endfacet + facet normal 0.248614 -0.432723 0.866569 + outer loop + vertex 782.43 126.643 16.9222 + vertex 787.513 127.219 15.7516 + vertex 787.508 129.498 16.8907 + endloop + endfacet + facet normal 0.1947 -0.336207 0.921443 + outer loop + vertex 782.43 126.643 16.9222 + vertex 787.508 129.498 16.8907 + vertex 782.85 129.138 17.7438 + endloop + endfacet + facet normal 0.194467 -0.316806 0.928341 + outer loop + vertex 782.85 129.138 17.7438 + vertex 787.508 129.498 16.8907 + vertex 787.483 132.24 17.8318 + endloop + endfacet + facet normal 0.191 -0.317056 0.928975 + outer loop + vertex 787.508 129.498 16.8907 + vertex 792.521 132.395 16.8489 + vertex 787.483 132.24 17.8318 + endloop + endfacet + facet normal 0.190774 -0.323528 0.926787 + outer loop + vertex 787.483 132.24 17.8318 + vertex 792.521 132.395 16.8489 + vertex 792.886 134.902 17.6488 + endloop + endfacet + facet normal 0.396004 -0.692397 0.603131 + outer loop + vertex 788.013 124.17 12.7285 + vertex 793.079 127.058 12.717 + vertex 787.722 125.426 14.3615 + endloop + endfacet + facet normal 0.39616 -0.688284 0.60772 + outer loop + vertex 787.722 125.426 14.3615 + vertex 793.079 127.058 12.717 + vertex 792.776 128.318 14.3416 + endloop + endfacet + facet normal 0.389444 -0.695943 0.603321 + outer loop + vertex 782.873 121.305 12.741 + vertex 788.013 124.17 12.7285 + vertex 782.595 122.568 14.3783 + endloop + endfacet + facet normal 0.389478 -0.695215 0.604138 + outer loop + vertex 782.595 122.568 14.3783 + vertex 788.013 124.17 12.7285 + vertex 787.722 125.426 14.3615 + endloop + endfacet + facet normal 0.316278 -0.562956 0.763576 + outer loop + vertex 782.595 122.568 14.3783 + vertex 787.722 125.426 14.3615 + vertex 782.406 124.36 15.7775 + endloop + endfacet + facet normal 0.316253 -0.557872 0.767309 + outer loop + vertex 782.406 124.36 15.7775 + vertex 787.722 125.426 14.3615 + vertex 787.513 127.219 15.7516 + endloop + endfacet + facet normal 0.321355 -0.556439 0.766229 + outer loop + vertex 787.722 125.426 14.3615 + vertex 792.776 128.318 14.3416 + vertex 787.513 127.219 15.7516 + endloop + endfacet + facet normal 0.321304 -0.552694 0.768956 + outer loop + vertex 787.513 127.219 15.7516 + vertex 792.776 128.318 14.3416 + vertex 792.549 130.109 15.7242 + endloop + endfacet + facet normal 0.494417 -0.86738 0.0565909 + outer loop + vertex 788.38 123.437 8.98056 + vertex 793.459 126.332 8.97732 + vertex 788.254 123.49 10.901 + endloop + endfacet + facet normal 0.494864 -0.867009 0.0583475 + outer loop + vertex 788.254 123.49 10.901 + vertex 793.459 126.332 8.97732 + vertex 793.328 126.386 10.8938 + endloop + endfacet + facet normal 0.484775 -0.873038 0.0528909 + outer loop + vertex 783.229 120.577 8.98342 + vertex 788.38 123.437 8.98056 + vertex 783.107 120.626 10.9071 + endloop + endfacet + facet normal 0.48561 -0.87237 0.0561496 + outer loop + vertex 783.107 120.626 10.9071 + vertex 788.38 123.437 8.98056 + vertex 788.254 123.49 10.901 + endloop + endfacet + facet normal 0.454128 -0.815157 0.359564 + outer loop + vertex 783.107 120.626 10.9071 + vertex 788.254 123.49 10.901 + vertex 782.873 121.305 12.741 + endloop + endfacet + facet normal 0.454503 -0.81369 0.362403 + outer loop + vertex 782.873 121.305 12.741 + vertex 788.254 123.49 10.901 + vertex 788.013 124.17 12.7285 + endloop + endfacet + facet normal 0.462445 -0.80944 0.361871 + outer loop + vertex 788.254 123.49 10.901 + vertex 793.328 126.386 10.8938 + vertex 788.013 124.17 12.7285 + endloop + endfacet + facet normal 0.462361 -0.809782 0.361215 + outer loop + vertex 788.013 124.17 12.7285 + vertex 793.328 126.386 10.8938 + vertex 793.079 127.058 12.717 + endloop + endfacet + facet normal 0.406544 -0.712664 -0.571693 + outer loop + vertex 788.028 125.232 5.40391 + vertex 793.099 128.123 5.40655 + vertex 788.336 124.045 7.10246 + endloop + endfacet + facet normal 0.406359 -0.712557 -0.571957 + outer loop + vertex 788.336 124.045 7.10246 + vertex 793.099 128.123 5.40655 + vertex 793.411 126.939 7.10272 + endloop + endfacet + facet normal 0.396015 -0.716183 -0.574678 + outer loop + vertex 782.873 122.377 5.40893 + vertex 788.028 125.232 5.40391 + vertex 783.185 121.189 7.10522 + endloop + endfacet + facet normal 0.397213 -0.716895 -0.572961 + outer loop + vertex 783.185 121.189 7.10522 + vertex 788.028 125.232 5.40391 + vertex 788.336 124.045 7.10246 + endloop + endfacet + facet normal 0.464852 -0.838598 -0.284016 + outer loop + vertex 783.185 121.189 7.10522 + vertex 788.336 124.045 7.10246 + vertex 783.229 120.577 8.98342 + endloop + endfacet + facet normal 0.465554 -0.838755 -0.282401 + outer loop + vertex 783.229 120.577 8.98342 + vertex 788.336 124.045 7.10246 + vertex 788.38 123.437 8.98056 + endloop + endfacet + facet normal 0.475414 -0.833682 -0.280991 + outer loop + vertex 788.336 124.045 7.10246 + vertex 793.411 126.939 7.10272 + vertex 788.38 123.437 8.98056 + endloop + endfacet + facet normal 0.474939 -0.833584 -0.282082 + outer loop + vertex 788.38 123.437 8.98056 + vertex 793.411 126.939 7.10272 + vertex 793.459 126.332 8.97732 + endloop + endfacet + facet normal 0.205469 -0.382543 -0.900801 + outer loop + vertex 786.45 128.969 2.87751 + vertex 791.311 131.242 3.02124 + vertex 787.359 126.828 3.9941 + endloop + endfacet + facet normal 0.226357 -0.39859 -0.888757 + outer loop + vertex 787.359 126.828 3.9941 + vertex 791.311 131.242 3.02124 + vertex 792.44 129.714 3.9939 + endloop + endfacet + facet normal 0.229541 -0.394107 -0.889939 + outer loop + vertex 781.031 125.493 3.01949 + vertex 786.45 128.969 2.87751 + vertex 782.198 123.969 3.9954 + endloop + endfacet + facet normal 0.210497 -0.380297 -0.900592 + outer loop + vertex 782.198 123.969 3.9954 + vertex 786.45 128.969 2.87751 + vertex 787.359 126.828 3.9941 + endloop + endfacet + facet normal 0.307679 -0.555625 -0.772408 + outer loop + vertex 782.198 123.969 3.9954 + vertex 787.359 126.828 3.9941 + vertex 782.873 122.377 5.40893 + endloop + endfacet + facet normal 0.306411 -0.554715 -0.773565 + outer loop + vertex 782.873 122.377 5.40893 + vertex 787.359 126.828 3.9941 + vertex 788.028 125.232 5.40391 + endloop + endfacet + facet normal 0.313208 -0.551495 -0.773145 + outer loop + vertex 787.359 126.828 3.9941 + vertex 792.44 129.714 3.9939 + vertex 788.028 125.232 5.40391 + endloop + endfacet + facet normal 0.315813 -0.553316 -0.770781 + outer loop + vertex 788.028 125.232 5.40391 + vertex 792.44 129.714 3.9939 + vertex 793.099 128.123 5.40655 + endloop + endfacet + facet normal 0.146154 -0.252136 -0.956591 + outer loop + vertex 791.311 131.242 3.02124 + vertex 786.45 128.969 2.87751 + vertex 793.287 136.207 2.01438 + endloop + endfacet + facet normal 0.136619 -0.252061 -0.958019 + outer loop + vertex 781.031 125.493 3.01949 + vertex 783.037 130.401 2.01427 + vertex 786.45 128.969 2.87751 + endloop + endfacet + facet normal 0.139419 -0.246081 -0.95917 + outer loop + vertex 783.037 130.401 2.01427 + vertex 793.287 136.207 2.01438 + vertex 786.45 128.969 2.87751 + endloop + endfacet + facet normal 0.0950685 -0.168599 -0.981089 + outer loop + vertex 780.809 134.334 1.12243 + vertex 791.072 140.122 1.12225 + vertex 783.037 130.401 2.01427 + endloop + endfacet + facet normal 0.0959065 -0.169273 -0.980892 + outer loop + vertex 783.037 130.401 2.01427 + vertex 791.072 140.122 1.12225 + vertex 793.287 136.207 2.01438 + endloop + endfacet + facet normal 0.219305 -0.280207 0.934553 + outer loop + vertex 788.98 164.47 22.455 + vertex 793.996 167.938 22.3176 + vertex 788.9 166.555 23.0987 + endloop + endfacet + facet normal 0.223313 -0.298774 0.927828 + outer loop + vertex 788.9 166.555 23.0987 + vertex 793.996 167.938 22.3176 + vertex 793.653 169.753 22.9846 + endloop + endfacet + facet normal 0.205301 -0.28624 0.935905 + outer loop + vertex 784.117 161.716 22.6793 + vertex 788.98 164.47 22.455 + vertex 784.121 163.533 23.234 + endloop + endfacet + facet normal 0.204662 -0.281659 0.937434 + outer loop + vertex 784.121 163.533 23.234 + vertex 788.98 164.47 22.455 + vertex 788.9 166.555 23.0987 + endloop + endfacet + facet normal 0.167796 -0.204509 0.964376 + outer loop + vertex 793.996 167.938 22.3176 + vertex 788.98 164.47 22.455 + vertex 794.23 165.532 21.7666 + endloop + endfacet + facet normal 0.135089 -0.151042 0.979254 + outer loop + vertex 794.976 163.733 21.3863 + vertex 794.23 165.532 21.7666 + vertex 788.237 160.799 21.8634 + endloop + endfacet + facet normal 0.150659 -0.186932 0.970751 + outer loop + vertex 784.117 161.716 22.6793 + vertex 788.237 160.799 21.8634 + vertex 788.98 164.47 22.455 + endloop + endfacet + facet normal 0.165207 -0.189415 0.967899 + outer loop + vertex 794.23 165.532 21.7666 + vertex 788.98 164.47 22.455 + vertex 788.237 160.799 21.8634 + endloop + endfacet + facet normal 0.147227 -0.230687 0.961825 + outer loop + vertex 792.886 134.902 17.6488 + vertex 797.421 138.092 17.7198 + vertex 789.516 136.703 18.5968 + endloop + endfacet + facet normal 0.148917 -0.219691 0.964137 + outer loop + vertex 802.762 140.88 17.5302 + vertex 799.382 142.63 18.4509 + vertex 797.421 138.092 17.7198 + endloop + endfacet + facet normal 0.145403 -0.218309 0.964987 + outer loop + vertex 799.382 142.63 18.4509 + vertex 789.516 136.703 18.5968 + vertex 797.421 138.092 17.7198 + endloop + endfacet + facet normal 0.259565 -0.418453 0.870358 + outer loop + vertex 797.545 133.053 15.6906 + vertex 802.523 136.066 15.6542 + vertex 797.493 135.339 16.8052 + endloop + endfacet + facet normal 0.259366 -0.412447 0.873279 + outer loop + vertex 797.493 135.339 16.8052 + vertex 802.523 136.066 15.6542 + vertex 802.443 138.35 16.7572 + endloop + endfacet + facet normal 0.255844 -0.424207 0.868673 + outer loop + vertex 792.549 130.109 15.7242 + vertex 797.545 133.053 15.6906 + vertex 792.521 132.395 16.8489 + endloop + endfacet + facet normal 0.25575 -0.418969 0.871239 + outer loop + vertex 792.521 132.395 16.8489 + vertex 797.545 133.053 15.6906 + vertex 797.493 135.339 16.8052 + endloop + endfacet + facet normal 0.200095 -0.324182 0.924591 + outer loop + vertex 792.521 132.395 16.8489 + vertex 797.493 135.339 16.8052 + vertex 792.886 134.902 17.6488 + endloop + endfacet + facet normal 0.199463 -0.304259 0.931472 + outer loop + vertex 792.886 134.902 17.6488 + vertex 797.493 135.339 16.8052 + vertex 797.421 138.092 17.7198 + endloop + endfacet + facet normal 0.194393 -0.3047 0.9324 + outer loop + vertex 797.493 135.339 16.8052 + vertex 802.443 138.35 16.7572 + vertex 797.421 138.092 17.7198 + endloop + endfacet + facet normal 0.194345 -0.308965 0.931005 + outer loop + vertex 797.421 138.092 17.7198 + vertex 802.443 138.35 16.7572 + vertex 802.762 140.88 17.5302 + endloop + endfacet + facet normal 0.409949 -0.681129 0.606634 + outer loop + vertex 798.107 130.001 12.7022 + vertex 803.124 133.007 12.6875 + vertex 797.79 131.253 14.3217 + endloop + endfacet + facet normal 0.409996 -0.676675 0.611567 + outer loop + vertex 797.79 131.253 14.3217 + vertex 803.124 133.007 12.6875 + vertex 802.791 134.261 14.2979 + endloop + endfacet + facet normal 0.402993 -0.685257 0.606647 + outer loop + vertex 793.079 127.058 12.717 + vertex 798.107 130.001 12.7022 + vertex 792.776 128.318 14.3416 + endloop + endfacet + facet normal 0.403018 -0.684289 0.607721 + outer loop + vertex 792.776 128.318 14.3416 + vertex 798.107 130.001 12.7022 + vertex 797.79 131.253 14.3217 + endloop + endfacet + facet normal 0.325844 -0.551374 0.767993 + outer loop + vertex 792.776 128.318 14.3416 + vertex 797.79 131.253 14.3217 + vertex 792.549 130.109 15.7242 + endloop + endfacet + facet normal 0.32565 -0.543742 0.773496 + outer loop + vertex 792.549 130.109 15.7242 + vertex 797.79 131.253 14.3217 + vertex 797.545 133.053 15.6906 + endloop + endfacet + facet normal 0.330006 -0.542439 0.772564 + outer loop + vertex 797.79 131.253 14.3217 + vertex 802.791 134.261 14.2979 + vertex 797.545 133.053 15.6906 + endloop + endfacet + facet normal 0.329723 -0.535531 0.777489 + outer loop + vertex 797.545 133.053 15.6906 + vertex 802.791 134.261 14.2979 + vertex 802.523 136.066 15.6542 + endloop + endfacet + facet normal 0.514719 -0.855303 0.0593367 + outer loop + vertex 798.502 129.266 8.97357 + vertex 803.532 132.293 8.9698 + vertex 798.367 129.317 10.8871 + endloop + endfacet + facet normal 0.51367 -0.856217 0.0550938 + outer loop + vertex 798.367 129.317 10.8871 + vertex 803.532 132.293 8.9698 + vertex 803.393 132.332 10.8766 + endloop + endfacet + facet normal 0.50207 -0.862831 0.0587194 + outer loop + vertex 793.459 126.332 8.97732 + vertex 798.502 129.266 8.97357 + vertex 793.328 126.386 10.8938 + endloop + endfacet + facet normal 0.50205 -0.862848 0.0586376 + outer loop + vertex 793.328 126.386 10.8938 + vertex 798.502 129.266 8.97357 + vertex 798.367 129.317 10.8871 + endloop + endfacet + facet normal 0.469352 -0.805954 0.360759 + outer loop + vertex 793.328 126.386 10.8938 + vertex 798.367 129.317 10.8871 + vertex 793.079 127.058 12.717 + endloop + endfacet + facet normal 0.470374 -0.801543 0.369158 + outer loop + vertex 793.079 127.058 12.717 + vertex 798.367 129.317 10.8871 + vertex 798.107 130.001 12.7022 + endloop + endfacet + facet normal 0.478716 -0.796854 0.368585 + outer loop + vertex 798.367 129.317 10.8871 + vertex 803.393 132.332 10.8766 + vertex 798.107 130.001 12.7022 + endloop + endfacet + facet normal 0.478685 -0.797 0.368308 + outer loop + vertex 798.107 130.001 12.7022 + vertex 803.393 132.332 10.8766 + vertex 803.124 133.007 12.6875 + endloop + endfacet + facet normal 0.422763 -0.70828 -0.565341 + outer loop + vertex 798.145 131.054 5.40265 + vertex 803.186 134.064 5.4009 + vertex 798.454 129.882 7.10198 + endloop + endfacet + facet normal 0.424056 -0.708987 -0.563484 + outer loop + vertex 798.454 129.882 7.10198 + vertex 803.186 134.064 5.4009 + vertex 803.492 132.897 7.10062 + endloop + endfacet + facet normal 0.412011 -0.709938 -0.571169 + outer loop + vertex 793.099 128.123 5.40655 + vertex 798.145 131.054 5.40265 + vertex 793.411 126.939 7.10272 + endloop + endfacet + facet normal 0.415338 -0.711803 -0.56642 + outer loop + vertex 793.411 126.939 7.10272 + vertex 798.145 131.054 5.40265 + vertex 798.454 129.882 7.10198 + endloop + endfacet + facet normal 0.483744 -0.828941 -0.2808 + outer loop + vertex 793.411 126.939 7.10272 + vertex 798.454 129.882 7.10198 + vertex 793.459 126.332 8.97732 + endloop + endfacet + facet normal 0.481882 -0.828572 -0.28506 + outer loop + vertex 793.459 126.332 8.97732 + vertex 798.454 129.882 7.10198 + vertex 798.502 129.266 8.97357 + endloop + endfacet + facet normal 0.492323 -0.822957 -0.283479 + outer loop + vertex 798.454 129.882 7.10198 + vertex 803.492 132.897 7.10062 + vertex 798.502 129.266 8.97357 + endloop + endfacet + facet normal 0.495337 -0.823513 -0.276527 + outer loop + vertex 798.502 129.266 8.97357 + vertex 803.492 132.897 7.10062 + vertex 803.532 132.293 8.9698 + endloop + endfacet + facet normal 0.214619 -0.380706 -0.899445 + outer loop + vertex 796.609 134.797 2.87758 + vertex 801.403 137.163 3.02001 + vertex 797.479 132.648 3.99491 + endloop + endfacet + facet normal 0.237578 -0.397793 -0.886181 + outer loop + vertex 797.479 132.648 3.99491 + vertex 801.403 137.163 3.02001 + vertex 802.516 135.654 3.99604 + endloop + endfacet + facet normal 0.237911 -0.390435 -0.889359 + outer loop + vertex 791.311 131.242 3.02124 + vertex 796.609 134.797 2.87758 + vertex 792.44 129.714 3.9939 + endloop + endfacet + facet normal 0.22038 -0.378199 -0.89911 + outer loop + vertex 792.44 129.714 3.9939 + vertex 796.609 134.797 2.87758 + vertex 797.479 132.648 3.99491 + endloop + endfacet + facet normal 0.3209 -0.550887 -0.77042 + outer loop + vertex 792.44 129.714 3.9939 + vertex 797.479 132.648 3.99491 + vertex 793.099 128.123 5.40655 + endloop + endfacet + facet normal 0.318492 -0.549236 -0.772595 + outer loop + vertex 793.099 128.123 5.40655 + vertex 797.479 132.648 3.99491 + vertex 798.145 131.054 5.40265 + endloop + endfacet + facet normal 0.325811 -0.545695 -0.772052 + outer loop + vertex 797.479 132.648 3.99491 + vertex 802.516 135.654 3.99604 + vertex 798.145 131.054 5.40265 + endloop + endfacet + facet normal 0.32546 -0.545458 -0.772368 + outer loop + vertex 798.145 131.054 5.40265 + vertex 802.516 135.654 3.99604 + vertex 803.186 134.064 5.4009 + endloop + endfacet + facet normal 0.151732 -0.249864 -0.956319 + outer loop + vertex 801.403 137.163 3.02001 + vertex 796.609 134.797 2.87758 + vertex 803.393 142.219 2.01473 + endloop + endfacet + facet normal 0.14236 -0.250812 -0.957511 + outer loop + vertex 791.311 131.242 3.02124 + vertex 793.287 136.207 2.01438 + vertex 796.609 134.797 2.87758 + endloop + endfacet + facet normal 0.145411 -0.244366 -0.958719 + outer loop + vertex 793.287 136.207 2.01438 + vertex 803.393 142.219 2.01473 + vertex 796.609 134.797 2.87758 + endloop + endfacet + facet normal 0.099059 -0.167488 -0.980885 + outer loop + vertex 791.072 140.122 1.12225 + vertex 801.206 146.115 1.12234 + vertex 793.287 136.207 2.01438 + endloop + endfacet + facet normal 0.100207 -0.168381 -0.980615 + outer loop + vertex 793.287 136.207 2.01438 + vertex 801.206 146.115 1.12234 + vertex 803.393 142.219 2.01473 + endloop + endfacet + facet normal 0.24131 -0.303023 0.921926 + outer loop + vertex 798.728 171.269 22.196 + vertex 803.29 174.508 22.0663 + vertex 798.343 172.985 22.8605 + endloop + endfacet + facet normal 0.239886 -0.29722 0.924183 + outer loop + vertex 798.343 172.985 22.8605 + vertex 803.29 174.508 22.0663 + vertex 802.934 176.192 22.7003 + endloop + endfacet + facet normal 0.232522 -0.296473 0.926303 + outer loop + vertex 793.996 167.938 22.3176 + vertex 798.728 171.269 22.196 + vertex 793.653 169.753 22.9846 + endloop + endfacet + facet normal 0.23455 -0.304965 0.923029 + outer loop + vertex 793.653 169.753 22.9846 + vertex 798.728 171.269 22.196 + vertex 798.343 172.985 22.8605 + endloop + endfacet + facet normal 0.141651 -0.149873 0.978506 + outer loop + vertex 799.591 166.523 21.1793 + vertex 803.82 170.022 21.1031 + vertex 799.123 169.101 21.642 + endloop + endfacet + facet normal 0.143252 -0.159018 0.976828 + outer loop + vertex 799.123 169.101 21.642 + vertex 803.82 170.022 21.1031 + vertex 803.773 172.449 21.505 + endloop + endfacet + facet normal 0.1352 -0.150994 0.979246 + outer loop + vertex 794.976 163.733 21.3863 + vertex 799.591 166.523 21.1793 + vertex 794.23 165.532 21.7666 + endloop + endfacet + facet normal 0.135229 -0.151166 0.979215 + outer loop + vertex 794.23 165.532 21.7666 + vertex 799.591 166.523 21.1793 + vertex 799.123 169.101 21.642 + endloop + endfacet + facet normal 0.173225 -0.203794 0.963567 + outer loop + vertex 794.23 165.532 21.7666 + vertex 799.123 169.101 21.642 + vertex 793.996 167.938 22.3176 + endloop + endfacet + facet normal 0.175147 -0.21371 0.961068 + outer loop + vertex 793.996 167.938 22.3176 + vertex 799.123 169.101 21.642 + vertex 798.728 171.269 22.196 + endloop + endfacet + facet normal 0.181193 -0.212396 0.960238 + outer loop + vertex 799.123 169.101 21.642 + vertex 803.773 172.449 21.505 + vertex 798.728 171.269 22.196 + endloop + endfacet + facet normal 0.18242 -0.218593 0.958614 + outer loop + vertex 798.728 171.269 22.196 + vertex 803.773 172.449 21.505 + vertex 803.29 174.508 22.0663 + endloop + endfacet + facet normal 0.149669 -0.218339 0.964328 + outer loop + vertex 802.762 140.88 17.5302 + vertex 807.266 144.218 17.5869 + vertex 799.382 142.63 18.4509 + endloop + endfacet + facet normal 0.149441 -0.20554 0.967171 + outer loop + vertex 812.609 147.195 17.394 + vertex 809.154 148.855 18.2806 + vertex 807.266 144.218 17.5869 + endloop + endfacet + facet normal 0.147295 -0.204741 0.96767 + outer loop + vertex 809.154 148.855 18.2806 + vertex 799.382 142.63 18.4509 + vertex 807.266 144.218 17.5869 + endloop + endfacet + facet normal 0.264706 -0.400703 0.877136 + outer loop + vertex 807.495 139.147 15.6208 + vertex 812.481 142.345 15.5772 + vertex 807.391 141.448 16.7037 + endloop + endfacet + facet normal 0.264245 -0.394234 0.880201 + outer loop + vertex 807.391 141.448 16.7037 + vertex 812.481 142.345 15.5772 + vertex 812.346 144.644 16.6474 + endloop + endfacet + facet normal 0.261295 -0.412166 0.872837 + outer loop + vertex 802.523 136.066 15.6542 + vertex 807.495 139.147 15.6208 + vertex 802.443 138.35 16.7572 + endloop + endfacet + facet normal 0.260754 -0.401309 0.878042 + outer loop + vertex 802.443 138.35 16.7572 + vertex 807.495 139.147 15.6208 + vertex 807.391 141.448 16.7037 + endloop + endfacet + facet normal 0.203813 -0.309486 0.928805 + outer loop + vertex 802.443 138.35 16.7572 + vertex 807.391 141.448 16.7037 + vertex 802.762 140.88 17.5302 + endloop + endfacet + facet normal 0.202536 -0.289191 0.9356 + outer loop + vertex 802.762 140.88 17.5302 + vertex 807.391 141.448 16.7037 + vertex 807.266 144.218 17.5869 + endloop + endfacet + facet normal 0.197479 -0.289712 0.93652 + outer loop + vertex 807.391 141.448 16.7037 + vertex 812.346 144.644 16.6474 + vertex 807.266 144.218 17.5869 + endloop + endfacet + facet normal 0.197587 -0.294023 0.935152 + outer loop + vertex 807.266 144.218 17.5869 + vertex 812.346 144.644 16.6474 + vertex 812.609 147.195 17.394 + endloop + endfacet + facet normal 0.42534 -0.666014 0.612789 + outer loop + vertex 808.145 136.105 12.6708 + vertex 813.175 139.301 12.6527 + vertex 807.792 137.353 14.2724 + endloop + endfacet + facet normal 0.425238 -0.662669 0.616476 + outer loop + vertex 807.792 137.353 14.2724 + vertex 813.175 139.301 12.6527 + vertex 812.801 140.543 14.2454 + endloop + endfacet + facet normal 0.417385 -0.673206 0.610396 + outer loop + vertex 803.124 133.007 12.6875 + vertex 808.145 136.105 12.6708 + vertex 802.791 134.261 14.2979 + endloop + endfacet + facet normal 0.417355 -0.669892 0.614052 + outer loop + vertex 802.791 134.261 14.2979 + vertex 808.145 136.105 12.6708 + vertex 807.792 137.353 14.2724 + endloop + endfacet + facet normal 0.334237 -0.534135 0.776522 + outer loop + vertex 802.791 134.261 14.2979 + vertex 807.792 137.353 14.2724 + vertex 802.523 136.066 15.6542 + endloop + endfacet + facet normal 0.334027 -0.530537 0.779074 + outer loop + vertex 802.523 136.066 15.6542 + vertex 807.792 137.353 14.2724 + vertex 807.495 139.147 15.6208 + endloop + endfacet + facet normal 0.340616 -0.528397 0.777675 + outer loop + vertex 807.792 137.353 14.2724 + vertex 812.801 140.543 14.2454 + vertex 807.495 139.147 15.6208 + endloop + endfacet + facet normal 0.339876 -0.519159 0.784193 + outer loop + vertex 807.495 139.147 15.6208 + vertex 812.801 140.543 14.2454 + vertex 812.481 142.345 15.5772 + endloop + endfacet + facet normal 0.534729 -0.84297 0.0588769 + outer loop + vertex 808.577 135.383 8.96315 + vertex 813.629 138.588 8.95867 + vertex 808.428 135.422 10.8684 + endloop + endfacet + facet normal 0.534838 -0.842868 0.0593432 + outer loop + vertex 808.428 135.422 10.8684 + vertex 813.629 138.588 8.95867 + vertex 813.473 138.623 10.8579 + endloop + endfacet + facet normal 0.52163 -0.85136 0.0555762 + outer loop + vertex 803.532 132.293 8.9698 + vertex 808.577 135.383 8.96315 + vertex 803.393 132.332 10.8766 + endloop + endfacet + facet normal 0.522232 -0.850825 0.0580615 + outer loop + vertex 803.393 132.332 10.8766 + vertex 808.577 135.383 8.96315 + vertex 808.428 135.422 10.8684 + endloop + endfacet + facet normal 0.486825 -0.792305 0.367768 + outer loop + vertex 803.393 132.332 10.8766 + vertex 808.428 135.422 10.8684 + vertex 803.124 133.007 12.6875 + endloop + endfacet + facet normal 0.487591 -0.788259 0.37537 + outer loop + vertex 803.124 133.007 12.6875 + vertex 808.428 135.422 10.8684 + vertex 808.145 136.105 12.6708 + endloop + endfacet + facet normal 0.497218 -0.782536 0.374715 + outer loop + vertex 808.428 135.422 10.8684 + vertex 813.473 138.623 10.8579 + vertex 808.145 136.105 12.6708 + endloop + endfacet + facet normal 0.497484 -0.780893 0.377777 + outer loop + vertex 808.145 136.105 12.6708 + vertex 813.473 138.623 10.8579 + vertex 813.175 139.301 12.6527 + endloop + endfacet + facet normal 0.441591 -0.698903 -0.562611 + outer loop + vertex 808.235 137.166 5.40111 + vertex 813.296 140.364 5.40057 + vertex 808.541 135.994 7.09714 + endloop + endfacet + facet normal 0.442265 -0.699259 -0.561639 + outer loop + vertex 808.541 135.994 7.09714 + vertex 813.296 140.364 5.40057 + vertex 813.6 139.196 7.09454 + endloop + endfacet + facet normal 0.43295 -0.704677 -0.562125 + outer loop + vertex 803.186 134.064 5.4009 + vertex 808.235 137.166 5.40111 + vertex 803.492 132.897 7.10062 + endloop + endfacet + facet normal 0.431485 -0.70389 -0.564234 + outer loop + vertex 803.492 132.897 7.10062 + vertex 808.235 137.166 5.40111 + vertex 808.541 135.994 7.09714 + endloop + endfacet + facet normal 0.502607 -0.819482 -0.275383 + outer loop + vertex 803.492 132.897 7.10062 + vertex 808.541 135.994 7.09714 + vertex 803.532 132.293 8.9698 + endloop + endfacet + facet normal 0.501548 -0.819298 -0.27785 + outer loop + vertex 803.532 132.293 8.9698 + vertex 808.541 135.994 7.09714 + vertex 808.577 135.383 8.96315 + endloop + endfacet + facet normal 0.513943 -0.812281 -0.275794 + outer loop + vertex 808.541 135.994 7.09714 + vertex 813.6 139.196 7.09454 + vertex 808.577 135.383 8.96315 + endloop + endfacet + facet normal 0.515088 -0.812467 -0.273096 + outer loop + vertex 808.577 135.383 8.96315 + vertex 813.6 139.196 7.09454 + vertex 813.629 138.588 8.95867 + endloop + endfacet + facet normal 0.225128 -0.37775 -0.898122 + outer loop + vertex 806.688 140.876 2.87814 + vertex 811.489 143.399 3.02024 + vertex 807.566 138.744 3.99452 + endloop + endfacet + facet normal 0.248605 -0.394694 -0.884541 + outer loop + vertex 807.566 138.744 3.99452 + vertex 811.489 143.399 3.02024 + vertex 812.622 141.93 3.99435 + endloop + endfacet + facet normal 0.249587 -0.389251 -0.886674 + outer loop + vertex 801.403 137.163 3.02001 + vertex 806.688 140.876 2.87814 + vertex 802.516 135.654 3.99604 + endloop + endfacet + facet normal 0.229669 -0.375723 -0.897822 + outer loop + vertex 802.516 135.654 3.99604 + vertex 806.688 140.876 2.87814 + vertex 807.566 138.744 3.99452 + endloop + endfacet + facet normal 0.331705 -0.542389 -0.771872 + outer loop + vertex 802.516 135.654 3.99604 + vertex 807.566 138.744 3.99452 + vertex 803.186 134.064 5.4009 + endloop + endfacet + facet normal 0.334326 -0.544132 -0.76951 + outer loop + vertex 803.186 134.064 5.4009 + vertex 807.566 138.744 3.99452 + vertex 808.235 137.166 5.40111 + endloop + endfacet + facet normal 0.340728 -0.540929 -0.76896 + outer loop + vertex 807.566 138.744 3.99452 + vertex 812.622 141.93 3.99435 + vertex 808.235 137.166 5.40111 + endloop + endfacet + facet normal 0.342455 -0.542058 -0.767396 + outer loop + vertex 808.235 137.166 5.40111 + vertex 812.622 141.93 3.99435 + vertex 813.296 140.364 5.40057 + endloop + endfacet + facet normal 0.15787 -0.246512 -0.956195 + outer loop + vertex 811.489 143.399 3.02024 + vertex 806.688 140.876 2.87814 + vertex 813.416 148.517 2.01883 + endloop + endfacet + facet normal 0.149189 -0.248988 -0.956947 + outer loop + vertex 801.403 137.163 3.02001 + vertex 803.393 142.219 2.01473 + vertex 806.688 140.876 2.87814 + endloop + endfacet + facet normal 0.152407 -0.241934 -0.958249 + outer loop + vertex 803.393 142.219 2.01473 + vertex 813.416 148.517 2.01883 + vertex 806.688 140.876 2.87814 + endloop + endfacet + facet normal 0.103739 -0.166392 -0.980588 + outer loop + vertex 801.206 146.115 1.12234 + vertex 811.194 152.347 1.12155 + vertex 803.393 142.219 2.01473 + endloop + endfacet + facet normal 0.106029 -0.168108 -0.98005 + outer loop + vertex 803.393 142.219 2.01473 + vertex 811.194 152.347 1.12155 + vertex 813.416 148.517 2.01883 + endloop + endfacet + facet normal 0.245788 -0.288663 0.925344 + outer loop + vertex 807.755 177.75 21.9223 + vertex 812.167 181.041 21.7769 + vertex 807.387 179.403 22.5354 + endloop + endfacet + facet normal 0.244973 -0.28577 0.926458 + outer loop + vertex 807.387 179.403 22.5354 + vertex 812.167 181.041 21.7769 + vertex 811.765 182.694 22.3931 + endloop + endfacet + facet normal 0.244683 -0.295893 0.923351 + outer loop + vertex 803.29 174.508 22.0663 + vertex 807.755 177.75 21.9223 + vertex 802.934 176.192 22.7003 + endloop + endfacet + facet normal 0.243004 -0.289462 0.92583 + outer loop + vertex 802.934 176.192 22.7003 + vertex 807.755 177.75 21.9223 + vertex 807.387 179.403 22.5354 + endloop + endfacet + facet normal 0.151312 -0.152185 0.976701 + outer loop + vertex 808.837 173.138 20.8718 + vertex 812.886 176.621 20.7874 + vertex 808.278 175.716 21.3601 + endloop + endfacet + facet normal 0.152654 -0.159935 0.975253 + outer loop + vertex 808.278 175.716 21.3601 + vertex 812.886 176.621 20.7874 + vertex 812.71 179.002 21.2052 + endloop + endfacet + facet normal 0.143753 -0.158997 0.976757 + outer loop + vertex 803.82 170.022 21.1031 + vertex 808.837 173.138 20.8718 + vertex 803.773 172.449 21.505 + endloop + endfacet + facet normal 0.143197 -0.154117 0.977621 + outer loop + vertex 803.773 172.449 21.505 + vertex 808.837 173.138 20.8718 + vertex 808.278 175.716 21.3601 + endloop + endfacet + facet normal 0.188188 -0.217033 0.957853 + outer loop + vertex 803.773 172.449 21.505 + vertex 808.278 175.716 21.3601 + vertex 803.29 174.508 22.0663 + endloop + endfacet + facet normal 0.188055 -0.216382 0.958026 + outer loop + vertex 803.29 174.508 22.0663 + vertex 808.278 175.716 21.3601 + vertex 807.755 177.75 21.9223 + endloop + endfacet + facet normal 0.192832 -0.214976 0.957393 + outer loop + vertex 808.278 175.716 21.3601 + vertex 812.71 179.002 21.2052 + vertex 807.755 177.75 21.9223 + endloop + endfacet + facet normal 0.193217 -0.216779 0.956909 + outer loop + vertex 807.755 177.75 21.9223 + vertex 812.71 179.002 21.2052 + vertex 812.167 181.041 21.7769 + endloop + endfacet + facet normal 0.150304 -0.203862 0.967393 + outer loop + vertex 812.609 147.195 17.394 + vertex 817.094 150.715 17.4391 + vertex 809.154 148.855 18.2806 + endloop + endfacet + facet normal 0.149658 -0.190293 0.970253 + outer loop + vertex 822.42 153.904 17.2429 + vertex 818.823 155.417 18.0944 + vertex 817.094 150.715 17.4391 + endloop + endfacet + facet normal 0.147295 -0.189496 0.97077 + outer loop + vertex 818.823 155.417 18.0944 + vertex 809.154 148.855 18.2806 + vertex 817.094 150.715 17.4391 + endloop + endfacet + facet normal 0.270688 -0.384814 0.882409 + outer loop + vertex 817.47 145.637 15.5358 + vertex 822.446 149.035 15.4909 + vertex 817.302 147.938 16.5907 + endloop + endfacet + facet normal 0.269708 -0.376203 0.886414 + outer loop + vertex 817.302 147.938 16.5907 + vertex 822.446 149.035 15.4909 + vertex 822.246 151.339 16.5299 + endloop + endfacet + facet normal 0.26717 -0.393752 0.879534 + outer loop + vertex 812.481 142.345 15.5772 + vertex 817.47 145.637 15.5358 + vertex 812.346 144.644 16.6474 + endloop + endfacet + facet normal 0.266417 -0.38557 0.883378 + outer loop + vertex 812.346 144.644 16.6474 + vertex 817.47 145.637 15.5358 + vertex 817.302 147.938 16.5907 + endloop + endfacet + facet normal 0.206339 -0.294341 0.93316 + outer loop + vertex 812.346 144.644 16.6474 + vertex 817.302 147.938 16.5907 + vertex 812.609 147.195 17.394 + endloop + endfacet + facet normal 0.204041 -0.271975 0.940424 + outer loop + vertex 812.609 147.195 17.394 + vertex 817.302 147.938 16.5907 + vertex 817.094 150.715 17.4391 + endloop + endfacet + facet normal 0.199117 -0.27261 0.941295 + outer loop + vertex 817.302 147.938 16.5907 + vertex 822.246 151.339 16.5299 + vertex 817.094 150.715 17.4391 + endloop + endfacet + facet normal 0.199278 -0.275006 0.940564 + outer loop + vertex 817.094 150.715 17.4391 + vertex 822.246 151.339 16.5299 + vertex 822.42 153.904 17.2429 + endloop + endfacet + facet normal 0.440465 -0.647262 0.622128 + outer loop + vertex 818.212 142.589 12.6374 + vertex 823.235 145.989 12.618 + vertex 817.815 143.837 14.217 + endloop + endfacet + facet normal 0.440105 -0.642555 0.627241 + outer loop + vertex 817.815 143.837 14.217 + vertex 823.235 145.989 12.618 + vertex 822.817 147.234 14.1864 + endloop + endfacet + facet normal 0.432175 -0.659183 0.615389 + outer loop + vertex 813.175 139.301 12.6527 + vertex 818.212 142.589 12.6374 + vertex 812.801 140.543 14.2454 + endloop + endfacet + facet normal 0.431783 -0.65177 0.623506 + outer loop + vertex 812.801 140.543 14.2454 + vertex 818.212 142.589 12.6374 + vertex 817.815 143.837 14.217 + endloop + endfacet + facet normal 0.344528 -0.517596 0.783196 + outer loop + vertex 812.801 140.543 14.2454 + vertex 817.815 143.837 14.217 + vertex 812.481 142.345 15.5772 + endloop + endfacet + facet normal 0.343871 -0.511121 0.787724 + outer loop + vertex 812.481 142.345 15.5772 + vertex 817.815 143.837 14.217 + vertex 817.47 145.637 15.5358 + endloop + endfacet + facet normal 0.350313 -0.508871 0.78634 + outer loop + vertex 817.815 143.837 14.217 + vertex 822.817 147.234 14.1864 + vertex 817.47 145.637 15.5358 + endloop + endfacet + facet normal 0.349377 -0.50127 0.791621 + outer loop + vertex 817.47 145.637 15.5358 + vertex 822.817 147.234 14.1864 + vertex 822.446 149.035 15.4909 + endloop + endfacet + facet normal 0.557343 -0.827946 0.0622441 + outer loop + vertex 818.689 141.895 8.95369 + vertex 823.735 145.292 8.94779 + vertex 818.524 141.927 10.8467 + endloop + endfacet + facet normal 0.558595 -0.82665 0.0679751 + outer loop + vertex 818.524 141.927 10.8467 + vertex 823.735 145.292 8.94779 + vertex 823.561 145.33 10.8359 + endloop + endfacet + facet normal 0.546175 -0.835509 0.0601445 + outer loop + vertex 813.629 138.588 8.95867 + vertex 818.689 141.895 8.95369 + vertex 813.473 138.623 10.8579 + endloop + endfacet + facet normal 0.546465 -0.835227 0.0614218 + outer loop + vertex 813.473 138.623 10.8579 + vertex 818.689 141.895 8.95369 + vertex 818.524 141.927 10.8467 + endloop + endfacet + facet normal 0.507575 -0.774698 0.377109 + outer loop + vertex 813.473 138.623 10.8579 + vertex 818.524 141.927 10.8467 + vertex 813.175 139.301 12.6527 + endloop + endfacet + facet normal 0.507447 -0.775609 0.375405 + outer loop + vertex 813.175 139.301 12.6527 + vertex 818.524 141.927 10.8467 + vertex 818.212 142.589 12.6374 + endloop + endfacet + facet normal 0.519564 -0.767905 0.374667 + outer loop + vertex 818.524 141.927 10.8467 + vertex 823.561 145.33 10.8359 + vertex 818.212 142.589 12.6374 + endloop + endfacet + facet normal 0.519803 -0.765884 0.378453 + outer loop + vertex 818.212 142.589 12.6374 + vertex 823.561 145.33 10.8359 + vertex 823.235 145.989 12.618 + endloop + endfacet + facet normal 0.461996 -0.68801 -0.559645 + outer loop + vertex 818.357 143.669 5.40264 + vertex 823.401 147.058 5.40104 + vertex 818.665 142.502 7.09194 + endloop + endfacet + facet normal 0.461431 -0.687725 -0.560461 + outer loop + vertex 818.665 142.502 7.09194 + vertex 823.401 147.058 5.40104 + vertex 823.714 145.893 7.08822 + endloop + endfacet + facet normal 0.453233 -0.693706 -0.559778 + outer loop + vertex 813.296 140.364 5.40057 + vertex 818.357 143.669 5.40264 + vertex 813.6 139.196 7.09454 + endloop + endfacet + facet normal 0.452122 -0.693133 -0.561385 + outer loop + vertex 813.6 139.196 7.09454 + vertex 818.357 143.669 5.40264 + vertex 818.665 142.502 7.09194 + endloop + endfacet + facet normal 0.526 -0.80609 -0.271187 + outer loop + vertex 813.6 139.196 7.09454 + vertex 818.665 142.502 7.09194 + vertex 813.629 138.588 8.95867 + endloop + endfacet + facet normal 0.526689 -0.806192 -0.269541 + outer loop + vertex 813.629 138.588 8.95867 + vertex 818.665 142.502 7.09194 + vertex 818.689 141.895 8.95369 + endloop + endfacet + facet normal 0.53703 -0.799977 -0.267648 + outer loop + vertex 818.665 142.502 7.09194 + vertex 823.714 145.893 7.08822 + vertex 818.689 141.895 8.95369 + endloop + endfacet + facet normal 0.538243 -0.800136 -0.26472 + outer loop + vertex 818.689 141.895 8.95369 + vertex 823.714 145.893 7.08822 + vertex 823.735 145.292 8.94779 + endloop + endfacet + facet normal 0.238241 -0.374732 -0.896001 + outer loop + vertex 816.758 147.293 2.87697 + vertex 821.54 149.99 3.02065 + vertex 817.681 145.21 3.99368 + endloop + endfacet + facet normal 0.263047 -0.391832 -0.881631 + outer loop + vertex 817.681 145.21 3.99368 + vertex 821.54 149.99 3.02065 + vertex 822.709 148.582 3.9953 + endloop + endfacet + facet normal 0.260885 -0.385548 -0.885038 + outer loop + vertex 811.489 143.399 3.02024 + vertex 816.758 147.293 2.87697 + vertex 812.622 141.93 3.99435 + endloop + endfacet + facet normal 0.241768 -0.373041 -0.895761 + outer loop + vertex 812.622 141.93 3.99435 + vertex 816.758 147.293 2.87697 + vertex 817.681 145.21 3.99368 + endloop + endfacet + facet normal 0.349157 -0.53863 -0.76679 + outer loop + vertex 812.622 141.93 3.99435 + vertex 817.681 145.21 3.99368 + vertex 813.296 140.364 5.40057 + endloop + endfacet + facet normal 0.354125 -0.54181 -0.762258 + outer loop + vertex 813.296 140.364 5.40057 + vertex 817.681 145.21 3.99368 + vertex 818.357 143.669 5.40264 + endloop + endfacet + facet normal 0.361114 -0.53813 -0.761586 + outer loop + vertex 817.681 145.21 3.99368 + vertex 822.709 148.582 3.9953 + vertex 818.357 143.669 5.40264 + endloop + endfacet + facet normal 0.361347 -0.538275 -0.761373 + outer loop + vertex 818.357 143.669 5.40264 + vertex 822.709 148.582 3.9953 + vertex 823.401 147.058 5.40104 + endloop + endfacet + facet normal 0.165908 -0.243283 -0.955661 + outer loop + vertex 821.54 149.99 3.02065 + vertex 816.758 147.293 2.87697 + vertex 823.31 155.14 2.01681 + endloop + endfacet + facet normal 0.155637 -0.24578 -0.956749 + outer loop + vertex 811.489 143.399 3.02024 + vertex 813.416 148.517 2.01883 + vertex 816.758 147.293 2.87697 + endloop + endfacet + facet normal 0.158954 -0.237759 -0.95823 + outer loop + vertex 813.416 148.517 2.01883 + vertex 823.31 155.14 2.01681 + vertex 816.758 147.293 2.87697 + endloop + endfacet + facet normal 0.110567 -0.165463 -0.979998 + outer loop + vertex 811.194 152.347 1.12155 + vertex 820.998 158.883 1.12408 + vertex 813.416 148.517 2.01883 + endloop + endfacet + facet normal 0.110547 -0.165448 -0.980003 + outer loop + vertex 813.416 148.517 2.01883 + vertex 820.998 158.883 1.12408 + vertex 823.31 155.14 2.01681 + endloop + endfacet + facet normal 0.258452 -0.283989 0.923338 + outer loop + vertex 816.507 184.399 21.6266 + vertex 820.741 187.757 21.4745 + vertex 816.072 186.057 22.2586 + endloop + endfacet + facet normal 0.259378 -0.287095 0.922117 + outer loop + vertex 816.072 186.057 22.2586 + vertex 820.741 187.757 21.4745 + vertex 820.291 189.447 22.1271 + endloop + endfacet + facet normal 0.251545 -0.283746 0.925318 + outer loop + vertex 812.167 181.041 21.7769 + vertex 816.507 184.399 21.6266 + vertex 811.765 182.694 22.3931 + endloop + endfacet + facet normal 0.252226 -0.28604 0.924426 + outer loop + vertex 811.765 182.694 22.3931 + vertex 816.507 184.399 21.6266 + vertex 816.072 186.057 22.2586 + endloop + endfacet + facet normal 0.159576 -0.14965 0.975777 + outer loop + vertex 817.737 179.755 20.5398 + vertex 821.619 183.289 20.4468 + vertex 817.078 182.335 21.043 + endloop + endfacet + facet normal 0.161076 -0.157737 0.974255 + outer loop + vertex 817.078 182.335 21.043 + vertex 821.619 183.289 20.4468 + vertex 821.353 185.687 20.8791 + endloop + endfacet + facet normal 0.153065 -0.159894 0.975195 + outer loop + vertex 812.886 176.621 20.7874 + vertex 817.737 179.755 20.5398 + vertex 812.71 179.002 21.2052 + endloop + endfacet + facet normal 0.152037 -0.151745 0.976657 + outer loop + vertex 812.71 179.002 21.2052 + vertex 817.737 179.755 20.5398 + vertex 817.078 182.335 21.043 + endloop + endfacet + facet normal 0.199444 -0.214883 0.956058 + outer loop + vertex 812.71 179.002 21.2052 + vertex 817.078 182.335 21.043 + vertex 812.167 181.041 21.7769 + endloop + endfacet + facet normal 0.199488 -0.215083 0.956004 + outer loop + vertex 812.167 181.041 21.7769 + vertex 817.078 182.335 21.043 + vertex 816.507 184.399 21.6266 + endloop + endfacet + facet normal 0.204163 -0.213604 0.955348 + outer loop + vertex 817.078 182.335 21.043 + vertex 821.353 185.687 20.8791 + vertex 816.507 184.399 21.6266 + endloop + endfacet + facet normal 0.204321 -0.214311 0.955156 + outer loop + vertex 816.507 184.399 21.6266 + vertex 821.353 185.687 20.8791 + vertex 820.741 187.757 21.4745 + endloop + endfacet + facet normal 0.149584 -0.190456 0.970233 + outer loop + vertex 822.42 153.904 17.2429 + vertex 826.786 157.557 17.2866 + vertex 818.823 155.417 18.0944 + endloop + endfacet + facet normal 0.147626 -0.176031 0.973252 + outer loop + vertex 831.965 160.878 17.1019 + vertex 828.244 162.238 17.9123 + vertex 826.786 157.557 17.2866 + endloop + endfacet + facet normal 0.14592 -0.175546 0.973597 + outer loop + vertex 828.244 162.238 17.9123 + vertex 818.823 155.417 18.0944 + vertex 826.786 157.557 17.2866 + endloop + endfacet + facet normal 0.274115 -0.364089 0.890112 + outer loop + vertex 827.374 152.499 15.4525 + vertex 832.219 156.038 15.4078 + vertex 827.132 154.809 16.4718 + endloop + endfacet + facet normal 0.273041 -0.356809 0.893384 + outer loop + vertex 827.132 154.809 16.4718 + vertex 832.219 156.038 15.4078 + vertex 831.93 158.339 16.4149 + endloop + endfacet + facet normal 0.271195 -0.375923 0.886079 + outer loop + vertex 822.446 149.035 15.4909 + vertex 827.374 152.499 15.4525 + vertex 822.246 151.339 16.5299 + endloop + endfacet + facet normal 0.269769 -0.36497 0.891079 + outer loop + vertex 822.246 151.339 16.5299 + vertex 827.374 152.499 15.4525 + vertex 827.132 154.809 16.4718 + endloop + endfacet + facet normal 0.206489 -0.275057 0.938992 + outer loop + vertex 822.246 151.339 16.5299 + vertex 827.132 154.809 16.4718 + vertex 822.42 153.904 17.2429 + endloop + endfacet + facet normal 0.203625 -0.254765 0.945321 + outer loop + vertex 822.42 153.904 17.2429 + vertex 827.132 154.809 16.4718 + vertex 826.786 157.557 17.2866 + endloop + endfacet + facet normal 0.19918 -0.255543 0.946058 + outer loop + vertex 827.132 154.809 16.4718 + vertex 831.93 158.339 16.4149 + vertex 826.786 157.557 17.2866 + endloop + endfacet + facet normal 0.199476 -0.258435 0.945209 + outer loop + vertex 826.786 157.557 17.2866 + vertex 831.93 158.339 16.4149 + vertex 831.965 160.878 17.1019 + endloop + endfacet + facet normal 0.456082 -0.629068 0.629493 + outer loop + vertex 828.21 149.47 12.598 + vertex 833.102 153 12.5816 + vertex 827.772 150.712 14.1559 + endloop + endfacet + facet normal 0.455264 -0.62186 0.637201 + outer loop + vertex 827.772 150.712 14.1559 + vertex 833.102 153 12.5816 + vertex 832.644 154.248 14.1261 + endloop + endfacet + facet normal 0.448878 -0.63784 0.625834 + outer loop + vertex 823.235 145.989 12.618 + vertex 828.21 149.47 12.598 + vertex 822.817 147.234 14.1864 + endloop + endfacet + facet normal 0.448441 -0.633312 0.630726 + outer loop + vertex 822.817 147.234 14.1864 + vertex 828.21 149.47 12.598 + vertex 827.772 150.712 14.1559 + endloop + endfacet + facet normal 0.355244 -0.499142 0.790354 + outer loop + vertex 822.817 147.234 14.1864 + vertex 827.772 150.712 14.1559 + vertex 822.446 149.035 15.4909 + endloop + endfacet + facet normal 0.354778 -0.495841 0.792638 + outer loop + vertex 822.446 149.035 15.4909 + vertex 827.772 150.712 14.1559 + vertex 827.374 152.499 15.4525 + endloop + endfacet + facet normal 0.362585 -0.492877 0.790952 + outer loop + vertex 827.772 150.712 14.1559 + vertex 832.644 154.248 14.1261 + vertex 827.374 152.499 15.4525 + endloop + endfacet + facet normal 0.361276 -0.484623 0.79663 + outer loop + vertex 827.374 152.499 15.4525 + vertex 832.644 154.248 14.1261 + vertex 832.219 156.038 15.4078 + endloop + endfacet + facet normal 0.583563 -0.809062 0.0698053 + outer loop + vertex 828.729 148.775 8.94186 + vertex 833.629 152.309 8.93676 + vertex 828.552 148.81 10.8245 + endloop + endfacet + facet normal 0.583888 -0.808691 0.071365 + outer loop + vertex 828.552 148.81 10.8245 + vertex 833.629 152.309 8.93676 + vertex 833.453 152.347 10.8136 + endloop + endfacet + facet normal 0.57079 -0.818198 0.0689321 + outer loop + vertex 823.735 145.292 8.94779 + vertex 828.729 148.775 8.94186 + vertex 823.561 145.33 10.8359 + endloop + endfacet + facet normal 0.570756 -0.818235 0.0687718 + outer loop + vertex 823.561 145.33 10.8359 + vertex 828.729 148.775 8.94186 + vertex 828.552 148.81 10.8245 + endloop + endfacet + facet normal 0.530188 -0.759044 0.377826 + outer loop + vertex 823.561 145.33 10.8359 + vertex 828.552 148.81 10.8245 + vertex 823.235 145.989 12.618 + endloop + endfacet + facet normal 0.530493 -0.755858 0.383741 + outer loop + vertex 823.235 145.989 12.618 + vertex 828.552 148.81 10.8245 + vertex 828.21 149.47 12.598 + endloop + endfacet + facet normal 0.541188 -0.748572 0.383086 + outer loop + vertex 828.552 148.81 10.8245 + vertex 833.453 152.347 10.8136 + vertex 828.21 149.47 12.598 + endloop + endfacet + facet normal 0.541218 -0.748185 0.3838 + outer loop + vertex 828.21 149.47 12.598 + vertex 833.453 152.347 10.8136 + vertex 833.102 153 12.5816 + endloop + endfacet + facet normal 0.485812 -0.677261 -0.552544 + outer loop + vertex 828.383 150.516 5.4005 + vertex 833.263 154.017 5.39969 + vertex 828.703 149.37 7.08673 + endloop + endfacet + facet normal 0.48888 -0.678659 -0.548104 + outer loop + vertex 828.703 149.37 7.08673 + vertex 833.263 154.017 5.39969 + vertex 833.592 152.892 7.08626 + endloop + endfacet + facet normal 0.473015 -0.681545 -0.558349 + outer loop + vertex 823.401 147.058 5.40104 + vertex 828.383 150.516 5.4005 + vertex 823.714 145.893 7.08822 + endloop + endfacet + facet normal 0.475727 -0.682854 -0.554431 + outer loop + vertex 823.714 145.893 7.08822 + vertex 828.383 150.516 5.4005 + vertex 828.703 149.37 7.08673 + endloop + endfacet + facet normal 0.551712 -0.791759 -0.262166 + outer loop + vertex 823.714 145.893 7.08822 + vertex 828.703 149.37 7.08673 + vertex 823.735 145.292 8.94779 + endloop + endfacet + facet normal 0.551976 -0.791788 -0.261525 + outer loop + vertex 823.735 145.292 8.94779 + vertex 828.703 149.37 7.08673 + vertex 828.729 148.775 8.94186 + endloop + endfacet + facet normal 0.564562 -0.783671 -0.259094 + outer loop + vertex 828.703 149.37 7.08673 + vertex 833.592 152.892 7.08626 + vertex 828.729 148.775 8.94186 + endloop + endfacet + facet normal 0.564932 -0.783702 -0.258192 + outer loop + vertex 828.729 148.775 8.94186 + vertex 833.592 152.892 7.08626 + vertex 833.629 152.309 8.93676 + endloop + endfacet + facet normal 0.250541 -0.370992 -0.8942 + outer loop + vertex 826.7 154.051 2.88003 + vertex 831.369 156.878 3.01553 + vertex 827.68 152.022 3.99661 + endloop + endfacet + facet normal 0.278866 -0.389219 -0.877919 + outer loop + vertex 827.68 152.022 3.99661 + vertex 831.369 156.878 3.01553 + vertex 832.548 155.511 3.9962 + endloop + endfacet + facet normal 0.276145 -0.381362 -0.882217 + outer loop + vertex 821.54 149.99 3.02065 + vertex 826.7 154.051 2.88003 + vertex 822.709 148.582 3.9953 + endloop + endfacet + facet normal 0.255286 -0.368522 -0.89388 + outer loop + vertex 822.709 148.582 3.9953 + vertex 826.7 154.051 2.88003 + vertex 827.68 152.022 3.99661 + endloop + endfacet + facet normal 0.369621 -0.533776 -0.760568 + outer loop + vertex 822.709 148.582 3.9953 + vertex 827.68 152.022 3.99661 + vertex 823.401 147.058 5.40104 + endloop + endfacet + facet normal 0.371003 -0.534611 -0.759308 + outer loop + vertex 823.401 147.058 5.40104 + vertex 827.68 152.022 3.99661 + vertex 828.383 150.516 5.4005 + endloop + endfacet + facet normal 0.379613 -0.529781 -0.758437 + outer loop + vertex 827.68 152.022 3.99661 + vertex 832.548 155.511 3.9962 + vertex 828.383 150.516 5.4005 + endloop + endfacet + facet normal 0.380219 -0.530132 -0.757887 + outer loop + vertex 828.383 150.516 5.4005 + vertex 832.548 155.511 3.9962 + vertex 833.263 154.017 5.39969 + endloop + endfacet + facet normal 0.170174 -0.235229 -0.956926 + outer loop + vertex 831.369 156.878 3.01553 + vertex 826.7 154.051 2.88003 + vertex 832.94 162.08 2.01628 + endloop + endfacet + facet normal 0.165311 -0.243107 -0.955809 + outer loop + vertex 821.54 149.99 3.02065 + vertex 823.31 155.14 2.01681 + vertex 826.7 154.051 2.88003 + endloop + endfacet + facet normal 0.168632 -0.23409 -0.957479 + outer loop + vertex 823.31 155.14 2.01681 + vertex 832.94 162.08 2.01628 + vertex 826.7 154.051 2.88003 + endloop + endfacet + facet normal 0.116453 -0.161783 -0.979931 + outer loop + vertex 820.998 158.883 1.12408 + vertex 830.559 165.771 1.12316 + vertex 823.31 155.14 2.01681 + endloop + endfacet + facet normal 0.116593 -0.161876 -0.979899 + outer loop + vertex 823.31 155.14 2.01681 + vertex 830.559 165.771 1.12316 + vertex 832.94 162.08 2.01628 + endloop + endfacet + facet normal 0.270104 -0.285535 0.919518 + outer loop + vertex 824.826 191.089 21.3266 + vertex 828.775 194.391 21.1922 + vertex 824.375 192.829 21.9996 + endloop + endfacet + facet normal 0.269664 -0.283982 0.920128 + outer loop + vertex 824.375 192.829 21.9996 + vertex 828.775 194.391 21.1922 + vertex 828.318 196.175 21.8767 + endloop + endfacet + facet normal 0.26574 -0.284959 0.920967 + outer loop + vertex 820.741 187.757 21.4745 + vertex 824.826 191.089 21.3266 + vertex 820.291 189.447 22.1271 + endloop + endfacet + facet normal 0.266279 -0.286805 0.920238 + outer loop + vertex 820.291 189.447 22.1271 + vertex 824.826 191.089 21.3266 + vertex 824.375 192.829 21.9996 + endloop + endfacet + facet normal 0.162321 -0.145491 0.975953 + outer loop + vertex 826.289 186.465 20.2038 + vertex 829.943 189.99 20.1213 + vertex 825.497 189.022 20.7165 + endloop + endfacet + facet normal 0.164236 -0.155434 0.974098 + outer loop + vertex 825.497 189.022 20.7165 + vertex 829.943 189.99 20.1213 + vertex 829.509 192.333 20.5685 + endloop + endfacet + facet normal 0.158282 -0.15812 0.974651 + outer loop + vertex 821.619 183.289 20.4468 + vertex 826.289 186.465 20.2038 + vertex 821.353 185.687 20.8791 + endloop + endfacet + facet normal 0.15684 -0.147314 0.976576 + outer loop + vertex 821.353 185.687 20.8791 + vertex 826.289 186.465 20.2038 + vertex 825.497 189.022 20.7165 + endloop + endfacet + facet normal 0.208706 -0.212837 0.954538 + outer loop + vertex 821.353 185.687 20.8791 + vertex 825.497 189.022 20.7165 + vertex 820.741 187.757 21.4745 + endloop + endfacet + facet normal 0.208923 -0.213814 0.954272 + outer loop + vertex 820.741 187.757 21.4745 + vertex 825.497 189.022 20.7165 + vertex 824.826 191.089 21.3266 + endloop + endfacet + facet normal 0.211038 -0.213041 0.953979 + outer loop + vertex 825.497 189.022 20.7165 + vertex 829.509 192.333 20.5685 + vertex 824.826 191.089 21.3266 + endloop + endfacet + facet normal 0.21118 -0.213681 0.953805 + outer loop + vertex 824.826 191.089 21.3266 + vertex 829.509 192.333 20.5685 + vertex 828.775 194.391 21.1922 + endloop + endfacet + facet normal 0.147319 -0.176815 0.973157 + outer loop + vertex 831.965 160.878 17.1019 + vertex 836.069 164.567 17.1509 + vertex 828.244 162.238 17.9123 + endloop + endfacet + facet normal 0.143016 -0.164073 0.976026 + outer loop + vertex 840.946 167.899 16.9963 + vertex 837.247 169.177 17.7532 + vertex 836.069 164.567 17.1509 + endloop + endfacet + facet normal 0.143847 -0.164265 0.975872 + outer loop + vertex 837.247 169.177 17.7532 + vertex 828.244 162.238 17.9123 + vertex 836.069 164.567 17.1509 + endloop + endfacet + facet normal 0.275789 -0.348737 0.895725 + outer loop + vertex 836.937 159.602 15.3697 + vertex 841.493 163.149 15.3479 + vertex 836.589 161.884 16.3655 + endloop + endfacet + facet normal 0.274009 -0.338135 0.900324 + outer loop + vertex 836.589 161.884 16.3655 + vertex 841.493 163.149 15.3479 + vertex 841.073 165.419 16.3283 + endloop + endfacet + facet normal 0.276232 -0.356102 0.892685 + outer loop + vertex 832.219 156.038 15.4078 + vertex 836.937 159.602 15.3697 + vertex 831.93 158.339 16.4149 + endloop + endfacet + facet normal 0.275083 -0.34891 0.895875 + outer loop + vertex 831.93 158.339 16.4149 + vertex 836.937 159.602 15.3697 + vertex 836.589 161.884 16.3655 + endloop + endfacet + facet normal 0.206504 -0.258143 0.943779 + outer loop + vertex 831.93 158.339 16.4149 + vertex 836.589 161.884 16.3655 + vertex 831.965 160.878 17.1019 + endloop + endfacet + facet normal 0.203191 -0.238658 0.949608 + outer loop + vertex 831.965 160.878 17.1019 + vertex 836.589 161.884 16.3655 + vertex 836.069 164.567 17.1509 + endloop + endfacet + facet normal 0.197142 -0.240096 0.95052 + outer loop + vertex 836.589 161.884 16.3655 + vertex 841.073 165.419 16.3283 + vertex 836.069 164.567 17.1509 + endloop + endfacet + facet normal 0.197819 -0.24556 0.948983 + outer loop + vertex 836.069 164.567 17.1509 + vertex 841.073 165.419 16.3283 + vertex 840.946 167.899 16.9963 + endloop + endfacet + facet normal 0.472075 -0.608662 0.637712 + outer loop + vertex 837.868 156.565 12.5654 + vertex 842.483 160.133 12.5551 + vertex 837.394 157.808 14.1026 + endloop + endfacet + facet normal 0.47177 -0.60644 0.640049 + outer loop + vertex 837.394 157.808 14.1026 + vertex 842.483 160.133 12.5551 + vertex 841.992 161.369 14.0871 + endloop + endfacet + facet normal 0.463672 -0.617051 0.635811 + outer loop + vertex 833.102 153 12.5816 + vertex 837.868 156.565 12.5654 + vertex 832.644 154.248 14.1261 + endloop + endfacet + facet normal 0.463264 -0.613857 0.639192 + outer loop + vertex 832.644 154.248 14.1261 + vertex 837.868 156.565 12.5654 + vertex 837.394 157.808 14.1026 + endloop + endfacet + facet normal 0.365829 -0.482834 0.795639 + outer loop + vertex 832.644 154.248 14.1261 + vertex 837.394 157.808 14.1026 + vertex 832.219 156.038 15.4078 + endloop + endfacet + facet normal 0.364242 -0.47357 0.80191 + outer loop + vertex 832.219 156.038 15.4078 + vertex 837.394 157.808 14.1026 + vertex 836.937 159.602 15.3697 + endloop + endfacet + facet normal 0.368179 -0.471966 0.801057 + outer loop + vertex 837.394 157.808 14.1026 + vertex 841.992 161.369 14.0871 + vertex 836.937 159.602 15.3697 + endloop + endfacet + facet normal 0.367241 -0.466758 0.804532 + outer loop + vertex 836.937 159.602 15.3697 + vertex 841.992 161.369 14.0871 + vertex 841.493 163.149 15.3479 + endloop + endfacet + facet normal 0.607574 -0.78979 0.0841733 + outer loop + vertex 838.41 155.846 8.93152 + vertex 843.027 159.398 8.93169 + vertex 838.229 155.906 10.8048 + endloop + endfacet + facet normal 0.607443 -0.789961 0.0835163 + outer loop + vertex 838.229 155.906 10.8048 + vertex 843.027 159.398 8.93169 + vertex 842.853 159.461 10.8024 + endloop + endfacet + facet normal 0.59322 -0.801806 0.0720984 + outer loop + vertex 833.629 152.309 8.93676 + vertex 838.41 155.846 8.93152 + vertex 833.453 152.347 10.8136 + endloop + endfacet + facet normal 0.595507 -0.79902 0.0833009 + outer loop + vertex 833.453 152.347 10.8136 + vertex 838.41 155.846 8.93152 + vertex 838.229 155.906 10.8048 + endloop + endfacet + facet normal 0.552348 -0.74036 0.383116 + outer loop + vertex 833.453 152.347 10.8136 + vertex 838.229 155.906 10.8048 + vertex 833.102 153 12.5816 + endloop + endfacet + facet normal 0.552563 -0.737018 0.389203 + outer loop + vertex 833.102 153 12.5816 + vertex 838.229 155.906 10.8048 + vertex 837.868 156.565 12.5654 + endloop + endfacet + facet normal 0.561767 -0.730353 0.38859 + outer loop + vertex 838.229 155.906 10.8048 + vertex 842.853 159.461 10.8024 + vertex 837.868 156.565 12.5654 + endloop + endfacet + facet normal 0.562 -0.725649 0.396976 + outer loop + vertex 837.868 156.565 12.5654 + vertex 842.853 159.461 10.8024 + vertex 842.483 160.133 12.5551 + endloop + endfacet + facet normal 0.506971 -0.662913 -0.550932 + outer loop + vertex 838 157.544 5.40253 + vertex 842.602 161.068 5.39689 + vertex 838.357 156.422 7.08195 + endloop + endfacet + facet normal 0.510656 -0.66439 -0.545726 + outer loop + vertex 838.357 156.422 7.08195 + vertex 842.602 161.068 5.39689 + vertex 842.962 159.96 7.08347 + endloop + endfacet + facet normal 0.500644 -0.671857 -0.545861 + outer loop + vertex 833.263 154.017 5.39969 + vertex 838 157.544 5.40253 + vertex 833.592 152.892 7.08626 + endloop + endfacet + facet normal 0.49562 -0.669698 -0.553051 + outer loop + vertex 833.592 152.892 7.08626 + vertex 838 157.544 5.40253 + vertex 838.357 156.422 7.08195 + endloop + endfacet + facet normal 0.575242 -0.776817 -0.256226 + outer loop + vertex 833.592 152.892 7.08626 + vertex 838.357 156.422 7.08195 + vertex 833.629 152.309 8.93676 + endloop + endfacet + facet normal 0.574331 -0.776762 -0.258426 + outer loop + vertex 833.629 152.309 8.93676 + vertex 838.357 156.422 7.08195 + vertex 838.41 155.846 8.93152 + endloop + endfacet + facet normal 0.589069 -0.76657 -0.255673 + outer loop + vertex 838.357 156.422 7.08195 + vertex 842.962 159.96 7.08347 + vertex 838.41 155.846 8.93152 + endloop + endfacet + facet normal 0.589739 -0.766589 -0.254066 + outer loop + vertex 838.41 155.846 8.93152 + vertex 842.962 159.96 7.08347 + vertex 843.027 159.398 8.93169 + endloop + endfacet + facet normal 0.268001 -0.363446 -0.892235 + outer loop + vertex 836.294 161.051 2.87391 + vertex 840.724 163.959 3.02044 + vertex 837.285 159.027 3.9962 + endloop + endfacet + facet normal 0.287503 -0.374895 -0.88136 + outer loop + vertex 837.285 159.027 3.9962 + vertex 840.724 163.959 3.02044 + vertex 841.883 162.566 3.99081 + endloop + endfacet + facet normal 0.293932 -0.376638 -0.878492 + outer loop + vertex 831.369 156.878 3.01553 + vertex 836.294 161.051 2.87391 + vertex 832.548 155.511 3.9962 + endloop + endfacet + facet normal 0.269302 -0.362749 -0.892126 + outer loop + vertex 832.548 155.511 3.9962 + vertex 836.294 161.051 2.87391 + vertex 837.285 159.027 3.9962 + endloop + endfacet + facet normal 0.389558 -0.524734 -0.756901 + outer loop + vertex 832.548 155.511 3.9962 + vertex 837.285 159.027 3.9962 + vertex 833.263 154.017 5.39969 + endloop + endfacet + facet normal 0.392357 -0.526275 -0.754381 + outer loop + vertex 833.263 154.017 5.39969 + vertex 837.285 159.027 3.9962 + vertex 838 157.544 5.40253 + endloop + endfacet + facet normal 0.40047 -0.521479 -0.753448 + outer loop + vertex 837.285 159.027 3.9962 + vertex 841.883 162.566 3.99081 + vertex 838 157.544 5.40253 + endloop + endfacet + facet normal 0.397035 -0.519681 -0.756501 + outer loop + vertex 838 157.544 5.40253 + vertex 841.883 162.566 3.99081 + vertex 842.602 161.068 5.39689 + endloop + endfacet + facet normal 0.184587 -0.233176 -0.954755 + outer loop + vertex 840.724 163.959 3.02044 + vertex 836.294 161.051 2.87391 + vertex 842.187 169.263 2.00789 + endloop + endfacet + facet normal 0.172313 -0.235776 -0.956409 + outer loop + vertex 831.369 156.878 3.01553 + vertex 832.94 162.08 2.01628 + vertex 836.294 161.051 2.87391 + endloop + endfacet + facet normal 0.175424 -0.22694 -0.957979 + outer loop + vertex 832.94 162.08 2.01628 + vertex 842.187 169.263 2.00789 + vertex 836.294 161.051 2.87391 + endloop + endfacet + facet normal 0.122272 -0.15819 -0.979809 + outer loop + vertex 830.559 165.771 1.12316 + vertex 839.806 172.969 1.11506 + vertex 832.94 162.08 2.01628 + endloop + endfacet + facet normal 0.121747 -0.157869 -0.979926 + outer loop + vertex 832.94 162.08 2.01628 + vertex 839.806 172.969 1.11506 + vertex 842.187 169.263 2.00789 + endloop + endfacet + facet normal 0.271678 -0.278837 0.921108 + outer loop + vertex 832.61 197.68 21.0732 + vertex 836.367 200.98 20.964 + vertex 832.112 199.458 21.7581 + endloop + endfacet + facet normal 0.270146 -0.273483 0.923162 + outer loop + vertex 832.112 199.458 21.7581 + vertex 836.367 200.98 20.964 + vertex 835.742 202.634 21.6367 + endloop + endfacet + facet normal 0.271534 -0.283365 0.919768 + outer loop + vertex 828.775 194.391 21.1922 + vertex 832.61 197.68 21.0732 + vertex 828.318 196.175 21.8767 + endloop + endfacet + facet normal 0.2704 -0.279287 0.921348 + outer loop + vertex 828.318 196.175 21.8767 + vertex 832.61 197.68 21.0732 + vertex 832.112 199.458 21.7581 + endloop + endfacet + facet normal 0.162613 -0.145738 0.975867 + outer loop + vertex 834.414 193.194 19.9049 + vertex 837.872 196.736 19.8575 + vertex 833.417 195.639 20.4361 + endloop + endfacet + facet normal 0.165006 -0.156551 0.973789 + outer loop + vertex 833.417 195.639 20.4361 + vertex 837.872 196.736 19.8575 + vertex 837.273 198.994 20.3221 + endloop + endfacet + facet normal 0.159363 -0.156461 0.974743 + outer loop + vertex 829.943 189.99 20.1213 + vertex 834.414 193.194 19.9049 + vertex 829.509 192.333 20.5685 + endloop + endfacet + facet normal 0.158038 -0.147704 0.976323 + outer loop + vertex 829.509 192.333 20.5685 + vertex 834.414 193.194 19.9049 + vertex 833.417 195.639 20.4361 + endloop + endfacet + facet normal 0.212605 -0.213115 0.953615 + outer loop + vertex 829.509 192.333 20.5685 + vertex 833.417 195.639 20.4361 + vertex 828.775 194.391 21.1922 + endloop + endfacet + facet normal 0.212701 -0.213541 0.953498 + outer loop + vertex 828.775 194.391 21.1922 + vertex 833.417 195.639 20.4361 + vertex 832.61 197.68 21.0732 + endloop + endfacet + facet normal 0.213638 -0.213134 0.95338 + outer loop + vertex 833.417 195.639 20.4361 + vertex 837.273 198.994 20.3221 + vertex 832.61 197.68 21.0732 + endloop + endfacet + facet normal 0.213161 -0.211125 0.953933 + outer loop + vertex 832.61 197.68 21.0732 + vertex 837.273 198.994 20.3221 + vertex 836.367 200.98 20.964 + endloop + endfacet + facet normal 0.142765 -0.164752 0.975948 + outer loop + vertex 840.946 167.899 16.9963 + vertex 844.769 171.56 17.0552 + vertex 837.247 169.177 17.7532 + endloop + endfacet + facet normal 0.139682 -0.149685 0.978817 + outer loop + vertex 849.466 174.928 16.8999 + vertex 845.933 176.252 17.6065 + vertex 844.769 171.56 17.0552 + endloop + endfacet + facet normal 0.138174 -0.149342 0.979084 + outer loop + vertex 845.933 176.252 17.6065 + vertex 837.247 169.177 17.7532 + vertex 844.769 171.56 17.0552 + endloop + endfacet + facet normal 0.279162 -0.330098 0.901722 + outer loop + vertex 845.872 166.678 15.3288 + vertex 850.129 170.204 15.3014 + vertex 845.383 168.918 16.3002 + endloop + endfacet + facet normal 0.278265 -0.325185 0.903783 + outer loop + vertex 845.383 168.918 16.3002 + vertex 850.129 170.204 15.3014 + vertex 849.601 172.427 16.2637 + endloop + endfacet + facet normal 0.276017 -0.337587 0.899916 + outer loop + vertex 841.493 163.149 15.3479 + vertex 845.872 166.678 15.3288 + vertex 841.073 165.419 16.3283 + endloop + endfacet + facet normal 0.274937 -0.33138 0.90255 + outer loop + vertex 841.073 165.419 16.3283 + vertex 845.872 166.678 15.3288 + vertex 845.383 168.918 16.3002 + endloop + endfacet + facet normal 0.204966 -0.244838 0.947652 + outer loop + vertex 841.073 165.419 16.3283 + vertex 845.383 168.918 16.3002 + vertex 840.946 167.899 16.9963 + endloop + endfacet + facet normal 0.201413 -0.225615 0.953169 + outer loop + vertex 840.946 167.899 16.9963 + vertex 845.383 168.918 16.3002 + vertex 844.769 171.56 17.0552 + endloop + endfacet + facet normal 0.196916 -0.226845 0.953816 + outer loop + vertex 845.383 168.918 16.3002 + vertex 849.601 172.427 16.2637 + vertex 844.769 171.56 17.0552 + endloop + endfacet + facet normal 0.197563 -0.23162 0.952534 + outer loop + vertex 844.769 171.56 17.0552 + vertex 849.601 172.427 16.2637 + vertex 849.466 174.928 16.8999 + endloop + endfacet + facet normal 0.486279 -0.590689 0.64391 + outer loop + vertex 846.947 163.679 12.553 + vertex 851.303 167.25 12.539 + vertex 846.427 164.912 14.0773 + endloop + endfacet + facet normal 0.484954 -0.582243 0.652543 + outer loop + vertex 846.427 164.912 14.0773 + vertex 851.303 167.25 12.539 + vertex 850.743 168.479 14.0515 + endloop + endfacet + facet normal 0.478618 -0.602283 0.63889 + outer loop + vertex 842.483 160.133 12.5551 + vertex 846.947 163.679 12.553 + vertex 841.992 161.369 14.0871 + endloop + endfacet + facet normal 0.477724 -0.596075 0.645348 + outer loop + vertex 841.992 161.369 14.0871 + vertex 846.947 163.679 12.553 + vertex 846.427 164.912 14.0773 + endloop + endfacet + facet normal 0.372824 -0.464357 0.803353 + outer loop + vertex 841.992 161.369 14.0871 + vertex 846.427 164.912 14.0773 + vertex 841.493 163.149 15.3479 + endloop + endfacet + facet normal 0.371313 -0.45632 0.80864 + outer loop + vertex 841.493 163.149 15.3479 + vertex 846.427 164.912 14.0773 + vertex 845.872 166.678 15.3288 + endloop + endfacet + facet normal 0.37894 -0.452813 0.807072 + outer loop + vertex 846.427 164.912 14.0773 + vertex 850.743 168.479 14.0515 + vertex 845.872 166.678 15.3288 + endloop + endfacet + facet normal 0.378549 -0.450843 0.808357 + outer loop + vertex 845.872 166.678 15.3288 + vertex 850.743 168.479 14.0515 + vertex 850.129 170.204 15.3014 + endloop + endfacet + facet normal 0.632475 -0.770245 0.0818443 + outer loop + vertex 847.501 162.939 8.93614 + vertex 851.878 166.533 8.93653 + vertex 847.331 162.998 10.8069 + endloop + endfacet + facet normal 0.632543 -0.770152 0.0821844 + outer loop + vertex 847.331 162.998 10.8069 + vertex 851.878 166.533 8.93653 + vertex 851.699 166.585 10.7979 + endloop + endfacet + facet normal 0.61838 -0.781351 0.0842438 + outer loop + vertex 843.027 159.398 8.93169 + vertex 847.501 162.939 8.93614 + vertex 842.853 159.461 10.8024 + endloop + endfacet + facet normal 0.617697 -0.782246 0.0808758 + outer loop + vertex 842.853 159.461 10.8024 + vertex 847.501 162.939 8.93614 + vertex 847.331 162.998 10.8069 + endloop + endfacet + facet normal 0.568739 -0.720651 0.396482 + outer loop + vertex 842.853 159.461 10.8024 + vertex 847.331 162.998 10.8069 + vertex 842.483 160.133 12.5551 + endloop + endfacet + facet normal 0.568907 -0.716112 0.404386 + outer loop + vertex 842.483 160.133 12.5551 + vertex 847.331 162.998 10.8069 + vertex 846.947 163.679 12.553 + endloop + endfacet + facet normal 0.58115 -0.706757 0.403433 + outer loop + vertex 847.331 162.998 10.8069 + vertex 851.699 166.585 10.7979 + vertex 846.947 163.679 12.553 + endloop + endfacet + facet normal 0.581136 -0.707354 0.402407 + outer loop + vertex 846.947 163.679 12.553 + vertex 851.699 166.585 10.7979 + vertex 851.303 167.25 12.539 + endloop + endfacet + facet normal 0.535133 -0.644907 -0.545644 + outer loop + vertex 847.057 164.623 5.40084 + vertex 851.436 168.251 5.40735 + vertex 847.428 163.503 7.0876 + endloop + endfacet + facet normal 0.528027 -0.642381 -0.555459 + outer loop + vertex 847.428 163.503 7.0876 + vertex 851.436 168.251 5.40735 + vertex 851.81 167.103 7.09038 + endloop + endfacet + facet normal 0.523901 -0.656148 -0.543136 + outer loop + vertex 842.602 161.068 5.39689 + vertex 847.057 164.623 5.40084 + vertex 842.962 159.96 7.08347 + endloop + endfacet + facet normal 0.51989 -0.654655 -0.548764 + outer loop + vertex 842.962 159.96 7.08347 + vertex 847.057 164.623 5.40084 + vertex 847.428 163.503 7.0876 + endloop + endfacet + facet normal 0.601626 -0.758025 -0.251882 + outer loop + vertex 842.962 159.96 7.08347 + vertex 847.428 163.503 7.0876 + vertex 843.027 159.398 8.93169 + endloop + endfacet + facet normal 0.600251 -0.758021 -0.255154 + outer loop + vertex 843.027 159.398 8.93169 + vertex 847.428 163.503 7.0876 + vertex 847.501 162.939 8.93614 + endloop + endfacet + facet normal 0.614266 -0.7476 -0.25253 + outer loop + vertex 847.428 163.503 7.0876 + vertex 851.81 167.103 7.09038 + vertex 847.501 162.939 8.93614 + endloop + endfacet + facet normal 0.613917 -0.747606 -0.253359 + outer loop + vertex 847.501 162.939 8.93614 + vertex 851.81 167.103 7.09038 + vertex 851.878 166.533 8.93653 + endloop + endfacet + facet normal 0.280949 -0.353075 -0.892416 + outer loop + vertex 845.397 168.225 2.87074 + vertex 849.623 171.215 3.01788 + vertex 846.344 166.139 3.99368 + endloop + endfacet + facet normal 0.303273 -0.365143 -0.880168 + outer loop + vertex 846.344 166.139 3.99368 + vertex 849.623 171.215 3.01788 + vertex 850.733 169.785 3.9937 + endloop + endfacet + facet normal 0.302598 -0.362444 -0.881515 + outer loop + vertex 840.724 163.959 3.02044 + vertex 845.397 168.225 2.87074 + vertex 841.883 162.566 3.99081 + endloop + endfacet + facet normal 0.282673 -0.352187 -0.892222 + outer loop + vertex 841.883 162.566 3.99081 + vertex 845.397 168.225 2.87074 + vertex 846.344 166.139 3.99368 + endloop + endfacet + facet normal 0.410361 -0.511708 -0.754824 + outer loop + vertex 841.883 162.566 3.99081 + vertex 846.344 166.139 3.99368 + vertex 842.602 161.068 5.39689 + endloop + endfacet + facet normal 0.407894 -0.510485 -0.756986 + outer loop + vertex 842.602 161.068 5.39689 + vertex 846.344 166.139 3.99368 + vertex 847.057 164.623 5.40084 + endloop + endfacet + facet normal 0.418618 -0.504023 -0.75546 + outer loop + vertex 846.344 166.139 3.99368 + vertex 850.733 169.785 3.9937 + vertex 847.057 164.623 5.40084 + endloop + endfacet + facet normal 0.418785 -0.504102 -0.755315 + outer loop + vertex 847.057 164.623 5.40084 + vertex 850.733 169.785 3.9937 + vertex 851.436 168.251 5.40735 + endloop + endfacet + facet normal 0.19483 -0.228364 -0.953882 + outer loop + vertex 849.623 171.215 3.01788 + vertex 845.397 168.225 2.87074 + vertex 851.02 176.604 2.01302 + endloop + endfacet + facet normal 0.181614 -0.232496 -0.95549 + outer loop + vertex 840.724 163.959 3.02044 + vertex 842.187 169.263 2.00789 + vertex 845.397 168.225 2.87074 + endloop + endfacet + facet normal 0.185352 -0.222343 -0.957188 + outer loop + vertex 842.187 169.263 2.00789 + vertex 851.02 176.604 2.01302 + vertex 845.397 168.225 2.87074 + endloop + endfacet + facet normal 0.127884 -0.153891 -0.979777 + outer loop + vertex 839.806 172.969 1.11506 + vertex 848.637 180.287 1.11817 + vertex 842.187 169.263 2.00789 + endloop + endfacet + facet normal 0.128998 -0.154523 -0.979532 + outer loop + vertex 842.187 169.263 2.00789 + vertex 848.637 180.287 1.11817 + vertex 851.02 176.604 2.01302 + endloop + endfacet + facet normal 0.271251 -0.272042 0.923264 + outer loop + vertex 840.13 204.345 20.8665 + vertex 843.968 207.887 20.7826 + vertex 839.274 205.834 21.5566 + endloop + endfacet + facet normal 0.273605 -0.278402 0.920669 + outer loop + vertex 839.274 205.834 21.5566 + vertex 843.968 207.887 20.7826 + vertex 843.032 209.349 21.5027 + endloop + endfacet + facet normal 0.268959 -0.274008 0.923353 + outer loop + vertex 836.367 200.98 20.964 + vertex 840.13 204.345 20.8665 + vertex 835.742 202.634 21.6367 + endloop + endfacet + facet normal 0.268816 -0.273564 0.923526 + outer loop + vertex 835.742 202.634 21.6367 + vertex 840.13 204.345 20.8665 + vertex 839.274 205.834 21.5566 + endloop + endfacet + facet normal 0.166256 -0.147852 0.974935 + outer loop + vertex 842.228 200.104 19.6749 + vertex 845.609 203.807 19.6599 + vertex 841.133 202.445 20.2166 + endloop + endfacet + facet normal 0.169438 -0.15927 0.972586 + outer loop + vertex 841.133 202.445 20.2166 + vertex 845.609 203.807 19.6599 + vertex 845.012 206.029 20.1277 + endloop + endfacet + facet normal 0.162456 -0.157291 0.974098 + outer loop + vertex 837.872 196.736 19.8575 + vertex 842.228 200.104 19.6749 + vertex 837.273 198.994 20.3221 + endloop + endfacet + facet normal 0.161081 -0.150382 0.975417 + outer loop + vertex 837.273 198.994 20.3221 + vertex 842.228 200.104 19.6749 + vertex 841.133 202.445 20.2166 + endloop + endfacet + facet normal 0.214294 -0.210566 0.953803 + outer loop + vertex 837.273 198.994 20.3221 + vertex 841.133 202.445 20.2166 + vertex 836.367 200.98 20.964 + endloop + endfacet + facet normal 0.214834 -0.212617 0.953226 + outer loop + vertex 836.367 200.98 20.964 + vertex 841.133 202.445 20.2166 + vertex 840.13 204.345 20.8665 + endloop + endfacet + facet normal 0.217099 -0.211342 0.952996 + outer loop + vertex 841.133 202.445 20.2166 + vertex 845.012 206.029 20.1277 + vertex 840.13 204.345 20.8665 + endloop + endfacet + facet normal 0.217693 -0.213317 0.952421 + outer loop + vertex 840.13 204.345 20.8665 + vertex 845.012 206.029 20.1277 + vertex 843.968 207.887 20.7826 + endloop + endfacet + facet normal 0.140414 -0.147826 0.978995 + outer loop + vertex 849.466 174.928 16.8999 + vertex 853.413 178.829 16.9229 + vertex 845.933 176.252 17.6065 + endloop + endfacet + facet normal 0.143324 -0.140343 0.979674 + outer loop + vertex 858.395 182.656 16.7421 + vertex 854.596 183.749 17.4546 + vertex 853.413 178.829 16.9229 + endloop + endfacet + facet normal 0.13755 -0.139065 0.980684 + outer loop + vertex 854.596 183.749 17.4546 + vertex 845.933 176.252 17.6065 + vertex 853.413 178.829 16.9229 + endloop + endfacet + facet normal 0.294368 -0.318398 0.901094 + outer loop + vertex 854.42 173.85 15.2388 + vertex 858.906 177.77 15.1585 + vertex 853.92 176.087 16.1927 + endloop + endfacet + facet normal 0.294744 -0.319918 0.900433 + outer loop + vertex 853.92 176.087 16.1927 + vertex 858.906 177.77 15.1585 + vertex 858.46 180.04 16.1111 + endloop + endfacet + facet normal 0.28705 -0.322351 0.902049 + outer loop + vertex 850.129 170.204 15.3014 + vertex 854.42 173.85 15.2388 + vertex 849.601 172.427 16.2637 + endloop + endfacet + facet normal 0.28673 -0.320792 0.902706 + outer loop + vertex 849.601 172.427 16.2637 + vertex 854.42 173.85 15.2388 + vertex 853.92 176.087 16.1927 + endloop + endfacet + facet normal 0.210779 -0.230267 0.950026 + outer loop + vertex 849.601 172.427 16.2637 + vertex 853.92 176.087 16.1927 + vertex 849.466 174.928 16.8999 + endloop + endfacet + facet normal 0.207637 -0.215693 0.95413 + outer loop + vertex 849.466 174.928 16.8999 + vertex 853.92 176.087 16.1927 + vertex 853.413 178.829 16.9229 + endloop + endfacet + facet normal 0.205408 -0.216203 0.954497 + outer loop + vertex 853.92 176.087 16.1927 + vertex 858.46 180.04 16.1111 + vertex 853.413 178.829 16.9229 + endloop + endfacet + facet normal 0.207058 -0.224628 0.952192 + outer loop + vertex 853.413 178.829 16.9229 + vertex 858.46 180.04 16.1111 + vertex 858.395 182.656 16.7421 + endloop + endfacet + facet normal 0.508396 -0.56807 0.647171 + outer loop + vertex 855.659 170.955 12.4903 + vertex 860.138 174.893 12.4285 + vertex 855.064 172.142 13.9999 + endloop + endfacet + facet normal 0.508202 -0.567176 0.648106 + outer loop + vertex 855.064 172.142 13.9999 + vertex 860.138 174.893 12.4285 + vertex 859.527 176.059 13.9282 + endloop + endfacet + facet normal 0.496214 -0.574808 0.650667 + outer loop + vertex 851.303 167.25 12.539 + vertex 855.659 170.955 12.4903 + vertex 850.743 168.479 14.0515 + endloop + endfacet + facet normal 0.4965 -0.576405 0.649034 + outer loop + vertex 850.743 168.479 14.0515 + vertex 855.659 170.955 12.4903 + vertex 855.064 172.142 13.9999 + endloop + endfacet + facet normal 0.387942 -0.446154 0.806503 + outer loop + vertex 850.743 168.479 14.0515 + vertex 855.064 172.142 13.9999 + vertex 850.129 170.204 15.3014 + endloop + endfacet + facet normal 0.38691 -0.441466 0.809573 + outer loop + vertex 850.129 170.204 15.3014 + vertex 855.064 172.142 13.9999 + vertex 854.42 173.85 15.2388 + endloop + endfacet + facet normal 0.396181 -0.436621 0.807714 + outer loop + vertex 855.064 172.142 13.9999 + vertex 859.527 176.059 13.9282 + vertex 854.42 173.85 15.2388 + endloop + endfacet + facet normal 0.396256 -0.436907 0.807523 + outer loop + vertex 854.42 173.85 15.2388 + vertex 859.527 176.059 13.9282 + vertex 858.906 177.77 15.1585 + endloop + endfacet + facet normal 0.662935 -0.744366 0.0802306 + outer loop + vertex 856.257 170.273 8.9083 + vertex 860.746 174.265 8.85408 + vertex 856.073 170.308 10.7587 + endloop + endfacet + facet normal 0.662423 -0.74512 0.0774054 + outer loop + vertex 856.073 170.308 10.7587 + vertex 860.746 174.265 8.85408 + vertex 860.563 174.294 10.7008 + endloop + endfacet + facet normal 0.647498 -0.757505 0.0832653 + outer loop + vertex 851.878 166.533 8.93653 + vertex 856.257 170.273 8.9083 + vertex 851.699 166.585 10.7979 + endloop + endfacet + facet normal 0.646645 -0.758702 0.0788737 + outer loop + vertex 851.699 166.585 10.7979 + vertex 856.257 170.273 8.9083 + vertex 856.073 170.308 10.7587 + endloop + endfacet + facet normal 0.595852 -0.695649 0.40129 + outer loop + vertex 851.699 166.585 10.7979 + vertex 856.073 170.308 10.7587 + vertex 851.303 167.25 12.539 + endloop + endfacet + facet normal 0.595853 -0.695209 0.402049 + outer loop + vertex 851.303 167.25 12.539 + vertex 856.073 170.308 10.7587 + vertex 855.659 170.955 12.4903 + endloop + endfacet + facet normal 0.611047 -0.682542 0.400945 + outer loop + vertex 856.073 170.308 10.7587 + vertex 860.563 174.294 10.7008 + vertex 855.659 170.955 12.4903 + endloop + endfacet + facet normal 0.611247 -0.689103 0.389249 + outer loop + vertex 855.659 170.955 12.4903 + vertex 860.563 174.294 10.7008 + vertex 860.138 174.893 12.4285 + endloop + endfacet + facet normal 0.555759 -0.620945 -0.552774 + outer loop + vertex 855.83 172.027 5.39545 + vertex 860.292 176.045 5.36882 + vertex 856.196 170.862 7.07322 + endloop + endfacet + facet normal 0.548403 -0.618441 -0.562836 + outer loop + vertex 856.196 170.862 7.07322 + vertex 860.292 176.045 5.36882 + vertex 860.673 174.872 7.02829 + endloop + endfacet + facet normal 0.542568 -0.632958 -0.552254 + outer loop + vertex 851.436 168.251 5.40735 + vertex 855.83 172.027 5.39545 + vertex 851.81 167.103 7.09038 + endloop + endfacet + facet normal 0.53929 -0.631827 -0.556741 + outer loop + vertex 851.81 167.103 7.09038 + vertex 855.83 172.027 5.39545 + vertex 856.196 170.862 7.07322 + endloop + endfacet + facet normal 0.629456 -0.735639 -0.25024 + outer loop + vertex 851.81 167.103 7.09038 + vertex 856.196 170.862 7.07322 + vertex 851.878 166.533 8.93653 + endloop + endfacet + facet normal 0.626702 -0.735724 -0.256817 + outer loop + vertex 851.878 166.533 8.93653 + vertex 856.196 170.862 7.07322 + vertex 856.257 170.273 8.9083 + endloop + endfacet + facet normal 0.644159 -0.721854 -0.252954 + outer loop + vertex 856.196 170.862 7.07322 + vertex 860.673 174.872 7.02829 + vertex 856.257 170.273 8.9083 + endloop + endfacet + facet normal 0.638849 -0.721981 -0.265735 + outer loop + vertex 856.257 170.273 8.9083 + vertex 860.673 174.872 7.02829 + vertex 860.746 174.265 8.85408 + endloop + endfacet + facet normal 0.291231 -0.344878 -0.892325 + outer loop + vertex 854.158 175.648 2.8785 + vertex 858.367 178.854 3.01273 + vertex 855.116 173.573 3.99313 + endloop + endfacet + facet normal 0.320509 -0.359905 -0.876209 + outer loop + vertex 855.116 173.573 3.99313 + vertex 858.367 178.854 3.01273 + vertex 859.543 177.544 3.98132 + endloop + endfacet + facet normal 0.318218 -0.353253 -0.879744 + outer loop + vertex 849.623 171.215 3.01788 + vertex 854.158 175.648 2.8785 + vertex 850.733 169.785 3.9937 + endloop + endfacet + facet normal 0.295819 -0.342451 -0.89175 + outer loop + vertex 850.733 169.785 3.9937 + vertex 854.158 175.648 2.8785 + vertex 855.116 173.573 3.99313 + endloop + endfacet + facet normal 0.429776 -0.497442 -0.753554 + outer loop + vertex 850.733 169.785 3.9937 + vertex 855.116 173.573 3.99313 + vertex 851.436 168.251 5.40735 + endloop + endfacet + facet normal 0.422727 -0.49419 -0.759657 + outer loop + vertex 851.436 168.251 5.40735 + vertex 855.116 173.573 3.99313 + vertex 855.83 172.027 5.39545 + endloop + endfacet + facet normal 0.43469 -0.486841 -0.757648 + outer loop + vertex 855.116 173.573 3.99313 + vertex 859.543 177.544 3.98132 + vertex 855.83 172.027 5.39545 + endloop + endfacet + facet normal 0.433172 -0.486155 -0.758957 + outer loop + vertex 855.83 172.027 5.39545 + vertex 859.543 177.544 3.98132 + vertex 860.292 176.045 5.36882 + endloop + endfacet + facet normal 0.202683 -0.226131 -0.952777 + outer loop + vertex 858.367 178.854 3.01273 + vertex 854.158 175.648 2.8785 + vertex 859.464 183.947 2.03727 + endloop + endfacet + facet normal 0.193618 -0.228107 -0.95419 + outer loop + vertex 849.623 171.215 3.01788 + vertex 851.02 176.604 2.01302 + vertex 854.158 175.648 2.8785 + endloop + endfacet + facet normal 0.19577 -0.221958 -0.955201 + outer loop + vertex 851.02 176.604 2.01302 + vertex 859.464 183.947 2.03727 + vertex 854.158 175.648 2.8785 + endloop + endfacet + facet normal 0.13296 -0.15193 -0.979407 + outer loop + vertex 848.637 180.287 1.11817 + vertex 856.905 187.362 1.14315 + vertex 851.02 176.604 2.01302 + endloop + endfacet + facet normal 0.136624 -0.153869 -0.9786 + outer loop + vertex 851.02 176.604 2.01302 + vertex 856.905 187.362 1.14315 + vertex 859.464 183.947 2.03727 + endloop + endfacet + facet normal 0.278071 -0.271022 0.921533 + outer loop + vertex 847.901 211.601 20.7135 + vertex 851.63 215.26 20.6644 + vertex 847.047 213.107 21.414 + endloop + endfacet + facet normal 0.274945 -0.263262 0.924715 + outer loop + vertex 847.047 213.107 21.414 + vertex 851.63 215.26 20.6644 + vertex 850.758 216.684 21.329 + endloop + endfacet + facet normal 0.276912 -0.276134 0.920364 + outer loop + vertex 843.968 207.887 20.7826 + vertex 847.901 211.601 20.7135 + vertex 843.032 209.349 21.5027 + endloop + endfacet + facet normal 0.275519 -0.272607 0.921832 + outer loop + vertex 843.032 209.349 21.5027 + vertex 847.901 211.601 20.7135 + vertex 847.047 213.107 21.414 + endloop + endfacet + facet normal 0.173028 -0.155867 0.972505 + outer loop + vertex 849.68 207.275 19.5275 + vertex 852.898 211.004 19.5525 + vertex 848.903 209.735 20.06 + endloop + endfacet + facet normal 0.176932 -0.169349 0.969544 + outer loop + vertex 848.903 209.735 20.06 + vertex 852.898 211.004 19.5525 + vertex 852.609 213.369 20.0183 + endloop + endfacet + facet normal 0.167756 -0.159767 0.972796 + outer loop + vertex 845.609 203.807 19.6599 + vertex 849.68 207.275 19.5275 + vertex 845.012 206.029 20.1277 + endloop + endfacet + facet normal 0.167289 -0.157827 0.973193 + outer loop + vertex 845.012 206.029 20.1277 + vertex 849.68 207.275 19.5275 + vertex 848.903 209.735 20.06 + endloop + endfacet + facet normal 0.219027 -0.212523 0.952293 + outer loop + vertex 845.012 206.029 20.1277 + vertex 848.903 209.735 20.06 + vertex 843.968 207.887 20.7826 + endloop + endfacet + facet normal 0.219909 -0.215191 0.95149 + outer loop + vertex 843.968 207.887 20.7826 + vertex 848.903 209.735 20.06 + vertex 847.901 211.601 20.7135 + endloop + endfacet + facet normal 0.221037 -0.214544 0.951374 + outer loop + vertex 848.903 209.735 20.06 + vertex 852.609 213.369 20.0183 + vertex 847.901 211.601 20.7135 + endloop + endfacet + facet normal 0.220006 -0.211431 0.95231 + outer loop + vertex 847.901 211.601 20.7135 + vertex 852.609 213.369 20.0183 + vertex 851.63 215.26 20.6644 + endloop + endfacet + facet normal 0.141649 -0.145804 0.97912 + outer loop + vertex 858.395 182.656 16.7421 + vertex 862.317 186.931 16.8115 + vertex 854.596 183.749 17.4546 + endloop + endfacet + facet normal 0.131476 -0.136488 0.981878 + outer loop + vertex 866.656 190.809 16.7695 + vertex 862.578 191.376 17.3943 + vertex 862.317 186.931 16.8115 + endloop + endfacet + facet normal 0.13807 -0.136752 0.980936 + outer loop + vertex 862.578 191.376 17.3943 + vertex 854.596 183.749 17.4546 + vertex 862.317 186.931 16.8115 + endloop + endfacet + facet normal 0.293969 -0.315435 0.902266 + outer loop + vertex 863.54 182.008 15.1283 + vertex 867.936 186.379 15.2241 + vertex 863.081 184.291 16.0759 + endloop + endfacet + facet normal 0.287976 -0.298352 0.909976 + outer loop + vertex 863.081 184.291 16.0759 + vertex 867.936 186.379 15.2241 + vertex 867.306 188.591 16.1485 + endloop + endfacet + facet normal 0.297679 -0.319063 0.89977 + outer loop + vertex 858.906 177.77 15.1585 + vertex 863.54 182.008 15.1283 + vertex 858.46 180.04 16.1111 + endloop + endfacet + facet normal 0.296377 -0.314727 0.901725 + outer loop + vertex 858.46 180.04 16.1111 + vertex 863.54 182.008 15.1283 + vertex 863.081 184.291 16.0759 + endloop + endfacet + facet normal 0.213439 -0.224157 0.950893 + outer loop + vertex 858.46 180.04 16.1111 + vertex 863.081 184.291 16.0759 + vertex 858.395 182.656 16.7421 + endloop + endfacet + facet normal 0.207924 -0.206214 0.956161 + outer loop + vertex 858.395 182.656 16.7421 + vertex 863.081 184.291 16.0759 + vertex 862.317 186.931 16.8115 + endloop + endfacet + facet normal 0.197039 -0.209792 0.957686 + outer loop + vertex 863.081 184.291 16.0759 + vertex 867.306 188.591 16.1485 + vertex 862.317 186.931 16.8115 + endloop + endfacet + facet normal 0.197186 -0.21029 0.957547 + outer loop + vertex 862.317 186.931 16.8115 + vertex 867.306 188.591 16.1485 + vertex 866.656 190.809 16.7695 + endloop + endfacet + facet normal 0.51982 -0.562622 0.64284 + outer loop + vertex 864.732 179.119 12.4272 + vertex 869.173 183.414 12.5942 + vertex 864.129 180.261 13.9138 + endloop + endfacet + facet normal 0.513195 -0.54283 0.664805 + outer loop + vertex 864.129 180.261 13.9138 + vertex 869.173 183.414 12.5942 + vertex 868.569 184.612 14.0388 + endloop + endfacet + facet normal 0.516467 -0.561163 0.646805 + outer loop + vertex 860.138 174.893 12.4285 + vertex 864.732 179.119 12.4272 + vertex 859.527 176.059 13.9282 + endloop + endfacet + facet normal 0.517361 -0.564434 0.643235 + outer loop + vertex 859.527 176.059 13.9282 + vertex 864.732 179.119 12.4272 + vertex 864.129 180.261 13.9138 + endloop + endfacet + facet normal 0.399776 -0.435088 0.80677 + outer loop + vertex 859.527 176.059 13.9282 + vertex 864.129 180.261 13.9138 + vertex 858.906 177.77 15.1585 + endloop + endfacet + facet normal 0.397989 -0.429375 0.810705 + outer loop + vertex 858.906 177.77 15.1585 + vertex 864.129 180.261 13.9138 + vertex 863.54 182.008 15.1283 + endloop + endfacet + facet normal 0.397938 -0.4294 0.810716 + outer loop + vertex 864.129 180.261 13.9138 + vertex 868.569 184.612 14.0388 + vertex 863.54 182.008 15.1283 + endloop + endfacet + facet normal 0.39144 -0.411728 0.822955 + outer loop + vertex 863.54 182.008 15.1283 + vertex 868.569 184.612 14.0388 + vertex 867.936 186.379 15.2241 + endloop + endfacet + facet normal 0.681691 -0.728494 0.0677833 + outer loop + vertex 865.364 178.52 8.84613 + vertex 869.938 182.816 9.02259 + vertex 865.181 178.522 10.7071 + endloop + endfacet + facet normal 0.684955 -0.722821 0.0914626 + outer loop + vertex 865.181 178.522 10.7071 + vertex 869.938 182.816 9.02259 + vertex 869.651 182.783 10.9107 + endloop + endfacet + facet normal 0.675555 -0.733117 0.0785193 + outer loop + vertex 860.746 174.265 8.85408 + vertex 865.364 178.52 8.84613 + vertex 860.563 174.294 10.7008 + endloop + endfacet + facet normal 0.67365 -0.736008 0.0670009 + outer loop + vertex 860.563 174.294 10.7008 + vertex 865.364 178.52 8.84613 + vertex 865.181 178.522 10.7071 + endloop + endfacet + facet normal 0.621844 -0.679892 0.388661 + outer loop + vertex 860.563 174.294 10.7008 + vertex 865.181 178.522 10.7071 + vertex 860.138 174.893 12.4285 + endloop + endfacet + facet normal 0.621459 -0.675358 0.39709 + outer loop + vertex 860.138 174.893 12.4285 + vertex 865.181 178.522 10.7071 + vertex 864.732 179.119 12.4272 + endloop + endfacet + facet normal 0.623796 -0.673267 0.396975 + outer loop + vertex 865.181 178.522 10.7071 + vertex 869.651 182.783 10.9107 + vertex 864.732 179.119 12.4272 + endloop + endfacet + facet normal 0.621459 -0.659204 0.423366 + outer loop + vertex 864.732 179.119 12.4272 + vertex 869.651 182.783 10.9107 + vertex 869.173 183.414 12.5942 + endloop + endfacet + facet normal 0.56865 -0.605366 -0.556929 + outer loop + vertex 864.815 180.239 5.33891 + vertex 869.26 184.372 5.38491 + vertex 865.249 179.115 7.00372 + endloop + endfacet + facet normal 0.583086 -0.610084 -0.536478 + outer loop + vertex 865.249 179.115 7.00372 + vertex 869.26 184.372 5.38491 + vertex 869.811 183.383 7.1089 + endloop + endfacet + facet normal 0.561523 -0.609564 -0.559575 + outer loop + vertex 860.292 176.045 5.36882 + vertex 864.815 180.239 5.33891 + vertex 860.673 174.872 7.02829 + endloop + endfacet + facet normal 0.562417 -0.609867 -0.558345 + outer loop + vertex 860.673 174.872 7.02829 + vertex 864.815 180.239 5.33891 + vertex 865.249 179.115 7.00372 + endloop + endfacet + facet normal 0.655388 -0.708431 -0.2619 + outer loop + vertex 860.673 174.872 7.02829 + vertex 865.249 179.115 7.00372 + vertex 860.746 174.265 8.85408 + endloop + endfacet + facet normal 0.652228 -0.708447 -0.269632 + outer loop + vertex 860.746 174.265 8.85408 + vertex 865.249 179.115 7.00372 + vertex 865.364 178.52 8.84613 + endloop + endfacet + facet normal 0.661511 -0.700543 -0.267663 + outer loop + vertex 865.249 179.115 7.00372 + vertex 869.811 183.383 7.1089 + vertex 865.364 178.52 8.84613 + endloop + endfacet + facet normal 0.66776 -0.700543 -0.251666 + outer loop + vertex 865.364 178.52 8.84613 + vertex 869.811 183.383 7.1089 + vertex 869.938 182.816 9.02259 + endloop + endfacet + facet normal 0.305393 -0.343187 -0.888233 + outer loop + vertex 862.81 183.406 2.87669 + vertex 866.933 186.709 3.01798 + vertex 864.008 181.667 3.96 + endloop + endfacet + facet normal 0.33935 -0.359356 -0.869313 + outer loop + vertex 864.008 181.667 3.96 + vertex 866.933 186.709 3.01798 + vertex 868.32 185.686 3.98239 + endloop + endfacet + facet normal 0.331588 -0.349902 -0.876138 + outer loop + vertex 858.367 178.854 3.01273 + vertex 862.81 183.406 2.87669 + vertex 859.543 177.544 3.98132 + endloop + endfacet + facet normal 0.309789 -0.339979 -0.887944 + outer loop + vertex 859.543 177.544 3.98132 + vertex 862.81 183.406 2.87669 + vertex 864.008 181.667 3.96 + endloop + endfacet + facet normal 0.440834 -0.481179 -0.757715 + outer loop + vertex 859.543 177.544 3.98132 + vertex 864.008 181.667 3.96 + vertex 860.292 176.045 5.36882 + endloop + endfacet + facet normal 0.441405 -0.481432 -0.757222 + outer loop + vertex 860.292 176.045 5.36882 + vertex 864.008 181.667 3.96 + vertex 864.815 180.239 5.33891 + endloop + endfacet + facet normal 0.448115 -0.476716 -0.756264 + outer loop + vertex 864.008 181.667 3.96 + vertex 868.32 185.686 3.98239 + vertex 864.815 180.239 5.33891 + endloop + endfacet + facet normal 0.452978 -0.478794 -0.752042 + outer loop + vertex 864.815 180.239 5.33891 + vertex 868.32 185.686 3.98239 + vertex 869.26 184.372 5.38491 + endloop + endfacet + facet normal 0.217355 -0.230726 -0.948432 + outer loop + vertex 866.933 186.709 3.01798 + vertex 862.81 183.406 2.87669 + vertex 867.174 190.744 2.09146 + endloop + endfacet + facet normal 0.202412 -0.226086 -0.952846 + outer loop + vertex 858.367 178.854 3.01273 + vertex 859.464 183.947 2.03727 + vertex 862.81 183.406 2.87669 + endloop + endfacet + facet normal 0.203102 -0.222791 -0.953474 + outer loop + vertex 859.464 183.947 2.03727 + vertex 867.174 190.744 2.09146 + vertex 862.81 183.406 2.87669 + endloop + endfacet + facet normal 0.138591 -0.152383 -0.978556 + outer loop + vertex 856.905 187.362 1.14315 + vertex 864.383 193.695 1.21607 + vertex 859.464 183.947 2.03727 + endloop + endfacet + facet normal 0.143163 -0.154605 -0.977549 + outer loop + vertex 859.464 183.947 2.03727 + vertex 864.383 193.695 1.21607 + vertex 867.174 190.744 2.09146 + endloop + endfacet + facet normal 0.384499 -0.380777 0.840934 + outer loop + vertex 850.628 218.19 21.9394 + vertex 853.063 220.924 22.0639 + vertex 851.233 219.736 22.3628 + endloop + endfacet + facet normal 0.396147 -0.402691 0.825172 + outer loop + vertex 851.233 219.736 22.3628 + vertex 853.063 220.924 22.0639 + vertex 852.612 221.416 22.5207 + endloop + endfacet + facet normal 0.276104 -0.262493 0.924588 + outer loop + vertex 851.63 215.26 20.6644 + vertex 854.689 218.501 20.671 + vertex 850.758 216.684 21.329 + endloop + endfacet + facet normal 0.280073 -0.272572 0.920469 + outer loop + vertex 850.758 216.684 21.329 + vertex 854.689 218.501 20.671 + vertex 853.653 219.751 21.3563 + endloop + endfacet + facet normal 0.167591 -0.170768 0.970954 + outer loop + vertex 852.898 211.004 19.5525 + vertex 856.478 213.937 19.4504 + vertex 852.609 213.369 20.0183 + endloop + endfacet + facet normal 0.165961 -0.157084 0.973541 + outer loop + vertex 852.609 213.369 20.0183 + vertex 856.478 213.937 19.4504 + vertex 855.886 216.761 20.0071 + endloop + endfacet + facet normal 0.221367 -0.210676 0.952162 + outer loop + vertex 852.609 213.369 20.0183 + vertex 855.886 216.761 20.0071 + vertex 851.63 215.26 20.6644 + endloop + endfacet + facet normal 0.221458 -0.21097 0.952076 + outer loop + vertex 851.63 215.26 20.6644 + vertex 855.886 216.761 20.0071 + vertex 854.689 218.501 20.671 + endloop + endfacet + facet normal 0.279204 -0.30155 0.911654 + outer loop + vertex 867.936 186.379 15.2241 + vertex 871.476 190.423 15.4775 + vertex 867.306 188.591 16.1485 + endloop + endfacet + facet normal 0.267182 -0.269196 0.925282 + outer loop + vertex 867.306 188.591 16.1485 + vertex 871.476 190.423 15.4775 + vertex 870.462 192.406 16.3473 + endloop + endfacet + facet normal 0.194842 -0.211064 0.957856 + outer loop + vertex 867.306 188.591 16.1485 + vertex 870.462 192.406 16.3473 + vertex 866.656 190.809 16.7695 + endloop + endfacet + facet normal 0.181365 -0.176408 0.967464 + outer loop + vertex 866.656 190.809 16.7695 + vertex 870.462 192.406 16.3473 + vertex 868.677 193.926 16.9591 + endloop + endfacet + facet normal 0.508543 -0.54618 0.665636 + outer loop + vertex 869.173 183.414 12.5942 + vertex 873.003 187.417 12.9533 + vertex 868.569 184.612 14.0388 + endloop + endfacet + facet normal 0.492616 -0.504077 0.709391 + outer loop + vertex 868.569 184.612 14.0388 + vertex 873.003 187.417 12.9533 + vertex 872.298 188.68 14.3403 + endloop + endfacet + facet normal 0.385721 -0.414616 0.824204 + outer loop + vertex 868.569 184.612 14.0388 + vertex 872.298 188.68 14.3403 + vertex 867.936 186.379 15.2241 + endloop + endfacet + facet normal 0.371335 -0.378216 0.847976 + outer loop + vertex 867.936 186.379 15.2241 + vertex 872.298 188.68 14.3403 + vertex 871.476 190.423 15.4775 + endloop + endfacet + facet normal 0.679708 -0.727869 0.090574 + outer loop + vertex 869.938 182.816 9.02259 + vertex 873.832 186.519 9.55752 + vertex 869.651 182.783 10.9107 + endloop + endfacet + facet normal 0.687076 -0.704423 0.178086 + outer loop + vertex 869.651 182.783 10.9107 + vertex 873.832 186.519 9.55752 + vertex 873.478 186.629 11.3582 + endloop + endfacet + facet normal 0.616978 -0.663244 0.423611 + outer loop + vertex 869.651 182.783 10.9107 + vertex 873.478 186.629 11.3582 + vertex 869.173 183.414 12.5942 + endloop + endfacet + facet normal 0.607574 -0.625147 0.489943 + outer loop + vertex 869.173 183.414 12.5942 + vertex 873.478 186.629 11.3582 + vertex 873.003 187.417 12.9533 + endloop + endfacet + facet normal 0.581005 -0.611789 -0.536793 + outer loop + vertex 869.26 184.372 5.38491 + vertex 873.309 188.019 5.61062 + vertex 869.811 183.383 7.1089 + endloop + endfacet + facet normal 0.606952 -0.61898 -0.498471 + outer loop + vertex 869.811 183.383 7.1089 + vertex 873.309 188.019 5.61062 + vertex 874.274 187.493 7.43896 + endloop + endfacet + facet normal 0.6656 -0.702445 -0.252085 + outer loop + vertex 869.811 183.383 7.1089 + vertex 874.274 187.493 7.43896 + vertex 869.938 182.816 9.02259 + endloop + endfacet + facet normal 0.690825 -0.700757 -0.178044 + outer loop + vertex 869.938 182.816 9.02259 + vertex 874.274 187.493 7.43896 + vertex 873.832 186.519 9.55752 + endloop + endfacet + facet normal 0.347974 -0.348582 -0.87029 + outer loop + vertex 866.933 186.709 3.01798 + vertex 870.69 190.629 2.94966 + vertex 868.32 185.686 3.98239 + endloop + endfacet + facet normal 0.346326 -0.34798 -0.871188 + outer loop + vertex 868.32 185.686 3.98239 + vertex 870.69 190.629 2.94966 + vertex 872.317 189.279 4.13586 + endloop + endfacet + facet normal 0.456664 -0.475802 -0.751712 + outer loop + vertex 868.32 185.686 3.98239 + vertex 872.317 189.279 4.13586 + vertex 869.26 184.372 5.38491 + endloop + endfacet + facet normal 0.476675 -0.483758 -0.734002 + outer loop + vertex 869.26 184.372 5.38491 + vertex 872.317 189.279 4.13586 + vertex 873.309 188.019 5.61062 + endloop + endfacet + facet normal 0.0412893 -0.145924 -0.988434 + outer loop + vertex 607.273 62.3069 1.48044 + vertex 606.481 66.6559 0.805322 + vertex 610.646 66.7451 0.966109 + endloop + endfacet + facet normal 0.0680969 -0.207641 -0.975832 + outer loop + vertex 607.203 58.4947 2.28677 + vertex 607.273 62.3069 1.48044 + vertex 611.097 61.8438 1.84589 + endloop + endfacet + facet normal -0.541472 -0.127175 -0.831044 + outer loop + vertex 606.626 55.8598 3.066 + vertex 607.203 58.4947 2.28677 + vertex 606.835 56.445 2.8404 + endloop + endfacet + facet normal 0.0674348 -0.452424 -0.88925 + outer loop + vertex 606.941 53.7521 4.16221 + vertex 606.626 55.8598 3.066 + vertex 607.163 55.0505 3.5184 + endloop + endfacet + facet normal 0.212025 -0.601204 -0.770454 + outer loop + vertex 607.205 52.127 5.50285 + vertex 606.941 53.7521 4.16221 + vertex 607.655 53.2149 4.77793 + endloop + endfacet + facet normal 0.329603 -0.732686 -0.595427 + outer loop + vertex 607.297 51.0689 6.85587 + vertex 607.205 52.127 5.50285 + vertex 607.897 51.5343 6.61573 + endloop + endfacet + facet normal 0.496292 -0.806447 -0.321462 + outer loop + vertex 607.393 50.5475 8.31232 + vertex 607.297 51.0689 6.85587 + vertex 607.897 51.5343 6.61573 + endloop + endfacet + facet normal 0.268748 -0.959506 -0.084396 + outer loop + vertex 607.365 50.3736 10.2009 + vertex 607.393 50.5475 8.31232 + vertex 608.147 50.7286 8.65495 + endloop + endfacet + facet normal 0.220021 -0.942071 0.253166 + outer loop + vertex 607.29 50.8582 12.0699 + vertex 607.365 50.3736 10.2009 + vertex 608.089 50.6533 10.6123 + endloop + endfacet + facet normal 0.217657 -0.821599 0.526878 + outer loop + vertex 607.178 51.9227 13.7761 + vertex 607.29 50.8582 12.0699 + vertex 608.008 51.3012 12.464 + endloop + endfacet + facet normal 0.182885 -0.675166 0.714636 + outer loop + vertex 607.027 53.4464 15.2541 + vertex 607.178 51.9227 13.7761 + vertex 607.853 52.4989 14.1476 + endloop + endfacet + facet normal 0.145976 -0.549885 0.822385 + outer loop + vertex 606.811 55.2238 16.4809 + vertex 607.027 53.4464 15.2541 + vertex 607.66 54.1164 15.5898 + endloop + endfacet + facet normal 0.105568 -0.447248 0.888158 + outer loop + vertex 606.694 57.1107 17.445 + vertex 606.811 55.2238 16.4809 + vertex 607.451 55.9376 16.7643 + endloop + endfacet + facet normal 0.065792 -0.327311 0.942623 + outer loop + vertex 607.141 59.7866 18.343 + vertex 606.694 57.1107 17.445 + vertex 607.489 57.7308 17.6048 + endloop + endfacet + facet normal 0.0591386 -0.255639 0.964962 + outer loop + vertex 607.219 64.2499 19.5206 + vertex 607.141 59.7866 18.343 + vertex 610.157 62.5215 18.8827 + endloop + endfacet + facet normal 0.0526007 -0.19794 0.978802 + outer loop + vertex 607.043 68.9257 20.4756 + vertex 607.219 64.2499 19.5206 + vertex 610.923 66.8025 19.8378 + endloop + endfacet + facet normal 0.29941 -0.377806 0.876137 + outer loop + vertex 604.48 84.2362 23.9307 + vertex 604.173 81.3065 22.7723 + vertex 604.873 82.9957 23.2616 + endloop + endfacet + facet normal 0.207183 -0.568144 0.796422 + outer loop + vertex 605.484 87.1402 25.7413 + vertex 604.48 84.2362 23.9307 + vertex 605.65 85.7738 24.7233 + endloop + endfacet + facet normal 0.0824887 -0.655808 0.750407 + outer loop + vertex 606.665 89.7983 27.9344 + vertex 605.484 87.1402 25.7413 + vertex 607.076 89.4984 27.6271 + endloop + endfacet + facet normal 0.602471 -0.714499 0.355697 + outer loop + vertex 608.22 92.6045 30.9375 + vertex 606.665 89.7983 27.9344 + vertex 607.739 91.5975 29.7297 + endloop + endfacet + facet normal 0.629559 -0.736046 0.248779 + outer loop + vertex 609.687 94.6868 33.3865 + vertex 608.22 92.6045 30.9375 + vertex 608.91 93.493 31.8195 + endloop + endfacet + facet normal 0.486397 -0.818674 0.305271 + outer loop + vertex 611.235 96.4954 35.7707 + vertex 609.687 94.6868 33.3865 + vertex 610.151 95.0884 33.724 + endloop + endfacet + facet normal 0.32272 -0.772381 0.547064 + outer loop + vertex 632.879 101.266 28.9522 + vertex 630.012 100.499 29.5606 + vertex 632.627 100.955 28.6616 + endloop + endfacet + facet normal 0.241306 -0.553187 0.797343 + outer loop + vertex 661.994 110.088 25.219 + vertex 657.26 108.727 25.7077 + vertex 658.665 108.039 24.8047 + endloop + endfacet + facet normal 0.211666 -0.526487 0.823413 + outer loop + vertex 716.305 131.602 25.2218 + vertex 710.781 129.05 25.0104 + vertex 714.531 129.5 24.3338 + endloop + endfacet + facet normal 0.231027 -0.52026 0.822166 + outer loop + vertex 722.278 133.973 25.0438 + vertex 716.305 131.602 25.2218 + vertex 719.817 131.78 24.348 + endloop + endfacet + facet normal 0.234927 -0.502052 0.832318 + outer loop + vertex 726.653 135.646 24.8187 + vertex 722.278 133.973 25.0438 + vertex 724.955 133.985 24.2955 + endloop + endfacet + facet normal 0.223237 -0.507791 0.832054 + outer loop + vertex 730.592 137.555 24.9267 + vertex 726.653 135.646 24.8187 + vertex 729.845 136.185 24.2905 + endloop + endfacet + facet normal 0.23687 -0.55074 0.800361 + outer loop + vertex 735.65 140.688 25.5857 + vertex 730.592 137.555 24.9267 + vertex 734.914 138.662 24.4089 + endloop + endfacet + facet normal 0.260576 -0.539297 0.800787 + outer loop + vertex 742.109 143.458 25.3492 + vertex 735.65 140.688 25.5857 + vertex 740.409 141.325 24.4657 + endloop + endfacet + facet normal 0.264286 -0.546454 0.794695 + outer loop + vertex 747.389 146.392 25.6111 + vertex 742.109 143.458 25.3492 + vertex 745.876 143.972 24.4501 + endloop + endfacet + facet normal 0.279817 -0.543814 0.791182 + outer loop + vertex 753.459 149.472 25.5809 + vertex 747.389 146.392 25.6111 + vertex 751.131 146.637 24.4553 + endloop + endfacet + facet normal 0.29264 -0.53616 0.791766 + outer loop + vertex 758.228 151.64 25.2867 + vertex 753.459 149.472 25.5809 + vertex 756.228 149.227 24.3917 + endloop + endfacet + facet normal 0.291904 -0.535574 0.792435 + outer loop + vertex 763.293 154.717 25.5001 + vertex 758.228 151.64 25.2867 + vertex 761.213 151.899 24.362 + endloop + endfacet + facet normal 0.30611 -0.526424 0.793205 + outer loop + vertex 770.23 158.363 25.2431 + vertex 763.293 154.717 25.5001 + vertex 766.488 154.789 24.315 + endloop + endfacet + facet normal 0.314409 -0.516294 0.79661 + outer loop + vertex 775.732 161.402 25.0411 + vertex 770.23 158.363 25.2431 + vertex 774.842 159.498 24.1581 + endloop + endfacet + facet normal 0.323433 -0.522533 0.788892 + outer loop + vertex 780.372 164.481 25.1786 + vertex 775.732 161.402 25.0411 + vertex 779.519 162.333 24.1052 + endloop + endfacet + facet normal 0.339111 -0.51443 0.787633 + outer loop + vertex 785.063 167.125 24.8852 + vertex 780.372 164.481 25.1786 + vertex 784.217 165.219 24.0047 + endloop + endfacet + facet normal 0.34841 -0.518812 0.780669 + outer loop + vertex 789.454 170.364 25.0781 + vertex 785.063 167.125 24.8852 + vertex 788.892 168.231 23.9115 + endloop + endfacet + facet normal 0.364231 -0.51268 0.777493 + outer loop + vertex 795.128 174.217 24.9608 + vertex 789.454 170.364 25.0781 + vertex 793.714 171.506 23.8353 + endloop + endfacet + facet normal 0.377953 -0.498542 0.780132 + outer loop + vertex 800.483 177.605 24.5315 + vertex 795.128 174.217 24.9608 + vertex 798.673 174.846 23.6455 + endloop + endfacet + facet normal 0.384546 -0.478575 0.789361 + outer loop + vertex 804.524 179.96 23.9905 + vertex 800.483 177.605 24.5315 + vertex 803.294 177.954 23.3737 + endloop + endfacet + facet normal 0.378011 -0.475888 0.794127 + outer loop + vertex 808.247 182.901 23.9811 + vertex 804.524 179.96 23.9905 + vertex 807.559 181.006 23.1726 + endloop + endfacet + facet normal 0.384803 -0.466896 0.7962 + outer loop + vertex 812.666 186.292 23.8336 + vertex 808.247 182.901 23.9811 + vertex 811.839 184.28 23.0539 + endloop + endfacet + facet normal 0.390638 -0.460971 0.796811 + outer loop + vertex 816.978 189.753 23.722 + vertex 812.666 186.292 23.8336 + vertex 816.147 187.685 22.9328 + endloop + endfacet + facet normal 0.396867 -0.459486 0.794587 + outer loop + vertex 821.471 193.688 23.7532 + vertex 816.978 189.753 23.722 + vertex 820.422 191.201 22.8391 + endloop + endfacet + facet normal 0.408771 -0.450758 0.793551 + outer loop + vertex 825.884 197.226 23.4902 + vertex 821.471 193.688 23.7532 + vertex 824.596 194.704 22.7208 + endloop + endfacet + facet normal 0.410329 -0.444263 0.796405 + outer loop + vertex 829.883 200.658 23.3438 + vertex 825.884 197.226 23.4902 + vertex 828.601 198.101 22.5785 + endloop + endfacet + facet normal 0.414459 -0.440279 0.796478 + outer loop + vertex 834.4 204.568 23.1547 + vertex 829.883 200.658 23.3438 + vertex 832.424 201.404 22.4343 + endloop + endfacet + facet normal 0.417336 -0.44327 0.793311 + outer loop + vertex 839.045 209.323 23.3679 + vertex 834.4 204.568 23.1547 + vertex 838.706 207.146 22.3301 + endloop + endfacet + facet normal 0.424112 -0.430983 0.796481 + outer loop + vertex 843.806 213.502 23.0946 + vertex 839.045 209.323 23.3679 + vertex 842.801 210.995 22.2729 + endloop + endfacet + facet normal 0.422732 -0.420806 0.802633 + outer loop + vertex 848.322 217.607 22.8678 + vertex 843.806 213.502 23.0946 + vertex 847.04 214.863 22.1048 + endloop + endfacet + facet normal 0.46676 -0.458795 0.75607 + outer loop + vertex 851.411 221.057 23.0545 + vertex 848.322 217.607 22.8678 + vertex 851.233 219.736 22.3628 + endloop + endfacet + facet normal 0.472167 -0.478623 0.740255 + outer loop + vertex 854.308 224.139 23.1992 + vertex 851.411 221.057 23.0545 + vertex 852.612 221.416 22.5207 + endloop + endfacet + facet normal 0.304021 -0.324294 0.89577 + outer loop + vertex 856.825 221.106 20.7705 + vertex 855.566 222.339 21.6441 + vertex 853.653 219.751 21.3563 + endloop + endfacet + facet normal 0.233016 -0.227147 0.945573 + outer loop + vertex 858.209 219.591 20.0655 + vertex 856.825 221.106 20.7705 + vertex 854.689 218.501 20.671 + endloop + endfacet + facet normal 0.173482 -0.162452 0.971346 + outer loop + vertex 859.334 217.3 19.4814 + vertex 858.209 219.591 20.0655 + vertex 855.886 216.761 20.0071 + endloop + endfacet + facet normal 0.144021 -0.122077 0.982016 + outer loop + vertex 872.261 195.678 16.6513 + vertex 869.356 198.16 17.3858 + vertex 868.677 193.926 16.9591 + endloop + endfacet + facet normal 0.235752 -0.217596 0.947139 + outer loop + vertex 873.795 193.747 15.8256 + vertex 872.261 195.678 16.6513 + vertex 870.462 192.406 16.3473 + endloop + endfacet + facet normal 0.339731 -0.329312 0.880986 + outer loop + vertex 874.802 191.972 14.7739 + vertex 873.795 193.747 15.8256 + vertex 871.476 190.423 15.4775 + endloop + endfacet + facet normal 0.456446 -0.44847 0.768461 + outer loop + vertex 875.871 190.727 13.4124 + vertex 874.802 191.972 14.7739 + vertex 872.298 188.68 14.3403 + endloop + endfacet + facet normal 0.574538 -0.578248 0.579254 + outer loop + vertex 876.437 189.776 11.9019 + vertex 875.871 190.727 13.4124 + vertex 873.003 187.417 12.9533 + endloop + endfacet + facet normal 0.666304 -0.679514 0.307083 + outer loop + vertex 876.536 189.151 10.3036 + vertex 876.437 189.776 11.9019 + vertex 873.478 186.629 11.3582 + endloop + endfacet + facet normal 0.697736 -0.716353 -0.00172844 + outer loop + vertex 876.968 189.576 8.56137 + vertex 876.536 189.151 10.3036 + vertex 873.832 186.519 9.55752 + endloop + endfacet + facet normal 0.657915 -0.69619 -0.287171 + outer loop + vertex 877.268 190.523 6.95203 + vertex 876.968 189.576 8.56137 + vertex 874.274 187.493 7.43896 + endloop + endfacet + facet normal 0.56942 -0.644588 -0.510164 + outer loop + vertex 876.285 190.533 5.84204 + vertex 877.268 190.523 6.95203 + vertex 874.274 187.493 7.43896 + endloop + endfacet + facet normal 0.486141 -0.51012 -0.709539 + outer loop + vertex 875.747 191.803 4.56028 + vertex 876.285 190.533 5.84204 + vertex 873.309 188.019 5.61062 + endloop + endfacet + facet normal 0.375438 -0.367068 -0.851063 + outer loop + vertex 874.346 193.47 3.2235 + vertex 875.747 191.803 4.56028 + vertex 872.317 189.279 4.13586 + endloop + endfacet + facet normal 0.270598 -0.258931 -0.927217 + outer loop + vertex 872.775 195.776 2.12094 + vertex 874.346 193.47 3.2235 + vertex 870.69 190.629 2.94966 + endloop + endfacet + facet normal 0.149107 -0.160251 -0.975749 + outer loop + vertex 870.892 198.695 1.35385 + vertex 872.775 195.776 2.12094 + vertex 867.174 190.744 2.09146 + endloop + endfacet + facet normal -0.307869 -0.623071 0.719027 + outer loop + vertex 607.076 89.4984 27.6271 + vertex 608.05 92.1642 30.3539 + vertex 607.739 91.5975 29.7297 + endloop + endfacet + facet normal 0.0196339 -0.469848 0.882529 + outer loop + vertex 604.873 82.9957 23.2616 + vertex 605.65 85.7738 24.7233 + vertex 604.48 84.2362 23.9307 + endloop + endfacet + facet normal -0.0547848 -0.600785 0.797531 + outer loop + vertex 605.65 85.7738 24.7233 + vertex 607.076 89.4984 27.6271 + vertex 605.484 87.1402 25.7413 + endloop + endfacet + facet normal 0.0642238 -0.155054 0.985816 + outer loop + vertex 606.179 79.6722 22.2049 + vertex 604.456 80.0321 22.3738 + vertex 605.253 78.4326 22.0703 + endloop + endfacet + facet normal 0.204244 -0.513908 0.833176 + outer loop + vertex 607.66 54.1164 15.5898 + vertex 607.451 55.9376 16.7643 + vertex 606.811 55.2238 16.4809 + endloop + endfacet + facet normal 0.149567 -0.422258 0.894052 + outer loop + vertex 607.451 55.9376 16.7643 + vertex 607.489 57.7308 17.6048 + vertex 606.694 57.1107 17.445 + endloop + endfacet + facet normal 0.0921186 -0.322643 0.942028 + outer loop + vertex 607.489 57.7308 17.6048 + vertex 609.492 59.3042 17.9479 + vertex 607.141 59.7866 18.343 + endloop + endfacet + facet normal 0.331514 -0.754114 0.56693 + outer loop + vertex 608.008 51.3012 12.464 + vertex 607.853 52.4989 14.1476 + vertex 607.178 51.9227 13.7761 + endloop + endfacet + facet normal 0.269743 -0.622691 0.734503 + outer loop + vertex 607.853 52.4989 14.1476 + vertex 607.66 54.1164 15.5898 + vertex 607.027 53.4464 15.2541 + endloop + endfacet + facet normal 0.372335 -0.927769 -0.0247213 + outer loop + vertex 608.147 50.7286 8.65495 + vertex 608.089 50.6533 10.6123 + vertex 607.365 50.3736 10.2009 + endloop + endfacet + facet normal 0.362782 -0.874479 0.321986 + outer loop + vertex 608.089 50.6533 10.6123 + vertex 608.008 51.3012 12.464 + vertex 607.29 50.8582 12.0699 + endloop + endfacet + facet normal 0.478886 -0.615502 -0.625959 + outer loop + vertex 607.655 53.2149 4.77793 + vertex 607.897 51.5343 6.61573 + vertex 607.205 52.127 5.50285 + endloop + endfacet + facet normal 0.375615 -0.845312 -0.379948 + outer loop + vertex 607.897 51.5343 6.61573 + vertex 608.147 50.7286 8.65495 + vertex 607.393 50.5475 8.31232 + endloop + endfacet + facet normal 0.131382 -0.280425 -0.950842 + outer loop + vertex 608.323 57.2689 2.80296 + vertex 606.835 56.445 2.8404 + vertex 607.203 58.4947 2.28677 + endloop + endfacet + facet normal 0.153554 -0.402662 -0.902377 + outer loop + vertex 606.835 56.445 2.8404 + vertex 607.163 55.0505 3.5184 + vertex 606.626 55.8598 3.066 + endloop + endfacet + facet normal 0.352448 -0.463321 -0.813089 + outer loop + vertex 607.163 55.0505 3.5184 + vertex 607.655 53.2149 4.77793 + vertex 606.941 53.7521 4.16221 + endloop + endfacet + facet normal 0.098824 -0.296435 0.949926 + outer loop + vertex 609.492 59.3042 17.9479 + vertex 610.157 62.5215 18.8827 + vertex 607.141 59.7866 18.343 + endloop + endfacet + facet normal 0.1326 -0.279372 -0.950983 + outer loop + vertex 611.097 61.8438 1.84589 + vertex 608.323 57.2689 2.80296 + vertex 607.203 58.4947 2.28677 + endloop + endfacet + facet normal 0.0733603 -0.169641 -0.982772 + outer loop + vertex 610.646 66.7451 0.966109 + vertex 611.097 61.8438 1.84589 + vertex 607.273 62.3069 1.48044 + endloop + endfacet + facet normal 0.322119 -0.774691 0.544144 + outer loop + vertex 627.1 99.5452 29.9263 + vertex 632.627 100.955 28.6616 + vertex 630.012 100.499 29.5606 + endloop + endfacet + facet normal 0.298422 -0.676599 0.67317 + outer loop + vertex 638.064 102.339 27.5361 + vertex 642.639 103.527 26.7015 + vertex 641.389 103.521 27.2507 + endloop + endfacet + facet normal 0.211546 -0.509064 0.834327 + outer loop + vertex 709.437 127.307 24.2875 + vertex 714.531 129.5 24.3338 + vertex 710.781 129.05 25.0104 + endloop + endfacet + facet normal 0.229344 -0.536611 0.812065 + outer loop + vertex 714.531 129.5 24.3338 + vertex 719.817 131.78 24.348 + vertex 716.305 131.602 25.2218 + endloop + endfacet + facet normal 0.231957 -0.52106 0.821397 + outer loop + vertex 719.817 131.78 24.348 + vertex 724.955 133.985 24.2955 + vertex 722.278 133.973 25.0438 + endloop + endfacet + facet normal 0.222183 -0.492006 0.841763 + outer loop + vertex 724.955 133.985 24.2955 + vertex 729.845 136.185 24.2905 + vertex 726.653 135.646 24.8187 + endloop + endfacet + facet normal 0.22985 -0.509942 0.828932 + outer loop + vertex 729.845 136.185 24.2905 + vertex 734.914 138.662 24.4089 + vertex 730.592 137.555 24.9267 + endloop + endfacet + facet normal 0.260202 -0.553761 0.790976 + outer loop + vertex 734.914 138.662 24.4089 + vertex 740.409 141.325 24.4657 + vertex 735.65 140.688 25.5857 + endloop + endfacet + facet normal 0.264413 -0.541278 0.798188 + outer loop + vertex 740.409 141.325 24.4657 + vertex 745.876 143.972 24.4501 + vertex 742.109 143.458 25.3492 + endloop + endfacet + facet normal 0.278789 -0.551463 0.786235 + outer loop + vertex 745.876 143.972 24.4501 + vertex 751.131 146.637 24.4553 + vertex 747.389 146.392 25.6111 + endloop + endfacet + facet normal 0.288563 -0.548463 0.784805 + outer loop + vertex 751.131 146.637 24.4553 + vertex 756.228 149.227 24.3917 + vertex 753.459 149.472 25.5809 + endloop + endfacet + facet normal 0.291886 -0.535743 0.792327 + outer loop + vertex 756.228 149.227 24.3917 + vertex 761.213 151.899 24.362 + vertex 758.228 151.64 25.2867 + endloop + endfacet + facet normal 0.303243 -0.54078 0.784602 + outer loop + vertex 761.213 151.899 24.362 + vertex 766.488 154.789 24.315 + vertex 763.293 154.717 25.5001 + endloop + endfacet + facet normal 0.303481 -0.524299 0.795619 + outer loop + vertex 766.488 154.789 24.315 + vertex 771.005 157.043 24.0774 + vertex 770.23 158.363 25.2431 + endloop + endfacet + facet normal 0.314536 -0.517787 0.79559 + outer loop + vertex 771.005 157.043 24.0774 + vertex 774.842 159.498 24.1581 + vertex 770.23 158.363 25.2431 + endloop + endfacet + facet normal 0.323104 -0.518174 0.791896 + outer loop + vertex 774.842 159.498 24.1581 + vertex 779.519 162.333 24.1052 + vertex 775.732 161.402 25.0411 + endloop + endfacet + facet normal 0.339016 -0.524708 0.780865 + outer loop + vertex 779.519 162.333 24.1052 + vertex 784.217 165.219 24.0047 + vertex 780.372 164.481 25.1786 + endloop + endfacet + facet normal 0.348117 -0.516101 0.782595 + outer loop + vertex 784.217 165.219 24.0047 + vertex 788.892 168.231 23.9115 + vertex 785.063 167.125 24.8852 + endloop + endfacet + facet normal 0.364639 -0.518959 0.773124 + outer loop + vertex 788.892 168.231 23.9115 + vertex 793.714 171.506 23.8353 + vertex 789.454 170.364 25.0781 + endloop + endfacet + facet normal 0.376992 -0.515904 0.769233 + outer loop + vertex 793.714 171.506 23.8353 + vertex 798.673 174.846 23.6455 + vertex 795.128 174.217 24.9608 + endloop + endfacet + facet normal 0.382143 -0.500277 0.776974 + outer loop + vertex 798.673 174.846 23.6455 + vertex 803.294 177.954 23.3737 + vertex 800.483 177.605 24.5315 + endloop + endfacet + facet normal 0.378033 -0.47602 0.794038 + outer loop + vertex 803.294 177.954 23.3737 + vertex 807.559 181.006 23.1726 + vertex 804.524 179.96 23.9905 + endloop + endfacet + facet normal 0.386869 -0.476993 0.789183 + outer loop + vertex 807.559 181.006 23.1726 + vertex 811.839 184.28 23.0539 + vertex 808.247 182.901 23.9811 + endloop + endfacet + facet normal 0.392242 -0.468238 0.79177 + outer loop + vertex 811.839 184.28 23.0539 + vertex 816.147 187.685 22.9328 + vertex 812.666 186.292 23.8336 + endloop + endfacet + facet normal 0.397513 -0.462167 0.792708 + outer loop + vertex 816.147 187.685 22.9328 + vertex 820.422 191.201 22.8391 + vertex 816.978 189.753 23.722 + endloop + endfacet + facet normal 0.410065 -0.462033 0.786366 + outer loop + vertex 820.422 191.201 22.8391 + vertex 824.596 194.704 22.7208 + vertex 821.471 193.688 23.7532 + endloop + endfacet + facet normal 0.411145 -0.451471 0.791918 + outer loop + vertex 824.596 194.704 22.7208 + vertex 828.601 198.101 22.5785 + vertex 825.884 197.226 23.4902 + endloop + endfacet + facet normal 0.414883 -0.445613 0.793285 + outer loop + vertex 828.601 198.101 22.5785 + vertex 832.424 201.404 22.4343 + vertex 829.883 200.658 23.3438 + endloop + endfacet + facet normal 0.409734 -0.43815 0.80009 + outer loop + vertex 832.424 201.404 22.4343 + vertex 835.764 204.134 22.2183 + vertex 834.4 204.568 23.1547 + endloop + endfacet + facet normal 0.412558 -0.432625 0.801643 + outer loop + vertex 835.764 204.134 22.2183 + vertex 838.706 207.146 22.3301 + vertex 834.4 204.568 23.1547 + endloop + endfacet + facet normal 0.42695 -0.442521 0.788599 + outer loop + vertex 838.706 207.146 22.3301 + vertex 842.801 210.995 22.2729 + vertex 839.045 209.323 23.3679 + endloop + endfacet + facet normal 0.425028 -0.431159 0.795898 + outer loop + vertex 842.801 210.995 22.2729 + vertex 847.04 214.863 22.1048 + vertex 843.806 213.502 23.0946 + endloop + endfacet + facet normal 0.42844 -0.422397 0.798761 + outer loop + vertex 847.04 214.863 22.1048 + vertex 850.628 218.19 21.9394 + vertex 848.322 217.607 22.8678 + endloop + endfacet + facet normal 0.130275 -0.144109 0.980949 + outer loop + vertex 862.578 191.376 17.3943 + vertex 866.656 190.809 16.7695 + vertex 868.677 193.926 16.9591 + endloop + endfacet + facet normal 0.223617 -0.230763 -0.946966 + outer loop + vertex 866.933 186.709 3.01798 + vertex 867.174 190.744 2.09146 + vertex 870.69 190.629 2.94966 + endloop + endfacet + facet normal 0.141016 -0.156633 -0.977538 + outer loop + vertex 867.174 190.744 2.09146 + vertex 864.383 193.695 1.21607 + vertex 870.892 198.695 1.35385 + endloop + endfacet + facet normal 0.427117 -0.390498 0.815526 + outer loop + vertex 850.628 218.19 21.9394 + vertex 851.233 219.736 22.3628 + vertex 848.322 217.607 22.8678 + endloop + endfacet + facet normal 0.471842 -0.458057 0.753358 + outer loop + vertex 851.233 219.736 22.3628 + vertex 852.612 221.416 22.5207 + vertex 851.411 221.057 23.0545 + endloop + endfacet + facet normal 0.363799 -0.432261 0.825107 + outer loop + vertex 852.612 221.416 22.5207 + vertex 853.063 220.924 22.0639 + vertex 854.308 224.139 23.1992 + endloop + endfacet + facet normal 0.284727 -0.268577 0.920216 + outer loop + vertex 853.653 219.751 21.3563 + vertex 854.689 218.501 20.671 + vertex 856.825 221.106 20.7705 + endloop + endfacet + facet normal 0.172595 -0.155515 0.972639 + outer loop + vertex 855.886 216.761 20.0071 + vertex 856.478 213.937 19.4504 + vertex 859.334 217.3 19.4814 + endloop + endfacet + facet normal 0.227661 -0.206517 0.951589 + outer loop + vertex 854.689 218.501 20.671 + vertex 855.886 216.761 20.0071 + vertex 858.209 219.591 20.0655 + endloop + endfacet + facet normal 0.255859 -0.275568 0.926606 + outer loop + vertex 870.462 192.406 16.3473 + vertex 871.476 190.423 15.4775 + vertex 873.795 193.747 15.8256 + endloop + endfacet + facet normal 0.173675 -0.185331 0.967207 + outer loop + vertex 868.677 193.926 16.9591 + vertex 870.462 192.406 16.3473 + vertex 872.261 195.678 16.6513 + endloop + endfacet + facet normal 0.479162 -0.513936 0.711529 + outer loop + vertex 872.298 188.68 14.3403 + vertex 873.003 187.417 12.9533 + vertex 875.871 190.727 13.4124 + endloop + endfacet + facet normal 0.359232 -0.385255 0.850018 + outer loop + vertex 871.476 190.423 15.4775 + vertex 872.298 188.68 14.3403 + vertex 874.802 191.972 14.7739 + endloop + endfacet + facet normal 0.661619 -0.729235 0.174578 + outer loop + vertex 873.478 186.629 11.3582 + vertex 873.832 186.519 9.55752 + vertex 876.536 189.151 10.3036 + endloop + endfacet + facet normal 0.590212 -0.639928 0.49208 + outer loop + vertex 873.003 187.417 12.9533 + vertex 873.478 186.629 11.3582 + vertex 876.437 189.776 11.9019 + endloop + endfacet + facet normal 0.583359 -0.645073 -0.493531 + outer loop + vertex 874.274 187.493 7.43896 + vertex 873.309 188.019 5.61062 + vertex 876.285 190.533 5.84204 + endloop + endfacet + facet normal 0.65024 -0.73262 -0.201138 + outer loop + vertex 873.832 186.519 9.55752 + vertex 874.274 187.493 7.43896 + vertex 876.968 189.576 8.56137 + endloop + endfacet + facet normal 0.340628 -0.354509 -0.870802 + outer loop + vertex 872.317 189.279 4.13586 + vertex 870.69 190.629 2.94966 + vertex 874.346 193.47 3.2235 + endloop + endfacet + facet normal 0.458473 -0.499396 -0.735123 + outer loop + vertex 873.309 188.019 5.61062 + vertex 872.317 189.279 4.13586 + vertex 875.747 191.803 4.56028 + endloop + endfacet + facet normal 0.00963088 -0.709181 0.70496 + outer loop + vertex 606.665 89.7983 27.9344 + vertex 607.076 89.4984 27.6271 + vertex 607.739 91.5975 29.7297 + endloop + endfacet + facet normal 0.26581 -0.557564 0.786427 + outer loop + vertex 645.4 104.459 26.4295 + vertex 642.639 103.527 26.7015 + vertex 647.221 104.41 25.7789 + endloop + endfacet + facet normal 0.119938 -0.118584 0.985674 + outer loop + vertex 868.677 193.926 16.9591 + vertex 869.356 198.16 17.3858 + vertex 862.578 191.376 17.3943 + endloop + endfacet + facet normal 0.222601 -0.242239 -0.944335 + outer loop + vertex 872.775 195.776 2.12094 + vertex 870.69 190.629 2.94966 + vertex 867.174 190.744 2.09146 + endloop + endfacet + facet normal 0.423855 -0.413776 0.80569 + outer loop + vertex 856.871 224.351 21.9673 + vertex 858.117 226.012 22.165 + vertex 855.838 225.675 23.1908 + endloop + endfacet + facet normal 0.421149 -0.448832 0.788152 + outer loop + vertex 855.838 225.675 23.1908 + vertex 858.117 226.012 22.165 + vertex 856.833 227.158 23.5031 + endloop + endfacet + facet normal 0.255598 -0.247555 0.934551 + outer loop + vertex 859.682 221.623 20.1656 + vertex 860.919 223.295 20.27 + vertex 858.219 223.06 20.9463 + endloop + endfacet + facet normal 0.255979 -0.271264 0.927842 + outer loop + vertex 858.219 223.06 20.9463 + vertex 860.919 223.295 20.27 + vertex 859.467 224.773 21.103 + endloop + endfacet + facet normal 0.346184 -0.33235 0.877325 + outer loop + vertex 858.219 223.06 20.9463 + vertex 859.467 224.773 21.103 + vertex 856.871 224.351 21.9673 + endloop + endfacet + facet normal 0.346992 -0.363152 0.864706 + outer loop + vertex 856.871 224.351 21.9673 + vertex 859.467 224.773 21.103 + vertex 858.117 226.012 22.165 + endloop + endfacet + facet normal 0.101367 -0.139553 0.985012 + outer loop + vertex 861.321 217.608 19.2273 + vertex 863.069 218.414 19.1616 + vertex 860.927 219.675 19.5607 + endloop + endfacet + facet normal 0.108975 -0.126922 0.985908 + outer loop + vertex 860.927 219.675 19.5607 + vertex 863.069 218.414 19.1616 + vertex 862.348 221.341 19.6182 + endloop + endfacet + facet normal 0.17874 -0.185719 0.966209 + outer loop + vertex 860.927 219.675 19.5607 + vertex 862.348 221.341 19.6182 + vertex 859.682 221.623 20.1656 + endloop + endfacet + facet normal 0.177869 -0.191918 0.965158 + outer loop + vertex 859.682 221.623 20.1656 + vertex 862.348 221.341 19.6182 + vertex 860.919 223.295 20.27 + endloop + endfacet + facet normal 0.30743 -0.296453 0.904214 + outer loop + vertex 876.343 194.425 15.1545 + vertex 877.767 196.591 15.3806 + vertex 875.303 196.342 16.1367 + endloop + endfacet + facet normal 0.307268 -0.26641 0.913571 + outer loop + vertex 875.303 196.342 16.1367 + vertex 877.767 196.591 15.3806 + vertex 876.677 198.688 16.3588 + endloop + endfacet + facet normal 0.204263 -0.210117 0.9561 + outer loop + vertex 875.303 196.342 16.1367 + vertex 876.677 198.688 16.3588 + vertex 873.86 198.067 16.824 + endloop + endfacet + facet normal 0.195478 -0.161986 0.967238 + outer loop + vertex 873.86 198.067 16.824 + vertex 876.677 198.688 16.3588 + vertex 874.858 200.732 17.0686 + endloop + endfacet + facet normal 0.510552 -0.482322 0.71183 + outer loop + vertex 877.693 191.94 12.9684 + vertex 878.189 192.791 13.1899 + vertex 877.016 192.796 14.0346 + endloop + endfacet + facet normal 0.524132 -0.459801 0.716846 + outer loop + vertex 878.938 193.445 13.0615 + vertex 878.305 194.417 14.1474 + vertex 878.189 192.791 13.1899 + endloop + endfacet + facet normal 0.51709 -0.461616 0.720783 + outer loop + vertex 878.305 194.417 14.1474 + vertex 877.016 192.796 14.0346 + vertex 878.189 192.791 13.1899 + endloop + endfacet + facet normal 0.419025 -0.39048 0.819721 + outer loop + vertex 877.016 192.796 14.0346 + vertex 878.305 194.417 14.1474 + vertex 876.343 194.425 15.1545 + endloop + endfacet + facet normal 0.423841 -0.365097 0.828893 + outer loop + vertex 876.343 194.425 15.1545 + vertex 878.305 194.417 14.1474 + vertex 877.767 196.591 15.3806 + endloop + endfacet + facet normal 0.730277 -0.681762 0.043541 + outer loop + vertex 878.894 191.337 9.00347 + vertex 879.447 191.929 8.99258 + vertex 878.882 191.392 10.064 + endloop + endfacet + facet normal 0.730538 -0.681465 0.0438277 + outer loop + vertex 878.882 191.392 10.064 + vertex 879.447 191.929 8.99258 + vertex 879.388 191.933 10.0544 + endloop + endfacet + facet normal 0.748585 -0.662754 0.0194511 + outer loop + vertex 878.616 191.019 8.86756 + vertex 878.894 191.337 9.00347 + vertex 878.613 191.048 9.94678 + endloop + endfacet + facet normal 0.780799 -0.623429 0.0410903 + outer loop + vertex 878.613 191.048 9.94678 + vertex 878.894 191.337 9.00347 + vertex 878.882 191.392 10.064 + endloop + endfacet + facet normal 0.739696 -0.643926 0.195471 + outer loop + vertex 878.613 191.048 9.94678 + vertex 878.882 191.392 10.064 + vertex 878.539 191.286 11.0136 + endloop + endfacet + facet normal 0.795059 -0.563475 0.224449 + outer loop + vertex 878.539 191.286 11.0136 + vertex 878.882 191.392 10.064 + vertex 878.741 191.617 11.1254 + endloop + endfacet + facet normal 0.712597 -0.661322 0.234219 + outer loop + vertex 878.882 191.392 10.064 + vertex 879.388 191.933 10.0544 + vertex 878.741 191.617 11.1254 + endloop + endfacet + facet normal 0.719641 -0.650985 0.241526 + outer loop + vertex 878.741 191.617 11.1254 + vertex 879.388 191.933 10.0544 + vertex 879.215 192.144 11.1359 + endloop + endfacet + facet normal 0.685313 -0.727164 -0.0397299 + outer loop + vertex 878.292 190.732 8.53582 + vertex 878.616 191.019 8.86756 + vertex 878.102 190.497 9.5526 + endloop + endfacet + facet normal 0.725339 -0.688099 0.0200659 + outer loop + vertex 878.102 190.497 9.5526 + vertex 878.616 191.019 8.86756 + vertex 878.613 191.048 9.94678 + endloop + endfacet + facet normal 0.668809 -0.728253 0.149476 + outer loop + vertex 878.102 190.497 9.5526 + vertex 878.613 191.048 9.94678 + vertex 877.995 190.655 10.799 + endloop + endfacet + facet normal 0.707363 -0.67774 0.200764 + outer loop + vertex 877.995 190.655 10.799 + vertex 878.613 191.048 9.94678 + vertex 878.539 191.286 11.0136 + endloop + endfacet + facet normal 0.668351 -0.67907 0.303598 + outer loop + vertex 877.995 190.655 10.799 + vertex 878.539 191.286 11.0136 + vertex 878.033 191.103 11.7167 + endloop + endfacet + facet normal 0.726431 -0.578031 0.371723 + outer loop + vertex 878.033 191.103 11.7167 + vertex 878.539 191.286 11.0136 + vertex 878.286 191.602 11.9971 + endloop + endfacet + facet normal 0.626841 -0.598761 0.498553 + outer loop + vertex 878.033 191.103 11.7167 + vertex 878.286 191.602 11.9971 + vertex 877.547 191.229 12.4792 + endloop + endfacet + facet normal 0.63462 -0.522479 0.56945 + outer loop + vertex 877.547 191.229 12.4792 + vertex 878.286 191.602 11.9971 + vertex 877.693 191.94 12.9684 + endloop + endfacet + facet normal 0.673521 -0.612984 0.413062 + outer loop + vertex 878.741 191.617 11.1254 + vertex 879.215 192.144 11.1359 + vertex 878.469 192.023 12.1726 + endloop + endfacet + facet normal 0.676061 -0.608589 0.415405 + outer loop + vertex 878.469 192.023 12.1726 + vertex 879.215 192.144 11.1359 + vertex 879.012 192.64 12.1935 + endloop + endfacet + facet normal 0.730308 -0.573435 0.371244 + outer loop + vertex 878.539 191.286 11.0136 + vertex 878.741 191.617 11.1254 + vertex 878.286 191.602 11.9971 + endloop + endfacet + facet normal 0.771973 -0.498596 0.394284 + outer loop + vertex 878.286 191.602 11.9971 + vertex 878.741 191.617 11.1254 + vertex 878.469 192.023 12.1726 + endloop + endfacet + facet normal 0.640224 -0.514778 0.57019 + outer loop + vertex 878.286 191.602 11.9971 + vertex 878.469 192.023 12.1726 + vertex 877.693 191.94 12.9684 + endloop + endfacet + facet normal 0.638475 -0.519343 0.568007 + outer loop + vertex 877.693 191.94 12.9684 + vertex 878.469 192.023 12.1726 + vertex 878.189 192.791 13.1899 + endloop + endfacet + facet normal 0.601782 -0.548851 0.580191 + outer loop + vertex 878.469 192.023 12.1726 + vertex 879.012 192.64 12.1935 + vertex 878.189 192.791 13.1899 + endloop + endfacet + facet normal 0.591851 -0.565388 0.574498 + outer loop + vertex 878.189 192.791 13.1899 + vertex 879.012 192.64 12.1935 + vertex 878.938 193.445 13.0615 + endloop + endfacet + facet normal 0.474415 -0.531652 -0.701625 + outer loop + vertex 878.018 193.533 4.90308 + vertex 878.489 193.642 5.13867 + vertex 878.33 192.438 5.94335 + endloop + endfacet + facet normal 0.54335 -0.514952 -0.66302 + outer loop + vertex 878.33 192.438 5.94335 + vertex 878.489 193.642 5.13867 + vertex 878.772 192.861 5.97674 + endloop + endfacet + facet normal 0.576625 -0.46103 -0.674504 + outer loop + vertex 877.514 192.83 4.95245 + vertex 878.018 193.533 4.90308 + vertex 878.138 192.313 5.83979 + endloop + endfacet + facet normal 0.631261 -0.432217 -0.64397 + outer loop + vertex 878.138 192.313 5.83979 + vertex 878.018 193.533 4.90308 + vertex 878.33 192.438 5.94335 + endloop + endfacet + facet normal 0.646343 -0.551089 -0.52777 + outer loop + vertex 878.138 192.313 5.83979 + vertex 878.33 192.438 5.94335 + vertex 878.388 191.655 6.83182 + endloop + endfacet + facet normal 0.700007 -0.512558 -0.497267 + outer loop + vertex 878.388 191.655 6.83182 + vertex 878.33 192.438 5.94335 + vertex 878.569 191.788 6.95007 + endloop + endfacet + facet normal 0.608082 -0.593233 -0.527552 + outer loop + vertex 878.33 192.438 5.94335 + vertex 878.772 192.861 5.97674 + vertex 878.569 191.788 6.95007 + endloop + endfacet + facet normal 0.616927 -0.589427 -0.521514 + outer loop + vertex 878.569 191.788 6.95007 + vertex 878.772 192.861 5.97674 + vertex 879.081 192.322 6.95195 + endloop + endfacet + facet normal 0.597256 -0.462284 -0.655422 + outer loop + vertex 877.157 192.003 5.21094 + vertex 877.514 192.83 4.95245 + vertex 877.721 191.822 5.85222 + endloop + endfacet + facet normal 0.554022 -0.488115 -0.674391 + outer loop + vertex 877.721 191.822 5.85222 + vertex 877.514 192.83 4.95245 + vertex 878.138 192.313 5.83979 + endloop + endfacet + facet normal 0.630893 -0.550243 -0.546998 + outer loop + vertex 877.721 191.822 5.85222 + vertex 878.138 192.313 5.83979 + vertex 878.152 191.554 6.61845 + endloop + endfacet + facet normal 0.685678 -0.51542 -0.513992 + outer loop + vertex 878.152 191.554 6.61845 + vertex 878.138 192.313 5.83979 + vertex 878.388 191.655 6.83182 + endloop + endfacet + facet normal 0.641931 -0.654173 -0.399978 + outer loop + vertex 878.152 191.554 6.61845 + vertex 878.388 191.655 6.83182 + vertex 878.151 190.96 7.58807 + endloop + endfacet + facet normal 0.672367 -0.637899 -0.375511 + outer loop + vertex 878.151 190.96 7.58807 + vertex 878.388 191.655 6.83182 + vertex 878.535 191.214 7.84554 + endloop + endfacet + facet normal 0.649131 -0.711859 -0.268115 + outer loop + vertex 878.151 190.96 7.58807 + vertex 878.535 191.214 7.84554 + vertex 878.292 190.732 8.53582 + endloop + endfacet + facet normal 0.749423 -0.637004 -0.180532 + outer loop + vertex 878.292 190.732 8.53582 + vertex 878.535 191.214 7.84554 + vertex 878.616 191.019 8.86756 + endloop + endfacet + facet normal 0.676024 -0.646658 -0.353307 + outer loop + vertex 878.569 191.788 6.95007 + vertex 879.081 192.322 6.95195 + vertex 878.779 191.451 7.96937 + endloop + endfacet + facet normal 0.68488 -0.641242 -0.346047 + outer loop + vertex 878.779 191.451 7.96937 + vertex 879.081 192.322 6.95195 + vertex 879.344 192.059 7.95908 + endloop + endfacet + facet normal 0.694085 -0.617626 -0.369845 + outer loop + vertex 878.388 191.655 6.83182 + vertex 878.569 191.788 6.95007 + vertex 878.535 191.214 7.84554 + endloop + endfacet + facet normal 0.738165 -0.580222 -0.344171 + outer loop + vertex 878.535 191.214 7.84554 + vertex 878.569 191.788 6.95007 + vertex 878.779 191.451 7.96937 + endloop + endfacet + facet normal 0.731229 -0.657149 -0.182919 + outer loop + vertex 878.535 191.214 7.84554 + vertex 878.779 191.451 7.96937 + vertex 878.616 191.019 8.86756 + endloop + endfacet + facet normal 0.77552 -0.612414 -0.153355 + outer loop + vertex 878.616 191.019 8.86756 + vertex 878.779 191.451 7.96937 + vertex 878.894 191.337 9.00347 + endloop + endfacet + facet normal 0.72302 -0.673384 -0.15426 + outer loop + vertex 878.779 191.451 7.96937 + vertex 879.344 192.059 7.95908 + vertex 878.894 191.337 9.00347 + endloop + endfacet + facet normal 0.720033 -0.675882 -0.157274 + outer loop + vertex 878.894 191.337 9.00347 + vertex 879.344 192.059 7.95908 + vertex 879.447 191.929 8.99258 + endloop + endfacet + facet normal 0.317223 -0.311867 -0.895605 + outer loop + vertex 875.67 196.979 2.53175 + vertex 877.616 198.195 2.79772 + vertex 876.943 194.724 3.76823 + endloop + endfacet + facet normal 0.361448 -0.315362 -0.877441 + outer loop + vertex 876.943 194.724 3.76823 + vertex 877.616 198.195 2.79772 + vertex 878.643 195.958 4.02465 + endloop + endfacet + facet normal 0.48258 -0.405453 -0.776353 + outer loop + vertex 878.489 193.642 5.13867 + vertex 878.018 193.533 4.90308 + vertex 878.643 195.958 4.02465 + endloop + endfacet + facet normal 0.443476 -0.375305 -0.813926 + outer loop + vertex 877.514 192.83 4.95245 + vertex 876.943 194.724 3.76823 + vertex 878.018 193.533 4.90308 + endloop + endfacet + facet normal 0.415391 -0.402432 -0.815781 + outer loop + vertex 876.943 194.724 3.76823 + vertex 878.643 195.958 4.02465 + vertex 878.018 193.533 4.90308 + endloop + endfacet + facet normal 0.173411 -0.137331 -0.975228 + outer loop + vertex 873.524 198.898 1.61255 + vertex 874.519 201.313 1.44936 + vertex 874.803 198.807 1.85274 + endloop + endfacet + facet normal 0.183724 -0.135892 -0.973539 + outer loop + vertex 874.803 198.807 1.85274 + vertex 874.519 201.313 1.44936 + vertex 876.373 200.246 1.94806 + endloop + endfacet + facet normal 0.26253 -0.224157 -0.938526 + outer loop + vertex 874.803 198.807 1.85274 + vertex 876.373 200.246 1.94806 + vertex 875.67 196.979 2.53175 + endloop + endfacet + facet normal 0.268624 -0.225118 -0.93657 + outer loop + vertex 875.67 196.979 2.53175 + vertex 876.373 200.246 1.94806 + vertex 877.616 198.195 2.79772 + endloop + endfacet + facet normal 0.513837 -0.645699 0.56484 + outer loop + vertex 850.618 241.113 42.5087 + vertex 854.117 244.787 43.5262 + vertex 850.228 243.109 45.1458 + endloop + endfacet + facet normal 0.510741 -0.694221 0.50715 + outer loop + vertex 850.228 243.109 45.1458 + vertex 854.117 244.787 43.5262 + vertex 854.072 246.585 46.0335 + endloop + endfacet + facet normal 0.542643 -0.660434 0.519005 + outer loop + vertex 850.618 241.113 42.5087 + vertex 854.625 242.565 40.1675 + vertex 854.117 244.787 43.5262 + endloop + endfacet + facet normal 0.565391 -0.626542 0.536449 + outer loop + vertex 851.251 238.508 38.9851 + vertex 855.558 240.055 36.252 + vertex 854.625 242.565 40.1675 + endloop + endfacet + facet normal 0.549524 -0.531369 0.644725 + outer loop + vertex 855.661 228.508 25.2946 + vertex 857.499 230.942 25.7341 + vertex 854.641 230.563 27.857 + endloop + endfacet + facet normal 0.550532 -0.53619 0.639855 + outer loop + vertex 860.211 233.38 25.4437 + vertex 857.952 234.252 28.1178 + vertex 857.499 230.942 25.7341 + endloop + endfacet + facet normal 0.547858 -0.536992 0.641476 + outer loop + vertex 857.952 234.252 28.1178 + vertex 854.641 230.563 27.857 + vertex 857.499 230.942 25.7341 + endloop + endfacet + facet normal 0.453847 -0.441802 0.773843 + outer loop + vertex 859.779 228.012 22.3309 + vertex 862.152 230.583 22.4074 + vertex 858.454 229.25 23.8152 + endloop + endfacet + facet normal 0.453854 -0.441859 0.773807 + outer loop + vertex 858.454 229.25 23.8152 + vertex 862.152 230.583 22.4074 + vertex 860.887 231.862 23.8796 + endloop + endfacet + facet normal 0.438619 -0.430241 0.78899 + outer loop + vertex 858.117 226.012 22.165 + vertex 859.779 228.012 22.3309 + vertex 856.833 227.158 23.5031 + endloop + endfacet + facet normal 0.439978 -0.456218 0.773489 + outer loop + vertex 856.833 227.158 23.5031 + vertex 859.779 228.012 22.3309 + vertex 858.454 229.25 23.8152 + endloop + endfacet + facet normal 0.277894 -0.272542 0.921138 + outer loop + vertex 862.517 225.194 20.3398 + vertex 864.837 227.649 20.3663 + vertex 861.166 226.744 21.2061 + endloop + endfacet + facet normal 0.278255 -0.274701 0.920388 + outer loop + vertex 861.166 226.744 21.2061 + vertex 864.837 227.649 20.3663 + vertex 863.532 229.268 21.244 + endloop + endfacet + facet normal 0.267917 -0.25953 0.927828 + outer loop + vertex 860.919 223.295 20.27 + vertex 862.517 225.194 20.3398 + vertex 859.467 224.773 21.103 + endloop + endfacet + facet normal 0.26917 -0.28029 0.921404 + outer loop + vertex 859.467 224.773 21.103 + vertex 862.517 225.194 20.3398 + vertex 861.166 226.744 21.2061 + endloop + endfacet + facet normal 0.356718 -0.352828 0.865023 + outer loop + vertex 859.467 224.773 21.103 + vertex 861.166 226.744 21.2061 + vertex 858.117 226.012 22.165 + endloop + endfacet + facet normal 0.358276 -0.369112 0.857551 + outer loop + vertex 858.117 226.012 22.165 + vertex 861.166 226.744 21.2061 + vertex 859.779 228.012 22.3309 + endloop + endfacet + facet normal 0.368416 -0.35828 0.857849 + outer loop + vertex 861.166 226.744 21.2061 + vertex 863.532 229.268 21.244 + vertex 859.779 228.012 22.3309 + endloop + endfacet + facet normal 0.370027 -0.366828 0.853532 + outer loop + vertex 859.779 228.012 22.3309 + vertex 863.532 229.268 21.244 + vertex 862.152 230.583 22.4074 + endloop + endfacet + facet normal 0.129662 -0.11299 0.9851 + outer loop + vertex 865.627 220.865 19.179 + vertex 867.2 223.603 19.2859 + vertex 863.918 223.292 19.6822 + endloop + endfacet + facet normal 0.131013 -0.130173 0.982797 + outer loop + vertex 863.918 223.292 19.6822 + vertex 867.2 223.603 19.2859 + vertex 866.077 225.688 19.7117 + endloop + endfacet + facet normal 0.113774 -0.12568 0.985525 + outer loop + vertex 863.069 218.414 19.1616 + vertex 865.627 220.865 19.179 + vertex 862.348 221.341 19.6182 + endloop + endfacet + facet normal 0.114022 -0.124129 0.985693 + outer loop + vertex 862.348 221.341 19.6182 + vertex 865.627 220.865 19.179 + vertex 863.918 223.292 19.6822 + endloop + endfacet + facet normal 0.188888 -0.183695 0.964664 + outer loop + vertex 862.348 221.341 19.6182 + vertex 863.918 223.292 19.6822 + vertex 860.919 223.295 20.27 + endloop + endfacet + facet normal 0.188497 -0.193988 0.962724 + outer loop + vertex 860.919 223.295 20.27 + vertex 863.918 223.292 19.6822 + vertex 862.517 225.194 20.3398 + endloop + endfacet + facet normal 0.195903 -0.188405 0.962354 + outer loop + vertex 863.918 223.292 19.6822 + vertex 866.077 225.688 19.7117 + vertex 862.517 225.194 20.3398 + endloop + endfacet + facet normal 0.196684 -0.196231 0.960629 + outer loop + vertex 862.517 225.194 20.3398 + vertex 866.077 225.688 19.7117 + vertex 864.837 227.649 20.3663 + endloop + endfacet + facet normal 0.280366 -0.26352 0.923013 + outer loop + vertex 879.705 199.061 15.4946 + vertex 882.365 202.028 15.5334 + vertex 878.629 201.354 16.4759 + endloop + endfacet + facet normal 0.280258 -0.262456 0.923348 + outer loop + vertex 878.629 201.354 16.4759 + vertex 882.365 202.028 15.5334 + vertex 881.425 204.368 16.4841 + endloop + endfacet + facet normal 0.294964 -0.27369 0.915473 + outer loop + vertex 877.767 196.591 15.3806 + vertex 879.705 199.061 15.4946 + vertex 876.677 198.688 16.3588 + endloop + endfacet + facet normal 0.294303 -0.256026 0.92078 + outer loop + vertex 876.677 198.688 16.3588 + vertex 879.705 199.061 15.4946 + vertex 878.629 201.354 16.4759 + endloop + endfacet + facet normal 0.180973 -0.175082 0.967778 + outer loop + vertex 876.677 198.688 16.3588 + vertex 878.629 201.354 16.4759 + vertex 874.858 200.732 17.0686 + endloop + endfacet + facet normal 0.180217 -0.169401 0.96893 + outer loop + vertex 874.858 200.732 17.0686 + vertex 878.629 201.354 16.4759 + vertex 877.613 204.157 17.1551 + endloop + endfacet + facet normal 0.179919 -0.169518 0.968965 + outer loop + vertex 878.629 201.354 16.4759 + vertex 881.425 204.368 16.4841 + vertex 877.613 204.157 17.1551 + endloop + endfacet + facet normal 0.180215 -0.182621 0.966526 + outer loop + vertex 877.613 204.157 17.1551 + vertex 881.425 204.368 16.4841 + vertex 880.806 206.835 17.0657 + endloop + endfacet + facet normal 0.479659 -0.466696 0.743049 + outer loop + vertex 881.403 196.008 13.0664 + vertex 882.843 197.736 13.2227 + vertex 880.321 196.734 14.2206 + endloop + endfacet + facet normal 0.482925 -0.446673 0.753171 + outer loop + vertex 884.714 199.481 13.0574 + vertex 883.153 199.791 14.2422 + vertex 882.843 197.736 13.2227 + endloop + endfacet + facet normal 0.47725 -0.447396 0.756352 + outer loop + vertex 883.153 199.791 14.2422 + vertex 880.321 196.734 14.2206 + vertex 882.843 197.736 13.2227 + endloop + endfacet + facet normal 0.495056 -0.484006 0.721566 + outer loop + vertex 878.938 193.445 13.0615 + vertex 879.919 194.683 13.2189 + vertex 878.305 194.417 14.1474 + endloop + endfacet + facet normal 0.485956 -0.458712 0.743929 + outer loop + vertex 881.403 196.008 13.0664 + vertex 880.321 196.734 14.2206 + vertex 879.919 194.683 13.2189 + endloop + endfacet + facet normal 0.499006 -0.457424 0.736041 + outer loop + vertex 880.321 196.734 14.2206 + vertex 878.305 194.417 14.1474 + vertex 879.919 194.683 13.2189 + endloop + endfacet + facet normal 0.400561 -0.374926 0.836051 + outer loop + vertex 878.305 194.417 14.1474 + vertex 880.321 196.734 14.2206 + vertex 877.767 196.591 15.3806 + endloop + endfacet + facet normal 0.402871 -0.355038 0.843589 + outer loop + vertex 877.767 196.591 15.3806 + vertex 880.321 196.734 14.2206 + vertex 879.705 199.061 15.4946 + endloop + endfacet + facet normal 0.384976 -0.362587 0.848719 + outer loop + vertex 880.321 196.734 14.2206 + vertex 883.153 199.791 14.2422 + vertex 879.705 199.061 15.4946 + endloop + endfacet + facet normal 0.384654 -0.35612 0.851598 + outer loop + vertex 879.705 199.061 15.4946 + vertex 883.153 199.791 14.2422 + vertex 882.365 202.028 15.5334 + endloop + endfacet + facet normal 0.729997 -0.682921 0.0269118 + outer loop + vertex 883.595 196.188 8.90851 + vertex 885.335 198.048 8.91873 + vertex 883.492 196.12 9.97646 + endloop + endfacet + facet normal 0.7286 -0.684605 0.0214096 + outer loop + vertex 883.492 196.12 9.97646 + vertex 885.335 198.048 8.91873 + vertex 885.245 197.985 9.982 + endloop + endfacet + facet normal 0.720823 -0.692464 0.0301278 + outer loop + vertex 881.916 194.44 8.91037 + vertex 883.595 196.188 8.90851 + vertex 881.812 194.379 9.98145 + endloop + endfacet + facet normal 0.719475 -0.694062 0.0251933 + outer loop + vertex 881.812 194.379 9.98145 + vertex 883.595 196.188 8.90851 + vertex 883.492 196.12 9.97646 + endloop + endfacet + facet normal 0.699246 -0.673934 0.238473 + outer loop + vertex 881.812 194.379 9.98145 + vertex 883.492 196.12 9.97646 + vertex 881.635 194.583 11.08 + endloop + endfacet + facet normal 0.698916 -0.674988 0.236448 + outer loop + vertex 881.635 194.583 11.08 + vertex 883.492 196.12 9.97646 + vertex 883.31 196.316 11.0738 + endloop + endfacet + facet normal 0.707815 -0.665715 0.236267 + outer loop + vertex 883.492 196.12 9.97646 + vertex 885.245 197.985 9.982 + vertex 883.31 196.316 11.0738 + endloop + endfacet + facet normal 0.706683 -0.669764 0.22807 + outer loop + vertex 883.31 196.316 11.0738 + vertex 885.245 197.985 9.982 + vertex 885.068 198.17 11.0747 + endloop + endfacet + facet normal 0.713401 -0.699776 0.037047 + outer loop + vertex 880.47 192.968 8.94108 + vertex 881.916 194.44 8.91037 + vertex 880.383 192.936 10.01 + endloop + endfacet + facet normal 0.710536 -0.703082 0.0285333 + outer loop + vertex 880.383 192.936 10.01 + vertex 881.916 194.44 8.91037 + vertex 881.812 194.379 9.98145 + endloop + endfacet + facet normal 0.712864 -0.699989 0.0429047 + outer loop + vertex 879.447 191.929 8.99258 + vertex 880.47 192.968 8.94108 + vertex 879.388 191.933 10.0544 + endloop + endfacet + facet normal 0.709764 -0.703485 0.0366423 + outer loop + vertex 879.388 191.933 10.0544 + vertex 880.47 192.968 8.94108 + vertex 880.383 192.936 10.01 + endloop + endfacet + facet normal 0.693573 -0.678274 0.242695 + outer loop + vertex 879.388 191.933 10.0544 + vertex 880.383 192.936 10.01 + vertex 879.215 192.144 11.1359 + endloop + endfacet + facet normal 0.692538 -0.680192 0.240272 + outer loop + vertex 879.215 192.144 11.1359 + vertex 880.383 192.936 10.01 + vertex 880.206 193.141 11.1027 + endloop + endfacet + facet normal 0.692095 -0.680638 0.240283 + outer loop + vertex 880.383 192.936 10.01 + vertex 881.812 194.379 9.98145 + vertex 880.206 193.141 11.1027 + endloop + endfacet + facet normal 0.691711 -0.681593 0.238677 + outer loop + vertex 880.206 193.141 11.1027 + vertex 881.812 194.379 9.98145 + vertex 881.635 194.583 11.08 + endloop + endfacet + facet normal 0.646177 -0.633538 0.42554 + outer loop + vertex 880.206 193.141 11.1027 + vertex 881.635 194.583 11.08 + vertex 880.033 193.686 12.1755 + endloop + endfacet + facet normal 0.646648 -0.631425 0.427959 + outer loop + vertex 880.033 193.686 12.1755 + vertex 881.635 194.583 11.08 + vertex 881.461 195.138 12.1611 + endloop + endfacet + facet normal 0.650228 -0.632115 0.421467 + outer loop + vertex 879.215 192.144 11.1359 + vertex 880.206 193.141 11.1027 + vertex 879.012 192.64 12.1935 + endloop + endfacet + facet normal 0.651405 -0.62911 0.424136 + outer loop + vertex 879.012 192.64 12.1935 + vertex 880.206 193.141 11.1027 + vertex 880.033 193.686 12.1755 + endloop + endfacet + facet normal 0.589963 -0.566487 0.575357 + outer loop + vertex 879.012 192.64 12.1935 + vertex 880.033 193.686 12.1755 + vertex 878.938 193.445 13.0615 + endloop + endfacet + facet normal 0.595911 -0.546918 0.588023 + outer loop + vertex 878.938 193.445 13.0615 + vertex 880.033 193.686 12.1755 + vertex 879.919 194.683 13.2189 + endloop + endfacet + facet normal 0.574846 -0.559157 0.597407 + outer loop + vertex 880.033 193.686 12.1755 + vertex 881.461 195.138 12.1611 + vertex 879.919 194.683 13.2189 + endloop + endfacet + facet normal 0.571858 -0.572968 0.5871 + outer loop + vertex 879.919 194.683 13.2189 + vertex 881.461 195.138 12.1611 + vertex 881.403 196.008 13.0664 + endloop + endfacet + facet normal 0.657557 -0.623307 0.423211 + outer loop + vertex 883.31 196.316 11.0738 + vertex 885.068 198.17 11.0747 + vertex 883.103 196.833 12.1572 + endloop + endfacet + facet normal 0.657503 -0.624063 0.422179 + outer loop + vertex 883.103 196.833 12.1572 + vertex 885.068 198.17 11.0747 + vertex 884.851 198.673 12.1545 + endloop + endfacet + facet normal 0.650874 -0.627855 0.426803 + outer loop + vertex 881.635 194.583 11.08 + vertex 883.31 196.316 11.0738 + vertex 881.461 195.138 12.1611 + endloop + endfacet + facet normal 0.650685 -0.629404 0.424805 + outer loop + vertex 881.461 195.138 12.1611 + vertex 883.31 196.316 11.0738 + vertex 883.103 196.833 12.1572 + endloop + endfacet + facet normal 0.585257 -0.565665 0.580946 + outer loop + vertex 881.461 195.138 12.1611 + vertex 883.103 196.833 12.1572 + vertex 881.403 196.008 13.0664 + endloop + endfacet + facet normal 0.585492 -0.542166 0.602707 + outer loop + vertex 881.403 196.008 13.0664 + vertex 883.103 196.833 12.1572 + vertex 882.843 197.736 13.2227 + endloop + endfacet + facet normal 0.577438 -0.547719 0.605449 + outer loop + vertex 883.103 196.833 12.1572 + vertex 884.851 198.673 12.1545 + vertex 882.843 197.736 13.2227 + endloop + endfacet + facet normal 0.57716 -0.563072 0.59147 + outer loop + vertex 882.843 197.736 13.2227 + vertex 884.851 198.673 12.1545 + vertex 884.714 199.481 13.0574 + endloop + endfacet + facet normal 0.520839 -0.497194 -0.69392 + outer loop + vertex 882.224 197.833 4.96649 + vertex 883.927 199.426 5.10325 + vertex 882.841 197.185 5.89366 + endloop + endfacet + facet normal 0.543765 -0.501021 -0.673273 + outer loop + vertex 882.841 197.185 5.89366 + vertex 883.927 199.426 5.10325 + vertex 884.601 199.082 5.90376 + endloop + endfacet + facet normal 0.551539 -0.498444 -0.668849 + outer loop + vertex 880.57 195.798 5.11918 + vertex 882.224 197.833 4.96649 + vertex 881.135 195.368 5.90576 + endloop + endfacet + facet normal 0.522765 -0.495263 -0.693853 + outer loop + vertex 881.135 195.368 5.90576 + vertex 882.224 197.833 4.96649 + vertex 882.841 197.185 5.89366 + endloop + endfacet + facet normal 0.614994 -0.580757 -0.533388 + outer loop + vertex 881.135 195.368 5.90576 + vertex 882.841 197.185 5.89366 + vertex 881.605 194.986 6.86268 + endloop + endfacet + facet normal 0.613677 -0.580708 -0.534956 + outer loop + vertex 881.605 194.986 6.86268 + vertex 882.841 197.185 5.89366 + vertex 883.312 196.793 6.86061 + endloop + endfacet + facet normal 0.620599 -0.573057 -0.535222 + outer loop + vertex 882.841 197.185 5.89366 + vertex 884.601 199.082 5.90376 + vertex 883.312 196.793 6.86061 + endloop + endfacet + facet normal 0.615502 -0.572764 -0.541386 + outer loop + vertex 883.312 196.793 6.86061 + vertex 884.601 199.082 5.90376 + vertex 885.057 198.655 6.87407 + endloop + endfacet + facet normal 0.503937 -0.515563 -0.692995 + outer loop + vertex 879.37 194.786 4.99922 + vertex 880.57 195.798 5.11918 + vertex 879.712 193.851 5.94306 + endloop + endfacet + facet normal 0.534592 -0.518296 -0.667518 + outer loop + vertex 879.712 193.851 5.94306 + vertex 880.57 195.798 5.11918 + vertex 881.135 195.368 5.90576 + endloop + endfacet + facet normal 0.554441 -0.507357 -0.659685 + outer loop + vertex 878.489 193.642 5.13867 + vertex 879.37 194.786 4.99922 + vertex 878.772 192.861 5.97674 + endloop + endfacet + facet normal 0.512566 -0.510099 -0.690706 + outer loop + vertex 878.772 192.861 5.97674 + vertex 879.37 194.786 4.99922 + vertex 879.712 193.851 5.94306 + endloop + endfacet + facet normal 0.60927 -0.596191 -0.522826 + outer loop + vertex 878.772 192.861 5.97674 + vertex 879.712 193.851 5.94306 + vertex 879.081 192.322 6.95195 + endloop + endfacet + facet normal 0.608042 -0.596439 -0.523971 + outer loop + vertex 879.081 192.322 6.95195 + vertex 879.712 193.851 5.94306 + vertex 880.122 193.429 6.90047 + endloop + endfacet + facet normal 0.614557 -0.589833 -0.523848 + outer loop + vertex 879.712 193.851 5.94306 + vertex 881.135 195.368 5.90576 + vertex 880.122 193.429 6.90047 + endloop + endfacet + facet normal 0.606358 -0.590199 -0.532912 + outer loop + vertex 880.122 193.429 6.90047 + vertex 881.135 195.368 5.90576 + vertex 881.605 194.986 6.86268 + endloop + endfacet + facet normal 0.671479 -0.647988 -0.359481 + outer loop + vertex 880.122 193.429 6.90047 + vertex 881.605 194.986 6.86268 + vertex 880.399 193.159 7.90491 + endloop + endfacet + facet normal 0.663354 -0.649529 -0.371583 + outer loop + vertex 880.399 193.159 7.90491 + vertex 881.605 194.986 6.86268 + vertex 881.869 194.679 7.87234 + endloop + endfacet + facet normal 0.675206 -0.651358 -0.346164 + outer loop + vertex 879.081 192.322 6.95195 + vertex 880.122 193.429 6.90047 + vertex 879.344 192.059 7.95908 + endloop + endfacet + facet normal 0.664233 -0.655415 -0.359479 + outer loop + vertex 879.344 192.059 7.95908 + vertex 880.122 193.429 6.90047 + vertex 880.399 193.159 7.90491 + endloop + endfacet + facet normal 0.708458 -0.687925 -0.157629 + outer loop + vertex 879.344 192.059 7.95908 + vertex 880.399 193.159 7.90491 + vertex 879.447 191.929 8.99258 + endloop + endfacet + facet normal 0.696975 -0.69519 -0.175889 + outer loop + vertex 879.447 191.929 8.99258 + vertex 880.399 193.159 7.90491 + vertex 880.47 192.968 8.94108 + endloop + endfacet + facet normal 0.70586 -0.686425 -0.174882 + outer loop + vertex 880.399 193.159 7.90491 + vertex 881.869 194.679 7.87234 + vertex 880.47 192.968 8.94108 + endloop + endfacet + facet normal 0.698515 -0.689896 -0.190056 + outer loop + vertex 880.47 192.968 8.94108 + vertex 881.869 194.679 7.87234 + vertex 881.916 194.44 8.91037 + endloop + endfacet + facet normal 0.675953 -0.630558 -0.381423 + outer loop + vertex 883.312 196.793 6.86061 + vertex 885.057 198.655 6.87407 + vertex 883.555 196.441 7.87216 + endloop + endfacet + facet normal 0.677668 -0.630436 -0.378572 + outer loop + vertex 883.555 196.441 7.87216 + vertex 885.057 198.655 6.87407 + vertex 885.287 198.295 7.88595 + endloop + endfacet + facet normal 0.674618 -0.638125 -0.371061 + outer loop + vertex 881.605 194.986 6.86268 + vertex 883.312 196.793 6.86061 + vertex 881.869 194.679 7.87234 + endloop + endfacet + facet normal 0.667697 -0.638776 -0.38229 + outer loop + vertex 881.869 194.679 7.87234 + vertex 883.312 196.793 6.86061 + vertex 883.555 196.441 7.87216 + endloop + endfacet + facet normal 0.709706 -0.678942 -0.18803 + outer loop + vertex 881.869 194.679 7.87234 + vertex 883.555 196.441 7.87216 + vertex 881.916 194.44 8.91037 + endloop + endfacet + facet normal 0.707425 -0.67983 -0.193345 + outer loop + vertex 881.916 194.44 8.91037 + vertex 883.555 196.441 7.87216 + vertex 883.595 196.188 8.90851 + endloop + endfacet + facet normal 0.717876 -0.669403 -0.191191 + outer loop + vertex 883.555 196.441 7.87216 + vertex 885.287 198.295 7.88595 + vertex 883.595 196.188 8.90851 + endloop + endfacet + facet normal 0.717133 -0.669682 -0.192994 + outer loop + vertex 883.595 196.188 8.90851 + vertex 885.287 198.295 7.88595 + vertex 885.335 198.048 8.91873 + endloop + endfacet + facet normal 0.350923 -0.3188 -0.880465 + outer loop + vertex 879.709 200.114 2.9129 + vertex 882.458 203.098 2.92838 + vertex 880.914 198.242 4.07122 + endloop + endfacet + facet normal 0.346568 -0.317897 -0.882515 + outer loop + vertex 880.914 198.242 4.07122 + vertex 882.458 203.098 2.92838 + vertex 884.048 201.676 4.06508 + endloop + endfacet + facet normal 0.345795 -0.324229 -0.880512 + outer loop + vertex 877.616 198.195 2.79772 + vertex 879.709 200.114 2.9129 + vertex 878.643 195.958 4.02465 + endloop + endfacet + facet normal 0.343805 -0.323954 -0.881392 + outer loop + vertex 878.643 195.958 4.02465 + vertex 879.709 200.114 2.9129 + vertex 880.914 198.242 4.07122 + endloop + endfacet + facet normal 0.423766 -0.406673 -0.809345 + outer loop + vertex 880.57 195.798 5.11918 + vertex 879.37 194.786 4.99922 + vertex 880.914 198.242 4.07122 + endloop + endfacet + facet normal 0.413166 -0.416854 -0.809646 + outer loop + vertex 878.489 193.642 5.13867 + vertex 878.643 195.958 4.02465 + vertex 879.37 194.786 4.99922 + endloop + endfacet + facet normal 0.4261 -0.407302 -0.807802 + outer loop + vertex 878.643 195.958 4.02465 + vertex 880.914 198.242 4.07122 + vertex 879.37 194.786 4.99922 + endloop + endfacet + facet normal 0.435701 -0.39638 -0.808114 + outer loop + vertex 883.927 199.426 5.10325 + vertex 882.224 197.833 4.96649 + vertex 884.048 201.676 4.06508 + endloop + endfacet + facet normal 0.425583 -0.406547 -0.808454 + outer loop + vertex 880.57 195.798 5.11918 + vertex 880.914 198.242 4.07122 + vertex 882.224 197.833 4.96649 + endloop + endfacet + facet normal 0.431124 -0.394946 -0.811264 + outer loop + vertex 880.914 198.242 4.07122 + vertex 884.048 201.676 4.06508 + vertex 882.224 197.833 4.96649 + endloop + endfacet + facet normal 0.161999 -0.154589 -0.974607 + outer loop + vertex 876.835 204.467 1.41458 + vertex 879.271 206.327 1.52456 + vertex 878.368 202.094 2.04587 + endloop + endfacet + facet normal 0.177951 -0.157591 -0.971339 + outer loop + vertex 878.368 202.094 2.04587 + vertex 879.271 206.327 1.52456 + vertex 880.85 204.734 2.07212 + endloop + endfacet + facet normal 0.179745 -0.142696 -0.973309 + outer loop + vertex 874.519 201.313 1.44936 + vertex 876.835 204.467 1.41458 + vertex 876.373 200.246 1.94806 + endloop + endfacet + facet normal 0.179851 -0.142705 -0.973288 + outer loop + vertex 876.373 200.246 1.94806 + vertex 876.835 204.467 1.41458 + vertex 878.368 202.094 2.04587 + endloop + endfacet + facet normal 0.259793 -0.23092 -0.937648 + outer loop + vertex 876.373 200.246 1.94806 + vertex 878.368 202.094 2.04587 + vertex 877.616 198.195 2.79772 + endloop + endfacet + facet normal 0.263792 -0.23145 -0.9364 + outer loop + vertex 877.616 198.195 2.79772 + vertex 878.368 202.094 2.04587 + vertex 879.709 200.114 2.9129 + endloop + endfacet + facet normal 0.25948 -0.234559 -0.936831 + outer loop + vertex 878.368 202.094 2.04587 + vertex 880.85 204.734 2.07212 + vertex 879.709 200.114 2.9129 + endloop + endfacet + facet normal 0.259907 -0.234639 -0.936693 + outer loop + vertex 879.709 200.114 2.9129 + vertex 880.85 204.734 2.07212 + vertex 882.458 203.098 2.92838 + endloop + endfacet + facet normal 0.116333 -0.0939309 -0.988759 + outer loop + vertex 879.271 206.327 1.52456 + vertex 876.835 204.467 1.41458 + vertex 878.775 211.498 0.974893 + endloop + endfacet + facet normal 0.107661 -0.0899589 -0.990109 + outer loop + vertex 874.519 201.313 1.44936 + vertex 873.717 206.265 0.912235 + vertex 876.835 204.467 1.41458 + endloop + endfacet + facet normal 0.106829 -0.0913908 -0.990068 + outer loop + vertex 873.717 206.265 0.912235 + vertex 878.775 211.498 0.974893 + vertex 876.835 204.467 1.41458 + endloop + endfacet + facet normal 0.565678 -0.665219 0.487331 + outer loop + vertex 854.117 244.787 43.5262 + vertex 859.198 249.571 44.1585 + vertex 854.072 246.585 46.0335 + endloop + endfacet + facet normal 0.566656 -0.699968 0.434678 + outer loop + vertex 854.072 246.585 46.0335 + vertex 859.198 249.571 44.1585 + vertex 859.794 251.509 46.5029 + endloop + endfacet + facet normal 0.578992 -0.636954 0.508977 + outer loop + vertex 854.625 242.565 40.1675 + vertex 859.496 247.537 40.8491 + vertex 854.117 244.787 43.5262 + endloop + endfacet + facet normal 0.575448 -0.672667 0.465165 + outer loop + vertex 854.117 244.787 43.5262 + vertex 859.496 247.537 40.8491 + vertex 859.198 249.571 44.1585 + endloop + endfacet + facet normal 0.586643 -0.642296 0.49326 + outer loop + vertex 854.625 242.565 40.1675 + vertex 860.453 245.387 36.9104 + vertex 859.496 247.537 40.8491 + endloop + endfacet + facet normal 0.556203 -0.52781 0.641915 + outer loop + vertex 860.211 233.38 25.4437 + vertex 862.807 236.525 25.7798 + vertex 857.952 234.252 28.1178 + endloop + endfacet + facet normal 0.564895 -0.528384 0.633801 + outer loop + vertex 866.183 239.643 25.3705 + vertex 863.762 240.484 28.2298 + vertex 862.807 236.525 25.7798 + endloop + endfacet + facet normal 0.556318 -0.530103 0.639923 + outer loop + vertex 863.762 240.484 28.2298 + vertex 857.952 234.252 28.1178 + vertex 862.807 236.525 25.7798 + endloop + endfacet + facet normal 0.465008 -0.433183 0.772088 + outer loop + vertex 864.973 233.559 22.4107 + vertex 867.914 236.74 22.4238 + vertex 863.729 234.844 23.8809 + endloop + endfacet + facet normal 0.464821 -0.432305 0.772692 + outer loop + vertex 863.729 234.844 23.8809 + vertex 867.914 236.74 22.4238 + vertex 866.724 238.047 23.8705 + endloop + endfacet + facet normal 0.459395 -0.436266 0.77371 + outer loop + vertex 862.152 230.583 22.4074 + vertex 864.973 233.559 22.4107 + vertex 860.887 231.862 23.8796 + endloop + endfacet + facet normal 0.459775 -0.438442 0.772254 + outer loop + vertex 860.887 231.862 23.8796 + vertex 864.973 233.559 22.4107 + vertex 863.729 234.844 23.8809 + endloop + endfacet + facet normal 0.283425 -0.269112 0.920461 + outer loop + vertex 867.706 230.629 20.3648 + vertex 870.739 233.881 20.3814 + vertex 866.382 232.257 21.2482 + endloop + endfacet + facet normal 0.281824 -0.263724 0.92251 + outer loop + vertex 866.382 232.257 21.2482 + vertex 870.739 233.881 20.3814 + vertex 869.343 235.462 21.2599 + endloop + endfacet + facet normal 0.282319 -0.271301 0.920159 + outer loop + vertex 864.837 227.649 20.3663 + vertex 867.706 230.629 20.3648 + vertex 863.532 229.268 21.244 + endloop + endfacet + facet normal 0.282062 -0.270265 0.920542 + outer loop + vertex 863.532 229.268 21.244 + vertex 867.706 230.629 20.3648 + vertex 866.382 232.257 21.2482 + endloop + endfacet + facet normal 0.376421 -0.360161 0.853575 + outer loop + vertex 863.532 229.268 21.244 + vertex 866.382 232.257 21.2482 + vertex 862.152 230.583 22.4074 + endloop + endfacet + facet normal 0.375619 -0.356958 0.855272 + outer loop + vertex 862.152 230.583 22.4074 + vertex 866.382 232.257 21.2482 + vertex 864.973 233.559 22.4107 + endloop + endfacet + facet normal 0.379037 -0.353279 0.855292 + outer loop + vertex 866.382 232.257 21.2482 + vertex 869.343 235.462 21.2599 + vertex 864.973 233.559 22.4107 + endloop + endfacet + facet normal 0.379336 -0.3543 0.854737 + outer loop + vertex 864.973 233.559 22.4107 + vertex 869.343 235.462 21.2599 + vertex 867.914 236.74 22.4238 + endloop + endfacet + facet normal 0.12974 -0.120209 0.984234 + outer loop + vertex 870.322 226.363 19.2574 + vertex 872.813 229.693 19.3357 + vertex 868.883 228.613 19.7219 + endloop + endfacet + facet normal 0.132153 -0.12953 0.98273 + outer loop + vertex 868.883 228.613 19.7219 + vertex 872.813 229.693 19.3357 + vertex 871.962 231.888 19.7396 + endloop + endfacet + facet normal 0.126335 -0.132748 0.983065 + outer loop + vertex 867.2 223.603 19.2859 + vertex 870.322 226.363 19.2574 + vertex 866.077 225.688 19.7117 + endloop + endfacet + facet normal 0.124982 -0.123298 0.984468 + outer loop + vertex 866.077 225.688 19.7117 + vertex 870.322 226.363 19.2574 + vertex 868.883 228.613 19.7219 + endloop + endfacet + facet normal 0.199314 -0.194505 0.960438 + outer loop + vertex 866.077 225.688 19.7117 + vertex 868.883 228.613 19.7219 + vertex 864.837 227.649 20.3663 + endloop + endfacet + facet normal 0.19854 -0.190631 0.961375 + outer loop + vertex 864.837 227.649 20.3663 + vertex 868.883 228.613 19.7219 + vertex 867.706 230.629 20.3648 + endloop + endfacet + facet normal 0.197777 -0.191098 0.96144 + outer loop + vertex 868.883 228.613 19.7219 + vertex 871.962 231.888 19.7396 + vertex 867.706 230.629 20.3648 + endloop + endfacet + facet normal 0.197204 -0.188889 0.961994 + outer loop + vertex 867.706 230.629 20.3648 + vertex 871.962 231.888 19.7396 + vertex 870.739 233.881 20.3814 + endloop + endfacet + facet normal 0.289695 -0.261493 0.920705 + outer loop + vertex 885.556 205.456 15.5238 + vertex 888.944 209.194 15.5197 + vertex 884.579 207.73 16.4774 + endloop + endfacet + facet normal 0.290022 -0.262774 0.920238 + outer loop + vertex 884.579 207.73 16.4774 + vertex 888.944 209.194 15.5197 + vertex 887.932 211.444 16.4811 + endloop + endfacet + facet normal 0.283216 -0.261061 0.922841 + outer loop + vertex 882.365 202.028 15.5334 + vertex 885.556 205.456 15.5238 + vertex 881.425 204.368 16.4841 + endloop + endfacet + facet normal 0.283834 -0.264425 0.921693 + outer loop + vertex 881.425 204.368 16.4841 + vertex 885.556 205.456 15.5238 + vertex 884.579 207.73 16.4774 + endloop + endfacet + facet normal 0.192893 -0.179019 0.964751 + outer loop + vertex 881.425 204.368 16.4841 + vertex 884.579 207.73 16.4774 + vertex 880.806 206.835 17.0657 + endloop + endfacet + facet normal 0.190035 -0.16496 0.96782 + outer loop + vertex 880.806 206.835 17.0657 + vertex 884.579 207.73 16.4774 + vertex 883.487 210.379 17.1433 + endloop + endfacet + facet normal 0.184393 -0.167452 0.968483 + outer loop + vertex 884.579 207.73 16.4774 + vertex 887.932 211.444 16.4811 + vertex 883.487 210.379 17.1433 + endloop + endfacet + facet normal 0.186895 -0.179553 0.965832 + outer loop + vertex 883.487 210.379 17.1433 + vertex 887.932 211.444 16.4811 + vertex 887.143 213.831 17.0775 + endloop + endfacet + facet normal 0.485629 -0.442837 0.753698 + outer loop + vertex 888.237 203.277 13.0546 + vertex 889.763 205.219 13.2121 + vertex 886.448 203.331 14.2387 + endloop + endfacet + facet normal 0.49852 -0.433105 0.750932 + outer loop + vertex 891.699 207.175 13.0554 + vertex 889.879 207.124 14.2343 + vertex 889.763 205.219 13.2121 + endloop + endfacet + facet normal 0.483538 -0.436406 0.758776 + outer loop + vertex 889.879 207.124 14.2343 + vertex 886.448 203.331 14.2387 + vertex 889.763 205.219 13.2121 + endloop + endfacet + facet normal 0.479161 -0.455226 0.750449 + outer loop + vertex 884.714 199.481 13.0574 + vertex 886.258 201.365 13.2144 + vertex 883.153 199.791 14.2422 + endloop + endfacet + facet normal 0.486391 -0.440232 0.754731 + outer loop + vertex 888.237 203.277 13.0546 + vertex 886.448 203.331 14.2387 + vertex 886.258 201.365 13.2144 + endloop + endfacet + facet normal 0.475801 -0.442138 0.760346 + outer loop + vertex 886.448 203.331 14.2387 + vertex 883.153 199.791 14.2422 + vertex 886.258 201.365 13.2144 + endloop + endfacet + facet normal 0.383893 -0.356496 0.851784 + outer loop + vertex 883.153 199.791 14.2422 + vertex 886.448 203.331 14.2387 + vertex 882.365 202.028 15.5334 + endloop + endfacet + facet normal 0.3836 -0.354701 0.852666 + outer loop + vertex 882.365 202.028 15.5334 + vertex 886.448 203.331 14.2387 + vertex 885.556 205.456 15.5238 + endloop + endfacet + facet normal 0.389618 -0.351361 0.851319 + outer loop + vertex 886.448 203.331 14.2387 + vertex 889.879 207.124 14.2343 + vertex 885.556 205.456 15.5238 + endloop + endfacet + facet normal 0.389838 -0.352311 0.850825 + outer loop + vertex 885.556 205.456 15.5238 + vertex 889.879 207.124 14.2343 + vertex 888.944 209.194 15.5197 + endloop + endfacet + facet normal 0.752573 -0.658444 0.00920704 + outer loop + vertex 890.477 203.754 8.93127 + vertex 892.165 205.683 8.93205 + vertex 890.441 203.727 9.99128 + endloop + endfacet + facet normal 0.752465 -0.658574 0.00879115 + outer loop + vertex 890.441 203.727 9.99128 + vertex 892.165 205.683 8.93205 + vertex 892.135 205.663 9.99334 + endloop + endfacet + facet normal 0.748222 -0.663301 0.0140031 + outer loop + vertex 888.775 201.834 8.92994 + vertex 890.477 203.754 8.93127 + vertex 888.723 201.797 9.98952 + endloop + endfacet + facet normal 0.746886 -0.664893 0.00884307 + outer loop + vertex 888.723 201.797 9.98952 + vertex 890.477 203.754 8.93127 + vertex 890.441 203.727 9.99128 + endloop + endfacet + facet normal 0.728844 -0.649023 0.218071 + outer loop + vertex 888.723 201.797 9.98952 + vertex 890.441 203.727 9.99128 + vertex 888.587 202.01 11.0772 + endloop + endfacet + facet normal 0.728309 -0.650928 0.214146 + outer loop + vertex 888.587 202.01 11.0772 + vertex 890.441 203.727 9.99128 + vertex 890.325 203.955 11.0791 + endloop + endfacet + facet normal 0.735066 -0.643563 0.213318 + outer loop + vertex 890.441 203.727 9.99128 + vertex 892.135 205.663 9.99334 + vertex 890.325 203.955 11.0791 + endloop + endfacet + facet normal 0.734828 -0.6444 0.211606 + outer loop + vertex 890.325 203.955 11.0791 + vertex 892.135 205.663 9.99334 + vertex 892.03 205.9 11.0817 + endloop + endfacet + facet normal 0.74226 -0.669841 0.0190246 + outer loop + vertex 887.062 199.935 8.92689 + vertex 888.775 201.834 8.92994 + vertex 886.99 199.886 9.9872 + endloop + endfacet + facet normal 0.740804 -0.671589 0.0133426 + outer loop + vertex 886.99 199.886 9.9872 + vertex 888.775 201.834 8.92994 + vertex 888.723 201.797 9.98952 + endloop + endfacet + facet normal 0.737528 -0.674934 0.0227388 + outer loop + vertex 885.335 198.048 8.91873 + vertex 887.062 199.935 8.92689 + vertex 885.245 197.985 9.982 + endloop + endfacet + facet normal 0.736413 -0.676284 0.0183232 + outer loop + vertex 885.245 197.985 9.982 + vertex 887.062 199.935 8.92689 + vertex 886.99 199.886 9.9872 + endloop + endfacet + facet normal 0.716871 -0.658912 0.227883 + outer loop + vertex 885.245 197.985 9.982 + vertex 886.99 199.886 9.9872 + vertex 885.068 198.17 11.0747 + endloop + endfacet + facet normal 0.7159 -0.662432 0.220615 + outer loop + vertex 885.068 198.17 11.0747 + vertex 886.99 199.886 9.9872 + vertex 886.832 200.078 11.0762 + endloop + endfacet + facet normal 0.72254 -0.655284 0.220315 + outer loop + vertex 886.99 199.886 9.9872 + vertex 888.723 201.797 9.98952 + vertex 886.832 200.078 11.0762 + endloop + endfacet + facet normal 0.722314 -0.656094 0.218639 + outer loop + vertex 886.832 200.078 11.0762 + vertex 888.723 201.797 9.98952 + vertex 888.587 202.01 11.0772 + endloop + endfacet + facet normal 0.674615 -0.61288 0.411427 + outer loop + vertex 886.832 200.078 11.0762 + vertex 888.587 202.01 11.0772 + vertex 886.62 200.567 12.1528 + endloop + endfacet + facet normal 0.674501 -0.615406 0.407829 + outer loop + vertex 886.62 200.567 12.1528 + vertex 888.587 202.01 11.0772 + vertex 888.394 202.51 12.1511 + endloop + endfacet + facet normal 0.665929 -0.616359 0.420285 + outer loop + vertex 885.068 198.17 11.0747 + vertex 886.832 200.078 11.0762 + vertex 884.851 198.673 12.1545 + endloop + endfacet + facet normal 0.665671 -0.621238 0.413455 + outer loop + vertex 884.851 198.673 12.1545 + vertex 886.832 200.078 11.0762 + vertex 886.62 200.567 12.1528 + endloop + endfacet + facet normal 0.593 -0.553223 0.585061 + outer loop + vertex 884.851 198.673 12.1545 + vertex 886.62 200.567 12.1528 + vertex 884.714 199.481 13.0574 + endloop + endfacet + facet normal 0.591319 -0.534919 0.603492 + outer loop + vertex 884.714 199.481 13.0574 + vertex 886.62 200.567 12.1528 + vertex 886.258 201.365 13.2144 + endloop + endfacet + facet normal 0.58877 -0.536967 0.604165 + outer loop + vertex 886.62 200.567 12.1528 + vertex 888.394 202.51 12.1511 + vertex 886.258 201.365 13.2144 + endloop + endfacet + facet normal 0.590013 -0.562088 0.579604 + outer loop + vertex 886.258 201.365 13.2144 + vertex 888.394 202.51 12.1511 + vertex 888.237 203.277 13.0546 + endloop + endfacet + facet normal 0.688645 -0.604175 0.400924 + outer loop + vertex 890.325 203.955 11.0791 + vertex 892.03 205.9 11.0817 + vertex 890.147 204.465 12.1527 + endloop + endfacet + facet normal 0.688583 -0.605431 0.399132 + outer loop + vertex 890.147 204.465 12.1527 + vertex 892.03 205.9 11.0817 + vertex 891.859 206.415 12.1555 + endloop + endfacet + facet normal 0.681259 -0.609077 0.406092 + outer loop + vertex 888.587 202.01 11.0772 + vertex 890.325 203.955 11.0791 + vertex 888.394 202.51 12.1511 + endloop + endfacet + facet normal 0.681161 -0.61122 0.403027 + outer loop + vertex 888.394 202.51 12.1511 + vertex 890.325 203.955 11.0791 + vertex 890.147 204.465 12.1527 + endloop + endfacet + facet normal 0.610716 -0.548188 0.571416 + outer loop + vertex 888.394 202.51 12.1511 + vertex 890.147 204.465 12.1527 + vertex 888.237 203.277 13.0546 + endloop + endfacet + facet normal 0.607951 -0.526097 0.594657 + outer loop + vertex 888.237 203.277 13.0546 + vertex 890.147 204.465 12.1527 + vertex 889.763 205.219 13.2121 + endloop + endfacet + facet normal 0.602909 -0.530445 0.595927 + outer loop + vertex 890.147 204.465 12.1527 + vertex 891.859 206.415 12.1555 + vertex 889.763 205.219 13.2121 + endloop + endfacet + facet normal 0.604383 -0.551989 0.574482 + outer loop + vertex 889.763 205.219 13.2121 + vertex 891.859 206.415 12.1555 + vertex 891.699 207.175 13.0554 + endloop + endfacet + facet normal 0.532952 -0.477447 -0.698575 + outer loop + vertex 889.019 205.367 4.97355 + vertex 890.652 206.981 5.11692 + vertex 889.662 204.701 5.91918 + endloop + endfacet + facet normal 0.551305 -0.47978 -0.68255 + outer loop + vertex 889.662 204.701 5.91918 + vertex 890.652 206.981 5.11692 + vertex 891.317 206.604 5.91884 + endloop + endfacet + facet normal 0.555857 -0.476218 -0.681351 + outer loop + vertex 887.346 203.21 5.1166 + vertex 889.019 205.367 4.97355 + vertex 887.998 202.823 5.91909 + endloop + endfacet + facet normal 0.535771 -0.474505 -0.698423 + outer loop + vertex 887.998 202.823 5.91909 + vertex 889.019 205.367 4.97355 + vertex 889.662 204.701 5.91918 + endloop + endfacet + facet normal 0.630524 -0.558436 -0.539063 + outer loop + vertex 887.998 202.823 5.91909 + vertex 889.662 204.701 5.91918 + vertex 888.443 202.388 6.89064 + endloop + endfacet + facet normal 0.627775 -0.558363 -0.542337 + outer loop + vertex 888.443 202.388 6.89064 + vertex 889.662 204.701 5.91918 + vertex 890.126 204.28 6.88964 + endloop + endfacet + facet normal 0.633825 -0.551551 -0.542271 + outer loop + vertex 889.662 204.701 5.91918 + vertex 891.317 206.604 5.91884 + vertex 890.126 204.28 6.88964 + endloop + endfacet + facet normal 0.632945 -0.551535 -0.543313 + outer loop + vertex 890.126 204.28 6.88964 + vertex 891.317 206.604 5.91884 + vertex 891.795 206.196 6.88923 + endloop + endfacet + facet normal 0.527967 -0.487569 -0.695362 + outer loop + vertex 885.67 201.602 4.97132 + vertex 887.346 203.21 5.1166 + vertex 886.318 200.959 5.91492 + endloop + endfacet + facet normal 0.545642 -0.490105 -0.679759 + outer loop + vertex 886.318 200.959 5.91492 + vertex 887.346 203.21 5.1166 + vertex 887.998 202.823 5.91909 + endloop + endfacet + facet normal 0.554752 -0.485344 -0.675789 + outer loop + vertex 883.927 199.426 5.10325 + vertex 885.67 201.602 4.97132 + vertex 884.601 199.082 5.90376 + endloop + endfacet + facet normal 0.532298 -0.483017 -0.695236 + outer loop + vertex 884.601 199.082 5.90376 + vertex 885.67 201.602 4.97132 + vertex 886.318 200.959 5.91492 + endloop + endfacet + facet normal 0.621855 -0.565893 -0.541351 + outer loop + vertex 884.601 199.082 5.90376 + vertex 886.318 200.959 5.91492 + vertex 885.057 198.655 6.87407 + endloop + endfacet + facet normal 0.622634 -0.56593 -0.540417 + outer loop + vertex 885.057 198.655 6.87407 + vertex 886.318 200.959 5.91492 + vertex 886.761 200.518 6.88644 + endloop + endfacet + facet normal 0.625741 -0.562587 -0.540318 + outer loop + vertex 886.318 200.959 5.91492 + vertex 887.998 202.823 5.91909 + vertex 886.761 200.518 6.88644 + endloop + endfacet + facet normal 0.626693 -0.56262 -0.53918 + outer loop + vertex 886.761 200.518 6.88644 + vertex 887.998 202.823 5.91909 + vertex 888.443 202.388 6.89064 + endloop + endfacet + facet normal 0.68853 -0.618615 -0.378474 + outer loop + vertex 886.761 200.518 6.88644 + vertex 888.443 202.388 6.89064 + vertex 886.999 200.165 7.89619 + endloop + endfacet + facet normal 0.688417 -0.618626 -0.378661 + outer loop + vertex 886.999 200.165 7.89619 + vertex 888.443 202.388 6.89064 + vertex 888.695 202.05 7.89977 + endloop + endfacet + facet normal 0.684478 -0.623579 -0.377676 + outer loop + vertex 885.057 198.655 6.87407 + vertex 886.761 200.518 6.88644 + vertex 885.287 198.295 7.88595 + endloop + endfacet + facet normal 0.683633 -0.623652 -0.379083 + outer loop + vertex 885.287 198.295 7.88595 + vertex 886.761 200.518 6.88644 + vertex 886.999 200.165 7.89619 + endloop + endfacet + facet normal 0.724523 -0.662106 -0.191527 + outer loop + vertex 885.287 198.295 7.88595 + vertex 886.999 200.165 7.89619 + vertex 885.335 198.048 8.91873 + endloop + endfacet + facet normal 0.724521 -0.662106 -0.191532 + outer loop + vertex 885.335 198.048 8.91873 + vertex 886.999 200.165 7.89619 + vertex 887.062 199.935 8.92689 + endloop + endfacet + facet normal 0.729971 -0.656368 -0.190587 + outer loop + vertex 886.999 200.165 7.89619 + vertex 888.695 202.05 7.89977 + vertex 887.062 199.935 8.92689 + endloop + endfacet + facet normal 0.728407 -0.656996 -0.19437 + outer loop + vertex 887.062 199.935 8.92689 + vertex 888.695 202.05 7.89977 + vertex 888.775 201.834 8.92994 + endloop + endfacet + facet normal 0.698644 -0.608737 -0.375946 + outer loop + vertex 890.126 204.28 6.88964 + vertex 891.795 206.196 6.88923 + vertex 890.389 203.958 7.89984 + endloop + endfacet + facet normal 0.696581 -0.608983 -0.379362 + outer loop + vertex 890.389 203.958 7.89984 + vertex 891.795 206.196 6.88923 + vertex 892.07 205.882 7.89946 + endloop + endfacet + facet normal 0.691729 -0.61513 -0.378321 + outer loop + vertex 888.443 202.388 6.89064 + vertex 890.126 204.28 6.88964 + vertex 888.695 202.05 7.89977 + endloop + endfacet + facet normal 0.692865 -0.615006 -0.376439 + outer loop + vertex 888.695 202.05 7.89977 + vertex 890.126 204.28 6.88964 + vertex 890.389 203.958 7.89984 + endloop + endfacet + facet normal 0.733727 -0.651284 -0.193583 + outer loop + vertex 888.695 202.05 7.89977 + vertex 890.389 203.958 7.89984 + vertex 888.775 201.834 8.92994 + endloop + endfacet + facet normal 0.734477 -0.650974 -0.19177 + outer loop + vertex 888.775 201.834 8.92994 + vertex 890.389 203.958 7.89984 + vertex 890.477 203.754 8.93127 + endloop + endfacet + facet normal 0.738993 -0.646019 -0.191178 + outer loop + vertex 890.389 203.958 7.89984 + vertex 892.07 205.882 7.89946 + vertex 890.477 203.754 8.93127 + endloop + endfacet + facet normal 0.738638 -0.64617 -0.192038 + outer loop + vertex 890.477 203.754 8.93127 + vertex 892.07 205.882 7.89946 + vertex 892.165 205.683 8.93205 + endloop + endfacet + facet normal 0.356891 -0.305138 -0.882904 + outer loop + vertex 885.661 206.76 2.90866 + vertex 888.938 210.624 2.89766 + vertex 887.398 205.458 4.06067 + endloop + endfacet + facet normal 0.353974 -0.304577 -0.884271 + outer loop + vertex 887.398 205.458 4.06067 + vertex 888.938 210.624 2.89766 + vertex 890.677 209.273 4.05905 + endloop + endfacet + facet normal 0.351568 -0.31232 -0.882528 + outer loop + vertex 882.458 203.098 2.92838 + vertex 885.661 206.76 2.90866 + vertex 884.048 201.676 4.06508 + endloop + endfacet + facet normal 0.351358 -0.312275 -0.882628 + outer loop + vertex 884.048 201.676 4.06508 + vertex 885.661 206.76 2.90866 + vertex 887.398 205.458 4.06067 + endloop + endfacet + facet normal 0.443561 -0.389475 -0.807195 + outer loop + vertex 887.346 203.21 5.1166 + vertex 885.67 201.602 4.97132 + vertex 887.398 205.458 4.06067 + endloop + endfacet + facet normal 0.433957 -0.396656 -0.808916 + outer loop + vertex 883.927 199.426 5.10325 + vertex 884.048 201.676 4.06508 + vertex 885.67 201.602 4.97132 + endloop + endfacet + facet normal 0.436215 -0.387364 -0.812198 + outer loop + vertex 884.048 201.676 4.06508 + vertex 887.398 205.458 4.06067 + vertex 885.67 201.602 4.97132 + endloop + endfacet + facet normal 0.445629 -0.379064 -0.811002 + outer loop + vertex 890.652 206.981 5.11692 + vertex 889.019 205.367 4.97355 + vertex 890.677 209.273 4.05905 + endloop + endfacet + facet normal 0.434987 -0.391096 -0.811067 + outer loop + vertex 887.346 203.21 5.1166 + vertex 887.398 205.458 4.06067 + vertex 889.019 205.367 4.97355 + endloop + endfacet + facet normal 0.43844 -0.377136 -0.815806 + outer loop + vertex 887.398 205.458 4.06067 + vertex 890.677 209.273 4.05905 + vertex 889.019 205.367 4.97355 + endloop + endfacet + facet normal 0.163547 -0.149702 -0.975111 + outer loop + vertex 881.959 210.145 1.44 + vertex 885.051 213.138 1.49915 + vertex 883.838 208.178 2.05711 + endloop + endfacet + facet normal 0.175931 -0.152441 -0.972528 + outer loop + vertex 883.838 208.178 2.05711 + vertex 885.051 213.138 1.49915 + vertex 887.035 212.004 2.03584 + endloop + endfacet + facet normal 0.184301 -0.15124 -0.971164 + outer loop + vertex 879.271 206.327 1.52456 + vertex 881.959 210.145 1.44 + vertex 880.85 204.734 2.07212 + endloop + endfacet + facet normal 0.165484 -0.147839 -0.975069 + outer loop + vertex 880.85 204.734 2.07212 + vertex 881.959 210.145 1.44 + vertex 883.838 208.178 2.05711 + endloop + endfacet + facet normal 0.262605 -0.231943 -0.936611 + outer loop + vertex 880.85 204.734 2.07212 + vertex 883.838 208.178 2.05711 + vertex 882.458 203.098 2.92838 + endloop + endfacet + facet normal 0.258292 -0.231016 -0.938039 + outer loop + vertex 882.458 203.098 2.92838 + vertex 883.838 208.178 2.05711 + vertex 885.661 206.76 2.90866 + endloop + endfacet + facet normal 0.263014 -0.22503 -0.938182 + outer loop + vertex 883.838 208.178 2.05711 + vertex 887.035 212.004 2.03584 + vertex 885.661 206.76 2.90866 + endloop + endfacet + facet normal 0.261978 -0.224816 -0.938523 + outer loop + vertex 885.661 206.76 2.90866 + vertex 887.035 212.004 2.03584 + vertex 888.938 210.624 2.89766 + endloop + endfacet + facet normal 0.103955 -0.0878247 -0.990697 + outer loop + vertex 885.051 213.138 1.49915 + vertex 881.959 210.145 1.44 + vertex 884.207 218.134 0.967703 + endloop + endfacet + facet normal 0.104142 -0.0952336 -0.989992 + outer loop + vertex 879.271 206.327 1.52456 + vertex 878.775 211.498 0.974893 + vertex 881.959 210.145 1.44 + endloop + endfacet + facet normal 0.106984 -0.0886536 -0.9903 + outer loop + vertex 878.775 211.498 0.974893 + vertex 884.207 218.134 0.967703 + vertex 881.959 210.145 1.44 + endloop + endfacet + facet normal 0.575927 -0.500019 0.646753 + outer loop + vertex 872.089 245.816 24.9389 + vertex 869.906 245.592 26.7095 + vertex 868.898 242.771 25.4259 + endloop + endfacet + facet normal 0.575896 -0.511128 0.638037 + outer loop + vertex 866.183 239.643 25.3705 + vertex 868.898 242.771 25.4259 + vertex 863.762 240.484 28.2298 + endloop + endfacet + facet normal 0.575779 -0.500024 0.64688 + outer loop + vertex 868.898 242.771 25.4259 + vertex 869.906 245.592 26.7095 + vertex 863.762 240.484 28.2298 + endloop + endfacet + facet normal 0.47323 -0.415375 0.776864 + outer loop + vertex 870.808 240.002 22.4597 + vertex 873.635 243.319 22.5111 + vertex 869.696 241.291 23.8261 + endloop + endfacet + facet normal 0.470245 -0.404808 0.784219 + outer loop + vertex 869.696 241.291 23.8261 + vertex 873.635 243.319 22.5111 + vertex 872.58 244.55 23.7793 + endloop + endfacet + facet normal 0.470972 -0.426283 0.772313 + outer loop + vertex 867.914 236.74 22.4238 + vertex 870.808 240.002 22.4597 + vertex 866.724 238.047 23.8705 + endloop + endfacet + facet normal 0.469266 -0.419178 0.777225 + outer loop + vertex 866.724 238.047 23.8705 + vertex 870.808 240.002 22.4597 + vertex 869.696 241.291 23.8261 + endloop + endfacet + facet normal 0.286555 -0.261522 0.921679 + outer loop + vertex 873.674 237.207 20.4287 + vertex 876.463 240.554 20.5113 + vertex 872.215 238.733 21.3151 + endloop + endfacet + facet normal 0.287497 -0.264185 0.920626 + outer loop + vertex 872.215 238.733 21.3151 + vertex 876.463 240.554 20.5113 + vertex 874.99 242.051 21.4009 + endloop + endfacet + facet normal 0.282919 -0.262728 0.922459 + outer loop + vertex 870.739 233.881 20.3814 + vertex 873.674 237.207 20.4287 + vertex 869.343 235.462 21.2599 + endloop + endfacet + facet normal 0.283501 -0.264497 0.921775 + outer loop + vertex 869.343 235.462 21.2599 + vertex 873.674 237.207 20.4287 + vertex 872.215 238.733 21.3151 + endloop + endfacet + facet normal 0.382751 -0.350519 0.854774 + outer loop + vertex 869.343 235.462 21.2599 + vertex 872.215 238.733 21.3151 + vertex 867.914 236.74 22.4238 + endloop + endfacet + facet normal 0.382042 -0.348311 0.855993 + outer loop + vertex 867.914 236.74 22.4238 + vertex 872.215 238.733 21.3151 + vertex 870.808 240.002 22.4597 + endloop + endfacet + facet normal 0.38551 -0.344468 0.855993 + outer loop + vertex 872.215 238.733 21.3151 + vertex 874.99 242.051 21.4009 + vertex 870.808 240.002 22.4597 + endloop + endfacet + facet normal 0.38422 -0.340771 0.85805 + outer loop + vertex 870.808 240.002 22.4597 + vertex 874.99 242.051 21.4009 + vertex 873.635 243.319 22.5111 + endloop + endfacet + facet normal 0.126581 -0.120707 0.984585 + outer loop + vertex 876.36 233.01 19.3324 + vertex 878.872 236.575 19.4466 + vertex 874.997 235.28 19.786 + endloop + endfacet + facet normal 0.129984 -0.131358 0.982776 + outer loop + vertex 874.997 235.28 19.786 + vertex 878.872 236.575 19.4466 + vertex 877.868 238.688 19.8618 + endloop + endfacet + facet normal 0.124807 -0.132485 0.983296 + outer loop + vertex 872.813 229.693 19.3357 + vertex 876.36 233.01 19.3324 + vertex 871.962 231.888 19.7396 + endloop + endfacet + facet normal 0.122568 -0.123158 0.984789 + outer loop + vertex 871.962 231.888 19.7396 + vertex 876.36 233.01 19.3324 + vertex 874.997 235.28 19.786 + endloop + endfacet + facet normal 0.196714 -0.189202 0.962032 + outer loop + vertex 871.962 231.888 19.7396 + vertex 874.997 235.28 19.786 + vertex 870.739 233.881 20.3814 + endloop + endfacet + facet normal 0.19594 -0.186558 0.962706 + outer loop + vertex 870.739 233.881 20.3814 + vertex 874.997 235.28 19.786 + vertex 873.674 237.207 20.4287 + endloop + endfacet + facet normal 0.195994 -0.18652 0.962703 + outer loop + vertex 874.997 235.28 19.786 + vertex 877.868 238.688 19.8618 + vertex 873.674 237.207 20.4287 + endloop + endfacet + facet normal 0.196234 -0.187271 0.962508 + outer loop + vertex 873.674 237.207 20.4287 + vertex 877.868 238.688 19.8618 + vertex 876.463 240.554 20.5113 + endloop + endfacet + facet normal 0.303471 -0.257235 0.917462 + outer loop + vertex 892.35 213.129 15.5303 + vertex 895.714 217.192 15.5567 + vertex 891.306 215.355 16.4999 + endloop + endfacet + facet normal 0.302849 -0.25537 0.918188 + outer loop + vertex 891.306 215.355 16.4999 + vertex 895.714 217.192 15.5567 + vertex 894.644 219.401 16.5239 + endloop + endfacet + facet normal 0.296679 -0.259292 0.919102 + outer loop + vertex 888.944 209.194 15.5197 + vertex 892.35 213.129 15.5303 + vertex 887.932 211.444 16.4811 + endloop + endfacet + facet normal 0.297102 -0.260703 0.918567 + outer loop + vertex 887.932 211.444 16.4811 + vertex 892.35 213.129 15.5303 + vertex 891.306 215.355 16.4999 + endloop + endfacet + facet normal 0.198064 -0.175493 0.964351 + outer loop + vertex 887.932 211.444 16.4811 + vertex 891.306 215.355 16.4999 + vertex 887.143 213.831 17.0775 + endloop + endfacet + facet normal 0.194445 -0.164604 0.967004 + outer loop + vertex 887.143 213.831 17.0775 + vertex 891.306 215.355 16.4999 + vertex 889.945 217.796 17.1889 + endloop + endfacet + facet normal 0.193316 -0.165265 0.967117 + outer loop + vertex 891.306 215.355 16.4999 + vertex 894.644 219.401 16.5239 + vertex 889.945 217.796 17.1889 + endloop + endfacet + facet normal 0.198439 -0.181935 0.963079 + outer loop + vertex 889.945 217.796 17.1889 + vertex 894.644 219.401 16.5239 + vertex 893.724 221.669 17.142 + endloop + endfacet + facet normal 0.509307 -0.428346 0.746409 + outer loop + vertex 895.01 211.054 13.0654 + vertex 896.445 213.04 13.2261 + vertex 893.264 211.027 14.2417 + endloop + endfacet + facet normal 0.521107 -0.420398 0.742774 + outer loop + vertex 898.316 215.094 13.076 + vertex 896.609 215.064 14.2566 + vertex 896.445 213.04 13.2261 + endloop + endfacet + facet normal 0.507423 -0.423264 0.750579 + outer loop + vertex 896.609 215.064 14.2566 + vertex 893.264 211.027 14.2417 + vertex 896.445 213.04 13.2261 + endloop + endfacet + facet normal 0.497702 -0.436474 0.749522 + outer loop + vertex 891.699 207.175 13.0554 + vertex 893.148 209.102 13.2154 + vertex 889.879 207.124 14.2343 + endloop + endfacet + facet normal 0.509269 -0.428495 0.746349 + outer loop + vertex 895.01 211.054 13.0654 + vertex 893.264 211.027 14.2417 + vertex 893.148 209.102 13.2154 + endloop + endfacet + facet normal 0.495957 -0.431524 0.753534 + outer loop + vertex 893.264 211.027 14.2417 + vertex 889.879 207.124 14.2343 + vertex 893.148 209.102 13.2154 + endloop + endfacet + facet normal 0.398512 -0.347202 0.848905 + outer loop + vertex 889.879 207.124 14.2343 + vertex 893.264 211.027 14.2417 + vertex 888.944 209.194 15.5197 + endloop + endfacet + facet normal 0.398529 -0.347267 0.84887 + outer loop + vertex 888.944 209.194 15.5197 + vertex 893.264 211.027 14.2417 + vertex 892.35 213.129 15.5303 + endloop + endfacet + facet normal 0.408375 -0.34154 0.846511 + outer loop + vertex 893.264 211.027 14.2417 + vertex 896.609 215.064 14.2566 + vertex 892.35 213.129 15.5303 + endloop + endfacet + facet normal 0.409176 -0.344293 0.845007 + outer loop + vertex 892.35 213.129 15.5303 + vertex 896.609 215.064 14.2566 + vertex 895.714 217.192 15.5567 + endloop + endfacet + facet normal 0.775389 -0.631436 0.00781116 + outer loop + vertex 897.103 211.519 8.9341 + vertex 898.763 213.557 8.93465 + vertex 897.07 211.491 9.99825 + endloop + endfacet + facet normal 0.775633 -0.631122 0.00881009 + outer loop + vertex 897.07 211.491 9.99825 + vertex 898.763 213.557 8.93465 + vertex 898.727 213.527 9.99973 + endloop + endfacet + facet normal 0.769492 -0.638514 0.0134375 + outer loop + vertex 895.466 209.546 8.9333 + vertex 897.103 211.519 8.9341 + vertex 895.434 209.529 9.99713 + endloop + endfacet + facet normal 0.767945 -0.640474 0.00734017 + outer loop + vertex 895.434 209.529 9.99713 + vertex 897.103 211.519 8.9341 + vertex 897.07 211.491 9.99825 + endloop + endfacet + facet normal 0.751536 -0.626903 0.205392 + outer loop + vertex 895.434 209.529 9.99713 + vertex 897.07 211.491 9.99825 + vertex 895.327 209.758 11.0874 + endloop + endfacet + facet normal 0.751999 -0.625212 0.208823 + outer loop + vertex 895.327 209.758 11.0874 + vertex 897.07 211.491 9.99825 + vertex 896.956 211.719 11.0899 + endloop + endfacet + facet normal 0.758646 -0.617444 0.207893 + outer loop + vertex 897.07 211.491 9.99825 + vertex 898.727 213.527 9.99973 + vertex 896.956 211.719 11.0899 + endloop + endfacet + facet normal 0.758468 -0.618154 0.206427 + outer loop + vertex 896.956 211.719 11.0899 + vertex 898.727 213.527 9.99973 + vertex 898.611 213.75 11.0922 + endloop + endfacet + facet normal 0.762849 -0.646466 0.011979 + outer loop + vertex 893.827 207.611 8.93277 + vertex 895.466 209.546 8.9333 + vertex 893.797 207.596 9.99539 + endloop + endfacet + facet normal 0.763145 -0.646093 0.013128 + outer loop + vertex 893.797 207.596 9.99539 + vertex 895.466 209.546 8.9333 + vertex 895.434 209.529 9.99713 + endloop + endfacet + facet normal 0.757477 -0.652799 0.00903657 + outer loop + vertex 892.165 205.683 8.93205 + vertex 893.827 207.611 8.93277 + vertex 892.135 205.663 9.99334 + endloop + endfacet + facet normal 0.758188 -0.651929 0.0117688 + outer loop + vertex 892.135 205.663 9.99334 + vertex 893.827 207.611 8.93277 + vertex 893.797 207.596 9.99539 + endloop + endfacet + facet normal 0.741113 -0.637459 0.210704 + outer loop + vertex 892.135 205.663 9.99334 + vertex 893.797 207.596 9.99539 + vertex 892.03 205.9 11.0817 + endloop + endfacet + facet normal 0.741108 -0.637477 0.210669 + outer loop + vertex 892.03 205.9 11.0817 + vertex 893.797 207.596 9.99539 + vertex 893.692 207.834 11.0844 + endloop + endfacet + facet normal 0.746119 -0.631855 0.209918 + outer loop + vertex 893.797 207.596 9.99539 + vertex 895.434 209.529 9.99713 + vertex 893.692 207.834 11.0844 + endloop + endfacet + facet normal 0.745596 -0.633685 0.206229 + outer loop + vertex 893.692 207.834 11.0844 + vertex 895.434 209.529 9.99713 + vertex 895.327 209.758 11.0874 + endloop + endfacet + facet normal 0.70027 -0.595473 0.393744 + outer loop + vertex 893.692 207.834 11.0844 + vertex 895.327 209.758 11.0874 + vertex 893.525 208.347 12.1589 + endloop + endfacet + facet normal 0.700387 -0.5933 0.396803 + outer loop + vertex 893.525 208.347 12.1589 + vertex 895.327 209.758 11.0874 + vertex 895.157 210.277 12.1629 + endloop + endfacet + facet normal 0.695674 -0.598675 0.397022 + outer loop + vertex 892.03 205.9 11.0817 + vertex 893.692 207.834 11.0844 + vertex 891.859 206.415 12.1555 + endloop + endfacet + facet normal 0.695603 -0.59998 0.39517 + outer loop + vertex 891.859 206.415 12.1555 + vertex 893.692 207.834 11.0844 + vertex 893.525 208.347 12.1589 + endloop + endfacet + facet normal 0.623822 -0.538446 0.5665 + outer loop + vertex 891.859 206.415 12.1555 + vertex 893.525 208.347 12.1589 + vertex 891.699 207.175 13.0554 + endloop + endfacet + facet normal 0.620954 -0.515903 0.590136 + outer loop + vertex 891.699 207.175 13.0554 + vertex 893.525 208.347 12.1589 + vertex 893.148 209.102 13.2154 + endloop + endfacet + facet normal 0.614811 -0.521314 0.59181 + outer loop + vertex 893.525 208.347 12.1589 + vertex 895.157 210.277 12.1629 + vertex 893.148 209.102 13.2154 + endloop + endfacet + facet normal 0.616341 -0.544281 0.569106 + outer loop + vertex 893.148 209.102 13.2154 + vertex 895.157 210.277 12.1629 + vertex 895.01 211.054 13.0654 + endloop + endfacet + facet normal 0.712468 -0.58089 0.393645 + outer loop + vertex 896.956 211.719 11.0899 + vertex 898.611 213.75 11.0922 + vertex 896.788 212.243 12.1667 + endloop + endfacet + facet normal 0.712488 -0.579896 0.395071 + outer loop + vertex 896.788 212.243 12.1667 + vertex 898.611 213.75 11.0922 + vertex 898.444 214.278 12.1697 + endloop + endfacet + facet normal 0.706321 -0.587483 0.394936 + outer loop + vertex 895.327 209.758 11.0874 + vertex 896.956 211.719 11.0899 + vertex 895.157 210.277 12.1629 + endloop + endfacet + facet normal 0.706342 -0.586977 0.395651 + outer loop + vertex 895.157 210.277 12.1629 + vertex 896.956 211.719 11.0899 + vertex 896.788 212.243 12.1667 + endloop + endfacet + facet normal 0.637019 -0.529764 0.559962 + outer loop + vertex 895.157 210.277 12.1629 + vertex 896.788 212.243 12.1667 + vertex 895.01 211.054 13.0654 + endloop + endfacet + facet normal 0.633682 -0.505205 0.585845 + outer loop + vertex 895.01 211.054 13.0654 + vertex 896.788 212.243 12.1667 + vertex 896.445 213.04 13.2261 + endloop + endfacet + facet normal 0.62719 -0.510816 0.587963 + outer loop + vertex 896.788 212.243 12.1667 + vertex 898.444 214.278 12.1697 + vertex 896.445 213.04 13.2261 + endloop + endfacet + facet normal 0.629068 -0.531566 0.567196 + outer loop + vertex 896.445 213.04 13.2261 + vertex 898.444 214.278 12.1697 + vertex 898.316 215.094 13.076 + endloop + endfacet + facet normal 0.544904 -0.453604 -0.705211 + outer loop + vertex 895.487 213.037 4.97251 + vertex 897.091 214.743 5.11362 + vertex 896.18 212.398 5.91857 + endloop + endfacet + facet normal 0.567025 -0.455661 -0.686189 + outer loop + vertex 896.18 212.398 5.91857 + vertex 897.091 214.743 5.11362 + vertex 897.804 214.419 5.91878 + endloop + endfacet + facet normal 0.56811 -0.451944 -0.687748 + outer loop + vertex 893.887 210.805 5.11707 + vertex 895.487 213.037 4.97251 + vertex 894.57 210.443 5.91886 + endloop + endfacet + facet normal 0.547262 -0.450905 -0.705117 + outer loop + vertex 894.57 210.443 5.91886 + vertex 895.487 213.037 4.97251 + vertex 896.18 212.398 5.91857 + endloop + endfacet + facet normal 0.644964 -0.531363 -0.549249 + outer loop + vertex 894.57 210.443 5.91886 + vertex 896.18 212.398 5.91857 + vertex 895.072 210.05 6.88836 + endloop + endfacet + facet normal 0.644213 -0.531369 -0.550125 + outer loop + vertex 895.072 210.05 6.88836 + vertex 896.18 212.398 5.91857 + vertex 896.695 212.017 6.88846 + endloop + endfacet + facet normal 0.650819 -0.523021 -0.550349 + outer loop + vertex 896.18 212.398 5.91857 + vertex 897.804 214.419 5.91878 + vertex 896.695 212.017 6.88846 + endloop + endfacet + facet normal 0.648418 -0.523044 -0.553154 + outer loop + vertex 896.695 212.017 6.88846 + vertex 897.804 214.419 5.91878 + vertex 898.338 214.054 6.88897 + endloop + endfacet + facet normal 0.540229 -0.466413 -0.700436 + outer loop + vertex 892.287 209.168 4.97308 + vertex 893.887 210.805 5.11707 + vertex 892.953 208.518 5.91944 + endloop + endfacet + facet normal 0.557195 -0.468206 -0.685797 + outer loop + vertex 892.953 208.518 5.91944 + vertex 893.887 210.805 5.11707 + vertex 894.57 210.443 5.91886 + endloop + endfacet + facet normal 0.561823 -0.464894 -0.684272 + outer loop + vertex 890.652 206.981 5.11692 + vertex 892.287 209.168 4.97308 + vertex 891.317 206.604 5.91884 + endloop + endfacet + facet normal 0.542788 -0.463613 -0.700317 + outer loop + vertex 891.317 206.604 5.91884 + vertex 892.287 209.168 4.97308 + vertex 892.953 208.518 5.91944 + endloop + endfacet + facet normal 0.638312 -0.545292 -0.543336 + outer loop + vertex 891.317 206.604 5.91884 + vertex 892.953 208.518 5.91944 + vertex 891.795 206.196 6.88923 + endloop + endfacet + facet normal 0.637003 -0.545283 -0.544879 + outer loop + vertex 891.795 206.196 6.88923 + vertex 892.953 208.518 5.91944 + vertex 893.442 208.12 6.88926 + endloop + endfacet + facet normal 0.641966 -0.539364 -0.544946 + outer loop + vertex 892.953 208.518 5.91944 + vertex 894.57 210.443 5.91886 + vertex 893.442 208.12 6.88926 + endloop + endfacet + facet normal 0.638406 -0.539372 -0.549104 + outer loop + vertex 893.442 208.12 6.88926 + vertex 894.57 210.443 5.91886 + vertex 895.072 210.05 6.88836 + endloop + endfacet + facet normal 0.706087 -0.596447 -0.381696 + outer loop + vertex 893.442 208.12 6.88926 + vertex 895.072 210.05 6.88836 + vertex 893.726 207.809 7.8996 + endloop + endfacet + facet normal 0.706089 -0.596447 -0.381692 + outer loop + vertex 893.726 207.809 7.8996 + vertex 895.072 210.05 6.88836 + vertex 895.361 209.746 7.89967 + endloop + endfacet + facet normal 0.703038 -0.601814 -0.378888 + outer loop + vertex 891.795 206.196 6.88923 + vertex 893.442 208.12 6.88926 + vertex 892.07 205.882 7.89946 + endloop + endfacet + facet normal 0.701128 -0.60206 -0.382025 + outer loop + vertex 892.07 205.882 7.89946 + vertex 893.442 208.12 6.88926 + vertex 893.726 207.809 7.8996 + endloop + endfacet + facet normal 0.744654 -0.63945 -0.191295 + outer loop + vertex 892.07 205.882 7.89946 + vertex 893.726 207.809 7.8996 + vertex 892.165 205.683 8.93205 + endloop + endfacet + facet normal 0.742941 -0.640195 -0.195419 + outer loop + vertex 892.165 205.683 8.93205 + vertex 893.726 207.809 7.8996 + vertex 893.827 207.611 8.93277 + endloop + endfacet + facet normal 0.74931 -0.632965 -0.194652 + outer loop + vertex 893.726 207.809 7.8996 + vertex 895.361 209.746 7.89967 + vertex 893.827 207.611 8.93277 + endloop + endfacet + facet normal 0.747779 -0.633638 -0.198316 + outer loop + vertex 893.827 207.611 8.93277 + vertex 895.361 209.746 7.89967 + vertex 895.466 209.546 8.9333 + endloop + endfacet + facet normal 0.718267 -0.579445 -0.385145 + outer loop + vertex 896.695 212.017 6.88846 + vertex 898.338 214.054 6.88897 + vertex 896.996 211.719 7.89984 + endloop + endfacet + facet normal 0.71581 -0.579783 -0.389188 + outer loop + vertex 896.996 211.719 7.89984 + vertex 898.338 214.054 6.88897 + vertex 898.651 213.761 7.90033 + endloop + endfacet + facet normal 0.713164 -0.588254 -0.381254 + outer loop + vertex 895.072 210.05 6.88836 + vertex 896.695 212.017 6.88846 + vertex 895.361 209.746 7.89967 + endloop + endfacet + facet normal 0.710539 -0.588627 -0.385555 + outer loop + vertex 895.361 209.746 7.89967 + vertex 896.695 212.017 6.88846 + vertex 896.996 211.719 7.89984 + endloop + endfacet + facet normal 0.754908 -0.625402 -0.19745 + outer loop + vertex 895.361 209.746 7.89967 + vertex 896.996 211.719 7.89984 + vertex 895.466 209.546 8.9333 + endloop + endfacet + facet normal 0.754181 -0.625724 -0.199202 + outer loop + vertex 895.466 209.546 8.9333 + vertex 896.996 211.719 7.89984 + vertex 897.103 211.519 8.9341 + endloop + endfacet + facet normal 0.761623 -0.616942 -0.198277 + outer loop + vertex 896.996 211.719 7.89984 + vertex 898.651 213.761 7.90033 + vertex 897.103 211.519 8.9341 + endloop + endfacet + facet normal 0.759041 -0.618065 -0.20458 + outer loop + vertex 897.103 211.519 8.9341 + vertex 898.651 213.761 7.90033 + vertex 898.763 213.557 8.93465 + endloop + endfacet + facet normal 0.362403 -0.284214 -0.88763 + outer loop + vertex 892.111 214.501 2.90229 + vertex 895.198 218.428 2.90525 + vertex 893.869 213.127 4.06002 + endloop + endfacet + facet normal 0.357385 -0.283451 -0.889905 + outer loop + vertex 893.869 213.127 4.06002 + vertex 895.198 218.428 2.90525 + vertex 897.023 217.101 4.06077 + endloop + endfacet + facet normal 0.361625 -0.294886 -0.88446 + outer loop + vertex 888.938 210.624 2.89766 + vertex 892.111 214.501 2.90229 + vertex 890.677 209.273 4.05905 + endloop + endfacet + facet normal 0.354914 -0.293731 -0.887557 + outer loop + vertex 890.677 209.273 4.05905 + vertex 892.111 214.501 2.90229 + vertex 893.869 213.127 4.06002 + endloop + endfacet + facet normal 0.449082 -0.367297 -0.814505 + outer loop + vertex 893.887 210.805 5.11707 + vertex 892.287 209.168 4.97308 + vertex 893.869 213.127 4.06002 + endloop + endfacet + facet normal 0.437625 -0.380644 -0.814613 + outer loop + vertex 890.652 206.981 5.11692 + vertex 890.677 209.273 4.05905 + vertex 892.287 209.168 4.97308 + endloop + endfacet + facet normal 0.441418 -0.365394 -0.819535 + outer loop + vertex 890.677 209.273 4.05905 + vertex 893.869 213.127 4.06002 + vertex 892.287 209.168 4.97308 + endloop + endfacet + facet normal 0.448632 -0.353601 -0.82079 + outer loop + vertex 897.091 214.743 5.11362 + vertex 895.487 213.037 4.97251 + vertex 897.023 217.101 4.06077 + endloop + endfacet + facet normal 0.440749 -0.369066 -0.818248 + outer loop + vertex 893.887 210.805 5.11707 + vertex 893.869 213.127 4.06002 + vertex 895.487 213.037 4.97251 + endloop + endfacet + facet normal 0.44457 -0.352653 -0.823403 + outer loop + vertex 893.869 213.127 4.06002 + vertex 897.023 217.101 4.06077 + vertex 895.487 213.037 4.97251 + endloop + endfacet + facet normal 0.168939 -0.138822 -0.975801 + outer loop + vertex 888.016 217.622 1.40918 + vertex 891.162 220.918 1.48483 + vertex 890.203 215.915 2.03047 + endloop + endfacet + facet normal 0.181304 -0.140918 -0.973279 + outer loop + vertex 890.203 215.915 2.03047 + vertex 891.162 220.918 1.48483 + vertex 893.248 219.829 2.03112 + endloop + endfacet + facet normal 0.1829 -0.14049 -0.973042 + outer loop + vertex 885.051 213.138 1.49915 + vertex 888.016 217.622 1.40918 + vertex 887.035 212.004 2.03584 + endloop + endfacet + facet normal 0.169257 -0.138415 -0.975804 + outer loop + vertex 887.035 212.004 2.03584 + vertex 888.016 217.622 1.40918 + vertex 890.203 215.915 2.03047 + endloop + endfacet + facet normal 0.267225 -0.217706 -0.93872 + outer loop + vertex 887.035 212.004 2.03584 + vertex 890.203 215.915 2.03047 + vertex 888.938 210.624 2.89766 + endloop + endfacet + facet normal 0.267444 -0.217747 -0.938648 + outer loop + vertex 888.938 210.624 2.89766 + vertex 890.203 215.915 2.03047 + vertex 892.111 214.501 2.90229 + endloop + endfacet + facet normal 0.272072 -0.211553 -0.938734 + outer loop + vertex 890.203 215.915 2.03047 + vertex 893.248 219.829 2.03112 + vertex 892.111 214.501 2.90229 + endloop + endfacet + facet normal 0.269495 -0.21114 -0.93957 + outer loop + vertex 892.111 214.501 2.90229 + vertex 893.248 219.829 2.03112 + vertex 895.198 218.428 2.90525 + endloop + endfacet + facet normal 0.107387 -0.0797347 -0.991015 + outer loop + vertex 891.162 220.918 1.48483 + vertex 888.016 217.622 1.40918 + vertex 889.85 225.7 0.957858 + endloop + endfacet + facet normal 0.102991 -0.0879967 -0.990782 + outer loop + vertex 885.051 213.138 1.49915 + vertex 884.207 218.134 0.967703 + vertex 888.016 217.622 1.40918 + endloop + endfacet + facet normal 0.104266 -0.0790482 -0.991403 + outer loop + vertex 884.207 218.134 0.967703 + vertex 889.85 225.7 0.957858 + vertex 888.016 217.622 1.40918 + endloop + endfacet + facet normal 0.601532 -0.491399 0.62983 + outer loop + vertex 874.15 248.703 25.2651 + vertex 876.908 252.291 25.43 + vertex 873.003 249.711 27.147 + endloop + endfacet + facet normal 0.602416 -0.495387 0.625849 + outer loop + vertex 873.003 249.711 27.147 + vertex 876.908 252.291 25.43 + vertex 876.271 253.602 27.0808 + endloop + endfacet + facet normal 0.579653 -0.48754 0.652922 + outer loop + vertex 872.089 245.816 24.9389 + vertex 874.15 248.703 25.2651 + vertex 869.906 245.592 26.7095 + endloop + endfacet + facet normal 0.58708 -0.508284 0.630067 + outer loop + vertex 869.906 245.592 26.7095 + vertex 874.15 248.703 25.2651 + vertex 873.003 249.711 27.147 + endloop + endfacet + facet normal 0.478771 -0.391606 0.785763 + outer loop + vertex 876.394 246.692 22.5719 + vertex 879.069 250.13 22.6553 + vertex 875.302 247.813 23.7954 + endloop + endfacet + facet normal 0.481542 -0.398709 0.780479 + outer loop + vertex 875.302 247.813 23.7954 + vertex 879.069 250.13 22.6553 + vertex 877.896 251.2 23.9253 + endloop + endfacet + facet normal 0.473657 -0.401512 0.783861 + outer loop + vertex 873.635 243.319 22.5111 + vertex 876.394 246.692 22.5719 + vertex 872.58 244.55 23.7793 + endloop + endfacet + facet normal 0.472538 -0.398184 0.786229 + outer loop + vertex 872.58 244.55 23.7793 + vertex 876.394 246.692 22.5719 + vertex 875.302 247.813 23.7954 + endloop + endfacet + facet normal 0.296064 -0.25372 0.920854 + outer loop + vertex 879.176 243.958 20.6134 + vertex 881.852 247.445 20.7138 + vertex 877.717 245.448 21.4931 + endloop + endfacet + facet normal 0.295721 -0.252875 0.921197 + outer loop + vertex 877.717 245.448 21.4931 + vertex 881.852 247.445 20.7138 + vertex 880.401 248.922 21.5851 + endloop + endfacet + facet normal 0.291621 -0.260055 0.920504 + outer loop + vertex 876.463 240.554 20.5113 + vertex 879.176 243.958 20.6134 + vertex 874.99 242.051 21.4009 + endloop + endfacet + facet normal 0.291104 -0.258695 0.921051 + outer loop + vertex 874.99 242.051 21.4009 + vertex 879.176 243.958 20.6134 + vertex 877.717 245.448 21.4931 + endloop + endfacet + facet normal 0.389001 -0.335571 0.857945 + outer loop + vertex 874.99 242.051 21.4009 + vertex 877.717 245.448 21.4931 + vertex 873.635 243.319 22.5111 + endloop + endfacet + facet normal 0.387929 -0.332762 0.859523 + outer loop + vertex 873.635 243.319 22.5111 + vertex 877.717 245.448 21.4931 + vertex 876.394 246.692 22.5719 + endloop + endfacet + facet normal 0.393435 -0.326738 0.859332 + outer loop + vertex 877.717 245.448 21.4931 + vertex 880.401 248.922 21.5851 + vertex 876.394 246.692 22.5719 + endloop + endfacet + facet normal 0.393586 -0.327101 0.859124 + outer loop + vertex 876.394 246.692 22.5719 + vertex 880.401 248.922 21.5851 + vertex 879.069 250.13 22.6553 + endloop + endfacet + facet normal 0.131105 -0.120422 0.984027 + outer loop + vertex 882.166 239.99 19.4851 + vertex 884.437 243.605 19.6249 + vertex 880.62 242.129 19.9528 + endloop + endfacet + facet normal 0.134795 -0.130357 0.982261 + outer loop + vertex 880.62 242.129 19.9528 + vertex 884.437 243.605 19.6249 + vertex 883.311 245.639 20.0493 + endloop + endfacet + facet normal 0.126464 -0.133075 0.983005 + outer loop + vertex 878.872 236.575 19.4466 + vertex 882.166 239.99 19.4851 + vertex 877.868 238.688 19.8618 + endloop + endfacet + facet normal 0.12426 -0.125424 0.984291 + outer loop + vertex 877.868 238.688 19.8618 + vertex 882.166 239.99 19.4851 + vertex 880.62 242.129 19.9528 + endloop + endfacet + facet normal 0.199326 -0.184882 0.962335 + outer loop + vertex 877.868 238.688 19.8618 + vertex 880.62 242.129 19.9528 + vertex 876.463 240.554 20.5113 + endloop + endfacet + facet normal 0.200664 -0.18878 0.961299 + outer loop + vertex 876.463 240.554 20.5113 + vertex 880.62 242.129 19.9528 + vertex 879.176 243.958 20.6134 + endloop + endfacet + facet normal 0.206063 -0.184412 0.961005 + outer loop + vertex 880.62 242.129 19.9528 + vertex 883.311 245.639 20.0493 + vertex 879.176 243.958 20.6134 + endloop + endfacet + facet normal 0.206773 -0.186336 0.960481 + outer loop + vertex 879.176 243.958 20.6134 + vertex 883.311 245.639 20.0493 + vertex 881.852 247.445 20.7138 + endloop + endfacet + facet normal 0.322926 -0.249171 0.913035 + outer loop + vertex 898.999 221.345 15.5807 + vertex 902.165 225.537 15.6047 + vertex 897.901 223.507 16.5591 + endloop + endfacet + facet normal 0.323744 -0.251301 0.912161 + outer loop + vertex 897.901 223.507 16.5591 + vertex 902.165 225.537 15.6047 + vertex 901.041 227.671 16.5915 + endloop + endfacet + facet normal 0.310668 -0.25097 0.916788 + outer loop + vertex 895.714 217.192 15.5567 + vertex 898.999 221.345 15.5807 + vertex 894.644 219.401 16.5239 + endloop + endfacet + facet normal 0.312285 -0.255462 0.914996 + outer loop + vertex 894.644 219.401 16.5239 + vertex 898.999 221.345 15.5807 + vertex 897.901 223.507 16.5591 + endloop + endfacet + facet normal 0.211681 -0.176092 0.961344 + outer loop + vertex 894.644 219.401 16.5239 + vertex 897.901 223.507 16.5591 + vertex 893.724 221.669 17.142 + endloop + endfacet + facet normal 0.205332 -0.160362 0.965465 + outer loop + vertex 893.724 221.669 17.142 + vertex 897.901 223.507 16.5591 + vertex 896.41 225.797 17.2564 + endloop + endfacet + facet normal 0.203916 -0.161327 0.965604 + outer loop + vertex 897.901 223.507 16.5591 + vertex 901.041 227.671 16.5915 + vertex 896.41 225.797 17.2564 + endloop + endfacet + facet normal 0.211098 -0.180853 0.960588 + outer loop + vertex 896.41 225.797 17.2564 + vertex 901.041 227.671 16.5915 + vertex 900.045 229.857 17.2218 + endloop + endfacet + facet normal 0.531979 -0.414198 0.738538 + outer loop + vertex 901.678 219.387 13.0836 + vertex 903.11 221.526 13.2515 + vertex 899.931 219.259 14.2704 + endloop + endfacet + facet normal 0.541193 -0.39819 0.740645 + outer loop + vertex 904.92 223.699 13.0976 + vertex 903.151 223.505 14.2856 + vertex 903.11 221.526 13.2515 + endloop + endfacet + facet normal 0.526727 -0.402189 0.748868 + outer loop + vertex 903.151 223.505 14.2856 + vertex 899.931 219.259 14.2704 + vertex 903.11 221.526 13.2515 + endloop + endfacet + facet normal 0.520983 -0.420892 0.742581 + outer loop + vertex 898.316 215.094 13.076 + vertex 899.79 217.206 13.2391 + vertex 896.609 215.064 14.2566 + endloop + endfacet + facet normal 0.533078 -0.408827 0.740735 + outer loop + vertex 901.678 219.387 13.0836 + vertex 899.931 219.259 14.2704 + vertex 899.79 217.206 13.2391 + endloop + endfacet + facet normal 0.517509 -0.412309 0.749791 + outer loop + vertex 899.931 219.259 14.2704 + vertex 896.609 215.064 14.2566 + vertex 899.79 217.206 13.2391 + endloop + endfacet + facet normal 0.421927 -0.336914 0.841704 + outer loop + vertex 896.609 215.064 14.2566 + vertex 899.931 219.259 14.2704 + vertex 895.714 217.192 15.5567 + endloop + endfacet + facet normal 0.422608 -0.33905 0.840504 + outer loop + vertex 895.714 217.192 15.5567 + vertex 899.931 219.259 14.2704 + vertex 898.999 221.345 15.5807 + endloop + endfacet + facet normal 0.433919 -0.332115 0.837505 + outer loop + vertex 899.931 219.259 14.2704 + vertex 903.151 223.505 14.2856 + vertex 898.999 221.345 15.5807 + endloop + endfacet + facet normal 0.434133 -0.332745 0.837143 + outer loop + vertex 898.999 221.345 15.5807 + vertex 903.151 223.505 14.2856 + vertex 902.165 225.537 15.6047 + endloop + endfacet + facet normal 0.803181 -0.595728 -0.00275545 + outer loop + vertex 903.829 220.069 8.93809 + vertex 905.449 222.254 8.93962 + vertex 903.806 220.033 10.0045 + endloop + endfacet + facet normal 0.802175 -0.597048 -0.0070601 + outer loop + vertex 903.806 220.033 10.0045 + vertex 905.449 222.254 8.93962 + vertex 905.435 222.223 10.0065 + endloop + endfacet + facet normal 0.79605 -0.605217 0.00402904 + outer loop + vertex 902.151 217.863 8.93669 + vertex 903.829 220.069 8.93809 + vertex 902.119 217.827 10.003 + endloop + endfacet + facet normal 0.794365 -0.607431 -0.00333886 + outer loop + vertex 902.119 217.827 10.003 + vertex 903.829 220.069 8.93809 + vertex 903.806 220.033 10.0045 + endloop + endfacet + facet normal 0.777556 -0.594721 0.20424 + outer loop + vertex 902.119 217.827 10.003 + vertex 903.806 220.033 10.0045 + vertex 902.003 218.052 11.0968 + endloop + endfacet + facet normal 0.777391 -0.595535 0.20249 + outer loop + vertex 902.003 218.052 11.0968 + vertex 903.806 220.033 10.0045 + vertex 903.69 220.254 11.0997 + endloop + endfacet + facet normal 0.785692 -0.58497 0.201242 + outer loop + vertex 903.806 220.033 10.0045 + vertex 905.435 222.223 10.0065 + vertex 903.69 220.254 11.0997 + endloop + endfacet + facet normal 0.78565 -0.58518 0.200796 + outer loop + vertex 903.69 220.254 11.0997 + vertex 905.435 222.223 10.0065 + vertex 905.318 222.441 11.1019 + endloop + endfacet + facet normal 0.788549 -0.614931 0.00709575 + outer loop + vertex 900.45 215.681 8.93591 + vertex 902.151 217.863 8.93669 + vertex 900.415 215.648 10.0014 + endloop + endfacet + facet normal 0.787708 -0.61604 0.00341742 + outer loop + vertex 900.415 215.648 10.0014 + vertex 902.151 217.863 8.93669 + vertex 902.119 217.827 10.003 + endloop + endfacet + facet normal 0.783051 -0.621888 0.00931568 + outer loop + vertex 898.763 213.557 8.93465 + vertex 900.45 215.681 8.93591 + vertex 898.727 213.527 9.99973 + endloop + endfacet + facet normal 0.782428 -0.622705 0.00665272 + outer loop + vertex 898.727 213.527 9.99973 + vertex 900.45 215.681 8.93591 + vertex 900.415 215.648 10.0014 + endloop + endfacet + facet normal 0.765678 -0.609533 0.205442 + outer loop + vertex 898.727 213.527 9.99973 + vertex 900.415 215.648 10.0014 + vertex 898.611 213.75 11.0922 + endloop + endfacet + facet normal 0.765441 -0.610562 0.203258 + outer loop + vertex 898.611 213.75 11.0922 + vertex 900.415 215.648 10.0014 + vertex 900.299 215.867 11.0942 + endloop + endfacet + facet normal 0.771332 -0.603375 0.202448 + outer loop + vertex 900.415 215.648 10.0014 + vertex 902.119 217.827 10.003 + vertex 900.299 215.867 11.0942 + endloop + endfacet + facet normal 0.771597 -0.60213 0.205128 + outer loop + vertex 900.299 215.867 11.0942 + vertex 902.119 217.827 10.003 + vertex 902.003 218.052 11.0968 + endloop + endfacet + facet normal 0.725424 -0.566334 0.391185 + outer loop + vertex 900.299 215.867 11.0942 + vertex 902.003 218.052 11.0968 + vertex 900.13 216.397 12.1735 + endloop + endfacet + facet normal 0.725402 -0.565507 0.39242 + outer loop + vertex 900.13 216.397 12.1735 + vertex 902.003 218.052 11.0968 + vertex 901.829 218.578 12.1771 + endloop + endfacet + facet normal 0.71879 -0.57354 0.392928 + outer loop + vertex 898.611 213.75 11.0922 + vertex 900.299 215.867 11.0942 + vertex 898.444 214.278 12.1697 + endloop + endfacet + facet normal 0.718788 -0.573152 0.393499 + outer loop + vertex 898.444 214.278 12.1697 + vertex 900.299 215.867 11.0942 + vertex 900.13 216.397 12.1735 + endloop + endfacet + facet normal 0.648872 -0.517769 0.557566 + outer loop + vertex 898.444 214.278 12.1697 + vertex 900.13 216.397 12.1735 + vertex 898.316 215.094 13.076 + endloop + endfacet + facet normal 0.64485 -0.494955 0.582399 + outer loop + vertex 898.316 215.094 13.076 + vertex 900.13 216.397 12.1735 + vertex 899.79 217.206 13.2391 + endloop + endfacet + facet normal 0.639947 -0.499277 0.584115 + outer loop + vertex 900.13 216.397 12.1735 + vertex 901.829 218.578 12.1771 + vertex 899.79 217.206 13.2391 + endloop + endfacet + facet normal 0.642161 -0.515678 0.567191 + outer loop + vertex 899.79 217.206 13.2391 + vertex 901.829 218.578 12.1771 + vertex 901.678 219.387 13.0836 + endloop + endfacet + facet normal 0.738176 -0.550019 0.390609 + outer loop + vertex 903.69 220.254 11.0997 + vertex 905.318 222.441 11.1019 + vertex 903.501 220.769 12.1812 + endloop + endfacet + facet normal 0.738222 -0.551251 0.388781 + outer loop + vertex 903.501 220.769 12.1812 + vertex 905.318 222.441 11.1019 + vertex 905.118 222.938 12.1855 + endloop + endfacet + facet normal 0.730649 -0.559996 0.390585 + outer loop + vertex 902.003 218.052 11.0968 + vertex 903.69 220.254 11.0997 + vertex 901.829 218.578 12.1771 + endloop + endfacet + facet normal 0.730586 -0.558243 0.393205 + outer loop + vertex 901.829 218.578 12.1771 + vertex 903.69 220.254 11.0997 + vertex 903.501 220.769 12.1812 + endloop + endfacet + facet normal 0.658584 -0.503609 0.559147 + outer loop + vertex 901.829 218.578 12.1771 + vertex 903.501 220.769 12.1812 + vertex 901.678 219.387 13.0836 + endloop + endfacet + facet normal 0.654431 -0.483826 0.581061 + outer loop + vertex 901.678 219.387 13.0836 + vertex 903.501 220.769 12.1812 + vertex 903.11 221.526 13.2515 + endloop + endfacet + facet normal 0.651319 -0.486831 0.582047 + outer loop + vertex 903.501 220.769 12.1812 + vertex 905.118 222.938 12.1855 + vertex 903.11 221.526 13.2515 + endloop + endfacet + facet normal 0.65403 -0.504685 0.563505 + outer loop + vertex 903.11 221.526 13.2515 + vertex 905.118 222.938 12.1855 + vertex 904.92 223.699 13.0976 + endloop + endfacet + facet normal 0.554826 -0.421442 -0.717324 + outer loop + vertex 901.96 221.398 4.97345 + vertex 903.58 223.29 5.11472 + vertex 902.784 220.875 5.9177 + endloop + endfacet + facet normal 0.575568 -0.422559 -0.700118 + outer loop + vertex 902.784 220.875 5.9177 + vertex 903.58 223.29 5.11472 + vertex 904.381 223.05 5.91841 + endloop + endfacet + facet normal 0.578688 -0.420321 -0.698892 + outer loop + vertex 900.353 218.948 5.1161 + vertex 901.96 221.398 4.97345 + vertex 901.128 218.681 5.91825 + endloop + endfacet + facet normal 0.555962 -0.419802 -0.717407 + outer loop + vertex 901.128 218.681 5.91825 + vertex 901.96 221.398 4.97345 + vertex 902.784 220.875 5.9177 + endloop + endfacet + facet normal 0.661775 -0.499626 -0.558952 + outer loop + vertex 901.128 218.681 5.91825 + vertex 902.784 220.875 5.9177 + vertex 901.699 218.351 6.88941 + endloop + endfacet + facet normal 0.66198 -0.499622 -0.558713 + outer loop + vertex 901.699 218.351 6.88941 + vertex 902.784 220.875 5.9177 + vertex 903.361 220.552 6.89005 + endloop + endfacet + facet normal 0.668141 -0.490605 -0.55937 + outer loop + vertex 902.784 220.875 5.9177 + vertex 904.381 223.05 5.91841 + vertex 903.361 220.552 6.89005 + endloop + endfacet + facet normal 0.663308 -0.490792 -0.564929 + outer loop + vertex 903.361 220.552 6.89005 + vertex 904.381 223.05 5.91841 + vertex 904.97 222.727 6.88996 + endloop + endfacet + facet normal 0.549633 -0.436318 -0.712411 + outer loop + vertex 898.706 217.105 4.97419 + vertex 900.353 218.948 5.1161 + vertex 899.462 216.516 5.91764 + endloop + endfacet + facet normal 0.569304 -0.438028 -0.695719 + outer loop + vertex 899.462 216.516 5.91764 + vertex 900.353 218.948 5.1161 + vertex 901.128 218.681 5.91825 + endloop + endfacet + facet normal 0.578733 -0.436516 -0.688856 + outer loop + vertex 897.091 214.743 5.11362 + vertex 898.706 217.105 4.97419 + vertex 897.804 214.419 5.91878 + endloop + endfacet + facet normal 0.550433 -0.435299 -0.712417 + outer loop + vertex 897.804 214.419 5.91878 + vertex 898.706 217.105 4.97419 + vertex 899.462 216.516 5.91764 + endloop + endfacet + facet normal 0.653368 -0.516546 -0.553435 + outer loop + vertex 897.804 214.419 5.91878 + vertex 899.462 216.516 5.91764 + vertex 898.338 214.054 6.88897 + endloop + endfacet + facet normal 0.654245 -0.516539 -0.552404 + outer loop + vertex 898.338 214.054 6.88897 + vertex 899.462 216.516 5.91764 + vertex 900.01 216.172 6.88939 + endloop + endfacet + facet normal 0.660365 -0.508163 -0.552891 + outer loop + vertex 899.462 216.516 5.91764 + vertex 901.128 218.681 5.91825 + vertex 900.01 216.172 6.88939 + endloop + endfacet + facet normal 0.655744 -0.508207 -0.558324 + outer loop + vertex 900.01 216.172 6.88939 + vertex 901.128 218.681 5.91825 + vertex 901.699 218.351 6.88941 + endloop + endfacet + facet normal 0.725962 -0.562629 -0.39551 + outer loop + vertex 900.01 216.172 6.88939 + vertex 901.699 218.351 6.88941 + vertex 900.337 215.883 7.90061 + endloop + endfacet + facet normal 0.726217 -0.562596 -0.395088 + outer loop + vertex 900.337 215.883 7.90061 + vertex 901.699 218.351 6.88941 + vertex 902.03 218.068 7.90147 + endloop + endfacet + facet normal 0.72307 -0.570922 -0.388867 + outer loop + vertex 898.338 214.054 6.88897 + vertex 900.01 216.172 6.88939 + vertex 898.651 213.761 7.90033 + endloop + endfacet + facet normal 0.718901 -0.571457 -0.395751 + outer loop + vertex 898.651 213.761 7.90033 + vertex 900.01 216.172 6.88939 + vertex 900.337 215.883 7.90061 + endloop + endfacet + facet normal 0.766395 -0.609239 -0.203632 + outer loop + vertex 898.651 213.761 7.90033 + vertex 900.337 215.883 7.90061 + vertex 898.763 213.557 8.93465 + endloop + endfacet + facet normal 0.766971 -0.608992 -0.202199 + outer loop + vertex 898.763 213.557 8.93465 + vertex 900.337 215.883 7.90061 + vertex 900.45 215.681 8.93591 + endloop + endfacet + facet normal 0.774318 -0.599947 -0.201236 + outer loop + vertex 900.337 215.883 7.90061 + vertex 902.03 218.068 7.90147 + vertex 900.45 215.681 8.93591 + endloop + endfacet + facet normal 0.771163 -0.601295 -0.209168 + outer loop + vertex 900.45 215.681 8.93591 + vertex 902.03 218.068 7.90147 + vertex 902.151 217.863 8.93669 + endloop + endfacet + facet normal 0.737232 -0.545481 -0.398673 + outer loop + vertex 903.361 220.552 6.89005 + vertex 904.97 222.727 6.88996 + vertex 903.7 220.27 7.90233 + endloop + endfacet + facet normal 0.736376 -0.545614 -0.400069 + outer loop + vertex 903.7 220.27 7.90233 + vertex 904.97 222.727 6.88996 + vertex 905.314 222.448 7.90304 + endloop + endfacet + facet normal 0.733291 -0.553508 -0.394859 + outer loop + vertex 901.699 218.351 6.88941 + vertex 903.361 220.552 6.89005 + vertex 902.03 218.068 7.90147 + endloop + endfacet + facet normal 0.730867 -0.553841 -0.398865 + outer loop + vertex 902.03 218.068 7.90147 + vertex 903.361 220.552 6.89005 + vertex 903.7 220.27 7.90233 + endloop + endfacet + facet normal 0.779528 -0.590801 -0.208065 + outer loop + vertex 902.03 218.068 7.90147 + vertex 903.7 220.27 7.90233 + vertex 902.151 217.863 8.93669 + endloop + endfacet + facet normal 0.778085 -0.591421 -0.21167 + outer loop + vertex 902.151 217.863 8.93669 + vertex 903.7 220.27 7.90233 + vertex 903.829 220.069 8.93809 + endloop + endfacet + facet normal 0.785398 -0.582007 -0.210756 + outer loop + vertex 903.7 220.27 7.90233 + vertex 905.314 222.448 7.90304 + vertex 903.829 220.069 8.93809 + endloop + endfacet + facet normal 0.785076 -0.582153 -0.211553 + outer loop + vertex 903.829 220.069 8.93809 + vertex 905.314 222.448 7.90304 + vertex 905.449 222.254 8.93962 + endloop + endfacet + facet normal 0.36896 -0.263123 -0.891423 + outer loop + vertex 898.239 222.473 2.90286 + vertex 901.207 226.628 2.90507 + vertex 900.177 221.261 4.0627 + endloop + endfacet + facet normal 0.363192 -0.262561 -0.893954 + outer loop + vertex 900.177 221.261 4.0627 + vertex 901.207 226.628 2.90507 + vertex 903.256 225.517 4.06373 + endloop + endfacet + facet normal 0.364166 -0.274246 -0.890041 + outer loop + vertex 895.198 218.428 2.90525 + vertex 898.239 222.473 2.90286 + vertex 897.023 217.101 4.06077 + endloop + endfacet + facet normal 0.361951 -0.273958 -0.891032 + outer loop + vertex 897.023 217.101 4.06077 + vertex 898.239 222.473 2.90286 + vertex 900.177 221.261 4.0627 + endloop + endfacet + facet normal 0.452334 -0.340764 -0.824181 + outer loop + vertex 900.353 218.948 5.1161 + vertex 898.706 217.105 4.97419 + vertex 900.177 221.261 4.0627 + endloop + endfacet + facet normal 0.446697 -0.354043 -0.821654 + outer loop + vertex 897.091 214.743 5.11362 + vertex 897.023 217.101 4.06077 + vertex 898.706 217.105 4.97419 + endloop + endfacet + facet normal 0.449136 -0.340078 -0.82621 + outer loop + vertex 897.023 217.101 4.06077 + vertex 900.177 221.261 4.0627 + vertex 898.706 217.105 4.97419 + endloop + endfacet + facet normal 0.452819 -0.325699 -0.829985 + outer loop + vertex 903.58 223.29 5.11472 + vertex 901.96 221.398 4.97345 + vertex 903.256 225.517 4.06373 + endloop + endfacet + facet normal 0.447946 -0.341963 -0.826078 + outer loop + vertex 900.353 218.948 5.1161 + vertex 900.177 221.261 4.0627 + vertex 901.96 221.398 4.97345 + endloop + endfacet + facet normal 0.449649 -0.325131 -0.831929 + outer loop + vertex 900.177 221.261 4.0627 + vertex 903.256 225.517 4.06373 + vertex 901.96 221.398 4.97345 + endloop + endfacet + facet normal 0.17297 -0.129101 -0.976429 + outer loop + vertex 893.88 225.452 1.40923 + vertex 896.858 228.839 1.48904 + vertex 896.198 223.804 2.03785 + endloop + endfacet + facet normal 0.183319 -0.130235 -0.974389 + outer loop + vertex 896.198 223.804 2.03785 + vertex 896.858 228.839 1.48904 + vertex 899.069 227.863 2.03543 + endloop + endfacet + facet normal 0.187758 -0.128783 -0.973736 + outer loop + vertex 891.162 220.918 1.48483 + vertex 893.88 225.452 1.40923 + vertex 893.248 219.829 2.03112 + endloop + endfacet + facet normal 0.174078 -0.127545 -0.976437 + outer loop + vertex 893.248 219.829 2.03112 + vertex 893.88 225.452 1.40923 + vertex 896.198 223.804 2.03785 + endloop + endfacet + facet normal 0.275478 -0.202865 -0.939658 + outer loop + vertex 893.248 219.829 2.03112 + vertex 896.198 223.804 2.03785 + vertex 895.198 218.428 2.90525 + endloop + endfacet + facet normal 0.267777 -0.201827 -0.942105 + outer loop + vertex 895.198 218.428 2.90525 + vertex 896.198 223.804 2.03785 + vertex 898.239 222.473 2.90286 + endloop + endfacet + facet normal 0.273125 -0.193734 -0.942268 + outer loop + vertex 896.198 223.804 2.03785 + vertex 899.069 227.863 2.03543 + vertex 898.239 222.473 2.90286 + endloop + endfacet + facet normal 0.27166 -0.193582 -0.942723 + outer loop + vertex 898.239 222.473 2.90286 + vertex 899.069 227.863 2.03543 + vertex 901.207 226.628 2.90507 + endloop + endfacet + facet normal 0.109374 -0.0728241 -0.991329 + outer loop + vertex 896.858 228.839 1.48904 + vertex 893.88 225.452 1.40923 + vertex 895.167 233.517 0.958754 + endloop + endfacet + facet normal 0.106071 -0.0801082 -0.991126 + outer loop + vertex 891.162 220.918 1.48483 + vertex 889.85 225.7 0.957858 + vertex 893.88 225.452 1.40923 + endloop + endfacet + facet normal 0.106606 -0.0724009 -0.991662 + outer loop + vertex 889.85 225.7 0.957858 + vertex 895.167 233.517 0.958754 + vertex 893.88 225.452 1.40923 + endloop + endfacet + facet normal 0.729149 -0.609446 0.311315 + outer loop + vertex 870.315 260.955 45.0128 + vertex 875.33 267.134 45.3644 + vertex 870.388 262.425 47.7207 + endloop + endfacet + facet normal 0.729053 -0.604214 0.32157 + outer loop + vertex 870.388 262.425 47.7207 + vertex 875.33 267.134 45.3644 + vertex 875.574 268.843 48.0216 + endloop + endfacet + facet normal 0.710207 -0.596834 0.373357 + outer loop + vertex 870.603 259.102 41.5033 + vertex 875.745 265.334 41.6837 + vertex 870.315 260.955 45.0128 + endloop + endfacet + facet normal 0.710152 -0.597505 0.372387 + outer loop + vertex 870.315 260.955 45.0128 + vertex 875.745 265.334 41.6837 + vertex 875.33 267.134 45.3644 + endloop + endfacet + facet normal 0.696022 -0.584577 0.416921 + outer loop + vertex 871.127 256.995 37.6741 + vertex 876.576 263.185 37.2579 + vertex 870.603 259.102 41.5033 + endloop + endfacet + facet normal 0.695795 -0.58615 0.415088 + outer loop + vertex 870.603 259.102 41.5033 + vertex 876.576 263.185 37.2579 + vertex 875.745 265.334 41.6837 + endloop + endfacet + facet normal 0.636412 -0.466921 0.613975 + outer loop + vertex 879.613 255.849 25.4895 + vertex 882.052 259.276 25.5672 + vertex 878.952 257.006 27.0549 + endloop + endfacet + facet normal 0.637762 -0.472495 0.608283 + outer loop + vertex 878.952 257.006 27.0549 + vertex 882.052 259.276 25.5672 + vertex 881.246 260.286 27.1974 + endloop + endfacet + facet normal 0.619013 -0.481019 0.620841 + outer loop + vertex 876.908 252.291 25.43 + vertex 879.613 255.849 25.4895 + vertex 876.271 253.602 27.0808 + endloop + endfacet + facet normal 0.619442 -0.483116 0.618782 + outer loop + vertex 876.271 253.602 27.0808 + vertex 879.613 255.849 25.4895 + vertex 878.952 257.006 27.0549 + endloop + endfacet + facet normal 0.506625 -0.376503 0.775614 + outer loop + vertex 881.657 253.634 22.7505 + vertex 884.14 257.166 22.8437 + vertex 880.505 254.719 24.0299 + endloop + endfacet + facet normal 0.507369 -0.378258 0.774272 + outer loop + vertex 880.505 254.719 24.0299 + vertex 884.14 257.166 22.8437 + vertex 882.984 258.228 24.1197 + endloop + endfacet + facet normal 0.493026 -0.385486 0.779953 + outer loop + vertex 879.069 250.13 22.6553 + vertex 881.657 253.634 22.7505 + vertex 877.896 251.2 23.9253 + endloop + endfacet + facet normal 0.494887 -0.390025 0.77651 + outer loop + vertex 877.896 251.2 23.9253 + vertex 881.657 253.634 22.7505 + vertex 880.505 254.719 24.0299 + endloop + endfacet + facet normal 0.308115 -0.239923 0.920599 + outer loop + vertex 884.466 250.996 20.8046 + vertex 886.969 254.564 20.8967 + vertex 883.004 252.449 21.6724 + endloop + endfacet + facet normal 0.308352 -0.240447 0.920383 + outer loop + vertex 883.004 252.449 21.6724 + vertex 886.969 254.564 20.8967 + vertex 885.495 255.995 21.7645 + endloop + endfacet + facet normal 0.302382 -0.246128 0.920862 + outer loop + vertex 881.852 247.445 20.7138 + vertex 884.466 250.996 20.8046 + vertex 880.401 248.922 21.5851 + endloop + endfacet + facet normal 0.302309 -0.245959 0.920931 + outer loop + vertex 880.401 248.922 21.5851 + vertex 884.466 250.996 20.8046 + vertex 883.004 252.449 21.6724 + endloop + endfacet + facet normal 0.401759 -0.317828 0.858822 + outer loop + vertex 880.401 248.922 21.5851 + vertex 883.004 252.449 21.6724 + vertex 879.069 250.13 22.6553 + endloop + endfacet + facet normal 0.40329 -0.321275 0.856819 + outer loop + vertex 879.069 250.13 22.6553 + vertex 883.004 252.449 21.6724 + vertex 881.657 253.634 22.7505 + endloop + endfacet + facet normal 0.411714 -0.311375 0.856468 + outer loop + vertex 883.004 252.449 21.6724 + vertex 885.495 255.995 21.7645 + vertex 881.657 253.634 22.7505 + endloop + endfacet + facet normal 0.41209 -0.312184 0.855992 + outer loop + vertex 881.657 253.634 22.7505 + vertex 885.495 255.995 21.7645 + vertex 884.14 257.166 22.8437 + endloop + endfacet + facet normal 0.138684 -0.117773 0.983309 + outer loop + vertex 887.561 247.142 19.6687 + vertex 889.65 250.82 19.8145 + vertex 885.937 249.206 20.1449 + endloop + endfacet + facet normal 0.142273 -0.126355 0.98173 + outer loop + vertex 885.937 249.206 20.1449 + vertex 889.65 250.82 19.8145 + vertex 888.46 252.8 20.2419 + endloop + endfacet + facet normal 0.134195 -0.130697 0.982298 + outer loop + vertex 884.437 243.605 19.6249 + vertex 887.561 247.142 19.6687 + vertex 883.311 245.639 20.0493 + endloop + endfacet + facet normal 0.131704 -0.123326 0.983588 + outer loop + vertex 883.311 245.639 20.0493 + vertex 887.561 247.142 19.6687 + vertex 885.937 249.206 20.1449 + endloop + endfacet + facet normal 0.212118 -0.181903 0.960165 + outer loop + vertex 883.311 245.639 20.0493 + vertex 885.937 249.206 20.1449 + vertex 881.852 247.445 20.7138 + endloop + endfacet + facet normal 0.211452 -0.180209 0.960631 + outer loop + vertex 881.852 247.445 20.7138 + vertex 885.937 249.206 20.1449 + vertex 884.466 250.996 20.8046 + endloop + endfacet + facet normal 0.215244 -0.177 0.960386 + outer loop + vertex 885.937 249.206 20.1449 + vertex 888.46 252.8 20.2419 + vertex 884.466 250.996 20.8046 + endloop + endfacet + facet normal 0.214551 -0.175322 0.960849 + outer loop + vertex 884.466 250.996 20.8046 + vertex 888.46 252.8 20.2419 + vertex 886.969 254.564 20.8967 + endloop + endfacet + facet normal 0.34614 -0.240725 0.906774 + outer loop + vertex 905.195 229.755 15.6295 + vertex 908.092 234.012 15.6539 + vertex 904.047 231.864 16.6277 + endloop + endfacet + facet normal 0.347209 -0.243225 0.905697 + outer loop + vertex 904.047 231.864 16.6277 + vertex 908.092 234.012 15.6539 + vertex 906.902 236.076 16.6646 + endloop + endfacet + facet normal 0.333756 -0.245134 0.910229 + outer loop + vertex 902.165 225.537 15.6047 + vertex 905.195 229.755 15.6295 + vertex 901.041 227.671 16.5915 + endloop + endfacet + facet normal 0.334888 -0.247933 0.909054 + outer loop + vertex 901.041 227.671 16.5915 + vertex 905.195 229.755 15.6295 + vertex 904.047 231.864 16.6277 + endloop + endfacet + facet normal 0.228622 -0.172171 0.95817 + outer loop + vertex 901.041 227.671 16.5915 + vertex 904.047 231.864 16.6277 + vertex 900.045 229.857 17.2218 + endloop + endfacet + facet normal 0.2225 -0.158862 0.961903 + outer loop + vertex 900.045 229.857 17.2218 + vertex 904.047 231.864 16.6277 + vertex 902.479 234.026 17.3476 + endloop + endfacet + facet normal 0.222258 -0.159047 0.961928 + outer loop + vertex 904.047 231.864 16.6277 + vertex 906.902 236.076 16.6646 + vertex 902.479 234.026 17.3476 + endloop + endfacet + facet normal 0.230167 -0.177832 0.956765 + outer loop + vertex 902.479 234.026 17.3476 + vertex 906.902 236.076 16.6646 + vertex 905.815 238.155 17.3125 + endloop + endfacet + facet normal 0.554619 -0.392714 0.733603 + outer loop + vertex 907.931 227.916 13.1058 + vertex 909.184 230.004 13.2765 + vertex 906.211 227.727 14.3055 + endloop + endfacet + facet normal 0.565233 -0.374252 0.735151 + outer loop + vertex 910.836 232.192 13.1203 + vertex 909.141 231.994 14.3231 + vertex 909.184 230.004 13.2765 + endloop + endfacet + facet normal 0.548585 -0.379733 0.744888 + outer loop + vertex 909.141 231.994 14.3231 + vertex 906.211 227.727 14.3055 + vertex 909.184 230.004 13.2765 + endloop + endfacet + facet normal 0.540897 -0.39994 0.739918 + outer loop + vertex 904.92 223.699 13.0976 + vertex 906.234 225.781 13.2624 + vertex 903.151 223.505 14.2856 + endloop + endfacet + facet normal 0.555477 -0.387691 0.735623 + outer loop + vertex 907.931 227.916 13.1058 + vertex 906.211 227.727 14.3055 + vertex 906.234 225.781 13.2624 + endloop + endfacet + facet normal 0.537885 -0.393281 0.74566 + outer loop + vertex 906.211 227.727 14.3055 + vertex 903.151 223.505 14.2856 + vertex 906.234 225.781 13.2624 + endloop + endfacet + facet normal 0.444426 -0.325974 0.834402 + outer loop + vertex 903.151 223.505 14.2856 + vertex 906.211 227.727 14.3055 + vertex 902.165 225.537 15.6047 + endloop + endfacet + facet normal 0.443578 -0.323592 0.835779 + outer loop + vertex 902.165 225.537 15.6047 + vertex 906.211 227.727 14.3055 + vertex 905.195 229.755 15.6295 + endloop + endfacet + facet normal 0.454973 -0.315822 0.83262 + outer loop + vertex 906.211 227.727 14.3055 + vertex 909.141 231.994 14.3231 + vertex 905.195 229.755 15.6295 + endloop + endfacet + facet normal 0.454239 -0.313863 0.833761 + outer loop + vertex 905.195 229.755 15.6295 + vertex 909.141 231.994 14.3231 + vertex 908.092 234.012 15.6539 + endloop + endfacet + facet normal 0.831156 -0.555927 -0.0111991 + outer loop + vertex 909.953 228.62 8.94307 + vertex 911.393 230.772 8.94452 + vertex 909.95 228.593 10.0128 + endloop + endfacet + facet normal 0.829661 -0.557995 -0.0174369 + outer loop + vertex 909.95 228.593 10.0128 + vertex 911.393 230.772 8.94452 + vertex 911.393 230.739 10.0147 + endloop + endfacet + facet normal 0.822775 -0.568257 -0.0112314 + outer loop + vertex 908.495 226.508 8.94228 + vertex 909.953 228.62 8.94307 + vertex 908.491 226.481 10.0107 + endloop + endfacet + facet normal 0.822698 -0.568361 -0.0115452 + outer loop + vertex 908.491 226.481 10.0107 + vertex 909.953 228.62 8.94307 + vertex 909.95 228.593 10.0128 + endloop + endfacet + facet normal 0.807173 -0.557832 0.193119 + outer loop + vertex 908.491 226.481 10.0107 + vertex 909.95 228.593 10.0128 + vertex 908.372 226.689 11.1083 + endloop + endfacet + facet normal 0.807148 -0.557954 0.19287 + outer loop + vertex 908.372 226.689 11.1083 + vertex 909.95 228.593 10.0128 + vertex 909.83 228.799 11.1113 + endloop + endfacet + facet normal 0.814303 -0.54785 0.191757 + outer loop + vertex 909.95 228.593 10.0128 + vertex 911.393 230.739 10.0147 + vertex 909.83 228.799 11.1113 + endloop + endfacet + facet normal 0.813996 -0.54942 0.188542 + outer loop + vertex 909.83 228.799 11.1113 + vertex 911.393 230.739 10.0147 + vertex 911.275 230.941 11.1146 + endloop + endfacet + facet normal 0.816616 -0.577102 -0.00962731 + outer loop + vertex 907.002 224.396 8.94093 + vertex 908.495 226.508 8.94228 + vertex 906.995 224.368 10.0085 + endloop + endfacet + facet normal 0.816159 -0.577713 -0.011496 + outer loop + vertex 906.995 224.368 10.0085 + vertex 908.495 226.508 8.94228 + vertex 908.491 226.481 10.0107 + endloop + endfacet + facet normal 0.809573 -0.586981 -0.00667174 + outer loop + vertex 905.449 222.254 8.93962 + vertex 907.002 224.396 8.94093 + vertex 905.435 222.223 10.0065 + endloop + endfacet + facet normal 0.80878 -0.588027 -0.00997073 + outer loop + vertex 905.435 222.223 10.0065 + vertex 907.002 224.396 8.94093 + vertex 906.995 224.368 10.0085 + endloop + endfacet + facet normal 0.792426 -0.57633 0.19976 + outer loop + vertex 905.435 222.223 10.0065 + vertex 906.995 224.368 10.0085 + vertex 905.318 222.441 11.1019 + endloop + endfacet + facet normal 0.792203 -0.577409 0.197517 + outer loop + vertex 905.318 222.441 11.1019 + vertex 906.995 224.368 10.0085 + vertex 906.877 224.581 11.1052 + endloop + endfacet + facet normal 0.800229 -0.566658 0.196297 + outer loop + vertex 906.995 224.368 10.0085 + vertex 908.491 226.481 10.0107 + vertex 906.877 224.581 11.1052 + endloop + endfacet + facet normal 0.800014 -0.567681 0.194204 + outer loop + vertex 906.877 224.581 11.1052 + vertex 908.491 226.481 10.0107 + vertex 908.372 226.689 11.1083 + endloop + endfacet + facet normal 0.752322 -0.534143 0.385621 + outer loop + vertex 906.877 224.581 11.1052 + vertex 908.372 226.689 11.1083 + vertex 906.665 225.066 12.1897 + endloop + endfacet + facet normal 0.752334 -0.534524 0.385069 + outer loop + vertex 906.665 225.066 12.1897 + vertex 908.372 226.689 11.1083 + vertex 908.155 227.166 12.1943 + endloop + endfacet + facet normal 0.745183 -0.543444 0.386486 + outer loop + vertex 905.318 222.441 11.1019 + vertex 906.877 224.581 11.1052 + vertex 905.118 222.938 12.1855 + endloop + endfacet + facet normal 0.745149 -0.542454 0.387938 + outer loop + vertex 905.118 222.938 12.1855 + vertex 906.877 224.581 11.1052 + vertex 906.665 225.066 12.1897 + endloop + endfacet + facet normal 0.672289 -0.489816 0.555074 + outer loop + vertex 905.118 222.938 12.1855 + vertex 906.665 225.066 12.1897 + vertex 904.92 223.699 13.0976 + endloop + endfacet + facet normal 0.667456 -0.467165 0.579879 + outer loop + vertex 904.92 223.699 13.0976 + vertex 906.665 225.066 12.1897 + vertex 906.234 225.781 13.2624 + endloop + endfacet + facet normal 0.663145 -0.471686 0.581163 + outer loop + vertex 906.665 225.066 12.1897 + vertex 908.155 227.166 12.1943 + vertex 906.234 225.781 13.2624 + endloop + endfacet + facet normal 0.66565 -0.487828 0.564743 + outer loop + vertex 906.234 225.781 13.2624 + vertex 908.155 227.166 12.1943 + vertex 907.931 227.916 13.1058 + endloop + endfacet + facet normal 0.76605 -0.517371 0.381437 + outer loop + vertex 909.83 228.799 11.1113 + vertex 911.275 230.941 11.1146 + vertex 909.612 229.278 12.1981 + endloop + endfacet + facet normal 0.765919 -0.514912 0.385011 + outer loop + vertex 909.612 229.278 12.1981 + vertex 911.275 230.941 11.1146 + vertex 911.056 231.429 12.2023 + endloop + endfacet + facet normal 0.759862 -0.525552 0.38263 + outer loop + vertex 908.372 226.689 11.1083 + vertex 909.83 228.799 11.1113 + vertex 908.155 227.166 12.1943 + endloop + endfacet + facet normal 0.759838 -0.524932 0.383527 + outer loop + vertex 908.155 227.166 12.1943 + vertex 909.83 228.799 11.1113 + vertex 909.612 229.278 12.1981 + endloop + endfacet + facet normal 0.683406 -0.472511 0.556498 + outer loop + vertex 908.155 227.166 12.1943 + vertex 909.612 229.278 12.1981 + vertex 907.931 227.916 13.1058 + endloop + endfacet + facet normal 0.67943 -0.454687 0.575877 + outer loop + vertex 907.931 227.916 13.1058 + vertex 909.612 229.278 12.1981 + vertex 909.184 230.004 13.2765 + endloop + endfacet + facet normal 0.677972 -0.456256 0.576354 + outer loop + vertex 909.612 229.278 12.1981 + vertex 911.056 231.429 12.2023 + vertex 909.184 230.004 13.2765 + endloop + endfacet + facet normal 0.681093 -0.474388 0.557735 + outer loop + vertex 909.184 230.004 13.2765 + vertex 911.056 231.429 12.2023 + vertex 910.836 232.192 13.1203 + endloop + endfacet + facet normal 0.565542 -0.386401 -0.728599 + outer loop + vertex 907.941 229.901 4.97429 + vertex 909.381 231.74 5.11643 + vertex 908.798 229.375 5.91875 + endloop + endfacet + facet normal 0.587066 -0.385944 -0.711619 + outer loop + vertex 908.798 229.375 5.91875 + vertex 909.381 231.74 5.11643 + vertex 910.2 231.505 5.92008 + endloop + endfacet + facet normal 0.594037 -0.383809 -0.706973 + outer loop + vertex 906.577 227.533 5.11394 + vertex 907.941 229.901 4.97429 + vertex 907.373 227.281 5.91944 + endloop + endfacet + facet normal 0.566087 -0.385557 -0.728623 + outer loop + vertex 907.373 227.281 5.91944 + vertex 907.941 229.901 4.97429 + vertex 908.798 229.375 5.91875 + endloop + endfacet + facet normal 0.676984 -0.460991 -0.573742 + outer loop + vertex 907.373 227.281 5.91944 + vertex 908.798 229.375 5.91875 + vertex 907.976 226.957 6.89077 + endloop + endfacet + facet normal 0.677183 -0.460971 -0.573523 + outer loop + vertex 907.976 226.957 6.89077 + vertex 908.798 229.375 5.91875 + vertex 909.409 229.062 6.89141 + endloop + endfacet + facet normal 0.684025 -0.449845 -0.574239 + outer loop + vertex 908.798 229.375 5.91875 + vertex 910.2 231.505 5.92008 + vertex 909.409 229.062 6.89141 + endloop + endfacet + facet normal 0.678383 -0.45047 -0.580408 + outer loop + vertex 909.409 229.062 6.89141 + vertex 910.2 231.505 5.92008 + vertex 910.833 231.206 6.89164 + endloop + endfacet + facet normal 0.558821 -0.406849 -0.722629 + outer loop + vertex 905.063 225.699 4.97578 + vertex 906.577 227.533 5.11394 + vertex 905.908 225.183 5.91968 + endloop + endfacet + facet normal 0.582881 -0.407057 -0.703245 + outer loop + vertex 905.908 225.183 5.91968 + vertex 906.577 227.533 5.11394 + vertex 907.373 227.281 5.91944 + endloop + endfacet + facet normal 0.585906 -0.401249 -0.704069 + outer loop + vertex 903.58 223.29 5.11472 + vertex 905.063 225.699 4.97578 + vertex 904.381 223.05 5.91841 + endloop + endfacet + facet normal 0.562152 -0.401822 -0.722858 + outer loop + vertex 904.381 223.05 5.91841 + vertex 905.063 225.699 4.97578 + vertex 905.908 225.183 5.91968 + endloop + endfacet + facet normal 0.670753 -0.479626 -0.56573 + outer loop + vertex 904.381 223.05 5.91841 + vertex 905.908 225.183 5.91968 + vertex 904.97 222.727 6.88996 + endloop + endfacet + facet normal 0.668401 -0.479775 -0.56838 + outer loop + vertex 904.97 222.727 6.88996 + vertex 905.908 225.183 5.91968 + vertex 906.501 224.858 6.891 + endloop + endfacet + facet normal 0.674242 -0.470832 -0.56896 + outer loop + vertex 905.908 225.183 5.91968 + vertex 907.373 227.281 5.91944 + vertex 906.501 224.858 6.891 + endloop + endfacet + facet normal 0.670505 -0.471147 -0.5731 + outer loop + vertex 906.501 224.858 6.891 + vertex 907.373 227.281 5.91944 + vertex 907.976 226.957 6.89077 + endloop + endfacet + facet normal 0.747708 -0.52537 -0.406103 + outer loop + vertex 906.501 224.858 6.891 + vertex 907.976 226.957 6.89077 + vertex 906.858 224.583 7.90373 + endloop + endfacet + facet normal 0.746399 -0.525633 -0.408164 + outer loop + vertex 906.858 224.583 7.90373 + vertex 907.976 226.957 6.89077 + vertex 908.341 226.69 7.90438 + endloop + endfacet + facet normal 0.744575 -0.534566 -0.39981 + outer loop + vertex 904.97 222.727 6.88996 + vertex 906.501 224.858 6.891 + vertex 905.314 222.448 7.90304 + endloop + endfacet + facet normal 0.740543 -0.535294 -0.406272 + outer loop + vertex 905.314 222.448 7.90304 + vertex 906.501 224.858 6.891 + vertex 906.858 224.583 7.90373 + endloop + endfacet + facet normal 0.79221 -0.572713 -0.210719 + outer loop + vertex 905.314 222.448 7.90304 + vertex 906.858 224.583 7.90373 + vertex 905.449 222.254 8.93962 + endloop + endfacet + facet normal 0.790921 -0.573331 -0.21386 + outer loop + vertex 905.449 222.254 8.93962 + vertex 906.858 224.583 7.90373 + vertex 907.002 224.396 8.94093 + endloop + endfacet + facet normal 0.798806 -0.562608 -0.213027 + outer loop + vertex 906.858 224.583 7.90373 + vertex 908.341 226.69 7.90438 + vertex 907.002 224.396 8.94093 + endloop + endfacet + facet normal 0.797337 -0.563345 -0.216555 + outer loop + vertex 907.002 224.396 8.94093 + vertex 908.341 226.69 7.90438 + vertex 908.495 226.508 8.94228 + endloop + endfacet + facet normal 0.759319 -0.504241 -0.411309 + outer loop + vertex 909.409 229.062 6.89141 + vertex 910.833 231.206 6.89164 + vertex 909.786 228.803 7.90552 + endloop + endfacet + facet normal 0.756997 -0.50476 -0.414937 + outer loop + vertex 909.786 228.803 7.90552 + vertex 910.833 231.206 6.89164 + vertex 911.221 230.955 7.90625 + endloop + endfacet + facet normal 0.754676 -0.513792 -0.408022 + outer loop + vertex 907.976 226.957 6.89077 + vertex 909.409 229.062 6.89141 + vertex 908.341 226.69 7.90438 + endloop + endfacet + facet normal 0.752554 -0.514256 -0.411345 + outer loop + vertex 908.341 226.69 7.90438 + vertex 909.409 229.062 6.89141 + vertex 909.786 228.803 7.90552 + endloop + endfacet + facet normal 0.806146 -0.550999 -0.215706 + outer loop + vertex 908.341 226.69 7.90438 + vertex 909.786 228.803 7.90552 + vertex 908.495 226.508 8.94228 + endloop + endfacet + facet normal 0.801393 -0.553408 -0.226957 + outer loop + vertex 908.495 226.508 8.94228 + vertex 909.786 228.803 7.90552 + vertex 909.953 228.62 8.94307 + endloop + endfacet + facet normal 0.810418 -0.540455 -0.226124 + outer loop + vertex 909.786 228.803 7.90552 + vertex 911.221 230.955 7.90625 + vertex 909.953 228.62 8.94307 + endloop + endfacet + facet normal 0.809178 -0.54108 -0.22905 + outer loop + vertex 909.953 228.62 8.94307 + vertex 911.221 230.955 7.90625 + vertex 911.393 230.772 8.94452 + endloop + endfacet + facet normal 0.370349 -0.237877 -0.897918 + outer loop + vertex 904.05 230.813 2.90411 + vertex 906.733 234.991 2.90386 + vertex 906.163 229.742 4.05968 + endloop + endfacet + facet normal 0.367637 -0.237831 -0.899044 + outer loop + vertex 906.163 229.742 4.05968 + vertex 906.733 234.991 2.90386 + vertex 908.899 233.96 4.06247 + endloop + endfacet + facet normal 0.369636 -0.251291 -0.894551 + outer loop + vertex 901.207 226.628 2.90507 + vertex 904.05 230.813 2.90411 + vertex 903.256 225.517 4.06373 + endloop + endfacet + facet normal 0.363349 -0.250934 -0.897223 + outer loop + vertex 903.256 225.517 4.06373 + vertex 904.05 230.813 2.90411 + vertex 906.163 229.742 4.05968 + endloop + endfacet + facet normal 0.454987 -0.312767 -0.833765 + outer loop + vertex 906.577 227.533 5.11394 + vertex 905.063 225.699 4.97578 + vertex 906.163 229.742 4.05968 + endloop + endfacet + facet normal 0.451863 -0.326023 -0.830378 + outer loop + vertex 903.58 223.29 5.11472 + vertex 903.256 225.517 4.06373 + vertex 905.063 225.699 4.97578 + endloop + endfacet + facet normal 0.452852 -0.312474 -0.835036 + outer loop + vertex 903.256 225.517 4.06373 + vertex 906.163 229.742 4.05968 + vertex 905.063 225.699 4.97578 + endloop + endfacet + facet normal 0.461652 -0.29678 -0.835942 + outer loop + vertex 909.381 231.74 5.11643 + vertex 907.941 229.901 4.97429 + vertex 908.899 233.96 4.06247 + endloop + endfacet + facet normal 0.45666 -0.31213 -0.833088 + outer loop + vertex 906.577 227.533 5.11394 + vertex 906.163 229.742 4.05968 + vertex 907.941 229.901 4.97429 + endloop + endfacet + facet normal 0.457862 -0.296384 -0.838164 + outer loop + vertex 906.163 229.742 4.05968 + vertex 908.899 233.96 4.06247 + vertex 907.941 229.901 4.97429 + endloop + endfacet + facet normal 0.172734 -0.117695 -0.977912 + outer loop + vertex 899.306 233.457 1.41422 + vertex 902.098 236.938 1.48849 + vertex 901.829 231.979 2.03773 + endloop + endfacet + facet normal 0.187786 -0.118199 -0.975072 + outer loop + vertex 901.829 231.979 2.03773 + vertex 902.098 236.938 1.48849 + vertex 904.435 236.099 2.04025 + endloop + endfacet + facet normal 0.189606 -0.1163 -0.974948 + outer loop + vertex 896.858 228.839 1.48904 + vertex 899.306 233.457 1.41422 + vertex 899.069 227.863 2.03543 + endloop + endfacet + facet normal 0.173757 -0.11596 -0.977937 + outer loop + vertex 899.069 227.863 2.03543 + vertex 899.306 233.457 1.41422 + vertex 901.829 231.979 2.03773 + endloop + endfacet + facet normal 0.276715 -0.185013 -0.942974 + outer loop + vertex 899.069 227.863 2.03543 + vertex 901.829 231.979 2.03773 + vertex 901.207 226.628 2.90507 + endloop + endfacet + facet normal 0.271537 -0.184666 -0.944545 + outer loop + vertex 901.207 226.628 2.90507 + vertex 901.829 231.979 2.03773 + vertex 904.05 230.813 2.90411 + endloop + endfacet + facet normal 0.276942 -0.174618 -0.944887 + outer loop + vertex 901.829 231.979 2.03773 + vertex 904.435 236.099 2.04025 + vertex 904.05 230.813 2.90411 + endloop + endfacet + facet normal 0.271631 -0.174487 -0.946452 + outer loop + vertex 904.05 230.813 2.90411 + vertex 904.435 236.099 2.04025 + vertex 906.733 234.991 2.90386 + endloop + endfacet + facet normal 0.107798 -0.065304 -0.992026 + outer loop + vertex 902.098 236.938 1.48849 + vertex 899.306 233.457 1.41422 + vertex 899.985 241.441 0.962449 + endloop + endfacet + facet normal 0.108027 -0.0733237 -0.99144 + outer loop + vertex 896.858 228.839 1.48904 + vertex 895.167 233.517 0.958754 + vertex 899.306 233.457 1.41422 + endloop + endfacet + facet normal 0.108201 -0.0653357 -0.99198 + outer loop + vertex 895.167 233.517 0.958754 + vertex 899.985 241.441 0.962449 + vertex 899.306 233.457 1.41422 + endloop + endfacet + facet normal 0.775453 -0.561091 0.289569 + outer loop + vertex 875.33 267.134 45.3644 + vertex 879.866 273.543 45.6361 + vertex 875.574 268.843 48.0216 + endloop + endfacet + facet normal 0.775292 -0.553492 0.304252 + outer loop + vertex 875.574 268.843 48.0216 + vertex 879.866 273.543 45.6361 + vertex 880.008 275.094 48.0942 + endloop + endfacet + facet normal 0.755867 -0.550437 0.35452 + outer loop + vertex 875.745 265.334 41.6837 + vertex 880.307 271.822 42.0319 + vertex 875.33 267.134 45.3644 + endloop + endfacet + facet normal 0.755883 -0.55002 0.355131 + outer loop + vertex 875.33 267.134 45.3644 + vertex 880.307 271.822 42.0319 + vertex 879.866 273.543 45.6361 + endloop + endfacet + facet normal 0.741558 -0.538277 0.400436 + outer loop + vertex 876.576 263.185 37.2579 + vertex 881.319 269.793 37.3558 + vertex 875.745 265.334 41.6837 + endloop + endfacet + facet normal 0.741141 -0.542297 0.395757 + outer loop + vertex 875.745 265.334 41.6837 + vertex 881.319 269.793 37.3558 + vertex 880.307 271.822 42.0319 + endloop + endfacet + facet normal 0.672795 -0.43918 0.595372 + outer loop + vertex 884.316 262.677 25.6667 + vertex 886.481 266.114 25.7557 + vertex 883.473 263.649 27.3369 + endloop + endfacet + facet normal 0.67511 -0.447899 0.586185 + outer loop + vertex 883.473 263.649 27.3369 + vertex 886.481 266.114 25.7557 + vertex 885.625 267.091 27.4876 + endloop + endfacet + facet normal 0.654624 -0.453474 0.604838 + outer loop + vertex 882.052 259.276 25.5672 + vertex 884.316 262.677 25.6667 + vertex 881.246 260.286 27.1974 + endloop + endfacet + facet normal 0.65615 -0.459353 0.598717 + outer loop + vertex 881.246 260.286 27.1974 + vertex 884.316 262.677 25.6667 + vertex 883.473 263.649 27.3369 + endloop + endfacet + facet normal 0.530766 -0.35069 0.77156 + outer loop + vertex 886.49 260.706 22.9335 + vertex 888.716 264.262 23.0188 + vertex 885.307 261.715 24.2061 + endloop + endfacet + facet normal 0.531088 -0.351368 0.771029 + outer loop + vertex 885.307 261.715 24.2061 + vertex 888.716 264.262 23.0188 + vertex 887.508 265.215 24.2845 + endloop + endfacet + facet normal 0.519103 -0.364234 0.773218 + outer loop + vertex 884.14 257.166 22.8437 + vertex 886.49 260.706 22.9335 + vertex 882.984 258.228 24.1197 + endloop + endfacet + facet normal 0.519499 -0.365124 0.772531 + outer loop + vertex 882.984 258.228 24.1197 + vertex 886.49 260.706 22.9335 + vertex 885.307 261.715 24.2061 + endloop + endfacet + facet normal 0.320813 -0.226451 0.919673 + outer loop + vertex 889.342 258.143 20.9882 + vertex 891.584 261.73 21.0895 + vertex 887.855 259.556 21.8551 + endloop + endfacet + facet normal 0.318677 -0.222155 0.921462 + outer loop + vertex 887.855 259.556 21.8551 + vertex 891.584 261.73 21.0895 + vertex 890.09 263.14 21.9462 + endloop + endfacet + facet normal 0.315528 -0.232778 0.919922 + outer loop + vertex 886.969 254.564 20.8967 + vertex 889.342 258.143 20.9882 + vertex 885.495 255.995 21.7645 + endloop + endfacet + facet normal 0.315361 -0.232427 0.920068 + outer loop + vertex 885.495 255.995 21.7645 + vertex 889.342 258.143 20.9882 + vertex 887.855 259.556 21.8551 + endloop + endfacet + facet normal 0.42133 -0.301023 0.855491 + outer loop + vertex 885.495 255.995 21.7645 + vertex 887.855 259.556 21.8551 + vertex 884.14 257.166 22.8437 + endloop + endfacet + facet normal 0.421603 -0.301585 0.855159 + outer loop + vertex 884.14 257.166 22.8437 + vertex 887.855 259.556 21.8551 + vertex 886.49 260.706 22.9335 + endloop + endfacet + facet normal 0.430652 -0.290275 0.854564 + outer loop + vertex 887.855 259.556 21.8551 + vertex 890.09 263.14 21.9462 + vertex 886.49 260.706 22.9335 + endloop + endfacet + facet normal 0.430464 -0.28991 0.854782 + outer loop + vertex 886.49 260.706 22.9335 + vertex 890.09 263.14 21.9462 + vertex 888.716 264.262 23.0188 + endloop + endfacet + facet normal 0.143776 -0.112589 0.983185 + outer loop + vertex 892.545 254.419 19.8645 + vertex 894.392 258.1 20.0159 + vertex 890.857 256.4 20.3381 + endloop + endfacet + facet normal 0.147233 -0.120042 0.98179 + outer loop + vertex 890.857 256.4 20.3381 + vertex 894.392 258.1 20.0159 + vertex 893.122 260.012 20.4401 + endloop + endfacet + facet normal 0.141073 -0.127093 0.981807 + outer loop + vertex 889.65 250.82 19.8145 + vertex 892.545 254.419 19.8645 + vertex 888.46 252.8 20.2419 + endloop + endfacet + facet normal 0.137589 -0.117922 0.983445 + outer loop + vertex 888.46 252.8 20.2419 + vertex 892.545 254.419 19.8645 + vertex 890.857 256.4 20.3381 + endloop + endfacet + facet normal 0.218952 -0.171491 0.960547 + outer loop + vertex 888.46 252.8 20.2419 + vertex 890.857 256.4 20.3381 + vertex 886.969 254.564 20.8967 + endloop + endfacet + facet normal 0.21792 -0.169106 0.961205 + outer loop + vertex 886.969 254.564 20.8967 + vertex 890.857 256.4 20.3381 + vertex 889.342 258.143 20.9882 + endloop + endfacet + facet normal 0.221417 -0.165972 0.960952 + outer loop + vertex 890.857 256.4 20.3381 + vertex 893.122 260.012 20.4401 + vertex 889.342 258.143 20.9882 + endloop + endfacet + facet normal 0.22112 -0.165319 0.961132 + outer loop + vertex 889.342 258.143 20.9882 + vertex 893.122 260.012 20.4401 + vertex 891.584 261.73 21.0895 + endloop + endfacet + facet normal 0.368686 -0.230121 0.900619 + outer loop + vertex 910.849 238.279 15.6872 + vertex 913.431 242.518 15.713 + vertex 909.599 240.269 16.7075 + endloop + endfacet + facet normal 0.369592 -0.232049 0.899753 + outer loop + vertex 909.599 240.269 16.7075 + vertex 913.431 242.518 15.713 + vertex 912.123 244.439 16.7457 + endloop + endfacet + facet normal 0.356161 -0.237146 0.903831 + outer loop + vertex 908.092 234.012 15.6539 + vertex 910.849 238.279 15.6872 + vertex 906.902 236.076 16.6646 + endloop + endfacet + facet normal 0.356903 -0.238798 0.903104 + outer loop + vertex 906.902 236.076 16.6646 + vertex 910.849 238.279 15.6872 + vertex 909.599 240.269 16.7075 + endloop + endfacet + facet normal 0.246696 -0.168433 0.954343 + outer loop + vertex 906.902 236.076 16.6646 + vertex 909.599 240.269 16.7075 + vertex 905.815 238.155 17.3125 + endloop + endfacet + facet normal 0.23895 -0.153277 0.958858 + outer loop + vertex 905.815 238.155 17.3125 + vertex 909.599 240.269 16.7075 + vertex 907.934 242.281 17.4439 + endloop + endfacet + facet normal 0.238809 -0.1534 0.958874 + outer loop + vertex 909.599 240.269 16.7075 + vertex 912.123 244.439 16.7457 + vertex 907.934 242.281 17.4439 + endloop + endfacet + facet normal 0.247176 -0.17132 0.953705 + outer loop + vertex 907.934 242.281 17.4439 + vertex 912.123 244.439 16.7457 + vertex 910.933 246.406 17.4077 + endloop + endfacet + facet normal 0.578163 -0.363174 0.730638 + outer loop + vertex 913.672 236.62 13.1315 + vertex 914.813 238.777 13.3005 + vertex 911.963 236.335 14.3422 + endloop + endfacet + facet normal 0.588446 -0.349761 0.728971 + outer loop + vertex 916.316 240.985 13.1466 + vertex 914.616 240.655 14.3603 + vertex 914.813 238.777 13.3005 + endloop + endfacet + facet normal 0.574329 -0.355893 0.737215 + outer loop + vertex 914.616 240.655 14.3603 + vertex 911.963 236.335 14.3422 + vertex 914.813 238.777 13.3005 + endloop + endfacet + facet normal 0.56503 -0.37553 0.734655 + outer loop + vertex 910.836 232.192 13.1203 + vertex 912.06 234.361 13.2879 + vertex 909.141 231.994 14.3231 + endloop + endfacet + facet normal 0.578288 -0.362119 0.731062 + outer loop + vertex 913.672 236.62 13.1315 + vertex 911.963 236.335 14.3422 + vertex 912.06 234.361 13.2879 + endloop + endfacet + facet normal 0.561425 -0.368282 0.74106 + outer loop + vertex 911.963 236.335 14.3422 + vertex 909.141 231.994 14.3231 + vertex 912.06 234.361 13.2879 + endloop + endfacet + facet normal 0.465181 -0.306101 0.830608 + outer loop + vertex 909.141 231.994 14.3231 + vertex 911.963 236.335 14.3422 + vertex 908.092 234.012 15.6539 + endloop + endfacet + facet normal 0.465667 -0.307319 0.829885 + outer loop + vertex 908.092 234.012 15.6539 + vertex 911.963 236.335 14.3422 + vertex 910.849 238.279 15.6872 + endloop + endfacet + facet normal 0.478506 -0.297403 0.826186 + outer loop + vertex 911.963 236.335 14.3422 + vertex 914.616 240.655 14.3603 + vertex 910.849 238.279 15.6872 + endloop + endfacet + facet normal 0.478042 -0.296296 0.826852 + outer loop + vertex 910.849 238.279 15.6872 + vertex 914.616 240.655 14.3603 + vertex 913.431 242.518 15.713 + endloop + endfacet + facet normal 0.85792 -0.512792 -0.0318864 + outer loop + vertex 915.614 237.456 8.94944 + vertex 916.928 239.656 8.95054 + vertex 915.633 237.422 10.0214 + endloop + endfacet + facet normal 0.859094 -0.511108 -0.0269536 + outer loop + vertex 915.633 237.422 10.0214 + vertex 916.928 239.656 8.95054 + vertex 916.947 239.63 10.0241 + endloop + endfacet + facet normal 0.852201 -0.522559 -0.0261737 + outer loop + vertex 914.241 235.217 8.94777 + vertex 915.614 237.456 8.94944 + vertex 914.251 235.18 10.0192 + endloop + endfacet + facet normal 0.850793 -0.524518 -0.0321373 + outer loop + vertex 914.251 235.18 10.0192 + vertex 915.614 237.456 8.94944 + vertex 915.633 237.422 10.0214 + endloop + endfacet + facet normal 0.836923 -0.51618 0.181983 + outer loop + vertex 914.251 235.18 10.0192 + vertex 915.633 237.422 10.0214 + vertex 914.136 235.383 11.1214 + endloop + endfacet + facet normal 0.836874 -0.516479 0.181362 + outer loop + vertex 914.136 235.383 11.1214 + vertex 915.633 237.422 10.0214 + vertex 915.519 237.625 11.1248 + endloop + endfacet + facet normal 0.845291 -0.503154 0.179777 + outer loop + vertex 915.633 237.422 10.0214 + vertex 916.947 239.63 10.0241 + vertex 915.519 237.625 11.1248 + endloop + endfacet + facet normal 0.844733 -0.506418 0.173108 + outer loop + vertex 915.519 237.625 11.1248 + vertex 916.947 239.63 10.0241 + vertex 916.838 239.825 11.1281 + endloop + endfacet + facet normal 0.844944 -0.534419 -0.021597 + outer loop + vertex 912.824 232.978 8.94631 + vertex 914.241 235.217 8.94777 + vertex 912.829 232.942 10.017 + endloop + endfacet + facet normal 0.843781 -0.53603 -0.0265611 + outer loop + vertex 912.829 232.942 10.017 + vertex 914.241 235.217 8.94777 + vertex 914.251 235.18 10.0192 + endloop + endfacet + facet normal 0.838747 -0.544255 -0.017021 + outer loop + vertex 911.393 230.772 8.94452 + vertex 912.824 232.978 8.94631 + vertex 911.393 230.739 10.0147 + endloop + endfacet + facet normal 0.837588 -0.545862 -0.0219405 + outer loop + vertex 911.393 230.739 10.0147 + vertex 912.824 232.978 8.94631 + vertex 912.829 232.942 10.017 + endloop + endfacet + facet normal 0.82289 -0.536503 0.187128 + outer loop + vertex 911.393 230.739 10.0147 + vertex 912.829 232.942 10.017 + vertex 911.275 230.941 11.1146 + endloop + endfacet + facet normal 0.822875 -0.536585 0.186958 + outer loop + vertex 911.275 230.941 11.1146 + vertex 912.829 232.942 10.017 + vertex 912.712 233.146 11.1177 + endloop + endfacet + facet normal 0.829275 -0.527023 0.185878 + outer loop + vertex 912.829 232.942 10.017 + vertex 914.251 235.18 10.0192 + vertex 912.712 233.146 11.1177 + endloop + endfacet + facet normal 0.829071 -0.528219 0.183376 + outer loop + vertex 912.712 233.146 11.1177 + vertex 914.251 235.18 10.0192 + vertex 914.136 235.383 11.1214 + endloop + endfacet + facet normal 0.781492 -0.498242 0.375534 + outer loop + vertex 912.712 233.146 11.1177 + vertex 914.136 235.383 11.1214 + vertex 912.496 233.628 12.2076 + endloop + endfacet + facet normal 0.781223 -0.495045 0.380292 + outer loop + vertex 912.496 233.628 12.2076 + vertex 914.136 235.383 11.1214 + vertex 913.913 235.869 12.2117 + endloop + endfacet + facet normal 0.773934 -0.504957 0.382158 + outer loop + vertex 911.275 230.941 11.1146 + vertex 912.712 233.146 11.1177 + vertex 911.056 231.429 12.2023 + endloop + endfacet + facet normal 0.774122 -0.507622 0.378226 + outer loop + vertex 911.056 231.429 12.2023 + vertex 912.712 233.146 11.1177 + vertex 912.496 233.628 12.2076 + endloop + endfacet + facet normal 0.69876 -0.4587 0.548935 + outer loop + vertex 911.056 231.429 12.2023 + vertex 912.496 233.628 12.2076 + vertex 910.836 232.192 13.1203 + endloop + endfacet + facet normal 0.692797 -0.435271 0.574953 + outer loop + vertex 910.836 232.192 13.1203 + vertex 912.496 233.628 12.2076 + vertex 912.06 234.361 13.2879 + endloop + endfacet + facet normal 0.690411 -0.437937 0.575798 + outer loop + vertex 912.496 233.628 12.2076 + vertex 913.913 235.869 12.2117 + vertex 912.06 234.361 13.2879 + endloop + endfacet + facet normal 0.69438 -0.457113 0.555773 + outer loop + vertex 912.06 234.361 13.2879 + vertex 913.913 235.869 12.2117 + vertex 913.672 236.62 13.1315 + endloop + endfacet + facet normal 0.795656 -0.477316 0.372963 + outer loop + vertex 915.519 237.625 11.1248 + vertex 916.838 239.825 11.1281 + vertex 915.289 238.096 12.2179 + endloop + endfacet + facet normal 0.795525 -0.475827 0.375138 + outer loop + vertex 915.289 238.096 12.2179 + vertex 916.838 239.825 11.1281 + vertex 916.596 240.283 12.2218 + endloop + endfacet + facet normal 0.787772 -0.486488 0.377815 + outer loop + vertex 914.136 235.383 11.1214 + vertex 915.519 237.625 11.1248 + vertex 913.913 235.869 12.2117 + endloop + endfacet + facet normal 0.787892 -0.487812 0.375853 + outer loop + vertex 913.913 235.869 12.2117 + vertex 915.519 237.625 11.1248 + vertex 915.289 238.096 12.2179 + endloop + endfacet + facet normal 0.711423 -0.441044 0.547136 + outer loop + vertex 913.913 235.869 12.2117 + vertex 915.289 238.096 12.2179 + vertex 913.672 236.62 13.1315 + endloop + endfacet + facet normal 0.704957 -0.417924 0.57304 + outer loop + vertex 913.672 236.62 13.1315 + vertex 915.289 238.096 12.2179 + vertex 914.813 238.777 13.3005 + endloop + endfacet + facet normal 0.70267 -0.420725 0.573798 + outer loop + vertex 915.289 238.096 12.2179 + vertex 916.596 240.283 12.2218 + vertex 914.813 238.777 13.3005 + endloop + endfacet + facet normal 0.707542 -0.443305 0.550331 + outer loop + vertex 914.813 238.777 13.3005 + vertex 916.596 240.283 12.2218 + vertex 916.316 240.985 13.1466 + endloop + endfacet + facet normal 0.573915 -0.35151 -0.739636 + outer loop + vertex 913.378 238.547 4.97534 + vertex 914.74 240.474 5.11641 + vertex 914.339 238.129 5.91978 + endloop + endfacet + facet normal 0.595646 -0.349591 -0.723182 + outer loop + vertex 914.339 238.129 5.91978 + vertex 914.74 240.474 5.11641 + vertex 915.624 240.317 5.92039 + endloop + endfacet + facet normal 0.599439 -0.346307 -0.721627 + outer loop + vertex 912.125 236.084 5.11597 + vertex 913.378 238.547 4.97534 + vertex 912.988 235.903 5.91989 + endloop + endfacet + facet normal 0.575092 -0.349209 -0.739813 + outer loop + vertex 912.988 235.903 5.91989 + vertex 913.378 238.547 4.97534 + vertex 914.339 238.129 5.91978 + endloop + endfacet + facet normal 0.693767 -0.421255 -0.58415 + outer loop + vertex 912.988 235.903 5.91989 + vertex 914.339 238.129 5.91978 + vertex 913.647 235.639 6.89348 + endloop + endfacet + facet normal 0.691057 -0.421646 -0.587074 + outer loop + vertex 913.647 235.639 6.89348 + vertex 914.339 238.129 5.91978 + vertex 915.009 237.871 6.89367 + endloop + endfacet + facet normal 0.697423 -0.409397 -0.588214 + outer loop + vertex 914.339 238.129 5.91978 + vertex 915.624 240.317 5.92039 + vertex 915.009 237.871 6.89367 + endloop + endfacet + facet normal 0.694468 -0.409902 -0.59135 + outer loop + vertex 915.009 237.871 6.89367 + vertex 915.624 240.317 5.92039 + vertex 916.303 240.062 6.89405 + endloop + endfacet + facet normal 0.573741 -0.370314 -0.73054 + outer loop + vertex 910.703 234.165 4.97264 + vertex 912.125 236.084 5.11597 + vertex 911.601 233.686 5.92055 + endloop + endfacet + facet normal 0.590591 -0.369574 -0.717369 + outer loop + vertex 911.601 233.686 5.92055 + vertex 912.125 236.084 5.11597 + vertex 912.988 235.903 5.91989 + endloop + endfacet + facet normal 0.595371 -0.36724 -0.714611 + outer loop + vertex 909.381 231.74 5.11643 + vertex 910.703 234.165 4.97264 + vertex 910.2 231.505 5.92008 + endloop + endfacet + facet normal 0.574514 -0.368989 -0.730603 + outer loop + vertex 910.2 231.505 5.92008 + vertex 910.703 234.165 4.97264 + vertex 911.601 233.686 5.92055 + endloop + endfacet + facet normal 0.684668 -0.439799 -0.581211 + outer loop + vertex 910.2 231.505 5.92008 + vertex 911.601 233.686 5.92055 + vertex 910.833 231.206 6.89164 + endloop + endfacet + facet normal 0.683969 -0.43988 -0.581973 + outer loop + vertex 910.833 231.206 6.89164 + vertex 911.601 233.686 5.92055 + vertex 912.247 233.404 6.89286 + endloop + endfacet + facet normal 0.688943 -0.431043 -0.582717 + outer loop + vertex 911.601 233.686 5.92055 + vertex 912.988 235.903 5.91989 + vertex 912.247 233.404 6.89286 + endloop + endfacet + facet normal 0.688463 -0.431104 -0.583239 + outer loop + vertex 912.247 233.404 6.89286 + vertex 912.988 235.903 5.91989 + vertex 913.647 235.639 6.89348 + endloop + endfacet + facet normal 0.768661 -0.481386 -0.421221 + outer loop + vertex 912.247 233.404 6.89286 + vertex 913.647 235.639 6.89348 + vertex 912.649 233.158 7.90713 + endloop + endfacet + facet normal 0.766962 -0.481781 -0.42386 + outer loop + vertex 912.649 233.158 7.90713 + vertex 913.647 235.639 6.89348 + vertex 914.056 235.397 7.90832 + endloop + endfacet + facet normal 0.765179 -0.49224 -0.41497 + outer loop + vertex 910.833 231.206 6.89164 + vertex 912.247 233.404 6.89286 + vertex 911.221 230.955 7.90625 + endloop + endfacet + facet normal 0.761227 -0.493133 -0.421133 + outer loop + vertex 911.221 230.955 7.90625 + vertex 912.247 233.404 6.89286 + vertex 912.649 233.158 7.90713 + endloop + endfacet + facet normal 0.817075 -0.529401 -0.228303 + outer loop + vertex 911.221 230.955 7.90625 + vertex 912.649 233.158 7.90713 + vertex 911.393 230.772 8.94452 + endloop + endfacet + facet normal 0.816542 -0.529674 -0.229575 + outer loop + vertex 911.393 230.772 8.94452 + vertex 912.649 233.158 7.90713 + vertex 912.824 232.978 8.94631 + endloop + endfacet + facet normal 0.824266 -0.517898 -0.228838 + outer loop + vertex 912.649 233.158 7.90713 + vertex 914.056 235.397 7.90832 + vertex 912.824 232.978 8.94631 + endloop + endfacet + facet normal 0.821391 -0.519382 -0.235709 + outer loop + vertex 912.824 232.978 8.94631 + vertex 914.056 235.397 7.90832 + vertex 914.241 235.217 8.94777 + endloop + endfacet + facet normal 0.779052 -0.459868 -0.426145 + outer loop + vertex 915.009 237.871 6.89367 + vertex 916.303 240.062 6.89405 + vertex 915.424 237.633 7.90913 + endloop + endfacet + facet normal 0.776713 -0.46051 -0.429707 + outer loop + vertex 915.424 237.633 7.90913 + vertex 916.303 240.062 6.89405 + vertex 916.726 239.828 7.91006 + endloop + endfacet + facet normal 0.773124 -0.471738 -0.423961 + outer loop + vertex 913.647 235.639 6.89348 + vertex 915.009 237.871 6.89367 + vertex 914.056 235.397 7.90832 + endloop + endfacet + facet normal 0.771781 -0.472071 -0.426033 + outer loop + vertex 914.056 235.397 7.90832 + vertex 915.009 237.871 6.89367 + vertex 915.424 237.633 7.90913 + endloop + endfacet + facet normal 0.82915 -0.507242 -0.23498 + outer loop + vertex 914.056 235.397 7.90832 + vertex 915.424 237.633 7.90913 + vertex 914.241 235.217 8.94777 + endloop + endfacet + facet normal 0.828254 -0.507717 -0.237104 + outer loop + vertex 914.241 235.217 8.94777 + vertex 915.424 237.633 7.90913 + vertex 915.614 237.456 8.94944 + endloop + endfacet + facet normal 0.835751 -0.49561 -0.236414 + outer loop + vertex 915.424 237.633 7.90913 + vertex 916.726 239.828 7.91006 + vertex 915.614 237.456 8.94944 + endloop + endfacet + facet normal 0.832425 -0.497446 -0.244165 + outer loop + vertex 915.614 237.456 8.94944 + vertex 916.726 239.828 7.91006 + vertex 916.928 239.656 8.95054 + endloop + endfacet + facet normal 0.373544 -0.212705 -0.902896 + outer loop + vertex 909.266 239.179 2.90682 + vertex 911.664 243.386 2.90763 + vertex 911.525 238.239 4.06256 + endloop + endfacet + facet normal 0.366918 -0.213113 -0.905513 + outer loop + vertex 911.525 238.239 4.06256 + vertex 911.664 243.386 2.90763 + vertex 914.012 242.535 4.05937 + endloop + endfacet + facet normal 0.373832 -0.225512 -0.899663 + outer loop + vertex 906.733 234.991 2.90386 + vertex 909.266 239.179 2.90682 + vertex 908.899 233.96 4.06247 + endloop + endfacet + facet normal 0.367772 -0.225632 -0.902128 + outer loop + vertex 908.899 233.96 4.06247 + vertex 909.266 239.179 2.90682 + vertex 911.525 238.239 4.06256 + endloop + endfacet + facet normal 0.464387 -0.281176 -0.839812 + outer loop + vertex 912.125 236.084 5.11597 + vertex 910.703 234.165 4.97264 + vertex 911.525 238.239 4.06256 + endloop + endfacet + facet normal 0.456606 -0.298841 -0.837977 + outer loop + vertex 909.381 231.74 5.11643 + vertex 908.899 233.96 4.06247 + vertex 910.703 234.165 4.97264 + endloop + endfacet + facet normal 0.457464 -0.280666 -0.843773 + outer loop + vertex 908.899 233.96 4.06247 + vertex 911.525 238.239 4.06256 + vertex 910.703 234.165 4.97264 + endloop + endfacet + facet normal 0.466102 -0.267718 -0.843253 + outer loop + vertex 914.74 240.474 5.11641 + vertex 913.378 238.547 4.97534 + vertex 914.012 242.535 4.05937 + endloop + endfacet + facet normal 0.461106 -0.28272 -0.841101 + outer loop + vertex 912.125 236.084 5.11597 + vertex 911.525 238.239 4.06256 + vertex 913.378 238.547 4.97534 + endloop + endfacet + facet normal 0.46104 -0.267563 -0.84608 + outer loop + vertex 911.525 238.239 4.06256 + vertex 914.012 242.535 4.05937 + vertex 913.378 238.547 4.97534 + endloop + endfacet + facet normal 0.174294 -0.104504 -0.979132 + outer loop + vertex 904.213 241.561 1.41298 + vertex 906.758 245.074 1.49105 + vertex 906.907 240.221 2.03554 + endloop + endfacet + facet normal 0.185381 -0.103943 -0.977154 + outer loop + vertex 906.907 240.221 2.03554 + vertex 906.758 245.074 1.49105 + vertex 909.222 244.35 2.03555 + endloop + endfacet + facet normal 0.192951 -0.104201 -0.97566 + outer loop + vertex 902.098 236.938 1.48849 + vertex 904.213 241.561 1.41298 + vertex 904.435 236.099 2.04025 + endloop + endfacet + facet normal 0.173858 -0.105375 -0.979117 + outer loop + vertex 904.435 236.099 2.04025 + vertex 904.213 241.561 1.41298 + vertex 906.907 240.221 2.03554 + endloop + endfacet + facet normal 0.275652 -0.16638 -0.946749 + outer loop + vertex 904.435 236.099 2.04025 + vertex 906.907 240.221 2.03554 + vertex 906.733 234.991 2.90386 + endloop + endfacet + facet normal 0.276127 -0.166373 -0.946612 + outer loop + vertex 906.733 234.991 2.90386 + vertex 906.907 240.221 2.03554 + vertex 909.266 239.179 2.90682 + endloop + endfacet + facet normal 0.280316 -0.157174 -0.946953 + outer loop + vertex 906.907 240.221 2.03554 + vertex 909.222 244.35 2.03555 + vertex 909.266 239.179 2.90682 + endloop + endfacet + facet normal 0.276495 -0.157389 -0.948039 + outer loop + vertex 909.266 239.179 2.90682 + vertex 909.222 244.35 2.03555 + vertex 911.664 243.386 2.90763 + endloop + endfacet + facet normal 0.109983 -0.0576253 -0.992262 + outer loop + vertex 906.758 245.074 1.49105 + vertex 904.213 241.561 1.41298 + vertex 904.27 249.461 0.960437 + endloop + endfacet + facet normal 0.107572 -0.0654122 -0.992043 + outer loop + vertex 902.098 236.938 1.48849 + vertex 899.985 241.441 0.962449 + vertex 904.213 241.561 1.41298 + endloop + endfacet + facet normal 0.107404 -0.0576231 -0.992544 + outer loop + vertex 899.985 241.441 0.962449 + vertex 904.27 249.461 0.960437 + vertex 904.213 241.561 1.41298 + endloop + endfacet + facet normal 0.712341 -0.411626 0.568449 + outer loop + vertex 888.569 269.633 25.8586 + vertex 890.577 273.242 25.9555 + vertex 887.706 270.644 27.6723 + endloop + endfacet + facet normal 0.714332 -0.419149 0.560397 + outer loop + vertex 887.706 270.644 27.6723 + vertex 890.577 273.242 25.9555 + vertex 889.719 274.247 27.8003 + endloop + endfacet + facet normal 0.691403 -0.427254 0.582595 + outer loop + vertex 886.481 266.114 25.7557 + vertex 888.569 269.633 25.8586 + vertex 885.625 267.091 27.4876 + endloop + endfacet + facet normal 0.693775 -0.436013 0.573209 + outer loop + vertex 885.625 267.091 27.4876 + vertex 888.569 269.633 25.8586 + vertex 887.706 270.644 27.6723 + endloop + endfacet + facet normal 0.555296 -0.321789 0.766876 + outer loop + vertex 890.832 267.859 23.0944 + vertex 892.853 271.528 23.1709 + vertex 889.612 268.761 24.3565 + endloop + endfacet + facet normal 0.556691 -0.324315 0.764797 + outer loop + vertex 889.612 268.761 24.3565 + vertex 892.853 271.528 23.1709 + vertex 891.626 272.392 24.4301 + endloop + endfacet + facet normal 0.542615 -0.335487 0.770076 + outer loop + vertex 888.716 264.262 23.0188 + vertex 890.832 267.859 23.0944 + vertex 887.508 265.215 24.2845 + endloop + endfacet + facet normal 0.544055 -0.338314 0.76782 + outer loop + vertex 887.508 265.215 24.2845 + vertex 890.832 267.859 23.0944 + vertex 889.612 268.761 24.3565 + endloop + endfacet + facet normal 0.330655 -0.206123 0.920967 + outer loop + vertex 893.711 265.362 21.1914 + vertex 895.737 269.074 21.2944 + vertex 892.212 266.761 22.0426 + endloop + endfacet + facet normal 0.328563 -0.202426 0.922535 + outer loop + vertex 892.212 266.761 22.0426 + vertex 895.737 269.074 21.2944 + vertex 894.234 270.46 22.1341 + endloop + endfacet + facet normal 0.32441 -0.215783 0.920975 + outer loop + vertex 891.584 261.73 21.0895 + vertex 893.711 265.362 21.1914 + vertex 890.09 263.14 21.9462 + endloop + endfacet + facet normal 0.323553 -0.214155 0.921657 + outer loop + vertex 890.09 263.14 21.9462 + vertex 893.711 265.362 21.1914 + vertex 892.212 266.761 22.0426 + endloop + endfacet + facet normal 0.438375 -0.27965 0.85418 + outer loop + vertex 890.09 263.14 21.9462 + vertex 892.212 266.761 22.0426 + vertex 888.716 264.262 23.0188 + endloop + endfacet + facet normal 0.435425 -0.274253 0.857432 + outer loop + vertex 888.716 264.262 23.0188 + vertex 892.212 266.761 22.0426 + vertex 890.832 267.859 23.0944 + endloop + endfacet + facet normal 0.44338 -0.263568 0.856707 + outer loop + vertex 892.212 266.761 22.0426 + vertex 894.234 270.46 22.1341 + vertex 890.832 267.859 23.0944 + endloop + endfacet + facet normal 0.442051 -0.261324 0.858079 + outer loop + vertex 890.832 267.859 23.0944 + vertex 894.234 270.46 22.1341 + vertex 892.853 271.528 23.1709 + endloop + endfacet + facet normal 0.150304 -0.107258 0.982804 + outer loop + vertex 897.036 261.77 20.0725 + vertex 898.657 265.512 20.233 + vertex 895.268 263.654 20.5485 + endloop + endfacet + facet normal 0.153748 -0.113754 0.98154 + outer loop + vertex 895.268 263.654 20.5485 + vertex 898.657 265.512 20.233 + vertex 897.312 267.374 20.6595 + endloop + endfacet + facet normal 0.146404 -0.120604 0.981845 + outer loop + vertex 894.392 258.1 20.0159 + vertex 897.036 261.77 20.0725 + vertex 893.122 260.012 20.4401 + endloop + endfacet + facet normal 0.143451 -0.113768 0.983097 + outer loop + vertex 893.122 260.012 20.4401 + vertex 897.036 261.77 20.0725 + vertex 895.268 263.654 20.5485 + endloop + endfacet + facet normal 0.225386 -0.161378 0.960811 + outer loop + vertex 893.122 260.012 20.4401 + vertex 895.268 263.654 20.5485 + vertex 891.584 261.73 21.0895 + endloop + endfacet + facet normal 0.223757 -0.157994 0.961754 + outer loop + vertex 891.584 261.73 21.0895 + vertex 895.268 263.654 20.5485 + vertex 893.711 265.362 21.1914 + endloop + endfacet + facet normal 0.228032 -0.153967 0.961403 + outer loop + vertex 895.268 263.654 20.5485 + vertex 897.312 267.374 20.6595 + vertex 893.711 265.362 21.1914 + endloop + endfacet + facet normal 0.226063 -0.150162 0.962469 + outer loop + vertex 893.711 265.362 21.1914 + vertex 897.312 267.374 20.6595 + vertex 895.737 269.074 21.2944 + endloop + endfacet + facet normal 0.389601 -0.215506 0.895415 + outer loop + vertex 915.858 246.745 15.7448 + vertex 918.161 251.045 15.778 + vertex 914.504 248.621 16.7855 + endloop + endfacet + facet normal 0.389028 -0.214431 0.895922 + outer loop + vertex 914.504 248.621 16.7855 + vertex 918.161 251.045 15.778 + vertex 916.763 252.891 16.8267 + endloop + endfacet + facet normal 0.379172 -0.224423 0.897699 + outer loop + vertex 913.431 242.518 15.713 + vertex 915.858 246.745 15.7448 + vertex 912.123 244.439 16.7457 + endloop + endfacet + facet normal 0.379134 -0.224346 0.897734 + outer loop + vertex 912.123 244.439 16.7457 + vertex 915.858 246.745 15.7448 + vertex 914.504 248.621 16.7855 + endloop + endfacet + facet normal 0.264768 -0.159753 0.950987 + outer loop + vertex 912.123 244.439 16.7457 + vertex 914.504 248.621 16.7855 + vertex 910.933 246.406 17.4077 + endloop + endfacet + facet normal 0.257526 -0.146941 0.955033 + outer loop + vertex 910.933 246.406 17.4077 + vertex 914.504 248.621 16.7855 + vertex 912.792 250.574 17.5475 + endloop + endfacet + facet normal 0.25856 -0.145983 0.954901 + outer loop + vertex 914.504 248.621 16.7855 + vertex 916.763 252.891 16.8267 + vertex 912.792 250.574 17.5475 + endloop + endfacet + facet normal 0.266018 -0.160111 0.950578 + outer loop + vertex 912.792 250.574 17.5475 + vertex 916.763 252.891 16.8267 + vertex 915.538 254.885 17.5052 + endloop + endfacet + facet normal 0.602538 -0.337125 0.723391 + outer loop + vertex 918.715 245.213 13.1555 + vertex 919.68 247.311 13.3294 + vertex 917.078 244.909 14.3779 + endloop + endfacet + facet normal 0.614792 -0.317996 0.72174 + outer loop + vertex 921.029 249.562 13.1721 + vertex 919.417 249.232 14.3999 + vertex 919.68 247.311 13.3294 + endloop + endfacet + facet normal 0.596749 -0.326695 0.732913 + outer loop + vertex 919.417 249.232 14.3999 + vertex 917.078 244.909 14.3779 + vertex 919.68 247.311 13.3294 + endloop + endfacet + facet normal 0.588507 -0.349117 0.729231 + outer loop + vertex 916.316 240.985 13.1466 + vertex 917.335 243.056 13.3159 + vertex 914.616 240.655 14.3603 + endloop + endfacet + facet normal 0.60305 -0.331922 0.725368 + outer loop + vertex 918.715 245.213 13.1555 + vertex 917.078 244.909 14.3779 + vertex 917.335 243.056 13.3159 + endloop + endfacet + facet normal 0.584128 -0.340966 0.73657 + outer loop + vertex 917.078 244.909 14.3779 + vertex 914.616 240.655 14.3603 + vertex 917.335 243.056 13.3159 + endloop + endfacet + facet normal 0.48952 -0.286595 0.823549 + outer loop + vertex 914.616 240.655 14.3603 + vertex 917.078 244.909 14.3779 + vertex 913.431 242.518 15.713 + endloop + endfacet + facet normal 0.489877 -0.287418 0.82305 + outer loop + vertex 913.431 242.518 15.713 + vertex 917.078 244.909 14.3779 + vertex 915.858 246.745 15.7448 + endloop + endfacet + facet normal 0.502563 -0.276159 0.819248 + outer loop + vertex 917.078 244.909 14.3779 + vertex 919.417 249.232 14.3999 + vertex 915.858 246.745 15.7448 + endloop + endfacet + facet normal 0.502095 -0.275151 0.819873 + outer loop + vertex 915.858 246.745 15.7448 + vertex 919.417 249.232 14.3999 + vertex 918.161 251.045 15.778 + endloop + endfacet + facet normal 0.885492 -0.462468 -0.0450324 + outer loop + vertex 920.494 246.049 8.95543 + vertex 921.638 248.241 8.95636 + vertex 920.531 246.017 10.0306 + endloop + endfacet + facet normal 0.886555 -0.460841 -0.0405704 + outer loop + vertex 920.531 246.017 10.0306 + vertex 921.638 248.241 8.95636 + vertex 921.673 248.212 10.0332 + endloop + endfacet + facet normal 0.879541 -0.474163 -0.0397162 + outer loop + vertex 919.345 243.918 8.95392 + vertex 920.494 246.049 8.95543 + vertex 919.379 243.892 10.0286 + endloop + endfacet + facet normal 0.878183 -0.476185 -0.0451922 + outer loop + vertex 919.379 243.892 10.0286 + vertex 920.494 246.049 8.95543 + vertex 920.531 246.017 10.0306 + endloop + endfacet + facet normal 0.866375 -0.469992 0.168824 + outer loop + vertex 919.379 243.892 10.0286 + vertex 920.531 246.017 10.0306 + vertex 919.264 244.077 11.135 + endloop + endfacet + facet normal 0.866403 -0.469822 0.169154 + outer loop + vertex 919.264 244.077 11.135 + vertex 920.531 246.017 10.0306 + vertex 920.415 246.201 11.138 + endloop + endfacet + facet normal 0.874644 -0.454895 0.167538 + outer loop + vertex 920.531 246.017 10.0306 + vertex 921.673 248.212 10.0332 + vertex 920.415 246.201 11.138 + endloop + endfacet + facet normal 0.87399 -0.459228 0.158904 + outer loop + vertex 920.415 246.201 11.138 + vertex 921.673 248.212 10.0332 + vertex 921.563 248.386 11.1415 + endloop + endfacet + facet normal 0.873351 -0.485926 -0.0336661 + outer loop + vertex 918.167 241.802 8.95204 + vertex 919.345 243.918 8.95392 + vertex 918.195 241.777 10.0261 + endloop + endfacet + facet normal 0.871829 -0.488189 -0.0398182 + outer loop + vertex 918.195 241.777 10.0261 + vertex 919.345 243.918 8.95392 + vertex 919.379 243.892 10.0286 + endloop + endfacet + facet normal 0.865768 -0.499728 -0.0267965 + outer loop + vertex 916.928 239.656 8.95054 + vertex 918.167 241.802 8.95204 + vertex 916.947 239.63 10.0241 + endloop + endfacet + facet normal 0.86407 -0.502236 -0.0338113 + outer loop + vertex 916.947 239.63 10.0241 + vertex 918.167 241.802 8.95204 + vertex 918.195 241.777 10.0261 + endloop + endfacet + facet normal 0.851626 -0.495193 0.171802 + outer loop + vertex 916.947 239.63 10.0241 + vertex 918.195 241.777 10.0261 + vertex 916.838 239.825 11.1281 + endloop + endfacet + facet normal 0.851792 -0.494263 0.173654 + outer loop + vertex 916.838 239.825 11.1281 + vertex 918.195 241.777 10.0261 + vertex 918.081 241.969 11.1316 + endloop + endfacet + facet normal 0.859383 -0.481462 0.172206 + outer loop + vertex 918.195 241.777 10.0261 + vertex 919.379 243.892 10.0286 + vertex 918.081 241.969 11.1316 + endloop + endfacet + facet normal 0.859203 -0.482505 0.170176 + outer loop + vertex 918.081 241.969 11.1316 + vertex 919.379 243.892 10.0286 + vertex 919.264 244.077 11.135 + endloop + endfacet + facet normal 0.810059 -0.455254 0.369524 + outer loop + vertex 918.081 241.969 11.1316 + vertex 919.264 244.077 11.135 + vertex 917.832 242.414 12.2265 + endloop + endfacet + facet normal 0.810239 -0.457477 0.366372 + outer loop + vertex 917.832 242.414 12.2265 + vertex 919.264 244.077 11.135 + vertex 919.014 244.512 12.2322 + endloop + endfacet + facet normal 0.802515 -0.466004 0.372573 + outer loop + vertex 916.838 239.825 11.1281 + vertex 918.081 241.969 11.1316 + vertex 916.596 240.283 12.2218 + endloop + endfacet + facet normal 0.802533 -0.46622 0.372263 + outer loop + vertex 916.596 240.283 12.2218 + vertex 918.081 241.969 11.1316 + vertex 917.832 242.414 12.2265 + endloop + endfacet + facet normal 0.727152 -0.422873 0.540766 + outer loop + vertex 916.596 240.283 12.2218 + vertex 917.832 242.414 12.2265 + vertex 916.316 240.985 13.1466 + endloop + endfacet + facet normal 0.721154 -0.400938 0.564965 + outer loop + vertex 916.316 240.985 13.1466 + vertex 917.832 242.414 12.2265 + vertex 917.335 243.056 13.3159 + endloop + endfacet + facet normal 0.717507 -0.405777 0.566152 + outer loop + vertex 917.832 242.414 12.2265 + vertex 919.014 244.512 12.2322 + vertex 917.335 243.056 13.3159 + endloop + endfacet + facet normal 0.720547 -0.420018 0.551722 + outer loop + vertex 917.335 243.056 13.3159 + vertex 919.014 244.512 12.2322 + vertex 918.715 245.213 13.1555 + endloop + endfacet + facet normal 0.825601 -0.43414 0.360424 + outer loop + vertex 920.415 246.201 11.138 + vertex 921.563 248.386 11.1415 + vertex 920.167 246.641 12.2366 + endloop + endfacet + facet normal 0.82541 -0.432423 0.362916 + outer loop + vertex 920.167 246.641 12.2366 + vertex 921.563 248.386 11.1415 + vertex 921.316 248.838 12.241 + endloop + endfacet + facet normal 0.818938 -0.444361 0.363158 + outer loop + vertex 919.264 244.077 11.135 + vertex 920.415 246.201 11.138 + vertex 919.014 244.512 12.2322 + endloop + endfacet + facet normal 0.818945 -0.44444 0.363047 + outer loop + vertex 919.014 244.512 12.2322 + vertex 920.415 246.201 11.138 + vertex 920.167 246.641 12.2366 + endloop + endfacet + facet normal 0.737942 -0.40093 0.542861 + outer loop + vertex 919.014 244.512 12.2322 + vertex 920.167 246.641 12.2366 + vertex 918.715 245.213 13.1555 + endloop + endfacet + facet normal 0.732952 -0.383711 0.561737 + outer loop + vertex 918.715 245.213 13.1555 + vertex 920.167 246.641 12.2366 + vertex 919.68 247.311 13.3294 + endloop + endfacet + facet normal 0.732552 -0.38425 0.561889 + outer loop + vertex 920.167 246.641 12.2366 + vertex 921.316 248.838 12.241 + vertex 919.68 247.311 13.3294 + endloop + endfacet + facet normal 0.737357 -0.404053 0.541338 + outer loop + vertex 919.68 247.311 13.3294 + vertex 921.316 248.838 12.241 + vertex 921.029 249.562 13.1721 + endloop + endfacet + facet normal 0.586186 -0.313137 -0.747215 + outer loop + vertex 918.133 247.085 4.97316 + vertex 919.322 248.969 5.11628 + vertex 919.111 246.653 5.92146 + endloop + endfacet + facet normal 0.607031 -0.309696 -0.731848 + outer loop + vertex 919.111 246.653 5.92146 + vertex 919.322 248.969 5.11628 + vertex 920.217 248.819 5.92238 + endloop + endfacet + facet normal 0.607495 -0.308083 -0.732144 + outer loop + vertex 917.11 244.724 5.11842 + vertex 918.133 247.085 4.97316 + vertex 917.991 244.55 5.92202 + endloop + endfacet + facet normal 0.586465 -0.312559 -0.747239 + outer loop + vertex 917.991 244.55 5.92202 + vertex 918.133 247.085 4.97316 + vertex 919.111 246.653 5.92146 + endloop + endfacet + facet normal 0.704626 -0.375454 -0.602111 + outer loop + vertex 917.991 244.55 5.92202 + vertex 919.111 246.653 5.92146 + vertex 918.686 244.296 6.89466 + endloop + endfacet + facet normal 0.704857 -0.375398 -0.601875 + outer loop + vertex 918.686 244.296 6.89466 + vertex 919.111 246.653 5.92146 + vertex 919.814 246.412 6.89555 + endloop + endfacet + facet normal 0.710633 -0.362659 -0.602893 + outer loop + vertex 919.111 246.653 5.92146 + vertex 920.217 248.819 5.92238 + vertex 919.814 246.412 6.89555 + endloop + endfacet + facet normal 0.706278 -0.363731 -0.607348 + outer loop + vertex 919.814 246.412 6.89555 + vertex 920.217 248.819 5.92238 + vertex 920.939 248.596 6.89579 + endloop + endfacet + facet normal 0.57947 -0.33227 -0.744185 + outer loop + vertex 915.863 242.868 4.976 + vertex 917.11 244.724 5.11842 + vertex 916.838 242.452 5.92102 + endloop + endfacet + facet normal 0.600285 -0.329337 -0.728831 + outer loop + vertex 916.838 242.452 5.92102 + vertex 917.11 244.724 5.11842 + vertex 917.991 244.55 5.92202 + endloop + endfacet + facet normal 0.603773 -0.325892 -0.727497 + outer loop + vertex 914.74 240.474 5.11641 + vertex 915.863 242.868 4.976 + vertex 915.624 240.317 5.92039 + endloop + endfacet + facet normal 0.5806 -0.329957 -0.744333 + outer loop + vertex 915.624 240.317 5.92039 + vertex 915.863 242.868 4.976 + vertex 916.838 242.452 5.92102 + endloop + endfacet + facet normal 0.700398 -0.39813 -0.592398 + outer loop + vertex 915.624 240.317 5.92039 + vertex 916.838 242.452 5.92102 + vertex 916.303 240.062 6.89405 + endloop + endfacet + facet normal 0.699151 -0.398381 -0.593701 + outer loop + vertex 916.303 240.062 6.89405 + vertex 916.838 242.452 5.92102 + vertex 917.52 242.197 6.89516 + endloop + endfacet + facet normal 0.704823 -0.386815 -0.594642 + outer loop + vertex 916.838 242.452 5.92102 + vertex 917.991 244.55 5.92202 + vertex 917.52 242.197 6.89516 + endloop + endfacet + facet normal 0.698539 -0.388229 -0.6011 + outer loop + vertex 917.52 242.197 6.89516 + vertex 917.991 244.55 5.92202 + vertex 918.686 244.296 6.89466 + endloop + endfacet + facet normal 0.786858 -0.437256 -0.435502 + outer loop + vertex 917.52 242.197 6.89516 + vertex 918.686 244.296 6.89466 + vertex 917.955 241.968 7.91106 + endloop + endfacet + facet normal 0.786576 -0.437349 -0.435917 + outer loop + vertex 917.955 241.968 7.91106 + vertex 918.686 244.296 6.89466 + vertex 919.128 244.076 7.91182 + endloop + endfacet + facet normal 0.784436 -0.4471 -0.429838 + outer loop + vertex 916.303 240.062 6.89405 + vertex 917.52 242.197 6.89516 + vertex 916.726 239.828 7.91006 + endloop + endfacet + facet normal 0.780745 -0.448225 -0.435351 + outer loop + vertex 916.726 239.828 7.91006 + vertex 917.52 242.197 6.89516 + vertex 917.955 241.968 7.91106 + endloop + endfacet + facet normal 0.841106 -0.482983 -0.243451 + outer loop + vertex 916.726 239.828 7.91006 + vertex 917.955 241.968 7.91106 + vertex 916.928 239.656 8.95054 + endloop + endfacet + facet normal 0.83907 -0.484163 -0.248088 + outer loop + vertex 916.928 239.656 8.95054 + vertex 917.955 241.968 7.91106 + vertex 918.167 241.802 8.95204 + endloop + endfacet + facet normal 0.846753 -0.470888 -0.247535 + outer loop + vertex 917.955 241.968 7.91106 + vertex 919.128 244.076 7.91182 + vertex 918.167 241.802 8.95204 + endloop + endfacet + facet normal 0.846712 -0.470913 -0.247628 + outer loop + vertex 918.167 241.802 8.95204 + vertex 919.128 244.076 7.91182 + vertex 919.345 243.918 8.95392 + endloop + endfacet + facet normal 0.797613 -0.410796 -0.441657 + outer loop + vertex 919.814 246.412 6.89555 + vertex 920.939 248.596 6.89579 + vertex 920.27 246.203 7.91264 + endloop + endfacet + facet normal 0.796616 -0.411143 -0.44313 + outer loop + vertex 920.27 246.203 7.91264 + vertex 920.939 248.596 6.89579 + vertex 921.404 248.399 7.91377 + endloop + endfacet + facet normal 0.794209 -0.423087 -0.436153 + outer loop + vertex 918.686 244.296 6.89466 + vertex 919.814 246.412 6.89555 + vertex 919.128 244.076 7.91182 + endloop + endfacet + facet normal 0.790692 -0.424306 -0.441328 + outer loop + vertex 919.128 244.076 7.91182 + vertex 919.814 246.412 6.89555 + vertex 920.27 246.203 7.91264 + endloop + endfacet + facet normal 0.853767 -0.458243 -0.247175 + outer loop + vertex 919.128 244.076 7.91182 + vertex 920.27 246.203 7.91264 + vertex 919.345 243.918 8.95392 + endloop + endfacet + facet normal 0.852161 -0.459252 -0.250817 + outer loop + vertex 919.345 243.918 8.95392 + vertex 920.27 246.203 7.91264 + vertex 920.494 246.049 8.95543 + endloop + endfacet + facet normal 0.860286 -0.444121 -0.250329 + outer loop + vertex 920.27 246.203 7.91264 + vertex 921.404 248.399 7.91377 + vertex 920.494 246.049 8.95543 + endloop + endfacet + facet normal 0.855836 -0.446886 -0.260457 + outer loop + vertex 920.494 246.049 8.95543 + vertex 921.404 248.399 7.91377 + vertex 921.638 248.241 8.95636 + endloop + endfacet + facet normal 0.377156 -0.185356 -0.907412 + outer loop + vertex 913.92 247.606 2.90257 + vertex 916.033 251.884 2.90659 + vertex 916.307 246.788 4.06144 + endloop + endfacet + facet normal 0.371253 -0.186186 -0.909674 + outer loop + vertex 916.307 246.788 4.06144 + vertex 916.033 251.884 2.90659 + vertex 918.469 251.1 4.06142 + endloop + endfacet + facet normal 0.372076 -0.200073 -0.906383 + outer loop + vertex 911.664 243.386 2.90763 + vertex 913.92 247.606 2.90257 + vertex 914.012 242.535 4.05937 + endloop + endfacet + facet normal 0.371674 -0.200116 -0.906539 + outer loop + vertex 914.012 242.535 4.05937 + vertex 913.92 247.606 2.90257 + vertex 916.307 246.788 4.06144 + endloop + endfacet + facet normal 0.469644 -0.25062 -0.846537 + outer loop + vertex 917.11 244.724 5.11842 + vertex 915.863 242.868 4.976 + vertex 916.307 246.788 4.06144 + endloop + endfacet + facet normal 0.465714 -0.26793 -0.8434 + outer loop + vertex 914.74 240.474 5.11641 + vertex 914.012 242.535 4.05937 + vertex 915.863 242.868 4.976 + endloop + endfacet + facet normal 0.465333 -0.250682 -0.848896 + outer loop + vertex 914.012 242.535 4.05937 + vertex 916.307 246.788 4.06144 + vertex 915.863 242.868 4.976 + endloop + endfacet + facet normal 0.471144 -0.232681 -0.850813 + outer loop + vertex 919.322 248.969 5.11628 + vertex 918.133 247.085 4.97316 + vertex 918.469 251.1 4.06142 + endloop + endfacet + facet normal 0.464793 -0.253446 -0.84837 + outer loop + vertex 917.11 244.724 5.11842 + vertex 916.307 246.788 4.06144 + vertex 918.133 247.085 4.97316 + endloop + endfacet + facet normal 0.464476 -0.232937 -0.854402 + outer loop + vertex 916.307 246.788 4.06144 + vertex 918.469 251.1 4.06142 + vertex 918.133 247.085 4.97316 + endloop + endfacet + facet normal 0.173828 -0.0934025 -0.980337 + outer loop + vertex 908.549 249.726 1.4144 + vertex 910.89 253.333 1.48575 + vertex 911.404 248.506 2.03687 + endloop + endfacet + facet normal 0.188202 -0.0915865 -0.977851 + outer loop + vertex 911.404 248.506 2.03687 + vertex 910.89 253.333 1.48575 + vertex 913.457 252.724 2.03681 + endloop + endfacet + facet normal 0.189847 -0.0892109 -0.977752 + outer loop + vertex 906.758 245.074 1.49105 + vertex 908.549 249.726 1.4144 + vertex 909.222 244.35 2.03555 + endloop + endfacet + facet normal 0.174687 -0.0914101 -0.980372 + outer loop + vertex 909.222 244.35 2.03555 + vertex 908.549 249.726 1.4144 + vertex 911.404 248.506 2.03687 + endloop + endfacet + facet normal 0.280709 -0.147088 -0.948455 + outer loop + vertex 909.222 244.35 2.03555 + vertex 911.404 248.506 2.03687 + vertex 911.664 243.386 2.90763 + endloop + endfacet + facet normal 0.27411 -0.147733 -0.950283 + outer loop + vertex 911.664 243.386 2.90763 + vertex 911.404 248.506 2.03687 + vertex 913.92 247.606 2.90257 + endloop + endfacet + facet normal 0.278626 -0.135584 -0.950781 + outer loop + vertex 911.404 248.506 2.03687 + vertex 913.457 252.724 2.03681 + vertex 913.92 247.606 2.90257 + endloop + endfacet + facet normal 0.276905 -0.135819 -0.95125 + outer loop + vertex 913.92 247.606 2.90257 + vertex 913.457 252.724 2.03681 + vertex 916.033 251.884 2.90659 + endloop + endfacet + facet normal 0.106516 -0.0494714 -0.99308 + outer loop + vertex 910.89 253.333 1.48575 + vertex 908.549 249.726 1.4144 + vertex 908.042 257.697 0.962891 + endloop + endfacet + facet normal 0.108865 -0.0582696 -0.992347 + outer loop + vertex 906.758 245.074 1.49105 + vertex 904.27 249.461 0.960437 + vertex 908.549 249.726 1.4144 + endloop + endfacet + facet normal 0.108369 -0.0493424 -0.992885 + outer loop + vertex 904.27 249.461 0.960437 + vertex 908.042 257.697 0.962891 + vertex 908.549 249.726 1.4144 + endloop + endfacet + facet normal 0.850143 -0.457315 0.260999 + outer loop + vertex 883.925 280.126 45.8729 + vertex 887.633 287.092 46.001 + vertex 883.834 281.37 48.3492 + endloop + endfacet + facet normal 0.849396 -0.452392 0.271787 + outer loop + vertex 883.834 281.37 48.3492 + vertex 887.633 287.092 46.001 + vertex 887.663 288.568 48.3636 + endloop + endfacet + facet normal 0.833285 -0.452089 0.318201 + outer loop + vertex 884.416 278.575 42.3849 + vertex 888.164 285.638 42.6048 + vertex 883.925 280.126 45.8729 + endloop + endfacet + facet normal 0.83309 -0.449369 0.322535 + outer loop + vertex 883.925 280.126 45.8729 + vertex 888.164 285.638 42.6048 + vertex 887.633 287.092 46.001 + endloop + endfacet + facet normal 0.819633 -0.444432 0.3615 + outer loop + vertex 885.333 276.675 37.9695 + vertex 889.109 283.904 38.2956 + vertex 884.416 278.575 42.3849 + endloop + endfacet + facet normal 0.819666 -0.446142 0.359311 + outer loop + vertex 884.416 278.575 42.3849 + vertex 889.109 283.904 38.2956 + vertex 888.164 285.638 42.6048 + endloop + endfacet + facet normal 0.803763 -0.436712 0.404039 + outer loop + vertex 886.433 274.249 33.1584 + vertex 890.346 281.76 33.4928 + vertex 885.333 276.675 37.9695 + endloop + endfacet + facet normal 0.803784 -0.438007 0.402593 + outer loop + vertex 885.333 276.675 37.9695 + vertex 890.346 281.76 33.4928 + vertex 889.109 283.904 38.2956 + endloop + endfacet + facet normal 0.751388 -0.373157 0.544214 + outer loop + vertex 892.5 276.952 26.0581 + vertex 894.328 280.763 26.1469 + vertex 891.594 277.882 27.9468 + endloop + endfacet + facet normal 0.753007 -0.378349 0.538361 + outer loop + vertex 891.594 277.882 27.9468 + vertex 894.328 280.763 26.1469 + vertex 893.412 281.666 28.0633 + endloop + endfacet + facet normal 0.73202 -0.394704 0.555297 + outer loop + vertex 890.577 273.242 25.9555 + vertex 892.5 276.952 26.0581 + vertex 889.719 274.247 27.8003 + endloop + endfacet + facet normal 0.733631 -0.400359 0.549089 + outer loop + vertex 889.719 274.247 27.8003 + vertex 892.5 276.952 26.0581 + vertex 891.594 277.882 27.9468 + endloop + endfacet + facet normal 0.581605 -0.289107 0.760363 + outer loop + vertex 894.783 275.302 23.2517 + vertex 896.621 279.204 23.329 + vertex 893.555 276.133 24.5072 + endloop + endfacet + facet normal 0.584888 -0.294089 0.755922 + outer loop + vertex 893.555 276.133 24.5072 + vertex 896.621 279.204 23.329 + vertex 895.393 279.996 24.5873 + endloop + endfacet + facet normal 0.567943 -0.306818 0.763743 + outer loop + vertex 892.853 271.528 23.1709 + vertex 894.783 275.302 23.2517 + vertex 891.626 272.392 24.4301 + endloop + endfacet + facet normal 0.569385 -0.309208 0.761703 + outer loop + vertex 891.626 272.392 24.4301 + vertex 894.783 275.302 23.2517 + vertex 893.555 276.133 24.5072 + endloop + endfacet + facet normal 0.336245 -0.182643 0.923894 + outer loop + vertex 897.675 272.893 21.4053 + vertex 899.527 276.851 21.5138 + vertex 896.166 274.266 22.2261 + endloop + endfacet + facet normal 0.334269 -0.179719 0.925184 + outer loop + vertex 896.166 274.266 22.2261 + vertex 899.527 276.851 21.5138 + vertex 898.008 278.198 22.3242 + endloop + endfacet + facet normal 0.333974 -0.196196 0.921937 + outer loop + vertex 895.737 269.074 21.2944 + vertex 897.675 272.893 21.4053 + vertex 894.234 270.46 22.1341 + endloop + endfacet + facet normal 0.330081 -0.189877 0.924658 + outer loop + vertex 894.234 270.46 22.1341 + vertex 897.675 272.893 21.4053 + vertex 896.166 274.266 22.2261 + endloop + endfacet + facet normal 0.450593 -0.249405 0.857183 + outer loop + vertex 894.234 270.46 22.1341 + vertex 896.166 274.266 22.2261 + vertex 892.853 271.528 23.1709 + endloop + endfacet + facet normal 0.450024 -0.248526 0.857737 + outer loop + vertex 892.853 271.528 23.1709 + vertex 896.166 274.266 22.2261 + vertex 894.783 275.302 23.2517 + endloop + endfacet + facet normal 0.458497 -0.23622 0.856726 + outer loop + vertex 896.166 274.266 22.2261 + vertex 898.008 278.198 22.3242 + vertex 894.783 275.302 23.2517 + endloop + endfacet + facet normal 0.455127 -0.231479 0.859812 + outer loop + vertex 894.783 275.302 23.2517 + vertex 898.008 278.198 22.3242 + vertex 896.621 279.204 23.329 + endloop + endfacet + facet normal 0.156783 -0.0989998 0.982659 + outer loop + vertex 901.099 269.383 20.2954 + vertex 902.539 273.321 20.4624 + vertex 899.268 271.202 20.7708 + endloop + endfacet + facet normal 0.159984 -0.104092 0.981616 + outer loop + vertex 899.268 271.202 20.7708 + vertex 902.539 273.321 20.4624 + vertex 901.136 275.173 20.8873 + endloop + endfacet + facet normal 0.154444 -0.11324 0.981491 + outer loop + vertex 898.657 265.512 20.233 + vertex 901.099 269.383 20.2954 + vertex 897.312 267.374 20.6595 + endloop + endfacet + facet normal 0.150455 -0.105453 0.982976 + outer loop + vertex 897.312 267.374 20.6595 + vertex 901.099 269.383 20.2954 + vertex 899.268 271.202 20.7708 + endloop + endfacet + facet normal 0.230612 -0.145796 0.962061 + outer loop + vertex 897.312 267.374 20.6595 + vertex 899.268 271.202 20.7708 + vertex 895.737 269.074 21.2944 + endloop + endfacet + facet normal 0.229936 -0.144589 0.962405 + outer loop + vertex 895.737 269.074 21.2944 + vertex 899.268 271.202 20.7708 + vertex 897.675 272.893 21.4053 + endloop + endfacet + facet normal 0.23557 -0.139078 0.961855 + outer loop + vertex 899.268 271.202 20.7708 + vertex 901.136 275.173 20.8873 + vertex 897.675 272.893 21.4053 + endloop + endfacet + facet normal 0.23344 -0.135616 0.962868 + outer loop + vertex 897.675 272.893 21.4053 + vertex 901.136 275.173 20.8873 + vertex 899.527 276.851 21.5138 + endloop + endfacet + facet normal 0.414806 -0.194877 0.888797 + outer loop + vertex 920.352 255.487 15.8067 + vertex 922.432 260.076 15.8419 + vertex 918.932 257.321 16.871 + endloop + endfacet + facet normal 0.415395 -0.195804 0.888317 + outer loop + vertex 918.932 257.321 16.871 + vertex 922.432 260.076 15.8419 + vertex 921.013 261.914 16.9104 + endloop + endfacet + facet normal 0.401148 -0.203639 0.893091 + outer loop + vertex 918.161 251.045 15.778 + vertex 920.352 255.487 15.8067 + vertex 916.763 252.891 16.8267 + endloop + endfacet + facet normal 0.402593 -0.206115 0.891872 + outer loop + vertex 916.763 252.891 16.8267 + vertex 920.352 255.487 15.8067 + vertex 918.932 257.321 16.871 + endloop + endfacet + facet normal 0.283475 -0.148328 0.947439 + outer loop + vertex 916.763 252.891 16.8267 + vertex 918.932 257.321 16.871 + vertex 915.538 254.885 17.5052 + endloop + endfacet + facet normal 0.276602 -0.13781 0.951052 + outer loop + vertex 915.538 254.885 17.5052 + vertex 918.932 257.321 16.871 + vertex 917.295 259.424 17.652 + endloop + endfacet + facet normal 0.279961 -0.134981 0.950475 + outer loop + vertex 918.932 257.321 16.871 + vertex 921.013 261.914 16.9104 + vertex 917.295 259.424 17.652 + endloop + endfacet + facet normal 0.29058 -0.152587 0.944606 + outer loop + vertex 917.295 259.424 17.652 + vertex 921.013 261.914 16.9104 + vertex 919.901 264.027 17.5937 + endloop + endfacet + facet normal 0.628034 -0.29724 0.719181 + outer loop + vertex 923.309 254.196 13.1858 + vertex 924.203 256.498 13.3567 + vertex 921.675 253.734 14.4218 + endloop + endfacet + facet normal 0.641774 -0.281797 0.713244 + outer loop + vertex 925.454 258.944 13.1977 + vertex 923.815 258.372 14.4461 + vertex 924.203 256.498 13.3567 + endloop + endfacet + facet normal 0.624439 -0.291914 0.724474 + outer loop + vertex 923.815 258.372 14.4461 + vertex 921.675 253.734 14.4218 + vertex 924.203 256.498 13.3567 + endloop + endfacet + facet normal 0.615013 -0.315175 0.722789 + outer loop + vertex 921.029 249.562 13.1721 + vertex 921.978 251.802 13.3411 + vertex 919.417 249.232 14.3999 + endloop + endfacet + facet normal 0.62793 -0.302454 0.717095 + outer loop + vertex 923.309 254.196 13.1858 + vertex 921.675 253.734 14.4218 + vertex 921.978 251.802 13.3411 + endloop + endfacet + facet normal 0.612193 -0.31056 0.727167 + outer loop + vertex 921.675 253.734 14.4218 + vertex 919.417 249.232 14.3999 + vertex 921.978 251.802 13.3411 + endloop + endfacet + facet normal 0.515605 -0.262549 0.81561 + outer loop + vertex 919.417 249.232 14.3999 + vertex 921.675 253.734 14.4218 + vertex 918.161 251.045 15.778 + endloop + endfacet + facet normal 0.513571 -0.25861 0.818148 + outer loop + vertex 918.161 251.045 15.778 + vertex 921.675 253.734 14.4218 + vertex 920.352 255.487 15.8067 + endloop + endfacet + facet normal 0.525378 -0.246679 0.814326 + outer loop + vertex 921.675 253.734 14.4218 + vertex 923.815 258.372 14.4461 + vertex 920.352 255.487 15.8067 + endloop + endfacet + facet normal 0.523658 -0.243665 0.816339 + outer loop + vertex 920.352 255.487 15.8067 + vertex 923.815 258.372 14.4461 + vertex 922.432 260.076 15.8419 + endloop + endfacet + facet normal 0.91316 -0.403066 -0.0606343 + outer loop + vertex 925.024 255.285 8.96172 + vertex 926.086 257.689 8.96361 + vertex 925.079 255.247 10.0403 + endloop + endfacet + facet normal 0.91202 -0.404844 -0.0657331 + outer loop + vertex 925.079 255.247 10.0403 + vertex 926.086 257.689 8.96361 + vertex 926.149 257.656 10.0429 + endloop + endfacet + facet normal 0.906271 -0.419155 -0.0546015 + outer loop + vertex 923.915 252.886 8.96008 + vertex 925.024 255.285 8.96172 + vertex 923.962 252.849 10.0379 + endloop + endfacet + facet normal 0.904875 -0.421306 -0.0608487 + outer loop + vertex 923.962 252.849 10.0379 + vertex 925.024 255.285 8.96172 + vertex 925.079 255.247 10.0403 + endloop + endfacet + facet normal 0.895845 -0.417307 0.152701 + outer loop + vertex 923.962 252.849 10.0379 + vertex 925.079 255.247 10.0403 + vertex 923.857 253.028 11.1487 + endloop + endfacet + facet normal 0.895955 -0.416221 0.154996 + outer loop + vertex 923.857 253.028 11.1487 + vertex 925.079 255.247 10.0403 + vertex 924.973 255.432 11.1522 + endloop + endfacet + facet normal 0.903122 -0.401133 0.153173 + outer loop + vertex 925.079 255.247 10.0403 + vertex 926.149 257.656 10.0429 + vertex 924.973 255.432 11.1522 + endloop + endfacet + facet normal 0.90299 -0.402578 0.150135 + outer loop + vertex 924.973 255.432 11.1522 + vertex 926.149 257.656 10.0429 + vertex 926.045 257.839 11.1559 + endloop + endfacet + facet normal 0.900268 -0.432482 -0.0497648 + outer loop + vertex 922.781 250.526 8.95816 + vertex 923.915 252.886 8.96008 + vertex 922.822 250.488 10.0352 + endloop + endfacet + facet normal 0.899134 -0.434228 -0.0548103 + outer loop + vertex 922.822 250.488 10.0352 + vertex 923.915 252.886 8.96008 + vertex 923.962 252.849 10.0379 + endloop + endfacet + facet normal 0.893718 -0.446804 -0.0404269 + outer loop + vertex 921.638 248.241 8.95636 + vertex 922.781 250.526 8.95816 + vertex 921.673 248.212 10.0332 + endloop + endfacet + facet normal 0.891515 -0.450218 -0.0500457 + outer loop + vertex 921.673 248.212 10.0332 + vertex 922.781 250.526 8.95816 + vertex 922.822 250.488 10.0352 + endloop + endfacet + facet normal 0.881428 -0.445302 0.157454 + outer loop + vertex 921.673 248.212 10.0332 + vertex 922.822 250.488 10.0352 + vertex 921.563 248.386 11.1415 + endloop + endfacet + facet normal 0.881767 -0.442723 0.16274 + outer loop + vertex 921.563 248.386 11.1415 + vertex 922.822 250.488 10.0352 + vertex 922.71 250.673 11.1448 + endloop + endfacet + facet normal 0.88861 -0.429397 0.161216 + outer loop + vertex 922.822 250.488 10.0352 + vertex 923.962 252.849 10.0379 + vertex 922.71 250.673 11.1448 + endloop + endfacet + facet normal 0.888245 -0.432628 0.154451 + outer loop + vertex 922.71 250.673 11.1448 + vertex 923.962 252.849 10.0379 + vertex 923.857 253.028 11.1487 + endloop + endfacet + facet normal 0.840732 -0.409823 0.353858 + outer loop + vertex 922.71 250.673 11.1448 + vertex 923.857 253.028 11.1487 + vertex 922.467 251.124 12.2458 + endloop + endfacet + facet normal 0.840531 -0.408567 0.355783 + outer loop + vertex 922.467 251.124 12.2458 + vertex 923.857 253.028 11.1487 + vertex 923.61 253.481 12.2509 + endloop + endfacet + facet normal 0.833879 -0.418984 0.359301 + outer loop + vertex 921.563 248.386 11.1415 + vertex 922.71 250.673 11.1448 + vertex 921.316 248.838 12.241 + endloop + endfacet + facet normal 0.83411 -0.420639 0.356825 + outer loop + vertex 921.316 248.838 12.241 + vertex 922.71 250.673 11.1448 + vertex 922.467 251.124 12.2458 + endloop + endfacet + facet normal 0.756842 -0.382107 0.530268 + outer loop + vertex 921.316 248.838 12.241 + vertex 922.467 251.124 12.2458 + vertex 921.029 249.562 13.1721 + endloop + endfacet + facet normal 0.749103 -0.359452 0.556452 + outer loop + vertex 921.029 249.562 13.1721 + vertex 922.467 251.124 12.2458 + vertex 921.978 251.802 13.3411 + endloop + endfacet + facet normal 0.746363 -0.363317 0.557623 + outer loop + vertex 922.467 251.124 12.2458 + vertex 923.61 253.481 12.2509 + vertex 921.978 251.802 13.3411 + endloop + endfacet + facet normal 0.752356 -0.383375 0.535709 + outer loop + vertex 921.978 251.802 13.3411 + vertex 923.61 253.481 12.2509 + vertex 923.309 254.196 13.1858 + endloop + endfacet + facet normal 0.857139 -0.382446 0.345032 + outer loop + vertex 924.973 255.432 11.1522 + vertex 926.045 257.839 11.1559 + vertex 924.724 255.87 12.2569 + endloop + endfacet + facet normal 0.857173 -0.382629 0.344745 + outer loop + vertex 924.724 255.87 12.2569 + vertex 926.045 257.839 11.1559 + vertex 925.791 258.265 12.2619 + endloop + endfacet + facet normal 0.848792 -0.394611 0.3519 + outer loop + vertex 923.857 253.028 11.1487 + vertex 924.973 255.432 11.1522 + vertex 923.61 253.481 12.2509 + endloop + endfacet + facet normal 0.849141 -0.396582 0.348831 + outer loop + vertex 923.61 253.481 12.2509 + vertex 924.973 255.432 11.1522 + vertex 924.724 255.87 12.2569 + endloop + endfacet + facet normal 0.771241 -0.360722 0.524469 + outer loop + vertex 923.61 253.481 12.2509 + vertex 924.724 255.87 12.2569 + vertex 923.309 254.196 13.1858 + endloop + endfacet + facet normal 0.7619 -0.336902 0.553178 + outer loop + vertex 923.309 254.196 13.1858 + vertex 924.724 255.87 12.2569 + vertex 924.203 256.498 13.3567 + endloop + endfacet + facet normal 0.760052 -0.33979 0.553953 + outer loop + vertex 924.724 255.87 12.2569 + vertex 925.791 258.265 12.2619 + vertex 924.203 256.498 13.3567 + endloop + endfacet + facet normal 0.765878 -0.356852 0.534871 + outer loop + vertex 924.203 256.498 13.3567 + vertex 925.791 258.265 12.2619 + vertex 925.454 258.944 13.1977 + endloop + endfacet + facet normal 0.590743 -0.269523 -0.760513 + outer loop + vertex 922.461 256.116 4.97585 + vertex 923.614 258.239 5.1191 + vertex 923.533 255.796 5.9221 + endloop + endfacet + facet normal 0.610685 -0.265435 -0.746062 + outer loop + vertex 923.533 255.796 5.9221 + vertex 923.614 258.239 5.1191 + vertex 924.572 258.186 5.92272 + endloop + endfacet + facet normal 0.617829 -0.263934 -0.740693 + outer loop + vertex 921.509 253.495 5.11558 + vertex 922.461 256.116 4.97585 + vertex 922.441 253.412 5.92299 + endloop + endfacet + facet normal 0.590335 -0.270647 -0.760431 + outer loop + vertex 922.441 253.412 5.92299 + vertex 922.461 256.116 4.97585 + vertex 923.533 255.796 5.9221 + endloop + endfacet + facet normal 0.718186 -0.329145 -0.613084 + outer loop + vertex 922.441 253.412 5.92299 + vertex 923.533 255.796 5.9221 + vertex 923.189 253.229 6.89771 + endloop + endfacet + facet normal 0.717185 -0.329404 -0.614117 + outer loop + vertex 923.189 253.229 6.89771 + vertex 923.533 255.796 5.9221 + vertex 924.288 255.622 6.89765 + endloop + endfacet + facet normal 0.722669 -0.314179 -0.615663 + outer loop + vertex 923.533 255.796 5.9221 + vertex 924.572 258.186 5.92272 + vertex 924.288 255.622 6.89765 + endloop + endfacet + facet normal 0.721019 -0.314641 -0.617359 + outer loop + vertex 924.288 255.622 6.89765 + vertex 924.572 258.186 5.92272 + vertex 925.334 258.017 6.89855 + endloop + endfacet + facet normal 0.586458 -0.29459 -0.754509 + outer loop + vertex 920.309 251.462 4.97704 + vertex 921.509 253.495 5.11558 + vertex 921.331 251.075 5.92262 + endloop + endfacet + facet normal 0.611479 -0.290283 -0.73609 + outer loop + vertex 921.331 251.075 5.92262 + vertex 921.509 253.495 5.11558 + vertex 922.441 253.412 5.92299 + endloop + endfacet + facet normal 0.614682 -0.284543 -0.735664 + outer loop + vertex 919.322 248.969 5.11628 + vertex 920.309 251.462 4.97704 + vertex 920.217 248.819 5.92238 + endloop + endfacet + facet normal 0.588233 -0.290446 -0.754733 + outer loop + vertex 920.217 248.819 5.92238 + vertex 920.309 251.462 4.97704 + vertex 921.331 251.075 5.92262 + endloop + endfacet + facet normal 0.71157 -0.351377 -0.608442 + outer loop + vertex 920.217 248.819 5.92238 + vertex 921.331 251.075 5.92262 + vertex 920.939 248.596 6.89579 + endloop + endfacet + facet normal 0.709903 -0.351785 -0.610152 + outer loop + vertex 920.939 248.596 6.89579 + vertex 921.331 251.075 5.92262 + vertex 922.068 250.874 6.8964 + endloop + endfacet + facet normal 0.714875 -0.339407 -0.611356 + outer loop + vertex 921.331 251.075 5.92262 + vertex 922.441 253.412 5.92299 + vertex 922.068 250.874 6.8964 + endloop + endfacet + facet normal 0.71424 -0.339565 -0.612011 + outer loop + vertex 922.068 250.874 6.8964 + vertex 922.441 253.412 5.92299 + vertex 923.189 253.229 6.89771 + endloop + endfacet + facet normal 0.807935 -0.384246 -0.446763 + outer loop + vertex 922.068 250.874 6.8964 + vertex 923.189 253.229 6.89771 + vertex 922.541 250.684 7.91486 + endloop + endfacet + facet normal 0.803132 -0.385893 -0.453944 + outer loop + vertex 922.541 250.684 7.91486 + vertex 923.189 253.229 6.89771 + vertex 923.675 253.042 7.91562 + endloop + endfacet + facet normal 0.803045 -0.398006 -0.44352 + outer loop + vertex 920.939 248.596 6.89579 + vertex 922.068 250.874 6.8964 + vertex 921.404 248.399 7.91377 + endloop + endfacet + facet normal 0.801176 -0.398652 -0.446312 + outer loop + vertex 921.404 248.399 7.91377 + vertex 922.068 250.874 6.8964 + vertex 922.541 250.684 7.91486 + endloop + endfacet + facet normal 0.864488 -0.430261 -0.259877 + outer loop + vertex 921.404 248.399 7.91377 + vertex 922.541 250.684 7.91486 + vertex 921.638 248.241 8.95636 + endloop + endfacet + facet normal 0.862908 -0.431224 -0.263506 + outer loop + vertex 921.638 248.241 8.95636 + vertex 922.541 250.684 7.91486 + vertex 922.781 250.526 8.95816 + endloop + endfacet + facet normal 0.869587 -0.417897 -0.263023 + outer loop + vertex 922.541 250.684 7.91486 + vertex 923.675 253.042 7.91562 + vertex 922.781 250.526 8.95816 + endloop + endfacet + facet normal 0.869887 -0.417713 -0.262321 + outer loop + vertex 922.781 250.526 8.95816 + vertex 923.675 253.042 7.91562 + vertex 923.915 252.886 8.96008 + endloop + endfacet + facet normal 0.815599 -0.356006 -0.456133 + outer loop + vertex 924.288 255.622 6.89765 + vertex 925.334 258.017 6.89855 + vertex 924.778 255.438 7.91647 + endloop + endfacet + facet normal 0.813662 -0.356728 -0.45902 + outer loop + vertex 924.778 255.438 7.91647 + vertex 925.334 258.017 6.89855 + vertex 925.831 257.838 7.91784 + endloop + endfacet + facet normal 0.809502 -0.371798 -0.454392 + outer loop + vertex 923.189 253.229 6.89771 + vertex 924.288 255.622 6.89765 + vertex 923.675 253.042 7.91562 + endloop + endfacet + facet normal 0.808631 -0.372104 -0.455691 + outer loop + vertex 923.675 253.042 7.91562 + vertex 924.288 255.622 6.89765 + vertex 924.778 255.438 7.91647 + endloop + endfacet + facet normal 0.876723 -0.403519 -0.261779 + outer loop + vertex 923.675 253.042 7.91562 + vertex 924.778 255.438 7.91647 + vertex 923.915 252.886 8.96008 + endloop + endfacet + facet normal 0.87505 -0.404569 -0.265729 + outer loop + vertex 923.915 252.886 8.96008 + vertex 924.778 255.438 7.91647 + vertex 925.024 255.285 8.96172 + endloop + endfacet + facet normal 0.883036 -0.387277 -0.265073 + outer loop + vertex 924.778 255.438 7.91647 + vertex 925.831 257.838 7.91784 + vertex 925.024 255.285 8.96172 + endloop + endfacet + facet normal 0.880901 -0.38866 -0.270105 + outer loop + vertex 925.024 255.285 8.96172 + vertex 925.831 257.838 7.91784 + vertex 926.086 257.689 8.96361 + endloop + endfacet + facet normal 0.375625 -0.159213 -0.912994 + outer loop + vertex 918.05 256.301 2.90745 + vertex 919.979 260.887 2.9016 + vertex 920.565 255.616 4.06167 + endloop + endfacet + facet normal 0.374627 -0.159406 -0.91337 + outer loop + vertex 920.565 255.616 4.06167 + vertex 919.979 260.887 2.9016 + vertex 922.562 260.308 4.06225 + endloop + endfacet + facet normal 0.376303 -0.171645 -0.910458 + outer loop + vertex 916.033 251.884 2.90659 + vertex 918.05 256.301 2.90745 + vertex 918.469 251.1 4.06142 + endloop + endfacet + facet normal 0.371674 -0.172408 -0.912214 + outer loop + vertex 918.469 251.1 4.06142 + vertex 918.05 256.301 2.90745 + vertex 920.565 255.616 4.06167 + endloop + endfacet + facet normal 0.467684 -0.217555 -0.856704 + outer loop + vertex 921.509 253.495 5.11558 + vertex 920.309 251.462 4.97704 + vertex 920.565 255.616 4.06167 + endloop + endfacet + facet normal 0.469649 -0.233568 -0.851396 + outer loop + vertex 919.322 248.969 5.11628 + vertex 918.469 251.1 4.06142 + vertex 920.309 251.462 4.97704 + endloop + endfacet + facet normal 0.468829 -0.217491 -0.856094 + outer loop + vertex 918.469 251.1 4.06142 + vertex 920.565 255.616 4.06167 + vertex 920.309 251.462 4.97704 + endloop + endfacet + facet normal 0.472399 -0.198621 -0.858714 + outer loop + vertex 923.614 258.239 5.1191 + vertex 922.461 256.116 4.97585 + vertex 922.562 260.308 4.06225 + endloop + endfacet + facet normal 0.469704 -0.216269 -0.855924 + outer loop + vertex 921.509 253.495 5.11558 + vertex 920.565 255.616 4.06167 + vertex 922.461 256.116 4.97585 + endloop + endfacet + facet normal 0.467703 -0.199045 -0.861182 + outer loop + vertex 920.565 255.616 4.06167 + vertex 922.562 260.308 4.06225 + vertex 922.461 256.116 4.97585 + endloop + endfacet + facet normal 0.174319 -0.078516 -0.981554 + outer loop + vertex 912.396 258.149 1.41429 + vertex 914.56 261.997 1.49076 + vertex 915.408 257.059 2.0364 + endloop + endfacet + facet normal 0.185046 -0.0764738 -0.97975 + outer loop + vertex 915.408 257.059 2.0364 + vertex 914.56 261.997 1.49076 + vertex 917.256 261.551 2.03497 + endloop + endfacet + facet normal 0.192353 -0.0746621 -0.978482 + outer loop + vertex 910.89 253.333 1.48575 + vertex 912.396 258.149 1.41429 + vertex 913.457 252.724 2.03681 + endloop + endfacet + facet normal 0.174309 -0.0785421 -0.981554 + outer loop + vertex 913.457 252.724 2.03681 + vertex 912.396 258.149 1.41429 + vertex 915.408 257.059 2.0364 + endloop + endfacet + facet normal 0.28017 -0.126182 -0.951621 + outer loop + vertex 913.457 252.724 2.03681 + vertex 915.408 257.059 2.0364 + vertex 916.033 251.884 2.90659 + endloop + endfacet + facet normal 0.277666 -0.126599 -0.952299 + outer loop + vertex 916.033 251.884 2.90659 + vertex 915.408 257.059 2.0364 + vertex 918.05 256.301 2.90745 + endloop + endfacet + facet normal 0.280872 -0.115906 -0.952721 + outer loop + vertex 915.408 257.059 2.0364 + vertex 917.256 261.551 2.03497 + vertex 918.05 256.301 2.90745 + endloop + endfacet + facet normal 0.275208 -0.117014 -0.954237 + outer loop + vertex 918.05 256.301 2.90745 + vertex 917.256 261.551 2.03497 + vertex 919.979 260.887 2.9016 + endloop + endfacet + facet normal 0.108981 -0.0415443 -0.993175 + outer loop + vertex 914.56 261.997 1.49076 + vertex 912.396 258.149 1.41429 + vertex 911.369 266.326 0.959542 + endloop + endfacet + facet normal 0.107988 -0.0484975 -0.992969 + outer loop + vertex 910.89 253.333 1.48575 + vertex 908.042 257.697 0.962891 + vertex 912.396 258.149 1.41429 + endloop + endfacet + facet normal 0.107327 -0.0417616 -0.993346 + outer loop + vertex 908.042 257.697 0.962891 + vertex 911.369 266.326 0.959542 + vertex 912.396 258.149 1.41429 + endloop + endfacet + facet normal 0.885258 -0.399438 0.238258 + outer loop + vertex 887.633 287.092 46.001 + vertex 890.92 294.432 46.096 + vertex 887.663 288.568 48.3636 + endloop + endfacet + facet normal 0.88361 -0.391119 0.257408 + outer loop + vertex 887.663 288.568 48.3636 + vertex 890.92 294.432 46.096 + vertex 890.73 295.624 48.5581 + endloop + endfacet + facet normal 0.866862 -0.394792 0.30445 + outer loop + vertex 888.164 285.638 42.6048 + vertex 891.499 293.044 42.7108 + vertex 887.633 287.092 46.001 + endloop + endfacet + facet normal 0.866488 -0.391953 0.309146 + outer loop + vertex 887.633 287.092 46.001 + vertex 891.499 293.044 42.7108 + vertex 890.92 294.432 46.096 + endloop + endfacet + facet normal 0.853901 -0.390246 0.344328 + outer loop + vertex 889.109 283.904 38.2956 + vertex 892.48 291.423 38.458 + vertex 888.164 285.638 42.6048 + endloop + endfacet + facet normal 0.853846 -0.389514 0.345291 + outer loop + vertex 888.164 285.638 42.6048 + vertex 892.48 291.423 38.458 + vertex 891.499 293.044 42.7108 + endloop + endfacet + facet normal 0.837605 -0.384939 0.387607 + outer loop + vertex 890.346 281.76 33.4928 + vertex 893.778 289.435 33.7 + vertex 889.109 283.904 38.2956 + endloop + endfacet + facet normal 0.837534 -0.38387 0.388821 + outer loop + vertex 889.109 283.904 38.2956 + vertex 893.778 289.435 33.7 + vertex 892.48 291.423 38.458 + endloop + endfacet + facet normal 0.788019 -0.323746 0.523654 + outer loop + vertex 896.061 284.7 26.2297 + vertex 897.675 288.736 26.2967 + vertex 895.14 285.568 28.1529 + endloop + endfacet + facet normal 0.788633 -0.325371 0.52172 + outer loop + vertex 895.14 285.568 28.1529 + vertex 897.675 288.736 26.2967 + vertex 896.746 289.568 28.2202 + endloop + endfacet + facet normal 0.770057 -0.350222 0.533252 + outer loop + vertex 894.328 280.763 26.1469 + vertex 896.061 284.7 26.2297 + vertex 893.412 281.666 28.0633 + endloop + endfacet + facet normal 0.771262 -0.353743 0.529169 + outer loop + vertex 893.412 281.666 28.0633 + vertex 896.061 284.7 26.2297 + vertex 895.14 285.568 28.1529 + endloop + endfacet + facet normal 0.6094 -0.252607 0.751546 + outer loop + vertex 898.36 283.232 23.4173 + vertex 899.977 287.373 23.4976 + vertex 897.13 283.979 24.6656 + endloop + endfacet + facet normal 0.611323 -0.255042 0.749158 + outer loop + vertex 897.13 283.979 24.6656 + vertex 899.977 287.373 23.4976 + vertex 898.747 288.068 24.7383 + endloop + endfacet + facet normal 0.596399 -0.273967 0.754487 + outer loop + vertex 896.621 279.204 23.329 + vertex 898.36 283.232 23.4173 + vertex 895.393 279.996 24.5873 + endloop + endfacet + facet normal 0.597358 -0.275296 0.753243 + outer loop + vertex 895.393 279.996 24.5873 + vertex 898.36 283.232 23.4173 + vertex 897.13 283.979 24.6656 + endloop + endfacet + facet normal 0.344018 -0.158532 0.925483 + outer loop + vertex 901.279 280.943 21.6234 + vertex 902.911 285.15 21.7372 + vertex 899.748 282.265 22.4188 + endloop + endfacet + facet normal 0.34084 -0.154614 0.92732 + outer loop + vertex 899.748 282.265 22.4188 + vertex 902.911 285.15 21.7372 + vertex 901.369 286.442 22.5196 + endloop + endfacet + facet normal 0.341509 -0.170966 0.924198 + outer loop + vertex 899.527 276.851 21.5138 + vertex 901.279 280.943 21.6234 + vertex 898.008 278.198 22.3242 + endloop + endfacet + facet normal 0.337925 -0.166136 0.926394 + outer loop + vertex 898.008 278.198 22.3242 + vertex 901.279 280.943 21.6234 + vertex 899.748 282.265 22.4188 + endloop + endfacet + facet normal 0.463753 -0.218402 0.858623 + outer loop + vertex 898.008 278.198 22.3242 + vertex 899.748 282.265 22.4188 + vertex 896.621 279.204 23.329 + endloop + endfacet + facet normal 0.464435 -0.219275 0.858032 + outer loop + vertex 896.621 279.204 23.329 + vertex 899.748 282.265 22.4188 + vertex 898.36 283.232 23.4173 + endloop + endfacet + facet normal 0.47373 -0.204467 0.856606 + outer loop + vertex 899.748 282.265 22.4188 + vertex 901.369 286.442 22.5196 + vertex 898.36 283.232 23.4173 + endloop + endfacet + facet normal 0.470189 -0.200331 0.859529 + outer loop + vertex 898.36 283.232 23.4173 + vertex 901.369 286.442 22.5196 + vertex 899.977 287.373 23.4976 + endloop + endfacet + facet normal 0.166229 -0.089247 0.98204 + outer loop + vertex 904.785 277.494 20.527 + vertex 906.028 281.672 20.6964 + vertex 902.911 279.28 21.0067 + endloop + endfacet + facet normal 0.169287 -0.0933496 0.981136 + outer loop + vertex 902.911 279.28 21.0067 + vertex 906.028 281.672 20.6964 + vertex 904.565 283.515 21.1242 + endloop + endfacet + facet normal 0.162074 -0.10247 0.981444 + outer loop + vertex 902.539 273.321 20.4624 + vertex 904.785 277.494 20.527 + vertex 901.136 275.173 20.8873 + endloop + endfacet + facet normal 0.158806 -0.0971641 0.982517 + outer loop + vertex 901.136 275.173 20.8873 + vertex 904.785 277.494 20.527 + vertex 902.911 279.28 21.0067 + endloop + endfacet + facet normal 0.238187 -0.130873 0.962361 + outer loop + vertex 901.136 275.173 20.8873 + vertex 902.911 279.28 21.0067 + vertex 899.527 276.851 21.5138 + endloop + endfacet + facet normal 0.235266 -0.126534 0.963659 + outer loop + vertex 899.527 276.851 21.5138 + vertex 902.911 279.28 21.0067 + vertex 901.279 280.943 21.6234 + endloop + endfacet + facet normal 0.240855 -0.120809 0.963013 + outer loop + vertex 902.911 279.28 21.0067 + vertex 904.565 283.515 21.1242 + vertex 901.279 280.943 21.6234 + endloop + endfacet + facet normal 0.239537 -0.119017 0.963565 + outer loop + vertex 901.279 280.943 21.6234 + vertex 904.565 283.515 21.1242 + vertex 902.911 285.15 21.7372 + endloop + endfacet + facet normal 0.449428 -0.174197 0.876168 + outer loop + vertex 924.396 264.814 15.8735 + vertex 926.239 269.686 15.8967 + vertex 923.019 266.598 16.9342 + endloop + endfacet + facet normal 0.456335 -0.183222 0.87074 + outer loop + vertex 923.019 266.598 16.9342 + vertex 926.239 269.686 15.8967 + vertex 924.886 271.315 16.9485 + endloop + endfacet + facet normal 0.428556 -0.183533 0.884678 + outer loop + vertex 922.432 260.076 15.8419 + vertex 924.396 264.814 15.8735 + vertex 921.013 261.914 16.9104 + endloop + endfacet + facet normal 0.432945 -0.1899 0.88119 + outer loop + vertex 921.013 261.914 16.9104 + vertex 924.396 264.814 15.8735 + vertex 923.019 266.598 16.9342 + endloop + endfacet + facet normal 0.313302 -0.138958 0.939432 + outer loop + vertex 921.013 261.914 16.9104 + vertex 923.019 266.598 16.9342 + vertex 919.901 264.027 17.5937 + endloop + endfacet + facet normal 0.31493 -0.141156 0.93856 + outer loop + vertex 919.901 264.027 17.5937 + vertex 923.019 266.598 16.9342 + vertex 921.623 268.441 17.6801 + endloop + endfacet + facet normal 0.325955 -0.131826 0.936149 + outer loop + vertex 923.019 266.598 16.9342 + vertex 924.886 271.315 16.9485 + vertex 921.623 268.441 17.6801 + endloop + endfacet + facet normal 0.348439 -0.160581 0.923474 + outer loop + vertex 921.623 268.441 17.6801 + vertex 924.886 271.315 16.9485 + vertex 923.891 272.869 17.5941 + endloop + endfacet + facet normal 0.64886 -0.252415 0.717821 + outer loop + vertex 927.417 263.703 13.2163 + vertex 928.141 266.06 13.3905 + vertex 925.801 263.112 14.4694 + endloop + endfacet + facet normal 0.662318 -0.235608 0.711213 + outer loop + vertex 929.225 268.625 13.231 + vertex 927.647 268.001 14.4939 + vertex 928.141 266.06 13.3905 + endloop + endfacet + facet normal 0.644682 -0.247045 0.723432 + outer loop + vertex 927.647 268.001 14.4939 + vertex 925.801 263.112 14.4694 + vertex 928.141 266.06 13.3905 + endloop + endfacet + facet normal 0.641687 -0.278856 0.714477 + outer loop + vertex 925.454 258.944 13.1977 + vertex 926.257 261.24 13.3723 + vertex 923.815 258.372 14.4461 + endloop + endfacet + facet normal 0.649287 -0.260662 0.71448 + outer loop + vertex 927.417 263.703 13.2163 + vertex 925.801 263.112 14.4694 + vertex 926.257 261.24 13.3723 + endloop + endfacet + facet normal 0.635025 -0.269655 0.723898 + outer loop + vertex 925.801 263.112 14.4694 + vertex 923.815 258.372 14.4461 + vertex 926.257 261.24 13.3723 + endloop + endfacet + facet normal 0.537096 -0.229051 0.811827 + outer loop + vertex 923.815 258.372 14.4461 + vertex 925.801 263.112 14.4694 + vertex 922.432 260.076 15.8419 + endloop + endfacet + facet normal 0.536257 -0.227697 0.812762 + outer loop + vertex 922.432 260.076 15.8419 + vertex 925.801 263.112 14.4694 + vertex 924.396 264.814 15.8735 + endloop + endfacet + facet normal 0.550331 -0.211842 0.807625 + outer loop + vertex 925.801 263.112 14.4694 + vertex 927.647 268.001 14.4939 + vertex 924.396 264.814 15.8735 + endloop + endfacet + facet normal 0.550512 -0.21211 0.807432 + outer loop + vertex 924.396 264.814 15.8735 + vertex 927.647 268.001 14.4939 + vertex 926.239 269.686 15.8967 + endloop + endfacet + facet normal 0.939107 -0.335513 -0.0742254 + outer loop + vertex 928.981 264.893 8.96766 + vertex 929.866 267.368 8.96966 + vertex 929.057 264.865 10.0499 + endloop + endfacet + facet normal 0.937184 -0.338767 -0.0832094 + outer loop + vertex 929.057 264.865 10.0499 + vertex 929.866 267.368 8.96966 + vertex 929.95 267.335 10.052 + endloop + endfacet + facet normal 0.932465 -0.35491 -0.0674385 + outer loop + vertex 928.061 262.474 8.96627 + vertex 928.981 264.893 8.96766 + vertex 928.129 262.449 10.048 + endloop + endfacet + facet normal 0.930996 -0.357401 -0.0742316 + outer loop + vertex 928.129 262.449 10.048 + vertex 928.981 264.893 8.96766 + vertex 929.057 264.865 10.0499 + endloop + endfacet + facet normal 0.925023 -0.355267 0.134601 + outer loop + vertex 928.129 262.449 10.048 + vertex 929.057 264.865 10.0499 + vertex 928.034 262.622 11.1631 + endloop + endfacet + facet normal 0.92495 -0.356153 0.132749 + outer loop + vertex 928.034 262.622 11.1631 + vertex 929.057 264.865 10.0499 + vertex 928.962 265.036 11.1664 + endloop + endfacet + facet normal 0.932346 -0.337206 0.130473 + outer loop + vertex 929.057 264.865 10.0499 + vertex 929.95 267.335 10.052 + vertex 928.962 265.036 11.1664 + endloop + endfacet + facet normal 0.932266 -0.338375 0.127993 + outer loop + vertex 928.962 265.036 11.1664 + vertex 929.95 267.335 10.052 + vertex 929.858 267.503 11.1696 + endloop + endfacet + facet normal 0.925977 -0.371992 -0.0647204 + outer loop + vertex 927.099 260.082 8.96485 + vertex 928.061 262.474 8.96627 + vertex 927.164 260.054 10.0456 + endloop + endfacet + facet normal 0.92539 -0.372973 -0.0674093 + outer loop + vertex 927.164 260.054 10.0456 + vertex 928.061 262.474 8.96627 + vertex 928.129 262.449 10.048 + endloop + endfacet + facet normal 0.918801 -0.389223 -0.0656534 + outer loop + vertex 926.086 257.689 8.96361 + vertex 927.099 260.082 8.96485 + vertex 926.149 257.656 10.0429 + endloop + endfacet + facet normal 0.919004 -0.388897 -0.0647416 + outer loop + vertex 926.149 257.656 10.0429 + vertex 927.099 260.082 8.96485 + vertex 927.164 260.054 10.0456 + endloop + endfacet + facet normal 0.910698 -0.38562 0.148073 + outer loop + vertex 926.149 257.656 10.0429 + vertex 927.164 260.054 10.0456 + vertex 926.045 257.839 11.1559 + endloop + endfacet + facet normal 0.910546 -0.387324 0.14452 + outer loop + vertex 926.045 257.839 11.1559 + vertex 927.164 260.054 10.0456 + vertex 927.063 260.233 11.1594 + endloop + endfacet + facet normal 0.91797 -0.370197 0.142425 + outer loop + vertex 927.164 260.054 10.0456 + vertex 928.129 262.449 10.048 + vertex 927.063 260.233 11.1594 + endloop + endfacet + facet normal 0.917727 -0.37294 0.136724 + outer loop + vertex 927.063 260.233 11.1594 + vertex 928.129 262.449 10.048 + vertex 928.034 262.622 11.1631 + endloop + endfacet + facet normal 0.872418 -0.354841 0.336116 + outer loop + vertex 927.063 260.233 11.1594 + vertex 928.034 262.622 11.1631 + vertex 926.805 260.649 12.2678 + endloop + endfacet + facet normal 0.87194 -0.352453 0.339849 + outer loop + vertex 926.805 260.649 12.2678 + vertex 928.034 262.622 11.1631 + vertex 927.769 263.036 12.2716 + endloop + endfacet + facet normal 0.86495 -0.368233 0.340979 + outer loop + vertex 926.045 257.839 11.1559 + vertex 927.063 260.233 11.1594 + vertex 925.791 258.265 12.2619 + endloop + endfacet + facet normal 0.865101 -0.36903 0.33973 + outer loop + vertex 925.791 258.265 12.2619 + vertex 927.063 260.233 11.1594 + vertex 926.805 260.649 12.2678 + endloop + endfacet + facet normal 0.782811 -0.334466 0.524727 + outer loop + vertex 925.791 258.265 12.2619 + vertex 926.805 260.649 12.2678 + vertex 925.454 258.944 13.1977 + endloop + endfacet + facet normal 0.77351 -0.312568 0.551347 + outer loop + vertex 925.454 258.944 13.1977 + vertex 926.805 260.649 12.2678 + vertex 926.257 261.24 13.3723 + endloop + endfacet + facet normal 0.773274 -0.312974 0.551447 + outer loop + vertex 926.805 260.649 12.2678 + vertex 927.769 263.036 12.2716 + vertex 926.257 261.24 13.3723 + endloop + endfacet + facet normal 0.781244 -0.334723 0.526895 + outer loop + vertex 926.257 261.24 13.3723 + vertex 927.769 263.036 12.2716 + vertex 927.417 263.703 13.2163 + endloop + endfacet + facet normal 0.886906 -0.322188 0.331047 + outer loop + vertex 928.962 265.036 11.1664 + vertex 929.858 267.503 11.1696 + vertex 928.698 265.451 12.2784 + endloop + endfacet + facet normal 0.886258 -0.319481 0.335379 + outer loop + vertex 928.698 265.451 12.2784 + vertex 929.858 267.503 11.1696 + vertex 929.589 267.927 12.2827 + endloop + endfacet + facet normal 0.878752 -0.338651 0.336319 + outer loop + vertex 928.034 262.622 11.1631 + vertex 928.962 265.036 11.1664 + vertex 927.769 263.036 12.2716 + endloop + endfacet + facet normal 0.878867 -0.339183 0.335481 + outer loop + vertex 927.769 263.036 12.2716 + vertex 928.962 265.036 11.1664 + vertex 928.698 265.451 12.2784 + endloop + endfacet + facet normal 0.799236 -0.309043 0.515475 + outer loop + vertex 927.769 263.036 12.2716 + vertex 928.698 265.451 12.2784 + vertex 927.417 263.703 13.2163 + endloop + endfacet + facet normal 0.787009 -0.282339 0.548545 + outer loop + vertex 927.417 263.703 13.2163 + vertex 928.698 265.451 12.2784 + vertex 928.141 266.06 13.3905 + endloop + endfacet + facet normal 0.786184 -0.283839 0.548954 + outer loop + vertex 928.698 265.451 12.2784 + vertex 929.589 267.927 12.2827 + vertex 928.141 266.06 13.3905 + endloop + endfacet + facet normal 0.793911 -0.302634 0.527369 + outer loop + vertex 928.141 266.06 13.3905 + vertex 929.589 267.927 12.2827 + vertex 929.225 268.625 13.231 + endloop + endfacet + facet normal 0.595301 -0.223799 -0.771706 + outer loop + vertex 926.287 265.648 4.97775 + vertex 927.285 267.819 5.11814 + vertex 927.395 265.335 5.92322 + endloop + endfacet + facet normal 0.618579 -0.217373 -0.755056 + outer loop + vertex 927.395 265.335 5.92322 + vertex 927.285 267.819 5.11814 + vertex 928.257 267.786 5.92389 + endloop + endfacet + facet normal 0.619589 -0.215255 -0.754834 + outer loop + vertex 925.536 262.993 5.11875 + vertex 926.287 265.648 4.97775 + vertex 926.498 262.939 5.92339 + endloop + endfacet + facet normal 0.595549 -0.223025 -0.771739 + outer loop + vertex 926.498 262.939 5.92339 + vertex 926.287 265.648 4.97775 + vertex 927.395 265.335 5.92322 + endloop + endfacet + facet normal 0.731129 -0.273775 -0.624898 + outer loop + vertex 926.498 262.939 5.92339 + vertex 927.395 265.335 5.92322 + vertex 927.272 262.778 6.89983 + endloop + endfacet + facet normal 0.731174 -0.27376 -0.624852 + outer loop + vertex 927.272 262.778 6.89983 + vertex 927.395 265.335 5.92322 + vertex 928.174 265.185 6.9006 + endloop + endfacet + facet normal 0.735633 -0.258581 -0.626083 + outer loop + vertex 927.395 265.335 5.92322 + vertex 928.257 267.786 5.92389 + vertex 928.174 265.185 6.9006 + endloop + endfacet + facet normal 0.733356 -0.259385 -0.628418 + outer loop + vertex 928.174 265.185 6.9006 + vertex 928.257 267.786 5.92389 + vertex 929.047 267.65 6.90135 + endloop + endfacet + facet normal 0.59752 -0.247415 -0.762729 + outer loop + vertex 924.473 260.871 4.97438 + vertex 925.536 262.993 5.11875 + vertex 925.558 260.564 5.92401 + endloop + endfacet + facet normal 0.614424 -0.243224 -0.75055 + outer loop + vertex 925.558 260.564 5.92401 + vertex 925.536 262.993 5.11875 + vertex 926.498 262.939 5.92339 + endloop + endfacet + facet normal 0.615351 -0.242259 -0.750102 + outer loop + vertex 923.614 258.239 5.1191 + vertex 924.473 260.871 4.97438 + vertex 924.572 258.186 5.92272 + endloop + endfacet + facet normal 0.597533 -0.247376 -0.762732 + outer loop + vertex 924.572 258.186 5.92272 + vertex 924.473 260.871 4.97438 + vertex 925.558 260.564 5.92401 + endloop + endfacet + facet normal 0.725826 -0.300655 -0.618695 + outer loop + vertex 924.572 258.186 5.92272 + vertex 925.558 260.564 5.92401 + vertex 925.334 258.017 6.89855 + endloop + endfacet + facet normal 0.723724 -0.301292 -0.620843 + outer loop + vertex 925.334 258.017 6.89855 + vertex 925.558 260.564 5.92401 + vertex 926.326 260.398 6.89959 + endloop + endfacet + facet normal 0.728058 -0.288137 -0.622019 + outer loop + vertex 925.558 260.564 5.92401 + vertex 926.498 262.939 5.92339 + vertex 926.326 260.398 6.89959 + endloop + endfacet + facet normal 0.726459 -0.288655 -0.623647 + outer loop + vertex 926.326 260.398 6.89959 + vertex 926.498 262.939 5.92339 + vertex 927.272 262.778 6.89983 + endloop + endfacet + facet normal 0.823274 -0.327148 -0.463889 + outer loop + vertex 926.326 260.398 6.89959 + vertex 927.272 262.778 6.89983 + vertex 926.832 260.225 7.9189 + endloop + endfacet + facet normal 0.822881 -0.327312 -0.464471 + outer loop + vertex 926.832 260.225 7.9189 + vertex 927.272 262.778 6.89983 + vertex 927.783 262.613 7.92006 + endloop + endfacet + facet normal 0.819967 -0.341465 -0.459408 + outer loop + vertex 925.334 258.017 6.89855 + vertex 926.326 260.398 6.89959 + vertex 925.831 257.838 7.91784 + endloop + endfacet + facet normal 0.817209 -0.342556 -0.463493 + outer loop + vertex 925.831 257.838 7.91784 + vertex 926.326 260.398 6.89959 + vertex 926.832 260.225 7.9189 + endloop + endfacet + facet normal 0.888083 -0.372369 -0.269539 + outer loop + vertex 925.831 257.838 7.91784 + vertex 926.832 260.225 7.9189 + vertex 926.086 257.689 8.96361 + endloop + endfacet + facet normal 0.884659 -0.374649 -0.27752 + outer loop + vertex 926.086 257.689 8.96361 + vertex 926.832 260.225 7.9189 + vertex 927.099 260.082 8.96485 + endloop + endfacet + facet normal 0.89281 -0.355238 -0.27694 + outer loop + vertex 926.832 260.225 7.9189 + vertex 927.783 262.613 7.92006 + vertex 927.099 260.082 8.96485 + endloop + endfacet + facet normal 0.889771 -0.357315 -0.283961 + outer loop + vertex 927.099 260.082 8.96485 + vertex 927.783 262.613 7.92006 + vertex 928.061 262.474 8.96627 + endloop + endfacet + facet normal 0.830676 -0.293879 -0.472878 + outer loop + vertex 928.174 265.185 6.9006 + vertex 929.047 267.65 6.90135 + vertex 928.7 265.029 7.92061 + endloop + endfacet + facet normal 0.828044 -0.295038 -0.476755 + outer loop + vertex 928.7 265.029 7.92061 + vertex 929.047 267.65 6.90135 + vertex 929.581 267.501 7.9216 + endloop + endfacet + facet normal 0.829129 -0.310514 -0.464894 + outer loop + vertex 927.272 262.778 6.89983 + vertex 928.174 265.185 6.9006 + vertex 927.783 262.613 7.92006 + endloop + endfacet + facet normal 0.824072 -0.312703 -0.472359 + outer loop + vertex 927.783 262.613 7.92006 + vertex 928.174 265.185 6.9006 + vertex 928.7 265.029 7.92061 + endloop + endfacet + facet normal 0.896576 -0.340267 -0.283497 + outer loop + vertex 927.783 262.613 7.92006 + vertex 928.7 265.029 7.92061 + vertex 928.061 262.474 8.96627 + endloop + endfacet + facet normal 0.895782 -0.340821 -0.285336 + outer loop + vertex 928.061 262.474 8.96627 + vertex 928.7 265.029 7.92061 + vertex 928.981 264.893 8.96766 + endloop + endfacet + facet normal 0.902952 -0.321823 -0.284793 + outer loop + vertex 928.7 265.029 7.92061 + vertex 929.581 267.501 7.9216 + vertex 928.981 264.893 8.96766 + endloop + endfacet + facet normal 0.902393 -0.322223 -0.28611 + outer loop + vertex 928.981 264.893 8.96766 + vertex 929.581 267.501 7.9216 + vertex 929.866 267.368 8.96966 + endloop + endfacet + facet normal 0.377023 -0.127523 -0.917383 + outer loop + vertex 921.769 265.613 2.90549 + vertex 923.404 270.44 2.90651 + vertex 924.401 265.077 4.06184 + endloop + endfacet + facet normal 0.372674 -0.128679 -0.918997 + outer loop + vertex 924.401 265.077 4.06184 + vertex 923.404 270.44 2.90651 + vertex 926.076 269.943 4.05974 + endloop + endfacet + facet normal 0.378839 -0.142694 -0.914396 + outer loop + vertex 919.979 260.887 2.9016 + vertex 921.769 265.613 2.90549 + vertex 922.562 260.308 4.06225 + endloop + endfacet + facet normal 0.373276 -0.14398 -0.916479 + outer loop + vertex 922.562 260.308 4.06225 + vertex 921.769 265.613 2.90549 + vertex 924.401 265.077 4.06184 + endloop + endfacet + facet normal 0.474164 -0.178864 -0.862077 + outer loop + vertex 925.536 262.993 5.11875 + vertex 924.473 260.871 4.97438 + vertex 924.401 265.077 4.06184 + endloop + endfacet + facet normal 0.469516 -0.200652 -0.859822 + outer loop + vertex 923.614 258.239 5.1191 + vertex 922.562 260.308 4.06225 + vertex 924.473 260.871 4.97438 + endloop + endfacet + facet normal 0.466387 -0.179871 -0.8661 + outer loop + vertex 922.562 260.308 4.06225 + vertex 924.401 265.077 4.06184 + vertex 924.473 260.871 4.97438 + endloop + endfacet + facet normal 0.473617 -0.161771 -0.865747 + outer loop + vertex 927.285 267.819 5.11814 + vertex 926.287 265.648 4.97775 + vertex 926.076 269.943 4.05974 + endloop + endfacet + facet normal 0.473199 -0.179583 -0.862457 + outer loop + vertex 925.536 262.993 5.11875 + vertex 924.401 265.077 4.06184 + vertex 926.287 265.648 4.97775 + endloop + endfacet + facet normal 0.470372 -0.162287 -0.867418 + outer loop + vertex 924.401 265.077 4.06184 + vertex 926.076 269.943 4.05974 + vertex 926.287 265.648 4.97775 + endloop + endfacet + facet normal 0.174886 -0.065961 -0.982377 + outer loop + vertex 915.815 267.087 1.41223 + vertex 917.791 271.22 1.48648 + vertex 918.991 266.196 2.03731 + endloop + endfacet + facet normal 0.187642 -0.0626812 -0.980235 + outer loop + vertex 918.991 266.196 2.03731 + vertex 917.791 271.22 1.48648 + vertex 920.58 270.958 2.03702 + endloop + endfacet + facet normal 0.187651 -0.0614287 -0.980313 + outer loop + vertex 914.56 261.997 1.49076 + vertex 915.815 267.087 1.41223 + vertex 917.256 261.551 2.03497 + endloop + endfacet + facet normal 0.175185 -0.0649077 -0.982394 + outer loop + vertex 917.256 261.551 2.03497 + vertex 915.815 267.087 1.41223 + vertex 918.991 266.196 2.03731 + endloop + endfacet + facet normal 0.278662 -0.103554 -0.95479 + outer loop + vertex 917.256 261.551 2.03497 + vertex 918.991 266.196 2.03731 + vertex 919.979 260.887 2.9016 + endloop + endfacet + facet normal 0.276731 -0.103997 -0.955303 + outer loop + vertex 919.979 260.887 2.9016 + vertex 918.991 266.196 2.03731 + vertex 921.769 265.613 2.90549 + endloop + endfacet + facet normal 0.279127 -0.0932104 -0.95572 + outer loop + vertex 918.991 266.196 2.03731 + vertex 920.58 270.958 2.03702 + vertex 921.769 265.613 2.90549 + endloop + endfacet + facet normal 0.277236 -0.0937121 -0.956221 + outer loop + vertex 921.769 265.613 2.90549 + vertex 920.58 270.958 2.03702 + vertex 923.404 270.44 2.90651 + endloop + endfacet + facet normal 0.106417 -0.0330233 -0.993773 + outer loop + vertex 917.791 271.22 1.48648 + vertex 915.815 267.087 1.41223 + vertex 914.204 275.409 0.963103 + endloop + endfacet + facet normal 0.108304 -0.0420498 -0.993228 + outer loop + vertex 914.56 261.997 1.49076 + vertex 911.369 266.326 0.959542 + vertex 915.815 267.087 1.41223 + endloop + endfacet + facet normal 0.106799 -0.0329472 -0.993735 + outer loop + vertex 911.369 266.326 0.959542 + vertex 914.204 275.409 0.963103 + vertex 915.815 267.087 1.41223 + endloop + endfacet + facet normal 0.914639 -0.331736 0.231057 + outer loop + vertex 890.92 294.432 46.096 + vertex 893.699 302.143 46.1632 + vertex 890.73 295.624 48.5581 + endloop + endfacet + facet normal 0.911953 -0.321963 0.254328 + outer loop + vertex 890.73 295.624 48.5581 + vertex 893.699 302.143 46.1632 + vertex 893.603 303.729 48.5166 + endloop + endfacet + facet normal 0.897982 -0.331267 0.28964 + outer loop + vertex 891.499 293.044 42.7108 + vertex 894.328 300.767 42.7749 + vertex 890.92 294.432 46.096 + endloop + endfacet + facet normal 0.896951 -0.325949 0.298725 + outer loop + vertex 890.92 294.432 46.096 + vertex 894.328 300.767 42.7749 + vertex 893.699 302.143 46.1632 + endloop + endfacet + facet normal 0.884573 -0.329927 0.329665 + outer loop + vertex 892.48 291.423 38.458 + vertex 895.348 299.205 38.55 + vertex 891.499 293.044 42.7108 + endloop + endfacet + facet normal 0.884111 -0.326557 0.334228 + outer loop + vertex 891.499 293.044 42.7108 + vertex 895.348 299.205 38.55 + vertex 894.328 300.767 42.7749 + endloop + endfacet + facet normal 0.868881 -0.325473 0.372978 + outer loop + vertex 893.778 289.435 33.7 + vertex 896.69 297.34 33.8137 + vertex 892.48 291.423 38.458 + endloop + endfacet + facet normal 0.868776 -0.324628 0.373959 + outer loop + vertex 892.48 291.423 38.458 + vertex 896.69 297.34 33.8137 + vertex 895.348 299.205 38.55 + endloop + endfacet + facet normal 0.817313 -0.269025 0.509534 + outer loop + vertex 899.152 292.861 26.3692 + vertex 900.476 297.014 26.4378 + vertex 898.218 293.645 28.2815 + endloop + endfacet + facet normal 0.817597 -0.269644 0.508751 + outer loop + vertex 898.218 293.645 28.2815 + vertex 900.476 297.014 26.4378 + vertex 899.536 297.755 28.3412 + endloop + endfacet + facet normal 0.803279 -0.296751 0.516413 + outer loop + vertex 897.675 288.736 26.2967 + vertex 899.152 292.861 26.3692 + vertex 896.746 289.568 28.2202 + endloop + endfacet + facet normal 0.803819 -0.298035 0.514831 + outer loop + vertex 896.746 289.568 28.2202 + vertex 899.152 292.861 26.3692 + vertex 898.218 293.645 28.2815 + endloop + endfacet + facet normal 0.632456 -0.212647 0.744836 + outer loop + vertex 901.455 291.589 23.5861 + vertex 902.774 295.823 23.6751 + vertex 900.226 292.235 24.8143 + endloop + endfacet + facet normal 0.632985 -0.213217 0.744224 + outer loop + vertex 900.226 292.235 24.8143 + vertex 902.774 295.823 23.6751 + vertex 901.549 296.431 24.8909 + endloop + endfacet + facet normal 0.621802 -0.233588 0.747528 + outer loop + vertex 899.977 287.373 23.4976 + vertex 901.455 291.589 23.5861 + vertex 898.747 288.068 24.7383 + endloop + endfacet + facet normal 0.622632 -0.234551 0.746536 + outer loop + vertex 898.747 288.068 24.7383 + vertex 901.455 291.589 23.5861 + vertex 900.226 292.235 24.8143 + endloop + endfacet + facet normal 0.353908 -0.132137 0.925899 + outer loop + vertex 904.403 289.445 21.8427 + vertex 905.733 293.759 21.95 + vertex 902.848 290.701 22.6165 + endloop + endfacet + facet normal 0.351088 -0.12915 0.927393 + outer loop + vertex 902.848 290.701 22.6165 + vertex 905.733 293.759 21.95 + vertex 904.166 294.978 22.713 + endloop + endfacet + facet normal 0.34906 -0.143985 0.925973 + outer loop + vertex 902.911 285.15 21.7372 + vertex 904.403 289.445 21.8427 + vertex 901.369 286.442 22.5196 + endloop + endfacet + facet normal 0.346923 -0.141561 0.927149 + outer loop + vertex 901.369 286.442 22.5196 + vertex 904.403 289.445 21.8427 + vertex 902.848 290.701 22.6165 + endloop + endfacet + facet normal 0.478847 -0.185791 0.858013 + outer loop + vertex 901.369 286.442 22.5196 + vertex 902.848 290.701 22.6165 + vertex 899.977 287.373 23.4976 + endloop + endfacet + facet normal 0.47887 -0.185816 0.857995 + outer loop + vertex 899.977 287.373 23.4976 + vertex 902.848 290.701 22.6165 + vertex 901.455 291.589 23.5861 + endloop + endfacet + facet normal 0.487905 -0.169718 0.856239 + outer loop + vertex 902.848 290.701 22.6165 + vertex 904.166 294.978 22.713 + vertex 901.455 291.589 23.5861 + endloop + endfacet + facet normal 0.488258 -0.170071 0.855967 + outer loop + vertex 901.455 291.589 23.5861 + vertex 904.166 294.978 22.713 + vertex 902.774 295.823 23.6751 + endloop + endfacet + facet normal 0.175601 -0.0771181 0.981436 + outer loop + vertex 907.995 286.079 20.7591 + vertex 908.965 290.387 20.9242 + vertex 906.082 287.833 21.2393 + endloop + endfacet + facet normal 0.178682 -0.0806995 0.980592 + outer loop + vertex 906.082 287.833 21.2393 + vertex 908.965 290.387 20.9242 + vertex 907.434 292.186 21.3512 + endloop + endfacet + facet normal 0.172305 -0.0908858 0.980842 + outer loop + vertex 906.028 281.672 20.6964 + vertex 907.995 286.079 20.7591 + vertex 904.565 283.515 21.1242 + endloop + endfacet + facet normal 0.168256 -0.0852983 0.982046 + outer loop + vertex 904.565 283.515 21.1242 + vertex 907.995 286.079 20.7591 + vertex 906.082 287.833 21.2393 + endloop + endfacet + facet normal 0.246058 -0.112117 0.962749 + outer loop + vertex 904.565 283.515 21.1242 + vertex 906.082 287.833 21.2393 + vertex 902.911 285.15 21.7372 + endloop + endfacet + facet normal 0.242785 -0.108008 0.964049 + outer loop + vertex 902.911 285.15 21.7372 + vertex 906.082 287.833 21.2393 + vertex 904.403 289.445 21.8427 + endloop + endfacet + facet normal 0.248377 -0.101902 0.963289 + outer loop + vertex 906.082 287.833 21.2393 + vertex 907.434 292.186 21.3512 + vertex 904.403 289.445 21.8427 + endloop + endfacet + facet normal 0.24681 -0.100063 0.963884 + outer loop + vertex 904.403 289.445 21.8427 + vertex 907.434 292.186 21.3512 + vertex 905.733 293.759 21.95 + endloop + endfacet + facet normal 0.491438 -0.149459 0.857992 + outer loop + vertex 927.927 274.624 15.925 + vertex 929.399 279.575 15.9442 + vertex 926.512 276.001 16.9753 + endloop + endfacet + facet normal 0.487504 -0.145435 0.860923 + outer loop + vertex 926.512 276.001 16.9753 + vertex 929.399 279.575 15.9442 + vertex 927.851 280.842 17.0351 + endloop + endfacet + facet normal 0.472432 -0.166483 0.865501 + outer loop + vertex 926.239 269.686 15.8967 + vertex 927.927 274.624 15.925 + vertex 924.886 271.315 16.9485 + endloop + endfacet + facet normal 0.475394 -0.169915 0.863209 + outer loop + vertex 924.886 271.315 16.9485 + vertex 927.927 274.624 15.925 + vertex 926.512 276.001 16.9753 + endloop + endfacet + facet normal 0.379704 -0.137 0.914907 + outer loop + vertex 924.886 271.315 16.9485 + vertex 926.512 276.001 16.9753 + vertex 923.891 272.869 17.5941 + endloop + endfacet + facet normal 0.360807 -0.119195 0.924992 + outer loop + vertex 923.891 272.869 17.5941 + vertex 926.512 276.001 16.9753 + vertex 924.846 276.904 17.7414 + endloop + endfacet + facet normal 0.36437 -0.112174 0.924474 + outer loop + vertex 926.512 276.001 16.9753 + vertex 927.851 280.842 17.0351 + vertex 924.846 276.904 17.7414 + endloop + endfacet + facet normal 0.36037 -0.108769 0.926446 + outer loop + vertex 924.846 276.904 17.7414 + vertex 927.851 280.842 17.0351 + vertex 926.165 282.228 17.8535 + endloop + endfacet + facet normal 0.67616 -0.206744 0.707152 + outer loop + vertex 930.893 273.757 13.2477 + vertex 931.47 276.254 13.4259 + vertex 929.35 273.049 14.5157 + endloop + endfacet + facet normal 0.692625 -0.187109 0.696606 + outer loop + vertex 932.359 278.93 13.261 + vertex 930.869 278.147 14.532 + vertex 931.47 276.254 13.4259 + endloop + endfacet + facet normal 0.672322 -0.202555 0.712007 + outer loop + vertex 930.869 278.147 14.532 + vertex 929.35 273.049 14.5157 + vertex 931.47 276.254 13.4259 + endloop + endfacet + facet normal 0.661885 -0.229976 0.713456 + outer loop + vertex 929.225 268.625 13.231 + vertex 929.89 271.088 13.4088 + vertex 927.647 268.001 14.4939 + endloop + endfacet + facet normal 0.676785 -0.211928 0.705017 + outer loop + vertex 930.893 273.757 13.2477 + vertex 929.35 273.049 14.5157 + vertex 929.89 271.088 13.4088 + endloop + endfacet + facet normal 0.657688 -0.225016 0.718898 + outer loop + vertex 929.35 273.049 14.5157 + vertex 927.647 268.001 14.4939 + vertex 929.89 271.088 13.4088 + endloop + endfacet + facet normal 0.565725 -0.194342 0.801365 + outer loop + vertex 927.647 268.001 14.4939 + vertex 929.35 273.049 14.5157 + vertex 926.239 269.686 15.8967 + endloop + endfacet + facet normal 0.569335 -0.199227 0.797601 + outer loop + vertex 926.239 269.686 15.8967 + vertex 929.35 273.049 14.5157 + vertex 927.927 274.624 15.925 + endloop + endfacet + facet normal 0.586478 -0.177233 0.790337 + outer loop + vertex 929.35 273.049 14.5157 + vertex 930.869 278.147 14.532 + vertex 927.927 274.624 15.925 + endloop + endfacet + facet normal 0.586715 -0.177527 0.790094 + outer loop + vertex 927.927 274.624 15.925 + vertex 930.869 278.147 14.532 + vertex 929.399 279.575 15.9442 + endloop + endfacet + facet normal 0.960741 -0.261156 -0.0936715 + outer loop + vertex 932.316 275.089 8.97369 + vertex 933.021 277.683 8.97582 + vertex 932.411 275.05 10.0588 + endloop + endfacet + facet normal 0.959245 -0.263868 -0.101107 + outer loop + vertex 932.411 275.05 10.0588 + vertex 933.021 277.683 8.97582 + vertex 933.124 277.643 10.0613 + endloop + endfacet + facet normal 0.954324 -0.284254 -0.0920054 + outer loop + vertex 931.541 272.489 8.97283 + vertex 932.316 275.089 8.97369 + vertex 931.634 272.45 10.0568 + endloop + endfacet + facet normal 0.95393 -0.284945 -0.0939377 + outer loop + vertex 931.634 272.45 10.0568 + vertex 932.316 275.089 8.97369 + vertex 932.411 275.05 10.0588 + endloop + endfacet + facet normal 0.951579 -0.284405 0.116667 + outer loop + vertex 931.634 272.45 10.0568 + vertex 932.411 275.05 10.0588 + vertex 931.547 272.617 11.1771 + endloop + endfacet + facet normal 0.951576 -0.28452 0.116415 + outer loop + vertex 931.547 272.617 11.1771 + vertex 932.411 275.05 10.0588 + vertex 932.323 275.216 11.1808 + endloop + endfacet + facet normal 0.957867 -0.263696 0.113822 + outer loop + vertex 932.411 275.05 10.0588 + vertex 933.124 277.643 10.0613 + vertex 932.323 275.216 11.1808 + endloop + endfacet + facet normal 0.957861 -0.264013 0.113131 + outer loop + vertex 932.323 275.216 11.1808 + vertex 933.124 277.643 10.0613 + vertex 933.037 277.809 11.1846 + endloop + endfacet + facet normal 0.95016 -0.300092 -0.0845042 + outer loop + vertex 930.724 269.904 8.97101 + vertex 931.541 272.489 8.97283 + vertex 930.81 269.869 10.0544 + endloop + endfacet + facet normal 0.94858 -0.302819 -0.0921766 + outer loop + vertex 930.81 269.869 10.0544 + vertex 931.541 272.489 8.97283 + vertex 931.634 272.45 10.0568 + endloop + endfacet + facet normal 0.943898 -0.319603 -0.0831335 + outer loop + vertex 929.866 267.368 8.96966 + vertex 930.724 269.904 8.97101 + vertex 929.95 267.335 10.052 + endloop + endfacet + facet normal 0.943585 -0.320134 -0.0846204 + outer loop + vertex 929.95 267.335 10.052 + vertex 930.724 269.904 8.97101 + vertex 930.81 269.869 10.0544 + endloop + endfacet + facet normal 0.939418 -0.318915 0.125647 + outer loop + vertex 929.95 267.335 10.052 + vertex 930.81 269.869 10.0544 + vertex 929.858 267.503 11.1696 + endloop + endfacet + facet normal 0.939345 -0.320266 0.12272 + outer loop + vertex 929.858 267.503 11.1696 + vertex 930.81 269.869 10.0544 + vertex 930.721 270.036 11.1733 + endloop + endfacet + facet normal 0.945636 -0.302074 0.120512 + outer loop + vertex 930.81 269.869 10.0544 + vertex 931.634 272.45 10.0568 + vertex 930.721 270.036 11.1733 + endloop + endfacet + facet normal 0.945606 -0.302794 0.11893 + outer loop + vertex 930.721 270.036 11.1733 + vertex 931.634 272.45 10.0568 + vertex 931.547 272.617 11.1771 + endloop + endfacet + facet normal 0.900202 -0.288568 0.326136 + outer loop + vertex 930.721 270.036 11.1733 + vertex 931.547 272.617 11.1771 + vertex 930.453 270.462 12.2893 + endloop + endfacet + facet normal 0.899794 -0.287128 0.328523 + outer loop + vertex 930.453 270.462 12.2893 + vertex 931.547 272.617 11.1771 + vertex 931.275 273.046 12.2958 + endloop + endfacet + facet normal 0.892925 -0.304751 0.331378 + outer loop + vertex 929.858 267.503 11.1696 + vertex 930.721 270.036 11.1733 + vertex 929.589 267.927 12.2827 + endloop + endfacet + facet normal 0.893028 -0.305141 0.330741 + outer loop + vertex 929.589 267.927 12.2827 + vertex 930.721 270.036 11.1733 + vertex 930.453 270.462 12.2893 + endloop + endfacet + facet normal 0.810743 -0.277591 0.515401 + outer loop + vertex 929.589 267.927 12.2827 + vertex 930.453 270.462 12.2893 + vertex 929.225 268.625 13.231 + endloop + endfacet + facet normal 0.799039 -0.254787 0.544628 + outer loop + vertex 929.225 268.625 13.231 + vertex 930.453 270.462 12.2893 + vertex 929.89 271.088 13.4088 + endloop + endfacet + facet normal 0.798671 -0.255493 0.544838 + outer loop + vertex 930.453 270.462 12.2893 + vertex 931.275 273.046 12.2958 + vertex 929.89 271.088 13.4088 + endloop + endfacet + facet normal 0.805971 -0.271296 0.526126 + outer loop + vertex 929.89 271.088 13.4088 + vertex 931.275 273.046 12.2958 + vertex 930.893 273.757 13.2477 + endloop + endfacet + facet normal 0.913165 -0.252003 0.320349 + outer loop + vertex 932.323 275.216 11.1808 + vertex 933.037 277.809 11.1846 + vertex 932.048 275.644 12.302 + endloop + endfacet + facet normal 0.912963 -0.251348 0.321439 + outer loop + vertex 932.048 275.644 12.302 + vertex 933.037 277.809 11.1846 + vertex 932.759 278.235 12.3076 + endloop + endfacet + facet normal 0.906316 -0.271292 0.324024 + outer loop + vertex 931.547 272.617 11.1771 + vertex 932.323 275.216 11.1808 + vertex 931.275 273.046 12.2958 + endloop + endfacet + facet normal 0.906034 -0.270345 0.325601 + outer loop + vertex 931.275 273.046 12.2958 + vertex 932.323 275.216 11.1808 + vertex 932.048 275.644 12.302 + endloop + endfacet + facet normal 0.822089 -0.245815 0.51356 + outer loop + vertex 931.275 273.046 12.2958 + vertex 932.048 275.644 12.302 + vertex 930.893 273.757 13.2477 + endloop + endfacet + facet normal 0.811002 -0.225949 0.539651 + outer loop + vertex 930.893 273.757 13.2477 + vertex 932.048 275.644 12.302 + vertex 931.47 276.254 13.4259 + endloop + endfacet + facet normal 0.811896 -0.224068 0.53909 + outer loop + vertex 932.048 275.644 12.302 + vertex 932.759 278.235 12.3076 + vertex 931.47 276.254 13.4259 + endloop + endfacet + facet normal 0.819922 -0.240289 0.519605 + outer loop + vertex 931.47 276.254 13.4259 + vertex 932.759 278.235 12.3076 + vertex 932.359 278.93 13.261 + endloop + endfacet + facet normal 0.601168 -0.176027 -0.779494 + outer loop + vertex 929.483 275.691 4.97722 + vertex 930.346 278.016 5.11728 + vertex 930.648 275.475 5.92439 + endloop + endfacet + facet normal 0.627595 -0.166834 -0.760454 + outer loop + vertex 930.648 275.475 5.92439 + vertex 930.346 278.016 5.11728 + vertex 931.338 278.061 5.92638 + endloop + endfacet + facet normal 0.627796 -0.165596 -0.760559 + outer loop + vertex 928.905 272.859 5.11661 + vertex 929.483 275.691 4.97722 + vertex 929.89 272.876 5.92542 + endloop + endfacet + facet normal 0.601217 -0.175812 -0.779505 + outer loop + vertex 929.89 272.876 5.92542 + vertex 929.483 275.691 4.97722 + vertex 930.648 275.475 5.92439 + endloop + endfacet + facet normal 0.73805 -0.215699 -0.63934 + outer loop + vertex 929.89 272.876 5.92542 + vertex 930.648 275.475 5.92439 + vertex 930.703 272.766 6.90188 + endloop + endfacet + facet normal 0.7406 -0.214702 -0.636722 + outer loop + vertex 930.703 272.766 6.90188 + vertex 930.648 275.475 5.92439 + vertex 931.459 275.37 6.9028 + endloop + endfacet + facet normal 0.744201 -0.198034 -0.637924 + outer loop + vertex 930.648 275.475 5.92439 + vertex 931.338 278.061 5.92638 + vertex 931.459 275.37 6.9028 + endloop + endfacet + facet normal 0.741303 -0.199249 -0.640913 + outer loop + vertex 931.459 275.37 6.9028 + vertex 931.338 278.061 5.92638 + vertex 932.156 277.96 6.90393 + endloop + endfacet + facet normal 0.598792 -0.201397 -0.775169 + outer loop + vertex 927.958 270.577 4.97777 + vertex 928.905 272.859 5.11661 + vertex 929.092 270.304 5.92476 + endloop + endfacet + facet normal 0.624847 -0.193547 -0.756377 + outer loop + vertex 929.092 270.304 5.92476 + vertex 928.905 272.859 5.11661 + vertex 929.89 272.876 5.92542 + endloop + endfacet + facet normal 0.622689 -0.190527 -0.758919 + outer loop + vertex 927.285 267.819 5.11814 + vertex 927.958 270.577 4.97777 + vertex 928.257 267.786 5.92389 + endloop + endfacet + facet normal 0.599581 -0.198552 -0.775293 + outer loop + vertex 928.257 267.786 5.92389 + vertex 927.958 270.577 4.97777 + vertex 929.092 270.304 5.92476 + endloop + endfacet + facet normal 0.737463 -0.244324 -0.629646 + outer loop + vertex 928.257 267.786 5.92389 + vertex 929.092 270.304 5.92476 + vertex 929.047 267.65 6.90135 + endloop + endfacet + facet normal 0.735939 -0.244875 -0.631213 + outer loop + vertex 929.047 267.65 6.90135 + vertex 929.092 270.304 5.92476 + vertex 929.89 270.182 6.90214 + endloop + endfacet + facet normal 0.739876 -0.229245 -0.63248 + outer loop + vertex 929.092 270.304 5.92476 + vertex 929.89 272.876 5.92542 + vertex 929.89 270.182 6.90214 + endloop + endfacet + facet normal 0.734425 -0.231272 -0.63807 + outer loop + vertex 929.89 270.182 6.90214 + vertex 929.89 272.876 5.92542 + vertex 930.703 272.766 6.90188 + endloop + endfacet + facet normal 0.8367 -0.263454 -0.480131 + outer loop + vertex 929.89 270.182 6.90214 + vertex 930.703 272.766 6.90188 + vertex 930.43 270.039 7.92287 + endloop + endfacet + facet normal 0.836764 -0.263424 -0.480034 + outer loop + vertex 930.43 270.039 7.92287 + vertex 930.703 272.766 6.90188 + vertex 931.245 272.625 7.92374 + endloop + endfacet + facet normal 0.833817 -0.277518 -0.477215 + outer loop + vertex 929.047 267.65 6.90135 + vertex 929.89 270.182 6.90214 + vertex 929.581 267.501 7.9216 + endloop + endfacet + facet normal 0.832089 -0.278291 -0.479773 + outer loop + vertex 929.581 267.501 7.9216 + vertex 929.89 270.182 6.90214 + vertex 930.43 270.039 7.92287 + endloop + endfacet + facet normal 0.908839 -0.304079 -0.285565 + outer loop + vertex 929.581 267.501 7.9216 + vertex 930.43 270.039 7.92287 + vertex 929.866 267.368 8.96966 + endloop + endfacet + facet normal 0.905494 -0.306486 -0.293508 + outer loop + vertex 929.866 267.368 8.96966 + vertex 930.43 270.039 7.92287 + vertex 930.724 269.904 8.97101 + endloop + endfacet + facet normal 0.912011 -0.28719 -0.292845 + outer loop + vertex 930.43 270.039 7.92287 + vertex 931.245 272.625 7.92374 + vertex 930.724 269.904 8.97101 + endloop + endfacet + facet normal 0.911338 -0.287681 -0.294454 + outer loop + vertex 930.724 269.904 8.97101 + vertex 931.245 272.625 7.92374 + vertex 931.541 272.489 8.97283 + endloop + endfacet + facet normal 0.844097 -0.226985 -0.485776 + outer loop + vertex 931.459 275.37 6.9028 + vertex 932.156 277.96 6.90393 + vertex 932.009 275.229 7.92473 + endloop + endfacet + facet normal 0.840797 -0.228646 -0.490695 + outer loop + vertex 932.009 275.229 7.92473 + vertex 932.156 277.96 6.90393 + vertex 932.714 277.82 7.9256 + endloop + endfacet + facet normal 0.842366 -0.24429 -0.480355 + outer loop + vertex 930.703 272.766 6.90188 + vertex 931.459 275.37 6.9028 + vertex 931.245 272.625 7.92374 + endloop + endfacet + facet normal 0.838872 -0.245964 -0.485589 + outer loop + vertex 931.245 272.625 7.92374 + vertex 931.459 275.37 6.9028 + vertex 932.009 275.229 7.92473 + endloop + endfacet + facet normal 0.917253 -0.269036 -0.293713 + outer loop + vertex 931.245 272.625 7.92374 + vertex 932.009 275.229 7.92473 + vertex 931.541 272.489 8.97283 + endloop + endfacet + facet normal 0.913314 -0.271968 -0.303134 + outer loop + vertex 931.541 272.489 8.97283 + vertex 932.009 275.229 7.92473 + vertex 932.316 275.089 8.97369 + endloop + endfacet + facet normal 0.919836 -0.250219 -0.302146 + outer loop + vertex 932.009 275.229 7.92473 + vertex 932.714 277.82 7.9256 + vertex 932.316 275.089 8.97369 + endloop + endfacet + facet normal 0.920175 -0.249956 -0.301331 + outer loop + vertex 932.316 275.089 8.97369 + vertex 932.714 277.82 7.9256 + vertex 933.021 277.683 8.97582 + endloop + endfacet + facet normal 0.377927 -0.0981193 -0.920621 + outer loop + vertex 924.878 275.361 2.90322 + vertex 926.168 280.327 2.90347 + vertex 927.591 274.949 4.06081 + endloop + endfacet + facet normal 0.376874 -0.0984826 -0.921014 + outer loop + vertex 927.591 274.949 4.06081 + vertex 926.168 280.327 2.90347 + vertex 928.919 280.007 4.06319 + endloop + endfacet + facet normal 0.375859 -0.113256 -0.91973 + outer loop + vertex 923.404 270.44 2.90651 + vertex 924.878 275.361 2.90322 + vertex 926.076 269.943 4.05974 + endloop + endfacet + facet normal 0.375312 -0.11342 -0.919933 + outer loop + vertex 926.076 269.943 4.05974 + vertex 924.878 275.361 2.90322 + vertex 927.591 274.949 4.06081 + endloop + endfacet + facet normal 0.471824 -0.142917 -0.870033 + outer loop + vertex 928.905 272.859 5.11661 + vertex 927.958 270.577 4.97777 + vertex 927.591 274.949 4.06081 + endloop + endfacet + facet normal 0.475804 -0.160084 -0.86486 + outer loop + vertex 927.285 267.819 5.11814 + vertex 926.076 269.943 4.05974 + vertex 927.958 270.577 4.97777 + endloop + endfacet + facet normal 0.472371 -0.142813 -0.869753 + outer loop + vertex 926.076 269.943 4.05974 + vertex 927.591 274.949 4.06081 + vertex 927.958 270.577 4.97777 + endloop + endfacet + facet normal 0.473042 -0.122901 -0.872426 + outer loop + vertex 930.346 278.016 5.11728 + vertex 929.483 275.691 4.97722 + vertex 928.919 280.007 4.06319 + endloop + endfacet + facet normal 0.475528 -0.139824 -0.868517 + outer loop + vertex 928.905 272.859 5.11661 + vertex 927.591 274.949 4.06081 + vertex 929.483 275.691 4.97722 + endloop + endfacet + facet normal 0.471354 -0.123303 -0.873282 + outer loop + vertex 927.591 274.949 4.06081 + vertex 928.919 280.007 4.06319 + vertex 929.483 275.691 4.97722 + endloop + endfacet + facet normal 0.175355 -0.0518161 -0.983141 + outer loop + vertex 918.708 276.506 1.41245 + vertex 920.41 280.816 1.4889 + vertex 922.01 275.812 2.03809 + endloop + endfacet + facet normal 0.187171 -0.0478198 -0.981163 + outer loop + vertex 922.01 275.812 2.03809 + vertex 920.41 280.816 1.4889 + vertex 923.26 280.704 2.03805 + endloop + endfacet + facet normal 0.189275 -0.0465543 -0.98082 + outer loop + vertex 917.791 271.22 1.48648 + vertex 918.708 276.506 1.41245 + vertex 920.58 270.958 2.03702 + endloop + endfacet + facet normal 0.175425 -0.0514893 -0.983145 + outer loop + vertex 920.58 270.958 2.03702 + vertex 918.708 276.506 1.41245 + vertex 922.01 275.812 2.03809 + endloop + endfacet + facet normal 0.279479 -0.0821641 -0.95663 + outer loop + vertex 920.58 270.958 2.03702 + vertex 922.01 275.812 2.03809 + vertex 923.404 270.44 2.90651 + endloop + endfacet + facet normal 0.275767 -0.0832852 -0.957609 + outer loop + vertex 923.404 270.44 2.90651 + vertex 922.01 275.812 2.03809 + vertex 924.878 275.361 2.90322 + endloop + endfacet + facet normal 0.277824 -0.0709764 -0.958006 + outer loop + vertex 922.01 275.812 2.03809 + vertex 923.26 280.704 2.03805 + vertex 924.878 275.361 2.90322 + endloop + endfacet + facet normal 0.275942 -0.0716265 -0.958502 + outer loop + vertex 924.878 275.361 2.90322 + vertex 923.26 280.704 2.03805 + vertex 926.168 280.327 2.90347 + endloop + endfacet + facet normal 0.107935 -0.0249992 -0.993844 + outer loop + vertex 920.41 280.816 1.4889 + vertex 918.708 276.506 1.41245 + vertex 916.461 284.785 0.960138 + endloop + endfacet + facet normal 0.107046 -0.0324782 -0.993723 + outer loop + vertex 917.791 271.22 1.48648 + vertex 914.204 275.409 0.963103 + vertex 918.708 276.506 1.41245 + endloop + endfacet + facet normal 0.10543 -0.0256928 -0.994095 + outer loop + vertex 914.204 275.409 0.963103 + vertex 916.461 284.785 0.960138 + vertex 918.708 276.506 1.41245 + endloop + endfacet + facet normal 0.9411 -0.261289 0.214615 + outer loop + vertex 893.699 302.143 46.1632 + vertex 895.906 310.132 46.2123 + vertex 893.603 303.729 48.5166 + endloop + endfacet + facet normal 0.939668 -0.256587 0.226247 + outer loop + vertex 893.603 303.729 48.5166 + vertex 895.906 310.132 46.2123 + vertex 895.666 311.459 48.716 + endloop + endfacet + facet normal 0.924257 -0.261895 0.277777 + outer loop + vertex 894.328 300.767 42.7749 + vertex 896.576 308.762 42.833 + vertex 893.699 302.143 46.1632 + endloop + endfacet + facet normal 0.922916 -0.25671 0.286926 + outer loop + vertex 893.699 302.143 46.1632 + vertex 896.576 308.762 42.833 + vertex 895.906 310.132 46.2123 + endloop + endfacet + facet normal 0.91169 -0.261567 0.316865 + outer loop + vertex 895.348 299.205 38.55 + vertex 897.627 307.216 38.6065 + vertex 894.328 300.767 42.7749 + endloop + endfacet + facet normal 0.911076 -0.258504 0.321118 + outer loop + vertex 894.328 300.767 42.7749 + vertex 897.627 307.216 38.6065 + vertex 896.576 308.762 42.833 + endloop + endfacet + facet normal 0.896757 -0.261469 0.357017 + outer loop + vertex 896.69 297.34 33.8137 + vertex 898.999 305.375 33.8967 + vertex 895.348 299.205 38.55 + endloop + endfacet + facet normal 0.896012 -0.257425 0.361795 + outer loop + vertex 895.348 299.205 38.55 + vertex 898.999 305.375 33.8967 + vertex 897.627 307.216 38.6065 + endloop + endfacet + facet normal 0.842137 -0.210266 0.496582 + outer loop + vertex 901.633 301.142 26.5052 + vertex 902.615 305.224 26.5692 + vertex 900.69 301.839 28.4003 + endloop + endfacet + facet normal 0.842068 -0.210133 0.496755 + outer loop + vertex 900.69 301.839 28.4003 + vertex 902.615 305.224 26.5692 + vertex 901.669 305.888 28.4532 + endloop + endfacet + facet normal 0.82977 -0.240732 0.503517 + outer loop + vertex 900.476 297.014 26.4378 + vertex 901.633 301.142 26.5052 + vertex 899.536 297.755 28.3412 + endloop + endfacet + facet normal 0.830256 -0.241727 0.502237 + outer loop + vertex 899.536 297.755 28.3412 + vertex 901.633 301.142 26.5052 + vertex 900.69 301.839 28.4003 + endloop + endfacet + facet normal 0.653126 -0.166869 0.738634 + outer loop + vertex 903.922 300.025 23.76 + vertex 904.893 304.18 23.8395 + vertex 902.703 300.598 24.9669 + endloop + endfacet + facet normal 0.655242 -0.168898 0.736296 + outer loop + vertex 902.703 300.598 24.9669 + vertex 904.893 304.18 23.8395 + vertex 903.681 304.717 25.0416 + endloop + endfacet + facet normal 0.642376 -0.190505 0.742335 + outer loop + vertex 902.774 295.823 23.6751 + vertex 903.922 300.025 23.76 + vertex 901.549 296.431 24.8909 + endloop + endfacet + facet normal 0.643648 -0.191797 0.740899 + outer loop + vertex 901.549 296.431 24.8909 + vertex 903.922 300.025 23.76 + vertex 902.703 300.598 24.9669 + endloop + endfacet + facet normal 0.36576 -0.104139 0.924865 + outer loop + vertex 906.886 298.042 22.0502 + vertex 907.856 302.275 22.1431 + vertex 905.31 299.218 22.8057 + endloop + endfacet + facet normal 0.364426 -0.102883 0.925532 + outer loop + vertex 905.31 299.218 22.8057 + vertex 907.856 302.275 22.1431 + vertex 906.277 303.409 22.8911 + endloop + endfacet + facet normal 0.358848 -0.118231 0.925878 + outer loop + vertex 905.733 293.759 21.95 + vertex 906.886 298.042 22.0502 + vertex 904.166 294.978 22.713 + endloop + endfacet + facet normal 0.357279 -0.116664 0.926683 + outer loop + vertex 904.166 294.978 22.713 + vertex 906.886 298.042 22.0502 + vertex 905.31 299.218 22.8057 + endloop + endfacet + facet normal 0.49733 -0.152868 0.853987 + outer loop + vertex 904.166 294.978 22.713 + vertex 905.31 299.218 22.8057 + vertex 902.774 295.823 23.6751 + endloop + endfacet + facet normal 0.497723 -0.153237 0.853692 + outer loop + vertex 902.774 295.823 23.6751 + vertex 905.31 299.218 22.8057 + vertex 903.922 300.025 23.76 + endloop + endfacet + facet normal 0.507126 -0.134272 0.851349 + outer loop + vertex 905.31 299.218 22.8057 + vertex 906.277 303.409 22.8911 + vertex 903.922 300.025 23.76 + endloop + endfacet + facet normal 0.508042 -0.135082 0.850674 + outer loop + vertex 903.922 300.025 23.76 + vertex 906.277 303.409 22.8911 + vertex 904.893 304.18 23.8395 + endloop + endfacet + facet normal 0.184614 -0.0631787 0.980778 + outer loop + vertex 910.577 294.846 20.9764 + vertex 911.209 299.118 21.1325 + vertex 908.616 296.523 21.4536 + endloop + endfacet + facet normal 0.187008 -0.0656471 0.980163 + outer loop + vertex 908.616 296.523 21.4536 + vertex 911.209 299.118 21.1325 + vertex 909.606 300.815 21.5521 + endloop + endfacet + facet normal 0.182417 -0.0774212 0.980168 + outer loop + vertex 908.965 290.387 20.9242 + vertex 910.577 294.846 20.9764 + vertex 907.434 292.186 21.3512 + endloop + endfacet + facet normal 0.177618 -0.071566 0.981494 + outer loop + vertex 907.434 292.186 21.3512 + vertex 910.577 294.846 20.9764 + vertex 908.616 296.523 21.4536 + endloop + endfacet + facet normal 0.253963 -0.0919261 0.962835 + outer loop + vertex 907.434 292.186 21.3512 + vertex 908.616 296.523 21.4536 + vertex 905.733 293.759 21.95 + endloop + endfacet + facet normal 0.252724 -0.090552 0.963292 + outer loop + vertex 905.733 293.759 21.95 + vertex 908.616 296.523 21.4536 + vertex 906.886 298.042 22.0502 + endloop + endfacet + facet normal 0.259822 -0.0820289 0.962166 + outer loop + vertex 908.616 296.523 21.4536 + vertex 909.606 300.815 21.5521 + vertex 906.886 298.042 22.0502 + endloop + endfacet + facet normal 0.258174 -0.0803071 0.962755 + outer loop + vertex 906.886 298.042 22.0502 + vertex 909.606 300.815 21.5521 + vertex 907.856 302.275 22.1431 + endloop + endfacet + facet normal 0.501474 -0.110935 0.858031 + outer loop + vertex 930.656 284.524 15.984 + vertex 931.685 289.433 16.0173 + vertex 929.069 285.959 17.0971 + endloop + endfacet + facet normal 0.500603 -0.110088 0.858648 + outer loop + vertex 929.069 285.959 17.0971 + vertex 931.685 289.433 16.0173 + vertex 930.112 290.985 17.1335 + endloop + endfacet + facet normal 0.495865 -0.132858 0.858176 + outer loop + vertex 929.399 279.575 15.9442 + vertex 930.656 284.524 15.984 + vertex 927.851 280.842 17.0351 + endloop + endfacet + facet normal 0.489935 -0.127122 0.862441 + outer loop + vertex 927.851 280.842 17.0351 + vertex 930.656 284.524 15.984 + vertex 929.069 285.959 17.0971 + endloop + endfacet + facet normal 0.367726 -0.0987734 0.924674 + outer loop + vertex 927.851 280.842 17.0351 + vertex 929.069 285.959 17.0971 + vertex 926.165 282.228 17.8535 + endloop + endfacet + facet normal 0.358204 -0.0904316 0.929254 + outer loop + vertex 926.165 282.228 17.8535 + vertex 929.069 285.959 17.0971 + vertex 927.419 288.112 17.9427 + endloop + endfacet + facet normal 0.366789 -0.0828144 0.926611 + outer loop + vertex 929.069 285.959 17.0971 + vertex 930.112 290.985 17.1335 + vertex 927.419 288.112 17.9427 + endloop + endfacet + facet normal 0.369266 -0.0854811 0.925384 + outer loop + vertex 927.419 288.112 17.9427 + vertex 930.112 290.985 17.1335 + vertex 928.703 292.944 17.8767 + endloop + endfacet + facet normal 0.706631 -0.155518 0.69028 + outer loop + vertex 933.597 284.012 13.277 + vertex 933.95 286.389 13.4517 + vertex 932.169 283.181 14.5513 + endloop + endfacet + facet normal 0.72506 -0.135561 0.675212 + outer loop + vertex 934.581 288.932 13.2841 + vertex 933.228 288.094 14.5687 + vertex 933.95 286.389 13.4517 + endloop + endfacet + facet normal 0.7056 -0.154508 0.69156 + outer loop + vertex 933.228 288.094 14.5687 + vertex 932.169 283.181 14.5513 + vertex 933.95 286.389 13.4517 + endloop + endfacet + facet normal 0.692239 -0.184722 0.697626 + outer loop + vertex 932.359 278.93 13.261 + vertex 932.832 281.383 13.4412 + vertex 930.869 278.147 14.532 + endloop + endfacet + facet normal 0.70814 -0.163222 0.686947 + outer loop + vertex 933.597 284.012 13.277 + vertex 932.169 283.181 14.5513 + vertex 932.832 281.383 13.4412 + endloop + endfacet + facet normal 0.688076 -0.180437 0.702847 + outer loop + vertex 932.169 283.181 14.5513 + vertex 930.869 278.147 14.532 + vertex 932.832 281.383 13.4412 + endloop + endfacet + facet normal 0.600033 -0.158008 0.784216 + outer loop + vertex 930.869 278.147 14.532 + vertex 932.169 283.181 14.5513 + vertex 929.399 279.575 15.9442 + endloop + endfacet + facet normal 0.600822 -0.158919 0.783427 + outer loop + vertex 929.399 279.575 15.9442 + vertex 932.169 283.181 14.5513 + vertex 930.656 284.524 15.984 + endloop + endfacet + facet normal 0.615285 -0.135344 0.776599 + outer loop + vertex 932.169 283.181 14.5513 + vertex 933.228 288.094 14.5687 + vertex 930.656 284.524 15.984 + endloop + endfacet + facet normal 0.614066 -0.133991 0.777798 + outer loop + vertex 930.656 284.524 15.984 + vertex 933.228 288.094 14.5687 + vertex 931.685 289.433 16.0173 + endloop + endfacet + facet normal 0.977292 -0.182597 -0.107509 + outer loop + vertex 934.782 285.296 8.97958 + vertex 935.244 287.77 8.9816 + vertex 934.895 285.262 10.0682 + endloop + endfacet + facet normal 0.975977 -0.185409 -0.114421 + outer loop + vertex 934.895 285.262 10.0682 + vertex 935.244 287.77 8.9816 + vertex 935.366 287.74 10.0705 + endloop + endfacet + facet normal 0.973978 -0.203165 -0.100452 + outer loop + vertex 934.258 282.787 8.978 + vertex 934.782 285.296 8.97958 + vertex 934.363 282.752 10.0663 + endloop + endfacet + facet normal 0.972591 -0.206053 -0.107745 + outer loop + vertex 934.363 282.752 10.0663 + vertex 934.782 285.296 8.97958 + vertex 934.895 285.262 10.0682 + endloop + endfacet + facet normal 0.973378 -0.206378 0.0997126 + outer loop + vertex 934.363 282.752 10.0663 + vertex 934.895 285.262 10.0682 + vertex 934.283 282.919 11.1921 + endloop + endfacet + facet normal 0.973369 -0.204792 0.103016 + outer loop + vertex 934.283 282.919 11.1921 + vertex 934.895 285.262 10.0682 + vertex 934.812 285.435 11.1957 + endloop + endfacet + facet normal 0.977426 -0.185883 0.100425 + outer loop + vertex 934.895 285.262 10.0682 + vertex 935.366 287.74 10.0705 + vertex 934.812 285.435 11.1957 + endloop + endfacet + facet normal 0.977429 -0.186034 0.100116 + outer loop + vertex 934.812 285.435 11.1957 + vertex 935.366 287.74 10.0705 + vertex 935.283 287.91 11.1986 + endloop + endfacet + facet normal 0.969536 -0.223617 -0.0999754 + outer loop + vertex 933.673 280.249 8.97671 + vertex 934.258 282.787 8.978 + vertex 933.776 280.21 10.0638 + endloop + endfacet + facet normal 0.969402 -0.223886 -0.100673 + outer loop + vertex 933.776 280.21 10.0638 + vertex 934.258 282.787 8.978 + vertex 934.363 282.752 10.0663 + endloop + endfacet + facet normal 0.964275 -0.244936 -0.100892 + outer loop + vertex 933.021 277.683 8.97582 + vertex 933.673 280.249 8.97671 + vertex 933.124 277.643 10.0613 + endloop + endfacet + facet normal 0.964406 -0.244691 -0.100235 + outer loop + vertex 933.124 277.643 10.0613 + vertex 933.673 280.249 8.97671 + vertex 933.776 280.21 10.0638 + endloop + endfacet + facet normal 0.963282 -0.24461 0.110695 + outer loop + vertex 933.124 277.643 10.0613 + vertex 933.776 280.21 10.0638 + vertex 933.037 277.809 11.1846 + endloop + endfacet + facet normal 0.963279 -0.244951 0.109963 + outer loop + vertex 933.037 277.809 11.1846 + vertex 933.776 280.21 10.0638 + vertex 933.69 280.377 11.1887 + endloop + endfacet + facet normal 0.968686 -0.22393 0.10725 + outer loop + vertex 933.776 280.21 10.0638 + vertex 934.363 282.752 10.0663 + vertex 933.69 280.377 11.1887 + endloop + endfacet + facet normal 0.968679 -0.226258 0.102319 + outer loop + vertex 933.69 280.377 11.1887 + vertex 934.363 282.752 10.0663 + vertex 934.283 282.919 11.1921 + endloop + endfacet + facet normal 0.92537 -0.216428 0.311206 + outer loop + vertex 933.69 280.377 11.1887 + vertex 934.283 282.919 11.1921 + vertex 933.412 280.803 12.3129 + endloop + endfacet + facet normal 0.924862 -0.214844 0.313803 + outer loop + vertex 933.412 280.803 12.3129 + vertex 934.283 282.919 11.1921 + vertex 934.001 283.346 12.3173 + endloop + endfacet + facet normal 0.91927 -0.2341 0.316449 + outer loop + vertex 933.037 277.809 11.1846 + vertex 933.69 280.377 11.1887 + vertex 932.759 278.235 12.3076 + endloop + endfacet + facet normal 0.91928 -0.234131 0.316397 + outer loop + vertex 932.759 278.235 12.3076 + vertex 933.69 280.377 11.1887 + vertex 933.412 280.803 12.3129 + endloop + endfacet + facet normal 0.835497 -0.21325 0.506428 + outer loop + vertex 932.759 278.235 12.3076 + vertex 933.412 280.803 12.3129 + vertex 932.359 278.93 13.261 + endloop + endfacet + facet normal 0.826703 -0.198086 0.526615 + outer loop + vertex 932.359 278.93 13.261 + vertex 933.412 280.803 12.3129 + vertex 932.832 281.383 13.4412 + endloop + endfacet + facet normal 0.828876 -0.192967 0.525098 + outer loop + vertex 933.412 280.803 12.3129 + vertex 934.001 283.346 12.3173 + vertex 932.832 281.383 13.4412 + endloop + endfacet + facet normal 0.838997 -0.212949 0.500736 + outer loop + vertex 932.832 281.383 13.4412 + vertex 934.001 283.346 12.3173 + vertex 933.597 284.012 13.277 + endloop + endfacet + facet normal 0.937518 -0.178676 0.298554 + outer loop + vertex 934.812 285.435 11.1957 + vertex 935.283 287.91 11.1986 + vertex 934.533 285.851 12.3223 + endloop + endfacet + facet normal 0.937766 -0.179443 0.297314 + outer loop + vertex 934.533 285.851 12.3223 + vertex 935.283 287.91 11.1986 + vertex 935.003 288.312 12.3259 + endloop + endfacet + facet normal 0.930873 -0.196147 0.308222 + outer loop + vertex 934.283 282.919 11.1921 + vertex 934.812 285.435 11.1957 + vertex 934.001 283.346 12.3173 + endloop + endfacet + facet normal 0.931629 -0.198483 0.304419 + outer loop + vertex 934.001 283.346 12.3173 + vertex 934.812 285.435 11.1957 + vertex 934.533 285.851 12.3223 + endloop + endfacet + facet normal 0.854607 -0.182482 0.486155 + outer loop + vertex 934.001 283.346 12.3173 + vertex 934.533 285.851 12.3223 + vertex 933.597 284.012 13.277 + endloop + endfacet + facet normal 0.842929 -0.162694 0.512837 + outer loop + vertex 933.597 284.012 13.277 + vertex 934.533 285.851 12.3223 + vertex 933.95 286.389 13.4517 + endloop + endfacet + facet normal 0.843284 -0.161726 0.512559 + outer loop + vertex 934.533 285.851 12.3223 + vertex 935.003 288.312 12.3259 + vertex 933.95 286.389 13.4517 + endloop + endfacet + facet normal 0.852456 -0.179328 0.491081 + outer loop + vertex 933.95 286.389 13.4517 + vertex 935.003 288.312 12.3259 + vertex 934.581 288.932 13.2841 + endloop + endfacet + facet normal 0.610172 -0.125712 -0.782232 + outer loop + vertex 931.871 285.792 4.97547 + vertex 932.511 288.009 5.11883 + vertex 933.054 285.622 5.92534 + endloop + endfacet + facet normal 0.631016 -0.115854 -0.76707 + outer loop + vertex 933.054 285.622 5.92534 + vertex 932.511 288.009 5.11883 + vertex 933.505 288.076 5.92608 + endloop + endfacet + facet normal 0.631738 -0.115417 -0.766542 + outer loop + vertex 931.548 283.08 5.11789 + vertex 931.871 285.792 4.97547 + vertex 932.54 283.135 5.92676 + endloop + endfacet + facet normal 0.610041 -0.126491 -0.782208 + outer loop + vertex 932.54 283.135 5.92676 + vertex 931.871 285.792 4.97547 + vertex 933.054 285.622 5.92534 + endloop + endfacet + facet normal 0.747449 -0.154804 -0.646031 + outer loop + vertex 932.54 283.135 5.92676 + vertex 933.054 285.622 5.92534 + vertex 933.367 283.047 6.90463 + endloop + endfacet + facet normal 0.747696 -0.154677 -0.645776 + outer loop + vertex 933.367 283.047 6.90463 + vertex 933.054 285.622 5.92534 + vertex 933.883 285.544 6.9045 + endloop + endfacet + facet normal 0.750267 -0.137829 -0.646609 + outer loop + vertex 933.054 285.622 5.92534 + vertex 933.505 288.076 5.92608 + vertex 933.883 285.544 6.9045 + endloop + endfacet + facet normal 0.748754 -0.138662 -0.648182 + outer loop + vertex 933.883 285.544 6.9045 + vertex 933.505 288.076 5.92608 + vertex 934.34 288.006 6.90514 + endloop + endfacet + facet normal 0.608218 -0.151791 -0.779121 + outer loop + vertex 930.799 280.806 4.97617 + vertex 931.548 283.08 5.11789 + vertex 931.97 280.616 5.92706 + endloop + endfacet + facet normal 0.630396 -0.142715 -0.763042 + outer loop + vertex 931.97 280.616 5.92706 + vertex 931.548 283.08 5.11789 + vertex 932.54 283.135 5.92676 + endloop + endfacet + facet normal 0.629445 -0.140921 -0.76416 + outer loop + vertex 930.346 278.016 5.11728 + vertex 930.799 280.806 4.97617 + vertex 931.338 278.061 5.92638 + endloop + endfacet + facet normal 0.608523 -0.15023 -0.779186 + outer loop + vertex 931.338 278.061 5.92638 + vertex 930.799 280.806 4.97617 + vertex 931.97 280.616 5.92706 + endloop + endfacet + facet normal 0.744403 -0.183859 -0.641919 + outer loop + vertex 931.338 278.061 5.92638 + vertex 931.97 280.616 5.92706 + vertex 932.156 277.96 6.90393 + endloop + endfacet + facet normal 0.743972 -0.184052 -0.642363 + outer loop + vertex 932.156 277.96 6.90393 + vertex 931.97 280.616 5.92706 + vertex 932.79 280.519 6.90463 + endloop + endfacet + facet normal 0.746783 -0.169032 -0.643228 + outer loop + vertex 931.97 280.616 5.92706 + vertex 932.54 283.135 5.92676 + vertex 932.79 280.519 6.90463 + endloop + endfacet + facet normal 0.744864 -0.169956 -0.645207 + outer loop + vertex 932.79 280.519 6.90463 + vertex 932.54 283.135 5.92676 + vertex 933.367 283.047 6.90463 + endloop + endfacet + facet normal 0.847926 -0.193471 -0.493549 + outer loop + vertex 932.79 280.519 6.90463 + vertex 933.367 283.047 6.90463 + vertex 933.354 280.384 7.92665 + endloop + endfacet + facet normal 0.848702 -0.193029 -0.492387 + outer loop + vertex 933.354 280.384 7.92665 + vertex 933.367 283.047 6.90463 + vertex 933.931 282.918 7.92768 + endloop + endfacet + facet normal 0.845779 -0.209304 -0.490765 + outer loop + vertex 932.156 277.96 6.90393 + vertex 932.79 280.519 6.90463 + vertex 932.714 277.82 7.9256 + endloop + endfacet + facet normal 0.843901 -0.210309 -0.49356 + outer loop + vertex 932.714 277.82 7.9256 + vertex 932.79 280.519 6.90463 + vertex 933.354 280.384 7.92665 + endloop + endfacet + facet normal 0.925489 -0.23074 -0.300381 + outer loop + vertex 932.714 277.82 7.9256 + vertex 933.354 280.384 7.92665 + vertex 933.021 277.683 8.97582 + endloop + endfacet + facet normal 0.921484 -0.233993 -0.310024 + outer loop + vertex 933.021 277.683 8.97582 + vertex 933.354 280.384 7.92665 + vertex 933.673 280.249 8.97671 + endloop + endfacet + facet normal 0.927399 -0.211022 -0.30887 + outer loop + vertex 933.354 280.384 7.92665 + vertex 933.931 282.918 7.92768 + vertex 933.673 280.249 8.97671 + endloop + endfacet + facet normal 0.924827 -0.213193 -0.31503 + outer loop + vertex 933.673 280.249 8.97671 + vertex 933.931 282.918 7.92768 + vertex 934.258 282.787 8.978 + endloop + endfacet + facet normal 0.855649 -0.158523 -0.492681 + outer loop + vertex 933.883 285.544 6.9045 + vertex 934.34 288.006 6.90514 + vertex 934.45 285.422 7.9285 + endloop + endfacet + facet normal 0.853508 -0.159905 -0.495938 + outer loop + vertex 934.45 285.422 7.9285 + vertex 934.34 288.006 6.90514 + vertex 934.913 287.89 7.92926 + endloop + endfacet + facet normal 0.852376 -0.17632 -0.492307 + outer loop + vertex 933.367 283.047 6.90463 + vertex 933.883 285.544 6.9045 + vertex 933.931 282.918 7.92768 + endloop + endfacet + facet normal 0.852034 -0.176528 -0.492824 + outer loop + vertex 933.931 282.918 7.92768 + vertex 933.883 285.544 6.9045 + vertex 934.45 285.422 7.9285 + endloop + endfacet + facet normal 0.929671 -0.192686 -0.313982 + outer loop + vertex 933.931 282.918 7.92768 + vertex 934.45 285.422 7.9285 + vertex 934.258 282.787 8.978 + endloop + endfacet + facet normal 0.928666 -0.193575 -0.316398 + outer loop + vertex 934.258 282.787 8.978 + vertex 934.45 285.422 7.9285 + vertex 934.782 285.296 8.97958 + endloop + endfacet + facet normal 0.932711 -0.174813 -0.315421 + outer loop + vertex 934.45 285.422 7.9285 + vertex 934.913 287.89 7.92926 + vertex 934.782 285.296 8.97958 + endloop + endfacet + facet normal 0.933349 -0.174214 -0.313861 + outer loop + vertex 934.782 285.296 8.97958 + vertex 934.913 287.89 7.92926 + vertex 935.244 287.77 8.9816 + endloop + endfacet + facet normal 0.37807 -0.0698083 -0.923141 + outer loop + vertex 927.252 285.254 2.90652 + vertex 928.136 290.107 2.90155 + vertex 930.028 284.992 4.0632 + endloop + endfacet + facet normal 0.380261 -0.0688105 -0.922316 + outer loop + vertex 930.028 284.992 4.0632 + vertex 928.136 290.107 2.90155 + vertex 930.914 289.876 4.06398 + endloop + endfacet + facet normal 0.378979 -0.0828072 -0.921693 + outer loop + vertex 926.168 280.327 2.90347 + vertex 927.252 285.254 2.90652 + vertex 928.919 280.007 4.06319 + endloop + endfacet + facet normal 0.376526 -0.0837886 -0.922609 + outer loop + vertex 928.919 280.007 4.06319 + vertex 927.252 285.254 2.90652 + vertex 930.028 284.992 4.0632 + endloop + endfacet + facet normal 0.47674 -0.102632 -0.873033 + outer loop + vertex 931.548 283.08 5.11789 + vertex 930.799 280.806 4.97617 + vertex 930.028 284.992 4.0632 + endloop + endfacet + facet normal 0.474822 -0.121236 -0.871691 + outer loop + vertex 930.346 278.016 5.11728 + vertex 928.919 280.007 4.06319 + vertex 930.799 280.806 4.97617 + endloop + endfacet + facet normal 0.470053 -0.104602 -0.876418 + outer loop + vertex 928.919 280.007 4.06319 + vertex 930.028 284.992 4.0632 + vertex 930.799 280.806 4.97617 + endloop + endfacet + facet normal 0.480385 -0.0823376 -0.873184 + outer loop + vertex 932.511 288.009 5.11883 + vertex 931.871 285.792 4.97547 + vertex 930.914 289.876 4.06398 + endloop + endfacet + facet normal 0.476794 -0.102577 -0.87301 + outer loop + vertex 931.548 283.08 5.11789 + vertex 930.028 284.992 4.0632 + vertex 931.871 285.792 4.97547 + endloop + endfacet + facet normal 0.471629 -0.0853864 -0.877653 + outer loop + vertex 930.028 284.992 4.0632 + vertex 930.914 289.876 4.06398 + vertex 931.871 285.792 4.97547 + endloop + endfacet + facet normal 0.173339 -0.039476 -0.984071 + outer loop + vertex 920.929 286.125 1.41585 + vertex 922.313 290.434 1.48687 + vertex 924.327 285.58 2.0362 + endloop + endfacet + facet normal 0.188395 -0.0329438 -0.981541 + outer loop + vertex 924.327 285.58 2.0362 + vertex 922.313 290.434 1.48687 + vertex 925.182 290.395 2.03874 + endloop + endfacet + facet normal 0.187896 -0.0318677 -0.981672 + outer loop + vertex 920.41 280.816 1.4889 + vertex 920.929 286.125 1.41585 + vertex 923.26 280.704 2.03805 + endloop + endfacet + facet normal 0.173526 -0.0383234 -0.984083 + outer loop + vertex 923.26 280.704 2.03805 + vertex 920.929 286.125 1.41585 + vertex 924.327 285.58 2.0362 + endloop + endfacet + facet normal 0.277407 -0.0610339 -0.958812 + outer loop + vertex 923.26 280.704 2.03805 + vertex 924.327 285.58 2.0362 + vertex 926.168 280.327 2.90347 + endloop + endfacet + facet normal 0.278377 -0.0606515 -0.958555 + outer loop + vertex 926.168 280.327 2.90347 + vertex 924.327 285.58 2.0362 + vertex 927.252 285.254 2.90652 + endloop + endfacet + facet normal 0.279734 -0.0491779 -0.958817 + outer loop + vertex 924.327 285.58 2.0362 + vertex 925.182 290.395 2.03874 + vertex 927.252 285.254 2.90652 + endloop + endfacet + facet normal 0.275356 -0.0511376 -0.959981 + outer loop + vertex 927.252 285.254 2.90652 + vertex 925.182 290.395 2.03874 + vertex 928.136 290.107 2.90155 + endloop + endfacet + facet normal 0.106539 -0.0178455 -0.994148 + outer loop + vertex 922.313 290.434 1.48687 + vertex 920.929 286.125 1.41585 + vertex 918.041 294.246 0.96056 + endloop + endfacet + facet normal 0.108641 -0.0242892 -0.993784 + outer loop + vertex 920.41 280.816 1.4889 + vertex 916.461 284.785 0.960138 + vertex 920.929 286.125 1.41585 + endloop + endfacet + facet normal 0.106724 -0.0177784 -0.99413 + outer loop + vertex 916.461 284.785 0.960138 + vertex 918.041 294.246 0.96056 + vertex 920.929 286.125 1.41585 + endloop + endfacet + facet normal 0.963413 -0.187243 0.191768 + outer loop + vertex 895.906 310.132 46.2123 + vertex 897.474 318.247 46.2583 + vertex 895.666 311.459 48.716 + endloop + endfacet + facet normal 0.958895 -0.174436 0.223813 + outer loop + vertex 895.666 311.459 48.716 + vertex 897.474 318.247 46.2583 + vertex 897.182 319.623 48.5846 + endloop + endfacet + facet normal 0.94605 -0.188216 0.26375 + outer loop + vertex 896.576 308.762 42.833 + vertex 898.196 316.968 42.877 + vertex 895.906 310.132 46.2123 + endloop + endfacet + facet normal 0.944724 -0.184083 0.27131 + outer loop + vertex 895.906 310.132 46.2123 + vertex 898.196 316.968 42.877 + vertex 897.474 318.247 46.2583 + endloop + endfacet + facet normal 0.934356 -0.18962 0.301699 + outer loop + vertex 897.627 307.216 38.6065 + vertex 899.279 315.448 38.6625 + vertex 896.576 308.762 42.833 + endloop + endfacet + facet normal 0.933382 -0.185946 0.306956 + outer loop + vertex 896.576 308.762 42.833 + vertex 899.279 315.448 38.6625 + vertex 898.196 316.968 42.877 + endloop + endfacet + facet normal 0.919634 -0.191522 0.342918 + outer loop + vertex 898.999 305.375 33.8967 + vertex 900.68 313.575 33.97 + vertex 897.627 307.216 38.6065 + endloop + endfacet + facet normal 0.918446 -0.186745 0.348688 + outer loop + vertex 897.627 307.216 38.6065 + vertex 900.68 313.575 33.97 + vertex 899.279 315.448 38.6625 + endloop + endfacet + facet normal 0.863682 -0.144412 0.482907 + outer loop + vertex 903.427 309.291 26.6261 + vertex 904.081 313.409 26.6879 + vertex 902.484 309.949 28.5085 + endloop + endfacet + facet normal 0.863128 -0.143493 0.484168 + outer loop + vertex 902.484 309.949 28.5085 + vertex 904.081 313.409 26.6879 + vertex 903.141 314.066 28.5582 + endloop + endfacet + facet normal 0.853103 -0.17726 0.490707 + outer loop + vertex 902.615 305.224 26.5692 + vertex 903.427 309.291 26.6261 + vertex 901.669 305.888 28.4532 + endloop + endfacet + facet normal 0.853563 -0.17809 0.489605 + outer loop + vertex 901.669 305.888 28.4532 + vertex 903.427 309.291 26.6261 + vertex 902.484 309.949 28.5085 + endloop + endfacet + facet normal 0.674523 -0.115364 0.729185 + outer loop + vertex 905.692 308.319 23.9136 + vertex 906.33 312.488 23.9836 + vertex 904.488 308.817 25.107 + endloop + endfacet + facet normal 0.676713 -0.117174 0.726863 + outer loop + vertex 904.488 308.817 25.107 + vertex 906.33 312.488 23.9836 + vertex 905.134 312.95 25.1714 + endloop + endfacet + facet normal 0.664719 -0.141456 0.733579 + outer loop + vertex 904.893 304.18 23.8395 + vertex 905.692 308.319 23.9136 + vertex 903.681 304.717 25.0416 + endloop + endfacet + facet normal 0.666096 -0.142691 0.73209 + outer loop + vertex 903.681 304.717 25.0416 + vertex 905.692 308.319 23.9136 + vertex 904.488 308.817 25.107 + endloop + endfacet + facet normal 0.381664 -0.0740049 0.921334 + outer loop + vertex 908.649 306.496 22.2301 + vertex 909.276 310.76 22.313 + vertex 907.069 307.586 22.9721 + endloop + endfacet + facet normal 0.382989 -0.0750585 0.920698 + outer loop + vertex 907.069 307.586 22.9721 + vertex 909.276 310.76 22.313 + vertex 907.701 311.796 23.0528 + endloop + endfacet + facet normal 0.373274 -0.0891713 0.923426 + outer loop + vertex 907.856 302.275 22.1431 + vertex 908.649 306.496 22.2301 + vertex 906.277 303.409 22.8911 + endloop + endfacet + facet normal 0.372675 -0.0886482 0.923718 + outer loop + vertex 906.277 303.409 22.8911 + vertex 908.649 306.496 22.2301 + vertex 907.069 307.586 22.9721 + endloop + endfacet + facet normal 0.517536 -0.114674 0.847942 + outer loop + vertex 906.277 303.409 22.8911 + vertex 907.069 307.586 22.9721 + vertex 904.893 304.18 23.8395 + endloop + endfacet + facet normal 0.518186 -0.115208 0.847473 + outer loop + vertex 904.893 304.18 23.8395 + vertex 907.069 307.586 22.9721 + vertex 905.692 308.319 23.9136 + endloop + endfacet + facet normal 0.526873 -0.0951739 0.844598 + outer loop + vertex 907.069 307.586 22.9721 + vertex 907.701 311.796 23.0528 + vertex 905.692 308.319 23.9136 + endloop + endfacet + facet normal 0.526141 -0.0946229 0.845116 + outer loop + vertex 905.692 308.319 23.9136 + vertex 907.701 311.796 23.0528 + vertex 906.33 312.488 23.9836 + endloop + endfacet + facet normal 0.193362 -0.0471722 0.979993 + outer loop + vertex 912.443 303.559 21.1706 + vertex 912.727 307.819 21.3196 + vertex 910.415 305.086 21.6443 + endloop + endfacet + facet normal 0.195102 -0.0486946 0.979573 + outer loop + vertex 910.415 305.086 21.6443 + vertex 912.727 307.819 21.3196 + vertex 911.049 309.405 21.7327 + endloop + endfacet + facet normal 0.191223 -0.0615286 0.979616 + outer loop + vertex 911.209 299.118 21.1325 + vertex 912.443 303.559 21.1706 + vertex 909.606 300.815 21.5521 + endloop + endfacet + facet normal 0.186527 -0.0565046 0.980824 + outer loop + vertex 909.606 300.815 21.5521 + vertex 912.443 303.559 21.1706 + vertex 910.415 305.086 21.6443 + endloop + endfacet + facet normal 0.265476 -0.0710478 0.961496 + outer loop + vertex 909.606 300.815 21.5521 + vertex 910.415 305.086 21.6443 + vertex 907.856 302.275 22.1431 + endloop + endfacet + facet normal 0.263768 -0.0693878 0.962087 + outer loop + vertex 907.856 302.275 22.1431 + vertex 910.415 305.086 21.6443 + vertex 908.649 306.496 22.2301 + endloop + endfacet + facet normal 0.271207 -0.0594848 0.960681 + outer loop + vertex 910.415 305.086 21.6443 + vertex 911.049 309.405 21.7327 + vertex 908.649 306.496 22.2301 + endloop + endfacet + facet normal 0.269929 -0.0583571 0.96111 + outer loop + vertex 908.649 306.496 22.2301 + vertex 911.049 309.405 21.7327 + vertex 909.276 310.76 22.313 + endloop + endfacet + facet normal 0.53138 -0.0702648 0.844214 + outer loop + vertex 932.484 294.303 16.0458 + vertex 933.087 299.222 16.0755 + vertex 930.905 295.803 17.1647 + endloop + endfacet + facet normal 0.533211 -0.0718438 0.842926 + outer loop + vertex 930.905 295.803 17.1647 + vertex 933.087 299.222 16.0755 + vertex 931.53 300.616 17.1794 + endloop + endfacet + facet normal 0.516005 -0.0896135 0.851885 + outer loop + vertex 931.685 289.433 16.0173 + vertex 932.484 294.303 16.0458 + vertex 930.112 290.985 17.1335 + endloop + endfacet + facet normal 0.51702 -0.0905743 0.851168 + outer loop + vertex 930.112 290.985 17.1335 + vertex 932.484 294.303 16.0458 + vertex 930.905 295.803 17.1647 + endloop + endfacet + facet normal 0.387805 -0.0697575 0.919098 + outer loop + vertex 930.112 290.985 17.1335 + vertex 930.905 295.803 17.1647 + vertex 928.703 292.944 17.8767 + endloop + endfacet + facet normal 0.386971 -0.0690136 0.919506 + outer loop + vertex 928.703 292.944 17.8767 + vertex 930.905 295.803 17.1647 + vertex 929.29 297.478 17.97 + endloop + endfacet + facet normal 0.399597 -0.0547056 0.915057 + outer loop + vertex 930.905 295.803 17.1647 + vertex 931.53 300.616 17.1794 + vertex 929.29 297.478 17.97 + endloop + endfacet + facet normal 0.425997 -0.076983 0.901443 + outer loop + vertex 929.29 297.478 17.97 + vertex 931.53 300.616 17.1794 + vertex 930.348 302.085 17.8635 + endloop + endfacet + facet normal 0.734402 -0.100505 0.671232 + outer loop + vertex 935.346 293.723 13.2965 + vertex 935.502 296.06 13.4757 + vertex 934.055 292.925 14.5895 + endloop + endfacet + facet normal 0.746802 -0.0773654 0.660531 + outer loop + vertex 935.919 298.663 13.3089 + vertex 934.68 297.841 14.6139 + vertex 935.502 296.06 13.4757 + endloop + endfacet + facet normal 0.729442 -0.0960723 0.677263 + outer loop + vertex 934.68 297.841 14.6139 + vertex 934.055 292.925 14.5895 + vertex 935.502 296.06 13.4757 + endloop + endfacet + facet normal 0.724425 -0.132588 0.676483 + outer loop + vertex 934.581 288.932 13.2841 + vertex 934.833 291.225 13.4643 + vertex 933.228 288.094 14.5687 + endloop + endfacet + facet normal 0.735675 -0.106269 0.668947 + outer loop + vertex 935.346 293.723 13.2965 + vertex 934.055 292.925 14.5895 + vertex 934.833 291.225 13.4643 + endloop + endfacet + facet normal 0.717155 -0.125688 0.685487 + outer loop + vertex 934.055 292.925 14.5895 + vertex 933.228 288.094 14.5687 + vertex 934.833 291.225 13.4643 + endloop + endfacet + facet normal 0.627557 -0.110721 0.770657 + outer loop + vertex 933.228 288.094 14.5687 + vertex 934.055 292.925 14.5895 + vertex 931.685 289.433 16.0173 + endloop + endfacet + facet normal 0.623954 -0.106861 0.77412 + outer loop + vertex 931.685 289.433 16.0173 + vertex 934.055 292.925 14.5895 + vertex 932.484 294.303 16.0458 + endloop + endfacet + facet normal 0.636461 -0.0846974 0.766645 + outer loop + vertex 934.055 292.925 14.5895 + vertex 934.68 297.841 14.6139 + vertex 932.484 294.303 16.0458 + endloop + endfacet + facet normal 0.634179 -0.0824164 0.768781 + outer loop + vertex 932.484 294.303 16.0458 + vertex 934.68 297.841 14.6139 + vertex 933.087 299.222 16.0755 + endloop + endfacet + facet normal 0.986994 -0.106164 -0.120718 + outer loop + vertex 936.331 295.062 8.9853 + vertex 936.599 297.556 8.98621 + vertex 936.46 295.027 10.0762 + endloop + endfacet + facet normal 0.986957 -0.106256 -0.120936 + outer loop + vertex 936.46 295.027 10.0762 + vertex 936.599 297.556 8.98621 + vertex 936.729 297.519 10.0781 + endloop + endfacet + facet normal 0.984983 -0.126365 -0.117645 + outer loop + vertex 936.018 292.625 8.98421 + vertex 936.331 295.062 8.9853 + vertex 936.144 292.595 10.0746 + endloop + endfacet + facet normal 0.984372 -0.127847 -0.121106 + outer loop + vertex 936.144 292.595 10.0746 + vertex 936.331 295.062 8.9853 + vertex 936.46 295.027 10.0762 + endloop + endfacet + facet normal 0.987918 -0.128443 0.0867169 + outer loop + vertex 936.144 292.595 10.0746 + vertex 936.46 295.027 10.0762 + vertex 936.065 292.747 11.2042 + endloop + endfacet + facet normal 0.98789 -0.127841 0.0879239 + outer loop + vertex 936.065 292.747 11.2042 + vertex 936.46 295.027 10.0762 + vertex 936.379 295.175 11.2065 + endloop + endfacet + facet normal 0.990609 -0.10681 0.0853537 + outer loop + vertex 936.46 295.027 10.0762 + vertex 936.729 297.519 10.0781 + vertex 936.379 295.175 11.2065 + endloop + endfacet + facet normal 0.990808 -0.110067 0.0786491 + outer loop + vertex 936.379 295.175 11.2065 + vertex 936.729 297.519 10.0781 + vertex 936.655 297.659 11.2089 + endloop + endfacet + facet normal 0.98321 -0.145057 -0.110711 + outer loop + vertex 935.661 290.206 8.98248 + vertex 936.018 292.625 8.98421 + vertex 935.779 290.179 10.0729 + endloop + endfacet + facet normal 0.981914 -0.148132 -0.117905 + outer loop + vertex 935.779 290.179 10.0729 + vertex 936.018 292.625 8.98421 + vertex 936.144 292.595 10.0746 + endloop + endfacet + facet normal 0.979259 -0.167307 -0.114283 + outer loop + vertex 935.244 287.77 8.9816 + vertex 935.661 290.206 8.98248 + vertex 935.366 287.74 10.0705 + endloop + endfacet + facet normal 0.979894 -0.165877 -0.110869 + outer loop + vertex 935.366 287.74 10.0705 + vertex 935.661 290.206 8.98248 + vertex 935.779 290.179 10.0729 + endloop + endfacet + facet normal 0.98125 -0.166312 0.097414 + outer loop + vertex 935.366 287.74 10.0705 + vertex 935.779 290.179 10.0729 + vertex 935.283 287.91 11.1986 + endloop + endfacet + facet normal 0.981281 -0.167501 0.0950307 + outer loop + vertex 935.283 287.91 11.1986 + vertex 935.779 290.179 10.0729 + vertex 935.698 290.343 11.2014 + endloop + endfacet + facet normal 0.984547 -0.148676 0.092537 + outer loop + vertex 935.779 290.179 10.0729 + vertex 936.144 292.595 10.0746 + vertex 935.698 290.343 11.2014 + endloop + endfacet + facet normal 0.984596 -0.15024 0.0894327 + outer loop + vertex 935.698 290.343 11.2014 + vertex 936.144 292.595 10.0746 + vertex 936.065 292.747 11.2042 + endloop + endfacet + facet normal 0.947059 -0.144747 0.286578 + outer loop + vertex 935.698 290.343 11.2014 + vertex 936.065 292.747 11.2042 + vertex 935.416 290.727 12.3292 + endloop + endfacet + facet normal 0.946907 -0.14429 0.287311 + outer loop + vertex 935.416 290.727 12.3292 + vertex 936.065 292.747 11.2042 + vertex 935.779 293.119 12.3336 + endloop + endfacet + facet normal 0.942731 -0.161155 0.292041 + outer loop + vertex 935.283 287.91 11.1986 + vertex 935.698 290.343 11.2014 + vertex 935.003 288.312 12.3259 + endloop + endfacet + facet normal 0.942885 -0.161629 0.29128 + outer loop + vertex 935.003 288.312 12.3259 + vertex 935.698 290.343 11.2014 + vertex 935.416 290.727 12.3292 + endloop + endfacet + facet normal 0.866076 -0.148751 0.477268 + outer loop + vertex 935.003 288.312 12.3259 + vertex 935.416 290.727 12.3292 + vertex 934.581 288.932 13.2841 + endloop + endfacet + facet normal 0.856644 -0.133098 0.498444 + outer loop + vertex 934.581 288.932 13.2841 + vertex 935.416 290.727 12.3292 + vertex 934.833 291.225 13.4643 + endloop + endfacet + facet normal 0.857285 -0.131066 0.49788 + outer loop + vertex 935.416 290.727 12.3292 + vertex 935.779 293.119 12.3336 + vertex 934.833 291.225 13.4643 + endloop + endfacet + facet normal 0.865047 -0.14555 0.480114 + outer loop + vertex 934.833 291.225 13.4643 + vertex 935.779 293.119 12.3336 + vertex 935.346 293.723 13.2965 + endloop + endfacet + facet normal 0.955393 -0.106328 0.275532 + outer loop + vertex 936.379 295.175 11.2065 + vertex 936.655 297.659 11.2089 + vertex 936.094 295.543 12.3374 + endloop + endfacet + facet normal 0.954736 -0.104594 0.278457 + outer loop + vertex 936.094 295.543 12.3374 + vertex 936.655 297.659 11.2089 + vertex 936.365 298.032 12.3412 + endloop + endfacet + facet normal 0.951576 -0.123324 0.281591 + outer loop + vertex 936.065 292.747 11.2042 + vertex 936.379 295.175 11.2065 + vertex 935.779 293.119 12.3336 + endloop + endfacet + facet normal 0.951835 -0.124056 0.280393 + outer loop + vertex 935.779 293.119 12.3336 + vertex 936.379 295.175 11.2065 + vertex 936.094 295.543 12.3374 + endloop + endfacet + facet normal 0.877213 -0.114661 0.466209 + outer loop + vertex 935.779 293.119 12.3336 + vertex 936.094 295.543 12.3374 + vertex 935.346 293.723 13.2965 + endloop + endfacet + facet normal 0.864846 -0.095529 0.492864 + outer loop + vertex 935.346 293.723 13.2965 + vertex 936.094 295.543 12.3374 + vertex 935.502 296.06 13.4757 + endloop + endfacet + facet normal 0.864963 -0.0951176 0.492738 + outer loop + vertex 936.094 295.543 12.3374 + vertex 936.365 298.032 12.3412 + vertex 935.502 296.06 13.4757 + endloop + endfacet + facet normal 0.873629 -0.109642 0.474079 + outer loop + vertex 935.502 296.06 13.4757 + vertex 936.365 298.032 12.3412 + vertex 935.919 298.663 13.3089 + endloop + endfacet + facet normal 0.612059 -0.0798915 -0.786766 + outer loop + vertex 933.362 295.494 4.97819 + vertex 933.831 297.71 5.11794 + vertex 934.559 295.321 5.92699 + endloop + endfacet + facet normal 0.638248 -0.0652328 -0.767062 + outer loop + vertex 934.559 295.321 5.92699 + vertex 933.831 297.71 5.11794 + vertex 934.813 297.794 5.928 + endloop + endfacet + facet normal 0.636429 -0.06274 -0.768779 + outer loop + vertex 933.269 292.841 5.11763 + vertex 933.362 295.494 4.97819 + vertex 934.254 292.904 5.92757 + endloop + endfacet + facet normal 0.612374 -0.0776109 -0.786749 + outer loop + vertex 934.254 292.904 5.92757 + vertex 933.362 295.494 4.97819 + vertex 934.559 295.321 5.92699 + endloop + endfacet + facet normal 0.752498 -0.0952948 -0.651664 + outer loop + vertex 934.254 292.904 5.92757 + vertex 934.559 295.321 5.92699 + vertex 935.093 292.84 6.90648 + endloop + endfacet + facet normal 0.753874 -0.0944202 -0.650199 + outer loop + vertex 935.093 292.84 6.90648 + vertex 934.559 295.321 5.92699 + vertex 935.397 295.266 6.90667 + endloop + endfacet + facet normal 0.755474 -0.0773193 -0.650601 + outer loop + vertex 934.559 295.321 5.92699 + vertex 934.813 297.794 5.928 + vertex 935.397 295.266 6.90667 + endloop + endfacet + facet normal 0.75452 -0.0779391 -0.651632 + outer loop + vertex 935.397 295.266 6.90667 + vertex 934.813 297.794 5.928 + vertex 935.655 297.753 6.90751 + endloop + endfacet + facet normal 0.61153 -0.104823 -0.784247 + outer loop + vertex 932.716 290.663 4.9772 + vertex 933.269 292.841 5.11763 + vertex 933.905 290.499 5.92691 + endloop + endfacet + facet normal 0.636109 -0.0918737 -0.76611 + outer loop + vertex 933.905 290.499 5.92691 + vertex 933.269 292.841 5.11763 + vertex 934.254 292.904 5.92757 + endloop + endfacet + facet normal 0.631664 -0.0896993 -0.770035 + outer loop + vertex 932.511 288.009 5.11883 + vertex 932.716 290.663 4.9772 + vertex 933.505 288.076 5.92608 + endloop + endfacet + facet normal 0.612116 -0.1009 -0.784304 + outer loop + vertex 933.505 288.076 5.92608 + vertex 932.716 290.663 4.9772 + vertex 933.905 290.499 5.92691 + endloop + endfacet + facet normal 0.750775 -0.123863 -0.648841 + outer loop + vertex 933.505 288.076 5.92608 + vertex 933.905 290.499 5.92691 + vertex 934.34 288.006 6.90514 + endloop + endfacet + facet normal 0.749809 -0.124427 -0.64985 + outer loop + vertex 934.34 288.006 6.90514 + vertex 933.905 290.499 5.92691 + vertex 934.743 290.432 6.90569 + endloop + endfacet + facet normal 0.751752 -0.108646 -0.650435 + outer loop + vertex 933.905 290.499 5.92691 + vertex 934.254 292.904 5.92757 + vertex 934.743 290.432 6.90569 + endloop + endfacet + facet normal 0.750968 -0.109127 -0.651259 + outer loop + vertex 934.743 290.432 6.90569 + vertex 934.254 292.904 5.92757 + vertex 935.093 292.84 6.90648 + endloop + endfacet + facet normal 0.858497 -0.124833 -0.497393 + outer loop + vertex 934.743 290.432 6.90569 + vertex 935.093 292.84 6.90648 + vertex 935.32 290.322 7.93012 + endloop + endfacet + facet normal 0.857748 -0.125371 -0.498549 + outer loop + vertex 935.32 290.322 7.93012 + vertex 935.093 292.84 6.90648 + vertex 935.674 292.736 7.93114 + endloop + endfacet + facet normal 0.856738 -0.142227 -0.495753 + outer loop + vertex 934.34 288.006 6.90514 + vertex 934.743 290.432 6.90569 + vertex 934.913 287.89 7.92926 + endloop + endfacet + facet normal 0.85549 -0.143078 -0.497659 + outer loop + vertex 934.913 287.89 7.92926 + vertex 934.743 290.432 6.90569 + vertex 935.32 290.322 7.93012 + endloop + endfacet + facet normal 0.93675 -0.156751 -0.312936 + outer loop + vertex 934.913 287.89 7.92926 + vertex 935.32 290.322 7.93012 + vertex 935.244 287.77 8.9816 + endloop + endfacet + facet normal 0.933967 -0.159493 -0.319793 + outer loop + vertex 935.244 287.77 8.9816 + vertex 935.32 290.322 7.93012 + vertex 935.661 290.206 8.98248 + endloop + endfacet + facet normal 0.937907 -0.137183 -0.318608 + outer loop + vertex 935.32 290.322 7.93012 + vertex 935.674 292.736 7.93114 + vertex 935.661 290.206 8.98248 + endloop + endfacet + facet normal 0.937027 -0.138089 -0.3208 + outer loop + vertex 935.661 290.206 8.98248 + vertex 935.674 292.736 7.93114 + vertex 936.018 292.625 8.98421 + endloop + endfacet + facet normal 0.860359 -0.0889537 -0.501865 + outer loop + vertex 935.397 295.266 6.90667 + vertex 935.655 297.753 6.90751 + vertex 935.985 295.171 7.9315 + endloop + endfacet + facet normal 0.860252 -0.0890348 -0.502035 + outer loop + vertex 935.985 295.171 7.9315 + vertex 935.655 297.753 6.90751 + vertex 936.244 297.666 7.93267 + endloop + endfacet + facet normal 0.860321 -0.107772 -0.49823 + outer loop + vertex 935.093 292.84 6.90648 + vertex 935.397 295.266 6.90667 + vertex 935.674 292.736 7.93114 + endloop + endfacet + facet normal 0.857719 -0.109696 -0.50228 + outer loop + vertex 935.674 292.736 7.93114 + vertex 935.397 295.266 6.90667 + vertex 935.985 295.171 7.9315 + endloop + endfacet + facet normal 0.939816 -0.12023 -0.31983 + outer loop + vertex 935.674 292.736 7.93114 + vertex 935.985 295.171 7.9315 + vertex 936.018 292.625 8.98421 + endloop + endfacet + facet normal 0.939609 -0.12045 -0.320355 + outer loop + vertex 936.018 292.625 8.98421 + vertex 935.985 295.171 7.9315 + vertex 936.331 295.062 8.9853 + endloop + endfacet + facet normal 0.942702 -0.0976762 -0.319017 + outer loop + vertex 935.985 295.171 7.9315 + vertex 936.244 297.666 7.93267 + vertex 936.331 295.062 8.9853 + endloop + endfacet + facet normal 0.939625 -0.100992 -0.326965 + outer loop + vertex 936.331 295.062 8.9853 + vertex 936.244 297.666 7.93267 + vertex 936.599 297.556 8.98621 + endloop + endfacet + facet normal 0.381737 -0.037777 -0.923499 + outer loop + vertex 928.812 294.928 2.90219 + vertex 929.3 299.806 2.90432 + vertex 931.599 294.719 4.06278 + endloop + endfacet + facet normal 0.380703 -0.0383362 -0.923902 + outer loop + vertex 931.599 294.719 4.06278 + vertex 929.3 299.806 2.90432 + vertex 932.095 299.638 4.06295 + endloop + endfacet + facet normal 0.381726 -0.0533525 -0.922734 + outer loop + vertex 928.136 290.107 2.90155 + vertex 928.812 294.928 2.90219 + vertex 930.914 289.876 4.06398 + endloop + endfacet + facet normal 0.380409 -0.0540164 -0.923239 + outer loop + vertex 930.914 289.876 4.06398 + vertex 928.812 294.928 2.90219 + vertex 931.599 294.719 4.06278 + endloop + endfacet + facet normal 0.479273 -0.0653487 -0.87523 + outer loop + vertex 933.269 292.841 5.11763 + vertex 932.716 290.663 4.9772 + vertex 931.599 294.719 4.06278 + endloop + endfacet + facet normal 0.479327 -0.0835091 -0.873654 + outer loop + vertex 932.511 288.009 5.11883 + vertex 930.914 289.876 4.06398 + vertex 932.716 290.663 4.9772 + endloop + endfacet + facet normal 0.474326 -0.0672843 -0.877774 + outer loop + vertex 930.914 289.876 4.06398 + vertex 931.599 294.719 4.06278 + vertex 932.716 290.663 4.9772 + endloop + endfacet + facet normal 0.480496 -0.046443 -0.875766 + outer loop + vertex 933.831 297.71 5.11794 + vertex 933.362 295.494 4.97819 + vertex 932.095 299.638 4.06295 + endloop + endfacet + facet normal 0.48145 -0.0628443 -0.874218 + outer loop + vertex 933.269 292.841 5.11763 + vertex 931.599 294.719 4.06278 + vertex 933.362 295.494 4.97819 + endloop + endfacet + facet normal 0.476757 -0.0480183 -0.877722 + outer loop + vertex 931.599 294.719 4.06278 + vertex 932.095 299.638 4.06295 + vertex 933.362 295.494 4.97819 + endloop + endfacet + facet normal 0.174384 -0.0250259 -0.98436 + outer loop + vertex 922.415 295.665 1.41421 + vertex 923.459 299.965 1.48972 + vertex 925.853 295.178 2.03566 + endloop + endfacet + facet normal 0.186727 -0.0186093 -0.982236 + outer loop + vertex 925.853 295.178 2.03566 + vertex 923.459 299.965 1.48972 + vertex 926.333 299.998 2.03559 + endloop + endfacet + facet normal 0.18867 -0.0173157 -0.981888 + outer loop + vertex 922.313 290.434 1.48687 + vertex 922.415 295.665 1.41421 + vertex 925.182 290.395 2.03874 + endloop + endfacet + facet normal 0.174371 -0.0251149 -0.98436 + outer loop + vertex 925.182 290.395 2.03874 + vertex 922.415 295.665 1.41421 + vertex 925.853 295.178 2.03566 + endloop + endfacet + facet normal 0.276555 -0.0394463 -0.960188 + outer loop + vertex 925.182 290.395 2.03874 + vertex 925.853 295.178 2.03566 + vertex 928.136 290.107 2.90155 + endloop + endfacet + facet normal 0.277863 -0.0387976 -0.959837 + outer loop + vertex 928.136 290.107 2.90155 + vertex 925.853 295.178 2.03566 + vertex 928.812 294.928 2.90219 + endloop + endfacet + facet normal 0.278821 -0.0277796 -0.959941 + outer loop + vertex 925.853 295.178 2.03566 + vertex 926.333 299.998 2.03559 + vertex 928.812 294.928 2.90219 + endloop + endfacet + facet normal 0.279311 -0.0275168 -0.959806 + outer loop + vertex 928.812 294.928 2.90219 + vertex 926.333 299.998 2.03559 + vertex 929.3 299.806 2.90432 + endloop + endfacet + facet normal 0.10882 -0.00894689 -0.994021 + outer loop + vertex 923.459 299.965 1.48972 + vertex 922.415 295.665 1.41421 + vertex 918.938 303.753 0.960715 + endloop + endfacet + facet normal 0.108242 -0.015916 -0.993997 + outer loop + vertex 922.313 290.434 1.48687 + vertex 918.041 294.246 0.96056 + vertex 922.415 295.665 1.41421 + endloop + endfacet + facet normal 0.106359 -0.0100195 -0.994277 + outer loop + vertex 918.041 294.246 0.96056 + vertex 918.938 303.753 0.960715 + vertex 922.415 295.665 1.41421 + endloop + endfacet + facet normal 0.975359 -0.112969 0.189507 + outer loop + vertex 897.474 318.247 46.2583 + vertex 898.43 326.509 46.262 + vertex 897.182 319.623 48.5846 + endloop + endfacet + facet normal 0.971722 -0.104869 0.211564 + outer loop + vertex 897.182 319.623 48.5846 + vertex 898.43 326.509 46.262 + vertex 898.048 327.702 48.609 + endloop + endfacet + facet normal 0.961581 -0.115587 0.249003 + outer loop + vertex 898.196 316.968 42.877 + vertex 899.192 325.325 42.9089 + vertex 897.474 318.247 46.2583 + endloop + endfacet + facet normal 0.959888 -0.111209 0.257386 + outer loop + vertex 897.474 318.247 46.2583 + vertex 899.192 325.325 42.9089 + vertex 898.43 326.509 46.262 + endloop + endfacet + facet normal 0.950681 -0.11793 0.286877 + outer loop + vertex 899.279 315.448 38.6625 + vertex 900.309 323.882 38.7168 + vertex 898.196 316.968 42.877 + endloop + endfacet + facet normal 0.949476 -0.114309 0.292282 + outer loop + vertex 898.196 316.968 42.877 + vertex 900.309 323.882 38.7168 + vertex 899.192 325.325 42.9089 + endloop + endfacet + facet normal 0.93732 -0.11931 0.327407 + outer loop + vertex 900.68 313.575 33.97 + vertex 901.732 322.024 34.0359 + vertex 899.279 315.448 38.6625 + endloop + endfacet + facet normal 0.936427 -0.116473 0.330966 + outer loop + vertex 899.279 315.448 38.6625 + vertex 901.732 322.024 34.0359 + vertex 900.309 323.882 38.7168 + endloop + endfacet + facet normal 0.878924 -0.0799574 0.470212 + outer loop + vertex 904.589 317.611 26.7433 + vertex 904.952 321.907 26.7947 + vertex 903.652 318.276 28.6062 + endloop + endfacet + facet normal 0.87785 -0.0784476 0.472467 + outer loop + vertex 903.652 318.276 28.6062 + vertex 904.952 321.907 26.7947 + vertex 904.012 322.574 28.6518 + endloop + endfacet + facet normal 0.87166 -0.111579 0.47724 + outer loop + vertex 904.081 313.409 26.6879 + vertex 904.589 317.611 26.7433 + vertex 903.141 314.066 28.5582 + endloop + endfacet + facet normal 0.871475 -0.111296 0.477646 + outer loop + vertex 903.141 314.066 28.5582 + vertex 904.589 317.611 26.7433 + vertex 903.652 318.276 28.6062 + endloop + endfacet + facet normal 0.692139 -0.0679451 0.718559 + outer loop + vertex 906.822 316.717 24.0487 + vertex 907.179 321.015 24.1112 + vertex 905.635 317.158 25.2337 + endloop + endfacet + facet normal 0.691694 -0.0676335 0.719017 + outer loop + vertex 905.635 317.158 25.2337 + vertex 907.179 321.015 24.1112 + vertex 905.995 321.454 25.2909 + endloop + endfacet + facet normal 0.683953 -0.0906985 0.723866 + outer loop + vertex 906.33 312.488 23.9836 + vertex 906.822 316.717 24.0487 + vertex 905.134 312.95 25.1714 + endloop + endfacet + facet normal 0.686118 -0.092342 0.721606 + outer loop + vertex 905.134 312.95 25.1714 + vertex 906.822 316.717 24.0487 + vertex 905.635 317.158 25.2337 + endloop + endfacet + facet normal 0.397477 -0.0465849 0.916429 + outer loop + vertex 909.753 315.081 22.3917 + vertex 910.1 319.441 22.4627 + vertex 908.184 316.066 23.1224 + endloop + endfacet + facet normal 0.396489 -0.0459337 0.91689 + outer loop + vertex 908.184 316.066 23.1224 + vertex 910.1 319.441 22.4627 + vertex 908.536 320.383 23.1861 + endloop + endfacet + facet normal 0.391712 -0.0599604 0.918132 + outer loop + vertex 909.276 310.76 22.313 + vertex 909.753 315.081 22.3917 + vertex 907.701 311.796 23.0528 + endloop + endfacet + facet normal 0.390616 -0.0591717 0.91865 + outer loop + vertex 907.701 311.796 23.0528 + vertex 909.753 315.081 22.3917 + vertex 908.184 316.066 23.1224 + endloop + endfacet + facet normal 0.534351 -0.0741805 0.842001 + outer loop + vertex 907.701 311.796 23.0528 + vertex 908.184 316.066 23.1224 + vertex 906.33 312.488 23.9836 + endloop + endfacet + facet normal 0.535962 -0.0752859 0.840878 + outer loop + vertex 906.33 312.488 23.9836 + vertex 908.184 316.066 23.1224 + vertex 906.822 316.717 24.0487 + endloop + endfacet + facet normal 0.542827 -0.0567261 0.837927 + outer loop + vertex 908.184 316.066 23.1224 + vertex 908.536 320.383 23.1861 + vertex 906.822 316.717 24.0487 + endloop + endfacet + facet normal 0.543815 -0.0573494 0.837243 + outer loop + vertex 906.822 316.717 24.0487 + vertex 908.536 320.383 23.1861 + vertex 907.179 321.015 24.1112 + endloop + endfacet + facet normal 0.201335 -0.0309329 0.979034 + outer loop + vertex 913.596 312.401 21.3496 + vertex 913.57 316.757 21.4927 + vertex 911.524 313.788 21.8195 + endloop + endfacet + facet normal 0.203989 -0.0328281 0.978423 + outer loop + vertex 911.524 313.788 21.8195 + vertex 913.57 316.757 21.4927 + vertex 911.862 318.218 21.8978 + endloop + endfacet + facet normal 0.199206 -0.0441933 0.978961 + outer loop + vertex 912.727 307.819 21.3196 + vertex 913.596 312.401 21.3496 + vertex 911.049 309.405 21.7327 + endloop + endfacet + facet normal 0.195092 -0.0405705 0.979945 + outer loop + vertex 911.049 309.405 21.7327 + vertex 913.596 312.401 21.3496 + vertex 911.524 313.788 21.8195 + endloop + endfacet + facet normal 0.276621 -0.0490101 0.959729 + outer loop + vertex 911.049 309.405 21.7327 + vertex 911.524 313.788 21.8195 + vertex 909.276 310.76 22.313 + endloop + endfacet + facet normal 0.275188 -0.0478695 0.960198 + outer loop + vertex 909.276 310.76 22.313 + vertex 911.524 313.788 21.8195 + vertex 909.753 315.081 22.3917 + endloop + endfacet + facet normal 0.281639 -0.0383951 0.958752 + outer loop + vertex 911.524 313.788 21.8195 + vertex 911.862 318.218 21.8978 + vertex 909.753 315.081 22.3917 + endloop + endfacet + facet normal 0.2811 -0.0380049 0.958926 + outer loop + vertex 909.753 315.081 22.3917 + vertex 911.862 318.218 21.8978 + vertex 910.1 319.441 22.4627 + endloop + endfacet + facet normal 0.562561 -0.0284336 0.826267 + outer loop + vertex 933.516 304.236 16.0969 + vertex 933.756 309.323 16.1086 + vertex 931.957 305.436 17.1997 + endloop + endfacet + facet normal 0.561129 -0.0274886 0.827272 + outer loop + vertex 931.957 305.436 17.1997 + vertex 933.756 309.323 16.1086 + vertex 932.126 310.444 17.2513 + endloop + endfacet + facet normal 0.547213 -0.0503038 0.83548 + outer loop + vertex 933.087 299.222 16.0755 + vertex 933.516 304.236 16.0969 + vertex 931.53 300.616 17.1794 + endloop + endfacet + facet normal 0.549631 -0.0521381 0.833779 + outer loop + vertex 931.53 300.616 17.1794 + vertex 933.516 304.236 16.0969 + vertex 931.957 305.436 17.1997 + endloop + endfacet + facet normal 0.458566 -0.0443083 0.887555 + outer loop + vertex 931.53 300.616 17.1794 + vertex 931.957 305.436 17.1997 + vertex 930.348 302.085 17.8635 + endloop + endfacet + facet normal 0.44126 -0.0341846 0.896728 + outer loop + vertex 930.348 302.085 17.8635 + vertex 931.957 305.436 17.1997 + vertex 930.383 306.208 18.0033 + endloop + endfacet + facet normal 0.445273 -0.0242708 0.895066 + outer loop + vertex 931.957 305.436 17.1997 + vertex 932.126 310.444 17.2513 + vertex 930.383 306.208 18.0033 + endloop + endfacet + facet normal 0.442145 -0.0227016 0.896656 + outer loop + vertex 930.383 306.208 18.0033 + vertex 932.126 310.444 17.2513 + vertex 930.467 311.523 18.0966 + endloop + endfacet + facet normal 0.753893 -0.0428553 0.655598 + outer loop + vertex 936.306 303.869 13.3195 + vertex 936.289 306.376 13.5028 + vertex 935.115 302.937 14.6282 + endloop + endfacet + facet normal 0.764577 -0.0153585 0.644349 + outer loop + vertex 936.49 309.111 13.329 + vertex 935.365 308.108 14.6401 + vertex 936.289 306.376 13.5028 + endloop + endfacet + facet normal 0.74682 -0.0377042 0.663957 + outer loop + vertex 935.365 308.108 14.6401 + vertex 935.115 302.937 14.6282 + vertex 936.289 306.376 13.5028 + endloop + endfacet + facet normal 0.74487 -0.0696324 0.663566 + outer loop + vertex 935.919 298.663 13.3089 + vertex 935.99 301.134 13.4888 + vertex 934.68 297.841 14.6139 + endloop + endfacet + facet normal 0.755102 -0.0467315 0.65394 + outer loop + vertex 936.306 303.869 13.3195 + vertex 935.115 302.937 14.6282 + vertex 935.99 301.134 13.4888 + endloop + endfacet + facet normal 0.739075 -0.0649637 0.670484 + outer loop + vertex 935.115 302.937 14.6282 + vertex 934.68 297.841 14.6139 + vertex 935.99 301.134 13.4888 + endloop + endfacet + facet normal 0.647623 -0.0574093 0.759795 + outer loop + vertex 934.68 297.841 14.6139 + vertex 935.115 302.937 14.6282 + vertex 933.087 299.222 16.0755 + endloop + endfacet + facet normal 0.649019 -0.0586728 0.758507 + outer loop + vertex 933.087 299.222 16.0755 + vertex 935.115 302.937 14.6282 + vertex 933.516 304.236 16.0969 + endloop + endfacet + facet normal 0.661061 -0.0337479 0.749573 + outer loop + vertex 935.115 302.937 14.6282 + vertex 935.365 308.108 14.6401 + vertex 933.516 304.236 16.0969 + endloop + endfacet + facet normal 0.659973 -0.0328533 0.75057 + outer loop + vertex 933.516 304.236 16.0969 + vertex 935.365 308.108 14.6401 + vertex 933.756 309.323 16.1086 + endloop + endfacet + facet normal 0.991209 -0.0241317 -0.130088 + outer loop + vertex 937.112 305.417 8.98944 + vertex 937.177 308.053 8.99073 + vertex 937.255 305.38 10.0828 + endloop + endfacet + facet normal 0.990813 -0.0252755 -0.13286 + outer loop + vertex 937.255 305.38 10.0828 + vertex 937.177 308.053 8.99073 + vertex 937.323 308.019 10.0846 + endloop + endfacet + facet normal 0.990834 -0.0457793 -0.127092 + outer loop + vertex 936.99 302.764 8.9888 + vertex 937.112 305.417 8.98944 + vertex 937.128 302.725 10.0817 + endloop + endfacet + facet normal 0.990286 -0.0472726 -0.130765 + outer loop + vertex 937.128 302.725 10.0817 + vertex 937.112 305.417 8.98944 + vertex 937.255 305.38 10.0828 + endloop + endfacet + facet normal 0.996611 -0.0476592 0.0670444 + outer loop + vertex 937.128 302.725 10.0817 + vertex 937.255 305.38 10.0828 + vertex 937.059 302.865 11.214 + endloop + endfacet + facet normal 0.996638 -0.047926 0.0664557 + outer loop + vertex 937.059 302.865 11.214 + vertex 937.255 305.38 10.0828 + vertex 937.186 305.521 11.2163 + endloop + endfacet + facet normal 0.997639 -0.025586 0.0637328 + outer loop + vertex 937.255 305.38 10.0828 + vertex 937.323 308.019 10.0846 + vertex 937.186 305.521 11.2163 + endloop + endfacet + facet normal 0.997652 -0.0257016 0.0634794 + outer loop + vertex 937.186 305.521 11.2163 + vertex 937.323 308.019 10.0846 + vertex 937.254 308.16 11.2189 + endloop + endfacet + facet normal 0.990252 -0.0642225 -0.123597 + outer loop + vertex 936.819 300.129 8.98752 + vertex 936.99 302.764 8.9888 + vertex 936.953 300.091 10.0798 + endloop + endfacet + facet normal 0.989628 -0.0658729 -0.127661 + outer loop + vertex 936.953 300.091 10.0798 + vertex 936.99 302.764 8.9888 + vertex 937.128 302.725 10.0817 + endloop + endfacet + facet normal 0.989118 -0.0844539 -0.120467 + outer loop + vertex 936.599 297.556 8.98621 + vertex 936.819 300.129 8.98752 + vertex 936.729 297.519 10.0781 + endloop + endfacet + facet normal 0.988532 -0.0859723 -0.124149 + outer loop + vertex 936.729 297.519 10.0781 + vertex 936.819 300.129 8.98752 + vertex 936.953 300.091 10.0798 + endloop + endfacet + facet normal 0.993354 -0.086524 0.0759037 + outer loop + vertex 936.729 297.519 10.0781 + vertex 936.953 300.091 10.0798 + vertex 936.655 297.659 11.2089 + endloop + endfacet + facet normal 0.993346 -0.0864165 0.0761332 + outer loop + vertex 936.655 297.659 11.2089 + vertex 936.953 300.091 10.0798 + vertex 936.878 300.233 11.2113 + endloop + endfacet + facet normal 0.995066 -0.0663763 0.0737388 + outer loop + vertex 936.953 300.091 10.0798 + vertex 937.128 302.725 10.0817 + vertex 936.878 300.233 11.2113 + endloop + endfacet + facet normal 0.995239 -0.0683057 0.0695205 + outer loop + vertex 936.878 300.233 11.2113 + vertex 937.128 302.725 10.0817 + vertex 937.059 302.865 11.214 + endloop + endfacet + facet normal 0.961626 -0.0662026 0.266258 + outer loop + vertex 936.878 300.233 11.2113 + vertex 937.059 302.865 11.214 + vertex 936.59 300.606 12.3453 + endloop + endfacet + facet normal 0.960955 -0.064669 0.269042 + outer loop + vertex 936.59 300.606 12.3453 + vertex 937.059 302.865 11.214 + vertex 936.766 303.241 12.3491 + endloop + endfacet + facet normal 0.95852 -0.0835706 0.272499 + outer loop + vertex 936.655 297.659 11.2089 + vertex 936.878 300.233 11.2113 + vertex 936.365 298.032 12.3412 + endloop + endfacet + facet normal 0.958765 -0.0841662 0.27145 + outer loop + vertex 936.365 298.032 12.3412 + vertex 936.878 300.233 11.2113 + vertex 936.59 300.606 12.3453 + endloop + endfacet + facet normal 0.885113 -0.0780368 0.458787 + outer loop + vertex 936.365 298.032 12.3412 + vertex 936.59 300.606 12.3453 + vertex 935.919 298.663 13.3089 + endloop + endfacet + facet normal 0.872151 -0.0603189 0.485504 + outer loop + vertex 935.919 298.663 13.3089 + vertex 936.59 300.606 12.3453 + vertex 935.99 301.134 13.4888 + endloop + endfacet + facet normal 0.872468 -0.0590588 0.485089 + outer loop + vertex 936.59 300.606 12.3453 + vertex 936.766 303.241 12.3491 + vertex 935.99 301.134 13.4888 + endloop + endfacet + facet normal 0.881925 -0.0730313 0.465698 + outer loop + vertex 935.99 301.134 13.4888 + vertex 936.766 303.241 12.3491 + vertex 936.306 303.869 13.3195 + endloop + endfacet + facet normal 0.965432 -0.0250691 0.259447 + outer loop + vertex 937.186 305.521 11.2163 + vertex 937.254 308.16 11.2189 + vertex 936.891 305.89 12.3526 + endloop + endfacet + facet normal 0.965717 -0.0256752 0.258325 + outer loop + vertex 936.891 305.89 12.3526 + vertex 937.254 308.16 11.2189 + vertex 936.959 308.519 12.3569 + endloop + endfacet + facet normal 0.96349 -0.0465031 0.263675 + outer loop + vertex 937.059 302.865 11.214 + vertex 937.186 305.521 11.2163 + vertex 936.766 303.241 12.3491 + endloop + endfacet + facet normal 0.963043 -0.0455268 0.265474 + outer loop + vertex 936.766 303.241 12.3491 + vertex 937.186 305.521 11.2163 + vertex 936.891 305.89 12.3526 + endloop + endfacet + facet normal 0.891739 -0.0424244 0.450558 + outer loop + vertex 936.766 303.241 12.3491 + vertex 936.891 305.89 12.3526 + vertex 936.306 303.869 13.3195 + endloop + endfacet + facet normal 0.880735 -0.0286286 0.472743 + outer loop + vertex 936.306 303.869 13.3195 + vertex 936.891 305.89 12.3526 + vertex 936.289 306.376 13.5028 + endloop + endfacet + facet normal 0.881694 -0.023832 0.471219 + outer loop + vertex 936.891 305.89 12.3526 + vertex 936.959 308.519 12.3569 + vertex 936.289 306.376 13.5028 + endloop + endfacet + facet normal 0.891093 -0.0368746 0.452321 + outer loop + vertex 936.289 306.376 13.5028 + vertex 936.959 308.519 12.3569 + vertex 936.49 309.111 13.329 + endloop + endfacet + facet normal 0.616741 -0.0300313 -0.786593 + outer loop + vertex 934.108 305.682 4.97847 + vertex 934.403 308.079 5.11867 + vertex 935.314 305.609 5.92718 + endloop + endfacet + facet normal 0.642094 -0.0141053 -0.766496 + outer loop + vertex 935.314 305.609 5.92718 + vertex 934.403 308.079 5.11867 + vertex 935.373 308.239 5.92853 + endloop + endfacet + facet normal 0.635957 -0.0150823 -0.771577 + outer loop + vertex 934.211 302.822 5.11989 + vertex 934.108 305.682 4.97847 + vertex 935.195 302.961 5.92779 + endloop + endfacet + facet normal 0.616857 -0.0279452 -0.786579 + outer loop + vertex 935.195 302.961 5.92779 + vertex 934.108 305.682 4.97847 + vertex 935.314 305.609 5.92718 + endloop + endfacet + facet normal 0.757701 -0.0342536 -0.651702 + outer loop + vertex 935.195 302.961 5.92779 + vertex 935.314 305.609 5.92718 + vertex 936.038 302.952 6.90817 + endloop + endfacet + facet normal 0.759583 -0.0329563 -0.649575 + outer loop + vertex 936.038 302.952 6.90817 + vertex 935.314 305.609 5.92718 + vertex 936.153 305.604 6.90834 + endloop + endfacet + facet normal 0.759925 -0.0168265 -0.649793 + outer loop + vertex 935.314 305.609 5.92718 + vertex 935.373 308.239 5.92853 + vertex 936.153 305.604 6.90834 + endloop + endfacet + facet normal 0.759465 -0.0171593 -0.650322 + outer loop + vertex 936.153 305.604 6.90834 + vertex 935.373 308.239 5.92853 + vertex 936.213 308.233 6.90918 + endloop + endfacet + facet normal 0.613442 -0.0536071 -0.787918 + outer loop + vertex 933.826 300.476 4.97929 + vertex 934.211 302.822 5.11989 + vertex 935.031 300.343 5.92692 + endloop + endfacet + facet normal 0.637583 -0.0395813 -0.769364 + outer loop + vertex 935.031 300.343 5.92692 + vertex 934.211 302.822 5.11989 + vertex 935.195 302.961 5.92779 + endloop + endfacet + facet normal 0.637747 -0.0373362 -0.76934 + outer loop + vertex 933.831 297.71 5.11794 + vertex 933.826 300.476 4.97929 + vertex 934.813 297.794 5.928 + endloop + endfacet + facet normal 0.613521 -0.0528213 -0.78791 + outer loop + vertex 934.813 297.794 5.928 + vertex 933.826 300.476 4.97929 + vertex 935.031 300.343 5.92692 + endloop + endfacet + facet normal 0.755496 -0.0649098 -0.65193 + outer loop + vertex 934.813 297.794 5.928 + vertex 935.031 300.343 5.92692 + vertex 935.655 297.753 6.90751 + endloop + endfacet + facet normal 0.755992 -0.0645847 -0.651386 + outer loop + vertex 935.655 297.753 6.90751 + vertex 935.031 300.343 5.92692 + vertex 935.874 300.32 6.90721 + endloop + endfacet + facet normal 0.756941 -0.0470771 -0.651785 + outer loop + vertex 935.031 300.343 5.92692 + vertex 935.195 302.961 5.92779 + vertex 935.874 300.32 6.90721 + endloop + endfacet + facet normal 0.757257 -0.0468653 -0.651433 + outer loop + vertex 935.874 300.32 6.90721 + vertex 935.195 302.961 5.92779 + vertex 936.038 302.952 6.90817 + endloop + endfacet + facet normal 0.863616 -0.0535362 -0.501299 + outer loop + vertex 935.874 300.32 6.90721 + vertex 936.038 302.952 6.90817 + vertex 936.464 300.239 7.93311 + endloop + endfacet + facet normal 0.862334 -0.0545296 -0.503395 + outer loop + vertex 936.464 300.239 7.93311 + vertex 936.038 302.952 6.90817 + vertex 936.631 302.873 7.93398 + endloop + endfacet + facet normal 0.861917 -0.0736057 -0.501678 + outer loop + vertex 935.655 297.753 6.90751 + vertex 935.874 300.32 6.90721 + vertex 936.244 297.666 7.93267 + endloop + endfacet + facet normal 0.861806 -0.07369 -0.501856 + outer loop + vertex 936.244 297.666 7.93267 + vertex 935.874 300.32 6.90721 + vertex 936.464 300.239 7.93311 + endloop + endfacet + facet normal 0.942048 -0.0805891 -0.325654 + outer loop + vertex 936.244 297.666 7.93267 + vertex 936.464 300.239 7.93311 + vertex 936.599 297.556 8.98621 + endloop + endfacet + facet normal 0.942272 -0.080347 -0.325066 + outer loop + vertex 936.599 297.556 8.98621 + vertex 936.464 300.239 7.93311 + vertex 936.819 300.129 8.98752 + endloop + endfacet + facet normal 0.944298 -0.0597885 -0.323615 + outer loop + vertex 936.464 300.239 7.93311 + vertex 936.631 302.873 7.93398 + vertex 936.819 300.129 8.98752 + endloop + endfacet + facet normal 0.943141 -0.0610657 -0.326736 + outer loop + vertex 936.819 300.129 8.98752 + vertex 936.631 302.873 7.93398 + vertex 936.99 302.764 8.9888 + endloop + endfacet + facet normal 0.864448 -0.0196072 -0.502339 + outer loop + vertex 936.153 305.604 6.90834 + vertex 936.213 308.233 6.90918 + vertex 936.747 305.526 7.93471 + endloop + endfacet + facet normal 0.863847 -0.0201102 -0.503353 + outer loop + vertex 936.747 305.526 7.93471 + vertex 936.213 308.233 6.90918 + vertex 936.809 308.157 7.93553 + endloop + endfacet + facet normal 0.863581 -0.0374834 -0.502815 + outer loop + vertex 936.038 302.952 6.90817 + vertex 936.153 305.604 6.90834 + vertex 936.631 302.873 7.93398 + endloop + endfacet + facet normal 0.863406 -0.0376226 -0.503104 + outer loop + vertex 936.631 302.873 7.93398 + vertex 936.153 305.604 6.90834 + vertex 936.747 305.526 7.93471 + endloop + endfacet + facet normal 0.944739 -0.0412286 -0.325221 + outer loop + vertex 936.631 302.873 7.93398 + vertex 936.747 305.526 7.93471 + vertex 936.99 302.764 8.9888 + endloop + endfacet + facet normal 0.942724 -0.0435055 -0.330725 + outer loop + vertex 936.99 302.764 8.9888 + vertex 936.747 305.526 7.93471 + vertex 937.112 305.417 8.98944 + endloop + endfacet + facet normal 0.94408 -0.0220467 -0.328978 + outer loop + vertex 936.747 305.526 7.93471 + vertex 936.809 308.157 7.93553 + vertex 937.112 305.417 8.98944 + endloop + endfacet + facet normal 0.943386 -0.0228664 -0.330908 + outer loop + vertex 937.112 305.417 8.98944 + vertex 936.809 308.157 7.93553 + vertex 937.177 308.053 8.99073 + endloop + endfacet + facet normal 0.381234 -0.0100745 -0.924424 + outer loop + vertex 929.612 304.805 2.90539 + vertex 929.747 309.91 2.90548 + vertex 932.412 304.726 4.06117 + endloop + endfacet + facet normal 0.383241 -0.00886032 -0.923606 + outer loop + vertex 932.412 304.726 4.06117 + vertex 929.747 309.91 2.90548 + vertex 932.536 309.91 4.06293 + endloop + endfacet + facet normal 0.381632 -0.0236217 -0.924013 + outer loop + vertex 929.3 299.806 2.90432 + vertex 929.612 304.805 2.90539 + vertex 932.095 299.638 4.06295 + endloop + endfacet + facet normal 0.380803 -0.0240935 -0.924342 + outer loop + vertex 932.095 299.638 4.06295 + vertex 929.612 304.805 2.90539 + vertex 932.412 304.726 4.06117 + endloop + endfacet + facet normal 0.48528 -0.0273888 -0.87393 + outer loop + vertex 934.211 302.822 5.11989 + vertex 933.826 300.476 4.97929 + vertex 932.412 304.726 4.06117 + endloop + endfacet + facet normal 0.483534 -0.0428916 -0.874274 + outer loop + vertex 933.831 297.71 5.11794 + vertex 932.095 299.638 4.06295 + vertex 933.826 300.476 4.97929 + endloop + endfacet + facet normal 0.478996 -0.0302066 -0.877297 + outer loop + vertex 932.095 299.638 4.06295 + vertex 932.412 304.726 4.06117 + vertex 933.826 300.476 4.97929 + endloop + endfacet + facet normal 0.485709 -0.00875917 -0.874077 + outer loop + vertex 934.403 308.079 5.11867 + vertex 934.108 305.682 4.97847 + vertex 932.536 309.91 4.06293 + endloop + endfacet + facet normal 0.486797 -0.0255164 -0.873142 + outer loop + vertex 934.211 302.822 5.11989 + vertex 932.412 304.726 4.06117 + vertex 934.108 305.682 4.97847 + endloop + endfacet + facet normal 0.480709 -0.0112093 -0.876808 + outer loop + vertex 932.412 304.726 4.06117 + vertex 932.536 309.91 4.06293 + vertex 934.108 305.682 4.97847 + endloop + endfacet + facet normal 0.176244 -0.0127447 -0.984264 + outer loop + vertex 923.188 305.289 1.41308 + vertex 923.928 309.763 1.48769 + vertex 926.643 304.922 2.0366 + endloop + endfacet + facet normal 0.189289 -0.00516062 -0.981908 + outer loop + vertex 926.643 304.922 2.0366 + vertex 923.928 309.763 1.48769 + vertex 926.781 309.949 2.03681 + endloop + endfacet + facet normal 0.1866 -0.00464145 -0.982425 + outer loop + vertex 923.459 299.965 1.48972 + vertex 923.188 305.289 1.41308 + vertex 926.333 299.998 2.03559 + endloop + endfacet + facet normal 0.176438 -0.010898 -0.984251 + outer loop + vertex 926.333 299.998 2.03559 + vertex 923.188 305.289 1.41308 + vertex 926.643 304.922 2.0366 + endloop + endfacet + facet normal 0.279978 -0.0174171 -0.959848 + outer loop + vertex 926.333 299.998 2.03559 + vertex 926.643 304.922 2.0366 + vertex 929.3 299.806 2.90432 + endloop + endfacet + facet normal 0.280213 -0.0172842 -0.959782 + outer loop + vertex 929.3 299.806 2.90432 + vertex 926.643 304.922 2.0366 + vertex 929.612 304.805 2.90539 + endloop + endfacet + facet normal 0.280594 -0.00767022 -0.959796 + outer loop + vertex 926.643 304.922 2.0366 + vertex 926.781 309.949 2.03681 + vertex 929.612 304.805 2.90539 + endloop + endfacet + facet normal 0.281011 -0.00742064 -0.959676 + outer loop + vertex 929.612 304.805 2.90539 + vertex 926.781 309.949 2.03681 + vertex 929.747 309.91 2.90548 + endloop + endfacet + facet normal 0.109478 -0.00153642 -0.993988 + outer loop + vertex 923.928 309.763 1.48769 + vertex 923.188 305.289 1.41308 + vertex 919.201 313.454 0.961414 + endloop + endfacet + facet normal 0.108975 -0.00875988 -0.994006 + outer loop + vertex 923.459 299.965 1.48972 + vertex 918.938 303.753 0.960715 + vertex 923.188 305.289 1.41308 + endloop + endfacet + facet normal 0.10686 -0.00283018 -0.99427 + outer loop + vertex 918.938 303.753 0.960715 + vertex 919.201 313.454 0.961414 + vertex 923.188 305.289 1.41308 + endloop + endfacet + facet normal 0.981877 -0.0467287 0.18367 + outer loop + vertex 898.43 326.509 46.262 + vertex 898.82 334.915 46.3166 + vertex 898.048 327.702 48.609 + endloop + endfacet + facet normal 0.978077 -0.0397272 0.20442 + outer loop + vertex 898.048 327.702 48.609 + vertex 898.82 334.915 46.3166 + vertex 898.361 336.207 48.7653 + endloop + endfacet + facet normal 0.969939 -0.0501905 0.238118 + outer loop + vertex 899.192 325.325 42.9089 + vertex 899.62 333.8 42.9543 + vertex 898.43 326.509 46.262 + endloop + endfacet + facet normal 0.968244 -0.0464988 0.245646 + outer loop + vertex 898.43 326.509 46.262 + vertex 899.62 333.8 42.9543 + vertex 898.82 334.915 46.3166 + endloop + endfacet + facet normal 0.960488 -0.0513498 0.273545 + outer loop + vertex 900.309 323.882 38.7168 + vertex 900.754 332.449 38.7629 + vertex 899.192 325.325 42.9089 + endloop + endfacet + facet normal 0.959908 -0.0498868 0.275841 + outer loop + vertex 899.192 325.325 42.9089 + vertex 900.754 332.449 38.7629 + vertex 899.62 333.8 42.9543 + endloop + endfacet + facet normal 0.949343 -0.0530701 0.309727 + outer loop + vertex 901.732 322.024 34.0359 + vertex 902.195 330.663 34.0966 + vertex 900.309 323.882 38.7168 + endloop + endfacet + facet normal 0.948542 -0.0509391 0.312527 + outer loop + vertex 900.309 323.882 38.7168 + vertex 902.195 330.663 34.0966 + vertex 900.754 332.449 38.7629 + endloop + endfacet + facet normal 0.888866 -0.0188051 0.457781 + outer loop + vertex 905.168 326.27 26.8392 + vertex 905.237 330.672 26.8868 + vertex 904.225 326.934 28.6969 + endloop + endfacet + facet normal 0.888317 -0.018128 0.458873 + outer loop + vertex 904.225 326.934 28.6969 + vertex 905.237 330.672 26.8868 + vertex 904.293 331.322 28.7384 + endloop + endfacet + facet normal 0.884046 -0.0485753 0.46487 + outer loop + vertex 904.952 321.907 26.7947 + vertex 905.168 326.27 26.8392 + vertex 904.012 322.574 28.6518 + endloop + endfacet + facet normal 0.883674 -0.0480882 0.465626 + outer loop + vertex 904.012 322.574 28.6518 + vertex 905.168 326.27 26.8392 + vertex 904.225 326.934 28.6969 + endloop + endfacet + facet normal 0.703842 -0.01913 0.710099 + outer loop + vertex 907.395 325.386 24.1586 + vertex 907.462 329.788 24.2102 + vertex 906.212 325.822 25.3426 + endloop + endfacet + facet normal 0.703335 -0.0188248 0.710609 + outer loop + vertex 906.212 325.822 25.3426 + vertex 907.462 329.788 24.2102 + vertex 906.282 330.233 25.39 + endloop + endfacet + facet normal 0.697473 -0.0422355 0.715366 + outer loop + vertex 907.179 321.015 24.1112 + vertex 907.395 325.386 24.1586 + vertex 905.995 321.454 25.2909 + endloop + endfacet + facet normal 0.698859 -0.0431342 0.713958 + outer loop + vertex 905.995 321.454 25.2909 + vertex 907.395 325.386 24.1586 + vertex 906.212 325.822 25.3426 + endloop + endfacet + facet normal 0.407427 -0.0175022 0.91307 + outer loop + vertex 910.328 323.87 22.5201 + vertex 910.399 328.45 22.5761 + vertex 908.756 324.772 23.2389 + endloop + endfacet + facet normal 0.406441 -0.016981 0.913519 + outer loop + vertex 908.756 324.772 23.2389 + vertex 910.399 328.45 22.5761 + vertex 908.814 329.208 23.2956 + endloop + endfacet + facet normal 0.403387 -0.0326041 0.914448 + outer loop + vertex 910.1 319.441 22.4627 + vertex 910.328 323.87 22.5201 + vertex 908.536 320.383 23.1861 + endloop + endfacet + facet normal 0.400817 -0.0310573 0.915632 + outer loop + vertex 908.536 320.383 23.1861 + vertex 910.328 323.87 22.5201 + vertex 908.756 324.772 23.2389 + endloop + endfacet + facet normal 0.550709 -0.0375743 0.833851 + outer loop + vertex 908.536 320.383 23.1861 + vertex 908.756 324.772 23.2389 + vertex 907.179 321.015 24.1112 + endloop + endfacet + facet normal 0.548272 -0.0361641 0.835518 + outer loop + vertex 907.179 321.015 24.1112 + vertex 908.756 324.772 23.2389 + vertex 907.395 325.386 24.1586 + endloop + endfacet + facet normal 0.554253 -0.0178712 0.832156 + outer loop + vertex 908.756 324.772 23.2389 + vertex 908.814 329.208 23.2956 + vertex 907.395 325.386 24.1586 + endloop + endfacet + facet normal 0.555015 -0.0182708 0.83164 + outer loop + vertex 907.395 325.386 24.1586 + vertex 908.814 329.208 23.2956 + vertex 907.462 329.788 24.2102 + endloop + endfacet + facet normal 0.207128 -0.0149978 0.978199 + outer loop + vertex 914.145 321.469 21.5089 + vertex 913.923 325.94 21.6245 + vertex 912.091 322.693 21.9626 + endloop + endfacet + facet normal 0.209306 -0.016277 0.977715 + outer loop + vertex 912.091 322.693 21.9626 + vertex 913.923 325.94 21.6245 + vertex 912.205 327.369 22.0161 + endloop + endfacet + facet normal 0.20739 -0.0286888 0.977838 + outer loop + vertex 913.57 316.757 21.4927 + vertex 914.145 321.469 21.5089 + vertex 911.862 318.218 21.8978 + endloop + endfacet + facet normal 0.201669 -0.0245142 0.979147 + outer loop + vertex 911.862 318.218 21.8978 + vertex 914.145 321.469 21.5089 + vertex 912.091 322.693 21.9626 + endloop + endfacet + facet normal 0.287169 -0.0285828 0.957453 + outer loop + vertex 911.862 318.218 21.8978 + vertex 912.091 322.693 21.9626 + vertex 910.1 319.441 22.4627 + endloop + endfacet + facet normal 0.284884 -0.0270717 0.95818 + outer loop + vertex 910.1 319.441 22.4627 + vertex 912.091 322.693 21.9626 + vertex 910.328 323.87 22.5201 + endloop + endfacet + facet normal 0.290469 -0.0180101 0.956715 + outer loop + vertex 912.091 322.693 21.9626 + vertex 912.205 327.369 22.0161 + vertex 910.328 323.87 22.5201 + endloop + endfacet + facet normal 0.287327 -0.016184 0.957696 + outer loop + vertex 910.328 323.87 22.5201 + vertex 912.205 327.369 22.0161 + vertex 910.399 328.45 22.5761 + endloop + endfacet + facet normal 0.575869 0.00849937 0.817498 + outer loop + vertex 933.821 314.487 16.132 + vertex 933.716 319.718 16.1518 + vertex 932.163 315.74 17.2872 + endloop + endfacet + facet normal 0.580693 0.00564698 0.814103 + outer loop + vertex 932.163 315.74 17.2872 + vertex 933.716 319.718 16.1518 + vertex 932.083 321.009 17.308 + endloop + endfacet + facet normal 0.568984 -0.0109773 0.822276 + outer loop + vertex 933.756 309.323 16.1086 + vertex 933.821 314.487 16.132 + vertex 932.126 310.444 17.2513 + endloop + endfacet + facet normal 0.566672 -0.00956199 0.823888 + outer loop + vertex 932.126 310.444 17.2513 + vertex 933.821 314.487 16.132 + vertex 932.163 315.74 17.2872 + endloop + endfacet + facet normal 0.449244 -0.00921084 0.893361 + outer loop + vertex 932.126 310.444 17.2513 + vertex 932.163 315.74 17.2872 + vertex 930.467 311.523 18.0966 + endloop + endfacet + facet normal 0.442781 -0.00598839 0.89661 + outer loop + vertex 930.467 311.523 18.0966 + vertex 932.163 315.74 17.2872 + vertex 930.413 317.215 18.1613 + endloop + endfacet + facet normal 0.449074 0.00332774 0.893489 + outer loop + vertex 932.163 315.74 17.2872 + vertex 932.083 321.009 17.308 + vertex 930.413 317.215 18.1613 + endloop + endfacet + facet normal 0.452121 0.0016418 0.891955 + outer loop + vertex 930.413 317.215 18.1613 + vertex 932.083 321.009 17.308 + vertex 930.536 322.281 18.0896 + endloop + endfacet + facet normal 0.773173 0.0173661 0.633957 + outer loop + vertex 936.484 314.24 13.3393 + vertex 936.287 316.675 13.513 + vertex 935.431 313.255 14.6502 + endloop + endfacet + facet normal 0.790842 0.0417444 0.610595 + outer loop + vertex 936.283 319.378 13.3328 + vertex 935.312 318.424 14.6565 + vertex 936.287 316.675 13.513 + endloop + endfacet + facet normal 0.773549 0.017122 0.633506 + outer loop + vertex 935.312 318.424 14.6565 + vertex 935.431 313.255 14.6502 + vertex 936.287 316.675 13.513 + endloop + endfacet + facet normal 0.764011 -0.0138004 0.645056 + outer loop + vertex 936.49 309.111 13.329 + vertex 936.381 311.559 13.5103 + vertex 935.365 308.108 14.6401 + endloop + endfacet + facet normal 0.77578 0.0105273 0.630916 + outer loop + vertex 936.484 314.24 13.3393 + vertex 935.431 313.255 14.6502 + vertex 936.381 311.559 13.5103 + endloop + endfacet + facet normal 0.759985 -0.011047 0.649846 + outer loop + vertex 935.431 313.255 14.6502 + vertex 935.365 308.108 14.6401 + vertex 936.381 311.559 13.5103 + endloop + endfacet + facet normal 0.669791 -0.0100676 0.742482 + outer loop + vertex 935.365 308.108 14.6401 + vertex 935.431 313.255 14.6502 + vertex 933.756 309.323 16.1086 + endloop + endfacet + facet normal 0.67221 -0.0119204 0.740265 + outer loop + vertex 933.756 309.323 16.1086 + vertex 935.431 313.255 14.6502 + vertex 933.821 314.487 16.132 + endloop + endfacet + facet normal 0.683292 0.0149164 0.729993 + outer loop + vertex 935.431 313.255 14.6502 + vertex 935.312 318.424 14.6565 + vertex 933.821 314.487 16.132 + endloop + endfacet + facet normal 0.688516 0.0111183 0.725136 + outer loop + vertex 933.821 314.487 16.132 + vertex 935.312 318.424 14.6565 + vertex 933.716 319.718 16.1518 + endloop + endfacet + facet normal 0.989215 0.0495157 -0.137848 + outer loop + vertex 937.077 315.78 8.99465 + vertex 936.948 318.375 8.99769 + vertex 937.232 315.748 10.0919 + endloop + endfacet + facet normal 0.988863 0.0482518 -0.140792 + outer loop + vertex 937.232 315.748 10.0919 + vertex 936.948 318.375 8.99769 + vertex 937.106 318.338 10.0939 + endloop + endfacet + facet normal 0.990132 0.0307856 -0.136715 + outer loop + vertex 937.157 313.214 8.99287 + vertex 937.077 315.78 8.99465 + vertex 937.309 313.183 10.0889 + endloop + endfacet + facet normal 0.989907 0.0300103 -0.138507 + outer loop + vertex 937.309 313.183 10.0889 + vertex 937.077 315.78 8.99465 + vertex 937.232 315.748 10.0919 + endloop + endfacet + facet normal 0.998059 0.0300298 0.0545549 + outer loop + vertex 937.309 313.183 10.0889 + vertex 937.232 315.748 10.0919 + vertex 937.243 313.32 11.2262 + endloop + endfacet + facet normal 0.998053 0.0300718 0.0546447 + outer loop + vertex 937.243 313.32 11.2262 + vertex 937.232 315.748 10.0919 + vertex 937.166 315.879 11.2291 + endloop + endfacet + facet normal 0.997443 0.0485192 0.0524796 + outer loop + vertex 937.232 315.748 10.0919 + vertex 937.106 318.338 10.0939 + vertex 937.166 315.879 11.2291 + endloop + endfacet + facet normal 0.997593 0.0475827 0.0504434 + outer loop + vertex 937.166 315.879 11.2291 + vertex 937.106 318.338 10.0939 + vertex 937.043 318.457 11.2273 + endloop + endfacet + facet normal 0.990509 0.0120831 -0.136912 + outer loop + vertex 937.188 310.648 8.99211 + vertex 937.157 313.214 8.99287 + vertex 937.34 310.617 10.0866 + endloop + endfacet + facet normal 0.99046 0.0119219 -0.137287 + outer loop + vertex 937.34 310.617 10.0866 + vertex 937.157 313.214 8.99287 + vertex 937.309 313.183 10.0889 + endloop + endfacet + facet normal 0.991207 -0.00424156 -0.132256 + outer loop + vertex 937.177 308.053 8.99073 + vertex 937.188 310.648 8.99211 + vertex 937.323 308.019 10.0846 + endloop + endfacet + facet normal 0.990488 -0.00643589 -0.137449 + outer loop + vertex 937.323 308.019 10.0846 + vertex 937.188 310.648 8.99211 + vertex 937.34 310.617 10.0866 + endloop + endfacet + facet normal 0.998107 -0.00663565 0.061139 + outer loop + vertex 937.323 308.019 10.0846 + vertex 937.34 310.617 10.0866 + vertex 937.254 308.16 11.2189 + endloop + endfacet + facet normal 0.998188 -0.00728513 0.0597358 + outer loop + vertex 937.254 308.16 11.2189 + vertex 937.34 310.617 10.0866 + vertex 937.273 310.756 11.2224 + endloop + endfacet + facet normal 0.998281 0.0118421 0.0573948 + outer loop + vertex 937.34 310.617 10.0866 + vertex 937.309 313.183 10.0889 + vertex 937.273 310.756 11.2224 + endloop + endfacet + facet normal 0.998319 0.0115599 0.0567919 + outer loop + vertex 937.273 310.756 11.2224 + vertex 937.309 313.183 10.0889 + vertex 937.243 313.32 11.2262 + endloop + endfacet + facet normal 0.96937 0.0109436 0.245361 + outer loop + vertex 937.273 310.756 11.2224 + vertex 937.243 313.32 11.2262 + vertex 936.981 311.106 12.3616 + endloop + endfacet + facet normal 0.968849 0.01203 0.247359 + outer loop + vertex 936.981 311.106 12.3616 + vertex 937.243 313.32 11.2262 + vertex 936.948 313.665 12.3648 + endloop + endfacet + facet normal 0.967445 -0.00732518 0.252977 + outer loop + vertex 937.254 308.16 11.2189 + vertex 937.273 310.756 11.2224 + vertex 936.959 308.519 12.3569 + endloop + endfacet + facet normal 0.967963 -0.00842497 0.250952 + outer loop + vertex 936.959 308.519 12.3569 + vertex 937.273 310.756 11.2224 + vertex 936.981 311.106 12.3616 + endloop + endfacet + facet normal 0.898686 -0.0081941 0.438516 + outer loop + vertex 936.959 308.519 12.3569 + vertex 936.981 311.106 12.3616 + vertex 936.49 309.111 13.329 + endloop + endfacet + facet normal 0.887513 0.00533541 0.460753 + outer loop + vertex 936.49 309.111 13.329 + vertex 936.981 311.106 12.3616 + vertex 936.381 311.559 13.5103 + endloop + endfacet + facet normal 0.888344 0.010739 0.459053 + outer loop + vertex 936.981 311.106 12.3616 + vertex 936.948 313.665 12.3648 + vertex 936.381 311.559 13.5103 + endloop + endfacet + facet normal 0.901342 -0.00690307 0.433054 + outer loop + vertex 936.381 311.559 13.5103 + vertex 936.948 313.665 12.3648 + vertex 936.484 314.24 13.3393 + endloop + endfacet + facet normal 0.970452 0.0464203 0.236787 + outer loop + vertex 937.166 315.879 11.2291 + vertex 937.043 318.457 11.2273 + vertex 936.872 316.218 12.3654 + endloop + endfacet + facet normal 0.970994 0.0453514 0.234765 + outer loop + vertex 936.872 316.218 12.3654 + vertex 937.043 318.457 11.2273 + vertex 936.753 318.787 12.3612 + endloop + endfacet + facet normal 0.969731 0.0290001 0.242449 + outer loop + vertex 937.243 313.32 11.2262 + vertex 937.166 315.879 11.2291 + vertex 936.948 313.665 12.3648 + endloop + endfacet + facet normal 0.969872 0.0287131 0.241917 + outer loop + vertex 936.948 313.665 12.3648 + vertex 937.166 315.879 11.2291 + vertex 936.872 316.218 12.3654 + endloop + endfacet + facet normal 0.908676 0.0268548 0.416637 + outer loop + vertex 936.948 313.665 12.3648 + vertex 936.872 316.218 12.3654 + vertex 936.484 314.24 13.3393 + endloop + endfacet + facet normal 0.896637 0.0411345 0.440851 + outer loop + vertex 936.484 314.24 13.3393 + vertex 936.872 316.218 12.3654 + vertex 936.287 316.675 13.513 + endloop + endfacet + facet normal 0.896771 0.0422573 0.440472 + outer loop + vertex 936.872 316.218 12.3654 + vertex 936.753 318.787 12.3612 + vertex 936.287 316.675 13.513 + endloop + endfacet + facet normal 0.906761 0.0292311 0.42063 + outer loop + vertex 936.287 316.675 13.513 + vertex 936.753 318.787 12.3612 + vertex 936.283 319.378 13.3328 + endloop + endfacet + facet normal 0.622786 0.0162948 -0.782223 + outer loop + vertex 934.075 316.019 4.97898 + vertex 934.192 318.354 5.12062 + vertex 935.269 315.935 5.92793 + endloop + endfacet + facet normal 0.64539 0.0327262 -0.763152 + outer loop + vertex 935.269 315.935 5.92793 + vertex 934.192 318.354 5.12062 + vertex 935.14 318.509 5.92908 + endloop + endfacet + facet normal 0.64299 0.0348344 -0.765082 + outer loop + vertex 934.391 313.242 5.11839 + vertex 934.075 316.019 4.97898 + vertex 935.348 313.385 5.92903 + endloop + endfacet + facet normal 0.622872 0.0189732 -0.782093 + outer loop + vertex 935.348 313.385 5.92903 + vertex 934.075 316.019 4.97898 + vertex 935.269 315.935 5.92793 + endloop + endfacet + facet normal 0.761393 0.0233252 -0.647871 + outer loop + vertex 935.348 313.385 5.92903 + vertex 935.269 315.935 5.92793 + vertex 936.183 313.377 6.90992 + endloop + endfacet + facet normal 0.761215 0.0231796 -0.648085 + outer loop + vertex 936.183 313.377 6.90992 + vertex 935.269 315.935 5.92793 + vertex 936.104 315.934 6.90925 + endloop + endfacet + facet normal 0.760863 0.0384685 -0.647771 + outer loop + vertex 935.269 315.935 5.92793 + vertex 935.14 318.509 5.92908 + vertex 936.104 315.934 6.90925 + endloop + endfacet + facet normal 0.759819 0.037592 -0.649046 + outer loop + vertex 936.104 315.934 6.90925 + vertex 935.14 318.509 5.92908 + vertex 935.977 318.52 6.90956 + endloop + endfacet + facet normal 0.620106 -0.00777094 -0.78448 + outer loop + vertex 934.186 310.9 4.97958 + vertex 934.391 313.242 5.11839 + vertex 935.386 310.829 5.92866 + endloop + endfacet + facet normal 0.645549 0.00971197 -0.763657 + outer loop + vertex 935.386 310.829 5.92866 + vertex 934.391 313.242 5.11839 + vertex 935.348 313.385 5.92903 + endloop + endfacet + facet normal 0.639657 0.0113052 -0.768577 + outer loop + vertex 934.403 308.079 5.11867 + vertex 934.186 310.9 4.97958 + vertex 935.373 308.239 5.92853 + endloop + endfacet + facet normal 0.620297 -0.002958 -0.784361 + outer loop + vertex 935.373 308.239 5.92853 + vertex 934.186 310.9 4.97958 + vertex 935.386 310.829 5.92866 + endloop + endfacet + facet normal 0.759607 -0.00363739 -0.650372 + outer loop + vertex 935.373 308.239 5.92853 + vertex 935.386 310.829 5.92866 + vertex 936.213 308.233 6.90918 + endloop + endfacet + facet normal 0.760432 -0.00301123 -0.649411 + outer loop + vertex 936.213 308.233 6.90918 + vertex 935.386 310.829 5.92866 + vertex 936.223 310.821 6.90947 + endloop + endfacet + facet normal 0.760444 0.0114047 -0.649304 + outer loop + vertex 935.386 310.829 5.92866 + vertex 935.348 313.385 5.92903 + vertex 936.223 310.821 6.90947 + endloop + endfacet + facet normal 0.761497 0.0122424 -0.648053 + outer loop + vertex 936.223 310.821 6.90947 + vertex 935.348 313.385 5.92903 + vertex 936.183 313.377 6.90992 + endloop + endfacet + facet normal 0.864186 0.0138527 -0.502982 + outer loop + vertex 936.223 310.821 6.90947 + vertex 936.183 313.377 6.90992 + vertex 936.822 310.747 7.93586 + endloop + endfacet + facet normal 0.863023 0.0127813 -0.505004 + outer loop + vertex 936.822 310.747 7.93586 + vertex 936.183 313.377 6.90992 + vertex 936.784 313.309 7.93645 + endloop + endfacet + facet normal 0.864559 -0.00345037 -0.502519 + outer loop + vertex 936.213 308.233 6.90918 + vertex 936.223 310.821 6.90947 + vertex 936.809 308.157 7.93553 + endloop + endfacet + facet normal 0.863696 -0.00420877 -0.503996 + outer loop + vertex 936.809 308.157 7.93553 + vertex 936.223 310.821 6.90947 + vertex 936.822 310.747 7.93586 + endloop + endfacet + facet normal 0.944181 -0.00462928 -0.329393 + outer loop + vertex 936.809 308.157 7.93553 + vertex 936.822 310.747 7.93586 + vertex 937.177 308.053 8.99073 + endloop + endfacet + facet normal 0.944736 -0.00393522 -0.327807 + outer loop + vertex 937.177 308.053 8.99073 + vertex 936.822 310.747 7.93586 + vertex 937.188 310.648 8.99211 + endloop + endfacet + facet normal 0.945169 0.0139461 -0.326285 + outer loop + vertex 936.822 310.747 7.93586 + vertex 936.784 313.309 7.93645 + vertex 937.188 310.648 8.99211 + endloop + endfacet + facet normal 0.943354 0.0115679 -0.331585 + outer loop + vertex 937.188 310.648 8.99211 + vertex 936.784 313.309 7.93645 + vertex 937.157 313.214 8.99287 + endloop + endfacet + facet normal 0.865066 0.042771 -0.499832 + outer loop + vertex 936.104 315.934 6.90925 + vertex 935.977 318.52 6.90956 + vertex 936.701 315.872 7.93723 + endloop + endfacet + facet normal 0.864646 0.042361 -0.500592 + outer loop + vertex 936.701 315.872 7.93723 + vertex 935.977 318.52 6.90956 + vertex 936.575 318.465 7.93857 + endloop + endfacet + facet normal 0.863184 0.0263448 -0.504201 + outer loop + vertex 936.183 313.377 6.90992 + vertex 936.104 315.934 6.90925 + vertex 936.784 313.309 7.93645 + endloop + endfacet + facet normal 0.865131 0.0281982 -0.500753 + outer loop + vertex 936.784 313.309 7.93645 + vertex 936.104 315.934 6.90925 + vertex 936.701 315.872 7.93723 + endloop + endfacet + facet normal 0.943511 0.0306864 -0.329917 + outer loop + vertex 936.784 313.309 7.93645 + vertex 936.701 315.872 7.93723 + vertex 937.157 313.214 8.99287 + endloop + endfacet + facet normal 0.942594 0.0294477 -0.33264 + outer loop + vertex 937.157 313.214 8.99287 + vertex 936.701 315.872 7.93723 + vertex 937.077 315.78 8.99465 + endloop + endfacet + facet normal 0.942455 0.0460629 -0.331143 + outer loop + vertex 936.701 315.872 7.93723 + vertex 936.575 318.465 7.93857 + vertex 937.077 315.78 8.99465 + endloop + endfacet + facet normal 0.943458 0.0474555 -0.328079 + outer loop + vertex 937.077 315.78 8.99465 + vertex 936.575 318.465 7.93857 + vertex 936.948 318.375 8.99769 + endloop + endfacet + facet normal 0.384407 0.0146419 -0.923048 + outer loop + vertex 929.702 315.042 2.90638 + vertex 929.495 320.154 2.90112 + vertex 932.475 315.059 4.06151 + endloop + endfacet + facet normal 0.389389 0.0180466 -0.920897 + outer loop + vertex 932.475 315.059 4.06151 + vertex 929.495 320.154 2.90112 + vertex 932.238 320.183 4.06156 + endloop + endfacet + facet normal 0.383255 0.00348438 -0.923636 + outer loop + vertex 929.747 309.91 2.90548 + vertex 929.702 315.042 2.90638 + vertex 932.536 309.91 4.06293 + endloop + endfacet + facet normal 0.3845 0.00428923 -0.923115 + outer loop + vertex 932.536 309.91 4.06293 + vertex 929.702 315.042 2.90638 + vertex 932.475 315.059 4.06151 + endloop + endfacet + facet normal 0.489461 0.00885133 -0.87198 + outer loop + vertex 934.391 313.242 5.11839 + vertex 934.186 310.9 4.97958 + vertex 932.475 315.059 4.06151 + endloop + endfacet + facet normal 0.488163 -0.00548257 -0.872735 + outer loop + vertex 934.403 308.079 5.11867 + vertex 932.536 309.91 4.06293 + vertex 934.186 310.9 4.97958 + endloop + endfacet + facet normal 0.483138 0.00546784 -0.875527 + outer loop + vertex 932.536 309.91 4.06293 + vertex 932.475 315.059 4.06151 + vertex 934.186 310.9 4.97958 + endloop + endfacet + facet normal 0.496405 0.027801 -0.867646 + outer loop + vertex 934.192 318.354 5.12062 + vertex 934.075 316.019 4.97898 + vertex 932.238 320.183 4.06156 + endloop + endfacet + facet normal 0.491967 0.0123381 -0.870527 + outer loop + vertex 934.391 313.242 5.11839 + vertex 932.475 315.059 4.06151 + vertex 934.075 316.019 4.97898 + endloop + endfacet + facet normal 0.48723 0.0225789 -0.872981 + outer loop + vertex 932.475 315.059 4.06151 + vertex 932.238 320.183 4.06156 + vertex 934.075 316.019 4.97898 + endloop + endfacet + facet normal 0.177552 -0.000739192 -0.984111 + outer loop + vertex 923.307 315.233 1.41432 + vertex 923.752 319.826 1.49113 + vertex 926.754 315.036 2.03634 + endloop + endfacet + facet normal 0.190713 0.00779295 -0.981615 + outer loop + vertex 926.754 315.036 2.03634 + vertex 923.752 319.826 1.49113 + vertex 926.559 320.12 2.03875 + endloop + endfacet + facet normal 0.188446 0.00820913 -0.982049 + outer loop + vertex 923.928 309.763 1.48769 + vertex 923.307 315.233 1.41432 + vertex 926.781 309.949 2.03681 + endloop + endfacet + facet normal 0.177641 0.000864574 -0.984095 + outer loop + vertex 926.781 309.949 2.03681 + vertex 923.307 315.233 1.41432 + vertex 926.754 315.036 2.03634 + endloop + endfacet + facet normal 0.281126 0.00142299 -0.95967 + outer loop + vertex 926.781 309.949 2.03681 + vertex 926.754 315.036 2.03634 + vertex 929.747 309.91 2.90548 + endloop + endfacet + facet normal 0.283017 0.00262161 -0.959111 + outer loop + vertex 929.747 309.91 2.90548 + vertex 926.754 315.036 2.03634 + vertex 929.702 315.042 2.90638 + endloop + endfacet + facet normal 0.282984 0.0113275 -0.959058 + outer loop + vertex 926.754 315.036 2.03634 + vertex 926.559 320.12 2.03875 + vertex 929.702 315.042 2.90638 + endloop + endfacet + facet normal 0.281656 0.0104366 -0.959459 + outer loop + vertex 929.702 315.042 2.90638 + vertex 926.559 320.12 2.03875 + vertex 929.495 320.154 2.90112 + endloop + endfacet + facet normal 0.112475 0.00572358 -0.993638 + outer loop + vertex 923.752 319.826 1.49113 + vertex 923.307 315.233 1.41432 + vertex 918.889 323.325 0.960884 + endloop + endfacet + facet normal 0.110008 -0.000849808 -0.99393 + outer loop + vertex 923.928 309.763 1.48769 + vertex 919.201 313.454 0.961414 + vertex 923.307 315.233 1.41432 + endloop + endfacet + facet normal 0.108203 0.00336407 -0.994123 + outer loop + vertex 919.201 313.454 0.961414 + vertex 918.889 323.325 0.960884 + vertex 923.307 315.233 1.41432 + endloop + endfacet + facet normal 0.896233 0.0350977 0.442193 + outer loop + vertex 905.168 335.072 26.9345 + vertex 904.98 339.439 26.9704 + vertex 904.234 335.705 28.7772 + endloop + endfacet + facet normal 0.897901 0.0331925 0.438944 + outer loop + vertex 904.234 335.705 28.7772 + vertex 904.98 339.439 26.9704 + vertex 904.057 340.068 28.8108 + endloop + endfacet + facet normal 0.892286 0.00896426 0.451382 + outer loop + vertex 905.237 330.672 26.8868 + vertex 905.168 335.072 26.9345 + vertex 904.293 331.322 28.7384 + endloop + endfacet + facet normal 0.893055 0.00806051 0.449876 + outer loop + vertex 904.293 331.322 28.7384 + vertex 905.168 335.072 26.9345 + vertex 904.234 335.705 28.7772 + endloop + endfacet + facet normal 0.708458 0.0217793 0.705417 + outer loop + vertex 907.4 334.185 24.2593 + vertex 907.227 338.58 24.2975 + vertex 906.214 334.648 25.436 + endloop + endfacet + facet normal 0.70413 0.0241227 0.709661 + outer loop + vertex 906.214 334.648 25.436 + vertex 907.227 338.58 24.2975 + vertex 906.018 339.043 25.4805 + endloop + endfacet + facet normal 0.707432 0.00218878 0.706778 + outer loop + vertex 907.462 329.788 24.2102 + vertex 907.4 334.185 24.2593 + vertex 906.282 330.233 25.39 + endloop + endfacet + facet normal 0.705045 0.00354384 0.709154 + outer loop + vertex 906.282 330.233 25.39 + vertex 907.4 334.185 24.2593 + vertex 906.214 334.648 25.436 + endloop + endfacet + facet normal 0.423526 0.0136323 0.905781 + outer loop + vertex 910.21 333.03 22.6653 + vertex 909.783 336.672 22.8098 + vertex 908.705 333.525 23.3615 + endloop + endfacet + facet normal 0.442466 0.00556164 0.896768 + outer loop + vertex 908.705 333.525 23.3615 + vertex 909.783 336.672 22.8098 + vertex 908.57 337.794 23.4015 + endloop + endfacet + facet normal 0.412989 -0.000652684 0.910736 + outer loop + vertex 910.399 328.45 22.5761 + vertex 910.21 333.03 22.6653 + vertex 908.814 329.208 23.2956 + endloop + endfacet + facet normal 0.418981 -0.0032944 0.907989 + outer loop + vertex 908.814 329.208 23.2956 + vertex 910.21 333.03 22.6653 + vertex 908.705 333.525 23.3615 + endloop + endfacet + facet normal 0.56094 0.00150991 0.827855 + outer loop + vertex 908.814 329.208 23.2956 + vertex 908.705 333.525 23.3615 + vertex 907.462 329.788 24.2102 + endloop + endfacet + facet normal 0.566356 -0.00113059 0.82416 + outer loop + vertex 907.462 329.788 24.2102 + vertex 908.705 333.525 23.3615 + vertex 907.4 334.185 24.2593 + endloop + endfacet + facet normal 0.570244 0.0103043 0.821411 + outer loop + vertex 908.705 333.525 23.3615 + vertex 908.57 337.794 23.4015 + vertex 907.4 334.185 24.2593 + endloop + endfacet + facet normal 0.560784 0.0148972 0.827828 + outer loop + vertex 907.4 334.185 24.2593 + vertex 908.57 337.794 23.4015 + vertex 907.227 338.58 24.2975 + endloop + endfacet + facet normal 0.208773 -0.00246917 0.977961 + outer loop + vertex 914.313 331.216 21.6129 + vertex 913.822 338.136 21.7352 + vertex 912.094 332.557 22.0898 + endloop + endfacet + facet normal 0.219798 -0.00603702 0.975527 + outer loop + vertex 912.094 332.557 22.0898 + vertex 913.822 338.136 21.7352 + vertex 911.368 337.825 22.286 + endloop + endfacet + facet normal 0.211537 -0.013476 0.977277 + outer loop + vertex 913.923 325.94 21.6245 + vertex 914.313 331.216 21.6129 + vertex 912.205 327.369 22.0161 + endloop + endfacet + facet normal 0.204666 -0.00955346 0.978785 + outer loop + vertex 912.205 327.369 22.0161 + vertex 914.313 331.216 21.6129 + vertex 912.094 332.557 22.0898 + endloop + endfacet + facet normal 0.292179 -0.00736981 0.956335 + outer loop + vertex 912.205 327.369 22.0161 + vertex 912.094 332.557 22.0898 + vertex 910.399 328.45 22.5761 + endloop + endfacet + facet normal 0.290496 -0.00661363 0.956853 + outer loop + vertex 910.399 328.45 22.5761 + vertex 912.094 332.557 22.0898 + vertex 910.21 333.03 22.6653 + endloop + endfacet + facet normal 0.293116 0.00479274 0.956065 + outer loop + vertex 912.094 332.557 22.0898 + vertex 911.368 337.825 22.286 + vertex 910.21 333.03 22.6653 + endloop + endfacet + facet normal 0.314363 -0.000876175 0.949302 + outer loop + vertex 910.21 333.03 22.6653 + vertex 911.368 337.825 22.286 + vertex 909.783 336.672 22.8098 + endloop + endfacet + facet normal 0.604107 0.04678 0.795529 + outer loop + vertex 933.427 324.949 16.1759 + vertex 932.954 330.128 16.2306 + vertex 931.788 326.108 17.3522 + endloop + endfacet + facet normal 0.604269 0.0467 0.795411 + outer loop + vertex 931.788 326.108 17.3522 + vertex 932.954 330.128 16.2306 + vertex 931.332 331.192 17.4 + endloop + endfacet + facet normal 0.592693 0.0290652 0.804904 + outer loop + vertex 933.716 319.718 16.1518 + vertex 933.427 324.949 16.1759 + vertex 932.083 321.009 17.308 + endloop + endfacet + facet normal 0.595645 0.0274478 0.802779 + outer loop + vertex 932.083 321.009 17.308 + vertex 933.427 324.949 16.1759 + vertex 931.788 326.108 17.3522 + endloop + endfacet + facet normal 0.463425 0.0190907 0.885931 + outer loop + vertex 932.083 321.009 17.308 + vertex 931.788 326.108 17.3522 + vertex 930.536 322.281 18.0896 + endloop + endfacet + facet normal 0.440368 0.0288356 0.897354 + outer loop + vertex 930.536 322.281 18.0896 + vertex 931.788 326.108 17.3522 + vertex 929.898 327.043 18.2496 + endloop + endfacet + facet normal 0.441258 0.0311277 0.89684 + outer loop + vertex 931.788 326.108 17.3522 + vertex 931.332 331.192 17.4 + vertex 929.898 327.043 18.2496 + endloop + endfacet + facet normal 0.454758 0.0251136 0.890261 + outer loop + vertex 929.898 327.043 18.2496 + vertex 931.332 331.192 17.4 + vertex 929.742 332.38 18.179 + endloop + endfacet + facet normal 0.802272 0.063248 0.593598 + outer loop + vertex 935.896 324.699 13.3739 + vertex 935.524 327.246 13.6058 + vertex 935.007 323.693 14.683 + endloop + endfacet + facet normal 0.794449 0.0973229 0.599482 + outer loop + vertex 935.299 329.726 13.5004 + vertex 934.522 329.007 14.6475 + vertex 935.524 327.246 13.6058 + endloop + endfacet + facet normal 0.779259 0.0752592 0.622167 + outer loop + vertex 934.522 329.007 14.6475 + vertex 935.007 323.693 14.683 + vertex 935.524 327.246 13.6058 + endloop + endfacet + facet normal 0.79065 0.0422384 0.61081 + outer loop + vertex 936.283 319.378 13.3328 + vertex 936.006 321.891 13.5181 + vertex 935.312 318.424 14.6565 + endloop + endfacet + facet normal 0.802842 0.0619219 0.592967 + outer loop + vertex 935.896 324.699 13.3739 + vertex 935.007 323.693 14.683 + vertex 936.006 321.891 13.5181 + endloop + endfacet + facet normal 0.789948 0.0426674 0.611688 + outer loop + vertex 935.007 323.693 14.683 + vertex 935.312 318.424 14.6565 + vertex 936.006 321.891 13.5181 + endloop + endfacet + facet normal 0.699071 0.0368902 0.7141 + outer loop + vertex 935.312 318.424 14.6565 + vertex 935.007 323.693 14.683 + vertex 933.716 319.718 16.1518 + endloop + endfacet + facet normal 0.701151 0.0354864 0.712129 + outer loop + vertex 933.716 319.718 16.1518 + vertex 935.007 323.693 14.683 + vertex 933.427 324.949 16.1759 + endloop + endfacet + facet normal 0.713905 0.0697934 0.696755 + outer loop + vertex 935.007 323.693 14.683 + vertex 934.522 329.007 14.6475 + vertex 933.427 324.949 16.1759 + endloop + endfacet + facet normal 0.729959 0.0594873 0.680898 + outer loop + vertex 933.427 324.949 16.1759 + vertex 934.522 329.007 14.6475 + vertex 932.954 330.128 16.2306 + endloop + endfacet + facet normal 0.983313 0.105451 -0.148245 + outer loop + vertex 936.317 326.268 8.98708 + vertex 936.039 328.852 8.98433 + vertex 936.487 326.222 10.0812 + endloop + endfacet + facet normal 0.984257 0.109617 -0.138643 + outer loop + vertex 936.487 326.222 10.0812 + vertex 936.039 328.852 8.98433 + vertex 936.196 328.862 10.1032 + endloop + endfacet + facet normal 0.985226 0.0935794 -0.143433 + outer loop + vertex 936.567 323.646 8.99411 + vertex 936.317 326.268 8.98708 + vertex 936.731 323.587 10.0824 + endloop + endfacet + facet normal 0.984618 0.0911961 -0.149036 + outer loop + vertex 936.731 323.587 10.0824 + vertex 936.317 326.268 8.98708 + vertex 936.487 326.222 10.0812 + endloop + endfacet + facet normal 0.994846 0.0922293 0.0421218 + outer loop + vertex 936.731 323.587 10.0824 + vertex 936.487 326.222 10.0812 + vertex 936.672 323.705 11.2188 + endloop + endfacet + facet normal 0.994486 0.0940924 0.0463028 + outer loop + vertex 936.672 323.705 11.2188 + vertex 936.487 326.222 10.0812 + vertex 936.417 326.392 11.2437 + endloop + endfacet + facet normal 0.993059 0.109066 0.0440378 + outer loop + vertex 936.487 326.222 10.0812 + vertex 936.196 328.862 10.1032 + vertex 936.417 326.392 11.2437 + endloop + endfacet + facet normal 0.991812 0.114623 0.0563149 + outer loop + vertex 936.417 326.392 11.2437 + vertex 936.196 328.862 10.1032 + vertex 936.097 329.126 11.3104 + endloop + endfacet + facet normal 0.98722 0.0782758 -0.138813 + outer loop + vertex 936.777 321.005 8.99845 + vertex 936.567 323.646 8.99411 + vertex 936.934 320.957 10.0907 + endloop + endfacet + facet normal 0.986581 0.0758313 -0.144592 + outer loop + vertex 936.934 320.957 10.0907 + vertex 936.567 323.646 8.99411 + vertex 936.731 323.587 10.0824 + endloop + endfacet + facet normal 0.988046 0.0642673 -0.140128 + outer loop + vertex 936.948 318.375 8.99769 + vertex 936.777 321.005 8.99845 + vertex 937.106 318.338 10.0939 + endloop + endfacet + facet normal 0.988112 0.0645172 -0.13954 + outer loop + vertex 937.106 318.338 10.0939 + vertex 936.777 321.005 8.99845 + vertex 936.934 320.957 10.0907 + endloop + endfacet + facet normal 0.996684 0.0653047 0.0485325 + outer loop + vertex 937.106 318.338 10.0939 + vertex 936.934 320.957 10.0907 + vertex 937.043 318.457 11.2273 + endloop + endfacet + facet normal 0.996972 0.0635985 0.044752 + outer loop + vertex 937.043 318.457 11.2273 + vertex 936.934 320.957 10.0907 + vertex 936.877 321.065 11.2202 + endloop + endfacet + facet normal 0.996073 0.0771603 0.0434157 + outer loop + vertex 936.934 320.957 10.0907 + vertex 936.731 323.587 10.0824 + vertex 936.877 321.065 11.2202 + endloop + endfacet + facet normal 0.996048 0.0773043 0.0437383 + outer loop + vertex 936.877 321.065 11.2202 + vertex 936.731 323.587 10.0824 + vertex 936.672 323.705 11.2188 + endloop + endfacet + facet normal 0.972028 0.0755381 0.222385 + outer loop + vertex 936.877 321.065 11.2202 + vertex 936.672 323.705 11.2188 + vertex 936.59 321.4 12.3589 + endloop + endfacet + facet normal 0.971794 0.0759781 0.223258 + outer loop + vertex 936.59 321.4 12.3589 + vertex 936.672 323.705 11.2188 + vertex 936.377 324.072 12.3757 + endloop + endfacet + facet normal 0.971221 0.062465 0.229841 + outer loop + vertex 937.043 318.457 11.2273 + vertex 936.877 321.065 11.2202 + vertex 936.753 318.787 12.3612 + endloop + endfacet + facet normal 0.972059 0.0608527 0.226714 + outer loop + vertex 936.753 318.787 12.3612 + vertex 936.877 321.065 11.2202 + vertex 936.59 321.4 12.3589 + endloop + endfacet + facet normal 0.912023 0.05726 0.406123 + outer loop + vertex 936.753 318.787 12.3612 + vertex 936.59 321.4 12.3589 + vertex 936.283 319.378 13.3328 + endloop + endfacet + facet normal 0.902265 0.0681987 0.425754 + outer loop + vertex 936.283 319.378 13.3328 + vertex 936.59 321.4 12.3589 + vertex 936.006 321.891 13.5181 + endloop + endfacet + facet normal 0.902364 0.0691835 0.425387 + outer loop + vertex 936.59 321.4 12.3589 + vertex 936.377 324.072 12.3757 + vertex 936.006 321.891 13.5181 + endloop + endfacet + facet normal 0.912721 0.0565578 0.404651 + outer loop + vertex 936.006 321.891 13.5181 + vertex 936.377 324.072 12.3757 + vertex 935.896 324.699 13.3739 + endloop + endfacet + facet normal 0.970049 0.108146 0.217505 + outer loop + vertex 936.417 326.392 11.2437 + vertex 936.097 329.126 11.3104 + vertex 936.103 326.806 12.4356 + endloop + endfacet + facet normal 0.962953 0.11981 0.241593 + outer loop + vertex 936.103 326.806 12.4356 + vertex 936.097 329.126 11.3104 + vertex 935.723 329.616 12.559 + endloop + endfacet + facet normal 0.97161 0.0903169 0.218669 + outer loop + vertex 936.672 323.705 11.2188 + vertex 936.417 326.392 11.2437 + vertex 936.377 324.072 12.3757 + endloop + endfacet + facet normal 0.970412 0.0924728 0.223046 + outer loop + vertex 936.377 324.072 12.3757 + vertex 936.417 326.392 11.2437 + vertex 936.103 326.806 12.4356 + endloop + endfacet + facet normal 0.917083 0.0834631 0.389863 + outer loop + vertex 936.377 324.072 12.3757 + vertex 936.103 326.806 12.4356 + vertex 935.896 324.699 13.3739 + endloop + endfacet + facet normal 0.905819 0.0948339 0.412914 + outer loop + vertex 935.896 324.699 13.3739 + vertex 936.103 326.806 12.4356 + vertex 935.524 327.246 13.6058 + endloop + endfacet + facet normal 0.90631 0.104769 0.409421 + outer loop + vertex 936.103 326.806 12.4356 + vertex 935.723 329.616 12.559 + vertex 935.524 327.246 13.6058 + endloop + endfacet + facet normal 0.911852 0.0993948 0.398305 + outer loop + vertex 935.524 327.246 13.6058 + vertex 935.723 329.616 12.559 + vertex 935.299 329.726 13.5004 + endloop + endfacet + facet normal 0.632263 0.0538968 -0.772877 + outer loop + vertex 933.349 326.395 4.97744 + vertex 933.319 328.776 5.11962 + vertex 934.515 326.395 5.93142 + endloop + endfacet + facet normal 0.654887 0.0722874 -0.752262 + outer loop + vertex 934.515 326.395 5.93142 + vertex 933.319 328.776 5.11962 + vertex 934.231 328.987 5.9331 + endloop + endfacet + facet normal 0.648377 0.0730528 -0.757806 + outer loop + vertex 933.832 323.562 5.11833 + vertex 933.349 326.395 4.97744 + vertex 934.76 323.759 5.93099 + endloop + endfacet + facet normal 0.63208 0.0589521 -0.772657 + outer loop + vertex 934.76 323.759 5.93099 + vertex 933.349 326.395 4.97744 + vertex 934.515 326.395 5.93142 + endloop + endfacet + facet normal 0.759741 0.0708126 -0.646358 + outer loop + vertex 934.76 323.759 5.93099 + vertex 934.515 326.395 5.93142 + vertex 935.591 323.799 6.91232 + endloop + endfacet + facet normal 0.763076 0.0738115 -0.642081 + outer loop + vertex 935.591 323.799 6.91232 + vertex 934.515 326.395 5.93142 + vertex 935.337 326.437 6.91336 + endloop + endfacet + facet normal 0.762245 0.0839858 -0.641817 + outer loop + vertex 934.515 326.395 5.93142 + vertex 934.231 328.987 5.9331 + vertex 935.337 326.437 6.91336 + endloop + endfacet + facet normal 0.761031 0.0828494 -0.643403 + outer loop + vertex 935.337 326.437 6.91336 + vertex 934.231 328.987 5.9331 + vertex 935.053 329.023 6.91115 + endloop + endfacet + facet normal 0.62678 0.0341489 -0.778447 + outer loop + vertex 933.789 321.171 4.97871 + vertex 933.832 323.562 5.11833 + vertex 934.972 321.122 5.92918 + endloop + endfacet + facet normal 0.651644 0.053001 -0.756671 + outer loop + vertex 934.972 321.122 5.92918 + vertex 933.832 323.562 5.11833 + vertex 934.76 323.759 5.93099 + endloop + endfacet + facet normal 0.642858 0.0533023 -0.764128 + outer loop + vertex 934.192 318.354 5.12062 + vertex 933.789 321.171 4.97871 + vertex 935.14 318.509 5.92908 + endloop + endfacet + facet normal 0.626793 0.0401481 -0.778151 + outer loop + vertex 935.14 318.509 5.92908 + vertex 933.789 321.171 4.97871 + vertex 934.972 321.122 5.92918 + endloop + endfacet + facet normal 0.759395 0.0486306 -0.64881 + outer loop + vertex 935.14 318.509 5.92908 + vertex 934.972 321.122 5.92918 + vertex 935.977 318.52 6.90956 + endloop + endfacet + facet normal 0.762359 0.051162 -0.645129 + outer loop + vertex 935.977 318.52 6.90956 + vertex 934.972 321.122 5.92918 + vertex 935.802 321.147 6.91136 + endloop + endfacet + facet normal 0.761765 0.0617937 -0.644899 + outer loop + vertex 934.972 321.122 5.92918 + vertex 934.76 323.759 5.93099 + vertex 935.802 321.147 6.91136 + endloop + endfacet + facet normal 0.760458 0.0606537 -0.646548 + outer loop + vertex 935.802 321.147 6.91136 + vertex 934.76 323.759 5.93099 + vertex 935.591 323.799 6.91232 + endloop + endfacet + facet normal 0.863984 0.0688259 -0.498794 + outer loop + vertex 935.802 321.147 6.91136 + vertex 935.591 323.799 6.91232 + vertex 936.4 321.098 7.94092 + endloop + endfacet + facet normal 0.865292 0.0701537 -0.496336 + outer loop + vertex 936.4 321.098 7.94092 + vertex 935.591 323.799 6.91232 + vertex 936.185 323.749 7.94134 + endloop + endfacet + facet normal 0.864333 0.057846 -0.499581 + outer loop + vertex 935.977 318.52 6.90956 + vertex 935.802 321.147 6.91136 + vertex 936.575 318.465 7.93857 + endloop + endfacet + facet normal 0.864361 0.057873 -0.499531 + outer loop + vertex 936.575 318.465 7.93857 + vertex 935.802 321.147 6.91136 + vertex 936.4 321.098 7.94092 + endloop + endfacet + facet normal 0.943055 0.0629464 -0.326628 + outer loop + vertex 936.575 318.465 7.93857 + vertex 936.4 321.098 7.94092 + vertex 936.948 318.375 8.99769 + endloop + endfacet + facet normal 0.941911 0.0613237 -0.330216 + outer loop + vertex 936.948 318.375 8.99769 + vertex 936.4 321.098 7.94092 + vertex 936.777 321.005 8.99845 + endloop + endfacet + facet normal 0.94135 0.0762874 -0.328694 + outer loop + vertex 936.4 321.098 7.94092 + vertex 936.185 323.749 7.94134 + vertex 936.777 321.005 8.99845 + endloop + endfacet + facet normal 0.939891 0.0741925 -0.333317 + outer loop + vertex 936.777 321.005 8.99845 + vertex 936.185 323.749 7.94134 + vertex 936.567 323.646 8.99411 + endloop + endfacet + facet normal 0.862492 0.0940933 -0.497246 + outer loop + vertex 935.337 326.437 6.91336 + vertex 935.053 329.023 6.91115 + vertex 935.934 326.379 7.93789 + endloop + endfacet + facet normal 0.860248 0.0916676 -0.501568 + outer loop + vertex 935.934 326.379 7.93789 + vertex 935.053 329.023 6.91115 + vertex 935.655 328.956 7.93138 + endloop + endfacet + facet normal 0.864678 0.0835478 -0.495331 + outer loop + vertex 935.591 323.799 6.91232 + vertex 935.337 326.437 6.91336 + vertex 936.185 323.749 7.94134 + endloop + endfacet + facet normal 0.863125 0.0819211 -0.498302 + outer loop + vertex 936.185 323.749 7.94134 + vertex 935.337 326.437 6.91336 + vertex 935.934 326.379 7.93789 + endloop + endfacet + facet normal 0.939186 0.089416 -0.331563 + outer loop + vertex 936.185 323.749 7.94134 + vertex 935.934 326.379 7.93789 + vertex 936.567 323.646 8.99411 + endloop + endfacet + facet normal 0.938652 0.0886281 -0.333282 + outer loop + vertex 936.567 323.646 8.99411 + vertex 935.934 326.379 7.93789 + vertex 936.317 326.268 8.98708 + endloop + endfacet + facet normal 0.937989 0.100495 -0.331778 + outer loop + vertex 935.934 326.379 7.93789 + vertex 935.655 328.956 7.93138 + vertex 936.317 326.268 8.98708 + endloop + endfacet + facet normal 0.937914 0.100379 -0.332026 + outer loop + vertex 936.317 326.268 8.98708 + vertex 935.655 328.956 7.93138 + vertex 936.039 328.852 8.98433 + endloop + endfacet + facet normal 0.391614 0.0390158 -0.919302 + outer loop + vertex 929.127 325.245 2.90271 + vertex 928.624 330.31 2.90357 + vertex 931.842 325.333 4.06296 + endloop + endfacet + facet normal 0.393871 0.0407171 -0.918263 + outer loop + vertex 931.842 325.333 4.06296 + vertex 928.624 330.31 2.90357 + vertex 931.31 330.456 4.06212 + endloop + endfacet + facet normal 0.3892 0.0284216 -0.920715 + outer loop + vertex 929.495 320.154 2.90112 + vertex 929.127 325.245 2.90271 + vertex 932.238 320.183 4.06156 + endloop + endfacet + facet normal 0.391967 0.0304055 -0.919477 + outer loop + vertex 932.238 320.183 4.06156 + vertex 929.127 325.245 2.90271 + vertex 931.842 325.333 4.06296 + endloop + endfacet + facet normal 0.496693 0.0416644 -0.866926 + outer loop + vertex 933.832 323.562 5.11833 + vertex 933.789 321.171 4.97871 + vertex 931.842 325.333 4.06296 + endloop + endfacet + facet normal 0.495905 0.0270895 -0.867954 + outer loop + vertex 934.192 318.354 5.12062 + vertex 932.238 320.183 4.06156 + vertex 933.789 321.171 4.97871 + endloop + endfacet + facet normal 0.490533 0.037975 -0.870595 + outer loop + vertex 932.238 320.183 4.06156 + vertex 931.842 325.333 4.06296 + vertex 933.789 321.171 4.97871 + endloop + endfacet + facet normal 0.502332 0.0576713 -0.862749 + outer loop + vertex 933.319 328.776 5.11962 + vertex 933.349 326.395 4.97744 + vertex 931.31 330.456 4.06212 + endloop + endfacet + facet normal 0.496734 0.0417262 -0.866899 + outer loop + vertex 933.832 323.562 5.11833 + vertex 931.842 325.333 4.06296 + vertex 933.349 326.395 4.97744 + endloop + endfacet + facet normal 0.491722 0.0508779 -0.869265 + outer loop + vertex 931.842 325.333 4.06296 + vertex 931.31 330.456 4.06212 + vertex 933.349 326.395 4.97744 + endloop + endfacet + facet normal 0.180609 0.00894913 -0.983514 + outer loop + vertex 922.823 325.28 1.41232 + vertex 923.006 329.85 1.48743 + vertex 926.221 325.181 2.03539 + endloop + endfacet + facet normal 0.1944 0.0187706 -0.980743 + outer loop + vertex 926.221 325.181 2.03539 + vertex 923.006 329.85 1.48743 + vertex 925.746 330.201 2.03721 + endloop + endfacet + facet normal 0.189649 0.0181053 -0.981685 + outer loop + vertex 923.752 319.826 1.49113 + vertex 922.823 325.28 1.41232 + vertex 926.559 320.12 2.03875 + endloop + endfacet + facet normal 0.180673 0.0113901 -0.983477 + outer loop + vertex 926.559 320.12 2.03875 + vertex 922.823 325.28 1.41232 + vertex 926.221 325.181 2.03539 + endloop + endfacet + facet normal 0.281543 0.0181297 -0.959377 + outer loop + vertex 926.559 320.12 2.03875 + vertex 926.221 325.181 2.03539 + vertex 929.495 320.154 2.90112 + endloop + endfacet + facet normal 0.285531 0.0209395 -0.958141 + outer loop + vertex 929.495 320.154 2.90112 + vertex 926.221 325.181 2.03539 + vertex 929.127 325.245 2.90271 + endloop + endfacet + facet normal 0.285355 0.0273782 -0.958031 + outer loop + vertex 926.221 325.181 2.03539 + vertex 925.746 330.201 2.03721 + vertex 929.127 325.245 2.90271 + endloop + endfacet + facet normal 0.287077 0.028649 -0.957479 + outer loop + vertex 929.127 325.245 2.90271 + vertex 925.746 330.201 2.03721 + vertex 928.624 330.31 2.90357 + endloop + endfacet + facet normal 0.113865 0.0117778 -0.993426 + outer loop + vertex 923.006 329.85 1.48743 + vertex 922.823 325.28 1.41232 + vertex 918.067 333.191 0.960906 + endloop + endfacet + facet normal 0.11172 0.00466138 -0.993729 + outer loop + vertex 923.752 319.826 1.49113 + vertex 918.889 323.325 0.960884 + vertex 922.823 325.28 1.41232 + endloop + endfacet + facet normal 0.109521 0.00913674 -0.993942 + outer loop + vertex 918.889 323.325 0.960884 + vertex 918.067 333.191 0.960906 + vertex 922.823 325.28 1.41232 + endloop + endfacet + facet normal 0.903363 0.0769104 0.421924 + outer loop + vertex 904.685 343.79 27.0147 + vertex 904.296 348.141 27.0543 + vertex 903.775 344.427 28.8465 + endloop + endfacet + facet normal 0.904295 0.0759028 0.420107 + outer loop + vertex 903.775 344.427 28.8465 + vertex 904.296 348.141 27.0543 + vertex 903.394 348.79 28.8768 + endloop + endfacet + facet normal 0.900083 0.0566408 0.432022 + outer loop + vertex 904.98 339.439 26.9704 + vertex 904.685 343.79 27.0147 + vertex 904.057 340.068 28.8108 + endloop + endfacet + facet normal 0.901733 0.0548091 0.428804 + outer loop + vertex 904.057 340.068 28.8108 + vertex 904.685 343.79 27.0147 + vertex 903.775 344.427 28.8465 + endloop + endfacet + facet normal 0.702383 0.0575379 0.70947 + outer loop + vertex 906.94 342.965 24.34 + vertex 906.539 347.341 24.3824 + vertex 905.711 343.403 25.5215 + endloop + endfacet + facet normal 0.700251 0.0585705 0.71149 + outer loop + vertex 905.711 343.403 25.5215 + vertex 906.539 347.341 24.3824 + vertex 905.305 347.751 25.5631 + endloop + endfacet + facet normal 0.706747 0.0393642 0.706371 + outer loop + vertex 907.227 338.58 24.2975 + vertex 906.94 342.965 24.34 + vertex 906.018 339.043 25.4805 + endloop + endfacet + facet normal 0.700189 0.0427386 0.712677 + outer loop + vertex 906.018 339.043 25.4805 + vertex 906.94 342.965 24.34 + vertex 905.711 343.403 25.5215 + endloop + endfacet + facet normal 0.411145 0.0190345 0.911371 + outer loop + vertex 909.973 340.984 22.7278 + vertex 909.578 345.201 22.8176 + vertex 908.368 342.148 23.4271 + endloop + endfacet + facet normal 0.400061 0.0243822 0.916164 + outer loop + vertex 908.368 342.148 23.4271 + vertex 909.578 345.201 22.8176 + vertex 908.036 346.572 23.4547 + endloop + endfacet + facet normal 0.436796 -0.00204147 0.899558 + outer loop + vertex 909.783 336.672 22.8098 + vertex 909.973 340.984 22.7278 + vertex 908.57 337.794 23.4015 + endloop + endfacet + facet normal 0.407835 0.0135192 0.912956 + outer loop + vertex 908.57 337.794 23.4015 + vertex 909.973 340.984 22.7278 + vertex 908.368 342.148 23.4271 + endloop + endfacet + facet normal 0.563269 0.0212302 0.826001 + outer loop + vertex 908.57 337.794 23.4015 + vertex 908.368 342.148 23.4271 + vertex 907.227 338.58 24.2975 + endloop + endfacet + facet normal 0.549509 0.0278353 0.835024 + outer loop + vertex 907.227 338.58 24.2975 + vertex 908.368 342.148 23.4271 + vertex 906.94 342.965 24.34 + endloop + endfacet + facet normal 0.552803 0.0363944 0.832517 + outer loop + vertex 908.368 342.148 23.4271 + vertex 908.036 346.572 23.4547 + vertex 906.94 342.965 24.34 + endloop + endfacet + facet normal 0.541606 0.0415362 0.839606 + outer loop + vertex 906.94 342.965 24.34 + vertex 908.036 346.572 23.4547 + vertex 906.539 347.341 24.3824 + endloop + endfacet + facet normal 0.310865 0.00445062 0.950444 + outer loop + vertex 909.783 336.672 22.8098 + vertex 911.368 337.825 22.286 + vertex 909.973 340.984 22.7278 + endloop + endfacet + facet normal 0.281335 0.00586603 0.959592 + outer loop + vertex 909.578 345.201 22.8176 + vertex 909.973 340.984 22.7278 + vertex 912.004 345.983 22.1015 + endloop + endfacet + facet normal 0.218462 0.00503803 0.975832 + outer loop + vertex 913.822 338.136 21.7352 + vertex 912.004 345.983 22.1015 + vertex 911.368 337.825 22.286 + endloop + endfacet + facet normal 0.298293 -0.00166816 0.954473 + outer loop + vertex 909.973 340.984 22.7278 + vertex 911.368 337.825 22.286 + vertex 912.004 345.983 22.1015 + endloop + endfacet + facet normal 0.61984 0.0819792 0.780434 + outer loop + vertex 932.337 335.234 16.2868 + vertex 931.625 340.273 16.3226 + vertex 930.758 336.229 17.4365 + endloop + endfacet + facet normal 0.621033 0.0814763 0.779538 + outer loop + vertex 930.758 336.229 17.4365 + vertex 931.625 340.273 16.3226 + vertex 930.075 341.212 17.4593 + endloop + endfacet + facet normal 0.611484 0.0652212 0.788564 + outer loop + vertex 932.954 330.128 16.2306 + vertex 932.337 335.234 16.2868 + vertex 931.332 331.192 17.4 + endloop + endfacet + facet normal 0.613522 0.0642994 0.787056 + outer loop + vertex 931.332 331.192 17.4 + vertex 932.337 335.234 16.2868 + vertex 930.758 336.229 17.4365 + endloop + endfacet + facet normal 0.467402 0.0469372 0.882798 + outer loop + vertex 931.332 331.192 17.4 + vertex 930.758 336.229 17.4365 + vertex 929.742 332.38 18.179 + endloop + endfacet + facet normal 0.447958 0.0539266 0.892427 + outer loop + vertex 929.742 332.38 18.179 + vertex 930.758 336.229 17.4365 + vertex 928.883 337.135 18.3228 + endloop + endfacet + facet normal 0.449244 0.0574354 0.891561 + outer loop + vertex 930.758 336.229 17.4365 + vertex 930.075 341.212 17.4593 + vertex 928.883 337.135 18.3228 + endloop + endfacet + facet normal 0.465659 0.0509256 0.883498 + outer loop + vertex 928.883 337.135 18.3228 + vertex 930.075 341.212 17.4593 + vertex 928.491 342.373 18.2274 + endloop + endfacet + facet normal 0.856652 0.133729 0.49826 + outer loop + vertex 935.04 333.001 12.869 + vertex 934.202 338.348 12.8757 + vertex 933.769 334.199 14.7339 + endloop + endfacet + facet normal 0.867795 0.124831 0.480988 + outer loop + vertex 933.769 334.199 14.7339 + vertex 934.202 338.348 12.8757 + vertex 932.999 339.35 14.7859 + endloop + endfacet + facet normal 0.757762 0.180788 0.626987 + outer loop + vertex 935.299 329.726 13.5004 + vertex 935.04 333.001 12.869 + vertex 934.522 329.007 14.6475 + endloop + endfacet + facet normal 0.853608 0.115359 0.507981 + outer loop + vertex 934.522 329.007 14.6475 + vertex 935.04 333.001 12.869 + vertex 933.769 334.199 14.7339 + endloop + endfacet + facet normal 0.740437 0.0963301 0.665187 + outer loop + vertex 934.522 329.007 14.6475 + vertex 933.769 334.199 14.7339 + vertex 932.954 330.128 16.2306 + endloop + endfacet + facet normal 0.760001 0.0847614 0.644372 + outer loop + vertex 932.954 330.128 16.2306 + vertex 933.769 334.199 14.7339 + vertex 932.337 335.234 16.2868 + endloop + endfacet + facet normal 0.765676 0.108026 0.63409 + outer loop + vertex 933.769 334.199 14.7339 + vertex 932.999 339.35 14.7859 + vertex 932.337 335.234 16.2868 + endloop + endfacet + facet normal 0.771815 0.104524 0.627198 + outer loop + vertex 932.337 335.234 16.2868 + vertex 932.999 339.35 14.7859 + vertex 931.625 340.273 16.3226 + endloop + endfacet + facet normal 0.980325 0.157909 -0.118439 + outer loop + vertex 935.014 336.409 9.01891 + vertex 934.61 338.923 9.02264 + vertex 935.132 336.551 10.1775 + endloop + endfacet + facet normal 0.980689 0.163138 -0.107863 + outer loop + vertex 935.132 336.551 10.1775 + vertex 934.61 338.923 9.02264 + vertex 934.709 339.1 10.1896 + endloop + endfacet + facet normal 0.981424 0.148554 -0.121405 + outer loop + vertex 935.391 333.914 9.00624 + vertex 935.014 336.409 9.01891 + vertex 935.51 334.06 10.1512 + endloop + endfacet + facet normal 0.9816 0.1504 -0.117651 + outer loop + vertex 935.51 334.06 10.1512 + vertex 935.014 336.409 9.01891 + vertex 935.132 336.551 10.1775 + endloop + endfacet + facet normal 0.985614 0.148924 0.0799123 + outer loop + vertex 935.51 334.06 10.1512 + vertex 935.132 336.551 10.1775 + vertex 935.368 334.421 11.2304 + endloop + endfacet + facet normal 0.978987 0.166726 0.117419 + outer loop + vertex 935.368 334.421 11.2304 + vertex 935.132 336.551 10.1775 + vertex 934.936 336.791 11.4685 + endloop + endfacet + facet normal 0.979676 0.161897 0.118421 + outer loop + vertex 935.132 336.551 10.1775 + vertex 934.709 339.1 10.1896 + vertex 934.936 336.791 11.4685 + endloop + endfacet + facet normal 0.985044 0.146803 0.0902122 + outer loop + vertex 934.936 336.791 11.4685 + vertex 934.709 339.1 10.1896 + vertex 934.544 339.543 11.2731 + endloop + endfacet + facet normal 0.982876 0.133132 -0.127398 + outer loop + vertex 935.729 331.4 8.99323 + vertex 935.391 333.914 9.00624 + vertex 935.866 331.493 10.1417 + endloop + endfacet + facet normal 0.983314 0.13665 -0.120083 + outer loop + vertex 935.866 331.493 10.1417 + vertex 935.391 333.914 9.00624 + vertex 935.51 334.06 10.1512 + endloop + endfacet + facet normal 0.983049 0.120061 -0.138567 + outer loop + vertex 936.039 328.852 8.98433 + vertex 935.729 331.4 8.99323 + vertex 936.196 328.862 10.1032 + endloop + endfacet + facet normal 0.983966 0.125335 -0.126894 + outer loop + vertex 936.196 328.862 10.1032 + vertex 935.729 331.4 8.99323 + vertex 935.866 331.493 10.1417 + endloop + endfacet + facet normal 0.990853 0.123546 0.0542884 + outer loop + vertex 936.196 328.862 10.1032 + vertex 935.866 331.493 10.1417 + vertex 936.097 329.126 11.3104 + endloop + endfacet + facet normal 0.986557 0.138857 0.0861604 + outer loop + vertex 936.097 329.126 11.3104 + vertex 935.866 331.493 10.1417 + vertex 935.697 331.914 11.3897 + endloop + endfacet + facet normal 0.986827 0.136377 0.087033 + outer loop + vertex 935.866 331.493 10.1417 + vertex 935.51 334.06 10.1512 + vertex 935.697 331.914 11.3897 + endloop + endfacet + facet normal 0.987203 0.135088 0.0847427 + outer loop + vertex 935.697 331.914 11.3897 + vertex 935.51 334.06 10.1512 + vertex 935.368 334.421 11.2304 + endloop + endfacet + facet normal 0.962608 0.131134 0.237043 + outer loop + vertex 936.097 329.126 11.3104 + vertex 935.697 331.914 11.3897 + vertex 935.723 329.616 12.559 + endloop + endfacet + facet normal 0.908464 0.147241 0.39117 + outer loop + vertex 935.299 329.726 13.5004 + vertex 935.723 329.616 12.559 + vertex 935.04 333.001 12.869 + endloop + endfacet + facet normal 0.939255 0.143232 0.311906 + outer loop + vertex 935.368 334.421 11.2304 + vertex 935.04 333.001 12.869 + vertex 935.697 331.914 11.3897 + endloop + endfacet + facet normal 0.940515 0.162182 0.298543 + outer loop + vertex 935.723 329.616 12.559 + vertex 935.697 331.914 11.3897 + vertex 935.04 333.001 12.869 + endloop + endfacet + facet normal 0.940424 0.140382 0.30967 + outer loop + vertex 935.368 334.421 11.2304 + vertex 934.936 336.791 11.4685 + vertex 935.04 333.001 12.869 + endloop + endfacet + facet normal 0.935946 0.155818 0.315793 + outer loop + vertex 934.544 339.543 11.2731 + vertex 934.202 338.348 12.8757 + vertex 934.936 336.791 11.4685 + endloop + endfacet + facet normal 0.93415 0.146098 0.325607 + outer loop + vertex 934.202 338.348 12.8757 + vertex 935.04 333.001 12.869 + vertex 934.936 336.791 11.4685 + endloop + endfacet + facet normal 0.636186 0.0898232 -0.76629 + outer loop + vertex 932.076 336.499 4.98118 + vertex 931.932 338.768 5.12746 + vertex 933.225 336.462 5.9304 + endloop + endfacet + facet normal 0.652691 0.104623 -0.750365 + outer loop + vertex 933.225 336.462 5.9304 + vertex 931.932 338.768 5.12746 + vertex 932.828 338.943 5.93137 + endloop + endfacet + facet normal 0.64843 0.106885 -0.753733 + outer loop + vertex 932.682 333.817 5.1226 + vertex 932.076 336.499 4.98118 + vertex 933.59 334.002 5.92945 + endloop + endfacet + facet normal 0.635987 0.094733 -0.765863 + outer loop + vertex 933.59 334.002 5.92945 + vertex 932.076 336.499 4.98118 + vertex 933.225 336.462 5.9304 + endloop + endfacet + facet normal 0.761511 0.113324 -0.638169 + outer loop + vertex 933.59 334.002 5.92945 + vertex 933.225 336.462 5.9304 + vertex 934.406 334.012 6.90447 + endloop + endfacet + facet normal 0.761809 0.113631 -0.637758 + outer loop + vertex 934.406 334.012 6.90447 + vertex 933.225 336.462 5.9304 + vertex 934.039 336.468 6.90391 + endloop + endfacet + facet normal 0.761031 0.121896 -0.63716 + outer loop + vertex 933.225 336.462 5.9304 + vertex 932.828 338.943 5.93137 + vertex 934.039 336.468 6.90391 + endloop + endfacet + facet normal 0.761617 0.122503 -0.636344 + outer loop + vertex 934.039 336.468 6.90391 + vertex 932.828 338.943 5.93137 + vertex 933.638 338.953 6.90257 + endloop + endfacet + facet normal 0.634639 0.0713586 -0.769507 + outer loop + vertex 932.768 331.524 4.98034 + vertex 932.682 333.817 5.1226 + vertex 933.922 331.52 5.93229 + endloop + endfacet + facet normal 0.652087 0.0865282 -0.75319 + outer loop + vertex 933.922 331.52 5.93229 + vertex 932.682 333.817 5.1226 + vertex 933.59 334.002 5.92945 + endloop + endfacet + facet normal 0.651134 0.0925013 -0.753305 + outer loop + vertex 933.319 328.776 5.11962 + vertex 932.768 331.524 4.98034 + vertex 934.231 328.987 5.9331 + endloop + endfacet + facet normal 0.634389 0.0768864 -0.769181 + outer loop + vertex 934.231 328.987 5.9331 + vertex 932.768 331.524 4.98034 + vertex 933.922 331.52 5.93229 + endloop + endfacet + facet normal 0.760226 0.0922274 -0.643079 + outer loop + vertex 934.231 328.987 5.9331 + vertex 933.922 331.52 5.93229 + vertex 935.053 329.023 6.91115 + endloop + endfacet + facet normal 0.762633 0.0945716 -0.63988 + outer loop + vertex 935.053 329.023 6.91115 + vertex 933.922 331.52 5.93229 + vertex 934.739 331.541 6.9082 + endloop + endfacet + facet normal 0.762047 0.101394 -0.639534 + outer loop + vertex 933.922 331.52 5.93229 + vertex 933.59 334.002 5.92945 + vertex 934.739 331.541 6.9082 + endloop + endfacet + facet normal 0.762517 0.101866 -0.638898 + outer loop + vertex 934.739 331.541 6.9082 + vertex 933.59 334.002 5.92945 + vertex 934.406 334.012 6.90447 + endloop + endfacet + facet normal 0.857511 0.114883 -0.501474 + outer loop + vertex 934.739 331.541 6.9082 + vertex 934.406 334.012 6.90447 + vertex 935.344 331.473 7.92772 + endloop + endfacet + facet normal 0.858871 0.116475 -0.498772 + outer loop + vertex 935.344 331.473 7.92772 + vertex 934.406 334.012 6.90447 + vertex 935.009 333.949 7.92833 + endloop + endfacet + facet normal 0.859377 0.106827 -0.500059 + outer loop + vertex 935.053 329.023 6.91115 + vertex 934.739 331.541 6.9082 + vertex 935.655 328.956 7.93138 + endloop + endfacet + facet normal 0.858138 0.10543 -0.502478 + outer loop + vertex 935.655 328.956 7.93138 + vertex 934.739 331.541 6.9082 + vertex 935.344 331.473 7.92772 + endloop + endfacet + facet normal 0.936847 0.115418 -0.330147 + outer loop + vertex 935.655 328.956 7.93138 + vertex 935.344 331.473 7.92772 + vertex 936.039 328.852 8.98433 + endloop + endfacet + facet normal 0.936646 0.115089 -0.330832 + outer loop + vertex 936.039 328.852 8.98433 + vertex 935.344 331.473 7.92772 + vertex 935.729 331.4 8.99323 + endloop + endfacet + facet normal 0.935551 0.126821 -0.329638 + outer loop + vertex 935.344 331.473 7.92772 + vertex 935.009 333.949 7.92833 + vertex 935.729 331.4 8.99323 + endloop + endfacet + facet normal 0.936147 0.12787 -0.327532 + outer loop + vertex 935.729 331.4 8.99323 + vertex 935.009 333.949 7.92833 + vertex 935.391 333.914 9.00624 + endloop + endfacet + facet normal 0.856755 0.137924 -0.496938 + outer loop + vertex 934.039 336.468 6.90391 + vertex 933.638 338.953 6.90257 + vertex 934.643 336.417 7.93127 + endloop + endfacet + facet normal 0.857789 0.139204 -0.494793 + outer loop + vertex 934.643 336.417 7.93127 + vertex 933.638 338.953 6.90257 + vertex 934.237 338.915 7.93031 + endloop + endfacet + facet normal 0.857952 0.128021 -0.497523 + outer loop + vertex 934.406 334.012 6.90447 + vertex 934.039 336.468 6.90391 + vertex 935.009 333.949 7.92833 + endloop + endfacet + facet normal 0.857711 0.12773 -0.498012 + outer loop + vertex 935.009 333.949 7.92833 + vertex 934.039 336.468 6.90391 + vertex 934.643 336.417 7.93127 + endloop + endfacet + facet normal 0.934852 0.138961 -0.326714 + outer loop + vertex 935.009 333.949 7.92833 + vertex 934.643 336.417 7.93127 + vertex 935.391 333.914 9.00624 + endloop + endfacet + facet normal 0.936897 0.142845 -0.319092 + outer loop + vertex 935.391 333.914 9.00624 + vertex 934.643 336.417 7.93127 + vertex 935.014 336.409 9.01891 + endloop + endfacet + facet normal 0.935636 0.151921 -0.318598 + outer loop + vertex 934.643 336.417 7.93127 + vertex 934.237 338.915 7.93031 + vertex 935.014 336.409 9.01891 + endloop + endfacet + facet normal 0.935143 0.15094 -0.320506 + outer loop + vertex 935.014 336.409 9.01891 + vertex 934.237 338.915 7.93031 + vertex 934.61 338.923 9.02264 + endloop + endfacet + facet normal 0.398034 0.0594019 -0.915446 + outer loop + vertex 928.002 335.324 2.90284 + vertex 927.265 340.299 2.90495 + vertex 930.654 335.481 4.06583 + endloop + endfacet + facet normal 0.403193 0.0636446 -0.912899 + outer loop + vertex 930.654 335.481 4.06583 + vertex 927.265 340.299 2.90495 + vertex 929.88 340.466 4.07166 + endloop + endfacet + facet normal 0.393365 0.0486715 -0.918093 + outer loop + vertex 928.624 330.31 2.90357 + vertex 928.002 335.324 2.90284 + vertex 931.31 330.456 4.06212 + endloop + endfacet + facet normal 0.398516 0.0527558 -0.915643 + outer loop + vertex 931.31 330.456 4.06212 + vertex 928.002 335.324 2.90284 + vertex 930.654 335.481 4.06583 + endloop + endfacet + facet normal 0.506646 0.0721521 -0.85913 + outer loop + vertex 932.682 333.817 5.1226 + vertex 932.768 331.524 4.98034 + vertex 930.654 335.481 4.06583 + endloop + endfacet + facet normal 0.501917 0.0569945 -0.863036 + outer loop + vertex 933.319 328.776 5.11962 + vertex 931.31 330.456 4.06212 + vertex 932.768 331.524 4.98034 + endloop + endfacet + facet normal 0.497017 0.0655914 -0.865258 + outer loop + vertex 931.31 330.456 4.06212 + vertex 930.654 335.481 4.06583 + vertex 932.768 331.524 4.98034 + endloop + endfacet + facet normal 0.512124 0.0876202 -0.854431 + outer loop + vertex 931.932 338.768 5.12746 + vertex 932.076 336.499 4.98118 + vertex 929.88 340.466 4.07166 + endloop + endfacet + facet normal 0.504605 0.0687219 -0.860611 + outer loop + vertex 932.682 333.817 5.1226 + vertex 930.654 335.481 4.06583 + vertex 932.076 336.499 4.98118 + endloop + endfacet + facet normal 0.49914 0.0784777 -0.86296 + outer loop + vertex 930.654 335.481 4.06583 + vertex 929.88 340.466 4.07166 + vertex 932.076 336.499 4.98118 + endloop + endfacet + facet normal 0.183395 0.0174967 -0.982884 + outer loop + vertex 921.819 335.215 1.41409 + vertex 921.784 339.733 1.48795 + vertex 925.155 335.184 2.03593 + endloop + endfacet + facet normal 0.196799 0.0277714 -0.98005 + outer loop + vertex 925.155 335.184 2.03593 + vertex 921.784 339.733 1.48795 + vertex 924.453 340.133 2.03516 + endloop + endfacet + facet normal 0.193053 0.0292983 -0.980751 + outer loop + vertex 923.006 329.85 1.48743 + vertex 921.819 335.215 1.41409 + vertex 925.746 330.201 2.03721 + endloop + endfacet + facet normal 0.183416 0.0214959 -0.9828 + outer loop + vertex 925.746 330.201 2.03721 + vertex 921.819 335.215 1.41409 + vertex 925.155 335.184 2.03593 + endloop + endfacet + facet normal 0.286854 0.0337678 -0.957379 + outer loop + vertex 925.746 330.201 2.03721 + vertex 925.155 335.184 2.03593 + vertex 928.624 330.31 2.90357 + endloop + endfacet + facet normal 0.289459 0.0357743 -0.956522 + outer loop + vertex 928.624 330.31 2.90357 + vertex 925.155 335.184 2.03593 + vertex 928.002 335.324 2.90284 + endloop + endfacet + facet normal 0.289172 0.0408819 -0.956404 + outer loop + vertex 925.155 335.184 2.03593 + vertex 924.453 340.133 2.03516 + vertex 928.002 335.324 2.90284 + endloop + endfacet + facet normal 0.292852 0.0438239 -0.955153 + outer loop + vertex 928.002 335.324 2.90284 + vertex 924.453 340.133 2.03516 + vertex 927.265 340.299 2.90495 + endloop + endfacet + facet normal 0.117226 0.0171455 -0.992957 + outer loop + vertex 921.784 339.733 1.48795 + vertex 921.819 335.215 1.41409 + vertex 916.815 342.975 0.957285 + endloop + endfacet + facet normal 0.113731 0.0115775 -0.993444 + outer loop + vertex 923.006 329.85 1.48743 + vertex 918.067 333.191 0.960906 + vertex 921.819 335.215 1.41409 + endloop + endfacet + facet normal 0.11243 0.0140168 -0.993561 + outer loop + vertex 918.067 333.191 0.960906 + vertex 916.815 342.975 0.957285 + vertex 921.819 335.215 1.41409 + endloop + endfacet + facet normal 0.907306 0.112588 0.405117 + outer loop + vertex 903.819 352.514 27.0895 + vertex 903.266 356.896 27.1113 + vertex 902.928 353.164 28.9052 + endloop + endfacet + facet normal 0.908064 0.111806 0.403632 + outer loop + vertex 902.928 353.164 28.9052 + vertex 903.266 356.896 27.1113 + vertex 902.381 357.537 28.9238 + endloop + endfacet + facet normal 0.905392 0.0952905 0.413746 + outer loop + vertex 904.296 348.141 27.0543 + vertex 903.819 352.514 27.0895 + vertex 903.394 348.79 28.8768 + endloop + endfacet + facet normal 0.906589 0.0940307 0.411405 + outer loop + vertex 903.394 348.79 28.8768 + vertex 903.819 352.514 27.0895 + vertex 902.928 353.164 28.9052 + endloop + endfacet + facet normal 0.707272 0.0873753 0.701521 + outer loop + vertex 906.033 351.733 24.4188 + vertex 905.45 356.141 24.4579 + vertex 904.813 352.117 25.6017 + endloop + endfacet + facet normal 0.710995 0.0857693 0.697946 + outer loop + vertex 904.813 352.117 25.6017 + vertex 905.45 356.141 24.4579 + vertex 904.245 356.512 25.6402 + endloop + endfacet + facet normal 0.702292 0.0749321 0.707934 + outer loop + vertex 906.539 347.341 24.3824 + vertex 906.033 351.733 24.4188 + vertex 905.305 347.751 25.5631 + endloop + endfacet + facet normal 0.705822 0.0733233 0.704584 + outer loop + vertex 905.305 347.751 25.5631 + vertex 906.033 351.733 24.4188 + vertex 904.813 352.117 25.6017 + endloop + endfacet + facet normal 0.387545 0.0466767 0.920668 + outer loop + vertex 909.446 349.962 22.7457 + vertex 908.594 354.451 22.8766 + vertex 907.552 351.042 23.4883 + endloop + endfacet + facet normal 0.394584 0.044011 0.917805 + outer loop + vertex 907.552 351.042 23.4883 + vertex 908.594 354.451 22.8766 + vertex 906.965 355.523 23.5256 + endloop + endfacet + facet normal 0.40048 0.0249459 0.915966 + outer loop + vertex 909.578 345.201 22.8176 + vertex 909.446 349.962 22.7457 + vertex 908.036 346.572 23.4547 + endloop + endfacet + facet normal 0.381697 0.0343655 0.923648 + outer loop + vertex 908.036 346.572 23.4547 + vertex 909.446 349.962 22.7457 + vertex 907.552 351.042 23.4883 + endloop + endfacet + facet normal 0.545433 0.0527406 0.836493 + outer loop + vertex 908.036 346.572 23.4547 + vertex 907.552 351.042 23.4883 + vertex 906.539 347.341 24.3824 + endloop + endfacet + facet normal 0.539774 0.0551376 0.840002 + outer loop + vertex 906.539 347.341 24.3824 + vertex 907.552 351.042 23.4883 + vertex 906.033 351.733 24.4188 + endloop + endfacet + facet normal 0.542396 0.0640225 0.83768 + outer loop + vertex 907.552 351.042 23.4883 + vertex 906.965 355.523 23.5256 + vertex 906.033 351.733 24.4188 + endloop + endfacet + facet normal 0.541787 0.0642607 0.838056 + outer loop + vertex 906.033 351.733 24.4188 + vertex 906.965 355.523 23.5256 + vertex 905.45 356.141 24.4579 + endloop + endfacet + facet normal 0.279039 0.0249466 0.959956 + outer loop + vertex 908.594 354.451 22.8766 + vertex 909.446 349.962 22.7457 + vertex 910.806 356.251 22.1869 + endloop + endfacet + facet normal 0.276429 0.0221797 0.960778 + outer loop + vertex 909.578 345.201 22.8176 + vertex 912.004 345.983 22.1015 + vertex 909.446 349.962 22.7457 + endloop + endfacet + facet normal 0.280066 0.0246985 0.959663 + outer loop + vertex 912.004 345.983 22.1015 + vertex 910.806 356.251 22.1869 + vertex 909.446 349.962 22.7457 + endloop + endfacet + facet normal 0.633583 0.118414 0.76456 + outer loop + vertex 930.804 345.263 16.3391 + vertex 929.868 350.234 16.3453 + vertex 929.275 346.17 17.4663 + endloop + endfacet + facet normal 0.638257 0.116728 0.760922 + outer loop + vertex 929.275 346.17 17.4663 + vertex 929.868 350.234 16.3453 + vertex 928.364 351.11 17.4726 + endloop + endfacet + facet normal 0.627299 0.100641 0.772248 + outer loop + vertex 931.625 340.273 16.3226 + vertex 930.804 345.263 16.3391 + vertex 930.075 341.212 17.4593 + endloop + endfacet + facet normal 0.628091 0.100331 0.771645 + outer loop + vertex 930.075 341.212 17.4593 + vertex 930.804 345.263 16.3391 + vertex 929.275 346.17 17.4663 + endloop + endfacet + facet normal 0.479662 0.0762205 0.874137 + outer loop + vertex 930.075 341.212 17.4593 + vertex 929.275 346.17 17.4663 + vertex 928.491 342.373 18.2274 + endloop + endfacet + facet normal 0.466566 0.0802679 0.880837 + outer loop + vertex 928.491 342.373 18.2274 + vertex 929.275 346.17 17.4663 + vertex 927.438 347.061 18.3577 + endloop + endfacet + facet normal 0.468304 0.0852365 0.879447 + outer loop + vertex 929.275 346.17 17.4663 + vertex 928.364 351.11 17.4726 + vertex 927.438 347.061 18.3577 + endloop + endfacet + facet normal 0.489941 0.0778494 0.868273 + outer loop + vertex 927.438 347.061 18.3577 + vertex 928.364 351.11 17.4726 + vertex 926.812 352.235 18.2472 + endloop + endfacet + facet normal 0.875072 0.163834 0.45542 + outer loop + vertex 933.312 343.533 12.9125 + vertex 932.335 348.642 12.952 + vertex 932.15 344.424 14.8246 + endloop + endfacet + facet normal 0.873426 0.165102 0.458114 + outer loop + vertex 932.15 344.424 14.8246 + vertex 932.335 348.642 12.952 + vertex 931.19 349.446 14.8449 + endloop + endfacet + facet normal 0.869862 0.145933 0.471215 + outer loop + vertex 934.202 338.348 12.8757 + vertex 933.312 343.533 12.9125 + vertex 932.999 339.35 14.7859 + endloop + endfacet + facet normal 0.873953 0.142665 0.4646 + outer loop + vertex 932.999 339.35 14.7859 + vertex 933.312 343.533 12.9125 + vertex 932.15 344.424 14.8246 + endloop + endfacet + facet normal 0.775815 0.125073 0.61844 + outer loop + vertex 932.999 339.35 14.7859 + vertex 932.15 344.424 14.8246 + vertex 931.625 340.273 16.3226 + endloop + endfacet + facet normal 0.775095 0.125461 0.619263 + outer loop + vertex 931.625 340.273 16.3226 + vertex 932.15 344.424 14.8246 + vertex 930.804 345.263 16.3391 + endloop + endfacet + facet normal 0.778325 0.146307 0.610577 + outer loop + vertex 932.15 344.424 14.8246 + vertex 931.19 349.446 14.8449 + vertex 930.804 345.263 16.3391 + endloop + endfacet + facet normal 0.778945 0.145994 0.609861 + outer loop + vertex 930.804 345.263 16.3391 + vertex 931.19 349.446 14.8449 + vertex 929.868 350.234 16.3453 + endloop + endfacet + facet normal 0.97307 0.197828 -0.118316 + outer loop + vertex 933.217 346.566 9.07979 + vertex 932.817 348.613 9.20953 + vertex 933.319 346.764 10.2444 + endloop + endfacet + facet normal 0.972844 0.212034 -0.0928256 + outer loop + vertex 933.319 346.764 10.2444 + vertex 932.817 348.613 9.20953 + vertex 932.762 349.286 10.174 + endloop + endfacet + facet normal 0.975503 0.186545 -0.116599 + outer loop + vertex 933.685 344.086 9.02124 + vertex 933.217 346.566 9.07979 + vertex 933.791 344.275 10.2107 + endloop + endfacet + facet normal 0.975503 0.186539 -0.11661 + outer loop + vertex 933.791 344.275 10.2107 + vertex 933.217 346.566 9.07979 + vertex 933.319 346.764 10.2444 + endloop + endfacet + facet normal 0.980062 0.184844 0.0728785 + outer loop + vertex 933.791 344.275 10.2107 + vertex 933.319 346.764 10.2444 + vertex 933.622 344.735 11.3092 + endloop + endfacet + facet normal 0.973367 0.202245 0.107947 + outer loop + vertex 933.622 344.735 11.3092 + vertex 933.319 346.764 10.2444 + vertex 933.096 347.149 11.5342 + endloop + endfacet + facet normal 0.970709 0.217027 0.103073 + outer loop + vertex 933.319 346.764 10.2444 + vertex 932.762 349.286 10.174 + vertex 933.096 347.149 11.5342 + endloop + endfacet + facet normal 0.979522 0.191792 0.061265 + outer loop + vertex 933.096 347.149 11.5342 + vertex 932.762 349.286 10.174 + vertex 932.577 349.869 11.3116 + endloop + endfacet + facet normal 0.977011 0.179483 -0.115048 + outer loop + vertex 934.16 341.495 9.01612 + vertex 933.685 344.086 9.02124 + vertex 934.262 341.692 10.1933 + endloop + endfacet + facet normal 0.976997 0.179225 -0.115568 + outer loop + vertex 934.262 341.692 10.1933 + vertex 933.685 344.086 9.02124 + vertex 933.791 344.275 10.2107 + endloop + endfacet + facet normal 0.979217 0.17107 -0.108945 + outer loop + vertex 934.61 338.923 9.02264 + vertex 934.16 341.495 9.01612 + vertex 934.709 339.1 10.1896 + endloop + endfacet + facet normal 0.979093 0.168835 -0.11345 + outer loop + vertex 934.709 339.1 10.1896 + vertex 934.16 341.495 9.01612 + vertex 934.262 341.692 10.1933 + endloop + endfacet + facet normal 0.98229 0.169107 0.080678 + outer loop + vertex 934.709 339.1 10.1896 + vertex 934.262 341.692 10.1933 + vertex 934.544 339.543 11.2731 + endloop + endfacet + facet normal 0.977093 0.182715 0.109111 + outer loop + vertex 934.544 339.543 11.2731 + vertex 934.262 341.692 10.1933 + vertex 934.059 341.999 11.4969 + endloop + endfacet + facet normal 0.977848 0.177853 0.110374 + outer loop + vertex 934.262 341.692 10.1933 + vertex 933.791 344.275 10.2107 + vertex 934.059 341.999 11.4969 + endloop + endfacet + facet normal 0.983198 0.162786 0.0825978 + outer loop + vertex 934.059 341.999 11.4969 + vertex 933.791 344.275 10.2107 + vertex 933.622 344.735 11.3092 + endloop + endfacet + facet normal 0.935964 0.155774 0.315764 + outer loop + vertex 934.544 339.543 11.2731 + vertex 934.059 341.999 11.4969 + vertex 934.202 338.348 12.8757 + endloop + endfacet + facet normal 0.935634 0.170715 0.308942 + outer loop + vertex 933.622 344.735 11.3092 + vertex 933.312 343.533 12.9125 + vertex 934.059 341.999 11.4969 + endloop + endfacet + facet normal 0.933574 0.157927 0.321713 + outer loop + vertex 933.312 343.533 12.9125 + vertex 934.202 338.348 12.8757 + vertex 934.059 341.999 11.4969 + endloop + endfacet + facet normal 0.934019 0.174681 0.311602 + outer loop + vertex 933.622 344.735 11.3092 + vertex 933.096 347.149 11.5342 + vertex 933.312 343.533 12.9125 + endloop + endfacet + facet normal 0.935696 0.202094 0.28919 + outer loop + vertex 932.577 349.869 11.3116 + vertex 932.335 348.642 12.952 + vertex 933.096 347.149 11.5342 + endloop + endfacet + facet normal 0.932615 0.175925 0.315087 + outer loop + vertex 932.335 348.642 12.952 + vertex 933.312 343.533 12.9125 + vertex 933.096 347.149 11.5342 + endloop + endfacet + facet normal 0.637232 0.114599 -0.762104 + outer loop + vertex 930.299 346.616 4.97765 + vertex 930.023 348.998 5.10536 + vertex 931.403 346.648 5.90601 + endloop + endfacet + facet normal 0.658922 0.134865 -0.740023 + outer loop + vertex 931.403 346.648 5.90601 + vertex 930.023 348.998 5.10536 + vertex 930.873 349.237 5.90524 + endloop + endfacet + facet normal 0.647753 0.132382 -0.750261 + outer loop + vertex 931.045 343.83 5.12992 + vertex 930.299 346.616 4.97765 + vertex 931.917 344.042 5.92076 + endloop + endfacet + facet normal 0.636612 0.121223 -0.761597 + outer loop + vertex 931.917 344.042 5.92076 + vertex 930.299 346.616 4.97765 + vertex 931.403 346.648 5.90601 + endloop + endfacet + facet normal 0.757847 0.14584 -0.635923 + outer loop + vertex 931.917 344.042 5.92076 + vertex 931.403 346.648 5.90601 + vertex 932.712 344.083 6.8776 + endloop + endfacet + facet normal 0.758585 0.146618 -0.634864 + outer loop + vertex 932.712 344.083 6.8776 + vertex 931.403 346.648 5.90601 + vertex 932.203 346.694 6.87172 + endloop + endfacet + facet normal 0.757392 0.155083 -0.634277 + outer loop + vertex 931.403 346.648 5.90601 + vertex 930.873 349.237 5.90524 + vertex 932.203 346.694 6.87172 + endloop + endfacet + facet normal 0.766071 0.164541 -0.621338 + outer loop + vertex 932.203 346.694 6.87172 + vertex 930.873 349.237 5.90524 + vertex 931.696 349.246 6.92281 + endloop + endfacet + facet normal 0.63536 0.103196 -0.76529 + outer loop + vertex 931.255 341.493 4.98938 + vertex 931.045 343.83 5.12992 + vertex 932.393 341.468 5.93042 + endloop + endfacet + facet normal 0.651066 0.117378 -0.749891 + outer loop + vertex 932.393 341.468 5.93042 + vertex 931.045 343.83 5.12992 + vertex 931.917 344.042 5.92076 + endloop + endfacet + facet normal 0.649218 0.123238 -0.750552 + outer loop + vertex 931.932 338.768 5.12746 + vertex 931.255 341.493 4.98938 + vertex 932.828 338.943 5.93137 + endloop + endfacet + facet normal 0.635025 0.109243 -0.764728 + outer loop + vertex 932.828 338.943 5.93137 + vertex 931.255 341.493 4.98938 + vertex 932.393 341.468 5.93042 + endloop + endfacet + facet normal 0.760742 0.130975 -0.635703 + outer loop + vertex 932.828 338.943 5.93137 + vertex 932.393 341.468 5.93042 + vertex 933.638 338.953 6.90257 + endloop + endfacet + facet normal 0.760136 0.130345 -0.636556 + outer loop + vertex 933.638 338.953 6.90257 + vertex 932.393 341.468 5.93042 + vertex 933.196 341.491 6.89421 + endloop + endfacet + facet normal 0.759277 0.137783 -0.636015 + outer loop + vertex 932.393 341.468 5.93042 + vertex 931.917 344.042 5.92076 + vertex 933.196 341.491 6.89421 + endloop + endfacet + facet normal 0.758949 0.137441 -0.63648 + outer loop + vertex 933.196 341.491 6.89421 + vertex 931.917 344.042 5.92076 + vertex 932.712 344.083 6.8776 + endloop + endfacet + facet normal 0.855832 0.156427 -0.493033 + outer loop + vertex 933.196 341.491 6.89421 + vertex 932.712 344.083 6.8776 + vertex 933.79 341.468 7.91869 + endloop + endfacet + facet normal 0.856203 0.156895 -0.49224 + outer loop + vertex 933.79 341.468 7.91869 + vertex 932.712 344.083 6.8776 + vertex 933.308 344.066 7.90764 + endloop + endfacet + facet normal 0.856867 0.147669 -0.493936 + outer loop + vertex 933.638 338.953 6.90257 + vertex 933.196 341.491 6.89421 + vertex 934.237 338.915 7.93031 + endloop + endfacet + facet normal 0.856906 0.147718 -0.493853 + outer loop + vertex 934.237 338.915 7.93031 + vertex 933.196 341.491 6.89421 + vertex 933.79 341.468 7.91869 + endloop + endfacet + facet normal 0.933474 0.161909 -0.320019 + outer loop + vertex 934.237 338.915 7.93031 + vertex 933.79 341.468 7.91869 + vertex 934.61 338.923 9.02264 + endloop + endfacet + facet normal 0.933809 0.162593 -0.31869 + outer loop + vertex 934.61 338.923 9.02264 + vertex 933.79 341.468 7.91869 + vertex 934.16 341.495 9.01612 + endloop + endfacet + facet normal 0.932265 0.171758 -0.318403 + outer loop + vertex 933.79 341.468 7.91869 + vertex 933.308 344.066 7.90764 + vertex 934.16 341.495 9.01612 + endloop + endfacet + facet normal 0.932222 0.171668 -0.318578 + outer loop + vertex 934.16 341.495 9.01612 + vertex 933.308 344.066 7.90764 + vertex 933.685 344.086 9.02124 + endloop + endfacet + facet normal 0.85636 0.179721 -0.484095 + outer loop + vertex 932.203 346.694 6.87172 + vertex 931.696 349.246 6.92281 + vertex 932.818 346.637 7.93881 + endloop + endfacet + facet normal 0.866892 0.19393 -0.459228 + outer loop + vertex 932.818 346.637 7.93881 + vertex 931.696 349.246 6.92281 + vertex 932.361 349.052 8.09619 + endloop + endfacet + facet normal 0.85501 0.165759 -0.491408 + outer loop + vertex 932.712 344.083 6.8776 + vertex 932.203 346.694 6.87172 + vertex 933.308 344.066 7.90764 + endloop + endfacet + facet normal 0.857729 0.169254 -0.485442 + outer loop + vertex 933.308 344.066 7.90764 + vertex 932.203 346.694 6.87172 + vertex 932.818 346.637 7.93881 + endloop + endfacet + facet normal 0.93057 0.1811 -0.318185 + outer loop + vertex 933.308 344.066 7.90764 + vertex 932.818 346.637 7.93881 + vertex 933.685 344.086 9.02124 + endloop + endfacet + facet normal 0.931434 0.182915 -0.314599 + outer loop + vertex 933.685 344.086 9.02124 + vertex 932.818 346.637 7.93881 + vertex 933.217 346.566 9.07979 + endloop + endfacet + facet normal 0.929261 0.196202 -0.313017 + outer loop + vertex 932.818 346.637 7.93881 + vertex 932.361 349.052 8.09619 + vertex 933.217 346.566 9.07979 + endloop + endfacet + facet normal 0.931769 0.201398 -0.302069 + outer loop + vertex 933.217 346.566 9.07979 + vertex 932.361 349.052 8.09619 + vertex 932.817 348.613 9.20953 + endloop + endfacet + facet normal 0.404304 0.0771625 -0.911364 + outer loop + vertex 926.414 345.285 2.91079 + vertex 925.462 350.295 2.91272 + vertex 928.988 345.506 4.07143 + endloop + endfacet + facet normal 0.408051 0.0803936 -0.909412 + outer loop + vertex 928.988 345.506 4.07143 + vertex 925.462 350.295 2.91272 + vertex 927.976 350.582 4.06611 + endloop + endfacet + facet normal 0.402698 0.069799 -0.912668 + outer loop + vertex 927.265 340.299 2.90495 + vertex 926.414 345.285 2.91079 + vertex 929.88 340.466 4.07166 + endloop + endfacet + facet normal 0.404871 0.0716277 -0.911564 + outer loop + vertex 929.88 340.466 4.07166 + vertex 926.414 345.285 2.91079 + vertex 928.988 345.506 4.07143 + endloop + endfacet + facet normal 0.517136 0.0976689 -0.850313 + outer loop + vertex 931.045 343.83 5.12992 + vertex 931.255 341.493 4.98938 + vertex 928.988 345.506 4.07143 + endloop + endfacet + facet normal 0.509473 0.0831563 -0.856459 + outer loop + vertex 931.932 338.768 5.12746 + vertex 929.88 340.466 4.07166 + vertex 931.255 341.493 4.98938 + endloop + endfacet + facet normal 0.505778 0.0894925 -0.858009 + outer loop + vertex 929.88 340.466 4.07166 + vertex 928.988 345.506 4.07143 + vertex 931.255 341.493 4.98938 + endloop + endfacet + facet normal 0.513543 0.105085 -0.851605 + outer loop + vertex 930.023 348.998 5.10536 + vertex 930.299 346.616 4.97765 + vertex 927.976 350.582 4.06611 + endloop + endfacet + facet normal 0.513103 0.0906955 -0.853522 + outer loop + vertex 931.045 343.83 5.12992 + vertex 928.988 345.506 4.07143 + vertex 930.299 346.616 4.97765 + endloop + endfacet + facet normal 0.506919 0.100159 -0.856155 + outer loop + vertex 928.988 345.506 4.07143 + vertex 927.976 350.582 4.06611 + vertex 930.299 346.616 4.97765 + endloop + endfacet + facet normal 0.18776 0.0261921 -0.981866 + outer loop + vertex 920.388 345.045 1.41137 + vertex 920.155 349.566 1.4875 + vertex 923.645 345.079 2.03509 + endloop + endfacet + facet normal 0.202668 0.038195 -0.978502 + outer loop + vertex 923.645 345.079 2.03509 + vertex 920.155 349.566 1.4875 + vertex 922.736 350.039 2.04043 + endloop + endfacet + facet normal 0.195377 0.0372142 -0.980022 + outer loop + vertex 921.784 339.733 1.48795 + vertex 920.388 345.045 1.41137 + vertex 924.453 340.133 2.03516 + endloop + endfacet + facet normal 0.187691 0.0306352 -0.98175 + outer loop + vertex 924.453 340.133 2.03516 + vertex 920.388 345.045 1.41137 + vertex 923.645 345.079 2.03509 + endloop + endfacet + facet normal 0.292586 0.0477642 -0.955046 + outer loop + vertex 924.453 340.133 2.03516 + vertex 923.645 345.079 2.03509 + vertex 927.265 340.299 2.90495 + endloop + endfacet + facet normal 0.297641 0.0519161 -0.953265 + outer loop + vertex 927.265 340.299 2.90495 + vertex 923.645 345.079 2.03509 + vertex 926.414 345.285 2.91079 + endloop + endfacet + facet normal 0.297338 0.055517 -0.953157 + outer loop + vertex 923.645 345.079 2.03509 + vertex 922.736 350.039 2.04043 + vertex 926.414 345.285 2.91079 + endloop + endfacet + facet normal 0.299398 0.0572478 -0.952409 + outer loop + vertex 926.414 345.285 2.91079 + vertex 922.736 350.039 2.04043 + vertex 925.462 350.295 2.91272 + endloop + endfacet + facet normal 0.121066 0.0229383 -0.992379 + outer loop + vertex 920.155 349.566 1.4875 + vertex 920.388 345.045 1.41137 + vertex 915.191 352.725 0.954875 + endloop + endfacet + facet normal 0.116719 0.0163568 -0.99303 + outer loop + vertex 921.784 339.733 1.48795 + vertex 916.815 342.975 0.957285 + vertex 920.388 345.045 1.41137 + endloop + endfacet + facet normal 0.115235 0.0189464 -0.993158 + outer loop + vertex 916.815 342.975 0.957285 + vertex 915.191 352.725 0.954875 + vertex 920.388 345.045 1.41137 + endloop + endfacet + facet normal 0.908138 0.144 0.393128 + outer loop + vertex 902.64 361.282 27.1246 + vertex 901.93 365.714 27.1422 + vertex 901.755 361.925 28.9338 + endloop + endfacet + facet normal 0.90713 0.144975 0.395091 + outer loop + vertex 901.755 361.925 28.9338 + vertex 901.93 365.714 27.1422 + vertex 901.024 366.41 28.9672 + endloop + endfacet + facet normal 0.90839 0.128378 0.397927 + outer loop + vertex 903.266 356.896 27.1113 + vertex 902.64 361.282 27.1246 + vertex 902.381 357.537 28.9238 + endloop + endfacet + facet normal 0.908076 0.128695 0.398542 + outer loop + vertex 902.381 357.537 28.9238 + vertex 902.64 361.282 27.1246 + vertex 901.755 361.925 28.9338 + endloop + endfacet + facet normal 0.713721 0.113984 0.691094 + outer loop + vertex 904.795 360.575 24.4933 + vertex 904.066 365.032 24.5115 + vertex 903.605 360.922 25.665 + endloop + endfacet + facet normal 0.714597 0.113647 0.690243 + outer loop + vertex 903.605 360.922 25.665 + vertex 904.066 365.032 24.5115 + vertex 902.893 365.344 25.6742 + endloop + endfacet + facet normal 0.712228 0.0996375 0.694841 + outer loop + vertex 905.45 356.141 24.4579 + vertex 904.795 360.575 24.4933 + vertex 904.245 356.512 25.6402 + endloop + endfacet + facet normal 0.71271 0.0994406 0.694375 + outer loop + vertex 904.245 356.512 25.6402 + vertex 904.795 360.575 24.4933 + vertex 903.605 360.922 25.665 + endloop + endfacet + facet normal 0.385485 0.0631344 0.920552 + outer loop + vertex 908.208 359.255 22.8138 + vertex 907.201 363.577 22.9389 + vertex 906.302 359.998 23.561 + endloop + endfacet + facet normal 0.399535 0.0586123 0.914842 + outer loop + vertex 906.302 359.998 23.561 + vertex 907.201 363.577 22.9389 + vertex 905.566 364.494 23.5942 + endloop + endfacet + facet normal 0.394439 0.0437454 0.91788 + outer loop + vertex 908.594 354.451 22.8766 + vertex 908.208 359.255 22.8138 + vertex 906.965 355.523 23.5256 + endloop + endfacet + facet normal 0.381105 0.0492027 0.923222 + outer loop + vertex 906.965 355.523 23.5256 + vertex 908.208 359.255 22.8138 + vertex 906.302 359.998 23.561 + endloop + endfacet + facet normal 0.544291 0.0740867 0.835618 + outer loop + vertex 906.965 355.523 23.5256 + vertex 906.302 359.998 23.561 + vertex 905.45 356.141 24.4579 + endloop + endfacet + facet normal 0.545014 0.0738231 0.835171 + outer loop + vertex 905.45 356.141 24.4579 + vertex 906.302 359.998 23.561 + vertex 904.795 360.575 24.4933 + endloop + endfacet + facet normal 0.547222 0.0833865 0.832824 + outer loop + vertex 906.302 359.998 23.561 + vertex 905.566 364.494 23.5942 + vertex 904.795 360.575 24.4933 + endloop + endfacet + facet normal 0.541726 0.0852472 0.836221 + outer loop + vertex 904.795 360.575 24.4933 + vertex 905.566 364.494 23.5942 + vertex 904.066 365.032 24.5115 + endloop + endfacet + facet normal 0.279244 0.0372601 0.959497 + outer loop + vertex 907.201 363.577 22.9389 + vertex 908.208 359.255 22.8138 + vertex 909.303 365.682 22.2455 + endloop + endfacet + facet normal 0.271852 0.0344556 0.961722 + outer loop + vertex 908.594 354.451 22.8766 + vertex 910.806 356.251 22.1869 + vertex 908.208 359.255 22.8138 + endloop + endfacet + facet normal 0.275621 0.0379677 0.960516 + outer loop + vertex 910.806 356.251 22.1869 + vertex 909.303 365.682 22.2455 + vertex 908.208 359.255 22.8138 + endloop + endfacet + facet normal 0.659154 0.15013 0.73687 + outer loop + vertex 928.823 355.193 16.3389 + vertex 927.698 360.14 16.3373 + vertex 927.362 356.028 17.4755 + endloop + endfacet + facet normal 0.665239 0.148221 0.73177 + outer loop + vertex 927.362 356.028 17.4755 + vertex 927.698 360.14 16.3373 + vertex 926.273 360.927 17.4728 + endloop + endfacet + facet normal 0.643837 0.136687 0.752855 + outer loop + vertex 929.868 350.234 16.3453 + vertex 928.823 355.193 16.3389 + vertex 928.364 351.11 17.4726 + endloop + endfacet + facet normal 0.654858 0.132978 0.743961 + outer loop + vertex 928.364 351.11 17.4726 + vertex 928.823 355.193 16.3389 + vertex 927.362 356.028 17.4755 + endloop + endfacet + facet normal 0.502498 0.10187 0.858556 + outer loop + vertex 928.364 351.11 17.4726 + vertex 927.362 356.028 17.4755 + vertex 926.812 352.235 18.2472 + endloop + endfacet + facet normal 0.494257 0.103983 0.863074 + outer loop + vertex 926.812 352.235 18.2472 + vertex 927.362 356.028 17.4755 + vertex 925.607 356.871 18.3788 + endloop + endfacet + facet normal 0.49644 0.110784 0.860973 + outer loop + vertex 927.362 356.028 17.4755 + vertex 926.273 360.927 17.4728 + vertex 925.607 356.871 18.3788 + endloop + endfacet + facet normal 0.522396 0.103273 0.846426 + outer loop + vertex 925.607 356.871 18.3788 + vertex 926.273 360.927 17.4728 + vertex 924.781 362.012 18.2613 + endloop + endfacet + facet normal 0.875544 0.208345 0.435907 + outer loop + vertex 931.242 353.672 12.962 + vertex 930.065 358.639 12.9527 + vertex 930.122 354.434 14.8472 + endloop + endfacet + facet normal 0.880891 0.20437 0.426924 + outer loop + vertex 930.122 354.434 14.8472 + vertex 930.065 358.639 12.9527 + vertex 928.965 359.421 14.8478 + endloop + endfacet + facet normal 0.873745 0.188916 0.448197 + outer loop + vertex 932.335 348.642 12.952 + vertex 931.242 353.672 12.962 + vertex 931.19 349.446 14.8449 + endloop + endfacet + facet normal 0.875911 0.187301 0.444633 + outer loop + vertex 931.19 349.446 14.8449 + vertex 931.242 353.672 12.962 + vertex 930.122 354.434 14.8472 + endloop + endfacet + facet normal 0.781535 0.167024 0.601088 + outer loop + vertex 931.19 349.446 14.8449 + vertex 930.122 354.434 14.8472 + vertex 929.868 350.234 16.3453 + endloop + endfacet + facet normal 0.783728 0.165975 0.598518 + outer loop + vertex 929.868 350.234 16.3453 + vertex 930.122 354.434 14.8472 + vertex 928.823 355.193 16.3389 + endloop + endfacet + facet normal 0.785324 0.182174 0.591674 + outer loop + vertex 930.122 354.434 14.8472 + vertex 928.965 359.421 14.8478 + vertex 928.823 355.193 16.3389 + endloop + endfacet + facet normal 0.790301 0.179904 0.585712 + outer loop + vertex 928.823 355.193 16.3389 + vertex 928.965 359.421 14.8478 + vertex 927.698 360.14 16.3373 + endloop + endfacet + facet normal 0.953355 0.2284 -0.19735 + outer loop + vertex 930.704 356.739 8.64103 + vertex 930.122 359.193 8.67127 + vertex 930.947 356.964 10.0752 + endloop + endfacet + facet normal 0.953748 0.233961 -0.188751 + outer loop + vertex 930.947 356.964 10.0752 + vertex 930.122 359.193 8.67127 + vertex 930.359 359.37 10.0889 + endloop + endfacet + facet normal 0.952838 0.225246 -0.203381 + outer loop + vertex 931.298 354.218 8.63208 + vertex 930.704 356.739 8.64103 + vertex 931.541 354.498 10.0787 + endloop + endfacet + facet normal 0.953151 0.229175 -0.197437 + outer loop + vertex 931.541 354.498 10.0787 + vertex 930.704 356.739 8.64103 + vertex 930.947 356.964 10.0752 + endloop + endfacet + facet normal 0.972182 0.234053 0.0090669 + outer loop + vertex 931.541 354.498 10.0787 + vertex 930.947 356.964 10.0752 + vertex 931.426 354.928 11.3072 + endloop + endfacet + facet normal 0.967074 0.25138 0.0396902 + outer loop + vertex 931.426 354.928 11.3072 + vertex 930.947 356.964 10.0752 + vertex 930.818 357.231 11.5165 + endloop + endfacet + facet normal 0.970629 0.236759 0.0427151 + outer loop + vertex 930.947 356.964 10.0752 + vertex 930.359 359.37 10.0889 + vertex 930.818 357.231 11.5165 + endloop + endfacet + facet normal 0.97379 0.226006 0.0255852 + outer loop + vertex 930.818 357.231 11.5165 + vertex 930.359 359.37 10.0889 + vertex 930.227 359.805 11.2927 + endloop + endfacet + facet normal 0.954369 0.226965 -0.194079 + outer loop + vertex 931.985 351.314 8.61443 + vertex 931.298 354.218 8.63208 + vertex 932.139 351.922 10.0822 + endloop + endfacet + facet normal 0.953891 0.221286 -0.20279 + outer loop + vertex 932.139 351.922 10.0822 + vertex 931.298 354.218 8.63208 + vertex 931.541 354.498 10.0787 + endloop + endfacet + facet normal 0.955212 0.265328 -0.131037 + outer loop + vertex 932.817 348.613 9.20953 + vertex 931.985 351.314 8.61443 + vertex 932.762 349.286 10.174 + endloop + endfacet + facet normal 0.956666 0.219571 -0.191257 + outer loop + vertex 932.762 349.286 10.174 + vertex 931.985 351.314 8.61443 + vertex 932.139 351.922 10.0822 + endloop + endfacet + facet normal 0.972075 0.231261 0.0398475 + outer loop + vertex 932.762 349.286 10.174 + vertex 932.139 351.922 10.0822 + vertex 932.577 349.869 11.3116 + endloop + endfacet + facet normal 0.971703 0.23245 0.041965 + outer loop + vertex 932.577 349.869 11.3116 + vertex 932.139 351.922 10.0822 + vertex 931.994 352.267 11.5279 + endloop + endfacet + facet normal 0.973128 0.226093 0.0436237 + outer loop + vertex 932.139 351.922 10.0822 + vertex 931.541 354.498 10.0787 + vertex 931.994 352.267 11.5279 + endloop + endfacet + facet normal 0.977483 0.210257 0.0178823 + outer loop + vertex 931.994 352.267 11.5279 + vertex 931.541 354.498 10.0787 + vertex 931.426 354.928 11.3072 + endloop + endfacet + facet normal 0.935949 0.201502 0.288784 + outer loop + vertex 932.577 349.869 11.3116 + vertex 931.994 352.267 11.5279 + vertex 932.335 348.642 12.952 + endloop + endfacet + facet normal 0.936042 0.22253 0.272591 + outer loop + vertex 931.426 354.928 11.3072 + vertex 931.242 353.672 12.962 + vertex 931.994 352.267 11.5279 + endloop + endfacet + facet normal 0.934861 0.202504 0.291594 + outer loop + vertex 931.242 353.672 12.962 + vertex 932.335 348.642 12.952 + vertex 931.994 352.267 11.5279 + endloop + endfacet + facet normal 0.936226 0.222116 0.272298 + outer loop + vertex 931.426 354.928 11.3072 + vertex 930.818 357.231 11.5165 + vertex 931.242 353.672 12.962 + endloop + endfacet + facet normal 0.936402 0.237632 0.25823 + outer loop + vertex 930.227 359.805 11.2927 + vertex 930.065 358.639 12.9527 + vertex 930.818 357.231 11.5165 + endloop + endfacet + facet normal 0.93597 0.222361 0.272976 + outer loop + vertex 930.065 358.639 12.9527 + vertex 931.242 353.672 12.962 + vertex 930.818 357.231 11.5165 + endloop + endfacet + facet normal 0.673336 0.143414 -0.725294 + outer loop + vertex 928.159 356.619 4.96112 + vertex 927.822 358.857 5.09034 + vertex 929.3 356.592 6.01508 + endloop + endfacet + facet normal 0.692215 0.165018 -0.702572 + outer loop + vertex 929.3 356.592 6.01508 + vertex 927.822 358.857 5.09034 + vertex 928.694 359.088 6.00442 + endloop + endfacet + facet normal 0.678091 0.16487 -0.716248 + outer loop + vertex 928.95 354.017 5.11133 + vertex 928.159 356.619 4.96112 + vertex 929.835 354.196 5.99031 + endloop + endfacet + facet normal 0.672048 0.15759 -0.723545 + outer loop + vertex 929.835 354.196 5.99031 + vertex 928.159 356.619 4.96112 + vertex 929.3 356.592 6.01508 + endloop + endfacet + facet normal 0.806066 0.185854 -0.561887 + outer loop + vertex 929.835 354.196 5.99031 + vertex 929.3 356.592 6.01508 + vertex 930.7 354.149 7.21613 + endloop + endfacet + facet normal 0.809796 0.191602 -0.554544 + outer loop + vertex 930.7 354.149 7.21613 + vertex 929.3 356.592 6.01508 + vertex 930.132 356.636 7.24461 + endloop + endfacet + facet normal 0.80935 0.194082 -0.554332 + outer loop + vertex 929.3 356.592 6.01508 + vertex 928.694 359.088 6.00442 + vertex 930.132 356.636 7.24461 + endloop + endfacet + facet normal 0.810233 0.195506 -0.55254 + outer loop + vertex 930.132 356.636 7.24461 + vertex 928.694 359.088 6.00442 + vertex 929.536 359.15 7.26048 + endloop + endfacet + facet normal 0.651759 0.131413 -0.746954 + outer loop + vertex 929.239 351.734 4.96116 + vertex 928.95 354.017 5.11133 + vertex 930.352 351.76 5.93716 + endloop + endfacet + facet normal 0.679234 0.159675 -0.716342 + outer loop + vertex 930.352 351.76 5.93716 + vertex 928.95 354.017 5.11133 + vertex 929.835 354.196 5.99031 + endloop + endfacet + facet normal 0.655377 0.148958 -0.740468 + outer loop + vertex 930.023 348.998 5.10536 + vertex 929.239 351.734 4.96116 + vertex 930.873 349.237 5.90524 + endloop + endfacet + facet normal 0.650468 0.143725 -0.745811 + outer loop + vertex 930.873 349.237 5.90524 + vertex 929.239 351.734 4.96116 + vertex 930.352 351.76 5.93716 + endloop + endfacet + facet normal 0.765877 0.165976 -0.621196 + outer loop + vertex 930.873 349.237 5.90524 + vertex 930.352 351.76 5.93716 + vertex 931.696 349.246 6.92281 + endloop + endfacet + facet normal 0.789404 0.193732 -0.582503 + outer loop + vertex 931.696 349.246 6.92281 + vertex 930.352 351.76 5.93716 + vertex 931.213 351.69 7.08102 + endloop + endfacet + facet normal 0.791034 0.180508 -0.584535 + outer loop + vertex 930.352 351.76 5.93716 + vertex 929.835 354.196 5.99031 + vertex 931.213 351.69 7.08102 + endloop + endfacet + facet normal 0.80428 0.198406 -0.560151 + outer loop + vertex 931.213 351.69 7.08102 + vertex 929.835 354.196 5.99031 + vertex 930.7 354.149 7.21613 + endloop + endfacet + facet normal 0.889823 0.237246 -0.389781 + outer loop + vertex 931.213 351.69 7.08102 + vertex 931.985 351.314 8.61443 + vertex 932.361 349.052 8.09619 + endloop + endfacet + facet normal 0.866149 0.200818 -0.457667 + outer loop + vertex 931.696 349.246 6.92281 + vertex 931.213 351.69 7.08102 + vertex 932.361 349.052 8.09619 + endloop + endfacet + facet normal 0.929944 0.221805 -0.29327 + outer loop + vertex 932.817 348.613 9.20953 + vertex 932.361 349.052 8.09619 + vertex 931.985 351.314 8.61443 + endloop + endfacet + facet normal 0.896143 0.214372 -0.388551 + outer loop + vertex 931.298 354.218 8.63208 + vertex 931.985 351.314 8.61443 + vertex 930.7 354.149 7.21613 + endloop + endfacet + facet normal 0.893197 0.208065 -0.398632 + outer loop + vertex 930.7 354.149 7.21613 + vertex 931.985 351.314 8.61443 + vertex 931.213 351.69 7.08102 + endloop + endfacet + facet normal 0.897162 0.209689 -0.388756 + outer loop + vertex 930.7 354.149 7.21613 + vertex 930.132 356.636 7.24461 + vertex 931.298 354.218 8.63208 + endloop + endfacet + facet normal 0.898439 0.213068 -0.383939 + outer loop + vertex 931.298 354.218 8.63208 + vertex 930.132 356.636 7.24461 + vertex 930.704 356.739 8.64103 + endloop + endfacet + facet normal 0.89887 0.21774 -0.380292 + outer loop + vertex 930.122 359.193 8.67127 + vertex 930.704 356.739 8.64103 + vertex 929.536 359.15 7.26048 + endloop + endfacet + facet normal 0.897943 0.215228 -0.383895 + outer loop + vertex 929.536 359.15 7.26048 + vertex 930.704 356.739 8.64103 + vertex 930.132 356.636 7.24461 + endloop + endfacet + facet normal 0.406438 0.0913055 -0.909105 + outer loop + vertex 924.425 355.283 2.91275 + vertex 923.302 360.214 2.90596 + vertex 926.899 355.565 4.04726 + endloop + endfacet + facet normal 0.40277 0.0879869 -0.911062 + outer loop + vertex 926.899 355.565 4.04726 + vertex 923.302 360.214 2.90596 + vertex 925.703 360.461 3.99125 + endloop + endfacet + facet normal 0.407491 0.0847279 -0.90927 + outer loop + vertex 925.462 350.295 2.91272 + vertex 924.425 355.283 2.91275 + vertex 927.976 350.582 4.06611 + endloop + endfacet + facet normal 0.407322 0.0845779 -0.90936 + outer loop + vertex 927.976 350.582 4.06611 + vertex 924.425 355.283 2.91275 + vertex 926.899 355.565 4.04726 + endloop + endfacet + facet normal 0.527987 0.121936 -0.840453 + outer loop + vertex 928.95 354.017 5.11133 + vertex 929.239 351.734 4.96116 + vertex 926.899 355.565 4.04726 + endloop + endfacet + facet normal 0.511769 0.101832 -0.853067 + outer loop + vertex 930.023 348.998 5.10536 + vertex 927.976 350.582 4.06611 + vertex 929.239 351.734 4.96116 + endloop + endfacet + facet normal 0.508403 0.106628 -0.854492 + outer loop + vertex 927.976 350.582 4.06611 + vertex 926.899 355.565 4.04726 + vertex 929.239 351.734 4.96116 + endloop + endfacet + facet normal 0.531576 0.128497 -0.837207 + outer loop + vertex 927.822 358.857 5.09034 + vertex 928.159 356.619 4.96112 + vertex 925.703 360.461 3.99125 + endloop + endfacet + facet normal 0.521732 0.109827 -0.846011 + outer loop + vertex 928.95 354.017 5.11133 + vertex 926.899 355.565 4.04726 + vertex 928.159 356.619 4.96112 + endloop + endfacet + facet normal 0.517296 0.116693 -0.847813 + outer loop + vertex 926.899 355.565 4.04726 + vertex 925.703 360.461 3.99125 + vertex 928.159 356.619 4.96112 + endloop + endfacet + facet normal 0.195841 0.0363254 -0.979963 + outer loop + vertex 918.58 354.885 1.41174 + vertex 918.177 359.432 1.49973 + vertex 921.741 355.005 2.04781 + endloop + endfacet + facet normal 0.208273 0.0467058 -0.976955 + outer loop + vertex 921.741 355.005 2.04781 + vertex 918.177 359.432 1.49973 + vertex 920.672 359.952 2.05637 + endloop + endfacet + facet normal 0.201292 0.0456762 -0.978466 + outer loop + vertex 920.155 349.566 1.4875 + vertex 918.58 354.885 1.41174 + vertex 922.736 350.039 2.04043 + endloop + endfacet + facet normal 0.195651 0.0406624 -0.97983 + outer loop + vertex 922.736 350.039 2.04043 + vertex 918.58 354.885 1.41174 + vertex 921.741 355.005 2.04781 + endloop + endfacet + facet normal 0.298976 0.0613271 -0.952288 + outer loop + vertex 922.736 350.039 2.04043 + vertex 921.741 355.005 2.04781 + vertex 925.462 350.295 2.91272 + endloop + endfacet + facet normal 0.300267 0.0624349 -0.95181 + outer loop + vertex 925.462 350.295 2.91272 + vertex 921.741 355.005 2.04781 + vertex 924.425 355.283 2.91275 + endloop + endfacet + facet normal 0.29981 0.0664466 -0.951682 + outer loop + vertex 921.741 355.005 2.04781 + vertex 920.672 359.952 2.05637 + vertex 924.425 355.283 2.91275 + endloop + endfacet + facet normal 0.300615 0.0671488 -0.951379 + outer loop + vertex 924.425 355.283 2.91275 + vertex 920.672 359.952 2.05637 + vertex 923.302 360.214 2.90596 + endloop + endfacet + facet normal 0.126489 0.0304016 -0.991502 + outer loop + vertex 918.177 359.432 1.49973 + vertex 918.58 354.885 1.41174 + vertex 913.246 362.489 0.964451 + endloop + endfacet + facet normal 0.120128 0.0214388 -0.992527 + outer loop + vertex 920.155 349.566 1.4875 + vertex 915.191 352.725 0.954875 + vertex 918.58 354.885 1.41174 + endloop + endfacet + facet normal 0.118191 0.0245114 -0.992688 + outer loop + vertex 915.191 352.725 0.954875 + vertex 913.246 362.489 0.964451 + vertex 918.58 354.885 1.41174 + endloop + endfacet + facet normal 0.90773 0.171705 0.38281 + outer loop + vertex 901.108 370.281 27.1955 + vertex 900.15 375.062 27.3218 + vertex 900.16 371.088 29.0813 + endloop + endfacet + facet normal 0.910541 0.169227 0.377196 + outer loop + vertex 900.16 371.088 29.0813 + vertex 900.15 375.062 27.3218 + vertex 899.122 376.035 29.3668 + endloop + endfacet + facet normal 0.907103 0.158719 0.389837 + outer loop + vertex 901.93 365.714 27.1422 + vertex 901.108 370.281 27.1955 + vertex 901.024 366.41 28.9672 + endloop + endfacet + facet normal 0.907729 0.158144 0.38861 + outer loop + vertex 901.024 366.41 28.9672 + vertex 901.108 370.281 27.1955 + vertex 900.16 371.088 29.0813 + endloop + endfacet + facet normal 0.716903 0.135587 0.683861 + outer loop + vertex 903.27 369.515 24.5261 + vertex 902.397 374.053 24.5418 + vertex 902.098 369.83 25.6923 + endloop + endfacet + facet normal 0.723185 0.133448 0.67764 + outer loop + vertex 902.098 369.83 25.6923 + vertex 902.397 374.053 24.5418 + vertex 901.2 374.443 25.7417 + endloop + endfacet + facet normal 0.715114 0.124693 0.687797 + outer loop + vertex 904.066 365.032 24.5115 + vertex 903.27 369.515 24.5261 + vertex 902.893 365.344 25.6742 + endloop + endfacet + facet normal 0.716456 0.124211 0.686485 + outer loop + vertex 902.893 365.344 25.6742 + vertex 903.27 369.515 24.5261 + vertex 902.098 369.83 25.6923 + endloop + endfacet + facet normal 0.386271 0.0760247 0.919247 + outer loop + vertex 906.653 368.398 22.8688 + vertex 905.519 372.712 22.9888 + vertex 904.758 369.014 23.6141 + endloop + endfacet + facet normal 0.395572 0.0734769 0.915491 + outer loop + vertex 904.758 369.014 23.6141 + vertex 905.519 372.712 22.9888 + vertex 903.882 373.564 23.6275 + endloop + endfacet + facet normal 0.399585 0.0587202 0.914814 + outer loop + vertex 907.201 363.577 22.9389 + vertex 906.653 368.398 22.8688 + vertex 905.566 364.494 23.5942 + endloop + endfacet + facet normal 0.383341 0.0644578 0.921355 + outer loop + vertex 905.566 364.494 23.5942 + vertex 906.653 368.398 22.8688 + vertex 904.758 369.014 23.6141 + endloop + endfacet + facet normal 0.543447 0.0934539 0.834225 + outer loop + vertex 905.566 364.494 23.5942 + vertex 904.758 369.014 23.6141 + vertex 904.066 365.032 24.5115 + endloop + endfacet + facet normal 0.542852 0.0936402 0.834592 + outer loop + vertex 904.066 365.032 24.5115 + vertex 904.758 369.014 23.6141 + vertex 903.27 369.515 24.5261 + endloop + endfacet + facet normal 0.544505 0.102401 0.832483 + outer loop + vertex 904.758 369.014 23.6141 + vertex 903.882 373.564 23.6275 + vertex 903.27 369.515 24.5261 + endloop + endfacet + facet normal 0.545552 0.102099 0.831834 + outer loop + vertex 903.27 369.515 24.5261 + vertex 903.882 373.564 23.6275 + vertex 902.397 374.053 24.5418 + endloop + endfacet + facet normal 0.281986 0.0475128 0.958241 + outer loop + vertex 905.519 372.712 22.9888 + vertex 906.653 368.398 22.8688 + vertex 907.519 374.952 22.289 + endloop + endfacet + facet normal 0.272147 0.0449121 0.961207 + outer loop + vertex 907.201 363.577 22.9389 + vertex 909.303 365.682 22.2455 + vertex 906.653 368.398 22.8688 + endloop + endfacet + facet normal 0.275575 0.0485203 0.960054 + outer loop + vertex 909.303 365.682 22.2455 + vertex 907.519 374.952 22.289 + vertex 906.653 368.398 22.8688 + endloop + endfacet + facet normal 0.675482 0.175723 0.716133 + outer loop + vertex 926.49 365.097 16.3421 + vertex 925.176 370.1 16.3533 + vertex 925.095 365.851 17.4724 + endloop + endfacet + facet normal 0.681453 0.174211 0.710826 + outer loop + vertex 925.095 365.851 17.4724 + vertex 925.176 370.1 16.3533 + vertex 923.791 370.868 17.493 + endloop + endfacet + facet normal 0.66832 0.162129 0.725991 + outer loop + vertex 927.698 360.14 16.3373 + vertex 926.49 365.097 16.3421 + vertex 926.273 360.927 17.4728 + endloop + endfacet + facet normal 0.672526 0.160927 0.722365 + outer loop + vertex 926.273 360.927 17.4728 + vertex 926.49 365.097 16.3421 + vertex 925.095 365.851 17.4724 + endloop + endfacet + facet normal 0.534499 0.12792 0.835432 + outer loop + vertex 926.273 360.927 17.4728 + vertex 925.095 365.851 17.4724 + vertex 924.781 362.012 18.2613 + endloop + endfacet + facet normal 0.523219 0.130231 0.842189 + outer loop + vertex 924.781 362.012 18.2613 + vertex 925.095 365.851 17.4724 + vertex 923.395 366.714 18.3955 + endloop + endfacet + facet normal 0.524015 0.132753 0.841299 + outer loop + vertex 925.095 365.851 17.4724 + vertex 923.791 370.868 17.493 + vertex 923.395 366.714 18.3955 + endloop + endfacet + facet normal 0.54657 0.127631 0.82763 + outer loop + vertex 923.395 366.714 18.3955 + vertex 923.791 370.868 17.493 + vertex 922.292 372.023 18.3046 + endloop + endfacet + facet normal 0.879618 0.237366 0.412225 + outer loop + vertex 928.794 363.71 12.9688 + vertex 927.346 369.05 12.9843 + vertex 927.707 364.469 14.8507 + endloop + endfacet + facet normal 0.884256 0.234357 0.403941 + outer loop + vertex 927.707 364.469 14.8507 + vertex 927.346 369.05 12.9843 + vertex 926.34 369.565 14.8875 + endloop + endfacet + facet normal 0.8804 0.219333 0.420464 + outer loop + vertex 930.065 358.639 12.9527 + vertex 928.794 363.71 12.9688 + vertex 928.965 359.421 14.8478 + endloop + endfacet + facet normal 0.880598 0.219191 0.420122 + outer loop + vertex 928.965 359.421 14.8478 + vertex 928.794 363.71 12.9688 + vertex 927.707 364.469 14.8507 + endloop + endfacet + facet normal 0.791523 0.196905 0.57855 + outer loop + vertex 928.965 359.421 14.8478 + vertex 927.707 364.469 14.8507 + vertex 927.698 360.14 16.3373 + endloop + endfacet + facet normal 0.798389 0.193969 0.570045 + outer loop + vertex 927.698 360.14 16.3373 + vertex 927.707 364.469 14.8507 + vertex 926.49 365.097 16.3421 + endloop + endfacet + facet normal 0.79886 0.210286 0.563563 + outer loop + vertex 927.707 364.469 14.8507 + vertex 926.34 369.565 14.8875 + vertex 926.49 365.097 16.3421 + endloop + endfacet + facet normal 0.801686 0.209203 0.559942 + outer loop + vertex 926.49 365.097 16.3421 + vertex 926.34 369.565 14.8875 + vertex 925.176 370.1 16.3533 + endloop + endfacet + facet normal 0.934193 0.285119 -0.214453 + outer loop + vertex 928.25 366.298 8.70913 + vertex 927.032 370.194 8.58638 + vertex 928.319 367.14 10.1311 + endloop + endfacet + facet normal 0.934441 0.287172 -0.210599 + outer loop + vertex 928.319 367.14 10.1311 + vertex 927.032 370.194 8.58638 + vertex 927.34 370.471 10.3306 + endloop + endfacet + facet normal 0.942643 0.294838 -0.156509 + outer loop + vertex 929.176 363.524 9.06205 + vertex 928.25 366.298 8.70913 + vertex 929.148 364.187 10.1455 + endloop + endfacet + facet normal 0.943103 0.263878 -0.202301 + outer loop + vertex 929.148 364.187 10.1455 + vertex 928.25 366.298 8.70913 + vertex 928.319 367.14 10.1311 + endloop + endfacet + facet normal 0.962659 0.270416 0.0127647 + outer loop + vertex 929.148 364.187 10.1455 + vertex 928.319 367.14 10.1311 + vertex 928.94 364.872 11.3266 + endloop + endfacet + facet normal 0.961563 0.273865 0.0198792 + outer loop + vertex 928.94 364.872 11.3266 + vertex 928.319 367.14 10.1311 + vertex 928.185 367.503 11.624 + endloop + endfacet + facet normal 0.959578 0.280866 0.0179989 + outer loop + vertex 928.319 367.14 10.1311 + vertex 927.34 370.471 10.3306 + vertex 928.185 367.503 11.624 + endloop + endfacet + facet normal 0.963243 0.268304 -0.0132232 + outer loop + vertex 928.185 367.503 11.624 + vertex 927.34 370.471 10.3306 + vertex 927.444 370.16 11.5774 + endloop + endfacet + facet normal 0.959382 0.223949 -0.171559 + outer loop + vertex 929.584 361.577 8.80095 + vertex 929.176 363.524 9.06205 + vertex 929.794 361.707 10.1471 + endloop + endfacet + facet normal 0.959739 0.249773 -0.128511 + outer loop + vertex 929.794 361.707 10.1471 + vertex 929.176 363.524 9.06205 + vertex 929.148 364.187 10.1455 + endloop + endfacet + facet normal 0.955751 0.226172 -0.188112 + outer loop + vertex 930.122 359.193 8.67127 + vertex 929.584 361.577 8.80095 + vertex 930.359 359.37 10.0889 + endloop + endfacet + facet normal 0.956446 0.235684 -0.172235 + outer loop + vertex 930.359 359.37 10.0889 + vertex 929.584 361.577 8.80095 + vertex 929.794 361.707 10.1471 + endloop + endfacet + facet normal 0.971844 0.234569 0.0222755 + outer loop + vertex 930.359 359.37 10.0889 + vertex 929.794 361.707 10.1471 + vertex 930.227 359.805 11.2927 + endloop + endfacet + facet normal 0.965334 0.254524 0.0578532 + outer loop + vertex 930.227 359.805 11.2927 + vertex 929.794 361.707 10.1471 + vertex 929.601 362.127 11.5226 + endloop + endfacet + facet normal 0.966056 0.251537 0.0588665 + outer loop + vertex 929.794 361.707 10.1471 + vertex 929.148 364.187 10.1455 + vertex 929.601 362.127 11.5226 + endloop + endfacet + facet normal 0.97112 0.236132 0.0341577 + outer loop + vertex 929.601 362.127 11.5226 + vertex 929.148 364.187 10.1455 + vertex 928.94 364.872 11.3266 + endloop + endfacet + facet normal 0.940298 0.228532 0.252217 + outer loop + vertex 930.227 359.805 11.2927 + vertex 929.601 362.127 11.5226 + vertex 930.065 358.639 12.9527 + endloop + endfacet + facet normal 0.935639 0.243399 0.25561 + outer loop + vertex 928.94 364.872 11.3266 + vertex 928.794 363.71 12.9688 + vertex 929.601 362.127 11.5226 + endloop + endfacet + facet normal 0.935211 0.233563 0.266138 + outer loop + vertex 928.794 363.71 12.9688 + vertex 930.065 358.639 12.9527 + vertex 929.601 362.127 11.5226 + endloop + endfacet + facet normal 0.936964 0.240388 0.253597 + outer loop + vertex 928.94 364.872 11.3266 + vertex 928.185 367.503 11.624 + vertex 928.794 363.71 12.9688 + endloop + endfacet + facet normal 0.925676 0.262834 0.272105 + outer loop + vertex 927.444 370.16 11.5774 + vertex 927.346 369.05 12.9843 + vertex 928.185 367.503 11.624 + endloop + endfacet + facet normal 0.924965 0.250029 0.286227 + outer loop + vertex 927.346 369.05 12.9843 + vertex 928.794 363.71 12.9688 + vertex 928.185 367.503 11.624 + endloop + endfacet + facet normal 0.821532 0.240829 -0.516804 + outer loop + vertex 928.413 364.451 7.76063 + vertex 927.207 365.268 6.22433 + vertex 926.468 369.115 6.84176 + endloop + endfacet + facet normal 0.692728 0.19929 -0.693117 + outer loop + vertex 925.77 365.552 4.86941 + vertex 924.742 369.733 5.04423 + vertex 927.207 365.268 6.22433 + endloop + endfacet + facet normal 0.740087 0.242879 -0.627121 + outer loop + vertex 924.742 369.733 5.04423 + vertex 926.468 369.115 6.84176 + vertex 927.207 365.268 6.22433 + endloop + endfacet + facet normal 0.674908 0.182702 -0.714926 + outer loop + vertex 926.798 361.783 4.8765 + vertex 925.77 365.552 4.86941 + vertex 927.953 361.969 6.01459 + endloop + endfacet + facet normal 0.692678 0.200604 -0.692788 + outer loop + vertex 927.953 361.969 6.01459 + vertex 925.77 365.552 4.86941 + vertex 927.207 365.268 6.22433 + endloop + endfacet + facet normal 0.686044 0.18868 -0.702669 + outer loop + vertex 927.822 358.857 5.09034 + vertex 926.798 361.783 4.8765 + vertex 928.694 359.088 6.00442 + endloop + endfacet + facet normal 0.676221 0.176504 -0.715242 + outer loop + vertex 928.694 359.088 6.00442 + vertex 926.798 361.783 4.8765 + vertex 927.953 361.969 6.01459 + endloop + endfacet + facet normal 0.807467 0.209694 -0.551385 + outer loop + vertex 928.694 359.088 6.00442 + vertex 927.953 361.969 6.01459 + vertex 929.536 359.15 7.26048 + endloop + endfacet + facet normal 0.80647 0.208249 -0.553388 + outer loop + vertex 929.536 359.15 7.26048 + vertex 927.953 361.969 6.01459 + vertex 928.931 361.803 7.3776 + endloop + endfacet + facet normal 0.805401 0.217099 -0.55154 + outer loop + vertex 927.953 361.969 6.01459 + vertex 927.207 365.268 6.22433 + vertex 928.931 361.803 7.3776 + endloop + endfacet + facet normal 0.821378 0.23575 -0.519384 + outer loop + vertex 928.931 361.803 7.3776 + vertex 927.207 365.268 6.22433 + vertex 928.413 364.451 7.76063 + endloop + endfacet + facet normal 0.898053 0.221471 -0.380067 + outer loop + vertex 929.536 359.15 7.26048 + vertex 928.931 361.803 7.3776 + vertex 930.122 359.193 8.67127 + endloop + endfacet + facet normal 0.898977 0.2236 -0.376621 + outer loop + vertex 930.122 359.193 8.67127 + vertex 928.931 361.803 7.3776 + vertex 929.584 361.577 8.80095 + endloop + endfacet + facet normal 0.902384 0.237242 -0.35975 + outer loop + vertex 929.176 363.524 9.06205 + vertex 929.584 361.577 8.80095 + vertex 928.413 364.451 7.76063 + endloop + endfacet + facet normal 0.897999 0.229873 -0.375175 + outer loop + vertex 928.413 364.451 7.76063 + vertex 929.584 361.577 8.80095 + vertex 928.931 361.803 7.3776 + endloop + endfacet + facet normal 0.862337 0.255655 -0.437053 + outer loop + vertex 927.032 370.194 8.58638 + vertex 928.25 366.298 8.70913 + vertex 926.468 369.115 6.84176 + endloop + endfacet + facet normal 0.902453 0.25738 -0.345448 + outer loop + vertex 929.176 363.524 9.06205 + vertex 928.413 364.451 7.76063 + vertex 928.25 366.298 8.70913 + endloop + endfacet + facet normal 0.870401 0.283759 -0.402347 + outer loop + vertex 928.413 364.451 7.76063 + vertex 926.468 369.115 6.84176 + vertex 928.25 366.298 8.70913 + endloop + endfacet + facet normal 0.394804 0.100344 -0.91327 + outer loop + vertex 922.06 365.123 2.86136 + vertex 920.745 370.012 2.82978 + vertex 924.133 365.404 3.78827 + endloop + endfacet + facet normal 0.409139 0.1125 -0.90551 + outer loop + vertex 924.133 365.404 3.78827 + vertex 920.745 370.012 2.82978 + vertex 922.881 369.997 3.79341 + endloop + endfacet + facet normal 0.402097 0.0934371 -0.910817 + outer loop + vertex 923.302 360.214 2.90596 + vertex 922.06 365.123 2.86136 + vertex 925.703 360.461 3.99125 + endloop + endfacet + facet normal 0.396614 0.0884508 -0.913714 + outer loop + vertex 925.703 360.461 3.99125 + vertex 922.06 365.123 2.86136 + vertex 924.133 365.404 3.78827 + endloop + endfacet + facet normal 0.536127 0.144637 -0.831654 + outer loop + vertex 925.77 365.552 4.86941 + vertex 926.798 361.783 4.8765 + vertex 924.133 365.404 3.78827 + endloop + endfacet + facet normal 0.529172 0.123798 -0.839435 + outer loop + vertex 927.822 358.857 5.09034 + vertex 925.703 360.461 3.99125 + vertex 926.798 361.783 4.8765 + endloop + endfacet + facet normal 0.522497 0.13136 -0.842461 + outer loop + vertex 925.703 360.461 3.99125 + vertex 924.133 365.404 3.78827 + vertex 926.798 361.783 4.8765 + endloop + endfacet + facet normal 0.535796 0.14693 -0.831465 + outer loop + vertex 924.133 365.404 3.78827 + vertex 922.881 369.997 3.79341 + vertex 925.77 365.552 4.86941 + endloop + endfacet + facet normal 0.566242 0.172909 -0.805898 + outer loop + vertex 925.77 365.552 4.86941 + vertex 922.881 369.997 3.79341 + vertex 924.742 369.733 5.04423 + endloop + endfacet + facet normal 0.198208 0.0437275 -0.979184 + outer loop + vertex 916.455 364.738 1.43666 + vertex 915.901 369.3 1.52826 + vertex 919.519 364.887 2.06356 + endloop + endfacet + facet normal 0.207504 0.0516295 -0.976871 + outer loop + vertex 919.519 364.887 2.06356 + vertex 915.901 369.3 1.52826 + vertex 918.284 369.831 2.06253 + endloop + endfacet + facet normal 0.206445 0.0554018 -0.976889 + outer loop + vertex 918.177 359.432 1.49973 + vertex 916.455 364.738 1.43666 + vertex 920.672 359.952 2.05637 + endloop + endfacet + facet normal 0.197987 0.0476702 -0.979045 + outer loop + vertex 920.672 359.952 2.05637 + vertex 916.455 364.738 1.43666 + vertex 919.519 364.887 2.06356 + endloop + endfacet + facet normal 0.30013 0.0714867 -0.951216 + outer loop + vertex 920.672 359.952 2.05637 + vertex 919.519 364.887 2.06356 + vertex 923.302 360.214 2.90596 + endloop + endfacet + facet normal 0.293347 0.0655379 -0.953757 + outer loop + vertex 923.302 360.214 2.90596 + vertex 919.519 364.887 2.06356 + vertex 922.06 365.123 2.86136 + endloop + endfacet + facet normal 0.292572 0.0728836 -0.953462 + outer loop + vertex 919.519 364.887 2.06356 + vertex 918.284 369.831 2.06253 + vertex 922.06 365.123 2.86136 + endloop + endfacet + facet normal 0.292049 0.0724317 -0.953657 + outer loop + vertex 922.06 365.123 2.86136 + vertex 918.284 369.831 2.06253 + vertex 920.745 370.012 2.82978 + endloop + endfacet + facet normal 0.132985 0.0360336 -0.990463 + outer loop + vertex 915.901 369.3 1.52826 + vertex 916.455 364.738 1.43666 + vertex 911.027 372.261 0.981559 + endloop + endfacet + facet normal 0.125632 0.0289935 -0.991653 + outer loop + vertex 918.177 359.432 1.49973 + vertex 913.246 362.489 0.964451 + vertex 916.455 364.738 1.43666 + endloop + endfacet + facet normal 0.124866 0.0300997 -0.991717 + outer loop + vertex 913.246 362.489 0.964451 + vertex 911.027 372.261 0.981559 + vertex 916.455 364.738 1.43666 + endloop + endfacet + facet normal 0.910575 0.180564 0.37182 + outer loop + vertex 900.15 375.062 27.3218 + vertex 899.064 380.087 27.5401 + vertex 899.122 376.035 29.3668 + endloop + endfacet + facet normal 0.917575 0.19231 0.347956 + outer loop + vertex 898.178 384.65 27.3559 + vertex 897.625 382.076 30.2371 + vertex 899.064 380.087 27.5401 + endloop + endfacet + facet normal 0.916386 0.175267 0.359886 + outer loop + vertex 899.122 376.035 29.3668 + vertex 899.064 380.087 27.5401 + vertex 897.625 382.076 30.2371 + endloop + endfacet + facet normal 0.733348 0.156611 0.66157 + outer loop + vertex 901.443 378.661 24.5691 + vertex 900.429 383.287 24.5983 + vertex 900.204 379.182 25.8189 + endloop + endfacet + facet normal 0.738371 0.154795 0.656389 + outer loop + vertex 900.204 379.182 25.8189 + vertex 900.429 383.287 24.5983 + vertex 899.181 383.881 25.8616 + endloop + endfacet + facet normal 0.723895 0.145837 0.674321 + outer loop + vertex 902.397 374.053 24.5418 + vertex 901.443 378.661 24.5691 + vertex 901.2 374.443 25.7417 + endloop + endfacet + facet normal 0.732113 0.143049 0.665994 + outer loop + vertex 901.2 374.443 25.7417 + vertex 901.443 378.661 24.5691 + vertex 900.204 379.182 25.8189 + endloop + endfacet + facet normal 0.384199 0.0884455 0.919004 + outer loop + vertex 904.825 377.58 22.9064 + vertex 903.578 381.902 23.012 + vertex 902.942 378.14 23.6398 + endloop + endfacet + facet normal 0.400589 0.0845634 0.912347 + outer loop + vertex 902.942 378.14 23.6398 + vertex 903.578 381.902 23.012 + vertex 901.941 382.726 23.6542 + endloop + endfacet + facet normal 0.394848 0.0717473 0.915941 + outer loop + vertex 905.519 372.712 22.9888 + vertex 904.825 377.58 22.9064 + vertex 903.882 373.564 23.6275 + endloop + endfacet + facet normal 0.381355 0.0758789 0.921309 + outer loop + vertex 903.882 373.564 23.6275 + vertex 904.825 377.58 22.9064 + vertex 902.942 378.14 23.6398 + endloop + endfacet + facet normal 0.546993 0.110158 0.829858 + outer loop + vertex 903.882 373.564 23.6275 + vertex 902.942 378.14 23.6398 + vertex 902.397 374.053 24.5418 + endloop + endfacet + facet normal 0.550836 0.109114 0.82745 + outer loop + vertex 902.397 374.053 24.5418 + vertex 902.942 378.14 23.6398 + vertex 901.443 378.661 24.5691 + endloop + endfacet + facet normal 0.552483 0.117992 0.825131 + outer loop + vertex 902.942 378.14 23.6398 + vertex 901.941 382.726 23.6542 + vertex 901.443 378.661 24.5691 + endloop + endfacet + facet normal 0.556715 0.116868 0.822442 + outer loop + vertex 901.443 378.661 24.5691 + vertex 901.941 382.726 23.6542 + vertex 900.429 383.287 24.5983 + endloop + endfacet + facet normal 0.279724 0.0573314 0.958367 + outer loop + vertex 903.578 381.902 23.012 + vertex 904.825 377.58 22.9064 + vertex 905.477 384.196 22.3203 + endloop + endfacet + facet normal 0.273966 0.0552709 0.96015 + outer loop + vertex 905.519 372.712 22.9888 + vertex 907.519 374.952 22.289 + vertex 904.825 377.58 22.9064 + endloop + endfacet + facet normal 0.276216 0.0577648 0.959358 + outer loop + vertex 907.519 374.952 22.289 + vertex 905.477 384.196 22.3203 + vertex 904.825 377.58 22.9064 + endloop + endfacet + facet normal 0.688411 0.204315 0.69595 + outer loop + vertex 923.74 375.189 16.3898 + vertex 922.128 380.428 16.4467 + vertex 922.315 376.045 17.5483 + endloop + endfacet + facet normal 0.684426 0.205074 0.699647 + outer loop + vertex 922.315 376.045 17.5483 + vertex 922.128 380.428 16.4467 + vertex 920.591 381.435 17.6543 + endloop + endfacet + facet normal 0.684097 0.188012 0.704743 + outer loop + vertex 925.176 370.1 16.3533 + vertex 923.74 375.189 16.3898 + vertex 923.791 370.868 17.493 + endloop + endfacet + facet normal 0.68499 0.187815 0.703928 + outer loop + vertex 923.791 370.868 17.493 + vertex 923.74 375.189 16.3898 + vertex 922.315 376.045 17.5483 + endloop + endfacet + facet normal 0.557895 0.150369 0.816175 + outer loop + vertex 923.791 370.868 17.493 + vertex 922.315 376.045 17.5483 + vertex 922.292 372.023 18.3046 + endloop + endfacet + facet normal 0.546452 0.151832 0.823612 + outer loop + vertex 922.292 372.023 18.3046 + vertex 922.315 376.045 17.5483 + vertex 920.678 376.856 18.4845 + endloop + endfacet + facet normal 0.548533 0.159244 0.820825 + outer loop + vertex 922.315 376.045 17.5483 + vertex 920.591 381.435 17.6543 + vertex 920.678 376.856 18.4845 + endloop + endfacet + facet normal 0.565399 0.157535 0.809634 + outer loop + vertex 920.678 376.856 18.4845 + vertex 920.591 381.435 17.6543 + vertex 919.448 381.622 18.4163 + endloop + endfacet + facet normal 0.890556 0.270885 0.365419 + outer loop + vertex 925.721 374.298 13.1477 + vertex 924.125 379.467 13.2046 + vertex 924.875 374.668 14.9347 + endloop + endfacet + facet normal 0.893701 0.269072 0.359026 + outer loop + vertex 924.875 374.668 14.9347 + vertex 924.125 379.467 13.2046 + vertex 923.323 379.778 14.968 + endloop + endfacet + facet normal 0.880939 0.2604 0.395144 + outer loop + vertex 927.346 369.05 12.9843 + vertex 925.721 374.298 13.1477 + vertex 926.34 369.565 14.8875 + endloop + endfacet + facet normal 0.893668 0.253035 0.370583 + outer loop + vertex 926.34 369.565 14.8875 + vertex 925.721 374.298 13.1477 + vertex 924.875 374.668 14.9347 + endloop + endfacet + facet normal 0.801514 0.224895 0.554074 + outer loop + vertex 926.34 369.565 14.8875 + vertex 924.875 374.668 14.9347 + vertex 925.176 370.1 16.3533 + endloop + endfacet + facet normal 0.805705 0.223455 0.54855 + outer loop + vertex 925.176 370.1 16.3533 + vertex 924.875 374.668 14.9347 + vertex 923.74 375.189 16.3898 + endloop + endfacet + facet normal 0.805181 0.240995 0.541853 + outer loop + vertex 924.875 374.668 14.9347 + vertex 923.323 379.778 14.968 + vertex 923.74 375.189 16.3898 + endloop + endfacet + facet normal 0.803739 0.241462 0.543783 + outer loop + vertex 923.74 375.189 16.3898 + vertex 923.323 379.778 14.968 + vertex 922.128 380.428 16.4467 + endloop + endfacet + facet normal 0.946562 0.299745 -0.119049 + outer loop + vertex 925.718 374.53 8.80092 + vertex 924.239 379.285 9.01683 + vertex 926.222 373.836 11.0632 + endloop + endfacet + facet normal 0.946506 0.306238 -0.101706 + outer loop + vertex 926.222 373.836 11.0632 + vertex 924.239 379.285 9.01683 + vertex 924.472 379.28 11.1716 + endloop + endfacet + facet normal 0.94894 0.315457 -0.000267973 + outer loop + vertex 927.444 370.16 11.5774 + vertex 927.34 370.471 10.3306 + vertex 926.222 373.836 11.0632 + endloop + endfacet + facet normal 0.932439 0.293178 -0.211199 + outer loop + vertex 927.032 370.194 8.58638 + vertex 925.718 374.53 8.80092 + vertex 927.34 370.471 10.3306 + endloop + endfacet + facet normal 0.936445 0.334361 -0.106179 + outer loop + vertex 925.718 374.53 8.80092 + vertex 926.222 373.836 11.0632 + vertex 927.34 370.471 10.3306 + endloop + endfacet + facet normal 0.881318 0.339045 0.329132 + outer loop + vertex 927.444 370.16 11.5774 + vertex 926.222 373.836 11.0632 + vertex 927.346 369.05 12.9843 + endloop + endfacet + facet normal 0.943901 0.287114 0.163147 + outer loop + vertex 927.346 369.05 12.9843 + vertex 926.222 373.836 11.0632 + vertex 925.721 374.298 13.1477 + endloop + endfacet + facet normal 0.940735 0.299181 0.159714 + outer loop + vertex 926.222 373.836 11.0632 + vertex 924.472 379.28 11.1716 + vertex 925.721 374.298 13.1477 + endloop + endfacet + facet normal 0.947209 0.290912 0.134776 + outer loop + vertex 925.721 374.298 13.1477 + vertex 924.472 379.28 11.1716 + vertex 924.125 379.467 13.2046 + endloop + endfacet + facet normal 0.748978 0.225243 -0.623136 + outer loop + vertex 923.48 374.476 5.21678 + vertex 922.005 379.529 5.27018 + vertex 924.88 374.443 6.88702 + endloop + endfacet + facet normal 0.766778 0.244748 -0.593422 + outer loop + vertex 924.88 374.443 6.88702 + vertex 922.005 379.529 5.27018 + vertex 923.371 379.416 6.98921 + endloop + endfacet + facet normal 0.740332 0.220113 -0.635184 + outer loop + vertex 924.742 369.733 5.04423 + vertex 923.48 374.476 5.21678 + vertex 926.468 369.115 6.84176 + endloop + endfacet + facet normal 0.748438 0.22844 -0.622619 + outer loop + vertex 926.468 369.115 6.84176 + vertex 923.48 374.476 5.21678 + vertex 924.88 374.443 6.88702 + endloop + endfacet + facet normal 0.859974 0.260136 -0.43906 + outer loop + vertex 926.468 369.115 6.84176 + vertex 924.88 374.443 6.88702 + vertex 927.032 370.194 8.58638 + endloop + endfacet + facet normal 0.87337 0.284383 -0.395412 + outer loop + vertex 927.032 370.194 8.58638 + vertex 924.88 374.443 6.88702 + vertex 925.718 374.53 8.80092 + endloop + endfacet + facet normal 0.876336 0.273924 -0.396234 + outer loop + vertex 924.88 374.443 6.88702 + vertex 923.371 379.416 6.98921 + vertex 925.718 374.53 8.80092 + endloop + endfacet + facet normal 0.885982 0.291864 -0.360348 + outer loop + vertex 925.718 374.53 8.80092 + vertex 923.371 379.416 6.98921 + vertex 924.239 379.285 9.01683 + endloop + endfacet + facet normal 0.424914 0.121365 -0.897061 + outer loop + vertex 919.411 374.908 2.83832 + vertex 918.005 379.869 2.84376 + vertex 921.599 374.764 3.85555 + endloop + endfacet + facet normal 0.44037 0.134094 -0.887746 + outer loop + vertex 921.599 374.764 3.85555 + vertex 918.005 379.869 2.84376 + vertex 920.172 379.728 3.89744 + endloop + endfacet + facet normal 0.409117 0.113032 -0.905454 + outer loop + vertex 920.745 370.012 2.82978 + vertex 919.411 374.908 2.83832 + vertex 922.881 369.997 3.79341 + endloop + endfacet + facet normal 0.424921 0.125954 -0.896425 + outer loop + vertex 922.881 369.997 3.79341 + vertex 919.411 374.908 2.83832 + vertex 921.599 374.764 3.85555 + endloop + endfacet + facet normal 0.566231 0.162803 -0.808008 + outer loop + vertex 922.881 369.997 3.79341 + vertex 921.599 374.764 3.85555 + vertex 924.742 369.733 5.04423 + endloop + endfacet + facet normal 0.594631 0.186684 -0.782025 + outer loop + vertex 924.742 369.733 5.04423 + vertex 921.599 374.764 3.85555 + vertex 923.48 374.476 5.21678 + endloop + endfacet + facet normal 0.594722 0.177594 -0.78407 + outer loop + vertex 921.599 374.764 3.85555 + vertex 920.172 379.728 3.89744 + vertex 923.48 374.476 5.21678 + endloop + endfacet + facet normal 0.602016 0.183964 -0.777003 + outer loop + vertex 923.48 374.476 5.21678 + vertex 920.172 379.728 3.89744 + vertex 922.005 379.529 5.27018 + endloop + endfacet + facet normal 0.199897 0.0485485 -0.978613 + outer loop + vertex 914.037 374.615 1.45559 + vertex 913.324 379.204 1.53761 + vertex 916.971 374.796 2.06396 + endloop + endfacet + facet normal 0.212222 0.0591257 -0.975431 + outer loop + vertex 916.971 374.796 2.06396 + vertex 913.324 379.204 1.53761 + vertex 915.59 379.758 2.06429 + endloop + endfacet + facet normal 0.205879 0.0588573 -0.976806 + outer loop + vertex 915.901 369.3 1.52826 + vertex 914.037 374.615 1.45559 + vertex 918.284 369.831 2.06253 + endloop + endfacet + facet normal 0.199583 0.0530594 -0.978443 + outer loop + vertex 918.284 369.831 2.06253 + vertex 914.037 374.615 1.45559 + vertex 916.971 374.796 2.06396 + endloop + endfacet + facet normal 0.291607 0.0773874 -0.953403 + outer loop + vertex 918.284 369.831 2.06253 + vertex 916.971 374.796 2.06396 + vertex 920.745 370.012 2.82978 + endloop + endfacet + facet normal 0.298034 0.082849 -0.950953 + outer loop + vertex 920.745 370.012 2.82978 + vertex 916.971 374.796 2.06396 + vertex 919.411 374.908 2.83832 + endloop + endfacet + facet normal 0.298024 0.0830019 -0.950943 + outer loop + vertex 916.971 374.796 2.06396 + vertex 915.59 379.758 2.06429 + vertex 919.411 374.908 2.83832 + endloop + endfacet + facet normal 0.302383 0.0867089 -0.949234 + outer loop + vertex 919.411 374.908 2.83832 + vertex 915.59 379.758 2.06429 + vertex 918.005 379.869 2.84376 + endloop + endfacet + facet normal 0.137276 0.0390176 -0.989764 + outer loop + vertex 913.324 379.204 1.53761 + vertex 914.037 374.615 1.45559 + vertex 908.556 381.998 0.986477 + endloop + endfacet + facet normal 0.130778 0.0323224 -0.990885 + outer loop + vertex 915.901 369.3 1.52826 + vertex 911.027 372.261 0.981559 + vertex 914.037 374.615 1.45559 + endloop + endfacet + facet normal 0.129897 0.0334642 -0.990963 + outer loop + vertex 911.027 372.261 0.981559 + vertex 908.556 381.998 0.986477 + vertex 914.037 374.615 1.45559 + endloop + endfacet + facet normal 0.909272 0.208081 0.360453 + outer loop + vertex 898.178 384.65 27.3559 + vertex 897.037 388.901 27.7801 + vertex 897.625 382.076 30.2371 + endloop + endfacet + facet normal 0.917159 0.215512 0.335222 + outer loop + vertex 896.012 393.742 27.472 + vertex 895.478 391.501 30.3751 + vertex 897.037 388.901 27.7801 + endloop + endfacet + facet normal 0.915754 0.203561 0.346348 + outer loop + vertex 895.478 391.501 30.3751 + vertex 897.625 382.076 30.2371 + vertex 897.037 388.901 27.7801 + endloop + endfacet + facet normal 0.747837 0.177244 0.639785 + outer loop + vertex 899.371 387.862 24.6219 + vertex 898.281 392.374 24.6453 + vertex 898.125 388.417 25.9238 + endloop + endfacet + facet normal 0.74841 0.177025 0.639175 + outer loop + vertex 898.125 388.417 25.9238 + vertex 898.281 392.374 24.6453 + vertex 897.029 392.933 25.957 + endloop + endfacet + facet normal 0.739736 0.167696 0.651666 + outer loop + vertex 900.429 383.287 24.5983 + vertex 899.371 387.862 24.6219 + vertex 899.181 383.881 25.8616 + endloop + endfacet + facet normal 0.746912 0.165006 0.644124 + outer loop + vertex 899.181 383.881 25.8616 + vertex 899.371 387.862 24.6219 + vertex 898.125 388.417 25.9238 + endloop + endfacet + facet normal 0.389785 0.0988917 0.915581 + outer loop + vertex 902.765 386.757 22.9225 + vertex 901.435 391.026 23.0278 + vertex 900.89 387.292 23.6632 + endloop + endfacet + facet normal 0.404921 0.0956199 0.909338 + outer loop + vertex 900.89 387.292 23.6632 + vertex 901.435 391.026 23.0278 + vertex 899.799 391.817 23.673 + endloop + endfacet + facet normal 0.400284 0.0837984 0.912552 + outer loop + vertex 903.578 381.902 23.012 + vertex 902.765 386.757 22.9225 + vertex 901.941 382.726 23.6542 + endloop + endfacet + facet normal 0.387369 0.0873879 0.917774 + outer loop + vertex 901.941 382.726 23.6542 + vertex 902.765 386.757 22.9225 + vertex 900.89 387.292 23.6632 + endloop + endfacet + facet normal 0.558698 0.12703 0.819585 + outer loop + vertex 901.941 382.726 23.6542 + vertex 900.89 387.292 23.6632 + vertex 900.429 383.287 24.5983 + endloop + endfacet + facet normal 0.562837 0.125931 0.816919 + outer loop + vertex 900.429 383.287 24.5983 + vertex 900.89 387.292 23.6632 + vertex 899.371 387.862 24.6219 + endloop + endfacet + facet normal 0.56443 0.134262 0.814489 + outer loop + vertex 900.89 387.292 23.6632 + vertex 899.799 391.817 23.673 + vertex 899.371 387.862 24.6219 + endloop + endfacet + facet normal 0.568749 0.133117 0.811668 + outer loop + vertex 899.371 387.862 24.6219 + vertex 899.799 391.817 23.673 + vertex 898.281 392.374 24.6453 + endloop + endfacet + facet normal 0.283159 0.0646446 0.956892 + outer loop + vertex 901.435 391.026 23.0278 + vertex 902.765 386.757 22.9225 + vertex 903.23 393.374 22.3381 + endloop + endfacet + facet normal 0.272996 0.0633693 0.959926 + outer loop + vertex 903.578 381.902 23.012 + vertex 905.477 384.196 22.3203 + vertex 902.765 386.757 22.9225 + endloop + endfacet + facet normal 0.274806 0.065441 0.95927 + outer loop + vertex 905.477 384.196 22.3203 + vertex 903.23 393.374 22.3381 + vertex 902.765 386.757 22.9225 + endloop + endfacet + facet normal 0.68793 0.220049 0.691615 + outer loop + vertex 922.128 380.428 16.4467 + vertex 920.342 385.832 16.5039 + vertex 920.591 381.435 17.6543 + endloop + endfacet + facet normal 0.56584 0.189912 0.802346 + outer loop + vertex 919.448 381.622 18.4163 + vertex 920.591 381.435 17.6543 + vertex 918.111 387.923 17.8683 + endloop + endfacet + facet normal 0.651192 0.221106 0.72599 + outer loop + vertex 918.877 390.705 16.3334 + vertex 918.111 387.923 17.8683 + vertex 920.342 385.832 16.5039 + endloop + endfacet + facet normal 0.65361 0.226119 0.722263 + outer loop + vertex 920.591 381.435 17.6543 + vertex 920.342 385.832 16.5039 + vertex 918.111 387.923 17.8683 + endloop + endfacet + facet normal 0.889932 0.298447 0.344893 + outer loop + vertex 922.505 384.501 13.2189 + vertex 920.849 389.43 13.227 + vertex 921.681 384.894 15.0039 + endloop + endfacet + facet normal 0.892367 0.296927 0.339875 + outer loop + vertex 921.681 384.894 15.0039 + vertex 920.849 389.43 13.227 + vertex 920.014 389.904 15.0057 + endloop + endfacet + facet normal 0.890342 0.285584 0.354588 + outer loop + vertex 924.125 379.467 13.2046 + vertex 922.505 384.501 13.2189 + vertex 923.323 379.778 14.968 + endloop + endfacet + facet normal 0.892862 0.284101 0.349405 + outer loop + vertex 923.323 379.778 14.968 + vertex 922.505 384.501 13.2189 + vertex 921.681 384.894 15.0039 + endloop + endfacet + facet normal 0.803637 0.254142 0.538125 + outer loop + vertex 923.323 379.778 14.968 + vertex 921.681 384.894 15.0039 + vertex 922.128 380.428 16.4467 + endloop + endfacet + facet normal 0.795022 0.256947 0.549471 + outer loop + vertex 922.128 380.428 16.4467 + vertex 921.681 384.894 15.0039 + vertex 920.342 385.832 16.5039 + endloop + endfacet + facet normal 0.795508 0.264612 0.545113 + outer loop + vertex 921.681 384.894 15.0039 + vertex 920.014 389.904 15.0057 + vertex 920.342 385.832 16.5039 + endloop + endfacet + facet normal 0.805433 0.260689 0.532278 + outer loop + vertex 920.342 385.832 16.5039 + vertex 920.014 389.904 15.0057 + vertex 918.877 390.705 16.3334 + endloop + endfacet + facet normal 0.942493 0.317503 -0.104396 + outer loop + vertex 922.594 384.344 9.07361 + vertex 920.931 389.277 9.06937 + vertex 922.82 384.372 11.1986 + endloop + endfacet + facet normal 0.942407 0.318603 -0.101785 + outer loop + vertex 922.82 384.372 11.1986 + vertex 920.931 389.277 9.06937 + vertex 921.159 389.281 11.1921 + endloop + endfacet + facet normal 0.945723 0.308679 -0.101616 + outer loop + vertex 924.239 379.285 9.01683 + vertex 922.594 384.344 9.07361 + vertex 924.472 379.28 11.1716 + endloop + endfacet + facet normal 0.945792 0.307464 -0.104612 + outer loop + vertex 924.472 379.28 11.1716 + vertex 922.594 384.344 9.07361 + vertex 922.82 384.372 11.1986 + endloop + endfacet + facet normal 0.942966 0.305284 0.132728 + outer loop + vertex 924.472 379.28 11.1716 + vertex 922.82 384.372 11.1986 + vertex 924.125 379.467 13.2046 + endloop + endfacet + facet normal 0.944213 0.303565 0.127713 + outer loop + vertex 924.125 379.467 13.2046 + vertex 922.82 384.372 11.1986 + vertex 922.505 384.501 13.2189 + endloop + endfacet + facet normal 0.939675 0.317982 0.126088 + outer loop + vertex 922.82 384.372 11.1986 + vertex 921.159 389.281 11.1921 + vertex 922.505 384.501 13.2189 + endloop + endfacet + facet normal 0.941078 0.316 0.120482 + outer loop + vertex 922.505 384.501 13.2189 + vertex 921.159 389.281 11.1921 + vertex 920.849 389.43 13.227 + endloop + endfacet + facet normal 0.774643 0.254396 -0.578974 + outer loop + vertex 920.428 384.542 5.29435 + vertex 918.801 389.469 5.28339 + vertex 921.781 384.401 7.0434 + endloop + endfacet + facet normal 0.781833 0.263443 -0.565098 + outer loop + vertex 921.781 384.401 7.0434 + vertex 918.801 389.469 5.28339 + vertex 920.119 389.338 7.04579 + endloop + endfacet + facet normal 0.766881 0.244128 -0.593545 + outer loop + vertex 922.005 379.529 5.27018 + vertex 920.428 384.542 5.29435 + vertex 923.371 379.416 6.98921 + endloop + endfacet + facet normal 0.774807 0.253428 -0.579179 + outer loop + vertex 923.371 379.416 6.98921 + vertex 920.428 384.542 5.29435 + vertex 921.781 384.401 7.0434 + endloop + endfacet + facet normal 0.887246 0.286922 -0.361207 + outer loop + vertex 923.371 379.416 6.98921 + vertex 921.781 384.401 7.0434 + vertex 924.239 379.285 9.01683 + endloop + endfacet + facet normal 0.890324 0.293432 -0.348167 + outer loop + vertex 924.239 379.285 9.01683 + vertex 921.781 384.401 7.0434 + vertex 922.594 384.344 9.07361 + endloop + endfacet + facet normal 0.888688 0.299305 -0.347346 + outer loop + vertex 921.781 384.401 7.0434 + vertex 920.119 389.338 7.04579 + vertex 922.594 384.344 9.07361 + endloop + endfacet + facet normal 0.888618 0.299139 -0.34767 + outer loop + vertex 922.594 384.344 9.07361 + vertex 920.119 389.338 7.04579 + vertex 920.931 389.277 9.06937 + endloop + endfacet + facet normal 0.446241 0.138767 -0.884089 + outer loop + vertex 916.506 384.82 2.84046 + vertex 914.957 389.698 2.82416 + vertex 918.635 384.722 3.89972 + endloop + endfacet + facet normal 0.452477 0.144253 -0.880032 + outer loop + vertex 918.635 384.722 3.89972 + vertex 914.957 389.698 2.82416 + vertex 917.039 389.631 3.88377 + endloop + endfacet + facet normal 0.440379 0.132751 -0.887943 + outer loop + vertex 918.005 379.869 2.84376 + vertex 916.506 384.82 2.84046 + vertex 920.172 379.728 3.89744 + endloop + endfacet + facet normal 0.446267 0.13776 -0.884233 + outer loop + vertex 920.172 379.728 3.89744 + vertex 916.506 384.82 2.84046 + vertex 918.635 384.722 3.89972 + endloop + endfacet + facet normal 0.601943 0.185626 -0.776665 + outer loop + vertex 920.172 379.728 3.89744 + vertex 918.635 384.722 3.89972 + vertex 922.005 379.529 5.27018 + endloop + endfacet + facet normal 0.614276 0.19694 -0.76412 + outer loop + vertex 922.005 379.529 5.27018 + vertex 918.635 384.722 3.89972 + vertex 920.428 384.542 5.29435 + endloop + endfacet + facet normal 0.614258 0.197229 -0.76406 + outer loop + vertex 918.635 384.722 3.89972 + vertex 917.039 389.631 3.88377 + vertex 920.428 384.542 5.29435 + endloop + endfacet + facet normal 0.620333 0.203066 -0.757595 + outer loop + vertex 920.428 384.542 5.29435 + vertex 917.039 389.631 3.88377 + vertex 918.801 389.469 5.28339 + endloop + endfacet + facet normal 0.204402 0.0534089 -0.977429 + outer loop + vertex 911.344 384.446 1.45493 + vertex 910.507 388.946 1.52577 + vertex 914.144 384.689 2.05375 + endloop + endfacet + facet normal 0.216185 0.0638692 -0.974261 + outer loop + vertex 914.144 384.689 2.05375 + vertex 910.507 388.946 1.52577 + vertex 912.654 389.539 2.04096 + endloop + endfacet + facet normal 0.210952 0.0642748 -0.975381 + outer loop + vertex 913.324 379.204 1.53761 + vertex 911.344 384.446 1.45493 + vertex 915.59 379.758 2.06429 + endloop + endfacet + facet normal 0.203994 0.0577273 -0.977269 + outer loop + vertex 915.59 379.758 2.06429 + vertex 911.344 384.446 1.45493 + vertex 914.144 384.689 2.05375 + endloop + endfacet + facet normal 0.302388 0.0866395 -0.949239 + outer loop + vertex 915.59 379.758 2.06429 + vertex 914.144 384.689 2.05375 + vertex 918.005 379.869 2.84376 + endloop + endfacet + facet normal 0.309985 0.0932296 -0.946159 + outer loop + vertex 918.005 379.869 2.84376 + vertex 914.144 384.689 2.05375 + vertex 916.506 384.82 2.84046 + endloop + endfacet + facet normal 0.310021 0.0927809 -0.946192 + outer loop + vertex 914.144 384.689 2.05375 + vertex 912.654 389.539 2.04096 + vertex 916.506 384.82 2.84046 + endloop + endfacet + facet normal 0.314449 0.0967102 -0.944335 + outer loop + vertex 916.506 384.82 2.84046 + vertex 912.654 389.539 2.04096 + vertex 914.957 389.698 2.82416 + endloop + endfacet + facet normal 0.13878 0.0413918 -0.989458 + outer loop + vertex 910.507 388.946 1.52577 + vertex 911.344 384.446 1.45493 + vertex 905.889 391.59 0.988669 + endloop + endfacet + facet normal 0.135232 0.0354484 -0.99018 + outer loop + vertex 913.324 379.204 1.53761 + vertex 908.556 381.998 0.986477 + vertex 911.344 384.446 1.45493 + endloop + endfacet + facet normal 0.133578 0.0373621 -0.990334 + outer loop + vertex 908.556 381.998 0.986477 + vertex 905.889 391.59 0.988669 + vertex 911.344 384.446 1.45493 + endloop + endfacet + facet normal 0.910485 0.228961 0.344374 + outer loop + vertex 896.012 393.742 27.472 + vertex 894.821 397.928 27.8381 + vertex 895.478 391.501 30.3751 + endloop + endfacet + facet normal 0.915859 0.233853 0.326368 + outer loop + vertex 893.748 402.613 27.4913 + vertex 893.259 400.438 30.4219 + vertex 894.821 397.928 27.8381 + endloop + endfacet + facet normal 0.915167 0.225406 0.334157 + outer loop + vertex 893.259 400.438 30.4219 + vertex 895.478 391.501 30.3751 + vertex 894.821 397.928 27.8381 + endloop + endfacet + facet normal 0.750272 0.194534 0.631861 + outer loop + vertex 897.162 396.847 24.6597 + vertex 896.008 401.293 24.6611 + vertex 895.911 397.399 25.9748 + endloop + endfacet + facet normal 0.752531 0.19366 0.629439 + outer loop + vertex 895.911 397.399 25.9748 + vertex 896.008 401.293 24.6611 + vertex 894.767 401.824 25.9817 + endloop + endfacet + facet normal 0.748964 0.185372 0.636152 + outer loop + vertex 898.281 392.374 24.6453 + vertex 897.162 396.847 24.6597 + vertex 897.029 392.933 25.957 + endloop + endfacet + facet normal 0.749737 0.185072 0.635329 + outer loop + vertex 897.029 392.933 25.957 + vertex 897.162 396.847 24.6597 + vertex 895.911 397.399 25.9748 + endloop + endfacet + facet normal 0.394205 0.109301 0.9125 + outer loop + vertex 900.525 395.836 22.9349 + vertex 899.122 400.058 23.035 + vertex 898.672 396.309 23.6785 + endloop + endfacet + facet normal 0.412464 0.105789 0.904811 + outer loop + vertex 898.672 396.309 23.6785 + vertex 899.122 400.058 23.035 + vertex 897.508 400.789 23.6856 + endloop + endfacet + facet normal 0.404352 0.0941093 0.909749 + outer loop + vertex 901.435 391.026 23.0278 + vertex 900.525 395.836 22.9349 + vertex 899.799 391.817 23.673 + endloop + endfacet + facet normal 0.392047 0.0972559 0.91479 + outer loop + vertex 899.799 391.817 23.673 + vertex 900.525 395.836 22.9349 + vertex 898.672 396.309 23.6785 + endloop + endfacet + facet normal 0.570354 0.142131 0.809009 + outer loop + vertex 899.799 391.817 23.673 + vertex 898.672 396.309 23.6785 + vertex 898.281 392.374 24.6453 + endloop + endfacet + facet normal 0.574266 0.141106 0.806417 + outer loop + vertex 898.281 392.374 24.6453 + vertex 898.672 396.309 23.6785 + vertex 897.162 396.847 24.6597 + endloop + endfacet + facet normal 0.575442 0.148313 0.804282 + outer loop + vertex 898.672 396.309 23.6785 + vertex 897.508 400.789 23.6856 + vertex 897.162 396.847 24.6597 + endloop + endfacet + facet normal 0.573901 0.148703 0.80531 + outer loop + vertex 897.162 396.847 24.6597 + vertex 897.508 400.789 23.6856 + vertex 896.008 401.293 24.6611 + endloop + endfacet + facet normal 0.286024 0.0723437 0.955488 + outer loop + vertex 899.122 400.058 23.035 + vertex 900.525 395.836 22.9349 + vertex 900.808 402.483 22.3467 + endloop + endfacet + facet normal 0.27585 0.0707327 0.958595 + outer loop + vertex 901.435 391.026 23.0278 + vertex 903.23 393.374 22.3381 + vertex 900.525 395.836 22.9349 + endloop + endfacet + facet normal 0.277682 0.0729135 0.957902 + outer loop + vertex 903.23 393.374 22.3381 + vertex 900.808 402.483 22.3467 + vertex 900.525 395.836 22.9349 + endloop + endfacet + facet normal 0.65584 0.218028 0.722729 + outer loop + vertex 918.877 390.705 16.3334 + vertex 917.093 395.264 16.5768 + vertex 918.111 387.923 17.8683 + endloop + endfacet + facet normal 0.667478 0.234214 0.706836 + outer loop + vertex 915.45 400.478 16.4014 + vertex 914.722 398.112 17.8722 + vertex 917.093 395.264 16.5768 + endloop + endfacet + facet normal 0.656419 0.218016 0.722207 + outer loop + vertex 914.722 398.112 17.8722 + vertex 918.111 387.923 17.8683 + vertex 917.093 395.264 16.5768 + endloop + endfacet + facet normal 0.889662 0.322503 0.323255 + outer loop + vertex 919.139 394.279 13.233 + vertex 917.391 399.085 13.2492 + vertex 918.319 394.736 15.0342 + endloop + endfacet + facet normal 0.893016 0.320293 0.316126 + outer loop + vertex 918.319 394.736 15.0342 + vertex 917.391 399.085 13.2492 + vertex 916.575 399.575 15.0592 + endloop + endfacet + facet normal 0.889057 0.313068 0.334015 + outer loop + vertex 920.849 389.43 13.227 + vertex 919.139 394.279 13.233 + vertex 920.014 389.904 15.0057 + endloop + endfacet + facet normal 0.892254 0.311006 0.327349 + outer loop + vertex 920.014 389.904 15.0057 + vertex 919.139 394.279 13.233 + vertex 918.319 394.736 15.0342 + endloop + endfacet + facet normal 0.806155 0.279662 0.521444 + outer loop + vertex 920.014 389.904 15.0057 + vertex 918.319 394.736 15.0342 + vertex 918.877 390.705 16.3334 + endloop + endfacet + facet normal 0.795756 0.28277 0.53555 + outer loop + vertex 918.877 390.705 16.3334 + vertex 918.319 394.736 15.0342 + vertex 917.093 395.264 16.5768 + endloop + endfacet + facet normal 0.795649 0.284066 0.535022 + outer loop + vertex 918.319 394.736 15.0342 + vertex 916.575 399.575 15.0592 + vertex 917.093 395.264 16.5768 + endloop + endfacet + facet normal 0.819853 0.27536 0.502014 + outer loop + vertex 917.093 395.264 16.5768 + vertex 916.575 399.575 15.0592 + vertex 915.45 400.478 16.4014 + endloop + endfacet + facet normal 0.933506 0.342436 -0.106321 + outer loop + vertex 919.221 394.094 9.05399 + vertex 917.466 398.876 9.04585 + vertex 919.463 394.096 11.1856 + endloop + endfacet + facet normal 0.933472 0.342763 -0.10556 + outer loop + vertex 919.463 394.096 11.1856 + vertex 917.466 398.876 9.04585 + vertex 917.704 398.886 11.185 + endloop + endfacet + facet normal 0.937599 0.332636 -0.101295 + outer loop + vertex 920.931 389.277 9.06937 + vertex 919.221 394.094 9.05399 + vertex 921.159 389.281 11.1921 + endloop + endfacet + facet normal 0.937821 0.33028 -0.1068 + outer loop + vertex 921.159 389.281 11.1921 + vertex 919.221 394.094 9.05399 + vertex 919.463 394.096 11.1856 + endloop + endfacet + facet normal 0.936447 0.330099 0.11875 + outer loop + vertex 921.159 389.281 11.1921 + vertex 919.463 394.096 11.1856 + vertex 920.849 389.43 13.227 + endloop + endfacet + facet normal 0.936476 0.330057 0.118634 + outer loop + vertex 920.849 389.43 13.227 + vertex 919.463 394.096 11.1856 + vertex 919.139 394.279 13.233 + endloop + endfacet + facet normal 0.932276 0.342351 0.116868 + outer loop + vertex 919.463 394.096 11.1856 + vertex 917.704 398.886 11.185 + vertex 919.139 394.279 13.233 + endloop + endfacet + facet normal 0.93429 0.339458 0.108951 + outer loop + vertex 919.139 394.279 13.233 + vertex 917.704 398.886 11.185 + vertex 917.391 399.085 13.2492 + endloop + endfacet + facet normal 0.781651 0.279716 -0.557478 + outer loop + vertex 917.128 394.306 5.26642 + vertex 915.407 399.097 5.25775 + vertex 918.43 394.173 7.02549 + endloop + endfacet + facet normal 0.785904 0.285565 -0.548459 + outer loop + vertex 918.43 394.173 7.02549 + vertex 915.407 399.097 5.25775 + vertex 916.684 398.961 7.01596 + endloop + endfacet + facet normal 0.780937 0.268255 -0.564071 + outer loop + vertex 918.801 389.469 5.28339 + vertex 917.128 394.306 5.26642 + vertex 920.119 389.338 7.04579 + endloop + endfacet + facet normal 0.783278 0.271367 -0.559317 + outer loop + vertex 920.119 389.338 7.04579 + vertex 917.128 394.306 5.26642 + vertex 918.43 394.173 7.02549 + endloop + endfacet + facet normal 0.886037 0.308171 -0.346364 + outer loop + vertex 920.119 389.338 7.04579 + vertex 918.43 394.173 7.02549 + vertex 920.931 389.277 9.06937 + endloop + endfacet + facet normal 0.88846 0.314442 -0.334312 + outer loop + vertex 920.931 389.277 9.06937 + vertex 918.43 394.173 7.02549 + vertex 919.221 394.094 9.05399 + endloop + endfacet + facet normal 0.886036 0.322516 -0.333052 + outer loop + vertex 918.43 394.173 7.02549 + vertex 916.684 398.961 7.01596 + vertex 919.221 394.094 9.05399 + endloop + endfacet + facet normal 0.886912 0.324957 -0.328313 + outer loop + vertex 919.221 394.094 9.05399 + vertex 916.684 398.961 7.01596 + vertex 917.466 398.876 9.04585 + endloop + endfacet + facet normal 0.458351 0.154647 -0.875213 + outer loop + vertex 913.372 394.496 2.81036 + vertex 911.753 399.257 2.80329 + vertex 915.404 394.453 3.86655 + endloop + endfacet + facet normal 0.467209 0.162747 -0.869039 + outer loop + vertex 915.404 394.453 3.86655 + vertex 911.753 399.257 2.80329 + vertex 913.726 399.233 3.85973 + endloop + endfacet + facet normal 0.45237 0.146843 -0.879658 + outer loop + vertex 914.957 389.698 2.82416 + vertex 913.372 394.496 2.81036 + vertex 917.039 389.631 3.88377 + endloop + endfacet + facet normal 0.458478 0.152352 -0.87555 + outer loop + vertex 917.039 389.631 3.88377 + vertex 913.372 394.496 2.81036 + vertex 915.404 394.453 3.86655 + endloop + endfacet + facet normal 0.619998 0.207551 -0.756654 + outer loop + vertex 917.039 389.631 3.88377 + vertex 915.404 394.453 3.86655 + vertex 918.801 389.469 5.28339 + endloop + endfacet + facet normal 0.626707 0.214235 -0.749228 + outer loop + vertex 918.801 389.469 5.28339 + vertex 915.404 394.453 3.86655 + vertex 917.128 394.306 5.26642 + endloop + endfacet + facet normal 0.626304 0.21876 -0.748256 + outer loop + vertex 915.404 394.453 3.86655 + vertex 913.726 399.233 3.85973 + vertex 917.128 394.306 5.26642 + endloop + endfacet + facet normal 0.633628 0.226225 -0.739823 + outer loop + vertex 917.128 394.306 5.26642 + vertex 913.726 399.233 3.85973 + vertex 915.407 399.097 5.25775 + endloop + endfacet + facet normal 0.208864 0.0603769 -0.976079 + outer loop + vertex 908.471 394.031 1.44648 + vertex 907.554 398.431 1.52225 + vertex 911.129 394.312 2.03262 + endloop + endfacet + facet normal 0.223796 0.0738671 -0.971833 + outer loop + vertex 911.129 394.312 2.03262 + vertex 907.554 398.431 1.52225 + vertex 909.574 399.044 2.03403 + endloop + endfacet + facet normal 0.214314 0.0706035 -0.97421 + outer loop + vertex 910.507 388.946 1.52577 + vertex 908.471 394.031 1.44648 + vertex 912.654 389.539 2.04096 + endloop + endfacet + facet normal 0.208354 0.0648318 -0.975902 + outer loop + vertex 912.654 389.539 2.04096 + vertex 908.471 394.031 1.44648 + vertex 911.129 394.312 2.03262 + endloop + endfacet + facet normal 0.314261 0.0987077 -0.944191 + outer loop + vertex 912.654 389.539 2.04096 + vertex 911.129 394.312 2.03262 + vertex 914.957 389.698 2.82416 + endloop + endfacet + facet normal 0.318361 0.102412 -0.942421 + outer loop + vertex 914.957 389.698 2.82416 + vertex 911.129 394.312 2.03262 + vertex 913.372 394.496 2.81036 + endloop + endfacet + facet normal 0.318097 0.104862 -0.942241 + outer loop + vertex 911.129 394.312 2.03262 + vertex 909.574 399.044 2.03403 + vertex 913.372 394.496 2.81036 + endloop + endfacet + facet normal 0.321548 0.108005 -0.940714 + outer loop + vertex 913.372 394.496 2.81036 + vertex 909.574 399.044 2.03403 + vertex 911.753 399.257 2.80329 + endloop + endfacet + facet normal 0.14539 0.0473469 -0.988241 + outer loop + vertex 907.554 398.431 1.52225 + vertex 908.471 394.031 1.44648 + vertex 903.079 401.017 0.987815 + endloop + endfacet + facet normal 0.137869 0.039761 -0.989652 + outer loop + vertex 910.507 388.946 1.52577 + vertex 905.889 391.59 0.988669 + vertex 908.471 394.031 1.44648 + endloop + endfacet + facet normal 0.136958 0.04074 -0.989739 + outer loop + vertex 905.889 391.59 0.988669 + vertex 903.079 401.017 0.987815 + vertex 908.471 394.031 1.44648 + endloop + endfacet + facet normal 0.909996 0.245559 0.334077 + outer loop + vertex 893.748 402.613 27.4913 + vertex 892.497 406.765 27.8481 + vertex 893.259 400.438 30.4219 + endloop + endfacet + facet normal 0.913908 0.248674 0.320832 + outer loop + vertex 891.337 411.482 27.4966 + vertex 890.925 409.214 30.4266 + vertex 892.497 406.765 27.8481 + endloop + endfacet + facet normal 0.913583 0.242794 0.326217 + outer loop + vertex 890.925 409.214 30.4266 + vertex 893.259 400.438 30.4219 + vertex 892.497 406.765 27.8481 + endloop + endfacet + facet normal 0.752425 0.206355 0.625519 + outer loop + vertex 894.813 405.751 24.6616 + vertex 893.571 410.255 24.6691 + vertex 893.578 406.259 25.9793 + endloop + endfacet + facet normal 0.75085 0.206912 0.627226 + outer loop + vertex 893.578 406.259 25.9793 + vertex 893.571 410.255 24.6691 + vertex 892.343 410.738 25.9806 + endloop + endfacet + facet normal 0.75286 0.201754 0.626496 + outer loop + vertex 896.008 401.293 24.6611 + vertex 894.813 405.751 24.6616 + vertex 894.767 401.824 25.9817 + endloop + endfacet + facet normal 0.752303 0.201962 0.627098 + outer loop + vertex 894.767 401.824 25.9817 + vertex 894.813 405.751 24.6616 + vertex 893.578 406.259 25.9793 + endloop + endfacet + facet normal 0.397089 0.117324 0.91025 + outer loop + vertex 898.112 404.874 22.9479 + vertex 896.638 409.106 23.0453 + vertex 896.3 405.276 23.6863 + endloop + endfacet + facet normal 0.416206 0.114266 0.902062 + outer loop + vertex 896.3 405.276 23.6863 + vertex 896.638 409.106 23.0453 + vertex 895.045 409.798 23.6925 + endloop + endfacet + facet normal 0.411406 0.102708 0.905647 + outer loop + vertex 899.122 400.058 23.035 + vertex 898.112 404.874 22.9479 + vertex 897.508 400.789 23.6856 + endloop + endfacet + facet normal 0.395471 0.106268 0.91231 + outer loop + vertex 897.508 400.789 23.6856 + vertex 898.112 404.874 22.9479 + vertex 896.3 405.276 23.6863 + endloop + endfacet + facet normal 0.574753 0.154531 0.803604 + outer loop + vertex 897.508 400.789 23.6856 + vertex 896.3 405.276 23.6863 + vertex 896.008 401.293 24.6611 + endloop + endfacet + facet normal 0.575832 0.154275 0.80288 + outer loop + vertex 896.008 401.293 24.6611 + vertex 896.3 405.276 23.6863 + vertex 894.813 405.751 24.6616 + endloop + endfacet + facet normal 0.576428 0.158864 0.801556 + outer loop + vertex 896.3 405.276 23.6863 + vertex 895.045 409.798 23.6925 + vertex 894.813 405.751 24.6616 + endloop + endfacet + facet normal 0.579072 0.158283 0.799764 + outer loop + vertex 894.813 405.751 24.6616 + vertex 895.045 409.798 23.6925 + vertex 893.571 410.255 24.6691 + endloop + endfacet + facet normal 0.29184 0.0796853 0.953142 + outer loop + vertex 896.638 409.106 23.0453 + vertex 898.112 404.874 22.9479 + vertex 898.213 411.584 22.3558 + endloop + endfacet + facet normal 0.280899 0.0762524 0.956703 + outer loop + vertex 899.122 400.058 23.035 + vertex 900.808 402.483 22.3467 + vertex 898.112 404.874 22.9479 + endloop + endfacet + facet normal 0.283962 0.0800115 0.955491 + outer loop + vertex 900.808 402.483 22.3467 + vertex 898.213 411.584 22.3558 + vertex 898.112 404.874 22.9479 + endloop + endfacet + facet normal 0.665345 0.235793 0.708321 + outer loop + vertex 915.45 400.478 16.4014 + vertex 913.596 405.053 16.6195 + vertex 914.722 398.112 17.8722 + endloop + endfacet + facet normal 0.692512 0.261309 0.672417 + outer loop + vertex 911.862 410.171 16.4168 + vertex 911.305 407.827 17.9006 + vertex 913.596 405.053 16.6195 + endloop + endfacet + facet normal 0.675941 0.235695 0.698249 + outer loop + vertex 911.305 407.827 17.9006 + vertex 914.722 398.112 17.8722 + vertex 913.596 405.053 16.6195 + endloop + endfacet + facet normal 0.892879 0.343148 0.291576 + outer loop + vertex 915.574 403.909 13.2513 + vertex 913.714 408.744 13.2552 + vertex 914.783 404.42 15.0715 + endloop + endfacet + facet normal 0.895168 0.34154 0.2864 + outer loop + vertex 914.783 404.42 15.0715 + vertex 913.714 408.744 13.2552 + vertex 912.935 409.263 15.0713 + endloop + endfacet + facet normal 0.88955 0.335027 0.310575 + outer loop + vertex 917.391 399.085 13.2492 + vertex 915.574 403.909 13.2513 + vertex 916.575 399.575 15.0592 + endloop + endfacet + facet normal 0.895995 0.330622 0.296449 + outer loop + vertex 916.575 399.575 15.0592 + vertex 915.574 403.909 13.2513 + vertex 914.783 404.42 15.0715 + endloop + endfacet + facet normal 0.82079 0.30233 0.484665 + outer loop + vertex 916.575 399.575 15.0592 + vertex 914.783 404.42 15.0715 + vertex 915.45 400.478 16.4014 + endloop + endfacet + facet normal 0.811903 0.305209 0.497655 + outer loop + vertex 915.45 400.478 16.4014 + vertex 914.783 404.42 15.0715 + vertex 913.596 405.053 16.6195 + endloop + endfacet + facet normal 0.811516 0.309631 0.49555 + outer loop + vertex 914.783 404.42 15.0715 + vertex 912.935 409.263 15.0713 + vertex 913.596 405.053 16.6195 + endloop + endfacet + facet normal 0.834061 0.300961 0.462346 + outer loop + vertex 913.596 405.053 16.6195 + vertex 912.935 409.263 15.0713 + vertex 911.862 410.171 16.4168 + endloop + endfacet + facet normal 0.926592 0.360901 -0.105723 + outer loop + vertex 915.646 403.683 9.04358 + vertex 913.758 408.532 9.04222 + vertex 915.887 403.694 11.1867 + endloop + endfacet + facet normal 0.926619 0.360672 -0.106267 + outer loop + vertex 915.887 403.694 11.1867 + vertex 913.758 408.532 9.04222 + vertex 914.001 408.538 11.1832 + endloop + endfacet + facet normal 0.930069 0.351994 -0.105224 + outer loop + vertex 917.466 398.876 9.04585 + vertex 915.646 403.683 9.04358 + vertex 917.704 398.886 11.185 + endloop + endfacet + facet normal 0.930109 0.351633 -0.106071 + outer loop + vertex 917.704 398.886 11.185 + vertex 915.646 403.683 9.04358 + vertex 915.887 403.694 11.1867 + endloop + endfacet + facet normal 0.930026 0.351529 0.107138 + outer loop + vertex 917.704 398.886 11.185 + vertex 915.887 403.694 11.1867 + vertex 917.391 399.085 13.2492 + endloop + endfacet + facet normal 0.930663 0.350605 0.104607 + outer loop + vertex 917.391 399.085 13.2492 + vertex 915.887 403.694 11.1867 + vertex 915.574 403.909 13.2513 + endloop + endfacet + facet normal 0.926892 0.36093 0.102964 + outer loop + vertex 915.887 403.694 11.1867 + vertex 914.001 408.538 11.1832 + vertex 915.574 403.909 13.2513 + endloop + endfacet + facet normal 0.929333 0.357328 0.0930461 + outer loop + vertex 915.574 403.909 13.2513 + vertex 914.001 408.538 11.1832 + vertex 913.714 408.744 13.2552 + endloop + endfacet + facet normal 0.787517 0.300213 -0.538228 + outer loop + vertex 913.629 403.902 5.25847 + vertex 911.787 408.745 5.26477 + vertex 914.879 403.768 7.01285 + endloop + endfacet + facet normal 0.791531 0.305935 -0.529039 + outer loop + vertex 914.879 403.768 7.01285 + vertex 911.787 408.745 5.26477 + vertex 913.005 408.619 7.01447 + endloop + endfacet + facet normal 0.784871 0.290543 -0.547322 + outer loop + vertex 915.407 399.097 5.25775 + vertex 913.629 403.902 5.25847 + vertex 916.684 398.961 7.01596 + endloop + endfacet + facet normal 0.788516 0.295654 -0.539288 + outer loop + vertex 916.684 398.961 7.01596 + vertex 913.629 403.902 5.25847 + vertex 914.879 403.768 7.01285 + endloop + endfacet + facet normal 0.884748 0.331915 -0.327189 + outer loop + vertex 916.684 398.961 7.01596 + vertex 914.879 403.768 7.01285 + vertex 917.466 398.876 9.04585 + endloop + endfacet + facet normal 0.885864 0.33516 -0.320801 + outer loop + vertex 917.466 398.876 9.04585 + vertex 914.879 403.768 7.01285 + vertex 915.646 403.683 9.04358 + endloop + endfacet + facet normal 0.883812 0.341512 -0.31976 + outer loop + vertex 914.879 403.768 7.01285 + vertex 913.005 408.619 7.01447 + vertex 915.646 403.683 9.04358 + endloop + endfacet + facet normal 0.88482 0.344572 -0.313631 + outer loop + vertex 915.646 403.683 9.04358 + vertex 913.005 408.619 7.01447 + vertex 913.758 408.532 9.04222 + endloop + endfacet + facet normal 0.475892 0.170923 -0.862735 + outer loop + vertex 910.083 404.025 2.80641 + vertex 908.357 408.832 2.80726 + vertex 911.996 404.024 3.86151 + endloop + endfacet + facet normal 0.48604 0.180267 -0.855143 + outer loop + vertex 911.996 404.024 3.86151 + vertex 908.357 408.832 2.80726 + vertex 910.207 408.854 3.86332 + endloop + endfacet + facet normal 0.46711 0.164192 -0.868821 + outer loop + vertex 911.753 399.257 2.80329 + vertex 910.083 404.025 2.80641 + vertex 913.726 399.233 3.85973 + endloop + endfacet + facet normal 0.475787 0.172169 -0.862545 + outer loop + vertex 913.726 399.233 3.85973 + vertex 910.083 404.025 2.80641 + vertex 911.996 404.024 3.86151 + endloop + endfacet + facet normal 0.633341 0.22903 -0.739205 + outer loop + vertex 913.726 399.233 3.85973 + vertex 911.996 404.024 3.86151 + vertex 915.407 399.097 5.25775 + endloop + endfacet + facet normal 0.641603 0.23755 -0.729325 + outer loop + vertex 915.407 399.097 5.25775 + vertex 911.996 404.024 3.86151 + vertex 913.629 403.902 5.25847 + endloop + endfacet + facet normal 0.641574 0.237802 -0.729269 + outer loop + vertex 911.996 404.024 3.86151 + vertex 910.207 408.854 3.86332 + vertex 913.629 403.902 5.25847 + endloop + endfacet + facet normal 0.652359 0.24904 -0.715826 + outer loop + vertex 913.629 403.902 5.25847 + vertex 910.207 408.854 3.86332 + vertex 911.787 408.745 5.26477 + endloop + endfacet + facet normal 0.217572 0.0672767 -0.973723 + outer loop + vertex 905.466 403.462 1.45295 + vertex 904.445 407.88 1.53 + vertex 907.973 403.788 2.03572 + endloop + endfacet + facet normal 0.234742 0.0827239 -0.968531 + outer loop + vertex 907.973 403.788 2.03572 + vertex 904.445 407.88 1.53 + vertex 906.321 408.555 2.04245 + endloop + endfacet + facet normal 0.222272 0.0788491 -0.971791 + outer loop + vertex 907.554 398.431 1.52225 + vertex 905.466 403.462 1.45295 + vertex 909.574 399.044 2.03403 + endloop + endfacet + facet normal 0.21671 0.073457 -0.973469 + outer loop + vertex 909.574 399.044 2.03403 + vertex 905.466 403.462 1.45295 + vertex 907.973 403.788 2.03572 + endloop + endfacet + facet normal 0.321452 0.108782 -0.940657 + outer loop + vertex 909.574 399.044 2.03403 + vertex 907.973 403.788 2.03572 + vertex 911.753 399.257 2.80329 + endloop + endfacet + facet normal 0.329353 0.115982 -0.937057 + outer loop + vertex 911.753 399.257 2.80329 + vertex 907.973 403.788 2.03572 + vertex 910.083 404.025 2.80641 + endloop + endfacet + facet normal 0.329421 0.115493 -0.937093 + outer loop + vertex 907.973 403.788 2.03572 + vertex 906.321 408.555 2.04245 + vertex 910.083 404.025 2.80641 + endloop + endfacet + facet normal 0.334656 0.120254 -0.934636 + outer loop + vertex 910.083 404.025 2.80641 + vertex 906.321 408.555 2.04245 + vertex 908.357 408.832 2.80726 + endloop + endfacet + facet normal 0.152345 0.0524294 -0.986936 + outer loop + vertex 904.445 407.88 1.53 + vertex 905.466 403.462 1.45295 + vertex 900.126 410.395 0.997051 + endloop + endfacet + facet normal 0.144928 0.0465265 -0.988348 + outer loop + vertex 907.554 398.431 1.52225 + vertex 903.079 401.017 0.987815 + vertex 905.466 403.462 1.45295 + endloop + endfacet + facet normal 0.144873 0.0465814 -0.988353 + outer loop + vertex 903.079 401.017 0.987815 + vertex 900.126 410.395 0.997051 + vertex 905.466 403.462 1.45295 + endloop + endfacet + facet normal 0.908777 0.258406 0.327645 + outer loop + vertex 891.337 411.482 27.4966 + vertex 890.029 415.63 27.8534 + vertex 890.925 409.214 30.4266 + endloop + endfacet + facet normal 0.912184 0.259702 0.316977 + outer loop + vertex 888.819 420.307 27.5043 + vertex 888.49 417.895 30.4269 + vertex 890.029 415.63 27.8534 + endloop + endfacet + facet normal 0.912106 0.255912 0.320267 + outer loop + vertex 888.49 417.895 30.4269 + vertex 890.925 409.214 30.4266 + vertex 890.029 415.63 27.8534 + endloop + endfacet + facet normal 0.752947 0.217431 0.621124 + outer loop + vertex 892.285 414.791 24.672 + vertex 890.979 419.303 24.6765 + vertex 891.074 415.234 25.9855 + endloop + endfacet + facet normal 0.754903 0.216784 0.618971 + outer loop + vertex 891.074 415.234 25.9855 + vertex 890.979 419.303 24.6765 + vertex 889.789 419.69 25.9916 + endloop + endfacet + facet normal 0.750938 0.212529 0.625239 + outer loop + vertex 893.571 410.255 24.6691 + vertex 892.285 414.791 24.672 + vertex 892.343 410.738 25.9806 + endloop + endfacet + facet normal 0.752967 0.211843 0.623027 + outer loop + vertex 892.343 410.738 25.9806 + vertex 892.285 414.791 24.672 + vertex 891.074 415.234 25.9855 + endloop + endfacet + facet normal 0.405128 0.125698 0.905578 + outer loop + vertex 895.529 413.967 22.9581 + vertex 893.99 418.224 23.0558 + vertex 893.749 414.353 23.701 + endloop + endfacet + facet normal 0.424632 0.123046 0.896966 + outer loop + vertex 893.749 414.353 23.701 + vertex 893.99 418.224 23.0558 + vertex 892.423 418.899 23.705 + endloop + endfacet + facet normal 0.41511 0.110876 0.90299 + outer loop + vertex 896.638 409.106 23.0453 + vertex 895.529 413.967 22.9581 + vertex 895.045 409.798 23.6925 + endloop + endfacet + facet normal 0.403408 0.113117 0.908001 + outer loop + vertex 895.045 409.798 23.6925 + vertex 895.529 413.967 22.9581 + vertex 893.749 414.353 23.701 + endloop + endfacet + facet normal 0.579694 0.163495 0.798263 + outer loop + vertex 895.045 409.798 23.6925 + vertex 893.749 414.353 23.701 + vertex 893.571 410.255 24.6691 + endloop + endfacet + facet normal 0.578944 0.163648 0.798776 + outer loop + vertex 893.571 410.255 24.6691 + vertex 893.749 414.353 23.701 + vertex 892.285 414.791 24.672 + endloop + endfacet + facet normal 0.579449 0.168289 0.797445 + outer loop + vertex 893.749 414.353 23.701 + vertex 892.423 418.899 23.705 + vertex 892.285 414.791 24.672 + endloop + endfacet + facet normal 0.582079 0.167775 0.795635 + outer loop + vertex 892.285 414.791 24.672 + vertex 892.423 418.899 23.705 + vertex 890.979 419.303 24.6765 + endloop + endfacet + facet normal 0.300327 0.0867893 0.94988 + outer loop + vertex 893.99 418.224 23.0558 + vertex 895.529 413.967 22.9581 + vertex 895.478 420.675 22.3613 + endloop + endfacet + facet normal 0.287553 0.0827008 0.954188 + outer loop + vertex 896.638 409.106 23.0453 + vertex 898.213 411.584 22.3558 + vertex 895.529 413.967 22.9581 + endloop + endfacet + facet normal 0.291025 0.086974 0.952754 + outer loop + vertex 898.213 411.584 22.3558 + vertex 895.478 420.675 22.3613 + vertex 895.529 413.967 22.9581 + endloop + endfacet + facet normal 0.691414 0.262092 0.673242 + outer loop + vertex 911.862 410.171 16.4168 + vertex 909.957 414.673 16.6198 + vertex 911.305 407.827 17.9006 + endloop + endfacet + facet normal 0.723967 0.287327 0.627149 + outer loop + vertex 908.151 419.684 16.4091 + vertex 907.8 417.289 17.9113 + vertex 909.957 414.673 16.6198 + endloop + endfacet + facet normal 0.709517 0.262082 0.654139 + outer loop + vertex 907.8 417.289 17.9113 + vertex 911.305 407.827 17.9006 + vertex 909.957 414.673 16.6198 + endloop + endfacet + facet normal 0.893671 0.363143 0.263591 + outer loop + vertex 911.79 413.595 13.2514 + vertex 909.834 418.409 13.2497 + vertex 911.05 414.093 15.074 + endloop + endfacet + facet normal 0.897458 0.360333 0.25442 + outer loop + vertex 911.05 414.093 15.074 + vertex 909.834 418.409 13.2497 + vertex 909.133 418.871 15.0689 + endloop + endfacet + facet normal 0.891883 0.354049 0.281414 + outer loop + vertex 913.714 408.744 13.2552 + vertex 911.79 413.595 13.2514 + vertex 912.935 409.263 15.0713 + endloop + endfacet + facet normal 0.897351 0.35013 0.268645 + outer loop + vertex 912.935 409.263 15.0713 + vertex 911.79 413.595 13.2514 + vertex 911.05 414.093 15.074 + endloop + endfacet + facet normal 0.833923 0.325274 0.445835 + outer loop + vertex 912.935 409.263 15.0713 + vertex 911.05 414.093 15.074 + vertex 911.862 410.171 16.4168 + endloop + endfacet + facet normal 0.825092 0.328249 0.459865 + outer loop + vertex 911.862 410.171 16.4168 + vertex 911.05 414.093 15.074 + vertex 909.957 414.673 16.6198 + endloop + endfacet + facet normal 0.824668 0.331347 0.458402 + outer loop + vertex 911.05 414.093 15.074 + vertex 909.133 418.871 15.0689 + vertex 909.957 414.673 16.6198 + endloop + endfacet + facet normal 0.846197 0.322842 0.423938 + outer loop + vertex 909.957 414.673 16.6198 + vertex 909.133 418.871 15.0689 + vertex 908.151 419.684 16.4091 + endloop + endfacet + facet normal 0.920583 0.377246 -0.101057 + outer loop + vertex 911.823 413.395 9.0377 + vertex 909.844 418.224 9.03684 + vertex 912.057 413.396 11.1796 + endloop + endfacet + facet normal 0.920794 0.375749 -0.104649 + outer loop + vertex 912.057 413.396 11.1796 + vertex 909.844 418.224 9.03684 + vertex 910.088 418.222 11.1779 + endloop + endfacet + facet normal 0.923962 0.367508 -0.105984 + outer loop + vertex 913.758 408.532 9.04222 + vertex 911.823 413.395 9.0377 + vertex 914.001 408.538 11.1832 + endloop + endfacet + facet normal 0.923713 0.369423 -0.101397 + outer loop + vertex 914.001 408.538 11.1832 + vertex 911.823 413.395 9.0377 + vertex 912.057 413.396 11.1796 + endloop + endfacet + facet normal 0.924586 0.369913 0.0911378 + outer loop + vertex 914.001 408.538 11.1832 + vertex 912.057 413.396 11.1796 + vertex 913.714 408.744 13.2552 + endloop + endfacet + facet normal 0.92618 0.367501 0.0844607 + outer loop + vertex 913.714 408.744 13.2552 + vertex 912.057 413.396 11.1796 + vertex 911.79 413.595 13.2514 + endloop + endfacet + facet normal 0.92265 0.376572 0.0831346 + outer loop + vertex 912.057 413.396 11.1796 + vertex 910.088 418.222 11.1779 + vertex 911.79 413.595 13.2514 + endloop + endfacet + facet normal 0.923536 0.37521 0.0793687 + outer loop + vertex 911.79 413.595 13.2514 + vertex 910.088 418.222 11.1779 + vertex 909.834 418.409 13.2497 + endloop + endfacet + facet normal 0.798282 0.317705 -0.511673 + outer loop + vertex 909.902 413.606 5.26041 + vertex 907.983 418.423 5.25889 + vertex 911.075 413.485 7.01614 + endloop + endfacet + facet normal 0.802147 0.32363 -0.501821 + outer loop + vertex 911.075 413.485 7.01614 + vertex 907.983 418.423 5.25889 + vertex 909.125 418.311 7.01169 + endloop + endfacet + facet normal 0.791405 0.30648 -0.528912 + outer loop + vertex 911.787 408.745 5.26477 + vertex 909.902 413.606 5.26041 + vertex 913.005 408.619 7.01447 + endloop + endfacet + facet normal 0.798486 0.316882 -0.511865 + outer loop + vertex 913.005 408.619 7.01447 + vertex 909.902 413.606 5.26041 + vertex 911.075 413.485 7.01614 + endloop + endfacet + facet normal 0.882907 0.350298 -0.312676 + outer loop + vertex 913.005 408.619 7.01447 + vertex 911.075 413.485 7.01614 + vertex 913.758 408.532 9.04222 + endloop + endfacet + facet normal 0.883156 0.351082 -0.311089 + outer loop + vertex 913.758 408.532 9.04222 + vertex 911.075 413.485 7.01614 + vertex 911.823 413.395 9.0377 + endloop + endfacet + facet normal 0.881523 0.355877 -0.310271 + outer loop + vertex 911.075 413.485 7.01614 + vertex 909.125 418.311 7.01169 + vertex 911.823 413.395 9.0377 + endloop + endfacet + facet normal 0.883306 0.361935 -0.297949 + outer loop + vertex 911.823 413.395 9.0377 + vertex 909.125 418.311 7.01169 + vertex 909.844 418.224 9.03684 + endloop + endfacet + facet normal 0.495818 0.187785 -0.847881 + outer loop + vertex 906.577 413.655 2.81183 + vertex 904.769 418.44 2.81438 + vertex 908.366 413.698 3.86702 + endloop + endfacet + facet normal 0.504086 0.195531 -0.841228 + outer loop + vertex 908.366 413.698 3.86702 + vertex 904.769 418.44 2.81438 + vertex 906.498 418.503 3.86494 + endloop + endfacet + facet normal 0.486047 0.180196 -0.855153 + outer loop + vertex 908.357 408.832 2.80726 + vertex 906.577 413.655 2.81183 + vertex 910.207 408.854 3.86332 + endloop + endfacet + facet normal 0.495666 0.189106 -0.847676 + outer loop + vertex 910.207 408.854 3.86332 + vertex 906.577 413.655 2.81183 + vertex 908.366 413.698 3.86702 + endloop + endfacet + facet normal 0.652417 0.248604 -0.715925 + outer loop + vertex 910.207 408.854 3.86332 + vertex 908.366 413.698 3.86702 + vertex 911.787 408.745 5.26477 + endloop + endfacet + facet normal 0.658116 0.254621 -0.708556 + outer loop + vertex 911.787 408.745 5.26477 + vertex 908.366 413.698 3.86702 + vertex 909.902 413.606 5.26041 + endloop + endfacet + facet normal 0.658003 0.255403 -0.708379 + outer loop + vertex 908.366 413.698 3.86702 + vertex 906.498 418.503 3.86494 + vertex 909.902 413.606 5.26041 + endloop + endfacet + facet normal 0.667398 0.26553 -0.695754 + outer loop + vertex 909.902 413.606 5.26041 + vertex 906.498 418.503 3.86494 + vertex 907.983 418.423 5.25889 + endloop + endfacet + facet normal 0.22998 0.0752916 -0.970278 + outer loop + vertex 902.285 412.936 1.45682 + vertex 901.156 417.379 1.53389 + vertex 904.616 413.353 2.04164 + endloop + endfacet + facet normal 0.245463 0.0892279 -0.965291 + outer loop + vertex 904.616 413.353 2.04164 + vertex 901.156 417.379 1.53389 + vertex 902.882 418.122 2.04145 + endloop + endfacet + facet normal 0.233647 0.0857671 -0.968531 + outer loop + vertex 904.445 407.88 1.53 + vertex 902.285 412.936 1.45682 + vertex 906.321 408.555 2.04245 + endloop + endfacet + facet normal 0.228877 0.0811679 -0.970066 + outer loop + vertex 906.321 408.555 2.04245 + vertex 902.285 412.936 1.45682 + vertex 904.616 413.353 2.04164 + endloop + endfacet + facet normal 0.334885 0.118844 -0.934734 + outer loop + vertex 906.321 408.555 2.04245 + vertex 904.616 413.353 2.04164 + vertex 908.357 408.832 2.80726 + endloop + endfacet + facet normal 0.345303 0.128322 -0.929677 + outer loop + vertex 908.357 408.832 2.80726 + vertex 904.616 413.353 2.04164 + vertex 906.577 413.655 2.81183 + endloop + endfacet + facet normal 0.345777 0.12571 -0.929858 + outer loop + vertex 904.616 413.353 2.04164 + vertex 902.882 418.122 2.04145 + vertex 906.577 413.655 2.81183 + endloop + endfacet + facet normal 0.355881 0.134954 -0.924736 + outer loop + vertex 906.577 413.655 2.81183 + vertex 902.882 418.122 2.04145 + vertex 904.769 418.44 2.81438 + endloop + endfacet + facet normal 0.162729 0.0584513 -0.984938 + outer loop + vertex 901.156 417.379 1.53389 + vertex 902.285 412.936 1.45682 + vertex 897.037 419.751 0.994233 + endloop + endfacet + facet normal 0.151112 0.0502476 -0.987239 + outer loop + vertex 904.445 407.88 1.53 + vertex 900.126 410.395 0.997051 + vertex 902.285 412.936 1.45682 + endloop + endfacet + facet normal 0.151658 0.0497735 -0.987179 + outer loop + vertex 900.126 410.395 0.997051 + vertex 897.037 419.751 0.994233 + vertex 902.285 412.936 1.45682 + endloop + endfacet + facet normal 0.906923 0.26911 0.324146 + outer loop + vertex 888.819 420.307 27.5043 + vertex 887.505 424.312 27.8535 + vertex 888.49 417.895 30.4269 + endloop + endfacet + facet normal 0.911337 0.268098 0.312391 + outer loop + vertex 886.28 428.887 27.5033 + vertex 885.998 426.436 30.4286 + vertex 887.505 424.312 27.8535 + endloop + endfacet + facet normal 0.911355 0.26583 0.314273 + outer loop + vertex 885.998 426.436 30.4286 + vertex 888.49 417.895 30.4269 + vertex 887.505 424.312 27.8535 + endloop + endfacet + facet normal 0.75491 0.225108 0.615985 + outer loop + vertex 889.671 423.734 24.6783 + vertex 888.37 428.079 24.6845 + vertex 888.504 424.057 25.9901 + endloop + endfacet + facet normal 0.754956 0.225093 0.615934 + outer loop + vertex 888.504 424.057 25.9901 + vertex 888.37 428.079 24.6845 + vertex 887.221 428.357 25.9917 + endloop + endfacet + facet normal 0.754737 0.222542 0.617128 + outer loop + vertex 890.979 419.303 24.6765 + vertex 889.671 423.734 24.6783 + vertex 889.789 419.69 25.9916 + endloop + endfacet + facet normal 0.755057 0.222436 0.616774 + outer loop + vertex 889.789 419.69 25.9916 + vertex 889.671 423.734 24.6783 + vertex 888.504 424.057 25.9901 + endloop + endfacet + facet normal 0.412009 0.132518 0.901492 + outer loop + vertex 892.826 423.037 22.965 + vertex 891.274 427.19 23.0635 + vertex 891.091 423.381 23.7074 + endloop + endfacet + facet normal 0.430077 0.130269 0.893344 + outer loop + vertex 891.091 423.381 23.7074 + vertex 891.274 427.19 23.0635 + vertex 889.758 427.781 23.7073 + endloop + endfacet + facet normal 0.423489 0.119399 0.897998 + outer loop + vertex 893.99 418.224 23.0558 + vertex 892.826 423.037 22.965 + vertex 892.423 418.899 23.705 + endloop + endfacet + facet normal 0.410751 0.12164 0.903597 + outer loop + vertex 892.423 418.899 23.705 + vertex 892.826 423.037 22.965 + vertex 891.091 423.381 23.7074 + endloop + endfacet + facet normal 0.582534 0.172765 0.794233 + outer loop + vertex 892.423 418.899 23.705 + vertex 891.091 423.381 23.7074 + vertex 890.979 419.303 24.6765 + endloop + endfacet + facet normal 0.584846 0.17232 0.792629 + outer loop + vertex 890.979 419.303 24.6765 + vertex 891.091 423.381 23.7074 + vertex 889.671 423.734 24.6783 + endloop + endfacet + facet normal 0.585164 0.177234 0.79131 + outer loop + vertex 891.091 423.381 23.7074 + vertex 889.758 427.781 23.7073 + vertex 889.671 423.734 24.6783 + endloop + endfacet + facet normal 0.591664 0.175997 0.786739 + outer loop + vertex 889.671 423.734 24.6783 + vertex 889.758 427.781 23.7073 + vertex 888.37 428.079 24.6845 + endloop + endfacet + facet normal 0.312739 0.0944042 0.945136 + outer loop + vertex 891.274 427.19 23.0635 + vertex 892.826 423.037 22.965 + vertex 892.659 429.671 22.3575 + endloop + endfacet + facet normal 0.296186 0.0895979 0.950919 + outer loop + vertex 893.99 418.224 23.0558 + vertex 895.478 420.675 22.3613 + vertex 892.826 423.037 22.965 + endloop + endfacet + facet normal 0.300126 0.0944602 0.949211 + outer loop + vertex 895.478 420.675 22.3613 + vertex 892.659 429.671 22.3575 + vertex 892.826 423.037 22.965 + endloop + endfacet + facet normal 0.723168 0.287866 0.627822 + outer loop + vertex 908.151 419.684 16.4091 + vertex 906.252 424.023 16.6067 + vertex 907.8 417.289 17.9113 + endloop + endfacet + facet normal 0.753439 0.312354 0.578589 + outer loop + vertex 904.401 428.901 16.3848 + vertex 904.196 426.572 17.9087 + vertex 906.252 424.023 16.6067 + endloop + endfacet + facet normal 0.740928 0.287869 0.606759 + outer loop + vertex 904.196 426.572 17.9087 + vertex 907.8 417.289 17.9113 + vertex 906.252 424.023 16.6067 + endloop + endfacet + facet normal 0.895591 0.378697 0.233464 + outer loop + vertex 907.87 423.135 13.245 + vertex 905.917 427.759 13.238 + vertex 907.223 423.545 15.0642 + endloop + endfacet + facet normal 0.898894 0.376024 0.224933 + outer loop + vertex 907.223 423.545 15.0642 + vertex 905.917 427.759 13.238 + vertex 905.308 428.132 15.0492 + endloop + endfacet + facet normal 0.893996 0.371716 0.250197 + outer loop + vertex 909.834 418.409 13.2497 + vertex 907.87 423.135 13.245 + vertex 909.133 418.871 15.0689 + endloop + endfacet + facet normal 0.89918 0.3677 0.237218 + outer loop + vertex 909.133 418.871 15.0689 + vertex 907.87 423.135 13.245 + vertex 907.223 423.545 15.0642 + endloop + endfacet + facet normal 0.844591 0.345565 0.408964 + outer loop + vertex 909.133 418.871 15.0689 + vertex 907.223 423.545 15.0642 + vertex 908.151 419.684 16.4091 + endloop + endfacet + facet normal 0.838433 0.347792 0.419608 + outer loop + vertex 908.151 419.684 16.4091 + vertex 907.223 423.545 15.0642 + vertex 906.252 424.023 16.6067 + endloop + endfacet + facet normal 0.837767 0.351135 0.418152 + outer loop + vertex 907.223 423.545 15.0642 + vertex 905.308 428.132 15.0492 + vertex 906.252 424.023 16.6067 + endloop + endfacet + facet normal 0.857032 0.342858 0.384636 + outer loop + vertex 906.252 424.023 16.6067 + vertex 905.308 428.132 15.0492 + vertex 904.401 428.901 16.3848 + endloop + endfacet + facet normal 0.915525 0.38946 -0.100675 + outer loop + vertex 907.864 422.974 9.03693 + vertex 905.877 427.645 9.03931 + vertex 908.1 422.971 11.1787 + endloop + endfacet + facet normal 0.91548 0.38973 -0.100039 + outer loop + vertex 908.1 422.971 11.1787 + vertex 905.877 427.645 9.03931 + vertex 906.116 427.631 11.1779 + endloop + endfacet + facet normal 0.917949 0.382737 -0.104316 + outer loop + vertex 909.844 418.224 9.03684 + vertex 907.864 422.974 9.03693 + vertex 910.088 418.222 11.1779 + endloop + endfacet + facet normal 0.917732 0.384163 -0.100926 + outer loop + vertex 910.088 418.222 11.1779 + vertex 907.864 422.974 9.03693 + vertex 908.1 422.971 11.1787 + endloop + endfacet + facet normal 0.919642 0.384932 0.0780112 + outer loop + vertex 910.088 418.222 11.1779 + vertex 908.1 422.971 11.1787 + vertex 909.834 418.409 13.2497 + endloop + endfacet + facet normal 0.921026 0.382771 0.072094 + outer loop + vertex 909.834 418.409 13.2497 + vertex 908.1 422.971 11.1787 + vertex 907.87 423.135 13.245 + endloop + endfacet + facet normal 0.917756 0.390729 0.0710957 + outer loop + vertex 908.1 422.971 11.1787 + vertex 906.116 427.631 11.1779 + vertex 907.87 423.135 13.245 + endloop + endfacet + facet normal 0.919201 0.388414 0.0648356 + outer loop + vertex 907.87 423.135 13.245 + vertex 906.116 427.631 11.1779 + vertex 905.917 427.759 13.238 + endloop + endfacet + facet normal 0.804749 0.333365 -0.491168 + outer loop + vertex 906.054 423.148 5.26411 + vertex 904.127 427.798 5.26333 + vertex 907.161 423.051 7.01193 + endloop + endfacet + facet normal 0.809403 0.341206 -0.47796 + outer loop + vertex 907.161 423.051 7.01193 + vertex 904.127 427.798 5.26333 + vertex 905.196 427.715 7.01337 + endloop + endfacet + facet normal 0.801096 0.327669 -0.500878 + outer loop + vertex 907.983 418.423 5.25889 + vertex 906.054 423.148 5.26411 + vertex 909.125 418.311 7.01169 + endloop + endfacet + facet normal 0.804716 0.333486 -0.491141 + outer loop + vertex 909.125 418.311 7.01169 + vertex 906.054 423.148 5.26411 + vertex 907.161 423.051 7.01193 + endloop + endfacet + facet normal 0.882034 0.365515 -0.297345 + outer loop + vertex 909.125 418.311 7.01169 + vertex 907.161 423.051 7.01193 + vertex 909.844 418.224 9.03684 + endloop + endfacet + facet normal 0.882702 0.368045 -0.292199 + outer loop + vertex 909.844 418.224 9.03684 + vertex 907.161 423.051 7.01193 + vertex 907.864 422.974 9.03693 + endloop + endfacet + facet normal 0.881441 0.371502 -0.291629 + outer loop + vertex 907.161 423.051 7.01193 + vertex 905.196 427.715 7.01337 + vertex 907.864 422.974 9.03693 + endloop + endfacet + facet normal 0.882383 0.375457 -0.283605 + outer loop + vertex 907.864 422.974 9.03693 + vertex 905.196 427.715 7.01337 + vertex 905.877 427.645 9.03931 + endloop + endfacet + facet normal 0.515196 0.200912 -0.833191 + outer loop + vertex 902.957 423.14 2.81414 + vertex 901.147 427.759 2.80859 + vertex 904.626 423.214 3.86397 + endloop + endfacet + facet normal 0.528415 0.213712 -0.821648 + outer loop + vertex 904.626 423.214 3.86397 + vertex 901.147 427.759 2.80859 + vertex 902.752 427.845 3.86303 + endloop + endfacet + facet normal 0.504234 0.19439 -0.841404 + outer loop + vertex 904.769 418.44 2.81438 + vertex 902.957 423.14 2.81414 + vertex 906.498 418.503 3.86494 + endloop + endfacet + facet normal 0.514704 0.204368 -0.832654 + outer loop + vertex 906.498 418.503 3.86494 + vertex 902.957 423.14 2.81414 + vertex 904.626 423.214 3.86397 + endloop + endfacet + facet normal 0.667466 0.265103 -0.695851 + outer loop + vertex 906.498 418.503 3.86494 + vertex 904.626 423.214 3.86397 + vertex 907.983 418.423 5.25889 + endloop + endfacet + facet normal 0.679086 0.278046 -0.679362 + outer loop + vertex 907.983 418.423 5.25889 + vertex 904.626 423.214 3.86397 + vertex 906.054 423.148 5.26411 + endloop + endfacet + facet normal 0.679637 0.274948 -0.680071 + outer loop + vertex 904.626 423.214 3.86397 + vertex 902.752 427.845 3.86303 + vertex 906.054 423.148 5.26411 + endloop + endfacet + facet normal 0.688554 0.28519 -0.666753 + outer loop + vertex 906.054 423.148 5.26411 + vertex 902.752 427.845 3.86303 + vertex 904.127 427.798 5.26333 + endloop + endfacet + facet normal 0.243026 0.0818455 -0.966561 + outer loop + vertex 898.971 422.358 1.4573 + vertex 897.793 426.702 1.52888 + vertex 901.135 422.818 2.04026 + endloop + endfacet + facet normal 0.262072 0.0991057 -0.959946 + outer loop + vertex 901.135 422.818 2.04026 + vertex 897.793 426.702 1.52888 + vertex 899.391 427.429 2.04025 + endloop + endfacet + facet normal 0.244163 0.0922789 -0.965334 + outer loop + vertex 901.156 417.379 1.53389 + vertex 898.971 422.358 1.4573 + vertex 902.882 418.122 2.04145 + endloop + endfacet + facet normal 0.241323 0.0895223 -0.966307 + outer loop + vertex 902.882 418.122 2.04145 + vertex 898.971 422.358 1.4573 + vertex 901.135 422.818 2.04026 + endloop + endfacet + facet normal 0.356396 0.132338 -0.924915 + outer loop + vertex 902.882 418.122 2.04145 + vertex 901.135 422.818 2.04026 + vertex 904.769 418.44 2.81438 + endloop + endfacet + facet normal 0.365768 0.140994 -0.919965 + outer loop + vertex 904.769 418.44 2.81438 + vertex 901.135 422.818 2.04026 + vertex 902.957 423.14 2.81414 + endloop + endfacet + facet normal 0.366278 0.138514 -0.920138 + outer loop + vertex 901.135 422.818 2.04026 + vertex 899.391 427.429 2.04025 + vertex 902.957 423.14 2.81414 + endloop + endfacet + facet normal 0.373592 0.145315 -0.91614 + outer loop + vertex 902.957 423.14 2.81414 + vertex 899.391 427.429 2.04025 + vertex 901.147 427.759 2.80859 + endloop + endfacet + facet normal 0.170541 0.0624615 -0.983369 + outer loop + vertex 897.793 426.702 1.52888 + vertex 898.971 422.358 1.4573 + vertex 893.873 429 0.994921 + endloop + endfacet + facet normal 0.161102 0.0555267 -0.985375 + outer loop + vertex 901.156 417.379 1.53389 + vertex 897.037 419.751 0.994233 + vertex 898.971 422.358 1.4573 + endloop + endfacet + facet normal 0.161395 0.0553032 -0.985339 + outer loop + vertex 897.037 419.751 0.994233 + vertex 893.873 429 0.994921 + vertex 898.971 422.358 1.4573 + endloop + endfacet + facet normal 0.907415 0.274981 0.317779 + outer loop + vertex 886.28 428.887 27.5033 + vertex 884.948 432.87 27.857 + vertex 885.998 426.436 30.4286 + endloop + endfacet + facet normal 0.911208 0.273686 0.30789 + outer loop + vertex 883.673 437.517 27.5004 + vertex 883.451 434.955 30.4345 + vertex 884.948 432.87 27.857 + endloop + endfacet + facet normal 0.91124 0.272155 0.309148 + outer loop + vertex 883.451 434.955 30.4345 + vertex 885.998 426.436 30.4286 + vertex 884.948 432.87 27.857 + endloop + endfacet + facet normal 0.757139 0.231967 0.610681 + outer loop + vertex 887.057 432.404 24.6851 + vertex 885.717 436.784 24.6835 + vertex 885.924 432.658 25.9935 + endloop + endfacet + facet normal 0.760096 0.231057 0.607345 + outer loop + vertex 885.924 432.658 25.9935 + vertex 885.717 436.784 24.6835 + vertex 884.598 437.021 25.9928 + endloop + endfacet + facet normal 0.754667 0.228993 0.61485 + outer loop + vertex 888.37 428.079 24.6845 + vertex 887.057 432.404 24.6851 + vertex 887.221 428.357 25.9917 + endloop + endfacet + facet normal 0.757474 0.228097 0.611723 + outer loop + vertex 887.221 428.357 25.9917 + vertex 887.057 432.404 24.6851 + vertex 885.924 432.658 25.9935 + endloop + endfacet + facet normal 0.42162 0.139037 0.89605 + outer loop + vertex 890.084 431.904 22.9611 + vertex 888.527 435.999 23.0581 + vertex 888.422 432.137 23.7068 + endloop + endfacet + facet normal 0.440936 0.136994 0.887022 + outer loop + vertex 888.422 432.137 23.7068 + vertex 888.527 435.999 23.0581 + vertex 887.061 436.532 23.7045 + endloop + endfacet + facet normal 0.429424 0.127873 0.894004 + outer loop + vertex 891.274 427.19 23.0635 + vertex 890.084 431.904 22.9611 + vertex 889.758 427.781 23.7073 + endloop + endfacet + facet normal 0.421027 0.129222 0.897796 + outer loop + vertex 889.758 427.781 23.7073 + vertex 890.084 431.904 22.9611 + vertex 888.422 432.137 23.7068 + endloop + endfacet + facet normal 0.591864 0.181608 0.785312 + outer loop + vertex 889.758 427.781 23.7073 + vertex 888.422 432.137 23.7068 + vertex 888.37 428.079 24.6845 + endloop + endfacet + facet normal 0.59608 0.180828 0.782298 + outer loop + vertex 888.37 428.079 24.6845 + vertex 888.422 432.137 23.7068 + vertex 887.057 432.404 24.6851 + endloop + endfacet + facet normal 0.596154 0.184993 0.781267 + outer loop + vertex 888.422 432.137 23.7068 + vertex 887.061 436.532 23.7045 + vertex 887.057 432.404 24.6851 + endloop + endfacet + facet normal 0.600814 0.184183 0.777881 + outer loop + vertex 887.057 432.404 24.6851 + vertex 887.061 436.532 23.7045 + vertex 885.717 436.784 24.6835 + endloop + endfacet + facet normal 0.324145 0.10093 0.940608 + outer loop + vertex 888.527 435.999 23.0581 + vertex 890.084 431.904 22.9611 + vertex 889.771 438.607 22.3496 + endloop + endfacet + facet normal 0.306929 0.0980813 0.946665 + outer loop + vertex 891.274 427.19 23.0635 + vertex 892.659 429.671 22.3575 + vertex 890.084 431.904 22.9611 + endloop + endfacet + facet normal 0.30897 0.100688 0.945727 + outer loop + vertex 892.659 429.671 22.3575 + vertex 889.771 438.607 22.3496 + vertex 890.084 431.904 22.9611 + endloop + endfacet + facet normal 0.675653 0.258676 0.690348 + outer loop + vertex 902.138 427.638 19.37 + vertex 900.397 435.99 17.9448 + vertex 898.516 437.018 19.3998 + endloop + endfacet + facet normal 0.758375 0.308901 0.573975 + outer loop + vertex 904.401 428.901 16.3848 + vertex 902.446 433.272 16.6144 + vertex 904.196 426.572 17.9087 + endloop + endfacet + facet normal 0.780332 0.327809 0.532562 + outer loop + vertex 900.43 438.335 16.4525 + vertex 900.397 435.99 17.9448 + vertex 902.446 433.272 16.6144 + endloop + endfacet + facet normal 0.771031 0.3089 0.556859 + outer loop + vertex 900.397 435.99 17.9448 + vertex 904.196 426.572 17.9087 + vertex 902.446 433.272 16.6144 + endloop + endfacet + facet normal 0.897642 0.389889 0.205489 + outer loop + vertex 903.946 432.346 13.2219 + vertex 901.925 437.001 13.2202 + vertex 903.365 432.725 15.0426 + endloop + endfacet + facet normal 0.900864 0.387114 0.196434 + outer loop + vertex 903.365 432.725 15.0426 + vertex 901.925 437.001 13.2202 + vertex 901.328 437.451 15.0672 + endloop + endfacet + facet normal 0.895614 0.385552 0.221868 + outer loop + vertex 905.917 427.759 13.238 + vertex 903.946 432.346 13.2219 + vertex 905.308 428.132 15.0492 + endloop + endfacet + facet normal 0.900693 0.38129 0.208253 + outer loop + vertex 905.308 428.132 15.0492 + vertex 903.946 432.346 13.2219 + vertex 903.365 432.725 15.0426 + endloop + endfacet + facet normal 0.854707 0.362073 0.371994 + outer loop + vertex 905.308 428.132 15.0492 + vertex 903.365 432.725 15.0426 + vertex 904.401 428.901 16.3848 + endloop + endfacet + facet normal 0.854173 0.362285 0.373012 + outer loop + vertex 904.401 428.901 16.3848 + vertex 903.365 432.725 15.0426 + vertex 902.446 433.272 16.6144 + endloop + endfacet + facet normal 0.853412 0.36576 0.371358 + outer loop + vertex 903.365 432.725 15.0426 + vertex 901.328 437.451 15.0672 + vertex 902.446 433.272 16.6144 + endloop + endfacet + facet normal 0.871015 0.357661 0.336765 + outer loop + vertex 902.446 433.272 16.6144 + vertex 901.328 437.451 15.0672 + vertex 900.43 438.335 16.4525 + endloop + endfacet + facet normal 0.911939 0.397609 -0.101357 + outer loop + vertex 903.871 432.285 9.04002 + vertex 901.836 436.951 9.03275 + vertex 904.126 432.244 11.1701 + endloop + endfacet + facet normal 0.911688 0.39904 -0.0979384 + outer loop + vertex 904.126 432.244 11.1701 + vertex 901.836 436.951 9.03275 + vertex 902.09 436.89 11.1568 + endloop + endfacet + facet normal 0.913336 0.394796 -0.0997665 + outer loop + vertex 905.877 427.645 9.03931 + vertex 903.871 432.285 9.04002 + vertex 906.116 427.631 11.1779 + endloop + endfacet + facet normal 0.913471 0.394014 -0.101609 + outer loop + vertex 906.116 427.631 11.1779 + vertex 903.871 432.285 9.04002 + vertex 904.126 432.244 11.1701 + endloop + endfacet + facet normal 0.916232 0.395486 0.0641088 + outer loop + vertex 906.116 427.631 11.1779 + vertex 904.126 432.244 11.1701 + vertex 905.917 427.759 13.238 + endloop + endfacet + facet normal 0.91703 0.394187 0.0605998 + outer loop + vertex 905.917 427.759 13.238 + vertex 904.126 432.244 11.1701 + vertex 903.946 432.346 13.2219 + endloop + endfacet + facet normal 0.914273 0.400624 0.060038 + outer loop + vertex 904.126 432.244 11.1701 + vertex 902.09 436.89 11.1568 + vertex 903.946 432.346 13.2219 + endloop + endfacet + facet normal 0.915982 0.397799 0.0522866 + outer loop + vertex 903.946 432.346 13.2219 + vertex 902.09 436.89 11.1568 + vertex 901.925 437.001 13.2202 + endloop + endfacet + facet normal 0.814736 0.346711 -0.464755 + outer loop + vertex 902.181 432.432 5.26424 + vertex 900.192 437.112 5.2698 + vertex 903.211 432.359 7.01612 + endloop + endfacet + facet normal 0.819205 0.354742 -0.450624 + outer loop + vertex 903.211 432.359 7.01612 + vertex 900.192 437.112 5.2698 + vertex 901.184 437.043 7.0179 + endloop + endfacet + facet normal 0.809692 0.340204 -0.478184 + outer loop + vertex 904.127 427.798 5.26333 + vertex 902.181 432.432 5.26424 + vertex 905.196 427.715 7.01337 + endloop + endfacet + facet normal 0.814276 0.348237 -0.464421 + outer loop + vertex 905.196 427.715 7.01337 + vertex 902.181 432.432 5.26424 + vertex 903.211 432.359 7.01612 + endloop + endfacet + facet normal 0.881809 0.376988 -0.283358 + outer loop + vertex 905.196 427.715 7.01337 + vertex 903.211 432.359 7.01612 + vertex 905.877 427.645 9.03931 + endloop + endfacet + facet normal 0.882812 0.381628 -0.273867 + outer loop + vertex 905.877 427.645 9.03931 + vertex 903.211 432.359 7.01612 + vertex 903.871 432.285 9.04002 + endloop + endfacet + facet normal 0.882622 0.382123 -0.273787 + outer loop + vertex 903.211 432.359 7.01612 + vertex 901.184 437.043 7.0179 + vertex 903.871 432.285 9.04002 + endloop + endfacet + facet normal 0.88317 0.384801 -0.268215 + outer loop + vertex 903.871 432.285 9.04002 + vertex 901.184 437.043 7.0179 + vertex 901.836 436.951 9.03275 + endloop + endfacet + facet normal 0.541078 0.216354 -0.812666 + outer loop + vertex 899.317 432.351 2.81202 + vertex 897.456 436.997 2.81027 + vertex 900.856 432.461 3.86605 + endloop + endfacet + facet normal 0.555502 0.230352 -0.798972 + outer loop + vertex 900.856 432.461 3.86605 + vertex 897.456 436.997 2.81027 + vertex 898.926 437.127 3.86895 + endloop + endfacet + facet normal 0.528786 0.211348 -0.822021 + outer loop + vertex 901.147 427.759 2.80859 + vertex 899.317 432.351 2.81202 + vertex 902.752 427.845 3.86303 + endloop + endfacet + facet normal 0.540028 0.222311 -0.811756 + outer loop + vertex 902.752 427.845 3.86303 + vertex 899.317 432.351 2.81202 + vertex 900.856 432.461 3.86605 + endloop + endfacet + facet normal 0.688911 0.28336 -0.667165 + outer loop + vertex 902.752 427.845 3.86303 + vertex 900.856 432.461 3.86605 + vertex 904.127 427.798 5.26333 + endloop + endfacet + facet normal 0.697122 0.292953 -0.654369 + outer loop + vertex 904.127 427.798 5.26333 + vertex 900.856 432.461 3.86605 + vertex 902.181 432.432 5.26424 + endloop + endfacet + facet normal 0.697914 0.289189 -0.655198 + outer loop + vertex 900.856 432.461 3.86605 + vertex 898.926 437.127 3.86895 + vertex 902.181 432.432 5.26424 + endloop + endfacet + facet normal 0.70868 0.301857 -0.637695 + outer loop + vertex 902.181 432.432 5.26424 + vertex 898.926 437.127 3.86895 + vertex 900.192 437.112 5.2698 + endloop + endfacet + facet normal 0.258025 0.0904354 -0.961896 + outer loop + vertex 895.622 431.561 1.45637 + vertex 894.396 435.86 1.53154 + vertex 897.635 432.007 2.03805 + endloop + endfacet + facet normal 0.277937 0.108145 -0.954492 + outer loop + vertex 897.635 432.007 2.03805 + vertex 894.396 435.86 1.53154 + vertex 895.852 436.618 2.04147 + endloop + endfacet + facet normal 0.260706 0.102144 -0.959999 + outer loop + vertex 897.793 426.702 1.52888 + vertex 895.622 431.561 1.45637 + vertex 899.391 427.429 2.04025 + endloop + endfacet + facet normal 0.256297 0.0978919 -0.961628 + outer loop + vertex 899.391 427.429 2.04025 + vertex 895.622 431.561 1.45637 + vertex 897.635 432.007 2.03805 + endloop + endfacet + facet normal 0.374073 0.14311 -0.916291 + outer loop + vertex 899.391 427.429 2.04025 + vertex 897.635 432.007 2.03805 + vertex 901.147 427.759 2.80859 + endloop + endfacet + facet normal 0.386574 0.154738 -0.909185 + outer loop + vertex 901.147 427.759 2.80859 + vertex 897.635 432.007 2.03805 + vertex 899.317 432.351 2.81202 + endloop + endfacet + facet normal 0.387575 0.150492 -0.909471 + outer loop + vertex 897.635 432.007 2.03805 + vertex 895.852 436.618 2.04147 + vertex 899.317 432.351 2.81202 + endloop + endfacet + facet normal 0.395998 0.158226 -0.904517 + outer loop + vertex 899.317 432.351 2.81202 + vertex 895.852 436.618 2.04147 + vertex 897.456 436.997 2.81027 + endloop + endfacet + facet normal 0.182065 0.0690949 -0.980856 + outer loop + vertex 894.396 435.86 1.53154 + vertex 895.622 431.561 1.45637 + vertex 890.66 438.159 1.00003 + endloop + endfacet + facet normal 0.169824 0.0611908 -0.983573 + outer loop + vertex 897.793 426.702 1.52888 + vertex 893.873 429 0.994921 + vertex 895.622 431.561 1.45637 + endloop + endfacet + facet normal 0.170839 0.0604732 -0.983441 + outer loop + vertex 893.873 429 0.994921 + vertex 890.66 438.159 1.00003 + vertex 895.622 431.561 1.45637 + endloop + endfacet + facet normal 0.909089 0.277312 0.310895 + outer loop + vertex 883.673 437.517 27.5004 + vertex 882.314 441.57 27.8607 + vertex 883.451 434.955 30.4345 + endloop + endfacet + facet normal 0.911416 0.274678 0.306387 + outer loop + vertex 881.012 446.281 27.5088 + vertex 880.869 443.491 30.437 + vertex 882.314 441.57 27.8607 + endloop + endfacet + facet normal 0.911374 0.275657 0.305633 + outer loop + vertex 880.869 443.491 30.437 + vertex 883.451 434.955 30.4345 + vertex 882.314 441.57 27.8607 + endloop + endfacet + facet normal 0.762246 0.234996 0.603124 + outer loop + vertex 884.346 441.245 24.6828 + vertex 882.958 445.755 24.6808 + vertex 883.248 441.45 25.9915 + endloop + endfacet + facet normal 0.766431 0.233799 0.598266 + outer loop + vertex 883.248 441.45 25.9915 + vertex 882.958 445.755 24.6808 + vertex 881.887 445.906 25.9928 + endloop + endfacet + facet normal 0.759865 0.233468 0.606711 + outer loop + vertex 885.717 436.784 24.6835 + vertex 884.346 441.245 24.6828 + vertex 884.598 437.021 25.9928 + endloop + endfacet + facet normal 0.762499 0.232691 0.603697 + outer loop + vertex 884.598 437.021 25.9928 + vertex 884.346 441.245 24.6828 + vertex 883.248 441.45 25.9915 + endloop + endfacet + facet normal 0.435295 0.145008 0.888533 + outer loop + vertex 887.274 440.794 22.9533 + vertex 885.676 444.997 23.0504 + vertex 885.671 441.006 23.704 + endloop + endfacet + facet normal 0.455738 0.14334 0.878497 + outer loop + vertex 885.671 441.006 23.704 + vertex 885.676 444.997 23.0504 + vertex 884.254 445.54 23.6992 + endloop + endfacet + facet normal 0.440332 0.134507 0.887703 + outer loop + vertex 888.527 435.999 23.0581 + vertex 887.274 440.794 22.9533 + vertex 887.061 436.532 23.7045 + endloop + endfacet + facet normal 0.434834 0.135238 0.890298 + outer loop + vertex 887.061 436.532 23.7045 + vertex 887.274 440.794 22.9533 + vertex 885.671 441.006 23.704 + endloop + endfacet + facet normal 0.600837 0.186817 0.777235 + outer loop + vertex 887.061 436.532 23.7045 + vertex 885.671 441.006 23.704 + vertex 885.717 436.784 24.6835 + endloop + endfacet + facet normal 0.605465 0.186073 0.773815 + outer loop + vertex 885.717 436.784 24.6835 + vertex 885.671 441.006 23.704 + vertex 884.346 441.245 24.6828 + endloop + endfacet + facet normal 0.605468 0.19002 0.772853 + outer loop + vertex 885.671 441.006 23.704 + vertex 884.254 445.54 23.6992 + vertex 884.346 441.245 24.6828 + endloop + endfacet + facet normal 0.612504 0.188957 0.767551 + outer loop + vertex 884.346 441.245 24.6828 + vertex 884.254 445.54 23.6992 + vertex 882.958 445.755 24.6808 + endloop + endfacet + facet normal 0.34109 0.108138 0.93379 + outer loop + vertex 885.676 444.997 23.0504 + vertex 887.274 440.794 22.9533 + vertex 886.788 447.624 22.3397 + endloop + endfacet + facet normal 0.318754 0.103913 0.942124 + outer loop + vertex 888.527 435.999 23.0581 + vertex 889.771 438.607 22.3496 + vertex 887.274 440.794 22.9533 + endloop + endfacet + facet normal 0.32147 0.107375 0.940812 + outer loop + vertex 889.771 438.607 22.3496 + vertex 886.788 447.624 22.3397 + vertex 887.274 440.794 22.9533 + endloop + endfacet + facet normal 0.679429 0.286715 0.675404 + outer loop + vertex 900.397 435.99 17.9448 + vertex 896.37 445.685 17.8801 + vertex 898.516 437.018 19.3998 + endloop + endfacet + facet normal 0.730151 0.289385 0.61898 + outer loop + vertex 898.516 437.018 19.3998 + vertex 896.37 445.685 17.8801 + vertex 894.743 446.437 19.4475 + endloop + endfacet + facet normal 0.78243 0.326378 0.53036 + outer loop + vertex 900.43 438.335 16.4525 + vertex 898.327 442.923 16.732 + vertex 900.397 435.99 17.9448 + endloop + endfacet + facet normal 0.788582 0.348003 0.506984 + outer loop + vertex 896.382 447.545 16.5846 + vertex 896.37 445.685 17.8801 + vertex 898.327 442.923 16.732 + endloop + endfacet + facet normal 0.776551 0.326146 0.539071 + outer loop + vertex 896.37 445.685 17.8801 + vertex 900.397 435.99 17.9448 + vertex 898.327 442.923 16.732 + endloop + endfacet + facet normal 0.899081 0.39902 0.180102 + outer loop + vertex 899.792 441.833 13.257 + vertex 897.538 446.867 13.3529 + vertex 899.166 442.388 15.153 + endloop + endfacet + facet normal 0.897639 0.40026 0.184491 + outer loop + vertex 899.166 442.388 15.153 + vertex 897.538 446.867 13.3529 + vertex 896.822 447.572 15.3071 + endloop + endfacet + facet normal 0.898061 0.394969 0.193613 + outer loop + vertex 901.925 437.001 13.2202 + vertex 899.792 441.833 13.257 + vertex 901.328 437.451 15.0672 + endloop + endfacet + facet normal 0.901635 0.391855 0.183043 + outer loop + vertex 901.328 437.451 15.0672 + vertex 899.792 441.833 13.257 + vertex 899.166 442.388 15.153 + endloop + endfacet + facet normal 0.868544 0.374902 0.324161 + outer loop + vertex 901.328 437.451 15.0672 + vertex 899.166 442.388 15.153 + vertex 900.43 438.335 16.4525 + endloop + endfacet + facet normal 0.864969 0.376301 0.332002 + outer loop + vertex 900.43 438.335 16.4525 + vertex 899.166 442.388 15.153 + vertex 898.327 442.923 16.732 + endloop + endfacet + facet normal 0.863852 0.380665 0.32993 + outer loop + vertex 899.166 442.388 15.153 + vertex 896.822 447.572 15.3071 + vertex 898.327 442.923 16.732 + endloop + endfacet + facet normal 0.87304 0.377232 0.309027 + outer loop + vertex 898.327 442.923 16.732 + vertex 896.822 447.572 15.3071 + vertex 896.382 447.545 16.5846 + endloop + endfacet + facet normal 0.909019 0.404938 -0.0985419 + outer loop + vertex 899.747 441.679 9.0235 + vertex 897.615 446.465 9.02109 + vertex 900.001 441.629 11.1582 + endloop + endfacet + facet normal 0.908439 0.408001 -0.0909617 + outer loop + vertex 900.001 441.629 11.1582 + vertex 897.615 446.465 9.02109 + vertex 897.816 446.502 11.1909 + endloop + endfacet + facet normal 0.910415 0.401994 -0.0977016 + outer loop + vertex 901.836 436.951 9.03275 + vertex 899.747 441.679 9.0235 + vertex 902.09 436.89 11.1568 + endloop + endfacet + facet normal 0.910495 0.401546 -0.0987966 + outer loop + vertex 902.09 436.89 11.1568 + vertex 899.747 441.679 9.0235 + vertex 900.001 441.629 11.1582 + endloop + endfacet + facet normal 0.913757 0.402941 0.0518337 + outer loop + vertex 902.09 436.89 11.1568 + vertex 900.001 441.629 11.1582 + vertex 901.925 437.001 13.2202 + endloop + endfacet + facet normal 0.91374 0.402969 0.0519131 + outer loop + vertex 901.925 437.001 13.2202 + vertex 900.001 441.629 11.1582 + vertex 899.792 441.833 13.257 + endloop + endfacet + facet normal 0.911384 0.408366 0.0511544 + outer loop + vertex 900.001 441.629 11.1582 + vertex 897.816 446.502 11.1909 + vertex 899.792 441.833 13.257 + endloop + endfacet + facet normal 0.912012 0.407321 0.0481926 + outer loop + vertex 899.792 441.833 13.257 + vertex 897.816 446.502 11.1909 + vertex 897.538 446.867 13.3529 + endloop + endfacet + facet normal 0.82475 0.358269 -0.437528 + outer loop + vertex 898.16 441.849 5.27086 + vertex 896.09 446.608 5.26533 + vertex 899.113 441.782 7.01305 + endloop + endfacet + facet normal 0.829136 0.366625 -0.422041 + outer loop + vertex 899.113 441.782 7.01305 + vertex 896.09 446.608 5.26533 + vertex 897.001 446.551 7.00599 + endloop + endfacet + facet normal 0.820069 0.351974 -0.451223 + outer loop + vertex 900.192 437.112 5.2698 + vertex 898.16 441.849 5.27086 + vertex 901.184 437.043 7.0179 + endloop + endfacet + facet normal 0.824284 0.359717 -0.437217 + outer loop + vertex 901.184 437.043 7.0179 + vertex 898.16 441.849 5.27086 + vertex 899.113 441.782 7.01305 + endloop + endfacet + facet normal 0.8829 0.385502 -0.268095 + outer loop + vertex 901.184 437.043 7.0179 + vertex 899.113 441.782 7.01305 + vertex 901.836 436.951 9.03275 + endloop + endfacet + facet normal 0.883762 0.389905 -0.258726 + outer loop + vertex 901.836 436.951 9.03275 + vertex 899.113 441.782 7.01305 + vertex 899.747 441.679 9.0235 + endloop + endfacet + facet normal 0.883376 0.390892 -0.258554 + outer loop + vertex 899.113 441.782 7.01305 + vertex 897.001 446.551 7.00599 + vertex 899.747 441.679 9.0235 + endloop + endfacet + facet normal 0.883882 0.393661 -0.252554 + outer loop + vertex 899.747 441.679 9.0235 + vertex 897.001 446.551 7.00599 + vertex 897.615 446.465 9.02109 + endloop + endfacet + facet normal 0.569563 0.23317 -0.788181 + outer loop + vertex 895.56 441.689 2.821 + vertex 893.641 446.384 2.8233 + vertex 896.955 441.845 3.87488 + endloop + endfacet + facet normal 0.583716 0.246901 -0.773508 + outer loop + vertex 896.955 441.845 3.87488 + vertex 893.641 446.384 2.8233 + vertex 894.951 446.575 3.87289 + endloop + endfacet + facet normal 0.556222 0.226677 -0.799522 + outer loop + vertex 897.456 436.997 2.81027 + vertex 895.56 441.689 2.821 + vertex 898.926 437.127 3.86895 + endloop + endfacet + facet normal 0.568409 0.238444 -0.787436 + outer loop + vertex 898.926 437.127 3.86895 + vertex 895.56 441.689 2.821 + vertex 896.955 441.845 3.87488 + endloop + endfacet + facet normal 0.70972 0.29729 -0.638683 + outer loop + vertex 898.926 437.127 3.86895 + vertex 896.955 441.845 3.87488 + vertex 900.192 437.112 5.2698 + endloop + endfacet + facet normal 0.719456 0.308841 -0.622093 + outer loop + vertex 900.192 437.112 5.2698 + vertex 896.955 441.845 3.87488 + vertex 898.16 441.849 5.27086 + endloop + endfacet + facet normal 0.720432 0.304868 -0.622923 + outer loop + vertex 896.955 441.845 3.87488 + vertex 894.951 446.575 3.87289 + vertex 898.16 441.849 5.27086 + endloop + endfacet + facet normal 0.730533 0.317089 -0.604794 + outer loop + vertex 898.16 441.849 5.27086 + vertex 894.951 446.575 3.87289 + vertex 896.09 446.608 5.26533 + endloop + endfacet + facet normal 0.276453 0.0994815 -0.955865 + outer loop + vertex 892.205 440.763 1.46286 + vertex 890.91 445.124 1.54206 + vertex 894.038 441.284 2.0471 + endloop + endfacet + facet normal 0.298374 0.118498 -0.947065 + outer loop + vertex 894.038 441.284 2.0471 + vertex 890.91 445.124 1.54206 + vertex 892.209 445.945 2.05406 + endloop + endfacet + facet normal 0.276837 0.110309 -0.954564 + outer loop + vertex 894.396 435.86 1.53154 + vertex 892.205 440.763 1.46286 + vertex 895.852 436.618 2.04147 + endloop + endfacet + facet normal 0.274049 0.107702 -0.955666 + outer loop + vertex 895.852 436.618 2.04147 + vertex 892.205 440.763 1.46286 + vertex 894.038 441.284 2.0471 + endloop + endfacet + facet normal 0.396758 0.155349 -0.904682 + outer loop + vertex 895.852 436.618 2.04147 + vertex 894.038 441.284 2.0471 + vertex 897.456 436.997 2.81027 + endloop + endfacet + facet normal 0.410875 0.168143 -0.896052 + outer loop + vertex 897.456 436.997 2.81027 + vertex 894.038 441.284 2.0471 + vertex 895.56 441.689 2.821 + endloop + endfacet + facet normal 0.412333 0.16314 -0.896307 + outer loop + vertex 894.038 441.284 2.0471 + vertex 892.209 445.945 2.05406 + vertex 895.56 441.689 2.821 + endloop + endfacet + facet normal 0.424118 0.173775 -0.888778 + outer loop + vertex 895.56 441.689 2.821 + vertex 892.209 445.945 2.05406 + vertex 893.641 446.384 2.8233 + endloop + endfacet + facet normal 0.196112 0.0760112 -0.977631 + outer loop + vertex 890.91 445.124 1.54206 + vertex 892.205 440.763 1.46286 + vertex 887.381 447.304 1.00367 + endloop + endfacet + facet normal 0.180863 0.0670578 -0.98122 + outer loop + vertex 894.396 435.86 1.53154 + vertex 890.66 438.159 1.00003 + vertex 892.205 440.763 1.46286 + endloop + endfacet + facet normal 0.182725 0.0659049 -0.980953 + outer loop + vertex 890.66 438.159 1.00003 + vertex 887.381 447.304 1.00367 + vertex 892.205 440.763 1.46286 + endloop + endfacet + facet normal 0.909331 0.278065 0.309511 + outer loop + vertex 881.012 446.281 27.5088 + vertex 879.682 450.239 27.8624 + vertex 880.869 443.491 30.437 + endloop + endfacet + facet normal 0.912135 0.273566 0.305241 + outer loop + vertex 878.416 454.853 27.5095 + vertex 878.318 451.92 30.4316 + vertex 879.682 450.239 27.8624 + endloop + endfacet + facet normal 0.911949 0.276201 0.303418 + outer loop + vertex 878.318 451.92 30.4316 + vertex 880.869 443.491 30.437 + vertex 879.682 450.239 27.8624 + endloop + endfacet + facet normal 0.769429 0.238253 0.592634 + outer loop + vertex 881.577 450.238 24.6812 + vertex 880.22 454.64 24.6738 + vertex 880.544 450.31 25.9931 + endloop + endfacet + facet normal 0.777357 0.235952 0.583132 + outer loop + vertex 880.544 450.31 25.9931 + vertex 880.22 454.64 24.6738 + vertex 879.232 454.632 25.9941 + endloop + endfacet + facet normal 0.766159 0.235853 0.597808 + outer loop + vertex 882.958 445.755 24.6808 + vertex 881.577 450.238 24.6812 + vertex 881.887 445.906 25.9928 + endloop + endfacet + facet normal 0.770005 0.234757 0.593281 + outer loop + vertex 881.887 445.906 25.9928 + vertex 881.577 450.238 24.6812 + vertex 880.544 450.31 25.9931 + endloop + endfacet + facet normal 0.453689 0.152663 0.877986 + outer loop + vertex 884.361 449.872 22.946 + vertex 882.759 454.072 23.0438 + vertex 882.836 450.075 23.699 + endloop + endfacet + facet normal 0.479484 0.150945 0.864472 + outer loop + vertex 882.836 450.075 23.699 + vertex 882.759 454.072 23.0438 + vertex 881.428 454.547 23.6992 + endloop + endfacet + facet normal 0.455298 0.141573 0.879011 + outer loop + vertex 885.676 444.997 23.0504 + vertex 884.361 449.872 22.946 + vertex 884.254 445.54 23.6992 + endloop + endfacet + facet normal 0.453252 0.141801 0.880031 + outer loop + vertex 884.254 445.54 23.6992 + vertex 884.361 449.872 22.946 + vertex 882.836 450.075 23.699 + endloop + endfacet + facet normal 0.612468 0.191592 0.766926 + outer loop + vertex 884.254 445.54 23.6992 + vertex 882.836 450.075 23.699 + vertex 882.958 445.755 24.6808 + endloop + endfacet + facet normal 0.619243 0.1906 0.761715 + outer loop + vertex 882.958 445.755 24.6808 + vertex 882.836 450.075 23.699 + vertex 881.577 450.238 24.6812 + endloop + endfacet + facet normal 0.619063 0.1949 0.760773 + outer loop + vertex 882.836 450.075 23.699 + vertex 881.428 454.547 23.6992 + vertex 881.577 450.238 24.6812 + endloop + endfacet + facet normal 0.625112 0.19403 0.756034 + outer loop + vertex 881.577 450.238 24.6812 + vertex 881.428 454.547 23.6992 + vertex 880.22 454.64 24.6738 + endloop + endfacet + facet normal 0.365317 0.117887 0.923388 + outer loop + vertex 882.759 454.072 23.0438 + vertex 884.361 449.872 22.946 + vertex 883.69 456.68 22.3424 + endloop + endfacet + facet normal 0.336128 0.110646 0.935294 + outer loop + vertex 885.676 444.997 23.0504 + vertex 886.788 447.624 22.3397 + vertex 884.361 449.872 22.946 + endloop + endfacet + facet normal 0.340782 0.116312 0.93292 + outer loop + vertex 886.788 447.624 22.3397 + vertex 883.69 456.68 22.3424 + vertex 884.361 449.872 22.946 + endloop + endfacet + facet normal 0.607487 0.238923 0.757546 + outer loop + vertex 893.302 446.619 20.4371 + vertex 890.872 455.754 19.5048 + vertex 889.68 455.75 20.4623 + endloop + endfacet + facet normal 0.729925 0.318451 0.604813 + outer loop + vertex 896.37 445.685 17.8801 + vertex 892.2 455.169 17.9188 + vertex 894.743 446.437 19.4475 + endloop + endfacet + facet normal 0.781155 0.321214 0.535368 + outer loop + vertex 894.743 446.437 19.4475 + vertex 892.2 455.169 17.9188 + vertex 890.872 455.754 19.5048 + endloop + endfacet + facet normal 0.731072 0.386769 0.562089 + outer loop + vertex 896.382 447.545 16.5846 + vertex 893.823 453.781 15.6218 + vertex 896.37 445.685 17.8801 + endloop + endfacet + facet normal 0.849087 0.371779 0.375276 + outer loop + vertex 896.37 445.685 17.8801 + vertex 893.823 453.781 15.6218 + vertex 892.2 455.169 17.9188 + endloop + endfacet + facet normal 0.894996 0.407788 0.180809 + outer loop + vertex 897.538 446.867 13.3529 + vertex 895.139 452.096 13.4338 + vertex 896.822 447.572 15.3071 + endloop + endfacet + facet normal 0.863196 0.401464 0.306136 + outer loop + vertex 896.382 447.545 16.5846 + vertex 896.822 447.572 15.3071 + vertex 893.823 453.781 15.6218 + endloop + endfacet + facet normal 0.885302 0.412194 0.215258 + outer loop + vertex 892.998 456.845 13.1473 + vertex 893.823 453.781 15.6218 + vertex 895.139 452.096 13.4338 + endloop + endfacet + facet normal 0.884254 0.416441 0.211358 + outer loop + vertex 896.822 447.572 15.3071 + vertex 895.139 452.096 13.4338 + vertex 893.823 453.781 15.6218 + endloop + endfacet + facet normal 0.905865 0.414382 -0.0877304 + outer loop + vertex 895.44 451.281 9.03601 + vertex 893.256 456.059 9.05608 + vertex 895.576 451.451 11.2443 + endloop + endfacet + facet normal 0.905544 0.415749 -0.084512 + outer loop + vertex 895.576 451.451 11.2443 + vertex 893.256 456.059 9.05608 + vertex 893.346 456.308 11.2464 + endloop + endfacet + facet normal 0.907482 0.410137 -0.0909092 + outer loop + vertex 897.615 446.465 9.02109 + vertex 895.44 451.281 9.03601 + vertex 897.816 446.502 11.1909 + endloop + endfacet + facet normal 0.907195 0.411492 -0.0875895 + outer loop + vertex 897.816 446.502 11.1909 + vertex 895.44 451.281 9.03601 + vertex 895.576 451.451 11.2443 + endloop + endfacet + facet normal 0.910225 0.411408 0.0472727 + outer loop + vertex 897.816 446.502 11.1909 + vertex 895.576 451.451 11.2443 + vertex 897.538 446.867 13.3529 + endloop + endfacet + facet normal 0.907705 0.415508 0.0585305 + outer loop + vertex 897.538 446.867 13.3529 + vertex 895.576 451.451 11.2443 + vertex 895.139 452.096 13.4338 + endloop + endfacet + facet normal 0.90728 0.416485 0.0581579 + outer loop + vertex 895.576 451.451 11.2443 + vertex 893.346 456.308 11.2464 + vertex 895.139 452.096 13.4338 + endloop + endfacet + facet normal 0.909339 0.413056 0.0498674 + outer loop + vertex 895.139 452.096 13.4338 + vertex 893.346 456.308 11.2464 + vertex 892.998 456.845 13.1473 + endloop + endfacet + facet normal 0.833957 0.370422 -0.409027 + outer loop + vertex 894.002 451.342 5.25104 + vertex 891.924 456.004 5.23502 + vertex 894.872 451.31 6.99627 + endloop + endfacet + facet normal 0.838087 0.379407 -0.391996 + outer loop + vertex 894.872 451.31 6.99627 + vertex 891.924 456.004 5.23502 + vertex 892.736 456.024 6.99251 + endloop + endfacet + facet normal 0.82981 0.364617 -0.422458 + outer loop + vertex 896.09 446.608 5.26533 + vertex 894.002 451.342 5.25104 + vertex 897.001 446.551 7.00599 + endloop + endfacet + facet normal 0.833435 0.371911 -0.40874 + outer loop + vertex 897.001 446.551 7.00599 + vertex 894.002 451.342 5.25104 + vertex 894.872 451.31 6.99627 + endloop + endfacet + facet normal 0.883499 0.394622 -0.252396 + outer loop + vertex 897.001 446.551 7.00599 + vertex 894.872 451.31 6.99627 + vertex 897.615 446.465 9.02109 + endloop + endfacet + facet normal 0.884373 0.400163 -0.24032 + outer loop + vertex 897.615 446.465 9.02109 + vertex 894.872 451.31 6.99627 + vertex 895.44 451.281 9.03601 + endloop + endfacet + facet normal 0.884255 0.400446 -0.240283 + outer loop + vertex 894.872 451.31 6.99627 + vertex 892.736 456.024 6.99251 + vertex 895.44 451.281 9.03601 + endloop + endfacet + facet normal 0.884842 0.40537 -0.22963 + outer loop + vertex 895.44 451.281 9.03601 + vertex 892.736 456.024 6.99251 + vertex 893.256 456.059 9.05608 + endloop + endfacet + facet normal 0.599766 0.252532 -0.759282 + outer loop + vertex 891.684 451.066 2.81445 + vertex 889.682 455.789 2.80363 + vertex 892.919 451.286 3.86313 + endloop + endfacet + facet normal 0.612015 0.264638 -0.745255 + outer loop + vertex 892.919 451.286 3.86313 + vertex 889.682 455.789 2.80363 + vertex 890.899 455.932 3.85375 + endloop + endfacet + facet normal 0.584704 0.242928 -0.77402 + outer loop + vertex 893.641 446.384 2.8233 + vertex 891.684 451.066 2.81445 + vertex 894.951 446.575 3.87289 + endloop + endfacet + facet normal 0.598627 0.256643 -0.758801 + outer loop + vertex 894.951 446.575 3.87289 + vertex 891.684 451.066 2.81445 + vertex 892.919 451.286 3.86313 + endloop + endfacet + facet normal 0.731311 0.314195 -0.605364 + outer loop + vertex 894.951 446.575 3.87289 + vertex 892.919 451.286 3.86313 + vertex 896.09 446.608 5.26533 + endloop + endfacet + facet normal 0.739367 0.324231 -0.590094 + outer loop + vertex 896.09 446.608 5.26533 + vertex 892.919 451.286 3.86313 + vertex 894.002 451.342 5.25104 + endloop + endfacet + facet normal 0.740366 0.320765 -0.590735 + outer loop + vertex 892.919 451.286 3.86313 + vertex 890.899 455.932 3.85375 + vertex 894.002 451.342 5.25104 + endloop + endfacet + facet normal 0.749141 0.332042 -0.573181 + outer loop + vertex 894.002 451.342 5.25104 + vertex 890.899 455.932 3.85375 + vertex 891.924 456.004 5.23502 + endloop + endfacet + facet normal 0.296947 0.10767 -0.948804 + outer loop + vertex 888.703 449.984 1.46396 + vertex 887.282 454.37 1.51695 + vertex 890.344 450.589 2.04627 + endloop + endfacet + facet normal 0.320849 0.128486 -0.938375 + outer loop + vertex 890.344 450.589 2.04627 + vertex 887.282 454.37 1.51695 + vertex 888.382 455.329 2.02428 + endloop + endfacet + facet normal 0.297535 0.11988 -0.947155 + outer loop + vertex 890.91 445.124 1.54206 + vertex 888.703 449.984 1.46396 + vertex 892.209 445.945 2.05406 + endloop + endfacet + facet normal 0.293742 0.11635 -0.948777 + outer loop + vertex 892.209 445.945 2.05406 + vertex 888.703 449.984 1.46396 + vertex 890.344 450.589 2.04627 + endloop + endfacet + facet normal 0.425554 0.169375 -0.888941 + outer loop + vertex 892.209 445.945 2.05406 + vertex 890.344 450.589 2.04627 + vertex 893.641 446.384 2.8233 + endloop + endfacet + facet normal 0.439504 0.182039 -0.879601 + outer loop + vertex 893.641 446.384 2.8233 + vertex 890.344 450.589 2.04627 + vertex 891.684 451.066 2.81445 + endloop + endfacet + facet normal 0.440832 0.178434 -0.879675 + outer loop + vertex 890.344 450.589 2.04627 + vertex 888.382 455.329 2.02428 + vertex 891.684 451.066 2.81445 + endloop + endfacet + facet normal 0.454271 0.190595 -0.870236 + outer loop + vertex 891.684 451.066 2.81445 + vertex 888.382 455.329 2.02428 + vertex 889.682 455.789 2.80363 + endloop + endfacet + facet normal 0.207923 0.0791435 -0.974938 + outer loop + vertex 887.282 454.37 1.51695 + vertex 888.703 449.984 1.46396 + vertex 883.955 456.378 0.97052 + endloop + endfacet + facet normal 0.193957 0.0723478 -0.978339 + outer loop + vertex 890.91 445.124 1.54206 + vertex 887.381 447.304 1.00367 + vertex 888.703 449.984 1.46396 + endloop + endfacet + facet normal 0.196964 0.0707812 -0.977852 + outer loop + vertex 887.381 447.304 1.00367 + vertex 883.955 456.378 0.97052 + vertex 888.703 449.984 1.46396 + endloop + endfacet + facet normal 0.908988 0.278521 0.310109 + outer loop + vertex 878.416 454.853 27.5095 + vertex 877.118 458.708 27.8532 + vertex 878.318 451.92 30.4316 + endloop + endfacet + facet normal 0.912155 0.273822 0.304949 + outer loop + vertex 875.838 463.338 27.5218 + vertex 875.792 460.292 30.3959 + vertex 877.118 458.708 27.8532 + endloop + endfacet + facet normal 0.911947 0.276426 0.303218 + outer loop + vertex 875.792 460.292 30.3959 + vertex 878.318 451.92 30.4316 + vertex 877.118 458.708 27.8532 + endloop + endfacet + facet normal 0.779624 0.242395 0.577435 + outer loop + vertex 878.891 458.956 24.6718 + vertex 877.555 463.246 24.6744 + vertex 877.936 458.89 25.9887 + endloop + endfacet + facet normal 0.789516 0.239526 0.565059 + outer loop + vertex 877.936 458.89 25.9887 + vertex 877.555 463.246 24.6744 + vertex 876.626 463.165 26.0066 + endloop + endfacet + facet normal 0.776657 0.239473 0.582629 + outer loop + vertex 880.22 454.64 24.6738 + vertex 878.891 458.956 24.6718 + vertex 879.232 454.632 25.9941 + endloop + endfacet + facet normal 0.780536 0.238332 0.577894 + outer loop + vertex 879.232 454.632 25.9941 + vertex 878.891 458.956 24.6718 + vertex 877.936 458.89 25.9887 + endloop + endfacet + facet normal 0.479371 0.164885 0.861984 + outer loop + vertex 881.412 458.856 22.9485 + vertex 879.832 462.933 23.0471 + vertex 880.04 458.935 23.696 + endloop + endfacet + facet normal 0.510471 0.163617 0.844185 + outer loop + vertex 880.04 458.935 23.696 + vertex 879.832 462.933 23.0471 + vertex 878.646 463.274 23.6983 + endloop + endfacet + facet normal 0.479773 0.152309 0.864072 + outer loop + vertex 882.759 454.072 23.0438 + vertex 881.412 458.856 22.9485 + vertex 881.428 454.547 23.6992 + endloop + endfacet + facet normal 0.479784 0.152308 0.864066 + outer loop + vertex 881.428 454.547 23.6992 + vertex 881.412 458.856 22.9485 + vertex 880.04 458.935 23.696 + endloop + endfacet + facet normal 0.624791 0.198071 0.755251 + outer loop + vertex 881.428 454.547 23.6992 + vertex 880.04 458.935 23.696 + vertex 880.22 454.64 24.6738 + endloop + endfacet + facet normal 0.636581 0.196408 0.745781 + outer loop + vertex 880.22 454.64 24.6738 + vertex 880.04 458.935 23.696 + vertex 878.891 458.956 24.6718 + endloop + endfacet + facet normal 0.635669 0.203908 0.744544 + outer loop + vertex 880.04 458.935 23.696 + vertex 878.646 463.274 23.6983 + vertex 878.891 458.956 24.6718 + endloop + endfacet + facet normal 0.650188 0.202001 0.732429 + outer loop + vertex 878.891 458.956 24.6718 + vertex 878.646 463.274 23.6983 + vertex 877.555 463.246 24.6744 + endloop + endfacet + facet normal 0.400662 0.133311 0.906476 + outer loop + vertex 879.832 462.933 23.0471 + vertex 881.412 458.856 22.9485 + vertex 880.455 465.663 22.3702 + endloop + endfacet + facet normal 0.360638 0.119979 0.924957 + outer loop + vertex 882.759 454.072 23.0438 + vertex 883.69 456.68 22.3424 + vertex 881.412 458.856 22.9485 + endloop + endfacet + facet normal 0.368999 0.130034 0.920288 + outer loop + vertex 883.69 456.68 22.3424 + vertex 880.455 465.663 22.3702 + vertex 881.412 458.856 22.9485 + endloop + endfacet + facet normal 0.603993 0.260324 0.753275 + outer loop + vertex 890.872 455.754 19.5048 + vertex 886.885 464.933 19.5296 + vertex 889.68 455.75 20.4623 + endloop + endfacet + facet normal 0.640078 0.267935 0.720077 + outer loop + vertex 889.68 455.75 20.4623 + vertex 886.885 464.933 19.5296 + vertex 885.881 464.807 20.4691 + endloop + endfacet + facet normal 0.778142 0.347633 0.523111 + outer loop + vertex 892.2 455.169 17.9188 + vertex 887.97 464.58 17.9562 + vertex 890.872 455.754 19.5048 + endloop + endfacet + facet normal 0.806208 0.348911 0.477797 + outer loop + vertex 890.872 455.754 19.5048 + vertex 887.97 464.58 17.9562 + vertex 886.885 464.933 19.5296 + endloop + endfacet + facet normal 0.846234 0.391643 0.361252 + outer loop + vertex 893.823 453.781 15.6218 + vertex 889.288 463.612 15.5859 + vertex 892.2 455.169 17.9188 + endloop + endfacet + facet normal 0.86392 0.386982 0.322314 + outer loop + vertex 892.2 455.169 17.9188 + vertex 889.288 463.612 15.5859 + vertex 887.97 464.58 17.9562 + endloop + endfacet + facet normal 0.887042 0.410096 0.21208 + outer loop + vertex 892.998 456.845 13.1473 + vertex 890.905 461.179 13.5209 + vertex 893.823 453.781 15.6218 + endloop + endfacet + facet normal 0.885369 0.421097 0.196974 + outer loop + vertex 888.565 466.234 13.2333 + vertex 889.288 463.612 15.5859 + vertex 890.905 461.179 13.5209 + endloop + endfacet + facet normal 0.887225 0.410002 0.211496 + outer loop + vertex 889.288 463.612 15.5859 + vertex 893.823 453.781 15.6218 + vertex 890.905 461.179 13.5209 + endloop + endfacet + facet normal 0.90061 0.427901 -0.0761726 + outer loop + vertex 891.09 460.745 9.07606 + vertex 888.896 465.368 9.10585 + vertex 891.177 460.956 11.294 + endloop + endfacet + facet normal 0.899802 0.430696 -0.0696953 + outer loop + vertex 891.177 460.956 11.294 + vertex 888.896 465.368 9.10585 + vertex 888.958 465.6 11.335 + endloop + endfacet + facet normal 0.904315 0.418367 -0.0847585 + outer loop + vertex 893.256 456.059 9.05608 + vertex 891.09 460.745 9.07606 + vertex 893.346 456.308 11.2464 + endloop + endfacet + facet normal 0.903303 0.422263 -0.0757419 + outer loop + vertex 893.346 456.308 11.2464 + vertex 891.09 460.745 9.07606 + vertex 891.177 460.956 11.294 + endloop + endfacet + facet normal 0.905401 0.42199 0.0466201 + outer loop + vertex 893.346 456.308 11.2464 + vertex 891.177 460.956 11.294 + vertex 892.998 456.845 13.1473 + endloop + endfacet + facet normal 0.900712 0.429188 0.0671929 + outer loop + vertex 892.998 456.845 13.1473 + vertex 891.177 460.956 11.294 + vertex 890.905 461.179 13.5209 + endloop + endfacet + facet normal 0.900433 0.429789 0.0670985 + outer loop + vertex 891.177 460.956 11.294 + vertex 888.958 465.6 11.335 + vertex 890.905 461.179 13.5209 + endloop + endfacet + facet normal 0.905474 0.421843 0.0465366 + outer loop + vertex 890.905 461.179 13.5209 + vertex 888.958 465.6 11.335 + vertex 888.565 466.234 13.2333 + endloop + endfacet + facet normal 0.840591 0.387696 -0.378283 + outer loop + vertex 889.84 460.595 5.22432 + vertex 887.714 465.188 5.20808 + vertex 890.595 460.685 6.9934 + endloop + endfacet + facet normal 0.843333 0.394941 -0.364433 + outer loop + vertex 890.595 460.685 6.9934 + vertex 887.714 465.188 5.20808 + vertex 888.431 465.31 6.9987 + endloop + endfacet + facet normal 0.838077 0.379433 -0.391992 + outer loop + vertex 891.924 456.004 5.23502 + vertex 889.84 460.595 5.22432 + vertex 892.736 456.024 6.99251 + endloop + endfacet + facet normal 0.841049 0.386565 -0.378422 + outer loop + vertex 892.736 456.024 6.99251 + vertex 889.84 460.595 5.22432 + vertex 890.595 460.685 6.9934 + endloop + endfacet + facet normal 0.884374 0.406446 -0.22953 + outer loop + vertex 892.736 456.024 6.99251 + vertex 890.595 460.685 6.9934 + vertex 893.256 456.059 9.05608 + endloop + endfacet + facet normal 0.88466 0.409868 -0.222225 + outer loop + vertex 893.256 456.059 9.05608 + vertex 890.595 460.685 6.9934 + vertex 891.09 460.745 9.07606 + endloop + endfacet + facet normal 0.883094 0.413378 -0.221954 + outer loop + vertex 890.595 460.685 6.9934 + vertex 888.431 465.31 6.9987 + vertex 891.09 460.745 9.07606 + endloop + endfacet + facet normal 0.883429 0.420587 -0.206543 + outer loop + vertex 891.09 460.745 9.07606 + vertex 888.431 465.31 6.9987 + vertex 888.896 465.368 9.10585 + endloop + endfacet + facet normal 0.634693 0.265916 -0.725571 + outer loop + vertex 887.786 460.399 2.84075 + vertex 886.426 464.004 2.97267 + vertex 888.967 460.37 3.86363 + endloop + endfacet + facet normal 0.671319 0.303652 -0.676111 + outer loop + vertex 888.967 460.37 3.86363 + vertex 886.426 464.004 2.97267 + vertex 886.951 464.778 3.84138 + endloop + endfacet + facet normal 0.613555 0.25837 -0.746187 + outer loop + vertex 889.682 455.789 2.80363 + vertex 887.786 460.399 2.84075 + vertex 890.899 455.932 3.85375 + endloop + endfacet + facet normal 0.632796 0.277022 -0.723068 + outer loop + vertex 890.899 455.932 3.85375 + vertex 887.786 460.399 2.84075 + vertex 888.967 460.37 3.86363 + endloop + endfacet + facet normal 0.750415 0.327881 -0.573909 + outer loop + vertex 890.899 455.932 3.85375 + vertex 888.967 460.37 3.86363 + vertex 891.924 456.004 5.23502 + endloop + endfacet + facet normal 0.763039 0.345018 -0.546566 + outer loop + vertex 891.924 456.004 5.23502 + vertex 888.967 460.37 3.86363 + vertex 889.84 460.595 5.22432 + endloop + endfacet + facet normal 0.762626 0.346071 -0.546476 + outer loop + vertex 888.967 460.37 3.86363 + vertex 886.951 464.778 3.84138 + vertex 889.84 460.595 5.22432 + endloop + endfacet + facet normal 0.76756 0.353344 -0.534789 + outer loop + vertex 889.84 460.595 5.22432 + vertex 886.951 464.778 3.84138 + vertex 887.714 465.188 5.20808 + endloop + endfacet + facet normal 0.317979 0.130424 -0.939084 + outer loop + vertex 884.774 459.597 1.40289 + vertex 882.176 466.283 1.45189 + vertex 886.25 460.473 2.02429 + endloop + endfacet + facet normal 0.354319 0.157612 -0.921747 + outer loop + vertex 886.25 460.473 2.02429 + vertex 882.176 466.283 1.45189 + vertex 884.444 465.592 2.20518 + endloop + endfacet + facet normal 0.317951 0.13207 -0.938863 + outer loop + vertex 887.282 454.37 1.51695 + vertex 884.774 459.597 1.40289 + vertex 888.382 455.329 2.02428 + endloop + endfacet + facet normal 0.317351 0.131522 -0.939143 + outer loop + vertex 888.382 455.329 2.02428 + vertex 884.774 459.597 1.40289 + vertex 886.25 460.473 2.02429 + endloop + endfacet + facet normal 0.455016 0.188575 -0.870287 + outer loop + vertex 888.382 455.329 2.02428 + vertex 886.25 460.473 2.02429 + vertex 889.682 455.789 2.80363 + endloop + endfacet + facet normal 0.467494 0.19922 -0.861255 + outer loop + vertex 889.682 455.789 2.80363 + vertex 886.25 460.473 2.02429 + vertex 887.786 460.399 2.84075 + endloop + endfacet + facet normal 0.467705 0.195513 -0.86199 + outer loop + vertex 886.25 460.473 2.02429 + vertex 884.444 465.592 2.20518 + vertex 887.786 460.399 2.84075 + endloop + endfacet + facet normal 0.499915 0.219195 -0.837877 + outer loop + vertex 887.786 460.399 2.84075 + vertex 884.444 465.592 2.20518 + vertex 886.426 464.004 2.97267 + endloop + endfacet + facet normal 0.234537 0.098211 -0.967133 + outer loop + vertex 882.176 466.283 1.45189 + vertex 884.774 459.597 1.40289 + vertex 880.208 465.209 0.865458 + endloop + endfacet + facet normal 0.207406 0.0782369 -0.975121 + outer loop + vertex 887.282 454.37 1.51695 + vertex 883.955 456.378 0.97052 + vertex 884.774 459.597 1.40289 + endloop + endfacet + facet normal 0.209983 0.0775151 -0.974627 + outer loop + vertex 883.955 456.378 0.97052 + vertex 880.208 465.209 0.865458 + vertex 884.774 459.597 1.40289 + endloop + endfacet + facet normal 0.908574 0.279261 0.310656 + outer loop + vertex 875.838 463.338 27.5218 + vertex 874.513 467.242 27.8898 + vertex 875.792 460.292 30.3959 + endloop + endfacet + facet normal 0.917911 0.271079 0.28975 + outer loop + vertex 873.332 471.469 27.6754 + vertex 873.281 468.847 30.2882 + vertex 874.513 467.242 27.8898 + endloop + endfacet + facet normal 0.917774 0.272942 0.288433 + outer loop + vertex 873.281 468.847 30.2882 + vertex 875.792 460.292 30.3959 + vertex 874.513 467.242 27.8898 + endloop + endfacet + facet normal 0.796166 0.251339 0.550408 + outer loop + vertex 876.168 467.611 24.7084 + vertex 874.686 472.155 24.7765 + vertex 875.255 467.55 26.0568 + endloop + endfacet + facet normal 0.81906 0.245325 0.51861 + outer loop + vertex 875.255 467.55 26.0568 + vertex 874.686 472.155 24.7765 + vertex 873.778 472.146 26.2155 + endloop + endfacet + facet normal 0.788003 0.245982 0.564397 + outer loop + vertex 877.555 463.246 24.6744 + vertex 876.168 467.611 24.7084 + vertex 876.626 463.165 26.0066 + endloop + endfacet + facet normal 0.798061 0.2432 0.551319 + outer loop + vertex 876.626 463.165 26.0066 + vertex 876.168 467.611 24.7084 + vertex 875.255 467.55 26.0568 + endloop + endfacet + facet normal 0.521084 0.18351 0.833544 + outer loop + vertex 878.398 467.673 22.9692 + vertex 876.77 471.749 23.089 + vertex 877.219 467.63 23.7156 + endloop + endfacet + facet normal 0.559765 0.183833 0.808003 + outer loop + vertex 877.219 467.63 23.7156 + vertex 876.77 471.749 23.089 + vertex 875.711 472.089 23.7455 + endloop + endfacet + facet normal 0.511134 0.168522 0.842818 + outer loop + vertex 879.832 462.933 23.0471 + vertex 878.398 467.673 22.9692 + vertex 878.646 463.274 23.6983 + endloop + endfacet + facet normal 0.522969 0.167998 0.835631 + outer loop + vertex 878.646 463.274 23.6983 + vertex 878.398 467.673 22.9692 + vertex 877.219 467.63 23.7156 + endloop + endfacet + facet normal 0.648997 0.209699 0.73132 + outer loop + vertex 878.646 463.274 23.6983 + vertex 877.219 467.63 23.7156 + vertex 877.555 463.246 24.6744 + endloop + endfacet + facet normal 0.669856 0.207286 0.71297 + outer loop + vertex 877.555 463.246 24.6744 + vertex 877.219 467.63 23.7156 + vertex 876.168 467.611 24.7084 + endloop + endfacet + facet normal 0.667667 0.220965 0.710911 + outer loop + vertex 877.219 467.63 23.7156 + vertex 875.711 472.089 23.7455 + vertex 876.168 467.611 24.7084 + endloop + endfacet + facet normal 0.699144 0.217747 0.681017 + outer loop + vertex 876.168 467.611 24.7084 + vertex 875.711 472.089 23.7455 + vertex 874.686 472.155 24.7765 + endloop + endfacet + facet normal 0.459982 0.157938 0.873769 + outer loop + vertex 876.77 471.749 23.089 + vertex 878.398 467.673 22.9692 + vertex 877.069 474.641 22.4091 + endloop + endfacet + facet normal 0.396111 0.13479 0.908255 + outer loop + vertex 879.832 462.933 23.0471 + vertex 880.455 465.663 22.3702 + vertex 878.398 467.673 22.9692 + endloop + endfacet + facet normal 0.408907 0.150318 0.900111 + outer loop + vertex 880.455 465.663 22.3702 + vertex 877.069 474.641 22.4091 + vertex 878.398 467.673 22.9692 + endloop + endfacet + facet normal 0.459112 0.194491 0.866827 + outer loop + vertex 884.561 464.707 21.0774 + vertex 881.807 473.905 20.4722 + vertex 880.606 473.844 21.1222 + endloop + endfacet + facet normal 0.634188 0.289987 0.716737 + outer loop + vertex 886.885 464.933 19.5296 + vertex 882.696 474.074 19.5382 + vertex 885.881 464.807 20.4691 + endloop + endfacet + facet normal 0.664336 0.297241 0.685788 + outer loop + vertex 885.881 464.807 20.4691 + vertex 882.696 474.074 19.5382 + vertex 881.807 473.905 20.4722 + endloop + endfacet + facet normal 0.800145 0.375645 0.46761 + outer loop + vertex 887.97 464.58 17.9562 + vertex 883.608 473.857 17.9681 + vertex 886.885 464.933 19.5296 + endloop + endfacet + facet normal 0.8226 0.376612 0.426019 + outer loop + vertex 886.885 464.933 19.5296 + vertex 883.608 473.857 17.9681 + vertex 882.696 474.074 19.5382 + endloop + endfacet + facet normal 0.857389 0.411983 0.308471 + outer loop + vertex 889.288 463.612 15.5859 + vertex 884.769 473.009 15.5982 + vertex 887.97 464.58 17.9562 + endloop + endfacet + facet normal 0.869042 0.408281 0.279415 + outer loop + vertex 887.97 464.58 17.9562 + vertex 884.769 473.009 15.5982 + vertex 883.608 473.857 17.9681 + endloop + endfacet + facet normal 0.880976 0.426669 0.204536 + outer loop + vertex 888.565 466.234 13.2333 + vertex 886.383 470.578 13.5678 + vertex 889.288 463.612 15.5859 + endloop + endfacet + facet normal 0.880489 0.44231 0.170591 + outer loop + vertex 883.963 475.525 13.2317 + vertex 884.769 473.009 15.5982 + vertex 886.383 470.578 13.5678 + endloop + endfacet + facet normal 0.884118 0.424989 0.194216 + outer loop + vertex 884.769 473.009 15.5982 + vertex 889.288 463.612 15.5859 + vertex 886.383 470.578 13.5678 + endloop + endfacet + facet normal 0.89363 0.443643 -0.0678656 + outer loop + vertex 886.657 469.972 9.12934 + vertex 884.38 474.559 9.13498 + vertex 886.698 470.232 11.3627 + endloop + endfacet + facet normal 0.892495 0.447036 -0.0600939 + outer loop + vertex 886.698 470.232 11.3627 + vertex 884.38 474.559 9.13498 + vertex 884.389 474.842 11.3625 + endloop + endfacet + facet normal 0.896957 0.436505 -0.0702236 + outer loop + vertex 888.896 465.368 9.10585 + vertex 886.657 469.972 9.12934 + vertex 888.958 465.6 11.335 + endloop + endfacet + facet normal 0.896555 0.437799 -0.0672391 + outer loop + vertex 888.958 465.6 11.335 + vertex 886.657 469.972 9.12934 + vertex 886.698 470.232 11.3627 + endloop + endfacet + facet normal 0.898134 0.43793 0.0396482 + outer loop + vertex 888.958 465.6 11.335 + vertex 886.698 470.232 11.3627 + vertex 888.565 466.234 13.2333 + endloop + endfacet + facet normal 0.893926 0.444469 0.0578267 + outer loop + vertex 888.565 466.234 13.2333 + vertex 886.698 470.232 11.3627 + vertex 886.383 470.578 13.5678 + endloop + endfacet + facet normal 0.892643 0.447116 0.0572294 + outer loop + vertex 886.698 470.232 11.3627 + vertex 884.389 474.842 11.3625 + vertex 886.383 470.578 13.5678 + endloop + endfacet + facet normal 0.896306 0.441366 0.042797 + outer loop + vertex 886.383 470.578 13.5678 + vertex 884.389 474.842 11.3625 + vertex 883.963 475.525 13.2317 + endloop + endfacet + facet normal 0.845736 0.404954 -0.34748 + outer loop + vertex 885.539 469.805 5.20553 + vertex 883.333 474.418 5.21464 + vertex 886.227 469.917 7.01187 + endloop + endfacet + facet normal 0.848884 0.415014 -0.327352 + outer loop + vertex 886.227 469.917 7.01187 + vertex 883.333 474.418 5.21464 + vertex 883.986 474.507 7.01818 + endloop + endfacet + facet normal 0.842524 0.396841 -0.364239 + outer loop + vertex 887.714 465.188 5.20808 + vertex 885.539 469.805 5.20553 + vertex 888.431 465.31 6.9987 + endloop + endfacet + facet normal 0.845511 0.405471 -0.347426 + outer loop + vertex 888.431 465.31 6.9987 + vertex 885.539 469.805 5.20553 + vertex 886.227 469.917 7.01187 + endloop + endfacet + facet normal 0.882441 0.422734 -0.206383 + outer loop + vertex 888.431 465.31 6.9987 + vertex 886.227 469.917 7.01187 + vertex 888.896 465.368 9.10585 + endloop + endfacet + facet normal 0.882471 0.430075 -0.190472 + outer loop + vertex 888.896 465.368 9.10585 + vertex 886.227 469.917 7.01187 + vertex 886.657 469.972 9.12934 + endloop + endfacet + facet normal 0.882028 0.431012 -0.190407 + outer loop + vertex 886.227 469.917 7.01187 + vertex 883.986 474.507 7.01818 + vertex 886.657 469.972 9.12934 + endloop + endfacet + facet normal 0.881771 0.437889 -0.175312 + outer loop + vertex 886.657 469.972 9.12934 + vertex 883.986 474.507 7.01818 + vertex 884.38 474.559 9.13498 + endloop + endfacet + facet normal 0.646196 0.296696 -0.703138 + outer loop + vertex 884.085 468.489 2.79097 + vertex 882.179 472.802 2.85975 + vertex 884.813 469.321 3.81177 + endloop + endfacet + facet normal 0.654473 0.306195 -0.69131 + outer loop + vertex 884.813 469.321 3.81177 + vertex 882.179 472.802 2.85975 + vertex 882.628 473.953 3.79433 + endloop + endfacet + facet normal 0.660007 0.31696 -0.681123 + outer loop + vertex 886.426 464.004 2.97267 + vertex 884.085 468.489 2.79097 + vertex 886.951 464.778 3.84138 + endloop + endfacet + facet normal 0.644659 0.29872 -0.703691 + outer loop + vertex 886.951 464.778 3.84138 + vertex 884.085 468.489 2.79097 + vertex 884.813 469.321 3.81177 + endloop + endfacet + facet normal 0.765865 0.356845 -0.534895 + outer loop + vertex 886.951 464.778 3.84138 + vertex 884.813 469.321 3.81177 + vertex 887.714 465.188 5.20808 + endloop + endfacet + facet normal 0.769387 0.362286 -0.526111 + outer loop + vertex 887.714 465.188 5.20808 + vertex 884.813 469.321 3.81177 + vertex 885.539 469.805 5.20553 + endloop + endfacet + facet normal 0.76991 0.361284 -0.526035 + outer loop + vertex 884.813 469.321 3.81177 + vertex 882.628 473.953 3.79433 + vertex 885.539 469.805 5.20553 + endloop + endfacet + facet normal 0.776836 0.372336 -0.507831 + outer loop + vertex 885.539 469.805 5.20553 + vertex 882.628 473.953 3.79433 + vertex 883.333 474.418 5.21464 + endloop + endfacet + facet normal 0.506419 0.230714 -0.83085 + outer loop + vertex 886.426 464.004 2.97267 + vertex 884.444 465.592 2.20518 + vertex 884.085 468.489 2.79097 + endloop + endfacet + facet normal 0.48059 0.225834 -0.847368 + outer loop + vertex 882.179 472.802 2.85975 + vertex 884.085 468.489 2.79097 + vertex 879.912 473.835 1.84886 + endloop + endfacet + facet normal 0.353644 0.154556 -0.922523 + outer loop + vertex 882.176 466.283 1.45189 + vertex 879.912 473.835 1.84886 + vertex 884.444 465.592 2.20518 + endloop + endfacet + facet normal 0.485778 0.230634 -0.843106 + outer loop + vertex 884.085 468.489 2.79097 + vertex 884.444 465.592 2.20518 + vertex 879.912 473.835 1.84886 + endloop + endfacet + facet normal 0.237634 0.0924338 -0.966947 + outer loop + vertex 880.208 465.209 0.865458 + vertex 877.184 473.498 0.914723 + vertex 882.176 466.283 1.45189 + endloop + endfacet + facet normal 0.305158 0.141027 -0.941801 + outer loop + vertex 882.176 466.283 1.45189 + vertex 877.184 473.498 0.914723 + vertex 879.912 473.835 1.84886 + endloop + endfacet + facet normal 0.937659 0.236114 0.255042 + outer loop + vertex 873.332 471.469 27.6754 + vertex 871.973 477.701 26.9001 + vertex 873.281 468.847 30.2882 + endloop + endfacet + facet normal 0.930805 0.242246 0.273714 + outer loop + vertex 873.281 468.847 30.2882 + vertex 871.973 477.701 26.9001 + vertex 870.973 477.239 30.7123 + endloop + endfacet + facet normal 0.816012 0.258994 0.516766 + outer loop + vertex 874.686 472.155 24.7765 + vertex 873.117 476.95 24.8508 + vertex 873.778 472.146 26.2155 + endloop + endfacet + facet normal 0.575674 0.217038 0.788349 + outer loop + vertex 875.198 476.621 22.9977 + vertex 873.542 480.866 23.0384 + vertex 874.135 476.697 23.7526 + endloop + endfacet + facet normal 0.622107 0.217446 0.752131 + outer loop + vertex 874.135 476.697 23.7526 + vertex 873.542 480.866 23.0384 + vertex 872.606 481.379 23.6642 + endloop + endfacet + facet normal 0.56128 0.196244 0.804023 + outer loop + vertex 876.77 471.749 23.089 + vertex 875.198 476.621 22.9977 + vertex 875.711 472.089 23.7455 + endloop + endfacet + facet normal 0.577241 0.196177 0.792658 + outer loop + vertex 875.711 472.089 23.7455 + vertex 875.198 476.621 22.9977 + vertex 874.135 476.697 23.7526 + endloop + endfacet + facet normal 0.69654 0.237149 0.677195 + outer loop + vertex 875.711 472.089 23.7455 + vertex 874.135 476.697 23.7526 + vertex 874.686 472.155 24.7765 + endloop + endfacet + facet normal 0.739427 0.23215 0.631944 + outer loop + vertex 874.686 472.155 24.7765 + vertex 874.135 476.697 23.7526 + vertex 873.117 476.95 24.8508 + endloop + endfacet + facet normal 0.737897 0.252893 0.625742 + outer loop + vertex 874.135 476.697 23.7526 + vertex 872.606 481.379 23.6642 + vertex 873.117 476.95 24.8508 + endloop + endfacet + facet normal 0.766325 0.247382 0.592915 + outer loop + vertex 873.117 476.95 24.8508 + vertex 872.606 481.379 23.6642 + vertex 871.808 481.56 24.6194 + endloop + endfacet + facet normal 0.436996 0.162013 0.884752 + outer loop + vertex 873.542 480.866 23.0384 + vertex 875.198 476.621 22.9977 + vertex 873.89 483.678 22.3516 + endloop + endfacet + facet normal 0.446931 0.160753 0.880006 + outer loop + vertex 876.77 471.749 23.089 + vertex 877.069 474.641 22.4091 + vertex 875.198 476.621 22.9977 + endloop + endfacet + facet normal 0.449491 0.163725 0.878152 + outer loop + vertex 877.069 474.641 22.4091 + vertex 873.89 483.678 22.3516 + vertex 875.198 476.621 22.9977 + endloop + endfacet + facet normal 0.408157 0.149325 0.900616 + outer loop + vertex 877.069 474.641 22.4091 + vertex 875.358 483.349 21.7407 + vertex 873.89 483.678 22.3516 + endloop + endfacet + facet normal 0.42265 0.163514 0.89142 + outer loop + vertex 878.97 474.126 21.7198 + vertex 876.634 483.189 21.165 + vertex 875.358 483.349 21.7407 + endloop + endfacet + facet normal 0.458046 0.202313 0.8656 + outer loop + vertex 881.807 473.905 20.4722 + vertex 877.651 483.235 20.491 + vertex 880.606 473.844 21.1222 + endloop + endfacet + facet normal 0.531752 0.222254 0.817217 + outer loop + vertex 880.606 473.844 21.1222 + vertex 877.651 483.235 20.491 + vertex 876.634 483.189 21.165 + endloop + endfacet + facet normal 0.662673 0.302407 0.685138 + outer loop + vertex 882.696 474.074 19.5382 + vertex 878.426 483.405 19.5498 + vertex 881.807 473.905 20.4722 + endloop + endfacet + facet normal 0.704803 0.312707 0.636763 + outer loop + vertex 881.807 473.905 20.4722 + vertex 878.426 483.405 19.5498 + vertex 877.651 483.235 20.491 + endloop + endfacet + facet normal 0.821808 0.379267 0.425191 + outer loop + vertex 883.608 473.857 17.9681 + vertex 879.149 483.4 18.0751 + vertex 882.696 474.074 19.5382 + endloop + endfacet + facet normal 0.831085 0.379823 0.406242 + outer loop + vertex 882.696 474.074 19.5382 + vertex 879.149 483.4 18.0751 + vertex 878.426 483.405 19.5498 + endloop + endfacet + facet normal 0.86471 0.421999 0.272384 + outer loop + vertex 884.769 473.009 15.5982 + vertex 880.111 482.513 15.6589 + vertex 883.608 473.857 17.9681 + endloop + endfacet + facet normal 0.888099 0.412747 0.202286 + outer loop + vertex 883.608 473.857 17.9681 + vertex 880.111 482.513 15.6589 + vertex 879.149 483.4 18.0751 + endloop + endfacet + facet normal 0.877482 0.446234 0.175787 + outer loop + vertex 883.963 475.525 13.2317 + vertex 881.692 479.874 13.5289 + vertex 884.769 473.009 15.5982 + endloop + endfacet + facet normal 0.886358 0.452761 0.0968307 + outer loop + vertex 879.191 484.845 13.176 + vertex 880.111 482.513 15.6589 + vertex 881.692 479.874 13.5289 + endloop + endfacet + facet normal 0.891651 0.436166 0.121317 + outer loop + vertex 880.111 482.513 15.6589 + vertex 884.769 473.009 15.5982 + vertex 881.692 479.874 13.5289 + endloop + endfacet + facet normal 0.890399 0.451991 -0.0537956 + outer loop + vertex 882.047 479.147 9.11533 + vertex 879.696 483.773 9.07324 + vertex 882.02 479.463 11.3229 + endloop + endfacet + facet normal 0.888906 0.455896 -0.0447717 + outer loop + vertex 882.02 479.463 11.3229 + vertex 879.696 483.773 9.07324 + vertex 879.631 484.115 11.2723 + endloop + endfacet + facet normal 0.889793 0.452302 -0.0607514 + outer loop + vertex 884.38 474.559 9.13498 + vertex 882.047 479.147 9.11533 + vertex 884.389 474.842 11.3625 + endloop + endfacet + facet normal 0.88877 0.455131 -0.0542648 + outer loop + vertex 884.389 474.842 11.3625 + vertex 882.047 479.147 9.11533 + vertex 882.02 479.463 11.3229 + endloop + endfacet + facet normal 0.889198 0.456122 0.035785 + outer loop + vertex 884.389 474.842 11.3625 + vertex 882.02 479.463 11.3229 + vertex 883.963 475.525 13.2317 + endloop + endfacet + facet normal 0.886751 0.459937 0.0461466 + outer loop + vertex 883.963 475.525 13.2317 + vertex 882.02 479.463 11.3229 + vertex 881.692 479.874 13.5289 + endloop + endfacet + facet normal 0.88841 0.456639 0.047008 + outer loop + vertex 882.02 479.463 11.3229 + vertex 879.631 484.115 11.2723 + vertex 881.692 479.874 13.5289 + endloop + endfacet + facet normal 0.891887 0.451031 0.0332938 + outer loop + vertex 881.692 479.874 13.5289 + vertex 879.631 484.115 11.2723 + vertex 879.191 484.845 13.176 + endloop + endfacet + facet normal 0.858705 0.416825 -0.298131 + outer loop + vertex 881.115 478.998 5.21291 + vertex 878.902 483.551 5.2041 + vertex 881.707 479.067 7.01669 + endloop + endfacet + facet normal 0.861149 0.427972 -0.274338 + outer loop + vertex 881.707 479.067 7.01669 + vertex 878.902 483.551 5.2041 + vertex 879.428 483.639 6.99239 + endloop + endfacet + facet normal 0.850314 0.411791 -0.327712 + outer loop + vertex 883.333 474.418 5.21464 + vertex 881.115 478.998 5.21291 + vertex 883.986 474.507 7.01818 + endloop + endfacet + facet normal 0.854252 0.426635 -0.297045 + outer loop + vertex 883.986 474.507 7.01818 + vertex 881.115 478.998 5.21291 + vertex 881.707 479.067 7.01669 + endloop + endfacet + facet normal 0.880782 0.439927 -0.175178 + outer loop + vertex 883.986 474.507 7.01818 + vertex 881.707 479.067 7.01669 + vertex 884.38 474.559 9.13498 + endloop + endfacet + facet normal 0.880215 0.447007 -0.159395 + outer loop + vertex 884.38 474.559 9.13498 + vertex 881.707 479.067 7.01669 + vertex 882.047 479.147 9.11533 + endloop + endfacet + facet normal 0.883756 0.439855 -0.159696 + outer loop + vertex 881.707 479.067 7.01669 + vertex 879.428 483.639 6.99239 + vertex 882.047 479.147 9.11533 + endloop + endfacet + facet normal 0.882888 0.447365 -0.142734 + outer loop + vertex 882.047 479.147 9.11533 + vertex 879.428 483.639 6.99239 + vertex 879.696 483.773 9.07324 + endloop + endfacet + facet normal 0.66826 0.293624 -0.68353 + outer loop + vertex 879.721 477.684 2.70163 + vertex 877.872 482.197 2.83286 + vertex 880.445 478.586 3.79728 + endloop + endfacet + facet normal 0.696411 0.325409 -0.639625 + outer loop + vertex 880.445 478.586 3.79728 + vertex 877.872 482.197 2.83286 + vertex 878.292 483.171 3.78507 + endloop + endfacet + facet normal 0.653762 0.306801 -0.691714 + outer loop + vertex 882.179 472.802 2.85975 + vertex 879.721 477.684 2.70163 + vertex 882.628 473.953 3.79433 + endloop + endfacet + facet normal 0.655954 0.309467 -0.688443 + outer loop + vertex 882.628 473.953 3.79433 + vertex 879.721 477.684 2.70163 + vertex 880.445 478.586 3.79728 + endloop + endfacet + facet normal 0.779358 0.367489 -0.507497 + outer loop + vertex 882.628 473.953 3.79433 + vertex 880.445 478.586 3.79728 + vertex 883.333 474.418 5.21464 + endloop + endfacet + facet normal 0.787779 0.381439 -0.48364 + outer loop + vertex 883.333 474.418 5.21464 + vertex 880.445 478.586 3.79728 + vertex 881.115 478.998 5.21291 + endloop + endfacet + facet normal 0.792982 0.371186 -0.483116 + outer loop + vertex 880.445 478.586 3.79728 + vertex 878.292 483.171 3.78507 + vertex 881.115 478.998 5.21291 + endloop + endfacet + facet normal 0.803576 0.389734 -0.449858 + outer loop + vertex 881.115 478.998 5.21291 + vertex 878.292 483.171 3.78507 + vertex 878.902 483.551 5.2041 + endloop + endfacet + facet normal 0.573873 0.257686 -0.777347 + outer loop + vertex 877.872 482.197 2.83286 + vertex 879.721 477.684 2.70163 + vertex 875.744 483.855 1.81144 + endloop + endfacet + facet normal 0.476978 0.212561 -0.852825 + outer loop + vertex 882.179 472.802 2.85975 + vertex 879.912 473.835 1.84886 + vertex 879.721 477.684 2.70163 + endloop + endfacet + facet normal 0.512119 0.209881 -0.832877 + outer loop + vertex 879.912 473.835 1.84886 + vertex 875.744 483.855 1.81144 + vertex 879.721 477.684 2.70163 + endloop + endfacet + facet normal 0.309426 0.113062 -0.944178 + outer loop + vertex 877.184 473.498 0.914723 + vertex 874.076 482.42 0.964467 + vertex 879.912 473.835 1.84886 + endloop + endfacet + facet normal 0.348647 0.141543 -0.926504 + outer loop + vertex 879.912 473.835 1.84886 + vertex 874.076 482.42 0.964467 + vertex 875.744 483.855 1.81144 + endloop + endfacet + facet normal 0.947923 0.169859 0.269426 + outer loop + vertex 871.973 477.701 26.9001 + vertex 870.02 488.074 27.2322 + vertex 870.973 477.239 30.7123 + endloop + endfacet + facet normal 0.956896 0.161617 0.24131 + outer loop + vertex 870.973 477.239 30.7123 + vertex 870.02 488.074 27.2322 + vertex 869.457 485.556 31.1534 + endloop + endfacet + facet normal 0.66383 0.0883946 0.742641 + outer loop + vertex 872.225 485.933 22.8479 + vertex 871.258 491.534 23.0455 + vertex 871.332 486.116 23.6241 + endloop + endfacet + facet normal 0.859001 0.0659727 0.507706 + outer loop + vertex 871.332 486.116 23.6241 + vertex 871.258 491.534 23.0455 + vertex 870.882 490.904 23.7635 + endloop + endfacet + facet normal 0.615228 0.188672 0.765439 + outer loop + vertex 873.542 480.866 23.0384 + vertex 872.225 485.933 22.8479 + vertex 872.606 481.379 23.6642 + endloop + endfacet + facet normal 0.666167 0.185226 0.722435 + outer loop + vertex 872.606 481.379 23.6642 + vertex 872.225 485.933 22.8479 + vertex 871.332 486.116 23.6241 + endloop + endfacet + facet normal 0.769569 0.212006 0.602343 + outer loop + vertex 872.606 481.379 23.6642 + vertex 871.332 486.116 23.6241 + vertex 871.808 481.56 24.6194 + endloop + endfacet + facet normal 0.882762 0.186455 0.431236 + outer loop + vertex 871.808 481.56 24.6194 + vertex 871.332 486.116 23.6241 + vertex 870.775 485.623 24.9776 + endloop + endfacet + facet normal 0.912436 0.0740615 0.402462 + outer loop + vertex 871.332 486.116 23.6241 + vertex 870.882 490.904 23.7635 + vertex 870.775 485.623 24.9776 + endloop + endfacet + facet normal 0.92058 0.0697174 0.38428 + outer loop + vertex 870.775 485.623 24.9776 + vertex 870.882 490.904 23.7635 + vertex 870.541 490.071 24.7314 + endloop + endfacet + facet normal 0.695251 0.0948823 0.712477 + outer loop + vertex 871.258 491.534 23.0455 + vertex 872.225 485.933 22.8479 + vertex 872.094 492.324 22.1242 + endloop + endfacet + facet normal 0.468541 0.15447 0.869833 + outer loop + vertex 873.542 480.866 23.0384 + vertex 873.89 483.678 22.3516 + vertex 872.225 485.933 22.8479 + endloop + endfacet + facet normal 0.418582 0.11063 0.901416 + outer loop + vertex 873.89 483.678 22.3516 + vertex 872.094 492.324 22.1242 + vertex 872.225 485.933 22.8479 + endloop + endfacet + facet normal 0.404394 0.12174 0.906446 + outer loop + vertex 875.358 483.349 21.7407 + vertex 872.84 492.666 21.6128 + vertex 873.89 483.678 22.3516 + endloop + endfacet + facet normal 0.519525 0.130094 0.844494 + outer loop + vertex 873.89 483.678 22.3516 + vertex 872.84 492.666 21.6128 + vertex 872.094 492.324 22.1242 + endloop + endfacet + facet normal 0.421682 0.139338 0.895974 + outer loop + vertex 876.634 483.189 21.165 + vertex 873.484 492.862 21.1434 + vertex 875.358 483.349 21.7407 + endloop + endfacet + facet normal 0.549344 0.159736 0.820186 + outer loop + vertex 875.358 483.349 21.7407 + vertex 873.484 492.862 21.1434 + vertex 872.84 492.666 21.6128 + endloop + endfacet + facet normal 0.535915 0.194276 0.821616 + outer loop + vertex 877.651 483.235 20.491 + vertex 874.139 493.056 20.4593 + vertex 876.634 483.189 21.165 + endloop + endfacet + facet normal 0.672272 0.220536 0.706693 + outer loop + vertex 876.634 483.189 21.165 + vertex 874.139 493.056 20.4593 + vertex 873.484 492.862 21.1434 + endloop + endfacet + facet normal 0.718934 0.269731 0.640608 + outer loop + vertex 878.426 483.405 19.5498 + vertex 874.685 493.221 19.6154 + vertex 877.651 483.235 20.491 + endloop + endfacet + facet normal 0.780195 0.280771 0.558984 + outer loop + vertex 877.651 483.235 20.491 + vertex 874.685 493.221 19.6154 + vertex 874.139 493.056 20.4593 + endloop + endfacet + facet normal 0.850408 0.322226 0.415905 + outer loop + vertex 879.149 483.4 18.0751 + vertex 875.213 493.382 18.3889 + vertex 878.426 483.405 19.5498 + endloop + endfacet + facet normal 0.853172 0.322434 0.410041 + outer loop + vertex 878.426 483.405 19.5498 + vertex 875.213 493.382 18.3889 + vertex 874.685 493.221 19.6154 + endloop + endfacet + facet normal 0.908709 0.344648 0.235513 + outer loop + vertex 880.111 482.513 15.6589 + vertex 875.708 493.534 16.5196 + vertex 879.149 483.4 18.0751 + endloop + endfacet + facet normal 0.899484 0.346273 0.266501 + outer loop + vertex 879.149 483.4 18.0751 + vertex 875.708 493.534 16.5196 + vertex 875.213 493.382 18.3889 + endloop + endfacet + facet normal 0.916444 0.398642 0.0348488 + outer loop + vertex 879.191 484.845 13.176 + vertex 877.217 489.343 13.6318 + vertex 880.111 482.513 15.6589 + endloop + endfacet + facet normal 0.958336 0.250555 0.137168 + outer loop + vertex 876.111 493.657 13.4843 + vertex 875.708 493.534 16.5196 + vertex 877.217 489.343 13.6318 + endloop + endfacet + facet normal 0.925361 0.374355 -0.0597197 + outer loop + vertex 875.708 493.534 16.5196 + vertex 880.111 482.513 15.6589 + vertex 877.217 489.343 13.6318 + endloop + endfacet + facet normal 0.963827 0.266449 -0.00655112 + outer loop + vertex 877.54 488.55 9.03849 + vertex 876.132 493.64 8.9815 + vertex 877.471 488.856 11.255 + endloop + endfacet + facet normal 0.966639 0.25375 -0.034932 + outer loop + vertex 877.471 488.856 11.255 + vertex 876.132 493.64 8.9815 + vertex 876.205 493.68 11.2788 + endloop + endfacet + facet normal 0.910927 0.410895 -0.0371139 + outer loop + vertex 879.696 483.773 9.07324 + vertex 877.54 488.55 9.03849 + vertex 879.631 484.115 11.2723 + endloop + endfacet + facet normal 0.909593 0.414509 -0.0286901 + outer loop + vertex 879.631 484.115 11.2723 + vertex 877.54 488.55 9.03849 + vertex 877.471 488.856 11.255 + endloop + endfacet + facet normal 0.908663 0.414377 0.0512183 + outer loop + vertex 879.631 484.115 11.2723 + vertex 877.471 488.856 11.255 + vertex 879.191 484.845 13.176 + endloop + endfacet + facet normal 0.916173 0.400485 0.0154861 + outer loop + vertex 879.191 484.845 13.176 + vertex 877.471 488.856 11.255 + vertex 877.217 489.343 13.6318 + endloop + endfacet + facet normal 0.966073 0.253178 0.0510213 + outer loop + vertex 877.471 488.856 11.255 + vertex 876.205 493.68 11.2788 + vertex 877.217 489.343 13.6318 + endloop + endfacet + facet normal 0.967328 0.249677 0.0440294 + outer loop + vertex 877.217 489.343 13.6318 + vertex 876.205 493.68 11.2788 + vertex 876.111 493.657 13.4843 + endloop + endfacet + facet normal 0.932975 0.256232 -0.252789 + outer loop + vertex 876.875 488.242 5.19146 + vertex 875.435 493.344 5.04799 + vertex 877.32 488.371 6.96216 + endloop + endfacet + facet normal 0.933607 0.258123 -0.248497 + outer loop + vertex 877.32 488.371 6.96216 + vertex 875.435 493.344 5.04799 + vertex 875.886 493.533 6.9396 + endloop + endfacet + facet normal 0.882048 0.380301 -0.278141 + outer loop + vertex 878.902 483.551 5.2041 + vertex 876.875 488.242 5.19146 + vertex 879.428 483.639 6.99239 + endloop + endfacet + facet normal 0.884886 0.392649 -0.250606 + outer loop + vertex 879.428 483.639 6.99239 + vertex 876.875 488.242 5.19146 + vertex 877.32 488.371 6.96216 + endloop + endfacet + facet normal 0.904443 0.402052 -0.142607 + outer loop + vertex 879.428 483.639 6.99239 + vertex 877.32 488.371 6.96216 + vertex 879.696 483.773 9.07324 + endloop + endfacet + facet normal 0.90394 0.407057 -0.131139 + outer loop + vertex 879.696 483.773 9.07324 + vertex 877.32 488.371 6.96216 + vertex 877.54 488.55 9.03849 + endloop + endfacet + facet normal 0.956203 0.264939 -0.124434 + outer loop + vertex 877.32 488.371 6.96216 + vertex 875.886 493.533 6.9396 + vertex 877.54 488.55 9.03849 + endloop + endfacet + facet normal 0.956133 0.26295 -0.129102 + outer loop + vertex 877.54 488.55 9.03849 + vertex 875.886 493.533 6.9396 + vertex 876.132 493.64 8.9815 + endloop + endfacet + facet normal 0.792048 0.195 -0.578477 + outer loop + vertex 875.672 487.041 2.63289 + vertex 874.31 492.875 2.73455 + vertex 876.278 487.954 3.7709 + endloop + endfacet + facet normal 0.814538 0.212111 -0.539942 + outer loop + vertex 876.278 487.954 3.7709 + vertex 874.31 492.875 2.73455 + vertex 874.945 493.139 3.79698 + endloop + endfacet + facet normal 0.719964 0.301199 -0.625244 + outer loop + vertex 877.872 482.197 2.83286 + vertex 875.672 487.041 2.63289 + vertex 878.292 483.171 3.78507 + endloop + endfacet + facet normal 0.719966 0.301201 -0.625241 + outer loop + vertex 878.292 483.171 3.78507 + vertex 875.672 487.041 2.63289 + vertex 876.278 487.954 3.7709 + endloop + endfacet + facet normal 0.824836 0.345871 -0.447234 + outer loop + vertex 878.292 483.171 3.78507 + vertex 876.278 487.954 3.7709 + vertex 878.902 483.551 5.2041 + endloop + endfacet + facet normal 0.832482 0.3585 -0.422436 + outer loop + vertex 878.902 483.551 5.2041 + vertex 876.278 487.954 3.7709 + vertex 876.875 488.242 5.19146 + endloop + endfacet + facet normal 0.880199 0.228367 -0.41605 + outer loop + vertex 876.278 487.954 3.7709 + vertex 874.945 493.139 3.79698 + vertex 876.875 488.242 5.19146 + endloop + endfacet + facet normal 0.889936 0.240291 -0.387651 + outer loop + vertex 876.875 488.242 5.19146 + vertex 874.945 493.139 3.79698 + vertex 875.435 493.344 5.04799 + endloop + endfacet + facet normal 0.628468 0.159993 -0.761203 + outer loop + vertex 874.31 492.875 2.73455 + vertex 875.672 487.041 2.63289 + vertex 872.947 492.317 1.4917 + endloop + endfacet + facet normal 0.555764 0.219327 -0.801887 + outer loop + vertex 877.872 482.197 2.83286 + vertex 875.744 483.855 1.81144 + vertex 875.672 487.041 2.63289 + endloop + endfacet + facet normal 0.678833 0.197693 -0.70718 + outer loop + vertex 875.744 483.855 1.81144 + vertex 872.947 492.317 1.4917 + vertex 875.672 487.041 2.63289 + endloop + endfacet + facet normal 0.38251 0.0976162 -0.91878 + outer loop + vertex 874.076 482.42 0.964467 + vertex 871.294 491.673 0.789366 + vertex 875.744 483.855 1.81144 + endloop + endfacet + facet normal 0.361652 0.0844756 -0.928478 + outer loop + vertex 875.744 483.855 1.81144 + vertex 871.294 491.673 0.789366 + vertex 872.947 492.317 1.4917 + endloop + endfacet + facet normal 0.110251 -0.185501 -0.976439 + outer loop + vertex 872.775 195.776 2.12094 + vertex 870.892 198.695 1.35385 + vertex 873.524 198.898 1.61255 + endloop + endfacet + facet normal 0.246582 -0.276124 -0.928953 + outer loop + vertex 874.346 193.47 3.2235 + vertex 872.775 195.776 2.12094 + vertex 875.67 196.979 2.53175 + endloop + endfacet + facet normal 0.361679 -0.379156 -0.851721 + outer loop + vertex 875.747 191.803 4.56028 + vertex 874.346 193.47 3.2235 + vertex 876.943 194.724 3.76823 + endloop + endfacet + facet normal 0.411879 -0.554941 -0.722769 + outer loop + vertex 876.285 190.533 5.84204 + vertex 875.747 191.803 4.56028 + vertex 877.157 192.003 5.21094 + endloop + endfacet + facet normal 0.574631 -0.636306 -0.514698 + outer loop + vertex 877.268 190.523 6.95203 + vertex 876.285 190.533 5.84204 + vertex 877.721 191.822 5.85222 + endloop + endfacet + facet normal 0.596073 -0.735589 -0.321879 + outer loop + vertex 876.968 189.576 8.56137 + vertex 877.268 190.523 6.95203 + vertex 878.151 190.96 7.58807 + endloop + endfacet + facet normal 0.644353 -0.764264 -0.0266413 + outer loop + vertex 876.536 189.151 10.3036 + vertex 876.968 189.576 8.56137 + vertex 878.102 190.497 9.5526 + endloop + endfacet + facet normal 0.626306 -0.712071 0.317327 + outer loop + vertex 876.437 189.776 11.9019 + vertex 876.536 189.151 10.3036 + vertex 877.995 190.655 10.799 + endloop + endfacet + facet normal 0.514008 -0.625871 0.586585 + outer loop + vertex 875.871 190.727 13.4124 + vertex 876.437 189.776 11.9019 + vertex 877.547 191.229 12.4792 + endloop + endfacet + facet normal 0.432099 -0.470428 0.769408 + outer loop + vertex 874.802 191.972 14.7739 + vertex 875.871 190.727 13.4124 + vertex 877.016 192.796 14.0346 + endloop + endfacet + facet normal 0.323148 -0.340002 0.883161 + outer loop + vertex 873.795 193.747 15.8256 + vertex 874.802 191.972 14.7739 + vertex 876.343 194.425 15.1545 + endloop + endfacet + facet normal 0.212071 -0.236833 0.948122 + outer loop + vertex 872.261 195.678 16.6513 + vertex 873.795 193.747 15.8256 + vertex 875.303 196.342 16.1367 + endloop + endfacet + facet normal 0.119294 -0.150823 0.981337 + outer loop + vertex 869.356 198.16 17.3858 + vertex 872.261 195.678 16.6513 + vertex 873.86 198.067 16.824 + endloop + endfacet + facet normal 0.139474 -0.0860072 0.986484 + outer loop + vertex 859.334 217.3 19.4814 + vertex 860.538 213.636 18.9917 + vertex 861.321 217.608 19.2273 + endloop + endfacet + facet normal 0.184986 -0.156511 0.970198 + outer loop + vertex 858.209 219.591 20.0655 + vertex 859.334 217.3 19.4814 + vertex 860.927 219.675 19.5607 + endloop + endfacet + facet normal 0.240096 -0.22058 0.945356 + outer loop + vertex 856.825 221.106 20.7705 + vertex 858.209 219.591 20.0655 + vertex 859.682 221.623 20.1656 + endloop + endfacet + facet normal 0.319537 -0.308551 0.895931 + outer loop + vertex 855.566 222.339 21.6441 + vertex 856.825 221.106 20.7705 + vertex 858.219 223.06 20.9463 + endloop + endfacet + facet normal 0.38377 -0.726552 0.569949 + outer loop + vertex 850.002 244.1 46.5611 + vertex 847.08 242.431 46.4005 + vertex 850.228 243.109 45.1458 + endloop + endfacet + facet normal 0.511666 -0.748112 0.422523 + outer loop + vertex 852.241 245.873 46.9897 + vertex 850.002 244.1 46.5611 + vertex 854.072 246.585 46.0335 + endloop + endfacet + facet normal 0.522923 -0.70893 0.473253 + outer loop + vertex 855.962 248.817 47.2881 + vertex 852.241 245.873 46.9897 + vertex 854.072 246.585 46.0335 + endloop + endfacet + facet normal 0.581024 -0.712065 0.394176 + outer loop + vertex 860.887 253.13 47.8191 + vertex 855.962 248.817 47.2881 + vertex 859.794 251.509 46.5029 + endloop + endfacet + facet normal 0.645778 -0.729506 0.225371 + outer loop + vertex 863.98 255.981 48.1831 + vertex 860.887 253.13 47.8191 + vertex 865.171 256.726 47.1826 + endloop + endfacet + facet normal 0.669648 -0.685017 0.286921 + outer loop + vertex 866.254 258.238 48.2666 + vertex 863.98 255.981 48.1831 + vertex 865.171 256.726 47.1826 + endloop + endfacet + facet normal 0.706702 -0.666892 0.236278 + outer loop + vertex 867.909 260.111 48.6002 + vertex 866.254 258.238 48.2666 + vertex 870.388 262.425 47.7207 + endloop + endfacet + facet normal 0.70646 -0.671867 0.222505 + outer loop + vertex 869.982 262.309 48.6581 + vertex 867.909 260.111 48.6002 + vertex 870.388 262.425 47.7207 + endloop + endfacet + facet normal 0.740663 -0.626393 0.243001 + outer loop + vertex 872.266 265.041 48.7403 + vertex 869.982 262.309 48.6581 + vertex 870.388 262.425 47.7207 + endloop + endfacet + facet normal 0.759574 -0.631606 0.155312 + outer loop + vertex 874.318 267.542 48.873 + vertex 872.266 265.041 48.7403 + vertex 875.574 268.843 48.0216 + endloop + endfacet + facet normal 0.770395 -0.596694 0.224606 + outer loop + vertex 875.285 268.807 48.9177 + vertex 874.318 267.542 48.873 + vertex 875.574 268.843 48.0216 + endloop + endfacet + facet normal 0.787994 -0.570564 0.23135 + outer loop + vertex 877.151 271.401 48.9583 + vertex 875.285 268.807 48.9177 + vertex 875.574 268.843 48.0216 + endloop + endfacet + facet normal 0.797859 -0.574515 0.18263 + outer loop + vertex 879.187 274.253 49.037 + vertex 877.151 271.401 48.9583 + vertex 880.008 275.094 48.0942 + endloop + endfacet + facet normal 0.812774 -0.534809 0.231039 + outer loop + vertex 880.767 276.637 48.9955 + vertex 879.187 274.253 49.037 + vertex 880.008 275.094 48.0942 + endloop + endfacet + facet normal 0.836389 -0.517188 0.181574 + outer loop + vertex 881.976 278.679 49.2433 + vertex 880.767 276.637 48.9955 + vertex 883.834 281.37 48.3492 + endloop + endfacet + facet normal 0.836424 -0.52064 0.171258 + outer loop + vertex 883.515 281.143 49.2174 + vertex 881.976 278.679 49.2433 + vertex 883.834 281.37 48.3492 + endloop + endfacet + facet normal 0.860127 -0.472329 0.192582 + outer loop + vertex 885.289 284.379 49.2328 + vertex 883.515 281.143 49.2174 + vertex 883.834 281.37 48.3492 + endloop + endfacet + facet normal 0.873976 -0.469007 0.127275 + outer loop + vertex 887.021 287.625 49.2953 + vertex 885.289 284.379 49.2328 + vertex 887.663 288.568 48.3636 + endloop + endfacet + facet normal 0.888001 -0.420565 0.185956 + outer loop + vertex 888.305 290.313 49.2477 + vertex 887.021 287.625 49.2953 + vertex 887.663 288.568 48.3636 + endloop + endfacet + facet normal 0.908803 -0.399296 0.120993 + outer loop + vertex 889.286 292.616 49.4759 + vertex 888.305 290.313 49.2477 + vertex 890.73 295.624 48.5581 + endloop + endfacet + facet normal 0.908796 -0.397842 0.125745 + outer loop + vertex 890.482 295.33 49.4221 + vertex 889.286 292.616 49.4759 + vertex 890.73 295.624 48.5581 + endloop + endfacet + facet normal 0.926575 -0.345476 0.148679 + outer loop + vertex 891.783 298.811 49.4031 + vertex 890.482 295.33 49.4221 + vertex 890.73 295.624 48.5581 + endloop + endfacet + facet normal 0.939402 -0.333084 0.0811142 + outer loop + vertex 893.086 302.5 49.4535 + vertex 891.783 298.811 49.4031 + vertex 893.603 303.729 48.5166 + endloop + endfacet + facet normal 0.947362 -0.280199 0.154898 + outer loop + vertex 894.184 306.235 49.4992 + vertex 893.086 302.5 49.4535 + vertex 893.603 303.729 48.5166 + endloop + endfacet + facet normal 0.962355 -0.271628 0.00949523 + outer loop + vertex 895.076 309.402 49.5932 + vertex 894.184 306.235 49.4992 + vertex 895.666 311.459 48.716 + endloop + endfacet + facet normal 0.966985 -0.235611 0.0970922 + outer loop + vertex 895.468 311.012 49.6049 + vertex 895.076 309.402 49.5932 + vertex 895.666 311.459 48.716 + endloop + endfacet + facet normal 0.973962 -0.191972 0.120597 + outer loop + vertex 896.125 314.316 49.5531 + vertex 895.468 311.012 49.6049 + vertex 895.666 311.459 48.716 + endloop + endfacet + facet normal 0.981186 -0.185597 0.0531816 + outer loop + vertex 896.847 318.13 49.5486 + vertex 896.125 314.316 49.5531 + vertex 897.182 319.623 48.5846 + endloop + endfacet + facet normal 0.981696 -0.130454 0.13876 + outer loop + vertex 897.372 322.053 49.5241 + vertex 896.847 318.13 49.5486 + vertex 897.182 319.623 48.5846 + endloop + endfacet + facet normal 0.992607 -0.110859 0.049418 + outer loop + vertex 897.805 325.944 49.5502 + vertex 897.372 322.053 49.5241 + vertex 898.048 327.702 48.609 + endloop + endfacet + facet normal 0.988091 -0.0610906 0.141224 + outer loop + vertex 898.048 329.9 49.5602 + vertex 897.805 325.944 49.5502 + vertex 898.048 327.702 48.609 + endloop + endfacet + facet normal 0.998751 -0.0498816 -0.00270732 + outer loop + vertex 898.227 333.473 49.6229 + vertex 898.048 329.9 49.5602 + vertex 898.361 336.207 48.7653 + endloop + endfacet + facet normal 0.992942 -0.0117255 0.118018 + outer loop + vertex 898.249 336.135 49.6974 + vertex 898.227 333.473 49.6229 + vertex 898.361 336.207 48.7653 + endloop + endfacet + facet normal 0.992864 0.00362312 0.119194 + outer loop + vertex 898.257 340.033 49.5149 + vertex 898.249 336.135 49.6974 + vertex 898.361 336.207 48.7653 + endloop + endfacet + facet normal 0.992405 0.030069 0.119283 + outer loop + vertex 898.119 343.852 49.6968 + vertex 898.257 340.033 49.5149 + vertex 898.203 345.237 48.6549 + endloop + endfacet + facet normal 0.987989 0.0504651 0.146052 + outer loop + vertex 897.922 348.237 49.5195 + vertex 898.119 343.852 49.6968 + vertex 898.203 345.237 48.6549 + endloop + endfacet + facet normal 0.987826 0.0762476 0.135599 + outer loop + vertex 897.608 351.967 49.7054 + vertex 897.922 348.237 49.5195 + vertex 897.614 353.744 48.6613 + endloop + endfacet + facet normal 0.982964 0.090566 0.159939 + outer loop + vertex 897.222 356.481 49.5241 + vertex 897.608 351.967 49.7054 + vertex 897.614 353.744 48.6613 + endloop + endfacet + facet normal 0.987744 0.111619 0.109105 + outer loop + vertex 896.832 359.742 49.7141 + vertex 897.222 356.481 49.5241 + vertex 896.628 362.477 48.7628 + endloop + endfacet + facet normal 0.984942 0.117554 0.126769 + outer loop + vertex 896.486 362.735 49.6283 + vertex 896.832 359.742 49.7141 + vertex 896.628 362.477 48.7628 + endloop + endfacet + facet normal 0.98282 0.140593 0.119576 + outer loop + vertex 895.956 366.482 49.583 + vertex 896.486 362.735 49.6283 + vertex 896.628 362.477 48.7628 + endloop + endfacet + facet normal 0.981519 0.148107 0.121179 + outer loop + vertex 895.353 370.465 49.5934 + vertex 895.956 366.482 49.583 + vertex 895.335 371.373 48.6326 + endloop + endfacet + facet normal 0.975575 0.168672 0.140725 + outer loop + vertex 894.661 374.464 49.6024 + vertex 895.353 370.465 49.5934 + vertex 895.335 371.373 48.6326 + endloop + endfacet + facet normal 0.97569 0.177147 0.129025 + outer loop + vertex 893.93 378.447 49.6587 + vertex 894.661 374.464 49.6024 + vertex 893.86 379.561 48.6614 + endloop + endfacet + facet normal 0.969352 0.195008 0.14943 + outer loop + vertex 893.102 382.562 49.6615 + vertex 893.93 378.447 49.6587 + vertex 893.86 379.561 48.6614 + endloop + endfacet + facet normal 0.971379 0.200423 0.127485 + outer loop + vertex 892.306 386.393 49.7026 + vertex 893.102 382.562 49.6615 + vertex 892.192 387.577 48.706 + endloop + endfacet + facet normal 0.965793 0.214827 0.145231 + outer loop + vertex 891.617 389.553 49.609 + vertex 892.306 386.393 49.7026 + vertex 892.192 387.577 48.706 + endloop + endfacet + facet normal 0.483675 -0.477484 0.733531 + outer loop + vertex 854.641 226.2 24.3212 + vertex 854.308 224.139 23.1992 + vertex 855.838 225.675 23.1908 + endloop + endfacet + facet normal 0.571739 -0.534349 0.622564 + outer loop + vertex 852.315 230.479 29.922 + vertex 853.934 228.094 26.3871 + vertex 854.641 230.563 27.857 + endloop + endfacet + facet normal 0.474397 -0.635683 0.608978 + outer loop + vertex 848.136 240.643 43.9523 + vertex 848.713 238.142 40.8917 + vertex 850.618 241.113 42.5087 + endloop + endfacet + facet normal 0.398009 -0.650671 0.646697 + outer loop + vertex 847.08 242.431 46.4005 + vertex 848.136 240.643 43.9523 + vertex 850.228 243.109 45.1458 + endloop + endfacet + facet normal 0.421829 -0.415513 0.805859 + outer loop + vertex 856.871 224.351 21.9673 + vertex 855.838 225.675 23.1908 + vertex 854.308 224.139 23.1992 + endloop + endfacet + facet normal 0.244678 -0.258631 0.934474 + outer loop + vertex 859.682 221.623 20.1656 + vertex 858.219 223.06 20.9463 + vertex 856.825 221.106 20.7705 + endloop + endfacet + facet normal 0.32652 -0.352591 0.876963 + outer loop + vertex 858.219 223.06 20.9463 + vertex 856.871 224.351 21.9673 + vertex 855.566 222.339 21.6441 + endloop + endfacet + facet normal 0.0710578 -0.0730156 0.994796 + outer loop + vertex 863.069 218.414 19.1616 + vertex 861.321 217.608 19.2273 + vertex 860.538 213.636 18.9917 + endloop + endfacet + facet normal 0.145611 -0.130442 0.980705 + outer loop + vertex 861.321 217.608 19.2273 + vertex 860.927 219.675 19.5607 + vertex 859.334 217.3 19.4814 + endloop + endfacet + facet normal 0.184948 -0.181627 0.965819 + outer loop + vertex 860.927 219.675 19.5607 + vertex 859.682 221.623 20.1656 + vertex 858.209 219.591 20.0655 + endloop + endfacet + facet normal 0.315474 -0.291493 0.903055 + outer loop + vertex 876.343 194.425 15.1545 + vertex 875.303 196.342 16.1367 + vertex 873.795 193.747 15.8256 + endloop + endfacet + facet normal 0.207058 -0.207745 0.956017 + outer loop + vertex 875.303 196.342 16.1367 + vertex 873.86 198.067 16.824 + vertex 872.261 195.678 16.6513 + endloop + endfacet + facet normal 0.500622 -0.491304 0.71274 + outer loop + vertex 877.693 191.94 12.9684 + vertex 877.016 192.796 14.0346 + vertex 875.871 190.727 13.4124 + endloop + endfacet + facet normal 0.419099 -0.390438 0.819704 + outer loop + vertex 877.016 192.796 14.0346 + vertex 876.343 194.425 15.1545 + vertex 874.802 191.972 14.7739 + endloop + endfacet + facet normal 0.656321 -0.752753 -0.0510395 + outer loop + vertex 878.292 190.732 8.53582 + vertex 878.102 190.497 9.5526 + vertex 876.968 189.576 8.56137 + endloop + endfacet + facet normal 0.684794 -0.713348 0.14897 + outer loop + vertex 878.102 190.497 9.5526 + vertex 877.995 190.655 10.799 + vertex 876.536 189.151 10.3036 + endloop + endfacet + facet normal 0.627229 -0.709893 0.320368 + outer loop + vertex 877.995 190.655 10.799 + vertex 878.033 191.103 11.7167 + vertex 876.437 189.776 11.9019 + endloop + endfacet + facet normal 0.591922 -0.644597 0.483862 + outer loop + vertex 878.033 191.103 11.7167 + vertex 877.547 191.229 12.4792 + vertex 876.437 189.776 11.9019 + endloop + endfacet + facet normal 0.525558 -0.553033 0.646486 + outer loop + vertex 877.547 191.229 12.4792 + vertex 877.693 191.94 12.9684 + vertex 875.871 190.727 13.4124 + endloop + endfacet + facet normal 0.427394 -0.432343 -0.793986 + outer loop + vertex 877.514 192.83 4.95245 + vertex 877.157 192.003 5.21094 + vertex 875.747 191.803 4.56028 + endloop + endfacet + facet normal 0.524255 -0.579302 -0.624152 + outer loop + vertex 877.157 192.003 5.21094 + vertex 877.721 191.822 5.85222 + vertex 876.285 190.533 5.84204 + endloop + endfacet + facet normal 0.548964 -0.643349 -0.533611 + outer loop + vertex 877.721 191.822 5.85222 + vertex 878.152 191.554 6.61845 + vertex 877.268 190.523 6.95203 + endloop + endfacet + facet normal 0.623813 -0.666799 -0.407721 + outer loop + vertex 878.152 191.554 6.61845 + vertex 878.151 190.96 7.58807 + vertex 877.268 190.523 6.95203 + endloop + endfacet + facet normal 0.630496 -0.728001 -0.269239 + outer loop + vertex 878.151 190.96 7.58807 + vertex 878.292 190.732 8.53582 + vertex 876.968 189.576 8.56137 + endloop + endfacet + facet normal 0.333025 -0.301707 -0.893346 + outer loop + vertex 875.67 196.979 2.53175 + vertex 876.943 194.724 3.76823 + vertex 874.346 193.47 3.2235 + endloop + endfacet + facet normal 0.410225 -0.391444 -0.823704 + outer loop + vertex 876.943 194.724 3.76823 + vertex 877.514 192.83 4.95245 + vertex 875.747 191.803 4.56028 + endloop + endfacet + facet normal 0.10563 -0.110284 -0.988271 + outer loop + vertex 874.519 201.313 1.44936 + vertex 873.524 198.898 1.61255 + vertex 870.892 198.695 1.35385 + endloop + endfacet + facet normal 0.167409 -0.197496 -0.965904 + outer loop + vertex 873.524 198.898 1.61255 + vertex 874.803 198.807 1.85274 + vertex 872.775 195.776 2.12094 + endloop + endfacet + facet normal 0.233276 -0.239493 -0.942457 + outer loop + vertex 874.803 198.807 1.85274 + vertex 875.67 196.979 2.53175 + vertex 872.775 195.776 2.12094 + endloop + endfacet + facet normal 0.463041 -0.672366 0.57751 + outer loop + vertex 850.618 241.113 42.5087 + vertex 850.228 243.109 45.1458 + vertex 848.136 240.643 43.9523 + endloop + endfacet + facet normal 0.485541 -0.677832 0.552081 + outer loop + vertex 850.228 243.109 45.1458 + vertex 854.072 246.585 46.0335 + vertex 850.002 244.1 46.5611 + endloop + endfacet + facet normal 0.538865 -0.539476 0.646986 + outer loop + vertex 855.661 228.508 25.2946 + vertex 854.641 230.563 27.857 + vertex 853.934 228.094 26.3871 + endloop + endfacet + facet normal 0.0928691 -0.0924924 -0.991373 + outer loop + vertex 873.717 206.265 0.912235 + vertex 874.519 201.313 1.44936 + vertex 870.892 198.695 1.35385 + endloop + endfacet + facet normal 0.581229 -0.712875 0.392406 + outer loop + vertex 854.072 246.585 46.0335 + vertex 859.794 251.509 46.5029 + vertex 855.962 248.817 47.2881 + endloop + endfacet + facet normal 0.634913 -0.697732 0.331745 + outer loop + vertex 859.794 251.509 46.5029 + vertex 865.171 256.726 47.1826 + vertex 860.887 253.13 47.8191 + endloop + endfacet + facet normal 0.707709 -0.669129 0.226748 + outer loop + vertex 865.171 256.726 47.1826 + vertex 870.388 262.425 47.7207 + vertex 866.254 258.238 48.2666 + endloop + endfacet + facet normal 0.757582 -0.62154 0.199394 + outer loop + vertex 870.388 262.425 47.7207 + vertex 875.574 268.843 48.0216 + vertex 872.266 265.041 48.7403 + endloop + endfacet + facet normal 0.796567 -0.567469 0.208471 + outer loop + vertex 875.574 268.843 48.0216 + vertex 880.008 275.094 48.0942 + vertex 877.151 271.401 48.9583 + endloop + endfacet + facet normal 0.836432 -0.517279 0.181117 + outer loop + vertex 880.008 275.094 48.0942 + vertex 883.834 281.37 48.3492 + vertex 880.767 276.637 48.9955 + endloop + endfacet + facet normal 0.873346 -0.46488 0.145441 + outer loop + vertex 883.834 281.37 48.3492 + vertex 887.663 288.568 48.3636 + vertex 885.289 284.379 49.2328 + endloop + endfacet + facet normal 0.908391 -0.398301 0.127208 + outer loop + vertex 887.663 288.568 48.3636 + vertex 890.73 295.624 48.5581 + vertex 888.305 290.313 49.2477 + endloop + endfacet + facet normal 0.939341 -0.332542 0.0839954 + outer loop + vertex 890.73 295.624 48.5581 + vertex 893.603 303.729 48.5166 + vertex 891.783 298.811 49.4031 + endloop + endfacet + facet normal 0.961463 -0.25895 0.0923747 + outer loop + vertex 893.603 303.729 48.5166 + vertex 895.666 311.459 48.716 + vertex 894.184 306.235 49.4992 + endloop + endfacet + facet normal 0.980365 -0.180757 0.0788083 + outer loop + vertex 895.666 311.459 48.716 + vertex 897.182 319.623 48.5846 + vertex 896.125 314.316 49.5531 + endloop + endfacet + facet normal 0.991471 -0.106575 0.0750187 + outer loop + vertex 897.182 319.623 48.5846 + vertex 898.048 327.702 48.609 + vertex 897.372 322.053 49.5241 + endloop + endfacet + facet normal 0.995351 -0.0382305 0.0884023 + outer loop + vertex 898.048 327.702 48.609 + vertex 898.361 336.207 48.7653 + vertex 898.048 329.9 49.5602 + endloop + endfacet + facet normal 0.998765 0.0180714 0.0462749 + outer loop + vertex 898.361 336.207 48.7653 + vertex 898.203 345.237 48.6549 + vertex 898.257 340.033 49.5149 + endloop + endfacet + facet normal 0.994027 0.068679 0.0848143 + outer loop + vertex 898.203 345.237 48.6549 + vertex 897.614 353.744 48.6613 + vertex 897.922 348.237 49.5195 + endloop + endfacet + facet normal 0.988892 0.110501 0.0994051 + outer loop + vertex 897.614 353.744 48.6613 + vertex 896.628 362.477 48.7628 + vertex 897.222 356.481 49.5241 + endloop + endfacet + facet normal 0.984296 0.14459 0.101269 + outer loop + vertex 896.628 362.477 48.7628 + vertex 895.335 371.373 48.6326 + vertex 895.956 366.482 49.583 + endloop + endfacet + facet normal 0.97716 0.175641 0.119618 + outer loop + vertex 895.335 371.373 48.6326 + vertex 893.86 379.561 48.6614 + vertex 894.661 374.464 49.6024 + endloop + endfacet + facet normal 0.97063 0.201144 0.131982 + outer loop + vertex 893.86 379.561 48.6614 + vertex 892.192 387.577 48.706 + vertex 893.102 382.562 49.6615 + endloop + endfacet + facet normal 0.284178 -0.893198 0.348482 + outer loop + vertex 573.491 84.8492 38.6513 + vertex 579.711 86.6942 38.3082 + vertex 573.689 85.4608 40.0577 + endloop + endfacet + facet normal 0.272497 -0.895756 0.351236 + outer loop + vertex 567.347 83.1508 39.087 + vertex 573.491 84.8492 38.6513 + vertex 573.689 85.4608 40.0577 + endloop + endfacet + facet normal 0.268219 -0.897916 0.349006 + outer loop + vertex 560.755 81.2946 39.3771 + vertex 567.347 83.1508 39.087 + vertex 561.55 82.2262 41.1631 + endloop + endfacet + facet normal 0.252297 -0.899434 0.356882 + outer loop + vertex 554.388 79.6388 39.7053 + vertex 560.755 81.2946 39.3771 + vertex 561.55 82.2262 41.1631 + endloop + endfacet + facet normal 0.24597 -0.902806 0.352762 + outer loop + vertex 547.623 77.8659 39.8848 + vertex 554.388 79.6388 39.7053 + vertex 548.189 78.7672 41.7969 + endloop + endfacet + facet normal 0.225814 -0.905258 0.359882 + outer loop + vertex 541.084 76.3403 40.1508 + vertex 547.623 77.8659 39.8848 + vertex 548.189 78.7672 41.7969 + endloop + endfacet + facet normal 0.220175 -0.908998 0.353902 + outer loop + vertex 534.272 74.7152 40.2144 + vertex 541.084 76.3403 40.1508 + vertex 533.777 75.3237 42.085 + endloop + endfacet + facet normal 0.202986 -0.914102 0.351019 + outer loop + vertex 528.157 73.3329 40.1507 + vertex 534.272 74.7152 40.2144 + vertex 533.777 75.3237 42.085 + endloop + endfacet + facet normal 0.138096 -0.935148 0.326233 + outer loop + vertex 503.102 72.2433 49.551 + vertex 501.717 70.72 45.7706 + vertex 503.318 71.8148 48.2311 + endloop + endfacet + facet normal 0.142151 -0.943019 0.300845 + outer loop + vertex 504.457 73.8285 53.8797 + vertex 503.102 72.2433 49.551 + vertex 504.576 73.3479 52.317 + endloop + endfacet + facet normal 0.130957 -0.950613 0.2814 + outer loop + vertex 505.491 75.2565 58.2223 + vertex 504.457 73.8285 53.8797 + vertex 505.621 74.8325 56.7294 + endloop + endfacet + facet normal 0.127732 -0.956697 0.261563 + outer loop + vertex 506.154 76.4209 62.1577 + vertex 505.491 75.2565 58.2223 + vertex 506.293 76.0917 60.8855 + endloop + endfacet + facet normal 0.281388 -0.959393 -0.01965 + outer loop + vertex 608.682 103.259 304.215 + vertex 610.266 103.666 307.004 + vertex 608.772 103.272 304.89 + endloop + endfacet + facet normal 0.558714 0.77597 -0.29276 + outer loop + vertex 607.285 103.027 300.933 + vertex 608.682 103.259 304.215 + vertex 607.707 103.094 301.917 + endloop + endfacet + facet normal -0.484329 0.862474 0.146846 + outer loop + vertex 605.91 102.944 296.887 + vertex 607.285 103.027 300.933 + vertex 606.248 102.969 297.856 + endloop + endfacet + facet normal 0.27697 -0.95585 -0.098173 + outer loop + vertex 604.873 103.093 292.51 + vertex 605.91 102.944 296.887 + vertex 604.936 103.017 293.428 + endloop + endfacet + facet normal 0.38975 -0.913997 -0.112713 + outer loop + vertex 598.949 114.513 213.58 + vertex 599.378 114.271 217.031 + vertex 597.831 113.494 217.984 + endloop + endfacet + facet normal 0.428103 -0.899281 -0.0895661 + outer loop + vertex 599.01 115.562 203.609 + vertex 599.07 115.249 207.035 + vertex 597.919 115.269 201.335 + endloop + endfacet + facet normal 0.43352 -0.898637 -0.0671646 + outer loop + vertex 598.823 116.125 194.998 + vertex 598.922 115.913 198.466 + vertex 597.807 115.787 192.953 + endloop + endfacet + facet normal 0.368184 -0.888565 0.273665 + outer loop + vertex 604.291 100.336 53.5582 + vertex 603.494 101.556 58.5911 + vertex 602.902 101.191 58.2022 + endloop + endfacet + facet normal -0.673173 0.638003 -0.373886 + outer loop + vertex 606.588 98.1927 44.5686 + vertex 605.166 99.1133 48.6998 + vertex 606.131 98.5013 45.9188 + endloop + endfacet + facet normal 0.321456 -0.889079 0.325891 + outer loop + vertex 608.34 97.3361 40.5032 + vertex 606.588 98.1927 44.5686 + vertex 607.572 97.6206 42.037 + endloop + endfacet + facet normal 0.105565 -0.921367 0.374083 + outer loop + vertex 501.237 69.376 42.537 + vertex 502.117 70.4207 44.8616 + vertex 500.43 69.3872 42.7923 + endloop + endfacet + facet normal 0.197787 -0.910704 0.362628 + outer loop + vertex 533.777 75.3237 42.085 + vertex 522.456 72.3517 40.7959 + vertex 528.157 73.3329 40.1507 + endloop + endfacet + facet normal 0.223037 -0.902662 0.368043 + outer loop + vertex 548.189 78.7672 41.7969 + vertex 533.777 75.3237 42.085 + vertex 541.084 76.3403 40.1508 + endloop + endfacet + facet normal 0.249487 -0.896651 0.365751 + outer loop + vertex 561.55 82.2262 41.1631 + vertex 548.189 78.7672 41.7969 + vertex 554.388 79.6388 39.7053 + endloop + endfacet + facet normal 0.270718 -0.893664 0.357879 + outer loop + vertex 573.689 85.4608 40.0577 + vertex 561.55 82.2262 41.1631 + vertex 567.347 83.1508 39.087 + endloop + endfacet + facet normal 0.285834 -0.889335 0.356906 + outer loop + vertex 583.628 88.2701 39.0982 + vertex 573.689 85.4608 40.0577 + vertex 579.711 86.6942 38.3082 + endloop + endfacet + facet normal 0.0877531 -0.950235 0.298921 + outer loop + vertex 504.576 73.3479 52.317 + vertex 505.621 74.8325 56.7294 + vertex 504.457 73.8285 53.8797 + endloop + endfacet + facet normal 0.100909 -0.941301 0.322134 + outer loop + vertex 503.318 71.8148 48.2311 + vertex 504.576 73.3479 52.317 + vertex 503.102 72.2433 49.551 + endloop + endfacet + facet normal -0.048866 0.969979 -0.238227 + outer loop + vertex 606.131 98.5013 45.9188 + vertex 607.572 97.6206 42.037 + vertex 606.588 98.1927 44.5686 + endloop + endfacet + facet normal -0.256735 0.921378 -0.291803 + outer loop + vertex 605.098 99.3709 49.5735 + vertex 606.131 98.5013 45.9188 + vertex 605.166 99.1133 48.6998 + endloop + endfacet + facet normal 0.476276 -0.828365 0.294911 + outer loop + vertex 602.902 101.191 58.2022 + vertex 604.584 99.8317 51.6663 + vertex 604.291 100.336 53.5582 + endloop + endfacet + facet normal 0.373225 -0.891229 0.257709 + outer loop + vertex 600.884 102.934 67.1497 + vertex 602.902 101.191 58.2022 + vertex 602.81 102.647 63.3681 + endloop + endfacet + facet normal 0.384011 -0.892995 0.234724 + outer loop + vertex 599.772 105.018 76.8984 + vertex 600.884 102.934 67.1497 + vertex 601.227 104.663 73.1688 + endloop + endfacet + facet normal 0.408265 -0.91077 -0.0617808 + outer loop + vertex 597.919 115.269 201.335 + vertex 597.807 115.787 192.953 + vertex 598.922 115.913 198.466 + endloop + endfacet + facet normal 0.395852 -0.914546 -0.0831058 + outer loop + vertex 597.585 114.405 209.243 + vertex 597.919 115.269 201.335 + vertex 599.07 115.249 207.035 + endloop + endfacet + facet normal 0.408924 -0.906381 -0.106083 + outer loop + vertex 597.831 113.494 217.984 + vertex 597.585 114.405 209.243 + vertex 598.949 114.513 213.58 + endloop + endfacet + facet normal 0.249067 -0.958971 -0.135423 + outer loop + vertex 603.972 103.288 289.109 + vertex 601.984 103.857 281.422 + vertex 603.942 103.58 286.985 + endloop + endfacet + facet normal 0.203619 -0.97446 -0.094693 + outer loop + vertex 604.936 103.017 293.428 + vertex 604.227 103.169 290.34 + vertex 604.873 103.093 292.51 + endloop + endfacet + facet normal -0.560241 0.80968 0.17478 + outer loop + vertex 606.248 102.969 297.856 + vertex 604.936 103.017 293.428 + vertex 605.91 102.944 296.887 + endloop + endfacet + facet normal -0.466934 0.873013 0.140787 + outer loop + vertex 607.707 103.094 301.917 + vertex 606.248 102.969 297.856 + vertex 607.285 103.027 300.933 + endloop + endfacet + facet normal 0.179701 -0.983705 -0.00568544 + outer loop + vertex 608.772 103.272 304.89 + vertex 607.707 103.094 301.917 + vertex 608.682 103.259 304.215 + endloop + endfacet + facet normal 0.130752 -0.36031 0.923624 + outer loop + vertex 399.092 90.9337 363.317 + vertex 391.968 88.9581 363.555 + vertex 395.904 89.6568 363.271 + endloop + endfacet + facet normal -0.161782 -0.48973 0.856732 + outer loop + vertex -399.507 79.5843 357.39 + vertex -402.121 81.547 358.019 + vertex -402.436 77.7108 355.766 + endloop + endfacet + facet normal -0.174929 -0.531199 0.828992 + outer loop + vertex -402.436 77.7108 355.766 + vertex -402.67 72.4442 352.342 + vertex -399.387 74.3205 354.237 + endloop + endfacet + facet normal 0.153942 -0.634567 0.757382 + outer loop + vertex 381.218 58.7921 345.754 + vertex 390.422 61.1743 345.879 + vertex 383.821 62.7985 348.581 + endloop + endfacet + facet normal 0.159637 -0.644429 0.747815 + outer loop + vertex 397.957 62.2815 345.224 + vertex 397.818 66.11 348.553 + vertex 390.422 61.1743 345.879 + endloop + endfacet + facet normal 0.152337 -0.637511 0.755231 + outer loop + vertex 397.818 66.11 348.553 + vertex 383.821 62.7985 348.581 + vertex 390.422 61.1743 345.879 + endloop + endfacet + facet normal 0.132666 -0.619741 0.773512 + outer loop + vertex 361.279 55.2105 346.479 + vertex 371.375 57.3755 346.482 + vertex 364.956 59.046 348.921 + endloop + endfacet + facet normal 0.147283 -0.632431 0.760485 + outer loop + vertex 381.218 58.7921 345.754 + vertex 383.821 62.7985 348.581 + vertex 371.375 57.3755 346.482 + endloop + endfacet + facet normal 0.136025 -0.613374 0.777991 + outer loop + vertex 383.821 62.7985 348.581 + vertex 364.956 59.046 348.921 + vertex 371.375 57.3755 346.482 + endloop + endfacet + facet normal 0.126402 -0.641273 0.75683 + outer loop + vertex 344.006 55.6479 349.541 + vertex 346.826 51.4039 345.474 + vertex 364.956 59.046 348.921 + endloop + endfacet + facet normal 0.103877 -0.603167 0.790822 + outer loop + vertex 364.956 59.046 348.921 + vertex 346.826 51.4039 345.474 + vertex 361.279 55.2105 346.479 + endloop + endfacet + facet normal 0.118885 -0.648844 0.751577 + outer loop + vertex 321.83 51.9677 349.872 + vertex 324.027 47.5611 345.72 + vertex 344.006 55.6479 349.541 + endloop + endfacet + facet normal 0.116945 -0.645536 0.754723 + outer loop + vertex 344.006 55.6479 349.541 + vertex 324.027 47.5611 345.72 + vertex 346.826 51.4039 345.474 + endloop + endfacet + facet normal 0.109961 -0.653695 0.748727 + outer loop + vertex 300.052 48.514 350.055 + vertex 301.174 43.9777 345.929 + vertex 321.83 51.9677 349.872 + endloop + endfacet + facet normal 0.109156 -0.652281 0.750076 + outer loop + vertex 321.83 51.9677 349.872 + vertex 301.174 43.9777 345.929 + vertex 324.027 47.5611 345.72 + endloop + endfacet + facet normal 0.0979699 -0.650075 0.753528 + outer loop + vertex 278.94 45.2845 350.013 + vertex 281.266 41.4592 346.411 + vertex 300.052 48.514 350.055 + endloop + endfacet + facet normal 0.101034 -0.655562 0.748352 + outer loop + vertex 300.052 48.514 350.055 + vertex 281.266 41.4592 346.411 + vertex 301.174 43.9777 345.929 + endloop + endfacet + facet normal 0.0914707 -0.656774 0.748519 + outer loop + vertex 257.716 42.1737 349.877 + vertex 260.139 37.8875 345.82 + vertex 278.94 45.2845 350.013 + endloop + endfacet + facet normal 0.0894731 -0.653469 0.751647 + outer loop + vertex 278.94 45.2845 350.013 + vertex 260.139 37.8875 345.82 + vertex 281.266 41.4592 346.411 + endloop + endfacet + facet normal 0.0856767 -0.659985 0.746378 + outer loop + vertex 236.394 39.377 349.852 + vertex 238.789 34.9976 345.705 + vertex 257.716 42.1737 349.877 + endloop + endfacet + facet normal 0.0851593 -0.659106 0.747213 + outer loop + vertex 257.716 42.1737 349.877 + vertex 238.789 34.9976 345.705 + vertex 260.139 37.8875 345.82 + endloop + endfacet + facet normal 0.0799837 -0.662211 0.745037 + outer loop + vertex 215.034 36.8176 349.87 + vertex 217.486 32.4491 345.724 + vertex 236.394 39.377 349.852 + endloop + endfacet + facet normal 0.0798846 -0.662038 0.745201 + outer loop + vertex 236.394 39.377 349.852 + vertex 217.486 32.4491 345.724 + vertex 238.789 34.9976 345.705 + endloop + endfacet + facet normal 0.0725997 -0.663711 0.744458 + outer loop + vertex 193.774 34.4983 349.876 + vertex 196.218 30.1227 345.737 + vertex 215.034 36.8176 349.87 + endloop + endfacet + facet normal 0.0731331 -0.664656 0.743562 + outer loop + vertex 215.034 36.8176 349.87 + vertex 196.218 30.1227 345.737 + vertex 217.486 32.4491 345.724 + endloop + endfacet + facet normal 0.0656436 -0.665097 0.743866 + outer loop + vertex 172.532 32.4068 349.88 + vertex 175.018 28.02 345.739 + vertex 193.774 34.4983 349.876 + endloop + endfacet + facet normal 0.066131 -0.665977 0.743035 + outer loop + vertex 193.774 34.4983 349.876 + vertex 175.018 28.02 345.739 + vertex 196.218 30.1227 345.737 + endloop + endfacet + facet normal 0.0571911 -0.665804 0.743932 + outer loop + vertex 151.231 30.5685 349.873 + vertex 153.725 26.1564 345.732 + vertex 172.532 32.4068 349.88 + endloop + endfacet + facet normal 0.058211 -0.667694 0.742156 + outer loop + vertex 172.532 32.4068 349.88 + vertex 153.725 26.1564 345.732 + vertex 175.018 28.02 345.739 + endloop + endfacet + facet normal 0.0498601 -0.667158 0.743246 + outer loop + vertex 129.766 28.9663 349.874 + vertex 132.215 24.5295 345.728 + vertex 151.231 30.5685 349.873 + endloop + endfacet + facet normal 0.0503751 -0.668146 0.742323 + outer loop + vertex 151.231 30.5685 349.873 + vertex 132.215 24.5295 345.728 + vertex 153.725 26.1564 345.732 + endloop + endfacet + facet normal 0.0413794 -0.667084 0.743832 + outer loop + vertex 108.252 27.6275 349.871 + vertex 110.653 23.1533 345.724 + vertex 129.766 28.9663 349.874 + endloop + endfacet + facet normal 0.0426284 -0.669554 0.741539 + outer loop + vertex 129.766 28.9663 349.874 + vertex 110.653 23.1533 345.724 + vertex 132.215 24.5295 345.728 + endloop + endfacet + facet normal 0.0332752 -0.666601 0.744672 + outer loop + vertex 86.696 26.5513 349.87 + vertex 89.1759 22.0439 345.725 + vertex 108.252 27.6275 349.871 + endloop + endfacet + facet normal 0.0345808 -0.66925 0.742232 + outer loop + vertex 108.252 27.6275 349.871 + vertex 89.1759 22.0439 345.725 + vertex 110.653 23.1533 345.724 + endloop + endfacet + facet normal 0.0251481 -0.667072 0.744569 + outer loop + vertex 65.1265 25.7376 349.87 + vertex 67.6359 21.2048 345.724 + vertex 86.696 26.5513 349.87 + endloop + endfacet + facet normal 0.0260375 -0.668927 0.742872 + outer loop + vertex 86.696 26.5513 349.87 + vertex 67.6359 21.2048 345.724 + vertex 89.1759 22.0439 345.725 + endloop + endfacet + facet normal 0.0176792 -0.66722 0.744651 + outer loop + vertex 43.6208 25.1702 349.872 + vertex 46.0741 20.6091 345.727 + vertex 65.1265 25.7376 349.87 + endloop + endfacet + facet normal 0.0185867 -0.669163 0.742883 + outer loop + vertex 65.1265 25.7376 349.87 + vertex 46.0741 20.6091 345.727 + vertex 67.6359 21.2048 345.724 + endloop + endfacet + facet normal 0.0105053 -0.668104 0.743994 + outer loop + vertex 22.2497 24.8362 349.874 + vertex 24.694 20.257 345.727 + vertex 43.6208 25.1702 349.872 + endloop + endfacet + facet normal 0.0110313 -0.669252 0.742953 + outer loop + vertex 43.6208 25.1702 349.872 + vertex 24.694 20.257 345.727 + vertex 46.0741 20.6091 345.727 + endloop + endfacet + facet normal 0.00348943 -0.667526 0.744578 + outer loop + vertex 0.979474 24.7231 349.872 + vertex 3.43544 20.1146 345.729 + vertex 22.2497 24.8362 349.874 + endloop + endfacet + facet normal 0.00455011 -0.669885 0.742451 + outer loop + vertex 22.2497 24.8362 349.874 + vertex 3.43544 20.1146 345.729 + vertex 24.694 20.257 345.727 + endloop + endfacet + facet normal -0.00321364 -0.667259 0.744819 + outer loop + vertex -20.3363 24.8238 349.87 + vertex -17.7851 20.1872 345.728 + vertex 0.979474 24.7231 349.872 + endloop + endfacet + facet normal -0.00233949 -0.669246 0.743037 + outer loop + vertex 0.979474 24.7231 349.872 + vertex -17.7851 20.1872 345.728 + vertex 3.43544 20.1146 345.729 + endloop + endfacet + facet normal -0.00964788 -0.667955 0.744139 + outer loop + vertex -41.8219 25.1385 349.874 + vertex -39.2172 20.479 345.726 + vertex -20.3363 24.8238 349.87 + endloop + endfacet + facet normal -0.0091789 -0.669055 0.743156 + outer loop + vertex -20.3363 24.8238 349.87 + vertex -39.2172 20.479 345.726 + vertex -17.7851 20.1872 345.728 + endloop + endfacet + facet normal -0.0170861 -0.667 0.744862 + outer loop + vertex -63.3485 25.6855 349.87 + vertex -60.8268 20.992 345.725 + vertex -41.8219 25.1385 349.874 + endloop + endfacet + facet normal -0.0159125 -0.669846 0.74233 + outer loop + vertex -41.8219 25.1385 349.874 + vertex -60.8268 20.992 345.725 + vertex -39.2172 20.479 345.726 + endloop + endfacet + facet normal -0.024517 -0.666949 0.7447 + outer loop + vertex -84.8144 26.472 349.868 + vertex -82.2551 21.7494 345.723 + vertex -63.3485 25.6855 349.87 + endloop + endfacet + facet normal -0.0237313 -0.668902 0.742972 + outer loop + vertex -63.3485 25.6855 349.87 + vertex -82.2551 21.7494 345.723 + vertex -60.8268 20.992 345.725 + endloop + endfacet + facet normal -0.032284 -0.666742 0.744589 + outer loop + vertex -106.199 27.5094 349.87 + vertex -103.582 22.7534 345.725 + vertex -84.8144 26.472 349.868 + endloop + endfacet + facet normal -0.0314304 -0.668916 0.742673 + outer loop + vertex -84.8144 26.472 349.868 + vertex -103.582 22.7534 345.725 + vertex -82.2551 21.7494 345.723 + endloop + endfacet + facet normal -0.0406068 -0.666879 0.744059 + outer loop + vertex -127.483 28.8074 349.872 + vertex -124.891 24.0242 345.726 + vertex -106.199 27.5094 349.87 + endloop + endfacet + facet normal -0.0398387 -0.668895 0.742289 + outer loop + vertex -106.199 27.5094 349.87 + vertex -124.891 24.0242 345.726 + vertex -103.582 22.7534 345.725 + endloop + endfacet + facet normal -0.048753 -0.666786 0.743653 + outer loop + vertex -148.739 30.3663 349.876 + vertex -146.119 25.5502 345.729 + vertex -127.483 28.8074 349.872 + endloop + endfacet + facet normal -0.0479695 -0.668908 0.741796 + outer loop + vertex -127.483 28.8074 349.872 + vertex -146.119 25.5502 345.729 + vertex -124.891 24.0242 345.726 + endloop + endfacet + facet normal -0.0568367 -0.665693 0.744058 + outer loop + vertex -170.03 32.1854 349.877 + vertex -167.438 27.3328 345.734 + vertex -148.739 30.3663 349.876 + endloop + endfacet + facet normal -0.055769 -0.668698 0.74144 + outer loop + vertex -148.739 30.3663 349.876 + vertex -167.438 27.3328 345.734 + vertex -146.119 25.5502 345.729 + endloop + endfacet + facet normal -0.0638753 -0.665615 0.743557 + outer loop + vertex -191.36 34.24 349.884 + vertex -188.852 29.3688 345.739 + vertex -170.03 32.1854 349.877 + endloop + endfacet + facet normal -0.0632716 -0.667388 0.742018 + outer loop + vertex -170.03 32.1854 349.877 + vertex -188.852 29.3688 345.739 + vertex -167.438 27.3328 345.734 + endloop + endfacet + facet normal -0.0717604 -0.66303 0.745146 + outer loop + vertex -212.663 36.5289 349.869 + vertex -210.19 31.6214 345.74 + vertex -191.36 34.24 349.884 + endloop + endfacet + facet normal -0.0703786 -0.667229 0.74152 + outer loop + vertex -191.36 34.24 349.884 + vertex -210.19 31.6214 345.74 + vertex -188.852 29.3688 345.739 + endloop + endfacet + facet normal -0.0786232 -0.661652 0.745678 + outer loop + vertex -234.246 39.0802 349.857 + vertex -231.641 34.1134 345.725 + vertex -212.663 36.5289 349.869 + endloop + endfacet + facet normal -0.0777389 -0.664463 0.743267 + outer loop + vertex -212.663 36.5289 349.869 + vertex -231.641 34.1134 345.725 + vertex -210.19 31.6214 345.74 + endloop + endfacet + facet normal -0.0857462 -0.659742 0.746584 + outer loop + vertex -256.171 41.9452 349.871 + vertex -253.871 36.9581 345.728 + vertex -234.246 39.0802 349.857 + endloop + endfacet + facet normal -0.0847566 -0.663179 0.743647 + outer loop + vertex -234.246 39.0802 349.857 + vertex -253.871 36.9581 345.728 + vertex -231.641 34.1134 345.725 + endloop + endfacet + facet normal -0.0915103 -0.658351 0.747128 + outer loop + vertex -277.772 45.0519 349.963 + vertex -276.765 40.2396 345.845 + vertex -256.171 41.9452 349.871 + endloop + endfacet + facet normal -0.0908941 -0.660819 0.745022 + outer loop + vertex -256.171 41.9452 349.871 + vertex -276.765 40.2396 345.845 + vertex -253.871 36.9581 345.728 + endloop + endfacet + facet normal -0.0978958 -0.649852 0.75373 + outer loop + vertex -298.861 48.2144 349.95 + vertex -297.001 43.7589 346.35 + vertex -277.772 45.0519 349.963 + endloop + endfacet + facet normal -0.0959207 -0.658607 0.746349 + outer loop + vertex -277.772 45.0519 349.963 + vertex -297.001 43.7589 346.35 + vertex -276.765 40.2396 345.845 + endloop + endfacet + facet normal -0.104975 -0.654344 0.748875 + outer loop + vertex -319.044 51.5442 350.03 + vertex -319.749 46.7154 345.712 + vertex -298.861 48.2144 349.95 + endloop + endfacet + facet normal -0.105717 -0.651271 0.751445 + outer loop + vertex -298.861 48.2144 349.95 + vertex -319.749 46.7154 345.712 + vertex -297.001 43.7589 346.35 + endloop + endfacet + facet normal -0.111826 -0.629359 0.769027 + outer loop + vertex -338.583 55.0546 350.062 + vertex -336.651 50.7975 346.859 + vertex -319.044 51.5442 350.03 + endloop + endfacet + facet normal -0.107148 -0.654011 0.748858 + outer loop + vertex -319.044 51.5442 350.03 + vertex -336.651 50.7975 346.859 + vertex -319.749 46.7154 345.712 + endloop + endfacet + facet normal -0.131568 -0.620059 0.773445 + outer loop + vertex -365.526 55.5285 346.045 + vertex -352.565 53.7291 346.807 + vertex -360.808 58.6076 349.316 + endloop + endfacet + facet normal -0.118714 -0.63081 0.766802 + outer loop + vertex -336.651 50.7975 346.859 + vertex -338.583 55.0546 350.062 + vertex -352.565 53.7291 346.807 + endloop + endfacet + facet normal -0.123985 -0.611409 0.781541 + outer loop + vertex -338.583 55.0546 350.062 + vertex -360.808 58.6076 349.316 + vertex -352.565 53.7291 346.807 + endloop + endfacet + facet normal -0.148101 -0.626694 0.765063 + outer loop + vertex -386.865 60.1389 345.773 + vertex -376.319 58.2381 346.258 + vertex -382.348 63.1373 349.104 + endloop + endfacet + facet normal -0.138663 -0.613455 0.777461 + outer loop + vertex -365.526 55.5285 346.045 + vertex -360.808 58.6076 349.316 + vertex -376.319 58.2381 346.258 + endloop + endfacet + facet normal -0.137735 -0.618778 0.773397 + outer loop + vertex -360.808 58.6076 349.316 + vertex -382.348 63.1373 349.104 + vertex -376.319 58.2381 346.258 + endloop + endfacet + facet normal -0.119508 -0.64619 0.753762 + outer loop + vertex -402.103 63.1815 345.082 + vertex -401.105 63.1484 345.212 + vertex -401.945 66.9786 348.362 + endloop + endfacet + facet normal -0.16017 -0.649863 0.742983 + outer loop + vertex -398.395 61.7385 344.563 + vertex -396.275 65.2498 348.091 + vertex -401.105 63.1484 345.212 + endloop + endfacet + facet normal -0.161919 -0.647796 0.744408 + outer loop + vertex -396.275 65.2498 348.091 + vertex -401.945 66.9786 348.362 + vertex -401.105 63.1484 345.212 + endloop + endfacet + facet normal 0.172097 -0.742319 0.647569 + outer loop + vertex 397.849 59.7782 342.798 + vertex 397.109 57.7394 340.657 + vertex 400.958 60.0662 342.302 + endloop + endfacet + facet normal 0.185791 -0.753238 0.630963 + outer loop + vertex 400.958 60.0662 342.302 + vertex 397.109 57.7394 340.657 + vertex 400.023 58.1 340.23 + endloop + endfacet + facet normal 0.152402 -0.691254 0.706358 + outer loop + vertex 397.957 62.2815 345.224 + vertex 397.849 59.7782 342.798 + vertex 401.276 61.9417 344.176 + endloop + endfacet + facet normal 0.174587 -0.710609 0.681582 + outer loop + vertex 401.276 61.9417 344.176 + vertex 397.849 59.7782 342.798 + vertex 400.958 60.0662 342.302 + endloop + endfacet + facet normal 0.174037 -0.730889 0.659933 + outer loop + vertex 383.037 57.0101 343.615 + vertex 383.267 54.9794 341.306 + vertex 391.857 58.8004 343.272 + endloop + endfacet + facet normal 0.175277 -0.732555 0.657754 + outer loop + vertex 391.857 58.8004 343.272 + vertex 383.267 54.9794 341.306 + vertex 391.629 56.6764 340.967 + endloop + endfacet + facet normal 0.16707 -0.68287 0.71118 + outer loop + vertex 381.218 58.7921 345.754 + vertex 383.037 57.0101 343.615 + vertex 390.422 61.1743 345.879 + endloop + endfacet + facet normal 0.166123 -0.681845 0.712383 + outer loop + vertex 390.422 61.1743 345.879 + vertex 383.037 57.0101 343.615 + vertex 391.857 58.8004 343.272 + endloop + endfacet + facet normal 0.162239 -0.683468 0.711723 + outer loop + vertex 390.422 61.1743 345.879 + vertex 391.857 58.8004 343.272 + vertex 397.957 62.2815 345.224 + endloop + endfacet + facet normal 0.168277 -0.689808 0.704164 + outer loop + vertex 397.957 62.2815 345.224 + vertex 391.857 58.8004 343.272 + vertex 397.849 59.7782 342.798 + endloop + endfacet + facet normal 0.171677 -0.732847 0.658379 + outer loop + vertex 391.857 58.8004 343.272 + vertex 391.629 56.6764 340.967 + vertex 397.849 59.7782 342.798 + endloop + endfacet + facet normal 0.180501 -0.742611 0.64494 + outer loop + vertex 397.849 59.7782 342.798 + vertex 391.629 56.6764 340.967 + vertex 397.109 57.7394 340.657 + endloop + endfacet + facet normal 0.150396 -0.718117 0.679477 + outer loop + vertex 360.815 53.0539 344.562 + vertex 361.56 50.8895 342.11 + vertex 372.445 54.9856 344.03 + endloop + endfacet + facet normal 0.156328 -0.728183 0.667317 + outer loop + vertex 372.445 54.9856 344.03 + vertex 361.56 50.8895 342.11 + vertex 372.929 52.9417 341.686 + endloop + endfacet + facet normal 0.144424 -0.674504 0.724007 + outer loop + vertex 361.279 55.2105 346.479 + vertex 360.815 53.0539 344.562 + vertex 371.375 57.3755 346.482 + endloop + endfacet + facet normal 0.145378 -0.676091 0.722334 + outer loop + vertex 371.375 57.3755 346.482 + vertex 360.815 53.0539 344.562 + vertex 372.445 54.9856 344.03 + endloop + endfacet + facet normal 0.150537 -0.674358 0.722896 + outer loop + vertex 371.375 57.3755 346.482 + vertex 372.445 54.9856 344.03 + vertex 381.218 58.7921 345.754 + endloop + endfacet + facet normal 0.159145 -0.687631 0.708404 + outer loop + vertex 381.218 58.7921 345.754 + vertex 372.445 54.9856 344.03 + vertex 383.037 57.0101 343.615 + endloop + endfacet + facet normal 0.164917 -0.726224 0.667384 + outer loop + vertex 372.445 54.9856 344.03 + vertex 372.929 52.9417 341.686 + vertex 383.037 57.0101 343.615 + endloop + endfacet + facet normal 0.168553 -0.731879 0.660259 + outer loop + vertex 383.037 57.0101 343.615 + vertex 372.929 52.9417 341.686 + vertex 383.267 54.9794 341.306 + endloop + endfacet + facet normal 0.143106 -0.720068 0.678987 + outer loop + vertex 361.56 50.8895 342.11 + vertex 360.815 53.0539 344.562 + vertex 349.877 48.9382 342.503 + endloop + endfacet + facet normal 0.129387 -0.69368 0.708567 + outer loop + vertex 339.444 46.8485 342.362 + vertex 349.877 48.9382 342.503 + vertex 346.826 51.4039 345.474 + endloop + endfacet + facet normal 0.126928 -0.674033 0.727715 + outer loop + vertex 361.279 55.2105 346.479 + vertex 346.826 51.4039 345.474 + vertex 360.815 53.0539 344.562 + endloop + endfacet + facet normal 0.128061 -0.694566 0.70794 + outer loop + vertex 349.877 48.9382 342.503 + vertex 360.815 53.0539 344.562 + vertex 346.826 51.4039 345.474 + endloop + endfacet + facet normal 0.117268 -0.691855 0.71245 + outer loop + vertex 318.172 43.3041 342.55 + vertex 329.992 45.6748 342.906 + vertex 324.027 47.5611 345.72 + endloop + endfacet + facet normal 0.126785 -0.691342 0.711317 + outer loop + vertex 339.444 46.8485 342.362 + vertex 346.826 51.4039 345.474 + vertex 329.992 45.6748 342.906 + endloop + endfacet + facet normal 0.123012 -0.6838 0.719226 + outer loop + vertex 346.826 51.4039 345.474 + vertex 324.027 47.5611 345.72 + vertex 329.992 45.6748 342.906 + endloop + endfacet + facet normal 0.108789 -0.699536 0.706268 + outer loop + vertex 293.468 39.4733 342.655 + vertex 306.854 41.8898 342.986 + vertex 301.174 43.9777 345.929 + endloop + endfacet + facet normal 0.11375 -0.689288 0.715502 + outer loop + vertex 318.172 43.3041 342.55 + vertex 324.027 47.5611 345.72 + vertex 306.854 41.8898 342.986 + endloop + endfacet + facet normal 0.115018 -0.691841 0.712831 + outer loop + vertex 324.027 47.5611 345.72 + vertex 301.174 43.9777 345.929 + vertex 306.854 41.8898 342.986 + endloop + endfacet + facet normal 0.105185 -0.695566 0.710721 + outer loop + vertex 281.266 41.4592 346.411 + vertex 282.167 38.3589 343.243 + vertex 301.174 43.9777 345.929 + endloop + endfacet + facet normal 0.105646 -0.696606 0.709634 + outer loop + vertex 301.174 43.9777 345.929 + vertex 282.167 38.3589 343.243 + vertex 293.468 39.4733 342.655 + endloop + endfacet + facet normal 0.0931207 -0.704829 0.703239 + outer loop + vertex 254.621 33.886 342.541 + vertex 267.082 36.165 343.175 + vertex 260.139 37.8875 345.82 + endloop + endfacet + facet normal 0.0981571 -0.6971 0.710223 + outer loop + vertex 282.167 38.3589 343.243 + vertex 281.266 41.4592 346.411 + vertex 267.082 36.165 343.175 + endloop + endfacet + facet normal 0.0979352 -0.69674 0.710607 + outer loop + vertex 281.266 41.4592 346.411 + vertex 260.139 37.8875 345.82 + vertex 267.082 36.165 343.175 + endloop + endfacet + facet normal 0.0870193 -0.707917 0.700915 + outer loop + vertex 233.212 31.1577 342.519 + vertex 244.482 32.9299 342.909 + vertex 238.789 34.9976 345.705 + endloop + endfacet + facet normal 0.0920062 -0.704051 0.704164 + outer loop + vertex 254.621 33.886 342.541 + vertex 260.139 37.8875 345.82 + vertex 244.482 32.9299 342.909 + endloop + endfacet + facet normal 0.0912761 -0.702632 0.705675 + outer loop + vertex 260.139 37.8875 345.82 + vertex 238.789 34.9976 345.705 + vertex 244.482 32.9299 342.909 + endloop + endfacet + facet normal 0.0805729 -0.70986 0.699719 + outer loop + vertex 211.92 28.7033 342.565 + vertex 223.272 30.3713 342.95 + vertex 217.486 32.4491 345.724 + endloop + endfacet + facet normal 0.0864041 -0.707465 0.701447 + outer loop + vertex 233.212 31.1577 342.519 + vertex 238.789 34.9976 345.705 + vertex 223.272 30.3713 342.95 + endloop + endfacet + facet normal 0.0849164 -0.70441 0.704696 + outer loop + vertex 238.789 34.9976 345.705 + vertex 217.486 32.4491 345.724 + vertex 223.272 30.3713 342.95 + endloop + endfacet + facet normal 0.0727544 -0.712217 0.698179 + outer loop + vertex 190.655 26.4455 342.565 + vertex 201.946 27.9951 342.969 + vertex 196.218 30.1227 345.737 + endloop + endfacet + facet normal 0.0787247 -0.708474 0.701332 + outer loop + vertex 211.92 28.7033 342.565 + vertex 217.486 32.4491 345.724 + vertex 201.946 27.9951 342.969 + endloop + endfacet + facet normal 0.0776567 -0.706223 0.703717 + outer loop + vertex 217.486 32.4491 345.724 + vertex 196.218 30.1227 345.737 + vertex 201.946 27.9951 342.969 + endloop + endfacet + facet normal 0.0655087 -0.714269 0.696799 + outer loop + vertex 169.528 24.4129 342.557 + vertex 180.776 25.842 342.965 + vertex 175.018 28.02 345.739 + endloop + endfacet + facet normal 0.0717459 -0.711453 0.699062 + outer loop + vertex 190.655 26.4455 342.565 + vertex 196.218 30.1227 345.737 + vertex 180.776 25.842 342.965 + endloop + endfacet + facet normal 0.070339 -0.708444 0.702253 + outer loop + vertex 196.218 30.1227 345.737 + vertex 175.018 28.02 345.739 + vertex 180.776 25.842 342.965 + endloop + endfacet + facet normal 0.0575403 -0.714997 0.696756 + outer loop + vertex 148.194 22.6103 342.55 + vertex 159.563 23.9234 342.959 + vertex 153.725 26.1564 345.732 + endloop + endfacet + facet normal 0.0631429 -0.712476 0.698849 + outer loop + vertex 169.528 24.4129 342.557 + vertex 175.018 28.02 345.739 + vertex 159.563 23.9234 342.959 + endloop + endfacet + facet normal 0.0619049 -0.709756 0.701723 + outer loop + vertex 175.018 28.02 345.739 + vertex 153.725 26.1564 345.732 + vertex 159.563 23.9234 342.959 + endloop + endfacet + facet normal 0.048855 -0.71416 0.698276 + outer loop + vertex 126.549 21.0309 342.546 + vertex 138.087 22.2177 342.952 + vertex 132.215 24.5295 345.728 + endloop + endfacet + facet normal 0.0555172 -0.713429 0.698525 + outer loop + vertex 148.194 22.6103 342.55 + vertex 153.725 26.1564 345.732 + vertex 138.087 22.2177 342.952 + endloop + endfacet + facet normal 0.0534517 -0.708715 0.703467 + outer loop + vertex 153.725 26.1564 345.732 + vertex 132.215 24.5295 345.728 + vertex 138.087 22.2177 342.952 + endloop + endfacet + facet normal 0.0395514 -0.715017 0.697987 + outer loop + vertex 104.902 19.729 342.542 + vertex 116.395 20.7616 342.949 + vertex 110.653 23.1533 345.724 + endloop + endfacet + facet normal 0.0467025 -0.712421 0.700197 + outer loop + vertex 126.549 21.0309 342.546 + vertex 132.215 24.5295 345.728 + vertex 116.395 20.7616 342.949 + endloop + endfacet + facet normal 0.0451314 -0.708687 0.704078 + outer loop + vertex 132.215 24.5295 345.728 + vertex 110.653 23.1533 345.724 + vertex 116.395 20.7616 342.949 + endloop + endfacet + facet normal 0.0310824 -0.715727 0.697689 + outer loop + vertex 83.5715 18.6973 342.541 + vertex 94.927 19.5845 342.945 + vertex 89.1759 22.0439 345.725 + endloop + endfacet + facet normal 0.0385868 -0.714212 0.698864 + outer loop + vertex 104.902 19.729 342.542 + vertex 110.653 23.1533 345.724 + vertex 94.927 19.5845 342.945 + endloop + endfacet + facet normal 0.0366603 -0.709516 0.703735 + outer loop + vertex 110.653 23.1533 345.724 + vertex 89.1759 22.0439 345.725 + vertex 94.927 19.5845 342.945 + endloop + endfacet + facet normal 0.0227101 -0.715491 0.698253 + outer loop + vertex 62.0348 17.9222 342.543 + vertex 73.5304 18.6807 342.946 + vertex 67.6359 21.2048 345.724 + endloop + endfacet + facet normal 0.0293627 -0.714303 0.69922 + outer loop + vertex 83.5715 18.6973 342.541 + vertex 89.1759 22.0439 345.725 + vertex 73.5304 18.6807 342.946 + endloop + endfacet + facet normal 0.0276373 -0.70997 0.70369 + outer loop + vertex 89.1759 22.0439 345.725 + vertex 67.6359 21.2048 345.724 + vertex 73.5304 18.6807 342.946 + endloop + endfacet + facet normal 0.0151135 -0.716364 0.697563 + outer loop + vertex 40.4251 17.3916 342.545 + vertex 51.8852 18.0261 342.949 + vertex 46.0741 20.6091 345.727 + endloop + endfacet + facet normal 0.0206858 -0.713787 0.700058 + outer loop + vertex 62.0348 17.9222 342.543 + vertex 67.6359 21.2048 345.724 + vertex 51.8852 18.0261 342.949 + endloop + endfacet + facet normal 0.0197467 -0.711334 0.702577 + outer loop + vertex 67.6359 21.2048 345.724 + vertex 46.0741 20.6091 345.727 + vertex 51.8852 18.0261 342.949 + endloop + endfacet + facet normal 0.00686273 -0.715787 0.698285 + outer loop + vertex 19.1331 17.1013 342.547 + vertex 30.4409 17.6039 342.951 + vertex 24.694 20.257 345.727 + endloop + endfacet + facet normal 0.0132382 -0.714747 0.699258 + outer loop + vertex 40.4251 17.3916 342.545 + vertex 46.0741 20.6091 345.727 + vertex 30.4409 17.6039 342.951 + endloop + endfacet + facet normal 0.0117128 -0.710667 0.703431 + outer loop + vertex 46.0741 20.6091 345.727 + vertex 24.694 20.257 345.727 + vertex 30.4409 17.6039 342.951 + endloop + endfacet + facet normal 0.000337229 -0.716789 0.69729 + outer loop + vertex -2.06869 17.0175 342.548 + vertex 9.19762 17.4157 342.952 + vertex 3.43544 20.1146 345.729 + endloop + endfacet + facet normal 0.00586227 -0.714924 0.699178 + outer loop + vertex 19.1331 17.1013 342.547 + vertex 24.694 20.257 345.727 + vertex 9.19762 17.4157 342.952 + endloop + endfacet + facet normal 0.00482937 -0.712104 0.702058 + outer loop + vertex 24.694 20.257 345.727 + vertex 3.43544 20.1146 345.729 + vertex 9.19762 17.4157 342.952 + endloop + endfacet + facet normal -0.00639787 -0.715817 0.698258 + outer loop + vertex -23.1798 17.1336 342.548 + vertex -11.958 17.4278 342.952 + vertex -17.7851 20.1872 345.728 + endloop + endfacet + facet normal -0.00113184 -0.715517 0.698594 + outer loop + vertex -2.06869 17.0175 342.548 + vertex 3.43544 20.1146 345.729 + vertex -11.958 17.4278 342.952 + endloop + endfacet + facet normal -0.00248225 -0.711747 0.702432 + outer loop + vertex 3.43544 20.1146 345.729 + vertex -17.7851 20.1872 345.728 + vertex -11.958 17.4278 342.952 + endloop + endfacet + facet normal -0.0142173 -0.714965 0.699015 + outer loop + vertex -44.6618 17.4778 342.545 + vertex -33.1964 17.6462 342.951 + vertex -39.2172 20.479 345.726 + endloop + endfacet + facet normal -0.00839276 -0.7141 0.699993 + outer loop + vertex -23.1798 17.1336 342.548 + vertex -17.7851 20.1872 345.728 + vertex -33.1964 17.6462 342.951 + endloop + endfacet + facet normal -0.00973567 -0.710229 0.703904 + outer loop + vertex -17.7851 20.1872 345.728 + vertex -39.2172 20.479 345.726 + vertex -33.1964 17.6462 342.951 + endloop + endfacet + facet normal -0.0221803 -0.716535 0.697199 + outer loop + vertex -66.4422 18.0691 342.543 + vertex -54.8988 18.1064 342.948 + vertex -60.8268 20.992 345.725 + endloop + endfacet + facet normal -0.0162035 -0.713212 0.700761 + outer loop + vertex -44.6618 17.4778 342.545 + vertex -39.2172 20.479 345.726 + vertex -54.8988 18.1064 342.948 + endloop + endfacet + facet normal -0.016892 -0.711124 0.702864 + outer loop + vertex -39.2172 20.479 345.726 + vertex -60.8268 20.992 345.725 + vertex -54.8988 18.1064 342.948 + endloop + endfacet + facet normal -0.0309425 -0.715028 0.69841 + outer loop + vertex -87.7346 18.8789 342.541 + vertex -76.4596 18.7866 342.946 + vertex -82.2551 21.7494 345.723 + endloop + endfacet + facet normal -0.0231379 -0.71565 0.698076 + outer loop + vertex -66.4422 18.0691 342.543 + vertex -60.8268 20.992 345.725 + vertex -76.4596 18.7866 342.946 + endloop + endfacet + facet normal -0.0251558 -0.709339 0.704418 + outer loop + vertex -60.8268 20.992 345.725 + vertex -82.2551 21.7494 345.723 + vertex -76.4596 18.7866 342.946 + endloop + endfacet + facet normal -0.0394046 -0.71563 0.697368 + outer loop + vertex -108.945 19.9471 342.542 + vertex -97.6467 19.7182 342.945 + vertex -103.582 22.7534 345.725 + endloop + endfacet + facet normal -0.0319639 -0.714091 0.699323 + outer loop + vertex -87.7346 18.8789 342.541 + vertex -82.2551 21.7494 345.723 + vertex -97.6467 19.7182 342.945 + endloop + endfacet + facet normal -0.0333513 -0.70965 0.703764 + outer loop + vertex -82.2551 21.7494 345.723 + vertex -103.582 22.7534 345.725 + vertex -97.6467 19.7182 342.945 + endloop + endfacet + facet normal -0.0480893 -0.715822 0.696625 + outer loop + vertex -130.3 21.2924 342.546 + vertex -118.979 20.923 342.947 + vertex -124.891 24.0242 345.726 + endloop + endfacet + facet normal -0.0411796 -0.714006 0.698927 + outer loop + vertex -108.945 19.9471 342.542 + vertex -103.582 22.7534 345.725 + vertex -118.979 20.923 342.947 + endloop + endfacet + facet normal -0.042307 -0.710235 0.702692 + outer loop + vertex -103.582 22.7534 345.725 + vertex -124.891 24.0242 345.726 + vertex -118.979 20.923 342.947 + endloop + endfacet + facet normal -0.0561974 -0.714185 0.697698 + outer loop + vertex -151.434 22.8633 342.551 + vertex -140.221 22.3732 342.952 + vertex -146.119 25.5502 345.729 + endloop + endfacet + facet normal -0.0492568 -0.714725 0.697669 + outer loop + vertex -130.3 21.2924 342.546 + vertex -124.891 24.0242 345.726 + vertex -140.221 22.3732 342.952 + endloop + endfacet + facet normal -0.0508668 -0.709132 0.703238 + outer loop + vertex -124.891 24.0242 345.726 + vertex -146.119 25.5502 345.729 + vertex -140.221 22.3732 342.952 + endloop + endfacet + facet normal -0.0642489 -0.714399 0.696783 + outer loop + vertex -172.794 24.7145 342.555 + vertex -161.428 24.0844 342.957 + vertex -167.438 27.3328 345.734 + endloop + endfacet + facet normal -0.0585443 -0.711978 0.699757 + outer loop + vertex -151.434 22.8633 342.551 + vertex -146.119 25.5502 345.729 + vertex -161.428 24.0844 342.957 + endloop + endfacet + facet normal -0.0591974 -0.709605 0.702109 + outer loop + vertex -146.119 25.5502 345.729 + vertex -167.438 27.3328 345.734 + vertex -161.428 24.0844 342.957 + endloop + endfacet + facet normal -0.0723726 -0.71342 0.696989 + outer loop + vertex -194.348 26.824 342.563 + vertex -182.919 26.0547 342.963 + vertex -188.852 29.3688 345.739 + endloop + endfacet + facet normal -0.0662022 -0.712517 0.698525 + outer loop + vertex -172.794 24.7145 342.555 + vertex -167.438 27.3328 345.734 + vertex -182.919 26.0547 342.963 + endloop + endfacet + facet normal -0.0672048 -0.708656 0.702346 + outer loop + vertex -167.438 27.3328 345.734 + vertex -188.852 29.3688 345.739 + vertex -182.919 26.0547 342.963 + endloop + endfacet + facet normal -0.0797457 -0.711675 0.697968 + outer loop + vertex -215.69 29.1291 342.571 + vertex -204.37 28.2536 342.972 + vertex -210.19 31.6214 345.74 + endloop + endfacet + facet normal -0.0732236 -0.712564 0.697776 + outer loop + vertex -194.348 26.824 342.563 + vertex -188.852 29.3688 345.739 + vertex -204.37 28.2536 342.972 + endloop + endfacet + facet normal -0.0745869 -0.707065 0.703204 + outer loop + vertex -188.852 29.3688 345.739 + vertex -210.19 31.6214 345.74 + vertex -204.37 28.2536 342.972 + endloop + endfacet + facet normal -0.0873356 -0.709481 0.699292 + outer loop + vertex -237.032 31.6474 342.549 + vertex -225.651 30.6574 342.966 + vertex -231.641 34.1134 345.725 + endloop + endfacet + facet normal -0.0811921 -0.710191 0.699311 + outer loop + vertex -215.69 29.1291 342.571 + vertex -210.19 31.6214 345.74 + vertex -225.651 30.6574 342.966 + endloop + endfacet + facet normal -0.082423 -0.705025 0.704376 + outer loop + vertex -210.19 31.6214 345.74 + vertex -231.641 34.1134 345.725 + vertex -225.651 30.6574 342.966 + endloop + endfacet + facet normal -0.094273 -0.705869 0.702041 + outer loop + vertex -259.466 34.5442 342.549 + vertex -247.384 33.3245 342.946 + vertex -253.871 36.9581 345.728 + endloop + endfacet + facet normal -0.0880402 -0.708764 0.699931 + outer loop + vertex -237.032 31.6474 342.549 + vertex -231.641 34.1134 345.725 + vertex -247.384 33.3245 342.946 + endloop + endfacet + facet normal -0.0896611 -0.701466 0.707041 + outer loop + vertex -231.641 34.1134 345.725 + vertex -253.871 36.9581 345.728 + vertex -247.384 33.3245 342.946 + endloop + endfacet + facet normal -0.102518 -0.704562 0.702198 + outer loop + vertex -283.989 38.016 342.56 + vertex -270.715 36.4827 342.959 + vertex -276.765 40.2396 345.845 + endloop + endfacet + facet normal -0.0957516 -0.70428 0.703436 + outer loop + vertex -259.466 34.5442 342.549 + vertex -253.871 36.9581 345.728 + vertex -270.715 36.4827 342.959 + endloop + endfacet + facet normal -0.0966369 -0.699558 0.708011 + outer loop + vertex -253.871 36.9581 345.728 + vertex -276.765 40.2396 345.845 + vertex -270.715 36.4827 342.959 + endloop + endfacet + facet normal -0.104142 -0.700147 0.706363 + outer loop + vertex -297.001 43.7589 346.35 + vertex -295.539 40.3197 343.157 + vertex -276.765 40.2396 345.845 + endloop + endfacet + facet normal -0.103785 -0.702791 0.703785 + outer loop + vertex -276.765 40.2396 345.845 + vertex -295.539 40.3197 343.157 + vertex -283.989 38.016 342.56 + endloop + endfacet + facet normal -0.115549 -0.701959 0.702782 + outer loop + vertex -322.803 44.0252 342.523 + vertex -310.799 42.6999 343.173 + vertex -319.749 46.7154 345.712 + endloop + endfacet + facet normal -0.10856 -0.700803 0.705046 + outer loop + vertex -295.539 40.3197 343.157 + vertex -297.001 43.7589 346.35 + vertex -310.799 42.6999 343.173 + endloop + endfacet + facet normal -0.110255 -0.695027 0.71048 + outer loop + vertex -297.001 43.7589 346.35 + vertex -319.749 46.7154 345.712 + vertex -310.799 42.6999 343.173 + endloop + endfacet + facet normal -0.131365 -0.73325 0.667149 + outer loop + vertex -342.386 46.8244 341.831 + vertex -332.385 45.647 342.507 + vertex -338.677 48.0712 343.932 + endloop + endfacet + facet normal -0.116699 -0.685161 0.718982 + outer loop + vertex -336.651 50.7975 346.859 + vertex -338.677 48.0712 343.932 + vertex -319.749 46.7154 345.712 + endloop + endfacet + facet normal -0.119601 -0.699481 0.704572 + outer loop + vertex -322.803 44.0252 342.523 + vertex -319.749 46.7154 345.712 + vertex -332.385 45.647 342.507 + endloop + endfacet + facet normal -0.116181 -0.709967 0.694586 + outer loop + vertex -338.677 48.0712 343.932 + vertex -332.385 45.647 342.507 + vertex -319.749 46.7154 345.712 + endloop + endfacet + facet normal -0.14585 -0.731437 0.666129 + outer loop + vertex -362.862 52.9028 344.097 + vertex -361.515 50.6918 341.964 + vertex -350.452 50.6313 344.32 + endloop + endfacet + facet normal -0.146545 -0.728236 0.669475 + outer loop + vertex -350.452 50.6313 344.32 + vertex -361.515 50.6918 341.964 + vertex -350.621 48.5878 342.06 + endloop + endfacet + facet normal -0.136419 -0.675788 0.724362 + outer loop + vertex -365.526 55.5285 346.045 + vertex -362.862 52.9028 344.097 + vertex -352.565 53.7291 346.807 + endloop + endfacet + facet normal -0.136609 -0.675175 0.724898 + outer loop + vertex -352.565 53.7291 346.807 + vertex -362.862 52.9028 344.097 + vertex -350.452 50.6313 344.32 + endloop + endfacet + facet normal -0.126173 -0.671958 0.729762 + outer loop + vertex -352.565 53.7291 346.807 + vertex -350.452 50.6313 344.32 + vertex -336.651 50.7975 346.859 + endloop + endfacet + facet normal -0.124453 -0.681616 0.721049 + outer loop + vertex -336.651 50.7975 346.859 + vertex -350.452 50.6313 344.32 + vertex -338.677 48.0712 343.932 + endloop + endfacet + facet normal -0.136582 -0.729667 0.670024 + outer loop + vertex -350.452 50.6313 344.32 + vertex -350.621 48.5878 342.06 + vertex -338.677 48.0712 343.932 + endloop + endfacet + facet normal -0.136942 -0.726736 0.673129 + outer loop + vertex -338.677 48.0712 343.932 + vertex -350.621 48.5878 342.06 + vertex -342.386 46.8244 341.831 + endloop + endfacet + facet normal -0.169743 -0.728223 0.663987 + outer loop + vertex -385.122 57.4709 343.629 + vertex -383.21 55.0076 341.416 + vertex -374.472 55.1539 343.81 + endloop + endfacet + facet normal -0.167987 -0.734099 0.657936 + outer loop + vertex -374.472 55.1539 343.81 + vertex -383.21 55.0076 341.416 + vertex -372.748 52.8478 341.677 + endloop + endfacet + facet normal -0.155283 -0.678554 0.71795 + outer loop + vertex -386.865 60.1389 345.773 + vertex -385.122 57.4709 343.629 + vertex -376.319 58.2381 346.258 + endloop + endfacet + facet normal -0.15816 -0.67019 0.725142 + outer loop + vertex -376.319 58.2381 346.258 + vertex -385.122 57.4709 343.629 + vertex -374.472 55.1539 343.81 + endloop + endfacet + facet normal -0.153618 -0.669066 0.727153 + outer loop + vertex -376.319 58.2381 346.258 + vertex -374.472 55.1539 343.81 + vertex -365.526 55.5285 346.045 + endloop + endfacet + facet normal -0.150035 -0.682731 0.7151 + outer loop + vertex -365.526 55.5285 346.045 + vertex -374.472 55.1539 343.81 + vertex -362.862 52.9028 344.097 + endloop + endfacet + facet normal -0.158228 -0.731598 0.66312 + outer loop + vertex -374.472 55.1539 343.81 + vertex -372.748 52.8478 341.677 + vertex -362.862 52.9028 344.097 + endloop + endfacet + facet normal -0.157688 -0.733663 0.660964 + outer loop + vertex -362.862 52.9028 344.097 + vertex -372.748 52.8478 341.677 + vertex -361.515 50.6918 341.964 + endloop + endfacet + facet normal -0.169026 -0.668608 0.72415 + outer loop + vertex -392.622 62.1054 346.245 + vertex -393.437 59.6628 343.8 + vertex -386.865 60.1389 345.773 + endloop + endfacet + facet normal -0.164877 -0.68113 0.713356 + outer loop + vertex -386.865 60.1389 345.773 + vertex -393.437 59.6628 343.8 + vertex -385.122 57.4709 343.629 + endloop + endfacet + facet normal -0.178803 -0.729789 0.659877 + outer loop + vertex -393.437 59.6628 343.8 + vertex -392.863 57.0464 341.062 + vertex -385.122 57.4709 343.629 + endloop + endfacet + facet normal -0.17849 -0.730596 0.659068 + outer loop + vertex -385.122 57.4709 343.629 + vertex -392.863 57.0464 341.062 + vertex -383.21 55.0076 341.416 + endloop + endfacet + facet normal -0.201983 -0.73473 0.647592 + outer loop + vertex -401.673 60.883 342.897 + vertex -401.126 58.6977 340.588 + vertex -401.163 60.3581 342.46 + endloop + endfacet + facet normal -0.136816 -0.742481 0.655746 + outer loop + vertex -401.163 60.3581 342.46 + vertex -401.126 58.6977 340.588 + vertex -400.626 58.1831 340.11 + endloop + endfacet + facet normal -0.115327 -0.695651 0.709062 + outer loop + vertex -402.103 63.1815 345.082 + vertex -401.673 60.883 342.897 + vertex -401.105 63.1484 345.212 + endloop + endfacet + facet normal -0.110457 -0.696656 0.708851 + outer loop + vertex -401.105 63.1484 345.212 + vertex -401.673 60.883 342.897 + vertex -401.163 60.3581 342.46 + endloop + endfacet + facet normal -0.189713 -0.687372 0.701091 + outer loop + vertex -401.105 63.1484 345.212 + vertex -401.163 60.3581 342.46 + vertex -398.395 61.7385 344.563 + endloop + endfacet + facet normal -0.174832 -0.701569 0.690822 + outer loop + vertex -398.395 61.7385 344.563 + vertex -401.163 60.3581 342.46 + vertex -398.58 59.146 341.883 + endloop + endfacet + facet normal -0.205054 -0.741301 0.639082 + outer loop + vertex -401.163 60.3581 342.46 + vertex -400.626 58.1831 340.11 + vertex -398.58 59.146 341.883 + endloop + endfacet + facet normal -0.186096 -0.757352 0.625928 + outer loop + vertex -398.58 59.146 341.883 + vertex -400.626 58.1831 340.11 + vertex -398.453 57.3625 339.763 + endloop + endfacet + facet normal 0.199231 -0.640156 0.741962 + outer loop + vertex -402.185 62.6117 344.612 + vertex -401.731 61.1394 343.22 + vertex -402.103 63.1815 345.082 + endloop + endfacet + facet normal 0.990068 0.0688505 0.122579 + outer loop + vertex -402.103 63.1815 345.082 + vertex -401.731 61.1394 343.22 + vertex -401.673 60.883 342.897 + endloop + endfacet + facet normal 0.749001 0.577726 -0.324392 + outer loop + vertex -401.731 61.1394 343.22 + vertex -401.072 59.1129 341.131 + vertex -401.673 60.883 342.897 + endloop + endfacet + facet normal 0.386747 0.713752 -0.583939 + outer loop + vertex -401.673 60.883 342.897 + vertex -401.072 59.1129 341.131 + vertex -401.126 58.6977 340.588 + endloop + endfacet + facet normal 0.190426 -0.833584 0.518532 + outer loop + vertex 395.95 55.9333 338.583 + vertex 394.62 54.3375 336.506 + vertex 398.822 56.305 338.126 + endloop + endfacet + facet normal 0.201781 -0.842352 0.499727 + outer loop + vertex 398.822 56.305 338.126 + vertex 394.62 54.3375 336.506 + vertex 397.458 54.7168 336 + endloop + endfacet + facet normal 0.183603 -0.789838 0.585189 + outer loop + vertex 397.109 57.7394 340.657 + vertex 395.95 55.9333 338.583 + vertex 400.023 58.1 340.23 + endloop + endfacet + facet normal 0.194082 -0.7982 0.570271 + outer loop + vertex 400.023 58.1 340.23 + vertex 395.95 55.9333 338.583 + vertex 398.822 56.305 338.126 + endloop + endfacet + facet normal 0.192404 -0.830197 0.523215 + outer loop + vertex 382.401 53.1523 339.18 + vertex 381.017 51.5699 337.179 + vertex 390.54 54.8434 338.871 + endloop + endfacet + facet normal 0.193946 -0.832495 0.518977 + outer loop + vertex 390.54 54.8434 338.871 + vertex 381.017 51.5699 337.179 + vertex 389.138 53.2483 336.836 + endloop + endfacet + facet normal 0.182672 -0.781081 0.597113 + outer loop + vertex 383.267 54.9794 341.306 + vertex 382.401 53.1523 339.18 + vertex 391.629 56.6764 340.967 + endloop + endfacet + facet normal 0.185671 -0.785503 0.590349 + outer loop + vertex 391.629 56.6764 340.967 + vertex 382.401 53.1523 339.18 + vertex 390.54 54.8434 338.871 + endloop + endfacet + facet normal 0.185734 -0.785508 0.590322 + outer loop + vertex 391.629 56.6764 340.967 + vertex 390.54 54.8434 338.871 + vertex 397.109 57.7394 340.657 + endloop + endfacet + facet normal 0.190183 -0.790544 0.582127 + outer loop + vertex 397.109 57.7394 340.657 + vertex 390.54 54.8434 338.871 + vertex 395.95 55.9333 338.583 + endloop + endfacet + facet normal 0.195276 -0.832669 0.518198 + outer loop + vertex 390.54 54.8434 338.871 + vertex 389.138 53.2483 336.836 + vertex 395.95 55.9333 338.583 + endloop + endfacet + facet normal 0.196724 -0.834287 0.515038 + outer loop + vertex 395.95 55.9333 338.583 + vertex 389.138 53.2483 336.836 + vertex 394.62 54.3375 336.506 + endloop + endfacet + facet normal 0.173078 -0.820821 0.544332 + outer loop + vertex 361.497 49.0684 339.869 + vertex 360.631 47.5586 337.868 + vertex 372.391 51.1394 339.529 + endloop + endfacet + facet normal 0.175216 -0.824751 0.537666 + outer loop + vertex 372.391 51.1394 339.529 + vertex 360.631 47.5586 337.868 + vertex 371.154 49.5847 337.547 + endloop + endfacet + facet normal 0.161735 -0.767978 0.619719 + outer loop + vertex 361.56 50.8895 342.11 + vertex 361.497 49.0684 339.869 + vertex 372.929 52.9417 341.686 + endloop + endfacet + facet normal 0.166672 -0.77675 0.607355 + outer loop + vertex 372.929 52.9417 341.686 + vertex 361.497 49.0684 339.869 + vertex 372.391 51.1394 339.529 + endloop + endfacet + facet normal 0.175343 -0.776617 0.605079 + outer loop + vertex 372.929 52.9417 341.686 + vertex 372.391 51.1394 339.529 + vertex 383.267 54.9794 341.306 + endloop + endfacet + facet normal 0.177849 -0.780845 0.598875 + outer loop + vertex 383.267 54.9794 341.306 + vertex 372.391 51.1394 339.529 + vertex 382.401 53.1523 339.18 + endloop + endfacet + facet normal 0.184609 -0.825913 0.532716 + outer loop + vertex 372.391 51.1394 339.529 + vertex 371.154 49.5847 337.547 + vertex 382.401 53.1523 339.18 + endloop + endfacet + facet normal 0.186601 -0.829388 0.526589 + outer loop + vertex 382.401 53.1523 339.18 + vertex 371.154 49.5847 337.547 + vertex 381.017 51.5699 337.179 + endloop + endfacet + facet normal 0.152547 -0.813453 0.561269 + outer loop + vertex 340.15 45.2959 340.351 + vertex 340.044 43.8433 338.274 + vertex 350.513 47.1087 340.161 + endloop + endfacet + facet normal 0.153377 -0.814828 0.559045 + outer loop + vertex 350.513 47.1087 340.161 + vertex 340.044 43.8433 338.274 + vertex 350.129 45.6206 338.098 + endloop + endfacet + facet normal 0.143346 -0.758468 0.63575 + outer loop + vertex 339.444 46.8485 342.362 + vertex 340.15 45.2959 340.351 + vertex 349.877 48.9382 342.503 + endloop + endfacet + facet normal 0.144561 -0.760274 0.633314 + outer loop + vertex 349.877 48.9382 342.503 + vertex 340.15 45.2959 340.351 + vertex 350.513 47.1087 340.161 + endloop + endfacet + facet normal 0.148142 -0.759365 0.633577 + outer loop + vertex 349.877 48.9382 342.503 + vertex 350.513 47.1087 340.161 + vertex 361.56 50.8895 342.11 + endloop + endfacet + facet normal 0.153672 -0.768868 0.620666 + outer loop + vertex 361.56 50.8895 342.11 + vertex 350.513 47.1087 340.161 + vertex 361.497 49.0684 339.869 + endloop + endfacet + facet normal 0.160143 -0.814534 0.557574 + outer loop + vertex 350.513 47.1087 340.161 + vertex 350.129 45.6206 338.098 + vertex 361.497 49.0684 339.869 + endloop + endfacet + facet normal 0.163357 -0.820282 0.548135 + outer loop + vertex 361.497 49.0684 339.869 + vertex 350.129 45.6206 338.098 + vertex 360.631 47.5586 337.868 + endloop + endfacet + facet normal 0.134912 -0.800453 0.584015 + outer loop + vertex 320.822 42.082 340.566 + vertex 323.373 41.3008 338.906 + vertex 330.741 43.7499 340.561 + endloop + endfacet + facet normal 0.143133 -0.81246 0.565174 + outer loop + vertex 330.741 43.7499 340.561 + vertex 323.373 41.3008 338.906 + vertex 330.81 42.346 338.525 + endloop + endfacet + facet normal 0.132127 -0.755321 0.641897 + outer loop + vertex 318.172 43.3041 342.55 + vertex 320.822 42.082 340.566 + vertex 329.992 45.6748 342.906 + endloop + endfacet + facet normal 0.125921 -0.746757 0.653068 + outer loop + vertex 329.992 45.6748 342.906 + vertex 320.822 42.082 340.566 + vertex 330.741 43.7499 340.561 + endloop + endfacet + facet normal 0.1302 -0.745633 0.653513 + outer loop + vertex 329.992 45.6748 342.906 + vertex 330.741 43.7499 340.561 + vertex 339.444 46.8485 342.362 + endloop + endfacet + facet normal 0.13901 -0.759732 0.635203 + outer loop + vertex 339.444 46.8485 342.362 + vertex 330.741 43.7499 340.561 + vertex 340.15 45.2959 340.351 + endloop + endfacet + facet normal 0.146043 -0.812064 0.564999 + outer loop + vertex 330.741 43.7499 340.561 + vertex 330.81 42.346 338.525 + vertex 340.15 45.2959 340.351 + endloop + endfacet + facet normal 0.147254 -0.813986 0.56191 + outer loop + vertex 340.15 45.2959 340.351 + vertex 330.81 42.346 338.525 + vertex 340.044 43.8433 338.274 + endloop + endfacet + facet normal 0.130762 -0.842654 0.522337 + outer loop + vertex 295.076 37.9077 340.381 + vertex 296.396 36.1769 337.258 + vertex 308.669 39.9955 340.346 + endloop + endfacet + facet normal 0.122658 -0.831882 0.541227 + outer loop + vertex 308.669 39.9955 340.346 + vertex 296.396 36.1769 337.258 + vertex 313.251 39.2772 338.204 + endloop + endfacet + facet normal 0.124349 -0.774012 0.62084 + outer loop + vertex 293.468 39.4733 342.655 + vertex 295.076 37.9077 340.381 + vertex 306.854 41.8898 342.986 + endloop + endfacet + facet normal 0.119277 -0.766057 0.631609 + outer loop + vertex 306.854 41.8898 342.986 + vertex 295.076 37.9077 340.381 + vertex 308.669 39.9955 340.346 + endloop + endfacet + facet normal 0.120072 -0.765696 0.631896 + outer loop + vertex 306.854 41.8898 342.986 + vertex 308.669 39.9955 340.346 + vertex 318.172 43.3041 342.55 + endloop + endfacet + facet normal 0.120005 -0.765594 0.632032 + outer loop + vertex 318.172 43.3041 342.55 + vertex 308.669 39.9955 340.346 + vertex 320.822 42.082 340.566 + endloop + endfacet + facet normal 0.130944 -0.821225 0.555376 + outer loop + vertex 308.669 39.9955 340.346 + vertex 313.251 39.2772 338.204 + vertex 320.822 42.082 340.566 + endloop + endfacet + facet normal 0.122725 -0.81194 0.570694 + outer loop + vertex 320.822 42.082 340.566 + vertex 313.251 39.2772 338.204 + vertex 323.373 41.3008 338.906 + endloop + endfacet + facet normal 0.108213 -0.757242 0.644108 + outer loop + vertex 282.167 38.3589 343.243 + vertex 281.849 36.0819 340.62 + vertex 293.468 39.4733 342.655 + endloop + endfacet + facet normal 0.118396 -0.776783 0.618539 + outer loop + vertex 293.468 39.4733 342.655 + vertex 281.849 36.0819 340.62 + vertex 295.076 37.9077 340.381 + endloop + endfacet + facet normal 0.132262 -0.842187 0.522712 + outer loop + vertex 296.396 36.1769 337.258 + vertex 295.076 37.9077 340.381 + vertex 281.95 34.5239 338.25 + endloop + endfacet + facet normal 0.124025 -0.826681 0.548832 + outer loop + vertex 281.95 34.5239 338.25 + vertex 295.076 37.9077 340.381 + vertex 281.849 36.0819 340.62 + endloop + endfacet + facet normal 0.113413 -0.824245 0.554759 + outer loop + vertex 256.422 32.514 340.57 + vertex 257.097 31.2186 338.508 + vertex 268.898 34.3314 340.72 + endloop + endfacet + facet normal 0.110542 -0.819123 0.562865 + outer loop + vertex 268.898 34.3314 340.72 + vertex 257.097 31.2186 338.508 + vertex 269.214 32.86 338.517 + endloop + endfacet + facet normal 0.108044 -0.766801 0.632727 + outer loop + vertex 254.621 33.886 342.541 + vertex 256.422 32.514 340.57 + vertex 267.082 36.165 343.175 + endloop + endfacet + facet normal 0.102841 -0.758934 0.642995 + outer loop + vertex 267.082 36.165 343.175 + vertex 256.422 32.514 340.57 + vertex 268.898 34.3314 340.72 + endloop + endfacet + facet normal 0.107153 -0.75691 0.644674 + outer loop + vertex 267.082 36.165 343.175 + vertex 268.898 34.3314 340.72 + vertex 282.167 38.3589 343.243 + endloop + endfacet + facet normal 0.107343 -0.757261 0.64423 + outer loop + vertex 282.167 38.3589 343.243 + vertex 268.898 34.3314 340.72 + vertex 281.849 36.0819 340.62 + endloop + endfacet + facet normal 0.114978 -0.818405 0.563021 + outer loop + vertex 268.898 34.3314 340.72 + vertex 269.214 32.86 338.517 + vertex 281.849 36.0819 340.62 + endloop + endfacet + facet normal 0.11956 -0.827226 0.549001 + outer loop + vertex 281.849 36.0819 340.62 + vertex 269.214 32.86 338.517 + vertex 281.95 34.5239 338.25 + endloop + endfacet + facet normal 0.102836 -0.830611 0.547275 + outer loop + vertex 234.712 29.7279 340.523 + vertex 235.132 28.4095 338.443 + vertex 245.293 31.0261 340.505 + endloop + endfacet + facet normal 0.101752 -0.828764 0.55027 + outer loop + vertex 245.293 31.0261 340.505 + vertex 235.132 28.4095 338.443 + vertex 245.791 29.7204 338.446 + endloop + endfacet + facet normal 0.0996243 -0.771956 0.627821 + outer loop + vertex 233.212 31.1577 342.519 + vertex 234.712 29.7279 340.523 + vertex 244.482 32.9299 342.909 + endloop + endfacet + facet normal 0.0948974 -0.76467 0.637397 + outer loop + vertex 244.482 32.9299 342.909 + vertex 234.712 29.7279 340.523 + vertex 245.293 31.0261 340.505 + endloop + endfacet + facet normal 0.0952868 -0.764575 0.637453 + outer loop + vertex 244.482 32.9299 342.909 + vertex 245.293 31.0261 340.505 + vertex 254.621 33.886 342.541 + endloop + endfacet + facet normal 0.0994594 -0.771631 0.628246 + outer loop + vertex 254.621 33.886 342.541 + vertex 245.293 31.0261 340.505 + vertex 256.422 32.514 340.57 + endloop + endfacet + facet normal 0.107401 -0.827623 0.550913 + outer loop + vertex 245.293 31.0261 340.505 + vertex 245.791 29.7204 338.446 + vertex 256.422 32.514 340.57 + endloop + endfacet + facet normal 0.106439 -0.825977 0.553563 + outer loop + vertex 256.422 32.514 340.57 + vertex 245.791 29.7204 338.446 + vertex 257.097 31.2186 338.508 + endloop + endfacet + facet normal 0.0944342 -0.832699 0.545614 + outer loop + vertex 213.466 27.3058 340.583 + vertex 213.98 25.9959 338.495 + vertex 224.143 28.5026 340.561 + endloop + endfacet + facet normal 0.0949047 -0.833513 0.544288 + outer loop + vertex 224.143 28.5026 340.561 + vertex 213.98 25.9959 338.495 + vertex 224.603 27.1924 338.475 + endloop + endfacet + facet normal 0.0932546 -0.778056 0.621235 + outer loop + vertex 211.92 28.7033 342.565 + vertex 213.466 27.3058 340.583 + vertex 223.272 30.3713 342.95 + endloop + endfacet + facet normal 0.0874566 -0.768886 0.633376 + outer loop + vertex 223.272 30.3713 342.95 + vertex 213.466 27.3058 340.583 + vertex 224.143 28.5026 340.561 + endloop + endfacet + facet normal 0.0882993 -0.768674 0.633517 + outer loop + vertex 223.272 30.3713 342.95 + vertex 224.143 28.5026 340.561 + vertex 233.212 31.1577 342.519 + endloop + endfacet + facet normal 0.0921744 -0.775408 0.624697 + outer loop + vertex 233.212 31.1577 342.519 + vertex 224.143 28.5026 340.561 + vertex 234.712 29.7279 340.523 + endloop + endfacet + facet normal 0.0985416 -0.832843 0.544668 + outer loop + vertex 224.143 28.5026 340.561 + vertex 224.603 27.1924 338.475 + vertex 234.712 29.7279 340.523 + endloop + endfacet + facet normal 0.0977717 -0.831517 0.546827 + outer loop + vertex 234.712 29.7279 340.523 + vertex 224.603 27.1924 338.475 + vertex 235.132 28.4095 338.443 + endloop + endfacet + facet normal 0.0868555 -0.835432 0.542687 + outer loop + vertex 192.154 25.0269 340.578 + vertex 192.62 23.7174 338.487 + vertex 202.784 26.136 340.584 + endloop + endfacet + facet normal 0.0870329 -0.835741 0.542183 + outer loop + vertex 202.784 26.136 340.584 + vertex 192.62 23.7174 338.487 + vertex 203.275 24.8331 338.497 + endloop + endfacet + facet normal 0.0847909 -0.779639 0.620462 + outer loop + vertex 190.655 26.4455 342.565 + vertex 192.154 25.0269 340.578 + vertex 201.946 27.9951 342.969 + endloop + endfacet + facet normal 0.0802255 -0.772351 0.630109 + outer loop + vertex 201.946 27.9951 342.969 + vertex 192.154 25.0269 340.578 + vertex 202.784 26.136 340.584 + endloop + endfacet + facet normal 0.0803718 -0.772317 0.630133 + outer loop + vertex 201.946 27.9951 342.969 + vertex 202.784 26.136 340.584 + vertex 211.92 28.7033 342.565 + endloop + endfacet + facet normal 0.0856583 -0.781632 0.61783 + outer loop + vertex 211.92 28.7033 342.565 + vertex 202.784 26.136 340.584 + vertex 213.466 27.3058 340.583 + endloop + endfacet + facet normal 0.0914862 -0.834919 0.542716 + outer loop + vertex 202.784 26.136 340.584 + vertex 203.275 24.8331 338.497 + vertex 213.466 27.3058 340.583 + endloop + endfacet + facet normal 0.0906297 -0.833433 0.545139 + outer loop + vertex 213.466 27.3058 340.583 + vertex 203.275 24.8331 338.497 + vertex 213.98 25.9959 338.495 + endloop + endfacet + facet normal 0.0778956 -0.838477 0.539342 + outer loop + vertex 171.025 22.9879 340.566 + vertex 171.458 21.6818 338.473 + vertex 181.594 23.9724 340.57 + endloop + endfacet + facet normal 0.0784439 -0.839447 0.537751 + outer loop + vertex 181.594 23.9724 340.57 + vertex 171.458 21.6818 338.473 + vertex 182.023 22.6735 338.48 + endloop + endfacet + facet normal 0.0770264 -0.782443 0.61794 + outer loop + vertex 169.528 24.4129 342.557 + vertex 171.025 22.9879 340.566 + vertex 180.776 25.842 342.965 + endloop + endfacet + facet normal 0.0718625 -0.774086 0.628989 + outer loop + vertex 180.776 25.842 342.965 + vertex 171.025 22.9879 340.566 + vertex 181.594 23.9724 340.57 + endloop + endfacet + facet normal 0.0727304 -0.773889 0.629131 + outer loop + vertex 180.776 25.842 342.965 + vertex 181.594 23.9724 340.57 + vertex 190.655 26.4455 342.565 + endloop + endfacet + facet normal 0.0777442 -0.782798 0.617401 + outer loop + vertex 190.655 26.4455 342.565 + vertex 181.594 23.9724 340.57 + vertex 192.154 25.0269 340.578 + endloop + endfacet + facet normal 0.0833756 -0.838643 0.538263 + outer loop + vertex 181.594 23.9724 340.57 + vertex 182.023 22.6735 338.48 + vertex 192.154 25.0269 340.578 + endloop + endfacet + facet normal 0.0820237 -0.836277 0.542138 + outer loop + vertex 192.154 25.0269 340.578 + vertex 182.023 22.6735 338.48 + vertex 192.62 23.7174 338.487 + endloop + endfacet + facet normal 0.0688365 -0.839826 0.538474 + outer loop + vertex 149.728 21.1681 340.558 + vertex 150.172 19.8611 338.463 + vertex 160.424 22.0467 340.561 + endloop + endfacet + facet normal 0.0693169 -0.840703 0.537041 + outer loop + vertex 160.424 22.0467 340.561 + vertex 150.172 19.8611 338.463 + vertex 160.854 20.745 338.468 + endloop + endfacet + facet normal 0.0681321 -0.78249 0.618924 + outer loop + vertex 148.194 22.6103 342.55 + vertex 149.728 21.1681 340.558 + vertex 159.563 23.9234 342.959 + endloop + endfacet + facet normal 0.0634613 -0.774708 0.629127 + outer loop + vertex 159.563 23.9234 342.959 + vertex 149.728 21.1681 340.558 + vertex 160.424 22.0467 340.561 + endloop + endfacet + facet normal 0.0633926 -0.774723 0.629115 + outer loop + vertex 159.563 23.9234 342.959 + vertex 160.424 22.0467 340.561 + vertex 169.528 24.4129 342.557 + endloop + endfacet + facet normal 0.0694426 -0.785766 0.614614 + outer loop + vertex 169.528 24.4129 342.557 + vertex 160.424 22.0467 340.561 + vertex 171.025 22.9879 340.566 + endloop + endfacet + facet normal 0.0742914 -0.839932 0.537583 + outer loop + vertex 160.424 22.0467 340.561 + vertex 160.854 20.745 338.468 + vertex 171.025 22.9879 340.566 + endloop + endfacet + facet normal 0.07384 -0.839123 0.538906 + outer loop + vertex 171.025 22.9879 340.566 + vertex 160.854 20.745 338.468 + vertex 171.458 21.6818 338.473 + endloop + endfacet + facet normal 0.0594817 -0.841452 0.537048 + outer loop + vertex 128.101 19.5741 340.55 + vertex 128.562 18.27 338.456 + vertex 138.95 20.3434 340.554 + endloop + endfacet + facet normal 0.0593515 -0.841205 0.537449 + outer loop + vertex 138.95 20.3434 340.554 + vertex 128.562 18.27 338.456 + vertex 139.399 19.0368 338.459 + endloop + endfacet + facet normal 0.0588539 -0.783899 0.618092 + outer loop + vertex 126.549 21.0309 342.546 + vertex 128.101 19.5741 340.55 + vertex 138.087 22.2177 342.952 + endloop + endfacet + facet normal 0.0548823 -0.777039 0.627055 + outer loop + vertex 138.087 22.2177 342.952 + vertex 128.101 19.5741 340.55 + vertex 138.95 20.3434 340.554 + endloop + endfacet + facet normal 0.055143 -0.776982 0.627103 + outer loop + vertex 138.087 22.2177 342.952 + vertex 138.95 20.3434 340.554 + vertex 148.194 22.6103 342.55 + endloop + endfacet + facet normal 0.0599406 -0.786078 0.615214 + outer loop + vertex 148.194 22.6103 342.55 + vertex 138.95 20.3434 340.554 + vertex 149.728 21.1681 340.558 + endloop + endfacet + facet normal 0.0641287 -0.840486 0.538025 + outer loop + vertex 138.95 20.3434 340.554 + vertex 139.399 19.0368 338.459 + vertex 149.728 21.1681 340.558 + endloop + endfacet + facet normal 0.0641601 -0.840544 0.53793 + outer loop + vertex 149.728 21.1681 340.558 + vertex 139.399 19.0368 338.459 + vertex 150.172 19.8611 338.463 + endloop + endfacet + facet normal 0.0494073 -0.841864 0.537424 + outer loop + vertex 106.404 18.2381 340.546 + vertex 106.872 16.9274 338.45 + vertex 117.218 18.8742 340.549 + endloop + endfacet + facet normal 0.0493047 -0.841664 0.537745 + outer loop + vertex 117.218 18.8742 340.549 + vertex 106.872 16.9274 338.45 + vertex 117.698 17.5627 338.452 + endloop + endfacet + facet normal 0.0483391 -0.782449 0.620835 + outer loop + vertex 104.902 19.729 342.542 + vertex 106.404 18.2381 340.546 + vertex 116.395 20.7616 342.949 + endloop + endfacet + facet normal 0.0456074 -0.777601 0.627102 + outer loop + vertex 116.395 20.7616 342.949 + vertex 106.404 18.2381 340.546 + vertex 117.218 18.8742 340.549 + endloop + endfacet + facet normal 0.0455285 -0.777617 0.627088 + outer loop + vertex 116.395 20.7616 342.949 + vertex 117.218 18.8742 340.549 + vertex 126.549 21.0309 342.546 + endloop + endfacet + facet normal 0.0505553 -0.787485 0.614257 + outer loop + vertex 126.549 21.0309 342.546 + vertex 117.218 18.8742 340.549 + vertex 128.101 19.5741 340.55 + endloop + endfacet + facet normal 0.0540056 -0.840967 0.538385 + outer loop + vertex 117.218 18.8742 340.549 + vertex 117.698 17.5627 338.452 + vertex 128.101 19.5741 340.55 + endloop + endfacet + facet normal 0.0546328 -0.842174 0.536432 + outer loop + vertex 128.101 19.5741 340.55 + vertex 117.698 17.5627 338.452 + vertex 128.562 18.27 338.456 + endloop + endfacet + facet normal 0.0390124 -0.842401 0.537438 + outer loop + vertex 85.0984 17.1886 340.545 + vertex 85.5552 15.8729 338.45 + vertex 95.7053 17.6804 340.546 + endloop + endfacet + facet normal 0.0390693 -0.842512 0.537258 + outer loop + vertex 95.7053 17.6804 340.546 + vertex 85.5552 15.8729 338.45 + vertex 96.1647 16.3646 338.45 + endloop + endfacet + facet normal 0.0390197 -0.782549 0.621366 + outer loop + vertex 83.5715 18.6973 342.541 + vertex 85.0984 17.1886 340.545 + vertex 94.927 19.5845 342.945 + endloop + endfacet + facet normal 0.0359764 -0.777081 0.628371 + outer loop + vertex 94.927 19.5845 342.945 + vertex 85.0984 17.1886 340.545 + vertex 95.7053 17.6804 340.546 + endloop + endfacet + facet normal 0.0366521 -0.776954 0.628489 + outer loop + vertex 94.927 19.5845 342.945 + vertex 95.7053 17.6804 340.546 + vertex 104.902 19.729 342.542 + endloop + endfacet + facet normal 0.0409312 -0.785484 0.617527 + outer loop + vertex 104.902 19.729 342.542 + vertex 95.7053 17.6804 340.546 + vertex 106.404 18.2381 340.546 + endloop + endfacet + facet normal 0.0438717 -0.841864 0.537904 + outer loop + vertex 95.7053 17.6804 340.546 + vertex 96.1647 16.3646 338.45 + vertex 106.404 18.2381 340.546 + endloop + endfacet + facet normal 0.0442457 -0.842594 0.536729 + outer loop + vertex 106.404 18.2381 340.546 + vertex 96.1647 16.3646 338.45 + vertex 106.872 16.9274 338.45 + endloop + endfacet + facet normal 0.0282202 -0.84117 0.540033 + outer loop + vertex 63.6412 16.4074 340.548 + vertex 64.1856 15.0799 338.452 + vertex 74.4302 16.7682 340.546 + endloop + endfacet + facet normal 0.0285207 -0.841785 0.539059 + outer loop + vertex 74.4302 16.7682 340.546 + vertex 64.1856 15.0799 338.452 + vertex 74.9366 15.4426 338.45 + endloop + endfacet + facet normal 0.029998 -0.784206 0.619775 + outer loop + vertex 62.0348 17.9222 342.543 + vertex 63.6412 16.4074 340.548 + vertex 73.5304 18.6807 342.946 + endloop + endfacet + facet normal 0.026087 -0.776948 0.629024 + outer loop + vertex 73.5304 18.6807 342.946 + vertex 63.6412 16.4074 340.548 + vertex 74.4302 16.7682 340.546 + endloop + endfacet + facet normal 0.0266414 -0.776834 0.629142 + outer loop + vertex 73.5304 18.6807 342.946 + vertex 74.4302 16.7682 340.546 + vertex 83.5715 18.6973 342.541 + endloop + endfacet + facet normal 0.031028 -0.785796 0.617707 + outer loop + vertex 83.5715 18.6973 342.541 + vertex 74.4302 16.7682 340.546 + vertex 85.0984 17.1886 340.545 + endloop + endfacet + facet normal 0.0332018 -0.841147 0.539786 + outer loop + vertex 74.4302 16.7682 340.546 + vertex 74.9366 15.4426 338.45 + vertex 85.0984 17.1886 340.545 + endloop + endfacet + facet normal 0.034147 -0.843034 0.536775 + outer loop + vertex 85.0984 17.1886 340.545 + vertex 74.9366 15.4426 338.45 + vertex 85.5552 15.8729 338.45 + endloop + endfacet + facet normal 0.0196292 -0.840881 0.540864 + outer loop + vertex 41.9865 15.8534 340.551 + vertex 42.5275 14.5179 338.455 + vertex 52.7822 16.1054 340.55 + endloop + endfacet + facet normal 0.0194877 -0.840584 0.541331 + outer loop + vertex 52.7822 16.1054 340.55 + vertex 42.5275 14.5179 338.455 + vertex 53.3477 14.7675 338.453 + endloop + endfacet + facet normal 0.0215233 -0.783484 0.621039 + outer loop + vertex 40.4251 17.3916 342.545 + vertex 41.9865 15.8534 340.551 + vertex 51.8852 18.0261 342.949 + endloop + endfacet + facet normal 0.0181395 -0.77705 0.629177 + outer loop + vertex 51.8852 18.0261 342.949 + vertex 41.9865 15.8534 340.551 + vertex 52.7822 16.1054 340.55 + endloop + endfacet + facet normal 0.0171929 -0.777237 0.628973 + outer loop + vertex 51.8852 18.0261 342.949 + vertex 52.7822 16.1054 340.55 + vertex 62.0348 17.9222 342.543 + endloop + endfacet + facet normal 0.0220321 -0.787529 0.615883 + outer loop + vertex 62.0348 17.9222 342.543 + vertex 52.7822 16.1054 340.55 + vertex 63.6412 16.4074 340.548 + endloop + endfacet + facet normal 0.0234763 -0.84002 0.542047 + outer loop + vertex 52.7822 16.1054 340.55 + vertex 53.3477 14.7675 338.453 + vertex 63.6412 16.4074 340.548 + endloop + endfacet + facet normal 0.0242939 -0.841723 0.539363 + outer loop + vertex 63.6412 16.4074 340.548 + vertex 53.3477 14.7675 338.453 + vertex 64.1856 15.0799 338.452 + endloop + endfacet + facet normal 0.00991355 -0.840563 0.541623 + outer loop + vertex 20.6959 15.5477 340.554 + vertex 21.2432 14.2047 338.46 + vertex 31.2994 15.6716 340.552 + endloop + endfacet + facet normal 0.010214 -0.841201 0.540627 + outer loop + vertex 31.2994 15.6716 340.552 + vertex 21.2432 14.2047 338.46 + vertex 31.8304 14.3317 338.457 + endloop + endfacet + facet normal 0.0126504 -0.78379 0.620897 + outer loop + vertex 19.1331 17.1013 342.547 + vertex 20.6959 15.5477 340.554 + vertex 30.4409 17.6039 342.951 + endloop + endfacet + facet normal 0.00918617 -0.777133 0.62927 + outer loop + vertex 30.4409 17.6039 342.951 + vertex 20.6959 15.5477 340.554 + vertex 31.2994 15.6716 340.552 + endloop + endfacet + facet normal 0.00906375 -0.777155 0.629244 + outer loop + vertex 30.4409 17.6039 342.951 + vertex 31.2994 15.6716 340.552 + vertex 40.4251 17.3916 342.545 + endloop + endfacet + facet normal 0.0134864 -0.786681 0.617213 + outer loop + vertex 40.4251 17.3916 342.545 + vertex 31.2994 15.6716 340.552 + vertex 41.9865 15.8534 340.551 + endloop + endfacet + facet normal 0.0143915 -0.840675 0.541349 + outer loop + vertex 31.2994 15.6716 340.552 + vertex 31.8304 14.3317 338.457 + vertex 41.9865 15.8534 340.551 + endloop + endfacet + facet normal 0.0147915 -0.84152 0.540023 + outer loop + vertex 41.9865 15.8534 340.551 + vertex 31.8304 14.3317 338.457 + vertex 42.5275 14.5179 338.455 + endloop + endfacet + facet normal 0.00169436 -0.840817 0.541318 + outer loop + vertex -0.486656 15.4507 340.555 + vertex 0.0991727 14.1041 338.461 + vertex 10.1075 15.4716 340.554 + endloop + endfacet + facet normal 0.00176807 -0.840976 0.541069 + outer loop + vertex 10.1075 15.4716 340.554 + vertex 0.0991727 14.1041 338.461 + vertex 10.6834 14.1255 338.46 + endloop + endfacet + facet normal 0.00546387 -0.784086 0.620628 + outer loop + vertex -2.06869 17.0175 342.548 + vertex -0.486656 15.4507 340.555 + vertex 9.19762 17.4157 342.952 + endloop + endfacet + facet normal 0.00157337 -0.776494 0.630122 + outer loop + vertex 9.19762 17.4157 342.952 + vertex -0.486656 15.4507 340.555 + vertex 10.1075 15.4716 340.554 + endloop + endfacet + facet normal 0.00109401 -0.776584 0.630013 + outer loop + vertex 9.19762 17.4157 342.952 + vertex 10.1075 15.4716 340.554 + vertex 19.1331 17.1013 342.547 + endloop + endfacet + facet normal 0.00564443 -0.786523 0.617535 + outer loop + vertex 19.1331 17.1013 342.547 + vertex 10.1075 15.4716 340.554 + vertex 20.6959 15.5477 340.554 + endloop + endfacet + facet normal 0.00603229 -0.840428 0.54189 + outer loop + vertex 10.1075 15.4716 340.554 + vertex 10.6834 14.1255 338.46 + vertex 20.6959 15.5477 340.554 + endloop + endfacet + facet normal 0.00630778 -0.841017 0.540972 + outer loop + vertex 20.6959 15.5477 340.554 + vertex 10.6834 14.1255 338.46 + vertex 21.2432 14.2047 338.46 + endloop + endfacet + facet normal -0.00582098 -0.841741 0.539851 + outer loop + vertex -21.5664 15.5496 340.553 + vertex -20.9974 14.203 338.46 + vertex -11.0441 15.4778 340.555 + endloop + endfacet + facet normal -0.00629522 -0.840697 0.541469 + outer loop + vertex -11.0441 15.4778 340.555 + vertex -20.9974 14.203 338.46 + vertex -10.4609 14.124 338.46 + endloop + endfacet + facet normal -0.00183105 -0.783809 0.620999 + outer loop + vertex -23.1798 17.1336 342.548 + vertex -21.5664 15.5496 340.553 + vertex -11.958 17.4278 342.952 + endloop + endfacet + facet normal -0.00539043 -0.776779 0.629751 + outer loop + vertex -11.958 17.4278 342.952 + vertex -21.5664 15.5496 340.553 + vertex -11.0441 15.4778 340.555 + endloop + endfacet + facet normal -0.00650678 -0.776981 0.62949 + outer loop + vertex -11.958 17.4278 342.952 + vertex -11.0441 15.4778 340.555 + vertex -2.06869 17.0175 342.548 + endloop + endfacet + facet normal -0.00201117 -0.786983 0.616972 + outer loop + vertex -2.06869 17.0175 342.548 + vertex -11.0441 15.4778 340.555 + vertex -0.486656 15.4507 340.555 + endloop + endfacet + facet normal -0.00214881 -0.840186 0.542293 + outer loop + vertex -11.0441 15.4778 340.555 + vertex -10.4609 14.124 338.46 + vertex -0.486656 15.4507 340.555 + endloop + endfacet + facet normal -0.00166354 -0.841244 0.540653 + outer loop + vertex -0.486656 15.4507 340.555 + vertex -10.4609 14.124 338.46 + vertex 0.0991727 14.1041 338.461 + endloop + endfacet + facet normal -0.0149506 -0.840904 0.540978 + outer loop + vertex -42.9431 15.8756 340.55 + vertex -42.2941 14.5162 338.455 + vertex -32.1776 15.6858 340.553 + endloop + endfacet + facet normal -0.0148364 -0.841166 0.540573 + outer loop + vertex -32.1776 15.6858 340.553 + vertex -42.2941 14.5162 338.455 + vertex -31.5707 14.3286 338.457 + endloop + endfacet + facet normal -0.0104307 -0.784028 0.620638 + outer loop + vertex -44.6618 17.4778 342.545 + vertex -42.9431 15.8756 340.55 + vertex -33.1964 17.6462 342.951 + endloop + endfacet + facet normal -0.0138437 -0.777018 0.629326 + outer loop + vertex -33.1964 17.6462 342.951 + vertex -42.9431 15.8756 340.55 + vertex -32.1776 15.6858 340.553 + endloop + endfacet + facet normal -0.0144679 -0.777141 0.629161 + outer loop + vertex -33.1964 17.6462 342.951 + vertex -32.1776 15.6858 340.553 + vertex -23.1798 17.1336 342.548 + endloop + endfacet + facet normal -0.010143 -0.787029 0.616832 + outer loop + vertex -23.1798 17.1336 342.548 + vertex -32.1776 15.6858 340.553 + vertex -21.5664 15.5496 340.553 + endloop + endfacet + facet normal -0.0108264 -0.840682 0.541421 + outer loop + vertex -32.1776 15.6858 340.553 + vertex -31.5707 14.3286 338.457 + vertex -21.5664 15.5496 340.553 + endloop + endfacet + facet normal -0.0101292 -0.842243 0.539003 + outer loop + vertex -21.5664 15.5496 340.553 + vertex -31.5707 14.3286 338.457 + vertex -20.9974 14.203 338.46 + endloop + endfacet + facet normal -0.0241182 -0.841549 0.539643 + outer loop + vertex -64.7797 16.441 340.548 + vertex -64.1062 15.0773 338.451 + vertex -53.8609 16.129 340.549 + endloop + endfacet + facet normal -0.0237224 -0.842494 0.538183 + outer loop + vertex -53.8609 16.129 340.549 + vertex -64.1062 15.0773 338.451 + vertex -53.1863 14.7718 338.454 + endloop + endfacet + facet normal -0.0193399 -0.782469 0.62239 + outer loop + vertex -66.4422 18.0691 342.543 + vertex -64.7797 16.441 340.548 + vertex -54.8988 18.1064 342.948 + endloop + endfacet + facet normal -0.0222634 -0.77621 0.630081 + outer loop + vertex -54.8988 18.1064 342.948 + vertex -64.7797 16.441 340.548 + vertex -53.8609 16.129 340.549 + endloop + endfacet + facet normal -0.0228682 -0.776327 0.629915 + outer loop + vertex -54.8988 18.1064 342.948 + vertex -53.8609 16.129 340.549 + vertex -44.6618 17.4778 342.545 + endloop + endfacet + facet normal -0.0183365 -0.787224 0.616394 + outer loop + vertex -44.6618 17.4778 342.545 + vertex -53.8609 16.129 340.549 + vertex -42.9431 15.8756 340.55 + endloop + endfacet + facet normal -0.0195985 -0.841968 0.539171 + outer loop + vertex -53.8609 16.129 340.549 + vertex -53.1863 14.7718 338.454 + vertex -42.9431 15.8756 340.55 + endloop + endfacet + facet normal -0.0197914 -0.841513 0.539874 + outer loop + vertex -42.9431 15.8756 340.55 + vertex -53.1863 14.7718 338.454 + vertex -42.2941 14.5162 338.455 + endloop + endfacet + facet normal -0.0336018 -0.84113 0.539788 + outer loop + vertex -86.1112 17.2337 340.546 + vertex -85.4748 15.8621 338.448 + vertex -75.5404 16.8124 340.547 + endloop + endfacet + facet normal -0.0330637 -0.84241 0.537821 + outer loop + vertex -75.5404 16.8124 340.547 + vertex -85.4748 15.8621 338.448 + vertex -74.8943 15.4486 338.451 + endloop + endfacet + facet normal -0.0287453 -0.782626 0.621828 + outer loop + vertex -87.7346 18.8789 342.541 + vertex -86.1112 17.2337 340.546 + vertex -76.4596 18.7866 342.946 + endloop + endfacet + facet normal -0.0310818 -0.77761 0.627978 + outer loop + vertex -76.4596 18.7866 342.946 + vertex -86.1112 17.2337 340.546 + vertex -75.5404 16.8124 340.547 + endloop + endfacet + facet normal -0.0303833 -0.777497 0.628152 + outer loop + vertex -76.4596 18.7866 342.946 + vertex -75.5404 16.8124 340.547 + vertex -66.4422 18.0691 342.543 + endloop + endfacet + facet normal -0.0271304 -0.78545 0.618331 + outer loop + vertex -66.4422 18.0691 342.543 + vertex -75.5404 16.8124 340.547 + vertex -64.7797 16.441 340.548 + endloop + endfacet + facet normal -0.0290774 -0.84196 0.538756 + outer loop + vertex -75.5404 16.8124 340.547 + vertex -74.8943 15.4486 338.451 + vertex -64.7797 16.441 340.548 + endloop + endfacet + facet normal -0.0289985 -0.842149 0.538465 + outer loop + vertex -64.7797 16.441 340.548 + vertex -74.8943 15.4486 338.451 + vertex -64.1062 15.0773 338.451 + endloop + endfacet + facet normal -0.0448271 -0.840517 0.539927 + outer loop + vertex -107.233 18.29 340.548 + vertex -106.519 16.9043 338.45 + vertex -96.6331 17.7234 340.546 + endloop + endfacet + facet normal -0.0440156 -0.842511 0.536878 + outer loop + vertex -96.6331 17.7234 340.546 + vertex -106.519 16.9043 338.45 + vertex -95.973 16.3533 338.45 + endloop + endfacet + facet normal -0.0380029 -0.784332 0.619177 + outer loop + vertex -108.945 19.9471 342.542 + vertex -107.233 18.29 340.548 + vertex -97.6467 19.7182 342.945 + endloop + endfacet + facet normal -0.0414088 -0.776842 0.628333 + outer loop + vertex -97.6467 19.7182 342.945 + vertex -107.233 18.29 340.548 + vertex -96.6331 17.7234 340.546 + endloop + endfacet + facet normal -0.0401382 -0.776622 0.628687 + outer loop + vertex -97.6467 19.7182 342.945 + vertex -96.6331 17.7234 340.546 + vertex -87.7346 18.8789 342.541 + endloop + endfacet + facet normal -0.0365528 -0.785469 0.617821 + outer loop + vertex -87.7346 18.8789 342.541 + vertex -96.6331 17.7234 340.546 + vertex -86.1112 17.2337 340.546 + endloop + endfacet + facet normal -0.0391843 -0.841994 0.538062 + outer loop + vertex -96.6331 17.7234 340.546 + vertex -95.973 16.3533 338.45 + vertex -86.1112 17.2337 340.546 + endloop + endfacet + facet normal -0.0392914 -0.841736 0.538458 + outer loop + vertex -86.1112 17.2337 340.546 + vertex -95.973 16.3533 338.45 + vertex -85.4748 15.8621 338.448 + endloop + endfacet + facet normal -0.0542127 -0.840634 0.538884 + outer loop + vertex -128.612 19.6093 340.551 + vertex -127.896 18.2193 338.455 + vertex -117.921 18.9185 340.549 + endloop + endfacet + facet normal -0.053672 -0.842019 0.536771 + outer loop + vertex -117.921 18.9185 340.549 + vertex -127.896 18.2193 338.455 + vertex -117.197 17.5365 338.454 + endloop + endfacet + facet normal -0.0475699 -0.782855 0.620383 + outer loop + vertex -130.3 21.2924 342.546 + vertex -128.612 19.6093 340.551 + vertex -118.979 20.923 342.947 + endloop + endfacet + facet normal -0.050091 -0.77711 0.627368 + outer loop + vertex -118.979 20.923 342.947 + vertex -128.612 19.6093 340.551 + vertex -117.921 18.9185 340.549 + endloop + endfacet + facet normal -0.0502148 -0.777132 0.627332 + outer loop + vertex -118.979 20.923 342.947 + vertex -117.921 18.9185 340.549 + vertex -108.945 19.9471 342.542 + endloop + endfacet + facet normal -0.0462275 -0.787419 0.614682 + outer loop + vertex -108.945 19.9471 342.542 + vertex -117.921 18.9185 340.549 + vertex -107.233 18.29 340.548 + endloop + endfacet + facet normal -0.0494206 -0.841543 0.537925 + outer loop + vertex -117.921 18.9185 340.549 + vertex -117.197 17.5365 338.454 + vertex -107.233 18.29 340.548 + endloop + endfacet + facet normal -0.0496108 -0.841063 0.538658 + outer loop + vertex -107.233 18.29 340.548 + vertex -117.197 17.5365 338.454 + vertex -106.519 16.9043 338.45 + endloop + endfacet + facet normal -0.0639658 -0.839486 0.539604 + outer loop + vertex -149.751 21.1677 340.557 + vertex -149.068 19.7693 338.463 + vertex -139.221 20.3639 340.555 + endloop + endfacet + facet normal -0.0633837 -0.841008 0.537297 + outer loop + vertex -139.221 20.3639 340.555 + vertex -149.068 19.7693 338.463 + vertex -138.536 18.9741 338.46 + endloop + endfacet + facet normal -0.0564037 -0.783532 0.618787 + outer loop + vertex -151.434 22.8633 342.551 + vertex -149.751 21.1677 340.557 + vertex -140.221 22.3732 342.952 + endloop + endfacet + facet normal -0.059183 -0.777088 0.626603 + outer loop + vertex -140.221 22.3732 342.952 + vertex -149.751 21.1677 340.557 + vertex -139.221 20.3639 340.555 + endloop + endfacet + facet normal -0.0589585 -0.777054 0.626667 + outer loop + vertex -140.221 22.3732 342.952 + vertex -139.221 20.3639 340.555 + vertex -130.3 21.2924 342.546 + endloop + endfacet + facet normal -0.0556691 -0.78578 0.615996 + outer loop + vertex -130.3 21.2924 342.546 + vertex -139.221 20.3639 340.555 + vertex -128.612 19.6093 340.551 + endloop + endfacet + facet normal -0.0595989 -0.840646 0.538296 + outer loop + vertex -139.221 20.3639 340.555 + vertex -138.536 18.9741 338.46 + vertex -128.612 19.6093 340.551 + endloop + endfacet + facet normal -0.0593925 -0.841183 0.53748 + outer loop + vertex -128.612 19.6093 340.551 + vertex -138.536 18.9741 338.46 + vertex -127.896 18.2193 338.455 + endloop + endfacet + facet normal -0.0738117 -0.839471 0.538368 + outer loop + vertex -171.041 22.9854 340.563 + vertex -170.315 21.581 338.473 + vertex -160.34 22.043 340.561 + endloop + endfacet + facet normal -0.0736454 -0.83993 0.537675 + outer loop + vertex -160.34 22.043 340.561 + vertex -170.315 21.581 338.473 + vertex -159.633 20.6414 338.468 + endloop + endfacet + facet normal -0.0652681 -0.781279 0.62076 + outer loop + vertex -172.794 24.7145 342.555 + vertex -171.041 22.9854 340.563 + vertex -161.428 24.0844 342.957 + endloop + endfacet + facet normal -0.0680706 -0.774499 0.628902 + outer loop + vertex -161.428 24.0844 342.957 + vertex -171.041 22.9854 340.563 + vertex -160.34 22.043 340.561 + endloop + endfacet + facet normal -0.0690971 -0.774669 0.62858 + outer loop + vertex -161.428 24.0844 342.957 + vertex -160.34 22.043 340.561 + vertex -151.434 22.8633 342.551 + endloop + endfacet + facet normal -0.0647979 -0.786479 0.614209 + outer loop + vertex -151.434 22.8633 342.551 + vertex -160.34 22.043 340.561 + vertex -149.751 21.1677 340.557 + endloop + endfacet + facet normal -0.0692089 -0.839522 0.5389 + outer loop + vertex -160.34 22.043 340.561 + vertex -159.633 20.6414 338.468 + vertex -149.751 21.1677 340.557 + endloop + endfacet + facet normal -0.0690498 -0.839949 0.538255 + outer loop + vertex -149.751 21.1677 340.557 + vertex -159.633 20.6414 338.468 + vertex -149.068 19.7693 338.463 + endloop + endfacet + facet normal -0.0826197 -0.835572 0.543133 + outer loop + vertex -192.647 25.0703 340.571 + vertex -191.915 23.6375 338.478 + vertex -181.843 23.9995 340.567 + endloop + endfacet + facet normal -0.0817732 -0.838021 0.539476 + outer loop + vertex -181.843 23.9995 340.567 + vertex -191.915 23.6375 338.478 + vertex -181.105 22.5812 338.476 + endloop + endfacet + facet normal -0.0741923 -0.779142 0.622442 + outer loop + vertex -194.348 26.824 342.563 + vertex -192.647 25.0703 340.571 + vertex -182.919 26.0547 342.963 + endloop + endfacet + facet normal -0.0764322 -0.773464 0.629215 + outer loop + vertex -182.919 26.0547 342.963 + vertex -192.647 25.0703 340.571 + vertex -181.843 23.9995 340.567 + endloop + endfacet + facet normal -0.0770786 -0.773565 0.629012 + outer loop + vertex -182.919 26.0547 342.963 + vertex -181.843 23.9995 340.567 + vertex -172.794 24.7145 342.555 + endloop + endfacet + facet normal -0.0734094 -0.784208 0.61614 + outer loop + vertex -172.794 24.7145 342.555 + vertex -181.843 23.9995 340.567 + vertex -171.041 22.9854 340.563 + endloop + endfacet + facet normal -0.0784588 -0.837716 0.54044 + outer loop + vertex -181.843 23.9995 340.567 + vertex -181.105 22.5812 338.476 + vertex -171.041 22.9854 340.563 + endloop + endfacet + facet normal -0.0777131 -0.839832 0.537255 + outer loop + vertex -171.041 22.9854 340.563 + vertex -181.105 22.5812 338.476 + vertex -170.315 21.581 338.473 + endloop + endfacet + facet normal -0.0912699 -0.832971 0.545737 + outer loop + vertex -214.086 27.369 340.583 + vertex -213.422 25.9258 338.492 + vertex -203.393 26.193 340.577 + endloop + endfacet + facet normal -0.0905834 -0.835028 0.542699 + outer loop + vertex -203.393 26.193 340.577 + vertex -213.422 25.9258 338.492 + vertex -202.693 24.7572 338.484 + endloop + endfacet + facet normal -0.082219 -0.778086 0.622754 + outer loop + vertex -215.69 29.1291 342.571 + vertex -214.086 27.369 340.583 + vertex -204.37 28.2536 342.972 + endloop + endfacet + facet normal -0.0845195 -0.772074 0.629887 + outer loop + vertex -204.37 28.2536 342.972 + vertex -214.086 27.369 340.583 + vertex -203.393 26.193 340.577 + endloop + endfacet + facet normal -0.0844778 -0.772069 0.629899 + outer loop + vertex -204.37 28.2536 342.972 + vertex -203.393 26.193 340.577 + vertex -194.348 26.824 342.563 + endloop + endfacet + facet normal -0.0813115 -0.781567 0.618499 + outer loop + vertex -194.348 26.824 342.563 + vertex -203.393 26.193 340.577 + vertex -192.647 25.0703 340.571 + endloop + endfacet + facet normal -0.0869084 -0.834746 0.543734 + outer loop + vertex -203.393 26.193 340.577 + vertex -202.693 24.7572 338.484 + vertex -192.647 25.0703 340.571 + endloop + endfacet + facet normal -0.0865127 -0.835911 0.542004 + outer loop + vertex -192.647 25.0703 340.571 + vertex -202.693 24.7572 338.484 + vertex -191.915 23.6375 338.478 + endloop + endfacet + facet normal -0.0990669 -0.830382 0.548317 + outer loop + vertex -235.391 29.8477 340.567 + vertex -234.84 28.4071 338.485 + vertex -224.732 28.5854 340.581 + endloop + endfacet + facet normal -0.0989029 -0.830894 0.54757 + outer loop + vertex -224.732 28.5854 340.581 + vertex -234.84 28.4071 338.485 + vertex -224.121 27.1366 338.493 + endloop + endfacet + facet normal -0.0902649 -0.773404 0.627454 + outer loop + vertex -237.032 31.6474 342.549 + vertex -235.391 29.8477 340.567 + vertex -225.651 30.6574 342.966 + endloop + endfacet + facet normal -0.0919072 -0.768982 0.63263 + outer loop + vertex -225.651 30.6574 342.966 + vertex -235.391 29.8477 340.567 + vertex -224.732 28.5854 340.581 + endloop + endfacet + facet normal -0.092888 -0.769094 0.63235 + outer loop + vertex -225.651 30.6574 342.966 + vertex -224.732 28.5854 340.581 + vertex -215.69 29.1291 342.571 + endloop + endfacet + facet normal -0.0892797 -0.780292 0.61901 + outer loop + vertex -215.69 29.1291 342.571 + vertex -224.732 28.5854 340.581 + vertex -214.086 27.369 340.583 + endloop + endfacet + facet normal -0.0950228 -0.830691 0.548565 + outer loop + vertex -224.732 28.5854 340.581 + vertex -224.121 27.1366 338.493 + vertex -214.086 27.369 340.583 + endloop + endfacet + facet normal -0.0942101 -0.833166 0.544939 + outer loop + vertex -214.086 27.369 340.583 + vertex -224.121 27.1366 338.493 + vertex -213.422 25.9258 338.492 + endloop + endfacet + facet normal -0.10684 -0.826132 0.553255 + outer loop + vertex -257.373 32.6481 340.569 + vertex -256.566 31.1437 338.478 + vertex -246.239 31.1992 340.555 + endloop + endfacet + facet normal -0.106217 -0.828241 0.550214 + outer loop + vertex -246.239 31.1992 340.555 + vertex -256.566 31.1437 338.478 + vertex -245.625 29.7345 338.469 + endloop + endfacet + facet normal -0.0983217 -0.768729 0.631972 + outer loop + vertex -259.466 34.5442 342.549 + vertex -257.373 32.6481 340.569 + vertex -247.384 33.3245 342.946 + endloop + endfacet + facet normal -0.0990105 -0.766724 0.634296 + outer loop + vertex -247.384 33.3245 342.946 + vertex -257.373 32.6481 340.569 + vertex -246.239 31.1992 340.555 + endloop + endfacet + facet normal -0.0999778 -0.766873 0.633964 + outer loop + vertex -247.384 33.3245 342.946 + vertex -246.239 31.1992 340.555 + vertex -237.032 31.6474 342.549 + endloop + endfacet + facet normal -0.0973154 -0.77563 0.623641 + outer loop + vertex -237.032 31.6474 342.549 + vertex -246.239 31.1992 340.555 + vertex -235.391 29.8477 340.567 + endloop + endfacet + facet normal -0.103776 -0.828126 0.550852 + outer loop + vertex -246.239 31.1992 340.555 + vertex -245.625 29.7345 338.469 + vertex -235.391 29.8477 340.567 + endloop + endfacet + facet normal -0.103035 -0.830526 0.547367 + outer loop + vertex -235.391 29.8477 340.567 + vertex -245.625 29.7345 338.469 + vertex -234.84 28.4071 338.485 + endloop + endfacet + facet normal -0.117097 -0.810419 0.574029 + outer loop + vertex -281.009 35.8844 340.466 + vertex -277.201 34.1421 338.783 + vertex -268.779 34.2156 340.605 + endloop + endfacet + facet normal -0.113459 -0.822259 0.557689 + outer loop + vertex -268.779 34.2156 340.605 + vertex -277.201 34.1421 338.783 + vertex -267.526 32.6663 338.576 + endloop + endfacet + facet normal -0.107811 -0.769255 0.629781 + outer loop + vertex -283.989 38.016 342.56 + vertex -281.009 35.8844 340.466 + vertex -270.715 36.4827 342.959 + endloop + endfacet + facet normal -0.110957 -0.759882 0.640521 + outer loop + vertex -270.715 36.4827 342.959 + vertex -281.009 35.8844 340.466 + vertex -268.779 34.2156 340.605 + endloop + endfacet + facet normal -0.107366 -0.758791 0.642424 + outer loop + vertex -270.715 36.4827 342.959 + vertex -268.779 34.2156 340.605 + vertex -259.466 34.5442 342.549 + endloop + endfacet + facet normal -0.103969 -0.771051 0.628228 + outer loop + vertex -259.466 34.5442 342.549 + vertex -268.779 34.2156 340.605 + vertex -257.373 32.6481 340.569 + endloop + endfacet + facet normal -0.111169 -0.821833 0.558778 + outer loop + vertex -268.779 34.2156 340.605 + vertex -267.526 32.6663 338.576 + vertex -257.373 32.6481 340.569 + endloop + endfacet + facet normal -0.109898 -0.826394 0.552264 + outer loop + vertex -257.373 32.6481 340.569 + vertex -267.526 32.6663 338.576 + vertex -256.566 31.1437 338.478 + endloop + endfacet + facet normal -0.12012 -0.765961 0.631565 + outer loop + vertex -295.539 40.3197 343.157 + vertex -294.492 37.8308 340.338 + vertex -283.989 38.016 342.56 + endloop + endfacet + facet normal -0.117772 -0.774752 0.621199 + outer loop + vertex -283.989 38.016 342.56 + vertex -294.492 37.8308 340.338 + vertex -281.009 35.8844 340.466 + endloop + endfacet + facet normal -0.130356 -0.821347 0.555335 + outer loop + vertex -277.201 34.1421 338.783 + vertex -281.009 35.8844 340.466 + vertex -289.973 35.4404 337.705 + endloop + endfacet + facet normal -0.125263 -0.831962 0.540507 + outer loop + vertex -289.973 35.4404 337.705 + vertex -281.009 35.8844 340.466 + vertex -294.492 37.8308 340.338 + endloop + endfacet + facet normal -0.128462 -0.815669 0.564076 + outer loop + vertex -320.155 42.0154 340.612 + vertex -318.862 40.2321 338.328 + vertex -308.011 40.0594 340.549 + endloop + endfacet + facet normal -0.124732 -0.829234 0.544806 + outer loop + vertex -308.011 40.0594 340.549 + vertex -318.862 40.2321 338.328 + vertex -306.619 37.9015 337.584 + endloop + endfacet + facet normal -0.118586 -0.761811 0.636853 + outer loop + vertex -322.803 44.0252 342.523 + vertex -320.155 42.0154 340.612 + vertex -310.799 42.6999 343.173 + endloop + endfacet + facet normal -0.11916 -0.760302 0.638547 + outer loop + vertex -310.799 42.6999 343.173 + vertex -320.155 42.0154 340.612 + vertex -308.011 40.0594 340.549 + endloop + endfacet + facet normal -0.117827 -0.759769 0.639428 + outer loop + vertex -310.799 42.6999 343.173 + vertex -308.011 40.0594 340.549 + vertex -295.539 40.3197 343.157 + endloop + endfacet + facet normal -0.116296 -0.765624 0.632688 + outer loop + vertex -295.539 40.3197 343.157 + vertex -308.011 40.0594 340.549 + vertex -294.492 37.8308 340.338 + endloop + endfacet + facet normal -0.128242 -0.829603 0.543428 + outer loop + vertex -308.011 40.0594 340.549 + vertex -306.619 37.9015 337.584 + vertex -294.492 37.8308 340.338 + endloop + endfacet + facet normal -0.127109 -0.833079 0.538352 + outer loop + vertex -294.492 37.8308 340.338 + vertex -306.619 37.9015 337.584 + vertex -289.973 35.4404 337.705 + endloop + endfacet + facet normal -0.145568 -0.819018 0.554995 + outer loop + vertex -340.629 45.3312 340.299 + vertex -339.507 43.8481 338.405 + vertex -330.671 43.6958 340.498 + endloop + endfacet + facet normal -0.146891 -0.814752 0.560893 + outer loop + vertex -330.671 43.6958 340.498 + vertex -339.507 43.8481 338.405 + vertex -329.388 42.0846 338.493 + endloop + endfacet + facet normal -0.133163 -0.781772 0.60918 + outer loop + vertex -342.386 46.8244 341.831 + vertex -340.629 45.3312 340.299 + vertex -332.385 45.647 342.507 + endloop + endfacet + facet normal -0.138429 -0.766856 0.626714 + outer loop + vertex -332.385 45.647 342.507 + vertex -340.629 45.3312 340.299 + vertex -330.671 43.6958 340.498 + endloop + endfacet + facet normal -0.130488 -0.764538 0.631233 + outer loop + vertex -332.385 45.647 342.507 + vertex -330.671 43.6958 340.498 + vertex -322.803 44.0252 342.523 + endloop + endfacet + facet normal -0.129476 -0.767539 0.62779 + outer loop + vertex -322.803 44.0252 342.523 + vertex -330.671 43.6958 340.498 + vertex -320.155 42.0154 340.612 + endloop + endfacet + facet normal -0.136051 -0.812876 0.566324 + outer loop + vertex -330.671 43.6958 340.498 + vertex -329.388 42.0846 338.493 + vertex -320.155 42.0154 340.612 + endloop + endfacet + facet normal -0.134898 -0.816627 0.56118 + outer loop + vertex -320.155 42.0154 340.612 + vertex -329.388 42.0846 338.493 + vertex -318.862 40.2321 338.328 + endloop + endfacet + facet normal -0.165251 -0.82812 0.535639 + outer loop + vertex -360.942 49.0148 339.908 + vertex -360.369 47.6177 337.925 + vertex -350.582 47.0653 340.09 + endloop + endfacet + facet normal -0.165932 -0.825555 0.539374 + outer loop + vertex -350.582 47.0653 340.09 + vertex -360.369 47.6177 337.925 + vertex -349.77 45.6691 338.203 + endloop + endfacet + facet normal -0.157118 -0.786281 0.597558 + outer loop + vertex -361.515 50.6918 341.964 + vertex -360.942 49.0148 339.908 + vertex -350.621 48.5878 342.06 + endloop + endfacet + facet normal -0.157885 -0.782787 0.601927 + outer loop + vertex -350.621 48.5878 342.06 + vertex -360.942 49.0148 339.908 + vertex -350.582 47.0653 340.09 + endloop + endfacet + facet normal -0.151069 -0.783566 0.602662 + outer loop + vertex -350.621 48.5878 342.06 + vertex -350.582 47.0653 340.09 + vertex -342.386 46.8244 341.831 + endloop + endfacet + facet normal -0.149908 -0.788479 0.596514 + outer loop + vertex -342.386 46.8244 341.831 + vertex -350.582 47.0653 340.09 + vertex -340.629 45.3312 340.299 + endloop + endfacet + facet normal -0.155143 -0.824917 0.543546 + outer loop + vertex -350.582 47.0653 340.09 + vertex -349.77 45.6691 338.203 + vertex -340.629 45.3312 340.299 + endloop + endfacet + facet normal -0.156409 -0.820544 0.549768 + outer loop + vertex -340.629 45.3312 340.299 + vertex -349.77 45.6691 338.203 + vertex -339.507 43.8481 338.405 + endloop + endfacet + facet normal -0.183057 -0.835489 0.518121 + outer loop + vertex -381.989 53.1435 339.313 + vertex -381.279 51.6597 337.172 + vertex -371.767 51.0853 339.606 + endloop + endfacet + facet normal -0.18426 -0.831731 0.52371 + outer loop + vertex -371.767 51.0853 339.606 + vertex -381.279 51.6597 337.172 + vertex -371.083 49.6497 337.567 + endloop + endfacet + facet normal -0.176925 -0.785198 0.593432 + outer loop + vertex -383.21 55.0076 341.416 + vertex -381.989 53.1435 339.313 + vertex -372.748 52.8478 341.677 + endloop + endfacet + facet normal -0.17576 -0.789258 0.58837 + outer loop + vertex -372.748 52.8478 341.677 + vertex -381.989 53.1435 339.313 + vertex -371.767 51.0853 339.606 + endloop + endfacet + facet normal -0.166453 -0.788477 0.592112 + outer loop + vertex -372.748 52.8478 341.677 + vertex -371.767 51.0853 339.606 + vertex -361.515 50.6918 341.964 + endloop + endfacet + facet normal -0.166995 -0.786314 0.59483 + outer loop + vertex -361.515 50.6918 341.964 + vertex -371.767 51.0853 339.606 + vertex -360.942 49.0148 339.908 + endloop + endfacet + facet normal -0.1738 -0.831754 0.527238 + outer loop + vertex -371.767 51.0853 339.606 + vertex -371.083 49.6497 337.567 + vertex -360.942 49.0148 339.908 + endloop + endfacet + facet normal -0.174844 -0.827994 0.53278 + outer loop + vertex -360.942 49.0148 339.908 + vertex -371.083 49.6497 337.567 + vertex -360.369 47.6177 337.925 + endloop + endfacet + facet normal -0.185901 -0.775321 0.603587 + outer loop + vertex -392.863 57.0464 341.062 + vertex -389.629 54.8987 339.299 + vertex -383.21 55.0076 341.416 + endloop + endfacet + facet normal -0.181644 -0.78579 0.591218 + outer loop + vertex -383.21 55.0076 341.416 + vertex -389.629 54.8987 339.299 + vertex -381.989 53.1435 339.313 + endloop + endfacet + facet normal -0.192963 -0.835695 0.514177 + outer loop + vertex -389.629 54.8987 339.299 + vertex -390.502 53.606 336.87 + vertex -381.989 53.1435 339.313 + endloop + endfacet + facet normal -0.193093 -0.835347 0.514695 + outer loop + vertex -381.989 53.1435 339.313 + vertex -390.502 53.606 336.87 + vertex -381.279 51.6597 337.172 + endloop + endfacet + facet normal -0.243499 -0.840326 0.484314 + outer loop + vertex -400.066 56.8145 338.411 + vertex -398.672 55.1976 336.307 + vertex -399.379 56.4012 338.039 + endloop + endfacet + facet normal -0.152504 -0.839774 0.521077 + outer loop + vertex -399.379 56.4012 338.039 + vertex -398.672 55.1976 336.307 + vertex -398.029 54.8787 335.981 + endloop + endfacet + facet normal -0.298024 -0.788942 0.537356 + outer loop + vertex -401.126 58.6977 340.588 + vertex -400.066 56.8145 338.411 + vertex -400.626 58.1831 340.11 + endloop + endfacet + facet normal -0.160056 -0.793782 0.586764 + outer loop + vertex -400.626 58.1831 340.11 + vertex -400.066 56.8145 338.411 + vertex -399.379 56.4012 338.039 + endloop + endfacet + facet normal -0.212735 -0.800279 0.560623 + outer loop + vertex -400.626 58.1831 340.11 + vertex -399.379 56.4012 338.039 + vertex -398.453 57.3625 339.763 + endloop + endfacet + facet normal -0.192103 -0.809559 0.554716 + outer loop + vertex -398.453 57.3625 339.763 + vertex -399.379 56.4012 338.039 + vertex -395.923 55.5915 338.054 + endloop + endfacet + facet normal -0.20036 -0.845922 0.494239 + outer loop + vertex -399.379 56.4012 338.039 + vertex -398.029 54.8787 335.981 + vertex -395.923 55.5915 338.054 + endloop + endfacet + facet normal -0.19709 -0.848172 0.491691 + outer loop + vertex -395.923 55.5915 338.054 + vertex -398.029 54.8787 335.981 + vertex -396.011 54.2696 335.739 + endloop + endfacet + facet normal 0.172446 0.774128 -0.609088 + outer loop + vertex -401.072 59.1129 341.131 + vertex -400.104 57.1827 338.952 + vertex -401.126 58.6977 340.588 + endloop + endfacet + facet normal 0.348165 0.786194 -0.510568 + outer loop + vertex -401.126 58.6977 340.588 + vertex -400.104 57.1827 338.952 + vertex -400.066 56.8145 338.411 + endloop + endfacet + facet normal 0.166234 0.820536 -0.546888 + outer loop + vertex -400.104 57.1827 338.952 + vertex -398.807 55.4912 336.808 + vertex -400.066 56.8145 338.411 + endloop + endfacet + facet normal 0.389637 0.83675 -0.38475 + outer loop + vertex -400.066 56.8145 338.411 + vertex -398.807 55.4912 336.808 + vertex -398.672 55.1976 336.307 + endloop + endfacet + facet normal 0.201838 -0.907865 0.367482 + outer loop + vertex 393.159 52.9446 334.418 + vertex 391.577 51.7622 332.365 + vertex 395.884 53.3363 333.889 + endloop + endfacet + facet normal 0.216478 -0.91687 0.335392 + outer loop + vertex 395.884 53.3363 333.889 + vertex 391.577 51.7622 332.365 + vertex 394.078 52.163 331.847 + endloop + endfacet + facet normal 0.196242 -0.873612 0.445299 + outer loop + vertex 394.62 54.3375 336.506 + vertex 393.159 52.9446 334.418 + vertex 397.458 54.7168 336 + endloop + endfacet + facet normal 0.208672 -0.882502 0.42148 + outer loop + vertex 397.458 54.7168 336 + vertex 393.159 52.9446 334.418 + vertex 395.884 53.3363 333.889 + endloop + endfacet + facet normal 0.202185 -0.90488 0.374585 + outer loop + vertex 379.569 50.2142 335.183 + vertex 378.487 49.1353 333.161 + vertex 387.743 51.8776 334.789 + endloop + endfacet + facet normal 0.2026 -0.9054 0.3731 + outer loop + vertex 387.743 51.8776 334.789 + vertex 378.487 49.1353 333.161 + vertex 386.476 50.755 332.753 + endloop + endfacet + facet normal 0.199047 -0.871706 0.447782 + outer loop + vertex 381.017 51.5699 337.179 + vertex 379.569 50.2142 335.183 + vertex 389.138 53.2483 336.836 + endloop + endfacet + facet normal 0.198945 -0.871563 0.448105 + outer loop + vertex 389.138 53.2483 336.836 + vertex 379.569 50.2142 335.183 + vertex 387.743 51.8776 334.789 + endloop + endfacet + facet normal 0.200085 -0.871666 0.447397 + outer loop + vertex 389.138 53.2483 336.836 + vertex 387.743 51.8776 334.789 + vertex 394.62 54.3375 336.506 + endloop + endfacet + facet normal 0.202515 -0.874206 0.441307 + outer loop + vertex 394.62 54.3375 336.506 + vertex 387.743 51.8776 334.789 + vertex 393.159 52.9446 334.418 + endloop + endfacet + facet normal 0.203931 -0.905435 0.372291 + outer loop + vertex 387.743 51.8776 334.789 + vertex 386.476 50.755 332.753 + vertex 393.159 52.9446 334.418 + endloop + endfacet + facet normal 0.206978 -0.908221 0.363724 + outer loop + vertex 393.159 52.9446 334.418 + vertex 386.476 50.755 332.753 + vertex 391.577 51.7622 332.365 + endloop + endfacet + facet normal 0.186694 -0.902922 0.38714 + outer loop + vertex 359.391 46.2707 335.969 + vertex 358.339 45.2207 334.028 + vertex 369.719 48.2509 335.608 + endloop + endfacet + facet normal 0.187628 -0.904394 0.383232 + outer loop + vertex 369.719 48.2509 335.608 + vertex 358.339 45.2207 334.028 + vertex 368.637 47.1823 333.615 + endloop + endfacet + facet normal 0.180806 -0.864754 0.468519 + outer loop + vertex 360.631 47.5586 337.868 + vertex 359.391 46.2707 335.969 + vertex 371.154 49.5847 337.547 + endloop + endfacet + facet normal 0.182608 -0.867967 0.46183 + outer loop + vertex 371.154 49.5847 337.547 + vertex 359.391 46.2707 335.969 + vertex 369.719 48.2509 335.608 + endloop + endfacet + facet normal 0.191963 -0.869171 0.455732 + outer loop + vertex 371.154 49.5847 337.547 + vertex 369.719 48.2509 335.608 + vertex 381.017 51.5699 337.179 + endloop + endfacet + facet normal 0.19308 -0.871046 0.451662 + outer loop + vertex 381.017 51.5699 337.179 + vertex 369.719 48.2509 335.608 + vertex 379.569 50.2142 335.183 + endloop + endfacet + facet normal 0.196593 -0.904513 0.378428 + outer loop + vertex 369.719 48.2509 335.608 + vertex 368.637 47.1823 333.615 + vertex 379.569 50.2142 335.183 + endloop + endfacet + facet normal 0.196833 -0.904871 0.377445 + outer loop + vertex 379.569 50.2142 335.183 + vertex 368.637 47.1823 333.615 + vertex 378.487 49.1353 333.161 + endloop + endfacet + facet normal 0.166023 -0.900639 0.401604 + outer loop + vertex 339.412 42.6368 336.322 + vertex 338.769 41.6706 334.421 + vertex 349.245 44.3932 336.196 + endloop + endfacet + facet normal 0.165537 -0.899931 0.403388 + outer loop + vertex 349.245 44.3932 336.196 + vertex 338.769 41.6706 334.421 + vertex 348.356 43.381 334.303 + endloop + endfacet + facet normal 0.160325 -0.862004 0.480879 + outer loop + vertex 340.044 43.8433 338.274 + vertex 339.412 42.6368 336.322 + vertex 350.129 45.6206 338.098 + endloop + endfacet + facet normal 0.160078 -0.861598 0.481689 + outer loop + vertex 350.129 45.6206 338.098 + vertex 339.412 42.6368 336.322 + vertex 349.245 44.3932 336.196 + endloop + endfacet + facet normal 0.169526 -0.862067 0.477599 + outer loop + vertex 350.129 45.6206 338.098 + vertex 349.245 44.3932 336.196 + vertex 360.631 47.5586 337.868 + endloop + endfacet + facet normal 0.170402 -0.863592 0.474523 + outer loop + vertex 360.631 47.5586 337.868 + vertex 349.245 44.3932 336.196 + vertex 359.391 46.2707 335.969 + endloop + endfacet + facet normal 0.175465 -0.900091 0.398809 + outer loop + vertex 349.245 44.3932 336.196 + vertex 348.356 43.381 334.303 + vertex 359.391 46.2707 335.969 + endloop + endfacet + facet normal 0.17714 -0.902669 0.392186 + outer loop + vertex 359.391 46.2707 335.969 + vertex 348.356 43.381 334.303 + vertex 358.339 45.2207 334.028 + endloop + endfacet + facet normal 0.147729 -0.898772 0.412777 + outer loop + vertex 320.908 39.7908 336.972 + vertex 319.664 38.5538 334.724 + vertex 329.939 41.059 336.501 + endloop + endfacet + facet normal 0.149406 -0.901291 0.406636 + outer loop + vertex 329.939 41.059 336.501 + vertex 319.664 38.5538 334.724 + vertex 329.33 40.0543 334.498 + endloop + endfacet + facet normal 0.145981 -0.861422 0.486458 + outer loop + vertex 323.373 41.3008 338.906 + vertex 320.908 39.7908 336.972 + vertex 330.81 42.346 338.525 + endloop + endfacet + facet normal 0.146348 -0.862075 0.485189 + outer loop + vertex 330.81 42.346 338.525 + vertex 320.908 39.7908 336.972 + vertex 329.939 41.059 336.501 + endloop + endfacet + facet normal 0.152947 -0.862406 0.482559 + outer loop + vertex 330.81 42.346 338.525 + vertex 329.939 41.059 336.501 + vertex 340.044 43.8433 338.274 + endloop + endfacet + facet normal 0.152697 -0.862005 0.483353 + outer loop + vertex 340.044 43.8433 338.274 + vertex 329.939 41.059 336.501 + vertex 339.412 42.6368 336.322 + endloop + endfacet + facet normal 0.157704 -0.901062 0.404001 + outer loop + vertex 329.939 41.059 336.501 + vertex 329.33 40.0543 334.498 + vertex 339.412 42.6368 336.322 + endloop + endfacet + facet normal 0.157542 -0.900834 0.404572 + outer loop + vertex 339.412 42.6368 336.322 + vertex 329.33 40.0543 334.498 + vertex 338.769 41.6706 334.421 + endloop + endfacet + facet normal 0.132362 -0.880215 0.455744 + outer loop + vertex 313.251 39.2772 338.204 + vertex 308.126 37.0048 335.303 + vertex 320.908 39.7908 336.972 + endloop + endfacet + facet normal 0.137187 -0.858001 0.494989 + outer loop + vertex 323.373 41.3008 338.906 + vertex 313.251 39.2772 338.204 + vertex 320.908 39.7908 336.972 + endloop + endfacet + facet normal 0.141496 -0.898303 0.41597 + outer loop + vertex 319.664 38.5538 334.724 + vertex 320.908 39.7908 336.972 + vertex 308.126 37.0048 335.303 + endloop + endfacet + facet normal 0.134751 -0.892437 0.430578 + outer loop + vertex 296.097 34.837 334.575 + vertex 308.126 37.0048 335.303 + vertex 296.396 36.1769 337.258 + endloop + endfacet + facet normal 0.137185 -0.882808 0.449255 + outer loop + vertex 296.396 36.1769 337.258 + vertex 308.126 37.0048 335.303 + vertex 313.251 39.2772 338.204 + endloop + endfacet + facet normal 0.131771 -0.918584 0.372612 + outer loop + vertex 276.149 31.7802 334.21 + vertex 286.195 33.4012 334.654 + vertex 279.657 33.0074 335.995 + endloop + endfacet + facet normal 0.132034 -0.879498 0.457221 + outer loop + vertex 281.95 34.5239 338.25 + vertex 279.657 33.0074 335.995 + vertex 296.396 36.1769 337.258 + endloop + endfacet + facet normal 0.132875 -0.892583 0.43086 + outer loop + vertex 296.097 34.837 334.575 + vertex 296.396 36.1769 337.258 + vertex 286.195 33.4012 334.654 + endloop + endfacet + facet normal 0.139108 -0.899613 0.413939 + outer loop + vertex 279.657 33.0074 335.995 + vertex 286.195 33.4012 334.654 + vertex 296.396 36.1769 337.258 + endloop + endfacet + facet normal 0.123369 -0.920981 0.369559 + outer loop + vertex 257.055 30.1668 336.565 + vertex 256.972 29.3908 334.658 + vertex 268.701 31.6941 336.483 + endloop + endfacet + facet normal 0.120377 -0.91605 0.382573 + outer loop + vertex 268.701 31.6941 336.483 + vertex 256.972 29.3908 334.658 + vertex 267.775 30.7651 334.55 + endloop + endfacet + facet normal 0.118094 -0.874362 0.470686 + outer loop + vertex 257.097 31.2186 338.508 + vertex 257.055 30.1668 336.565 + vertex 269.214 32.86 338.517 + endloop + endfacet + facet normal 0.11793 -0.87406 0.471287 + outer loop + vertex 269.214 32.86 338.517 + vertex 257.055 30.1668 336.565 + vertex 268.701 31.6941 336.483 + endloop + endfacet + facet normal 0.124019 -0.874047 0.469745 + outer loop + vertex 269.214 32.86 338.517 + vertex 268.701 31.6941 336.483 + vertex 281.95 34.5239 338.25 + endloop + endfacet + facet normal 0.125786 -0.877716 0.462377 + outer loop + vertex 281.95 34.5239 338.25 + vertex 268.701 31.6941 336.483 + vertex 279.657 33.0074 335.995 + endloop + endfacet + facet normal 0.126743 -0.916391 0.379688 + outer loop + vertex 268.701 31.6941 336.483 + vertex 267.775 30.7651 334.55 + vertex 279.657 33.0074 335.995 + endloop + endfacet + facet normal 0.126457 -0.915822 0.381155 + outer loop + vertex 279.657 33.0074 335.995 + vertex 267.775 30.7651 334.55 + vertex 276.149 31.7802 334.21 + endloop + endfacet + facet normal 0.113042 -0.924909 0.362993 + outer loop + vertex 235.015 27.3815 336.496 + vertex 234.946 26.6264 334.593 + vertex 245.778 28.707 336.521 + endloop + endfacet + facet normal 0.112379 -0.923936 0.365669 + outer loop + vertex 245.778 28.707 336.521 + vertex 234.946 26.6264 334.593 + vertex 245.815 27.9641 334.633 + endloop + endfacet + facet normal 0.108302 -0.88179 0.45904 + outer loop + vertex 235.132 28.4095 338.443 + vertex 235.015 27.3815 336.496 + vertex 245.791 29.7204 338.446 + endloop + endfacet + facet normal 0.107282 -0.880055 0.462596 + outer loop + vertex 245.791 29.7204 338.446 + vertex 235.015 27.3815 336.496 + vertex 245.778 28.707 336.521 + endloop + endfacet + facet normal 0.114016 -0.87941 0.462211 + outer loop + vertex 245.791 29.7204 338.446 + vertex 245.778 28.707 336.521 + vertex 257.097 31.2186 338.508 + endloop + endfacet + facet normal 0.111461 -0.874975 0.471163 + outer loop + vertex 257.097 31.2186 338.508 + vertex 245.778 28.707 336.521 + vertex 257.055 30.1668 336.565 + endloop + endfacet + facet normal 0.11812 -0.923277 0.365522 + outer loop + vertex 245.778 28.707 336.521 + vertex 245.815 27.9641 334.633 + vertex 257.055 30.1668 336.565 + endloop + endfacet + facet normal 0.117006 -0.921599 0.370087 + outer loop + vertex 257.055 30.1668 336.565 + vertex 245.815 27.9641 334.633 + vertex 256.972 29.3908 334.658 + endloop + endfacet + facet normal 0.10393 -0.928301 0.357009 + outer loop + vertex 213.866 24.9777 336.525 + vertex 213.716 24.2193 334.597 + vertex 224.468 26.1582 336.508 + endloop + endfacet + facet normal 0.10332 -0.927399 0.359522 + outer loop + vertex 224.468 26.1582 336.508 + vertex 213.716 24.2193 334.597 + vertex 224.328 25.3976 334.587 + endloop + endfacet + facet normal 0.10066 -0.88615 0.452334 + outer loop + vertex 213.98 25.9959 338.495 + vertex 213.866 24.9777 336.525 + vertex 224.603 27.1924 338.475 + endloop + endfacet + facet normal 0.0990992 -0.88347 0.457887 + outer loop + vertex 224.603 27.1924 338.475 + vertex 213.866 24.9777 336.525 + vertex 224.468 26.1582 336.508 + endloop + endfacet + facet normal 0.103476 -0.883197 0.457445 + outer loop + vertex 224.603 27.1924 338.475 + vertex 224.468 26.1582 336.508 + vertex 235.132 28.4095 338.443 + endloop + endfacet + facet normal 0.102873 -0.882166 0.459565 + outer loop + vertex 235.132 28.4095 338.443 + vertex 224.468 26.1582 336.508 + vertex 235.015 27.3815 336.496 + endloop + endfacet + facet normal 0.10796 -0.927054 0.359047 + outer loop + vertex 224.468 26.1582 336.508 + vertex 224.328 25.3976 334.587 + vertex 235.015 27.3815 336.496 + endloop + endfacet + facet normal 0.106881 -0.925467 0.363438 + outer loop + vertex 235.015 27.3815 336.496 + vertex 224.328 25.3976 334.587 + vertex 234.946 26.6264 334.593 + endloop + endfacet + facet normal 0.0967174 -0.931949 0.349453 + outer loop + vertex 192.498 22.7094 336.518 + vertex 192.357 21.9728 334.593 + vertex 203.177 23.8211 336.527 + endloop + endfacet + facet normal 0.0957402 -0.930507 0.353541 + outer loop + vertex 203.177 23.8211 336.527 + vertex 192.357 21.9728 334.593 + vertex 203.04 23.0748 334.6 + endloop + endfacet + facet normal 0.0926575 -0.888654 0.449119 + outer loop + vertex 192.62 23.7174 338.487 + vertex 192.498 22.7094 336.518 + vertex 203.275 24.8331 338.497 + endloop + endfacet + facet normal 0.0920059 -0.887533 0.451464 + outer loop + vertex 203.275 24.8331 338.497 + vertex 192.498 22.7094 336.518 + vertex 203.177 23.8211 336.527 + endloop + endfacet + facet normal 0.0964589 -0.887247 0.451096 + outer loop + vertex 203.275 24.8331 338.497 + vertex 203.177 23.8211 336.527 + vertex 213.98 25.9959 338.495 + endloop + endfacet + facet normal 0.0959956 -0.886451 0.452759 + outer loop + vertex 213.98 25.9959 338.495 + vertex 203.177 23.8211 336.527 + vertex 213.866 24.9777 336.525 + endloop + endfacet + facet normal 0.100709 -0.930166 0.353057 + outer loop + vertex 203.177 23.8211 336.527 + vertex 203.04 23.0748 334.6 + vertex 213.866 24.9777 336.525 + endloop + endfacet + facet normal 0.0996504 -0.928597 0.357459 + outer loop + vertex 213.866 24.9777 336.525 + vertex 203.04 23.0748 334.6 + vertex 213.716 24.2193 334.597 + endloop + endfacet + facet normal 0.0868141 -0.934769 0.344485 + outer loop + vertex 171.311 20.6769 336.501 + vertex 171.154 19.9519 334.573 + vertex 181.892 21.662 336.507 + endloop + endfacet + facet normal 0.086456 -0.934241 0.346006 + outer loop + vertex 181.892 21.662 336.507 + vertex 171.154 19.9519 334.573 + vertex 181.739 20.9348 334.582 + endloop + endfacet + facet normal 0.0832902 -0.890441 0.447413 + outer loop + vertex 171.458 21.6818 338.473 + vertex 171.311 20.6769 336.501 + vertex 182.023 22.6735 338.48 + endloop + endfacet + facet normal 0.0824873 -0.889038 0.450342 + outer loop + vertex 182.023 22.6735 338.48 + vertex 171.311 20.6769 336.501 + vertex 181.892 21.662 336.507 + endloop + endfacet + facet normal 0.0872567 -0.888804 0.449905 + outer loop + vertex 182.023 22.6735 338.48 + vertex 181.892 21.662 336.507 + vertex 192.62 23.7174 338.487 + endloop + endfacet + facet normal 0.087341 -0.88895 0.4496 + outer loop + vertex 192.62 23.7174 338.487 + vertex 181.892 21.662 336.507 + vertex 192.498 22.7094 336.518 + endloop + endfacet + facet normal 0.0918837 -0.933925 0.345458 + outer loop + vertex 181.892 21.662 336.507 + vertex 181.739 20.9348 334.582 + vertex 192.498 22.7094 336.518 + endloop + endfacet + facet normal 0.0907967 -0.932327 0.350033 + outer loop + vertex 192.498 22.7094 336.518 + vertex 181.739 20.9348 334.582 + vertex 192.357 21.9728 334.593 + endloop + endfacet + facet normal 0.0771174 -0.936111 0.343145 + outer loop + vertex 150.015 18.8634 336.489 + vertex 149.855 18.1429 334.559 + vertex 160.699 19.7457 336.495 + endloop + endfacet + facet normal 0.0765211 -0.935206 0.345737 + outer loop + vertex 160.699 19.7457 336.495 + vertex 149.855 18.1429 334.559 + vertex 160.536 19.0195 334.566 + endloop + endfacet + facet normal 0.0736363 -0.892382 0.445232 + outer loop + vertex 150.172 19.8611 338.463 + vertex 150.015 18.8634 336.489 + vertex 160.854 20.745 338.468 + endloop + endfacet + facet normal 0.0734164 -0.891986 0.446061 + outer loop + vertex 160.854 20.745 338.468 + vertex 150.015 18.8634 336.489 + vertex 160.699 19.7457 336.495 + endloop + endfacet + facet normal 0.0785437 -0.891798 0.445564 + outer loop + vertex 160.854 20.745 338.468 + vertex 160.699 19.7457 336.495 + vertex 171.458 21.6818 338.473 + endloop + endfacet + facet normal 0.0779054 -0.890668 0.44793 + outer loop + vertex 171.458 21.6818 338.473 + vertex 160.699 19.7457 336.495 + vertex 171.311 20.6769 336.501 + endloop + endfacet + facet normal 0.0818485 -0.934956 0.345192 + outer loop + vertex 160.699 19.7457 336.495 + vertex 160.536 19.0195 334.566 + vertex 171.311 20.6769 336.501 + endloop + endfacet + facet normal 0.0818969 -0.935029 0.344985 + outer loop + vertex 171.311 20.6769 336.501 + vertex 160.536 19.0195 334.566 + vertex 171.154 19.9519 334.573 + endloop + endfacet + facet normal 0.0664148 -0.936795 0.343518 + outer loop + vertex 128.431 17.2708 336.479 + vertex 128.285 16.5518 334.547 + vertex 139.252 18.0397 336.484 + endloop + endfacet + facet normal 0.0664326 -0.936823 0.343439 + outer loop + vertex 139.252 18.0397 336.484 + vertex 128.285 16.5518 334.547 + vertex 139.1 17.3208 334.552 + endloop + endfacet + facet normal 0.0629998 -0.892377 0.446872 + outer loop + vertex 128.562 18.27 338.456 + vertex 128.431 17.2708 336.479 + vertex 139.399 19.0368 338.459 + endloop + endfacet + facet normal 0.0632451 -0.892835 0.445921 + outer loop + vertex 139.399 19.0368 338.459 + vertex 128.431 17.2708 336.479 + vertex 139.252 18.0397 336.484 + endloop + endfacet + facet normal 0.0681777 -0.892692 0.44548 + outer loop + vertex 139.399 19.0368 338.459 + vertex 139.252 18.0397 336.484 + vertex 150.172 19.8611 338.463 + endloop + endfacet + facet normal 0.0681044 -0.892557 0.445761 + outer loop + vertex 150.172 19.8611 338.463 + vertex 139.252 18.0397 336.484 + vertex 150.015 18.8634 336.489 + endloop + endfacet + facet normal 0.0715225 -0.936621 0.342965 + outer loop + vertex 139.252 18.0397 336.484 + vertex 139.1 17.3208 334.552 + vertex 150.015 18.8634 336.489 + endloop + endfacet + facet normal 0.0713522 -0.936359 0.343716 + outer loop + vertex 150.015 18.8634 336.489 + vertex 139.1 17.3208 334.552 + vertex 149.855 18.1429 334.559 + endloop + endfacet + facet normal 0.0552513 -0.936503 0.346279 + outer loop + vertex 106.78 15.9331 336.472 + vertex 106.664 15.2111 334.538 + vertex 117.59 16.572 336.475 + endloop + endfacet + facet normal 0.0551512 -0.936342 0.34673 + outer loop + vertex 117.59 16.572 336.475 + vertex 106.664 15.2111 334.538 + vertex 117.458 15.8481 334.542 + endloop + endfacet + facet normal 0.0523439 -0.893218 0.446567 + outer loop + vertex 106.872 16.9274 338.45 + vertex 106.78 15.9331 336.472 + vertex 117.698 17.5627 338.452 + endloop + endfacet + facet normal 0.0527071 -0.893911 0.445134 + outer loop + vertex 117.698 17.5627 338.452 + vertex 106.78 15.9331 336.472 + vertex 117.59 16.572 336.475 + endloop + endfacet + facet normal 0.0580249 -0.893763 0.444771 + outer loop + vertex 117.698 17.5627 338.452 + vertex 117.59 16.572 336.475 + vertex 128.562 18.27 338.456 + endloop + endfacet + facet normal 0.0573738 -0.892531 0.447322 + outer loop + vertex 128.562 18.27 338.456 + vertex 117.59 16.572 336.475 + vertex 128.431 17.2708 336.479 + endloop + endfacet + facet normal 0.0602239 -0.936181 0.346322 + outer loop + vertex 117.59 16.572 336.475 + vertex 117.458 15.8481 334.542 + vertex 128.431 17.2708 336.479 + endloop + endfacet + facet normal 0.0607357 -0.936995 0.344022 + outer loop + vertex 128.431 17.2708 336.479 + vertex 117.458 15.8481 334.542 + vertex 128.285 16.5518 334.547 + endloop + endfacet + facet normal 0.043225 -0.93624 0.348691 + outer loop + vertex 85.4706 14.8793 336.471 + vertex 85.3654 14.1538 334.536 + vertex 96.0767 15.3688 336.471 + endloop + endfacet + facet normal 0.0439779 -0.937465 0.345291 + outer loop + vertex 96.0767 15.3688 336.471 + vertex 85.3654 14.1538 334.536 + vertex 95.9707 14.6513 334.536 + endloop + endfacet + facet normal 0.0414352 -0.893616 0.446915 + outer loop + vertex 85.5552 15.8729 338.45 + vertex 85.4706 14.8793 336.471 + vertex 96.1647 16.3646 338.45 + endloop + endfacet + facet normal 0.0412444 -0.893247 0.44767 + outer loop + vertex 96.1647 16.3646 338.45 + vertex 85.4706 14.8793 336.471 + vertex 96.0767 15.3688 336.471 + endloop + endfacet + facet normal 0.0469088 -0.893125 0.447357 + outer loop + vertex 96.1647 16.3646 338.45 + vertex 96.0767 15.3688 336.471 + vertex 106.872 16.9274 338.45 + endloop + endfacet + facet normal 0.0470295 -0.893356 0.446881 + outer loop + vertex 106.872 16.9274 338.45 + vertex 96.0767 15.3688 336.471 + vertex 106.78 15.9331 336.472 + endloop + endfacet + facet normal 0.0493632 -0.937324 0.344944 + outer loop + vertex 96.0767 15.3688 336.471 + vertex 95.9707 14.6513 334.536 + vertex 106.78 15.9331 336.472 + endloop + endfacet + facet normal 0.0489687 -0.936688 0.346725 + outer loop + vertex 106.78 15.9331 336.472 + vertex 95.9707 14.6513 334.536 + vertex 106.664 15.2111 334.538 + endloop + endfacet + facet normal 0.0316668 -0.937174 0.347422 + outer loop + vertex 64.1435 14.0858 336.474 + vertex 64.0888 13.367 334.54 + vertex 74.8628 14.4471 336.472 + endloop + endfacet + facet normal 0.0319138 -0.93759 0.346276 + outer loop + vertex 74.8628 14.4471 336.472 + vertex 64.0888 13.367 334.54 + vertex 74.7782 13.7299 334.537 + endloop + endfacet + facet normal 0.0302405 -0.893352 0.448338 + outer loop + vertex 64.1856 15.0799 338.452 + vertex 64.1435 14.0858 336.474 + vertex 74.9366 15.4426 338.45 + endloop + endfacet + facet normal 0.0302122 -0.893295 0.448454 + outer loop + vertex 74.9366 15.4426 338.45 + vertex 64.1435 14.0858 336.474 + vertex 74.8628 14.4471 336.472 + endloop + endfacet + facet normal 0.0361824 -0.893207 0.448187 + outer loop + vertex 74.9366 15.4426 338.45 + vertex 74.8628 14.4471 336.472 + vertex 85.5552 15.8729 338.45 + endloop + endfacet + facet normal 0.0364363 -0.893705 0.447174 + outer loop + vertex 85.5552 15.8729 338.45 + vertex 74.8628 14.4471 336.472 + vertex 85.4706 14.8793 336.471 + endloop + endfacet + facet normal 0.0382143 -0.937472 0.345957 + outer loop + vertex 74.8628 14.4471 336.472 + vertex 74.7782 13.7299 334.537 + vertex 85.4706 14.8793 336.471 + endloop + endfacet + facet normal 0.037536 -0.936354 0.349043 + outer loop + vertex 85.4706 14.8793 336.471 + vertex 74.7782 13.7299 334.537 + vertex 85.3654 14.1538 334.536 + endloop + endfacet + facet normal 0.0216981 -0.937485 0.347349 + outer loop + vertex 42.4971 13.5262 336.479 + vertex 42.4705 12.8094 334.547 + vertex 53.3159 13.7754 336.476 + endloop + endfacet + facet normal 0.0213435 -0.936868 0.349033 + outer loop + vertex 53.3159 13.7754 336.476 + vertex 42.4705 12.8094 334.547 + vertex 53.2769 13.0544 334.543 + endloop + endfacet + facet normal 0.0206944 -0.893624 0.44834 + outer loop + vertex 42.5275 14.5179 338.455 + vertex 42.4971 13.5262 336.479 + vertex 53.3477 14.7675 338.453 + endloop + endfacet + facet normal 0.0207178 -0.893672 0.448242 + outer loop + vertex 53.3477 14.7675 338.453 + vertex 42.4971 13.5262 336.479 + vertex 53.3159 13.7754 336.476 + endloop + endfacet + facet normal 0.0257835 -0.893599 0.448124 + outer loop + vertex 53.3477 14.7675 338.453 + vertex 53.3159 13.7754 336.476 + vertex 64.1856 15.0799 338.452 + endloop + endfacet + facet normal 0.0256994 -0.893427 0.448473 + outer loop + vertex 64.1856 15.0799 338.452 + vertex 53.3159 13.7754 336.476 + vertex 64.1435 14.0858 336.474 + endloop + endfacet + facet normal 0.0269231 -0.936778 0.348887 + outer loop + vertex 53.3159 13.7754 336.476 + vertex 53.2769 13.0544 334.543 + vertex 64.1435 14.0858 336.474 + endloop + endfacet + facet normal 0.027201 -0.937256 0.347579 + outer loop + vertex 64.1435 14.0858 336.474 + vertex 53.2769 13.0544 334.543 + vertex 64.0888 13.367 334.54 + endloop + endfacet + facet normal 0.0116821 -0.936997 0.349143 + outer loop + vertex 21.2411 13.2024 336.484 + vertex 21.225 12.4829 334.553 + vertex 31.8045 13.3334 336.482 + endloop + endfacet + facet normal 0.0119387 -0.937444 0.347932 + outer loop + vertex 31.8045 13.3334 336.482 + vertex 21.225 12.4829 334.553 + vertex 31.7742 12.6162 334.55 + endloop + endfacet + facet normal 0.0108011 -0.891824 0.452253 + outer loop + vertex 21.2432 14.2047 338.46 + vertex 21.2411 13.2024 336.484 + vertex 31.8304 14.3317 338.457 + endloop + endfacet + facet normal 0.0111496 -0.892555 0.450801 + outer loop + vertex 31.8304 14.3317 338.457 + vertex 21.2411 13.2024 336.484 + vertex 31.8045 13.3334 336.482 + endloop + endfacet + facet normal 0.0156553 -0.892525 0.450727 + outer loop + vertex 31.8304 14.3317 338.457 + vertex 31.8045 13.3334 336.482 + vertex 42.5275 14.5179 338.455 + endloop + endfacet + facet normal 0.016204 -0.89367 0.448432 + outer loop + vertex 42.5275 14.5179 338.455 + vertex 31.8045 13.3334 336.482 + vertex 42.4971 13.5262 336.479 + endloop + endfacet + facet normal 0.0169707 -0.937401 0.347838 + outer loop + vertex 31.8045 13.3334 336.482 + vertex 31.7742 12.6162 334.55 + vertex 42.4971 13.5262 336.479 + endloop + endfacet + facet normal 0.0170555 -0.937549 0.347436 + outer loop + vertex 42.4971 13.5262 336.479 + vertex 31.7742 12.6162 334.55 + vertex 42.4705 12.8094 334.547 + endloop + endfacet + facet normal 0.00212816 -0.936603 0.350385 + outer loop + vertex 0.149844 13.1044 336.486 + vertex 0.207159 12.3823 334.556 + vertex 10.7079 13.1281 336.485 + endloop + endfacet + facet normal 0.00239333 -0.937074 0.349124 + outer loop + vertex 10.7079 13.1281 336.485 + vertex 0.207159 12.3823 334.556 + vertex 10.7361 12.4089 334.555 + endloop + endfacet + facet normal 0.0018606 -0.892204 0.451628 + outer loop + vertex 0.0991727 14.1041 338.461 + vertex 0.149844 13.1044 336.486 + vertex 10.6834 14.1255 338.46 + endloop + endfacet + facet normal 0.00203454 -0.892576 0.450892 + outer loop + vertex 10.6834 14.1255 338.46 + vertex 0.149844 13.1044 336.486 + vertex 10.7079 13.1281 336.485 + endloop + endfacet + facet normal 0.00669453 -0.892535 0.450929 + outer loop + vertex 10.6834 14.1255 338.46 + vertex 10.7079 13.1281 336.485 + vertex 21.2432 14.2047 338.46 + endloop + endfacet + facet normal 0.00637316 -0.891856 0.452274 + outer loop + vertex 21.2432 14.2047 338.46 + vertex 10.7079 13.1281 336.485 + vertex 21.2411 13.2024 336.484 + endloop + endfacet + facet normal 0.00667336 -0.937035 0.349172 + outer loop + vertex 10.7079 13.1281 336.485 + vertex 10.7361 12.4089 334.555 + vertex 21.2411 13.2024 336.484 + endloop + endfacet + facet normal 0.00666835 -0.937026 0.349195 + outer loop + vertex 21.2411 13.2024 336.484 + vertex 10.7361 12.4089 334.555 + vertex 21.225 12.4829 334.553 + endloop + endfacet + facet normal -0.00645669 -0.937039 0.349166 + outer loop + vertex -20.9529 13.1985 336.483 + vertex -20.8922 12.4788 334.553 + vertex -10.4098 13.1264 336.485 + endloop + endfacet + facet normal -0.00624643 -0.937417 0.348152 + outer loop + vertex -10.4098 13.1264 336.485 + vertex -20.8922 12.4788 334.553 + vertex -10.3403 12.409 334.554 + endloop + endfacet + facet normal -0.00667758 -0.891526 0.452921 + outer loop + vertex -20.9974 14.203 338.46 + vertex -20.9529 13.1985 336.483 + vertex -10.4609 14.124 338.46 + endloop + endfacet + facet normal -0.00616681 -0.892639 0.450731 + outer loop + vertex -10.4609 14.124 338.46 + vertex -20.9529 13.1985 336.483 + vertex -10.4098 13.1264 336.485 + endloop + endfacet + facet normal -0.00174843 -0.892608 0.45083 + outer loop + vertex -10.4609 14.124 338.46 + vertex -10.4098 13.1264 336.485 + vertex 0.0991727 14.1041 338.461 + endloop + endfacet + facet normal -0.00191792 -0.892243 0.451551 + outer loop + vertex 0.0991727 14.1041 338.461 + vertex -10.4098 13.1264 336.485 + vertex 0.149844 13.1044 336.486 + endloop + endfacet + facet normal -0.00199818 -0.937384 0.348292 + outer loop + vertex -10.4098 13.1264 336.485 + vertex -10.3403 12.409 334.554 + vertex 0.149844 13.1044 336.486 + endloop + endfacet + facet normal -0.00241049 -0.936647 0.350266 + outer loop + vertex 0.149844 13.1044 336.486 + vertex -10.3403 12.409 334.554 + vertex 0.207159 12.3823 334.556 + endloop + endfacet + facet normal -0.0168213 -0.936982 0.348974 + outer loop + vertex -42.2255 13.522 336.479 + vertex -42.1344 12.8007 334.547 + vertex -31.5223 13.3306 336.481 + endloop + endfacet + facet normal -0.016893 -0.936847 0.34933 + outer loop + vertex -31.5223 13.3306 336.481 + vertex -42.1344 12.8007 334.547 + vertex -31.456 12.6093 334.55 + endloop + endfacet + facet normal -0.0157285 -0.8934 0.448986 + outer loop + vertex -42.2941 14.5162 338.455 + vertex -42.2255 13.522 336.479 + vertex -31.5707 14.3286 338.457 + endloop + endfacet + facet normal -0.0160471 -0.892679 0.450408 + outer loop + vertex -31.5707 14.3286 338.457 + vertex -42.2255 13.522 336.479 + vertex -31.5223 13.3306 336.481 + endloop + endfacet + facet normal -0.0107084 -0.89269 0.450545 + outer loop + vertex -31.5707 14.3286 338.457 + vertex -31.5223 13.3306 336.481 + vertex -20.9974 14.203 338.46 + endloop + endfacet + facet normal -0.0112325 -0.891531 0.452821 + outer loop + vertex -20.9974 14.203 338.46 + vertex -31.5223 13.3306 336.481 + vertex -20.9529 13.1985 336.483 + endloop + endfacet + facet normal -0.0117791 -0.936859 0.34951 + outer loop + vertex -31.5223 13.3306 336.481 + vertex -31.456 12.6093 334.55 + vertex -20.9529 13.1985 336.483 + endloop + endfacet + facet normal -0.0116756 -0.937048 0.349005 + outer loop + vertex -20.9529 13.1985 336.483 + vertex -31.456 12.6093 334.55 + vertex -20.8922 12.4788 334.553 + endloop + endfacet + facet normal -0.0267116 -0.937418 0.34718 + outer loop + vertex -63.9898 14.0788 336.474 + vertex -63.8628 13.3593 334.54 + vertex -53.0832 13.769 336.476 + endloop + endfacet + facet normal -0.02681 -0.937227 0.347688 + outer loop + vertex -53.0832 13.769 336.476 + vertex -63.8628 13.3593 334.54 + vertex -52.9673 13.0487 334.543 + endloop + endfacet + facet normal -0.0251098 -0.89297 0.449415 + outer loop + vertex -64.1062 15.0773 338.451 + vertex -63.9898 14.0788 336.474 + vertex -53.1863 14.7718 338.454 + endloop + endfacet + facet normal -0.0254514 -0.892163 0.450996 + outer loop + vertex -53.1863 14.7718 338.454 + vertex -63.9898 14.0788 336.474 + vertex -53.0832 13.769 336.476 + endloop + endfacet + facet normal -0.0209731 -0.892162 0.451229 + outer loop + vertex -53.1863 14.7718 338.454 + vertex -53.0832 13.769 336.476 + vertex -42.2941 14.5162 338.455 + endloop + endfacet + facet normal -0.0204458 -0.89339 0.448817 + outer loop + vertex -42.2941 14.5162 338.455 + vertex -53.0832 13.769 336.476 + vertex -42.2255 13.522 336.479 + endloop + endfacet + facet normal -0.0214152 -0.937243 0.348017 + outer loop + vertex -53.0832 13.769 336.476 + vertex -52.9673 13.0487 334.543 + vertex -42.2255 13.522 336.479 + endloop + endfacet + facet normal -0.0215586 -0.936969 0.348746 + outer loop + vertex -42.2255 13.522 336.479 + vertex -52.9673 13.0487 334.543 + vertex -42.1344 12.8007 334.547 + endloop + endfacet + facet normal -0.0371889 -0.937507 0.345973 + outer loop + vertex -85.3645 14.8689 336.471 + vertex -85.2353 14.15 334.537 + vertex -74.7731 14.4491 336.472 + endloop + endfacet + facet normal -0.0370938 -0.93769 0.345487 + outer loop + vertex -74.7731 14.4491 336.472 + vertex -85.2353 14.15 334.537 + vertex -74.6375 13.7311 334.537 + endloop + endfacet + facet normal -0.0350497 -0.893837 0.447021 + outer loop + vertex -85.4748 15.8621 338.448 + vertex -85.3645 14.8689 336.471 + vertex -74.8943 15.4486 338.451 + endloop + endfacet + facet normal -0.0354336 -0.892936 0.448787 + outer loop + vertex -74.8943 15.4486 338.451 + vertex -85.3645 14.8689 336.471 + vertex -74.7731 14.4491 336.472 + endloop + endfacet + facet normal -0.0307447 -0.89296 0.449086 + outer loop + vertex -74.8943 15.4486 338.451 + vertex -74.7731 14.4491 336.472 + vertex -64.1062 15.0773 338.451 + endloop + endfacet + facet normal -0.0307433 -0.892963 0.449079 + outer loop + vertex -64.1062 15.0773 338.451 + vertex -74.7731 14.4491 336.472 + vertex -63.9898 14.0788 336.474 + endloop + endfacet + facet normal -0.0322638 -0.937737 0.345843 + outer loop + vertex -74.7731 14.4491 336.472 + vertex -74.6375 13.7311 334.537 + vertex -63.9898 14.0788 336.474 + endloop + endfacet + facet normal -0.0324475 -0.937381 0.34679 + outer loop + vertex -63.9898 14.0788 336.474 + vertex -74.6375 13.7311 334.537 + vertex -63.8628 13.3593 334.54 + endloop + endfacet + facet normal -0.0494839 -0.937555 0.3443 + outer loop + vertex -106.362 15.9125 336.473 + vertex -106.171 15.1918 334.538 + vertex -95.8402 15.3565 336.471 + endloop + endfacet + facet normal -0.0495197 -0.937485 0.344486 + outer loop + vertex -95.8402 15.3565 336.471 + vertex -106.171 15.1918 334.538 + vertex -95.6855 14.6374 334.537 + endloop + endfacet + facet normal -0.0467228 -0.894302 0.445018 + outer loop + vertex -106.519 16.9043 338.45 + vertex -106.362 15.9125 336.473 + vertex -95.973 16.3533 338.45 + endloop + endfacet + facet normal -0.0471309 -0.89332 0.446943 + outer loop + vertex -95.973 16.3533 338.45 + vertex -106.362 15.9125 336.473 + vertex -95.8402 15.3565 336.471 + endloop + endfacet + facet normal -0.0417239 -0.893389 0.447341 + outer loop + vertex -95.973 16.3533 338.45 + vertex -95.8402 15.3565 336.471 + vertex -85.4748 15.8621 338.448 + endloop + endfacet + facet normal -0.0415679 -0.893759 0.446618 + outer loop + vertex -85.4748 15.8621 338.448 + vertex -95.8402 15.3565 336.471 + vertex -85.3645 14.8689 336.471 + endloop + endfacet + facet normal -0.0436169 -0.93759 0.344997 + outer loop + vertex -95.8402 15.3565 336.471 + vertex -95.6855 14.6374 334.537 + vertex -85.3645 14.8689 336.471 + endloop + endfacet + facet normal -0.0437149 -0.937401 0.345497 + outer loop + vertex -85.3645 14.8689 336.471 + vertex -95.6855 14.6374 334.537 + vertex -85.2353 14.15 334.537 + endloop + endfacet + facet normal -0.0599994 -0.937763 0.342054 + outer loop + vertex -127.719 17.2222 336.479 + vertex -127.489 16.5027 334.547 + vertex -117.011 16.5359 336.476 + endloop + endfacet + facet normal -0.0606114 -0.936512 0.345358 + outer loop + vertex -117.011 16.5359 336.476 + vertex -127.489 16.5027 334.547 + vertex -116.797 15.8089 334.542 + endloop + endfacet + facet normal -0.0569577 -0.893344 0.44575 + outer loop + vertex -127.896 18.2193 338.455 + vertex -127.719 17.2222 336.479 + vertex -117.197 17.5365 338.454 + endloop + endfacet + facet normal -0.0570967 -0.892993 0.446435 + outer loop + vertex -117.197 17.5365 338.454 + vertex -127.719 17.2222 336.479 + vertex -117.011 16.5359 336.476 + endloop + endfacet + facet normal -0.0527194 -0.893043 0.446872 + outer loop + vertex -117.197 17.5365 338.454 + vertex -117.011 16.5359 336.476 + vertex -106.519 16.9043 338.45 + endloop + endfacet + facet normal -0.05224 -0.894232 0.444546 + outer loop + vertex -106.519 16.9043 338.45 + vertex -117.011 16.5359 336.476 + vertex -106.362 15.9125 336.473 + endloop + endfacet + facet normal -0.0547464 -0.936619 0.346046 + outer loop + vertex -117.011 16.5359 336.476 + vertex -116.797 15.8089 334.542 + vertex -106.362 15.9125 336.473 + endloop + endfacet + facet normal -0.0543205 -0.937474 0.343791 + outer loop + vertex -106.362 15.9125 336.473 + vertex -116.797 15.8089 334.542 + vertex -106.171 15.1918 334.538 + endloop + endfacet + facet normal -0.0707607 -0.936707 0.342888 + outer loop + vertex -148.911 18.771 336.489 + vertex -148.697 18.0486 334.56 + vertex -138.365 17.9728 336.485 + endloop + endfacet + facet normal -0.0709685 -0.936277 0.34402 + outer loop + vertex -138.365 17.9728 336.485 + vertex -148.697 18.0486 334.56 + vertex -138.15 17.2468 334.553 + endloop + endfacet + facet normal -0.0672876 -0.892459 0.446082 + outer loop + vertex -149.068 19.7693 338.463 + vertex -148.911 18.771 336.489 + vertex -138.536 18.9741 338.46 + endloop + endfacet + facet normal -0.0673548 -0.892286 0.446418 + outer loop + vertex -138.536 18.9741 338.46 + vertex -148.911 18.771 336.489 + vertex -138.365 17.9728 336.485 + endloop + endfacet + facet normal -0.0630727 -0.892388 0.446839 + outer loop + vertex -138.536 18.9741 338.46 + vertex -138.365 17.9728 336.485 + vertex -127.896 18.2193 338.455 + endloop + endfacet + facet normal -0.0627399 -0.893242 0.445178 + outer loop + vertex -127.896 18.2193 338.455 + vertex -138.365 17.9728 336.485 + vertex -127.719 17.2222 336.479 + endloop + endfacet + facet normal -0.0658365 -0.936422 0.344645 + outer loop + vertex -138.365 17.9728 336.485 + vertex -138.15 17.2468 334.553 + vertex -127.719 17.2222 336.479 + endloop + endfacet + facet normal -0.0652388 -0.937654 0.341392 + outer loop + vertex -127.719 17.2222 336.479 + vertex -138.15 17.2468 334.553 + vertex -127.489 16.5027 334.547 + endloop + endfacet + facet normal -0.081646 -0.934205 0.347268 + outer loop + vertex -170.118 20.5716 336.501 + vertex -169.867 19.8332 334.573 + vertex -159.457 19.6377 336.495 + endloop + endfacet + facet normal -0.0809068 -0.935808 0.343101 + outer loop + vertex -159.457 19.6377 336.495 + vertex -169.867 19.8332 334.573 + vertex -159.224 18.9105 334.566 + endloop + endfacet + facet normal -0.0781422 -0.890595 0.448035 + outer loop + vertex -170.315 21.581 338.473 + vertex -170.118 20.5716 336.501 + vertex -159.633 20.6414 338.468 + endloop + endfacet + facet normal -0.0778438 -0.891405 0.446473 + outer loop + vertex -159.633 20.6414 338.468 + vertex -170.118 20.5716 336.501 + vertex -159.457 19.6377 336.495 + endloop + endfacet + facet normal -0.0733577 -0.891548 0.446947 + outer loop + vertex -159.633 20.6414 338.468 + vertex -159.457 19.6377 336.495 + vertex -149.068 19.7693 338.463 + endloop + endfacet + facet normal -0.0730801 -0.892279 0.44553 + outer loop + vertex -149.068 19.7693 338.463 + vertex -159.457 19.6377 336.495 + vertex -148.911 18.771 336.489 + endloop + endfacet + facet normal -0.0767274 -0.935954 0.34366 + outer loop + vertex -159.457 19.6377 336.495 + vertex -159.224 18.9105 334.566 + vertex -148.911 18.771 336.489 + endloop + endfacet + facet normal -0.07646 -0.936516 0.342185 + outer loop + vertex -148.911 18.771 336.489 + vertex -159.224 18.9105 334.566 + vertex -148.697 18.0486 334.56 + endloop + endfacet + facet normal -0.0909215 -0.933527 0.346785 + outer loop + vertex -191.727 22.6226 336.509 + vertex -191.477 21.8834 334.585 + vertex -180.902 21.5667 336.505 + endloop + endfacet + facet normal -0.0906004 -0.934258 0.344896 + outer loop + vertex -180.902 21.5667 336.505 + vertex -191.477 21.8834 334.585 + vertex -180.642 20.8309 334.58 + endloop + endfacet + facet normal -0.0867581 -0.888851 0.449907 + outer loop + vertex -191.915 23.6375 338.478 + vertex -191.727 22.6226 336.509 + vertex -181.105 22.5812 338.476 + endloop + endfacet + facet normal -0.0865767 -0.88937 0.448916 + outer loop + vertex -181.105 22.5812 338.476 + vertex -191.727 22.6226 336.509 + vertex -180.902 21.5667 336.505 + endloop + endfacet + facet normal -0.0823409 -0.889514 0.449427 + outer loop + vertex -181.105 22.5812 338.476 + vertex -180.902 21.5667 336.505 + vertex -170.315 21.581 338.473 + endloop + endfacet + facet normal -0.0819975 -0.890473 0.447587 + outer loop + vertex -170.315 21.581 338.473 + vertex -180.902 21.5667 336.505 + vertex -170.118 20.5716 336.501 + endloop + endfacet + facet normal -0.0860938 -0.934435 0.34557 + outer loop + vertex -180.902 21.5667 336.505 + vertex -180.642 20.8309 334.58 + vertex -170.118 20.5716 336.501 + endloop + endfacet + facet normal -0.0862722 -0.934037 0.346602 + outer loop + vertex -170.118 20.5716 336.501 + vertex -180.642 20.8309 334.58 + vertex -169.867 19.8332 334.573 + endloop + endfacet + facet normal -0.100162 -0.929128 0.355933 + outer loop + vertex -213.248 24.8903 336.52 + vertex -213.042 24.1306 334.594 + vertex -202.509 23.7302 336.513 + endloop + endfacet + facet normal -0.0991974 -0.931423 0.350157 + outer loop + vertex -202.509 23.7302 336.513 + vertex -213.042 24.1306 334.594 + vertex -202.282 22.9827 334.589 + endloop + endfacet + facet normal -0.0960594 -0.884741 0.456077 + outer loop + vertex -213.422 25.9258 338.492 + vertex -213.248 24.8903 336.52 + vertex -202.693 24.7572 338.484 + endloop + endfacet + facet normal -0.0954932 -0.886422 0.452921 + outer loop + vertex -202.693 24.7572 338.484 + vertex -213.248 24.8903 336.52 + vertex -202.509 23.7302 336.513 + endloop + endfacet + facet normal -0.0918301 -0.886589 0.453351 + outer loop + vertex -202.693 24.7572 338.484 + vertex -202.509 23.7302 336.513 + vertex -191.915 23.6375 338.478 + endloop + endfacet + facet normal -0.0911155 -0.888672 0.449399 + outer loop + vertex -191.915 23.6375 338.478 + vertex -202.509 23.7302 336.513 + vertex -191.727 22.6226 336.509 + endloop + endfacet + facet normal -0.0955664 -0.931615 0.350658 + outer loop + vertex -202.509 23.7302 336.513 + vertex -202.282 22.9827 334.589 + vertex -191.727 22.6226 336.509 + endloop + endfacet + facet normal -0.0948167 -0.933353 0.34621 + outer loop + vertex -191.727 22.6226 336.509 + vertex -202.282 22.9827 334.589 + vertex -191.477 21.8834 334.585 + endloop + endfacet + facet normal -0.108682 -0.925833 0.36197 + outer loop + vertex -234.773 27.3682 336.523 + vertex -234.624 26.601 334.605 + vertex -223.998 26.1046 336.526 + endloop + endfacet + facet normal -0.108148 -0.92718 0.358666 + outer loop + vertex -223.998 26.1046 336.526 + vertex -234.624 26.601 334.605 + vertex -223.81 25.3383 334.602 + endloop + endfacet + facet normal -0.104707 -0.880414 0.462501 + outer loop + vertex -234.84 28.4071 338.485 + vertex -234.773 27.3682 336.523 + vertex -224.121 27.1366 338.493 + endloop + endfacet + facet normal -0.103739 -0.883441 0.456914 + outer loop + vertex -224.121 27.1366 338.493 + vertex -234.773 27.3682 336.523 + vertex -223.998 26.1046 336.526 + endloop + endfacet + facet normal -0.0999391 -0.883689 0.457281 + outer loop + vertex -224.121 27.1366 338.493 + vertex -223.998 26.1046 336.526 + vertex -213.422 25.9258 338.492 + endloop + endfacet + facet normal -0.099653 -0.884556 0.455664 + outer loop + vertex -213.422 25.9258 338.492 + vertex -223.998 26.1046 336.526 + vertex -213.248 24.8903 336.52 + endloop + endfacet + facet normal -0.104551 -0.92742 0.359113 + outer loop + vertex -223.998 26.1046 336.526 + vertex -223.81 25.3383 334.602 + vertex -213.248 24.8903 336.52 + endloop + endfacet + facet normal -0.103947 -0.928902 0.355439 + outer loop + vertex -213.248 24.8903 336.52 + vertex -223.81 25.3383 334.602 + vertex -213.042 24.1306 334.594 + endloop + endfacet + facet normal -0.117427 -0.919825 0.374344 + outer loop + vertex -256.453 30.0682 336.495 + vertex -256.303 29.2656 334.57 + vertex -245.575 28.6835 336.505 + endloop + endfacet + facet normal -0.116353 -0.922708 0.367522 + outer loop + vertex -245.575 28.6835 336.505 + vertex -256.303 29.2656 334.57 + vertex -245.467 27.9089 334.594 + endloop + endfacet + facet normal -0.112458 -0.876167 0.468706 + outer loop + vertex -256.566 31.1437 338.478 + vertex -256.453 30.0682 336.495 + vertex -245.625 29.7345 338.469 + endloop + endfacet + facet normal -0.112105 -0.87735 0.466572 + outer loop + vertex -245.625 29.7345 338.469 + vertex -256.453 30.0682 336.495 + vertex -245.575 28.6835 336.505 + endloop + endfacet + facet normal -0.108714 -0.877646 0.466817 + outer loop + vertex -245.625 29.7345 338.469 + vertex -245.575 28.6835 336.505 + vertex -234.84 28.4071 338.485 + endloop + endfacet + facet normal -0.107937 -0.880155 0.462252 + outer loop + vertex -234.84 28.4071 338.485 + vertex -245.575 28.6835 336.505 + vertex -234.773 27.3682 336.523 + endloop + endfacet + facet normal -0.112999 -0.923001 0.367831 + outer loop + vertex -245.575 28.6835 336.505 + vertex -245.467 27.9089 334.594 + vertex -234.773 27.3682 336.523 + endloop + endfacet + facet normal -0.112007 -0.925577 0.36161 + outer loop + vertex -234.773 27.3682 336.523 + vertex -245.467 27.9089 334.594 + vertex -234.624 26.601 334.605 + endloop + endfacet + facet normal -0.128076 -0.908084 0.398723 + outer loop + vertex -278.402 33.2222 336.827 + vertex -278.085 32.2305 334.67 + vertex -267.43 31.5566 336.558 + endloop + endfacet + facet normal -0.125827 -0.914886 0.383603 + outer loop + vertex -267.43 31.5566 336.558 + vertex -278.085 32.2305 334.67 + vertex -267.176 30.6878 334.569 + endloop + endfacet + facet normal -0.121927 -0.867232 0.482744 + outer loop + vertex -277.201 34.1421 338.783 + vertex -278.402 33.2222 336.827 + vertex -267.526 32.6663 338.576 + endloop + endfacet + facet normal -0.120779 -0.872186 0.474029 + outer loop + vertex -267.526 32.6663 338.576 + vertex -278.402 33.2222 336.827 + vertex -267.43 31.5566 336.558 + endloop + endfacet + facet normal -0.116997 -0.872507 0.474387 + outer loop + vertex -267.526 32.6663 338.576 + vertex -267.43 31.5566 336.558 + vertex -256.566 31.1437 338.478 + endloop + endfacet + facet normal -0.116058 -0.875888 0.46835 + outer loop + vertex -256.566 31.1437 338.478 + vertex -267.43 31.5566 336.558 + vertex -256.453 30.0682 336.495 + endloop + endfacet + facet normal -0.121869 -0.91516 0.384227 + outer loop + vertex -267.43 31.5566 336.558 + vertex -267.176 30.6878 334.569 + vertex -256.453 30.0682 336.495 + endloop + endfacet + facet normal -0.120293 -0.919586 0.374021 + outer loop + vertex -256.453 30.0682 336.495 + vertex -267.176 30.6878 334.569 + vertex -256.303 29.2656 334.57 + endloop + endfacet + facet normal -0.131225 -0.907879 0.398166 + outer loop + vertex -278.085 32.2305 334.67 + vertex -278.402 33.2222 336.827 + vertex -289.224 33.9605 334.944 + endloop + endfacet + facet normal -0.132818 -0.888143 0.439956 + outer loop + vertex -301.154 35.8287 335.114 + vertex -289.224 33.9605 334.944 + vertex -289.973 35.4404 337.705 + endloop + endfacet + facet normal -0.128874 -0.864547 0.485747 + outer loop + vertex -277.201 34.1421 338.783 + vertex -289.973 35.4404 337.705 + vertex -278.402 33.2222 336.827 + endloop + endfacet + facet normal -0.136947 -0.888086 0.438804 + outer loop + vertex -289.224 33.9605 334.944 + vertex -278.402 33.2222 336.827 + vertex -289.973 35.4404 337.705 + endloop + endfacet + facet normal -0.13161 -0.88962 0.437326 + outer loop + vertex -312.732 37.4324 334.79 + vertex -306.619 37.9015 337.584 + vertex -319.571 39.0603 336.043 + endloop + endfacet + facet normal -0.14372 -0.907563 0.394556 + outer loop + vertex -321.337 38.5324 334.185 + vertex -312.732 37.4324 334.79 + vertex -319.571 39.0603 336.043 + endloop + endfacet + facet normal -0.134991 -0.864031 0.485003 + outer loop + vertex -318.862 40.2321 338.328 + vertex -319.571 39.0603 336.043 + vertex -306.619 37.9015 337.584 + endloop + endfacet + facet normal -0.134102 -0.884942 0.445976 + outer loop + vertex -289.973 35.4404 337.705 + vertex -306.619 37.9015 337.584 + vertex -301.154 35.8287 335.114 + endloop + endfacet + facet normal -0.135111 -0.885623 0.444316 + outer loop + vertex -301.154 35.8287 335.114 + vertex -306.619 37.9015 337.584 + vertex -312.732 37.4324 334.79 + endloop + endfacet + facet normal -0.161074 -0.898357 0.408668 + outer loop + vertex -338.754 42.589 336.456 + vertex -338.022 41.5624 334.488 + vertex -328.865 40.813 336.449 + endloop + endfacet + facet normal -0.160571 -0.899752 0.405788 + outer loop + vertex -328.865 40.813 336.449 + vertex -338.022 41.5624 334.488 + vertex -328.646 39.8771 334.461 + endloop + endfacet + facet normal -0.153493 -0.856 0.493663 + outer loop + vertex -339.507 43.8481 338.405 + vertex -338.754 42.589 336.456 + vertex -329.388 42.0846 338.493 + endloop + endfacet + facet normal -0.153443 -0.856166 0.493392 + outer loop + vertex -329.388 42.0846 338.493 + vertex -338.754 42.589 336.456 + vertex -328.865 40.813 336.449 + endloop + endfacet + facet normal -0.142912 -0.856359 0.496211 + outer loop + vertex -329.388 42.0846 338.493 + vertex -328.865 40.813 336.449 + vertex -318.862 40.2321 338.328 + endloop + endfacet + facet normal -0.141369 -0.862375 0.486132 + outer loop + vertex -318.862 40.2321 338.328 + vertex -328.865 40.813 336.449 + vertex -319.571 39.0603 336.043 + endloop + endfacet + facet normal -0.152038 -0.900623 0.407139 + outer loop + vertex -328.865 40.813 336.449 + vertex -328.646 39.8771 334.461 + vertex -319.571 39.0603 336.043 + endloop + endfacet + facet normal -0.151167 -0.903722 0.400544 + outer loop + vertex -319.571 39.0603 336.043 + vertex -328.646 39.8771 334.461 + vertex -321.337 38.5324 334.185 + endloop + endfacet + facet normal -0.177017 -0.896682 0.405741 + outer loop + vertex -359.656 46.3952 335.965 + vertex -358.767 45.3337 334.007 + vertex -349.027 44.4341 336.268 + endloop + endfacet + facet normal -0.176907 -0.89697 0.405154 + outer loop + vertex -349.027 44.4341 336.268 + vertex -358.767 45.3337 334.007 + vertex -348.183 43.3852 334.315 + endloop + endfacet + facet normal -0.171093 -0.862695 0.475903 + outer loop + vertex -360.369 47.6177 337.925 + vertex -359.656 46.3952 335.965 + vertex -349.77 45.6691 338.203 + endloop + endfacet + facet normal -0.172241 -0.858972 0.482182 + outer loop + vertex -349.77 45.6691 338.203 + vertex -359.656 46.3952 335.965 + vertex -349.027 44.4341 336.268 + endloop + endfacet + facet normal -0.161944 -0.858805 0.486033 + outer loop + vertex -349.77 45.6691 338.203 + vertex -349.027 44.4341 336.268 + vertex -339.507 43.8481 338.405 + endloop + endfacet + facet normal -0.162734 -0.856251 0.490257 + outer loop + vertex -339.507 43.8481 338.405 + vertex -349.027 44.4341 336.268 + vertex -338.754 42.589 336.456 + endloop + endfacet + facet normal -0.168558 -0.896947 0.408746 + outer loop + vertex -349.027 44.4341 336.268 + vertex -348.183 43.3852 334.315 + vertex -338.754 42.589 336.456 + endloop + endfacet + facet normal -0.168053 -0.898276 0.406028 + outer loop + vertex -338.754 42.589 336.456 + vertex -348.183 43.3852 334.315 + vertex -338.022 41.5624 334.488 + endloop + endfacet + facet normal -0.193997 -0.900659 0.388817 + outer loop + vertex -380.243 50.3516 335.104 + vertex -379.082 49.252 333.137 + vertex -370.311 48.4132 335.57 + endloop + endfacet + facet normal -0.194692 -0.899205 0.391823 + outer loop + vertex -370.311 48.4132 335.57 + vertex -379.082 49.252 333.137 + vertex -369.331 47.3482 333.613 + endloop + endfacet + facet normal -0.189132 -0.869836 0.455646 + outer loop + vertex -381.279 51.6597 337.172 + vertex -380.243 50.3516 335.104 + vertex -371.083 49.6497 337.567 + endloop + endfacet + facet normal -0.190665 -0.86589 0.462472 + outer loop + vertex -371.083 49.6497 337.567 + vertex -380.243 50.3516 335.104 + vertex -370.311 48.4132 335.57 + endloop + endfacet + facet normal -0.179835 -0.865944 0.466691 + outer loop + vertex -371.083 49.6497 337.567 + vertex -370.311 48.4132 335.57 + vertex -360.369 47.6177 337.925 + endloop + endfacet + facet normal -0.180905 -0.862667 0.472313 + outer loop + vertex -360.369 47.6177 337.925 + vertex -370.311 48.4132 335.57 + vertex -359.656 46.3952 335.965 + endloop + endfacet + facet normal -0.185006 -0.899139 0.396637 + outer loop + vertex -370.311 48.4132 335.57 + vertex -369.331 47.3482 333.613 + vertex -359.656 46.3952 335.965 + endloop + endfacet + facet normal -0.185991 -0.896696 0.401676 + outer loop + vertex -359.656 46.3952 335.965 + vertex -369.331 47.3482 333.613 + vertex -358.767 45.3337 334.007 + endloop + endfacet + facet normal -0.198721 -0.872629 0.446127 + outer loop + vertex -390.502 53.606 336.87 + vertex -388.508 52.0098 334.636 + vertex -381.279 51.6597 337.172 + endloop + endfacet + facet normal -0.200083 -0.870143 0.450353 + outer loop + vertex -381.279 51.6597 337.172 + vertex -388.508 52.0098 334.636 + vertex -380.243 50.3516 335.104 + endloop + endfacet + facet normal -0.202743 -0.904825 0.374415 + outer loop + vertex -388.508 52.0098 334.636 + vertex -386.969 50.8277 332.613 + vertex -380.243 50.3516 335.104 + endloop + endfacet + facet normal -0.205374 -0.900943 0.38226 + outer loop + vertex -380.243 50.3516 335.104 + vertex -386.969 50.8277 332.613 + vertex -379.082 49.252 333.137 + endloop + endfacet + facet normal -0.235445 -0.913329 0.332259 + outer loop + vertex -397.068 53.7878 334.214 + vertex -395.254 52.5771 332.171 + vertex -396.598 53.5701 333.948 + endloop + endfacet + facet normal -0.180126 -0.910401 0.372459 + outer loop + vertex -396.598 53.5701 333.948 + vertex -395.254 52.5771 332.171 + vertex -394.738 52.4009 331.99 + endloop + endfacet + facet normal -0.222336 -0.87903 0.421749 + outer loop + vertex -398.672 55.1976 336.307 + vertex -397.068 53.7878 334.214 + vertex -398.029 54.8787 335.981 + endloop + endfacet + facet normal -0.144537 -0.875182 0.461698 + outer loop + vertex -398.029 54.8787 335.981 + vertex -397.068 53.7878 334.214 + vertex -396.598 53.5701 333.948 + endloop + endfacet + facet normal -0.216727 -0.883155 0.416014 + outer loop + vertex -398.029 54.8787 335.981 + vertex -396.598 53.5701 333.948 + vertex -396.011 54.2696 335.739 + endloop + endfacet + facet normal -0.206161 -0.886661 0.41392 + outer loop + vertex -396.011 54.2696 335.739 + vertex -396.598 53.5701 333.948 + vertex -394.081 53.0798 334.152 + endloop + endfacet + facet normal -0.20627 -0.913875 0.349693 + outer loop + vertex -396.598 53.5701 333.948 + vertex -394.738 52.4009 331.99 + vertex -394.081 53.0798 334.152 + endloop + endfacet + facet normal -0.214085 -0.911455 0.351308 + outer loop + vertex -394.081 53.0798 334.152 + vertex -394.738 52.4009 331.99 + vertex -392.267 51.8929 332.177 + endloop + endfacet + facet normal 0.199694 0.868205 -0.45425 + outer loop + vertex -398.807 55.4912 336.808 + vertex -397.216 54.0186 334.693 + vertex -398.672 55.1976 336.307 + endloop + endfacet + facet normal 0.368968 0.87694 -0.30796 + outer loop + vertex -398.672 55.1976 336.307 + vertex -397.216 54.0186 334.693 + vertex -397.068 53.7878 334.214 + endloop + endfacet + facet normal 0.209683 0.904756 -0.370743 + outer loop + vertex -397.216 54.0186 334.693 + vertex -395.468 52.7668 332.627 + vertex -397.068 53.7878 334.214 + endloop + endfacet + facet normal 0.381093 0.903301 -0.197015 + outer loop + vertex -397.068 53.7878 334.214 + vertex -395.468 52.7668 332.627 + vertex -395.254 52.5771 332.171 + endloop + endfacet + facet normal 0.209345 -0.962442 0.172859 + outer loop + vertex 389.626 50.7465 330.389 + vertex 387.36 49.9017 328.43 + vertex 392.336 51.2462 329.889 + endloop + endfacet + facet normal 0.215684 -0.964396 0.153042 + outer loop + vertex 392.336 51.2462 329.889 + vertex 387.36 49.9017 328.43 + vertex 391.013 50.6348 327.9 + endloop + endfacet + facet normal 0.207782 -0.938132 0.27701 + outer loop + vertex 391.577 51.7622 332.365 + vertex 389.626 50.7465 330.389 + vertex 394.078 52.163 331.847 + endloop + endfacet + facet normal 0.219544 -0.943896 0.246701 + outer loop + vertex 394.078 52.163 331.847 + vertex 389.626 50.7465 330.389 + vertex 392.336 51.2462 329.889 + endloop + endfacet + facet normal 0.204505 -0.956596 0.207611 + outer loop + vertex 377.957 48.3975 331.191 + vertex 377.984 48.058 329.601 + vertex 385.23 49.8715 330.819 + endloop + endfacet + facet normal 0.210879 -0.961384 0.176834 + outer loop + vertex 385.23 49.8715 330.819 + vertex 377.984 48.058 329.601 + vertex 382.81 48.9959 328.944 + endloop + endfacet + facet normal 0.204295 -0.933473 0.294774 + outer loop + vertex 378.487 49.1353 333.161 + vertex 377.957 48.3975 331.191 + vertex 386.476 50.755 332.753 + endloop + endfacet + facet normal 0.204282 -0.93346 0.294825 + outer loop + vertex 386.476 50.755 332.753 + vertex 377.957 48.3975 331.191 + vertex 385.23 49.8715 330.819 + endloop + endfacet + facet normal 0.206603 -0.933425 0.293314 + outer loop + vertex 386.476 50.755 332.753 + vertex 385.23 49.8715 330.819 + vertex 391.577 51.7622 332.365 + endloop + endfacet + facet normal 0.213377 -0.938444 0.271649 + outer loop + vertex 391.577 51.7622 332.365 + vertex 385.23 49.8715 330.819 + vertex 389.626 50.7465 330.389 + endloop + endfacet + facet normal 0.208904 -0.961346 0.179367 + outer loop + vertex 385.23 49.8715 330.819 + vertex 382.81 48.9959 328.944 + vertex 389.626 50.7465 330.389 + endloop + endfacet + facet normal 0.210956 -0.962424 0.170988 + outer loop + vertex 389.626 50.7465 330.389 + vertex 382.81 48.9959 328.944 + vertex 387.36 49.9017 328.43 + endloop + endfacet + facet normal 0.19145 -0.965414 0.176981 + outer loop + vertex 358.071 44.5326 331.99 + vertex 359.276 44.4204 330.074 + vertex 368.369 46.5022 331.594 + endloop + endfacet + facet normal 0.192832 -0.966385 0.170045 + outer loop + vertex 368.369 46.5022 331.594 + vertex 359.276 44.4204 330.074 + vertex 368.547 46.1761 329.539 + endloop + endfacet + facet normal 0.190248 -0.937459 0.291507 + outer loop + vertex 358.339 45.2207 334.028 + vertex 358.071 44.5326 331.99 + vertex 368.637 47.1823 333.615 + endloop + endfacet + facet normal 0.190524 -0.937792 0.290254 + outer loop + vertex 368.637 47.1823 333.615 + vertex 358.071 44.5326 331.99 + vertex 368.369 46.5022 331.594 + endloop + endfacet + facet normal 0.199009 -0.936509 0.288697 + outer loop + vertex 368.637 47.1823 333.615 + vertex 368.369 46.5022 331.594 + vertex 378.487 49.1353 333.161 + endloop + endfacet + facet normal 0.197148 -0.934301 0.297007 + outer loop + vertex 378.487 49.1353 333.161 + vertex 368.369 46.5022 331.594 + vertex 377.957 48.3975 331.191 + endloop + endfacet + facet normal 0.197957 -0.965301 0.170317 + outer loop + vertex 368.369 46.5022 331.594 + vertex 368.547 46.1761 329.539 + vertex 377.957 48.3975 331.191 + endloop + endfacet + facet normal 0.189976 -0.959505 0.207987 + outer loop + vertex 377.957 48.3975 331.191 + vertex 368.547 46.1761 329.539 + vertex 377.984 48.058 329.601 + endloop + endfacet + facet normal 0.175206 -0.967587 0.181877 + outer loop + vertex 338.471 40.9757 332.477 + vertex 339.197 40.7599 330.629 + vertex 348.004 42.6716 332.316 + endloop + endfacet + facet normal 0.182357 -0.971824 0.149344 + outer loop + vertex 348.004 42.6716 332.316 + vertex 339.197 40.7599 330.629 + vertex 348.407 42.3949 330.023 + endloop + endfacet + facet normal 0.170771 -0.935842 0.308282 + outer loop + vertex 338.769 41.6706 334.421 + vertex 338.471 40.9757 332.477 + vertex 348.356 43.381 334.303 + endloop + endfacet + facet normal 0.171842 -0.93703 0.304049 + outer loop + vertex 348.356 43.381 334.303 + vertex 338.471 40.9757 332.477 + vertex 348.004 42.6716 332.316 + endloop + endfacet + facet normal 0.180801 -0.935978 0.302087 + outer loop + vertex 348.356 43.381 334.303 + vertex 348.004 42.6716 332.316 + vertex 358.339 45.2207 334.028 + endloop + endfacet + facet normal 0.18296 -0.938501 0.292816 + outer loop + vertex 358.339 45.2207 334.028 + vertex 348.004 42.6716 332.316 + vertex 358.071 44.5326 331.99 + endloop + endfacet + facet normal 0.184413 -0.971389 0.149653 + outer loop + vertex 348.004 42.6716 332.316 + vertex 348.407 42.3949 330.023 + vertex 358.071 44.5326 331.99 + endloop + endfacet + facet normal 0.179761 -0.968938 0.169836 + outer loop + vertex 358.071 44.5326 331.99 + vertex 348.407 42.3949 330.023 + vertex 359.276 44.4204 330.074 + endloop + endfacet + facet normal 0.158977 -0.967658 0.195866 + outer loop + vertex 319.813 37.8405 332.573 + vertex 320.585 37.5949 330.734 + vertex 329.191 39.3707 332.521 + endloop + endfacet + facet normal 0.166747 -0.972405 0.163169 + outer loop + vertex 329.191 39.3707 332.521 + vertex 320.585 37.5949 330.734 + vertex 329.114 38.9934 330.352 + endloop + endfacet + facet normal 0.1526 -0.934806 0.320704 + outer loop + vertex 319.664 38.5538 334.724 + vertex 319.813 37.8405 332.573 + vertex 329.33 40.0543 334.498 + endloop + endfacet + facet normal 0.154629 -0.937011 0.313209 + outer loop + vertex 329.33 40.0543 334.498 + vertex 319.813 37.8405 332.573 + vertex 329.191 39.3707 332.521 + endloop + endfacet + facet normal 0.162803 -0.935941 0.312266 + outer loop + vertex 329.33 40.0543 334.498 + vertex 329.191 39.3707 332.521 + vertex 338.769 41.6706 334.421 + endloop + endfacet + facet normal 0.163489 -0.936675 0.309697 + outer loop + vertex 338.769 41.6706 334.421 + vertex 329.191 39.3707 332.521 + vertex 338.471 40.9757 332.477 + endloop + endfacet + facet normal 0.168914 -0.972054 0.163031 + outer loop + vertex 329.191 39.3707 332.521 + vertex 329.114 38.9934 330.352 + vertex 338.471 40.9757 332.477 + endloop + endfacet + facet normal 0.165051 -0.970058 0.178172 + outer loop + vertex 338.471 40.9757 332.477 + vertex 329.114 38.9934 330.352 + vertex 339.197 40.7599 330.629 + endloop + endfacet + facet normal 0.146502 -0.967673 0.205294 + outer loop + vertex 299.376 34.7394 332.755 + vertex 301.297 34.6181 330.812 + vertex 309.902 36.3265 332.724 + endloop + endfacet + facet normal 0.152196 -0.971282 0.182886 + outer loop + vertex 309.902 36.3265 332.724 + vertex 301.297 34.6181 330.812 + vertex 310.346 35.9593 330.404 + endloop + endfacet + facet normal 0.149316 -0.935837 0.319238 + outer loop + vertex 296.097 34.837 334.575 + vertex 299.376 34.7394 332.755 + vertex 308.126 37.0048 335.303 + endloop + endfacet + facet normal 0.141107 -0.929214 0.341541 + outer loop + vertex 308.126 37.0048 335.303 + vertex 299.376 34.7394 332.755 + vertex 309.902 36.3265 332.724 + endloop + endfacet + facet normal 0.141893 -0.928923 0.342006 + outer loop + vertex 308.126 37.0048 335.303 + vertex 309.902 36.3265 332.724 + vertex 319.664 38.5538 334.724 + endloop + endfacet + facet normal 0.147795 -0.935602 0.320633 + outer loop + vertex 319.664 38.5538 334.724 + vertex 309.902 36.3265 332.724 + vertex 319.813 37.8405 332.573 + endloop + endfacet + facet normal 0.151178 -0.971472 0.182721 + outer loop + vertex 309.902 36.3265 332.724 + vertex 310.346 35.9593 330.404 + vertex 319.813 37.8405 332.573 + endloop + endfacet + facet normal 0.148792 -0.970067 0.191915 + outer loop + vertex 319.813 37.8405 332.573 + vertex 310.346 35.9593 330.404 + vertex 320.585 37.5949 330.734 + endloop + endfacet + facet normal 0.138299 -0.976776 0.163654 + outer loop + vertex 278.429 31.6808 332.663 + vertex 280.636 31.6926 330.868 + vertex 288.849 33.1621 332.698 + endloop + endfacet + facet normal 0.140648 -0.977995 0.154093 + outer loop + vertex 288.849 33.1621 332.698 + vertex 280.636 31.6926 330.868 + vertex 290.343 33.0276 330.481 + endloop + endfacet + facet normal 0.141754 -0.952379 0.269963 + outer loop + vertex 276.149 31.7802 334.21 + vertex 278.429 31.6808 332.663 + vertex 286.195 33.4012 334.654 + endloop + endfacet + facet normal 0.133416 -0.945621 0.296649 + outer loop + vertex 286.195 33.4012 334.654 + vertex 278.429 31.6808 332.663 + vertex 288.849 33.1621 332.698 + endloop + endfacet + facet normal 0.139096 -0.942472 0.303973 + outer loop + vertex 286.195 33.4012 334.654 + vertex 288.849 33.1621 332.698 + vertex 296.097 34.837 334.575 + endloop + endfacet + facet normal 0.13966 -0.942951 0.302223 + outer loop + vertex 296.097 34.837 334.575 + vertex 288.849 33.1621 332.698 + vertex 299.376 34.7394 332.755 + endloop + endfacet + facet normal 0.145511 -0.976773 0.157295 + outer loop + vertex 288.849 33.1621 332.698 + vertex 290.343 33.0276 330.481 + vertex 299.376 34.7394 332.755 + endloop + endfacet + facet normal 0.135193 -0.97157 0.194355 + outer loop + vertex 299.376 34.7394 332.755 + vertex 290.343 33.0276 330.481 + vertex 301.297 34.6181 330.812 + endloop + endfacet + facet normal 0.126222 -0.981114 0.14657 + outer loop + vertex 257.479 28.9149 332.703 + vertex 259.085 28.8501 330.886 + vertex 268.078 30.2717 332.657 + endloop + endfacet + facet normal 0.131286 -0.983693 0.122932 + outer loop + vertex 268.078 30.2717 332.657 + vertex 259.085 28.8501 330.886 + vertex 269.217 30.1558 330.513 + endloop + endfacet + facet normal 0.124304 -0.956205 0.264993 + outer loop + vertex 256.972 29.3908 334.658 + vertex 257.479 28.9149 332.703 + vertex 267.775 30.7651 334.55 + endloop + endfacet + facet normal 0.12344 -0.95524 0.268848 + outer loop + vertex 267.775 30.7651 334.55 + vertex 257.479 28.9149 332.703 + vertex 268.078 30.2717 332.657 + endloop + endfacet + facet normal 0.126636 -0.954716 0.269223 + outer loop + vertex 267.775 30.7651 334.55 + vertex 268.078 30.2717 332.657 + vertex 276.149 31.7802 334.21 + endloop + endfacet + facet normal 0.130355 -0.958495 0.253564 + outer loop + vertex 276.149 31.7802 334.21 + vertex 268.078 30.2717 332.657 + vertex 278.429 31.6808 332.663 + endloop + endfacet + facet normal 0.133783 -0.983193 0.124232 + outer loop + vertex 268.078 30.2717 332.657 + vertex 269.217 30.1558 330.513 + vertex 278.429 31.6808 332.663 + endloop + endfacet + facet normal 0.127292 -0.980443 0.150096 + outer loop + vertex 278.429 31.6808 332.663 + vertex 269.217 30.1558 330.513 + vertex 280.636 31.6926 330.868 + endloop + endfacet + facet normal 0.119707 -0.984519 0.128031 + outer loop + vertex 235.482 26.184 332.646 + vertex 237.038 26.1381 330.839 + vertex 246.441 27.5216 332.685 + endloop + endfacet + facet normal 0.123187 -0.986101 0.111491 + outer loop + vertex 246.441 27.5216 332.685 + vertex 237.038 26.1381 330.839 + vertex 247.335 27.3866 330.505 + endloop + endfacet + facet normal 0.11735 -0.960921 0.250718 + outer loop + vertex 234.946 26.6264 334.593 + vertex 235.482 26.184 332.646 + vertex 245.815 27.9641 334.633 + endloop + endfacet + facet normal 0.116236 -0.959795 0.255505 + outer loop + vertex 245.815 27.9641 334.633 + vertex 235.482 26.184 332.646 + vertex 246.441 27.5216 332.685 + endloop + endfacet + facet normal 0.121999 -0.958653 0.2571 + outer loop + vertex 245.815 27.9641 334.633 + vertex 246.441 27.5216 332.685 + vertex 256.972 29.3908 334.658 + endloop + endfacet + facet normal 0.120374 -0.95694 0.264152 + outer loop + vertex 256.972 29.3908 334.658 + vertex 246.441 27.5216 332.685 + vertex 257.479 28.9149 332.703 + endloop + endfacet + facet normal 0.124279 -0.985914 0.111926 + outer loop + vertex 246.441 27.5216 332.685 + vertex 247.335 27.3866 330.505 + vertex 257.479 28.9149 332.703 + endloop + endfacet + facet normal 0.117933 -0.9832 0.139317 + outer loop + vertex 257.479 28.9149 332.703 + vertex 247.335 27.3866 330.505 + vertex 259.085 28.8501 330.886 + endloop + endfacet + facet normal 0.108926 -0.987439 0.114449 + outer loop + vertex 214.086 23.765 332.632 + vertex 215.453 23.7056 330.818 + vertex 224.744 24.9403 332.629 + endloop + endfacet + facet normal 0.112767 -0.988992 0.095802 + outer loop + vertex 224.744 24.9403 332.629 + vertex 215.453 23.7056 330.818 + vertex 225.466 24.8126 330.46 + endloop + endfacet + facet normal 0.107281 -0.964054 0.243084 + outer loop + vertex 213.716 24.2193 334.597 + vertex 214.086 23.765 332.632 + vertex 224.328 25.3976 334.587 + endloop + endfacet + facet normal 0.106272 -0.963037 0.24752 + outer loop + vertex 224.328 25.3976 334.587 + vertex 214.086 23.765 332.632 + vertex 224.744 24.9403 332.629 + endloop + endfacet + facet normal 0.111209 -0.962256 0.248387 + outer loop + vertex 224.328 25.3976 334.587 + vertex 224.744 24.9403 332.629 + vertex 234.946 26.6264 334.593 + endloop + endfacet + facet normal 0.111014 -0.96206 0.249231 + outer loop + vertex 234.946 26.6264 334.593 + vertex 224.744 24.9403 332.629 + vertex 235.482 26.184 332.646 + endloop + endfacet + facet normal 0.114354 -0.98876 0.0963167 + outer loop + vertex 224.744 24.9403 332.629 + vertex 225.466 24.8126 330.46 + vertex 235.482 26.184 332.646 + endloop + endfacet + facet normal 0.109144 -0.986877 0.118999 + outer loop + vertex 235.482 26.184 332.646 + vertex 225.466 24.8126 330.46 + vertex 237.038 26.1381 330.839 + endloop + endfacet + facet normal 0.100787 -0.98955 0.103112 + outer loop + vertex 192.73 21.5402 332.632 + vertex 194.073 21.4882 330.821 + vertex 203.405 22.6279 332.637 + endloop + endfacet + facet normal 0.104373 -0.990856 0.0855033 + outer loop + vertex 203.405 22.6279 332.637 + vertex 194.073 21.4882 330.821 + vertex 204.019 22.5048 330.46 + endloop + endfacet + facet normal 0.0996367 -0.967488 0.232464 + outer loop + vertex 192.357 21.9728 334.593 + vertex 192.73 21.5402 332.632 + vertex 203.04 23.0748 334.6 + endloop + endfacet + facet normal 0.0983524 -0.966222 0.238205 + outer loop + vertex 203.04 23.0748 334.6 + vertex 192.73 21.5402 332.632 + vertex 203.405 22.6279 332.637 + endloop + endfacet + facet normal 0.103571 -0.965478 0.239007 + outer loop + vertex 203.04 23.0748 334.6 + vertex 203.405 22.6279 332.637 + vertex 213.716 24.2193 334.597 + endloop + endfacet + facet normal 0.102809 -0.964715 0.242395 + outer loop + vertex 213.716 24.2193 334.597 + vertex 203.405 22.6279 332.637 + vertex 214.086 23.765 332.632 + endloop + endfacet + facet normal 0.10551 -0.990709 0.0858155 + outer loop + vertex 203.405 22.6279 332.637 + vertex 204.019 22.5048 330.46 + vertex 214.086 23.765 332.632 + endloop + endfacet + facet normal 0.100486 -0.989044 0.108139 + outer loop + vertex 214.086 23.765 332.632 + vertex 204.019 22.5048 330.46 + vertex 215.453 23.7056 330.818 + endloop + endfacet + facet normal 0.0916411 -0.991326 0.0942061 + outer loop + vertex 171.492 19.5168 332.613 + vertex 172.809 19.4666 330.803 + vertex 182.087 20.4973 332.623 + endloop + endfacet + facet normal 0.0956604 -0.992626 0.0744541 + outer loop + vertex 182.087 20.4973 332.623 + vertex 172.809 19.4666 330.803 + vertex 182.684 20.3919 330.451 + endloop + endfacet + facet normal 0.0897702 -0.968907 0.230564 + outer loop + vertex 171.154 19.9519 334.573 + vertex 171.492 19.5168 332.613 + vertex 181.739 20.9348 334.582 + endloop + endfacet + facet normal 0.0894037 -0.968547 0.232213 + outer loop + vertex 181.739 20.9348 334.582 + vertex 171.492 19.5168 332.613 + vertex 182.087 20.4973 332.623 + endloop + endfacet + facet normal 0.094393 -0.967896 0.232954 + outer loop + vertex 181.739 20.9348 334.582 + vertex 182.087 20.4973 332.623 + vertex 192.357 21.9728 334.593 + endloop + endfacet + facet normal 0.0946791 -0.968176 0.231671 + outer loop + vertex 192.357 21.9728 334.593 + vertex 182.087 20.4973 332.623 + vertex 192.73 21.5402 332.632 + endloop + endfacet + facet normal 0.097191 -0.992446 0.074866 + outer loop + vertex 182.087 20.4973 332.623 + vertex 182.684 20.3919 330.451 + vertex 192.73 21.5402 332.632 + endloop + endfacet + facet normal 0.0922585 -0.991016 0.0968326 + outer loop + vertex 192.73 21.5402 332.632 + vertex 182.684 20.3919 330.451 + vertex 194.073 21.4882 330.821 + endloop + endfacet + facet normal 0.081629 -0.991976 0.0965459 + outer loop + vertex 150.219 17.7144 332.595 + vertex 151.547 17.6472 330.781 + vertex 160.892 18.5935 332.604 + endloop + endfacet + facet normal 0.086673 -0.993664 0.0715585 + outer loop + vertex 160.892 18.5935 332.604 + vertex 151.547 17.6472 330.781 + vertex 161.455 18.486 330.43 + endloop + endfacet + facet normal 0.0795174 -0.970757 0.226511 + outer loop + vertex 149.855 18.1429 334.559 + vertex 150.219 17.7144 332.595 + vertex 160.536 19.0195 334.566 + endloop + endfacet + facet normal 0.0798033 -0.971039 0.2252 + outer loop + vertex 160.536 19.0195 334.566 + vertex 150.219 17.7144 332.595 + vertex 160.892 18.5935 332.604 + endloop + endfacet + facet normal 0.0850793 -0.9704 0.226019 + outer loop + vertex 160.536 19.0195 334.566 + vertex 160.892 18.5935 332.604 + vertex 171.154 19.9519 334.573 + endloop + endfacet + facet normal 0.0842536 -0.969593 0.229764 + outer loop + vertex 171.154 19.9519 334.573 + vertex 160.892 18.5935 332.604 + vertex 171.492 19.5168 332.613 + endloop + endfacet + facet normal 0.0864932 -0.993682 0.071513 + outer loop + vertex 160.892 18.5935 332.604 + vertex 161.455 18.486 330.43 + vertex 171.492 19.5168 332.613 + endloop + endfacet + facet normal 0.0828395 -0.992684 0.0878389 + outer loop + vertex 171.492 19.5168 332.613 + vertex 161.455 18.486 330.43 + vertex 172.809 19.4666 330.803 + endloop + endfacet + facet normal 0.0708823 -0.992885 0.0956837 + outer loop + vertex 128.678 16.1195 332.579 + vertex 130.068 16.0435 330.762 + vertex 139.479 16.8913 332.586 + endloop + endfacet + facet normal 0.0762918 -0.99472 0.0686368 + outer loop + vertex 139.479 16.8913 332.586 + vertex 130.068 16.0435 330.762 + vertex 140.092 16.7881 330.409 + endloop + endfacet + facet normal 0.0689516 -0.971396 0.227234 + outer loop + vertex 128.285 16.5518 334.547 + vertex 128.678 16.1195 332.579 + vertex 139.1 17.3208 334.552 + endloop + endfacet + facet normal 0.0692844 -0.971734 0.225682 + outer loop + vertex 139.1 17.3208 334.552 + vertex 128.678 16.1195 332.579 + vertex 139.479 16.8913 332.586 + endloop + endfacet + facet normal 0.0740898 -0.971192 0.226489 + outer loop + vertex 139.1 17.3208 334.552 + vertex 139.479 16.8913 332.586 + vertex 149.855 18.1429 334.559 + endloop + endfacet + facet normal 0.0742667 -0.971369 0.225671 + outer loop + vertex 149.855 18.1429 334.559 + vertex 139.479 16.8913 332.586 + vertex 150.219 17.7144 332.595 + endloop + endfacet + facet normal 0.076184 -0.994731 0.0686069 + outer loop + vertex 139.479 16.8913 332.586 + vertex 140.092 16.7881 330.409 + vertex 150.219 17.7144 332.595 + endloop + endfacet + facet normal 0.071607 -0.993431 0.0892621 + outer loop + vertex 150.219 17.7144 332.595 + vertex 140.092 16.7881 330.409 + vertex 151.547 17.6472 330.781 + endloop + endfacet + facet normal 0.0586054 -0.993441 0.09819 + outer loop + vertex 107.096 14.78 332.568 + vertex 108.516 14.6839 330.749 + vertex 117.871 15.4161 332.573 + endloop + endfacet + facet normal 0.0644471 -0.995528 0.0690683 + outer loop + vertex 117.871 15.4161 332.573 + vertex 108.516 14.6839 330.749 + vertex 118.561 15.3094 330.392 + endloop + endfacet + facet normal 0.0573289 -0.972577 0.225406 + outer loop + vertex 106.664 15.2111 334.538 + vertex 107.096 14.78 332.568 + vertex 117.458 15.8481 334.542 + endloop + endfacet + facet normal 0.0573186 -0.972566 0.225454 + outer loop + vertex 117.458 15.8481 334.542 + vertex 107.096 14.78 332.568 + vertex 117.871 15.4161 332.573 + endloop + endfacet + facet normal 0.0630639 -0.971961 0.226527 + outer loop + vertex 117.458 15.8481 334.542 + vertex 117.871 15.4161 332.573 + vertex 128.285 16.5518 334.547 + endloop + endfacet + facet normal 0.0631315 -0.972031 0.22621 + outer loop + vertex 128.285 16.5518 334.547 + vertex 117.871 15.4161 332.573 + vertex 128.678 16.1195 332.579 + endloop + endfacet + facet normal 0.064755 -0.995501 0.0691645 + outer loop + vertex 117.871 15.4161 332.573 + vertex 118.561 15.3094 330.392 + vertex 128.678 16.1195 332.579 + endloop + endfacet + facet normal 0.060609 -0.994285 0.0878872 + outer loop + vertex 128.678 16.1195 332.579 + vertex 118.561 15.3094 330.392 + vertex 130.068 16.0435 330.762 + endloop + endfacet + facet normal 0.0463608 -0.994169 0.097359 + outer loop + vertex 85.7864 13.7131 332.565 + vertex 87.1843 13.5999 330.744 + vertex 96.3893 14.2076 332.566 + endloop + endfacet + facet normal 0.0521104 -0.996255 0.0690011 + outer loop + vertex 96.3893 14.2076 332.566 + vertex 87.1843 13.5999 330.744 + vertex 97.104 14.0938 330.383 + endloop + endfacet + facet normal 0.0456341 -0.972761 0.227275 + outer loop + vertex 85.3654 14.1538 334.536 + vertex 85.7864 13.7131 332.565 + vertex 95.9707 14.6513 334.536 + endloop + endfacet + facet normal 0.0453413 -0.972454 0.228642 + outer loop + vertex 95.9707 14.6513 334.536 + vertex 85.7864 13.7131 332.565 + vertex 96.3893 14.2076 332.566 + endloop + endfacet + facet normal 0.050834 -0.971935 0.229692 + outer loop + vertex 95.9707 14.6513 334.536 + vertex 96.3893 14.2076 332.566 + vertex 106.664 15.2111 334.538 + endloop + endfacet + facet normal 0.0519751 -0.973121 0.224351 + outer loop + vertex 106.664 15.2111 334.538 + vertex 96.3893 14.2076 332.566 + vertex 107.096 14.78 332.568 + endloop + endfacet + facet normal 0.0532404 -0.99617 0.0693667 + outer loop + vertex 96.3893 14.2076 332.566 + vertex 97.104 14.0938 330.383 + vertex 107.096 14.78 332.568 + endloop + endfacet + facet normal 0.0485408 -0.994721 0.0904045 + outer loop + vertex 107.096 14.78 332.568 + vertex 97.104 14.0938 330.383 + vertex 108.516 14.6839 330.749 + endloop + endfacet + facet normal 0.0340691 -0.994523 0.0988099 + outer loop + vertex 64.5653 12.9163 332.57 + vertex 66.0015 12.7846 330.75 + vertex 75.2082 13.2806 332.567 + endloop + endfacet + facet normal 0.0395152 -0.996636 0.0718006 + outer loop + vertex 75.2082 13.2806 332.567 + vertex 66.0015 12.7846 330.75 + vertex 75.8883 13.1503 330.384 + endloop + endfacet + facet normal 0.0330723 -0.97251 0.230501 + outer loop + vertex 64.0888 13.367 334.54 + vertex 64.5653 12.9163 332.57 + vertex 74.7782 13.7299 334.537 + endloop + endfacet + facet normal 0.0333614 -0.972824 0.229131 + outer loop + vertex 74.7782 13.7299 334.537 + vertex 64.5653 12.9163 332.57 + vertex 75.2082 13.2806 332.567 + endloop + endfacet + facet normal 0.0389626 -0.972352 0.230245 + outer loop + vertex 74.7782 13.7299 334.537 + vertex 75.2082 13.2806 332.567 + vertex 85.3654 14.1538 334.536 + endloop + endfacet + facet normal 0.0398356 -0.973277 0.226152 + outer loop + vertex 85.3654 14.1538 334.536 + vertex 75.2082 13.2806 332.567 + vertex 85.7864 13.7131 332.565 + endloop + endfacet + facet normal 0.0407591 -0.996558 0.0721834 + outer loop + vertex 75.2082 13.2806 332.567 + vertex 75.8883 13.1503 330.384 + vertex 85.7864 13.7131 332.565 + endloop + endfacet + facet normal 0.0367485 -0.995259 0.0900484 + outer loop + vertex 85.7864 13.7131 332.565 + vertex 75.8883 13.1503 330.384 + vertex 87.1843 13.5999 330.744 + endloop + endfacet + facet normal 0.0236053 -0.994825 0.0988211 + outer loop + vertex 42.9964 12.3481 332.579 + vertex 44.5576 12.2044 330.76 + vertex 53.7968 12.6039 332.574 + endloop + endfacet + facet normal 0.0284754 -0.996817 0.0744646 + outer loop + vertex 53.7968 12.6039 332.574 + vertex 44.5576 12.2044 330.76 + vertex 54.5975 12.4638 330.393 + endloop + endfacet + facet normal 0.0221054 -0.972028 0.233823 + outer loop + vertex 42.4705 12.8094 334.547 + vertex 42.9964 12.3481 332.579 + vertex 53.2769 13.0544 334.543 + endloop + endfacet + facet normal 0.0231509 -0.973204 0.228774 + outer loop + vertex 53.2769 13.0544 334.543 + vertex 42.9964 12.3481 332.579 + vertex 53.7968 12.6039 332.574 + endloop + endfacet + facet normal 0.0281924 -0.97278 0.230009 + outer loop + vertex 53.2769 13.0544 334.543 + vertex 53.7968 12.6039 332.574 + vertex 64.0888 13.367 334.54 + endloop + endfacet + facet normal 0.0283105 -0.972911 0.229441 + outer loop + vertex 64.0888 13.367 334.54 + vertex 53.7968 12.6039 332.574 + vertex 64.5653 12.9163 332.57 + endloop + endfacet + facet normal 0.0289431 -0.996791 0.0746346 + outer loop + vertex 53.7968 12.6039 332.574 + vertex 54.5975 12.4638 330.393 + vertex 64.5653 12.9163 332.57 + endloop + endfacet + facet normal 0.0251276 -0.995458 0.0918239 + outer loop + vertex 64.5653 12.9163 332.57 + vertex 54.5975 12.4638 330.393 + vertex 66.0015 12.7846 330.75 + endloop + endfacet + facet normal 0.0128176 -0.99472 0.101824 + outer loop + vertex 21.7565 12.0213 332.586 + vertex 23.2856 11.855 330.769 + vertex 32.3033 12.1569 332.583 + endloop + endfacet + facet normal 0.0175696 -0.996756 0.0785442 + outer loop + vertex 32.3033 12.1569 332.583 + vertex 23.2856 11.855 330.769 + vertex 33.1806 12.0006 330.403 + endloop + endfacet + facet normal 0.0123525 -0.972724 0.231638 + outer loop + vertex 21.225 12.4829 334.553 + vertex 21.7565 12.0213 332.586 + vertex 31.7742 12.6162 334.55 + endloop + endfacet + facet normal 0.0125772 -0.972975 0.230567 + outer loop + vertex 31.7742 12.6162 334.55 + vertex 21.7565 12.0213 332.586 + vertex 32.3033 12.1569 332.583 + endloop + endfacet + facet normal 0.017649 -0.972593 0.231842 + outer loop + vertex 31.7742 12.6162 334.55 + vertex 32.3033 12.1569 332.583 + vertex 42.4705 12.8094 334.547 + endloop + endfacet + facet normal 0.017476 -0.972398 0.232673 + outer loop + vertex 42.4705 12.8094 334.547 + vertex 32.3033 12.1569 332.583 + vertex 42.9964 12.3481 332.579 + endloop + endfacet + facet normal 0.0178524 -0.996742 0.0786569 + outer loop + vertex 32.3033 12.1569 332.583 + vertex 33.1806 12.0006 330.403 + vertex 42.9964 12.3481 332.579 + endloop + endfacet + facet normal 0.014972 -0.995694 0.0914818 + outer loop + vertex 42.9964 12.3481 332.579 + vertex 33.1806 12.0006 330.403 + vertex 44.5576 12.2044 330.76 + endloop + endfacet + facet normal 0.00249753 -0.994796 0.101852 + outer loop + vertex 0.806427 11.9129 332.59 + vertex 2.35929 11.7308 330.773 + vertex 11.2876 11.9391 332.589 + endloop + endfacet + facet normal 0.00774629 -0.997054 0.0763059 + outer loop + vertex 11.2876 11.9391 332.589 + vertex 2.35929 11.7308 330.773 + vertex 12.141 11.779 330.411 + endloop + endfacet + facet normal 0.00247213 -0.972476 0.232991 + outer loop + vertex 0.207159 12.3823 334.556 + vertex 0.806427 11.9129 332.59 + vertex 10.7361 12.4089 334.555 + endloop + endfacet + facet normal 0.00244998 -0.97245 0.233097 + outer loop + vertex 10.7361 12.4089 334.555 + vertex 0.806427 11.9129 332.59 + vertex 11.2876 11.9391 332.589 + endloop + endfacet + facet normal 0.00689929 -0.972146 0.234272 + outer loop + vertex 10.7361 12.4089 334.555 + vertex 11.2876 11.9391 332.589 + vertex 21.225 12.4829 334.553 + endloop + endfacet + facet normal 0.00770271 -0.973052 0.230458 + outer loop + vertex 21.225 12.4829 334.553 + vertex 11.2876 11.9391 332.589 + vertex 21.7565 12.0213 332.586 + endloop + endfacet + facet normal 0.00785076 -0.99705 0.0763465 + outer loop + vertex 11.2876 11.9391 332.589 + vertex 12.141 11.779 330.411 + vertex 21.7565 12.0213 332.586 + endloop + endfacet + facet normal 0.00375615 -0.995539 0.0942755 + outer loop + vertex 21.7565 12.0213 332.586 + vertex 12.141 11.779 330.411 + vertex 23.2856 11.855 330.769 + endloop + endfacet + facet normal -0.00653187 -0.994959 0.100072 + outer loop + vertex -20.2753 12.0044 332.587 + vertex -18.6775 11.8111 330.77 + vertex -9.7229 11.9353 332.589 + endloop + endfacet + facet normal -0.00226573 -0.996856 0.0791987 + outer loop + vertex -9.7229 11.9353 332.589 + vertex -18.6775 11.8111 330.77 + vertex -8.82011 11.7601 330.41 + endloop + endfacet + facet normal -0.00646223 -0.972536 0.232663 + outer loop + vertex -20.8922 12.4788 334.553 + vertex -20.2753 12.0044 332.587 + vertex -10.3403 12.409 334.554 + endloop + endfacet + facet normal -0.00640727 -0.9726 0.232398 + outer loop + vertex -10.3403 12.409 334.554 + vertex -20.2753 12.0044 332.587 + vertex -9.7229 11.9353 332.589 + endloop + endfacet + facet normal -0.00248767 -0.972338 0.233566 + outer loop + vertex -10.3403 12.409 334.554 + vertex -9.7229 11.9353 332.589 + vertex 0.207159 12.3823 334.556 + endloop + endfacet + facet normal -0.00209267 -0.972791 0.231675 + outer loop + vertex 0.207159 12.3823 334.556 + vertex -9.7229 11.9353 332.589 + vertex 0.806427 11.9129 332.59 + endloop + endfacet + facet normal -0.00213114 -0.996852 0.0792542 + outer loop + vertex -9.7229 11.9353 332.589 + vertex -8.82011 11.7601 330.41 + vertex 0.806427 11.9129 332.59 + endloop + endfacet + facet normal -0.00569883 -0.995469 0.094913 + outer loop + vertex 0.806427 11.9129 332.59 + vertex -8.82011 11.7601 330.41 + vertex 2.35929 11.7308 330.773 + endloop + endfacet + facet normal -0.0176489 -0.994805 0.100252 + outer loop + vertex -41.4738 12.3206 332.579 + vertex -39.8422 12.1085 330.762 + vertex -30.8304 12.1322 332.583 + endloop + endfacet + facet normal -0.012752 -0.997022 0.076058 + outer loop + vertex -30.8304 12.1322 332.583 + vertex -39.8422 12.1085 330.762 + vertex -29.9136 11.9542 330.404 + endloop + endfacet + facet normal -0.0174999 -0.972687 0.23146 + outer loop + vertex -42.1344 12.8007 334.547 + vertex -41.4738 12.3206 332.579 + vertex -31.456 12.6093 334.55 + endloop + endfacet + facet normal -0.0173114 -0.97291 0.230534 + outer loop + vertex -31.456 12.6093 334.55 + vertex -41.4738 12.3206 332.579 + vertex -30.8304 12.1322 332.583 + endloop + endfacet + facet normal -0.012083 -0.972611 0.232125 + outer loop + vertex -31.456 12.6093 334.55 + vertex -30.8304 12.1322 332.583 + vertex -20.8922 12.4788 334.553 + endloop + endfacet + facet normal -0.0118608 -0.97287 0.231049 + outer loop + vertex -20.8922 12.4788 334.553 + vertex -30.8304 12.1322 332.583 + vertex -20.2753 12.0044 332.587 + endloop + endfacet + facet normal -0.0120994 -0.997009 0.0763314 + outer loop + vertex -30.8304 12.1322 332.583 + vertex -29.9136 11.9542 330.404 + vertex -20.2753 12.0044 332.587 + endloop + endfacet + facet normal -0.0156788 -0.995626 0.0920996 + outer loop + vertex -20.2753 12.0044 332.587 + vertex -29.9136 11.9542 330.404 + vertex -18.6775 11.8111 330.77 + endloop + endfacet + facet normal -0.0283978 -0.994296 0.102803 + outer loop + vertex -63.1228 12.8734 332.571 + vertex -61.373 12.6353 330.751 + vertex -52.2659 12.5637 332.575 + endloop + endfacet + facet normal -0.0230777 -0.99683 0.0761385 + outer loop + vertex -52.2659 12.5637 332.575 + vertex -61.373 12.6353 330.751 + vertex -51.2383 12.3733 330.394 + endloop + endfacet + facet normal -0.027795 -0.972895 0.229571 + outer loop + vertex -63.8628 13.3593 334.54 + vertex -63.1228 12.8734 332.571 + vertex -52.9673 13.0487 334.543 + endloop + endfacet + facet normal -0.0278357 -0.972845 0.229776 + outer loop + vertex -52.9673 13.0487 334.543 + vertex -63.1228 12.8734 332.571 + vertex -52.2659 12.5637 332.575 + endloop + endfacet + facet normal -0.0223363 -0.97254 0.231661 + outer loop + vertex -52.9673 13.0487 334.543 + vertex -52.2659 12.5637 332.575 + vertex -42.1344 12.8007 334.547 + endloop + endfacet + facet normal -0.0220055 -0.97294 0.230009 + outer loop + vertex -42.1344 12.8007 334.547 + vertex -52.2659 12.5637 332.575 + vertex -41.4738 12.3206 332.579 + endloop + endfacet + facet normal -0.0224839 -0.996822 0.0764175 + outer loop + vertex -52.2659 12.5637 332.575 + vertex -51.2383 12.3733 330.394 + vertex -41.4738 12.3206 332.579 + endloop + endfacet + facet normal -0.026123 -0.99535 0.0927096 + outer loop + vertex -41.4738 12.3206 332.579 + vertex -51.2383 12.3733 330.394 + vertex -39.8422 12.1085 330.762 + endloop + endfacet + facet normal -0.0398317 -0.994314 0.0987587 + outer loop + vertex -84.533 13.6584 332.566 + vertex -82.8073 13.4084 330.745 + vertex -73.93 13.2338 332.568 + endloop + endfacet + facet normal -0.0341458 -0.996904 0.0708226 + outer loop + vertex -73.93 13.2338 332.568 + vertex -82.8073 13.4084 330.745 + vertex -72.7841 13.0396 330.386 + endloop + endfacet + facet normal -0.0384673 -0.972676 0.228959 + outer loop + vertex -85.2353 14.15 334.537 + vertex -84.533 13.6584 332.566 + vertex -74.6375 13.7311 334.537 + endloop + endfacet + facet normal -0.0389643 -0.972071 0.231431 + outer loop + vertex -74.6375 13.7311 334.537 + vertex -84.533 13.6584 332.566 + vertex -73.93 13.2338 332.568 + endloop + endfacet + facet normal -0.0336033 -0.971825 0.233295 + outer loop + vertex -74.6375 13.7311 334.537 + vertex -73.93 13.2338 332.568 + vertex -63.8628 13.3593 334.54 + endloop + endfacet + facet normal -0.0325216 -0.973151 0.227859 + outer loop + vertex -63.8628 13.3593 334.54 + vertex -73.93 13.2338 332.568 + vertex -63.1228 12.8734 332.571 + endloop + endfacet + facet normal -0.0332709 -0.996901 0.0712817 + outer loop + vertex -73.93 13.2338 332.568 + vertex -72.7841 13.0396 330.386 + vertex -63.1228 12.8734 332.571 + endloop + endfacet + facet normal -0.0382424 -0.994893 0.0934145 + outer loop + vertex -63.1228 12.8734 332.571 + vertex -72.7841 13.0396 330.386 + vertex -61.373 12.6353 330.751 + endloop + endfacet + facet normal -0.0515024 -0.993875 0.0977742 + outer loop + vertex -105.437 14.6846 332.569 + vertex -103.732 14.417 330.747 + vertex -94.9788 14.1424 332.566 + endloop + endfacet + facet normal -0.0464151 -0.996256 0.0729351 + outer loop + vertex -94.9788 14.1424 332.566 + vertex -103.732 14.417 330.747 + vertex -93.9239 13.9334 330.383 + endloop + endfacet + facet normal -0.0513402 -0.97158 0.231077 + outer loop + vertex -106.171 15.1918 334.538 + vertex -105.437 14.6846 332.569 + vertex -95.6855 14.6374 334.537 + endloop + endfacet + facet normal -0.0503774 -0.972759 0.226278 + outer loop + vertex -95.6855 14.6374 334.537 + vertex -105.437 14.6846 332.569 + vertex -94.9788 14.1424 332.566 + endloop + endfacet + facet normal -0.0453573 -0.972595 0.228038 + outer loop + vertex -95.6855 14.6374 334.537 + vertex -94.9788 14.1424 332.566 + vertex -85.2353 14.15 334.537 + endloop + endfacet + facet normal -0.0450794 -0.972929 0.226665 + outer loop + vertex -85.2353 14.15 334.537 + vertex -94.9788 14.1424 332.566 + vertex -84.533 13.6584 332.566 + endloop + endfacet + facet normal -0.0461599 -0.996259 0.0730587 + outer loop + vertex -94.9788 14.1424 332.566 + vertex -93.9239 13.9334 330.383 + vertex -84.533 13.6584 332.566 + endloop + endfacet + facet normal -0.049889 -0.994756 0.0892888 + outer loop + vertex -84.533 13.6584 332.566 + vertex -93.9239 13.9334 330.383 + vertex -82.8073 13.4084 330.745 + endloop + endfacet + facet normal -0.0639515 -0.993536 0.093786 + outer loop + vertex -126.656 15.9905 332.578 + vertex -124.826 15.7009 330.759 + vertex -115.998 15.3039 332.573 + endloop + endfacet + facet normal -0.0593036 -0.995734 0.0706824 + outer loop + vertex -115.998 15.3039 332.573 + vertex -124.826 15.7009 330.759 + vertex -114.871 15.0819 330.39 + endloop + endfacet + facet normal -0.062969 -0.97203 0.226258 + outer loop + vertex -127.489 16.5027 334.547 + vertex -126.656 15.9905 332.578 + vertex -116.797 15.8089 334.542 + endloop + endfacet + facet normal -0.0625321 -0.972578 0.224014 + outer loop + vertex -116.797 15.8089 334.542 + vertex -126.656 15.9905 332.578 + vertex -115.998 15.3039 332.573 + endloop + endfacet + facet normal -0.0563895 -0.972387 0.226458 + outer loop + vertex -116.797 15.8089 334.542 + vertex -115.998 15.3039 332.573 + vertex -106.171 15.1918 334.538 + endloop + endfacet + facet normal -0.0569007 -0.97175 0.22905 + outer loop + vertex -106.171 15.1918 334.538 + vertex -115.998 15.3039 332.573 + vertex -105.437 14.6846 332.569 + endloop + endfacet + facet normal -0.0583682 -0.995755 0.0711675 + outer loop + vertex -115.998 15.3039 332.573 + vertex -114.871 15.0819 330.39 + vertex -105.437 14.6846 332.569 + endloop + endfacet + facet normal -0.062154 -0.994193 0.0878483 + outer loop + vertex -105.437 14.6846 332.569 + vertex -114.871 15.0819 330.39 + vertex -103.732 14.417 330.747 + endloop + endfacet + facet normal -0.0751357 -0.992967 0.0914931 + outer loop + vertex -147.884 17.5294 332.594 + vertex -146.055 17.2235 330.777 + vertex -137.324 16.7295 332.586 + endloop + endfacet + facet normal -0.0704483 -0.995177 0.0682627 + outer loop + vertex -137.324 16.7295 332.586 + vertex -146.055 17.2235 330.777 + vertex -136.089 16.4926 330.406 + endloop + endfacet + facet normal -0.0737053 -0.97132 0.226065 + outer loop + vertex -148.697 18.0486 334.56 + vertex -147.884 17.5294 332.594 + vertex -138.15 17.2468 334.553 + endloop + endfacet + facet normal -0.0734226 -0.971679 0.224609 + outer loop + vertex -138.15 17.2468 334.553 + vertex -147.884 17.5294 332.594 + vertex -137.324 16.7295 332.586 + endloop + endfacet + facet normal -0.0676733 -0.971543 0.226989 + outer loop + vertex -138.15 17.2468 334.553 + vertex -137.324 16.7295 332.586 + vertex -127.489 16.5027 334.547 + endloop + endfacet + facet normal -0.0671919 -0.972154 0.224504 + outer loop + vertex -127.489 16.5027 334.547 + vertex -137.324 16.7295 332.586 + vertex -126.656 15.9905 332.578 + endloop + endfacet + facet normal -0.0689 -0.995224 0.0691449 + outer loop + vertex -137.324 16.7295 332.586 + vertex -136.089 16.4926 330.406 + vertex -126.656 15.9905 332.578 + endloop + endfacet + facet normal -0.0725165 -0.993722 0.0851971 + outer loop + vertex -126.656 15.9905 332.578 + vertex -136.089 16.4926 330.406 + vertex -124.826 15.7009 330.759 + endloop + endfacet + facet normal -0.0855549 -0.992036 0.0924366 + outer loop + vertex -169.014 19.3008 332.612 + vertex -167.179 18.9735 330.798 + vertex -158.401 18.3847 332.602 + endloop + endfacet + facet normal -0.0811603 -0.994216 0.0703459 + outer loop + vertex -158.401 18.3847 332.602 + vertex -167.179 18.9735 330.798 + vertex -157.228 18.135 330.427 + endloop + endfacet + facet normal -0.0839759 -0.970306 0.226836 + outer loop + vertex -169.867 19.8332 334.573 + vertex -169.014 19.3008 332.612 + vertex -159.224 18.9105 334.566 + endloop + endfacet + facet normal -0.0836049 -0.970793 0.224881 + outer loop + vertex -159.224 18.9105 334.566 + vertex -169.014 19.3008 332.612 + vertex -158.401 18.3847 332.602 + endloop + endfacet + facet normal -0.0793349 -0.970739 0.226654 + outer loop + vertex -159.224 18.9105 334.566 + vertex -158.401 18.3847 332.602 + vertex -148.697 18.0486 334.56 + endloop + endfacet + facet normal -0.0788171 -0.971403 0.223973 + outer loop + vertex -148.697 18.0486 334.56 + vertex -158.401 18.3847 332.602 + vertex -147.884 17.5294 332.594 + endloop + endfacet + facet normal -0.0807973 -0.994231 0.0705433 + outer loop + vertex -158.401 18.3847 332.602 + vertex -157.228 18.135 330.427 + vertex -147.884 17.5294 332.594 + endloop + endfacet + facet normal -0.0836037 -0.993038 0.0829771 + outer loop + vertex -147.884 17.5294 332.594 + vertex -157.228 18.135 330.427 + vertex -146.055 17.2235 330.777 + endloop + endfacet + facet normal -0.0954408 -0.990451 0.0994923 + outer loop + vertex -190.605 21.3347 332.626 + vertex -188.724 20.9716 330.816 + vertex -179.763 20.2892 332.62 + endloop + endfacet + facet normal -0.0907902 -0.993011 0.075411 + outer loop + vertex -179.763 20.2892 332.62 + vertex -188.724 20.9716 330.816 + vertex -178.547 20.0132 330.448 + endloop + endfacet + facet normal -0.094002 -0.96874 0.229577 + outer loop + vertex -191.477 21.8834 334.585 + vertex -190.605 21.3347 332.626 + vertex -180.642 20.8309 334.58 + endloop + endfacet + facet normal -0.0933544 -0.969633 0.226044 + outer loop + vertex -180.642 20.8309 334.58 + vertex -190.605 21.3347 332.626 + vertex -179.763 20.2892 332.62 + endloop + endfacet + facet normal -0.0896352 -0.969596 0.227703 + outer loop + vertex -180.642 20.8309 334.58 + vertex -179.763 20.2892 332.62 + vertex -169.867 19.8332 334.573 + endloop + endfacet + facet normal -0.0890656 -0.970363 0.224639 + outer loop + vertex -169.867 19.8332 334.573 + vertex -179.763 20.2892 332.62 + vertex -169.014 19.3008 332.612 + endloop + endfacet + facet normal -0.0912573 -0.992988 0.0751467 + outer loop + vertex -179.763 20.2892 332.62 + vertex -178.547 20.0132 330.448 + vertex -169.014 19.3008 332.612 + endloop + endfacet + facet normal -0.0933257 -0.992037 0.084573 + outer loop + vertex -169.014 19.3008 332.612 + vertex -178.547 20.0132 330.448 + vertex -167.179 18.9735 330.798 + endloop + endfacet + facet normal -0.104052 -0.988775 0.107221 + outer loop + vertex -212.253 23.564 332.637 + vertex -210.45 23.1783 330.829 + vertex -201.449 22.4266 332.632 + endloop + endfacet + facet normal -0.0995169 -0.991532 0.0834308 + outer loop + vertex -201.449 22.4266 332.632 + vertex -210.45 23.1783 330.829 + vertex -200.254 22.1242 330.464 + endloop + endfacet + facet normal -0.102918 -0.965798 0.237996 + outer loop + vertex -213.042 24.1306 334.594 + vertex -212.253 23.564 332.637 + vertex -202.282 22.9827 334.589 + endloop + endfacet + facet normal -0.101756 -0.967484 0.231559 + outer loop + vertex -202.282 22.9827 334.589 + vertex -212.253 23.564 332.637 + vertex -201.449 22.4266 332.632 + endloop + endfacet + facet normal -0.0983356 -0.967488 0.233016 + outer loop + vertex -202.282 22.9827 334.589 + vertex -201.449 22.4266 332.632 + vertex -191.477 21.8834 334.585 + endloop + endfacet + facet normal -0.0974336 -0.968761 0.228056 + outer loop + vertex -191.477 21.8834 334.585 + vertex -201.449 22.4266 332.632 + vertex -190.605 21.3347 332.626 + endloop + endfacet + facet normal -0.0997976 -0.991517 0.0832739 + outer loop + vertex -201.449 22.4266 332.632 + vertex -200.254 22.1242 330.464 + vertex -190.605 21.3347 332.626 + endloop + endfacet + facet normal -0.101852 -0.990459 0.0928276 + outer loop + vertex -190.605 21.3347 332.626 + vertex -200.254 22.1242 330.464 + vertex -188.724 20.9716 330.816 + endloop + endfacet + facet normal -0.113474 -0.985747 0.124202 + outer loop + vertex -233.891 26.0057 332.65 + vertex -232.148 25.5771 330.84 + vertex -223.048 24.7567 332.643 + endloop + endfacet + facet normal -0.108106 -0.989554 0.0953759 + outer loop + vertex -223.048 24.7567 332.643 + vertex -232.148 25.5771 330.84 + vertex -221.957 24.4284 330.474 + endloop + endfacet + facet normal -0.112194 -0.961557 0.250641 + outer loop + vertex -234.624 26.601 334.605 + vertex -233.891 26.0057 332.65 + vertex -223.81 25.3383 334.602 + endloop + endfacet + facet normal -0.110858 -0.963665 0.243021 + outer loop + vertex -223.81 25.3383 334.602 + vertex -233.891 26.0057 332.65 + vertex -223.048 24.7567 332.643 + endloop + endfacet + facet normal -0.107925 -0.963707 0.244175 + outer loop + vertex -223.81 25.3383 334.602 + vertex -223.048 24.7567 332.643 + vertex -213.042 24.1306 334.594 + endloop + endfacet + facet normal -0.106561 -0.965766 0.236518 + outer loop + vertex -213.042 24.1306 334.594 + vertex -223.048 24.7567 332.643 + vertex -212.253 23.564 332.637 + endloop + endfacet + facet normal -0.109265 -0.989483 0.0947825 + outer loop + vertex -223.048 24.7567 332.643 + vertex -221.957 24.4284 330.474 + vertex -212.253 23.564 332.637 + endloop + endfacet + facet normal -0.110531 -0.988752 0.100755 + outer loop + vertex -212.253 23.564 332.637 + vertex -221.957 24.4284 330.474 + vertex -210.45 23.1783 330.829 + endloop + endfacet + facet normal -0.121571 -0.982605 0.140383 + outer loop + vertex -255.599 28.6367 332.629 + vertex -253.865 28.1657 330.833 + vertex -244.774 27.3003 332.649 + endloop + endfacet + facet normal -0.115936 -0.987146 0.110003 + outer loop + vertex -244.774 27.3003 332.649 + vertex -253.865 28.1657 330.833 + vertex -243.683 26.9306 330.481 + endloop + endfacet + facet normal -0.12034 -0.956367 0.266233 + outer loop + vertex -256.303 29.2656 334.57 + vertex -255.599 28.6367 332.629 + vertex -245.467 27.9089 334.594 + endloop + endfacet + facet normal -0.118862 -0.958891 0.25768 + outer loop + vertex -245.467 27.9089 334.594 + vertex -255.599 28.6367 332.629 + vertex -244.774 27.3003 332.649 + endloop + endfacet + facet normal -0.115935 -0.958963 0.258746 + outer loop + vertex -245.467 27.9089 334.594 + vertex -244.774 27.3003 332.649 + vertex -234.624 26.601 334.605 + endloop + endfacet + facet normal -0.114388 -0.961516 0.249805 + outer loop + vertex -234.624 26.601 334.605 + vertex -244.774 27.3003 332.649 + vertex -233.891 26.0057 332.65 + endloop + endfacet + facet normal -0.11742 -0.987056 0.10924 + outer loop + vertex -244.774 27.3003 332.649 + vertex -243.683 26.9306 330.481 + vertex -233.891 26.0057 332.65 + endloop + endfacet + facet normal -0.119356 -0.98575 0.11854 + outer loop + vertex -233.891 26.0057 332.65 + vertex -243.683 26.9306 330.481 + vertex -232.148 25.5771 330.84 + endloop + endfacet + facet normal -0.130955 -0.978475 0.159494 + outer loop + vertex -277.056 31.4433 332.598 + vertex -275.141 30.8898 330.775 + vertex -266.359 30.0117 332.598 + endloop + endfacet + facet normal -0.124785 -0.984008 0.12711 + outer loop + vertex -266.359 30.0117 332.598 + vertex -275.141 30.8898 330.775 + vertex -265.183 29.5844 330.445 + endloop + endfacet + facet normal -0.13114 -0.946623 0.29446 + outer loop + vertex -278.085 32.2305 334.67 + vertex -277.056 31.4433 332.598 + vertex -267.176 30.6878 334.569 + endloop + endfacet + facet normal -0.127576 -0.953209 0.274075 + outer loop + vertex -267.176 30.6878 334.569 + vertex -277.056 31.4433 332.598 + vertex -266.359 30.0117 332.598 + endloop + endfacet + facet normal -0.124691 -0.953243 0.275283 + outer loop + vertex -267.176 30.6878 334.569 + vertex -266.359 30.0117 332.598 + vertex -256.303 29.2656 334.57 + endloop + endfacet + facet normal -0.122954 -0.956304 0.265264 + outer loop + vertex -256.303 29.2656 334.57 + vertex -266.359 30.0117 332.598 + vertex -255.599 28.6367 332.629 + endloop + endfacet + facet normal -0.126091 -0.983935 0.126382 + outer loop + vertex -266.359 30.0117 332.598 + vertex -265.183 29.5844 330.445 + vertex -255.599 28.6367 332.629 + endloop + endfacet + facet normal -0.127789 -0.982654 0.134391 + outer loop + vertex -255.599 28.6367 332.629 + vertex -265.183 29.5844 330.445 + vertex -253.865 28.1657 330.833 + endloop + endfacet + facet normal -0.144471 -0.970274 0.194154 + outer loop + vertex -298.32 34.5725 332.783 + vertex -295.762 33.7959 330.806 + vertex -287.695 32.9687 332.674 + endloop + endfacet + facet normal -0.136847 -0.977935 0.157851 + outer loop + vertex -287.695 32.9687 332.674 + vertex -295.762 33.7959 330.806 + vertex -286.078 32.3769 330.409 + endloop + endfacet + facet normal -0.141395 -0.933007 0.330917 + outer loop + vertex -301.154 35.8287 335.114 + vertex -298.32 34.5725 332.783 + vertex -289.224 33.9605 334.944 + endloop + endfacet + facet normal -0.138398 -0.938346 0.316786 + outer loop + vertex -289.224 33.9605 334.944 + vertex -298.32 34.5725 332.783 + vertex -287.695 32.9687 332.674 + endloop + endfacet + facet normal -0.137944 -0.938314 0.317078 + outer loop + vertex -289.224 33.9605 334.944 + vertex -287.695 32.9687 332.674 + vertex -278.085 32.2305 334.67 + endloop + endfacet + facet normal -0.133632 -0.946655 0.293234 + outer loop + vertex -278.085 32.2305 334.67 + vertex -287.695 32.9687 332.674 + vertex -277.056 31.4433 332.598 + endloop + endfacet + facet normal -0.139089 -0.977878 0.156236 + outer loop + vertex -287.695 32.9687 332.674 + vertex -286.078 32.3769 330.409 + vertex -277.056 31.4433 332.598 + endloop + endfacet + facet normal -0.138145 -0.978678 0.152002 + outer loop + vertex -277.056 31.4433 332.598 + vertex -286.078 32.3769 330.409 + vertex -275.141 30.8898 330.775 + endloop + endfacet + facet normal -0.149872 -0.971818 0.181959 + outer loop + vertex -318.446 37.626 332.633 + vertex -315.458 36.8247 330.815 + vertex -308.765 36.1614 332.785 + endloop + endfacet + facet normal -0.147161 -0.974043 0.172 + outer loop + vertex -308.765 36.1614 332.785 + vertex -315.458 36.8247 330.815 + vertex -306.195 35.3626 330.46 + endloop + endfacet + facet normal -0.141346 -0.946664 0.289566 + outer loop + vertex -321.337 38.5324 334.185 + vertex -318.446 37.626 332.633 + vertex -312.732 37.4324 334.79 + endloop + endfacet + facet normal -0.147115 -0.940799 0.305376 + outer loop + vertex -312.732 37.4324 334.79 + vertex -318.446 37.626 332.633 + vertex -308.765 36.1614 332.785 + endloop + endfacet + facet normal -0.13878 -0.937313 0.319664 + outer loop + vertex -312.732 37.4324 334.79 + vertex -308.765 36.1614 332.785 + vertex -301.154 35.8287 335.114 + endloop + endfacet + facet normal -0.141879 -0.93312 0.330391 + outer loop + vertex -301.154 35.8287 335.114 + vertex -308.765 36.1614 332.785 + vertex -298.32 34.5725 332.783 + endloop + endfacet + facet normal -0.148145 -0.974083 0.170927 + outer loop + vertex -308.765 36.1614 332.785 + vertex -306.195 35.3626 330.46 + vertex -298.32 34.5725 332.783 + endloop + endfacet + facet normal -0.15192 -0.970965 0.184788 + outer loop + vertex -298.32 34.5725 332.783 + vertex -306.195 35.3626 330.46 + vertex -295.762 33.7959 330.806 + endloop + endfacet + facet normal -0.170129 -0.971698 0.163887 + outer loop + vertex -336.766 40.7127 332.481 + vertex -334.51 40.0052 330.628 + vertex -327.431 39.0868 332.531 + endloop + endfacet + facet normal -0.164368 -0.976385 0.1402 + outer loop + vertex -327.431 39.0868 332.531 + vertex -334.51 40.0052 330.628 + vertex -325.372 38.4273 330.352 + endloop + endfacet + facet normal -0.168328 -0.941128 0.293161 + outer loop + vertex -338.022 41.5624 334.488 + vertex -336.766 40.7127 332.481 + vertex -328.646 39.8771 334.461 + endloop + endfacet + facet normal -0.166085 -0.944807 0.282411 + outer loop + vertex -328.646 39.8771 334.461 + vertex -336.766 40.7127 332.481 + vertex -327.431 39.0868 332.531 + endloop + endfacet + facet normal -0.163107 -0.944768 0.28427 + outer loop + vertex -328.646 39.8771 334.461 + vertex -327.431 39.0868 332.531 + vertex -321.337 38.5324 334.185 + endloop + endfacet + facet normal -0.15776 -0.95205 0.26213 + outer loop + vertex -321.337 38.5324 334.185 + vertex -327.431 39.0868 332.531 + vertex -318.446 37.626 332.633 + endloop + endfacet + facet normal -0.160392 -0.976494 0.143991 + outer loop + vertex -327.431 39.0868 332.531 + vertex -325.372 38.4273 330.352 + vertex -318.446 37.626 332.633 + endloop + endfacet + facet normal -0.164754 -0.973554 0.15827 + outer loop + vertex -318.446 37.626 332.633 + vertex -325.372 38.4273 330.352 + vertex -315.458 36.8247 330.815 + endloop + endfacet + facet normal -0.181285 -0.96841 0.171226 + outer loop + vertex -357.276 44.4127 332.029 + vertex -354.898 43.6423 330.189 + vertex -346.85 42.5102 332.307 + endloop + endfacet + facet normal -0.175538 -0.973486 0.146669 + outer loop + vertex -346.85 42.5102 332.307 + vertex -354.898 43.6423 330.189 + vertex -345.073 41.8486 330.043 + endloop + endfacet + facet normal -0.181155 -0.936732 0.299525 + outer loop + vertex -358.767 45.3337 334.007 + vertex -357.276 44.4127 332.029 + vertex -348.183 43.3852 334.315 + endloop + endfacet + facet normal -0.179268 -0.939904 0.290592 + outer loop + vertex -348.183 43.3852 334.315 + vertex -357.276 44.4127 332.029 + vertex -346.85 42.5102 332.307 + endloop + endfacet + facet normal -0.173601 -0.93981 0.294313 + outer loop + vertex -348.183 43.3852 334.315 + vertex -346.85 42.5102 332.307 + vertex -338.022 41.5624 334.488 + endloop + endfacet + facet normal -0.17278 -0.941178 0.290397 + outer loop + vertex -338.022 41.5624 334.488 + vertex -346.85 42.5102 332.307 + vertex -336.766 40.7127 332.481 + endloop + endfacet + facet normal -0.176045 -0.973455 0.146262 + outer loop + vertex -346.85 42.5102 332.307 + vertex -345.073 41.8486 330.043 + vertex -336.766 40.7127 332.481 + endloop + endfacet + facet normal -0.178149 -0.97185 0.154179 + outer loop + vertex -336.766 40.7127 332.481 + vertex -345.073 41.8486 330.043 + vertex -334.51 40.0052 330.628 + endloop + endfacet + facet normal -0.195796 -0.961894 0.190852 + outer loop + vertex -377.563 48.3171 331.282 + vertex -375.566 47.5276 329.353 + vertex -367.879 46.4175 331.643 + endloop + endfacet + facet normal -0.189136 -0.967886 0.1656 + outer loop + vertex -367.879 46.4175 331.643 + vertex -375.566 47.5276 329.353 + vertex -365.062 45.5081 329.546 + endloop + endfacet + facet normal -0.19677 -0.93078 0.308107 + outer loop + vertex -379.082 49.252 333.137 + vertex -377.563 48.3171 331.282 + vertex -369.331 47.3482 333.613 + endloop + endfacet + facet normal -0.194421 -0.934468 0.298278 + outer loop + vertex -369.331 47.3482 333.613 + vertex -377.563 48.3171 331.282 + vertex -367.879 46.4175 331.643 + endloop + endfacet + facet normal -0.189446 -0.934333 0.301882 + outer loop + vertex -369.331 47.3482 333.613 + vertex -367.879 46.4175 331.643 + vertex -358.767 45.3337 334.007 + endloop + endfacet + facet normal -0.187866 -0.936979 0.294579 + outer loop + vertex -358.767 45.3337 334.007 + vertex -367.879 46.4175 331.643 + vertex -357.276 44.4127 332.029 + endloop + endfacet + facet normal -0.189024 -0.967883 0.165749 + outer loop + vertex -367.879 46.4175 331.643 + vertex -365.062 45.5081 329.546 + vertex -357.276 44.4127 332.029 + endloop + endfacet + facet normal -0.188094 -0.968613 0.162509 + outer loop + vertex -357.276 44.4127 332.029 + vertex -365.062 45.5081 329.546 + vertex -354.898 43.6423 330.189 + endloop + endfacet + facet normal -0.205986 -0.933538 0.29339 + outer loop + vertex -386.969 50.8277 332.613 + vertex -385.129 49.8306 330.732 + vertex -379.082 49.252 333.137 + endloop + endfacet + facet normal -0.208046 -0.93126 0.299118 + outer loop + vertex -379.082 49.252 333.137 + vertex -385.129 49.8306 330.732 + vertex -377.563 48.3171 331.282 + endloop + endfacet + facet normal -0.206618 -0.954161 0.216529 + outer loop + vertex -385.129 49.8306 330.732 + vertex -382.695 48.9831 329.32 + vertex -377.563 48.3171 331.282 + endloop + endfacet + facet normal -0.197235 -0.961894 0.189363 + outer loop + vertex -377.563 48.3171 331.282 + vertex -382.695 48.9831 329.32 + vertex -375.566 47.5276 329.353 + endloop + endfacet + facet normal -0.233803 -0.958551 0.162839 + outer loop + vertex -393.388 51.5751 330.182 + vertex -391.488 50.7818 328.241 + vertex -392.733 51.389 330.028 + endloop + endfacet + facet normal -0.199946 -0.9617 0.187497 + outer loop + vertex -392.733 51.389 330.028 + vertex -391.488 50.7818 328.241 + vertex -390.524 50.5464 328.061 + endloop + endfacet + facet normal -0.230186 -0.938613 0.256943 + outer loop + vertex -395.254 52.5771 332.171 + vertex -393.388 51.5751 330.182 + vertex -394.738 52.4009 331.99 + endloop + endfacet + facet normal -0.201071 -0.939044 0.278866 + outer loop + vertex -394.738 52.4009 331.99 + vertex -393.388 51.5751 330.182 + vertex -392.733 51.389 330.028 + endloop + endfacet + facet normal -0.213502 -0.939867 0.266586 + outer loop + vertex -394.738 52.4009 331.99 + vertex -392.733 51.389 330.028 + vertex -392.267 51.8929 332.177 + endloop + endfacet + facet normal -0.217669 -0.93873 0.267221 + outer loop + vertex -392.267 51.8929 332.177 + vertex -392.733 51.389 330.028 + vertex -390.276 50.8685 330.201 + endloop + endfacet + facet normal -0.215668 -0.96159 0.169799 + outer loop + vertex -392.733 51.389 330.028 + vertex -390.524 50.5464 328.061 + vertex -390.276 50.8685 330.201 + endloop + endfacet + facet normal -0.209326 -0.963081 0.169287 + outer loop + vertex -390.276 50.8685 330.201 + vertex -390.524 50.5464 328.061 + vertex -387.347 49.8639 328.107 + endloop + endfacet + facet normal 0.20768 0.933881 -0.291093 + outer loop + vertex -395.468 52.7668 332.627 + vertex -393.923 51.8019 330.634 + vertex -395.254 52.5771 332.171 + endloop + endfacet + facet normal 0.00523562 -0.891073 0.45383 + outer loop + vertex -395.254 52.5771 332.171 + vertex -393.923 51.8019 330.634 + vertex -393.388 51.5751 330.182 + endloop + endfacet + facet normal -0.263997 -0.950351 0.164736 + outer loop + vertex -393.923 51.8019 330.634 + vertex -392.749 51.1281 328.628 + vertex -393.388 51.5751 330.182 + endloop + endfacet + facet normal -0.204703 -0.959836 0.191864 + outer loop + vertex -393.388 51.5751 330.182 + vertex -392.749 51.1281 328.628 + vertex -391.488 50.7818 328.241 + endloop + endfacet + facet normal 0.194382 -0.98033 -0.0341792 + outer loop + vertex 385.282 49.3329 326.402 + vertex 384.596 49.2689 324.337 + vertex 389.568 50.1995 325.92 + endloop + endfacet + facet normal 0.181443 -0.983367 0.00822275 + outer loop + vertex 389.568 50.1995 325.92 + vertex 384.596 49.2689 324.337 + vertex 388.522 49.9948 324.522 + endloop + endfacet + facet normal 0.20519 -0.976645 0.0637254 + outer loop + vertex 387.36 49.9017 328.43 + vertex 385.282 49.3329 326.402 + vertex 391.013 50.6348 327.9 + endloop + endfacet + facet normal 0.204807 -0.97663 0.0651782 + outer loop + vertex 391.013 50.6348 327.9 + vertex 385.282 49.3329 326.402 + vertex 389.568 50.1995 325.92 + endloop + endfacet + facet normal 0.186007 -0.981925 -0.0349969 + outer loop + vertex 372.363 46.7967 327.841 + vertex 367.438 45.9564 325.242 + vertex 379.508 48.1848 326.872 + endloop + endfacet + facet normal 0.187411 -0.981185 -0.0464095 + outer loop + vertex 379.508 48.1848 326.872 + vertex 367.438 45.9564 325.242 + vertex 377.37 47.8903 324.465 + endloop + endfacet + facet normal 0.198922 -0.977831 0.0653947 + outer loop + vertex 377.984 48.058 329.601 + vertex 372.363 46.7967 327.841 + vertex 382.81 48.9959 328.944 + endloop + endfacet + facet normal 0.198874 -0.977813 0.0658135 + outer loop + vertex 382.81 48.9959 328.944 + vertex 372.363 46.7967 327.841 + vertex 379.508 48.1848 326.872 + endloop + endfacet + facet normal 0.201575 -0.977546 0.0614062 + outer loop + vertex 382.81 48.9959 328.944 + vertex 379.508 48.1848 326.872 + vertex 387.36 49.9017 328.43 + endloop + endfacet + facet normal 0.199971 -0.97735 0.0692698 + outer loop + vertex 387.36 49.9017 328.43 + vertex 379.508 48.1848 326.872 + vertex 385.282 49.3329 326.402 + endloop + endfacet + facet normal 0.190901 -0.980355 -0.049611 + outer loop + vertex 379.508 48.1848 326.872 + vertex 377.37 47.8903 324.465 + vertex 385.282 49.3329 326.402 + endloop + endfacet + facet normal 0.186772 -0.981895 -0.0316037 + outer loop + vertex 385.282 49.3329 326.402 + vertex 377.37 47.8903 324.465 + vertex 384.596 49.2689 324.337 + endloop + endfacet + facet normal 0.194434 -0.977679 0.0796172 + outer loop + vertex 377.984 48.058 329.601 + vertex 368.547 46.1761 329.539 + vertex 372.363 46.7967 327.841 + endloop + endfacet + facet normal 0.181704 -0.982996 -0.0264939 + outer loop + vertex 367.438 45.9564 325.242 + vertex 372.363 46.7967 327.841 + vertex 354.465 43.5072 327.143 + endloop + endfacet + facet normal 0.186119 -0.982527 0.000615368 + outer loop + vertex 359.276 44.4204 330.074 + vertex 354.465 43.5072 327.143 + vertex 368.547 46.1761 329.539 + endloop + endfacet + facet normal 0.178981 -0.982913 0.0429923 + outer loop + vertex 372.363 46.7967 327.841 + vertex 368.547 46.1761 329.539 + vertex 354.465 43.5072 327.143 + endloop + endfacet + facet normal 0.183169 -0.983065 0.00562467 + outer loop + vertex 359.276 44.4204 330.074 + vertex 348.407 42.3949 330.023 + vertex 354.465 43.5072 327.143 + endloop + endfacet + facet normal 0.1746 -0.984635 -0.00303667 + outer loop + vertex 339.197 40.7599 330.629 + vertex 333.513 39.7607 327.751 + vertex 348.407 42.3949 330.023 + endloop + endfacet + facet normal 0.175707 -0.984386 -0.0105857 + outer loop + vertex 333.513 39.7607 327.751 + vertex 354.465 43.5072 327.143 + vertex 348.407 42.3949 330.023 + endloop + endfacet + facet normal 0.172535 -0.985003 0.00117212 + outer loop + vertex 339.197 40.7599 330.629 + vertex 329.114 38.9934 330.352 + vertex 333.513 39.7607 327.751 + endloop + endfacet + facet normal 0.161681 -0.986839 -0.00269224 + outer loop + vertex 320.585 37.5949 330.734 + vertex 314.433 36.5947 327.938 + vertex 329.114 38.9934 330.352 + endloop + endfacet + facet normal 0.163547 -0.98643 -0.0144531 + outer loop + vertex 314.433 36.5947 327.938 + vertex 333.513 39.7607 327.751 + vertex 329.114 38.9934 330.352 + endloop + endfacet + facet normal 0.157541 -0.98749 0.00665077 + outer loop + vertex 320.585 37.5949 330.734 + vertex 310.346 35.9593 330.404 + vertex 314.433 36.5947 327.938 + endloop + endfacet + facet normal 0.146558 -0.989202 -0.00102517 + outer loop + vertex 301.297 34.6181 330.812 + vertex 295.089 33.7013 327.977 + vertex 310.346 35.9593 330.404 + endloop + endfacet + facet normal 0.147901 -0.988955 -0.00970074 + outer loop + vertex 295.089 33.7013 327.977 + vertex 314.433 36.5947 327.938 + vertex 310.346 35.9593 330.404 + endloop + endfacet + facet normal 0.143526 -0.98963 0.00574961 + outer loop + vertex 301.297 34.6181 330.812 + vertex 290.343 33.0276 330.481 + vertex 295.089 33.7013 327.977 + endloop + endfacet + facet normal 0.135531 -0.990614 -0.0177424 + outer loop + vertex 280.636 31.6926 330.868 + vertex 274.571 30.9139 328.014 + vertex 290.343 33.0276 330.481 + endloop + endfacet + facet normal 0.134587 -0.990835 -0.0115186 + outer loop + vertex 274.571 30.9139 328.014 + vertex 295.089 33.7013 327.977 + vertex 290.343 33.0276 330.481 + endloop + endfacet + facet normal 0.133795 -0.99091 -0.0139745 + outer loop + vertex 280.636 31.6926 330.868 + vertex 269.217 30.1558 330.513 + vertex 274.571 30.9139 328.014 + endloop + endfacet + facet normal 0.126192 -0.991136 -0.0415346 + outer loop + vertex 259.085 28.8501 330.886 + vertex 253.011 28.1964 328.03 + vertex 269.217 30.1558 330.513 + endloop + endfacet + facet normal 0.124959 -0.991609 -0.0331136 + outer loop + vertex 253.011 28.1964 328.03 + vertex 274.571 30.9139 328.014 + vertex 269.217 30.1558 330.513 + endloop + endfacet + facet normal 0.124729 -0.991449 -0.0383523 + outer loop + vertex 259.085 28.8501 330.886 + vertex 247.335 27.3866 330.505 + vertex 253.011 28.1964 328.03 + endloop + endfacet + facet normal 0.118042 -0.990901 -0.06466 + outer loop + vertex 237.038 26.1381 330.839 + vertex 231.108 25.6162 328.012 + vertex 247.335 27.3866 330.505 + endloop + endfacet + facet normal 0.116851 -0.991544 -0.0564527 + outer loop + vertex 231.108 25.6162 328.012 + vertex 253.011 28.1964 328.03 + vertex 247.335 27.3866 330.505 + endloop + endfacet + facet normal 0.115524 -0.991535 -0.0592624 + outer loop + vertex 237.038 26.1381 330.839 + vertex 225.466 24.8126 330.46 + vertex 231.108 25.6162 328.012 + endloop + endfacet + facet normal 0.106987 -0.991543 -0.073459 + outer loop + vertex 215.453 23.7056 330.818 + vertex 209.448 23.2662 328.004 + vertex 225.466 24.8126 330.46 + endloop + endfacet + facet normal 0.107568 -0.991174 -0.0774841 + outer loop + vertex 209.448 23.2662 328.004 + vertex 231.108 25.6162 328.012 + vertex 225.466 24.8126 330.46 + endloop + endfacet + facet normal 0.106411 -0.991697 -0.0722062 + outer loop + vertex 215.453 23.7056 330.818 + vertex 204.019 22.5048 330.46 + vertex 209.448 23.2662 328.004 + endloop + endfacet + facet normal 0.0984097 -0.99179 -0.081663 + outer loop + vertex 194.073 21.4882 330.821 + vertex 188.039 21.1221 327.995 + vertex 204.019 22.5048 330.46 + endloop + endfacet + facet normal 0.0992982 -0.99118 -0.0877653 + outer loop + vertex 188.039 21.1221 327.995 + vertex 209.448 23.2662 328.004 + vertex 204.019 22.5048 330.46 + endloop + endfacet + facet normal 0.0981165 -0.991871 -0.0810262 + outer loop + vertex 194.073 21.4882 330.821 + vertex 182.684 20.3919 330.451 + vertex 188.039 21.1221 327.995 + endloop + endfacet + facet normal 0.0896686 -0.99176 -0.0914991 + outer loop + vertex 172.809 19.4666 330.803 + vertex 166.748 19.1794 327.976 + vertex 182.684 20.3919 330.451 + endloop + endfacet + facet normal 0.0905288 -0.991124 -0.0973488 + outer loop + vertex 166.748 19.1794 327.976 + vertex 188.039 21.1221 327.995 + vertex 182.684 20.3919 330.451 + endloop + endfacet + facet normal 0.0886025 -0.992067 -0.089182 + outer loop + vertex 172.809 19.4666 330.803 + vertex 161.455 18.486 330.43 + vertex 166.748 19.1794 327.976 + endloop + endfacet + facet normal 0.0805238 -0.99195 -0.0977294 + outer loop + vertex 151.547 17.6472 330.781 + vertex 145.455 17.4316 327.949 + vertex 161.455 18.486 330.43 + endloop + endfacet + facet normal 0.0814904 -0.991204 -0.104281 + outer loop + vertex 145.455 17.4316 327.949 + vertex 166.748 19.1794 327.976 + vertex 161.455 18.486 330.43 + endloop + endfacet + facet normal 0.0774108 -0.992841 -0.090964 + outer loop + vertex 151.547 17.6472 330.781 + vertex 140.092 16.7881 330.409 + vertex 145.455 17.4316 327.949 + endloop + endfacet + facet normal 0.0701326 -0.992352 -0.101586 + outer loop + vertex 130.068 16.0435 330.762 + vertex 124.05 15.9083 327.929 + vertex 140.092 16.7881 330.409 + endloop + endfacet + facet normal 0.0706932 -0.991918 -0.105365 + outer loop + vertex 124.05 15.9083 327.929 + vertex 145.455 17.4316 327.949 + vertex 140.092 16.7881 330.409 + endloop + endfacet + facet normal 0.0663877 -0.993396 -0.0935816 + outer loop + vertex 130.068 16.0435 330.762 + vertex 118.561 15.3094 330.392 + vertex 124.05 15.9083 327.929 + endloop + endfacet + facet normal 0.0582173 -0.993078 -0.102013 + outer loop + vertex 108.516 14.6839 330.749 + vertex 102.629 14.6295 327.918 + vertex 118.561 15.3094 330.392 + endloop + endfacet + facet normal 0.059287 -0.992258 -0.109128 + outer loop + vertex 102.629 14.6295 327.918 + vertex 124.05 15.9083 327.929 + vertex 118.561 15.3094 330.392 + endloop + endfacet + facet normal 0.0544144 -0.994076 -0.0940852 + outer loop + vertex 108.516 14.6839 330.749 + vertex 97.104 14.0938 330.383 + vertex 102.629 14.6295 327.918 + endloop + endfacet + facet normal 0.0459517 -0.994184 -0.0974009 + outer loop + vertex 87.1843 13.5999 330.744 + vertex 81.3491 13.6074 327.915 + vertex 97.104 14.0938 330.383 + endloop + endfacet + facet normal 0.0477083 -0.992911 -0.108862 + outer loop + vertex 81.3491 13.6074 327.915 + vertex 102.629 14.6295 327.918 + vertex 97.104 14.0938 330.383 + endloop + endfacet + facet normal 0.0424866 -0.995012 -0.0902574 + outer loop + vertex 87.1843 13.5999 330.744 + vertex 75.8883 13.1503 330.384 + vertex 81.3491 13.6074 327.915 + endloop + endfacet + facet normal 0.0334468 -0.995289 -0.0909989 + outer loop + vertex 66.0015 12.7846 330.75 + vertex 60.1524 12.8466 327.922 + vertex 75.8883 13.1503 330.384 + endloop + endfacet + facet normal 0.0356375 -0.993814 -0.105181 + outer loop + vertex 60.1524 12.8466 327.922 + vertex 81.3491 13.6074 327.915 + vertex 75.8883 13.1503 330.384 + endloop + endfacet + facet normal 0.0306838 -0.995883 -0.0852969 + outer loop + vertex 66.0015 12.7846 330.75 + vertex 54.5975 12.4638 330.393 + vertex 60.1524 12.8466 327.922 + endloop + endfacet + facet normal 0.0225057 -0.99585 -0.0881871 + outer loop + vertex 44.5576 12.2044 330.76 + vertex 38.9078 12.327 327.934 + vertex 54.5975 12.4638 330.393 + endloop + endfacet + facet normal 0.0242738 -0.994738 -0.0995305 + outer loop + vertex 38.9078 12.327 327.934 + vertex 60.1524 12.8466 327.922 + vertex 54.5975 12.4638 330.393 + endloop + endfacet + facet normal 0.0204898 -0.99624 -0.0841736 + outer loop + vertex 44.5576 12.2044 330.76 + vertex 33.1806 12.0006 330.403 + vertex 38.9078 12.327 327.934 + endloop + endfacet + facet normal 0.0115162 -0.996319 -0.084941 + outer loop + vertex 23.2856 11.855 330.769 + vertex 17.7887 12.0324 327.942 + vertex 33.1806 12.0006 330.403 + endloop + endfacet + facet normal 0.0138361 -0.994948 -0.0994361 + outer loop + vertex 17.7887 12.0324 327.942 + vertex 38.9078 12.327 327.934 + vertex 33.1806 12.0006 330.403 + endloop + endfacet + facet normal 0.00938929 -0.996684 -0.0808276 + outer loop + vertex 23.2856 11.855 330.769 + vertex 12.141 11.779 330.411 + vertex 17.7887 12.0324 327.942 + endloop + endfacet + facet normal 0.00177953 -0.996404 -0.0847145 + outer loop + vertex 2.35929 11.7308 330.773 + vertex -3.17229 11.9614 327.944 + vertex 12.141 11.779 330.411 + endloop + endfacet + facet normal 0.00336481 -0.99552 -0.0944918 + outer loop + vertex -3.17229 11.9614 327.944 + vertex 17.7887 12.0324 327.942 + vertex 12.141 11.779 330.411 + endloop + endfacet + facet normal 2.12061e-05 -0.99669 -0.0812994 + outer loop + vertex 2.35929 11.7308 330.773 + vertex -8.82011 11.7601 330.41 + vertex -3.17229 11.9614 327.944 + endloop + endfacet + facet normal -0.00829581 -0.996261 -0.085991 + outer loop + vertex -18.6775 11.8111 330.77 + vertex -24.2031 12.1016 327.938 + vertex -8.82011 11.7601 330.41 + endloop + endfacet + facet normal -0.00660716 -0.995324 -0.0963713 + outer loop + vertex -24.2031 12.1016 327.938 + vertex -3.17229 11.9614 327.944 + vertex -8.82011 11.7601 330.41 + endloop + endfacet + facet normal -0.00999091 -0.996524 -0.08271 + outer loop + vertex -18.6775 11.8111 330.77 + vertex -29.9136 11.9542 330.404 + vertex -24.2031 12.1016 327.938 + endloop + endfacet + facet normal -0.018676 -0.995882 -0.0887111 + outer loop + vertex -39.8422 12.1085 330.762 + vertex -45.3838 12.4648 327.928 + vertex -29.9136 11.9542 330.404 + endloop + endfacet + facet normal -0.0170166 -0.994953 -0.0988902 + outer loop + vertex -45.3838 12.4648 327.928 + vertex -24.2031 12.1016 327.938 + vertex -29.9136 11.9542 330.404 + endloop + endfacet + facet normal -0.0203894 -0.996139 -0.085392 + outer loop + vertex -39.8422 12.1085 330.762 + vertex -51.2383 12.3733 330.394 + vertex -45.3838 12.4648 327.928 + endloop + endfacet + facet normal -0.029011 -0.995231 -0.093127 + outer loop + vertex -61.373 12.6353 330.751 + vertex -66.7212 13.0564 327.917 + vertex -51.2383 12.3733 330.394 + endloop + endfacet + facet normal -0.0275142 -0.994378 -0.102247 + outer loop + vertex -66.7212 13.0564 327.917 + vertex -45.3838 12.4648 327.928 + vertex -51.2383 12.3733 330.394 + endloop + endfacet + facet normal -0.0325041 -0.995712 -0.0866082 + outer loop + vertex -61.373 12.6353 330.751 + vertex -72.7841 13.0396 330.386 + vertex -66.7212 13.0564 327.917 + endloop + endfacet + facet normal -0.0401123 -0.99435 -0.0982809 + outer loop + vertex -82.8073 13.4084 330.745 + vertex -87.9543 13.8959 327.914 + vertex -72.7841 13.0396 330.386 + endloop + endfacet + facet normal -0.0392791 -0.993882 -0.103231 + outer loop + vertex -87.9543 13.8959 327.914 + vertex -66.7212 13.0564 327.917 + vertex -72.7841 13.0396 330.386 + endloop + endfacet + facet normal -0.0440137 -0.994853 -0.0912754 + outer loop + vertex -82.8073 13.4084 330.745 + vertex -93.9239 13.9334 330.383 + vertex -87.9543 13.8959 327.914 + endloop + endfacet + facet normal -0.0526922 -0.993628 -0.099637 + outer loop + vertex -103.732 14.417 330.747 + vertex -108.94 14.9767 327.92 + vertex -93.9239 13.9334 330.383 + endloop + endfacet + facet normal -0.0511639 -0.992769 -0.108592 + outer loop + vertex -108.94 14.9767 327.92 + vertex -87.9543 13.8959 327.914 + vertex -93.9239 13.9334 330.383 + endloop + endfacet + facet normal -0.056355 -0.994072 -0.0929765 + outer loop + vertex -103.732 14.417 330.747 + vertex -114.871 15.0819 330.39 + vertex -108.94 14.9767 327.92 + endloop + endfacet + facet normal -0.0653165 -0.99324 -0.0959581 + outer loop + vertex -124.826 15.7009 330.759 + vertex -129.983 16.3126 327.938 + vertex -114.871 15.0819 330.39 + endloop + endfacet + facet normal -0.0630704 -0.992018 -0.109188 + outer loop + vertex -129.983 16.3126 327.938 + vertex -108.94 14.9767 327.92 + vertex -114.871 15.0819 330.39 + endloop + endfacet + facet normal -0.0669126 -0.993408 -0.0930759 + outer loop + vertex -124.826 15.7009 330.759 + vertex -136.089 16.4926 330.406 + vertex -129.983 16.3126 327.938 + endloop + endfacet + facet normal -0.0763113 -0.992611 -0.0943374 + outer loop + vertex -146.055 17.2235 330.777 + vertex -151.144 17.8825 327.961 + vertex -136.089 16.4926 330.406 + endloop + endfacet + facet normal -0.0736523 -0.991209 -0.10991 + outer loop + vertex -151.144 17.8825 327.961 + vertex -129.983 16.3126 327.938 + vertex -136.089 16.4926 330.406 + endloop + endfacet + facet normal -0.078125 -0.992773 -0.0910976 + outer loop + vertex -146.055 17.2235 330.777 + vertex -157.228 18.135 330.427 + vertex -151.144 17.8825 327.961 + endloop + endfacet + facet normal -0.0869411 -0.992222 -0.0890839 + outer loop + vertex -167.179 18.9735 330.798 + vertex -172.443 19.6871 327.987 + vertex -157.228 18.135 330.427 + endloop + endfacet + facet normal -0.0840842 -0.990805 -0.106001 + outer loop + vertex -172.443 19.6871 327.987 + vertex -151.144 17.8825 327.961 + vertex -157.228 18.135 330.427 + endloop + endfacet + facet normal -0.088065 -0.992308 -0.0870005 + outer loop + vertex -167.179 18.9735 330.798 + vertex -178.547 20.0132 330.448 + vertex -172.443 19.6871 327.987 + endloop + endfacet + facet normal -0.0963029 -0.992231 -0.0787613 + outer loop + vertex -188.724 20.9716 330.816 + vertex -194.061 21.7125 328.008 + vertex -178.547 20.0132 330.448 + endloop + endfacet + facet normal -0.0929152 -0.990715 -0.0992464 + outer loop + vertex -194.061 21.7125 328.008 + vertex -172.443 19.6871 327.987 + vertex -178.547 20.0132 330.448 + endloop + endfacet + facet normal -0.0968121 -0.992257 -0.0778008 + outer loop + vertex -188.724 20.9716 330.816 + vertex -200.254 22.1242 330.464 + vertex -194.061 21.7125 328.008 + endloop + endfacet + facet normal -0.104961 -0.992247 -0.0665531 + outer loop + vertex -210.45 23.1783 330.829 + vertex -215.863 23.9392 328.022 + vertex -200.254 22.1242 330.464 + endloop + endfacet + facet normal -0.101251 -0.990851 -0.0892313 + outer loop + vertex -215.863 23.9392 328.022 + vertex -194.061 21.7125 328.008 + vertex -200.254 22.1242 330.464 + endloop + endfacet + facet normal -0.105802 -0.992265 -0.0649367 + outer loop + vertex -210.45 23.1783 330.829 + vertex -221.957 24.4284 330.474 + vertex -215.863 23.9392 328.022 + endloop + endfacet + facet normal -0.113526 -0.992444 -0.0465561 + outer loop + vertex -232.148 25.5771 330.84 + vertex -237.601 26.333 328.023 + vertex -221.957 24.4284 330.474 + endloop + endfacet + facet normal -0.109167 -0.991303 -0.0734911 + outer loop + vertex -237.601 26.333 328.023 + vertex -215.863 23.9392 328.022 + vertex -221.957 24.4284 330.474 + endloop + endfacet + facet normal -0.115102 -0.992401 -0.0434942 + outer loop + vertex -232.148 25.5771 330.84 + vertex -243.683 26.9306 330.481 + vertex -237.601 26.333 328.023 + endloop + endfacet + facet normal -0.121433 -0.992096 -0.0316204 + outer loop + vertex -253.865 28.1657 330.833 + vertex -259.074 28.8933 328.012 + vertex -243.683 26.9306 330.481 + endloop + endfacet + facet normal -0.118209 -0.99166 -0.0513596 + outer loop + vertex -259.074 28.8933 328.012 + vertex -237.601 26.333 328.023 + vertex -243.683 26.9306 330.481 + endloop + endfacet + facet normal -0.123388 -0.991964 -0.0279761 + outer loop + vertex -253.865 28.1657 330.833 + vertex -265.183 29.5844 330.445 + vertex -259.074 28.8933 328.012 + endloop + endfacet + facet normal -0.130569 -0.991261 -0.0188182 + outer loop + vertex -275.141 30.8898 330.775 + vertex -279.896 31.5694 327.969 + vertex -265.183 29.5844 330.445 + endloop + endfacet + facet normal -0.127313 -0.991132 -0.038063 + outer loop + vertex -279.896 31.5694 327.969 + vertex -259.074 28.8933 328.012 + vertex -265.183 29.5844 330.445 + endloop + endfacet + facet normal -0.134304 -0.990863 -0.0123917 + outer loop + vertex -275.141 30.8898 330.775 + vertex -286.078 32.3769 330.409 + vertex -279.896 31.5694 327.969 + endloop + endfacet + facet normal -0.144867 -0.989446 0.00305368 + outer loop + vertex -295.762 33.7959 330.806 + vertex -299.835 34.3834 327.936 + vertex -286.078 32.3769 330.409 + endloop + endfacet + facet normal -0.139653 -0.989852 -0.0262792 + outer loop + vertex -299.835 34.3834 327.936 + vertex -279.896 31.5694 327.969 + vertex -286.078 32.3769 330.409 + endloop + endfacet + facet normal -0.148772 -0.988833 0.00872217 + outer loop + vertex -295.762 33.7959 330.806 + vertex -306.195 35.3626 330.46 + vertex -299.835 34.3834 327.936 + endloop + endfacet + facet normal -0.155723 -0.987787 0.00527234 + outer loop + vertex -315.458 36.8247 330.815 + vertex -318.978 37.3639 327.862 + vertex -306.195 35.3626 330.46 + endloop + endfacet + facet normal -0.153824 -0.988089 -0.00429841 + outer loop + vertex -318.978 37.3639 327.862 + vertex -299.835 34.3834 327.936 + vertex -306.195 35.3626 330.46 + endloop + endfacet + facet normal -0.16004 -0.987054 0.0105528 + outer loop + vertex -315.458 36.8247 330.815 + vertex -325.372 38.4273 330.352 + vertex -318.978 37.3639 327.862 + endloop + endfacet + facet normal -0.169893 -0.985422 0.00890571 + outer loop + vertex -334.51 40.0052 330.628 + vertex -338.066 40.5909 327.601 + vertex -325.372 38.4273 330.352 + endloop + endfacet + facet normal -0.166601 -0.986001 -0.00673999 + outer loop + vertex -338.066 40.5909 327.601 + vertex -318.978 37.3639 327.862 + vertex -325.372 38.4273 330.352 + endloop + endfacet + facet normal -0.172557 -0.984925 0.0121315 + outer loop + vertex -334.51 40.0052 330.628 + vertex -345.073 41.8486 330.043 + vertex -338.066 40.5909 327.601 + endloop + endfacet + facet normal -0.179363 -0.983667 0.0151187 + outer loop + vertex -354.898 43.6423 330.189 + vertex -358.336 44.2205 327.016 + vertex -345.073 41.8486 330.043 + endloop + endfacet + facet normal -0.176289 -0.984338 0.00112056 + outer loop + vertex -358.336 44.2205 327.016 + vertex -338.066 40.5909 327.601 + vertex -345.073 41.8486 330.043 + endloop + endfacet + facet normal -0.189544 -0.979876 0.0625834 + outer loop + vertex -375.566 47.5276 329.353 + vertex -372.35 46.7662 327.171 + vertex -365.062 45.5081 329.546 + endloop + endfacet + facet normal -0.181603 -0.983214 0.017628 + outer loop + vertex -354.898 43.6423 330.189 + vertex -365.062 45.5081 329.546 + vertex -358.336 44.2205 327.016 + endloop + endfacet + facet normal -0.178921 -0.983621 -0.0218313 + outer loop + vertex -369.703 46.324 325.407 + vertex -358.336 44.2205 327.016 + vertex -372.35 46.7662 327.171 + endloop + endfacet + facet normal -0.178387 -0.983607 0.0263775 + outer loop + vertex -365.062 45.5081 329.546 + vertex -372.35 46.7662 327.171 + vertex -358.336 44.2205 327.016 + endloop + endfacet + facet normal -0.199714 -0.976443 0.0816942 + outer loop + vertex -382.695 48.9831 329.32 + vertex -381.366 48.5446 327.328 + vertex -375.566 47.5276 329.353 + endloop + endfacet + facet normal -0.1922 -0.979606 0.0585748 + outer loop + vertex -375.566 47.5276 329.353 + vertex -381.366 48.5446 327.328 + vertex -372.35 46.7662 327.171 + endloop + endfacet + facet normal -0.194028 -0.980203 -0.0394254 + outer loop + vertex -381.366 48.5446 327.328 + vertex -377.465 47.8753 324.767 + vertex -372.35 46.7662 327.171 + endloop + endfacet + facet normal -0.192427 -0.980373 -0.0429107 + outer loop + vertex -372.35 46.7662 327.171 + vertex -377.465 47.8753 324.767 + vertex -369.703 46.324 325.407 + endloop + endfacet + facet normal -0.207616 -0.977256 -0.0432059 + outer loop + vertex -389.434 50.1706 326.307 + vertex -387.173 49.7861 324.14 + vertex -388.021 49.8862 325.947 + endloop + endfacet + facet normal -0.172551 -0.984648 -0.0263549 + outer loop + vertex -388.021 49.8862 325.947 + vertex -387.173 49.7861 324.14 + vertex -384.494 49.3283 323.701 + endloop + endfacet + facet normal -0.224681 -0.972015 0.0685895 + outer loop + vertex -391.488 50.7818 328.241 + vertex -389.434 50.1706 326.307 + vertex -390.524 50.5464 328.061 + endloop + endfacet + facet normal -0.1707 -0.979839 0.103816 + outer loop + vertex -390.524 50.5464 328.061 + vertex -389.434 50.1706 326.307 + vertex -388.021 49.8862 325.947 + endloop + endfacet + facet normal -0.210474 -0.976022 0.0555226 + outer loop + vertex -390.524 50.5464 328.061 + vertex -388.021 49.8862 325.947 + vertex -387.347 49.8639 328.107 + endloop + endfacet + facet normal -0.193156 -0.979889 0.0500848 + outer loop + vertex -387.347 49.8639 328.107 + vertex -388.021 49.8862 325.947 + vertex -384.784 49.2287 325.563 + endloop + endfacet + facet normal -0.208025 -0.974459 -0.0845891 + outer loop + vertex -388.021 49.8862 325.947 + vertex -384.494 49.3283 323.701 + vertex -384.784 49.2287 325.563 + endloop + endfacet + facet normal -0.197293 -0.976821 -0.083042 + outer loop + vertex -384.784 49.2287 325.563 + vertex -384.494 49.3283 323.701 + vertex -382.15 48.8437 323.833 + endloop + endfacet + facet normal -0.241882 -0.967227 0.0772298 + outer loop + vertex -392.749 51.1281 328.628 + vertex -391.121 50.5611 326.626 + vertex -391.488 50.7818 328.241 + endloop + endfacet + facet normal -0.209307 -0.974099 0.0855703 + outer loop + vertex -391.488 50.7818 328.241 + vertex -391.121 50.5611 326.626 + vertex -389.434 50.1706 326.307 + endloop + endfacet + facet normal -0.227496 -0.973717 -0.0109607 + outer loop + vertex -391.121 50.5611 326.626 + vertex -389.126 50.1146 324.899 + vertex -389.434 50.1706 326.307 + endloop + endfacet + facet normal -0.164609 -0.986353 0.00327505 + outer loop + vertex -389.434 50.1706 326.307 + vertex -389.126 50.1146 324.899 + vertex -387.173 49.7861 324.14 + endloop + endfacet + facet normal 0.182398 -0.970607 -0.157012 + outer loop + vertex 384.596 49.2689 324.337 + vertex 377.37 47.8903 324.465 + vertex 377.951 48.5076 321.324 + endloop + endfacet + facet normal 0.179413 -0.97479 -0.132647 + outer loop + vertex 367.438 45.9564 325.242 + vertex 366.203 46.1182 322.383 + vertex 377.37 47.8903 324.465 + endloop + endfacet + facet normal 0.183236 -0.970478 -0.156832 + outer loop + vertex 366.203 46.1182 322.383 + vertex 377.951 48.5076 321.324 + vertex 377.37 47.8903 324.465 + endloop + endfacet + facet normal 0.170345 -0.980249 -0.10047 + outer loop + vertex 354.465 43.5072 327.143 + vertex 351.389 43.4079 322.896 + vertex 367.438 45.9564 325.242 + endloop + endfacet + facet normal 0.174057 -0.976063 -0.130405 + outer loop + vertex 367.438 45.9564 325.242 + vertex 351.389 43.4079 322.896 + vertex 366.203 46.1182 322.383 + endloop + endfacet + facet normal 0.171586 -0.978374 -0.115507 + outer loop + vertex 333.513 39.7607 327.751 + vertex 334.085 40.3158 323.899 + vertex 354.465 43.5072 327.143 + endloop + endfacet + facet normal 0.169415 -0.98048 -0.0997907 + outer loop + vertex 354.465 43.5072 327.143 + vertex 334.085 40.3158 323.899 + vertex 351.389 43.4079 322.896 + endloop + endfacet + facet normal 0.161321 -0.979346 -0.121887 + outer loop + vertex 314.433 36.5947 327.938 + vertex 315.115 37.1586 324.31 + vertex 333.513 39.7607 327.751 + endloop + endfacet + facet normal 0.160573 -0.98002 -0.117379 + outer loop + vertex 333.513 39.7607 327.751 + vertex 315.115 37.1586 324.31 + vertex 334.085 40.3158 323.899 + endloop + endfacet + facet normal 0.146486 -0.981053 -0.126793 + outer loop + vertex 295.089 33.7013 327.977 + vertex 295.932 34.2891 324.403 + vertex 314.433 36.5947 327.938 + endloop + endfacet + facet normal 0.146184 -0.981323 -0.125041 + outer loop + vertex 314.433 36.5947 327.938 + vertex 295.932 34.2891 324.403 + vertex 315.115 37.1586 324.31 + endloop + endfacet + facet normal 0.133052 -0.981234 -0.139562 + outer loop + vertex 274.571 30.9139 328.014 + vertex 275.871 31.6038 324.403 + vertex 295.089 33.7013 327.977 + endloop + endfacet + facet normal 0.13154 -0.982672 -0.130588 + outer loop + vertex 295.089 33.7013 327.977 + vertex 275.871 31.6038 324.403 + vertex 295.932 34.2891 324.403 + endloop + endfacet + facet normal 0.123324 -0.979396 -0.159923 + outer loop + vertex 253.011 28.1964 328.03 + vertex 254.767 29.0099 324.402 + vertex 274.571 30.9139 328.014 + endloop + endfacet + facet normal 0.120719 -0.98216 -0.144181 + outer loop + vertex 274.571 30.9139 328.014 + vertex 254.767 29.0099 324.402 + vertex 275.871 31.6038 324.403 + endloop + endfacet + facet normal 0.115147 -0.976216 -0.183692 + outer loop + vertex 231.108 25.6162 328.012 + vertex 233.047 26.5238 324.405 + vertex 253.011 28.1964 328.03 + endloop + endfacet + facet normal 0.112134 -0.979825 -0.165437 + outer loop + vertex 253.011 28.1964 328.03 + vertex 233.047 26.5238 324.405 + vertex 254.767 29.0099 324.402 + endloop + endfacet + facet normal 0.105799 -0.974421 -0.198266 + outer loop + vertex 209.448 23.2662 328.004 + vertex 211.304 24.2008 324.401 + vertex 231.108 25.6162 328.012 + endloop + endfacet + facet normal 0.10434 -0.976316 -0.189526 + outer loop + vertex 231.108 25.6162 328.012 + vertex 211.304 24.2008 324.401 + vertex 233.047 26.5238 324.405 + endloop + endfacet + facet normal 0.0974923 -0.972665 -0.210754 + outer loop + vertex 188.039 21.1221 327.995 + vertex 189.779 22.0772 324.392 + vertex 209.448 23.2662 328.004 + endloop + endfacet + facet normal 0.0962099 -0.974399 -0.203199 + outer loop + vertex 209.448 23.2662 328.004 + vertex 189.779 22.0772 324.392 + vertex 211.304 24.2008 324.401 + endloop + endfacet + facet normal 0.0889525 -0.972677 -0.214447 + outer loop + vertex 166.748 19.1794 327.976 + vertex 168.457 20.132 324.364 + vertex 188.039 21.1221 327.995 + endloop + endfacet + facet normal 0.0890181 -0.972587 -0.214825 + outer loop + vertex 188.039 21.1221 327.995 + vertex 168.457 20.132 324.364 + vertex 189.779 22.0772 324.392 + endloop + endfacet + facet normal 0.0800986 -0.972498 -0.218705 + outer loop + vertex 145.455 17.4316 327.949 + vertex 147.182 18.3869 324.334 + vertex 166.748 19.1794 327.976 + endloop + endfacet + facet normal 0.0800809 -0.972522 -0.218605 + outer loop + vertex 166.748 19.1794 327.976 + vertex 147.182 18.3869 324.334 + vertex 168.457 20.132 324.364 + endloop + endfacet + facet normal 0.0694769 -0.973304 -0.218754 + outer loop + vertex 124.05 15.9083 327.929 + vertex 125.885 16.8532 324.307 + vertex 145.455 17.4316 327.949 + endloop + endfacet + facet normal 0.0702932 -0.972209 -0.223314 + outer loop + vertex 145.455 17.4316 327.949 + vertex 125.885 16.8532 324.307 + vertex 147.182 18.3869 324.334 + endloop + endfacet + facet normal 0.05828 -0.974487 -0.216744 + outer loop + vertex 102.629 14.6295 327.918 + vertex 104.579 15.5529 324.291 + vertex 124.05 15.9083 327.929 + endloop + endfacet + facet normal 0.0595437 -0.972845 -0.223668 + outer loop + vertex 124.05 15.9083 327.929 + vertex 104.579 15.5529 324.291 + vertex 125.885 16.8532 324.307 + endloop + endfacet + facet normal 0.0469015 -0.975764 -0.213742 + outer loop + vertex 81.3491 13.6074 327.915 + vertex 83.3443 14.4985 324.285 + vertex 102.629 14.6295 327.918 + endloop + endfacet + facet normal 0.0484227 -0.97387 -0.221885 + outer loop + vertex 102.629 14.6295 327.918 + vertex 83.3443 14.4985 324.285 + vertex 104.579 15.5529 324.291 + endloop + endfacet + facet normal 0.0349803 -0.976517 -0.212583 + outer loop + vertex 60.1524 12.8466 327.922 + vertex 62.1955 13.7093 324.295 + vertex 81.3491 13.6074 327.915 + endloop + endfacet + facet normal 0.0362744 -0.974963 -0.219387 + outer loop + vertex 81.3491 13.6074 327.915 + vertex 62.1955 13.7093 324.295 + vertex 83.3443 14.4985 324.285 + endloop + endfacet + facet normal 0.02378 -0.977119 -0.21136 + outer loop + vertex 38.9078 12.327 327.934 + vertex 41.1115 13.1642 324.311 + vertex 60.1524 12.8466 327.922 + endloop + endfacet + facet normal 0.0250568 -0.975635 -0.217964 + outer loop + vertex 60.1524 12.8466 327.922 + vertex 41.1115 13.1642 324.311 + vertex 62.1955 13.7093 324.295 + endloop + endfacet + facet normal 0.0135541 -0.977912 -0.208576 + outer loop + vertex 17.7887 12.0324 327.942 + vertex 20.1119 12.8375 324.318 + vertex 38.9078 12.327 327.934 + endloop + endfacet + facet normal 0.0151095 -0.976184 -0.216419 + outer loop + vertex 38.9078 12.327 327.934 + vertex 20.1119 12.8375 324.318 + vertex 41.1115 13.1642 324.311 + endloop + endfacet + facet normal 0.00329391 -0.977944 -0.20884 + outer loop + vertex -3.17229 11.9614 327.944 + vertex -0.835017 12.7425 324.323 + vertex 17.7887 12.0324 327.942 + endloop + endfacet + facet normal 0.00438088 -0.976779 -0.214205 + outer loop + vertex 17.7887 12.0324 327.942 + vertex -0.835017 12.7425 324.323 + vertex 20.1119 12.8375 324.318 + endloop + endfacet + facet normal -0.00646004 -0.978071 -0.20817 + outer loop + vertex -24.2031 12.1016 327.938 + vertex -21.7908 12.857 324.314 + vertex -3.17229 11.9614 327.944 + endloop + endfacet + facet normal -0.00524196 -0.976797 -0.214103 + outer loop + vertex -3.17229 11.9614 327.944 + vertex -21.7908 12.857 324.314 + vertex -0.835017 12.7425 324.323 + endloop + endfacet + facet normal -0.0166677 -0.97763 -0.209672 + outer loop + vertex -45.3838 12.4648 327.928 + vertex -42.865 13.1996 324.302 + vertex -24.2031 12.1016 327.938 + endloop + endfacet + facet normal -0.0157556 -0.976691 -0.214069 + outer loop + vertex -24.2031 12.1016 327.938 + vertex -42.865 13.1996 324.302 + vertex -21.7908 12.857 324.314 + endloop + endfacet + facet normal -0.0269556 -0.976461 -0.214004 + outer loop + vertex -66.7212 13.0564 327.917 + vertex -64.0271 13.7764 324.292 + vertex -45.3838 12.4648 327.928 + endloop + endfacet + facet normal -0.0265003 -0.975996 -0.21617 + outer loop + vertex -45.3838 12.4648 327.928 + vertex -64.0271 13.7764 324.292 + vertex -42.865 13.1996 324.302 + endloop + endfacet + facet normal -0.038554 -0.975946 -0.214579 + outer loop + vertex -87.9543 13.8959 327.914 + vertex -85.1413 14.5826 324.285 + vertex -66.7212 13.0564 327.917 + endloop + endfacet + facet normal -0.0371338 -0.974525 -0.221185 + outer loop + vertex -66.7212 13.0564 327.917 + vertex -85.1413 14.5826 324.285 + vertex -64.0271 13.7764 324.292 + endloop + endfacet + facet normal -0.0502913 -0.975161 -0.215714 + outer loop + vertex -108.94 14.9767 327.92 + vertex -106.123 15.6341 324.291 + vertex -87.9543 13.8959 327.914 + endloop + endfacet + facet normal -0.0488727 -0.973783 -0.222168 + outer loop + vertex -87.9543 13.8959 327.914 + vertex -106.123 15.6341 324.291 + vertex -85.1413 14.5826 324.285 + endloop + endfacet + facet normal -0.0620296 -0.974173 -0.217118 + outer loop + vertex -129.983 16.3126 327.938 + vertex -127.069 16.9347 324.314 + vertex -108.94 14.9767 327.92 + endloop + endfacet + facet normal -0.0606499 -0.972853 -0.223337 + outer loop + vertex -108.94 14.9767 327.92 + vertex -127.069 16.9347 324.314 + vertex -106.123 15.6341 324.291 + endloop + endfacet + facet normal -0.0724262 -0.973131 -0.218567 + outer loop + vertex -151.144 17.8825 327.961 + vertex -148.145 18.4712 324.346 + vertex -129.983 16.3126 327.938 + endloop + endfacet + facet normal -0.0711913 -0.971961 -0.224106 + outer loop + vertex -129.983 16.3126 327.938 + vertex -148.145 18.4712 324.346 + vertex -127.069 16.9347 324.314 + endloop + endfacet + facet normal -0.0827648 -0.973648 -0.212506 + outer loop + vertex -172.443 19.6871 327.987 + vertex -169.442 20.2206 324.374 + vertex -151.144 17.8825 327.961 + endloop + endfacet + facet normal -0.0800775 -0.971157 -0.224593 + outer loop + vertex -151.144 17.8825 327.961 + vertex -169.442 20.2206 324.374 + vertex -148.145 18.4712 324.346 + endloop + endfacet + facet normal -0.0915047 -0.974593 -0.204438 + outer loop + vertex -194.061 21.7125 328.008 + vertex -191.077 22.1889 324.401 + vertex -172.443 19.6871 327.987 + endloop + endfacet + facet normal -0.0887095 -0.972085 -0.217212 + outer loop + vertex -172.443 19.6871 327.987 + vertex -191.077 22.1889 324.401 + vertex -169.442 20.2206 324.374 + endloop + endfacet + facet normal -0.0998642 -0.976662 -0.190156 + outer loop + vertex -215.863 23.9392 328.022 + vertex -212.955 24.3441 324.415 + vertex -194.061 21.7125 328.008 + endloop + endfacet + facet normal -0.0960146 -0.973403 -0.208011 + outer loop + vertex -194.061 21.7125 328.008 + vertex -212.955 24.3441 324.415 + vertex -191.077 22.1889 324.401 + endloop + endfacet + facet normal -0.107822 -0.979037 -0.172803 + outer loop + vertex -237.601 26.333 328.023 + vertex -234.786 26.6596 324.415 + vertex -215.863 23.9392 328.022 + endloop + endfacet + facet normal -0.1035 -0.975728 -0.192983 + outer loop + vertex -215.863 23.9392 328.022 + vertex -234.786 26.6596 324.415 + vertex -212.955 24.3441 324.415 + endloop + endfacet + facet normal -0.116917 -0.981259 -0.153172 + outer loop + vertex -259.074 28.8933 328.012 + vertex -256.208 29.1138 324.411 + vertex -237.601 26.333 328.023 + endloop + endfacet + facet normal -0.112003 -0.978002 -0.175973 + outer loop + vertex -237.601 26.333 328.023 + vertex -256.208 29.1138 324.411 + vertex -234.786 26.6596 324.415 + endloop + endfacet + facet normal -0.125993 -0.982437 -0.137635 + outer loop + vertex -279.896 31.5694 327.969 + vertex -276.886 31.6839 324.397 + vertex -259.074 28.8933 328.012 + endloop + endfacet + facet normal -0.121711 -0.980083 -0.156917 + outer loop + vertex -259.074 28.8933 328.012 + vertex -276.886 31.6839 324.397 + vertex -256.208 29.1138 324.411 + endloop + endfacet + facet normal -0.138519 -0.982943 -0.12098 + outer loop + vertex -299.835 34.3834 327.936 + vertex -296.623 34.3702 324.366 + vertex -279.896 31.5694 327.969 + endloop + endfacet + facet normal -0.133239 -0.980614 -0.143681 + outer loop + vertex -279.896 31.5694 327.969 + vertex -296.623 34.3702 324.366 + vertex -276.886 31.6839 324.397 + endloop + endfacet + facet normal -0.152692 -0.983207 -0.0999481 + outer loop + vertex -318.978 37.3639 327.862 + vertex -315.324 37.1598 324.287 + vertex -299.835 34.3834 327.936 + endloop + endfacet + facet normal -0.145806 -0.981057 -0.127543 + outer loop + vertex -299.835 34.3834 327.936 + vertex -315.324 37.1598 324.287 + vertex -296.623 34.3702 324.366 + endloop + endfacet + facet normal -0.164896 -0.982432 -0.0873922 + outer loop + vertex -338.066 40.5909 327.601 + vertex -333.141 40.0765 324.091 + vertex -318.978 37.3639 327.862 + endloop + endfacet + facet normal -0.159478 -0.981387 -0.106989 + outer loop + vertex -318.978 37.3639 327.862 + vertex -333.141 40.0765 324.091 + vertex -315.324 37.1598 324.287 + endloop + endfacet + facet normal -0.173127 -0.980988 -0.0876891 + outer loop + vertex -358.336 44.2205 327.016 + vertex -350.417 43.1208 323.685 + vertex -338.066 40.5909 327.601 + endloop + endfacet + facet normal -0.170561 -0.980699 -0.0955955 + outer loop + vertex -338.066 40.5909 327.601 + vertex -350.417 43.1208 323.685 + vertex -333.141 40.0765 324.091 + endloop + endfacet + facet normal -0.163023 -0.978379 -0.127271 + outer loop + vertex -369.703 46.324 325.407 + vertex -366.516 46.0922 323.105 + vertex -358.336 44.2205 327.016 + endloop + endfacet + facet normal -0.177227 -0.979279 -0.097999 + outer loop + vertex -358.336 44.2205 327.016 + vertex -366.516 46.0922 323.105 + vertex -350.417 43.1208 323.685 + endloop + endfacet + facet normal -0.186856 -0.960279 -0.207241 + outer loop + vertex -382.15 48.8437 323.833 + vertex -384.494 49.3283 323.701 + vertex -377.091 48.3552 321.535 + endloop + endfacet + facet normal -0.191762 -0.968174 -0.160831 + outer loop + vertex -387.173 49.7861 324.14 + vertex -383.504 49.5378 321.259 + vertex -384.494 49.3283 323.701 + endloop + endfacet + facet normal -0.172812 -0.972912 -0.153555 + outer loop + vertex -383.504 49.5378 321.259 + vertex -377.091 48.3552 321.535 + vertex -384.494 49.3283 323.701 + endloop + endfacet + facet normal 0.172184 -0.954524 -0.243384 + outer loop + vertex 366.203 46.1182 322.383 + vertex 365.06 46.58 319.763 + vertex 377.951 48.5076 321.324 + endloop + endfacet + facet normal 0.175097 -0.943627 -0.280908 + outer loop + vertex 377.951 48.5076 321.324 + vertex 365.06 46.58 319.763 + vertex 372.238 48.4185 318.062 + endloop + endfacet + facet normal 0.170374 -0.965717 -0.195864 + outer loop + vertex 346.441 42.968 320.762 + vertex 354.992 44.5128 320.583 + vertex 351.389 43.4079 322.896 + endloop + endfacet + facet normal 0.175854 -0.953492 -0.244803 + outer loop + vertex 365.06 46.58 319.763 + vertex 366.203 46.1182 322.383 + vertex 354.992 44.5128 320.583 + endloop + endfacet + facet normal 0.169859 -0.965651 -0.196635 + outer loop + vertex 366.203 46.1182 322.383 + vertex 351.389 43.4079 322.896 + vertex 354.992 44.5128 320.583 + endloop + endfacet + facet normal 0.157465 -0.958422 -0.237973 + outer loop + vertex 334.085 40.3158 323.899 + vertex 333.99 41.1564 320.451 + vertex 351.389 43.4079 322.896 + endloop + endfacet + facet normal 0.14596 -0.979846 -0.136371 + outer loop + vertex 351.389 43.4079 322.896 + vertex 333.99 41.1564 320.451 + vertex 346.441 42.968 320.762 + endloop + endfacet + facet normal 0.15323 -0.95412 -0.257246 + outer loop + vertex 315.115 37.1586 324.31 + vertex 315.005 38.0331 321.001 + vertex 334.085 40.3158 323.899 + endloop + endfacet + facet normal 0.150951 -0.959452 -0.238046 + outer loop + vertex 334.085 40.3158 323.899 + vertex 315.005 38.0331 321.001 + vertex 333.99 41.1564 320.451 + endloop + endfacet + facet normal 0.141264 -0.953051 -0.26784 + outer loop + vertex 295.932 34.2891 324.403 + vertex 296.011 35.2051 321.185 + vertex 315.115 37.1586 324.31 + endloop + endfacet + facet normal 0.139863 -0.956146 -0.257337 + outer loop + vertex 315.115 37.1586 324.31 + vertex 296.011 35.2051 321.185 + vertex 315.005 38.0331 321.001 + endloop + endfacet + facet normal 0.127283 -0.950864 -0.282235 + outer loop + vertex 275.871 31.6038 324.403 + vertex 276.205 32.6013 321.193 + vertex 295.932 34.2891 324.403 + endloop + endfacet + facet normal 0.125447 -0.954997 -0.268783 + outer loop + vertex 295.932 34.2891 324.403 + vertex 276.205 32.6013 321.193 + vertex 296.011 35.2051 321.185 + endloop + endfacet + facet normal 0.116323 -0.946339 -0.301517 + outer loop + vertex 254.767 29.0099 324.402 + vertex 255.364 30.1136 321.169 + vertex 275.871 31.6038 324.403 + endloop + endfacet + facet normal 0.113971 -0.952032 -0.283982 + outer loop + vertex 275.871 31.6038 324.403 + vertex 255.364 30.1136 321.169 + vertex 276.205 32.6013 321.193 + endloop + endfacet + facet normal 0.107635 -0.940674 -0.321786 + outer loop + vertex 233.047 26.5238 324.405 + vertex 233.789 27.7183 321.161 + vertex 254.767 29.0099 324.402 + endloop + endfacet + facet normal 0.105234 -0.946919 -0.303762 + outer loop + vertex 254.767 29.0099 324.402 + vertex 233.789 27.7183 321.161 + vertex 255.364 30.1136 321.169 + endloop + endfacet + facet normal 0.0999701 -0.935144 -0.339869 + outer loop + vertex 211.304 24.2008 324.401 + vertex 212.018 25.4546 321.161 + vertex 233.047 26.5238 324.405 + endloop + endfacet + facet normal 0.0978365 -0.940941 -0.324127 + outer loop + vertex 233.047 26.5238 324.405 + vertex 212.018 25.4546 321.161 + vertex 233.789 27.7183 321.161 + endloop + endfacet + facet normal 0.0921397 -0.932569 -0.349035 + outer loop + vertex 189.779 22.0772 324.392 + vertex 190.42 23.355 321.148 + vertex 211.304 24.2008 324.401 + endloop + endfacet + facet normal 0.0911367 -0.935313 -0.341882 + outer loop + vertex 211.304 24.2008 324.401 + vertex 190.42 23.355 321.148 + vertex 212.018 25.4546 321.161 + endloop + endfacet + facet normal 0.0854208 -0.931133 -0.354535 + outer loop + vertex 168.457 20.132 324.364 + vertex 169.06 21.4251 321.113 + vertex 189.779 22.0772 324.392 + endloop + endfacet + facet normal 0.0848365 -0.932701 -0.350531 + outer loop + vertex 189.779 22.0772 324.392 + vertex 169.06 21.4251 321.113 + vertex 190.42 23.355 321.148 + endloop + endfacet + facet normal 0.0768376 -0.930552 -0.358006 + outer loop + vertex 147.182 18.3869 324.334 + vertex 147.801 19.6906 321.078 + vertex 168.457 20.132 324.364 + endloop + endfacet + facet normal 0.0765695 -0.931257 -0.356226 + outer loop + vertex 168.457 20.132 324.364 + vertex 147.801 19.6906 321.078 + vertex 169.06 21.4251 321.113 + endloop + endfacet + facet normal 0.0675932 -0.932441 -0.354943 + outer loop + vertex 125.885 16.8532 324.307 + vertex 126.591 18.1484 321.039 + vertex 147.182 18.3869 324.334 + endloop + endfacet + facet normal 0.0683229 -0.930587 -0.359638 + outer loop + vertex 147.182 18.3869 324.334 + vertex 126.591 18.1484 321.039 + vertex 147.801 19.6906 321.078 + endloop + endfacet + facet normal 0.0572311 -0.933321 -0.354453 + outer loop + vertex 104.579 15.5529 324.291 + vertex 105.373 16.8436 321.02 + vertex 125.885 16.8532 324.307 + endloop + endfacet + facet normal 0.0576452 -0.932309 -0.35704 + outer loop + vertex 125.885 16.8532 324.307 + vertex 105.373 16.8436 321.02 + vertex 126.591 18.1484 321.039 + endloop + endfacet + facet normal 0.0464686 -0.933713 -0.354993 + outer loop + vertex 83.3443 14.4985 324.285 + vertex 84.2053 15.7838 321.017 + vertex 104.579 15.5529 324.291 + endloop + endfacet + facet normal 0.0467767 -0.932986 -0.356859 + outer loop + vertex 104.579 15.5529 324.291 + vertex 84.2053 15.7838 321.017 + vertex 105.373 16.8436 321.02 + endloop + endfacet + facet normal 0.0347298 -0.935328 -0.352072 + outer loop + vertex 62.1955 13.7093 324.295 + vertex 63.1277 14.9742 321.027 + vertex 83.3443 14.4985 324.285 + endloop + endfacet + facet normal 0.0356756 -0.933182 -0.357628 + outer loop + vertex 83.3443 14.4985 324.285 + vertex 63.1277 14.9742 321.027 + vertex 84.2053 15.7838 321.017 + endloop + endfacet + facet normal 0.0239731 -0.937549 -0.347027 + outer loop + vertex 41.1115 13.1642 324.311 + vertex 42.1619 14.4021 321.039 + vertex 62.1955 13.7093 324.295 + endloop + endfacet + facet normal 0.0252899 -0.934705 -0.354523 + outer loop + vertex 62.1955 13.7093 324.295 + vertex 42.1619 14.4021 321.039 + vertex 63.1277 14.9742 321.027 + endloop + endfacet + facet normal 0.0144525 -0.936901 -0.349296 + outer loop + vertex 20.1119 12.8375 324.318 + vertex 21.2627 14.0718 321.055 + vertex 41.1115 13.1642 324.311 + endloop + endfacet + facet normal 0.0145342 -0.936731 -0.349747 + outer loop + vertex 41.1115 13.1642 324.311 + vertex 21.2627 14.0718 321.055 + vertex 42.1619 14.4021 321.039 + endloop + endfacet + facet normal 0.00417042 -0.937487 -0.347996 + outer loop + vertex -0.835017 12.7425 324.323 + vertex 0.409075 13.9596 321.06 + vertex 20.1119 12.8375 324.318 + endloop + endfacet + facet normal 0.00496642 -0.935889 -0.352259 + outer loop + vertex 20.1119 12.8375 324.318 + vertex 0.409075 13.9596 321.06 + vertex 21.2627 14.0718 321.055 + endloop + endfacet + facet normal -0.00496324 -0.936974 -0.349364 + outer loop + vertex -21.7908 12.857 324.314 + vertex -20.4772 14.0664 321.052 + vertex -0.835017 12.7425 324.323 + endloop + endfacet + facet normal -0.00465923 -0.936383 -0.35095 + outer loop + vertex -0.835017 12.7425 324.323 + vertex -20.4772 14.0664 321.052 + vertex 0.409075 13.9596 321.06 + endloop + endfacet + facet normal -0.0150261 -0.936569 -0.350161 + outer loop + vertex -42.865 13.1996 324.302 + vertex -41.4545 14.3977 321.037 + vertex -21.7908 12.857 324.314 + endloop + endfacet + facet normal -0.0145264 -0.935619 -0.352713 + outer loop + vertex -21.7908 12.857 324.314 + vertex -41.4545 14.3977 321.037 + vertex -20.4772 14.0664 321.052 + endloop + endfacet + facet normal -0.0253811 -0.937162 -0.34797 + outer loop + vertex -64.0271 13.7764 324.292 + vertex -62.4835 14.9504 321.018 + vertex -42.865 13.1996 324.302 + endloop + endfacet + facet normal -0.0242528 -0.935082 -0.353601 + outer loop + vertex -42.865 13.1996 324.302 + vertex -62.4835 14.9504 321.018 + vertex -41.4545 14.3977 321.037 + endloop + endfacet + facet normal -0.0355747 -0.934907 -0.353105 + outer loop + vertex -85.1413 14.5826 324.285 + vertex -83.5066 15.7553 321.015 + vertex -64.0271 13.7764 324.292 + endloop + endfacet + facet normal -0.0357651 -0.935249 -0.35218 + outer loop + vertex -64.0271 13.7764 324.292 + vertex -83.5066 15.7553 321.015 + vertex -62.4835 14.9504 321.018 + endloop + endfacet + facet normal -0.0469148 -0.933904 -0.354433 + outer loop + vertex -106.123 15.6341 324.291 + vertex -104.417 16.7894 321.021 + vertex -85.1413 14.5826 324.285 + endloop + endfacet + facet normal -0.0462342 -0.932712 -0.357647 + outer loop + vertex -85.1413 14.5826 324.285 + vertex -104.417 16.7894 321.021 + vertex -83.5066 15.7553 321.015 + endloop + endfacet + facet normal -0.0582841 -0.932426 -0.356629 + outer loop + vertex -127.069 16.9347 324.314 + vertex -125.293 18.0726 321.049 + vertex -106.123 15.6341 324.291 + endloop + endfacet + facet normal -0.0577253 -0.931468 -0.359214 + outer loop + vertex -106.123 15.6341 324.291 + vertex -125.293 18.0726 321.049 + vertex -104.417 16.7894 321.021 + endloop + endfacet + facet normal -0.0684896 -0.932202 -0.355399 + outer loop + vertex -148.145 18.4712 324.346 + vertex -146.269 19.5771 321.083 + vertex -127.069 16.9347 324.314 + endloop + endfacet + facet normal -0.0673132 -0.930222 -0.360771 + outer loop + vertex -127.069 16.9347 324.314 + vertex -146.269 19.5771 321.083 + vertex -125.293 18.0726 321.049 + endloop + endfacet + facet normal -0.0769693 -0.931157 -0.356402 + outer loop + vertex -169.442 20.2206 324.374 + vertex -167.545 21.3073 321.125 + vertex -148.145 18.4712 324.346 + endloop + endfacet + facet normal -0.0763512 -0.930125 -0.359217 + outer loop + vertex -148.145 18.4712 324.346 + vertex -167.545 21.3073 321.125 + vertex -146.269 19.5771 321.083 + endloop + endfacet + facet normal -0.0853652 -0.933524 -0.348202 + outer loop + vertex -191.077 22.1889 324.401 + vertex -189.18 23.2264 321.155 + vertex -169.442 20.2206 324.374 + endloop + endfacet + facet normal -0.0829381 -0.929514 -0.359339 + outer loop + vertex -169.442 20.2206 324.374 + vertex -189.18 23.2264 321.155 + vertex -167.545 21.3073 321.125 + endloop + endfacet + facet normal -0.0925076 -0.937006 -0.33684 + outer loop + vertex -212.955 24.3441 324.415 + vertex -211.129 25.3299 321.171 + vertex -191.077 22.1889 324.401 + endloop + endfacet + facet normal -0.0896081 -0.93234 -0.350302 + outer loop + vertex -191.077 22.1889 324.401 + vertex -211.129 25.3299 321.171 + vertex -189.18 23.2264 321.155 + endloop + endfacet + facet normal -0.0999181 -0.941918 -0.320636 + outer loop + vertex -234.786 26.6596 324.415 + vertex -233.044 27.5798 321.169 + vertex -212.955 24.3441 324.415 + endloop + endfacet + facet normal -0.0960758 -0.93603 -0.338552 + outer loop + vertex -212.955 24.3441 324.415 + vertex -233.044 27.5798 321.169 + vertex -211.129 25.3299 321.171 + endloop + endfacet + facet normal -0.10855 -0.948099 -0.298873 + outer loop + vertex -256.208 29.1138 324.411 + vertex -254.464 29.9392 321.159 + vertex -234.786 26.6596 324.415 + endloop + endfacet + facet normal -0.103488 -0.94097 -0.322283 + outer loop + vertex -234.786 26.6596 324.415 + vertex -254.464 29.9392 321.159 + vertex -233.044 27.5798 321.169 + endloop + endfacet + facet normal -0.118175 -0.952283 -0.281411 + outer loop + vertex -276.886 31.6839 324.397 + vertex -275.027 32.4088 321.163 + vertex -256.208 29.1138 324.411 + endloop + endfacet + facet normal -0.113765 -0.946713 -0.301318 + outer loop + vertex -256.208 29.1138 324.411 + vertex -275.027 32.4088 321.163 + vertex -254.464 29.9392 321.159 + endloop + endfacet + facet normal -0.129631 -0.955514 -0.264933 + outer loop + vertex -296.623 34.3702 324.366 + vertex -294.641 34.9893 321.163 + vertex -276.886 31.6839 324.397 + endloop + endfacet + facet normal -0.125031 -0.950362 -0.284921 + outer loop + vertex -276.886 31.6839 324.397 + vertex -294.641 34.9893 321.163 + vertex -275.027 32.4088 321.163 + endloop + endfacet + facet normal -0.141891 -0.958237 -0.248293 + outer loop + vertex -315.324 37.1598 324.287 + vertex -313.341 37.6871 321.119 + vertex -296.623 34.3702 324.366 + endloop + endfacet + facet normal -0.136899 -0.953358 -0.269013 + outer loop + vertex -296.623 34.3702 324.366 + vertex -313.341 37.6871 321.119 + vertex -294.641 34.9893 321.163 + endloop + endfacet + facet normal -0.155413 -0.963891 -0.216243 + outer loop + vertex -333.141 40.0765 324.091 + vertex -330.314 40.302 321.054 + vertex -315.324 37.1598 324.287 + endloop + endfacet + facet normal -0.146461 -0.956863 -0.250924 + outer loop + vertex -315.324 37.1598 324.287 + vertex -330.314 40.302 321.054 + vertex -313.341 37.6871 321.119 + endloop + endfacet + facet normal -0.166013 -0.967545 -0.190514 + outer loop + vertex -350.417 43.1208 323.685 + vertex -345.372 42.8158 320.837 + vertex -333.141 40.0765 324.091 + endloop + endfacet + facet normal -0.157634 -0.963077 -0.218251 + outer loop + vertex -333.141 40.0765 324.091 + vertex -345.372 42.8158 320.837 + vertex -330.314 40.302 321.054 + endloop + endfacet + facet normal -0.176305 -0.961116 -0.212538 + outer loop + vertex -368.087 47.0727 319.975 + vertex -358.667 45.2486 320.409 + vertex -366.516 46.0922 323.105 + endloop + endfacet + facet normal -0.170245 -0.965251 -0.198259 + outer loop + vertex -345.372 42.8158 320.837 + vertex -350.417 43.1208 323.685 + vertex -358.667 45.2486 320.409 + endloop + endfacet + facet normal -0.171151 -0.965521 -0.196153 + outer loop + vertex -350.417 43.1208 323.685 + vertex -366.516 46.0922 323.105 + vertex -358.667 45.2486 320.409 + endloop + endfacet + facet normal -0.164994 -0.953539 -0.252071 + outer loop + vertex -383.504 49.5378 321.259 + vertex -377.624 49.2945 318.331 + vertex -377.091 48.3552 321.535 + endloop + endfacet + facet normal -0.15711 -0.954452 -0.253651 + outer loop + vertex -377.091 48.3552 321.535 + vertex -377.624 49.2945 318.331 + vertex -371.077 48.3303 317.904 + endloop + endfacet + facet normal 0.156427 -0.926781 -0.341479 + outer loop + vertex 365.06 46.58 319.763 + vertex 361.964 46.905 317.463 + vertex 372.238 48.4185 318.062 + endloop + endfacet + facet normal 0.143962 -0.896688 -0.4186 + outer loop + vertex 358.208 46.997 315.974 + vertex 367.085 48.7569 315.257 + vertex 361.964 46.905 317.463 + endloop + endfacet + facet normal 0.156369 -0.904632 -0.396472 + outer loop + vertex 367.085 48.7569 315.257 + vertex 372.238 48.4185 318.062 + vertex 361.964 46.905 317.463 + endloop + endfacet + facet normal 0.148761 -0.90308 -0.402886 + outer loop + vertex 344.526 43.2085 319.235 + vertex 344.993 43.9768 317.686 + vertex 354.263 45.0956 318.6 + endloop + endfacet + facet normal 0.149428 -0.895838 -0.418505 + outer loop + vertex 354.263 45.0956 318.6 + vertex 344.993 43.9768 317.686 + vertex 352.209 45.5379 316.92 + endloop + endfacet + facet normal 0.159779 -0.924467 -0.346168 + outer loop + vertex 346.441 42.968 320.762 + vertex 344.526 43.2085 319.235 + vertex 354.992 44.5128 320.583 + endloop + endfacet + facet normal 0.158603 -0.929942 -0.331742 + outer loop + vertex 354.992 44.5128 320.583 + vertex 344.526 43.2085 319.235 + vertex 354.263 45.0956 318.6 + endloop + endfacet + facet normal 0.163547 -0.928578 -0.33316 + outer loop + vertex 354.992 44.5128 320.583 + vertex 354.263 45.0956 318.6 + vertex 365.06 46.58 319.763 + endloop + endfacet + facet normal 0.164575 -0.921531 -0.351705 + outer loop + vertex 365.06 46.58 319.763 + vertex 354.263 45.0956 318.6 + vertex 361.964 46.905 317.463 + endloop + endfacet + facet normal 0.148853 -0.896215 -0.417901 + outer loop + vertex 354.263 45.0956 318.6 + vertex 352.209 45.5379 316.92 + vertex 361.964 46.905 317.463 + endloop + endfacet + facet normal 0.148722 -0.890389 -0.43022 + outer loop + vertex 361.964 46.905 317.463 + vertex 352.209 45.5379 316.92 + vertex 358.208 46.997 315.974 + endloop + endfacet + facet normal 0.132257 -0.90335 -0.408004 + outer loop + vertex 344.993 43.9768 317.686 + vertex 344.526 43.2085 319.235 + vertex 331.536 42.1263 317.42 + endloop + endfacet + facet normal 0.144015 -0.933692 -0.327839 + outer loop + vertex 346.441 42.968 320.762 + vertex 333.99 41.1564 320.451 + vertex 344.526 43.2085 319.235 + endloop + endfacet + facet normal 0.131128 -0.908456 -0.39688 + outer loop + vertex 333.99 41.1564 320.451 + vertex 331.536 42.1263 317.42 + vertex 344.526 43.2085 319.235 + endloop + endfacet + facet normal 0.136615 -0.902357 -0.408764 + outer loop + vertex 315.005 38.0331 321.001 + vertex 313.876 39.2025 318.042 + vertex 333.99 41.1564 320.451 + endloop + endfacet + facet normal 0.135964 -0.906324 -0.400113 + outer loop + vertex 333.99 41.1564 320.451 + vertex 313.876 39.2025 318.042 + vertex 331.536 42.1263 317.42 + endloop + endfacet + facet normal 0.129682 -0.898352 -0.419697 + outer loop + vertex 296.011 35.2051 321.185 + vertex 295.319 36.4552 318.296 + vertex 315.005 38.0331 321.001 + endloop + endfacet + facet normal 0.128368 -0.904589 -0.406499 + outer loop + vertex 315.005 38.0331 321.001 + vertex 295.319 36.4552 318.296 + vertex 313.876 39.2025 318.042 + endloop + endfacet + facet normal 0.117254 -0.893141 -0.434224 + outer loop + vertex 276.205 32.6013 321.193 + vertex 275.759 33.9344 318.33 + vertex 296.011 35.2051 321.185 + endloop + endfacet + facet normal 0.115415 -0.901294 -0.41755 + outer loop + vertex 296.011 35.2051 321.185 + vertex 275.759 33.9344 318.33 + vertex 295.319 36.4552 318.296 + endloop + endfacet + facet normal 0.106039 -0.883901 -0.455494 + outer loop + vertex 255.364 30.1136 321.169 + vertex 255.047 31.5521 318.303 + vertex 276.205 32.6013 321.193 + endloop + endfacet + facet normal 0.103553 -0.895365 -0.433126 + outer loop + vertex 276.205 32.6013 321.193 + vertex 255.047 31.5521 318.303 + vertex 275.759 33.9344 318.33 + endloop + endfacet + facet normal 0.0974216 -0.876026 -0.472322 + outer loop + vertex 233.789 27.7183 321.161 + vertex 233.523 29.2407 318.283 + vertex 255.364 30.1136 321.169 + endloop + endfacet + facet normal 0.0955108 -0.885331 -0.455047 + outer loop + vertex 255.364 30.1136 321.169 + vertex 233.523 29.2407 318.283 + vertex 255.047 31.5521 318.303 + endloop + endfacet + facet normal 0.090349 -0.86892 -0.486636 + outer loop + vertex 212.018 25.4546 321.161 + vertex 211.71 27.0381 318.276 + vertex 233.789 27.7183 321.161 + endloop + endfacet + facet normal 0.0886981 -0.877085 -0.472076 + outer loop + vertex 233.789 27.7183 321.161 + vertex 211.71 27.0381 318.276 + vertex 233.523 29.2407 318.283 + endloop + endfacet + facet normal 0.0843175 -0.864195 -0.496041 + outer loop + vertex 190.42 23.355 321.148 + vertex 190.039 24.9757 318.259 + vertex 212.018 25.4546 321.161 + endloop + endfacet + facet normal 0.0831601 -0.869798 -0.48635 + outer loop + vertex 212.018 25.4546 321.161 + vertex 190.039 24.9757 318.259 + vertex 211.71 27.0381 318.276 + endloop + endfacet + facet normal 0.0786356 -0.861377 -0.501843 + outer loop + vertex 169.06 21.4251 321.113 + vertex 168.633 23.0711 318.221 + vertex 190.42 23.355 321.148 + endloop + endfacet + facet normal 0.0778515 -0.865025 -0.495653 + outer loop + vertex 190.42 23.355 321.148 + vertex 168.633 23.0711 318.221 + vertex 190.039 24.9757 318.259 + endloop + endfacet + facet normal 0.0711246 -0.861522 -0.502713 + outer loop + vertex 147.801 19.6906 321.078 + vertex 147.401 21.3507 318.176 + vertex 169.06 21.4251 321.113 + endloop + endfacet + facet normal 0.0709323 -0.862377 -0.501273 + outer loop + vertex 169.06 21.4251 321.113 + vertex 147.401 21.3507 318.176 + vertex 168.633 23.0711 318.221 + endloop + endfacet + facet normal 0.0636037 -0.862102 -0.502727 + outer loop + vertex 126.591 18.1484 321.039 + vertex 126.248 19.8182 318.132 + vertex 147.801 19.6906 321.078 + endloop + endfacet + facet normal 0.0635273 -0.862425 -0.502182 + outer loop + vertex 147.801 19.6906 321.078 + vertex 126.248 19.8182 318.132 + vertex 147.401 21.3507 318.176 + endloop + endfacet + facet normal 0.0535571 -0.863743 -0.501078 + outer loop + vertex 105.373 16.8436 321.02 + vertex 105.123 18.5177 318.108 + vertex 126.591 18.1484 321.039 + endloop + endfacet + facet normal 0.0537131 -0.863116 -0.502142 + outer loop + vertex 126.591 18.1484 321.039 + vertex 105.123 18.5177 318.108 + vertex 126.248 19.8182 318.132 + endloop + endfacet + facet normal 0.0435032 -0.867132 -0.496175 + outer loop + vertex 84.2053 15.7838 321.017 + vertex 84.0486 17.446 318.098 + vertex 105.373 16.8436 321.02 + endloop + endfacet + facet normal 0.0441985 -0.86449 -0.500704 + outer loop + vertex 105.373 16.8436 321.02 + vertex 84.0486 17.446 318.098 + vertex 105.123 18.5177 318.108 + endloop + endfacet + facet normal 0.0330997 -0.867805 -0.495802 + outer loop + vertex 63.1277 14.9742 321.027 + vertex 63.0499 16.6368 318.111 + vertex 84.2053 15.7838 321.017 + endloop + endfacet + facet normal 0.0331236 -0.867718 -0.495951 + outer loop + vertex 84.2053 15.7838 321.017 + vertex 63.0499 16.6368 318.111 + vertex 84.0486 17.446 318.098 + endloop + endfacet + facet normal 0.0233662 -0.867335 -0.497176 + outer loop + vertex 42.1619 14.4021 321.039 + vertex 42.1626 16.0691 318.131 + vertex 63.1277 14.9742 321.027 + endloop + endfacet + facet normal 0.0231246 -0.868163 -0.49574 + outer loop + vertex 63.1277 14.9742 321.027 + vertex 42.1626 16.0691 318.131 + vertex 63.0499 16.6368 318.111 + endloop + endfacet + facet normal 0.0133567 -0.869311 -0.494085 + outer loop + vertex 21.2627 14.0718 321.055 + vertex 21.3737 15.7272 318.146 + vertex 42.1619 14.4021 321.039 + endloop + endfacet + facet normal 0.0139157 -0.867487 -0.497266 + outer loop + vertex 42.1619 14.4021 321.039 + vertex 21.3737 15.7272 318.146 + vertex 42.1626 16.0691 318.131 + endloop + endfacet + facet normal 0.00457857 -0.869083 -0.494644 + outer loop + vertex 0.409075 13.9596 321.06 + vertex 0.61874 15.6153 318.152 + vertex 21.2627 14.0718 321.055 + endloop + endfacet + facet normal 0.00452992 -0.869235 -0.494379 + outer loop + vertex 21.2627 14.0718 321.055 + vertex 0.61874 15.6153 318.152 + vertex 21.3737 15.7272 318.146 + endloop + endfacet + facet normal -0.00426083 -0.868979 -0.49483 + outer loop + vertex -20.4772 14.0664 321.052 + vertex -20.1748 15.7208 318.144 + vertex 0.409075 13.9596 321.06 + endloop + endfacet + facet normal -0.00420509 -0.868813 -0.495123 + outer loop + vertex 0.409075 13.9596 321.06 + vertex -20.1748 15.7208 318.144 + vertex 0.61874 15.6153 318.152 + endloop + endfacet + facet normal -0.0133732 -0.868896 -0.494813 + outer loop + vertex -41.4545 14.3977 321.037 + vertex -41.0557 16.0494 318.126 + vertex -20.4772 14.0664 321.052 + endloop + endfacet + facet normal -0.0132388 -0.868509 -0.495497 + outer loop + vertex -20.4772 14.0664 321.052 + vertex -41.0557 16.0494 318.126 + vertex -20.1748 15.7208 318.144 + endloop + endfacet + facet normal -0.0223357 -0.867154 -0.497538 + outer loop + vertex -62.4835 14.9504 321.018 + vertex -61.9962 16.6079 318.107 + vertex -41.4545 14.3977 321.037 + endloop + endfacet + facet normal -0.0227108 -0.868199 -0.495697 + outer loop + vertex -41.4545 14.3977 321.037 + vertex -61.9962 16.6079 318.107 + vertex -41.0557 16.0494 318.126 + endloop + endfacet + facet normal -0.0331438 -0.867239 -0.496788 + outer loop + vertex -83.5066 15.7553 321.015 + vertex -82.9133 17.4033 318.099 + vertex -62.4835 14.9504 321.018 + endloop + endfacet + facet normal -0.0327388 -0.866151 -0.498709 + outer loop + vertex -62.4835 14.9504 321.018 + vertex -82.9133 17.4033 318.099 + vertex -61.9962 16.6079 318.107 + endloop + endfacet + facet normal -0.0429311 -0.865091 -0.499774 + outer loop + vertex -104.417 16.7894 321.021 + vertex -103.748 18.4391 318.108 + vertex -83.5066 15.7553 321.015 + endloop + endfacet + facet normal -0.043285 -0.866007 -0.498155 + outer loop + vertex -83.5066 15.7553 321.015 + vertex -103.748 18.4391 318.108 + vertex -82.9133 17.4033 318.099 + endloop + endfacet + facet normal -0.0537612 -0.863939 -0.500718 + outer loop + vertex -125.293 18.0726 321.049 + vertex -124.546 19.7131 318.138 + vertex -104.417 16.7894 321.021 + endloop + endfacet + facet normal -0.053615 -0.863572 -0.501367 + outer loop + vertex -104.417 16.7894 321.021 + vertex -124.546 19.7131 318.138 + vertex -103.748 18.4391 318.108 + endloop + endfacet + facet normal -0.0627188 -0.862964 -0.501358 + outer loop + vertex -146.269 19.5771 321.083 + vertex -145.453 21.2051 318.179 + vertex -125.293 18.0726 321.049 + endloop + endfacet + facet normal -0.0625332 -0.862508 -0.502165 + outer loop + vertex -125.293 18.0726 321.049 + vertex -145.453 21.2051 318.179 + vertex -124.546 19.7131 318.138 + endloop + endfacet + facet normal -0.0712058 -0.863433 -0.499413 + outer loop + vertex -167.545 21.3073 321.125 + vertex -166.676 22.9122 318.227 + vertex -146.269 19.5771 321.083 + endloop + endfacet + facet normal -0.0704345 -0.861563 -0.502741 + outer loop + vertex -146.269 19.5771 321.083 + vertex -166.676 22.9122 318.227 + vertex -145.453 21.2051 318.179 + endloop + endfacet + facet normal -0.0773353 -0.864235 -0.497108 + outer loop + vertex -189.18 23.2264 321.155 + vertex -188.331 24.8115 318.267 + vertex -167.545 21.3073 321.125 + endloop + endfacet + facet normal -0.0765647 -0.86238 -0.500438 + outer loop + vertex -167.545 21.3073 321.125 + vertex -188.331 24.8115 318.267 + vertex -166.676 22.9122 318.227 + endloop + endfacet + facet normal -0.0837503 -0.870171 -0.48558 + outer loop + vertex -211.129 25.3299 321.171 + vertex -210.325 26.8644 318.282 + vertex -189.18 23.2264 321.155 + endloop + endfacet + facet normal -0.0809486 -0.863519 -0.497778 + outer loop + vertex -189.18 23.2264 321.155 + vertex -210.325 26.8644 318.282 + vertex -188.331 24.8115 318.267 + endloop + endfacet + facet normal -0.0900218 -0.877162 -0.471682 + outer loop + vertex -233.044 27.5798 321.169 + vertex -232.316 29.0602 318.277 + vertex -211.129 25.3299 321.171 + endloop + endfacet + facet normal -0.0867198 -0.869591 -0.486098 + outer loop + vertex -211.129 25.3299 321.171 + vertex -232.316 29.0602 318.277 + vertex -210.325 26.8644 318.282 + endloop + endfacet + facet normal -0.0972103 -0.884573 -0.456158 + outer loop + vertex -254.464 29.9392 321.159 + vertex -253.734 31.3518 318.264 + vertex -233.044 27.5798 321.169 + endloop + endfacet + facet normal -0.0934846 -0.87651 -0.472219 + outer loop + vertex -233.044 27.5798 321.169 + vertex -253.734 31.3518 318.264 + vertex -232.316 29.0602 318.277 + endloop + endfacet + facet normal -0.107532 -0.894581 -0.433776 + outer loop + vertex -275.027 32.4088 321.163 + vertex -274.156 33.7106 318.263 + vertex -254.464 29.9392 321.159 + endloop + endfacet + facet normal -0.102032 -0.883638 -0.456918 + outer loop + vertex -254.464 29.9392 321.159 + vertex -274.156 33.7106 318.263 + vertex -253.734 31.3518 318.264 + endloop + endfacet + facet normal -0.118402 -0.899982 -0.419539 + outer loop + vertex -294.641 34.9893 321.163 + vertex -293.507 36.1817 318.285 + vertex -275.027 32.4088 321.163 + endloop + endfacet + facet normal -0.114545 -0.893025 -0.435184 + outer loop + vertex -275.027 32.4088 321.163 + vertex -293.507 36.1817 318.285 + vertex -274.156 33.7106 318.263 + endloop + endfacet + facet normal -0.129502 -0.904341 -0.406689 + outer loop + vertex -313.341 37.6871 321.119 + vertex -312.204 38.8079 318.264 + vertex -294.641 34.9893 321.163 + endloop + endfacet + facet normal -0.12567 -0.898034 -0.421595 + outer loop + vertex -294.641 34.9893 321.163 + vertex -312.204 38.8079 318.264 + vertex -293.507 36.1817 318.285 + endloop + endfacet + facet normal -0.139131 -0.912586 -0.384486 + outer loop + vertex -330.314 40.302 321.054 + vertex -330.768 41.6107 318.112 + vertex -313.341 37.6871 321.119 + endloop + endfacet + facet normal -0.133046 -0.903363 -0.407718 + outer loop + vertex -313.341 37.6871 321.119 + vertex -330.768 41.6107 318.112 + vertex -312.204 38.8079 318.264 + endloop + endfacet + facet normal -0.151286 -0.934118 -0.323319 + outer loop + vertex -345.372 42.8158 320.837 + vertex -343.296 43.2824 318.518 + vertex -330.314 40.302 321.054 + endloop + endfacet + facet normal -0.13253 -0.884792 -0.446742 + outer loop + vertex -344.203 44.2782 316.815 + vertex -330.768 41.6107 318.112 + vertex -343.296 43.2824 318.518 + endloop + endfacet + facet normal -0.134297 -0.912931 -0.385385 + outer loop + vertex -330.768 41.6107 318.112 + vertex -330.314 40.302 321.054 + vertex -343.296 43.2824 318.518 + endloop + endfacet + facet normal -0.156624 -0.905886 -0.393498 + outer loop + vertex -363.479 46.9577 317.827 + vertex -359.391 46.8738 316.392 + vertex -354.354 45.1916 318.26 + endloop + endfacet + facet normal -0.144514 -0.896867 -0.418025 + outer loop + vertex -354.354 45.1916 318.26 + vertex -359.391 46.8738 316.392 + vertex -352.31 45.6388 316.594 + endloop + endfacet + facet normal -0.16712 -0.936478 -0.308351 + outer loop + vertex -368.087 47.0727 319.975 + vertex -363.479 46.9577 317.827 + vertex -358.667 45.2486 320.409 + endloop + endfacet + facet normal -0.166502 -0.936256 -0.309356 + outer loop + vertex -358.667 45.2486 320.409 + vertex -363.479 46.9577 317.827 + vertex -354.354 45.1916 318.26 + endloop + endfacet + facet normal -0.16228 -0.939783 -0.300787 + outer loop + vertex -358.667 45.2486 320.409 + vertex -354.354 45.1916 318.26 + vertex -345.372 42.8158 320.837 + endloop + endfacet + facet normal -0.153534 -0.933122 -0.325131 + outer loop + vertex -345.372 42.8158 320.837 + vertex -354.354 45.1916 318.26 + vertex -343.296 43.2824 318.518 + endloop + endfacet + facet normal -0.145038 -0.896526 -0.418576 + outer loop + vertex -354.354 45.1916 318.26 + vertex -352.31 45.6388 316.594 + vertex -343.296 43.2824 318.518 + endloop + endfacet + facet normal -0.136454 -0.885144 -0.444859 + outer loop + vertex -343.296 43.2824 318.518 + vertex -352.31 45.6388 316.594 + vertex -344.203 44.2782 316.815 + endloop + endfacet + facet normal -0.158866 -0.919542 -0.359449 + outer loop + vertex -377.624 49.2945 318.331 + vertex -372.282 49.5969 315.197 + vertex -371.077 48.3303 317.904 + endloop + endfacet + facet normal -0.142135 -0.919371 -0.366816 + outer loop + vertex -371.077 48.3303 317.904 + vertex -372.282 49.5969 315.197 + vertex -365.023 48.4576 315.239 + endloop + endfacet + facet normal -0.0262005 -0.652143 -0.757643 + outer loop + vertex 344.644 57.3774 302.817 + vertex 347.14 54.9833 304.791 + vertex 341.548 56.5947 303.598 + endloop + endfacet + facet normal 0.0715009 -0.736999 -0.672101 + outer loop + vertex -346.698 57.7132 302.373 + vertex -346.302 57.4498 302.704 + vertex -350.771 55.4629 304.407 + endloop + endfacet + facet normal 0.0378392 -0.659717 -0.750561 + outer loop + vertex -344.248 57.6591 302.623 + vertex -346.815 55.0018 304.829 + vertex -346.302 57.4498 302.704 + endloop + endfacet + facet normal 0.00411724 -0.656164 -0.754607 + outer loop + vertex -346.815 55.0018 304.829 + vertex -350.771 55.4629 304.407 + vertex -346.302 57.4498 302.704 + endloop + endfacet + facet normal 0.037583 -0.55265 -0.832566 + outer loop + vertex -341.179 57.8536 302.596 + vertex -339.012 59.7051 301.465 + vertex -337.107 57.6024 302.947 + endloop + endfacet + facet normal 0.0651661 -0.534685 -0.842535 + outer loop + vertex -337.107 57.6024 302.947 + vertex -339.012 59.7051 301.465 + vertex -335.156 59.3521 301.987 + endloop + endfacet + facet normal 0.121257 -0.615534 -0.778726 + outer loop + vertex -344.117 59.2775 301.298 + vertex -341.676 61.1489 300.199 + vertex -343.431 59.5064 301.224 + endloop + endfacet + facet normal 0.173461 -0.648108 -0.741531 + outer loop + vertex -343.431 59.5064 301.224 + vertex -341.676 61.1489 300.199 + vertex -340.985 61.4266 300.118 + endloop + endfacet + facet normal 0.0674181 -0.561105 -0.824995 + outer loop + vertex -343.431 59.5064 301.224 + vertex -340.985 61.4266 300.118 + vertex -341.798 59.724 301.209 + endloop + endfacet + facet normal 0.115805 -0.57469 -0.810136 + outer loop + vertex -341.798 59.724 301.209 + vertex -340.985 61.4266 300.118 + vertex -339.505 61.5844 300.217 + endloop + endfacet + facet normal 0.248518 -0.712416 -0.65628 + outer loop + vertex -344.571 59.1189 301.298 + vertex -342.26 60.8461 300.298 + vertex -344.117 59.2775 301.298 + endloop + endfacet + facet normal 0.264945 -0.721387 -0.639848 + outer loop + vertex -344.117 59.2775 301.298 + vertex -342.26 60.8461 300.298 + vertex -341.676 61.1489 300.199 + endloop + endfacet + facet normal -0.190026 -0.494812 -0.847969 + outer loop + vertex 338.068 62.7371 299.763 + vertex 336.156 64.7469 299.019 + vertex 338.863 63.495 299.143 + endloop + endfacet + facet normal -0.182784 -0.480143 -0.857935 + outer loop + vertex 338.863 63.495 299.143 + vertex 336.156 64.7469 299.019 + vertex 336.969 65.2924 298.541 + endloop + endfacet + facet normal -0.158844 -0.554157 -0.817116 + outer loop + vertex 340.212 60.8461 300.629 + vertex 338.068 62.7371 299.763 + vertex 341.136 61.5165 299.995 + endloop + endfacet + facet normal -0.147524 -0.529207 -0.835569 + outer loop + vertex 341.136 61.5165 299.995 + vertex 338.068 62.7371 299.763 + vertex 338.863 63.495 299.143 + endloop + endfacet + facet normal -0.110352 -0.423877 -0.898972 + outer loop + vertex 333.146 61.4236 301.111 + vertex 331.449 63.4991 300.341 + vertex 336.169 62.1579 300.393 + endloop + endfacet + facet normal -0.11415 -0.436979 -0.892199 + outer loop + vertex 336.169 62.1579 300.393 + vertex 331.449 63.4991 300.341 + vertex 334.325 64.2102 299.624 + endloop + endfacet + facet normal -0.0817941 -0.477576 -0.874775 + outer loop + vertex 334.949 59.4878 301.999 + vertex 333.146 61.4236 301.111 + vertex 338.187 60.2535 301.278 + endloop + endfacet + facet normal -0.0856797 -0.493028 -0.865784 + outer loop + vertex 338.187 60.2535 301.278 + vertex 333.146 61.4236 301.111 + vertex 336.169 62.1579 300.393 + endloop + endfacet + facet normal -0.119244 -0.519465 -0.846131 + outer loop + vertex 338.187 60.2535 301.278 + vertex 336.169 62.1579 300.393 + vertex 340.212 60.8461 300.629 + endloop + endfacet + facet normal -0.120497 -0.522914 -0.843826 + outer loop + vertex 340.212 60.8461 300.629 + vertex 336.169 62.1579 300.393 + vertex 338.068 62.7371 299.763 + endloop + endfacet + facet normal -0.149248 -0.461825 -0.874324 + outer loop + vertex 336.169 62.1579 300.393 + vertex 334.325 64.2102 299.624 + vertex 338.068 62.7371 299.763 + endloop + endfacet + facet normal -0.151235 -0.466603 -0.871441 + outer loop + vertex 338.068 62.7371 299.763 + vertex 334.325 64.2102 299.624 + vertex 336.156 64.7469 299.019 + endloop + endfacet + facet normal -0.044353 -0.363835 -0.930407 + outer loop + vertex 323.907 59.2571 302.571 + vertex 323.634 61.3853 301.752 + vertex 329.165 60.4246 301.864 + endloop + endfacet + facet normal -0.045784 -0.371702 -0.927223 + outer loop + vertex 329.165 60.4246 301.864 + vertex 323.634 61.3853 301.752 + vertex 327.664 62.5252 301.096 + endloop + endfacet + facet normal -0.0259804 -0.420862 -0.906753 + outer loop + vertex 326.367 57.2984 303.41 + vertex 323.907 59.2571 302.571 + vertex 330.737 58.4705 302.741 + endloop + endfacet + facet normal -0.0267585 -0.426995 -0.903858 + outer loop + vertex 330.737 58.4705 302.741 + vertex 323.907 59.2571 302.571 + vertex 329.165 60.4246 301.864 + endloop + endfacet + facet normal -0.0507762 -0.442493 -0.895333 + outer loop + vertex 330.737 58.4705 302.741 + vertex 329.165 60.4246 301.864 + vertex 334.949 59.4878 301.999 + endloop + endfacet + facet normal -0.0533081 -0.457046 -0.887844 + outer loop + vertex 334.949 59.4878 301.999 + vertex 329.165 60.4246 301.864 + vertex 333.146 61.4236 301.111 + endloop + endfacet + facet normal -0.0758623 -0.389743 -0.917794 + outer loop + vertex 329.165 60.4246 301.864 + vertex 327.664 62.5252 301.096 + vertex 333.146 61.4236 301.111 + endloop + endfacet + facet normal -0.0784669 -0.402628 -0.911994 + outer loop + vertex 333.146 61.4236 301.111 + vertex 327.664 62.5252 301.096 + vertex 331.449 63.4991 300.341 + endloop + endfacet + facet normal -0.0269935 -0.362128 -0.931737 + outer loop + vertex 323.634 61.3853 301.752 + vertex 323.907 59.2571 302.571 + vertex 315.185 61.418 301.984 + endloop + endfacet + facet normal -0.00281773 -0.396582 -0.917995 + outer loop + vertex 326.367 57.2984 303.41 + vertex 317.312 57.0446 303.547 + vertex 323.907 59.2571 302.571 + endloop + endfacet + facet normal -0.0226461 -0.346247 -0.93787 + outer loop + vertex 317.312 57.0446 303.547 + vertex 315.185 61.418 301.984 + vertex 323.907 59.2571 302.571 + endloop + endfacet + facet normal 0.0128908 -0.334836 -0.942188 + outer loop + vertex 304.312 54.7836 304.173 + vertex 302.827 59.2168 302.577 + vertex 317.312 57.0446 303.547 + endloop + endfacet + facet normal 0.0136123 -0.330676 -0.943646 + outer loop + vertex 317.312 57.0446 303.547 + vertex 302.827 59.2168 302.577 + vertex 315.185 61.418 301.984 + endloop + endfacet + facet normal 0.0282005 -0.330087 -0.943529 + outer loop + vertex 289.024 52.6809 304.452 + vertex 287.983 57.1903 302.843 + vertex 304.312 54.7836 304.173 + endloop + endfacet + facet normal 0.028183 -0.330187 -0.943495 + outer loop + vertex 304.312 54.7836 304.173 + vertex 287.983 57.1903 302.843 + vertex 302.827 59.2168 302.577 + endloop + endfacet + facet normal 0.0312987 -0.326822 -0.944568 + outer loop + vertex 271.227 50.774 304.522 + vertex 270.448 55.3518 302.912 + vertex 289.024 52.6809 304.452 + endloop + endfacet + facet normal 0.0308342 -0.32952 -0.943645 + outer loop + vertex 289.024 52.6809 304.452 + vertex 270.448 55.3518 302.912 + vertex 287.983 57.1903 302.843 + endloop + endfacet + facet normal 0.0301063 -0.324858 -0.945283 + outer loop + vertex 251.213 48.9406 304.514 + vertex 250.565 53.5776 302.9 + vertex 271.227 50.774 304.522 + endloop + endfacet + facet normal 0.0297468 -0.327073 -0.944531 + outer loop + vertex 271.227 50.774 304.522 + vertex 250.565 53.5776 302.9 + vertex 270.448 55.3518 302.912 + endloop + endfacet + facet normal 0.0287597 -0.319633 -0.947105 + outer loop + vertex 229.722 47.0804 304.49 + vertex 229.071 51.7839 302.883 + vertex 251.213 48.9406 304.514 + endloop + endfacet + facet normal 0.0279141 -0.325153 -0.945249 + outer loop + vertex 251.213 48.9406 304.514 + vertex 229.071 51.7839 302.883 + vertex 250.565 53.5776 302.9 + endloop + endfacet + facet normal 0.0275646 -0.317126 -0.947983 + outer loop + vertex 207.625 45.2119 304.472 + vertex 206.964 49.9562 302.866 + vertex 229.722 47.0804 304.49 + endloop + endfacet + facet normal 0.0271565 -0.319846 -0.94708 + outer loop + vertex 229.722 47.0804 304.49 + vertex 206.964 49.9562 302.866 + vertex 229.071 51.7839 302.883 + endloop + endfacet + facet normal 0.0281705 -0.31573 -0.948431 + outer loop + vertex 185.671 43.3652 304.435 + vertex 185.005 48.1373 302.826 + vertex 207.625 45.2119 304.472 + endloop + endfacet + facet normal 0.0279647 -0.317073 -0.947989 + outer loop + vertex 207.625 45.2119 304.472 + vertex 185.005 48.1373 302.826 + vertex 206.964 49.9562 302.866 + endloop + endfacet + facet normal 0.0284363 -0.315218 -0.948593 + outer loop + vertex 164.197 41.6134 304.373 + vertex 163.555 46.4047 302.762 + vertex 185.671 43.3652 304.435 + endloop + endfacet + facet normal 0.0283574 -0.315705 -0.948434 + outer loop + vertex 185.671 43.3652 304.435 + vertex 163.555 46.4047 302.762 + vertex 185.005 48.1373 302.826 + endloop + endfacet + facet normal 0.0282122 -0.317455 -0.947854 + outer loop + vertex 143.179 39.9877 304.292 + vertex 142.58 44.7781 302.67 + vertex 164.197 41.6134 304.373 + endloop + endfacet + facet normal 0.0286012 -0.315197 -0.948595 + outer loop + vertex 164.197 41.6134 304.373 + vertex 142.58 44.7781 302.67 + vertex 163.555 46.4047 302.762 + endloop + endfacet + facet normal 0.0261282 -0.318078 -0.947705 + outer loop + vertex 122.449 38.5184 304.214 + vertex 121.928 43.3183 302.588 + vertex 143.179 39.9877 304.292 + endloop + endfacet + facet normal 0.0261976 -0.317699 -0.94783 + outer loop + vertex 143.179 39.9877 304.292 + vertex 121.928 43.3183 302.588 + vertex 142.58 44.7781 302.67 + endloop + endfacet + facet normal 0.0220535 -0.318206 -0.947765 + outer loop + vertex 101.86 37.2432 304.163 + vertex 101.429 42.0531 302.538 + vertex 122.449 38.5184 304.214 + endloop + endfacet + facet normal 0.0219939 -0.318512 -0.947664 + outer loop + vertex 122.449 38.5184 304.214 + vertex 101.429 42.0531 302.538 + vertex 121.928 43.3183 302.588 + endloop + endfacet + facet normal 0.0171672 -0.318498 -0.947768 + outer loop + vertex 81.3479 36.1854 304.147 + vertex 81.0063 41.0001 302.523 + vertex 101.86 37.2432 304.163 + endloop + endfacet + facet normal 0.0171395 -0.318632 -0.947723 + outer loop + vertex 101.86 37.2432 304.163 + vertex 81.0063 41.0001 302.523 + vertex 101.429 42.0531 302.538 + endloop + endfacet + facet normal 0.0121556 -0.318896 -0.947712 + outer loop + vertex 60.9173 35.3615 304.162 + vertex 60.6615 40.1767 302.538 + vertex 81.3479 36.1854 304.147 + endloop + endfacet + facet normal 0.0121679 -0.31884 -0.94773 + outer loop + vertex 81.3479 36.1854 304.147 + vertex 60.6615 40.1767 302.538 + vertex 81.0063 41.0001 302.523 + endloop + endfacet + facet normal 0.00728739 -0.318525 -0.947887 + outer loop + vertex 40.5918 34.789 304.198 + vertex 40.42 39.6055 302.578 + vertex 60.9173 35.3615 304.162 + endloop + endfacet + facet normal 0.00714159 -0.319151 -0.947677 + outer loop + vertex 60.9173 35.3615 304.162 + vertex 40.42 39.6055 302.578 + vertex 60.6615 40.1767 302.538 + endloop + endfacet + facet normal 0.00374254 -0.319963 -0.947423 + outer loop + vertex 20.3643 34.454 304.231 + vertex 20.271 39.2575 302.609 + vertex 40.5918 34.789 304.198 + endloop + endfacet + facet normal 0.00406986 -0.318634 -0.947869 + outer loop + vertex 40.5918 34.789 304.198 + vertex 20.271 39.2575 302.609 + vertex 40.42 39.6055 302.578 + endloop + endfacet + facet normal 0.00113694 -0.319809 -0.947481 + outer loop + vertex 0.176449 34.3444 304.244 + vertex 0.164796 39.1478 302.623 + vertex 20.3643 34.454 304.231 + endloop + endfacet + facet normal 0.00108432 -0.320012 -0.947413 + outer loop + vertex 20.3643 34.454 304.231 + vertex 0.164796 39.1478 302.623 + vertex 20.271 39.2575 302.609 + endloop + endfacet + facet normal -0.00104323 -0.319145 -0.947705 + outer loop + vertex -20.0507 34.4551 304.229 + vertex -19.981 39.2646 302.609 + vertex 0.176449 34.3444 304.244 + endloop + endfacet + facet normal -0.00122475 -0.319814 -0.94748 + outer loop + vertex 0.176449 34.3444 304.244 + vertex -19.981 39.2646 302.609 + vertex 0.164796 39.1478 302.623 + endloop + endfacet + facet normal -0.0036975 -0.319413 -0.947608 + outer loop + vertex -40.363 34.7921 304.195 + vertex -40.2109 39.6027 302.573 + vertex -20.0507 34.4551 304.229 + endloop + endfacet + facet normal -0.00361158 -0.31911 -0.947711 + outer loop + vertex -20.0507 34.4551 304.229 + vertex -40.2109 39.6027 302.573 + vertex -19.981 39.2646 302.609 + endloop + endfacet + facet normal -0.00769325 -0.320002 -0.947386 + outer loop + vertex -60.7325 35.3747 304.163 + vertex -60.4957 40.1821 302.538 + vertex -40.363 34.7921 304.195 + endloop + endfacet + facet normal -0.00748552 -0.319299 -0.947624 + outer loop + vertex -40.363 34.7921 304.195 + vertex -60.4957 40.1821 302.538 + vertex -40.2109 39.6027 302.573 + endloop + endfacet + facet normal -0.0115826 -0.318306 -0.947917 + outer loop + vertex -81.08 36.1746 304.143 + vertex -80.755 40.9945 302.521 + vertex -60.7325 35.3747 304.163 + endloop + endfacet + facet normal -0.0120421 -0.319796 -0.94741 + outer loop + vertex -60.7325 35.3747 304.163 + vertex -80.755 40.9945 302.521 + vertex -60.4957 40.1821 302.538 + endloop + endfacet + facet normal -0.0171125 -0.31867 -0.947711 + outer loop + vertex -101.36 37.2151 304.16 + vertex -100.948 42.0277 302.534 + vertex -81.08 36.1746 304.143 + endloop + endfacet + facet normal -0.0168839 -0.317961 -0.947953 + outer loop + vertex -81.08 36.1746 304.143 + vertex -100.948 42.0277 302.534 + vertex -80.755 40.9945 302.521 + endloop + endfacet + facet normal -0.0222089 -0.317893 -0.947866 + outer loop + vertex -121.653 38.4744 304.213 + vertex -121.153 43.2822 302.589 + vertex -101.36 37.2151 304.16 + endloop + endfacet + facet normal -0.0223234 -0.318236 -0.947749 + outer loop + vertex -101.36 37.2151 304.16 + vertex -121.153 43.2822 302.589 + vertex -100.948 42.0277 302.534 + endloop + endfacet + facet normal -0.0255926 -0.315621 -0.94854 + outer loop + vertex -142.16 39.9126 304.288 + vertex -141.595 44.7227 302.672 + vertex -121.653 38.4744 304.213 + endloop + endfacet + facet normal -0.0262265 -0.317487 -0.9479 + outer loop + vertex -121.653 38.4744 304.213 + vertex -141.595 44.7227 302.672 + vertex -121.153 43.2822 302.589 + endloop + endfacet + facet normal -0.0280313 -0.316262 -0.948258 + outer loop + vertex -163.148 41.5158 304.373 + vertex -162.526 46.3052 302.758 + vertex -142.16 39.9126 304.288 + endloop + endfacet + facet normal -0.0277306 -0.315377 -0.948561 + outer loop + vertex -142.16 39.9126 304.288 + vertex -162.526 46.3052 302.758 + vertex -141.595 44.7227 302.672 + endloop + endfacet + facet normal -0.0285933 -0.316776 -0.948069 + outer loop + vertex -184.781 43.2515 304.446 + vertex -184.125 48.0195 302.833 + vertex -163.148 41.5158 304.373 + endloop + endfacet + facet normal -0.0284053 -0.316215 -0.948262 + outer loop + vertex -163.148 41.5158 304.373 + vertex -184.125 48.0195 302.833 + vertex -162.526 46.3052 302.758 + endloop + endfacet + facet normal -0.0276905 -0.315981 -0.948361 + outer loop + vertex -206.964 45.0871 304.482 + vertex -206.292 49.8443 302.877 + vertex -184.781 43.2515 304.446 + endloop + endfacet + facet normal -0.0279808 -0.316857 -0.94806 + outer loop + vertex -184.781 43.2515 304.446 + vertex -206.292 49.8443 302.877 + vertex -184.125 48.0195 302.833 + endloop + endfacet + facet normal -0.0276234 -0.31791 -0.947719 + outer loop + vertex -229.248 47.0135 304.485 + vertex -228.564 51.7414 302.879 + vertex -206.964 45.0871 304.482 + endloop + endfacet + facet normal -0.027011 -0.316074 -0.94835 + outer loop + vertex -206.964 45.0871 304.482 + vertex -228.564 51.7414 302.879 + vertex -206.292 49.8443 302.877 + endloop + endfacet + facet normal -0.0280541 -0.319694 -0.947105 + outer loop + vertex -250.789 48.9642 304.465 + vertex -250.089 53.6588 302.859 + vertex -229.248 47.0135 304.485 + endloop + endfacet + facet normal -0.0274454 -0.317934 -0.947715 + outer loop + vertex -229.248 47.0135 304.485 + vertex -250.089 53.6588 302.859 + vertex -228.564 51.7414 302.879 + endloop + endfacet + facet normal -0.030209 -0.32515 -0.94518 + outer loop + vertex -270.637 50.8615 304.446 + vertex -269.896 55.4831 302.833 + vertex -250.789 48.9642 304.465 + endloop + endfacet + facet normal -0.0281769 -0.319676 -0.947108 + outer loop + vertex -250.789 48.9642 304.465 + vertex -269.896 55.4831 302.833 + vertex -250.089 53.6588 302.859 + endloop + endfacet + facet normal -0.0325124 -0.329937 -0.943443 + outer loop + vertex -288.229 52.6452 304.429 + vertex -287.198 57.1709 302.811 + vertex -270.637 50.8615 304.446 + endloop + endfacet + facet normal -0.0304993 -0.325105 -0.945186 + outer loop + vertex -270.637 50.8615 304.446 + vertex -287.198 57.1709 302.811 + vertex -269.896 55.4831 302.833 + endloop + endfacet + facet normal -0.0313083 -0.335969 -0.941352 + outer loop + vertex -303.619 54.27 304.361 + vertex -302.181 58.7785 302.704 + vertex -288.229 52.6452 304.429 + endloop + endfacet + facet normal -0.0287679 -0.330734 -0.943285 + outer loop + vertex -288.229 52.6452 304.429 + vertex -302.181 58.7785 302.704 + vertex -287.198 57.1709 302.811 + endloop + endfacet + facet normal -0.0219756 -0.356681 -0.933968 + outer loop + vertex -317.354 55.7577 304.116 + vertex -315.391 60.0429 302.433 + vertex -303.619 54.27 304.361 + endloop + endfacet + facet normal -0.0133888 -0.341154 -0.939912 + outer loop + vertex -303.619 54.27 304.361 + vertex -315.391 60.0429 302.433 + vertex -302.181 58.7785 302.704 + endloop + endfacet + facet normal 0.0113985 -0.380705 -0.924626 + outer loop + vertex -325.494 58.1487 303.031 + vertex -323.313 59.8463 302.359 + vertex -317.354 55.7577 304.116 + endloop + endfacet + facet normal 0.017324 -0.343582 -0.938963 + outer loop + vertex -323.052 62.3278 301.456 + vertex -315.391 60.0429 302.433 + vertex -323.313 59.8463 302.359 + endloop + endfacet + facet normal 0.0179388 -0.372553 -0.927838 + outer loop + vertex -315.391 60.0429 302.433 + vertex -317.354 55.7577 304.116 + vertex -323.313 59.8463 302.359 + endloop + endfacet + facet normal 0.0710123 -0.50068 -0.862715 + outer loop + vertex -339.012 59.7051 301.465 + vertex -336.965 61.5233 300.579 + vertex -335.156 59.3521 301.987 + endloop + endfacet + facet normal 0.0944669 -0.485349 -0.869202 + outer loop + vertex -335.156 59.3521 301.987 + vertex -336.965 61.5233 300.579 + vertex -333.38 61.187 301.156 + endloop + endfacet + facet normal 0.101127 -0.447541 -0.888527 + outer loop + vertex -336.965 61.5233 300.579 + vertex -335.128 63.5349 299.774 + vertex -333.38 61.187 301.156 + endloop + endfacet + facet normal 0.119723 -0.435777 -0.892057 + outer loop + vertex -333.38 61.187 301.156 + vertex -335.128 63.5349 299.774 + vertex -331.747 63.261 300.362 + endloop + endfacet + facet normal 0.151111 -0.480407 -0.86393 + outer loop + vertex -339.528 62.9828 299.336 + vertex -337.655 64.8281 298.637 + vertex -338.849 63.2861 299.286 + endloop + endfacet + facet normal 0.250109 -0.53351 -0.807969 + outer loop + vertex -338.849 63.2861 299.286 + vertex -337.655 64.8281 298.637 + vertex -336.969 65.2464 298.573 + endloop + endfacet + facet normal 0.113983 -0.529154 -0.840835 + outer loop + vertex -341.676 61.1489 300.199 + vertex -339.528 62.9828 299.336 + vertex -340.985 61.4266 300.118 + endloop + endfacet + facet normal 0.203584 -0.585009 -0.785059 + outer loop + vertex -340.985 61.4266 300.118 + vertex -339.528 62.9828 299.336 + vertex -338.849 63.2861 299.286 + endloop + endfacet + facet normal 0.111786 -0.509906 -0.852936 + outer loop + vertex -340.985 61.4266 300.118 + vertex -338.849 63.2861 299.286 + vertex -339.505 61.5844 300.217 + endloop + endfacet + facet normal 0.155646 -0.519742 -0.840025 + outer loop + vertex -339.505 61.5844 300.217 + vertex -338.849 63.2861 299.286 + vertex -337.481 63.4743 299.423 + endloop + endfacet + facet normal 0.151135 -0.462457 -0.873666 + outer loop + vertex -338.849 63.2861 299.286 + vertex -336.969 65.2464 298.573 + vertex -337.481 63.4743 299.423 + endloop + endfacet + facet normal 0.191398 -0.46869 -0.862378 + outer loop + vertex -337.481 63.4743 299.423 + vertex -336.969 65.2464 298.573 + vertex -335.742 65.581 298.664 + endloop + endfacet + facet normal 0.161783 -0.575411 -0.801704 + outer loop + vertex -342.26 60.8461 300.298 + vertex -340.005 62.7663 299.375 + vertex -341.676 61.1489 300.199 + endloop + endfacet + facet normal 0.214009 -0.609741 -0.763162 + outer loop + vertex -341.676 61.1489 300.199 + vertex -340.005 62.7663 299.375 + vertex -339.528 62.9828 299.336 + endloop + endfacet + facet normal 0.1597 -0.505581 -0.84787 + outer loop + vertex -340.005 62.7663 299.375 + vertex -338.296 64.3229 298.769 + vertex -339.528 62.9828 299.336 + endloop + endfacet + facet normal 0.335093 -0.611486 -0.716796 + outer loop + vertex -339.528 62.9828 299.336 + vertex -338.296 64.3229 298.769 + vertex -337.655 64.8281 298.637 + endloop + endfacet + facet normal -0.232878 -0.389874 -0.890935 + outer loop + vertex 334.524 66.8567 298.363 + vertex 332.993 69.1859 297.743 + vertex 335.732 67.1235 297.93 + endloop + endfacet + facet normal -0.252466 -0.414391 -0.87438 + outer loop + vertex 335.732 67.1235 297.93 + vertex 332.993 69.1859 297.743 + vertex 334.077 69.5404 297.263 + endloop + endfacet + facet normal -0.217865 -0.439663 -0.871339 + outer loop + vertex 336.156 64.7469 299.019 + vertex 334.524 66.8567 298.363 + vertex 336.969 65.2924 298.541 + endloop + endfacet + facet normal -0.216073 -0.437062 -0.873092 + outer loop + vertex 336.969 65.2924 298.541 + vertex 334.524 66.8567 298.363 + vertex 335.732 67.1235 297.93 + endloop + endfacet + facet normal -0.160898 -0.3296 -0.930309 + outer loop + vertex 329.917 65.7573 299.654 + vertex 328.514 68.2034 299.03 + vertex 332.685 66.436 298.935 + endloop + endfacet + facet normal -0.166989 -0.344317 -0.923884 + outer loop + vertex 332.685 66.436 298.935 + vertex 328.514 68.2034 299.03 + vertex 331.167 68.8448 298.311 + endloop + endfacet + facet normal -0.136685 -0.371966 -0.918128 + outer loop + vertex 331.449 63.4991 300.341 + vertex 329.917 65.7573 299.654 + vertex 334.325 64.2102 299.624 + endloop + endfacet + facet normal -0.141875 -0.386887 -0.911148 + outer loop + vertex 334.325 64.2102 299.624 + vertex 329.917 65.7573 299.654 + vertex 332.685 66.436 298.935 + endloop + endfacet + facet normal -0.176563 -0.40771 -0.895878 + outer loop + vertex 334.325 64.2102 299.624 + vertex 332.685 66.436 298.935 + vertex 336.156 64.7469 299.019 + endloop + endfacet + facet normal -0.181405 -0.41739 -0.890437 + outer loop + vertex 336.156 64.7469 299.019 + vertex 332.685 66.436 298.935 + vertex 334.524 66.8567 298.363 + endloop + endfacet + facet normal -0.200335 -0.361857 -0.910453 + outer loop + vertex 332.685 66.436 298.935 + vertex 331.167 68.8448 298.311 + vertex 334.524 66.8567 298.363 + endloop + endfacet + facet normal -0.209804 -0.377623 -0.901877 + outer loop + vertex 334.524 66.8567 298.363 + vertex 331.167 68.8448 298.311 + vertex 332.993 69.1859 297.743 + endloop + endfacet + facet normal -0.0764702 -0.267693 -0.960465 + outer loop + vertex 321.444 63.6717 301.114 + vertex 321.309 66.0917 300.45 + vertex 326.294 64.7905 300.416 + endloop + endfacet + facet normal -0.0796797 -0.280087 -0.956662 + outer loop + vertex 326.294 64.7905 300.416 + vertex 321.309 66.0917 300.45 + vertex 325.051 67.2428 299.801 + endloop + endfacet + facet normal -0.0622682 -0.323235 -0.944268 + outer loop + vertex 323.634 61.3853 301.752 + vertex 321.444 63.6717 301.114 + vertex 327.664 62.5252 301.096 + endloop + endfacet + facet normal -0.0618967 -0.321208 -0.944984 + outer loop + vertex 327.664 62.5252 301.096 + vertex 321.444 63.6717 301.114 + vertex 326.294 64.7905 300.416 + endloop + endfacet + facet normal -0.0990022 -0.340648 -0.934964 + outer loop + vertex 327.664 62.5252 301.096 + vertex 326.294 64.7905 300.416 + vertex 331.449 63.4991 300.341 + endloop + endfacet + facet normal -0.101787 -0.35203 -0.930438 + outer loop + vertex 331.449 63.4991 300.341 + vertex 326.294 64.7905 300.416 + vertex 329.917 65.7573 299.654 + endloop + endfacet + facet normal -0.119709 -0.297969 -0.94704 + outer loop + vertex 326.294 64.7905 300.416 + vertex 325.051 67.2428 299.801 + vertex 329.917 65.7573 299.654 + endloop + endfacet + facet normal -0.123627 -0.311282 -0.942242 + outer loop + vertex 329.917 65.7573 299.654 + vertex 325.051 67.2428 299.801 + vertex 328.514 68.2034 299.03 + endloop + endfacet + facet normal -0.0454989 -0.266591 -0.962735 + outer loop + vertex 321.309 66.0917 300.45 + vertex 321.444 63.6717 301.114 + vertex 313.371 66.3356 300.758 + endloop + endfacet + facet normal -0.0273852 -0.293013 -0.955716 + outer loop + vertex 323.634 61.3853 301.752 + vertex 315.185 61.418 301.984 + vertex 321.444 63.6717 301.114 + endloop + endfacet + facet normal -0.0419807 -0.256322 -0.965679 + outer loop + vertex 315.185 61.418 301.984 + vertex 313.371 66.3356 300.758 + vertex 321.444 63.6717 301.114 + endloop + endfacet + facet normal -0.00224766 -0.248379 -0.96866 + outer loop + vertex 302.827 59.2168 302.577 + vertex 301.464 64.1726 301.31 + vertex 315.185 61.418 301.984 + endloop + endfacet + facet normal -0.000954873 -0.242317 -0.970197 + outer loop + vertex 315.185 61.418 301.984 + vertex 301.464 64.1726 301.31 + vertex 313.371 66.3356 300.758 + endloop + endfacet + facet normal 0.016259 -0.246197 -0.969083 + outer loop + vertex 287.983 57.1903 302.843 + vertex 286.985 62.2042 301.552 + vertex 302.827 59.2168 302.577 + endloop + endfacet + facet normal 0.0168279 -0.243417 -0.969776 + outer loop + vertex 302.827 59.2168 302.577 + vertex 286.985 62.2042 301.552 + vertex 301.464 64.1726 301.31 + endloop + endfacet + facet normal 0.0218174 -0.244493 -0.969406 + outer loop + vertex 270.448 55.3518 302.912 + vertex 269.676 60.4246 301.615 + vertex 287.983 57.1903 302.843 + endloop + endfacet + facet normal 0.0216891 -0.245156 -0.969241 + outer loop + vertex 287.983 57.1903 302.843 + vertex 269.676 60.4246 301.615 + vertex 286.985 62.2042 301.552 + endloop + endfacet + facet normal 0.0220642 -0.240801 -0.970324 + outer loop + vertex 250.565 53.5776 302.9 + vertex 249.868 58.7149 301.609 + vertex 270.448 55.3518 302.912 + endloop + endfacet + facet normal 0.0213921 -0.244556 -0.969399 + outer loop + vertex 270.448 55.3518 302.912 + vertex 249.868 58.7149 301.609 + vertex 269.676 60.4246 301.615 + endloop + endfacet + facet normal 0.0207732 -0.239336 -0.970715 + outer loop + vertex 229.071 51.7839 302.883 + vertex 228.416 56.9637 301.591 + vertex 250.565 53.5776 302.9 + endloop + endfacet + facet normal 0.0204931 -0.24101 -0.970306 + outer loop + vertex 250.565 53.5776 302.9 + vertex 228.416 56.9637 301.591 + vertex 249.868 58.7149 301.609 + endloop + endfacet + facet normal 0.0204125 -0.238049 -0.971039 + outer loop + vertex 206.964 49.9562 302.866 + vertex 206.31 55.1673 301.575 + vertex 229.071 51.7839 302.883 + endloop + endfacet + facet normal 0.0201917 -0.239408 -0.970709 + outer loop + vertex 229.071 51.7839 302.883 + vertex 206.31 55.1673 301.575 + vertex 228.416 56.9637 301.591 + endloop + endfacet + facet normal 0.0213398 -0.236586 -0.971376 + outer loop + vertex 185.005 48.1373 302.826 + vertex 184.367 53.3757 301.537 + vertex 206.964 49.9562 302.866 + endloop + endfacet + facet normal 0.021112 -0.237963 -0.971045 + outer loop + vertex 206.964 49.9562 302.866 + vertex 184.367 53.3757 301.537 + vertex 206.31 55.1673 301.575 + endloop + endfacet + facet normal 0.0221475 -0.237983 -0.971017 + outer loop + vertex 163.555 46.4047 302.762 + vertex 162.939 51.6469 301.463 + vertex 185.005 48.1373 302.826 + endloop + endfacet + facet normal 0.0224128 -0.236457 -0.971383 + outer loop + vertex 185.005 48.1373 302.826 + vertex 162.939 51.6469 301.463 + vertex 184.367 53.3757 301.537 + endloop + endfacet + facet normal 0.0226172 -0.236752 -0.971307 + outer loop + vertex 142.58 44.7781 302.67 + vertex 142.034 50.0431 301.374 + vertex 163.555 46.4047 302.762 + endloop + endfacet + facet normal 0.0223953 -0.237954 -0.971018 + outer loop + vertex 163.555 46.4047 302.762 + vertex 142.034 50.0431 301.374 + vertex 162.939 51.6469 301.463 + endloop + endfacet + facet normal 0.0206135 -0.2374 -0.971193 + outer loop + vertex 121.928 43.3183 302.588 + vertex 121.455 48.5895 301.29 + vertex 142.58 44.7781 302.67 + endloop + endfacet + facet normal 0.0207017 -0.236949 -0.971301 + outer loop + vertex 142.58 44.7781 302.67 + vertex 121.455 48.5895 301.29 + vertex 142.034 50.0431 301.374 + endloop + endfacet + facet normal 0.0172272 -0.240364 -0.97053 + outer loop + vertex 101.429 42.0531 302.538 + vertex 101.032 47.3115 301.229 + vertex 121.928 43.3183 302.588 + endloop + endfacet + facet normal 0.0177883 -0.237652 -0.971187 + outer loop + vertex 121.928 43.3183 302.588 + vertex 101.032 47.3115 301.229 + vertex 121.455 48.5895 301.29 + endloop + endfacet + facet normal 0.0131212 -0.240364 -0.970594 + outer loop + vertex 81.0063 41.0001 302.523 + vertex 80.6931 46.2627 301.215 + vertex 101.429 42.0531 302.538 + endloop + endfacet + facet normal 0.0130529 -0.240676 -0.970518 + outer loop + vertex 101.429 42.0531 302.538 + vertex 80.6931 46.2627 301.215 + vertex 101.032 47.3115 301.229 + endloop + endfacet + facet normal 0.00894641 -0.239687 -0.970809 + outer loop + vertex 60.6615 40.1767 302.538 + vertex 60.4289 45.4456 301.235 + vertex 81.0063 41.0001 302.523 + endloop + endfacet + facet normal 0.00873001 -0.240622 -0.97058 + outer loop + vertex 81.0063 41.0001 302.523 + vertex 60.4289 45.4456 301.235 + vertex 80.6931 46.2627 301.215 + endloop + endfacet + facet normal 0.00490444 -0.241457 -0.970399 + outer loop + vertex 40.42 39.6055 302.578 + vertex 40.2581 44.8596 301.27 + vertex 60.6615 40.1767 302.538 + endloop + endfacet + facet normal 0.0052993 -0.239845 -0.970797 + outer loop + vertex 60.6615 40.1767 302.538 + vertex 40.2581 44.8596 301.27 + vertex 60.4289 45.4456 301.235 + endloop + endfacet + facet normal 0.00267741 -0.240029 -0.970762 + outer loop + vertex 20.271 39.2575 302.609 + vertex 20.1842 44.5203 301.307 + vertex 40.42 39.6055 302.578 + endloop + endfacet + facet normal 0.00228813 -0.241536 -0.970389 + outer loop + vertex 40.42 39.6055 302.578 + vertex 20.1842 44.5203 301.307 + vertex 40.2581 44.8596 301.27 + endloop + endfacet + facet normal 0.000633071 -0.240277 -0.970704 + outer loop + vertex 0.164796 39.1478 302.623 + vertex 0.148762 44.4072 301.321 + vertex 20.271 39.2575 302.609 + endloop + endfacet + facet normal 0.000691959 -0.240061 -0.970758 + outer loop + vertex 20.271 39.2575 302.609 + vertex 0.148762 44.4072 301.321 + vertex 20.1842 44.5203 301.307 + endloop + endfacet + facet normal -0.000747857 -0.240251 -0.97071 + outer loop + vertex -19.981 39.2646 302.609 + vertex -19.9249 44.5249 301.307 + vertex 0.164796 39.1478 302.623 + endloop + endfacet + facet normal -0.000756483 -0.240281 -0.970703 + outer loop + vertex 0.164796 39.1478 302.623 + vertex -19.9249 44.5249 301.307 + vertex 0.148762 44.4072 301.321 + endloop + endfacet + facet normal -0.00225338 -0.240335 -0.970687 + outer loop + vertex -40.2109 39.6027 302.573 + vertex -40.0811 44.8655 301.269 + vertex -19.981 39.2646 302.609 + endloop + endfacet + facet normal -0.00222411 -0.240236 -0.970712 + outer loop + vertex -19.981 39.2646 302.609 + vertex -40.0811 44.8655 301.269 + vertex -19.9249 44.5249 301.307 + endloop + endfacet + facet normal -0.00519546 -0.240518 -0.970631 + outer loop + vertex -60.4957 40.1821 302.538 + vertex -60.2896 45.4459 301.232 + vertex -40.2109 39.6027 302.573 + endloop + endfacet + facet normal -0.00511771 -0.240266 -0.970694 + outer loop + vertex -40.2109 39.6027 302.573 + vertex -60.2896 45.4459 301.232 + vertex -40.0811 44.8655 301.269 + endloop + endfacet + facet normal -0.00882245 -0.239987 -0.970736 + outer loop + vertex -80.755 40.9945 302.521 + vertex -80.4689 46.2623 301.216 + vertex -60.4957 40.1821 302.538 + endloop + endfacet + facet normal -0.00894664 -0.240374 -0.970639 + outer loop + vertex -60.4957 40.1821 302.538 + vertex -80.4689 46.2623 301.216 + vertex -60.2896 45.4459 301.232 + endloop + endfacet + facet normal -0.0128918 -0.239652 -0.970773 + outer loop + vertex -100.948 42.0277 302.534 + vertex -100.58 47.2962 301.228 + vertex -80.755 40.9945 302.521 + endloop + endfacet + facet normal -0.0129299 -0.239766 -0.970745 + outer loop + vertex -80.755 40.9945 302.521 + vertex -100.58 47.2962 301.228 + vertex -80.4689 46.2623 301.216 + endloop + endfacet + facet normal -0.017447 -0.238684 -0.970941 + outer loop + vertex -121.153 43.2822 302.589 + vertex -120.705 48.5498 301.286 + vertex -100.948 42.0277 302.534 + endloop + endfacet + facet normal -0.0176672 -0.23932 -0.97078 + outer loop + vertex -100.948 42.0277 302.534 + vertex -120.705 48.5498 301.286 + vertex -100.58 47.2962 301.228 + endloop + endfacet + facet normal -0.020799 -0.239143 -0.970762 + outer loop + vertex -141.595 44.7227 302.672 + vertex -141.067 49.9762 301.366 + vertex -121.153 43.2822 302.589 + endloop + endfacet + facet normal -0.0205452 -0.238421 -0.970944 + outer loop + vertex -121.153 43.2822 302.589 + vertex -141.067 49.9762 301.366 + vertex -120.705 48.5498 301.286 + endloop + endfacet + facet normal -0.021913 -0.237203 -0.971213 + outer loop + vertex -162.526 46.3052 302.758 + vertex -161.953 51.5593 301.461 + vertex -141.595 44.7227 302.672 + endloop + endfacet + facet normal -0.022533 -0.23897 -0.970766 + outer loop + vertex -141.595 44.7227 302.672 + vertex -161.953 51.5593 301.461 + vertex -141.067 49.9762 301.366 + endloop + endfacet + facet normal -0.0222029 -0.237057 -0.971242 + outer loop + vertex -184.125 48.0195 302.833 + vertex -183.515 53.2596 301.54 + vertex -162.526 46.3052 302.758 + endloop + endfacet + facet normal -0.0222411 -0.237167 -0.971214 + outer loop + vertex -162.526 46.3052 302.758 + vertex -183.515 53.2596 301.54 + vertex -161.953 51.5593 301.461 + endloop + endfacet + facet normal -0.0214781 -0.237304 -0.971198 + outer loop + vertex -206.292 49.8443 302.877 + vertex -205.642 55.0656 301.587 + vertex -184.125 48.0195 302.833 + endloop + endfacet + facet normal -0.0214243 -0.237147 -0.971238 + outer loop + vertex -184.125 48.0195 302.833 + vertex -205.642 55.0656 301.587 + vertex -183.515 53.2596 301.54 + endloop + endfacet + facet normal -0.0203307 -0.237622 -0.971145 + outer loop + vertex -228.564 51.7414 302.879 + vertex -227.869 56.9429 301.592 + vertex -206.292 49.8443 302.877 + endloop + endfacet + facet normal -0.020272 -0.237452 -0.971188 + outer loop + vertex -206.292 49.8443 302.877 + vertex -227.869 56.9429 301.592 + vertex -205.642 55.0656 301.587 + endloop + endfacet + facet normal -0.0203998 -0.239076 -0.970787 + outer loop + vertex -250.089 53.6588 302.859 + vertex -249.362 58.8257 301.572 + vertex -228.564 51.7414 302.879 + endloop + endfacet + facet normal -0.0199016 -0.237678 -0.97114 + outer loop + vertex -228.564 51.7414 302.879 + vertex -249.362 58.8257 301.572 + vertex -227.869 56.9429 301.592 + endloop + endfacet + facet normal -0.0210199 -0.242308 -0.969972 + outer loop + vertex -269.896 55.4831 302.833 + vertex -269.124 60.5798 301.543 + vertex -250.089 53.6588 302.859 + endloop + endfacet + facet normal -0.019818 -0.239156 -0.970779 + outer loop + vertex -250.089 53.6588 302.859 + vertex -269.124 60.5798 301.543 + vertex -249.362 58.8257 301.572 + endloop + endfacet + facet normal -0.0230421 -0.248961 -0.968239 + outer loop + vertex -287.198 57.1709 302.811 + vertex -286.209 62.0937 301.521 + vertex -269.896 55.4831 302.833 + endloop + endfacet + facet normal -0.0202535 -0.242421 -0.96996 + outer loop + vertex -269.896 55.4831 302.833 + vertex -286.209 62.0937 301.521 + vertex -269.124 60.5798 301.543 + endloop + endfacet + facet normal -0.0203051 -0.253445 -0.967137 + outer loop + vertex -302.181 58.7785 302.704 + vertex -300.441 63.5083 301.428 + vertex -287.198 57.1709 302.811 + endloop + endfacet + facet normal -0.0184801 -0.249844 -0.96811 + outer loop + vertex -287.198 57.1709 302.811 + vertex -300.441 63.5083 301.428 + vertex -286.209 62.0937 301.521 + endloop + endfacet + facet normal -0.00522478 -0.261282 -0.965248 + outer loop + vertex -315.391 60.0429 302.433 + vertex -313.673 65.5224 300.941 + vertex -302.181 58.7785 302.704 + endloop + endfacet + facet normal -0.0038765 -0.259137 -0.965833 + outer loop + vertex -302.181 58.7785 302.704 + vertex -313.673 65.5224 300.941 + vertex -300.441 63.5083 301.428 + endloop + endfacet + facet normal 0.0375209 -0.28404 -0.958078 + outer loop + vertex -323.052 62.3278 301.456 + vertex -321.067 64.5608 300.872 + vertex -315.391 60.0429 302.433 + endloop + endfacet + facet normal 0.0420064 -0.2535 -0.966423 + outer loop + vertex -320.975 67.4991 300.105 + vertex -313.673 65.5224 300.941 + vertex -321.067 64.5608 300.872 + endloop + endfacet + facet normal 0.0448239 -0.275608 -0.960225 + outer loop + vertex -313.673 65.5224 300.941 + vertex -315.391 60.0429 302.433 + vertex -321.067 64.5608 300.872 + endloop + endfacet + facet normal 0.125792 -0.39728 -0.909035 + outer loop + vertex -335.128 63.5349 299.774 + vertex -333.403 66.1982 298.849 + vertex -331.747 63.261 300.362 + endloop + endfacet + facet normal 0.144063 -0.38771 -0.910454 + outer loop + vertex -331.747 63.261 300.362 + vertex -333.403 66.1982 298.849 + vertex -330.178 65.5088 299.653 + endloop + endfacet + facet normal 0.157818 -0.341938 -0.926376 + outer loop + vertex -333.403 66.1982 298.849 + vertex -331.398 68.1455 298.472 + vertex -330.178 65.5088 299.653 + endloop + endfacet + facet normal 0.166246 -0.338024 -0.926338 + outer loop + vertex -330.178 65.5088 299.653 + vertex -331.398 68.1455 298.472 + vertex -328.692 68.0168 299.004 + endloop + endfacet + facet normal 0.203724 -0.395045 -0.895788 + outer loop + vertex -335.902 66.8896 297.982 + vertex -334.264 69.205 297.333 + vertex -335.308 67.3928 297.895 + endloop + endfacet + facet normal 0.415641 -0.479112 -0.773107 + outer loop + vertex -335.308 67.3928 297.895 + vertex -334.264 69.205 297.333 + vertex -333.764 69.7349 297.274 + endloop + endfacet + facet normal 0.184556 -0.436969 -0.88034 + outer loop + vertex -337.655 64.8281 298.637 + vertex -335.902 66.8896 297.982 + vertex -336.969 65.2464 298.573 + endloop + endfacet + facet normal 0.291461 -0.486069 -0.823886 + outer loop + vertex -336.969 65.2464 298.573 + vertex -335.902 66.8896 297.982 + vertex -335.308 67.3928 297.895 + endloop + endfacet + facet normal 0.18028 -0.420683 -0.889115 + outer loop + vertex -336.969 65.2464 298.573 + vertex -335.308 67.3928 297.895 + vertex -335.742 65.581 298.664 + endloop + endfacet + facet normal 0.23092 -0.426577 -0.874476 + outer loop + vertex -335.742 65.581 298.664 + vertex -335.308 67.3928 297.895 + vertex -334.457 67.7273 297.956 + endloop + endfacet + facet normal 0.214458 -0.380007 -0.899779 + outer loop + vertex -335.308 67.3928 297.895 + vertex -333.764 69.7349 297.274 + vertex -334.457 67.7273 297.956 + endloop + endfacet + facet normal 0.266308 -0.391463 -0.880816 + outer loop + vertex -334.457 67.7273 297.956 + vertex -333.764 69.7349 297.274 + vertex -332.724 69.7913 297.563 + endloop + endfacet + facet normal 0.176248 -0.451272 -0.874809 + outer loop + vertex -338.296 64.3229 298.769 + vertex -336.733 66.1619 298.135 + vertex -337.655 64.8281 298.637 + endloop + endfacet + facet normal 0.29692 -0.509435 -0.80766 + outer loop + vertex -337.655 64.8281 298.637 + vertex -336.733 66.1619 298.135 + vertex -335.902 66.8896 297.982 + endloop + endfacet + facet normal 0.197598 -0.413119 -0.888981 + outer loop + vertex -336.733 66.1619 298.135 + vertex -334.952 68.4899 297.449 + vertex -335.902 66.8896 297.982 + endloop + endfacet + facet normal 0.367528 -0.48264 -0.794973 + outer loop + vertex -335.902 66.8896 297.982 + vertex -334.952 68.4899 297.449 + vertex -334.264 69.205 297.333 + endloop + endfacet + facet normal -0.324162 -0.317246 -0.891221 + outer loop + vertex 331.557 71.753 297.154 + vertex 330.534 74.4487 296.567 + vertex 332.643 71.9881 296.675 + endloop + endfacet + facet normal -0.365542 -0.351415 -0.861909 + outer loop + vertex 332.643 71.9881 296.675 + vertex 330.534 74.4487 296.567 + vertex 331.794 73.8448 296.278 + endloop + endfacet + facet normal -0.277605 -0.3598 -0.890775 + outer loop + vertex 332.993 69.1859 297.743 + vertex 331.557 71.753 297.154 + vertex 334.077 69.5404 297.263 + endloop + endfacet + facet normal -0.301006 -0.385542 -0.872211 + outer loop + vertex 334.077 69.5404 297.263 + vertex 331.557 71.753 297.154 + vertex 332.643 71.9881 296.675 + endloop + endfacet + facet normal -0.205983 -0.254786 -0.944804 + outer loop + vertex 327.22 70.8137 298.468 + vertex 326.054 73.6083 297.968 + vertex 329.771 71.4593 297.738 + endloop + endfacet + facet normal -0.209347 -0.260863 -0.942403 + outer loop + vertex 329.771 71.4593 297.738 + vertex 326.054 73.6083 297.968 + vertex 328.506 74.4512 297.19 + endloop + endfacet + facet normal -0.183363 -0.292869 -0.938406 + outer loop + vertex 328.514 68.2034 299.03 + vertex 327.22 70.8137 298.468 + vertex 331.167 68.8448 298.311 + endloop + endfacet + facet normal -0.189657 -0.305916 -0.932977 + outer loop + vertex 331.167 68.8448 298.311 + vertex 327.22 70.8137 298.468 + vertex 329.771 71.4593 297.738 + endloop + endfacet + facet normal -0.225616 -0.322131 -0.919418 + outer loop + vertex 331.167 68.8448 298.311 + vertex 329.771 71.4593 297.738 + vertex 332.993 69.1859 297.743 + endloop + endfacet + facet normal -0.240292 -0.3429 -0.908119 + outer loop + vertex 332.993 69.1859 297.743 + vertex 329.771 71.4593 297.738 + vertex 331.557 71.753 297.154 + endloop + endfacet + facet normal -0.25673 -0.277849 -0.925684 + outer loop + vertex 329.771 71.4593 297.738 + vertex 328.506 74.4512 297.19 + vertex 331.557 71.753 297.154 + endloop + endfacet + facet normal -0.280361 -0.304777 -0.910225 + outer loop + vertex 331.557 71.753 297.154 + vertex 328.506 74.4512 297.19 + vertex 330.534 74.4487 296.567 + endloop + endfacet + facet normal -0.103873 -0.198365 -0.974609 + outer loop + vertex 319.374 68.7162 299.96 + vertex 319.357 71.3848 299.419 + vertex 323.902 69.8504 299.247 + endloop + endfacet + facet normal -0.108931 -0.213774 -0.970791 + outer loop + vertex 323.902 69.8504 299.247 + vertex 319.357 71.3848 299.419 + vertex 322.861 72.5723 298.764 + endloop + endfacet + facet normal -0.0911675 -0.247253 -0.964653 + outer loop + vertex 321.309 66.0917 300.45 + vertex 319.374 68.7162 299.96 + vertex 325.051 67.2428 299.801 + endloop + endfacet + facet normal -0.0906559 -0.245221 -0.965219 + outer loop + vertex 325.051 67.2428 299.801 + vertex 319.374 68.7162 299.96 + vertex 323.902 69.8504 299.247 + endloop + endfacet + facet normal -0.139332 -0.264347 -0.95431 + outer loop + vertex 325.051 67.2428 299.801 + vertex 323.902 69.8504 299.247 + vertex 328.514 68.2034 299.03 + endloop + endfacet + facet normal -0.143156 -0.27555 -0.950567 + outer loop + vertex 328.514 68.2034 299.03 + vertex 323.902 69.8504 299.247 + vertex 327.22 70.8137 298.468 + endloop + endfacet + facet normal -0.158375 -0.230775 -0.960031 + outer loop + vertex 323.902 69.8504 299.247 + vertex 322.861 72.5723 298.764 + vertex 327.22 70.8137 298.468 + endloop + endfacet + facet normal -0.161311 -0.23845 -0.957664 + outer loop + vertex 327.22 70.8137 298.468 + vertex 322.861 72.5723 298.764 + vertex 326.054 73.6083 297.968 + endloop + endfacet + facet normal -0.0612273 -0.198796 -0.978126 + outer loop + vertex 319.357 71.3848 299.419 + vertex 319.374 68.7162 299.96 + vertex 311.813 71.7192 299.823 + endloop + endfacet + facet normal -0.0444089 -0.214831 -0.975641 + outer loop + vertex 321.309 66.0917 300.45 + vertex 313.371 66.3356 300.758 + vertex 319.374 68.7162 299.96 + endloop + endfacet + facet normal -0.0563138 -0.186547 -0.980831 + outer loop + vertex 313.371 66.3356 300.758 + vertex 311.813 71.7192 299.823 + vertex 319.374 68.7162 299.96 + endloop + endfacet + facet normal 0.058274 -0.198458 -0.978375 + outer loop + vertex -320.975 67.4991 300.105 + vertex -319.907 69.9965 299.662 + vertex -313.673 65.5224 300.941 + endloop + endfacet + facet normal 0.169965 -0.304675 -0.937169 + outer loop + vertex -331.398 68.1455 298.472 + vertex -330.201 71.2577 297.677 + vertex -328.692 68.0168 299.004 + endloop + endfacet + facet normal 0.190784 -0.294654 -0.936365 + outer loop + vertex -328.692 68.0168 299.004 + vertex -330.201 71.2577 297.677 + vertex -327.161 70.7076 298.47 + endloop + endfacet + facet normal 0.20271 -0.245468 -0.947973 + outer loop + vertex -330.201 71.2577 297.677 + vertex -327.794 74.1345 297.447 + vertex -327.161 70.7076 298.47 + endloop + endfacet + facet normal 0.188333 -0.248755 -0.95008 + outer loop + vertex -327.161 70.7076 298.47 + vertex -327.794 74.1345 297.447 + vertex -325.627 72.8017 298.225 + endloop + endfacet + facet normal 0.388488 -0.335701 -0.858127 + outer loop + vertex -332.805 71.7726 296.718 + vertex -331.385 74.8377 296.162 + vertex -332.251 72.4729 296.695 + endloop + endfacet + facet normal 0.401812 -0.338906 -0.850699 + outer loop + vertex -332.251 72.4729 296.695 + vertex -331.385 74.8377 296.162 + vertex -330.431 75.5647 296.323 + endloop + endfacet + facet normal 0.297352 -0.378898 -0.876366 + outer loop + vertex -334.264 69.205 297.333 + vertex -332.805 71.7726 296.718 + vertex -333.764 69.7349 297.274 + endloop + endfacet + facet normal 0.53518 -0.447165 -0.716676 + outer loop + vertex -333.764 69.7349 297.274 + vertex -332.805 71.7726 296.718 + vertex -332.251 72.4729 296.695 + endloop + endfacet + facet normal 0.26919 -0.33928 -0.901347 + outer loop + vertex -333.764 69.7349 297.274 + vertex -332.251 72.4729 296.695 + vertex -332.724 69.7913 297.563 + endloop + endfacet + facet normal 0.308826 -0.341808 -0.887578 + outer loop + vertex -332.724 69.7913 297.563 + vertex -332.251 72.4729 296.695 + vertex -331.371 72.8476 296.856 + endloop + endfacet + facet normal 0.28751 -0.279469 -0.916098 + outer loop + vertex -332.251 72.4729 296.695 + vertex -330.431 75.5647 296.323 + vertex -331.371 72.8476 296.856 + endloop + endfacet + facet normal 0.278775 -0.277114 -0.919507 + outer loop + vertex -331.371 72.8476 296.856 + vertex -330.431 75.5647 296.323 + vertex -329.722 74.7041 296.797 + endloop + endfacet + facet normal 0.249925 -0.384677 -0.888572 + outer loop + vertex -334.952 68.4899 297.449 + vertex -333.371 70.9937 296.81 + vertex -334.264 69.205 297.333 + endloop + endfacet + facet normal 0.536679 -0.472415 -0.699143 + outer loop + vertex -334.264 69.205 297.333 + vertex -333.371 70.9937 296.81 + vertex -332.805 71.7726 296.718 + endloop + endfacet + facet normal 0.354001 -0.359099 -0.863557 + outer loop + vertex -333.371 70.9937 296.81 + vertex -332.151 73.4429 296.291 + vertex -332.805 71.7726 296.718 + endloop + endfacet + facet normal 0.651717 -0.416941 -0.633581 + outer loop + vertex -332.805 71.7726 296.718 + vertex -332.151 73.4429 296.291 + vertex -331.385 74.8377 296.162 + endloop + endfacet + facet normal -0.227167 -0.215735 -0.94966 + outer loop + vertex 326.054 73.6083 297.968 + vertex 324.912 76.6825 297.543 + vertex 328.506 74.4512 297.19 + endloop + endfacet + facet normal -0.286555 -0.227457 -0.930672 + outer loop + vertex 330.534 74.4487 296.567 + vertex 328.506 74.4512 297.19 + vertex 327.111 78.8791 296.538 + endloop + endfacet + facet normal -0.250863 -0.183918 -0.95039 + outer loop + vertex 323.568 79.4443 297.364 + vertex 327.111 78.8791 296.538 + vertex 324.912 76.6825 297.543 + endloop + endfacet + facet normal -0.224352 -0.210925 -0.951408 + outer loop + vertex 328.506 74.4512 297.19 + vertex 324.912 76.6825 297.543 + vertex 327.111 78.8791 296.538 + endloop + endfacet + facet normal -0.127702 -0.138031 -0.982161 + outer loop + vertex 317.644 74.1988 299.083 + vertex 317.746 76.9867 298.677 + vertex 321.921 75.3967 298.358 + endloop + endfacet + facet normal -0.130403 -0.14541 -0.98074 + outer loop + vertex 321.921 75.3967 298.358 + vertex 317.746 76.9867 298.677 + vertex 321.034 78.2486 298.053 + endloop + endfacet + facet normal -0.118261 -0.18852 -0.974923 + outer loop + vertex 319.357 71.3848 299.419 + vertex 317.644 74.1988 299.083 + vertex 322.861 72.5723 298.764 + endloop + endfacet + facet normal -0.115394 -0.178904 -0.977076 + outer loop + vertex 322.861 72.5723 298.764 + vertex 317.644 74.1988 299.083 + vertex 321.921 75.3967 298.358 + endloop + endfacet + facet normal -0.176313 -0.197339 -0.96435 + outer loop + vertex 322.861 72.5723 298.764 + vertex 321.921 75.3967 298.358 + vertex 326.054 73.6083 297.968 + endloop + endfacet + facet normal -0.177014 -0.199065 -0.963867 + outer loop + vertex 326.054 73.6083 297.968 + vertex 321.921 75.3967 298.358 + vertex 324.912 76.6825 297.543 + endloop + endfacet + facet normal -0.193257 -0.163535 -0.967423 + outer loop + vertex 321.921 75.3967 298.358 + vertex 321.034 78.2486 298.053 + vertex 324.912 76.6825 297.543 + endloop + endfacet + facet normal -0.190335 -0.155689 -0.969296 + outer loop + vertex 324.912 76.6825 297.543 + vertex 321.034 78.2486 298.053 + vertex 323.568 79.4443 297.364 + endloop + endfacet + facet normal -0.0735885 -0.140762 -0.987305 + outer loop + vertex 317.746 76.9867 298.677 + vertex 317.644 74.1988 299.083 + vertex 310.48 77.3782 299.163 + endloop + endfacet + facet normal -0.0596856 -0.154218 -0.986232 + outer loop + vertex 319.357 71.3848 299.419 + vertex 311.813 71.7192 299.823 + vertex 317.644 74.1988 299.083 + endloop + endfacet + facet normal -0.0695881 -0.13171 -0.988843 + outer loop + vertex 311.813 71.7192 299.823 + vertex 310.48 77.3782 299.163 + vertex 317.644 74.1988 299.083 + endloop + endfacet + facet normal 0.312032 -0.248358 -0.917036 + outer loop + vertex -329.722 74.7041 296.797 + vertex -330.431 75.5647 296.323 + vertex -327.132 78.9298 296.534 + endloop + endfacet + facet normal 0.344601 -0.251907 -0.904319 + outer loop + vertex -331.385 74.8377 296.162 + vertex -329.498 78.8904 295.752 + vertex -330.431 75.5647 296.323 + endloop + endfacet + facet normal 0.307997 -0.244248 -0.9195 + outer loop + vertex -329.498 78.8904 295.752 + vertex -327.132 78.9298 296.534 + vertex -330.431 75.5647 296.323 + endloop + endfacet + facet normal -0.246393 -0.144221 -0.958379 + outer loop + vertex 323.568 79.4443 297.364 + vertex 323.23 82.3139 297.019 + vertex 327.111 78.8791 296.538 + endloop + endfacet + facet normal -0.28277 -0.13601 -0.949496 + outer loop + vertex 322.047 85.3643 296.934 + vertex 325.074 85.0665 296.075 + vertex 323.23 82.3139 297.019 + endloop + endfacet + facet normal -0.255916 -0.155583 -0.954097 + outer loop + vertex 325.074 85.0665 296.075 + vertex 327.111 78.8791 296.538 + vertex 323.23 82.3139 297.019 + endloop + endfacet + facet normal -0.141999 -0.0881448 -0.985935 + outer loop + vertex 316.245 79.8935 298.496 + vertex 316.463 82.7588 298.208 + vertex 320.305 81.1101 297.802 + endloop + endfacet + facet normal -0.146399 -0.0988048 -0.984279 + outer loop + vertex 320.305 81.1101 297.802 + vertex 316.463 82.7588 298.208 + vertex 319.64 84.0499 297.606 + endloop + endfacet + facet normal -0.135948 -0.131558 -0.981942 + outer loop + vertex 317.746 76.9867 298.677 + vertex 316.245 79.8935 298.496 + vertex 321.034 78.2486 298.053 + endloop + endfacet + facet normal -0.132137 -0.119921 -0.983951 + outer loop + vertex 321.034 78.2486 298.053 + vertex 316.245 79.8935 298.496 + vertex 320.305 81.1101 297.802 + endloop + endfacet + facet normal -0.199908 -0.135997 -0.970331 + outer loop + vertex 321.034 78.2486 298.053 + vertex 320.305 81.1101 297.802 + vertex 323.568 79.4443 297.364 + endloop + endfacet + facet normal -0.201962 -0.140292 -0.969293 + outer loop + vertex 323.568 79.4443 297.364 + vertex 320.305 81.1101 297.802 + vertex 323.23 82.3139 297.019 + endloop + endfacet + facet normal -0.213472 -0.113041 -0.970387 + outer loop + vertex 320.305 81.1101 297.802 + vertex 319.64 84.0499 297.606 + vertex 323.23 82.3139 297.019 + endloop + endfacet + facet normal -0.21168 -0.10905 -0.971236 + outer loop + vertex 323.23 82.3139 297.019 + vertex 319.64 84.0499 297.606 + vertex 322.047 85.3643 296.934 + endloop + endfacet + facet normal -0.0804246 -0.0934755 -0.992368 + outer loop + vertex 316.463 82.7588 298.208 + vertex 316.245 79.8935 298.496 + vertex 309.351 83.1869 298.744 + endloop + endfacet + facet normal -0.0716875 -0.0990406 -0.992498 + outer loop + vertex 317.746 76.9867 298.677 + vertex 310.48 77.3782 299.163 + vertex 316.245 79.8935 298.496 + endloop + endfacet + facet normal -0.0771874 -0.0866328 -0.993246 + outer loop + vertex 310.48 77.3782 299.163 + vertex 309.351 83.1869 298.744 + vertex 316.245 79.8935 298.496 + endloop + endfacet + facet normal 0.311348 -0.1815 -0.932802 + outer loop + vertex -329.498 78.8904 295.752 + vertex -327.384 84.1632 295.432 + vertex -327.132 78.9298 296.534 + endloop + endfacet + facet normal 0.336705 -0.178535 -0.92453 + outer loop + vertex -327.132 78.9298 296.534 + vertex -327.384 84.1632 295.432 + vertex -324.683 85.8152 296.096 + endloop + endfacet + facet normal -0.281297 -0.1101 -0.953284 + outer loop + vertex 322.047 85.3643 296.934 + vertex 321.849 88.3162 296.652 + vertex 325.074 85.0665 296.075 + endloop + endfacet + facet normal -0.318972 -0.102266 -0.94223 + outer loop + vertex 320.864 91.327 296.658 + vertex 324.104 91.0753 295.589 + vertex 321.849 88.3162 296.652 + endloop + endfacet + facet normal -0.294546 -0.124274 -0.947522 + outer loop + vertex 324.104 91.0753 295.589 + vertex 325.074 85.0665 296.075 + vertex 321.849 88.3162 296.652 + endloop + endfacet + facet normal -0.152522 -0.0513483 -0.986965 + outer loop + vertex 315.036 85.7503 298.137 + vertex 315.285 88.6582 297.947 + vertex 319.009 87.0211 297.457 + endloop + endfacet + facet normal -0.157989 -0.0642678 -0.985347 + outer loop + vertex 319.009 87.0211 297.457 + vertex 315.285 88.6582 297.947 + vertex 318.429 89.9771 297.357 + endloop + endfacet + facet normal -0.148332 -0.0941257 -0.984448 + outer loop + vertex 316.463 82.7588 298.208 + vertex 315.036 85.7503 298.137 + vertex 319.64 84.0499 297.606 + endloop + endfacet + facet normal -0.143305 -0.0798859 -0.986449 + outer loop + vertex 319.64 84.0499 297.606 + vertex 315.036 85.7503 298.137 + vertex 319.009 87.0211 297.457 + endloop + endfacet + facet normal -0.219163 -0.0952436 -0.971028 + outer loop + vertex 319.64 84.0499 297.606 + vertex 319.009 87.0211 297.457 + vertex 322.047 85.3643 296.934 + endloop + endfacet + facet normal -0.225526 -0.107788 -0.968256 + outer loop + vertex 322.047 85.3643 296.934 + vertex 319.009 87.0211 297.457 + vertex 321.849 88.3162 296.652 + endloop + endfacet + facet normal -0.238363 -0.0794304 -0.967922 + outer loop + vertex 319.009 87.0211 297.457 + vertex 318.429 89.9771 297.357 + vertex 321.849 88.3162 296.652 + endloop + endfacet + facet normal -0.236484 -0.0752226 -0.968719 + outer loop + vertex 321.849 88.3162 296.652 + vertex 318.429 89.9771 297.357 + vertex 320.864 91.327 296.658 + endloop + endfacet + facet normal -0.0848797 -0.0576595 -0.994721 + outer loop + vertex 315.285 88.6582 297.947 + vertex 315.036 85.7503 298.137 + vertex 308.336 89.0637 298.517 + endloop + endfacet + facet normal -0.0786784 -0.0611366 -0.995024 + outer loop + vertex 316.463 82.7588 298.208 + vertex 309.351 83.1869 298.744 + vertex 315.036 85.7503 298.137 + endloop + endfacet + facet normal -0.0824785 -0.0527502 -0.995196 + outer loop + vertex 309.351 83.1869 298.744 + vertex 308.336 89.0637 298.517 + vertex 315.036 85.7503 298.137 + endloop + endfacet + facet normal 0.317168 -0.141253 -0.937791 + outer loop + vertex -327.384 84.1632 295.432 + vertex -325.891 90.4484 294.99 + vertex -324.683 85.8152 296.096 + endloop + endfacet + facet normal 0.36499 -0.12515 -0.922562 + outer loop + vertex -324.683 85.8152 296.096 + vertex -325.891 90.4484 294.99 + vertex -323.233 92.017 295.828 + endloop + endfacet + facet normal -0.318 -0.0787619 -0.944814 + outer loop + vertex 320.864 91.327 296.658 + vertex 320.742 94.3074 296.451 + vertex 324.104 91.0753 295.589 + endloop + endfacet + facet normal -0.341821 -0.0742519 -0.936827 + outer loop + vertex 319.81 97.2738 296.556 + vertex 322.952 97.4953 295.392 + vertex 320.742 94.3074 296.451 + endloop + endfacet + facet normal -0.325332 -0.087257 -0.941565 + outer loop + vertex 322.952 97.4953 295.392 + vertex 324.104 91.0753 295.589 + vertex 320.742 94.3074 296.451 + endloop + endfacet + facet normal -0.161844 -0.0243506 -0.986516 + outer loop + vertex 313.954 91.6335 297.967 + vertex 314.278 94.5102 297.843 + vertex 317.878 92.9185 297.291 + endloop + endfacet + facet normal -0.168836 -0.0407586 -0.984801 + outer loop + vertex 317.878 92.9185 297.291 + vertex 314.278 94.5102 297.843 + vertex 317.384 95.8387 297.255 + endloop + endfacet + facet normal -0.157972 -0.0643078 -0.985347 + outer loop + vertex 315.285 88.6582 297.947 + vertex 313.954 91.6335 297.967 + vertex 318.429 89.9771 297.357 + endloop + endfacet + facet normal -0.153216 -0.0508913 -0.986881 + outer loop + vertex 318.429 89.9771 297.357 + vertex 313.954 91.6335 297.967 + vertex 317.878 92.9185 297.291 + endloop + endfacet + facet normal -0.240947 -0.0669194 -0.968228 + outer loop + vertex 318.429 89.9771 297.357 + vertex 317.878 92.9185 297.291 + vertex 320.864 91.327 296.658 + endloop + endfacet + facet normal -0.246045 -0.0773008 -0.966171 + outer loop + vertex 320.864 91.327 296.658 + vertex 317.878 92.9185 297.291 + vertex 320.742 94.3074 296.451 + endloop + endfacet + facet normal -0.256368 -0.055305 -0.964996 + outer loop + vertex 317.878 92.9185 297.291 + vertex 317.384 95.8387 297.255 + vertex 320.742 94.3074 296.451 + endloop + endfacet + facet normal -0.252064 -0.0449927 -0.966664 + outer loop + vertex 320.742 94.3074 296.451 + vertex 317.384 95.8387 297.255 + vertex 319.81 97.2738 296.556 + endloop + endfacet + facet normal -0.0842776 -0.0334988 -0.995879 + outer loop + vertex 314.278 94.5102 297.843 + vertex 313.954 91.6335 297.967 + vertex 307.396 94.9278 298.411 + endloop + endfacet + facet normal -0.083424 -0.030872 -0.996036 + outer loop + vertex 315.285 88.6582 297.947 + vertex 308.336 89.0637 298.517 + vertex 313.954 91.6335 297.967 + endloop + endfacet + facet normal -0.0832073 -0.0313464 -0.996039 + outer loop + vertex 308.336 89.0637 298.517 + vertex 307.396 94.9278 298.411 + vertex 313.954 91.6335 297.967 + endloop + endfacet + facet normal 0.352569 -0.0998962 -0.930439 + outer loop + vertex -325.891 90.4484 294.99 + vertex -324.632 97.016 294.762 + vertex -323.233 92.017 295.828 + endloop + endfacet + facet normal 0.385192 -0.0882426 -0.918608 + outer loop + vertex -323.233 92.017 295.828 + vertex -324.632 97.016 294.762 + vertex -322.147 97.93 295.716 + endloop + endfacet + facet normal -0.343351 -0.0562023 -0.937524 + outer loop + vertex 319.81 97.2738 296.556 + vertex 319.718 100.176 296.416 + vertex 322.952 97.4953 295.392 + endloop + endfacet + facet normal -0.344103 -0.0582963 -0.93712 + outer loop + vertex 318.838 103.021 296.562 + vertex 321.644 103.297 295.514 + vertex 319.718 100.176 296.416 + endloop + endfacet + facet normal -0.344609 -0.0579367 -0.936957 + outer loop + vertex 321.644 103.297 295.514 + vertex 322.952 97.4953 295.392 + vertex 319.718 100.176 296.416 + endloop + endfacet + facet normal -0.162879 -0.0122969 -0.986569 + outer loop + vertex 313.019 97.4637 297.897 + vertex 313.406 100.317 297.797 + vertex 316.929 98.7373 297.236 + endloop + endfacet + facet normal -0.170445 -0.029751 -0.984918 + outer loop + vertex 316.929 98.7373 297.236 + vertex 313.406 100.317 297.797 + vertex 316.491 101.618 297.224 + endloop + endfacet + facet normal -0.164153 -0.0518298 -0.985072 + outer loop + vertex 314.278 94.5102 297.843 + vertex 313.019 97.4637 297.897 + vertex 317.384 95.8387 297.255 + endloop + endfacet + facet normal -0.156799 -0.0312595 -0.987136 + outer loop + vertex 317.384 95.8387 297.255 + vertex 313.019 97.4637 297.897 + vertex 316.929 98.7373 297.236 + endloop + endfacet + facet normal -0.251495 -0.0460031 -0.966765 + outer loop + vertex 317.384 95.8387 297.255 + vertex 316.929 98.7373 297.236 + vertex 319.81 97.2738 296.556 + endloop + endfacet + facet normal -0.255584 -0.054764 -0.965234 + outer loop + vertex 319.81 97.2738 296.556 + vertex 316.929 98.7373 297.236 + vertex 319.718 100.176 296.416 + endloop + endfacet + facet normal -0.261139 -0.0434752 -0.964322 + outer loop + vertex 316.929 98.7373 297.236 + vertex 316.491 101.618 297.224 + vertex 319.718 100.176 296.416 + endloop + endfacet + facet normal -0.255352 -0.0293577 -0.966402 + outer loop + vertex 319.718 100.176 296.416 + vertex 316.491 101.618 297.224 + vertex 318.838 103.021 296.562 + endloop + endfacet + facet normal -0.0840628 -0.0233419 -0.996187 + outer loop + vertex 313.406 100.317 297.797 + vertex 313.019 97.4637 297.897 + vertex 306.548 100.768 298.366 + endloop + endfacet + facet normal -0.0833273 -0.017161 -0.996374 + outer loop + vertex 314.278 94.5102 297.843 + vertex 307.396 94.9278 298.411 + vertex 313.019 97.4637 297.897 + endloop + endfacet + facet normal -0.0822022 -0.0196651 -0.996422 + outer loop + vertex 307.396 94.9278 298.411 + vertex 306.548 100.768 298.366 + vertex 313.019 97.4637 297.897 + endloop + endfacet + facet normal 0.379737 -0.0693601 -0.922491 + outer loop + vertex -324.632 97.016 294.762 + vertex -323.452 102.725 294.818 + vertex -322.147 97.93 295.716 + endloop + endfacet + facet normal 0.386322 -0.0670884 -0.919921 + outer loop + vertex -322.147 97.93 295.716 + vertex -323.452 102.725 294.818 + vertex -321.229 103.685 295.682 + endloop + endfacet + facet normal -0.345031 -0.049485 -0.937286 + outer loop + vertex 318.838 103.021 296.562 + vertex 318.862 105.898 296.401 + vertex 321.644 103.297 295.514 + endloop + endfacet + facet normal -0.353927 -0.0545761 -0.933679 + outer loop + vertex 318.102 108.768 296.521 + vertex 321.141 108.979 295.357 + vertex 318.862 105.898 296.401 + endloop + endfacet + facet normal -0.351144 -0.0569427 -0.934588 + outer loop + vertex 321.141 108.979 295.357 + vertex 321.644 103.297 295.514 + vertex 318.862 105.898 296.401 + endloop + endfacet + facet normal -0.162986 -0.00910053 -0.986586 + outer loop + vertex 312.206 103.267 297.872 + vertex 312.584 106.124 297.783 + vertex 316.09 104.495 297.219 + endloop + endfacet + facet normal -0.170822 -0.0265338 -0.984945 + outer loop + vertex 316.09 104.495 297.219 + vertex 312.584 106.124 297.783 + vertex 315.677 107.395 297.213 + endloop + endfacet + facet normal -0.165246 -0.0422684 -0.985346 + outer loop + vertex 313.406 100.317 297.797 + vertex 312.206 103.267 297.872 + vertex 316.491 101.618 297.224 + endloop + endfacet + facet normal -0.158411 -0.0238285 -0.987086 + outer loop + vertex 316.491 101.618 297.224 + vertex 312.206 103.267 297.872 + vertex 316.09 104.495 297.219 + endloop + endfacet + facet normal -0.251188 -0.0367186 -0.967242 + outer loop + vertex 316.491 101.618 297.224 + vertex 316.09 104.495 297.219 + vertex 318.838 103.021 296.562 + endloop + endfacet + facet normal -0.258607 -0.0517353 -0.964596 + outer loop + vertex 318.838 103.021 296.562 + vertex 316.09 104.495 297.219 + vertex 318.862 105.898 296.401 + endloop + endfacet + facet normal -0.26436 -0.0397886 -0.963603 + outer loop + vertex 316.09 104.495 297.219 + vertex 315.677 107.395 297.213 + vertex 318.862 105.898 296.401 + endloop + endfacet + facet normal -0.259356 -0.0281833 -0.96537 + outer loop + vertex 318.862 105.898 296.401 + vertex 315.677 107.395 297.213 + vertex 318.102 108.768 296.521 + endloop + endfacet + facet normal -0.0845588 -0.0197759 -0.996222 + outer loop + vertex 312.584 106.124 297.783 + vertex 312.206 103.267 297.872 + vertex 305.751 106.611 298.354 + endloop + endfacet + facet normal -0.0831173 -0.00856406 -0.996503 + outer loop + vertex 313.406 100.317 297.797 + vertex 306.548 100.768 298.366 + vertex 312.206 103.267 297.872 + endloop + endfacet + facet normal -0.0811271 -0.0130939 -0.996618 + outer loop + vertex 306.548 100.768 298.366 + vertex 305.751 106.611 298.354 + vertex 312.206 103.267 297.872 + endloop + endfacet + facet normal 0.384186 -0.0609519 -0.921242 + outer loop + vertex -323.452 102.725 294.818 + vertex -322.748 108.493 294.73 + vertex -321.229 103.685 295.682 + endloop + endfacet + facet normal 0.388781 -0.0591413 -0.91943 + outer loop + vertex -321.229 103.685 295.682 + vertex -322.748 108.493 294.73 + vertex -320.383 109.498 295.665 + endloop + endfacet + facet normal -0.35441 -0.0484583 -0.933834 + outer loop + vertex 318.102 108.768 296.521 + vertex 318.1 111.719 296.369 + vertex 321.141 108.979 295.357 + endloop + endfacet + facet normal -0.355358 -0.0541264 -0.933162 + outer loop + vertex 317.249 114.669 296.522 + vertex 320.296 114.91 295.347 + vertex 318.1 111.719 296.369 + endloop + endfacet + facet normal -0.357508 -0.0524141 -0.932438 + outer loop + vertex 320.296 114.91 295.347 + vertex 321.141 108.979 295.357 + vertex 318.1 111.719 296.369 + endloop + endfacet + facet normal -0.164561 -0.00550916 -0.986351 + outer loop + vertex 311.373 109.102 297.868 + vertex 311.756 111.983 297.788 + vertex 315.269 110.318 297.211 + endloop + endfacet + facet normal -0.173644 -0.025329 -0.984483 + outer loop + vertex 315.269 110.318 297.211 + vertex 311.756 111.983 297.788 + vertex 314.84 113.268 297.211 + endloop + endfacet + facet normal -0.16559 -0.039471 -0.985404 + outer loop + vertex 312.584 106.124 297.783 + vertex 311.373 109.102 297.868 + vertex 315.677 107.395 297.213 + endloop + endfacet + facet normal -0.159245 -0.0228634 -0.986974 + outer loop + vertex 315.677 107.395 297.213 + vertex 311.373 109.102 297.868 + vertex 315.269 110.318 297.211 + endloop + endfacet + facet normal -0.255054 -0.0362212 -0.966248 + outer loop + vertex 315.677 107.395 297.213 + vertex 315.269 110.318 297.211 + vertex 318.102 108.768 296.521 + endloop + endfacet + facet normal -0.261966 -0.0499448 -0.963784 + outer loop + vertex 318.102 108.768 296.521 + vertex 315.269 110.318 297.211 + vertex 318.1 111.719 296.369 + endloop + endfacet + facet normal -0.267137 -0.0389438 -0.962871 + outer loop + vertex 315.269 110.318 297.211 + vertex 314.84 113.268 297.211 + vertex 318.1 111.719 296.369 + endloop + endfacet + facet normal -0.261198 -0.0253158 -0.964953 + outer loop + vertex 318.1 111.719 296.369 + vertex 314.84 113.268 297.211 + vertex 317.249 114.669 296.522 + endloop + endfacet + facet normal -0.0840879 -0.0164767 -0.996322 + outer loop + vertex 311.756 111.983 297.788 + vertex 311.373 109.102 297.868 + vertex 304.937 112.487 298.355 + endloop + endfacet + facet normal -0.083586 -0.00580548 -0.996484 + outer loop + vertex 312.584 106.124 297.783 + vertex 305.751 106.611 298.354 + vertex 311.373 109.102 297.868 + endloop + endfacet + facet normal -0.0812669 -0.0110688 -0.996631 + outer loop + vertex 305.751 106.611 298.354 + vertex 304.937 112.487 298.355 + vertex 311.373 109.102 297.868 + endloop + endfacet + facet normal 0.388112 -0.0571923 -0.919836 + outer loop + vertex -322.748 108.493 294.73 + vertex -321.9 114.401 294.721 + vertex -320.383 109.498 295.665 + endloop + endfacet + facet normal 0.389253 -0.0567519 -0.919381 + outer loop + vertex -320.383 109.498 295.665 + vertex -321.9 114.401 294.721 + vertex -319.508 115.351 295.675 + endloop + endfacet + facet normal -0.356028 -0.046428 -0.933321 + outer loop + vertex 317.249 114.669 296.522 + vertex 317.179 117.634 296.401 + vertex 320.296 114.91 295.347 + endloop + endfacet + facet normal -0.350593 -0.0533648 -0.935006 + outer loop + vertex 316.307 120.599 296.559 + vertex 319.107 120.737 295.501 + vertex 317.179 117.634 296.401 + endloop + endfacet + facet normal -0.357513 -0.0483852 -0.932654 + outer loop + vertex 319.107 120.737 295.501 + vertex 320.296 114.91 295.347 + vertex 317.179 117.634 296.401 + endloop + endfacet + facet normal -0.16518 -0.00799416 -0.986231 + outer loop + vertex 310.553 114.991 297.873 + vertex 310.921 117.904 297.787 + vertex 314.412 116.228 297.216 + endloop + endfacet + facet normal -0.172401 -0.023547 -0.984745 + outer loop + vertex 314.412 116.228 297.216 + vertex 310.921 117.904 297.787 + vertex 313.981 119.202 297.221 + endloop + endfacet + facet normal -0.167904 -0.0393414 -0.985018 + outer loop + vertex 311.756 111.983 297.788 + vertex 310.553 114.991 297.873 + vertex 314.84 113.268 297.211 + endloop + endfacet + facet normal -0.160962 -0.0214149 -0.986728 + outer loop + vertex 314.84 113.268 297.211 + vertex 310.553 114.991 297.873 + vertex 314.412 116.228 297.216 + endloop + endfacet + facet normal -0.255801 -0.035156 -0.96609 + outer loop + vertex 314.84 113.268 297.211 + vertex 314.412 116.228 297.216 + vertex 317.249 114.669 296.522 + endloop + endfacet + facet normal -0.261027 -0.0454763 -0.96426 + outer loop + vertex 317.249 114.669 296.522 + vertex 314.412 116.228 297.216 + vertex 317.179 117.634 296.401 + endloop + endfacet + facet normal -0.265103 -0.0370168 -0.963509 + outer loop + vertex 314.412 116.228 297.216 + vertex 313.981 119.202 297.221 + vertex 317.179 117.634 296.401 + endloop + endfacet + facet normal -0.259683 -0.024987 -0.965371 + outer loop + vertex 317.179 117.634 296.401 + vertex 313.981 119.202 297.221 + vertex 316.307 120.599 296.559 + endloop + endfacet + facet normal -0.0846977 -0.0184541 -0.996236 + outer loop + vertex 310.921 117.904 297.787 + vertex 310.553 114.991 297.873 + vertex 304.128 118.414 298.355 + endloop + endfacet + facet normal -0.0832684 -0.00517399 -0.996514 + outer loop + vertex 311.756 111.983 297.788 + vertex 304.937 112.487 298.355 + vertex 310.553 114.991 297.873 + endloop + endfacet + facet normal -0.0807185 -0.0109238 -0.996677 + outer loop + vertex 304.937 112.487 298.355 + vertex 304.128 118.414 298.355 + vertex 310.553 114.991 297.873 + endloop + endfacet + facet normal 0.388864 -0.0555326 -0.91962 + outer loop + vertex -321.9 114.401 294.721 + vertex -320.894 120.076 294.803 + vertex -319.508 115.351 295.675 + endloop + endfacet + facet normal 0.386954 -0.0562335 -0.920383 + outer loop + vertex -319.508 115.351 295.675 + vertex -320.894 120.076 294.803 + vertex -318.652 121.261 295.674 + endloop + endfacet + facet normal -0.350884 -0.0486146 -0.935156 + outer loop + vertex 316.307 120.599 296.559 + vertex 316.313 123.594 296.401 + vertex 319.107 120.737 295.501 + endloop + endfacet + facet normal -0.360558 -0.0538194 -0.931183 + outer loop + vertex 315.534 126.595 296.529 + vertex 318.578 126.741 295.342 + vertex 316.313 123.594 296.401 + endloop + endfacet + facet normal -0.357684 -0.0562127 -0.932149 + outer loop + vertex 318.578 126.741 295.342 + vertex 319.107 120.737 295.501 + vertex 316.313 123.594 296.401 + endloop + endfacet + facet normal -0.163404 -0.00727416 -0.986532 + outer loop + vertex 309.716 120.948 297.87 + vertex 310.091 123.901 297.786 + vertex 313.572 122.192 297.222 + endloop + endfacet + facet normal -0.172064 -0.0255092 -0.984755 + outer loop + vertex 313.572 122.192 297.222 + vertex 310.091 123.901 297.786 + vertex 313.152 125.208 297.217 + endloop + endfacet + facet normal -0.165948 -0.0390307 -0.985362 + outer loop + vertex 310.921 117.904 297.787 + vertex 309.716 120.948 297.87 + vertex 313.981 119.202 297.221 + endloop + endfacet + facet normal -0.158957 -0.0213322 -0.987055 + outer loop + vertex 313.981 119.202 297.221 + vertex 309.716 120.948 297.87 + vertex 313.572 122.192 297.222 + endloop + endfacet + facet normal -0.254359 -0.0343792 -0.966498 + outer loop + vertex 313.981 119.202 297.221 + vertex 313.572 122.192 297.222 + vertex 316.307 120.599 296.559 + endloop + endfacet + facet normal -0.262915 -0.0503115 -0.963506 + outer loop + vertex 316.307 120.599 296.559 + vertex 313.572 122.192 297.222 + vertex 316.313 123.594 296.401 + endloop + endfacet + facet normal -0.268451 -0.0388986 -0.962508 + outer loop + vertex 313.572 122.192 297.222 + vertex 313.152 125.208 297.217 + vertex 316.313 123.594 296.401 + endloop + endfacet + facet normal -0.262886 -0.0270165 -0.964449 + outer loop + vertex 316.313 123.594 296.401 + vertex 313.152 125.208 297.217 + vertex 315.534 126.595 296.529 + endloop + endfacet + facet normal -0.084872 -0.0175067 -0.996238 + outer loop + vertex 310.091 123.901 297.786 + vertex 309.716 120.948 297.87 + vertex 303.308 124.4 298.355 + endloop + endfacet + facet normal -0.0837973 -0.00622166 -0.996463 + outer loop + vertex 310.921 117.904 297.787 + vertex 304.128 118.414 298.355 + vertex 309.716 120.948 297.87 + endloop + endfacet + facet normal -0.0815297 -0.0112496 -0.996607 + outer loop + vertex 304.128 118.414 298.355 + vertex 303.308 124.4 298.355 + vertex 309.716 120.948 297.87 + endloop + endfacet + facet normal 0.388972 -0.0608946 -0.919235 + outer loop + vertex -320.894 120.076 294.803 + vertex -320.202 126.17 294.692 + vertex -318.652 121.261 295.674 + endloop + endfacet + facet normal 0.396715 -0.0578266 -0.916118 + outer loop + vertex -318.652 121.261 295.674 + vertex -320.202 126.17 294.692 + vertex -317.788 127.199 295.673 + endloop + endfacet + facet normal -0.360989 -0.0466563 -0.931402 + outer loop + vertex 315.534 126.595 296.529 + vertex 315.47 129.572 296.404 + vertex 318.578 126.741 295.342 + endloop + endfacet + facet normal -0.354532 -0.0532559 -0.933526 + outer loop + vertex 314.605 132.543 296.564 + vertex 317.396 132.577 295.502 + vertex 315.47 129.572 296.404 + endloop + endfacet + facet normal -0.361881 -0.0477871 -0.930999 + outer loop + vertex 317.396 132.577 295.502 + vertex 318.578 126.741 295.342 + vertex 315.47 129.572 296.404 + endloop + endfacet + facet normal -0.164676 -0.00654243 -0.986326 + outer loop + vertex 308.876 126.977 297.869 + vertex 309.236 129.944 297.79 + vertex 312.721 128.227 297.219 + endloop + endfacet + facet normal -0.17232 -0.0225802 -0.984782 + outer loop + vertex 312.721 128.227 297.219 + vertex 309.236 129.944 297.79 + vertex 312.287 131.226 297.226 + endloop + endfacet + facet normal -0.166419 -0.038967 -0.985285 + outer loop + vertex 310.091 123.901 297.786 + vertex 308.876 126.977 297.869 + vertex 313.152 125.208 297.217 + endloop + endfacet + facet normal -0.159705 -0.022143 -0.986916 + outer loop + vertex 313.152 125.208 297.217 + vertex 308.876 126.977 297.869 + vertex 312.721 128.227 297.219 + endloop + endfacet + facet normal -0.257859 -0.0361708 -0.965505 + outer loop + vertex 313.152 125.208 297.217 + vertex 312.721 128.227 297.219 + vertex 315.534 126.595 296.529 + endloop + endfacet + facet normal -0.263076 -0.0459281 -0.963681 + outer loop + vertex 315.534 126.595 296.529 + vertex 312.721 128.227 297.219 + vertex 315.47 129.572 296.404 + endloop + endfacet + facet normal -0.267486 -0.0364207 -0.962873 + outer loop + vertex 312.721 128.227 297.219 + vertex 312.287 131.226 297.226 + vertex 315.47 129.572 296.404 + endloop + endfacet + facet normal -0.261826 -0.024567 -0.964802 + outer loop + vertex 315.47 129.572 296.404 + vertex 312.287 131.226 297.226 + vertex 314.605 132.543 296.564 + endloop + endfacet + facet normal -0.0847204 -0.0165176 -0.996268 + outer loop + vertex 309.236 129.944 297.79 + vertex 308.876 126.977 297.869 + vertex 302.463 130.399 298.358 + endloop + endfacet + facet normal -0.0840525 -0.0061393 -0.996442 + outer loop + vertex 310.091 123.901 297.786 + vertex 303.308 124.4 298.355 + vertex 308.876 126.977 297.869 + endloop + endfacet + facet normal -0.0818082 -0.0110141 -0.996587 + outer loop + vertex 303.308 124.4 298.355 + vertex 302.463 130.399 298.358 + vertex 308.876 126.977 297.869 + endloop + endfacet + facet normal 0.396047 -0.0558679 -0.916529 + outer loop + vertex -320.202 126.17 294.692 + vertex -319.173 131.87 294.79 + vertex -317.788 127.199 295.673 + endloop + endfacet + facet normal 0.391349 -0.057622 -0.918436 + outer loop + vertex -317.788 127.199 295.673 + vertex -319.173 131.87 294.79 + vertex -316.918 133.126 295.672 + endloop + endfacet + facet normal -0.35473 -0.0462931 -0.933822 + outer loop + vertex 314.605 132.543 296.564 + vertex 314.638 135.449 296.407 + vertex 317.396 132.577 295.502 + endloop + endfacet + facet normal -0.36195 -0.0565254 -0.930482 + outer loop + vertex 313.857 138.369 296.533 + vertex 316.866 138.475 295.357 + vertex 314.638 135.449 296.407 + endloop + endfacet + facet normal -0.36312 -0.0555269 -0.930087 + outer loop + vertex 316.866 138.475 295.357 + vertex 317.396 132.577 295.502 + vertex 314.638 135.449 296.407 + endloop + endfacet + facet normal -0.163815 -0.00809861 -0.986458 + outer loop + vertex 308.022 132.977 297.876 + vertex 308.38 135.873 297.793 + vertex 311.867 134.181 297.228 + endloop + endfacet + facet normal -0.171976 -0.0254824 -0.984771 + outer loop + vertex 311.867 134.181 297.228 + vertex 308.38 135.873 297.793 + vertex 311.458 137.095 297.224 + endloop + endfacet + facet normal -0.16583 -0.0383006 -0.98541 + outer loop + vertex 309.236 129.944 297.79 + vertex 308.022 132.977 297.876 + vertex 312.287 131.226 297.226 + endloop + endfacet + facet normal -0.15947 -0.0222358 -0.986952 + outer loop + vertex 312.287 131.226 297.226 + vertex 308.022 132.977 297.876 + vertex 311.867 134.181 297.228 + endloop + endfacet + facet normal -0.25574 -0.0359204 -0.966078 + outer loop + vertex 312.287 131.226 297.226 + vertex 311.867 134.181 297.228 + vertex 314.605 132.543 296.564 + endloop + endfacet + facet normal -0.262924 -0.0489438 -0.963574 + outer loop + vertex 314.605 132.543 296.564 + vertex 311.867 134.181 297.228 + vertex 314.638 135.449 296.407 + endloop + endfacet + facet normal -0.267336 -0.0388211 -0.962821 + outer loop + vertex 311.867 134.181 297.228 + vertex 311.458 137.095 297.224 + vertex 314.638 135.449 296.407 + endloop + endfacet + facet normal -0.262401 -0.0284327 -0.96454 + outer loop + vertex 314.638 135.449 296.407 + vertex 311.458 137.095 297.224 + vertex 313.857 138.369 296.533 + endloop + endfacet + facet normal -0.085362 -0.0180957 -0.996186 + outer loop + vertex 308.38 135.873 297.793 + vertex 308.022 132.977 297.876 + vertex 301.621 136.325 298.364 + endloop + endfacet + facet normal -0.0839768 -0.00522041 -0.996454 + outer loop + vertex 309.236 129.944 297.79 + vertex 302.463 130.399 298.358 + vertex 308.022 132.977 297.876 + endloop + endfacet + facet normal -0.0814853 -0.0106233 -0.996618 + outer loop + vertex 302.463 130.399 298.358 + vertex 301.621 136.325 298.364 + vertex 308.022 132.977 297.876 + endloop + endfacet + facet normal 0.392807 -0.0608196 -0.917608 + outer loop + vertex -319.173 131.87 294.79 + vertex -318.462 137.901 294.694 + vertex -316.918 133.126 295.672 + endloop + endfacet + facet normal 0.39841 -0.0585438 -0.915337 + outer loop + vertex -316.918 133.126 295.672 + vertex -318.462 137.901 294.694 + vertex -316.065 139.017 295.666 + endloop + endfacet + facet normal -0.362353 -0.0484065 -0.930783 + outer loop + vertex 313.857 138.369 296.533 + vertex 313.803 141.271 296.403 + vertex 316.866 138.475 295.357 + endloop + endfacet + facet normal -0.357323 -0.0570277 -0.932238 + outer loop + vertex 312.927 144.226 296.558 + vertex 315.701 144.328 295.489 + vertex 313.803 141.271 296.403 + endloop + endfacet + facet normal -0.364854 -0.0515752 -0.929635 + outer loop + vertex 315.701 144.328 295.489 + vertex 316.866 138.475 295.357 + vertex 313.803 141.271 296.403 + endloop + endfacet + facet normal -0.164992 -0.00804558 -0.986262 + outer loop + vertex 307.176 138.838 297.879 + vertex 307.526 141.698 297.797 + vertex 311.034 139.995 297.224 + endloop + endfacet + facet normal -0.172056 -0.0230885 -0.984817 + outer loop + vertex 311.034 139.995 297.224 + vertex 307.526 141.698 297.797 + vertex 310.6 142.916 297.232 + endloop + endfacet + facet normal -0.166711 -0.0389568 -0.985236 + outer loop + vertex 308.38 135.873 297.793 + vertex 307.176 138.838 297.879 + vertex 311.458 137.095 297.224 + endloop + endfacet + facet normal -0.16053 -0.0231948 -0.986758 + outer loop + vertex 311.458 137.095 297.224 + vertex 307.176 138.838 297.879 + vertex 311.034 139.995 297.224 + endloop + endfacet + facet normal -0.257875 -0.0374491 -0.965452 + outer loop + vertex 311.458 137.095 297.224 + vertex 311.034 139.995 297.224 + vertex 313.857 138.369 296.533 + endloop + endfacet + facet normal -0.26349 -0.0480408 -0.963465 + outer loop + vertex 313.857 138.369 296.533 + vertex 311.034 139.995 297.224 + vertex 313.803 141.271 296.403 + endloop + endfacet + facet normal -0.268142 -0.037417 -0.962653 + outer loop + vertex 311.034 139.995 297.224 + vertex 310.6 142.916 297.232 + vertex 313.803 141.271 296.403 + endloop + endfacet + facet normal -0.263482 -0.02753 -0.964272 + outer loop + vertex 313.803 141.271 296.403 + vertex 310.6 142.916 297.232 + vertex 312.927 144.226 296.558 + endloop + endfacet + facet normal -0.0858558 -0.0180227 -0.996145 + outer loop + vertex 307.526 141.698 297.797 + vertex 307.176 138.838 297.879 + vertex 300.803 142.199 298.368 + endloop + endfacet + facet normal -0.0845192 -0.00523552 -0.996408 + outer loop + vertex 308.38 135.873 297.793 + vertex 301.621 136.325 298.364 + vertex 307.176 138.838 297.879 + endloop + endfacet + facet normal -0.0820452 -0.0107372 -0.996571 + outer loop + vertex 301.621 136.325 298.364 + vertex 300.803 142.199 298.368 + vertex 307.176 138.838 297.879 + endloop + endfacet + facet normal 0.397692 -0.0566261 -0.91577 + outer loop + vertex -318.462 137.901 294.694 + vertex -317.436 143.633 294.785 + vertex -316.065 139.017 295.666 + endloop + endfacet + facet normal 0.396033 -0.0572489 -0.91645 + outer loop + vertex -316.065 139.017 295.666 + vertex -317.436 143.633 294.785 + vertex -315.227 144.901 295.661 + endloop + endfacet + facet normal -0.357365 -0.0562293 -0.932271 + outer loop + vertex 312.927 144.226 296.558 + vertex 312.892 147.202 296.392 + vertex 315.701 144.328 295.489 + endloop + endfacet + facet normal -0.360109 -0.0646613 -0.930667 + outer loop + vertex 312.042 150.226 296.511 + vertex 315.081 150.26 295.333 + vertex 312.892 147.202 296.392 + endloop + endfacet + facet normal -0.362852 -0.0623819 -0.929756 + outer loop + vertex 315.081 150.26 295.333 + vertex 315.701 144.328 295.489 + vertex 312.892 147.202 296.392 + endloop + endfacet + facet normal -0.167663 -0.00976952 -0.985796 + outer loop + vertex 306.34 144.697 297.886 + vertex 306.692 147.615 297.798 + vertex 310.141 145.882 297.228 + endloop + endfacet + facet normal -0.177859 -0.0307904 -0.983574 + outer loop + vertex 310.141 145.882 297.228 + vertex 306.692 147.615 297.798 + vertex 309.692 148.88 297.216 + endloop + endfacet + facet normal -0.166767 -0.0366599 -0.985315 + outer loop + vertex 307.526 141.698 297.797 + vertex 306.34 144.697 297.886 + vertex 310.6 142.916 297.232 + endloop + endfacet + facet normal -0.1626 -0.0263154 -0.986341 + outer loop + vertex 310.6 142.916 297.232 + vertex 306.34 144.697 297.886 + vertex 310.141 145.882 297.228 + endloop + endfacet + facet normal -0.256424 -0.0408081 -0.965702 + outer loop + vertex 310.6 142.916 297.232 + vertex 310.141 145.882 297.228 + vertex 312.927 144.226 296.558 + endloop + endfacet + facet normal -0.265183 -0.0568332 -0.962522 + outer loop + vertex 312.927 144.226 296.558 + vertex 310.141 145.882 297.228 + vertex 312.892 147.202 296.392 + endloop + endfacet + facet normal -0.27077 -0.044612 -0.96161 + outer loop + vertex 310.141 145.882 297.228 + vertex 309.692 148.88 297.216 + vertex 312.892 147.202 296.392 + endloop + endfacet + facet normal -0.267248 -0.0372611 -0.962907 + outer loop + vertex 312.892 147.202 296.392 + vertex 309.692 148.88 297.216 + vertex 312.042 150.226 296.511 + endloop + endfacet + facet normal -0.08746 -0.0197594 -0.995972 + outer loop + vertex 306.692 147.615 297.798 + vertex 306.34 144.697 297.886 + vertex 300.1 148.124 298.366 + endloop + endfacet + facet normal -0.0848253 -0.00394006 -0.996388 + outer loop + vertex 307.526 141.698 297.797 + vertex 300.803 142.199 298.368 + vertex 306.34 144.697 297.886 + endloop + endfacet + facet normal -0.0821255 -0.00996112 -0.996572 + outer loop + vertex 300.803 142.199 298.368 + vertex 300.1 148.124 298.366 + vertex 306.34 144.697 297.886 + endloop + endfacet + facet normal 0.396933 -0.0591706 -0.915938 + outer loop + vertex -317.436 143.633 294.785 + vertex -316.719 149.63 294.709 + vertex -315.227 144.901 295.661 + endloop + endfacet + facet normal 0.401239 -0.0574559 -0.914169 + outer loop + vertex -315.227 144.901 295.661 + vertex -316.719 149.63 294.709 + vertex -314.377 150.895 295.657 + endloop + endfacet + facet normal -0.360336 -0.0575426 -0.931046 + outer loop + vertex 312.042 150.226 296.511 + vertex 311.936 153.238 296.366 + vertex 315.081 150.26 295.333 + endloop + endfacet + facet normal -0.36127 -0.0548799 -0.930845 + outer loop + vertex 311.041 156.243 296.536 + vertex 314.03 156.26 295.375 + vertex 311.936 153.238 296.366 + endloop + endfacet + facet normal -0.35939 -0.0563922 -0.931482 + outer loop + vertex 314.03 156.26 295.375 + vertex 315.081 150.26 295.333 + vertex 311.936 153.238 296.366 + endloop + endfacet + facet normal -0.175759 -0.00762686 -0.984404 + outer loop + vertex 305.555 150.665 297.876 + vertex 305.929 153.606 297.786 + vertex 309.241 151.892 297.208 + endloop + endfacet + facet normal -0.18367 -0.0234883 -0.982707 + outer loop + vertex 309.241 151.892 297.208 + vertex 305.929 153.606 297.786 + vertex 308.818 154.894 297.215 + endloop + endfacet + facet normal -0.174139 -0.0397625 -0.983918 + outer loop + vertex 306.692 147.615 297.798 + vertex 305.555 150.665 297.876 + vertex 309.692 148.88 297.216 + endloop + endfacet + facet normal -0.169184 -0.0278024 -0.985192 + outer loop + vertex 309.692 148.88 297.216 + vertex 305.555 150.665 297.876 + vertex 309.241 151.892 297.208 + endloop + endfacet + facet normal -0.264669 -0.0420359 -0.963423 + outer loop + vertex 309.692 148.88 297.216 + vertex 309.241 151.892 297.208 + vertex 312.042 150.226 296.511 + endloop + endfacet + facet normal -0.272202 -0.0558669 -0.960617 + outer loop + vertex 312.042 150.226 296.511 + vertex 309.241 151.892 297.208 + vertex 311.936 153.238 296.366 + endloop + endfacet + facet normal -0.280986 -0.0372672 -0.958988 + outer loop + vertex 309.241 151.892 297.208 + vertex 308.818 154.894 297.215 + vertex 311.936 153.238 296.366 + endloop + endfacet + facet normal -0.276481 -0.0279503 -0.960613 + outer loop + vertex 311.936 153.238 296.366 + vertex 308.818 154.894 297.215 + vertex 311.041 156.243 296.536 + endloop + endfacet + facet normal -0.092812 -0.0184878 -0.995512 + outer loop + vertex 305.929 153.606 297.786 + vertex 305.555 150.665 297.876 + vertex 299.532 154.092 298.374 + endloop + endfacet + facet normal -0.0864791 -0.00676964 -0.996231 + outer loop + vertex 306.692 147.615 297.798 + vertex 300.1 148.124 298.366 + vertex 305.555 150.665 297.876 + endloop + endfacet + facet normal -0.0863562 -0.00703506 -0.996239 + outer loop + vertex 300.1 148.124 298.366 + vertex 299.532 154.092 298.374 + vertex 305.555 150.665 297.876 + endloop + endfacet + facet normal 0.400277 -0.0552566 -0.914727 + outer loop + vertex -316.719 149.63 294.709 + vertex -315.798 155.83 294.737 + vertex -314.377 150.895 295.657 + endloop + endfacet + facet normal 0.397074 -0.0564256 -0.916051 + outer loop + vertex -314.377 150.895 295.657 + vertex -315.798 155.83 294.737 + vertex -313.447 156.893 295.691 + endloop + endfacet + facet normal -0.361788 -0.0294371 -0.931796 + outer loop + vertex 311.041 156.243 296.536 + vertex 311.099 159.078 296.424 + vertex 314.03 156.26 295.375 + endloop + endfacet + facet normal -0.381139 -0.0235909 -0.924217 + outer loop + vertex 310.745 162.098 296.493 + vertex 313.088 161.135 295.552 + vertex 311.099 159.078 296.424 + endloop + endfacet + facet normal -0.368617 -0.0376522 -0.928819 + outer loop + vertex 313.088 161.135 295.552 + vertex 314.03 156.26 295.375 + vertex 311.099 159.078 296.424 + endloop + endfacet + facet normal -0.181378 0.0118576 -0.983342 + outer loop + vertex 304.882 156.639 297.886 + vertex 305.37 159.601 297.831 + vertex 308.483 157.884 297.237 + endloop + endfacet + facet normal -0.191618 -0.00736381 -0.981442 + outer loop + vertex 308.483 157.884 297.237 + vertex 305.37 159.601 297.831 + vertex 308.328 160.967 297.244 + endloop + endfacet + facet normal -0.180792 -0.0301043 -0.983061 + outer loop + vertex 305.929 153.606 297.786 + vertex 304.882 156.639 297.886 + vertex 308.818 154.894 297.215 + endloop + endfacet + facet normal -0.173247 -0.0124179 -0.9848 + outer loop + vertex 308.818 154.894 297.215 + vertex 304.882 156.639 297.886 + vertex 308.483 157.884 297.237 + endloop + endfacet + facet normal -0.278495 -0.024387 -0.960128 + outer loop + vertex 308.818 154.894 297.215 + vertex 308.483 157.884 297.237 + vertex 311.041 156.243 296.536 + endloop + endfacet + facet normal -0.283015 -0.0320937 -0.958578 + outer loop + vertex 311.041 156.243 296.536 + vertex 308.483 157.884 297.237 + vertex 311.099 159.078 296.424 + endloop + endfacet + facet normal -0.29135 -0.0124427 -0.956535 + outer loop + vertex 308.483 157.884 297.237 + vertex 308.328 160.967 297.244 + vertex 311.099 159.078 296.424 + endloop + endfacet + facet normal -0.291278 -0.0123263 -0.956559 + outer loop + vertex 311.099 159.078 296.424 + vertex 308.328 160.967 297.244 + vertex 310.745 162.098 296.493 + endloop + endfacet + facet normal -0.100653 -0.00165782 -0.99492 + outer loop + vertex 305.37 159.601 297.831 + vertex 304.882 156.639 297.886 + vertex 298.864 159.969 298.489 + endloop + endfacet + facet normal -0.0913465 0.00118368 -0.995818 + outer loop + vertex 305.929 153.606 297.786 + vertex 299.532 154.092 298.374 + vertex 304.882 156.639 297.886 + endloop + endfacet + facet normal -0.0949286 0.00878044 -0.995445 + outer loop + vertex 299.532 154.092 298.374 + vertex 298.864 159.969 298.489 + vertex 304.882 156.639 297.886 + endloop + endfacet + facet normal 0.392192 -0.0430975 -0.918873 + outer loop + vertex -315.798 155.83 294.737 + vertex -314.722 161.807 294.916 + vertex -313.447 156.893 295.691 + endloop + endfacet + facet normal 0.388487 -0.0442985 -0.920389 + outer loop + vertex -313.447 156.893 295.691 + vertex -314.722 161.807 294.916 + vertex -312.7 162.89 295.718 + endloop + endfacet + facet normal -0.230707 0.114794 -0.966228 + outer loop + vertex 304.25 162.732 298.037 + vertex 304.541 166.444 298.409 + vertex 308.498 164.54 297.237 + endloop + endfacet + facet normal -0.218142 0.140596 -0.965737 + outer loop + vertex 308.498 164.54 297.237 + vertex 304.541 166.444 298.409 + vertex 307.607 167.133 297.816 + endloop + endfacet + facet normal -0.192857 -0.00458418 -0.981216 + outer loop + vertex 305.37 159.601 297.831 + vertex 304.25 162.732 298.037 + vertex 308.328 160.967 297.244 + endloop + endfacet + facet normal -0.18793 0.00721985 -0.982156 + outer loop + vertex 308.328 160.967 297.244 + vertex 304.25 162.732 298.037 + vertex 308.498 164.54 297.237 + endloop + endfacet + facet normal -0.301954 0.0126999 -0.953238 + outer loop + vertex 308.328 160.967 297.244 + vertex 308.498 164.54 297.237 + vertex 310.745 162.098 296.493 + endloop + endfacet + facet normal -0.336497 -0.0226889 -0.941411 + outer loop + vertex 310.745 162.098 296.493 + vertex 308.498 164.54 297.237 + vertex 312.063 164.828 295.956 + endloop + endfacet + facet normal -0.114045 0.107788 -0.987611 + outer loop + vertex 304.541 166.444 298.409 + vertex 304.25 162.732 298.037 + vertex 297.833 165.215 299.049 + endloop + endfacet + facet normal -0.0988376 0.029935 -0.994653 + outer loop + vertex 305.37 159.601 297.831 + vertex 298.864 159.969 298.489 + vertex 304.25 162.732 298.037 + endloop + endfacet + facet normal -0.124583 0.0810704 -0.988892 + outer loop + vertex 298.864 159.969 298.489 + vertex 297.833 165.215 299.049 + vertex 304.25 162.732 298.037 + endloop + endfacet + facet normal 0.362254 0.0132698 -0.931985 + outer loop + vertex -314.722 161.807 294.916 + vertex -314.367 169.006 295.156 + vertex -312.7 162.89 295.718 + endloop + endfacet + facet normal 0.504707 0.0585889 -0.8613 + outer loop + vertex -312.7 162.89 295.718 + vertex -314.367 169.006 295.156 + vertex -314.285 168.981 295.203 + endloop + endfacet + facet normal 0.144017 -0.605218 0.782924 + outer loop + vertex 403.275 67.0725 348.294 + vertex 403.912 69.3812 349.961 + vertex 397.818 66.11 348.553 + endloop + endfacet + facet normal 0.149733 -0.6472 0.74747 + outer loop + vertex 402.995 64.598 346.207 + vertex 403.275 67.0725 348.294 + vertex 397.818 66.11 348.553 + endloop + endfacet + facet normal 0.183489 -0.669313 0.719966 + outer loop + vertex 403.747 62.1234 343.715 + vertex 402.995 64.598 346.207 + vertex 401.276 61.9417 344.176 + endloop + endfacet + facet normal 0.197167 -0.722488 0.662673 + outer loop + vertex 403.027 59.9042 341.51 + vertex 403.747 62.1234 343.715 + vertex 400.958 60.0662 342.302 + endloop + endfacet + facet normal 0.206482 -0.771045 0.602374 + outer loop + vertex 401.892 57.9086 339.344 + vertex 403.027 59.9042 341.51 + vertex 400.023 58.1 340.23 + endloop + endfacet + facet normal 0.214499 -0.817101 0.535104 + outer loop + vertex 400.64 56.1595 337.175 + vertex 401.892 57.9086 339.344 + vertex 398.822 56.305 338.126 + endloop + endfacet + facet normal 0.222072 -0.861632 0.456372 + outer loop + vertex 399.214 54.6471 335.014 + vertex 400.64 56.1595 337.175 + vertex 397.458 54.7168 336 + endloop + endfacet + facet normal 0.227717 -0.8992 0.373609 + outer loop + vertex 397.561 53.3663 332.939 + vertex 399.214 54.6471 335.014 + vertex 395.884 53.3363 333.889 + endloop + endfacet + facet normal 0.227336 -0.927453 0.296898 + outer loop + vertex 395.955 52.36 331.025 + vertex 397.561 53.3663 332.939 + vertex 394.078 52.163 331.847 + endloop + endfacet + facet normal 0.22178 -0.949022 0.223989 + outer loop + vertex 395.63 51.8401 329.144 + vertex 395.955 52.36 331.025 + vertex 392.336 51.2462 329.889 + endloop + endfacet + facet normal 0.223125 -0.968518 0.110398 + outer loop + vertex 396.581 51.7796 326.692 + vertex 395.63 51.8401 329.144 + vertex 391.013 50.6348 327.9 + endloop + endfacet + facet normal 0.219323 -0.975642 0.00456923 + outer loop + vertex 392.736 50.905 324.494 + vertex 396.581 51.7796 326.692 + vertex 389.568 50.1995 325.92 + endloop + endfacet + facet normal 0.208963 -0.97107 -0.115573 + outer loop + vertex 388.263 50.1793 322.503 + vertex 392.736 50.905 324.494 + vertex 388.522 49.9948 324.522 + endloop + endfacet + facet normal 0.151641 -0.933627 -0.32457 + outer loop + vertex 377.298 50.0413 315.758 + vertex 381.569 49.9086 318.135 + vertex 372.238 48.4185 318.062 + endloop + endfacet + facet normal 0.104943 -0.867899 -0.48553 + outer loop + vertex 367.35 51.1962 310.74 + vertex 369.657 50.2976 312.845 + vertex 361.426 49.3496 312.76 + endloop + endfacet + facet normal 0.0319063 -0.749622 -0.661097 + outer loop + vertex 355.03 54.7669 304.967 + vertex 360.135 53.1643 307.031 + vertex 351.975 52.4331 307.466 + endloop + endfacet + facet normal -0.00454761 -0.725759 -0.687934 + outer loop + vertex 351.483 56.3364 303.335 + vertex 355.03 54.7669 304.967 + vertex 347.14 54.9833 304.791 + endloop + endfacet + facet normal -0.0337588 -0.679946 -0.732484 + outer loop + vertex 347.908 57.2358 302.665 + vertex 351.483 56.3364 303.335 + vertex 347.14 54.9833 304.791 + endloop + endfacet + facet normal -0.0679853 -0.669918 -0.739316 + outer loop + vertex 346.376 58.9249 301.275 + vertex 347.908 57.2358 302.665 + vertex 345.362 58.3468 301.892 + endloop + endfacet + facet normal -0.0946819 -0.630207 -0.770632 + outer loop + vertex 343.805 60.6742 300.161 + vertex 346.376 58.9249 301.275 + vertex 343.478 59.7581 300.95 + endloop + endfacet + facet normal -0.128784 -0.568077 -0.812837 + outer loop + vertex 341.232 62.656 299.183 + vertex 343.805 60.6742 300.161 + vertex 341.136 61.5165 299.995 + endloop + endfacet + facet normal -0.160131 -0.493115 -0.8551 + outer loop + vertex 338.515 65.1299 298.265 + vertex 341.232 62.656 299.183 + vertex 338.863 63.495 299.143 + endloop + endfacet + facet normal -0.230523 -0.465509 -0.854494 + outer loop + vertex 336.417 67.8356 297.357 + vertex 338.515 65.1299 298.265 + vertex 335.732 67.1235 297.93 + endloop + endfacet + facet normal -0.271844 -0.42126 -0.86524 + outer loop + vertex 334.571 70.4797 296.65 + vertex 336.417 67.8356 297.357 + vertex 334.077 69.5404 297.263 + endloop + endfacet + facet normal -0.288701 -0.354004 -0.889569 + outer loop + vertex 332.922 73.2514 296.082 + vertex 334.571 70.4797 296.65 + vertex 332.643 71.9881 296.675 + endloop + endfacet + facet normal -0.299412 -0.265962 -0.916306 + outer loop + vertex 330.819 76.7 295.768 + vertex 332.922 73.2514 296.082 + vertex 331.794 73.8448 296.278 + endloop + endfacet + facet normal -0.316816 -0.212719 -0.924326 + outer loop + vertex 328.667 82.5365 295.163 + vertex 330.819 76.7 295.768 + vertex 327.111 78.8791 296.538 + endloop + endfacet + facet normal -0.347622 -0.160521 -0.923792 + outer loop + vertex 326.852 87.273 295.023 + vertex 328.667 82.5365 295.163 + vertex 325.074 85.0665 296.075 + endloop + endfacet + facet normal -0.398368 -0.153304 -0.904324 + outer loop + vertex 326.933 90.7438 294.399 + vertex 326.852 87.273 295.023 + vertex 324.104 91.0753 295.589 + endloop + endfacet + facet normal -0.3966 -0.11522 -0.910732 + outer loop + vertex 325.814 94.2699 294.44 + vertex 326.933 90.7438 294.399 + vertex 324.104 91.0753 295.589 + endloop + endfacet + facet normal -0.416102 -0.102585 -0.903513 + outer loop + vertex 325.778 98.2431 294.005 + vertex 325.814 94.2699 294.44 + vertex 322.952 97.4953 295.392 + endloop + endfacet + facet normal -0.423326 -0.0742038 -0.902933 + outer loop + vertex 324.337 101.798 294.389 + vertex 325.778 98.2431 294.005 + vertex 322.952 97.4953 295.392 + endloop + endfacet + facet normal -0.41811 -0.0713274 -0.905592 + outer loop + vertex 323.866 106.57 294.23 + vertex 324.337 101.798 294.389 + vertex 321.644 103.297 295.514 + endloop + endfacet + facet normal -0.424334 -0.0574088 -0.903684 + outer loop + vertex 323.399 109.85 294.241 + vertex 323.866 106.57 294.23 + vertex 321.141 108.979 295.357 + endloop + endfacet + facet normal -0.424099 -0.0581039 -0.90375 + outer loop + vertex 322.774 112.18 294.385 + vertex 323.399 109.85 294.241 + vertex 321.141 108.979 295.357 + endloop + endfacet + facet normal -0.432183 -0.0754059 -0.898628 + outer loop + vertex 322.941 115.734 294.006 + vertex 322.774 112.18 294.385 + vertex 320.296 114.91 295.347 + endloop + endfacet + facet normal -0.437638 -0.0559196 -0.897411 + outer loop + vertex 321.763 119.024 294.376 + vertex 322.941 115.734 294.006 + vertex 320.296 114.91 295.347 + endloop + endfacet + facet normal -0.426592 -0.0690711 -0.901803 + outer loop + vertex 321.399 123.796 294.183 + vertex 321.763 119.024 294.376 + vertex 319.107 120.737 295.501 + endloop + endfacet + facet normal -0.432175 -0.059713 -0.899811 + outer loop + vertex 320.992 127.426 294.137 + vertex 321.399 123.796 294.183 + vertex 318.578 126.741 295.342 + endloop + endfacet + facet normal -0.430268 -0.0671278 -0.900202 + outer loop + vertex 320.336 131.141 294.174 + vertex 320.992 127.426 294.137 + vertex 318.578 126.741 295.342 + endloop + endfacet + facet normal -0.433701 -0.05611 -0.899308 + outer loop + vertex 319.397 135.44 294.358 + vertex 320.336 131.141 294.174 + vertex 317.396 132.577 295.502 + endloop + endfacet + facet normal -0.440101 -0.0726001 -0.895009 + outer loop + vertex 319.554 139.464 293.955 + vertex 319.397 135.44 294.358 + vertex 316.866 138.475 295.357 + endloop + endfacet + facet normal -0.445353 -0.0563038 -0.893583 + outer loop + vertex 318.341 142.714 294.354 + vertex 319.554 139.464 293.955 + vertex 316.866 138.475 295.357 + endloop + endfacet + facet normal -0.429464 -0.0694189 -0.900412 + outer loop + vertex 317.876 147.627 294.197 + vertex 318.341 142.714 294.354 + vertex 315.701 144.328 295.489 + endloop + endfacet + facet normal -0.425179 -0.0618364 -0.902994 + outer loop + vertex 317.352 151.066 294.209 + vertex 317.876 147.627 294.197 + vertex 315.081 150.26 295.333 + endloop + endfacet + facet normal -0.423658 -0.0666431 -0.903367 + outer loop + vertex 316.612 153.514 294.375 + vertex 317.352 151.066 294.209 + vertex 315.081 150.26 295.333 + endloop + endfacet + facet normal -0.430512 -0.0772027 -0.899277 + outer loop + vertex 316.605 157.125 294.068 + vertex 316.612 153.514 294.375 + vertex 314.03 156.26 295.375 + endloop + endfacet + facet normal -0.437529 -0.0537709 -0.897595 + outer loop + vertex 315.293 160.231 294.522 + vertex 316.605 157.125 294.068 + vertex 314.03 156.26 295.375 + endloop + endfacet + facet normal -0.433299 -0.0309417 -0.900719 + outer loop + vertex 314.87 164.527 294.578 + vertex 315.293 160.231 294.522 + vertex 313.088 161.135 295.552 + endloop + endfacet + facet normal -0.434231 0.065567 -0.898412 + outer loop + vertex 314.45 169.032 295.109 + vertex 314.87 164.527 294.578 + vertex 312.063 164.828 295.956 + endloop + endfacet + facet normal 0.502506 0.0333708 -0.863929 + outer loop + vertex -315.729 165.468 294.228 + vertex -314.45 169.032 295.109 + vertex -314.367 169.006 295.156 + endloop + endfacet + facet normal 0.465399 -0.038252 -0.884274 + outer loop + vertex -316.198 160.588 294.192 + vertex -315.729 165.468 294.228 + vertex -314.722 161.807 294.916 + endloop + endfacet + facet normal 0.486865 -0.0589094 -0.871489 + outer loop + vertex -317.099 157.247 293.914 + vertex -316.198 160.588 294.192 + vertex -315.798 155.83 294.737 + endloop + endfacet + facet normal 0.476801 -0.0708549 -0.876151 + outer loop + vertex -317.233 153.47 294.147 + vertex -317.099 157.247 293.914 + vertex -315.798 155.83 294.737 + endloop + endfacet + facet normal 0.47929 -0.0638606 -0.87533 + outer loop + vertex -317.747 151.056 294.041 + vertex -317.233 153.47 294.147 + vertex -316.719 149.63 294.709 + endloop + endfacet + facet normal 0.478356 -0.0647432 -0.875776 + outer loop + vertex -318.3 147.615 293.994 + vertex -317.747 151.056 294.041 + vertex -316.719 149.63 294.709 + endloop + endfacet + facet normal 0.473086 -0.0718525 -0.878081 + outer loop + vertex -318.881 142.702 294.083 + vertex -318.3 147.615 293.994 + vertex -317.436 143.633 294.785 + endloop + endfacet + facet normal 0.495371 -0.0670187 -0.866092 + outer loop + vertex -319.801 139.614 293.796 + vertex -318.881 142.702 294.083 + vertex -318.462 137.901 294.694 + endloop + endfacet + facet normal 0.483849 -0.0789148 -0.871586 + outer loop + vertex -319.98 135.459 294.073 + vertex -319.801 139.614 293.796 + vertex -318.462 137.901 294.694 + endloop + endfacet + facet normal 0.477638 -0.0675845 -0.875954 + outer loop + vertex -320.825 131.189 293.941 + vertex -319.98 135.459 294.073 + vertex -319.173 131.87 294.79 + endloop + endfacet + facet normal 0.470364 -0.0732266 -0.879429 + outer loop + vertex -321.396 127.547 293.939 + vertex -320.825 131.189 293.941 + vertex -320.202 126.17 294.692 + endloop + endfacet + facet normal 0.474881 -0.0682027 -0.877403 + outer loop + vertex -321.892 123.854 293.958 + vertex -321.396 127.547 293.939 + vertex -320.202 126.17 294.692 + endloop + endfacet + facet normal 0.466645 -0.0739716 -0.881346 + outer loop + vertex -322.364 119.052 294.111 + vertex -321.892 123.854 293.958 + vertex -320.894 120.076 294.803 + endloop + endfacet + facet normal 0.484426 -0.0660175 -0.872337 + outer loop + vertex -323.227 115.872 293.872 + vertex -322.364 119.052 294.111 + vertex -321.9 114.401 294.721 + endloop + endfacet + facet normal 0.474416 -0.0776635 -0.876868 + outer loop + vertex -323.316 112.239 294.146 + vertex -323.227 115.872 293.872 + vertex -321.9 114.401 294.721 + endloop + endfacet + facet normal 0.47205 -0.0655304 -0.879133 + outer loop + vertex -323.807 109.976 294.051 + vertex -323.316 112.239 294.146 + vertex -322.748 108.493 294.73 + endloop + endfacet + facet normal 0.471174 -0.0663434 -0.879542 + outer loop + vertex -324.36 106.661 294.005 + vertex -323.807 109.976 294.051 + vertex -322.748 108.493 294.73 + endloop + endfacet + facet normal 0.46103 -0.076342 -0.884094 + outer loop + vertex -324.96 101.873 294.105 + vertex -324.36 106.661 294.005 + vertex -323.452 102.725 294.818 + endloop + endfacet + facet normal 0.472493 -0.0866175 -0.877067 + outer loop + vertex -326.079 98.4196 293.843 + vertex -324.96 101.873 294.105 + vertex -324.632 97.016 294.762 + endloop + endfacet + facet normal 0.457003 -0.106512 -0.883065 + outer loop + vertex -326.367 94.3462 294.186 + vertex -326.079 98.4196 293.843 + vertex -324.632 97.016 294.762 + endloop + endfacet + facet normal 0.453505 -0.126564 -0.882222 + outer loop + vertex -327.239 90.8855 294.234 + vertex -326.367 94.3462 294.186 + vertex -325.891 90.4484 294.99 + endloop + endfacet + facet normal 0.44216 -0.161623 -0.882254 + outer loop + vertex -327.575 87.2433 294.733 + vertex -327.239 90.8855 294.234 + vertex -325.891 90.4484 294.99 + endloop + endfacet + facet normal 0.397932 -0.179393 -0.899705 + outer loop + vertex -329.215 82.6108 294.931 + vertex -327.575 87.2433 294.733 + vertex -327.384 84.1632 295.432 + endloop + endfacet + facet normal 0.364308 -0.226944 -0.903203 + outer loop + vertex -331.164 76.8562 295.591 + vertex -329.215 82.6108 294.931 + vertex -329.498 78.8904 295.752 + endloop + endfacet + facet normal 0.326148 -0.279612 -0.90302 + outer loop + vertex -332.846 73.1736 296.124 + vertex -331.164 76.8562 295.591 + vertex -332.151 73.4429 296.291 + endloop + endfacet + facet normal 0.271218 -0.347753 -0.897501 + outer loop + vertex -334.462 70.2878 296.754 + vertex -332.846 73.1736 296.124 + vertex -333.371 70.9937 296.81 + endloop + endfacet + facet normal 0.236887 -0.405964 -0.882654 + outer loop + vertex -336.318 67.6551 297.466 + vertex -334.462 70.2878 296.754 + vertex -334.952 68.4899 297.449 + endloop + endfacet + facet normal 0.185238 -0.444025 -0.876658 + outer loop + vertex -338.552 64.9216 298.379 + vertex -336.318 67.6551 297.466 + vertex -336.733 66.1619 298.135 + endloop + endfacet + facet normal 0.164189 -0.502921 -0.848594 + outer loop + vertex -341.094 62.5517 299.292 + vertex -338.552 64.9216 298.379 + vertex -340.005 62.7663 299.375 + endloop + endfacet + facet normal 0.140002 -0.572508 -0.807857 + outer loop + vertex -343.535 60.5343 300.298 + vertex -341.094 62.5517 299.292 + vertex -342.26 60.8461 300.298 + endloop + endfacet + facet normal 0.0913029 -0.618344 -0.780586 + outer loop + vertex -346.1 58.8168 301.359 + vertex -343.535 60.5343 300.298 + vertex -344.571 59.1189 301.298 + endloop + endfacet + facet normal 0.0283849 -0.648306 -0.76085 + outer loop + vertex -348.442 57.3346 302.534 + vertex -346.1 58.8168 301.359 + vertex -346.221 58.1136 301.953 + endloop + endfacet + facet normal 0.0534044 -0.73873 -0.671883 + outer loop + vertex -351.99 56.4949 303.175 + vertex -348.442 57.3346 302.534 + vertex -350.771 55.4629 304.407 + endloop + endfacet + facet normal 0.022252 -0.75533 -0.654967 + outer loop + vertex -356.236 54.9809 304.777 + vertex -351.99 56.4949 303.175 + vertex -350.771 55.4629 304.407 + endloop + endfacet + facet normal -0.0141455 -0.775022 -0.631775 + outer loop + vertex -361.486 53.3582 306.885 + vertex -356.236 54.9809 304.777 + vertex -356.658 52.9522 307.275 + endloop + endfacet + facet normal -0.0310871 -0.825386 -0.563712 + outer loop + vertex -365.905 52.4401 308.473 + vertex -361.486 53.3582 306.885 + vertex -362.456 51.3693 309.851 + endloop + endfacet + facet normal -0.0659001 -0.861032 -0.504263 + outer loop + vertex -368.666 51.4154 310.584 + vertex -365.905 52.4401 308.473 + vertex -362.456 51.3693 309.851 + endloop + endfacet + facet normal -0.0978924 -0.878251 -0.468074 + outer loop + vertex -371.441 50.5987 312.697 + vertex -368.666 51.4154 310.584 + vertex -366.846 50.0829 312.703 + endloop + endfacet + facet normal -0.141132 -0.942747 -0.302176 + outer loop + vertex -383.01 50.1609 318.143 + vertex -378.608 50.2762 315.728 + vertex -377.624 49.2945 318.331 + endloop + endfacet + facet normal -0.14452 -0.965634 -0.216021 + outer loop + vertex -386.839 50.3321 319.94 + vertex -383.01 50.1609 318.143 + vertex -383.504 49.5378 321.259 + endloop + endfacet + facet normal -0.172288 -0.973473 -0.150556 + outer loop + vertex -388.999 50.327 322.445 + vertex -386.839 50.3321 319.94 + vertex -383.504 49.5378 321.259 + endloop + endfacet + facet normal -0.208201 -0.973453 -0.0950826 + outer loop + vertex -392.534 50.8764 324.56 + vertex -388.999 50.327 322.445 + vertex -389.126 50.1146 324.899 + endloop + endfacet + facet normal -0.220545 -0.975375 0.00195153 + outer loop + vertex -396.315 51.7358 326.793 + vertex -392.534 50.8764 324.56 + vertex -391.121 50.5611 326.626 + endloop + endfacet + facet normal -0.223352 -0.968124 0.113358 + outer loop + vertex -395.349 51.7985 329.23 + vertex -396.315 51.7358 326.793 + vertex -392.749 51.1281 328.628 + endloop + endfacet + facet normal -0.222086 -0.948005 0.227958 + outer loop + vertex -395.548 52.3116 331.17 + vertex -395.349 51.7985 329.23 + vertex -393.923 51.8019 330.634 + endloop + endfacet + facet normal -0.227033 -0.925948 0.301789 + outer loop + vertex -397.044 53.3045 333.091 + vertex -395.548 52.3116 331.17 + vertex -395.468 52.7668 332.627 + endloop + endfacet + facet normal -0.229136 -0.897983 0.375664 + outer loop + vertex -398.694 54.5913 335.161 + vertex -397.044 53.3045 333.091 + vertex -397.216 54.0186 334.693 + endloop + endfacet + facet normal -0.234839 -0.859763 0.453495 + outer loop + vertex -400.206 56.134 337.302 + vertex -398.694 54.5913 335.161 + vertex -398.807 55.4912 336.808 + endloop + endfacet + facet normal -0.231927 -0.814329 0.532051 + outer loop + vertex -401.385 57.8994 339.49 + vertex -400.206 56.134 337.302 + vertex -400.104 57.1827 338.952 + endloop + endfacet + facet normal -0.212955 -0.765666 0.606965 + outer loop + vertex -402.374 59.9141 341.685 + vertex -401.385 57.8994 339.49 + vertex -401.072 59.1129 341.131 + endloop + endfacet + facet normal -0.203222 -0.721923 0.661459 + outer loop + vertex -403.158 62.0929 343.822 + vertex -402.374 59.9141 341.685 + vertex -401.731 61.1394 343.22 + endloop + endfacet + facet normal -0.2166 -0.672082 0.708089 + outer loop + vertex -403.527 64.6279 346.115 + vertex -403.158 62.0929 343.822 + vertex -402.185 62.6117 344.612 + endloop + endfacet + facet normal -0.113721 -0.645426 0.755309 + outer loop + vertex -403.979 67.0337 348.103 + vertex -403.527 64.6279 346.115 + vertex -401.945 66.9786 348.362 + endloop + endfacet + facet normal -0.116821 -0.603843 0.788497 + outer loop + vertex -404.532 69.498 349.908 + vertex -403.979 67.0337 348.103 + vertex -401.945 66.9786 348.362 + endloop + endfacet + facet normal -0.130821 -0.580972 0.803341 + outer loop + vertex -405.098 72.6409 352.089 + vertex -404.532 69.498 349.908 + vertex -402.67 72.4442 352.342 + endloop + endfacet + facet normal -0.130518 -0.546669 0.827114 + outer loop + vertex -404.343 75.3608 354.006 + vertex -405.098 72.6409 352.089 + vertex -402.67 72.4442 352.342 + endloop + endfacet + facet normal -0.158352 -0.506457 0.8476 + outer loop + vertex -404.744 78.9861 356.097 + vertex -404.343 75.3608 354.006 + vertex -402.436 77.7108 355.766 + endloop + endfacet + facet normal -0.132316 -0.421582 0.897085 + outer loop + vertex -378.599 85.5373 363.993 + vertex -387.47 87.9726 363.829 + vertex -383.983 86.7119 363.751 + endloop + endfacet + facet normal -0.127385 -0.453701 0.882002 + outer loop + vertex -368.029 83.001 364.215 + vertex -378.599 85.5373 363.993 + vertex -374.621 84.1612 363.86 + endloop + endfacet + facet normal 0.133753 -0.473557 0.870548 + outer loop + vertex 378.052 85.4362 364.001 + vertex 367.866 82.8852 364.178 + vertex 370.61 83.2129 363.935 + endloop + endfacet + facet normal 0.142865 -0.457735 0.877535 + outer loop + vertex 389.155 88.5455 363.815 + vertex 378.052 85.4362 364.001 + vertex 381.335 85.9999 363.76 + endloop + endfacet + facet normal -0.434001 0.065412 -0.898535 + outer loop + vertex 310.324 167.829 297.015 + vertex 314.45 169.032 295.109 + vertex 312.063 164.828 295.956 + endloop + endfacet + facet normal -0.306242 0.105934 -0.946041 + outer loop + vertex 307.607 167.133 297.816 + vertex 310.324 167.829 297.015 + vertex 308.498 164.54 297.237 + endloop + endfacet + facet normal 0.44335 0.115487 -0.888878 + outer loop + vertex -314.285 168.981 295.203 + vertex -310.46 167.866 296.966 + vertex -310.62 164.192 296.409 + endloop + endfacet + facet normal 0.137385 -0.52814 0.83797 + outer loop + vertex 363.594 81.5995 364.068 + vertex 370.61 83.2129 363.935 + vertex 367.866 82.8852 364.178 + endloop + endfacet + facet normal 0.152891 -0.536414 0.82999 + outer loop + vertex 370.61 83.2129 363.935 + vertex 381.335 85.9999 363.76 + vertex 378.052 85.4362 364.001 + endloop + endfacet + facet normal -0.150773 -0.517462 0.842318 + outer loop + vertex -383.983 86.7119 363.751 + vertex -374.621 84.1612 363.86 + vertex -378.599 85.5373 363.993 + endloop + endfacet + facet normal -0.137564 -0.524294 0.840352 + outer loop + vertex -374.621 84.1612 363.86 + vertex -365.136 81.8031 363.941 + vertex -368.029 83.001 364.215 + endloop + endfacet + facet normal -0.149252 -0.466856 0.871648 + outer loop + vertex -390.934 88.6951 363.623 + vertex -383.983 86.7119 363.751 + vertex -387.47 87.9726 363.829 + endloop + endfacet + facet normal 0.112413 -0.526967 0.842419 + outer loop + vertex 340.788 75.646 363.405 + vertex 360.214 80.4026 363.788 + vertex 355.211 80.1705 364.311 + endloop + endfacet + facet normal 0.100247 -0.543234 0.833575 + outer loop + vertex 315.739 70.9838 363.379 + vertex 340.788 75.646 363.405 + vertex 328.732 74.7232 364.254 + endloop + endfacet + facet normal -0.101667 -0.539805 0.835628 + outer loop + vertex -342.569 76.3826 363.642 + vertex -321.206 72.1359 363.497 + vertex -328.975 74.8591 364.311 + endloop + endfacet + facet normal -0.113229 -0.527831 0.841768 + outer loop + vertex -360.078 80.0328 363.575 + vertex -342.569 76.3826 363.642 + vertex -354.593 80.0527 364.326 + endloop + endfacet + facet normal -0.146141 -0.487748 0.860665 + outer loop + vertex -402.436 77.7108 355.766 + vertex -403.348 81.814 357.937 + vertex -404.744 78.9861 356.097 + endloop + endfacet + facet normal -0.107808 -0.538534 0.835679 + outer loop + vertex -402.67 72.4442 352.342 + vertex -402.436 77.7108 355.766 + vertex -404.343 75.3608 354.006 + endloop + endfacet + facet normal 0.145494 -0.607193 0.78112 + outer loop + vertex 400.531 70.3677 351.358 + vertex 397.818 66.11 348.553 + vertex 403.912 69.3812 349.961 + endloop + endfacet + facet normal -0.102143 -0.594396 0.797659 + outer loop + vertex -401.945 66.9786 348.362 + vertex -402.67 72.4442 352.342 + vertex -404.532 69.498 349.908 + endloop + endfacet + facet normal 0.150782 -0.645526 0.748706 + outer loop + vertex 397.818 66.11 348.553 + vertex 397.957 62.2815 345.224 + vertex 402.995 64.598 346.207 + endloop + endfacet + facet normal -0.150507 -0.624521 0.766369 + outer loop + vertex -386.865 60.1389 345.773 + vertex -382.348 63.1373 349.104 + vertex -392.622 62.1054 346.245 + endloop + endfacet + facet normal -0.109881 -0.647147 0.754405 + outer loop + vertex -402.103 63.1815 345.082 + vertex -401.945 66.9786 348.362 + vertex -403.527 64.6279 346.115 + endloop + endfacet + facet normal -0.176444 -0.642641 0.745574 + outer loop + vertex -396.275 65.2498 348.091 + vertex -398.395 61.7385 344.563 + vertex -392.622 62.1054 346.245 + endloop + endfacet + facet normal 0.183034 -0.753033 0.632013 + outer loop + vertex 400.958 60.0662 342.302 + vertex 400.023 58.1 340.23 + vertex 403.027 59.9042 341.51 + endloop + endfacet + facet normal 0.162738 -0.66365 0.730127 + outer loop + vertex 397.957 62.2815 345.224 + vertex 401.276 61.9417 344.176 + vertex 402.995 64.598 346.207 + endloop + endfacet + facet normal 0.179169 -0.710407 0.680603 + outer loop + vertex 401.276 61.9417 344.176 + vertex 400.958 60.0662 342.302 + vertex 403.747 62.1234 343.715 + endloop + endfacet + facet normal -0.168535 -0.668753 0.724131 + outer loop + vertex -393.437 59.6628 343.8 + vertex -392.622 62.1054 346.245 + vertex -398.395 61.7385 344.563 + endloop + endfacet + facet normal -0.17307 -0.729947 0.66123 + outer loop + vertex -392.863 57.0464 341.062 + vertex -393.437 59.6628 343.8 + vertex -398.58 59.146 341.883 + endloop + endfacet + facet normal -0.186739 -0.699579 0.689723 + outer loop + vertex -398.395 61.7385 344.563 + vertex -398.58 59.146 341.883 + vertex -393.437 59.6628 343.8 + endloop + endfacet + facet normal -0.188163 -0.757111 0.625601 + outer loop + vertex -398.58 59.146 341.883 + vertex -398.453 57.3625 339.763 + vertex -392.863 57.0464 341.062 + endloop + endfacet + facet normal -0.181315 -0.704638 0.68601 + outer loop + vertex -401.731 61.1394 343.22 + vertex -402.185 62.6117 344.612 + vertex -403.158 62.0929 343.822 + endloop + endfacet + facet normal -0.0754906 -0.627794 0.77471 + outer loop + vertex -402.185 62.6117 344.612 + vertex -402.103 63.1815 345.082 + vertex -403.527 64.6279 346.115 + endloop + endfacet + facet normal -0.171654 -0.733591 0.657555 + outer loop + vertex -401.072 59.1129 341.131 + vertex -401.731 61.1394 343.22 + vertex -402.374 59.9141 341.685 + endloop + endfacet + facet normal 0.195795 -0.841748 0.503115 + outer loop + vertex 398.822 56.305 338.126 + vertex 397.458 54.7168 336 + vertex 400.64 56.1595 337.175 + endloop + endfacet + facet normal 0.189569 -0.797728 0.572446 + outer loop + vertex 400.023 58.1 340.23 + vertex 398.822 56.305 338.126 + vertex 401.892 57.9086 339.344 + endloop + endfacet + facet normal -0.202188 -0.785026 0.585537 + outer loop + vertex -389.629 54.8987 339.299 + vertex -392.863 57.0464 341.062 + vertex -395.923 55.5915 338.054 + endloop + endfacet + facet normal -0.193654 -0.83546 0.5143 + outer loop + vertex -390.502 53.606 336.87 + vertex -389.629 54.8987 339.299 + vertex -395.923 55.5915 338.054 + endloop + endfacet + facet normal -0.177632 -0.802813 0.569155 + outer loop + vertex -398.453 57.3625 339.763 + vertex -395.923 55.5915 338.054 + vertex -392.863 57.0464 341.062 + endloop + endfacet + facet normal -0.202926 -0.84704 0.491268 + outer loop + vertex -395.923 55.5915 338.054 + vertex -396.011 54.2696 335.739 + vertex -390.502 53.606 336.87 + endloop + endfacet + facet normal -0.178182 -0.774542 0.606906 + outer loop + vertex -400.104 57.1827 338.952 + vertex -401.072 59.1129 341.131 + vertex -401.385 57.8994 339.49 + endloop + endfacet + facet normal -0.189276 -0.823299 0.535119 + outer loop + vertex -398.807 55.4912 336.808 + vertex -400.104 57.1827 338.952 + vertex -400.206 56.134 337.302 + endloop + endfacet + facet normal 0.209631 -0.916338 0.341143 + outer loop + vertex 395.884 53.3363 333.889 + vertex 394.078 52.163 331.847 + vertex 397.561 53.3663 332.939 + endloop + endfacet + facet normal 0.203613 -0.882025 0.42494 + outer loop + vertex 397.458 54.7168 336 + vertex 395.884 53.3363 333.889 + vertex 399.214 54.6471 335.014 + endloop + endfacet + facet normal -0.206083 -0.873826 0.440407 + outer loop + vertex -388.508 52.0098 334.636 + vertex -390.502 53.606 336.87 + vertex -394.081 53.0798 334.152 + endloop + endfacet + facet normal -0.212253 -0.905458 0.367551 + outer loop + vertex -386.969 50.8277 332.613 + vertex -388.508 52.0098 334.636 + vertex -392.267 51.8929 332.177 + endloop + endfacet + facet normal -0.193988 -0.883507 0.426361 + outer loop + vertex -396.011 54.2696 335.739 + vertex -394.081 53.0798 334.152 + vertex -390.502 53.606 336.87 + endloop + endfacet + facet normal -0.205999 -0.910622 0.358234 + outer loop + vertex -394.081 53.0798 334.152 + vertex -392.267 51.8929 332.177 + vertex -388.508 52.0098 334.636 + endloop + endfacet + facet normal -0.190278 -0.867023 0.460506 + outer loop + vertex -397.216 54.0186 334.693 + vertex -398.807 55.4912 336.808 + vertex -398.694 54.5913 335.161 + endloop + endfacet + facet normal -0.195786 -0.903337 0.381642 + outer loop + vertex -395.468 52.7668 332.627 + vertex -397.216 54.0186 334.693 + vertex -397.044 53.3045 333.091 + endloop + endfacet + facet normal 0.209586 -0.965055 0.157299 + outer loop + vertex 392.336 51.2462 329.889 + vertex 391.013 50.6348 327.9 + vertex 395.63 51.8401 329.144 + endloop + endfacet + facet normal 0.210557 -0.943828 0.254664 + outer loop + vertex 394.078 52.163 331.847 + vertex 392.336 51.2462 329.889 + vertex 395.955 52.36 331.025 + endloop + endfacet + facet normal -0.217557 -0.93428 0.282473 + outer loop + vertex -385.129 49.8306 330.732 + vertex -386.969 50.8277 332.613 + vertex -390.276 50.8685 330.201 + endloop + endfacet + facet normal -0.22826 -0.956679 0.180728 + outer loop + vertex -382.695 48.9831 329.32 + vertex -385.129 49.8306 330.732 + vertex -387.347 49.8639 328.107 + endloop + endfacet + facet normal -0.211145 -0.938379 0.273612 + outer loop + vertex -392.267 51.8929 332.177 + vertex -390.276 50.8685 330.201 + vertex -386.969 50.8277 332.613 + endloop + endfacet + facet normal -0.211404 -0.963129 0.166404 + outer loop + vertex -390.276 50.8685 330.201 + vertex -387.347 49.8639 328.107 + vertex -385.129 49.8306 330.732 + endloop + endfacet + facet normal -0.193018 -0.933478 0.302262 + outer loop + vertex -393.923 51.8019 330.634 + vertex -395.468 52.7668 332.627 + vertex -395.548 52.3116 331.17 + endloop + endfacet + facet normal -0.199559 -0.958181 0.205097 + outer loop + vertex -392.749 51.1281 328.628 + vertex -393.923 51.8019 330.634 + vertex -395.349 51.7985 329.23 + endloop + endfacet + facet normal 0.211004 -0.977374 -0.0147631 + outer loop + vertex 389.568 50.1995 325.92 + vertex 388.522 49.9948 324.522 + vertex 392.736 50.905 324.494 + endloop + endfacet + facet normal 0.18582 -0.976058 -0.113057 + outer loop + vertex 388.522 49.9948 324.522 + vertex 384.596 49.2689 324.337 + vertex 388.263 50.1793 322.503 + endloop + endfacet + facet normal 0.213279 -0.975227 0.0586843 + outer loop + vertex 391.013 50.6348 327.9 + vertex 389.568 50.1995 325.92 + vertex 396.581 51.7796 326.692 + endloop + endfacet + facet normal -0.205051 -0.975642 0.0779563 + outer loop + vertex -381.366 48.5446 327.328 + vertex -382.695 48.9831 329.32 + vertex -387.347 49.8639 328.107 + endloop + endfacet + facet normal -0.184275 -0.982583 -0.023945 + outer loop + vertex -377.465 47.8753 324.767 + vertex -381.366 48.5446 327.328 + vertex -384.784 49.2287 325.563 + endloop + endfacet + facet normal -0.181498 -0.971327 -0.153564 + outer loop + vertex -369.703 46.324 325.407 + vertex -377.465 47.8753 324.767 + vertex -366.516 46.0922 323.105 + endloop + endfacet + facet normal -0.211456 -0.976899 0.0308999 + outer loop + vertex -387.347 49.8639 328.107 + vertex -384.784 49.2287 325.563 + vertex -381.366 48.5446 327.328 + endloop + endfacet + facet normal -0.188653 -0.979598 -0.069265 + outer loop + vertex -384.784 49.2287 325.563 + vertex -382.15 48.8437 323.833 + vertex -377.465 47.8753 324.767 + endloop + endfacet + facet normal -0.216502 -0.971248 0.0990139 + outer loop + vertex -391.121 50.5611 326.626 + vertex -392.749 51.1281 328.628 + vertex -396.315 51.7358 326.793 + endloop + endfacet + facet normal -0.218236 -0.975896 0.000292566 + outer loop + vertex -389.126 50.1146 324.899 + vertex -391.121 50.5611 326.626 + vertex -392.534 50.8764 324.56 + endloop + endfacet + facet normal -0.200826 -0.975026 -0.0948359 + outer loop + vertex -387.173 49.7861 324.14 + vertex -389.126 50.1146 324.899 + vertex -388.999 50.327 322.445 + endloop + endfacet + facet normal 0.173756 -0.975243 -0.136781 + outer loop + vertex 384.596 49.2689 324.337 + vertex 377.951 48.5076 321.324 + vertex 388.263 50.1793 322.503 + endloop + endfacet + facet normal -0.168256 -0.97204 -0.163792 + outer loop + vertex -382.15 48.8437 323.833 + vertex -377.091 48.3552 321.535 + vertex -377.465 47.8753 324.767 + endloop + endfacet + facet normal -0.168445 -0.977052 -0.130367 + outer loop + vertex -383.504 49.5378 321.259 + vertex -387.173 49.7861 324.14 + vertex -388.999 50.327 322.445 + endloop + endfacet + facet normal 0.15477 -0.957106 -0.244937 + outer loop + vertex 377.951 48.5076 321.324 + vertex 372.238 48.4185 318.062 + vertex 381.569 49.9086 318.135 + endloop + endfacet + facet normal -0.173975 -0.96127 -0.213757 + outer loop + vertex -368.087 47.0727 319.975 + vertex -366.516 46.0922 323.105 + vertex -377.091 48.3552 321.535 + endloop + endfacet + facet normal -0.147715 -0.965062 -0.216414 + outer loop + vertex -377.624 49.2945 318.331 + vertex -383.504 49.5378 321.259 + vertex -383.01 50.1609 318.143 + endloop + endfacet + facet normal -0.185363 -0.935573 -0.300572 + outer loop + vertex -377.091 48.3552 321.535 + vertex -371.077 48.3303 317.904 + vertex -368.087 47.0727 319.975 + endloop + endfacet + facet normal 0.13376 -0.924359 -0.357308 + outer loop + vertex 372.238 48.4185 318.062 + vertex 367.085 48.7569 315.257 + vertex 377.298 50.0413 315.758 + endloop + endfacet + facet normal -0.165291 -0.892829 -0.418969 + outer loop + vertex -359.391 46.8738 316.392 + vertex -363.479 46.9577 317.827 + vertex -365.023 48.4576 315.239 + endloop + endfacet + facet normal -0.171676 -0.932299 -0.318348 + outer loop + vertex -363.479 46.9577 317.827 + vertex -368.087 47.0727 319.975 + vertex -371.077 48.3303 317.904 + endloop + endfacet + facet normal -0.127098 -0.942999 -0.307571 + outer loop + vertex -372.282 49.5969 315.197 + vertex -377.624 49.2945 318.331 + vertex -378.608 50.2762 315.728 + endloop + endfacet + facet normal -0.16558 -0.892851 -0.418809 + outer loop + vertex -371.077 48.3303 317.904 + vertex -365.023 48.4576 315.239 + vertex -363.479 46.9577 317.827 + endloop + endfacet + facet normal 0.106645 -0.885684 -0.451874 + outer loop + vertex 367.085 48.7569 315.257 + vertex 361.426 49.3496 312.76 + vertex 369.657 50.2976 312.845 + endloop + endfacet + facet normal -0.101687 -0.911151 -0.39933 + outer loop + vertex -366.846 50.0829 312.703 + vertex -372.282 49.5969 315.197 + vertex -371.441 50.5987 312.697 + endloop + endfacet + facet normal 0.0777961 -0.838926 -0.538657 + outer loop + vertex 361.426 49.3496 312.76 + vertex 357.858 50.8127 309.966 + vertex 367.35 51.1962 310.74 + endloop + endfacet + facet normal -0.0643832 -0.868822 -0.490921 + outer loop + vertex -362.456 51.3693 309.851 + vertex -366.846 50.0829 312.703 + vertex -368.666 51.4154 310.584 + endloop + endfacet + facet normal 0.0388338 -0.794297 -0.606287 + outer loop + vertex 357.858 50.8127 309.966 + vertex 351.975 52.4331 307.466 + vertex 360.135 53.1643 307.031 + endloop + endfacet + facet normal -0.0241005 -0.826616 -0.562251 + outer loop + vertex -356.658 52.9522 307.275 + vertex -362.456 51.3693 309.851 + vertex -361.486 53.3582 306.885 + endloop + endfacet + facet normal -0.00466104 -0.72798 -0.685582 + outer loop + vertex 351.975 52.4331 307.466 + vertex 347.14 54.9833 304.791 + vertex 355.03 54.7669 304.967 + endloop + endfacet + facet normal 0.0261256 -0.778161 -0.627521 + outer loop + vertex -350.771 55.4629 304.407 + vertex -356.658 52.9522 307.275 + vertex -356.236 54.9809 304.777 + endloop + endfacet + facet normal -0.0634994 -0.673529 -0.736428 + outer loop + vertex 347.14 54.9833 304.791 + vertex 344.644 57.3774 302.817 + vertex 347.908 57.2358 302.665 + endloop + endfacet + facet normal 0.107987 -0.767117 -0.632354 + outer loop + vertex -346.698 57.7132 302.373 + vertex -350.771 55.4629 304.407 + vertex -348.442 57.3346 302.534 + endloop + endfacet + facet normal -0.0129899 -0.631271 -0.775454 + outer loop + vertex -346.815 55.0018 304.829 + vertex -344.248 57.6591 302.623 + vertex -342.935 55.8179 304.1 + endloop + endfacet + facet normal -0.146052 -0.615299 -0.774646 + outer loop + vertex 343.478 59.7581 300.95 + vertex 341.136 61.5165 299.995 + vertex 343.805 60.6742 300.161 + endloop + endfacet + facet normal -0.0634856 -0.663743 -0.745261 + outer loop + vertex 344.644 57.3774 302.817 + vertex 345.362 58.3468 301.892 + vertex 347.908 57.2358 302.665 + endloop + endfacet + facet normal -0.0985686 -0.640277 -0.761794 + outer loop + vertex 345.362 58.3468 301.892 + vertex 343.478 59.7581 300.95 + vertex 346.376 58.9249 301.275 + endloop + endfacet + facet normal 0.0707281 -0.579022 -0.812238 + outer loop + vertex -339.012 59.7051 301.465 + vertex -341.179 57.8536 302.596 + vertex -341.798 59.724 301.209 + endloop + endfacet + facet normal 0.0735162 -0.538247 -0.839575 + outer loop + vertex -341.798 59.724 301.209 + vertex -339.505 61.5844 300.217 + vertex -339.012 59.7051 301.465 + endloop + endfacet + facet normal 0.0991907 -0.65244 -0.751321 + outer loop + vertex -344.571 59.1189 301.298 + vertex -346.221 58.1136 301.953 + vertex -346.1 58.8168 301.359 + endloop + endfacet + facet normal 0.11209 -0.779282 -0.616567 + outer loop + vertex -346.221 58.1136 301.953 + vertex -346.698 57.7132 302.373 + vertex -348.442 57.3346 302.534 + endloop + endfacet + facet normal 0.157529 -0.644134 -0.748516 + outer loop + vertex -342.26 60.8461 300.298 + vertex -344.571 59.1189 301.298 + vertex -343.535 60.5343 300.298 + endloop + endfacet + facet normal -0.202453 -0.496277 -0.844229 + outer loop + vertex 338.863 63.495 299.143 + vertex 336.969 65.2924 298.541 + vertex 338.515 65.1299 298.265 + endloop + endfacet + facet normal -0.184545 -0.559793 -0.807821 + outer loop + vertex 341.136 61.5165 299.995 + vertex 338.863 63.495 299.143 + vertex 341.232 62.656 299.183 + endloop + endfacet + facet normal 0.106851 -0.530427 -0.84097 + outer loop + vertex -336.965 61.5233 300.579 + vertex -339.012 59.7051 301.465 + vertex -339.505 61.5844 300.217 + endloop + endfacet + facet normal 0.14187 -0.476414 -0.867699 + outer loop + vertex -335.128 63.5349 299.774 + vertex -336.965 61.5233 300.579 + vertex -337.481 63.4743 299.423 + endloop + endfacet + facet normal 0.111759 -0.484382 -0.867689 + outer loop + vertex -339.505 61.5844 300.217 + vertex -337.481 63.4743 299.423 + vertex -336.965 61.5233 300.579 + endloop + endfacet + facet normal 0.143806 -0.43834 -0.887231 + outer loop + vertex -337.481 63.4743 299.423 + vertex -335.742 65.581 298.664 + vertex -335.128 63.5349 299.774 + endloop + endfacet + facet normal 0.176268 -0.58691 -0.790232 + outer loop + vertex -340.005 62.7663 299.375 + vertex -342.26 60.8461 300.298 + vertex -341.094 62.5517 299.292 + endloop + endfacet + facet normal 0.146971 -0.49493 -0.856414 + outer loop + vertex -338.296 64.3229 298.769 + vertex -340.005 62.7663 299.375 + vertex -338.552 64.9216 298.379 + endloop + endfacet + facet normal -0.276154 -0.426944 -0.861079 + outer loop + vertex 335.732 67.1235 297.93 + vertex 334.077 69.5404 297.263 + vertex 336.417 67.8356 297.357 + endloop + endfacet + facet normal -0.201849 -0.429789 -0.880079 + outer loop + vertex 336.969 65.2924 298.541 + vertex 335.732 67.1235 297.93 + vertex 338.515 65.1299 298.265 + endloop + endfacet + facet normal 0.182571 -0.426084 -0.88607 + outer loop + vertex -333.403 66.1982 298.849 + vertex -335.128 63.5349 299.774 + vertex -335.742 65.581 298.664 + endloop + endfacet + facet normal 0.178798 -0.361361 -0.915123 + outer loop + vertex -331.398 68.1455 298.472 + vertex -333.403 66.1982 298.849 + vertex -332.724 69.7913 297.563 + endloop + endfacet + facet normal 0.177247 -0.40227 -0.898199 + outer loop + vertex -335.742 65.581 298.664 + vertex -334.457 67.7273 297.956 + vertex -333.403 66.1982 298.849 + endloop + endfacet + facet normal 0.231809 -0.366368 -0.901132 + outer loop + vertex -334.457 67.7273 297.956 + vertex -332.724 69.7913 297.563 + vertex -333.403 66.1982 298.849 + endloop + endfacet + facet normal 0.205904 -0.470664 -0.85795 + outer loop + vertex -336.733 66.1619 298.135 + vertex -338.296 64.3229 298.769 + vertex -338.552 64.9216 298.379 + endloop + endfacet + facet normal 0.267089 -0.454683 -0.849663 + outer loop + vertex -334.952 68.4899 297.449 + vertex -336.733 66.1619 298.135 + vertex -336.318 67.6551 297.466 + endloop + endfacet + facet normal -0.331991 -0.33992 -0.879907 + outer loop + vertex 332.643 71.9881 296.675 + vertex 331.794 73.8448 296.278 + vertex 332.922 73.2514 296.082 + endloop + endfacet + facet normal -0.338123 -0.27621 -0.899656 + outer loop + vertex 331.794 73.8448 296.278 + vertex 330.534 74.4487 296.567 + vertex 330.819 76.7 295.768 + endloop + endfacet + facet normal -0.31958 -0.393922 -0.861797 + outer loop + vertex 334.077 69.5404 297.263 + vertex 332.643 71.9881 296.675 + vertex 334.571 70.4797 296.65 + endloop + endfacet + facet normal 0.229108 -0.322619 -0.918383 + outer loop + vertex -330.201 71.2577 297.677 + vertex -331.398 68.1455 298.472 + vertex -332.724 69.7913 297.563 + endloop + endfacet + facet normal 0.234607 -0.271001 -0.933551 + outer loop + vertex -327.794 74.1345 297.447 + vertex -330.201 71.2577 297.677 + vertex -329.722 74.7041 296.797 + endloop + endfacet + facet normal 0.207199 -0.219934 -0.953256 + outer loop + vertex -325.627 72.8017 298.225 + vertex -327.794 74.1345 297.447 + vertex -325.176 75.5894 297.68 + endloop + endfacet + facet normal 0.223305 -0.312245 -0.923384 + outer loop + vertex -332.724 69.7913 297.563 + vertex -331.371 72.8476 296.856 + vertex -330.201 71.2577 297.677 + endloop + endfacet + facet normal 0.27471 -0.273574 -0.921787 + outer loop + vertex -331.371 72.8476 296.856 + vertex -329.722 74.7041 296.797 + vertex -330.201 71.2577 297.677 + endloop + endfacet + facet normal 0.31292 -0.415629 -0.85401 + outer loop + vertex -333.371 70.9937 296.81 + vertex -334.952 68.4899 297.449 + vertex -334.462 70.2878 296.754 + endloop + endfacet + facet normal 0.347351 -0.356578 -0.867295 + outer loop + vertex -332.151 73.4429 296.291 + vertex -333.371 70.9937 296.81 + vertex -332.846 73.1736 296.124 + endloop + endfacet + facet normal 0.379173 -0.289968 -0.878719 + outer loop + vertex -331.385 74.8377 296.162 + vertex -332.151 73.4429 296.291 + vertex -331.164 76.8562 295.591 + endloop + endfacet + facet normal -0.347177 -0.274074 -0.896857 + outer loop + vertex 330.534 74.4487 296.567 + vertex 327.111 78.8791 296.538 + vertex 330.819 76.7 295.768 + endloop + endfacet + facet normal 0.225453 -0.195534 -0.95443 + outer loop + vertex -324.073 78.1944 297.407 + vertex -325.176 75.5894 297.68 + vertex -327.132 78.9298 296.534 + endloop + endfacet + facet normal 0.254427 -0.214664 -0.942967 + outer loop + vertex -329.722 74.7041 296.797 + vertex -327.132 78.9298 296.534 + vertex -327.794 74.1345 297.447 + endloop + endfacet + facet normal 0.43495 -0.288779 -0.852892 + outer loop + vertex -329.498 78.8904 295.752 + vertex -331.385 74.8377 296.162 + vertex -331.164 76.8562 295.591 + endloop + endfacet + facet normal -0.364066 -0.188058 -0.91219 + outer loop + vertex 327.111 78.8791 296.538 + vertex 325.074 85.0665 296.075 + vertex 328.667 82.5365 295.163 + endloop + endfacet + facet normal 0.250409 -0.135302 -0.958639 + outer loop + vertex -322.365 84.2947 296.916 + vertex -323.564 81.4002 297.012 + vertex -324.683 85.8152 296.096 + endloop + endfacet + facet normal 0.236321 -0.155874 -0.959091 + outer loop + vertex -323.564 81.4002 297.012 + vertex -324.073 78.1944 297.407 + vertex -327.132 78.9298 296.534 + endloop + endfacet + facet normal 0.430071 -0.225535 -0.87417 + outer loop + vertex -327.384 84.1632 295.432 + vertex -329.498 78.8904 295.752 + vertex -329.215 82.6108 294.931 + endloop + endfacet + facet normal 0.227371 -0.142122 -0.963382 + outer loop + vertex -327.132 78.9298 296.534 + vertex -324.683 85.8152 296.096 + vertex -323.564 81.4002 297.012 + endloop + endfacet + facet normal -0.375446 -0.13486 -0.91698 + outer loop + vertex 325.074 85.0665 296.075 + vertex 324.104 91.0753 295.589 + vertex 326.852 87.273 295.023 + endloop + endfacet + facet normal 0.286221 -0.0962071 -0.953321 + outer loop + vertex -321.096 90.2152 296.652 + vertex -322.001 87.5179 296.653 + vertex -323.233 92.017 295.828 + endloop + endfacet + facet normal 0.267506 -0.108587 -0.957418 + outer loop + vertex -322.001 87.5179 296.653 + vertex -322.365 84.2947 296.916 + vertex -324.683 85.8152 296.096 + endloop + endfacet + facet normal 0.456388 -0.169808 -0.873427 + outer loop + vertex -325.891 90.4484 294.99 + vertex -327.384 84.1632 295.432 + vertex -327.575 87.2433 294.733 + endloop + endfacet + facet normal 0.264393 -0.103206 -0.958877 + outer loop + vertex -324.683 85.8152 296.096 + vertex -323.233 92.017 295.828 + vertex -322.001 87.5179 296.653 + endloop + endfacet + facet normal -0.415882 -0.102353 -0.90364 + outer loop + vertex 324.104 91.0753 295.589 + vertex 322.952 97.4953 295.392 + vertex 325.814 94.2699 294.44 + endloop + endfacet + facet normal 0.305702 -0.0702736 -0.94953 + outer loop + vertex -320.063 96.0122 296.529 + vertex -320.858 93.3785 296.468 + vertex -322.147 97.93 295.716 + endloop + endfacet + facet normal 0.300538 -0.0779729 -0.950577 + outer loop + vertex -320.858 93.3785 296.468 + vertex -321.096 90.2152 296.652 + vertex -323.233 92.017 295.828 + endloop + endfacet + facet normal 0.476047 -0.121492 -0.870988 + outer loop + vertex -324.632 97.016 294.762 + vertex -325.891 90.4484 294.99 + vertex -326.367 94.3462 294.186 + endloop + endfacet + facet normal 0.297931 -0.07285 -0.951803 + outer loop + vertex -323.233 92.017 295.828 + vertex -322.147 97.93 295.716 + vertex -320.858 93.3785 296.468 + endloop + endfacet + facet normal -0.419988 -0.0756146 -0.904374 + outer loop + vertex 322.952 97.4953 295.392 + vertex 321.644 103.297 295.514 + vertex 324.337 101.798 294.389 + endloop + endfacet + facet normal 0.315955 -0.0564493 -0.947094 + outer loop + vertex -319.165 101.823 296.481 + vertex -319.918 99.1851 296.387 + vertex -321.229 103.685 295.682 + endloop + endfacet + facet normal 0.317094 -0.0566885 -0.946698 + outer loop + vertex -319.918 99.1851 296.387 + vertex -320.063 96.0122 296.529 + vertex -322.147 97.93 295.716 + endloop + endfacet + facet normal 0.465711 -0.0875524 -0.880595 + outer loop + vertex -323.452 102.725 294.818 + vertex -324.632 97.016 294.762 + vertex -324.96 101.873 294.105 + endloop + endfacet + facet normal 0.316829 -0.0561516 -0.946819 + outer loop + vertex -322.147 97.93 295.716 + vertex -321.229 103.685 295.682 + vertex -319.918 99.1851 296.387 + endloop + endfacet + facet normal -0.428229 -0.062842 -0.901483 + outer loop + vertex 321.644 103.297 295.514 + vertex 321.141 108.979 295.357 + vertex 323.866 106.57 294.23 + endloop + endfacet + facet normal 0.322481 -0.0505894 -0.945223 + outer loop + vertex -318.31 107.661 296.471 + vertex -319.041 105 296.364 + vertex -320.383 109.498 295.665 + endloop + endfacet + facet normal 0.32328 -0.04748 -0.945111 + outer loop + vertex -319.041 105 296.364 + vertex -319.165 101.823 296.481 + vertex -321.229 103.685 295.682 + endloop + endfacet + facet normal 0.475683 -0.0714321 -0.876712 + outer loop + vertex -322.748 108.493 294.73 + vertex -323.452 102.725 294.818 + vertex -324.36 106.661 294.005 + endloop + endfacet + facet normal 0.324543 -0.0498704 -0.944555 + outer loop + vertex -321.229 103.685 295.682 + vertex -320.383 109.498 295.665 + vertex -319.041 105 296.364 + endloop + endfacet + facet normal -0.419291 -0.0611762 -0.905788 + outer loop + vertex 321.141 108.979 295.357 + vertex 320.296 114.91 295.347 + vertex 322.774 112.18 294.385 + endloop + endfacet + facet normal 0.323164 -0.0492639 -0.94506 + outer loop + vertex -317.45 113.516 296.474 + vertex -318.181 110.842 296.363 + vertex -319.508 115.351 295.675 + endloop + endfacet + facet normal 0.326806 -0.0451786 -0.944011 + outer loop + vertex -318.181 110.842 296.363 + vertex -318.31 107.661 296.471 + vertex -320.383 109.498 295.665 + endloop + endfacet + facet normal 0.462294 -0.0677893 -0.884132 + outer loop + vertex -321.9 114.401 294.721 + vertex -322.748 108.493 294.73 + vertex -323.316 112.239 294.146 + endloop + endfacet + facet normal 0.328086 -0.0475695 -0.943449 + outer loop + vertex -320.383 109.498 295.665 + vertex -319.508 115.351 295.675 + vertex -318.181 110.842 296.363 + endloop + endfacet + facet normal -0.423259 -0.062563 -0.903846 + outer loop + vertex 320.296 114.91 295.347 + vertex 319.107 120.737 295.501 + vertex 321.763 119.024 294.376 + endloop + endfacet + facet normal 0.324547 -0.0492964 -0.944584 + outer loop + vertex -316.598 119.425 296.475 + vertex -317.328 116.724 296.365 + vertex -318.652 121.261 295.674 + endloop + endfacet + facet normal 0.327012 -0.0444776 -0.943973 + outer loop + vertex -317.328 116.724 296.365 + vertex -317.45 113.516 296.474 + vertex -319.508 115.351 295.675 + endloop + endfacet + facet normal 0.464247 -0.0694253 -0.88298 + outer loop + vertex -320.894 120.076 294.803 + vertex -321.9 114.401 294.721 + vertex -322.364 119.052 294.111 + endloop + endfacet + facet normal 0.328861 -0.0478212 -0.943167 + outer loop + vertex -319.508 115.351 295.675 + vertex -318.652 121.261 295.674 + vertex -317.328 116.724 296.365 + endloop + endfacet + facet normal -0.434164 -0.0620573 -0.898694 + outer loop + vertex 319.107 120.737 295.501 + vertex 318.578 126.741 295.342 + vertex 321.399 123.796 294.183 + endloop + endfacet + facet normal 0.32839 -0.0482695 -0.943308 + outer loop + vertex -315.739 125.411 296.478 + vertex -316.456 122.66 296.369 + vertex -317.788 127.199 295.673 + endloop + endfacet + facet normal 0.327705 -0.0453716 -0.94369 + outer loop + vertex -316.456 122.66 296.369 + vertex -316.598 119.425 296.475 + vertex -318.652 121.261 295.674 + endloop + endfacet + facet normal 0.476923 -0.0700923 -0.876146 + outer loop + vertex -320.202 126.17 294.692 + vertex -320.894 120.076 294.803 + vertex -321.892 123.854 293.958 + endloop + endfacet + facet normal 0.329176 -0.0479988 -0.943048 + outer loop + vertex -318.652 121.261 295.674 + vertex -317.788 127.199 295.673 + vertex -316.456 122.66 296.369 + endloop + endfacet + facet normal -0.436609 -0.0638469 -0.897383 + outer loop + vertex 318.578 126.741 295.342 + vertex 317.396 132.577 295.502 + vertex 320.336 131.141 294.174 + endloop + endfacet + facet normal 0.328409 -0.0499765 -0.943213 + outer loop + vertex -314.858 131.412 296.48 + vertex -315.591 128.661 296.37 + vertex -316.918 133.126 295.672 + endloop + endfacet + facet normal 0.330028 -0.0461819 -0.942841 + outer loop + vertex -315.591 128.661 296.37 + vertex -315.739 125.411 296.478 + vertex -317.788 127.199 295.673 + endloop + endfacet + facet normal 0.478778 -0.0715214 -0.875018 + outer loop + vertex -319.173 131.87 294.79 + vertex -320.202 126.17 294.692 + vertex -320.825 131.189 293.941 + endloop + endfacet + facet normal 0.331595 -0.0488636 -0.942155 + outer loop + vertex -317.788 127.199 295.673 + vertex -316.918 133.126 295.672 + vertex -315.591 128.661 296.37 + endloop + endfacet + facet normal -0.428411 -0.0606989 -0.901543 + outer loop + vertex 317.396 132.577 295.502 + vertex 316.866 138.475 295.357 + vertex 319.397 135.44 294.358 + endloop + endfacet + facet normal 0.332731 -0.0496764 -0.941713 + outer loop + vertex -314.023 137.338 296.476 + vertex -314.732 134.628 296.369 + vertex -316.065 139.017 295.666 + endloop + endfacet + facet normal 0.331731 -0.0455382 -0.942274 + outer loop + vertex -314.732 134.628 296.369 + vertex -314.858 131.412 296.48 + vertex -316.918 133.126 295.672 + endloop + endfacet + facet normal 0.471752 -0.0695129 -0.878987 + outer loop + vertex -318.462 137.901 294.694 + vertex -319.173 131.87 294.79 + vertex -319.98 135.459 294.073 + endloop + endfacet + facet normal 0.333961 -0.0492366 -0.9413 + outer loop + vertex -316.918 133.126 295.672 + vertex -316.065 139.017 295.666 + vertex -314.732 134.628 296.369 + endloop + endfacet + facet normal -0.427145 -0.0645991 -0.901872 + outer loop + vertex 316.866 138.475 295.357 + vertex 315.701 144.328 295.489 + vertex 318.341 142.714 294.354 + endloop + endfacet + facet normal 0.334616 -0.049332 -0.941063 + outer loop + vertex -313.197 143.174 296.473 + vertex -313.895 140.489 296.366 + vertex -315.227 144.901 295.661 + endloop + endfacet + facet normal 0.334985 -0.0466245 -0.941069 + outer loop + vertex -313.895 140.489 296.366 + vertex -314.023 137.338 296.476 + vertex -316.065 139.017 295.666 + endloop + endfacet + facet normal 0.472485 -0.0705982 -0.878507 + outer loop + vertex -317.436 143.633 294.785 + vertex -318.462 137.901 294.694 + vertex -318.881 142.702 294.083 + endloop + endfacet + facet normal 0.336247 -0.0487513 -0.940511 + outer loop + vertex -316.065 139.017 295.666 + vertex -315.227 144.901 295.661 + vertex -313.895 140.489 296.366 + endloop + endfacet + facet normal -0.430395 -0.0686541 -0.900026 + outer loop + vertex 315.701 144.328 295.489 + vertex 315.081 150.26 295.333 + vertex 317.876 147.627 294.197 + endloop + endfacet + facet normal 0.337573 -0.0487493 -0.940036 + outer loop + vertex -312.376 149.126 296.468 + vertex -313.071 146.377 296.36 + vertex -314.377 150.895 295.657 + endloop + endfacet + facet normal 0.336896 -0.0463389 -0.940401 + outer loop + vertex -313.071 146.377 296.36 + vertex -313.197 143.174 296.473 + vertex -315.227 144.901 295.661 + endloop + endfacet + facet normal 0.48244 -0.068856 -0.873219 + outer loop + vertex -316.719 149.63 294.709 + vertex -317.436 143.633 294.785 + vertex -318.3 147.615 293.994 + endloop + endfacet + facet normal 0.338209 -0.0485318 -0.939819 + outer loop + vertex -315.227 144.901 295.661 + vertex -314.377 150.895 295.657 + vertex -313.071 146.377 296.36 + endloop + endfacet + facet normal -0.422104 -0.0675682 -0.904026 + outer loop + vertex 315.081 150.26 295.333 + vertex 314.03 156.26 295.375 + vertex 316.612 153.514 294.375 + endloop + endfacet + facet normal 0.327188 -0.0518189 -0.943537 + outer loop + vertex -311.477 155.083 296.473 + vertex -312.235 152.374 296.359 + vertex -313.447 156.893 295.691 + endloop + endfacet + facet normal 0.339719 -0.0460303 -0.9394 + outer loop + vertex -312.235 152.374 296.359 + vertex -312.376 149.126 296.468 + vertex -314.377 150.895 295.657 + endloop + endfacet + facet normal 0.47012 -0.0657928 -0.880147 + outer loop + vertex -315.798 155.83 294.737 + vertex -316.719 149.63 294.709 + vertex -317.233 153.47 294.147 + endloop + endfacet + facet normal 0.340631 -0.047543 -0.938994 + outer loop + vertex -314.377 150.895 295.657 + vertex -313.447 156.893 295.691 + vertex -312.235 152.374 296.359 + endloop + endfacet + facet normal -0.440172 -0.0526666 -0.896368 + outer loop + vertex 314.03 156.26 295.375 + vertex 313.088 161.135 295.552 + vertex 315.293 160.231 294.522 + endloop + endfacet + facet normal -0.37363 -0.00203358 -0.927576 + outer loop + vertex 313.088 161.135 295.552 + vertex 310.745 162.098 296.493 + vertex 312.063 164.828 295.956 + endloop + endfacet + facet normal 0.291306 -0.0446023 -0.95559 + outer loop + vertex -310.444 160.866 296.5 + vertex -311.24 158.238 296.38 + vertex -312.7 162.89 295.718 + endloop + endfacet + facet normal 0.32658 -0.0525546 -0.943707 + outer loop + vertex -311.24 158.238 296.38 + vertex -311.477 155.083 296.473 + vertex -313.447 156.893 295.691 + endloop + endfacet + facet normal 0.479159 -0.0600375 -0.875672 + outer loop + vertex -314.722 161.807 294.916 + vertex -315.798 155.83 294.737 + vertex -316.198 160.588 294.192 + endloop + endfacet + facet normal 0.31731 -0.0353129 -0.947664 + outer loop + vertex -313.447 156.893 295.691 + vertex -312.7 162.89 295.718 + vertex -311.24 158.238 296.38 + endloop + endfacet + facet normal -0.344575 0.128304 -0.929949 + outer loop + vertex 312.063 164.828 295.956 + vertex 308.498 164.54 297.237 + vertex 310.324 167.829 297.015 + endloop + endfacet + facet normal 0.320425 -0.00890817 -0.947232 + outer loop + vertex -310.62 164.192 296.409 + vertex -310.444 160.866 296.5 + vertex -312.7 162.89 295.718 + endloop + endfacet + facet normal 0.563834 -0.000211751 -0.825888 + outer loop + vertex -314.367 169.006 295.156 + vertex -314.722 161.807 294.916 + vertex -315.729 165.468 294.228 + endloop + endfacet + facet normal 0.31448 0.00166039 -0.949263 + outer loop + vertex -312.7 162.89 295.718 + vertex -314.285 168.981 295.203 + vertex -310.62 164.192 296.409 + endloop + endfacet + facet normal -0.442825 -0.0246588 -0.896269 + outer loop + vertex 314.87 164.527 294.578 + vertex 313.088 161.135 295.552 + vertex 312.063 164.828 295.956 + endloop + endfacet + facet normal -0.150473 -0.624632 0.766285 + outer loop + vertex -392.622 62.1054 346.245 + vertex -382.348 63.1373 349.104 + vertex -396.275 65.2498 348.091 + endloop + endfacet + facet normal -0.182893 -0.969178 -0.165059 + outer loop + vertex -366.516 46.0922 323.105 + vertex -377.465 47.8753 324.767 + vertex -377.091 48.3552 321.535 + endloop + endfacet + facet normal 0.201985 -0.210016 -0.956606 + outer loop + vertex -325.176 75.5894 297.68 + vertex -327.794 74.1345 297.447 + vertex -327.132 78.9298 296.534 + endloop + endfacet + facet normal 0.162235 -0.554089 0.816496 + outer loop + vertex 408.888 71.3492 350.369 + vertex 415.769 73.226 350.275 + vertex 408.492 75.8224 353.483 + endloop + endfacet + facet normal 0.16518 -0.549189 0.819211 + outer loop + vertex 408.492 75.8224 353.483 + vertex 415.769 73.226 350.275 + vertex 416.063 77.6543 353.185 + endloop + endfacet + facet normal 0.172042 -0.607912 0.775141 + outer loop + vertex 407.772 67.4936 347.593 + vertex 415.316 69.4936 347.487 + vertex 408.888 71.3492 350.369 + endloop + endfacet + facet normal 0.175005 -0.602804 0.77846 + outer loop + vertex 408.888 71.3492 350.369 + vertex 415.316 69.4936 347.487 + vertex 415.769 73.226 350.275 + endloop + endfacet + facet normal 0.183907 -0.655458 0.732497 + outer loop + vertex 407.829 64.2388 344.666 + vertex 414.641 66.2918 344.793 + vertex 407.772 67.4936 347.593 + endloop + endfacet + facet normal 0.184 -0.655269 0.732644 + outer loop + vertex 407.772 67.4936 347.593 + vertex 414.641 66.2918 344.793 + vertex 415.316 69.4936 347.487 + endloop + endfacet + facet normal 0.199373 -0.70455 0.681072 + outer loop + vertex 407.173 61.6623 342.193 + vertex 413.825 63.5542 342.203 + vertex 407.829 64.2388 344.666 + endloop + endfacet + facet normal 0.199545 -0.704193 0.681391 + outer loop + vertex 407.829 64.2388 344.666 + vertex 413.825 63.5542 342.203 + vertex 414.641 66.2918 344.793 + endloop + endfacet + facet normal 0.213006 -0.754236 0.621093 + outer loop + vertex 406.005 59.4573 339.916 + vertex 412.668 61.2194 339.771 + vertex 407.173 61.6623 342.193 + endloop + endfacet + facet normal 0.213388 -0.753521 0.621829 + outer loop + vertex 407.173 61.6623 342.193 + vertex 412.668 61.2194 339.771 + vertex 413.825 63.5542 342.203 + endloop + endfacet + facet normal 0.222412 -0.802354 0.55386 + outer loop + vertex 404.728 57.5614 337.682 + vertex 411.283 59.21 337.438 + vertex 406.005 59.4573 339.916 + endloop + endfacet + facet normal 0.223745 -0.800167 0.556481 + outer loop + vertex 406.005 59.4573 339.916 + vertex 411.283 59.21 337.438 + vertex 412.668 61.2194 339.771 + endloop + endfacet + facet normal 0.228439 -0.848394 0.477539 + outer loop + vertex 403.392 55.9553 335.468 + vertex 409.838 57.5197 335.164 + vertex 404.728 57.5614 337.682 + endloop + endfacet + facet normal 0.230564 -0.845403 0.481802 + outer loop + vertex 404.728 57.5614 337.682 + vertex 409.838 57.5197 335.164 + vertex 411.283 59.21 337.438 + endloop + endfacet + facet normal 0.163358 -0.549272 0.819521 + outer loop + vertex 415.769 73.226 350.275 + vertex 425.064 74.9829 349.6 + vertex 416.063 77.6543 353.185 + endloop + endfacet + facet normal 0.157958 -0.559538 0.813613 + outer loop + vertex 416.063 77.6543 353.185 + vertex 425.064 74.9829 349.6 + vertex 425.621 79.137 352.349 + endloop + endfacet + facet normal 0.17545 -0.602791 0.778371 + outer loop + vertex 415.316 69.4936 347.487 + vertex 424.569 71.3722 346.856 + vertex 415.769 73.226 350.275 + endloop + endfacet + facet normal 0.171616 -0.610887 0.772894 + outer loop + vertex 415.769 73.226 350.275 + vertex 424.569 71.3722 346.856 + vertex 425.064 74.9829 349.6 + endloop + endfacet + facet normal 0.189448 -0.655256 0.731265 + outer loop + vertex 414.641 66.2918 344.793 + vertex 423.954 68.2958 344.176 + vertex 415.316 69.4936 347.487 + endloop + endfacet + facet normal 0.184539 -0.666326 0.722464 + outer loop + vertex 415.316 69.4936 347.487 + vertex 423.954 68.2958 344.176 + vertex 424.569 71.3722 346.856 + endloop + endfacet + facet normal 0.203268 -0.704228 0.680254 + outer loop + vertex 413.825 63.5542 342.203 + vertex 423.066 65.6074 341.567 + vertex 414.641 66.2918 344.793 + endloop + endfacet + facet normal 0.198351 -0.715545 0.669815 + outer loop + vertex 414.641 66.2918 344.793 + vertex 423.066 65.6074 341.567 + vertex 423.954 68.2958 344.176 + endloop + endfacet + facet normal 0.215979 -0.753676 0.620746 + outer loop + vertex 412.668 61.2194 339.771 + vertex 421.873 63.2518 339.035 + vertex 413.825 63.5542 342.203 + endloop + endfacet + facet normal 0.21158 -0.763246 0.610482 + outer loop + vertex 413.825 63.5542 342.203 + vertex 421.873 63.2518 339.035 + vertex 423.066 65.6074 341.567 + endloop + endfacet + facet normal 0.225406 -0.800304 0.555613 + outer loop + vertex 411.283 59.21 337.438 + vertex 420.374 61.1889 336.6 + vertex 412.668 61.2194 339.771 + endloop + endfacet + facet normal 0.221894 -0.807093 0.547142 + outer loop + vertex 412.668 61.2194 339.771 + vertex 420.374 61.1889 336.6 + vertex 421.873 63.2518 339.035 + endloop + endfacet + facet normal 0.232786 -0.84554 0.480493 + outer loop + vertex 409.838 57.5197 335.164 + vertex 418.796 59.4553 334.23 + vertex 411.283 59.21 337.438 + endloop + endfacet + facet normal 0.228851 -0.852052 0.470781 + outer loop + vertex 411.283 59.21 337.438 + vertex 418.796 59.4553 334.23 + vertex 420.374 61.1889 336.6 + endloop + endfacet + facet normal 0.168346 -0.559547 0.811521 + outer loop + vertex 425.064 74.9829 349.6 + vertex 435.835 76.8613 348.661 + vertex 425.621 79.137 352.349 + endloop + endfacet + facet normal 0.161343 -0.575319 0.801858 + outer loop + vertex 425.621 79.137 352.349 + vertex 435.835 76.8613 348.661 + vertex 436.414 80.7306 351.321 + endloop + endfacet + facet normal 0.182144 -0.610644 0.770673 + outer loop + vertex 424.569 71.3722 346.856 + vertex 435.316 73.3912 345.916 + vertex 425.064 74.9829 349.6 + endloop + endfacet + facet normal 0.175507 -0.626779 0.759174 + outer loop + vertex 425.064 74.9829 349.6 + vertex 435.316 73.3912 345.916 + vertex 435.835 76.8613 348.661 + endloop + endfacet + facet normal 0.196795 -0.666119 0.719414 + outer loop + vertex 423.954 68.2958 344.176 + vertex 434.707 70.4093 343.191 + vertex 424.569 71.3722 346.856 + endloop + endfacet + facet normal 0.190027 -0.683114 0.705157 + outer loop + vertex 424.569 71.3722 346.856 + vertex 434.707 70.4093 343.191 + vertex 435.316 73.3912 345.916 + endloop + endfacet + facet normal 0.210514 -0.715741 0.665882 + outer loop + vertex 423.066 65.6074 341.567 + vertex 433.84 67.7982 340.516 + vertex 423.954 68.2958 344.176 + endloop + endfacet + facet normal 0.203487 -0.732866 0.64923 + outer loop + vertex 423.954 68.2958 344.176 + vertex 433.84 67.7982 340.516 + vertex 434.707 70.4093 343.191 + endloop + endfacet + facet normal 0.221894 -0.76379 0.606125 + outer loop + vertex 421.873 63.2518 339.035 + vertex 432.613 65.4739 337.904 + vertex 423.066 65.6074 341.567 + endloop + endfacet + facet normal 0.215747 -0.777584 0.590607 + outer loop + vertex 423.066 65.6074 341.567 + vertex 432.613 65.4739 337.904 + vertex 433.84 67.7982 340.516 + endloop + endfacet + facet normal 0.231682 -0.807929 0.541826 + outer loop + vertex 420.374 61.1889 336.6 + vertex 431.045 63.4205 335.365 + vertex 421.873 63.2518 339.035 + endloop + endfacet + facet normal 0.225141 -0.820857 0.524886 + outer loop + vertex 421.873 63.2518 339.035 + vertex 431.045 63.4205 335.365 + vertex 432.613 65.4739 337.904 + endloop + endfacet + facet normal 0.237973 -0.852647 0.465147 + outer loop + vertex 418.796 59.4553 334.23 + vertex 429.281 61.6613 332.909 + vertex 420.374 61.1889 336.6 + endloop + endfacet + facet normal 0.232414 -0.861973 0.450539 + outer loop + vertex 420.374 61.1889 336.6 + vertex 429.281 61.6613 332.909 + vertex 431.045 63.4205 335.365 + endloop + endfacet + facet normal 0.177362 -0.575362 0.798437 + outer loop + vertex 435.835 76.8613 348.661 + vertex 447.157 78.952 347.653 + vertex 436.414 80.7306 351.321 + endloop + endfacet + facet normal 0.171494 -0.590511 0.788598 + outer loop + vertex 436.414 80.7306 351.321 + vertex 447.157 78.952 347.653 + vertex 447.497 82.6676 350.361 + endloop + endfacet + facet normal 0.192885 -0.626331 0.755318 + outer loop + vertex 435.316 73.3912 345.916 + vertex 446.705 75.6048 344.843 + vertex 435.835 76.8613 348.661 + endloop + endfacet + facet normal 0.185279 -0.646311 0.740239 + outer loop + vertex 435.835 76.8613 348.661 + vertex 446.705 75.6048 344.843 + vertex 447.157 78.952 347.653 + endloop + endfacet + facet normal 0.208613 -0.682572 0.700411 + outer loop + vertex 434.707 70.4093 343.191 + vertex 446.087 72.688 342.023 + vertex 435.316 73.3912 345.916 + endloop + endfacet + facet normal 0.200866 -0.702642 0.682603 + outer loop + vertex 435.316 73.3912 345.916 + vertex 446.087 72.688 342.023 + vertex 446.705 75.6048 344.843 + endloop + endfacet + facet normal 0.222336 -0.732818 0.643074 + outer loop + vertex 433.84 67.7982 340.516 + vertex 445.184 70.1168 339.236 + vertex 434.707 70.4093 343.191 + endloop + endfacet + facet normal 0.214555 -0.751518 0.623849 + outer loop + vertex 434.707 70.4093 343.191 + vertex 445.184 70.1168 339.236 + vertex 446.087 72.688 342.023 + endloop + endfacet + facet normal 0.234262 -0.778303 0.582551 + outer loop + vertex 432.613 65.4739 337.904 + vertex 443.893 67.8249 336.509 + vertex 433.84 67.7982 340.516 + endloop + endfacet + facet normal 0.226037 -0.795794 0.5618 + outer loop + vertex 433.84 67.7982 340.516 + vertex 443.893 67.8249 336.509 + vertex 445.184 70.1168 339.236 + endloop + endfacet + facet normal 0.242633 -0.822084 0.51508 + outer loop + vertex 431.045 63.4205 335.365 + vertex 442.22 65.7816 333.87 + vertex 432.613 65.4739 337.904 + endloop + endfacet + facet normal 0.235534 -0.835063 0.497186 + outer loop + vertex 432.613 65.4739 337.904 + vertex 442.22 65.7816 333.87 + vertex 443.893 67.8249 336.509 + endloop + endfacet + facet normal 0.247283 -0.862983 0.440581 + outer loop + vertex 429.281 61.6613 332.909 + vertex 440.305 64.0126 331.328 + vertex 431.045 63.4205 335.365 + endloop + endfacet + facet normal 0.241234 -0.872291 0.425341 + outer loop + vertex 431.045 63.4205 335.365 + vertex 440.305 64.0126 331.328 + vertex 442.22 65.7816 333.87 + endloop + endfacet + facet normal 0.185846 -0.589825 0.785855 + outer loop + vertex 447.157 78.952 347.653 + vertex 458.701 81.2888 346.676 + vertex 447.497 82.6676 350.361 + endloop + endfacet + facet normal 0.179723 -0.607389 0.773808 + outer loop + vertex 447.497 82.6676 350.361 + vertex 458.701 81.2888 346.676 + vertex 458.885 84.9113 349.477 + endloop + endfacet + facet normal 0.203086 -0.645429 0.736327 + outer loop + vertex 446.705 75.6048 344.843 + vertex 458.317 78.02 343.757 + vertex 447.157 78.952 347.653 + endloop + endfacet + facet normal 0.195665 -0.665868 0.719954 + outer loop + vertex 447.157 78.952 347.653 + vertex 458.317 78.02 343.757 + vertex 458.701 81.2888 346.676 + endloop + endfacet + facet normal 0.219617 -0.701828 0.677648 + outer loop + vertex 446.087 72.688 342.023 + vertex 457.702 75.1457 340.804 + vertex 446.705 75.6048 344.843 + endloop + endfacet + facet normal 0.211765 -0.722103 0.658576 + outer loop + vertex 446.705 75.6048 344.843 + vertex 457.702 75.1457 340.804 + vertex 458.317 78.02 343.757 + endloop + endfacet + facet normal 0.235245 -0.751143 0.616801 + outer loop + vertex 445.184 70.1168 339.236 + vertex 456.749 72.6025 337.852 + vertex 446.087 72.688 342.023 + endloop + endfacet + facet normal 0.22577 -0.772885 0.593024 + outer loop + vertex 446.087 72.688 342.023 + vertex 456.749 72.6025 337.852 + vertex 457.702 75.1457 340.804 + endloop + endfacet + facet normal 0.247019 -0.796245 0.552246 + outer loop + vertex 443.893 67.8249 336.509 + vertex 455.362 70.3049 334.954 + vertex 445.184 70.1168 339.236 + endloop + endfacet + facet normal 0.238313 -0.8133 0.530801 + outer loop + vertex 445.184 70.1168 339.236 + vertex 455.362 70.3049 334.954 + vertex 456.749 72.6025 337.852 + endloop + endfacet + facet normal 0.255437 -0.836143 0.485403 + outer loop + vertex 442.22 65.7816 333.87 + vertex 453.55 68.254 332.166 + vertex 443.893 67.8249 336.509 + endloop + endfacet + facet normal 0.246861 -0.85023 0.46494 + outer loop + vertex 443.893 67.8249 336.509 + vertex 453.55 68.254 332.166 + vertex 455.362 70.3049 334.954 + endloop + endfacet + facet normal 0.259521 -0.873314 0.412276 + outer loop + vertex 440.305 64.0126 331.328 + vertex 451.511 66.4797 329.5 + vertex 442.22 65.7816 333.87 + endloop + endfacet + facet normal 0.252155 -0.883397 0.395003 + outer loop + vertex 442.22 65.7816 333.87 + vertex 451.511 66.4797 329.5 + vertex 453.55 68.254 332.166 + endloop + endfacet + facet normal 0.189945 -0.606536 0.772033 + outer loop + vertex 458.701 81.2888 346.676 + vertex 470.435 83.8994 345.84 + vertex 458.885 84.9113 349.477 + endloop + endfacet + facet normal 0.183881 -0.625676 0.758101 + outer loop + vertex 458.885 84.9113 349.477 + vertex 470.435 83.8994 345.84 + vertex 470.544 87.4833 348.772 + endloop + endfacet + facet normal 0.20826 -0.664949 0.717266 + outer loop + vertex 458.317 78.02 343.757 + vertex 469.99 80.6519 342.808 + vertex 458.701 81.2888 346.676 + endloop + endfacet + facet normal 0.201972 -0.683046 0.701894 + outer loop + vertex 458.701 81.2888 346.676 + vertex 469.99 80.6519 342.808 + vertex 470.435 83.8994 345.84 + endloop + endfacet + facet normal 0.225553 -0.721273 0.654898 + outer loop + vertex 457.702 75.1457 340.804 + vertex 469.37 77.8127 339.722 + vertex 458.317 78.02 343.757 + endloop + endfacet + facet normal 0.218527 -0.739589 0.636595 + outer loop + vertex 458.317 78.02 343.757 + vertex 469.37 77.8127 339.722 + vertex 469.99 80.6519 342.808 + endloop + endfacet + facet normal 0.241216 -0.772368 0.58759 + outer loop + vertex 456.749 72.6025 337.852 + vertex 468.449 75.2929 336.586 + vertex 457.702 75.1457 340.804 + endloop + endfacet + facet normal 0.233163 -0.790429 0.566442 + outer loop + vertex 457.702 75.1457 340.804 + vertex 468.449 75.2929 336.586 + vertex 469.37 77.8127 339.722 + endloop + endfacet + facet normal 0.2546 -0.813377 0.523065 + outer loop + vertex 455.362 70.3049 334.954 + vertex 467.066 72.9912 333.435 + vertex 456.749 72.6025 337.852 + endloop + endfacet + facet normal 0.245145 -0.830945 0.499435 + outer loop + vertex 456.749 72.6025 337.852 + vertex 467.066 72.9912 333.435 + vertex 468.449 75.2929 336.586 + endloop + endfacet + facet normal 0.26321 -0.850832 0.454759 + outer loop + vertex 453.55 68.254 332.166 + vertex 465.174 70.8957 330.38 + vertex 455.362 70.3049 334.954 + endloop + endfacet + facet normal 0.254704 -0.863734 0.434844 + outer loop + vertex 455.362 70.3049 334.954 + vertex 465.174 70.8957 330.38 + vertex 467.066 72.9912 333.435 + endloop + endfacet + facet normal 0.26746 -0.883906 0.383635 + outer loop + vertex 451.511 66.4797 329.5 + vertex 462.972 69.0873 327.517 + vertex 453.55 68.254 332.166 + endloop + endfacet + facet normal 0.259289 -0.89407 0.365252 + outer loop + vertex 453.55 68.254 332.166 + vertex 462.972 69.0873 327.517 + vertex 465.174 70.8957 330.38 + endloop + endfacet + facet normal 0.190318 -0.625017 0.757055 + outer loop + vertex 470.435 83.8994 345.84 + vertex 481.829 86.7644 345.341 + vertex 470.544 87.4833 348.772 + endloop + endfacet + facet normal 0.186729 -0.637138 0.747789 + outer loop + vertex 470.544 87.4833 348.772 + vertex 481.829 86.7644 345.341 + vertex 481.541 90.3881 348.501 + endloop + endfacet + facet normal 0.208686 -0.682566 0.700396 + outer loop + vertex 469.99 80.6519 342.808 + vertex 481.189 83.4069 342.156 + vertex 470.435 83.8994 345.84 + endloop + endfacet + facet normal 0.204722 -0.693916 0.69034 + outer loop + vertex 470.435 83.8994 345.84 + vertex 481.189 83.4069 342.156 + vertex 481.829 86.7644 345.341 + endloop + endfacet + facet normal 0.224703 -0.739152 0.634951 + outer loop + vertex 469.37 77.8127 339.722 + vertex 480.343 80.5751 339.055 + vertex 469.99 80.6519 342.808 + endloop + endfacet + facet normal 0.22071 -0.749484 0.624148 + outer loop + vertex 469.99 80.6519 342.808 + vertex 480.343 80.5751 339.055 + vertex 481.189 83.4069 342.156 + endloop + endfacet + facet normal 0.240059 -0.790038 0.564102 + outer loop + vertex 468.449 75.2929 336.586 + vertex 479.667 78.1301 335.785 + vertex 469.37 77.8127 339.722 + endloop + endfacet + facet normal 0.235155 -0.801111 0.550385 + outer loop + vertex 469.37 77.8127 339.722 + vertex 479.667 78.1301 335.785 + vertex 480.343 80.5751 339.055 + endloop + endfacet + facet normal 0.252861 -0.830747 0.495904 + outer loop + vertex 467.066 72.9912 333.435 + vertex 478.509 75.8357 332.365 + vertex 468.449 75.2929 336.586 + endloop + endfacet + facet normal 0.24708 -0.841318 0.480765 + outer loop + vertex 468.449 75.2929 336.586 + vertex 478.509 75.8357 332.365 + vertex 479.667 78.1301 335.785 + endloop + endfacet + facet normal 0.264068 -0.8638 0.42909 + outer loop + vertex 465.174 70.8957 330.38 + vertex 476.877 73.7215 328.867 + vertex 467.066 72.9912 333.435 + endloop + endfacet + facet normal 0.255946 -0.875546 0.409769 + outer loop + vertex 467.066 72.9912 333.435 + vertex 476.877 73.7215 328.867 + vertex 478.509 75.8357 332.365 + endloop + endfacet + facet normal 0.267942 -0.894183 0.358669 + outer loop + vertex 462.972 69.0873 327.517 + vertex 474.587 71.8048 325.616 + vertex 465.174 70.8957 330.38 + endloop + endfacet + facet normal 0.26227 -0.900751 0.346211 + outer loop + vertex 465.174 70.8957 330.38 + vertex 474.587 71.8048 325.616 + vertex 476.877 73.7215 328.867 + endloop + endfacet + facet normal 0.186288 -0.637213 0.747835 + outer loop + vertex 481.829 86.7644 345.341 + vertex 491.066 89.8258 345.649 + vertex 481.541 90.3881 348.501 + endloop + endfacet + facet normal 0.187956 -0.631472 0.752274 + outer loop + vertex 481.541 90.3881 348.501 + vertex 491.066 89.8258 345.649 + vertex 490.257 93.4671 348.908 + endloop + endfacet + facet normal 0.212031 -0.693556 0.688494 + outer loop + vertex 481.189 83.4069 342.156 + vertex 491.62 86.1232 341.68 + vertex 481.829 86.7644 345.341 + endloop + endfacet + facet normal 0.209354 -0.700252 0.682509 + outer loop + vertex 481.829 86.7644 345.341 + vertex 491.62 86.1232 341.68 + vertex 491.066 89.8258 345.649 + endloop + endfacet + facet normal 0.223131 -0.749389 0.623401 + outer loop + vertex 480.343 80.5751 339.055 + vertex 488.574 82.9814 339.001 + vertex 481.189 83.4069 342.156 + endloop + endfacet + facet normal 0.223459 -0.748726 0.624079 + outer loop + vertex 481.189 83.4069 342.156 + vertex 488.574 82.9814 339.001 + vertex 491.62 86.1232 341.68 + endloop + endfacet + facet normal 0.236835 -0.800941 0.549911 + outer loop + vertex 479.667 78.1301 335.785 + vertex 488.981 80.9155 335.831 + vertex 480.343 80.5751 339.055 + endloop + endfacet + facet normal 0.237374 -0.799698 0.551487 + outer loop + vertex 480.343 80.5751 339.055 + vertex 488.981 80.9155 335.831 + vertex 488.574 82.9814 339.001 + endloop + endfacet + facet normal 0.248443 -0.841219 0.480237 + outer loop + vertex 478.509 75.8357 332.365 + vertex 488.256 78.6162 332.193 + vertex 479.667 78.1301 335.785 + endloop + endfacet + facet normal 0.248945 -0.840312 0.481562 + outer loop + vertex 479.667 78.1301 335.785 + vertex 488.256 78.6162 332.193 + vertex 488.981 80.9155 335.831 + endloop + endfacet + facet normal 0.257684 -0.875444 0.408897 + outer loop + vertex 476.877 73.7215 328.867 + vertex 487.049 76.4917 328.388 + vertex 478.509 75.8357 332.365 + endloop + endfacet + facet normal 0.257141 -0.876207 0.407603 + outer loop + vertex 478.509 75.8357 332.365 + vertex 487.049 76.4917 328.388 + vertex 488.256 78.6162 332.193 + endloop + endfacet + facet normal 0.267081 -0.900655 0.342764 + outer loop + vertex 474.587 71.8048 325.616 + vertex 486.057 74.5959 324.012 + vertex 476.877 73.7215 328.867 + endloop + endfacet + facet normal 0.262353 -0.905727 0.332911 + outer loop + vertex 476.877 73.7215 328.867 + vertex 486.057 74.5959 324.012 + vertex 487.049 76.4917 328.388 + endloop + endfacet + facet normal 0.171934 -0.677622 0.71503 + outer loop + vertex 497.474 89.2328 343.263 + vertex 500.301 91.3657 344.604 + vertex 496.893 92.7656 346.75 + endloop + endfacet + facet normal 0.194245 -0.651464 0.733392 + outer loop + vertex 496.893 92.7656 346.75 + vertex 500.301 91.3657 344.604 + vertex 500.407 95.1439 347.932 + endloop + endfacet + facet normal 0.200599 -0.738677 0.643519 + outer loop + vertex 497.976 86.6347 340.124 + vertex 500.543 88.2545 341.183 + vertex 497.474 89.2328 343.263 + endloop + endfacet + facet normal 0.222871 -0.71332 0.664457 + outer loop + vertex 497.474 89.2328 343.263 + vertex 500.543 88.2545 341.183 + vertex 500.301 91.3657 344.604 + endloop + endfacet + facet normal 0.22441 -0.786088 0.57594 + outer loop + vertex 495.51 83.7995 337.215 + vertex 499.849 85.4023 337.712 + vertex 497.976 86.6347 340.124 + endloop + endfacet + facet normal 0.245819 -0.77244 0.585585 + outer loop + vertex 497.976 86.6347 340.124 + vertex 499.849 85.4023 337.712 + vertex 500.543 88.2545 341.183 + endloop + endfacet + facet normal 0.230281 -0.827218 0.512524 + outer loop + vertex 495.042 81.0581 333.001 + vertex 499.082 82.9042 334.165 + vertex 495.51 83.7995 337.215 + endloop + endfacet + facet normal 0.241923 -0.817149 0.523203 + outer loop + vertex 495.51 83.7995 337.215 + vertex 499.082 82.9042 334.165 + vertex 499.849 85.4023 337.712 + endloop + endfacet + facet normal 0.241735 -0.866889 0.435967 + outer loop + vertex 494.156 78.8542 329.109 + vertex 498.287 80.6532 330.396 + vertex 495.042 81.0581 333.001 + endloop + endfacet + facet normal 0.258483 -0.852377 0.454577 + outer loop + vertex 495.042 81.0581 333.001 + vertex 498.287 80.6532 330.396 + vertex 499.082 82.9042 334.165 + endloop + endfacet + facet normal 0.248976 -0.899897 0.358046 + outer loop + vertex 493.129 76.9797 325.113 + vertex 497.151 78.6724 326.57 + vertex 494.156 78.8542 329.109 + endloop + endfacet + facet normal 0.26768 -0.885797 0.379093 + outer loop + vertex 494.156 78.8542 329.109 + vertex 497.151 78.6724 326.57 + vertex 498.287 80.6532 330.396 + endloop + endfacet + facet normal 0.258826 -0.921548 0.289411 + outer loop + vertex 492.99 75.6997 321.161 + vertex 495.981 76.98 322.563 + vertex 493.129 76.9797 325.113 + endloop + endfacet + facet normal 0.273182 -0.912173 0.305469 + outer loop + vertex 493.129 76.9797 325.113 + vertex 495.981 76.98 322.563 + vertex 497.151 78.6724 326.57 + endloop + endfacet + facet normal 0.320383 -0.93794 0.132751 + outer loop + vertex 492.381 74.1628 314.242 + vertex 494.565 75.4919 318.361 + vertex 492.18 74.4718 316.908 + endloop + endfacet + facet normal 0.28168 -0.955058 0.092309 + outer loop + vertex 490.09 73.1393 310.642 + vertex 492.381 74.1628 314.242 + vertex 489.233 73.1144 312.999 + endloop + endfacet + facet normal 0.223513 -0.927365 0.30006 + outer loop + vertex 397.561 53.3663 332.939 + vertex 395.955 52.36 331.025 + vertex 400.273 53.5417 331.46 + endloop + endfacet + facet normal 0.222773 -0.898878 0.377348 + outer loop + vertex 399.214 54.6471 335.014 + vertex 397.561 53.3663 332.939 + vertex 401.853 54.6059 333.358 + endloop + endfacet + facet normal 0.220019 -0.861492 0.457629 + outer loop + vertex 400.64 56.1595 337.175 + vertex 399.214 54.6471 335.014 + vertex 403.392 55.9553 335.468 + endloop + endfacet + facet normal 0.213812 -0.817049 0.535459 + outer loop + vertex 401.892 57.9086 339.344 + vertex 400.64 56.1595 337.175 + vertex 404.728 57.5614 337.682 + endloop + endfacet + facet normal 0.206644 -0.771058 0.602302 + outer loop + vertex 403.027 59.9042 341.51 + vertex 401.892 57.9086 339.344 + vertex 406.005 59.4573 339.916 + endloop + endfacet + facet normal 0.197161 -0.722488 0.662675 + outer loop + vertex 403.747 62.1234 343.715 + vertex 403.027 59.9042 341.51 + vertex 407.173 61.6623 342.193 + endloop + endfacet + facet normal 0.17966 -0.670416 0.719906 + outer loop + vertex 402.995 64.598 346.207 + vertex 403.747 62.1234 343.715 + vertex 407.829 64.2388 344.666 + endloop + endfacet + facet normal 0.176185 -0.646107 0.742633 + outer loop + vertex 403.275 67.0725 348.294 + vertex 402.995 64.598 346.207 + vertex 407.772 67.4936 347.593 + endloop + endfacet + facet normal 0.177481 -0.607932 0.773898 + outer loop + vertex 403.912 69.3812 349.961 + vertex 403.275 67.0725 348.294 + vertex 407.772 67.4936 347.593 + endloop + endfacet + facet normal 0.149311 -0.526875 0.836725 + outer loop + vertex 503.141 101.172 351.832 + vertex 503.045 103.809 353.509 + vertex 500.466 102.207 352.961 + endloop + endfacet + facet normal 0.156604 -0.56589 0.809471 + outer loop + vertex 502.915 97.8592 349.56 + vertex 503.141 101.172 351.832 + vertex 500.327 99.1747 350.98 + endloop + endfacet + facet normal 0.156477 -0.610093 0.776725 + outer loop + vertex 503.021 95.085 347.359 + vertex 502.915 97.8592 349.56 + vertex 500.407 95.1439 347.932 + endloop + endfacet + facet normal 0.145758 -0.664041 0.733352 + outer loop + vertex 502.515 92.6093 345.218 + vertex 503.021 95.085 347.359 + vertex 500.407 95.1439 347.932 + endloop + endfacet + facet normal 0.196597 -0.69265 0.693964 + outer loop + vertex 501.961 90.1975 342.968 + vertex 502.515 92.6093 345.218 + vertex 500.301 91.3657 344.604 + endloop + endfacet + facet normal 0.210356 -0.777583 0.592549 + outer loop + vertex 502.369 86.6226 338.393 + vertex 502.722 88.6288 340.9 + vertex 500.543 88.2545 341.183 + endloop + endfacet + facet normal 0.245331 -0.806736 0.537578 + outer loop + vertex 501.958 84.319 335.124 + vertex 502.369 86.6226 338.393 + vertex 499.849 85.4023 337.712 + endloop + endfacet + facet normal 0.255884 -0.841999 0.474933 + outer loop + vertex 501.375 82.1547 331.601 + vertex 501.958 84.319 335.124 + vertex 499.082 82.9042 334.165 + endloop + endfacet + facet normal 0.265766 -0.873608 0.407649 + outer loop + vertex 500.235 80.1291 328.003 + vertex 501.375 82.1547 331.601 + vertex 498.287 80.6532 330.396 + endloop + endfacet + facet normal 0.269399 -0.902064 0.337202 + outer loop + vertex 498.671 78.2961 324.349 + vertex 500.235 80.1291 328.003 + vertex 497.151 78.6724 326.57 + endloop + endfacet + facet normal 0.270549 -0.92325 0.272787 + outer loop + vertex 497.401 76.6868 320.162 + vertex 498.671 78.2961 324.349 + vertex 495.981 76.98 322.563 + endloop + endfacet + facet normal 0.276501 -0.942113 0.189661 + outer loop + vertex 495.296 75.1906 315.799 + vertex 497.401 76.6868 320.162 + vertex 494.565 75.4919 318.361 + endloop + endfacet + facet normal 0.266845 -0.954837 0.13069 + outer loop + vertex 493.428 74.0845 311.532 + vertex 495.296 75.1906 315.799 + vertex 492.381 74.1628 314.242 + endloop + endfacet + facet normal 0.251015 -0.964425 0.0829206 + outer loop + vertex 491.407 73.2621 308.084 + vertex 493.428 74.0845 311.532 + vertex 490.09 73.1393 310.642 + endloop + endfacet + facet normal 0.180912 -0.551106 0.814588 + outer loop + vertex 408.888 71.3492 350.369 + vertex 408.492 75.8224 353.483 + vertex 404.384 72.7732 352.333 + endloop + endfacet + facet normal 0.177145 -0.608327 0.773665 + outer loop + vertex 407.772 67.4936 347.593 + vertex 408.888 71.3492 350.369 + vertex 403.912 69.3812 349.961 + endloop + endfacet + facet normal 0.184758 -0.655343 0.732386 + outer loop + vertex 407.829 64.2388 344.666 + vertex 407.772 67.4936 347.593 + vertex 402.995 64.598 346.207 + endloop + endfacet + facet normal 0.206829 -0.70443 0.67897 + outer loop + vertex 407.173 61.6623 342.193 + vertex 407.829 64.2388 344.666 + vertex 403.747 62.1234 343.715 + endloop + endfacet + facet normal 0.217996 -0.754614 0.618899 + outer loop + vertex 406.005 59.4573 339.916 + vertex 407.173 61.6623 342.193 + vertex 403.027 59.9042 341.51 + endloop + endfacet + facet normal 0.225459 -0.802574 0.552307 + outer loop + vertex 404.728 57.5614 337.682 + vertex 406.005 59.4573 339.916 + vertex 401.892 57.9086 339.344 + endloop + endfacet + facet normal 0.232056 -0.848568 0.475482 + outer loop + vertex 403.392 55.9553 335.468 + vertex 404.728 57.5614 337.682 + vertex 400.64 56.1595 337.175 + endloop + endfacet + facet normal 0.223516 -0.964126 0.143183 + outer loop + vertex 402.11 53.187 328.44 + vertex 397.932 52.2887 328.913 + vertex 400.172 52.6921 328.132 + endloop + endfacet + facet normal 0.177646 -0.634058 0.752604 + outer loop + vertex 490.257 93.4671 348.908 + vertex 491.066 89.8258 345.649 + vertex 496.893 92.7656 346.75 + endloop + endfacet + facet normal 0.189447 -0.704632 0.683815 + outer loop + vertex 491.066 89.8258 345.649 + vertex 491.62 86.1232 341.68 + vertex 497.474 89.2328 343.263 + endloop + endfacet + facet normal 0.245519 -0.755692 0.607166 + outer loop + vertex 491.62 86.1232 341.68 + vertex 488.574 82.9814 339.001 + vertex 495.51 83.7995 337.215 + endloop + endfacet + facet normal 0.236411 -0.799953 0.55153 + outer loop + vertex 488.574 82.9814 339.001 + vertex 488.981 80.9155 335.831 + vertex 495.51 83.7995 337.215 + endloop + endfacet + facet normal 0.245131 -0.840815 0.482639 + outer loop + vertex 488.981 80.9155 335.831 + vertex 488.256 78.6162 332.193 + vertex 495.042 81.0581 333.001 + endloop + endfacet + facet normal 0.249851 -0.877023 0.410372 + outer loop + vertex 488.256 78.6162 332.193 + vertex 487.049 76.4917 328.388 + vertex 494.156 78.8542 329.109 + endloop + endfacet + facet normal 0.253577 -0.907248 0.335559 + outer loop + vertex 487.049 76.4917 328.388 + vertex 486.057 74.5959 324.012 + vertex 493.129 76.9797 325.113 + endloop + endfacet + facet normal 0.141504 -0.516888 0.844277 + outer loop + vertex 500.44 103.782 353.93 + vertex 500.466 102.207 352.961 + vertex 503.045 103.809 353.509 + endloop + endfacet + facet normal 0.137472 -0.546127 0.826345 + outer loop + vertex 500.466 102.207 352.961 + vertex 500.327 99.1747 350.98 + vertex 503.141 101.172 351.832 + endloop + endfacet + facet normal 0.13158 -0.596222 0.791964 + outer loop + vertex 500.327 99.1747 350.98 + vertex 500.407 95.1439 347.932 + vertex 502.915 97.8592 349.56 + endloop + endfacet + facet normal 0.203555 -0.670682 0.713268 + outer loop + vertex 497.474 89.2328 343.263 + vertex 496.893 92.7656 346.75 + vertex 491.066 89.8258 345.649 + endloop + endfacet + facet normal 0.163048 -0.65472 0.738077 + outer loop + vertex 500.407 95.1439 347.932 + vertex 500.301 91.3657 344.604 + vertex 502.515 92.6093 345.218 + endloop + endfacet + facet normal 0.216531 -0.734767 0.642831 + outer loop + vertex 497.976 86.6347 340.124 + vertex 497.474 89.2328 343.263 + vertex 491.62 86.1232 341.68 + endloop + endfacet + facet normal 0.15038 -0.726096 0.670948 + outer loop + vertex 500.301 91.3657 344.604 + vertex 500.543 88.2545 341.183 + vertex 501.961 90.1975 342.968 + endloop + endfacet + facet normal 0.206786 -0.782465 0.587357 + outer loop + vertex 495.51 83.7995 337.215 + vertex 497.976 86.6347 340.124 + vertex 491.62 86.1232 341.68 + endloop + endfacet + facet normal 0.214798 -0.775207 0.594067 + outer loop + vertex 500.543 88.2545 341.183 + vertex 499.849 85.4023 337.712 + vertex 502.369 86.6226 338.393 + endloop + endfacet + facet normal 0.256068 -0.823057 0.506959 + outer loop + vertex 495.042 81.0581 333.001 + vertex 495.51 83.7995 337.215 + vertex 488.981 80.9155 335.831 + endloop + endfacet + facet normal 0.226871 -0.81868 0.527534 + outer loop + vertex 499.849 85.4023 337.712 + vertex 499.082 82.9042 334.165 + vertex 501.958 84.319 335.124 + endloop + endfacet + facet normal 0.259831 -0.864411 0.430442 + outer loop + vertex 494.156 78.8542 329.109 + vertex 495.042 81.0581 333.001 + vertex 488.256 78.6162 332.193 + endloop + endfacet + facet normal 0.236041 -0.855378 0.4611 + outer loop + vertex 499.082 82.9042 334.165 + vertex 498.287 80.6532 330.396 + vertex 501.375 82.1547 331.601 + endloop + endfacet + facet normal 0.262527 -0.897808 0.353582 + outer loop + vertex 493.129 76.9797 325.113 + vertex 494.156 78.8542 329.109 + vertex 487.049 76.4917 328.388 + endloop + endfacet + facet normal 0.239149 -0.889455 0.389458 + outer loop + vertex 498.287 80.6532 330.396 + vertex 497.151 78.6724 326.57 + vertex 500.235 80.1291 328.003 + endloop + endfacet + facet normal 0.265167 -0.919973 0.288678 + outer loop + vertex 492.99 75.6997 321.161 + vertex 493.129 76.9797 325.113 + vertex 486.057 74.5959 324.012 + endloop + endfacet + facet normal 0.237725 -0.91774 0.318183 + outer loop + vertex 497.151 78.6724 326.57 + vertex 495.981 76.98 322.563 + vertex 498.671 78.2961 324.349 + endloop + endfacet + facet normal 0.239854 -0.953865 0.180587 + outer loop + vertex 494.565 75.4919 318.361 + vertex 492.381 74.1628 314.242 + vertex 495.296 75.1906 315.799 + endloop + endfacet + facet normal 0.240546 -0.963095 0.120768 + outer loop + vertex 492.381 74.1628 314.242 + vertex 490.09 73.1393 310.642 + vertex 493.428 74.0845 311.532 + endloop + endfacet + facet normal 0.174577 -0.599657 0.780983 + outer loop + vertex 507.281 96.9119 347.839 + vertex 516.499 99.8012 347.997 + vertex 507.646 100.146 350.241 + endloop + endfacet + facet normal 0.175342 -0.596182 0.783468 + outer loop + vertex 507.646 100.146 350.241 + vertex 516.499 99.8012 347.997 + vertex 516.872 103.167 350.476 + endloop + endfacet + facet normal 0.190151 -0.656012 0.730404 + outer loop + vertex 507.033 93.9737 345.265 + vertex 516.224 96.6963 345.318 + vertex 507.281 96.9119 347.839 + endloop + endfacet + facet normal 0.191451 -0.65095 0.734581 + outer loop + vertex 507.281 96.9119 347.839 + vertex 516.224 96.6963 345.318 + vertex 516.499 99.8012 347.997 + endloop + endfacet + facet normal 0.205004 -0.707673 0.676145 + outer loop + vertex 506.252 90.914 342.3 + vertex 516.134 93.8578 342.385 + vertex 507.033 93.9737 345.265 + endloop + endfacet + facet normal 0.205392 -0.706436 0.67732 + outer loop + vertex 507.033 93.9737 345.265 + vertex 516.134 93.8578 342.385 + vertex 516.224 96.6963 345.318 + endloop + endfacet + facet normal 0.238917 -0.970937 0.0141711 + outer loop + vertex 495.868 74.2553 306.62 + vertex 506.823 76.9471 306.357 + vertex 499.329 75.1106 306.873 + endloop + endfacet + facet normal 0.171864 -0.596298 0.78415 + outer loop + vertex 516.499 99.8012 347.997 + vertex 530.718 103.761 347.892 + vertex 516.872 103.167 350.476 + endloop + endfacet + facet normal 0.171748 -0.597509 0.783253 + outer loop + vertex 516.872 103.167 350.476 + vertex 530.718 103.761 347.892 + vertex 530.986 107.197 350.455 + endloop + endfacet + facet normal 0.186768 -0.651305 0.735472 + outer loop + vertex 516.224 96.6963 345.318 + vertex 530.622 100.635 345.15 + vertex 516.499 99.8012 347.997 + endloop + endfacet + facet normal 0.186783 -0.651174 0.735585 + outer loop + vertex 516.499 99.8012 347.997 + vertex 530.622 100.635 345.15 + vertex 530.718 103.761 347.892 + endloop + endfacet + facet normal 0.201042 -0.707018 0.678017 + outer loop + vertex 516.134 93.8578 342.385 + vertex 530.653 97.8156 342.206 + vertex 516.224 96.6963 345.318 + endloop + endfacet + facet normal 0.201145 -0.706274 0.678762 + outer loop + vertex 516.224 96.6963 345.318 + vertex 530.653 97.8156 342.206 + vertex 530.622 100.635 345.15 + endloop + endfacet + facet normal 0.246188 -0.961639 0.121002 + outer loop + vertex 527.67 82.3146 306.773 + vertex 510.366 77.8828 306.758 + vertex 519.715 80.2082 306.217 + endloop + endfacet + facet normal 0.170996 -0.59755 0.783387 + outer loop + vertex 530.718 103.761 347.892 + vertex 548.263 108.544 347.711 + vertex 530.986 107.197 350.455 + endloop + endfacet + facet normal 0.170828 -0.601508 0.780388 + outer loop + vertex 530.986 107.197 350.455 + vertex 548.263 108.544 347.711 + vertex 548.24 111.954 350.344 + endloop + endfacet + facet normal 0.18532 -0.651331 0.735816 + outer loop + vertex 530.622 100.635 345.15 + vertex 548.478 105.433 344.899 + vertex 530.718 103.761 347.892 + endloop + endfacet + facet normal 0.185295 -0.651804 0.735403 + outer loop + vertex 530.718 103.761 347.892 + vertex 548.478 105.433 344.899 + vertex 548.263 108.544 347.711 + endloop + endfacet + facet normal 0.199263 -0.706562 0.679018 + outer loop + vertex 530.653 97.8156 342.206 + vertex 548.66 102.627 341.928 + vertex 530.622 100.635 345.15 + endloop + endfacet + facet normal 0.199285 -0.706256 0.679329 + outer loop + vertex 530.622 100.635 345.15 + vertex 548.66 102.627 341.928 + vertex 548.478 105.433 344.899 + endloop + endfacet + facet normal 0.171789 -0.601402 0.780259 + outer loop + vertex 548.263 108.544 347.711 + vertex 565.798 113.522 347.687 + vertex 548.24 111.954 350.344 + endloop + endfacet + facet normal 0.17178 -0.601754 0.779989 + outer loop + vertex 548.24 111.954 350.344 + vertex 565.798 113.522 347.687 + vertex 565.409 116.818 350.316 + endloop + endfacet + facet normal 0.186063 -0.651677 0.735321 + outer loop + vertex 548.478 105.433 344.899 + vertex 566.84 110.514 344.756 + vertex 548.263 108.544 347.711 + endloop + endfacet + facet normal 0.186056 -0.651885 0.735139 + outer loop + vertex 548.263 108.544 347.711 + vertex 566.84 110.514 344.756 + vertex 565.798 113.522 347.687 + endloop + endfacet + facet normal 0.199513 -0.706215 0.679305 + outer loop + vertex 548.66 102.627 341.928 + vertex 567.16 107.635 341.701 + vertex 548.478 105.433 344.899 + endloop + endfacet + facet normal 0.199721 -0.702511 0.683073 + outer loop + vertex 548.478 105.433 344.899 + vertex 567.16 107.635 341.701 + vertex 566.84 110.514 344.756 + endloop + endfacet + facet normal 0.171517 -0.601802 0.78001 + outer loop + vertex 565.798 113.522 347.687 + vertex 578.314 117.57 348.059 + vertex 565.409 116.818 350.316 + endloop + endfacet + facet normal 0.17214 -0.593189 0.786444 + outer loop + vertex 565.409 116.818 350.316 + vertex 578.314 117.57 348.059 + vertex 580.451 121.016 350.19 + endloop + endfacet + facet normal 0.186886 -0.65162 0.735163 + outer loop + vertex 566.84 110.514 344.756 + vertex 583.329 115.485 344.97 + vertex 565.798 113.522 347.687 + endloop + endfacet + facet normal 0.187017 -0.646044 0.740035 + outer loop + vertex 565.798 113.522 347.687 + vertex 583.329 115.485 344.97 + vertex 578.314 117.57 348.059 + endloop + endfacet + facet normal 0.200528 -0.702349 0.683004 + outer loop + vertex 567.16 107.635 341.701 + vertex 582.921 112.066 341.631 + vertex 566.84 110.514 344.756 + endloop + endfacet + facet normal 0.201074 -0.696681 0.688626 + outer loop + vertex 566.84 110.514 344.756 + vertex 582.921 112.066 341.631 + vertex 583.329 115.485 344.97 + endloop + endfacet + facet normal 0.166621 -0.608652 0.775745 + outer loop + vertex 590.341 120.049 347.21 + vertex 597.06 122.959 348.049 + vertex 591.516 124.013 350.067 + endloop + endfacet + facet normal 0.167062 -0.607652 0.776434 + outer loop + vertex 591.516 124.013 350.067 + vertex 597.06 122.959 348.049 + vertex 597.193 125.887 350.312 + endloop + endfacet + facet normal 0.181355 -0.659531 0.729472 + outer loop + vertex 594.375 117.773 344.148 + vertex 597.875 119.931 345.23 + vertex 590.341 120.049 347.21 + endloop + endfacet + facet normal 0.185312 -0.642521 0.743522 + outer loop + vertex 590.341 120.049 347.21 + vertex 597.875 119.931 345.23 + vertex 597.06 122.959 348.049 + endloop + endfacet + facet normal 0.197049 -0.704164 0.682147 + outer loop + vertex 593.624 115.146 341.654 + vertex 599.12 117.154 342.139 + vertex 594.375 117.773 344.148 + endloop + endfacet + facet normal 0.206556 -0.684957 0.69869 + outer loop + vertex 594.375 117.773 344.148 + vertex 599.12 117.154 342.139 + vertex 597.875 119.931 345.23 + endloop + endfacet + facet normal 0.276077 -0.897299 0.344436 + outer loop + vertex 604.698 104.655 318.848 + vertex 603.354 105.64 322.491 + vertex 602.495 104.712 320.761 + endloop + endfacet + facet normal 0.251762 -0.927564 0.276118 + outer loop + vertex 605.515 103.906 315.586 + vertex 604.698 104.655 318.848 + vertex 601.958 103.511 317.5 + endloop + endfacet + facet normal 0.25501 -0.937247 0.237779 + outer loop + vertex 605.124 103.467 314.275 + vertex 606.851 103.672 313.232 + vertex 605.515 103.906 315.586 + endloop + endfacet + facet normal 0.238663 -0.961901 0.133368 + outer loop + vertex 601.473 101.463 307.048 + vertex 606.888 102.83 307.217 + vertex 603.097 101.893 307.249 + endloop + endfacet + facet normal 0.240742 -0.904936 0.350906 + outer loop + vertex 500.235 80.1291 328.003 + vertex 498.671 78.2961 324.349 + vertex 503.134 79.9308 325.503 + endloop + endfacet + facet normal 0.24529 -0.875923 0.415441 + outer loop + vertex 501.375 82.1547 331.601 + vertex 500.235 80.1291 328.003 + vertex 505.449 81.9564 328.777 + endloop + endfacet + facet normal 0.238925 -0.844513 0.479283 + outer loop + vertex 501.958 84.319 335.124 + vertex 501.375 82.1547 331.601 + vertex 506.455 83.9925 332.307 + endloop + endfacet + facet normal 0.230909 -0.808804 0.540849 + outer loop + vertex 502.369 86.6226 338.393 + vertex 501.958 84.319 335.124 + vertex 506.779 86.0921 335.717 + endloop + endfacet + facet normal 0.22589 -0.775907 0.589017 + outer loop + vertex 502.722 88.6288 340.9 + vertex 502.369 86.6226 338.393 + vertex 506.823 88.3227 338.925 + endloop + endfacet + facet normal 0.222499 -0.691929 0.686825 + outer loop + vertex 502.515 92.6093 345.218 + vertex 501.961 90.1975 342.968 + vertex 506.252 90.914 342.3 + endloop + endfacet + facet normal 0.193039 -0.664121 0.722274 + outer loop + vertex 503.021 95.085 347.359 + vertex 502.515 92.6093 345.218 + vertex 507.033 93.9737 345.265 + endloop + endfacet + facet normal 0.173369 -0.607943 0.774822 + outer loop + vertex 502.915 97.8592 349.56 + vertex 503.021 95.085 347.359 + vertex 507.281 96.9119 347.839 + endloop + endfacet + facet normal 0.156935 -0.565876 0.809417 + outer loop + vertex 503.141 101.172 351.832 + vertex 502.915 97.8592 349.56 + vertex 507.646 100.146 350.241 + endloop + endfacet + facet normal 0.185578 -0.512732 0.838252 + outer loop + vertex 599.247 127.523 351.053 + vertex 597.89 129.695 352.682 + vertex 597.57 127.674 351.516 + endloop + endfacet + facet normal 0.183982 -0.587632 0.787933 + outer loop + vertex 600.026 125.345 349.247 + vertex 599.247 127.523 351.053 + vertex 597.193 125.887 350.312 + endloop + endfacet + facet normal 0.194741 -0.622427 0.758064 + outer loop + vertex 600.415 122.088 346.473 + vertex 600.026 125.345 349.247 + vertex 597.06 122.959 348.049 + endloop + endfacet + facet normal 0.203647 -0.657671 0.725256 + outer loop + vertex 600.542 119.34 343.945 + vertex 600.415 122.088 346.473 + vertex 597.875 119.931 345.23 + endloop + endfacet + facet normal 0.211502 -0.700561 0.681528 + outer loop + vertex 601.362 117.725 342.03 + vertex 600.542 119.34 343.945 + vertex 599.12 117.154 342.139 + endloop + endfacet + facet normal 0.216308 -0.724662 0.654275 + outer loop + vertex 601.13 115.836 340.015 + vertex 601.362 117.725 342.03 + vertex 599.12 117.154 342.139 + endloop + endfacet + facet normal 0.239957 -0.780132 0.577767 + outer loop + vertex 602.665 111.703 334.037 + vertex 601.849 113.974 337.442 + vertex 599.601 112.22 336.008 + endloop + endfacet + facet normal 0.240918 -0.813395 0.529478 + outer loop + vertex 603.518 109.634 330.471 + vertex 602.665 111.703 334.037 + vertex 600.25 110.138 332.731 + endloop + endfacet + facet normal 0.237245 -0.87885 0.413929 + outer loop + vertex 605.17 106.914 324.348 + vertex 603.987 108.07 327.48 + vertex 601.869 106.878 326.163 + endloop + endfacet + facet normal 0.257526 -0.895683 0.362537 + outer loop + vertex 605.991 105.529 320.342 + vertex 605.17 106.914 324.348 + vertex 603.354 105.64 322.491 + endloop + endfacet + facet normal 0.277037 -0.914521 0.294792 + outer loop + vertex 606.667 104.374 316.126 + vertex 605.991 105.529 320.342 + vertex 604.698 104.655 318.848 + endloop + endfacet + facet normal 0.303372 -0.934847 0.184466 + outer loop + vertex 609.329 103.607 309.079 + vertex 607.874 103.745 312.174 + vertex 608.188 103.515 310.49 + endloop + endfacet + facet normal 0.177395 -0.599558 0.780424 + outer loop + vertex 507.281 96.9119 347.839 + vertex 507.646 100.146 350.241 + vertex 502.915 97.8592 349.56 + endloop + endfacet + facet normal 0.198858 -0.655286 0.728735 + outer loop + vertex 507.033 93.9737 345.265 + vertex 507.281 96.9119 347.839 + vertex 503.021 95.085 347.359 + endloop + endfacet + facet normal 0.206665 -0.70764 0.675674 + outer loop + vertex 506.252 90.914 342.3 + vertex 507.033 93.9737 345.265 + vertex 502.515 92.6093 345.218 + endloop + endfacet + facet normal 0.177969 -0.595104 0.783696 + outer loop + vertex 580.451 121.016 350.19 + vertex 578.314 117.57 348.059 + vertex 590.341 120.049 347.21 + endloop + endfacet + facet normal 0.185648 -0.647701 0.738931 + outer loop + vertex 578.314 117.57 348.059 + vertex 583.329 115.485 344.97 + vertex 590.341 120.049 347.21 + endloop + endfacet + facet normal 0.199041 -0.696849 0.689046 + outer loop + vertex 583.329 115.485 344.97 + vertex 582.921 112.066 341.631 + vertex 593.624 115.146 341.654 + endloop + endfacet + facet normal 0.169509 -0.575077 0.800346 + outer loop + vertex 597.57 127.674 351.516 + vertex 597.193 125.887 350.312 + vertex 599.247 127.523 351.053 + endloop + endfacet + facet normal 0.173582 -0.609267 0.773733 + outer loop + vertex 590.341 120.049 347.21 + vertex 591.516 124.013 350.067 + vertex 580.451 121.016 350.19 + endloop + endfacet + facet normal 0.175446 -0.606998 0.775095 + outer loop + vertex 597.193 125.887 350.312 + vertex 597.06 122.959 348.049 + vertex 600.026 125.345 349.247 + endloop + endfacet + facet normal 0.189618 -0.651611 0.734472 + outer loop + vertex 594.375 117.773 344.148 + vertex 590.341 120.049 347.21 + vertex 583.329 115.485 344.97 + endloop + endfacet + facet normal 0.182502 -0.643299 0.743546 + outer loop + vertex 597.06 122.959 348.049 + vertex 597.875 119.931 345.23 + vertex 600.415 122.088 346.473 + endloop + endfacet + facet normal 0.19662 -0.704161 0.682274 + outer loop + vertex 593.624 115.146 341.654 + vertex 594.375 117.773 344.148 + vertex 583.329 115.485 344.97 + endloop + endfacet + facet normal 0.181885 -0.693868 0.696753 + outer loop + vertex 597.875 119.931 345.23 + vertex 599.12 117.154 342.139 + vertex 600.542 119.34 343.945 + endloop + endfacet + facet normal 0.218668 -0.770258 0.599072 + outer loop + vertex 599.106 114.495 339.113 + vertex 599.601 112.22 336.008 + vertex 601.849 113.974 337.442 + endloop + endfacet + facet normal 0.2208 -0.802754 0.553926 + outer loop + vertex 599.601 112.22 336.008 + vertex 600.25 110.138 332.731 + vertex 602.665 111.703 334.037 + endloop + endfacet + facet normal 0.220364 -0.834793 0.50454 + outer loop + vertex 600.25 110.138 332.731 + vertex 600.982 108.361 329.471 + vertex 603.518 109.634 330.471 + endloop + endfacet + facet normal 0.211651 -0.869387 0.446509 + outer loop + vertex 600.982 108.361 329.471 + vertex 601.869 106.878 326.163 + vertex 603.987 108.07 327.48 + endloop + endfacet + facet normal 0.225179 -0.892105 0.391718 + outer loop + vertex 601.869 106.878 326.163 + vertex 603.354 105.64 322.491 + vertex 605.17 106.914 324.348 + endloop + endfacet + facet normal 0.232582 -0.913842 0.332865 + outer loop + vertex 603.354 105.64 322.491 + vertex 604.698 104.655 318.848 + vertex 605.991 105.529 320.342 + endloop + endfacet + facet normal 0.248381 -0.928652 0.275521 + outer loop + vertex 604.698 104.655 318.848 + vertex 605.515 103.906 315.586 + vertex 606.667 104.374 316.126 + endloop + endfacet + facet normal 0.254512 -0.956352 0.143579 + outer loop + vertex 608.188 103.515 310.49 + vertex 608.688 103.46 309.237 + vertex 609.329 103.607 309.079 + endloop + endfacet + facet normal 0.148582 -0.434978 0.888098 + outer loop + vertex 607.724 134.863 353.758 + vertex 607.526 139.599 356.111 + vertex 601.978 133.784 354.191 + endloop + endfacet + facet normal 0.134543 -0.424057 0.895585 + outer loop + vertex 601.978 133.784 354.191 + vertex 607.526 139.599 356.111 + vertex 599.968 137.659 356.328 + endloop + endfacet + facet normal 0.142676 -0.440683 0.886252 + outer loop + vertex 614.772 136.795 353.584 + vertex 614.775 141.634 355.99 + vertex 607.724 134.863 353.758 + endloop + endfacet + facet normal 0.137272 -0.436085 0.889374 + outer loop + vertex 607.724 134.863 353.758 + vertex 614.775 141.634 355.99 + vertex 607.526 139.599 356.111 + endloop + endfacet + facet normal 0.13798 -0.439795 0.887435 + outer loop + vertex 623.212 139.468 353.597 + vertex 623.036 144.264 356.001 + vertex 614.772 136.795 353.584 + endloop + endfacet + facet normal 0.139196 -0.440902 0.886696 + outer loop + vertex 614.772 136.795 353.584 + vertex 623.036 144.264 356.001 + vertex 614.775 141.634 355.99 + endloop + endfacet + facet normal 0.139064 -0.437897 0.888205 + outer loop + vertex 632.287 142.473 353.658 + vertex 631.948 147.221 356.052 + vertex 623.212 139.468 353.597 + endloop + endfacet + facet normal 0.14082 -0.439533 0.887119 + outer loop + vertex 623.212 139.468 353.597 + vertex 631.948 147.221 356.052 + vertex 623.036 144.264 356.001 + endloop + endfacet + facet normal 0.144296 -0.43794 0.887349 + outer loop + vertex 641.157 145.446 353.682 + vertex 640.797 150.188 356.081 + vertex 632.287 142.473 353.658 + endloop + endfacet + facet normal 0.143639 -0.437342 0.88775 + outer loop + vertex 632.287 142.473 353.658 + vertex 640.797 150.188 356.081 + vertex 631.948 147.221 356.052 + endloop + endfacet + facet normal 0.151358 -0.436584 0.88684 + outer loop + vertex 649.68 148.392 353.678 + vertex 649.343 153.144 356.075 + vertex 641.157 145.446 353.682 + endloop + endfacet + facet normal 0.151806 -0.436976 0.886571 + outer loop + vertex 641.157 145.446 353.682 + vertex 649.343 153.144 356.075 + vertex 640.797 150.188 356.081 + endloop + endfacet + facet normal 0.15718 -0.433904 0.887142 + outer loop + vertex 658.202 151.492 353.685 + vertex 657.878 156.261 356.074 + vertex 649.68 148.392 353.678 + endloop + endfacet + facet normal 0.159142 -0.43559 0.885966 + outer loop + vertex 649.68 148.392 353.678 + vertex 657.878 156.261 356.074 + vertex 649.343 153.144 356.075 + endloop + endfacet + facet normal 0.162047 -0.433189 0.886616 + outer loop + vertex 666.969 154.746 353.672 + vertex 666.671 159.553 356.075 + vertex 658.202 151.492 353.685 + endloop + endfacet + facet normal 0.162144 -0.433274 0.886557 + outer loop + vertex 658.202 151.492 353.685 + vertex 666.671 159.553 356.075 + vertex 657.878 156.261 356.074 + endloop + endfacet + facet normal 0.162468 -0.434349 0.885972 + outer loop + vertex 675.6 157.7 353.537 + vertex 675.478 162.606 355.965 + vertex 666.969 154.746 353.672 + endloop + endfacet + facet normal 0.161285 -0.433283 0.886709 + outer loop + vertex 666.969 154.746 353.672 + vertex 675.478 162.606 355.965 + vertex 666.671 159.553 356.075 + endloop + endfacet + facet normal 0.166217 -0.449817 0.877517 + outer loop + vertex 682.945 159.573 353.106 + vertex 683.594 164.685 355.604 + vertex 675.6 157.7 353.537 + endloop + endfacet + facet normal 0.151027 -0.435383 0.887487 + outer loop + vertex 675.6 157.7 353.537 + vertex 683.594 164.685 355.604 + vertex 675.478 162.606 355.965 + endloop + endfacet + facet normal 0.117402 -0.353678 0.92797 + outer loop + vertex 607.526 139.599 356.111 + vertex 607.29 144.614 358.052 + vertex 599.968 137.659 356.328 + endloop + endfacet + facet normal 0.108337 -0.345198 0.932256 + outer loop + vertex 599.968 137.659 356.328 + vertex 607.29 144.614 358.052 + vertex 599.559 143.111 358.394 + endloop + endfacet + facet normal 0.116401 -0.359557 0.925835 + outer loop + vertex 614.775 141.634 355.99 + vertex 614.799 146.684 357.948 + vertex 607.526 139.599 356.111 + endloop + endfacet + facet normal 0.110529 -0.354244 0.928598 + outer loop + vertex 607.526 139.599 356.111 + vertex 614.799 146.684 357.948 + vertex 607.29 144.614 358.052 + endloop + endfacet + facet normal 0.113362 -0.35989 0.926082 + outer loop + vertex 623.036 144.264 356.001 + vertex 622.956 149.287 357.963 + vertex 614.775 141.634 355.99 + endloop + endfacet + facet normal 0.113139 -0.35968 0.926191 + outer loop + vertex 614.775 141.634 355.99 + vertex 622.956 149.287 357.963 + vertex 614.799 146.684 357.948 + endloop + endfacet + facet normal 0.113746 -0.358638 0.926521 + outer loop + vertex 631.948 147.221 356.052 + vertex 631.707 152.206 358.011 + vertex 623.036 144.264 356.001 + endloop + endfacet + facet normal 0.114951 -0.359801 0.925921 + outer loop + vertex 623.036 144.264 356.001 + vertex 631.707 152.206 358.011 + vertex 622.956 149.287 357.963 + endloop + endfacet + facet normal 0.116443 -0.3566 0.926972 + outer loop + vertex 640.797 150.188 356.081 + vertex 640.499 155.167 358.034 + vertex 631.948 147.221 356.052 + endloop + endfacet + facet normal 0.118187 -0.358262 0.92611 + outer loop + vertex 631.948 147.221 356.052 + vertex 640.499 155.167 358.034 + vertex 631.707 152.206 358.011 + endloop + endfacet + facet normal 0.123947 -0.356379 0.926084 + outer loop + vertex 649.343 153.144 356.075 + vertex 649.073 158.134 358.032 + vertex 640.797 150.188 356.081 + endloop + endfacet + facet normal 0.123455 -0.355926 0.926324 + outer loop + vertex 640.797 150.188 356.081 + vertex 649.073 158.134 358.032 + vertex 640.499 155.167 358.034 + endloop + endfacet + facet normal 0.130291 -0.356563 0.925142 + outer loop + vertex 657.878 156.261 356.074 + vertex 657.624 161.255 358.035 + vertex 649.343 153.144 356.075 + endloop + endfacet + facet normal 0.12951 -0.355858 0.925523 + outer loop + vertex 649.343 153.144 356.075 + vertex 657.624 161.255 358.035 + vertex 649.073 158.134 358.032 + endloop + endfacet + facet normal 0.133125 -0.355765 0.925045 + outer loop + vertex 666.671 159.553 356.075 + vertex 666.396 164.571 358.045 + vertex 657.878 156.261 356.074 + endloop + endfacet + facet normal 0.133659 -0.35625 0.924781 + outer loop + vertex 657.878 156.261 356.074 + vertex 666.396 164.571 358.045 + vertex 657.624 161.255 358.035 + endloop + endfacet + facet normal 0.135432 -0.357375 0.924089 + outer loop + vertex 675.478 162.606 355.965 + vertex 675.24 167.774 357.998 + vertex 666.671 159.553 356.075 + endloop + endfacet + facet normal 0.133638 -0.355716 0.92499 + outer loop + vertex 666.671 159.553 356.075 + vertex 675.24 167.774 357.998 + vertex 666.396 164.571 358.045 + endloop + endfacet + facet normal 0.13496 -0.366945 0.920401 + outer loop + vertex 683.594 164.685 355.604 + vertex 683.531 170.131 357.784 + vertex 675.478 162.606 355.965 + endloop + endfacet + facet normal 0.125749 -0.35823 0.925126 + outer loop + vertex 675.478 162.606 355.965 + vertex 683.531 170.131 357.784 + vertex 675.24 167.774 357.998 + endloop + endfacet + facet normal 0.132068 -0.985533 0.106221 + outer loop + vertex 607.874 103.745 312.174 + vertex 609.329 103.607 309.079 + vertex 609.077 103.756 310.775 + endloop + endfacet + facet normal 0.190896 -0.958682 0.21092 + outer loop + vertex 606.667 104.374 316.126 + vertex 607.874 103.745 312.174 + vertex 608.272 104.402 314.799 + endloop + endfacet + facet normal 0.237371 -0.902012 0.360597 + outer loop + vertex 605.17 106.914 324.348 + vertex 605.991 105.529 320.342 + vertex 608.376 107.048 322.572 + endloop + endfacet + facet normal 0.271656 -0.865021 0.421832 + outer loop + vertex 603.987 108.07 327.48 + vertex 605.17 106.914 324.348 + vertex 606.702 109.124 327.893 + endloop + endfacet + facet normal 0.236985 -0.814678 0.529281 + outer loop + vertex 602.665 111.703 334.037 + vertex 603.518 109.634 330.471 + vertex 605.789 111.661 332.573 + endloop + endfacet + facet normal 0.23998 -0.780125 0.577767 + outer loop + vertex 601.849 113.974 337.442 + vertex 602.665 111.703 334.037 + vertex 604.811 114.211 336.531 + endloop + endfacet + facet normal 0.249588 -0.720721 0.646735 + outer loop + vertex 601.362 117.725 342.03 + vertex 601.13 115.836 340.015 + vertex 603.634 117.093 340.45 + endloop + endfacet + facet normal 0.251805 -0.6839 0.684744 + outer loop + vertex 600.542 119.34 343.945 + vertex 601.362 117.725 342.03 + vertex 603.11 120.902 344.56 + endloop + endfacet + facet normal 0.224617 -0.65403 0.722352 + outer loop + vertex 600.415 122.088 346.473 + vertex 600.542 119.34 343.945 + vertex 603.11 120.902 344.56 + endloop + endfacet + facet normal 0.203709 -0.620614 0.757193 + outer loop + vertex 600.026 125.345 349.247 + vertex 600.415 122.088 346.473 + vertex 603.144 125.251 348.331 + endloop + endfacet + facet normal 0.222907 -0.573823 0.788061 + outer loop + vertex 599.247 127.523 351.053 + vertex 600.026 125.345 349.247 + vertex 602.292 129.263 351.459 + endloop + endfacet + facet normal 0.182349 -0.514478 0.837891 + outer loop + vertex 597.89 129.695 352.682 + vertex 599.247 127.523 351.053 + vertex 602.292 129.263 351.459 + endloop + endfacet + facet normal 0.109724 -0.333016 0.936515 + outer loop + vertex 687.611 169.439 357.06 + vertex 688.764 172.602 358.05 + vertex 683.531 170.131 357.784 + endloop + endfacet + facet normal 0.128748 -0.388327 0.912483 + outer loop + vertex 688.879 167.337 355.987 + vertex 687.611 169.439 357.06 + vertex 683.594 164.685 355.604 + endloop + endfacet + facet normal 0.153554 -0.434186 0.887639 + outer loop + vertex 688.22 163.729 354.336 + vertex 688.879 167.337 355.987 + vertex 683.594 164.685 355.604 + endloop + endfacet + facet normal 0.295361 -0.809073 0.508097 + outer loop + vertex 674.052 123.722 320.163 + vertex 677.742 125.193 320.361 + vertex 675.112 124.732 321.156 + endloop + endfacet + facet normal 0.211878 -0.825514 0.523101 + outer loop + vertex 649.822 115.528 319.101 + vertex 651.76 116.118 319.246 + vertex 651.356 116.326 319.738 + endloop + endfacet + facet normal 0.176122 -0.798619 0.57549 + outer loop + vertex 646.856 114.57 318.678 + vertex 649.822 115.528 319.101 + vertex 651.356 116.326 319.738 + endloop + endfacet + facet normal 0.202951 -0.847487 0.490486 + outer loop + vertex 643.93 113.599 318.211 + vertex 646.856 114.57 318.678 + vertex 643.33 113.717 318.664 + endloop + endfacet + facet normal 0.192617 -0.856347 0.479132 + outer loop + vertex 642.451 113.124 317.958 + vertex 643.93 113.599 318.211 + vertex 643.33 113.717 318.664 + endloop + endfacet + facet normal 0.173152 -0.849788 0.497875 + outer loop + vertex 639.644 112.266 317.469 + vertex 642.451 113.124 317.958 + vertex 643.33 113.717 318.664 + endloop + endfacet + facet normal 0.197507 -0.887162 0.417054 + outer loop + vertex 636.508 111.282 316.862 + vertex 639.644 112.266 317.469 + vertex 635.139 111.158 317.246 + endloop + endfacet + facet normal 0.187844 -0.907369 0.376027 + outer loop + vertex 634.425 110.639 316.35 + vertex 636.508 111.282 316.862 + vertex 635.139 111.158 317.246 + endloop + endfacet + facet normal 0.183267 -0.9069 0.379402 + outer loop + vertex 631.24 109.737 315.733 + vertex 634.425 110.639 316.35 + vertex 635.139 111.158 317.246 + endloop + endfacet + facet normal 0.17889 -0.904107 0.388058 + outer loop + vertex 635.139 111.158 317.246 + vertex 627.199 108.742 315.277 + vertex 631.24 109.737 315.733 + endloop + endfacet + facet normal 0.189584 -0.864644 0.46524 + outer loop + vertex 643.33 113.717 318.664 + vertex 635.139 111.158 317.246 + vertex 639.644 112.266 317.469 + endloop + endfacet + facet normal 0.197413 -0.825225 0.52918 + outer loop + vertex 651.356 116.326 319.738 + vertex 643.33 113.717 318.664 + vertex 646.856 114.57 318.678 + endloop + endfacet + facet normal 0.228667 -0.816544 0.530064 + outer loop + vertex 659.118 119.002 320.512 + vertex 651.356 116.326 319.738 + vertex 655.07 117.055 319.259 + endloop + endfacet + facet normal 0.279629 -0.808732 0.517455 + outer loop + vertex 675.112 124.732 321.156 + vertex 666.619 121.569 320.801 + vertex 669.78 122.124 319.961 + endloop + endfacet + facet normal 0.296961 -0.802821 0.517004 + outer loop + vertex 683.477 127.879 321.238 + vertex 675.112 124.732 321.156 + vertex 677.742 125.193 320.361 + endloop + endfacet + facet normal 0.263959 -0.904831 0.334076 + outer loop + vertex 607.412 105.187 318.293 + vertex 608.376 107.048 322.572 + vertex 605.991 105.529 320.342 + endloop + endfacet + facet normal 0.270149 -0.865139 0.422556 + outer loop + vertex 608.376 107.048 322.572 + vertex 606.702 109.124 327.893 + vertex 605.17 106.914 324.348 + endloop + endfacet + facet normal 0.255267 -0.782884 0.567389 + outer loop + vertex 605.789 111.661 332.573 + vertex 604.811 114.211 336.531 + vertex 602.665 111.703 334.037 + endloop + endfacet + facet normal 0.276402 -0.687171 0.671861 + outer loop + vertex 603.634 117.093 340.45 + vertex 603.11 120.902 344.56 + vertex 601.362 117.725 342.03 + endloop + endfacet + facet normal 0.239433 -0.637046 0.732697 + outer loop + vertex 603.11 120.902 344.56 + vertex 603.144 125.251 348.331 + vertex 600.415 122.088 346.473 + endloop + endfacet + facet normal 0.21535 -0.571562 0.791796 + outer loop + vertex 603.144 125.251 348.331 + vertex 602.292 129.263 351.459 + vertex 600.026 125.345 349.247 + endloop + endfacet + facet normal 0.186291 -0.498721 0.846506 + outer loop + vertex 602.292 129.263 351.459 + vertex 601.978 133.784 354.191 + vertex 597.89 129.695 352.682 + endloop + endfacet + facet normal 0.148606 -0.449262 0.880954 + outer loop + vertex 683.594 164.685 355.604 + vertex 682.945 159.573 353.106 + vertex 688.22 163.729 354.336 + endloop + endfacet + facet normal 0.121492 -0.343793 0.931153 + outer loop + vertex 599.968 137.659 356.328 + vertex 599.559 143.111 358.394 + vertex 592.657 137.039 357.053 + endloop + endfacet + facet normal 0.101435 -0.368761 0.923973 + outer loop + vertex 683.531 170.131 357.784 + vertex 683.594 164.685 355.604 + vertex 687.611 169.439 357.06 + endloop + endfacet + facet normal 0.105912 -0.267063 0.957841 + outer loop + vertex 599.559 143.111 358.394 + vertex 599.939 148.799 359.938 + vertex 594.779 143.803 359.116 + endloop + endfacet + facet normal 0.0467322 -0.133732 0.989915 + outer loop + vertex 600.49 154.188 360.96 + vertex 599.375 158.805 361.637 + vertex 593.762 152.965 361.113 + endloop + endfacet + facet normal 0.576756 -0.572812 -0.582442 + outer loop + vertex 856.624 230.682 311.046 + vertex 855.195 229.619 310.677 + vertex 855.138 231.302 308.965 + endloop + endfacet + facet normal 0.532872 -0.59444 -0.602236 + outer loop + vertex 855.138 231.302 308.965 + vertex 855.195 229.619 310.677 + vertex 853.824 230.343 308.749 + endloop + endfacet + facet normal 0.685229 -0.691677 -0.228133 + outer loop + vertex 859.143 231.043 315.344 + vertex 857.911 229.943 314.98 + vertex 858.098 230.679 313.308 + endloop + endfacet + facet normal 0.655796 -0.71518 -0.241763 + outer loop + vertex 858.098 230.679 313.308 + vertex 857.911 229.943 314.98 + vertex 856.591 229.478 312.774 + endloop + endfacet + facet normal 0.651509 -0.628221 -0.425292 + outer loop + vertex 858.098 230.679 313.308 + vertex 856.591 229.478 312.774 + vertex 856.624 230.682 311.046 + endloop + endfacet + facet normal 0.605476 -0.658377 -0.447145 + outer loop + vertex 856.624 230.682 311.046 + vertex 856.591 229.478 312.774 + vertex 855.195 229.619 310.677 + endloop + endfacet + facet normal 0.596459 -0.787794 0.153679 + outer loop + vertex 860.646 232.59 318.575 + vertex 859.799 232.107 319.385 + vertex 860.015 231.817 317.062 + endloop + endfacet + facet normal 0.680707 -0.716488 0.15259 + outer loop + vertex 860.015 231.817 317.062 + vertex 859.799 232.107 319.385 + vertex 858.951 230.84 317.216 + endloop + endfacet + facet normal 0.675922 -0.736893 -0.0108691 + outer loop + vertex 860.015 231.817 317.062 + vertex 858.951 230.84 317.216 + vertex 859.143 231.043 315.344 + endloop + endfacet + facet normal 0.668156 -0.743918 -0.0124318 + outer loop + vertex 859.143 231.043 315.344 + vertex 858.951 230.84 317.216 + vertex 857.911 229.943 314.98 + endloop + endfacet + facet normal 0.245084 -0.527271 -0.813584 + outer loop + vertex 845.464 236.954 299.826 + vertex 841.512 233.122 301.119 + vertex 844.545 237.593 299.134 + endloop + endfacet + facet normal 0.0715198 -0.444734 -0.892803 + outer loop + vertex 844.545 237.593 299.134 + vertex 841.512 233.122 301.119 + vertex 842.532 235.685 299.924 + endloop + endfacet + facet normal 0.274215 -0.568076 -0.775948 + outer loop + vertex 847.595 239.544 298.683 + vertex 845.464 236.954 299.826 + vertex 846.605 239.731 298.196 + endloop + endfacet + facet normal 0.214281 -0.558397 -0.801421 + outer loop + vertex 846.605 239.731 298.196 + vertex 845.464 236.954 299.826 + vertex 844.545 237.593 299.134 + endloop + endfacet + facet normal 0.220953 -0.508653 -0.832137 + outer loop + vertex 841.512 233.122 301.119 + vertex 845.464 236.954 299.826 + vertex 843.722 231.956 302.419 + endloop + endfacet + facet normal 0.280013 -0.570988 -0.771729 + outer loop + vertex 847.595 239.544 298.683 + vertex 847.756 236.464 301.02 + vertex 845.464 236.954 299.826 + endloop + endfacet + facet normal 0.304591 -0.520063 -0.797972 + outer loop + vertex 847.756 236.464 301.02 + vertex 843.722 231.956 302.419 + vertex 845.464 236.954 299.826 + endloop + endfacet + facet normal 0.312241 -0.524984 -0.791769 + outer loop + vertex 843.722 231.956 302.419 + vertex 847.756 236.464 301.02 + vertex 846.91 232.227 303.496 + endloop + endfacet + facet normal 0.537978 -0.578386 -0.613229 + outer loop + vertex 853.041 227.604 310.671 + vertex 850.145 224.775 310.799 + vertex 851.761 228.367 308.829 + endloop + endfacet + facet normal 0.528109 -0.578539 -0.621605 + outer loop + vertex 851.761 228.367 308.829 + vertex 850.145 224.775 310.799 + vertex 848.897 225.562 309.007 + endloop + endfacet + facet normal 0.544469 -0.580654 -0.605305 + outer loop + vertex 855.195 229.619 310.677 + vertex 853.041 227.604 310.671 + vertex 853.824 230.343 308.749 + endloop + endfacet + facet normal 0.534224 -0.582714 -0.612413 + outer loop + vertex 853.824 230.343 308.749 + vertex 853.041 227.604 310.671 + vertex 851.761 228.367 308.829 + endloop + endfacet + facet normal 0.663706 -0.701608 -0.259308 + outer loop + vertex 855.71 227.88 314.849 + vertex 852.671 224.997 314.871 + vertex 854.357 227.407 312.666 + endloop + endfacet + facet normal 0.666464 -0.700294 -0.255762 + outer loop + vertex 854.357 227.407 312.666 + vertex 852.671 224.997 314.871 + vertex 851.37 224.54 312.732 + endloop + endfacet + facet normal 0.669435 -0.698285 -0.253484 + outer loop + vertex 857.911 229.943 314.98 + vertex 855.71 227.88 314.849 + vertex 856.591 229.478 312.774 + endloop + endfacet + facet normal 0.663346 -0.702068 -0.258985 + outer loop + vertex 856.591 229.478 312.774 + vertex 855.71 227.88 314.849 + vertex 854.357 227.407 312.666 + endloop + endfacet + facet normal 0.61744 -0.642356 -0.454033 + outer loop + vertex 856.591 229.478 312.774 + vertex 854.357 227.407 312.666 + vertex 855.195 229.619 310.677 + endloop + endfacet + facet normal 0.605787 -0.646578 -0.463638 + outer loop + vertex 855.195 229.619 310.677 + vertex 854.357 227.407 312.666 + vertex 853.041 227.604 310.671 + endloop + endfacet + facet normal 0.607781 -0.643942 -0.464694 + outer loop + vertex 854.357 227.407 312.666 + vertex 851.37 224.54 312.732 + vertex 853.041 227.604 310.671 + endloop + endfacet + facet normal 0.608454 -0.643825 -0.463975 + outer loop + vertex 853.041 227.604 310.671 + vertex 851.37 224.54 312.732 + vertex 850.145 224.775 310.799 + endloop + endfacet + facet normal 0.68986 -0.703427 0.171124 + outer loop + vertex 857.499 230.149 319.897 + vertex 855.006 227.588 319.422 + vertex 856.893 228.897 317.193 + endloop + endfacet + facet normal 0.680064 -0.716557 0.155108 + outer loop + vertex 856.893 228.897 317.193 + vertex 855.006 227.588 319.422 + vertex 853.959 226.114 317.203 + endloop + endfacet + facet normal 0.660447 -0.731538 0.169299 + outer loop + vertex 859.799 232.107 319.385 + vertex 857.499 230.149 319.897 + vertex 858.951 230.84 317.216 + endloop + endfacet + facet normal 0.674055 -0.716262 0.180605 + outer loop + vertex 858.951 230.84 317.216 + vertex 857.499 230.149 319.897 + vertex 856.893 228.897 317.193 + endloop + endfacet + facet normal 0.686265 -0.726823 -0.0277123 + outer loop + vertex 858.951 230.84 317.216 + vertex 856.893 228.897 317.193 + vertex 857.911 229.943 314.98 + endloop + endfacet + facet normal 0.684391 -0.728523 -0.0293779 + outer loop + vertex 857.911 229.943 314.98 + vertex 856.893 228.897 317.193 + vertex 855.71 227.88 314.849 + endloop + endfacet + facet normal 0.687721 -0.725248 -0.0324798 + outer loop + vertex 856.893 228.897 317.193 + vertex 853.959 226.114 317.203 + vertex 855.71 227.88 314.849 + endloop + endfacet + facet normal 0.68775 -0.725222 -0.0324387 + outer loop + vertex 855.71 227.88 314.849 + vertex 853.959 226.114 317.203 + vertex 852.671 224.997 314.871 + endloop + endfacet + facet normal 0.642669 -0.688211 0.336663 + outer loop + vertex 855.006 227.588 319.422 + vertex 857.499 230.149 319.897 + vertex 853.177 227.63 322.997 + endloop + endfacet + facet normal 0.654268 -0.684511 0.321524 + outer loop + vertex 859.799 232.107 319.385 + vertex 858.317 232.568 323.383 + vertex 857.499 230.149 319.897 + endloop + endfacet + facet normal 0.640911 -0.692849 0.330444 + outer loop + vertex 858.317 232.568 323.383 + vertex 853.177 227.63 322.997 + vertex 857.499 230.149 319.897 + endloop + endfacet + facet normal 0.486771 -0.533425 0.691745 + outer loop + vertex 856.465 253.253 347.241 + vertex 851.639 248.08 346.649 + vertex 856.647 249.159 343.957 + endloop + endfacet + facet normal 0.485282 -0.543446 0.684959 + outer loop + vertex 856.647 249.159 343.957 + vertex 851.639 248.08 346.649 + vertex 852.226 244.342 343.267 + endloop + endfacet + facet normal 0.455279 -0.498524 0.737696 + outer loop + vertex 855.4 256.831 350.317 + vertex 851.048 252.016 349.749 + vertex 856.465 253.253 347.241 + endloop + endfacet + facet normal 0.454625 -0.507996 0.731612 + outer loop + vertex 856.465 253.253 347.241 + vertex 851.048 252.016 349.749 + vertex 851.639 248.08 346.649 + endloop + endfacet + facet normal 0.416146 -0.457982 0.785542 + outer loop + vertex 855.209 261.301 353.025 + vertex 850.443 256.148 352.544 + vertex 855.4 256.831 350.317 + endloop + endfacet + facet normal 0.415182 -0.467332 0.780529 + outer loop + vertex 855.4 256.831 350.317 + vertex 850.443 256.148 352.544 + vertex 851.048 252.016 349.749 + endloop + endfacet + facet normal 0.36902 -0.406902 0.835617 + outer loop + vertex 854.208 265.256 355.392 + vertex 849.864 260.471 354.981 + vertex 855.209 261.301 353.025 + endloop + endfacet + facet normal 0.368765 -0.418322 0.830071 + outer loop + vertex 855.209 261.301 353.025 + vertex 849.864 260.471 354.981 + vertex 850.443 256.148 352.544 + endloop + endfacet + facet normal 0.316008 -0.346466 0.883233 + outer loop + vertex 854.133 269.956 357.263 + vertex 849.345 264.939 357.008 + vertex 854.208 265.256 355.392 + endloop + endfacet + facet normal 0.315086 -0.361537 0.877503 + outer loop + vertex 854.208 265.256 355.392 + vertex 849.345 264.939 357.008 + vertex 849.864 260.471 354.981 + endloop + endfacet + facet normal 0.26217 -0.277551 0.924247 + outer loop + vertex 853.185 274.49 358.893 + vertex 848.857 269.586 358.648 + vertex 854.133 269.956 357.263 + endloop + endfacet + facet normal 0.261964 -0.296674 0.918346 + outer loop + vertex 854.133 269.956 357.263 + vertex 848.857 269.586 358.648 + vertex 849.345 264.939 357.008 + endloop + endfacet + facet normal 0.210828 -0.21908 0.952657 + outer loop + vertex 852.965 279.628 360.123 + vertex 848.34 274.386 359.941 + vertex 853.185 274.49 358.893 + endloop + endfacet + facet normal 0.210425 -0.233143 0.949403 + outer loop + vertex 853.185 274.49 358.893 + vertex 848.34 274.386 359.941 + vertex 848.857 269.586 358.648 + endloop + endfacet + facet normal 0.159667 -0.16229 0.973739 + outer loop + vertex 852.507 285.068 361.105 + vertex 847.862 279.373 360.918 + vertex 852.965 279.628 360.123 + endloop + endfacet + facet normal 0.159948 -0.174841 0.971518 + outer loop + vertex 852.965 279.628 360.123 + vertex 847.862 279.373 360.918 + vertex 848.34 274.386 359.941 + endloop + endfacet + facet normal 0.253234 -0.465311 -0.84815 + outer loop + vertex 843.722 231.956 302.419 + vertex 837.962 226.227 303.841 + vertex 841.512 233.122 301.119 + endloop + endfacet + facet normal 0.135303 -0.423397 -0.895783 + outer loop + vertex 841.512 233.122 301.119 + vertex 837.962 226.227 303.841 + vertex 835.323 227.14 303.011 + endloop + endfacet + facet normal 0.248359 -0.461308 -0.851771 + outer loop + vertex 837.962 226.227 303.841 + vertex 843.722 231.956 302.419 + vertex 841.021 226.317 304.685 + endloop + endfacet + facet normal 0.520149 -0.577759 -0.628999 + outer loop + vertex 846.706 221.495 310.935 + vertex 843.059 218.106 311.032 + vertex 845.503 222.297 309.203 + endloop + endfacet + facet normal 0.504472 -0.575154 -0.643977 + outer loop + vertex 845.503 222.297 309.203 + vertex 843.059 218.106 311.032 + vertex 841.884 218.929 309.377 + endloop + endfacet + facet normal 0.527716 -0.578983 -0.621526 + outer loop + vertex 850.145 224.775 310.799 + vertex 846.706 221.495 310.935 + vertex 848.897 225.562 309.007 + endloop + endfacet + facet normal 0.51975 -0.578198 -0.628925 + outer loop + vertex 848.897 225.562 309.007 + vertex 846.706 221.495 310.935 + vertex 845.503 222.297 309.203 + endloop + endfacet + facet normal 0.652359 -0.71952 -0.238156 + outer loop + vertex 849.099 221.647 314.929 + vertex 845.325 218.215 314.96 + vertex 847.873 221.232 312.822 + endloop + endfacet + facet normal 0.655228 -0.718503 -0.233302 + outer loop + vertex 847.873 221.232 312.822 + vertex 845.325 218.215 314.96 + vertex 844.173 217.841 312.876 + endloop + endfacet + facet normal 0.660201 -0.708165 -0.250275 + outer loop + vertex 852.671 224.997 314.871 + vertex 849.099 221.647 314.929 + vertex 851.37 224.54 312.732 + endloop + endfacet + facet normal 0.662609 -0.707223 -0.246545 + outer loop + vertex 851.37 224.54 312.732 + vertex 849.099 221.647 314.929 + vertex 847.873 221.232 312.822 + endloop + endfacet + facet normal 0.603319 -0.65039 -0.461518 + outer loop + vertex 851.37 224.54 312.732 + vertex 847.873 221.232 312.822 + vertex 850.145 224.775 310.799 + endloop + endfacet + facet normal 0.602156 -0.650456 -0.462942 + outer loop + vertex 850.145 224.775 310.799 + vertex 847.873 221.232 312.822 + vertex 846.706 221.495 310.935 + endloop + endfacet + facet normal 0.596216 -0.657772 -0.460286 + outer loop + vertex 847.873 221.232 312.822 + vertex 844.173 217.841 312.876 + vertex 846.706 221.495 310.935 + endloop + endfacet + facet normal 0.599089 -0.657772 -0.456539 + outer loop + vertex 846.706 221.495 310.935 + vertex 844.173 217.841 312.876 + vertex 843.059 218.106 311.032 + endloop + endfacet + facet normal 0.668803 -0.717353 0.195209 + outer loop + vertex 851.375 224.433 319.9 + vertex 847.803 220.988 319.478 + vertex 850.382 222.785 317.246 + endloop + endfacet + facet normal 0.661655 -0.72835 0.178097 + outer loop + vertex 850.382 222.785 317.246 + vertex 847.803 220.988 319.478 + vertex 846.55 219.31 317.271 + endloop + endfacet + facet normal 0.658824 -0.731626 0.175138 + outer loop + vertex 855.006 227.588 319.422 + vertex 851.375 224.433 319.9 + vertex 853.959 226.114 317.203 + endloop + endfacet + facet normal 0.669535 -0.716833 0.194612 + outer loop + vertex 853.959 226.114 317.203 + vertex 851.375 224.433 319.9 + vertex 850.382 222.785 317.246 + endloop + endfacet + facet normal 0.680911 -0.731924 -0.0254486 + outer loop + vertex 853.959 226.114 317.203 + vertex 850.382 222.785 317.246 + vertex 852.671 224.997 314.871 + endloop + endfacet + facet normal 0.683811 -0.729377 -0.020283 + outer loop + vertex 852.671 224.997 314.871 + vertex 850.382 222.785 317.246 + vertex 849.099 221.647 314.929 + endloop + endfacet + facet normal 0.671713 -0.740768 -0.00799376 + outer loop + vertex 850.382 222.785 317.246 + vertex 846.55 219.31 317.271 + vertex 849.099 221.647 314.929 + endloop + endfacet + facet normal 0.672775 -0.739823 -0.00589534 + outer loop + vertex 849.099 221.647 314.929 + vertex 846.55 219.31 317.271 + vertex 845.325 218.215 314.96 + endloop + endfacet + facet normal 0.624244 -0.69172 0.363103 + outer loop + vertex 847.803 220.988 319.478 + vertex 851.375 224.433 319.9 + vertex 846.199 221.386 322.994 + endloop + endfacet + facet normal 0.642528 -0.688377 0.336593 + outer loop + vertex 855.006 227.588 319.422 + vertex 853.177 227.63 322.997 + vertex 851.375 224.433 319.9 + endloop + endfacet + facet normal 0.622941 -0.696419 0.356292 + outer loop + vertex 853.177 227.63 322.997 + vertex 846.199 221.386 322.994 + vertex 851.375 224.433 319.9 + endloop + endfacet + facet normal 0.483228 -0.544397 0.685655 + outer loop + vertex 851.639 248.08 346.649 + vertex 845.454 242.385 346.486 + vertex 852.226 244.342 343.267 + endloop + endfacet + facet normal 0.482994 -0.547856 0.68306 + outer loop + vertex 852.226 244.342 343.267 + vertex 845.454 242.385 346.486 + vertex 846.018 238.653 343.094 + endloop + endfacet + facet normal 0.452749 -0.50877 0.732237 + outer loop + vertex 851.048 252.016 349.749 + vertex 844.879 246.325 349.609 + vertex 851.639 248.08 346.649 + endloop + endfacet + facet normal 0.452617 -0.512412 0.729775 + outer loop + vertex 851.639 248.08 346.649 + vertex 844.879 246.325 349.609 + vertex 845.454 242.385 346.486 + endloop + endfacet + facet normal 0.416602 -0.46682 0.780078 + outer loop + vertex 850.443 256.148 352.544 + vertex 844.314 250.478 352.425 + vertex 851.048 252.016 349.749 + endloop + endfacet + facet normal 0.416568 -0.470673 0.777778 + outer loop + vertex 851.048 252.016 349.749 + vertex 844.314 250.478 352.425 + vertex 844.879 246.325 349.609 + endloop + endfacet + facet normal 0.372154 -0.417304 0.829071 + outer loop + vertex 849.864 260.471 354.981 + vertex 843.753 254.83 354.884 + vertex 850.443 256.148 352.544 + endloop + endfacet + facet normal 0.372198 -0.419823 0.827778 + outer loop + vertex 850.443 256.148 352.544 + vertex 843.753 254.83 354.884 + vertex 844.314 250.478 352.425 + endloop + endfacet + facet normal 0.321968 -0.359908 0.875673 + outer loop + vertex 849.345 264.939 357.008 + vertex 843.263 259.363 356.953 + vertex 849.864 260.471 354.981 + endloop + endfacet + facet normal 0.322126 -0.363875 0.873973 + outer loop + vertex 849.864 260.471 354.981 + vertex 843.263 259.363 356.953 + vertex 843.753 254.83 354.884 + endloop + endfacet + facet normal 0.267351 -0.295674 0.917115 + outer loop + vertex 848.857 269.586 358.648 + vertex 842.819 264.029 358.617 + vertex 849.345 264.939 357.008 + endloop + endfacet + facet normal 0.267648 -0.301045 0.91528 + outer loop + vertex 849.345 264.939 357.008 + vertex 842.819 264.029 358.617 + vertex 843.263 259.363 356.953 + endloop + endfacet + facet normal 0.213957 -0.232586 0.94875 + outer loop + vertex 848.34 274.386 359.941 + vertex 842.406 268.801 359.911 + vertex 848.857 269.586 358.648 + endloop + endfacet + facet normal 0.214353 -0.238258 0.947252 + outer loop + vertex 848.857 269.586 358.648 + vertex 842.406 268.801 359.911 + vertex 842.819 264.029 358.617 + endloop + endfacet + facet normal 0.163728 -0.174371 0.970973 + outer loop + vertex 847.862 279.373 360.918 + vertex 842.001 273.661 360.88 + vertex 848.34 274.386 359.941 + endloop + endfacet + facet normal 0.164192 -0.179825 0.969899 + outer loop + vertex 848.34 274.386 359.941 + vertex 842.001 273.661 360.88 + vertex 842.406 268.801 359.911 + endloop + endfacet + facet normal 0.161262 -0.366896 -0.916178 + outer loop + vertex 837.962 226.227 303.841 + vertex 831.402 220.017 305.174 + vertex 835.323 227.14 303.011 + endloop + endfacet + facet normal 0.0921534 -0.335354 -0.937574 + outer loop + vertex 835.323 227.14 303.011 + vertex 831.402 220.017 305.174 + vertex 828.495 220.483 304.722 + endloop + endfacet + facet normal 0.188553 -0.348582 -0.918117 + outer loop + vertex 830.857 216.42 306.428 + vertex 831.402 220.017 305.174 + vertex 834.315 220 305.779 + endloop + endfacet + facet normal 0.185063 -0.389086 -0.902421 + outer loop + vertex 831.402 220.017 305.174 + vertex 837.962 226.227 303.841 + vertex 834.315 220 305.779 + endloop + endfacet + facet normal 0.212926 -0.369645 -0.904447 + outer loop + vertex 834.315 220 305.779 + vertex 832.185 215.255 307.216 + vertex 830.857 216.42 306.428 + endloop + endfacet + facet normal 0.491577 -0.573587 -0.655248 + outer loop + vertex 839.387 214.818 311.102 + vertex 835.772 211.65 311.162 + vertex 838.245 215.644 309.522 + endloop + endfacet + facet normal 0.480079 -0.570897 -0.666033 + outer loop + vertex 838.245 215.644 309.522 + vertex 835.772 211.65 311.162 + vertex 834.664 212.481 309.652 + endloop + endfacet + facet normal 0.503632 -0.576054 -0.643829 + outer loop + vertex 843.059 218.106 311.032 + vertex 839.387 214.818 311.102 + vertex 841.884 218.929 309.377 + endloop + endfacet + facet normal 0.491614 -0.573548 -0.655254 + outer loop + vertex 841.884 218.929 309.377 + vertex 839.387 214.818 311.102 + vertex 838.245 215.644 309.522 + endloop + endfacet + facet normal 0.635404 -0.741398 -0.215847 + outer loop + vertex 841.566 214.886 314.959 + vertex 837.882 211.729 314.956 + vertex 840.47 214.546 312.9 + endloop + endfacet + facet normal 0.641254 -0.739278 -0.205575 + outer loop + vertex 840.47 214.546 312.9 + vertex 837.882 211.729 314.956 + vertex 836.825 211.379 312.918 + endloop + endfacet + facet normal 0.645818 -0.72922 -0.226181 + outer loop + vertex 845.325 218.215 314.96 + vertex 841.566 214.886 314.959 + vertex 844.173 217.841 312.876 + endloop + endfacet + facet normal 0.647011 -0.728805 -0.224098 + outer loop + vertex 844.173 217.841 312.876 + vertex 841.566 214.886 314.959 + vertex 840.47 214.546 312.9 + endloop + endfacet + facet normal 0.590956 -0.667491 -0.45302 + outer loop + vertex 844.173 217.841 312.876 + vertex 840.47 214.546 312.9 + vertex 843.059 218.106 311.032 + endloop + endfacet + facet normal 0.589087 -0.667443 -0.455518 + outer loop + vertex 843.059 218.106 311.032 + vertex 840.47 214.546 312.9 + vertex 839.387 214.818 311.102 + endloop + endfacet + facet normal 0.583418 -0.674037 -0.453098 + outer loop + vertex 840.47 214.546 312.9 + vertex 836.825 211.379 312.918 + vertex 839.387 214.818 311.102 + endloop + endfacet + facet normal 0.582959 -0.67402 -0.453713 + outer loop + vertex 839.387 214.818 311.102 + vertex 836.825 211.379 312.918 + vertex 835.772 211.65 311.162 + endloop + endfacet + facet normal 0.642606 -0.733102 0.222752 + outer loop + vertex 843.75 217.654 319.93 + vertex 840.096 214.312 319.474 + vertex 842.714 215.937 317.268 + endloop + endfacet + facet normal 0.634638 -0.745314 0.204308 + outer loop + vertex 842.714 215.937 317.268 + vertex 840.096 214.312 319.474 + vertex 838.962 212.738 317.254 + endloop + endfacet + facet normal 0.635336 -0.744451 0.205283 + outer loop + vertex 847.803 220.988 319.478 + vertex 843.75 217.654 319.93 + vertex 846.55 219.31 317.271 + endloop + endfacet + facet normal 0.64383 -0.732325 0.221773 + outer loop + vertex 846.55 219.31 317.271 + vertex 843.75 217.654 319.93 + vertex 842.714 215.937 317.268 + endloop + endfacet + facet normal 0.660358 -0.750928 0.0059496 + outer loop + vertex 846.55 219.31 317.271 + vertex 842.714 215.937 317.268 + vertex 845.325 218.215 314.96 + endloop + endfacet + facet normal 0.662903 -0.748623 0.0111045 + outer loop + vertex 845.325 218.215 314.96 + vertex 842.714 215.937 317.268 + vertex 841.566 214.886 314.959 + endloop + endfacet + facet normal 0.648526 -0.76082 0.0238055 + outer loop + vertex 842.714 215.937 317.268 + vertex 838.962 212.738 317.254 + vertex 841.566 214.886 314.959 + endloop + endfacet + facet normal 0.650399 -0.759093 0.0275457 + outer loop + vertex 841.566 214.886 314.959 + vertex 838.962 212.738 317.254 + vertex 837.882 211.729 314.956 + endloop + endfacet + facet normal 0.598187 -0.705905 0.379303 + outer loop + vertex 840.096 214.312 319.474 + vertex 843.75 217.654 319.93 + vertex 838.545 214.896 323.006 + endloop + endfacet + facet normal 0.616259 -0.70023 0.360421 + outer loop + vertex 847.803 220.988 319.478 + vertex 846.199 221.386 322.994 + vertex 843.75 217.654 319.93 + endloop + endfacet + facet normal 0.598443 -0.705036 0.380515 + outer loop + vertex 846.199 221.386 322.994 + vertex 838.545 214.896 323.006 + vertex 843.75 217.654 319.93 + endloop + endfacet + facet normal 0.47229 -0.552714 0.686622 + outer loop + vertex 845.454 242.385 346.486 + vertex 838.06 236.127 346.534 + vertex 846.018 238.653 343.094 + endloop + endfacet + facet normal 0.472287 -0.552814 0.686543 + outer loop + vertex 846.018 238.653 343.094 + vertex 838.06 236.127 346.534 + vertex 838.631 232.421 343.157 + endloop + endfacet + facet normal 0.442993 -0.516313 0.732925 + outer loop + vertex 844.879 246.325 349.609 + vertex 837.507 240.07 349.659 + vertex 845.454 242.385 346.486 + endloop + endfacet + facet normal 0.443004 -0.517765 0.731893 + outer loop + vertex 845.454 242.385 346.486 + vertex 837.507 240.07 349.659 + vertex 838.06 236.127 346.534 + endloop + endfacet + facet normal 0.408607 -0.473467 0.780301 + outer loop + vertex 844.314 250.478 352.425 + vertex 836.97 244.228 352.478 + vertex 844.879 246.325 349.609 + endloop + endfacet + facet normal 0.408683 -0.475502 0.779023 + outer loop + vertex 844.879 246.325 349.609 + vertex 836.97 244.228 352.478 + vertex 837.507 240.07 349.659 + endloop + endfacet + facet normal 0.365867 -0.421696 0.829647 + outer loop + vertex 843.753 254.83 354.884 + vertex 836.453 248.598 354.936 + vertex 844.314 250.478 352.425 + endloop + endfacet + facet normal 0.365949 -0.422923 0.828986 + outer loop + vertex 844.314 250.478 352.425 + vertex 836.453 248.598 354.936 + vertex 836.97 244.228 352.478 + endloop + endfacet + facet normal 0.317347 -0.36498 0.87526 + outer loop + vertex 843.263 259.363 356.953 + vertex 835.989 253.158 357.002 + vertex 843.753 254.83 354.884 + endloop + endfacet + facet normal 0.317295 -0.364418 0.875513 + outer loop + vertex 843.753 254.83 354.884 + vertex 835.989 253.158 357.002 + vertex 836.453 248.598 354.936 + endloop + endfacet + facet normal 0.263793 -0.30173 0.916173 + outer loop + vertex 842.819 264.029 358.617 + vertex 835.596 257.87 358.668 + vertex 843.263 259.363 356.953 + endloop + endfacet + facet normal 0.263812 -0.301902 0.916111 + outer loop + vertex 843.263 259.363 356.953 + vertex 835.596 257.87 358.668 + vertex 835.989 253.158 357.002 + endloop + endfacet + facet normal 0.210492 -0.238791 0.947983 + outer loop + vertex 842.406 268.801 359.911 + vertex 835.264 262.685 359.956 + vertex 842.819 264.029 358.617 + endloop + endfacet + facet normal 0.210518 -0.238988 0.947928 + outer loop + vertex 842.819 264.029 358.617 + vertex 835.264 262.685 359.956 + vertex 835.596 257.87 358.668 + endloop + endfacet + facet normal 0.160512 -0.180239 0.970438 + outer loop + vertex 842.001 273.661 360.88 + vertex 834.967 267.565 360.911 + vertex 842.406 268.801 359.911 + endloop + endfacet + facet normal 0.160516 -0.180268 0.970432 + outer loop + vertex 842.406 268.801 359.911 + vertex 834.967 267.565 360.911 + vertex 835.264 262.685 359.956 + endloop + endfacet + facet normal 0.104228 -0.277107 -0.955169 + outer loop + vertex 831.402 220.017 305.174 + vertex 824.793 213.95 306.213 + vertex 828.495 220.483 304.722 + endloop + endfacet + facet normal 0.0852013 -0.267383 -0.959816 + outer loop + vertex 828.495 220.483 304.722 + vertex 824.793 213.95 306.213 + vertex 822.231 214.413 305.856 + endloop + endfacet + facet normal 0.200356 -0.349389 -0.915306 + outer loop + vertex 830.857 216.42 306.428 + vertex 827.584 213.913 306.668 + vertex 831.402 220.017 305.174 + endloop + endfacet + facet normal 0.150525 -0.286648 -0.946137 + outer loop + vertex 824.178 210.526 307.152 + vertex 824.793 213.95 306.213 + vertex 827.584 213.913 306.668 + endloop + endfacet + facet normal 0.14828 -0.321674 -0.935168 + outer loop + vertex 824.793 213.95 306.213 + vertex 831.402 220.017 305.174 + vertex 827.584 213.913 306.668 + endloop + endfacet + facet normal 0.229285 -0.35284 -0.907156 + outer loop + vertex 832.185 215.255 307.216 + vertex 828.78 212.244 307.527 + vertex 830.857 216.42 306.428 + endloop + endfacet + facet normal 0.190815 -0.337547 -0.921765 + outer loop + vertex 830.857 216.42 306.428 + vertex 828.78 212.244 307.527 + vertex 827.584 213.913 306.668 + endloop + endfacet + facet normal 0.209294 -0.324632 -0.922394 + outer loop + vertex 828.78 212.244 307.527 + vertex 825.413 209.327 307.789 + vertex 827.584 213.913 306.668 + endloop + endfacet + facet normal 0.178041 -0.312457 -0.933098 + outer loop + vertex 827.584 213.913 306.668 + vertex 825.413 209.327 307.789 + vertex 824.178 210.526 307.152 + endloop + endfacet + facet normal 0.470589 -0.571616 -0.672162 + outer loop + vertex 832.212 208.599 311.23 + vertex 828.678 205.613 311.295 + vertex 831.148 209.431 309.778 + endloop + endfacet + facet normal 0.462659 -0.569402 -0.679506 + outer loop + vertex 831.148 209.431 309.778 + vertex 828.678 205.613 311.295 + vertex 827.668 206.462 309.896 + endloop + endfacet + facet normal 0.478239 -0.572796 -0.665727 + outer loop + vertex 835.772 211.65 311.162 + vertex 832.212 208.599 311.23 + vertex 834.664 212.481 309.652 + endloop + endfacet + facet normal 0.471199 -0.571002 -0.672257 + outer loop + vertex 834.664 212.481 309.652 + vertex 832.212 208.599 311.23 + vertex 831.148 209.431 309.778 + endloop + endfacet + facet normal 0.623177 -0.759786 -0.185405 + outer loop + vertex 834.248 208.676 314.961 + vertex 830.623 205.699 314.977 + vertex 833.227 208.33 312.947 + endloop + endfacet + facet normal 0.628342 -0.757739 -0.176123 + outer loop + vertex 833.227 208.33 312.947 + vertex 830.623 205.699 314.977 + vertex 829.643 205.35 312.983 + endloop + endfacet + facet normal 0.630374 -0.750619 -0.19799 + outer loop + vertex 837.882 211.729 314.956 + vertex 834.248 208.676 314.961 + vertex 836.825 211.379 312.918 + endloop + endfacet + facet normal 0.63352 -0.749415 -0.192429 + outer loop + vertex 836.825 211.379 312.918 + vertex 834.248 208.676 314.961 + vertex 833.227 208.33 312.947 + endloop + endfacet + facet normal 0.575073 -0.682979 -0.450367 + outer loop + vertex 836.825 211.379 312.918 + vertex 833.227 208.33 312.947 + vertex 835.772 211.65 311.162 + endloop + endfacet + facet normal 0.576826 -0.683054 -0.448006 + outer loop + vertex 835.772 211.65 311.162 + vertex 833.227 208.33 312.947 + vertex 832.212 208.599 311.23 + endloop + endfacet + facet normal 0.569928 -0.690685 -0.445125 + outer loop + vertex 833.227 208.33 312.947 + vertex 829.643 205.35 312.983 + vertex 832.212 208.599 311.23 + endloop + endfacet + facet normal 0.57578 -0.69097 -0.437077 + outer loop + vertex 832.212 208.599 311.23 + vertex 829.643 205.35 312.983 + vertex 828.678 205.613 311.295 + endloop + endfacet + facet normal 0.619031 -0.746908 0.242752 + outer loop + vertex 836.167 211.272 319.912 + vertex 832.632 208.194 319.459 + vertex 835.282 209.672 317.247 + endloop + endfacet + facet normal 0.613965 -0.75461 0.231538 + outer loop + vertex 835.282 209.672 317.247 + vertex 832.632 208.194 319.459 + vertex 831.617 206.691 317.25 + endloop + endfacet + facet normal 0.611915 -0.758223 0.225071 + outer loop + vertex 840.096 214.312 319.474 + vertex 836.167 211.272 319.912 + vertex 838.962 212.738 317.254 + endloop + endfacet + facet normal 0.620934 -0.745757 0.24143 + outer loop + vertex 838.962 212.738 317.254 + vertex 836.167 211.272 319.912 + vertex 835.282 209.672 317.247 + endloop + endfacet + facet normal 0.639686 -0.767774 0.036394 + outer loop + vertex 838.962 212.738 317.254 + vertex 835.282 209.672 317.247 + vertex 837.882 211.729 314.956 + endloop + endfacet + facet normal 0.64271 -0.764937 0.0423737 + outer loop + vertex 837.882 211.729 314.956 + vertex 835.282 209.672 317.247 + vertex 834.248 208.676 314.961 + endloop + endfacet + facet normal 0.63015 -0.774709 0.0523165 + outer loop + vertex 835.282 209.672 317.247 + vertex 831.617 206.691 317.25 + vertex 834.248 208.676 314.961 + endloop + endfacet + facet normal 0.633697 -0.771301 0.0593493 + outer loop + vertex 834.248 208.676 314.961 + vertex 831.617 206.691 317.25 + vertex 830.623 205.699 314.977 + endloop + endfacet + facet normal 0.574572 -0.717942 0.392971 + outer loop + vertex 832.632 208.194 319.459 + vertex 836.167 211.272 319.912 + vertex 830.911 208.755 323 + endloop + endfacet + facet normal 0.592669 -0.711354 0.37778 + outer loop + vertex 840.096 214.312 319.474 + vertex 838.545 214.896 323.006 + vertex 836.167 211.272 319.912 + endloop + endfacet + facet normal 0.575309 -0.715619 0.396119 + outer loop + vertex 838.545 214.896 323.006 + vertex 830.911 208.755 323 + vertex 836.167 211.272 319.912 + endloop + endfacet + facet normal 0.455029 -0.56044 0.691994 + outer loop + vertex 838.06 236.127 346.534 + vertex 830.118 229.763 346.603 + vertex 838.631 232.421 343.157 + endloop + endfacet + facet normal 0.455029 -0.56043 0.692002 + outer loop + vertex 838.631 232.421 343.157 + vertex 830.118 229.763 346.603 + vertex 830.702 226.073 343.23 + endloop + endfacet + facet normal 0.426877 -0.524058 0.73698 + outer loop + vertex 837.507 240.07 349.659 + vertex 829.579 233.709 349.728 + vertex 838.06 236.127 346.534 + endloop + endfacet + facet normal 0.426888 -0.524847 0.736412 + outer loop + vertex 838.06 236.127 346.534 + vertex 829.579 233.709 349.728 + vertex 830.118 229.763 346.603 + endloop + endfacet + facet normal 0.393345 -0.480673 0.78373 + outer loop + vertex 836.97 244.228 352.478 + vertex 829.065 237.871 352.547 + vertex 837.507 240.07 349.659 + endloop + endfacet + facet normal 0.393394 -0.48183 0.782995 + outer loop + vertex 837.507 240.07 349.659 + vertex 829.065 237.871 352.547 + vertex 829.579 233.709 349.728 + endloop + endfacet + facet normal 0.351932 -0.426858 0.833028 + outer loop + vertex 836.453 248.598 354.936 + vertex 828.583 242.239 355.003 + vertex 836.97 244.228 352.478 + endloop + endfacet + facet normal 0.352077 -0.428838 0.831949 + outer loop + vertex 836.97 244.228 352.478 + vertex 828.583 242.239 355.003 + vertex 829.065 237.871 352.547 + endloop + endfacet + facet normal 0.303806 -0.36739 0.879049 + outer loop + vertex 835.989 253.158 357.002 + vertex 828.155 246.807 357.055 + vertex 836.453 248.598 354.936 + endloop + endfacet + facet normal 0.30374 -0.366728 0.879348 + outer loop + vertex 836.453 248.598 354.936 + vertex 828.155 246.807 357.055 + vertex 828.583 242.239 355.003 + endloop + endfacet + facet normal 0.25256 -0.303745 0.918669 + outer loop + vertex 835.596 257.87 358.668 + vertex 827.797 251.529 358.716 + vertex 835.989 253.158 357.002 + endloop + endfacet + facet normal 0.252574 -0.303861 0.918627 + outer loop + vertex 835.989 253.158 357.002 + vertex 827.797 251.529 358.716 + vertex 828.155 246.807 357.055 + endloop + endfacet + facet normal 0.200692 -0.240157 0.949762 + outer loop + vertex 835.264 262.685 359.956 + vertex 827.511 256.373 359.998 + vertex 835.596 257.87 358.668 + endloop + endfacet + facet normal 0.200617 -0.239614 0.949915 + outer loop + vertex 835.596 257.87 358.668 + vertex 827.511 256.373 359.998 + vertex 827.797 251.529 358.716 + endloop + endfacet + facet normal 0.151846 -0.18104 0.971683 + outer loop + vertex 834.967 267.565 360.911 + vertex 827.282 261.295 360.944 + vertex 835.264 262.685 359.956 + endloop + endfacet + facet normal 0.15166 -0.179783 0.971945 + outer loop + vertex 835.264 262.685 359.956 + vertex 827.282 261.295 360.944 + vertex 827.511 256.373 359.998 + endloop + endfacet + facet normal 0.165458 -0.288491 -0.943078 + outer loop + vertex 824.178 210.526 307.152 + vertex 820.933 208.132 307.315 + vertex 824.793 213.95 306.213 + endloop + endfacet + facet normal 0.132448 -0.241323 -0.961364 + outer loop + vertex 817.474 204.846 307.664 + vertex 818.253 208.24 306.919 + vertex 820.933 208.132 307.315 + endloop + endfacet + facet normal 0.130409 -0.267446 -0.954707 + outer loop + vertex 818.253 208.24 306.919 + vertex 824.793 213.95 306.213 + vertex 820.933 208.132 307.315 + endloop + endfacet + facet normal 0.190776 -0.30015 -0.93462 + outer loop + vertex 825.413 209.327 307.789 + vertex 822.041 206.466 308.02 + vertex 824.178 210.526 307.152 + endloop + endfacet + facet normal 0.165616 -0.2887 -0.942987 + outer loop + vertex 824.178 210.526 307.152 + vertex 822.041 206.466 308.02 + vertex 820.933 208.132 307.315 + endloop + endfacet + facet normal 0.17949 -0.279568 -0.9432 + outer loop + vertex 822.041 206.466 308.02 + vertex 818.626 203.628 308.211 + vertex 820.933 208.132 307.315 + endloop + endfacet + facet normal 0.163062 -0.272171 -0.948332 + outer loop + vertex 820.933 208.132 307.315 + vertex 818.626 203.628 308.211 + vertex 817.474 204.846 307.664 + endloop + endfacet + facet normal 0.453009 -0.576785 -0.679781 + outer loop + vertex 825.128 202.695 311.361 + vertex 821.534 199.806 311.418 + vertex 824.183 203.554 310.003 + endloop + endfacet + facet normal 0.453177 -0.576843 -0.67962 + outer loop + vertex 824.183 203.554 310.003 + vertex 821.534 199.806 311.418 + vertex 820.657 200.676 310.094 + endloop + endfacet + facet normal 0.458633 -0.573294 -0.678962 + outer loop + vertex 828.678 205.613 311.295 + vertex 825.128 202.695 311.361 + vertex 827.668 206.462 309.896 + endloop + endfacet + facet normal 0.45725 -0.572865 -0.680256 + outer loop + vertex 827.668 206.462 309.896 + vertex 825.128 202.695 311.361 + vertex 824.183 203.554 310.003 + endloop + endfacet + facet normal 0.607927 -0.779654 -0.150216 + outer loop + vertex 826.973 202.76 314.991 + vertex 823.264 199.865 315.009 + vertex 826.038 202.412 313.015 + endloop + endfacet + facet normal 0.615553 -0.776374 -0.135421 + outer loop + vertex 826.038 202.412 313.015 + vertex 823.264 199.865 315.009 + vertex 822.382 199.508 313.044 + endloop + endfacet + facet normal 0.617736 -0.767987 -0.169111 + outer loop + vertex 830.623 205.699 314.977 + vertex 826.973 202.76 314.991 + vertex 829.643 205.35 312.983 + endloop + endfacet + facet normal 0.622809 -0.765906 -0.159679 + outer loop + vertex 829.643 205.35 312.983 + vertex 826.973 202.76 314.991 + vertex 826.038 202.412 313.015 + endloop + endfacet + facet normal 0.566983 -0.700421 -0.433521 + outer loop + vertex 829.643 205.35 312.983 + vertex 826.038 202.412 313.015 + vertex 828.678 205.613 311.295 + endloop + endfacet + facet normal 0.567767 -0.700471 -0.432412 + outer loop + vertex 828.678 205.613 311.295 + vertex 826.038 202.412 313.015 + vertex 825.128 202.695 311.361 + endloop + endfacet + facet normal 0.559591 -0.70888 -0.429356 + outer loop + vertex 826.038 202.412 313.015 + vertex 822.382 199.508 313.044 + vertex 825.128 202.695 311.361 + endloop + endfacet + facet normal 0.563552 -0.709231 -0.423558 + outer loop + vertex 825.128 202.695 311.361 + vertex 822.382 199.508 313.044 + vertex 821.534 199.806 311.418 + endloop + endfacet + facet normal 0.597414 -0.754538 0.271605 + outer loop + vertex 828.703 205.321 319.91 + vertex 825.15 202.347 319.462 + vertex 827.933 203.756 317.256 + endloop + endfacet + facet normal 0.591634 -0.763638 0.258507 + outer loop + vertex 827.933 203.756 317.256 + vertex 825.15 202.347 319.462 + vertex 824.188 200.857 317.263 + endloop + endfacet + facet normal 0.589962 -0.76735 0.251236 + outer loop + vertex 832.632 208.194 319.459 + vertex 828.703 205.321 319.91 + vertex 831.617 206.691 317.25 + endloop + endfacet + facet normal 0.600198 -0.752952 0.269861 + outer loop + vertex 831.617 206.691 317.25 + vertex 828.703 205.321 319.91 + vertex 827.933 203.756 317.256 + endloop + endfacet + facet normal 0.621649 -0.780292 0.0685354 + outer loop + vertex 831.617 206.691 317.25 + vertex 827.933 203.756 317.256 + vertex 830.623 205.699 314.977 + endloop + endfacet + facet normal 0.625513 -0.776468 0.0763564 + outer loop + vertex 830.623 205.699 314.977 + vertex 827.933 203.756 317.256 + vertex 826.973 202.76 314.991 + endloop + endfacet + facet normal 0.609885 -0.787603 0.0878761 + outer loop + vertex 827.933 203.756 317.256 + vertex 824.188 200.857 317.263 + vertex 826.973 202.76 314.991 + endloop + endfacet + facet normal 0.612936 -0.784495 0.0942179 + outer loop + vertex 826.973 202.76 314.991 + vertex 824.188 200.857 317.263 + vertex 823.264 199.865 315.009 + endloop + endfacet + facet normal 0.55414 -0.723829 0.411097 + outer loop + vertex 825.15 202.347 319.462 + vertex 828.703 205.321 319.91 + vertex 823.257 202.907 322.999 + endloop + endfacet + facet normal 0.571903 -0.720551 0.392088 + outer loop + vertex 832.632 208.194 319.459 + vertex 830.911 208.755 323 + vertex 828.703 205.321 319.91 + endloop + endfacet + facet normal 0.553825 -0.724828 0.40976 + outer loop + vertex 830.911 208.755 323 + vertex 823.257 202.907 322.999 + vertex 828.703 205.321 319.91 + endloop + endfacet + facet normal 0.434389 -0.569227 0.69806 + outer loop + vertex 830.118 229.763 346.603 + vertex 822.091 223.652 346.614 + vertex 830.702 226.073 343.23 + endloop + endfacet + facet normal 0.434375 -0.569661 0.697714 + outer loop + vertex 830.702 226.073 343.23 + vertex 822.091 223.652 346.614 + vertex 822.677 219.965 343.24 + endloop + endfacet + facet normal 0.407229 -0.53217 0.742267 + outer loop + vertex 829.579 233.709 349.728 + vertex 821.564 227.602 349.746 + vertex 830.118 229.763 346.603 + endloop + endfacet + facet normal 0.407217 -0.533452 0.741352 + outer loop + vertex 830.118 229.763 346.603 + vertex 821.564 227.602 349.746 + vertex 822.091 223.652 346.614 + endloop + endfacet + facet normal 0.374164 -0.48799 0.788586 + outer loop + vertex 829.065 237.871 352.547 + vertex 821.073 231.774 352.566 + vertex 829.579 233.709 349.728 + endloop + endfacet + facet normal 0.374176 -0.488654 0.788168 + outer loop + vertex 829.579 233.709 349.728 + vertex 821.073 231.774 352.566 + vertex 821.564 227.602 349.746 + endloop + endfacet + facet normal 0.333893 -0.43365 0.836937 + outer loop + vertex 828.583 242.239 355.003 + vertex 820.617 236.143 355.022 + vertex 829.065 237.871 352.547 + endloop + endfacet + facet normal 0.333962 -0.435135 0.836138 + outer loop + vertex 829.065 237.871 352.547 + vertex 820.617 236.143 355.022 + vertex 821.073 231.774 352.566 + endloop + endfacet + facet normal 0.287346 -0.3701 0.883436 + outer loop + vertex 828.155 246.807 357.055 + vertex 820.215 240.697 357.078 + vertex 828.583 242.239 355.003 + endloop + endfacet + facet normal 0.287557 -0.372963 0.882162 + outer loop + vertex 828.583 242.239 355.003 + vertex 820.215 240.697 357.078 + vertex 820.617 236.143 355.022 + endloop + endfacet + facet normal 0.237466 -0.306155 0.921889 + outer loop + vertex 827.797 251.529 358.716 + vertex 819.884 245.421 358.725 + vertex 828.155 246.807 357.055 + endloop + endfacet + facet normal 0.237355 -0.304997 0.922301 + outer loop + vertex 828.155 246.807 357.055 + vertex 819.884 245.421 358.725 + vertex 820.215 240.697 357.078 + endloop + endfacet + facet normal 0.187555 -0.240999 0.952231 + outer loop + vertex 827.511 256.373 359.998 + vertex 819.622 250.262 360.005 + vertex 827.797 251.529 358.716 + endloop + endfacet + facet normal 0.187614 -0.241529 0.952084 + outer loop + vertex 827.797 251.529 358.716 + vertex 819.622 250.262 360.005 + vertex 819.884 245.421 358.725 + endloop + endfacet + facet normal 0.140809 -0.180573 0.97343 + outer loop + vertex 827.282 261.295 360.944 + vertex 819.423 255.196 360.95 + vertex 827.511 256.373 359.998 + endloop + endfacet + facet normal 0.140818 -0.180642 0.973416 + outer loop + vertex 827.511 256.373 359.998 + vertex 819.423 255.196 360.95 + vertex 819.622 250.262 360.005 + endloop + endfacet + facet normal 0.144512 -0.243585 -0.959053 + outer loop + vertex 817.474 204.846 307.664 + vertex 814.153 202.5 307.759 + vertex 818.253 208.24 306.919 + endloop + endfacet + facet normal 0.123202 -0.21134 -0.969617 + outer loop + vertex 810.542 199.247 308.009 + vertex 811.524 202.638 307.395 + vertex 814.153 202.5 307.759 + endloop + endfacet + facet normal 0.121796 -0.228366 -0.965927 + outer loop + vertex 811.524 202.638 307.395 + vertex 818.253 208.24 306.919 + vertex 814.153 202.5 307.759 + endloop + endfacet + facet normal 0.171559 -0.26444 -0.94902 + outer loop + vertex 818.626 203.628 308.211 + vertex 815.152 200.805 308.37 + vertex 817.474 204.846 307.664 + endloop + endfacet + facet normal 0.152278 -0.254413 -0.955032 + outer loop + vertex 817.474 204.846 307.664 + vertex 815.152 200.805 308.37 + vertex 814.153 202.5 307.759 + endloop + endfacet + facet normal 0.16196 -0.248672 -0.954951 + outer loop + vertex 815.152 200.805 308.37 + vertex 811.603 197.999 308.499 + vertex 814.153 202.5 307.759 + endloop + endfacet + facet normal 0.153944 -0.244526 -0.957345 + outer loop + vertex 814.153 202.5 307.759 + vertex 811.603 197.999 308.499 + vertex 810.542 199.247 308.009 + endloop + endfacet + facet normal 0.44102 -0.585674 -0.680064 + outer loop + vertex 817.877 196.934 311.465 + vertex 814.152 194.083 311.505 + vertex 817.063 197.821 310.174 + endloop + endfacet + facet normal 0.442658 -0.586359 -0.678407 + outer loop + vertex 817.063 197.821 310.174 + vertex 814.152 194.083 311.505 + vertex 813.4 194.98 310.24 + endloop + endfacet + facet normal 0.447778 -0.581583 -0.679158 + outer loop + vertex 821.534 199.806 311.418 + vertex 817.877 196.934 311.465 + vertex 820.657 200.676 310.094 + endloop + endfacet + facet normal 0.446524 -0.581103 -0.680393 + outer loop + vertex 820.657 200.676 310.094 + vertex 817.877 196.934 311.465 + vertex 817.063 197.821 310.174 + endloop + endfacet + facet normal 0.594309 -0.797174 -0.106352 + outer loop + vertex 819.486 196.979 315.021 + vertex 815.641 194.111 315.03 + vertex 818.66 196.623 313.068 + endloop + endfacet + facet normal 0.59948 -0.794704 -0.0952302 + outer loop + vertex 818.66 196.623 313.068 + vertex 815.641 194.111 315.03 + vertex 814.872 193.764 313.089 + endloop + endfacet + facet normal 0.601827 -0.788454 -0.12706 + outer loop + vertex 823.264 199.865 315.009 + vertex 819.486 196.979 315.021 + vertex 822.382 199.508 313.044 + endloop + endfacet + facet normal 0.608071 -0.785614 -0.114283 + outer loop + vertex 822.382 199.508 313.044 + vertex 819.486 196.979 315.021 + vertex 818.66 196.623 313.068 + endloop + endfacet + facet normal 0.554106 -0.718526 -0.420342 + outer loop + vertex 822.382 199.508 313.044 + vertex 818.66 196.623 313.068 + vertex 821.534 199.806 311.418 + endloop + endfacet + facet normal 0.559198 -0.71909 -0.412561 + outer loop + vertex 821.534 199.806 311.418 + vertex 818.66 196.623 313.068 + vertex 817.877 196.934 311.465 + endloop + endfacet + facet normal 0.548381 -0.729244 -0.409246 + outer loop + vertex 818.66 196.623 313.068 + vertex 814.872 193.764 313.089 + vertex 817.877 196.934 311.465 + endloop + endfacet + facet normal 0.554494 -0.730036 -0.399478 + outer loop + vertex 817.877 196.934 311.465 + vertex 814.872 193.764 313.089 + vertex 814.152 194.083 311.505 + endloop + endfacet + facet normal 0.573789 -0.762743 0.298311 + outer loop + vertex 821.088 199.544 319.913 + vertex 817.419 196.61 319.467 + vertex 820.376 197.974 317.268 + endloop + endfacet + facet normal 0.568102 -0.772082 0.284869 + outer loop + vertex 820.376 197.974 317.268 + vertex 817.419 196.61 319.467 + vertex 816.487 195.114 317.274 + endloop + endfacet + facet normal 0.566287 -0.775937 0.277921 + outer loop + vertex 825.15 202.347 319.462 + vertex 821.088 199.544 319.913 + vertex 824.188 200.857 317.263 + endloop + endfacet + facet normal 0.576312 -0.761413 0.296842 + outer loop + vertex 824.188 200.857 317.263 + vertex 821.088 199.544 319.913 + vertex 820.376 197.974 317.268 + endloop + endfacet + facet normal 0.600086 -0.793233 0.103337 + outer loop + vertex 824.188 200.857 317.263 + vertex 820.376 197.974 317.268 + vertex 823.264 199.865 315.009 + endloop + endfacet + facet normal 0.603498 -0.789642 0.110705 + outer loop + vertex 823.264 199.865 315.009 + vertex 820.376 197.974 317.268 + vertex 819.486 196.979 315.021 + endloop + endfacet + facet normal 0.588127 -0.799634 0.121211 + outer loop + vertex 820.376 197.974 317.268 + vertex 816.487 195.114 317.274 + vertex 819.486 196.979 315.021 + endloop + endfacet + facet normal 0.592818 -0.794492 0.131717 + outer loop + vertex 819.486 196.979 315.021 + vertex 816.487 195.114 317.274 + vertex 815.641 194.111 315.03 + endloop + endfacet + facet normal 0.531753 -0.730103 0.429171 + outer loop + vertex 817.419 196.61 319.467 + vertex 821.088 199.544 319.913 + vertex 815.405 197.218 322.997 + endloop + endfacet + facet normal 0.548601 -0.729225 0.408985 + outer loop + vertex 825.15 202.347 319.462 + vertex 823.257 202.907 322.999 + vertex 821.088 199.544 319.913 + endloop + endfacet + facet normal 0.530884 -0.732906 0.425455 + outer loop + vertex 823.257 202.907 322.999 + vertex 815.405 197.218 322.997 + vertex 821.088 199.544 319.913 + endloop + endfacet + facet normal 0.414012 -0.577961 0.703247 + outer loop + vertex 822.091 223.652 346.614 + vertex 814.088 217.887 346.588 + vertex 822.677 219.965 343.24 + endloop + endfacet + facet normal 0.414074 -0.576983 0.704013 + outer loop + vertex 822.677 219.965 343.24 + vertex 814.088 217.887 346.588 + vertex 814.665 214.185 343.215 + endloop + endfacet + facet normal 0.387584 -0.540406 0.74682 + outer loop + vertex 821.564 227.602 349.746 + vertex 813.577 221.843 349.724 + vertex 822.091 223.652 346.614 + endloop + endfacet + facet normal 0.38754 -0.541415 0.746112 + outer loop + vertex 822.091 223.652 346.614 + vertex 813.577 221.843 349.724 + vertex 814.088 217.887 346.588 + endloop + endfacet + facet normal 0.35518 -0.494399 0.793358 + outer loop + vertex 821.073 231.774 352.566 + vertex 813.104 226.021 352.549 + vertex 821.564 227.602 349.746 + endloop + endfacet + facet normal 0.355159 -0.49561 0.792611 + outer loop + vertex 821.564 227.602 349.746 + vertex 813.104 226.021 352.549 + vertex 813.577 221.843 349.724 + endloop + endfacet + facet normal 0.316264 -0.439548 0.840699 + outer loop + vertex 820.617 236.143 355.022 + vertex 812.668 230.394 355.006 + vertex 821.073 231.774 352.566 + endloop + endfacet + facet normal 0.316277 -0.440653 0.840116 + outer loop + vertex 821.073 231.774 352.566 + vertex 812.668 230.394 355.006 + vertex 813.104 226.021 352.549 + endloop + endfacet + facet normal 0.270981 -0.376174 0.886037 + outer loop + vertex 820.215 240.697 357.078 + vertex 812.287 234.947 357.062 + vertex 820.617 236.143 355.022 + endloop + endfacet + facet normal 0.271016 -0.377115 0.885627 + outer loop + vertex 820.617 236.143 355.022 + vertex 812.287 234.947 357.062 + vertex 812.668 230.394 355.006 + endloop + endfacet + facet normal 0.221889 -0.30717 0.925425 + outer loop + vertex 819.884 245.421 358.725 + vertex 811.974 239.662 358.711 + vertex 820.215 240.697 357.078 + endloop + endfacet + facet normal 0.221977 -0.308722 0.924887 + outer loop + vertex 820.215 240.697 357.078 + vertex 811.974 239.662 358.711 + vertex 812.287 234.947 357.062 + endloop + endfacet + facet normal 0.175444 -0.242721 0.9541 + outer loop + vertex 819.622 250.262 360.005 + vertex 811.728 244.495 359.99 + vertex 819.884 245.421 358.725 + endloop + endfacet + facet normal 0.175502 -0.243529 0.953883 + outer loop + vertex 819.884 245.421 358.725 + vertex 811.728 244.495 359.99 + vertex 811.974 239.662 358.711 + endloop + endfacet + facet normal 0.131242 -0.181262 0.974638 + outer loop + vertex 819.423 255.196 360.95 + vertex 811.542 249.42 360.937 + vertex 819.622 250.262 360.005 + endloop + endfacet + facet normal 0.131335 -0.1824 0.974413 + outer loop + vertex 819.622 250.262 360.005 + vertex 811.542 249.42 360.937 + vertex 811.728 244.495 359.99 + endloop + endfacet + facet normal 0.1323 -0.213665 -0.967907 + outer loop + vertex 810.542 199.247 308.009 + vertex 807.13 196.956 308.049 + vertex 811.524 202.638 307.395 + endloop + endfacet + facet normal 0.118336 -0.190979 -0.974435 + outer loop + vertex 803.392 193.782 308.217 + vertex 804.57 197.178 307.694 + vertex 807.13 196.956 308.049 + endloop + endfacet + facet normal 0.117049 -0.202374 -0.972288 + outer loop + vertex 804.57 197.178 307.694 + vertex 811.524 202.638 307.395 + vertex 807.13 196.956 308.049 + endloop + endfacet + facet normal 0.158046 -0.241116 -0.957541 + outer loop + vertex 811.603 197.999 308.499 + vertex 807.998 195.221 308.603 + vertex 810.542 199.247 308.009 + endloop + endfacet + facet normal 0.146105 -0.234107 -0.96117 + outer loop + vertex 810.542 199.247 308.009 + vertex 807.998 195.221 308.603 + vertex 807.13 196.956 308.049 + endloop + endfacet + facet normal 0.15311 -0.230528 -0.960944 + outer loop + vertex 807.998 195.221 308.603 + vertex 804.349 192.479 308.68 + vertex 807.13 196.956 308.049 + endloop + endfacet + facet normal 0.151923 -0.229841 -0.961297 + outer loop + vertex 807.13 196.956 308.049 + vertex 804.349 192.479 308.68 + vertex 803.392 193.782 308.217 + endloop + endfacet + facet normal 0.432094 -0.597243 -0.675719 + outer loop + vertex 810.372 191.264 311.536 + vertex 806.558 188.483 311.556 + vertex 809.677 192.169 310.293 + endloop + endfacet + facet normal 0.430877 -0.596657 -0.677012 + outer loop + vertex 809.677 192.169 310.293 + vertex 806.558 188.483 311.556 + vertex 805.916 189.405 310.334 + endloop + endfacet + facet normal 0.435758 -0.591794 -0.678156 + outer loop + vertex 814.152 194.083 311.505 + vertex 810.372 191.264 311.536 + vertex 813.4 194.98 310.24 + endloop + endfacet + facet normal 0.438015 -0.592814 -0.675807 + outer loop + vertex 813.4 194.98 310.24 + vertex 810.372 191.264 311.536 + vertex 809.677 192.169 310.293 + endloop + endfacet + facet normal 0.575888 -0.814484 -0.0704822 + outer loop + vertex 811.744 191.278 315.035 + vertex 807.815 188.5 315.041 + vertex 811.033 190.942 313.106 + endloop + endfacet + facet normal 0.580427 -0.812104 -0.0599302 + outer loop + vertex 811.033 190.942 313.106 + vertex 807.815 188.5 315.041 + vertex 807.159 188.173 313.121 + endloop + endfacet + facet normal 0.585688 -0.805769 -0.087781 + outer loop + vertex 815.641 194.111 315.03 + vertex 811.744 191.278 315.035 + vertex 814.872 193.764 313.089 + endloop + endfacet + facet normal 0.590191 -0.803518 -0.0776695 + outer loop + vertex 814.872 193.764 313.089 + vertex 811.744 191.278 315.035 + vertex 811.033 190.942 313.106 + endloop + endfacet + facet normal 0.542579 -0.740691 -0.396214 + outer loop + vertex 814.872 193.764 313.089 + vertex 811.033 190.942 313.106 + vertex 814.152 194.083 311.505 + endloop + endfacet + facet normal 0.550049 -0.74175 -0.383736 + outer loop + vertex 814.152 194.083 311.505 + vertex 811.033 190.942 313.106 + vertex 810.372 191.264 311.536 + endloop + endfacet + facet normal 0.536915 -0.752951 -0.38051 + outer loop + vertex 811.033 190.942 313.106 + vertex 807.159 188.173 313.121 + vertex 810.372 191.264 311.536 + endloop + endfacet + facet normal 0.548433 -0.754577 -0.360326 + outer loop + vertex 810.372 191.264 311.536 + vertex 807.159 188.173 313.121 + vertex 806.558 188.483 311.556 + endloop + endfacet + facet normal 0.548734 -0.77106 0.323044 + outer loop + vertex 813.214 193.856 319.917 + vertex 809.443 190.985 319.469 + vertex 812.545 192.273 317.275 + endloop + endfacet + facet normal 0.544582 -0.778096 0.313044 + outer loop + vertex 812.545 192.273 317.275 + vertex 809.443 190.985 319.469 + vertex 808.565 189.489 317.277 + endloop + endfacet + facet normal 0.544646 -0.782441 0.301906 + outer loop + vertex 817.419 196.61 319.467 + vertex 813.214 193.856 319.917 + vertex 816.487 195.114 317.274 + endloop + endfacet + facet normal 0.554021 -0.768479 0.320157 + outer loop + vertex 816.487 195.114 317.274 + vertex 813.214 193.856 319.917 + vertex 812.545 192.273 317.275 + endloop + endfacet + facet normal 0.578945 -0.803118 0.140798 + outer loop + vertex 816.487 195.114 317.274 + vertex 812.545 192.273 317.275 + vertex 815.641 194.111 315.03 + endloop + endfacet + facet normal 0.581759 -0.799911 0.147304 + outer loop + vertex 815.641 194.111 315.03 + vertex 812.545 192.273 317.275 + vertex 811.744 191.278 315.035 + endloop + endfacet + facet normal 0.566218 -0.80917 0.156972 + outer loop + vertex 812.545 192.273 317.275 + vertex 808.565 189.489 317.277 + vertex 811.744 191.278 315.035 + endloop + endfacet + facet normal 0.569637 -0.80516 0.165019 + outer loop + vertex 811.744 191.278 315.035 + vertex 808.565 189.489 317.277 + vertex 807.815 188.5 315.041 + endloop + endfacet + facet normal 0.509971 -0.738557 0.440981 + outer loop + vertex 809.443 190.985 319.469 + vertex 813.214 193.856 319.917 + vertex 807.363 191.658 323.001 + endloop + endfacet + facet normal 0.526866 -0.734792 0.427191 + outer loop + vertex 817.419 196.61 319.467 + vertex 815.405 197.218 322.997 + vertex 813.214 193.856 319.917 + endloop + endfacet + facet normal 0.51025 -0.737666 0.442147 + outer loop + vertex 815.405 197.218 322.997 + vertex 807.363 191.658 323.001 + vertex 813.214 193.856 319.917 + endloop + endfacet + facet normal 0.396447 -0.583824 0.708505 + outer loop + vertex 814.088 217.887 346.588 + vertex 806.019 212.377 346.563 + vertex 814.665 214.185 343.215 + endloop + endfacet + facet normal 0.396407 -0.584265 0.708164 + outer loop + vertex 814.665 214.185 343.215 + vertex 806.019 212.377 346.563 + vertex 806.584 208.673 343.19 + endloop + endfacet + facet normal 0.371243 -0.546908 0.75038 + outer loop + vertex 813.577 221.843 349.724 + vertex 805.522 216.342 349.7 + vertex 814.088 217.887 346.588 + endloop + endfacet + facet normal 0.371231 -0.547076 0.750264 + outer loop + vertex 814.088 217.887 346.588 + vertex 805.522 216.342 349.7 + vertex 806.019 212.377 346.563 + endloop + endfacet + facet normal 0.339685 -0.500053 0.796593 + outer loop + vertex 813.104 226.021 352.549 + vertex 805.065 220.525 352.527 + vertex 813.577 221.843 349.724 + endloop + endfacet + facet normal 0.339649 -0.500845 0.796111 + outer loop + vertex 813.577 221.843 349.724 + vertex 805.065 220.525 352.527 + vertex 805.522 216.342 349.7 + endloop + endfacet + facet normal 0.301999 -0.444025 0.843587 + outer loop + vertex 812.668 230.394 355.006 + vertex 804.645 224.899 354.986 + vertex 813.104 226.021 352.549 + endloop + endfacet + facet normal 0.301981 -0.445093 0.84303 + outer loop + vertex 813.104 226.021 352.549 + vertex 804.645 224.899 354.986 + vertex 805.065 220.525 352.527 + endloop + endfacet + facet normal 0.257648 -0.379561 0.888567 + outer loop + vertex 812.287 234.947 357.062 + vertex 804.277 229.456 357.039 + vertex 812.668 230.394 355.006 + endloop + endfacet + facet normal 0.257647 -0.379419 0.888628 + outer loop + vertex 812.668 230.394 355.006 + vertex 804.277 229.456 357.039 + vertex 804.645 224.899 354.986 + endloop + endfacet + facet normal 0.211299 -0.31014 0.926912 + outer loop + vertex 811.974 239.662 358.711 + vertex 803.977 234.165 358.694 + vertex 812.287 234.947 357.062 + endloop + endfacet + facet normal 0.211354 -0.312174 0.926216 + outer loop + vertex 812.287 234.947 357.062 + vertex 803.977 234.165 358.694 + vertex 804.277 229.456 357.039 + endloop + endfacet + facet normal 0.166097 -0.244393 0.955345 + outer loop + vertex 811.728 244.495 359.99 + vertex 803.742 238.997 359.972 + vertex 811.974 239.662 358.711 + endloop + endfacet + facet normal 0.1661 -0.244464 0.955326 + outer loop + vertex 811.974 239.662 358.711 + vertex 803.742 238.997 359.972 + vertex 803.977 234.165 358.694 + endloop + endfacet + facet normal 0.124326 -0.182826 0.975253 + outer loop + vertex 811.542 249.42 360.937 + vertex 803.565 243.915 360.922 + vertex 811.728 244.495 359.99 + endloop + endfacet + facet normal 0.124376 -0.183848 0.975054 + outer loop + vertex 811.728 244.495 359.99 + vertex 803.565 243.915 360.922 + vertex 803.742 238.997 359.972 + endloop + endfacet + facet normal 0.12353 -0.192631 -0.973465 + outer loop + vertex 803.392 193.782 308.217 + vertex 799.907 191.578 308.211 + vertex 804.57 197.178 307.694 + endloop + endfacet + facet normal 0.11521 -0.179358 -0.977015 + outer loop + vertex 796.044 188.484 308.323 + vertex 797.33 191.882 307.851 + vertex 799.907 191.578 308.211 + endloop + endfacet + facet normal 0.114374 -0.185244 -0.976014 + outer loop + vertex 797.33 191.882 307.851 + vertex 804.57 197.178 307.694 + vertex 799.907 191.578 308.211 + endloop + endfacet + facet normal 0.153386 -0.228774 -0.96132 + outer loop + vertex 804.349 192.479 308.68 + vertex 800.677 189.795 308.732 + vertex 803.392 193.782 308.217 + endloop + endfacet + facet normal 0.141598 -0.221209 -0.964892 + outer loop + vertex 803.392 193.782 308.217 + vertex 800.677 189.795 308.732 + vertex 799.907 191.578 308.211 + endloop + endfacet + facet normal 0.146178 -0.219169 -0.964674 + outer loop + vertex 800.677 189.795 308.732 + vertex 796.961 187.159 308.768 + vertex 799.907 191.578 308.211 + endloop + endfacet + facet normal 0.148783 -0.220809 -0.963902 + outer loop + vertex 799.907 191.578 308.211 + vertex 796.961 187.159 308.768 + vertex 796.044 188.484 308.323 + endloop + endfacet + facet normal 0.421821 -0.616168 -0.665135 + outer loop + vertex 802.721 185.775 311.576 + vertex 798.861 183.119 311.588 + vertex 802.134 186.686 310.36 + endloop + endfacet + facet normal 0.428181 -0.619519 -0.657919 + outer loop + vertex 802.134 186.686 310.36 + vertex 798.861 183.119 311.588 + vertex 798.326 184.032 310.38 + endloop + endfacet + facet normal 0.42199 -0.602919 -0.677062 + outer loop + vertex 806.558 188.483 311.556 + vertex 802.721 185.775 311.576 + vertex 805.916 189.405 310.334 + endloop + endfacet + facet normal 0.433124 -0.608553 -0.664881 + outer loop + vertex 805.916 189.405 310.334 + vertex 802.721 185.775 311.576 + vertex 802.134 186.686 310.36 + endloop + endfacet + facet normal 0.556816 -0.829854 -0.0360354 + outer loop + vertex 803.869 185.77 315.04 + vertex 799.908 183.112 315.044 + vertex 803.269 185.451 313.127 + endloop + endfacet + facet normal 0.561372 -0.827192 -0.0248016 + outer loop + vertex 803.269 185.451 313.127 + vertex 799.908 183.112 315.044 + vertex 799.359 182.797 313.134 + endloop + endfacet + facet normal 0.568003 -0.821245 -0.0541322 + outer loop + vertex 807.815 188.5 315.041 + vertex 803.869 185.77 315.04 + vertex 807.159 188.173 313.121 + endloop + endfacet + facet normal 0.57268 -0.818657 -0.0428741 + outer loop + vertex 807.159 188.173 313.121 + vertex 803.869 185.77 315.04 + vertex 803.269 185.451 313.127 + endloop + endfacet + facet normal 0.535039 -0.765527 -0.357354 + outer loop + vertex 807.159 188.173 313.121 + vertex 803.269 185.451 313.127 + vertex 806.558 188.483 311.556 + endloop + endfacet + facet normal 0.53883 -0.766061 -0.350446 + outer loop + vertex 806.558 188.483 311.556 + vertex 803.269 185.451 313.127 + vertex 802.721 185.775 311.576 + endloop + endfacet + facet normal 0.526002 -0.77603 -0.347994 + outer loop + vertex 803.269 185.451 313.127 + vertex 799.359 182.797 313.134 + vertex 802.721 185.775 311.576 + endloop + endfacet + facet normal 0.533651 -0.77713 -0.333596 + outer loop + vertex 802.721 185.775 311.576 + vertex 799.359 182.797 313.134 + vertex 798.861 183.119 311.588 + endloop + endfacet + facet normal 0.527621 -0.776573 0.34431 + outer loop + vertex 805.163 188.327 319.918 + vertex 801.367 185.549 319.47 + vertex 804.569 186.752 317.277 + endloop + endfacet + facet normal 0.522275 -0.785713 0.331487 + outer loop + vertex 804.569 186.752 317.277 + vertex 801.367 185.549 319.47 + vertex 800.557 184.086 317.278 + endloop + endfacet + facet normal 0.522998 -0.786838 0.327656 + outer loop + vertex 809.443 190.985 319.469 + vertex 805.163 188.327 319.918 + vertex 808.565 189.489 317.277 + endloop + endfacet + facet normal 0.530726 -0.775143 0.342759 + outer loop + vertex 808.565 189.489 317.277 + vertex 805.163 188.327 319.918 + vertex 804.569 186.752 317.277 + endloop + endfacet + facet normal 0.556477 -0.812702 0.172768 + outer loop + vertex 808.565 189.489 317.277 + vertex 804.569 186.752 317.277 + vertex 807.815 188.5 315.041 + endloop + endfacet + facet normal 0.559515 -0.809028 0.180048 + outer loop + vertex 807.815 188.5 315.041 + vertex 804.569 186.752 317.277 + vertex 803.869 185.77 315.04 + endloop + endfacet + facet normal 0.543562 -0.817834 0.188914 + outer loop + vertex 804.569 186.752 317.277 + vertex 800.557 184.086 317.278 + vertex 803.869 185.77 315.04 + endloop + endfacet + facet normal 0.546522 -0.814174 0.196047 + outer loop + vertex 803.869 185.77 315.04 + vertex 800.557 184.086 317.278 + vertex 799.908 183.112 315.044 + endloop + endfacet + facet normal 0.489488 -0.742645 0.457034 + outer loop + vertex 801.367 185.549 319.47 + vertex 805.163 188.327 319.918 + vertex 799.18 186.281 323.001 + endloop + endfacet + facet normal 0.506666 -0.741635 0.439622 + outer loop + vertex 809.443 190.985 319.469 + vertex 807.363 191.658 323.001 + vertex 805.163 188.327 319.918 + endloop + endfacet + facet normal 0.488985 -0.744211 0.45502 + outer loop + vertex 807.363 191.658 323.001 + vertex 799.18 186.281 323.001 + vertex 805.163 188.327 319.918 + endloop + endfacet + facet normal 0.382246 -0.589532 0.711576 + outer loop + vertex 806.019 212.377 346.563 + vertex 797.798 207.038 346.555 + vertex 806.584 208.673 343.19 + endloop + endfacet + facet normal 0.382326 -0.588796 0.712142 + outer loop + vertex 806.584 208.673 343.19 + vertex 797.798 207.038 346.555 + vertex 798.353 203.322 343.185 + endloop + endfacet + facet normal 0.357738 -0.551427 0.753626 + outer loop + vertex 805.522 216.342 349.7 + vertex 797.313 211.006 349.692 + vertex 806.019 212.377 346.563 + endloop + endfacet + facet normal 0.357703 -0.551808 0.753364 + outer loop + vertex 806.019 212.377 346.563 + vertex 797.313 211.006 349.692 + vertex 797.798 207.038 346.555 + endloop + endfacet + facet normal 0.327316 -0.504235 0.799132 + outer loop + vertex 805.065 220.525 352.527 + vertex 796.867 215.191 352.518 + vertex 805.522 216.342 349.7 + endloop + endfacet + facet normal 0.327289 -0.504657 0.798876 + outer loop + vertex 805.522 216.342 349.7 + vertex 796.867 215.191 352.518 + vertex 797.313 211.006 349.692 + endloop + endfacet + facet normal 0.290734 -0.447636 0.845633 + outer loop + vertex 804.645 224.899 354.986 + vertex 796.457 219.566 354.978 + vertex 805.065 220.525 352.527 + endloop + endfacet + facet normal 0.290719 -0.448063 0.845413 + outer loop + vertex 805.065 220.525 352.527 + vertex 796.457 219.566 354.978 + vertex 796.867 215.191 352.518 + endloop + endfacet + facet normal 0.247607 -0.381176 0.890728 + outer loop + vertex 804.277 229.456 357.039 + vertex 796.098 224.124 357.031 + vertex 804.645 224.899 354.986 + endloop + endfacet + facet normal 0.247604 -0.381489 0.890594 + outer loop + vertex 804.645 224.899 354.986 + vertex 796.098 224.124 357.031 + vertex 796.457 219.566 354.978 + endloop + endfacet + facet normal 0.20351 -0.313173 0.927635 + outer loop + vertex 803.977 234.165 358.694 + vertex 795.806 228.833 358.687 + vertex 804.277 229.456 357.039 + endloop + endfacet + facet normal 0.203513 -0.313603 0.927489 + outer loop + vertex 804.277 229.456 357.039 + vertex 795.806 228.833 358.687 + vertex 796.098 224.124 357.031 + endloop + endfacet + facet normal 0.159062 -0.245081 0.956365 + outer loop + vertex 803.742 238.997 359.972 + vertex 795.578 233.666 359.963 + vertex 803.977 234.165 358.694 + endloop + endfacet + facet normal 0.159062 -0.245106 0.956359 + outer loop + vertex 803.977 234.165 358.694 + vertex 795.578 233.666 359.963 + vertex 795.806 228.833 358.687 + endloop + endfacet + facet normal 0.119885 -0.184109 0.975567 + outer loop + vertex 803.565 243.915 360.922 + vertex 795.408 238.58 360.917 + vertex 803.742 238.997 359.972 + endloop + endfacet + facet normal 0.119914 -0.185162 0.975364 + outer loop + vertex 803.742 238.997 359.972 + vertex 795.408 238.58 360.917 + vertex 795.578 233.666 359.963 + endloop + endfacet + facet normal 0.117551 -0.180185 -0.976583 + outer loop + vertex 796.044 188.484 308.323 + vertex 792.432 186.341 308.284 + vertex 797.33 191.882 307.851 + endloop + endfacet + facet normal 0.111516 -0.173186 -0.978555 + outer loop + vertex 788.393 183.304 308.361 + vertex 789.77 186.635 307.928 + vertex 792.432 186.341 308.284 + endloop + endfacet + facet normal 0.111303 -0.174795 -0.978294 + outer loop + vertex 789.77 186.635 307.928 + vertex 797.33 191.882 307.851 + vertex 792.432 186.341 308.284 + endloop + endfacet + facet normal 0.146853 -0.222142 -0.963892 + outer loop + vertex 796.961 187.159 308.768 + vertex 793.173 184.55 308.792 + vertex 796.044 188.484 308.323 + endloop + endfacet + facet normal 0.139163 -0.216811 -0.966243 + outer loop + vertex 796.044 188.484 308.323 + vertex 793.173 184.55 308.792 + vertex 792.432 186.341 308.284 + endloop + endfacet + facet normal 0.141071 -0.215995 -0.96615 + outer loop + vertex 793.173 184.55 308.792 + vertex 789.298 181.968 308.804 + vertex 792.432 186.341 308.284 + endloop + endfacet + facet normal 0.147031 -0.22005 -0.964344 + outer loop + vertex 792.432 186.341 308.284 + vertex 789.298 181.968 308.804 + vertex 788.393 183.304 308.361 + endloop + endfacet + facet normal 0.414857 -0.633861 -0.652774 + outer loop + vertex 794.956 180.504 311.595 + vertex 790.989 177.909 311.593 + vertex 794.47 181.423 310.393 + endloop + endfacet + facet normal 0.416722 -0.634942 -0.650531 + outer loop + vertex 794.47 181.423 310.393 + vertex 790.989 177.909 311.593 + vertex 790.545 178.84 310.399 + endloop + endfacet + facet normal 0.41812 -0.625938 -0.658314 + outer loop + vertex 798.861 183.119 311.588 + vertex 794.956 180.504 311.595 + vertex 798.326 184.032 310.38 + endloop + endfacet + facet normal 0.423268 -0.628779 -0.652289 + outer loop + vertex 798.326 184.032 310.38 + vertex 794.956 180.504 311.595 + vertex 794.47 181.423 310.393 + endloop + endfacet + facet normal 0.537662 -0.843159 -0.00133787 + outer loop + vertex 795.913 180.494 315.044 + vertex 791.859 177.909 315.044 + vertex 795.408 180.175 313.134 + endloop + endfacet + facet normal 0.540367 -0.84141 0.00576241 + outer loop + vertex 795.408 180.175 313.134 + vertex 791.859 177.909 315.044 + vertex 791.392 177.596 313.139 + endloop + endfacet + facet normal 0.548073 -0.836204 -0.0194895 + outer loop + vertex 799.908 183.112 315.044 + vertex 795.913 180.494 315.044 + vertex 799.359 182.797 313.134 + endloop + endfacet + facet normal 0.552949 -0.833185 -0.00704749 + outer loop + vertex 799.359 182.797 313.134 + vertex 795.913 180.494 315.044 + vertex 795.408 180.175 313.134 + endloop + endfacet + facet normal 0.521711 -0.786036 -0.331609 + outer loop + vertex 799.359 182.797 313.134 + vertex 795.408 180.175 313.134 + vertex 798.861 183.119 311.588 + endloop + endfacet + facet normal 0.526382 -0.786721 -0.322477 + outer loop + vertex 798.861 183.119 311.588 + vertex 795.408 180.175 313.134 + vertex 794.956 180.504 311.595 + endloop + endfacet + facet normal 0.511611 -0.797246 -0.320396 + outer loop + vertex 795.408 180.175 313.134 + vertex 791.392 177.596 313.139 + vertex 794.956 180.504 311.595 + endloop + endfacet + facet normal 0.522578 -0.79881 -0.298018 + outer loop + vertex 794.956 180.504 311.595 + vertex 791.392 177.596 313.139 + vertex 790.989 177.909 311.593 + endloop + endfacet + facet normal 0.505 -0.783307 0.3625 + outer loop + vertex 797.034 183.012 319.919 + vertex 793.197 180.331 319.471 + vertex 796.523 181.46 317.277 + endloop + endfacet + facet normal 0.50045 -0.791177 0.351552 + outer loop + vertex 796.523 181.46 317.277 + vertex 793.197 180.331 319.471 + vertex 792.44 178.878 317.278 + endloop + endfacet + facet normal 0.500658 -0.793939 0.344968 + outer loop + vertex 801.367 185.549 319.47 + vertex 797.034 183.012 319.919 + vertex 800.557 184.086 317.278 + endloop + endfacet + facet normal 0.508774 -0.781648 0.360797 + outer loop + vertex 800.557 184.086 317.278 + vertex 797.034 183.012 319.919 + vertex 796.523 181.46 317.277 + endloop + endfacet + facet normal 0.534254 -0.820719 0.202467 + outer loop + vertex 800.557 184.086 317.278 + vertex 796.523 181.46 317.277 + vertex 799.908 183.112 315.044 + endloop + endfacet + facet normal 0.536244 -0.818199 0.207346 + outer loop + vertex 799.908 183.112 315.044 + vertex 796.523 181.46 317.277 + vertex 795.913 180.494 315.044 + endloop + endfacet + facet normal 0.522128 -0.825489 0.21436 + outer loop + vertex 796.523 181.46 317.277 + vertex 792.44 178.878 317.278 + vertex 795.913 180.494 315.044 + endloop + endfacet + facet normal 0.52448 -0.822451 0.220214 + outer loop + vertex 795.913 180.494 315.044 + vertex 792.44 178.878 317.278 + vertex 791.859 177.909 315.044 + endloop + endfacet + facet normal 0.46952 -0.749848 0.466132 + outer loop + vertex 793.197 180.331 319.471 + vertex 797.034 183.012 319.919 + vertex 790.903 181.091 323.004 + endloop + endfacet + facet normal 0.484639 -0.74709 0.454952 + outer loop + vertex 801.367 185.549 319.47 + vertex 799.18 186.281 323.001 + vertex 797.034 183.012 319.919 + endloop + endfacet + facet normal 0.469811 -0.748961 0.467263 + outer loop + vertex 799.18 186.281 323.001 + vertex 790.903 181.091 323.004 + vertex 797.034 183.012 319.919 + endloop + endfacet + facet normal 0.369376 -0.593433 0.715121 + outer loop + vertex 797.798 207.038 346.555 + vertex 789.429 201.835 346.561 + vertex 798.353 203.322 343.185 + endloop + endfacet + facet normal 0.36932 -0.593885 0.714775 + outer loop + vertex 798.353 203.322 343.185 + vertex 789.429 201.835 346.561 + vertex 789.978 198.119 343.189 + endloop + endfacet + facet normal 0.345587 -0.55557 0.756249 + outer loop + vertex 797.313 211.006 349.692 + vertex 788.951 205.809 349.695 + vertex 797.798 207.038 346.555 + endloop + endfacet + facet normal 0.345627 -0.555185 0.756513 + outer loop + vertex 797.798 207.038 346.555 + vertex 788.951 205.809 349.695 + vertex 789.429 201.835 346.561 + endloop + endfacet + facet normal 0.316324 -0.507563 0.801448 + outer loop + vertex 796.867 215.191 352.518 + vertex 788.513 209.992 352.524 + vertex 797.313 211.006 349.692 + endloop + endfacet + facet normal 0.316262 -0.508357 0.800969 + outer loop + vertex 797.313 211.006 349.692 + vertex 788.513 209.992 352.524 + vertex 788.951 205.809 349.695 + endloop + endfacet + facet normal 0.280691 -0.450252 0.847636 + outer loop + vertex 796.457 219.566 354.978 + vertex 788.109 214.369 354.982 + vertex 796.867 215.191 352.518 + endloop + endfacet + facet normal 0.280691 -0.45025 0.847636 + outer loop + vertex 796.867 215.191 352.518 + vertex 788.109 214.369 354.982 + vertex 788.513 209.992 352.524 + endloop + endfacet + facet normal 0.239039 -0.382937 0.892312 + outer loop + vertex 796.098 224.124 357.031 + vertex 787.756 218.927 357.035 + vertex 796.457 219.566 354.978 + endloop + endfacet + facet normal 0.239029 -0.383296 0.89216 + outer loop + vertex 796.457 219.566 354.978 + vertex 787.756 218.927 357.035 + vertex 788.109 214.369 354.982 + endloop + endfacet + facet normal 0.195983 -0.314529 0.928796 + outer loop + vertex 795.806 228.833 358.687 + vertex 787.469 223.639 358.687 + vertex 796.098 224.124 357.031 + endloop + endfacet + facet normal 0.195989 -0.31381 0.929038 + outer loop + vertex 796.098 224.124 357.031 + vertex 787.469 223.639 358.687 + vertex 787.756 218.927 357.035 + endloop + endfacet + facet normal 0.154043 -0.245531 0.957071 + outer loop + vertex 795.578 233.666 359.963 + vertex 787.246 228.467 359.971 + vertex 795.806 228.833 358.687 + endloop + endfacet + facet normal 0.15405 -0.24722 0.956635 + outer loop + vertex 795.806 228.833 358.687 + vertex 787.246 228.467 359.971 + vertex 787.469 223.639 358.687 + endloop + endfacet + facet normal 0.115735 -0.185396 0.975825 + outer loop + vertex 795.408 238.58 360.917 + vertex 787.079 233.386 360.918 + vertex 795.578 233.666 359.963 + endloop + endfacet + facet normal 0.11572 -0.184091 0.976073 + outer loop + vertex 795.578 233.666 359.963 + vertex 787.079 233.386 360.918 + vertex 787.246 228.467 359.971 + endloop + endfacet + facet normal 0.110668 -0.172855 -0.97871 + outer loop + vertex 788.393 183.304 308.361 + vertex 784.679 181.236 308.306 + vertex 789.77 186.635 307.928 + endloop + endfacet + facet normal 0.107785 -0.173464 -0.978924 + outer loop + vertex 780.555 178.303 308.372 + vertex 782.073 181.634 307.949 + vertex 784.679 181.236 308.306 + endloop + endfacet + facet normal 0.108276 -0.170645 -0.979365 + outer loop + vertex 782.073 181.634 307.949 + vertex 789.77 186.635 307.928 + vertex 784.679 181.236 308.306 + endloop + endfacet + facet normal 0.142855 -0.22287 -0.964324 + outer loop + vertex 789.298 181.968 308.804 + vertex 785.362 179.421 308.809 + vertex 788.393 183.304 308.361 + endloop + endfacet + facet normal 0.135147 -0.217132 -0.966741 + outer loop + vertex 788.393 183.304 308.361 + vertex 785.362 179.421 308.809 + vertex 784.679 181.236 308.306 + endloop + endfacet + facet normal 0.136314 -0.216676 -0.96668 + outer loop + vertex 785.362 179.421 308.809 + vertex 781.406 176.939 308.808 + vertex 784.679 181.236 308.306 + endloop + endfacet + facet normal 0.141334 -0.220319 -0.965134 + outer loop + vertex 784.679 181.236 308.306 + vertex 781.406 176.939 308.808 + vertex 780.555 178.303 308.372 + endloop + endfacet + facet normal 0.405604 -0.653688 -0.638888 + outer loop + vertex 786.957 175.367 311.6 + vertex 782.903 172.857 311.595 + vertex 786.553 176.288 310.401 + endloop + endfacet + facet normal 0.405932 -0.653892 -0.63847 + outer loop + vertex 786.553 176.288 310.401 + vertex 782.903 172.857 311.595 + vertex 782.53 173.79 310.402 + endloop + endfacet + facet normal 0.403767 -0.642315 -0.651463 + outer loop + vertex 790.989 177.909 311.593 + vertex 786.957 175.367 311.6 + vertex 790.545 178.84 310.399 + endloop + endfacet + facet normal 0.414514 -0.648813 -0.638138 + outer loop + vertex 790.545 178.84 310.399 + vertex 786.957 175.367 311.6 + vertex 786.553 176.288 310.401 + endloop + endfacet + facet normal 0.517046 -0.855574 0.0256225 + outer loop + vertex 787.748 175.354 315.045 + vertex 783.613 172.856 315.049 + vertex 787.319 175.038 313.137 + endloop + endfacet + facet normal 0.521135 -0.852678 0.036852 + outer loop + vertex 787.319 175.038 313.137 + vertex 783.613 172.856 315.049 + vertex 783.224 172.535 313.138 + endloop + endfacet + facet normal 0.527745 -0.849342 0.0101661 + outer loop + vertex 791.859 177.909 315.044 + vertex 787.748 175.354 315.045 + vertex 791.392 177.596 313.139 + endloop + endfacet + facet normal 0.531696 -0.846678 0.020852 + outer loop + vertex 791.392 177.596 313.139 + vertex 787.748 175.354 315.045 + vertex 787.319 175.038 313.137 + endloop + endfacet + facet normal 0.508004 -0.808807 -0.296249 + outer loop + vertex 791.392 177.596 313.139 + vertex 787.319 175.038 313.137 + vertex 790.989 177.909 311.593 + endloop + endfacet + facet normal 0.509435 -0.809009 -0.293223 + outer loop + vertex 790.989 177.909 311.593 + vertex 787.319 175.038 313.137 + vertex 786.957 175.367 311.6 + endloop + endfacet + facet normal 0.49871 -0.816031 -0.2922 + outer loop + vertex 787.319 175.038 313.137 + vertex 783.224 172.535 313.138 + vertex 786.957 175.367 311.6 + endloop + endfacet + facet normal 0.506358 -0.817096 -0.2756 + outer loop + vertex 786.957 175.367 311.6 + vertex 783.224 172.535 313.138 + vertex 782.903 172.857 311.595 + endloop + endfacet + facet normal 0.485781 -0.788797 0.376586 + outer loop + vertex 788.771 177.872 319.921 + vertex 784.864 175.251 319.472 + vertex 788.303 176.322 317.278 + endloop + endfacet + facet normal 0.480751 -0.797538 0.364433 + outer loop + vertex 788.303 176.322 317.278 + vertex 784.864 175.251 319.472 + vertex 784.132 173.807 317.278 + endloop + endfacet + facet normal 0.480478 -0.798286 0.363155 + outer loop + vertex 793.197 180.331 319.471 + vertex 788.771 177.872 319.921 + vertex 792.44 178.878 317.278 + endloop + endfacet + facet normal 0.487029 -0.788277 0.37606 + outer loop + vertex 792.44 178.878 317.278 + vertex 788.771 177.872 319.921 + vertex 788.303 176.322 317.278 + endloop + endfacet + facet normal 0.511983 -0.828687 0.226166 + outer loop + vertex 792.44 178.878 317.278 + vertex 788.303 176.322 317.278 + vertex 791.859 177.909 315.044 + endloop + endfacet + facet normal 0.513612 -0.826543 0.230281 + outer loop + vertex 791.859 177.909 315.044 + vertex 788.303 176.322 317.278 + vertex 787.748 175.354 315.045 + endloop + endfacet + facet normal 0.501714 -0.832295 0.235728 + outer loop + vertex 788.303 176.322 317.278 + vertex 784.132 173.807 317.278 + vertex 787.748 175.354 315.045 + endloop + endfacet + facet normal 0.502555 -0.83118 0.237862 + outer loop + vertex 787.748 175.354 315.045 + vertex 784.132 173.807 317.278 + vertex 783.613 172.856 315.049 + endloop + endfacet + facet normal 0.452 -0.755234 0.474676 + outer loop + vertex 784.864 175.251 319.472 + vertex 788.771 177.872 319.921 + vertex 782.516 176.068 323.007 + endloop + endfacet + facet normal 0.465741 -0.753264 0.464413 + outer loop + vertex 793.197 180.331 319.471 + vertex 790.903 181.091 323.004 + vertex 788.771 177.872 319.921 + endloop + endfacet + facet normal 0.452171 -0.754725 0.475322 + outer loop + vertex 790.903 181.091 323.004 + vertex 782.516 176.068 323.007 + vertex 788.771 177.872 319.921 + endloop + endfacet + facet normal 0.357075 -0.598126 0.717456 + outer loop + vertex 789.429 201.835 346.561 + vertex 780.957 196.786 346.568 + vertex 789.978 198.119 343.189 + endloop + endfacet + facet normal 0.357087 -0.598042 0.71752 + outer loop + vertex 789.978 198.119 343.189 + vertex 780.957 196.786 346.568 + vertex 781.504 193.067 343.196 + endloop + endfacet + facet normal 0.333846 -0.55872 0.759196 + outer loop + vertex 788.951 205.809 349.695 + vertex 780.484 200.761 349.704 + vertex 789.429 201.835 346.561 + endloop + endfacet + facet normal 0.333809 -0.559028 0.758985 + outer loop + vertex 789.429 201.835 346.561 + vertex 780.484 200.761 349.704 + vertex 780.957 196.786 346.568 + endloop + endfacet + facet normal 0.305302 -0.511168 0.803429 + outer loop + vertex 788.513 209.992 352.524 + vertex 780.051 204.948 352.53 + vertex 788.951 205.809 349.695 + endloop + endfacet + facet normal 0.305335 -0.510819 0.803639 + outer loop + vertex 788.951 205.809 349.695 + vertex 780.051 204.948 352.53 + vertex 780.484 200.761 349.704 + endloop + endfacet + facet normal 0.270608 -0.452382 0.849777 + outer loop + vertex 788.109 214.369 354.982 + vertex 779.653 209.323 354.989 + vertex 788.513 209.992 352.524 + endloop + endfacet + facet normal 0.270576 -0.45286 0.849533 + outer loop + vertex 788.513 209.992 352.524 + vertex 779.653 209.323 354.989 + vertex 780.051 204.948 352.53 + endloop + endfacet + facet normal 0.230369 -0.384716 0.893825 + outer loop + vertex 787.756 218.927 357.035 + vertex 779.304 213.881 357.041 + vertex 788.109 214.369 354.982 + endloop + endfacet + facet normal 0.230362 -0.384868 0.893762 + outer loop + vertex 788.109 214.369 354.982 + vertex 779.304 213.881 357.041 + vertex 779.653 209.323 354.989 + endloop + endfacet + facet normal 0.188436 -0.314713 0.930295 + outer loop + vertex 787.469 223.639 358.687 + vertex 779.02 218.594 358.692 + vertex 787.756 218.927 357.035 + endloop + endfacet + facet normal 0.188443 -0.31444 0.930385 + outer loop + vertex 787.756 218.927 357.035 + vertex 779.02 218.594 358.692 + vertex 779.304 213.881 357.041 + endloop + endfacet + facet normal 0.148454 -0.247681 0.957401 + outer loop + vertex 787.246 228.467 359.971 + vertex 778.799 223.422 359.975 + vertex 787.469 223.639 358.687 + endloop + endfacet + facet normal 0.148453 -0.24773 0.957388 + outer loop + vertex 787.469 223.639 358.687 + vertex 778.799 223.422 359.975 + vertex 779.02 218.594 358.692 + endloop + endfacet + facet normal 0.111147 -0.18434 0.976558 + outer loop + vertex 787.079 233.386 360.918 + vertex 778.635 228.338 360.926 + vertex 787.246 228.467 359.971 + endloop + endfacet + facet normal 0.111142 -0.185193 0.976397 + outer loop + vertex 787.246 228.467 359.971 + vertex 778.635 228.338 360.926 + vertex 778.799 223.422 359.975 + endloop + endfacet + facet normal 0.107323 -0.173265 -0.97901 + outer loop + vertex 780.555 178.303 308.372 + vertex 776.821 176.367 308.305 + vertex 782.073 181.634 307.949 + endloop + endfacet + facet normal 0.106033 -0.177357 -0.978418 + outer loop + vertex 772.614 173.555 308.359 + vertex 774.183 176.816 307.938 + vertex 776.821 176.367 308.305 + endloop + endfacet + facet normal 0.106899 -0.172851 -0.97913 + outer loop + vertex 774.183 176.816 307.938 + vertex 782.073 181.634 307.949 + vertex 776.821 176.367 308.305 + endloop + endfacet + facet normal 0.136139 -0.223559 -0.965136 + outer loop + vertex 781.406 176.939 308.808 + vertex 777.45 174.533 308.807 + vertex 780.555 178.303 308.372 + endloop + endfacet + facet normal 0.131129 -0.219618 -0.966733 + outer loop + vertex 780.555 178.303 308.372 + vertex 777.45 174.533 308.807 + vertex 776.821 176.367 308.305 + endloop + endfacet + facet normal 0.131016 -0.219658 -0.966739 + outer loop + vertex 777.45 174.533 308.807 + vertex 773.46 172.181 308.801 + vertex 776.821 176.367 308.305 + endloop + endfacet + facet normal 0.138137 -0.22511 -0.964491 + outer loop + vertex 776.821 176.367 308.305 + vertex 773.46 172.181 308.801 + vertex 772.614 173.555 308.359 + endloop + endfacet + facet normal 0.392722 -0.671085 -0.62882 + outer loop + vertex 778.851 170.435 311.599 + vertex 774.792 168.062 311.597 + vertex 778.51 171.359 310.401 + endloop + endfacet + facet normal 0.393814 -0.671794 -0.627378 + outer loop + vertex 778.51 171.359 310.401 + vertex 774.792 168.062 311.597 + vertex 774.479 168.996 310.4 + endloop + endfacet + facet normal 0.39385 -0.660155 -0.639592 + outer loop + vertex 782.903 172.857 311.595 + vertex 778.851 170.435 311.599 + vertex 782.53 173.79 310.402 + endloop + endfacet + facet normal 0.40298 -0.665955 -0.627783 + outer loop + vertex 782.53 173.79 310.402 + vertex 778.851 170.435 311.599 + vertex 778.51 171.359 310.401 + endloop + endfacet + facet normal 0.499304 -0.865214 0.0458217 + outer loop + vertex 779.491 170.407 315.046 + vertex 775.379 168.034 315.046 + vertex 779.143 170.105 313.139 + endloop + endfacet + facet normal 0.50093 -0.864023 0.0503245 + outer loop + vertex 779.143 170.105 313.139 + vertex 775.379 168.034 315.046 + vertex 775.057 167.736 313.14 + endloop + endfacet + facet normal 0.510246 -0.859091 0.0401413 + outer loop + vertex 783.613 172.856 315.049 + vertex 779.491 170.407 315.046 + vertex 783.224 172.535 313.138 + endloop + endfacet + facet normal 0.51113 -0.858447 0.042591 + outer loop + vertex 783.224 172.535 313.138 + vertex 779.491 170.407 315.046 + vertex 779.143 170.105 313.139 + endloop + endfacet + facet normal 0.491877 -0.826262 -0.274496 + outer loop + vertex 783.224 172.535 313.138 + vertex 779.143 170.105 313.139 + vertex 782.903 172.857 311.595 + endloop + endfacet + facet normal 0.493672 -0.826496 -0.270541 + outer loop + vertex 782.903 172.857 311.595 + vertex 779.143 170.105 313.139 + vertex 778.851 170.435 311.599 + endloop + endfacet + facet normal 0.482894 -0.833045 -0.269905 + outer loop + vertex 779.143 170.105 313.139 + vertex 775.057 167.736 313.14 + vertex 778.851 170.435 311.599 + endloop + endfacet + facet normal 0.487537 -0.833643 -0.259514 + outer loop + vertex 778.851 170.435 311.599 + vertex 775.057 167.736 313.14 + vertex 774.792 168.062 311.597 + endloop + endfacet + facet normal 0.467941 -0.794075 0.387911 + outer loop + vertex 780.385 172.892 319.921 + vertex 776.484 170.374 319.472 + vertex 779.97 171.357 317.28 + endloop + endfacet + facet normal 0.462179 -0.803904 0.374339 + outer loop + vertex 779.97 171.357 317.28 + vertex 776.484 170.374 319.472 + vertex 775.821 168.972 317.28 + endloop + endfacet + facet normal 0.461131 -0.804071 0.375271 + outer loop + vertex 784.864 175.251 319.472 + vertex 780.385 172.892 319.921 + vertex 784.132 173.807 317.278 + endloop + endfacet + facet normal 0.467695 -0.794174 0.388007 + outer loop + vertex 784.132 173.807 317.278 + vertex 780.385 172.892 319.921 + vertex 779.97 171.357 317.28 + endloop + endfacet + facet normal 0.492273 -0.836029 0.242329 + outer loop + vertex 784.132 173.807 317.278 + vertex 779.97 171.357 317.28 + vertex 783.613 172.856 315.049 + endloop + endfacet + facet normal 0.494551 -0.832988 0.248095 + outer loop + vertex 783.613 172.856 315.049 + vertex 779.97 171.357 317.28 + vertex 779.491 170.407 315.046 + endloop + endfacet + facet normal 0.48217 -0.838697 0.25318 + outer loop + vertex 779.97 171.357 317.28 + vertex 775.821 168.972 317.28 + vertex 779.491 170.407 315.046 + endloop + endfacet + facet normal 0.483222 -0.837291 0.255813 + outer loop + vertex 779.491 170.407 315.046 + vertex 775.821 168.972 317.28 + vertex 775.379 168.034 315.046 + endloop + endfacet + facet normal 0.435319 -0.760333 0.482069 + outer loop + vertex 776.484 170.374 319.472 + vertex 780.385 172.892 319.921 + vertex 774.067 171.229 323.004 + endloop + endfacet + facet normal 0.447332 -0.759349 0.472528 + outer loop + vertex 784.864 175.251 319.472 + vertex 782.516 176.068 323.007 + vertex 780.385 172.892 319.921 + endloop + endfacet + facet normal 0.435287 -0.760425 0.481954 + outer loop + vertex 782.516 176.068 323.007 + vertex 774.067 171.229 323.004 + vertex 780.385 172.892 319.921 + endloop + endfacet + facet normal 0.344585 -0.602237 0.720119 + outer loop + vertex 780.957 196.786 346.568 + vertex 772.43 191.907 346.568 + vertex 781.504 193.067 343.196 + endloop + endfacet + facet normal 0.344727 -0.601321 0.720816 + outer loop + vertex 781.504 193.067 343.196 + vertex 772.43 191.907 346.568 + vertex 772.975 188.179 343.198 + endloop + endfacet + facet normal 0.322278 -0.562377 0.761491 + outer loop + vertex 780.484 200.761 349.704 + vertex 771.961 195.88 349.706 + vertex 780.957 196.786 346.568 + endloop + endfacet + facet normal 0.322181 -0.563089 0.761006 + outer loop + vertex 780.957 196.786 346.568 + vertex 771.961 195.88 349.706 + vertex 772.43 191.907 346.568 + endloop + endfacet + facet normal 0.294714 -0.513456 0.805919 + outer loop + vertex 780.051 204.948 352.53 + vertex 771.535 200.066 352.534 + vertex 780.484 200.761 349.704 + endloop + endfacet + facet normal 0.294642 -0.514108 0.805531 + outer loop + vertex 780.484 200.761 349.704 + vertex 771.535 200.066 352.534 + vertex 771.961 195.88 349.706 + endloop + endfacet + facet normal 0.260941 -0.454837 0.851489 + outer loop + vertex 779.653 209.323 354.989 + vertex 771.142 204.444 354.991 + vertex 780.051 204.948 352.53 + endloop + endfacet + facet normal 0.260966 -0.454542 0.851638 + outer loop + vertex 780.051 204.948 352.53 + vertex 771.142 204.444 354.991 + vertex 771.535 200.066 352.534 + endloop + endfacet + facet normal 0.222157 -0.386176 0.895273 + outer loop + vertex 779.304 213.881 357.041 + vertex 770.798 208.998 357.046 + vertex 779.653 209.323 354.989 + endloop + endfacet + facet normal 0.222102 -0.387076 0.894898 + outer loop + vertex 779.653 209.323 354.989 + vertex 770.798 208.998 357.046 + vertex 771.142 204.444 354.991 + endloop + endfacet + facet normal 0.181513 -0.315245 0.93149 + outer loop + vertex 779.02 218.594 358.692 + vertex 770.517 213.71 358.696 + vertex 779.304 213.881 357.041 + endloop + endfacet + facet normal 0.18151 -0.315329 0.931462 + outer loop + vertex 779.304 213.881 357.041 + vertex 770.517 213.71 358.696 + vertex 770.798 208.998 357.046 + endloop + endfacet + facet normal 0.143125 -0.24816 0.958088 + outer loop + vertex 778.799 223.422 359.975 + vertex 770.298 218.538 359.98 + vertex 779.02 218.594 358.692 + endloop + endfacet + facet normal 0.143118 -0.248368 0.958035 + outer loop + vertex 779.02 218.594 358.692 + vertex 770.298 218.538 359.98 + vertex 770.517 213.71 358.696 + endloop + endfacet + facet normal 0.106708 -0.185428 0.976847 + outer loop + vertex 778.635 228.338 360.926 + vertex 770.137 223.458 360.928 + vertex 778.799 223.422 359.975 + endloop + endfacet + facet normal 0.106724 -0.184778 0.976968 + outer loop + vertex 778.799 223.422 359.975 + vertex 770.137 223.458 360.928 + vertex 770.298 218.538 359.98 + endloop + endfacet + facet normal 0.107376 -0.17797 -0.97816 + outer loop + vertex 772.614 173.555 308.359 + vertex 768.729 171.665 308.276 + vertex 774.183 176.816 307.938 + endloop + endfacet + facet normal 0.109193 -0.184284 -0.976789 + outer loop + vertex 764.308 168.877 308.308 + vertex 766.037 172.122 307.889 + vertex 768.729 171.665 308.276 + endloop + endfacet + facet normal 0.109905 -0.180598 -0.977397 + outer loop + vertex 766.037 172.122 307.889 + vertex 774.183 176.816 307.938 + vertex 768.729 171.665 308.276 + endloop + endfacet + facet normal 0.133219 -0.228131 -0.964473 + outer loop + vertex 773.46 172.181 308.801 + vertex 769.371 169.843 308.789 + vertex 772.614 173.555 308.359 + endloop + endfacet + facet normal 0.130324 -0.225714 -0.965437 + outer loop + vertex 772.614 173.555 308.359 + vertex 769.371 169.843 308.789 + vertex 768.729 171.665 308.276 + endloop + endfacet + facet normal 0.130838 -0.225525 -0.965412 + outer loop + vertex 769.371 169.843 308.789 + vertex 765.163 167.503 308.765 + vertex 768.729 171.665 308.276 + endloop + endfacet + facet normal 0.14006 -0.233064 -0.962323 + outer loop + vertex 768.729 171.665 308.276 + vertex 765.163 167.503 308.765 + vertex 764.308 168.877 308.308 + endloop + endfacet + facet normal 0.379231 -0.68563 -0.621366 + outer loop + vertex 770.67 165.727 311.598 + vertex 766.45 163.394 311.596 + vertex 770.382 166.658 310.395 + endloop + endfacet + facet normal 0.383087 -0.688306 -0.616019 + outer loop + vertex 770.382 166.658 310.395 + vertex 766.45 163.394 311.596 + vertex 766.178 164.325 310.387 + endloop + endfacet + facet normal 0.38325 -0.676813 -0.628526 + outer loop + vertex 774.792 168.062 311.597 + vertex 770.67 165.727 311.598 + vertex 774.479 168.996 310.4 + endloop + endfacet + facet normal 0.389429 -0.680959 -0.620193 + outer loop + vertex 774.479 168.996 310.4 + vertex 770.67 165.727 311.598 + vertex 770.382 166.658 310.395 + endloop + endfacet + facet normal 0.482231 -0.873673 0.0644179 + outer loop + vertex 771.219 165.703 315.052 + vertex 766.963 163.353 315.047 + vertex 770.914 165.393 313.139 + endloop + endfacet + facet normal 0.481785 -0.874012 0.0631315 + outer loop + vertex 770.914 165.393 313.139 + vertex 766.963 163.353 315.047 + vertex 766.671 163.055 313.139 + endloop + endfacet + facet normal 0.488289 -0.871037 0.0535539 + outer loop + vertex 775.379 168.034 315.046 + vertex 771.219 165.703 315.052 + vertex 775.057 167.736 313.14 + endloop + endfacet + facet normal 0.491358 -0.868737 0.0621606 + outer loop + vertex 775.057 167.736 313.14 + vertex 771.219 165.703 315.052 + vertex 770.914 165.393 313.139 + endloop + endfacet + facet normal 0.475578 -0.840695 -0.258955 + outer loop + vertex 775.057 167.736 313.14 + vertex 770.914 165.393 313.139 + vertex 774.792 168.062 311.597 + endloop + endfacet + facet normal 0.476243 -0.840785 -0.257436 + outer loop + vertex 774.792 168.062 311.597 + vertex 770.914 165.393 313.139 + vertex 770.67 165.727 311.598 + endloop + endfacet + facet normal 0.466532 -0.846313 -0.257102 + outer loop + vertex 770.914 165.393 313.139 + vertex 766.671 163.055 313.139 + vertex 770.67 165.727 311.598 + endloop + endfacet + facet normal 0.468025 -0.84654 -0.253621 + outer loop + vertex 770.67 165.727 311.598 + vertex 766.671 163.055 313.139 + vertex 766.45 163.394 311.596 + endloop + endfacet + facet normal 0.448794 -0.801458 0.395284 + outer loop + vertex 771.996 168.124 319.921 + vertex 768.051 165.693 319.472 + vertex 771.648 166.626 317.28 + endloop + endfacet + facet normal 0.443867 -0.809816 0.383641 + outer loop + vertex 771.648 166.626 317.28 + vertex 768.051 165.693 319.472 + vertex 767.394 164.296 317.282 + endloop + endfacet + facet normal 0.444275 -0.80968 0.383454 + outer loop + vertex 776.484 170.374 319.472 + vertex 771.996 168.124 319.921 + vertex 775.821 168.972 317.28 + endloop + endfacet + facet normal 0.450168 -0.800925 0.394801 + outer loop + vertex 775.821 168.972 317.28 + vertex 771.996 168.124 319.921 + vertex 771.648 166.626 317.28 + endloop + endfacet + facet normal 0.473159 -0.841827 0.259709 + outer loop + vertex 775.821 168.972 317.28 + vertex 771.648 166.626 317.28 + vertex 775.379 168.034 315.046 + endloop + endfacet + facet normal 0.472599 -0.842573 0.258305 + outer loop + vertex 775.379 168.034 315.046 + vertex 771.648 166.626 317.28 + vertex 771.219 165.703 315.052 + endloop + endfacet + facet normal 0.463866 -0.846408 0.261575 + outer loop + vertex 771.648 166.626 317.28 + vertex 767.394 164.296 317.282 + vertex 771.219 165.703 315.052 + endloop + endfacet + facet normal 0.465636 -0.844016 0.266121 + outer loop + vertex 771.219 165.703 315.052 + vertex 767.394 164.296 317.282 + vertex 766.963 163.353 315.047 + endloop + endfacet + facet normal 0.41925 -0.769473 0.48181 + outer loop + vertex 768.051 165.693 319.472 + vertex 771.996 168.124 319.921 + vertex 765.576 166.556 323.004 + endloop + endfacet + facet normal 0.431053 -0.764035 0.480045 + outer loop + vertex 776.484 170.374 319.472 + vertex 774.067 171.229 323.004 + vertex 771.996 168.124 319.921 + endloop + endfacet + facet normal 0.420933 -0.764852 0.487665 + outer loop + vertex 774.067 171.229 323.004 + vertex 765.576 166.556 323.004 + vertex 771.996 168.124 319.921 + endloop + endfacet + facet normal 0.333601 -0.60494 0.72302 + outer loop + vertex 772.43 191.907 346.568 + vertex 763.894 187.194 346.563 + vertex 772.975 188.179 343.198 + endloop + endfacet + facet normal 0.333532 -0.605343 0.722715 + outer loop + vertex 772.975 188.179 343.198 + vertex 763.894 187.194 346.563 + vertex 764.435 183.467 343.192 + endloop + endfacet + facet normal 0.312893 -0.565708 0.762936 + outer loop + vertex 771.961 195.88 349.706 + vertex 763.429 191.16 349.706 + vertex 772.43 191.907 346.568 + endloop + endfacet + facet normal 0.312681 -0.567088 0.761999 + outer loop + vertex 772.43 191.907 346.568 + vertex 763.429 191.16 349.706 + vertex 763.894 187.194 346.563 + endloop + endfacet + facet normal 0.285328 -0.516351 0.807446 + outer loop + vertex 771.535 200.066 352.534 + vertex 763.008 195.352 352.532 + vertex 771.961 195.88 349.706 + endloop + endfacet + facet normal 0.285379 -0.51596 0.807678 + outer loop + vertex 771.961 195.88 349.706 + vertex 763.008 195.352 352.532 + vertex 763.429 191.16 349.706 + endloop + endfacet + facet normal 0.253063 -0.456116 0.853181 + outer loop + vertex 771.142 204.444 354.991 + vertex 762.621 199.725 354.996 + vertex 771.535 200.066 352.534 + endloop + endfacet + facet normal 0.2529 -0.45772 0.85237 + outer loop + vertex 771.535 200.066 352.534 + vertex 762.621 199.725 354.996 + vertex 763.008 195.352 352.532 + endloop + endfacet + facet normal 0.214844 -0.388204 0.896181 + outer loop + vertex 770.798 208.998 357.046 + vertex 762.284 204.285 357.045 + vertex 771.142 204.444 354.991 + endloop + endfacet + facet normal 0.214922 -0.387197 0.896597 + outer loop + vertex 771.142 204.444 354.991 + vertex 762.284 204.285 357.045 + vertex 762.621 199.725 354.996 + endloop + endfacet + facet normal 0.175883 -0.315967 0.932325 + outer loop + vertex 770.517 213.71 358.696 + vertex 762.007 208.992 358.702 + vertex 770.798 208.998 357.046 + endloop + endfacet + facet normal 0.175781 -0.317641 0.931775 + outer loop + vertex 770.798 208.998 357.046 + vertex 762.007 208.992 358.702 + vertex 762.284 204.285 357.045 + endloop + endfacet + facet normal 0.13757 -0.248806 0.958734 + outer loop + vertex 770.298 218.538 359.98 + vertex 761.794 213.827 359.978 + vertex 770.517 213.71 358.696 + endloop + endfacet + facet normal 0.137662 -0.246992 0.959189 + outer loop + vertex 770.517 213.71 358.696 + vertex 761.794 213.827 359.978 + vertex 762.007 208.992 358.702 + endloop + endfacet + facet normal 0.102763 -0.184982 0.977354 + outer loop + vertex 770.137 223.458 360.928 + vertex 761.638 218.747 360.93 + vertex 770.298 218.538 359.98 + endloop + endfacet + facet normal 0.102722 -0.185902 0.977184 + outer loop + vertex 770.298 218.538 359.98 + vertex 761.638 218.747 360.93 + vertex 761.794 213.827 359.978 + endloop + endfacet + facet normal 0.112502 -0.185958 -0.976096 + outer loop + vertex 764.308 168.877 308.308 + vertex 760.282 167.008 308.2 + vertex 766.037 172.122 307.889 + endloop + endfacet + facet normal 0.118408 -0.19522 -0.973585 + outer loop + vertex 755.79 164.305 308.196 + vertex 757.602 167.558 307.764 + vertex 760.282 167.008 308.2 + endloop + endfacet + facet normal 0.118915 -0.193046 -0.973957 + outer loop + vertex 757.602 167.558 307.764 + vertex 766.037 172.122 307.889 + vertex 760.282 167.008 308.2 + endloop + endfacet + facet normal 0.135863 -0.235664 -0.962291 + outer loop + vertex 765.163 167.503 308.765 + vertex 760.885 165.177 308.731 + vertex 764.308 168.877 308.308 + endloop + endfacet + facet normal 0.134766 -0.234694 -0.962682 + outer loop + vertex 764.308 168.877 308.308 + vertex 760.885 165.177 308.731 + vertex 760.282 167.008 308.2 + endloop + endfacet + facet normal 0.135346 -0.234493 -0.96265 + outer loop + vertex 760.885 165.177 308.731 + vertex 756.606 162.905 308.683 + vertex 760.282 167.008 308.2 + endloop + endfacet + facet normal 0.149091 -0.246225 -0.957677 + outer loop + vertex 760.282 167.008 308.2 + vertex 756.606 162.905 308.683 + vertex 755.79 164.305 308.196 + endloop + endfacet + facet normal 0.368861 -0.696437 -0.615563 + outer loop + vertex 762.153 161.069 311.589 + vertex 757.848 158.795 311.582 + vertex 761.888 162.002 310.375 + endloop + endfacet + facet normal 0.374408 -0.700438 -0.607623 + outer loop + vertex 761.888 162.002 310.375 + vertex 757.848 158.795 311.582 + vertex 757.589 159.722 310.354 + endloop + endfacet + facet normal 0.375355 -0.691747 -0.616924 + outer loop + vertex 766.45 163.394 311.596 + vertex 762.153 161.069 311.589 + vertex 766.178 164.325 310.387 + endloop + endfacet + facet normal 0.376983 -0.69291 -0.614622 + outer loop + vertex 766.178 164.325 310.387 + vertex 762.153 161.069 311.589 + vertex 761.888 162.002 310.375 + endloop + endfacet + facet normal 0.466842 -0.881225 0.074167 + outer loop + vertex 762.628 161.031 315.053 + vertex 758.286 158.73 315.047 + vertex 762.355 160.725 313.136 + endloop + endfacet + facet normal 0.465493 -0.882262 0.0702134 + outer loop + vertex 762.355 160.725 313.136 + vertex 758.286 158.73 315.047 + vertex 758.036 158.445 313.134 + endloop + endfacet + facet normal 0.471341 -0.879509 0.065587 + outer loop + vertex 766.963 163.353 315.047 + vertex 762.628 161.031 315.053 + vertex 766.671 163.055 313.139 + endloop + endfacet + facet normal 0.473744 -0.877663 0.0726153 + outer loop + vertex 766.671 163.055 313.139 + vertex 762.628 161.031 315.053 + vertex 762.355 160.725 313.136 + endloop + endfacet + facet normal 0.459651 -0.851168 -0.253442 + outer loop + vertex 766.671 163.055 313.139 + vertex 762.355 160.725 313.136 + vertex 766.45 163.394 311.596 + endloop + endfacet + facet normal 0.461145 -0.851411 -0.24989 + outer loop + vertex 766.45 163.394 311.596 + vertex 762.355 160.725 313.136 + vertex 762.153 161.069 311.589 + endloop + endfacet + facet normal 0.451972 -0.856345 -0.24979 + outer loop + vertex 762.355 160.725 313.136 + vertex 758.036 158.445 313.134 + vertex 762.153 161.069 311.589 + endloop + endfacet + facet normal 0.452745 -0.856472 -0.247946 + outer loop + vertex 762.153 161.069 311.589 + vertex 758.036 158.445 313.134 + vertex 757.848 158.795 311.582 + endloop + endfacet + facet normal 0.434978 -0.806832 0.39977 + outer loop + vertex 763.444 163.475 319.92 + vertex 759.396 161.072 319.472 + vertex 763.057 161.959 317.281 + endloop + endfacet + facet normal 0.429701 -0.815656 0.38738 + outer loop + vertex 763.057 161.959 317.281 + vertex 759.396 161.072 319.472 + vertex 758.705 159.667 317.282 + endloop + endfacet + facet normal 0.42985 -0.814062 0.390553 + outer loop + vertex 768.051 165.693 319.472 + vertex 763.444 163.475 319.92 + vertex 767.394 164.296 317.282 + endloop + endfacet + facet normal 0.434617 -0.806963 0.399898 + outer loop + vertex 767.394 164.296 317.282 + vertex 763.444 163.475 319.92 + vertex 763.057 161.959 317.281 + endloop + endfacet + facet normal 0.456663 -0.847848 0.269468 + outer loop + vertex 767.394 164.296 317.282 + vertex 763.057 161.959 317.281 + vertex 766.963 163.353 315.047 + endloop + endfacet + facet normal 0.455489 -0.849441 0.266421 + outer loop + vertex 766.963 163.353 315.047 + vertex 763.057 161.959 317.281 + vertex 762.628 161.031 315.053 + endloop + endfacet + facet normal 0.448903 -0.852183 0.268831 + outer loop + vertex 763.057 161.959 317.281 + vertex 758.705 159.667 317.282 + vertex 762.628 161.031 315.053 + endloop + endfacet + facet normal 0.450236 -0.850385 0.272276 + outer loop + vertex 762.628 161.031 315.053 + vertex 758.705 159.667 317.282 + vertex 758.286 158.73 315.047 + endloop + endfacet + facet normal 0.406151 -0.774223 0.485406 + outer loop + vertex 759.396 161.072 319.472 + vertex 763.444 163.475 319.92 + vertex 756.99 162.023 323.004 + endloop + endfacet + facet normal 0.417779 -0.770725 0.481086 + outer loop + vertex 768.051 165.693 319.472 + vertex 765.576 166.556 323.004 + vertex 763.444 163.475 319.92 + endloop + endfacet + facet normal 0.407237 -0.771374 0.489021 + outer loop + vertex 765.576 166.556 323.004 + vertex 756.99 162.023 323.004 + vertex 763.444 163.475 319.92 + endloop + endfacet + facet normal 0.323376 -0.608552 0.724632 + outer loop + vertex 763.894 187.194 346.563 + vertex 755.378 182.664 346.56 + vertex 764.435 183.467 343.192 + endloop + endfacet + facet normal 0.323347 -0.608706 0.724516 + outer loop + vertex 764.435 183.467 343.192 + vertex 755.378 182.664 346.56 + vertex 755.91 178.935 343.188 + endloop + endfacet + facet normal 0.302815 -0.569799 0.763959 + outer loop + vertex 763.429 191.16 349.706 + vertex 754.92 186.63 349.7 + vertex 763.894 187.194 346.563 + endloop + endfacet + facet normal 0.302799 -0.56989 0.763897 + outer loop + vertex 763.894 187.194 346.563 + vertex 754.92 186.63 349.7 + vertex 755.378 182.664 346.56 + endloop + endfacet + facet normal 0.276099 -0.518129 0.809513 + outer loop + vertex 763.008 195.352 352.532 + vertex 754.501 190.813 352.528 + vertex 763.429 191.16 349.706 + endloop + endfacet + facet normal 0.27592 -0.519346 0.808794 + outer loop + vertex 763.429 191.16 349.706 + vertex 754.501 190.813 352.528 + vertex 754.92 186.63 349.7 + endloop + endfacet + facet normal 0.244231 -0.459401 0.853992 + outer loop + vertex 762.621 199.725 354.996 + vertex 754.116 195.189 354.987 + vertex 763.008 195.352 352.532 + endloop + endfacet + facet normal 0.244325 -0.458619 0.854385 + outer loop + vertex 763.008 195.352 352.532 + vertex 754.116 195.189 354.987 + vertex 754.501 190.813 352.528 + endloop + endfacet + facet normal 0.206865 -0.388407 0.897968 + outer loop + vertex 762.284 204.285 357.045 + vertex 753.783 199.749 357.042 + vertex 762.621 199.725 354.996 + endloop + endfacet + facet normal 0.20678 -0.389272 0.897613 + outer loop + vertex 762.621 199.725 354.996 + vertex 753.783 199.749 357.042 + vertex 754.116 195.189 354.987 + endloop + endfacet + facet normal 0.169603 -0.318325 0.932686 + outer loop + vertex 762.007 208.992 358.702 + vertex 753.516 204.461 358.7 + vertex 762.284 204.285 357.045 + endloop + endfacet + facet normal 0.169583 -0.318572 0.932606 + outer loop + vertex 762.284 204.285 357.045 + vertex 753.516 204.461 358.7 + vertex 753.783 199.749 357.042 + endloop + endfacet + facet normal 0.13216 -0.24741 0.959855 + outer loop + vertex 761.794 213.827 359.978 + vertex 753.312 209.299 359.979 + vertex 762.007 208.992 358.702 + endloop + endfacet + facet normal 0.132112 -0.248079 0.959689 + outer loop + vertex 762.007 208.992 358.702 + vertex 753.312 209.299 359.979 + vertex 753.516 204.461 358.7 + endloop + endfacet + facet normal 0.0992656 -0.186074 0.977508 + outer loop + vertex 761.638 218.747 360.93 + vertex 753.165 214.224 360.93 + vertex 761.794 213.827 359.978 + endloop + endfacet + facet normal 0.0992826 -0.185817 0.977556 + outer loop + vertex 761.794 213.827 359.978 + vertex 753.165 214.224 360.93 + vertex 753.312 209.299 359.979 + endloop + endfacet + facet normal 0.124334 -0.198339 -0.972215 + outer loop + vertex 755.79 164.305 308.196 + vertex 751.802 162.56 308.042 + vertex 757.602 167.558 307.764 + endloop + endfacet + facet normal 0.133387 -0.212339 -0.96805 + outer loop + vertex 747.343 159.982 307.993 + vertex 749.04 163.118 307.539 + vertex 751.802 162.56 308.042 + endloop + endfacet + facet normal 0.134071 -0.209439 -0.968587 + outer loop + vertex 749.04 163.118 307.539 + vertex 757.602 167.558 307.764 + vertex 751.802 162.56 308.042 + endloop + endfacet + facet normal 0.144782 -0.24874 -0.957688 + outer loop + vertex 756.606 162.905 308.683 + vertex 752.376 160.709 308.614 + vertex 755.79 164.305 308.196 + endloop + endfacet + facet normal 0.146449 -0.250248 -0.957042 + outer loop + vertex 755.79 164.305 308.196 + vertex 752.376 160.709 308.614 + vertex 751.802 162.56 308.042 + endloop + endfacet + facet normal 0.147127 -0.250024 -0.956996 + outer loop + vertex 752.376 160.709 308.614 + vertex 748.176 158.582 308.524 + vertex 751.802 162.56 308.042 + endloop + endfacet + facet normal 0.162831 -0.263582 -0.950795 + outer loop + vertex 751.802 162.56 308.042 + vertex 748.176 158.582 308.524 + vertex 747.343 159.982 307.993 + endloop + endfacet + facet normal 0.362389 -0.705736 -0.608779 + outer loop + vertex 753.591 156.582 311.563 + vertex 749.385 154.442 311.541 + vertex 753.337 157.519 310.326 + endloop + endfacet + facet normal 0.364022 -0.706909 -0.606439 + outer loop + vertex 753.337 157.519 310.326 + vertex 749.385 154.442 311.541 + vertex 749.132 155.385 310.289 + endloop + endfacet + facet normal 0.368187 -0.703116 -0.608331 + outer loop + vertex 757.848 158.795 311.582 + vertex 753.591 156.582 311.563 + vertex 757.589 159.722 310.354 + endloop + endfacet + facet normal 0.368344 -0.703229 -0.608106 + outer loop + vertex 757.589 159.722 310.354 + vertex 753.591 156.582 311.563 + vertex 753.337 157.519 310.326 + endloop + endfacet + facet normal 0.449949 -0.889637 0.0780463 + outer loop + vertex 754.011 156.528 315.05 + vertex 749.803 154.399 315.051 + vertex 753.773 156.238 313.128 + endloop + endfacet + facet normal 0.450379 -0.889314 0.0792434 + outer loop + vertex 753.773 156.238 313.128 + vertex 749.803 154.399 315.051 + vertex 749.567 154.107 313.121 + endloop + endfacet + facet normal 0.45683 -0.886635 0.0719979 + outer loop + vertex 758.286 158.73 315.047 + vertex 754.011 156.528 315.05 + vertex 758.036 158.445 313.134 + endloop + endfacet + facet normal 0.458363 -0.885477 0.0763766 + outer loop + vertex 758.036 158.445 313.134 + vertex 754.011 156.528 315.05 + vertex 753.773 156.238 313.128 + endloop + endfacet + facet normal 0.445719 -0.860155 -0.247928 + outer loop + vertex 758.036 158.445 313.134 + vertex 753.773 156.238 313.128 + vertex 757.848 158.795 311.582 + endloop + endfacet + facet normal 0.448478 -0.860586 -0.241368 + outer loop + vertex 757.848 158.795 311.582 + vertex 753.773 156.238 313.128 + vertex 753.591 156.582 311.563 + endloop + endfacet + facet normal 0.438851 -0.865543 -0.241339 + outer loop + vertex 753.773 156.238 313.128 + vertex 749.567 154.107 313.121 + vertex 753.591 156.582 311.563 + endloop + endfacet + facet normal 0.44197 -0.865979 -0.233972 + outer loop + vertex 753.591 156.582 311.563 + vertex 749.567 154.107 313.121 + vertex 749.385 154.442 311.541 + endloop + endfacet + facet normal 0.421025 -0.811984 0.404252 + outer loop + vertex 754.793 158.954 319.921 + vertex 750.819 156.671 319.475 + vertex 754.405 157.438 317.281 + endloop + endfacet + facet normal 0.415974 -0.819972 0.393207 + outer loop + vertex 754.405 157.438 317.281 + vertex 750.819 156.671 319.475 + vertex 750.178 155.295 317.282 + endloop + endfacet + facet normal 0.415529 -0.819626 0.394396 + outer loop + vertex 759.396 161.072 319.472 + vertex 754.793 158.954 319.921 + vertex 758.705 159.667 317.282 + endloop + endfacet + facet normal 0.420837 -0.81205 0.404317 + outer loop + vertex 758.705 159.667 317.282 + vertex 754.793 158.954 319.921 + vertex 754.405 157.438 317.281 + endloop + endfacet + facet normal 0.44241 -0.853582 0.275085 + outer loop + vertex 758.705 159.667 317.282 + vertex 754.405 157.438 317.281 + vertex 758.286 158.73 315.047 + endloop + endfacet + facet normal 0.440946 -0.855507 0.27143 + outer loop + vertex 758.286 158.73 315.047 + vertex 754.405 157.438 317.281 + vertex 754.011 156.528 315.05 + endloop + endfacet + facet normal 0.435141 -0.857846 0.273409 + outer loop + vertex 754.405 157.438 317.281 + vertex 750.178 155.295 317.282 + vertex 754.011 156.528 315.05 + endloop + endfacet + facet normal 0.434379 -0.858817 0.271565 + outer loop + vertex 754.011 156.528 315.05 + vertex 750.178 155.295 317.282 + vertex 749.803 154.399 315.051 + endloop + endfacet + facet normal 0.392849 -0.779306 0.488212 + outer loop + vertex 750.819 156.671 319.475 + vertex 754.793 158.954 319.921 + vertex 748.383 157.66 323.014 + endloop + endfacet + facet normal 0.404155 -0.775845 0.484483 + outer loop + vertex 759.396 161.072 319.472 + vertex 756.99 162.023 323.004 + vertex 754.793 158.954 319.921 + endloop + endfacet + facet normal 0.39409 -0.776254 0.49206 + outer loop + vertex 756.99 162.023 323.004 + vertex 748.383 157.66 323.014 + vertex 754.793 158.954 319.921 + endloop + endfacet + facet normal 0.312781 -0.611941 0.726427 + outer loop + vertex 755.378 182.664 346.56 + vertex 746.811 178.303 346.574 + vertex 755.91 178.935 343.188 + endloop + endfacet + facet normal 0.312546 -0.613059 0.725585 + outer loop + vertex 755.91 178.935 343.188 + vertex 746.811 178.303 346.574 + vertex 747.331 174.571 343.197 + endloop + endfacet + facet normal 0.292731 -0.572571 0.765814 + outer loop + vertex 754.92 186.63 349.7 + vertex 746.37 182.273 349.71 + vertex 755.378 182.664 346.56 + endloop + endfacet + facet normal 0.292752 -0.572462 0.765887 + outer loop + vertex 755.378 182.664 346.56 + vertex 746.37 182.273 349.71 + vertex 746.811 178.303 346.574 + endloop + endfacet + facet normal 0.267048 -0.521367 0.81047 + outer loop + vertex 754.501 190.813 352.528 + vertex 745.958 186.445 352.533 + vertex 754.92 186.63 349.7 + endloop + endfacet + facet normal 0.26696 -0.521899 0.810157 + outer loop + vertex 754.92 186.63 349.7 + vertex 745.958 186.445 352.533 + vertex 746.37 182.273 349.71 + endloop + endfacet + facet normal 0.235555 -0.460273 0.855957 + outer loop + vertex 754.116 195.189 354.987 + vertex 745.569 190.813 354.987 + vertex 754.501 190.813 352.528 + endloop + endfacet + facet normal 0.235615 -0.459835 0.856176 + outer loop + vertex 754.501 190.813 352.528 + vertex 745.569 190.813 354.987 + vertex 745.958 186.445 352.533 + endloop + endfacet + facet normal 0.200366 -0.390211 0.898659 + outer loop + vertex 753.783 199.749 357.042 + vertex 745.231 195.369 357.047 + vertex 754.116 195.189 354.987 + endloop + endfacet + facet normal 0.200241 -0.391296 0.898216 + outer loop + vertex 754.116 195.189 354.987 + vertex 745.231 195.369 357.047 + vertex 745.569 190.813 354.987 + endloop + endfacet + facet normal 0.162871 -0.319288 0.933557 + outer loop + vertex 753.516 204.461 358.7 + vertex 744.965 200.098 358.699 + vertex 753.783 199.749 357.042 + endloop + endfacet + facet normal 0.163066 -0.317342 0.934186 + outer loop + vertex 753.783 199.749 357.042 + vertex 744.965 200.098 358.699 + vertex 745.231 195.369 357.047 + endloop + endfacet + facet normal 0.126768 -0.248468 0.960309 + outer loop + vertex 753.312 209.299 359.979 + vertex 744.775 204.95 359.98 + vertex 753.516 204.461 358.7 + endloop + endfacet + facet normal 0.126762 -0.248535 0.960292 + outer loop + vertex 753.516 204.461 358.7 + vertex 744.775 204.95 359.98 + vertex 744.965 200.098 358.699 + endloop + endfacet + facet normal 0.0949841 -0.18602 0.977944 + outer loop + vertex 753.165 214.224 360.93 + vertex 744.643 209.882 360.932 + vertex 753.312 209.299 359.979 + endloop + endfacet + facet normal 0.0949796 -0.186071 0.977935 + outer loop + vertex 753.312 209.299 359.979 + vertex 744.643 209.882 360.932 + vertex 744.775 204.95 359.98 + endloop + endfacet + facet normal 0.14283 -0.217101 -0.965643 + outer loop + vertex 747.343 159.982 307.993 + vertex 743.325 158.311 307.774 + vertex 749.04 163.118 307.539 + endloop + endfacet + facet normal 0.157435 -0.241051 -0.957658 + outer loop + vertex 738.801 155.789 307.665 + vertex 740.456 158.917 307.15 + vertex 743.325 158.311 307.774 + endloop + endfacet + facet normal 0.158795 -0.235746 -0.958753 + outer loop + vertex 740.456 158.917 307.15 + vertex 749.04 163.118 307.539 + vertex 743.325 158.311 307.774 + endloop + endfacet + facet normal 0.157967 -0.266478 -0.950808 + outer loop + vertex 748.176 158.582 308.524 + vertex 743.952 156.48 308.411 + vertex 747.343 159.982 307.993 + endloop + endfacet + facet normal 0.16512 -0.273035 -0.947727 + outer loop + vertex 747.343 159.982 307.993 + vertex 743.952 156.48 308.411 + vertex 743.325 158.311 307.774 + endloop + endfacet + facet normal 0.163954 -0.273463 -0.947806 + outer loop + vertex 743.952 156.48 308.411 + vertex 739.677 154.393 308.274 + vertex 743.325 158.311 307.774 + endloop + endfacet + facet normal 0.185569 -0.292352 -0.938134 + outer loop + vertex 743.325 158.311 307.774 + vertex 739.677 154.393 308.274 + vertex 738.801 155.789 307.665 + endloop + endfacet + facet normal 0.356288 -0.718351 -0.597521 + outer loop + vertex 745.178 152.357 311.52 + vertex 740.923 150.275 311.486 + vertex 744.922 153.294 310.241 + endloop + endfacet + facet normal 0.359403 -0.72059 -0.592942 + outer loop + vertex 744.922 153.294 310.241 + vertex 740.923 150.275 311.486 + vertex 740.655 151.215 310.182 + endloop + endfacet + facet normal 0.355115 -0.710595 -0.607411 + outer loop + vertex 749.385 154.442 311.541 + vertex 745.178 152.357 311.52 + vertex 749.132 155.385 310.289 + endloop + endfacet + facet normal 0.362391 -0.715818 -0.59689 + outer loop + vertex 749.132 155.385 310.289 + vertex 745.178 152.357 311.52 + vertex 744.922 153.294 310.241 + endloop + endfacet + facet normal 0.438142 -0.895501 0.0781611 + outer loop + vertex 745.605 152.307 315.046 + vertex 741.359 150.229 315.041 + vertex 745.365 152.021 313.112 + endloop + endfacet + facet normal 0.436726 -0.896523 0.0742725 + outer loop + vertex 745.365 152.021 313.112 + vertex 741.359 150.229 315.041 + vertex 741.115 149.95 313.101 + endloop + endfacet + facet normal 0.444487 -0.89217 0.080398 + outer loop + vertex 749.803 154.399 315.051 + vertex 745.605 152.307 315.046 + vertex 749.567 154.107 313.121 + endloop + endfacet + facet normal 0.443308 -0.893043 0.0771545 + outer loop + vertex 749.567 154.107 313.121 + vertex 745.605 152.307 315.046 + vertex 745.365 152.021 313.112 + endloop + endfacet + facet normal 0.43282 -0.870608 -0.233901 + outer loop + vertex 749.567 154.107 313.121 + vertex 745.365 152.021 313.112 + vertex 749.385 154.442 311.541 + endloop + endfacet + facet normal 0.432451 -0.870557 -0.234768 + outer loop + vertex 749.385 154.442 311.541 + vertex 745.365 152.021 313.112 + vertex 745.178 152.357 311.52 + endloop + endfacet + facet normal 0.426353 -0.873581 -0.234691 + outer loop + vertex 745.365 152.021 313.112 + vertex 741.115 149.95 313.101 + vertex 745.178 152.357 311.52 + endloop + endfacet + facet normal 0.429459 -0.874001 -0.22735 + outer loop + vertex 745.178 152.357 311.52 + vertex 741.115 149.95 313.101 + vertex 740.923 150.275 311.486 + endloop + endfacet + facet normal 0.408987 -0.815961 0.40858 + outer loop + vertex 746.283 154.686 319.931 + vertex 742.326 152.481 319.489 + vertex 745.978 153.208 317.285 + endloop + endfacet + facet normal 0.402513 -0.826032 0.394531 + outer loop + vertex 745.978 153.208 317.285 + vertex 742.326 152.481 319.489 + vertex 741.726 151.139 317.29 + endloop + endfacet + facet normal 0.40093 -0.82408 0.400184 + outer loop + vertex 750.819 156.671 319.475 + vertex 746.283 154.686 319.931 + vertex 750.178 155.295 317.282 + endloop + endfacet + facet normal 0.406124 -0.816949 0.409461 + outer loop + vertex 750.178 155.295 317.282 + vertex 746.283 154.686 319.931 + vertex 745.978 153.208 317.285 + endloop + endfacet + facet normal 0.42809 -0.861318 0.273624 + outer loop + vertex 750.178 155.295 317.282 + vertex 745.978 153.208 317.285 + vertex 749.803 154.399 315.051 + endloop + endfacet + facet normal 0.428591 -0.860689 0.274816 + outer loop + vertex 749.803 154.399 315.051 + vertex 745.978 153.208 317.285 + vertex 745.605 152.307 315.046 + endloop + endfacet + facet normal 0.420719 -0.863752 0.27736 + outer loop + vertex 745.978 153.208 317.285 + vertex 741.726 151.139 317.29 + vertex 745.605 152.307 315.046 + endloop + endfacet + facet normal 0.421727 -0.862484 0.279763 + outer loop + vertex 745.605 152.307 315.046 + vertex 741.726 151.139 317.29 + vertex 741.359 150.229 315.041 + endloop + endfacet + facet normal 0.380347 -0.781752 0.494166 + outer loop + vertex 742.326 152.481 319.489 + vertex 746.283 154.686 319.931 + vertex 739.65 153.425 323.042 + endloop + endfacet + facet normal 0.390799 -0.780934 0.487255 + outer loop + vertex 750.819 156.671 319.475 + vertex 748.383 157.66 323.014 + vertex 746.283 154.686 319.931 + endloop + endfacet + facet normal 0.380508 -0.781355 0.494669 + outer loop + vertex 748.383 157.66 323.014 + vertex 739.65 153.425 323.042 + vertex 746.283 154.686 319.931 + endloop + endfacet + facet normal 0.301098 -0.61644 0.727559 + outer loop + vertex 746.811 178.303 346.574 + vertex 737.995 174.035 346.606 + vertex 747.331 174.571 343.197 + endloop + endfacet + facet normal 0.301193 -0.616006 0.727887 + outer loop + vertex 747.331 174.571 343.197 + vertex 737.995 174.035 346.606 + vertex 738.514 170.289 343.221 + endloop + endfacet + facet normal 0.281876 -0.575245 0.767879 + outer loop + vertex 746.37 182.273 349.71 + vertex 737.577 178.011 349.745 + vertex 746.811 178.303 346.574 + endloop + endfacet + facet normal 0.281706 -0.57609 0.767308 + outer loop + vertex 746.811 178.303 346.574 + vertex 737.577 178.011 349.745 + vertex 737.995 174.035 346.606 + endloop + endfacet + facet normal 0.257288 -0.524035 0.811905 + outer loop + vertex 745.958 186.445 352.533 + vertex 737.188 182.182 352.561 + vertex 746.37 182.273 349.71 + endloop + endfacet + facet normal 0.257273 -0.524125 0.811852 + outer loop + vertex 746.37 182.273 349.71 + vertex 737.188 182.182 352.561 + vertex 737.577 178.011 349.745 + endloop + endfacet + facet normal 0.226527 -0.461514 0.857724 + outer loop + vertex 745.569 190.813 354.987 + vertex 736.804 186.542 355.003 + vertex 745.958 186.445 352.533 + endloop + endfacet + facet normal 0.226646 -0.460691 0.858135 + outer loop + vertex 745.958 186.445 352.533 + vertex 736.804 186.542 355.003 + vertex 737.188 182.182 352.561 + endloop + endfacet + facet normal 0.19205 -0.392478 0.899487 + outer loop + vertex 745.231 195.369 357.047 + vertex 736.454 191.092 357.055 + vertex 745.569 190.813 354.987 + endloop + endfacet + facet normal 0.192234 -0.390987 0.900097 + outer loop + vertex 745.569 190.813 354.987 + vertex 736.454 191.092 357.055 + vertex 736.804 186.542 355.003 + endloop + endfacet + facet normal 0.155576 -0.318117 0.935199 + outer loop + vertex 744.965 200.098 358.699 + vertex 736.175 195.826 358.709 + vertex 745.231 195.369 357.047 + endloop + endfacet + facet normal 0.155627 -0.317656 0.935348 + outer loop + vertex 745.231 195.369 357.047 + vertex 736.175 195.826 358.709 + vertex 736.454 191.092 357.055 + endloop + endfacet + facet normal 0.121051 -0.248927 0.960928 + outer loop + vertex 744.775 204.95 359.98 + vertex 735.983 200.697 359.986 + vertex 744.965 200.098 358.699 + endloop + endfacet + facet normal 0.121211 -0.24735 0.961315 + outer loop + vertex 744.965 200.098 358.699 + vertex 735.983 200.697 359.986 + vertex 736.175 195.826 358.709 + endloop + endfacet + facet normal 0.090666 -0.186258 0.978308 + outer loop + vertex 744.643 209.882 360.932 + vertex 735.867 205.646 360.938 + vertex 744.775 204.95 359.98 + endloop + endfacet + facet normal 0.0906802 -0.186113 0.978335 + outer loop + vertex 744.775 204.95 359.98 + vertex 735.867 205.646 360.938 + vertex 735.983 200.697 359.986 + endloop + endfacet + facet normal 0.170854 -0.247497 -0.953706 + outer loop + vertex 738.801 155.789 307.665 + vertex 734.649 154.139 307.35 + vertex 740.456 158.917 307.15 + endloop + endfacet + facet normal 0.191641 -0.28386 -0.93952 + outer loop + vertex 730.007 151.644 307.157 + vertex 731.509 154.748 306.525 + vertex 734.649 154.139 307.35 + endloop + endfacet + facet normal 0.193921 -0.275027 -0.941677 + outer loop + vertex 731.509 154.748 306.525 + vertex 740.456 158.917 307.15 + vertex 734.649 154.139 307.35 + endloop + endfacet + facet normal 0.179622 -0.296078 -0.938122 + outer loop + vertex 739.677 154.393 308.274 + vertex 735.35 152.31 308.103 + vertex 738.801 155.789 307.665 + endloop + endfacet + facet normal 0.1936 -0.309066 -0.931127 + outer loop + vertex 738.801 155.789 307.665 + vertex 735.35 152.31 308.103 + vertex 734.649 154.139 307.35 + endloop + endfacet + facet normal 0.189715 -0.310665 -0.931394 + outer loop + vertex 735.35 152.31 308.103 + vertex 730.994 150.251 307.902 + vertex 734.649 154.139 307.35 + endloop + endfacet + facet normal 0.218457 -0.335549 -0.916342 + outer loop + vertex 734.649 154.139 307.35 + vertex 730.994 150.251 307.902 + vertex 730.007 151.644 307.157 + endloop + endfacet + facet normal 0.350887 -0.734817 -0.58045 + outer loop + vertex 736.607 148.208 311.448 + vertex 732.272 146.169 311.409 + vertex 736.332 149.135 310.109 + endloop + endfacet + facet normal 0.362977 -0.743261 -0.56197 + outer loop + vertex 736.332 149.135 310.109 + vertex 732.272 146.169 311.409 + vertex 731.996 147.079 310.027 + endloop + endfacet + facet normal 0.351862 -0.723721 -0.593651 + outer loop + vertex 740.923 150.275 311.486 + vertex 736.607 148.208 311.448 + vertex 740.655 151.215 310.182 + endloop + endfacet + facet normal 0.361276 -0.730465 -0.579569 + outer loop + vertex 740.655 151.215 310.182 + vertex 736.607 148.208 311.448 + vertex 736.332 149.135 310.109 + endloop + endfacet + facet normal 0.424201 -0.90223 0.0776804 + outer loop + vertex 737.044 148.164 315.04 + vertex 732.685 146.115 315.041 + vertex 736.807 147.884 313.086 + endloop + endfacet + facet normal 0.426249 -0.90076 0.0833286 + outer loop + vertex 736.807 147.884 313.086 + vertex 732.685 146.115 315.041 + vertex 732.472 145.831 313.064 + endloop + endfacet + facet normal 0.430518 -0.899421 0.0754713 + outer loop + vertex 741.359 150.229 315.041 + vertex 737.044 148.164 315.04 + vertex 741.115 149.95 313.101 + endloop + endfacet + facet normal 0.430866 -0.899173 0.0764322 + outer loop + vertex 741.115 149.95 313.101 + vertex 737.044 148.164 315.04 + vertex 736.807 147.884 313.086 + endloop + endfacet + facet normal 0.421698 -0.877813 -0.227192 + outer loop + vertex 741.115 149.95 313.101 + vertex 736.807 147.884 313.086 + vertex 740.923 150.275 311.486 + endloop + endfacet + facet normal 0.422575 -0.877928 -0.225108 + outer loop + vertex 740.923 150.275 311.486 + vertex 736.807 147.884 313.086 + vertex 736.607 148.208 311.448 + endloop + endfacet + facet normal 0.418049 -0.880122 -0.22499 + outer loop + vertex 736.807 147.884 313.086 + vertex 732.472 145.831 313.064 + vertex 736.607 148.208 311.448 + endloop + endfacet + facet normal 0.415945 -0.879835 -0.229956 + outer loop + vertex 736.607 148.208 311.448 + vertex 732.472 145.831 313.064 + vertex 732.272 146.169 311.409 + endloop + endfacet + facet normal 0.394773 -0.821087 0.412275 + outer loop + vertex 737.63 150.512 319.954 + vertex 733.521 148.317 319.517 + vertex 737.395 149.065 317.297 + endloop + endfacet + facet normal 0.389702 -0.829204 0.40069 + outer loop + vertex 737.395 149.065 317.297 + vertex 733.521 148.317 319.517 + vertex 732.986 146.997 317.307 + endloop + endfacet + facet normal 0.387761 -0.829979 0.400968 + outer loop + vertex 742.326 152.481 319.489 + vertex 737.63 150.512 319.954 + vertex 741.726 151.139 317.29 + endloop + endfacet + facet normal 0.393944 -0.821371 0.412503 + outer loop + vertex 741.726 151.139 317.29 + vertex 737.63 150.512 319.954 + vertex 737.395 149.065 317.297 + endloop + endfacet + facet normal 0.414707 -0.865159 0.281989 + outer loop + vertex 741.726 151.139 317.29 + vertex 737.395 149.065 317.297 + vertex 741.359 150.229 315.041 + endloop + endfacet + facet normal 0.414336 -0.865627 0.281096 + outer loop + vertex 741.359 150.229 315.041 + vertex 737.395 149.065 317.297 + vertex 737.044 148.164 315.04 + endloop + endfacet + facet normal 0.40769 -0.868119 0.283123 + outer loop + vertex 737.395 149.065 317.297 + vertex 732.986 146.997 317.307 + vertex 737.044 148.164 315.04 + endloop + endfacet + facet normal 0.40801 -0.867713 0.283905 + outer loop + vertex 737.044 148.164 315.04 + vertex 732.986 146.997 317.307 + vertex 732.685 146.115 315.041 + endloop + endfacet + facet normal 0.367276 -0.786407 0.496661 + outer loop + vertex 733.521 148.317 319.517 + vertex 737.63 150.512 319.954 + vertex 730.624 149.212 323.077 + endloop + endfacet + facet normal 0.377574 -0.784029 0.492682 + outer loop + vertex 742.326 152.481 319.489 + vertex 739.65 153.425 323.042 + vertex 737.63 150.512 319.954 + endloop + endfacet + facet normal 0.368059 -0.784397 0.499253 + outer loop + vertex 739.65 153.425 323.042 + vertex 730.624 149.212 323.077 + vertex 737.63 150.512 319.954 + endloop + endfacet + facet normal 0.290373 -0.619101 0.729656 + outer loop + vertex 737.995 174.035 346.606 + vertex 728.795 169.746 346.629 + vertex 738.514 170.289 343.221 + endloop + endfacet + facet normal 0.290693 -0.617588 0.73081 + outer loop + vertex 738.514 170.289 343.221 + vertex 728.795 169.746 346.629 + vertex 729.329 165.997 343.248 + endloop + endfacet + facet normal 0.271703 -0.578536 0.769073 + outer loop + vertex 737.577 178.011 349.745 + vertex 728.372 173.722 349.771 + vertex 737.995 174.035 346.606 + endloop + endfacet + facet normal 0.27166 -0.578758 0.768921 + outer loop + vertex 737.995 174.035 346.606 + vertex 728.372 173.722 349.771 + vertex 728.795 169.746 346.629 + endloop + endfacet + facet normal 0.247343 -0.526218 0.813583 + outer loop + vertex 737.188 182.182 352.561 + vertex 728.002 177.906 352.588 + vertex 737.577 178.011 349.745 + endloop + endfacet + facet normal 0.247371 -0.526045 0.813686 + outer loop + vertex 737.577 178.011 349.745 + vertex 728.002 177.906 352.588 + vertex 728.372 173.722 349.771 + endloop + endfacet + facet normal 0.218543 -0.462144 0.859454 + outer loop + vertex 736.804 186.542 355.003 + vertex 727.657 182.277 355.036 + vertex 737.188 182.182 352.561 + endloop + endfacet + facet normal 0.218336 -0.463616 0.858714 + outer loop + vertex 737.188 182.182 352.561 + vertex 727.657 182.277 355.036 + vertex 728.002 177.906 352.588 + endloop + endfacet + facet normal 0.184692 -0.392067 0.901206 + outer loop + vertex 736.454 191.092 357.055 + vertex 727.316 186.831 357.073 + vertex 736.804 186.542 355.003 + endloop + endfacet + facet normal 0.184964 -0.389794 0.902136 + outer loop + vertex 736.804 186.542 355.003 + vertex 727.316 186.831 357.073 + vertex 727.657 182.277 355.036 + endloop + endfacet + facet normal 0.149731 -0.318267 0.936102 + outer loop + vertex 736.175 195.826 358.709 + vertex 727.017 191.556 358.722 + vertex 736.454 191.092 357.055 + endloop + endfacet + facet normal 0.149845 -0.317197 0.936447 + outer loop + vertex 736.454 191.092 357.055 + vertex 727.017 191.556 358.722 + vertex 727.316 186.831 357.073 + endloop + endfacet + facet normal 0.116288 -0.247681 0.961837 + outer loop + vertex 735.983 200.697 359.986 + vertex 726.807 196.428 359.996 + vertex 736.175 195.826 358.709 + endloop + endfacet + facet normal 0.116388 -0.24667 0.962085 + outer loop + vertex 736.175 195.826 358.709 + vertex 726.807 196.428 359.996 + vertex 727.017 191.556 358.722 + endloop + endfacet + facet normal 0.0872198 -0.18625 0.978623 + outer loop + vertex 735.867 205.646 360.938 + vertex 726.688 201.384 360.945 + vertex 735.983 200.697 359.986 + endloop + endfacet + facet normal 0.0873044 -0.185336 0.978789 + outer loop + vertex 735.983 200.697 359.986 + vertex 726.688 201.384 360.945 + vertex 726.807 196.428 359.996 + endloop + endfacet + facet normal 0.236521 -0.283677 -0.929293 + outer loop + vertex 728.736 155.896 305.66 + vertex 721.717 150.471 305.53 + vertex 720.486 152.807 304.503 + endloop + endfacet + facet normal 0.206348 -0.289961 -0.934528 + outer loop + vertex 730.007 151.644 307.157 + vertex 725.654 149.996 306.707 + vertex 731.509 154.748 306.525 + endloop + endfacet + facet normal 0.231485 -0.339987 -0.911495 + outer loop + vertex 721.016 147.518 306.453 + vertex 721.717 150.471 305.53 + vertex 725.654 149.996 306.707 + endloop + endfacet + facet normal 0.234818 -0.324343 -0.916331 + outer loop + vertex 721.717 150.471 305.53 + vertex 731.509 154.748 306.525 + vertex 725.654 149.996 306.707 + endloop + endfacet + facet normal 0.20882 -0.342257 -0.916108 + outer loop + vertex 730.994 150.251 307.902 + vertex 726.626 148.23 307.662 + vertex 730.007 151.644 307.157 + endloop + endfacet + facet normal 0.230257 -0.36161 -0.903449 + outer loop + vertex 730.007 151.644 307.157 + vertex 726.626 148.23 307.662 + vertex 725.654 149.996 306.707 + endloop + endfacet + facet normal 0.224656 -0.36477 -0.903589 + outer loop + vertex 726.626 148.23 307.662 + vertex 722.287 146.232 307.389 + vertex 725.654 149.996 306.707 + endloop + endfacet + facet normal 0.256673 -0.389918 -0.884354 + outer loop + vertex 725.654 149.996 306.707 + vertex 722.287 146.232 307.389 + vertex 721.016 147.518 306.453 + endloop + endfacet + facet normal 0.352736 -0.756265 -0.551036 + outer loop + vertex 727.978 144.167 311.362 + vertex 723.749 142.23 311.314 + vertex 727.708 145.079 309.938 + endloop + endfacet + facet normal 0.363343 -0.763042 -0.534554 + outer loop + vertex 727.708 145.079 309.938 + vertex 723.749 142.23 311.314 + vertex 723.491 143.142 309.836 + endloop + endfacet + facet normal 0.354306 -0.746924 -0.562647 + outer loop + vertex 732.272 146.169 311.409 + vertex 727.978 144.167 311.362 + vertex 731.996 147.079 310.027 + endloop + endfacet + facet normal 0.362289 -0.752275 -0.550299 + outer loop + vertex 731.996 147.079 310.027 + vertex 727.978 144.167 311.362 + vertex 727.708 145.079 309.938 + endloop + endfacet + facet normal 0.412801 -0.906839 0.08508 + outer loop + vertex 728.325 144.092 315.038 + vertex 723.985 142.116 315.038 + vertex 728.16 143.83 313.046 + endloop + endfacet + facet normal 0.413452 -0.906375 0.0868437 + outer loop + vertex 728.16 143.83 313.046 + vertex 723.985 142.116 315.038 + vertex 723.892 141.881 313.03 + endloop + endfacet + facet normal 0.419295 -0.903906 0.0845314 + outer loop + vertex 732.685 146.115 315.041 + vertex 728.325 144.092 315.038 + vertex 732.472 145.831 313.064 + endloop + endfacet + facet normal 0.419166 -0.903999 0.0841786 + outer loop + vertex 732.472 145.831 313.064 + vertex 728.325 144.092 315.038 + vertex 728.16 143.83 313.046 + endloop + endfacet + facet normal 0.410444 -0.882449 -0.229826 + outer loop + vertex 732.472 145.831 313.064 + vertex 728.16 143.83 313.046 + vertex 732.272 146.169 311.409 + endloop + endfacet + facet normal 0.41396 -0.882901 -0.221637 + outer loop + vertex 732.272 146.169 311.409 + vertex 728.16 143.83 313.046 + vertex 727.978 144.167 311.362 + endloop + endfacet + facet normal 0.405692 -0.88676 -0.221519 + outer loop + vertex 728.16 143.83 313.046 + vertex 723.892 141.881 313.03 + vertex 727.978 144.167 311.362 + endloop + endfacet + facet normal 0.408817 -0.887094 -0.21432 + outer loop + vertex 727.978 144.167 311.362 + vertex 723.892 141.881 313.03 + vertex 723.749 142.23 311.314 + endloop + endfacet + facet normal 0.383201 -0.822914 0.419487 + outer loop + vertex 728.648 146.349 319.986 + vertex 724.482 144.188 319.551 + vertex 728.549 144.941 317.315 + endloop + endfacet + facet normal 0.377982 -0.831506 0.407097 + outer loop + vertex 728.549 144.941 317.315 + vertex 724.482 144.188 319.551 + vertex 724.106 142.927 317.326 + endloop + endfacet + facet normal 0.375467 -0.832987 0.406394 + outer loop + vertex 733.521 148.317 319.517 + vertex 728.648 146.349 319.986 + vertex 732.986 146.997 317.307 + endloop + endfacet + facet normal 0.382233 -0.823255 0.419702 + outer loop + vertex 732.986 146.997 317.307 + vertex 728.648 146.349 319.986 + vertex 728.549 144.941 317.315 + endloop + endfacet + facet normal 0.403387 -0.86945 0.285195 + outer loop + vertex 732.986 146.997 317.307 + vertex 728.549 144.941 317.315 + vertex 732.685 146.115 315.041 + endloop + endfacet + facet normal 0.40325 -0.869625 0.284854 + outer loop + vertex 732.685 146.115 315.041 + vertex 728.549 144.941 317.315 + vertex 728.325 144.092 315.038 + endloop + endfacet + facet normal 0.396182 -0.872312 0.286552 + outer loop + vertex 728.549 144.941 317.315 + vertex 724.106 142.927 317.326 + vertex 728.325 144.092 315.038 + endloop + endfacet + facet normal 0.396757 -0.871578 0.287986 + outer loop + vertex 728.325 144.092 315.038 + vertex 724.106 142.927 317.326 + vertex 723.985 142.116 315.038 + endloop + endfacet + facet normal 0.357126 -0.788907 0.500087 + outer loop + vertex 724.482 144.188 319.551 + vertex 728.648 146.349 319.986 + vertex 721.522 145.102 323.107 + endloop + endfacet + facet normal 0.365781 -0.78767 0.495763 + outer loop + vertex 733.521 148.317 319.517 + vertex 730.624 149.212 323.077 + vertex 728.648 146.349 319.986 + endloop + endfacet + facet normal 0.3575 -0.787953 0.501322 + outer loop + vertex 730.624 149.212 323.077 + vertex 721.522 145.102 323.107 + vertex 728.648 146.349 319.986 + endloop + endfacet + facet normal 0.281707 -0.620112 0.73219 + outer loop + vertex 728.795 169.746 346.629 + vertex 719.488 165.47 346.588 + vertex 729.329 165.997 343.248 + endloop + endfacet + facet normal 0.281297 -0.622091 0.730667 + outer loop + vertex 729.329 165.997 343.248 + vertex 719.488 165.47 346.588 + vertex 719.964 161.761 343.247 + endloop + endfacet + facet normal 0.264295 -0.58052 0.770159 + outer loop + vertex 728.372 173.722 349.771 + vertex 719.012 169.374 349.706 + vertex 728.795 169.746 346.629 + endloop + endfacet + facet normal 0.26403 -0.581992 0.769138 + outer loop + vertex 728.795 169.746 346.629 + vertex 719.012 169.374 349.706 + vertex 719.488 165.47 346.588 + endloop + endfacet + facet normal 0.239851 -0.527563 0.814953 + outer loop + vertex 728.002 177.906 352.588 + vertex 718.576 173.543 352.538 + vertex 728.372 173.722 349.771 + endloop + endfacet + facet normal 0.239736 -0.528316 0.814499 + outer loop + vertex 728.372 173.722 349.771 + vertex 718.576 173.543 352.538 + vertex 719.012 169.374 349.706 + endloop + endfacet + facet normal 0.210081 -0.465002 0.860023 + outer loop + vertex 727.657 182.277 355.036 + vertex 718.229 177.975 355.013 + vertex 728.002 177.906 352.588 + endloop + endfacet + facet normal 0.210207 -0.464056 0.860503 + outer loop + vertex 728.002 177.906 352.588 + vertex 718.229 177.975 355.013 + vertex 718.576 173.543 352.538 + endloop + endfacet + facet normal 0.177921 -0.390767 0.903131 + outer loop + vertex 727.316 186.831 357.073 + vertex 717.979 182.588 357.077 + vertex 727.657 182.277 355.036 + endloop + endfacet + facet normal 0.177546 -0.393921 0.901833 + outer loop + vertex 727.657 182.277 355.036 + vertex 717.979 182.588 357.077 + vertex 718.229 177.975 355.013 + endloop + endfacet + facet normal 0.144996 -0.31771 0.937036 + outer loop + vertex 727.017 191.556 358.722 + vertex 717.729 187.313 358.72 + vertex 727.316 186.831 357.073 + endloop + endfacet + facet normal 0.144948 -0.318166 0.936889 + outer loop + vertex 727.316 186.831 357.073 + vertex 717.729 187.313 358.72 + vertex 717.979 182.588 357.077 + endloop + endfacet + facet normal 0.113087 -0.2469 0.96242 + outer loop + vertex 726.807 196.428 359.996 + vertex 717.484 192.146 359.993 + vertex 727.017 191.556 358.722 + endloop + endfacet + facet normal 0.113011 -0.24771 0.962221 + outer loop + vertex 727.017 191.556 358.722 + vertex 717.484 192.146 359.993 + vertex 717.729 187.313 358.72 + endloop + endfacet + facet normal 0.0858995 -0.185391 0.978903 + outer loop + vertex 726.688 201.384 360.945 + vertex 717.346 197.061 360.946 + vertex 726.807 196.428 359.996 + endloop + endfacet + facet normal 0.0857321 -0.187355 0.978544 + outer loop + vertex 726.807 196.428 359.996 + vertex 717.346 197.061 360.946 + vertex 717.484 192.146 359.993 + endloop + endfacet + facet normal 0.267662 -0.362982 -0.892525 + outer loop + vertex 713.825 146.136 304.926 + vertex 714.461 148.771 304.045 + vertex 721.717 150.471 305.53 + endloop + endfacet + facet normal 0.284296 -0.321852 -0.903099 + outer loop + vertex 713.044 149.925 303.188 + vertex 720.486 152.807 304.503 + vertex 714.461 148.771 304.045 + endloop + endfacet + facet normal 0.253945 -0.273775 -0.927663 + outer loop + vertex 720.486 152.807 304.503 + vertex 721.717 150.471 305.53 + vertex 714.461 148.771 304.045 + endloop + endfacet + facet normal 0.238745 -0.341007 -0.909239 + outer loop + vertex 721.016 147.518 306.453 + vertex 716.85 145.81 306 + vertex 721.717 150.471 305.53 + endloop + endfacet + facet normal 0.267205 -0.403399 -0.87514 + outer loop + vertex 712.447 143.391 305.77 + vertex 713.825 146.136 304.926 + vertex 716.85 145.81 306 + endloop + endfacet + facet normal 0.273906 -0.375326 -0.885497 + outer loop + vertex 713.825 146.136 304.926 + vertex 721.717 150.471 305.53 + vertex 716.85 145.81 306 + endloop + endfacet + facet normal 0.244135 -0.401215 -0.88285 + outer loop + vertex 722.287 146.232 307.389 + vertex 717.956 144.205 307.113 + vertex 721.016 147.518 306.453 + endloop + endfacet + facet normal 0.266135 -0.418629 -0.868287 + outer loop + vertex 721.016 147.518 306.453 + vertex 717.956 144.205 307.113 + vertex 716.85 145.81 306 + endloop + endfacet + facet normal 0.255521 -0.425755 -0.86801 + outer loop + vertex 717.956 144.205 307.113 + vertex 713.594 142.144 306.84 + vertex 716.85 145.81 306 + endloop + endfacet + facet normal 0.292619 -0.452799 -0.842227 + outer loop + vertex 716.85 145.81 306 + vertex 713.594 142.144 306.84 + vertex 712.447 143.391 305.77 + endloop + endfacet + facet normal 0.350039 -0.775132 -0.525969 + outer loop + vertex 719.548 140.322 311.251 + vertex 715.278 138.436 311.188 + vertex 719.296 141.246 309.721 + endloop + endfacet + facet normal 0.36716 -0.785284 -0.49852 + outer loop + vertex 719.296 141.246 309.721 + vertex 715.278 138.436 311.188 + vertex 715.032 139.329 309.599 + endloop + endfacet + facet normal 0.356074 -0.76605 -0.535144 + outer loop + vertex 723.749 142.23 311.314 + vertex 719.548 140.322 311.251 + vertex 723.491 143.142 309.836 + endloop + endfacet + facet normal 0.362581 -0.770036 -0.524957 + outer loop + vertex 723.491 143.142 309.836 + vertex 719.548 140.322 311.251 + vertex 719.296 141.246 309.721 + endloop + endfacet + facet normal 0.403075 -0.910213 0.0950883 + outer loop + vertex 719.644 140.174 315.041 + vertex 715.251 138.228 315.036 + vertex 719.637 139.958 313.005 + endloop + endfacet + facet normal 0.402103 -0.910921 0.092386 + outer loop + vertex 719.637 139.958 313.005 + vertex 715.251 138.228 315.036 + vertex 715.318 138.049 312.979 + endloop + endfacet + facet normal 0.406829 -0.909305 0.0874939 + outer loop + vertex 723.985 142.116 315.038 + vertex 719.644 140.174 315.041 + vertex 723.892 141.881 313.03 + endloop + endfacet + facet normal 0.409496 -0.907376 0.0947659 + outer loop + vertex 723.892 141.881 313.03 + vertex 719.644 140.174 315.041 + vertex 719.637 139.958 313.005 + endloop + endfacet + facet normal 0.40324 -0.889631 -0.214369 + outer loop + vertex 723.892 141.881 313.03 + vertex 719.637 139.958 313.005 + vertex 723.749 142.23 311.314 + endloop + endfacet + facet normal 0.407397 -0.890001 -0.204759 + outer loop + vertex 723.749 142.23 311.314 + vertex 719.637 139.958 313.005 + vertex 719.548 140.322 311.251 + endloop + endfacet + facet normal 0.396718 -0.894712 -0.205195 + outer loop + vertex 719.637 139.958 313.005 + vertex 715.318 138.049 312.979 + vertex 719.548 140.322 311.251 + endloop + endfacet + facet normal 0.398135 -0.894835 -0.201889 + outer loop + vertex 719.548 140.322 311.251 + vertex 715.318 138.049 312.979 + vertex 715.278 138.436 311.188 + endloop + endfacet + facet normal 0.37165 -0.825745 0.424289 + outer loop + vertex 719.608 142.302 320.029 + vertex 715.491 140.228 319.598 + vertex 719.664 140.946 317.34 + endloop + endfacet + facet normal 0.366421 -0.834308 0.411906 + outer loop + vertex 719.664 140.946 317.34 + vertex 715.491 140.228 319.598 + vertex 715.21 138.999 317.358 + endloop + endfacet + facet normal 0.363531 -0.835595 0.411858 + outer loop + vertex 724.482 144.188 319.551 + vertex 719.608 142.302 320.029 + vertex 724.106 142.927 317.326 + endloop + endfacet + facet normal 0.369894 -0.826386 0.424576 + outer loop + vertex 724.106 142.927 317.326 + vertex 719.608 142.302 320.029 + vertex 719.664 140.946 317.34 + endloop + endfacet + facet normal 0.390682 -0.873936 0.289142 + outer loop + vertex 724.106 142.927 317.326 + vertex 719.664 140.946 317.34 + vertex 723.985 142.116 315.038 + endloop + endfacet + facet normal 0.390959 -0.87358 0.289843 + outer loop + vertex 723.985 142.116 315.038 + vertex 719.664 140.946 317.34 + vertex 719.644 140.174 315.041 + endloop + endfacet + facet normal 0.38426 -0.876232 0.290794 + outer loop + vertex 719.664 140.946 317.34 + vertex 715.21 138.999 317.358 + vertex 719.644 140.174 315.041 + endloop + endfacet + facet normal 0.386507 -0.873299 0.296582 + outer loop + vertex 719.644 140.174 315.041 + vertex 715.21 138.999 317.358 + vertex 715.251 138.228 315.036 + endloop + endfacet + facet normal 0.347034 -0.792811 0.501017 + outer loop + vertex 715.491 140.228 319.598 + vertex 719.608 142.302 320.029 + vertex 712.849 141.323 323.16 + endloop + endfacet + facet normal 0.354753 -0.790901 0.498624 + outer loop + vertex 724.482 144.188 319.551 + vertex 721.522 145.102 323.107 + vertex 719.608 142.302 320.029 + endloop + endfacet + facet normal 0.347782 -0.791124 0.50316 + outer loop + vertex 721.522 145.102 323.107 + vertex 712.849 141.323 323.16 + vertex 719.608 142.302 320.029 + endloop + endfacet + facet normal 0.275754 -0.62357 0.73152 + outer loop + vertex 719.488 165.47 346.588 + vertex 710.861 161.547 346.496 + vertex 719.964 161.761 343.247 + endloop + endfacet + facet normal 0.27461 -0.628161 0.728014 + outer loop + vertex 719.964 161.761 343.247 + vertex 710.861 161.547 346.496 + vertex 711.047 157.862 343.247 + endloop + endfacet + facet normal 0.260337 -0.5829 0.76971 + outer loop + vertex 719.012 169.374 349.706 + vertex 710.444 165.226 349.462 + vertex 719.488 165.47 346.588 + endloop + endfacet + facet normal 0.259306 -0.588199 0.766017 + outer loop + vertex 719.488 165.47 346.588 + vertex 710.444 165.226 349.462 + vertex 710.861 161.547 346.496 + endloop + endfacet + facet normal 0.235836 -0.529136 0.815105 + outer loop + vertex 718.576 173.543 352.538 + vertex 709.759 169.201 352.27 + vertex 719.012 169.374 349.706 + endloop + endfacet + facet normal 0.235186 -0.533462 0.812469 + outer loop + vertex 719.012 169.374 349.706 + vertex 709.759 169.201 352.27 + vertex 710.444 165.226 349.462 + endloop + endfacet + facet normal 0.204381 -0.465009 0.861391 + outer loop + vertex 718.229 177.975 355.013 + vertex 709.158 173.675 354.844 + vertex 718.576 173.543 352.538 + endloop + endfacet + facet normal 0.204054 -0.467375 0.860188 + outer loop + vertex 718.576 173.543 352.538 + vertex 709.158 173.675 354.844 + vertex 709.759 169.201 352.27 + endloop + endfacet + facet normal 0.171188 -0.394669 0.902735 + outer loop + vertex 717.979 182.588 357.077 + vertex 708.949 178.521 357.011 + vertex 718.229 177.975 355.013 + endloop + endfacet + facet normal 0.170972 -0.39614 0.902132 + outer loop + vertex 718.229 177.975 355.013 + vertex 708.949 178.521 357.011 + vertex 709.158 173.675 354.844 + endloop + endfacet + facet normal 0.1412 -0.318522 0.93734 + outer loop + vertex 717.729 187.313 358.72 + vertex 709.07 183.354 358.679 + vertex 717.979 182.588 357.077 + endloop + endfacet + facet normal 0.1401 -0.32616 0.934875 + outer loop + vertex 717.979 182.588 357.077 + vertex 709.07 183.354 358.679 + vertex 708.949 178.521 357.011 + endloop + endfacet + facet normal 0.110547 -0.247897 0.962459 + outer loop + vertex 717.484 192.146 359.993 + vertex 708.795 188.086 359.946 + vertex 717.729 187.313 358.72 + endloop + endfacet + facet normal 0.110182 -0.250928 0.961715 + outer loop + vertex 717.729 187.313 358.72 + vertex 708.795 188.086 359.946 + vertex 709.07 183.354 358.679 + endloop + endfacet + facet normal 0.084177 -0.187422 0.978666 + outer loop + vertex 717.346 197.061 360.946 + vertex 708.622 192.923 360.904 + vertex 717.484 192.146 359.993 + endloop + endfacet + facet normal 0.0838104 -0.190864 0.978032 + outer loop + vertex 717.484 192.146 359.993 + vertex 708.622 192.923 360.904 + vertex 708.795 188.086 359.946 + endloop + endfacet + facet normal 0.32084 -0.400154 -0.858451 + outer loop + vertex 708.847 144.913 303.828 + vertex 704.877 143.891 302.821 + vertex 708.591 146.874 302.818 + endloop + endfacet + facet normal 0.351766 -0.438622 -0.826965 + outer loop + vertex 708.591 146.874 302.818 + vertex 704.877 143.891 302.821 + vertex 703.732 144.908 301.794 + endloop + endfacet + facet normal 0.285206 -0.365105 -0.886203 + outer loop + vertex 713.825 146.136 304.926 + vertex 708.847 144.913 303.828 + vertex 714.461 148.771 304.045 + endloop + endfacet + facet normal 0.310199 -0.402896 -0.861076 + outer loop + vertex 714.461 148.771 304.045 + vertex 708.847 144.913 303.828 + vertex 708.591 146.874 302.818 + endloop + endfacet + facet normal 0.290571 -0.314569 -0.903667 + outer loop + vertex 714.461 148.771 304.045 + vertex 708.591 146.874 302.818 + vertex 713.044 149.925 303.188 + endloop + endfacet + facet normal 0.332429 -0.380625 -0.862911 + outer loop + vertex 713.044 149.925 303.188 + vertex 708.591 146.874 302.818 + vertex 707.184 147.595 301.958 + endloop + endfacet + facet normal 0.33461 -0.377173 -0.863584 + outer loop + vertex 708.591 146.874 302.818 + vertex 703.732 144.908 301.794 + vertex 707.184 147.595 301.958 + endloop + endfacet + facet normal 0.378677 -0.436681 -0.816035 + outer loop + vertex 707.184 147.595 301.958 + vertex 703.732 144.908 301.794 + vertex 702.463 145.571 300.85 + endloop + endfacet + facet normal 0.27461 -0.406036 -0.871622 + outer loop + vertex 712.447 143.391 305.77 + vertex 708.674 142.284 305.098 + vertex 713.825 146.136 304.926 + endloop + endfacet + facet normal 0.294119 -0.431296 -0.852923 + outer loop + vertex 713.825 146.136 304.926 + vertex 708.674 142.284 305.098 + vertex 708.847 144.913 303.828 + endloop + endfacet + facet normal 0.3276 -0.458053 -0.826357 + outer loop + vertex 704.877 143.891 302.821 + vertex 708.847 144.913 303.828 + vertex 703.703 140.735 304.105 + endloop + endfacet + facet normal 0.303936 -0.430476 -0.84989 + outer loop + vertex 703.703 140.735 304.105 + vertex 708.847 144.913 303.828 + vertex 708.674 142.284 305.098 + endloop + endfacet + facet normal 0.273211 -0.468761 -0.840011 + outer loop + vertex 713.594 142.144 306.84 + vertex 709.205 140.152 306.524 + vertex 712.447 143.391 305.77 + endloop + endfacet + facet normal 0.288892 -0.48153 -0.827448 + outer loop + vertex 712.447 143.391 305.77 + vertex 709.205 140.152 306.524 + vertex 708.674 142.284 305.098 + endloop + endfacet + facet normal 0.282656 -0.483684 -0.828345 + outer loop + vertex 709.205 140.152 306.524 + vertex 704.824 138.348 306.082 + vertex 708.674 142.284 305.098 + endloop + endfacet + facet normal 0.318804 -0.511453 -0.797985 + outer loop + vertex 708.674 142.284 305.098 + vertex 704.824 138.348 306.082 + vertex 703.703 140.735 304.105 + endloop + endfacet + facet normal 0.355852 -0.803939 -0.476499 + outer loop + vertex 710.944 136.522 311.124 + vertex 706.75 134.677 311.106 + vertex 710.688 137.374 309.496 + endloop + endfacet + facet normal 0.376641 -0.813918 -0.442357 + outer loop + vertex 710.688 137.374 309.496 + vertex 706.75 134.677 311.106 + vertex 706.47 135.455 309.435 + endloop + endfacet + facet normal 0.356032 -0.789857 -0.499367 + outer loop + vertex 715.278 138.436 311.188 + vertex 710.944 136.522 311.124 + vertex 715.032 139.329 309.599 + endloop + endfacet + facet normal 0.370395 -0.797871 -0.475615 + outer loop + vertex 715.032 139.329 309.599 + vertex 710.944 136.522 311.124 + vertex 710.688 137.374 309.496 + endloop + endfacet + facet normal 0.386189 -0.917316 0.0968981 + outer loop + vertex 710.814 136.318 315.043 + vertex 706.561 134.531 315.075 + vertex 710.937 136.15 312.957 + endloop + endfacet + facet normal 0.390072 -0.914541 0.107042 + outer loop + vertex 710.937 136.15 312.957 + vertex 706.561 134.531 315.075 + vertex 706.724 134.354 312.966 + endloop + endfacet + facet normal 0.393815 -0.914531 0.0924309 + outer loop + vertex 715.251 138.228 315.036 + vertex 710.814 136.318 315.043 + vertex 715.318 138.049 312.979 + endloop + endfacet + facet normal 0.395499 -0.913317 0.097124 + outer loop + vertex 715.318 138.049 312.979 + vertex 710.814 136.318 315.043 + vertex 710.937 136.15 312.957 + endloop + endfacet + facet normal 0.390447 -0.898096 -0.202421 + outer loop + vertex 715.318 138.049 312.979 + vertex 710.937 136.15 312.957 + vertex 715.278 138.436 311.188 + endloop + endfacet + facet normal 0.399421 -0.898689 -0.181167 + outer loop + vertex 715.278 138.436 311.188 + vertex 710.937 136.15 312.957 + vertex 710.944 136.522 311.124 + endloop + endfacet + facet normal 0.385193 -0.904625 -0.182427 + outer loop + vertex 710.937 136.15 312.957 + vertex 706.724 134.354 312.966 + vertex 710.944 136.522 311.124 + endloop + endfacet + facet normal 0.398666 -0.904509 -0.151423 + outer loop + vertex 710.944 136.522 311.124 + vertex 706.724 134.354 312.966 + vertex 706.75 134.677 311.106 + endloop + endfacet + facet normal 0.362041 -0.829189 0.425878 + outer loop + vertex 710.81 138.495 320.085 + vertex 706.926 136.581 319.659 + vertex 710.751 137.081 317.38 + endloop + endfacet + facet normal 0.356296 -0.837438 0.414428 + outer loop + vertex 710.751 137.081 317.38 + vertex 706.926 136.581 319.659 + vertex 706.514 135.295 317.415 + endloop + endfacet + facet normal 0.353425 -0.838073 0.415601 + outer loop + vertex 715.491 140.228 319.598 + vertex 710.81 138.495 320.085 + vertex 715.21 138.999 317.358 + endloop + endfacet + facet normal 0.359227 -0.830128 0.426431 + outer loop + vertex 715.21 138.999 317.358 + vertex 710.81 138.495 320.085 + vertex 710.751 137.081 317.38 + endloop + endfacet + facet normal 0.378532 -0.876476 0.297495 + outer loop + vertex 715.21 138.999 317.358 + vertex 710.751 137.081 317.38 + vertex 715.251 138.228 315.036 + endloop + endfacet + facet normal 0.37804 -0.877113 0.29624 + outer loop + vertex 715.251 138.228 315.036 + vertex 710.751 137.081 317.38 + vertex 710.814 136.318 315.043 + endloop + endfacet + facet normal 0.372892 -0.879138 0.296763 + outer loop + vertex 710.751 137.081 317.38 + vertex 706.514 135.295 317.415 + vertex 710.814 136.318 315.043 + endloop + endfacet + facet normal 0.372038 -0.88017 0.294769 + outer loop + vertex 710.814 136.318 315.043 + vertex 706.514 135.295 317.415 + vertex 706.561 134.531 315.075 + endloop + endfacet + facet normal 0.338436 -0.797626 0.499254 + outer loop + vertex 706.926 136.581 319.659 + vertex 710.81 138.495 320.085 + vertex 705.269 138.089 323.191 + endloop + endfacet + facet normal 0.34582 -0.793731 0.5004 + outer loop + vertex 715.491 140.228 319.598 + vertex 712.849 141.323 323.16 + vertex 710.81 138.495 320.085 + endloop + endfacet + facet normal 0.340715 -0.793773 0.503823 + outer loop + vertex 712.849 141.323 323.16 + vertex 705.269 138.089 323.191 + vertex 710.81 138.495 320.085 + endloop + endfacet + facet normal 0.265501 -0.630111 0.729705 + outer loop + vertex 710.861 161.547 346.496 + vertex 703.442 158.544 346.602 + vertex 711.047 157.862 343.247 + endloop + endfacet + facet normal 0.266742 -0.62704 0.731894 + outer loop + vertex 711.047 157.862 343.247 + vertex 703.442 158.544 346.602 + vertex 703.33 154.593 343.258 + endloop + endfacet + facet normal 0.257021 -0.588742 0.76637 + outer loop + vertex 710.444 165.226 349.462 + vertex 704.333 161.988 349.024 + vertex 710.861 161.547 346.496 + endloop + endfacet + facet normal 0.253514 -0.59947 0.759188 + outer loop + vertex 710.861 161.547 346.496 + vertex 704.333 161.988 349.024 + vertex 703.442 158.544 346.602 + endloop + endfacet + facet normal 0.234044 -0.533756 0.812606 + outer loop + vertex 709.759 169.201 352.27 + vertex 702.764 165.141 351.618 + vertex 710.444 165.226 349.462 + endloop + endfacet + facet normal 0.231948 -0.546597 0.804632 + outer loop + vertex 710.444 165.226 349.462 + vertex 702.764 165.141 351.618 + vertex 704.333 161.988 349.024 + endloop + endfacet + facet normal 0.206419 -0.466885 0.859889 + outer loop + vertex 709.158 173.675 354.844 + vertex 701.753 169.447 354.326 + vertex 709.759 169.201 352.27 + endloop + endfacet + facet normal 0.203195 -0.486559 0.849689 + outer loop + vertex 709.759 169.201 352.27 + vertex 701.753 169.447 354.326 + vertex 702.764 165.141 351.618 + endloop + endfacet + facet normal 0.169155 -0.396334 0.902389 + outer loop + vertex 708.949 178.521 357.011 + vertex 700.469 174.542 356.853 + vertex 709.158 173.675 354.844 + endloop + endfacet + facet normal 0.16769 -0.403878 0.899312 + outer loop + vertex 709.158 173.675 354.844 + vertex 700.469 174.542 356.853 + vertex 701.753 169.447 354.326 + endloop + endfacet + facet normal 0.134333 -0.326291 0.935676 + outer loop + vertex 709.07 183.354 358.679 + vertex 701.493 180.196 358.666 + vertex 708.949 178.521 357.011 + endloop + endfacet + facet normal 0.134842 -0.324549 0.936208 + outer loop + vertex 708.949 178.521 357.011 + vertex 701.493 180.196 358.666 + vertex 700.469 174.542 356.853 + endloop + endfacet + facet normal 0.110731 -0.250882 0.961664 + outer loop + vertex 708.795 188.086 359.946 + vertex 702.556 184.674 359.774 + vertex 709.07 183.354 358.679 + endloop + endfacet + facet normal 0.107834 -0.262802 0.958805 + outer loop + vertex 709.07 183.354 358.679 + vertex 702.556 184.674 359.774 + vertex 701.493 180.196 358.666 + endloop + endfacet + facet normal 0.0792136 -0.191095 0.97837 + outer loop + vertex 708.622 192.923 360.904 + vertex 700.614 189.202 360.826 + vertex 708.795 188.086 359.946 + endloop + endfacet + facet normal 0.078852 -0.193409 0.977944 + outer loop + vertex 708.795 188.086 359.946 + vertex 700.614 189.202 360.826 + vertex 702.556 184.674 359.774 + endloop + endfacet + facet normal 0.437078 -0.482068 -0.759324 + outer loop + vertex 698.939 144.134 299.859 + vertex 696.718 143.339 299.085 + vertex 698.237 144.481 299.235 + endloop + endfacet + facet normal 0.45323 -0.506959 -0.733195 + outer loop + vertex 698.237 144.481 299.235 + vertex 696.718 143.339 299.085 + vertex 695.818 143.482 298.43 + endloop + endfacet + facet normal 0.40396 -0.43566 -0.804373 + outer loop + vertex 702.463 145.571 300.85 + vertex 698.939 144.134 299.859 + vertex 701.069 145.573 300.149 + endloop + endfacet + facet normal 0.432952 -0.487924 -0.757946 + outer loop + vertex 701.069 145.573 300.149 + vertex 698.939 144.134 299.859 + vertex 698.237 144.481 299.235 + endloop + endfacet + facet normal 0.374874 -0.479481 -0.793453 + outer loop + vertex 701.074 141.692 302.388 + vertex 697.698 139.637 302.034 + vertex 699.757 143.059 300.939 + endloop + endfacet + facet normal 0.421786 -0.49657 -0.758627 + outer loop + vertex 699.757 143.059 300.939 + vertex 697.698 139.637 302.034 + vertex 696.907 142.065 300.006 + endloop + endfacet + facet normal 0.349229 -0.441187 -0.826676 + outer loop + vertex 704.877 143.891 302.821 + vertex 701.074 141.692 302.388 + vertex 703.732 144.908 301.794 + endloop + endfacet + facet normal 0.388219 -0.467431 -0.794225 + outer loop + vertex 703.732 144.908 301.794 + vertex 701.074 141.692 302.388 + vertex 699.757 143.059 300.939 + endloop + endfacet + facet normal 0.378635 -0.436741 -0.816022 + outer loop + vertex 703.732 144.908 301.794 + vertex 699.757 143.059 300.939 + vertex 702.463 145.571 300.85 + endloop + endfacet + facet normal 0.41158 -0.470962 -0.780254 + outer loop + vertex 702.463 145.571 300.85 + vertex 699.757 143.059 300.939 + vertex 698.939 144.134 299.859 + endloop + endfacet + facet normal 0.418025 -0.465757 -0.779952 + outer loop + vertex 699.757 143.059 300.939 + vertex 696.907 142.065 300.006 + vertex 698.939 144.134 299.859 + endloop + endfacet + facet normal 0.437193 -0.483074 -0.758618 + outer loop + vertex 698.939 144.134 299.859 + vertex 696.907 142.065 300.006 + vertex 696.718 143.339 299.085 + endloop + endfacet + facet normal 0.311464 -0.51527 -0.798428 + outer loop + vertex 704.824 138.348 306.082 + vertex 700.846 136.609 305.653 + vertex 703.703 140.735 304.105 + endloop + endfacet + facet normal 0.366793 -0.538611 -0.758526 + outer loop + vertex 703.703 140.735 304.105 + vertex 700.846 136.609 305.653 + vertex 699.362 138.31 303.727 + endloop + endfacet + facet normal 0.34149 -0.558101 -0.756246 + outer loop + vertex 700.846 136.609 305.653 + vertex 698.254 135.611 305.219 + vertex 699.362 138.31 303.727 + endloop + endfacet + facet normal 0.385085 -0.562428 -0.731699 + outer loop + vertex 699.362 138.31 303.727 + vertex 698.254 135.611 305.219 + vertex 697.568 137.17 303.659 + endloop + endfacet + facet normal 0.362587 -0.838213 -0.407344 + outer loop + vertex 703.169 133.096 311.155 + vertex 700.676 131.98 311.232 + vertex 702.822 133.792 309.414 + endloop + endfacet + facet normal 0.377019 -0.839398 -0.391493 + outer loop + vertex 702.822 133.792 309.414 + vertex 700.676 131.98 311.232 + vertex 700.232 132.643 309.383 + endloop + endfacet + facet normal 0.35701 -0.822371 -0.443001 + outer loop + vertex 706.75 134.677 311.106 + vertex 703.169 133.096 311.155 + vertex 706.47 135.455 309.435 + endloop + endfacet + facet normal 0.380835 -0.829926 -0.407662 + outer loop + vertex 706.47 135.455 309.435 + vertex 703.169 133.096 311.155 + vertex 702.822 133.792 309.414 + endloop + endfacet + facet normal 0.383415 -0.914824 0.126845 + outer loop + vertex 702.977 133.056 315.149 + vertex 700.548 132.051 315.244 + vertex 703.156 132.838 313.032 + endloop + endfacet + facet normal 0.394481 -0.907806 0.142385 + outer loop + vertex 703.156 132.838 313.032 + vertex 700.548 132.051 315.244 + vertex 700.752 131.809 313.134 + endloop + endfacet + facet normal 0.38026 -0.918712 0.106636 + outer loop + vertex 706.561 134.531 315.075 + vertex 702.977 133.056 315.149 + vertex 706.724 134.354 312.966 + endloop + endfacet + facet normal 0.389878 -0.912052 0.127105 + outer loop + vertex 706.724 134.354 312.966 + vertex 702.977 133.056 315.149 + vertex 703.156 132.838 313.032 + endloop + endfacet + facet normal 0.384131 -0.910567 -0.15268 + outer loop + vertex 706.724 134.354 312.966 + vertex 703.156 132.838 313.032 + vertex 706.75 134.677 311.106 + endloop + endfacet + facet normal 0.39951 -0.908566 -0.122065 + outer loop + vertex 706.75 134.677 311.106 + vertex 703.156 132.838 313.032 + vertex 703.169 133.096 311.155 + endloop + endfacet + facet normal 0.38595 -0.91429 -0.122946 + outer loop + vertex 703.156 132.838 313.032 + vertex 700.752 131.809 313.134 + vertex 703.169 133.096 311.155 + endloop + endfacet + facet normal 0.404079 -0.909493 -0.0976846 + outer loop + vertex 703.169 133.096 311.155 + vertex 700.752 131.809 313.134 + vertex 700.676 131.98 311.232 + endloop + endfacet + facet normal 0.363547 -0.83095 0.421137 + outer loop + vertex 703.189 135.284 320.133 + vertex 700.524 133.917 319.736 + vertex 702.872 133.802 317.482 + endloop + endfacet + facet normal 0.353716 -0.840041 0.411359 + outer loop + vertex 702.872 133.802 317.482 + vertex 700.524 133.917 319.736 + vertex 700.351 132.779 317.562 + endloop + endfacet + facet normal 0.344723 -0.840381 0.418241 + outer loop + vertex 706.926 136.581 319.659 + vertex 703.189 135.284 320.133 + vertex 706.514 135.295 317.415 + endloop + endfacet + facet normal 0.350138 -0.83479 0.424887 + outer loop + vertex 706.514 135.295 317.415 + vertex 703.189 135.284 320.133 + vertex 702.872 133.802 317.482 + endloop + endfacet + facet normal 0.367111 -0.882063 0.295287 + outer loop + vertex 706.514 135.295 317.415 + vertex 702.872 133.802 317.482 + vertex 706.561 134.531 315.075 + endloop + endfacet + facet normal 0.368541 -0.880578 0.297928 + outer loop + vertex 706.561 134.531 315.075 + vertex 702.872 133.802 317.482 + vertex 702.977 133.056 315.149 + endloop + endfacet + facet normal 0.366845 -0.88124 0.298063 + outer loop + vertex 702.872 133.802 317.482 + vertex 700.351 132.779 317.562 + vertex 702.977 133.056 315.149 + endloop + endfacet + facet normal 0.374046 -0.875269 0.306583 + outer loop + vertex 702.977 133.056 315.149 + vertex 700.351 132.779 317.562 + vertex 700.548 132.051 315.244 + endloop + endfacet + facet normal 0.455623 -0.475805 -0.752342 + outer loop + vertex 696.718 143.339 299.085 + vertex 696.907 142.065 300.006 + vertex 695.13 142.175 298.859 + endloop + endfacet + facet normal 0.430471 -0.492099 -0.756659 + outer loop + vertex 697.698 139.637 302.034 + vertex 695.376 139.651 300.704 + vertex 696.907 142.065 300.006 + endloop + endfacet + facet normal 0.447637 -0.4988 -0.742172 + outer loop + vertex 695.376 139.651 300.704 + vertex 695.13 142.175 298.859 + vertex 696.907 142.065 300.006 + endloop + endfacet + facet normal 0.239196 -0.542908 -0.805007 + outer loop + vertex 697.568 137.17 303.659 + vertex 696.75 136.126 304.12 + vertex 697.698 139.637 302.034 + endloop + endfacet + facet normal 0.414279 -0.544979 -0.728952 + outer loop + vertex 697.698 139.637 302.034 + vertex 696.75 136.126 304.12 + vertex 695.376 139.651 300.704 + endloop + endfacet + facet normal 0.335868 -0.588125 -0.735732 + outer loop + vertex 697.568 137.17 303.659 + vertex 698.254 135.611 305.219 + vertex 696.75 136.126 304.12 + endloop + endfacet + facet normal 0.27971 -0.664232 -0.693223 + outer loop + vertex 697.868 133.485 307.102 + vertex 696.75 136.126 304.12 + vertex 698.096 133.646 307.04 + endloop + endfacet + facet normal 0.278565 -0.664779 -0.69316 + outer loop + vertex 698.254 135.611 305.219 + vertex 698.096 133.646 307.04 + vertex 696.75 136.126 304.12 + endloop + endfacet + facet normal 0.239249 -0.886934 -0.395106 + outer loop + vertex 699.453 131.476 311.252 + vertex 699.068 131.418 311.149 + vertex 698.947 132.224 309.268 + endloop + endfacet + facet normal 0.126065 -0.909001 -0.397271 + outer loop + vertex 698.947 132.224 309.268 + vertex 699.068 131.418 311.149 + vertex 698.585 132.25 309.093 + endloop + endfacet + facet normal 0.345206 -0.854061 -0.389117 + outer loop + vertex 700.676 131.98 311.232 + vertex 699.453 131.476 311.252 + vertex 700.232 132.643 309.383 + endloop + endfacet + facet normal 0.316127 -0.858416 -0.403962 + outer loop + vertex 700.232 132.643 309.383 + vertex 699.453 131.476 311.252 + vertex 698.947 132.224 309.268 + endloop + endfacet + facet normal 0.523495 -0.839838 0.143611 + outer loop + vertex 699.466 131.559 315.244 + vertex 699.133 131.311 315.012 + vertex 699.613 131.296 313.174 + endloop + endfacet + facet normal 0.393292 -0.912786 0.110197 + outer loop + vertex 699.613 131.296 313.174 + vertex 699.133 131.311 315.012 + vertex 699.272 131.137 313.069 + endloop + endfacet + facet normal 0.410262 -0.900672 0.143093 + outer loop + vertex 700.548 132.051 315.244 + vertex 699.466 131.559 315.244 + vertex 700.752 131.809 313.134 + endloop + endfacet + facet normal 0.410539 -0.900515 0.14328 + outer loop + vertex 700.752 131.809 313.134 + vertex 699.466 131.559 315.244 + vertex 699.613 131.296 313.174 + endloop + endfacet + facet normal 0.405774 -0.908738 -0.097685 + outer loop + vertex 700.752 131.809 313.134 + vertex 699.613 131.296 313.174 + vertex 700.676 131.98 311.232 + endloop + endfacet + facet normal 0.376324 -0.919016 -0.117428 + outer loop + vertex 700.676 131.98 311.232 + vertex 699.613 131.296 313.174 + vertex 699.453 131.476 311.252 + endloop + endfacet + facet normal 0.45081 -0.884462 -0.120402 + outer loop + vertex 699.613 131.296 313.174 + vertex 699.272 131.137 313.069 + vertex 699.453 131.476 311.252 + endloop + endfacet + facet normal 0.18885 -0.968535 -0.1621 + outer loop + vertex 699.453 131.476 311.252 + vertex 699.272 131.137 313.069 + vertex 699.068 131.418 311.149 + endloop + endfacet + facet normal 0.393242 -0.817997 0.419811 + outer loop + vertex 698.942 133.479 320.134 + vertex 698.068 132.79 319.61 + vertex 699.149 132.26 317.566 + endloop + endfacet + facet normal 0.386609 -0.822364 0.417434 + outer loop + vertex 699.149 132.26 317.566 + vertex 698.068 132.79 319.61 + vertex 698.753 131.88 317.184 + endloop + endfacet + facet normal 0.338272 -0.844608 0.414981 + outer loop + vertex 700.524 133.917 319.736 + vertex 698.942 133.479 320.134 + vertex 700.351 132.779 317.562 + endloop + endfacet + facet normal 0.360309 -0.831204 0.423412 + outer loop + vertex 700.351 132.779 317.562 + vertex 698.942 133.479 320.134 + vertex 699.149 132.26 317.566 + endloop + endfacet + facet normal 0.37823 -0.873536 0.306395 + outer loop + vertex 700.351 132.779 317.562 + vertex 699.149 132.26 317.566 + vertex 700.548 132.051 315.244 + endloop + endfacet + facet normal 0.393505 -0.863775 0.314717 + outer loop + vertex 700.548 132.051 315.244 + vertex 699.149 132.26 317.566 + vertex 699.466 131.559 315.244 + endloop + endfacet + facet normal 0.483001 -0.817762 0.31301 + outer loop + vertex 699.149 132.26 317.566 + vertex 698.753 131.88 317.184 + vertex 699.466 131.559 315.244 + endloop + endfacet + facet normal 0.426378 -0.853973 0.298214 + outer loop + vertex 699.466 131.559 315.244 + vertex 698.753 131.88 317.184 + vertex 699.133 131.311 315.012 + endloop + endfacet + facet normal 0.336624 -0.802081 0.493305 + outer loop + vertex 698.068 132.79 319.61 + vertex 698.942 133.479 320.134 + vertex 697.062 134.169 322.539 + endloop + endfacet + facet normal 0.345428 -0.796322 0.496539 + outer loop + vertex 700.524 133.917 319.736 + vertex 699.926 135.695 323.004 + vertex 698.942 133.479 320.134 + endloop + endfacet + facet normal 0.343762 -0.796567 0.497301 + outer loop + vertex 699.926 135.695 323.004 + vertex 697.062 134.169 322.539 + vertex 698.942 133.479 320.134 + endloop + endfacet + facet normal 0.266496 -0.621156 0.736984 + outer loop + vertex 697.538 156.16 346.662 + vertex 692.909 153.68 346.245 + vertex 697.516 152.237 343.363 + endloop + endfacet + facet normal 0.26368 -0.62525 0.734531 + outer loop + vertex 697.516 152.237 343.363 + vertex 692.909 153.68 346.245 + vertex 693.759 150.254 343.024 + endloop + endfacet + facet normal 0.253755 -0.581549 0.772923 + outer loop + vertex 697.986 160.894 350.076 + vertex 693.092 157.881 349.416 + vertex 697.538 156.16 346.662 + endloop + endfacet + facet normal 0.247308 -0.590576 0.768153 + outer loop + vertex 697.538 156.16 346.662 + vertex 693.092 157.881 349.416 + vertex 692.909 153.68 346.245 + endloop + endfacet + facet normal 0.232652 -0.517848 0.823229 + outer loop + vertex 696.587 165.575 353.416 + vertex 692.153 162.075 352.468 + vertex 697.986 160.894 350.076 + endloop + endfacet + facet normal 0.223208 -0.540337 0.811304 + outer loop + vertex 697.986 160.894 350.076 + vertex 692.153 162.075 352.468 + vertex 693.092 157.881 349.416 + endloop + endfacet + facet normal 0.206131 -0.440298 0.87387 + outer loop + vertex 695.746 170.004 355.846 + vertex 692.115 166.687 355.032 + vertex 696.587 165.575 353.416 + endloop + endfacet + facet normal 0.191789 -0.475627 0.858485 + outer loop + vertex 696.587 165.575 353.416 + vertex 692.115 166.687 355.032 + vertex 692.153 162.075 352.468 + endloop + endfacet + facet normal 0.172035 -0.369943 0.912987 + outer loop + vertex 694.606 173.622 357.527 + vertex 691.38 170.841 357.008 + vertex 695.746 170.004 355.846 + endloop + endfacet + facet normal 0.163246 -0.4002 0.901771 + outer loop + vertex 695.746 170.004 355.846 + vertex 691.38 170.841 357.008 + vertex 692.115 166.687 355.032 + endloop + endfacet + facet normal 0.142949 -0.298763 0.943561 + outer loop + vertex 695.527 177.794 358.708 + vertex 691.601 175.241 358.495 + vertex 694.606 173.622 357.527 + endloop + endfacet + facet normal 0.127829 -0.32328 0.93763 + outer loop + vertex 694.606 173.622 357.527 + vertex 691.601 175.241 358.495 + vertex 691.38 170.841 357.008 + endloop + endfacet + facet normal 0.120612 -0.243707 0.96232 + outer loop + vertex 696.205 183.614 360.097 + vertex 691.136 179.894 359.791 + vertex 695.527 177.794 358.708 + endloop + endfacet + facet normal 0.114191 -0.2559 0.959935 + outer loop + vertex 695.527 177.794 358.708 + vertex 691.136 179.894 359.791 + vertex 691.601 175.241 358.495 + endloop + endfacet + facet normal 0.0897684 -0.177905 0.979945 + outer loop + vertex 694.536 188.492 361.136 + vertex 690.801 185.424 360.921 + vertex 696.205 183.614 360.097 + endloop + endfacet + facet normal 0.0837398 -0.194691 0.977284 + outer loop + vertex 696.205 183.614 360.097 + vertex 690.801 185.424 360.921 + vertex 691.136 179.894 359.791 + endloop + endfacet + facet normal 0.403883 -0.811188 -0.422908 + outer loop + vertex 699.068 131.418 311.149 + vertex 698.662 131.354 310.885 + vertex 698.585 132.25 309.093 + endloop + endfacet + facet normal 0.276858 -0.85466 -0.439211 + outer loop + vertex 698.585 132.25 309.093 + vertex 698.662 131.354 310.885 + vertex 698.327 132.318 308.798 + endloop + endfacet + facet normal 0.495754 -0.861091 0.112915 + outer loop + vertex 699.133 131.311 315.012 + vertex 698.73 131.015 314.524 + vertex 699.272 131.137 313.069 + endloop + endfacet + facet normal 0.308894 -0.950422 0.0358194 + outer loop + vertex 699.272 131.137 313.069 + vertex 698.73 131.015 314.524 + vertex 698.725 130.952 312.896 + endloop + endfacet + facet normal 0.363252 -0.915507 -0.172903 + outer loop + vertex 699.272 131.137 313.069 + vertex 698.725 130.952 312.896 + vertex 699.068 131.418 311.149 + endloop + endfacet + facet normal 0.277256 -0.940498 -0.196449 + outer loop + vertex 699.068 131.418 311.149 + vertex 698.725 130.952 312.896 + vertex 698.662 131.354 310.885 + endloop + endfacet + facet normal 0.385839 -0.822761 0.417365 + outer loop + vertex 698.068 132.79 319.61 + vertex 697.416 131.949 318.556 + vertex 698.753 131.88 317.184 + endloop + endfacet + facet normal 0.333797 -0.867459 0.368909 + outer loop + vertex 698.753 131.88 317.184 + vertex 697.416 131.949 318.556 + vertex 697.896 131.239 316.451 + endloop + endfacet + facet normal 0.396361 -0.86878 0.296849 + outer loop + vertex 698.753 131.88 317.184 + vertex 697.896 131.239 316.451 + vertex 699.133 131.311 315.012 + endloop + endfacet + facet normal 0.351088 -0.90057 0.256341 + outer loop + vertex 699.133 131.311 315.012 + vertex 697.896 131.239 316.451 + vertex 698.73 131.015 314.524 + endloop + endfacet + facet normal 0.230795 -0.606711 -0.760681 + outer loop + vertex 846.2 240.098 297.781 + vertex 848.339 242.413 296.583 + vertex 846.605 239.731 298.196 + endloop + endfacet + facet normal 0.124299 -0.534189 -0.836177 + outer loop + vertex 843.374 237.315 299.138 + vertex 846.2 240.098 297.781 + vertex 844.545 237.593 299.134 + endloop + endfacet + facet normal 0.11454 -0.478702 -0.870474 + outer loop + vertex 839.574 233.255 300.871 + vertex 843.374 237.315 299.138 + vertex 842.532 235.685 299.924 + endloop + endfacet + facet normal -0.059175 -0.292897 -0.954311 + outer loop + vertex 835.212 229.457 302.307 + vertex 839.574 233.255 300.871 + vertex 835.323 227.14 303.011 + endloop + endfacet + facet normal 0.00480929 -0.290612 -0.956829 + outer loop + vertex 831.667 225.337 303.541 + vertex 835.212 229.457 302.307 + vertex 835.323 227.14 303.011 + endloop + endfacet + facet normal -0.0329861 -0.215855 -0.975868 + outer loop + vertex 828.209 222.127 304.368 + vertex 831.667 225.337 303.541 + vertex 828.495 220.483 304.722 + endloop + endfacet + facet normal 0.00588379 -0.209494 -0.977792 + outer loop + vertex 824.508 218.6 305.101 + vertex 828.209 222.127 304.368 + vertex 828.495 220.483 304.722 + endloop + endfacet + facet normal 0.0219112 -0.18904 -0.981725 + outer loop + vertex 820.248 214.592 305.778 + vertex 824.508 218.6 305.101 + vertex 822.231 214.413 305.856 + endloop + endfacet + facet normal -0.000899465 -0.136442 -0.990648 + outer loop + vertex 816.764 212.409 306.081 + vertex 820.248 214.592 305.778 + vertex 815.976 209.208 306.523 + endloop + endfacet + facet normal 0.0279545 -0.143358 -0.989276 + outer loop + vertex 812.005 207.978 306.589 + vertex 816.764 212.409 306.081 + vertex 815.976 209.208 306.523 + endloop + endfacet + facet normal 0.0380778 -0.125336 -0.991383 + outer loop + vertex 806.507 203.292 306.97 + vertex 812.005 207.978 306.589 + vertex 809.125 203.236 307.078 + endloop + endfacet + facet normal 0.0380584 -0.103001 -0.993953 + outer loop + vertex 803.021 200.419 307.134 + vertex 806.507 203.292 306.97 + vertex 802.448 198.221 307.34 + endloop + endfacet + facet normal 0.127407 -0.128938 -0.983434 + outer loop + vertex 738.379 162.823 306.185 + vertex 744.116 165.181 306.619 + vertex 737.847 160.294 306.447 + endloop + endfacet + facet normal 0.150672 -0.133434 -0.979537 + outer loop + vertex 732.798 159.632 305.761 + vertex 738.379 162.823 306.185 + vertex 737.847 160.294 306.447 + endloop + endfacet + facet normal 0.186413 -0.176609 -0.966467 + outer loop + vertex 726.341 156.605 305.069 + vertex 732.798 159.632 305.761 + vertex 728.736 155.896 305.66 + endloop + endfacet + facet normal 0.201534 -0.16701 -0.965138 + outer loop + vertex 721.204 154.832 304.303 + vertex 726.341 156.605 305.069 + vertex 720.486 152.807 304.503 + endloop + endfacet + facet normal 0.241503 -0.180054 -0.95355 + outer loop + vertex 716.291 152.469 303.505 + vertex 721.204 154.832 304.303 + vertex 720.486 152.807 304.503 + endloop + endfacet + facet normal 0.293845 -0.26049 -0.919674 + outer loop + vertex 710.332 150.037 302.29 + vertex 716.291 152.469 303.505 + vertex 713.044 149.925 303.188 + endloop + endfacet + facet normal 0.358602 -0.344447 -0.867618 + outer loop + vertex 704.718 147.28 301.064 + vertex 710.332 150.037 302.29 + vertex 707.184 147.595 301.958 + endloop + endfacet + facet normal 0.406788 -0.4408 -0.800137 + outer loop + vertex 701.069 145.836 300.004 + vertex 704.718 147.28 301.064 + vertex 701.069 145.573 300.149 + endloop + endfacet + facet normal 0.453455 -0.51505 -0.727394 + outer loop + vertex 693.645 143.512 297.054 + vertex 696.323 144.017 298.366 + vertex 695.818 143.482 298.43 + endloop + endfacet + facet normal 0.314865 -0.799752 0.511133 + outer loop + vertex 692.043 133.168 324.065 + vertex 695.719 132.51 320.77 + vertex 697.062 134.169 322.539 + endloop + endfacet + facet normal 0.302131 -0.769068 0.56325 + outer loop + vertex 691.749 136.633 328.953 + vertex 692.043 133.168 324.065 + vertex 696.325 136.606 326.463 + endloop + endfacet + facet normal 0.291864 -0.744681 0.600221 + outer loop + vertex 690.358 139.809 333.57 + vertex 691.749 136.633 328.953 + vertex 695.863 139.937 331.052 + endloop + endfacet + facet normal 0.279346 -0.716218 0.639529 + outer loop + vertex 690.647 143.731 337.836 + vertex 690.358 139.809 333.57 + vertex 695.105 143.475 335.602 + endloop + endfacet + facet normal 0.173191 -0.435762 0.883242 + outer loop + vertex 688.879 167.337 355.987 + vertex 688.22 163.729 354.336 + vertex 692.115 166.687 355.032 + endloop + endfacet + facet normal 0.152187 -0.375157 0.914383 + outer loop + vertex 687.611 169.439 357.06 + vertex 688.879 167.337 355.987 + vertex 691.38 170.841 357.008 + endloop + endfacet + facet normal 0.139972 -0.341781 0.929297 + outer loop + vertex 688.764 172.602 358.05 + vertex 687.611 169.439 357.06 + vertex 691.38 170.841 357.008 + endloop + endfacet + facet normal 0.123745 -0.257351 0.958362 + outer loop + vertex 687.839 178.553 359.856 + vertex 688.033 175.726 359.072 + vertex 691.136 179.894 359.791 + endloop + endfacet + facet normal 0.455235 -0.494392 -0.740499 + outer loop + vertex 693.508 140.577 298.93 + vertex 693.645 143.512 297.054 + vertex 695.13 142.175 298.859 + endloop + endfacet + facet normal 0.43582 -0.52379 -0.731918 + outer loop + vertex 693.724 138.801 300.329 + vertex 693.508 140.577 298.93 + vertex 695.376 139.651 300.704 + endloop + endfacet + facet normal 0.44048 -0.53899 -0.71796 + outer loop + vertex 694.688 137.195 302.126 + vertex 693.724 138.801 300.329 + vertex 695.376 139.651 300.704 + endloop + endfacet + facet normal 0.387089 -0.58425 -0.713312 + outer loop + vertex 695.457 135.352 304.053 + vertex 694.688 137.195 302.126 + vertex 696.75 136.126 304.12 + endloop + endfacet + facet normal 0.397788 -0.604092 -0.690534 + outer loop + vertex 696.825 133.892 306.118 + vertex 695.457 135.352 304.053 + vertex 696.75 136.126 304.12 + endloop + endfacet + facet normal 0.258584 -0.73383 -0.628194 + outer loop + vertex 697.556 132.513 308.03 + vertex 696.825 133.892 306.118 + vertex 697.971 133.11 307.504 + endloop + endfacet + facet normal 0.340063 -0.771671 -0.537477 + outer loop + vertex 697.212 131.012 309.968 + vertex 697.556 132.513 308.03 + vertex 698.327 132.318 308.798 + endloop + endfacet + facet normal 0.43275 -0.818094 -0.378747 + outer loop + vertex 697.764 130.708 311.254 + vertex 697.212 131.012 309.968 + vertex 698.662 131.354 310.885 + endloop + endfacet + facet normal 0.549649 -0.827954 -0.111259 + outer loop + vertex 697.525 130.378 312.526 + vertex 697.764 130.708 311.254 + vertex 698.662 131.354 310.885 + endloop + endfacet + facet normal 0.402895 -0.909323 0.10396 + outer loop + vertex 696.059 129.983 314.748 + vertex 697.525 130.378 312.526 + vertex 698.725 130.952 312.896 + endloop + endfacet + facet normal 0.325889 -0.893943 0.307671 + outer loop + vertex 693.621 130.227 318.04 + vertex 696.059 129.983 314.748 + vertex 697.896 131.239 316.451 + endloop + endfacet + facet normal 0.316462 -0.833224 0.45342 + outer loop + vertex 695.719 132.51 320.77 + vertex 693.621 130.227 318.04 + vertex 697.416 131.949 318.556 + endloop + endfacet + facet normal 0.143267 -0.156399 0.977248 + outer loop + vertex 855.335 284.231 360.557 + vertex 855.55 287.78 361.093 + vertex 852.507 285.068 361.105 + endloop + endfacet + facet normal 0.164359 -0.175972 0.970577 + outer loop + vertex 855.595 281.484 360.015 + vertex 855.335 284.231 360.557 + vertex 852.965 279.628 360.123 + endloop + endfacet + facet normal 0.199186 -0.2263 0.953474 + outer loop + vertex 855.954 278.862 359.317 + vertex 855.595 281.484 360.015 + vertex 852.965 279.628 360.123 + endloop + endfacet + facet normal 0.251793 -0.25015 0.934893 + outer loop + vertex 856.563 274.739 358.05 + vertex 855.954 278.862 359.317 + vertex 853.185 274.49 358.893 + endloop + endfacet + facet normal 0.266069 -0.28667 0.920341 + outer loop + vertex 856.949 271.886 357.05 + vertex 856.563 274.739 358.05 + vertex 854.133 269.956 357.263 + endloop + endfacet + facet normal 0.307118 -0.350495 0.884778 + outer loop + vertex 857.111 269.243 355.946 + vertex 856.949 271.886 357.05 + vertex 854.133 269.956 357.263 + endloop + endfacet + facet normal 0.351043 -0.374903 0.85803 + outer loop + vertex 857.162 265.679 354.369 + vertex 857.111 269.243 355.946 + vertex 854.208 265.256 355.392 + endloop + endfacet + facet normal 0.394952 -0.42609 0.813917 + outer loop + vertex 858.351 264.271 353.054 + vertex 857.162 265.679 354.369 + vertex 855.209 261.301 353.025 + endloop + endfacet + facet normal 0.41808 -0.450316 0.788939 + outer loop + vertex 858.343 260.824 351.091 + vertex 858.351 264.271 353.054 + vertex 855.209 261.301 353.025 + endloop + endfacet + facet normal 0.446674 -0.476086 0.757512 + outer loop + vertex 858.394 257.436 348.932 + vertex 858.343 260.824 351.091 + vertex 855.4 256.831 350.317 + endloop + endfacet + facet normal 0.477209 -0.509382 0.716102 + outer loop + vertex 859.627 256.239 347.258 + vertex 858.394 257.436 348.932 + vertex 856.465 253.253 347.241 + endloop + endfacet + facet normal 0.493242 -0.526228 0.692674 + outer loop + vertex 859.623 253.116 344.889 + vertex 859.627 256.239 347.258 + vertex 856.465 253.253 347.241 + endloop + endfacet + facet normal 0.543683 -0.576453 0.610009 + outer loop + vertex 860.857 246.312 337.84 + vertex 860.83 249.058 340.46 + vertex 857.7 245.973 340.334 + endloop + endfacet + facet normal 0.56423 -0.615792 0.549949 + outer loop + vertex 861.539 241.023 331.568 + vertex 861.286 242.693 333.697 + vertex 858.684 238.963 332.19 + endloop + endfacet + facet normal 0.618897 -0.655951 0.432083 + outer loop + vertex 861.529 236.695 325.338 + vertex 861.599 239.415 329.365 + vertex 858.335 235.559 328.187 + endloop + endfacet + facet normal 0.653567 -0.672823 0.346641 + outer loop + vertex 861.149 233.867 320.564 + vertex 861.529 236.695 325.338 + vertex 858.317 232.568 323.383 + endloop + endfacet + facet normal 0.92952 -0.368767 0.00171982 + outer loop + vertex 860.585 232.432 317.629 + vertex 861.149 233.867 320.564 + vertex 860.646 232.59 318.575 + endloop + endfacet + facet normal 0.782074 -0.610571 -0.124754 + outer loop + vertex 859.425 231.508 314.882 + vertex 860.585 232.432 317.629 + vertex 860.015 231.817 317.062 + endloop + endfacet + facet normal 0.766921 -0.52344 -0.371272 + outer loop + vertex 857.753 231.143 311.94 + vertex 859.425 231.508 314.882 + vertex 858.098 230.679 313.308 + endloop + endfacet + facet normal 0.647008 -0.540847 -0.537461 + outer loop + vertex 856.19 231.515 309.685 + vertex 857.753 231.143 311.94 + vertex 856.624 230.682 311.046 + endloop + endfacet + facet normal 0.553322 -0.513199 -0.656096 + outer loop + vertex 854.613 232.502 307.583 + vertex 856.19 231.515 309.685 + vertex 855.138 231.302 308.965 + endloop + endfacet + facet normal 0.292572 -0.613004 -0.733912 + outer loop + vertex 848.339 242.413 296.583 + vertex 849.46 240.007 299.039 + vertex 847.595 239.544 298.683 + endloop + endfacet + facet normal 0.515397 -0.647821 -0.560976 + outer loop + vertex 856.624 230.682 311.046 + vertex 855.138 231.302 308.965 + vertex 856.19 231.515 309.685 + endloop + endfacet + facet normal 0.466904 -0.57204 -0.674367 + outer loop + vertex 855.138 231.302 308.965 + vertex 853.694 232.427 307.011 + vertex 854.613 232.502 307.583 + endloop + endfacet + facet normal 0.70378 -0.667967 -0.241898 + outer loop + vertex 859.143 231.043 315.344 + vertex 858.098 230.679 313.308 + vertex 859.425 231.508 314.882 + endloop + endfacet + facet normal 0.595493 -0.702969 -0.388874 + outer loop + vertex 858.098 230.679 313.308 + vertex 856.624 230.682 311.046 + vertex 857.753 231.143 311.94 + endloop + endfacet + facet normal 0.662893 -0.695008 0.278454 + outer loop + vertex 859.799 232.107 319.385 + vertex 860.646 232.59 318.575 + vertex 861.149 233.867 320.564 + endloop + endfacet + facet normal 0.695817 -0.714325 0.0746886 + outer loop + vertex 860.646 232.59 318.575 + vertex 860.015 231.817 317.062 + vertex 860.585 232.432 317.629 + endloop + endfacet + facet normal 0.786831 -0.603965 -0.126976 + outer loop + vertex 860.015 231.817 317.062 + vertex 859.143 231.043 315.344 + vertex 859.425 231.508 314.882 + endloop + endfacet + facet normal 0.110679 -0.477315 -0.871734 + outer loop + vertex 844.545 237.593 299.134 + vertex 842.532 235.685 299.924 + vertex 843.374 237.315 299.138 + endloop + endfacet + facet normal 0.0830998 -0.448088 -0.890119 + outer loop + vertex 842.532 235.685 299.924 + vertex 841.512 233.122 301.119 + vertex 839.574 233.255 300.871 + endloop + endfacet + facet normal 0.252177 -0.613248 -0.748554 + outer loop + vertex 847.595 239.544 298.683 + vertex 846.605 239.731 298.196 + vertex 848.339 242.413 296.583 + endloop + endfacet + facet normal 0.257711 -0.585759 -0.768421 + outer loop + vertex 846.605 239.731 298.196 + vertex 844.545 237.593 299.134 + vertex 846.2 240.098 297.781 + endloop + endfacet + facet normal 0.288564 -0.56917 -0.76992 + outer loop + vertex 847.756 236.464 301.02 + vertex 847.595 239.544 298.683 + vertex 849.46 240.007 299.039 + endloop + endfacet + facet normal 0.637745 -0.701815 0.317392 + outer loop + vertex 858.317 232.568 323.383 + vertex 859.799 232.107 319.385 + vertex 861.149 233.867 320.564 + endloop + endfacet + facet normal 0.490997 -0.531827 0.689986 + outer loop + vertex 856.465 253.253 347.241 + vertex 856.647 249.159 343.957 + vertex 859.623 253.116 344.889 + endloop + endfacet + facet normal 0.444456 -0.504136 0.740477 + outer loop + vertex 855.4 256.831 350.317 + vertex 856.465 253.253 347.241 + vertex 858.394 257.436 348.932 + endloop + endfacet + facet normal 0.415027 -0.458282 0.785958 + outer loop + vertex 855.209 261.301 353.025 + vertex 855.4 256.831 350.317 + vertex 858.343 260.824 351.091 + endloop + endfacet + facet normal 0.350427 -0.414234 0.840007 + outer loop + vertex 854.208 265.256 355.392 + vertex 855.209 261.301 353.025 + vertex 857.162 265.679 354.369 + endloop + endfacet + facet normal 0.308183 -0.347525 0.885579 + outer loop + vertex 854.133 269.956 357.263 + vertex 854.208 265.256 355.392 + vertex 857.111 269.243 355.946 + endloop + endfacet + facet normal 0.251866 -0.280424 0.926243 + outer loop + vertex 853.185 274.49 358.893 + vertex 854.133 269.956 357.263 + vertex 856.563 274.739 358.05 + endloop + endfacet + facet normal 0.201105 -0.219951 0.954557 + outer loop + vertex 852.965 279.628 360.123 + vertex 853.185 274.49 358.893 + vertex 855.954 278.862 359.317 + endloop + endfacet + facet normal 0.140731 -0.164349 0.976311 + outer loop + vertex 852.507 285.068 361.105 + vertex 852.965 279.628 360.123 + vertex 855.335 284.231 360.557 + endloop + endfacet + facet normal 0.0910898 -0.384827 -0.918483 + outer loop + vertex 841.512 233.122 301.119 + vertex 835.323 227.14 303.011 + vertex 839.574 233.255 300.871 + endloop + endfacet + facet normal -0.0356981 -0.214151 -0.976148 + outer loop + vertex 835.323 227.14 303.011 + vertex 828.495 220.483 304.722 + vertex 831.667 225.337 303.541 + endloop + endfacet + facet normal -0.0131922 -0.17059 -0.985254 + outer loop + vertex 828.495 220.483 304.722 + vertex 822.231 214.413 305.856 + vertex 824.508 218.6 305.101 + endloop + endfacet + facet normal 0.0250605 -0.156584 -0.987347 + outer loop + vertex 822.231 214.413 305.856 + vertex 815.976 209.208 306.523 + vertex 820.248 214.592 305.778 + endloop + endfacet + facet normal 0.0187271 -0.113784 -0.993329 + outer loop + vertex 815.976 209.208 306.523 + vertex 809.125 203.236 307.078 + vertex 812.005 207.978 306.589 + endloop + endfacet + facet normal 0.0386531 -0.103472 -0.993881 + outer loop + vertex 809.125 203.236 307.078 + vertex 802.448 198.221 307.34 + vertex 806.507 203.292 306.97 + endloop + endfacet + facet normal 0.0499767 -0.0967861 -0.99405 + outer loop + vertex 802.448 198.221 307.34 + vertex 794.841 192.701 307.495 + vertex 799.175 197.774 307.219 + endloop + endfacet + facet normal 0.0705803 -0.095947 -0.992881 + outer loop + vertex 764.03 173.432 307.487 + vertex 754.907 168.574 307.308 + vertex 759.895 173.201 307.215 + endloop + endfacet + facet normal 0.116791 -0.115213 -0.986451 + outer loop + vertex 746.459 164.097 307.023 + vertex 737.847 160.294 306.447 + vertex 744.116 165.181 306.619 + endloop + endfacet + facet normal 0.15117 -0.13796 -0.978833 + outer loop + vertex 737.847 160.294 306.447 + vertex 728.736 155.896 305.66 + vertex 732.798 159.632 305.761 + endloop + endfacet + facet normal 0.19362 -0.15425 -0.968875 + outer loop + vertex 728.736 155.896 305.66 + vertex 720.486 152.807 304.503 + vertex 726.341 156.605 305.069 + endloop + endfacet + facet normal 0.241831 -0.190155 -0.951503 + outer loop + vertex 720.486 152.807 304.503 + vertex 713.044 149.925 303.188 + vertex 716.291 152.469 303.505 + endloop + endfacet + facet normal 0.294553 -0.254647 -0.921083 + outer loop + vertex 713.044 149.925 303.188 + vertex 707.184 147.595 301.958 + vertex 710.332 150.037 302.29 + endloop + endfacet + facet normal 0.358212 -0.365294 -0.859211 + outer loop + vertex 707.184 147.595 301.958 + vertex 702.463 145.571 300.85 + vertex 704.718 147.28 301.064 + endloop + endfacet + facet normal 0.360122 -0.463372 -0.80969 + outer loop + vertex 704.877 143.891 302.821 + vertex 703.703 140.735 304.105 + vertex 701.074 141.692 302.388 + endloop + endfacet + facet normal 0.339926 -0.79678 0.499592 + outer loop + vertex 706.926 136.581 319.659 + vertex 705.269 138.089 323.191 + vertex 703.189 135.284 320.133 + endloop + endfacet + facet normal 0.260943 -0.62797 0.733187 + outer loop + vertex 703.33 154.593 343.258 + vertex 703.442 158.544 346.602 + vertex 697.538 156.16 346.662 + endloop + endfacet + facet normal 0.230391 -0.598938 0.766937 + outer loop + vertex 703.442 158.544 346.602 + vertex 704.333 161.988 349.024 + vertex 697.986 160.894 350.076 + endloop + endfacet + facet normal 0.227918 -0.54849 0.804495 + outer loop + vertex 704.333 161.988 349.024 + vertex 702.764 165.141 351.618 + vertex 697.986 160.894 350.076 + endloop + endfacet + facet normal 0.213112 -0.483721 0.84888 + outer loop + vertex 702.764 165.141 351.618 + vertex 701.753 169.447 354.326 + vertex 696.587 165.575 353.416 + endloop + endfacet + facet normal 0.190373 -0.397363 0.897697 + outer loop + vertex 701.753 169.447 354.326 + vertex 700.469 174.542 356.853 + vertex 695.746 170.004 355.846 + endloop + endfacet + facet normal 0.137485 -0.324868 0.935713 + outer loop + vertex 700.469 174.542 356.853 + vertex 701.493 180.196 358.666 + vertex 695.527 177.794 358.708 + endloop + endfacet + facet normal 0.0923429 -0.259732 0.961255 + outer loop + vertex 701.493 180.196 358.666 + vertex 702.556 184.674 359.774 + vertex 696.205 183.614 360.097 + endloop + endfacet + facet normal 0.0819033 -0.192102 0.977951 + outer loop + vertex 702.556 184.674 359.774 + vertex 700.614 189.202 360.826 + vertex 696.205 183.614 360.097 + endloop + endfacet + facet normal 0.454572 -0.515944 -0.726062 + outer loop + vertex 698.237 144.481 299.235 + vertex 695.818 143.482 298.43 + vertex 696.323 144.017 298.366 + endloop + endfacet + facet normal 0.462184 -0.486941 -0.741131 + outer loop + vertex 695.818 143.482 298.43 + vertex 696.718 143.339 299.085 + vertex 695.13 142.175 298.859 + endloop + endfacet + facet normal 0.404519 -0.43309 -0.80548 + outer loop + vertex 702.463 145.571 300.85 + vertex 701.069 145.573 300.149 + vertex 704.718 147.28 301.064 + endloop + endfacet + facet normal 0.424596 -0.436861 -0.793014 + outer loop + vertex 701.069 145.573 300.149 + vertex 698.237 144.481 299.235 + vertex 701.069 145.836 300.004 + endloop + endfacet + facet normal 0.386573 -0.502127 -0.773583 + outer loop + vertex 697.698 139.637 302.034 + vertex 701.074 141.692 302.388 + vertex 699.362 138.31 303.727 + endloop + endfacet + facet normal 0.343903 -0.491121 -0.800332 + outer loop + vertex 703.703 140.735 304.105 + vertex 699.362 138.31 303.727 + vertex 701.074 141.692 302.388 + endloop + endfacet + facet normal 0.363214 -0.525792 -0.769167 + outer loop + vertex 699.362 138.31 303.727 + vertex 697.568 137.17 303.659 + vertex 697.698 139.637 302.034 + endloop + endfacet + facet normal 0.336354 -0.799989 0.496874 + outer loop + vertex 700.524 133.917 319.736 + vertex 703.189 135.284 320.133 + vertex 699.926 135.695 323.004 + endloop + endfacet + facet normal 0.456472 -0.495578 -0.738942 + outer loop + vertex 695.13 142.175 298.859 + vertex 695.376 139.651 300.704 + vertex 693.508 140.577 298.93 + endloop + endfacet + facet normal 0.423758 -0.539763 -0.727382 + outer loop + vertex 695.376 139.651 300.704 + vertex 696.75 136.126 304.12 + vertex 694.688 137.195 302.126 + endloop + endfacet + facet normal 0.413168 -0.59925 -0.685705 + outer loop + vertex 696.75 136.126 304.12 + vertex 697.868 133.485 307.102 + vertex 696.825 133.892 306.118 + endloop + endfacet + facet normal 0.339251 -0.800791 0.493601 + outer loop + vertex 698.068 132.79 319.61 + vertex 697.062 134.169 322.539 + vertex 695.719 132.51 320.77 + endloop + endfacet + facet normal 0.310555 -0.754198 0.578568 + outer loop + vertex 696.325 136.606 326.463 + vertex 695.863 139.937 331.052 + vertex 691.749 136.633 328.953 + endloop + endfacet + facet normal 0.298848 -0.7286 0.616305 + outer loop + vertex 695.863 139.937 331.052 + vertex 695.105 143.475 335.602 + vertex 690.358 139.809 333.57 + endloop + endfacet + facet normal 0.288734 -0.697272 0.656083 + outer loop + vertex 695.105 143.475 335.602 + vertex 693.894 146.904 339.78 + vertex 690.647 143.731 337.836 + endloop + endfacet + facet normal 0.265127 -0.621394 0.737277 + outer loop + vertex 697.538 156.16 346.662 + vertex 697.516 152.237 343.363 + vertex 703.33 154.593 343.258 + endloop + endfacet + facet normal 0.268498 -0.623673 0.734126 + outer loop + vertex 693.759 150.254 343.024 + vertex 692.909 153.68 346.245 + vertex 690.575 150.743 344.604 + endloop + endfacet + facet normal 0.243022 -0.5825 0.775651 + outer loop + vertex 697.986 160.894 350.076 + vertex 697.538 156.16 346.662 + vertex 703.442 158.544 346.602 + endloop + endfacet + facet normal 0.202991 -0.527802 0.824754 + outer loop + vertex 696.587 165.575 353.416 + vertex 697.986 160.894 350.076 + vertex 702.764 165.141 351.618 + endloop + endfacet + facet normal 0.249495 -0.532602 0.808757 + outer loop + vertex 693.092 157.881 349.416 + vertex 692.153 162.075 352.468 + vertex 689.484 158.555 350.973 + endloop + endfacet + facet normal 0.180414 -0.446559 0.876377 + outer loop + vertex 695.746 170.004 355.846 + vertex 696.587 165.575 353.416 + vertex 701.753 169.447 354.326 + endloop + endfacet + facet normal 0.207144 -0.47401 0.855807 + outer loop + vertex 692.153 162.075 352.468 + vertex 692.115 166.687 355.032 + vertex 688.22 163.729 354.336 + endloop + endfacet + facet normal 0.163458 -0.372832 0.913388 + outer loop + vertex 694.606 173.622 357.527 + vertex 695.746 170.004 355.846 + vertex 700.469 174.542 356.853 + endloop + endfacet + facet normal 0.186177 -0.395102 0.899573 + outer loop + vertex 692.115 166.687 355.032 + vertex 691.38 170.841 357.008 + vertex 688.879 167.337 355.987 + endloop + endfacet + facet normal 0.155317 -0.30076 0.940968 + outer loop + vertex 695.527 177.794 358.708 + vertex 694.606 173.622 357.527 + vertex 700.469 174.542 356.853 + endloop + endfacet + facet normal 0.154175 -0.323259 0.933667 + outer loop + vertex 691.38 170.841 357.008 + vertex 691.601 175.241 358.495 + vertex 688.764 172.602 358.05 + endloop + endfacet + facet normal 0.104465 -0.242356 0.964547 + outer loop + vertex 696.205 183.614 360.097 + vertex 695.527 177.794 358.708 + vertex 701.493 180.196 358.666 + endloop + endfacet + facet normal 0.120504 -0.255112 0.959373 + outer loop + vertex 691.601 175.241 358.495 + vertex 691.136 179.894 359.791 + vertex 688.033 175.726 359.072 + endloop + endfacet + facet normal 0.0715254 -0.184219 0.980279 + outer loop + vertex 694.536 188.492 361.136 + vertex 696.205 183.614 360.097 + vertex 700.614 189.202 360.826 + endloop + endfacet + facet normal 0.10237 -0.193259 0.975793 + outer loop + vertex 691.136 179.894 359.791 + vertex 690.801 185.424 360.921 + vertex 687.348 181.14 360.435 + endloop + endfacet + facet normal 0.0465879 -0.0875046 0.995074 + outer loop + vertex 691.201 190.57 361.61 + vertex 690.784 195.653 362.076 + vertex 687.156 191.099 361.846 + endloop + endfacet + facet normal 0.457024 -0.777308 -0.432344 + outer loop + vertex 698.327 132.318 308.798 + vertex 698.662 131.354 310.885 + vertex 697.212 131.012 309.968 + endloop + endfacet + facet normal 0.39958 -0.61648 -0.678445 + outer loop + vertex 697.868 133.485 307.102 + vertex 697.971 133.11 307.504 + vertex 696.825 133.892 306.118 + endloop + endfacet + facet normal 0.365992 -0.745589 -0.556908 + outer loop + vertex 697.971 133.11 307.504 + vertex 698.327 132.318 308.798 + vertex 697.556 132.513 308.03 + endloop + endfacet + facet normal 0.362866 -0.931187 0.0348981 + outer loop + vertex 698.725 130.952 312.896 + vertex 698.73 131.015 314.524 + vertex 696.059 129.983 314.748 + endloop + endfacet + facet normal 0.470147 -0.862569 -0.186913 + outer loop + vertex 698.662 131.354 310.885 + vertex 698.725 130.952 312.896 + vertex 697.525 130.378 312.526 + endloop + endfacet + facet normal 0.325026 -0.827155 0.458446 + outer loop + vertex 697.416 131.949 318.556 + vertex 698.068 132.79 319.61 + vertex 695.719 132.51 320.77 + endloop + endfacet + facet normal 0.34183 -0.864037 0.369585 + outer loop + vertex 697.896 131.239 316.451 + vertex 697.416 131.949 318.556 + vertex 693.621 130.227 318.04 + endloop + endfacet + facet normal 0.366965 -0.892495 0.262278 + outer loop + vertex 698.73 131.015 314.524 + vertex 697.896 131.239 316.451 + vertex 696.059 129.983 314.748 + endloop + endfacet + facet normal 0.462423 -0.487005 -0.74094 + outer loop + vertex 693.645 143.512 297.054 + vertex 695.818 143.482 298.43 + vertex 695.13 142.175 298.859 + endloop + endfacet + facet normal 0.33944 -0.79678 0.499923 + outer loop + vertex 703.189 135.284 320.133 + vertex 705.269 138.089 323.191 + vertex 699.926 135.695 323.004 + endloop + endfacet + facet normal 0.394334 -0.629662 -0.669348 + outer loop + vertex 854.908 244.624 297.801 + vertex 854.818 242.468 299.776 + vertex 852.367 242.57 298.236 + endloop + endfacet + facet normal 0.406753 -0.601852 -0.68726 + outer loop + vertex 852.367 242.57 298.236 + vertex 854.818 242.468 299.776 + vertex 852.511 240.564 300.078 + endloop + endfacet + facet normal 0.393405 -0.657099 -0.643003 + outer loop + vertex 855.354 246.288 296.373 + vertex 854.908 244.624 297.801 + vertex 852.576 244.147 296.861 + endloop + endfacet + facet normal 0.397249 -0.632361 -0.665066 + outer loop + vertex 852.576 244.147 296.861 + vertex 854.908 244.624 297.801 + vertex 852.367 242.57 298.236 + endloop + endfacet + facet normal 0.34242 -0.642736 -0.685302 + outer loop + vertex 852.576 244.147 296.861 + vertex 852.367 242.57 298.236 + vertex 850.528 242.419 297.459 + endloop + endfacet + facet normal 0.349788 -0.612868 -0.708549 + outer loop + vertex 850.528 242.419 297.459 + vertex 852.367 242.57 298.236 + vertex 850.908 241.116 298.774 + endloop + endfacet + facet normal 0.357441 -0.617601 -0.700574 + outer loop + vertex 852.367 242.57 298.236 + vertex 852.511 240.564 300.078 + vertex 850.908 241.116 298.774 + endloop + endfacet + facet normal 0.500999 -0.640366 -0.582177 + outer loop + vertex 862.479 251.142 296.872 + vertex 862.663 248.799 299.607 + vertex 858.383 247.443 297.415 + endloop + endfacet + facet normal 0.504703 -0.61687 -0.603942 + outer loop + vertex 858.383 247.443 297.415 + vertex 862.663 248.799 299.607 + vertex 858.033 245.119 299.496 + endloop + endfacet + facet normal 0.522297 -0.685286 -0.507532 + outer loop + vertex 861.957 251.948 295.247 + vertex 862.479 251.142 296.872 + vertex 858.682 249.002 295.854 + endloop + endfacet + facet normal 0.516622 -0.653432 -0.553289 + outer loop + vertex 858.682 249.002 295.854 + vertex 862.479 251.142 296.872 + vertex 858.383 247.443 297.415 + endloop + endfacet + facet normal 0.456822 -0.671789 -0.583107 + outer loop + vertex 858.682 249.002 295.854 + vertex 858.383 247.443 297.415 + vertex 855.354 246.288 296.373 + endloop + endfacet + facet normal 0.456785 -0.646591 -0.610956 + outer loop + vertex 855.354 246.288 296.373 + vertex 858.383 247.443 297.415 + vertex 854.908 244.624 297.801 + endloop + endfacet + facet normal 0.444043 -0.63394 -0.633203 + outer loop + vertex 858.383 247.443 297.415 + vertex 858.033 245.119 299.496 + vertex 854.908 244.624 297.801 + endloop + endfacet + facet normal 0.559064 -0.610757 -0.560735 + outer loop + vertex 862.663 248.799 299.607 + vertex 862.479 251.142 296.872 + vertex 867.771 254.029 299.003 + endloop + endfacet + facet normal 0.568145 -0.649971 -0.504727 + outer loop + vertex 861.957 251.948 295.247 + vertex 866.983 255.937 295.767 + vertex 862.479 251.142 296.872 + endloop + endfacet + facet normal 0.560968 -0.646169 -0.517476 + outer loop + vertex 866.983 255.937 295.767 + vertex 867.771 254.029 299.003 + vertex 862.479 251.142 296.872 + endloop + endfacet + facet normal 0.72371 -0.543391 -0.425406 + outer loop + vertex 883.382 275.557 294.583 + vertex 883.574 273.297 297.796 + vertex 878.434 268.772 294.832 + endloop + endfacet + facet normal 0.724079 -0.548906 -0.417625 + outer loop + vertex 878.434 268.772 294.832 + vertex 883.574 273.297 297.796 + vertex 878.533 266.451 298.055 + endloop + endfacet + facet normal 0.40895 -0.604007 -0.684057 + outer loop + vertex 854.818 242.468 299.776 + vertex 855.074 240.012 302.097 + vertex 852.511 240.564 300.078 + endloop + endfacet + facet normal 0.54795 -0.602198 -0.58061 + outer loop + vertex 867.771 254.029 299.003 + vertex 868.333 250.961 302.716 + vertex 862.663 248.799 299.607 + endloop + endfacet + facet normal 0.693192 -0.528896 -0.489647 + outer loop + vertex 883.574 273.297 297.796 + vertex 884.554 270.886 301.788 + vertex 878.533 266.451 298.055 + endloop + endfacet + facet normal 0.69297 -0.523322 -0.495911 + outer loop + vertex 878.533 266.451 298.055 + vertex 884.554 270.886 301.788 + vertex 879.521 264.033 301.988 + endloop + endfacet + facet normal 0.671461 -0.637244 0.378234 + outer loop + vertex 868.093 242.021 322.647 + vertex 868.179 244.89 327.328 + vertex 864.111 238.135 323.169 + endloop + endfacet + facet normal 0.669511 -0.637709 0.380897 + outer loop + vertex 864.111 238.135 323.169 + vertex 868.179 244.89 327.328 + vertex 864.458 241.392 328.011 + endloop + endfacet + facet normal 0.680645 -0.626553 0.379676 + outer loop + vertex 873.46 247.846 322.638 + vertex 873.018 250.148 327.229 + vertex 868.093 242.021 322.647 + endloop + endfacet + facet normal 0.68688 -0.625198 0.370571 + outer loop + vertex 868.093 242.021 322.647 + vertex 873.018 250.148 327.229 + vertex 868.179 244.89 327.328 + endloop + endfacet + facet normal 0.704328 -0.604999 0.371347 + outer loop + vertex 879.016 254.332 322.666 + vertex 878.41 256.462 327.287 + vertex 873.46 247.846 322.638 + endloop + endfacet + facet normal 0.704463 -0.604967 0.371144 + outer loop + vertex 873.46 247.846 322.638 + vertex 878.41 256.462 327.287 + vertex 873.018 250.148 327.229 + endloop + endfacet + facet normal 0.73809 -0.575469 0.352219 + outer loop + vertex 884.159 260.923 322.658 + vertex 883.641 263.111 327.317 + vertex 879.016 254.332 322.666 + endloop + endfacet + facet normal 0.731712 -0.577405 0.362217 + outer loop + vertex 879.016 254.332 322.666 + vertex 883.641 263.111 327.317 + vertex 878.41 256.462 327.287 + endloop + endfacet + facet normal 0.771117 -0.541711 0.334556 + outer loop + vertex 888.932 267.714 322.651 + vertex 888.442 269.894 327.313 + vertex 884.159 260.923 322.658 + endloop + endfacet + facet normal 0.767675 -0.543035 0.340276 + outer loop + vertex 884.159 260.923 322.658 + vertex 888.442 269.894 327.313 + vertex 883.641 263.111 327.317 + endloop + endfacet + facet normal 0.807318 -0.498775 0.315376 + outer loop + vertex 893.329 274.825 322.643 + vertex 892.801 276.913 327.298 + vertex 888.932 267.714 322.651 + endloop + endfacet + facet normal 0.805576 -0.499613 0.318487 + outer loop + vertex 888.932 267.714 322.651 + vertex 892.801 276.913 327.298 + vertex 888.442 269.894 327.313 + endloop + endfacet + facet normal 0.844228 -0.449174 0.292441 + outer loop + vertex 897.275 282.236 322.636 + vertex 896.724 284.231 327.291 + vertex 893.329 274.825 322.643 + endloop + endfacet + facet normal 0.841502 -0.450807 0.297738 + outer loop + vertex 893.329 274.825 322.643 + vertex 896.724 284.231 327.291 + vertex 892.801 276.913 327.298 + endloop + endfacet + facet normal 0.88022 -0.393669 0.265025 + outer loop + vertex 900.724 289.946 322.634 + vertex 900.168 291.839 327.291 + vertex 897.275 282.236 322.636 + endloop + endfacet + facet normal 0.876198 -0.396675 0.273726 + outer loop + vertex 897.275 282.236 322.636 + vertex 900.168 291.839 327.291 + vertex 896.724 284.231 327.291 + endloop + endfacet + facet normal 0.913498 -0.331555 0.235782 + outer loop + vertex 903.612 297.909 322.641 + vertex 903.061 299.697 327.286 + vertex 900.724 289.946 322.634 + endloop + endfacet + facet normal 0.909906 -0.33495 0.244704 + outer loop + vertex 900.724 289.946 322.634 + vertex 903.061 299.697 327.286 + vertex 900.168 291.839 327.291 + endloop + endfacet + facet normal 0.942676 -0.264446 0.203542 + outer loop + vertex 905.88 306.005 322.652 + vertex 905.358 307.708 327.284 + vertex 903.612 297.909 322.641 + endloop + endfacet + facet normal 0.938874 -0.269075 0.214741 + outer loop + vertex 903.612 297.909 322.641 + vertex 905.358 307.708 327.284 + vertex 903.061 299.697 327.286 + endloop + endfacet + facet normal 0.966584 -0.193128 0.168574 + outer loop + vertex 907.519 314.212 322.66 + vertex 907.033 315.815 327.28 + vertex 905.88 306.005 322.652 + endloop + endfacet + facet normal 0.963016 -0.198921 0.181744 + outer loop + vertex 905.88 306.005 322.652 + vertex 907.033 315.815 327.28 + vertex 905.358 307.708 327.284 + endloop + endfacet + facet normal 0.983322 -0.123757 0.133275 + outer loop + vertex 908.562 322.497 322.66 + vertex 908.123 323.984 327.28 + vertex 907.519 314.212 322.66 + endloop + endfacet + facet normal 0.980261 -0.130694 0.148349 + outer loop + vertex 907.519 314.212 322.66 + vertex 908.123 323.984 327.28 + vertex 907.033 315.815 327.28 + endloop + endfacet + facet normal 0.652649 -0.605145 0.455905 + outer loop + vertex 868.179 244.89 327.328 + vertex 867.87 247.721 331.528 + vertex 864.458 241.392 328.011 + endloop + endfacet + facet normal 0.641773 -0.606646 0.469157 + outer loop + vertex 864.458 241.392 328.011 + vertex 867.87 247.721 331.528 + vertex 863.87 243.882 332.035 + endloop + endfacet + facet normal 0.660964 -0.599828 0.450925 + outer loop + vertex 873.018 250.148 327.229 + vertex 872.561 252.818 331.45 + vertex 868.179 244.89 327.328 + endloop + endfacet + facet normal 0.659409 -0.600018 0.452945 + outer loop + vertex 868.179 244.89 327.328 + vertex 872.561 252.818 331.45 + vertex 867.87 247.721 331.528 + endloop + endfacet + facet normal 0.679612 -0.584403 0.443397 + outer loop + vertex 878.41 256.462 327.287 + vertex 877.833 259.015 331.536 + vertex 873.018 250.148 327.229 + endloop + endfacet + facet normal 0.679763 -0.584384 0.44319 + outer loop + vertex 873.018 250.148 327.229 + vertex 877.833 259.015 331.536 + vertex 872.561 252.818 331.45 + endloop + endfacet + facet normal 0.709004 -0.559846 0.42882 + outer loop + vertex 883.641 263.111 327.317 + vertex 883.082 265.682 331.598 + vertex 878.41 256.462 327.287 + endloop + endfacet + facet normal 0.70641 -0.560268 0.432533 + outer loop + vertex 878.41 256.462 327.287 + vertex 883.082 265.682 331.598 + vertex 877.833 259.015 331.536 + endloop + endfacet + facet normal 0.745717 -0.527448 0.407069 + outer loop + vertex 888.442 269.894 327.313 + vertex 887.929 272.484 331.608 + vertex 883.641 263.111 327.317 + endloop + endfacet + facet normal 0.740993 -0.528552 0.414201 + outer loop + vertex 883.641 263.111 327.317 + vertex 887.929 272.484 331.608 + vertex 883.082 265.682 331.598 + endloop + endfacet + facet normal 0.785194 -0.486824 0.382718 + outer loop + vertex 892.801 276.913 327.298 + vertex 892.283 279.453 331.591 + vertex 888.442 269.894 327.313 + endloop + endfacet + facet normal 0.782239 -0.487784 0.387516 + outer loop + vertex 888.442 269.894 327.313 + vertex 892.283 279.453 331.591 + vertex 887.929 272.484 331.608 + endloop + endfacet + facet normal 0.823355 -0.44102 0.357195 + outer loop + vertex 896.724 284.231 327.291 + vertex 896.178 286.688 331.581 + vertex 892.801 276.913 327.298 + endloop + endfacet + facet normal 0.821498 -0.441814 0.360473 + outer loop + vertex 892.801 276.913 327.298 + vertex 896.178 286.688 331.581 + vertex 892.283 279.453 331.591 + endloop + endfacet + facet normal 0.860562 -0.389594 0.3281 + outer loop + vertex 900.168 291.839 327.291 + vertex 899.605 294.208 331.582 + vertex 896.724 284.231 327.291 + endloop + endfacet + facet normal 0.858074 -0.390962 0.332952 + outer loop + vertex 896.724 284.231 327.291 + vertex 899.605 294.208 331.582 + vertex 896.178 286.688 331.581 + endloop + endfacet + facet normal 0.897652 -0.330413 0.29163 + outer loop + vertex 903.061 299.697 327.286 + vertex 902.502 301.968 331.583 + vertex 900.168 291.839 327.291 + endloop + endfacet + facet normal 0.893237 -0.333555 0.301445 + outer loop + vertex 900.168 291.839 327.291 + vertex 902.502 301.968 331.583 + vertex 899.605 294.208 331.582 + endloop + endfacet + facet normal 0.929785 -0.266458 0.25397 + outer loop + vertex 905.358 307.708 327.284 + vertex 904.809 309.887 331.579 + vertex 903.061 299.697 327.286 + endloop + endfacet + facet normal 0.926229 -0.269774 0.263291 + outer loop + vertex 903.061 299.697 327.286 + vertex 904.809 309.887 331.579 + vertex 902.502 301.968 331.583 + endloop + endfacet + facet normal 0.956936 -0.197648 0.212622 + outer loop + vertex 907.033 315.815 327.28 + vertex 906.508 317.893 331.574 + vertex 905.358 307.708 327.284 + endloop + endfacet + facet normal 0.953301 -0.202183 0.224364 + outer loop + vertex 905.358 307.708 327.284 + vertex 906.508 317.893 331.574 + vertex 904.809 309.887 331.579 + endloop + endfacet + facet normal 0.976311 -0.130167 0.172841 + outer loop + vertex 908.123 323.984 327.28 + vertex 907.624 325.948 331.573 + vertex 907.033 315.815 327.28 + endloop + endfacet + facet normal 0.97358 -0.134851 0.184272 + outer loop + vertex 907.033 315.815 327.28 + vertex 907.624 325.948 331.573 + vertex 906.508 317.893 331.574 + endloop + endfacet + facet normal 0.622618 -0.579139 0.526255 + outer loop + vertex 867.87 247.721 331.528 + vertex 867.356 250.695 335.409 + vertex 863.87 243.882 332.035 + endloop + endfacet + facet normal 0.612813 -0.579545 0.537204 + outer loop + vertex 863.87 243.882 332.035 + vertex 867.356 250.695 335.409 + vertex 863.409 247.071 336.001 + endloop + endfacet + facet normal 0.631905 -0.573657 0.521166 + outer loop + vertex 872.561 252.818 331.45 + vertex 872.055 255.798 335.344 + vertex 867.87 247.721 331.528 + endloop + endfacet + facet normal 0.630245 -0.573714 0.52311 + outer loop + vertex 867.87 247.721 331.528 + vertex 872.055 255.798 335.344 + vertex 867.356 250.695 335.409 + endloop + endfacet + facet normal 0.65076 -0.560668 0.512018 + outer loop + vertex 877.833 259.015 331.536 + vertex 877.293 261.96 335.447 + vertex 872.561 252.818 331.45 + endloop + endfacet + facet normal 0.649534 -0.560699 0.513539 + outer loop + vertex 872.561 252.818 331.45 + vertex 877.293 261.96 335.447 + vertex 872.055 255.798 335.344 + endloop + endfacet + facet normal 0.678702 -0.539072 0.498764 + outer loop + vertex 883.082 265.682 331.598 + vertex 882.549 268.647 335.529 + vertex 877.833 259.015 331.536 + endloop + endfacet + facet normal 0.678095 -0.539103 0.499555 + outer loop + vertex 877.833 259.015 331.536 + vertex 882.549 268.647 335.529 + vertex 877.293 261.96 335.447 + endloop + endfacet + facet normal 0.714509 -0.509779 0.479168 + outer loop + vertex 887.929 272.484 331.608 + vertex 887.418 275.472 335.549 + vertex 883.082 265.682 331.598 + endloop + endfacet + facet normal 0.712849 -0.509961 0.481441 + outer loop + vertex 883.082 265.682 331.598 + vertex 887.418 275.472 335.549 + vertex 882.549 268.647 335.529 + endloop + endfacet + facet normal 0.755955 -0.471201 0.454424 + outer loop + vertex 892.283 279.453 331.591 + vertex 891.765 282.42 335.53 + vertex 887.929 272.484 331.608 + endloop + endfacet + facet normal 0.755358 -0.471316 0.455297 + outer loop + vertex 887.929 272.484 331.608 + vertex 891.765 282.42 335.53 + vertex 887.418 275.472 335.549 + endloop + endfacet + facet normal 0.796535 -0.428277 0.426744 + outer loop + vertex 896.178 286.688 331.581 + vertex 895.631 289.59 335.515 + vertex 892.283 279.453 331.591 + endloop + endfacet + facet normal 0.796085 -0.428404 0.427457 + outer loop + vertex 892.283 279.453 331.591 + vertex 895.631 289.59 335.515 + vertex 891.765 282.42 335.53 + endloop + endfacet + facet normal 0.835246 -0.380567 0.396905 + outer loop + vertex 899.605 294.208 331.582 + vertex 899.025 297.038 335.514 + vertex 896.178 286.688 331.581 + endloop + endfacet + facet normal 0.835227 -0.380574 0.396938 + outer loop + vertex 896.178 286.688 331.581 + vertex 899.025 297.038 335.514 + vertex 895.631 289.59 335.515 + endloop + endfacet + facet normal 0.873437 -0.326175 0.361549 + outer loop + vertex 902.502 301.968 331.583 + vertex 901.901 304.718 335.516 + vertex 899.605 294.208 331.582 + endloop + endfacet + facet normal 0.872368 -0.326721 0.363632 + outer loop + vertex 899.605 294.208 331.582 + vertex 901.901 304.718 335.516 + vertex 899.025 297.038 335.514 + endloop + endfacet + facet normal 0.910533 -0.265174 0.317193 + outer loop + vertex 904.809 309.887 331.579 + vertex 904.21 312.542 335.52 + vertex 902.502 301.968 331.583 + endloop + endfacet + facet normal 0.906731 -0.267763 0.325794 + outer loop + vertex 902.502 301.968 331.583 + vertex 904.21 312.542 335.52 + vertex 901.901 304.718 335.516 + endloop + endfacet + facet normal 0.941416 -0.199628 0.271816 + outer loop + vertex 906.508 317.893 331.574 + vertex 905.911 320.446 335.518 + vertex 904.809 309.887 331.579 + endloop + endfacet + facet normal 0.938815 -0.202019 0.278953 + outer loop + vertex 904.809 309.887 331.579 + vertex 905.911 320.446 335.518 + vertex 904.21 312.542 335.52 + endloop + endfacet + facet normal 0.964359 -0.133572 0.228409 + outer loop + vertex 907.624 325.948 331.573 + vertex 907.029 328.392 335.516 + vertex 906.508 317.893 331.574 + endloop + endfacet + facet normal 0.962882 -0.13541 0.233498 + outer loop + vertex 906.508 317.893 331.574 + vertex 907.029 328.392 335.516 + vertex 905.911 320.446 335.518 + endloop + endfacet + facet normal 0.727435 -0.453679 0.514795 + outer loop + vertex 891.765 282.42 335.53 + vertex 891.194 285.683 339.212 + vertex 887.418 275.472 335.549 + endloop + endfacet + facet normal 0.727578 -0.453664 0.514606 + outer loop + vertex 887.418 275.472 335.549 + vertex 891.194 285.683 339.212 + vertex 886.862 278.757 339.231 + endloop + endfacet + facet normal 0.768809 -0.413577 0.487736 + outer loop + vertex 895.631 289.59 335.515 + vertex 895.025 292.8 339.193 + vertex 891.765 282.42 335.53 + endloop + endfacet + facet normal 0.770273 -0.413302 0.485654 + outer loop + vertex 891.765 282.42 335.53 + vertex 895.025 292.8 339.193 + vertex 891.194 285.683 339.212 + endloop + endfacet + facet normal 0.80954 -0.368853 0.456719 + outer loop + vertex 899.025 297.038 335.514 + vertex 898.383 300.179 339.189 + vertex 895.631 289.59 335.515 + endloop + endfacet + facet normal 0.810436 -0.368604 0.45533 + outer loop + vertex 895.631 289.59 335.515 + vertex 898.383 300.179 339.189 + vertex 895.025 292.8 339.193 + endloop + endfacet + facet normal 0.849881 -0.318321 0.419969 + outer loop + vertex 901.901 304.718 335.516 + vertex 901.232 307.782 339.192 + vertex 899.025 297.038 335.514 + endloop + endfacet + facet normal 0.849495 -0.31847 0.420636 + outer loop + vertex 899.025 297.038 335.514 + vertex 901.232 307.782 339.192 + vertex 898.383 300.179 339.189 + endloop + endfacet + facet normal 0.888023 -0.262265 0.377667 + outer loop + vertex 904.21 312.542 335.52 + vertex 903.525 315.519 339.198 + vertex 901.901 304.718 335.516 + endloop + endfacet + facet normal 0.886557 -0.263033 0.380566 + outer loop + vertex 901.901 304.718 335.516 + vertex 903.525 315.519 339.198 + vertex 901.232 307.782 339.192 + endloop + endfacet + facet normal 0.923271 -0.198661 0.328793 + outer loop + vertex 905.911 320.446 335.518 + vertex 905.219 323.321 339.199 + vertex 904.21 312.542 335.52 + endloop + endfacet + facet normal 0.921264 -0.200088 0.333522 + outer loop + vertex 904.21 312.542 335.52 + vertex 905.219 323.321 339.199 + vertex 903.525 315.519 339.198 + endloop + endfacet + facet normal 0.950697 -0.133685 0.279827 + outer loop + vertex 907.029 328.392 335.516 + vertex 906.333 331.152 339.199 + vertex 905.911 320.446 335.518 + endloop + endfacet + facet normal 0.949262 -0.135066 0.284006 + outer loop + vertex 905.911 320.446 335.518 + vertex 906.333 331.152 339.199 + vertex 905.219 323.321 339.199 + endloop + endfacet + facet normal 0.701195 -0.437025 0.563324 + outer loop + vertex 891.194 285.683 339.212 + vertex 890.514 289.119 342.723 + vertex 886.862 278.757 339.231 + endloop + endfacet + facet normal 0.703773 -0.436884 0.56021 + outer loop + vertex 886.862 278.757 339.231 + vertex 890.514 289.119 342.723 + vertex 886.212 282.218 342.747 + endloop + endfacet + facet normal 0.743954 -0.399001 0.536032 + outer loop + vertex 895.025 292.8 339.193 + vertex 894.311 296.183 342.702 + vertex 891.194 285.683 339.212 + endloop + endfacet + facet normal 0.745157 -0.398842 0.534478 + outer loop + vertex 891.194 285.683 339.212 + vertex 894.311 296.183 342.702 + vertex 890.514 289.119 342.723 + endloop + endfacet + facet normal 0.785268 -0.35712 0.505785 + outer loop + vertex 898.383 300.179 339.189 + vertex 897.631 303.491 342.695 + vertex 895.025 292.8 339.193 + endloop + endfacet + facet normal 0.78649 -0.356856 0.50407 + outer loop + vertex 895.025 292.8 339.193 + vertex 897.631 303.491 342.695 + vertex 894.311 296.183 342.702 + endloop + endfacet + facet normal 0.827628 -0.3103 0.467703 + outer loop + vertex 901.232 307.782 339.192 + vertex 900.46 311.011 342.7 + vertex 898.383 300.179 339.189 + endloop + endfacet + facet normal 0.825636 -0.310921 0.4708 + outer loop + vertex 898.383 300.179 339.189 + vertex 900.46 311.011 342.7 + vertex 897.631 303.491 342.695 + endloop + endfacet + facet normal 0.866993 -0.257268 0.426773 + outer loop + vertex 903.525 315.519 339.198 + vertex 902.73 318.658 342.705 + vertex 901.232 307.782 339.192 + endloop + endfacet + facet normal 0.866515 -0.257475 0.42762 + outer loop + vertex 901.232 307.782 339.192 + vertex 902.73 318.658 342.705 + vertex 900.46 311.011 342.7 + endloop + endfacet + facet normal 0.905236 -0.196617 0.376683 + outer loop + vertex 905.219 323.321 339.199 + vertex 904.417 326.354 342.708 + vertex 903.525 315.519 339.198 + endloop + endfacet + facet normal 0.902716 -0.198104 0.381915 + outer loop + vertex 903.525 315.519 339.198 + vertex 904.417 326.354 342.708 + vertex 902.73 318.658 342.705 + endloop + endfacet + facet normal 0.936368 -0.13323 0.324754 + outer loop + vertex 906.333 331.152 339.199 + vertex 905.53 334.065 342.709 + vertex 905.219 323.321 339.199 + endloop + endfacet + facet normal 0.934315 -0.134868 0.32995 + outer loop + vertex 905.219 323.321 339.199 + vertex 905.53 334.065 342.709 + vertex 904.417 326.354 342.708 + endloop + endfacet + facet normal 0.677002 -0.420043 0.604344 + outer loop + vertex 890.514 289.119 342.723 + vertex 889.722 292.669 346.078 + vertex 886.212 282.218 342.747 + endloop + endfacet + facet normal 0.676859 -0.420046 0.604502 + outer loop + vertex 886.212 282.218 342.747 + vertex 889.722 292.669 346.078 + vertex 885.442 285.805 346.101 + endloop + endfacet + facet normal 0.717838 -0.38402 0.580721 + outer loop + vertex 894.311 296.183 342.702 + vertex 893.471 299.681 346.053 + vertex 890.514 289.119 342.723 + endloop + endfacet + facet normal 0.721505 -0.38368 0.576385 + outer loop + vertex 890.514 289.119 342.723 + vertex 893.471 299.681 346.053 + vertex 889.722 292.669 346.078 + endloop + endfacet + facet normal 0.761358 -0.345395 0.548668 + outer loop + vertex 897.631 303.491 342.695 + vertex 896.768 306.914 346.047 + vertex 894.311 296.183 342.702 + endloop + endfacet + facet normal 0.759412 -0.345724 0.551152 + outer loop + vertex 894.311 296.183 342.702 + vertex 896.768 306.914 346.047 + vertex 893.471 299.681 346.053 + endloop + endfacet + facet normal 0.801697 -0.301943 0.51586 + outer loop + vertex 900.46 311.011 342.7 + vertex 899.563 314.351 346.049 + vertex 897.631 303.491 342.695 + endloop + endfacet + facet normal 0.802528 -0.30173 0.514692 + outer loop + vertex 897.631 303.491 342.695 + vertex 899.563 314.351 346.049 + vertex 896.768 306.914 346.047 + endloop + endfacet + facet normal 0.845782 -0.25135 0.470612 + outer loop + vertex 902.73 318.658 342.705 + vertex 901.828 321.897 346.057 + vertex 900.46 311.011 342.7 + endloop + endfacet + facet normal 0.841355 -0.252959 0.477633 + outer loop + vertex 900.46 311.011 342.7 + vertex 901.828 321.897 346.057 + vertex 899.563 314.351 346.049 + endloop + endfacet + facet normal 0.885338 -0.194312 0.422398 + outer loop + vertex 904.417 326.354 342.708 + vertex 903.505 329.481 346.059 + vertex 902.73 318.658 342.705 + endloop + endfacet + facet normal 0.883049 -0.195462 0.426636 + outer loop + vertex 902.73 318.658 342.705 + vertex 903.505 329.481 346.059 + vertex 901.828 321.897 346.057 + endloop + endfacet + facet normal 0.920551 -0.132886 0.367325 + outer loop + vertex 905.53 334.065 342.709 + vertex 904.625 337.064 346.063 + vertex 904.417 326.354 342.708 + endloop + endfacet + facet normal 0.916608 -0.13556 0.376104 + outer loop + vertex 904.417 326.354 342.708 + vertex 904.625 337.064 346.063 + vertex 903.505 329.481 346.059 + endloop + endfacet + facet normal 0.530878 -0.48156 0.69733 + outer loop + vertex 865.613 261.056 346.056 + vertex 864.924 264.823 349.182 + vertex 862.075 257.86 346.543 + endloop + endfacet + facet normal 0.520792 -0.48056 0.705576 + outer loop + vertex 862.075 257.86 346.543 + vertex 864.924 264.823 349.182 + vertex 861.096 261.181 349.528 + endloop + endfacet + facet normal 0.535614 -0.477211 0.696697 + outer loop + vertex 870.187 266.088 345.986 + vertex 869.45 269.846 349.128 + vertex 865.613 261.056 346.056 + endloop + endfacet + facet normal 0.538472 -0.477595 0.694227 + outer loop + vertex 865.613 261.056 346.056 + vertex 869.45 269.846 349.128 + vertex 864.924 264.823 349.182 + endloop + endfacet + facet normal 0.547509 -0.4672 0.694232 + outer loop + vertex 875.379 272.26 346.046 + vertex 874.596 276.019 349.193 + vertex 870.187 266.088 345.986 + endloop + endfacet + facet normal 0.552608 -0.467984 0.689649 + outer loop + vertex 870.187 266.088 345.986 + vertex 874.596 276.019 349.193 + vertex 869.45 269.846 349.128 + endloop + endfacet + facet normal 0.570852 -0.450403 0.686487 + outer loop + vertex 880.617 278.977 346.097 + vertex 879.798 282.731 349.241 + vertex 875.379 272.26 346.046 + endloop + endfacet + facet normal 0.575701 -0.451075 0.681983 + outer loop + vertex 875.379 272.26 346.046 + vertex 879.798 282.731 349.241 + vertex 874.596 276.019 349.193 + endloop + endfacet + facet normal 0.604234 -0.427356 0.672509 + outer loop + vertex 885.442 285.805 346.101 + vertex 884.587 289.539 349.242 + vertex 880.617 278.977 346.097 + endloop + endfacet + facet normal 0.607879 -0.427684 0.669006 + outer loop + vertex 880.617 278.977 346.097 + vertex 884.587 289.539 349.242 + vertex 879.798 282.731 349.241 + endloop + endfacet + facet normal 0.643396 -0.399021 0.653317 + outer loop + vertex 889.722 292.669 346.078 + vertex 888.823 296.362 349.219 + vertex 885.442 285.805 346.101 + endloop + endfacet + facet normal 0.64633 -0.399091 0.650372 + outer loop + vertex 885.442 285.805 346.101 + vertex 888.823 296.362 349.219 + vertex 884.587 289.539 349.242 + endloop + endfacet + facet normal 0.689392 -0.36633 0.624932 + outer loop + vertex 893.471 299.681 346.053 + vertex 892.547 303.309 349.199 + vertex 889.722 292.669 346.078 + endloop + endfacet + facet normal 0.687012 -0.366445 0.62748 + outer loop + vertex 889.722 292.669 346.078 + vertex 892.547 303.309 349.199 + vertex 888.823 296.362 349.219 + endloop + endfacet + facet normal 0.728173 -0.331449 0.599921 + outer loop + vertex 896.768 306.914 346.047 + vertex 895.799 310.472 349.189 + vertex 893.471 299.681 346.053 + endloop + endfacet + facet normal 0.731086 -0.331101 0.596561 + outer loop + vertex 893.471 299.681 346.053 + vertex 895.799 310.472 349.189 + vertex 892.547 303.309 349.199 + endloop + endfacet + facet normal 0.774197 -0.291091 0.562037 + outer loop + vertex 899.563 314.351 346.049 + vertex 898.583 317.819 349.195 + vertex 896.768 306.914 346.047 + endloop + endfacet + facet normal 0.769471 -0.292028 0.568009 + outer loop + vertex 896.768 306.914 346.047 + vertex 898.583 317.819 349.195 + vertex 895.799 310.472 349.189 + endloop + endfacet + facet normal 0.815486 -0.245246 0.524249 + outer loop + vertex 901.828 321.897 346.057 + vertex 900.822 325.272 349.199 + vertex 899.563 314.351 346.049 + endloop + endfacet + facet normal 0.815404 -0.24527 0.524365 + outer loop + vertex 899.563 314.351 346.049 + vertex 900.822 325.272 349.199 + vertex 898.583 317.819 349.195 + endloop + endfacet + facet normal 0.859932 -0.190366 0.47358 + outer loop + vertex 903.505 329.481 346.059 + vertex 902.496 332.742 349.203 + vertex 901.828 321.897 346.057 + endloop + endfacet + facet normal 0.855984 -0.191994 0.480031 + outer loop + vertex 901.828 321.897 346.057 + vertex 902.496 332.742 349.203 + vertex 900.822 325.272 349.199 + endloop + endfacet + facet normal 0.897314 -0.132731 0.420963 + outer loop + vertex 904.625 337.064 346.063 + vertex 903.614 340.192 349.205 + vertex 903.505 329.481 346.059 + endloop + endfacet + facet normal 0.894443 -0.134336 0.426528 + outer loop + vertex 903.505 329.481 346.059 + vertex 903.614 340.192 349.205 + vertex 902.496 332.742 349.203 + endloop + endfacet + facet normal 0.490882 -0.44499 0.749012 + outer loop + vertex 864.924 264.823 349.182 + vertex 864.273 268.884 352.022 + vertex 861.096 261.181 349.528 + endloop + endfacet + facet normal 0.487054 -0.444343 0.751889 + outer loop + vertex 861.096 261.181 349.528 + vertex 864.273 268.884 352.022 + vertex 860.788 265.763 352.435 + endloop + endfacet + facet normal 0.497517 -0.440116 0.747512 + outer loop + vertex 869.45 269.846 349.128 + vertex 868.745 273.886 351.976 + vertex 864.924 264.823 349.182 + endloop + endfacet + facet normal 0.500637 -0.440685 0.74509 + outer loop + vertex 864.924 264.823 349.182 + vertex 868.745 273.886 351.976 + vertex 864.273 268.884 352.022 + endloop + endfacet + facet normal 0.508161 -0.43151 0.745367 + outer loop + vertex 874.596 276.019 349.193 + vertex 873.823 280.038 352.047 + vertex 869.45 269.846 349.128 + endloop + endfacet + facet normal 0.513733 -0.43262 0.74089 + outer loop + vertex 869.45 269.846 349.128 + vertex 873.823 280.038 352.047 + vertex 868.745 273.886 351.976 + endloop + endfacet + facet normal 0.530111 -0.416157 0.73878 + outer loop + vertex 879.798 282.731 349.241 + vertex 878.962 286.734 352.096 + vertex 874.596 276.019 349.193 + endloop + endfacet + facet normal 0.536807 -0.417382 0.733233 + outer loop + vertex 874.596 276.019 349.193 + vertex 878.962 286.734 352.096 + vertex 873.823 280.038 352.047 + endloop + endfacet + facet normal 0.56363 -0.396563 0.72461 + outer loop + vertex 884.587 289.539 349.242 + vertex 883.703 293.506 352.101 + vertex 879.798 282.731 349.241 + endloop + endfacet + facet normal 0.566237 -0.396916 0.722381 + outer loop + vertex 879.798 282.731 349.241 + vertex 883.703 293.506 352.101 + vertex 878.962 286.734 352.096 + endloop + endfacet + facet normal 0.601843 -0.371281 0.707061 + outer loop + vertex 888.823 296.362 349.219 + vertex 887.882 300.279 352.077 + vertex 884.587 289.539 349.242 + endloop + endfacet + facet normal 0.60623 -0.371591 0.703139 + outer loop + vertex 884.587 289.539 349.242 + vertex 887.882 300.279 352.077 + vertex 883.703 293.506 352.101 + endloop + endfacet + facet normal 0.642813 -0.342581 0.685149 + outer loop + vertex 892.547 303.309 349.199 + vertex 891.552 307.158 352.057 + vertex 888.823 296.362 349.219 + endloop + endfacet + facet normal 0.645872 -0.342595 0.682259 + outer loop + vertex 888.823 296.362 349.219 + vertex 891.552 307.158 352.057 + vertex 887.882 300.279 352.077 + endloop + endfacet + facet normal 0.686498 -0.310776 0.657373 + outer loop + vertex 895.799 310.472 349.189 + vertex 894.764 314.237 352.05 + vertex 892.547 303.309 349.199 + endloop + endfacet + facet normal 0.686374 -0.310783 0.657499 + outer loop + vertex 892.547 303.309 349.199 + vertex 894.764 314.237 352.05 + vertex 891.552 307.158 352.057 + endloop + endfacet + facet normal 0.727753 -0.27627 0.627734 + outer loop + vertex 898.583 317.819 349.195 + vertex 897.511 321.496 352.056 + vertex 895.799 310.472 349.189 + endloop + endfacet + facet normal 0.728412 -0.276183 0.627008 + outer loop + vertex 895.799 310.472 349.189 + vertex 897.511 321.496 352.056 + vertex 894.764 314.237 352.05 + endloop + endfacet + facet normal 0.774231 -0.232937 0.588479 + outer loop + vertex 900.822 325.272 349.199 + vertex 899.726 328.857 352.06 + vertex 898.583 317.819 349.195 + endloop + endfacet + facet normal 0.773497 -0.233095 0.58938 + outer loop + vertex 898.583 317.819 349.195 + vertex 899.726 328.857 352.06 + vertex 897.511 321.496 352.056 + endloop + endfacet + facet normal 0.82094 -0.184169 0.540498 + outer loop + vertex 902.496 332.742 349.203 + vertex 901.392 336.224 352.066 + vertex 900.822 325.272 349.199 + endloop + endfacet + facet normal 0.817523 -0.185245 0.545289 + outer loop + vertex 900.822 325.272 349.199 + vertex 901.392 336.224 352.066 + vertex 899.726 328.857 352.06 + endloop + endfacet + facet normal 0.865229 -0.129971 0.484237 + outer loop + vertex 903.614 340.192 349.205 + vertex 902.513 343.547 352.071 + vertex 902.496 332.742 349.203 + endloop + endfacet + facet normal 0.86029 -0.132126 0.492386 + outer loop + vertex 902.496 332.742 349.203 + vertex 902.513 343.547 352.071 + vertex 901.392 336.224 352.066 + endloop + endfacet + facet normal 0.900278 -0.0738632 0.429003 + outer loop + vertex 904.222 347.619 349.207 + vertex 903.121 350.816 352.068 + vertex 903.614 340.192 349.205 + endloop + endfacet + facet normal 0.898497 -0.0748997 0.432543 + outer loop + vertex 903.614 340.192 349.205 + vertex 903.121 350.816 352.068 + vertex 902.513 343.547 352.071 + endloop + endfacet + facet normal 0.927717 -0.0199449 0.37275 + outer loop + vertex 904.382 355.023 349.205 + vertex 903.297 358.033 352.067 + vertex 904.222 347.619 349.207 + endloop + endfacet + facet normal 0.924369 -0.022463 0.380838 + outer loop + vertex 904.222 347.619 349.207 + vertex 903.297 358.033 352.067 + vertex 903.121 350.816 352.068 + endloop + endfacet + facet normal 0.945505 0.0267783 0.324504 + outer loop + vertex 904.172 362.396 349.207 + vertex 903.11 365.206 352.07 + vertex 904.382 355.023 349.205 + endloop + endfacet + facet normal 0.942998 0.0243828 0.331905 + outer loop + vertex 904.382 355.023 349.205 + vertex 903.11 365.206 352.07 + vertex 903.297 358.033 352.067 + endloop + endfacet + facet normal 0.447614 -0.393535 0.802977 + outer loop + vertex 864.273 268.884 352.022 + vertex 863.68 273.346 354.539 + vertex 860.788 265.763 352.435 + endloop + endfacet + facet normal 0.437195 -0.391432 0.809717 + outer loop + vertex 860.788 265.763 352.435 + vertex 863.68 273.346 354.539 + vertex 859.846 269.666 354.83 + endloop + endfacet + facet normal 0.447079 -0.392279 0.803889 + outer loop + vertex 868.745 273.886 351.976 + vertex 868.1 278.314 354.495 + vertex 864.273 268.884 352.022 + endloop + endfacet + facet normal 0.449564 -0.39285 0.802223 + outer loop + vertex 864.273 268.884 352.022 + vertex 868.1 278.314 354.495 + vertex 863.68 273.346 354.539 + endloop + endfacet + facet normal 0.453415 -0.383553 0.804551 + outer loop + vertex 873.823 280.038 352.047 + vertex 873.101 284.452 354.558 + vertex 868.745 273.886 351.976 + endloop + endfacet + facet normal 0.463879 -0.386104 0.797333 + outer loop + vertex 868.745 273.886 351.976 + vertex 873.101 284.452 354.558 + vertex 868.1 278.314 354.495 + endloop + endfacet + facet normal 0.476186 -0.371326 0.797097 + outer loop + vertex 878.962 286.734 352.096 + vertex 878.153 291.098 354.612 + vertex 873.823 280.038 352.047 + endloop + endfacet + facet normal 0.481557 -0.372546 0.793292 + outer loop + vertex 873.823 280.038 352.047 + vertex 878.153 291.098 354.612 + vertex 873.101 284.452 354.558 + endloop + endfacet + facet normal 0.504349 -0.353647 0.78776 + outer loop + vertex 883.703 293.506 352.101 + vertex 882.806 297.825 354.614 + vertex 878.962 286.734 352.096 + endloop + endfacet + facet normal 0.513332 -0.355271 0.7812 + outer loop + vertex 878.962 286.734 352.096 + vertex 882.806 297.825 354.614 + vertex 878.153 291.098 354.612 + endloop + endfacet + facet normal 0.544169 -0.333061 0.770032 + outer loop + vertex 887.882 300.279 352.077 + vertex 886.918 304.526 354.595 + vertex 883.703 293.506 352.101 + endloop + endfacet + facet normal 0.546779 -0.333373 0.768046 + outer loop + vertex 883.703 293.506 352.101 + vertex 886.918 304.526 354.595 + vertex 882.806 297.825 354.614 + endloop + endfacet + facet normal 0.583511 -0.309121 0.750972 + outer loop + vertex 891.552 307.158 352.057 + vertex 890.517 311.322 354.575 + vertex 887.882 300.279 352.077 + endloop + endfacet + facet normal 0.588397 -0.309397 0.747036 + outer loop + vertex 887.882 300.279 352.077 + vertex 890.517 311.322 354.575 + vertex 886.918 304.526 354.595 + endloop + endfacet + facet normal 0.624063 -0.282435 0.728544 + outer loop + vertex 894.764 314.237 352.05 + vertex 893.667 318.309 354.568 + vertex 891.552 307.158 352.057 + endloop + endfacet + facet normal 0.628061 -0.282419 0.725106 + outer loop + vertex 891.552 307.158 352.057 + vertex 893.667 318.309 354.568 + vertex 890.517 311.322 354.575 + endloop + endfacet + facet normal 0.665561 -0.252464 0.702347 + outer loop + vertex 897.511 321.496 352.056 + vertex 896.36 325.473 354.576 + vertex 894.764 314.237 352.05 + endloop + endfacet + facet normal 0.668892 -0.252242 0.699254 + outer loop + vertex 894.764 314.237 352.05 + vertex 896.36 325.473 354.576 + vertex 893.667 318.309 354.568 + endloop + endfacet + facet normal 0.712204 -0.214696 0.668335 + outer loop + vertex 899.726 328.857 352.06 + vertex 898.531 332.736 354.58 + vertex 897.511 321.496 352.056 + endloop + endfacet + facet normal 0.715597 -0.214222 0.664853 + outer loop + vertex 897.511 321.496 352.056 + vertex 898.531 332.736 354.58 + vertex 896.36 325.473 354.576 + endloop + endfacet + facet normal 0.760578 -0.172437 0.625929 + outer loop + vertex 901.392 336.224 352.066 + vertex 900.171 340.001 354.589 + vertex 899.726 328.857 352.06 + endloop + endfacet + facet normal 0.760342 -0.172489 0.6262 + outer loop + vertex 899.726 328.857 352.06 + vertex 900.171 340.001 354.589 + vertex 898.531 332.736 354.58 + endloop + endfacet + facet normal 0.806409 -0.123933 0.578227 + outer loop + vertex 902.513 343.547 352.071 + vertex 901.27 347.209 354.59 + vertex 901.392 336.224 352.066 + endloop + endfacet + facet normal 0.80845 -0.123285 0.575509 + outer loop + vertex 901.392 336.224 352.066 + vertex 901.27 347.209 354.59 + vertex 900.171 340.001 354.589 + endloop + endfacet + facet normal 0.852891 -0.071055 0.517231 + outer loop + vertex 903.121 350.816 352.068 + vertex 901.884 354.324 354.589 + vertex 902.513 343.547 352.071 + endloop + endfacet + facet normal 0.848003 -0.0731368 0.524921 + outer loop + vertex 902.513 343.547 352.071 + vertex 901.884 354.324 354.589 + vertex 901.27 347.209 354.59 + endloop + endfacet + facet normal 0.887975 -0.0215565 0.459386 + outer loop + vertex 903.297 358.033 352.067 + vertex 902.074 361.344 354.586 + vertex 903.121 350.816 352.068 + endloop + endfacet + facet normal 0.884147 -0.0236644 0.466609 + outer loop + vertex 903.121 350.816 352.068 + vertex 902.074 361.344 354.586 + vertex 901.884 354.324 354.589 + endloop + endfacet + facet normal 0.911415 0.0235194 0.410815 + outer loop + vertex 903.11 365.206 352.07 + vertex 901.898 368.296 354.582 + vertex 903.297 358.033 352.067 + endloop + endfacet + facet normal 0.911032 0.0232553 0.411679 + outer loop + vertex 903.297 358.033 352.067 + vertex 901.898 368.296 354.582 + vertex 902.074 361.344 354.586 + endloop + endfacet + facet normal 0.929971 0.0662646 0.361611 + outer loop + vertex 902.603 372.336 352.069 + vertex 901.419 375.205 354.588 + vertex 903.11 365.206 352.07 + endloop + endfacet + facet normal 0.927355 0.064047 0.36866 + outer loop + vertex 903.11 365.206 352.07 + vertex 901.419 375.205 354.588 + vertex 901.898 368.296 354.582 + endloop + endfacet + facet normal 0.939575 0.102086 0.326767 + outer loop + vertex 901.833 379.421 352.069 + vertex 900.668 382.08 354.588 + vertex 902.603 372.336 352.069 + endloop + endfacet + facet normal 0.940145 0.102671 0.32494 + outer loop + vertex 902.603 372.336 352.069 + vertex 900.668 382.08 354.588 + vertex 901.419 375.205 354.588 + endloop + endfacet + facet normal 0.945597 0.133526 0.296677 + outer loop + vertex 900.84 386.453 352.069 + vertex 899.701 388.91 354.591 + vertex 901.833 379.421 352.069 + endloop + endfacet + facet normal 0.945702 0.133654 0.296285 + outer loop + vertex 901.833 379.421 352.069 + vertex 899.701 388.91 354.591 + vertex 900.668 382.08 354.588 + endloop + endfacet + facet normal 0.949149 0.161146 0.270458 + outer loop + vertex 899.658 393.421 352.066 + vertex 898.555 395.673 354.594 + vertex 900.84 386.453 352.069 + endloop + endfacet + facet normal 0.948876 0.160752 0.271648 + outer loop + vertex 900.84 386.453 352.069 + vertex 898.555 395.673 354.594 + vertex 899.701 388.91 354.591 + endloop + endfacet + facet normal 0.949422 0.183707 0.254657 + outer loop + vertex 898.322 400.32 352.067 + vertex 897.254 402.353 354.585 + vertex 899.658 393.421 352.066 + endloop + endfacet + facet normal 0.950483 0.185489 0.249351 + outer loop + vertex 899.658 393.421 352.066 + vertex 897.254 402.353 354.585 + vertex 898.555 395.673 354.594 + endloop + endfacet + facet normal 0.949898 0.205531 0.23548 + outer loop + vertex 896.847 407.15 352.058 + vertex 895.831 408.958 354.578 + vertex 898.322 400.32 352.067 + endloop + endfacet + facet normal 0.949514 0.204783 0.237671 + outer loop + vertex 898.322 400.32 352.067 + vertex 895.831 408.958 354.578 + vertex 897.254 402.353 354.585 + endloop + endfacet + facet normal 0.948549 0.222897 0.22488 + outer loop + vertex 895.263 413.909 352.04 + vertex 894.296 415.486 354.554 + vertex 896.847 407.15 352.058 + endloop + endfacet + facet normal 0.949003 0.223919 0.221931 + outer loop + vertex 896.847 407.15 352.058 + vertex 894.296 415.486 354.554 + vertex 895.831 408.958 354.578 + endloop + endfacet + facet normal 0.947233 0.238216 0.214482 + outer loop + vertex 893.593 420.578 352.006 + vertex 892.684 421.931 354.521 + vertex 895.263 413.909 352.04 + endloop + endfacet + facet normal 0.947187 0.238097 0.214819 + outer loop + vertex 895.263 413.909 352.04 + vertex 892.684 421.931 354.521 + vertex 894.296 415.486 354.554 + endloop + endfacet + facet normal 0.945559 0.249141 0.209397 + outer loop + vertex 891.864 427.17 351.973 + vertex 891.013 428.292 354.478 + vertex 893.593 420.578 352.006 + endloop + endfacet + facet normal 0.945764 0.249736 0.207755 + outer loop + vertex 893.593 420.578 352.006 + vertex 891.013 428.292 354.478 + vertex 892.684 421.931 354.521 + endloop + endfacet + facet normal 0.944703 0.255331 0.205772 + outer loop + vertex 890.076 433.783 351.977 + vertex 889.297 434.661 354.464 + vertex 891.864 427.17 351.973 + endloop + endfacet + facet normal 0.944628 0.255091 0.206415 + outer loop + vertex 891.864 427.17 351.973 + vertex 889.297 434.661 354.464 + vertex 891.013 428.292 354.478 + endloop + endfacet + facet normal 0.944539 0.259298 0.201521 + outer loop + vertex 888.196 440.6 352.016 + vertex 887.506 441.191 354.488 + vertex 890.076 433.783 351.977 + endloop + endfacet + facet normal 0.944193 0.258125 0.204626 + outer loop + vertex 890.076 433.783 351.977 + vertex 887.506 441.191 354.488 + vertex 889.297 434.661 354.464 + endloop + endfacet + facet normal 0.945062 0.259806 0.198393 + outer loop + vertex 886.235 447.706 352.052 + vertex 885.643 447.967 354.528 + vertex 888.196 440.6 352.016 + endloop + endfacet + facet normal 0.9447 0.258536 0.201747 + outer loop + vertex 888.196 440.6 352.016 + vertex 885.643 447.967 354.528 + vertex 887.506 441.191 354.488 + endloop + endfacet + facet normal 0.946484 0.260934 0.18995 + outer loop + vertex 884.28 454.861 351.964 + vertex 883.813 454.725 354.478 + vertex 886.235 447.706 352.052 + endloop + endfacet + facet normal 0.945594 0.257584 0.198754 + outer loop + vertex 886.235 447.706 352.052 + vertex 883.813 454.725 354.478 + vertex 885.643 447.967 354.528 + endloop + endfacet + facet normal 0.948627 0.26285 0.176114 + outer loop + vertex 882.325 462.03 351.793 + vertex 882.438 460.079 354.1 + vertex 884.28 454.861 351.964 + endloop + endfacet + facet normal 0.947608 0.256833 0.189937 + outer loop + vertex 884.28 454.861 351.964 + vertex 882.438 460.079 354.1 + vertex 883.813 454.725 354.478 + endloop + endfacet + facet normal 0.945103 0.274172 0.177794 + outer loop + vertex 880.538 468.416 352.013 + vertex 880.33 467.79 354.08 + vertex 880.92 466.622 352.747 + endloop + endfacet + facet normal 0.947192 0.25241 0.197779 + outer loop + vertex 880.92 466.622 352.747 + vertex 880.33 467.79 354.08 + vertex 880.921 465.02 354.788 + endloop + endfacet + facet normal 0.385751 -0.333861 0.860077 + outer loop + vertex 863.68 273.346 354.539 + vertex 863.018 278.156 356.703 + vertex 859.846 269.666 354.83 + endloop + endfacet + facet normal 0.382433 -0.33302 0.861883 + outer loop + vertex 859.846 269.666 354.83 + vertex 863.018 278.156 356.703 + vertex 859.214 274.827 357.105 + endloop + endfacet + facet normal 0.382102 -0.332287 0.862313 + outer loop + vertex 868.1 278.314 354.495 + vertex 867.441 283.144 356.648 + vertex 863.68 273.346 354.539 + endloop + endfacet + facet normal 0.386841 -0.333546 0.85971 + outer loop + vertex 863.68 273.346 354.539 + vertex 867.441 283.144 356.648 + vertex 863.018 278.156 356.703 + endloop + endfacet + facet normal 0.389014 -0.325782 0.861704 + outer loop + vertex 873.101 284.452 354.558 + vertex 872.369 289.253 356.704 + vertex 868.1 278.314 354.495 + endloop + endfacet + facet normal 0.396985 -0.327987 0.857221 + outer loop + vertex 868.1 278.314 354.495 + vertex 872.369 289.253 356.704 + vertex 867.441 283.144 356.648 + endloop + endfacet + facet normal 0.405354 -0.315145 0.858121 + outer loop + vertex 878.153 291.098 354.612 + vertex 877.316 295.846 356.751 + vertex 873.101 284.452 354.558 + endloop + endfacet + facet normal 0.415135 -0.31768 0.852492 + outer loop + vertex 873.101 284.452 354.558 + vertex 877.316 295.846 356.751 + vertex 872.369 289.253 356.704 + endloop + endfacet + facet normal 0.434833 -0.300988 0.848721 + outer loop + vertex 882.806 297.825 354.614 + vertex 881.866 302.502 356.754 + vertex 878.153 291.098 354.612 + endloop + endfacet + facet normal 0.442018 -0.302526 0.844451 + outer loop + vertex 878.153 291.098 354.612 + vertex 881.866 302.502 356.754 + vertex 877.316 295.846 356.751 + endloop + endfacet + facet normal 0.467532 -0.284553 0.836925 + outer loop + vertex 886.918 304.526 354.595 + vertex 885.889 309.131 356.736 + vertex 882.806 297.825 354.614 + endloop + endfacet + facet normal 0.474502 -0.285645 0.832619 + outer loop + vertex 882.806 297.825 354.614 + vertex 885.889 309.131 356.736 + vertex 881.866 302.502 356.754 + endloop + endfacet + facet normal 0.504859 -0.26493 0.821541 + outer loop + vertex 890.517 311.322 354.575 + vertex 889.406 315.836 356.714 + vertex 886.918 304.526 354.595 + endloop + endfacet + facet normal 0.511469 -0.265577 0.817232 + outer loop + vertex 886.918 304.526 354.595 + vertex 889.406 315.836 356.714 + vertex 885.889 309.131 356.736 + endloop + endfacet + facet normal 0.543596 -0.244278 0.803014 + outer loop + vertex 893.667 318.309 354.568 + vertex 892.486 322.726 356.711 + vertex 890.517 311.322 354.575 + endloop + endfacet + facet normal 0.547376 -0.244439 0.800393 + outer loop + vertex 890.517 311.322 354.575 + vertex 892.486 322.726 356.711 + vertex 889.406 315.836 356.714 + endloop + endfacet + facet normal 0.580097 -0.218951 0.784569 + outer loop + vertex 896.36 325.473 354.576 + vertex 895.101 329.806 356.716 + vertex 893.667 318.309 354.568 + endloop + endfacet + facet normal 0.590857 -0.218794 0.776542 + outer loop + vertex 893.667 318.309 354.568 + vertex 895.101 329.806 356.716 + vertex 892.486 322.726 356.711 + endloop + endfacet + facet normal 0.629385 -0.188508 0.753882 + outer loop + vertex 898.531 332.736 354.58 + vertex 897.224 336.96 356.727 + vertex 896.36 325.473 354.576 + endloop + endfacet + facet normal 0.630956 -0.188386 0.752599 + outer loop + vertex 896.36 325.473 354.576 + vertex 897.224 336.96 356.727 + vertex 895.101 329.806 356.716 + endloop + endfacet + facet normal 0.677242 -0.153843 0.719497 + outer loop + vertex 900.171 340.001 354.589 + vertex 898.818 344.087 356.737 + vertex 898.531 332.736 354.58 + endloop + endfacet + facet normal 0.681031 -0.153281 0.716032 + outer loop + vertex 898.531 332.736 354.58 + vertex 898.818 344.087 356.737 + vertex 897.224 336.96 356.727 + endloop + endfacet + facet normal 0.729235 -0.111221 0.675164 + outer loop + vertex 901.27 347.209 354.59 + vertex 899.883 351.148 356.737 + vertex 900.171 340.001 354.589 + endloop + endfacet + facet normal 0.732465 -0.110485 0.67178 + outer loop + vertex 900.171 340.001 354.589 + vertex 899.883 351.148 356.737 + vertex 898.818 344.087 356.737 + endloop + endfacet + facet normal 0.776679 -0.0669573 0.626328 + outer loop + vertex 901.884 354.324 354.589 + vertex 900.481 358.107 356.734 + vertex 901.27 347.209 354.59 + endloop + endfacet + facet normal 0.778028 -0.0665387 0.624696 + outer loop + vertex 901.27 347.209 354.59 + vertex 900.481 358.107 356.734 + vertex 899.883 351.148 356.737 + endloop + endfacet + facet normal 0.820976 -0.0219139 0.570542 + outer loop + vertex 902.074 361.344 354.586 + vertex 900.679 364.939 356.731 + vertex 901.884 354.324 354.589 + endloop + endfacet + facet normal 0.817064 -0.0234737 0.576069 + outer loop + vertex 901.884 354.324 354.589 + vertex 900.679 364.939 356.731 + vertex 900.481 358.107 356.734 + endloop + endfacet + facet normal 0.855319 0.0218971 0.517638 + outer loop + vertex 901.898 368.296 354.582 + vertex 900.517 371.663 356.722 + vertex 902.074 361.344 354.586 + endloop + endfacet + facet normal 0.854091 0.0212873 0.519688 + outer loop + vertex 902.074 361.344 354.586 + vertex 900.517 371.663 356.722 + vertex 900.679 364.939 356.731 + endloop + endfacet + facet normal 0.87991 0.0606705 0.471251 + outer loop + vertex 901.419 375.205 354.588 + vertex 900.055 378.35 356.728 + vertex 901.898 368.296 354.582 + endloop + endfacet + facet normal 0.879151 0.0602175 0.472723 + outer loop + vertex 901.898 368.296 354.582 + vertex 900.055 378.35 356.728 + vertex 900.517 371.663 356.722 + endloop + endfacet + facet normal 0.897531 0.0980187 0.429919 + outer loop + vertex 900.668 382.08 354.588 + vertex 899.323 385.007 356.729 + vertex 901.419 375.205 354.588 + endloop + endfacet + facet normal 0.898789 0.0989083 0.427078 + outer loop + vertex 901.419 375.205 354.588 + vertex 899.323 385.007 356.729 + vertex 900.055 378.35 356.728 + endloop + endfacet + facet normal 0.908745 0.128374 0.397118 + outer loop + vertex 899.701 388.91 354.591 + vertex 898.383 391.611 356.735 + vertex 900.668 382.08 354.588 + endloop + endfacet + facet normal 0.909547 0.129028 0.395065 + outer loop + vertex 900.668 382.08 354.588 + vertex 898.383 391.611 356.735 + vertex 899.323 385.007 356.729 + endloop + endfacet + facet normal 0.914846 0.154947 0.372892 + outer loop + vertex 898.555 395.673 354.594 + vertex 897.264 398.139 356.736 + vertex 899.701 388.91 354.591 + endloop + endfacet + facet normal 0.917228 0.157167 0.366048 + outer loop + vertex 899.701 388.91 354.591 + vertex 897.264 398.139 356.736 + vertex 898.383 391.611 356.735 + endloop + endfacet + facet normal 0.920511 0.179782 0.346897 + outer loop + vertex 897.254 402.353 354.585 + vertex 896.006 404.584 356.739 + vertex 898.555 395.673 354.594 + endloop + endfacet + facet normal 0.920192 0.179446 0.347916 + outer loop + vertex 898.555 395.673 354.594 + vertex 896.006 404.584 356.739 + vertex 897.264 398.139 356.736 + endloop + endfacet + facet normal 0.921527 0.19885 0.333536 + outer loop + vertex 895.831 408.958 354.578 + vertex 894.627 410.936 356.725 + vertex 897.254 402.353 354.585 + endloop + endfacet + facet normal 0.923551 0.201242 0.326429 + outer loop + vertex 897.254 402.353 354.585 + vertex 894.627 410.936 356.725 + vertex 896.006 404.584 356.739 + endloop + endfacet + facet normal 0.923472 0.218263 0.315532 + outer loop + vertex 894.296 415.486 354.554 + vertex 893.152 417.213 356.708 + vertex 895.831 408.958 354.578 + endloop + endfacet + facet normal 0.923091 0.217764 0.316988 + outer loop + vertex 895.831 408.958 354.578 + vertex 893.152 417.213 356.708 + vertex 894.627 410.936 356.725 + endloop + endfacet + facet normal 0.923099 0.232538 0.306292 + outer loop + vertex 892.684 421.931 354.521 + vertex 891.596 423.413 356.674 + vertex 894.296 415.486 354.554 + endloop + endfacet + facet normal 0.923785 0.23353 0.303456 + outer loop + vertex 894.296 415.486 354.554 + vertex 891.596 423.413 356.674 + vertex 893.152 417.213 356.708 + endloop + endfacet + facet normal 0.923562 0.244507 0.295381 + outer loop + vertex 891.013 428.292 354.478 + vertex 889.99 429.547 356.639 + vertex 892.684 421.931 354.521 + endloop + endfacet + facet normal 0.922802 0.243308 0.298728 + outer loop + vertex 892.684 421.931 354.521 + vertex 889.99 429.547 356.639 + vertex 891.596 423.413 356.674 + endloop + endfacet + facet normal 0.922832 0.249407 0.293559 + outer loop + vertex 889.297 434.661 354.464 + vertex 888.341 435.674 356.606 + vertex 891.013 428.292 354.478 + endloop + endfacet + facet normal 0.923167 0.249972 0.29202 + outer loop + vertex 891.013 428.292 354.478 + vertex 888.341 435.674 356.606 + vertex 889.99 429.547 356.639 + endloop + endfacet + facet normal 0.924076 0.252298 0.287103 + outer loop + vertex 887.506 441.191 354.488 + vertex 886.644 441.932 356.612 + vertex 889.297 434.661 354.464 + endloop + endfacet + facet normal 0.922769 0.250006 0.293248 + outer loop + vertex 889.297 434.661 354.464 + vertex 886.644 441.932 356.612 + vertex 888.341 435.674 356.606 + endloop + endfacet + facet normal 0.926364 0.253037 0.278967 + outer loop + vertex 885.643 447.967 354.528 + vertex 884.891 448.379 356.65 + vertex 887.506 441.191 354.488 + endloop + endfacet + facet normal 0.924472 0.249566 0.288217 + outer loop + vertex 887.506 441.191 354.488 + vertex 884.891 448.379 356.65 + vertex 886.644 441.932 356.612 + endloop + endfacet + facet normal 0.929439 0.253726 0.267894 + outer loop + vertex 883.813 454.725 354.478 + vertex 883.14 454.875 356.67 + vertex 885.643 447.967 354.528 + endloop + endfacet + facet normal 0.927113 0.249132 0.279992 + outer loop + vertex 885.643 447.967 354.528 + vertex 883.14 454.875 356.67 + vertex 884.891 448.379 356.65 + endloop + endfacet + facet normal 0.933506 0.257426 0.249599 + outer loop + vertex 882.438 460.079 354.1 + vertex 881.487 461.229 356.468 + vertex 883.813 454.725 354.478 + endloop + endfacet + facet normal 0.930183 0.250503 0.268343 + outer loop + vertex 883.813 454.725 354.478 + vertex 881.487 461.229 356.468 + vertex 883.14 454.875 356.67 + endloop + endfacet + facet normal 0.933524 0.261605 0.245144 + outer loop + vertex 880.33 467.79 354.08 + vertex 879.969 467.296 355.984 + vertex 880.921 465.02 354.788 + endloop + endfacet + facet normal 0.931839 0.253055 0.260074 + outer loop + vertex 880.921 465.02 354.788 + vertex 879.969 467.296 355.984 + vertex 880.194 465.486 356.939 + endloop + endfacet + facet normal 0.334504 -0.273408 0.901862 + outer loop + vertex 863.018 278.156 356.703 + vertex 862.239 283.069 358.482 + vertex 859.214 274.827 357.105 + endloop + endfacet + facet normal 0.313941 -0.267389 0.911012 + outer loop + vertex 859.214 274.827 357.105 + vertex 862.239 283.069 358.482 + vertex 858.779 280.107 358.805 + endloop + endfacet + facet normal 0.318253 -0.272207 0.908085 + outer loop + vertex 867.441 283.144 356.648 + vertex 866.574 288.009 358.41 + vertex 863.018 278.156 356.703 + endloop + endfacet + facet normal 0.328256 -0.275049 0.903657 + outer loop + vertex 863.018 278.156 356.703 + vertex 866.574 288.009 358.41 + vertex 862.239 283.069 358.482 + endloop + endfacet + facet normal 0.320481 -0.26675 0.90892 + outer loop + vertex 872.369 289.253 356.704 + vertex 871.443 294.12 358.458 + vertex 867.441 283.144 356.648 + endloop + endfacet + facet normal 0.328984 -0.269228 0.905144 + outer loop + vertex 867.441 283.144 356.648 + vertex 871.443 294.12 358.458 + vertex 866.574 288.009 358.41 + endloop + endfacet + facet normal 0.335033 -0.257951 0.906209 + outer loop + vertex 877.316 295.846 356.751 + vertex 876.307 300.672 358.498 + vertex 872.369 289.253 356.704 + endloop + endfacet + facet normal 0.343092 -0.260156 0.902555 + outer loop + vertex 872.369 289.253 356.704 + vertex 876.307 300.672 358.498 + vertex 871.443 294.12 358.458 + endloop + endfacet + facet normal 0.359905 -0.246421 0.899858 + outer loop + vertex 881.866 302.502 356.754 + vertex 880.759 307.26 358.5 + vertex 877.316 295.846 356.751 + endloop + endfacet + facet normal 0.366525 -0.247944 0.896763 + outer loop + vertex 877.316 295.846 356.751 + vertex 880.759 307.26 358.5 + vertex 876.307 300.672 358.498 + endloop + endfacet + facet normal 0.387058 -0.232421 0.892281 + outer loop + vertex 885.889 309.131 356.736 + vertex 884.699 313.86 358.484 + vertex 881.866 302.502 356.754 + endloop + endfacet + facet normal 0.39542 -0.233889 0.888223 + outer loop + vertex 881.866 302.502 356.754 + vertex 884.699 313.86 358.484 + vertex 880.759 307.26 358.5 + endloop + endfacet + facet normal 0.419491 -0.217118 0.881412 + outer loop + vertex 889.406 315.836 356.714 + vertex 888.157 320.517 358.461 + vertex 885.889 309.131 356.736 + endloop + endfacet + facet normal 0.425057 -0.217797 0.878573 + outer loop + vertex 885.889 309.131 356.736 + vertex 888.157 320.517 358.461 + vertex 884.699 313.86 358.484 + endloop + endfacet + facet normal 0.450035 -0.200895 0.87012 + outer loop + vertex 892.486 322.726 356.711 + vertex 891.169 327.313 358.451 + vertex 889.406 315.836 356.714 + endloop + endfacet + facet normal 0.457182 -0.20141 0.866267 + outer loop + vertex 889.406 315.836 356.714 + vertex 891.169 327.313 358.451 + vertex 888.157 320.517 358.461 + endloop + endfacet + facet normal 0.486531 -0.180311 0.854854 + outer loop + vertex 895.101 329.806 356.716 + vertex 893.72 334.346 358.46 + vertex 892.486 322.726 356.711 + endloop + endfacet + facet normal 0.494749 -0.180467 0.850091 + outer loop + vertex 892.486 322.726 356.711 + vertex 893.72 334.346 358.46 + vertex 891.169 327.313 358.451 + endloop + endfacet + facet normal 0.526311 -0.157465 0.835584 + outer loop + vertex 897.224 336.96 356.727 + vertex 895.793 341.459 358.476 + vertex 895.101 329.806 356.716 + endloop + endfacet + facet normal 0.532858 -0.157232 0.831469 + outer loop + vertex 895.101 329.806 356.716 + vertex 895.793 341.459 358.476 + vertex 893.72 334.346 358.46 + endloop + endfacet + facet normal 0.575192 -0.129722 0.807667 + outer loop + vertex 898.818 344.087 356.737 + vertex 897.345 348.403 358.479 + vertex 897.224 336.96 356.727 + endloop + endfacet + facet normal 0.577926 -0.129458 0.805756 + outer loop + vertex 897.224 336.96 356.727 + vertex 897.345 348.403 358.479 + vertex 895.793 341.459 358.476 + endloop + endfacet + facet normal 0.633659 -0.0955887 0.767684 + outer loop + vertex 899.883 351.148 356.737 + vertex 898.381 355.183 358.479 + vertex 898.818 344.087 356.737 + endloop + endfacet + facet normal 0.629736 -0.0962365 0.770825 + outer loop + vertex 898.818 344.087 356.737 + vertex 898.381 355.183 358.479 + vertex 897.345 348.403 358.479 + endloop + endfacet + facet normal 0.685417 -0.0585392 0.725794 + outer loop + vertex 900.481 358.107 356.734 + vertex 898.952 361.913 358.484 + vertex 899.883 351.148 356.737 + endloop + endfacet + facet normal 0.684854 -0.0586724 0.726314 + outer loop + vertex 899.883 351.148 356.737 + vertex 898.952 361.913 358.484 + vertex 898.381 355.183 358.479 + endloop + endfacet + facet normal 0.726538 -0.020802 0.686811 + outer loop + vertex 900.679 364.939 356.731 + vertex 899.13 368.554 358.479 + vertex 900.481 358.107 356.734 + endloop + endfacet + facet normal 0.732194 -0.0190718 0.680829 + outer loop + vertex 900.481 358.107 356.734 + vertex 899.13 368.554 358.479 + vertex 898.952 361.913 358.484 + endloop + endfacet + facet normal 0.771833 0.0194517 0.635528 + outer loop + vertex 900.517 371.663 356.722 + vertex 898.987 375.083 358.475 + vertex 900.679 364.939 356.731 + endloop + endfacet + facet normal 0.765669 0.0171375 0.643007 + outer loop + vertex 900.679 364.939 356.731 + vertex 898.987 375.083 358.475 + vertex 899.13 368.554 358.479 + endloop + endfacet + facet normal 0.798364 0.0545276 0.599701 + outer loop + vertex 900.055 378.35 356.728 + vertex 898.528 381.569 358.469 + vertex 900.517 371.663 356.722 + endloop + endfacet + facet normal 0.805156 0.0575546 0.590264 + outer loop + vertex 900.517 371.663 356.722 + vertex 898.528 381.569 358.469 + vertex 898.987 375.083 358.475 + endloop + endfacet + facet normal 0.826903 0.0909849 0.554935 + outer loop + vertex 899.323 385.007 356.729 + vertex 897.811 388.081 358.478 + vertex 900.055 378.35 356.728 + endloop + endfacet + facet normal 0.825316 0.0901711 0.557425 + outer loop + vertex 900.055 378.35 356.728 + vertex 897.811 388.081 358.478 + vertex 898.528 381.569 358.469 + endloop + endfacet + facet normal 0.844671 0.119671 0.521738 + outer loop + vertex 898.383 391.611 356.735 + vertex 896.906 394.455 358.475 + vertex 899.323 385.007 356.729 + endloop + endfacet + facet normal 0.845826 0.120342 0.519708 + outer loop + vertex 899.323 385.007 356.729 + vertex 896.906 394.455 358.475 + vertex 897.811 388.081 358.478 + endloop + endfacet + facet normal 0.861286 0.147568 0.48622 + outer loop + vertex 897.264 398.139 356.736 + vertex 895.848 400.67 358.476 + vertex 898.383 391.611 356.735 + endloop + endfacet + facet normal 0.858972 0.14605 0.490751 + outer loop + vertex 898.383 391.611 356.735 + vertex 895.848 400.67 358.476 + vertex 896.906 394.455 358.475 + endloop + endfacet + facet normal 0.868096 0.169229 0.466659 + outer loop + vertex 896.006 404.584 356.739 + vertex 894.636 406.807 358.481 + vertex 897.264 398.139 356.736 + endloop + endfacet + facet normal 0.871483 0.171722 0.459378 + outer loop + vertex 897.264 398.139 356.736 + vertex 894.636 406.807 358.481 + vertex 895.848 400.67 358.476 + endloop + endfacet + facet normal 0.874495 0.190841 0.445913 + outer loop + vertex 894.627 410.936 356.725 + vertex 893.303 412.895 358.483 + vertex 896.006 404.584 356.739 + endloop + endfacet + facet normal 0.875362 0.191545 0.443904 + outer loop + vertex 896.006 404.584 356.739 + vertex 893.303 412.895 358.483 + vertex 894.636 406.807 358.481 + endloop + endfacet + facet normal 0.876865 0.207226 0.433781 + outer loop + vertex 893.152 417.213 356.708 + vertex 891.884 418.893 358.468 + vertex 894.627 410.936 356.725 + endloop + endfacet + facet normal 0.878811 0.208946 0.428991 + outer loop + vertex 894.627 410.936 356.725 + vertex 891.884 418.893 358.468 + vertex 893.303 412.895 358.483 + endloop + endfacet + facet normal 0.880185 0.223219 0.418865 + outer loop + vertex 891.596 423.413 356.674 + vertex 890.397 424.821 358.444 + vertex 893.152 417.213 356.708 + endloop + endfacet + facet normal 0.879336 0.222408 0.421073 + outer loop + vertex 893.152 417.213 356.708 + vertex 890.397 424.821 358.444 + vertex 891.884 418.893 358.468 + endloop + endfacet + facet normal 0.881344 0.233099 0.410972 + outer loop + vertex 889.99 429.547 356.639 + vertex 888.858 430.699 358.413 + vertex 891.596 423.413 356.674 + endloop + endfacet + facet normal 0.881028 0.232775 0.411832 + outer loop + vertex 891.596 423.413 356.674 + vertex 888.858 430.699 358.413 + vertex 890.397 424.821 358.444 + endloop + endfacet + facet normal 0.88338 0.23986 0.402624 + outer loop + vertex 888.341 435.674 356.606 + vertex 887.284 436.585 358.383 + vertex 889.99 429.547 356.639 + endloop + endfacet + facet normal 0.881469 0.237791 0.408006 + outer loop + vertex 889.99 429.547 356.639 + vertex 887.284 436.585 358.383 + vertex 888.858 430.699 358.413 + endloop + endfacet + facet normal 0.885747 0.239855 0.397393 + outer loop + vertex 886.644 441.932 356.612 + vertex 885.672 442.603 358.373 + vertex 888.341 435.674 356.606 + endloop + endfacet + facet normal 0.883453 0.23729 0.403985 + outer loop + vertex 888.341 435.674 356.606 + vertex 885.672 442.603 358.373 + vertex 887.284 436.585 358.383 + endloop + endfacet + facet normal 0.890679 0.239803 0.386246 + outer loop + vertex 884.891 448.379 356.65 + vertex 884.042 448.742 358.383 + vertex 886.644 441.932 356.612 + endloop + endfacet + facet normal 0.886154 0.234597 0.399619 + outer loop + vertex 886.644 441.932 356.612 + vertex 884.042 448.742 358.383 + vertex 885.672 442.603 358.373 + endloop + endfacet + facet normal 0.897885 0.240979 0.368417 + outer loop + vertex 883.14 454.875 356.67 + vertex 882.451 454.772 358.416 + vertex 884.891 448.379 356.65 + endloop + endfacet + facet normal 0.891635 0.233154 0.388106 + outer loop + vertex 884.891 448.379 356.65 + vertex 882.451 454.772 358.416 + vertex 884.042 448.742 358.383 + endloop + endfacet + facet normal 0.905498 0.246539 0.345388 + outer loop + vertex 881.487 461.229 356.468 + vertex 881.018 460.22 358.417 + vertex 883.14 454.875 356.67 + endloop + endfacet + facet normal 0.899031 0.236385 0.368599 + outer loop + vertex 883.14 454.875 356.67 + vertex 881.018 460.22 358.417 + vertex 882.451 454.772 358.416 + endloop + endfacet + facet normal 0.908042 0.278121 0.313222 + outer loop + vertex 879.969 467.296 355.984 + vertex 879.522 466.525 357.965 + vertex 880.194 465.486 356.939 + endloop + endfacet + facet normal 0.905698 0.242632 0.347622 + outer loop + vertex 880.194 465.486 356.939 + vertex 879.522 466.525 357.965 + vertex 879.965 464.286 358.373 + endloop + endfacet + facet normal 0.278601 -0.223602 0.934015 + outer loop + vertex 862.239 283.069 358.482 + vertex 861.152 287.142 359.781 + vertex 858.779 280.107 358.805 + endloop + endfacet + facet normal 0.25851 -0.217814 0.941132 + outer loop + vertex 858.779 280.107 358.805 + vertex 861.152 287.142 359.781 + vertex 857.712 284.066 360.014 + endloop + endfacet + facet normal 0.269611 -0.223103 0.936768 + outer loop + vertex 866.574 288.009 358.41 + vertex 865.329 292.117 359.747 + vertex 862.239 283.069 358.482 + endloop + endfacet + facet normal 0.275222 -0.224737 0.934744 + outer loop + vertex 862.239 283.069 358.482 + vertex 865.329 292.117 359.747 + vertex 861.152 287.142 359.781 + endloop + endfacet + facet normal 0.264409 -0.218042 0.939439 + outer loop + vertex 871.443 294.12 358.458 + vertex 870.145 298.314 359.797 + vertex 866.574 288.009 358.41 + endloop + endfacet + facet normal 0.274869 -0.221163 0.9357 + outer loop + vertex 866.574 288.009 358.41 + vertex 870.145 298.314 359.797 + vertex 865.329 292.117 359.747 + endloop + endfacet + facet normal 0.274529 -0.209481 0.938484 + outer loop + vertex 876.307 300.672 358.498 + vertex 874.959 304.864 359.828 + vertex 871.443 294.12 358.458 + endloop + endfacet + facet normal 0.281784 -0.211522 0.935872 + outer loop + vertex 871.443 294.12 358.458 + vertex 874.959 304.864 359.828 + vertex 870.145 298.314 359.797 + endloop + endfacet + facet normal 0.29599 -0.200285 0.933957 + outer loop + vertex 880.759 307.26 358.5 + vertex 879.368 311.437 359.836 + vertex 876.307 300.672 358.498 + endloop + endfacet + facet normal 0.297258 -0.200588 0.933489 + outer loop + vertex 876.307 300.672 358.498 + vertex 879.368 311.437 359.836 + vertex 874.959 304.864 359.828 + endloop + endfacet + facet normal 0.317966 -0.187549 0.929367 + outer loop + vertex 884.699 313.86 358.484 + vertex 883.244 318.005 359.818 + vertex 880.759 307.26 358.5 + endloop + endfacet + facet normal 0.32414 -0.188686 0.927001 + outer loop + vertex 880.759 307.26 358.5 + vertex 883.244 318.005 359.818 + vertex 879.368 311.437 359.836 + endloop + endfacet + facet normal 0.339437 -0.173164 0.924552 + outer loop + vertex 888.157 320.517 358.461 + vertex 886.713 324.887 359.81 + vertex 884.699 313.86 358.484 + endloop + endfacet + facet normal 0.348061 -0.174327 0.921121 + outer loop + vertex 884.699 313.86 358.484 + vertex 886.713 324.887 359.81 + vertex 883.244 318.005 359.818 + endloop + endfacet + facet normal 0.367985 -0.1618 0.915646 + outer loop + vertex 891.169 327.313 358.451 + vertex 889.746 331.609 359.783 + vertex 888.157 320.517 358.461 + endloop + endfacet + facet normal 0.366507 -0.161662 0.916263 + outer loop + vertex 888.157 320.517 358.461 + vertex 889.746 331.609 359.783 + vertex 886.713 324.887 359.81 + endloop + endfacet + facet normal 0.402347 -0.147024 0.903604 + outer loop + vertex 893.72 334.346 358.46 + vertex 892.252 338.537 359.796 + vertex 891.169 327.313 358.451 + endloop + endfacet + facet normal 0.401683 -0.146995 0.903904 + outer loop + vertex 891.169 327.313 358.451 + vertex 892.252 338.537 359.796 + vertex 889.746 331.609 359.783 + endloop + endfacet + facet normal 0.427538 -0.126679 0.895077 + outer loop + vertex 895.793 341.459 358.476 + vertex 894.28 345.849 359.82 + vertex 893.72 334.346 358.46 + endloop + endfacet + facet normal 0.445254 -0.126518 0.886421 + outer loop + vertex 893.72 334.346 358.46 + vertex 894.28 345.849 359.82 + vertex 892.252 338.537 359.796 + endloop + endfacet + facet normal 0.471937 -0.105796 0.875261 + outer loop + vertex 897.345 348.403 358.479 + vertex 895.846 352.748 359.812 + vertex 895.793 341.459 358.476 + endloop + endfacet + facet normal 0.470857 -0.105859 0.875836 + outer loop + vertex 895.793 341.459 358.476 + vertex 895.846 352.748 359.812 + vertex 894.28 345.849 359.82 + endloop + endfacet + facet normal 0.533053 -0.0814623 0.842151 + outer loop + vertex 898.381 355.183 358.479 + vertex 896.898 359.035 359.79 + vertex 897.345 348.403 358.479 + endloop + endfacet + facet normal 0.51637 -0.0834148 0.852294 + outer loop + vertex 897.345 348.403 358.479 + vertex 896.898 359.035 359.79 + vertex 895.846 352.748 359.812 + endloop + endfacet + facet normal 0.59044 -0.050731 0.805485 + outer loop + vertex 898.952 361.913 358.484 + vertex 897.447 365.216 359.796 + vertex 898.381 355.183 358.479 + endloop + endfacet + facet normal 0.581726 -0.0523578 0.811698 + outer loop + vertex 898.381 355.183 358.479 + vertex 897.447 365.216 359.796 + vertex 896.898 359.035 359.79 + endloop + endfacet + facet normal 0.633773 -0.016356 0.773346 + outer loop + vertex 899.13 368.554 358.479 + vertex 897.58 371.653 359.815 + vertex 898.952 361.913 358.484 + endloop + endfacet + facet normal 0.637324 -0.0154592 0.770441 + outer loop + vertex 898.952 361.913 358.484 + vertex 897.58 371.653 359.815 + vertex 897.447 365.216 359.796 + endloop + endfacet + facet normal 0.668157 0.015055 0.743868 + outer loop + vertex 898.987 375.083 358.475 + vertex 897.435 378.014 359.81 + vertex 899.13 368.554 358.479 + endloop + endfacet + facet normal 0.670732 0.0158452 0.741531 + outer loop + vertex 899.13 368.554 358.479 + vertex 897.435 378.014 359.81 + vertex 897.58 371.653 359.815 + endloop + endfacet + facet normal 0.710693 0.0509824 0.701652 + outer loop + vertex 898.528 381.569 358.469 + vertex 897.003 384.34 359.813 + vertex 898.987 375.083 358.475 + endloop + endfacet + facet normal 0.701504 0.0476521 0.71107 + outer loop + vertex 898.987 375.083 358.475 + vertex 897.003 384.34 359.813 + vertex 897.435 378.014 359.81 + endloop + endfacet + facet normal 0.729947 0.0794909 0.678866 + outer loop + vertex 897.811 388.081 358.478 + vertex 896.259 390.838 359.824 + vertex 898.528 381.569 358.469 + endloop + endfacet + facet normal 0.739851 0.0835691 0.667561 + outer loop + vertex 898.528 381.569 358.469 + vertex 896.259 390.838 359.824 + vertex 897.003 384.34 359.813 + endloop + endfacet + facet normal 0.756177 0.107678 0.645447 + outer loop + vertex 896.906 394.455 358.475 + vertex 895.352 397.255 359.828 + vertex 897.811 388.081 358.478 + endloop + endfacet + facet normal 0.752143 0.105862 0.650441 + outer loop + vertex 897.811 388.081 358.478 + vertex 895.352 397.255 359.828 + vertex 896.259 390.838 359.824 + endloop + endfacet + facet normal 0.785068 0.133457 0.604862 + outer loop + vertex 895.848 400.67 358.476 + vertex 894.43 403.043 359.793 + vertex 896.906 394.455 358.475 + endloop + endfacet + facet normal 0.771345 0.12661 0.623696 + outer loop + vertex 896.906 394.455 358.475 + vertex 894.43 403.043 359.793 + vertex 895.352 397.255 359.828 + endloop + endfacet + facet normal 0.803199 0.158137 0.574338 + outer loop + vertex 894.636 406.807 358.481 + vertex 893.344 408.624 359.788 + vertex 895.848 400.67 358.476 + endloop + endfacet + facet normal 0.79969 0.156138 0.579755 + outer loop + vertex 895.848 400.67 358.476 + vertex 893.344 408.624 359.788 + vertex 894.43 403.043 359.793 + endloop + endfacet + facet normal 0.808136 0.176774 0.561842 + outer loop + vertex 893.303 412.895 358.483 + vertex 892.043 414.418 359.816 + vertex 894.636 406.807 358.481 + endloop + endfacet + facet normal 0.812962 0.17982 0.553857 + outer loop + vertex 894.636 406.807 358.481 + vertex 892.043 414.418 359.816 + vertex 893.344 408.624 359.788 + endloop + endfacet + facet normal 0.812286 0.193527 0.550216 + outer loop + vertex 891.884 418.893 358.468 + vertex 890.662 420.191 359.816 + vertex 893.303 412.895 358.483 + endloop + endfacet + facet normal 0.814182 0.194809 0.546952 + outer loop + vertex 893.303 412.895 358.483 + vertex 890.662 420.191 359.816 + vertex 892.043 414.418 359.816 + endloop + endfacet + facet normal 0.816193 0.207045 0.539409 + outer loop + vertex 890.397 424.821 358.444 + vertex 889.236 425.858 359.802 + vertex 891.884 418.893 358.468 + endloop + endfacet + facet normal 0.815526 0.206564 0.5406 + outer loop + vertex 891.884 418.893 358.468 + vertex 889.236 425.858 359.802 + vertex 890.662 420.191 359.816 + endloop + endfacet + facet normal 0.819908 0.21739 0.529615 + outer loop + vertex 888.858 430.699 358.413 + vertex 887.772 431.458 359.782 + vertex 890.397 424.821 358.444 + endloop + endfacet + facet normal 0.817514 0.215548 0.534051 + outer loop + vertex 890.397 424.821 358.444 + vertex 887.772 431.458 359.782 + vertex 889.236 425.858 359.802 + endloop + endfacet + facet normal 0.823513 0.222871 0.521684 + outer loop + vertex 887.284 436.585 358.383 + vertex 886.278 437.075 359.761 + vertex 888.858 430.699 358.413 + endloop + endfacet + facet normal 0.820071 0.22009 0.528246 + outer loop + vertex 888.858 430.699 358.413 + vertex 886.278 437.075 359.761 + vertex 887.772 431.458 359.782 + endloop + endfacet + facet normal 0.826872 0.222317 0.516583 + outer loop + vertex 885.672 442.603 358.373 + vertex 884.75 442.842 359.747 + vertex 887.284 436.585 358.383 + endloop + endfacet + facet normal 0.823609 0.219616 0.522912 + outer loop + vertex 887.284 436.585 358.383 + vertex 884.75 442.842 359.747 + vertex 886.278 437.075 359.761 + endloop + endfacet + facet normal 0.83335 0.220412 0.506898 + outer loop + vertex 884.042 448.742 358.383 + vertex 883.19 448.843 359.741 + vertex 885.672 442.603 358.373 + endloop + endfacet + facet normal 0.827605 0.215642 0.518237 + outer loop + vertex 885.672 442.603 358.373 + vertex 883.19 448.843 359.741 + vertex 884.75 442.842 359.747 + endloop + endfacet + facet normal 0.845882 0.220547 0.485637 + outer loop + vertex 882.451 454.772 358.416 + vertex 881.748 454.593 359.722 + vertex 884.042 448.742 358.383 + endloop + endfacet + facet normal 0.834809 0.210968 0.508514 + outer loop + vertex 884.042 448.742 358.383 + vertex 881.748 454.593 359.722 + vertex 883.19 448.843 359.741 + endloop + endfacet + facet normal 0.859288 0.22591 0.4589 + outer loop + vertex 881.018 460.22 358.417 + vertex 880.524 459.486 359.704 + vertex 882.451 454.772 358.416 + endloop + endfacet + facet normal 0.847602 0.213829 0.485642 + outer loop + vertex 882.451 454.772 358.416 + vertex 880.524 459.486 359.704 + vertex 881.748 454.593 359.722 + endloop + endfacet + facet normal 0.873373 0.249165 0.418494 + outer loop + vertex 879.522 466.525 357.965 + vertex 879.128 465.415 359.448 + vertex 879.965 464.286 358.373 + endloop + endfacet + facet normal 0.868919 0.224171 0.441279 + outer loop + vertex 879.965 464.286 358.373 + vertex 879.128 465.415 359.448 + vertex 879.566 463.246 359.687 + endloop + endfacet + facet normal 0.231797 -0.18693 0.954635 + outer loop + vertex 861.152 287.142 359.781 + vertex 860.054 289.734 360.555 + vertex 857.712 284.066 360.014 + endloop + endfacet + facet normal 0.202447 -0.175644 0.963413 + outer loop + vertex 857.712 284.066 360.014 + vertex 860.054 289.734 360.555 + vertex 857.671 288.487 360.828 + endloop + endfacet + facet normal 0.229439 -0.186155 0.955356 + outer loop + vertex 865.329 292.117 359.747 + vertex 863.632 294.577 360.634 + vertex 861.152 287.142 359.781 + endloop + endfacet + facet normal 0.231888 -0.186888 0.954621 + outer loop + vertex 861.152 287.142 359.781 + vertex 863.632 294.577 360.634 + vertex 860.054 289.734 360.555 + endloop + endfacet + facet normal 0.224128 -0.181904 0.957433 + outer loop + vertex 870.145 298.314 359.797 + vertex 868.42 300.924 360.697 + vertex 865.329 292.117 359.747 + endloop + endfacet + facet normal 0.231887 -0.184377 0.955109 + outer loop + vertex 865.329 292.117 359.747 + vertex 868.42 300.924 360.697 + vertex 863.632 294.577 360.634 + endloop + endfacet + facet normal 0.232496 -0.175397 0.956651 + outer loop + vertex 874.959 304.864 359.828 + vertex 873.258 307.598 360.743 + vertex 870.145 298.314 359.797 + endloop + endfacet + facet normal 0.23316 -0.1756 0.956452 + outer loop + vertex 870.145 298.314 359.797 + vertex 873.258 307.598 360.743 + vertex 868.42 300.924 360.697 + endloop + endfacet + facet normal 0.245628 -0.165974 0.955049 + outer loop + vertex 879.368 311.437 359.836 + vertex 877.664 314.15 360.746 + vertex 874.959 304.864 359.828 + endloop + endfacet + facet normal 0.246359 -0.166165 0.954828 + outer loop + vertex 874.959 304.864 359.828 + vertex 877.664 314.15 360.746 + vertex 873.258 307.598 360.743 + endloop + endfacet + facet normal 0.267529 -0.155219 0.950965 + outer loop + vertex 883.244 318.005 359.818 + vertex 881.538 320.676 360.734 + vertex 879.368 311.437 359.836 + endloop + endfacet + facet normal 0.262864 -0.154265 0.952421 + outer loop + vertex 879.368 311.437 359.836 + vertex 881.538 320.676 360.734 + vertex 877.664 314.15 360.746 + endloop + endfacet + facet normal 0.287222 -0.143621 0.947036 + outer loop + vertex 886.713 324.887 359.81 + vertex 885.002 327.563 360.734 + vertex 883.244 318.005 359.818 + endloop + endfacet + facet normal 0.284648 -0.143228 0.947872 + outer loop + vertex 883.244 318.005 359.818 + vertex 885.002 327.563 360.734 + vertex 881.538 320.676 360.734 + endloop + endfacet + facet normal 0.29409 -0.128871 0.94705 + outer loop + vertex 889.746 331.609 359.783 + vertex 888.354 335.875 360.795 + vertex 886.713 324.887 359.81 + endloop + endfacet + facet normal 0.305942 -0.130287 0.943093 + outer loop + vertex 886.713 324.887 359.81 + vertex 888.354 335.875 360.795 + vertex 885.002 327.563 360.734 + endloop + endfacet + facet normal 0.337709 -0.123908 0.933059 + outer loop + vertex 892.252 338.537 359.796 + vertex 890.862 340.889 360.611 + vertex 889.746 331.609 359.783 + endloop + endfacet + facet normal 0.31252 -0.121682 0.942085 + outer loop + vertex 889.746 331.609 359.783 + vertex 890.862 340.889 360.611 + vertex 888.354 335.875 360.795 + endloop + endfacet + facet normal 0.357125 -0.102215 0.928447 + outer loop + vertex 894.28 345.849 359.82 + vertex 892.722 349.411 360.812 + vertex 892.252 338.537 359.796 + endloop + endfacet + facet normal 0.36888 -0.102292 0.923831 + outer loop + vertex 892.252 338.537 359.796 + vertex 892.722 349.411 360.812 + vertex 890.862 340.889 360.611 + endloop + endfacet + facet normal 0.387381 -0.0868577 0.917819 + outer loop + vertex 895.846 352.748 359.812 + vertex 894.484 356.6 360.752 + vertex 894.28 345.849 359.82 + endloop + endfacet + facet normal 0.385828 -0.0868847 0.91847 + outer loop + vertex 894.28 345.849 359.82 + vertex 894.484 356.6 360.752 + vertex 892.722 349.411 360.812 + endloop + endfacet + facet normal 0.424228 -0.0678185 0.903012 + outer loop + vertex 896.898 359.035 359.79 + vertex 895.573 362.881 360.701 + vertex 895.846 352.748 359.812 + endloop + endfacet + facet normal 0.430233 -0.0674098 0.900198 + outer loop + vertex 895.846 352.748 359.812 + vertex 895.573 362.881 360.701 + vertex 894.484 356.6 360.752 + endloop + endfacet + facet normal 0.505456 -0.0456306 0.861645 + outer loop + vertex 897.447 365.216 359.796 + vertex 896.28 367.212 360.586 + vertex 896.898 359.035 359.79 + endloop + endfacet + facet normal 0.460246 -0.0514498 0.886299 + outer loop + vertex 896.898 359.035 359.79 + vertex 896.28 367.212 360.586 + vertex 895.573 362.881 360.701 + endloop + endfacet + facet normal 0.546946 -0.0137872 0.837054 + outer loop + vertex 897.58 371.653 359.815 + vertex 896.264 373.356 360.703 + vertex 897.447 365.216 359.796 + endloop + endfacet + facet normal 0.543486 -0.0145396 0.839292 + outer loop + vertex 897.447 365.216 359.796 + vertex 896.264 373.356 360.703 + vertex 896.28 367.212 360.586 + endloop + endfacet + facet normal 0.584896 0.0139302 0.810989 + outer loop + vertex 897.435 378.014 359.81 + vertex 896.106 379.847 360.737 + vertex 897.58 371.653 359.815 + endloop + endfacet + facet normal 0.567671 0.00945577 0.823202 + outer loop + vertex 897.58 371.653 359.815 + vertex 896.106 379.847 360.737 + vertex 896.264 373.356 360.703 + endloop + endfacet + facet normal 0.617813 0.0419088 0.785207 + outer loop + vertex 897.003 384.34 359.813 + vertex 895.727 385.961 360.73 + vertex 897.435 378.014 359.81 + endloop + endfacet + facet normal 0.606908 0.0385674 0.793836 + outer loop + vertex 897.435 378.014 359.81 + vertex 895.727 385.961 360.73 + vertex 896.106 379.847 360.737 + endloop + endfacet + facet normal 0.655093 0.0737158 0.751943 + outer loop + vertex 896.259 390.838 359.824 + vertex 895.038 392.242 360.75 + vertex 897.003 384.34 359.813 + endloop + endfacet + facet normal 0.637573 0.0675236 0.767425 + outer loop + vertex 897.003 384.34 359.813 + vertex 895.038 392.242 360.75 + vertex 895.727 385.961 360.73 + endloop + endfacet + facet normal 0.656094 0.0922254 0.749022 + outer loop + vertex 895.352 397.255 359.828 + vertex 893.876 399.546 360.839 + vertex 896.259 390.838 359.824 + endloop + endfacet + facet normal 0.670292 0.0976703 0.735642 + outer loop + vertex 896.259 390.838 359.824 + vertex 893.876 399.546 360.839 + vertex 895.038 392.242 360.75 + endloop + endfacet + facet normal 0.678936 0.112508 0.725526 + outer loop + vertex 894.43 403.043 359.793 + vertex 893.052 405.382 360.72 + vertex 895.352 397.255 359.828 + endloop + endfacet + facet normal 0.671958 0.109779 0.732408 + outer loop + vertex 895.352 397.255 359.828 + vertex 893.052 405.382 360.72 + vertex 893.876 399.546 360.839 + endloop + endfacet + facet normal 0.72928 0.14251 0.66921 + outer loop + vertex 893.344 408.624 359.788 + vertex 892.452 409.466 360.58 + vertex 894.43 403.043 359.793 + endloop + endfacet + facet normal 0.691833 0.125857 0.711004 + outer loop + vertex 894.43 403.043 359.793 + vertex 892.452 409.466 360.58 + vertex 893.052 405.382 360.72 + endloop + endfacet + facet normal 0.734516 0.1617 0.659045 + outer loop + vertex 892.043 414.418 359.816 + vertex 891.164 414.806 360.701 + vertex 893.344 408.624 359.788 + endloop + endfacet + facet normal 0.736925 0.162995 0.656029 + outer loop + vertex 893.344 408.624 359.788 + vertex 891.164 414.806 360.701 + vertex 892.452 409.466 360.58 + endloop + endfacet + facet normal 0.73911 0.176848 0.649954 + outer loop + vertex 890.662 420.191 359.816 + vertex 889.753 420.616 360.735 + vertex 892.043 414.418 359.816 + endloop + endfacet + facet normal 0.73566 0.174918 0.654376 + outer loop + vertex 892.043 414.418 359.816 + vertex 889.753 420.616 360.735 + vertex 891.164 414.806 360.701 + endloop + endfacet + facet normal 0.74272 0.188499 0.642523 + outer loop + vertex 889.236 425.858 359.802 + vertex 888.347 426.182 360.735 + vertex 890.662 420.191 359.816 + endloop + endfacet + facet normal 0.739963 0.186875 0.646167 + outer loop + vertex 890.662 420.191 359.816 + vertex 888.347 426.182 360.735 + vertex 889.753 420.616 360.735 + endloop + endfacet + facet normal 0.74689 0.197454 0.634955 + outer loop + vertex 887.772 431.458 359.782 + vertex 886.937 431.573 360.729 + vertex 889.236 425.858 359.802 + endloop + endfacet + facet normal 0.742867 0.194949 0.640424 + outer loop + vertex 889.236 425.858 359.802 + vertex 886.937 431.573 360.729 + vertex 888.347 426.182 360.735 + endloop + endfacet + facet normal 0.750769 0.202027 0.628912 + outer loop + vertex 886.278 437.075 359.761 + vertex 885.524 436.907 360.716 + vertex 887.772 431.458 359.782 + endloop + endfacet + facet normal 0.74671 0.199382 0.634564 + outer loop + vertex 887.772 431.458 359.782 + vertex 885.524 436.907 360.716 + vertex 886.937 431.573 360.729 + endloop + endfacet + facet normal 0.755724 0.201871 0.623 + outer loop + vertex 884.75 442.842 359.747 + vertex 884.085 442.372 360.705 + vertex 886.278 437.075 359.761 + endloop + endfacet + facet normal 0.751509 0.199061 0.628975 + outer loop + vertex 886.278 437.075 359.761 + vertex 884.085 442.372 360.705 + vertex 885.524 436.907 360.716 + endloop + endfacet + facet normal 0.763059 0.198966 0.614942 + outer loop + vertex 883.19 448.843 359.741 + vertex 882.597 448.134 360.706 + vertex 884.75 442.842 359.747 + endloop + endfacet + facet normal 0.758304 0.195788 0.621806 + outer loop + vertex 884.75 442.842 359.747 + vertex 882.597 448.134 360.706 + vertex 884.085 442.372 360.705 + endloop + endfacet + facet normal 0.771899 0.195503 0.604939 + outer loop + vertex 881.748 454.593 359.722 + vertex 881.003 454.44 360.723 + vertex 883.19 448.843 359.741 + endloop + endfacet + facet normal 0.766866 0.192238 0.612341 + outer loop + vertex 883.19 448.843 359.741 + vertex 881.003 454.44 360.723 + vertex 882.597 448.134 360.706 + endloop + endfacet + facet normal 0.799609 0.202134 0.56548 + outer loop + vertex 880.524 459.486 359.704 + vertex 880.199 458.608 360.478 + vertex 881.748 454.593 359.722 + endloop + endfacet + facet normal 0.774343 0.184925 0.605141 + outer loop + vertex 881.748 454.593 359.722 + vertex 880.199 458.608 360.478 + vertex 881.003 454.44 360.723 + endloop + endfacet + facet normal 0.812563 0.22351 0.538317 + outer loop + vertex 879.128 465.415 359.448 + vertex 878.7 464.37 360.528 + vertex 879.566 463.246 359.687 + endloop + endfacet + facet normal 0.806376 0.207039 0.553979 + outer loop + vertex 879.566 463.246 359.687 + vertex 878.7 464.37 360.528 + vertex 879.296 462.027 360.535 + endloop + endfacet + facet normal 0.724777 0.17968 0.665141 + outer loop + vertex 878.329 464.393 360.978 + vertex 878.265 464.253 361.086 + vertex 878.581 463.286 361.003 + endloop + endfacet + facet normal 0.71261 0.174481 0.679517 + outer loop + vertex 878.581 463.286 361.003 + vertex 878.265 464.253 361.086 + vertex 878.365 463.677 361.128 + endloop + endfacet + facet normal 0.295397 -0.611669 -0.733895 + outer loop + vertex 849.46 240.007 299.039 + vertex 848.339 242.413 296.583 + vertex 850.528 242.419 297.459 + endloop + endfacet + facet normal 0.461793 -0.617711 -0.636538 + outer loop + vertex 856.19 231.515 309.685 + vertex 854.613 232.502 307.583 + vertex 855.985 232.248 308.826 + endloop + endfacet + facet normal 0.499303 -0.730259 -0.466282 + outer loop + vertex 857.753 231.143 311.94 + vertex 856.19 231.515 309.685 + vertex 857.523 231.665 310.877 + endloop + endfacet + facet normal 0.476199 -0.863966 -0.163696 + outer loop + vertex 859.425 231.508 314.882 + vertex 857.753 231.143 311.94 + vertex 858.948 231.581 313.111 + endloop + endfacet + facet normal 0.561091 -0.826728 0.0411991 + outer loop + vertex 860.585 232.432 317.629 + vertex 859.425 231.508 314.882 + vertex 860.661 232.446 316.889 + endloop + endfacet + facet normal 0.414726 -0.846414 0.334045 + outer loop + vertex 861.149 233.867 320.564 + vertex 860.585 232.432 317.629 + vertex 861.074 232.999 318.459 + endloop + endfacet + facet normal 0.660587 -0.667769 0.343087 + outer loop + vertex 861.529 236.695 325.338 + vertex 861.149 233.867 320.564 + vertex 864.111 238.135 323.169 + endloop + endfacet + facet normal 0.64236 -0.640333 0.421127 + outer loop + vertex 861.599 239.415 329.365 + vertex 861.529 236.695 325.338 + vertex 864.458 241.392 328.011 + endloop + endfacet + facet normal 0.650029 -0.605132 0.45965 + outer loop + vertex 861.539 241.023 331.568 + vertex 861.599 239.415 329.365 + vertex 863.87 243.882 332.035 + endloop + endfacet + facet normal 0.611608 -0.585634 0.531949 + outer loop + vertex 861.286 242.693 333.697 + vertex 861.539 241.023 331.568 + vertex 863.87 243.882 332.035 + endloop + endfacet + facet normal 0.578813 -0.55982 0.592939 + outer loop + vertex 860.83 249.058 340.46 + vertex 860.857 246.312 337.84 + vertex 863.287 250.791 339.697 + endloop + endfacet + facet normal 0.535096 -0.511099 0.672644 + outer loop + vertex 859.627 256.239 347.258 + vertex 859.623 253.116 344.889 + vertex 862.075 257.86 346.543 + endloop + endfacet + facet normal 0.506664 -0.479537 0.716474 + outer loop + vertex 858.394 257.436 348.932 + vertex 859.627 256.239 347.258 + vertex 861.096 261.181 349.528 + endloop + endfacet + facet normal 0.481916 -0.465775 0.742166 + outer loop + vertex 858.343 260.824 351.091 + vertex 858.394 257.436 348.932 + vertex 861.096 261.181 349.528 + endloop + endfacet + facet normal 0.464381 -0.439136 0.769096 + outer loop + vertex 858.351 264.271 353.054 + vertex 858.343 260.824 351.091 + vertex 860.788 265.763 352.435 + endloop + endfacet + facet normal 0.437008 -0.388174 0.811384 + outer loop + vertex 857.162 265.679 354.369 + vertex 858.351 264.271 353.054 + vertex 859.846 269.666 354.83 + endloop + endfacet + facet normal 0.399643 -0.366358 0.840278 + outer loop + vertex 857.111 269.243 355.946 + vertex 857.162 265.679 354.369 + vertex 859.846 269.666 354.83 + endloop + endfacet + facet normal 0.408159 -0.330239 0.851087 + outer loop + vertex 856.949 271.886 357.05 + vertex 857.111 269.243 355.946 + vertex 859.214 274.827 357.105 + endloop + endfacet + facet normal 0.331195 -0.271963 0.903519 + outer loop + vertex 856.563 274.739 358.05 + vertex 856.949 271.886 357.05 + vertex 859.214 274.827 357.105 + endloop + endfacet + facet normal 0.27656 -0.244771 0.929302 + outer loop + vertex 855.954 278.862 359.317 + vertex 856.563 274.739 358.05 + vertex 858.779 280.107 358.805 + endloop + endfacet + facet normal 0.261798 -0.214398 0.941008 + outer loop + vertex 855.595 281.484 360.015 + vertex 855.954 278.862 359.317 + vertex 857.712 284.066 360.014 + endloop + endfacet + facet normal 0.208126 -0.170363 0.963151 + outer loop + vertex 855.335 284.231 360.557 + vertex 855.595 281.484 360.015 + vertex 857.712 284.066 360.014 + endloop + endfacet + facet normal 0.173805 -0.157472 0.972108 + outer loop + vertex 855.55 287.78 361.093 + vertex 855.335 284.231 360.557 + vertex 857.671 288.487 360.828 + endloop + endfacet + facet normal 0.210809 -0.15292 0.965492 + outer loop + vertex 873.374 313.468 361.569 + vertex 871.476 310.904 361.577 + vertex 873.779 313.623 361.505 + endloop + endfacet + facet normal 0.264861 -0.127854 0.955773 + outer loop + vertex 883.256 330.96 361.566 + vertex 881.915 328.181 361.566 + vertex 881.498 326.828 361.5 + endloop + endfacet + facet normal 0.365191 -0.154428 0.918034 + outer loop + vertex 886.872 338.958 361.569 + vertex 885.818 336.387 361.556 + vertex 887.485 340.054 361.51 + endloop + endfacet + facet normal 0.341564 -0.140613 0.92928 + outer loop + vertex 887.931 341.493 361.563 + vertex 886.872 338.958 361.569 + vertex 887.485 340.054 361.51 + endloop + endfacet + facet normal 0.89282 -0.289952 0.344674 + outer loop + vertex 889.106 345.123 361.575 + vertex 887.931 341.493 361.563 + vertex 887.485 340.054 361.51 + endloop + endfacet + facet normal 0.263867 -0.0804469 0.961199 + outer loop + vertex 890.992 351.404 361.582 + vertex 889.106 345.123 361.575 + vertex 889.864 346.69 361.498 + endloop + endfacet + facet normal 0.284668 -0.0719413 0.955923 + outer loop + vertex 892.382 356.807 361.575 + vertex 890.992 351.404 361.582 + vertex 891.66 353.036 361.506 + endloop + endfacet + facet normal 0.346215 -0.0665544 0.935791 + outer loop + vertex 893.366 361.968 361.578 + vertex 892.382 356.807 361.575 + vertex 892.994 359.121 361.513 + endloop + endfacet + facet normal 0.448618 -0.0625008 0.891535 + outer loop + vertex 894.093 367.242 361.582 + vertex 893.366 361.968 361.578 + vertex 894.043 365.866 361.511 + endloop + endfacet + facet normal 0.712312 -0.0621946 0.699102 + outer loop + vertex 894.444 371.166 361.573 + vertex 894.093 367.242 361.582 + vertex 894.043 365.866 361.511 + endloop + endfacet + facet normal 0.481222 -0.0166982 0.87644 + outer loop + vertex 894.598 376.495 361.59 + vertex 894.444 371.166 361.573 + vertex 894.632 372.342 361.492 + endloop + endfacet + facet normal 0.413406 0.00431543 0.910537 + outer loop + vertex 894.52 382.908 361.595 + vertex 894.598 376.495 361.59 + vertex 894.772 378.758 361.5 + endloop + endfacet + facet normal 0.447169 0.0241632 0.894123 + outer loop + vertex 894.265 388.047 361.584 + vertex 894.52 382.908 361.595 + vertex 894.577 384.924 361.512 + endloop + endfacet + facet normal 0.498096 0.0490019 0.865736 + outer loop + vertex 893.777 392.96 361.587 + vertex 894.265 388.047 361.584 + vertex 894.173 390.411 361.503 + endloop + endfacet + facet normal 0.498208 0.0648765 0.864627 + outer loop + vertex 892.982 399.065 361.587 + vertex 893.777 392.96 361.587 + vertex 893.535 395.942 361.502 + endloop + endfacet + facet normal 0.557463 0.0878584 0.82554 + outer loop + vertex 892.207 404.024 361.582 + vertex 892.982 399.065 361.587 + vertex 892.72 401.369 361.518 + endloop + endfacet + facet normal 0.565381 0.104021 0.818245 + outer loop + vertex 891.319 408.773 361.592 + vertex 892.207 404.024 361.582 + vertex 891.864 406.347 361.524 + endloop + endfacet + facet normal 0.546396 0.112324 0.829961 + outer loop + vertex 890.108 414.707 361.586 + vertex 891.319 408.773 361.592 + vertex 890.88 411.578 361.501 + endloop + endfacet + facet normal 0.588492 0.13209 0.79764 + outer loop + vertex 889.019 419.627 361.575 + vertex 890.108 414.707 361.586 + vertex 889.638 417.367 361.492 + endloop + endfacet + facet normal 0.669852 0.161759 0.724661 + outer loop + vertex 878.772 461.528 361.248 + vertex 879.564 457.463 361.424 + vertex 879.433 458.398 361.337 + endloop + endfacet + facet normal -0.795722 -0.182829 -0.577408 + outer loop + vertex 878.302 464.302 361.019 + vertex 878.772 461.528 361.248 + vertex 878.365 463.677 361.128 + endloop + endfacet + facet normal 0.742748 0.218566 0.632893 + outer loop + vertex 878.729 465.236 360.194 + vertex 878.302 464.302 361.019 + vertex 878.7 464.37 360.528 + endloop + endfacet + facet normal 0.810333 0.298355 0.504327 + outer loop + vertex 879.199 466.354 358.779 + vertex 878.729 465.236 360.194 + vertex 879.128 465.415 359.448 + endloop + endfacet + facet normal 0.826405 0.386541 0.409439 + outer loop + vertex 879.597 467.458 356.932 + vertex 879.199 466.354 358.779 + vertex 879.522 466.525 357.965 + endloop + endfacet + facet normal 0.882219 0.377292 0.281676 + outer loop + vertex 880.08 468.478 354.054 + vertex 879.597 467.458 356.932 + vertex 879.969 467.296 355.984 + endloop + endfacet + facet normal 0.922856 0.330921 0.197047 + outer loop + vertex 880.446 469.14 351.225 + vertex 880.08 468.478 354.054 + vertex 880.538 468.416 352.013 + endloop + endfacet + facet normal 0.953303 0.272407 0.130416 + outer loop + vertex 880.623 469.489 349.202 + vertex 880.446 469.14 351.225 + vertex 880.85 468.781 349.022 + endloop + endfacet + facet normal 0.954396 0.278712 0.106996 + outer loop + vertex 880.82 469.609 347.134 + vertex 880.623 469.489 349.202 + vertex 880.85 468.781 349.022 + endloop + endfacet + facet normal 0.961479 0.266184 0.06858 + outer loop + vertex 880.928 469.888 344.543 + vertex 880.82 469.609 347.134 + vertex 881.162 468.762 345.621 + endloop + endfacet + facet normal 0.967011 0.251252 -0.0419662 + outer loop + vertex 881.016 469.604 324.5 + vertex 881.052 469.818 326.626 + vertex 881.221 469.164 326.609 + endloop + endfacet + facet normal 0.96792 0.243716 -0.0611024 + outer loop + vertex 880.9 469.494 322.233 + vertex 881.016 469.604 324.5 + vertex 881.082 468.812 322.393 + endloop + endfacet + facet normal 0.967577 0.238348 -0.0835818 + outer loop + vertex 880.815 469.081 320.07 + vertex 880.9 469.494 322.233 + vertex 881.082 468.812 322.393 + endloop + endfacet + facet normal 0.961255 0.246995 -0.122405 + outer loop + vertex 880.61 468.402 317.088 + vertex 880.815 469.081 320.07 + vertex 880.856 468.125 318.462 + endloop + endfacet + facet normal 0.976491 0.170142 -0.132351 + outer loop + vertex 880.369 467.508 314.159 + vertex 880.61 468.402 317.088 + vertex 880.485 466.829 314.144 + endloop + endfacet + facet normal 0.968884 0.16987 -0.180023 + outer loop + vertex 880.104 466.59 311.868 + vertex 880.369 467.508 314.159 + vertex 880.485 466.829 314.144 + endloop + endfacet + facet normal 0.953039 0.19874 -0.228514 + outer loop + vertex 879.708 465.894 309.614 + vertex 880.104 466.59 311.868 + vertex 879.777 465.069 309.181 + endloop + endfacet + facet normal 0.938313 0.218318 -0.268155 + outer loop + vertex 879.118 464.911 306.747 + vertex 879.708 465.894 309.614 + vertex 879.777 465.069 309.181 + endloop + endfacet + facet normal 0.953749 0.179378 -0.24122 + outer loop + vertex 898.037 382.312 292.693 + vertex 897.592 385.291 293.15 + vertex 898.688 380.893 294.21 + endloop + endfacet + facet normal 0.95364 0.177012 -0.243387 + outer loop + vertex 898.641 379.288 292.862 + vertex 898.037 382.312 292.693 + vertex 898.688 380.893 294.21 + endloop + endfacet + facet normal 0.961024 0.16109 -0.224684 + outer loop + vertex 899.261 375.657 292.91 + vertex 898.641 379.288 292.862 + vertex 898.688 380.893 294.21 + endloop + endfacet + facet normal 0.957903 0.155211 -0.241518 + outer loop + vertex 899.938 371.527 292.94 + vertex 899.261 375.657 292.91 + vertex 900.16 372.388 294.373 + endloop + endfacet + facet normal 0.963848 0.134515 -0.230007 + outer loop + vertex 900.462 367.731 292.914 + vertex 899.938 371.527 292.94 + vertex 900.16 372.388 294.373 + endloop + endfacet + facet normal 0.961542 0.127396 -0.243325 + outer loop + vertex 900.996 363.681 292.904 + vertex 900.462 367.731 292.914 + vertex 901.281 364.319 294.365 + endloop + endfacet + facet normal 0.966935 0.102502 -0.233516 + outer loop + vertex 901.389 359.924 292.885 + vertex 900.996 363.681 292.904 + vertex 901.281 364.319 294.365 + endloop + endfacet + facet normal 0.964957 0.0940814 -0.244964 + outer loop + vertex 901.784 355.896 292.894 + vertex 901.389 359.924 292.885 + vertex 902.11 356.354 294.352 + endloop + endfacet + facet normal 0.969246 0.0659787 -0.237086 + outer loop + vertex 902.05 352.024 292.901 + vertex 901.784 355.896 292.894 + vertex 902.11 356.354 294.352 + endloop + endfacet + facet normal 0.967049 0.0550505 -0.248569 + outer loop + vertex 902.29 347.917 292.927 + vertex 902.05 352.024 292.901 + vertex 902.642 348.138 294.345 + endloop + endfacet + facet normal 0.969269 0.0261553 -0.244608 + outer loop + vertex 902.396 343.926 292.922 + vertex 902.29 347.917 292.927 + vertex 902.642 348.138 294.345 + endloop + endfacet + facet normal 0.973917 0.0178366 -0.226203 + outer loop + vertex 902.463 340.033 292.9 + vertex 902.396 343.926 292.922 + vertex 902.782 339.216 294.209 + endloop + endfacet + facet normal 0.968654 -0.0186647 -0.247712 + outer loop + vertex 902.362 337.355 292.707 + vertex 902.463 340.033 292.9 + vertex 902.782 339.216 294.209 + endloop + endfacet + facet normal 0.970481 -0.0254351 -0.239831 + outer loop + vertex 902.372 333.8 293.125 + vertex 902.362 337.355 292.707 + vertex 902.782 339.216 294.209 + endloop + endfacet + facet normal 0.962125 -0.0606734 -0.265773 + outer loop + vertex 902.02 329.904 292.742 + vertex 902.372 333.8 293.125 + vertex 902.527 330.741 294.385 + endloop + endfacet + facet normal 0.963399 -0.0824969 -0.255061 + outer loop + vertex 901.784 326.001 293.113 + vertex 902.02 329.904 292.742 + vertex 902.527 330.741 294.385 + endloop + endfacet + facet normal 0.953948 -0.123166 -0.273519 + outer loop + vertex 901.172 322.156 292.709 + vertex 901.784 326.001 293.113 + vertex 901.705 322.65 294.345 + endloop + endfacet + facet normal 0.952511 -0.150173 -0.264899 + outer loop + vertex 900.642 318.179 293.059 + vertex 901.172 322.156 292.709 + vertex 901.705 322.65 294.345 + endloop + endfacet + facet normal 0.943586 -0.187382 -0.273007 + outer loop + vertex 899.826 314.628 292.676 + vertex 900.642 318.179 293.059 + vertex 900.193 314.275 294.183 + endloop + endfacet + facet normal 0.940804 -0.198308 -0.274885 + outer loop + vertex 899.358 312.081 292.912 + vertex 899.826 314.628 292.676 + vertex 900.193 314.275 294.183 + endloop + endfacet + facet normal 0.948708 -0.244274 -0.200707 + outer loop + vertex 898.798 309.717 293.142 + vertex 899.358 312.081 292.912 + vertex 900.193 314.275 294.183 + endloop + endfacet + facet normal 0.917521 -0.271999 -0.290126 + outer loop + vertex 897.686 306.362 292.768 + vertex 898.798 309.717 293.142 + vertex 898.222 306.474 294.358 + endloop + endfacet + facet normal 0.911569 -0.294884 -0.286507 + outer loop + vertex 896.503 302.37 293.114 + vertex 897.686 306.362 292.768 + vertex 898.222 306.474 294.358 + endloop + endfacet + facet normal 0.900937 -0.33159 -0.279929 + outer loop + vertex 895.178 299.106 292.717 + vertex 896.503 302.37 293.114 + vertex 895.27 298.078 294.228 + endloop + endfacet + facet normal 0.89281 -0.345552 -0.288937 + outer loop + vertex 894.172 296.338 292.918 + vertex 895.178 299.106 292.717 + vertex 895.27 298.078 294.228 + endloop + endfacet + facet normal 0.890838 -0.400915 -0.213717 + outer loop + vertex 892.707 293.053 292.971 + vertex 894.172 296.338 292.918 + vertex 895.27 298.078 294.228 + endloop + endfacet + facet normal 0.875574 -0.396183 -0.276421 + outer loop + vertex 891.246 289.793 293.016 + vertex 892.707 293.053 292.971 + vertex 891.687 289.87 294.302 + endloop + endfacet + facet normal 0.857261 -0.439929 -0.267519 + outer loop + vertex 890.49 288.32 293.019 + vertex 891.246 289.793 293.016 + vertex 891.687 289.87 294.302 + endloop + endfacet + facet normal 0.850677 -0.481312 -0.211395 + outer loop + vertex 888.962 285.616 293.026 + vertex 890.49 288.32 293.019 + vertex 891.687 289.87 294.302 + endloop + endfacet + facet normal 0.819905 -0.46736 -0.330651 + outer loop + vertex 887.021 282.182 293.066 + vertex 888.962 285.616 293.026 + vertex 887.903 282.67 294.564 + endloop + endfacet + facet normal 0.802984 -0.511194 -0.306427 + outer loop + vertex 884.981 278.937 293.133 + vertex 887.021 282.182 293.066 + vertex 887.903 282.67 294.564 + endloop + endfacet + facet normal 0.796128 -0.513764 -0.31973 + outer loop + vertex 883.089 275.96 293.208 + vertex 884.981 278.937 293.133 + vertex 883.382 275.557 294.583 + endloop + endfacet + facet normal 0.771845 -0.546895 -0.324285 + outer loop + vertex 882.136 274.585 293.256 + vertex 883.089 275.96 293.208 + vertex 883.382 275.557 294.583 + endloop + endfacet + facet normal 0.762172 -0.577311 -0.292925 + outer loop + vertex 880.237 272.023 293.364 + vertex 882.136 274.585 293.256 + vertex 883.382 275.557 294.583 + endloop + endfacet + facet normal 0.752277 -0.567938 -0.333954 + outer loop + vertex 878.201 269.258 293.481 + vertex 880.237 272.023 293.364 + vertex 878.434 268.772 294.832 + endloop + endfacet + facet normal 0.727266 -0.596316 -0.33984 + outer loop + vertex 877.187 267.988 293.538 + vertex 878.201 269.258 293.481 + vertex 878.434 268.772 294.832 + endloop + endfacet + facet normal 0.713844 -0.629531 -0.306786 + outer loop + vertex 875.143 265.633 293.616 + vertex 877.187 267.988 293.538 + vertex 878.434 268.772 294.832 + endloop + endfacet + facet normal 0.696754 -0.620255 -0.360301 + outer loop + vertex 872.723 262.866 293.7 + vertex 875.143 265.633 293.616 + vertex 872.84 262.149 295.161 + endloop + endfacet + facet normal 0.656364 -0.655111 -0.374187 + outer loop + vertex 870.667 260.832 293.654 + vertex 872.723 262.866 293.7 + vertex 872.84 262.149 295.161 + endloop + endfacet + facet normal 0.656189 -0.655747 -0.373379 + outer loop + vertex 868.622 258.433 294.274 + vertex 870.667 260.832 293.654 + vertex 872.84 262.149 295.161 + endloop + endfacet + facet normal 0.62339 -0.660109 -0.419095 + outer loop + vertex 866.5 256.441 294.255 + vertex 868.622 258.433 294.274 + vertex 866.983 255.937 295.767 + endloop + endfacet + facet normal 0.594095 -0.68686 -0.418658 + outer loop + vertex 864.096 254.271 294.403 + vertex 866.5 256.441 294.255 + vertex 866.983 255.937 295.767 + endloop + endfacet + facet normal 0.576729 -0.689828 -0.437631 + outer loop + vertex 861.582 252.039 294.608 + vertex 864.096 254.271 294.403 + vertex 861.957 251.948 295.247 + endloop + endfacet + facet normal 0.546424 -0.721997 -0.42443 + outer loop + vertex 859.423 250.243 294.885 + vertex 861.582 252.039 294.608 + vertex 861.957 251.948 295.247 + endloop + endfacet + facet normal 0.480021 -0.699825 -0.528986 + outer loop + vertex 856.219 247.651 295.406 + vertex 859.423 250.243 294.885 + vertex 858.682 249.002 295.854 + endloop + endfacet + facet normal 0.412676 -0.686606 -0.598557 + outer loop + vertex 853.354 245.464 295.939 + vertex 856.219 247.651 295.406 + vertex 855.354 246.288 296.373 + endloop + endfacet + facet normal 0.34384 -0.666342 -0.661636 + outer loop + vertex 850.994 243.855 296.334 + vertex 853.354 245.464 295.939 + vertex 852.576 244.147 296.861 + endloop + endfacet + facet normal 0.28491 -0.646818 -0.707427 + outer loop + vertex 848.339 242.413 296.583 + vertex 850.994 243.855 296.334 + vertex 850.528 242.419 297.459 + endloop + endfacet + facet normal 0.410697 -0.673147 -0.614981 + outer loop + vertex 855.354 246.288 296.373 + vertex 852.576 244.147 296.861 + vertex 853.354 245.464 295.939 + endloop + endfacet + facet normal 0.346317 -0.645706 -0.680535 + outer loop + vertex 852.576 244.147 296.861 + vertex 850.528 242.419 297.459 + vertex 850.994 243.855 296.334 + endloop + endfacet + facet normal 0.341741 -0.616232 -0.709557 + outer loop + vertex 850.528 242.419 297.459 + vertex 850.908 241.116 298.774 + vertex 849.46 240.007 299.039 + endloop + endfacet + facet normal 0.331642 -0.606232 -0.722839 + outer loop + vertex 850.908 241.116 298.774 + vertex 851.063 239.414 300.272 + vertex 849.46 240.007 299.039 + endloop + endfacet + facet normal 0.535956 -0.694733 -0.479684 + outer loop + vertex 861.957 251.948 295.247 + vertex 858.682 249.002 295.854 + vertex 859.423 250.243 294.885 + endloop + endfacet + facet normal 0.477232 -0.68949 -0.544843 + outer loop + vertex 858.682 249.002 295.854 + vertex 855.354 246.288 296.373 + vertex 856.219 247.651 295.406 + endloop + endfacet + facet normal 0.593174 -0.694144 -0.40781 + outer loop + vertex 866.983 255.937 295.767 + vertex 861.957 251.948 295.247 + vertex 864.096 254.271 294.403 + endloop + endfacet + facet normal 0.655942 -0.655088 -0.374965 + outer loop + vertex 872.84 262.149 295.161 + vertex 866.983 255.937 295.767 + vertex 868.622 258.433 294.274 + endloop + endfacet + facet normal 0.712393 -0.618151 -0.332242 + outer loop + vertex 878.434 268.772 294.832 + vertex 872.84 262.149 295.161 + vertex 875.143 265.633 293.616 + endloop + endfacet + facet normal 0.759834 -0.565863 -0.320081 + outer loop + vertex 883.382 275.557 294.583 + vertex 878.434 268.772 294.832 + vertex 880.237 272.023 293.364 + endloop + endfacet + facet normal 0.802996 -0.511254 -0.306297 + outer loop + vertex 887.903 282.67 294.564 + vertex 883.382 275.557 294.583 + vertex 884.981 278.937 293.133 + endloop + endfacet + facet normal 0.84334 -0.45359 -0.288155 + outer loop + vertex 891.687 289.87 294.302 + vertex 887.903 282.67 294.564 + vertex 888.962 285.616 293.026 + endloop + endfacet + facet normal 0.886212 -0.389129 -0.251408 + outer loop + vertex 895.27 298.078 294.228 + vertex 891.687 289.87 294.302 + vertex 892.707 293.053 292.971 + endloop + endfacet + facet normal 0.922296 -0.320955 -0.21531 + outer loop + vertex 898.222 306.474 294.358 + vertex 895.27 298.078 294.228 + vertex 896.503 302.37 293.114 + endloop + endfacet + facet normal 0.948649 -0.244161 -0.201124 + outer loop + vertex 900.193 314.275 294.183 + vertex 898.222 306.474 294.358 + vertex 898.798 309.717 293.142 + endloop + endfacet + facet normal 0.963879 -0.170117 -0.204931 + outer loop + vertex 901.705 322.65 294.345 + vertex 900.193 314.275 294.183 + vertex 900.642 318.179 293.059 + endloop + endfacet + facet normal 0.974123 -0.0979718 -0.203682 + outer loop + vertex 902.527 330.741 294.385 + vertex 901.705 322.65 294.345 + vertex 901.784 326.001 293.113 + endloop + endfacet + facet normal 0.978789 -0.0336105 -0.202095 + outer loop + vertex 902.782 339.216 294.209 + vertex 902.527 330.741 294.385 + vertex 902.372 333.8 293.125 + endloop + endfacet + facet normal 0.974558 0.0186662 -0.223358 + outer loop + vertex 902.642 348.138 294.345 + vertex 902.782 339.216 294.209 + vertex 902.396 343.926 292.922 + endloop + endfacet + facet normal 0.971459 0.0631241 -0.228653 + outer loop + vertex 902.11 356.354 294.352 + vertex 902.642 348.138 294.345 + vertex 902.05 352.024 292.901 + endloop + endfacet + facet normal 0.968077 0.101126 -0.229346 + outer loop + vertex 901.281 364.319 294.365 + vertex 902.11 356.354 294.352 + vertex 901.389 359.924 292.885 + endloop + endfacet + facet normal 0.964168 0.134176 -0.228859 + outer loop + vertex 900.16 372.388 294.373 + vertex 901.281 364.319 294.365 + vertex 900.462 367.731 292.914 + endloop + endfacet + facet normal 0.9601 0.161831 -0.228077 + outer loop + vertex 898.688 380.893 294.21 + vertex 900.16 372.388 294.373 + vertex 899.261 375.657 292.91 + endloop + endfacet + facet normal 0.957575 0.185267 -0.220741 + outer loop + vertex 897.136 389.121 294.384 + vertex 898.688 380.893 294.21 + vertex 897.592 385.291 293.15 + endloop + endfacet + facet normal 0.595474 -0.535883 -0.598532 + outer loop + vertex 855.985 232.248 308.826 + vertex 857.523 231.665 310.877 + vertex 856.19 231.515 309.685 + endloop + endfacet + facet normal 0.937386 0.222256 -0.268159 + outer loop + vertex 879.777 465.069 309.181 + vertex 878.721 463.642 304.308 + vertex 879.118 464.911 306.747 + endloop + endfacet + facet normal 0.62599 -0.753871 -0.199537 + outer loop + vertex 858.948 231.581 313.111 + vertex 860.052 231.968 315.111 + vertex 859.425 231.508 314.882 + endloop + endfacet + facet normal 0.656237 -0.611663 -0.441839 + outer loop + vertex 857.523 231.665 310.877 + vertex 858.948 231.581 313.111 + vertex 857.753 231.143 311.94 + endloop + endfacet + facet normal 0.979909 0.0970704 -0.17423 + outer loop + vertex 880.485 466.829 314.144 + vertex 879.777 465.069 309.181 + vertex 880.104 466.59 311.868 + endloop + endfacet + facet normal 0.711527 -0.700163 0.0591673 + outer loop + vertex 860.661 232.446 316.889 + vertex 861.074 232.999 318.459 + vertex 860.585 232.432 317.629 + endloop + endfacet + facet normal 0.693162 -0.674734 0.253497 + outer loop + vertex 861.074 232.999 318.459 + vertex 861.957 234.169 319.158 + vertex 861.149 233.867 320.564 + endloop + endfacet + facet normal 0.973782 0.180869 -0.13797 + outer loop + vertex 880.856 468.125 318.462 + vertex 880.485 466.829 314.144 + vertex 880.61 468.402 317.088 + endloop + endfacet + facet normal 0.708024 -0.653968 0.266509 + outer loop + vertex 861.957 234.169 319.158 + vertex 864.111 238.135 323.169 + vertex 861.149 233.867 320.564 + endloop + endfacet + facet normal 0.977062 0.193039 -0.089921 + outer loop + vertex 881.082 468.812 322.393 + vertex 880.856 468.125 318.462 + vertex 880.815 469.081 320.07 + endloop + endfacet + facet normal 0.672754 -0.635368 0.379089 + outer loop + vertex 864.111 238.135 323.169 + vertex 864.458 241.392 328.011 + vertex 861.529 236.695 325.338 + endloop + endfacet + facet normal 0.975221 0.215453 -0.0502415 + outer loop + vertex 881.221 469.164 326.609 + vertex 881.082 468.812 322.393 + vertex 881.016 469.604 324.5 + endloop + endfacet + facet normal 0.641799 -0.606625 0.469148 + outer loop + vertex 864.458 241.392 328.011 + vertex 863.87 243.882 332.035 + vertex 861.599 239.415 329.365 + endloop + endfacet + facet normal 0.612414 -0.579811 0.537371 + outer loop + vertex 863.87 243.882 332.035 + vertex 863.409 247.071 336.001 + vertex 861.286 242.693 333.697 + endloop + endfacet + facet normal 0.966536 0.251231 0.0518796 + outer loop + vertex 881.162 468.762 345.621 + vertex 881.255 469.125 342.14 + vertex 880.928 469.888 344.543 + endloop + endfacet + facet normal 0.523269 -0.479084 0.704747 + outer loop + vertex 862.075 257.86 346.543 + vertex 861.096 261.181 349.528 + vertex 859.627 256.239 347.258 + endloop + endfacet + facet normal 0.968057 0.234943 0.0875657 + outer loop + vertex 880.85 468.781 349.022 + vertex 881.162 468.762 345.621 + vertex 880.82 469.609 347.134 + endloop + endfacet + facet normal 0.485201 -0.444986 0.752707 + outer loop + vertex 861.096 261.181 349.528 + vertex 860.788 265.763 352.435 + vertex 858.343 260.824 351.091 + endloop + endfacet + facet normal 0.955336 0.264349 0.132105 + outer loop + vertex 880.538 468.416 352.013 + vertex 880.85 468.781 349.022 + vertex 880.446 469.14 351.225 + endloop + endfacet + facet normal 0.443326 -0.38871 0.807692 + outer loop + vertex 860.788 265.763 352.435 + vertex 859.846 269.666 354.83 + vertex 858.351 264.271 353.054 + endloop + endfacet + facet normal 0.947285 0.265892 0.178752 + outer loop + vertex 882.438 460.079 354.1 + vertex 882.325 462.03 351.793 + vertex 880.921 465.02 354.788 + endloop + endfacet + facet normal 0.918932 0.342373 0.195816 + outer loop + vertex 880.33 467.79 354.08 + vertex 880.538 468.416 352.013 + vertex 880.08 468.478 354.054 + endloop + endfacet + facet normal 0.948403 0.24958 0.195557 + outer loop + vertex 880.92 466.622 352.747 + vertex 880.921 465.02 354.788 + vertex 882.325 462.03 351.793 + endloop + endfacet + facet normal 0.400047 -0.32815 0.855734 + outer loop + vertex 859.846 269.666 354.83 + vertex 859.214 274.827 357.105 + vertex 857.111 269.243 355.946 + endloop + endfacet + facet normal 0.934255 0.251575 0.252741 + outer loop + vertex 881.487 461.229 356.468 + vertex 882.438 460.079 354.1 + vertex 880.921 465.02 354.788 + endloop + endfacet + facet normal 0.904061 0.339423 0.259742 + outer loop + vertex 879.969 467.296 355.984 + vertex 880.33 467.79 354.08 + vertex 880.08 468.478 354.054 + endloop + endfacet + facet normal 0.931603 0.254275 0.25973 + outer loop + vertex 880.921 465.02 354.788 + vertex 880.194 465.486 356.939 + vertex 881.487 461.229 356.468 + endloop + endfacet + facet normal 0.331693 -0.264199 0.905637 + outer loop + vertex 859.214 274.827 357.105 + vertex 858.779 280.107 358.805 + vertex 856.563 274.739 358.05 + endloop + endfacet + facet normal 0.908652 0.239121 0.342304 + outer loop + vertex 881.018 460.22 358.417 + vertex 881.487 461.229 356.468 + vertex 879.965 464.286 358.373 + endloop + endfacet + facet normal 0.910898 0.271057 0.311115 + outer loop + vertex 879.522 466.525 357.965 + vertex 879.969 467.296 355.984 + vertex 879.597 467.458 356.932 + endloop + endfacet + facet normal 0.908321 0.237866 0.344053 + outer loop + vertex 880.194 465.486 356.939 + vertex 879.965 464.286 358.373 + vertex 881.487 461.229 356.468 + endloop + endfacet + facet normal 0.265534 -0.215487 0.939711 + outer loop + vertex 858.779 280.107 358.805 + vertex 857.712 284.066 360.014 + vertex 855.954 278.862 359.317 + endloop + endfacet + facet normal 0.861327 0.221553 0.457198 + outer loop + vertex 880.524 459.486 359.704 + vertex 881.018 460.22 358.417 + vertex 879.566 463.246 359.687 + endloop + endfacet + facet normal 0.890607 0.217513 0.399384 + outer loop + vertex 879.128 465.415 359.448 + vertex 879.522 466.525 357.965 + vertex 879.199 466.354 358.779 + endloop + endfacet + facet normal 0.866027 0.229189 0.444375 + outer loop + vertex 879.965 464.286 358.373 + vertex 879.566 463.246 359.687 + vertex 881.018 460.22 358.417 + endloop + endfacet + facet normal 0.207596 -0.175403 0.96236 + outer loop + vertex 857.712 284.066 360.014 + vertex 857.671 288.487 360.828 + vertex 855.335 284.231 360.557 + endloop + endfacet + facet normal 0.799983 0.201673 0.565116 + outer loop + vertex 880.199 458.608 360.478 + vertex 880.524 459.486 359.704 + vertex 879.296 462.027 360.535 + endloop + endfacet + facet normal 0.853873 0.161543 0.494777 + outer loop + vertex 878.7 464.37 360.528 + vertex 879.128 465.415 359.448 + vertex 878.729 465.236 360.194 + endloop + endfacet + facet normal 0.805621 0.207777 0.5548 + outer loop + vertex 879.566 463.246 359.687 + vertex 879.296 462.027 360.535 + vertex 880.524 459.486 359.704 + endloop + endfacet + facet normal 0.194848 -0.13926 0.970897 + outer loop + vertex 869.218 307.171 361.495 + vertex 873.779 313.623 361.505 + vertex 871.476 310.904 361.577 + endloop + endfacet + facet normal 0.217135 -0.134577 0.96682 + outer loop + vertex 873.779 313.623 361.505 + vertex 877.837 320.131 361.499 + vertex 875.824 317.353 361.565 + endloop + endfacet + facet normal 0.226712 -0.12406 0.966028 + outer loop + vertex 877.837 320.131 361.499 + vertex 881.498 326.828 361.5 + vertex 879.705 324.051 361.564 + endloop + endfacet + facet normal 0.257445 -0.124739 0.958208 + outer loop + vertex 881.498 326.828 361.5 + vertex 884.655 333.283 361.493 + vertex 883.256 330.96 361.566 + endloop + endfacet + facet normal 0.37684 -0.159794 0.912391 + outer loop + vertex 884.655 333.283 361.493 + vertex 887.485 340.054 361.51 + vertex 885.818 336.387 361.556 + endloop + endfacet + facet normal 0.350722 -0.124067 0.928225 + outer loop + vertex 887.485 340.054 361.51 + vertex 889.864 346.69 361.498 + vertex 889.106 345.123 361.575 + endloop + endfacet + facet normal 0.353648 -0.101387 0.929868 + outer loop + vertex 889.864 346.69 361.498 + vertex 891.66 353.036 361.506 + vertex 890.992 351.404 361.582 + endloop + endfacet + facet normal 0.520299 -0.114998 0.846206 + outer loop + vertex 891.66 353.036 361.506 + vertex 892.994 359.121 361.513 + vertex 892.382 356.807 361.575 + endloop + endfacet + facet normal 0.677113 -0.105028 0.728346 + outer loop + vertex 892.994 359.121 361.513 + vertex 894.043 365.866 361.511 + vertex 893.366 361.968 361.578 + endloop + endfacet + facet normal 0.690251 -0.0607803 0.721012 + outer loop + vertex 894.043 365.866 361.511 + vertex 894.632 372.342 361.492 + vertex 894.444 371.166 361.573 + endloop + endfacet + facet normal 0.595957 -0.0140112 0.802894 + outer loop + vertex 894.632 372.342 361.492 + vertex 894.772 378.758 361.5 + vertex 894.598 376.495 361.59 + endloop + endfacet + facet normal 0.584195 0.0169427 0.811437 + outer loop + vertex 894.772 378.758 361.5 + vertex 894.577 384.924 361.512 + vertex 894.52 382.908 361.595 + endloop + endfacet + facet normal 0.683626 0.0515265 0.728012 + outer loop + vertex 894.577 384.924 361.512 + vertex 894.173 390.411 361.503 + vertex 894.265 388.047 361.584 + endloop + endfacet + facet normal 0.633131 0.0731345 0.770582 + outer loop + vertex 894.173 390.411 361.503 + vertex 893.535 395.942 361.502 + vertex 893.777 392.96 361.587 + endloop + endfacet + facet normal 0.662427 0.0972858 0.742783 + outer loop + vertex 893.535 395.942 361.502 + vertex 892.72 401.369 361.518 + vertex 892.982 399.065 361.587 + endloop + endfacet + facet normal 0.726519 0.124231 0.675824 + outer loop + vertex 892.72 401.369 361.518 + vertex 891.864 406.347 361.524 + vertex 892.207 404.024 361.582 + endloop + endfacet + facet normal 0.658345 0.127002 0.741925 + outer loop + vertex 891.864 406.347 361.524 + vertex 890.88 411.578 361.501 + vertex 891.319 408.773 361.592 + endloop + endfacet + facet normal 0.658006 0.142319 0.739441 + outer loop + vertex 890.88 411.578 361.501 + vertex 889.638 417.367 361.492 + vertex 890.108 414.707 361.586 + endloop + endfacet + facet normal 0.600819 0.152122 0.784778 + outer loop + vertex 882.638 444.573 361.527 + vertex 881.32 449.915 361.5 + vertex 881.661 448.138 361.583 + endloop + endfacet + facet normal 0.675845 0.162075 0.719003 + outer loop + vertex 880.168 454.801 361.456 + vertex 879.433 458.398 361.337 + vertex 879.564 457.463 361.424 + endloop + endfacet + facet normal -0.901128 0.0868426 -0.424766 + outer loop + vertex 878.265 464.253 361.086 + vertex 878.329 464.393 360.978 + vertex 878.302 464.302 361.019 + endloop + endfacet + facet normal 0.710596 0.172539 0.682117 + outer loop + vertex 878.581 463.286 361.003 + vertex 878.365 463.677 361.128 + vertex 878.772 461.528 361.248 + endloop + endfacet + facet normal -0.802639 -0.181895 -0.568054 + outer loop + vertex 878.365 463.677 361.128 + vertex 878.265 464.253 361.086 + vertex 878.302 464.302 361.019 + endloop + endfacet + facet normal -0.772632 -0.0461847 -0.633172 + outer loop + vertex 878.7 464.37 360.528 + vertex 878.302 464.302 361.019 + vertex 878.329 464.393 360.978 + endloop + endfacet + facet normal 0.192882 -0.588474 0.785172 + outer loop + vertex 389.155 88.5455 363.815 + vertex 397.798 91.1067 363.611 + vertex 395.234 90.5026 363.788 + endloop + endfacet + facet normal 0.159273 -0.518568 0.840071 + outer loop + vertex 378.052 85.4362 364.001 + vertex 389.155 88.5455 363.815 + vertex 383.932 87.4585 364.134 + endloop + endfacet + facet normal -0.147384 -0.478591 0.86558 + outer loop + vertex -387.47 87.9726 363.829 + vertex -378.599 85.5373 363.993 + vertex -384.79 87.5175 364.034 + endloop + endfacet + facet normal -0.157644 -0.470495 0.868207 + outer loop + vertex -394.906 90.0554 363.607 + vertex -387.47 87.9726 363.829 + vertex -392.318 89.5971 363.829 + endloop + endfacet + facet normal -0.212789 -0.42028 0.882091 + outer loop + vertex -378.776 177.36 407.784 + vertex -379.966 174.862 406.307 + vertex -377.884 172.723 405.79 + endloop + endfacet + facet normal 0.208759 -0.638393 0.740861 + outer loop + vertex 395.234 90.5026 363.788 + vertex 390.85 89.1829 363.886 + vertex 389.155 88.5455 363.815 + endloop + endfacet + facet normal -0.107525 -0.470602 0.875769 + outer loop + vertex -349.308 81.1655 365.572 + vertex -363.915 83.3285 364.941 + vertex -354.593 80.0527 364.326 + endloop + endfacet + facet normal 0.273612 -0.746914 -0.606017 + outer loop + vertex 851.047 248.833 290.437 + vertex 851.588 248.513 291.075 + vertex 850.266 246.433 293.042 + endloop + endfacet + facet normal 0.275903 -0.747133 -0.604707 + outer loop + vertex 850.266 246.433 293.042 + vertex 851.588 248.513 291.075 + vertex 851.019 246.467 293.344 + endloop + endfacet + facet normal 0.284829 -0.722756 -0.629679 + outer loop + vertex 850.266 246.433 293.042 + vertex 851.019 246.467 293.344 + vertex 849.816 244.651 294.884 + endloop + endfacet + facet normal 0.320063 -0.727144 -0.607307 + outer loop + vertex 849.816 244.651 294.884 + vertex 851.019 246.467 293.344 + vertex 850.899 245.297 294.681 + endloop + endfacet + facet normal 0.259604 -0.799207 -0.542102 + outer loop + vertex 852.38 253.03 285.19 + vertex 852.944 253.077 285.391 + vertex 851.827 251.071 287.812 + endloop + endfacet + facet normal 0.217946 -0.798684 -0.560895 + outer loop + vertex 851.827 251.071 287.812 + vertex 852.944 253.077 285.391 + vertex 852.288 250.828 288.338 + endloop + endfacet + facet normal 0.256264 -0.771723 -0.582042 + outer loop + vertex 851.827 251.071 287.812 + vertex 852.288 250.828 288.338 + vertex 851.047 248.833 290.437 + endloop + endfacet + facet normal 0.24085 -0.770586 -0.590075 + outer loop + vertex 851.047 248.833 290.437 + vertex 852.288 250.828 288.338 + vertex 851.588 248.513 291.075 + endloop + endfacet + facet normal 0.234884 -0.843954 -0.482256 + outer loop + vertex 853.558 257.315 278.639 + vertex 854.019 257.289 278.91 + vertex 853.044 255.375 281.784 + endloop + endfacet + facet normal 0.213183 -0.845054 -0.490343 + outer loop + vertex 853.044 255.375 281.784 + vertex 854.019 257.289 278.91 + vertex 853.522 255.245 282.217 + endloop + endfacet + facet normal 0.244333 -0.820256 -0.517186 + outer loop + vertex 853.044 255.375 281.784 + vertex 853.522 255.245 282.217 + vertex 852.38 253.03 285.19 + endloop + endfacet + facet normal 0.251429 -0.819962 -0.514242 + outer loop + vertex 852.38 253.03 285.19 + vertex 853.522 255.245 282.217 + vertex 852.944 253.077 285.391 + endloop + endfacet + facet normal 0.311005 -0.814521 0.489725 + outer loop + vertex 851.071 252.12 57.1707 + vertex 851.865 252.771 57.7498 + vertex 851.858 254.511 60.6489 + endloop + endfacet + facet normal 0.267002 -0.825962 0.496485 + outer loop + vertex 851.858 254.511 60.6489 + vertex 851.865 252.771 57.7498 + vertex 852.541 254.949 61.0102 + endloop + endfacet + facet normal 0.29085 -0.836579 0.464264 + outer loop + vertex 851.858 254.511 60.6489 + vertex 852.541 254.949 61.0102 + vertex 852.584 256.65 64.0464 + endloop + endfacet + facet normal 0.295493 -0.835365 0.463518 + outer loop + vertex 852.584 256.65 64.0464 + vertex 852.541 254.949 61.0102 + vertex 853.102 256.578 63.5885 + endloop + endfacet + facet normal 0.38313 -0.761771 0.522413 + outer loop + vertex 849.327 247.255 51.0725 + vertex 850.403 248.171 51.6189 + vertex 850.202 249.639 53.9078 + endloop + endfacet + facet normal 0.324956 -0.782753 0.530755 + outer loop + vertex 850.202 249.639 53.9078 + vertex 850.403 248.171 51.6189 + vertex 851.139 250.435 54.508 + endloop + endfacet + facet normal 0.344985 -0.789215 0.50806 + outer loop + vertex 850.202 249.639 53.9078 + vertex 851.139 250.435 54.508 + vertex 851.071 252.12 57.1707 + endloop + endfacet + facet normal 0.284352 -0.806919 0.517712 + outer loop + vertex 851.071 252.12 57.1707 + vertex 851.139 250.435 54.508 + vertex 851.865 252.771 57.7498 + endloop + endfacet + facet normal 0.407703 -0.713529 0.569785 + outer loop + vertex 847.972 243.793 47.5108 + vertex 849.106 244.72 47.8603 + vertex 848.5 245.159 48.8439 + endloop + endfacet + facet normal 0.392057 -0.725586 0.565524 + outer loop + vertex 848.5 245.159 48.8439 + vertex 849.106 244.72 47.8603 + vertex 849.694 246.185 49.3323 + endloop + endfacet + facet normal 0.411273 -0.735224 0.538795 + outer loop + vertex 848.5 245.159 48.8439 + vertex 849.694 246.185 49.3323 + vertex 849.327 247.255 51.0725 + endloop + endfacet + facet normal 0.367823 -0.755528 0.54211 + outer loop + vertex 849.327 247.255 51.0725 + vertex 849.694 246.185 49.3323 + vertex 850.403 248.171 51.6189 + endloop + endfacet + facet normal 0.386941 -0.705573 -0.59367 + outer loop + vertex 852.334 245.921 294.75 + vertex 854.734 247.406 294.549 + vertex 852.404 245.28 295.557 + endloop + endfacet + facet normal 0.402685 -0.713315 -0.573608 + outer loop + vertex 852.404 245.28 295.557 + vertex 854.734 247.406 294.549 + vertex 854.597 246.755 295.262 + endloop + endfacet + facet normal 0.33877 -0.711589 -0.615529 + outer loop + vertex 850.899 245.297 294.681 + vertex 852.334 245.921 294.75 + vertex 850.508 244.279 295.643 + endloop + endfacet + facet normal 0.351899 -0.718023 -0.600509 + outer loop + vertex 850.508 244.279 295.643 + vertex 852.334 245.921 294.75 + vertex 852.404 245.28 295.557 + endloop + endfacet + facet normal 0.374103 -0.739947 -0.559039 + outer loop + vertex 853.012 249.016 291.18 + vertex 855.251 250.196 291.116 + vertex 852.59 247.189 293.315 + endloop + endfacet + facet normal 0.39851 -0.744467 -0.535684 + outer loop + vertex 852.59 247.189 293.315 + vertex 855.251 250.196 291.116 + vertex 854.927 248.533 293.187 + endloop + endfacet + facet normal 0.306321 -0.743802 -0.594075 + outer loop + vertex 851.588 248.513 291.075 + vertex 853.012 249.016 291.18 + vertex 851.019 246.467 293.344 + endloop + endfacet + facet normal 0.333535 -0.747933 -0.573891 + outer loop + vertex 851.019 246.467 293.344 + vertex 853.012 249.016 291.18 + vertex 852.59 247.189 293.315 + endloop + endfacet + facet normal 0.32307 -0.726505 -0.606478 + outer loop + vertex 851.019 246.467 293.344 + vertex 852.59 247.189 293.315 + vertex 850.899 245.297 294.681 + endloop + endfacet + facet normal 0.346471 -0.732569 -0.585918 + outer loop + vertex 850.899 245.297 294.681 + vertex 852.59 247.189 293.315 + vertex 852.334 245.921 294.75 + endloop + endfacet + facet normal 0.385006 -0.724408 -0.571843 + outer loop + vertex 852.59 247.189 293.315 + vertex 854.927 248.533 293.187 + vertex 852.334 245.921 294.75 + endloop + endfacet + facet normal 0.406792 -0.731386 -0.547353 + outer loop + vertex 852.334 245.921 294.75 + vertex 854.927 248.533 293.187 + vertex 854.734 247.406 294.549 + endloop + endfacet + facet normal 0.354574 -0.781109 -0.513952 + outer loop + vertex 854.138 253.448 285.463 + vertex 856.069 254.328 285.459 + vertex 853.57 251.206 288.481 + endloop + endfacet + facet normal 0.375186 -0.781953 -0.49778 + outer loop + vertex 853.57 251.206 288.481 + vertex 856.069 254.328 285.459 + vertex 855.662 252.221 288.461 + endloop + endfacet + facet normal 0.279667 -0.792292 -0.542273 + outer loop + vertex 852.944 253.077 285.391 + vertex 854.138 253.448 285.463 + vertex 852.288 250.828 288.338 + endloop + endfacet + facet normal 0.292902 -0.792911 -0.534322 + outer loop + vertex 852.288 250.828 288.338 + vertex 854.138 253.448 285.463 + vertex 853.57 251.206 288.481 + endloop + endfacet + facet normal 0.289403 -0.766103 -0.573875 + outer loop + vertex 852.288 250.828 288.338 + vertex 853.57 251.206 288.481 + vertex 851.588 248.513 291.075 + endloop + endfacet + facet normal 0.312393 -0.768337 -0.558632 + outer loop + vertex 851.588 248.513 291.075 + vertex 853.57 251.206 288.481 + vertex 853.012 249.016 291.18 + endloop + endfacet + facet normal 0.363563 -0.758844 -0.540349 + outer loop + vertex 853.57 251.206 288.481 + vertex 855.662 252.221 288.461 + vertex 853.012 249.016 291.18 + endloop + endfacet + facet normal 0.386367 -0.761185 -0.520882 + outer loop + vertex 853.012 249.016 291.18 + vertex 855.662 252.221 288.461 + vertex 855.251 250.196 291.116 + endloop + endfacet + facet normal 0.336451 -0.824246 -0.455433 + outer loop + vertex 855.052 257.586 278.954 + vertex 856.753 258.289 278.939 + vertex 854.638 255.588 282.265 + endloop + endfacet + facet normal 0.355575 -0.823274 -0.442477 + outer loop + vertex 854.638 255.588 282.265 + vertex 856.753 258.289 278.939 + vertex 856.448 256.376 282.254 + endloop + endfacet + facet normal 0.261929 -0.838015 -0.478669 + outer loop + vertex 854.019 257.289 278.91 + vertex 855.052 257.586 278.954 + vertex 853.522 255.245 282.217 + endloop + endfacet + facet normal 0.277978 -0.837371 -0.470678 + outer loop + vertex 853.522 255.245 282.217 + vertex 855.052 257.586 278.954 + vertex 854.638 255.588 282.265 + endloop + endfacet + facet normal 0.273258 -0.816796 -0.508109 + outer loop + vertex 853.522 255.245 282.217 + vertex 854.638 255.588 282.265 + vertex 852.944 253.077 285.391 + endloop + endfacet + facet normal 0.284821 -0.816744 -0.501803 + outer loop + vertex 852.944 253.077 285.391 + vertex 854.638 255.588 282.265 + vertex 854.138 253.448 285.463 + endloop + endfacet + facet normal 0.346828 -0.803752 -0.483418 + outer loop + vertex 854.638 255.588 282.265 + vertex 856.448 256.376 282.254 + vertex 854.138 253.448 285.463 + endloop + endfacet + facet normal 0.364894 -0.803567 -0.470247 + outer loop + vertex 854.138 253.448 285.463 + vertex 856.448 256.376 282.254 + vertex 856.069 254.328 285.459 + endloop + endfacet + facet normal 0.323533 -0.856095 -0.403022 + outer loop + vertex 855.646 261.169 272.108 + vertex 857.198 261.733 272.157 + vertex 855.395 259.434 275.592 + endloop + endfacet + facet normal 0.333123 -0.855086 -0.397313 + outer loop + vertex 855.395 259.434 275.592 + vertex 857.198 261.733 272.157 + vertex 857.009 260.073 275.57 + endloop + endfacet + facet normal 0.269804 -0.869929 -0.412831 + outer loop + vertex 854.667 260.987 271.852 + vertex 855.646 261.169 272.108 + vertex 854.385 259.126 275.588 + endloop + endfacet + facet normal 0.266614 -0.870268 -0.414186 + outer loop + vertex 854.385 259.126 275.588 + vertex 855.646 261.169 272.108 + vertex 855.395 259.434 275.592 + endloop + endfacet + facet normal 0.262464 -0.856317 -0.444785 + outer loop + vertex 854.385 259.126 275.588 + vertex 855.395 259.434 275.592 + vertex 854.019 257.289 278.91 + endloop + endfacet + facet normal 0.265605 -0.856098 -0.443341 + outer loop + vertex 854.019 257.289 278.91 + vertex 855.395 259.434 275.592 + vertex 855.052 257.586 278.954 + endloop + endfacet + facet normal 0.327423 -0.841784 -0.429179 + outer loop + vertex 855.395 259.434 275.592 + vertex 857.009 260.073 275.57 + vertex 855.052 257.586 278.954 + endloop + endfacet + facet normal 0.343501 -0.840525 -0.418958 + outer loop + vertex 855.052 257.586 278.954 + vertex 857.009 260.073 275.57 + vertex 856.753 258.289 278.939 + endloop + endfacet + facet normal 0.332773 -0.8774 -0.345588 + outer loop + vertex 855.9 264.574 264.086 + vertex 857.349 264.847 264.79 + vertex 855.799 262.861 268.339 + endloop + endfacet + facet normal 0.322371 -0.8791 -0.351083 + outer loop + vertex 855.799 262.861 268.339 + vertex 857.349 264.847 264.79 + vertex 857.301 263.302 268.615 + endloop + endfacet + facet normal 0.257897 -0.899015 -0.353922 + outer loop + vertex 855.048 264.453 263.774 + vertex 855.9 264.574 264.086 + vertex 854.891 262.853 267.723 + endloop + endfacet + facet normal 0.249776 -0.900196 -0.356733 + outer loop + vertex 854.891 262.853 267.723 + vertex 855.9 264.574 264.086 + vertex 855.799 262.861 268.339 + endloop + endfacet + facet normal 0.26856 -0.883149 -0.384609 + outer loop + vertex 854.891 262.853 267.723 + vertex 855.799 262.861 268.339 + vertex 854.667 260.987 271.852 + endloop + endfacet + facet normal 0.265297 -0.883577 -0.385888 + outer loop + vertex 854.667 260.987 271.852 + vertex 855.799 262.861 268.339 + vertex 855.646 261.169 272.108 + endloop + endfacet + facet normal 0.323782 -0.867987 -0.376516 + outer loop + vertex 855.799 262.861 268.339 + vertex 857.301 263.302 268.615 + vertex 855.646 261.169 272.108 + endloop + endfacet + facet normal 0.32683 -0.867578 -0.374821 + outer loop + vertex 855.646 261.169 272.108 + vertex 857.301 263.302 268.615 + vertex 857.198 261.733 272.157 + endloop + endfacet + facet normal 0.325129 -0.887755 -0.325856 + outer loop + vertex 857.349 264.847 264.79 + vertex 855.9 264.574 264.086 + vertex 857.392 266.412 260.569 + endloop + endfacet + facet normal 0.332167 -0.892138 -0.306193 + outer loop + vertex 857.648 267.833 256.707 + vertex 857.392 266.412 260.569 + vertex 855.96 266.66 258.294 + endloop + endfacet + facet normal 0.249434 -0.911971 -0.325717 + outer loop + vertex 855.048 264.453 263.774 + vertex 855.96 266.66 258.294 + vertex 855.9 264.574 264.086 + endloop + endfacet + facet normal 0.346832 -0.88363 -0.314492 + outer loop + vertex 857.392 266.412 260.569 + vertex 855.9 264.574 264.086 + vertex 855.96 266.66 258.294 + endloop + endfacet + facet normal 0.330261 -0.903742 -0.272356 + outer loop + vertex 857.503 270.166 248.955 + vertex 857.356 268.883 253.034 + vertex 855.934 269.219 250.195 + endloop + endfacet + facet normal 0.353514 -0.891573 -0.283064 + outer loop + vertex 857.648 267.833 256.707 + vertex 855.96 266.66 258.294 + vertex 857.356 268.883 253.034 + endloop + endfacet + facet normal 0.354108 -0.891409 -0.282838 + outer loop + vertex 855.96 266.66 258.294 + vertex 855.934 269.219 250.195 + vertex 857.356 268.883 253.034 + endloop + endfacet + facet normal 0.331261 -0.913424 -0.236479 + outer loop + vertex 857.331 272.124 241.36 + vertex 857.222 271.07 245.279 + vertex 855.963 271.389 242.283 + endloop + endfacet + facet normal 0.348792 -0.903579 -0.248774 + outer loop + vertex 857.503 270.166 248.955 + vertex 855.934 269.219 250.195 + vertex 857.222 271.07 245.279 + endloop + endfacet + facet normal 0.356655 -0.901305 -0.245858 + outer loop + vertex 855.934 269.219 250.195 + vertex 855.963 271.389 242.283 + vertex 857.222 271.07 245.279 + endloop + endfacet + facet normal 0.305018 -0.929895 -0.205572 + outer loop + vertex 856.992 273.764 233.62 + vertex 856.98 272.855 237.71 + vertex 855.586 273.102 234.525 + endloop + endfacet + facet normal 0.344889 -0.91339 -0.216264 + outer loop + vertex 857.331 272.124 241.36 + vertex 855.963 271.389 242.283 + vertex 856.98 272.855 237.71 + endloop + endfacet + facet normal 0.337426 -0.91561 -0.218636 + outer loop + vertex 855.963 271.389 242.283 + vertex 855.586 273.102 234.525 + vertex 856.98 272.855 237.71 + endloop + endfacet + facet normal 0.273046 -0.945405 -0.17792 + outer loop + vertex 856.465 275.144 225.605 + vertex 856.554 274.422 229.579 + vertex 855.342 274.675 226.373 + endloop + endfacet + facet normal 0.317653 -0.92981 -0.185874 + outer loop + vertex 856.992 273.764 233.62 + vertex 855.586 273.102 234.525 + vertex 856.554 274.422 229.579 + endloop + endfacet + facet normal 0.305389 -0.933244 -0.189188 + outer loop + vertex 855.586 273.102 234.525 + vertex 855.342 274.675 226.373 + vertex 856.554 274.422 229.579 + endloop + endfacet + facet normal 0.337675 -0.926617 -0.1654 + outer loop + vertex 854.964 275.975 218.318 + vertex 856.995 276.433 219.897 + vertex 855.342 274.675 226.373 + endloop + endfacet + facet normal 0.265524 -0.945413 -0.18892 + outer loop + vertex 855.342 274.675 226.373 + vertex 856.995 276.433 219.897 + vertex 856.465 275.144 225.605 + endloop + endfacet + facet normal 0.344354 -0.929473 -0.132292 + outer loop + vertex 854.742 277.085 209.942 + vertex 856.701 277.623 211.264 + vertex 854.964 275.975 218.318 + endloop + endfacet + facet normal 0.320238 -0.936939 -0.139976 + outer loop + vertex 854.964 275.975 218.318 + vertex 856.701 277.623 211.264 + vertex 856.995 276.433 219.897 + endloop + endfacet + facet normal 0.349999 -0.930915 -0.104398 + outer loop + vertex 854.577 277.948 201.69 + vertex 856.486 278.52 202.996 + vertex 854.742 277.085 209.942 + endloop + endfacet + facet normal 0.331565 -0.936965 -0.110276 + outer loop + vertex 854.742 277.085 209.942 + vertex 856.486 278.52 202.996 + vertex 856.701 277.623 211.264 + endloop + endfacet + facet normal 0.35723 -0.93089 -0.0763511 + outer loop + vertex 854.581 278.582 193.982 + vertex 856.352 279.179 194.988 + vertex 854.577 277.948 201.69 + endloop + endfacet + facet normal 0.337326 -0.937733 -0.0828777 + outer loop + vertex 854.577 277.948 201.69 + vertex 856.352 279.179 194.988 + vertex 856.486 278.52 202.996 + endloop + endfacet + facet normal 0.351902 -0.934297 -0.0570432 + outer loop + vertex 854.412 278.977 186.467 + vertex 856.265 279.633 187.161 + vertex 854.581 278.582 193.982 + endloop + endfacet + facet normal 0.348423 -0.935535 -0.0580926 + outer loop + vertex 854.581 278.582 193.982 + vertex 856.265 279.633 187.161 + vertex 856.352 279.179 194.988 + endloop + endfacet + facet normal 0.352926 -0.935092 -0.0323601 + outer loop + vertex 854.364 279.242 178.297 + vertex 856.198 279.9 179.271 + vertex 854.412 278.977 186.467 + endloop + endfacet + facet normal 0.344859 -0.938012 -0.0347366 + outer loop + vertex 854.412 278.977 186.467 + vertex 856.198 279.9 179.271 + vertex 856.265 279.633 187.161 + endloop + endfacet + facet normal 0.353997 -0.93522 -0.00707056 + outer loop + vertex 854.35 279.298 170.158 + vertex 856.167 279.977 171.3 + vertex 854.364 279.242 178.297 + endloop + endfacet + facet normal 0.342793 -0.939353 -0.0103923 + outer loop + vertex 854.364 279.242 178.297 + vertex 856.167 279.977 171.3 + vertex 856.198 279.9 179.271 + endloop + endfacet + facet normal 0.360712 -0.932474 0.0194813 + outer loop + vertex 854.46 279.178 162.388 + vertex 856.193 279.87 163.426 + vertex 854.35 279.298 170.158 + endloop + endfacet + facet normal 0.342422 -0.939444 0.0138791 + outer loop + vertex 854.35 279.298 170.158 + vertex 856.193 279.87 163.426 + vertex 856.167 279.977 171.3 + endloop + endfacet + facet normal 0.352763 -0.934902 0.0389483 + outer loop + vertex 854.402 278.847 154.965 + vertex 856.235 279.57 155.704 + vertex 854.46 279.178 162.388 + endloop + endfacet + facet normal 0.350702 -0.935701 0.038354 + outer loop + vertex 854.46 279.178 162.388 + vertex 856.235 279.57 155.704 + vertex 856.193 279.87 163.426 + endloop + endfacet + facet normal 0.354754 -0.932761 0.0640834 + outer loop + vertex 854.468 278.31 146.786 + vertex 856.316 279.088 147.874 + vertex 854.402 278.847 154.965 + endloop + endfacet + facet normal 0.344538 -0.936776 0.0611897 + outer loop + vertex 854.402 278.847 154.965 + vertex 856.316 279.088 147.874 + vertex 856.235 279.57 155.704 + endloop + endfacet + facet normal 0.355342 -0.930523 0.0886529 + outer loop + vertex 854.565 277.562 138.543 + vertex 856.443 278.405 139.862 + vertex 854.468 278.31 146.786 + endloop + endfacet + facet normal 0.343408 -0.935315 0.0851838 + outer loop + vertex 854.468 278.31 146.786 + vertex 856.443 278.405 139.862 + vertex 856.316 279.088 147.874 + endloop + endfacet + facet normal 0.360269 -0.925601 0.116052 + outer loop + vertex 854.804 276.687 130.823 + vertex 856.615 277.521 131.854 + vertex 854.565 277.562 138.543 + endloop + endfacet + facet normal 0.341421 -0.933413 0.110325 + outer loop + vertex 854.565 277.562 138.543 + vertex 856.615 277.521 131.854 + vertex 856.443 278.405 139.862 + endloop + endfacet + facet normal 0.346261 -0.927942 0.137943 + outer loop + vertex 854.812 275.605 123.52 + vertex 856.733 276.39 123.981 + vertex 854.804 276.687 130.823 + endloop + endfacet + facet normal 0.34822 -0.927131 0.13846 + outer loop + vertex 854.804 276.687 130.823 + vertex 856.733 276.39 123.981 + vertex 856.615 277.521 131.854 + endloop + endfacet + facet normal 0.330858 -0.928699 0.167486 + outer loop + vertex 855.007 274.316 115.989 + vertex 856.633 275.035 116.765 + vertex 854.812 275.605 123.52 + endloop + endfacet + facet normal 0.337914 -0.925852 0.169148 + outer loop + vertex 854.812 275.605 123.52 + vertex 856.633 275.035 116.765 + vertex 856.733 276.39 123.981 + endloop + endfacet + facet normal 0.314484 -0.929416 0.193096 + outer loop + vertex 855.164 272.799 108.435 + vertex 856.518 273.646 110.305 + vertex 855.007 274.316 115.989 + endloop + endfacet + facet normal 0.317986 -0.928063 0.193867 + outer loop + vertex 855.007 274.316 115.989 + vertex 856.518 273.646 110.305 + vertex 856.633 275.035 116.765 + endloop + endfacet + facet normal 0.338178 -0.914513 0.222042 + outer loop + vertex 857.039 271.435 99.9718 + vertex 856.661 272.362 104.364 + vertex 855.618 271.114 100.812 + endloop + endfacet + facet normal 0.294944 -0.932461 0.208624 + outer loop + vertex 856.518 273.646 110.305 + vertex 855.164 272.799 108.435 + vertex 856.661 272.362 104.364 + endloop + endfacet + facet normal 0.337418 -0.914721 0.222338 + outer loop + vertex 855.164 272.799 108.435 + vertex 855.618 271.114 100.812 + vertex 856.661 272.362 104.364 + endloop + endfacet + facet normal 0.348385 -0.90177 0.255811 + outer loop + vertex 857.095 269.391 92.4712 + vertex 856.878 270.393 96.2972 + vertex 855.544 268.981 93.1359 + endloop + endfacet + facet normal 0.347876 -0.905828 0.24178 + outer loop + vertex 857.039 271.435 99.9718 + vertex 855.618 271.114 100.812 + vertex 856.878 270.393 96.2972 + endloop + endfacet + facet normal 0.367204 -0.897081 0.245779 + outer loop + vertex 855.618 271.114 100.812 + vertex 855.544 268.981 93.1359 + vertex 856.878 270.393 96.2972 + endloop + endfacet + facet normal 0.361147 -0.88702 0.287694 + outer loop + vertex 857.092 266.965 84.8127 + vertex 856.872 268.139 88.7078 + vertex 855.512 266.322 84.8131 + endloop + endfacet + facet normal 0.354846 -0.893204 0.27617 + outer loop + vertex 857.095 269.391 92.4712 + vertex 855.544 268.981 93.1359 + vertex 856.872 268.139 88.7078 + endloop + endfacet + facet normal 0.376116 -0.883057 0.280618 + outer loop + vertex 855.544 268.981 93.1359 + vertex 855.512 266.322 84.8131 + vertex 856.872 268.139 88.7078 + endloop + endfacet + facet normal 0.36159 -0.875072 0.321716 + outer loop + vertex 857.069 264.464 77.8767 + vertex 856.89 265.668 81.3539 + vertex 855.792 264.338 78.9693 + endloop + endfacet + facet normal 0.285994 -0.903081 0.320393 + outer loop + vertex 854.657 264.009 79.0569 + vertex 855.792 264.338 78.9693 + vertex 855.512 266.322 84.8131 + endloop + endfacet + facet normal 0.358592 -0.880731 0.309396 + outer loop + vertex 857.092 266.965 84.8127 + vertex 855.512 266.322 84.8131 + vertex 856.89 265.668 81.3539 + endloop + endfacet + facet normal 0.374607 -0.872328 0.314188 + outer loop + vertex 855.792 264.338 78.9693 + vertex 856.89 265.668 81.3539 + vertex 855.512 266.322 84.8131 + endloop + endfacet + facet normal 0.347063 -0.866593 0.358558 + outer loop + vertex 854.861 260.923 71.2779 + vertex 856.356 261.624 71.5253 + vertex 855.229 262.672 75.1481 + endloop + endfacet + facet normal 0.343272 -0.868376 0.357893 + outer loop + vertex 855.229 262.672 75.1481 + vertex 856.356 261.624 71.5253 + vertex 856.675 263.204 75.0538 + endloop + endfacet + facet normal 0.302383 -0.874863 0.37839 + outer loop + vertex 853.81 260.14 70.3078 + vertex 854.861 260.923 71.2779 + vertex 854.208 262.1 74.5208 + endloop + endfacet + facet normal 0.266259 -0.887647 0.375752 + outer loop + vertex 854.208 262.1 74.5208 + vertex 854.861 260.923 71.2779 + vertex 855.229 262.672 75.1481 + endloop + endfacet + facet normal 0.286547 -0.892839 0.34746 + outer loop + vertex 854.208 262.1 74.5208 + vertex 855.229 262.672 75.1481 + vertex 854.657 264.009 79.0569 + endloop + endfacet + facet normal 0.285241 -0.893274 0.347417 + outer loop + vertex 854.657 264.009 79.0569 + vertex 855.229 262.672 75.1481 + vertex 855.792 264.338 78.9693 + endloop + endfacet + facet normal 0.345094 -0.877922 0.33191 + outer loop + vertex 855.229 262.672 75.1481 + vertex 856.675 263.204 75.0538 + vertex 855.792 264.338 78.9693 + endloop + endfacet + facet normal 0.3716 -0.866057 0.334453 + outer loop + vertex 855.792 264.338 78.9693 + vertex 856.675 263.204 75.0538 + vertex 857.069 264.464 77.8767 + endloop + endfacet + facet normal 0.361529 -0.836332 0.412122 + outer loop + vertex 854.116 257.265 64.2102 + vertex 855.724 258.107 64.5083 + vertex 854.503 259.101 67.5955 + endloop + endfacet + facet normal 0.345416 -0.844878 0.408497 + outer loop + vertex 854.503 259.101 67.5955 + vertex 855.724 258.107 64.5083 + vertex 856.06 259.912 67.9569 + endloop + endfacet + facet normal 0.305232 -0.846159 0.436862 + outer loop + vertex 853.102 256.578 63.5885 + vertex 854.116 257.265 64.2102 + vertex 853.389 258.188 66.5049 + endloop + endfacet + facet normal 0.278704 -0.857264 0.432924 + outer loop + vertex 853.389 258.188 66.5049 + vertex 854.116 257.265 64.2102 + vertex 854.503 259.101 67.5955 + endloop + endfacet + facet normal 0.305798 -0.860327 0.40783 + outer loop + vertex 853.389 258.188 66.5049 + vertex 854.503 259.101 67.5955 + vertex 853.81 260.14 70.3078 + endloop + endfacet + facet normal 0.275923 -0.871863 0.404625 + outer loop + vertex 853.81 260.14 70.3078 + vertex 854.503 259.101 67.5955 + vertex 854.861 260.923 71.2779 + endloop + endfacet + facet normal 0.35386 -0.851493 0.386965 + outer loop + vertex 854.503 259.101 67.5955 + vertex 856.06 259.912 67.9569 + vertex 854.861 260.923 71.2779 + endloop + endfacet + facet normal 0.339218 -0.858806 0.383906 + outer loop + vertex 854.861 260.923 71.2779 + vertex 856.06 259.912 67.9569 + vertex 856.356 261.624 71.5253 + endloop + endfacet + facet normal 0.398013 -0.802242 0.444965 + outer loop + vertex 853.12 253.368 57.8785 + vertex 854.985 254.272 57.8422 + vertex 853.67 255.401 61.0531 + endloop + endfacet + facet normal 0.374007 -0.816354 0.440097 + outer loop + vertex 853.67 255.401 61.0531 + vertex 854.985 254.272 57.8422 + vertex 855.382 256.237 61.1478 + endloop + endfacet + facet normal 0.338017 -0.813421 0.473383 + outer loop + vertex 851.865 252.771 57.7498 + vertex 853.12 253.368 57.8785 + vertex 852.541 254.949 61.0102 + endloop + endfacet + facet normal 0.311568 -0.823734 0.473696 + outer loop + vertex 852.541 254.949 61.0102 + vertex 853.12 253.368 57.8785 + vertex 853.67 255.401 61.0531 + endloop + endfacet + facet normal 0.315405 -0.831729 0.456888 + outer loop + vertex 852.541 254.949 61.0102 + vertex 853.67 255.401 61.0531 + vertex 853.102 256.578 63.5885 + endloop + endfacet + facet normal 0.290417 -0.841386 0.455771 + outer loop + vertex 853.102 256.578 63.5885 + vertex 853.67 255.401 61.0531 + vertex 854.116 257.265 64.2102 + endloop + endfacet + facet normal 0.376336 -0.820101 0.431052 + outer loop + vertex 853.67 255.401 61.0531 + vertex 855.382 256.237 61.1478 + vertex 854.116 257.265 64.2102 + endloop + endfacet + facet normal 0.356253 -0.831357 0.426531 + outer loop + vertex 854.116 257.265 64.2102 + vertex 855.382 256.237 61.1478 + vertex 855.724 258.107 64.5083 + endloop + endfacet + facet normal 0.422971 -0.771893 0.474633 + outer loop + vertex 851.938 249.228 52.0287 + vertex 853.572 250.43 52.527 + vertex 852.466 251.219 54.7968 + endloop + endfacet + facet normal 0.412174 -0.779338 0.471959 + outer loop + vertex 852.466 251.219 54.7968 + vertex 853.572 250.43 52.527 + vertex 854.375 252.211 54.7663 + endloop + endfacet + facet normal 0.395617 -0.769058 0.502032 + outer loop + vertex 850.403 248.171 51.6189 + vertex 851.938 249.228 52.0287 + vertex 851.139 250.435 54.508 + endloop + endfacet + facet normal 0.357479 -0.789111 0.499512 + outer loop + vertex 851.139 250.435 54.508 + vertex 851.938 249.228 52.0287 + vertex 852.466 251.219 54.7968 + endloop + endfacet + facet normal 0.361741 -0.792933 0.490307 + outer loop + vertex 851.139 250.435 54.508 + vertex 852.466 251.219 54.7968 + vertex 851.865 252.771 57.7498 + endloop + endfacet + facet normal 0.332387 -0.805344 0.490856 + outer loop + vertex 851.865 252.771 57.7498 + vertex 852.466 251.219 54.7968 + vertex 853.12 253.368 57.8785 + endloop + endfacet + facet normal 0.415077 -0.785319 0.459331 + outer loop + vertex 852.466 251.219 54.7968 + vertex 854.375 252.211 54.7663 + vertex 853.12 253.368 57.8785 + endloop + endfacet + facet normal 0.395766 -0.79717 0.455949 + outer loop + vertex 853.12 253.368 57.8785 + vertex 854.375 252.211 54.7663 + vertex 854.985 254.272 57.8422 + endloop + endfacet + facet normal 0.46685 -0.728865 0.500806 + outer loop + vertex 851.058 246.149 48.198 + vertex 853.392 248.037 48.7701 + vertex 851.496 247.497 49.752 + endloop + endfacet + facet normal 0.460072 -0.749133 0.476585 + outer loop + vertex 851.496 247.497 49.752 + vertex 853.392 248.037 48.7701 + vertex 853.879 249.373 50.4008 + endloop + endfacet + facet normal 0.432638 -0.7195 0.543272 + outer loop + vertex 849.106 244.72 47.8603 + vertex 851.058 246.149 48.198 + vertex 849.694 246.185 49.3323 + endloop + endfacet + facet normal 0.41735 -0.741342 0.525577 + outer loop + vertex 849.694 246.185 49.3323 + vertex 851.058 246.149 48.198 + vertex 851.496 247.497 49.752 + endloop + endfacet + facet normal 0.4223 -0.745134 0.516176 + outer loop + vertex 849.694 246.185 49.3323 + vertex 851.496 247.497 49.752 + vertex 850.403 248.171 51.6189 + endloop + endfacet + facet normal 0.392991 -0.767161 0.506973 + outer loop + vertex 850.403 248.171 51.6189 + vertex 851.496 247.497 49.752 + vertex 851.938 249.228 52.0287 + endloop + endfacet + facet normal 0.458389 -0.748109 0.479805 + outer loop + vertex 851.496 247.497 49.752 + vertex 853.879 249.373 50.4008 + vertex 851.938 249.228 52.0287 + endloop + endfacet + facet normal 0.435884 -0.779317 0.450189 + outer loop + vertex 851.938 249.228 52.0287 + vertex 853.879 249.373 50.4008 + vertex 853.572 250.43 52.527 + endloop + endfacet + facet normal 0.410829 -0.643248 0.646106 + outer loop + vertex 850.158 244.559 47.023 + vertex 853.053 246.772 47.3855 + vertex 850.637 245.239 47.3952 + endloop + endfacet + facet normal 0.432114 -0.677104 0.595658 + outer loop + vertex 850.637 245.239 47.3952 + vertex 853.053 246.772 47.3855 + vertex 853.687 247.671 47.9473 + endloop + endfacet + facet normal 0.362305 -0.646117 0.671765 + outer loop + vertex 848.642 243.475 46.7976 + vertex 850.158 244.559 47.023 + vertex 848.626 243.756 47.0771 + endloop + endfacet + facet normal 0.353831 -0.628541 0.692633 + outer loop + vertex 848.626 243.756 47.0771 + vertex 850.158 244.559 47.023 + vertex 850.637 245.239 47.3952 + endloop + endfacet + facet normal 0.414213 -0.689358 0.594318 + outer loop + vertex 848.626 243.756 47.0771 + vertex 850.637 245.239 47.3952 + vertex 849.106 244.72 47.8603 + endloop + endfacet + facet normal 0.413982 -0.702445 0.578956 + outer loop + vertex 849.106 244.72 47.8603 + vertex 850.637 245.239 47.3952 + vertex 851.058 246.149 48.198 + endloop + endfacet + facet normal 0.456781 -0.698011 0.551482 + outer loop + vertex 850.637 245.239 47.3952 + vertex 853.687 247.671 47.9473 + vertex 851.058 246.149 48.198 + endloop + endfacet + facet normal 0.470552 -0.7313 0.493743 + outer loop + vertex 851.058 246.149 48.198 + vertex 853.687 247.671 47.9473 + vertex 853.392 248.037 48.7701 + endloop + endfacet + facet normal 0.507578 -0.717765 -0.476632 + outer loop + vertex 858.091 251.976 291.035 + vertex 860.958 254.008 291.028 + vertex 857.907 250.542 292.999 + endloop + endfacet + facet normal 0.53613 -0.721251 -0.43859 + outer loop + vertex 857.907 250.542 292.999 + vertex 860.958 254.008 291.028 + vertex 861.738 253.654 292.564 + endloop + endfacet + facet normal 0.443534 -0.731331 -0.518105 + outer loop + vertex 855.251 250.196 291.116 + vertex 858.091 251.976 291.035 + vertex 854.927 248.533 293.187 + endloop + endfacet + facet normal 0.464631 -0.735285 -0.49343 + outer loop + vertex 854.927 248.533 293.187 + vertex 858.091 251.976 291.035 + vertex 857.907 250.542 292.999 + endloop + endfacet + facet normal 0.450765 -0.718157 -0.530153 + outer loop + vertex 854.927 248.533 293.187 + vertex 857.907 250.542 292.999 + vertex 854.734 247.406 294.549 + endloop + endfacet + facet normal 0.467527 -0.723866 -0.507382 + outer loop + vertex 854.734 247.406 294.549 + vertex 857.907 250.542 292.999 + vertex 857.839 249.544 294.36 + endloop + endfacet + facet normal 0.515564 -0.7031 -0.48974 + outer loop + vertex 857.907 250.542 292.999 + vertex 861.738 253.654 292.564 + vertex 857.839 249.544 294.36 + endloop + endfacet + facet normal 0.51662 -0.703416 -0.488171 + outer loop + vertex 857.839 249.544 294.36 + vertex 861.738 253.654 292.564 + vertex 861.76 252.668 294.008 + endloop + endfacet + facet normal 0.501158 -0.742924 -0.44374 + outer loop + vertex 858.594 255.705 285.536 + vertex 861.141 257.251 285.825 + vertex 858.343 253.775 288.484 + endloop + endfacet + facet normal 0.519457 -0.742165 -0.423504 + outer loop + vertex 858.343 253.775 288.484 + vertex 861.141 257.251 285.825 + vertex 861.59 256.11 288.375 + endloop + endfacet + facet normal 0.431749 -0.764855 -0.47811 + outer loop + vertex 856.069 254.328 285.459 + vertex 858.594 255.705 285.536 + vertex 855.662 252.221 288.461 + endloop + endfacet + facet normal 0.447359 -0.765233 -0.462913 + outer loop + vertex 855.662 252.221 288.461 + vertex 858.594 255.705 285.536 + vertex 858.343 253.775 288.484 + endloop + endfacet + facet normal 0.436853 -0.746512 -0.501876 + outer loop + vertex 855.662 252.221 288.461 + vertex 858.343 253.775 288.484 + vertex 855.251 250.196 291.116 + endloop + endfacet + facet normal 0.455139 -0.748222 -0.482714 + outer loop + vertex 855.251 250.196 291.116 + vertex 858.343 253.775 288.484 + vertex 858.091 251.976 291.035 + endloop + endfacet + facet normal 0.507284 -0.727077 -0.462625 + outer loop + vertex 858.343 253.775 288.484 + vertex 861.59 256.11 288.375 + vertex 858.091 251.976 291.035 + endloop + endfacet + facet normal 0.514567 -0.727542 -0.453766 + outer loop + vertex 858.091 251.976 291.035 + vertex 861.59 256.11 288.375 + vertex 860.958 254.008 291.028 + endloop + endfacet + facet normal 0.499644 -0.771693 -0.393506 + outer loop + vertex 858.998 259.407 279.068 + vertex 861.306 260.691 279.481 + vertex 858.819 257.61 282.365 + endloop + endfacet + facet normal 0.512699 -0.76979 -0.380216 + outer loop + vertex 858.819 257.61 282.365 + vertex 861.306 260.691 279.481 + vertex 861.738 259.494 282.487 + endloop + endfacet + facet normal 0.423196 -0.801027 -0.423393 + outer loop + vertex 856.753 258.289 278.939 + vertex 858.998 259.407 279.068 + vertex 856.448 256.376 282.254 + endloop + endfacet + facet normal 0.435746 -0.800031 -0.412402 + outer loop + vertex 856.448 256.376 282.254 + vertex 858.998 259.407 279.068 + vertex 858.819 257.61 282.365 + endloop + endfacet + facet normal 0.428852 -0.783422 -0.449819 + outer loop + vertex 856.448 256.376 282.254 + vertex 858.819 257.61 282.365 + vertex 856.069 254.328 285.459 + endloop + endfacet + facet normal 0.440486 -0.783054 -0.439087 + outer loop + vertex 856.069 254.328 285.459 + vertex 858.819 257.61 282.365 + vertex 858.594 255.705 285.536 + endloop + endfacet + facet normal 0.504917 -0.755298 -0.417833 + outer loop + vertex 858.819 257.61 282.365 + vertex 861.738 259.494 282.487 + vertex 858.594 255.705 285.536 + endloop + endfacet + facet normal 0.505619 -0.755257 -0.417057 + outer loop + vertex 858.594 255.705 285.536 + vertex 861.738 259.494 282.487 + vertex 861.141 257.251 285.825 + endloop + endfacet + facet normal 0.495651 -0.793311 -0.353537 + outer loop + vertex 859.245 262.682 272.284 + vertex 861.368 263.821 272.707 + vertex 859.141 261.098 275.695 + endloop + endfacet + facet normal 0.510135 -0.790114 -0.339828 + outer loop + vertex 859.141 261.098 275.695 + vertex 861.368 263.821 272.707 + vertex 861.807 262.738 275.882 + endloop + endfacet + facet normal 0.408661 -0.8295 -0.380692 + outer loop + vertex 857.198 261.733 272.157 + vertex 859.245 262.682 272.284 + vertex 857.009 260.073 275.57 + endloop + endfacet + facet normal 0.419737 -0.827946 -0.371922 + outer loop + vertex 857.009 260.073 275.57 + vertex 859.245 262.682 272.284 + vertex 859.141 261.098 275.695 + endloop + endfacet + facet normal 0.415875 -0.816392 -0.400689 + outer loop + vertex 857.009 260.073 275.57 + vertex 859.141 261.098 275.695 + vertex 856.753 258.289 278.939 + endloop + endfacet + facet normal 0.42826 -0.814992 -0.390361 + outer loop + vertex 856.753 258.289 278.939 + vertex 859.141 261.098 275.695 + vertex 858.998 259.407 279.068 + endloop + endfacet + facet normal 0.505752 -0.779626 -0.369322 + outer loop + vertex 859.141 261.098 275.695 + vertex 861.807 262.738 275.882 + vertex 858.998 259.407 279.068 + endloop + endfacet + facet normal 0.501005 -0.780339 -0.374253 + outer loop + vertex 858.998 259.407 279.068 + vertex 861.807 262.738 275.882 + vertex 861.306 260.691 279.481 + endloop + endfacet + facet normal 0.487618 -0.811511 -0.321992 + outer loop + vertex 859.29 265.594 265.219 + vertex 861.31 266.612 265.712 + vertex 859.297 264.17 268.82 + endloop + endfacet + facet normal 0.503988 -0.806989 -0.307838 + outer loop + vertex 859.297 264.17 268.82 + vertex 861.31 266.612 265.712 + vertex 861.782 265.657 268.99 + endloop + endfacet + facet normal 0.402369 -0.850576 -0.338556 + outer loop + vertex 857.349 264.847 264.79 + vertex 859.29 265.594 265.219 + vertex 857.301 263.302 268.615 + endloop + endfacet + facet normal 0.404395 -0.850189 -0.33711 + outer loop + vertex 857.301 263.302 268.615 + vertex 859.29 265.594 265.219 + vertex 859.297 264.17 268.82 + endloop + endfacet + facet normal 0.402879 -0.841105 -0.360874 + outer loop + vertex 857.301 263.302 268.615 + vertex 859.297 264.17 268.82 + vertex 857.198 261.733 272.157 + endloop + endfacet + facet normal 0.411722 -0.839641 -0.354242 + outer loop + vertex 857.198 261.733 272.157 + vertex 859.297 264.17 268.82 + vertex 859.245 262.682 272.284 + endloop + endfacet + facet normal 0.500592 -0.798197 -0.335097 + outer loop + vertex 859.297 264.17 268.82 + vertex 861.782 265.657 268.99 + vertex 859.245 262.682 272.284 + endloop + endfacet + facet normal 0.496007 -0.799188 -0.339522 + outer loop + vertex 859.245 262.682 272.284 + vertex 861.782 265.657 268.99 + vertex 861.368 263.821 272.707 + endloop + endfacet + facet normal 0.489916 -0.823743 -0.28536 + outer loop + vertex 859.216 268.305 257.541 + vertex 861.109 269.169 258.296 + vertex 859.246 266.978 261.419 + endloop + endfacet + facet normal 0.498867 -0.820878 -0.278012 + outer loop + vertex 859.246 266.978 261.419 + vertex 861.109 269.169 258.296 + vertex 861.62 268.294 261.797 + endloop + endfacet + facet normal 0.413901 -0.862893 -0.290003 + outer loop + vertex 857.648 267.833 256.707 + vertex 859.216 268.305 257.541 + vertex 857.392 266.412 260.569 + endloop + endfacet + facet normal 0.401747 -0.865563 -0.298997 + outer loop + vertex 857.392 266.412 260.569 + vertex 859.216 268.305 257.541 + vertex 859.246 266.978 261.419 + endloop + endfacet + facet normal 0.406348 -0.858059 -0.314032 + outer loop + vertex 857.392 266.412 260.569 + vertex 859.246 266.978 261.419 + vertex 857.349 264.847 264.79 + endloop + endfacet + facet normal 0.401076 -0.859185 -0.31771 + outer loop + vertex 857.349 264.847 264.79 + vertex 859.246 266.978 261.419 + vertex 859.29 265.594 265.219 + endloop + endfacet + facet normal 0.498191 -0.812801 -0.30193 + outer loop + vertex 859.246 266.978 261.419 + vertex 861.62 268.294 261.797 + vertex 859.29 265.594 265.219 + endloop + endfacet + facet normal 0.487241 -0.815742 -0.311707 + outer loop + vertex 859.29 265.594 265.219 + vertex 861.62 268.294 261.797 + vertex 861.31 266.612 265.712 + endloop + endfacet + facet normal 0.493524 -0.831311 -0.255647 + outer loop + vertex 859.011 270.611 249.886 + vertex 860.826 271.447 250.674 + vertex 859.129 269.502 253.722 + endloop + endfacet + facet normal 0.500986 -0.828627 -0.24978 + outer loop + vertex 859.129 269.502 253.722 + vertex 860.826 271.447 250.674 + vertex 861.359 270.693 254.24 + endloop + endfacet + facet normal 0.417092 -0.871185 -0.258982 + outer loop + vertex 857.503 270.166 248.955 + vertex 859.011 270.611 249.886 + vertex 857.356 268.883 253.034 + endloop + endfacet + facet normal 0.407774 -0.873702 -0.265263 + outer loop + vertex 857.356 268.883 253.034 + vertex 859.011 270.611 249.886 + vertex 859.129 269.502 253.722 + endloop + endfacet + facet normal 0.411463 -0.867129 -0.280689 + outer loop + vertex 857.356 268.883 253.034 + vertex 859.129 269.502 253.722 + vertex 857.648 267.833 256.707 + endloop + endfacet + facet normal 0.410591 -0.86736 -0.28125 + outer loop + vertex 857.648 267.833 256.707 + vertex 859.129 269.502 253.722 + vertex 859.216 268.305 257.541 + endloop + endfacet + facet normal 0.501927 -0.821978 -0.269112 + outer loop + vertex 859.129 269.502 253.722 + vertex 861.359 270.693 254.24 + vertex 859.216 268.305 257.541 + endloop + endfacet + facet normal 0.488975 -0.825994 -0.280424 + outer loop + vertex 859.216 268.305 257.541 + vertex 861.359 270.693 254.24 + vertex 861.109 269.169 258.296 + endloop + endfacet + facet normal 0.495579 -0.839136 -0.224172 + outer loop + vertex 858.761 272.553 242.341 + vertex 860.496 273.367 243.132 + vertex 858.888 271.63 246.079 + endloop + endfacet + facet normal 0.503289 -0.836118 -0.218188 + outer loop + vertex 858.888 271.63 246.079 + vertex 860.496 273.367 243.132 + vertex 861.028 272.771 246.643 + endloop + endfacet + facet normal 0.418736 -0.87979 -0.22501 + outer loop + vertex 857.331 272.124 241.36 + vertex 858.761 272.553 242.341 + vertex 857.222 271.07 245.279 + endloop + endfacet + facet normal 0.408346 -0.882853 -0.231998 + outer loop + vertex 857.222 271.07 245.279 + vertex 858.761 272.553 242.341 + vertex 858.888 271.63 246.079 + endloop + endfacet + facet normal 0.413396 -0.876402 -0.24703 + outer loop + vertex 857.222 271.07 245.279 + vertex 858.888 271.63 246.079 + vertex 857.503 270.166 248.955 + endloop + endfacet + facet normal 0.411944 -0.876827 -0.247946 + outer loop + vertex 857.503 270.166 248.955 + vertex 858.888 271.63 246.079 + vertex 859.011 270.611 249.886 + endloop + endfacet + facet normal 0.505078 -0.829527 -0.238288 + outer loop + vertex 858.888 271.63 246.079 + vertex 861.028 272.771 246.643 + vertex 859.011 270.611 249.886 + endloop + endfacet + facet normal 0.492078 -0.834063 -0.249394 + outer loop + vertex 859.011 270.611 249.886 + vertex 861.028 272.771 246.643 + vertex 860.826 271.447 250.674 + endloop + endfacet + facet normal 0.501725 -0.842601 -0.195691 + outer loop + vertex 858.455 274.2 234.728 + vertex 860.181 275.018 235.629 + vertex 858.613 273.388 238.626 + endloop + endfacet + facet normal 0.508583 -0.839672 -0.19051 + outer loop + vertex 858.613 273.388 238.626 + vertex 860.181 275.018 235.629 + vertex 860.688 274.52 239.179 + endloop + endfacet + facet normal 0.413616 -0.889067 -0.196169 + outer loop + vertex 856.992 273.764 233.62 + vertex 858.455 274.2 234.728 + vertex 856.98 272.855 237.71 + endloop + endfacet + facet normal 0.40444 -0.891973 -0.20202 + outer loop + vertex 856.98 272.855 237.71 + vertex 858.455 274.2 234.728 + vertex 858.613 273.388 238.626 + endloop + endfacet + facet normal 0.410749 -0.885545 -0.217017 + outer loop + vertex 856.98 272.855 237.71 + vertex 858.613 273.388 238.626 + vertex 857.331 272.124 241.36 + endloop + endfacet + facet normal 0.41354 -0.884664 -0.2153 + outer loop + vertex 857.331 272.124 241.36 + vertex 858.613 273.388 238.626 + vertex 858.761 272.553 242.341 + endloop + endfacet + facet normal 0.510365 -0.834458 -0.207863 + outer loop + vertex 858.613 273.388 238.626 + vertex 860.688 274.52 239.179 + vertex 858.761 272.553 242.341 + endloop + endfacet + facet normal 0.494775 -0.840429 -0.22108 + outer loop + vertex 858.761 272.553 242.341 + vertex 860.688 274.52 239.179 + vertex 860.496 273.367 243.132 + endloop + endfacet + facet normal 0.514571 -0.839632 -0.17388 + outer loop + vertex 857.86 275.847 225.269 + vertex 860.251 277.293 225.362 + vertex 858.268 275.062 230.269 + endloop + endfacet + facet normal 0.516634 -0.838631 -0.172591 + outer loop + vertex 858.268 275.062 230.269 + vertex 860.251 277.293 225.362 + vertex 860.467 276.233 231.161 + endloop + endfacet + facet normal 0.410177 -0.89565 -0.171944 + outer loop + vertex 856.465 275.144 225.605 + vertex 857.86 275.847 225.269 + vertex 856.554 274.422 229.579 + endloop + endfacet + facet normal 0.405273 -0.897477 -0.174034 + outer loop + vertex 856.554 274.422 229.579 + vertex 857.86 275.847 225.269 + vertex 858.268 275.062 230.269 + endloop + endfacet + facet normal 0.409662 -0.892284 -0.189751 + outer loop + vertex 856.554 274.422 229.579 + vertex 858.268 275.062 230.269 + vertex 856.992 273.764 233.62 + endloop + endfacet + facet normal 0.409695 -0.892273 -0.189734 + outer loop + vertex 856.992 273.764 233.62 + vertex 858.268 275.062 230.269 + vertex 858.455 274.2 234.728 + endloop + endfacet + facet normal 0.518974 -0.834921 -0.18323 + outer loop + vertex 858.268 275.062 230.269 + vertex 860.467 276.233 231.161 + vertex 858.455 274.2 234.728 + endloop + endfacet + facet normal 0.502096 -0.842111 -0.196846 + outer loop + vertex 858.455 274.2 234.728 + vertex 860.467 276.233 231.161 + vertex 860.181 275.018 235.629 + endloop + endfacet + facet normal 0.515652 -0.842605 -0.155306 + outer loop + vertex 860.251 277.293 225.362 + vertex 857.86 275.847 225.269 + vertex 859.752 278.166 218.969 + endloop + endfacet + facet normal 0.412296 -0.896138 -0.164161 + outer loop + vertex 856.465 275.144 225.605 + vertex 856.995 276.433 219.897 + vertex 857.86 275.847 225.269 + endloop + endfacet + facet normal 0.482307 -0.859073 -0.171386 + outer loop + vertex 856.995 276.433 219.897 + vertex 859.752 278.166 218.969 + vertex 857.86 275.847 225.269 + endloop + endfacet + facet normal 0.490767 -0.860726 -0.135269 + outer loop + vertex 856.701 277.623 211.264 + vertex 859.277 279.042 211.577 + vertex 856.995 276.433 219.897 + endloop + endfacet + facet normal 0.494802 -0.858687 -0.133523 + outer loop + vertex 856.995 276.433 219.897 + vertex 859.277 279.042 211.577 + vertex 859.752 278.166 218.969 + endloop + endfacet + facet normal 0.496046 -0.861751 -0.106407 + outer loop + vertex 856.486 278.52 202.996 + vertex 858.979 279.898 203.459 + vertex 856.701 277.623 211.264 + endloop + endfacet + facet normal 0.4899 -0.864922 -0.109125 + outer loop + vertex 856.701 277.623 211.264 + vertex 858.979 279.898 203.459 + vertex 859.277 279.042 211.577 + endloop + endfacet + facet normal 0.501385 -0.861577 -0.0793559 + outer loop + vertex 856.352 279.179 194.988 + vertex 858.791 280.564 195.366 + vertex 856.486 278.52 202.996 + endloop + endfacet + facet normal 0.493795 -0.865634 -0.0827359 + outer loop + vertex 856.486 278.52 202.996 + vertex 858.791 280.564 195.366 + vertex 858.979 279.898 203.459 + endloop + endfacet + facet normal 0.503209 -0.862376 -0.0555753 + outer loop + vertex 856.265 279.633 187.161 + vertex 858.672 281.021 187.41 + vertex 856.352 279.179 194.988 + endloop + endfacet + facet normal 0.499549 -0.864396 -0.057187 + outer loop + vertex 856.352 279.179 194.988 + vertex 858.672 281.021 187.41 + vertex 858.791 280.564 195.366 + endloop + endfacet + facet normal 0.503947 -0.863083 -0.0335297 + outer loop + vertex 856.198 279.9 179.271 + vertex 858.606 281.297 179.518 + vertex 856.265 279.633 187.161 + endloop + endfacet + facet normal 0.502039 -0.864163 -0.0343494 + outer loop + vertex 856.265 279.633 187.161 + vertex 858.606 281.297 179.518 + vertex 858.672 281.021 187.41 + endloop + endfacet + facet normal 0.504076 -0.863598 -0.0102847 + outer loop + vertex 856.167 279.977 171.3 + vertex 858.573 281.377 171.634 + vertex 856.198 279.9 179.271 + endloop + endfacet + facet normal 0.502464 -0.864529 -0.0109662 + outer loop + vertex 856.198 279.9 179.271 + vertex 858.573 281.377 171.634 + vertex 858.606 281.297 179.518 + endloop + endfacet + facet normal 0.505847 -0.86252 0.013375 + outer loop + vertex 856.193 279.87 163.426 + vertex 858.588 281.28 163.771 + vertex 856.167 279.977 171.3 + endloop + endfacet + facet normal 0.501789 -0.864911 0.0116564 + outer loop + vertex 856.167 279.977 171.3 + vertex 858.588 281.28 163.771 + vertex 858.573 281.377 171.634 + endloop + endfacet + facet normal 0.504314 -0.862755 0.0363422 + outer loop + vertex 856.235 279.57 155.704 + vertex 858.64 280.986 155.967 + vertex 856.193 279.87 163.426 + endloop + endfacet + facet normal 0.503157 -0.863451 0.0358587 + outer loop + vertex 856.193 279.87 163.426 + vertex 858.64 280.986 155.967 + vertex 858.588 281.28 163.771 + endloop + endfacet + facet normal 0.502433 -0.862651 0.0582516 + outer loop + vertex 856.316 279.088 147.874 + vertex 858.746 280.523 148.16 + vertex 856.235 279.57 155.704 + endloop + endfacet + facet normal 0.502022 -0.862902 0.0580832 + outer loop + vertex 856.235 279.57 155.704 + vertex 858.746 280.523 148.16 + vertex 858.64 280.986 155.967 + endloop + endfacet + facet normal 0.500309 -0.86201 0.0814173 + outer loop + vertex 856.443 278.405 139.862 + vertex 858.901 279.872 140.287 + vertex 856.316 279.088 147.874 + endloop + endfacet + facet normal 0.499612 -0.862441 0.0811351 + outer loop + vertex 856.316 279.088 147.874 + vertex 858.901 279.872 140.287 + vertex 858.746 280.523 148.16 + endloop + endfacet + facet normal 0.498619 -0.860358 0.105653 + outer loop + vertex 856.615 277.521 131.854 + vertex 859.107 279.023 132.319 + vertex 856.443 278.405 139.862 + endloop + endfacet + facet normal 0.4962 -0.861875 0.104675 + outer loop + vertex 856.443 278.405 139.862 + vertex 859.107 279.023 132.319 + vertex 858.901 279.872 140.287 + endloop + endfacet + facet normal 0.494856 -0.859062 0.130882 + outer loop + vertex 856.733 276.39 123.981 + vertex 859.317 277.912 124.199 + vertex 856.615 277.521 131.854 + endloop + endfacet + facet normal 0.49367 -0.859814 0.130424 + outer loop + vertex 856.615 277.521 131.854 + vertex 859.317 277.912 124.199 + vertex 859.107 279.023 132.319 + endloop + endfacet + facet normal 0.469615 -0.868867 0.156626 + outer loop + vertex 856.633 275.035 116.765 + vertex 859.377 276.325 115.692 + vertex 856.733 276.39 123.981 + endloop + endfacet + facet normal 0.490389 -0.856096 0.163152 + outer loop + vertex 856.733 276.39 123.981 + vertex 859.377 276.325 115.692 + vertex 859.317 277.912 124.199 + endloop + endfacet + facet normal 0.415609 -0.890718 0.184094 + outer loop + vertex 856.518 273.646 110.305 + vertex 858.425 274.597 110.602 + vertex 856.633 275.035 116.765 + endloop + endfacet + facet normal 0.516226 -0.835773 0.187068 + outer loop + vertex 860.132 275.505 109.948 + vertex 859.377 276.325 115.692 + vertex 858.425 274.597 110.602 + endloop + endfacet + facet normal 0.479773 -0.854257 0.200159 + outer loop + vertex 859.377 276.325 115.692 + vertex 856.633 275.035 116.765 + vertex 858.425 274.597 110.602 + endloop + endfacet + facet normal 0.502461 -0.840306 0.203515 + outer loop + vertex 858.4 272.361 101.054 + vertex 860.067 273.562 101.896 + vertex 858.286 273.387 105.57 + endloop + endfacet + facet normal 0.511207 -0.833893 0.208061 + outer loop + vertex 858.286 273.387 105.57 + vertex 860.067 273.562 101.896 + vertex 860.374 274.74 105.862 + endloop + endfacet + facet normal 0.421612 -0.879236 0.221785 + outer loop + vertex 857.039 271.435 99.9718 + vertex 858.4 272.361 101.054 + vertex 856.661 272.362 104.364 + endloop + endfacet + facet normal 0.403562 -0.88998 0.212304 + outer loop + vertex 856.661 272.362 104.364 + vertex 858.4 272.361 101.054 + vertex 858.286 273.387 105.57 + endloop + endfacet + facet normal 0.410642 -0.889132 0.202035 + outer loop + vertex 856.661 272.362 104.364 + vertex 858.286 273.387 105.57 + vertex 856.518 273.646 110.305 + endloop + endfacet + facet normal 0.411691 -0.888564 0.202396 + outer loop + vertex 856.518 273.646 110.305 + vertex 858.286 273.387 105.57 + vertex 858.425 274.597 110.602 + endloop + endfacet + facet normal 0.515642 -0.836167 0.186916 + outer loop + vertex 858.286 273.387 105.57 + vertex 860.374 274.74 105.862 + vertex 858.425 274.597 110.602 + endloop + endfacet + facet normal 0.516248 -0.835734 0.187178 + outer loop + vertex 858.425 274.597 110.602 + vertex 860.374 274.74 105.862 + vertex 860.132 275.505 109.948 + endloop + endfacet + facet normal 0.507624 -0.829717 0.232137 + outer loop + vertex 858.546 270.414 93.5275 + vertex 860.274 271.684 94.2894 + vertex 858.489 271.399 97.1713 + endloop + endfacet + facet normal 0.511212 -0.826802 0.234648 + outer loop + vertex 858.489 271.399 97.1713 + vertex 860.274 271.684 94.2894 + vertex 860.552 272.835 97.7361 + endloop + endfacet + facet normal 0.428593 -0.867796 0.251472 + outer loop + vertex 857.095 269.391 92.4712 + vertex 858.546 270.414 93.5275 + vertex 856.878 270.393 96.2972 + endloop + endfacet + facet normal 0.415242 -0.876554 0.243367 + outer loop + vertex 856.878 270.393 96.2972 + vertex 858.546 270.414 93.5275 + vertex 858.489 271.399 97.1713 + endloop + endfacet + facet normal 0.422433 -0.876664 0.230239 + outer loop + vertex 856.878 270.393 96.2972 + vertex 858.489 271.399 97.1713 + vertex 857.039 271.435 99.9718 + endloop + endfacet + facet normal 0.41733 -0.879782 0.227637 + outer loop + vertex 857.039 271.435 99.9718 + vertex 858.489 271.399 97.1713 + vertex 858.4 272.361 101.054 + endloop + endfacet + facet normal 0.516893 -0.828062 0.217105 + outer loop + vertex 858.489 271.399 97.1713 + vertex 860.552 272.835 97.7361 + vertex 858.4 272.361 101.054 + endloop + endfacet + facet normal 0.501563 -0.840383 0.205404 + outer loop + vertex 858.4 272.361 101.054 + vertex 860.552 272.835 97.7361 + vertex 860.067 273.562 101.896 + endloop + endfacet + facet normal 0.510512 -0.81949 0.260411 + outer loop + vertex 858.568 268.145 86.1144 + vertex 860.371 269.559 87.0289 + vertex 858.568 269.333 89.8553 + endloop + endfacet + facet normal 0.512408 -0.817878 0.26175 + outer loop + vertex 858.568 269.333 89.8553 + vertex 860.371 269.559 87.0289 + vertex 860.72 270.872 90.451 + endloop + endfacet + facet normal 0.434399 -0.855346 0.282278 + outer loop + vertex 857.092 266.965 84.8127 + vertex 858.568 268.145 86.1144 + vertex 856.872 268.139 88.7078 + endloop + endfacet + facet normal 0.422511 -0.863796 0.274483 + outer loop + vertex 856.872 268.139 88.7078 + vertex 858.568 268.145 86.1144 + vertex 858.568 269.333 89.8553 + endloop + endfacet + facet normal 0.430935 -0.863572 0.261799 + outer loop + vertex 856.872 268.139 88.7078 + vertex 858.568 269.333 89.8553 + vertex 857.095 269.391 92.4712 + endloop + endfacet + facet normal 0.424045 -0.868108 0.258019 + outer loop + vertex 857.095 269.391 92.4712 + vertex 858.568 269.333 89.8553 + vertex 858.546 270.414 93.5275 + endloop + endfacet + facet normal 0.518399 -0.8195 0.2443 + outer loop + vertex 858.568 269.333 89.8553 + vertex 860.72 270.872 90.451 + vertex 858.546 270.414 93.5275 + endloop + endfacet + facet normal 0.506596 -0.829698 0.234439 + outer loop + vertex 858.546 270.414 93.5275 + vertex 860.72 270.872 90.451 + vertex 860.274 271.684 94.2894 + endloop + endfacet + facet normal 0.513185 -0.807547 0.290705 + outer loop + vertex 858.554 265.546 78.6912 + vertex 860.39 267.023 79.5514 + vertex 858.571 266.879 82.3636 + endloop + endfacet + facet normal 0.514269 -0.806586 0.291456 + outer loop + vertex 858.571 266.879 82.3636 + vertex 860.39 267.023 79.5514 + vertex 860.787 268.549 83.0726 + endloop + endfacet + facet normal 0.440906 -0.840862 0.313931 + outer loop + vertex 857.069 264.464 77.8767 + vertex 858.554 265.546 78.6912 + vertex 856.89 265.668 81.3539 + endloop + endfacet + facet normal 0.428385 -0.850015 0.306528 + outer loop + vertex 856.89 265.668 81.3539 + vertex 858.554 265.546 78.6912 + vertex 858.571 266.879 82.3636 + endloop + endfacet + facet normal 0.436531 -0.850466 0.29351 + outer loop + vertex 856.89 265.668 81.3539 + vertex 858.571 266.879 82.3636 + vertex 857.092 266.965 84.8127 + endloop + endfacet + facet normal 0.428849 -0.855882 0.289059 + outer loop + vertex 857.092 266.965 84.8127 + vertex 858.571 266.879 82.3636 + vertex 858.568 268.145 86.1144 + endloop + endfacet + facet normal 0.521488 -0.808373 0.273099 + outer loop + vertex 858.571 266.879 82.3636 + vertex 860.787 268.549 83.0726 + vertex 858.568 268.145 86.1144 + endloop + endfacet + facet normal 0.509322 -0.819484 0.262749 + outer loop + vertex 858.568 268.145 86.1144 + vertex 860.787 268.549 83.0726 + vertex 860.371 269.559 87.0289 + endloop + endfacet + facet normal 0.514057 -0.798063 0.314389 + outer loop + vertex 858.281 262.663 71.6719 + vertex 860.302 264.167 72.1836 + vertex 858.47 264.159 75.1576 + endloop + endfacet + facet normal 0.520204 -0.792554 0.318191 + outer loop + vertex 858.47 264.159 75.1576 + vertex 860.302 264.167 72.1836 + vertex 860.787 265.861 75.6113 + endloop + endfacet + facet normal 0.42725 -0.838928 0.337131 + outer loop + vertex 856.356 261.624 71.5253 + vertex 858.281 262.663 71.6719 + vertex 856.675 263.204 75.0538 + endloop + endfacet + facet normal 0.426561 -0.839381 0.336876 + outer loop + vertex 856.675 263.204 75.0538 + vertex 858.281 262.663 71.6719 + vertex 858.47 264.159 75.1576 + endloop + endfacet + facet normal 0.430728 -0.845041 0.316827 + outer loop + vertex 856.675 263.204 75.0538 + vertex 858.47 264.159 75.1576 + vertex 857.069 264.464 77.8767 + endloop + endfacet + facet normal 0.437425 -0.84048 0.319768 + outer loop + vertex 857.069 264.464 77.8767 + vertex 858.47 264.159 75.1576 + vertex 858.554 265.546 78.6912 + endloop + endfacet + facet normal 0.526077 -0.795726 0.300106 + outer loop + vertex 858.47 264.159 75.1576 + vertex 860.787 265.861 75.6113 + vertex 858.554 265.546 78.6912 + endloop + endfacet + facet normal 0.513612 -0.807582 0.289852 + outer loop + vertex 858.554 265.546 78.6912 + vertex 860.787 265.861 75.6113 + vertex 860.39 267.023 79.5514 + endloop + endfacet + facet normal 0.52273 -0.778239 0.347992 + outer loop + vertex 857.836 259.34 64.6845 + vertex 860.05 261.023 65.1218 + vertex 858.066 261.04 68.1407 + endloop + endfacet + facet normal 0.521992 -0.778948 0.347511 + outer loop + vertex 858.066 261.04 68.1407 + vertex 860.05 261.023 65.1218 + vertex 860.631 262.87 68.3899 + endloop + endfacet + facet normal 0.441926 -0.811755 0.381779 + outer loop + vertex 855.724 258.107 64.5083 + vertex 857.836 259.34 64.6845 + vertex 856.06 259.912 67.9569 + endloop + endfacet + facet normal 0.427702 -0.822072 0.375858 + outer loop + vertex 856.06 259.912 67.9569 + vertex 857.836 259.34 64.6845 + vertex 858.066 261.04 68.1407 + endloop + endfacet + facet normal 0.43169 -0.826714 0.360816 + outer loop + vertex 856.06 259.912 67.9569 + vertex 858.066 261.04 68.1407 + vertex 856.356 261.624 71.5253 + endloop + endfacet + facet normal 0.422505 -0.83298 0.357259 + outer loop + vertex 856.356 261.624 71.5253 + vertex 858.066 261.04 68.1407 + vertex 858.281 262.663 71.6719 + endloop + endfacet + facet normal 0.527277 -0.783731 0.328245 + outer loop + vertex 858.066 261.04 68.1407 + vertex 860.631 262.87 68.3899 + vertex 858.281 262.663 71.6719 + endloop + endfacet + facet normal 0.513029 -0.797626 0.317166 + outer loop + vertex 858.281 262.663 71.6719 + vertex 860.631 262.87 68.3899 + vertex 860.302 264.167 72.1836 + endloop + endfacet + facet normal 0.538727 -0.756033 0.371736 + outer loop + vertex 857.41 255.799 57.9716 + vertex 859.857 257.789 58.4734 + vertex 857.599 257.568 61.2949 + endloop + endfacet + facet normal 0.537929 -0.756949 0.371025 + outer loop + vertex 857.599 257.568 61.2949 + vertex 859.857 257.789 58.4734 + vertex 860.416 259.701 61.5628 + endloop + endfacet + facet normal 0.470595 -0.782243 0.408211 + outer loop + vertex 854.985 254.272 57.8422 + vertex 857.41 255.799 57.9716 + vertex 855.382 256.237 61.1478 + endloop + endfacet + facet normal 0.452496 -0.797638 0.398773 + outer loop + vertex 855.382 256.237 61.1478 + vertex 857.41 255.799 57.9716 + vertex 857.599 257.568 61.2949 + endloop + endfacet + facet normal 0.452685 -0.797877 0.39808 + outer loop + vertex 855.382 256.237 61.1478 + vertex 857.599 257.568 61.2949 + vertex 855.724 258.107 64.5083 + endloop + endfacet + facet normal 0.439132 -0.808421 0.391942 + outer loop + vertex 855.724 258.107 64.5083 + vertex 857.599 257.568 61.2949 + vertex 857.836 259.34 64.6845 + endloop + endfacet + facet normal 0.541374 -0.76005 0.359497 + outer loop + vertex 857.599 257.568 61.2949 + vertex 860.416 259.701 61.5628 + vertex 857.836 259.34 64.6845 + endloop + endfacet + facet normal 0.524406 -0.779213 0.343257 + outer loop + vertex 857.836 259.34 64.6845 + vertex 860.416 259.701 61.5628 + vertex 860.05 261.023 65.1218 + endloop + endfacet + facet normal 0.564373 -0.736135 0.373616 + outer loop + vertex 856.024 251.711 51.9956 + vertex 860.033 254.817 52.0597 + vertex 857.101 253.919 54.7183 + endloop + endfacet + facet normal 0.561544 -0.740622 0.368982 + outer loop + vertex 857.101 253.919 54.7183 + vertex 860.033 254.817 52.0597 + vertex 860.464 256.74 55.2646 + endloop + endfacet + facet normal 0.489689 -0.759435 0.428326 + outer loop + vertex 853.572 250.43 52.527 + vertex 856.024 251.711 51.9956 + vertex 854.375 252.211 54.7663 + endloop + endfacet + facet normal 0.485653 -0.763007 0.426569 + outer loop + vertex 854.375 252.211 54.7663 + vertex 856.024 251.711 51.9956 + vertex 857.101 253.919 54.7183 + endloop + endfacet + facet normal 0.487825 -0.766732 0.417311 + outer loop + vertex 854.375 252.211 54.7663 + vertex 857.101 253.919 54.7183 + vertex 854.985 254.272 57.8422 + endloop + endfacet + facet normal 0.47078 -0.782481 0.407542 + outer loop + vertex 854.985 254.272 57.8422 + vertex 857.101 253.919 54.7183 + vertex 857.41 255.799 57.9716 + endloop + endfacet + facet normal 0.55968 -0.739412 0.374204 + outer loop + vertex 857.101 253.919 54.7183 + vertex 860.464 256.74 55.2646 + vertex 857.41 255.799 57.9716 + endloop + endfacet + facet normal 0.546209 -0.760199 0.351785 + outer loop + vertex 857.41 255.799 57.9716 + vertex 860.464 256.74 55.2646 + vertex 859.857 257.789 58.4734 + endloop + endfacet + facet normal 0.506394 -0.705848 0.495323 + outer loop + vertex 853.392 248.037 48.7701 + vertex 853.687 247.671 47.9473 + vertex 857.721 251.631 49.4655 + endloop + endfacet + facet normal 0.500006 -0.68441 0.530639 + outer loop + vertex 853.053 246.772 47.3855 + vertex 857.363 250.424 48.0334 + vertex 853.687 247.671 47.9473 + endloop + endfacet + facet normal 0.522063 -0.711962 0.469638 + outer loop + vertex 857.363 250.424 48.0334 + vertex 857.721 251.631 49.4655 + vertex 853.687 247.671 47.9473 + endloop + endfacet + facet normal 0.57142 -0.673639 -0.468711 + outer loop + vertex 861.76 252.668 294.008 + vertex 861.738 253.654 292.564 + vertex 866.931 257.952 292.717 + endloop + endfacet + facet normal 0.562804 -0.695779 -0.446255 + outer loop + vertex 860.958 254.008 291.028 + vertex 865.542 259.002 289.024 + vertex 861.738 253.654 292.564 + endloop + endfacet + facet normal 0.586621 -0.693827 -0.417708 + outer loop + vertex 865.542 259.002 289.024 + vertex 866.931 257.952 292.717 + vertex 861.738 253.654 292.564 + endloop + endfacet + facet normal 0.580463 -0.699912 -0.416156 + outer loop + vertex 860.958 254.008 291.028 + vertex 861.59 256.11 288.375 + vertex 865.542 259.002 289.024 + endloop + endfacet + facet normal 0.556273 -0.717622 -0.419022 + outer loop + vertex 861.141 257.251 285.825 + vertex 865.219 261.58 283.824 + vertex 861.59 256.11 288.375 + endloop + endfacet + facet normal 0.584706 -0.711742 -0.389284 + outer loop + vertex 865.219 261.58 283.824 + vertex 865.542 259.002 289.024 + vertex 861.59 256.11 288.375 + endloop + endfacet + facet normal 0.578614 -0.721118 -0.381044 + outer loop + vertex 861.141 257.251 285.825 + vertex 861.738 259.494 282.487 + vertex 865.219 261.58 283.824 + endloop + endfacet + facet normal 0.563558 -0.736434 -0.374256 + outer loop + vertex 861.306 260.691 279.481 + vertex 865.037 264.539 277.527 + vertex 861.738 259.494 282.487 + endloop + endfacet + facet normal 0.577538 -0.73232 -0.360773 + outer loop + vertex 865.037 264.539 277.527 + vertex 865.219 261.58 283.824 + vertex 861.738 259.494 282.487 + endloop + endfacet + facet normal 0.583776 -0.737937 -0.338607 + outer loop + vertex 861.306 260.691 279.481 + vertex 861.807 262.738 275.882 + vertex 865.037 264.539 277.527 + endloop + endfacet + facet normal 0.571552 -0.749334 -0.334405 + outer loop + vertex 861.368 263.821 272.707 + vertex 864.818 267.342 270.713 + vertex 861.807 262.738 275.882 + endloop + endfacet + facet normal 0.581396 -0.745701 -0.325437 + outer loop + vertex 864.818 267.342 270.713 + vertex 865.037 264.539 277.527 + vertex 861.807 262.738 275.882 + endloop + endfacet + facet normal 0.588521 -0.748977 -0.304428 + outer loop + vertex 861.368 263.821 272.707 + vertex 861.782 265.657 268.99 + vertex 864.818 267.342 270.713 + endloop + endfacet + facet normal 0.575885 -0.758843 -0.304162 + outer loop + vertex 861.31 266.612 265.712 + vertex 864.528 269.899 263.604 + vertex 861.782 265.657 268.99 + endloop + endfacet + facet normal 0.586316 -0.754343 -0.295298 + outer loop + vertex 864.528 269.899 263.604 + vertex 864.818 267.342 270.713 + vertex 861.782 265.657 268.99 + endloop + endfacet + facet normal 0.591055 -0.757106 -0.278289 + outer loop + vertex 861.31 266.612 265.712 + vertex 861.62 268.294 261.797 + vertex 864.528 269.899 263.604 + endloop + endfacet + facet normal 0.578275 -0.767627 -0.276309 + outer loop + vertex 861.109 269.169 258.296 + vertex 864.168 272.219 256.225 + vertex 861.62 268.294 261.797 + endloop + endfacet + facet normal 0.588144 -0.762898 -0.268464 + outer loop + vertex 864.168 272.219 256.225 + vertex 864.528 269.899 263.604 + vertex 861.62 268.294 261.797 + endloop + endfacet + facet normal 0.592843 -0.765156 -0.251146 + outer loop + vertex 861.109 269.169 258.296 + vertex 861.359 270.693 254.24 + vertex 864.168 272.219 256.225 + endloop + endfacet + facet normal 0.581811 -0.773858 -0.25028 + outer loop + vertex 860.826 271.447 250.674 + vertex 863.751 274.293 248.671 + vertex 861.359 270.693 254.24 + endloop + endfacet + facet normal 0.59014 -0.769567 -0.243929 + outer loop + vertex 863.751 274.293 248.671 + vertex 864.168 272.219 256.225 + vertex 861.359 270.693 254.24 + endloop + endfacet + facet normal 0.597046 -0.770511 -0.223269 + outer loop + vertex 860.826 271.447 250.674 + vertex 861.028 272.771 246.643 + vertex 863.751 274.293 248.671 + endloop + endfacet + facet normal 0.590729 -0.775952 -0.22122 + outer loop + vertex 860.496 273.367 243.132 + vertex 863.321 276.09 241.124 + vertex 861.028 272.771 246.643 + endloop + endfacet + facet normal 0.594927 -0.77363 -0.21808 + outer loop + vertex 863.321 276.09 241.124 + vertex 863.751 274.293 248.671 + vertex 861.028 272.771 246.643 + endloop + endfacet + facet normal 0.604914 -0.771864 -0.195716 + outer loop + vertex 860.496 273.367 243.132 + vertex 860.688 274.52 239.179 + vertex 863.321 276.09 241.124 + endloop + endfacet + facet normal 0.60012 -0.77587 -0.194632 + outer loop + vertex 860.181 275.018 235.629 + vertex 862.977 277.698 233.568 + vertex 860.688 274.52 239.179 + endloop + endfacet + facet normal 0.603476 -0.773885 -0.192139 + outer loop + vertex 862.977 277.698 233.568 + vertex 863.321 276.09 241.124 + vertex 860.688 274.52 239.179 + endloop + endfacet + facet normal 0.613429 -0.771141 -0.17043 + outer loop + vertex 860.181 275.018 235.629 + vertex 860.467 276.233 231.161 + vertex 862.977 277.698 233.568 + endloop + endfacet + facet normal 0.623283 -0.764805 -0.163067 + outer loop + vertex 860.251 277.293 225.362 + vertex 863.079 279.472 225.955 + vertex 860.467 276.233 231.161 + endloop + endfacet + facet normal 0.613936 -0.770539 -0.171324 + outer loop + vertex 863.079 279.472 225.955 + vertex 862.977 277.698 233.568 + vertex 860.467 276.233 231.161 + endloop + endfacet + facet normal 0.61634 -0.772361 -0.153566 + outer loop + vertex 859.752 278.166 218.969 + vertex 862.728 280.568 218.835 + vertex 860.251 277.293 225.362 + endloop + endfacet + facet normal 0.622824 -0.768054 -0.148943 + outer loop + vertex 860.251 277.293 225.362 + vertex 862.728 280.568 218.835 + vertex 863.079 279.472 225.955 + endloop + endfacet + facet normal 0.613434 -0.778691 -0.131681 + outer loop + vertex 859.277 279.042 211.577 + vertex 862.287 281.449 211.364 + vertex 859.752 278.166 218.969 + endloop + endfacet + facet normal 0.619327 -0.774635 -0.127967 + outer loop + vertex 859.752 278.166 218.969 + vertex 862.287 281.449 211.364 + vertex 862.728 280.568 218.835 + endloop + endfacet + facet normal 0.617499 -0.779559 -0.104799 + outer loop + vertex 858.979 279.898 203.459 + vertex 861.929 282.235 203.451 + vertex 859.277 279.042 211.577 + endloop + endfacet + facet normal 0.616535 -0.780243 -0.105383 + outer loop + vertex 859.277 279.042 211.577 + vertex 861.929 282.235 203.451 + vertex 862.287 281.449 211.364 + endloop + endfacet + facet normal 0.622359 -0.778777 -0.0785811 + outer loop + vertex 858.791 280.564 195.366 + vertex 861.696 282.885 195.372 + vertex 858.979 279.898 203.459 + endloop + endfacet + facet normal 0.618935 -0.781289 -0.0806593 + outer loop + vertex 858.979 279.898 203.459 + vertex 861.696 282.885 195.372 + vertex 861.929 282.235 203.451 + endloop + endfacet + facet normal 0.626376 -0.777641 -0.054103 + outer loop + vertex 858.672 281.021 187.41 + vertex 861.551 283.343 187.361 + vertex 858.791 280.564 195.366 + endloop + endfacet + facet normal 0.623279 -0.779993 -0.055987 + outer loop + vertex 858.791 280.564 195.366 + vertex 861.551 283.343 187.361 + vertex 861.696 282.885 195.372 + endloop + endfacet + facet normal 0.628204 -0.777376 -0.032361 + outer loop + vertex 858.606 281.297 179.518 + vertex 861.469 283.613 179.445 + vertex 858.672 281.021 187.41 + endloop + endfacet + facet normal 0.627172 -0.778182 -0.0329858 + outer loop + vertex 858.672 281.021 187.41 + vertex 861.469 283.613 179.445 + vertex 861.551 283.343 187.361 + endloop + endfacet + facet normal 0.628525 -0.777717 -0.0106139 + outer loop + vertex 858.573 281.377 171.634 + vertex 861.434 283.69 171.584 + vertex 858.606 281.297 179.518 + endloop + endfacet + facet normal 0.628838 -0.777466 -0.0104269 + outer loop + vertex 858.606 281.297 179.518 + vertex 861.434 283.69 171.584 + vertex 861.469 283.613 179.445 + endloop + endfacet + facet normal 0.628698 -0.777574 0.0108267 + outer loop + vertex 858.588 281.28 163.771 + vertex 861.452 283.595 163.745 + vertex 858.573 281.377 171.634 + endloop + endfacet + facet normal 0.628754 -0.777529 0.01086 + outer loop + vertex 858.573 281.377 171.634 + vertex 861.452 283.595 163.745 + vertex 861.434 283.69 171.584 + endloop + endfacet + facet normal 0.627503 -0.777895 0.0334568 + outer loop + vertex 858.64 280.986 155.967 + vertex 861.517 283.305 155.917 + vertex 858.588 281.28 163.771 + endloop + endfacet + facet normal 0.6285 -0.777064 0.0340428 + outer loop + vertex 858.588 281.28 163.771 + vertex 861.517 283.305 155.917 + vertex 861.452 283.595 163.745 + endloop + endfacet + facet normal 0.625329 -0.778438 0.0547438 + outer loop + vertex 858.746 280.523 148.16 + vertex 861.64 282.842 148.088 + vertex 858.64 280.986 155.967 + endloop + endfacet + facet normal 0.627112 -0.776929 0.0557783 + outer loop + vertex 858.64 280.986 155.967 + vertex 861.64 282.842 148.088 + vertex 861.517 283.305 155.917 + endloop + endfacet + facet normal 0.622939 -0.778508 0.0766343 + outer loop + vertex 858.901 279.872 140.287 + vertex 861.826 282.208 140.249 + vertex 858.746 280.523 148.16 + endloop + endfacet + facet normal 0.624727 -0.776972 0.0776573 + outer loop + vertex 858.746 280.523 148.16 + vertex 861.826 282.208 140.249 + vertex 861.64 282.842 148.088 + endloop + endfacet + facet normal 0.619736 -0.778544 0.0989787 + outer loop + vertex 859.107 279.023 132.319 + vertex 862.074 281.392 132.378 + vertex 858.901 279.872 140.287 + endloop + endfacet + facet normal 0.621826 -0.776723 0.100167 + outer loop + vertex 858.901 279.872 140.287 + vertex 862.074 281.392 132.378 + vertex 861.826 282.208 140.249 + endloop + endfacet + facet normal 0.616071 -0.77812 0.122418 + outer loop + vertex 859.317 277.912 124.199 + vertex 862.366 280.359 124.413 + vertex 859.107 279.023 132.319 + endloop + endfacet + facet normal 0.617736 -0.776651 0.123353 + outer loop + vertex 859.107 279.023 132.319 + vertex 862.366 280.359 124.413 + vertex 862.074 281.392 132.378 + endloop + endfacet + facet normal 0.614658 -0.774625 0.148832 + outer loop + vertex 859.377 276.325 115.692 + vertex 862.628 279.014 116.268 + vertex 859.317 277.912 124.199 + endloop + endfacet + facet normal 0.612808 -0.776281 0.147829 + outer loop + vertex 859.317 277.912 124.199 + vertex 862.628 279.014 116.268 + vertex 862.366 280.359 124.413 + endloop + endfacet + facet normal 0.633091 -0.750339 0.190226 + outer loop + vertex 860.132 275.505 109.948 + vertex 862.655 277.16 108.08 + vertex 859.377 276.325 115.692 + endloop + endfacet + facet normal 0.608638 -0.773416 0.177164 + outer loop + vertex 859.377 276.325 115.692 + vertex 862.655 277.16 108.08 + vertex 862.628 279.014 116.268 + endloop + endfacet + facet normal 0.628909 -0.756582 0.179046 + outer loop + vertex 860.132 275.505 109.948 + vertex 860.374 274.74 105.862 + vertex 862.655 277.16 108.08 + endloop + endfacet + facet normal 0.604508 -0.775199 0.183401 + outer loop + vertex 860.067 273.562 101.896 + vertex 863.016 275.391 99.9086 + vertex 860.374 274.74 105.862 + endloop + endfacet + facet normal 0.620358 -0.760443 0.192049 + outer loop + vertex 863.016 275.391 99.9086 + vertex 862.655 277.16 108.08 + vertex 860.374 274.74 105.862 + endloop + endfacet + facet normal 0.61197 -0.763879 0.204894 + outer loop + vertex 860.067 273.562 101.896 + vertex 860.552 272.835 97.7361 + vertex 863.016 275.391 99.9086 + endloop + endfacet + facet normal 0.599898 -0.772222 0.209276 + outer loop + vertex 860.274 271.684 94.2894 + vertex 863.309 273.523 92.3731 + vertex 860.552 272.835 97.7361 + endloop + endfacet + facet normal 0.606492 -0.765894 0.213478 + outer loop + vertex 863.309 273.523 92.3731 + vertex 863.016 275.391 99.9086 + vertex 860.552 272.835 97.7361 + endloop + endfacet + facet normal 0.606754 -0.760454 0.231428 + outer loop + vertex 860.274 271.684 94.2894 + vertex 860.72 270.872 90.451 + vertex 863.309 273.523 92.3731 + endloop + endfacet + facet normal 0.5981 -0.766689 0.233376 + outer loop + vertex 860.371 269.559 87.0289 + vertex 863.523 271.423 85.0759 + vertex 860.72 270.872 90.451 + endloop + endfacet + facet normal 0.603618 -0.761293 0.236808 + outer loop + vertex 863.523 271.423 85.0759 + vertex 863.309 273.523 92.3731 + vertex 860.72 270.872 90.451 + endloop + endfacet + facet normal 0.604743 -0.754123 0.256095 + outer loop + vertex 860.371 269.559 87.0289 + vertex 860.787 268.549 83.0726 + vertex 863.523 271.423 85.0759 + endloop + endfacet + facet normal 0.599152 -0.757093 0.260435 + outer loop + vertex 860.39 267.023 79.5514 + vertex 863.671 268.979 77.6885 + vertex 860.787 268.549 83.0726 + endloop + endfacet + facet normal 0.601358 -0.754872 0.261794 + outer loop + vertex 863.671 268.979 77.6885 + vertex 863.523 271.423 85.0759 + vertex 860.787 268.549 83.0726 + endloop + endfacet + facet normal 0.604014 -0.745877 0.280774 + outer loop + vertex 860.39 267.023 79.5514 + vertex 860.787 265.861 75.6113 + vertex 863.671 268.979 77.6885 + endloop + endfacet + facet normal 0.602285 -0.746185 0.283656 + outer loop + vertex 860.302 264.167 72.1836 + vertex 863.759 266.266 70.3649 + vertex 860.787 265.861 75.6113 + endloop + endfacet + facet normal 0.602279 -0.746191 0.283653 + outer loop + vertex 863.759 266.266 70.3649 + vertex 863.671 268.979 77.6885 + vertex 860.787 265.861 75.6113 + endloop + endfacet + facet normal 0.606135 -0.735038 0.303841 + outer loop + vertex 860.302 264.167 72.1836 + vertex 860.631 262.87 68.3899 + vertex 863.759 266.266 70.3649 + endloop + endfacet + facet normal 0.608065 -0.732553 0.305979 + outer loop + vertex 860.05 261.023 65.1218 + vertex 863.807 263.445 63.4554 + vertex 860.631 262.87 68.3899 + endloop + endfacet + facet normal 0.605883 -0.735063 0.304282 + outer loop + vertex 863.807 263.445 63.4554 + vertex 863.759 266.266 70.3649 + vertex 860.631 262.87 68.3899 + endloop + endfacet + facet normal 0.610588 -0.719876 0.330093 + outer loop + vertex 860.05 261.023 65.1218 + vertex 860.416 259.701 61.5628 + vertex 863.807 263.445 63.4554 + endloop + endfacet + facet normal 0.620091 -0.712404 0.328585 + outer loop + vertex 859.857 257.789 58.4734 + vertex 863.988 260.868 57.3521 + vertex 860.416 259.701 61.5628 + endloop + endfacet + facet normal 0.614919 -0.719786 0.322153 + outer loop + vertex 863.988 260.868 57.3521 + vertex 863.807 263.445 63.4554 + vertex 860.416 259.701 61.5628 + endloop + endfacet + facet normal 0.619138 -0.704308 0.347301 + outer loop + vertex 859.857 257.789 58.4734 + vertex 860.464 256.74 55.2646 + vertex 863.988 260.868 57.3521 + endloop + endfacet + facet normal 0.628149 -0.701535 0.336567 + outer loop + vertex 860.033 254.817 52.0597 + vertex 864.682 259.355 52.842 + vertex 860.464 256.74 55.2646 + endloop + endfacet + facet normal 0.627451 -0.704011 0.332678 + outer loop + vertex 864.682 259.355 52.842 + vertex 863.988 260.868 57.3521 + vertex 860.464 256.74 55.2646 + endloop + endfacet + facet normal 0.57931 -0.688806 0.435828 + outer loop + vertex 857.363 250.424 48.0334 + vertex 863.467 255.981 48.7043 + vertex 857.721 251.631 49.4655 + endloop + endfacet + facet normal 0.577236 -0.684385 0.44544 + outer loop + vertex 857.721 251.631 49.4655 + vertex 863.467 255.981 48.7043 + vertex 864.157 257.54 50.204 + endloop + endfacet + facet normal 0.625972 -0.655964 -0.421747 + outer loop + vertex 865.542 259.002 289.024 + vertex 871.408 264.75 288.79 + vertex 866.931 257.952 292.717 + endloop + endfacet + facet normal 0.645924 -0.653463 -0.394675 + outer loop + vertex 866.931 257.952 292.717 + vertex 871.408 264.75 288.79 + vertex 872.936 264.259 292.103 + endloop + endfacet + facet normal 0.637935 -0.673404 -0.373585 + outer loop + vertex 865.219 261.58 283.824 + vertex 870.595 266.564 284.02 + vertex 865.542 259.002 289.024 + endloop + endfacet + facet normal 0.644013 -0.672082 -0.365449 + outer loop + vertex 865.542 259.002 289.024 + vertex 870.595 266.564 284.02 + vertex 871.408 264.75 288.79 + endloop + endfacet + facet normal 0.645007 -0.684296 -0.340155 + outer loop + vertex 865.037 264.539 277.527 + vertex 870.058 269.014 278.045 + vertex 865.219 261.58 283.824 + endloop + endfacet + facet normal 0.64635 -0.683862 -0.338472 + outer loop + vertex 865.219 261.58 283.824 + vertex 870.058 269.014 278.045 + vertex 870.595 266.564 284.02 + endloop + endfacet + facet normal 0.654629 -0.691473 -0.305493 + outer loop + vertex 864.818 267.342 270.713 + vertex 869.536 271.533 271.336 + vertex 865.037 264.539 277.527 + endloop + endfacet + facet normal 0.650064 -0.693352 -0.310933 + outer loop + vertex 865.037 264.539 277.527 + vertex 869.536 271.533 271.336 + vertex 870.058 269.014 278.045 + endloop + endfacet + facet normal 0.662619 -0.695725 -0.277312 + outer loop + vertex 864.528 269.899 263.604 + vertex 868.986 273.892 264.24 + vertex 864.818 267.342 270.713 + endloop + endfacet + facet normal 0.657615 -0.698174 -0.283012 + outer loop + vertex 864.818 267.342 270.713 + vertex 868.986 273.892 264.24 + vertex 869.536 271.533 271.336 + endloop + endfacet + facet normal 0.669105 -0.699017 -0.252335 + outer loop + vertex 864.168 272.219 256.225 + vertex 868.426 276.048 256.907 + vertex 864.528 269.899 263.604 + endloop + endfacet + facet normal 0.664811 -0.701402 -0.257024 + outer loop + vertex 864.528 269.899 263.604 + vertex 868.426 276.048 256.907 + vertex 868.986 273.892 264.24 + endloop + endfacet + facet normal 0.675896 -0.700307 -0.229641 + outer loop + vertex 863.751 274.293 248.671 + vertex 867.844 278.008 249.39 + vertex 864.168 272.219 256.225 + endloop + endfacet + facet normal 0.6705 -0.703597 -0.235331 + outer loop + vertex 864.168 272.219 256.225 + vertex 867.844 278.008 249.39 + vertex 868.426 276.048 256.907 + endloop + endfacet + facet normal 0.683409 -0.700455 -0.205706 + outer loop + vertex 863.321 276.09 241.124 + vertex 867.266 279.74 241.8 + vertex 863.751 274.293 248.671 + endloop + endfacet + facet normal 0.676905 -0.704749 -0.212436 + outer loop + vertex 863.751 274.293 248.671 + vertex 867.266 279.74 241.8 + vertex 867.844 278.008 249.39 + endloop + endfacet + facet normal 0.694436 -0.696715 -0.17985 + outer loop + vertex 862.977 277.698 233.568 + vertex 866.717 281.264 234.193 + vertex 863.321 276.09 241.124 + endloop + endfacet + facet normal 0.684132 -0.704071 -0.19039 + outer loop + vertex 863.321 276.09 241.124 + vertex 866.717 281.264 234.193 + vertex 867.266 279.74 241.8 + endloop + endfacet + facet normal 0.709324 -0.688531 -0.150942 + outer loop + vertex 863.079 279.472 225.955 + vertex 866.285 282.639 226.575 + vertex 862.977 277.698 233.568 + endloop + endfacet + facet normal 0.694937 -0.699728 -0.165659 + outer loop + vertex 862.977 277.698 233.568 + vertex 866.285 282.639 226.575 + vertex 866.717 281.264 234.193 + endloop + endfacet + facet normal 0.712427 -0.687445 -0.14095 + outer loop + vertex 862.728 280.568 218.835 + vertex 865.89 283.82 218.955 + vertex 863.079 279.472 225.955 + endloop + endfacet + facet normal 0.709388 -0.690002 -0.143758 + outer loop + vertex 863.079 279.472 225.955 + vertex 865.89 283.82 218.955 + vertex 866.285 282.639 226.575 + endloop + endfacet + facet normal 0.71293 -0.690266 -0.123547 + outer loop + vertex 862.287 281.449 211.364 + vertex 865.458 284.745 211.251 + vertex 862.728 280.568 218.835 + endloop + endfacet + facet normal 0.713826 -0.689475 -0.122789 + outer loop + vertex 862.728 280.568 218.835 + vertex 865.458 284.745 211.251 + vertex 865.89 283.82 218.955 + endloop + endfacet + facet normal 0.715522 -0.691249 -0.10101 + outer loop + vertex 861.929 282.235 203.451 + vertex 865.084 285.519 203.325 + vertex 862.287 281.449 211.364 + endloop + endfacet + facet normal 0.715121 -0.691616 -0.101335 + outer loop + vertex 862.287 281.449 211.364 + vertex 865.084 285.519 203.325 + vertex 865.458 284.745 211.251 + endloop + endfacet + facet normal 0.719559 -0.690232 -0.07625 + outer loop + vertex 861.696 282.885 195.372 + vertex 864.814 286.146 195.273 + vertex 861.929 282.235 203.451 + endloop + endfacet + facet normal 0.717461 -0.692224 -0.0779424 + outer loop + vertex 861.929 282.235 203.451 + vertex 864.814 286.146 195.273 + vertex 865.084 285.519 203.325 + endloop + endfacet + facet normal 0.722495 -0.689372 -0.0525971 + outer loop + vertex 861.551 283.343 187.361 + vertex 864.64 286.591 187.246 + vertex 861.696 282.885 195.372 + endloop + endfacet + facet normal 0.720955 -0.690887 -0.0538457 + outer loop + vertex 861.696 282.885 195.372 + vertex 864.64 286.591 187.246 + vertex 864.814 286.146 195.273 + endloop + endfacet + facet normal 0.724986 -0.688069 -0.0309323 + outer loop + vertex 861.469 283.613 179.445 + vertex 864.54 286.855 179.313 + vertex 861.551 283.343 187.361 + endloop + endfacet + facet normal 0.723486 -0.689589 -0.032153 + outer loop + vertex 861.551 283.343 187.361 + vertex 864.54 286.855 179.313 + vertex 864.64 286.591 187.246 + endloop + endfacet + facet normal 0.72585 -0.687781 -0.00997175 + outer loop + vertex 861.434 283.69 171.584 + vertex 864.501 286.929 171.455 + vertex 861.469 283.613 179.445 + endloop + endfacet + facet normal 0.725721 -0.687916 -0.0100767 + outer loop + vertex 861.469 283.613 179.445 + vertex 864.501 286.929 171.455 + vertex 864.54 286.855 179.313 + endloop + endfacet + facet normal 0.725727 -0.68791 0.00999217 + outer loop + vertex 861.452 283.595 163.745 + vertex 864.522 286.833 163.632 + vertex 861.434 283.69 171.584 + endloop + endfacet + facet normal 0.72625 -0.687351 0.0104163 + outer loop + vertex 861.434 283.69 171.584 + vertex 864.522 286.833 163.632 + vertex 864.501 286.929 171.455 + endloop + endfacet + facet normal 0.72455 -0.6885 0.0315552 + outer loop + vertex 861.517 283.305 155.917 + vertex 864.605 286.55 155.801 + vertex 861.452 283.595 163.745 + endloop + endfacet + facet normal 0.725772 -0.687165 0.0325369 + outer loop + vertex 861.452 283.595 163.745 + vertex 864.605 286.55 155.801 + vertex 864.522 286.833 163.632 + endloop + endfacet + facet normal 0.722438 -0.689469 0.052111 + outer loop + vertex 861.64 282.842 148.088 + vertex 864.752 286.093 147.949 + vertex 861.517 283.305 155.917 + endloop + endfacet + facet normal 0.724262 -0.687442 0.0535609 + outer loop + vertex 861.517 283.305 155.917 + vertex 864.752 286.093 147.949 + vertex 864.605 286.55 155.801 + endloop + endfacet + facet normal 0.719209 -0.690954 0.0729395 + outer loop + vertex 861.826 282.208 140.249 + vertex 864.966 285.461 140.09 + vertex 861.64 282.842 148.088 + endloop + endfacet + facet normal 0.721872 -0.687947 0.0750319 + outer loop + vertex 861.64 282.842 148.088 + vertex 864.966 285.461 140.09 + vertex 864.752 286.093 147.949 + endloop + endfacet + facet normal 0.715852 -0.691851 0.0943319 + outer loop + vertex 862.074 281.392 132.378 + vertex 865.254 284.665 132.25 + vertex 861.826 282.208 140.249 + endloop + endfacet + facet normal 0.718349 -0.688988 0.0962816 + outer loop + vertex 861.826 282.208 140.249 + vertex 865.254 284.665 132.25 + vertex 864.966 285.461 140.09 + endloop + endfacet + facet normal 0.711338 -0.693218 0.115959 + outer loop + vertex 862.366 280.359 124.413 + vertex 865.611 283.689 124.412 + vertex 862.074 281.392 132.378 + endloop + endfacet + facet normal 0.714475 -0.689569 0.118404 + outer loop + vertex 862.074 281.392 132.378 + vertex 865.611 283.689 124.412 + vertex 865.254 284.665 132.25 + endloop + endfacet + facet normal 0.706318 -0.694446 0.137331 + outer loop + vertex 862.628 279.014 116.268 + vertex 866.012 282.507 116.52 + vertex 862.366 280.359 124.413 + endloop + endfacet + facet normal 0.709166 -0.691091 0.13956 + outer loop + vertex 862.366 280.359 124.413 + vertex 866.012 282.507 116.52 + vertex 865.611 283.689 124.412 + endloop + endfacet + facet normal 0.701235 -0.694821 0.159668 + outer loop + vertex 862.655 277.16 108.08 + vertex 866.402 281.057 108.582 + vertex 862.628 279.014 116.268 + endloop + endfacet + facet normal 0.702892 -0.692834 0.16101 + outer loop + vertex 862.628 279.014 116.268 + vertex 866.402 281.057 108.582 + vertex 866.012 282.507 116.52 + endloop + endfacet + facet normal 0.69654 -0.694288 0.1811 + outer loop + vertex 863.016 275.391 99.9086 + vertex 866.819 279.419 100.723 + vertex 862.655 277.16 108.08 + endloop + endfacet + facet normal 0.697062 -0.693634 0.181596 + outer loop + vertex 862.655 277.16 108.08 + vertex 866.819 279.419 100.723 + vertex 866.402 281.057 108.582 + endloop + endfacet + facet normal 0.690195 -0.695633 0.199314 + outer loop + vertex 863.309 273.523 92.3731 + vertex 867.271 277.67 93.1271 + vertex 863.016 275.391 99.9086 + endloop + endfacet + facet normal 0.691679 -0.693701 0.200895 + outer loop + vertex 863.016 275.391 99.9086 + vertex 867.271 277.67 93.1271 + vertex 866.819 279.419 100.723 + endloop + endfacet + facet normal 0.683649 -0.695767 0.220301 + outer loop + vertex 863.523 271.423 85.0759 + vertex 867.689 275.741 85.7884 + vertex 863.309 273.523 92.3731 + endloop + endfacet + facet normal 0.684679 -0.694388 0.22145 + outer loop + vertex 863.309 273.523 92.3731 + vertex 867.689 275.741 85.7884 + vertex 867.271 277.67 93.1271 + endloop + endfacet + facet normal 0.67986 -0.692058 0.242583 + outer loop + vertex 863.671 268.979 77.6885 + vertex 868.071 273.583 78.4926 + vertex 863.523 271.423 85.0759 + endloop + endfacet + facet normal 0.678386 -0.69409 0.240898 + outer loop + vertex 863.523 271.423 85.0759 + vertex 868.071 273.583 78.4926 + vertex 867.689 275.741 85.7884 + endloop + endfacet + facet normal 0.677217 -0.687277 0.262731 + outer loop + vertex 863.759 266.266 70.3649 + vertex 868.441 271.212 71.2362 + vertex 863.671 268.979 77.6885 + endloop + endfacet + facet normal 0.675018 -0.690472 0.26 + outer loop + vertex 863.671 268.979 77.6885 + vertex 868.441 271.212 71.2362 + vertex 868.071 273.583 78.4926 + endloop + endfacet + facet normal 0.676976 -0.679759 0.282191 + outer loop + vertex 863.807 263.445 63.4554 + vertex 868.8 268.78 64.3302 + vertex 863.759 266.266 70.3649 + endloop + endfacet + facet normal 0.673168 -0.685864 0.276468 + outer loop + vertex 863.759 266.266 70.3649 + vertex 868.8 268.78 64.3302 + vertex 868.441 271.212 71.2362 + endloop + endfacet + facet normal 0.678894 -0.668984 0.302595 + outer loop + vertex 863.988 260.868 57.3521 + vertex 869.148 266.529 58.2909 + vertex 863.807 263.445 63.4554 + endloop + endfacet + facet normal 0.674044 -0.678597 0.291839 + outer loop + vertex 863.807 263.445 63.4554 + vertex 869.148 266.529 58.2909 + vertex 868.8 268.78 64.3302 + endloop + endfacet + facet normal 0.679482 -0.657704 0.32516 + outer loop + vertex 864.682 259.355 52.842 + vertex 869.463 264.709 53.6799 + vertex 863.988 260.868 57.3521 + endloop + endfacet + facet normal 0.676516 -0.668033 0.309933 + outer loop + vertex 863.988 260.868 57.3521 + vertex 869.463 264.709 53.6799 + vertex 869.148 266.529 58.2909 + endloop + endfacet + facet normal 0.647636 -0.657485 0.385073 + outer loop + vertex 863.467 255.981 48.7043 + vertex 868.883 261.616 49.2156 + vertex 864.157 257.54 50.204 + endloop + endfacet + facet normal 0.641582 -0.642081 0.419648 + outer loop + vertex 864.157 257.54 50.204 + vertex 868.883 261.616 49.2156 + vertex 869.413 263.163 50.772 + endloop + endfacet + facet normal 0.68096 -0.610497 -0.404459 + outer loop + vertex 871.408 264.75 288.79 + vertex 876.528 270.568 288.629 + vertex 872.936 264.259 292.103 + endloop + endfacet + facet normal 0.696735 -0.607131 -0.382038 + outer loop + vertex 872.936 264.259 292.103 + vertex 876.528 270.568 288.629 + vertex 877.855 269.929 292.065 + endloop + endfacet + facet normal 0.693634 -0.625989 -0.356385 + outer loop + vertex 870.595 266.564 284.02 + vertex 875.582 272.069 284.057 + vertex 871.408 264.75 288.79 + endloop + endfacet + facet normal 0.698476 -0.624398 -0.349654 + outer loop + vertex 871.408 264.75 288.79 + vertex 875.582 272.069 284.057 + vertex 876.528 270.568 288.629 + endloop + endfacet + facet normal 0.703487 -0.633165 -0.322813 + outer loop + vertex 870.058 269.014 278.045 + vertex 874.801 274.167 278.274 + vertex 870.595 266.564 284.02 + endloop + endfacet + facet normal 0.702026 -0.633806 -0.324731 + outer loop + vertex 870.595 266.564 284.02 + vertex 874.801 274.167 278.274 + vertex 875.582 272.069 284.057 + endloop + endfacet + facet normal 0.713034 -0.636315 -0.294424 + outer loop + vertex 869.536 271.533 271.336 + vertex 874.035 276.422 271.666 + vertex 870.058 269.014 278.045 + endloop + endfacet + facet normal 0.708467 -0.638757 -0.300106 + outer loop + vertex 870.058 269.014 278.045 + vertex 874.035 276.422 271.666 + vertex 874.801 274.167 278.274 + endloop + endfacet + facet normal 0.723759 -0.636096 -0.267499 + outer loop + vertex 868.986 273.892 264.24 + vertex 873.238 278.582 264.591 + vertex 869.536 271.533 271.336 + endloop + endfacet + facet normal 0.716408 -0.640644 -0.276288 + outer loop + vertex 869.536 271.533 271.336 + vertex 873.238 278.582 264.591 + vertex 874.035 276.422 271.666 + endloop + endfacet + facet normal 0.733859 -0.634493 -0.24263 + outer loop + vertex 868.426 276.048 256.907 + vertex 872.46 280.574 257.272 + vertex 868.986 273.892 264.24 + endloop + endfacet + facet normal 0.726383 -0.639685 -0.251336 + outer loop + vertex 868.986 273.892 264.24 + vertex 872.46 280.574 257.272 + vertex 873.238 278.582 264.591 + endloop + endfacet + facet normal 0.742159 -0.632292 -0.222277 + outer loop + vertex 867.844 278.008 249.39 + vertex 871.706 282.405 249.776 + vertex 868.426 276.048 256.907 + endloop + endfacet + facet normal 0.735708 -0.637191 -0.229612 + outer loop + vertex 868.426 276.048 256.907 + vertex 871.706 282.405 249.776 + vertex 872.46 280.574 257.272 + endloop + endfacet + facet normal 0.751068 -0.628953 -0.200788 + outer loop + vertex 867.266 279.74 241.8 + vertex 870.982 284.06 242.17 + vertex 867.844 278.008 249.39 + endloop + endfacet + facet normal 0.743801 -0.634906 -0.208935 + outer loop + vertex 867.844 278.008 249.39 + vertex 870.982 284.06 242.17 + vertex 871.706 282.405 249.776 + endloop + endfacet + facet normal 0.760002 -0.624517 -0.179932 + outer loop + vertex 866.717 281.264 234.193 + vertex 870.292 285.524 234.508 + vertex 867.266 279.74 241.8 + endloop + endfacet + facet normal 0.752418 -0.631179 -0.188364 + outer loop + vertex 867.266 279.74 241.8 + vertex 870.292 285.524 234.508 + vertex 870.982 284.06 242.17 + endloop + endfacet + facet normal 0.771142 -0.617475 -0.155128 + outer loop + vertex 866.285 282.639 226.575 + vertex 869.665 286.799 226.816 + vertex 866.717 281.264 234.193 + endloop + endfacet + facet normal 0.761379 -0.626706 -0.165955 + outer loop + vertex 866.717 281.264 234.193 + vertex 869.665 286.799 226.816 + vertex 870.292 285.524 234.508 + endloop + endfacet + facet normal 0.78023 -0.610717 -0.135151 + outer loop + vertex 865.89 283.82 218.955 + vertex 869.109 287.907 219.066 + vertex 866.285 282.639 226.575 + endloop + endfacet + facet normal 0.772139 -0.618933 -0.143958 + outer loop + vertex 866.285 282.639 226.575 + vertex 869.109 287.907 219.066 + vertex 869.665 286.799 226.816 + endloop + endfacet + facet normal 0.785106 -0.608205 -0.117025 + outer loop + vertex 865.458 284.745 211.251 + vertex 868.624 288.836 211.226 + vertex 865.89 283.82 218.955 + endloop + endfacet + facet normal 0.781494 -0.612101 -0.120831 + outer loop + vertex 865.89 283.82 218.955 + vertex 868.624 288.836 211.226 + vertex 869.109 287.907 219.066 + endloop + endfacet + facet normal 0.788427 -0.6075 -0.0965747 + outer loop + vertex 865.084 285.519 203.325 + vertex 868.219 289.599 203.261 + vertex 865.458 284.745 211.251 + endloop + endfacet + facet normal 0.786768 -0.609373 -0.0982854 + outer loop + vertex 865.458 284.745 211.251 + vertex 868.219 289.599 203.261 + vertex 868.624 288.836 211.226 + endloop + endfacet + facet normal 0.791967 -0.606096 -0.0737359 + outer loop + vertex 864.814 286.146 195.273 + vertex 867.917 290.208 195.218 + vertex 865.084 285.519 203.325 + endloop + endfacet + facet normal 0.790011 -0.608395 -0.075749 + outer loop + vertex 865.084 285.519 203.325 + vertex 867.917 290.208 195.218 + vertex 868.219 289.599 203.261 + endloop + endfacet + facet normal 0.795693 -0.60358 -0.05063 + outer loop + vertex 864.64 286.591 187.246 + vertex 867.713 290.645 187.194 + vertex 864.814 286.146 195.273 + endloop + endfacet + facet normal 0.793136 -0.606709 -0.0532902 + outer loop + vertex 864.814 286.146 195.273 + vertex 867.713 290.645 187.194 + vertex 867.917 290.208 195.218 + endloop + endfacet + facet normal 0.797155 -0.603019 -0.0301922 + outer loop + vertex 864.54 286.855 179.313 + vertex 867.594 290.895 179.252 + vertex 864.64 286.591 187.246 + endloop + endfacet + facet normal 0.796455 -0.603906 -0.0309284 + outer loop + vertex 864.64 286.591 187.246 + vertex 867.594 290.895 179.252 + vertex 867.713 290.645 187.194 + endloop + endfacet + facet normal 0.798772 -0.601556 -0.00963282 + outer loop + vertex 864.501 286.929 171.455 + vertex 867.545 290.973 171.395 + vertex 864.54 286.855 179.313 + endloop + endfacet + facet normal 0.797614 -0.603071 -0.0108601 + outer loop + vertex 864.54 286.855 179.313 + vertex 867.545 290.973 171.395 + vertex 867.594 290.895 179.252 + endloop + endfacet + facet normal 0.798268 -0.602226 0.00957103 + outer loop + vertex 864.522 286.833 163.632 + vertex 867.571 290.873 163.578 + vertex 864.501 286.929 171.455 + endloop + endfacet + facet normal 0.79891 -0.601363 0.0102534 + outer loop + vertex 864.501 286.929 171.455 + vertex 867.571 290.873 163.578 + vertex 867.545 290.973 171.395 + endloop + endfacet + facet normal 0.79728 -0.602851 0.0302441 + outer loop + vertex 864.605 286.55 155.801 + vertex 867.67 290.601 155.753 + vertex 864.522 286.833 163.632 + endloop + endfacet + facet normal 0.798058 -0.60178 0.0310675 + outer loop + vertex 864.522 286.833 163.632 + vertex 867.67 290.601 155.753 + vertex 867.571 290.873 163.578 + endloop + endfacet + facet normal 0.795562 -0.603804 0.0500245 + outer loop + vertex 864.752 286.093 147.949 + vertex 867.844 290.161 147.892 + vertex 864.605 286.55 155.801 + endloop + endfacet + facet normal 0.796717 -0.602177 0.0512404 + outer loop + vertex 864.605 286.55 155.801 + vertex 867.844 290.161 147.892 + vertex 867.67 290.601 155.753 + endloop + endfacet + facet normal 0.792207 -0.606181 0.0703728 + outer loop + vertex 864.966 285.461 140.09 + vertex 868.094 289.538 140.007 + vertex 864.752 286.093 147.949 + endloop + endfacet + facet normal 0.794595 -0.602752 0.0728647 + outer loop + vertex 864.752 286.093 147.949 + vertex 868.094 289.538 140.007 + vertex 867.844 290.161 147.892 + endloop + endfacet + facet normal 0.788318 -0.608548 0.0906839 + outer loop + vertex 865.254 284.665 132.25 + vertex 868.42 288.75 132.142 + vertex 864.966 285.461 140.09 + endloop + endfacet + facet normal 0.790933 -0.604733 0.0933993 + outer loop + vertex 864.966 285.461 140.09 + vertex 868.42 288.75 132.142 + vertex 868.094 289.538 140.007 + endloop + endfacet + facet normal 0.783871 -0.610784 0.111757 + outer loop + vertex 865.611 283.689 124.412 + vertex 868.827 287.801 124.328 + vertex 865.254 284.665 132.25 + endloop + endfacet + facet normal 0.786668 -0.606636 0.11466 + outer loop + vertex 865.254 284.665 132.25 + vertex 868.827 287.801 124.328 + vertex 868.42 288.75 132.142 + endloop + endfacet + facet normal 0.778562 -0.61364 0.131484 + outer loop + vertex 866.012 282.507 116.52 + vertex 869.305 286.692 116.551 + vertex 865.611 283.689 124.412 + endloop + endfacet + facet normal 0.781833 -0.608718 0.134902 + outer loop + vertex 865.611 283.689 124.412 + vertex 869.305 286.692 116.551 + vertex 868.827 287.801 124.328 + endloop + endfacet + facet normal 0.771269 -0.618395 0.150768 + outer loop + vertex 866.402 281.057 108.582 + vertex 869.832 285.387 108.794 + vertex 866.012 282.507 116.52 + endloop + endfacet + facet normal 0.775735 -0.611598 0.15551 + outer loop + vertex 866.012 282.507 116.52 + vertex 869.832 285.387 108.794 + vertex 869.305 286.692 116.551 + endloop + endfacet + facet normal 0.764542 -0.621703 0.170181 + outer loop + vertex 866.819 279.419 100.723 + vertex 870.384 283.907 101.103 + vertex 866.402 281.057 108.582 + endloop + endfacet + facet normal 0.76775 -0.616733 0.173783 + outer loop + vertex 866.402 281.057 108.582 + vertex 870.384 283.907 101.103 + vertex 869.832 285.387 108.794 + endloop + endfacet + facet normal 0.757495 -0.624894 0.188968 + outer loop + vertex 867.271 277.67 93.1271 + vertex 870.958 282.273 93.5671 + vertex 866.819 279.419 100.723 + endloop + endfacet + facet normal 0.760389 -0.620291 0.192477 + outer loop + vertex 866.819 279.419 100.723 + vertex 870.958 282.273 93.5671 + vertex 870.384 283.907 101.103 + endloop + endfacet + facet normal 0.750747 -0.62714 0.207542 + outer loop + vertex 867.689 275.741 85.7884 + vertex 871.541 280.493 86.2097 + vertex 867.271 277.67 93.1271 + endloop + endfacet + facet normal 0.753047 -0.623388 0.210493 + outer loop + vertex 867.271 277.67 93.1271 + vertex 871.541 280.493 86.2097 + vertex 870.958 282.273 93.5671 + endloop + endfacet + facet normal 0.7441 -0.629004 0.225097 + outer loop + vertex 868.071 273.583 78.4926 + vertex 872.132 278.548 78.9426 + vertex 867.689 275.741 85.7884 + endloop + endfacet + facet normal 0.746292 -0.625344 0.22802 + outer loop + vertex 867.689 275.741 85.7884 + vertex 872.132 278.548 78.9426 + vertex 871.541 280.493 86.2097 + endloop + endfacet + facet normal 0.738061 -0.629365 0.243239 + outer loop + vertex 868.441 271.212 71.2362 + vertex 872.739 276.451 71.7489 + vertex 868.071 273.583 78.4926 + endloop + endfacet + facet normal 0.739426 -0.627002 0.245188 + outer loop + vertex 868.071 273.583 78.4926 + vertex 872.739 276.451 71.7489 + vertex 872.132 278.548 78.9426 + endloop + endfacet + facet normal 0.733159 -0.628628 0.259431 + outer loop + vertex 868.8 268.78 64.3302 + vertex 873.355 274.315 64.8658 + vertex 868.441 271.212 71.2362 + endloop + endfacet + facet normal 0.733756 -0.627516 0.260433 + outer loop + vertex 868.441 271.212 71.2362 + vertex 873.355 274.315 64.8658 + vertex 872.739 276.451 71.7489 + endloop + endfacet + facet normal 0.731431 -0.624084 0.274822 + outer loop + vertex 869.148 266.529 58.2909 + vertex 873.908 272.339 58.8167 + vertex 868.8 268.78 64.3302 + endloop + endfacet + facet normal 0.730008 -0.627202 0.27149 + outer loop + vertex 868.8 268.78 64.3302 + vertex 873.908 272.339 58.8167 + vertex 873.355 274.315 64.8658 + endloop + endfacet + facet normal 0.729686 -0.617523 0.293639 + outer loop + vertex 869.463 264.709 53.6799 + vertex 874.28 270.624 54.1501 + vertex 869.148 266.529 58.2909 + endloop + endfacet + facet normal 0.728165 -0.622496 0.286835 + outer loop + vertex 869.148 266.529 58.2909 + vertex 874.28 270.624 54.1501 + vertex 873.908 272.339 58.8167 + endloop + endfacet + facet normal 0.701908 -0.610195 0.367405 + outer loop + vertex 868.883 261.616 49.2156 + vertex 873.919 267.552 49.4527 + vertex 869.413 263.163 50.772 + endloop + endfacet + facet normal 0.697574 -0.597162 0.395963 + outer loop + vertex 869.413 263.163 50.772 + vertex 873.919 267.552 49.4527 + vertex 874.305 269.136 51.1619 + endloop + endfacet + facet normal 0.732299 -0.560284 -0.387065 + outer loop + vertex 876.528 270.568 288.629 + vertex 881.102 276.661 288.463 + vertex 877.855 269.929 292.065 + endloop + endfacet + facet normal 0.742947 -0.556958 -0.371251 + outer loop + vertex 877.855 269.929 292.065 + vertex 881.102 276.661 288.463 + vertex 882.578 276.386 291.827 + endloop + endfacet + facet normal 0.745527 -0.571935 -0.342169 + outer loop + vertex 875.582 272.069 284.057 + vertex 880.063 277.978 283.943 + vertex 876.528 270.568 288.629 + endloop + endfacet + facet normal 0.748083 -0.570806 -0.338455 + outer loop + vertex 876.528 270.568 288.629 + vertex 880.063 277.978 283.943 + vertex 881.102 276.661 288.463 + endloop + endfacet + facet normal 0.755488 -0.57655 -0.311171 + outer loop + vertex 874.801 274.167 278.274 + vertex 879.132 279.854 278.252 + vertex 875.582 272.069 284.057 + endloop + endfacet + facet normal 0.753686 -0.57757 -0.31364 + outer loop + vertex 875.582 272.069 284.057 + vertex 879.132 279.854 278.252 + vertex 880.063 277.978 283.943 + endloop + endfacet + facet normal 0.766284 -0.575688 -0.285293 + outer loop + vertex 874.035 276.422 271.666 + vertex 878.164 281.911 271.68 + vertex 874.801 274.167 278.274 + endloop + endfacet + facet normal 0.759989 -0.579911 -0.293462 + outer loop + vertex 874.801 274.167 278.274 + vertex 878.164 281.911 271.68 + vertex 879.132 279.854 278.252 + endloop + endfacet + facet normal 0.776229 -0.573232 -0.262437 + outer loop + vertex 873.238 278.582 264.591 + vertex 877.171 283.889 264.631 + vertex 874.035 276.422 271.666 + endloop + endfacet + facet normal 0.76964 -0.578252 -0.270702 + outer loop + vertex 874.035 276.422 271.666 + vertex 877.171 283.889 264.631 + vertex 878.164 281.911 271.68 + endloop + endfacet + facet normal 0.787916 -0.567799 -0.238314 + outer loop + vertex 872.46 280.574 257.272 + vertex 876.186 285.726 257.318 + vertex 873.238 278.582 264.591 + endloop + endfacet + facet normal 0.778962 -0.575356 -0.249366 + outer loop + vertex 873.238 278.582 264.591 + vertex 876.186 285.726 257.318 + vertex 877.171 283.889 264.631 + endloop + endfacet + facet normal 0.797373 -0.562866 -0.217666 + outer loop + vertex 871.706 282.405 249.776 + vertex 875.266 287.421 249.848 + vertex 872.46 280.574 257.272 + endloop + endfacet + facet normal 0.790147 -0.569518 -0.226533 + outer loop + vertex 872.46 280.574 257.272 + vertex 875.266 287.421 249.848 + vertex 876.186 285.726 257.318 + endloop + endfacet + facet normal 0.805975 -0.557826 -0.198077 + outer loop + vertex 870.982 284.06 242.17 + vertex 874.409 288.979 242.258 + vertex 871.706 282.405 249.776 + endloop + endfacet + facet normal 0.799319 -0.56441 -0.206228 + outer loop + vertex 871.706 282.405 249.776 + vertex 874.409 288.979 242.258 + vertex 875.266 287.421 249.848 + endloop + endfacet + facet normal 0.813364 -0.553528 -0.179015 + outer loop + vertex 870.292 285.524 234.508 + vertex 873.615 290.379 234.592 + vertex 870.982 284.06 242.17 + endloop + endfacet + facet normal 0.807844 -0.559349 -0.185787 + outer loop + vertex 870.982 284.06 242.17 + vertex 873.615 290.379 234.592 + vertex 874.409 288.979 242.258 + endloop + endfacet + facet normal 0.822327 -0.546734 -0.157671 + outer loop + vertex 869.665 286.799 226.816 + vertex 872.878 291.618 226.863 + vertex 870.292 285.524 234.508 + endloop + endfacet + facet normal 0.815056 -0.5549 -0.16664 + outer loop + vertex 870.292 285.524 234.508 + vertex 872.878 291.618 226.863 + vertex 873.615 290.379 234.592 + endloop + endfacet + facet normal 0.829479 -0.541478 -0.136992 + outer loop + vertex 869.109 287.907 219.066 + vertex 872.227 292.681 219.078 + vertex 869.665 286.799 226.816 + endloop + endfacet + facet normal 0.82403 -0.548005 -0.143757 + outer loop + vertex 869.665 286.799 226.816 + vertex 872.227 292.681 219.078 + vertex 872.878 291.618 226.863 + endloop + endfacet + facet normal 0.836152 -0.536256 -0.115233 + outer loop + vertex 868.624 288.836 211.226 + vertex 871.668 293.586 211.206 + vertex 869.109 287.907 219.066 + endloop + endfacet + facet normal 0.831157 -0.542612 -0.121452 + outer loop + vertex 869.109 287.907 219.066 + vertex 871.668 293.586 211.206 + vertex 872.227 292.681 219.078 + endloop + endfacet + facet normal 0.840845 -0.5331 -0.093725 + outer loop + vertex 868.219 289.599 203.261 + vertex 871.216 294.329 203.242 + vertex 868.624 288.836 211.226 + endloop + endfacet + facet normal 0.837778 -0.537225 -0.0975589 + outer loop + vertex 868.624 288.836 211.226 + vertex 871.216 294.329 203.242 + vertex 871.668 293.586 211.206 + endloop + endfacet + facet normal 0.844661 -0.53045 -0.0719011 + outer loop + vertex 867.917 290.208 195.218 + vertex 870.874 294.917 195.218 + vertex 868.219 289.599 203.261 + endloop + endfacet + facet normal 0.842219 -0.533895 -0.074985 + outer loop + vertex 868.219 289.599 203.261 + vertex 870.874 294.917 195.218 + vertex 871.216 294.329 203.242 + endloop + endfacet + facet normal 0.847402 -0.528554 -0.0504049 + outer loop + vertex 867.713 290.645 187.194 + vertex 870.638 295.334 187.206 + vertex 867.917 290.208 195.218 + endloop + endfacet + facet normal 0.84568 -0.531091 -0.0526135 + outer loop + vertex 867.917 290.208 195.218 + vertex 870.638 295.334 187.206 + vertex 870.874 294.917 195.218 + endloop + endfacet + facet normal 0.849909 -0.526115 -0.0292876 + outer loop + vertex 867.594 290.895 179.252 + vertex 870.495 295.581 179.267 + vertex 867.713 290.645 187.194 + endloop + endfacet + facet normal 0.848031 -0.528995 -0.031739 + outer loop + vertex 867.713 290.645 187.194 + vertex 870.495 295.581 179.267 + vertex 870.638 295.334 187.206 + endloop + endfacet + facet normal 0.850824 -0.525348 -0.0104191 + outer loop + vertex 867.545 290.973 171.395 + vertex 870.436 295.654 171.407 + vertex 867.594 290.895 179.252 + endloop + endfacet + facet normal 0.850194 -0.526349 -0.0112548 + outer loop + vertex 867.594 290.895 179.252 + vertex 870.436 295.654 171.407 + vertex 870.495 295.581 179.267 + endloop + endfacet + facet normal 0.850835 -0.525348 0.00945046 + outer loop + vertex 867.571 290.873 163.578 + vertex 870.464 295.558 163.593 + vertex 867.545 290.973 171.395 + endloop + endfacet + facet normal 0.850809 -0.525391 0.00941539 + outer loop + vertex 867.545 290.973 171.395 + vertex 870.464 295.558 163.593 + vertex 870.436 295.654 171.407 + endloop + endfacet + facet normal 0.849882 -0.526168 0.0291002 + outer loop + vertex 867.67 290.601 155.753 + vertex 870.578 295.298 155.774 + vertex 867.571 290.873 163.578 + endloop + endfacet + facet normal 0.850463 -0.525185 0.0298816 + outer loop + vertex 867.571 290.873 163.578 + vertex 870.578 295.298 155.774 + vertex 870.464 295.558 163.593 + endloop + endfacet + facet normal 0.8474 -0.528757 0.0482538 + outer loop + vertex 867.844 290.161 147.892 + vertex 870.78 294.869 147.915 + vertex 867.67 290.601 155.753 + endloop + endfacet + facet normal 0.849113 -0.525786 0.0505508 + outer loop + vertex 867.67 290.601 155.753 + vertex 870.78 294.869 147.915 + vertex 870.578 295.298 155.774 + endloop + endfacet + facet normal 0.844911 -0.530471 0.0687432 + outer loop + vertex 868.094 289.538 140.007 + vertex 871.066 294.273 140.02 + vertex 867.844 290.161 147.892 + endloop + endfacet + facet normal 0.84623 -0.528133 0.0705039 + outer loop + vertex 867.844 290.161 147.892 + vertex 871.066 294.273 140.02 + vertex 870.78 294.869 147.915 + endloop + endfacet + facet normal 0.84157 -0.53288 0.0883095 + outer loop + vertex 868.42 288.75 132.142 + vertex 871.436 293.511 132.13 + vertex 868.094 289.538 140.007 + endloop + endfacet + facet normal 0.843393 -0.529579 0.090748 + outer loop + vertex 868.094 289.538 140.007 + vertex 871.436 293.511 132.13 + vertex 871.066 294.273 140.02 + endloop + endfacet + facet normal 0.837198 -0.535987 0.108708 + outer loop + vertex 868.827 287.801 124.328 + vertex 871.892 292.58 124.287 + vertex 868.42 288.75 132.142 + endloop + endfacet + facet normal 0.839591 -0.531564 0.111921 + outer loop + vertex 868.42 288.75 132.142 + vertex 871.892 292.58 124.287 + vertex 871.436 293.511 132.13 + endloop + endfacet + facet normal 0.831907 -0.539911 0.128166 + outer loop + vertex 869.305 286.692 116.551 + vertex 872.43 291.497 116.513 + vertex 868.827 287.801 124.328 + endloop + endfacet + facet normal 0.834891 -0.534306 0.132193 + outer loop + vertex 868.827 287.801 124.328 + vertex 872.43 291.497 116.513 + vertex 871.892 292.58 124.287 + endloop + endfacet + facet normal 0.826245 -0.543653 0.147511 + outer loop + vertex 869.832 285.387 108.794 + vertex 873.035 290.259 108.808 + vertex 869.305 286.692 116.551 + endloop + endfacet + facet normal 0.829222 -0.537979 0.151559 + outer loop + vertex 869.305 286.692 116.551 + vertex 873.035 290.259 108.808 + vertex 872.43 291.497 116.513 + endloop + endfacet + facet normal 0.819619 -0.548803 0.164438 + outer loop + vertex 870.384 283.907 101.103 + vertex 873.686 288.865 101.192 + vertex 869.832 285.387 108.794 + endloop + endfacet + facet normal 0.823265 -0.541757 0.16951 + outer loop + vertex 869.832 285.387 108.794 + vertex 873.686 288.865 101.192 + vertex 873.035 290.259 108.808 + endloop + endfacet + facet normal 0.812842 -0.553338 0.181947 + outer loop + vertex 870.958 282.273 93.5671 + vertex 874.37 287.329 93.7035 + vertex 870.384 283.907 101.103 + endloop + endfacet + facet normal 0.816129 -0.546877 0.186705 + outer loop + vertex 870.384 283.907 101.103 + vertex 874.37 287.329 93.7035 + vertex 873.686 288.865 101.192 + endloop + endfacet + facet normal 0.806243 -0.557215 0.198704 + outer loop + vertex 871.541 280.493 86.2097 + vertex 875.085 285.671 86.3544 + vertex 870.958 282.273 93.5671 + endloop + endfacet + facet normal 0.809136 -0.551408 0.203096 + outer loop + vertex 870.958 282.273 93.5671 + vertex 875.085 285.671 86.3544 + vertex 874.37 287.329 93.7035 + endloop + endfacet + facet normal 0.799228 -0.5612 0.215149 + outer loop + vertex 872.132 278.548 78.9426 + vertex 875.842 283.891 79.0993 + vertex 871.541 280.493 86.2097 + endloop + endfacet + facet normal 0.802221 -0.555055 0.219896 + outer loop + vertex 871.541 280.493 86.2097 + vertex 875.842 283.891 79.0993 + vertex 875.085 285.671 86.3544 + endloop + endfacet + facet normal 0.792116 -0.564768 0.231495 + outer loop + vertex 872.739 276.451 71.7489 + vertex 876.638 281.998 71.9419 + vertex 872.132 278.548 78.9426 + endloop + endfacet + facet normal 0.794924 -0.558831 0.236229 + outer loop + vertex 872.132 278.548 78.9426 + vertex 876.638 281.998 71.9419 + vertex 875.842 283.891 79.0993 + endloop + endfacet + facet normal 0.785486 -0.567672 0.246495 + outer loop + vertex 873.355 274.315 64.8658 + vertex 877.435 280.07 65.1192 + vertex 872.739 276.451 71.7489 + endloop + endfacet + facet normal 0.787823 -0.56243 0.251011 + outer loop + vertex 872.739 276.451 71.7489 + vertex 877.435 280.07 65.1192 + vertex 876.638 281.998 71.9419 + endloop + endfacet + facet normal 0.780353 -0.569915 0.257383 + outer loop + vertex 873.908 272.339 58.8167 + vertex 878.181 278.314 59.0905 + vertex 873.355 274.315 64.8658 + endloop + endfacet + facet normal 0.781945 -0.565824 0.261546 + outer loop + vertex 873.355 274.315 64.8658 + vertex 878.181 278.314 59.0905 + vertex 877.435 280.07 65.1192 + endloop + endfacet + facet normal 0.777841 -0.56727 0.270496 + outer loop + vertex 874.28 270.624 54.1501 + vertex 878.71 276.833 54.4314 + vertex 873.908 272.339 58.8167 + endloop + endfacet + facet normal 0.777527 -0.568425 0.268968 + outer loop + vertex 873.908 272.339 58.8167 + vertex 878.71 276.833 54.4314 + vertex 878.181 278.314 59.0905 + endloop + endfacet + facet normal 0.751138 -0.560051 0.349479 + outer loop + vertex 873.919 267.552 49.4527 + vertex 878.725 274.125 49.6562 + vertex 874.305 269.136 51.1619 + endloop + endfacet + facet normal 0.749219 -0.55451 0.362201 + outer loop + vertex 874.305 269.136 51.1619 + vertex 878.725 274.125 49.6562 + vertex 878.855 275.422 51.3736 + endloop + endfacet + facet normal 0.772786 -0.508073 -0.380347 + outer loop + vertex 881.102 276.661 288.463 + vertex 885.299 283.183 288.277 + vertex 882.578 276.386 291.827 + endloop + endfacet + facet normal 0.784746 -0.503212 -0.361871 + outer loop + vertex 882.578 276.386 291.827 + vertex 885.299 283.183 288.277 + vertex 886.852 283.295 291.488 + endloop + endfacet + facet normal 0.789155 -0.516655 -0.332117 + outer loop + vertex 880.063 277.978 283.943 + vertex 884.127 284.287 283.786 + vertex 881.102 276.661 288.463 + endloop + endfacet + facet normal 0.788647 -0.516931 -0.332894 + outer loop + vertex 881.102 276.661 288.463 + vertex 884.127 284.287 283.786 + vertex 885.299 283.183 288.277 + endloop + endfacet + facet normal 0.800603 -0.517755 -0.301604 + outer loop + vertex 879.132 279.854 278.252 + vertex 883.048 285.99 278.115 + vertex 880.063 277.978 283.943 + endloop + endfacet + facet normal 0.796336 -0.520676 -0.307806 + outer loop + vertex 880.063 277.978 283.943 + vertex 883.048 285.99 278.115 + vertex 884.127 284.287 283.786 + endloop + endfacet + facet normal 0.810293 -0.514577 -0.28042 + outer loop + vertex 878.164 281.911 271.68 + vertex 881.916 287.89 271.55 + vertex 879.132 279.854 278.252 + endloop + endfacet + facet normal 0.803988 -0.519636 -0.289105 + outer loop + vertex 879.132 279.854 278.252 + vertex 881.916 287.89 271.55 + vertex 883.048 285.99 278.115 + endloop + endfacet + facet normal 0.820403 -0.509924 -0.258682 + outer loop + vertex 877.171 283.889 264.631 + vertex 880.753 289.718 264.502 + vertex 878.164 281.911 271.68 + endloop + endfacet + facet normal 0.813392 -0.516254 -0.268095 + outer loop + vertex 878.164 281.911 271.68 + vertex 880.753 289.718 264.502 + vertex 881.916 287.89 271.55 + endloop + endfacet + facet normal 0.829866 -0.504464 -0.238409 + outer loop + vertex 876.186 285.726 257.318 + vertex 879.609 291.411 257.2 + vertex 877.171 283.889 264.631 + endloop + endfacet + facet normal 0.822994 -0.511271 -0.247555 + outer loop + vertex 877.171 283.889 264.631 + vertex 879.609 291.411 257.2 + vertex 880.753 289.718 264.502 + endloop + endfacet + facet normal 0.840116 -0.4974 -0.216327 + outer loop + vertex 875.266 287.421 249.848 + vertex 878.533 292.982 249.746 + vertex 876.186 285.726 257.318 + endloop + endfacet + facet normal 0.832371 -0.505729 -0.226709 + outer loop + vertex 876.186 285.726 257.318 + vertex 878.533 292.982 249.746 + vertex 879.609 291.411 257.2 + endloop + endfacet + facet normal 0.848866 -0.490655 -0.196681 + outer loop + vertex 874.409 288.979 242.258 + vertex 877.548 294.441 242.181 + vertex 875.266 287.421 249.848 + endloop + endfacet + facet normal 0.842166 -0.498411 -0.205776 + outer loop + vertex 875.266 287.421 249.848 + vertex 877.548 294.441 242.181 + vertex 878.533 292.982 249.746 + endloop + endfacet + facet normal 0.856535 -0.484715 -0.177197 + outer loop + vertex 873.615 290.379 234.592 + vertex 876.654 295.773 234.53 + vertex 874.409 288.979 242.258 + endloop + endfacet + facet normal 0.850917 -0.491667 -0.184941 + outer loop + vertex 874.409 288.979 242.258 + vertex 876.654 295.773 234.53 + vertex 877.548 294.441 242.181 + endloop + endfacet + facet normal 0.862646 -0.480103 -0.159193 + outer loop + vertex 872.878 291.618 226.863 + vertex 875.843 296.962 226.812 + vertex 873.615 290.379 234.592 + endloop + endfacet + facet normal 0.858427 -0.485643 -0.165089 + outer loop + vertex 873.615 290.379 234.592 + vertex 875.843 296.962 226.812 + vertex 876.654 295.773 234.53 + endloop + endfacet + facet normal 0.868855 -0.475556 -0.137615 + outer loop + vertex 872.227 292.681 219.078 + vertex 875.127 297.993 219.03 + vertex 872.878 291.618 226.863 + endloop + endfacet + facet normal 0.864832 -0.481166 -0.143335 + outer loop + vertex 872.878 291.618 226.863 + vertex 875.127 297.993 219.03 + vertex 875.843 296.962 226.812 + endloop + endfacet + facet normal 0.874207 -0.471416 -0.116318 + outer loop + vertex 871.668 293.586 211.206 + vertex 874.511 298.869 211.17 + vertex 872.227 292.681 219.078 + endloop + endfacet + facet normal 0.870791 -0.476466 -0.121257 + outer loop + vertex 872.227 292.681 219.078 + vertex 874.511 298.869 211.17 + vertex 875.127 297.993 219.03 + endloop + endfacet + facet normal 0.879329 -0.466974 -0.0933603 + outer loop + vertex 871.216 294.329 203.242 + vertex 874.009 299.59 203.228 + vertex 871.668 293.586 211.206 + endloop + endfacet + facet normal 0.87597 -0.472241 -0.0983092 + outer loop + vertex 871.668 293.586 211.206 + vertex 874.009 299.59 203.228 + vertex 874.511 298.869 211.17 + endloop + endfacet + facet normal 0.882901 -0.464067 -0.0716075 + outer loop + vertex 870.874 294.917 195.218 + vertex 873.626 300.15 195.233 + vertex 871.216 294.329 203.242 + endloop + endfacet + facet normal 0.880727 -0.467668 -0.0748787 + outer loop + vertex 871.216 294.329 203.242 + vertex 873.626 300.15 195.233 + vertex 874.009 299.59 203.228 + endloop + endfacet + facet normal 0.886017 -0.460934 -0.0501448 + outer loop + vertex 870.638 295.334 187.206 + vertex 873.354 300.551 187.24 + vertex 870.874 294.917 195.218 + endloop + endfacet + facet normal 0.883889 -0.464637 -0.053421 + outer loop + vertex 870.874 294.917 195.218 + vertex 873.354 300.551 187.24 + vertex 873.626 300.15 195.233 + endloop + endfacet + facet normal 0.887708 -0.459408 -0.0302971 + outer loop + vertex 870.495 295.581 179.267 + vertex 873.188 300.783 179.304 + vertex 870.638 295.334 187.206 + endloop + endfacet + facet normal 0.88663 -0.461371 -0.0319982 + outer loop + vertex 870.638 295.334 187.206 + vertex 873.188 300.783 179.304 + vertex 873.354 300.551 187.24 + endloop + endfacet + facet normal 0.888657 -0.458442 -0.010905 + outer loop + vertex 870.436 295.654 171.407 + vertex 873.119 300.854 171.443 + vertex 870.495 295.581 179.267 + endloop + endfacet + facet normal 0.887998 -0.459691 -0.0119679 + outer loop + vertex 870.495 295.581 179.267 + vertex 873.119 300.854 171.443 + vertex 873.188 300.783 179.304 + endloop + endfacet + facet normal 0.888814 -0.458185 0.00872368 + outer loop + vertex 870.464 295.558 163.593 + vertex 873.147 300.764 163.629 + vertex 870.436 295.654 171.407 + endloop + endfacet + facet normal 0.888624 -0.45856 0.00841157 + outer loop + vertex 870.436 295.654 171.407 + vertex 873.147 300.764 163.629 + vertex 873.119 300.854 171.443 + endloop + endfacet + facet normal 0.88789 -0.459188 0.0282317 + outer loop + vertex 870.578 295.298 155.774 + vertex 873.274 300.515 155.811 + vertex 870.464 295.558 163.593 + endloop + endfacet + facet normal 0.888414 -0.458119 0.0291015 + outer loop + vertex 870.464 295.558 163.593 + vertex 873.274 300.515 155.811 + vertex 873.147 300.764 163.629 + endloop + endfacet + facet normal 0.886203 -0.460809 0.0479513 + outer loop + vertex 870.78 294.869 147.915 + vertex 873.5 300.105 147.956 + vertex 870.578 295.298 155.774 + endloop + endfacet + facet normal 0.887096 -0.45893 0.0494412 + outer loop + vertex 870.578 295.298 155.774 + vertex 873.5 300.105 147.956 + vertex 873.274 300.515 155.811 + endloop + endfacet + facet normal 0.883716 -0.463208 0.0669645 + outer loop + vertex 871.066 294.273 140.02 + vertex 873.822 299.538 140.064 + vertex 870.78 294.869 147.915 + endloop + endfacet + facet normal 0.88503 -0.460369 0.0691622 + outer loop + vertex 870.78 294.869 147.915 + vertex 873.822 299.538 140.064 + vertex 873.5 300.105 147.956 + endloop + endfacet + facet normal 0.880211 -0.466652 0.0863941 + outer loop + vertex 871.436 293.511 132.13 + vertex 874.238 298.803 132.168 + vertex 871.066 294.273 140.02 + endloop + endfacet + facet normal 0.882069 -0.462537 0.0895194 + outer loop + vertex 871.066 294.273 140.02 + vertex 874.238 298.803 132.168 + vertex 873.822 299.538 140.064 + endloop + endfacet + facet normal 0.876474 -0.469476 0.106705 + outer loop + vertex 871.892 292.58 124.287 + vertex 874.746 297.911 124.305 + vertex 871.436 293.511 132.13 + endloop + endfacet + facet normal 0.87813 -0.465717 0.109519 + outer loop + vertex 871.436 293.511 132.13 + vertex 874.746 297.911 124.305 + vertex 874.238 298.803 132.168 + endloop + endfacet + facet normal 0.871733 -0.473434 0.12626 + outer loop + vertex 872.43 291.497 116.513 + vertex 875.343 296.858 116.502 + vertex 871.892 292.58 124.287 + endloop + endfacet + facet normal 0.873979 -0.46822 0.13012 + outer loop + vertex 871.892 292.58 124.287 + vertex 875.343 296.858 116.502 + vertex 874.746 297.911 124.305 + endloop + endfacet + facet normal 0.866656 -0.477439 0.144774 + outer loop + vertex 873.035 290.259 108.808 + vertex 876.016 295.661 108.779 + vertex 872.43 291.497 116.513 + endloop + endfacet + facet normal 0.868997 -0.471901 0.148841 + outer loop + vertex 872.43 291.497 116.513 + vertex 876.016 295.661 108.779 + vertex 875.343 296.858 116.502 + endloop + endfacet + facet normal 0.86077 -0.482565 0.161882 + outer loop + vertex 873.686 288.865 101.192 + vertex 876.749 294.318 101.161 + vertex 873.035 290.259 108.808 + endloop + endfacet + facet normal 0.863643 -0.475658 0.166943 + outer loop + vertex 873.035 290.259 108.808 + vertex 876.749 294.318 101.161 + vertex 876.016 295.661 108.779 + endloop + endfacet + facet normal 0.854996 -0.487135 0.177991 + outer loop + vertex 874.37 287.329 93.7035 + vertex 877.525 292.859 93.6815 + vertex 873.686 288.865 101.192 + endloop + endfacet + facet normal 0.857634 -0.480687 0.182768 + outer loop + vertex 873.686 288.865 101.192 + vertex 877.525 292.859 93.6815 + vertex 876.749 294.318 101.161 + endloop + endfacet + facet normal 0.848733 -0.492118 0.193578 + outer loop + vertex 875.085 285.671 86.3544 + vertex 878.352 291.3 86.337 + vertex 874.37 287.329 93.7035 + endloop + endfacet + facet normal 0.851548 -0.485085 0.198892 + outer loop + vertex 874.37 287.329 93.7035 + vertex 878.352 291.3 86.337 + vertex 877.525 292.859 93.6815 + endloop + endfacet + facet normal 0.842586 -0.496085 0.209639 + outer loop + vertex 875.842 283.891 79.0993 + vertex 879.242 289.663 79.0909 + vertex 875.085 285.671 86.3544 + endloop + endfacet + facet normal 0.845003 -0.489889 0.214426 + outer loop + vertex 875.085 285.671 86.3544 + vertex 879.242 289.663 79.0909 + vertex 878.352 291.3 86.337 + endloop + endfacet + facet normal 0.836088 -0.500196 0.2253 + outer loop + vertex 876.638 281.998 71.9419 + vertex 880.187 287.936 71.9534 + vertex 875.842 283.891 79.0993 + endloop + endfacet + facet normal 0.838547 -0.493675 0.230488 + outer loop + vertex 875.842 283.891 79.0993 + vertex 880.187 287.936 71.9534 + vertex 879.242 289.663 79.0909 + endloop + endfacet + facet normal 0.829306 -0.504832 0.239575 + outer loop + vertex 877.435 280.07 65.1192 + vertex 881.112 286.13 65.1606 + vertex 876.638 281.998 71.9419 + endloop + endfacet + facet normal 0.83185 -0.497702 0.245597 + outer loop + vertex 876.638 281.998 71.9419 + vertex 881.112 286.13 65.1606 + vertex 880.187 287.936 71.9534 + endloop + endfacet + facet normal 0.822492 -0.510646 0.250495 + outer loop + vertex 878.181 278.314 59.0905 + vertex 881.881 284.364 59.2744 + vertex 877.435 280.07 65.1192 + endloop + endfacet + facet normal 0.825082 -0.502398 0.258525 + outer loop + vertex 877.435 280.07 65.1192 + vertex 881.881 284.364 59.2744 + vertex 881.112 286.13 65.1606 + endloop + endfacet + facet normal 0.819245 -0.513071 0.256117 + outer loop + vertex 878.71 276.833 54.4314 + vertex 882.628 283.201 54.6565 + vertex 878.181 278.314 59.0905 + endloop + endfacet + facet normal 0.820006 -0.509442 0.260881 + outer loop + vertex 878.181 278.314 59.0905 + vertex 882.628 283.201 54.6565 + vertex 881.881 284.364 59.2744 + endloop + endfacet + facet normal 0.793299 -0.513167 0.327623 + outer loop + vertex 878.725 274.125 49.6562 + vertex 882.721 280.432 49.861 + vertex 878.855 275.422 51.3736 + endloop + endfacet + facet normal 0.787359 -0.497626 0.363916 + outer loop + vertex 878.855 275.422 51.3736 + vertex 882.721 280.432 49.861 + vertex 883.001 282.119 51.5611 + endloop + endfacet + facet normal 0.80869 -0.453033 -0.375208 + outer loop + vertex 885.299 283.183 288.277 + vertex 889.061 289.98 288.178 + vertex 886.852 283.295 291.488 + endloop + endfacet + facet normal 0.81463 -0.450238 -0.365601 + outer loop + vertex 886.852 283.295 291.488 + vertex 889.061 289.98 288.178 + vertex 890.619 290.018 291.602 + endloop + endfacet + facet normal 0.82504 -0.459874 -0.328367 + outer loop + vertex 884.127 284.287 283.786 + vertex 887.798 290.956 283.67 + vertex 885.299 283.183 288.277 + endloop + endfacet + facet normal 0.823733 -0.460705 -0.330478 + outer loop + vertex 885.299 283.183 288.277 + vertex 887.798 290.956 283.67 + vertex 889.061 289.98 288.178 + endloop + endfacet + facet normal 0.837488 -0.458688 -0.297016 + outer loop + vertex 883.048 285.99 278.115 + vertex 886.58 292.525 277.982 + vertex 884.127 284.287 283.786 + endloop + endfacet + facet normal 0.831807 -0.463209 -0.305834 + outer loop + vertex 884.127 284.287 283.786 + vertex 886.58 292.525 277.982 + vertex 887.798 290.956 283.67 + endloop + endfacet + facet normal 0.846286 -0.454684 -0.277603 + outer loop + vertex 881.916 287.89 271.55 + vertex 885.309 294.282 271.424 + vertex 883.048 285.99 278.115 + endloop + endfacet + facet normal 0.840467 -0.460079 -0.286256 + outer loop + vertex 883.048 285.99 278.115 + vertex 885.309 294.282 271.424 + vertex 886.58 292.525 277.982 + endloop + endfacet + facet normal 0.855757 -0.448713 -0.25756 + outer loop + vertex 880.753 289.718 264.502 + vertex 883.999 295.984 264.372 + vertex 881.916 287.89 271.55 + endloop + endfacet + facet normal 0.848868 -0.455857 -0.267615 + outer loop + vertex 881.916 287.89 271.55 + vertex 883.999 295.984 264.372 + vertex 885.309 294.282 271.424 + endloop + endfacet + facet normal 0.86435 -0.442905 -0.238188 + outer loop + vertex 879.609 291.411 257.2 + vertex 882.722 297.555 257.076 + vertex 880.753 289.718 264.502 + endloop + endfacet + facet normal 0.858274 -0.4498 -0.247076 + outer loop + vertex 880.753 289.718 264.502 + vertex 882.722 297.555 257.076 + vertex 883.999 295.984 264.372 + endloop + endfacet + facet normal 0.872943 -0.436423 -0.217958 + outer loop + vertex 878.533 292.982 249.746 + vertex 881.521 299.015 249.635 + vertex 879.609 291.411 257.2 + endloop + endfacet + facet normal 0.866818 -0.443931 -0.227051 + outer loop + vertex 879.609 291.411 257.2 + vertex 881.521 299.015 249.635 + vertex 882.722 297.555 257.076 + endloop + endfacet + facet normal 0.88099 -0.429889 -0.197615 + outer loop + vertex 877.548 294.441 242.181 + vertex 880.424 300.379 242.087 + vertex 878.533 292.982 249.746 + endloop + endfacet + facet normal 0.875306 -0.437378 -0.20625 + outer loop + vertex 878.533 292.982 249.746 + vertex 880.424 300.379 242.087 + vertex 881.521 299.015 249.635 + endloop + endfacet + facet normal 0.888507 -0.423178 -0.177414 + outer loop + vertex 876.654 295.773 234.53 + vertex 879.432 301.638 234.453 + vertex 877.548 294.441 242.181 + endloop + endfacet + facet normal 0.883146 -0.430746 -0.185771 + outer loop + vertex 877.548 294.441 242.181 + vertex 879.432 301.638 234.453 + vertex 880.424 300.379 242.087 + endloop + endfacet + facet normal 0.894352 -0.418349 -0.158491 + outer loop + vertex 875.843 296.962 226.812 + vertex 878.548 302.769 226.751 + vertex 876.654 295.773 234.53 + endloop + endfacet + facet normal 0.8906 -0.423999 -0.164487 + outer loop + vertex 876.654 295.773 234.53 + vertex 878.548 302.769 226.751 + vertex 879.432 301.638 234.453 + endloop + endfacet + facet normal 0.900041 -0.413507 -0.137618 + outer loop + vertex 875.127 297.993 219.03 + vertex 877.769 303.761 218.982 + vertex 875.843 296.962 226.812 + endloop + endfacet + facet normal 0.896499 -0.41919 -0.143423 + outer loop + vertex 875.843 296.962 226.812 + vertex 877.769 303.761 218.982 + vertex 878.548 302.769 226.751 + endloop + endfacet + facet normal 0.904797 -0.409607 -0.116466 + outer loop + vertex 874.511 298.869 211.17 + vertex 877.104 304.604 211.137 + vertex 875.127 297.993 219.03 + endloop + endfacet + facet normal 0.902055 -0.414291 -0.121077 + outer loop + vertex 875.127 297.993 219.03 + vertex 877.104 304.604 211.137 + vertex 877.769 303.761 218.982 + endloop + endfacet + facet normal 0.908679 -0.406678 -0.0944242 + outer loop + vertex 874.009 299.59 203.228 + vertex 876.56 305.293 203.216 + vertex 874.511 298.869 211.17 + endloop + endfacet + facet normal 0.906661 -0.410343 -0.0979038 + outer loop + vertex 874.511 298.869 211.17 + vertex 876.56 305.293 203.216 + vertex 877.104 304.604 211.137 + endloop + endfacet + facet normal 0.91251 -0.402696 -0.0718513 + outer loop + vertex 873.626 300.15 195.233 + vertex 876.134 305.831 195.24 + vertex 874.009 299.59 203.228 + endloop + endfacet + facet normal 0.910127 -0.407286 -0.0760721 + outer loop + vertex 874.009 299.59 203.228 + vertex 876.134 305.831 195.24 + vertex 876.56 305.293 203.216 + endloop + endfacet + facet normal 0.915084 -0.399996 -0.0512383 + outer loop + vertex 873.354 300.551 187.24 + vertex 875.83 306.212 187.261 + vertex 873.626 300.15 195.233 + endloop + endfacet + facet normal 0.913526 -0.403169 -0.0540812 + outer loop + vertex 873.626 300.15 195.233 + vertex 875.83 306.212 187.261 + vertex 876.134 305.831 195.24 + endloop + endfacet + facet normal 0.916769 -0.39823 -0.0307822 + outer loop + vertex 873.188 300.783 179.304 + vertex 875.643 306.432 179.329 + vertex 873.354 300.551 187.24 + endloop + endfacet + facet normal 0.915773 -0.400367 -0.0326586 + outer loop + vertex 873.354 300.551 187.24 + vertex 875.643 306.432 179.329 + vertex 875.83 306.212 187.261 + endloop + endfacet + facet normal 0.917634 -0.397256 -0.0116676 + outer loop + vertex 873.119 300.854 171.443 + vertex 875.563 306.499 171.465 + vertex 873.188 300.783 179.304 + endloop + endfacet + facet normal 0.917101 -0.398453 -0.0127016 + outer loop + vertex 873.188 300.783 179.304 + vertex 875.563 306.499 171.465 + vertex 875.643 306.432 179.329 + endloop + endfacet + facet normal 0.9175 -0.397658 0.00781758 + outer loop + vertex 873.147 300.764 163.629 + vertex 875.594 306.412 163.648 + vertex 873.119 300.854 171.443 + endloop + endfacet + facet normal 0.917638 -0.397335 0.00809172 + outer loop + vertex 873.119 300.854 171.443 + vertex 875.594 306.412 163.648 + vertex 875.563 306.499 171.465 + endloop + endfacet + facet normal 0.916907 -0.398142 0.0276498 + outer loop + vertex 873.274 300.515 155.811 + vertex 875.732 306.176 155.83 + vertex 873.147 300.764 163.629 + endloop + endfacet + facet normal 0.91714 -0.397572 0.0281224 + outer loop + vertex 873.147 300.764 163.629 + vertex 875.732 306.176 155.83 + vertex 875.594 306.412 163.648 + endloop + endfacet + facet normal 0.91536 -0.399863 0.0471775 + outer loop + vertex 873.5 300.105 147.956 + vertex 875.98 305.785 147.977 + vertex 873.274 300.515 155.811 + endloop + endfacet + facet normal 0.91614 -0.397879 0.0487809 + outer loop + vertex 873.274 300.515 155.811 + vertex 875.98 305.785 147.977 + vertex 875.732 306.176 155.83 + endloop + endfacet + facet normal 0.913036 -0.402482 0.0661364 + outer loop + vertex 873.822 299.538 140.064 + vertex 876.334 305.242 140.089 + vertex 873.5 300.105 147.956 + endloop + endfacet + facet normal 0.914197 -0.399431 0.068547 + outer loop + vertex 873.5 300.105 147.956 + vertex 876.334 305.242 140.089 + vertex 875.98 305.785 147.977 + endloop + endfacet + facet normal 0.910181 -0.405254 0.0856775 + outer loop + vertex 874.238 298.803 132.168 + vertex 876.792 304.546 132.197 + vertex 873.822 299.538 140.064 + endloop + endfacet + facet normal 0.91143 -0.401869 0.0883036 + outer loop + vertex 873.822 299.538 140.064 + vertex 876.792 304.546 132.197 + vertex 876.334 305.242 140.089 + endloop + endfacet + facet normal 0.9063 -0.409399 0.104946 + outer loop + vertex 874.746 297.911 124.305 + vertex 877.353 303.691 124.333 + vertex 874.238 298.803 132.168 + endloop + endfacet + facet normal 0.908078 -0.404434 0.10875 + outer loop + vertex 874.238 298.803 132.168 + vertex 877.353 303.691 124.333 + vertex 876.792 304.546 132.197 + endloop + endfacet + facet normal 0.902413 -0.412412 0.124765 + outer loop + vertex 875.343 296.858 116.502 + vertex 878.007 302.691 116.519 + vertex 874.746 297.911 124.305 + endloop + endfacet + facet normal 0.903815 -0.408386 0.127823 + outer loop + vertex 874.746 297.911 124.305 + vertex 878.007 302.691 116.519 + vertex 877.353 303.691 124.333 + endloop + endfacet + facet normal 0.897603 -0.417024 0.142828 + outer loop + vertex 876.016 295.661 108.779 + vertex 878.748 301.54 108.774 + vertex 875.343 296.858 116.502 + endloop + endfacet + facet normal 0.899583 -0.411184 0.147239 + outer loop + vertex 875.343 296.858 116.502 + vertex 878.748 301.54 108.774 + vertex 878.007 302.691 116.519 + endloop + endfacet + facet normal 0.892586 -0.421467 0.160174 + outer loop + vertex 876.749 294.318 101.161 + vertex 879.556 300.254 101.135 + vertex 876.016 295.661 108.779 + endloop + endfacet + facet normal 0.894536 -0.41558 0.164615 + outer loop + vertex 876.016 295.661 108.779 + vertex 879.556 300.254 101.135 + vertex 878.748 301.54 108.774 + endloop + endfacet + facet normal 0.887329 -0.426523 0.175287 + outer loop + vertex 877.525 292.859 93.6815 + vertex 880.418 298.861 93.6401 + vertex 876.749 294.318 101.161 + endloop + endfacet + facet normal 0.889472 -0.419906 0.180329 + outer loop + vertex 876.749 294.318 101.161 + vertex 880.418 298.861 93.6401 + vertex 879.556 300.254 101.135 + endloop + endfacet + facet normal 0.881912 -0.431059 0.190837 + outer loop + vertex 878.352 291.3 86.337 + vertex 881.341 297.394 86.2908 + vertex 877.525 292.859 93.6815 + endloop + endfacet + facet normal 0.883904 -0.424731 0.195748 + outer loop + vertex 877.525 292.859 93.6815 + vertex 881.341 297.394 86.2908 + vertex 880.418 298.861 93.6401 + endloop + endfacet + facet normal 0.876307 -0.435496 0.205982 + outer loop + vertex 879.242 289.663 79.0909 + vertex 882.339 295.877 79.052 + vertex 878.352 291.3 86.337 + endloop + endfacet + facet normal 0.878248 -0.429109 0.211058 + outer loop + vertex 878.352 291.3 86.337 + vertex 882.339 295.877 79.052 + vertex 881.341 297.394 86.2908 + endloop + endfacet + facet normal 0.870357 -0.439715 0.221651 + outer loop + vertex 880.187 287.936 71.9534 + vertex 883.409 294.301 71.9291 + vertex 879.242 289.663 79.0909 + endloop + endfacet + facet normal 0.872215 -0.433326 0.226871 + outer loop + vertex 879.242 289.663 79.0909 + vertex 883.409 294.301 71.9291 + vertex 882.339 295.877 79.052 + endloop + endfacet + facet normal 0.864872 -0.443261 0.235619 + outer loop + vertex 881.112 286.13 65.1606 + vertex 884.458 292.644 65.1334 + vertex 880.187 287.936 71.9534 + endloop + endfacet + facet normal 0.866401 -0.437641 0.240456 + outer loop + vertex 880.187 287.936 71.9534 + vertex 884.458 292.644 65.1334 + vertex 883.409 294.301 71.9291 + endloop + endfacet + facet normal 0.859154 -0.448301 0.24674 + outer loop + vertex 881.881 284.364 59.2744 + vertex 885.274 290.819 59.1881 + vertex 881.112 286.13 65.1606 + endloop + endfacet + facet normal 0.860875 -0.441133 0.253567 + outer loop + vertex 881.112 286.13 65.1606 + vertex 885.274 290.819 59.1881 + vertex 884.458 292.644 65.1334 + endloop + endfacet + facet normal 0.851625 -0.458903 0.253265 + outer loop + vertex 882.628 283.201 54.6565 + vertex 885.417 288.697 55.2341 + vertex 881.881 284.364 59.2744 + endloop + endfacet + facet normal 0.853801 -0.445178 0.269891 + outer loop + vertex 881.881 284.364 59.2744 + vertex 885.417 288.697 55.2341 + vertex 885.274 290.819 59.1881 + endloop + endfacet + facet normal 0.829962 -0.458351 0.317926 + outer loop + vertex 882.721 280.432 49.861 + vertex 886.684 287.66 49.9361 + vertex 883.001 282.119 51.5611 + endloop + endfacet + facet normal 0.821093 -0.43855 0.36535 + outer loop + vertex 883.001 282.119 51.5611 + vertex 886.684 287.66 49.9361 + vertex 886.961 289.81 51.8948 + endloop + endfacet + facet normal 0.838852 -0.392426 -0.377265 + outer loop + vertex 889.061 289.98 288.178 + vertex 892.327 297.003 288.135 + vertex 890.619 290.018 291.602 + endloop + endfacet + facet normal 0.849889 -0.385953 -0.358789 + outer loop + vertex 890.619 290.018 291.602 + vertex 892.327 297.003 288.135 + vertex 893.778 297.196 291.365 + endloop + endfacet + facet normal 0.8563 -0.400182 -0.326505 + outer loop + vertex 887.798 290.956 283.67 + vertex 891.031 297.913 283.623 + vertex 889.061 289.98 288.178 + endloop + endfacet + facet normal 0.856262 -0.400209 -0.32657 + outer loop + vertex 889.061 289.98 288.178 + vertex 891.031 297.913 283.623 + vertex 892.327 297.003 288.135 + endloop + endfacet + facet normal 0.86791 -0.399005 -0.295851 + outer loop + vertex 886.58 292.525 277.982 + vertex 889.713 299.386 277.918 + vertex 887.798 290.956 283.67 + endloop + endfacet + facet normal 0.863246 -0.403255 -0.303631 + outer loop + vertex 887.798 290.956 283.67 + vertex 889.713 299.386 277.918 + vertex 891.031 297.913 283.623 + endloop + endfacet + facet normal 0.876349 -0.394931 -0.275758 + outer loop + vertex 885.309 294.282 271.424 + vertex 888.327 301.024 271.362 + vertex 886.58 292.525 277.982 + endloop + endfacet + facet normal 0.871182 -0.40039 -0.284129 + outer loop + vertex 886.58 292.525 277.982 + vertex 888.327 301.024 271.362 + vertex 889.713 299.386 277.918 + endloop + endfacet + facet normal 0.884242 -0.389225 -0.258107 + outer loop + vertex 883.999 295.984 264.372 + vertex 886.898 302.61 264.311 + vertex 885.309 294.282 271.424 + endloop + endfacet + facet normal 0.878598 -0.395859 -0.267136 + outer loop + vertex 885.309 294.282 271.424 + vertex 886.898 302.61 264.311 + vertex 888.327 301.024 271.362 + endloop + endfacet + facet normal 0.892181 -0.38344 -0.238719 + outer loop + vertex 882.722 297.555 257.076 + vertex 885.51 304.076 257.022 + vertex 883.999 295.984 264.372 + endloop + endfacet + facet normal 0.886857 -0.39027 -0.247333 + outer loop + vertex 883.999 295.984 264.372 + vertex 885.51 304.076 257.022 + vertex 886.898 302.61 264.311 + endloop + endfacet + facet normal 0.899755 -0.377293 -0.219296 + outer loop + vertex 881.521 299.015 249.635 + vertex 884.204 305.44 249.59 + vertex 882.722 297.555 257.076 + endloop + endfacet + facet normal 0.894624 -0.384394 -0.227791 + outer loop + vertex 882.722 297.555 257.076 + vertex 884.204 305.44 249.59 + vertex 885.51 304.076 257.022 + endloop + endfacet + facet normal 0.906863 -0.371516 -0.198934 + outer loop + vertex 880.424 300.379 242.087 + vertex 883.013 306.719 242.051 + vertex 881.521 299.015 249.635 + endloop + endfacet + facet normal 0.902322 -0.378276 -0.206695 + outer loop + vertex 881.521 299.015 249.635 + vertex 883.013 306.719 242.051 + vertex 884.204 305.44 249.59 + endloop + endfacet + facet normal 0.913521 -0.36533 -0.178922 + outer loop + vertex 879.432 301.638 234.453 + vertex 881.934 307.907 234.425 + vertex 880.424 300.379 242.087 + endloop + endfacet + facet normal 0.909113 -0.372365 -0.186704 + outer loop + vertex 880.424 300.379 242.087 + vertex 881.934 307.907 234.425 + vertex 883.013 306.719 242.051 + endloop + endfacet + facet normal 0.919677 -0.359341 -0.158328 + outer loop + vertex 878.548 302.769 226.751 + vertex 880.972 308.981 226.73 + vertex 879.432 301.638 234.453 + endloop + endfacet + facet normal 0.915708 -0.366143 -0.165587 + outer loop + vertex 879.432 301.638 234.453 + vertex 880.972 308.981 226.73 + vertex 881.934 307.907 234.425 + endloop + endfacet + facet normal 0.924802 -0.354534 -0.138008 + outer loop + vertex 877.769 303.761 218.982 + vertex 880.13 309.924 218.967 + vertex 878.548 302.769 226.751 + endloop + endfacet + facet normal 0.92177 -0.360108 -0.143747 + outer loop + vertex 878.548 302.769 226.751 + vertex 880.13 309.924 218.967 + vertex 880.972 308.981 226.73 + endloop + endfacet + facet normal 0.929311 -0.350432 -0.116526 + outer loop + vertex 877.104 304.604 211.137 + vertex 879.411 310.727 211.129 + vertex 877.769 303.761 218.982 + endloop + endfacet + facet normal 0.926851 -0.355279 -0.12134 + outer loop + vertex 877.769 303.761 218.982 + vertex 879.411 310.727 211.129 + vertex 880.13 309.924 218.967 + endloop + endfacet + facet normal 0.933343 -0.346411 -0.094179 + outer loop + vertex 876.56 305.293 203.216 + vertex 878.821 311.385 203.215 + vertex 877.104 304.604 211.137 + endloop + endfacet + facet normal 0.931127 -0.351094 -0.0986683 + outer loop + vertex 877.104 304.604 211.137 + vertex 878.821 311.385 203.215 + vertex 879.411 310.727 211.129 + endloop + endfacet + facet normal 0.936066 -0.344126 -0.0731924 + outer loop + vertex 876.134 305.831 195.24 + vertex 878.363 311.893 195.246 + vertex 876.56 305.293 203.216 + endloop + endfacet + facet normal 0.934813 -0.346954 -0.0758176 + outer loop + vertex 876.56 305.293 203.216 + vertex 878.363 311.893 195.246 + vertex 878.821 311.385 203.215 + endloop + endfacet + facet normal 0.938392 -0.341623 -0.0520949 + outer loop + vertex 875.83 306.212 187.261 + vertex 878.03 312.253 187.269 + vertex 876.134 305.831 195.24 + endloop + endfacet + facet normal 0.93717 -0.344551 -0.0547443 + outer loop + vertex 876.134 305.831 195.24 + vertex 878.03 312.253 187.269 + vertex 878.363 311.893 195.246 + endloop + endfacet + facet normal 0.94019 -0.339186 -0.0315377 + outer loop + vertex 875.643 306.432 179.329 + vertex 877.82 312.465 179.336 + vertex 875.83 306.212 187.261 + endloop + endfacet + facet normal 0.939118 -0.341912 -0.0339578 + outer loop + vertex 875.83 306.212 187.261 + vertex 877.82 312.465 179.336 + vertex 878.03 312.253 187.269 + endloop + endfacet + facet normal 0.940773 -0.33881 -0.0124269 + outer loop + vertex 875.563 306.499 171.465 + vertex 877.735 312.528 171.468 + vertex 875.643 306.432 179.329 + endloop + endfacet + facet normal 0.940573 -0.339347 -0.0128962 + outer loop + vertex 875.643 306.432 179.329 + vertex 877.735 312.528 171.468 + vertex 877.82 312.465 179.336 + endloop + endfacet + facet normal 0.94088 -0.338657 0.00752646 + outer loop + vertex 875.594 306.412 163.648 + vertex 877.767 312.446 163.648 + vertex 875.563 306.499 171.465 + endloop + endfacet + facet normal 0.940817 -0.338835 0.00737346 + outer loop + vertex 875.563 306.499 171.465 + vertex 877.767 312.446 163.648 + vertex 877.735 312.528 171.468 + endloop + endfacet + facet normal 0.940105 -0.339831 0.0267871 + outer loop + vertex 875.732 306.176 155.83 + vertex 877.917 312.22 155.829 + vertex 875.594 306.412 163.648 + endloop + endfacet + facet normal 0.940541 -0.338533 0.0278809 + outer loop + vertex 875.594 306.412 163.648 + vertex 877.917 312.22 155.829 + vertex 877.767 312.446 163.648 + endloop + endfacet + facet normal 0.938946 -0.340887 0.0466634 + outer loop + vertex 875.98 305.785 147.977 + vertex 878.183 311.851 147.974 + vertex 875.732 306.176 155.83 + endloop + endfacet + facet normal 0.939371 -0.339561 0.0477535 + outer loop + vertex 875.732 306.176 155.83 + vertex 878.183 311.851 147.974 + vertex 877.917 312.22 155.829 + endloop + endfacet + facet normal 0.937058 -0.342941 0.0656824 + outer loop + vertex 876.334 305.242 140.089 + vertex 878.564 311.335 140.088 + vertex 875.98 305.785 147.977 + endloop + endfacet + facet normal 0.937817 -0.34047 0.0676694 + outer loop + vertex 875.98 305.785 147.977 + vertex 878.564 311.335 140.088 + vertex 878.183 311.851 147.974 + endloop + endfacet + facet normal 0.934326 -0.346204 0.0847231 + outer loop + vertex 876.792 304.546 132.197 + vertex 879.061 310.67 132.199 + vertex 876.334 305.242 140.089 + endloop + endfacet + facet normal 0.935463 -0.342354 0.0877654 + outer loop + vertex 876.334 305.242 140.089 + vertex 879.061 310.67 132.199 + vertex 878.564 311.335 140.088 + endloop + endfacet + facet normal 0.93126 -0.349082 0.104384 + outer loop + vertex 877.353 303.691 124.333 + vertex 879.666 309.864 124.341 + vertex 876.792 304.546 132.197 + endloop + endfacet + facet normal 0.932289 -0.345459 0.107213 + outer loop + vertex 876.792 304.546 132.197 + vertex 879.666 309.864 124.341 + vertex 879.061 310.67 132.199 + endloop + endfacet + facet normal 0.927324 -0.353548 0.122775 + outer loop + vertex 878.007 302.691 116.519 + vertex 880.377 308.913 116.529 + vertex 877.353 303.691 124.333 + endloop + endfacet + facet normal 0.928792 -0.348187 0.126932 + outer loop + vertex 877.353 303.691 124.333 + vertex 880.377 308.913 116.529 + vertex 879.666 309.864 124.341 + endloop + endfacet + facet normal 0.923028 -0.35775 0.14154 + outer loop + vertex 878.748 301.54 108.774 + vertex 881.182 307.823 108.782 + vertex 878.007 302.691 116.519 + endloop + endfacet + facet normal 0.924422 -0.352481 0.145606 + outer loop + vertex 878.007 302.691 116.519 + vertex 881.182 307.823 108.782 + vertex 880.377 308.913 116.529 + endloop + endfacet + facet normal 0.918673 -0.361978 0.158148 + outer loop + vertex 879.556 300.254 101.135 + vertex 882.059 306.607 101.136 + vertex 878.748 301.54 108.774 + endloop + endfacet + facet normal 0.920044 -0.356621 0.162296 + outer loop + vertex 878.748 301.54 108.774 + vertex 882.059 306.607 101.136 + vertex 881.182 307.823 108.782 + endloop + endfacet + facet normal 0.914016 -0.366808 0.173285 + outer loop + vertex 880.418 298.861 93.6401 + vertex 882.999 305.288 93.6321 + vertex 879.556 300.254 101.135 + endloop + endfacet + facet normal 0.915515 -0.360737 0.178045 + outer loop + vertex 879.556 300.254 101.135 + vertex 882.999 305.288 93.6321 + vertex 882.059 306.607 101.136 + endloop + endfacet + facet normal 0.908974 -0.37188 0.188338 + outer loop + vertex 881.341 297.394 86.2908 + vertex 884.006 303.902 86.2771 + vertex 880.418 298.861 93.6401 + endloop + endfacet + facet normal 0.910517 -0.365378 0.193541 + outer loop + vertex 880.418 298.861 93.6401 + vertex 884.006 303.902 86.2771 + vertex 882.999 305.288 93.6321 + endloop + endfacet + facet normal 0.903895 -0.376234 0.203521 + outer loop + vertex 882.339 295.877 79.052 + vertex 885.094 302.49 79.0435 + vertex 881.341 297.394 86.2908 + endloop + endfacet + facet normal 0.905235 -0.370306 0.208384 + outer loop + vertex 881.341 297.394 86.2908 + vertex 885.094 302.49 79.0435 + vertex 884.006 303.902 86.2771 + endloop + endfacet + facet normal 0.898651 -0.380053 0.219055 + outer loop + vertex 883.409 294.301 71.9291 + vertex 886.258 301.046 71.942 + vertex 882.339 295.877 79.052 + endloop + endfacet + facet normal 0.899825 -0.374513 0.22373 + outer loop + vertex 882.339 295.877 79.052 + vertex 886.258 301.046 71.942 + vertex 885.094 302.49 79.0435 + endloop + endfacet + facet normal 0.893613 -0.384422 0.231677 + outer loop + vertex 884.458 292.644 65.1334 + vertex 887.414 299.542 65.1778 + vertex 883.409 294.301 71.9291 + endloop + endfacet + facet normal 0.894768 -0.378447 0.237 + outer loop + vertex 883.409 294.301 71.9291 + vertex 887.414 299.542 65.1778 + vertex 886.258 301.046 71.942 + endloop + endfacet + facet normal 0.889391 -0.3883 0.241262 + outer loop + vertex 885.274 290.819 59.1881 + vertex 888.401 297.957 59.1484 + vertex 884.458 292.644 65.1334 + endloop + endfacet + facet normal 0.890233 -0.383069 0.246461 + outer loop + vertex 884.458 292.644 65.1334 + vertex 888.401 297.957 59.1484 + vertex 887.414 299.542 65.1778 + endloop + endfacet + facet normal 0.883694 -0.398315 0.245823 + outer loop + vertex 885.417 288.697 55.2341 + vertex 888.972 295.893 54.1165 + vertex 885.274 290.819 59.1881 + endloop + endfacet + facet normal 0.885256 -0.38639 0.258892 + outer loop + vertex 885.274 290.819 59.1881 + vertex 888.972 295.893 54.1165 + vertex 888.401 297.957 59.1484 + endloop + endfacet + facet normal 0.861489 -0.398088 0.315219 + outer loop + vertex 886.684 287.66 49.9361 + vertex 889.877 294.63 50.0102 + vertex 886.961 289.81 51.8948 + endloop + endfacet + facet normal 0.848808 -0.363579 0.383843 + outer loop + vertex 886.961 289.81 51.8948 + vertex 889.877 294.63 50.0102 + vertex 890.406 297.007 51.0943 + endloop + endfacet + facet normal 0.867857 -0.331418 -0.370116 + outer loop + vertex 892.327 297.003 288.135 + vertex 895.061 304.194 288.108 + vertex 893.778 297.196 291.365 + endloop + endfacet + facet normal 0.877518 -0.325031 -0.352586 + outer loop + vertex 893.778 297.196 291.365 + vertex 895.061 304.194 288.108 + vertex 896.343 304.133 291.352 + endloop + endfacet + facet normal 0.884504 -0.337557 -0.322037 + outer loop + vertex 891.031 297.913 283.623 + vertex 893.769 305.108 283.6 + vertex 892.327 297.003 288.135 + endloop + endfacet + facet normal 0.884495 -0.337565 -0.322054 + outer loop + vertex 892.327 297.003 288.135 + vertex 893.769 305.108 283.6 + vertex 895.061 304.194 288.108 + endloop + endfacet + facet normal 0.894605 -0.336769 -0.293714 + outer loop + vertex 889.713 299.386 277.918 + vertex 892.386 306.506 277.896 + vertex 891.031 297.913 283.623 + endloop + endfacet + facet normal 0.89142 -0.340115 -0.299487 + outer loop + vertex 891.031 297.913 283.623 + vertex 892.386 306.506 277.896 + vertex 893.769 305.108 283.6 + endloop + endfacet + facet normal 0.902211 -0.333164 -0.273893 + outer loop + vertex 888.327 301.024 271.362 + vertex 890.914 308.043 271.344 + vertex 889.713 299.386 277.918 + endloop + endfacet + facet normal 0.898165 -0.338067 -0.281089 + outer loop + vertex 889.713 299.386 277.918 + vertex 890.914 308.043 271.344 + vertex 892.386 306.506 277.896 + endloop + endfacet + facet normal 0.908694 -0.328188 -0.258009 + outer loop + vertex 886.898 302.61 264.311 + vertex 889.392 309.523 264.301 + vertex 888.327 301.024 271.362 + endloop + endfacet + facet normal 0.9044 -0.33395 -0.26559 + outer loop + vertex 888.327 301.024 271.362 + vertex 889.392 309.523 264.301 + vertex 890.914 308.043 271.344 + endloop + endfacet + facet normal 0.915597 -0.323133 -0.239306 + outer loop + vertex 885.51 304.076 257.022 + vertex 887.915 310.891 257.02 + vertex 886.898 302.61 264.311 + endloop + endfacet + facet normal 0.911464 -0.32917 -0.246739 + outer loop + vertex 886.898 302.61 264.311 + vertex 887.915 310.891 257.02 + vertex 889.392 309.523 264.301 + endloop + endfacet + facet normal 0.92225 -0.31762 -0.22039 + outer loop + vertex 884.204 305.44 249.59 + vertex 886.523 312.168 249.596 + vertex 885.51 304.076 257.022 + endloop + endfacet + facet normal 0.918173 -0.324039 -0.22794 + outer loop + vertex 885.51 304.076 257.022 + vertex 886.523 312.168 249.596 + vertex 887.915 310.891 257.02 + endloop + endfacet + facet normal 0.928827 -0.312116 -0.19966 + outer loop + vertex 883.013 306.719 242.051 + vertex 885.251 313.37 242.063 + vertex 884.204 305.44 249.59 + endloop + endfacet + facet normal 0.925015 -0.318585 -0.207005 + outer loop + vertex 884.204 305.44 249.59 + vertex 885.251 313.37 242.063 + vertex 886.523 312.168 249.596 + endloop + endfacet + facet normal 0.93457 -0.306829 -0.180096 + outer loop + vertex 881.934 307.907 234.425 + vertex 884.098 314.49 234.44 + vertex 883.013 306.719 242.051 + endloop + endfacet + facet normal 0.931217 -0.312944 -0.186817 + outer loop + vertex 883.013 306.719 242.051 + vertex 884.098 314.49 234.44 + vertex 885.251 313.37 242.063 + endloop + endfacet + facet normal 0.940166 -0.301046 -0.159562 + outer loop + vertex 880.972 308.981 226.73 + vertex 883.064 315.506 226.744 + vertex 881.934 307.907 234.425 + endloop + endfacet + facet normal 0.936828 -0.307602 -0.166539 + outer loop + vertex 881.934 307.907 234.425 + vertex 883.064 315.506 226.744 + vertex 884.098 314.49 234.44 + endloop + endfacet + facet normal 0.945121 -0.29592 -0.138484 + outer loop + vertex 880.13 309.924 218.967 + vertex 882.159 316.398 218.981 + vertex 880.972 308.981 226.73 + endloop + endfacet + facet normal 0.94236 -0.301782 -0.144518 + outer loop + vertex 880.972 308.981 226.73 + vertex 882.159 316.398 218.981 + vertex 883.064 315.506 226.744 + endloop + endfacet + facet normal 0.949306 -0.291812 -0.116894 + outer loop + vertex 879.411 310.727 211.129 + vertex 881.39 317.158 211.142 + vertex 880.13 309.924 218.967 + endloop + endfacet + facet normal 0.947216 -0.296612 -0.121669 + outer loop + vertex 880.13 309.924 218.967 + vertex 881.39 317.158 211.142 + vertex 882.159 316.398 218.981 + endloop + endfacet + facet normal 0.952972 -0.287774 -0.0950304 + outer loop + vertex 878.821 311.385 203.215 + vertex 880.753 317.78 203.226 + vertex 879.411 310.727 211.129 + endloop + endfacet + facet normal 0.951108 -0.292401 -0.0994762 + outer loop + vertex 879.411 310.727 211.129 + vertex 880.753 317.78 203.226 + vertex 881.39 317.158 211.142 + endloop + endfacet + facet normal 0.955829 -0.2847 -0.0730565 + outer loop + vertex 878.363 311.893 195.246 + vertex 880.261 318.262 195.255 + vertex 878.821 311.385 203.215 + endloop + endfacet + facet normal 0.954499 -0.288267 -0.0763779 + outer loop + vertex 878.821 311.385 203.215 + vertex 880.261 318.262 195.255 + vertex 880.753 317.78 203.226 + endloop + endfacet + facet normal 0.957825 -0.282459 -0.0528029 + outer loop + vertex 878.03 312.253 187.269 + vertex 879.902 318.601 187.274 + vertex 878.363 311.893 195.246 + endloop + endfacet + facet normal 0.956924 -0.285051 -0.0551571 + outer loop + vertex 878.363 311.893 195.246 + vertex 879.902 318.601 187.274 + vertex 880.261 318.262 195.255 + endloop + endfacet + facet normal 0.959121 -0.281081 -0.0328617 + outer loop + vertex 877.82 312.465 179.336 + vertex 879.677 318.801 179.335 + vertex 878.03 312.253 187.269 + endloop + endfacet + facet normal 0.958595 -0.2827 -0.034307 + outer loop + vertex 878.03 312.253 187.269 + vertex 879.677 318.801 179.335 + vertex 879.902 318.601 187.274 + endloop + endfacet + facet normal 0.959787 -0.280445 -0.0126367 + outer loop + vertex 877.735 312.528 171.468 + vertex 879.585 318.86 171.463 + vertex 877.82 312.465 179.336 + endloop + endfacet + facet normal 0.959555 -0.281206 -0.0133069 + outer loop + vertex 877.82 312.465 179.336 + vertex 879.585 318.86 171.463 + vertex 879.677 318.801 179.335 + endloop + endfacet + facet normal 0.960022 -0.27984 0.0068367 + outer loop + vertex 877.767 312.446 163.648 + vertex 879.614 318.784 163.64 + vertex 877.735 312.528 171.468 + endloop + endfacet + facet normal 0.959849 -0.280447 0.00631011 + outer loop + vertex 877.735 312.528 171.468 + vertex 879.614 318.784 163.64 + vertex 879.585 318.86 171.463 + endloop + endfacet + facet normal 0.959378 -0.280871 0.0265768 + outer loop + vertex 877.917 312.22 155.829 + vertex 879.776 318.571 155.819 + vertex 877.767 312.446 163.648 + endloop + endfacet + facet normal 0.959687 -0.279716 0.0275595 + outer loop + vertex 877.767 312.446 163.648 + vertex 879.776 318.571 155.819 + vertex 879.614 318.784 163.64 + endloop + endfacet + facet normal 0.958269 -0.282192 0.0456921 + outer loop + vertex 878.183 311.851 147.974 + vertex 880.059 318.221 147.965 + vertex 877.917 312.22 155.829 + endloop + endfacet + facet normal 0.958664 -0.280632 0.0469899 + outer loop + vertex 877.917 312.22 155.829 + vertex 880.059 318.221 147.965 + vertex 879.776 318.571 155.819 + endloop + endfacet + facet normal 0.956656 -0.283902 0.0648797 + outer loop + vertex 878.564 311.335 140.088 + vertex 880.463 317.732 140.078 + vertex 878.183 311.851 147.974 + endloop + endfacet + facet normal 0.957152 -0.281832 0.0665647 + outer loop + vertex 878.183 311.851 147.974 + vertex 880.463 317.732 140.078 + vertex 880.059 318.221 147.965 + endloop + endfacet + facet normal 0.95436 -0.286529 0.0842553 + outer loop + vertex 879.061 310.67 132.199 + vertex 880.994 317.103 132.19 + vertex 878.564 311.335 140.088 + endloop + endfacet + facet normal 0.95507 -0.283399 0.0867599 + outer loop + vertex 878.564 311.335 140.088 + vertex 880.994 317.103 132.19 + vertex 880.463 317.732 140.078 + endloop + endfacet + facet normal 0.951571 -0.28967 0.102972 + outer loop + vertex 879.666 309.864 124.341 + vertex 881.638 316.34 124.334 + vertex 879.061 310.67 132.199 + endloop + endfacet + facet normal 0.952383 -0.285904 0.105953 + outer loop + vertex 879.061 310.67 132.199 + vertex 881.638 316.34 124.334 + vertex 880.994 317.103 132.19 + endloop + endfacet + facet normal 0.948329 -0.292903 0.121982 + outer loop + vertex 880.377 308.913 116.529 + vertex 882.395 315.445 116.527 + vertex 879.666 309.864 124.341 + endloop + endfacet + facet normal 0.949145 -0.288908 0.125121 + outer loop + vertex 879.666 309.864 124.341 + vertex 882.395 315.445 116.527 + vertex 881.638 316.34 124.334 + endloop + endfacet + facet normal 0.944705 -0.296606 0.139846 + outer loop + vertex 881.182 307.823 108.782 + vertex 883.253 314.421 108.785 + vertex 880.377 308.913 116.529 + endloop + endfacet + facet normal 0.945589 -0.292049 0.143416 + outer loop + vertex 880.377 308.913 116.529 + vertex 883.253 314.421 108.785 + vertex 882.395 315.445 116.527 + endloop + endfacet + facet normal 0.940691 -0.301337 0.155875 + outer loop + vertex 882.059 306.607 101.136 + vertex 884.194 313.275 101.142 + vertex 881.182 307.823 108.782 + endloop + endfacet + facet normal 0.941737 -0.295684 0.160322 + outer loop + vertex 881.182 307.823 108.782 + vertex 884.194 313.275 101.142 + vertex 883.253 314.421 108.785 + endloop + endfacet + facet normal 0.936393 -0.306414 0.171109 + outer loop + vertex 882.999 305.288 93.6321 + vertex 885.204 312.03 93.6399 + vertex 882.059 306.607 101.136 + endloop + endfacet + facet normal 0.937466 -0.300323 0.175966 + outer loop + vertex 882.059 306.607 101.136 + vertex 885.204 312.03 93.6399 + vertex 884.194 313.275 101.142 + endloop + endfacet + facet normal 0.932146 -0.310553 0.186175 + outer loop + vertex 884.006 303.902 86.2771 + vertex 886.278 310.729 86.2909 + vertex 882.999 305.288 93.6321 + endloop + endfacet + facet normal 0.933011 -0.30533 0.190434 + outer loop + vertex 882.999 305.288 93.6321 + vertex 886.278 310.729 86.2909 + vertex 885.204 312.03 93.6399 + endloop + endfacet + facet normal 0.927624 -0.314868 0.200929 + outer loop + vertex 885.094 302.49 79.0435 + vertex 887.437 309.408 79.0649 + vertex 884.006 303.902 86.2771 + endloop + endfacet + facet normal 0.928466 -0.309368 0.205529 + outer loop + vertex 884.006 303.902 86.2771 + vertex 887.437 309.408 79.0649 + vertex 886.278 310.729 86.2909 + endloop + endfacet + facet normal 0.923044 -0.318263 0.216098 + outer loop + vertex 886.258 301.046 71.942 + vertex 888.67 308.066 71.982 + vertex 885.094 302.49 79.0435 + endloop + endfacet + facet normal 0.923693 -0.313596 0.220113 + outer loop + vertex 885.094 302.49 79.0435 + vertex 888.67 308.066 71.982 + vertex 887.437 309.408 79.0649 + endloop + endfacet + facet normal 0.918188 -0.323416 0.228765 + outer loop + vertex 887.414 299.542 65.1778 + vertex 889.901 306.653 65.2473 + vertex 886.258 301.046 71.942 + endloop + endfacet + facet normal 0.918966 -0.316968 0.234589 + outer loop + vertex 886.258 301.046 71.942 + vertex 889.901 306.653 65.2473 + vertex 888.67 308.066 71.982 + endloop + endfacet + facet normal 0.913771 -0.330325 0.23645 + outer loop + vertex 888.401 297.957 59.1484 + vertex 890.941 305.155 59.39 + vertex 887.414 299.542 65.1778 + endloop + endfacet + facet normal 0.914476 -0.322274 0.244689 + outer loop + vertex 887.414 299.542 65.1778 + vertex 890.941 305.155 59.39 + vertex 889.901 306.653 65.2473 + endloop + endfacet + facet normal 0.911951 -0.332822 0.239948 + outer loop + vertex 888.972 295.893 54.1165 + vertex 891.789 304.065 54.7444 + vertex 888.401 297.957 59.1484 + endloop + endfacet + facet normal 0.91194 -0.329931 0.243948 + outer loop + vertex 888.401 297.957 59.1484 + vertex 891.789 304.065 54.7444 + vertex 890.941 305.155 59.39 + endloop + endfacet + facet normal 0.89143 -0.336448 0.303572 + outer loop + vertex 889.877 294.63 50.0102 + vertex 892.513 301.621 50.0203 + vertex 890.406 297.007 51.0943 + endloop + endfacet + facet normal 0.875913 -0.314948 0.365492 + outer loop + vertex 890.406 297.007 51.0943 + vertex 892.513 301.621 50.0203 + vertex 892.445 303.258 51.5919 + endloop + endfacet + facet normal 0.894357 -0.268035 -0.358166 + outer loop + vertex 895.061 304.194 288.108 + vertex 897.27 311.569 288.103 + vertex 896.343 304.133 291.352 + endloop + endfacet + facet normal 0.899552 -0.264185 -0.347869 + outer loop + vertex 896.343 304.133 291.352 + vertex 897.27 311.569 288.103 + vertex 898.613 311.666 291.503 + endloop + endfacet + facet normal 0.908587 -0.273243 -0.315923 + outer loop + vertex 893.769 305.108 283.6 + vertex 895.975 312.457 283.588 + vertex 895.061 304.194 288.108 + endloop + endfacet + facet normal 0.909338 -0.272496 -0.314405 + outer loop + vertex 895.061 304.194 288.108 + vertex 895.975 312.457 283.588 + vertex 897.27 311.569 288.103 + endloop + endfacet + facet normal 0.917634 -0.272518 -0.289276 + outer loop + vertex 892.386 306.506 277.896 + vertex 894.549 313.797 277.888 + vertex 893.769 305.108 283.6 + endloop + endfacet + facet normal 0.915398 -0.275252 -0.29374 + outer loop + vertex 893.769 305.108 283.6 + vertex 894.549 313.797 277.888 + vertex 895.975 312.457 283.588 + endloop + endfacet + facet normal 0.924172 -0.269378 -0.270816 + outer loop + vertex 890.914 308.043 271.344 + vertex 893.013 315.245 271.344 + vertex 892.386 306.506 277.896 + endloop + endfacet + facet normal 0.921201 -0.273563 -0.276682 + outer loop + vertex 892.386 306.506 277.896 + vertex 893.013 315.245 271.344 + vertex 894.549 313.797 277.888 + endloop + endfacet + facet normal 0.929482 -0.265052 -0.256537 + outer loop + vertex 889.392 309.523 264.301 + vertex 891.419 316.626 264.305 + vertex 890.914 308.043 271.344 + endloop + endfacet + facet normal 0.926303 -0.269999 -0.262797 + outer loop + vertex 890.914 308.043 271.344 + vertex 891.419 316.626 264.305 + vertex 893.013 315.245 271.344 + endloop + endfacet + facet normal 0.935594 -0.260196 -0.238667 + outer loop + vertex 887.915 310.891 257.02 + vertex 889.867 317.902 257.03 + vertex 889.392 309.523 264.301 + endloop + endfacet + facet normal 0.932256 -0.26585 -0.245401 + outer loop + vertex 889.392 309.523 264.301 + vertex 889.867 317.902 257.03 + vertex 891.419 316.626 264.305 + endloop + endfacet + facet normal 0.941018 -0.256537 -0.220621 + outer loop + vertex 886.523 312.168 249.596 + vertex 888.415 319.095 249.614 + vertex 887.915 310.891 257.02 + endloop + endfacet + facet normal 0.938555 -0.261038 -0.225773 + outer loop + vertex 887.915 310.891 257.02 + vertex 888.415 319.095 249.614 + vertex 889.867 317.902 257.03 + endloop + endfacet + facet normal 0.94712 -0.250971 -0.199942 + outer loop + vertex 885.251 313.37 242.063 + vertex 887.071 320.224 242.083 + vertex 886.523 312.168 249.596 + endloop + endfacet + facet normal 0.94388 -0.257355 -0.207025 + outer loop + vertex 886.523 312.168 249.596 + vertex 887.071 320.224 242.083 + vertex 888.415 319.095 249.614 + endloop + endfacet + facet normal 0.952503 -0.24554 -0.180132 + outer loop + vertex 884.098 314.49 234.44 + vertex 885.852 321.278 234.461 + vertex 885.251 313.37 242.063 + endloop + endfacet + facet normal 0.949625 -0.251676 -0.186742 + outer loop + vertex 885.251 313.37 242.063 + vertex 885.852 321.278 234.461 + vertex 887.071 320.224 242.083 + endloop + endfacet + facet normal 0.95707 -0.241351 -0.160521 + outer loop + vertex 883.064 315.506 226.744 + vertex 884.764 322.235 226.765 + vertex 884.098 314.49 234.44 + endloop + endfacet + facet normal 0.95496 -0.246219 -0.165615 + outer loop + vertex 884.098 314.49 234.44 + vertex 884.764 322.235 226.765 + vertex 885.852 321.278 234.461 + endloop + endfacet + facet normal 0.961658 -0.236278 -0.139238 + outer loop + vertex 882.159 316.398 218.981 + vertex 883.802 323.074 218.998 + vertex 883.064 315.506 226.744 + endloop + endfacet + facet normal 0.95938 -0.241984 -0.145029 + outer loop + vertex 883.064 315.506 226.744 + vertex 883.802 323.074 218.998 + vertex 884.764 322.235 226.765 + endloop + endfacet + facet normal 0.965747 -0.231521 -0.117179 + outer loop + vertex 881.39 317.158 211.142 + vertex 882.981 323.789 211.156 + vertex 882.159 316.398 218.981 + endloop + endfacet + facet normal 0.963803 -0.236851 -0.122417 + outer loop + vertex 882.159 316.398 218.981 + vertex 882.981 323.789 211.156 + vertex 883.802 323.074 218.998 + endloop + endfacet + facet normal 0.968721 -0.228872 -0.095899 + outer loop + vertex 880.753 317.78 203.226 + vertex 882.312 324.375 203.238 + vertex 881.39 317.158 211.142 + endloop + endfacet + facet normal 0.967671 -0.23202 -0.0988964 + outer loop + vertex 881.39 317.158 211.142 + vertex 882.312 324.375 203.238 + vertex 882.981 323.789 211.156 + endloop + endfacet + facet normal 0.971517 -0.225242 -0.0736212 + outer loop + vertex 880.261 318.262 195.255 + vertex 881.783 324.827 195.262 + vertex 880.753 317.78 203.226 + endloop + endfacet + facet normal 0.970284 -0.229274 -0.0773487 + outer loop + vertex 880.753 317.78 203.226 + vertex 881.783 324.827 195.262 + vertex 882.312 324.375 203.238 + endloop + endfacet + facet normal 0.97337 -0.222969 -0.0532537 + outer loop + vertex 879.902 318.601 187.274 + vertex 881.401 325.147 187.276 + vertex 880.261 318.262 195.255 + endloop + endfacet + facet normal 0.972652 -0.225523 -0.0555602 + outer loop + vertex 880.261 318.262 195.255 + vertex 881.401 325.147 187.276 + vertex 881.783 324.827 195.262 + endloop + endfacet + facet normal 0.974505 -0.221892 -0.033232 + outer loop + vertex 879.677 318.801 179.335 + vertex 881.164 325.334 179.333 + vertex 879.902 318.601 187.274 + endloop + endfacet + facet normal 0.974176 -0.22316 -0.0343597 + outer loop + vertex 879.902 318.601 187.274 + vertex 881.164 325.334 179.333 + vertex 881.401 325.147 187.276 + endloop + endfacet + facet normal 0.975287 -0.220558 -0.0130335 + outer loop + vertex 879.585 318.86 171.463 + vertex 881.062 325.391 171.458 + vertex 879.677 318.801 179.335 + endloop + endfacet + facet normal 0.974945 -0.221985 -0.0142872 + outer loop + vertex 879.677 318.801 179.335 + vertex 881.062 325.391 171.458 + vertex 881.164 325.334 179.333 + endloop + endfacet + facet normal 0.975157 -0.22144 0.00579611 + outer loop + vertex 879.614 318.784 163.64 + vertex 881.098 325.319 163.633 + vertex 879.585 318.86 171.463 + endloop + endfacet + facet normal 0.975352 -0.220558 0.00656161 + outer loop + vertex 879.585 318.86 171.463 + vertex 881.098 325.319 163.633 + vertex 881.062 325.391 171.458 + endloop + endfacet + facet normal 0.974845 -0.22133 0.026282 + outer loop + vertex 879.776 318.571 155.819 + vertex 881.263 325.119 155.812 + vertex 879.614 318.784 163.64 + endloop + endfacet + facet normal 0.974841 -0.221347 0.0262678 + outer loop + vertex 879.614 318.784 163.64 + vertex 881.263 325.119 155.812 + vertex 881.098 325.319 163.633 + endloop + endfacet + facet normal 0.973931 -0.222349 0.0449401 + outer loop + vertex 880.059 318.221 147.965 + vertex 881.559 324.79 147.958 + vertex 879.776 318.571 155.819 + endloop + endfacet + facet normal 0.974157 -0.221151 0.0459387 + outer loop + vertex 879.776 318.571 155.819 + vertex 881.559 324.79 147.958 + vertex 881.263 325.119 155.812 + endloop + endfacet + facet normal 0.972414 -0.224371 0.0637862 + outer loop + vertex 880.463 317.732 140.078 + vertex 881.986 324.329 140.071 + vertex 880.059 318.221 147.965 + endloop + endfacet + facet normal 0.972817 -0.222071 0.0656643 + outer loop + vertex 880.059 318.221 147.965 + vertex 881.986 324.329 140.071 + vertex 881.559 324.79 147.958 + endloop + endfacet + facet normal 0.970479 -0.226363 0.0832512 + outer loop + vertex 880.994 317.103 132.19 + vertex 882.542 323.738 132.182 + vertex 880.463 317.732 140.078 + endloop + endfacet + facet normal 0.970864 -0.223989 0.0851578 + outer loop + vertex 880.463 317.732 140.078 + vertex 882.542 323.738 132.182 + vertex 881.986 324.329 140.071 + endloop + endfacet + facet normal 0.968172 -0.228697 0.101691 + outer loop + vertex 881.638 316.34 124.334 + vertex 883.217 323.02 124.326 + vertex 880.994 317.103 132.19 + endloop + endfacet + facet normal 0.968593 -0.225898 0.103916 + outer loop + vertex 880.994 317.103 132.19 + vertex 883.217 323.02 124.326 + vertex 882.542 323.738 132.182 + endloop + endfacet + facet normal 0.965226 -0.23216 0.120171 + outer loop + vertex 882.395 315.445 116.527 + vertex 884.015 322.178 116.52 + vertex 881.638 316.34 124.334 + endloop + endfacet + facet normal 0.965788 -0.228109 0.123368 + outer loop + vertex 881.638 316.34 124.334 + vertex 884.015 322.178 116.52 + vertex 883.217 323.02 124.326 + endloop + endfacet + facet normal 0.962164 -0.2351 0.137722 + outer loop + vertex 883.253 314.421 108.785 + vertex 884.915 321.219 108.781 + vertex 882.395 315.445 116.527 + endloop + endfacet + facet normal 0.962626 -0.231512 0.140547 + outer loop + vertex 882.395 315.445 116.527 + vertex 884.915 321.219 108.781 + vertex 884.015 322.178 116.52 + endloop + endfacet + facet normal 0.958724 -0.23907 0.153927 + outer loop + vertex 884.194 313.275 101.142 + vertex 885.908 320.146 101.141 + vertex 883.253 314.421 108.785 + endloop + endfacet + facet normal 0.95928 -0.234382 0.157631 + outer loop + vertex 883.253 314.421 108.785 + vertex 885.908 320.146 101.141 + vertex 884.915 321.219 108.781 + endloop + endfacet + facet normal 0.955325 -0.242616 0.168793 + outer loop + vertex 885.204 312.03 93.6399 + vertex 886.967 318.976 93.6466 + vertex 884.194 313.275 101.142 + endloop + endfacet + facet normal 0.955791 -0.238336 0.17222 + outer loop + vertex 884.194 313.275 101.142 + vertex 886.967 318.976 93.6466 + vertex 885.908 320.146 101.141 + endloop + endfacet + facet normal 0.951309 -0.248058 0.182971 + outer loop + vertex 886.278 310.729 86.2909 + vertex 888.105 317.745 86.3031 + vertex 885.204 312.03 93.6399 + endloop + endfacet + facet normal 0.951925 -0.241771 0.188111 + outer loop + vertex 885.204 312.03 93.6399 + vertex 888.105 317.745 86.3031 + vertex 886.967 318.976 93.6466 + endloop + endfacet + facet normal 0.947463 -0.251256 0.19795 + outer loop + vertex 887.437 309.408 79.0649 + vertex 889.314 316.506 79.0899 + vertex 886.278 310.729 86.2909 + endloop + endfacet + facet normal 0.947815 -0.24718 0.201368 + outer loop + vertex 886.278 310.729 86.2909 + vertex 889.314 316.506 79.0899 + vertex 888.105 317.745 86.3031 + endloop + endfacet + facet normal 0.94371 -0.253695 0.21225 + outer loop + vertex 888.67 308.066 71.982 + vertex 890.594 315.257 72.0214 + vertex 887.437 309.408 79.0649 + endloop + endfacet + facet normal 0.943948 -0.250386 0.215104 + outer loop + vertex 887.437 309.408 79.0649 + vertex 890.594 315.257 72.0214 + vertex 889.314 316.506 79.0899 + endloop + endfacet + facet normal 0.939751 -0.256727 0.225743 + outer loop + vertex 889.901 306.653 65.2473 + vertex 891.875 313.918 65.2935 + vertex 888.67 308.066 71.982 + endloop + endfacet + facet normal 0.93996 -0.252785 0.229292 + outer loop + vertex 888.67 308.066 71.982 + vertex 891.875 313.918 65.2935 + vertex 890.594 315.257 72.0214 + endloop + endfacet + facet normal 0.936462 -0.262034 0.233187 + outer loop + vertex 890.941 305.155 59.39 + vertex 892.955 312.377 59.4166 + vertex 889.901 306.653 65.2473 + endloop + endfacet + facet normal 0.936618 -0.255961 0.23923 + outer loop + vertex 889.901 306.653 65.2473 + vertex 892.955 312.377 59.4166 + vertex 891.875 313.918 65.2935 + endloop + endfacet + facet normal 0.932241 -0.275283 0.234832 + outer loop + vertex 891.789 304.065 54.7444 + vertex 893.464 310.342 55.4519 + vertex 890.941 305.155 59.39 + endloop + endfacet + facet normal 0.931524 -0.260732 0.253537 + outer loop + vertex 890.941 305.155 59.39 + vertex 893.464 310.342 55.4519 + vertex 892.955 312.377 59.4166 + endloop + endfacet + facet normal 0.907574 -0.270826 0.320878 + outer loop + vertex 892.513 301.621 50.0203 + vertex 894.748 309.274 50.1575 + vertex 892.445 303.258 51.5919 + endloop + endfacet + facet normal 0.8947 -0.254962 0.366752 + outer loop + vertex 892.445 303.258 51.5919 + vertex 894.748 309.274 50.1575 + vertex 894.647 311.726 52.1077 + endloop + endfacet + facet normal 0.912483 -0.203871 -0.354699 + outer loop + vertex 897.27 311.569 288.103 + vertex 898.95 319.111 288.091 + vertex 898.613 311.666 291.503 + endloop + endfacet + facet normal 0.923267 -0.193812 -0.331685 + outer loop + vertex 898.613 311.666 291.503 + vertex 898.95 319.111 288.091 + vertex 900.176 319.469 291.294 + endloop + endfacet + facet normal 0.928669 -0.207805 -0.307231 + outer loop + vertex 895.975 312.457 283.588 + vertex 897.637 319.903 283.577 + vertex 897.27 311.569 288.103 + endloop + endfacet + facet normal 0.928959 -0.207466 -0.306584 + outer loop + vertex 897.27 311.569 288.103 + vertex 897.637 319.903 283.577 + vertex 898.95 319.111 288.091 + endloop + endfacet + facet normal 0.936598 -0.206721 -0.282932 + outer loop + vertex 894.549 313.797 277.888 + vertex 896.175 321.173 277.882 + vertex 895.975 312.457 283.588 + endloop + endfacet + facet normal 0.9349 -0.209165 -0.286725 + outer loop + vertex 895.975 312.457 283.588 + vertex 896.175 321.173 277.882 + vertex 897.637 319.903 283.577 + endloop + endfacet + facet normal 0.942193 -0.203594 -0.266125 + outer loop + vertex 893.013 315.245 271.344 + vertex 894.588 322.538 271.341 + vertex 894.549 313.797 277.888 + endloop + endfacet + facet normal 0.939885 -0.207436 -0.271268 + outer loop + vertex 894.549 313.797 277.888 + vertex 894.588 322.538 271.341 + vertex 896.175 321.173 277.882 + endloop + endfacet + facet normal 0.94643 -0.199891 -0.253603 + outer loop + vertex 891.419 316.626 264.305 + vertex 892.94 323.826 264.306 + vertex 893.013 315.245 271.344 + endloop + endfacet + facet normal 0.944189 -0.204022 -0.258615 + outer loop + vertex 893.013 315.245 271.344 + vertex 892.94 323.826 264.306 + vertex 894.588 322.538 271.341 + endloop + endfacet + facet normal 0.95145 -0.196082 -0.237264 + outer loop + vertex 889.867 317.902 257.03 + vertex 891.334 325.011 257.035 + vertex 891.419 316.626 264.305 + endloop + endfacet + facet normal 0.949255 -0.200489 -0.24232 + outer loop + vertex 891.419 316.626 264.305 + vertex 891.334 325.011 257.035 + vertex 892.94 323.826 264.306 + endloop + endfacet + facet normal 0.956839 -0.191923 -0.21823 + outer loop + vertex 888.415 319.095 249.614 + vertex 889.827 326.123 249.621 + vertex 889.867 317.902 257.03 + endloop + endfacet + facet normal 0.954624 -0.196746 -0.22357 + outer loop + vertex 889.867 317.902 257.03 + vertex 889.827 326.123 249.621 + vertex 891.334 325.011 257.035 + endloop + endfacet + facet normal 0.961685 -0.187757 -0.199773 + outer loop + vertex 887.071 320.224 242.083 + vertex 888.431 327.177 242.093 + vertex 888.415 319.095 249.614 + endloop + endfacet + facet normal 0.95967 -0.192505 -0.204879 + outer loop + vertex 888.415 319.095 249.614 + vertex 888.431 327.177 242.093 + vertex 889.827 326.123 249.621 + endloop + endfacet + facet normal 0.966439 -0.18331 -0.179979 + outer loop + vertex 885.852 321.278 234.461 + vertex 887.16 328.165 234.47 + vertex 887.071 320.224 242.083 + endloop + endfacet + facet normal 0.964481 -0.188324 -0.185232 + outer loop + vertex 887.071 320.224 242.083 + vertex 887.16 328.165 234.47 + vertex 888.431 327.177 242.093 + endloop + endfacet + facet normal 0.971017 -0.178085 -0.159413 + outer loop + vertex 884.764 322.235 226.765 + vertex 886.017 329.06 226.772 + vertex 885.852 321.278 234.461 + endloop + endfacet + facet normal 0.968971 -0.183811 -0.165253 + outer loop + vertex 885.852 321.278 234.461 + vertex 886.017 329.06 226.772 + vertex 887.16 328.165 234.47 + endloop + endfacet + facet normal 0.974675 -0.174668 -0.139645 + outer loop + vertex 883.802 323.074 218.998 + vertex 885.017 329.849 219.005 + vertex 884.764 322.235 226.765 + endloop + endfacet + facet normal 0.973414 -0.178542 -0.143487 + outer loop + vertex 884.764 322.235 226.765 + vertex 885.017 329.849 219.005 + vertex 886.017 329.06 226.772 + endloop + endfacet + facet normal 0.97808 -0.171589 -0.117968 + outer loop + vertex 882.981 323.789 211.156 + vertex 884.163 330.519 211.163 + vertex 883.802 323.074 218.998 + endloop + endfacet + facet normal 0.97704 -0.175112 -0.121363 + outer loop + vertex 883.802 323.074 218.998 + vertex 884.163 330.519 211.163 + vertex 885.017 329.849 219.005 + endloop + endfacet + facet normal 0.98127 -0.167436 -0.0952623 + outer loop + vertex 882.312 324.375 203.238 + vertex 883.454 331.065 203.241 + vertex 882.981 323.789 211.156 + endloop + endfacet + facet normal 0.980068 -0.171956 -0.0994898 + outer loop + vertex 882.981 323.789 211.156 + vertex 883.454 331.065 203.241 + vertex 884.163 330.519 211.163 + endloop + endfacet + facet normal 0.98349 -0.164882 -0.074572 + outer loop + vertex 881.783 324.827 195.262 + vertex 882.9 331.488 195.263 + vertex 882.312 324.375 203.238 + endloop + endfacet + facet normal 0.982814 -0.167708 -0.077143 + outer loop + vertex 882.312 324.375 203.238 + vertex 882.9 331.488 195.263 + vertex 883.454 331.065 203.241 + endloop + endfacet + facet normal 0.985177 -0.162931 -0.0536581 + outer loop + vertex 881.401 325.147 187.276 + vertex 882.499 331.787 187.275 + vertex 881.783 324.827 195.262 + endloop + endfacet + facet normal 0.984711 -0.165089 -0.0555807 + outer loop + vertex 881.783 324.827 195.262 + vertex 882.499 331.787 187.275 + vertex 882.9 331.488 195.263 + endloop + endfacet + facet normal 0.986361 -0.161201 -0.0332596 + outer loop + vertex 881.164 325.334 179.333 + vertex 882.247 331.962 179.33 + vertex 881.401 325.147 187.276 + endloop + endfacet + facet normal 0.985998 -0.163063 -0.0348953 + outer loop + vertex 881.401 325.147 187.276 + vertex 882.247 331.962 179.33 + vertex 882.499 331.787 187.275 + endloop + endfacet + facet normal 0.98686 -0.160972 -0.0140024 + outer loop + vertex 881.062 325.391 171.458 + vertex 882.142 332.016 171.453 + vertex 881.164 325.334 179.333 + endloop + endfacet + facet normal 0.986808 -0.161266 -0.0142579 + outer loop + vertex 881.164 325.334 179.333 + vertex 882.142 332.016 171.453 + vertex 882.247 331.962 179.33 + endloop + endfacet + facet normal 0.987047 -0.160317 0.00606443 + outer loop + vertex 881.098 325.319 163.633 + vertex 882.175 331.949 163.629 + vertex 881.062 325.391 171.458 + endloop + endfacet + facet normal 0.986943 -0.160973 0.00549985 + outer loop + vertex 881.062 325.391 171.458 + vertex 882.175 331.949 163.629 + vertex 882.142 332.016 171.453 + endloop + endfacet + facet normal 0.98668 -0.160748 0.0249668 + outer loop + vertex 881.263 325.119 155.812 + vertex 882.346 331.762 155.808 + vertex 881.098 325.319 163.633 + endloop + endfacet + facet normal 0.986749 -0.160256 0.0253828 + outer loop + vertex 881.098 325.319 163.633 + vertex 882.346 331.762 155.808 + vertex 882.175 331.949 163.629 + endloop + endfacet + facet normal 0.985808 -0.162037 0.0438975 + outer loop + vertex 881.559 324.79 147.958 + vertex 882.654 331.454 147.954 + vertex 881.263 325.119 155.812 + endloop + endfacet + facet normal 0.985986 -0.160622 0.0450698 + outer loop + vertex 881.263 325.119 155.812 + vertex 882.654 331.454 147.954 + vertex 882.346 331.762 155.808 + endloop + endfacet + facet normal 0.984547 -0.163445 0.0628774 + outer loop + vertex 881.986 324.329 140.071 + vertex 883.098 331.023 140.067 + vertex 881.559 324.79 147.958 + endloop + endfacet + facet normal 0.984727 -0.161849 0.0641738 + outer loop + vertex 881.559 324.79 147.958 + vertex 883.098 331.023 140.067 + vertex 882.654 331.454 147.954 + endloop + endfacet + facet normal 0.982957 -0.164747 0.0815678 + outer loop + vertex 882.542 323.738 132.182 + vertex 883.67 330.47 132.179 + vertex 881.986 324.329 140.071 + endloop + endfacet + facet normal 0.983112 -0.163196 0.0828082 + outer loop + vertex 881.986 324.329 140.071 + vertex 883.67 330.47 132.179 + vertex 883.098 331.023 140.067 + endloop + endfacet + facet normal 0.980847 -0.16738 0.0996193 + outer loop + vertex 883.217 323.02 124.326 + vertex 884.374 329.798 124.322 + vertex 882.542 323.738 132.182 + endloop + endfacet + facet normal 0.981106 -0.164426 0.101957 + outer loop + vertex 882.542 323.738 132.182 + vertex 884.374 329.798 124.322 + vertex 883.67 330.47 132.179 + endloop + endfacet + facet normal 0.978446 -0.16925 0.118315 + outer loop + vertex 884.015 322.178 116.52 + vertex 885.198 329.012 116.516 + vertex 883.217 323.02 124.326 + endloop + endfacet + facet normal 0.978618 -0.166986 0.120095 + outer loop + vertex 883.217 323.02 124.326 + vertex 885.198 329.012 116.516 + vertex 884.374 329.798 124.322 + endloop + endfacet + facet normal 0.975799 -0.172227 0.134736 + outer loop + vertex 884.915 321.219 108.781 + vertex 886.133 328.117 108.778 + vertex 884.015 322.178 116.52 + endloop + endfacet + facet normal 0.976022 -0.168821 0.13741 + outer loop + vertex 884.015 322.178 116.52 + vertex 886.133 328.117 108.778 + vertex 885.198 329.012 116.516 + endloop + endfacet + facet normal 0.972797 -0.175574 0.151126 + outer loop + vertex 885.908 320.146 101.141 + vertex 887.166 327.116 101.138 + vertex 884.915 321.219 108.781 + endloop + endfacet + facet normal 0.973009 -0.171725 0.154158 + outer loop + vertex 884.915 321.219 108.781 + vertex 887.166 327.116 101.138 + vertex 886.133 328.117 108.778 + endloop + endfacet + facet normal 0.969775 -0.179714 0.165043 + outer loop + vertex 886.967 318.976 93.6466 + vertex 888.272 326.016 93.644 + vertex 885.908 320.146 101.141 + endloop + endfacet + facet normal 0.969988 -0.175058 0.168756 + outer loop + vertex 885.908 320.146 101.141 + vertex 888.272 326.016 93.644 + vertex 887.166 327.116 101.138 + endloop + endfacet + facet normal 0.966487 -0.182596 0.180448 + outer loop + vertex 888.105 317.745 86.3031 + vertex 889.446 324.851 86.3093 + vertex 886.967 318.976 93.6466 + endloop + endfacet + facet normal 0.966606 -0.17912 0.183272 + outer loop + vertex 886.967 318.976 93.6466 + vertex 889.446 324.851 86.3093 + vertex 888.272 326.016 93.644 + endloop + endfacet + facet normal 0.963333 -0.185923 0.19345 + outer loop + vertex 889.314 316.506 79.0899 + vertex 890.695 323.679 79.1064 + vertex 888.105 317.745 86.3031 + endloop + endfacet + facet normal 0.96342 -0.182031 0.196689 + outer loop + vertex 888.105 317.745 86.3031 + vertex 890.695 323.679 79.1064 + vertex 889.446 324.851 86.3093 + endloop + endfacet + facet normal 0.960145 -0.187834 0.206979 + outer loop + vertex 890.594 315.257 72.0214 + vertex 892.01 322.523 72.0451 + vertex 889.314 316.506 79.0899 + endloop + endfacet + facet normal 0.960166 -0.185349 0.20911 + outer loop + vertex 889.314 316.506 79.0899 + vertex 892.01 322.523 72.0451 + vertex 890.695 323.679 79.1064 + endloop + endfacet + facet normal 0.956956 -0.189396 0.219919 + outer loop + vertex 891.875 313.918 65.2935 + vertex 893.327 321.286 65.3192 + vertex 890.594 315.257 72.0214 + endloop + endfacet + facet normal 0.956935 -0.187257 0.221835 + outer loop + vertex 890.594 315.257 72.0214 + vertex 893.327 321.286 65.3192 + vertex 892.01 322.523 72.0451 + endloop + endfacet + facet normal 0.95443 -0.194469 0.226375 + outer loop + vertex 892.955 312.377 59.4166 + vertex 894.462 319.785 59.4262 + vertex 891.875 313.918 65.2935 + endloop + endfacet + facet normal 0.954232 -0.188901 0.231857 + outer loop + vertex 891.875 313.918 65.2935 + vertex 894.462 319.785 59.4262 + vertex 893.327 321.286 65.3192 + endloop + endfacet + facet normal 0.95316 -0.20126 0.225789 + outer loop + vertex 893.464 310.342 55.4519 + vertex 895.333 318.103 54.4817 + vertex 892.955 312.377 59.4166 + endloop + endfacet + facet normal 0.952697 -0.194127 0.233844 + outer loop + vertex 892.955 312.377 59.4166 + vertex 895.333 318.103 54.4817 + vertex 894.462 319.785 59.4262 + endloop + endfacet + facet normal 0.934391 -0.197462 0.296518 + outer loop + vertex 894.748 309.274 50.1575 + vertex 896.382 317.082 50.2057 + vertex 894.647 311.726 52.1077 + endloop + endfacet + facet normal 0.919776 -0.172918 0.352294 + outer loop + vertex 894.647 311.726 52.1077 + vertex 896.382 317.082 50.2057 + vertex 896.442 319.751 51.3619 + endloop + endfacet + facet normal 0.929922 -0.139415 -0.340306 + outer loop + vertex 898.95 319.111 288.091 + vertex 900.077 326.688 288.065 + vertex 900.176 319.469 291.294 + endloop + endfacet + facet normal 0.93833 -0.130325 -0.320237 + outer loop + vertex 900.176 319.469 291.294 + vertex 900.077 326.688 288.065 + vertex 901.235 327.064 291.306 + endloop + endfacet + facet normal 0.943253 -0.14342 -0.299507 + outer loop + vertex 897.637 319.903 283.577 + vertex 898.778 327.386 283.587 + vertex 898.95 319.111 288.091 + endloop + endfacet + facet normal 0.944672 -0.141454 -0.295948 + outer loop + vertex 898.95 319.111 288.091 + vertex 898.778 327.386 283.587 + vertex 900.077 326.688 288.065 + endloop + endfacet + facet normal 0.950766 -0.141507 -0.275716 + outer loop + vertex 896.175 321.173 277.882 + vertex 897.277 328.582 277.882 + vertex 897.637 319.903 283.577 + endloop + endfacet + facet normal 0.949109 -0.144339 -0.279927 + outer loop + vertex 897.637 319.903 283.577 + vertex 897.277 328.582 277.882 + vertex 898.778 327.386 283.587 + endloop + endfacet + facet normal 0.955509 -0.138175 -0.260597 + outer loop + vertex 894.588 322.538 271.341 + vertex 895.647 329.864 271.338 + vertex 896.175 321.173 277.882 + endloop + endfacet + facet normal 0.953624 -0.141932 -0.265435 + outer loop + vertex 896.175 321.173 277.882 + vertex 895.647 329.864 271.338 + vertex 897.277 328.582 277.882 + endloop + endfacet + facet normal 0.958935 -0.134992 -0.24944 + outer loop + vertex 892.94 323.826 264.306 + vertex 893.958 331.062 264.304 + vertex 894.588 322.538 271.341 + endloop + endfacet + facet normal 0.957383 -0.138443 -0.25348 + outer loop + vertex 894.588 322.538 271.341 + vertex 893.958 331.062 264.304 + vertex 895.647 329.864 271.338 + endloop + endfacet + facet normal 0.963178 -0.131999 -0.234233 + outer loop + vertex 891.334 325.011 257.035 + vertex 892.313 332.16 257.035 + vertex 892.94 323.826 264.306 + endloop + endfacet + facet normal 0.961783 -0.13539 -0.238 + outer loop + vertex 892.94 323.826 264.306 + vertex 892.313 332.16 257.035 + vertex 893.958 331.062 264.304 + endloop + endfacet + facet normal 0.967967 -0.128042 -0.215974 + outer loop + vertex 889.827 326.123 249.621 + vertex 890.761 333.19 249.621 + vertex 891.334 325.011 257.035 + endloop + endfacet + facet normal 0.966313 -0.132429 -0.220686 + outer loop + vertex 891.334 325.011 257.035 + vertex 890.761 333.19 249.621 + vertex 892.313 332.16 257.035 + endloop + endfacet + facet normal 0.972364 -0.124237 -0.197671 + outer loop + vertex 888.431 327.177 242.093 + vertex 889.324 334.169 242.092 + vertex 889.827 326.123 249.621 + endloop + endfacet + facet normal 0.970916 -0.128431 -0.202056 + outer loop + vertex 889.827 326.123 249.621 + vertex 889.324 334.169 242.092 + vertex 890.761 333.19 249.621 + endloop + endfacet + facet normal 0.97652 -0.120648 -0.178472 + outer loop + vertex 887.16 328.165 234.47 + vertex 888.016 335.09 234.471 + vertex 888.431 327.177 242.093 + endloop + endfacet + facet normal 0.975275 -0.124608 -0.182515 + outer loop + vertex 888.431 327.177 242.093 + vertex 888.016 335.09 234.471 + vertex 889.324 334.169 242.092 + endloop + endfacet + facet normal 0.9803 -0.116961 -0.159158 + outer loop + vertex 886.017 329.06 226.772 + vertex 886.836 335.925 226.772 + vertex 887.16 328.165 234.47 + endloop + endfacet + facet normal 0.979156 -0.120974 -0.163155 + outer loop + vertex 887.16 328.165 234.47 + vertex 886.836 335.925 226.772 + vertex 888.016 335.09 234.471 + endloop + endfacet + facet normal 0.983987 -0.112618 -0.138157 + outer loop + vertex 885.017 329.849 219.005 + vertex 885.796 336.656 219.004 + vertex 886.017 329.06 226.772 + endloop + endfacet + facet normal 0.982801 -0.117259 -0.142661 + outer loop + vertex 886.017 329.06 226.772 + vertex 885.796 336.656 219.004 + vertex 886.836 335.925 226.772 + endloop + endfacet + facet normal 0.987173 -0.108838 -0.116802 + outer loop + vertex 884.163 330.519 211.163 + vertex 884.907 337.278 211.159 + vertex 885.017 329.849 219.005 + endloop + endfacet + facet normal 0.986262 -0.112874 -0.120611 + outer loop + vertex 885.017 329.849 219.005 + vertex 884.907 337.278 211.159 + vertex 885.796 336.656 219.004 + endloop + endfacet + facet normal 0.989665 -0.106663 -0.0958447 + outer loop + vertex 883.454 331.065 203.241 + vertex 884.179 337.788 203.238 + vertex 884.163 330.519 211.163 + endloop + endfacet + facet normal 0.98919 -0.109051 -0.0980364 + outer loop + vertex 884.163 330.519 211.163 + vertex 884.179 337.788 203.238 + vertex 884.907 337.278 211.159 + endloop + endfacet + facet normal 0.99176 -0.104287 -0.0744037 + outer loop + vertex 882.9 331.488 195.263 + vertex 883.604 338.18 195.26 + vertex 883.454 331.065 203.241 + endloop + endfacet + facet normal 0.991315 -0.106834 -0.0766821 + outer loop + vertex 883.454 331.065 203.241 + vertex 883.604 338.18 195.26 + vertex 884.179 337.788 203.238 + endloop + endfacet + facet normal 0.99325 -0.10282 -0.0536827 + outer loop + vertex 882.499 331.787 187.275 + vertex 883.19 338.458 187.272 + vertex 882.9 331.488 195.263 + endloop + endfacet + facet normal 0.993008 -0.104411 -0.0550793 + outer loop + vertex 882.9 331.488 195.263 + vertex 883.19 338.458 187.272 + vertex 883.604 338.18 195.26 + endloop + endfacet + facet normal 0.994262 -0.101492 -0.0338025 + outer loop + vertex 882.247 331.962 179.33 + vertex 882.927 338.62 179.327 + vertex 882.499 331.787 187.275 + endloop + endfacet + facet normal 0.994075 -0.102897 -0.0350209 + outer loop + vertex 882.499 331.787 187.275 + vertex 882.927 338.62 179.327 + vertex 883.19 338.458 187.272 + endloop + endfacet + facet normal 0.994811 -0.100782 -0.0139469 + outer loop + vertex 882.142 332.016 171.453 + vertex 882.816 338.671 171.45 + vertex 882.247 331.962 179.33 + endloop + endfacet + facet normal 0.994725 -0.101531 -0.0145904 + outer loop + vertex 882.247 331.962 179.33 + vertex 882.816 338.671 171.45 + vertex 882.927 338.62 179.327 + endloop + endfacet + facet normal 0.994908 -0.100661 0.00501559 + outer loop + vertex 882.175 331.949 163.629 + vertex 882.849 338.609 163.626 + vertex 882.142 332.016 171.453 + endloop + endfacet + facet normal 0.994896 -0.100783 0.004912 + outer loop + vertex 882.142 332.016 171.453 + vertex 882.849 338.609 163.626 + vertex 882.816 338.671 171.45 + endloop + endfacet + facet normal 0.994622 -0.100718 0.0241294 + outer loop + vertex 882.346 331.762 155.808 + vertex 883.021 338.435 155.805 + vertex 882.175 331.949 163.629 + endloop + endfacet + facet normal 0.99463 -0.100626 0.0242068 + outer loop + vertex 882.175 331.949 163.629 + vertex 883.021 338.435 155.805 + vertex 882.849 338.609 163.626 + endloop + endfacet + facet normal 0.993892 -0.101604 0.0430669 + outer loop + vertex 882.654 331.454 147.954 + vertex 883.339 338.149 147.952 + vertex 882.346 331.762 155.808 + endloop + endfacet + facet normal 0.993955 -0.100644 0.0438553 + outer loop + vertex 882.346 331.762 155.808 + vertex 883.339 338.149 147.952 + vertex 883.021 338.435 155.805 + endloop + endfacet + facet normal 0.992825 -0.102615 0.0613967 + outer loop + vertex 883.098 331.023 140.067 + vertex 883.793 337.75 140.066 + vertex 882.654 331.454 147.954 + endloop + endfacet + facet normal 0.992883 -0.101496 0.0622985 + outer loop + vertex 882.654 331.454 147.954 + vertex 883.793 337.75 140.066 + vertex 883.339 338.149 147.952 + endloop + endfacet + facet normal 0.991351 -0.104572 0.0792956 + outer loop + vertex 883.67 330.47 132.179 + vertex 884.384 337.237 132.177 + vertex 883.098 331.023 140.067 + endloop + endfacet + facet normal 0.991436 -0.102468 0.0809666 + outer loop + vertex 883.098 331.023 140.067 + vertex 884.384 337.237 132.177 + vertex 883.793 337.75 140.066 + endloop + endfacet + facet normal 0.989581 -0.105761 0.0976979 + outer loop + vertex 884.374 329.798 124.322 + vertex 885.103 336.612 124.321 + vertex 883.67 330.47 132.179 + endloop + endfacet + facet normal 0.989619 -0.104385 0.0987803 + outer loop + vertex 883.67 330.47 132.179 + vertex 885.103 336.612 124.321 + vertex 884.384 337.237 132.177 + endloop + endfacet + facet normal 0.987398 -0.108572 0.115137 + outer loop + vertex 885.198 329.012 116.516 + vertex 885.954 335.882 116.513 + vertex 884.374 329.798 124.322 + endloop + endfacet + facet normal 0.987448 -0.105529 0.117518 + outer loop + vertex 884.374 329.798 124.322 + vertex 885.954 335.882 116.513 + vertex 885.103 336.612 124.321 + endloop + endfacet + facet normal 0.985038 -0.111017 0.131816 + outer loop + vertex 886.133 328.117 108.778 + vertex 886.915 335.052 108.774 + vertex 885.198 329.012 116.516 + endloop + endfacet + facet normal 0.985054 -0.108307 0.133935 + outer loop + vertex 885.198 329.012 116.516 + vertex 886.915 335.052 108.774 + vertex 885.954 335.882 116.513 + endloop + endfacet + facet normal 0.982587 -0.112696 0.147723 + outer loop + vertex 887.166 327.116 101.138 + vertex 887.97 334.125 101.137 + vertex 886.133 328.117 108.778 + endloop + endfacet + facet normal 0.982577 -0.110731 0.149266 + outer loop + vertex 886.133 328.117 108.778 + vertex 887.97 334.125 101.137 + vertex 886.915 335.052 108.774 + endloop + endfacet + facet normal 0.980127 -0.115232 0.161468 + outer loop + vertex 888.272 326.016 93.644 + vertex 889.104 333.098 93.6439 + vertex 887.166 327.116 101.138 + endloop + endfacet + facet normal 0.980083 -0.112406 0.163712 + outer loop + vertex 887.166 327.116 101.138 + vertex 889.104 333.098 93.6439 + vertex 887.97 334.125 101.137 + endloop + endfacet + facet normal 0.977404 -0.118111 0.175306 + outer loop + vertex 889.446 324.851 86.3093 + vertex 890.309 331.994 86.3113 + vertex 888.272 326.016 93.644 + endloop + endfacet + facet normal 0.977318 -0.114902 0.177898 + outer loop + vertex 888.272 326.016 93.644 + vertex 890.309 331.994 86.3113 + vertex 889.104 333.098 93.6439 + endloop + endfacet + facet normal 0.974662 -0.120282 0.188591 + outer loop + vertex 890.695 323.679 79.1064 + vertex 891.582 330.88 79.1157 + vertex 889.446 324.851 86.3093 + endloop + endfacet + facet normal 0.974565 -0.117772 0.190666 + outer loop + vertex 889.446 324.851 86.3093 + vertex 891.582 330.88 79.1157 + vertex 890.309 331.994 86.3113 + endloop + endfacet + facet normal 0.971973 -0.122022 0.200944 + outer loop + vertex 892.01 322.523 72.0451 + vertex 892.923 329.814 72.0585 + vertex 890.695 323.679 79.1064 + endloop + endfacet + facet normal 0.971864 -0.119955 0.202709 + outer loop + vertex 890.695 323.679 79.1064 + vertex 892.923 329.814 72.0585 + vertex 891.582 330.88 79.1157 + endloop + endfacet + facet normal 0.969664 -0.121333 0.212204 + outer loop + vertex 893.327 321.286 65.3192 + vertex 894.257 328.731 65.3274 + vertex 892.01 322.523 72.0451 + endloop + endfacet + facet normal 0.969694 -0.121757 0.211823 + outer loop + vertex 892.01 322.523 72.0451 + vertex 894.257 328.731 65.3274 + vertex 892.923 329.814 72.0585 + endloop + endfacet + facet normal 0.967894 -0.124829 0.218173 + outer loop + vertex 894.462 319.785 59.4262 + vertex 895.439 327.329 59.4065 + vertex 893.327 321.286 65.3192 + endloop + endfacet + facet normal 0.967528 -0.121077 0.221877 + outer loop + vertex 893.327 321.286 65.3192 + vertex 895.439 327.329 59.4065 + vertex 894.257 328.731 65.3274 + endloop + endfacet + facet normal 0.966155 -0.138849 0.217407 + outer loop + vertex 895.333 318.103 54.4817 + vertex 896.154 325.207 55.3718 + vertex 894.462 319.785 59.4262 + endloop + endfacet + facet normal 0.963791 -0.124252 0.23594 + outer loop + vertex 894.462 319.785 59.4262 + vertex 896.154 325.207 55.3718 + vertex 895.439 327.329 59.4065 + endloop + endfacet + facet normal 0.957012 -0.132839 0.257841 + outer loop + vertex 896.382 317.082 50.2057 + vertex 897.453 324.759 50.1889 + vertex 896.442 319.751 51.3619 + endloop + endfacet + facet normal 0.941246 -0.115734 0.317273 + outer loop + vertex 896.442 319.751 51.3619 + vertex 897.453 324.759 50.1889 + vertex 897.106 326.917 52.0033 + endloop + endfacet + facet normal 0.954983 0.223327 -0.195274 + outer loop + vertex 861.354 462.678 242.586 + vertex 862.627 463.772 250.067 + vertex 862.089 460.453 243.639 + endloop + endfacet + facet normal 0.953038 0.245115 -0.177868 + outer loop + vertex 860.663 459.078 234.026 + vertex 860.137 461.665 234.773 + vertex 861.392 459.449 238.442 + endloop + endfacet + facet normal 0.952604 0.248262 -0.175819 + outer loop + vertex 861.392 459.449 238.442 + vertex 860.137 461.665 234.773 + vertex 860.734 462.158 238.703 + endloop + endfacet + facet normal 0.952607 0.248261 -0.175802 + outer loop + vertex 861.392 459.449 238.442 + vertex 860.734 462.158 238.703 + vertex 862.089 460.453 243.639 + endloop + endfacet + facet normal 0.955942 0.229332 -0.183256 + outer loop + vertex 862.089 460.453 243.639 + vertex 860.734 462.158 238.703 + vertex 861.354 462.678 242.586 + endloop + endfacet + facet normal 0.961875 0.222377 -0.159198 + outer loop + vertex 859.49 458.582 226.58 + vertex 859.068 460.795 227.12 + vertex 860.035 458.823 230.213 + endloop + endfacet + facet normal 0.961175 0.228044 -0.155368 + outer loop + vertex 860.035 458.823 230.213 + vertex 859.068 460.795 227.12 + vertex 859.589 461.217 230.962 + endloop + endfacet + facet normal 0.95701 0.232796 -0.173027 + outer loop + vertex 860.035 458.823 230.213 + vertex 859.589 461.217 230.962 + vertex 860.663 459.078 234.026 + endloop + endfacet + facet normal 0.955897 0.242275 -0.166021 + outer loop + vertex 860.663 459.078 234.026 + vertex 859.589 461.217 230.962 + vertex 860.137 461.665 234.773 + endloop + endfacet + facet normal 0.96545 0.227355 -0.127345 + outer loop + vertex 858.601 457.893 219.194 + vertex 858.125 460.038 219.41 + vertex 859.004 458.291 222.956 + endloop + endfacet + facet normal 0.967458 0.214538 -0.134158 + outer loop + vertex 859.004 458.291 222.956 + vertex 858.125 460.038 219.41 + vertex 858.58 460.402 223.275 + endloop + endfacet + facet normal 0.965282 0.216022 -0.146854 + outer loop + vertex 859.004 458.291 222.956 + vertex 858.58 460.402 223.275 + vertex 859.49 458.582 226.58 + endloop + endfacet + facet normal 0.964814 0.219439 -0.144843 + outer loop + vertex 859.49 458.582 226.58 + vertex 858.58 460.402 223.275 + vertex 859.068 460.795 227.12 + endloop + endfacet + facet normal 0.966828 0.228864 -0.113421 + outer loop + vertex 857.779 457.29 211.28 + vertex 857.306 459.383 211.471 + vertex 858.178 457.563 215.235 + endloop + endfacet + facet normal 0.966674 0.22974 -0.112963 + outer loop + vertex 858.178 457.563 215.235 + vertex 857.306 459.383 211.471 + vertex 857.696 459.695 215.447 + endloop + endfacet + facet normal 0.965385 0.230376 -0.122308 + outer loop + vertex 858.178 457.563 215.235 + vertex 857.696 459.695 215.447 + vertex 858.601 457.893 219.194 + endloop + endfacet + facet normal 0.965938 0.227126 -0.124004 + outer loop + vertex 858.601 457.893 219.194 + vertex 857.696 459.695 215.447 + vertex 858.125 460.038 219.41 + endloop + endfacet + facet normal 0.969621 0.227324 -0.0903252 + outer loop + vertex 857.108 456.819 203.426 + vertex 856.644 458.86 203.587 + vertex 857.422 457.042 207.358 + endloop + endfacet + facet normal 0.96986 0.226036 -0.0909952 + outer loop + vertex 857.422 457.042 207.358 + vertex 856.644 458.86 203.587 + vertex 856.957 459.106 207.534 + endloop + endfacet + facet normal 0.968538 0.226726 -0.102611 + outer loop + vertex 857.422 457.042 207.358 + vertex 856.957 459.106 207.534 + vertex 857.779 457.29 211.28 + endloop + endfacet + facet normal 0.968284 0.22814 -0.101869 + outer loop + vertex 857.779 457.29 211.28 + vertex 856.957 459.106 207.534 + vertex 857.306 459.383 211.471 + endloop + endfacet + facet normal 0.969768 0.234273 -0.0683093 + outer loop + vertex 856.594 456.461 195.466 + vertex 856.12 458.461 195.596 + vertex 856.836 456.622 199.457 + endloop + endfacet + facet normal 0.970384 0.231244 -0.0698659 + outer loop + vertex 856.836 456.622 199.457 + vertex 856.12 458.461 195.596 + vertex 856.364 458.644 199.595 + endloop + endfacet + facet normal 0.969687 0.231627 -0.077826 + outer loop + vertex 856.836 456.622 199.457 + vertex 856.364 458.644 199.595 + vertex 857.108 456.819 203.426 + endloop + endfacet + facet normal 0.970631 0.226765 -0.0803265 + outer loop + vertex 857.108 456.819 203.426 + vertex 856.364 458.644 199.595 + vertex 856.644 458.86 203.587 + endloop + endfacet + facet normal 0.971851 0.230271 -0.0498085 + outer loop + vertex 856.197 456.224 187.461 + vertex 855.736 458.192 187.557 + vertex 856.378 456.328 191.463 + endloop + endfacet + facet normal 0.971487 0.231987 -0.0489295 + outer loop + vertex 856.378 456.328 191.463 + vertex 855.736 458.192 187.557 + vertex 855.911 458.309 191.58 + endloop + endfacet + facet normal 0.970744 0.232471 -0.0601116 + outer loop + vertex 856.378 456.328 191.463 + vertex 855.911 458.309 191.58 + vertex 856.594 456.461 195.466 + endloop + endfacet + facet normal 0.970455 0.233854 -0.0594029 + outer loop + vertex 856.594 456.461 195.466 + vertex 855.911 458.309 191.58 + vertex 856.12 458.461 195.596 + endloop + endfacet + facet normal 0.972915 0.229158 -0.0303998 + outer loop + vertex 855.948 456.107 179.46 + vertex 855.492 458.061 179.614 + vertex 856.062 456.152 183.462 + endloop + endfacet + facet normal 0.972165 0.232544 -0.0286083 + outer loop + vertex 856.062 456.152 183.462 + vertex 855.492 458.061 179.614 + vertex 855.598 458.11 183.587 + endloop + endfacet + facet normal 0.971773 0.232991 -0.0370441 + outer loop + vertex 856.062 456.152 183.462 + vertex 855.598 458.11 183.587 + vertex 856.197 456.224 187.461 + endloop + endfacet + facet normal 0.972454 0.229866 -0.0386715 + outer loop + vertex 856.197 456.224 187.461 + vertex 855.598 458.11 183.587 + vertex 855.736 458.192 187.557 + endloop + endfacet + facet normal 0.974064 0.226062 -0.00980085 + outer loop + vertex 855.833 456.109 171.538 + vertex 855.378 458.068 171.53 + vertex 855.876 456.094 175.468 + endloop + endfacet + facet normal 0.973525 0.228421 -0.00855037 + outer loop + vertex 855.876 456.094 175.468 + vertex 855.378 458.068 171.53 + vertex 855.419 458.047 175.572 + endloop + endfacet + facet normal 0.973283 0.228883 -0.0182644 + outer loop + vertex 855.876 456.094 175.468 + vertex 855.419 458.047 175.572 + vertex 855.948 456.107 179.46 + endloop + endfacet + facet normal 0.973406 0.228334 -0.0185553 + outer loop + vertex 855.948 456.107 179.46 + vertex 855.419 458.047 175.572 + vertex 855.492 458.061 179.614 + endloop + endfacet + facet normal 0.975067 0.221706 0.00956124 + outer loop + vertex 855.841 456.23 163.836 + vertex 855.39 458.206 163.949 + vertex 855.82 456.155 167.678 + endloop + endfacet + facet normal 0.974804 0.222831 0.0102103 + outer loop + vertex 855.82 456.155 167.678 + vertex 855.39 458.206 163.949 + vertex 855.37 458.121 167.739 + endloop + endfacet + facet normal 0.974782 0.223158 -0.000606793 + outer loop + vertex 855.82 456.155 167.678 + vertex 855.37 458.121 167.739 + vertex 855.833 456.109 171.538 + endloop + endfacet + facet normal 0.9741 0.226116 0.00104276 + outer loop + vertex 855.833 456.109 171.538 + vertex 855.37 458.121 167.739 + vertex 855.378 458.068 171.53 + endloop + endfacet + facet normal 0.976387 0.214195 0.0281062 + outer loop + vertex 855.962 456.479 156.065 + vertex 855.519 458.485 156.165 + vertex 855.881 456.334 159.974 + endloop + endfacet + facet normal 0.976225 0.214879 0.0285078 + outer loop + vertex 855.881 456.334 159.974 + vertex 855.519 458.485 156.165 + vertex 855.44 458.328 160.056 + endloop + endfacet + facet normal 0.976388 0.215421 0.0161023 + outer loop + vertex 855.881 456.334 159.974 + vertex 855.44 458.328 160.056 + vertex 855.841 456.23 163.836 + endloop + endfacet + facet normal 0.975049 0.221137 0.0194172 + outer loop + vertex 855.841 456.23 163.836 + vertex 855.44 458.328 160.056 + vertex 855.39 458.206 163.949 + endloop + endfacet + facet normal 0.977517 0.206109 0.0445023 + outer loop + vertex 856.2 456.898 148.125 + vertex 855.77 458.916 148.224 + vertex 856.067 456.669 152.104 + endloop + endfacet + facet normal 0.976535 0.210183 0.0469369 + outer loop + vertex 856.067 456.669 152.104 + vertex 855.77 458.916 148.224 + vertex 855.63 458.682 152.192 + endloop + endfacet + facet normal 0.976879 0.210733 0.0360303 + outer loop + vertex 856.067 456.669 152.104 + vertex 855.63 458.682 152.192 + vertex 855.962 456.479 156.065 + endloop + endfacet + facet normal 0.976177 0.213664 0.0377578 + outer loop + vertex 855.962 456.479 156.065 + vertex 855.63 458.682 152.192 + vertex 855.519 458.485 156.165 + endloop + endfacet + facet normal 0.976881 0.203376 0.0658949 + outer loop + vertex 856.586 457.384 140.192 + vertex 856.137 459.498 140.323 + vertex 856.368 457.144 144.156 + endloop + endfacet + facet normal 0.977321 0.201611 0.0647841 + outer loop + vertex 856.368 457.144 144.156 + vertex 856.137 459.498 140.323 + vertex 855.939 459.188 144.27 + endloop + endfacet + facet normal 0.977831 0.202318 0.0539838 + outer loop + vertex 856.368 457.144 144.156 + vertex 855.939 459.188 144.27 + vertex 856.2 456.898 148.125 + endloop + endfacet + facet normal 0.97707 0.20545 0.0558961 + outer loop + vertex 856.2 456.898 148.125 + vertex 855.939 459.188 144.27 + vertex 855.77 458.916 148.224 + endloop + endfacet + facet normal 0.975852 0.20191 0.0833397 + outer loop + vertex 857.125 457.909 132.14 + vertex 856.632 460.26 132.225 + vertex 856.841 457.612 136.192 + endloop + endfacet + facet normal 0.97585 0.201916 0.0833442 + outer loop + vertex 856.841 457.612 136.192 + vertex 856.632 460.26 132.225 + vertex 856.37 459.858 136.269 + endloop + endfacet + facet normal 0.976518 0.20238 0.073855 + outer loop + vertex 856.841 457.612 136.192 + vertex 856.37 459.858 136.269 + vertex 856.586 457.384 140.192 + endloop + endfacet + facet normal 0.976418 0.202771 0.0741069 + outer loop + vertex 856.586 457.384 140.192 + vertex 856.37 459.858 136.269 + vertex 856.137 459.498 140.323 + endloop + endfacet + facet normal 0.960947 0.244708 0.129221 + outer loop + vertex 858.125 458.35 123.041 + vertex 857.212 461.143 124.545 + vertex 857.513 458.167 127.94 + endloop + endfacet + facet normal 0.97112 0.215391 0.102625 + outer loop + vertex 857.513 458.167 127.94 + vertex 857.212 461.143 124.545 + vertex 856.909 460.682 128.379 + endloop + endfacet + facet normal 0.971106 0.215349 0.102849 + outer loop + vertex 857.513 458.167 127.94 + vertex 856.909 460.682 128.379 + vertex 857.125 457.909 132.14 + endloop + endfacet + facet normal 0.975138 0.201434 0.0923592 + outer loop + vertex 857.125 457.909 132.14 + vertex 856.909 460.682 128.379 + vertex 856.632 460.26 132.225 + endloop + endfacet + facet normal 0.960864 0.249948 0.119445 + outer loop + vertex 857.212 461.143 124.545 + vertex 858.125 458.35 123.041 + vertex 857.9 462.192 116.816 + endloop + endfacet + facet normal 0.330882 -0.716805 0.613766 + outer loop + vertex 847.56 243.901 47.8596 + vertex 847.08 242.431 46.4005 + vertex 847.972 243.793 47.5108 + endloop + endfacet + facet normal 0.381193 -0.729412 0.568023 + outer loop + vertex 848.634 246.294 50.2113 + vertex 847.56 243.901 47.8596 + vertex 848.5 245.159 48.8439 + endloop + endfacet + facet normal 0.366902 -0.753521 0.545518 + outer loop + vertex 849.558 248.713 52.9314 + vertex 848.634 246.294 50.2113 + vertex 849.327 247.255 51.0725 + endloop + endfacet + facet normal 0.318421 -0.78365 0.533386 + outer loop + vertex 850.449 251.195 56.0451 + vertex 849.558 248.713 52.9314 + vertex 850.202 249.639 53.9078 + endloop + endfacet + facet normal 0.278648 -0.811737 0.513263 + outer loop + vertex 851.315 253.689 59.5201 + vertex 850.449 251.195 56.0451 + vertex 851.071 252.12 57.1707 + endloop + endfacet + facet normal 0.268521 -0.835437 0.479522 + outer loop + vertex 852.084 256.069 63.2361 + vertex 851.315 253.689 59.5201 + vertex 851.858 254.511 60.6489 + endloop + endfacet + facet normal 0.279324 -0.853904 0.439119 + outer loop + vertex 852.889 258.696 67.8324 + vertex 852.084 256.069 63.2361 + vertex 852.584 256.65 64.0464 + endloop + endfacet + facet normal 0.286153 -0.870167 0.401156 + outer loop + vertex 853.496 261.245 72.9269 + vertex 852.889 258.696 67.8324 + vertex 853.81 260.14 70.3078 + endloop + endfacet + facet normal 0.241933 -0.895835 0.372758 + outer loop + vertex 853.867 263.201 77.389 + vertex 853.496 261.245 72.9269 + vertex 854.208 262.1 74.5208 + endloop + endfacet + facet normal 0.205406 -0.915409 0.346172 + outer loop + vertex 854.197 265.247 82.6019 + vertex 853.867 263.201 77.389 + vertex 854.657 264.009 79.0569 + endloop + endfacet + facet normal 0.232252 -0.921833 0.310295 + outer loop + vertex 854.527 267.326 88.5334 + vertex 854.197 265.247 82.6019 + vertex 855.512 266.322 84.8131 + endloop + endfacet + facet normal 0.185022 -0.937104 0.295977 + outer loop + vertex 854.423 268.905 93.5975 + vertex 854.527 267.326 88.5334 + vertex 855.544 268.981 93.1359 + endloop + endfacet + facet normal 0.172285 -0.949281 0.263028 + outer loop + vertex 854.645 270.29 98.4504 + vertex 854.423 268.905 93.5975 + vertex 855.544 268.981 93.1359 + endloop + endfacet + facet normal 0.216714 -0.94609 0.240724 + outer loop + vertex 854.576 271.702 104.062 + vertex 854.645 270.29 98.4504 + vertex 855.618 271.114 100.812 + endloop + endfacet + facet normal 0.142426 -0.964403 0.222805 + outer loop + vertex 854.327 272.801 108.976 + vertex 854.576 271.702 104.062 + vertex 855.164 272.799 108.435 + endloop + endfacet + facet normal 0.125904 -0.972226 0.197295 + outer loop + vertex 854.374 273.728 113.517 + vertex 854.327 272.801 108.976 + vertex 855.164 272.799 108.435 + endloop + endfacet + facet normal 0.169703 -0.96769 0.186484 + outer loop + vertex 854.224 274.493 117.619 + vertex 854.374 273.728 113.517 + vertex 855.007 274.316 115.989 + endloop + endfacet + facet normal 0.13184 -0.97671 0.16928 + outer loop + vertex 854.301 274.995 120.458 + vertex 854.224 274.493 117.619 + vertex 855.007 274.316 115.989 + endloop + endfacet + facet normal 0.155924 -0.973422 0.167741 + outer loop + vertex 854.093 275.44 123.234 + vertex 854.301 274.995 120.458 + vertex 854.812 275.605 123.52 + endloop + endfacet + facet normal 0.163146 -0.975058 0.150484 + outer loop + vertex 854.029 275.842 125.908 + vertex 854.093 275.44 123.234 + vertex 854.812 275.605 123.52 + endloop + endfacet + facet normal 0.122852 -0.982779 0.138032 + outer loop + vertex 854.075 276.283 129.008 + vertex 854.029 275.842 125.908 + vertex 854.812 275.605 123.52 + endloop + endfacet + facet normal 0.209694 -0.968904 0.131352 + outer loop + vertex 854.014 276.678 132.014 + vertex 854.075 276.283 129.008 + vertex 854.804 276.687 130.823 + endloop + endfacet + facet normal 0.194704 -0.973324 0.121373 + outer loop + vertex 853.967 277.035 134.952 + vertex 854.014 276.678 132.014 + vertex 854.804 276.687 130.823 + endloop + endfacet + facet normal 0.168138 -0.978936 0.115818 + outer loop + vertex 853.821 277.41 138.335 + vertex 853.967 277.035 134.952 + vertex 854.565 277.562 138.543 + endloop + endfacet + facet normal 0.17305 -0.979926 0.0989887 + outer loop + vertex 853.856 277.619 140.341 + vertex 853.821 277.41 138.335 + vertex 854.565 277.562 138.543 + endloop + endfacet + facet normal 0.157468 -0.983141 0.0929422 + outer loop + vertex 853.862 277.877 143.06 + vertex 853.856 277.619 140.341 + vertex 854.565 277.562 138.543 + endloop + endfacet + facet normal 0.15437 -0.983958 0.0894245 + outer loop + vertex 853.745 278.175 146.544 + vertex 853.862 277.877 143.06 + vertex 854.468 278.31 146.786 + endloop + endfacet + facet normal 0.159438 -0.984393 0.0744956 + outer loop + vertex 853.732 278.382 149.309 + vertex 853.745 278.175 146.544 + vertex 854.468 278.31 146.786 + endloop + endfacet + facet normal 0.113018 -0.991708 0.0611758 + outer loop + vertex 853.852 278.553 151.858 + vertex 853.732 278.382 149.309 + vertex 854.468 278.31 146.786 + endloop + endfacet + facet normal 0.151584 -0.986201 0.0665526 + outer loop + vertex 853.688 278.722 154.737 + vertex 853.852 278.553 151.858 + vertex 854.402 278.847 154.965 + endloop + endfacet + facet normal 0.156854 -0.986349 0.050117 + outer loop + vertex 853.659 278.856 157.459 + vertex 853.688 278.722 154.737 + vertex 854.402 278.847 154.965 + endloop + endfacet + facet normal 0.109838 -0.993292 0.036146 + outer loop + vertex 853.739 278.978 160.568 + vertex 853.659 278.856 157.459 + vertex 854.402 278.847 154.965 + endloop + endfacet + facet normal 0.193592 -0.980581 0.0313406 + outer loop + vertex 853.724 279.07 163.548 + vertex 853.739 278.978 160.568 + vertex 854.46 279.178 162.388 + endloop + endfacet + facet normal 0.180728 -0.983266 0.0229309 + outer loop + vertex 853.726 279.138 166.455 + vertex 853.724 279.07 163.548 + vertex 854.46 279.178 162.388 + endloop + endfacet + facet normal 0.147589 -0.988888 0.0178135 + outer loop + vertex 853.63 279.185 169.829 + vertex 853.726 279.138 166.455 + vertex 854.35 279.298 170.158 + endloop + endfacet + facet normal 0.154832 -0.987939 0.00168913 + outer loop + vertex 853.644 279.191 172.54 + vertex 853.63 279.185 169.829 + vertex 854.35 279.298 170.158 + endloop + endfacet + facet normal 0.110725 -0.993783 -0.01164 + outer loop + vertex 853.785 279.177 175.091 + vertex 853.644 279.191 172.54 + vertex 854.35 279.298 170.158 + endloop + endfacet + facet normal 0.145498 -0.989338 -0.00632828 + outer loop + vertex 853.652 279.139 177.979 + vertex 853.785 279.177 175.091 + vertex 854.364 279.242 178.297 + endloop + endfacet + facet normal 0.152959 -0.987953 -0.0234951 + outer loop + vertex 853.664 279.075 180.739 + vertex 853.652 279.139 177.979 + vertex 854.364 279.242 178.297 + endloop + endfacet + facet normal 0.107592 -0.993511 -0.0368775 + outer loop + vertex 853.825 278.998 183.306 + vertex 853.664 279.075 180.739 + vertex 854.364 279.242 178.297 + endloop + endfacet + facet normal 0.143831 -0.98905 -0.0330535 + outer loop + vertex 853.703 278.883 186.206 + vertex 853.825 278.998 183.306 + vertex 854.412 278.977 186.467 + endloop + endfacet + facet normal 0.149476 -0.987552 -0.048971 + outer loop + vertex 853.712 278.747 188.966 + vertex 853.703 278.883 186.206 + vertex 854.412 278.977 186.467 + endloop + endfacet + facet normal 0.104556 -0.992583 -0.0620244 + outer loop + vertex 853.838 278.562 192.139 + vertex 853.712 278.747 188.966 + vertex 854.412 278.977 186.467 + endloop + endfacet + facet normal 0.193413 -0.978791 -0.0675301 + outer loop + vertex 853.854 278.353 195.213 + vertex 853.838 278.562 192.139 + vertex 854.581 278.582 193.982 + endloop + endfacet + facet normal 0.180784 -0.980634 -0.0753303 + outer loop + vertex 853.892 278.135 198.149 + vertex 853.854 278.353 195.213 + vertex 854.581 278.582 193.982 + endloop + endfacet + facet normal 0.156307 -0.984289 -0.0821205 + outer loop + vertex 853.839 277.844 201.539 + vertex 853.892 278.135 198.149 + vertex 854.577 277.948 201.69 + endloop + endfacet + facet normal 0.159436 -0.982249 -0.0988312 + outer loop + vertex 853.93 277.66 203.51 + vertex 853.839 277.844 201.539 + vertex 854.577 277.948 201.69 + endloop + endfacet + facet normal 0.142923 -0.984148 -0.105002 + outer loop + vertex 854.01 277.383 206.215 + vertex 853.93 277.66 203.51 + vertex 854.577 277.948 201.69 + endloop + endfacet + facet normal 0.151628 -0.982473 -0.108422 + outer loop + vertex 853.988 276.999 209.664 + vertex 854.01 277.383 206.215 + vertex 854.742 277.085 209.942 + endloop + endfacet + facet normal 0.156851 -0.979885 -0.123383 + outer loop + vertex 854.053 276.665 212.4 + vertex 853.988 276.999 209.664 + vertex 854.742 277.085 209.942 + endloop + endfacet + facet normal 0.112059 -0.984257 -0.136675 + outer loop + vertex 854.257 276.33 214.98 + vertex 854.053 276.665 212.4 + vertex 854.742 277.085 209.942 + endloop + endfacet + facet normal 0.141593 -0.980772 -0.134302 + outer loop + vertex 854.168 275.928 217.824 + vertex 854.257 276.33 214.98 + vertex 854.964 275.975 218.318 + endloop + endfacet + facet normal 0.151939 -0.976733 -0.151349 + outer loop + vertex 854.218 275.515 220.537 + vertex 854.168 275.928 217.824 + vertex 854.964 275.975 218.318 + endloop + endfacet + facet normal 0.11225 -0.97983 -0.165327 + outer loop + vertex 854.428 274.989 223.797 + vertex 854.218 275.515 220.537 + vertex 854.964 275.975 218.318 + endloop + endfacet + facet normal 0.150631 -0.973478 -0.172194 + outer loop + vertex 854.523 274.44 226.982 + vertex 854.428 274.989 223.797 + vertex 855.342 274.675 226.373 + endloop + endfacet + facet normal 0.140566 -0.972559 -0.185393 + outer loop + vertex 854.622 273.829 230.264 + vertex 854.523 274.44 226.982 + vertex 855.342 274.675 226.373 + endloop + endfacet + facet normal 0.130731 -0.971978 -0.195368 + outer loop + vertex 854.574 272.901 234.85 + vertex 854.622 273.829 230.264 + vertex 855.586 273.102 234.525 + endloop + endfacet + facet normal 0.120173 -0.966896 -0.225101 + outer loop + vertex 854.881 271.773 239.857 + vertex 854.574 272.901 234.85 + vertex 855.586 273.102 234.525 + endloop + endfacet + facet normal 0.205406 -0.948286 -0.241995 + outer loop + vertex 854.9 270.194 246.061 + vertex 854.881 271.773 239.857 + vertex 855.963 271.389 242.283 + endloop + endfacet + facet normal 0.183861 -0.945414 -0.26905 + outer loop + vertex 854.856 268.75 251.106 + vertex 854.9 270.194 246.061 + vertex 855.934 269.219 250.195 + endloop + endfacet + facet normal 0.156291 -0.94121 -0.299495 + outer loop + vertex 854.948 267.359 255.524 + vertex 854.856 268.75 251.106 + vertex 855.934 269.219 250.195 + endloop + endfacet + facet normal 0.223726 -0.922405 -0.314828 + outer loop + vertex 854.671 265.327 261.282 + vertex 854.948 267.359 255.524 + vertex 855.96 266.66 258.294 + endloop + endfacet + facet normal 0.198869 -0.914987 -0.351068 + outer loop + vertex 854.427 263.327 266.357 + vertex 854.671 265.327 261.282 + vertex 855.048 264.453 263.774 + endloop + endfacet + facet normal 0.213814 -0.898205 -0.384073 + outer loop + vertex 854.177 261.427 270.661 + vertex 854.427 263.327 266.357 + vertex 854.891 262.853 267.723 + endloop + endfacet + facet normal 0.232007 -0.877534 -0.419652 + outer loop + vertex 853.697 258.903 275.672 + vertex 854.177 261.427 270.661 + vertex 854.667 260.987 271.852 + endloop + endfacet + facet normal 0.349262 -0.832818 -0.429453 + outer loop + vertex 852.994 256.161 280.418 + vertex 853.697 258.903 275.672 + vertex 853.558 257.315 278.639 + endloop + endfacet + facet normal 0.324042 -0.814706 -0.480885 + outer loop + vertex 852.294 253.651 284.199 + vertex 852.994 256.161 280.418 + vertex 853.044 255.375 281.784 + endloop + endfacet + facet normal 0.330213 -0.786497 -0.521902 + outer loop + vertex 851.276 250.431 288.408 + vertex 852.294 253.651 284.199 + vertex 852.38 253.03 285.19 + endloop + endfacet + facet normal 0.376473 -0.74798 -0.54662 + outer loop + vertex 850.212 247.179 292.125 + vertex 851.276 250.431 288.408 + vertex 851.047 248.833 290.437 + endloop + endfacet + facet normal 0.322151 -0.725085 -0.608663 + outer loop + vertex 849.386 244.797 294.526 + vertex 850.212 247.179 292.125 + vertex 850.266 246.433 293.042 + endloop + endfacet + facet normal 0.306102 -0.695467 -0.650098 + outer loop + vertex 848.339 242.413 296.583 + vertex 849.386 244.797 294.526 + vertex 849.816 244.651 294.884 + endloop + endfacet + facet normal 0.941898 0.233027 0.241921 + outer loop + vertex 890.283 395.281 49.7133 + vertex 889.383 398.987 49.6457 + vertex 890.412 394.182 50.2672 + endloop + endfacet + facet normal 0.949548 0.212082 0.231039 + outer loop + vertex 891.617 389.553 49.609 + vertex 890.972 392.231 49.8018 + vertex 892.12 386.565 50.2828 + endloop + endfacet + facet normal 0.947157 0.213553 0.239349 + outer loop + vertex 892.306 386.393 49.7026 + vertex 891.617 389.553 49.609 + vertex 892.12 386.565 50.2828 + endloop + endfacet + facet normal 0.949594 0.194629 0.245745 + outer loop + vertex 893.102 382.562 49.6615 + vertex 892.306 386.393 49.7026 + vertex 892.12 386.565 50.2828 + endloop + endfacet + facet normal 0.947859 0.190609 0.255406 + outer loop + vertex 893.93 378.447 49.6587 + vertex 893.102 382.562 49.6615 + vertex 893.865 377.818 50.3685 + endloop + endfacet + facet normal 0.955552 0.171892 0.239528 + outer loop + vertex 894.661 374.464 49.6024 + vertex 893.93 378.447 49.6587 + vertex 893.865 377.818 50.3685 + endloop + endfacet + facet normal 0.951242 0.164185 0.261116 + outer loop + vertex 895.353 370.465 49.5934 + vertex 894.661 374.464 49.6024 + vertex 895.288 369.74 50.2859 + endloop + endfacet + facet normal 0.959636 0.144483 0.241296 + outer loop + vertex 895.956 366.482 49.583 + vertex 895.353 370.465 49.5934 + vertex 895.288 369.74 50.2859 + endloop + endfacet + facet normal 0.95061 0.137952 0.278048 + outer loop + vertex 896.486 362.735 49.6283 + vertex 895.956 366.482 49.583 + vertex 896.383 362.141 50.2748 + endloop + endfacet + facet normal 0.958018 0.118294 0.261167 + outer loop + vertex 896.832 359.742 49.7141 + vertex 896.486 362.735 49.6283 + vertex 896.383 362.141 50.2748 + endloop + endfacet + facet normal 0.96117 0.0998106 0.257274 + outer loop + vertex 897.222 356.481 49.5241 + vertex 896.832 359.742 49.7141 + vertex 897.2 354.712 50.2909 + endloop + endfacet + facet normal 0.966307 0.092367 0.240246 + outer loop + vertex 897.608 351.967 49.7054 + vertex 897.222 356.481 49.5241 + vertex 897.2 354.712 50.2909 + endloop + endfacet + facet normal 0.958452 0.0667151 0.277341 + outer loop + vertex 897.922 348.237 49.5195 + vertex 897.608 351.967 49.7054 + vertex 897.801 346.851 50.2699 + endloop + endfacet + facet normal 0.965523 0.0538419 0.254688 + outer loop + vertex 898.119 343.852 49.6968 + vertex 897.922 348.237 49.5195 + vertex 897.801 346.851 50.2699 + endloop + endfacet + facet normal 0.962487 0.0217904 0.270452 + outer loop + vertex 898.257 340.033 49.5149 + vertex 898.119 343.852 49.6968 + vertex 898.085 339.237 50.1926 + endloop + endfacet + facet normal 0.966161 0.0101645 0.257741 + outer loop + vertex 898.249 336.135 49.6974 + vertex 898.257 340.033 49.5149 + vertex 898.085 339.237 50.1926 + endloop + endfacet + facet normal 0.931923 -0.0180393 0.362208 + outer loop + vertex 898.227 333.473 49.6229 + vertex 898.249 336.135 49.6974 + vertex 897.973 332.126 50.2097 + endloop + endfacet + facet normal 0.954903 -0.0528613 0.292176 + outer loop + vertex 898.048 329.9 49.5602 + vertex 898.227 333.473 49.6229 + vertex 897.973 332.126 50.2097 + endloop + endfacet + facet normal 0.915336 -0.0572732 0.398598 + outer loop + vertex 897.805 325.944 49.5502 + vertex 898.048 329.9 49.5602 + vertex 897.453 324.759 50.1889 + endloop + endfacet + facet normal 0.941128 -0.106943 0.320689 + outer loop + vertex 897.372 322.053 49.5241 + vertex 897.805 325.944 49.5502 + vertex 897.453 324.759 50.1889 + endloop + endfacet + facet normal 0.888962 -0.116152 0.443007 + outer loop + vertex 896.847 318.13 49.5486 + vertex 897.372 322.053 49.5241 + vertex 896.382 317.082 50.2057 + endloop + endfacet + facet normal 0.912808 -0.172286 0.37027 + outer loop + vertex 896.125 314.316 49.5531 + vertex 896.847 318.13 49.5486 + vertex 896.382 317.082 50.2057 + endloop + endfacet + facet normal 0.805411 -0.151324 0.573074 + outer loop + vertex 895.468 311.012 49.6049 + vertex 896.125 314.316 49.5531 + vertex 894.748 309.274 50.1575 + endloop + endfacet + facet normal 0.864505 -0.213309 0.455116 + outer loop + vertex 895.076 309.402 49.5932 + vertex 895.468 311.012 49.6049 + vertex 894.748 309.274 50.1575 + endloop + endfacet + facet normal 0.859506 -0.255491 0.442689 + outer loop + vertex 894.184 306.235 49.4992 + vertex 895.076 309.402 49.5932 + vertex 894.748 309.274 50.1575 + endloop + endfacet + facet normal 0.848609 -0.254963 0.463526 + outer loop + vertex 893.086 302.5 49.4535 + vertex 894.184 306.235 49.4992 + vertex 892.513 301.621 50.0203 + endloop + endfacet + facet normal 0.86521 -0.311134 0.393201 + outer loop + vertex 891.783 298.811 49.4031 + vertex 893.086 302.5 49.4535 + vertex 892.513 301.621 50.0203 + endloop + endfacet + facet normal 0.821697 -0.304463 0.481786 + outer loop + vertex 890.482 295.33 49.4221 + vertex 891.783 298.811 49.4031 + vertex 889.877 294.63 50.0102 + endloop + endfacet + facet normal 0.830297 -0.35727 0.427744 + outer loop + vertex 889.286 292.616 49.4759 + vertex 890.482 295.33 49.4221 + vertex 889.877 294.63 50.0102 + endloop + endfacet + facet normal 0.818344 -0.390547 0.421647 + outer loop + vertex 888.305 290.313 49.2477 + vertex 889.286 292.616 49.4759 + vertex 886.684 287.66 49.9361 + endloop + endfacet + facet normal 0.810034 -0.378714 0.447685 + outer loop + vertex 887.021 287.625 49.2953 + vertex 888.305 290.313 49.2477 + vertex 886.684 287.66 49.9361 + endloop + endfacet + facet normal 0.788917 -0.429613 0.439366 + outer loop + vertex 885.289 284.379 49.2328 + vertex 887.021 287.625 49.2953 + vertex 886.684 287.66 49.9361 + endloop + endfacet + facet normal 0.768116 -0.423267 0.480461 + outer loop + vertex 883.515 281.143 49.2174 + vertex 885.289 284.379 49.2328 + vertex 882.721 280.432 49.861 + endloop + endfacet + facet normal 0.770113 -0.476568 0.424038 + outer loop + vertex 881.976 278.679 49.2433 + vertex 883.515 281.143 49.2174 + vertex 882.721 280.432 49.861 + endloop + endfacet + facet normal 0.75211 -0.497671 0.432034 + outer loop + vertex 880.767 276.637 48.9955 + vertex 881.976 278.679 49.2433 + vertex 878.725 274.125 49.6562 + endloop + endfacet + facet normal 0.74584 -0.486543 0.45497 + outer loop + vertex 879.187 274.253 49.037 + vertex 880.767 276.637 48.9955 + vertex 878.725 274.125 49.6562 + endloop + endfacet + facet normal 0.728213 -0.531691 0.432447 + outer loop + vertex 877.151 271.401 48.9583 + vertex 879.187 274.253 49.037 + vertex 878.725 274.125 49.6562 + endloop + endfacet + facet normal 0.669376 -0.490335 0.558128 + outer loop + vertex 875.285 268.807 48.9177 + vertex 877.151 271.401 48.9583 + vertex 873.919 267.552 49.4527 + endloop + endfacet + facet normal 0.687716 -0.54262 0.482297 + outer loop + vertex 874.318 267.542 48.873 + vertex 875.285 268.807 48.9177 + vertex 873.919 267.552 49.4527 + endloop + endfacet + facet normal 0.669725 -0.574589 0.470442 + outer loop + vertex 872.266 265.041 48.7403 + vertex 874.318 267.542 48.873 + vertex 873.919 267.552 49.4527 + endloop + endfacet + facet normal 0.626006 -0.540172 0.562433 + outer loop + vertex 869.982 262.309 48.6581 + vertex 872.266 265.041 48.7403 + vertex 868.883 261.616 49.2156 + endloop + endfacet + facet normal 0.629132 -0.605927 0.486873 + outer loop + vertex 867.909 260.111 48.6002 + vertex 869.982 262.309 48.6581 + vertex 868.883 261.616 49.2156 + endloop + endfacet + facet normal 0.577693 -0.607807 0.544832 + outer loop + vertex 866.254 258.238 48.2666 + vertex 867.909 260.111 48.6002 + vertex 863.467 255.981 48.7043 + endloop + endfacet + facet normal 0.57135 -0.596265 0.56394 + outer loop + vertex 863.98 255.981 48.1831 + vertex 866.254 258.238 48.2666 + vertex 863.467 255.981 48.7043 + endloop + endfacet + facet normal 0.539028 -0.652859 0.532188 + outer loop + vertex 860.887 253.13 47.8191 + vertex 863.98 255.981 48.1831 + vertex 863.467 255.981 48.7043 + endloop + endfacet + facet normal 0.562335 -0.696976 0.444976 + outer loop + vertex 855.962 248.817 47.2881 + vertex 860.887 253.13 47.8191 + vertex 857.363 250.424 48.0334 + endloop + endfacet + facet normal 0.499039 -0.684622 0.531275 + outer loop + vertex 852.241 245.873 46.9897 + vertex 855.962 248.817 47.2881 + vertex 853.053 246.772 47.3855 + endloop + endfacet + facet normal 0.45286 -0.703983 0.547107 + outer loop + vertex 850.002 244.1 46.5611 + vertex 852.241 245.873 46.9897 + vertex 850.158 244.559 47.023 + endloop + endfacet + facet normal 0.43956 -0.807261 0.393849 + outer loop + vertex 847.08 242.431 46.4005 + vertex 850.002 244.1 46.5611 + vertex 848.642 243.475 46.7976 + endloop + endfacet + facet normal 0.315718 -0.693264 -0.647848 + outer loop + vertex 850.994 243.855 296.334 + vertex 848.339 242.413 296.583 + vertex 850.508 244.279 295.643 + endloop + endfacet + facet normal 0.378624 -0.702766 -0.602298 + outer loop + vertex 853.354 245.464 295.939 + vertex 850.994 243.855 296.334 + vertex 852.404 245.28 295.557 + endloop + endfacet + facet normal 0.441605 -0.711762 -0.546241 + outer loop + vertex 856.219 247.651 295.406 + vertex 853.354 245.464 295.939 + vertex 854.597 246.755 295.262 + endloop + endfacet + facet normal 0.483059 -0.702346 -0.522843 + outer loop + vertex 859.423 250.243 294.885 + vertex 856.219 247.651 295.406 + vertex 857.839 249.544 294.36 + endloop + endfacet + facet normal 0.486894 -0.67125 -0.55889 + outer loop + vertex 861.582 252.039 294.608 + vertex 859.423 250.243 294.885 + vertex 861.76 252.668 294.008 + endloop + endfacet + facet normal 0.539605 -0.656226 -0.527442 + outer loop + vertex 864.096 254.271 294.403 + vertex 861.582 252.039 294.608 + vertex 861.76 252.668 294.008 + endloop + endfacet + facet normal 0.566657 -0.66142 -0.491349 + outer loop + vertex 866.5 256.441 294.255 + vertex 864.096 254.271 294.403 + vertex 866.931 257.952 292.717 + endloop + endfacet + facet normal 0.608933 -0.644309 -0.462673 + outer loop + vertex 868.622 258.433 294.274 + vertex 866.5 256.441 294.255 + vertex 866.931 257.952 292.717 + endloop + endfacet + facet normal 0.610564 -0.640669 -0.465569 + outer loop + vertex 870.667 260.832 293.654 + vertex 868.622 258.433 294.274 + vertex 866.931 257.952 292.717 + endloop + endfacet + facet normal 0.628976 -0.625429 -0.461766 + outer loop + vertex 872.723 262.866 293.7 + vertex 870.667 260.832 293.654 + vertex 872.936 264.259 292.103 + endloop + endfacet + facet normal 0.671494 -0.60041 -0.434285 + outer loop + vertex 875.143 265.633 293.616 + vertex 872.723 262.866 293.7 + vertex 872.936 264.259 292.103 + endloop + endfacet + facet normal 0.657409 -0.586135 -0.47356 + outer loop + vertex 877.187 267.988 293.538 + vertex 875.143 265.633 293.616 + vertex 877.855 269.929 292.065 + endloop + endfacet + facet normal 0.69189 -0.572492 -0.439932 + outer loop + vertex 878.201 269.258 293.481 + vertex 877.187 267.988 293.538 + vertex 877.855 269.929 292.065 + endloop + endfacet + facet normal 0.716843 -0.546075 -0.433518 + outer loop + vertex 880.237 272.023 293.364 + vertex 878.201 269.258 293.481 + vertex 877.855 269.929 292.065 + endloop + endfacet + facet normal 0.702362 -0.540154 -0.463597 + outer loop + vertex 882.136 274.585 293.256 + vertex 880.237 272.023 293.364 + vertex 882.578 276.386 291.827 + endloop + endfacet + facet normal 0.733142 -0.52391 -0.433613 + outer loop + vertex 883.089 275.96 293.208 + vertex 882.136 274.585 293.256 + vertex 882.578 276.386 291.827 + endloop + endfacet + facet normal 0.756278 -0.491258 -0.432098 + outer loop + vertex 884.981 278.937 293.133 + vertex 883.089 275.96 293.208 + vertex 882.578 276.386 291.827 + endloop + endfacet + facet normal 0.761902 -0.487865 -0.426019 + outer loop + vertex 887.021 282.182 293.066 + vertex 884.981 278.937 293.133 + vertex 886.852 283.295 291.488 + endloop + endfacet + facet normal 0.793838 -0.453485 -0.405182 + outer loop + vertex 888.962 285.616 293.026 + vertex 887.021 282.182 293.066 + vertex 886.852 283.295 291.488 + endloop + endfacet + facet normal 0.774285 -0.438798 -0.456004 + outer loop + vertex 890.49 288.32 293.019 + vertex 888.962 285.616 293.026 + vertex 890.619 290.018 291.602 + endloop + endfacet + facet normal 0.805973 -0.413859 -0.423235 + outer loop + vertex 891.246 289.793 293.016 + vertex 890.49 288.32 293.019 + vertex 890.619 290.018 291.602 + endloop + endfacet + facet normal 0.823834 -0.375083 -0.424983 + outer loop + vertex 892.707 293.053 292.971 + vertex 891.246 289.793 293.016 + vertex 890.619 290.018 291.602 + endloop + endfacet + facet normal 0.827309 -0.375831 -0.417506 + outer loop + vertex 894.172 296.338 292.918 + vertex 892.707 293.053 292.971 + vertex 893.778 297.196 291.365 + endloop + endfacet + facet normal 0.850448 -0.338433 -0.402743 + outer loop + vertex 895.178 299.106 292.717 + vertex 894.172 296.338 292.918 + vertex 893.778 297.196 291.365 + endloop + endfacet + facet normal 0.870251 -0.306252 -0.385839 + outer loop + vertex 896.503 302.37 293.114 + vertex 895.178 299.106 292.717 + vertex 896.343 304.133 291.352 + endloop + endfacet + facet normal 0.880083 -0.293098 -0.373562 + outer loop + vertex 897.686 306.362 292.768 + vertex 896.503 302.37 293.114 + vertex 896.343 304.133 291.352 + endloop + endfacet + facet normal 0.88379 -0.249 -0.396124 + outer loop + vertex 898.798 309.717 293.142 + vertex 897.686 306.362 292.768 + vertex 898.613 311.666 291.503 + endloop + endfacet + facet normal 0.884592 -0.247964 -0.394982 + outer loop + vertex 899.358 312.081 292.912 + vertex 898.798 309.717 293.142 + vertex 898.613 311.666 291.503 + endloop + endfacet + facet normal 0.889085 -0.201429 -0.41104 + outer loop + vertex 899.826 314.628 292.676 + vertex 899.358 312.081 292.912 + vertex 898.613 311.666 291.503 + endloop + endfacet + facet normal 0.914666 -0.170658 -0.366419 + outer loop + vertex 900.642 318.179 293.059 + vertex 899.826 314.628 292.676 + vertex 900.176 319.469 291.294 + endloop + endfacet + facet normal 0.921633 -0.15409 -0.356157 + outer loop + vertex 901.172 322.156 292.709 + vertex 900.642 318.179 293.059 + vertex 900.176 319.469 291.294 + endloop + endfacet + facet normal 0.930607 -0.111573 -0.348601 + outer loop + vertex 901.784 326.001 293.113 + vertex 901.172 322.156 292.709 + vertex 901.235 327.064 291.306 + endloop + endfacet + facet normal 0.937251 -0.088719 -0.33718 + outer loop + vertex 902.02 329.904 292.742 + vertex 901.784 326.001 293.113 + vertex 901.235 327.064 291.306 + endloop + endfacet + facet normal 0.942204 -0.0524613 -0.330907 + outer loop + vertex 902.372 333.8 293.125 + vertex 902.02 329.904 292.742 + vertex 901.787 334.617 291.329 + endloop + endfacet + facet normal 0.945332 -0.0354377 -0.32418 + outer loop + vertex 902.362 337.355 292.707 + vertex 902.372 333.8 293.125 + vertex 901.787 334.617 291.329 + endloop + endfacet + facet normal 0.938377 -0.0104639 -0.345456 + outer loop + vertex 902.463 340.033 292.9 + vertex 902.362 337.355 292.707 + vertex 901.903 341.898 291.323 + endloop + endfacet + facet normal 0.948726 0.0179031 -0.315593 + outer loop + vertex 902.396 343.926 292.922 + vertex 902.463 340.033 292.9 + vertex 901.903 341.898 291.323 + endloop + endfacet + facet normal 0.942404 0.0255657 -0.333498 + outer loop + vertex 902.29 347.917 292.927 + vertex 902.396 343.926 292.922 + vertex 901.682 349.513 291.332 + endloop + endfacet + facet normal 0.949802 0.0536616 -0.308214 + outer loop + vertex 902.05 352.024 292.901 + vertex 902.29 347.917 292.927 + vertex 901.682 349.513 291.332 + endloop + endfacet + facet normal 0.943733 0.0640738 -0.324442 + outer loop + vertex 901.784 355.896 292.894 + vertex 902.05 352.024 292.901 + vertex 901.133 357.354 291.288 + endloop + endfacet + facet normal 0.949162 0.0924074 -0.30092 + outer loop + vertex 901.389 359.924 292.885 + vertex 901.784 355.896 292.894 + vertex 901.133 357.354 291.288 + endloop + endfacet + facet normal 0.946043 0.100672 -0.308007 + outer loop + vertex 900.996 363.681 292.904 + vertex 901.389 359.924 292.885 + vertex 900.326 365.053 291.296 + endloop + endfacet + facet normal 0.949361 0.125911 -0.287853 + outer loop + vertex 900.462 367.731 292.914 + vertex 900.996 363.681 292.904 + vertex 900.326 365.053 291.296 + endloop + endfacet + facet normal 0.94638 0.132539 -0.294615 + outer loop + vertex 899.938 371.527 292.94 + vertex 900.462 367.731 292.914 + vertex 899.254 372.789 291.309 + endloop + endfacet + facet normal 0.947918 0.153302 -0.279197 + outer loop + vertex 899.261 375.657 292.91 + vertex 899.938 371.527 292.94 + vertex 899.254 372.789 291.309 + endloop + endfacet + facet normal 0.945363 0.173534 -0.275998 + outer loop + vertex 898.037 382.312 292.693 + vertex 898.641 379.288 292.862 + vertex 897.989 380.364 291.303 + endloop + endfacet + facet normal 0.880382 0.373859 -0.291815 + outer loop + vertex 874.418 465.655 294.529 + vertex 875.31 463.15 294.011 + vertex 873.514 465.984 292.223 + endloop + endfacet + facet normal 0.876532 0.385157 -0.288698 + outer loop + vertex 873.528 467.255 293.961 + vertex 874.418 465.655 294.529 + vertex 873.514 465.984 292.223 + endloop + endfacet + facet normal 0.225235 -0.749311 -0.622738 + outer loop + vertex 851.047 248.833 290.437 + vertex 850.266 246.433 293.042 + vertex 850.212 247.179 292.125 + endloop + endfacet + facet normal 0.280763 -0.723149 -0.631053 + outer loop + vertex 850.266 246.433 293.042 + vertex 849.816 244.651 294.884 + vertex 849.386 244.797 294.526 + endloop + endfacet + facet normal 0.307504 -0.713184 -0.629928 + outer loop + vertex 849.816 244.651 294.884 + vertex 850.899 245.297 294.681 + vertex 850.508 244.279 295.643 + endloop + endfacet + facet normal 0.359976 -0.782324 -0.508317 + outer loop + vertex 852.38 253.03 285.19 + vertex 851.827 251.071 287.812 + vertex 851.276 250.431 288.408 + endloop + endfacet + facet normal 0.273099 -0.77049 -0.575989 + outer loop + vertex 851.827 251.071 287.812 + vertex 851.047 248.833 290.437 + vertex 851.276 250.431 288.408 + endloop + endfacet + facet normal 0.217196 -0.864083 -0.454078 + outer loop + vertex 854.019 257.289 278.91 + vertex 853.558 257.315 278.639 + vertex 854.385 259.126 275.588 + endloop + endfacet + facet normal 0.175619 -0.850424 -0.49592 + outer loop + vertex 853.558 257.315 278.639 + vertex 853.044 255.375 281.784 + vertex 852.994 256.161 280.418 + endloop + endfacet + facet normal 0.18043 -0.82618 -0.533733 + outer loop + vertex 853.044 255.375 281.784 + vertex 852.38 253.03 285.19 + vertex 852.294 253.651 284.199 + endloop + endfacet + facet normal 0.133419 -0.830467 0.540855 + outer loop + vertex 851.071 252.12 57.1707 + vertex 851.858 254.511 60.6489 + vertex 851.315 253.689 59.5201 + endloop + endfacet + facet normal 0.182824 -0.849243 0.495341 + outer loop + vertex 851.858 254.511 60.6489 + vertex 852.584 256.65 64.0464 + vertex 852.084 256.069 63.2361 + endloop + endfacet + facet normal 0.275385 -0.852903 0.443531 + outer loop + vertex 852.584 256.65 64.0464 + vertex 853.102 256.578 63.5885 + vertex 853.389 258.188 66.5049 + endloop + endfacet + facet normal 0.238651 -0.778231 0.580864 + outer loop + vertex 849.327 247.255 51.0725 + vertex 850.202 249.639 53.9078 + vertex 849.558 248.713 52.9314 + endloop + endfacet + facet normal 0.173898 -0.805731 0.566177 + outer loop + vertex 850.202 249.639 53.9078 + vertex 851.071 252.12 57.1707 + vertex 850.449 251.195 56.0451 + endloop + endfacet + facet normal 0.372831 -0.689958 0.620447 + outer loop + vertex 849.106 244.72 47.8603 + vertex 847.972 243.793 47.5108 + vertex 848.626 243.756 47.0771 + endloop + endfacet + facet normal 0.326646 -0.721704 0.610284 + outer loop + vertex 847.972 243.793 47.5108 + vertex 848.5 245.159 48.8439 + vertex 847.56 243.901 47.8596 + endloop + endfacet + facet normal 0.302511 -0.747819 0.590977 + outer loop + vertex 848.5 245.159 48.8439 + vertex 849.327 247.255 51.0725 + vertex 848.634 246.294 50.2113 + endloop + endfacet + facet normal 0.381362 -0.689935 -0.615267 + outer loop + vertex 852.404 245.28 295.557 + vertex 854.597 246.755 295.262 + vertex 853.354 245.464 295.939 + endloop + endfacet + facet normal 0.449119 -0.701219 -0.5537 + outer loop + vertex 854.597 246.755 295.262 + vertex 854.734 247.406 294.549 + vertex 857.839 249.544 294.36 + endloop + endfacet + facet normal 0.33079 -0.682449 -0.651798 + outer loop + vertex 850.508 244.279 295.643 + vertex 852.404 245.28 295.557 + vertex 850.994 243.855 296.334 + endloop + endfacet + facet normal 0.232994 -0.877421 -0.41934 + outer loop + vertex 854.667 260.987 271.852 + vertex 854.385 259.126 275.588 + vertex 853.697 258.903 275.672 + endloop + endfacet + facet normal 0.141315 -0.919484 -0.366851 + outer loop + vertex 855.048 264.453 263.774 + vertex 854.891 262.853 267.723 + vertex 854.427 263.327 266.357 + endloop + endfacet + facet normal 0.159972 -0.902737 -0.399344 + outer loop + vertex 854.891 262.853 267.723 + vertex 854.667 260.987 271.852 + vertex 854.177 261.427 270.661 + endloop + endfacet + facet normal 0.151129 -0.92542 -0.347501 + outer loop + vertex 855.96 266.66 258.294 + vertex 855.048 264.453 263.774 + vertex 854.671 265.327 261.282 + endloop + endfacet + facet normal 0.164457 -0.940388 -0.297697 + outer loop + vertex 855.934 269.219 250.195 + vertex 855.96 266.66 258.294 + vertex 854.948 267.359 255.524 + endloop + endfacet + facet normal 0.144042 -0.95447 -0.261225 + outer loop + vertex 855.963 271.389 242.283 + vertex 855.934 269.219 250.195 + vertex 854.9 270.194 246.061 + endloop + endfacet + facet normal 0.151111 -0.963678 -0.220205 + outer loop + vertex 855.586 273.102 234.525 + vertex 855.963 271.389 242.283 + vertex 854.881 271.773 239.857 + endloop + endfacet + facet normal 0.110974 -0.975209 -0.191445 + outer loop + vertex 855.342 274.675 226.373 + vertex 855.586 273.102 234.525 + vertex 854.622 273.829 230.264 + endloop + endfacet + facet normal 0.125274 -0.978505 -0.163815 + outer loop + vertex 854.964 275.975 218.318 + vertex 855.342 274.675 226.373 + vertex 854.428 274.989 223.797 + endloop + endfacet + facet normal 0.138453 -0.981304 -0.133694 + outer loop + vertex 854.742 277.085 209.942 + vertex 854.964 275.975 218.318 + vertex 854.257 276.33 214.98 + endloop + endfacet + facet normal 0.137278 -0.984866 -0.105798 + outer loop + vertex 854.577 277.948 201.69 + vertex 854.742 277.085 209.942 + vertex 854.01 277.383 206.215 + endloop + endfacet + facet normal 0.149912 -0.985381 -0.0809414 + outer loop + vertex 854.581 278.582 193.982 + vertex 854.577 277.948 201.69 + vertex 853.892 278.135 198.149 + endloop + endfacet + facet normal 0.163686 -0.984951 -0.0554807 + outer loop + vertex 854.412 278.977 186.467 + vertex 854.581 278.582 193.982 + vertex 853.838 278.562 192.139 + endloop + endfacet + facet normal 0.142858 -0.989197 -0.0328739 + outer loop + vertex 854.364 279.242 178.297 + vertex 854.412 278.977 186.467 + vertex 853.825 278.998 183.306 + endloop + endfacet + facet normal 0.149561 -0.988727 -0.00707404 + outer loop + vertex 854.35 279.298 170.158 + vertex 854.364 279.242 178.297 + vertex 853.785 279.177 175.091 + endloop + endfacet + facet normal 0.150149 -0.988511 0.0173665 + outer loop + vertex 854.46 279.178 162.388 + vertex 854.35 279.298 170.158 + vertex 853.726 279.138 166.455 + endloop + endfacet + facet normal 0.16633 -0.985148 0.0426391 + outer loop + vertex 854.402 278.847 154.965 + vertex 854.46 279.178 162.388 + vertex 853.739 278.978 160.568 + endloop + endfacet + facet normal 0.154744 -0.985751 0.0659511 + outer loop + vertex 854.468 278.31 146.786 + vertex 854.402 278.847 154.965 + vertex 853.852 278.553 151.858 + endloop + endfacet + facet normal 0.144838 -0.98525 0.0911235 + outer loop + vertex 854.565 277.562 138.543 + vertex 854.468 278.31 146.786 + vertex 853.862 277.877 143.06 + endloop + endfacet + facet normal 0.16644 -0.979188 0.116138 + outer loop + vertex 854.804 276.687 130.823 + vertex 854.565 277.562 138.543 + vertex 853.967 277.035 134.952 + endloop + endfacet + facet normal 0.179434 -0.973108 0.144442 + outer loop + vertex 854.812 275.605 123.52 + vertex 854.804 276.687 130.823 + vertex 854.075 276.283 129.008 + endloop + endfacet + facet normal 0.141273 -0.975171 0.170536 + outer loop + vertex 855.007 274.316 115.989 + vertex 854.812 275.605 123.52 + vertex 854.301 274.995 120.458 + endloop + endfacet + facet normal 0.129449 -0.971669 0.197744 + outer loop + vertex 855.164 272.799 108.435 + vertex 855.007 274.316 115.989 + vertex 854.374 273.728 113.517 + endloop + endfacet + facet normal 0.14796 -0.963777 0.221905 + outer loop + vertex 855.618 271.114 100.812 + vertex 855.164 272.799 108.435 + vertex 854.576 271.702 104.062 + endloop + endfacet + facet normal 0.167493 -0.950294 0.262466 + outer loop + vertex 855.544 268.981 93.1359 + vertex 855.618 271.114 100.812 + vertex 854.645 270.29 98.4504 + endloop + endfacet + facet normal 0.173059 -0.938401 0.299089 + outer loop + vertex 855.512 266.322 84.8131 + vertex 855.544 268.981 93.1359 + vertex 854.527 267.326 88.5334 + endloop + endfacet + facet normal 0.174898 -0.922304 0.344625 + outer loop + vertex 854.657 264.009 79.0569 + vertex 855.512 266.322 84.8131 + vertex 854.197 265.247 82.6019 + endloop + endfacet + facet normal 0.182446 -0.897972 0.400449 + outer loop + vertex 853.81 260.14 70.3078 + vertex 854.208 262.1 74.5208 + vertex 853.496 261.245 72.9269 + endloop + endfacet + facet normal 0.155227 -0.915903 0.37017 + outer loop + vertex 854.208 262.1 74.5208 + vertex 854.657 264.009 79.0569 + vertex 853.867 263.201 77.389 + endloop + endfacet + facet normal 0.234368 -0.875133 0.423336 + outer loop + vertex 853.389 258.188 66.5049 + vertex 853.81 260.14 70.3078 + vertex 852.889 258.696 67.8324 + endloop + endfacet + facet normal 0.53243 -0.725688 0.43577 + outer loop + vertex 853.879 249.373 50.4008 + vertex 853.392 248.037 48.7701 + vertex 857.721 251.631 49.4655 + endloop + endfacet + facet normal 0.488707 -0.751138 0.443798 + outer loop + vertex 853.572 250.43 52.527 + vertex 853.879 249.373 50.4008 + vertex 856.024 251.711 51.9956 + endloop + endfacet + facet normal 0.424803 -0.657606 0.622171 + outer loop + vertex 853.053 246.772 47.3855 + vertex 850.158 244.559 47.023 + vertex 852.241 245.873 46.9897 + endloop + endfacet + facet normal 0.42405 -0.709738 0.562543 + outer loop + vertex 850.158 244.559 47.023 + vertex 848.642 243.475 46.7976 + vertex 850.002 244.1 46.5611 + endloop + endfacet + facet normal 0.272248 -0.669946 0.690691 + outer loop + vertex 848.642 243.475 46.7976 + vertex 848.626 243.756 47.0771 + vertex 847.08 242.431 46.4005 + endloop + endfacet + facet normal 0.482453 -0.669229 -0.565129 + outer loop + vertex 857.839 249.544 294.36 + vertex 861.76 252.668 294.008 + vertex 859.423 250.243 294.885 + endloop + endfacet + facet normal 0.55802 -0.728429 0.397498 + outer loop + vertex 860.033 254.817 52.0597 + vertex 856.024 251.711 51.9956 + vertex 857.721 251.631 49.4655 + endloop + endfacet + facet normal 0.497666 -0.682476 0.535308 + outer loop + vertex 857.363 250.424 48.0334 + vertex 853.053 246.772 47.3855 + vertex 855.962 248.817 47.2881 + endloop + endfacet + facet normal 0.539854 -0.65684 -0.526421 + outer loop + vertex 861.76 252.668 294.008 + vertex 866.931 257.952 292.717 + vertex 864.096 254.271 294.403 + endloop + endfacet + facet normal 0.621131 -0.697818 0.356717 + outer loop + vertex 864.682 259.355 52.842 + vertex 860.033 254.817 52.0597 + vertex 864.157 257.54 50.204 + endloop + endfacet + facet normal 0.532095 -0.649861 0.54273 + outer loop + vertex 863.467 255.981 48.7043 + vertex 857.363 250.424 48.0334 + vertex 860.887 253.13 47.8191 + endloop + endfacet + facet normal 0.618635 -0.714615 0.326522 + outer loop + vertex 857.721 251.631 49.4655 + vertex 864.157 257.54 50.204 + vertex 860.033 254.817 52.0597 + endloop + endfacet + facet normal 0.60508 -0.624257 -0.494148 + outer loop + vertex 866.931 257.952 292.717 + vertex 872.936 264.259 292.103 + vertex 870.667 260.832 293.654 + endloop + endfacet + facet normal 0.675362 -0.655903 0.337161 + outer loop + vertex 869.463 264.709 53.6799 + vertex 864.682 259.355 52.842 + vertex 869.413 263.163 50.772 + endloop + endfacet + facet normal 0.569597 -0.598632 0.563204 + outer loop + vertex 868.883 261.616 49.2156 + vertex 863.467 255.981 48.7043 + vertex 867.909 260.111 48.6002 + endloop + endfacet + facet normal 0.675077 -0.663565 0.322416 + outer loop + vertex 864.157 257.54 50.204 + vertex 869.413 263.163 50.772 + vertex 864.682 259.355 52.842 + endloop + endfacet + facet normal 0.673408 -0.587345 -0.448941 + outer loop + vertex 872.936 264.259 292.103 + vertex 877.855 269.929 292.065 + vertex 875.143 265.633 293.616 + endloop + endfacet + facet normal 0.72435 -0.614658 0.31227 + outer loop + vertex 874.28 270.624 54.1501 + vertex 869.463 264.709 53.6799 + vertex 874.305 269.136 51.1619 + endloop + endfacet + facet normal 0.648255 -0.570158 0.504664 + outer loop + vertex 873.919 267.552 49.4527 + vertex 868.883 261.616 49.2156 + vertex 872.266 265.041 48.7403 + endloop + endfacet + facet normal 0.724392 -0.613772 0.313911 + outer loop + vertex 869.413 263.163 50.772 + vertex 874.305 269.136 51.1619 + vertex 869.463 264.709 53.6799 + endloop + endfacet + facet normal 0.716193 -0.540005 -0.442112 + outer loop + vertex 877.855 269.929 292.065 + vertex 882.578 276.386 291.827 + vertex 880.237 272.023 293.364 + endloop + endfacet + facet normal 0.770969 -0.563552 0.296675 + outer loop + vertex 878.71 276.833 54.4314 + vertex 874.28 270.624 54.1501 + vertex 878.855 275.422 51.3736 + endloop + endfacet + facet normal 0.70211 -0.528167 0.477579 + outer loop + vertex 878.725 274.125 49.6562 + vertex 873.919 267.552 49.4527 + vertex 877.151 271.401 48.9583 + endloop + endfacet + facet normal 0.770775 -0.567657 0.289261 + outer loop + vertex 874.305 269.136 51.1619 + vertex 878.855 275.422 51.3736 + vertex 874.28 270.624 54.1501 + endloop + endfacet + facet normal 0.755733 -0.488883 -0.435731 + outer loop + vertex 882.578 276.386 291.827 + vertex 886.852 283.295 291.488 + vertex 884.981 278.937 293.133 + endloop + endfacet + facet normal 0.814066 -0.510613 0.276715 + outer loop + vertex 882.628 283.201 54.6565 + vertex 878.71 276.833 54.4314 + vertex 883.001 282.119 51.5611 + endloop + endfacet + facet normal 0.734425 -0.480787 0.479024 + outer loop + vertex 882.721 280.432 49.861 + vertex 878.725 274.125 49.6562 + vertex 881.976 278.679 49.2433 + endloop + endfacet + facet normal 0.814063 -0.511662 0.27478 + outer loop + vertex 878.855 275.422 51.3736 + vertex 883.001 282.119 51.5611 + vertex 878.71 276.833 54.4314 + endloop + endfacet + facet normal 0.791514 -0.436232 -0.428027 + outer loop + vertex 886.852 283.295 291.488 + vertex 890.619 290.018 291.602 + vertex 888.962 285.616 293.026 + endloop + endfacet + facet normal 0.854726 -0.459281 0.241877 + outer loop + vertex 885.417 288.697 55.2341 + vertex 882.628 283.201 54.6565 + vertex 886.961 289.81 51.8948 + endloop + endfacet + facet normal 0.773422 -0.428899 0.46676 + outer loop + vertex 886.684 287.66 49.9361 + vertex 882.721 280.432 49.861 + vertex 885.289 284.379 49.2328 + endloop + endfacet + facet normal 0.853734 -0.450809 0.260595 + outer loop + vertex 883.001 282.119 51.5611 + vertex 886.961 289.81 51.8948 + vertex 882.628 283.201 54.6565 + endloop + endfacet + facet normal 0.82452 -0.376874 -0.422058 + outer loop + vertex 890.619 290.018 291.602 + vertex 893.778 297.196 291.365 + vertex 892.707 293.053 292.971 + endloop + endfacet + facet normal 0.878197 -0.390992 0.27549 + outer loop + vertex 888.972 295.893 54.1165 + vertex 885.417 288.697 55.2341 + vertex 886.961 289.81 51.8948 + endloop + endfacet + facet normal 0.782305 -0.363828 0.505597 + outer loop + vertex 889.877 294.63 50.0102 + vertex 886.684 287.66 49.9361 + vertex 889.286 292.616 49.4759 + endloop + endfacet + facet normal 0.879193 -0.390442 0.273082 + outer loop + vertex 886.961 289.81 51.8948 + vertex 890.406 297.007 51.0943 + vertex 888.972 295.893 54.1165 + endloop + endfacet + facet normal 0.84524 -0.313248 -0.432949 + outer loop + vertex 893.778 297.196 291.365 + vertex 896.343 304.133 291.352 + vertex 895.178 299.106 292.717 + endloop + endfacet + facet normal 0.902834 -0.332217 0.272987 + outer loop + vertex 891.789 304.065 54.7444 + vertex 888.972 295.893 54.1165 + vertex 892.445 303.258 51.5919 + endloop + endfacet + facet normal 0.83598 -0.315758 0.448815 + outer loop + vertex 892.513 301.621 50.0203 + vertex 889.877 294.63 50.0102 + vertex 891.783 298.811 49.4031 + endloop + endfacet + facet normal 0.896795 -0.31722 0.308431 + outer loop + vertex 890.406 297.007 51.0943 + vertex 892.445 303.258 51.5919 + vertex 888.972 295.893 54.1165 + endloop + endfacet + facet normal 0.868808 -0.253364 -0.425417 + outer loop + vertex 896.343 304.133 291.352 + vertex 898.613 311.666 291.503 + vertex 897.686 306.362 292.768 + endloop + endfacet + facet normal 0.936633 -0.274515 0.217622 + outer loop + vertex 893.464 310.342 55.4519 + vertex 891.789 304.065 54.7444 + vertex 894.647 311.726 52.1077 + endloop + endfacet + facet normal 0.851972 -0.257012 0.456167 + outer loop + vertex 894.748 309.274 50.1575 + vertex 892.513 301.621 50.0203 + vertex 894.184 306.235 49.4992 + endloop + endfacet + facet normal 0.930638 -0.257786 0.25973 + outer loop + vertex 892.445 303.258 51.5919 + vertex 894.647 311.726 52.1077 + vertex 891.789 304.065 54.7444 + endloop + endfacet + facet normal 0.880192 -0.187978 -0.435806 + outer loop + vertex 898.613 311.666 291.503 + vertex 900.176 319.469 291.294 + vertex 899.826 314.628 292.676 + endloop + endfacet + facet normal 0.947149 -0.196324 0.253704 + outer loop + vertex 895.333 318.103 54.4817 + vertex 893.464 310.342 55.4519 + vertex 894.647 311.726 52.1077 + endloop + endfacet + facet normal 0.876557 -0.186261 0.443795 + outer loop + vertex 896.382 317.082 50.2057 + vertex 894.748 309.274 50.1575 + vertex 896.125 314.316 49.5531 + endloop + endfacet + facet normal 0.952433 -0.190883 0.23756 + outer loop + vertex 894.647 311.726 52.1077 + vertex 896.442 319.751 51.3619 + vertex 895.333 318.103 54.4817 + endloop + endfacet + facet normal 0.907863 -0.125951 -0.399903 + outer loop + vertex 900.176 319.469 291.294 + vertex 901.235 327.064 291.306 + vertex 901.172 322.156 292.709 + endloop + endfacet + facet normal 0.969197 -0.137557 0.204294 + outer loop + vertex 896.154 325.207 55.3718 + vertex 895.333 318.103 54.4817 + vertex 897.106 326.917 52.0033 + endloop + endfacet + facet normal 0.907509 -0.125627 0.400807 + outer loop + vertex 897.453 324.759 50.1889 + vertex 896.382 317.082 50.2057 + vertex 897.372 322.053 49.5241 + endloop + endfacet + facet normal 0.953599 -0.113444 0.278889 + outer loop + vertex 896.442 319.751 51.3619 + vertex 897.106 326.917 52.0033 + vertex 895.333 318.103 54.4817 + endloop + endfacet + facet normal 0.924832 -0.0664018 -0.374536 + outer loop + vertex 901.235 327.064 291.306 + vertex 901.787 334.617 291.329 + vertex 902.02 329.904 292.742 + endloop + endfacet + facet normal 0.938271 -0.0671795 0.339314 + outer loop + vertex 897.973 332.126 50.2097 + vertex 897.453 324.759 50.1889 + vertex 898.048 329.9 49.5602 + endloop + endfacet + facet normal 0.933107 -0.0152049 -0.359277 + outer loop + vertex 901.787 334.617 291.329 + vertex 901.903 341.898 291.323 + vertex 902.362 337.355 292.707 + endloop + endfacet + facet normal 0.920275 -0.0135522 0.391036 + outer loop + vertex 898.085 339.237 50.1926 + vertex 897.973 332.126 50.2097 + vertex 898.249 336.135 49.6974 + endloop + endfacet + facet normal 0.944672 0.0277506 -0.32684 + outer loop + vertex 901.903 341.898 291.323 + vertex 901.682 349.513 291.332 + vertex 902.396 343.926 292.922 + endloop + endfacet + facet normal 0.934042 0.0311758 0.3558 + outer loop + vertex 897.801 346.851 50.2699 + vertex 898.085 339.237 50.1926 + vertex 898.119 343.852 49.6968 + endloop + endfacet + facet normal 0.943926 0.0642904 -0.323837 + outer loop + vertex 901.682 349.513 291.332 + vertex 901.133 357.354 291.288 + vertex 902.05 352.024 292.901 + endloop + endfacet + facet normal 0.943562 0.0712399 0.323442 + outer loop + vertex 897.2 354.712 50.2909 + vertex 897.801 346.851 50.2699 + vertex 897.608 351.967 49.7054 + endloop + endfacet + facet normal 0.945039 0.0993866 -0.311486 + outer loop + vertex 901.133 357.354 291.288 + vertex 900.326 365.053 291.296 + vertex 901.389 359.924 292.885 + endloop + endfacet + facet normal 0.945165 0.104614 0.309386 + outer loop + vertex 896.383 362.141 50.2748 + vertex 897.2 354.712 50.2909 + vertex 896.832 359.742 49.7141 + endloop + endfacet + facet normal 0.945758 0.13163 -0.297012 + outer loop + vertex 900.326 365.053 291.296 + vertex 899.254 372.789 291.309 + vertex 900.462 367.731 292.914 + endloop + endfacet + facet normal 0.95305 0.136924 0.27009 + outer loop + vertex 895.288 369.74 50.2859 + vertex 896.383 362.141 50.2748 + vertex 895.956 366.482 49.583 + endloop + endfacet + facet normal 0.94996 0.164643 0.26546 + outer loop + vertex 893.865 377.818 50.3685 + vertex 895.288 369.74 50.2859 + vertex 894.661 374.464 49.6024 + endloop + endfacet + facet normal 0.945988 0.191257 0.261777 + outer loop + vertex 892.12 386.565 50.2828 + vertex 893.865 377.818 50.3685 + vertex 893.102 382.562 49.6615 + endloop + endfacet + facet normal 0.94563 0.212572 0.246164 + outer loop + vertex 890.412 394.182 50.2672 + vertex 892.12 386.565 50.2828 + vertex 890.972 392.231 49.8018 + endloop + endfacet + facet normal 0.946962 0.23163 0.222733 + outer loop + vertex 888.632 401.437 50.2899 + vertex 890.412 394.182 50.2672 + vertex 889.383 398.987 49.6457 + endloop + endfacet + facet normal 0.883759 0.341431 -0.319992 + outer loop + vertex 877.694 454.418 291.121 + vertex 875.482 460.583 291.59 + vertex 877.291 457.049 292.815 + endloop + endfacet + facet normal 0.878765 0.357362 -0.31633 + outer loop + vertex 875.482 460.583 291.59 + vertex 873.514 465.984 292.223 + vertex 875.31 463.15 294.011 + endloop + endfacet + facet normal 0.355577 -0.719218 0.596901 + outer loop + vertex 847.972 243.793 47.5108 + vertex 847.08 242.431 46.4005 + vertex 848.626 243.756 47.0771 + endloop + endfacet + facet normal 0.293374 -0.850663 0.436238 + outer loop + vertex 852.889 258.696 67.8324 + vertex 852.584 256.65 64.0464 + vertex 853.389 258.188 66.5049 + endloop + endfacet + facet normal 0.224505 -0.86345 -0.45172 + outer loop + vertex 853.558 257.315 278.639 + vertex 853.697 258.903 275.672 + vertex 854.385 259.126 275.588 + endloop + endfacet + facet normal 0.324346 -0.698353 -0.638046 + outer loop + vertex 848.339 242.413 296.583 + vertex 849.816 244.651 294.884 + vertex 850.508 244.279 295.643 + endloop + endfacet + facet normal 0.432874 -0.69063 -0.579354 + outer loop + vertex 856.219 247.651 295.406 + vertex 854.597 246.755 295.262 + vertex 857.839 249.544 294.36 + endloop + endfacet + facet normal 0.535461 -0.752656 0.383133 + outer loop + vertex 853.879 249.373 50.4008 + vertex 857.721 251.631 49.4655 + vertex 856.024 251.711 51.9956 + endloop + endfacet + facet normal 0.497492 -0.72044 0.483185 + outer loop + vertex 682.282 136 47.5916 + vertex 678.698 135.609 50.6986 + vertex 676.674 131.994 47.3921 + endloop + endfacet + facet normal 0.507536 -0.71875 0.475191 + outer loop + vertex 676.674 131.994 47.3921 + vertex 678.698 135.609 50.6986 + vertex 673.962 132.44 50.9646 + endloop + endfacet + facet normal 0.544659 -0.643918 0.537322 + outer loop + vertex 683.592 140.624 52.0548 + vertex 682.024 138.536 51.1413 + vertex 684.812 139.409 49.3612 + endloop + endfacet + facet normal 0.505148 -0.662272 0.553374 + outer loop + vertex 686.772 138.835 46.8863 + vertex 684.812 139.409 49.3612 + vertex 682.282 136 47.5916 + endloop + endfacet + facet normal 0.52427 -0.67445 0.519863 + outer loop + vertex 678.698 135.609 50.6986 + vertex 682.282 136 47.5916 + vertex 682.024 138.536 51.1413 + endloop + endfacet + facet normal 0.537954 -0.666972 0.515513 + outer loop + vertex 684.812 139.409 49.3612 + vertex 682.024 138.536 51.1413 + vertex 682.282 136 47.5916 + endloop + endfacet + facet normal 0.552926 -0.615752 0.561358 + outer loop + vertex 688.34 142.105 48.9431 + vertex 686.214 142.691 51.6804 + vertex 687.06 140.934 48.9197 + endloop + endfacet + facet normal 0.562369 -0.608645 0.559725 + outer loop + vertex 687.06 140.934 48.9197 + vertex 686.214 142.691 51.6804 + vertex 685.08 141.654 51.6924 + endloop + endfacet + facet normal 0.533169 -0.60963 0.586585 + outer loop + vertex 690.161 141.881 47.0546 + vertex 688.34 142.105 48.9431 + vertex 688.754 140.757 47.166 + endloop + endfacet + facet normal 0.541829 -0.604078 0.58439 + outer loop + vertex 688.754 140.757 47.166 + vertex 688.34 142.105 48.9431 + vertex 687.06 140.934 48.9197 + endloop + endfacet + facet normal 0.527428 -0.627438 0.572836 + outer loop + vertex 688.754 140.757 47.166 + vertex 687.06 140.934 48.9197 + vertex 686.772 138.835 46.8863 + endloop + endfacet + facet normal 0.53547 -0.624455 0.56862 + outer loop + vertex 686.772 138.835 46.8863 + vertex 687.06 140.934 48.9197 + vertex 684.812 139.409 49.3612 + endloop + endfacet + facet normal 0.540016 -0.636272 0.550945 + outer loop + vertex 687.06 140.934 48.9197 + vertex 685.08 141.654 51.6924 + vertex 684.812 139.409 49.3612 + endloop + endfacet + facet normal 0.564445 -0.62592 0.538169 + outer loop + vertex 684.812 139.409 49.3612 + vertex 685.08 141.654 51.6924 + vertex 683.592 140.624 52.0548 + endloop + endfacet + facet normal 0.546552 -0.620682 0.56217 + outer loop + vertex 689.326 142.915 48.839 + vertex 687.094 143.486 51.6397 + vertex 688.954 142.756 49.025 + endloop + endfacet + facet normal 0.568215 -0.593503 0.569988 + outer loop + vertex 688.954 142.756 49.025 + vertex 687.094 143.486 51.6397 + vertex 686.775 143.327 51.7919 + endloop + endfacet + facet normal 0.516807 -0.629097 0.580644 + outer loop + vertex 691.017 142.74 47.1448 + vertex 689.326 142.915 48.839 + vertex 690.713 142.648 47.3154 + endloop + endfacet + facet normal 0.548949 -0.580502 0.601392 + outer loop + vertex 690.713 142.648 47.3154 + vertex 689.326 142.915 48.839 + vertex 688.954 142.756 49.025 + endloop + endfacet + facet normal 0.542644 -0.592241 0.595641 + outer loop + vertex 690.713 142.648 47.3154 + vertex 688.954 142.756 49.025 + vertex 690.161 141.881 47.0546 + endloop + endfacet + facet normal 0.54548 -0.589226 0.596041 + outer loop + vertex 690.161 141.881 47.0546 + vertex 688.954 142.756 49.025 + vertex 688.34 142.105 48.9431 + endloop + endfacet + facet normal 0.562486 -0.60162 0.567153 + outer loop + vertex 688.954 142.756 49.025 + vertex 686.775 143.327 51.7919 + vertex 688.34 142.105 48.9431 + endloop + endfacet + facet normal 0.565596 -0.598391 0.567476 + outer loop + vertex 688.34 142.105 48.9431 + vertex 686.775 143.327 51.7919 + vertex 686.214 142.691 51.6804 + endloop + endfacet + facet normal -0.684856 -0.0169163 -0.728482 + outer loop + vertex 691.443 142.683 46.7455 + vertex 689.98 142.759 48.1188 + vertex 691.017 142.74 47.1448 + endloop + endfacet + facet normal -0.598659 0.473248 -0.646253 + outer loop + vertex 691.017 142.74 47.1448 + vertex 689.98 142.759 48.1188 + vertex 689.326 142.915 48.839 + endloop + endfacet + facet normal -0.371767 -0.917853 -0.13905 + outer loop + vertex 689.98 142.759 48.1188 + vertex 687.673 143.277 50.8691 + vertex 689.326 142.915 48.839 + endloop + endfacet + facet normal -0.654033 0.44469 -0.611957 + outer loop + vertex 689.326 142.915 48.839 + vertex 687.673 143.277 50.8691 + vertex 687.094 143.486 51.6397 + endloop + endfacet + facet normal 0.511351 -0.725702 0.460301 + outer loop + vertex 678.698 135.609 50.6986 + vertex 676.373 136.485 54.6623 + vertex 673.962 132.44 50.9646 + endloop + endfacet + facet normal 0.543654 -0.714691 0.440065 + outer loop + vertex 675.316 138.104 58.5976 + vertex 672.033 134.45 56.7194 + vertex 676.373 136.485 54.6623 + endloop + endfacet + facet normal 0.542697 -0.719603 0.433187 + outer loop + vertex 672.033 134.45 56.7194 + vertex 673.962 132.44 50.9646 + vertex 676.373 136.485 54.6623 + endloop + endfacet + facet normal 0.584869 -0.656516 0.476357 + outer loop + vertex 681.768 141.015 54.5877 + vertex 679.852 141.883 58.1376 + vertex 679.583 138.881 54.33 + endloop + endfacet + facet normal 0.603767 -0.646153 0.466853 + outer loop + vertex 679.583 138.881 54.33 + vertex 679.852 141.883 58.1376 + vertex 677.74 139.921 58.1542 + endloop + endfacet + facet normal 0.567171 -0.648091 0.508227 + outer loop + vertex 683.592 140.624 52.0548 + vertex 681.768 141.015 54.5877 + vertex 682.024 138.536 51.1413 + endloop + endfacet + facet normal 0.570873 -0.645872 0.506906 + outer loop + vertex 682.024 138.536 51.1413 + vertex 681.768 141.015 54.5877 + vertex 679.583 138.881 54.33 + endloop + endfacet + facet normal 0.539421 -0.686737 0.487255 + outer loop + vertex 682.024 138.536 51.1413 + vertex 679.583 138.881 54.33 + vertex 678.698 135.609 50.6986 + endloop + endfacet + facet normal 0.556916 -0.679997 0.476916 + outer loop + vertex 678.698 135.609 50.6986 + vertex 679.583 138.881 54.33 + vertex 676.373 136.485 54.6623 + endloop + endfacet + facet normal 0.561642 -0.688927 0.458189 + outer loop + vertex 679.583 138.881 54.33 + vertex 677.74 139.921 58.1542 + vertex 676.373 136.485 54.6623 + endloop + endfacet + facet normal 0.589303 -0.679087 0.437678 + outer loop + vertex 676.373 136.485 54.6623 + vertex 677.74 139.921 58.1542 + vertex 675.316 138.104 58.5976 + endloop + endfacet + facet normal 0.608032 -0.617669 0.498781 + outer loop + vertex 684.056 143.55 55.01 + vertex 682.086 144.552 58.6519 + vertex 683.145 142.543 54.8738 + endloop + endfacet + facet normal 0.626046 -0.602085 0.49554 + outer loop + vertex 683.145 142.543 54.8738 + vertex 682.086 144.552 58.6519 + vertex 681.274 143.479 58.3738 + endloop + endfacet + facet normal 0.574166 -0.621864 0.532558 + outer loop + vertex 686.214 142.691 51.6804 + vertex 684.056 143.55 55.01 + vertex 685.08 141.654 51.6924 + endloop + endfacet + facet normal 0.591998 -0.607354 0.529773 + outer loop + vertex 685.08 141.654 51.6924 + vertex 684.056 143.55 55.01 + vertex 683.145 142.543 54.8738 + endloop + endfacet + facet normal 0.567632 -0.635884 0.52292 + outer loop + vertex 685.08 141.654 51.6924 + vertex 683.145 142.543 54.8738 + vertex 683.592 140.624 52.0548 + endloop + endfacet + facet normal 0.585409 -0.623979 0.517635 + outer loop + vertex 683.592 140.624 52.0548 + vertex 683.145 142.543 54.8738 + vertex 681.768 141.015 54.5877 + endloop + endfacet + facet normal 0.600317 -0.632198 0.489842 + outer loop + vertex 683.145 142.543 54.8738 + vertex 681.274 143.479 58.3738 + vertex 681.768 141.015 54.5877 + endloop + endfacet + facet normal 0.616196 -0.620892 0.484557 + outer loop + vertex 681.768 141.015 54.5877 + vertex 681.274 143.479 58.3738 + vertex 679.852 141.883 58.1376 + endloop + endfacet + facet normal 0.597729 -0.619084 0.509368 + outer loop + vertex 684.721 144.307 55.1097 + vertex 682.636 145.209 58.6521 + vertex 684.525 144.15 55.1493 + endloop + endfacet + facet normal 0.717876 -0.456976 0.525192 + outer loop + vertex 684.525 144.15 55.1493 + vertex 682.636 145.209 58.6521 + vertex 682.469 145.101 58.7864 + endloop + endfacet + facet normal 0.56763 -0.624869 0.536036 + outer loop + vertex 687.094 143.486 51.6397 + vertex 684.721 144.307 55.1097 + vertex 686.775 143.327 51.7919 + endloop + endfacet + facet normal 0.588847 -0.599792 0.541765 + outer loop + vertex 686.775 143.327 51.7919 + vertex 684.721 144.307 55.1097 + vertex 684.525 144.15 55.1493 + endloop + endfacet + facet normal 0.582302 -0.608215 0.539443 + outer loop + vertex 686.775 143.327 51.7919 + vertex 684.525 144.15 55.1493 + vertex 686.214 142.691 51.6804 + endloop + endfacet + facet normal 0.597888 -0.592144 0.540274 + outer loop + vertex 686.214 142.691 51.6804 + vertex 684.525 144.15 55.1493 + vertex 684.056 143.55 55.01 + endloop + endfacet + facet normal 0.618623 -0.600533 0.506622 + outer loop + vertex 684.525 144.15 55.1493 + vertex 682.469 145.101 58.7864 + vertex 684.056 143.55 55.01 + endloop + endfacet + facet normal 0.644423 -0.573129 0.506204 + outer loop + vertex 684.056 143.55 55.01 + vertex 682.469 145.101 58.7864 + vertex 682.086 144.552 58.6519 + endloop + endfacet + facet normal -0.633994 -0.720461 -0.281047 + outer loop + vertex 687.673 143.277 50.8691 + vertex 685.097 144.117 54.526 + vertex 687.094 143.486 51.6397 + endloop + endfacet + facet normal -0.742149 0.327227 -0.584925 + outer loop + vertex 687.094 143.486 51.6397 + vertex 685.097 144.117 54.526 + vertex 684.721 144.307 55.1097 + endloop + endfacet + facet normal -0.828202 -0.383368 -0.408791 + outer loop + vertex 685.097 144.117 54.526 + vertex 682.744 145.07 58.3997 + vertex 684.721 144.307 55.1097 + endloop + endfacet + facet normal -0.741952 0.399517 -0.538418 + outer loop + vertex 684.721 144.307 55.1097 + vertex 682.744 145.07 58.3997 + vertex 682.636 145.209 58.6521 + endloop + endfacet + facet normal 0.567159 -0.717484 0.404409 + outer loop + vertex 675.316 138.104 58.5976 + vertex 673.525 138.733 62.2265 + vertex 672.033 134.45 56.7194 + endloop + endfacet + facet normal 0.580669 -0.715721 0.38803 + outer loop + vertex 672.558 140.01 66.0275 + vertex 669.757 136.653 64.0274 + vertex 673.525 138.733 62.2265 + endloop + endfacet + facet normal 0.581559 -0.71094 0.395417 + outer loop + vertex 669.757 136.653 64.0274 + vertex 672.033 134.45 56.7194 + vertex 673.525 138.733 62.2265 + endloop + endfacet + facet normal 0.638532 -0.655673 0.402951 + outer loop + vertex 678.128 142.925 62.1047 + vertex 676.56 143.702 65.8536 + vertex 676.145 141.015 62.1398 + endloop + endfacet + facet normal 0.647815 -0.649778 0.397648 + outer loop + vertex 676.145 141.015 62.1398 + vertex 676.56 143.702 65.8536 + vertex 674.496 142.089 66.5798 + endloop + endfacet + facet normal 0.613262 -0.656612 0.439057 + outer loop + vertex 679.852 141.883 58.1376 + vertex 678.128 142.925 62.1047 + vertex 677.74 139.921 58.1542 + endloop + endfacet + facet normal 0.630258 -0.646588 0.429766 + outer loop + vertex 677.74 139.921 58.1542 + vertex 678.128 142.925 62.1047 + vertex 676.145 141.015 62.1398 + endloop + endfacet + facet normal 0.591562 -0.685223 0.424881 + outer loop + vertex 677.74 139.921 58.1542 + vertex 676.145 141.015 62.1398 + vertex 675.316 138.104 58.5976 + endloop + endfacet + facet normal 0.605007 -0.678682 0.416361 + outer loop + vertex 675.316 138.104 58.5976 + vertex 676.145 141.015 62.1398 + vertex 673.525 138.733 62.2265 + endloop + endfacet + facet normal 0.611344 -0.686841 0.393075 + outer loop + vertex 676.145 141.015 62.1398 + vertex 674.496 142.089 66.5798 + vertex 673.525 138.733 62.2265 + endloop + endfacet + facet normal 0.621098 -0.681599 0.386858 + outer loop + vertex 673.525 138.733 62.2265 + vertex 674.496 142.089 66.5798 + vertex 672.558 140.01 66.0275 + endloop + endfacet + facet normal 0.682211 -0.602432 0.414323 + outer loop + vertex 680.331 145.6 62.5363 + vertex 678.859 146.436 66.1756 + vertex 679.541 144.51 62.2539 + endloop + endfacet + facet normal 0.697092 -0.588232 0.409934 + outer loop + vertex 679.541 144.51 62.2539 + vertex 678.859 146.436 66.1756 + vertex 677.75 145.507 66.7287 + endloop + endfacet + facet normal 0.648229 -0.608925 0.457175 + outer loop + vertex 682.086 144.552 58.6519 + vertex 680.331 145.6 62.5363 + vertex 681.274 143.479 58.3738 + endloop + endfacet + facet normal 0.660978 -0.597358 0.454171 + outer loop + vertex 681.274 143.479 58.3738 + vertex 680.331 145.6 62.5363 + vertex 679.541 144.51 62.2539 + endloop + endfacet + facet normal 0.632475 -0.630315 0.450198 + outer loop + vertex 681.274 143.479 58.3738 + vertex 679.541 144.51 62.2539 + vertex 679.852 141.883 58.1376 + endloop + endfacet + facet normal 0.647709 -0.619035 0.44415 + outer loop + vertex 679.852 141.883 58.1376 + vertex 679.541 144.51 62.2539 + vertex 678.128 142.925 62.1047 + endloop + endfacet + facet normal 0.663148 -0.629153 0.405464 + outer loop + vertex 679.541 144.51 62.2539 + vertex 677.75 145.507 66.7287 + vertex 678.128 142.925 62.1047 + endloop + endfacet + facet normal 0.659464 -0.632137 0.406829 + outer loop + vertex 678.128 142.925 62.1047 + vertex 677.75 145.507 66.7287 + vertex 676.56 143.702 65.8536 + endloop + endfacet + facet normal 0.844989 -0.343989 0.409471 + outer loop + vertex 680.896 146.128 62.2166 + vertex 679.168 147.278 66.7473 + vertex 680.642 146.146 62.7565 + endloop + endfacet + facet normal 0.871195 -0.28229 0.40166 + outer loop + vertex 680.642 146.146 62.7565 + vertex 679.168 147.278 66.7473 + vertex 678.942 147.245 67.2163 + endloop + endfacet + facet normal 0.714757 -0.508615 0.480035 + outer loop + vertex 682.636 145.209 58.6521 + vertex 680.896 146.128 62.2166 + vertex 682.469 145.101 58.7864 + endloop + endfacet + facet normal 0.903627 -0.0400437 0.426445 + outer loop + vertex 682.469 145.101 58.7864 + vertex 680.896 146.128 62.2166 + vertex 680.642 146.146 62.7565 + endloop + endfacet + facet normal 0.670751 -0.580552 0.461576 + outer loop + vertex 682.469 145.101 58.7864 + vertex 680.642 146.146 62.7565 + vertex 682.086 144.552 58.6519 + endloop + endfacet + facet normal 0.678851 -0.571574 0.460939 + outer loop + vertex 682.086 144.552 58.6519 + vertex 680.642 146.146 62.7565 + vertex 680.331 145.6 62.5363 + endloop + endfacet + facet normal 0.711129 -0.570032 0.411533 + outer loop + vertex 680.642 146.146 62.7565 + vertex 678.942 147.245 67.2163 + vertex 680.331 145.6 62.5363 + endloop + endfacet + facet normal 0.682281 -0.602347 0.414332 + outer loop + vertex 680.331 145.6 62.5363 + vertex 678.942 147.245 67.2163 + vertex 678.859 146.436 66.1756 + endloop + endfacet + facet normal -0.822873 0.268053 -0.501027 + outer loop + vertex 682.744 145.07 58.3997 + vertex 681.232 145.832 61.2915 + vertex 682.636 145.209 58.6521 + endloop + endfacet + facet normal -0.405881 0.817364 -0.408873 + outer loop + vertex 682.636 145.209 58.6521 + vertex 681.232 145.832 61.2915 + vertex 680.896 146.128 62.2166 + endloop + endfacet + facet normal -0.634277 0.639254 -0.434796 + outer loop + vertex 681.232 145.832 61.2915 + vertex 680.086 146.498 63.9418 + vertex 680.896 146.128 62.2166 + endloop + endfacet + facet normal -0.380481 0.851359 -0.361139 + outer loop + vertex 680.896 146.128 62.2166 + vertex 680.086 146.498 63.9418 + vertex 679.168 147.278 66.7473 + endloop + endfacet + facet normal 0.591431 -0.715294 0.372241 + outer loop + vertex 672.558 140.01 66.0275 + vertex 671.913 142.321 71.494 + vertex 669.757 136.653 64.0274 + endloop + endfacet + facet normal 0.616008 -0.702859 0.355702 + outer loop + vertex 669.757 136.653 64.0274 + vertex 671.913 142.321 71.494 + vertex 667.39 138.438 71.6545 + endloop + endfacet + facet normal 0.631144 -0.684913 0.364076 + outer loop + vertex 672.558 140.01 66.0275 + vertex 674.496 142.089 66.5798 + vertex 671.913 142.321 71.494 + endloop + endfacet + facet normal 0.649233 -0.66207 0.374378 + outer loop + vertex 676.56 143.702 65.8536 + vertex 675.272 145.879 71.9354 + vertex 674.496 142.089 66.5798 + endloop + endfacet + facet normal 0.650943 -0.66097 0.373352 + outer loop + vertex 675.272 145.879 71.9354 + vertex 671.913 142.321 71.494 + vertex 674.496 142.089 66.5798 + endloop + endfacet + facet normal 0.682999 -0.629785 0.369976 + outer loop + vertex 676.56 143.702 65.8536 + vertex 677.75 145.507 66.7287 + vertex 675.272 145.879 71.9354 + endloop + endfacet + facet normal 0.698001 -0.612 0.37182 + outer loop + vertex 678.859 146.436 66.1756 + vertex 677.071 148.027 72.15 + vertex 677.75 145.507 66.7287 + endloop + endfacet + facet normal 0.692419 -0.617256 0.373565 + outer loop + vertex 677.071 148.027 72.15 + vertex 675.272 145.879 71.9354 + vertex 677.75 145.507 66.7287 + endloop + endfacet + facet normal 0.746606 -0.552524 0.370536 + outer loop + vertex 678.859 146.436 66.1756 + vertex 678.942 147.245 67.2163 + vertex 677.071 148.027 72.15 + endloop + endfacet + facet normal 0.815173 -0.451402 0.362946 + outer loop + vertex 679.168 147.278 66.7473 + vertex 677.441 148.737 72.4412 + vertex 678.942 147.245 67.2163 + endloop + endfacet + facet normal 0.752353 -0.544098 0.371379 + outer loop + vertex 677.441 148.737 72.4412 + vertex 677.071 148.027 72.15 + vertex 678.942 147.245 67.2163 + endloop + endfacet + facet normal 0.622231 -0.711296 0.326935 + outer loop + vertex 671.913 142.321 71.494 + vertex 669.89 144.409 79.8867 + vertex 667.39 138.438 71.6545 + endloop + endfacet + facet normal 0.642257 -0.699866 0.312561 + outer loop + vertex 667.39 138.438 71.6545 + vertex 669.89 144.409 79.8867 + vertex 665.798 140.472 79.4811 + endloop + endfacet + facet normal 0.665183 -0.669189 0.331235 + outer loop + vertex 675.272 145.879 71.9354 + vertex 673.018 147.685 80.1128 + vertex 671.913 142.321 71.494 + endloop + endfacet + facet normal 0.672112 -0.664209 0.327248 + outer loop + vertex 671.913 142.321 71.494 + vertex 673.018 147.685 80.1128 + vertex 669.89 144.409 79.8867 + endloop + endfacet + facet normal 0.706712 -0.625026 0.331513 + outer loop + vertex 677.071 148.027 72.15 + vertex 674.928 149.799 80.0613 + vertex 675.272 145.879 71.9354 + endloop + endfacet + facet normal 0.703725 -0.627757 0.332705 + outer loop + vertex 675.272 145.879 71.9354 + vertex 674.928 149.799 80.0613 + vertex 673.018 147.685 80.1128 + endloop + endfacet + facet normal 0.776716 -0.538486 0.326719 + outer loop + vertex 677.441 148.737 72.4412 + vertex 675.73 150.604 79.5879 + vertex 677.071 148.027 72.15 + endloop + endfacet + facet normal 0.758734 -0.560895 0.33124 + outer loop + vertex 677.071 148.027 72.15 + vertex 675.73 150.604 79.5879 + vertex 674.928 149.799 80.0613 + endloop + endfacet + facet normal 0.649252 -0.704472 0.286689 + outer loop + vertex 669.89 144.409 79.8867 + vertex 668.638 146.468 87.7818 + vertex 665.798 140.472 79.4811 + endloop + endfacet + facet normal 0.666111 -0.693965 0.273329 + outer loop + vertex 665.798 140.472 79.4811 + vertex 668.638 146.468 87.7818 + vertex 664.74 142.5 87.207 + endloop + endfacet + facet normal 0.681393 -0.670706 0.293014 + outer loop + vertex 673.018 147.685 80.1128 + vertex 671.605 149.761 88.1497 + vertex 669.89 144.409 79.8867 + endloop + endfacet + facet normal 0.696788 -0.659325 0.282448 + outer loop + vertex 669.89 144.409 79.8867 + vertex 671.605 149.761 88.1497 + vertex 668.638 146.468 87.7818 + endloop + endfacet + facet normal 0.712644 -0.63675 0.294429 + outer loop + vertex 674.928 149.799 80.0613 + vertex 673.464 151.825 87.9855 + vertex 673.018 147.685 80.1128 + endloop + endfacet + facet normal 0.722596 -0.62787 0.289197 + outer loop + vertex 673.018 147.685 80.1128 + vertex 673.464 151.825 87.9855 + vertex 671.605 149.761 88.1497 + endloop + endfacet + facet normal 0.75797 -0.583697 0.29117 + outer loop + vertex 675.73 150.604 79.5879 + vertex 674.377 152.549 87.0079 + vertex 674.928 149.799 80.0613 + endloop + endfacet + facet normal 0.765282 -0.575432 0.28848 + outer loop + vertex 674.928 149.799 80.0613 + vertex 674.377 152.549 87.0079 + vertex 673.464 151.825 87.9855 + endloop + endfacet + facet normal 0.672791 -0.696907 0.248341 + outer loop + vertex 668.638 146.468 87.7818 + vertex 667.852 148.438 95.4412 + vertex 664.74 142.5 87.207 + endloop + endfacet + facet normal 0.683198 -0.689894 0.239349 + outer loop + vertex 664.74 142.5 87.207 + vertex 667.852 148.438 95.4412 + vertex 664.013 144.436 94.8623 + endloop + endfacet + facet normal 0.705045 -0.663253 0.251012 + outer loop + vertex 671.605 149.761 88.1497 + vertex 670.732 151.754 95.8687 + vertex 668.638 146.468 87.7818 + endloop + endfacet + facet normal 0.716927 -0.653871 0.241804 + outer loop + vertex 668.638 146.468 87.7818 + vertex 670.732 151.754 95.8687 + vertex 667.852 148.438 95.4412 + endloop + endfacet + facet normal 0.728619 -0.6361 0.253953 + outer loop + vertex 673.464 151.825 87.9855 + vertex 672.529 153.879 95.8121 + vertex 671.605 149.761 88.1497 + endloop + endfacet + facet normal 0.74343 -0.622401 0.244805 + outer loop + vertex 671.605 149.761 88.1497 + vertex 672.529 153.879 95.8121 + vertex 670.732 151.754 95.8687 + endloop + endfacet + facet normal 0.753976 -0.604934 0.256076 + outer loop + vertex 674.377 152.549 87.0079 + vertex 673.427 154.649 94.7653 + vertex 673.464 151.825 87.9855 + endloop + endfacet + facet normal 0.779543 -0.57668 0.244443 + outer loop + vertex 673.464 151.825 87.9855 + vertex 673.427 154.649 94.7653 + vertex 672.529 153.879 95.8121 + endloop + endfacet + facet normal 0.688748 -0.691915 0.216517 + outer loop + vertex 667.852 148.438 95.4412 + vertex 667.309 150.267 103.012 + vertex 664.013 144.436 94.8623 + endloop + endfacet + facet normal 0.69474 -0.687611 0.211014 + outer loop + vertex 664.013 144.436 94.8623 + vertex 667.309 150.267 103.012 + vertex 663.493 146.253 102.496 + endloop + endfacet + facet normal 0.723586 -0.656113 0.214335 + outer loop + vertex 670.732 151.754 95.8687 + vertex 670.177 153.603 103.4 + vertex 667.852 148.438 95.4412 + endloop + endfacet + facet normal 0.729208 -0.651392 0.209629 + outer loop + vertex 667.852 148.438 95.4412 + vertex 670.177 153.603 103.4 + vertex 667.309 150.267 103.012 + endloop + endfacet + facet normal 0.748491 -0.627489 0.214521 + outer loop + vertex 672.529 153.879 95.8121 + vertex 671.947 155.768 103.37 + vertex 670.732 151.754 95.8687 + endloop + endfacet + facet normal 0.758857 -0.617345 0.207413 + outer loop + vertex 670.732 151.754 95.8687 + vertex 671.947 155.768 103.37 + vertex 670.177 153.603 103.4 + endloop + endfacet + facet normal 0.768971 -0.601217 0.217305 + outer loop + vertex 673.427 154.649 94.7653 + vertex 672.797 156.722 102.73 + vertex 672.529 153.879 95.8121 + endloop + endfacet + facet normal 0.794802 -0.571519 0.204096 + outer loop + vertex 672.529 153.879 95.8121 + vertex 672.797 156.722 102.73 + vertex 671.947 155.768 103.37 + endloop + endfacet + facet normal 0.699155 -0.689156 0.190385 + outer loop + vertex 667.309 150.267 103.012 + vertex 666.913 151.958 110.587 + vertex 663.493 146.253 102.496 + endloop + endfacet + facet normal 0.703268 -0.68604 0.186448 + outer loop + vertex 663.493 146.253 102.496 + vertex 666.913 151.958 110.587 + vertex 663.108 147.93 110.117 + endloop + endfacet + facet normal 0.734198 -0.652942 0.186065 + outer loop + vertex 670.177 153.603 103.4 + vertex 669.793 155.316 110.925 + vertex 667.309 150.267 103.012 + endloop + endfacet + facet normal 0.736839 -0.650617 0.183752 + outer loop + vertex 667.309 150.267 103.012 + vertex 669.793 155.316 110.925 + vertex 666.913 151.958 110.587 + endloop + endfacet + facet normal 0.762546 -0.620715 0.182309 + outer loop + vertex 671.947 155.768 103.37 + vertex 671.554 157.469 110.806 + vertex 670.177 153.603 103.4 + endloop + endfacet + facet normal 0.766502 -0.61666 0.179457 + outer loop + vertex 670.177 153.603 103.4 + vertex 671.554 157.469 110.806 + vertex 669.793 155.316 110.925 + endloop + endfacet + facet normal 0.791009 -0.585098 0.178789 + outer loop + vertex 672.797 156.722 102.73 + vertex 672.387 158.355 109.887 + vertex 671.947 155.768 103.37 + endloop + endfacet + facet normal 0.800668 -0.573433 0.173507 + outer loop + vertex 671.947 155.768 103.37 + vertex 672.387 158.355 109.887 + vertex 671.554 157.469 110.806 + endloop + endfacet + facet normal 0.707083 -0.687296 0.166305 + outer loop + vertex 666.913 151.958 110.587 + vertex 666.639 153.517 118.196 + vertex 663.108 147.93 110.117 + endloop + endfacet + facet normal 0.710324 -0.684717 0.163104 + outer loop + vertex 663.108 147.93 110.117 + vertex 666.639 153.517 118.196 + vertex 662.824 149.452 117.743 + endloop + endfacet + facet normal 0.740887 -0.651872 0.16171 + outer loop + vertex 669.793 155.316 110.925 + vertex 669.506 156.871 118.51 + vertex 666.913 151.958 110.587 + endloop + endfacet + facet normal 0.742823 -0.650094 0.159974 + outer loop + vertex 666.913 151.958 110.587 + vertex 669.506 156.871 118.51 + vertex 666.639 153.517 118.196 + endloop + endfacet + facet normal 0.76882 -0.619765 0.157504 + outer loop + vertex 671.554 157.469 110.806 + vertex 671.265 159.038 118.391 + vertex 669.793 155.316 110.925 + endloop + endfacet + facet normal 0.77124 -0.617197 0.155746 + outer loop + vertex 669.793 155.316 110.925 + vertex 671.265 159.038 118.391 + vertex 669.506 156.871 118.51 + endloop + endfacet + facet normal 0.794833 -0.586546 0.155582 + outer loop + vertex 672.387 158.355 109.887 + vertex 672.112 159.981 117.427 + vertex 671.554 157.469 110.806 + endloop + endfacet + facet normal 0.806624 -0.571962 0.149055 + outer loop + vertex 671.554 157.469 110.806 + vertex 672.112 159.981 117.427 + vertex 671.265 159.038 118.391 + endloop + endfacet + facet normal 0.713912 -0.685716 0.141858 + outer loop + vertex 666.639 153.517 118.196 + vertex 666.417 154.872 125.863 + vertex 662.824 149.452 117.743 + endloop + endfacet + facet normal 0.71589 -0.684059 0.139876 + outer loop + vertex 662.824 149.452 117.743 + vertex 666.417 154.872 125.863 + vertex 662.617 150.806 125.424 + endloop + endfacet + facet normal 0.746493 -0.651096 0.137198 + outer loop + vertex 669.506 156.871 118.51 + vertex 669.264 158.205 126.16 + vertex 666.639 153.517 118.196 + endloop + endfacet + facet normal 0.747183 -0.650433 0.13658 + outer loop + vertex 666.639 153.517 118.196 + vertex 669.264 158.205 126.16 + vertex 666.417 154.872 125.863 + endloop + endfacet + facet normal 0.773117 -0.619914 0.134157 + outer loop + vertex 671.265 159.038 118.391 + vertex 671.037 160.409 126.035 + vertex 669.506 156.871 118.51 + endloop + endfacet + facet normal 0.775888 -0.616872 0.132163 + outer loop + vertex 669.506 156.871 118.51 + vertex 671.037 160.409 126.035 + vertex 669.264 158.205 126.16 + endloop + endfacet + facet normal 0.800755 -0.58431 0.131803 + outer loop + vertex 672.112 159.981 117.427 + vertex 671.887 161.457 125.333 + vertex 671.265 159.038 118.391 + endloop + endfacet + facet normal 0.810338 -0.572102 0.126692 + outer loop + vertex 671.265 159.038 118.391 + vertex 671.887 161.457 125.333 + vertex 671.037 160.409 126.035 + endloop + endfacet + facet normal 0.71912 -0.684746 0.118275 + outer loop + vertex 666.417 154.872 125.863 + vertex 666.246 156.035 133.633 + vertex 662.617 150.806 125.424 + endloop + endfacet + facet normal 0.719807 -0.684142 0.117586 + outer loop + vertex 662.617 150.806 125.424 + vertex 666.246 156.035 133.633 + vertex 662.462 151.981 133.211 + endloop + endfacet + facet normal 0.75053 -0.651161 0.112668 + outer loop + vertex 669.264 158.205 126.16 + vertex 669.049 159.3 133.92 + vertex 666.417 154.872 125.863 + endloop + endfacet + facet normal 0.748829 -0.652858 0.114156 + outer loop + vertex 666.417 154.872 125.863 + vertex 669.049 159.3 133.92 + vertex 666.246 156.035 133.633 + endloop + endfacet + facet normal 0.777475 -0.619492 0.108455 + outer loop + vertex 671.037 160.409 126.035 + vertex 670.787 161.439 133.711 + vertex 669.264 158.205 126.16 + endloop + endfacet + facet normal 0.776586 -0.620499 0.109065 + outer loop + vertex 669.264 158.205 126.16 + vertex 670.787 161.439 133.711 + vertex 669.049 159.3 133.92 + endloop + endfacet + facet normal 0.806224 -0.581819 0.10719 + outer loop + vertex 671.887 161.457 125.333 + vertex 671.642 162.47 132.673 + vertex 671.037 160.409 126.035 + endloop + endfacet + facet normal 0.814259 -0.571258 0.103179 + outer loop + vertex 671.037 160.409 126.035 + vertex 671.642 162.47 132.673 + vertex 670.787 161.439 133.711 + endloop + endfacet + facet normal 0.722612 -0.684531 0.0961759 + outer loop + vertex 666.246 156.035 133.633 + vertex 666.114 157.002 141.505 + vertex 662.462 151.981 133.211 + endloop + endfacet + facet normal 0.723161 -0.684028 0.0956294 + outer loop + vertex 662.462 151.981 133.211 + vertex 666.114 157.002 141.505 + vertex 662.341 152.957 141.106 + endloop + endfacet + facet normal 0.751683 -0.653246 0.0907798 + outer loop + vertex 669.049 159.3 133.92 + vertex 668.879 160.2 141.805 + vertex 666.246 156.035 133.633 + endloop + endfacet + facet normal 0.74891 -0.656095 0.0931251 + outer loop + vertex 666.246 156.035 133.633 + vertex 668.879 160.2 141.805 + vertex 666.114 157.002 141.505 + endloop + endfacet + facet normal 0.777263 -0.623385 0.0851635 + outer loop + vertex 670.787 161.439 133.711 + vertex 670.552 162.225 141.612 + vertex 669.049 159.3 133.92 + endloop + endfacet + facet normal 0.77199 -0.629443 0.0884987 + outer loop + vertex 669.049 159.3 133.92 + vertex 670.552 162.225 141.612 + vertex 668.879 160.2 141.805 + endloop + endfacet + facet normal 0.807295 -0.584029 0.084768 + outer loop + vertex 671.642 162.47 132.673 + vertex 671.462 163.337 140.362 + vertex 670.787 161.439 133.711 + endloop + endfacet + facet normal 0.814242 -0.574787 0.0814264 + outer loop + vertex 670.787 161.439 133.711 + vertex 671.462 163.337 140.362 + vertex 670.552 162.225 141.612 + endloop + endfacet + facet normal 0.72551 -0.684149 0.0746715 + outer loop + vertex 666.114 157.002 141.505 + vertex 666.018 157.766 149.443 + vertex 662.341 152.957 141.106 + endloop + endfacet + facet normal 0.726445 -0.683256 0.073744 + outer loop + vertex 662.341 152.957 141.106 + vertex 666.018 157.766 149.443 + vertex 662.244 153.713 149.07 + endloop + endfacet + facet normal 0.751309 -0.656108 0.0711198 + outer loop + vertex 668.879 160.2 141.805 + vertex 668.747 160.909 149.733 + vertex 666.114 157.002 141.505 + endloop + endfacet + facet normal 0.749711 -0.65779 0.0724302 + outer loop + vertex 666.114 157.002 141.505 + vertex 668.747 160.909 149.733 + vertex 666.018 157.766 149.443 + endloop + endfacet + facet normal 0.772287 -0.631802 0.0663199 + outer loop + vertex 670.552 162.225 141.612 + vertex 670.368 162.842 149.628 + vertex 668.879 160.2 141.805 + endloop + endfacet + facet normal 0.766241 -0.638749 0.0698168 + outer loop + vertex 668.879 160.2 141.805 + vertex 670.368 162.842 149.628 + vertex 668.747 160.909 149.733 + endloop + endfacet + facet normal 0.806861 -0.587147 0.0650679 + outer loop + vertex 671.462 163.337 140.362 + vertex 671.332 164.077 148.655 + vertex 670.552 162.225 141.612 + endloop + endfacet + facet normal 0.810496 -0.582303 0.0633924 + outer loop + vertex 670.552 162.225 141.612 + vertex 671.332 164.077 148.655 + vertex 670.368 162.842 149.628 + endloop + endfacet + facet normal 0.728439 -0.683125 0.0521295 + outer loop + vertex 666.018 157.766 149.443 + vertex 665.947 158.298 157.399 + vertex 662.244 153.713 149.07 + endloop + endfacet + facet normal 0.729379 -0.682192 0.0511977 + outer loop + vertex 662.244 153.713 149.07 + vertex 665.947 158.298 157.399 + vertex 662.177 154.24 157.049 + endloop + endfacet + facet normal 0.751722 -0.657531 0.0506686 + outer loop + vertex 668.747 160.909 149.733 + vertex 668.664 161.424 157.649 + vertex 666.018 157.766 149.443 + endloop + endfacet + facet normal 0.751785 -0.657463 0.0506183 + outer loop + vertex 666.018 157.766 149.443 + vertex 668.664 161.424 157.649 + vertex 665.947 158.298 157.399 + endloop + endfacet + facet normal 0.766636 -0.640209 0.049005 + outer loop + vertex 670.368 162.842 149.628 + vertex 670.257 163.313 157.519 + vertex 668.747 160.909 149.733 + endloop + endfacet + facet normal 0.765208 -0.641854 0.0497897 + outer loop + vertex 668.747 160.909 149.733 + vertex 670.257 163.313 157.519 + vertex 668.664 161.424 157.649 + endloop + endfacet + facet normal 0.805063 -0.591363 0.0465133 + outer loop + vertex 671.332 164.077 148.655 + vertex 671.185 164.52 156.826 + vertex 670.368 162.842 149.628 + endloop + endfacet + facet normal 0.804731 -0.591803 0.0466535 + outer loop + vertex 670.368 162.842 149.628 + vertex 671.185 164.52 156.826 + vertex 670.257 163.313 157.519 + endloop + endfacet + facet normal 0.730999 -0.681769 0.0288434 + outer loop + vertex 665.947 158.298 157.399 + vertex 665.894 158.576 165.329 + vertex 662.177 154.24 157.049 + endloop + endfacet + facet normal 0.730706 -0.68207 0.0291327 + outer loop + vertex 662.177 154.24 157.049 + vertex 665.894 158.576 165.329 + vertex 662.12 154.519 164.998 + endloop + endfacet + facet normal 0.753329 -0.657028 0.0284558 + outer loop + vertex 668.664 161.424 157.649 + vertex 668.623 161.719 165.555 + vertex 665.947 158.298 157.399 + endloop + endfacet + facet normal 0.753761 -0.656548 0.0281129 + outer loop + vertex 665.947 158.298 157.399 + vertex 668.623 161.719 165.555 + vertex 665.894 158.576 165.329 + endloop + endfacet + facet normal 0.765125 -0.643236 0.028816 + outer loop + vertex 670.257 163.313 157.519 + vertex 670.206 163.602 165.344 + vertex 668.664 161.424 157.649 + endloop + endfacet + facet normal 0.766774 -0.641309 0.0279402 + outer loop + vertex 668.664 161.424 157.649 + vertex 670.206 163.602 165.344 + vertex 668.623 161.719 165.555 + endloop + endfacet + facet normal 0.800564 -0.598528 0.0293485 + outer loop + vertex 671.185 164.52 156.826 + vertex 671.101 164.774 164.315 + vertex 670.257 163.313 157.519 + endloop + endfacet + facet normal 0.805877 -0.591459 0.0271686 + outer loop + vertex 670.257 163.313 157.519 + vertex 671.101 164.774 164.315 + vertex 670.206 163.602 165.344 + endloop + endfacet + facet normal 0.731912 -0.681366 0.00676711 + outer loop + vertex 665.894 158.576 165.329 + vertex 665.876 158.635 173.216 + vertex 662.12 154.519 164.998 + endloop + endfacet + facet normal 0.731265 -0.682054 0.0074075 + outer loop + vertex 662.12 154.519 164.998 + vertex 665.876 158.635 173.216 + vertex 662.091 154.574 172.907 + endloop + endfacet + facet normal 0.754786 -0.655932 0.00713233 + outer loop + vertex 668.623 161.719 165.555 + vertex 668.622 161.803 173.421 + vertex 665.894 158.576 165.329 + endloop + endfacet + facet normal 0.755429 -0.655197 0.00662267 + outer loop + vertex 665.894 158.576 165.329 + vertex 668.622 161.803 173.421 + vertex 665.876 158.635 173.216 + endloop + endfacet + facet normal 0.765948 -0.642854 0.00789174 + outer loop + vertex 670.206 163.602 165.344 + vertex 670.207 163.7 173.223 + vertex 668.623 161.719 165.555 + endloop + endfacet + facet normal 0.767744 -0.640719 0.00696903 + outer loop + vertex 668.623 161.719 165.555 + vertex 670.207 163.7 173.223 + vertex 668.622 161.803 173.421 + endloop + endfacet + facet normal 0.798959 -0.601304 0.00993658 + outer loop + vertex 671.101 164.774 164.315 + vertex 671.106 164.912 172.186 + vertex 670.206 163.602 165.344 + endloop + endfacet + facet normal 0.805876 -0.592039 0.00725237 + outer loop + vertex 670.206 163.602 165.344 + vertex 671.106 164.912 172.186 + vertex 670.207 163.7 173.223 + endloop + endfacet + facet normal 0.732057 -0.681077 -0.0150656 + outer loop + vertex 665.876 158.635 173.216 + vertex 665.899 158.486 181.08 + vertex 662.091 154.574 172.907 + endloop + endfacet + facet normal 0.731354 -0.681846 -0.0143704 + outer loop + vertex 662.091 154.574 172.907 + vertex 665.899 158.486 181.08 + vertex 662.092 154.409 180.799 + endloop + endfacet + facet normal 0.756007 -0.654434 -0.0129868 + outer loop + vertex 668.622 161.803 173.421 + vertex 668.679 161.714 181.238 + vertex 665.876 158.635 173.216 + endloop + endfacet + facet normal 0.758008 -0.652082 -0.0145891 + outer loop + vertex 665.876 158.635 173.216 + vertex 668.679 161.714 181.238 + vertex 665.899 158.486 181.08 + endloop + endfacet + facet normal 0.76684 -0.641757 -0.0102446 + outer loop + vertex 670.207 163.7 173.223 + vertex 670.288 163.673 180.997 + vertex 668.622 161.803 173.421 + endloop + endfacet + facet normal 0.771927 -0.63558 -0.0128879 + outer loop + vertex 668.622 161.803 173.421 + vertex 670.288 163.673 180.997 + vertex 668.679 161.714 181.238 + endloop + endfacet + facet normal 0.798999 -0.601258 -0.00947755 + outer loop + vertex 671.106 164.912 172.186 + vertex 671.161 164.857 180.232 + vertex 670.207 163.7 173.223 + endloop + endfacet + facet normal 0.801741 -0.597581 -0.0104578 + outer loop + vertex 670.207 163.7 173.223 + vertex 671.161 164.857 180.232 + vertex 670.288 163.673 180.997 + endloop + endfacet + facet normal 0.731708 -0.680613 -0.037014 + outer loop + vertex 665.899 158.486 181.08 + vertex 665.949 158.111 188.966 + vertex 662.092 154.409 180.799 + endloop + endfacet + facet normal 0.730526 -0.681943 -0.0358533 + outer loop + vertex 662.092 154.409 180.799 + vertex 665.949 158.111 188.966 + vertex 662.133 154.037 188.706 + endloop + endfacet + facet normal 0.758118 -0.651227 -0.0340717 + outer loop + vertex 668.679 161.714 181.238 + vertex 668.778 161.418 189.087 + vertex 665.899 158.486 181.08 + endloop + endfacet + facet normal 0.760124 -0.648797 -0.0356827 + outer loop + vertex 665.899 158.486 181.08 + vertex 668.778 161.418 189.087 + vertex 665.949 158.111 188.966 + endloop + endfacet + facet normal 0.77069 -0.636548 -0.0290354 + outer loop + vertex 670.288 163.673 180.997 + vertex 670.429 163.49 188.747 + vertex 668.679 161.714 181.238 + endloop + endfacet + facet normal 0.778913 -0.626243 -0.0333894 + outer loop + vertex 668.679 161.714 181.238 + vertex 670.429 163.49 188.747 + vertex 668.778 161.418 189.087 + endloop + endfacet + facet normal 0.797002 -0.603461 -0.0249595 + outer loop + vertex 671.161 164.857 180.232 + vertex 671.283 164.713 187.623 + vertex 670.288 163.673 180.997 + endloop + endfacet + facet normal 0.806993 -0.589869 -0.028592 + outer loop + vertex 670.288 163.673 180.997 + vertex 671.283 164.713 187.623 + vertex 670.429 163.49 188.747 + endloop + endfacet + facet normal 0.730457 -0.680387 -0.0592127 + outer loop + vertex 665.949 158.111 188.966 + vertex 666.031 157.511 196.88 + vertex 662.133 154.037 188.706 + endloop + endfacet + facet normal 0.728412 -0.682744 -0.0572355 + outer loop + vertex 662.133 154.037 188.706 + vertex 666.031 157.511 196.88 + vertex 662.204 153.448 196.63 + endloop + endfacet + facet normal 0.759769 -0.647728 -0.0565654 + outer loop + vertex 668.778 161.418 189.087 + vertex 668.887 160.855 197.009 + vertex 665.949 158.111 188.966 + endloop + endfacet + facet normal 0.760313 -0.647052 -0.0569942 + outer loop + vertex 665.949 158.111 188.966 + vertex 668.887 160.855 197.009 + vertex 666.031 157.511 196.88 + endloop + endfacet + facet normal 0.776924 -0.627535 -0.0508927 + outer loop + vertex 670.429 163.49 188.747 + vertex 670.595 163.052 196.693 + vertex 668.778 161.418 189.087 + endloop + endfacet + facet normal 0.784426 -0.617799 -0.0547769 + outer loop + vertex 668.778 161.418 189.087 + vertex 670.595 163.052 196.693 + vertex 668.887 160.855 197.009 + endloop + endfacet + facet normal 0.79907 -0.599542 -0.0451366 + outer loop + vertex 671.283 164.713 187.623 + vertex 671.376 164.241 195.541 + vertex 670.429 163.49 188.747 + endloop + endfacet + facet normal 0.812484 -0.580915 -0.0490636 + outer loop + vertex 670.429 163.49 188.747 + vertex 671.376 164.241 195.541 + vertex 670.595 163.052 196.693 + endloop + endfacet + facet normal 0.727929 -0.680803 -0.0814037 + outer loop + vertex 666.031 157.511 196.88 + vertex 666.138 156.679 204.781 + vertex 662.204 153.448 196.63 + endloop + endfacet + facet normal 0.725237 -0.683969 -0.0788491 + outer loop + vertex 662.204 153.448 196.63 + vertex 666.138 156.679 204.781 + vertex 662.305 152.642 204.55 + endloop + endfacet + facet normal 0.75959 -0.645583 -0.0790296 + outer loop + vertex 668.887 160.855 197.009 + vertex 669.016 160.036 204.929 + vertex 666.031 157.511 196.88 + endloop + endfacet + facet normal 0.758572 -0.646874 -0.0782473 + outer loop + vertex 666.031 157.511 196.88 + vertex 669.016 160.036 204.929 + vertex 666.138 156.679 204.781 + endloop + endfacet + facet normal 0.782052 -0.618767 -0.0743137 + outer loop + vertex 670.595 163.052 196.693 + vertex 670.758 162.294 204.711 + vertex 668.887 160.855 197.009 + endloop + endfacet + facet normal 0.78582 -0.613747 -0.076167 + outer loop + vertex 668.887 160.855 197.009 + vertex 670.758 162.294 204.711 + vertex 669.016 160.036 204.929 + endloop + endfacet + facet normal 0.803146 -0.592019 -0.0668596 + outer loop + vertex 671.376 164.241 195.541 + vertex 671.545 163.539 203.784 + vertex 670.595 163.052 196.693 + endloop + endfacet + facet normal 0.818611 -0.570012 -0.0704447 + outer loop + vertex 670.595 163.052 196.693 + vertex 671.545 163.539 203.784 + vertex 670.758 162.294 204.711 + endloop + endfacet + facet normal 0.724301 -0.681666 -0.103536 + outer loop + vertex 666.138 156.679 204.781 + vertex 666.266 155.623 212.638 + vertex 662.305 152.642 204.55 + endloop + endfacet + facet normal 0.721387 -0.685153 -0.100824 + outer loop + vertex 662.305 152.642 204.55 + vertex 666.266 155.623 212.638 + vertex 662.445 151.629 212.441 + endloop + endfacet + facet normal 0.757493 -0.64493 -0.10134 + outer loop + vertex 669.016 160.036 204.929 + vertex 669.162 158.977 212.767 + vertex 666.138 156.679 204.781 + endloop + endfacet + facet normal 0.75506 -0.648058 -0.0995187 + outer loop + vertex 666.138 156.679 204.781 + vertex 669.162 158.977 212.767 + vertex 666.266 155.623 212.638 + endloop + endfacet + facet normal 0.783375 -0.613897 -0.0972307 + outer loop + vertex 670.758 162.294 204.711 + vertex 670.919 161.257 212.558 + vertex 669.016 160.036 204.929 + endloop + endfacet + facet normal 0.784005 -0.613046 -0.0975241 + outer loop + vertex 669.016 160.036 204.929 + vertex 670.919 161.257 212.558 + vertex 669.162 158.977 212.767 + endloop + endfacet + facet normal 0.809978 -0.579443 -0.0904479 + outer loop + vertex 671.545 163.539 203.784 + vertex 671.725 162.533 211.845 + vertex 670.758 162.294 204.711 + endloop + endfacet + facet normal 0.817801 -0.568118 -0.0918881 + outer loop + vertex 670.758 162.294 204.711 + vertex 671.725 162.533 211.845 + vertex 670.919 161.257 212.558 + endloop + endfacet + facet normal 0.719895 -0.682458 -0.1265 + outer loop + vertex 666.266 155.623 212.638 + vertex 666.461 154.382 220.44 + vertex 662.445 151.629 212.441 + endloop + endfacet + facet normal 0.716874 -0.686139 -0.123715 + outer loop + vertex 662.445 151.629 212.441 + vertex 666.461 154.382 220.44 + vertex 662.624 150.403 220.271 + endloop + endfacet + facet normal 0.753459 -0.645739 -0.123777 + outer loop + vertex 669.162 158.977 212.767 + vertex 669.344 157.7 220.536 + vertex 666.266 155.623 212.638 + endloop + endfacet + facet normal 0.750971 -0.648976 -0.121956 + outer loop + vertex 666.266 155.623 212.638 + vertex 669.344 157.7 220.536 + vertex 666.461 154.382 220.44 + endloop + endfacet + facet normal 0.78111 -0.612841 -0.119552 + outer loop + vertex 670.919 161.257 212.558 + vertex 671.102 159.986 220.265 + vertex 669.162 158.977 212.767 + endloop + endfacet + facet normal 0.780276 -0.613974 -0.119184 + outer loop + vertex 669.162 158.977 212.767 + vertex 671.102 159.986 220.265 + vertex 669.344 157.7 220.536 + endloop + endfacet + facet normal 0.81035 -0.575011 -0.112669 + outer loop + vertex 671.725 162.533 211.845 + vertex 671.884 161.299 219.285 + vertex 670.919 161.257 212.558 + endloop + endfacet + facet normal 0.813999 -0.569724 -0.113225 + outer loop + vertex 670.919 161.257 212.558 + vertex 671.884 161.299 219.285 + vertex 671.102 159.986 220.265 + endloop + endfacet + facet normal 0.714819 -0.683044 -0.149948 + outer loop + vertex 666.461 154.382 220.44 + vertex 666.7 152.939 228.153 + vertex 662.624 150.403 220.271 + endloop + endfacet + facet normal 0.711362 -0.687327 -0.146783 + outer loop + vertex 662.624 150.403 220.271 + vertex 666.7 152.939 228.153 + vertex 662.866 149.002 228.008 + endloop + endfacet + facet normal 0.748737 -0.646303 -0.14726 + outer loop + vertex 669.344 157.7 220.536 + vertex 669.599 156.241 228.233 + vertex 666.461 154.382 220.44 + endloop + endfacet + facet normal 0.74536 -0.650737 -0.144844 + outer loop + vertex 666.461 154.382 220.44 + vertex 669.599 156.241 228.233 + vertex 666.7 152.939 228.153 + endloop + endfacet + facet normal 0.776473 -0.613819 -0.142533 + outer loop + vertex 671.102 159.986 220.265 + vertex 671.359 158.519 227.984 + vertex 669.344 157.7 220.536 + endloop + endfacet + facet normal 0.775681 -0.614896 -0.142201 + outer loop + vertex 669.344 157.7 220.536 + vertex 671.359 158.519 227.984 + vertex 669.599 156.241 228.233 + endloop + endfacet + facet normal 0.804367 -0.578981 -0.133321 + outer loop + vertex 671.884 161.299 219.285 + vertex 672.128 159.866 226.977 + vertex 671.102 159.986 220.265 + endloop + endfacet + facet normal 0.813931 -0.56517 -0.134536 + outer loop + vertex 671.102 159.986 220.265 + vertex 672.128 159.866 226.977 + vertex 671.359 158.519 227.984 + endloop + endfacet + facet normal 0.708662 -0.683685 -0.17428 + outer loop + vertex 666.7 152.939 228.153 + vertex 667.054 151.368 235.753 + vertex 662.866 149.002 228.008 + endloop + endfacet + facet normal 0.704726 -0.688654 -0.170634 + outer loop + vertex 662.866 149.002 228.008 + vertex 667.054 151.368 235.753 + vertex 663.188 147.445 235.62 + endloop + endfacet + facet normal 0.742425 -0.647503 -0.171889 + outer loop + vertex 669.599 156.241 228.233 + vertex 669.956 154.635 235.825 + vertex 666.7 152.939 228.153 + endloop + endfacet + facet normal 0.738709 -0.652436 -0.169221 + outer loop + vertex 666.7 152.939 228.153 + vertex 669.956 154.635 235.825 + vertex 667.054 151.368 235.753 + endloop + endfacet + facet normal 0.77113 -0.614174 -0.167775 + outer loop + vertex 671.359 158.519 227.984 + vertex 671.71 156.887 235.574 + vertex 669.599 156.241 228.233 + endloop + endfacet + facet normal 0.768685 -0.617501 -0.166779 + outer loop + vertex 669.599 156.241 228.233 + vertex 671.71 156.887 235.574 + vertex 669.956 154.635 235.825 + endloop + endfacet + facet normal 0.802084 -0.575935 -0.157984 + outer loop + vertex 672.128 159.866 226.977 + vertex 672.472 158.191 234.833 + vertex 671.359 158.519 227.984 + endloop + endfacet + facet normal 0.810489 -0.563826 -0.15877 + outer loop + vertex 671.359 158.519 227.984 + vertex 672.472 158.191 234.833 + vertex 671.71 156.887 235.574 + endloop + endfacet + facet normal 0.701116 -0.68406 -0.201242 + outer loop + vertex 667.054 151.368 235.753 + vertex 667.529 149.656 243.227 + vertex 663.188 147.445 235.62 + endloop + endfacet + facet normal 0.696767 -0.689678 -0.197128 + outer loop + vertex 663.188 147.445 235.62 + vertex 667.529 149.656 243.227 + vertex 663.65 145.765 243.131 + endloop + endfacet + facet normal 0.734831 -0.648329 -0.199228 + outer loop + vertex 669.956 154.635 235.825 + vertex 670.45 152.904 243.282 + vertex 667.054 151.368 235.753 + endloop + endfacet + facet normal 0.730684 -0.653911 -0.196218 + outer loop + vertex 667.054 151.368 235.753 + vertex 670.45 152.904 243.282 + vertex 667.529 149.656 243.227 + endloop + endfacet + facet normal 0.762811 -0.616189 -0.196038 + outer loop + vertex 671.71 156.887 235.574 + vertex 672.215 155.137 243.038 + vertex 669.956 154.635 235.825 + endloop + endfacet + facet normal 0.759126 -0.621196 -0.194536 + outer loop + vertex 669.956 154.635 235.825 + vertex 672.215 155.137 243.038 + vertex 670.45 152.904 243.282 + endloop + endfacet + facet normal 0.797919 -0.572838 -0.187568 + outer loop + vertex 672.472 158.191 234.833 + vertex 672.914 156.436 242.075 + vertex 671.71 156.887 235.574 + endloop + endfacet + facet normal 0.79984 -0.570098 -0.187734 + outer loop + vertex 671.71 156.887 235.574 + vertex 672.914 156.436 242.075 + vertex 672.215 155.137 243.038 + endloop + endfacet + facet normal 0.691573 -0.683611 -0.233245 + outer loop + vertex 667.529 149.656 243.227 + vertex 668.186 147.792 250.64 + vertex 663.65 145.765 243.131 + endloop + endfacet + facet normal 0.68598 -0.69102 -0.227865 + outer loop + vertex 663.65 145.765 243.131 + vertex 668.186 147.792 250.64 + vertex 664.293 143.939 250.605 + endloop + endfacet + facet normal 0.725331 -0.648504 -0.23095 + outer loop + vertex 670.45 152.904 243.282 + vertex 671.141 151.06 250.631 + vertex 667.529 149.656 243.227 + endloop + endfacet + facet normal 0.72181 -0.653347 -0.228315 + outer loop + vertex 667.529 149.656 243.227 + vertex 671.141 151.06 250.631 + vertex 668.186 147.792 250.64 + endloop + endfacet + facet normal 0.751814 -0.618986 -0.227226 + outer loop + vertex 672.215 155.137 243.038 + vertex 672.908 153.294 250.352 + vertex 670.45 152.904 243.282 + endloop + endfacet + facet normal 0.75004 -0.621408 -0.226476 + outer loop + vertex 670.45 152.904 243.282 + vertex 672.908 153.294 250.352 + vertex 671.141 151.06 250.631 + endloop + endfacet + facet normal 0.780856 -0.584395 -0.220784 + outer loop + vertex 672.914 156.436 242.075 + vertex 673.618 154.518 249.639 + vertex 672.215 155.137 243.038 + endloop + endfacet + facet normal 0.782291 -0.582428 -0.220905 + outer loop + vertex 672.215 155.137 243.038 + vertex 673.618 154.518 249.639 + vertex 672.908 153.294 250.352 + endloop + endfacet + facet normal 0.678645 -0.683227 -0.269521 + outer loop + vertex 668.186 147.792 250.64 + vertex 669.092 145.758 258.076 + vertex 664.293 143.939 250.605 + endloop + endfacet + facet normal 0.669985 -0.694942 -0.261106 + outer loop + vertex 664.293 143.939 250.605 + vertex 669.092 145.758 258.076 + vertex 665.143 141.962 258.05 + endloop + endfacet + facet normal 0.713813 -0.646224 -0.269935 + outer loop + vertex 671.141 151.06 250.631 + vertex 672.085 149.023 258.004 + vertex 668.186 147.792 250.64 + endloop + endfacet + facet normal 0.707732 -0.654781 -0.265285 + outer loop + vertex 668.186 147.792 250.64 + vertex 672.085 149.023 258.004 + vertex 669.092 145.758 258.076 + endloop + endfacet + facet normal 0.740104 -0.618295 -0.264495 + outer loop + vertex 672.908 153.294 250.352 + vertex 673.857 151.353 257.544 + vertex 671.141 151.06 250.631 + endloop + endfacet + facet normal 0.741638 -0.616156 -0.265188 + outer loop + vertex 671.141 151.06 250.631 + vertex 673.857 151.353 257.544 + vertex 672.085 149.023 258.004 + endloop + endfacet + facet normal 0.764142 -0.592203 -0.255699 + outer loop + vertex 673.618 154.518 249.639 + vertex 674.499 152.654 256.59 + vertex 672.908 153.294 250.352 + endloop + endfacet + facet normal 0.778097 -0.573033 -0.25729 + outer loop + vertex 672.908 153.294 250.352 + vertex 674.499 152.654 256.59 + vertex 673.857 151.353 257.544 + endloop + endfacet + facet normal 0.661171 -0.685466 -0.304941 + outer loop + vertex 669.092 145.758 258.076 + vertex 670.237 143.598 265.415 + vertex 665.143 141.962 258.05 + endloop + endfacet + facet normal 0.649284 -0.701803 -0.293092 + outer loop + vertex 665.143 141.962 258.05 + vertex 670.237 143.598 265.415 + vertex 666.185 139.912 265.264 + endloop + endfacet + facet normal 0.697295 -0.64621 -0.310149 + outer loop + vertex 672.085 149.023 258.004 + vertex 673.41 146.839 265.534 + vertex 669.092 145.758 258.076 + endloop + endfacet + facet normal 0.686691 -0.661333 -0.301818 + outer loop + vertex 669.092 145.758 258.076 + vertex 673.41 146.839 265.534 + vertex 670.237 143.598 265.415 + endloop + endfacet + facet normal 0.726714 -0.613472 -0.309095 + outer loop + vertex 673.857 151.353 257.544 + vertex 675.238 149.21 265.045 + vertex 672.085 149.023 258.004 + endloop + endfacet + facet normal 0.722186 -0.619889 -0.306897 + outer loop + vertex 672.085 149.023 258.004 + vertex 675.238 149.21 265.045 + vertex 673.41 146.839 265.534 + endloop + endfacet + facet normal 0.751481 -0.589082 -0.297084 + outer loop + vertex 674.499 152.654 256.59 + vertex 675.706 150.744 263.431 + vertex 673.857 151.353 257.544 + endloop + endfacet + facet normal 0.776139 -0.553976 -0.301196 + outer loop + vertex 673.857 151.353 257.544 + vertex 675.706 150.744 263.431 + vertex 675.238 149.21 265.045 + endloop + endfacet + facet normal 0.676528 -0.649746 -0.346612 + outer loop + vertex 673.41 146.839 265.534 + vertex 675.133 144.624 273.048 + vertex 670.237 143.598 265.415 + endloop + endfacet + facet normal 0.661483 -0.671459 -0.334041 + outer loop + vertex 670.237 143.598 265.415 + vertex 675.133 144.624 273.048 + vertex 671.38 141.452 271.992 + endloop + endfacet + facet normal 0.705879 -0.616097 -0.349513 + outer loop + vertex 675.238 149.21 265.045 + vertex 677.315 147.064 273.022 + vertex 673.41 146.839 265.534 + endloop + endfacet + facet normal 0.697879 -0.62765 -0.344993 + outer loop + vertex 673.41 146.839 265.534 + vertex 677.315 147.064 273.022 + vertex 675.133 144.624 273.048 + endloop + endfacet + facet normal 0.732456 -0.586867 -0.345103 + outer loop + vertex 675.706 150.744 263.431 + vertex 677.81 148.456 271.786 + vertex 675.238 149.21 265.045 + endloop + endfacet + facet normal 0.742591 -0.572615 -0.347377 + outer loop + vertex 675.238 149.21 265.045 + vertex 677.81 148.456 271.786 + vertex 677.315 147.064 273.022 + endloop + endfacet + facet normal 0.52038 -0.708159 -0.477195 + outer loop + vertex 678.652 135.178 292.326 + vertex 673.039 132.401 290.325 + vertex 677.147 136.019 289.437 + endloop + endfacet + facet normal 0.560688 -0.638338 -0.527402 + outer loop + vertex 682.415 140.935 288.835 + vertex 684.159 140.036 291.778 + vertex 680.26 138.749 289.19 + endloop + endfacet + facet normal 0.554634 -0.659042 -0.50798 + outer loop + vertex 680.26 138.749 289.19 + vertex 684.159 140.036 291.778 + vertex 681.675 137.704 292.09 + endloop + endfacet + facet normal 0.545427 -0.667721 -0.506615 + outer loop + vertex 680.26 138.749 289.19 + vertex 681.675 137.704 292.09 + vertex 677.147 136.019 289.437 + endloop + endfacet + facet normal 0.539441 -0.690441 -0.481969 + outer loop + vertex 677.147 136.019 289.437 + vertex 681.675 137.704 292.09 + vertex 678.652 135.178 292.326 + endloop + endfacet + facet normal 0.608364 -0.546212 -0.575799 + outer loop + vertex 684.898 143.508 288.801 + vertex 687.032 142.861 291.669 + vertex 683.951 142.529 288.728 + endloop + endfacet + facet normal 0.593365 -0.582002 -0.556051 + outer loop + vertex 683.951 142.529 288.728 + vertex 687.032 142.861 291.669 + vertex 685.934 141.775 291.634 + endloop + endfacet + facet normal 0.581568 -0.597532 -0.552027 + outer loop + vertex 683.951 142.529 288.728 + vertex 685.934 141.775 291.634 + vertex 682.415 140.935 288.835 + endloop + endfacet + facet normal 0.571078 -0.626833 -0.530047 + outer loop + vertex 682.415 140.935 288.835 + vertex 685.934 141.775 291.634 + vertex 684.159 140.036 291.778 + endloop + endfacet + facet normal 0.643371 -0.493742 -0.585057 + outer loop + vertex 685.173 144.248 288.473 + vertex 687.414 143.576 291.504 + vertex 685.303 144.015 288.811 + endloop + endfacet + facet normal 0.71004 -0.346096 -0.613237 + outer loop + vertex 685.303 144.015 288.811 + vertex 687.414 143.576 291.504 + vertex 687.508 143.393 291.716 + endloop + endfacet + facet normal 0.637527 -0.495248 -0.590159 + outer loop + vertex 685.303 144.015 288.811 + vertex 687.508 143.393 291.716 + vertex 684.898 143.508 288.801 + endloop + endfacet + facet normal 0.63011 -0.51158 -0.584163 + outer loop + vertex 684.898 143.508 288.801 + vertex 687.508 143.393 291.716 + vertex 687.032 142.861 291.669 + endloop + endfacet + facet normal -0.385333 -0.921557 0.0474494 + outer loop + vertex 684.479 144.482 287.38 + vertex 686.8 143.685 290.745 + vertex 685.173 144.248 288.473 + endloop + endfacet + facet normal -0.614166 0.541531 0.57406 + outer loop + vertex 685.173 144.248 288.473 + vertex 686.8 143.685 290.745 + vertex 687.414 143.576 291.504 + endloop + endfacet + facet normal 0.548562 -0.584087 -0.598265 + outer loop + vertex 688.842 142.277 293.991 + vertex 689.689 141.631 295.398 + vertex 687.511 141.047 293.97 + endloop + endfacet + facet normal 0.542544 -0.608518 -0.579096 + outer loop + vertex 687.511 141.047 293.97 + vertex 689.689 141.631 295.398 + vertex 688.254 140.26 295.494 + endloop + endfacet + facet normal 0.57657 -0.563869 -0.591286 + outer loop + vertex 687.032 142.861 291.669 + vertex 688.842 142.277 293.991 + vertex 685.934 141.775 291.634 + endloop + endfacet + facet normal 0.563413 -0.60069 -0.567219 + outer loop + vertex 685.934 141.775 291.634 + vertex 688.842 142.277 293.991 + vertex 687.511 141.047 293.97 + endloop + endfacet + facet normal 0.553889 -0.612132 -0.564359 + outer loop + vertex 685.934 141.775 291.634 + vertex 687.511 141.047 293.97 + vertex 684.159 140.036 291.778 + endloop + endfacet + facet normal 0.547828 -0.635157 -0.544481 + outer loop + vertex 684.159 140.036 291.778 + vertex 687.511 141.047 293.97 + vertex 685.511 139.229 294.08 + endloop + endfacet + facet normal 0.531078 -0.618809 -0.57882 + outer loop + vertex 687.511 141.047 293.97 + vertex 688.254 140.26 295.494 + vertex 685.511 139.229 294.08 + endloop + endfacet + facet normal 0.529203 -0.633474 -0.564494 + outer loop + vertex 685.511 139.229 294.08 + vertex 688.254 140.26 295.494 + vertex 686.336 138.831 295.299 + endloop + endfacet + facet normal 0.607766 -0.447836 -0.655792 + outer loop + vertex 689.582 143.16 293.963 + vertex 691.009 142.867 295.485 + vertex 689.504 142.929 294.048 + endloop + endfacet + facet normal 0.577639 -0.522163 -0.627439 + outer loop + vertex 689.504 142.929 294.048 + vertex 691.009 142.867 295.485 + vertex 690.733 142.392 295.627 + endloop + endfacet + facet normal 0.648674 -0.409893 -0.641257 + outer loop + vertex 687.414 143.576 291.504 + vertex 689.582 143.16 293.963 + vertex 687.508 143.393 291.716 + endloop + endfacet + facet normal 0.633537 -0.447486 -0.631179 + outer loop + vertex 687.508 143.393 291.716 + vertex 689.582 143.16 293.963 + vertex 689.504 142.929 294.048 + endloop + endfacet + facet normal 0.611059 -0.491319 -0.620654 + outer loop + vertex 687.508 143.393 291.716 + vertex 689.504 142.929 294.048 + vertex 687.032 142.861 291.669 + endloop + endfacet + facet normal 0.58923 -0.545054 -0.596426 + outer loop + vertex 687.032 142.861 291.669 + vertex 689.504 142.929 294.048 + vertex 688.842 142.277 293.991 + endloop + endfacet + facet normal 0.574178 -0.52715 -0.626444 + outer loop + vertex 689.504 142.929 294.048 + vertex 690.733 142.392 295.627 + vertex 688.842 142.277 293.991 + endloop + endfacet + facet normal 0.55341 -0.578929 -0.598814 + outer loop + vertex 688.842 142.277 293.991 + vertex 690.733 142.392 295.627 + vertex 689.689 141.631 295.398 + endloop + endfacet + facet normal -0.692914 -0.53459 0.483822 + outer loop + vertex 686.8 143.685 290.745 + vertex 689.169 143.17 293.568 + vertex 687.414 143.576 291.504 + endloop + endfacet + facet normal -0.536171 0.616148 0.57696 + outer loop + vertex 687.414 143.576 291.504 + vertex 689.169 143.17 293.568 + vertex 689.582 143.16 293.963 + endloop + endfacet + facet normal -0.684593 0.115497 0.719717 + outer loop + vertex 689.169 143.17 293.568 + vertex 691.223 142.98 295.553 + vertex 689.582 143.16 293.963 + endloop + endfacet + facet normal 0.51218 -0.615983 -0.598529 + outer loop + vertex 689.582 143.16 293.963 + vertex 691.223 142.98 295.553 + vertex 691.009 142.867 295.485 + endloop + endfacet + facet normal 0.290179 -0.942018 -0.168514 + outer loop + vertex 634.129 110.774 299.317 + vertex 629.277 109.066 300.51 + vertex 629.969 109.475 299.418 + endloop + endfacet + facet normal 0.314254 -0.929679 -0.192203 + outer loop + vertex 639.98 112.986 298.185 + vertex 634.129 110.774 299.317 + vertex 636.279 111.766 298.035 + endloop + endfacet + facet normal 0.498155 -0.663067 -0.558734 + outer loop + vertex 682.914 136.822 294.463 + vertex 681.573 134.811 295.655 + vertex 677.565 133.28 293.898 + endloop + endfacet + facet normal 0.509854 -0.620703 -0.595632 + outer loop + vertex 686.336 138.831 295.299 + vertex 686.821 138.44 296.122 + vertex 682.914 136.822 294.463 + endloop + endfacet + facet normal 0.507903 -0.663797 -0.549006 + outer loop + vertex 682.914 136.822 294.463 + vertex 686.821 138.44 296.122 + vertex 681.573 134.811 295.655 + endloop + endfacet + facet normal 0.517489 -0.613361 -0.596652 + outer loop + vertex 686.336 138.831 295.299 + vertex 688.254 140.26 295.494 + vertex 686.821 138.44 296.122 + endloop + endfacet + facet normal 0.521319 -0.589003 -0.617496 + outer loop + vertex 689.689 141.631 295.398 + vertex 690.348 141.145 296.418 + vertex 688.254 140.26 295.494 + endloop + endfacet + facet normal 0.52102 -0.614627 -0.59226 + outer loop + vertex 690.348 141.145 296.418 + vertex 686.821 138.44 296.122 + vertex 688.254 140.26 295.494 + endloop + endfacet + facet normal 0.546173 -0.562354 -0.620849 + outer loop + vertex 689.689 141.631 295.398 + vertex 690.733 142.392 295.627 + vertex 690.348 141.145 296.418 + endloop + endfacet + facet normal 0.546614 -0.51421 -0.660909 + outer loop + vertex 691.009 142.867 295.485 + vertex 691.854 142.5 296.471 + vertex 690.733 142.392 295.627 + endloop + endfacet + facet normal 0.530103 -0.564761 -0.632484 + outer loop + vertex 691.854 142.5 296.471 + vertex 690.348 141.145 296.418 + vertex 690.733 142.392 295.627 + endloop + endfacet + facet normal 0.359199 -0.869861 0.338109 + outer loop + vertex 606.588 98.1927 44.5686 + vertex 608.34 97.3361 40.5032 + vertex 607.597 97.9861 42.965 + endloop + endfacet + facet normal 0.206274 -0.977218 -0.0499537 + outer loop + vertex 607.285 103.027 300.933 + vertex 605.91 102.944 296.887 + vertex 607.27 103.073 299.98 + endloop + endfacet + facet normal 0.194082 -0.980895 -0.0132884 + outer loop + vertex 608.682 103.259 304.215 + vertex 607.285 103.027 300.933 + vertex 608.544 103.246 303.186 + endloop + endfacet + facet normal 0.260123 -0.926882 -0.270602 + outer loop + vertex 633.8 110.572 299.695 + vertex 630.648 109.473 300.427 + vertex 634.129 110.774 299.317 + endloop + endfacet + facet normal 0.275435 -0.926335 -0.256981 + outer loop + vertex 635.79 111.295 299.221 + vertex 633.8 110.572 299.695 + vertex 634.129 110.774 299.317 + endloop + endfacet + facet normal 0.242119 -0.856625 -0.4556 + outer loop + vertex 638.494 112.323 298.725 + vertex 635.79 111.295 299.221 + vertex 634.129 110.774 299.317 + endloop + endfacet + facet normal 0.29193 -0.905299 -0.308562 + outer loop + vertex 641.13 113.335 298.248 + vertex 638.494 112.323 298.725 + vertex 639.98 112.986 298.185 + endloop + endfacet + facet normal 0.286877 -0.872982 -0.394466 + outer loop + vertex 643.087 114.146 297.878 + vertex 641.13 113.335 298.248 + vertex 639.98 112.986 298.185 + endloop + endfacet + facet normal 0.301193 -0.868973 -0.392643 + outer loop + vertex 645.495 115.141 297.521 + vertex 643.087 114.146 297.878 + vertex 645.514 115.306 297.171 + endloop + endfacet + facet normal 0.308542 -0.866994 -0.391309 + outer loop + vertex 647.303 115.927 297.208 + vertex 645.495 115.141 297.521 + vertex 645.514 115.306 297.171 + endloop + endfacet + facet normal 0.285784 -0.792612 -0.538604 + outer loop + vertex 649.509 116.904 296.94 + vertex 647.303 115.927 297.208 + vertex 645.514 115.306 297.171 + endloop + endfacet + facet normal 0.364714 -0.824429 -0.432782 + outer loop + vertex 657.314 120.364 296.605 + vertex 654.963 119.339 296.576 + vertex 657.743 120.966 295.821 + endloop + endfacet + facet normal 0.375329 -0.823191 -0.42601 + outer loop + vertex 659.104 121.281 296.412 + vertex 657.314 120.364 296.605 + vertex 657.743 120.966 295.821 + endloop + endfacet + facet normal 0.38497 -0.799683 -0.460766 + outer loop + vertex 661.876 122.7 296.263 + vertex 659.104 121.281 296.412 + vertex 657.743 120.966 295.821 + endloop + endfacet + facet normal 0.391495 -0.805834 -0.444255 + outer loop + vertex 664.81 124.214 296.103 + vertex 661.876 122.7 296.263 + vertex 664.153 124.256 295.447 + endloop + endfacet + facet normal 0.411099 -0.785494 -0.462597 + outer loop + vertex 667.043 125.463 295.966 + vertex 664.81 124.214 296.103 + vertex 664.153 124.256 295.447 + endloop + endfacet + facet normal 0.424348 -0.769335 -0.477549 + outer loop + vertex 669.551 126.763 296.102 + vertex 667.043 125.463 295.966 + vertex 670.231 127.595 295.365 + endloop + endfacet + facet normal 0.422543 -0.76931 -0.479187 + outer loop + vertex 671.666 128 295.979 + vertex 669.551 126.763 296.102 + vertex 670.231 127.595 295.365 + endloop + endfacet + facet normal 0.435634 -0.716854 -0.544374 + outer loop + vertex 673.588 129.226 295.904 + vertex 671.666 128 295.979 + vertex 670.231 127.595 295.365 + endloop + endfacet + facet normal 0.465366 -0.722111 -0.51185 + outer loop + vertex 676.476 130.919 296.141 + vertex 673.588 129.226 295.904 + vertex 676.062 131.201 295.366 + endloop + endfacet + facet normal 0.471756 -0.716872 -0.513363 + outer loop + vertex 679.381 132.885 296.065 + vertex 676.476 130.919 296.141 + vertex 676.062 131.201 295.366 + endloop + endfacet + facet normal 0.46631 -0.656903 -0.592481 + outer loop + vertex 681.623 134.299 296.262 + vertex 679.381 132.885 296.065 + vertex 681.573 134.811 295.655 + endloop + endfacet + facet normal 0.486274 -0.647784 -0.586441 + outer loop + vertex 684.343 136.105 296.522 + vertex 681.623 134.299 296.262 + vertex 681.573 134.811 295.655 + endloop + endfacet + facet normal 0.467313 -0.606235 -0.643504 + outer loop + vertex 687.292 138.085 296.799 + vertex 684.343 136.105 296.522 + vertex 686.821 138.44 296.122 + endloop + endfacet + facet normal 0.487979 -0.585751 -0.647126 + outer loop + vertex 689.447 139.619 297.035 + vertex 687.292 138.085 296.799 + vertex 686.821 138.44 296.122 + endloop + endfacet + facet normal 0.497199 -0.561252 -0.661657 + outer loop + vertex 691.69 141.52 297.108 + vertex 689.447 139.619 297.035 + vertex 690.348 141.145 296.418 + endloop + endfacet + facet normal 0.517316 -0.526001 -0.675061 + outer loop + vertex 693.645 143.512 297.054 + vertex 691.69 141.52 297.108 + vertex 691.854 142.5 296.471 + endloop + endfacet + facet normal 0.467516 -0.732691 -0.494563 + outer loop + vertex 690.686 142.952 295.086 + vertex 693.645 143.512 297.054 + vertex 691.223 142.98 295.553 + endloop + endfacet + facet normal 0.00288512 -0.989414 -0.145091 + outer loop + vertex 688.37 143.302 292.65 + vertex 690.686 142.952 295.086 + vertex 689.169 143.17 293.568 + endloop + endfacet + facet normal 0.381574 -0.793821 -0.47355 + outer loop + vertex 685.796 144.193 289.084 + vertex 688.37 143.302 292.65 + vertex 686.8 143.685 290.745 + endloop + endfacet + facet normal 0.368232 -0.82685 -0.425117 + outer loop + vertex 683.037 145.207 284.722 + vertex 685.796 144.193 289.084 + vertex 684.479 144.482 287.38 + endloop + endfacet + facet normal 0.313436 -0.867695 -0.385828 + outer loop + vertex 681.056 146.273 280.715 + vertex 683.037 145.207 284.722 + vertex 681.458 145.921 281.832 + endloop + endfacet + facet normal 0.4341 -0.812133 -0.389868 + outer loop + vertex 679.443 147.393 276.585 + vertex 681.056 146.273 280.715 + vertex 680.443 146.495 279.568 + endloop + endfacet + facet normal 0.85595 -0.360101 -0.371049 + outer loop + vertex 677.912 148.868 271.622 + vertex 679.443 147.393 276.585 + vertex 677.81 148.456 271.786 + endloop + endfacet + facet normal 0.805534 -0.505069 -0.309872 + outer loop + vertex 675.517 151.76 261.284 + vertex 676.672 150.159 266.895 + vertex 675.706 150.744 263.431 + endloop + endfacet + facet normal 0.797801 -0.536427 -0.275246 + outer loop + vertex 674.581 153.305 255.557 + vertex 675.517 151.76 261.284 + vertex 674.499 152.654 256.59 + endloop + endfacet + facet normal 0.880509 -0.415381 -0.228391 + outer loop + vertex 673.926 154.461 250.932 + vertex 674.581 153.305 255.557 + vertex 673.618 154.518 249.639 + endloop + endfacet + facet normal 0.830056 -0.512208 -0.220569 + outer loop + vertex 673.481 155.525 246.787 + vertex 673.926 154.461 250.932 + vertex 673.618 154.518 249.639 + endloop + endfacet + facet normal 0.82138 -0.523235 0.227069 + outer loop + vertex 673.967 154.111 91.5737 + vertex 673.52 155.277 95.8777 + vertex 673.427 154.649 94.7653 + endloop + endfacet + facet normal 0.825202 -0.507595 0.247769 + outer loop + vertex 674.778 152.63 85.8377 + vertex 673.967 154.111 91.5737 + vertex 674.377 152.549 87.0079 + endloop + endfacet + facet normal 0.959517 -0.190215 0.207713 + outer loop + vertex 675.545 151.347 81.1226 + vertex 674.778 152.63 85.8377 + vertex 675.73 150.604 79.5879 + endloop + endfacet + facet normal 0.879606 -0.377917 0.288914 + outer loop + vertex 676.468 150.063 76.6316 + vertex 675.545 151.347 81.1226 + vertex 675.73 150.604 79.5879 + endloop + endfacet + facet normal 0.814956 -0.470609 0.338192 + outer loop + vertex 677.889 148.596 71.1656 + vertex 676.468 150.063 76.6316 + vertex 677.441 148.737 72.4412 + endloop + endfacet + facet normal 0.785559 -0.492655 0.374418 + outer loop + vertex 679.331 147.185 66.2846 + vertex 677.889 148.596 71.1656 + vertex 679.168 147.278 66.7473 + endloop + endfacet + facet normal 0.268098 -0.897617 0.349869 + outer loop + vertex 681.001 146.019 62.0132 + vertex 679.331 147.185 66.2846 + vertex 680.086 146.498 63.9418 + endloop + endfacet + facet normal 0.368059 -0.840203 0.398236 + outer loop + vertex 683.417 144.915 57.4502 + vertex 681.001 146.019 62.0132 + vertex 682.744 145.07 58.3997 + endloop + endfacet + facet normal 0.424191 -0.781824 0.45696 + outer loop + vertex 686.204 143.836 53.0177 + vertex 683.417 144.915 57.4502 + vertex 685.097 144.117 54.526 + endloop + endfacet + facet normal 0.362566 -0.811171 0.458855 + outer loop + vertex 688.971 142.978 49.3145 + vertex 686.204 143.836 53.0177 + vertex 687.673 143.277 50.8691 + endloop + endfacet + facet normal 0.417332 -0.763982 0.492103 + outer loop + vertex 691.448 142.718 46.8104 + vertex 688.971 142.978 49.3145 + vertex 689.98 142.759 48.1188 + endloop + endfacet + facet normal 0.462821 -0.79255 0.397065 + outer loop + vertex 693.15 143.184 45.7555 + vertex 691.448 142.718 46.8104 + vertex 691.443 142.683 46.7455 + endloop + endfacet + facet normal 0.524218 -0.612707 0.591427 + outer loop + vertex 689.02 139.796 45.9062 + vertex 693.15 143.184 45.7555 + vertex 690.161 141.881 47.0546 + endloop + endfacet + facet normal 0.520107 -0.637086 0.568867 + outer loop + vertex 686.944 137.946 45.7323 + vertex 689.02 139.796 45.9062 + vertex 686.772 138.835 46.8863 + endloop + endfacet + facet normal 0.495588 -0.650499 0.575539 + outer loop + vertex 685.039 136.715 45.9815 + vertex 686.944 137.946 45.7323 + vertex 686.772 138.835 46.8863 + endloop + endfacet + facet normal 0.485727 -0.702765 0.519799 + outer loop + vertex 681.975 134.467 45.8068 + vertex 685.039 136.715 45.9815 + vertex 682.282 136 47.5916 + endloop + endfacet + facet normal 0.482867 -0.703747 0.521134 + outer loop + vertex 679.19 132.786 46.1157 + vertex 681.975 134.467 45.8068 + vertex 682.282 136 47.5916 + endloop + endfacet + facet normal 0.477223 -0.731661 0.486756 + outer loop + vertex 676.76 131.022 45.848 + vertex 679.19 132.786 46.1157 + vertex 676.674 131.994 47.3921 + endloop + endfacet + facet normal 0.445179 -0.746599 0.494374 + outer loop + vertex 673.471 128.938 45.6623 + vertex 676.76 131.022 45.848 + vertex 676.674 131.994 47.3921 + endloop + endfacet + facet normal 0.460561 -0.768094 0.444878 + outer loop + vertex 670.594 127.065 45.4074 + vertex 673.471 128.938 45.6623 + vertex 670.746 128.055 46.9579 + endloop + endfacet + facet normal 0.443882 -0.774537 0.450623 + outer loop + vertex 669.417 126.355 45.3451 + vertex 670.594 127.065 45.4074 + vertex 670.746 128.055 46.9579 + endloop + endfacet + facet normal 0.424881 -0.775387 0.467173 + outer loop + vertex 667.671 125.476 45.4747 + vertex 669.417 126.355 45.3451 + vertex 670.746 128.055 46.9579 + endloop + endfacet + facet normal 0.438708 -0.779919 0.446388 + outer loop + vertex 670.746 128.055 46.9579 + vertex 664.823 124.709 46.9335 + vertex 667.671 125.476 45.4747 + endloop + endfacet + facet normal 0.465601 -0.752147 0.466358 + outer loop + vertex 676.674 131.994 47.3921 + vertex 670.746 128.055 46.9579 + vertex 673.471 128.938 45.6623 + endloop + endfacet + facet normal 0.484753 -0.704368 0.518536 + outer loop + vertex 682.282 136 47.5916 + vertex 676.674 131.994 47.3921 + vertex 679.19 132.786 46.1157 + endloop + endfacet + facet normal 0.501188 -0.652177 0.56875 + outer loop + vertex 686.772 138.835 46.8863 + vertex 682.282 136 47.5916 + vertex 685.039 136.715 45.9815 + endloop + endfacet + facet normal 0.535457 -0.61306 0.580898 + outer loop + vertex 690.161 141.881 47.0546 + vertex 688.754 140.757 47.166 + vertex 689.02 139.796 45.9062 + endloop + endfacet + facet normal 0.52063 -0.622152 0.584698 + outer loop + vertex 688.754 140.757 47.166 + vertex 686.772 138.835 46.8863 + vertex 689.02 139.796 45.9062 + endloop + endfacet + facet normal 0.52501 -0.582852 0.620201 + outer loop + vertex 691.017 142.74 47.1448 + vertex 690.713 142.648 47.3154 + vertex 693.15 143.184 45.7555 + endloop + endfacet + facet normal 0.524125 -0.586398 0.617601 + outer loop + vertex 690.713 142.648 47.3154 + vertex 690.161 141.881 47.0546 + vertex 693.15 143.184 45.7555 + endloop + endfacet + facet normal 0.357349 -0.830704 0.426887 + outer loop + vertex 689.98 142.759 48.1188 + vertex 691.443 142.683 46.7455 + vertex 691.448 142.718 46.8104 + endloop + endfacet + facet normal -0.53508 0.540673 -0.649124 + outer loop + vertex 691.443 142.683 46.7455 + vertex 691.017 142.74 47.1448 + vertex 693.15 143.184 45.7555 + endloop + endfacet + facet normal -0.582667 0.555271 -0.593441 + outer loop + vertex 687.673 143.277 50.8691 + vertex 689.98 142.759 48.1188 + vertex 688.971 142.978 49.3145 + endloop + endfacet + facet normal 0.673302 -0.459001 0.57964 + outer loop + vertex 685.097 144.117 54.526 + vertex 687.673 143.277 50.8691 + vertex 686.204 143.836 53.0177 + endloop + endfacet + facet normal 0.548073 -0.671888 0.498179 + outer loop + vertex 682.744 145.07 58.3997 + vertex 685.097 144.117 54.526 + vertex 683.417 144.915 57.4502 + endloop + endfacet + facet normal -0.0160576 -0.968932 0.246807 + outer loop + vertex 681.232 145.832 61.2915 + vertex 682.744 145.07 58.3997 + vertex 681.001 146.019 62.0132 + endloop + endfacet + facet normal 0.0739452 -0.959179 0.272961 + outer loop + vertex 680.086 146.498 63.9418 + vertex 681.232 145.832 61.2915 + vertex 681.001 146.019 62.0132 + endloop + endfacet + facet normal 0.888054 -0.276472 0.367319 + outer loop + vertex 679.168 147.278 66.7473 + vertex 680.086 146.498 63.9418 + vertex 679.331 147.185 66.2846 + endloop + endfacet + facet normal 0.891866 -0.292068 0.345356 + outer loop + vertex 677.441 148.737 72.4412 + vertex 679.168 147.278 66.7473 + vertex 677.889 148.596 71.1656 + endloop + endfacet + facet normal 0.956859 -0.125585 0.262011 + outer loop + vertex 675.73 150.604 79.5879 + vertex 677.441 148.737 72.4412 + vertex 676.468 150.063 76.6316 + endloop + endfacet + facet normal 0.866901 -0.420193 0.26818 + outer loop + vertex 674.377 152.549 87.0079 + vertex 675.73 150.604 79.5879 + vertex 674.778 152.63 85.8377 + endloop + endfacet + facet normal 0.887643 -0.405446 0.218413 + outer loop + vertex 673.427 154.649 94.7653 + vertex 674.377 152.549 87.0079 + vertex 673.967 154.111 91.5737 + endloop + endfacet + facet normal 0.885698 -0.427398 0.1813 + outer loop + vertex 672.797 156.722 102.73 + vertex 673.427 154.649 94.7653 + vertex 673.187 156.219 99.6376 + endloop + endfacet + facet normal 0.87513 -0.463994 -0.137319 + outer loop + vertex 672.472 158.191 234.833 + vertex 672.128 159.866 226.977 + vertex 672.502 159.139 231.819 + endloop + endfacet + facet normal 0.894708 -0.406016 -0.186144 + outer loop + vertex 673.618 154.518 249.639 + vertex 672.914 156.436 242.075 + vertex 673.481 155.525 246.787 + endloop + endfacet + facet normal 0.845059 -0.479852 -0.235833 + outer loop + vertex 674.499 152.654 256.59 + vertex 673.618 154.518 249.639 + vertex 674.581 153.305 255.557 + endloop + endfacet + facet normal 0.87692 -0.400033 -0.266429 + outer loop + vertex 675.706 150.744 263.431 + vertex 674.499 152.654 256.59 + vertex 675.517 151.76 261.284 + endloop + endfacet + facet normal 0.924416 -0.238064 -0.297961 + outer loop + vertex 677.81 148.456 271.786 + vertex 675.706 150.744 263.431 + vertex 676.672 150.159 266.895 + endloop + endfacet + facet normal 0.947074 0.130106 -0.293469 + outer loop + vertex 680.089 146.858 278.433 + vertex 677.81 148.456 271.786 + vertex 679.443 147.393 276.585 + endloop + endfacet + facet normal 0.51413 -0.747711 -0.420237 + outer loop + vertex 681.458 145.921 281.832 + vertex 680.443 146.495 279.568 + vertex 681.056 146.273 280.715 + endloop + endfacet + facet normal 0.0681241 -0.959182 -0.274462 + outer loop + vertex 682.761 145.27 284.433 + vertex 681.458 145.921 281.832 + vertex 683.037 145.207 284.722 + endloop + endfacet + facet normal 0.520509 -0.701407 -0.486928 + outer loop + vertex 673.039 132.401 290.325 + vertex 678.652 135.178 292.326 + vertex 677.565 133.28 293.898 + endloop + endfacet + facet normal 0.537733 -0.645626 -0.542227 + outer loop + vertex 681.675 137.704 292.09 + vertex 684.159 140.036 291.778 + vertex 685.511 139.229 294.08 + endloop + endfacet + facet normal 0.522187 -0.673624 -0.523021 + outer loop + vertex 678.652 135.178 292.326 + vertex 681.675 137.704 292.09 + vertex 682.914 136.822 294.463 + endloop + endfacet + facet normal 0.123608 -0.938359 -0.322805 + outer loop + vertex 684.479 144.482 287.38 + vertex 682.761 145.27 284.433 + vertex 683.037 145.207 284.722 + endloop + endfacet + facet normal 0.534795 -0.661491 -0.525761 + outer loop + vertex 686.8 143.685 290.745 + vertex 684.479 144.482 287.38 + vertex 685.796 144.193 289.084 + endloop + endfacet + facet normal 0.241945 -0.970087 -0.019838 + outer loop + vertex 608.544 103.246 303.186 + vertex 609.764 103.505 305.393 + vertex 608.682 103.259 304.215 + endloop + endfacet + facet normal 0.516772 -0.647108 -0.560534 + outer loop + vertex 685.511 139.229 294.08 + vertex 686.336 138.831 295.299 + vertex 682.914 136.822 294.463 + endloop + endfacet + facet normal -0.611566 0.508922 0.605794 + outer loop + vertex 689.169 143.17 293.568 + vertex 686.8 143.685 290.745 + vertex 688.37 143.302 292.65 + endloop + endfacet + facet normal -0.599397 0.44791 0.663401 + outer loop + vertex 691.223 142.98 295.553 + vertex 689.169 143.17 293.568 + vertex 690.686 142.952 295.086 + endloop + endfacet + facet normal 0.50452 -0.572303 -0.646474 + outer loop + vertex 691.009 142.867 295.485 + vertex 691.223 142.98 295.553 + vertex 691.854 142.5 296.471 + endloop + endfacet + facet normal 0.258193 -0.925957 -0.275571 + outer loop + vertex 629.277 109.066 300.51 + vertex 634.129 110.774 299.317 + vertex 630.648 109.473 300.427 + endloop + endfacet + facet normal 0.268371 -0.893806 -0.359287 + outer loop + vertex 634.129 110.774 299.317 + vertex 639.98 112.986 298.185 + vertex 638.494 112.323 298.725 + endloop + endfacet + facet normal 0.269996 -0.845342 -0.460976 + outer loop + vertex 639.98 112.986 298.185 + vertex 645.514 115.306 297.171 + vertex 643.087 114.146 297.878 + endloop + endfacet + facet normal 0.300439 -0.821448 -0.484726 + outer loop + vertex 645.514 115.306 297.171 + vertex 651.342 117.965 296.277 + vertex 649.509 116.904 296.94 + endloop + endfacet + facet normal 0.346655 -0.811244 -0.470865 + outer loop + vertex 651.342 117.965 296.277 + vertex 657.743 120.966 295.821 + vertex 654.963 119.339 296.576 + endloop + endfacet + facet normal 0.38563 -0.802776 -0.454797 + outer loop + vertex 657.743 120.966 295.821 + vertex 664.153 124.256 295.447 + vertex 661.876 122.7 296.263 + endloop + endfacet + facet normal 0.407468 -0.754505 -0.514482 + outer loop + vertex 664.153 124.256 295.447 + vertex 670.231 127.595 295.365 + vertex 667.043 125.463 295.966 + endloop + endfacet + facet normal 0.430244 -0.695469 -0.575512 + outer loop + vertex 670.231 127.595 295.365 + vertex 676.062 131.201 295.366 + vertex 673.588 129.226 295.904 + endloop + endfacet + facet normal 0.51667 -0.701943 -0.490232 + outer loop + vertex 682.914 136.822 294.463 + vertex 677.565 133.28 293.898 + vertex 678.652 135.178 292.326 + endloop + endfacet + facet normal 0.457471 -0.649909 -0.606909 + outer loop + vertex 676.062 131.201 295.366 + vertex 681.573 134.811 295.655 + vertex 679.381 132.885 296.065 + endloop + endfacet + facet normal 0.483071 -0.618835 -0.619423 + outer loop + vertex 681.573 134.811 295.655 + vertex 686.821 138.44 296.122 + vertex 684.343 136.105 296.522 + endloop + endfacet + facet normal 0.484785 -0.558537 -0.673067 + outer loop + vertex 686.821 138.44 296.122 + vertex 690.348 141.145 296.418 + vertex 689.447 139.619 297.035 + endloop + endfacet + facet normal 0.500327 -0.529602 -0.684978 + outer loop + vertex 690.348 141.145 296.418 + vertex 691.854 142.5 296.471 + vertex 691.69 141.52 297.108 + endloop + endfacet + facet normal 0.523534 -0.552056 -0.648957 + outer loop + vertex 693.645 143.512 297.054 + vertex 691.854 142.5 296.471 + vertex 691.223 142.98 295.553 + endloop + endfacet + facet normal 0.53526 -0.661458 -0.525328 + outer loop + vertex 681.675 137.704 292.09 + vertex 685.511 139.229 294.08 + vertex 682.914 136.822 294.463 + endloop + endfacet + facet normal 0.301288 -0.597472 0.743137 + outer loop + vertex 707.138 136.052 32.7165 + vertex 705.931 138.79 35.4073 + vertex 701.218 133.389 32.9757 + endloop + endfacet + facet normal 0.284687 -0.559007 0.778758 + outer loop + vertex 713.956 138.888 32.26 + vertex 713.102 141.87 34.7131 + vertex 707.138 136.052 32.7165 + endloop + endfacet + facet normal 0.323877 -0.586648 0.742259 + outer loop + vertex 707.138 136.052 32.7165 + vertex 713.102 141.87 34.7131 + vertex 705.931 138.79 35.4073 + endloop + endfacet + facet normal 0.262114 -0.521713 0.811857 + outer loop + vertex 722.14 142.514 31.9478 + vertex 721.357 145.604 34.186 + vertex 713.956 138.888 32.26 + endloop + endfacet + facet normal 0.299837 -0.553326 0.777128 + outer loop + vertex 713.956 138.888 32.26 + vertex 721.357 145.604 34.186 + vertex 713.102 141.87 34.7131 + endloop + endfacet + facet normal 0.278074 -0.51632 0.809993 + outer loop + vertex 722.14 142.514 31.9478 + vertex 730.037 149.655 33.7881 + vertex 721.357 145.604 34.186 + endloop + endfacet + facet normal 0.341955 -0.555477 0.757966 + outer loop + vertex 705.931 138.79 35.4073 + vertex 704.996 141.585 37.8773 + vertex 700.391 136.956 36.5628 + endloop + endfacet + facet normal 0.29883 -0.514481 0.803747 + outer loop + vertex 713.102 141.87 34.7131 + vertex 712.292 144.637 36.7851 + vertex 705.931 138.79 35.4073 + endloop + endfacet + facet normal 0.345191 -0.554032 0.757556 + outer loop + vertex 705.931 138.79 35.4073 + vertex 712.292 144.637 36.7851 + vertex 704.996 141.585 37.8773 + endloop + endfacet + facet normal 0.265047 -0.467012 0.843593 + outer loop + vertex 721.357 145.604 34.186 + vertex 720.779 148.506 35.9744 + vertex 713.102 141.87 34.7131 + endloop + endfacet + facet normal 0.309313 -0.510395 0.802386 + outer loop + vertex 713.102 141.87 34.7131 + vertex 720.779 148.506 35.9744 + vertex 712.292 144.637 36.7851 + endloop + endfacet + facet normal 0.238074 -0.42435 0.87364 + outer loop + vertex 730.037 149.655 33.7881 + vertex 729.65 152.688 35.367 + vertex 721.357 145.604 34.186 + endloop + endfacet + facet normal 0.27622 -0.463703 0.841833 + outer loop + vertex 721.357 145.604 34.186 + vertex 729.65 152.688 35.367 + vertex 720.779 148.506 35.9744 + endloop + endfacet + facet normal 0.218528 -0.388719 0.895066 + outer loop + vertex 738.625 153.771 33.4792 + vertex 738.391 156.883 34.8878 + vertex 730.037 149.655 33.7881 + endloop + endfacet + facet normal 0.250171 -0.421709 0.871536 + outer loop + vertex 730.037 149.655 33.7881 + vertex 738.391 156.883 34.8878 + vertex 729.65 152.688 35.367 + endloop + endfacet + facet normal 0.208992 -0.366248 0.906744 + outer loop + vertex 747.06 157.932 33.2158 + vertex 746.891 161.075 34.5242 + vertex 738.625 153.771 33.4792 + endloop + endfacet + facet normal 0.229096 -0.387054 0.893143 + outer loop + vertex 738.625 153.771 33.4792 + vertex 746.891 161.075 34.5242 + vertex 738.391 156.883 34.8878 + endloop + endfacet + facet normal 0.200105 -0.350423 0.914965 + outer loop + vertex 755.409 162.238 33.0389 + vertex 755.259 165.385 34.2771 + vertex 747.06 157.932 33.2158 + endloop + endfacet + facet normal 0.214991 -0.365472 0.905654 + outer loop + vertex 747.06 157.932 33.2158 + vertex 755.259 165.385 34.2771 + vertex 746.891 161.075 34.5242 + endloop + endfacet + facet normal 0.196001 -0.338982 0.920149 + outer loop + vertex 763.646 166.714 32.9335 + vertex 763.531 169.871 34.1208 + vertex 755.409 162.238 33.0389 + endloop + endfacet + facet normal 0.206858 -0.34963 0.913766 + outer loop + vertex 755.409 162.238 33.0389 + vertex 763.531 169.871 34.1208 + vertex 755.259 165.385 34.2771 + endloop + endfacet + facet normal 0.202214 -0.335829 0.919961 + outer loop + vertex 771.751 171.386 32.8574 + vertex 771.644 174.537 34.0311 + vertex 763.646 166.714 32.9335 + endloop + endfacet + facet normal 0.204609 -0.338088 0.918603 + outer loop + vertex 763.646 166.714 32.9335 + vertex 771.644 174.537 34.0311 + vertex 763.531 169.871 34.1208 + endloop + endfacet + facet normal 0.215248 -0.337386 0.916427 + outer loop + vertex 779.803 176.317 32.7813 + vertex 779.587 179.398 33.9667 + vertex 771.751 171.386 32.8574 + endloop + endfacet + facet normal 0.212348 -0.334776 0.918059 + outer loop + vertex 771.751 171.386 32.8574 + vertex 779.587 179.398 33.9667 + vertex 771.644 174.537 34.0311 + endloop + endfacet + facet normal 0.229151 -0.33953 0.912255 + outer loop + vertex 787.912 181.538 32.688 + vertex 787.423 184.52 33.9205 + vertex 779.803 176.317 32.7813 + endloop + endfacet + facet normal 0.224997 -0.335996 0.914594 + outer loop + vertex 779.803 176.317 32.7813 + vertex 787.423 184.52 33.9205 + vertex 779.587 179.398 33.9667 + endloop + endfacet + facet normal 0.235452 -0.336909 0.911622 + outer loop + vertex 795.933 186.799 32.5606 + vertex 795.141 189.866 33.8981 + vertex 787.912 181.538 32.688 + endloop + endfacet + facet normal 0.236576 -0.337795 0.911003 + outer loop + vertex 787.912 181.538 32.688 + vertex 795.141 189.866 33.8981 + vertex 787.423 184.52 33.9205 + endloop + endfacet + facet normal 0.257758 -0.346094 0.902098 + outer loop + vertex 803.744 192.602 32.5547 + vertex 802.608 195.395 33.9509 + vertex 795.933 186.799 32.5606 + endloop + endfacet + facet normal 0.241594 -0.334939 0.91074 + outer loop + vertex 795.933 186.799 32.5606 + vertex 802.608 195.395 33.9509 + vertex 795.141 189.866 33.8981 + endloop + endfacet + facet normal 0.287617 -0.367892 0.884269 + outer loop + vertex 810.78 198.13 32.5659 + vertex 809.646 200.957 34.1112 + vertex 803.744 192.602 32.5547 + endloop + endfacet + facet normal 0.254244 -0.347711 0.902473 + outer loop + vertex 803.744 192.602 32.5547 + vertex 809.646 200.957 34.1112 + vertex 802.608 195.395 33.9509 + endloop + endfacet + facet normal 0.310431 -0.398346 0.863106 + outer loop + vertex 817.458 203.682 32.7268 + vertex 816.325 206.509 34.4389 + vertex 810.78 198.13 32.5659 + endloop + endfacet + facet normal 0.269377 -0.376393 0.886434 + outer loop + vertex 810.78 198.13 32.5659 + vertex 816.325 206.509 34.4389 + vertex 809.646 200.957 34.1112 + endloop + endfacet + facet normal 0.339127 -0.438865 0.8321 + outer loop + vertex 824.16 209.508 33.0683 + vertex 822.901 212.252 35.0288 + vertex 817.458 203.682 32.7268 + endloop + endfacet + facet normal 0.281982 -0.411825 0.866537 + outer loop + vertex 817.458 203.682 32.7268 + vertex 822.901 212.252 35.0288 + vertex 816.325 206.509 34.4389 + endloop + endfacet + facet normal 0.373376 -0.485433 0.790535 + outer loop + vertex 830.865 215.791 33.7595 + vertex 829.44 218.278 35.9597 + vertex 824.16 209.508 33.0683 + endloop + endfacet + facet normal 0.303061 -0.45799 0.835703 + outer loop + vertex 824.16 209.508 33.0683 + vertex 829.44 218.278 35.9597 + vertex 822.901 212.252 35.0288 + endloop + endfacet + facet normal 0.337304 -0.507941 0.792605 + outer loop + vertex 830.865 215.791 33.7595 + vertex 835.718 224.45 37.2432 + vertex 829.44 218.278 35.9597 + endloop + endfacet + facet normal 0.368026 -0.528626 0.764926 + outer loop + vertex 704.996 141.585 37.8773 + vertex 704.301 143.897 39.8099 + vertex 699.388 139.604 39.206 + endloop + endfacet + facet normal 0.324871 -0.486284 0.811164 + outer loop + vertex 712.292 144.637 36.7851 + vertex 711.693 146.926 38.3971 + vertex 704.996 141.585 37.8773 + endloop + endfacet + facet normal 0.3637 -0.530544 0.765666 + outer loop + vertex 704.996 141.585 37.8773 + vertex 711.693 146.926 38.3971 + vertex 704.301 143.897 39.8099 + endloop + endfacet + facet normal 0.278441 -0.430942 0.858347 + outer loop + vertex 720.779 148.506 35.9744 + vertex 720.295 150.797 37.2816 + vertex 712.292 144.637 36.7851 + endloop + endfacet + facet normal 0.324165 -0.486554 0.811284 + outer loop + vertex 712.292 144.637 36.7851 + vertex 720.295 150.797 37.2816 + vertex 711.693 146.926 38.3971 + endloop + endfacet + facet normal 0.281717 -0.429929 0.857786 + outer loop + vertex 720.779 148.506 35.9744 + vertex 729.355 155.053 36.4391 + vertex 720.295 150.797 37.2816 + endloop + endfacet + facet normal 0.268545 -0.397558 0.8774 + outer loop + vertex 822.901 212.252 35.0288 + vertex 822.117 214.482 36.2789 + vertex 816.325 206.509 34.4389 + endloop + endfacet + facet normal 0.296602 -0.451852 0.841343 + outer loop + vertex 829.44 218.278 35.9597 + vertex 828.556 220.428 37.426 + vertex 822.901 212.252 35.0288 + endloop + endfacet + facet normal 0.226 -0.414765 0.881416 + outer loop + vertex 822.901 212.252 35.0288 + vertex 828.556 220.428 37.426 + vertex 822.117 214.482 36.2789 + endloop + endfacet + facet normal 0.337343 -0.507973 0.792567 + outer loop + vertex 835.718 224.45 37.2432 + vertex 834.716 226.409 38.9257 + vertex 829.44 218.278 35.9597 + endloop + endfacet + facet normal 0.252762 -0.47206 0.844554 + outer loop + vertex 829.44 218.278 35.9597 + vertex 834.716 226.409 38.9257 + vertex 828.556 220.428 37.426 + endloop + endfacet + facet normal 0.297993 -0.529529 0.794229 + outer loop + vertex 835.718 224.45 37.2432 + vertex 840.144 231.907 40.5544 + vertex 834.716 226.409 38.9257 + endloop + endfacet + facet normal 0.397517 -0.616921 0.679256 + outer loop + vertex 845.136 233.643 39.1403 + vertex 846.877 237.909 41.9951 + vertex 844.488 236.513 42.1255 + endloop + endfacet + facet normal 0.391557 -0.51189 0.764625 + outer loop + vertex 704.301 143.897 39.8099 + vertex 703.467 145.515 41.3193 + vertex 698.62 141.779 41.3008 + endloop + endfacet + facet normal 0.348158 -0.471948 0.80997 + outer loop + vertex 711.693 146.926 38.3971 + vertex 711.117 148.446 39.53 + vertex 704.301 143.897 39.8099 + endloop + endfacet + facet normal 0.378333 -0.519883 0.765889 + outer loop + vertex 704.301 143.897 39.8099 + vertex 711.117 148.446 39.53 + vertex 703.467 145.515 41.3193 + endloop + endfacet + facet normal 0.297319 -0.412554 0.861046 + outer loop + vertex 720.295 150.797 37.2816 + vertex 719.591 152.124 38.1604 + vertex 711.693 146.926 38.3971 + endloop + endfacet + facet normal 0.338117 -0.476807 0.811377 + outer loop + vertex 711.693 146.926 38.3971 + vertex 719.591 152.124 38.1604 + vertex 711.117 148.446 39.53 + endloop + endfacet + facet normal 0.291146 -0.416098 0.861451 + outer loop + vertex 720.295 150.797 37.2816 + vertex 728.77 156.357 37.1027 + vertex 719.591 152.124 38.1604 + endloop + endfacet + facet normal 0.215175 -0.404482 0.888872 + outer loop + vertex 828.556 220.428 37.426 + vertex 827.976 221.71 38.1496 + vertex 822.117 214.482 36.2789 + endloop + endfacet + facet normal 0.15366 -0.362475 0.919239 + outer loop + vertex 822.117 214.482 36.2789 + vertex 827.976 221.71 38.1496 + vertex 821.436 215.623 36.8427 + endloop + endfacet + facet normal 0.258325 -0.476709 0.840248 + outer loop + vertex 834.716 226.409 38.9257 + vertex 834.203 227.787 39.8649 + vertex 828.556 220.428 37.426 + endloop + endfacet + facet normal 0.169942 -0.425066 0.889066 + outer loop + vertex 828.556 220.428 37.426 + vertex 834.203 227.787 39.8649 + vertex 827.976 221.71 38.1496 + endloop + endfacet + facet normal 0.306944 -0.53605 0.786407 + outer loop + vertex 840.144 231.907 40.5544 + vertex 839.462 233.16 41.6745 + vertex 834.716 226.409 38.9257 + endloop + endfacet + facet normal 0.215058 -0.494212 0.842321 + outer loop + vertex 834.716 226.409 38.9257 + vertex 839.462 233.16 41.6745 + vertex 834.203 227.787 39.8649 + endloop + endfacet + facet normal 0.403346 -0.628198 0.665341 + outer loop + vertex 846.877 237.909 41.9951 + vertex 846.466 240.314 44.5148 + vertex 844.488 236.513 42.1255 + endloop + endfacet + facet normal 0.232297 -0.601437 0.764403 + outer loop + vertex 844.488 236.513 42.1255 + vertex 846.466 240.314 44.5148 + vertex 845.429 239.444 44.1459 + endloop + endfacet + facet normal 0.402773 -0.456223 0.793495 + outer loop + vertex 704.455 146.858 41.5908 + vertex 699.962 144.932 42.7637 + vertex 703.467 145.515 41.3193 + endloop + endfacet + facet normal 0.402393 -0.462515 0.790037 + outer loop + vertex 697.507 143.068 42.9228 + vertex 703.467 145.515 41.3193 + vertex 699.962 144.932 42.7637 + endloop + endfacet + facet normal 0.352101 -0.403383 0.844575 + outer loop + vertex 711.117 148.446 39.53 + vertex 710.59 149.362 40.1875 + vertex 703.467 145.515 41.3193 + endloop + endfacet + facet normal 0.365684 -0.434912 0.822877 + outer loop + vertex 703.467 145.515 41.3193 + vertex 710.59 149.362 40.1875 + vertex 704.455 146.858 41.5908 + endloop + endfacet + facet normal 0.32979 -0.417691 0.846624 + outer loop + vertex 711.117 148.446 39.53 + vertex 718.219 152.508 38.7682 + vertex 710.59 149.362 40.1875 + endloop + endfacet + facet normal 0.042928 -0.253614 0.966352 + outer loop + vertex 827.976 221.71 38.1496 + vertex 826.638 221.386 38.1239 + vertex 821.436 215.623 36.8427 + endloop + endfacet + facet normal 0.147843 -0.406024 0.901824 + outer loop + vertex 834.203 227.787 39.8649 + vertex 834.142 228.698 40.2851 + vertex 827.976 221.71 38.1496 + endloop + endfacet + facet normal 0.0653694 -0.343918 0.936721 + outer loop + vertex 827.976 221.71 38.1496 + vertex 834.142 228.698 40.2851 + vertex 826.638 221.386 38.1239 + endloop + endfacet + facet normal 0.239615 -0.51231 0.824696 + outer loop + vertex 839.462 233.16 41.6745 + vertex 839.317 233.893 42.1722 + vertex 834.203 227.787 39.8649 + endloop + endfacet + facet normal 0.176042 -0.486277 0.855888 + outer loop + vertex 840.138 234.899 42.5751 + vertex 834.142 228.698 40.2851 + vertex 839.317 233.893 42.1722 + endloop + endfacet + facet normal 0.0835374 -0.412711 0.907023 + outer loop + vertex 834.142 228.698 40.2851 + vertex 834.203 227.787 39.8649 + vertex 839.317 233.893 42.1722 + endloop + endfacet + facet normal 0.291867 -0.609529 0.737081 + outer loop + vertex 845.374 240.189 44.7904 + vertex 844.889 240.097 44.9064 + vertex 843.031 237.862 43.7934 + endloop + endfacet + facet normal 0.292589 -0.609853 0.736526 + outer loop + vertex 843.031 237.862 43.7934 + vertex 844.889 240.097 44.9064 + vertex 842.938 237.969 43.9192 + endloop + endfacet + facet normal 0.316394 -0.607011 0.728994 + outer loop + vertex 845.429 239.444 44.1459 + vertex 845.374 240.189 44.7904 + vertex 843.468 237.363 43.2644 + endloop + endfacet + facet normal 0.257639 -0.58783 0.766863 + outer loop + vertex 843.468 237.363 43.2644 + vertex 845.374 240.189 44.7904 + vertex 843.031 237.862 43.7934 + endloop + endfacet + facet normal 0.288121 -0.566579 0.771994 + outer loop + vertex 843.468 237.363 43.2644 + vertex 843.031 237.862 43.7934 + vertex 839.462 233.16 41.6745 + endloop + endfacet + facet normal 0.197552 -0.523448 0.82884 + outer loop + vertex 839.462 233.16 41.6745 + vertex 843.031 237.862 43.7934 + vertex 839.317 233.893 42.1722 + endloop + endfacet + facet normal 0.31348 -0.595512 0.739659 + outer loop + vertex 843.031 237.862 43.7934 + vertex 842.938 237.969 43.9192 + vertex 839.317 233.893 42.1722 + endloop + endfacet + facet normal -0.360825 -0.077712 0.92939 + outer loop + vertex 839.317 233.893 42.1722 + vertex 842.938 237.969 43.9192 + vertex 840.138 234.899 42.5751 + endloop + endfacet + facet normal 0.289864 -0.683056 0.670384 + outer loop + vertex 844.889 240.097 44.9064 + vertex 845.374 240.189 44.7904 + vertex 845.956 241.044 45.4091 + endloop + endfacet + facet normal 0.257345 -0.621098 0.740278 + outer loop + vertex 845.429 239.444 44.1459 + vertex 846.466 240.314 44.5148 + vertex 845.374 240.189 44.7904 + endloop + endfacet + facet normal 0.251766 -0.674325 0.69419 + outer loop + vertex 846.466 240.314 44.5148 + vertex 845.956 241.044 45.4091 + vertex 845.374 240.189 44.7904 + endloop + endfacet + facet normal 0.363327 -0.313084 0.87748 + outer loop + vertex 704.455 146.858 41.5908 + vertex 701.117 145.649 42.5415 + vertex 699.962 144.932 42.7637 + endloop + endfacet + facet normal 0.422765 -0.434192 0.795454 + outer loop + vertex 699.962 144.932 42.7637 + vertex 701.117 145.649 42.5415 + vertex 697.919 144.402 43.5598 + endloop + endfacet + facet normal 0.42293 -0.438554 0.792969 + outer loop + vertex 699.962 144.932 42.7637 + vertex 697.919 144.402 43.5598 + vertex 696.683 143.587 43.769 + endloop + endfacet + facet normal 0.76549 -0.537247 -0.354105 + outer loop + vertex 844.889 240.097 44.9064 + vertex 844.767 239.934 44.8905 + vertex 842.938 237.969 43.9192 + endloop + endfacet + facet normal 0.154242 0.318841 -0.935174 + outer loop + vertex 842.938 237.969 43.9192 + vertex 844.767 239.934 44.8905 + vertex 843.039 237.964 43.9338 + endloop + endfacet + facet normal 0.153766 0.275203 -0.94901 + outer loop + vertex 842.938 237.969 43.9192 + vertex 843.039 237.964 43.9338 + vertex 840.138 234.899 42.5751 + endloop + endfacet + facet normal -0.537306 0.710312 -0.454708 + outer loop + vertex 840.138 234.899 42.5751 + vertex 843.039 237.964 43.9338 + vertex 841.192 235.962 42.9897 + endloop + endfacet + facet normal 0.493072 -0.497042 0.714023 + outer loop + vertex 851.411 221.057 23.0545 + vertex 854.308 224.139 23.1992 + vertex 852 223.335 24.2333 + endloop + endfacet + facet normal 0.497105 -0.484019 0.720147 + outer loop + vertex 848.322 217.607 22.8678 + vertex 851.411 221.057 23.0545 + vertex 848.99 220.163 24.1251 + endloop + endfacet + facet normal 0.477673 -0.485136 0.732442 + outer loop + vertex 843.806 213.502 23.0946 + vertex 848.322 217.607 22.8678 + vertex 845.341 216.546 24.1093 + endloop + endfacet + facet normal 0.469643 -0.486765 0.736543 + outer loop + vertex 839.045 209.323 23.3679 + vertex 843.806 213.502 23.0946 + vertex 841.478 212.967 24.2254 + endloop + endfacet + facet normal 0.46698 -0.489224 0.736607 + outer loop + vertex 834.4 204.568 23.1547 + vertex 839.045 209.323 23.3679 + vertex 835.554 207.432 24.3258 + endloop + endfacet + facet normal 0.459879 -0.495636 0.736787 + outer loop + vertex 829.883 200.658 23.3438 + vertex 834.4 204.568 23.1547 + vertex 831.734 203.825 24.3188 + endloop + endfacet + facet normal 0.456366 -0.500511 0.735676 + outer loop + vertex 825.884 197.226 23.4902 + vertex 829.883 200.658 23.3438 + vertex 827.914 200.404 24.3927 + endloop + endfacet + facet normal 0.450061 -0.506563 0.735417 + outer loop + vertex 821.471 193.688 23.7532 + vertex 825.884 197.226 23.4902 + vertex 824.287 197.324 24.5348 + endloop + endfacet + facet normal 0.444424 -0.513313 0.734164 + outer loop + vertex 816.978 189.753 23.722 + vertex 821.471 193.688 23.7532 + vertex 818.283 192.255 24.681 + endloop + endfacet + facet normal 0.435624 -0.518995 0.735443 + outer loop + vertex 812.666 186.292 23.8336 + vertex 816.978 189.753 23.722 + vertex 814.306 188.996 24.7704 + endloop + endfacet + facet normal 0.428357 -0.526345 0.734487 + outer loop + vertex 808.247 182.901 23.9811 + vertex 812.666 186.292 23.8336 + vertex 809.881 185.69 25.0266 + endloop + endfacet + facet normal 0.420147 -0.529402 0.737028 + outer loop + vertex 804.524 179.96 23.9905 + vertex 808.247 182.901 23.9811 + vertex 804.566 181.823 25.305 + endloop + endfacet + facet normal 0.409283 -0.532092 0.741192 + outer loop + vertex 800.483 177.605 24.5315 + vertex 804.524 179.96 23.9905 + vertex 804.566 181.823 25.305 + endloop + endfacet + facet normal 0.351423 -0.677459 0.646182 + outer loop + vertex 848.136 240.643 43.9523 + vertex 847.08 242.431 46.4005 + vertex 846.466 240.314 44.5148 + endloop + endfacet + facet normal 0.556851 -0.547507 0.624622 + outer loop + vertex 853.934 228.094 26.3871 + vertex 852.315 230.479 29.922 + vertex 852.613 228.216 27.6718 + endloop + endfacet + facet normal -0.863416 0.341621 -0.371225 + outer loop + vertex 854.308 224.139 23.1992 + vertex 854.641 226.2 24.3212 + vertex 854.621 225.898 24.0908 + endloop + endfacet + facet normal 0.456814 -0.531529 0.713301 + outer loop + vertex 699.023 144.93 43.2466 + vertex 696.23 143.898 44.2665 + vertex 697.919 144.402 43.5598 + endloop + endfacet + facet normal 0.396892 -0.307344 0.864879 + outer loop + vertex 701.58 145.927 42.4275 + vertex 699.023 144.93 43.2466 + vertex 701.117 145.649 42.5415 + endloop + endfacet + facet normal 0.316354 -0.142954 0.937808 + outer loop + vertex 704.065 146.919 41.7404 + vertex 701.58 145.927 42.4275 + vertex 701.117 145.649 42.5415 + endloop + endfacet + facet normal 0.314026 -0.246365 0.916893 + outer loop + vertex 707.841 148.762 40.9425 + vertex 704.065 146.919 41.7404 + vertex 704.455 146.858 41.5908 + endloop + endfacet + facet normal 0.309846 -0.273831 0.910501 + outer loop + vertex 711.974 150.795 40.1474 + vertex 707.841 148.762 40.9425 + vertex 710.59 149.362 40.1875 + endloop + endfacet + facet normal 0.278161 -0.242696 0.929368 + outer loop + vertex 716.64 152.892 39.2984 + vertex 711.974 150.795 40.1474 + vertex 710.59 149.362 40.1875 + endloop + endfacet + facet normal 0.255235 -0.243309 0.935765 + outer loop + vertex 722.875 155.393 38.2481 + vertex 716.64 152.892 39.2984 + vertex 718.219 152.508 38.7682 + endloop + endfacet + facet normal 0.197591 -0.156974 0.967635 + outer loop + vertex 728.044 157.891 37.598 + vertex 722.875 155.393 38.2481 + vertex 727.142 156.538 37.5626 + endloop + endfacet + facet normal 0.163939 -0.1348 0.977217 + outer loop + vertex 733.068 159.859 37.0265 + vertex 728.044 157.891 37.598 + vertex 727.142 156.538 37.5626 + endloop + endfacet + facet normal 0.1527 -0.154807 0.976072 + outer loop + vertex 738.487 162.574 36.6095 + vertex 733.068 159.859 37.0265 + vertex 736.783 160.962 36.6202 + endloop + endfacet + facet normal 0.137098 -0.172606 0.975403 + outer loop + vertex 749.463 167.589 35.8993 + vertex 743.883 164.981 36.222 + vertex 745.15 164.885 36.027 + endloop + endfacet + facet normal 0.102079 -0.177268 0.978854 + outer loop + vertex 805.859 203.696 35.7497 + vertex 802.267 200.611 35.5657 + vertex 801.037 198.92 35.3877 + endloop + endfacet + facet normal 0.115857 -0.211482 0.970491 + outer loop + vertex 811.285 207.992 36.0382 + vertex 805.859 203.696 35.7497 + vertex 807.593 204.202 35.6531 + endloop + endfacet + facet normal 0.112517 -0.22911 0.966876 + outer loop + vertex 815.306 211.303 36.3549 + vertex 811.285 207.992 36.0382 + vertex 814.261 209.925 36.15 + endloop + endfacet + facet normal 0.045245 -0.180433 0.982546 + outer loop + vertex 818.683 214.4 36.7681 + vertex 815.306 211.303 36.3549 + vertex 814.261 209.925 36.15 + endloop + endfacet + facet normal 0.0788125 -0.249409 0.965186 + outer loop + vertex 823.192 218.892 37.5607 + vertex 818.683 214.4 36.7681 + vertex 820.231 215.326 36.8811 + endloop + endfacet + facet normal -0.0382578 -0.169554 0.984778 + outer loop + vertex 826.995 222.477 38.3258 + vertex 823.192 218.892 37.5607 + vertex 826.638 221.386 38.1239 + endloop + endfacet + facet normal -0.122584 -0.141493 0.98232 + outer loop + vertex 830.434 225.655 39.2126 + vertex 826.995 222.477 38.3258 + vertex 826.638 221.386 38.1239 + endloop + endfacet + facet normal -0.0914875 -0.229949 0.968893 + outer loop + vertex 834.007 229.463 40.4539 + vertex 830.434 225.655 39.2126 + vertex 834.142 228.698 40.2851 + endloop + endfacet + facet normal -0.126275 -0.234986 0.963762 + outer loop + vertex 838.327 233.455 41.9931 + vertex 834.007 229.463 40.4539 + vertex 834.142 228.698 40.2851 + endloop + endfacet + facet normal 0.232806 -0.577061 0.782816 + outer loop + vertex 842.061 237.17 43.6215 + vertex 838.327 233.455 41.9931 + vertex 841.192 235.962 42.9897 + endloop + endfacet + facet normal 0.302709 -0.648009 0.698893 + outer loop + vertex 844.973 240.23 45.1976 + vertex 842.061 237.17 43.6215 + vertex 843.039 237.964 43.9338 + endloop + endfacet + facet normal 0.510845 -0.733958 0.447597 + outer loop + vertex 847.08 242.431 46.4005 + vertex 844.973 240.23 45.1976 + vertex 845.956 241.044 45.4091 + endloop + endfacet + facet normal 0.429018 -0.516849 0.740818 + outer loop + vertex 814.306 188.996 24.7704 + vertex 809.881 185.69 25.0266 + vertex 812.666 186.292 23.8336 + endloop + endfacet + facet normal 0.419979 -0.523895 0.741047 + outer loop + vertex 809.881 185.69 25.0266 + vertex 804.566 181.823 25.305 + vertex 808.247 182.901 23.9811 + endloop + endfacet + facet normal 0.444123 -0.511874 0.73535 + outer loop + vertex 821.362 195.095 24.7984 + vertex 818.283 192.255 24.681 + vertex 821.471 193.688 23.7532 + endloop + endfacet + facet normal 0.435564 -0.511264 0.740873 + outer loop + vertex 818.283 192.255 24.681 + vertex 814.306 188.996 24.7704 + vertex 816.978 189.753 23.722 + endloop + endfacet + facet normal 0.452762 -0.49911 0.738848 + outer loop + vertex 827.914 200.404 24.3927 + vertex 824.287 197.324 24.5348 + vertex 825.884 197.226 23.4902 + endloop + endfacet + facet normal 0.453611 -0.508548 0.731858 + outer loop + vertex 824.287 197.324 24.5348 + vertex 821.362 195.095 24.7984 + vertex 821.471 193.688 23.7532 + endloop + endfacet + facet normal 0.459947 -0.488413 0.741554 + outer loop + vertex 835.554 207.432 24.3258 + vertex 831.734 203.825 24.3188 + vertex 834.4 204.568 23.1547 + endloop + endfacet + facet normal 0.457354 -0.494814 0.738909 + outer loop + vertex 831.734 203.825 24.3188 + vertex 827.914 200.404 24.3927 + vertex 829.883 200.658 23.3438 + endloop + endfacet + facet normal 0.471049 -0.487394 0.735228 + outer loop + vertex 841.478 212.967 24.2254 + vertex 838.481 210.428 24.4615 + vertex 839.045 209.323 23.3679 + endloop + endfacet + facet normal 0.467225 -0.490027 0.735917 + outer loop + vertex 838.481 210.428 24.4615 + vertex 835.554 207.432 24.3258 + vertex 839.045 209.323 23.3679 + endloop + endfacet + facet normal 0.477666 -0.485026 0.73252 + outer loop + vertex 848.99 220.163 24.1251 + vertex 845.341 216.546 24.1093 + vertex 848.322 217.607 22.8678 + endloop + endfacet + facet normal 0.469881 -0.483286 0.738679 + outer loop + vertex 845.341 216.546 24.1093 + vertex 841.478 212.967 24.2254 + vertex 843.806 213.502 23.0946 + endloop + endfacet + facet normal 0.492873 -0.490448 0.718705 + outer loop + vertex 853.663 225.398 24.5007 + vertex 852 223.335 24.2333 + vertex 854.308 224.139 23.1992 + endloop + endfacet + facet normal 0.497746 -0.496695 0.711016 + outer loop + vertex 852 223.335 24.2333 + vertex 848.99 220.163 24.1251 + vertex 851.411 221.057 23.0545 + endloop + endfacet + facet normal 0.58483 -0.453425 0.672592 + outer loop + vertex 854.651 226.16 24.2633 + vertex 854.409 226.115 24.4436 + vertex 854.308 224.139 23.1992 + endloop + endfacet + facet normal 0.512485 -0.476154 0.714589 + outer loop + vertex 854.409 226.115 24.4436 + vertex 853.663 225.398 24.5007 + vertex 854.308 224.139 23.1992 + endloop + endfacet + facet normal 0.875416 -0.333125 0.350251 + outer loop + vertex 854.621 225.898 24.0908 + vertex 854.651 226.16 24.2633 + vertex 854.308 224.139 23.1992 + endloop + endfacet + facet normal 0.351612 -0.58182 0.733385 + outer loop + vertex 840.144 231.907 40.5544 + vertex 841.179 229.975 38.5256 + vertex 844.488 236.513 42.1255 + endloop + endfacet + facet normal 0.447171 -0.594397 0.668379 + outer loop + vertex 845.136 233.643 39.1403 + vertex 844.488 236.513 42.1255 + vertex 841.179 229.975 38.5256 + endloop + endfacet + facet normal 0.27085 -0.555484 0.786179 + outer loop + vertex 839.462 233.16 41.6745 + vertex 840.144 231.907 40.5544 + vertex 843.468 237.363 43.2644 + endloop + endfacet + facet normal 0.355087 -0.646654 0.675093 + outer loop + vertex 846.466 240.314 44.5148 + vertex 846.877 237.909 41.9951 + vertex 848.136 240.643 43.9523 + endloop + endfacet + facet normal 0.312911 -0.605052 0.732119 + outer loop + vertex 844.488 236.513 42.1255 + vertex 845.429 239.444 44.1459 + vertex 843.468 237.363 43.2644 + endloop + endfacet + facet normal 0.303293 -0.22411 0.926169 + outer loop + vertex 704.455 146.858 41.5908 + vertex 710.59 149.362 40.1875 + vertex 707.841 148.762 40.9425 + endloop + endfacet + facet normal 0.263643 -0.215047 0.940344 + outer loop + vertex 710.59 149.362 40.1875 + vertex 718.219 152.508 38.7682 + vertex 716.64 152.892 39.2984 + endloop + endfacet + facet normal 0.192527 -0.135567 0.971882 + outer loop + vertex 718.219 152.508 38.7682 + vertex 727.142 156.538 37.5626 + vertex 722.875 155.393 38.2481 + endloop + endfacet + facet normal 0.129244 -0.0709679 0.98907 + outer loop + vertex 727.142 156.538 37.5626 + vertex 736.783 160.962 36.6202 + vertex 733.068 159.859 37.0265 + endloop + endfacet + facet normal 0.139403 -0.149291 0.978917 + outer loop + vertex 736.783 160.962 36.6202 + vertex 745.15 164.885 36.027 + vertex 743.883 164.981 36.222 + endloop + endfacet + facet normal 0.105984 -0.122442 0.986801 + outer loop + vertex 745.15 164.885 36.027 + vertex 753.473 169.118 35.6584 + vertex 749.463 167.589 35.8993 + endloop + endfacet + facet normal 0.115878 -0.178101 0.977165 + outer loop + vertex 793.434 193.164 35.2403 + vertex 801.037 198.92 35.3877 + vertex 798.38 197.795 35.4978 + endloop + endfacet + facet normal 0.107917 -0.183034 0.977165 + outer loop + vertex 801.037 198.92 35.3877 + vertex 807.593 204.202 35.6531 + vertex 805.859 203.696 35.7497 + endloop + endfacet + facet normal 0.0760979 -0.173902 0.981818 + outer loop + vertex 807.593 204.202 35.6531 + vertex 814.261 209.925 36.15 + vertex 811.285 207.992 36.0382 + endloop + endfacet + facet normal 0.0233339 -0.159385 0.986941 + outer loop + vertex 814.261 209.925 36.15 + vertex 820.231 215.326 36.8811 + vertex 818.683 214.4 36.7681 + endloop + endfacet + facet normal -0.0631848 -0.13599 0.988693 + outer loop + vertex 820.231 215.326 36.8811 + vertex 826.638 221.386 38.1239 + vertex 823.192 218.892 37.5607 + endloop + endfacet + facet normal -0.283542 0.00758943 0.95893 + outer loop + vertex 826.638 221.386 38.1239 + vertex 834.142 228.698 40.2851 + vertex 830.434 225.655 39.2126 + endloop + endfacet + facet normal -0.112792 -0.246423 0.962577 + outer loop + vertex 834.142 228.698 40.2851 + vertex 840.138 234.899 42.5751 + vertex 838.327 233.455 41.9931 + endloop + endfacet + facet normal 0.672584 -0.444624 -0.591557 + outer loop + vertex 844.889 240.097 44.9064 + vertex 845.956 241.044 45.4091 + vertex 844.767 239.934 44.8905 + endloop + endfacet + facet normal 0.23364 -0.683612 0.691438 + outer loop + vertex 845.956 241.044 45.4091 + vertex 846.466 240.314 44.5148 + vertex 847.08 242.431 46.4005 + endloop + endfacet + facet normal 0.328668 -0.178062 0.927508 + outer loop + vertex 701.117 145.649 42.5415 + vertex 704.455 146.858 41.5908 + vertex 704.065 146.919 41.7404 + endloop + endfacet + facet normal 0.402079 -0.334916 0.852152 + outer loop + vertex 697.919 144.402 43.5598 + vertex 701.117 145.649 42.5415 + vertex 699.023 144.93 43.2466 + endloop + endfacet + facet normal 0.456876 -0.507798 0.730346 + outer loop + vertex 695.412 143.344 44.3931 + vertex 697.919 144.402 43.5598 + vertex 696.23 143.898 44.2665 + endloop + endfacet + facet normal 0.67695 -0.701622 0.222407 + outer loop + vertex 843.039 237.964 43.9338 + vertex 844.767 239.934 44.8905 + vertex 844.973 240.23 45.1976 + endloop + endfacet + facet normal -0.0465989 -0.322471 0.945432 + outer loop + vertex 840.138 234.899 42.5751 + vertex 841.192 235.962 42.9897 + vertex 838.327 233.455 41.9931 + endloop + endfacet + facet normal 0.202523 -0.564413 0.800264 + outer loop + vertex 841.192 235.962 42.9897 + vertex 843.039 237.964 43.9338 + vertex 842.061 237.17 43.6215 + endloop + endfacet + facet normal 0.546955 -0.755186 0.361297 + outer loop + vertex 845.956 241.044 45.4091 + vertex 844.973 240.23 45.1976 + vertex 844.767 239.934 44.8905 + endloop + endfacet + facet normal 0.344672 -0.577541 0.740033 + outer loop + vertex 840.144 231.907 40.5544 + vertex 844.488 236.513 42.1255 + vertex 843.468 237.363 43.2644 + endloop + endfacet + facet normal 0.272827 -0.959333 -0.0724223 + outer loop + vertex 650.341 113.554 309.517 + vertex 656.991 115.424 309.803 + vertex 654.131 114.53 310.864 + endloop + endfacet + facet normal 0.2737 -0.959264 -0.0700102 + outer loop + vertex 656.991 115.424 309.803 + vertex 659.854 116.172 310.75 + vertex 654.131 114.53 310.864 + endloop + endfacet + facet normal 0.27527 -0.961177 -0.0191126 + outer loop + vertex 654.131 114.53 310.864 + vertex 659.854 116.172 310.75 + vertex 657.526 115.484 311.803 + endloop + endfacet + facet normal 0.272974 -0.961709 -0.0245358 + outer loop + vertex 659.854 116.172 310.75 + vertex 661.849 116.722 311.383 + vertex 657.526 115.484 311.803 + endloop + endfacet + facet normal 0.276629 -0.96085 0.0156338 + outer loop + vertex 657.526 115.484 311.803 + vertex 661.849 116.722 311.383 + vertex 659.876 116.171 312.456 + endloop + endfacet + facet normal 0.263449 -0.964616 -0.0105576 + outer loop + vertex 661.849 116.722 311.383 + vertex 662.523 116.9 311.901 + vertex 659.876 116.171 312.456 + endloop + endfacet + facet normal 0.27721 -0.958755 0.0627884 + outer loop + vertex 659.876 116.171 312.456 + vertex 662.523 116.9 311.901 + vertex 660.689 116.442 313.003 + endloop + endfacet + facet normal 0.235058 -0.944321 0.23023 + outer loop + vertex 636.508 111.282 316.862 + vertex 634.425 110.639 316.35 + vertex 638.273 111.7 316.773 + endloop + endfacet + facet normal 0.234143 -0.927133 0.292578 + outer loop + vertex 639.644 112.266 317.469 + vertex 636.508 111.282 316.862 + vertex 638.273 111.7 316.773 + endloop + endfacet + facet normal 0.245783 -0.939506 0.238577 + outer loop + vertex 642.451 113.124 317.958 + vertex 639.644 112.266 317.469 + vertex 644.084 113.535 317.891 + endloop + endfacet + facet normal 0.243897 -0.921602 0.301935 + outer loop + vertex 643.93 113.599 318.211 + vertex 642.451 113.124 317.958 + vertex 644.084 113.535 317.891 + endloop + endfacet + facet normal 0.255363 -0.916967 0.306531 + outer loop + vertex 646.856 114.57 318.678 + vertex 643.93 113.599 318.211 + vertex 644.084 113.535 317.891 + endloop + endfacet + facet normal 0.234313 -0.893688 0.382648 + outer loop + vertex 649.822 115.528 319.101 + vertex 646.856 114.57 318.678 + vertex 649.615 115.33 318.765 + endloop + endfacet + facet normal 0.243569 -0.893652 0.376908 + outer loop + vertex 651.76 116.118 319.246 + vertex 649.822 115.528 319.101 + vertex 649.615 115.33 318.765 + endloop + endfacet + facet normal 0.356577 -0.88593 -0.296617 + outer loop + vertex 647.303 115.927 297.208 + vertex 649.509 116.904 296.94 + vertex 647.978 116.13 297.411 + endloop + endfacet + facet normal 0.348271 -0.902916 -0.251893 + outer loop + vertex 645.495 115.141 297.521 + vertex 647.303 115.927 297.208 + vertex 647.978 116.13 297.411 + endloop + endfacet + facet normal 0.351189 -0.916985 -0.18922 + outer loop + vertex 643.087 114.146 297.878 + vertex 645.495 115.141 297.521 + vertex 643.012 114.052 298.194 + endloop + endfacet + facet normal 0.344397 -0.919096 -0.191448 + outer loop + vertex 641.13 113.335 298.248 + vertex 643.087 114.146 297.878 + vertex 643.012 114.052 298.194 + endloop + endfacet + facet normal 0.355276 -0.934545 -0.0201091 + outer loop + vertex 638.494 112.323 298.725 + vertex 641.13 113.335 298.248 + vertex 643.012 114.052 298.194 + endloop + endfacet + facet normal 0.327349 -0.93303 -0.149321 + outer loop + vertex 635.79 111.295 299.221 + vertex 638.494 112.323 298.725 + vertex 637.449 111.874 299.239 + endloop + endfacet + facet normal 0.329645 -0.942548 -0.054203 + outer loop + vertex 633.8 110.572 299.695 + vertex 635.79 111.295 299.221 + vertex 637.449 111.874 299.239 + endloop + endfacet + facet normal 0.302478 -0.945969 -0.116832 + outer loop + vertex 630.648 109.473 300.427 + vertex 633.8 110.572 299.695 + vertex 631.973 109.896 300.439 + endloop + endfacet + facet normal 0.246799 -0.887419 0.38933 + outer loop + vertex 657.28 116.42 316.512 + vertex 657.153 116.999 317.911 + vertex 655.733 116.335 317.3 + endloop + endfacet + facet normal 0.246223 -0.921565 0.300153 + outer loop + vertex 658.632 116.314 315.078 + vertex 657.28 116.42 316.512 + vertex 657.019 116.141 315.868 + endloop + endfacet + facet normal 0.272959 -0.932314 0.237242 + outer loop + vertex 660.512 116.489 313.603 + vertex 658.632 116.314 315.078 + vertex 658.773 116.174 314.366 + endloop + endfacet + facet normal 0.292876 -0.942536 0.160776 + outer loop + vertex 662.147 116.804 312.468 + vertex 660.512 116.489 313.603 + vertex 660.689 116.442 313.003 + endloop + endfacet + facet normal 0.322467 -0.945084 0.05321 + outer loop + vertex 663.748 117.3 311.586 + vertex 662.147 116.804 312.468 + vertex 662.523 116.9 311.901 + endloop + endfacet + facet normal 0.371641 -0.927702 0.035384 + outer loop + vertex 666.065 118.181 310.343 + vertex 663.748 117.3 311.586 + vertex 664.324 117.508 310.987 + endloop + endfacet + facet normal 0.315068 -0.949069 0.000266039 + outer loop + vertex 631.973 109.896 300.439 + vertex 626.591 108.109 301.837 + vertex 627.698 108.476 301.263 + endloop + endfacet + facet normal 0.330959 -0.942623 -0.0439034 + outer loop + vertex 637.449 111.874 299.239 + vertex 631.973 109.896 300.439 + vertex 633.8 110.572 299.695 + endloop + endfacet + facet normal 0.342971 -0.932066 -0.116719 + outer loop + vertex 643.012 114.052 298.194 + vertex 637.449 111.874 299.239 + vertex 638.494 112.323 298.725 + endloop + endfacet + facet normal 0.358451 -0.918792 -0.165331 + outer loop + vertex 647.978 116.13 297.411 + vertex 643.012 114.052 298.194 + vertex 645.495 115.141 297.521 + endloop + endfacet + facet normal 0.337293 -0.876416 -0.343697 + outer loop + vertex 651.115 117.487 297.029 + vertex 647.978 116.13 297.411 + vertex 649.509 116.904 296.94 + endloop + endfacet + facet normal 0.230006 -0.956107 0.181541 + outer loop + vertex 626.832 108.288 313.853 + vertex 632.589 109.984 315.488 + vertex 628.142 108.767 314.714 + endloop + endfacet + facet normal 0.237733 -0.947499 0.213842 + outer loop + vertex 632.589 109.984 315.488 + vertex 638.273 111.7 316.773 + vertex 634.425 110.639 316.35 + endloop + endfacet + facet normal 0.238092 -0.928264 0.285723 + outer loop + vertex 638.273 111.7 316.773 + vertex 644.084 113.535 317.891 + vertex 639.644 112.266 317.469 + endloop + endfacet + facet normal 0.238615 -0.90563 0.350567 + outer loop + vertex 644.084 113.535 317.891 + vertex 649.615 115.33 318.765 + vertex 646.856 114.57 318.678 + endloop + endfacet + facet normal 0.239416 -0.889642 0.388867 + outer loop + vertex 649.615 115.33 318.765 + vertex 652.993 116.424 319.187 + vertex 651.76 116.118 319.246 + endloop + endfacet + facet normal 0.211403 -0.924984 0.315774 + outer loop + vertex 655.733 116.335 317.3 + vertex 657.019 116.141 315.868 + vertex 657.28 116.42 316.512 + endloop + endfacet + facet normal 0.214403 -0.949504 0.229069 + outer loop + vertex 657.019 116.141 315.868 + vertex 658.773 116.174 314.366 + vertex 658.632 116.314 315.078 + endloop + endfacet + facet normal 0.237978 -0.960239 0.14597 + outer loop + vertex 658.773 116.174 314.366 + vertex 660.689 116.442 313.003 + vertex 660.512 116.489 313.603 + endloop + endfacet + facet normal 0.238395 -0.971144 -0.00690512 + outer loop + vertex 660.689 116.442 313.003 + vertex 662.523 116.9 311.901 + vertex 662.147 116.804 312.468 + endloop + endfacet + facet normal 0.300651 -0.952828 -0.0415541 + outer loop + vertex 662.523 116.9 311.901 + vertex 664.324 117.508 310.987 + vertex 663.748 117.3 311.586 + endloop + endfacet + facet normal 0.306005 -0.730796 0.610162 + outer loop + vertex 655.799 109.037 26.6548 + vertex 658.745 111.283 27.8673 + vertex 652.948 108.372 27.2884 + endloop + endfacet + facet normal 0.301754 -0.71662 0.628808 + outer loop + vertex 656.902 109.102 26.1994 + vertex 658.806 110.697 27.1043 + vertex 655.799 109.037 26.6548 + endloop + endfacet + facet normal 0.319666 -0.739282 0.592685 + outer loop + vertex 655.799 109.037 26.6548 + vertex 658.806 110.697 27.1043 + vertex 658.745 111.283 27.8673 + endloop + endfacet + facet normal 0.386323 -0.880866 0.27355 + outer loop + vertex 639.29 110.276 41.8652 + vertex 636.322 108.778 41.2342 + vertex 639.974 110.456 41.4797 + endloop + endfacet + facet normal 0.39736 -0.869204 0.29426 + outer loop + vertex 648.386 114.745 42.861 + vertex 644.546 112.867 42.4984 + vertex 642.867 111.599 41.0209 + endloop + endfacet + facet normal 0.382474 -0.853645 0.353559 + outer loop + vertex 650.709 116.178 43.8078 + vertex 648.386 114.745 42.861 + vertex 651.641 116.347 43.2091 + endloop + endfacet + facet normal 0.32948 -0.861958 0.38532 + outer loop + vertex 660.139 115.954 34.4713 + vertex 657.903 116.058 36.6162 + vertex 658.28 115.668 35.421 + endloop + endfacet + facet normal 0.330821 -0.84864 0.412755 + outer loop + vertex 662.478 115.959 32.6075 + vertex 660.139 115.954 34.4713 + vertex 660.324 115.552 33.4965 + endloop + endfacet + facet normal 0.324632 -0.840975 0.432869 + outer loop + vertex 664.875 116.122 31.1266 + vertex 662.478 115.959 32.6075 + vertex 662.885 115.727 31.8501 + endloop + endfacet + facet normal 0.309744 -0.750523 0.583758 + outer loop + vertex 660.994 112.052 27.6136 + vertex 664.073 114.405 29.0056 + vertex 661.212 112.489 28.0597 + endloop + endfacet + facet normal 0.307414 -0.727279 0.613646 + outer loop + vertex 658.755 110.243 26.591 + vertex 660.994 112.052 27.6136 + vertex 658.806 110.697 27.1043 + endloop + endfacet + facet normal 0.317529 -0.725272 0.610865 + outer loop + vertex 658.806 110.697 27.1043 + vertex 656.902 109.102 26.1994 + vertex 658.755 110.243 26.591 + endloop + endfacet + facet normal 0.388726 -0.884045 0.259532 + outer loop + vertex 632.531 106.734 39.949 + vertex 639.974 110.456 41.4797 + vertex 636.322 108.778 41.2342 + endloop + endfacet + facet normal 0.33093 -0.749915 0.572812 + outer loop + vertex 661.212 112.489 28.0597 + vertex 658.806 110.697 27.1043 + vertex 660.994 112.052 27.6136 + endloop + endfacet + facet normal 0.379125 -0.861964 0.336574 + outer loop + vertex 648.386 114.745 42.861 + vertex 642.867 111.599 41.0209 + vertex 650.3 115.352 42.2612 + endloop + endfacet + facet normal -0.151657 -0.642342 -0.751264 + outer loop + vertex 343.596 62.2235 299.001 + vertex 345.903 62.3291 298.446 + vertex 346.448 60.2995 300.071 + endloop + endfacet + facet normal -0.120823 -0.640062 -0.758764 + outer loop + vertex 346.448 60.2995 300.071 + vertex 345.903 62.3291 298.446 + vertex 348.922 60.5188 299.492 + endloop + endfacet + facet normal -0.105219 -0.6938 -0.71244 + outer loop + vertex 346.448 60.2995 300.071 + vertex 348.922 60.5188 299.492 + vertex 349.943 58.3539 301.449 + endloop + endfacet + facet normal -0.0918823 -0.691335 -0.716668 + outer loop + vertex 349.943 58.3539 301.449 + vertex 348.922 60.5188 299.492 + vertex 352.061 59.1922 300.369 + endloop + endfacet + facet normal -0.251219 -0.522204 -0.814979 + outer loop + vertex 338.689 66.8904 297.187 + vertex 340.859 66.729 296.621 + vertex 341.036 64.399 298.06 + endloop + endfacet + facet normal -0.214881 -0.524803 -0.823655 + outer loop + vertex 341.036 64.399 298.06 + vertex 340.859 66.729 296.621 + vertex 343.262 64.3786 297.492 + endloop + endfacet + facet normal -0.205873 -0.5826 -0.786253 + outer loop + vertex 341.036 64.399 298.06 + vertex 343.262 64.3786 297.492 + vertex 343.596 62.2235 299.001 + endloop + endfacet + facet normal -0.165072 -0.582846 -0.795639 + outer loop + vertex 343.596 62.2235 299.001 + vertex 343.262 64.3786 297.492 + vertex 345.903 62.3291 298.446 + endloop + endfacet + facet normal -0.328496 -0.41352 -0.849171 + outer loop + vertex 334.682 72.4943 295.72 + vertex 336.539 72.2841 295.104 + vertex 336.581 69.5842 296.402 + endloop + endfacet + facet normal -0.289319 -0.418543 -0.860881 + outer loop + vertex 336.581 69.5842 296.402 + vertex 336.539 72.2841 295.104 + vertex 338.609 69.3702 295.825 + endloop + endfacet + facet normal -0.287355 -0.468226 -0.835579 + outer loop + vertex 336.581 69.5842 296.402 + vertex 338.609 69.3702 295.825 + vertex 338.689 66.8904 297.187 + endloop + endfacet + facet normal -0.255035 -0.471816 -0.844007 + outer loop + vertex 338.689 66.8904 297.187 + vertex 338.609 69.3702 295.825 + vertex 340.859 66.729 296.621 + endloop + endfacet + facet normal -0.443133 -0.290401 -0.848116 + outer loop + vertex 331.19 79.9172 294.636 + vertex 332.957 79.212 293.954 + vertex 332.889 75.8263 295.148 + endloop + endfacet + facet normal -0.382914 -0.300573 -0.873518 + outer loop + vertex 332.889 75.8263 295.148 + vertex 332.957 79.212 293.954 + vertex 334.664 75.5245 294.474 + endloop + endfacet + facet normal -0.384096 -0.352944 -0.853171 + outer loop + vertex 332.889 75.8263 295.148 + vertex 334.664 75.5245 294.474 + vertex 334.682 72.4943 295.72 + endloop + endfacet + facet normal -0.330188 -0.360506 -0.87236 + outer loop + vertex 334.682 72.4943 295.72 + vertex 334.664 75.5245 294.474 + vertex 336.539 72.2841 295.104 + endloop + endfacet + facet normal -0.468302 -0.187665 -0.863409 + outer loop + vertex 328.616 87.424 294.174 + vertex 330.038 87.1117 293.471 + vertex 330.052 83.7792 294.188 + endloop + endfacet + facet normal -0.454404 -0.189131 -0.870487 + outer loop + vertex 330.052 83.7792 294.188 + vertex 330.038 87.1117 293.471 + vertex 331.434 83.2906 293.572 + endloop + endfacet + facet normal -0.463571 -0.235645 -0.854151 + outer loop + vertex 330.052 83.7792 294.188 + vertex 331.434 83.2906 293.572 + vertex 331.19 79.9172 294.636 + endloop + endfacet + facet normal -0.431962 -0.242516 -0.868674 + outer loop + vertex 331.19 79.9172 294.636 + vertex 331.434 83.2906 293.572 + vertex 332.957 79.212 293.954 + endloop + endfacet + facet normal 0.000967117 -0.818399 -0.574649 + outer loop + vertex 360.994 55.5106 304.059 + vertex 366.644 56.6105 302.502 + vertex 366.596 54.1102 306.063 + endloop + endfacet + facet normal 0.0194176 -0.818363 -0.574374 + outer loop + vertex 366.596 54.1102 306.063 + vertex 366.644 56.6105 302.502 + vertex 372.738 55.2474 304.65 + endloop + endfacet + facet normal -0.0343618 -0.782902 -0.621196 + outer loop + vertex 355.169 57.251 302.188 + vertex 360.047 58.3842 300.49 + vertex 360.994 55.5106 304.059 + endloop + endfacet + facet normal -0.0197928 -0.781335 -0.623798 + outer loop + vertex 360.994 55.5106 304.059 + vertex 360.047 58.3842 300.49 + vertex 366.644 56.6105 302.502 + endloop + endfacet + facet normal -0.0744219 -0.74265 -0.665532 + outer loop + vertex 352.061 59.1922 300.369 + vertex 354.825 59.5557 299.654 + vertex 355.169 57.251 302.188 + endloop + endfacet + facet normal -0.0701888 -0.767341 -0.637387 + outer loop + vertex 356.747 60.4638 298.349 + vertex 360.047 58.3842 300.49 + vertex 354.825 59.5557 299.654 + endloop + endfacet + facet normal -0.0598121 -0.742397 -0.667285 + outer loop + vertex 360.047 58.3842 300.49 + vertex 355.169 57.251 302.188 + vertex 354.825 59.5557 299.654 + endloop + endfacet + facet normal -0.152548 -0.68912 -0.708409 + outer loop + vertex 348.142 62.8155 297.55 + vertex 350.333 63.4428 296.469 + vertex 351.235 61.0998 298.553 + endloop + endfacet + facet normal -0.142137 -0.688 -0.711656 + outer loop + vertex 351.235 61.0998 298.553 + vertex 350.333 63.4428 296.469 + vertex 353.505 61.7461 297.475 + endloop + endfacet + facet normal -0.146937 -0.667156 -0.730282 + outer loop + vertex 345.903 62.3291 298.446 + vertex 348.142 62.8155 297.55 + vertex 348.922 60.5188 299.492 + endloop + endfacet + facet normal -0.130903 -0.665533 -0.734799 + outer loop + vertex 348.922 60.5188 299.492 + vertex 348.142 62.8155 297.55 + vertex 351.235 61.0998 298.553 + endloop + endfacet + facet normal -0.104772 -0.709052 -0.697329 + outer loop + vertex 348.922 60.5188 299.492 + vertex 351.235 61.0998 298.553 + vertex 352.061 59.1922 300.369 + endloop + endfacet + facet normal -0.0886178 -0.706569 -0.702074 + outer loop + vertex 352.061 59.1922 300.369 + vertex 351.235 61.0998 298.553 + vertex 354.825 59.5557 299.654 + endloop + endfacet + facet normal -0.109785 -0.733476 -0.670791 + outer loop + vertex 351.235 61.0998 298.553 + vertex 353.505 61.7461 297.475 + vertex 354.825 59.5557 299.654 + endloop + endfacet + facet normal -0.109119 -0.733335 -0.671053 + outer loop + vertex 354.825 59.5557 299.654 + vertex 353.505 61.7461 297.475 + vertex 356.747 60.4638 298.349 + endloop + endfacet + facet normal -0.257434 -0.574688 -0.776828 + outer loop + vertex 342.93 67.1062 295.723 + vertex 344.923 67.6827 294.636 + vertex 345.412 64.8138 296.596 + endloop + endfacet + facet normal -0.239156 -0.575259 -0.782228 + outer loop + vertex 345.412 64.8138 296.596 + vertex 344.923 67.6827 294.636 + vertex 347.506 65.4154 295.513 + endloop + endfacet + facet normal -0.246819 -0.548324 -0.799013 + outer loop + vertex 340.859 66.729 296.621 + vertex 342.93 67.1062 295.723 + vertex 343.262 64.3786 297.492 + endloop + endfacet + facet normal -0.224201 -0.549406 -0.804914 + outer loop + vertex 343.262 64.3786 297.492 + vertex 342.93 67.1062 295.723 + vertex 345.412 64.8138 296.596 + endloop + endfacet + facet normal -0.196364 -0.610121 -0.767589 + outer loop + vertex 343.262 64.3786 297.492 + vertex 345.412 64.8138 296.596 + vertex 345.903 62.3291 298.446 + endloop + endfacet + facet normal -0.176288 -0.609904 -0.772618 + outer loop + vertex 345.903 62.3291 298.446 + vertex 345.412 64.8138 296.596 + vertex 348.142 62.8155 297.55 + endloop + endfacet + facet normal -0.203431 -0.634226 -0.745904 + outer loop + vertex 345.412 64.8138 296.596 + vertex 347.506 65.4154 295.513 + vertex 348.142 62.8155 297.55 + endloop + endfacet + facet normal -0.188915 -0.633883 -0.750002 + outer loop + vertex 348.142 62.8155 297.55 + vertex 347.506 65.4154 295.513 + vertex 350.333 63.4428 296.469 + endloop + endfacet + facet normal -0.345934 -0.464264 -0.815346 + outer loop + vertex 338.395 72.6175 294.203 + vertex 340.188 73.189 293.117 + vertex 340.589 69.7137 294.926 + endloop + endfacet + facet normal -0.331581 -0.465374 -0.820659 + outer loop + vertex 340.589 69.7137 294.926 + vertex 340.188 73.189 293.117 + vertex 342.483 70.2829 293.838 + endloop + endfacet + facet normal -0.327017 -0.439341 -0.836683 + outer loop + vertex 336.539 72.2841 295.104 + vertex 338.395 72.6175 294.203 + vertex 338.609 69.3702 295.825 + endloop + endfacet + facet normal -0.30634 -0.441347 -0.843427 + outer loop + vertex 338.609 69.3702 295.825 + vertex 338.395 72.6175 294.203 + vertex 340.589 69.7137 294.926 + endloop + endfacet + facet normal -0.28745 -0.492606 -0.821408 + outer loop + vertex 338.609 69.3702 295.825 + vertex 340.589 69.7137 294.926 + vertex 340.859 66.729 296.621 + endloop + endfacet + facet normal -0.268791 -0.494016 -0.826861 + outer loop + vertex 340.859 66.729 296.621 + vertex 340.589 69.7137 294.926 + vertex 342.93 67.1062 295.723 + endloop + endfacet + facet normal -0.304023 -0.51742 -0.799904 + outer loop + vertex 340.589 69.7137 294.926 + vertex 342.483 70.2829 293.838 + vertex 342.93 67.1062 295.723 + endloop + endfacet + facet normal -0.289056 -0.51827 -0.804886 + outer loop + vertex 342.93 67.1062 295.723 + vertex 342.483 70.2829 293.838 + vertex 344.923 67.6827 294.636 + endloop + endfacet + facet normal -0.442128 -0.344477 -0.828166 + outer loop + vertex 334.599 79.3391 293.059 + vertex 336.22 79.8642 291.976 + vertex 336.399 75.7978 293.571 + endloop + endfacet + facet normal -0.417388 -0.34784 -0.83952 + outer loop + vertex 336.399 75.7978 293.571 + vertex 336.22 79.8642 291.976 + vertex 338.097 76.3854 292.484 + endloop + endfacet + facet normal -0.43399 -0.319792 -0.84225 + outer loop + vertex 332.957 79.212 293.954 + vertex 334.599 79.3391 293.059 + vertex 334.664 75.5245 294.474 + endloop + endfacet + facet normal -0.395676 -0.325304 -0.858847 + outer loop + vertex 334.664 75.5245 294.474 + vertex 334.599 79.3391 293.059 + vertex 336.399 75.7978 293.571 + endloop + endfacet + facet normal -0.378336 -0.382644 -0.842879 + outer loop + vertex 334.664 75.5245 294.474 + vertex 336.399 75.7978 293.571 + vertex 336.539 72.2841 295.104 + endloop + endfacet + facet normal -0.345408 -0.386663 -0.855094 + outer loop + vertex 336.539 72.2841 295.104 + vertex 336.399 75.7978 293.571 + vertex 338.395 72.6175 294.203 + endloop + endfacet + facet normal -0.388229 -0.40784 -0.826405 + outer loop + vertex 336.399 75.7978 293.571 + vertex 338.097 76.3854 292.484 + vertex 338.395 72.6175 294.203 + endloop + endfacet + facet normal -0.373706 -0.409388 -0.832313 + outer loop + vertex 338.395 72.6175 294.203 + vertex 338.097 76.3854 292.484 + vertex 340.188 73.189 293.117 + endloop + endfacet + facet normal -0.478807 -0.257268 -0.839379 + outer loop + vertex 331.434 83.2906 293.572 + vertex 332.961 83.2927 292.7 + vertex 332.957 79.212 293.954 + endloop + endfacet + facet normal -0.445821 -0.262348 -0.855814 + outer loop + vertex 332.957 79.212 293.954 + vertex 332.961 83.2927 292.7 + vertex 334.599 79.3391 293.059 + endloop + endfacet + facet normal -0.493219 -0.279092 -0.823919 + outer loop + vertex 332.961 83.2927 292.7 + vertex 334.51 83.669 291.646 + vertex 334.599 79.3391 293.059 + endloop + endfacet + facet normal -0.468101 -0.2829 -0.837167 + outer loop + vertex 334.599 79.3391 293.059 + vertex 334.51 83.669 291.646 + vertex 336.22 79.8642 291.976 + endloop + endfacet + facet normal -0.533333 -0.18049 -0.826426 + outer loop + vertex 333.04 87.4705 291.519 + vertex 331.363 88.0972 292.464 + vertex 332.237 94.4082 290.522 + endloop + endfacet + facet normal -0.517816 -0.161754 -0.840061 + outer loop + vertex 330.038 87.1117 293.471 + vertex 328.62 94.0852 293.002 + vertex 331.363 88.0972 292.464 + endloop + endfacet + facet normal -0.545864 -0.176492 -0.819074 + outer loop + vertex 328.62 94.0852 293.002 + vertex 332.237 94.4082 290.522 + vertex 331.363 88.0972 292.464 + endloop + endfacet + facet normal -0.562916 -0.12316 -0.817286 + outer loop + vertex 326.59 104.019 292.903 + vertex 329.907 103.446 290.705 + vertex 328.62 94.0852 293.002 + endloop + endfacet + facet normal -0.553329 -0.125974 -0.823382 + outer loop + vertex 328.62 94.0852 293.002 + vertex 329.907 103.446 290.705 + vertex 332.237 94.4082 290.522 + endloop + endfacet + facet normal -0.574269 -0.0953011 -0.8131 + outer loop + vertex 324.943 112.608 293.06 + vertex 328.158 112.365 290.818 + vertex 326.59 104.019 292.903 + endloop + endfacet + facet normal -0.56159 -0.0997522 -0.821381 + outer loop + vertex 326.59 104.019 292.903 + vertex 328.158 112.365 290.818 + vertex 329.907 103.446 290.705 + endloop + endfacet + facet normal -0.582646 -0.0854103 -0.808226 + outer loop + vertex 323.901 121.175 292.906 + vertex 326.802 120.805 290.854 + vertex 324.943 112.608 293.06 + endloop + endfacet + facet normal -0.574284 -0.0888136 -0.813824 + outer loop + vertex 324.943 112.608 293.06 + vertex 326.802 120.805 290.854 + vertex 328.158 112.365 290.818 + endloop + endfacet + facet normal -0.584611 -0.0863663 -0.806703 + outer loop + vertex 322.761 129.232 292.869 + vertex 325.613 129.005 290.827 + vertex 323.901 121.175 292.906 + endloop + endfacet + facet normal -0.582705 -0.0871274 -0.808 + outer loop + vertex 323.901 121.175 292.906 + vertex 325.613 129.005 290.827 + vertex 326.802 120.805 290.854 + endloop + endfacet + facet normal -0.588101 -0.0861473 -0.804186 + outer loop + vertex 321.596 137.205 292.867 + vertex 324.413 137.104 290.818 + vertex 322.761 129.232 292.869 + endloop + endfacet + facet normal -0.584613 -0.0875031 -0.80658 + outer loop + vertex 322.761 129.232 292.869 + vertex 324.413 137.104 290.818 + vertex 325.613 129.005 290.827 + endloop + endfacet + facet normal -0.587909 -0.0872909 -0.804203 + outer loop + vertex 320.346 145.363 292.895 + vertex 323.173 145.301 290.836 + vertex 321.596 137.205 292.867 + endloop + endfacet + facet normal -0.588072 -0.0872312 -0.804091 + outer loop + vertex 321.596 137.205 292.867 + vertex 323.173 145.301 290.836 + vertex 324.413 137.104 290.818 + endloop + endfacet + facet normal -0.579927 -0.0895606 -0.809731 + outer loop + vertex 318.755 153.908 293.09 + vertex 321.837 153.747 290.9 + vertex 320.346 145.363 292.895 + endloop + endfacet + facet normal -0.587926 -0.0868318 -0.804241 + outer loop + vertex 320.346 145.363 292.895 + vertex 321.837 153.747 290.9 + vertex 323.173 145.301 290.836 + endloop + endfacet + facet normal -0.574669 -0.077733 -0.814686 + outer loop + vertex 317.541 162.536 293.123 + vertex 320.537 162.378 291.024 + vertex 318.755 153.908 293.09 + endloop + endfacet + facet normal -0.580112 -0.075692 -0.811012 + outer loop + vertex 318.755 153.908 293.09 + vertex 320.537 162.378 291.024 + vertex 321.837 153.747 290.9 + endloop + endfacet + facet normal -0.615125 -0.00534262 -0.788412 + outer loop + vertex 317.217 169.899 293.326 + vertex 319.753 170.723 291.342 + vertex 317.541 162.536 293.123 + endloop + endfacet + facet normal -0.574315 -0.0228692 -0.818315 + outer loop + vertex 317.541 162.536 293.123 + vertex 319.753 170.723 291.342 + vertex 320.537 162.378 291.024 + endloop + endfacet + facet normal -0.00167159 -0.846491 -0.5324 + outer loop + vertex 366.644 56.6105 302.502 + vertex 372.311 57.9578 300.342 + vertex 372.738 55.2474 304.65 + endloop + endfacet + facet normal 0.0140174 -0.845708 -0.533462 + outer loop + vertex 372.738 55.2474 304.65 + vertex 372.311 57.9578 300.342 + vertex 378.986 56.6844 302.536 + endloop + endfacet + facet normal -0.0434961 -0.815898 -0.576558 + outer loop + vertex 360.047 58.3842 300.49 + vertex 365.153 59.6681 298.288 + vertex 366.644 56.6105 302.502 + endloop + endfacet + facet normal -0.0278075 -0.81375 -0.580549 + outer loop + vertex 366.644 56.6105 302.502 + vertex 365.153 59.6681 298.288 + vertex 372.311 57.9578 300.342 + endloop + endfacet + facet normal -0.0902736 -0.780234 -0.61894 + outer loop + vertex 356.747 60.4638 298.349 + vertex 359.579 60.8197 297.488 + vertex 360.047 58.3842 300.49 + endloop + endfacet + facet normal -0.0817808 -0.80447 -0.588337 + outer loop + vertex 361.521 61.7326 295.969 + vertex 365.153 59.6681 298.288 + vertex 359.579 60.8197 297.488 + endloop + endfacet + facet normal -0.0719526 -0.78001 -0.621616 + outer loop + vertex 365.153 59.6681 298.288 + vertex 360.047 58.3842 300.49 + vertex 359.579 60.8197 297.488 + endloop + endfacet + facet normal -0.173412 -0.734488 -0.656092 + outer loop + vertex 352.488 64.0524 295.315 + vertex 354.629 64.6329 294.099 + vertex 355.775 62.3682 296.332 + endloop + endfacet + facet normal -0.161 -0.732975 -0.660928 + outer loop + vertex 355.775 62.3682 296.332 + vertex 354.629 64.6329 294.099 + vertex 358.041 62.9727 295.109 + endloop + endfacet + facet normal -0.164132 -0.71198 -0.682749 + outer loop + vertex 350.333 63.4428 296.469 + vertex 352.488 64.0524 295.315 + vertex 353.505 61.7461 297.475 + endloop + endfacet + facet normal -0.151531 -0.710542 -0.687145 + outer loop + vertex 353.505 61.7461 297.475 + vertex 352.488 64.0524 295.315 + vertex 355.775 62.3682 296.332 + endloop + endfacet + facet normal -0.121676 -0.75046 -0.649618 + outer loop + vertex 353.505 61.7461 297.475 + vertex 355.775 62.3682 296.332 + vertex 356.747 60.4638 298.349 + endloop + endfacet + facet normal -0.105353 -0.74806 -0.655215 + outer loop + vertex 356.747 60.4638 298.349 + vertex 355.775 62.3682 296.332 + vertex 359.579 60.8197 297.488 + endloop + endfacet + facet normal -0.127258 -0.774921 -0.619114 + outer loop + vertex 355.775 62.3682 296.332 + vertex 358.041 62.9727 295.109 + vertex 359.579 60.8197 297.488 + endloop + endfacet + facet normal -0.122092 -0.773853 -0.621487 + outer loop + vertex 359.579 60.8197 297.488 + vertex 358.041 62.9727 295.109 + vertex 361.521 61.7326 295.969 + endloop + endfacet + facet normal -0.288053 -0.628028 -0.722915 + outer loop + vertex 346.852 68.2657 293.468 + vertex 348.752 68.7999 292.247 + vertex 349.549 66.0107 294.352 + endloop + endfacet + facet normal -0.268324 -0.628065 -0.730436 + outer loop + vertex 349.549 66.0107 294.352 + vertex 348.752 68.7999 292.247 + vertex 351.564 66.5641 293.136 + endloop + endfacet + facet normal -0.272836 -0.601482 -0.750853 + outer loop + vertex 344.923 67.6827 294.636 + vertex 346.852 68.2657 293.468 + vertex 347.506 65.4154 295.513 + endloop + endfacet + facet normal -0.25491 -0.601731 -0.756929 + outer loop + vertex 347.506 65.4154 295.513 + vertex 346.852 68.2657 293.468 + vertex 349.549 66.0107 294.352 + endloop + endfacet + facet normal -0.21697 -0.659443 -0.719763 + outer loop + vertex 347.506 65.4154 295.513 + vertex 349.549 66.0107 294.352 + vertex 350.333 63.4428 296.469 + endloop + endfacet + facet normal -0.201625 -0.658863 -0.72474 + outer loop + vertex 350.333 63.4428 296.469 + vertex 349.549 66.0107 294.352 + vertex 352.488 64.0524 295.315 + endloop + endfacet + facet normal -0.229525 -0.684578 -0.691861 + outer loop + vertex 349.549 66.0107 294.352 + vertex 351.564 66.5641 293.136 + vertex 352.488 64.0524 295.315 + endloop + endfacet + facet normal -0.211306 -0.683664 -0.698536 + outer loop + vertex 352.488 64.0524 295.315 + vertex 351.564 66.5641 293.136 + vertex 354.629 64.6329 294.099 + endloop + endfacet + facet normal -0.394723 -0.511739 -0.763097 + outer loop + vertex 341.909 73.7833 291.945 + vertex 343.6 74.3047 290.721 + vertex 344.303 70.8613 292.666 + endloop + endfacet + facet normal -0.377467 -0.51274 -0.771114 + outer loop + vertex 344.303 70.8613 292.666 + vertex 343.6 74.3047 290.721 + vertex 346.094 71.3844 291.442 + endloop + endfacet + facet normal -0.369783 -0.48809 -0.790588 + outer loop + vertex 340.188 73.189 293.117 + vertex 341.909 73.7833 291.945 + vertex 342.483 70.2829 293.838 + endloop + endfacet + facet normal -0.356945 -0.488896 -0.795972 + outer loop + vertex 342.483 70.2829 293.838 + vertex 341.909 73.7833 291.945 + vertex 344.303 70.8613 292.666 + endloop + endfacet + facet normal -0.325587 -0.543067 -0.773997 + outer loop + vertex 342.483 70.2829 293.838 + vertex 344.303 70.8613 292.666 + vertex 344.923 67.6827 294.636 + endloop + endfacet + facet normal -0.308272 -0.543764 -0.78057 + outer loop + vertex 344.923 67.6827 294.636 + vertex 344.303 70.8613 292.666 + vertex 346.852 68.2657 293.468 + endloop + endfacet + facet normal -0.344455 -0.568872 -0.746817 + outer loop + vertex 344.303 70.8613 292.666 + vertex 346.094 71.3844 291.442 + vertex 346.852 68.2657 293.468 + endloop + endfacet + facet normal -0.325127 -0.569473 -0.754978 + outer loop + vertex 346.852 68.2657 293.468 + vertex 346.094 71.3844 291.442 + vertex 348.752 68.7999 292.247 + endloop + endfacet + facet normal -0.490763 -0.38897 -0.77965 + outer loop + vertex 337.817 80.4518 290.788 + vertex 339.389 80.9528 289.548 + vertex 339.738 76.9837 291.309 + endloop + endfacet + facet normal -0.474071 -0.3915 -0.78866 + outer loop + vertex 339.738 76.9837 291.309 + vertex 339.389 80.9528 289.548 + vertex 341.346 77.5048 290.084 + endloop + endfacet + facet normal -0.463967 -0.368054 -0.805773 + outer loop + vertex 336.22 79.8642 291.976 + vertex 337.817 80.4518 290.788 + vertex 338.097 76.3854 292.484 + endloop + endfacet + facet normal -0.447799 -0.370307 -0.813848 + outer loop + vertex 338.097 76.3854 292.484 + vertex 337.817 80.4518 290.788 + vertex 339.738 76.9837 291.309 + endloop + endfacet + facet normal -0.416237 -0.430932 -0.800652 + outer loop + vertex 338.097 76.3854 292.484 + vertex 339.738 76.9837 291.309 + vertex 340.188 73.189 293.117 + endloop + endfacet + facet normal -0.40067 -0.432463 -0.807737 + outer loop + vertex 340.188 73.189 293.117 + vertex 339.738 76.9837 291.309 + vertex 341.909 73.7833 291.945 + endloop + endfacet + facet normal -0.442308 -0.453903 -0.773522 + outer loop + vertex 339.738 76.9837 291.309 + vertex 341.346 77.5048 290.084 + vertex 341.909 73.7833 291.945 + endloop + endfacet + facet normal -0.425641 -0.45555 -0.78186 + outer loop + vertex 341.909 73.7833 291.945 + vertex 341.346 77.5048 290.084 + vertex 343.6 74.3047 290.721 + endloop + endfacet + facet normal -0.512355 -0.299965 -0.804682 + outer loop + vertex 334.51 83.669 291.646 + vertex 336.067 84.2507 290.438 + vertex 336.22 79.8642 291.976 + endloop + endfacet + facet normal -0.494572 -0.302847 -0.814667 + outer loop + vertex 336.22 79.8642 291.976 + vertex 336.067 84.2507 290.438 + vertex 337.817 80.4518 290.788 + endloop + endfacet + facet normal -0.538189 -0.319729 -0.779824 + outer loop + vertex 336.067 84.2507 290.438 + vertex 337.663 84.6775 289.161 + vertex 337.817 80.4518 290.788 + endloop + endfacet + facet normal -0.520271 -0.323181 -0.790488 + outer loop + vertex 337.817 80.4518 290.788 + vertex 337.663 84.6775 289.161 + vertex 339.389 80.9528 289.548 + endloop + endfacet + facet normal -0.575183 -0.181205 -0.797702 + outer loop + vertex 333.04 87.4705 291.519 + vertex 332.237 94.4082 290.522 + vertex 334.356 88.574 290.319 + endloop + endfacet + facet normal -0.00551003 -0.872068 -0.489353 + outer loop + vertex 372.311 57.9578 300.342 + vertex 377.932 59.4501 297.619 + vertex 378.986 56.6844 302.536 + endloop + endfacet + facet normal 0.00810425 -0.870805 -0.491562 + outer loop + vertex 378.986 56.6844 302.536 + vertex 377.932 59.4501 297.619 + vertex 385.061 58.3023 299.77 + endloop + endfacet + facet normal -0.0501312 -0.846494 -0.530033 + outer loop + vertex 365.153 59.6681 298.288 + vertex 370.295 61.0529 295.59 + vertex 372.311 57.9578 300.342 + endloop + endfacet + facet normal -0.0349968 -0.844167 -0.534937 + outer loop + vertex 372.311 57.9578 300.342 + vertex 370.295 61.0529 295.59 + vertex 377.932 59.4501 297.619 + endloop + endfacet + facet normal -0.100951 -0.816259 -0.568798 + outer loop + vertex 361.521 61.7326 295.969 + vertex 364.418 62.1154 294.906 + vertex 365.153 59.6681 298.288 + endloop + endfacet + facet normal -0.0889402 -0.838172 -0.538105 + outer loop + vertex 366.31 63.0515 293.135 + vertex 370.295 61.0529 295.59 + vertex 364.418 62.1154 294.906 + endloop + endfacet + facet normal -0.0808457 -0.815717 -0.572774 + outer loop + vertex 370.295 61.0529 295.59 + vertex 365.153 59.6681 298.288 + vertex 364.418 62.1154 294.906 + endloop + endfacet + facet normal -0.186486 -0.776475 -0.601922 + outer loop + vertex 356.763 65.2095 292.79 + vertex 358.9 65.8039 291.361 + vertex 360.315 63.5884 293.78 + endloop + endfacet + facet normal -0.173503 -0.774778 -0.60796 + outer loop + vertex 360.315 63.5884 293.78 + vertex 358.9 65.8039 291.361 + vertex 362.583 64.2191 292.329 + endloop + endfacet + facet normal -0.181633 -0.755933 -0.628948 + outer loop + vertex 354.629 64.6329 294.099 + vertex 356.763 65.2095 292.79 + vertex 358.041 62.9727 295.109 + endloop + endfacet + facet normal -0.166969 -0.754062 -0.635226 + outer loop + vertex 358.041 62.9727 295.109 + vertex 356.763 65.2095 292.79 + vertex 360.315 63.5884 293.78 + endloop + endfacet + facet normal -0.134398 -0.791155 -0.596666 + outer loop + vertex 358.041 62.9727 295.109 + vertex 360.315 63.5884 293.78 + vertex 361.521 61.7326 295.969 + endloop + endfacet + facet normal -0.117446 -0.788484 -0.603737 + outer loop + vertex 361.521 61.7326 295.969 + vertex 360.315 63.5884 293.78 + vertex 364.418 62.1154 294.906 + endloop + endfacet + facet normal -0.136384 -0.81274 -0.566439 + outer loop + vertex 360.315 63.5884 293.78 + vertex 362.583 64.2191 292.329 + vertex 364.418 62.1154 294.906 + endloop + endfacet + facet normal -0.131211 -0.811642 -0.569228 + outer loop + vertex 364.418 62.1154 294.906 + vertex 362.583 64.2191 292.329 + vertex 366.31 63.0515 293.135 + endloop + endfacet + facet normal -0.305974 -0.673658 -0.67273 + outer loop + vertex 350.657 69.3241 290.944 + vertex 352.58 69.8649 289.528 + vertex 353.577 67.1089 291.834 + endloop + endfacet + facet normal -0.288589 -0.673717 -0.68031 + outer loop + vertex 353.577 67.1089 291.834 + vertex 352.58 69.8649 289.528 + vertex 355.599 67.6747 290.416 + endloop + endfacet + facet normal -0.297603 -0.651814 -0.697547 + outer loop + vertex 348.752 68.7999 292.247 + vertex 350.657 69.3241 290.944 + vertex 351.564 66.5641 293.136 + endloop + endfacet + facet normal -0.279549 -0.651793 -0.704996 + outer loop + vertex 351.564 66.5641 293.136 + vertex 350.657 69.3241 290.944 + vertex 353.577 67.1089 291.834 + endloop + endfacet + facet normal -0.237816 -0.708648 -0.664275 + outer loop + vertex 351.564 66.5641 293.136 + vertex 353.577 67.1089 291.834 + vertex 354.629 64.6329 294.099 + endloop + endfacet + facet normal -0.220595 -0.707678 -0.671215 + outer loop + vertex 354.629 64.6329 294.099 + vertex 353.577 67.1089 291.834 + vertex 356.763 65.2095 292.79 + endloop + endfacet + facet normal -0.243631 -0.729933 -0.638625 + outer loop + vertex 353.577 67.1089 291.834 + vertex 355.599 67.6747 290.416 + vertex 356.763 65.2095 292.79 + endloop + endfacet + facet normal -0.22856 -0.729084 -0.645133 + outer loop + vertex 356.763 65.2095 292.79 + vertex 355.599 67.6747 290.416 + vertex 358.9 65.8039 291.361 + endloop + endfacet + facet normal -0.423291 -0.554367 -0.716591 + outer loop + vertex 345.31 74.788 289.417 + vertex 347.063 75.2804 288.001 + vertex 347.898 71.8816 290.137 + endloop + endfacet + facet normal -0.404803 -0.555801 -0.726099 + outer loop + vertex 347.898 71.8816 290.137 + vertex 347.063 75.2804 288.001 + vertex 349.734 72.3968 288.719 + endloop + endfacet + facet normal -0.411861 -0.534033 -0.738363 + outer loop + vertex 343.6 74.3047 290.721 + vertex 345.31 74.788 289.417 + vertex 346.094 71.3844 291.442 + endloop + endfacet + facet normal -0.393177 -0.535236 -0.747619 + outer loop + vertex 346.094 71.3844 291.442 + vertex 345.31 74.788 289.417 + vertex 347.898 71.8816 290.137 + endloop + endfacet + facet normal -0.358172 -0.592939 -0.721204 + outer loop + vertex 346.094 71.3844 291.442 + vertex 347.898 71.8816 290.137 + vertex 348.752 68.7999 292.247 + endloop + endfacet + facet normal -0.336487 -0.593641 -0.731004 + outer loop + vertex 348.752 68.7999 292.247 + vertex 347.898 71.8816 290.137 + vertex 350.657 69.3241 290.944 + endloop + endfacet + facet normal -0.366325 -0.615387 -0.697929 + outer loop + vertex 347.898 71.8816 290.137 + vertex 349.734 72.3968 288.719 + vertex 350.657 69.3241 290.944 + endloop + endfacet + facet normal -0.347302 -0.616172 -0.706904 + outer loop + vertex 350.657 69.3241 290.944 + vertex 349.734 72.3968 288.719 + vertex 352.58 69.8649 289.528 + endloop + endfacet + facet normal -0.522935 -0.422631 -0.740217 + outer loop + vertex 340.963 81.4142 288.246 + vertex 342.568 81.8851 286.843 + vertex 342.974 77.9824 288.784 + endloop + endfacet + facet normal -0.50755 -0.425511 -0.749222 + outer loop + vertex 342.974 77.9824 288.784 + vertex 342.568 81.8851 286.843 + vertex 344.651 78.4647 287.374 + endloop + endfacet + facet normal -0.508779 -0.406559 -0.75885 + outer loop + vertex 339.389 80.9528 289.548 + vertex 340.963 81.4142 288.246 + vertex 341.346 77.5048 290.084 + endloop + endfacet + facet normal -0.492695 -0.409264 -0.767955 + outer loop + vertex 341.346 77.5048 290.084 + vertex 340.963 81.4142 288.246 + vertex 342.974 77.9824 288.784 + endloop + endfacet + facet normal -0.460177 -0.473708 -0.750891 + outer loop + vertex 341.346 77.5048 290.084 + vertex 342.974 77.9824 288.784 + vertex 343.6 74.3047 290.721 + endloop + endfacet + facet normal -0.444361 -0.475434 -0.75928 + outer loop + vertex 343.6 74.3047 290.721 + vertex 342.974 77.9824 288.784 + vertex 345.31 74.788 289.417 + endloop + endfacet + facet normal -0.47348 -0.491159 -0.73115 + outer loop + vertex 342.974 77.9824 288.784 + vertex 344.651 78.4647 287.374 + vertex 345.31 74.788 289.417 + endloop + endfacet + facet normal -0.458805 -0.493011 -0.739215 + outer loop + vertex 345.31 74.788 289.417 + vertex 344.651 78.4647 287.374 + vertex 347.063 75.2804 288.001 + endloop + endfacet + facet normal -0.556649 -0.336814 -0.759406 + outer loop + vertex 337.663 84.6775 289.161 + vertex 339.233 85.0722 287.836 + vertex 339.389 80.9528 289.548 + endloop + endfacet + facet normal -0.53803 -0.340892 -0.770919 + outer loop + vertex 339.389 80.9528 289.548 + vertex 339.233 85.0722 287.836 + vertex 340.963 81.4142 288.246 + endloop + endfacet + facet normal -0.566867 -0.351622 -0.744999 + outer loop + vertex 339.233 85.0722 287.836 + vertex 340.801 85.5193 286.431 + vertex 340.963 81.4142 288.246 + endloop + endfacet + facet normal -0.554114 -0.354696 -0.753092 + outer loop + vertex 340.963 81.4142 288.246 + vertex 340.801 85.5193 286.431 + vertex 342.568 81.8851 286.843 + endloop + endfacet + facet normal -0.0547843 -0.873533 -0.483673 + outer loop + vertex 370.295 61.0529 295.59 + vertex 375.237 62.4749 292.462 + vertex 377.932 59.4501 297.619 + endloop + endfacet + facet normal -0.0415991 -0.871187 -0.489186 + outer loop + vertex 377.932 59.4501 297.619 + vertex 375.237 62.4749 292.462 + vertex 383.259 60.9958 294.414 + endloop + endfacet + facet normal -0.10618 -0.848464 -0.518492 + outer loop + vertex 366.31 63.0515 293.135 + vertex 369.184 63.4664 291.868 + vertex 370.295 61.0529 295.59 + endloop + endfacet + facet normal -0.0934642 -0.865456 -0.49219 + outer loop + vertex 370.899 64.3929 289.913 + vertex 375.237 62.4749 292.462 + vertex 369.184 63.4664 291.868 + endloop + endfacet + facet normal -0.0874582 -0.847538 -0.523479 + outer loop + vertex 375.237 62.4749 292.462 + vertex 370.295 61.0529 295.59 + vertex 369.184 63.4664 291.868 + endloop + endfacet + facet normal -0.191109 -0.81004 -0.554358 + outer loop + vertex 361.033 66.4169 289.817 + vertex 363.131 67.0352 288.19 + vertex 364.838 64.8673 290.77 + endloop + endfacet + facet normal -0.181258 -0.808632 -0.559696 + outer loop + vertex 364.838 64.8673 290.77 + vertex 363.131 67.0352 288.19 + vertex 367.024 65.5088 289.135 + endloop + endfacet + facet normal -0.189798 -0.794027 -0.577493 + outer loop + vertex 358.9 65.8039 291.361 + vertex 361.033 66.4169 289.817 + vertex 362.583 64.2191 292.329 + endloop + endfacet + facet normal -0.17638 -0.792219 -0.584191 + outer loop + vertex 362.583 64.2191 292.329 + vertex 361.033 66.4169 289.817 + vertex 364.838 64.8673 290.77 + endloop + endfacet + facet normal -0.140565 -0.82569 -0.546331 + outer loop + vertex 362.583 64.2191 292.329 + vertex 364.838 64.8673 290.77 + vertex 366.31 63.0515 293.135 + endloop + endfacet + facet normal -0.125406 -0.823146 -0.553809 + outer loop + vertex 366.31 63.0515 293.135 + vertex 364.838 64.8673 290.77 + vertex 369.184 63.4664 291.868 + endloop + endfacet + facet normal -0.140659 -0.84315 -0.518953 + outer loop + vertex 364.838 64.8673 290.77 + vertex 367.024 65.5088 289.135 + vertex 369.184 63.4664 291.868 + endloop + endfacet + facet normal -0.138134 -0.842594 -0.520533 + outer loop + vertex 369.184 63.4664 291.868 + vertex 367.024 65.5088 289.135 + vertex 370.899 64.3929 289.913 + endloop + endfacet + facet normal -0.316334 -0.710925 -0.628107 + outer loop + vertex 354.512 70.4291 287.996 + vertex 356.424 71.0074 286.379 + vertex 357.624 68.2622 288.882 + endloop + endfacet + facet normal -0.302207 -0.710992 -0.63495 + outer loop + vertex 357.624 68.2622 288.882 + vertex 356.424 71.0074 286.379 + vertex 359.623 68.8595 287.261 + endloop + endfacet + facet normal -0.312157 -0.693593 -0.64922 + outer loop + vertex 352.58 69.8649 289.528 + vertex 354.512 70.4291 287.996 + vertex 355.599 67.6747 290.416 + endloop + endfacet + facet normal -0.296266 -0.693714 -0.656496 + outer loop + vertex 355.599 67.6747 290.416 + vertex 354.512 70.4291 287.996 + vertex 357.624 68.2622 288.882 + endloop + endfacet + facet normal -0.248471 -0.748754 -0.614516 + outer loop + vertex 355.599 67.6747 290.416 + vertex 357.624 68.2622 288.882 + vertex 358.9 65.8039 291.361 + endloop + endfacet + facet normal -0.234484 -0.747966 -0.620938 + outer loop + vertex 358.9 65.8039 291.361 + vertex 357.624 68.2622 288.882 + vertex 361.033 66.4169 289.817 + endloop + endfacet + facet normal -0.251627 -0.765243 -0.592525 + outer loop + vertex 357.624 68.2622 288.882 + vertex 359.623 68.8595 287.261 + vertex 361.033 66.4169 289.817 + endloop + endfacet + facet normal -0.238975 -0.764454 -0.59875 + outer loop + vertex 361.033 66.4169 289.817 + vertex 359.623 68.8595 287.261 + vertex 363.131 67.0352 288.19 + endloop + endfacet + facet normal -0.437753 -0.589763 -0.67864 + outer loop + vertex 348.843 75.8 286.471 + vertex 350.612 76.3404 284.86 + vertex 351.586 72.939 287.187 + endloop + endfacet + facet normal -0.423676 -0.591049 -0.686411 + outer loop + vertex 351.586 72.939 287.187 + vertex 350.612 76.3404 284.86 + vertex 353.423 73.4995 285.572 + endloop + endfacet + facet normal -0.431509 -0.573188 -0.696603 + outer loop + vertex 347.063 75.2804 288.001 + vertex 348.843 75.8 286.471 + vertex 349.734 72.3968 288.719 + endloop + endfacet + facet normal -0.415023 -0.574654 -0.705357 + outer loop + vertex 349.734 72.3968 288.719 + vertex 348.843 75.8 286.471 + vertex 351.586 72.939 287.187 + endloop + endfacet + facet normal -0.373092 -0.635338 -0.676128 + outer loop + vertex 349.734 72.3968 288.719 + vertex 351.586 72.939 287.187 + vertex 352.58 69.8649 289.528 + endloop + endfacet + facet normal -0.35665 -0.636155 -0.684184 + outer loop + vertex 352.58 69.8649 289.528 + vertex 351.586 72.939 287.187 + vertex 354.512 70.4291 287.996 + endloop + endfacet + facet normal -0.378461 -0.652626 -0.656389 + outer loop + vertex 351.586 72.939 287.187 + vertex 353.423 73.4995 285.572 + vertex 354.512 70.4291 287.996 + endloop + endfacet + facet normal -0.363962 -0.653352 -0.663825 + outer loop + vertex 354.512 70.4291 287.996 + vertex 353.423 73.4995 285.572 + vertex 356.424 71.0074 286.379 + endloop + endfacet + facet normal -0.544948 -0.451765 -0.706356 + outer loop + vertex 344.209 82.3771 285.329 + vertex 345.856 82.8858 283.733 + vertex 346.361 78.965 285.851 + endloop + endfacet + facet normal -0.534644 -0.453927 -0.712815 + outer loop + vertex 346.361 78.965 285.851 + vertex 345.856 82.8858 283.733 + vertex 348.064 79.4804 284.245 + endloop + endfacet + facet normal -0.535182 -0.438148 -0.722223 + outer loop + vertex 342.568 81.8851 286.843 + vertex 344.209 82.3771 285.329 + vertex 344.651 78.4647 287.374 + endloop + endfacet + facet normal -0.521847 -0.440856 -0.730289 + outer loop + vertex 344.651 78.4647 287.374 + vertex 344.209 82.3771 285.329 + vertex 346.361 78.965 285.851 + endloop + endfacet + facet normal -0.485562 -0.507836 -0.71157 + outer loop + vertex 344.651 78.4647 287.374 + vertex 346.361 78.965 285.851 + vertex 347.063 75.2804 288.001 + endloop + endfacet + facet normal -0.470282 -0.509985 -0.720243 + outer loop + vertex 347.063 75.2804 288.001 + vertex 346.361 78.965 285.851 + vertex 348.843 75.8 286.471 + endloop + endfacet + facet normal -0.494917 -0.523998 -0.693169 + outer loop + vertex 346.361 78.965 285.851 + vertex 348.064 79.4804 284.245 + vertex 348.843 75.8 286.471 + endloop + endfacet + facet normal -0.478932 -0.526308 -0.702584 + outer loop + vertex 348.843 75.8 286.471 + vertex 348.064 79.4804 284.245 + vertex 350.612 76.3404 284.86 + endloop + endfacet + facet normal -0.579343 -0.364253 -0.729165 + outer loop + vertex 340.801 85.5193 286.431 + vertex 342.386 86.0122 284.926 + vertex 342.568 81.8851 286.843 + endloop + endfacet + facet normal -0.569121 -0.366909 -0.735853 + outer loop + vertex 342.568 81.8851 286.843 + vertex 342.386 86.0122 284.926 + vertex 344.209 82.3771 285.329 + endloop + endfacet + facet normal -0.592492 -0.376032 -0.712428 + outer loop + vertex 342.386 86.0122 284.926 + vertex 343.975 86.5219 283.336 + vertex 344.209 82.3771 285.329 + endloop + endfacet + facet normal -0.580878 -0.379158 -0.720291 + outer loop + vertex 344.209 82.3771 285.329 + vertex 343.975 86.5219 283.336 + vertex 345.856 82.8858 283.733 + endloop + endfacet + facet normal -0.108959 -0.874502 -0.472625 + outer loop + vertex 370.899 64.3929 289.913 + vertex 373.601 64.803 288.531 + vertex 375.237 62.4749 292.462 + endloop + endfacet + facet normal -0.0976281 -0.887555 -0.450238 + outer loop + vertex 375.033 65.6943 286.464 + vertex 379.825 63.8794 289.002 + vertex 373.601 64.803 288.531 + endloop + endfacet + facet normal -0.0933697 -0.873197 -0.47834 + outer loop + vertex 379.825 63.8794 289.002 + vertex 375.237 62.4749 292.462 + vertex 373.601 64.803 288.531 + endloop + endfacet + facet normal -0.195096 -0.834597 -0.515156 + outer loop + vertex 365.15 67.6473 286.519 + vertex 367.065 68.2495 284.818 + vertex 369.106 66.1425 287.459 + endloop + endfacet + facet normal -0.190428 -0.833824 -0.518146 + outer loop + vertex 369.106 66.1425 287.459 + vertex 367.065 68.2495 284.818 + vertex 371.058 66.7629 285.743 + endloop + endfacet + facet normal -0.19294 -0.822844 -0.534511 + outer loop + vertex 363.131 67.0352 288.19 + vertex 365.15 67.6473 286.519 + vertex 367.024 65.5088 289.135 + endloop + endfacet + facet normal -0.184311 -0.821502 -0.539597 + outer loop + vertex 367.024 65.5088 289.135 + vertex 365.15 67.6473 286.519 + vertex 369.106 66.1425 287.459 + endloop + endfacet + facet normal -0.144705 -0.85259 -0.502146 + outer loop + vertex 367.024 65.5088 289.135 + vertex 369.106 66.1425 287.459 + vertex 370.899 64.3929 289.913 + endloop + endfacet + facet normal -0.131708 -0.850108 -0.509871 + outer loop + vertex 370.899 64.3929 289.913 + vertex 369.106 66.1425 287.459 + vertex 373.601 64.803 288.531 + endloop + endfacet + facet normal -0.14434 -0.866652 -0.477578 + outer loop + vertex 369.106 66.1425 287.459 + vertex 371.058 66.7629 285.743 + vertex 373.601 64.803 288.531 + endloop + endfacet + facet normal -0.146936 -0.867276 -0.475649 + outer loop + vertex 373.601 64.803 288.531 + vertex 371.058 66.7629 285.743 + vertex 375.033 65.6943 286.464 + endloop + endfacet + facet normal -0.323759 -0.741175 -0.588082 + outer loop + vertex 358.282 71.5832 284.713 + vertex 360.07 72.1487 283.016 + vertex 361.563 69.4522 285.592 + endloop + endfacet + facet normal -0.312348 -0.740969 -0.594478 + outer loop + vertex 361.563 69.4522 285.592 + vertex 360.07 72.1487 283.016 + vertex 363.419 70.0324 283.893 + endloop + endfacet + facet normal -0.320075 -0.726542 -0.60802 + outer loop + vertex 356.424 71.0074 286.379 + vertex 358.282 71.5832 284.713 + vertex 359.623 68.8595 287.261 + endloop + endfacet + facet normal -0.307041 -0.726464 -0.614798 + outer loop + vertex 359.623 68.8595 287.261 + vertex 358.282 71.5832 284.713 + vertex 361.563 69.4522 285.592 + endloop + endfacet + facet normal -0.254023 -0.779827 -0.572139 + outer loop + vertex 359.623 68.8595 287.261 + vertex 361.563 69.4522 285.592 + vertex 363.131 67.0352 288.19 + endloop + endfacet + facet normal -0.242484 -0.778959 -0.578294 + outer loop + vertex 363.131 67.0352 288.19 + vertex 361.563 69.4522 285.592 + vertex 365.15 67.6473 286.519 + endloop + endfacet + facet normal -0.256727 -0.79358 -0.551655 + outer loop + vertex 361.563 69.4522 285.592 + vertex 363.419 70.0324 283.893 + vertex 365.15 67.6473 286.519 + endloop + endfacet + facet normal -0.246133 -0.792648 -0.557788 + outer loop + vertex 365.15 67.6473 286.519 + vertex 363.419 70.0324 283.893 + vertex 367.065 68.2495 284.818 + endloop + endfacet + facet normal -0.450769 -0.621254 -0.640976 + outer loop + vertex 352.33 76.8779 283.203 + vertex 353.988 77.4116 281.52 + vertex 355.208 74.0601 283.91 + endloop + endfacet + facet normal -0.438937 -0.622153 -0.648275 + outer loop + vertex 355.208 74.0601 283.91 + vertex 353.988 77.4116 281.52 + vertex 356.927 74.6099 282.219 + endloop + endfacet + facet normal -0.445816 -0.606027 -0.658771 + outer loop + vertex 350.612 76.3404 284.86 + vertex 352.33 76.8779 283.203 + vertex 353.423 73.4995 285.572 + endloop + endfacet + facet normal -0.43058 -0.607323 -0.667653 + outer loop + vertex 353.423 73.4995 285.572 + vertex 352.33 76.8779 283.203 + vertex 355.208 74.0601 283.91 + endloop + endfacet + facet normal -0.383406 -0.668254 -0.637524 + outer loop + vertex 353.423 73.4995 285.572 + vertex 355.208 74.0601 283.91 + vertex 356.424 71.0074 286.379 + endloop + endfacet + facet normal -0.370659 -0.668787 -0.644465 + outer loop + vertex 356.424 71.0074 286.379 + vertex 355.208 74.0601 283.91 + vertex 358.282 71.5832 284.713 + endloop + endfacet + facet normal -0.389315 -0.683275 -0.617712 + outer loop + vertex 355.208 74.0601 283.91 + vertex 356.927 74.6099 282.219 + vertex 358.282 71.5832 284.713 + endloop + endfacet + facet normal -0.376918 -0.683668 -0.624925 + outer loop + vertex 358.282 71.5832 284.713 + vertex 356.927 74.6099 282.219 + vertex 360.07 72.1487 283.016 + endloop + endfacet + facet normal -0.56339 -0.475705 -0.675497 + outer loop + vertex 347.466 83.3996 282.091 + vertex 349.029 83.9182 280.422 + vertex 349.725 80.005 282.597 + endloop + endfacet + facet normal -0.554178 -0.477559 -0.681781 + outer loop + vertex 349.725 80.005 282.597 + vertex 349.029 83.9182 280.422 + vertex 351.333 80.5296 280.923 + endloop + endfacet + facet normal -0.555441 -0.46399 -0.690071 + outer loop + vertex 345.856 82.8858 283.733 + vertex 347.466 83.3996 282.091 + vertex 348.064 79.4804 284.245 + endloop + endfacet + facet normal -0.544346 -0.466287 -0.697327 + outer loop + vertex 348.064 79.4804 284.245 + vertex 347.466 83.3996 282.091 + vertex 349.725 80.005 282.597 + endloop + endfacet + facet normal -0.501052 -0.53923 -0.676889 + outer loop + vertex 348.064 79.4804 284.245 + vertex 349.725 80.005 282.597 + vertex 350.612 76.3404 284.86 + endloop + endfacet + facet normal -0.490197 -0.540744 -0.683596 + outer loop + vertex 350.612 76.3404 284.86 + vertex 349.725 80.005 282.597 + vertex 352.33 76.8779 283.203 + endloop + endfacet + facet normal -0.508507 -0.55164 -0.661146 + outer loop + vertex 349.725 80.005 282.597 + vertex 351.333 80.5296 280.923 + vertex 352.33 76.8779 283.203 + endloop + endfacet + facet normal -0.499315 -0.552855 -0.66711 + outer loop + vertex 352.33 76.8779 283.203 + vertex 351.333 80.5296 280.923 + vertex 353.988 77.4116 281.52 + endloop + endfacet + facet normal -0.601967 -0.387645 -0.698117 + outer loop + vertex 343.975 86.5219 283.336 + vertex 345.542 87.0406 281.696 + vertex 345.856 82.8858 283.733 + endloop + endfacet + facet normal -0.593402 -0.389951 -0.704139 + outer loop + vertex 345.856 82.8858 283.733 + vertex 345.542 87.0406 281.696 + vertex 347.466 83.3996 282.091 + endloop + endfacet + facet normal -0.611625 -0.397408 -0.684092 + outer loop + vertex 345.542 87.0406 281.696 + vertex 347.072 87.563 280.025 + vertex 347.466 83.3996 282.091 + endloop + endfacet + facet normal -0.603885 -0.399477 -0.68974 + outer loop + vertex 347.466 83.3996 282.091 + vertex 347.072 87.563 280.025 + vertex 349.029 83.9182 280.422 + endloop + endfacet + facet normal -0.111817 -0.89609 -0.429558 + outer loop + vertex 375.033 65.6943 286.464 + vertex 377.657 66.1 284.934 + vertex 379.825 63.8794 289.002 + endloop + endfacet + facet normal -0.0979425 -0.90676 -0.410114 + outer loop + vertex 378.995 66.9582 282.717 + vertex 384.324 65.219 285.29 + vertex 377.657 66.1 284.934 + endloop + endfacet + facet normal -0.0948144 -0.894171 -0.43757 + outer loop + vertex 384.324 65.219 285.29 + vertex 379.825 63.8794 289.002 + vertex 377.657 66.1 284.934 + endloop + endfacet + facet normal -0.204281 -0.857346 -0.472469 + outer loop + vertex 368.883 68.8317 283.069 + vertex 370.656 69.4118 281.25 + vertex 372.935 67.3757 283.959 + endloop + endfacet + facet normal -0.200608 -0.856752 -0.475113 + outer loop + vertex 372.935 67.3757 283.959 + vertex 370.656 69.4118 281.25 + vertex 374.78 67.977 282.096 + endloop + endfacet + facet normal -0.201575 -0.847208 -0.491534 + outer loop + vertex 367.065 68.2495 284.818 + vertex 368.883 68.8317 283.069 + vertex 371.058 66.7629 285.743 + endloop + endfacet + facet normal -0.195088 -0.846135 -0.49598 + outer loop + vertex 371.058 66.7629 285.743 + vertex 368.883 68.8317 283.069 + vertex 372.935 67.3757 283.959 + endloop + endfacet + facet normal -0.151744 -0.874749 -0.460205 + outer loop + vertex 371.058 66.7629 285.743 + vertex 372.935 67.3757 283.959 + vertex 375.033 65.6943 286.464 + endloop + endfacet + facet normal -0.138708 -0.872064 -0.469323 + outer loop + vertex 375.033 65.6943 286.464 + vertex 372.935 67.3757 283.959 + vertex 377.657 66.1 284.934 + endloop + endfacet + facet normal -0.150038 -0.887814 -0.435058 + outer loop + vertex 372.935 67.3757 283.959 + vertex 374.78 67.977 282.096 + vertex 377.657 66.1 284.934 + endloop + endfacet + facet normal -0.15058 -0.887948 -0.434597 + outer loop + vertex 377.657 66.1 284.934 + vertex 374.78 67.977 282.096 + vertex 378.995 66.9582 282.717 + endloop + endfacet + facet normal -0.333091 -0.767933 -0.54711 + outer loop + vertex 361.801 72.7008 281.277 + vertex 363.494 73.2408 279.488 + vertex 365.203 70.6012 282.153 + endloop + endfacet + facet normal -0.325558 -0.767801 -0.55181 + outer loop + vertex 365.203 70.6012 282.153 + vertex 363.494 73.2408 279.488 + vertex 366.934 71.1582 280.357 + endloop + endfacet + facet normal -0.328607 -0.755315 -0.567024 + outer loop + vertex 360.07 72.1487 283.016 + vertex 361.801 72.7008 281.277 + vertex 363.419 70.0324 283.893 + endloop + endfacet + facet normal -0.318489 -0.755095 -0.573059 + outer loop + vertex 363.419 70.0324 283.893 + vertex 361.801 72.7008 281.277 + vertex 365.203 70.6012 282.153 + endloop + endfacet + facet normal -0.26013 -0.806969 -0.530219 + outer loop + vertex 363.419 70.0324 283.893 + vertex 365.203 70.6012 282.153 + vertex 367.065 68.2495 284.818 + endloop + endfacet + facet normal -0.254931 -0.806505 -0.533442 + outer loop + vertex 367.065 68.2495 284.818 + vertex 365.203 70.6012 282.153 + vertex 368.883 68.8317 283.069 + endloop + endfacet + facet normal -0.266199 -0.817867 -0.510129 + outer loop + vertex 365.203 70.6012 282.153 + vertex 366.934 71.1582 280.357 + vertex 368.883 68.8317 283.069 + endloop + endfacet + facet normal -0.260081 -0.817357 -0.514087 + outer loop + vertex 368.883 68.8317 283.069 + vertex 366.934 71.1582 280.357 + vertex 370.656 69.4118 281.25 + endloop + endfacet + facet normal -0.465664 -0.648541 -0.602123 + outer loop + vertex 355.605 77.9398 279.798 + vertex 357.201 78.4433 278.022 + vertex 358.6 75.1507 280.486 + endloop + endfacet + facet normal -0.455713 -0.64934 -0.608838 + outer loop + vertex 358.6 75.1507 280.486 + vertex 357.201 78.4433 278.022 + vertex 360.245 75.6702 278.701 + endloop + endfacet + facet normal -0.456615 -0.63454 -0.623588 + outer loop + vertex 353.988 77.4116 281.52 + vertex 355.605 77.9398 279.798 + vertex 356.927 74.6099 282.219 + endloop + endfacet + facet normal -0.446906 -0.635251 -0.629866 + outer loop + vertex 356.927 74.6099 282.219 + vertex 355.605 77.9398 279.798 + vertex 358.6 75.1507 280.486 + endloop + endfacet + facet normal -0.394337 -0.697354 -0.598494 + outer loop + vertex 356.927 74.6099 282.219 + vertex 358.6 75.1507 280.486 + vertex 360.07 72.1487 283.016 + endloop + endfacet + facet normal -0.384618 -0.697628 -0.60447 + outer loop + vertex 360.07 72.1487 283.016 + vertex 358.6 75.1507 280.486 + vertex 361.801 72.7008 281.277 + endloop + endfacet + facet normal -0.4017 -0.711098 -0.577041 + outer loop + vertex 358.6 75.1507 280.486 + vertex 360.245 75.6702 278.701 + vertex 361.801 72.7008 281.277 + endloop + endfacet + facet normal -0.390389 -0.711469 -0.584302 + outer loop + vertex 361.801 72.7008 281.277 + vertex 360.245 75.6702 278.701 + vertex 363.494 73.2408 279.488 + endloop + endfacet + facet normal -0.585299 -0.498797 -0.63924 + outer loop + vertex 350.562 84.4269 278.714 + vertex 352.078 84.9009 276.956 + vertex 352.903 81.0438 279.211 + endloop + endfacet + facet normal -0.574964 -0.501024 -0.646831 + outer loop + vertex 352.903 81.0438 279.211 + vertex 352.078 84.9009 276.956 + vertex 354.458 81.5353 277.447 + endloop + endfacet + facet normal -0.572942 -0.486978 -0.659234 + outer loop + vertex 349.029 83.9182 280.422 + vertex 350.562 84.4269 278.714 + vertex 351.333 80.5296 280.923 + endloop + endfacet + facet normal -0.565113 -0.488577 -0.664786 + outer loop + vertex 351.333 80.5296 280.923 + vertex 350.562 84.4269 278.714 + vertex 352.903 81.0438 279.211 + endloop + endfacet + facet normal -0.517461 -0.563824 -0.64369 + outer loop + vertex 351.333 80.5296 280.923 + vertex 352.903 81.0438 279.211 + vertex 353.988 77.4116 281.52 + endloop + endfacet + facet normal -0.507713 -0.56511 -0.650291 + outer loop + vertex 353.988 77.4116 281.52 + vertex 352.903 81.0438 279.211 + vertex 355.605 77.9398 279.798 + endloop + endfacet + facet normal -0.526328 -0.576525 -0.624977 + outer loop + vertex 352.903 81.0438 279.211 + vertex 354.458 81.5353 277.447 + vertex 355.605 77.9398 279.798 + endloop + endfacet + facet normal -0.519145 -0.577537 -0.630031 + outer loop + vertex 355.605 77.9398 279.798 + vertex 354.458 81.5353 277.447 + vertex 357.201 78.4433 278.022 + endloop + endfacet + facet normal -0.622341 -0.407083 -0.668561 + outer loop + vertex 347.072 87.563 280.025 + vertex 348.575 88.0742 278.314 + vertex 349.029 83.9182 280.422 + endloop + endfacet + facet normal -0.615212 -0.409036 -0.673946 + outer loop + vertex 349.029 83.9182 280.422 + vertex 348.575 88.0742 278.314 + vertex 350.562 84.4269 278.714 + endloop + endfacet + facet normal -0.633487 -0.416585 -0.652036 + outer loop + vertex 348.575 88.0742 278.314 + vertex 350.075 88.5473 276.554 + vertex 350.562 84.4269 278.714 + endloop + endfacet + facet normal -0.629268 -0.417812 -0.655328 + outer loop + vertex 350.562 84.4269 278.714 + vertex 350.075 88.5473 276.554 + vertex 352.078 84.9009 276.956 + endloop + endfacet + facet normal -0.108765 -0.913426 -0.392202 + outer loop + vertex 378.995 66.9582 282.717 + vertex 381.712 67.3135 281.136 + vertex 384.324 65.219 285.29 + endloop + endfacet + facet normal -0.0916879 -0.919663 -0.381854 + outer loop + vertex 382.669 68.0699 279.085 + vertex 389.114 66.3852 281.595 + vertex 381.712 67.3135 281.136 + endloop + endfacet + facet normal -0.0892552 -0.910777 -0.403135 + outer loop + vertex 389.114 66.3852 281.595 + vertex 384.324 65.219 285.29 + vertex 381.712 67.3135 281.136 + endloop + endfacet + facet normal -0.2074 -0.873242 -0.440946 + outer loop + vertex 372.383 69.9656 279.407 + vertex 373.973 70.4662 277.668 + vertex 376.623 68.5527 280.211 + endloop + endfacet + facet normal -0.200069 -0.871668 -0.447401 + outer loop + vertex 376.623 68.5527 280.211 + vertex 373.973 70.4662 277.668 + vertex 378.293 69.0724 278.452 + endloop + endfacet + facet normal -0.2079 -0.865872 -0.45502 + outer loop + vertex 370.656 69.4118 281.25 + vertex 372.383 69.9656 279.407 + vertex 374.78 67.977 282.096 + endloop + endfacet + facet normal -0.200858 -0.86468 -0.460418 + outer loop + vertex 374.78 67.977 282.096 + vertex 372.383 69.9656 279.407 + vertex 376.623 68.5527 280.211 + endloop + endfacet + facet normal -0.153556 -0.893095 -0.42285 + outer loop + vertex 374.78 67.977 282.096 + vertex 376.623 68.5527 280.211 + vertex 378.995 66.9582 282.717 + endloop + endfacet + facet normal -0.137322 -0.889458 -0.435898 + outer loop + vertex 378.995 66.9582 282.717 + vertex 376.623 68.5527 280.211 + vertex 381.712 67.3135 281.136 + endloop + endfacet + facet normal -0.146063 -0.902464 -0.405247 + outer loop + vertex 376.623 68.5527 280.211 + vertex 378.293 69.0724 278.452 + vertex 381.712 67.3135 281.136 + endloop + endfacet + facet normal -0.148722 -0.903299 -0.402408 + outer loop + vertex 381.712 67.3135 281.136 + vertex 378.293 69.0724 278.452 + vertex 382.669 68.0699 279.085 + endloop + endfacet + facet normal -0.337799 -0.786705 -0.516708 + outer loop + vertex 365.125 73.7467 277.684 + vertex 366.605 74.2217 275.993 + vertex 368.602 71.6897 278.543 + endloop + endfacet + facet normal -0.331648 -0.786367 -0.521188 + outer loop + vertex 368.602 71.6897 278.543 + vertex 366.605 74.2217 275.993 + vertex 370.124 72.1784 276.837 + endloop + endfacet + facet normal -0.339563 -0.780014 -0.525618 + outer loop + vertex 363.494 73.2408 279.488 + vertex 365.125 73.7467 277.684 + vertex 366.934 71.1582 280.357 + endloop + endfacet + facet normal -0.329978 -0.779842 -0.531941 + outer loop + vertex 366.934 71.1582 280.357 + vertex 365.125 73.7467 277.684 + vertex 368.602 71.6897 278.543 + endloop + endfacet + facet normal -0.270496 -0.827905 -0.49133 + outer loop + vertex 366.934 71.1582 280.357 + vertex 368.602 71.6897 278.543 + vertex 370.656 69.4118 281.25 + endloop + endfacet + facet normal -0.263861 -0.827333 -0.495881 + outer loop + vertex 370.656 69.4118 281.25 + vertex 368.602 71.6897 278.543 + vertex 372.383 69.9656 279.407 + endloop + endfacet + facet normal -0.270561 -0.834267 -0.480411 + outer loop + vertex 368.602 71.6897 278.543 + vertex 370.124 72.1784 276.837 + vertex 372.383 69.9656 279.407 + endloop + endfacet + facet normal -0.266457 -0.833757 -0.48358 + outer loop + vertex 372.383 69.9656 279.407 + vertex 370.124 72.1784 276.837 + vertex 373.973 70.4662 277.668 + endloop + endfacet + facet normal -0.472201 -0.666186 -0.577254 + outer loop + vertex 358.762 78.9256 276.237 + vertex 360.181 79.3703 274.563 + vertex 361.841 76.164 276.905 + endloop + endfacet + facet normal -0.464692 -0.66648 -0.58298 + outer loop + vertex 361.841 76.164 276.905 + vertex 360.181 79.3703 274.563 + vertex 363.29 76.6242 275.224 + endloop + endfacet + facet normal -0.468971 -0.65884 -0.588214 + outer loop + vertex 357.201 78.4433 278.022 + vertex 358.762 78.9256 276.237 + vertex 360.245 75.6702 278.701 + endloop + endfacet + facet normal -0.462714 -0.659321 -0.592615 + outer loop + vertex 360.245 75.6702 278.701 + vertex 358.762 78.9256 276.237 + vertex 361.841 76.164 276.905 + endloop + endfacet + facet normal -0.405296 -0.723254 -0.559142 + outer loop + vertex 360.245 75.6702 278.701 + vertex 361.841 76.164 276.905 + vertex 363.494 73.2408 279.488 + endloop + endfacet + facet normal -0.398949 -0.723455 -0.563429 + outer loop + vertex 363.494 73.2408 279.488 + vertex 361.841 76.164 276.905 + vertex 365.125 73.7467 277.684 + endloop + endfacet + facet normal -0.406535 -0.729464 -0.550101 + outer loop + vertex 361.841 76.164 276.905 + vertex 363.29 76.6242 275.224 + vertex 365.125 73.7467 277.684 + endloop + endfacet + facet normal -0.399903 -0.729421 -0.554997 + outer loop + vertex 365.125 73.7467 277.684 + vertex 363.29 76.6242 275.224 + vertex 366.605 74.2217 275.993 + endloop + endfacet + facet normal -0.596544 -0.514994 -0.615562 + outer loop + vertex 353.573 85.3426 275.194 + vertex 354.934 85.7461 273.537 + vertex 355.975 81.9909 275.67 + endloop + endfacet + facet normal -0.586692 -0.516767 -0.623493 + outer loop + vertex 355.975 81.9909 275.67 + vertex 354.934 85.7461 273.537 + vertex 357.367 82.4202 274.005 + endloop + endfacet + facet normal -0.589495 -0.508498 -0.627635 + outer loop + vertex 352.078 84.9009 276.956 + vertex 353.573 85.3426 275.194 + vertex 354.458 81.5353 277.447 + endloop + endfacet + facet normal -0.585669 -0.509327 -0.630538 + outer loop + vertex 354.458 81.5353 277.447 + vertex 353.573 85.3426 275.194 + vertex 355.975 81.9909 275.67 + endloop + endfacet + facet normal -0.534988 -0.587363 -0.607283 + outer loop + vertex 354.458 81.5353 277.447 + vertex 355.975 81.9909 275.67 + vertex 357.201 78.4433 278.022 + endloop + endfacet + facet normal -0.522642 -0.589078 -0.616305 + outer loop + vertex 357.201 78.4433 278.022 + vertex 355.975 81.9909 275.67 + vertex 358.762 78.9256 276.237 + endloop + endfacet + facet normal -0.533782 -0.596141 -0.599743 + outer loop + vertex 355.975 81.9909 275.67 + vertex 357.367 82.4202 274.005 + vertex 358.762 78.9256 276.237 + endloop + endfacet + facet normal -0.526849 -0.596834 -0.605161 + outer loop + vertex 358.762 78.9256 276.237 + vertex 357.367 82.4202 274.005 + vertex 360.181 79.3703 274.563 + endloop + endfacet + facet normal -0.64362 -0.423714 -0.637354 + outer loop + vertex 350.075 88.5473 276.554 + vertex 351.547 88.9672 274.789 + vertex 352.078 84.9009 276.956 + endloop + endfacet + facet normal -0.634125 -0.426524 -0.644952 + outer loop + vertex 352.078 84.9009 276.956 + vertex 351.547 88.9672 274.789 + vertex 353.573 85.3426 275.194 + endloop + endfacet + facet normal -0.646908 -0.431831 -0.628516 + outer loop + vertex 351.547 88.9672 274.789 + vertex 352.896 89.3497 273.138 + vertex 353.573 85.3426 275.194 + endloop + endfacet + facet normal -0.6418 -0.433173 -0.632814 + outer loop + vertex 353.573 85.3426 275.194 + vertex 352.896 89.3497 273.138 + vertex 354.934 85.7461 273.537 + endloop + endfacet + facet normal -0.201046 -0.873344 -0.443678 + outer loop + vertex 375.238 70.9018 276.219 + vertex 376.02 71.2477 275.184 + vertex 379.512 69.5195 277.003 + endloop + endfacet + facet normal -0.203031 -0.874336 -0.440812 + outer loop + vertex 379.512 69.5195 277.003 + vertex 376.02 71.2477 275.184 + vertex 380.209 69.8631 276.001 + endloop + endfacet + facet normal -0.202509 -0.874961 -0.439811 + outer loop + vertex 373.973 70.4662 277.668 + vertex 375.238 70.9018 276.219 + vertex 378.293 69.0724 278.452 + endloop + endfacet + facet normal -0.202177 -0.874853 -0.440177 + outer loop + vertex 378.293 69.0724 278.452 + vertex 375.238 70.9018 276.219 + vertex 379.512 69.5195 277.003 + endloop + endfacet + facet normal -0.148441 -0.902819 -0.403588 + outer loop + vertex 378.293 69.0724 278.452 + vertex 379.512 69.5195 277.003 + vertex 382.669 68.0699 279.085 + endloop + endfacet + facet normal -0.142619 -0.9005 -0.410804 + outer loop + vertex 382.669 68.0699 279.085 + vertex 379.512 69.5195 277.003 + vertex 384.221 68.3343 277.966 + endloop + endfacet + facet normal -0.143306 -0.90141 -0.408564 + outer loop + vertex 379.512 69.5195 277.003 + vertex 380.209 69.8631 276.001 + vertex 384.221 68.3343 277.966 + endloop + endfacet + facet normal -0.166748 -0.9138 -0.370359 + outer loop + vertex 384.221 68.3343 277.966 + vertex 380.209 69.8631 276.001 + vertex 384.019 68.8739 276.726 + endloop + endfacet + facet normal -0.331214 -0.786372 -0.521456 + outer loop + vertex 367.785 74.6417 274.588 + vertex 368.546 74.9841 273.588 + vertex 371.346 72.5999 275.404 + endloop + endfacet + facet normal -0.332184 -0.786683 -0.520368 + outer loop + vertex 371.346 72.5999 275.404 + vertex 368.546 74.9841 273.588 + vertex 372.126 72.9465 274.383 + endloop + endfacet + facet normal -0.334162 -0.788616 -0.516159 + outer loop + vertex 366.605 74.2217 275.993 + vertex 367.785 74.6417 274.588 + vertex 370.124 72.1784 276.837 + endloop + endfacet + facet normal -0.333535 -0.788522 -0.516708 + outer loop + vertex 370.124 72.1784 276.837 + vertex 367.785 74.6417 274.588 + vertex 371.346 72.5999 275.404 + endloop + endfacet + facet normal -0.269467 -0.836985 -0.476282 + outer loop + vertex 370.124 72.1784 276.837 + vertex 371.346 72.5999 275.404 + vertex 373.973 70.4662 277.668 + endloop + endfacet + facet normal -0.263872 -0.835729 -0.48159 + outer loop + vertex 373.973 70.4662 277.668 + vertex 371.346 72.5999 275.404 + vertex 375.238 70.9018 276.219 + endloop + endfacet + facet normal -0.262955 -0.834711 -0.483852 + outer loop + vertex 371.346 72.5999 275.404 + vertex 372.126 72.9465 274.383 + vertex 375.238 70.9018 276.219 + endloop + endfacet + facet normal -0.265923 -0.835906 -0.480152 + outer loop + vertex 375.238 70.9018 276.219 + vertex 372.126 72.9465 274.383 + vertex 376.02 71.2477 275.184 + endloop + endfacet + facet normal -0.46142 -0.66834 -0.58345 + outer loop + vertex 361.317 79.7692 273.156 + vertex 362.061 80.1099 272.178 + vertex 364.447 77.0315 273.818 + endloop + endfacet + facet normal -0.464062 -0.668916 -0.580688 + outer loop + vertex 364.447 77.0315 273.818 + vertex 362.061 80.1099 272.178 + vertex 365.197 77.3694 272.828 + endloop + endfacet + facet normal -0.471612 -0.67155 -0.571492 + outer loop + vertex 360.181 79.3703 274.563 + vertex 361.317 79.7692 273.156 + vertex 363.29 76.6242 275.224 + endloop + endfacet + facet normal -0.465302 -0.671225 -0.57702 + outer loop + vertex 363.29 76.6242 275.224 + vertex 361.317 79.7692 273.156 + vertex 364.447 77.0315 273.818 + endloop + endfacet + facet normal -0.405123 -0.733618 -0.545601 + outer loop + vertex 363.29 76.6242 275.224 + vertex 364.447 77.0315 273.818 + vertex 366.605 74.2217 275.993 + endloop + endfacet + facet normal -0.397234 -0.732832 -0.552415 + outer loop + vertex 366.605 74.2217 275.993 + vertex 364.447 77.0315 273.818 + vertex 367.785 74.6417 274.588 + endloop + endfacet + facet normal -0.397446 -0.733005 -0.552033 + outer loop + vertex 364.447 77.0315 273.818 + vertex 365.197 77.3694 272.828 + vertex 367.785 74.6417 274.588 + endloop + endfacet + facet normal -0.396618 -0.732789 -0.552915 + outer loop + vertex 367.785 74.6417 274.588 + vertex 365.197 77.3694 272.828 + vertex 368.546 74.9841 273.588 + endloop + endfacet + facet normal -0.57804 -0.513167 -0.634453 + outer loop + vertex 356.027 86.1466 272.168 + vertex 356.746 86.525 271.207 + vertex 358.48 82.8244 272.62 + endloop + endfacet + facet normal -0.585274 -0.513811 -0.627257 + outer loop + vertex 358.48 82.8244 272.62 + vertex 356.746 86.525 271.207 + vertex 359.216 83.1777 271.644 + endloop + endfacet + facet normal -0.588489 -0.51773 -0.620995 + outer loop + vertex 354.934 85.7461 273.537 + vertex 356.027 86.1466 272.168 + vertex 357.367 82.4202 274.005 + endloop + endfacet + facet normal -0.586587 -0.517874 -0.622674 + outer loop + vertex 357.367 82.4202 274.005 + vertex 356.027 86.1466 272.168 + vertex 358.48 82.8244 272.62 + endloop + endfacet + facet normal -0.529829 -0.598757 -0.600643 + outer loop + vertex 357.367 82.4202 274.005 + vertex 358.48 82.8244 272.62 + vertex 360.181 79.3703 274.563 + endloop + endfacet + facet normal -0.531469 -0.598752 -0.599197 + outer loop + vertex 360.181 79.3703 274.563 + vertex 358.48 82.8244 272.62 + vertex 361.317 79.7692 273.156 + endloop + endfacet + facet normal -0.524226 -0.593966 -0.610239 + outer loop + vertex 358.48 82.8244 272.62 + vertex 359.216 83.1777 271.644 + vertex 361.317 79.7692 273.156 + endloop + endfacet + facet normal -0.5269 -0.594401 -0.607506 + outer loop + vertex 361.317 79.7692 273.156 + vertex 359.216 83.1777 271.644 + vertex 362.061 80.1099 272.178 + endloop + endfacet + facet normal -0.640433 -0.432596 -0.634591 + outer loop + vertex 352.896 89.3497 273.138 + vertex 353.975 89.739 271.784 + vertex 354.934 85.7461 273.537 + endloop + endfacet + facet normal -0.638641 -0.432874 -0.636206 + outer loop + vertex 354.934 85.7461 273.537 + vertex 353.975 89.739 271.784 + vertex 356.027 86.1466 272.168 + endloop + endfacet + facet normal -0.632311 -0.430127 -0.64434 + outer loop + vertex 353.975 89.739 271.784 + vertex 354.68 90.1206 270.837 + vertex 356.027 86.1466 272.168 + endloop + endfacet + facet normal -0.63347 -0.430136 -0.643194 + outer loop + vertex 356.027 86.1466 272.168 + vertex 354.68 90.1206 270.837 + vertex 356.746 86.525 271.207 + endloop + endfacet + facet normal 0.217454 -0.974687 -0.0519469 + outer loop + vertex 480.343 70.7609 303.716 + vertex 484.782 71.6547 305.526 + vertex 482.204 71.0673 305.754 + endloop + endfacet + facet normal 0.216269 -0.971273 -0.0992785 + outer loop + vertex 473.789 69.5704 301.086 + vertex 480.343 70.7609 303.716 + vertex 476.76 69.993 303.422 + endloop + endfacet + facet normal 0.207258 -0.96515 -0.159781 + outer loop + vertex 465.943 68.3293 298.405 + vertex 473.789 69.5704 301.086 + vertex 469.439 68.7182 300.59 + endloop + endfacet + facet normal 0.185232 -0.963982 -0.190862 + outer loop + vertex 458.064 67.3114 295.9 + vertex 465.943 68.3293 298.405 + vertex 461.095 67.5225 297.775 + endloop + endfacet + facet normal -0.101939 -0.915497 -0.389195 + outer loop + vertex 384.019 68.8739 276.726 + vertex 385.446 68.7654 276.607 + vertex 388.809 67.6083 278.448 + endloop + endfacet + facet normal -0.105078 -0.932512 -0.345515 + outer loop + vertex 385.295 68.8943 276.305 + vertex 392.199 67.3937 278.256 + vertex 385.446 68.7654 276.607 + endloop + endfacet + facet normal -0.0810805 -0.903894 -0.420001 + outer loop + vertex 392.199 67.3937 278.256 + vertex 388.809 67.6083 278.448 + vertex 385.446 68.7654 276.607 + endloop + endfacet + facet normal -0.205588 -0.876431 -0.435433 + outer loop + vertex 376.392 71.4771 274.596 + vertex 376.683 71.5164 274.379 + vertex 380.628 70.0542 275.46 + endloop + endfacet + facet normal -0.181301 -0.852027 -0.4911 + outer loop + vertex 380.628 70.0542 275.46 + vertex 376.683 71.5164 274.379 + vertex 381.001 70.0606 275.311 + endloop + endfacet + facet normal -0.195971 -0.865205 -0.461536 + outer loop + vertex 376.02 71.2477 275.184 + vertex 376.392 71.4771 274.596 + vertex 380.209 69.8631 276.001 + endloop + endfacet + facet normal -0.197387 -0.866275 -0.458918 + outer loop + vertex 380.209 69.8631 276.001 + vertex 376.392 71.4771 274.596 + vertex 380.628 70.0542 275.46 + endloop + endfacet + facet normal -0.149275 -0.890329 -0.430152 + outer loop + vertex 380.209 69.8631 276.001 + vertex 380.628 70.0542 275.46 + vertex 384.019 68.8739 276.726 + endloop + endfacet + facet normal -0.107235 -0.854087 -0.508956 + outer loop + vertex 384.019 68.8739 276.726 + vertex 380.628 70.0542 275.46 + vertex 385.446 68.7654 276.607 + endloop + endfacet + facet normal -0.145502 -0.903309 -0.403561 + outer loop + vertex 380.628 70.0542 275.46 + vertex 381.001 70.0606 275.311 + vertex 385.446 68.7654 276.607 + endloop + endfacet + facet normal -0.18245 -0.933918 -0.307425 + outer loop + vertex 385.446 68.7654 276.607 + vertex 381.001 70.0606 275.311 + vertex 385.295 68.8943 276.305 + endloop + endfacet + facet normal -0.377381 -0.827488 -0.415749 + outer loop + vertex 368.903 75.211 273.003 + vertex 369.081 75.2492 272.766 + vertex 372.484 73.1833 273.788 + endloop + endfacet + facet normal -0.349944 -0.809692 -0.471104 + outer loop + vertex 372.484 73.1833 273.788 + vertex 369.081 75.2492 272.766 + vertex 372.703 73.2313 273.543 + endloop + endfacet + facet normal -0.336165 -0.790434 -0.512061 + outer loop + vertex 368.546 74.9841 273.588 + vertex 368.903 75.211 273.003 + vertex 372.126 72.9465 274.383 + endloop + endfacet + facet normal -0.333861 -0.789214 -0.51544 + outer loop + vertex 372.126 72.9465 274.383 + vertex 368.903 75.211 273.003 + vertex 372.484 73.1833 273.788 + endloop + endfacet + facet normal -0.262253 -0.831782 -0.489246 + outer loop + vertex 372.126 72.9465 274.383 + vertex 372.484 73.1833 273.788 + vertex 376.02 71.2477 275.184 + endloop + endfacet + facet normal -0.261792 -0.831483 -0.490001 + outer loop + vertex 376.02 71.2477 275.184 + vertex 372.484 73.1833 273.788 + vertex 376.392 71.4771 274.596 + endloop + endfacet + facet normal -0.287147 -0.858623 -0.424632 + outer loop + vertex 372.484 73.1833 273.788 + vertex 372.703 73.2313 273.543 + vertex 376.392 71.4771 274.596 + endloop + endfacet + facet normal -0.254737 -0.831692 -0.493354 + outer loop + vertex 376.392 71.4771 274.596 + vertex 372.703 73.2313 273.543 + vertex 376.683 71.5164 274.379 + endloop + endfacet + facet normal -0.551276 -0.727751 -0.408011 + outer loop + vertex 362.458 80.2989 271.63 + vertex 362.717 80.214 271.431 + vertex 365.568 77.5821 272.273 + endloop + endfacet + facet normal -0.516461 -0.711806 -0.476025 + outer loop + vertex 365.568 77.5821 272.273 + vertex 362.717 80.214 271.431 + vertex 365.766 77.5818 272.059 + endloop + endfacet + facet normal -0.469479 -0.672956 -0.571594 + outer loop + vertex 362.061 80.1099 272.178 + vertex 362.458 80.2989 271.63 + vertex 365.197 77.3694 272.828 + endloop + endfacet + facet normal -0.469727 -0.673056 -0.571272 + outer loop + vertex 365.197 77.3694 272.828 + vertex 362.458 80.2989 271.63 + vertex 365.568 77.5821 272.273 + endloop + endfacet + facet normal -0.399314 -0.73501 -0.548004 + outer loop + vertex 365.197 77.3694 272.828 + vertex 365.568 77.5821 272.273 + vertex 368.546 74.9841 273.588 + endloop + endfacet + facet normal -0.408121 -0.739025 -0.535985 + outer loop + vertex 368.546 74.9841 273.588 + vertex 365.568 77.5821 272.273 + vertex 368.903 75.211 273.003 + endloop + endfacet + facet normal -0.461021 -0.779148 -0.424721 + outer loop + vertex 365.568 77.5821 272.273 + vertex 365.766 77.5818 272.059 + vertex 368.903 75.211 273.003 + endloop + endfacet + facet normal -0.444673 -0.770362 -0.456955 + outer loop + vertex 368.903 75.211 273.003 + vertex 365.766 77.5818 272.059 + vertex 369.081 75.2492 272.766 + endloop + endfacet + facet normal -0.662074 -0.549044 -0.510106 + outer loop + vertex 357.134 86.7712 270.668 + vertex 357.404 86.6478 270.451 + vertex 359.624 83.3709 271.096 + endloop + endfacet + facet normal -0.651998 -0.545472 -0.526649 + outer loop + vertex 359.624 83.3709 271.096 + vertex 357.404 86.6478 270.451 + vertex 359.93 83.2011 270.893 + endloop + endfacet + facet normal -0.573 -0.50693 -0.643967 + outer loop + vertex 356.746 86.525 271.207 + vertex 357.134 86.7712 270.668 + vertex 359.216 83.1777 271.644 + endloop + endfacet + facet normal -0.59271 -0.512257 -0.62152 + outer loop + vertex 359.216 83.1777 271.644 + vertex 357.134 86.7712 270.668 + vertex 359.624 83.3709 271.096 + endloop + endfacet + facet normal -0.529296 -0.595988 -0.603857 + outer loop + vertex 359.216 83.1777 271.644 + vertex 359.624 83.3709 271.096 + vertex 362.061 80.1099 272.178 + endloop + endfacet + facet normal -0.536818 -0.598544 -0.59462 + outer loop + vertex 362.061 80.1099 272.178 + vertex 359.624 83.3709 271.096 + vertex 362.458 80.2989 271.63 + endloop + endfacet + facet normal -0.634769 -0.656396 -0.407692 + outer loop + vertex 359.624 83.3709 271.096 + vertex 359.93 83.2011 270.893 + vertex 362.458 80.2989 271.63 + endloop + endfacet + facet normal -0.58896 -0.6387 -0.495164 + outer loop + vertex 362.458 80.2989 271.63 + vertex 359.93 83.2011 270.893 + vertex 362.717 80.214 271.431 + endloop + endfacet + facet normal -0.620043 -0.424153 -0.660031 + outer loop + vertex 354.68 90.1206 270.837 + vertex 355.04 90.4042 270.316 + vertex 356.746 86.525 271.207 + endloop + endfacet + facet normal -0.630631 -0.426182 -0.648594 + outer loop + vertex 356.746 86.525 271.207 + vertex 355.04 90.4042 270.316 + vertex 357.134 86.7712 270.668 + endloop + endfacet + facet normal -0.658396 -0.438613 -0.611665 + outer loop + vertex 355.04 90.4042 270.316 + vertex 355.235 90.4029 270.108 + vertex 357.134 86.7712 270.668 + endloop + endfacet + facet normal -0.676407 -0.444291 -0.587434 + outer loop + vertex 357.134 86.7712 270.668 + vertex 355.235 90.4029 270.108 + vertex 357.404 86.6478 270.451 + endloop + endfacet + facet normal -0.355584 -0.904847 0.234121 + outer loop + vertex 376.683 71.5164 274.379 + vertex 377.321 71.2837 274.45 + vertex 381.001 70.0606 275.311 + endloop + endfacet + facet normal -0.365575 -0.873611 0.321183 + outer loop + vertex 381.001 70.0606 275.311 + vertex 377.321 71.2837 274.45 + vertex 381.349 69.9261 275.341 + endloop + endfacet + facet normal -0.335918 -0.737807 0.585491 + outer loop + vertex 381.001 70.0606 275.311 + vertex 381.349 69.9261 275.341 + vertex 385.295 68.8943 276.305 + endloop + endfacet + facet normal -0.321498 -0.452433 0.831832 + outer loop + vertex 385.295 68.8943 276.305 + vertex 381.349 69.9261 275.341 + vertex 384.152 69.1297 275.991 + endloop + endfacet + facet normal -0.512443 -0.790816 0.334682 + outer loop + vertex 369.081 75.2492 272.766 + vertex 369.538 74.9624 272.789 + vertex 372.703 73.2313 273.543 + endloop + endfacet + facet normal -0.339988 -0.821252 -0.458207 + outer loop + vertex 372.703 73.2313 273.543 + vertex 369.538 74.9624 272.789 + vertex 373.28 72.9699 273.583 + endloop + endfacet + facet normal -0.416208 -0.898758 0.137858 + outer loop + vertex 372.703 73.2313 273.543 + vertex 373.28 72.9699 273.583 + vertex 376.683 71.5164 274.379 + endloop + endfacet + facet normal -0.264819 -0.859419 -0.437344 + outer loop + vertex 376.683 71.5164 274.379 + vertex 373.28 72.9699 273.583 + vertex 377.321 71.2837 274.45 + endloop + endfacet + facet normal -0.545081 -0.464908 0.697673 + outer loop + vertex 362.717 80.214 271.431 + vertex 363.128 79.7756 271.46 + vertex 365.766 77.5818 272.059 + endloop + endfacet + facet normal -0.639583 -0.768722 0.00103914 + outer loop + vertex 365.766 77.5818 272.059 + vertex 363.128 79.7756 271.46 + vertex 366.15 77.262 272.079 + endloop + endfacet + facet normal -0.564171 -0.645786 0.514462 + outer loop + vertex 365.766 77.5818 272.059 + vertex 366.15 77.262 272.079 + vertex 369.081 75.2492 272.766 + endloop + endfacet + facet normal -0.50176 -0.822179 -0.268809 + outer loop + vertex 369.081 75.2492 272.766 + vertex 366.15 77.262 272.079 + vertex 369.538 74.9624 272.789 + endloop + endfacet + facet normal -0.629314 -0.373832 0.681333 + outer loop + vertex 357.404 86.6478 270.451 + vertex 358.014 85.6985 270.494 + vertex 359.93 83.2011 270.893 + endloop + endfacet + facet normal -0.787117 -0.613674 -0.0620597 + outer loop + vertex 359.93 83.2011 270.893 + vertex 358.014 85.6985 270.494 + vertex 360.477 82.494 270.942 + endloop + endfacet + facet normal -0.534822 -0.361529 0.763716 + outer loop + vertex 359.93 83.2011 270.893 + vertex 360.477 82.494 270.942 + vertex 362.717 80.214 271.431 + endloop + endfacet + facet normal -0.719318 -0.660337 0.215724 + outer loop + vertex 362.717 80.214 271.431 + vertex 360.477 82.494 270.942 + vertex 363.128 79.7756 271.46 + endloop + endfacet + facet normal -0.836571 -0.455282 0.304741 + outer loop + vertex 355.235 90.4029 270.108 + vertex 355.56 89.7963 270.093 + vertex 357.404 86.6478 270.451 + endloop + endfacet + facet normal -0.676729 -0.461427 -0.573692 + outer loop + vertex 357.404 86.6478 270.451 + vertex 355.56 89.7963 270.093 + vertex 358.014 85.6985 270.494 + endloop + endfacet + facet normal -0.55152 0.0468744 -0.832844 + outer loop + vertex 314.87 164.527 294.578 + vertex 314.45 169.032 295.109 + vertex 317.217 169.899 293.326 + endloop + endfacet + facet normal -0.499639 -0.0379305 -0.865403 + outer loop + vertex 315.293 160.231 294.522 + vertex 314.87 164.527 294.578 + vertex 317.541 162.536 293.123 + endloop + endfacet + facet normal -0.473028 -0.0716048 -0.878133 + outer loop + vertex 316.605 157.125 294.068 + vertex 315.293 160.231 294.522 + vertex 317.541 162.536 293.123 + endloop + endfacet + facet normal -0.502838 -0.0741233 -0.861196 + outer loop + vertex 316.612 153.514 294.375 + vertex 316.605 157.125 294.068 + vertex 318.755 153.908 293.09 + endloop + endfacet + facet normal -0.499557 -0.092414 -0.861338 + outer loop + vertex 317.352 151.066 294.209 + vertex 316.612 153.514 294.375 + vertex 318.755 153.908 293.09 + endloop + endfacet + facet normal -0.521876 -0.0767609 -0.849561 + outer loop + vertex 317.876 147.627 294.197 + vertex 317.352 151.066 294.209 + vertex 318.755 153.908 293.09 + endloop + endfacet + facet normal -0.518737 -0.0762976 -0.851522 + outer loop + vertex 318.341 142.714 294.354 + vertex 317.876 147.627 294.197 + vertex 320.346 145.363 292.895 + endloop + endfacet + facet normal -0.510192 -0.0851433 -0.855836 + outer loop + vertex 319.554 139.464 293.955 + vertex 318.341 142.714 294.354 + vertex 320.346 145.363 292.895 + endloop + endfacet + facet normal -0.523885 -0.0647515 -0.849324 + outer loop + vertex 319.397 135.44 294.358 + vertex 319.554 139.464 293.955 + vertex 321.596 137.205 292.867 + endloop + endfacet + facet normal -0.516889 -0.0762762 -0.852648 + outer loop + vertex 320.336 131.141 294.174 + vertex 319.397 135.44 294.358 + vertex 321.596 137.205 292.867 + endloop + endfacet + facet normal -0.522417 -0.0839297 -0.84855 + outer loop + vertex 320.992 127.426 294.137 + vertex 320.336 131.141 294.174 + vertex 322.761 129.232 292.869 + endloop + endfacet + facet normal -0.532682 -0.0702539 -0.843395 + outer loop + vertex 321.399 123.796 294.183 + vertex 320.992 127.426 294.137 + vertex 322.761 129.232 292.869 + endloop + endfacet + facet normal -0.513496 -0.0737992 -0.854912 + outer loop + vertex 321.763 119.024 294.376 + vertex 321.399 123.796 294.183 + vertex 323.901 121.175 292.906 + endloop + endfacet + facet normal -0.505361 -0.0845177 -0.858759 + outer loop + vertex 322.941 115.734 294.006 + vertex 321.763 119.024 294.376 + vertex 323.901 121.175 292.906 + endloop + endfacet + facet normal -0.510376 -0.0673412 -0.857311 + outer loop + vertex 322.774 112.18 294.385 + vertex 322.941 115.734 294.006 + vertex 324.943 112.608 293.06 + endloop + endfacet + facet normal -0.507441 -0.0832803 -0.857653 + outer loop + vertex 323.399 109.85 294.241 + vertex 322.774 112.18 294.385 + vertex 324.943 112.608 293.06 + endloop + endfacet + facet normal -0.522332 -0.071554 -0.849735 + outer loop + vertex 323.866 106.57 294.23 + vertex 323.399 109.85 294.241 + vertex 324.943 112.608 293.06 + endloop + endfacet + facet normal -0.494367 -0.077521 -0.86579 + outer loop + vertex 324.337 101.798 294.389 + vertex 323.866 106.57 294.23 + vertex 326.59 104.019 292.903 + endloop + endfacet + facet normal -0.477529 -0.0994073 -0.872974 + outer loop + vertex 325.778 98.2431 294.005 + vertex 324.337 101.798 294.389 + vertex 326.59 104.019 292.903 + endloop + endfacet + facet normal -0.458896 -0.100702 -0.882765 + outer loop + vertex 325.814 94.2699 294.44 + vertex 325.778 98.2431 294.005 + vertex 328.62 94.0852 293.002 + endloop + endfacet + facet normal -0.458819 -0.135354 -0.87816 + outer loop + vertex 326.933 90.7438 294.399 + vertex 325.814 94.2699 294.44 + vertex 328.62 94.0852 293.002 + endloop + endfacet + facet normal -0.417928 -0.15131 -0.895791 + outer loop + vertex 326.852 87.273 295.023 + vertex 326.933 90.7438 294.399 + vertex 328.616 87.424 294.174 + endloop + endfacet + facet normal -0.413126 -0.184686 -0.89175 + outer loop + vertex 328.667 82.5365 295.163 + vertex 326.852 87.273 295.023 + vertex 328.616 87.424 294.174 + endloop + endfacet + facet normal -0.44181 -0.252222 -0.860923 + outer loop + vertex 330.819 76.7 295.768 + vertex 328.667 82.5365 295.163 + vertex 331.19 79.9172 294.636 + endloop + endfacet + facet normal -0.392642 -0.317961 -0.862979 + outer loop + vertex 332.922 73.2514 296.082 + vertex 330.819 76.7 295.768 + vertex 332.889 75.8263 295.148 + endloop + endfacet + facet normal -0.340193 -0.378721 -0.86072 + outer loop + vertex 334.571 70.4797 296.65 + vertex 332.922 73.2514 296.082 + vertex 334.682 72.4943 295.72 + endloop + endfacet + facet normal -0.298804 -0.435747 -0.849024 + outer loop + vertex 336.417 67.8356 297.357 + vertex 334.571 70.4797 296.65 + vertex 336.581 69.5842 296.402 + endloop + endfacet + facet normal -0.264264 -0.484727 -0.833789 + outer loop + vertex 338.515 65.1299 298.265 + vertex 336.417 67.8356 297.357 + vertex 338.689 66.8904 297.187 + endloop + endfacet + facet normal -0.224089 -0.545685 -0.807472 + outer loop + vertex 341.232 62.656 299.183 + vertex 338.515 65.1299 298.265 + vertex 341.036 64.399 298.06 + endloop + endfacet + facet normal -0.170493 -0.604957 -0.777791 + outer loop + vertex 343.805 60.6742 300.161 + vertex 341.232 62.656 299.183 + vertex 343.596 62.2235 299.001 + endloop + endfacet + facet normal -0.117782 -0.650957 -0.749922 + outer loop + vertex 346.376 58.9249 301.275 + vertex 343.805 60.6742 300.161 + vertex 346.448 60.2995 300.071 + endloop + endfacet + facet normal -0.0715229 -0.671597 -0.737457 + outer loop + vertex 347.908 57.2358 302.665 + vertex 346.376 58.9249 301.275 + vertex 349.943 58.3539 301.449 + endloop + endfacet + facet normal -0.0421333 -0.699215 -0.713669 + outer loop + vertex 351.483 56.3364 303.335 + vertex 347.908 57.2358 302.665 + vertex 349.943 58.3539 301.449 + endloop + endfacet + facet normal 0.212319 -0.975431 -0.058781 + outer loop + vertex 478.587 70.4604 302.358 + vertex 483.752 71.4713 304.24 + vertex 480.343 70.7609 303.716 + endloop + endfacet + facet normal 0.17907 -0.979078 -0.0966477 + outer loop + vertex 466.812 68.5048 298.237 + vertex 470.393 69.0387 299.464 + vertex 465.943 68.3293 298.405 + endloop + endfacet + facet normal 0.173851 -0.977215 -0.121767 + outer loop + vertex 462.61 67.9166 296.959 + vertex 466.812 68.5048 298.237 + vertex 465.943 68.3293 298.405 + endloop + endfacet + facet normal 0.16094 -0.978114 -0.131873 + outer loop + vertex 458.687 67.443 295.684 + vertex 462.61 67.9166 296.959 + vertex 458.064 67.3114 295.9 + endloop + endfacet + facet normal 0.155873 -0.976965 -0.145753 + outer loop + vertex 454.18 66.9131 294.416 + vertex 458.687 67.443 295.684 + vertex 458.064 67.3114 295.9 + endloop + endfacet + facet normal 0.13175 -0.984701 -0.114039 + outer loop + vertex 450.461 66.5549 293.211 + vertex 454.18 66.9131 294.416 + vertex 449.609 66.4101 293.478 + endloop + endfacet + facet normal 0.128097 -0.983822 -0.12524 + outer loop + vertex 447.473 66.2758 292.349 + vertex 450.461 66.5549 293.211 + vertex 449.609 66.4101 293.478 + endloop + endfacet + facet normal 0.0828576 -0.995827 -0.0382631 + outer loop + vertex 443.826 66.0138 291.267 + vertex 447.473 66.2758 292.349 + vertex 449.609 66.4101 293.478 + endloop + endfacet + facet normal 0.115866 -0.980469 -0.15892 + outer loop + vertex 440.061 65.7517 290.14 + vertex 443.826 66.0138 291.267 + vertex 441.436 65.7369 291.233 + endloop + endfacet + facet normal 0.0893494 -0.988039 -0.12568 + outer loop + vertex 437.291 65.5956 289.398 + vertex 440.061 65.7517 290.14 + vertex 441.436 65.7369 291.233 + endloop + endfacet + facet normal 0.0916198 -0.978938 -0.182447 + outer loop + vertex 433.568 65.4612 288.25 + vertex 437.291 65.5956 289.398 + vertex 433.739 65.33 289.039 + endloop + endfacet + facet normal 0.0804263 -0.980326 -0.180259 + outer loop + vertex 429.43 65.3062 287.246 + vertex 433.568 65.4612 288.25 + vertex 433.739 65.33 289.039 + endloop + endfacet + facet normal 0.0717177 -0.976927 -0.201174 + outer loop + vertex 425.232 65.2431 286.056 + vertex 429.43 65.3062 287.246 + vertex 425.583 65.111 286.822 + endloop + endfacet + facet normal 0.0610261 -0.978588 -0.196572 + outer loop + vertex 421.377 65.1803 285.171 + vertex 425.232 65.2431 286.056 + vertex 425.583 65.111 286.822 + endloop + endfacet + facet normal 0.0345118 -0.991566 -0.12492 + outer loop + vertex 418.74 65.1788 284.455 + vertex 421.377 65.1803 285.171 + vertex 417.277 65.1147 284.56 + endloop + endfacet + facet normal 0.0296968 -0.982038 -0.186331 + outer loop + vertex 416.319 65.2296 283.802 + vertex 418.74 65.1788 284.455 + vertex 417.277 65.1147 284.56 + endloop + endfacet + facet normal 0.022061 -0.983967 -0.17698 + outer loop + vertex 412.701 65.2995 282.961 + vertex 416.319 65.2296 283.802 + vertex 417.277 65.1147 284.56 + endloop + endfacet + facet normal 0.00248398 -0.978139 -0.207936 + outer loop + vertex 408.583 65.5342 281.809 + vertex 412.701 65.2995 282.961 + vertex 408.976 65.3948 282.469 + endloop + endfacet + facet normal -0.0271842 -0.981226 -0.190934 + outer loop + vertex 404.326 65.8406 280.84 + vertex 408.583 65.5342 281.809 + vertex 408.976 65.3948 282.469 + endloop + endfacet + facet normal -0.0394302 -0.952896 -0.300724 + outer loop + vertex 398.211 66.5739 279.318 + vertex 404.326 65.8406 280.84 + vertex 401.085 66.0571 280.579 + endloop + endfacet + facet normal -0.113165 -0.986225 -0.120643 + outer loop + vertex 393.016 67.3204 278.089 + vertex 398.211 66.5739 279.318 + vertex 392.199 67.3937 278.256 + endloop + endfacet + facet normal -0.132657 -0.965159 -0.225546 + outer loop + vertex 387.596 68.3601 276.828 + vertex 393.016 67.3204 278.089 + vertex 392.199 67.3937 278.256 + endloop + endfacet + facet normal 0.310625 0.735276 -0.602396 + outer loop + vertex 382.747 69.4871 275.703 + vertex 387.596 68.3601 276.828 + vertex 384.152 69.1297 275.991 + endloop + endfacet + facet normal 0.297826 0.954594 0.00702545 + outer loop + vertex 378.839 70.7131 274.813 + vertex 382.747 69.4871 275.703 + vertex 381.349 69.9261 275.341 + endloop + endfacet + facet normal 0.407034 0.781353 -0.473086 + outer loop + vertex 374.726 72.3026 273.9 + vertex 378.839 70.7131 274.813 + vertex 377.321 71.2837 274.45 + endloop + endfacet + facet normal 0.265606 0.121935 -0.95634 + outer loop + vertex 370.798 74.2155 273.053 + vertex 374.726 72.3026 273.9 + vertex 373.28 72.9699 273.583 + endloop + endfacet + facet normal 0.228169 0.0410146 -0.972757 + outer loop + vertex 367.2 76.4644 272.303 + vertex 370.798 74.2155 273.053 + vertex 369.538 74.9624 272.789 + endloop + endfacet + facet normal 0.460736 0.380318 -0.801923 + outer loop + vertex 363.919 79.0356 271.638 + vertex 367.2 76.4644 272.303 + vertex 366.15 77.262 272.079 + endloop + endfacet + facet normal 0.686766 0.726173 -0.0320354 + outer loop + vertex 361.409 81.3871 271.134 + vertex 363.919 79.0356 271.638 + vertex 363.128 79.7756 271.46 + endloop + endfacet + facet normal 0.741966 0.651874 0.156672 + outer loop + vertex 359.314 83.865 270.745 + vertex 361.409 81.3871 271.134 + vertex 360.477 82.494 270.942 + endloop + endfacet + facet normal 0.671118 0.389542 -0.63076 + outer loop + vertex 357.005 87.1761 270.332 + vertex 359.314 83.865 270.745 + vertex 358.014 85.6985 270.494 + endloop + endfacet + facet normal -0.0843436 0.0443213 0.995451 + outer loop + vertex 355.295 90.153 270.055 + vertex 357.005 87.1761 270.332 + vertex 355.56 89.7963 270.093 + endloop + endfacet + facet normal -0.143782 -0.00038352 0.989609 + outer loop + vertex 353.896 93.1716 269.853 + vertex 355.295 90.153 270.055 + vertex 355.56 89.7963 270.093 + endloop + endfacet + facet normal 0.170443 0.123586 0.977587 + outer loop + vertex 352.7 96.1352 269.686 + vertex 353.896 93.1716 269.853 + vertex 353.678 93.7662 269.815 + endloop + endfacet + facet normal 0.771902 0.286591 0.56748 + outer loop + vertex 351.768 98.8759 269.571 + vertex 352.7 96.1352 269.686 + vertex 352.361 97.179 269.621 + endloop + endfacet + facet normal 0.890671 0.268375 0.366989 + outer loop + vertex 350.862 102.001 269.484 + vertex 351.768 98.8759 269.571 + vertex 351.434 100.088 269.495 + endloop + endfacet + facet normal -0.367595 -0.0852244 0.926073 + outer loop + vertex 349.974 105.646 269.467 + vertex 350.862 102.001 269.484 + vertex 350.765 102.651 269.505 + endloop + endfacet + facet normal -0.112563 -0.604953 -0.788265 + outer loop + vertex 343.596 62.2235 299.001 + vertex 346.448 60.2995 300.071 + vertex 343.805 60.6742 300.161 + endloop + endfacet + facet normal -0.0682257 -0.655476 -0.752128 + outer loop + vertex 346.448 60.2995 300.071 + vertex 349.943 58.3539 301.449 + vertex 346.376 58.9249 301.275 + endloop + endfacet + facet normal -0.0579986 -0.730417 -0.680535 + outer loop + vertex 349.943 58.3539 301.449 + vertex 352.061 59.1922 300.369 + vertex 355.169 57.251 302.188 + endloop + endfacet + facet normal -0.212294 -0.495172 -0.842458 + outer loop + vertex 338.689 66.8904 297.187 + vertex 341.036 64.399 298.06 + vertex 338.515 65.1299 298.265 + endloop + endfacet + facet normal -0.163272 -0.547409 -0.820783 + outer loop + vertex 341.036 64.399 298.06 + vertex 343.596 62.2235 299.001 + vertex 341.232 62.656 299.183 + endloop + endfacet + facet normal -0.281623 -0.389445 -0.876939 + outer loop + vertex 334.682 72.4943 295.72 + vertex 336.581 69.5842 296.402 + vertex 334.571 70.4797 296.65 + endloop + endfacet + facet normal -0.250072 -0.445985 -0.859396 + outer loop + vertex 336.581 69.5842 296.402 + vertex 338.689 66.8904 297.187 + vertex 336.417 67.8356 297.357 + endloop + endfacet + facet normal -0.378531 -0.26829 -0.885852 + outer loop + vertex 331.19 79.9172 294.636 + vertex 332.889 75.8263 295.148 + vertex 330.819 76.7 295.768 + endloop + endfacet + facet normal -0.323299 -0.326257 -0.888276 + outer loop + vertex 332.889 75.8263 295.148 + vertex 334.682 72.4943 295.72 + vertex 332.922 73.2514 296.082 + endloop + endfacet + facet normal -0.46496 -0.153145 -0.871986 + outer loop + vertex 330.038 87.1117 293.471 + vertex 328.616 87.424 294.174 + vertex 328.62 94.0852 293.002 + endloop + endfacet + facet normal -0.452192 -0.181357 -0.873288 + outer loop + vertex 328.616 87.424 294.174 + vertex 330.052 83.7792 294.188 + vertex 328.667 82.5365 295.163 + endloop + endfacet + facet normal -0.417751 -0.225171 -0.880217 + outer loop + vertex 330.052 83.7792 294.188 + vertex 331.19 79.9172 294.636 + vertex 328.667 82.5365 295.163 + endloop + endfacet + facet normal -0.461822 -0.103138 -0.880956 + outer loop + vertex 326.59 104.019 292.903 + vertex 328.62 94.0852 293.002 + vertex 325.778 98.2431 294.005 + endloop + endfacet + facet normal -0.495586 -0.0792673 -0.864934 + outer loop + vertex 324.943 112.608 293.06 + vertex 326.59 104.019 292.903 + vertex 323.866 106.57 294.23 + endloop + endfacet + facet normal -0.524173 -0.0790118 -0.847939 + outer loop + vertex 323.901 121.175 292.906 + vertex 324.943 112.608 293.06 + vertex 322.941 115.734 294.006 + endloop + endfacet + facet normal -0.515839 -0.0768534 -0.853231 + outer loop + vertex 322.761 129.232 292.869 + vertex 323.901 121.175 292.906 + vertex 321.399 123.796 294.183 + endloop + endfacet + facet normal -0.517974 -0.0759155 -0.852021 + outer loop + vertex 321.596 137.205 292.867 + vertex 322.761 129.232 292.869 + vertex 320.336 131.141 294.174 + endloop + endfacet + facet normal -0.535292 -0.0790993 -0.840955 + outer loop + vertex 320.346 145.363 292.895 + vertex 321.596 137.205 292.867 + vertex 319.554 139.464 293.955 + endloop + endfacet + facet normal -0.519434 -0.0773567 -0.851002 + outer loop + vertex 318.755 153.908 293.09 + vertex 320.346 145.363 292.895 + vertex 317.876 147.627 294.197 + endloop + endfacet + facet normal -0.493598 -0.0661291 -0.867172 + outer loop + vertex 317.541 162.536 293.123 + vertex 318.755 153.908 293.09 + vertex 316.605 157.125 294.068 + endloop + endfacet + facet normal -0.476439 0.00327591 -0.879201 + outer loop + vertex 317.217 169.899 293.326 + vertex 317.541 162.536 293.123 + vertex 314.87 164.527 294.578 + endloop + endfacet + facet normal -0.101913 -0.927132 -0.36061 + outer loop + vertex 389.114 66.3852 281.595 + vertex 382.669 68.0699 279.085 + vertex 384.221 68.3343 277.966 + endloop + endfacet + facet normal -0.105127 -0.918072 -0.382221 + outer loop + vertex 384.221 68.3343 277.966 + vertex 384.019 68.8739 276.726 + vertex 388.809 67.6083 278.448 + endloop + endfacet + facet normal 0.207934 -0.977768 -0.0270753 + outer loop + vertex 484.782 71.6547 305.526 + vertex 480.343 70.7609 303.716 + vertex 483.752 71.4713 304.24 + endloop + endfacet + facet normal 0.16013 -0.987026 -0.0117322 + outer loop + vertex 473.789 69.5704 301.086 + vertex 465.943 68.3293 298.405 + vertex 470.393 69.0387 299.464 + endloop + endfacet + facet normal 0.142279 -0.988771 -0.0456907 + outer loop + vertex 465.943 68.3293 298.405 + vertex 458.064 67.3114 295.9 + vertex 462.61 67.9166 296.959 + endloop + endfacet + facet normal 0.117801 -0.992146 -0.0420596 + outer loop + vertex 458.064 67.3114 295.9 + vertex 449.609 66.4101 293.478 + vertex 454.18 66.9131 294.416 + endloop + endfacet + facet normal 0.115954 -0.985134 -0.126754 + outer loop + vertex 449.609 66.4101 293.478 + vertex 441.436 65.7369 291.233 + vertex 443.826 66.0138 291.267 + endloop + endfacet + facet normal 0.0858559 -0.989332 -0.117692 + outer loop + vertex 441.436 65.7369 291.233 + vertex 433.739 65.33 289.039 + vertex 437.291 65.5956 289.398 + endloop + endfacet + facet normal 0.0661365 -0.987097 -0.145828 + outer loop + vertex 433.739 65.33 289.039 + vertex 425.583 65.111 286.822 + vertex 429.43 65.3062 287.246 + endloop + endfacet + facet normal 0.0355946 -0.990572 -0.132286 + outer loop + vertex 425.583 65.111 286.822 + vertex 417.277 65.1147 284.56 + vertex 421.377 65.1803 285.171 + endloop + endfacet + facet normal -0.0164991 -0.997539 -0.0681505 + outer loop + vertex 417.277 65.1147 284.56 + vertex 408.976 65.3948 282.469 + vertex 412.701 65.2995 282.961 + endloop + endfacet + facet normal -0.0576969 -0.992589 -0.106953 + outer loop + vertex 408.976 65.3948 282.469 + vertex 401.085 66.0571 280.579 + vertex 404.326 65.8406 280.84 + endloop + endfacet + facet normal -0.105027 -0.981067 -0.162715 + outer loop + vertex 401.085 66.0571 280.579 + vertex 392.199 67.3937 278.256 + vertex 398.211 66.5739 279.318 + endloop + endfacet + facet normal -0.272463 -0.929264 0.249463 + outer loop + vertex 392.199 67.3937 278.256 + vertex 385.295 68.8943 276.305 + vertex 387.596 68.3601 276.828 + endloop + endfacet + facet normal -0.781821 -0.198964 0.590905 + outer loop + vertex 350.765 102.651 269.505 + vertex 349.163 109.205 269.593 + vertex 349.974 105.646 269.467 + endloop + endfacet + facet normal -0.906022 -0.180747 -0.382694 + outer loop + vertex 349.163 109.205 269.593 + vertex 347.429 117.786 269.645 + vertex 348.334 113.669 269.448 + endloop + endfacet + facet normal -0.0601364 0.416931 0.906947 + outer loop + vertex 381.349 69.9261 275.341 + vertex 377.321 71.2837 274.45 + vertex 378.839 70.7131 274.813 + endloop + endfacet + facet normal -0.299025 -0.833905 0.463883 + outer loop + vertex 385.295 68.8943 276.305 + vertex 384.152 69.1297 275.991 + vertex 387.596 68.3601 276.828 + endloop + endfacet + facet normal 0.0184309 0.670541 0.741643 + outer loop + vertex 384.152 69.1297 275.991 + vertex 381.349 69.9261 275.341 + vertex 382.747 69.4871 275.703 + endloop + endfacet + facet normal -0.23019 -0.04465 0.972121 + outer loop + vertex 373.28 72.9699 273.583 + vertex 369.538 74.9624 272.789 + vertex 370.798 74.2155 273.053 + endloop + endfacet + facet normal -0.169643 0.0974771 0.980673 + outer loop + vertex 377.321 71.2837 274.45 + vertex 373.28 72.9699 273.583 + vertex 374.726 72.3026 273.9 + endloop + endfacet + facet normal -0.040178 0.193134 0.980349 + outer loop + vertex 366.15 77.262 272.079 + vertex 363.128 79.7756 271.46 + vertex 363.919 79.0356 271.638 + endloop + endfacet + facet normal -0.169201 0.0544576 0.984076 + outer loop + vertex 369.538 74.9624 272.789 + vertex 366.15 77.262 272.079 + vertex 367.2 76.4644 272.303 + endloop + endfacet + facet normal -0.0474952 0.102329 0.993616 + outer loop + vertex 360.477 82.494 270.942 + vertex 358.014 85.6985 270.494 + vertex 359.314 83.865 270.745 + endloop + endfacet + facet normal -0.122237 0.0695578 0.990061 + outer loop + vertex 363.128 79.7756 271.46 + vertex 360.477 82.494 270.942 + vertex 361.409 81.3871 271.134 + endloop + endfacet + facet normal -0.0687579 0.0371234 0.996942 + outer loop + vertex 355.56 89.7963 270.093 + vertex 353.678 93.7662 269.815 + vertex 353.896 93.1716 269.853 + endloop + endfacet + facet normal -0.136282 0.0152347 0.990553 + outer loop + vertex 358.014 85.6985 270.494 + vertex 355.56 89.7963 270.093 + vertex 357.005 87.1761 270.332 + endloop + endfacet + facet normal 0.400908 0.166735 0.900817 + outer loop + vertex 352.361 97.179 269.621 + vertex 351.434 100.088 269.495 + vertex 351.768 98.8759 269.571 + endloop + endfacet + facet normal 0.0958479 0.093536 0.990992 + outer loop + vertex 353.678 93.7662 269.815 + vertex 352.361 97.179 269.621 + vertex 352.7 96.1352 269.686 + endloop + endfacet + facet normal -0.42729 -0.156416 -0.890482 + outer loop + vertex 326.933 90.7438 294.399 + vertex 328.62 94.0852 293.002 + vertex 328.616 87.424 294.174 + endloop + endfacet + facet normal -0.0474659 -0.701174 -0.711409 + outer loop + vertex 351.483 56.3364 303.335 + vertex 349.943 58.3539 301.449 + vertex 355.169 57.251 302.188 + endloop + endfacet + facet normal -0.110303 -0.929932 -0.350799 + outer loop + vertex 389.114 66.3852 281.595 + vertex 384.221 68.3343 277.966 + vertex 388.809 67.6083 278.448 + endloop + endfacet + facet normal 0.174941 -0.979613 -0.0987574 + outer loop + vertex 470.19 69.2384 297.613 + vertex 471.827 69.3571 299.334 + vertex 464.621 68.2979 297.076 + endloop + endfacet + facet normal 0.155085 -0.981463 -0.112598 + outer loop + vertex 464.621 68.2979 297.076 + vertex 455.419 67.1748 294.191 + vertex 461.482 68.058 294.844 + endloop + endfacet + facet normal 0.135495 -0.981053 -0.138481 + outer loop + vertex 455.419 67.1748 294.191 + vertex 447.183 66.3833 291.74 + vertex 452.749 67.0778 292.266 + endloop + endfacet + facet normal 0.116303 -0.977839 -0.174083 + outer loop + vertex 447.183 66.3833 291.74 + vertex 438.661 65.7908 289.374 + vertex 443.462 66.3113 289.658 + endloop + endfacet + facet normal -0.35671 -0.906879 0.224339 + outer loop + vertex 453.237 80.9705 65.3292 + vertex 452.705 80.4411 62.3429 + vertex 455.466 79.7356 63.8819 + endloop + endfacet + facet normal -0.358075 -0.905582 0.227383 + outer loop + vertex 452.705 80.4411 62.3429 + vertex 457.449 77.9273 59.8025 + vertex 455.466 79.7356 63.8819 + endloop + endfacet + facet normal -0.338575 -0.937253 0.0832107 + outer loop + vertex 455.301 82.9327 80.3888 + vertex 459.066 81.5033 79.6088 + vertex 455.76 83.346 86.91 + endloop + endfacet + facet normal -0.401922 -0.886626 0.228808 + outer loop + vertex 453.237 80.9705 65.3292 + vertex 450.896 82.1397 65.7473 + vertex 452.705 80.4411 62.3429 + endloop + endfacet + facet normal -0.450367 -0.868426 0.20738 + outer loop + vertex 448.765 83.5585 67.0619 + vertex 447.988 83.2061 63.8988 + vertex 450.896 82.1397 65.7473 + endloop + endfacet + facet normal -0.446181 -0.872688 0.198337 + outer loop + vertex 447.988 83.2061 63.8988 + vertex 452.705 80.4411 62.3429 + vertex 450.896 82.1397 65.7473 + endloop + endfacet + facet normal -0.402052 -0.903253 0.149961 + outer loop + vertex 451.306 83.4295 72.5493 + vertex 453.52 82.3557 72.0173 + vertex 451 84.6094 78.835 + endloop + endfacet + facet normal -0.379138 -0.921422 0.0850597 + outer loop + vertex 455.76 83.346 86.91 + vertex 450.959 85.3817 87.5641 + vertex 455.301 82.9327 80.3888 + endloop + endfacet + facet normal -0.386833 -0.918718 0.0794801 + outer loop + vertex 455.301 82.9327 80.3888 + vertex 450.959 85.3817 87.5641 + vertex 451 84.6094 78.835 + endloop + endfacet + facet normal -0.354209 -0.933598 0.0541311 + outer loop + vertex 456.06 83.6434 94.0073 + vertex 450.856 85.6795 95.0682 + vertex 455.76 83.346 86.91 + endloop + endfacet + facet normal -0.386593 -0.92172 0.0312679 + outer loop + vertex 455.76 83.346 86.91 + vertex 450.856 85.6795 95.0682 + vertex 450.959 85.3817 87.5641 + endloop + endfacet + facet normal -0.326991 -0.944552 0.0299906 + outer loop + vertex 455.81 83.9798 101.866 + vertex 450.394 85.8783 102.608 + vertex 456.06 83.6434 94.0073 + endloop + endfacet + facet normal -0.363936 -0.931421 0.00223524 + outer loop + vertex 456.06 83.6434 94.0073 + vertex 450.394 85.8783 102.608 + vertex 450.856 85.6795 95.0682 + endloop + endfacet + facet normal -0.301028 -0.953593 0.00655519 + outer loop + vertex 455.047 84.2757 109.91 + vertex 449.503 86.0298 110.451 + vertex 455.81 83.9798 101.866 + endloop + endfacet + facet normal -0.333127 -0.942677 -0.0196354 + outer loop + vertex 455.81 83.9798 101.866 + vertex 449.503 86.0298 110.451 + vertex 450.394 85.8783 102.608 + endloop + endfacet + facet normal -0.27702 -0.960768 -0.0135733 + outer loop + vertex 453.904 84.4912 117.996 + vertex 448.264 86.1106 118.478 + vertex 455.047 84.2757 109.91 + endloop + endfacet + facet normal -0.304724 -0.951704 -0.0374478 + outer loop + vertex 455.047 84.2757 109.91 + vertex 448.264 86.1106 118.478 + vertex 449.503 86.0298 110.451 + endloop + endfacet + facet normal -0.254828 -0.966558 -0.0287879 + outer loop + vertex 452.531 84.611 126.123 + vertex 446.797 86.1107 126.526 + vertex 453.904 84.4912 117.996 + endloop + endfacet + facet normal -0.279634 -0.958755 -0.0509346 + outer loop + vertex 453.904 84.4912 117.996 + vertex 446.797 86.1107 126.526 + vertex 448.264 86.1106 118.478 + endloop + endfacet + facet normal -0.232343 -0.971848 -0.0391054 + outer loop + vertex 451.003 84.6473 134.302 + vertex 445.174 86.0299 134.573 + vertex 452.531 84.611 126.123 + endloop + endfacet + facet normal -0.256604 -0.964561 -0.0614538 + outer loop + vertex 452.531 84.611 126.123 + vertex 445.174 86.0299 134.573 + vertex 446.797 86.1107 126.526 + endloop + endfacet + facet normal -0.211343 -0.97619 -0.0488651 + outer loop + vertex 449.359 84.59 142.554 + vertex 443.395 85.8747 142.685 + vertex 451.003 84.6473 134.302 + endloop + endfacet + facet normal -0.233302 -0.969902 -0.0697156 + outer loop + vertex 451.003 84.6473 134.302 + vertex 443.395 85.8747 142.685 + vertex 445.174 86.0299 134.573 + endloop + endfacet + facet normal -0.191016 -0.979888 -0.0577267 + outer loop + vertex 447.591 84.4464 150.842 + vertex 441.46 85.6395 150.877 + vertex 449.359 84.59 142.554 + endloop + endfacet + facet normal -0.211563 -0.974252 -0.0779375 + outer loop + vertex 449.359 84.59 142.554 + vertex 441.46 85.6395 150.877 + vertex 443.395 85.8747 142.685 + endloop + endfacet + facet normal -0.172659 -0.982698 -0.067036 + outer loop + vertex 445.702 84.2126 159.136 + vertex 439.388 85.326 159.077 + vertex 447.591 84.4464 150.842 + endloop + endfacet + facet normal -0.190787 -0.977891 -0.085608 + outer loop + vertex 447.591 84.4464 150.842 + vertex 439.388 85.326 159.077 + vertex 441.46 85.6395 150.877 + endloop + endfacet + facet normal -0.156078 -0.984781 -0.0764532 + outer loop + vertex 443.705 83.8874 167.403 + vertex 437.197 84.9314 167.24 + vertex 445.702 84.2126 159.136 + endloop + endfacet + facet normal -0.172048 -0.980634 -0.0935806 + outer loop + vertex 445.702 84.2126 159.136 + vertex 437.197 84.9314 167.24 + vertex 439.388 85.326 159.077 + endloop + endfacet + facet normal -0.140958 -0.986235 -0.0864342 + outer loop + vertex 441.62 83.4656 175.614 + vertex 434.912 84.4478 175.347 + vertex 443.705 83.8874 167.403 + endloop + endfacet + facet normal -0.155078 -0.982589 -0.10232 + outer loop + vertex 443.705 83.8874 167.403 + vertex 434.912 84.4478 175.347 + vertex 437.197 84.9314 167.24 + endloop + endfacet + facet normal -0.12908 -0.98684 -0.0973963 + outer loop + vertex 439.468 82.9452 183.74 + vertex 432.541 83.8898 183.349 + vertex 441.62 83.4656 175.614 + endloop + endfacet + facet normal -0.139701 -0.984063 -0.110015 + outer loop + vertex 441.62 83.4656 175.614 + vertex 432.541 83.8898 183.349 + vertex 434.912 84.4478 175.347 + endloop + endfacet + facet normal -0.117571 -0.987124 -0.108457 + outer loop + vertex 437.257 82.3262 191.77 + vertex 430.111 83.2334 191.26 + vertex 439.468 82.9452 183.74 + endloop + endfacet + facet normal -0.127432 -0.98446 -0.120829 + outer loop + vertex 439.468 82.9452 183.74 + vertex 430.111 83.2334 191.26 + vertex 432.541 83.8898 183.349 + endloop + endfacet + facet normal -0.108767 -0.986668 -0.12106 + outer loop + vertex 434.999 81.6015 199.706 + vertex 427.619 82.4944 199.058 + vertex 437.257 82.3262 191.77 + endloop + endfacet + facet normal -0.115706 -0.984702 -0.130283 + outer loop + vertex 437.257 82.3262 191.77 + vertex 427.619 82.4944 199.058 + vertex 430.111 83.2334 191.26 + endloop + endfacet + facet normal -0.100441 -0.985808 -0.134518 + outer loop + vertex 432.705 80.765 207.549 + vertex 425.082 81.6489 206.763 + vertex 434.999 81.6015 199.706 + endloop + endfacet + facet normal -0.10651 -0.983966 -0.143058 + outer loop + vertex 434.999 81.6015 199.706 + vertex 425.082 81.6489 206.763 + vertex 427.619 82.4944 199.058 + endloop + endfacet + facet normal -0.093718 -0.984382 -0.149025 + outer loop + vertex 430.38 79.8155 215.283 + vertex 422.511 80.7084 214.334 + vertex 432.705 80.765 207.549 + endloop + endfacet + facet normal -0.0979612 -0.982984 -0.155389 + outer loop + vertex 432.705 80.765 207.549 + vertex 422.511 80.7084 214.334 + vertex 425.082 81.6489 206.763 + endloop + endfacet + facet normal -0.087663 -0.982552 -0.164032 + outer loop + vertex 428.015 78.7566 222.89 + vertex 419.905 79.669 221.758 + vertex 430.38 79.8155 215.283 + endloop + endfacet + facet normal -0.0909312 -0.981362 -0.169292 + outer loop + vertex 430.38 79.8155 215.283 + vertex 419.905 79.669 221.758 + vertex 422.511 80.7084 214.334 + endloop + endfacet + facet normal -0.0816169 -0.980431 -0.179149 + outer loop + vertex 425.611 77.5945 230.344 + vertex 417.25 78.5276 229.047 + vertex 428.015 78.7566 222.89 + endloop + endfacet + facet normal -0.0844901 -0.979264 -0.184128 + outer loop + vertex 428.015 78.7566 222.89 + vertex 417.25 78.5276 229.047 + vertex 419.905 79.669 221.758 + endloop + endfacet + facet normal -0.0761064 -0.977999 -0.194233 + outer loop + vertex 423.168 76.3403 237.617 + vertex 414.56 77.3057 236.128 + vertex 425.611 77.5945 230.344 + endloop + endfacet + facet normal -0.0782628 -0.977011 -0.198303 + outer loop + vertex 425.611 77.5945 230.344 + vertex 414.56 77.3057 236.128 + vertex 417.25 78.5276 229.047 + endloop + endfacet + facet normal -0.0716794 -0.975058 -0.210058 + outer loop + vertex 420.639 75.0012 244.696 + vertex 411.816 76.0198 242.978 + vertex 423.168 76.3403 237.617 + endloop + endfacet + facet normal -0.0726385 -0.974554 -0.212058 + outer loop + vertex 423.168 76.3403 237.617 + vertex 411.816 76.0198 242.978 + vertex 414.56 77.3057 236.128 + endloop + endfacet + facet normal -0.0671766 -0.971881 -0.225685 + outer loop + vertex 417.906 73.5997 251.544 + vertex 408.949 74.6589 249.649 + vertex 420.639 75.0012 244.696 + endloop + endfacet + facet normal -0.0678962 -0.971443 -0.227353 + outer loop + vertex 420.639 75.0012 244.696 + vertex 408.949 74.6589 249.649 + vertex 411.816 76.0198 242.978 + endloop + endfacet + facet normal -0.06426 -0.967626 -0.244073 + outer loop + vertex 414.902 72.1325 258.152 + vertex 405.89 73.2564 256.069 + vertex 417.906 73.5997 251.544 + endloop + endfacet + facet normal -0.063357 -0.968274 -0.241724 + outer loop + vertex 417.906 73.5997 251.544 + vertex 405.89 73.2564 256.069 + vertex 408.949 74.6589 249.649 + endloop + endfacet + facet normal -0.0616532 -0.962758 -0.263241 + outer loop + vertex 411.774 70.5914 264.521 + vertex 402.654 71.8139 262.186 + vertex 414.902 72.1325 258.152 + endloop + endfacet + facet normal -0.0602987 -0.963934 -0.25922 + outer loop + vertex 414.902 72.1325 258.152 + vertex 402.654 71.8139 262.186 + vertex 405.89 73.2564 256.069 + endloop + endfacet + facet normal -0.0567506 -0.958918 -0.277949 + outer loop + vertex 409.164 68.9998 270.545 + vertex 399.467 70.3018 268.033 + vertex 411.774 70.5914 264.521 + endloop + endfacet + facet normal -0.0570593 -0.958593 -0.279004 + outer loop + vertex 411.774 70.5914 264.521 + vertex 399.467 70.3018 268.033 + vertex 402.654 71.8139 262.186 + endloop + endfacet + facet normal -0.0466608 -0.959398 -0.278169 + outer loop + vertex 408.864 67.5224 275.691 + vertex 396.933 68.7154 273.577 + vertex 409.164 68.9998 270.545 + endloop + endfacet + facet normal -0.0512929 -0.953711 -0.29632 + outer loop + vertex 409.164 68.9998 270.545 + vertex 396.933 68.7154 273.577 + vertex 399.467 70.3018 268.033 + endloop + endfacet + facet normal -0.0511501 -0.952828 -0.29917 + outer loop + vertex 404.26 66.1627 280.175 + vertex 393.442 67.4959 277.778 + vertex 400.965 67.1479 277.601 + endloop + endfacet + facet normal -0.0515653 -0.933912 -0.353765 + outer loop + vertex 400.965 67.1479 277.601 + vertex 393.442 67.4959 277.778 + vertex 391.711 68.2037 276.162 + endloop + endfacet + facet normal -0.499608 -0.838844 0.21618 + outer loop + vertex 448.765 83.5585 67.0619 + vertex 446.732 84.9076 67.5973 + vertex 447.988 83.2061 63.8988 + endloop + endfacet + facet normal -0.518404 -0.845851 0.125669 + outer loop + vertex 446.515 86.5672 74.8217 + vertex 449.097 84.8758 74.0891 + vertex 447.283 86.698 78.8727 + endloop + endfacet + facet normal -0.487482 -0.868943 0.0854369 + outer loop + vertex 447.227 87.1285 82.9316 + vertex 447.283 86.698 78.8727 + vertex 451 84.6094 78.835 + endloop + endfacet + facet normal -0.471982 -0.87036 0.140378 + outer loop + vertex 451.306 83.4295 72.5493 + vertex 451 84.6094 78.835 + vertex 449.097 84.8758 74.0891 + endloop + endfacet + facet normal -0.483601 -0.86312 0.145442 + outer loop + vertex 447.283 86.698 78.8727 + vertex 449.097 84.8758 74.0891 + vertex 451 84.6094 78.835 + endloop + endfacet + facet normal -0.461482 -0.886517 0.0334887 + outer loop + vertex 447.271 87.424 90.8001 + vertex 447.789 86.988 86.406 + vertex 450.959 85.3817 87.5641 + endloop + endfacet + facet normal -0.517248 -0.854426 0.0491012 + outer loop + vertex 447.227 87.1285 82.9316 + vertex 451 84.6094 78.835 + vertex 447.789 86.988 86.406 + endloop + endfacet + facet normal -0.472544 -0.878069 0.0754846 + outer loop + vertex 451 84.6094 78.835 + vertex 450.959 85.3817 87.5641 + vertex 447.789 86.988 86.406 + endloop + endfacet + facet normal -0.436358 -0.899766 -0.00366167 + outer loop + vertex 446.91 87.58 98.2805 + vertex 447.623 87.2511 94.1744 + vertex 450.856 85.6795 95.0682 + endloop + endfacet + facet normal -0.480849 -0.876788 0.0052739 + outer loop + vertex 447.271 87.424 90.8001 + vertex 450.959 85.3817 87.5641 + vertex 447.623 87.2511 94.1744 + endloop + endfacet + facet normal -0.443565 -0.895758 0.0294552 + outer loop + vertex 450.959 85.3817 87.5641 + vertex 450.856 85.6795 95.0682 + vertex 447.623 87.2511 94.1744 + endloop + endfacet + facet normal -0.40948 -0.911858 -0.0289912 + outer loop + vertex 446.157 87.6815 105.732 + vertex 447.104 87.3877 101.594 + vertex 450.394 85.8783 102.608 + endloop + endfacet + facet normal -0.450536 -0.892396 -0.0254368 + outer loop + vertex 446.91 87.58 98.2805 + vertex 450.856 85.6795 95.0682 + vertex 447.104 87.3877 101.594 + endloop + endfacet + facet normal -0.416646 -0.909067 -0.00158686 + outer loop + vertex 450.856 85.6795 95.0682 + vertex 450.394 85.8783 102.608 + vertex 447.104 87.3877 101.594 + endloop + endfacet + facet normal -0.382296 -0.922613 -0.0513291 + outer loop + vertex 445.034 87.7095 113.539 + vertex 446.185 87.4733 109.212 + vertex 449.503 86.0298 110.451 + endloop + endfacet + facet normal -0.422541 -0.904924 -0.0507024 + outer loop + vertex 446.157 87.6815 105.732 + vertex 450.394 85.8783 102.608 + vertex 446.185 87.4733 109.212 + endloop + endfacet + facet normal -0.390494 -0.920222 -0.0265868 + outer loop + vertex 450.394 85.8783 102.608 + vertex 449.503 86.0298 110.451 + vertex 446.185 87.4733 109.212 + endloop + endfacet + facet normal -0.35643 -0.931892 -0.0673392 + outer loop + vertex 443.619 87.6614 121.603 + vertex 444.927 87.4807 117.182 + vertex 448.264 86.1106 118.478 + endloop + endfacet + facet normal -0.392588 -0.917106 -0.0692136 + outer loop + vertex 445.034 87.7095 113.539 + vertex 449.503 86.0298 110.451 + vertex 444.927 87.4807 117.182 + endloop + endfacet + facet normal -0.363772 -0.930313 -0.0467766 + outer loop + vertex 449.503 86.0298 110.451 + vertex 448.264 86.1106 118.478 + vertex 444.927 87.4807 117.182 + endloop + endfacet + facet normal -0.332925 -0.939591 -0.0795639 + outer loop + vertex 442.023 87.5415 129.608 + vertex 443.43 87.4131 125.237 + vertex 446.797 86.1107 126.526 + endloop + endfacet + facet normal -0.364998 -0.927361 -0.0823264 + outer loop + vertex 443.619 87.6614 121.603 + vertex 448.264 86.1106 118.478 + vertex 443.43 87.4131 125.237 + endloop + endfacet + facet normal -0.339348 -0.938628 -0.061812 + outer loop + vertex 448.264 86.1106 118.478 + vertex 446.797 86.1107 126.526 + vertex 443.43 87.4131 125.237 + endloop + endfacet + facet normal -0.310315 -0.9464 -0.0896134 + outer loop + vertex 440.274 87.3555 137.54 + vertex 441.775 87.2741 133.202 + vertex 445.174 86.0299 134.573 + endloop + endfacet + facet normal -0.340454 -0.935644 -0.0930626 + outer loop + vertex 442.023 87.5415 129.608 + vertex 446.797 86.1107 126.526 + vertex 441.775 87.2741 133.202 + endloop + endfacet + facet normal -0.316613 -0.945713 -0.0733722 + outer loop + vertex 446.797 86.1107 126.526 + vertex 445.174 86.0299 134.573 + vertex 441.775 87.2741 133.202 + endloop + endfacet + facet normal -0.286953 -0.952894 -0.0982425 + outer loop + vertex 438.342 87.0988 145.572 + vertex 439.956 87.0652 141.182 + vertex 443.395 85.8747 142.685 + endloop + endfacet + facet normal -0.317336 -0.942719 -0.102851 + outer loop + vertex 440.274 87.3555 137.54 + vertex 445.174 86.0299 134.573 + vertex 439.956 87.0652 141.182 + endloop + endfacet + facet normal -0.2936 -0.952353 -0.0826036 + outer loop + vertex 445.174 86.0299 134.573 + vertex 443.395 85.8747 142.685 + vertex 439.956 87.0652 141.182 + endloop + endfacet + facet normal -0.264299 -0.958698 -0.105089 + outer loop + vertex 436.22 86.7715 153.729 + vertex 437.948 86.7814 149.294 + vertex 441.46 85.6395 150.877 + endloop + endfacet + facet normal -0.293963 -0.949225 -0.112066 + outer loop + vertex 438.342 87.0988 145.572 + vertex 443.395 85.8747 142.685 + vertex 437.948 86.7814 149.294 + endloop + endfacet + facet normal -0.270388 -0.958405 -0.0913749 + outer loop + vertex 443.395 85.8747 142.685 + vertex 441.46 85.6395 150.877 + vertex 437.948 86.7814 149.294 + endloop + endfacet + facet normal -0.242955 -0.963392 -0.113354 + outer loop + vertex 433.965 86.3664 161.857 + vertex 435.778 86.4271 157.456 + vertex 439.388 85.326 159.077 + endloop + endfacet + facet normal -0.271828 -0.954774 -0.120482 + outer loop + vertex 436.22 86.7715 153.729 + vertex 441.46 85.6395 150.877 + vertex 435.778 86.4271 157.456 + endloop + endfacet + facet normal -0.249037 -0.963341 -0.0997708 + outer loop + vertex 441.46 85.6395 150.877 + vertex 439.388 85.326 159.077 + vertex 435.778 86.4271 157.456 + endloop + endfacet + facet normal -0.224112 -0.966911 -0.121893 + outer loop + vertex 431.59 85.8924 169.926 + vertex 433.485 86.0032 165.562 + vertex 437.197 84.9314 167.24 + endloop + endfacet + facet normal -0.249031 -0.960213 -0.126393 + outer loop + vertex 433.965 86.3664 161.857 + vertex 439.388 85.326 159.077 + vertex 433.485 86.0032 165.562 + endloop + endfacet + facet normal -0.230196 -0.967073 -0.108534 + outer loop + vertex 439.388 85.326 159.077 + vertex 437.197 84.9314 167.24 + vertex 433.485 86.0032 165.562 + endloop + endfacet + facet normal -0.207438 -0.969661 -0.129329 + outer loop + vertex 429.114 85.3446 177.922 + vertex 431.079 85.4987 173.615 + vertex 434.912 84.4478 175.347 + endloop + endfacet + facet normal -0.229707 -0.9639 -0.134653 + outer loop + vertex 431.59 85.8924 169.926 + vertex 437.197 84.9314 167.24 + vertex 431.079 85.4987 173.615 + endloop + endfacet + facet normal -0.212728 -0.969982 -0.117817 + outer loop + vertex 437.197 84.9314 167.24 + vertex 434.912 84.4478 175.347 + vertex 431.079 85.4987 173.615 + endloop + endfacet + facet normal -0.19133 -0.971808 -0.137777 + outer loop + vertex 426.564 84.7185 185.804 + vertex 428.589 84.9204 181.568 + vertex 432.541 83.8898 183.349 + endloop + endfacet + facet normal -0.213096 -0.966484 -0.143172 + outer loop + vertex 429.114 85.3446 177.922 + vertex 434.912 84.4478 175.347 + vertex 428.589 84.9204 181.568 + endloop + endfacet + facet normal -0.196728 -0.972316 -0.126093 + outer loop + vertex 434.912 84.4478 175.347 + vertex 432.541 83.8898 183.349 + vertex 428.589 84.9204 181.568 + endloop + endfacet + facet normal -0.178634 -0.973002 -0.146141 + outer loop + vertex 423.94 84.0172 193.585 + vertex 426.025 84.2603 189.417 + vertex 430.111 83.2334 191.26 + endloop + endfacet + facet normal -0.1968 -0.96856 -0.152189 + outer loop + vertex 426.564 84.7185 185.804 + vertex 432.541 83.8898 183.349 + vertex 426.025 84.2603 189.417 + endloop + endfacet + facet normal -0.182906 -0.973543 -0.136966 + outer loop + vertex 432.541 83.8898 183.349 + vertex 430.111 83.2334 191.26 + vertex 426.025 84.2603 189.417 + endloop + endfacet + facet normal -0.165976 -0.973581 -0.15682 + outer loop + vertex 421.263 83.2255 201.247 + vertex 423.398 83.5206 197.155 + vertex 427.619 82.4944 199.058 + endloop + endfacet + facet normal -0.184435 -0.969268 -0.1628 + outer loop + vertex 423.94 84.0172 193.585 + vertex 430.111 83.2334 191.26 + vertex 423.398 83.5206 197.155 + endloop + endfacet + facet normal -0.170649 -0.974327 -0.146855 + outer loop + vertex 430.111 83.2334 191.26 + vertex 427.619 82.4944 199.058 + vertex 423.398 83.5206 197.155 + endloop + endfacet + facet normal -0.156499 -0.973268 -0.1681 + outer loop + vertex 418.523 82.3493 208.814 + vertex 420.712 82.6931 204.785 + vertex 425.082 81.6489 206.763 + endloop + endfacet + facet normal -0.170992 -0.970043 -0.172566 + outer loop + vertex 421.263 83.2255 201.247 + vertex 427.619 82.4944 199.058 + vertex 420.712 82.6931 204.785 + endloop + endfacet + facet normal -0.160466 -0.974031 -0.159734 + outer loop + vertex 427.619 82.4944 199.058 + vertex 425.082 81.6489 206.763 + vertex 420.712 82.6931 204.785 + endloop + endfacet + facet normal -0.146983 -0.972487 -0.180735 + outer loop + vertex 415.759 81.3781 216.221 + vertex 417.981 81.7701 212.304 + vertex 422.511 80.7084 214.334 + endloop + endfacet + facet normal -0.161637 -0.969178 -0.185925 + outer loop + vertex 418.523 82.3493 208.814 + vertex 425.082 81.6489 206.763 + vertex 417.981 81.7701 212.304 + endloop + endfacet + facet normal -0.151015 -0.973414 -0.172221 + outer loop + vertex 425.082 81.6489 206.763 + vertex 422.511 80.7084 214.334 + vertex 417.981 81.7701 212.304 + endloop + endfacet + facet normal -0.13826 -0.971281 -0.193641 + outer loop + vertex 412.969 80.3188 223.451 + vertex 415.234 80.7567 219.637 + vertex 419.905 79.669 221.758 + endloop + endfacet + facet normal -0.15176 -0.968099 -0.199384 + outer loop + vertex 415.759 81.3781 216.221 + vertex 422.511 80.7084 214.334 + vertex 415.234 80.7567 219.637 + endloop + endfacet + facet normal -0.141985 -0.972249 -0.185935 + outer loop + vertex 422.511 80.7084 214.334 + vertex 419.905 79.669 221.758 + vertex 415.234 80.7567 219.637 + endloop + endfacet + facet normal -0.130046 -0.969204 -0.209121 + outer loop + vertex 410.108 79.1566 230.573 + vertex 412.431 79.6509 226.838 + vertex 417.25 78.5276 229.047 + endloop + endfacet + facet normal -0.142607 -0.966528 -0.213275 + outer loop + vertex 412.969 80.3188 223.451 + vertex 419.905 79.669 221.758 + vertex 412.431 79.6509 226.838 + endloop + endfacet + facet normal -0.134131 -0.970402 -0.200819 + outer loop + vertex 419.905 79.669 221.758 + vertex 417.25 78.5276 229.047 + vertex 412.431 79.6509 226.838 + endloop + endfacet + facet normal -0.123333 -0.966986 -0.222993 + outer loop + vertex 407.222 77.9404 237.435 + vertex 409.577 78.4615 233.872 + vertex 414.56 77.3057 236.128 + endloop + endfacet + facet normal -0.133044 -0.965288 -0.224764 + outer loop + vertex 410.108 79.1566 230.573 + vertex 417.25 78.5276 229.047 + vertex 409.577 78.4615 233.872 + endloop + endfacet + facet normal -0.12709 -0.968235 -0.215336 + outer loop + vertex 417.25 78.5276 229.047 + vertex 414.56 77.3057 236.128 + vertex 409.577 78.4615 233.872 + endloop + endfacet + facet normal -0.117056 -0.964807 -0.235469 + outer loop + vertex 404.302 76.6756 244.027 + vertex 406.707 77.2167 240.614 + vertex 411.816 76.0198 242.978 + endloop + endfacet + facet normal -0.125911 -0.962681 -0.239565 + outer loop + vertex 407.222 77.9404 237.435 + vertex 414.56 77.3057 236.128 + vertex 406.707 77.2167 240.614 + endloop + endfacet + facet normal -0.120096 -0.965883 -0.229447 + outer loop + vertex 414.56 77.3057 236.128 + vertex 411.816 76.0198 242.978 + vertex 406.707 77.2167 240.614 + endloop + endfacet + facet normal -0.111183 -0.961715 -0.250483 + outer loop + vertex 401.25 75.3294 250.492 + vertex 403.749 75.9063 247.168 + vertex 408.949 74.6589 249.649 + endloop + endfacet + facet normal -0.119429 -0.959291 -0.255925 + outer loop + vertex 404.302 76.6756 244.027 + vertex 411.816 76.0198 242.978 + vertex 403.749 75.9063 247.168 + endloop + endfacet + facet normal -0.113882 -0.962726 -0.245337 + outer loop + vertex 411.816 76.0198 242.978 + vertex 408.949 74.6589 249.649 + vertex 403.749 75.9063 247.168 + endloop + endfacet + facet normal -0.106597 -0.958173 -0.265595 + outer loop + vertex 398.075 73.9477 256.712 + vertex 400.651 74.5346 253.56 + vertex 405.89 73.2564 256.069 + endloop + endfacet + facet normal -0.112821 -0.956298 -0.269752 + outer loop + vertex 401.25 75.3294 250.492 + vertex 408.949 74.6589 249.649 + vertex 400.651 74.5346 253.56 + endloop + endfacet + facet normal -0.108835 -0.959079 -0.261384 + outer loop + vertex 408.949 74.6589 249.649 + vertex 405.89 73.2564 256.069 + vertex 400.651 74.5346 253.56 + endloop + endfacet + facet normal -0.104367 -0.953205 -0.28374 + outer loop + vertex 394.772 72.5754 262.527 + vertex 397.426 73.1525 259.612 + vertex 402.654 71.8139 262.186 + endloop + endfacet + facet normal -0.1077 -0.952389 -0.28523 + outer loop + vertex 398.075 73.9477 256.712 + vertex 405.89 73.2564 256.069 + vertex 397.426 73.1525 259.612 + endloop + endfacet + facet normal -0.105898 -0.953856 -0.28097 + outer loop + vertex 405.89 73.2564 256.069 + vertex 402.654 71.8139 262.186 + vertex 397.426 73.1525 259.612 + endloop + endfacet + facet normal -0.100111 -0.947111 -0.30489 + outer loop + vertex 391.408 71.1526 268.036 + vertex 394.075 71.7509 265.302 + vertex 399.467 70.3018 268.033 + endloop + endfacet + facet normal -0.104674 -0.945834 -0.307313 + outer loop + vertex 394.772 72.5754 262.527 + vertex 402.654 71.8139 262.186 + vertex 394.075 71.7509 265.302 + endloop + endfacet + facet normal -0.102359 -0.948119 -0.300986 + outer loop + vertex 402.654 71.8139 262.186 + vertex 399.467 70.3018 268.033 + vertex 394.075 71.7509 265.302 + endloop + endfacet + facet normal -0.0914356 -0.943536 -0.318402 + outer loop + vertex 388.344 69.7726 272.911 + vertex 390.868 70.2803 270.682 + vertex 396.933 68.7154 273.577 + endloop + endfacet + facet normal -0.0992453 -0.938818 -0.329804 + outer loop + vertex 391.408 71.1526 268.036 + vertex 399.467 70.3018 268.033 + vertex 390.868 70.2803 270.682 + endloop + endfacet + facet normal -0.0941801 -0.944936 -0.313411 + outer loop + vertex 399.467 70.3018 268.033 + vertex 396.933 68.7154 273.577 + vertex 390.868 70.2803 270.682 + endloop + endfacet + facet normal -0.103386 -0.942754 -0.317059 + outer loop + vertex 385.626 68.8296 276.361 + vertex 386.378 68.7896 276.235 + vertex 393.442 67.4959 277.778 + endloop + endfacet + facet normal -0.107578 -0.938299 -0.328667 + outer loop + vertex 385.642 69.121 275.53 + vertex 391.711 68.2037 276.162 + vertex 386.378 68.7896 276.235 + endloop + endfacet + facet normal -0.108243 -0.948019 -0.299239 + outer loop + vertex 391.711 68.2037 276.162 + vertex 393.442 67.4959 277.778 + vertex 386.378 68.7896 276.235 + endloop + endfacet + facet normal -0.635935 -0.741534 0.213809 + outer loop + vertex 443.106 87.8712 69.098 + vertex 440.961 89.9024 69.7616 + vertex 442.565 87.6149 66.5984 + endloop + endfacet + facet normal -0.642135 -0.737836 0.207991 + outer loop + vertex 442.565 87.6149 66.5984 + vertex 440.961 89.9024 69.7616 + vertex 440.352 89.7457 67.3258 + endloop + endfacet + facet normal -0.59344 -0.781256 0.193565 + outer loop + vertex 444.857 86.5037 68.9447 + vertex 443.106 87.8712 69.098 + vertex 444.94 85.7889 66.3159 + endloop + endfacet + facet normal -0.580748 -0.787441 0.206561 + outer loop + vertex 444.94 85.7889 66.3159 + vertex 443.106 87.8712 69.098 + vertex 442.565 87.6149 66.5984 + endloop + endfacet + facet normal -0.571654 -0.782054 0.248201 + outer loop + vertex 444.94 85.7889 66.3159 + vertex 442.565 87.6149 66.5984 + vertex 444.167 85.7247 64.3316 + endloop + endfacet + facet normal -0.581519 -0.777989 0.237842 + outer loop + vertex 444.167 85.7247 64.3316 + vertex 442.565 87.6149 66.5984 + vertex 441.611 87.8652 65.0856 + endloop + endfacet + facet normal -0.620598 -0.736416 0.26935 + outer loop + vertex 442.565 87.6149 66.5984 + vertex 440.352 89.7457 67.3258 + vertex 441.611 87.8652 65.0856 + endloop + endfacet + facet normal -0.643453 -0.724664 0.246639 + outer loop + vertex 441.611 87.8652 65.0856 + vertex 440.352 89.7457 67.3258 + vertex 439.579 89.9305 65.8507 + endloop + endfacet + facet normal -0.63172 -0.761469 0.145241 + outer loop + vertex 444.15 88.3606 75.5522 + vertex 441.902 90.375 76.3347 + vertex 443.585 88.1774 72.1338 + endloop + endfacet + facet normal -0.652914 -0.74639 0.128861 + outer loop + vertex 443.585 88.1774 72.1338 + vertex 441.902 90.375 76.3347 + vertex 441.465 90.1562 72.8549 + endloop + endfacet + facet normal -0.612682 -0.787032 0.0721218 + outer loop + vertex 444.847 88.7177 83.313 + vertex 442.402 90.6735 83.8851 + vertex 444.621 88.532 79.3668 + endloop + endfacet + facet normal -0.633171 -0.772058 0.0549623 + outer loop + vertex 444.621 88.532 79.3668 + vertex 442.402 90.6735 83.8851 + vertex 442.233 90.5381 80.0453 + endloop + endfacet + facet normal -0.54433 -0.834947 0.0810458 + outer loop + vertex 447.227 87.1285 82.9316 + vertex 444.847 88.7177 83.313 + vertex 447.283 86.698 78.8727 + endloop + endfacet + facet normal -0.556843 -0.827592 0.0708328 + outer loop + vertex 447.283 86.698 78.8727 + vertex 444.847 88.7177 83.313 + vertex 444.621 88.532 79.3668 + endloop + endfacet + facet normal -0.545868 -0.827678 0.130293 + outer loop + vertex 447.283 86.698 78.8727 + vertex 444.621 88.532 79.3668 + vertex 446.515 86.5672 74.8217 + endloop + endfacet + facet normal -0.579459 -0.807851 0.107722 + outer loop + vertex 446.515 86.5672 74.8217 + vertex 444.621 88.532 79.3668 + vertex 444.15 88.3606 75.5522 + endloop + endfacet + facet normal -0.620601 -0.776177 0.111371 + outer loop + vertex 444.621 88.532 79.3668 + vertex 442.233 90.5381 80.0453 + vertex 444.15 88.3606 75.5522 + endloop + endfacet + facet normal -0.646788 -0.75722 0.0910105 + outer loop + vertex 444.15 88.3606 75.5522 + vertex 442.233 90.5381 80.0453 + vertex 441.902 90.375 76.3347 + endloop + endfacet + facet normal -0.596613 -0.802487 0.00820299 + outer loop + vertex 444.891 88.9016 90.9965 + vertex 442.329 90.8121 91.5472 + vertex 444.941 88.8255 87.1538 + endloop + endfacet + facet normal -0.610678 -0.791864 -0.00496127 + outer loop + vertex 444.941 88.8255 87.1538 + vertex 442.329 90.8121 91.5472 + vertex 442.422 90.7642 87.7365 + endloop + endfacet + facet normal -0.526149 -0.850102 0.0222415 + outer loop + vertex 447.271 87.424 90.8001 + vertex 444.891 88.9016 90.9965 + vertex 447.789 86.988 86.406 + endloop + endfacet + facet normal -0.540285 -0.841426 0.00970087 + outer loop + vertex 447.789 86.988 86.406 + vertex 444.891 88.9016 90.9965 + vertex 444.941 88.8255 87.1538 + endloop + endfacet + facet normal -0.531742 -0.84532 0.0518137 + outer loop + vertex 447.789 86.988 86.406 + vertex 444.941 88.8255 87.1538 + vertex 447.227 87.1285 82.9316 + endloop + endfacet + facet normal -0.550689 -0.833892 0.0369607 + outer loop + vertex 447.227 87.1285 82.9316 + vertex 444.941 88.8255 87.1538 + vertex 444.847 88.7177 83.313 + endloop + endfacet + facet normal -0.604122 -0.796023 0.0372125 + outer loop + vertex 444.941 88.8255 87.1538 + vertex 442.422 90.7642 87.7365 + vertex 444.847 88.7177 83.313 + endloop + endfacet + facet normal -0.621387 -0.7832 0.021818 + outer loop + vertex 444.847 88.7177 83.313 + vertex 442.422 90.7642 87.7365 + vertex 442.402 90.6735 83.8851 + endloop + endfacet + facet normal -0.578943 -0.814735 -0.0321195 + outer loop + vertex 444.474 89.0022 98.469 + vertex 441.848 90.8484 98.9786 + vertex 444.732 88.9642 94.779 + endloop + endfacet + facet normal -0.590972 -0.805462 -0.0445425 + outer loop + vertex 444.732 88.9642 94.779 + vertex 441.848 90.8484 98.9786 + vertex 442.135 90.8411 95.3003 + endloop + endfacet + facet normal -0.505161 -0.862825 -0.0185594 + outer loop + vertex 446.91 87.58 98.2805 + vertex 444.474 89.0022 98.469 + vertex 447.623 87.2511 94.1744 + endloop + endfacet + facet normal -0.513853 -0.857449 -0.0271239 + outer loop + vertex 447.623 87.2511 94.1744 + vertex 444.474 89.0022 98.469 + vertex 444.732 88.9642 94.779 + endloop + endfacet + facet normal -0.50844 -0.861051 0.00896 + outer loop + vertex 447.623 87.2511 94.1744 + vertex 444.732 88.9642 94.779 + vertex 447.271 87.424 90.8001 + endloop + endfacet + facet normal -0.528074 -0.849159 -0.00816809 + outer loop + vertex 447.271 87.424 90.8001 + vertex 444.732 88.9642 94.779 + vertex 444.891 88.9016 90.9965 + endloop + endfacet + facet normal -0.587148 -0.809401 -0.0113095 + outer loop + vertex 444.732 88.9642 94.779 + vertex 442.135 90.8411 95.3003 + vertex 444.891 88.9016 90.9965 + endloop + endfacet + facet normal -0.601022 -0.798843 -0.0249532 + outer loop + vertex 444.891 88.9016 90.9965 + vertex 442.135 90.8411 95.3003 + vertex 442.329 90.8121 91.5472 + endloop + endfacet + facet normal -0.562462 -0.824302 -0.0645254 + outer loop + vertex 443.679 89.048 105.826 + vertex 441.011 90.8332 106.274 + vertex 444.124 89.0332 102.13 + endloop + endfacet + facet normal -0.572602 -0.816341 -0.0756003 + outer loop + vertex 444.124 89.0332 102.13 + vertex 441.011 90.8332 106.274 + vertex 441.472 90.849 102.614 + endloop + endfacet + facet normal -0.483691 -0.873885 -0.0486703 + outer loop + vertex 446.157 87.6815 105.732 + vertex 443.679 89.048 105.826 + vertex 447.104 87.3877 101.594 + endloop + endfacet + facet normal -0.490312 -0.869769 -0.055643 + outer loop + vertex 447.104 87.3877 101.594 + vertex 443.679 89.048 105.826 + vertex 444.124 89.0332 102.13 + endloop + endfacet + facet normal -0.486352 -0.87348 -0.0222459 + outer loop + vertex 447.104 87.3877 101.594 + vertex 444.124 89.0332 102.13 + vertex 446.91 87.58 98.2805 + endloop + endfacet + facet normal -0.506121 -0.861484 -0.0410821 + outer loop + vertex 446.91 87.58 98.2805 + vertex 444.124 89.0332 102.13 + vertex 444.474 89.0022 98.469 + endloop + endfacet + facet normal -0.570117 -0.820186 -0.0475472 + outer loop + vertex 444.124 89.0332 102.13 + vertex 441.472 90.849 102.614 + vertex 444.474 89.0022 98.469 + endloop + endfacet + facet normal -0.581812 -0.811102 -0.0600667 + outer loop + vertex 444.474 89.0022 98.469 + vertex 441.472 90.849 102.614 + vertex 441.848 90.8484 98.9786 + endloop + endfacet + facet normal -0.545528 -0.833087 -0.0914601 + outer loop + vertex 442.532 89.0193 113.53 + vertex 439.841 90.7406 113.897 + vertex 443.149 89.0443 109.62 + endloop + endfacet + facet normal -0.555682 -0.825053 -0.102498 + outer loop + vertex 443.149 89.0443 109.62 + vertex 439.841 90.7406 113.897 + vertex 440.467 90.7999 110.027 + endloop + endfacet + facet normal -0.462204 -0.88362 -0.0747152 + outer loop + vertex 445.034 87.7095 113.539 + vertex 442.532 89.0193 113.53 + vertex 446.185 87.4733 109.212 + endloop + endfacet + facet normal -0.466482 -0.88097 -0.0792834 + outer loop + vertex 446.185 87.4733 109.212 + vertex 442.532 89.0193 113.53 + vertex 443.149 89.0443 109.62 + endloop + endfacet + facet normal -0.46419 -0.884372 -0.0491324 + outer loop + vertex 446.185 87.4733 109.212 + vertex 443.149 89.0443 109.62 + vertex 446.157 87.6815 105.732 + endloop + endfacet + facet normal -0.483706 -0.872556 -0.068374 + outer loop + vertex 446.157 87.6815 105.732 + vertex 443.149 89.0443 109.62 + vertex 443.679 89.048 105.826 + endloop + endfacet + facet normal -0.554326 -0.828619 -0.0781893 + outer loop + vertex 443.149 89.0443 109.62 + vertex 440.467 90.7999 110.027 + vertex 443.679 89.048 105.826 + endloop + endfacet + facet normal -0.564233 -0.820802 -0.0890233 + outer loop + vertex 443.679 89.048 105.826 + vertex 440.467 90.7999 110.027 + vertex 441.011 90.8332 106.274 + endloop + endfacet + facet normal -0.5266 -0.842702 -0.11201 + outer loop + vertex 441.092 88.9119 121.571 + vertex 438.373 90.5684 121.892 + vertex 441.844 88.9787 117.533 + endloop + endfacet + facet normal -0.535005 -0.836124 -0.121103 + outer loop + vertex 441.844 88.9787 117.533 + vertex 438.373 90.5684 121.892 + vertex 439.139 90.6606 117.869 + endloop + endfacet + facet normal -0.440624 -0.892773 -0.0938459 + outer loop + vertex 443.619 87.6614 121.603 + vertex 441.092 88.9119 121.571 + vertex 444.927 87.4807 117.182 + endloop + endfacet + facet normal -0.443947 -0.890742 -0.0974116 + outer loop + vertex 444.927 87.4807 117.182 + vertex 441.092 88.9119 121.571 + vertex 441.844 88.9787 117.533 + endloop + endfacet + facet normal -0.442387 -0.894147 -0.0692405 + outer loop + vertex 444.927 87.4807 117.182 + vertex 441.844 88.9787 117.533 + vertex 445.034 87.7095 113.539 + endloop + endfacet + facet normal -0.461648 -0.88266 -0.0882763 + outer loop + vertex 445.034 87.7095 113.539 + vertex 441.844 88.9787 117.533 + vertex 442.532 89.0193 113.53 + endloop + endfacet + facet normal -0.534382 -0.839267 -0.100334 + outer loop + vertex 441.844 88.9787 117.533 + vertex 439.139 90.6606 117.869 + vertex 442.532 89.0193 113.53 + endloop + endfacet + facet normal -0.546419 -0.82981 -0.113321 + outer loop + vertex 442.532 89.0193 113.53 + vertex 439.139 90.6606 117.869 + vertex 439.841 90.7406 113.897 + endloop + endfacet + facet normal -0.504285 -0.854305 -0.125935 + outer loop + vertex 439.46 88.7408 129.565 + vertex 436.693 90.3316 129.854 + vertex 440.296 88.8329 125.59 + endloop + endfacet + facet normal -0.516129 -0.845128 -0.139171 + outer loop + vertex 440.296 88.8329 125.59 + vertex 436.693 90.3316 129.854 + vertex 437.554 90.4571 125.897 + endloop + endfacet + facet normal -0.419783 -0.901097 -0.108658 + outer loop + vertex 442.023 87.5415 129.608 + vertex 439.46 88.7408 129.565 + vertex 443.43 87.4131 125.237 + endloop + endfacet + facet normal -0.420421 -0.900715 -0.109361 + outer loop + vertex 443.43 87.4131 125.237 + vertex 439.46 88.7408 129.565 + vertex 440.296 88.8329 125.59 + endloop + endfacet + facet normal -0.419053 -0.90411 -0.083545 + outer loop + vertex 443.43 87.4131 125.237 + vertex 440.296 88.8329 125.59 + vertex 443.619 87.6614 121.603 + endloop + endfacet + facet normal -0.440037 -0.891863 -0.104627 + outer loop + vertex 443.619 87.6614 121.603 + vertex 440.296 88.8329 125.59 + vertex 441.092 88.9119 121.571 + endloop + endfacet + facet normal -0.515804 -0.848434 -0.118772 + outer loop + vertex 440.296 88.8329 125.59 + vertex 437.554 90.4571 125.897 + vertex 441.092 88.9119 121.571 + endloop + endfacet + facet normal -0.527014 -0.83969 -0.131061 + outer loop + vertex 441.092 88.9119 121.571 + vertex 437.554 90.4571 125.897 + vertex 438.373 90.5684 121.892 + endloop + endfacet + facet normal -0.4842 -0.863515 -0.141042 + outer loop + vertex 437.667 88.5013 137.434 + vertex 434.842 90.0466 137.67 + vertex 438.585 88.628 133.504 + endloop + endfacet + facet normal -0.49444 -0.855654 -0.15292 + outer loop + vertex 438.585 88.628 133.504 + vertex 434.842 90.0466 137.67 + vertex 435.79 90.196 133.768 + endloop + endfacet + facet normal -0.395299 -0.910721 -0.119688 + outer loop + vertex 440.274 87.3555 137.54 + vertex 437.667 88.5013 137.434 + vertex 441.775 87.2741 133.202 + endloop + endfacet + facet normal -0.397555 -0.909396 -0.122263 + outer loop + vertex 441.775 87.2741 133.202 + vertex 437.667 88.5013 137.434 + vertex 438.585 88.628 133.504 + endloop + endfacet + facet normal -0.396551 -0.913058 -0.0952465 + outer loop + vertex 441.775 87.2741 133.202 + vertex 438.585 88.628 133.504 + vertex 442.023 87.5415 129.608 + endloop + endfacet + facet normal -0.419154 -0.90011 -0.118798 + outer loop + vertex 442.023 87.5415 129.608 + vertex 438.585 88.628 133.504 + vertex 439.46 88.7408 129.565 + endloop + endfacet + facet normal -0.494432 -0.858775 -0.134319 + outer loop + vertex 438.585 88.628 133.504 + vertex 435.79 90.196 133.768 + vertex 439.46 88.7408 129.565 + endloop + endfacet + facet normal -0.504473 -0.851034 -0.145766 + outer loop + vertex 439.46 88.7408 129.565 + vertex 435.79 90.196 133.768 + vertex 436.693 90.3316 129.854 + endloop + endfacet + facet normal -0.460786 -0.874416 -0.1519 + outer loop + vertex 435.678 88.206 145.391 + vertex 432.787 89.7004 145.561 + vertex 436.701 88.3621 141.391 + endloop + endfacet + facet normal -0.472548 -0.865572 -0.165781 + outer loop + vertex 436.701 88.3621 141.391 + vertex 432.787 89.7004 145.561 + vertex 433.842 89.8837 141.594 + endloop + endfacet + facet normal -0.373047 -0.918635 -0.130172 + outer loop + vertex 438.342 87.0988 145.572 + vertex 435.678 88.206 145.391 + vertex 439.956 87.0652 141.182 + endloop + endfacet + facet normal -0.374146 -0.918005 -0.131459 + outer loop + vertex 439.956 87.0652 141.182 + vertex 435.678 88.206 145.391 + vertex 436.701 88.3621 141.391 + endloop + endfacet + facet normal -0.373864 -0.921397 -0.106085 + outer loop + vertex 439.956 87.0652 141.182 + vertex 436.701 88.3621 141.391 + vertex 440.274 87.3555 137.54 + endloop + endfacet + facet normal -0.394571 -0.909862 -0.128314 + outer loop + vertex 440.274 87.3555 137.54 + vertex 436.701 88.3621 141.391 + vertex 437.667 88.5013 137.434 + endloop + endfacet + facet normal -0.472926 -0.868922 -0.145999 + outer loop + vertex 436.701 88.3621 141.391 + vertex 433.842 89.8837 141.594 + vertex 437.667 88.5013 137.434 + endloop + endfacet + facet normal -0.484039 -0.860476 -0.15902 + outer loop + vertex 437.667 88.5013 137.434 + vertex 433.842 89.8837 141.594 + vertex 434.842 90.0466 137.67 + endloop + endfacet + facet normal -0.44034 -0.882746 -0.163891 + outer loop + vertex 433.485 87.833 153.5 + vertex 430.516 89.2919 153.618 + vertex 434.606 88.0287 149.433 + endloop + endfacet + facet normal -0.448649 -0.876635 -0.173856 + outer loop + vertex 434.606 88.0287 149.433 + vertex 430.516 89.2919 153.618 + vertex 431.675 89.5007 149.573 + endloop + endfacet + facet normal -0.348263 -0.927225 -0.137723 + outer loop + vertex 436.22 86.7715 153.729 + vertex 433.485 87.833 153.5 + vertex 437.948 86.7814 149.294 + endloop + endfacet + facet normal -0.351331 -0.925511 -0.141408 + outer loop + vertex 437.948 86.7814 149.294 + vertex 433.485 87.833 153.5 + vertex 434.606 88.0287 149.433 + endloop + endfacet + facet normal -0.351552 -0.928901 -0.116425 + outer loop + vertex 437.948 86.7814 149.294 + vertex 434.606 88.0287 149.433 + vertex 438.342 87.0988 145.572 + endloop + endfacet + facet normal -0.372077 -0.91774 -0.138971 + outer loop + vertex 438.342 87.0988 145.572 + vertex 434.606 88.0287 149.433 + vertex 435.678 88.206 145.391 + endloop + endfacet + facet normal -0.449252 -0.879365 -0.157765 + outer loop + vertex 434.606 88.0287 149.433 + vertex 431.675 89.5007 149.573 + vertex 435.678 88.206 145.391 + endloop + endfacet + facet normal -0.460237 -0.87121 -0.170805 + outer loop + vertex 435.678 88.206 145.391 + vertex 431.675 89.5007 149.573 + vertex 432.787 89.7004 145.561 + endloop + endfacet + facet normal -0.417315 -0.892284 -0.172271 + outer loop + vertex 431.147 87.4015 161.594 + vertex 428.09 88.8163 161.67 + vertex 432.332 87.6263 157.56 + endloop + endfacet + facet normal -0.426714 -0.885484 -0.183939 + outer loop + vertex 432.332 87.6263 157.56 + vertex 428.09 88.8163 161.67 + vertex 429.318 89.0586 157.657 + endloop + endfacet + facet normal -0.328724 -0.932717 -0.148254 + outer loop + vertex 433.965 86.3664 161.857 + vertex 431.147 87.4015 161.594 + vertex 435.778 86.4271 157.456 + endloop + endfacet + facet normal -0.328979 -0.932576 -0.148573 + outer loop + vertex 435.778 86.4271 157.456 + vertex 431.147 87.4015 161.594 + vertex 432.332 87.6263 157.56 + endloop + endfacet + facet normal -0.329406 -0.935802 -0.125561 + outer loop + vertex 435.778 86.4271 157.456 + vertex 432.332 87.6263 157.56 + vertex 436.22 86.7715 153.729 + endloop + endfacet + facet normal -0.347255 -0.92637 -0.145782 + outer loop + vertex 436.22 86.7715 153.729 + vertex 432.332 87.6263 157.56 + vertex 433.485 87.833 153.5 + endloop + endfacet + facet normal -0.427585 -0.888478 -0.166668 + outer loop + vertex 432.332 87.6263 157.56 + vertex 429.318 89.0586 157.657 + vertex 433.485 87.833 153.5 + endloop + endfacet + facet normal -0.439555 -0.87974 -0.181243 + outer loop + vertex 433.485 87.833 153.5 + vertex 429.318 89.0586 157.657 + vertex 430.516 89.2919 153.618 + endloop + endfacet + facet normal -0.397897 -0.899059 -0.182676 + outer loop + vertex 428.69 86.897 169.607 + vertex 425.546 88.2843 169.627 + vertex 429.935 87.1585 165.607 + endloop + endfacet + facet normal -0.406297 -0.893008 -0.193543 + outer loop + vertex 429.935 87.1585 165.607 + vertex 425.546 88.2843 169.627 + vertex 426.834 88.559 165.656 + endloop + endfacet + facet normal -0.307728 -0.938351 -0.157485 + outer loop + vertex 431.59 85.8924 169.926 + vertex 428.69 86.897 169.607 + vertex 433.485 86.0032 165.562 + endloop + endfacet + facet normal -0.307419 -0.93852 -0.157081 + outer loop + vertex 433.485 86.0032 165.562 + vertex 428.69 86.897 169.607 + vertex 429.935 87.1585 165.607 + endloop + endfacet + facet normal -0.308258 -0.94206 -0.132291 + outer loop + vertex 433.485 86.0032 165.562 + vertex 429.935 87.1585 165.607 + vertex 433.965 86.3664 161.857 + endloop + endfacet + facet normal -0.327757 -0.931895 -0.155394 + outer loop + vertex 433.965 86.3664 161.857 + vertex 429.935 87.1585 165.607 + vertex 431.147 87.4015 161.594 + endloop + endfacet + facet normal -0.40735 -0.895908 -0.177242 + outer loop + vertex 429.935 87.1585 165.607 + vertex 426.834 88.559 165.656 + vertex 431.147 87.4015 161.594 + endloop + endfacet + facet normal -0.416384 -0.889393 -0.188693 + outer loop + vertex 431.147 87.4015 161.594 + vertex 426.834 88.559 165.656 + vertex 428.09 88.8163 161.67 + endloop + endfacet + facet normal -0.375309 -0.907204 -0.190065 + outer loop + vertex 426.124 86.328 177.562 + vertex 422.883 87.6764 177.525 + vertex 427.419 86.6225 173.598 + endloop + endfacet + facet normal -0.384938 -0.900334 -0.203032 + outer loop + vertex 427.419 86.6225 173.598 + vertex 422.883 87.6764 177.525 + vertex 424.227 87.9898 173.586 + endloop + endfacet + facet normal -0.289912 -0.94255 -0.165984 + outer loop + vertex 429.114 85.3446 177.922 + vertex 426.124 86.328 177.562 + vertex 431.079 85.4987 173.615 + endloop + endfacet + facet normal -0.288799 -0.943159 -0.164458 + outer loop + vertex 431.079 85.4987 173.615 + vertex 426.124 86.328 177.562 + vertex 427.419 86.6225 173.598 + endloop + endfacet + facet normal -0.289956 -0.946575 -0.141145 + outer loop + vertex 431.079 85.4987 173.615 + vertex 427.419 86.6225 173.598 + vertex 431.59 85.8924 169.926 + endloop + endfacet + facet normal -0.307004 -0.937774 -0.162257 + outer loop + vertex 431.59 85.8924 169.926 + vertex 427.419 86.6225 173.598 + vertex 428.69 86.897 169.607 + endloop + endfacet + facet normal -0.386383 -0.903558 -0.185177 + outer loop + vertex 427.419 86.6225 173.598 + vertex 424.227 87.9898 173.586 + vertex 428.69 86.897 169.607 + endloop + endfacet + facet normal -0.396717 -0.896156 -0.198798 + outer loop + vertex 428.69 86.897 169.607 + vertex 424.227 87.9898 173.586 + vertex 425.546 88.2843 169.627 + endloop + endfacet + facet normal -0.357922 -0.912216 -0.199382 + outer loop + vertex 423.478 85.6845 185.391 + vertex 420.137 87.0139 185.306 + vertex 424.812 86.0137 181.491 + endloop + endfacet + facet normal -0.365625 -0.906701 -0.210266 + outer loop + vertex 424.812 86.0137 181.491 + vertex 420.137 87.0139 185.306 + vertex 421.52 87.3545 181.433 + endloop + endfacet + facet normal -0.272642 -0.945989 -0.175418 + outer loop + vertex 426.564 84.7185 185.804 + vertex 423.478 85.6845 185.391 + vertex 428.589 84.9204 181.568 + endloop + endfacet + facet normal -0.270609 -0.947113 -0.172475 + outer loop + vertex 428.589 84.9204 181.568 + vertex 423.478 85.6845 185.391 + vertex 424.812 86.0137 181.491 + endloop + endfacet + facet normal -0.272062 -0.950546 -0.149812 + outer loop + vertex 428.589 84.9204 181.568 + vertex 424.812 86.0137 181.491 + vertex 429.114 85.3446 177.922 + endloop + endfacet + facet normal -0.28896 -0.941795 -0.171825 + outer loop + vertex 429.114 85.3446 177.922 + vertex 424.812 86.0137 181.491 + vertex 426.124 86.328 177.562 + endloop + endfacet + facet normal -0.367021 -0.909479 -0.195302 + outer loop + vertex 424.812 86.0137 181.491 + vertex 421.52 87.3545 181.433 + vertex 426.124 86.328 177.562 + endloop + endfacet + facet normal -0.374015 -0.904496 -0.204939 + outer loop + vertex 426.124 86.328 177.562 + vertex 421.52 87.3545 181.433 + vertex 422.883 87.6764 177.525 + endloop + endfacet + facet normal -0.340217 -0.916993 -0.208267 + outer loop + vertex 420.755 84.9677 193.121 + vertex 417.31 86.2787 192.977 + vertex 422.126 85.3337 189.269 + endloop + endfacet + facet normal -0.346994 -0.912104 -0.218317 + outer loop + vertex 422.126 85.3337 189.269 + vertex 417.31 86.2787 192.977 + vertex 418.733 86.6527 189.153 + endloop + endfacet + facet normal -0.256474 -0.948938 -0.18368 + outer loop + vertex 423.94 84.0172 193.585 + vertex 420.755 84.9677 193.121 + vertex 426.025 84.2603 189.417 + endloop + endfacet + facet normal -0.25469 -0.949942 -0.18095 + outer loop + vertex 426.025 84.2603 189.417 + vertex 420.755 84.9677 193.121 + vertex 422.126 85.3337 189.269 + endloop + endfacet + facet normal -0.25646 -0.953359 -0.159166 + outer loop + vertex 426.025 84.2603 189.417 + vertex 422.126 85.3337 189.269 + vertex 426.564 84.7185 185.804 + endloop + endfacet + facet normal -0.271792 -0.945329 -0.180227 + outer loop + vertex 426.564 84.7185 185.804 + vertex 422.126 85.3337 189.269 + vertex 423.478 85.6845 185.391 + endloop + endfacet + facet normal -0.348521 -0.914785 -0.204208 + outer loop + vertex 422.126 85.3337 189.269 + vertex 418.733 86.6527 189.153 + vertex 423.478 85.6845 185.391 + endloop + endfacet + facet normal -0.356306 -0.909185 -0.215471 + outer loop + vertex 423.478 85.6845 185.391 + vertex 418.733 86.6527 189.153 + vertex 420.137 87.0139 185.306 + endloop + endfacet + facet normal -0.322923 -0.920945 -0.218133 + outer loop + vertex 417.975 84.1748 200.723 + vertex 414.419 85.4706 200.516 + vertex 419.373 84.5806 196.939 + endloop + endfacet + facet normal -0.329657 -0.915983 -0.228695 + outer loop + vertex 419.373 84.5806 196.939 + vertex 414.419 85.4706 200.516 + vertex 415.871 85.8842 196.766 + endloop + endfacet + facet normal -0.243139 -0.950109 -0.195389 + outer loop + vertex 421.263 83.2255 201.247 + vertex 417.975 84.1748 200.723 + vertex 423.398 83.5206 197.155 + endloop + endfacet + facet normal -0.240402 -0.95171 -0.190934 + outer loop + vertex 423.398 83.5206 197.155 + vertex 417.975 84.1748 200.723 + vertex 419.373 84.5806 196.939 + endloop + endfacet + facet normal -0.242467 -0.95521 -0.169655 + outer loop + vertex 423.398 83.5206 197.155 + vertex 419.373 84.5806 196.939 + vertex 423.94 84.0172 193.585 + endloop + endfacet + facet normal -0.25554 -0.948219 -0.188627 + outer loop + vertex 423.94 84.0172 193.585 + vertex 419.373 84.5806 196.939 + vertex 420.755 84.9677 193.121 + endloop + endfacet + facet normal -0.331559 -0.919032 -0.213188 + outer loop + vertex 419.373 84.5806 196.939 + vertex 415.871 85.8842 196.766 + vertex 420.755 84.9677 193.121 + endloop + endfacet + facet normal -0.338441 -0.914019 -0.22367 + outer loop + vertex 420.755 84.9677 193.121 + vertex 415.871 85.8842 196.766 + vertex 417.31 86.2787 192.977 + endloop + endfacet + facet normal -0.308647 -0.92308 -0.229479 + outer loop + vertex 415.129 83.2949 208.225 + vertex 411.465 84.5906 207.941 + vertex 416.561 83.7457 204.485 + endloop + endfacet + facet normal -0.314662 -0.918501 -0.239468 + outer loop + vertex 416.561 83.7457 204.485 + vertex 411.465 84.5906 207.941 + vertex 412.952 85.0458 204.241 + endloop + endfacet + facet normal -0.229326 -0.951345 -0.205797 + outer loop + vertex 418.523 82.3493 208.814 + vertex 415.129 83.2949 208.225 + vertex 420.712 82.6931 204.785 + endloop + endfacet + facet normal -0.227012 -0.952756 -0.201794 + outer loop + vertex 420.712 82.6931 204.785 + vertex 415.129 83.2949 208.225 + vertex 416.561 83.7457 204.485 + endloop + endfacet + facet normal -0.229581 -0.956565 -0.179658 + outer loop + vertex 420.712 82.6931 204.785 + vertex 416.561 83.7457 204.485 + vertex 421.263 83.2255 201.247 + endloop + endfacet + facet normal -0.242337 -0.949498 -0.199315 + outer loop + vertex 421.263 83.2255 201.247 + vertex 416.561 83.7457 204.485 + vertex 417.975 84.1748 200.723 + endloop + endfacet + facet normal -0.316823 -0.921626 -0.224118 + outer loop + vertex 416.561 83.7457 204.485 + vertex 412.952 85.0458 204.241 + vertex 417.975 84.1748 200.723 + endloop + endfacet + facet normal -0.321217 -0.918349 -0.231202 + outer loop + vertex 417.975 84.1748 200.723 + vertex 412.952 85.0458 204.241 + vertex 414.419 85.4706 200.516 + endloop + endfacet + facet normal -0.29494 -0.924754 -0.240498 + outer loop + vertex 412.251 82.3294 215.574 + vertex 408.47 83.6275 215.22 + vertex 413.691 82.8182 211.928 + endloop + endfacet + facet normal -0.300743 -0.920126 -0.250842 + outer loop + vertex 413.691 82.8182 211.928 + vertex 408.47 83.6275 215.22 + vertex 409.97 84.1218 211.609 + endloop + endfacet + facet normal -0.217656 -0.951208 -0.2187 + outer loop + vertex 415.759 81.3781 216.221 + vertex 412.251 82.3294 215.574 + vertex 417.981 81.7701 212.304 + endloop + endfacet + facet normal -0.21432 -0.953371 -0.212485 + outer loop + vertex 417.981 81.7701 212.304 + vertex 412.251 82.3294 215.574 + vertex 413.691 82.8182 211.928 + endloop + endfacet + facet normal -0.216961 -0.957012 -0.192497 + outer loop + vertex 417.981 81.7701 212.304 + vertex 413.691 82.8182 211.928 + vertex 418.523 82.3493 208.814 + endloop + endfacet + facet normal -0.228201 -0.950494 -0.210915 + outer loop + vertex 418.523 82.3493 208.814 + vertex 413.691 82.8182 211.928 + vertex 415.129 83.2949 208.225 + endloop + endfacet + facet normal -0.303047 -0.923176 -0.236451 + outer loop + vertex 413.691 82.8182 211.928 + vertex 409.97 84.1218 211.609 + vertex 415.129 83.2949 208.225 + endloop + endfacet + facet normal -0.306667 -0.920366 -0.242657 + outer loop + vertex 415.129 83.2949 208.225 + vertex 409.97 84.1218 211.609 + vertex 411.465 84.5906 207.941 + endloop + endfacet + facet normal -0.282261 -0.924701 -0.255455 + outer loop + vertex 409.357 81.2798 222.715 + vertex 405.464 82.5898 222.275 + vertex 410.811 81.8164 219.166 + endloop + endfacet + facet normal -0.28594 -0.921575 -0.262559 + outer loop + vertex 410.811 81.8164 219.166 + vertex 405.464 82.5898 222.275 + vertex 406.972 83.1201 218.772 + endloop + endfacet + facet normal -0.205825 -0.950831 -0.231424 + outer loop + vertex 412.969 80.3188 223.451 + vertex 409.357 81.2798 222.715 + vertex 415.234 80.7567 219.637 + endloop + endfacet + facet normal -0.20389 -0.952194 -0.227498 + outer loop + vertex 415.234 80.7567 219.637 + vertex 409.357 81.2798 222.715 + vertex 410.811 81.8164 219.166 + endloop + endfacet + facet normal -0.207214 -0.956408 -0.205784 + outer loop + vertex 415.234 80.7567 219.637 + vertex 410.811 81.8164 219.166 + vertex 415.759 81.3781 216.221 + endloop + endfacet + facet normal -0.216735 -0.950499 -0.222659 + outer loop + vertex 415.759 81.3781 216.221 + vertex 410.811 81.8164 219.166 + vertex 412.251 82.3294 215.574 + endloop + endfacet + facet normal -0.288564 -0.924841 -0.247792 + outer loop + vertex 410.811 81.8164 219.166 + vertex 406.972 83.1201 218.772 + vertex 412.251 82.3294 215.574 + endloop + endfacet + facet normal -0.292497 -0.921617 -0.255083 + outer loop + vertex 412.251 82.3294 215.574 + vertex 406.972 83.1201 218.772 + vertex 408.47 83.6275 215.22 + endloop + endfacet + facet normal -0.270527 -0.924251 -0.269399 + outer loop + vertex 406.388 80.1408 229.754 + vertex 402.39 81.4694 229.211 + vertex 407.885 80.7241 226.25 + endloop + endfacet + facet normal -0.272433 -0.922523 -0.27337 + outer loop + vertex 407.885 80.7241 226.25 + vertex 402.39 81.4694 229.211 + vertex 403.936 82.0372 225.754 + endloop + endfacet + facet normal -0.19645 -0.948708 -0.24771 + outer loop + vertex 410.108 79.1566 230.573 + vertex 406.388 80.1408 229.754 + vertex 412.431 79.6509 226.838 + endloop + endfacet + facet normal -0.193365 -0.951088 -0.240917 + outer loop + vertex 412.431 79.6509 226.838 + vertex 406.388 80.1408 229.754 + vertex 407.885 80.7241 226.25 + endloop + endfacet + facet normal -0.197127 -0.955434 -0.219743 + outer loop + vertex 412.431 79.6509 226.838 + vertex 407.885 80.7241 226.25 + vertex 412.969 80.3188 223.451 + endloop + endfacet + facet normal -0.204976 -0.950196 -0.23476 + outer loop + vertex 412.969 80.3188 223.451 + vertex 407.885 80.7241 226.25 + vertex 409.357 81.2798 222.715 + endloop + endfacet + facet normal -0.27511 -0.925561 -0.260099 + outer loop + vertex 407.885 80.7241 226.25 + vertex 403.936 82.0372 225.754 + vertex 409.357 81.2798 222.715 + endloop + endfacet + facet normal -0.279658 -0.921586 -0.269203 + outer loop + vertex 409.357 81.2798 222.715 + vertex 403.936 82.0372 225.754 + vertex 405.464 82.5898 222.275 + endloop + endfacet + facet normal -0.258944 -0.923506 -0.282993 + outer loop + vertex 403.392 78.9381 236.558 + vertex 399.28 80.2816 235.935 + vertex 404.891 79.5463 233.201 + endloop + endfacet + facet normal -0.260837 -0.921614 -0.287387 + outer loop + vertex 404.891 79.5463 233.201 + vertex 399.28 80.2816 235.935 + vertex 400.832 80.878 232.615 + endloop + endfacet + facet normal -0.186651 -0.946872 -0.261906 + outer loop + vertex 407.222 77.9404 237.435 + vertex 403.392 78.9381 236.558 + vertex 409.577 78.4615 233.872 + endloop + endfacet + facet normal -0.183437 -0.949647 -0.254011 + outer loop + vertex 409.577 78.4615 233.872 + vertex 403.392 78.9381 236.558 + vertex 404.891 79.5463 233.201 + endloop + endfacet + facet normal -0.187828 -0.954575 -0.231314 + outer loop + vertex 409.577 78.4615 233.872 + vertex 404.891 79.5463 233.201 + vertex 410.108 79.1566 230.573 + endloop + endfacet + facet normal -0.196162 -0.948493 -0.24876 + outer loop + vertex 410.108 79.1566 230.573 + vertex 404.891 79.5463 233.201 + vertex 406.388 80.1408 229.754 + endloop + endfacet + facet normal -0.263814 -0.924818 -0.274068 + outer loop + vertex 404.891 79.5463 233.201 + vertex 400.832 80.878 232.615 + vertex 406.388 80.1408 229.754 + endloop + endfacet + facet normal -0.267704 -0.921134 -0.282573 + outer loop + vertex 406.388 80.1408 229.754 + vertex 400.832 80.878 232.615 + vertex 402.39 81.4694 229.211 + endloop + endfacet + facet normal -0.248894 -0.921425 -0.298374 + outer loop + vertex 400.381 77.697 243.047 + vertex 396.173 79.0658 242.329 + vertex 401.898 78.3281 239.833 + endloop + endfacet + facet normal -0.249516 -0.920726 -0.300007 + outer loop + vertex 401.898 78.3281 239.833 + vertex 396.173 79.0658 242.329 + vertex 397.731 79.6753 239.163 + endloop + endfacet + facet normal -0.177472 -0.944951 -0.274903 + outer loop + vertex 404.302 76.6756 244.027 + vertex 400.381 77.697 243.047 + vertex 406.707 77.2167 240.614 + endloop + endfacet + facet normal -0.175241 -0.947158 -0.268668 + outer loop + vertex 406.707 77.2167 240.614 + vertex 400.381 77.697 243.047 + vertex 401.898 78.3281 239.833 + endloop + endfacet + facet normal -0.180128 -0.952384 -0.246007 + outer loop + vertex 406.707 77.2167 240.614 + vertex 401.898 78.3281 239.833 + vertex 407.222 77.9404 237.435 + endloop + endfacet + facet normal -0.186745 -0.946944 -0.26158 + outer loop + vertex 407.222 77.9404 237.435 + vertex 401.898 78.3281 239.833 + vertex 403.392 78.9381 236.558 + endloop + endfacet + facet normal -0.252588 -0.923926 -0.287332 + outer loop + vertex 401.898 78.3281 239.833 + vertex 397.731 79.6753 239.163 + vertex 403.392 78.9381 236.558 + endloop + endfacet + facet normal -0.255982 -0.920338 -0.295721 + outer loop + vertex 403.392 78.9381 236.558 + vertex 397.731 79.6753 239.163 + vertex 399.28 80.2816 235.935 + endloop + endfacet + facet normal -0.237552 -0.920166 -0.31123 + outer loop + vertex 397.249 76.3872 249.418 + vertex 392.952 77.7782 248.585 + vertex 398.834 77.0511 246.244 + endloop + endfacet + facet normal -0.239803 -0.917344 -0.317766 + outer loop + vertex 398.834 77.0511 246.244 + vertex 392.952 77.7782 248.585 + vertex 394.582 78.4326 245.465 + endloop + endfacet + facet normal -0.170531 -0.941232 -0.291549 + outer loop + vertex 401.25 75.3294 250.492 + vertex 397.249 76.3872 249.418 + vertex 403.749 75.9063 247.168 + endloop + endfacet + facet normal -0.167252 -0.944938 -0.281282 + outer loop + vertex 403.749 75.9063 247.168 + vertex 397.249 76.3872 249.418 + vertex 398.834 77.0511 246.244 + endloop + endfacet + facet normal -0.171791 -0.949453 -0.262729 + outer loop + vertex 403.749 75.9063 247.168 + vertex 398.834 77.0511 246.244 + vertex 404.302 76.6756 244.027 + endloop + endfacet + facet normal -0.177005 -0.9446 -0.276406 + outer loop + vertex 404.302 76.6756 244.027 + vertex 398.834 77.0511 246.244 + vertex 400.381 77.697 243.047 + endloop + endfacet + facet normal -0.243562 -0.921064 -0.303839 + outer loop + vertex 398.834 77.0511 246.244 + vertex 394.582 78.4326 245.465 + vertex 400.381 77.697 243.047 + endloop + endfacet + facet normal -0.245869 -0.918326 -0.310202 + outer loop + vertex 400.381 77.697 243.047 + vertex 394.582 78.4326 245.465 + vertex 396.173 79.0658 242.329 + endloop + endfacet + facet normal -0.230931 -0.915815 -0.328564 + outer loop + vertex 394.015 75.0262 255.585 + vertex 389.643 76.4553 254.675 + vertex 395.639 75.7074 252.545 + endloop + endfacet + facet normal -0.231307 -0.91527 -0.329815 + outer loop + vertex 395.639 75.7074 252.545 + vertex 389.643 76.4553 254.675 + vertex 391.301 77.1193 251.669 + endloop + endfacet + facet normal -0.163438 -0.937193 -0.308151 + outer loop + vertex 398.075 73.9477 256.712 + vertex 394.015 75.0262 255.585 + vertex 400.651 74.5346 253.56 + endloop + endfacet + facet normal -0.160213 -0.941486 -0.29654 + outer loop + vertex 400.651 74.5346 253.56 + vertex 394.015 75.0262 255.585 + vertex 395.639 75.7074 252.545 + endloop + endfacet + facet normal -0.165245 -0.946432 -0.277417 + outer loop + vertex 400.651 74.5346 253.56 + vertex 395.639 75.7074 252.545 + vertex 401.25 75.3294 250.492 + endloop + endfacet + facet normal -0.170303 -0.941062 -0.292231 + outer loop + vertex 401.25 75.3294 250.492 + vertex 395.639 75.7074 252.545 + vertex 397.249 76.3872 249.418 + endloop + endfacet + facet normal -0.234159 -0.917997 -0.320081 + outer loop + vertex 395.639 75.7074 252.545 + vertex 391.301 77.1193 251.669 + vertex 397.249 76.3872 249.418 + endloop + endfacet + facet normal -0.23464 -0.917357 -0.321559 + outer loop + vertex 397.249 76.3872 249.418 + vertex 391.301 77.1193 251.669 + vertex 392.952 77.7782 248.585 + endloop + endfacet + facet normal -0.223434 -0.911045 -0.346518 + outer loop + vertex 390.726 73.6896 261.33 + vertex 386.329 75.1401 260.352 + vertex 392.382 74.3533 258.517 + endloop + endfacet + facet normal -0.223412 -0.911083 -0.346432 + outer loop + vertex 392.382 74.3533 258.517 + vertex 386.329 75.1401 260.352 + vertex 387.985 75.7909 257.572 + endloop + endfacet + facet normal -0.158985 -0.930836 -0.329041 + outer loop + vertex 394.772 72.5754 262.527 + vertex 390.726 73.6896 261.33 + vertex 397.426 73.1525 259.612 + endloop + endfacet + facet normal -0.155259 -0.93713 -0.312541 + outer loop + vertex 397.426 73.1525 259.612 + vertex 390.726 73.6896 261.33 + vertex 392.382 74.3533 258.517 + endloop + endfacet + facet normal -0.160434 -0.942173 -0.294229 + outer loop + vertex 397.426 73.1525 259.612 + vertex 392.382 74.3533 258.517 + vertex 398.075 73.9477 256.712 + endloop + endfacet + facet normal -0.164007 -0.93763 -0.306517 + outer loop + vertex 398.075 73.9477 256.712 + vertex 392.382 74.3533 258.517 + vertex 394.015 75.0262 255.585 + endloop + endfacet + facet normal -0.226659 -0.914172 -0.336028 + outer loop + vertex 392.382 74.3533 258.517 + vertex 387.985 75.7909 257.572 + vertex 394.015 75.0262 255.585 + endloop + endfacet + facet normal -0.227615 -0.912644 -0.339517 + outer loop + vertex 394.015 75.0262 255.585 + vertex 387.985 75.7909 257.572 + vertex 389.643 76.4553 254.675 + endloop + endfacet + facet normal -0.217979 -0.901556 -0.373741 + outer loop + vertex 387.341 72.3371 266.691 + vertex 382.976 73.8447 265.6 + vertex 389.04 73.0206 264.052 + endloop + endfacet + facet normal -0.217053 -0.903752 -0.368944 + outer loop + vertex 389.04 73.0206 264.052 + vertex 382.976 73.8447 265.6 + vertex 384.657 74.4929 263.023 + endloop + endfacet + facet normal -0.15287 -0.923725 -0.351231 + outer loop + vertex 391.408 71.1526 268.036 + vertex 387.341 72.3371 266.691 + vertex 394.075 71.7509 265.302 + endloop + endfacet + facet normal -0.150513 -0.929219 -0.337487 + outer loop + vertex 394.075 71.7509 265.302 + vertex 387.341 72.3371 266.691 + vertex 389.04 73.0206 264.052 + endloop + endfacet + facet normal -0.157035 -0.935224 -0.317326 + outer loop + vertex 394.075 71.7509 265.302 + vertex 389.04 73.0206 264.052 + vertex 394.772 72.5754 262.527 + endloop + endfacet + facet normal -0.159486 -0.931221 -0.327708 + outer loop + vertex 394.772 72.5754 262.527 + vertex 389.04 73.0206 264.052 + vertex 390.726 73.6896 261.33 + endloop + endfacet + facet normal -0.220317 -0.906803 -0.3594 + outer loop + vertex 389.04 73.0206 264.052 + vertex 384.657 74.4929 263.023 + vertex 390.726 73.6896 261.33 + endloop + endfacet + facet normal -0.21989 -0.907675 -0.357456 + outer loop + vertex 390.726 73.6896 261.33 + vertex 384.657 74.4929 263.023 + vertex 386.329 75.1401 260.352 + endloop + endfacet + facet normal -0.211157 -0.895994 -0.390649 + outer loop + vertex 384.197 71.0114 271.497 + vertex 379.807 72.5791 270.274 + vertex 385.705 71.6458 269.227 + endloop + endfacet + facet normal -0.211085 -0.896311 -0.389961 + outer loop + vertex 385.705 71.6458 269.227 + vertex 379.807 72.5791 270.274 + vertex 381.327 73.1875 268.053 + endloop + endfacet + facet normal -0.146092 -0.915856 -0.373986 + outer loop + vertex 388.344 69.7726 272.911 + vertex 384.197 71.0114 271.497 + vertex 390.868 70.2803 270.682 + endloop + endfacet + facet normal -0.144559 -0.923924 -0.354213 + outer loop + vertex 390.868 70.2803 270.682 + vertex 384.197 71.0114 271.497 + vertex 385.705 71.6458 269.227 + endloop + endfacet + facet normal -0.15078 -0.92929 -0.337172 + outer loop + vertex 390.868 70.2803 270.682 + vertex 385.705 71.6458 269.227 + vertex 391.408 71.1526 268.036 + endloop + endfacet + facet normal -0.153124 -0.923912 -0.350626 + outer loop + vertex 391.408 71.1526 268.036 + vertex 385.705 71.6458 269.227 + vertex 387.341 72.3371 266.691 + endloop + endfacet + facet normal -0.213819 -0.898702 -0.382904 + outer loop + vertex 385.705 71.6458 269.227 + vertex 381.327 73.1875 268.053 + vertex 387.341 72.3371 266.691 + endloop + endfacet + facet normal -0.214068 -0.897981 -0.384454 + outer loop + vertex 387.341 72.3371 266.691 + vertex 381.327 73.1875 268.053 + vertex 382.976 73.8447 265.6 + endloop + endfacet + facet normal -0.215545 -0.88911 -0.403762 + outer loop + vertex 381.808 70.2396 274.466 + vertex 377.496 71.8044 273.322 + vertex 382.844 70.5231 273.289 + endloop + endfacet + facet normal -0.217456 -0.897618 -0.3834 + outer loop + vertex 382.844 70.5231 273.289 + vertex 377.496 71.8044 273.322 + vertex 378.495 72.0921 272.082 + endloop + endfacet + facet normal -0.146083 -0.897106 -0.416967 + outer loop + vertex 385.642 69.121 275.53 + vertex 381.808 70.2396 274.466 + vertex 387.727 69.2336 274.557 + endloop + endfacet + facet normal -0.151334 -0.922432 -0.35527 + outer loop + vertex 387.727 69.2336 274.557 + vertex 381.808 70.2396 274.466 + vertex 382.844 70.5231 273.289 + endloop + endfacet + facet normal -0.150347 -0.921493 -0.358116 + outer loop + vertex 387.727 69.2336 274.557 + vertex 382.844 70.5231 273.289 + vertex 388.344 69.7726 272.911 + endloop + endfacet + facet normal -0.150436 -0.919126 -0.36411 + outer loop + vertex 388.344 69.7726 272.911 + vertex 382.844 70.5231 273.289 + vertex 384.197 71.0114 271.497 + endloop + endfacet + facet normal -0.21014 -0.891363 -0.401637 + outer loop + vertex 382.844 70.5231 273.289 + vertex 378.495 72.0921 272.082 + vertex 384.197 71.0114 271.497 + endloop + endfacet + facet normal -0.209999 -0.895003 -0.393536 + outer loop + vertex 384.197 71.0114 271.497 + vertex 378.495 72.0921 272.082 + vertex 379.807 72.5791 270.274 + endloop + endfacet + facet normal -0.225622 -0.90342 -0.364591 + outer loop + vertex 381.275 69.9928 275.376 + vertex 376.81 71.5295 274.331 + vertex 381.284 70.0994 275.106 + endloop + endfacet + facet normal -0.209535 -0.883057 -0.419888 + outer loop + vertex 381.284 70.0994 275.106 + vertex 376.81 71.5295 274.331 + vertex 376.893 71.6597 274.016 + endloop + endfacet + facet normal -0.125838 -0.871843 -0.473345 + outer loop + vertex 385.626 68.8296 276.361 + vertex 381.275 69.9928 275.376 + vertex 386.378 68.7896 276.235 + endloop + endfacet + facet normal -0.154306 -0.917071 -0.367656 + outer loop + vertex 386.378 68.7896 276.235 + vertex 381.275 69.9928 275.376 + vertex 381.284 70.0994 275.106 + endloop + endfacet + facet normal -0.189015 -0.949852 -0.249106 + outer loop + vertex 386.378 68.7896 276.235 + vertex 381.284 70.0994 275.106 + vertex 385.642 69.121 275.53 + endloop + endfacet + facet normal -0.173606 -0.922581 -0.344537 + outer loop + vertex 385.642 69.121 275.53 + vertex 381.284 70.0994 275.106 + vertex 381.808 70.2396 274.466 + endloop + endfacet + facet normal -0.224318 -0.897151 -0.380528 + outer loop + vertex 381.284 70.0994 275.106 + vertex 376.893 71.6597 274.016 + vertex 381.808 70.2396 274.466 + endloop + endfacet + facet normal -0.22401 -0.896573 -0.382068 + outer loop + vertex 381.808 70.2396 274.466 + vertex 376.893 71.6597 274.016 + vertex 377.496 71.8044 273.322 + endloop + endfacet + facet normal 0.140695 -0.268925 -0.95283 + outer loop + vertex 384.227 69.0753 276.085 + vertex 381.447 69.8667 275.452 + vertex 385.626 68.8296 276.361 + endloop + endfacet + facet normal 0.0930932 -0.417703 -0.903802 + outer loop + vertex 385.626 68.8296 276.361 + vertex 381.447 69.8667 275.452 + vertex 381.275 69.9928 275.376 + endloop + endfacet + facet normal 0.0395473 -0.475833 -0.878646 + outer loop + vertex 381.447 69.8667 275.452 + vertex 377.367 71.2526 274.517 + vertex 381.275 69.9928 275.376 + endloop + endfacet + facet normal 0.00592079 -0.550343 -0.834918 + outer loop + vertex 381.275 69.9928 275.376 + vertex 377.367 71.2526 274.517 + vertex 376.81 71.5295 274.331 + endloop + endfacet + facet normal -0.748307 -0.604343 0.273508 + outer loop + vertex 437.708 92.1966 66.5568 + vertex 435.71 94.993 67.2695 + vertex 437.017 92.759 65.9095 + endloop + endfacet + facet normal -0.793535 -0.578753 0.188007 + outer loop + vertex 437.017 92.759 65.9095 + vertex 435.71 94.993 67.2695 + vertex 434.862 95.9607 66.6715 + endloop + endfacet + facet normal -0.67858 -0.660426 0.321506 + outer loop + vertex 439.579 89.9305 65.8507 + vertex 437.708 92.1966 66.5568 + vertex 438.699 90.5933 65.356 + endloop + endfacet + facet normal -0.737084 -0.633025 0.236616 + outer loop + vertex 438.699 90.5933 65.356 + vertex 437.708 92.1966 66.5568 + vertex 437.017 92.759 65.9095 + endloop + endfacet + facet normal -0.747849 -0.631131 0.2059 + outer loop + vertex 438.795 92.3318 70.5619 + vertex 436.669 95.1 71.3237 + vertex 438.28 92.145 68.1177 + endloop + endfacet + facet normal -0.762358 -0.619329 0.18773 + outer loop + vertex 438.28 92.145 68.1177 + vertex 436.669 95.1 71.3237 + vertex 436.239 94.8809 68.8549 + endloop + endfacet + facet normal -0.691976 -0.688449 0.217272 + outer loop + vertex 440.961 89.9024 69.7616 + vertex 438.795 92.3318 70.5619 + vertex 440.352 89.7457 67.3258 + endloop + endfacet + facet normal -0.707601 -0.677435 0.200953 + outer loop + vertex 440.352 89.7457 67.3258 + vertex 438.795 92.3318 70.5619 + vertex 438.28 92.145 68.1177 + endloop + endfacet + facet normal -0.681858 -0.678824 0.27252 + outer loop + vertex 440.352 89.7457 67.3258 + vertex 438.28 92.145 68.1177 + vertex 439.579 89.9305 65.8507 + endloop + endfacet + facet normal -0.710979 -0.661414 0.238833 + outer loop + vertex 439.579 89.9305 65.8507 + vertex 438.28 92.145 68.1177 + vertex 437.708 92.1966 66.5568 + endloop + endfacet + facet normal -0.742042 -0.621367 0.251548 + outer loop + vertex 438.28 92.145 68.1177 + vertex 436.239 94.8809 68.8549 + vertex 437.708 92.1966 66.5568 + endloop + endfacet + facet normal -0.768267 -0.603379 0.213775 + outer loop + vertex 437.708 92.1966 66.5568 + vertex 436.239 94.8809 68.8549 + vertex 435.71 94.993 67.2695 + endloop + endfacet + facet normal -0.75453 -0.645223 0.119877 + outer loop + vertex 439.664 92.7419 77.1346 + vertex 437.428 95.4993 77.9004 + vertex 439.266 92.5616 73.6592 + endloop + endfacet + facet normal -0.766754 -0.633099 0.106181 + outer loop + vertex 439.266 92.5616 73.6592 + vertex 437.428 95.4993 77.9004 + vertex 437.07 95.3518 74.4383 + endloop + endfacet + facet normal -0.697615 -0.704242 0.13182 + outer loop + vertex 441.902 90.375 76.3347 + vertex 439.664 92.7419 77.1346 + vertex 441.465 90.1562 72.8549 + endloop + endfacet + facet normal -0.712985 -0.691263 0.117508 + outer loop + vertex 441.465 90.1562 72.8549 + vertex 439.664 92.7419 77.1346 + vertex 439.266 92.5616 73.6592 + endloop + endfacet + facet normal -0.698 -0.695409 0.170886 + outer loop + vertex 441.465 90.1562 72.8549 + vertex 439.266 92.5616 73.6592 + vertex 440.961 89.9024 69.7616 + endloop + endfacet + facet normal -0.710415 -0.68563 0.158815 + outer loop + vertex 440.961 89.9024 69.7616 + vertex 439.266 92.5616 73.6592 + vertex 438.795 92.3318 70.5619 + endloop + endfacet + facet normal -0.753023 -0.637806 0.161741 + outer loop + vertex 439.266 92.5616 73.6592 + vertex 437.07 95.3518 74.4383 + vertex 438.795 92.3318 70.5619 + endloop + endfacet + facet normal -0.763912 -0.627851 0.149138 + outer loop + vertex 438.795 92.3318 70.5619 + vertex 437.07 95.3518 74.4383 + vertex 436.669 95.1 71.3237 + endloop + endfacet + facet normal -0.752349 -0.657615 0.038904 + outer loop + vertex 440.062 92.9475 84.5734 + vertex 437.774 95.6069 85.2871 + vertex 439.941 92.8628 80.8018 + endloop + endfacet + facet normal -0.763484 -0.645304 0.025993 + outer loop + vertex 439.941 92.8628 80.8018 + vertex 437.774 95.6069 85.2871 + vertex 437.675 95.573 81.5472 + endloop + endfacet + facet normal -0.687389 -0.724154 0.055649 + outer loop + vertex 442.402 90.6735 83.8851 + vertex 440.062 92.9475 84.5734 + vertex 442.233 90.5381 80.0453 + endloop + endfacet + facet normal -0.705169 -0.707992 0.0385224 + outer loop + vertex 442.233 90.5381 80.0453 + vertex 440.062 92.9475 84.5734 + vertex 439.941 92.8628 80.8018 + endloop + endfacet + facet normal -0.693541 -0.71435 0.0932982 + outer loop + vertex 442.233 90.5381 80.0453 + vertex 439.941 92.8628 80.8018 + vertex 441.902 90.375 76.3347 + endloop + endfacet + facet normal -0.711365 -0.698623 0.076713 + outer loop + vertex 441.902 90.375 76.3347 + vertex 439.941 92.8628 80.8018 + vertex 439.664 92.7419 77.1346 + endloop + endfacet + facet normal -0.754194 -0.651953 0.0784062 + outer loop + vertex 439.941 92.8628 80.8018 + vertex 437.675 95.573 81.5472 + vertex 439.664 92.7419 77.1346 + endloop + endfacet + facet normal -0.766138 -0.639384 0.0649589 + outer loop + vertex 439.664 92.7419 77.1346 + vertex 437.675 95.573 81.5472 + vertex 437.428 95.4993 77.9004 + endloop + endfacet + facet normal -0.744028 -0.667779 -0.0222086 + outer loop + vertex 439.893 93.0376 92.1882 + vertex 437.554 95.6212 92.8644 + vertex 440.035 93.0061 88.3883 + endloop + endfacet + facet normal -0.753763 -0.656249 -0.0343399 + outer loop + vertex 440.035 93.0061 88.3883 + vertex 437.554 95.6212 92.8644 + vertex 437.724 95.6242 89.0761 + endloop + endfacet + facet normal -0.675428 -0.73739 -0.00722597 + outer loop + vertex 442.329 90.8121 91.5472 + vertex 439.893 93.0376 92.1882 + vertex 442.422 90.7642 87.7365 + endloop + endfacet + facet normal -0.687176 -0.726226 -0.0196023 + outer loop + vertex 442.422 90.7642 87.7365 + vertex 439.893 93.0376 92.1882 + vertex 440.035 93.0061 88.3883 + endloop + endfacet + facet normal -0.681277 -0.731727 0.0209292 + outer loop + vertex 442.422 90.7642 87.7365 + vertex 440.035 93.0061 88.3883 + vertex 442.402 90.6735 83.8851 + endloop + endfacet + facet normal -0.696001 -0.718015 0.00608677 + outer loop + vertex 442.402 90.6735 83.8851 + vertex 440.035 93.0061 88.3883 + vertex 440.062 92.9475 84.5734 + endloop + endfacet + facet normal -0.749104 -0.662435 0.00485652 + outer loop + vertex 440.035 93.0061 88.3883 + vertex 437.724 95.6242 89.0761 + vertex 440.062 92.9475 84.5734 + endloop + endfacet + facet normal -0.759028 -0.65102 -0.00708177 + outer loop + vertex 440.062 92.9475 84.5734 + vertex 437.724 95.6242 89.0761 + vertex 437.774 95.6069 85.2871 + endloop + endfacet + facet normal -0.7339 -0.676066 -0.0657753 + outer loop + vertex 439.343 93.0235 99.5989 + vertex 436.948 95.559 100.26 + vertex 439.66 93.0363 95.9307 + endloop + endfacet + facet normal -0.741693 -0.666386 -0.0762971 + outer loop + vertex 439.66 93.0363 95.9307 + vertex 436.948 95.559 100.26 + vertex 437.291 95.5966 96.6007 + endloop + endfacet + facet normal -0.661883 -0.747925 -0.0501946 + outer loop + vertex 441.848 90.8484 98.9786 + vertex 439.343 93.0235 99.5989 + vertex 442.135 90.8411 95.3003 + endloop + endfacet + facet normal -0.670903 -0.739069 -0.06055 + outer loop + vertex 442.135 90.8411 95.3003 + vertex 439.343 93.0235 99.5989 + vertex 439.66 93.0363 95.9307 + endloop + endfacet + facet normal -0.667355 -0.744183 -0.0288099 + outer loop + vertex 442.135 90.8411 95.3003 + vertex 439.66 93.0363 95.9307 + vertex 442.329 90.8121 91.5472 + endloop + endfacet + facet normal -0.679883 -0.732084 -0.0425784 + outer loop + vertex 442.329 90.8121 91.5472 + vertex 439.66 93.0363 95.9307 + vertex 439.893 93.0376 92.1882 + endloop + endfacet + facet normal -0.739178 -0.671921 -0.0462475 + outer loop + vertex 439.66 93.0363 95.9307 + vertex 437.291 95.5966 96.6007 + vertex 439.893 93.0376 92.1882 + endloop + endfacet + facet normal -0.747499 -0.661811 -0.0570182 + outer loop + vertex 439.893 93.0376 92.1882 + vertex 437.291 95.5966 96.6007 + vertex 437.554 95.6212 92.8644 + endloop + endfacet + facet normal -0.722088 -0.684003 -0.10358 + outer loop + vertex 438.469 92.9473 106.861 + vertex 436.036 95.4189 107.497 + vertex 438.945 92.9952 103.221 + endloop + endfacet + facet normal -0.729617 -0.674247 -0.114231 + outer loop + vertex 438.945 92.9952 103.221 + vertex 436.036 95.4189 107.497 + vertex 436.53 95.4984 103.871 + endloop + endfacet + facet normal -0.648575 -0.7564 -0.0849045 + outer loop + vertex 441.011 90.8332 106.274 + vertex 438.469 92.9473 106.861 + vertex 441.472 90.849 102.614 + endloop + endfacet + facet normal -0.657747 -0.747099 -0.095983 + outer loop + vertex 441.472 90.849 102.614 + vertex 438.469 92.9473 106.861 + vertex 438.945 92.9952 103.221 + endloop + endfacet + facet normal -0.655353 -0.752284 -0.0676848 + outer loop + vertex 441.472 90.849 102.614 + vertex 438.945 92.9952 103.221 + vertex 441.848 90.8484 98.9786 + endloop + endfacet + facet normal -0.664664 -0.742979 -0.0787649 + outer loop + vertex 441.848 90.8484 98.9786 + vertex 438.945 92.9952 103.221 + vertex 439.343 93.0235 99.5989 + endloop + endfacet + facet normal -0.728015 -0.680243 -0.0852256 + outer loop + vertex 438.945 92.9952 103.221 + vertex 436.53 95.4984 103.871 + vertex 439.343 93.0235 99.5989 + endloop + endfacet + facet normal -0.73601 -0.670075 -0.0963778 + outer loop + vertex 439.343 93.0235 99.5989 + vertex 436.53 95.4984 103.871 + vertex 436.948 95.559 100.26 + endloop + endfacet + facet normal -0.710862 -0.690322 -0.134648 + outer loop + vertex 437.271 92.7849 114.431 + vertex 434.803 95.2079 115.037 + vertex 437.911 92.8759 110.586 + endloop + endfacet + facet normal -0.717729 -0.681227 -0.144208 + outer loop + vertex 437.911 92.8759 110.586 + vertex 434.803 95.2079 115.037 + vertex 435.461 95.3247 111.209 + endloop + endfacet + facet normal -0.632781 -0.765884 -0.114058 + outer loop + vertex 439.841 90.7406 113.897 + vertex 437.271 92.7849 114.431 + vertex 440.467 90.7999 110.027 + endloop + endfacet + facet normal -0.641763 -0.756693 -0.124721 + outer loop + vertex 440.467 90.7999 110.027 + vertex 437.271 92.7849 114.431 + vertex 437.911 92.8759 110.586 + endloop + endfacet + facet normal -0.640285 -0.761664 -0.0995157 + outer loop + vertex 440.467 90.7999 110.027 + vertex 437.911 92.8759 110.586 + vertex 441.011 90.8332 106.274 + endloop + endfacet + facet normal -0.650493 -0.75124 -0.111793 + outer loop + vertex 441.011 90.8332 106.274 + vertex 437.911 92.8759 110.586 + vertex 438.469 92.9473 106.861 + endloop + endfacet + facet normal -0.717029 -0.686545 -0.120519 + outer loop + vertex 437.911 92.8759 110.586 + vertex 435.461 95.3247 111.209 + vertex 438.469 92.9473 106.861 + endloop + endfacet + facet normal -0.723169 -0.678484 -0.129175 + outer loop + vertex 438.469 92.9473 106.861 + vertex 435.461 95.3247 111.209 + vertex 436.036 95.4189 107.497 + endloop + endfacet + facet normal -0.694731 -0.701481 -0.158978 + outer loop + vertex 435.767 92.555 122.377 + vertex 433.255 94.9151 122.94 + vertex 436.553 92.6816 118.381 + endloop + endfacet + facet normal -0.702839 -0.690706 -0.170123 + outer loop + vertex 436.553 92.6816 118.381 + vertex 433.255 94.9151 122.94 + vertex 434.064 95.0703 118.966 + endloop + endfacet + facet normal -0.616469 -0.775677 -0.135241 + outer loop + vertex 438.373 90.5684 121.892 + vertex 435.767 92.555 122.377 + vertex 439.139 90.6606 117.869 + endloop + endfacet + facet normal -0.627006 -0.764893 -0.147655 + outer loop + vertex 439.139 90.6606 117.869 + vertex 435.767 92.555 122.377 + vertex 436.553 92.6816 118.381 + endloop + endfacet + facet normal -0.62624 -0.769346 -0.126218 + outer loop + vertex 439.139 90.6606 117.869 + vertex 436.553 92.6816 118.381 + vertex 439.841 90.7406 113.897 + endloop + endfacet + facet normal -0.633767 -0.761639 -0.135074 + outer loop + vertex 439.841 90.7406 113.897 + vertex 436.553 92.6816 118.381 + vertex 437.271 92.7849 114.431 + endloop + endfacet + facet normal -0.70264 -0.69643 -0.145884 + outer loop + vertex 436.553 92.6816 118.381 + vertex 434.064 95.0703 118.966 + vertex 437.271 92.7849 114.431 + endloop + endfacet + facet normal -0.711286 -0.684967 -0.157775 + outer loop + vertex 437.271 92.7849 114.431 + vertex 434.064 95.0703 118.966 + vertex 434.803 95.2079 115.037 + endloop + endfacet + facet normal -0.678322 -0.7122 -0.180694 + outer loop + vertex 434.037 92.2664 130.295 + vertex 431.475 94.5764 130.811 + vertex 434.925 92.4192 126.361 + endloop + endfacet + facet normal -0.686626 -0.701053 -0.192536 + outer loop + vertex 434.925 92.4192 126.361 + vertex 431.475 94.5764 130.811 + vertex 432.388 94.7556 126.899 + endloop + endfacet + facet normal -0.598487 -0.78595 -0.155226 + outer loop + vertex 436.693 90.3316 129.854 + vertex 434.037 92.2664 130.295 + vertex 437.554 90.4571 125.897 + endloop + endfacet + facet normal -0.608453 -0.775734 -0.167397 + outer loop + vertex 437.554 90.4571 125.897 + vertex 434.037 92.2664 130.295 + vertex 434.925 92.4192 126.361 + endloop + endfacet + facet normal -0.608102 -0.780321 -0.145984 + outer loop + vertex 437.554 90.4571 125.897 + vertex 434.925 92.4192 126.361 + vertex 438.373 90.5684 121.892 + endloop + endfacet + facet normal -0.617034 -0.771185 -0.156659 + outer loop + vertex 438.373 90.5684 121.892 + vertex 434.925 92.4192 126.361 + vertex 435.767 92.555 122.377 + endloop + endfacet + facet normal -0.686924 -0.706752 -0.169228 + outer loop + vertex 434.925 92.4192 126.361 + vertex 432.388 94.7556 126.899 + vertex 435.767 92.555 122.377 + endloop + endfacet + facet normal -0.69469 -0.696408 -0.180062 + outer loop + vertex 435.767 92.555 122.377 + vertex 432.388 94.7556 126.899 + vertex 433.255 94.9151 122.94 + endloop + endfacet + facet normal -0.660941 -0.723485 -0.199315 + outer loop + vertex 432.127 91.9318 138.062 + vertex 429.509 94.1947 138.532 + vertex 433.106 92.1057 134.186 + endloop + endfacet + facet normal -0.669676 -0.711688 -0.212216 + outer loop + vertex 433.106 92.1057 134.186 + vertex 429.509 94.1947 138.532 + vertex 430.516 94.396 134.677 + endloop + endfacet + facet normal -0.578541 -0.797499 -0.171128 + outer loop + vertex 434.842 90.0466 137.67 + vertex 432.127 91.9318 138.062 + vertex 435.79 90.196 133.768 + endloop + endfacet + facet normal -0.588654 -0.787184 -0.183925 + outer loop + vertex 435.79 90.196 133.768 + vertex 432.127 91.9318 138.062 + vertex 433.106 92.1057 134.186 + endloop + endfacet + facet normal -0.588667 -0.791746 -0.163122 + outer loop + vertex 435.79 90.196 133.768 + vertex 433.106 92.1057 134.186 + vertex 436.693 90.3316 129.854 + endloop + endfacet + facet normal -0.59865 -0.781533 -0.175571 + outer loop + vertex 436.693 90.3316 129.854 + vertex 433.106 92.1057 134.186 + vertex 434.037 92.2664 130.295 + endloop + endfacet + facet normal -0.670391 -0.717247 -0.190087 + outer loop + vertex 433.106 92.1057 134.186 + vertex 430.516 94.396 134.677 + vertex 434.037 92.2664 130.295 + endloop + endfacet + facet normal -0.677871 -0.707171 -0.200994 + outer loop + vertex 434.037 92.2664 130.295 + vertex 430.516 94.396 134.677 + vertex 431.475 94.5764 130.811 + endloop + endfacet + facet normal -0.644959 -0.732843 -0.216722 + outer loop + vertex 430.005 91.5375 145.904 + vertex 427.326 93.7683 146.336 + vertex 431.095 91.7443 141.962 + endloop + endfacet + facet normal -0.652014 -0.723371 -0.227185 + outer loop + vertex 431.095 91.7443 141.962 + vertex 427.326 93.7683 146.336 + vertex 428.447 93.9903 142.411 + endloop + endfacet + facet normal -0.557432 -0.809172 -0.18577 + outer loop + vertex 432.787 89.7004 145.561 + vertex 430.005 91.5375 145.904 + vertex 433.842 89.8837 141.594 + endloop + endfacet + facet normal -0.567657 -0.798898 -0.198816 + outer loop + vertex 433.842 89.8837 141.594 + vertex 430.005 91.5375 145.904 + vertex 431.095 91.7443 141.962 + endloop + endfacet + facet normal -0.568016 -0.803528 -0.178048 + outer loop + vertex 433.842 89.8837 141.594 + vertex 431.095 91.7443 141.962 + vertex 434.842 90.0466 137.67 + endloop + endfacet + facet normal -0.578357 -0.793057 -0.191217 + outer loop + vertex 434.842 90.0466 137.67 + vertex 431.095 91.7443 141.962 + vertex 432.127 91.9318 138.062 + endloop + endfacet + facet normal -0.652943 -0.728331 -0.207847 + outer loop + vertex 431.095 91.7443 141.962 + vertex 428.447 93.9903 142.411 + vertex 432.127 91.9318 138.062 + endloop + endfacet + facet normal -0.660176 -0.718606 -0.218572 + outer loop + vertex 432.127 91.9318 138.062 + vertex 428.447 93.9903 142.411 + vertex 429.509 94.1947 138.532 + endloop + endfacet + facet normal -0.626308 -0.744706 -0.230546 + outer loop + vertex 427.662 91.0849 153.913 + vertex 424.914 93.2748 154.305 + vertex 428.859 91.3218 149.896 + endloop + endfacet + facet normal -0.633674 -0.734953 -0.241457 + outer loop + vertex 428.859 91.3218 149.896 + vertex 424.914 93.2748 154.305 + vertex 426.145 93.5263 150.307 + endloop + endfacet + facet normal -0.536056 -0.821104 -0.196044 + outer loop + vertex 430.516 89.2919 153.618 + vertex 427.662 91.0849 153.913 + vertex 431.675 89.5007 149.573 + endloop + endfacet + facet normal -0.547653 -0.809679 -0.210939 + outer loop + vertex 431.675 89.5007 149.573 + vertex 427.662 91.0849 153.913 + vertex 428.859 91.3218 149.896 + endloop + endfacet + facet normal -0.548249 -0.8139 -0.192327 + outer loop + vertex 431.675 89.5007 149.573 + vertex 428.859 91.3218 149.896 + vertex 432.787 89.7004 145.561 + endloop + endfacet + facet normal -0.556997 -0.805195 -0.203507 + outer loop + vertex 432.787 89.7004 145.561 + vertex 428.859 91.3218 149.896 + vertex 430.005 91.5375 145.904 + endloop + endfacet + facet normal -0.634843 -0.739958 -0.222341 + outer loop + vertex 428.859 91.3218 149.896 + vertex 426.145 93.5263 150.307 + vertex 430.005 91.5375 145.904 + endloop + endfacet + facet normal -0.643898 -0.727892 -0.23573 + outer loop + vertex 430.005 91.5375 145.904 + vertex 426.145 93.5263 150.307 + vertex 427.326 93.7683 146.336 + endloop + endfacet + facet normal -0.607602 -0.756446 -0.242092 + outer loop + vertex 425.157 90.5794 161.923 + vertex 422.336 92.7343 162.27 + vertex 426.425 90.8386 157.931 + endloop + endfacet + facet normal -0.615767 -0.745701 -0.25448 + outer loop + vertex 426.425 90.8386 157.931 + vertex 422.336 92.7343 162.27 + vertex 423.642 93.0112 158.3 + endloop + endfacet + facet normal -0.51697 -0.830297 -0.208206 + outer loop + vertex 428.09 88.8163 161.67 + vertex 425.157 90.5794 161.923 + vertex 429.318 89.0586 157.657 + endloop + endfacet + facet normal -0.526232 -0.821266 -0.220458 + outer loop + vertex 429.318 89.0586 157.657 + vertex 425.157 90.5794 161.923 + vertex 426.425 90.8386 157.931 + endloop + endfacet + facet normal -0.526985 -0.825022 -0.204024 + outer loop + vertex 429.318 89.0586 157.657 + vertex 426.425 90.8386 157.931 + vertex 430.516 89.2919 153.618 + endloop + endfacet + facet normal -0.535334 -0.816852 -0.214873 + outer loop + vertex 430.516 89.2919 153.618 + vertex 426.425 90.8386 157.931 + vertex 427.662 91.0849 153.913 + endloop + endfacet + facet normal -0.617155 -0.750615 -0.236002 + outer loop + vertex 426.425 90.8386 157.931 + vertex 423.642 93.0112 158.3 + vertex 427.662 91.0849 153.913 + endloop + endfacet + facet normal -0.625121 -0.740108 -0.247918 + outer loop + vertex 427.662 91.0849 153.913 + vertex 423.642 93.0112 158.3 + vertex 424.914 93.2748 154.305 + endloop + endfacet + facet normal -0.587703 -0.768103 -0.25421 + outer loop + vertex 422.529 90.0114 169.83 + vertex 419.628 92.1297 170.135 + vertex 423.858 90.2998 165.885 + endloop + endfacet + facet normal -0.596714 -0.756284 -0.268268 + outer loop + vertex 423.858 90.2998 165.885 + vertex 419.628 92.1297 170.135 + vertex 420.999 92.4399 166.212 + endloop + endfacet + facet normal -0.495783 -0.840399 -0.218926 + outer loop + vertex 425.546 88.2843 169.627 + vertex 422.529 90.0114 169.83 + vertex 426.834 88.559 165.656 + endloop + endfacet + facet normal -0.504492 -0.831987 -0.230836 + outer loop + vertex 426.834 88.559 165.656 + vertex 422.529 90.0114 169.83 + vertex 423.858 90.2998 165.885 + endloop + endfacet + facet normal -0.50551 -0.836029 -0.213342 + outer loop + vertex 426.834 88.559 165.656 + vertex 423.858 90.2998 165.885 + vertex 428.09 88.8163 161.67 + endloop + endfacet + facet normal -0.515966 -0.825869 -0.227418 + outer loop + vertex 428.09 88.8163 161.67 + vertex 423.858 90.2998 165.885 + vertex 425.157 90.5794 161.923 + endloop + endfacet + facet normal -0.598348 -0.76128 -0.249863 + outer loop + vertex 423.858 90.2998 165.885 + vertex 420.999 92.4399 166.212 + vertex 425.157 90.5794 161.923 + endloop + endfacet + facet normal -0.605998 -0.751201 -0.261653 + outer loop + vertex 425.157 90.5794 161.923 + vertex 420.999 92.4399 166.212 + vertex 422.336 92.7343 162.27 + endloop + endfacet + facet normal -0.570063 -0.777033 -0.266923 + outer loop + vertex 419.777 89.3753 177.678 + vertex 416.795 91.4745 177.936 + vertex 421.166 89.7009 173.763 + endloop + endfacet + facet normal -0.576971 -0.767998 -0.277999 + outer loop + vertex 421.166 89.7009 173.763 + vertex 416.795 91.4745 177.936 + vertex 418.225 91.8081 174.045 + endloop + endfacet + facet normal -0.475724 -0.849009 -0.229938 + outer loop + vertex 422.883 87.6764 177.525 + vertex 419.777 89.3753 177.678 + vertex 424.227 87.9898 173.586 + endloop + endfacet + facet normal -0.484058 -0.840987 -0.241719 + outer loop + vertex 424.227 87.9898 173.586 + vertex 419.777 89.3753 177.678 + vertex 421.166 89.7009 173.763 + endloop + endfacet + facet normal -0.485321 -0.845021 -0.224506 + outer loop + vertex 424.227 87.9898 173.586 + vertex 421.166 89.7009 173.763 + vertex 425.546 88.2843 169.627 + endloop + endfacet + facet normal -0.494566 -0.836103 -0.23735 + outer loop + vertex 425.546 88.2843 169.627 + vertex 421.166 89.7009 173.763 + vertex 422.529 90.0114 169.83 + endloop + endfacet + facet normal -0.578638 -0.772541 -0.261455 + outer loop + vertex 421.166 89.7009 173.763 + vertex 418.225 91.8081 174.045 + vertex 422.529 90.0114 169.83 + endloop + endfacet + facet normal -0.585941 -0.76299 -0.272982 + outer loop + vertex 422.529 90.0114 169.83 + vertex 418.225 91.8081 174.045 + vertex 419.628 92.1297 170.135 + endloop + endfacet + facet normal -0.550714 -0.787441 -0.276859 + outer loop + vertex 416.936 88.6878 185.412 + vertex 413.866 90.7623 185.62 + vertex 418.367 89.0406 181.563 + endloop + endfacet + facet normal -0.557364 -0.778744 -0.287929 + outer loop + vertex 418.367 89.0406 181.563 + vertex 413.866 90.7623 185.62 + vertex 415.34 91.121 181.796 + endloop + endfacet + facet normal -0.456228 -0.85737 -0.238272 + outer loop + vertex 420.137 87.0139 185.306 + vertex 416.936 88.6878 185.412 + vertex 421.52 87.3545 181.433 + endloop + endfacet + facet normal -0.464525 -0.84939 -0.250505 + outer loop + vertex 421.52 87.3545 181.433 + vertex 416.936 88.6878 185.412 + vertex 418.367 89.0406 181.563 + endloop + endfacet + facet normal -0.466038 -0.853579 -0.232835 + outer loop + vertex 421.52 87.3545 181.433 + vertex 418.367 89.0406 181.563 + vertex 422.883 87.6764 177.525 + endloop + endfacet + facet normal -0.474519 -0.845442 -0.24507 + outer loop + vertex 422.883 87.6764 177.525 + vertex 418.367 89.0406 181.563 + vertex 419.777 89.3753 177.678 + endloop + endfacet + facet normal -0.559331 -0.78356 -0.270524 + outer loop + vertex 418.367 89.0406 181.563 + vertex 415.34 91.121 181.796 + vertex 419.777 89.3753 177.678 + endloop + endfacet + facet normal -0.56812 -0.77207 -0.284865 + outer loop + vertex 419.777 89.3753 177.678 + vertex 415.34 91.121 181.796 + vertex 416.795 91.4745 177.936 + endloop + endfacet + facet normal -0.532606 -0.796279 -0.286829 + outer loop + vertex 414.012 87.9324 193.027 + vertex 410.852 89.9912 193.178 + vertex 415.484 88.3151 189.231 + endloop + endfacet + facet normal -0.540719 -0.785541 -0.300911 + outer loop + vertex 415.484 88.3151 189.231 + vertex 410.852 89.9912 193.178 + vertex 412.371 90.389 189.411 + endloop + endfacet + facet normal -0.437331 -0.864634 -0.247286 + outer loop + vertex 417.31 86.2787 192.977 + vertex 414.012 87.9324 193.027 + vertex 418.733 86.6527 189.153 + endloop + endfacet + facet normal -0.444942 -0.857295 -0.258983 + outer loop + vertex 418.733 86.6527 189.153 + vertex 414.012 87.9324 193.027 + vertex 415.484 88.3151 189.231 + endloop + endfacet + facet normal -0.446442 -0.860944 -0.243856 + outer loop + vertex 418.733 86.6527 189.153 + vertex 415.484 88.3151 189.231 + vertex 420.137 87.0139 185.306 + endloop + endfacet + facet normal -0.45458 -0.853093 -0.256106 + outer loop + vertex 420.137 87.0139 185.306 + vertex 415.484 88.3151 189.231 + vertex 416.936 88.6878 185.412 + endloop + endfacet + facet normal -0.542967 -0.790416 -0.2836 + outer loop + vertex 415.484 88.3151 189.231 + vertex 412.371 90.389 189.411 + vertex 416.936 88.6878 185.412 + endloop + endfacet + facet normal -0.54872 -0.782833 -0.293392 + outer loop + vertex 416.936 88.6878 185.412 + vertex 412.371 90.389 189.411 + vertex 413.866 90.7623 185.62 + endloop + endfacet + facet normal -0.514229 -0.804023 -0.298522 + outer loop + vertex 411.019 87.1077 200.514 + vertex 407.767 89.1511 200.612 + vertex 412.523 87.5287 196.79 + endloop + endfacet + facet normal -0.520782 -0.795262 -0.310394 + outer loop + vertex 412.523 87.5287 196.79 + vertex 407.767 89.1511 200.612 + vertex 409.317 89.5794 196.913 + endloop + endfacet + facet normal -0.41901 -0.870471 -0.258284 + outer loop + vertex 414.419 85.4706 200.516 + vertex 411.019 87.1077 200.514 + vertex 415.871 85.8842 196.766 + endloop + endfacet + facet normal -0.426052 -0.863578 -0.269652 + outer loop + vertex 415.871 85.8842 196.766 + vertex 411.019 87.1077 200.514 + vertex 412.523 87.5287 196.79 + endloop + endfacet + facet normal -0.427962 -0.86771 -0.252839 + outer loop + vertex 415.871 85.8842 196.766 + vertex 412.523 87.5287 196.79 + vertex 417.31 86.2787 192.977 + endloop + endfacet + facet normal -0.435478 -0.860413 -0.264668 + outer loop + vertex 417.31 86.2787 192.977 + vertex 412.523 87.5287 196.79 + vertex 414.012 87.9324 193.027 + endloop + endfacet + facet normal -0.523281 -0.80022 -0.292959 + outer loop + vertex 412.523 87.5287 196.79 + vertex 409.317 89.5794 196.913 + vertex 414.012 87.9324 193.027 + endloop + endfacet + facet normal -0.530127 -0.791134 -0.305078 + outer loop + vertex 414.012 87.9324 193.027 + vertex 409.317 89.5794 196.913 + vertex 410.852 89.9912 193.178 + endloop + endfacet + facet normal -0.496448 -0.811697 -0.307711 + outer loop + vertex 407.965 86.2239 207.867 + vertex 404.618 88.2559 207.906 + vertex 409.5 86.6738 204.204 + endloop + endfacet + facet normal -0.502993 -0.802814 -0.320136 + outer loop + vertex 409.5 86.6738 204.204 + vertex 404.618 88.2559 207.906 + vertex 406.201 88.7122 204.275 + endloop + endfacet + facet normal -0.402565 -0.874845 -0.269422 + outer loop + vertex 411.465 84.5906 207.941 + vertex 407.965 86.2239 207.867 + vertex 412.952 85.0458 204.241 + endloop + endfacet + facet normal -0.407342 -0.870082 -0.277541 + outer loop + vertex 412.952 85.0458 204.241 + vertex 407.965 86.2239 207.867 + vertex 409.5 86.6738 204.204 + endloop + endfacet + facet normal -0.409474 -0.874216 -0.260918 + outer loop + vertex 412.952 85.0458 204.241 + vertex 409.5 86.6738 204.204 + vertex 414.419 85.4706 200.516 + endloop + endfacet + facet normal -0.417163 -0.866658 -0.273639 + outer loop + vertex 414.419 85.4706 200.516 + vertex 409.5 86.6738 204.204 + vertex 411.019 87.1077 200.514 + endloop + endfacet + facet normal -0.505657 -0.807724 -0.303138 + outer loop + vertex 409.5 86.6738 204.204 + vertex 406.201 88.7122 204.275 + vertex 411.019 87.1077 200.514 + endloop + endfacet + facet normal -0.511825 -0.799422 -0.314579 + outer loop + vertex 411.019 87.1077 200.514 + vertex 406.201 88.7122 204.275 + vertex 407.767 89.1511 200.612 + endloop + endfacet + facet normal -0.48067 -0.815934 -0.321259 + outer loop + vertex 404.863 85.2537 215.07 + vertex 401.424 87.2919 215.038 + vertex 406.415 85.7467 211.495 + endloop + endfacet + facet normal -0.484986 -0.809878 -0.32998 + outer loop + vertex 406.415 85.7467 211.495 + vertex 401.424 87.2919 215.038 + vertex 403.022 87.777 211.5 + endloop + endfacet + facet normal -0.384852 -0.879418 -0.280201 + outer loop + vertex 408.47 83.6275 215.22 + vertex 404.863 85.2537 215.07 + vertex 409.97 84.1218 211.609 + endloop + endfacet + facet normal -0.390245 -0.873855 -0.289975 + outer loop + vertex 409.97 84.1218 211.609 + vertex 404.863 85.2537 215.07 + vertex 406.415 85.7467 211.495 + endloop + endfacet + facet normal -0.392849 -0.878325 -0.272424 + outer loop + vertex 409.97 84.1218 211.609 + vertex 406.415 85.7467 211.495 + vertex 411.465 84.5906 207.941 + endloop + endfacet + facet normal -0.400322 -0.870765 -0.2855 + outer loop + vertex 411.465 84.5906 207.941 + vertex 406.415 85.7467 211.495 + vertex 407.965 86.2239 207.867 + endloop + endfacet + facet normal -0.487539 -0.814179 -0.315307 + outer loop + vertex 406.415 85.7467 211.495 + vertex 403.022 87.777 211.5 + vertex 407.965 86.2239 207.867 + endloop + endfacet + facet normal -0.493331 -0.806199 -0.3266 + outer loop + vertex 407.965 86.2239 207.867 + vertex 403.022 87.777 211.5 + vertex 404.618 88.2559 207.906 + endloop + endfacet + facet normal -0.462997 -0.82158 -0.332625 + outer loop + vertex 401.753 84.2284 222.048 + vertex 398.217 86.2642 221.942 + vertex 403.312 84.752 218.585 + endloop + endfacet + facet normal -0.467255 -0.815339 -0.341899 + outer loop + vertex 403.312 84.752 218.585 + vertex 398.217 86.2642 221.942 + vertex 399.822 86.7806 218.517 + endloop + endfacet + facet normal -0.371197 -0.881073 -0.293128 + outer loop + vertex 405.464 82.5898 222.275 + vertex 401.753 84.2284 222.048 + vertex 406.972 83.1201 218.772 + endloop + endfacet + facet normal -0.375475 -0.876418 -0.301514 + outer loop + vertex 406.972 83.1201 218.772 + vertex 401.753 84.2284 222.048 + vertex 403.312 84.752 218.585 + endloop + endfacet + facet normal -0.378185 -0.880646 -0.285376 + outer loop + vertex 406.972 83.1201 218.772 + vertex 403.312 84.752 218.585 + vertex 408.47 83.6275 215.22 + endloop + endfacet + facet normal -0.382693 -0.87589 -0.293876 + outer loop + vertex 408.47 83.6275 215.22 + vertex 403.312 84.752 218.585 + vertex 404.863 85.2537 215.07 + endloop + endfacet + facet normal -0.470558 -0.820445 -0.324724 + outer loop + vertex 403.312 84.752 218.585 + vertex 399.822 86.7806 218.517 + vertex 404.863 85.2537 215.07 + endloop + endfacet + facet normal -0.477377 -0.810659 -0.339033 + outer loop + vertex 404.863 85.2537 215.07 + vertex 399.822 86.7806 218.517 + vertex 401.424 87.2919 215.038 + endloop + endfacet + facet normal -0.447798 -0.823881 -0.347415 + outer loop + vertex 398.577 83.1111 228.888 + vertex 394.95 85.1615 228.7 + vertex 400.175 83.6791 225.482 + endloop + endfacet + facet normal -0.451098 -0.818779 -0.355121 + outer loop + vertex 400.175 83.6791 225.482 + vertex 394.95 85.1615 228.7 + vertex 396.591 85.7166 225.336 + endloop + endfacet + facet normal -0.354919 -0.884108 -0.303952 + outer loop + vertex 402.39 81.4694 229.211 + vertex 398.577 83.1111 228.888 + vertex 403.936 82.0372 225.754 + endloop + endfacet + facet normal -0.360369 -0.877868 -0.315409 + outer loop + vertex 403.936 82.0372 225.754 + vertex 398.577 83.1111 228.888 + vertex 400.175 83.6791 225.482 + endloop + endfacet + facet normal -0.363366 -0.882126 -0.299697 + outer loop + vertex 403.936 82.0372 225.754 + vertex 400.175 83.6791 225.482 + vertex 405.464 82.5898 222.275 + endloop + endfacet + facet normal -0.368245 -0.876666 -0.3096 + outer loop + vertex 405.464 82.5898 222.275 + vertex 400.175 83.6791 225.482 + vertex 401.753 84.2284 222.048 + endloop + endfacet + facet normal -0.454214 -0.823223 -0.340577 + outer loop + vertex 400.175 83.6791 225.482 + vertex 396.591 85.7166 225.336 + vertex 401.753 84.2284 222.048 + endloop + endfacet + facet normal -0.459115 -0.815829 -0.351619 + outer loop + vertex 401.753 84.2284 222.048 + vertex 396.591 85.7166 225.336 + vertex 398.217 86.2642 221.942 + endloop + endfacet + facet normal -0.430863 -0.828404 -0.357915 + outer loop + vertex 395.373 81.9473 235.524 + vertex 391.656 83.9998 235.249 + vertex 396.972 82.5323 232.245 + endloop + endfacet + facet normal -0.43578 -0.820202 -0.370627 + outer loop + vertex 396.972 82.5323 232.245 + vertex 391.656 83.9998 235.249 + vertex 393.301 84.5874 232.013 + endloop + endfacet + facet normal -0.343061 -0.883502 -0.318957 + outer loop + vertex 399.28 80.2816 235.935 + vertex 395.373 81.9473 235.524 + vertex 400.832 80.878 232.615 + endloop + endfacet + facet normal -0.34595 -0.879908 -0.325699 + outer loop + vertex 400.832 80.878 232.615 + vertex 395.373 81.9473 235.524 + vertex 396.972 82.5323 232.245 + endloop + endfacet + facet normal -0.348661 -0.883415 -0.313071 + outer loop + vertex 400.832 80.878 232.615 + vertex 396.972 82.5323 232.245 + vertex 402.39 81.4694 229.211 + endloop + endfacet + facet normal -0.351716 -0.879788 -0.319796 + outer loop + vertex 402.39 81.4694 229.211 + vertex 396.972 82.5323 232.245 + vertex 398.577 83.1111 228.888 + endloop + endfacet + facet normal -0.440049 -0.825802 -0.352715 + outer loop + vertex 396.972 82.5323 232.245 + vertex 393.301 84.5874 232.013 + vertex 398.577 83.1111 228.888 + endloop + endfacet + facet normal -0.444261 -0.819057 -0.363011 + outer loop + vertex 398.577 83.1111 228.888 + vertex 393.301 84.5874 232.013 + vertex 394.95 85.1615 228.7 + endloop + endfacet + facet normal -0.417711 -0.82833 -0.373345 + outer loop + vertex 392.177 80.7493 241.833 + vertex 388.383 82.8243 241.475 + vertex 393.778 81.349 238.712 + endloop + endfacet + facet normal -0.421228 -0.821788 -0.383707 + outer loop + vertex 393.778 81.349 238.712 + vertex 388.383 82.8243 241.475 + vertex 390.024 83.4214 238.394 + endloop + endfacet + facet normal -0.330731 -0.883127 -0.332723 + outer loop + vertex 396.173 79.0658 242.329 + vertex 392.177 80.7493 241.833 + vertex 397.731 79.6753 239.163 + endloop + endfacet + facet normal -0.333471 -0.879337 -0.339946 + outer loop + vertex 397.731 79.6753 239.163 + vertex 392.177 80.7493 241.833 + vertex 393.778 81.349 238.712 + endloop + endfacet + facet normal -0.336454 -0.882981 -0.327327 + outer loop + vertex 397.731 79.6753 239.163 + vertex 393.778 81.349 238.712 + vertex 399.28 80.2816 235.935 + endloop + endfacet + facet normal -0.339471 -0.879002 -0.334836 + outer loop + vertex 399.28 80.2816 235.935 + vertex 393.778 81.349 238.712 + vertex 395.373 81.9473 235.524 + endloop + endfacet + facet normal -0.425341 -0.826831 -0.368014 + outer loop + vertex 393.778 81.349 238.712 + vertex 390.024 83.4214 238.394 + vertex 395.373 81.9473 235.524 + endloop + endfacet + facet normal -0.427136 -0.823675 -0.37298 + outer loop + vertex 395.373 81.9473 235.524 + vertex 390.024 83.4214 238.394 + vertex 391.656 83.9998 235.249 + endloop + endfacet + facet normal -0.405609 -0.825933 -0.391555 + outer loop + vertex 388.882 79.4889 247.991 + vertex 385.024 81.5937 247.548 + vertex 390.547 80.1268 244.921 + endloop + endfacet + facet normal -0.407103 -0.822882 -0.3964 + outer loop + vertex 390.547 80.1268 244.921 + vertex 385.024 81.5937 247.548 + vertex 386.718 82.2136 244.521 + endloop + endfacet + facet normal -0.318782 -0.880334 -0.35127 + outer loop + vertex 392.952 77.7782 248.585 + vertex 388.882 79.4889 247.991 + vertex 394.582 78.4326 245.465 + endloop + endfacet + facet normal -0.320466 -0.877759 -0.356147 + outer loop + vertex 394.582 78.4326 245.465 + vertex 388.882 79.4889 247.991 + vertex 390.547 80.1268 244.921 + endloop + endfacet + facet normal -0.324032 -0.881868 -0.342509 + outer loop + vertex 394.582 78.4326 245.465 + vertex 390.547 80.1268 244.921 + vertex 396.173 79.0658 242.329 + endloop + endfacet + facet normal -0.326561 -0.878179 -0.349513 + outer loop + vertex 396.173 79.0658 242.329 + vertex 390.547 80.1268 244.921 + vertex 392.177 80.7493 241.833 + endloop + endfacet + facet normal -0.410734 -0.827103 -0.383665 + outer loop + vertex 390.547 80.1268 244.921 + vertex 386.718 82.2136 244.521 + vertex 392.177 80.7493 241.833 + endloop + endfacet + facet normal -0.412993 -0.822693 -0.390656 + outer loop + vertex 392.177 80.7493 241.833 + vertex 386.718 82.2136 244.521 + vertex 388.383 82.8243 241.475 + endloop + endfacet + facet normal -0.393254 -0.823956 -0.407979 + outer loop + vertex 385.496 78.1878 253.989 + vertex 381.582 80.3185 253.458 + vertex 387.194 78.8439 251.027 + endloop + endfacet + facet normal -0.39425 -0.821633 -0.411687 + outer loop + vertex 387.194 78.8439 251.027 + vertex 381.582 80.3185 253.458 + vertex 383.303 80.9548 250.54 + endloop + endfacet + facet normal -0.307211 -0.879375 -0.363759 + outer loop + vertex 389.643 76.4553 254.675 + vertex 385.496 78.1878 253.989 + vertex 391.301 77.1193 251.669 + endloop + endfacet + facet normal -0.309517 -0.875375 -0.371372 + outer loop + vertex 391.301 77.1193 251.669 + vertex 385.496 78.1878 253.989 + vertex 387.194 78.8439 251.027 + endloop + endfacet + facet normal -0.313919 -0.880159 -0.356054 + outer loop + vertex 391.301 77.1193 251.669 + vertex 387.194 78.8439 251.027 + vertex 392.952 77.7782 248.585 + endloop + endfacet + facet normal -0.315847 -0.877058 -0.361952 + outer loop + vertex 392.952 77.7782 248.585 + vertex 387.194 78.8439 251.027 + vertex 388.882 79.4889 247.991 + endloop + endfacet + facet normal -0.398719 -0.826545 -0.397298 + outer loop + vertex 387.194 78.8439 251.027 + vertex 383.303 80.9548 250.54 + vertex 388.882 79.4889 247.991 + endloop + endfacet + facet normal -0.401272 -0.821035 -0.406056 + outer loop + vertex 388.882 79.4889 247.991 + vertex 383.303 80.9548 250.54 + vertex 385.024 81.5937 247.548 + endloop + endfacet + facet normal -0.381611 -0.822146 -0.422432 + outer loop + vertex 382.14 76.9086 259.595 + vertex 378.176 79.0621 258.984 + vertex 383.812 77.5438 256.848 + endloop + endfacet + facet normal -0.383088 -0.817844 -0.429389 + outer loop + vertex 383.812 77.5438 256.848 + vertex 378.176 79.0621 258.984 + vertex 379.873 79.6897 256.275 + endloop + endfacet + facet normal -0.299666 -0.873737 -0.383125 + outer loop + vertex 386.329 75.1401 260.352 + vertex 382.14 76.9086 259.595 + vertex 387.985 75.7909 257.572 + endloop + endfacet + facet normal -0.300007 -0.873009 -0.384514 + outer loop + vertex 387.985 75.7909 257.572 + vertex 382.14 76.9086 259.595 + vertex 383.812 77.5438 256.848 + endloop + endfacet + facet normal -0.30315 -0.876314 -0.374398 + outer loop + vertex 387.985 75.7909 257.572 + vertex 383.812 77.5438 256.848 + vertex 389.643 76.4553 254.675 + endloop + endfacet + facet normal -0.303576 -0.875503 -0.375948 + outer loop + vertex 389.643 76.4553 254.675 + vertex 383.812 77.5438 256.848 + vertex 385.496 78.1878 253.989 + endloop + endfacet + facet normal -0.388279 -0.823279 -0.414066 + outer loop + vertex 383.812 77.5438 256.848 + vertex 379.873 79.6897 256.275 + vertex 385.496 78.1878 253.989 + endloop + endfacet + facet normal -0.389554 -0.81999 -0.419361 + outer loop + vertex 385.496 78.1878 253.989 + vertex 379.873 79.6897 256.275 + vertex 381.582 80.3185 253.458 + endloop + endfacet + facet normal -0.371267 -0.812728 -0.449037 + outer loop + vertex 378.793 75.6358 264.775 + vertex 374.82 77.8203 264.107 + vertex 380.467 76.2741 262.236 + endloop + endfacet + facet normal -0.371241 -0.812828 -0.448877 + outer loop + vertex 380.467 76.2741 262.236 + vertex 374.82 77.8203 264.107 + vertex 376.493 78.444 261.594 + endloop + endfacet + facet normal -0.290448 -0.865882 -0.407294 + outer loop + vertex 382.976 73.8447 265.6 + vertex 378.793 75.6358 264.775 + vertex 384.657 74.4929 263.023 + endloop + endfacet + facet normal -0.2908 -0.864909 -0.409106 + outer loop + vertex 384.657 74.4929 263.023 + vertex 378.793 75.6358 264.775 + vertex 380.467 76.2741 262.236 + endloop + endfacet + facet normal -0.295384 -0.869673 -0.395496 + outer loop + vertex 384.657 74.4929 263.023 + vertex 380.467 76.2741 262.236 + vertex 386.329 75.1401 260.352 + endloop + endfacet + facet normal -0.2955 -0.869392 -0.396026 + outer loop + vertex 386.329 75.1401 260.352 + vertex 380.467 76.2741 262.236 + vertex 382.14 76.9086 259.595 + endloop + endfacet + facet normal -0.376353 -0.818056 -0.434905 + outer loop + vertex 380.467 76.2741 262.236 + vertex 376.493 78.444 261.594 + vertex 382.14 76.9086 259.595 + endloop + endfacet + facet normal -0.37666 -0.817036 -0.436554 + outer loop + vertex 382.14 76.9086 259.595 + vertex 376.493 78.444 261.594 + vertex 378.176 79.0621 258.984 + endloop + endfacet + facet normal -0.3609 -0.805327 -0.470319 + outer loop + vertex 375.641 74.4202 269.347 + vertex 371.679 76.6204 268.619 + vertex 377.157 75.0055 267.181 + endloop + endfacet + facet normal -0.361084 -0.803887 -0.472635 + outer loop + vertex 377.157 75.0055 267.181 + vertex 371.679 76.6204 268.619 + vertex 373.189 77.1978 266.483 + endloop + endfacet + facet normal -0.283499 -0.857696 -0.428936 + outer loop + vertex 379.807 72.5791 270.274 + vertex 375.641 74.4202 269.347 + vertex 381.327 73.1875 268.053 + endloop + endfacet + facet normal -0.283638 -0.857021 -0.430191 + outer loop + vertex 381.327 73.1875 268.053 + vertex 375.641 74.4202 269.347 + vertex 377.157 75.0055 267.181 + endloop + endfacet + facet normal -0.286379 -0.859771 -0.422824 + outer loop + vertex 381.327 73.1875 268.053 + vertex 377.157 75.0055 267.181 + vertex 382.976 73.8447 265.6 + endloop + endfacet + facet normal -0.285937 -0.861247 -0.420111 + outer loop + vertex 382.976 73.8447 265.6 + vertex 377.157 75.0055 267.181 + vertex 378.793 75.6358 264.775 + endloop + endfacet + facet normal -0.365834 -0.808676 -0.460661 + outer loop + vertex 377.157 75.0055 267.181 + vertex 373.189 77.1978 266.483 + vertex 378.793 75.6358 264.775 + endloop + endfacet + facet normal -0.366084 -0.807455 -0.4626 + outer loop + vertex 378.793 75.6358 264.775 + vertex 373.189 77.1978 266.483 + vertex 374.82 77.8203 264.107 + endloop + endfacet + facet normal -0.36053 -0.805124 -0.470949 + outer loop + vertex 373.347 73.6789 272.348 + vertex 369.412 75.8989 271.565 + vertex 374.34 73.955 271.116 + endloop + endfacet + facet normal -0.36036 -0.804362 -0.47238 + outer loop + vertex 374.34 73.955 271.116 + vertex 369.412 75.8989 271.565 + vertex 370.396 76.1692 270.354 + endloop + endfacet + facet normal -0.286197 -0.856643 -0.429247 + outer loop + vertex 377.496 71.8044 273.322 + vertex 373.347 73.6789 272.348 + vertex 378.495 72.0921 272.082 + endloop + endfacet + facet normal -0.286718 -0.859275 -0.423603 + outer loop + vertex 378.495 72.0921 272.082 + vertex 373.347 73.6789 272.348 + vertex 374.34 73.955 271.116 + endloop + endfacet + facet normal -0.282128 -0.855022 -0.435133 + outer loop + vertex 378.495 72.0921 272.082 + vertex 374.34 73.955 271.116 + vertex 379.807 72.5791 270.274 + endloop + endfacet + facet normal -0.282067 -0.856315 -0.432624 + outer loop + vertex 379.807 72.5791 270.274 + vertex 374.34 73.955 271.116 + vertex 375.641 74.4202 269.347 + endloop + endfacet + facet normal -0.359129 -0.80318 -0.475318 + outer loop + vertex 374.34 73.955 271.116 + vertex 370.396 76.1692 270.354 + vertex 375.641 74.4202 269.347 + endloop + endfacet + facet normal -0.359132 -0.803576 -0.474647 + outer loop + vertex 375.641 74.4202 269.347 + vertex 370.396 76.1692 270.354 + vertex 371.679 76.6204 268.619 + endloop + endfacet + facet normal -0.347817 -0.796846 -0.494024 + outer loop + vertex 372.629 73.3801 273.373 + vertex 368.726 75.5949 272.548 + vertex 372.732 73.5362 273.048 + endloop + endfacet + facet normal -0.324029 -0.765569 -0.555797 + outer loop + vertex 372.732 73.5362 273.048 + vertex 368.726 75.5949 272.548 + vertex 368.817 75.7824 272.237 + endloop + endfacet + facet normal -0.281661 -0.858378 -0.428783 + outer loop + vertex 376.81 71.5295 274.331 + vertex 372.629 73.3801 273.373 + vertex 376.893 71.6597 274.016 + endloop + endfacet + facet normal -0.263306 -0.833905 -0.485049 + outer loop + vertex 376.893 71.6597 274.016 + vertex 372.629 73.3801 273.373 + vertex 372.732 73.5362 273.048 + endloop + endfacet + facet normal -0.286815 -0.856852 -0.428418 + outer loop + vertex 376.893 71.6597 274.016 + vertex 372.732 73.5362 273.048 + vertex 377.496 71.8044 273.322 + endloop + endfacet + facet normal -0.287139 -0.857504 -0.426893 + outer loop + vertex 377.496 71.8044 273.322 + vertex 372.732 73.5362 273.048 + vertex 373.347 73.6789 272.348 + endloop + endfacet + facet normal -0.359937 -0.800476 -0.479253 + outer loop + vertex 372.732 73.5362 273.048 + vertex 368.817 75.7824 272.237 + vertex 373.347 73.6789 272.348 + endloop + endfacet + facet normal -0.364004 -0.808359 -0.462662 + outer loop + vertex 373.347 73.6789 272.348 + vertex 368.817 75.7824 272.237 + vertex 369.412 75.8989 271.565 + endloop + endfacet + facet normal -0.221322 -0.810784 -0.54189 + outer loop + vertex 377.367 71.2526 274.517 + vertex 373.227 73.0067 273.584 + vertex 376.81 71.5295 274.331 + endloop + endfacet + facet normal -0.060025 -0.562578 -0.824562 + outer loop + vertex 376.81 71.5295 274.331 + vertex 373.227 73.0067 273.584 + vertex 372.629 73.3801 273.373 + endloop + endfacet + facet normal -0.329606 -0.806254 -0.491237 + outer loop + vertex 373.227 73.0067 273.584 + vertex 369.343 75.1015 272.752 + vertex 372.629 73.3801 273.373 + endloop + endfacet + facet normal -0.0709013 -0.455344 -0.887488 + outer loop + vertex 372.629 73.3801 273.373 + vertex 369.343 75.1015 272.752 + vertex 368.726 75.5949 272.548 + endloop + endfacet + facet normal -0.83871 -0.496245 0.22429 + outer loop + vertex 433.662 98.2314 67.9469 + vertex 431.698 101.816 68.5325 + vertex 432.994 99.0905 67.3496 + endloop + endfacet + facet normal -0.863998 -0.47868 0.156116 + outer loop + vertex 432.994 99.0905 67.3496 + vertex 431.698 101.816 68.5325 + vertex 431.279 102.332 67.7991 + endloop + endfacet + facet normal -0.798581 -0.554092 0.235057 + outer loop + vertex 435.71 94.993 67.2695 + vertex 433.662 98.2314 67.9469 + vertex 434.862 95.9607 66.6715 + endloop + endfacet + facet normal -0.830843 -0.531595 0.164643 + outer loop + vertex 434.862 95.9607 66.6715 + vertex 433.662 98.2314 67.9469 + vertex 432.994 99.0905 67.3496 + endloop + endfacet + facet normal -0.834767 -0.522447 0.173822 + outer loop + vertex 434.591 98.1963 72.0377 + vertex 432.599 101.583 72.6473 + vertex 434.188 98.013 69.5487 + endloop + endfacet + facet normal -0.846589 -0.509745 0.153125 + outer loop + vertex 434.188 98.013 69.5487 + vertex 432.599 101.583 72.6473 + vertex 432.182 101.523 70.1434 + endloop + endfacet + facet normal -0.794581 -0.576805 0.18957 + outer loop + vertex 436.669 95.1 71.3237 + vertex 434.591 98.1963 72.0377 + vertex 436.239 94.8809 68.8549 + endloop + endfacet + facet normal -0.806139 -0.566057 0.172392 + outer loop + vertex 436.239 94.8809 68.8549 + vertex 434.591 98.1963 72.0377 + vertex 434.188 98.013 69.5487 + endloop + endfacet + facet normal -0.791821 -0.568142 0.22413 + outer loop + vertex 436.239 94.8809 68.8549 + vertex 434.188 98.013 69.5487 + vertex 435.71 94.993 67.2695 + endloop + endfacet + facet normal -0.811151 -0.552804 0.190899 + outer loop + vertex 435.71 94.993 67.2695 + vertex 434.188 98.013 69.5487 + vertex 433.662 98.2314 67.9469 + endloop + endfacet + facet normal -0.834622 -0.511565 0.204225 + outer loop + vertex 434.188 98.013 69.5487 + vertex 432.182 101.523 70.1434 + vertex 433.662 98.2314 67.9469 + endloop + endfacet + facet normal -0.853012 -0.494633 0.166461 + outer loop + vertex 433.662 98.2314 67.9469 + vertex 432.182 101.523 70.1434 + vertex 431.698 101.816 68.5325 + endloop + endfacet + facet normal -0.841707 -0.531049 0.097555 + outer loop + vertex 435.247 98.6089 78.609 + vertex 433.197 101.974 79.2466 + vertex 434.941 98.4582 75.1533 + endloop + endfacet + facet normal -0.847499 -0.523369 0.0884896 + outer loop + vertex 434.941 98.4582 75.1533 + vertex 433.197 101.974 79.2466 + vertex 432.934 101.816 75.789 + endloop + endfacet + facet normal -0.802184 -0.587248 0.107888 + outer loop + vertex 437.428 95.4993 77.9004 + vertex 435.247 98.6089 78.609 + vertex 437.07 95.3518 74.4383 + endloop + endfacet + facet normal -0.810468 -0.577724 0.0968293 + outer loop + vertex 437.07 95.3518 74.4383 + vertex 435.247 98.6089 78.609 + vertex 434.941 98.4582 75.1533 + endloop + endfacet + facet normal -0.799112 -0.582175 0.149979 + outer loop + vertex 437.07 95.3518 74.4383 + vertex 434.941 98.4582 75.1533 + vertex 436.669 95.1 71.3237 + endloop + endfacet + facet normal -0.807281 -0.573616 0.138788 + outer loop + vertex 436.669 95.1 71.3237 + vertex 434.941 98.4582 75.1533 + vertex 434.591 98.1963 72.0377 + endloop + endfacet + facet normal -0.838319 -0.527325 0.13838 + outer loop + vertex 434.941 98.4582 75.1533 + vertex 432.934 101.816 75.789 + vertex 434.591 98.1963 72.0377 + endloop + endfacet + facet normal -0.844433 -0.519995 0.128603 + outer loop + vertex 434.591 98.1963 72.0377 + vertex 432.934 101.816 75.789 + vertex 432.599 101.583 72.6473 + endloop + endfacet + facet normal -0.842253 -0.538833 0.0163709 + outer loop + vertex 435.543 98.6313 85.9601 + vertex 433.426 101.959 86.5714 + vertex 435.462 98.6436 82.2358 + endloop + endfacet + facet normal -0.848831 -0.528636 0.0054842 + outer loop + vertex 435.462 98.6436 82.2358 + vertex 433.426 101.959 86.5714 + vertex 433.373 102.006 82.8624 + endloop + endfacet + facet normal -0.801595 -0.597277 0.0265637 + outer loop + vertex 437.774 95.6069 85.2871 + vertex 435.543 98.6313 85.9601 + vertex 437.675 95.573 81.5472 + endloop + endfacet + facet normal -0.809539 -0.586862 0.0155071 + outer loop + vertex 437.675 95.573 81.5472 + vertex 435.543 98.6313 85.9601 + vertex 435.462 98.6436 82.2358 + endloop + endfacet + facet normal -0.802363 -0.593123 0.0664825 + outer loop + vertex 437.675 95.573 81.5472 + vertex 435.462 98.6436 82.2358 + vertex 437.428 95.4993 77.9004 + endloop + endfacet + facet normal -0.811681 -0.581608 0.0539075 + outer loop + vertex 437.428 95.4993 77.9004 + vertex 435.462 98.6436 82.2358 + vertex 435.247 98.6089 78.609 + endloop + endfacet + facet normal -0.843344 -0.534517 0.0553418 + outer loop + vertex 435.462 98.6436 82.2358 + vertex 433.373 102.006 82.8624 + vertex 435.247 98.6089 78.609 + endloop + endfacet + facet normal -0.849322 -0.525884 0.0458142 + outer loop + vertex 435.247 98.6089 78.609 + vertex 433.373 102.006 82.8624 + vertex 433.197 101.974 79.2466 + endloop + endfacet + facet normal -0.838074 -0.543592 -0.04625 + outer loop + vertex 435.291 98.5705 93.5186 + vertex 433.141 101.834 94.1109 + vertex 435.479 98.6029 89.7386 + endloop + endfacet + facet normal -0.842181 -0.536518 -0.0536733 + outer loop + vertex 435.479 98.6029 89.7386 + vertex 433.141 101.834 94.1109 + vertex 433.344 101.894 90.3402 + endloop + endfacet + facet normal -0.796723 -0.603258 -0.0362265 + outer loop + vertex 437.554 95.6212 92.8644 + vertex 435.291 98.5705 93.5186 + vertex 437.724 95.6242 89.0761 + endloop + endfacet + facet normal -0.802521 -0.59493 -0.0449247 + outer loop + vertex 437.724 95.6242 89.0761 + vertex 435.291 98.5705 93.5186 + vertex 435.479 98.6029 89.7386 + endloop + endfacet + facet normal -0.799363 -0.600797 -0.00784408 + outer loop + vertex 437.724 95.6242 89.0761 + vertex 435.479 98.6029 89.7386 + vertex 437.774 95.6069 85.2871 + endloop + endfacet + facet normal -0.806506 -0.590948 -0.0181558 + outer loop + vertex 437.774 95.6069 85.2871 + vertex 435.479 98.6029 89.7386 + vertex 435.543 98.6313 85.9601 + endloop + endfacet + facet normal -0.840326 -0.54177 -0.0183602 + outer loop + vertex 435.479 98.6029 89.7386 + vertex 433.344 101.894 90.3402 + vertex 435.543 98.6313 85.9601 + endloop + endfacet + facet normal -0.845701 -0.532942 -0.0276336 + outer loop + vertex 435.543 98.6313 85.9601 + vertex 433.344 101.894 90.3402 + vertex 433.426 101.959 86.5714 + endloop + endfacet + facet normal -0.831216 -0.548267 -0.0921094 + outer loop + vertex 434.646 98.454 100.899 + vertex 432.463 101.666 101.474 + vertex 435.008 98.519 97.2484 + endloop + endfacet + facet normal -0.835422 -0.540334 -0.10055 + outer loop + vertex 435.008 98.519 97.2484 + vertex 432.463 101.666 101.474 + vertex 432.842 101.759 97.8321 + endloop + endfacet + facet normal -0.788737 -0.609488 -0.0801175 + outer loop + vertex 436.948 95.559 100.26 + vertex 434.646 98.454 100.899 + vertex 437.291 95.5966 96.6007 + endloop + endfacet + facet normal -0.794404 -0.600775 -0.0893978 + outer loop + vertex 437.291 95.5966 96.6007 + vertex 434.646 98.454 100.899 + vertex 435.008 98.519 97.2484 + endloop + endfacet + facet normal -0.793024 -0.606243 -0.0598586 + outer loop + vertex 437.291 95.5966 96.6007 + vertex 435.008 98.519 97.2484 + vertex 437.554 95.6212 92.8644 + endloop + endfacet + facet normal -0.798818 -0.597611 -0.0689295 + outer loop + vertex 437.554 95.6212 92.8644 + vertex 435.008 98.519 97.2484 + vertex 435.291 98.5705 93.5186 + endloop + endfacet + facet normal -0.835124 -0.545464 -0.0709669 + outer loop + vertex 435.008 98.519 97.2484 + vertex 432.842 101.759 97.8321 + vertex 435.291 98.5705 93.5186 + endloop + endfacet + facet normal -0.839039 -0.53839 -0.0784195 + outer loop + vertex 435.291 98.5705 93.5186 + vertex 432.842 101.759 97.8321 + vertex 433.141 101.834 94.1109 + endloop + endfacet + facet normal -0.82305 -0.55233 -0.132367 + outer loop + vertex 433.699 98.2648 108.112 + vertex 431.487 101.431 108.662 + vertex 434.211 98.3692 104.498 + endloop + endfacet + facet normal -0.827041 -0.544179 -0.140972 + outer loop + vertex 434.211 98.3692 104.498 + vertex 431.487 101.431 108.662 + vertex 432.014 101.562 105.059 + endloop + endfacet + facet normal -0.779863 -0.614386 -0.119767 + outer loop + vertex 436.036 95.4189 107.497 + vertex 433.699 98.2648 108.112 + vertex 436.53 95.4984 103.871 + endloop + endfacet + facet normal -0.784914 -0.606128 -0.128526 + outer loop + vertex 436.53 95.4984 103.871 + vertex 433.699 98.2648 108.112 + vertex 434.211 98.3692 104.498 + endloop + endfacet + facet normal -0.784522 -0.611819 -0.101013 + outer loop + vertex 436.53 95.4984 103.871 + vertex 434.211 98.3692 104.498 + vertex 436.948 95.559 100.26 + endloop + endfacet + facet normal -0.78964 -0.603682 -0.109714 + outer loop + vertex 436.948 95.559 100.26 + vertex 434.211 98.3692 104.498 + vertex 434.646 98.454 100.899 + endloop + endfacet + facet normal -0.827759 -0.549577 -0.113049 + outer loop + vertex 434.211 98.3692 104.498 + vertex 432.014 101.562 105.059 + vertex 434.646 98.454 100.899 + endloop + endfacet + facet normal -0.831026 -0.543155 -0.119913 + outer loop + vertex 434.646 98.454 100.899 + vertex 432.014 101.562 105.059 + vertex 432.463 101.666 101.474 + endloop + endfacet + facet normal -0.813487 -0.557612 -0.165252 + outer loop + vertex 432.429 97.9992 115.623 + vertex 430.182 101.122 116.147 + vertex 433.107 98.1405 111.809 + endloop + endfacet + facet normal -0.817472 -0.549129 -0.17377 + outer loop + vertex 433.107 98.1405 111.809 + vertex 430.182 101.122 116.147 + vertex 430.878 101.288 112.347 + endloop + endfacet + facet normal -0.768382 -0.621896 -0.151108 + outer loop + vertex 434.803 95.2079 115.037 + vertex 432.429 97.9992 115.623 + vertex 435.461 95.3247 111.209 + endloop + endfacet + facet normal -0.773739 -0.612905 -0.160236 + outer loop + vertex 435.461 95.3247 111.209 + vertex 432.429 97.9992 115.623 + vertex 433.107 98.1405 111.809 + endloop + endfacet + facet normal -0.774056 -0.618441 -0.13553 + outer loop + vertex 435.461 95.3247 111.209 + vertex 433.107 98.1405 111.809 + vertex 436.036 95.4189 107.497 + endloop + endfacet + facet normal -0.779853 -0.608806 -0.14555 + outer loop + vertex 436.036 95.4189 107.497 + vertex 433.107 98.1405 111.809 + vertex 433.699 98.2648 108.112 + endloop + endfacet + facet normal -0.818806 -0.554138 -0.14996 + outer loop + vertex 433.107 98.1405 111.809 + vertex 430.878 101.288 112.347 + vertex 433.699 98.2648 108.112 + endloop + endfacet + facet normal -0.822048 -0.547357 -0.156961 + outer loop + vertex 433.699 98.2648 108.112 + vertex 430.878 101.288 112.347 + vertex 431.487 101.431 108.662 + endloop + endfacet + facet normal -0.802846 -0.56384 -0.193708 + outer loop + vertex 430.836 97.6609 123.49 + vertex 428.552 100.744 123.981 + vertex 431.668 97.8351 119.535 + endloop + endfacet + facet normal -0.806428 -0.555996 -0.201352 + outer loop + vertex 431.668 97.8351 119.535 + vertex 428.552 100.744 123.981 + vertex 429.402 100.937 120.045 + endloop + endfacet + facet normal -0.755778 -0.630019 -0.178536 + outer loop + vertex 433.255 94.9151 122.94 + vertex 430.836 97.6609 123.49 + vertex 434.064 95.0703 118.966 + endloop + endfacet + facet normal -0.76104 -0.621036 -0.187434 + outer loop + vertex 434.064 95.0703 118.966 + vertex 430.836 97.6609 123.49 + vertex 431.668 97.8351 119.535 + endloop + endfacet + facet normal -0.761856 -0.626317 -0.165233 + outer loop + vertex 434.064 95.0703 118.966 + vertex 431.668 97.8351 119.535 + vertex 434.803 95.2079 115.037 + endloop + endfacet + facet normal -0.767764 -0.616317 -0.175192 + outer loop + vertex 434.803 95.2079 115.037 + vertex 431.668 97.8351 119.535 + vertex 432.429 97.9992 115.623 + endloop + endfacet + facet normal -0.808116 -0.560619 -0.180705 + outer loop + vertex 431.668 97.8351 119.535 + vertex 429.402 100.937 120.045 + vertex 432.429 97.9992 115.623 + endloop + endfacet + facet normal -0.811869 -0.552519 -0.188656 + outer loop + vertex 432.429 97.9992 115.623 + vertex 429.402 100.937 120.045 + vertex 430.182 101.122 116.147 + endloop + endfacet + facet normal -0.790755 -0.571559 -0.21915 + outer loop + vertex 429.009 97.2763 131.318 + vertex 426.685 100.318 131.772 + vertex 429.946 97.4713 127.429 + endloop + endfacet + facet normal -0.794814 -0.562281 -0.228278 + outer loop + vertex 429.946 97.4713 127.429 + vertex 426.685 100.318 131.772 + vertex 427.642 100.536 127.901 + endloop + endfacet + facet normal -0.741754 -0.639343 -0.202589 + outer loop + vertex 431.475 94.5764 130.811 + vertex 429.009 97.2763 131.318 + vertex 432.388 94.7556 126.899 + endloop + endfacet + facet normal -0.746826 -0.630483 -0.211523 + outer loop + vertex 432.388 94.7556 126.899 + vertex 429.009 97.2763 131.318 + vertex 429.946 97.4713 127.429 + endloop + endfacet + facet normal -0.748123 -0.63598 -0.189318 + outer loop + vertex 432.388 94.7556 126.899 + vertex 429.946 97.4713 127.429 + vertex 433.255 94.9151 122.94 + endloop + endfacet + facet normal -0.754699 -0.624644 -0.200621 + outer loop + vertex 433.255 94.9151 122.94 + vertex 429.946 97.4713 127.429 + vertex 430.836 97.6609 123.49 + endloop + endfacet + facet normal -0.79705 -0.567173 -0.207425 + outer loop + vertex 429.946 97.4713 127.429 + vertex 427.642 100.536 127.901 + vertex 430.836 97.6609 123.49 + endloop + endfacet + facet normal -0.800777 -0.558829 -0.215562 + outer loop + vertex 430.836 97.6609 123.49 + vertex 427.642 100.536 127.901 + vertex 428.552 100.744 123.981 + endloop + endfacet + facet normal -0.777963 -0.579765 -0.242169 + outer loop + vertex 426.994 96.8548 139 + vertex 424.626 99.8558 139.421 + vertex 428.027 97.0712 135.164 + endloop + endfacet + facet normal -0.781725 -0.570891 -0.250978 + outer loop + vertex 428.027 97.0712 135.164 + vertex 424.626 99.8558 139.421 + vertex 425.681 100.091 135.602 + endloop + endfacet + facet normal -0.727538 -0.648456 -0.224038 + outer loop + vertex 429.509 94.1947 138.532 + vertex 426.994 96.8548 139 + vertex 430.516 94.396 134.677 + endloop + endfacet + facet normal -0.732612 -0.639406 -0.233322 + outer loop + vertex 430.516 94.396 134.677 + vertex 426.994 96.8548 139 + vertex 428.027 97.0712 135.164 + endloop + endfacet + facet normal -0.734303 -0.644845 -0.212071 + outer loop + vertex 430.516 94.396 134.677 + vertex 428.027 97.0712 135.164 + vertex 431.475 94.5764 130.811 + endloop + endfacet + facet normal -0.740321 -0.634214 -0.22293 + outer loop + vertex 431.475 94.5764 130.811 + vertex 428.027 97.0712 135.164 + vertex 429.009 97.2763 131.318 + endloop + endfacet + facet normal -0.784287 -0.575772 -0.231044 + outer loop + vertex 428.027 97.0712 135.164 + vertex 425.681 100.091 135.602 + vertex 429.009 97.2763 131.318 + endloop + endfacet + facet normal -0.788266 -0.566507 -0.240223 + outer loop + vertex 429.009 97.2763 131.318 + vertex 425.681 100.091 135.602 + vertex 426.685 100.318 131.772 + endloop + endfacet + facet normal -0.765589 -0.587896 -0.261249 + outer loop + vertex 424.754 96.3818 146.768 + vertex 422.34 99.3528 147.158 + vertex 425.904 96.6215 142.861 + endloop + endfacet + facet normal -0.770129 -0.577028 -0.27192 + outer loop + vertex 425.904 96.6215 142.861 + vertex 422.34 99.3528 147.158 + vertex 423.517 99.6169 143.265 + endloop + endfacet + facet normal -0.711512 -0.660194 -0.240611 + outer loop + vertex 427.326 93.7683 146.336 + vertex 424.754 96.3818 146.768 + vertex 428.447 93.9903 142.411 + endloop + endfacet + facet normal -0.717119 -0.650255 -0.250818 + outer loop + vertex 428.447 93.9903 142.411 + vertex 424.754 96.3818 146.768 + vertex 425.904 96.6215 142.861 + endloop + endfacet + facet normal -0.718987 -0.655393 -0.23134 + outer loop + vertex 428.447 93.9903 142.411 + vertex 425.904 96.6215 142.861 + vertex 429.509 94.1947 138.532 + endloop + endfacet + facet normal -0.725765 -0.64331 -0.243758 + outer loop + vertex 429.509 94.1947 138.532 + vertex 425.904 96.6215 142.861 + vertex 426.994 96.8548 139 + endloop + endfacet + facet normal -0.772906 -0.581749 -0.253346 + outer loop + vertex 425.904 96.6215 142.861 + vertex 423.517 99.6169 143.265 + vertex 426.994 96.8548 139 + endloop + endfacet + facet normal -0.775561 -0.575421 -0.259608 + outer loop + vertex 426.994 96.8548 139 + vertex 423.517 99.6169 143.265 + vertex 424.626 99.8558 139.421 + endloop + endfacet + facet normal -0.751494 -0.597863 -0.278957 + outer loop + vertex 422.281 95.8578 154.701 + vertex 419.812 98.7942 155.06 + vertex 423.544 96.1269 150.722 + endloop + endfacet + facet normal -0.755994 -0.587107 -0.289443 + outer loop + vertex 423.544 96.1269 150.722 + vertex 419.812 98.7942 155.06 + vertex 421.105 99.084 151.096 + endloop + endfacet + facet normal -0.696329 -0.670252 -0.256687 + outer loop + vertex 424.914 93.2748 154.305 + vertex 422.281 95.8578 154.701 + vertex 426.145 93.5263 150.307 + endloop + endfacet + facet normal -0.702293 -0.659709 -0.267525 + outer loop + vertex 426.145 93.5263 150.307 + vertex 422.281 95.8578 154.701 + vertex 423.544 96.1269 150.722 + endloop + endfacet + facet normal -0.704278 -0.664519 -0.249814 + outer loop + vertex 426.145 93.5263 150.307 + vertex 423.544 96.1269 150.722 + vertex 427.326 93.7683 146.336 + endloop + endfacet + facet normal -0.709558 -0.655165 -0.259397 + outer loop + vertex 427.326 93.7683 146.336 + vertex 423.544 96.1269 150.722 + vertex 424.754 96.3818 146.768 + endloop + endfacet + facet normal -0.759123 -0.592083 -0.2705 + outer loop + vertex 423.544 96.1269 150.722 + vertex 421.105 99.084 151.096 + vertex 424.754 96.3818 146.768 + endloop + endfacet + facet normal -0.762808 -0.583291 -0.279097 + outer loop + vertex 424.754 96.3818 146.768 + vertex 421.105 99.084 151.096 + vertex 422.34 99.3528 147.158 + endloop + endfacet + facet normal -0.738204 -0.606358 -0.29561 + outer loop + vertex 419.635 95.2759 162.628 + vertex 417.11 98.1926 162.951 + vertex 420.974 95.5708 158.678 + endloop + endfacet + facet normal -0.742129 -0.596841 -0.305 + outer loop + vertex 420.974 95.5708 158.678 + vertex 417.11 98.1926 162.951 + vertex 418.479 98.5002 159.018 + endloop + endfacet + facet normal -0.678472 -0.682924 -0.270721 + outer loop + vertex 422.336 92.7343 162.27 + vertex 419.635 95.2759 162.628 + vertex 423.642 93.0112 158.3 + endloop + endfacet + facet normal -0.684787 -0.671809 -0.282381 + outer loop + vertex 423.642 93.0112 158.3 + vertex 419.635 95.2759 162.628 + vertex 420.974 95.5708 158.678 + endloop + endfacet + facet normal -0.687142 -0.677052 -0.263508 + outer loop + vertex 423.642 93.0112 158.3 + vertex 420.974 95.5708 158.678 + vertex 424.914 93.2748 154.305 + endloop + endfacet + facet normal -0.694019 -0.664922 -0.276072 + outer loop + vertex 424.914 93.2748 154.305 + vertex 420.974 95.5708 158.678 + vertex 422.281 95.8578 154.701 + endloop + endfacet + facet normal -0.745155 -0.601359 -0.288291 + outer loop + vertex 420.974 95.5708 158.678 + vertex 418.479 98.5002 159.018 + vertex 422.281 95.8578 154.701 + endloop + endfacet + facet normal -0.748528 -0.593261 -0.29622 + outer loop + vertex 422.281 95.8578 154.701 + vertex 418.479 98.5002 159.018 + vertex 419.812 98.7942 155.06 + endloop + endfacet + facet normal -0.723041 -0.616451 -0.31177 + outer loop + vertex 416.856 94.6449 170.454 + vertex 414.268 97.5362 170.74 + vertex 418.263 94.9687 166.551 + endloop + endfacet + facet normal -0.727096 -0.606469 -0.321755 + outer loop + vertex 418.263 94.9687 166.551 + vertex 414.268 97.5362 170.74 + vertex 415.707 97.8714 166.854 + endloop + endfacet + facet normal -0.661683 -0.693108 -0.285968 + outer loop + vertex 419.628 92.1297 170.135 + vertex 416.856 94.6449 170.454 + vertex 420.999 92.4399 166.212 + endloop + endfacet + facet normal -0.667648 -0.682545 -0.297285 + outer loop + vertex 420.999 92.4399 166.212 + vertex 416.856 94.6449 170.454 + vertex 418.263 94.9687 166.551 + endloop + endfacet + facet normal -0.670233 -0.687829 -0.278708 + outer loop + vertex 420.999 92.4399 166.212 + vertex 418.263 94.9687 166.551 + vertex 422.336 92.7343 162.27 + endloop + endfacet + facet normal -0.676001 -0.677648 -0.289511 + outer loop + vertex 422.336 92.7343 162.27 + vertex 418.263 94.9687 166.551 + vertex 419.635 95.2759 162.628 + endloop + endfacet + facet normal -0.730694 -0.611552 -0.303464 + outer loop + vertex 418.263 94.9687 166.551 + vertex 415.707 97.8714 166.854 + vertex 419.635 95.2759 162.628 + endloop + endfacet + facet normal -0.734824 -0.601456 -0.313503 + outer loop + vertex 419.635 95.2759 162.628 + vertex 415.707 97.8714 166.854 + vertex 417.11 98.1926 162.951 + endloop + endfacet + facet normal -0.708056 -0.62728 -0.324311 + outer loop + vertex 413.948 93.9758 178.209 + vertex 411.292 96.8483 178.452 + vertex 415.417 94.3169 174.342 + endloop + endfacet + facet normal -0.712347 -0.616615 -0.335185 + outer loop + vertex 415.417 94.3169 174.342 + vertex 411.292 96.8483 178.452 + vertex 412.797 97.1997 174.606 + endloop + endfacet + facet normal -0.646044 -0.702806 -0.297809 + outer loop + vertex 416.795 91.4745 177.936 + vertex 413.948 93.9758 178.209 + vertex 418.225 91.8081 174.045 + endloop + endfacet + facet normal -0.651598 -0.69293 -0.308656 + outer loop + vertex 418.225 91.8081 174.045 + vertex 413.948 93.9758 178.209 + vertex 415.417 94.3169 174.342 + endloop + endfacet + facet normal -0.654124 -0.69772 -0.292078 + outer loop + vertex 418.225 91.8081 174.045 + vertex 415.417 94.3169 174.342 + vertex 419.628 92.1297 170.135 + endloop + endfacet + facet normal -0.659341 -0.688478 -0.302105 + outer loop + vertex 419.628 92.1297 170.135 + vertex 415.417 94.3169 174.342 + vertex 416.856 94.6449 170.454 + endloop + endfacet + facet normal -0.716086 -0.621639 -0.317466 + outer loop + vertex 415.417 94.3169 174.342 + vertex 412.797 97.1997 174.606 + vertex 416.856 94.6449 170.454 + endloop + endfacet + facet normal -0.71993 -0.612155 -0.327058 + outer loop + vertex 416.856 94.6449 170.454 + vertex 412.797 97.1997 174.606 + vertex 414.268 97.5362 170.74 + endloop + endfacet + facet normal -0.695117 -0.635036 -0.33696 + outer loop + vertex 410.941 93.26 185.838 + vertex 408.22 96.1374 186.03 + vertex 412.453 93.6186 182.044 + endloop + endfacet + facet normal -0.698949 -0.625221 -0.347231 + outer loop + vertex 412.453 93.6186 182.044 + vertex 408.22 96.1374 186.03 + vertex 409.768 96.5008 182.26 + endloop + endfacet + facet normal -0.630804 -0.711361 -0.309922 + outer loop + vertex 413.866 90.7623 185.62 + vertex 410.941 93.26 185.838 + vertex 415.34 91.121 181.796 + endloop + endfacet + facet normal -0.635555 -0.702785 -0.319629 + outer loop + vertex 415.34 91.121 181.796 + vertex 410.941 93.26 185.838 + vertex 412.453 93.6186 182.044 + endloop + endfacet + facet normal -0.637961 -0.706993 -0.305231 + outer loop + vertex 415.34 91.121 181.796 + vertex 412.453 93.6186 182.044 + vertex 416.795 91.4745 177.936 + endloop + endfacet + facet normal -0.643193 -0.697613 -0.315656 + outer loop + vertex 416.795 91.4745 177.936 + vertex 412.453 93.6186 182.044 + vertex 413.948 93.9758 178.209 + endloop + endfacet + facet normal -0.702336 -0.629491 -0.332361 + outer loop + vertex 412.453 93.6186 182.044 + vertex 409.768 96.5008 182.26 + vertex 413.948 93.9758 178.209 + endloop + endfacet + facet normal -0.704877 -0.623096 -0.338969 + outer loop + vertex 413.948 93.9758 178.209 + vertex 409.768 96.5008 182.26 + vertex 411.292 96.8483 178.452 + endloop + endfacet + facet normal -0.682152 -0.64096 -0.351908 + outer loop + vertex 407.849 92.4874 193.334 + vertex 405.063 95.3788 193.467 + vertex 409.405 92.8804 189.601 + endloop + endfacet + facet normal -0.684678 -0.634255 -0.359078 + outer loop + vertex 409.405 92.8804 189.601 + vertex 405.063 95.3788 193.467 + vertex 406.65 95.7611 189.766 + endloop + endfacet + facet normal -0.614576 -0.719388 -0.323694 + outer loop + vertex 410.852 89.9912 193.178 + vertex 407.849 92.4874 193.334 + vertex 412.371 90.389 189.411 + endloop + endfacet + facet normal -0.618904 -0.711407 -0.332953 + outer loop + vertex 412.371 90.389 189.411 + vertex 407.849 92.4874 193.334 + vertex 409.405 92.8804 189.601 + endloop + endfacet + facet normal -0.622059 -0.716472 -0.315771 + outer loop + vertex 412.371 90.389 189.411 + vertex 409.405 92.8804 189.601 + vertex 413.866 90.7623 185.62 + endloop + endfacet + facet normal -0.627701 -0.706181 -0.327567 + outer loop + vertex 413.866 90.7623 185.62 + vertex 409.405 92.8804 189.601 + vertex 410.941 93.26 185.838 + endloop + endfacet + facet normal -0.688028 -0.638243 -0.345345 + outer loop + vertex 409.405 92.8804 189.601 + vertex 406.65 95.7611 189.766 + vertex 410.941 93.26 185.838 + endloop + endfacet + facet normal -0.691138 -0.630144 -0.353902 + outer loop + vertex 410.941 93.26 185.838 + vertex 406.65 95.7611 189.766 + vertex 408.22 96.1374 186.03 + endloop + endfacet + facet normal -0.668558 -0.647614 -0.365548 + outer loop + vertex 404.685 91.654 200.704 + vertex 401.833 94.5644 200.764 + vertex 406.276 92.082 197.035 + endloop + endfacet + facet normal -0.67088 -0.641154 -0.372616 + outer loop + vertex 406.276 92.082 197.035 + vertex 401.833 94.5644 200.764 + vertex 403.454 94.9772 197.134 + endloop + endfacet + facet normal -0.599812 -0.726383 -0.335548 + outer loop + vertex 407.767 89.1511 200.612 + vertex 404.685 91.654 200.704 + vertex 409.317 89.5794 196.913 + endloop + endfacet + facet normal -0.60438 -0.717696 -0.345886 + outer loop + vertex 409.317 89.5794 196.913 + vertex 404.685 91.654 200.704 + vertex 406.276 92.082 197.035 + endloop + endfacet + facet normal -0.607745 -0.722586 -0.329418 + outer loop + vertex 409.317 89.5794 196.913 + vertex 406.276 92.082 197.035 + vertex 410.852 89.9912 193.178 + endloop + endfacet + facet normal -0.611755 -0.715086 -0.338242 + outer loop + vertex 410.852 89.9912 193.178 + vertex 406.276 92.082 197.035 + vertex 407.849 92.4874 193.334 + endloop + endfacet + facet normal -0.674883 -0.645571 -0.357452 + outer loop + vertex 406.276 92.082 197.035 + vertex 403.454 94.9772 197.134 + vertex 407.849 92.4874 193.334 + endloop + endfacet + facet normal -0.678232 -0.636477 -0.367284 + outer loop + vertex 407.849 92.4874 193.334 + vertex 403.454 94.9772 197.134 + vertex 405.063 95.3788 193.467 + endloop + endfacet + facet normal -0.65345 -0.655712 -0.378212 + outer loop + vertex 401.45 90.7429 207.946 + vertex 398.526 93.6566 207.948 + vertex 403.075 91.2035 204.342 + endloop + endfacet + facet normal -0.656672 -0.646308 -0.388675 + outer loop + vertex 403.075 91.2035 204.342 + vertex 398.526 93.6566 207.948 + vertex 400.187 94.1209 204.369 + endloop + endfacet + facet normal -0.582025 -0.73581 -0.346166 + outer loop + vertex 404.618 88.2559 207.906 + vertex 401.45 90.7429 207.946 + vertex 406.201 88.7122 204.275 + endloop + endfacet + facet normal -0.586695 -0.726766 -0.357212 + outer loop + vertex 406.201 88.7122 204.275 + vertex 401.45 90.7429 207.946 + vertex 403.075 91.2035 204.342 + endloop + endfacet + facet normal -0.590441 -0.731925 -0.340096 + outer loop + vertex 406.201 88.7122 204.275 + vertex 403.075 91.2035 204.342 + vertex 407.767 89.1511 200.612 + endloop + endfacet + facet normal -0.596063 -0.721125 -0.353112 + outer loop + vertex 407.767 89.1511 200.612 + vertex 403.075 91.2035 204.342 + vertex 404.685 91.654 200.704 + endloop + endfacet + facet normal -0.661131 -0.650863 -0.373208 + outer loop + vertex 403.075 91.2035 204.342 + vertex 400.187 94.1209 204.369 + vertex 404.685 91.654 200.704 + endloop + endfacet + facet normal -0.663956 -0.642761 -0.382127 + outer loop + vertex 404.685 91.654 200.704 + vertex 400.187 94.1209 204.369 + vertex 401.833 94.5644 200.764 + endloop + endfacet + facet normal -0.637423 -0.664347 -0.3903 + outer loop + vertex 398.171 89.7734 215.018 + vertex 395.171 92.679 214.97 + vertex 399.81 90.2604 211.512 + endloop + endfacet + facet normal -0.640406 -0.655248 -0.400664 + outer loop + vertex 399.81 90.2604 211.512 + vertex 395.171 92.679 214.97 + vertex 396.848 93.1693 211.489 + endloop + endfacet + facet normal -0.565022 -0.743816 -0.357055 + outer loop + vertex 401.424 87.2919 215.038 + vertex 398.171 89.7734 215.018 + vertex 403.022 87.777 211.5 + endloop + endfacet + facet normal -0.569509 -0.734837 -0.368339 + outer loop + vertex 403.022 87.777 211.5 + vertex 398.171 89.7734 215.018 + vertex 399.81 90.2604 211.512 + endloop + endfacet + facet normal -0.573071 -0.739515 -0.353138 + outer loop + vertex 403.022 87.777 211.5 + vertex 399.81 90.2604 211.512 + vertex 404.618 88.2559 207.906 + endloop + endfacet + facet normal -0.577822 -0.73016 -0.364675 + outer loop + vertex 404.618 88.2559 207.906 + vertex 399.81 90.2604 211.512 + vertex 401.45 90.7429 207.946 + endloop + endfacet + facet normal -0.644863 -0.659674 -0.385982 + outer loop + vertex 399.81 90.2604 211.512 + vertex 396.848 93.1693 211.489 + vertex 401.45 90.7429 207.946 + endloop + endfacet + facet normal -0.64802 -0.650255 -0.396534 + outer loop + vertex 401.45 90.7429 207.946 + vertex 396.848 93.1693 211.489 + vertex 398.526 93.6566 207.948 + endloop + endfacet + facet normal -0.621908 -0.670271 -0.404929 + outer loop + vertex 394.877 88.7448 221.854 + vertex 391.807 91.6577 221.747 + vertex 396.525 89.2635 218.463 + endloop + endfacet + facet normal -0.624276 -0.662472 -0.414017 + outer loop + vertex 396.525 89.2635 218.463 + vertex 391.807 91.6577 221.747 + vertex 393.49 92.1717 218.386 + endloop + endfacet + facet normal -0.547587 -0.750604 -0.369786 + outer loop + vertex 398.217 86.2642 221.942 + vertex 394.877 88.7448 221.854 + vertex 399.822 86.7806 218.517 + endloop + endfacet + facet normal -0.551997 -0.741302 -0.381799 + outer loop + vertex 399.822 86.7806 218.517 + vertex 394.877 88.7448 221.854 + vertex 396.525 89.2635 218.463 + endloop + endfacet + facet normal -0.556043 -0.746325 -0.365807 + outer loop + vertex 399.822 86.7806 218.517 + vertex 396.525 89.2635 218.463 + vertex 401.424 87.2919 215.038 + endloop + endfacet + facet normal -0.560228 -0.737695 -0.376764 + outer loop + vertex 401.424 87.2919 215.038 + vertex 396.525 89.2635 218.463 + vertex 398.171 89.7734 215.018 + endloop + endfacet + facet normal -0.629042 -0.667058 -0.399174 + outer loop + vertex 396.525 89.2635 218.463 + vertex 393.49 92.1717 218.386 + vertex 398.171 89.7734 215.018 + endloop + endfacet + facet normal -0.631671 -0.658711 -0.408768 + outer loop + vertex 398.171 89.7734 215.018 + vertex 393.49 92.1717 218.386 + vertex 395.171 92.679 214.97 + endloop + endfacet + facet normal -0.605257 -0.676897 -0.418897 + outer loop + vertex 391.528 87.6539 228.538 + vertex 388.384 90.5703 228.369 + vertex 393.211 88.2082 225.211 + endloop + endfacet + facet normal -0.607713 -0.668224 -0.42914 + outer loop + vertex 393.211 88.2082 225.211 + vertex 388.384 90.5703 228.369 + vertex 390.104 91.1223 225.073 + endloop + endfacet + facet normal -0.531678 -0.75495 -0.383887 + outer loop + vertex 394.95 85.1615 228.7 + vertex 391.528 87.6539 228.538 + vertex 396.591 85.7166 225.336 + endloop + endfacet + facet normal -0.535538 -0.746334 -0.395202 + outer loop + vertex 396.591 85.7166 225.336 + vertex 391.528 87.6539 228.538 + vertex 393.211 88.2082 225.211 + endloop + endfacet + facet normal -0.539742 -0.751268 -0.379836 + outer loop + vertex 396.591 85.7166 225.336 + vertex 393.211 88.2082 225.211 + vertex 398.217 86.2642 221.942 + endloop + endfacet + facet normal -0.542744 -0.744743 -0.388312 + outer loop + vertex 398.217 86.2642 221.942 + vertex 393.211 88.2082 225.211 + vertex 394.877 88.7448 221.854 + endloop + endfacet + facet normal -0.613537 -0.673624 -0.412071 + outer loop + vertex 393.211 88.2082 225.211 + vertex 390.104 91.1223 225.073 + vertex 394.877 88.7448 221.854 + endloop + endfacet + facet normal -0.616118 -0.664811 -0.422404 + outer loop + vertex 394.877 88.7448 221.854 + vertex 390.104 91.1223 225.073 + vertex 391.807 91.6577 221.747 + endloop + endfacet + facet normal -0.590309 -0.681961 -0.431816 + outer loop + vertex 388.158 86.5102 235.009 + vertex 384.946 89.4395 234.774 + vertex 389.836 87.0801 231.815 + endloop + endfacet + facet normal -0.592695 -0.672401 -0.443384 + outer loop + vertex 389.836 87.0801 231.815 + vertex 384.946 89.4395 234.774 + vertex 386.664 90.011 231.611 + endloop + endfacet + facet normal -0.516147 -0.757312 -0.400088 + outer loop + vertex 391.656 83.9998 235.249 + vertex 388.158 86.5102 235.009 + vertex 393.301 84.5874 232.013 + endloop + endfacet + facet normal -0.518092 -0.752571 -0.40647 + outer loop + vertex 393.301 84.5874 232.013 + vertex 388.158 86.5102 235.009 + vertex 389.836 87.0801 231.815 + endloop + endfacet + facet normal -0.522525 -0.75753 -0.391301 + outer loop + vertex 393.301 84.5874 232.013 + vertex 389.836 87.0801 231.815 + vertex 394.95 85.1615 228.7 + endloop + endfacet + facet normal -0.526302 -0.748796 -0.402879 + outer loop + vertex 394.95 85.1615 228.7 + vertex 389.836 87.0801 231.815 + vertex 391.528 87.6539 228.538 + endloop + endfacet + facet normal -0.598426 -0.677506 -0.427635 + outer loop + vertex 389.836 87.0801 231.815 + vertex 386.664 90.011 231.611 + vertex 391.528 87.6539 228.538 + endloop + endfacet + facet normal -0.599902 -0.672013 -0.434185 + outer loop + vertex 391.528 87.6539 228.538 + vertex 386.664 90.011 231.611 + vertex 388.384 90.5703 228.369 + endloop + endfacet + facet normal -0.575821 -0.682976 -0.449415 + outer loop + vertex 384.813 85.3461 241.158 + vertex 381.549 88.2979 240.854 + vertex 386.488 85.9354 238.116 + endloop + endfacet + facet normal -0.576889 -0.677845 -0.455769 + outer loop + vertex 386.488 85.9354 238.116 + vertex 381.549 88.2979 240.854 + vertex 383.249 88.8735 237.847 + endloop + endfacet + facet normal -0.500418 -0.760387 -0.413996 + outer loop + vertex 388.383 82.8243 241.475 + vertex 384.813 85.3461 241.158 + vertex 390.024 83.4214 238.394 + endloop + endfacet + facet normal -0.502755 -0.75391 -0.422914 + outer loop + vertex 390.024 83.4214 238.394 + vertex 384.813 85.3461 241.158 + vertex 386.488 85.9354 238.116 + endloop + endfacet + facet normal -0.508836 -0.760335 -0.403704 + outer loop + vertex 390.024 83.4214 238.394 + vertex 386.488 85.9354 238.116 + vertex 391.656 83.9998 235.249 + endloop + endfacet + facet normal -0.511808 -0.752618 -0.41427 + outer loop + vertex 391.656 83.9998 235.249 + vertex 386.488 85.9354 238.116 + vertex 388.158 86.5102 235.009 + endloop + endfacet + facet normal -0.58305 -0.683167 -0.439699 + outer loop + vertex 386.488 85.9354 238.116 + vertex 383.249 88.8735 237.847 + vertex 388.158 86.5102 235.009 + endloop + endfacet + facet normal -0.584502 -0.676851 -0.44747 + outer loop + vertex 388.158 86.5102 235.009 + vertex 383.249 88.8735 237.847 + vertex 384.946 89.4395 234.774 + endloop + endfacet + facet normal -0.561023 -0.685685 -0.463777 + outer loop + vertex 381.397 84.1384 247.155 + vertex 378.083 87.1011 246.783 + vertex 383.12 84.7506 244.166 + endloop + endfacet + facet normal -0.561983 -0.680363 -0.470404 + outer loop + vertex 383.12 84.7506 244.166 + vertex 378.083 87.1011 246.783 + vertex 379.825 87.7048 243.829 + endloop + endfacet + facet normal -0.487366 -0.76077 -0.428607 + outer loop + vertex 385.024 81.5937 247.548 + vertex 381.397 84.1384 247.155 + vertex 386.718 82.2136 244.521 + endloop + endfacet + facet normal -0.489238 -0.754997 -0.436607 + outer loop + vertex 386.718 82.2136 244.521 + vertex 381.397 84.1384 247.155 + vertex 383.12 84.7506 244.166 + endloop + endfacet + facet normal -0.494097 -0.759901 -0.422395 + outer loop + vertex 386.718 82.2136 244.521 + vertex 383.12 84.7506 244.166 + vertex 388.383 82.8243 241.475 + endloop + endfacet + facet normal -0.495624 -0.755431 -0.42858 + outer loop + vertex 388.383 82.8243 241.475 + vertex 383.12 84.7506 244.166 + vertex 384.813 85.3461 241.158 + endloop + endfacet + facet normal -0.56806 -0.685438 -0.455502 + outer loop + vertex 383.12 84.7506 244.166 + vertex 379.825 87.7048 243.829 + vertex 384.813 85.3461 241.158 + endloop + endfacet + facet normal -0.569556 -0.677668 -0.465158 + outer loop + vertex 384.813 85.3461 241.158 + vertex 379.825 87.7048 243.829 + vertex 381.549 88.2979 240.854 + endloop + endfacet + facet normal -0.547074 -0.685225 -0.480809 + outer loop + vertex 377.91 82.8826 252.987 + vertex 374.566 85.8631 252.544 + vertex 379.654 83.5113 250.107 + endloop + endfacet + facet normal -0.547603 -0.681434 -0.485571 + outer loop + vertex 379.654 83.5113 250.107 + vertex 374.566 85.8631 252.544 + vertex 376.32 86.4803 249.7 + endloop + endfacet + facet normal -0.4736 -0.760016 -0.445059 + outer loop + vertex 381.582 80.3185 253.458 + vertex 377.91 82.8826 252.987 + vertex 383.303 80.9548 250.54 + endloop + endfacet + facet normal -0.475049 -0.75477 -0.452384 + outer loop + vertex 383.303 80.9548 250.54 + vertex 377.91 82.8826 252.987 + vertex 379.654 83.5113 250.107 + endloop + endfacet + facet normal -0.48021 -0.759764 -0.438358 + outer loop + vertex 383.303 80.9548 250.54 + vertex 379.654 83.5113 250.107 + vertex 385.024 81.5937 247.548 + endloop + endfacet + facet normal -0.481624 -0.755095 -0.444825 + outer loop + vertex 385.024 81.5937 247.548 + vertex 379.654 83.5113 250.107 + vertex 381.397 84.1384 247.155 + endloop + endfacet + facet normal -0.553291 -0.686027 -0.47248 + outer loop + vertex 379.654 83.5113 250.107 + vertex 376.32 86.4803 249.7 + vertex 381.397 84.1384 247.155 + endloop + endfacet + facet normal -0.554252 -0.680125 -0.479828 + outer loop + vertex 381.397 84.1384 247.155 + vertex 376.32 86.4803 249.7 + vertex 378.083 87.1011 246.783 + endloop + endfacet + facet normal -0.533114 -0.683266 -0.498935 + outer loop + vertex 374.473 81.6534 258.436 + vertex 371.107 84.653 257.925 + vertex 376.186 82.2676 255.764 + endloop + endfacet + facet normal -0.533298 -0.68084 -0.502046 + outer loop + vertex 376.186 82.2676 255.764 + vertex 371.107 84.653 257.925 + vertex 372.825 85.2516 255.288 + endloop + endfacet + facet normal -0.460766 -0.756648 -0.463873 + outer loop + vertex 378.176 79.0621 258.984 + vertex 374.473 81.6534 258.436 + vertex 379.873 79.6897 256.275 + endloop + endfacet + facet normal -0.461508 -0.752998 -0.469046 + outer loop + vertex 379.873 79.6897 256.275 + vertex 374.473 81.6534 258.436 + vertex 376.186 82.2676 255.764 + endloop + endfacet + facet normal -0.467785 -0.75883 -0.45316 + outer loop + vertex 379.873 79.6897 256.275 + vertex 376.186 82.2676 255.764 + vertex 381.582 80.3185 253.458 + endloop + endfacet + facet normal -0.468638 -0.755312 -0.458128 + outer loop + vertex 381.582 80.3185 253.458 + vertex 376.186 82.2676 255.764 + vertex 377.91 82.8826 252.987 + endloop + endfacet + facet normal -0.540154 -0.686191 -0.487212 + outer loop + vertex 376.186 82.2676 255.764 + vertex 372.825 85.2516 255.288 + vertex 377.91 82.8826 252.987 + endloop + endfacet + facet normal -0.540802 -0.680261 -0.494751 + outer loop + vertex 377.91 82.8826 252.987 + vertex 372.825 85.2516 255.288 + vertex 374.566 85.8631 252.544 + endloop + endfacet + facet normal -0.520064 -0.678813 -0.518407 + outer loop + vertex 371.1 80.44 263.495 + vertex 367.725 83.4631 262.923 + vertex 372.779 81.0511 261.011 + endloop + endfacet + facet normal -0.520103 -0.675171 -0.523104 + outer loop + vertex 372.779 81.0511 261.011 + vertex 367.725 83.4631 262.923 + vertex 369.412 84.0658 260.467 + endloop + endfacet + facet normal -0.448816 -0.750523 -0.485057 + outer loop + vertex 374.82 77.8203 264.107 + vertex 371.1 80.44 263.495 + vertex 376.493 78.444 261.594 + endloop + endfacet + facet normal -0.449051 -0.748725 -0.487611 + outer loop + vertex 376.493 78.444 261.594 + vertex 371.1 80.44 263.495 + vertex 372.779 81.0511 261.011 + endloop + endfacet + facet normal -0.455452 -0.754481 -0.472569 + outer loop + vertex 376.493 78.444 261.594 + vertex 372.779 81.0511 261.011 + vertex 378.176 79.0621 258.984 + endloop + endfacet + facet normal -0.455842 -0.752154 -0.475891 + outer loop + vertex 378.176 79.0621 258.984 + vertex 372.779 81.0511 261.011 + vertex 374.473 81.6534 258.436 + endloop + endfacet + facet normal -0.528168 -0.68125 -0.50689 + outer loop + vertex 372.779 81.0511 261.011 + vertex 369.412 84.0658 260.467 + vertex 374.473 81.6534 258.436 + endloop + endfacet + facet normal -0.528241 -0.679534 -0.509112 + outer loop + vertex 374.473 81.6534 258.436 + vertex 369.412 84.0658 260.467 + vertex 371.107 84.653 257.925 + endloop + endfacet + facet normal -0.508256 -0.669018 -0.542301 + outer loop + vertex 367.96 79.2525 267.97 + vertex 364.596 82.3104 267.351 + vertex 369.467 79.8254 265.851 + endloop + endfacet + facet normal -0.508396 -0.670413 -0.540444 + outer loop + vertex 369.467 79.8254 265.851 + vertex 364.596 82.3104 267.351 + vertex 366.095 82.864 265.254 + endloop + endfacet + facet normal -0.436245 -0.741999 -0.509046 + outer loop + vertex 371.679 76.6204 268.619 + vertex 367.96 79.2525 267.97 + vertex 373.189 77.1978 266.483 + endloop + endfacet + facet normal -0.436262 -0.740947 -0.510561 + outer loop + vertex 373.189 77.1978 266.483 + vertex 367.96 79.2525 267.97 + vertex 369.467 79.8254 265.851 + endloop + endfacet + facet normal -0.441819 -0.7459 -0.498427 + outer loop + vertex 373.189 77.1978 266.483 + vertex 369.467 79.8254 265.851 + vertex 374.82 77.8203 264.107 + endloop + endfacet + facet normal -0.44195 -0.744391 -0.500562 + outer loop + vertex 374.82 77.8203 264.107 + vertex 369.467 79.8254 265.851 + vertex 371.1 80.44 263.495 + endloop + endfacet + facet normal -0.51314 -0.673922 -0.531523 + outer loop + vertex 369.467 79.8254 265.851 + vertex 366.095 82.864 265.254 + vertex 371.1 80.44 263.495 + endloop + endfacet + facet normal -0.513131 -0.673628 -0.531903 + outer loop + vertex 371.1 80.44 263.495 + vertex 366.095 82.864 265.254 + vertex 367.725 83.4631 262.923 + endloop + endfacet + facet normal -0.506693 -0.666327 -0.547056 + outer loop + vertex 365.757 78.5558 270.872 + vertex 362.403 81.6149 270.252 + vertex 366.702 78.8135 269.682 + endloop + endfacet + facet normal -0.508205 -0.669803 -0.541379 + outer loop + vertex 366.702 78.8135 269.682 + vertex 362.403 81.6149 270.252 + vertex 363.332 81.8727 269.062 + endloop + endfacet + facet normal -0.436206 -0.735362 -0.518621 + outer loop + vertex 369.412 75.8989 271.565 + vertex 365.757 78.5558 270.872 + vertex 370.396 76.1692 270.354 + endloop + endfacet + facet normal -0.438075 -0.741145 -0.508719 + outer loop + vertex 370.396 76.1692 270.354 + vertex 365.757 78.5558 270.872 + vertex 366.702 78.8135 269.682 + endloop + endfacet + facet normal -0.435438 -0.73887 -0.514262 + outer loop + vertex 370.396 76.1692 270.354 + vertex 366.702 78.8135 269.682 + vertex 371.679 76.6204 268.619 + endloop + endfacet + facet normal -0.435737 -0.74155 -0.510133 + outer loop + vertex 371.679 76.6204 268.619 + vertex 366.702 78.8135 269.682 + vertex 367.96 79.2525 267.97 + endloop + endfacet + facet normal -0.5069 -0.668852 -0.543773 + outer loop + vertex 366.702 78.8135 269.682 + vertex 363.332 81.8727 269.062 + vertex 367.96 79.2525 267.97 + endloop + endfacet + facet normal -0.506677 -0.667866 -0.545192 + outer loop + vertex 367.96 79.2525 267.97 + vertex 363.332 81.8727 269.062 + vertex 364.596 82.3104 267.351 + endloop + endfacet + facet normal -0.490338 -0.651923 -0.578416 + outer loop + vertex 365.038 78.2853 271.82 + vertex 361.651 81.4086 271.171 + vertex 365.16 78.4451 271.537 + endloop + endfacet + facet normal -0.472921 -0.635266 -0.610559 + outer loop + vertex 365.16 78.4451 271.537 + vertex 361.651 81.4086 271.171 + vertex 361.848 81.5169 270.906 + endloop + endfacet + facet normal -0.415761 -0.720173 -0.555422 + outer loop + vertex 368.726 75.5949 272.548 + vertex 365.038 78.2853 271.82 + vertex 368.817 75.7824 272.237 + endloop + endfacet + facet normal -0.406712 -0.709791 -0.575137 + outer loop + vertex 368.817 75.7824 272.237 + vertex 365.038 78.2853 271.82 + vertex 365.16 78.4451 271.537 + endloop + endfacet + facet normal -0.437698 -0.736679 -0.515484 + outer loop + vertex 368.817 75.7824 272.237 + vertex 365.16 78.4451 271.537 + vertex 369.412 75.8989 271.565 + endloop + endfacet + facet normal -0.437624 -0.736558 -0.515721 + outer loop + vertex 369.412 75.8989 271.565 + vertex 365.16 78.4451 271.537 + vertex 365.757 78.5558 270.872 + endloop + endfacet + facet normal -0.502898 -0.657428 -0.561143 + outer loop + vertex 365.16 78.4451 271.537 + vertex 361.848 81.5169 270.906 + vertex 365.757 78.5558 270.872 + endloop + endfacet + facet normal -0.512748 -0.670714 -0.535941 + outer loop + vertex 365.757 78.5558 270.872 + vertex 361.848 81.5169 270.906 + vertex 362.403 81.6149 270.252 + endloop + endfacet + facet normal -0.372343 -0.711855 -0.595503 + outer loop + vertex 369.343 75.1015 272.752 + vertex 365.672 77.643 272.009 + vertex 368.726 75.5949 272.548 + endloop + endfacet + facet normal -0.058543 -0.334759 -0.940484 + outer loop + vertex 368.726 75.5949 272.548 + vertex 365.672 77.643 272.009 + vertex 365.038 78.2853 271.82 + endloop + endfacet + facet normal -0.390895 -0.593073 -0.703893 + outer loop + vertex 365.672 77.643 272.009 + vertex 361.945 80.9727 271.274 + vertex 365.038 78.2853 271.82 + endloop + endfacet + facet normal -0.0633886 -0.268431 -0.961211 + outer loop + vertex 365.038 78.2853 271.82 + vertex 361.945 80.9727 271.274 + vertex 361.651 81.4086 271.171 + endloop + endfacet + facet normal -0.875009 -0.458071 0.156618 + outer loop + vertex 432.599 101.583 72.6473 + vertex 430.705 105.353 73.0942 + vertex 432.182 101.523 70.1434 + endloop + endfacet + facet normal -0.884891 -0.445643 0.135541 + outer loop + vertex 432.182 101.523 70.1434 + vertex 430.705 105.353 73.0942 + vertex 430.237 105.514 70.5691 + endloop + endfacet + facet normal -0.87839 -0.4697 0.0883922 + outer loop + vertex 433.197 101.974 79.2466 + vertex 431.321 105.581 79.7625 + vertex 432.934 101.816 75.789 + endloop + endfacet + facet normal -0.882066 -0.464019 0.0815174 + outer loop + vertex 432.934 101.816 75.789 + vertex 431.321 105.581 79.7625 + vertex 431.07 105.442 76.2639 + endloop + endfacet + facet normal -0.875191 -0.466562 0.127909 + outer loop + vertex 432.934 101.816 75.789 + vertex 431.07 105.442 76.2639 + vertex 432.599 101.583 72.6473 + endloop + endfacet + facet normal -0.882236 -0.456697 0.114405 + outer loop + vertex 432.599 101.583 72.6473 + vertex 431.07 105.442 76.2639 + vertex 430.705 105.353 73.0942 + endloop + endfacet + facet normal -0.879933 -0.475052 0.00660926 + outer loop + vertex 433.426 101.959 86.5714 + vertex 431.481 105.568 87.0853 + vertex 433.373 102.006 82.8624 + endloop + endfacet + facet normal -0.884304 -0.466907 -0.0022185 + outer loop + vertex 433.373 102.006 82.8624 + vertex 431.481 105.568 87.0853 + vertex 431.461 105.624 83.3876 + endloop + endfacet + facet normal -0.880376 -0.471955 0.046858 + outer loop + vertex 433.373 102.006 82.8624 + vertex 431.461 105.624 83.3876 + vertex 433.197 101.974 79.2466 + endloop + endfacet + facet normal -0.88405 -0.465695 0.0398004 + outer loop + vertex 433.197 101.974 79.2466 + vertex 431.461 105.624 83.3876 + vertex 431.321 105.581 79.7625 + endloop + endfacet + facet normal -0.874744 -0.481505 -0.0545546 + outer loop + vertex 433.141 101.834 94.1109 + vertex 431.157 105.384 94.5996 + vertex 433.344 101.894 90.3402 + endloop + endfacet + facet normal -0.878663 -0.473219 -0.063359 + outer loop + vertex 433.344 101.894 90.3402 + vertex 431.157 105.384 94.5996 + vertex 431.377 105.479 90.8362 + endloop + endfacet + facet normal -0.878019 -0.477842 -0.0273861 + outer loop + vertex 433.344 101.894 90.3402 + vertex 431.377 105.479 90.8362 + vertex 433.426 101.959 86.5714 + endloop + endfacet + facet normal -0.881897 -0.470092 -0.0356464 + outer loop + vertex 433.426 101.959 86.5714 + vertex 431.377 105.479 90.8362 + vertex 431.481 105.568 87.0853 + endloop + endfacet + facet normal -0.869512 -0.48313 -0.102636 + outer loop + vertex 432.463 101.666 101.474 + vertex 430.453 105.187 101.93 + vertex 432.842 101.759 97.8321 + endloop + endfacet + facet normal -0.871345 -0.478787 -0.107337 + outer loop + vertex 432.842 101.759 97.8321 + vertex 430.453 105.187 101.93 + vertex 430.843 105.29 98.3075 + endloop + endfacet + facet normal -0.872037 -0.482865 -0.0799571 + outer loop + vertex 432.842 101.759 97.8321 + vertex 430.843 105.29 98.3075 + vertex 433.141 101.834 94.1109 + endloop + endfacet + facet normal -0.874623 -0.477092 -0.0861281 + outer loop + vertex 433.141 101.834 94.1109 + vertex 430.843 105.29 98.3075 + vertex 431.157 105.384 94.5996 + endloop + endfacet + facet normal -0.862483 -0.485164 -0.144007 + outer loop + vertex 431.487 101.431 108.662 + vertex 429.453 104.919 109.091 + vertex 432.014 101.562 105.059 + endloop + endfacet + facet normal -0.863944 -0.481302 -0.14815 + outer loop + vertex 432.014 101.562 105.059 + vertex 429.453 104.919 109.091 + vertex 429.99 105.059 105.505 + endloop + endfacet + facet normal -0.865594 -0.485514 -0.122571 + outer loop + vertex 432.014 101.562 105.059 + vertex 429.99 105.059 105.505 + vertex 432.463 101.666 101.474 + endloop + endfacet + facet normal -0.868232 -0.478887 -0.12977 + outer loop + vertex 432.463 101.666 101.474 + vertex 429.99 105.059 105.505 + vertex 430.453 105.187 101.93 + endloop + endfacet + facet normal -0.853808 -0.48928 -0.177809 + outer loop + vertex 430.182 101.122 116.147 + vertex 428.121 104.569 116.557 + vertex 430.878 101.288 112.347 + endloop + endfacet + facet normal -0.85566 -0.484073 -0.18308 + outer loop + vertex 430.878 101.288 112.347 + vertex 428.121 104.569 116.557 + vertex 428.83 104.75 112.767 + endloop + endfacet + facet normal -0.857878 -0.488117 -0.160585 + outer loop + vertex 430.878 101.288 112.347 + vertex 428.83 104.75 112.767 + vertex 431.487 101.431 108.662 + endloop + endfacet + facet normal -0.860457 -0.481036 -0.167981 + outer loop + vertex 431.487 101.431 108.662 + vertex 428.83 104.75 112.767 + vertex 429.453 104.919 109.091 + endloop + endfacet + facet normal -0.844501 -0.494122 -0.206545 + outer loop + vertex 428.552 100.744 123.981 + vertex 426.462 104.155 124.368 + vertex 429.402 100.937 120.045 + endloop + endfacet + facet normal -0.846673 -0.487715 -0.21279 + outer loop + vertex 429.402 100.937 120.045 + vertex 426.462 104.155 124.368 + vertex 427.326 104.366 120.445 + endloop + endfacet + facet normal -0.849166 -0.491509 -0.193227 + outer loop + vertex 429.402 100.937 120.045 + vertex 427.326 104.366 120.445 + vertex 430.182 101.122 116.147 + endloop + endfacet + facet normal -0.851342 -0.485237 -0.199406 + outer loop + vertex 430.182 101.122 116.147 + vertex 427.326 104.366 120.445 + vertex 428.121 104.569 116.557 + endloop + endfacet + facet normal -0.834528 -0.498563 -0.234517 + outer loop + vertex 426.685 100.318 131.772 + vertex 424.566 103.697 132.127 + vertex 427.642 100.536 127.901 + endloop + endfacet + facet normal -0.836277 -0.493024 -0.239934 + outer loop + vertex 427.642 100.536 127.901 + vertex 424.566 103.697 132.127 + vertex 425.536 103.927 128.275 + endloop + endfacet + facet normal -0.83916 -0.496884 -0.22117 + outer loop + vertex 427.642 100.536 127.901 + vertex 425.536 103.927 128.275 + vertex 428.552 100.744 123.981 + endloop + endfacet + facet normal -0.841472 -0.489827 -0.228023 + outer loop + vertex 428.552 100.744 123.981 + vertex 425.536 103.927 128.275 + vertex 426.462 104.155 124.368 + endloop + endfacet + facet normal -0.824292 -0.503657 -0.258597 + outer loop + vertex 424.626 99.8558 139.421 + vertex 422.477 103.208 139.744 + vertex 425.681 100.091 135.602 + endloop + endfacet + facet normal -0.826092 -0.497568 -0.264572 + outer loop + vertex 425.681 100.091 135.602 + vertex 422.477 103.208 139.744 + vertex 423.546 103.455 135.94 + endloop + endfacet + facet normal -0.829231 -0.501317 -0.247097 + outer loop + vertex 425.681 100.091 135.602 + vertex 423.546 103.455 135.94 + vertex 426.685 100.318 131.772 + endloop + endfacet + facet normal -0.831296 -0.494518 -0.253769 + outer loop + vertex 426.685 100.318 131.772 + vertex 423.546 103.455 135.94 + vertex 424.566 103.697 132.127 + endloop + endfacet + facet normal -0.81302 -0.510293 -0.280358 + outer loop + vertex 422.34 99.3528 147.158 + vertex 420.151 102.676 147.457 + vertex 423.517 99.6169 143.265 + endloop + endfacet + facet normal -0.814679 -0.50455 -0.285881 + outer loop + vertex 423.517 99.6169 143.265 + vertex 420.151 102.676 147.457 + vertex 421.345 102.947 143.577 + endloop + endfacet + facet normal -0.818296 -0.508606 -0.26779 + outer loop + vertex 423.517 99.6169 143.265 + vertex 421.345 102.947 143.577 + vertex 424.626 99.8558 139.421 + endloop + endfacet + facet normal -0.820879 -0.499755 -0.276411 + outer loop + vertex 424.626 99.8558 139.421 + vertex 421.345 102.947 143.577 + vertex 422.477 103.208 139.744 + endloop + endfacet + facet normal -0.801764 -0.517314 -0.299268 + outer loop + vertex 419.812 98.7942 155.06 + vertex 417.581 102.095 155.331 + vertex 421.105 99.084 151.096 + endloop + endfacet + facet normal -0.803739 -0.510342 -0.305868 + outer loop + vertex 421.105 99.084 151.096 + vertex 417.581 102.095 155.331 + vertex 418.895 102.393 151.381 + endloop + endfacet + facet normal -0.807582 -0.514408 -0.288437 + outer loop + vertex 421.105 99.084 151.096 + vertex 418.895 102.393 151.381 + vertex 422.34 99.3528 147.158 + endloop + endfacet + facet normal -0.809771 -0.506775 -0.29572 + outer loop + vertex 422.34 99.3528 147.158 + vertex 418.895 102.393 151.381 + vertex 420.151 102.676 147.457 + endloop + endfacet + facet normal -0.789396 -0.526343 -0.315938 + outer loop + vertex 417.11 98.1926 162.951 + vertex 414.829 101.467 163.195 + vertex 418.479 98.5002 159.018 + endloop + endfacet + facet normal -0.791465 -0.518857 -0.323063 + outer loop + vertex 418.479 98.5002 159.018 + vertex 414.829 101.467 163.195 + vertex 416.221 101.782 159.279 + endloop + endfacet + facet normal -0.795339 -0.522815 -0.306756 + outer loop + vertex 418.479 98.5002 159.018 + vertex 416.221 101.782 159.279 + vertex 419.812 98.7942 155.06 + endloop + endfacet + facet normal -0.797977 -0.513408 -0.315666 + outer loop + vertex 419.812 98.7942 155.06 + vertex 416.221 101.782 159.279 + vertex 417.581 102.095 155.331 + endloop + endfacet + facet normal -0.776235 -0.534835 -0.333783 + outer loop + vertex 414.268 97.5362 170.74 + vertex 411.935 100.79 170.95 + vertex 415.707 97.8714 166.854 + endloop + endfacet + facet normal -0.778497 -0.52634 -0.341919 + outer loop + vertex 415.707 97.8714 166.854 + vertex 411.935 100.79 170.95 + vertex 413.401 101.134 167.083 + endloop + endfacet + facet normal -0.78286 -0.530611 -0.324934 + outer loop + vertex 415.707 97.8714 166.854 + vertex 413.401 101.134 167.083 + vertex 417.11 98.1926 162.951 + endloop + endfacet + facet normal -0.785159 -0.522116 -0.333046 + outer loop + vertex 417.11 98.1926 162.951 + vertex 413.401 101.134 167.083 + vertex 414.829 101.467 163.195 + endloop + endfacet + facet normal -0.764398 -0.54227 -0.348768 + outer loop + vertex 411.292 96.8483 178.452 + vertex 408.908 100.099 178.623 + vertex 412.797 97.1997 174.606 + endloop + endfacet + facet normal -0.765991 -0.536097 -0.354765 + outer loop + vertex 412.797 97.1997 174.606 + vertex 408.908 100.099 178.623 + vertex 410.437 100.445 174.799 + endloop + endfacet + facet normal -0.770053 -0.539937 -0.339834 + outer loop + vertex 412.797 97.1997 174.606 + vertex 410.437 100.445 174.799 + vertex 414.268 97.5362 170.74 + endloop + endfacet + facet normal -0.772375 -0.531127 -0.34834 + outer loop + vertex 414.268 97.5362 170.74 + vertex 410.437 100.445 174.799 + vertex 411.935 100.79 170.95 + endloop + endfacet + facet normal -0.752143 -0.550741 -0.361891 + outer loop + vertex 408.22 96.1374 186.03 + vertex 405.783 99.3774 186.164 + vertex 409.768 96.5008 182.26 + endloop + endfacet + facet normal -0.753985 -0.54327 -0.369276 + outer loop + vertex 409.768 96.5008 182.26 + vertex 405.783 99.3774 186.164 + vertex 407.355 99.7454 182.412 + endloop + endfacet + facet normal -0.758535 -0.547392 -0.353535 + outer loop + vertex 409.768 96.5008 182.26 + vertex 407.355 99.7454 182.412 + vertex 411.292 96.8483 178.452 + endloop + endfacet + facet normal -0.760688 -0.538859 -0.361918 + outer loop + vertex 411.292 96.8483 178.452 + vertex 407.355 99.7454 182.412 + vertex 408.908 100.099 178.623 + endloop + endfacet + facet normal -0.738502 -0.560647 -0.374552 + outer loop + vertex 405.063 95.3788 193.467 + vertex 402.567 98.5908 193.581 + vertex 406.65 95.7611 189.766 + endloop + endfacet + facet normal -0.740644 -0.55173 -0.383458 + outer loop + vertex 406.65 95.7611 189.766 + vertex 402.567 98.5908 193.581 + vertex 404.184 98.9868 189.888 + endloop + endfacet + facet normal -0.745036 -0.555632 -0.369046 + outer loop + vertex 406.65 95.7611 189.766 + vertex 404.184 98.9868 189.888 + vertex 408.22 96.1374 186.03 + endloop + endfacet + facet normal -0.747268 -0.546403 -0.378198 + outer loop + vertex 408.22 96.1374 186.03 + vertex 404.184 98.9868 189.888 + vertex 405.783 99.3774 186.164 + endloop + endfacet + facet normal -0.725589 -0.567822 -0.388715 + outer loop + vertex 401.833 94.5644 200.764 + vertex 399.278 97.7792 200.836 + vertex 403.454 94.9772 197.134 + endloop + endfacet + facet normal -0.727443 -0.559681 -0.396968 + outer loop + vertex 403.454 94.9772 197.134 + vertex 399.278 97.7792 200.836 + vertex 400.93 98.1871 197.233 + endloop + endfacet + facet normal -0.731927 -0.563643 -0.382869 + outer loop + vertex 403.454 94.9772 197.134 + vertex 400.93 98.1871 197.233 + vertex 405.063 95.3788 193.467 + endloop + endfacet + facet normal -0.733647 -0.55632 -0.390218 + outer loop + vertex 405.063 95.3788 193.467 + vertex 400.93 98.1871 197.233 + vertex 402.567 98.5908 193.581 + endloop + endfacet + facet normal -0.713218 -0.571904 -0.405272 + outer loop + vertex 398.526 93.6566 207.948 + vertex 395.92 96.9068 207.947 + vertex 400.187 94.1209 204.369 + endloop + endfacet + facet normal -0.714688 -0.56484 -0.412525 + outer loop + vertex 400.187 94.1209 204.369 + vertex 395.92 96.9068 207.947 + vertex 397.61 97.358 204.402 + endloop + endfacet + facet normal -0.71952 -0.568834 -0.398394 + outer loop + vertex 400.187 94.1209 204.369 + vertex 397.61 97.358 204.402 + vertex 401.833 94.5644 200.764 + endloop + endfacet + facet normal -0.720666 -0.563574 -0.403763 + outer loop + vertex 401.833 94.5644 200.764 + vertex 397.61 97.358 204.402 + vertex 399.278 97.7792 200.836 + endloop + endfacet + facet normal -0.699066 -0.579939 -0.418303 + outer loop + vertex 395.171 92.679 214.97 + vertex 392.504 95.9272 214.924 + vertex 396.848 93.1693 211.489 + endloop + endfacet + facet normal -0.700742 -0.571175 -0.427458 + outer loop + vertex 396.848 93.1693 211.489 + vertex 392.504 95.9272 214.924 + vertex 394.212 96.4234 211.463 + endloop + endfacet + facet normal -0.705796 -0.575155 -0.41358 + outer loop + vertex 396.848 93.1693 211.489 + vertex 394.212 96.4234 211.463 + vertex 398.526 93.6566 207.948 + endloop + endfacet + facet normal -0.707373 -0.567222 -0.421761 + outer loop + vertex 398.526 93.6566 207.948 + vertex 394.212 96.4234 211.463 + vertex 395.92 96.9068 207.947 + endloop + endfacet + facet normal -0.68461 -0.58663 -0.432636 + outer loop + vertex 391.807 91.6577 221.747 + vertex 389.081 94.906 221.655 + vertex 393.49 92.1717 218.386 + endloop + endfacet + facet normal -0.685994 -0.578503 -0.441301 + outer loop + vertex 393.49 92.1717 218.386 + vertex 389.081 94.906 221.655 + vertex 390.794 95.4204 218.318 + endloop + endfacet + facet normal -0.691475 -0.582749 -0.426925 + outer loop + vertex 393.49 92.1717 218.386 + vertex 390.794 95.4204 218.318 + vertex 395.171 92.679 214.97 + endloop + endfacet + facet normal -0.692856 -0.575078 -0.435012 + outer loop + vertex 395.171 92.679 214.97 + vertex 390.794 95.4204 218.318 + vertex 392.504 95.9272 214.924 + endloop + endfacet + facet normal -0.669875 -0.591523 -0.44874 + outer loop + vertex 388.384 90.5703 228.369 + vertex 385.603 93.8291 228.223 + vertex 390.104 91.1223 225.073 + endloop + endfacet + facet normal -0.670857 -0.585056 -0.455698 + outer loop + vertex 390.104 91.1223 225.073 + vertex 385.603 93.8291 228.223 + vertex 387.348 94.3738 224.955 + endloop + endfacet + facet normal -0.676646 -0.58944 -0.44126 + outer loop + vertex 390.104 91.1223 225.073 + vertex 387.348 94.3738 224.955 + vertex 391.807 91.6577 221.747 + endloop + endfacet + facet normal -0.677922 -0.5815 -0.449755 + outer loop + vertex 391.807 91.6577 221.747 + vertex 387.348 94.3738 224.955 + vertex 389.081 94.906 221.655 + endloop + endfacet + facet normal -0.655538 -0.596022 -0.463711 + outer loop + vertex 384.946 89.4395 234.774 + vertex 382.113 92.7116 234.573 + vertex 386.664 90.011 231.611 + endloop + endfacet + facet normal -0.656067 -0.591723 -0.468444 + outer loop + vertex 386.664 90.011 231.611 + vertex 382.113 92.7116 234.573 + vertex 383.848 93.2692 231.439 + endloop + endfacet + facet normal -0.662095 -0.596175 -0.454098 + outer loop + vertex 386.664 90.011 231.611 + vertex 383.848 93.2692 231.439 + vertex 388.384 90.5703 228.369 + endloop + endfacet + facet normal -0.66342 -0.586712 -0.464374 + outer loop + vertex 388.384 90.5703 228.369 + vertex 383.848 93.2692 231.439 + vertex 385.603 93.8291 228.223 + endloop + endfacet + facet normal -0.640181 -0.602151 -0.477055 + outer loop + vertex 381.549 88.2979 240.854 + vertex 378.659 91.5729 240.599 + vertex 383.249 88.8735 237.847 + endloop + endfacet + facet normal -0.640883 -0.594101 -0.48612 + outer loop + vertex 383.249 88.8735 237.847 + vertex 378.659 91.5729 240.599 + vertex 380.387 92.1472 237.619 + endloop + endfacet + facet normal -0.648641 -0.599672 -0.468676 + outer loop + vertex 383.249 88.8735 237.847 + vertex 380.387 92.1472 237.619 + vertex 384.946 89.4395 234.774 + endloop + endfacet + facet normal -0.649472 -0.591628 -0.477663 + outer loop + vertex 384.946 89.4395 234.774 + vertex 380.387 92.1472 237.619 + vertex 382.113 92.7116 234.573 + endloop + endfacet + facet normal -0.6269 -0.603329 -0.492941 + outer loop + vertex 378.083 87.1011 246.783 + vertex 375.165 90.3906 246.468 + vertex 379.825 87.7048 243.829 + endloop + endfacet + facet normal -0.627311 -0.596803 -0.500307 + outer loop + vertex 379.825 87.7048 243.829 + vertex 375.165 90.3906 246.468 + vertex 376.925 90.992 243.545 + endloop + endfacet + facet normal -0.633574 -0.601179 -0.486999 + outer loop + vertex 379.825 87.7048 243.829 + vertex 376.925 90.992 243.545 + vertex 381.549 88.2979 240.854 + endloop + endfacet + facet normal -0.633837 -0.597639 -0.490997 + outer loop + vertex 381.549 88.2979 240.854 + vertex 376.925 90.992 243.545 + vertex 378.659 91.5729 240.599 + endloop + endfacet + facet normal -0.612662 -0.604606 -0.509016 + outer loop + vertex 374.566 85.8631 252.544 + vertex 371.626 89.1612 252.166 + vertex 376.32 86.4803 249.7 + endloop + endfacet + facet normal -0.612779 -0.600628 -0.513564 + outer loop + vertex 376.32 86.4803 249.7 + vertex 371.626 89.1612 252.166 + vertex 373.385 89.7711 249.354 + endloop + endfacet + facet normal -0.618298 -0.604379 -0.502428 + outer loop + vertex 376.32 86.4803 249.7 + vertex 373.385 89.7711 249.354 + vertex 378.083 87.1011 246.783 + endloop + endfacet + facet normal -0.618627 -0.597624 -0.510045 + outer loop + vertex 378.083 87.1011 246.783 + vertex 373.385 89.7711 249.354 + vertex 375.165 90.3906 246.468 + endloop + endfacet + facet normal -0.600044 -0.601399 -0.527509 + outer loop + vertex 371.107 84.653 257.925 + vertex 368.162 87.9759 257.486 + vertex 372.825 85.2516 255.288 + endloop + endfacet + facet normal -0.599984 -0.599489 -0.529748 + outer loop + vertex 372.825 85.2516 255.288 + vertex 368.162 87.9759 257.486 + vertex 369.881 88.5597 254.878 + endloop + endfacet + facet normal -0.605745 -0.603262 -0.518794 + outer loop + vertex 372.825 85.2516 255.288 + vertex 369.881 88.5597 254.878 + vertex 374.566 85.8631 252.544 + endloop + endfacet + facet normal -0.605746 -0.599995 -0.522569 + outer loop + vertex 374.566 85.8631 252.544 + vertex 369.881 88.5597 254.878 + vertex 371.626 89.1612 252.166 + endloop + endfacet + facet normal -0.585413 -0.596797 -0.548749 + outer loop + vertex 367.725 83.4631 262.923 + vertex 364.781 86.8029 262.431 + vertex 369.412 84.0658 260.467 + endloop + endfacet + facet normal -0.585226 -0.594734 -0.551183 + outer loop + vertex 369.412 84.0658 260.467 + vertex 364.781 86.8029 262.431 + vertex 366.465 87.3973 260.001 + endloop + endfacet + facet normal -0.594335 -0.600521 -0.534921 + outer loop + vertex 369.412 84.0658 260.467 + vertex 366.465 87.3973 260.001 + vertex 371.107 84.653 257.925 + endloop + endfacet + facet normal -0.594156 -0.597615 -0.538363 + outer loop + vertex 371.107 84.653 257.925 + vertex 366.465 87.3973 260.001 + vertex 368.162 87.9759 257.486 + endloop + endfacet + facet normal -0.573269 -0.59227 -0.566197 + outer loop + vertex 364.596 82.3104 267.351 + vertex 361.652 85.6697 266.817 + vertex 366.095 82.864 265.254 + endloop + endfacet + facet normal -0.572794 -0.589841 -0.569205 + outer loop + vertex 366.095 82.864 265.254 + vertex 361.652 85.6697 266.817 + vertex 363.16 86.2135 264.736 + endloop + endfacet + facet normal -0.579564 -0.594027 -0.557887 + outer loop + vertex 366.095 82.864 265.254 + vertex 363.16 86.2135 264.736 + vertex 367.725 83.4631 262.923 + endloop + endfacet + facet normal -0.579439 -0.593048 -0.559057 + outer loop + vertex 367.725 83.4631 262.923 + vertex 363.16 86.2135 264.736 + vertex 364.781 86.8029 262.431 + endloop + endfacet + facet normal -0.575746 -0.581371 -0.574913 + outer loop + vertex 362.403 81.6149 270.252 + vertex 359.497 85.0481 269.691 + vertex 363.332 81.8727 269.062 + endloop + endfacet + facet normal -0.581446 -0.591482 -0.558632 + outer loop + vertex 363.332 81.8727 269.062 + vertex 359.497 85.0481 269.691 + vertex 360.405 85.2722 268.508 + endloop + endfacet + facet normal -0.572644 -0.586252 -0.573051 + outer loop + vertex 363.332 81.8727 269.062 + vertex 360.405 85.2722 268.508 + vertex 364.596 82.3104 267.351 + endloop + endfacet + facet normal -0.574961 -0.593308 -0.563388 + outer loop + vertex 364.596 82.3104 267.351 + vertex 360.405 85.2722 268.508 + vertex 361.652 85.6697 266.817 + endloop + endfacet + facet normal -0.540192 -0.558665 -0.629353 + outer loop + vertex 361.651 81.4086 271.171 + vertex 358.777 84.805 270.623 + vertex 361.848 81.5169 270.906 + endloop + endfacet + facet normal -0.53098 -0.55128 -0.643545 + outer loop + vertex 361.848 81.5169 270.906 + vertex 358.777 84.805 270.623 + vertex 358.963 84.9392 270.355 + endloop + endfacet + facet normal -0.576643 -0.578983 -0.576422 + outer loop + vertex 361.848 81.5169 270.906 + vertex 358.963 84.9392 270.355 + vertex 362.403 81.6149 270.252 + endloop + endfacet + facet normal -0.582261 -0.585168 -0.564403 + outer loop + vertex 362.403 81.6149 270.252 + vertex 358.963 84.9392 270.355 + vertex 359.497 85.0481 269.691 + endloop + endfacet + facet normal -0.318001 -0.414589 -0.852638 + outer loop + vertex 361.945 80.9727 271.274 + vertex 358.918 84.4729 270.7 + vertex 361.651 81.4086 271.171 + endloop + endfacet + facet normal -0.160344 -0.288035 -0.9441 + outer loop + vertex 361.651 81.4086 271.171 + vertex 358.918 84.4729 270.7 + vertex 358.777 84.805 270.623 + endloop + endfacet + facet normal -0.926839 -0.321708 0.193582 + outer loop + vertex 427.976 110.089 68.9861 + vertex 428.276 110.309 70.7922 + vertex 425.836 117.37 70.8448 + endloop + endfacet + facet normal 0.0849047 -0.959243 0.269525 + outer loop + vertex 505.491 75.2565 58.2223 + vertex 506.154 76.4209 62.1577 + vertex 505.656 75.9608 60.6772 + endloop + endfacet + facet normal 0.0796758 -0.952414 0.294208 + outer loop + vertex 504.457 73.8285 53.8797 + vertex 505.491 75.2565 58.2223 + vertex 504.755 74.6555 56.476 + endloop + endfacet + facet normal 0.0750456 -0.943724 0.322106 + outer loop + vertex 503.102 72.2433 49.551 + vertex 504.457 73.8285 53.8797 + vertex 503.475 73.1016 51.9787 + endloop + endfacet + facet normal 0.0940248 -0.934885 0.34227 + outer loop + vertex 501.717 70.72 45.7706 + vertex 503.102 72.2433 49.551 + vertex 501.806 71.3012 47.3338 + endloop + endfacet + facet normal -0.108879 -0.0280725 -0.993659 + outer loop + vertex 349.974 105.646 269.467 + vertex 349.127 109.66 269.446 + vertex 349.988 105.872 269.459 + endloop + endfacet + facet normal 0.682023 0.169616 0.71139 + outer loop + vertex 350.862 102.001 269.484 + vertex 349.974 105.646 269.467 + vertex 350.559 103.041 269.527 + endloop + endfacet + facet normal 0.838749 0.256455 0.480344 + outer loop + vertex 351.768 98.8759 269.571 + vertex 350.862 102.001 269.484 + vertex 351.477 99.782 269.595 + endloop + endfacet + facet normal 0.612013 0.175643 -0.771097 + outer loop + vertex 352.7 96.1352 269.686 + vertex 351.768 98.8759 269.571 + vertex 352.864 95.7818 269.736 + endloop + endfacet + facet normal 0.780581 0.283634 -0.556997 + outer loop + vertex 353.896 93.1716 269.853 + vertex 352.7 96.1352 269.686 + vertex 352.864 95.7818 269.736 + endloop + endfacet + facet normal 0.906789 0.421341 0.0143673 + outer loop + vertex 355.295 90.153 270.055 + vertex 353.896 93.1716 269.853 + vertex 354.656 91.5319 269.974 + endloop + endfacet + facet normal 0.765882 0.479671 0.428182 + outer loop + vertex 357.005 87.1761 270.332 + vertex 355.295 90.153 270.055 + vertex 356.567 87.9236 270.278 + endloop + endfacet + facet normal 0.685696 0.402758 -0.606306 + outer loop + vertex 359.314 83.865 270.745 + vertex 357.005 87.1761 270.332 + vertex 358.918 84.4729 270.7 + endloop + endfacet + facet normal 0.365829 0.16526 -0.915892 + outer loop + vertex 361.409 81.3871 271.134 + vertex 359.314 83.865 270.745 + vertex 361.945 80.9727 271.274 + endloop + endfacet + facet normal 0.452758 0.303704 -0.838316 + outer loop + vertex 363.919 79.0356 271.638 + vertex 361.409 81.3871 271.134 + vertex 361.945 80.9727 271.274 + endloop + endfacet + facet normal 0.328899 0.606881 0.723547 + outer loop + vertex 367.2 76.4644 272.303 + vertex 363.919 79.0356 271.638 + vertex 365.672 77.643 272.009 + endloop + endfacet + facet normal -0.145274 0.0956411 0.984758 + outer loop + vertex 370.798 74.2155 273.053 + vertex 367.2 76.4644 272.303 + vertex 369.343 75.1015 272.752 + endloop + endfacet + facet normal -0.072651 0.275228 0.95863 + outer loop + vertex 374.726 72.3026 273.9 + vertex 370.798 74.2155 273.053 + vertex 373.227 73.0067 273.584 + endloop + endfacet + facet normal 0.131118 0.726667 0.674361 + outer loop + vertex 378.839 70.7131 274.813 + vertex 374.726 72.3026 273.9 + vertex 377.367 71.2526 274.517 + endloop + endfacet + facet normal 0.142587 0.837582 0.527376 + outer loop + vertex 382.747 69.4871 275.703 + vertex 378.839 70.7131 274.813 + vertex 381.447 69.8667 275.452 + endloop + endfacet + facet normal -0.0848627 0.496789 0.863712 + outer loop + vertex 387.596 68.3601 276.828 + vertex 382.747 69.4871 275.703 + vertex 384.227 69.0753 276.085 + endloop + endfacet + facet normal -0.0387426 -0.846371 -0.531183 + outer loop + vertex 393.016 67.3204 278.089 + vertex 387.596 68.3601 276.828 + vertex 393.442 67.4959 277.778 + endloop + endfacet + facet normal -0.00659181 -0.866788 -0.498633 + outer loop + vertex 398.211 66.5739 279.318 + vertex 393.016 67.3204 278.089 + vertex 393.442 67.4959 277.778 + endloop + endfacet + facet normal 0.000558885 -0.899987 -0.435916 + outer loop + vertex 404.326 65.8406 280.84 + vertex 398.211 66.5739 279.318 + vertex 404.26 66.1627 280.175 + endloop + endfacet + facet normal 0.0351206 -0.89809 -0.438408 + outer loop + vertex 408.583 65.5342 281.809 + vertex 404.326 65.8406 280.84 + vertex 404.26 66.1627 280.175 + endloop + endfacet + facet normal 0.051738 -0.926267 -0.3733 + outer loop + vertex 412.701 65.2995 282.961 + vertex 408.583 65.5342 281.809 + vertex 413.161 65.5189 282.481 + endloop + endfacet + facet normal 0.0659336 -0.930061 -0.36144 + outer loop + vertex 416.319 65.2296 283.802 + vertex 412.701 65.2995 282.961 + vertex 413.161 65.5189 282.481 + endloop + endfacet + facet normal 0.0907681 -0.908926 -0.406959 + outer loop + vertex 418.74 65.1788 284.455 + vertex 416.319 65.2296 283.802 + vertex 421.202 65.3377 284.649 + endloop + endfacet + facet normal 0.0857905 -0.945612 -0.313781 + outer loop + vertex 421.377 65.1803 285.171 + vertex 418.74 65.1788 284.455 + vertex 421.202 65.3377 284.649 + endloop + endfacet + facet normal 0.0874877 -0.945298 -0.314258 + outer loop + vertex 425.232 65.2431 286.056 + vertex 421.377 65.1803 285.171 + vertex 421.202 65.3377 284.649 + endloop + endfacet + facet normal 0.100292 -0.94753 -0.303526 + outer loop + vertex 429.43 65.3062 287.246 + vertex 425.232 65.2431 286.056 + vertex 430.098 65.4861 286.905 + endloop + endfacet + facet normal 0.10656 -0.950256 -0.292674 + outer loop + vertex 433.568 65.4612 288.25 + vertex 429.43 65.3062 287.246 + vertex 430.098 65.4861 286.905 + endloop + endfacet + facet normal 0.129116 -0.942496 -0.308269 + outer loop + vertex 437.291 65.5956 289.398 + vertex 433.568 65.4612 288.25 + vertex 438.661 65.7908 289.374 + endloop + endfacet + facet normal 0.1304 -0.948962 -0.28717 + outer loop + vertex 440.061 65.7517 290.14 + vertex 437.291 65.5956 289.398 + vertex 438.661 65.7908 289.374 + endloop + endfacet + facet normal 0.172175 -0.916162 -0.361943 + outer loop + vertex 443.826 66.0138 291.267 + vertex 440.061 65.7517 290.14 + vertex 438.661 65.7908 289.374 + endloop + endfacet + facet normal 0.139132 -0.961662 -0.236322 + outer loop + vertex 447.473 66.2758 292.349 + vertex 443.826 66.0138 291.267 + vertex 447.183 66.3833 291.74 + endloop + endfacet + facet normal 0.160201 -0.956096 -0.245389 + outer loop + vertex 450.461 66.5549 293.211 + vertex 447.473 66.2758 292.349 + vertex 447.183 66.3833 291.74 + endloop + endfacet + facet normal 0.163544 -0.961922 -0.218996 + outer loop + vertex 454.18 66.9131 294.416 + vertex 450.461 66.5549 293.211 + vertex 455.419 67.1748 294.191 + endloop + endfacet + facet normal 0.168637 -0.96606 -0.195676 + outer loop + vertex 458.687 67.443 295.684 + vertex 454.18 66.9131 294.416 + vertex 455.419 67.1748 294.191 + endloop + endfacet + facet normal 0.194352 -0.949804 -0.245151 + outer loop + vertex 462.61 67.9166 296.959 + vertex 458.687 67.443 295.684 + vertex 464.621 68.2979 297.076 + endloop + endfacet + facet normal 0.193644 -0.961705 -0.193971 + outer loop + vertex 466.812 68.5048 298.237 + vertex 462.61 67.9166 296.959 + vertex 464.621 68.2979 297.076 + endloop + endfacet + facet normal 0.244541 -0.917131 -0.314756 + outer loop + vertex 470.393 69.0387 299.464 + vertex 466.812 68.5048 298.237 + vertex 471.404 69.2342 299.68 + endloop + endfacet + facet normal -0.277587 -0.913495 0.297442 + outer loop + vertex 456.166 77.7383 58.0245 + vertex 459.271 76.3776 56.7436 + vertex 457.449 77.9273 59.8025 + endloop + endfacet + facet normal -0.317667 -0.891131 0.323996 + outer loop + vertex 453.308 79.3457 59.644 + vertex 456.166 77.7383 58.0245 + vertex 457.449 77.9273 59.8025 + endloop + endfacet + facet normal -0.38427 -0.882209 0.272112 + outer loop + vertex 450.318 81.1049 61.1249 + vertex 453.308 79.3457 59.644 + vertex 452.705 80.4411 62.3429 + endloop + endfacet + facet normal -0.429988 -0.855939 0.287189 + outer loop + vertex 447.799 82.5245 61.5846 + vertex 450.318 81.1049 61.1249 + vertex 447.988 83.2061 63.8988 + endloop + endfacet + facet normal -0.494593 -0.82195 0.282447 + outer loop + vertex 445.185 84.4935 62.7364 + vertex 447.799 82.5245 61.5846 + vertex 447.988 83.2061 63.8988 + endloop + endfacet + facet normal -0.563547 -0.787878 0.248318 + outer loop + vertex 442.342 86.85 63.7625 + vertex 445.185 84.4935 62.7364 + vertex 444.167 85.7247 64.3316 + endloop + endfacet + facet normal -0.620002 -0.74941 0.232341 + outer loop + vertex 440.169 88.9274 64.6633 + vertex 442.342 86.85 63.7625 + vertex 441.611 87.8652 65.0856 + endloop + endfacet + facet normal -0.731469 -0.6775 0.077115 + outer loop + vertex 438.205 91.0982 65.1034 + vertex 440.169 88.9274 64.6633 + vertex 438.699 90.5933 65.356 + endloop + endfacet + facet normal -0.804994 -0.59231 0.03395 + outer loop + vertex 435.859 94.3347 65.9483 + vertex 438.205 91.0982 65.1034 + vertex 437.017 92.759 65.9095 + endloop + endfacet + facet normal -0.853514 -0.521047 -0.00493135 + outer loop + vertex 433.147 98.7682 66.897 + vertex 435.859 94.3347 65.9483 + vertex 434.862 95.9607 66.6715 + endloop + endfacet + facet normal -0.875202 -0.477803 0.0756747 + outer loop + vertex 430.518 103.703 67.6434 + vertex 433.147 98.7682 66.897 + vertex 431.279 102.332 67.7991 + endloop + endfacet + facet normal -0.868115 -0.4399 0.229924 + outer loop + vertex 429.036 106.836 68.0439 + vertex 430.518 103.703 67.6434 + vertex 429.468 106.079 68.2251 + endloop + endfacet + facet normal -0.917623 -0.384053 0.102327 + outer loop + vertex 427.875 109.59 67.9713 + vertex 429.036 106.836 68.0439 + vertex 428.518 108.144 68.3042 + endloop + endfacet + facet normal -0.908105 -0.33319 0.253632 + outer loop + vertex 426.378 114.06 68.4811 + vertex 427.875 109.59 67.9713 + vertex 427.976 110.089 68.9861 + endloop + endfacet + facet normal -0.939844 -0.264721 0.215905 + outer loop + vertex 423.224 124.557 68.5067 + vertex 424.366 120.799 68.871 + vertex 423.047 127.001 70.735 + endloop + endfacet + facet normal 0.235176 -0.931434 -0.277711 + outer loop + vertex 464.621 68.2979 297.076 + vertex 471.404 69.2342 299.68 + vertex 466.812 68.5048 298.237 + endloop + endfacet + facet normal 0.197871 -0.944106 -0.263649 + outer loop + vertex 455.419 67.1748 294.191 + vertex 464.621 68.2979 297.076 + vertex 458.687 67.443 295.684 + endloop + endfacet + facet normal 0.172404 -0.946229 -0.273729 + outer loop + vertex 447.183 66.3833 291.74 + vertex 455.419 67.1748 294.191 + vertex 450.461 66.5549 293.211 + endloop + endfacet + facet normal 0.144056 -0.948728 -0.281359 + outer loop + vertex 438.661 65.7908 289.374 + vertex 447.183 66.3833 291.74 + vertex 443.826 66.0138 291.267 + endloop + endfacet + facet normal 0.145463 -0.908263 -0.392299 + outer loop + vertex 430.098 65.4861 286.905 + vertex 438.661 65.7908 289.374 + vertex 433.568 65.4612 288.25 + endloop + endfacet + facet normal 0.112978 -0.915847 -0.385305 + outer loop + vertex 421.202 65.3377 284.649 + vertex 430.098 65.4861 286.905 + vertex 425.232 65.2431 286.056 + endloop + endfacet + facet normal -0.237421 -0.916222 0.322752 + outer loop + vertex 460.792 76.0462 56.9218 + vertex 457.449 77.9273 59.8025 + vertex 459.271 76.3776 56.7436 + endloop + endfacet + facet normal 0.0928796 -0.902802 -0.419906 + outer loop + vertex 413.161 65.5189 282.481 + vertex 421.202 65.3377 284.649 + vertex 416.319 65.2296 283.802 + endloop + endfacet + facet normal -0.3198 -0.900705 0.294039 + outer loop + vertex 457.449 77.9273 59.8025 + vertex 452.705 80.4411 62.3429 + vertex 453.308 79.3457 59.644 + endloop + endfacet + facet normal 0.0738706 -0.849581 -0.52226 + outer loop + vertex 404.26 66.1627 280.175 + vertex 413.161 65.5189 282.481 + vertex 408.583 65.5342 281.809 + endloop + endfacet + facet normal -0.400319 -0.860365 0.315463 + outer loop + vertex 452.705 80.4411 62.3429 + vertex 447.988 83.2061 63.8988 + vertex 450.318 81.1049 61.1249 + endloop + endfacet + facet normal -0.035506 -0.942708 -0.331725 + outer loop + vertex 396.933 68.7154 273.577 + vertex 408.864 67.5224 275.691 + vertex 400.965 67.1479 277.601 + endloop + endfacet + facet normal 0.0246533 -0.822175 -0.5687 + outer loop + vertex 393.442 67.4959 277.778 + vertex 404.26 66.1627 280.175 + vertex 398.211 66.5739 279.318 + endloop + endfacet + facet normal -0.0601756 -0.949008 -0.309455 + outer loop + vertex 400.965 67.1479 277.601 + vertex 391.711 68.2037 276.162 + vertex 396.933 68.7154 273.577 + endloop + endfacet + facet normal -0.499305 -0.810337 0.306672 + outer loop + vertex 447.988 83.2061 63.8988 + vertex 444.167 85.7247 64.3316 + vertex 445.185 84.4935 62.7364 + endloop + endfacet + facet normal -0.0888721 -0.936257 -0.339888 + outer loop + vertex 388.344 69.7726 272.911 + vertex 396.933 68.7154 273.577 + vertex 387.727 69.2336 274.557 + endloop + endfacet + facet normal 0.0320209 -0.633629 -0.772974 + outer loop + vertex 385.626 68.8296 276.361 + vertex 393.442 67.4959 277.778 + vertex 387.596 68.3601 276.828 + endloop + endfacet + facet normal -0.106386 -0.935708 -0.336352 + outer loop + vertex 391.711 68.2037 276.162 + vertex 385.642 69.121 275.53 + vertex 387.727 69.2336 274.557 + endloop + endfacet + facet normal -0.565922 -0.774829 0.281732 + outer loop + vertex 444.167 85.7247 64.3316 + vertex 441.611 87.8652 65.0856 + vertex 442.342 86.85 63.7625 + endloop + endfacet + facet normal -0.621099 -0.72319 0.302047 + outer loop + vertex 441.611 87.8652 65.0856 + vertex 439.579 89.9305 65.8507 + vertex 440.169 88.9274 64.6633 + endloop + endfacet + facet normal 0.310169 0.929453 -0.199781 + outer loop + vertex 381.447 69.8667 275.452 + vertex 384.227 69.0753 276.085 + vertex 382.747 69.4871 275.703 + endloop + endfacet + facet normal 0.072821 -0.532384 -0.843365 + outer loop + vertex 384.227 69.0753 276.085 + vertex 385.626 68.8296 276.361 + vertex 387.596 68.3601 276.828 + endloop + endfacet + facet normal 0.37425 0.66872 -0.642456 + outer loop + vertex 377.367 71.2526 274.517 + vertex 381.447 69.8667 275.452 + vertex 378.839 70.7131 274.813 + endloop + endfacet + facet normal -0.782215 -0.580327 0.226626 + outer loop + vertex 437.017 92.759 65.9095 + vertex 434.862 95.9607 66.6715 + vertex 435.859 94.3347 65.9483 + endloop + endfacet + facet normal -0.669527 -0.697257 0.256059 + outer loop + vertex 439.579 89.9305 65.8507 + vertex 438.699 90.5933 65.356 + vertex 440.169 88.9274 64.6633 + endloop + endfacet + facet normal -0.748313 -0.632429 0.200153 + outer loop + vertex 438.699 90.5933 65.356 + vertex 437.017 92.759 65.9095 + vertex 438.205 91.0982 65.1034 + endloop + endfacet + facet normal 0.325336 0.288648 -0.900466 + outer loop + vertex 373.227 73.0067 273.584 + vertex 377.367 71.2526 274.517 + vertex 374.726 72.3026 273.9 + endloop + endfacet + facet normal 0.261607 0.104024 -0.959552 + outer loop + vertex 369.343 75.1015 272.752 + vertex 373.227 73.0067 273.584 + vertex 370.798 74.2155 273.053 + endloop + endfacet + facet normal -0.881129 -0.471353 0.0379241 + outer loop + vertex 432.994 99.0905 67.3496 + vertex 431.279 102.332 67.7991 + vertex 433.147 98.7682 66.897 + endloop + endfacet + facet normal -0.846958 -0.524449 0.0872689 + outer loop + vertex 434.862 95.9607 66.6715 + vertex 432.994 99.0905 67.3496 + vertex 433.147 98.7682 66.897 + endloop + endfacet + facet normal 0.274407 0.117433 -0.954416 + outer loop + vertex 365.672 77.643 272.009 + vertex 369.343 75.1015 272.752 + vertex 367.2 76.4644 272.303 + endloop + endfacet + facet normal 0.30809 0.136861 -0.941461 + outer loop + vertex 361.945 80.9727 271.274 + vertex 365.672 77.643 272.009 + vertex 363.919 79.0356 271.638 + endloop + endfacet + facet normal -0.850344 -0.404095 0.337078 + outer loop + vertex 429.468 106.079 68.2251 + vertex 428.518 108.144 68.3042 + vertex 429.036 106.836 68.0439 + endloop + endfacet + facet normal -0.854056 -0.443821 0.271314 + outer loop + vertex 431.279 102.332 67.7991 + vertex 429.468 106.079 68.2251 + vertex 430.518 103.703 67.6434 + endloop + endfacet + facet normal 0.385728 0.185577 -0.903756 + outer loop + vertex 358.918 84.4729 270.7 + vertex 361.945 80.9727 271.274 + vertex 359.314 83.865 270.745 + endloop + endfacet + facet normal 0.449915 0.199877 -0.870417 + outer loop + vertex 356.567 87.9236 270.278 + vertex 358.918 84.4729 270.7 + vertex 357.005 87.1761 270.332 + endloop + endfacet + facet normal -0.907267 -0.332332 0.257725 + outer loop + vertex 427.976 110.089 68.9861 + vertex 425.836 117.37 70.8448 + vertex 426.378 114.06 68.4811 + endloop + endfacet + facet normal 0.36089 0.113348 -0.925695 + outer loop + vertex 354.656 91.5319 269.974 + vertex 356.567 87.9236 270.278 + vertex 355.295 90.153 270.055 + endloop + endfacet + facet normal 0.394095 0.114974 -0.91185 + outer loop + vertex 352.864 95.7818 269.736 + vertex 354.656 91.5319 269.974 + vertex 353.896 93.1716 269.853 + endloop + endfacet + facet normal -0.93529 -0.268238 0.230827 + outer loop + vertex 425.836 117.37 70.8448 + vertex 423.047 127.001 70.735 + vertex 424.366 120.799 68.871 + endloop + endfacet + facet normal 0.883709 0.293602 -0.364495 + outer loop + vertex 351.477 99.782 269.595 + vertex 352.864 95.7818 269.736 + vertex 351.768 98.8759 269.571 + endloop + endfacet + facet normal 0.951123 0.271017 0.148035 + outer loop + vertex 350.559 103.041 269.527 + vertex 351.477 99.782 269.595 + vertex 350.862 102.001 269.484 + endloop + endfacet + facet normal -0.557681 -0.129444 -0.8199 + outer loop + vertex 348.659 112.985 269.24 + vertex 349.988 105.872 269.459 + vertex 349.127 109.66 269.446 + endloop + endfacet + facet normal -0.0912082 -0.925538 -0.367507 + outer loop + vertex 396.933 68.7154 273.577 + vertex 391.711 68.2037 276.162 + vertex 387.727 69.2336 274.557 + endloop + endfacet + facet normal -0.237636 -0.903043 0.35783 + outer loop + vertex 456.726 77.1178 56.761 + vertex 456.696 76.5815 55.3877 + vertex 460.324 75.5466 55.1855 + endloop + endfacet + facet normal -0.235149 -0.897368 0.373412 + outer loop + vertex 460.324 75.5466 55.1855 + vertex 456.696 76.5815 55.3877 + vertex 460.259 74.961 53.7374 + endloop + endfacet + facet normal -0.184114 -0.908327 0.375559 + outer loop + vertex 460.324 75.5466 55.1855 + vertex 460.259 74.961 53.7374 + vertex 463.769 74.126 53.4382 + endloop + endfacet + facet normal -0.17929 -0.897699 0.402481 + outer loop + vertex 463.769 74.126 53.4382 + vertex 460.259 74.961 53.7374 + vertex 463.059 73.712 52.1987 + endloop + endfacet + facet normal -0.367345 -0.866981 0.336752 + outer loop + vertex 449.448 81.1605 60.0037 + vertex 449.244 80.6747 58.5303 + vertex 453.17 78.9168 58.2876 + endloop + endfacet + facet normal -0.364271 -0.862216 0.35198 + outer loop + vertex 453.17 78.9168 58.2876 + vertex 449.244 80.6747 58.5303 + vertex 452.944 78.4735 56.9676 + endloop + endfacet + facet normal -0.299199 -0.887901 0.349444 + outer loop + vertex 453.17 78.9168 58.2876 + vertex 452.944 78.4735 56.9676 + vertex 456.726 77.1178 56.761 + endloop + endfacet + facet normal -0.29861 -0.886771 0.352803 + outer loop + vertex 456.726 77.1178 56.761 + vertex 452.944 78.4735 56.9676 + vertex 456.696 76.5815 55.3877 + endloop + endfacet + facet normal -0.535515 -0.78862 0.302162 + outer loop + vertex 442.604 86.3357 62.7758 + vertex 442.421 85.9654 61.4862 + vertex 445.649 83.7559 61.4395 + endloop + endfacet + facet normal -0.534528 -0.787287 0.307341 + outer loop + vertex 445.649 83.7559 61.4395 + vertex 442.421 85.9654 61.4862 + vertex 445.683 83.1973 60.068 + endloop + endfacet + facet normal -0.445106 -0.833145 0.328253 + outer loop + vertex 445.649 83.7559 61.4395 + vertex 445.683 83.1973 60.068 + vertex 449.448 81.1605 60.0037 + endloop + endfacet + facet normal -0.443801 -0.830961 0.335477 + outer loop + vertex 449.448 81.1605 60.0037 + vertex 445.683 83.1973 60.068 + vertex 449.244 80.6747 58.5303 + endloop + endfacet + facet normal -0.691053 -0.653889 0.308018 + outer loop + vertex 436.675 92.9869 65.1675 + vertex 436.772 92.2845 63.895 + vertex 439.642 89.3416 64.0867 + endloop + endfacet + facet normal -0.697581 -0.662553 0.272771 + outer loop + vertex 439.642 89.3416 64.0867 + vertex 436.772 92.2845 63.895 + vertex 439.501 88.9487 62.7712 + endloop + endfacet + facet normal -0.617699 -0.732877 0.285198 + outer loop + vertex 439.642 89.3416 64.0867 + vertex 439.501 88.9487 62.7712 + vertex 442.604 86.3357 62.7758 + endloop + endfacet + facet normal -0.615457 -0.730194 0.296697 + outer loop + vertex 442.604 86.3357 62.7758 + vertex 439.501 88.9487 62.7712 + vertex 442.421 85.9654 61.4862 + endloop + endfacet + facet normal -0.801826 -0.507377 0.315663 + outer loop + vertex 431.655 101.239 66.8493 + vertex 431.875 100.106 65.5888 + vertex 434.082 96.9333 66.0956 + endloop + endfacet + facet normal -0.808074 -0.517059 0.282252 + outer loop + vertex 434.082 96.9333 66.0956 + vertex 431.875 100.106 65.5888 + vertex 434.22 96.0273 64.8298 + endloop + endfacet + facet normal -0.752663 -0.571374 0.327153 + outer loop + vertex 434.082 96.9333 66.0956 + vertex 434.22 96.0273 64.8298 + vertex 436.675 92.9869 65.1675 + endloop + endfacet + facet normal -0.764275 -0.587564 0.265805 + outer loop + vertex 436.675 92.9869 65.1675 + vertex 434.22 96.0273 64.8298 + vertex 436.772 92.2845 63.895 + endloop + endfacet + facet normal -0.8927 -0.421593 0.159202 + outer loop + vertex 429.066 106.646 67.7224 + vertex 428.07 108.374 66.716 + vertex 429.872 104.773 67.2849 + endloop + endfacet + facet normal -0.883662 -0.405179 0.234459 + outer loop + vertex 429.872 104.773 67.2849 + vertex 428.07 108.374 66.716 + vertex 429.803 104.272 66.1577 + endloop + endfacet + facet normal -0.849779 -0.460298 0.256909 + outer loop + vertex 429.872 104.773 67.2849 + vertex 429.803 104.272 66.1577 + vertex 431.655 101.239 66.8493 + endloop + endfacet + facet normal -0.848899 -0.458301 0.263309 + outer loop + vertex 431.655 101.239 66.8493 + vertex 429.803 104.272 66.1577 + vertex 431.875 100.106 65.5888 + endloop + endfacet + facet normal 0.0541069 -0.790526 0.610033 + outer loop + vertex 489.544 65.4607 37.4846 + vertex 483.621 64.2591 36.4528 + vertex 482.501 63.4894 35.5546 + endloop + endfacet + facet normal 0.0773067 -0.843588 0.531397 + outer loop + vertex 489.544 65.4607 37.4846 + vertex 494.476 66.9642 39.1538 + vertex 491.848 66.3503 38.5616 + endloop + endfacet + facet normal 0.0483112 -0.831134 0.55397 + outer loop + vertex 479.917 65.5624 38.6907 + vertex 482.415 64.8749 37.4414 + vertex 486.391 66.3358 39.2864 + endloop + endfacet + facet normal 0.0583378 -0.813825 0.578175 + outer loop + vertex 482.415 64.8749 37.4414 + vertex 483.621 64.2591 36.4528 + vertex 488.352 65.6949 37.9964 + endloop + endfacet + facet normal -0.0470611 -0.851879 0.521619 + outer loop + vertex 473.767 69.1665 44.8622 + vertex 467.03 69.0924 44.1334 + vertex 470.082 67.9599 42.5593 + endloop + endfacet + facet normal -0.0223963 -0.84739 0.530499 + outer loop + vertex 476.629 68.3077 43.3913 + vertex 470.082 67.9599 42.5593 + vertex 473.04 67.0119 41.1699 + endloop + endfacet + facet normal -0.116792 -0.887901 0.444963 + outer loop + vertex 462.502 72.8756 50.1832 + vertex 460.162 71.8598 47.5421 + vertex 466.236 71.5197 48.4575 + endloop + endfacet + facet normal -0.121956 -0.864281 0.488 + outer loop + vertex 466.236 71.5197 48.4575 + vertex 460.162 71.8598 47.5421 + vertex 463.65 70.3967 45.8225 + endloop + endfacet + facet normal -0.131045 -0.902332 0.41064 + outer loop + vertex 463.059 73.712 52.1987 + vertex 462.502 72.8756 50.1832 + vertex 466.71 72.7038 51.1486 + endloop + endfacet + facet normal -0.132733 -0.898371 0.418703 + outer loop + vertex 466.71 72.7038 51.1486 + vertex 462.502 72.8756 50.1832 + vertex 466.236 71.5197 48.4575 + endloop + endfacet + facet normal -0.0837341 -0.897283 0.433441 + outer loop + vertex 471.15 71.3367 49.0281 + vertex 466.236 71.5197 48.4575 + vertex 470.199 70.2506 46.596 + endloop + endfacet + facet normal -0.0730989 -0.889602 0.45085 + outer loop + vertex 466.236 71.5197 48.4575 + vertex 463.65 70.3967 45.8225 + vertex 470.199 70.2506 46.596 + endloop + endfacet + facet normal -0.078886 -0.859152 0.505604 + outer loop + vertex 470.199 70.2506 46.596 + vertex 463.65 70.3967 45.8225 + vertex 467.03 69.0924 44.1334 + endloop + endfacet + facet normal -0.215464 -0.872731 0.438081 + outer loop + vertex 455.532 76.0302 53.4535 + vertex 453.244 75.3071 50.8879 + vertex 459.048 74.3326 51.8009 + endloop + endfacet + facet normal -0.218163 -0.849981 0.479518 + outer loop + vertex 459.048 74.3326 51.8009 + vertex 453.244 75.3071 50.8879 + vertex 456.683 73.4862 49.2243 + endloop + endfacet + facet normal -0.225359 -0.892788 0.390055 + outer loop + vertex 456.696 76.5815 55.3877 + vertex 455.532 76.0302 53.4535 + vertex 460.259 74.961 53.7374 + endloop + endfacet + facet normal -0.223915 -0.877207 0.4247 + outer loop + vertex 460.259 74.961 53.7374 + vertex 455.532 76.0302 53.4535 + vertex 459.048 74.3326 51.8009 + endloop + endfacet + facet normal -0.178862 -0.897506 0.403103 + outer loop + vertex 460.259 74.961 53.7374 + vertex 459.048 74.3326 51.8009 + vertex 463.059 73.712 52.1987 + endloop + endfacet + facet normal -0.179292 -0.890148 0.418916 + outer loop + vertex 463.059 73.712 52.1987 + vertex 459.048 74.3326 51.8009 + vertex 462.502 72.8756 50.1832 + endloop + endfacet + facet normal -0.16527 -0.881931 0.441455 + outer loop + vertex 459.048 74.3326 51.8009 + vertex 456.683 73.4862 49.2243 + vertex 462.502 72.8756 50.1832 + endloop + endfacet + facet normal -0.169503 -0.860181 0.480997 + outer loop + vertex 462.502 72.8756 50.1832 + vertex 456.683 73.4862 49.2243 + vertex 460.162 71.8598 47.5421 + endloop + endfacet + facet normal -0.337769 -0.839822 0.424983 + outer loop + vertex 448.242 80.2501 56.6559 + vertex 446.313 79.7093 54.0541 + vertex 451.875 77.9981 55.0932 + endloop + endfacet + facet normal -0.338611 -0.813224 0.473296 + outer loop + vertex 451.875 77.9981 55.0932 + vertex 446.313 79.7093 54.0541 + vertex 449.75 77.3759 52.5033 + endloop + endfacet + facet normal -0.348855 -0.856494 0.380419 + outer loop + vertex 449.244 80.6747 58.5303 + vertex 448.242 80.2501 56.6559 + vertex 452.944 78.4735 56.9676 + endloop + endfacet + facet normal -0.345938 -0.843387 0.411127 + outer loop + vertex 452.944 78.4735 56.9676 + vertex 448.242 80.2501 56.6559 + vertex 451.875 77.9981 55.0932 + endloop + endfacet + facet normal -0.281861 -0.879379 0.383728 + outer loop + vertex 452.944 78.4735 56.9676 + vertex 451.875 77.9981 55.0932 + vertex 456.696 76.5815 55.3877 + endloop + endfacet + facet normal -0.27976 -0.865713 0.415061 + outer loop + vertex 456.696 76.5815 55.3877 + vertex 451.875 77.9981 55.0932 + vertex 455.532 76.0302 53.4535 + endloop + endfacet + facet normal -0.271037 -0.861471 0.429426 + outer loop + vertex 451.875 77.9981 55.0932 + vertex 449.75 77.3759 52.5033 + vertex 455.532 76.0302 53.4535 + endloop + endfacet + facet normal -0.272852 -0.83461 0.478516 + outer loop + vertex 455.532 76.0302 53.4535 + vertex 449.75 77.3759 52.5033 + vertex 453.244 75.3071 50.8879 + endloop + endfacet + facet normal -0.493637 -0.764492 0.414577 + outer loop + vertex 441.565 85.64 59.5476 + vertex 439.952 85.2256 56.8629 + vertex 444.775 82.8057 58.1428 + endloop + endfacet + facet normal -0.49261 -0.736698 0.463262 + outer loop + vertex 444.775 82.8057 58.1428 + vertex 439.952 85.2256 56.8629 + vertex 443.03 82.3229 55.5193 + endloop + endfacet + facet normal -0.509634 -0.783097 0.356416 + outer loop + vertex 442.421 85.9654 61.4862 + vertex 441.565 85.64 59.5476 + vertex 445.683 83.1973 60.068 + endloop + endfacet + facet normal -0.50524 -0.767607 0.394351 + outer loop + vertex 445.683 83.1973 60.068 + vertex 441.565 85.64 59.5476 + vertex 444.775 82.8057 58.1428 + endloop + endfacet + facet normal -0.425958 -0.826131 0.368873 + outer loop + vertex 445.683 83.1973 60.068 + vertex 444.775 82.8057 58.1428 + vertex 449.244 80.6747 58.5303 + endloop + endfacet + facet normal -0.4215 -0.809556 0.408603 + outer loop + vertex 449.244 80.6747 58.5303 + vertex 444.775 82.8057 58.1428 + vertex 448.242 80.2501 56.6559 + endloop + endfacet + facet normal -0.412991 -0.80647 0.423137 + outer loop + vertex 444.775 82.8057 58.1428 + vertex 443.03 82.3229 55.5193 + vertex 448.242 80.2501 56.6559 + endloop + endfacet + facet normal -0.412794 -0.781149 0.468409 + outer loop + vertex 448.242 80.2501 56.6559 + vertex 443.03 82.3229 55.5193 + vertex 446.313 79.7093 54.0541 + endloop + endfacet + facet normal -0.651676 -0.647994 0.394237 + outer loop + vertex 435.987 92.0446 61.8687 + vertex 434.534 91.8061 59.0751 + vertex 438.639 88.7213 60.7907 + endloop + endfacet + facet normal -0.649945 -0.622426 0.436069 + outer loop + vertex 438.639 88.7213 60.7907 + vertex 434.534 91.8061 59.0751 + vertex 437.117 88.3965 58.0581 + endloop + endfacet + facet normal -0.669505 -0.661517 0.337874 + outer loop + vertex 436.772 92.2845 63.895 + vertex 435.987 92.0446 61.8687 + vertex 439.501 88.9487 62.7712 + endloop + endfacet + facet normal -0.666458 -0.650226 0.364747 + outer loop + vertex 439.501 88.9487 62.7712 + vertex 435.987 92.0446 61.8687 + vertex 438.639 88.7213 60.7907 + endloop + endfacet + facet normal -0.593668 -0.728399 0.342042 + outer loop + vertex 439.501 88.9487 62.7712 + vertex 438.639 88.7213 60.7907 + vertex 442.421 85.9654 61.4862 + endloop + endfacet + facet normal -0.589384 -0.71298 0.379849 + outer loop + vertex 442.421 85.9654 61.4862 + vertex 438.639 88.7213 60.7907 + vertex 441.565 85.64 59.5476 + endloop + endfacet + facet normal -0.575719 -0.710211 0.405152 + outer loop + vertex 438.639 88.7213 60.7907 + vertex 437.117 88.3965 58.0581 + vertex 441.565 85.64 59.5476 + endloop + endfacet + facet normal -0.574348 -0.683461 0.450561 + outer loop + vertex 441.565 85.64 59.5476 + vertex 437.117 88.3965 58.0581 + vertex 439.952 85.2256 56.8629 + endloop + endfacet + facet normal -0.771649 -0.509482 0.380769 + outer loop + vertex 431.319 99.5812 63.4737 + vertex 430.072 99.3115 60.5862 + vertex 433.553 95.6594 62.7554 + endloop + endfacet + facet normal -0.769705 -0.492586 0.406095 + outer loop + vertex 433.553 95.6594 62.7554 + vertex 430.072 99.3115 60.5862 + vertex 432.195 95.442 59.9178 + endloop + endfacet + facet normal -0.788393 -0.51565 0.335473 + outer loop + vertex 431.875 100.106 65.5888 + vertex 431.319 99.5812 63.4737 + vertex 434.22 96.0273 64.8298 + endloop + endfacet + facet normal -0.787407 -0.511683 0.343759 + outer loop + vertex 434.22 96.0273 64.8298 + vertex 431.319 99.5812 63.4737 + vertex 433.553 95.6594 62.7554 + endloop + endfacet + facet normal -0.735183 -0.58631 0.340215 + outer loop + vertex 434.22 96.0273 64.8298 + vertex 433.553 95.6594 62.7554 + vertex 436.772 92.2845 63.895 + endloop + endfacet + facet normal -0.733682 -0.580506 0.353164 + outer loop + vertex 436.772 92.2845 63.895 + vertex 433.553 95.6594 62.7554 + vertex 435.987 92.0446 61.8687 + endloop + endfacet + facet normal -0.717768 -0.578289 0.387803 + outer loop + vertex 433.553 95.6594 62.7554 + vertex 432.195 95.442 59.9178 + vertex 435.987 92.0446 61.8687 + endloop + endfacet + facet normal -0.715919 -0.557768 0.419946 + outer loop + vertex 435.987 92.0446 61.8687 + vertex 432.195 95.442 59.9178 + vertex 434.534 91.8061 59.0751 + endloop + endfacet + facet normal -0.846851 -0.393673 0.357581 + outer loop + vertex 427.463 108.035 64.4433 + vertex 426.392 107.675 61.5096 + vertex 429.282 103.746 64.0286 + endloop + endfacet + facet normal -0.845021 -0.381076 0.375129 + outer loop + vertex 429.282 103.746 64.0286 + vertex 426.392 107.675 61.5096 + vertex 428.144 103.403 61.1162 + endloop + endfacet + facet normal -0.866236 -0.405615 0.291741 + outer loop + vertex 428.07 108.374 66.716 + vertex 427.463 108.035 64.4433 + vertex 429.803 104.272 66.1577 + endloop + endfacet + facet normal -0.864375 -0.39644 0.309341 + outer loop + vertex 429.803 104.272 66.1577 + vertex 427.463 108.035 64.4433 + vertex 429.282 103.746 64.0286 + endloop + endfacet + facet normal -0.83145 -0.456843 0.316205 + outer loop + vertex 429.803 104.272 66.1577 + vertex 429.282 103.746 64.0286 + vertex 431.875 100.106 65.5888 + endloop + endfacet + facet normal -0.829902 -0.4498 0.330063 + outer loop + vertex 431.875 100.106 65.5888 + vertex 429.282 103.746 64.0286 + vertex 431.319 99.5812 63.4737 + endloop + endfacet + facet normal -0.813872 -0.447383 0.370756 + outer loop + vertex 429.282 103.746 64.0286 + vertex 428.144 103.403 61.1162 + vertex 431.319 99.5812 63.4737 + endloop + endfacet + facet normal -0.811989 -0.43329 0.391068 + outer loop + vertex 431.319 99.5812 63.4737 + vertex 428.144 103.403 61.1162 + vertex 430.072 99.3115 60.5862 + endloop + endfacet + facet normal -0.88843 -0.303123 0.344685 + outer loop + vertex 424.349 116.936 64.8402 + vertex 423.375 116.497 61.9434 + vertex 425.815 112.451 64.6735 + endloop + endfacet + facet normal -0.887828 -0.299733 0.349173 + outer loop + vertex 425.815 112.451 64.6735 + vertex 423.375 116.497 61.9434 + vertex 424.808 112.06 61.779 + endloop + endfacet + facet normal -0.871645 -0.343663 0.349471 + outer loop + vertex 425.815 112.451 64.6735 + vertex 424.808 112.06 61.779 + vertex 427.463 108.035 64.4433 + endloop + endfacet + facet normal -0.870498 -0.336472 0.359192 + outer loop + vertex 427.463 108.035 64.4433 + vertex 424.808 112.06 61.779 + vertex 426.392 107.675 61.5096 + endloop + endfacet + facet normal -0.905602 -0.248845 0.343454 + outer loop + vertex 421.873 125.705 64.983 + vertex 420.913 125.299 62.1578 + vertex 423.046 121.39 64.9496 + endloop + endfacet + facet normal -0.905928 -0.250498 0.341389 + outer loop + vertex 423.046 121.39 64.9496 + vertex 420.913 125.299 62.1578 + vertex 422.09 120.923 62.0712 + endloop + endfacet + facet normal -0.899379 -0.271525 0.342626 + outer loop + vertex 423.046 121.39 64.9496 + vertex 422.09 120.923 62.0712 + vertex 424.349 116.936 64.8402 + endloop + endfacet + facet normal -0.899258 -0.270887 0.343446 + outer loop + vertex 424.349 116.936 64.8402 + vertex 422.09 120.923 62.0712 + vertex 423.375 116.497 61.9434 + endloop + endfacet + facet normal -0.912006 -0.224738 0.34313 + outer loop + vertex 419.761 134.23 65.0748 + vertex 418.765 133.953 62.247 + vertex 420.808 129.896 65.0204 + endloop + endfacet + facet normal -0.911961 -0.224548 0.343375 + outer loop + vertex 420.808 129.896 65.0204 + vertex 418.765 133.953 62.247 + vertex 419.82 129.619 62.2141 + endloop + endfacet + facet normal -0.909524 -0.234098 0.343459 + outer loop + vertex 420.808 129.896 65.0204 + vertex 419.82 129.619 62.2141 + vertex 421.873 125.705 64.983 + endloop + endfacet + facet normal -0.90964 -0.234636 0.342784 + outer loop + vertex 421.873 125.705 64.983 + vertex 419.82 129.619 62.2141 + vertex 420.913 125.299 62.1578 + endloop + endfacet + facet normal -0.913345 -0.216012 0.345166 + outer loop + vertex 417.595 143.315 65.072 + vertex 416.618 142.947 62.2581 + vertex 418.671 138.787 65.0865 + endloop + endfacet + facet normal -0.913697 -0.217426 0.343342 + outer loop + vertex 418.671 138.787 65.0865 + vertex 416.618 142.947 62.2581 + vertex 417.697 138.407 62.2525 + endloop + endfacet + facet normal -0.913235 -0.21923 0.343425 + outer loop + vertex 418.671 138.787 65.0865 + vertex 417.697 138.407 62.2525 + vertex 419.761 134.23 65.0748 + endloop + endfacet + facet normal -0.913301 -0.2195 0.343074 + outer loop + vertex 419.761 134.23 65.0748 + vertex 417.697 138.407 62.2525 + vertex 418.765 133.953 62.247 + endloop + endfacet + facet normal -0.914476 -0.21575 0.342323 + outer loop + vertex 415.49 152.275 65.0953 + vertex 414.487 152.028 62.2609 + vertex 416.548 147.753 65.0709 + endloop + endfacet + facet normal -0.914125 -0.214415 0.344095 + outer loop + vertex 416.548 147.753 65.0709 + vertex 414.487 152.028 62.2609 + vertex 415.551 147.498 62.2636 + endloop + endfacet + facet normal -0.913855 -0.21555 0.344103 + outer loop + vertex 416.548 147.753 65.0709 + vertex 415.551 147.498 62.2636 + vertex 417.595 143.315 65.072 + endloop + endfacet + facet normal -0.913657 -0.214775 0.345112 + outer loop + vertex 417.595 143.315 65.072 + vertex 415.551 147.498 62.2636 + vertex 416.618 142.947 62.2581 + endloop + endfacet + facet normal -0.915155 -0.214647 0.341202 + outer loop + vertex 413.353 161.363 65.0842 + vertex 412.384 161.006 62.2607 + vertex 414.407 156.897 65.1023 + endloop + endfacet + facet normal -0.914981 -0.21393 0.342116 + outer loop + vertex 414.407 156.897 65.1023 + vertex 412.384 161.006 62.2607 + vertex 413.422 156.547 62.2491 + endloop + endfacet + facet normal -0.914757 -0.214835 0.342149 + outer loop + vertex 414.407 156.897 65.1023 + vertex 413.422 156.547 62.2491 + vertex 415.49 152.275 65.0953 + endloop + endfacet + facet normal -0.914723 -0.214706 0.342319 + outer loop + vertex 415.49 152.275 65.0953 + vertex 413.422 156.547 62.2491 + vertex 414.487 152.028 62.2609 + endloop + endfacet + facet normal -0.915289 -0.214327 0.341042 + outer loop + vertex 411.369 169.792 65.0548 + vertex 410.363 169.635 62.2567 + vertex 412.362 165.592 65.0806 + endloop + endfacet + facet normal -0.915076 -0.213429 0.342177 + outer loop + vertex 412.362 165.592 65.0806 + vertex 410.363 169.635 62.2567 + vertex 411.363 165.358 62.2625 + endloop + endfacet + facet normal -0.914921 -0.214088 0.342177 + outer loop + vertex 412.362 165.592 65.0806 + vertex 411.363 165.358 62.2625 + vertex 413.353 161.363 65.0842 + endloop + endfacet + facet normal -0.915101 -0.21486 0.341211 + outer loop + vertex 413.353 161.363 65.0842 + vertex 411.363 165.358 62.2625 + vertex 412.384 161.006 62.2607 + endloop + endfacet + facet normal -0.916283 -0.218658 0.335581 + outer loop + vertex 409.245 178.802 65.1004 + vertex 408.311 178.37 62.2683 + vertex 410.341 174.164 65.0716 + endloop + endfacet + facet normal -0.915589 -0.215871 0.33926 + outer loop + vertex 410.341 174.164 65.0716 + vertex 408.311 178.37 62.2683 + vertex 409.345 173.942 62.2403 + endloop + endfacet + facet normal -0.915454 -0.216446 0.339258 + outer loop + vertex 410.341 174.164 65.0716 + vertex 409.345 173.942 62.2403 + vertex 411.369 169.792 65.0548 + endloop + endfacet + facet normal -0.915118 -0.215085 0.341024 + outer loop + vertex 411.369 169.792 65.0548 + vertex 409.345 173.942 62.2403 + vertex 410.363 169.635 62.2567 + endloop + endfacet + facet normal -0.919031 -0.203347 0.337687 + outer loop + vertex 407.16 187.924 65.0928 + vertex 406.218 187.493 62.271 + vertex 408.149 183.475 65.1056 + endloop + endfacet + facet normal -0.919627 -0.205867 0.334521 + outer loop + vertex 408.149 183.475 65.1056 + vertex 406.218 187.493 62.271 + vertex 407.256 182.922 62.3089 + endloop + endfacet + facet normal -0.917036 -0.21546 0.335593 + outer loop + vertex 408.149 183.475 65.1056 + vertex 407.256 182.922 62.3089 + vertex 409.245 178.802 65.1004 + endloop + endfacet + facet normal -0.917075 -0.215624 0.335379 + outer loop + vertex 409.245 178.802 65.1004 + vertex 407.256 182.922 62.3089 + vertex 408.311 178.37 62.2683 + endloop + endfacet + facet normal -0.94213 -0.122092 0.312225 + outer loop + vertex 405.807 197.021 65.3929 + vertex 404.838 196.808 62.384 + vertex 406.462 192.186 65.477 + endloop + endfacet + facet normal -0.938063 -0.109671 0.328649 + outer loop + vertex 406.462 192.186 65.477 + vertex 404.838 196.808 62.384 + vertex 405.322 192.046 62.1775 + endloop + endfacet + facet normal -0.927121 -0.181433 0.327917 + outer loop + vertex 406.462 192.186 65.477 + vertex 405.322 192.046 62.1775 + vertex 407.16 187.924 65.0928 + endloop + endfacet + facet normal -0.925553 -0.175312 0.335584 + outer loop + vertex 407.16 187.924 65.0928 + vertex 405.322 192.046 62.1775 + vertex 406.218 187.493 62.271 + endloop + endfacet + facet normal 0.0575073 -0.735941 0.674599 + outer loop + vertex 475.545 62.0804 34.4532 + vertex 467.612 60.0054 32.8657 + vertex 474.677 61.3994 33.7842 + endloop + endfacet + facet normal 0.0299478 -0.651348 0.758188 + outer loop + vertex 474.677 61.3994 33.7842 + vertex 467.612 60.0054 32.8657 + vertex 466.487 59.2724 32.2804 + endloop + endfacet + facet normal 0.0663775 -0.797019 0.600296 + outer loop + vertex 483.621 64.2591 36.4528 + vertex 475.545 62.0804 34.4532 + vertex 482.501 63.4894 35.5546 + endloop + endfacet + facet normal 0.0376928 -0.724302 0.688452 + outer loop + vertex 482.501 63.4894 35.5546 + vertex 475.545 62.0804 34.4532 + vertex 474.677 61.3994 33.7842 + endloop + endfacet + facet normal 0.0393244 -0.767482 0.639863 + outer loop + vertex 473.069 63.5122 36.2833 + vertex 465.935 61.5442 34.3613 + vertex 474.901 62.7604 35.2689 + endloop + endfacet + facet normal 0.0216278 -0.695486 0.718214 + outer loop + vertex 474.901 62.7604 35.2689 + vertex 465.935 61.5442 34.3613 + vertex 467.281 60.7218 33.5244 + endloop + endfacet + facet normal 0.0515039 -0.827867 0.558556 + outer loop + vertex 479.917 65.5624 38.6907 + vertex 473.069 63.5122 36.2833 + vertex 482.415 64.8749 37.4414 + endloop + endfacet + facet normal 0.03407 -0.772505 0.634094 + outer loop + vertex 482.415 64.8749 37.4414 + vertex 473.069 63.5122 36.2833 + vertex 474.901 62.7604 35.2689 + endloop + endfacet + facet normal 0.0608259 -0.8122 0.5802 + outer loop + vertex 482.415 64.8749 37.4414 + vertex 474.901 62.7604 35.2689 + vertex 483.621 64.2591 36.4528 + endloop + endfacet + facet normal 0.0398714 -0.751842 0.658137 + outer loop + vertex 483.621 64.2591 36.4528 + vertex 474.901 62.7604 35.2689 + vertex 475.545 62.0804 34.4532 + endloop + endfacet + facet normal 0.0485914 -0.748055 0.661855 + outer loop + vertex 474.901 62.7604 35.2689 + vertex 467.281 60.7218 33.5244 + vertex 475.545 62.0804 34.4532 + endloop + endfacet + facet normal 0.0267222 -0.669838 0.742027 + outer loop + vertex 475.545 62.0804 34.4532 + vertex 467.281 60.7218 33.5244 + vertex 467.612 60.0054 32.8657 + endloop + endfacet + facet normal 0.00688511 -0.78709 0.6168 + outer loop + vertex 467.975 65.3755 38.773 + vertex 461.717 63.6112 36.5914 + vertex 470.657 64.3899 37.4853 + endloop + endfacet + facet normal -0.00361137 -0.73585 0.677134 + outer loop + vertex 470.657 64.3899 37.4853 + vertex 461.717 63.6112 36.5914 + vertex 463.941 62.5083 35.4048 + endloop + endfacet + facet normal -0.00202021 -0.796106 0.605154 + outer loop + vertex 476.862 66.3276 40.0551 + vertex 467.975 65.3755 38.773 + vertex 470.657 64.3899 37.4853 + endloop + endfacet + facet normal 0.0197278 -0.788174 0.615136 + outer loop + vertex 479.917 65.5624 38.6907 + vertex 470.657 64.3899 37.4853 + vertex 473.069 63.5122 36.2833 + endloop + endfacet + facet normal 0.0260055 -0.781753 0.623046 + outer loop + vertex 470.657 64.3899 37.4853 + vertex 463.941 62.5083 35.4048 + vertex 473.069 63.5122 36.2833 + endloop + endfacet + facet normal 0.0128366 -0.722079 0.691691 + outer loop + vertex 473.069 63.5122 36.2833 + vertex 463.941 62.5083 35.4048 + vertex 465.935 61.5442 34.3613 + endloop + endfacet + facet normal -0.0412273 -0.797354 0.602102 + outer loop + vertex 462.479 67.7421 41.6169 + vertex 457.009 66.2474 39.263 + vertex 465.23 66.4832 40.1381 + endloop + endfacet + facet normal -0.0494414 -0.745049 0.665174 + outer loop + vertex 465.23 66.4832 40.1381 + vertex 457.009 66.2474 39.263 + vertex 459.416 64.859 37.8867 + endloop + endfacet + facet normal -0.0413424 -0.847339 0.52944 + outer loop + vertex 467.03 69.0924 44.1334 + vertex 462.479 67.7421 41.6169 + vertex 470.082 67.9599 42.5593 + endloop + endfacet + facet normal -0.0502616 -0.804701 0.591549 + outer loop + vertex 470.082 67.9599 42.5593 + vertex 462.479 67.7421 41.6169 + vertex 465.23 66.4832 40.1381 + endloop + endfacet + facet normal -0.0147116 -0.840255 0.541992 + outer loop + vertex 470.082 67.9599 42.5593 + vertex 465.23 66.4832 40.1381 + vertex 473.04 67.0119 41.1699 + endloop + endfacet + facet normal -0.0249637 -0.800277 0.599111 + outer loop + vertex 473.04 67.0119 41.1699 + vertex 465.23 66.4832 40.1381 + vertex 467.975 65.3755 38.773 + endloop + endfacet + facet normal -0.0154971 -0.791475 0.611005 + outer loop + vertex 465.23 66.4832 40.1381 + vertex 459.416 64.859 37.8867 + vertex 467.975 65.3755 38.773 + endloop + endfacet + facet normal -0.0246671 -0.741534 0.670461 + outer loop + vertex 467.975 65.3755 38.773 + vertex 459.416 64.859 37.8867 + vertex 461.717 63.6112 36.5914 + endloop + endfacet + facet normal -0.105856 -0.806352 0.581885 + outer loop + vertex 456.359 70.715 44.7721 + vertex 451.652 69.4454 42.1563 + vertex 459.506 69.1499 43.1758 + endloop + endfacet + facet normal -0.112467 -0.753064 0.648264 + outer loop + vertex 459.506 69.1499 43.1758 + vertex 451.652 69.4454 42.1563 + vertex 454.424 67.7714 40.6927 + endloop + endfacet + facet normal -0.110126 -0.856065 0.505001 + outer loop + vertex 460.162 71.8598 47.5421 + vertex 456.359 70.715 44.7721 + vertex 463.65 70.3967 45.8225 + endloop + endfacet + facet normal -0.117349 -0.814894 0.567606 + outer loop + vertex 463.65 70.3967 45.8225 + vertex 456.359 70.715 44.7721 + vertex 459.506 69.1499 43.1758 + endloop + endfacet + facet normal -0.0721091 -0.854026 0.515208 + outer loop + vertex 463.65 70.3967 45.8225 + vertex 459.506 69.1499 43.1758 + vertex 467.03 69.0924 44.1334 + endloop + endfacet + facet normal -0.0799962 -0.810846 0.579767 + outer loop + vertex 467.03 69.0924 44.1334 + vertex 459.506 69.1499 43.1758 + vertex 462.479 67.7421 41.6169 + endloop + endfacet + facet normal -0.0707322 -0.803628 0.590914 + outer loop + vertex 459.506 69.1499 43.1758 + vertex 454.424 67.7714 40.6927 + vertex 462.479 67.7421 41.6169 + endloop + endfacet + facet normal -0.0781752 -0.749387 0.657501 + outer loop + vertex 462.479 67.7421 41.6169 + vertex 454.424 67.7714 40.6927 + vertex 457.009 66.2474 39.263 + endloop + endfacet + facet normal -0.196148 -0.795514 0.573309 + outer loop + vertex 449.93 74.3912 47.9608 + vertex 445.891 73.3241 45.0982 + vertex 453.149 72.4535 46.3734 + endloop + endfacet + facet normal -0.20116 -0.744365 0.636753 + outer loop + vertex 453.149 72.4535 46.3734 + vertex 445.891 73.3241 45.0982 + vertex 448.782 71.286 43.629 + endloop + endfacet + facet normal -0.205984 -0.842952 0.496993 + outer loop + vertex 453.244 75.3071 50.8879 + vertex 449.93 74.3912 47.9608 + vertex 456.683 73.4862 49.2243 + endloop + endfacet + facet normal -0.211579 -0.80525 0.553901 + outer loop + vertex 456.683 73.4862 49.2243 + vertex 449.93 74.3912 47.9608 + vertex 453.149 72.4535 46.3734 + endloop + endfacet + facet normal -0.155581 -0.851251 0.501164 + outer loop + vertex 456.683 73.4862 49.2243 + vertex 453.149 72.4535 46.3734 + vertex 460.162 71.8598 47.5421 + endloop + endfacet + facet normal -0.16195 -0.8135 0.55856 + outer loop + vertex 460.162 71.8598 47.5421 + vertex 453.149 72.4535 46.3734 + vertex 456.359 70.715 44.7721 + endloop + endfacet + facet normal -0.147552 -0.803567 0.576636 + outer loop + vertex 453.149 72.4535 46.3734 + vertex 448.782 71.286 43.629 + vertex 456.359 70.715 44.7721 + endloop + endfacet + facet normal -0.153385 -0.752012 0.641054 + outer loop + vertex 456.359 70.715 44.7721 + vertex 448.782 71.286 43.629 + vertex 451.652 69.4454 42.1563 + endloop + endfacet + facet normal -0.315759 -0.760319 0.567636 + outer loop + vertex 443.568 78.9858 51.0114 + vertex 440.193 78.1002 47.9481 + vertex 446.724 76.5596 49.5172 + endloop + endfacet + facet normal -0.318444 -0.709131 0.629068 + outer loop + vertex 446.724 76.5596 49.5172 + vertex 440.193 78.1002 47.9481 + vertex 443.018 75.5866 46.5446 + endloop + endfacet + facet normal -0.328422 -0.808362 0.488559 + outer loop + vertex 446.313 79.7093 54.0541 + vertex 443.568 78.9858 51.0114 + vertex 449.75 77.3759 52.5033 + endloop + endfacet + facet normal -0.332109 -0.768673 0.546667 + outer loop + vertex 449.75 77.3759 52.5033 + vertex 443.568 78.9858 51.0114 + vertex 446.724 76.5596 49.5172 + endloop + endfacet + facet normal -0.262935 -0.829269 0.493132 + outer loop + vertex 449.75 77.3759 52.5033 + vertex 446.724 76.5596 49.5172 + vertex 453.244 75.3071 50.8879 + endloop + endfacet + facet normal -0.267597 -0.790824 0.550444 + outer loop + vertex 453.244 75.3071 50.8879 + vertex 446.724 76.5596 49.5172 + vertex 449.93 74.3912 47.9608 + endloop + endfacet + facet normal -0.252038 -0.781942 0.570126 + outer loop + vertex 446.724 76.5596 49.5172 + vertex 443.018 75.5866 46.5446 + vertex 449.93 74.3912 47.9608 + endloop + endfacet + facet normal -0.256064 -0.730155 0.633487 + outer loop + vertex 449.93 74.3912 47.9608 + vertex 443.018 75.5866 46.5446 + vertex 445.891 73.3241 45.0982 + endloop + endfacet + facet normal -0.460429 -0.687229 0.561891 + outer loop + vertex 437.668 84.6525 53.7099 + vertex 434.835 83.9296 50.5039 + vertex 440.537 81.6782 52.4231 + endloop + endfacet + facet normal -0.459915 -0.64184 0.613612 + outer loop + vertex 440.537 81.6782 52.4231 + vertex 434.835 83.9296 50.5039 + vertex 437.451 80.8848 49.28 + endloop + endfacet + facet normal -0.480849 -0.73271 0.481581 + outer loop + vertex 439.952 85.2256 56.8629 + vertex 437.668 84.6525 53.7099 + vertex 443.03 82.3229 55.5193 + endloop + endfacet + facet normal -0.481994 -0.695487 0.532898 + outer loop + vertex 443.03 82.3229 55.5193 + vertex 437.668 84.6525 53.7099 + vertex 440.537 81.6782 52.4231 + endloop + endfacet + facet normal -0.401738 -0.776663 0.485181 + outer loop + vertex 443.03 82.3229 55.5193 + vertex 440.537 81.6782 52.4231 + vertex 446.313 79.7093 54.0541 + endloop + endfacet + facet normal -0.404143 -0.738151 0.540186 + outer loop + vertex 446.313 79.7093 54.0541 + vertex 440.537 81.6782 52.4231 + vertex 443.568 78.9858 51.0114 + endloop + endfacet + facet normal -0.386218 -0.730229 0.563561 + outer loop + vertex 440.537 81.6782 52.4231 + vertex 437.451 80.8848 49.28 + vertex 443.568 78.9858 51.0114 + endloop + endfacet + facet normal -0.387323 -0.679502 0.623103 + outer loop + vertex 443.568 78.9858 51.0114 + vertex 437.451 80.8848 49.28 + vertex 440.193 78.1002 47.9481 + endloop + endfacet + facet normal -0.602945 -0.577565 0.550342 + outer loop + vertex 432.543 91.3877 55.8313 + vertex 430.08 90.8 52.5167 + vertex 434.999 87.8942 54.8556 + endloop + endfacet + facet normal -0.599793 -0.539761 0.590682 + outer loop + vertex 434.999 87.8942 54.8556 + vertex 430.08 90.8 52.5167 + vertex 432.369 87.2421 51.5895 + endloop + endfacet + facet normal -0.631888 -0.618142 0.467567 + outer loop + vertex 434.534 91.8061 59.0751 + vertex 432.543 91.3877 55.8313 + vertex 437.117 88.3965 58.0581 + endloop + endfacet + facet normal -0.630812 -0.585621 0.509042 + outer loop + vertex 437.117 88.3965 58.0581 + vertex 432.543 91.3877 55.8313 + vertex 434.999 87.8942 54.8556 + endloop + endfacet + facet normal -0.558743 -0.67911 0.476042 + outer loop + vertex 437.117 88.3965 58.0581 + vertex 434.999 87.8942 54.8556 + vertex 439.952 85.2256 56.8629 + endloop + endfacet + facet normal -0.558713 -0.644511 0.521963 + outer loop + vertex 439.952 85.2256 56.8629 + vertex 434.999 87.8942 54.8556 + vertex 437.668 84.6525 53.7099 + endloop + endfacet + facet normal -0.533827 -0.636352 0.556853 + outer loop + vertex 434.999 87.8942 54.8556 + vertex 432.369 87.2421 51.5895 + vertex 437.668 84.6525 53.7099 + endloop + endfacet + facet normal -0.531811 -0.593708 0.603894 + outer loop + vertex 437.668 84.6525 53.7099 + vertex 432.369 87.2421 51.5895 + vertex 434.835 83.9296 50.5039 + endloop + endfacet + facet normal -0.713256 -0.456592 0.531779 + outer loop + vertex 428.285 99.0109 57.2691 + vertex 426.062 98.5544 53.8945 + vertex 430.305 95.1043 56.6235 + endloop + endfacet + facet normal -0.708821 -0.42865 0.560208 + outer loop + vertex 430.305 95.1043 56.6235 + vertex 426.062 98.5544 53.8945 + vertex 427.977 94.584 53.2805 + endloop + endfacet + facet normal -0.749037 -0.488421 0.447648 + outer loop + vertex 430.072 99.3115 60.5862 + vertex 428.285 99.0109 57.2691 + vertex 432.195 95.442 59.9178 + endloop + endfacet + facet normal -0.746611 -0.464636 0.476115 + outer loop + vertex 432.195 95.442 59.9178 + vertex 428.285 99.0109 57.2691 + vertex 430.305 95.1043 56.6235 + endloop + endfacet + facet normal -0.696453 -0.553712 0.456461 + outer loop + vertex 432.195 95.442 59.9178 + vertex 430.305 95.1043 56.6235 + vertex 434.534 91.8061 59.0751 + endloop + endfacet + facet normal -0.694442 -0.523422 0.49374 + outer loop + vertex 434.534 91.8061 59.0751 + vertex 430.305 95.1043 56.6235 + vertex 432.543 91.3877 55.8313 + endloop + endfacet + facet normal -0.663685 -0.515243 0.54226 + outer loop + vertex 430.305 95.1043 56.6235 + vertex 427.977 94.584 53.2805 + vertex 432.543 91.3877 55.8313 + endloop + endfacet + facet normal -0.659766 -0.482901 0.575774 + outer loop + vertex 432.543 91.3877 55.8313 + vertex 427.977 94.584 53.2805 + vertex 430.08 90.8 52.5167 + endloop + endfacet + facet normal -0.781776 -0.352412 0.514425 + outer loop + vertex 424.793 107.345 58.1517 + vertex 422.734 106.943 54.7479 + vertex 426.453 103.097 57.7661 + endloop + endfacet + facet normal -0.778141 -0.336308 0.530466 + outer loop + vertex 426.453 103.097 57.7661 + vertex 422.734 106.943 54.7479 + vertex 424.323 102.68 54.3758 + endloop + endfacet + facet normal -0.82154 -0.376343 0.428296 + outer loop + vertex 426.392 107.675 61.5096 + vertex 424.793 107.345 58.1517 + vertex 428.144 103.403 61.1162 + endloop + endfacet + facet normal -0.819021 -0.360779 0.446143 + outer loop + vertex 428.144 103.403 61.1162 + vertex 424.793 107.345 58.1517 + vertex 426.453 103.097 57.7661 + endloop + endfacet + facet normal -0.790111 -0.429032 0.437785 + outer loop + vertex 428.144 103.403 61.1162 + vertex 426.453 103.097 57.7661 + vertex 430.072 99.3115 60.5862 + endloop + endfacet + facet normal -0.787416 -0.409068 0.461129 + outer loop + vertex 430.072 99.3115 60.5862 + vertex 426.453 103.097 57.7661 + vertex 428.285 99.0109 57.2691 + endloop + endfacet + facet normal -0.7526 -0.400909 0.522366 + outer loop + vertex 426.453 103.097 57.7661 + vertex 424.323 102.68 54.3758 + vertex 428.285 99.0109 57.2691 + endloop + endfacet + facet normal -0.748351 -0.378945 0.5444 + outer loop + vertex 428.285 99.0109 57.2691 + vertex 424.323 102.68 54.3758 + vertex 426.062 98.5544 53.8945 + endloop + endfacet + facet normal -0.820168 -0.277078 0.500551 + outer loop + vertex 421.889 116.168 58.6221 + vertex 419.938 115.788 55.2143 + vertex 423.274 111.721 58.43 + endloop + endfacet + facet normal -0.817841 -0.26853 0.508947 + outer loop + vertex 423.274 111.721 58.43 + vertex 419.938 115.788 55.2143 + vertex 421.282 111.326 55.0198 + endloop + endfacet + facet normal -0.861413 -0.293617 0.414436 + outer loop + vertex 423.375 116.497 61.9434 + vertex 421.889 116.168 58.6221 + vertex 424.808 112.06 61.779 + endloop + endfacet + facet normal -0.859875 -0.286088 0.422811 + outer loop + vertex 424.808 112.06 61.779 + vertex 421.889 116.168 58.6221 + vertex 423.274 111.721 58.43 + endloop + endfacet + facet normal -0.844801 -0.330955 0.420452 + outer loop + vertex 424.808 112.06 61.779 + vertex 423.274 111.721 58.43 + vertex 426.392 107.675 61.5096 + endloop + endfacet + facet normal -0.842771 -0.319944 0.432865 + outer loop + vertex 426.392 107.675 61.5096 + vertex 423.274 111.721 58.43 + vertex 424.793 107.345 58.1517 + endloop + endfacet + facet normal -0.804385 -0.311278 0.506035 + outer loop + vertex 423.274 111.721 58.43 + vertex 421.282 111.326 55.0198 + vertex 424.793 107.345 58.1517 + endloop + endfacet + facet normal -0.800935 -0.297601 0.519555 + outer loop + vertex 424.793 107.345 58.1517 + vertex 421.282 111.326 55.0198 + vertex 422.734 106.943 54.7479 + endloop + endfacet + facet normal -0.839353 -0.232162 0.491515 + outer loop + vertex 419.452 125.037 58.8493 + vertex 417.541 124.708 55.43 + vertex 420.618 120.62 58.7529 + endloop + endfacet + facet normal -0.837738 -0.226632 0.496823 + outer loop + vertex 420.618 120.62 58.7529 + vertex 417.541 124.708 55.43 + vertex 418.693 120.265 55.3455 + endloop + endfacet + facet normal -0.879683 -0.24475 0.407744 + outer loop + vertex 420.913 125.299 62.1578 + vertex 419.452 125.037 58.8493 + vertex 422.09 120.923 62.0712 + endloop + endfacet + facet normal -0.878778 -0.240829 0.412009 + outer loop + vertex 422.09 120.923 62.0712 + vertex 419.452 125.037 58.8493 + vertex 420.618 120.62 58.7529 + endloop + endfacet + facet normal -0.87215 -0.264978 0.411268 + outer loop + vertex 422.09 120.923 62.0712 + vertex 420.618 120.62 58.7529 + vertex 423.375 116.497 61.9434 + endloop + endfacet + facet normal -0.871278 -0.261028 0.415619 + outer loop + vertex 423.375 116.497 61.9434 + vertex 420.618 120.62 58.7529 + vertex 421.889 116.168 58.6221 + endloop + endfacet + facet normal -0.831135 -0.251919 0.495734 + outer loop + vertex 420.618 120.62 58.7529 + vertex 418.693 120.265 55.3455 + vertex 421.889 116.168 58.6221 + endloop + endfacet + facet normal -0.829242 -0.245275 0.502194 + outer loop + vertex 421.889 116.168 58.6221 + vertex 418.693 120.265 55.3455 + vertex 419.938 115.788 55.2143 + endloop + endfacet + facet normal -0.847388 -0.209185 0.488032 + outer loop + vertex 417.287 133.785 58.9333 + vertex 415.387 133.487 55.5054 + vertex 418.351 129.413 58.9065 + endloop + endfacet + facet normal -0.846845 -0.207352 0.489754 + outer loop + vertex 418.351 129.413 58.9065 + vertex 415.387 133.487 55.5054 + vertex 416.446 129.102 55.4805 + endloop + endfacet + facet normal -0.886962 -0.218944 0.406648 + outer loop + vertex 418.765 133.953 62.247 + vertex 417.287 133.785 58.9333 + vertex 419.82 129.619 62.2141 + endloop + endfacet + facet normal -0.886797 -0.21828 0.407364 + outer loop + vertex 419.82 129.619 62.2141 + vertex 417.287 133.785 58.9333 + vertex 418.351 129.413 58.9065 + endloop + endfacet + facet normal -0.88428 -0.229056 0.406917 + outer loop + vertex 419.82 129.619 62.2141 + vertex 418.351 129.413 58.9065 + vertex 420.913 125.299 62.1578 + endloop + endfacet + facet normal -0.883975 -0.227777 0.408296 + outer loop + vertex 420.913 125.299 62.1578 + vertex 418.351 129.413 58.9065 + vertex 419.452 125.037 58.8493 + endloop + endfacet + facet normal -0.844201 -0.218828 0.489325 + outer loop + vertex 418.351 129.413 58.9065 + vertex 416.446 129.102 55.4805 + vertex 419.452 125.037 58.8493 + endloop + endfacet + facet normal -0.843323 -0.215826 0.492163 + outer loop + vertex 419.452 125.037 58.8493 + vertex 416.446 129.102 55.4805 + vertex 417.541 124.708 55.43 + endloop + endfacet + facet normal -0.850899 -0.200638 0.485505 + outer loop + vertex 415.17 142.732 58.9438 + vertex 413.283 142.417 55.506 + vertex 416.233 138.216 58.9396 + endloop + endfacet + facet normal -0.850682 -0.19994 0.486174 + outer loop + vertex 416.233 138.216 58.9396 + vertex 413.283 142.417 55.506 + vertex 414.342 137.916 55.5075 + endloop + endfacet + facet normal -0.8904 -0.211967 0.402812 + outer loop + vertex 416.618 142.947 62.2581 + vertex 415.17 142.732 58.9438 + vertex 417.697 138.407 62.2525 + endloop + endfacet + facet normal -0.889805 -0.209718 0.405298 + outer loop + vertex 417.697 138.407 62.2525 + vertex 415.17 142.732 58.9438 + vertex 416.233 138.216 58.9396 + endloop + endfacet + facet normal -0.888922 -0.213728 0.405139 + outer loop + vertex 417.697 138.407 62.2525 + vertex 416.233 138.216 58.9396 + vertex 418.765 133.953 62.247 + endloop + endfacet + facet normal -0.888486 -0.212041 0.406978 + outer loop + vertex 418.765 133.953 62.247 + vertex 416.233 138.216 58.9396 + vertex 417.287 133.785 58.9333 + endloop + endfacet + facet normal -0.850014 -0.202998 0.486073 + outer loop + vertex 416.233 138.216 58.9396 + vertex 414.342 137.916 55.5075 + vertex 417.287 133.785 58.9333 + endloop + endfacet + facet normal -0.849286 -0.200602 0.488337 + outer loop + vertex 417.287 133.785 58.9333 + vertex 414.342 137.916 55.5075 + vertex 415.387 133.487 55.5054 + endloop + endfacet + facet normal -0.853516 -0.200608 0.480903 + outer loop + vertex 413.024 151.849 58.9415 + vertex 411.161 151.532 55.502 + vertex 414.097 147.297 58.9465 + endloop + endfacet + facet normal -0.852772 -0.198219 0.483207 + outer loop + vertex 414.097 147.297 58.9465 + vertex 411.161 151.532 55.502 + vertex 412.221 146.975 55.5035 + endloop + endfacet + facet normal -0.890678 -0.208874 0.403813 + outer loop + vertex 414.487 152.028 62.2609 + vertex 413.024 151.849 58.9415 + vertex 415.551 147.498 62.2636 + endloop + endfacet + facet normal -0.890842 -0.209491 0.403131 + outer loop + vertex 415.551 147.498 62.2636 + vertex 413.024 151.849 58.9415 + vertex 414.097 147.297 58.9465 + endloop + endfacet + facet normal -0.890841 -0.209493 0.403131 + outer loop + vertex 415.551 147.498 62.2636 + vertex 414.097 147.297 58.9465 + vertex 416.618 142.947 62.2581 + endloop + endfacet + facet normal -0.890901 -0.209715 0.402884 + outer loop + vertex 416.618 142.947 62.2581 + vertex 414.097 147.297 58.9465 + vertex 415.17 142.732 58.9438 + endloop + endfacet + facet normal -0.852234 -0.200673 0.483143 + outer loop + vertex 414.097 147.297 58.9465 + vertex 412.221 146.975 55.5035 + vertex 415.17 142.732 58.9438 + endloop + endfacet + facet normal -0.851442 -0.19815 0.485575 + outer loop + vertex 415.17 142.732 58.9438 + vertex 412.221 146.975 55.5035 + vertex 413.283 142.417 55.506 + endloop + endfacet + facet normal -0.854503 -0.199377 0.47966 + outer loop + vertex 410.938 160.775 58.9263 + vertex 409.088 160.44 55.4905 + vertex 411.974 156.349 58.931 + endloop + endfacet + facet normal -0.853551 -0.19618 0.482663 + outer loop + vertex 411.974 156.349 58.931 + vertex 409.088 160.44 55.4905 + vertex 410.108 156.024 55.4999 + endloop + endfacet + facet normal -0.891924 -0.208715 0.401136 + outer loop + vertex 412.384 161.006 62.2607 + vertex 410.938 160.775 58.9263 + vertex 413.422 156.547 62.2491 + endloop + endfacet + facet normal -0.891788 -0.208182 0.401713 + outer loop + vertex 413.422 156.547 62.2491 + vertex 410.938 160.775 58.9263 + vertex 411.974 156.349 58.931 + endloop + endfacet + facet normal -0.891589 -0.209098 0.401681 + outer loop + vertex 413.422 156.547 62.2491 + vertex 411.974 156.349 58.931 + vertex 414.487 152.028 62.2609 + endloop + endfacet + facet normal -0.891061 -0.207091 0.403886 + outer loop + vertex 414.487 152.028 62.2609 + vertex 411.974 156.349 58.931 + vertex 413.024 151.849 58.9415 + endloop + endfacet + facet normal -0.853143 -0.198055 0.482619 + outer loop + vertex 411.974 156.349 58.931 + vertex 410.108 156.024 55.4999 + vertex 413.024 151.849 58.9415 + endloop + endfacet + facet normal -0.853686 -0.199831 0.480923 + outer loop + vertex 413.024 151.849 58.9415 + vertex 410.108 156.024 55.4999 + vertex 411.161 151.532 55.502 + endloop + endfacet + facet normal -0.856674 -0.199394 0.475764 + outer loop + vertex 408.921 169.457 58.9362 + vertex 407.087 169.111 55.4894 + vertex 409.925 165.136 58.9331 + endloop + endfacet + facet normal -0.856055 -0.197198 0.477789 + outer loop + vertex 409.925 165.136 58.9331 + vertex 407.087 169.111 55.4894 + vertex 408.083 164.785 55.489 + endloop + endfacet + facet normal -0.892991 -0.20819 0.399028 + outer loop + vertex 410.363 169.635 62.2567 + vertex 408.921 169.457 58.9362 + vertex 411.363 165.358 62.2625 + endloop + endfacet + facet normal -0.892887 -0.207755 0.399487 + outer loop + vertex 411.363 165.358 62.2625 + vertex 408.921 169.457 58.9362 + vertex 409.925 165.136 58.9331 + endloop + endfacet + facet normal -0.892485 -0.209577 0.399435 + outer loop + vertex 411.363 165.358 62.2625 + vertex 409.925 165.136 58.9331 + vertex 412.384 161.006 62.2607 + endloop + endfacet + facet normal -0.892092 -0.207956 0.401157 + outer loop + vertex 412.384 161.006 62.2607 + vertex 409.925 165.136 58.9331 + vertex 410.938 160.775 58.9263 + endloop + endfacet + facet normal -0.855526 -0.199578 0.477748 + outer loop + vertex 409.925 165.136 58.9331 + vertex 408.083 164.785 55.489 + vertex 410.938 160.775 58.9263 + endloop + endfacet + facet normal -0.854922 -0.197475 0.4797 + outer loop + vertex 410.938 160.775 58.9263 + vertex 408.083 164.785 55.489 + vertex 409.088 160.44 55.4905 + endloop + endfacet + facet normal -0.859271 -0.200615 0.470539 + outer loop + vertex 406.885 178.18 58.9376 + vertex 405.062 177.877 55.4809 + vertex 407.904 173.788 58.9265 + endloop + endfacet + facet normal -0.857992 -0.196209 0.474713 + outer loop + vertex 407.904 173.788 58.9265 + vertex 405.062 177.877 55.4809 + vertex 406.074 173.462 55.4846 + endloop + endfacet + facet normal -0.894092 -0.211205 0.394957 + outer loop + vertex 408.311 178.37 62.2683 + vertex 406.885 178.18 58.9376 + vertex 409.345 173.942 62.2403 + endloop + endfacet + facet normal -0.893373 -0.208345 0.398091 + outer loop + vertex 409.345 173.942 62.2403 + vertex 406.885 178.18 58.9376 + vertex 407.904 173.788 58.9265 + endloop + endfacet + facet normal -0.893093 -0.20966 0.39803 + outer loop + vertex 409.345 173.942 62.2403 + vertex 407.904 173.788 58.9265 + vertex 410.363 169.635 62.2567 + endloop + endfacet + facet normal -0.892871 -0.208747 0.399006 + outer loop + vertex 410.363 169.635 62.2567 + vertex 407.904 173.788 58.9265 + vertex 408.921 169.457 58.9362 + endloop + endfacet + facet normal -0.857121 -0.200183 0.474627 + outer loop + vertex 407.904 173.788 58.9265 + vertex 406.074 173.462 55.4846 + vertex 408.921 169.457 58.9362 + endloop + endfacet + facet normal -0.856773 -0.198949 0.475771 + outer loop + vertex 408.921 169.457 58.9362 + vertex 406.074 173.462 55.4846 + vertex 407.087 169.111 55.4894 + endloop + endfacet + facet normal -0.862435 -0.195823 0.466754 + outer loop + vertex 404.863 187.171 59.0221 + vertex 403.079 186.841 55.5873 + vertex 405.872 182.651 58.9909 + endloop + endfacet + facet normal -0.862071 -0.19463 0.467925 + outer loop + vertex 405.872 182.651 58.9909 + vertex 403.079 186.841 55.5873 + vertex 404.055 182.345 55.5154 + endloop + endfacet + facet normal -0.896997 -0.200239 0.394083 + outer loop + vertex 406.218 187.493 62.271 + vertex 404.863 187.171 59.0221 + vertex 407.256 182.922 62.3089 + endloop + endfacet + facet normal -0.897758 -0.203187 0.390827 + outer loop + vertex 407.256 182.922 62.3089 + vertex 404.863 187.171 59.0221 + vertex 405.872 182.651 58.9909 + endloop + endfacet + facet normal -0.895946 -0.211218 0.390726 + outer loop + vertex 407.256 182.922 62.3089 + vertex 405.872 182.651 58.9909 + vertex 408.311 178.37 62.2683 + endloop + endfacet + facet normal -0.894944 -0.2073 0.395098 + outer loop + vertex 408.311 178.37 62.2683 + vertex 405.872 182.651 58.9909 + vertex 406.885 178.18 58.9376 + endloop + endfacet + facet normal -0.860817 -0.20044 0.46778 + outer loop + vertex 405.872 182.651 58.9909 + vertex 404.055 182.345 55.5154 + vertex 406.885 178.18 58.9376 + endloop + endfacet + facet normal -0.859944 -0.197512 0.470622 + outer loop + vertex 406.885 178.18 58.9376 + vertex 404.055 182.345 55.5154 + vertex 405.062 177.877 55.4809 + endloop + endfacet + facet normal -0.87389 -0.094281 0.476894 + outer loop + vertex 403.366 196.472 58.8104 + vertex 401.619 196.066 55.5292 + vertex 403.943 191.737 58.931 + endloop + endfacet + facet normal -0.874476 -0.0956559 0.475544 + outer loop + vertex 403.943 191.737 58.931 + vertex 401.619 196.066 55.5292 + vertex 402.175 191.368 55.6069 + endloop + endfacet + facet normal -0.91535 -0.109907 0.387369 + outer loop + vertex 404.838 196.808 62.384 + vertex 403.366 196.472 58.8104 + vertex 405.322 192.046 62.1775 + endloop + endfacet + facet normal -0.912138 -0.100968 0.397253 + outer loop + vertex 405.322 192.046 62.1775 + vertex 403.366 196.472 58.8104 + vertex 403.943 191.737 58.931 + endloop + endfacet + facet normal -0.901166 -0.169207 0.399085 + outer loop + vertex 405.322 192.046 62.1775 + vertex 403.943 191.737 58.931 + vertex 406.218 187.493 62.271 + endloop + endfacet + facet normal -0.902553 -0.174102 0.39381 + outer loop + vertex 406.218 187.493 62.271 + vertex 403.943 191.737 58.931 + vertex 404.863 187.171 59.0221 + endloop + endfacet + facet normal -0.863249 -0.164514 0.477218 + outer loop + vertex 403.943 191.737 58.931 + vertex 402.175 191.368 55.6069 + vertex 404.863 187.171 59.0221 + endloop + endfacet + facet normal -0.866752 -0.175072 0.467001 + outer loop + vertex 404.863 187.171 59.0221 + vertex 402.175 191.368 55.6069 + vertex 403.079 186.841 55.5873 + endloop + endfacet + facet normal 0.0584115 -0.621583 0.781168 + outer loop + vertex 459.491 57.9496 31.6088 + vertex 451.501 55.8933 30.5701 + vertex 459.458 57.5535 31.2961 + endloop + endfacet + facet normal 0.072151 -0.669229 0.739545 + outer loop + vertex 459.458 57.5535 31.2961 + vertex 451.501 55.8933 30.5701 + vertex 456.567 56.7816 30.8797 + endloop + endfacet + facet normal 0.0569793 -0.674886 0.735719 + outer loop + vertex 467.612 60.0054 32.8657 + vertex 459.491 57.9496 31.6088 + vertex 466.487 59.2724 32.2804 + endloop + endfacet + facet normal 0.0423516 -0.621254 0.782464 + outer loop + vertex 466.487 59.2724 32.2804 + vertex 459.491 57.9496 31.6088 + vertex 459.458 57.5535 31.2961 + endloop + endfacet + facet normal 0.0280072 -0.594938 0.803283 + outer loop + vertex 458.51 59.6541 32.8984 + vertex 450.394 57.6523 31.6987 + vertex 459.251 58.6822 32.1527 + endloop + endfacet + facet normal 0.0150979 -0.509165 0.860536 + outer loop + vertex 459.251 58.6822 32.1527 + vertex 450.394 57.6523 31.6987 + vertex 450.019 56.4 30.9643 + endloop + endfacet + facet normal 0.0317933 -0.686867 0.726088 + outer loop + vertex 465.935 61.5442 34.3613 + vertex 458.51 59.6541 32.8984 + vertex 467.281 60.7218 33.5244 + endloop + endfacet + facet normal 0.0161072 -0.60087 0.799184 + outer loop + vertex 467.281 60.7218 33.5244 + vertex 458.51 59.6541 32.8984 + vertex 459.251 58.6822 32.1527 + endloop + endfacet + facet normal 0.0418088 -0.665664 0.74508 + outer loop + vertex 467.281 60.7218 33.5244 + vertex 459.251 58.6822 32.1527 + vertex 467.612 60.0054 32.8657 + endloop + endfacet + facet normal 0.0247005 -0.590675 0.806532 + outer loop + vertex 467.612 60.0054 32.8657 + vertex 459.251 58.6822 32.1527 + vertex 459.491 57.9496 31.6088 + endloop + endfacet + facet normal 0.0409947 -0.586893 0.808626 + outer loop + vertex 459.251 58.6822 32.1527 + vertex 450.019 56.4 30.9643 + vertex 459.491 57.9496 31.6088 + endloop + endfacet + facet normal 0.03342 -0.55106 0.833796 + outer loop + vertex 459.491 57.9496 31.6088 + vertex 450.019 56.4 30.9643 + vertex 451.501 55.8933 30.5701 + endloop + endfacet + facet normal 0.00568293 -0.655792 0.75492 + outer loop + vertex 455.124 61.9361 34.8629 + vertex 448.353 60.3293 33.5181 + vertex 457.024 60.7422 33.8115 + endloop + endfacet + facet normal -0.000185797 -0.576665 0.81698 + outer loop + vertex 457.024 60.7422 33.8115 + vertex 448.353 60.3293 33.5181 + vertex 449.751 58.98 32.566 + endloop + endfacet + facet normal 0.00508339 -0.727712 0.685864 + outer loop + vertex 461.717 63.6112 36.5914 + vertex 455.124 61.9361 34.8629 + vertex 463.941 62.5083 35.4048 + endloop + endfacet + facet normal -0.00291104 -0.663515 0.748157 + outer loop + vertex 463.941 62.5083 35.4048 + vertex 455.124 61.9361 34.8629 + vertex 457.024 60.7422 33.8115 + endloop + endfacet + facet normal 0.0210759 -0.713926 0.699903 + outer loop + vertex 463.941 62.5083 35.4048 + vertex 457.024 60.7422 33.8115 + vertex 465.935 61.5442 34.3613 + endloop + endfacet + facet normal 0.00951779 -0.63515 0.77233 + outer loop + vertex 465.935 61.5442 34.3613 + vertex 457.024 60.7422 33.8115 + vertex 458.51 59.6541 32.8984 + endloop + endfacet + facet normal 0.0187635 -0.627566 0.778337 + outer loop + vertex 457.024 60.7422 33.8115 + vertex 449.751 58.98 32.566 + vertex 458.51 59.6541 32.8984 + endloop + endfacet + facet normal 0.0099747 -0.543461 0.839375 + outer loop + vertex 458.51 59.6541 32.8984 + vertex 449.751 58.98 32.566 + vertex 450.394 57.6523 31.6987 + endloop + endfacet + facet normal -0.034179 -0.67094 0.740723 + outer loop + vertex 451.019 64.7185 37.2449 + vertex 444.76 63.2437 35.6203 + vertex 453.104 63.2535 36.0141 + endloop + endfacet + facet normal -0.0366718 -0.609407 0.792009 + outer loop + vertex 453.104 63.2535 36.0141 + vertex 444.76 63.2437 35.6203 + vertex 446.604 61.7321 34.5425 + endloop + endfacet + facet normal -0.0392505 -0.73694 0.674817 + outer loop + vertex 457.009 66.2474 39.263 + vertex 451.019 64.7185 37.2449 + vertex 459.416 64.859 37.8867 + endloop + endfacet + facet normal -0.0446426 -0.679089 0.732697 + outer loop + vertex 459.416 64.859 37.8867 + vertex 451.019 64.7185 37.2449 + vertex 453.104 63.2535 36.0141 + endloop + endfacet + facet normal -0.0150892 -0.733393 0.679638 + outer loop + vertex 459.416 64.859 37.8867 + vertex 453.104 63.2535 36.0141 + vertex 461.717 63.6112 36.5914 + endloop + endfacet + facet normal -0.0212726 -0.676163 0.736445 + outer loop + vertex 461.717 63.6112 36.5914 + vertex 453.104 63.2535 36.0141 + vertex 455.124 61.9361 34.8629 + endloop + endfacet + facet normal -0.0119668 -0.668308 0.743788 + outer loop + vertex 453.104 63.2535 36.0141 + vertex 446.604 61.7321 34.5425 + vertex 455.124 61.9361 34.8629 + endloop + endfacet + facet normal -0.0155904 -0.602304 0.798114 + outer loop + vertex 455.124 61.9361 34.8629 + vertex 446.604 61.7321 34.5425 + vertex 448.353 60.3293 33.5181 + endloop + endfacet + facet normal -0.0909049 -0.672101 0.734858 + outer loop + vertex 446.41 68.1129 39.8642 + vertex 440.825 66.7693 37.9444 + vertex 448.796 66.3419 38.5397 + endloop + endfacet + facet normal -0.0914919 -0.606222 0.790015 + outer loop + vertex 448.796 66.3419 38.5397 + vertex 440.825 66.7693 37.9444 + vertex 442.847 64.9218 36.761 + endloop + endfacet + facet normal -0.100024 -0.743642 0.661054 + outer loop + vertex 451.652 69.4454 42.1563 + vertex 446.41 68.1129 39.8642 + vertex 454.424 67.7714 40.6927 + endloop + endfacet + facet normal -0.103915 -0.681684 0.72423 + outer loop + vertex 454.424 67.7714 40.6927 + vertex 446.41 68.1129 39.8642 + vertex 448.796 66.3419 38.5397 + endloop + endfacet + facet normal -0.0673731 -0.741011 0.668104 + outer loop + vertex 454.424 67.7714 40.6927 + vertex 448.796 66.3419 38.5397 + vertex 457.009 66.2474 39.263 + endloop + endfacet + facet normal -0.072068 -0.68034 0.729345 + outer loop + vertex 457.009 66.2474 39.263 + vertex 448.796 66.3419 38.5397 + vertex 451.019 64.7185 37.2449 + endloop + endfacet + facet normal -0.0604405 -0.671646 0.738403 + outer loop + vertex 448.796 66.3419 38.5397 + vertex 442.847 64.9218 36.761 + vertex 451.019 64.7185 37.2449 + endloop + endfacet + facet normal -0.061992 -0.608464 0.791157 + outer loop + vertex 451.019 64.7185 37.2449 + vertex 442.847 64.9218 36.761 + vertex 444.76 63.2437 35.6203 + endloop + endfacet + facet normal -0.165748 -0.661004 0.731848 + outer loop + vertex 441.368 72.1667 42.5442 + vertex 436.489 70.9942 40.3802 + vertex 443.908 70.0482 41.2062 + endloop + endfacet + facet normal -0.163596 -0.598154 0.784505 + outer loop + vertex 443.908 70.0482 41.2062 + vertex 436.489 70.9942 40.3802 + vertex 438.689 68.7946 39.1619 + endloop + endfacet + facet normal -0.182944 -0.732334 0.65591 + outer loop + vertex 445.891 73.3241 45.0982 + vertex 441.368 72.1667 42.5442 + vertex 448.782 71.286 43.629 + endloop + endfacet + facet normal -0.184707 -0.673541 0.7157 + outer loop + vertex 448.782 71.286 43.629 + vertex 441.368 72.1667 42.5442 + vertex 443.908 70.0482 41.2062 + endloop + endfacet + facet normal -0.138303 -0.741181 0.656904 + outer loop + vertex 448.782 71.286 43.629 + vertex 443.908 70.0482 41.2062 + vertex 451.652 69.4454 42.1563 + endloop + endfacet + facet normal -0.141188 -0.680849 0.718686 + outer loop + vertex 451.652 69.4454 42.1563 + vertex 443.908 70.0482 41.2062 + vertex 446.41 68.1129 39.8642 + endloop + endfacet + facet normal -0.125704 -0.669889 0.731742 + outer loop + vertex 443.908 70.0482 41.2062 + vertex 438.689 68.7946 39.1619 + vertex 446.41 68.1129 39.8642 + endloop + endfacet + facet normal -0.124936 -0.604632 0.786645 + outer loop + vertex 446.41 68.1129 39.8642 + vertex 438.689 68.7946 39.1619 + vertex 440.825 66.7693 37.9444 + endloop + endfacet + facet normal -0.261849 -0.620856 0.7389 + outer loop + vertex 436.334 77.1068 45.1675 + vertex 432.06 76.0613 42.7746 + vertex 438.834 74.5126 43.8737 + endloop + endfacet + facet normal -0.256253 -0.563301 0.78551 + outer loop + vertex 438.834 74.5126 43.8737 + vertex 432.06 76.0613 42.7746 + vertex 434.269 73.4066 41.5915 + endloop + endfacet + facet normal -0.293318 -0.695747 0.655668 + outer loop + vertex 440.193 78.1002 47.9481 + vertex 436.334 77.1068 45.1675 + vertex 443.018 75.5866 46.5446 + endloop + endfacet + facet normal -0.291869 -0.637072 0.713409 + outer loop + vertex 443.018 75.5866 46.5446 + vertex 436.334 77.1068 45.1675 + vertex 438.834 74.5126 43.8737 + endloop + endfacet + facet normal -0.234632 -0.717347 0.656019 + outer loop + vertex 443.018 75.5866 46.5446 + vertex 438.834 74.5126 43.8737 + vertex 445.891 73.3241 45.0982 + endloop + endfacet + facet normal -0.234952 -0.658792 0.714696 + outer loop + vertex 445.891 73.3241 45.0982 + vertex 438.834 74.5126 43.8737 + vertex 441.368 72.1667 42.5442 + endloop + endfacet + facet normal -0.211215 -0.644552 0.734807 + outer loop + vertex 438.834 74.5126 43.8737 + vertex 434.269 73.4066 41.5915 + vertex 441.368 72.1667 42.5442 + endloop + endfacet + facet normal -0.207395 -0.584614 0.784356 + outer loop + vertex 441.368 72.1667 42.5442 + vertex 434.269 73.4066 41.5915 + vertex 436.489 70.9942 40.3802 + endloop + endfacet + facet normal -0.374743 -0.554603 0.742956 + outer loop + vertex 431.53 83.1019 47.5525 + vertex 427.772 82.1852 44.9726 + vertex 433.889 79.9757 46.4083 + endloop + endfacet + facet normal -0.365254 -0.501478 0.784289 + outer loop + vertex 433.889 79.9757 46.4083 + vertex 427.772 82.1852 44.9726 + vertex 429.884 78.9907 43.9137 + endloop + endfacet + facet normal -0.4253 -0.627577 0.652125 + outer loop + vertex 434.835 83.9296 50.5039 + vertex 431.53 83.1019 47.5525 + vertex 437.451 80.8848 49.28 + endloop + endfacet + facet normal -0.420066 -0.574101 0.702818 + outer loop + vertex 437.451 80.8848 49.28 + vertex 431.53 83.1019 47.5525 + vertex 433.889 79.9757 46.4083 + endloop + endfacet + facet normal -0.357946 -0.665708 0.654758 + outer loop + vertex 437.451 80.8848 49.28 + vertex 433.889 79.9757 46.4083 + vertex 440.193 78.1002 47.9481 + endloop + endfacet + facet normal -0.354462 -0.609017 0.709545 + outer loop + vertex 440.193 78.1002 47.9481 + vertex 433.889 79.9757 46.4083 + vertex 436.334 77.1068 45.1675 + endloop + endfacet + facet normal -0.316837 -0.590936 0.741896 + outer loop + vertex 433.889 79.9757 46.4083 + vertex 429.884 78.9907 43.9137 + vertex 436.334 77.1068 45.1675 + endloop + endfacet + facet normal -0.30917 -0.535308 0.78604 + outer loop + vertex 436.334 77.1068 45.1675 + vertex 429.884 78.9907 43.9137 + vertex 432.06 76.0613 42.7746 + endloop + endfacet + facet normal -0.488547 -0.463113 0.739492 + outer loop + vertex 427.183 90.0989 49.4512 + vertex 423.835 89.309 46.7445 + vertex 429.285 86.4851 48.5767 + endloop + endfacet + facet normal -0.477288 -0.420575 0.771565 + outer loop + vertex 429.285 86.4851 48.5767 + vertex 423.835 89.309 46.7445 + vertex 425.748 85.6339 45.9248 + endloop + endfacet + facet normal -0.55521 -0.525211 0.644899 + outer loop + vertex 430.08 90.8 52.5167 + vertex 427.183 90.0989 49.4512 + vertex 432.369 87.2421 51.5895 + endloop + endfacet + facet normal -0.547892 -0.483827 0.682441 + outer loop + vertex 432.369 87.2421 51.5895 + vertex 427.183 90.0989 49.4512 + vertex 429.285 86.4851 48.5767 + endloop + endfacet + facet normal -0.492361 -0.579322 0.649589 + outer loop + vertex 432.369 87.2421 51.5895 + vertex 429.285 86.4851 48.5767 + vertex 434.835 83.9296 50.5039 + endloop + endfacet + facet normal -0.485873 -0.532326 0.693222 + outer loop + vertex 434.835 83.9296 50.5039 + vertex 429.285 86.4851 48.5767 + vertex 431.53 83.1019 47.5525 + endloop + endfacet + facet normal -0.433025 -0.511978 0.741868 + outer loop + vertex 429.285 86.4851 48.5767 + vertex 425.748 85.6339 45.9248 + vertex 431.53 83.1019 47.5525 + endloop + endfacet + facet normal -0.422125 -0.462951 0.779414 + outer loop + vertex 431.53 83.1019 47.5525 + vertex 425.748 85.6339 45.9248 + vertex 427.772 82.1852 44.9726 + endloop + endfacet + facet normal -0.580306 -0.365045 0.728002 + outer loop + vertex 423.439 97.9478 50.7608 + vertex 420.384 97.2361 47.9687 + vertex 425.233 93.9308 50.1769 + endloop + endfacet + facet normal -0.570087 -0.335335 0.750034 + outer loop + vertex 425.233 93.9308 50.1769 + vertex 420.384 97.2361 47.9687 + vertex 422.048 93.1841 47.4219 + endloop + endfacet + facet normal -0.65686 -0.414365 0.629949 + outer loop + vertex 426.062 98.5544 53.8945 + vertex 423.439 97.9478 50.7608 + vertex 427.977 94.584 53.2805 + endloop + endfacet + facet normal -0.649537 -0.385417 0.655404 + outer loop + vertex 427.977 94.584 53.2805 + vertex 423.439 97.9478 50.7608 + vertex 425.233 93.9308 50.1769 + endloop + endfacet + facet normal -0.610716 -0.468306 0.638527 + outer loop + vertex 427.977 94.584 53.2805 + vertex 425.233 93.9308 50.1769 + vertex 430.08 90.8 52.5167 + endloop + endfacet + facet normal -0.603231 -0.433679 0.669354 + outer loop + vertex 430.08 90.8 52.5167 + vertex 425.233 93.9308 50.1769 + vertex 427.183 90.0989 49.4512 + endloop + endfacet + facet normal -0.538431 -0.413047 0.734496 + outer loop + vertex 425.233 93.9308 50.1769 + vertex 422.048 93.1841 47.4219 + vertex 427.183 90.0989 49.4512 + endloop + endfacet + facet normal -0.527167 -0.376261 0.76192 + outer loop + vertex 427.183 90.0989 49.4512 + vertex 422.048 93.1841 47.4219 + vertex 423.835 89.309 46.7445 + endloop + endfacet + facet normal -0.639968 -0.283353 0.714249 + outer loop + vertex 420.278 106.412 51.5687 + vertex 417.397 105.756 48.7265 + vertex 421.791 102.117 51.2201 + endloop + endfacet + facet normal -0.632968 -0.266175 0.726982 + outer loop + vertex 421.791 102.117 51.2201 + vertex 417.397 105.756 48.7265 + vertex 418.837 101.435 48.3985 + endloop + endfacet + facet normal -0.722246 -0.322577 0.611804 + outer loop + vertex 422.734 106.943 54.7479 + vertex 420.278 106.412 51.5687 + vertex 424.323 102.68 54.3758 + endloop + endfacet + facet normal -0.716107 -0.303226 0.628685 + outer loop + vertex 424.323 102.68 54.3758 + vertex 420.278 106.412 51.5687 + vertex 421.791 102.117 51.2201 + endloop + endfacet + facet normal -0.693376 -0.364758 0.621435 + outer loop + vertex 424.323 102.68 54.3758 + vertex 421.791 102.117 51.2201 + vertex 426.062 98.5544 53.8945 + endloop + endfacet + facet normal -0.686907 -0.342216 0.64113 + outer loop + vertex 426.062 98.5544 53.8945 + vertex 421.791 102.117 51.2201 + vertex 423.439 97.9478 50.7608 + endloop + endfacet + facet normal -0.613963 -0.322135 0.72061 + outer loop + vertex 421.791 102.117 51.2201 + vertex 418.837 101.435 48.3985 + vertex 423.439 97.9478 50.7608 + endloop + endfacet + facet normal -0.605046 -0.298508 0.738114 + outer loop + vertex 423.439 97.9478 50.7608 + vertex 418.837 101.435 48.3985 + vertex 420.384 97.2361 47.9687 + endloop + endfacet + facet normal -0.675672 -0.225318 0.701925 + outer loop + vertex 417.572 115.291 52.0122 + vertex 414.791 114.667 49.1341 + vertex 418.875 110.815 51.8294 + endloop + endfacet + facet normal -0.671529 -0.21615 0.708751 + outer loop + vertex 418.875 110.815 51.8294 + vertex 414.791 114.667 49.1341 + vertex 416.056 110.179 48.9638 + endloop + endfacet + facet normal -0.758552 -0.25463 0.599802 + outer loop + vertex 419.938 115.788 55.2143 + vertex 417.572 115.291 52.0122 + vertex 421.282 111.326 55.0198 + endloop + endfacet + facet normal -0.754885 -0.24456 0.608556 + outer loop + vertex 421.282 111.326 55.0198 + vertex 417.572 115.291 52.0122 + vertex 418.875 110.815 51.8294 + endloop + endfacet + facet normal -0.743129 -0.283812 0.605979 + outer loop + vertex 421.282 111.326 55.0198 + vertex 418.875 110.815 51.8294 + vertex 422.734 106.943 54.7479 + endloop + endfacet + facet normal -0.739049 -0.27195 0.61632 + outer loop + vertex 422.734 106.943 54.7479 + vertex 418.875 110.815 51.8294 + vertex 420.278 106.412 51.5687 + endloop + endfacet + facet normal -0.661098 -0.252458 0.706551 + outer loop + vertex 418.875 110.815 51.8294 + vertex 416.056 110.179 48.9638 + vertex 420.278 106.412 51.5687 + endloop + endfacet + facet normal -0.654359 -0.236907 0.718115 + outer loop + vertex 420.278 106.412 51.5687 + vertex 416.056 110.179 48.9638 + vertex 417.397 105.756 48.7265 + endloop + endfacet + facet normal -0.695102 -0.189749 0.693418 + outer loop + vertex 415.216 124.233 52.209 + vertex 412.489 123.621 49.3074 + vertex 416.356 119.782 52.1337 + endloop + endfacet + facet normal -0.692519 -0.184139 0.697502 + outer loop + vertex 416.356 119.782 52.1337 + vertex 412.489 123.621 49.3074 + vertex 413.607 119.168 49.2418 + endloop + endfacet + facet normal -0.777145 -0.212737 0.592274 + outer loop + vertex 417.541 124.708 55.43 + vertex 415.216 124.233 52.209 + vertex 418.693 120.265 55.3455 + endloop + endfacet + facet normal -0.775632 -0.208722 0.595676 + outer loop + vertex 418.693 120.265 55.3455 + vertex 415.216 124.233 52.209 + vertex 416.356 119.782 52.1337 + endloop + endfacet + facet normal -0.769795 -0.231463 0.594845 + outer loop + vertex 418.693 120.265 55.3455 + vertex 416.356 119.782 52.1337 + vertex 419.938 115.788 55.2143 + endloop + endfacet + facet normal -0.766996 -0.223984 0.601288 + outer loop + vertex 419.938 115.788 55.2143 + vertex 416.356 119.782 52.1337 + vertex 417.572 115.291 52.0122 + endloop + endfacet + facet normal -0.687241 -0.204973 0.696912 + outer loop + vertex 416.356 119.782 52.1337 + vertex 413.607 119.168 49.2418 + vertex 417.572 115.291 52.0122 + endloop + endfacet + facet normal -0.683359 -0.196562 0.703124 + outer loop + vertex 417.572 115.291 52.0122 + vertex 413.607 119.168 49.2418 + vertex 414.791 114.667 49.1341 + endloop + endfacet + facet normal -0.704934 -0.171335 0.688268 + outer loop + vertex 413.094 133.01 52.2649 + vertex 410.401 132.385 49.3502 + vertex 414.141 128.631 52.2465 + endloop + endfacet + facet normal -0.702472 -0.165926 0.692099 + outer loop + vertex 414.141 128.631 52.2465 + vertex 410.401 132.385 49.3502 + vertex 411.425 128.013 49.3418 + endloop + endfacet + facet normal -0.787307 -0.193512 0.585406 + outer loop + vertex 415.387 133.487 55.5054 + vertex 413.094 133.01 52.2649 + vertex 416.446 129.102 55.4805 + endloop + endfacet + facet normal -0.786115 -0.190311 0.588052 + outer loop + vertex 416.446 129.102 55.4805 + vertex 413.094 133.01 52.2649 + vertex 414.141 128.631 52.2465 + endloop + endfacet + facet normal -0.783381 -0.201989 0.587806 + outer loop + vertex 416.446 129.102 55.4805 + vertex 414.141 128.631 52.2465 + vertex 417.541 124.708 55.43 + endloop + endfacet + facet normal -0.781172 -0.196085 0.592723 + outer loop + vertex 417.541 124.708 55.43 + vertex 414.141 128.631 52.2465 + vertex 415.216 124.233 52.209 + endloop + endfacet + facet normal -0.699844 -0.177043 0.692007 + outer loop + vertex 414.141 128.631 52.2465 + vertex 411.425 128.013 49.3418 + vertex 415.216 124.233 52.209 + endloop + endfacet + facet normal -0.698769 -0.174689 0.69369 + outer loop + vertex 415.216 124.233 52.209 + vertex 411.425 128.013 49.3418 + vertex 412.489 123.621 49.3074 + endloop + endfacet + facet normal -0.708725 -0.163475 0.686284 + outer loop + vertex 411.018 141.928 52.2585 + vertex 408.346 141.287 49.3466 + vertex 412.061 137.433 52.2646 + endloop + endfacet + facet normal -0.707539 -0.160958 0.688099 + outer loop + vertex 412.061 137.433 52.2646 + vertex 408.346 141.287 49.3466 + vertex 409.374 136.797 49.3535 + endloop + endfacet + facet normal -0.792488 -0.186222 0.580761 + outer loop + vertex 413.283 142.417 55.506 + vertex 411.018 141.928 52.2585 + vertex 414.342 137.916 55.5075 + endloop + endfacet + facet normal -0.791145 -0.182734 0.583694 + outer loop + vertex 414.342 137.916 55.5075 + vertex 411.018 141.928 52.2585 + vertex 412.061 137.433 52.2646 + endloop + endfacet + facet normal -0.790244 -0.186716 0.583654 + outer loop + vertex 414.342 137.916 55.5075 + vertex 412.061 137.433 52.2646 + vertex 415.387 133.487 55.5054 + endloop + endfacet + facet normal -0.789382 -0.18444 0.585541 + outer loop + vertex 415.387 133.487 55.5054 + vertex 412.061 137.433 52.2646 + vertex 413.094 133.01 52.2649 + endloop + endfacet + facet normal -0.706577 -0.165083 0.688111 + outer loop + vertex 412.061 137.433 52.2646 + vertex 409.374 136.797 49.3535 + vertex 413.094 133.01 52.2649 + endloop + endfacet + facet normal -0.706463 -0.164836 0.688287 + outer loop + vertex 413.094 133.01 52.2649 + vertex 409.374 136.797 49.3535 + vertex 410.401 132.385 49.3502 + endloop + endfacet + facet normal -0.712114 -0.164769 0.682455 + outer loop + vertex 408.905 151.029 52.2585 + vertex 406.261 150.388 49.3445 + vertex 409.959 146.478 52.2584 + endloop + endfacet + facet normal -0.710358 -0.161095 0.685157 + outer loop + vertex 409.959 146.478 52.2584 + vertex 406.261 150.388 49.3445 + vertex 407.298 145.835 49.3483 + endloop + endfacet + facet normal -0.79334 -0.184362 0.580192 + outer loop + vertex 411.161 151.532 55.502 + vertex 408.905 151.029 52.2585 + vertex 412.221 146.975 55.5035 + endloop + endfacet + facet normal -0.792996 -0.183482 0.58094 + outer loop + vertex 412.221 146.975 55.5035 + vertex 408.905 151.029 52.2585 + vertex 409.959 146.478 52.2584 + endloop + endfacet + facet normal -0.792781 -0.184427 0.580935 + outer loop + vertex 412.221 146.975 55.5035 + vertex 409.959 146.478 52.2584 + vertex 413.283 142.417 55.506 + endloop + endfacet + facet normal -0.792854 -0.184615 0.580774 + outer loop + vertex 413.283 142.417 55.506 + vertex 409.959 146.478 52.2584 + vertex 411.018 141.928 52.2585 + endloop + endfacet + facet normal -0.709397 -0.165178 0.685181 + outer loop + vertex 409.959 146.478 52.2584 + vertex 407.298 145.835 49.3483 + vertex 411.018 141.928 52.2585 + endloop + endfacet + facet normal -0.708679 -0.163672 0.686284 + outer loop + vertex 411.018 141.928 52.2585 + vertex 407.298 145.835 49.3483 + vertex 408.346 141.287 49.3466 + endloop + endfacet + facet normal -0.716108 -0.164244 0.678391 + outer loop + vertex 406.858 159.938 52.2524 + vertex 404.244 159.301 49.3386 + vertex 407.872 155.528 52.2546 + endloop + endfacet + facet normal -0.714244 -0.160191 0.681318 + outer loop + vertex 407.872 155.528 52.2546 + vertex 404.244 159.301 49.3386 + vertex 405.239 154.886 49.3436 + endloop + endfacet + facet normal -0.796327 -0.182758 0.576596 + outer loop + vertex 409.088 160.44 55.4905 + vertex 406.858 159.938 52.2524 + vertex 410.108 156.024 55.4999 + endloop + endfacet + facet normal -0.796316 -0.18273 0.57662 + outer loop + vertex 410.108 156.024 55.4999 + vertex 406.858 159.938 52.2524 + vertex 407.872 155.528 52.2546 + endloop + endfacet + facet normal -0.795533 -0.186159 0.576604 + outer loop + vertex 410.108 156.024 55.4999 + vertex 407.872 155.528 52.2546 + vertex 411.161 151.532 55.502 + endloop + endfacet + facet normal -0.793903 -0.181894 0.580201 + outer loop + vertex 411.161 151.532 55.502 + vertex 407.872 155.528 52.2546 + vertex 408.905 151.029 52.2585 + endloop + endfacet + facet normal -0.713506 -0.163337 0.681344 + outer loop + vertex 407.872 155.528 52.2546 + vertex 405.239 154.886 49.3436 + vertex 408.905 151.029 52.2585 + endloop + endfacet + facet normal -0.712803 -0.161843 0.682436 + outer loop + vertex 408.905 151.029 52.2585 + vertex 405.239 154.886 49.3436 + vertex 406.261 150.388 49.3445 + endloop + endfacet + facet normal -0.716839 -0.164289 0.677607 + outer loop + vertex 404.874 168.589 52.2501 + vertex 402.274 167.947 49.344 + vertex 405.863 164.274 52.251 + endloop + endfacet + facet normal -0.716967 -0.164577 0.677402 + outer loop + vertex 405.863 164.274 52.251 + vertex 402.274 167.947 49.344 + vertex 403.26 163.637 49.3403 + endloop + endfacet + facet normal -0.797566 -0.183735 0.57457 + outer loop + vertex 407.087 169.111 55.4894 + vertex 404.874 168.589 52.2501 + vertex 408.083 164.785 55.489 + endloop + endfacet + facet normal -0.797211 -0.182749 0.575376 + outer loop + vertex 408.083 164.785 55.489 + vertex 404.874 168.589 52.2501 + vertex 405.863 164.274 52.251 + endloop + endfacet + facet normal -0.796915 -0.184032 0.575376 + outer loop + vertex 408.083 164.785 55.489 + vertex 405.863 164.274 52.251 + vertex 409.088 160.44 55.4905 + endloop + endfacet + facet normal -0.796375 -0.182547 0.576596 + outer loop + vertex 409.088 160.44 55.4905 + vertex 405.863 164.274 52.251 + vertex 406.858 159.938 52.2524 + endloop + endfacet + facet normal -0.71703 -0.16431 0.6774 + outer loop + vertex 405.863 164.274 52.251 + vertex 403.26 163.637 49.3403 + vertex 406.858 159.938 52.2524 + endloop + endfacet + facet normal -0.716415 -0.162939 0.678381 + outer loop + vertex 406.858 159.938 52.2524 + vertex 403.26 163.637 49.3403 + vertex 404.244 159.301 49.3386 + endloop + endfacet + facet normal -0.718787 -0.163795 0.67566 + outer loop + vertex 402.853 177.372 52.2321 + vertex 400.263 176.725 49.3204 + vertex 403.872 172.944 52.2431 + endloop + endfacet + facet normal -0.717859 -0.161772 0.677132 + outer loop + vertex 403.872 172.944 52.2431 + vertex 400.263 176.725 49.3204 + vertex 401.279 172.296 49.339 + endloop + endfacet + facet normal -0.799527 -0.18273 0.572159 + outer loop + vertex 405.062 177.877 55.4809 + vertex 402.853 177.372 52.2321 + vertex 406.074 173.462 55.4846 + endloop + endfacet + facet normal -0.799489 -0.182628 0.572245 + outer loop + vertex 406.074 173.462 55.4846 + vertex 402.853 177.372 52.2321 + vertex 403.872 172.944 52.2431 + endloop + endfacet + facet normal -0.798856 -0.18536 0.572251 + outer loop + vertex 406.074 173.462 55.4846 + vertex 403.872 172.944 52.2431 + vertex 407.087 169.111 55.4894 + endloop + endfacet + facet normal -0.797841 -0.182547 0.574567 + outer loop + vertex 407.087 169.111 55.4894 + vertex 403.872 172.944 52.2431 + vertex 404.874 168.589 52.2501 + endloop + endfacet + facet normal -0.71736 -0.163875 0.677156 + outer loop + vertex 403.872 172.944 52.2431 + vertex 401.279 172.296 49.339 + vertex 404.874 168.589 52.2501 + endloop + endfacet + facet normal -0.717083 -0.163259 0.677598 + outer loop + vertex 404.874 168.589 52.2501 + vertex 401.279 172.296 49.339 + vertex 402.274 167.947 49.344 + endloop + endfacet + facet normal -0.724417 -0.164641 0.669413 + outer loop + vertex 400.867 186.373 52.2781 + vertex 398.248 185.753 49.2922 + vertex 401.845 181.864 52.228 + endloop + endfacet + facet normal -0.720293 -0.155916 0.67592 + outer loop + vertex 401.845 181.864 52.228 + vertex 398.248 185.753 49.2922 + vertex 399.234 181.225 49.2979 + endloop + endfacet + facet normal -0.804965 -0.183771 0.564145 + outer loop + vertex 403.079 186.841 55.5873 + vertex 400.867 186.373 52.2781 + vertex 404.055 182.345 55.5154 + endloop + endfacet + facet normal -0.8038 -0.180728 0.566783 + outer loop + vertex 404.055 182.345 55.5154 + vertex 400.867 186.373 52.2781 + vertex 401.845 181.864 52.228 + endloop + endfacet + facet normal -0.802759 -0.185362 0.566762 + outer loop + vertex 404.055 182.345 55.5154 + vertex 401.845 181.864 52.228 + vertex 405.062 177.877 55.4809 + endloop + endfacet + facet normal -0.800366 -0.179032 0.572155 + outer loop + vertex 405.062 177.877 55.4809 + vertex 401.845 181.864 52.228 + vertex 402.853 177.372 52.2321 + endloop + endfacet + facet normal -0.719182 -0.160722 0.675978 + outer loop + vertex 401.845 181.864 52.228 + vertex 399.234 181.225 49.2979 + vertex 402.853 177.372 52.2321 + endloop + endfacet + facet normal -0.719403 -0.161194 0.67563 + outer loop + vertex 402.853 177.372 52.2321 + vertex 399.234 181.225 49.2979 + vertex 400.263 176.725 49.3204 + endloop + endfacet + facet normal -0.738662 -0.0835492 0.668878 + outer loop + vertex 399.393 195.546 52.2819 + vertex 396.809 194.943 49.3526 + vertex 399.983 190.894 52.3523 + endloop + endfacet + facet normal -0.741754 -0.0890417 0.664735 + outer loop + vertex 399.983 190.894 52.3523 + vertex 396.809 194.943 49.3526 + vertex 397.378 190.293 49.3647 + endloop + endfacet + facet normal -0.815123 -0.0870239 0.572714 + outer loop + vertex 401.619 196.066 55.5292 + vertex 399.393 195.546 52.2819 + vertex 402.175 191.368 55.6069 + endloop + endfacet + facet normal -0.819122 -0.095314 0.565645 + outer loop + vertex 402.175 191.368 55.6069 + vertex 399.393 195.546 52.2819 + vertex 399.983 190.894 52.3523 + endloop + endfacet + facet normal -0.807008 -0.163577 0.567433 + outer loop + vertex 402.175 191.368 55.6069 + vertex 399.983 190.894 52.3523 + vertex 403.079 186.841 55.5873 + endloop + endfacet + facet normal -0.808514 -0.167316 0.56419 + outer loop + vertex 403.079 186.841 55.5873 + vertex 399.983 190.894 52.3523 + vertex 400.867 186.373 52.2781 + endloop + endfacet + facet normal -0.72926 -0.153509 0.666794 + outer loop + vertex 399.983 190.894 52.3523 + vertex 397.378 190.293 49.3647 + vertex 400.867 186.373 52.2781 + endloop + endfacet + facet normal -0.727665 -0.150246 0.669275 + outer loop + vertex 400.867 186.373 52.2781 + vertex 397.378 190.293 49.3647 + vertex 398.248 185.753 49.2922 + endloop + endfacet + facet normal 0.0255455 -0.51138 0.858975 + outer loop + vertex 450.394 57.6523 31.6987 + vertex 441.144 55.4247 30.6477 + vertex 450.019 56.4 30.9643 + endloop + endfacet + facet normal 0.0442454 -0.529692 0.847035 + outer loop + vertex 451.501 55.8933 30.5701 + vertex 450.019 56.4 30.9643 + vertex 436.436 53.1747 29.6569 + endloop + endfacet + facet normal 0.018914 -0.4358 0.899845 + outer loop + vertex 433.404 53.7961 30.0216 + vertex 436.436 53.1747 29.6569 + vertex 441.144 55.4247 30.6477 + endloop + endfacet + facet normal 0.0149034 -0.428899 0.903229 + outer loop + vertex 450.019 56.4 30.9643 + vertex 441.144 55.4247 30.6477 + vertex 436.436 53.1747 29.6569 + endloop + endfacet + facet normal 0.0122468 -0.493636 0.869582 + outer loop + vertex 441.146 58.6304 32.4118 + vertex 433.223 56.6759 31.4138 + vertex 441.749 57.0349 31.4976 + endloop + endfacet + facet normal 0.009355 -0.432428 0.90162 + outer loop + vertex 441.749 57.0349 31.4976 + vertex 433.223 56.6759 31.4138 + vertex 432.97 54.8787 30.5545 + endloop + endfacet + facet normal 0.00846307 -0.57065 0.82115 + outer loop + vertex 448.353 60.3293 33.5181 + vertex 441.146 58.6304 32.4118 + vertex 449.751 58.98 32.566 + endloop + endfacet + facet normal 0.0045774 -0.495855 0.868393 + outer loop + vertex 449.751 58.98 32.566 + vertex 441.146 58.6304 32.4118 + vertex 441.749 57.0349 31.4976 + endloop + endfacet + facet normal 0.019008 -0.540309 0.841252 + outer loop + vertex 449.751 58.98 32.566 + vertex 441.749 57.0349 31.4976 + vertex 450.394 57.6523 31.6987 + endloop + endfacet + facet normal 0.0130744 -0.470577 0.882262 + outer loop + vertex 450.394 57.6523 31.6987 + vertex 441.749 57.0349 31.4976 + vertex 441.144 55.4247 30.6477 + endloop + endfacet + facet normal 0.0215552 -0.472996 0.880801 + outer loop + vertex 441.749 57.0349 31.4976 + vertex 432.97 54.8787 30.5545 + vertex 441.144 55.4247 30.6477 + endloop + endfacet + facet normal 0.0188288 -0.435459 0.900011 + outer loop + vertex 441.144 55.4247 30.6477 + vertex 432.97 54.8787 30.5545 + vertex 433.404 53.7961 30.0216 + endloop + endfacet + facet normal -0.0152022 -0.526974 0.849745 + outer loop + vertex 438.279 61.7716 34.3027 + vertex 431.388 60.1593 33.1796 + vertex 439.855 60.1872 33.3484 + endloop + endfacet + facet normal -0.0161345 -0.463399 0.886003 + outer loop + vertex 439.855 60.1872 33.3484 + vertex 431.388 60.1593 33.1796 + vertex 432.576 58.4406 32.3023 + endloop + endfacet + facet normal -0.0258629 -0.601056 0.798788 + outer loop + vertex 444.76 63.2437 35.6203 + vertex 438.279 61.7716 34.3027 + vertex 446.604 61.7321 34.5425 + endloop + endfacet + facet normal -0.0268605 -0.535266 0.844256 + outer loop + vertex 446.604 61.7321 34.5425 + vertex 438.279 61.7716 34.3027 + vertex 439.855 60.1872 33.3484 + endloop + endfacet + facet normal -0.00611347 -0.594718 0.803911 + outer loop + vertex 446.604 61.7321 34.5425 + vertex 439.855 60.1872 33.3484 + vertex 448.353 60.3293 33.5181 + endloop + endfacet + facet normal -0.00834853 -0.520575 0.853775 + outer loop + vertex 448.353 60.3293 33.5181 + vertex 439.855 60.1872 33.3484 + vertex 441.146 58.6304 32.4118 + endloop + endfacet + facet normal 0.000465084 -0.515234 0.857049 + outer loop + vertex 439.855 60.1872 33.3484 + vertex 432.576 58.4406 32.3023 + vertex 441.146 58.6304 32.4118 + endloop + endfacet + facet normal -0.00143591 -0.45011 0.892972 + outer loop + vertex 441.146 58.6304 32.4118 + vertex 432.576 58.4406 32.3023 + vertex 433.223 56.6759 31.4138 + endloop + endfacet + facet normal -0.0592437 -0.522084 0.850834 + outer loop + vertex 434.919 65.4048 36.3577 + vertex 428.603 63.9154 35.004 + vertex 436.624 63.4922 35.3029 + endloop + endfacet + facet normal -0.0573407 -0.461808 0.885125 + outer loop + vertex 436.624 63.4922 35.3029 + vertex 428.603 63.9154 35.004 + vertex 430.015 61.9486 34.0693 + endloop + endfacet + facet normal -0.0769693 -0.596176 0.799156 + outer loop + vertex 440.825 66.7693 37.9444 + vertex 434.919 65.4048 36.3577 + vertex 442.847 64.9218 36.761 + endloop + endfacet + facet normal -0.0753164 -0.532228 0.843244 + outer loop + vertex 442.847 64.9218 36.761 + vertex 434.919 65.4048 36.3577 + vertex 436.624 63.4922 35.3029 + endloop + endfacet + facet normal -0.0494783 -0.599452 0.79888 + outer loop + vertex 442.847 64.9218 36.761 + vertex 436.624 63.4922 35.3029 + vertex 444.76 63.2437 35.6203 + endloop + endfacet + facet normal -0.0492584 -0.536909 0.842201 + outer loop + vertex 444.76 63.2437 35.6203 + vertex 436.624 63.4922 35.3029 + vertex 438.279 61.7716 34.3027 + endloop + endfacet + facet normal -0.0352721 -0.527362 0.848908 + outer loop + vertex 436.624 63.4922 35.3029 + vertex 430.015 61.9486 34.0693 + vertex 438.279 61.7716 34.3027 + endloop + endfacet + facet normal -0.0349537 -0.466355 0.883907 + outer loop + vertex 438.279 61.7716 34.3027 + vertex 430.015 61.9486 34.0693 + vertex 431.388 60.1593 33.1796 + endloop + endfacet + facet normal -0.118357 -0.50879 0.852716 + outer loop + vertex 431.274 69.8087 38.5636 + vertex 425.643 68.5037 37.0033 + vertex 433.138 67.511 37.4513 + endloop + endfacet + facet normal -0.112041 -0.444944 0.888522 + outer loop + vertex 433.138 67.511 37.4513 + vertex 425.643 68.5037 37.0033 + vertex 427.159 66.1011 35.9913 + endloop + endfacet + facet normal -0.144494 -0.586107 0.797245 + outer loop + vertex 436.489 70.9942 40.3802 + vertex 431.274 69.8087 38.5636 + vertex 438.689 68.7946 39.1619 + endloop + endfacet + facet normal -0.139181 -0.520661 0.842342 + outer loop + vertex 438.689 68.7946 39.1619 + vertex 431.274 69.8087 38.5636 + vertex 433.138 67.511 37.4513 + endloop + endfacet + facet normal -0.108436 -0.593674 0.797366 + outer loop + vertex 438.689 68.7946 39.1619 + vertex 433.138 67.511 37.4513 + vertex 440.825 66.7693 37.9444 + endloop + endfacet + facet normal -0.104939 -0.526729 0.843531 + outer loop + vertex 440.825 66.7693 37.9444 + vertex 433.138 67.511 37.4513 + vertex 434.919 65.4048 36.3577 + endloop + endfacet + facet normal -0.08652 -0.515738 0.852366 + outer loop + vertex 433.138 67.511 37.4513 + vertex 427.159 66.1011 35.9913 + vertex 434.919 65.4048 36.3577 + endloop + endfacet + facet normal -0.082696 -0.455117 0.886583 + outer loop + vertex 434.919 65.4048 36.3577 + vertex 427.159 66.1011 35.9913 + vertex 428.603 63.9154 35.004 + endloop + endfacet + facet normal -0.194042 -0.479182 0.855998 + outer loop + vertex 427.409 75.0161 40.7453 + vertex 422.392 73.9554 39.0143 + vertex 429.357 72.3006 39.6667 + endloop + endfacet + facet normal -0.18291 -0.419207 0.889275 + outer loop + vertex 429.357 72.3006 39.6667 + vertex 422.392 73.9554 39.0143 + vertex 424.046 71.1264 38.0209 + endloop + endfacet + facet normal -0.227867 -0.548228 0.804688 + outer loop + vertex 432.06 76.0613 42.7746 + vertex 427.409 75.0161 40.7453 + vertex 434.269 73.4066 41.5915 + endloop + endfacet + facet normal -0.219338 -0.491976 0.842527 + outer loop + vertex 434.269 73.4066 41.5915 + vertex 427.409 75.0161 40.7453 + vertex 429.357 72.3006 39.6667 + endloop + endfacet + facet normal -0.184661 -0.571375 0.799644 + outer loop + vertex 434.269 73.4066 41.5915 + vertex 429.357 72.3006 39.6667 + vertex 436.489 70.9942 40.3802 + endloop + endfacet + facet normal -0.177543 -0.509364 0.842037 + outer loop + vertex 436.489 70.9942 40.3802 + vertex 429.357 72.3006 39.6667 + vertex 431.274 69.8087 38.5636 + endloop + endfacet + facet normal -0.15472 -0.497028 0.85383 + outer loop + vertex 429.357 72.3006 39.6667 + vertex 424.046 71.1264 38.0209 + vertex 431.274 69.8087 38.5636 + endloop + endfacet + facet normal -0.145839 -0.433769 0.889143 + outer loop + vertex 431.274 69.8087 38.5636 + vertex 424.046 71.1264 38.0209 + vertex 425.643 68.5037 37.0033 + endloop + endfacet + facet normal -0.272991 -0.41953 0.86572 + outer loop + vertex 423.559 81.2174 42.7465 + vertex 418.96 80.2476 40.8263 + vertex 425.462 77.9827 41.7791 + endloop + endfacet + facet normal -0.261084 -0.375414 0.889325 + outer loop + vertex 425.462 77.9827 41.7791 + vertex 418.96 80.2476 40.8263 + vertex 420.68 76.9855 39.9542 + endloop + endfacet + facet normal -0.320187 -0.482043 0.815546 + outer loop + vertex 427.772 82.1852 44.9726 + vertex 423.559 81.2174 42.7465 + vertex 429.884 78.9907 43.9137 + endloop + endfacet + facet normal -0.309151 -0.434843 0.845776 + outer loop + vertex 429.884 78.9907 43.9137 + vertex 423.559 81.2174 42.7465 + vertex 425.462 77.9827 41.7791 + endloop + endfacet + facet normal -0.273162 -0.518087 0.810536 + outer loop + vertex 429.884 78.9907 43.9137 + vertex 425.462 77.9827 41.7791 + vertex 432.06 76.0613 42.7746 + endloop + endfacet + facet normal -0.263346 -0.466964 0.844152 + outer loop + vertex 432.06 76.0613 42.7746 + vertex 425.462 77.9827 41.7791 + vertex 427.409 75.0161 40.7453 + endloop + endfacet + facet normal -0.23377 -0.453161 0.86023 + outer loop + vertex 425.462 77.9827 41.7791 + vertex 420.68 76.9855 39.9542 + vertex 427.409 75.0161 40.7453 + endloop + endfacet + facet normal -0.221873 -0.401049 0.888781 + outer loop + vertex 427.409 75.0161 40.7453 + vertex 420.68 76.9855 39.9542 + vertex 422.392 73.9554 39.0143 + endloop + endfacet + facet normal -0.35008 -0.339352 0.873089 + outer loop + vertex 420.01 88.4276 44.3725 + vertex 415.733 87.4921 42.294 + vertex 421.736 84.7068 43.6183 + endloop + endfacet + facet normal -0.33759 -0.303985 0.890857 + outer loop + vertex 421.736 84.7068 43.6183 + vertex 415.733 87.4921 42.294 + vertex 417.3 83.7555 41.6128 + endloop + endfacet + facet normal -0.415268 -0.398583 0.817731 + outer loop + vertex 423.835 89.309 46.7445 + vertex 420.01 88.4276 44.3725 + vertex 425.748 85.6339 45.9248 + endloop + endfacet + facet normal -0.402034 -0.357354 0.843011 + outer loop + vertex 425.748 85.6339 45.9248 + vertex 420.01 88.4276 44.3725 + vertex 421.736 84.7068 43.6183 + endloop + endfacet + facet normal -0.368134 -0.441925 0.818034 + outer loop + vertex 425.748 85.6339 45.9248 + vertex 421.736 84.7068 43.6183 + vertex 427.772 82.1852 44.9726 + endloop + endfacet + facet normal -0.355736 -0.397246 0.845959 + outer loop + vertex 427.772 82.1852 44.9726 + vertex 421.736 84.7068 43.6183 + vertex 423.559 81.2174 42.7465 + endloop + endfacet + facet normal -0.311992 -0.380533 0.870549 + outer loop + vertex 421.736 84.7068 43.6183 + vertex 417.3 83.7555 41.6128 + vertex 423.559 81.2174 42.7465 + endloop + endfacet + facet normal -0.416594 -0.262816 0.870274 + outer loop + vertex 416.858 96.4346 45.5038 + vertex 412.862 95.558 43.3264 + vertex 418.383 92.3489 45.0002 + endloop + endfacet + facet normal -0.405067 -0.236221 0.883244 + outer loop + vertex 418.383 92.3489 45.0002 + vertex 412.862 95.558 43.3264 + vertex 414.257 91.4408 42.8651 + endloop + endfacet + facet normal -0.495387 -0.312805 0.810398 + outer loop + vertex 420.384 97.2361 47.9687 + vertex 416.858 96.4346 45.5038 + vertex 422.048 93.1841 47.4219 + endloop + endfacet + facet normal -0.483194 -0.282555 0.828666 + outer loop + vertex 422.048 93.1841 47.4219 + vertex 416.858 96.4346 45.5038 + vertex 418.383 92.3489 45.0002 + endloop + endfacet + facet normal -0.458192 -0.353805 0.815403 + outer loop + vertex 422.048 93.1841 47.4219 + vertex 418.383 92.3489 45.0002 + vertex 423.835 89.309 46.7445 + endloop + endfacet + facet normal -0.445424 -0.318702 0.836676 + outer loop + vertex 423.835 89.309 46.7445 + vertex 418.383 92.3489 45.0002 + vertex 420.01 88.4276 44.3725 + endloop + endfacet + facet normal -0.385621 -0.299653 0.872642 + outer loop + vertex 418.383 92.3489 45.0002 + vertex 414.257 91.4408 42.8651 + vertex 420.01 88.4276 44.3725 + endloop + endfacet + facet normal -0.373089 -0.267906 0.888274 + outer loop + vertex 420.01 88.4276 44.3725 + vertex 414.257 91.4408 42.8651 + vertex 415.733 87.4921 42.294 + endloop + endfacet + facet normal -0.463729 -0.204702 0.862005 + outer loop + vertex 414.064 104.999 46.2 + vertex 410.27 104.169 43.9616 + vertex 415.42 100.659 45.899 + endloop + endfacet + facet normal -0.455161 -0.187466 0.870451 + outer loop + vertex 415.42 100.659 45.899 + vertex 410.27 104.169 43.9616 + vertex 411.539 99.8079 43.6861 + endloop + endfacet + facet normal -0.550102 -0.243995 0.798658 + outer loop + vertex 417.397 105.756 48.7265 + vertex 414.064 104.999 46.2 + vertex 418.837 101.435 48.3985 + endloop + endfacet + facet normal -0.541412 -0.225369 0.809989 + outer loop + vertex 418.837 101.435 48.3985 + vertex 414.064 104.999 46.2 + vertex 415.42 100.659 45.899 + endloop + endfacet + facet normal -0.525867 -0.276126 0.804498 + outer loop + vertex 418.837 101.435 48.3985 + vertex 415.42 100.659 45.899 + vertex 420.384 97.2361 47.9687 + endloop + endfacet + facet normal -0.515313 -0.251976 0.819122 + outer loop + vertex 420.384 97.2361 47.9687 + vertex 415.42 100.659 45.899 + vertex 416.858 96.4346 45.5038 + endloop + endfacet + facet normal -0.442957 -0.23175 0.866073 + outer loop + vertex 415.42 100.659 45.899 + vertex 411.539 99.8079 43.6861 + vertex 416.858 96.4346 45.5038 + endloop + endfacet + facet normal -0.432238 -0.208829 0.877246 + outer loop + vertex 416.858 96.4346 45.5038 + vertex 411.539 99.8079 43.6861 + vertex 412.862 95.558 43.3264 + endloop + endfacet + facet normal -0.492952 -0.162349 0.854776 + outer loop + vertex 411.563 113.934 46.5746 + vertex 407.888 113.124 44.3013 + vertex 412.779 109.436 46.4216 + endloop + endfacet + facet normal -0.488225 -0.153598 0.859095 + outer loop + vertex 412.779 109.436 46.4216 + vertex 407.888 113.124 44.3013 + vertex 409.057 108.618 44.16 + endloop + endfacet + facet normal -0.582121 -0.19402 0.789615 + outer loop + vertex 414.791 114.667 49.1341 + vertex 411.563 113.934 46.5746 + vertex 416.056 110.179 48.9638 + endloop + endfacet + facet normal -0.576459 -0.182942 0.796384 + outer loop + vertex 416.056 110.179 48.9638 + vertex 411.563 113.934 46.5746 + vertex 412.779 109.436 46.4216 + endloop + endfacet + facet normal -0.567861 -0.214786 0.794607 + outer loop + vertex 416.056 110.179 48.9638 + vertex 412.779 109.436 46.4216 + vertex 417.397 105.756 48.7265 + endloop + endfacet + facet normal -0.561948 -0.202779 0.801932 + outer loop + vertex 417.397 105.756 48.7265 + vertex 412.779 109.436 46.4216 + vertex 414.064 104.999 46.2 + endloop + endfacet + facet normal -0.481033 -0.182125 0.857577 + outer loop + vertex 412.779 109.436 46.4216 + vertex 409.057 108.618 44.16 + vertex 414.064 104.999 46.2 + endloop + endfacet + facet normal -0.473452 -0.167606 0.864726 + outer loop + vertex 414.064 104.999 46.2 + vertex 409.057 108.618 44.16 + vertex 410.27 104.169 43.9616 + endloop + endfacet + facet normal -0.508938 -0.135106 0.850135 + outer loop + vertex 409.324 122.895 46.7284 + vertex 405.715 122.092 44.4405 + vertex 410.413 118.439 46.6722 + endloop + endfacet + facet normal -0.506302 -0.130299 0.852455 + outer loop + vertex 410.413 118.439 46.6722 + vertex 405.715 122.092 44.4405 + vertex 406.776 117.634 44.3892 + endloop + endfacet + facet normal -0.600655 -0.162334 0.782854 + outer loop + vertex 412.489 123.621 49.3074 + vertex 409.324 122.895 46.7284 + vertex 413.607 119.168 49.2418 + endloop + endfacet + facet normal -0.597322 -0.15591 0.786701 + outer loop + vertex 413.607 119.168 49.2418 + vertex 409.324 122.895 46.7284 + vertex 410.413 118.439 46.6722 + endloop + endfacet + facet normal -0.592683 -0.174702 0.786261 + outer loop + vertex 413.607 119.168 49.2418 + vertex 410.413 118.439 46.6722 + vertex 414.791 114.667 49.1341 + endloop + endfacet + facet normal -0.588943 -0.167514 0.790623 + outer loop + vertex 414.791 114.667 49.1341 + vertex 410.413 118.439 46.6722 + vertex 411.563 113.934 46.5746 + endloop + endfacet + facet normal -0.50242 -0.146756 0.852078 + outer loop + vertex 410.413 118.439 46.6722 + vertex 406.776 117.634 44.3892 + vertex 411.563 113.934 46.5746 + endloop + endfacet + facet normal -0.498476 -0.139576 0.855594 + outer loop + vertex 411.563 113.934 46.5746 + vertex 406.776 117.634 44.3892 + vertex 407.888 113.124 44.3013 + endloop + endfacet + facet normal -0.517335 -0.122461 0.846976 + outer loop + vertex 407.269 131.651 46.7682 + vertex 403.706 130.847 44.4757 + vertex 408.283 127.285 46.7565 + endloop + endfacet + facet normal -0.515764 -0.119564 0.848347 + outer loop + vertex 408.283 127.285 46.7565 + vertex 403.706 130.847 44.4757 + vertex 404.7 126.483 44.4648 + endloop + endfacet + facet normal -0.609115 -0.144222 0.779858 + outer loop + vertex 410.401 132.385 49.3502 + vertex 407.269 131.651 46.7682 + vertex 411.425 128.013 49.3418 + endloop + endfacet + facet normal -0.608756 -0.143522 0.780268 + outer loop + vertex 411.425 128.013 49.3418 + vertex 407.269 131.651 46.7682 + vertex 408.283 127.285 46.7565 + endloop + endfacet + facet normal -0.606511 -0.153019 0.780211 + outer loop + vertex 411.425 128.013 49.3418 + vertex 408.283 127.285 46.7565 + vertex 412.489 123.621 49.3074 + endloop + endfacet + facet normal -0.604047 -0.148218 0.783045 + outer loop + vertex 412.489 123.621 49.3074 + vertex 408.283 127.285 46.7565 + vertex 409.324 122.895 46.7284 + endloop + endfacet + facet normal -0.513999 -0.127288 0.848294 + outer loop + vertex 408.283 127.285 46.7565 + vertex 404.7 126.483 44.4648 + vertex 409.324 122.895 46.7284 + endloop + endfacet + facet normal -0.511716 -0.123084 0.850292 + outer loop + vertex 409.324 122.895 46.7284 + vertex 404.7 126.483 44.4648 + vertex 405.715 122.092 44.4405 + endloop + endfacet + facet normal -0.521405 -0.11697 0.845254 + outer loop + vertex 405.25 140.544 46.7625 + vertex 401.719 139.741 44.4735 + vertex 406.264 136.058 46.7673 + endloop + endfacet + facet normal -0.520812 -0.115921 0.845764 + outer loop + vertex 406.264 136.058 46.7673 + vertex 401.719 139.741 44.4735 + vertex 402.72 135.253 44.4746 + endloop + endfacet + facet normal -0.614497 -0.139518 0.776485 + outer loop + vertex 408.346 141.287 49.3466 + vertex 405.25 140.544 46.7625 + vertex 409.374 136.797 49.3535 + endloop + endfacet + facet normal -0.613632 -0.137894 0.777458 + outer loop + vertex 409.374 136.797 49.3535 + vertex 405.25 140.544 46.7625 + vertex 406.264 136.058 46.7673 + endloop + endfacet + facet normal -0.612429 -0.143028 0.777479 + outer loop + vertex 409.374 136.797 49.3535 + vertex 406.264 136.058 46.7673 + vertex 410.401 132.385 49.3502 + endloop + endfacet + facet normal -0.610335 -0.139 0.779852 + outer loop + vertex 410.401 132.385 49.3502 + vertex 406.264 136.058 46.7673 + vertex 407.269 131.651 46.7682 + endloop + endfacet + facet normal -0.520241 -0.118446 0.845766 + outer loop + vertex 406.264 136.058 46.7673 + vertex 402.72 135.253 44.4746 + vertex 407.269 131.651 46.7682 + endloop + endfacet + facet normal -0.518827 -0.115882 0.846989 + outer loop + vertex 407.269 131.651 46.7682 + vertex 402.72 135.253 44.4746 + vertex 403.706 130.847 44.4757 + endloop + endfacet + facet normal -0.524868 -0.118008 0.842963 + outer loop + vertex 403.195 149.649 46.7614 + vertex 399.702 148.851 44.4742 + vertex 404.22 145.095 46.7618 + endloop + endfacet + facet normal -0.523783 -0.116133 0.843898 + outer loop + vertex 404.22 145.095 46.7618 + vertex 399.702 148.851 44.4742 + vertex 400.709 144.293 44.4725 + endloop + endfacet + facet normal -0.618029 -0.140009 0.773588 + outer loop + vertex 406.261 150.388 49.3445 + vertex 403.195 149.649 46.7614 + vertex 407.298 145.835 49.3483 + endloop + endfacet + facet normal -0.617387 -0.138827 0.774313 + outer loop + vertex 407.298 145.835 49.3483 + vertex 403.195 149.649 46.7614 + vertex 404.22 145.095 46.7618 + endloop + endfacet + facet normal -0.616532 -0.142457 0.774335 + outer loop + vertex 407.298 145.835 49.3483 + vertex 404.22 145.095 46.7618 + vertex 408.346 141.287 49.3466 + endloop + endfacet + facet normal -0.614632 -0.138941 0.776481 + outer loop + vertex 408.346 141.287 49.3466 + vertex 404.22 145.095 46.7618 + vertex 405.25 140.544 46.7625 + endloop + endfacet + facet normal -0.523299 -0.118265 0.843903 + outer loop + vertex 404.22 145.095 46.7618 + vertex 400.709 144.293 44.4725 + vertex 405.25 140.544 46.7625 + endloop + endfacet + facet normal -0.521729 -0.11554 0.845251 + outer loop + vertex 405.25 140.544 46.7625 + vertex 400.709 144.293 44.4725 + vertex 401.719 139.741 44.4735 + endloop + endfacet + facet normal -0.52911 -0.118221 0.840277 + outer loop + vertex 401.201 158.565 46.7626 + vertex 397.743 157.772 44.4735 + vertex 402.187 154.15 46.7623 + endloop + endfacet + facet normal -0.528346 -0.11686 0.840948 + outer loop + vertex 402.187 154.15 46.7623 + vertex 397.743 157.772 44.4735 + vertex 398.716 153.355 44.4713 + endloop + endfacet + facet normal -0.620038 -0.138857 0.772186 + outer loop + vertex 404.244 159.301 49.3386 + vertex 401.201 158.565 46.7626 + vertex 405.239 154.886 49.3436 + endloop + endfacet + facet normal -0.619839 -0.13848 0.772414 + outer loop + vertex 405.239 154.886 49.3436 + vertex 401.201 158.565 46.7626 + vertex 402.187 154.15 46.7623 + endloop + endfacet + facet normal -0.619345 -0.140586 0.77243 + outer loop + vertex 405.239 154.886 49.3436 + vertex 402.187 154.15 46.7623 + vertex 406.261 150.388 49.3445 + endloop + endfacet + facet normal -0.618335 -0.138704 0.773578 + outer loop + vertex 406.261 150.388 49.3445 + vertex 402.187 154.15 46.7623 + vertex 403.195 149.649 46.7614 + endloop + endfacet + facet normal -0.52798 -0.118473 0.840953 + outer loop + vertex 402.187 154.15 46.7623 + vertex 398.716 153.355 44.4713 + vertex 403.195 149.649 46.7614 + endloop + endfacet + facet normal -0.525674 -0.114451 0.842952 + outer loop + vertex 403.195 149.649 46.7614 + vertex 398.716 153.355 44.4713 + vertex 399.702 148.851 44.4742 + endloop + endfacet + facet normal -0.531889 -0.12142 0.838064 + outer loop + vertex 399.253 167.218 46.7639 + vertex 395.815 166.428 44.4678 + vertex 400.232 162.906 46.7607 + endloop + endfacet + facet normal -0.530129 -0.118188 0.83964 + outer loop + vertex 400.232 162.906 46.7607 + vertex 395.815 166.428 44.4678 + vertex 396.783 162.115 44.4714 + endloop + endfacet + facet normal -0.622552 -0.143062 0.769391 + outer loop + vertex 402.274 167.947 49.344 + vertex 399.253 167.218 46.7639 + vertex 403.26 163.637 49.3403 + endloop + endfacet + facet normal -0.621917 -0.141815 0.770135 + outer loop + vertex 403.26 163.637 49.3403 + vertex 399.253 167.218 46.7639 + vertex 400.232 162.906 46.7607 + endloop + endfacet + facet normal -0.621983 -0.141533 0.770133 + outer loop + vertex 403.26 163.637 49.3403 + vertex 400.232 162.906 46.7607 + vertex 404.244 159.301 49.3386 + endloop + endfacet + facet normal -0.620215 -0.138101 0.77218 + outer loop + vertex 404.244 159.301 49.3386 + vertex 400.232 162.906 46.7607 + vertex 401.201 158.565 46.7626 + endloop + endfacet + facet normal -0.530178 -0.117974 0.839639 + outer loop + vertex 400.232 162.906 46.7607 + vertex 396.783 162.115 44.4714 + vertex 401.201 158.565 46.7626 + endloop + endfacet + facet normal -0.529462 -0.116674 0.840272 + outer loop + vertex 401.201 158.565 46.7626 + vertex 396.783 162.115 44.4714 + vertex 397.743 157.772 44.4735 + endloop + endfacet + facet normal -0.530217 -0.122375 0.838984 + outer loop + vertex 397.231 175.989 46.7553 + vertex 393.794 175.196 44.4675 + vertex 398.26 171.565 46.7606 + endloop + endfacet + facet normal -0.529144 -0.120451 0.83994 + outer loop + vertex 398.26 171.565 46.7606 + vertex 393.794 175.196 44.4675 + vertex 394.811 170.775 44.4742 + endloop + endfacet + facet normal -0.619681 -0.138858 0.772472 + outer loop + vertex 400.263 176.725 49.3204 + vertex 397.231 175.989 46.7553 + vertex 401.279 172.296 49.339 + endloop + endfacet + facet normal -0.622327 -0.143896 0.769417 + outer loop + vertex 401.279 172.296 49.339 + vertex 397.231 175.989 46.7553 + vertex 398.26 171.565 46.7606 + endloop + endfacet + facet normal -0.622871 -0.141601 0.769403 + outer loop + vertex 401.279 172.296 49.339 + vertex 398.26 171.565 46.7606 + vertex 402.274 167.947 49.344 + endloop + endfacet + facet normal -0.622889 -0.141636 0.769382 + outer loop + vertex 402.274 167.947 49.344 + vertex 398.26 171.565 46.7606 + vertex 399.253 167.218 46.7639 + endloop + endfacet + facet normal -0.529203 -0.120193 0.839939 + outer loop + vertex 398.26 171.565 46.7606 + vertex 394.811 170.775 44.4742 + vertex 399.253 167.218 46.7639 + endloop + endfacet + facet normal -0.531293 -0.124011 0.838063 + outer loop + vertex 399.253 167.218 46.7639 + vertex 394.811 170.775 44.4742 + vertex 395.815 166.428 44.4678 + endloop + endfacet + facet normal -0.532615 -0.110528 0.83911 + outer loop + vertex 395.203 185.021 46.6865 + vertex 391.778 184.225 44.4082 + vertex 396.2 180.488 46.7227 + endloop + endfacet + facet normal -0.531851 -0.109219 0.839765 + outer loop + vertex 396.2 180.488 46.7227 + vertex 391.778 184.225 44.4082 + vertex 392.769 179.693 44.446 + endloop + endfacet + facet normal -0.625164 -0.135095 0.768712 + outer loop + vertex 398.248 185.753 49.2922 + vertex 395.203 185.021 46.6865 + vertex 399.234 181.225 49.2979 + endloop + endfacet + facet normal -0.622907 -0.130946 0.771258 + outer loop + vertex 399.234 181.225 49.2979 + vertex 395.203 185.021 46.6865 + vertex 396.2 180.488 46.7227 + endloop + endfacet + facet normal -0.621211 -0.138253 0.771352 + outer loop + vertex 399.234 181.225 49.2979 + vertex 396.2 180.488 46.7227 + vertex 400.263 176.725 49.3204 + endloop + endfacet + facet normal -0.620245 -0.136453 0.772449 + outer loop + vertex 400.263 176.725 49.3204 + vertex 396.2 180.488 46.7227 + vertex 397.231 175.989 46.7553 + endloop + endfacet + facet normal -0.530455 -0.115404 0.839821 + outer loop + vertex 396.2 180.488 46.7227 + vertex 392.769 179.693 44.446 + vertex 397.231 175.989 46.7553 + endloop + endfacet + facet normal -0.531426 -0.117102 0.838972 + outer loop + vertex 397.231 175.989 46.7553 + vertex 392.769 179.693 44.446 + vertex 393.794 175.196 44.4675 + endloop + endfacet + facet normal -0.564829 -0.0647971 0.82266 + outer loop + vertex 393.949 194.281 46.8064 + vertex 390.721 193.544 44.5318 + vertex 394.367 189.586 46.7238 + endloop + endfacet + facet normal -0.553947 -0.0501302 0.831042 + outer loop + vertex 394.367 189.586 46.7238 + vertex 390.721 193.544 44.5318 + vertex 390.968 188.799 44.4106 + endloop + endfacet + facet normal -0.652838 -0.0779312 0.753478 + outer loop + vertex 396.809 194.943 49.3526 + vertex 393.949 194.281 46.8064 + vertex 397.378 190.293 49.3647 + endloop + endfacet + facet normal -0.648305 -0.0710991 0.758054 + outer loop + vertex 397.378 190.293 49.3647 + vertex 393.949 194.281 46.8064 + vertex 394.367 189.586 46.7238 + endloop + endfacet + facet normal -0.635529 -0.134029 0.760354 + outer loop + vertex 397.378 190.293 49.3647 + vertex 394.367 189.586 46.7238 + vertex 398.248 185.753 49.2922 + endloop + endfacet + facet normal -0.628288 -0.121255 0.768474 + outer loop + vertex 398.248 185.753 49.2922 + vertex 394.367 189.586 46.7238 + vertex 395.203 185.021 46.6865 + endloop + endfacet + facet normal -0.542541 -0.106094 0.833303 + outer loop + vertex 394.367 189.586 46.7238 + vertex 390.968 188.799 44.4106 + vertex 395.203 185.021 46.6865 + endloop + endfacet + facet normal -0.535955 -0.0953776 0.838841 + outer loop + vertex 395.203 185.021 46.6865 + vertex 390.968 188.799 44.4106 + vertex 391.778 184.225 44.4082 + endloop + endfacet + facet normal 0.0262116 -0.407749 0.912718 + outer loop + vertex 433.404 53.7961 30.0216 + vertex 421.956 52.1178 29.6006 + vertex 436.436 53.1747 29.6569 + endloop + endfacet + facet normal 0.0231437 -0.36664 0.930075 + outer loop + vertex 436.436 53.1747 29.6569 + vertex 421.956 52.1178 29.6006 + vertex 418.518 49.0769 28.4874 + endloop + endfacet + facet normal 0.0157193 -0.433121 0.901199 + outer loop + vertex 433.223 56.6759 31.4138 + vertex 424.521 54.5093 30.5243 + vertex 432.97 54.8787 30.5545 + endloop + endfacet + facet normal 0.0301308 -0.431676 0.901525 + outer loop + vertex 433.404 53.7961 30.0216 + vertex 432.97 54.8787 30.5545 + vertex 421.956 52.1178 29.6006 + endloop + endfacet + facet normal 0.0127875 -0.372182 0.928072 + outer loop + vertex 417.198 52.9616 30.0046 + vertex 421.956 52.1178 29.6006 + vertex 424.521 54.5093 30.5243 + endloop + endfacet + facet normal 0.0129666 -0.372348 0.928003 + outer loop + vertex 432.97 54.8787 30.5545 + vertex 424.521 54.5093 30.5243 + vertex 421.956 52.1178 29.6006 + endloop + endfacet + facet normal 0.000635102 -0.401139 0.916017 + outer loop + vertex 423.924 58.3031 32.172 + vertex 416.739 56.3917 31.34 + vertex 424.657 56.4394 31.3554 + endloop + endfacet + facet normal 0.000341559 -0.358098 0.933684 + outer loop + vertex 424.657 56.4394 31.3554 + vertex 416.739 56.3917 31.34 + vertex 415.713 54.345 30.5554 + endloop + endfacet + facet normal -0.0061058 -0.457969 0.888947 + outer loop + vertex 431.388 60.1593 33.1796 + vertex 423.924 58.3031 32.172 + vertex 432.576 58.4406 32.3023 + endloop + endfacet + facet normal -0.007357 -0.403764 0.914834 + outer loop + vertex 432.576 58.4406 32.3023 + vertex 423.924 58.3031 32.172 + vertex 424.657 56.4394 31.3554 + endloop + endfacet + facet normal 0.00626458 -0.44785 0.894087 + outer loop + vertex 432.576 58.4406 32.3023 + vertex 424.657 56.4394 31.3554 + vertex 433.223 56.6759 31.4138 + endloop + endfacet + facet normal 0.00466017 -0.395743 0.918349 + outer loop + vertex 433.223 56.6759 31.4138 + vertex 424.657 56.4394 31.3554 + vertex 424.521 54.5093 30.5243 + endloop + endfacet + facet normal 0.0106258 -0.396081 0.918154 + outer loop + vertex 424.657 56.4394 31.3554 + vertex 415.713 54.345 30.5554 + vertex 424.521 54.5093 30.5243 + endloop + endfacet + facet normal 0.010015 -0.360607 0.932664 + outer loop + vertex 424.521 54.5093 30.5243 + vertex 415.713 54.345 30.5554 + vertex 417.198 52.9616 30.0046 + endloop + endfacet + facet normal -0.0281033 -0.393572 0.918864 + outer loop + vertex 421.733 62.2346 33.8266 + vertex 415.046 60.4604 32.8621 + vertex 422.866 60.1904 32.9857 + endloop + endfacet + facet normal -0.0267901 -0.347018 0.937476 + outer loop + vertex 422.866 60.1904 32.9857 + vertex 415.046 60.4604 32.8621 + vertex 414.435 58.2056 32.01 + endloop + endfacet + facet normal -0.0417456 -0.453148 0.890457 + outer loop + vertex 428.603 63.9154 35.004 + vertex 421.733 62.2346 33.8266 + vertex 430.015 61.9486 34.0693 + endloop + endfacet + facet normal -0.0406328 -0.399307 0.915917 + outer loop + vertex 430.015 61.9486 34.0693 + vertex 421.733 62.2346 33.8266 + vertex 422.866 60.1904 32.9857 + endloop + endfacet + facet normal -0.0218886 -0.458559 0.888395 + outer loop + vertex 430.015 61.9486 34.0693 + vertex 422.866 60.1904 32.9857 + vertex 431.388 60.1593 33.1796 + endloop + endfacet + facet normal -0.0222686 -0.406288 0.913474 + outer loop + vertex 431.388 60.1593 33.1796 + vertex 422.866 60.1904 32.9857 + vertex 423.924 58.3031 32.172 + endloop + endfacet + facet normal -0.011512 -0.401294 0.915877 + outer loop + vertex 422.866 60.1904 32.9857 + vertex 414.435 58.2056 32.01 + vertex 423.924 58.3031 32.172 + endloop + endfacet + facet normal -0.0122246 -0.36012 0.932826 + outer loop + vertex 423.924 58.3031 32.172 + vertex 414.435 58.2056 32.01 + vertex 416.739 56.3917 31.34 + endloop + endfacet + facet normal -0.0678605 -0.37353 0.925133 + outer loop + vertex 419.497 66.9493 35.6289 + vertex 413.323 65.2904 34.5062 + vertex 420.607 64.4844 34.7151 + endloop + endfacet + facet normal -0.0631239 -0.326029 0.94325 + outer loop + vertex 420.607 64.4844 34.7151 + vertex 413.323 65.2904 34.5062 + vertex 412.71 62.6953 33.5682 + endloop + endfacet + facet normal -0.0904992 -0.434544 0.896092 + outer loop + vertex 425.643 68.5037 37.0033 + vertex 419.497 66.9493 35.6289 + vertex 427.159 66.1011 35.9913 + endloop + endfacet + facet normal -0.0856399 -0.380006 0.921011 + outer loop + vertex 427.159 66.1011 35.9913 + vertex 419.497 66.9493 35.6289 + vertex 420.607 64.4844 34.7151 + endloop + endfacet + facet normal -0.0639787 -0.445618 0.892934 + outer loop + vertex 427.159 66.1011 35.9913 + vertex 420.607 64.4844 34.7151 + vertex 428.603 63.9154 35.004 + endloop + endfacet + facet normal -0.0611189 -0.39293 0.917535 + outer loop + vertex 428.603 63.9154 35.004 + vertex 420.607 64.4844 34.7151 + vertex 421.733 62.2346 33.8266 + endloop + endfacet + facet normal -0.0461264 -0.386803 0.921008 + outer loop + vertex 420.607 64.4844 34.7151 + vertex 412.71 62.6953 33.5682 + vertex 421.733 62.2346 33.8266 + endloop + endfacet + facet normal -0.0443774 -0.342826 0.93835 + outer loop + vertex 421.733 62.2346 33.8266 + vertex 412.71 62.6953 33.5682 + vertex 415.046 60.4604 32.8621 + endloop + endfacet + facet normal -0.12153 -0.339013 0.932899 + outer loop + vertex 416.925 72.7282 37.4966 + vertex 410.738 71.145 36.1153 + vertex 418.164 69.6949 36.5557 + endloop + endfacet + facet normal -0.112226 -0.285651 0.95174 + outer loop + vertex 418.164 69.6949 36.5557 + vertex 410.738 71.145 36.1153 + vertex 411.34 67.8094 35.1851 + endloop + endfacet + facet normal -0.158006 -0.408114 0.899153 + outer loop + vertex 422.392 73.9554 39.0143 + vertex 416.925 72.7282 37.4966 + vertex 424.046 71.1264 38.0209 + endloop + endfacet + facet normal -0.146282 -0.347092 0.926352 + outer loop + vertex 424.046 71.1264 38.0209 + vertex 416.925 72.7282 37.4966 + vertex 418.164 69.6949 36.5557 + endloop + endfacet + facet normal -0.121022 -0.422238 0.89837 + outer loop + vertex 424.046 71.1264 38.0209 + vertex 418.164 69.6949 36.5557 + vertex 425.643 68.5037 37.0033 + endloop + endfacet + facet normal -0.113697 -0.366879 0.923295 + outer loop + vertex 425.643 68.5037 37.0033 + vertex 418.164 69.6949 36.5557 + vertex 419.497 66.9493 35.6289 + endloop + endfacet + facet normal -0.0882135 -0.356772 0.930017 + outer loop + vertex 418.164 69.6949 36.5557 + vertex 411.34 67.8094 35.1851 + vertex 419.497 66.9493 35.6289 + endloop + endfacet + facet normal -0.0851833 -0.321248 0.943156 + outer loop + vertex 419.497 66.9493 35.6289 + vertex 411.34 67.8094 35.1851 + vertex 413.323 65.2904 34.5062 + endloop + endfacet + facet normal -0.231492 -0.363318 0.902447 + outer loop + vertex 418.96 80.2476 40.8263 + vertex 414.052 79.278 39.1769 + vertex 420.68 76.9855 39.9542 + endloop + endfacet + facet normal -0.195399 -0.389581 0.900026 + outer loop + vertex 420.68 76.9855 39.9542 + vertex 415.544 75.9232 38.3792 + vertex 422.392 73.9554 39.0143 + endloop + endfacet + facet normal -0.351386 -0.221004 0.909772 + outer loop + vertex 412.862 95.558 43.3264 + vertex 408.482 94.6504 41.4143 + vertex 414.257 91.4408 42.8651 + endloop + endfacet + facet normal -0.341052 -0.198287 0.918894 + outer loop + vertex 414.257 91.4408 42.8651 + vertex 408.482 94.6504 41.4143 + vertex 409.765 90.5211 40.9993 + endloop + endfacet + facet normal -0.326278 -0.253641 0.910609 + outer loop + vertex 414.257 91.4408 42.8651 + vertex 409.765 90.5211 40.9993 + vertex 415.733 87.4921 42.294 + endloop + endfacet + facet normal -0.315009 -0.226736 0.921607 + outer loop + vertex 415.733 87.4921 42.294 + vertex 409.765 90.5211 40.9993 + vertex 411.12 86.5706 40.4904 + endloop + endfacet + facet normal -0.390897 -0.170909 0.904428 + outer loop + vertex 410.27 104.169 43.9616 + vertex 406.084 103.301 41.9888 + vertex 411.539 99.8079 43.6861 + endloop + endfacet + facet normal -0.382384 -0.154419 0.911009 + outer loop + vertex 411.539 99.8079 43.6861 + vertex 406.084 103.301 41.9888 + vertex 407.262 98.9202 41.7403 + endloop + endfacet + facet normal -0.372852 -0.192909 0.907616 + outer loop + vertex 411.539 99.8079 43.6861 + vertex 407.262 98.9202 41.7403 + vertex 412.862 95.558 43.3264 + endloop + endfacet + facet normal -0.363542 -0.173813 0.915219 + outer loop + vertex 412.862 95.558 43.3264 + vertex 407.262 98.9202 41.7403 + vertex 408.482 94.6504 41.4143 + endloop + endfacet + facet normal -0.416335 -0.136197 0.898953 + outer loop + vertex 407.888 113.124 44.3013 + vertex 403.83 112.283 42.2944 + vertex 409.057 108.618 44.16 + endloop + endfacet + facet normal -0.410348 -0.125466 0.903257 + outer loop + vertex 409.057 108.618 44.16 + vertex 403.83 112.283 42.2944 + vertex 404.939 107.767 42.1711 + endloop + endfacet + facet normal -0.404586 -0.150499 0.902031 + outer loop + vertex 409.057 108.618 44.16 + vertex 404.939 107.767 42.1711 + vertex 410.27 104.169 43.9616 + endloop + endfacet + facet normal -0.398472 -0.139189 0.906558 + outer loop + vertex 410.27 104.169 43.9616 + vertex 404.939 107.767 42.1711 + vertex 406.084 103.301 41.9888 + endloop + endfacet + facet normal -0.428971 -0.1124 0.896298 + outer loop + vertex 405.715 122.092 44.4405 + vertex 401.724 121.256 42.4254 + vertex 406.776 117.634 44.3892 + endloop + endfacet + facet normal -0.426684 -0.108349 0.897887 + outer loop + vertex 406.776 117.634 44.3892 + vertex 401.724 121.256 42.4254 + vertex 402.755 116.796 42.3771 + endloop + endfacet + facet normal -0.423688 -0.121955 0.897561 + outer loop + vertex 406.776 117.634 44.3892 + vertex 402.755 116.796 42.3771 + vertex 407.888 113.124 44.3013 + endloop + endfacet + facet normal -0.420721 -0.116711 0.899651 + outer loop + vertex 407.888 113.124 44.3013 + vertex 402.755 116.796 42.3771 + vertex 403.83 112.283 42.2944 + endloop + endfacet + facet normal -0.436548 -0.101638 0.893921 + outer loop + vertex 403.706 130.847 44.4757 + vertex 399.763 130.019 42.4563 + vertex 404.7 126.483 44.4648 + endloop + endfacet + facet normal -0.434841 -0.0985888 0.895094 + outer loop + vertex 404.7 126.483 44.4648 + vertex 399.763 130.019 42.4563 + vertex 400.734 125.65 42.4467 + endloop + endfacet + facet normal -0.433417 -0.105219 0.89503 + outer loop + vertex 404.7 126.483 44.4648 + vertex 400.734 125.65 42.4467 + vertex 405.715 122.092 44.4405 + endloop + endfacet + facet normal -0.431335 -0.101501 0.896464 + outer loop + vertex 405.715 122.092 44.4405 + vertex 400.734 125.65 42.4467 + vertex 401.724 121.256 42.4254 + endloop + endfacet + facet normal -0.441117 -0.0981408 0.892067 + outer loop + vertex 401.719 139.741 44.4735 + vertex 397.819 138.917 42.4542 + vertex 402.72 135.253 44.4746 + endloop + endfacet + facet normal -0.439428 -0.0952489 0.893214 + outer loop + vertex 402.72 135.253 44.4746 + vertex 397.819 138.917 42.4542 + vertex 398.797 134.428 42.4565 + endloop + endfacet + facet normal -0.438849 -0.0979739 0.893204 + outer loop + vertex 402.72 135.253 44.4746 + vertex 398.797 134.428 42.4565 + vertex 403.706 130.847 44.4757 + endloop + endfacet + facet normal -0.437744 -0.0960344 0.893956 + outer loop + vertex 403.706 130.847 44.4757 + vertex 398.797 134.428 42.4565 + vertex 399.763 130.019 42.4563 + endloop + endfacet + facet normal -0.4451 -0.0987516 0.890019 + outer loop + vertex 399.702 148.851 44.4742 + vertex 395.845 148.033 42.4548 + vertex 400.709 144.293 44.4725 + endloop + endfacet + facet normal -0.443452 -0.0960026 0.891142 + outer loop + vertex 400.709 144.293 44.4725 + vertex 395.845 148.033 42.4548 + vertex 396.83 143.473 42.4538 + endloop + endfacet + facet normal -0.443012 -0.0980707 0.891136 + outer loop + vertex 400.709 144.293 44.4725 + vertex 396.83 143.473 42.4538 + vertex 401.719 139.741 44.4735 + endloop + endfacet + facet normal -0.441627 -0.0957477 0.892075 + outer loop + vertex 401.719 139.741 44.4735 + vertex 396.83 143.473 42.4538 + vertex 397.819 138.917 42.4542 + endloop + endfacet + facet normal -0.449295 -0.0994641 0.887829 + outer loop + vertex 397.743 157.772 44.4735 + vertex 393.926 156.958 42.4505 + vertex 398.716 153.355 44.4713 + endloop + endfacet + facet normal -0.447155 -0.095787 0.889313 + outer loop + vertex 398.716 153.355 44.4713 + vertex 393.926 156.958 42.4505 + vertex 394.878 152.538 42.4533 + endloop + endfacet + facet normal -0.446858 -0.0971776 0.889311 + outer loop + vertex 398.716 153.355 44.4713 + vertex 394.878 152.538 42.4533 + vertex 399.702 148.851 44.4742 + endloop + endfacet + facet normal -0.445811 -0.0954157 0.890027 + outer loop + vertex 399.702 148.851 44.4742 + vertex 394.878 152.538 42.4533 + vertex 395.845 148.033 42.4548 + endloop + endfacet + facet normal -0.449123 -0.0999826 0.887858 + outer loop + vertex 395.815 166.428 44.4678 + vertex 392.003 165.614 42.448 + vertex 396.783 162.115 44.4714 + endloop + endfacet + facet normal -0.44879 -0.099392 0.888093 + outer loop + vertex 396.783 162.115 44.4714 + vertex 392.003 165.614 42.448 + vertex 392.968 161.3 42.4525 + endloop + endfacet + facet normal -0.448909 -0.0988368 0.888094 + outer loop + vertex 396.783 162.115 44.4714 + vertex 392.968 161.3 42.4525 + vertex 397.743 157.772 44.4735 + endloop + endfacet + facet normal -0.449287 -0.0995001 0.887829 + outer loop + vertex 397.743 157.772 44.4735 + vertex 392.968 161.3 42.4525 + vertex 393.926 156.958 42.4505 + endloop + endfacet + facet normal -0.45048 -0.102281 0.886908 + outer loop + vertex 393.794 175.196 44.4675 + vertex 390.01 174.38 42.4517 + vertex 394.811 170.775 44.4742 + endloop + endfacet + facet normal -0.450005 -0.10146 0.887244 + outer loop + vertex 394.811 170.775 44.4742 + vertex 390.01 174.38 42.4517 + vertex 391.009 169.96 42.4528 + endloop + endfacet + facet normal -0.449209 -0.105114 0.887221 + outer loop + vertex 394.811 170.775 44.4742 + vertex 391.009 169.96 42.4528 + vertex 395.815 166.428 44.4678 + endloop + endfacet + facet normal -0.448343 -0.103583 0.887839 + outer loop + vertex 395.815 166.428 44.4678 + vertex 391.009 169.96 42.4528 + vertex 392.003 165.614 42.448 + endloop + endfacet + facet normal -0.45632 -0.0923359 0.885012 + outer loop + vertex 391.778 184.225 44.4082 + vertex 388.081 183.403 42.4159 + vertex 392.769 179.693 44.446 + endloop + endfacet + facet normal -0.454116 -0.0887294 0.886513 + outer loop + vertex 392.769 179.693 44.446 + vertex 388.081 183.403 42.4159 + vertex 389.022 178.874 42.445 + endloop + endfacet + facet normal -0.451947 -0.0987615 0.886561 + outer loop + vertex 392.769 179.693 44.446 + vertex 389.022 178.874 42.445 + vertex 393.794 175.196 44.4675 + endloop + endfacet + facet normal -0.451432 -0.0978959 0.886919 + outer loop + vertex 393.794 175.196 44.4675 + vertex 389.022 178.874 42.445 + vertex 390.01 174.38 42.4517 + endloop + endfacet + facet normal -0.476781 -0.0472969 0.877749 + outer loop + vertex 390.721 193.544 44.5318 + vertex 386.951 192.696 42.4386 + vertex 390.968 188.799 44.4106 + endloop + endfacet + facet normal -0.470566 -0.0389902 0.881503 + outer loop + vertex 390.968 188.799 44.4106 + vertex 386.951 192.696 42.4386 + vertex 387.264 187.967 42.3963 + endloop + endfacet + facet normal -0.461753 -0.0822576 0.883186 + outer loop + vertex 390.968 188.799 44.4106 + vertex 387.264 187.967 42.3963 + vertex 391.778 184.225 44.4082 + endloop + endfacet + facet normal -0.459305 -0.0784302 0.88481 + outer loop + vertex 391.778 184.225 44.4082 + vertex 387.264 187.967 42.3963 + vertex 388.081 183.403 42.4159 + endloop + endfacet + facet normal 0.0337863 -0.377028 0.925585 + outer loop + vertex 421.956 52.1178 29.6006 + vertex 404.678 48.2685 28.6633 + vertex 418.518 49.0769 28.4874 + endloop + endfacet + facet normal 0.0183089 -0.345856 0.938109 + outer loop + vertex 417.198 52.9616 30.0046 + vertex 405.97 51.4541 29.6679 + vertex 421.956 52.1178 29.6006 + endloop + endfacet + facet normal 0.0192028 -0.351998 0.935804 + outer loop + vertex 417.198 52.9616 30.0046 + vertex 415.713 54.345 30.5554 + vertex 405.97 51.4541 29.6679 + endloop + endfacet + facet normal 0.00143393 -0.358575 0.9335 + outer loop + vertex 416.739 56.3917 31.34 + vertex 404.519 55.0584 30.8466 + vertex 415.713 54.345 30.5554 + endloop + endfacet + facet normal -5.69603e-05 -0.346583 0.938019 + outer loop + vertex 416.739 56.3917 31.34 + vertex 414.435 58.2056 32.01 + vertex 404.519 55.0584 30.8466 + endloop + endfacet + facet normal -0.0246538 -0.347544 0.937339 + outer loop + vertex 415.046 60.4604 32.8621 + vertex 403.241 59.5145 32.2009 + vertex 414.435 58.2056 32.01 + endloop + endfacet + facet normal -0.0267628 -0.326462 0.944831 + outer loop + vertex 415.046 60.4604 32.8621 + vertex 412.71 62.6953 33.5682 + vertex 403.241 59.5145 32.2009 + endloop + endfacet + facet normal -0.060722 -0.326584 0.943216 + outer loop + vertex 413.323 65.2904 34.5062 + vertex 401.956 64.9665 33.6623 + vertex 412.71 62.6953 33.5682 + endloop + endfacet + facet normal -0.0933117 -0.283028 0.954562 + outer loop + vertex 410.738 71.145 36.1153 + vertex 403.576 69.2287 34.8469 + vertex 411.34 67.8094 35.1851 + endloop + endfacet + facet normal -0.061874 -0.304849 0.950389 + outer loop + vertex 413.323 65.2904 34.5062 + vertex 411.34 67.8094 35.1851 + vertex 401.956 64.9665 33.6623 + endloop + endfacet + facet normal -0.047433 -0.395708 0.917151 + outer loop + vertex -406.588 46.5443 28.0635 + vertex -419.137 50.7388 29.2242 + vertex -421.669 49.5758 28.5915 + endloop + endfacet + facet normal -0.0399052 -0.388445 0.920607 + outer loop + vertex -404.372 47.9647 28.6937 + vertex -420.114 53.662 30.4153 + vertex -419.137 50.7388 29.2242 + endloop + endfacet + facet normal -0.0237537 -0.370563 0.928503 + outer loop + vertex -403.651 50.6771 29.6452 + vertex -419.258 57.5369 31.9836 + vertex -420.114 53.662 30.4153 + endloop + endfacet + facet normal 0.00904531 -0.307233 0.951591 + outer loop + vertex -402.31 54.0346 30.6918 + vertex -413.571 59.9652 32.7136 + vertex -419.258 57.5369 31.9836 + endloop + endfacet + facet normal 0.0210952 -0.31527 0.948768 + outer loop + vertex -413.571 59.9652 32.7136 + vertex -401.546 58.446 31.9414 + vertex -413.242 63.4879 33.8769 + endloop + endfacet + facet normal -0.0348611 -0.417989 0.907783 + outer loop + vertex -419.137 50.7388 29.2242 + vertex -432.23 53.34 29.9191 + vertex -421.669 49.5758 28.5915 + endloop + endfacet + facet normal -0.040176 -0.430716 0.901593 + outer loop + vertex -421.669 49.5758 28.5915 + vertex -432.23 53.34 29.9191 + vertex -437.986 53.2889 29.6382 + endloop + endfacet + facet normal -0.0253831 -0.43404 0.900536 + outer loop + vertex -432.324 56.8887 31.6263 + vertex -430.948 54.8302 30.6729 + vertex -420.114 53.662 30.4153 + endloop + endfacet + facet normal -0.0366164 -0.42583 0.904062 + outer loop + vertex -432.23 53.34 29.9191 + vertex -419.137 50.7388 29.2242 + vertex -430.948 54.8302 30.6729 + endloop + endfacet + facet normal -0.0193082 -0.382792 0.923633 + outer loop + vertex -419.137 50.7388 29.2242 + vertex -420.114 53.662 30.4153 + vertex -430.948 54.8302 30.6729 + endloop + endfacet + facet normal -0.00091348 -0.443413 0.896317 + outer loop + vertex -430.536 60.4368 33.4067 + vertex -430.042 58.2228 32.312 + vertex -419.258 57.5369 31.9836 + endloop + endfacet + facet normal -0.0228199 -0.425833 0.904514 + outer loop + vertex -432.324 56.8887 31.6263 + vertex -420.114 53.662 30.4153 + vertex -430.042 58.2228 32.312 + endloop + endfacet + facet normal 0.00429683 -0.375995 0.926612 + outer loop + vertex -420.114 53.662 30.4153 + vertex -419.258 57.5369 31.9836 + vertex -430.042 58.2228 32.312 + endloop + endfacet + facet normal 0.00236071 -0.433137 0.901325 + outer loop + vertex -430.536 60.4368 33.4067 + vertex -419.258 57.5369 31.9836 + vertex -428.902 62.129 34.2157 + endloop + endfacet + facet normal -0.0321339 -0.545322 0.83761 + outer loop + vertex -451.409 58.2275 32.0795 + vertex -449.605 56.6748 31.1378 + vertex -443.566 56.0474 30.9611 + endloop + endfacet + facet normal -0.0380204 -0.493583 0.868867 + outer loop + vertex -432.23 53.34 29.9191 + vertex -443.566 56.0474 30.9611 + vertex -437.986 53.2889 29.6382 + endloop + endfacet + facet normal -0.0543286 -0.554296 0.830545 + outer loop + vertex -450.561 55.8553 30.5284 + vertex -437.986 53.2889 29.6382 + vertex -449.605 56.6748 31.1378 + endloop + endfacet + facet normal -0.022961 -0.469677 0.88254 + outer loop + vertex -443.566 56.0474 30.9611 + vertex -449.605 56.6748 31.1378 + vertex -437.986 53.2889 29.6382 + endloop + endfacet + facet normal 0.0101496 -0.502406 0.864572 + outer loop + vertex -439.843 58.2866 32.3341 + vertex -447.651 60.0656 33.4595 + vertex -440.836 56.8208 31.494 + endloop + endfacet + facet normal -0.0266115 -0.558219 0.829267 + outer loop + vertex -440.836 56.8208 31.494 + vertex -447.651 60.0656 33.4595 + vertex -449.365 58.88 32.6064 + endloop + endfacet + facet normal 0.00833978 -0.415641 0.909491 + outer loop + vertex -432.324 56.8887 31.6263 + vertex -439.843 58.2866 32.3341 + vertex -430.948 54.8302 30.6729 + endloop + endfacet + facet normal -0.0248974 -0.484365 0.874511 + outer loop + vertex -430.948 54.8302 30.6729 + vertex -439.843 58.2866 32.3341 + vertex -440.836 56.8208 31.494 + endloop + endfacet + facet normal -0.0143799 -0.441464 0.897163 + outer loop + vertex -430.948 54.8302 30.6729 + vertex -440.836 56.8208 31.494 + vertex -432.23 53.34 29.9191 + endloop + endfacet + facet normal -0.0345182 -0.481561 0.875732 + outer loop + vertex -432.23 53.34 29.9191 + vertex -440.836 56.8208 31.494 + vertex -443.566 56.0474 30.9611 + endloop + endfacet + facet normal -0.0164759 -0.527212 0.849574 + outer loop + vertex -440.836 56.8208 31.494 + vertex -449.365 58.88 32.6064 + vertex -443.566 56.0474 30.9611 + endloop + endfacet + facet normal -0.036316 -0.556493 0.830058 + outer loop + vertex -443.566 56.0474 30.9611 + vertex -449.365 58.88 32.6064 + vertex -451.409 58.2275 32.0795 + endloop + endfacet + facet normal 0.0437492 -0.532995 0.844987 + outer loop + vertex -437.304 61.5309 34.2271 + vertex -444.289 63.0475 35.5453 + vertex -438.746 59.8715 33.255 + endloop + endfacet + facet normal 0.00749391 -0.576256 0.817235 + outer loop + vertex -438.746 59.8715 33.255 + vertex -444.289 63.0475 35.5453 + vertex -446.075 61.5066 34.4752 + endloop + endfacet + facet normal 0.0384955 -0.436002 0.899122 + outer loop + vertex -430.536 60.4368 33.4067 + vertex -437.304 61.5309 34.2271 + vertex -430.042 58.2228 32.312 + endloop + endfacet + facet normal -0.00193641 -0.504194 0.863588 + outer loop + vertex -430.042 58.2228 32.312 + vertex -437.304 61.5309 34.2271 + vertex -438.746 59.8715 33.255 + endloop + endfacet + facet normal 0.00734238 -0.467007 0.884223 + outer loop + vertex -430.042 58.2228 32.312 + vertex -438.746 59.8715 33.255 + vertex -432.324 56.8887 31.6263 + endloop + endfacet + facet normal -0.0106832 -0.496837 0.867778 + outer loop + vertex -432.324 56.8887 31.6263 + vertex -438.746 59.8715 33.255 + vertex -439.843 58.2866 32.3341 + endloop + endfacet + facet normal 0.027323 -0.516289 0.855979 + outer loop + vertex -438.746 59.8715 33.255 + vertex -446.075 61.5066 34.4752 + vertex -439.843 58.2866 32.3341 + endloop + endfacet + facet normal -0.0108392 -0.568132 0.822866 + outer loop + vertex -439.843 58.2866 32.3341 + vertex -446.075 61.5066 34.4752 + vertex -447.651 60.0656 33.4595 + endloop + endfacet + facet normal 0.0996089 -0.539551 0.83604 + outer loop + vertex -434.285 65.3242 36.3659 + vertex -440.149 66.5613 37.8629 + vertex -435.802 63.3509 35.2732 + endloop + endfacet + facet normal 0.0527608 -0.582737 0.810946 + outer loop + vertex -435.802 63.3509 35.2732 + vertex -440.149 66.5613 37.8629 + vertex -442.266 64.7124 36.6721 + endloop + endfacet + facet normal 0.0417839 -0.508419 0.860096 + outer loop + vertex -428.902 62.129 34.2157 + vertex -434.285 65.3242 36.3659 + vertex -435.802 63.3509 35.2732 + endloop + endfacet + facet normal 0.0515998 -0.470831 0.880713 + outer loop + vertex -428.902 62.129 34.2157 + vertex -435.802 63.3509 35.2732 + vertex -430.536 60.4368 33.4067 + endloop + endfacet + facet normal 0.0214403 -0.511454 0.859043 + outer loop + vertex -430.536 60.4368 33.4067 + vertex -435.802 63.3509 35.2732 + vertex -437.304 61.5309 34.2271 + endloop + endfacet + facet normal 0.0682048 -0.538882 0.839616 + outer loop + vertex -435.802 63.3509 35.2732 + vertex -442.266 64.7124 36.6721 + vertex -437.304 61.5309 34.2271 + endloop + endfacet + facet normal 0.0268669 -0.582446 0.812425 + outer loop + vertex -437.304 61.5309 34.2271 + vertex -442.266 64.7124 36.6721 + vertex -444.289 63.0475 35.5453 + endloop + endfacet + facet normal 0.159877 -0.538759 0.82715 + outer loop + vertex -430.64 69.5886 38.494 + vertex -435.879 70.8204 40.3089 + vertex -432.635 67.3964 37.4517 + endloop + endfacet + facet normal 0.119758 -0.56675 0.81514 + outer loop + vertex -432.635 67.3964 37.4517 + vertex -435.879 70.8204 40.3089 + vertex -438.036 68.5973 39.0801 + endloop + endfacet + facet normal 0.134729 -0.469843 0.872408 + outer loop + vertex -425.098 68.3549 36.9738 + vertex -430.64 69.5886 38.494 + vertex -426.998 66.0264 36.0131 + endloop + endfacet + facet normal 0.0984645 -0.498979 0.861002 + outer loop + vertex -426.998 66.0264 36.0131 + vertex -430.64 69.5886 38.494 + vertex -432.635 67.3964 37.4517 + endloop + endfacet + facet normal 0.10055 -0.493473 0.86393 + outer loop + vertex -426.998 66.0264 36.0131 + vertex -432.635 67.3964 37.4517 + vertex -429.31 64.5332 35.4293 + endloop + endfacet + facet normal 0.130698 -0.539824 0.831569 + outer loop + vertex -432.635 67.3964 37.4517 + vertex -438.036 68.5973 39.0801 + vertex -434.285 65.3242 36.3659 + endloop + endfacet + facet normal 0.0861676 -0.575598 0.81318 + outer loop + vertex -434.285 65.3242 36.3659 + vertex -438.036 68.5973 39.0801 + vertex -440.149 66.5613 37.8629 + endloop + endfacet + facet normal 0.246055 -0.495558 0.832994 + outer loop + vertex -426.88 74.8932 40.7136 + vertex -431.549 75.9633 42.7292 + vertex -428.732 72.1114 39.6056 + endloop + endfacet + facet normal 0.197172 -0.526461 0.82702 + outer loop + vertex -428.732 72.1114 39.6056 + vertex -431.549 75.9633 42.7292 + vertex -433.709 73.2612 41.5241 + endloop + endfacet + facet normal 0.213988 -0.429229 0.87748 + outer loop + vertex -422.047 73.822 39.0108 + vertex -426.88 74.8932 40.7136 + vertex -423.597 71.0108 38.0137 + endloop + endfacet + facet normal 0.171197 -0.460799 0.870836 + outer loop + vertex -423.597 71.0108 38.0137 + vertex -426.88 74.8932 40.7136 + vertex -428.732 72.1114 39.6056 + endloop + endfacet + facet normal 0.177112 -0.444039 0.878328 + outer loop + vertex -423.597 71.0108 38.0137 + vertex -428.732 72.1114 39.6056 + vertex -425.098 68.3549 36.9738 + endloop + endfacet + facet normal 0.130773 -0.480903 0.866966 + outer loop + vertex -425.098 68.3549 36.9738 + vertex -428.732 72.1114 39.6056 + vertex -430.64 69.5886 38.494 + endloop + endfacet + facet normal 0.20077 -0.518166 0.831382 + outer loop + vertex -428.732 72.1114 39.6056 + vertex -433.709 73.2612 41.5241 + vertex -430.64 69.5886 38.494 + endloop + endfacet + facet normal 0.155936 -0.547829 0.821929 + outer loop + vertex -430.64 69.5886 38.494 + vertex -433.709 73.2612 41.5241 + vertex -435.879 70.8204 40.3089 + endloop + endfacet + facet normal 0.338162 -0.437449 0.833237 + outer loop + vertex -423.174 81.1746 42.7199 + vertex -427.343 82.1335 44.9152 + vertex -425.024 77.9081 41.7559 + endloop + endfacet + facet normal 0.294126 -0.463551 0.835829 + outer loop + vertex -425.024 77.9081 41.7559 + vertex -427.343 82.1335 44.9152 + vertex -429.426 78.9207 43.8665 + endloop + endfacet + facet normal 0.287112 -0.378895 0.879776 + outer loop + vertex -418.708 80.1507 40.8214 + vertex -423.174 81.1746 42.7199 + vertex -420.383 76.8494 39.9464 + endloop + endfacet + facet normal 0.251471 -0.40224 0.880321 + outer loop + vertex -420.383 76.8494 39.9464 + vertex -423.174 81.1746 42.7199 + vertex -425.024 77.9081 41.7559 + endloop + endfacet + facet normal 0.249236 -0.408328 0.878151 + outer loop + vertex -420.383 76.8494 39.9464 + vertex -425.024 77.9081 41.7559 + vertex -422.047 73.822 39.0108 + endloop + endfacet + facet normal 0.21242 -0.433537 0.875741 + outer loop + vertex -422.047 73.822 39.0108 + vertex -425.024 77.9081 41.7559 + vertex -426.88 74.8932 40.7136 + endloop + endfacet + facet normal 0.292157 -0.468175 0.83394 + outer loop + vertex -425.024 77.9081 41.7559 + vertex -429.426 78.9207 43.8665 + vertex -426.88 74.8932 40.7136 + endloop + endfacet + facet normal 0.245653 -0.496488 0.832559 + outer loop + vertex -426.88 74.8932 40.7136 + vertex -429.426 78.9207 43.8665 + vertex -431.549 75.9633 42.7292 + endloop + endfacet + facet normal 0.431583 -0.359292 0.827433 + outer loop + vertex -419.693 88.4027 44.3097 + vertex -423.467 89.2525 46.6475 + vertex -421.388 84.6806 43.5774 + endloop + endfacet + facet normal 0.392662 -0.38288 0.836193 + outer loop + vertex -421.388 84.6806 43.5774 + vertex -423.467 89.2525 46.6475 + vertex -425.344 85.5867 45.8501 + endloop + endfacet + facet normal 0.362532 -0.306401 0.880164 + outer loop + vertex -415.535 87.4833 42.2771 + vertex -419.693 88.4027 44.3097 + vertex -417.09 83.7025 41.6012 + endloop + endfacet + facet normal 0.332806 -0.325643 0.884984 + outer loop + vertex -417.09 83.7025 41.6012 + vertex -419.693 88.4027 44.3097 + vertex -421.388 84.6806 43.5774 + endloop + endfacet + facet normal 0.327064 -0.342401 0.88079 + outer loop + vertex -417.09 83.7025 41.6012 + vertex -421.388 84.6806 43.5774 + vertex -418.708 80.1507 40.8214 + endloop + endfacet + facet normal 0.292079 -0.365041 0.883988 + outer loop + vertex -418.708 80.1507 40.8214 + vertex -421.388 84.6806 43.5774 + vertex -423.174 81.1746 42.7199 + endloop + endfacet + facet normal 0.385938 -0.399981 0.831305 + outer loop + vertex -421.388 84.6806 43.5774 + vertex -425.344 85.5867 45.8501 + vertex -423.174 81.1746 42.7199 + endloop + endfacet + facet normal 0.343153 -0.425373 0.837439 + outer loop + vertex -423.174 81.1746 42.7199 + vertex -425.344 85.5867 45.8501 + vertex -427.343 82.1335 44.9152 + endloop + endfacet + facet normal 0.501654 -0.284013 0.817117 + outer loop + vertex -416.578 96.4035 45.4128 + vertex -420.101 97.1379 47.8309 + vertex -418.087 92.3197 44.92 + endloop + endfacet + facet normal 0.475984 -0.300437 0.826545 + outer loop + vertex -418.087 92.3197 44.92 + vertex -420.101 97.1379 47.8309 + vertex -421.725 93.1087 47.3019 + endloop + endfacet + facet normal 0.428369 -0.238106 0.871668 + outer loop + vertex -412.706 95.596 43.2895 + vertex -416.578 96.4035 45.4128 + vertex -414.08 91.4601 42.8351 + endloop + endfacet + facet normal 0.402733 -0.254932 0.8791 + outer loop + vertex -414.08 91.4601 42.8351 + vertex -416.578 96.4035 45.4128 + vertex -418.087 92.3197 44.92 + endloop + endfacet + facet normal 0.398578 -0.268836 0.876848 + outer loop + vertex -414.08 91.4601 42.8351 + vertex -418.087 92.3197 44.92 + vertex -415.535 87.4833 42.2771 + endloop + endfacet + facet normal 0.368233 -0.288643 0.883793 + outer loop + vertex -415.535 87.4833 42.2771 + vertex -418.087 92.3197 44.92 + vertex -419.693 88.4027 44.3097 + endloop + endfacet + facet normal 0.469209 -0.320543 0.822858 + outer loop + vertex -418.087 92.3197 44.92 + vertex -421.725 93.1087 47.3019 + vertex -419.693 88.4027 44.3097 + endloop + endfacet + facet normal 0.438862 -0.339445 0.831972 + outer loop + vertex -419.693 88.4027 44.3097 + vertex -421.725 93.1087 47.3019 + vertex -423.467 89.2525 46.6475 + endloop + endfacet + facet normal 0.552808 -0.224002 0.802637 + outer loop + vertex -413.823 104.966 46.086 + vertex -417.158 105.639 48.5703 + vertex -415.162 100.626 45.7969 + endloop + endfacet + facet normal 0.536481 -0.234886 0.810565 + outer loop + vertex -415.162 100.626 45.7969 + vertex -417.158 105.639 48.5703 + vertex -418.573 101.322 48.2562 + endloop + endfacet + facet normal 0.471013 -0.189213 0.861594 + outer loop + vertex -410.148 104.214 43.9117 + vertex -413.823 104.966 46.086 + vertex -411.406 99.854 43.6419 + endloop + endfacet + facet normal 0.456688 -0.198651 0.867164 + outer loop + vertex -411.406 99.854 43.6419 + vertex -413.823 104.966 46.086 + vertex -415.162 100.626 45.7969 + endloop + endfacet + facet normal 0.453664 -0.210198 0.866029 + outer loop + vertex -411.406 99.854 43.6419 + vertex -415.162 100.626 45.7969 + vertex -412.706 95.596 43.2895 + endloop + endfacet + facet normal 0.432196 -0.224365 0.873422 + outer loop + vertex -412.706 95.596 43.2895 + vertex -415.162 100.626 45.7969 + vertex -416.578 96.4035 45.4128 + endloop + endfacet + facet normal 0.531651 -0.25182 0.808662 + outer loop + vertex -415.162 100.626 45.7969 + vertex -418.573 101.322 48.2562 + vertex -416.578 96.4035 45.4128 + endloop + endfacet + facet normal 0.506533 -0.268236 0.819435 + outer loop + vertex -416.578 96.4035 45.4128 + vertex -418.573 101.322 48.2562 + vertex -420.101 97.1379 47.8309 + endloop + endfacet + facet normal 0.582793 -0.18252 0.791857 + outer loop + vertex -411.339 113.903 46.4423 + vertex -414.554 114.565 48.9607 + vertex -412.55 109.404 46.2962 + endloop + endfacet + facet normal 0.573457 -0.188884 0.797163 + outer loop + vertex -412.55 109.404 46.2962 + vertex -414.554 114.565 48.9607 + vertex -415.815 110.069 48.803 + endloop + endfacet + facet normal 0.498755 -0.152715 0.853183 + outer loop + vertex -407.786 113.177 44.235 + vertex -411.339 113.903 46.4423 + vertex -408.942 108.666 44.1033 + endloop + endfacet + facet normal 0.488728 -0.15935 0.85776 + outer loop + vertex -408.942 108.666 44.1033 + vertex -411.339 113.903 46.4423 + vertex -412.55 109.404 46.2962 + endloop + endfacet + facet normal 0.486495 -0.168718 0.857238 + outer loop + vertex -408.942 108.666 44.1033 + vertex -412.55 109.404 46.2962 + vertex -410.148 104.214 43.9117 + endloop + endfacet + facet normal 0.474083 -0.176894 0.862528 + outer loop + vertex -410.148 104.214 43.9117 + vertex -412.55 109.404 46.2962 + vertex -413.823 104.966 46.086 + endloop + endfacet + facet normal 0.570303 -0.201374 0.796369 + outer loop + vertex -412.55 109.404 46.2962 + vertex -415.815 110.069 48.803 + vertex -413.823 104.966 46.086 + endloop + endfacet + facet normal 0.556333 -0.210775 0.803783 + outer loop + vertex -413.823 104.966 46.086 + vertex -415.815 110.069 48.803 + vertex -417.158 105.639 48.5703 + endloop + endfacet + facet normal 0.598616 -0.155231 0.785851 + outer loop + vertex -409.116 122.857 46.5902 + vertex -412.264 123.507 49.1172 + vertex -410.197 118.406 46.5348 + endloop + endfacet + facet normal 0.59299 -0.159259 0.789304 + outer loop + vertex -410.197 118.406 46.5348 + vertex -412.264 123.507 49.1172 + vertex -413.376 119.063 49.0558 + endloop + endfacet + facet normal 0.513031 -0.12981 0.848498 + outer loop + vertex -405.627 122.147 44.3722 + vertex -409.116 122.857 46.5902 + vertex -406.677 117.688 44.3248 + endloop + endfacet + facet normal 0.507187 -0.133832 0.851382 + outer loop + vertex -406.677 117.688 44.3248 + vertex -409.116 122.857 46.5902 + vertex -410.197 118.406 46.5348 + endloop + endfacet + facet normal 0.505545 -0.141214 0.851166 + outer loop + vertex -406.677 117.688 44.3248 + vertex -410.197 118.406 46.5348 + vertex -407.786 113.177 44.235 + endloop + endfacet + facet normal 0.500635 -0.14451 0.853511 + outer loop + vertex -407.786 113.177 44.235 + vertex -410.197 118.406 46.5348 + vertex -411.339 113.903 46.4423 + endloop + endfacet + facet normal 0.591379 -0.166198 0.789081 + outer loop + vertex -410.197 118.406 46.5348 + vertex -413.376 119.063 49.0558 + vertex -411.339 113.903 46.4423 + endloop + endfacet + facet normal 0.585789 -0.170092 0.792414 + outer loop + vertex -411.339 113.903 46.4423 + vertex -413.376 119.063 49.0558 + vertex -414.554 114.565 48.9607 + endloop + endfacet + facet normal 0.607635 -0.141872 0.781443 + outer loop + vertex -407.075 131.606 46.6283 + vertex -410.188 132.253 49.1662 + vertex -408.082 127.243 46.6191 + endloop + endfacet + facet normal 0.603418 -0.14501 0.784129 + outer loop + vertex -408.082 127.243 46.6191 + vertex -410.188 132.253 49.1662 + vertex -411.214 127.889 49.1487 + endloop + endfacet + facet normal 0.519225 -0.120789 0.846059 + outer loop + vertex -403.621 130.902 44.4079 + vertex -407.075 131.606 46.6283 + vertex -404.615 126.538 44.3954 + endloop + endfacet + facet normal 0.518354 -0.121408 0.846504 + outer loop + vertex -404.615 126.538 44.3954 + vertex -407.075 131.606 46.6283 + vertex -408.082 127.243 46.6191 + endloop + endfacet + facet normal 0.517853 -0.123763 0.84647 + outer loop + vertex -404.615 126.538 44.3954 + vertex -408.082 127.243 46.6191 + vertex -405.627 122.147 44.3722 + endloop + endfacet + facet normal 0.513708 -0.126683 0.848561 + outer loop + vertex -405.627 122.147 44.3722 + vertex -408.082 127.243 46.6191 + vertex -409.116 122.857 46.5902 + endloop + endfacet + facet normal 0.602916 -0.14729 0.78409 + outer loop + vertex -408.082 127.243 46.6191 + vertex -411.214 127.889 49.1487 + vertex -409.116 122.857 46.5902 + endloop + endfacet + facet normal 0.599903 -0.149507 0.78598 + outer loop + vertex -409.116 122.857 46.5902 + vertex -411.214 127.889 49.1487 + vertex -412.264 123.507 49.1172 + endloop + endfacet + facet normal 0.611062 -0.139724 0.779154 + outer loop + vertex -405.046 140.498 46.6309 + vertex -408.131 141.153 49.1682 + vertex -406.069 136.011 46.6287 + endloop + endfacet + facet normal 0.608524 -0.141558 0.780807 + outer loop + vertex -406.069 136.011 46.6287 + vertex -408.131 141.153 49.1682 + vertex -409.172 136.662 49.1649 + endloop + endfacet + facet normal 0.526049 -0.116313 0.842463 + outer loop + vertex -401.634 139.798 44.4036 + vertex -405.046 140.498 46.6309 + vertex -402.632 135.308 44.4074 + endloop + endfacet + facet normal 0.521627 -0.119363 0.844783 + outer loop + vertex -402.632 135.308 44.4074 + vertex -405.046 140.498 46.6309 + vertex -406.069 136.011 46.6287 + endloop + endfacet + facet normal 0.522125 -0.117002 0.844806 + outer loop + vertex -402.632 135.308 44.4074 + vertex -406.069 136.011 46.6287 + vertex -403.621 130.902 44.4079 + endloop + endfacet + facet normal 0.519658 -0.118739 0.846083 + outer loop + vertex -403.621 130.902 44.4079 + vertex -406.069 136.011 46.6287 + vertex -407.075 131.606 46.6283 + endloop + endfacet + facet normal 0.60905 -0.139146 0.780831 + outer loop + vertex -406.069 136.011 46.6287 + vertex -409.172 136.662 49.1649 + vertex -407.075 131.606 46.6283 + endloop + endfacet + facet normal 0.608069 -0.139871 0.781465 + outer loop + vertex -407.075 131.606 46.6283 + vertex -409.172 136.662 49.1649 + vertex -410.188 132.253 49.1662 + endloop + endfacet + facet normal 0.613801 -0.139692 0.777004 + outer loop + vertex -402.983 149.61 46.6325 + vertex -406.04 150.262 49.1652 + vertex -404.016 145.051 46.6296 + endloop + endfacet + facet normal 0.611741 -0.141153 0.778363 + outer loop + vertex -404.016 145.051 46.6296 + vertex -406.04 150.262 49.1652 + vertex -407.089 145.706 49.1633 + endloop + endfacet + facet normal 0.528274 -0.118012 0.840833 + outer loop + vertex -399.598 148.912 44.408 + vertex -402.983 149.61 46.6325 + vertex -400.614 144.352 44.4067 + endloop + endfacet + facet normal 0.525696 -0.119753 0.842201 + outer loop + vertex -400.614 144.352 44.4067 + vertex -402.983 149.61 46.6325 + vertex -404.016 145.051 46.6296 + endloop + endfacet + facet normal 0.526003 -0.118301 0.842215 + outer loop + vertex -400.614 144.352 44.4067 + vertex -404.016 145.051 46.6296 + vertex -401.634 139.798 44.4036 + endloop + endfacet + facet normal 0.525569 -0.118595 0.842445 + outer loop + vertex -401.634 139.798 44.4036 + vertex -404.016 145.051 46.6296 + vertex -405.046 140.498 46.6309 + endloop + endfacet + facet normal 0.612379 -0.138241 0.778384 + outer loop + vertex -404.016 145.051 46.6296 + vertex -407.089 145.706 49.1633 + vertex -405.046 140.498 46.6309 + endloop + endfacet + facet normal 0.611203 -0.139079 0.779159 + outer loop + vertex -405.046 140.498 46.6309 + vertex -407.089 145.706 49.1633 + vertex -408.131 141.153 49.1682 + endloop + endfacet + facet normal 0.614669 -0.138392 0.77655 + outer loop + vertex -400.968 158.53 46.6257 + vertex -404.009 159.173 49.1468 + vertex -401.967 154.115 46.6291 + endloop + endfacet + facet normal 0.614813 -0.138287 0.776455 + outer loop + vertex -401.967 154.115 46.6291 + vertex -404.009 159.173 49.1468 + vertex -405.014 154.761 49.1574 + endloop + endfacet + facet normal 0.532732 -0.117104 0.838143 + outer loop + vertex -397.621 157.835 44.4007 + vertex -400.968 158.53 46.6257 + vertex -398.599 153.417 44.4053 + endloop + endfacet + facet normal 0.529793 -0.119149 0.839716 + outer loop + vertex -398.599 153.417 44.4053 + vertex -400.968 158.53 46.6257 + vertex -401.967 154.115 46.6291 + endloop + endfacet + facet normal 0.530232 -0.117075 0.839731 + outer loop + vertex -398.599 153.417 44.4053 + vertex -401.967 154.115 46.6291 + vertex -399.598 148.912 44.408 + endloop + endfacet + facet normal 0.528175 -0.11848 0.840829 + outer loop + vertex -399.598 148.912 44.408 + vertex -401.967 154.115 46.6291 + vertex -402.983 149.61 46.6325 + endloop + endfacet + facet normal 0.614858 -0.138079 0.776456 + outer loop + vertex -401.967 154.115 46.6291 + vertex -405.014 154.761 49.1574 + vertex -402.983 149.61 46.6325 + endloop + endfacet + facet normal 0.614022 -0.13868 0.77701 + outer loop + vertex -402.983 149.61 46.6325 + vertex -405.014 154.761 49.1574 + vertex -406.04 150.262 49.1652 + endloop + endfacet + facet normal 0.619074 -0.1389 0.772952 + outer loop + vertex -399.015 167.189 46.6084 + vertex -402.024 167.825 49.1328 + vertex -399.992 162.872 46.6151 + endloop + endfacet + facet normal 0.618912 -0.139021 0.77306 + outer loop + vertex -399.992 162.872 46.6151 + vertex -402.024 167.825 49.1328 + vertex -403.009 163.508 49.1448 + endloop + endfacet + facet normal 0.534946 -0.117175 0.836721 + outer loop + vertex -395.703 166.49 44.393 + vertex -399.015 167.189 46.6084 + vertex -396.657 162.175 44.3984 + endloop + endfacet + facet normal 0.532175 -0.119135 0.838211 + outer loop + vertex -396.657 162.175 44.3984 + vertex -399.015 167.189 46.6084 + vertex -399.992 162.872 46.6151 + endloop + endfacet + facet normal 0.532459 -0.117801 0.838219 + outer loop + vertex -396.657 162.175 44.3984 + vertex -399.992 162.872 46.6151 + vertex -397.621 157.835 44.4007 + endloop + endfacet + facet normal 0.532607 -0.117697 0.838139 + outer loop + vertex -397.621 157.835 44.4007 + vertex -399.992 162.872 46.6151 + vertex -400.968 158.53 46.6257 + endloop + endfacet + facet normal 0.619274 -0.137342 0.77307 + outer loop + vertex -399.992 162.872 46.6151 + vertex -403.009 163.508 49.1448 + vertex -400.968 158.53 46.6257 + endloop + endfacet + facet normal 0.614051 -0.141233 0.776528 + outer loop + vertex -400.968 158.53 46.6257 + vertex -403.009 163.508 49.1448 + vertex -404.009 159.173 49.1468 + endloop + endfacet + facet normal 0.627775 -0.136642 0.766308 + outer loop + vertex -397.05 175.981 46.5817 + vertex -400.02 176.628 49.1299 + vertex -398.035 171.545 46.5979 + endloop + endfacet + facet normal 0.621271 -0.141387 0.770734 + outer loop + vertex -398.035 171.545 46.5979 + vertex -400.02 176.628 49.1299 + vertex -401.028 172.185 49.1277 + endloop + endfacet + facet normal 0.539564 -0.114522 0.83412 + outer loop + vertex -393.785 175.273 44.3727 + vertex -397.05 175.981 46.5817 + vertex -394.747 170.842 44.3864 + endloop + endfacet + facet normal 0.53705 -0.11624 0.835503 + outer loop + vertex -394.747 170.842 44.3864 + vertex -397.05 175.981 46.5817 + vertex -398.035 171.545 46.5979 + endloop + endfacet + facet normal 0.536945 -0.116725 0.835503 + outer loop + vertex -394.747 170.842 44.3864 + vertex -398.035 171.545 46.5979 + vertex -395.703 166.49 44.393 + endloop + endfacet + facet normal 0.534709 -0.118286 0.836717 + outer loop + vertex -395.703 166.49 44.393 + vertex -398.035 171.545 46.5979 + vertex -399.015 167.189 46.6084 + endloop + endfacet + facet normal 0.621992 -0.138085 0.770752 + outer loop + vertex -398.035 171.545 46.5979 + vertex -401.028 172.185 49.1277 + vertex -399.015 167.189 46.6084 + endloop + endfacet + facet normal 0.618725 -0.140505 0.772941 + outer loop + vertex -399.015 167.189 46.6084 + vertex -401.028 172.185 49.1277 + vertex -402.024 167.825 49.1328 + endloop + endfacet + facet normal 0.636329 -0.130881 0.760234 + outer loop + vertex -395.103 185.022 46.5294 + vertex -398.062 185.68 49.12 + vertex -396.069 180.489 46.5576 + endloop + endfacet + facet normal 0.632326 -0.133813 0.763058 + outer loop + vertex -396.069 180.489 46.5576 + vertex -398.062 185.68 49.12 + vertex -399.027 181.14 49.1229 + endloop + endfacet + facet normal 0.540199 -0.110689 0.834226 + outer loop + vertex -391.827 184.291 44.3113 + vertex -395.103 185.022 46.5294 + vertex -392.81 179.774 44.3486 + endloop + endfacet + facet normal 0.541053 -0.110117 0.833748 + outer loop + vertex -392.81 179.774 44.3486 + vertex -395.103 185.022 46.5294 + vertex -396.069 180.489 46.5576 + endloop + endfacet + facet normal 0.540519 -0.112596 0.833763 + outer loop + vertex -392.81 179.774 44.3486 + vertex -396.069 180.489 46.5576 + vertex -393.785 175.273 44.3727 + endloop + endfacet + facet normal 0.539887 -0.113021 0.834115 + outer loop + vertex -393.785 175.273 44.3727 + vertex -396.069 180.489 46.5576 + vertex -397.05 175.981 46.5817 + endloop + endfacet + facet normal 0.632387 -0.133528 0.763057 + outer loop + vertex -396.069 180.489 46.5576 + vertex -399.027 181.14 49.1229 + vertex -397.05 175.981 46.5817 + endloop + endfacet + facet normal 0.627714 -0.13692 0.766308 + outer loop + vertex -397.05 175.981 46.5817 + vertex -399.027 181.14 49.1229 + vertex -400.02 176.628 49.1299 + endloop + endfacet + facet normal 0.646836 -0.082473 0.758156 + outer loop + vertex -393.722 194.229 46.6286 + vertex -396.697 194.917 49.241 + vertex -394.222 189.565 46.5476 + endloop + endfacet + facet normal 0.643623 -0.0851825 0.760588 + outer loop + vertex -394.222 189.565 46.5476 + vertex -396.697 194.917 49.241 + vertex -397.197 190.236 49.1406 + endloop + endfacet + facet normal 0.556435 -0.0657352 0.828287 + outer loop + vertex -390.354 193.461 44.3048 + vertex -393.722 194.229 46.6286 + vertex -390.914 188.813 44.3122 + endloop + endfacet + facet normal 0.546945 -0.0730862 0.833972 + outer loop + vertex -390.914 188.813 44.3122 + vertex -393.722 194.229 46.6286 + vertex -394.222 189.565 46.5476 + endloop + endfacet + facet normal 0.539418 -0.109074 0.834944 + outer loop + vertex -390.914 188.813 44.3122 + vertex -394.222 189.565 46.5476 + vertex -391.827 184.291 44.3113 + endloop + endfacet + facet normal 0.540749 -0.108155 0.834202 + outer loop + vertex -391.827 184.291 44.3113 + vertex -394.222 189.565 46.5476 + vertex -395.103 185.022 46.5294 + endloop + endfacet + facet normal 0.635414 -0.126215 0.761787 + outer loop + vertex -394.222 189.565 46.5476 + vertex -397.197 190.236 49.1406 + vertex -395.103 185.022 46.5294 + endloop + endfacet + facet normal 0.637692 -0.124488 0.760166 + outer loop + vertex -395.103 185.022 46.5294 + vertex -397.197 190.236 49.1406 + vertex -398.062 185.68 49.12 + endloop + endfacet + facet normal -0.0513912 -0.67732 0.733891 + outer loop + vertex -459.011 57.8767 31.5515 + vertex -466.772 59.803 32.7859 + vertex -460.292 57.7565 31.3509 + endloop + endfacet + facet normal -0.0665829 -0.705537 0.705538 + outer loop + vertex -460.292 57.7565 31.3509 + vertex -466.772 59.803 32.7859 + vertex -468.361 59.7471 32.5801 + endloop + endfacet + facet normal -0.0750204 -0.68189 0.727598 + outer loop + vertex -450.561 55.8553 30.5284 + vertex -459.011 57.8767 31.5515 + vertex -455.27 56.6034 30.744 + endloop + endfacet + facet normal -0.0576816 -0.65004 0.757707 + outer loop + vertex -455.27 56.6034 30.744 + vertex -459.011 57.8767 31.5515 + vertex -460.292 57.7565 31.3509 + endloop + endfacet + facet normal -0.000191526 -0.617588 0.786501 + outer loop + vertex -457.306 59.4698 32.8976 + vertex -464.558 61.1978 34.2527 + vertex -457.693 58.3783 32.0404 + endloop + endfacet + facet normal -0.0432643 -0.679804 0.732117 + outer loop + vertex -457.693 58.3783 32.0404 + vertex -464.558 61.1978 34.2527 + vertex -465.659 60.3191 33.3718 + endloop + endfacet + facet normal 0.0124966 -0.507873 0.861341 + outer loop + vertex -451.409 58.2275 32.0795 + vertex -457.306 59.4698 32.8976 + vertex -449.605 56.6748 31.1378 + endloop + endfacet + facet normal -0.0396966 -0.608408 0.792631 + outer loop + vertex -449.605 56.6748 31.1378 + vertex -457.306 59.4698 32.8976 + vertex -457.693 58.3783 32.0404 + endloop + endfacet + facet normal -0.0295899 -0.574029 0.8183 + outer loop + vertex -449.605 56.6748 31.1378 + vertex -457.693 58.3783 32.0404 + vertex -450.561 55.8553 30.5284 + endloop + endfacet + facet normal -0.0538086 -0.620804 0.782117 + outer loop + vertex -450.561 55.8553 30.5284 + vertex -457.693 58.3783 32.0404 + vertex -459.011 57.8767 31.5515 + endloop + endfacet + facet normal -0.0324516 -0.652534 0.757064 + outer loop + vertex -457.693 58.3783 32.0404 + vertex -465.659 60.3191 33.3718 + vertex -459.011 57.8767 31.5515 + endloop + endfacet + facet normal -0.0574802 -0.692429 0.719192 + outer loop + vertex -459.011 57.8767 31.5515 + vertex -465.659 60.3191 33.3718 + vertex -466.772 59.803 32.7859 + endloop + endfacet + facet normal 0.0220378 -0.670679 0.74142 + outer loop + vertex -454.737 61.8364 34.872 + vertex -461.274 63.5225 36.5915 + vertex -456.478 60.658 33.8577 + endloop + endfacet + facet normal -0.0129369 -0.701596 0.712457 + outer loop + vertex -456.478 60.658 33.8577 + vertex -461.274 63.5225 36.5915 + vertex -463.188 62.3209 35.3735 + endloop + endfacet + facet normal 0.0115176 -0.59494 0.803688 + outer loop + vertex -447.651 60.0656 33.4595 + vertex -454.737 61.8364 34.872 + vertex -449.365 58.88 32.6064 + endloop + endfacet + facet normal -0.0221611 -0.633164 0.773701 + outer loop + vertex -449.365 58.88 32.6064 + vertex -454.737 61.8364 34.872 + vertex -456.478 60.658 33.8577 + endloop + endfacet + facet normal -0.0115658 -0.60602 0.795365 + outer loop + vertex -449.365 58.88 32.6064 + vertex -456.478 60.658 33.8577 + vertex -451.409 58.2275 32.0795 + endloop + endfacet + facet normal -0.0215679 -0.619233 0.784911 + outer loop + vertex -451.409 58.2275 32.0795 + vertex -456.478 60.658 33.8577 + vertex -457.306 59.4698 32.8976 + endloop + endfacet + facet normal 0.0168764 -0.635505 0.771913 + outer loop + vertex -456.478 60.658 33.8577 + vertex -463.188 62.3209 35.3735 + vertex -457.306 59.4698 32.8976 + endloop + endfacet + facet normal -0.0285876 -0.688375 0.724792 + outer loop + vertex -457.306 59.4698 32.8976 + vertex -463.188 62.3209 35.3735 + vertex -464.558 61.1978 34.2527 + endloop + endfacet + facet normal 0.065603 -0.693647 0.717321 + outer loop + vertex -450.647 64.6256 37.2194 + vertex -456.428 66.1667 39.2384 + vertex -452.776 63.1729 36.0094 + endloop + endfacet + facet normal 0.0231348 -0.719934 0.693657 + outer loop + vertex -452.776 63.1729 36.0094 + vertex -456.428 66.1667 39.2384 + vertex -458.916 64.7939 37.8966 + endloop + endfacet + facet normal 0.0556888 -0.612287 0.788672 + outer loop + vertex -444.289 63.0475 35.5453 + vertex -450.647 64.6256 37.2194 + vertex -446.075 61.5066 34.4752 + endloop + endfacet + facet normal 0.0121456 -0.650423 0.759475 + outer loop + vertex -446.075 61.5066 34.4752 + vertex -450.647 64.6256 37.2194 + vertex -452.776 63.1729 36.0094 + endloop + endfacet + facet normal 0.0337366 -0.600155 0.799172 + outer loop + vertex -446.075 61.5066 34.4752 + vertex -452.776 63.1729 36.0094 + vertex -447.651 60.0656 33.4595 + endloop + endfacet + facet normal -0.00749263 -0.641695 0.766923 + outer loop + vertex -447.651 60.0656 33.4595 + vertex -452.776 63.1729 36.0094 + vertex -454.737 61.8364 34.872 + endloop + endfacet + facet normal 0.043408 -0.683686 0.728484 + outer loop + vertex -452.776 63.1729 36.0094 + vertex -458.916 64.7939 37.8966 + vertex -454.737 61.8364 34.872 + endloop + endfacet + facet normal -0.000813293 -0.715557 0.698554 + outer loop + vertex -454.737 61.8364 34.872 + vertex -458.916 64.7939 37.8966 + vertex -461.274 63.5225 36.5915 + endloop + endfacet + facet normal 0.124819 -0.70195 0.701203 + outer loop + vertex -445.857 67.9287 39.7598 + vertex -451.054 69.2959 42.0535 + vertex -448.332 66.1948 38.4646 + endloop + endfacet + facet normal 0.0777297 -0.724448 0.684933 + outer loop + vertex -448.332 66.1948 38.4646 + vertex -451.054 69.2959 42.0535 + vertex -453.805 67.6564 40.6315 + endloop + endfacet + facet normal 0.10823 -0.622925 0.774759 + outer loop + vertex -440.149 66.5613 37.8629 + vertex -445.857 67.9287 39.7598 + vertex -442.266 64.7124 36.6721 + endloop + endfacet + facet normal 0.0631622 -0.653556 0.754238 + outer loop + vertex -442.266 64.7124 36.6721 + vertex -445.857 67.9287 39.7598 + vertex -448.332 66.1948 38.4646 + endloop + endfacet + facet normal 0.078148 -0.62215 0.778988 + outer loop + vertex -442.266 64.7124 36.6721 + vertex -448.332 66.1948 38.4646 + vertex -444.289 63.0475 35.5453 + endloop + endfacet + facet normal 0.0367087 -0.653831 0.755749 + outer loop + vertex -444.289 63.0475 35.5453 + vertex -448.332 66.1948 38.4646 + vertex -450.647 64.6256 37.2194 + endloop + endfacet + facet normal 0.0935007 -0.699836 0.708158 + outer loop + vertex -448.332 66.1948 38.4646 + vertex -453.805 67.6564 40.6315 + vertex -450.647 64.6256 37.2194 + endloop + endfacet + facet normal 0.0467355 -0.724962 0.687202 + outer loop + vertex -450.647 64.6256 37.2194 + vertex -453.805 67.6564 40.6315 + vertex -456.428 66.1667 39.2384 + endloop + endfacet + facet normal 0.212037 -0.683144 0.698823 + outer loop + vertex -440.838 72.016 42.4425 + vertex -445.386 73.1687 44.9493 + vertex -443.331 69.8668 41.098 + endloop + endfacet + facet normal 0.155436 -0.707448 0.689461 + outer loop + vertex -443.331 69.8668 41.098 + vertex -445.386 73.1687 44.9493 + vertex -448.232 71.1247 43.4936 + endloop + endfacet + facet normal 0.185909 -0.607304 0.772412 + outer loop + vertex -435.879 70.8204 40.3089 + vertex -440.838 72.016 42.4425 + vertex -438.036 68.5973 39.0801 + endloop + endfacet + facet normal 0.137448 -0.635 0.760186 + outer loop + vertex -438.036 68.5973 39.0801 + vertex -440.838 72.016 42.4425 + vertex -443.331 69.8668 41.098 + endloop + endfacet + facet normal 0.147355 -0.615728 0.774058 + outer loop + vertex -438.036 68.5973 39.0801 + vertex -443.331 69.8668 41.098 + vertex -440.149 66.5613 37.8629 + endloop + endfacet + facet normal 0.096154 -0.6474 0.756061 + outer loop + vertex -440.149 66.5613 37.8629 + vertex -443.331 69.8668 41.098 + vertex -445.857 67.9287 39.7598 + endloop + endfacet + facet normal 0.163291 -0.695808 0.699419 + outer loop + vertex -443.331 69.8668 41.098 + vertex -448.232 71.1247 43.4936 + vertex -445.857 67.9287 39.7598 + endloop + endfacet + facet normal 0.114433 -0.717594 0.686997 + outer loop + vertex -445.857 67.9287 39.7598 + vertex -448.232 71.1247 43.4936 + vertex -451.054 69.2959 42.0535 + endloop + endfacet + facet normal 0.320805 -0.64445 0.694096 + outer loop + vertex -435.924 77.0061 45.0813 + vertex -439.839 77.972 47.7877 + vertex -438.367 74.3881 43.78 + endloop + endfacet + facet normal 0.26185 -0.669651 0.694983 + outer loop + vertex -438.367 74.3881 43.78 + vertex -439.839 77.972 47.7877 + vertex -442.586 75.4442 46.387 + endloop + endfacet + facet normal 0.280165 -0.568829 0.773267 + outer loop + vertex -431.549 75.9633 42.7292 + vertex -435.924 77.0061 45.0813 + vertex -433.709 73.2612 41.5241 + endloop + endfacet + facet normal 0.228596 -0.595997 0.76976 + outer loop + vertex -433.709 73.2612 41.5241 + vertex -435.924 77.0061 45.0813 + vertex -438.367 74.3881 43.78 + endloop + endfacet + facet normal 0.231473 -0.590639 0.773024 + outer loop + vertex -433.709 73.2612 41.5241 + vertex -438.367 74.3881 43.78 + vertex -435.879 70.8204 40.3089 + endloop + endfacet + facet normal 0.179915 -0.618615 0.764818 + outer loop + vertex -435.879 70.8204 40.3089 + vertex -438.367 74.3881 43.78 + vertex -440.838 72.016 42.4425 + endloop + endfacet + facet normal 0.2635 -0.66724 0.696676 + outer loop + vertex -438.367 74.3881 43.78 + vertex -442.586 75.4442 46.387 + vertex -440.838 72.016 42.4425 + endloop + endfacet + facet normal 0.206383 -0.691404 0.692364 + outer loop + vertex -440.838 72.016 42.4425 + vertex -442.586 75.4442 46.387 + vertex -445.386 73.1687 44.9493 + endloop + endfacet + facet normal 0.443919 -0.577704 0.684977 + outer loop + vertex -431.164 83.0337 47.4549 + vertex -434.557 83.8356 50.33 + vertex -433.506 79.8895 46.3209 + endloop + endfacet + facet normal 0.388331 -0.603829 0.696125 + outer loop + vertex -433.506 79.8895 46.3209 + vertex -434.557 83.8356 50.33 + vertex -437.149 80.7706 49.1172 + endloop + endfacet + facet normal 0.391999 -0.505156 0.768865 + outer loop + vertex -427.343 82.1335 44.9152 + vertex -431.164 83.0337 47.4549 + vertex -429.426 78.9207 43.8665 + endloop + endfacet + facet normal 0.33981 -0.532661 0.775114 + outer loop + vertex -429.426 78.9207 43.8665 + vertex -431.164 83.0337 47.4549 + vertex -433.506 79.8895 46.3209 + endloop + endfacet + facet normal 0.336697 -0.538674 0.772312 + outer loop + vertex -429.426 78.9207 43.8665 + vertex -433.506 79.8895 46.3209 + vertex -431.549 75.9633 42.7292 + endloop + endfacet + facet normal 0.280637 -0.567937 0.773751 + outer loop + vertex -431.549 75.9633 42.7292 + vertex -433.506 79.8895 46.3209 + vertex -435.924 77.0061 45.0813 + endloop + endfacet + facet normal 0.380662 -0.615749 0.689891 + outer loop + vertex -433.506 79.8895 46.3209 + vertex -437.149 80.7706 49.1172 + vertex -435.924 77.0061 45.0813 + endloop + endfacet + facet normal 0.323002 -0.641176 0.696106 + outer loop + vertex -435.924 77.0061 45.0813 + vertex -437.149 80.7706 49.1172 + vertex -439.839 77.972 47.7877 + endloop + endfacet + facet normal 0.566914 -0.481762 0.668217 + outer loop + vertex -426.867 90.0313 49.311 + vertex -429.835 90.7086 52.3168 + vertex -428.932 86.4224 48.4605 + endloop + endfacet + facet normal 0.519489 -0.508431 0.686753 + outer loop + vertex -428.932 86.4224 48.4605 + vertex -429.835 90.7086 52.3168 + vertex -432.104 87.1515 51.3999 + endloop + endfacet + facet normal 0.498111 -0.419979 0.75862 + outer loop + vertex -423.467 89.2525 46.6475 + vertex -426.867 90.0313 49.311 + vertex -425.344 85.5867 45.8501 + endloop + endfacet + facet normal 0.457522 -0.443362 0.770781 + outer loop + vertex -425.344 85.5867 45.8501 + vertex -426.867 90.0313 49.311 + vertex -428.932 86.4224 48.4605 + endloop + endfacet + facet normal 0.447178 -0.465625 0.763692 + outer loop + vertex -425.344 85.5867 45.8501 + vertex -428.932 86.4224 48.4605 + vertex -427.343 82.1335 44.9152 + endloop + endfacet + facet normal 0.398446 -0.492166 0.77396 + outer loop + vertex -427.343 82.1335 44.9152 + vertex -428.932 86.4224 48.4605 + vertex -431.164 83.0337 47.4549 + endloop + endfacet + facet normal 0.505324 -0.534049 0.67782 + outer loop + vertex -428.932 86.4224 48.4605 + vertex -432.104 87.1515 51.3999 + vertex -431.164 83.0337 47.4549 + endloop + endfacet + facet normal 0.454676 -0.55986 0.692695 + outer loop + vertex -431.164 83.0337 47.4549 + vertex -432.104 87.1515 51.3999 + vertex -434.557 83.8356 50.33 + endloop + endfacet + facet normal 0.659186 -0.383046 0.647108 + outer loop + vertex -423.204 97.8302 50.5892 + vertex -425.872 98.4767 53.6897 + vertex -424.959 93.8408 50.0162 + endloop + endfacet + facet normal 0.631178 -0.401605 0.663572 + outer loop + vertex -424.959 93.8408 50.0162 + vertex -425.872 98.4767 53.6897 + vertex -427.761 94.4943 53.0763 + endloop + endfacet + facet normal 0.583987 -0.33268 0.740462 + outer loop + vertex -420.101 97.1379 47.8309 + vertex -423.204 97.8302 50.5892 + vertex -421.725 93.1087 47.3019 + endloop + endfacet + facet normal 0.553667 -0.352059 0.754657 + outer loop + vertex -421.725 93.1087 47.3019 + vertex -423.204 97.8302 50.5892 + vertex -424.959 93.8408 50.0162 + endloop + endfacet + facet normal 0.545218 -0.373654 0.750413 + outer loop + vertex -421.725 93.1087 47.3019 + vertex -424.959 93.8408 50.0162 + vertex -423.467 89.2525 46.6475 + endloop + endfacet + facet normal 0.508311 -0.396118 0.764664 + outer loop + vertex -423.467 89.2525 46.6475 + vertex -424.959 93.8408 50.0162 + vertex -426.867 90.0313 49.311 + endloop + endfacet + facet normal 0.617788 -0.431132 0.65762 + outer loop + vertex -424.959 93.8408 50.0162 + vertex -427.761 94.4943 53.0763 + vertex -426.867 90.0313 49.311 + endloop + endfacet + facet normal 0.58091 -0.453796 0.675732 + outer loop + vertex -426.867 90.0313 49.311 + vertex -427.761 94.4943 53.0763 + vertex -429.835 90.7086 52.3168 + endloop + endfacet + facet normal 0.720532 -0.302288 0.624064 + outer loop + vertex -420.092 106.281 51.3995 + vertex -422.576 106.925 54.5783 + vertex -421.59 101.981 51.0458 + endloop + endfacet + facet normal 0.703029 -0.31533 0.63743 + outer loop + vertex -421.59 101.981 51.0458 + vertex -422.576 106.925 54.5783 + vertex -424.149 102.627 54.1874 + endloop + endfacet + facet normal 0.639362 -0.262234 0.722807 + outer loop + vertex -417.158 105.639 48.5703 + vertex -420.092 106.281 51.3995 + vertex -418.573 101.322 48.2562 + endloop + endfacet + facet normal 0.619256 -0.276142 0.735029 + outer loop + vertex -418.573 101.322 48.2562 + vertex -420.092 106.281 51.3995 + vertex -421.59 101.981 51.0458 + endloop + endfacet + facet normal 0.612129 -0.297955 0.732476 + outer loop + vertex -418.573 101.322 48.2562 + vertex -421.59 101.981 51.0458 + vertex -420.101 97.1379 47.8309 + endloop + endfacet + facet normal 0.591483 -0.311707 0.743631 + outer loop + vertex -420.101 97.1379 47.8309 + vertex -421.59 101.981 51.0458 + vertex -423.204 97.8302 50.5892 + endloop + endfacet + facet normal 0.693901 -0.339569 0.634976 + outer loop + vertex -421.59 101.981 51.0458 + vertex -424.149 102.627 54.1874 + vertex -423.204 97.8302 50.5892 + endloop + endfacet + facet normal 0.670238 -0.356278 0.651036 + outer loop + vertex -423.204 97.8302 50.5892 + vertex -424.149 102.627 54.1874 + vertex -425.872 98.4767 53.6897 + endloop + endfacet + facet normal 0.756033 -0.241297 0.608432 + outer loop + vertex -417.39 115.205 51.8211 + vertex -419.782 115.832 55.0425 + vertex -418.693 110.706 51.6559 + endloop + endfacet + facet normal 0.746164 -0.249274 0.617334 + outer loop + vertex -418.693 110.706 51.6559 + vertex -419.782 115.832 55.0425 + vertex -421.13 111.344 54.8594 + endloop + endfacet + facet normal 0.669623 -0.212868 0.711543 + outer loop + vertex -414.554 114.565 48.9607 + vertex -417.39 115.205 51.8211 + vertex -415.815 110.069 48.803 + endloop + endfacet + facet normal 0.662353 -0.218145 0.716729 + outer loop + vertex -415.815 110.069 48.803 + vertex -417.39 115.205 51.8211 + vertex -418.693 110.706 51.6559 + endloop + endfacet + facet normal 0.657157 -0.236688 0.715628 + outer loop + vertex -415.815 110.069 48.803 + vertex -418.693 110.706 51.6559 + vertex -417.158 105.639 48.5703 + endloop + endfacet + facet normal 0.644298 -0.245803 0.724197 + outer loop + vertex -417.158 105.639 48.5703 + vertex -418.693 110.706 51.6559 + vertex -420.092 106.281 51.3995 + endloop + endfacet + facet normal 0.739707 -0.269745 0.616499 + outer loop + vertex -418.693 110.706 51.6559 + vertex -421.13 111.344 54.8594 + vertex -420.092 106.281 51.3995 + endloop + endfacet + facet normal 0.728795 -0.278237 0.625653 + outer loop + vertex -420.092 106.281 51.3995 + vertex -421.13 111.344 54.8594 + vertex -422.576 106.925 54.5783 + endloop + endfacet + facet normal 0.773058 -0.205771 0.600033 + outer loop + vertex -415.031 124.153 51.9846 + vertex -417.376 124.784 55.2215 + vertex -416.169 119.708 51.9255 + endloop + endfacet + facet normal 0.7682 -0.210012 0.604784 + outer loop + vertex -416.169 119.708 51.9255 + vertex -417.376 124.784 55.2215 + vertex -418.54 120.333 55.1541 + endloop + endfacet + facet normal 0.686906 -0.181571 0.703699 + outer loop + vertex -412.264 123.507 49.1172 + vertex -415.031 124.153 51.9846 + vertex -413.376 119.063 49.0558 + endloop + endfacet + facet normal 0.683426 -0.184248 0.706387 + outer loop + vertex -413.376 119.063 49.0558 + vertex -415.031 124.153 51.9846 + vertex -416.169 119.708 51.9255 + endloop + endfacet + facet normal 0.681147 -0.193231 0.706187 + outer loop + vertex -413.376 119.063 49.0558 + vertex -416.169 119.708 51.9255 + vertex -414.554 114.565 48.9607 + endloop + endfacet + facet normal 0.673272 -0.199103 0.712083 + outer loop + vertex -414.554 114.565 48.9607 + vertex -416.169 119.708 51.9255 + vertex -417.39 115.205 51.8211 + endloop + endfacet + facet normal 0.765042 -0.221501 0.604689 + outer loop + vertex -416.169 119.708 51.9255 + vertex -418.54 120.333 55.1541 + vertex -417.39 115.205 51.8211 + endloop + endfacet + facet normal 0.760735 -0.22512 0.608772 + outer loop + vertex -417.39 115.205 51.8211 + vertex -418.54 120.333 55.1541 + vertex -419.782 115.832 55.0425 + endloop + endfacet + facet normal 0.780764 -0.187404 0.59606 + outer loop + vertex -412.93 132.898 52.0295 + vertex -415.238 133.546 55.2561 + vertex -413.965 128.534 52.0123 + endloop + endfacet + facet normal 0.779897 -0.188198 0.596945 + outer loop + vertex -413.965 128.534 52.0123 + vertex -415.238 133.546 55.2561 + vertex -416.286 129.177 55.248 + endloop + endfacet + facet normal 0.693254 -0.165798 0.701362 + outer loop + vertex -410.188 132.253 49.1662 + vertex -412.93 132.898 52.0295 + vertex -411.214 127.889 49.1487 + endloop + endfacet + facet normal 0.692017 -0.166789 0.702348 + outer loop + vertex -411.214 127.889 49.1487 + vertex -412.93 132.898 52.0295 + vertex -413.965 128.534 52.0123 + endloop + endfacet + facet normal 0.691065 -0.170767 0.70233 + outer loop + vertex -411.214 127.889 49.1487 + vertex -413.965 128.534 52.0123 + vertex -412.264 123.507 49.1172 + endloop + endfacet + facet normal 0.689193 -0.172251 0.703806 + outer loop + vertex -412.264 123.507 49.1172 + vertex -413.965 128.534 52.0123 + vertex -415.031 124.153 51.9846 + endloop + endfacet + facet normal 0.77858 -0.193337 0.597021 + outer loop + vertex -413.965 128.534 52.0123 + vertex -416.286 129.177 55.248 + vertex -415.031 124.153 51.9846 + endloop + endfacet + facet normal 0.775625 -0.196004 0.59999 + outer loop + vertex -415.031 124.153 51.9846 + vertex -416.286 129.177 55.248 + vertex -417.376 124.784 55.2215 + endloop + endfacet + facet normal 0.783756 -0.181454 0.593971 + outer loop + vertex -410.848 141.816 52.0414 + vertex -413.144 142.474 55.2722 + vertex -411.892 137.315 52.0434 + endloop + endfacet + facet normal 0.781661 -0.183328 0.596152 + outer loop + vertex -411.892 137.315 52.0434 + vertex -413.144 142.474 55.2722 + vertex -414.197 137.965 55.2659 + endloop + endfacet + facet normal 0.698034 -0.162234 0.697445 + outer loop + vertex -408.131 141.153 49.1682 + vertex -410.848 141.816 52.0414 + vertex -409.172 136.662 49.1649 + endloop + endfacet + facet normal 0.698725 -0.161693 0.696878 + outer loop + vertex -409.172 136.662 49.1649 + vertex -410.848 141.816 52.0414 + vertex -411.892 137.315 52.0434 + endloop + endfacet + facet normal 0.698928 -0.160831 0.696874 + outer loop + vertex -409.172 136.662 49.1649 + vertex -411.892 137.315 52.0434 + vertex -410.188 132.253 49.1662 + endloop + endfacet + facet normal 0.693385 -0.165249 0.701363 + outer loop + vertex -410.188 132.253 49.1662 + vertex -411.892 137.315 52.0434 + vertex -412.93 132.898 52.0295 + endloop + endfacet + facet normal 0.781101 -0.185546 0.596199 + outer loop + vertex -411.892 137.315 52.0434 + vertex -414.197 137.965 55.2659 + vertex -412.93 132.898 52.0295 + endloop + endfacet + facet normal 0.781275 -0.185388 0.59602 + outer loop + vertex -412.93 132.898 52.0295 + vertex -414.197 137.965 55.2659 + vertex -415.238 133.546 55.2561 + endloop + endfacet + facet normal 0.787362 -0.180575 0.589452 + outer loop + vertex -408.732 150.932 52.0286 + vertex -411.001 151.603 55.266 + vertex -409.785 146.376 52.0399 + endloop + endfacet + facet normal 0.784732 -0.182904 0.592235 + outer loop + vertex -409.785 146.376 52.0399 + vertex -411.001 151.603 55.266 + vertex -412.071 147.042 55.2748 + endloop + endfacet + facet normal 0.699946 -0.161421 0.695714 + outer loop + vertex -406.04 150.262 49.1652 + vertex -408.732 150.932 52.0286 + vertex -407.089 145.706 49.1633 + endloop + endfacet + facet normal 0.701263 -0.160408 0.694622 + outer loop + vertex -407.089 145.706 49.1633 + vertex -408.732 150.932 52.0286 + vertex -409.785 146.376 52.0399 + endloop + endfacet + facet normal 0.701403 -0.15982 0.694616 + outer loop + vertex -407.089 145.706 49.1633 + vertex -409.785 146.376 52.0399 + vertex -408.131 141.153 49.1682 + endloop + endfacet + facet normal 0.69798 -0.162461 0.697446 + outer loop + vertex -408.131 141.153 49.1682 + vertex -409.785 146.376 52.0399 + vertex -410.848 141.816 52.0414 + endloop + endfacet + facet normal 0.784777 -0.182725 0.59223 + outer loop + vertex -409.785 146.376 52.0399 + vertex -412.071 147.042 55.2748 + vertex -410.848 141.816 52.0414 + endloop + endfacet + facet normal 0.783051 -0.184249 0.59404 + outer loop + vertex -410.848 141.816 52.0414 + vertex -412.071 147.042 55.2748 + vertex -413.144 142.474 55.2722 + endloop + endfacet + facet normal 0.787985 -0.180486 0.588646 + outer loop + vertex -406.67 159.823 52.0105 + vertex -408.922 160.479 55.2263 + vertex -407.686 155.423 52.0219 + endloop + endfacet + facet normal 0.785702 -0.182568 0.591051 + outer loop + vertex -407.686 155.423 52.0219 + vertex -408.922 160.479 55.2263 + vertex -409.953 156.095 55.2416 + endloop + endfacet + facet normal 0.704892 -0.159024 0.691258 + outer loop + vertex -404.009 159.173 49.1468 + vertex -406.67 159.823 52.0105 + vertex -405.014 154.761 49.1574 + endloop + endfacet + facet normal 0.702947 -0.160574 0.692879 + outer loop + vertex -405.014 154.761 49.1574 + vertex -406.67 159.823 52.0105 + vertex -407.686 155.423 52.0219 + endloop + endfacet + facet normal 0.703277 -0.159183 0.692865 + outer loop + vertex -405.014 154.761 49.1574 + vertex -407.686 155.423 52.0219 + vertex -406.04 150.262 49.1652 + endloop + endfacet + facet normal 0.699841 -0.161858 0.695718 + outer loop + vertex -406.04 150.262 49.1652 + vertex -407.686 155.423 52.0219 + vertex -408.732 150.932 52.0286 + endloop + endfacet + facet normal 0.785838 -0.182033 0.591035 + outer loop + vertex -407.686 155.423 52.0219 + vertex -409.953 156.095 55.2416 + vertex -408.732 150.932 52.0286 + endloop + endfacet + facet normal 0.787331 -0.180697 0.589456 + outer loop + vertex -408.732 150.932 52.0286 + vertex -409.953 156.095 55.2416 + vertex -411.001 151.603 55.266 + endloop + endfacet + facet normal 0.790075 -0.181178 0.585624 + outer loop + vertex -404.676 168.458 52.0007 + vertex -406.925 169.11 55.2365 + vertex -405.668 164.15 52.0061 + endloop + endfacet + facet normal 0.787531 -0.183566 0.588301 + outer loop + vertex -405.668 164.15 52.0061 + vertex -406.925 169.11 55.2365 + vertex -407.922 164.802 55.227 + endloop + endfacet + facet normal 0.707067 -0.159362 0.688956 + outer loop + vertex -402.024 167.825 49.1328 + vertex -404.676 168.458 52.0007 + vertex -403.009 163.508 49.1448 + endloop + endfacet + facet normal 0.704614 -0.161367 0.691 + outer loop + vertex -403.009 163.508 49.1448 + vertex -404.676 168.458 52.0007 + vertex -405.668 164.15 52.0061 + endloop + endfacet + facet normal 0.704437 -0.162116 0.691004 + outer loop + vertex -403.009 163.508 49.1448 + vertex -405.668 164.15 52.0061 + vertex -404.009 159.173 49.1468 + endloop + endfacet + facet normal 0.704099 -0.162391 0.691285 + outer loop + vertex -404.009 159.173 49.1468 + vertex -405.668 164.15 52.0061 + vertex -406.67 159.823 52.0105 + endloop + endfacet + facet normal 0.787946 -0.181918 0.588257 + outer loop + vertex -405.668 164.15 52.0061 + vertex -407.922 164.802 55.227 + vertex -406.67 159.823 52.0105 + endloop + endfacet + facet normal 0.787528 -0.182307 0.588697 + outer loop + vertex -406.67 159.823 52.0105 + vertex -407.922 164.802 55.227 + vertex -408.922 160.479 55.2263 + endloop + endfacet + facet normal 0.793468 -0.185362 0.579698 + outer loop + vertex -402.651 177.249 52.0404 + vertex -404.891 177.865 55.3032 + vertex -403.668 172.812 52.0128 + endloop + endfacet + facet normal 0.789889 -0.188702 0.583495 + outer loop + vertex -403.668 172.812 52.0128 + vertex -404.891 177.865 55.3032 + vertex -405.913 173.455 55.2595 + endloop + endfacet + facet normal 0.714335 -0.162462 0.680685 + outer loop + vertex -400.02 176.628 49.1299 + vertex -402.651 177.249 52.0404 + vertex -401.028 172.185 49.1277 + endloop + endfacet + facet normal 0.7091 -0.166691 0.685121 + outer loop + vertex -401.028 172.185 49.1277 + vertex -402.651 177.249 52.0404 + vertex -403.668 172.812 52.0128 + endloop + endfacet + facet normal 0.710307 -0.161539 0.685106 + outer loop + vertex -401.028 172.185 49.1277 + vertex -403.668 172.812 52.0128 + vertex -402.024 167.825 49.1328 + endloop + endfacet + facet normal 0.705677 -0.165303 0.688981 + outer loop + vertex -402.024 167.825 49.1328 + vertex -403.668 172.812 52.0128 + vertex -404.676 168.458 52.0007 + endloop + endfacet + facet normal 0.790893 -0.184739 0.583404 + outer loop + vertex -403.668 172.812 52.0128 + vertex -405.913 173.455 55.2595 + vertex -404.676 168.458 52.0007 + endloop + endfacet + facet normal 0.788646 -0.186839 0.585772 + outer loop + vertex -404.676 168.458 52.0007 + vertex -405.913 173.455 55.2595 + vertex -406.925 169.11 55.2365 + endloop + endfacet + facet normal 0.803134 -0.177386 0.568779 + outer loop + vertex -400.677 186.287 52.1039 + vertex -402.906 186.844 55.4256 + vertex -401.652 181.756 52.0681 + endloop + endfacet + facet normal 0.798451 -0.181929 0.573914 + outer loop + vertex -401.652 181.756 52.0681 + vertex -402.906 186.844 55.4256 + vertex -403.889 182.343 55.3664 + endloop + endfacet + facet normal 0.727425 -0.154071 0.668666 + outer loop + vertex -398.062 185.68 49.12 + vertex -400.677 186.287 52.1039 + vertex -399.027 181.14 49.1229 + endloop + endfacet + facet normal 0.719918 -0.160314 0.67529 + outer loop + vertex -399.027 181.14 49.1229 + vertex -400.677 186.287 52.1039 + vertex -401.652 181.756 52.0681 + endloop + endfacet + facet normal 0.72056 -0.157489 0.675271 + outer loop + vertex -399.027 181.14 49.1229 + vertex -401.652 181.756 52.0681 + vertex -400.02 176.628 49.1299 + endloop + endfacet + facet normal 0.714307 -0.162581 0.680686 + outer loop + vertex -400.02 176.628 49.1299 + vertex -401.652 181.756 52.0681 + vertex -402.651 177.249 52.0404 + endloop + endfacet + facet normal 0.798756 -0.180652 0.573894 + outer loop + vertex -401.652 181.756 52.0681 + vertex -403.889 182.343 55.3664 + vertex -402.651 177.249 52.0404 + endloop + endfacet + facet normal 0.793371 -0.185755 0.579705 + outer loop + vertex -402.651 177.249 52.0404 + vertex -403.889 182.343 55.3664 + vertex -404.891 177.865 55.3032 + endloop + endfacet + facet normal 0.810774 -0.0931266 0.577904 + outer loop + vertex -399.282 195.52 52.1404 + vertex -401.513 196.041 55.3536 + vertex -399.813 190.839 52.1303 + endloop + endfacet + facet normal 0.820187 -0.0827267 0.566082 + outer loop + vertex -399.813 190.839 52.1303 + vertex -401.513 196.041 55.3536 + vertex -402.03 191.37 55.421 + endloop + endfacet + facet normal 0.733441 -0.0929209 0.673372 + outer loop + vertex -396.697 194.917 49.241 + vertex -399.282 195.52 52.1404 + vertex -397.197 190.236 49.1406 + endloop + endfacet + facet normal 0.741324 -0.0854462 0.665685 + outer loop + vertex -397.197 190.236 49.1406 + vertex -399.282 195.52 52.1404 + vertex -399.813 190.839 52.1303 + endloop + endfacet + facet normal 0.730744 -0.141737 0.667776 + outer loop + vertex -397.197 190.236 49.1406 + vertex -399.813 190.839 52.1303 + vertex -398.062 185.68 49.12 + endloop + endfacet + facet normal 0.729942 -0.142434 0.668504 + outer loop + vertex -398.062 185.68 49.12 + vertex -399.813 190.839 52.1303 + vertex -400.677 186.287 52.1039 + endloop + endfacet + facet normal 0.807155 -0.156514 0.569214 + outer loop + vertex -399.813 190.839 52.1303 + vertex -402.03 191.37 55.421 + vertex -400.677 186.287 52.1039 + endloop + endfacet + facet normal 0.807907 -0.155752 0.568355 + outer loop + vertex -400.677 186.287 52.1039 + vertex -402.03 191.37 55.421 + vertex -402.906 186.844 55.4256 + endloop + endfacet + facet normal -0.0768002 -0.805552 0.587526 + outer loop + vertex -475.103 61.9501 34.4331 + vertex -483.458 64.0759 36.2557 + vertex -477.119 62.034 34.2847 + endloop + endfacet + facet normal -0.0885068 -0.820257 0.565107 + outer loop + vertex -477.119 62.034 34.2847 + vertex -483.458 64.0759 36.2557 + vertex -484.301 63.9096 35.8822 + endloop + endfacet + facet normal -0.0600735 -0.743813 0.665682 + outer loop + vertex -466.772 59.803 32.7859 + vertex -475.103 61.9501 34.4331 + vertex -468.361 59.7471 32.5801 + endloop + endfacet + facet normal -0.0786051 -0.771578 0.63126 + outer loop + vertex -468.361 59.7471 32.5801 + vertex -475.103 61.9501 34.4331 + vertex -477.119 62.034 34.2847 + endloop + endfacet + facet normal -0.0273443 -0.774405 0.632099 + outer loop + vertex -472.096 63.1395 36.0859 + vertex -479.83 65.1623 38.2295 + vertex -473.675 62.3832 35.091 + endloop + endfacet + facet normal -0.0666816 -0.808306 0.584974 + outer loop + vertex -473.675 62.3832 35.091 + vertex -479.83 65.1623 38.2295 + vertex -481.945 64.5111 37.0886 + endloop + endfacet + facet normal -0.00809923 -0.702916 0.711226 + outer loop + vertex -464.558 61.1978 34.2527 + vertex -472.096 63.1395 36.0859 + vertex -465.659 60.3191 33.3718 + endloop + endfacet + facet normal -0.0530324 -0.752619 0.656317 + outer loop + vertex -465.659 60.3191 33.3718 + vertex -472.096 63.1395 36.0859 + vertex -473.675 62.3832 35.091 + endloop + endfacet + facet normal -0.0348775 -0.716101 0.697124 + outer loop + vertex -465.659 60.3191 33.3718 + vertex -473.675 62.3832 35.091 + vertex -466.772 59.803 32.7859 + endloop + endfacet + facet normal -0.0677638 -0.759394 0.647092 + outer loop + vertex -466.772 59.803 32.7859 + vertex -473.675 62.3832 35.091 + vertex -475.103 61.9501 34.4331 + endloop + endfacet + facet normal -0.0503169 -0.780512 0.623113 + outer loop + vertex -473.675 62.3832 35.091 + vertex -481.945 64.5111 37.0886 + vertex -475.103 61.9501 34.4331 + endloop + endfacet + facet normal -0.0819248 -0.814453 0.574417 + outer loop + vertex -475.103 61.9501 34.4331 + vertex -481.945 64.5111 37.0886 + vertex -483.458 64.0759 36.2557 + endloop + endfacet + facet normal 0.0145758 -0.799256 0.600814 + outer loop + vertex -467.684 65.2 38.7077 + vertex -474.193 66.8899 41.1136 + vertex -470.138 64.1041 37.3094 + endloop + endfacet + facet normal -0.0336405 -0.823105 0.566892 + outer loop + vertex -470.138 64.1041 37.3094 + vertex -474.193 66.8899 41.1136 + vertex -477.216 65.9651 39.5915 + endloop + endfacet + facet normal 0.0309929 -0.735459 0.67686 + outer loop + vertex -461.274 63.5225 36.5915 + vertex -467.684 65.2 38.7077 + vertex -463.188 62.3209 35.3735 + endloop + endfacet + facet normal -0.0197822 -0.76977 0.638015 + outer loop + vertex -463.188 62.3209 35.3735 + vertex -467.684 65.2 38.7077 + vertex -470.138 64.1041 37.3094 + endloop + endfacet + facet normal 0.0120097 -0.713613 0.700437 + outer loop + vertex -463.188 62.3209 35.3735 + vertex -470.138 64.1041 37.3094 + vertex -464.558 61.1978 34.2527 + endloop + endfacet + facet normal -0.0358499 -0.756105 0.653468 + outer loop + vertex -464.558 61.1978 34.2527 + vertex -470.138 64.1041 37.3094 + vertex -472.096 63.1395 36.0859 + endloop + endfacet + facet normal -0.00450085 -0.781769 0.623551 + outer loop + vertex -470.138 64.1041 37.3094 + vertex -477.216 65.9651 39.5915 + vertex -472.096 63.1395 36.0859 + endloop + endfacet + facet normal -0.0521194 -0.813341 0.579448 + outer loop + vertex -472.096 63.1395 36.0859 + vertex -477.216 65.9651 39.5915 + vertex -479.83 65.1623 38.2295 + endloop + endfacet + facet normal 0.0679654 -0.824312 0.562042 + outer loop + vertex -461.687 67.6319 41.6246 + vertex -466.565 68.9785 44.1894 + vertex -464.786 66.3688 40.1467 + endloop + endfacet + facet normal 0.0200505 -0.835939 0.548456 + outer loop + vertex -464.786 66.3688 40.1467 + vertex -466.565 68.9785 44.1894 + vertex -470.701 67.9486 42.7709 + endloop + endfacet + facet normal 0.0771007 -0.764861 0.639565 + outer loop + vertex -456.428 66.1667 39.2384 + vertex -461.687 67.6319 41.6246 + vertex -458.916 64.7939 37.8966 + endloop + endfacet + facet normal 0.0258642 -0.786056 0.617614 + outer loop + vertex -458.916 64.7939 37.8966 + vertex -461.687 67.6319 41.6246 + vertex -464.786 66.3688 40.1467 + endloop + endfacet + facet normal 0.0470024 -0.756626 0.652156 + outer loop + vertex -458.916 64.7939 37.8966 + vertex -464.786 66.3688 40.1467 + vertex -461.274 63.5225 36.5915 + endloop + endfacet + facet normal 0.00301177 -0.779193 0.626777 + outer loop + vertex -461.274 63.5225 36.5915 + vertex -464.786 66.3688 40.1467 + vertex -467.684 65.2 38.7077 + endloop + endfacet + facet normal 0.0400578 -0.81357 0.580085 + outer loop + vertex -464.786 66.3688 40.1467 + vertex -470.701 67.9486 42.7709 + vertex -467.684 65.2 38.7077 + endloop + endfacet + facet normal -0.0109878 -0.832005 0.554659 + outer loop + vertex -467.684 65.2 38.7077 + vertex -470.701 67.9486 42.7709 + vertex -474.193 66.8899 41.1136 + endloop + endfacet + facet normal 0.146148 -0.827541 0.542049 + outer loop + vertex -455.589 70.5833 44.6931 + vertex -459.395 71.7494 47.4995 + vertex -458.639 69.0349 43.1513 + endloop + endfacet + facet normal 0.0951978 -0.836891 0.539028 + outer loop + vertex -458.639 69.0349 43.1513 + vertex -459.395 71.7494 47.4995 + vertex -462.864 70.2808 45.8318 + endloop + endfacet + facet normal 0.140767 -0.772835 0.618797 + outer loop + vertex -451.054 69.2959 42.0535 + vertex -455.589 70.5833 44.6931 + vertex -453.805 67.6564 40.6315 + endloop + endfacet + facet normal 0.0924865 -0.78809 0.608572 + outer loop + vertex -453.805 67.6564 40.6315 + vertex -455.589 70.5833 44.6931 + vertex -458.639 69.0349 43.1513 + endloop + endfacet + facet normal 0.106112 -0.772445 0.626155 + outer loop + vertex -453.805 67.6564 40.6315 + vertex -458.639 69.0349 43.1513 + vertex -456.428 66.1667 39.2384 + endloop + endfacet + facet normal 0.0573124 -0.789493 0.611077 + outer loop + vertex -456.428 66.1667 39.2384 + vertex -458.639 69.0349 43.1513 + vertex -461.687 67.6319 41.6246 + endloop + endfacet + facet normal 0.105256 -0.828006 0.550752 + outer loop + vertex -458.639 69.0349 43.1513 + vertex -462.864 70.2808 45.8318 + vertex -461.687 67.6319 41.6246 + endloop + endfacet + facet normal 0.054033 -0.838125 0.542796 + outer loop + vertex -461.687 67.6319 41.6246 + vertex -462.864 70.2808 45.8318 + vertex -466.565 68.9785 44.1894 + endloop + endfacet + facet normal 0.241111 -0.813712 0.528902 + outer loop + vertex -449.37 74.2367 47.774 + vertex -452.623 75.1998 50.7387 + vertex -452.506 72.306 46.2333 + endloop + endfacet + facet normal 0.191666 -0.823524 0.533922 + outer loop + vertex -452.506 72.306 46.2333 + vertex -452.623 75.1998 50.7387 + vertex -455.988 73.3756 49.1328 + endloop + endfacet + facet normal 0.23072 -0.756801 0.611573 + outer loop + vertex -445.386 73.1687 44.9493 + vertex -449.37 74.2367 47.774 + vertex -448.232 71.1247 43.4936 + endloop + endfacet + facet normal 0.176737 -0.773148 0.609103 + outer loop + vertex -448.232 71.1247 43.4936 + vertex -449.37 74.2367 47.774 + vertex -452.506 72.306 46.2333 + endloop + endfacet + facet normal 0.182668 -0.766638 0.615548 + outer loop + vertex -448.232 71.1247 43.4936 + vertex -452.506 72.306 46.2333 + vertex -451.054 69.2959 42.0535 + endloop + endfacet + facet normal 0.132573 -0.781904 0.609139 + outer loop + vertex -451.054 69.2959 42.0535 + vertex -452.506 72.306 46.2333 + vertex -455.589 70.5833 44.6931 + endloop + endfacet + facet normal 0.192575 -0.822781 0.53474 + outer loop + vertex -452.506 72.306 46.2333 + vertex -455.988 73.3756 49.1328 + vertex -455.589 70.5833 44.6931 + endloop + endfacet + facet normal 0.140273 -0.832414 0.536107 + outer loop + vertex -455.589 70.5833 44.6931 + vertex -455.988 73.3756 49.1328 + vertex -459.395 71.7494 47.4995 + endloop + endfacet + facet normal 0.365598 -0.774056 0.516889 + outer loop + vertex -443.214 78.8312 50.776 + vertex -445.955 79.5905 53.8518 + vertex -446.258 76.4041 49.2946 + endloop + endfacet + facet normal 0.309505 -0.788849 0.530966 + outer loop + vertex -446.258 76.4041 49.2946 + vertex -445.955 79.5905 53.8518 + vertex -449.25 77.2624 52.3137 + endloop + endfacet + facet normal 0.351563 -0.716139 0.60295 + outer loop + vertex -439.839 77.972 47.7877 + vertex -443.214 78.8312 50.776 + vertex -442.586 75.4442 46.387 + endloop + endfacet + facet normal 0.290574 -0.73696 0.610292 + outer loop + vertex -442.586 75.4442 46.387 + vertex -443.214 78.8312 50.776 + vertex -446.258 76.4041 49.2946 + endloop + endfacet + facet normal 0.288455 -0.739349 0.608405 + outer loop + vertex -442.586 75.4442 46.387 + vertex -446.258 76.4041 49.2946 + vertex -445.386 73.1687 44.9493 + endloop + endfacet + facet normal 0.229629 -0.758006 0.610489 + outer loop + vertex -445.386 73.1687 44.9493 + vertex -446.258 76.4041 49.2946 + vertex -449.37 74.2367 47.774 + endloop + endfacet + facet normal 0.299605 -0.797532 0.523622 + outer loop + vertex -446.258 76.4041 49.2946 + vertex -449.25 77.2624 52.3137 + vertex -449.37 74.2367 47.774 + endloop + endfacet + facet normal 0.246111 -0.809515 0.533025 + outer loop + vertex -449.37 74.2367 47.774 + vertex -449.25 77.2624 52.3137 + vertex -452.623 75.1998 50.7387 + endloop + endfacet + facet normal 0.512353 -0.699377 0.498365 + outer loop + vertex -437.43 84.5155 53.4643 + vertex -439.718 85.0993 56.6357 + vertex -440.251 81.5374 52.1854 + endloop + endfacet + facet normal 0.459706 -0.719403 0.520701 + outer loop + vertex -440.251 81.5374 52.1854 + vertex -439.718 85.0993 56.6357 + vertex -442.752 82.2035 55.3138 + endloop + endfacet + facet normal 0.488224 -0.645334 0.587521 + outer loop + vertex -434.557 83.8356 50.33 + vertex -437.43 84.5155 53.4643 + vertex -437.149 80.7706 49.1172 + endloop + endfacet + facet normal 0.432361 -0.669138 0.604416 + outer loop + vertex -437.149 80.7706 49.1172 + vertex -437.43 84.5155 53.4643 + vertex -440.251 81.5374 52.1854 + endloop + endfacet + facet normal 0.419139 -0.685635 0.59517 + outer loop + vertex -437.149 80.7706 49.1172 + vertex -440.251 81.5374 52.1854 + vertex -439.839 77.972 47.7877 + endloop + endfacet + facet normal 0.358004 -0.708593 0.608053 + outer loop + vertex -439.839 77.972 47.7877 + vertex -440.251 81.5374 52.1854 + vertex -443.214 78.8312 50.776 + endloop + endfacet + facet normal 0.436967 -0.742652 0.507471 + outer loop + vertex -440.251 81.5374 52.1854 + vertex -442.752 82.2035 55.3138 + vertex -443.214 78.8312 50.776 + endloop + endfacet + facet normal 0.380134 -0.760466 0.526488 + outer loop + vertex -443.214 78.8312 50.776 + vertex -442.752 82.2035 55.3138 + vertex -445.955 79.5905 53.8518 + endloop + endfacet + facet normal 0.651148 -0.587765 0.480144 + outer loop + vertex -432.36 91.2078 55.5319 + vertex -434.382 91.5215 58.6591 + vertex -434.785 87.7354 54.5698 + endloop + endfacet + facet normal 0.613439 -0.608668 0.503206 + outer loop + vertex -434.785 87.7354 54.5698 + vertex -434.382 91.5215 58.6591 + vertex -436.91 88.2374 57.7679 + endloop + endfacet + facet normal 0.618382 -0.541346 0.569691 + outer loop + vertex -429.835 90.7086 52.3168 + vertex -432.36 91.2078 55.5319 + vertex -432.104 87.1515 51.3999 + endloop + endfacet + facet normal 0.575431 -0.565548 0.590792 + outer loop + vertex -432.104 87.1515 51.3999 + vertex -432.36 91.2078 55.5319 + vertex -434.785 87.7354 54.5698 + endloop + endfacet + facet normal 0.554788 -0.597291 0.579183 + outer loop + vertex -432.104 87.1515 51.3999 + vertex -434.785 87.7354 54.5698 + vertex -434.557 83.8356 50.33 + endloop + endfacet + facet normal 0.505929 -0.621151 0.598505 + outer loop + vertex -434.557 83.8356 50.33 + vertex -434.785 87.7354 54.5698 + vertex -437.43 84.5155 53.4643 + endloop + endfacet + facet normal 0.583755 -0.647701 0.489606 + outer loop + vertex -434.785 87.7354 54.5698 + vertex -436.91 88.2374 57.7679 + vertex -437.43 84.5155 53.4643 + endloop + endfacet + facet normal 0.539808 -0.667891 0.512376 + outer loop + vertex -437.43 84.5155 53.4643 + vertex -436.91 88.2374 57.7679 + vertex -439.718 85.0993 56.6357 + endloop + endfacet + facet normal 0.760887 -0.46299 0.454633 + outer loop + vertex -428.095 98.9999 57.0518 + vertex -429.942 99.2888 60.4362 + vertex -430.138 94.9783 56.3755 + endloop + endfacet + facet normal 0.732723 -0.484046 0.478348 + outer loop + vertex -430.138 94.9783 56.3755 + vertex -429.942 99.2888 60.4362 + vertex -432.106 95.1796 59.5932 + endloop + endfacet + facet normal 0.722456 -0.426514 0.54419 + outer loop + vertex -425.872 98.4767 53.6897 + vertex -428.095 98.9999 57.0518 + vertex -427.761 94.4943 53.0763 + endloop + endfacet + facet normal 0.693228 -0.447211 0.565187 + outer loop + vertex -427.761 94.4943 53.0763 + vertex -428.095 98.9999 57.0518 + vertex -430.138 94.9783 56.3755 + endloop + endfacet + facet normal 0.675729 -0.482052 0.557688 + outer loop + vertex -427.761 94.4943 53.0763 + vertex -430.138 94.9783 56.3755 + vertex -429.835 90.7086 52.3168 + endloop + endfacet + facet normal 0.6385 -0.505899 0.579987 + outer loop + vertex -429.835 90.7086 52.3168 + vertex -430.138 94.9783 56.3755 + vertex -432.36 91.2078 55.5319 + endloop + endfacet + facet normal 0.711676 -0.523945 0.467974 + outer loop + vertex -430.138 94.9783 56.3755 + vertex -432.106 95.1796 59.5932 + vertex -432.36 91.2078 55.5319 + endloop + endfacet + facet normal 0.676834 -0.54697 0.492666 + outer loop + vertex -432.36 91.2078 55.5319 + vertex -432.106 95.1796 59.5932 + vertex -434.382 91.5215 58.6591 + endloop + endfacet + facet normal 0.827359 -0.359122 0.431867 + outer loop + vertex -424.598 107.512 58.0006 + vertex -426.207 107.87 61.38 + vertex -426.255 103.189 57.5793 + endloop + endfacet + facet normal 0.814141 -0.371014 0.446681 + outer loop + vertex -426.255 103.189 57.5793 + vertex -426.207 107.87 61.38 + vertex -427.952 103.535 60.9598 + endloop + endfacet + facet normal 0.784924 -0.334754 0.521377 + outer loop + vertex -422.576 106.925 54.5783 + vertex -424.598 107.512 58.0006 + vertex -424.149 102.627 54.1874 + endloop + endfacet + facet normal 0.76985 -0.347187 0.53553 + outer loop + vertex -424.149 102.627 54.1874 + vertex -424.598 107.512 58.0006 + vertex -426.255 103.189 57.5793 + endloop + endfacet + facet normal 0.757096 -0.378149 0.532737 + outer loop + vertex -424.149 102.627 54.1874 + vertex -426.255 103.189 57.5793 + vertex -425.872 98.4767 53.6897 + endloop + endfacet + facet normal 0.737578 -0.393163 0.549001 + outer loop + vertex -425.872 98.4767 53.6897 + vertex -426.255 103.189 57.5793 + vertex -428.095 98.9999 57.0518 + endloop + endfacet + facet normal 0.799046 -0.40679 0.442772 + outer loop + vertex -426.255 103.189 57.5793 + vertex -427.952 103.535 60.9598 + vertex -428.095 98.9999 57.0518 + endloop + endfacet + facet normal 0.78004 -0.422428 0.461618 + outer loop + vertex -428.095 98.9999 57.0518 + vertex -427.952 103.535 60.9598 + vertex -429.942 99.2888 60.4362 + endloop + endfacet + facet normal 0.864366 -0.283686 0.415202 + outer loop + vertex -421.725 116.41 58.4923 + vertex -423.219 116.787 61.8602 + vertex -423.102 111.944 58.3083 + endloop + endfacet + facet normal 0.859435 -0.288726 0.421911 + outer loop + vertex -423.102 111.944 58.3083 + vertex -423.219 116.787 61.8602 + vertex -424.64 112.311 61.6914 + endloop + endfacet + facet normal 0.819921 -0.2669 0.506453 + outer loop + vertex -419.782 115.832 55.0425 + vertex -421.725 116.41 58.4923 + vertex -421.13 111.344 54.8594 + endloop + endfacet + facet normal 0.814131 -0.272219 0.512921 + outer loop + vertex -421.13 111.344 54.8594 + vertex -421.725 116.41 58.4923 + vertex -423.102 111.944 58.3083 + endloop + endfacet + facet normal 0.805982 -0.296289 0.512451 + outer loop + vertex -421.13 111.344 54.8594 + vertex -423.102 111.944 58.3083 + vertex -422.576 106.925 54.5783 + endloop + endfacet + facet normal 0.795999 -0.305039 0.522817 + outer loop + vertex -422.576 106.925 54.5783 + vertex -423.102 111.944 58.3083 + vertex -424.598 107.512 58.0006 + endloop + endfacet + facet normal 0.850268 -0.316273 0.420733 + outer loop + vertex -423.102 111.944 58.3083 + vertex -424.64 112.311 61.6914 + vertex -424.598 107.512 58.0006 + endloop + endfacet + facet normal 0.839473 -0.326728 0.434205 + outer loop + vertex -424.598 107.512 58.0006 + vertex -424.64 112.311 61.6914 + vertex -426.207 107.87 61.38 + endloop + endfacet + facet normal 0.879757 -0.241178 0.409709 + outer loop + vertex -419.306 125.256 58.7064 + vertex -420.837 125.267 62.0005 + vertex -420.468 120.841 58.6036 + endloop + endfacet + facet normal 0.876901 -0.24456 0.413806 + outer loop + vertex -420.468 120.841 58.6036 + vertex -420.837 125.267 62.0005 + vertex -421.951 121.089 61.8926 + endloop + endfacet + facet normal 0.838662 -0.226774 0.495197 + outer loop + vertex -417.376 124.784 55.2215 + vertex -419.306 125.256 58.7064 + vertex -418.54 120.333 55.1541 + endloop + endfacet + facet normal 0.834244 -0.231311 0.500532 + outer loop + vertex -418.54 120.333 55.1541 + vertex -419.306 125.256 58.7064 + vertex -420.468 120.841 58.6036 + endloop + endfacet + facet normal 0.831287 -0.241912 0.50044 + outer loop + vertex -418.54 120.333 55.1541 + vertex -420.468 120.841 58.6036 + vertex -419.782 115.832 55.0425 + endloop + endfacet + facet normal 0.826058 -0.246993 0.506579 + outer loop + vertex -419.782 115.832 55.0425 + vertex -420.468 120.841 58.6036 + vertex -421.725 116.41 58.4923 + endloop + endfacet + facet normal 0.873311 -0.258049 0.413204 + outer loop + vertex -420.468 120.841 58.6036 + vertex -421.951 121.089 61.8926 + vertex -421.725 116.41 58.4923 + endloop + endfacet + facet normal 0.871541 -0.25997 0.41573 + outer loop + vertex -421.725 116.41 58.4923 + vertex -421.951 121.089 61.8926 + vertex -423.219 116.787 61.8602 + endloop + endfacet + facet normal 0.890595 -0.216658 0.399875 + outer loop + vertex -417.129 134.085 58.7498 + vertex -418.657 134.283 62.26 + vertex -418.207 129.687 58.766 + endloop + endfacet + facet normal 0.88961 -0.217904 0.401387 + outer loop + vertex -418.207 129.687 58.766 + vertex -418.657 134.283 62.26 + vertex -419.769 129.694 62.2337 + endloop + endfacet + facet normal 0.847349 -0.204182 0.490214 + outer loop + vertex -415.238 133.546 55.2561 + vertex -417.129 134.085 58.7498 + vertex -416.286 129.177 55.248 + endloop + endfacet + facet normal 0.846182 -0.205442 0.4917 + outer loop + vertex -416.286 129.177 55.248 + vertex -417.129 134.085 58.7498 + vertex -418.207 129.687 58.766 + endloop + endfacet + facet normal 0.844427 -0.212418 0.491754 + outer loop + vertex -416.286 129.177 55.248 + vertex -418.207 129.687 58.766 + vertex -417.376 124.784 55.2215 + endloop + endfacet + facet normal 0.84159 -0.215451 0.495284 + outer loop + vertex -417.376 124.784 55.2215 + vertex -418.207 129.687 58.766 + vertex -419.306 125.256 58.7064 + endloop + endfacet + facet normal 0.887989 -0.225691 0.400673 + outer loop + vertex -418.207 129.687 58.766 + vertex -419.769 129.694 62.2337 + vertex -419.306 125.256 58.7064 + endloop + endfacet + facet normal 0.88133 -0.23413 0.410415 + outer loop + vertex -419.306 125.256 58.7064 + vertex -419.769 129.694 62.2337 + vertex -420.837 125.267 62.0005 + endloop + endfacet + facet normal 0.890115 -0.209505 0.404727 + outer loop + vertex -415.028 142.983 58.7392 + vertex -416.533 143.074 62.0944 + vertex -416.08 138.492 58.728 + endloop + endfacet + facet normal 0.890097 -0.209526 0.404754 + outer loop + vertex -416.08 138.492 58.728 + vertex -416.533 143.074 62.0944 + vertex -417.566 138.681 62.0928 + endloop + endfacet + facet normal 0.848545 -0.198797 0.490359 + outer loop + vertex -413.144 142.474 55.2722 + vertex -415.028 142.983 58.7392 + vertex -414.197 137.965 55.2659 + endloop + endfacet + facet normal 0.847629 -0.19977 0.491545 + outer loop + vertex -414.197 137.965 55.2659 + vertex -415.028 142.983 58.7392 + vertex -416.08 138.492 58.728 + endloop + endfacet + facet normal 0.847392 -0.200731 0.491563 + outer loop + vertex -414.197 137.965 55.2659 + vertex -416.08 138.492 58.728 + vertex -415.238 133.546 55.2561 + endloop + endfacet + facet normal 0.848507 -0.199532 0.490125 + outer loop + vertex -415.238 133.546 55.2561 + vertex -416.08 138.492 58.728 + vertex -417.129 134.085 58.7498 + endloop + endfacet + facet normal 0.89003 -0.209836 0.404741 + outer loop + vertex -416.08 138.492 58.728 + vertex -417.566 138.681 62.0928 + vertex -417.129 134.085 58.7498 + endloop + endfacet + facet normal 0.892866 -0.206321 0.400278 + outer loop + vertex -417.129 134.085 58.7498 + vertex -417.566 138.681 62.0928 + vertex -418.657 134.283 62.26 + endloop + endfacet + facet normal 0.889951 -0.210112 0.404771 + outer loop + vertex -412.884 152.094 58.7532 + vertex -414.419 152.037 62.0995 + vertex -413.957 147.535 58.7461 + endloop + endfacet + facet normal 0.889827 -0.210268 0.404964 + outer loop + vertex -413.957 147.535 58.7461 + vertex -414.419 152.037 62.0995 + vertex -415.477 147.584 62.1121 + endloop + endfacet + facet normal 0.850503 -0.198534 0.487061 + outer loop + vertex -411.001 151.603 55.266 + vertex -412.884 152.094 58.7532 + vertex -412.071 147.042 55.2748 + endloop + endfacet + facet normal 0.848632 -0.200519 0.489507 + outer loop + vertex -412.071 147.042 55.2748 + vertex -412.884 152.094 58.7532 + vertex -413.957 147.535 58.7461 + endloop + endfacet + facet normal 0.848844 -0.199641 0.489497 + outer loop + vertex -412.071 147.042 55.2748 + vertex -413.957 147.535 58.7461 + vertex -413.144 142.474 55.2722 + endloop + endfacet + facet normal 0.848164 -0.200357 0.490382 + outer loop + vertex -413.144 142.474 55.2722 + vertex -413.957 147.535 58.7461 + vertex -415.028 142.983 58.7392 + endloop + endfacet + facet normal 0.889872 -0.210044 0.404981 + outer loop + vertex -413.957 147.535 58.7461 + vertex -415.477 147.584 62.1121 + vertex -415.028 142.983 58.7392 + endloop + endfacet + facet normal 0.890049 -0.209825 0.404706 + outer loop + vertex -415.028 142.983 58.7392 + vertex -415.477 147.584 62.1121 + vertex -416.533 143.074 62.0944 + endloop + endfacet + facet normal 0.893517 -0.206498 0.398731 + outer loop + vertex -410.789 160.997 58.6899 + vertex -412.297 161.08 62.1102 + vertex -411.824 156.612 58.7368 + endloop + endfacet + facet normal 0.892911 -0.20728 0.399682 + outer loop + vertex -411.824 156.612 58.7368 + vertex -412.297 161.08 62.1102 + vertex -413.376 156.626 62.2107 + endloop + endfacet + facet normal 0.850124 -0.198067 0.487913 + outer loop + vertex -408.922 160.479 55.2263 + vertex -410.789 160.997 58.6899 + vertex -409.953 156.095 55.2416 + endloop + endfacet + facet normal 0.852182 -0.195823 0.485221 + outer loop + vertex -409.953 156.095 55.2416 + vertex -410.789 160.997 58.6899 + vertex -411.824 156.612 58.7368 + endloop + endfacet + facet normal 0.852048 -0.196378 0.485232 + outer loop + vertex -409.953 156.095 55.2416 + vertex -411.824 156.612 58.7368 + vertex -411.001 151.603 55.266 + endloop + endfacet + facet normal 0.850663 -0.197868 0.487053 + outer loop + vertex -411.001 151.603 55.266 + vertex -411.824 156.612 58.7368 + vertex -412.884 152.094 58.7532 + endloop + endfacet + facet normal 0.892758 -0.208063 0.399616 + outer loop + vertex -411.824 156.612 58.7368 + vertex -413.376 156.626 62.2107 + vertex -412.884 152.094 58.7532 + endloop + endfacet + facet normal 0.889559 -0.212179 0.404556 + outer loop + vertex -412.884 152.094 58.7532 + vertex -413.376 156.626 62.2107 + vertex -414.419 152.037 62.0995 + endloop + endfacet + facet normal 0.893052 -0.212048 0.396854 + outer loop + vertex -408.777 169.643 58.7541 + vertex -410.315 169.685 62.2372 + vertex -409.784 165.304 58.7028 + endloop + endfacet + facet normal 0.890749 -0.215146 0.400348 + outer loop + vertex -409.784 165.304 58.7028 + vertex -410.315 169.685 62.2372 + vertex -411.293 165.299 62.0558 + endloop + endfacet + facet normal 0.854446 -0.198814 0.479995 + outer loop + vertex -406.925 169.11 55.2365 + vertex -408.777 169.643 58.7541 + vertex -407.922 164.802 55.227 + endloop + endfacet + facet normal 0.850525 -0.203218 0.485088 + outer loop + vertex -407.922 164.802 55.227 + vertex -408.777 169.643 58.7541 + vertex -409.784 165.304 58.7028 + endloop + endfacet + facet normal 0.851988 -0.197203 0.485003 + outer loop + vertex -407.922 164.802 55.227 + vertex -409.784 165.304 58.7028 + vertex -408.922 160.479 55.2263 + endloop + endfacet + facet normal 0.849718 -0.199726 0.487943 + outer loop + vertex -408.922 160.479 55.2263 + vertex -409.784 165.304 58.7028 + vertex -410.789 160.997 58.6899 + endloop + endfacet + facet normal 0.891902 -0.209309 0.400876 + outer loop + vertex -409.784 165.304 58.7028 + vertex -411.293 165.299 62.0558 + vertex -410.789 160.997 58.6899 + endloop + endfacet + facet normal 0.89333 -0.207417 0.398671 + outer loop + vertex -410.789 160.997 58.6899 + vertex -411.293 165.299 62.0558 + vertex -412.297 161.08 62.1102 + endloop + endfacet + facet normal 0.894062 -0.210151 0.395587 + outer loop + vertex -406.728 178.426 58.7944 + vertex -408.168 178.757 62.2245 + vertex -407.755 174.032 58.78 + endloop + endfacet + facet normal 0.895474 -0.208379 0.393326 + outer loop + vertex -407.755 174.032 58.78 + vertex -408.168 178.757 62.2245 + vertex -409.251 174.251 62.3027 + endloop + endfacet + facet normal 0.852912 -0.202282 0.481272 + outer loop + vertex -404.891 177.865 55.3032 + vertex -406.728 178.426 58.7944 + vertex -405.913 173.455 55.2595 + endloop + endfacet + facet normal 0.854012 -0.201073 0.479826 + outer loop + vertex -405.913 173.455 55.2595 + vertex -406.728 178.426 58.7944 + vertex -407.755 174.032 58.78 + endloop + endfacet + facet normal 0.853908 -0.201484 0.479839 + outer loop + vertex -405.913 173.455 55.2595 + vertex -407.755 174.032 58.78 + vertex -406.925 169.11 55.2365 + endloop + endfacet + facet normal 0.853742 -0.201669 0.480056 + outer loop + vertex -406.925 169.11 55.2365 + vertex -407.755 174.032 58.78 + vertex -408.777 169.643 58.7541 + endloop + endfacet + facet normal 0.89495 -0.210756 0.393251 + outer loop + vertex -407.755 174.032 58.78 + vertex -409.251 174.251 62.3027 + vertex -408.777 169.643 58.7541 + endloop + endfacet + facet normal 0.892723 -0.213663 0.396729 + outer loop + vertex -408.777 169.643 58.7541 + vertex -409.251 174.251 62.3027 + vertex -410.315 169.685 62.2372 + endloop + endfacet + facet normal 0.894245 -0.201806 0.399499 + outer loop + vertex -404.735 187.293 58.9015 + vertex -406.173 187.4 62.1743 + vertex -405.715 182.832 58.843 + endloop + endfacet + facet normal 0.894204 -0.201859 0.399566 + outer loop + vertex -405.715 182.832 58.843 + vertex -406.173 187.4 62.1743 + vertex -407.134 183.057 62.1309 + endloop + endfacet + facet normal 0.857745 -0.193592 0.476231 + outer loop + vertex -402.906 186.844 55.4256 + vertex -404.735 187.293 58.9015 + vertex -403.889 182.343 55.3664 + endloop + endfacet + facet normal 0.856845 -0.194607 0.477436 + outer loop + vertex -403.889 182.343 55.3664 + vertex -404.735 187.293 58.9015 + vertex -405.715 182.832 58.843 + endloop + endfacet + facet normal 0.85596 -0.198323 0.477495 + outer loop + vertex -403.889 182.343 55.3664 + vertex -405.715 182.832 58.843 + vertex -404.891 177.865 55.3032 + endloop + endfacet + facet normal 0.853117 -0.20147 0.481249 + outer loop + vertex -404.891 177.865 55.3032 + vertex -405.715 182.832 58.843 + vertex -406.728 178.426 58.7944 + endloop + endfacet + facet normal 0.892506 -0.209624 0.399363 + outer loop + vertex -405.715 182.832 58.843 + vertex -407.134 183.057 62.1309 + vertex -406.728 178.426 58.7944 + endloop + endfacet + facet normal 0.894865 -0.2067 0.395591 + outer loop + vertex -406.728 178.426 58.7944 + vertex -407.134 183.057 62.1309 + vertex -408.168 178.757 62.2245 + endloop + endfacet + facet normal 0.914593 -0.0916085 0.393862 + outer loop + vertex -403.247 196.445 58.5587 + vertex -404.714 196.78 62.0451 + vertex -403.842 191.806 58.8625 + endloop + endfacet + facet normal 0.911946 -0.095402 0.399065 + outer loop + vertex -403.842 191.806 58.8625 + vertex -404.714 196.78 62.0451 + vertex -405.279 192.021 62.1968 + endloop + endfacet + facet normal 0.871235 -0.0895865 0.482623 + outer loop + vertex -401.513 196.041 55.3536 + vertex -403.247 196.445 58.5587 + vertex -402.03 191.37 55.421 + endloop + endfacet + facet normal 0.877606 -0.0817178 0.472367 + outer loop + vertex -402.03 191.37 55.421 + vertex -403.247 196.445 58.5587 + vertex -403.842 191.806 58.8625 + endloop + endfacet + facet normal 0.863642 -0.166633 0.475768 + outer loop + vertex -402.03 191.37 55.421 + vertex -403.842 191.806 58.8625 + vertex -402.906 186.844 55.4256 + endloop + endfacet + facet normal 0.863596 -0.166687 0.475833 + outer loop + vertex -402.906 186.844 55.4256 + vertex -403.842 191.806 58.8625 + vertex -404.735 187.293 58.9015 + endloop + endfacet + facet normal 0.900144 -0.174577 0.399079 + outer loop + vertex -403.842 191.806 58.8625 + vertex -405.279 192.021 62.1968 + vertex -404.735 187.293 58.9015 + endloop + endfacet + facet normal 0.899125 -0.175891 0.400796 + outer loop + vertex -404.735 187.293 58.9015 + vertex -405.279 192.021 62.1968 + vertex -406.173 187.4 62.1743 + endloop + endfacet + facet normal -0.0802878 -0.830545 0.551135 + outer loop + vertex -484.301 63.9096 35.8822 + vertex -483.458 64.0759 36.2557 + vertex -488.745 65.2865 37.3099 + endloop + endfacet + facet normal -0.048976 -0.825646 0.562059 + outer loop + vertex -481.945 64.5111 37.0886 + vertex -479.83 65.1623 38.2295 + vertex -485.224 66.3072 39.4412 + endloop + endfacet + facet normal -0.0687721 -0.827453 0.557307 + outer loop + vertex -483.458 64.0759 36.2557 + vertex -481.945 64.5111 37.0886 + vertex -487.577 65.7209 38.1897 + endloop + endfacet + facet normal -0.0303502 -0.834518 0.550144 + outer loop + vertex -479.83 65.1623 38.2295 + vertex -477.216 65.9651 39.5915 + vertex -482.149 66.9856 40.8673 + endloop + endfacet + facet normal 0.364464 -0.8143 0.451754 + outer loop + vertex -445.955 79.5905 53.8518 + vertex -447.928 80.2557 56.6429 + vertex -449.25 77.2624 52.3137 + endloop + endfacet + facet normal 0.31939 -0.822269 0.471025 + outer loop + vertex -449.25 77.2624 52.3137 + vertex -447.928 80.2557 56.6429 + vertex -451.42 78.0081 55.0872 + endloop + endfacet + facet normal 0.297996 -0.837334 0.458334 + outer loop + vertex -449.25 77.2624 52.3137 + vertex -451.42 78.0081 55.0872 + vertex -452.623 75.1998 50.7387 + endloop + endfacet + facet normal 0.517473 -0.739091 0.431238 + outer loop + vertex -439.718 85.0993 56.6357 + vertex -441.382 85.6114 59.5105 + vertex -442.752 82.2035 55.3138 + endloop + endfacet + facet normal 0.471228 -0.753671 0.458175 + outer loop + vertex -442.752 82.2035 55.3138 + vertex -441.382 85.6114 59.5105 + vertex -444.566 82.7885 58.1414 + endloop + endfacet + facet normal 0.437049 -0.783144 0.44235 + outer loop + vertex -442.752 82.2035 55.3138 + vertex -444.566 82.7885 58.1414 + vertex -445.955 79.5905 53.8518 + endloop + endfacet + facet normal 0.390738 -0.794112 0.46552 + outer loop + vertex -445.955 79.5905 53.8518 + vertex -444.566 82.7885 58.1414 + vertex -447.928 80.2557 56.6429 + endloop + endfacet + facet normal 0.662035 -0.622698 0.417081 + outer loop + vertex -434.382 91.5215 58.6591 + vertex -435.708 92.0459 61.5462 + vertex -436.91 88.2374 57.7679 + endloop + endfacet + facet normal 0.637641 -0.634539 0.436777 + outer loop + vertex -436.91 88.2374 57.7679 + vertex -435.708 92.0459 61.5462 + vertex -438.41 88.7238 60.6652 + endloop + endfacet + facet normal 0.594268 -0.684255 0.42266 + outer loop + vertex -436.91 88.2374 57.7679 + vertex -438.41 88.7238 60.6652 + vertex -439.718 85.0993 56.6357 + endloop + endfacet + facet normal 0.558005 -0.69882 0.447528 + outer loop + vertex -439.718 85.0993 56.6357 + vertex -438.41 88.7238 60.6652 + vertex -441.382 85.6114 59.5105 + endloop + endfacet + facet normal 0.78182 -0.490691 0.384682 + outer loop + vertex -429.942 99.2888 60.4362 + vertex -431.492 99.2822 63.5786 + vertex -432.106 95.1796 59.5932 + endloop + endfacet + facet normal 0.746058 -0.51805 0.418355 + outer loop + vertex -432.106 95.1796 59.5932 + vertex -431.492 99.2822 63.5786 + vertex -433.591 94.896 61.8896 + endloop + endfacet + facet normal 0.727861 -0.55556 0.401959 + outer loop + vertex -432.106 95.1796 59.5932 + vertex -433.591 94.896 61.8896 + vertex -434.382 91.5215 58.6591 + endloop + endfacet + facet normal 0.701023 -0.572077 0.425788 + outer loop + vertex -434.382 91.5215 58.6591 + vertex -433.591 94.896 61.8896 + vertex -435.708 92.0459 61.5462 + endloop + endfacet + facet normal 0.851496 -0.377982 0.363435 + outer loop + vertex -426.207 107.87 61.38 + vertex -427.453 107.812 64.2378 + vertex -427.952 103.535 60.9598 + endloop + endfacet + facet normal 0.839102 -0.389236 0.380004 + outer loop + vertex -427.952 103.535 60.9598 + vertex -427.453 107.812 64.2378 + vertex -429.237 103.659 63.9237 + endloop + endfacet + facet normal 0.821236 -0.430926 0.373997 + outer loop + vertex -427.952 103.535 60.9598 + vertex -429.237 103.659 63.9237 + vertex -429.942 99.2888 60.4362 + endloop + endfacet + facet normal 0.803411 -0.445158 0.395431 + outer loop + vertex -429.942 99.2888 60.4362 + vertex -429.237 103.659 63.9237 + vertex -431.492 99.2822 63.5786 + endloop + endfacet + facet normal 0.889116 -0.295419 0.349571 + outer loop + vertex -423.219 116.787 61.8602 + vertex -424.389 116.631 64.7032 + vertex -424.64 112.311 61.6914 + endloop + endfacet + facet normal 0.882661 -0.302264 0.359925 + outer loop + vertex -424.64 112.311 61.6914 + vertex -424.389 116.631 64.7032 + vertex -425.856 112.146 64.5352 + endloop + endfacet + facet normal 0.873743 -0.333221 0.354312 + outer loop + vertex -424.64 112.311 61.6914 + vertex -425.856 112.146 64.5352 + vertex -426.207 107.87 61.38 + endloop + endfacet + facet normal 0.863475 -0.343484 0.369363 + outer loop + vertex -426.207 107.87 61.38 + vertex -425.856 112.146 64.5352 + vertex -427.453 107.812 64.2378 + endloop + endfacet + facet normal 0.902375 -0.249737 0.351214 + outer loop + vertex -420.837 125.267 62.0005 + vertex -421.919 124.618 64.3185 + vertex -421.951 121.089 61.8926 + endloop + endfacet + facet normal 0.902869 -0.249153 0.350358 + outer loop + vertex -421.951 121.089 61.8926 + vertex -421.919 124.618 64.3185 + vertex -423.022 121.113 64.6682 + endloop + endfacet + facet normal 0.898278 -0.267345 0.348744 + outer loop + vertex -421.951 121.089 61.8926 + vertex -423.022 121.113 64.6682 + vertex -423.219 116.787 61.8602 + endloop + endfacet + facet normal 0.895489 -0.270349 0.353569 + outer loop + vertex -423.219 116.787 61.8602 + vertex -423.022 121.113 64.6682 + vertex -424.389 116.631 64.7032 + endloop + endfacet + facet normal 0.91534 -0.223758 0.33479 + outer loop + vertex -418.657 134.283 62.26 + vertex -419.975 133.709 65.4787 + vertex -419.769 129.694 62.2337 + endloop + endfacet + facet normal 0.909209 -0.232581 0.345318 + outer loop + vertex -419.769 129.694 62.2337 + vertex -419.975 133.709 65.4787 + vertex -421.087 128.521 64.9123 + endloop + endfacet + facet normal 0.908847 -0.237219 0.343109 + outer loop + vertex -419.769 129.694 62.2337 + vertex -421.087 128.521 64.9123 + vertex -420.837 125.267 62.0005 + endloop + endfacet + facet normal 0.902889 -0.246066 0.352483 + outer loop + vertex -420.837 125.267 62.0005 + vertex -421.087 128.521 64.9123 + vertex -421.919 124.618 64.3185 + endloop + endfacet + facet normal 0.912395 -0.214752 0.348449 + outer loop + vertex -416.533 143.074 62.0944 + vertex -417.628 142.345 64.5129 + vertex -417.566 138.681 62.0928 + endloop + endfacet + facet normal 0.917159 -0.208744 0.339477 + outer loop + vertex -417.566 138.681 62.0928 + vertex -417.628 142.345 64.5129 + vertex -418.667 138.601 65.0181 + endloop + endfacet + facet normal 0.916062 -0.21441 0.338909 + outer loop + vertex -417.566 138.681 62.0928 + vertex -418.667 138.601 65.0181 + vertex -418.657 134.283 62.26 + endloop + endfacet + facet normal 0.916903 -0.213371 0.337285 + outer loop + vertex -418.657 134.283 62.26 + vertex -418.667 138.601 65.0181 + vertex -419.975 133.709 65.4787 + endloop + endfacet + facet normal 0.911982 -0.215691 0.34895 + outer loop + vertex -414.419 152.037 62.0995 + vertex -415.553 151.193 64.5393 + vertex -415.477 147.584 62.1121 + endloop + endfacet + facet normal 0.916356 -0.210117 0.340796 + outer loop + vertex -415.477 147.584 62.1121 + vertex -415.553 151.193 64.5393 + vertex -416.737 147.028 65.157 + endloop + endfacet + facet normal 0.915582 -0.215542 0.339486 + outer loop + vertex -415.477 147.584 62.1121 + vertex -416.737 147.028 65.157 + vertex -416.533 143.074 62.0944 + endloop + endfacet + facet normal 0.911735 -0.220994 0.346267 + outer loop + vertex -416.533 143.074 62.0944 + vertex -416.737 147.028 65.157 + vertex -417.628 142.345 64.5129 + endloop + endfacet + facet normal 0.917457 -0.214687 0.334936 + outer loop + vertex -412.297 161.08 62.1102 + vertex -413.574 160.652 65.3361 + vertex -413.376 156.626 62.2107 + endloop + endfacet + facet normal 0.914592 -0.21881 0.340065 + outer loop + vertex -413.376 156.626 62.2107 + vertex -413.574 160.652 65.3361 + vertex -414.706 155.374 64.9837 + endloop + endfacet + facet normal 0.914736 -0.216371 0.341235 + outer loop + vertex -413.376 156.626 62.2107 + vertex -414.706 155.374 64.9837 + vertex -414.419 152.037 62.0995 + endloop + endfacet + facet normal 0.911459 -0.221403 0.346731 + outer loop + vertex -414.419 152.037 62.0995 + vertex -414.706 155.374 64.9837 + vertex -415.553 151.193 64.5393 + endloop + endfacet + facet normal 0.915473 -0.218086 0.338153 + outer loop + vertex -410.315 169.685 62.2372 + vertex -411.611 168.537 65.005 + vertex -411.293 165.299 62.0558 + endloop + endfacet + facet normal 0.913468 -0.221302 0.341469 + outer loop + vertex -411.293 165.299 62.0558 + vertex -411.611 168.537 65.005 + vertex -412.411 164.565 64.5729 + endloop + endfacet + facet normal 0.914368 -0.213124 0.344252 + outer loop + vertex -411.293 165.299 62.0558 + vertex -412.411 164.565 64.5729 + vertex -412.297 161.08 62.1102 + endloop + endfacet + facet normal 0.918611 -0.207407 0.336358 + outer loop + vertex -412.297 161.08 62.1102 + vertex -412.411 164.565 64.5729 + vertex -413.574 160.652 65.3361 + endloop + endfacet + facet normal 0.916897 -0.214512 0.336578 + outer loop + vertex -408.168 178.757 62.2245 + vertex -409.291 178.541 65.1444 + vertex -409.251 174.251 62.3027 + endloop + endfacet + facet normal 0.918216 -0.212823 0.334046 + outer loop + vertex -409.251 174.251 62.3027 + vertex -409.291 178.541 65.1444 + vertex -410.557 173.656 65.5134 + endloop + endfacet + facet normal 0.917388 -0.21849 0.332658 + outer loop + vertex -409.251 174.251 62.3027 + vertex -410.557 173.656 65.5134 + vertex -410.315 169.685 62.2372 + endloop + endfacet + facet normal 0.915197 -0.221785 0.33649 + outer loop + vertex -410.315 169.685 62.2372 + vertex -410.557 173.656 65.5134 + vertex -411.611 168.537 65.005 + endloop + endfacet + facet normal 0.914602 -0.205858 0.348032 + outer loop + vertex -406.173 187.4 62.1743 + vertex -407.201 186.719 64.4734 + vertex -407.134 183.057 62.1309 + endloop + endfacet + facet normal 0.9171 -0.202752 0.343249 + outer loop + vertex -407.134 183.057 62.1309 + vertex -407.201 186.719 64.4734 + vertex -408.166 183.057 64.8887 + endloop + endfacet + facet normal 0.915115 -0.212728 0.342508 + outer loop + vertex -407.134 183.057 62.1309 + vertex -408.166 183.057 64.8887 + vertex -408.168 178.757 62.2245 + endloop + endfacet + facet normal 0.917793 -0.209499 0.337293 + outer loop + vertex -408.168 178.757 62.2245 + vertex -408.166 183.057 64.8887 + vertex -409.291 178.541 65.1444 + endloop + endfacet + facet normal 0.942894 -0.10168 0.317194 + outer loop + vertex -404.714 196.78 62.0451 + vertex -405.755 197.01 65.2122 + vertex -405.279 192.021 62.1968 + endloop + endfacet + facet normal 0.928791 -0.122679 0.349709 + outer loop + vertex -405.279 192.021 62.1968 + vertex -405.755 197.01 65.2122 + vertex -406.494 191.527 65.2509 + endloop + endfacet + facet normal 0.923592 -0.180321 0.338323 + outer loop + vertex -405.279 192.021 62.1968 + vertex -406.494 191.527 65.2509 + vertex -406.173 187.4 62.1743 + endloop + endfacet + facet normal 0.915855 -0.191706 0.352787 + outer loop + vertex -406.173 187.4 62.1743 + vertex -406.494 191.527 65.2509 + vertex -407.201 186.719 64.4734 + endloop + endfacet + facet normal -0.041103 -0.890291 0.453534 + outer loop + vertex -480.929 69.7841 46.3582 + vertex -485.095 69.1044 44.6465 + vertex -483.179 68.9911 44.5977 + endloop + endfacet + facet normal -0.0601157 -0.888506 0.454909 + outer loop + vertex -485.095 69.1044 44.6465 + vertex -489.176 68.567 43.0575 + vertex -487.145 68.4051 43.0096 + endloop + endfacet + facet normal -0.0111695 -0.888766 0.458226 + outer loop + vertex -476.598 70.7043 48.2485 + vertex -480.929 69.7841 46.3582 + vertex -478.935 69.7995 46.4367 + endloop + endfacet + facet normal 0.0626716 -0.887228 0.457054 + outer loop + vertex -466.056 73.5075 52.6057 + vertex -471.708 71.8187 50.1024 + vertex -469.062 71.8833 49.865 + endloop + endfacet + facet normal 0.0975824 -0.899444 0.426003 + outer loop + vertex -464.52 73.3313 51.8818 + vertex -466.056 73.5075 52.6057 + vertex -469.062 71.8833 49.865 + endloop + endfacet + facet normal 0.122115 -0.928495 0.350691 + outer loop + vertex -466.885 73.4208 52.6648 + vertex -471.708 71.8187 50.1024 + vertex -466.056 73.5075 52.6057 + endloop + endfacet + facet normal 0.226074 -0.908831 0.350595 + outer loop + vertex -457.18 76.9385 56.6106 + vertex -457.724 76.83 56.6803 + vertex -461.35 75.1802 54.7416 + endloop + endfacet + facet normal 0.152452 -0.875002 0.459489 + outer loop + vertex -461.35 75.1802 54.7416 + vertex -457.724 76.83 56.6803 + vertex -461.966 75.0965 54.7867 + endloop + endfacet + facet normal 0.21758 -0.89126 0.397888 + outer loop + vertex -456.408 76.6495 55.5412 + vertex -457.18 76.9385 56.6106 + vertex -460.309 74.925 53.8117 + endloop + endfacet + facet normal 0.17535 -0.881622 0.438173 + outer loop + vertex -460.309 74.925 53.8117 + vertex -457.18 76.9385 56.6106 + vertex -461.35 75.1802 54.7416 + endloop + endfacet + facet normal 0.14996 -0.897755 0.414184 + outer loop + vertex -460.309 74.925 53.8117 + vertex -461.35 75.1802 54.7416 + vertex -464.52 73.3313 51.8818 + endloop + endfacet + facet normal 0.110561 -0.88602 0.450271 + outer loop + vertex -464.52 73.3313 51.8818 + vertex -461.35 75.1802 54.7416 + vertex -466.056 73.5075 52.6057 + endloop + endfacet + facet normal 0.151718 -0.912368 0.380219 + outer loop + vertex -461.35 75.1802 54.7416 + vertex -461.966 75.0965 54.7867 + vertex -466.056 73.5075 52.6057 + endloop + endfacet + facet normal 0.124012 -0.898156 0.421825 + outer loop + vertex -466.056 73.5075 52.6057 + vertex -461.966 75.0965 54.7867 + vertex -466.885 73.4208 52.6648 + endloop + endfacet + facet normal 0.400356 -0.874572 0.273566 + outer loop + vertex -449.694 81.0253 59.8695 + vertex -450.034 80.9137 60.0099 + vertex -453.33 78.8638 58.2798 + endloop + endfacet + facet normal 0.325512 -0.858247 0.396804 + outer loop + vertex -453.33 78.8638 58.2798 + vertex -450.034 80.9137 60.0099 + vertex -453.761 78.7569 58.4024 + endloop + endfacet + facet normal 0.357797 -0.854827 0.375836 + outer loop + vertex -449.134 80.7713 58.7587 + vertex -449.694 81.0253 59.8695 + vertex -452.721 78.5815 57.1924 + endloop + endfacet + facet normal 0.329416 -0.852523 0.40582 + outer loop + vertex -452.721 78.5815 57.1924 + vertex -449.694 81.0253 59.8695 + vertex -453.33 78.8638 58.2798 + endloop + endfacet + facet normal 0.285698 -0.87646 0.38755 + outer loop + vertex -452.721 78.5815 57.1924 + vertex -453.33 78.8638 58.2798 + vertex -456.408 76.6495 55.5412 + endloop + endfacet + facet normal 0.254231 -0.871653 0.419032 + outer loop + vertex -456.408 76.6495 55.5412 + vertex -453.33 78.8638 58.2798 + vertex -457.18 76.9385 56.6106 + endloop + endfacet + facet normal 0.311725 -0.896434 0.315013 + outer loop + vertex -453.33 78.8638 58.2798 + vertex -453.761 78.7569 58.4024 + vertex -457.18 76.9385 56.6106 + endloop + endfacet + facet normal 0.229488 -0.867097 0.44213 + outer loop + vertex -457.18 76.9385 56.6106 + vertex -453.761 78.7569 58.4024 + vertex -457.724 76.83 56.6803 + endloop + endfacet + facet normal 0.574034 -0.795143 0.195532 + outer loop + vertex -442.934 86.1913 62.8394 + vertex -443.307 85.9639 63.0114 + vertex -446.23 83.4596 61.4073 + endloop + endfacet + facet normal 0.514447 -0.799299 0.31059 + outer loop + vertex -446.23 83.4596 61.4073 + vertex -443.307 85.9639 63.0114 + vertex -446.58 83.289 61.5478 + endloop + endfacet + facet normal 0.514427 -0.783732 0.348035 + outer loop + vertex -442.402 86.0185 61.6649 + vertex -442.934 86.1913 62.8394 + vertex -445.676 83.248 60.2653 + endloop + endfacet + facet normal 0.48607 -0.786368 0.381262 + outer loop + vertex -445.676 83.248 60.2653 + vertex -442.934 86.1913 62.8394 + vertex -446.23 83.4596 61.4073 + endloop + endfacet + facet normal 0.432967 -0.825213 0.362716 + outer loop + vertex -445.676 83.248 60.2653 + vertex -446.23 83.4596 61.4073 + vertex -449.134 80.7713 58.7587 + endloop + endfacet + facet normal 0.405382 -0.825321 0.393078 + outer loop + vertex -449.134 80.7713 58.7587 + vertex -446.23 83.4596 61.4073 + vertex -449.694 81.0253 59.8695 + endloop + endfacet + facet normal 0.496205 -0.84143 0.213953 + outer loop + vertex -446.23 83.4596 61.4073 + vertex -446.58 83.289 61.5478 + vertex -449.694 81.0253 59.8695 + endloop + endfacet + facet normal 0.419797 -0.837323 0.350229 + outer loop + vertex -449.694 81.0253 59.8695 + vertex -446.58 83.289 61.5478 + vertex -450.034 80.9137 60.0099 + endloop + endfacet + facet normal 0.717385 -0.664718 0.208587 + outer loop + vertex -436.999 92.6463 65.1215 + vertex -437.347 92.3714 65.4426 + vertex -439.85 89.2412 64.0786 + endloop + endfacet + facet normal 0.676317 -0.67222 0.30119 + outer loop + vertex -439.85 89.2412 64.0786 + vertex -437.347 92.3714 65.4426 + vertex -440.21 88.9895 64.3245 + endloop + endfacet + facet normal 0.686886 -0.655211 0.31446 + outer loop + vertex -436.494 92.5614 63.8432 + vertex -436.999 92.6463 65.1215 + vertex -439.343 89.1041 62.8628 + endloop + endfacet + facet normal 0.662223 -0.66209 0.350852 + outer loop + vertex -439.343 89.1041 62.8628 + vertex -436.999 92.6463 65.1215 + vertex -439.85 89.2412 64.0786 + endloop + endfacet + facet normal 0.601887 -0.725894 0.33288 + outer loop + vertex -439.343 89.1041 62.8628 + vertex -439.85 89.2412 64.0786 + vertex -442.402 86.0185 61.6649 + endloop + endfacet + facet normal 0.57512 -0.730777 0.367699 + outer loop + vertex -442.402 86.0185 61.6649 + vertex -439.85 89.2412 64.0786 + vertex -442.934 86.1913 62.8394 + endloop + endfacet + facet normal 0.648656 -0.735387 0.19609 + outer loop + vertex -439.85 89.2412 64.0786 + vertex -440.21 88.9895 64.3245 + vertex -442.934 86.1913 62.8394 + endloop + endfacet + facet normal 0.594279 -0.742467 0.309151 + outer loop + vertex -442.934 86.1913 62.8394 + vertex -440.21 88.9895 64.3245 + vertex -443.307 85.9639 63.0114 + endloop + endfacet + facet normal 0.846623 -0.513618 0.139377 + outer loop + vertex -432.025 100.52 66.862 + vertex -432.397 99.9829 67.142 + vertex -434.364 96.4345 66.0127 + endloop + endfacet + facet normal 0.797773 -0.532314 0.283197 + outer loop + vertex -434.364 96.4345 66.0127 + vertex -432.397 99.9829 67.142 + vertex -434.711 96.1056 66.3729 + endloop + endfacet + facet normal 0.826794 -0.500171 0.257372 + outer loop + vertex -431.45 101.087 66.1131 + vertex -432.025 100.52 66.862 + vertex -433.663 96.6613 64.624 + endloop + endfacet + facet normal 0.793678 -0.519975 0.315754 + outer loop + vertex -433.663 96.6613 64.624 + vertex -432.025 100.52 66.862 + vertex -434.364 96.4345 66.0127 + endloop + endfacet + facet normal 0.761007 -0.58064 0.289352 + outer loop + vertex -433.663 96.6613 64.624 + vertex -434.364 96.4345 66.0127 + vertex -436.494 92.5614 63.8432 + endloop + endfacet + facet normal 0.736897 -0.590066 0.329854 + outer loop + vertex -436.494 92.5614 63.8432 + vertex -434.364 96.4345 66.0127 + vertex -436.999 92.6463 65.1215 + endloop + endfacet + facet normal 0.778534 -0.591064 0.211014 + outer loop + vertex -434.364 96.4345 66.0127 + vertex -434.711 96.1056 66.3729 + vertex -436.999 92.6463 65.1215 + endloop + endfacet + facet normal 0.744685 -0.598903 0.294549 + outer loop + vertex -436.999 92.6463 65.1215 + vertex -434.711 96.1056 66.3729 + vertex -437.347 92.3714 65.4426 + endloop + endfacet + facet normal 0.900806 -0.395927 0.178297 + outer loop + vertex -428.212 108.757 67.4084 + vertex -428.485 108.404 68.0045 + vertex -430.033 104.617 67.4157 + endloop + endfacet + facet normal 0.89615 -0.397098 0.198063 + outer loop + vertex -430.033 104.617 67.4157 + vertex -428.485 108.404 68.0045 + vertex -430.405 103.922 67.7076 + endloop + endfacet + facet normal 0.85248 -0.396578 0.340594 + outer loop + vertex -428.342 107.33 66.0721 + vertex -428.212 108.757 67.4084 + vertex -429.83 104.214 66.1694 + endloop + endfacet + facet normal 0.881869 -0.387439 0.268696 + outer loop + vertex -429.83 104.214 66.1694 + vertex -428.212 108.757 67.4084 + vertex -430.033 104.617 67.4157 + endloop + endfacet + facet normal 0.849821 -0.445173 0.282179 + outer loop + vertex -429.83 104.214 66.1694 + vertex -430.033 104.617 67.4157 + vertex -431.45 101.087 66.1131 + endloop + endfacet + facet normal 0.83943 -0.44956 0.305375 + outer loop + vertex -431.45 101.087 66.1131 + vertex -430.033 104.617 67.4157 + vertex -432.025 100.52 66.862 + endloop + endfacet + facet normal 0.892144 -0.444686 0.0795873 + outer loop + vertex -430.033 104.617 67.4157 + vertex -430.405 103.922 67.7076 + vertex -432.025 100.52 66.862 + endloop + endfacet + facet normal 0.852157 -0.465352 0.239326 + outer loop + vertex -432.025 100.52 66.862 + vertex -430.405 103.922 67.7076 + vertex -432.397 99.9829 67.142 + endloop + endfacet + facet normal 0.915838 -0.335148 0.221173 + outer loop + vertex -428.485 108.404 68.0045 + vertex -428.212 108.757 67.4084 + vertex -425.903 115.477 68.0317 + endloop + endfacet + facet normal 0.875828 -0.333265 0.349084 + outer loop + vertex -428.212 108.757 67.4084 + vertex -426.855 111.389 66.5163 + vertex -425.903 115.477 68.0317 + endloop + endfacet + facet normal 0.902573 -0.270782 0.334723 + outer loop + vertex -422.854 125.766 68.1346 + vertex -425.903 115.477 68.0317 + vertex -423.987 120.256 66.7318 + endloop + endfacet + facet normal 0.923169 -0.235619 0.303716 + outer loop + vertex -420.604 134.678 68.2079 + vertex -422.854 125.766 68.1346 + vertex -421.258 130.632 67.0583 + endloop + endfacet + facet normal 0.316464 0.230779 -0.920104 + outer loop + vertex -457.724 76.83 56.6803 + vertex -458.389 76.4934 56.3672 + vertex -461.966 75.0965 54.7867 + endloop + endfacet + facet normal 0.297651 0.272968 -0.914818 + outer loop + vertex -461.966 75.0965 54.7867 + vertex -458.389 76.4934 56.3672 + vertex -462.041 75.0139 54.7376 + endloop + endfacet + facet normal 0.303256 0.267721 -0.914528 + outer loop + vertex -461.966 75.0965 54.7867 + vertex -462.041 75.0139 54.7376 + vertex -466.885 73.4208 52.6648 + endloop + endfacet + facet normal 0.450575 -0.258308 -0.854552 + outer loop + vertex -466.885 73.4208 52.6648 + vertex -462.041 75.0139 54.7376 + vertex -464.29 74.1954 53.7992 + endloop + endfacet + facet normal 0.58446 -0.619019 -0.524616 + outer loop + vertex -450.034 80.9137 60.0099 + vertex -450.708 80.4803 59.7709 + vertex -453.761 78.7569 58.4024 + endloop + endfacet + facet normal 0.285466 -0.852901 0.437115 + outer loop + vertex -453.761 78.7569 58.4024 + vertex -450.708 80.4803 59.7709 + vertex -454.724 78.2361 58.0151 + endloop + endfacet + facet normal 0.528176 -0.433943 -0.72988 + outer loop + vertex -453.761 78.7569 58.4024 + vertex -454.724 78.2361 58.0151 + vertex -457.724 76.83 56.6803 + endloop + endfacet + facet normal 0.0984539 0.566586 -0.8181 + outer loop + vertex -457.724 76.83 56.6803 + vertex -454.724 78.2361 58.0151 + vertex -458.389 76.4934 56.3672 + endloop + endfacet + facet normal -0.0436897 0.52015 -0.852957 + outer loop + vertex -443.307 85.9639 63.0114 + vertex -444.018 85.2422 62.6077 + vertex -446.58 83.289 61.5478 + endloop + endfacet + facet normal -0.341014 0.752731 -0.563122 + outer loop + vertex -446.58 83.289 61.5478 + vertex -444.018 85.2422 62.6077 + vertex -447.167 82.7844 61.2293 + endloop + endfacet + facet normal 0.04889 0.491772 -0.86935 + outer loop + vertex -446.58 83.289 61.5478 + vertex -447.167 82.7844 61.2293 + vertex -450.034 80.9137 60.0099 + endloop + endfacet + facet normal 0.510168 -0.853096 0.109343 + outer loop + vertex -450.034 80.9137 60.0099 + vertex -447.167 82.7844 61.2293 + vertex -450.708 80.4803 59.7709 + endloop + endfacet + facet normal -0.324605 0.533145 -0.781273 + outer loop + vertex -437.347 92.3714 65.4426 + vertex -437.823 91.6475 65.1464 + vertex -440.21 88.9895 64.3245 + endloop + endfacet + facet normal -0.605102 0.674353 -0.423202 + outer loop + vertex -440.21 88.9895 64.3245 + vertex -437.823 91.6475 65.1464 + vertex -440.743 88.2874 63.9682 + endloop + endfacet + facet normal -0.220188 0.569181 -0.792181 + outer loop + vertex -440.21 88.9895 64.3245 + vertex -440.743 88.2874 63.9682 + vertex -443.307 85.9639 63.0114 + endloop + endfacet + facet normal -0.520639 0.745689 -0.415792 + outer loop + vertex -443.307 85.9639 63.0114 + vertex -440.743 88.2874 63.9682 + vertex -444.018 85.2422 62.6077 + endloop + endfacet + facet normal -0.713795 0.519243 -0.469982 + outer loop + vertex -432.397 99.9829 67.142 + vertex -432.677 99.4429 66.9698 + vertex -434.711 96.1056 66.3729 + endloop + endfacet + facet normal -0.851607 0.523602 -0.0246156 + outer loop + vertex -434.711 96.1056 66.3729 + vertex -432.677 99.4429 66.9698 + vertex -435.151 95.3795 66.1368 + endloop + endfacet + facet normal -0.512453 0.529968 -0.675667 + outer loop + vertex -434.711 96.1056 66.3729 + vertex -435.151 95.3795 66.1368 + vertex -437.347 92.3714 65.4426 + endloop + endfacet + facet normal -0.736921 0.606681 -0.298137 + outer loop + vertex -437.347 92.3714 65.4426 + vertex -435.151 95.3795 66.1368 + vertex -437.823 91.6475 65.1464 + endloop + endfacet + facet normal 0.176681 -0.0105036 -0.984212 + outer loop + vertex -428.485 108.404 68.0045 + vertex -429.321 106.172 67.8782 + vertex -430.405 103.922 67.7076 + endloop + endfacet + facet normal -0.737835 0.396805 -0.546027 + outer loop + vertex -430.405 103.922 67.7076 + vertex -429.321 106.172 67.8782 + vertex -430.91 102.754 67.5416 + endloop + endfacet + facet normal 0.0194121 0.132495 -0.990994 + outer loop + vertex -430.405 103.922 67.7076 + vertex -430.91 102.754 67.5416 + vertex -432.397 99.9829 67.142 + endloop + endfacet + facet normal -0.871382 0.481289 -0.0951527 + outer loop + vertex -432.397 99.9829 67.142 + vertex -430.91 102.754 67.5416 + vertex -432.677 99.4429 66.9698 + endloop + endfacet + facet normal 0.0798217 -0.834336 0.545447 + outer loop + vertex 487.968 64.8045 36.7114 + vertex 493.585 66.4385 38.389 + vertex 489.544 65.4607 37.4846 + endloop + endfacet + facet normal 0.0362816 -0.740803 0.670741 + outer loop + vertex 480.327 62.7231 34.8259 + vertex 487.968 64.8045 36.7114 + vertex 482.501 63.4894 35.5546 + endloop + endfacet + facet normal 0.0163534 -0.660528 0.750623 + outer loop + vertex 472.256 60.5973 33.1312 + vertex 480.327 62.7231 34.8259 + vertex 474.677 61.3994 33.7842 + endloop + endfacet + facet normal 0.0766613 -0.753233 0.653271 + outer loop + vertex 467.047 59.2584 32.1987 + vertex 472.256 60.5973 33.1312 + vertex 466.487 59.2724 32.2804 + endloop + endfacet + facet normal 0.0824792 -0.721327 0.687666 + outer loop + vertex 461.055 57.7994 31.3869 + vertex 467.047 59.2584 32.1987 + vertex 466.487 59.2724 32.2804 + endloop + endfacet + facet normal -0.0793872 -0.141613 0.986734 + outer loop + vertex 452.868 55.8647 30.4505 + vertex 461.055 57.7994 31.3869 + vertex 456.567 56.7816 30.8797 + endloop + endfacet + facet normal 0.0584908 -0.585806 0.808338 + outer loop + vertex 443.789 53.8676 29.6601 + vertex 452.868 55.8647 30.4505 + vertex 451.501 55.8933 30.5701 + endloop + endfacet + facet normal 0.0470213 -0.502929 0.863048 + outer loop + vertex 436.889 52.3992 29.1803 + vertex 443.789 53.8676 29.6601 + vertex 436.436 53.1747 29.6569 + endloop + endfacet + facet normal 0.0592358 -0.497329 0.865537 + outer loop + vertex 428.859 50.6223 28.7089 + vertex 436.889 52.3992 29.1803 + vertex 436.436 53.1747 29.6569 + endloop + endfacet + facet normal 0.0466841 -0.440855 0.896363 + outer loop + vertex 421.784 48.9642 28.2619 + vertex 428.859 50.6223 28.7089 + vertex 418.518 49.0769 28.4874 + endloop + endfacet + facet normal 0.0488474 -0.408414 0.911489 + outer loop + vertex 418.28 48.1905 28.103 + vertex 421.784 48.9642 28.2619 + vertex 418.518 49.0769 28.4874 + endloop + endfacet + facet normal 0.0575414 -0.410182 0.910187 + outer loop + vertex 410.834 46.6771 27.8917 + vertex 418.28 48.1905 28.103 + vertex 418.518 49.0769 28.4874 + endloop + endfacet + facet normal -0.0724173 -0.480955 0.87375 + outer loop + vertex -418.729 48.3235 28.1459 + vertex -412.125 46.9935 27.9611 + vertex -421.669 49.5758 28.5915 + endloop + endfacet + facet normal -0.0636705 -0.463915 0.883589 + outer loop + vertex -422.084 49.0503 28.2856 + vertex -418.729 48.3235 28.1459 + vertex -421.669 49.5758 28.5915 + endloop + endfacet + facet normal -0.0568069 -0.46827 0.881757 + outer loop + vertex -428.804 50.5731 28.6614 + vertex -422.084 49.0503 28.2856 + vertex -421.669 49.5758 28.5915 + endloop + endfacet + facet normal -0.0756441 -0.553948 0.829108 + outer loop + vertex -437.14 52.3557 29.0919 + vertex -428.804 50.5731 28.6614 + vertex -437.986 53.2889 29.6382 + endloop + endfacet + facet normal -0.059564 -0.543979 0.836982 + outer loop + vertex -444.401 54.0234 29.6591 + vertex -437.14 52.3557 29.0919 + vertex -437.986 53.2889 29.6382 + endloop + endfacet + facet normal -0.0527776 -0.567438 0.821723 + outer loop + vertex -453.731 56.0827 30.4819 + vertex -444.401 54.0234 29.6591 + vertex -450.561 55.8553 30.5284 + endloop + endfacet + facet normal -0.0207803 -0.523658 0.851675 + outer loop + vertex -462.275 58.0767 31.4994 + vertex -453.731 56.0827 30.4819 + vertex -460.292 57.7565 31.3509 + endloop + endfacet + facet normal -0.102582 -0.776195 0.622092 + outer loop + vertex -467.436 59.3423 32.2275 + vertex -462.275 58.0767 31.4994 + vertex -468.361 59.7471 32.5801 + endloop + endfacet + facet normal -0.0698891 -0.741168 0.667672 + outer loop + vertex -472.834 60.7471 33.2218 + vertex -467.436 59.3423 32.2275 + vertex -468.361 59.7471 32.5801 + endloop + endfacet + facet normal -0.0519842 -0.733129 0.6781 + outer loop + vertex -480.386 62.7394 34.7969 + vertex -472.834 60.7471 33.2218 + vertex -477.119 62.034 34.2847 + endloop + endfacet + facet normal -0.0458552 -0.757464 0.651264 + outer loop + vertex -486.939 64.5184 36.4045 + vertex -480.386 62.7394 34.7969 + vertex -484.301 63.9096 35.8822 + endloop + endfacet + facet normal -0.0999349 -0.869487 0.483741 + outer loop + vertex -498.556 67.9088 40.0162 + vertex -492.742 66.1796 38.1092 + vertex -494.377 66.738 38.775 + endloop + endfacet + facet normal -0.908795 -0.333144 0.25121 + outer loop + vertex 427.875 109.59 67.9713 + vertex 426.378 114.06 68.4811 + vertex 426.269 113.122 66.8437 + endloop + endfacet + facet normal -0.913553 -0.381304 0.14152 + outer loop + vertex 429.036 106.836 68.0439 + vertex 427.875 109.59 67.9713 + vertex 429.066 106.646 67.7224 + endloop + endfacet + facet normal -0.880427 -0.439185 0.178786 + outer loop + vertex 430.518 103.703 67.6434 + vertex 429.036 106.836 68.0439 + vertex 429.066 106.646 67.7224 + endloop + endfacet + facet normal -0.808642 -0.481922 0.337416 + outer loop + vertex 433.147 98.7682 66.897 + vertex 430.518 103.703 67.6434 + vertex 431.655 101.239 66.8493 + endloop + endfacet + facet normal -0.764081 -0.542199 0.349571 + outer loop + vertex 435.859 94.3347 65.9483 + vertex 433.147 98.7682 66.897 + vertex 434.082 96.9333 66.0956 + endloop + endfacet + facet normal -0.741678 -0.610241 0.278423 + outer loop + vertex 438.205 91.0982 65.1034 + vertex 435.859 94.3347 65.9483 + vertex 436.675 92.9869 65.1675 + endloop + endfacet + facet normal -0.71463 -0.679937 0.164285 + outer loop + vertex 440.169 88.9274 64.6633 + vertex 438.205 91.0982 65.1034 + vertex 439.642 89.3416 64.0867 + endloop + endfacet + facet normal -0.67046 -0.737321 0.0827176 + outer loop + vertex 442.342 86.85 63.7625 + vertex 440.169 88.9274 64.6633 + vertex 439.642 89.3416 64.0867 + endloop + endfacet + facet normal -0.557819 -0.787265 0.262779 + outer loop + vertex 445.185 84.4935 62.7364 + vertex 442.342 86.85 63.7625 + vertex 442.604 86.3357 62.7758 + endloop + endfacet + facet normal -0.489981 -0.821389 0.291955 + outer loop + vertex 447.799 82.5245 61.5846 + vertex 445.185 84.4935 62.7364 + vertex 445.649 83.7559 61.4395 + endloop + endfacet + facet normal -0.428992 -0.855282 0.290617 + outer loop + vertex 450.318 81.1049 61.1249 + vertex 447.799 82.5245 61.5846 + vertex 449.448 81.1605 60.0037 + endloop + endfacet + facet normal -0.390911 -0.883036 0.259684 + outer loop + vertex 453.308 79.3457 59.644 + vertex 450.318 81.1049 61.1249 + vertex 449.448 81.1605 60.0037 + endloop + endfacet + facet normal -0.323342 -0.892273 0.315118 + outer loop + vertex 456.166 77.7383 58.0245 + vertex 453.308 79.3457 59.644 + vertex 453.17 78.9168 58.2876 + endloop + endfacet + facet normal -0.261562 -0.907172 0.329581 + outer loop + vertex 459.271 76.3776 56.7436 + vertex 456.166 77.7383 58.0245 + vertex 456.726 77.1178 56.761 + endloop + endfacet + facet normal -0.20423 -0.914358 0.349628 + outer loop + vertex 462.868 74.9382 55.0804 + vertex 459.271 76.3776 56.7436 + vertex 460.324 75.5466 55.1855 + endloop + endfacet + facet normal -0.151738 -0.916519 0.370093 + outer loop + vertex 466.632 73.5973 53.3027 + vertex 462.868 74.9382 55.0804 + vertex 463.769 74.126 53.4382 + endloop + endfacet + facet normal 0.00749758 -0.912903 0.408108 + outer loop + vertex 483.594 69.8188 46.3324 + vertex 478.952 70.5579 48.071 + vertex 481.522 69.7293 46.1702 + endloop + endfacet + facet normal 0.0430612 -0.9046 0.424081 + outer loop + vertex 488.004 69.0578 44.2613 + vertex 483.594 69.8188 46.3324 + vertex 485.456 69.1228 44.6588 + endloop + endfacet + facet normal 0.0664838 -0.898297 0.43433 + outer loop + vertex 491.796 68.535 42.5996 + vertex 488.004 69.0578 44.2613 + vertex 489.406 68.5579 43.0128 + endloop + endfacet + facet normal -0.0535823 -0.909609 0.411996 + outer loop + vertex -488.074 69.029 44.1878 + vertex -491.892 68.4973 42.5175 + vertex -490.537 68.6115 42.9458 + endloop + endfacet + facet normal -0.0297426 -0.916719 0.398423 + outer loop + vertex -483.565 69.7951 46.2872 + vertex -488.074 69.029 44.1878 + vertex -486.465 69.1454 44.5758 + endloop + endfacet + facet normal 0.161521 -0.922117 0.351584 + outer loop + vertex -462.557 74.951 54.9852 + vertex -466.152 73.7698 53.5388 + vertex -464.29 74.1954 53.7992 + endloop + endfacet + facet normal 0.245985 -0.928687 0.277546 + outer loop + vertex -459.24 76.2785 56.4868 + vertex -462.557 74.951 54.9852 + vertex -462.041 75.0139 54.7376 + endloop + endfacet + facet normal 0.273322 -0.912544 0.304235 + outer loop + vertex -456.272 77.5985 57.78 + vertex -459.24 76.2785 56.4868 + vertex -458.389 76.4934 56.3672 + endloop + endfacet + facet normal 0.318645 -0.891887 0.320941 + outer loop + vertex -453.29 79.2621 59.4419 + vertex -456.272 77.5985 57.78 + vertex -454.724 78.2361 58.0151 + endloop + endfacet + facet normal 0.376122 -0.877517 0.297484 + outer loop + vertex -450.171 81.1098 60.9486 + vertex -453.29 79.2621 59.4419 + vertex -450.708 80.4803 59.7709 + endloop + endfacet + facet normal 0.434331 -0.861666 0.262465 + outer loop + vertex -447.945 82.3518 61.3426 + vertex -450.171 81.1098 60.9486 + vertex -450.708 80.4803 59.7709 + endloop + endfacet + facet normal 0.498106 -0.825108 0.266623 + outer loop + vertex -445.302 84.3246 62.5116 + vertex -447.945 82.3518 61.3426 + vertex -447.167 82.7844 61.2293 + endloop + endfacet + facet normal 0.54014 -0.787056 0.297978 + outer loop + vertex -442.386 86.7195 63.5504 + vertex -445.302 84.3246 62.5116 + vertex -444.018 85.2422 62.6077 + endloop + endfacet + facet normal 0.70264 -0.692698 -0.162682 + outer loop + vertex -440.209 88.7546 64.2888 + vertex -442.386 86.7195 63.5504 + vertex -440.743 88.2874 63.9682 + endloop + endfacet + facet normal 0.72348 -0.505814 -0.469817 + outer loop + vertex -438.354 90.864 64.8733 + vertex -440.209 88.7546 64.2888 + vertex -440.743 88.2874 63.9682 + endloop + endfacet + facet normal -0.626057 0.598764 -0.499534 + outer loop + vertex -435.946 94.1219 65.7604 + vertex -438.354 90.864 64.8733 + vertex -437.823 91.6475 65.1464 + endloop + endfacet + facet normal -0.853631 0.513413 0.0878647 + outer loop + vertex -433.2 98.5256 66.7107 + vertex -435.946 94.1219 65.7604 + vertex -435.151 95.3795 66.1368 + endloop + endfacet + facet normal -0.872415 0.433757 0.225271 + outer loop + vertex -430.606 103.355 67.4573 + vertex -433.2 98.5256 66.7107 + vertex -432.677 99.4429 66.9698 + endloop + endfacet + facet normal -0.874036 0.431832 -0.222672 + outer loop + vertex -428.862 107.101 67.8793 + vertex -430.606 103.355 67.4573 + vertex -429.321 106.172 67.8782 + endloop + endfacet + facet normal -0.634812 0.314314 -0.705847 + outer loop + vertex -427.721 110.223 68.2425 + vertex -428.862 107.101 67.8793 + vertex -429.321 106.172 67.8782 + endloop + endfacet + facet normal 0.940236 -0.320698 0.114491 + outer loop + vertex -426.434 114.236 68.9178 + vertex -427.721 110.223 68.2425 + vertex -425.903 115.477 68.0317 + endloop + endfacet + facet normal 0.942461 -0.303873 0.139388 + outer loop + vertex -425.509 117.193 69.1083 + vertex -426.434 114.236 68.9178 + vertex -425.903 115.477 68.0317 + endloop + endfacet + facet normal 0.955742 -0.278666 0.0943547 + outer loop + vertex -424.284 121.405 69.1435 + vertex -425.509 117.193 69.1083 + vertex -425.903 115.477 68.0317 + endloop + endfacet + facet normal 0.949232 -0.276583 0.149872 + outer loop + vertex -423.125 125.318 69.0198 + vertex -424.284 121.405 69.1435 + vertex -422.854 125.766 68.1346 + endloop + endfacet + facet normal 0.953539 -0.253417 0.162919 + outer loop + vertex -422.621 127.202 69.0046 + vertex -423.125 125.318 69.0198 + vertex -422.854 125.766 68.1346 + endloop + endfacet + facet normal 0.961988 -0.237627 0.134586 + outer loop + vertex -421.713 130.924 69.0862 + vertex -422.621 127.202 69.0046 + vertex -422.854 125.766 68.1346 + endloop + endfacet + facet normal 0.00901477 -0.919713 0.392489 + outer loop + vertex 481.522 69.7293 46.1702 + vertex 485.456 69.1228 44.6588 + vertex 483.594 69.8188 46.3324 + endloop + endfacet + facet normal 0.0407869 -0.910931 0.410538 + outer loop + vertex 485.456 69.1228 44.6588 + vertex 489.406 68.5579 43.0128 + vertex 488.004 69.0578 44.2613 + endloop + endfacet + facet normal -0.263611 -0.913741 0.30917 + outer loop + vertex 456.726 77.1178 56.761 + vertex 460.324 75.5466 55.1855 + vertex 459.271 76.3776 56.7436 + endloop + endfacet + facet normal -0.205291 -0.917325 0.341131 + outer loop + vertex 460.324 75.5466 55.1855 + vertex 463.769 74.126 53.4382 + vertex 462.868 74.9382 55.0804 + endloop + endfacet + facet normal -0.140985 -0.911951 0.385315 + outer loop + vertex 463.769 74.126 53.4382 + vertex 463.059 73.712 52.1987 + vertex 466.71 72.7038 51.1486 + endloop + endfacet + facet normal -0.379819 -0.870182 0.313882 + outer loop + vertex 449.448 81.1605 60.0037 + vertex 453.17 78.9168 58.2876 + vertex 453.308 79.3457 59.644 + endloop + endfacet + facet normal -0.3271 -0.897507 0.295782 + outer loop + vertex 453.17 78.9168 58.2876 + vertex 456.726 77.1178 56.761 + vertex 456.166 77.7383 58.0245 + endloop + endfacet + facet normal -0.560059 -0.790111 0.249115 + outer loop + vertex 442.604 86.3357 62.7758 + vertex 445.649 83.7559 61.4395 + vertex 445.185 84.4935 62.7364 + endloop + endfacet + facet normal -0.496468 -0.84247 0.209201 + outer loop + vertex 445.649 83.7559 61.4395 + vertex 449.448 81.1605 60.0037 + vertex 447.799 82.5245 61.5846 + endloop + endfacet + facet normal -0.77719 -0.629153 -0.0119168 + outer loop + vertex 436.675 92.9869 65.1675 + vertex 439.642 89.3416 64.0867 + vertex 438.205 91.0982 65.1034 + endloop + endfacet + facet normal -0.649471 -0.731038 0.209213 + outer loop + vertex 439.642 89.3416 64.0867 + vertex 442.604 86.3357 62.7758 + vertex 442.342 86.85 63.7625 + endloop + endfacet + facet normal -0.844328 -0.506625 0.174475 + outer loop + vertex 431.655 101.239 66.8493 + vertex 434.082 96.9333 66.0956 + vertex 433.147 98.7682 66.897 + endloop + endfacet + facet normal -0.81606 -0.564864 0.122372 + outer loop + vertex 434.082 96.9333 66.0956 + vertex 436.675 92.9869 65.1675 + vertex 435.859 94.3347 65.9483 + endloop + endfacet + facet normal -0.895167 -0.381408 0.230661 + outer loop + vertex 428.07 108.374 66.716 + vertex 429.066 106.646 67.7224 + vertex 427.875 109.59 67.9713 + endloop + endfacet + facet normal -0.86268 -0.432659 0.261894 + outer loop + vertex 429.066 106.646 67.7224 + vertex 429.872 104.773 67.2849 + vertex 430.518 103.703 67.6434 + endloop + endfacet + facet normal -0.867619 -0.460691 0.187084 + outer loop + vertex 429.872 104.773 67.2849 + vertex 431.655 101.239 66.8493 + vertex 430.518 103.703 67.6434 + endloop + endfacet + facet normal 0.0903199 -0.842537 0.531012 + outer loop + vertex 489.544 65.4607 37.4846 + vertex 482.501 63.4894 35.5546 + vertex 487.968 64.8045 36.7114 + endloop + endfacet + facet normal -0.923019 -0.3042 0.23558 + outer loop + vertex 424.829 117.818 67.2662 + vertex 426.269 113.122 66.8437 + vertex 426.378 114.06 68.4811 + endloop + endfacet + facet normal -0.914419 -0.352234 0.199424 + outer loop + vertex 426.269 113.122 66.8437 + vertex 428.07 108.374 66.716 + vertex 427.875 109.59 67.9713 + endloop + endfacet + facet normal 0.0820988 -0.766468 0.637013 + outer loop + vertex 474.677 61.3994 33.7842 + vertex 466.487 59.2724 32.2804 + vertex 472.256 60.5973 33.1312 + endloop + endfacet + facet normal 0.0705331 -0.785206 0.615205 + outer loop + vertex 482.501 63.4894 35.5546 + vertex 474.677 61.3994 33.7842 + vertex 480.327 62.7231 34.8259 + endloop + endfacet + facet normal 0.0490258 -0.610214 0.790718 + outer loop + vertex 459.458 57.5535 31.2961 + vertex 456.567 56.7816 30.8797 + vertex 461.055 57.7994 31.3869 + endloop + endfacet + facet normal 0.0570473 -0.602745 0.795892 + outer loop + vertex 456.567 56.7816 30.8797 + vertex 451.501 55.8933 30.5701 + vertex 452.868 55.8647 30.4505 + endloop + endfacet + facet normal 0.0622158 -0.675273 0.734939 + outer loop + vertex 466.487 59.2724 32.2804 + vertex 459.458 57.5535 31.2961 + vertex 461.055 57.7994 31.3869 + endloop + endfacet + facet normal 0.0535074 -0.571543 0.818826 + outer loop + vertex 451.501 55.8933 30.5701 + vertex 436.436 53.1747 29.6569 + vertex 443.789 53.8676 29.6601 + endloop + endfacet + facet normal 0.0535339 -0.483447 0.873735 + outer loop + vertex 436.436 53.1747 29.6569 + vertex 418.518 49.0769 28.4874 + vertex 428.859 50.6223 28.7089 + endloop + endfacet + facet normal 0.0431541 -0.368673 0.928557 + outer loop + vertex 418.518 49.0769 28.4874 + vertex 402.179 45.6762 27.8965 + vertex 410.834 46.6771 27.8917 + endloop + endfacet + facet normal -0.0498876 -0.407031 0.912051 + outer loop + vertex -406.588 46.5443 28.0635 + vertex -421.669 49.5758 28.5915 + vertex -412.125 46.9935 27.9611 + endloop + endfacet + facet normal -0.0650981 -0.525251 0.848454 + outer loop + vertex -421.669 49.5758 28.5915 + vertex -437.986 53.2889 29.6382 + vertex -428.804 50.5731 28.6614 + endloop + endfacet + facet normal -0.0661875 -0.600679 0.796746 + outer loop + vertex -437.986 53.2889 29.6382 + vertex -450.561 55.8553 30.5284 + vertex -444.401 54.0234 29.6591 + endloop + endfacet + facet normal -0.0531017 -0.671574 0.739033 + outer loop + vertex -460.292 57.7565 31.3509 + vertex -468.361 59.7471 32.5801 + vertex -462.275 58.0767 31.4994 + endloop + endfacet + facet normal -0.0528942 -0.569334 0.820403 + outer loop + vertex -450.561 55.8553 30.5284 + vertex -455.27 56.6034 30.744 + vertex -453.731 56.0827 30.4819 + endloop + endfacet + facet normal 0.0149746 -0.413889 0.910204 + outer loop + vertex -455.27 56.6034 30.744 + vertex -460.292 57.7565 31.3509 + vertex -453.731 56.0827 30.4819 + endloop + endfacet + facet normal -0.0884893 -0.820228 0.565151 + outer loop + vertex -477.119 62.034 34.2847 + vertex -484.301 63.9096 35.8822 + vertex -480.386 62.7394 34.7969 + endloop + endfacet + facet normal -0.0948132 -0.802351 0.589274 + outer loop + vertex -468.361 59.7471 32.5801 + vertex -477.119 62.034 34.2847 + vertex -472.834 60.7471 33.2218 + endloop + endfacet + facet normal 0.358158 -0.839417 0.40878 + outer loop + vertex -451.42 78.0081 55.0872 + vertex -447.928 80.2557 56.6429 + vertex -449.134 80.7713 58.7587 + endloop + endfacet + facet normal 0.512684 -0.766154 0.387508 + outer loop + vertex -444.566 82.7885 58.1414 + vertex -441.382 85.6114 59.5105 + vertex -442.402 86.0185 61.6649 + endloop + endfacet + facet normal 0.430893 -0.808791 0.400236 + outer loop + vertex -447.928 80.2557 56.6429 + vertex -444.566 82.7885 58.1414 + vertex -445.676 83.248 60.2653 + endloop + endfacet + facet normal 0.668754 -0.643001 0.373254 + outer loop + vertex -438.41 88.7238 60.6652 + vertex -435.708 92.0459 61.5462 + vertex -436.494 92.5614 63.8432 + endloop + endfacet + facet normal 0.596548 -0.709071 0.375965 + outer loop + vertex -441.382 85.6114 59.5105 + vertex -438.41 88.7238 60.6652 + vertex -439.343 89.1041 62.8628 + endloop + endfacet + facet normal 0.785169 -0.510604 0.35042 + outer loop + vertex -433.591 94.896 61.8896 + vertex -431.492 99.2822 63.5786 + vertex -433.663 96.6613 64.624 + endloop + endfacet + facet normal 0.71509 -0.578504 0.392402 + outer loop + vertex -435.708 92.0459 61.5462 + vertex -433.591 94.896 61.8896 + vertex -433.663 96.6613 64.624 + endloop + endfacet + facet normal 0.828082 -0.452758 0.330592 + outer loop + vertex -431.492 99.2822 63.5786 + vertex -429.237 103.659 63.9237 + vertex -429.83 104.214 66.1694 + endloop + endfacet + facet normal -0.0156368 -0.937995 0.346297 + outer loop + vertex -490.537 68.6115 42.9458 + vertex -486.465 69.1454 44.5758 + vertex -488.074 69.029 44.1878 + endloop + endfacet + facet normal 0.19662 -0.965105 0.172951 + outer loop + vertex -472.964 71.7268 50.1224 + vertex -466.885 73.4208 52.6648 + vertex -470.074 72.615 51.794 + endloop + endfacet + facet normal 0.476806 -0.773963 0.416698 + outer loop + vertex -442.402 86.0185 61.6649 + vertex -445.676 83.248 60.2653 + vertex -444.566 82.7885 58.1414 + endloop + endfacet + facet normal 0.39743 -0.813372 0.424824 + outer loop + vertex -445.676 83.248 60.2653 + vertex -449.134 80.7713 58.7587 + vertex -447.928 80.2557 56.6429 + endloop + endfacet + facet normal 0.653421 -0.648974 0.38971 + outer loop + vertex -436.494 92.5614 63.8432 + vertex -439.343 89.1041 62.8628 + vertex -438.41 88.7238 60.6652 + endloop + endfacet + facet normal 0.566434 -0.71833 0.403924 + outer loop + vertex -439.343 89.1041 62.8628 + vertex -442.402 86.0185 61.6649 + vertex -441.382 85.6114 59.5105 + endloop + endfacet + facet normal 0.785178 -0.510641 0.350346 + outer loop + vertex -431.45 101.087 66.1131 + vertex -433.663 96.6613 64.624 + vertex -431.492 99.2822 63.5786 + endloop + endfacet + facet normal 0.726765 -0.573796 0.377585 + outer loop + vertex -433.663 96.6613 64.624 + vertex -436.494 92.5614 63.8432 + vertex -435.708 92.0459 61.5462 + endloop + endfacet + facet normal 0.844573 -0.442795 0.301047 + outer loop + vertex -429.83 104.214 66.1694 + vertex -431.45 101.087 66.1131 + vertex -431.492 99.2822 63.5786 + endloop + endfacet + facet normal 0.870401 -0.316267 -0.37733 + outer loop + vertex -428.485 108.404 68.0045 + vertex -425.903 115.477 68.0317 + vertex -427.721 110.223 68.2425 + endloop + endfacet + facet normal 0.950995 -0.283026 0.124517 + outer loop + vertex -425.903 115.477 68.0317 + vertex -422.854 125.766 68.1346 + vertex -424.284 121.405 69.1435 + endloop + endfacet + facet normal 0.955169 -0.242597 0.1697 + outer loop + vertex -422.854 125.766 68.1346 + vertex -420.604 134.678 68.2079 + vertex -421.713 130.924 69.0862 + endloop + endfacet + facet normal 0.26953 -0.932022 0.242256 + outer loop + vertex -462.041 75.0139 54.7376 + vertex -458.389 76.4934 56.3672 + vertex -459.24 76.2785 56.4868 + endloop + endfacet + facet normal 0.187002 -0.956228 0.225072 + outer loop + vertex -466.885 73.4208 52.6648 + vertex -464.29 74.1954 53.7992 + vertex -466.152 73.7698 53.5388 + endloop + endfacet + facet normal 0.235642 -0.938182 0.253549 + outer loop + vertex -464.29 74.1954 53.7992 + vertex -462.041 75.0139 54.7376 + vertex -462.557 74.951 54.9852 + endloop + endfacet + facet normal 0.38711 -0.887743 0.249114 + outer loop + vertex -454.724 78.2361 58.0151 + vertex -450.708 80.4803 59.7709 + vertex -453.29 79.2621 59.4419 + endloop + endfacet + facet normal 0.34794 -0.916845 0.195789 + outer loop + vertex -458.389 76.4934 56.3672 + vertex -454.724 78.2361 58.0151 + vertex -456.272 77.5985 57.78 + endloop + endfacet + facet normal 0.567781 -0.809935 0.147072 + outer loop + vertex -447.167 82.7844 61.2293 + vertex -444.018 85.2422 62.6077 + vertex -445.302 84.3246 62.5116 + endloop + endfacet + facet normal 0.497219 -0.855496 0.144569 + outer loop + vertex -450.708 80.4803 59.7709 + vertex -447.167 82.7844 61.2293 + vertex -447.945 82.3518 61.3426 + endloop + endfacet + facet normal 0.0104662 0.322754 -0.946425 + outer loop + vertex -440.743 88.2874 63.9682 + vertex -437.823 91.6475 65.1464 + vertex -438.354 90.864 64.8733 + endloop + endfacet + facet normal 0.700725 -0.705139 -0.10846 + outer loop + vertex -444.018 85.2422 62.6077 + vertex -440.743 88.2874 63.9682 + vertex -442.386 86.7195 63.5504 + endloop + endfacet + facet normal -0.754332 0.536802 -0.377925 + outer loop + vertex -435.151 95.3795 66.1368 + vertex -432.677 99.4429 66.9698 + vertex -433.2 98.5256 66.7107 + endloop + endfacet + facet normal -0.334053 0.457795 -0.823912 + outer loop + vertex -437.823 91.6475 65.1464 + vertex -435.151 95.3795 66.1368 + vertex -435.946 94.1219 65.7604 + endloop + endfacet + facet normal 0.819889 -0.27901 -0.499935 + outer loop + vertex -429.321 106.172 67.8782 + vertex -428.485 108.404 68.0045 + vertex -427.721 110.223 68.2425 + endloop + endfacet + facet normal -0.889766 0.429011 -0.155774 + outer loop + vertex -430.91 102.754 67.5416 + vertex -429.321 106.172 67.8782 + vertex -430.606 103.355 67.4573 + endloop + endfacet + facet normal -0.88514 0.459157 0.0755124 + outer loop + vertex -432.677 99.4429 66.9698 + vertex -430.91 102.754 67.5416 + vertex -430.606 103.355 67.4573 + endloop + endfacet + facet normal -0.151275 -0.91501 0.373996 + outer loop + vertex 466.632 73.5973 53.3027 + vertex 463.769 74.126 53.4382 + vertex 466.71 72.7038 51.1486 + endloop + endfacet + facet normal 0.0815554 -0.657244 0.749252 + outer loop + vertex 845.245 242.301 46.8136 + vertex 845.127 241.922 46.4934 + vertex 845.752 241.75 46.2749 + endloop + endfacet + facet normal 0.0498387 -0.600953 0.797729 + outer loop + vertex 844.624 241.5 46.2075 + vertex 845.032 240.933 45.7542 + vertex 845.127 241.922 46.4934 + endloop + endfacet + facet normal 0.111352 -0.601717 0.790909 + outer loop + vertex 845.032 240.933 45.7542 + vertex 845.752 241.75 46.2749 + vertex 845.127 241.922 46.4934 + endloop + endfacet + facet normal -0.20543 -0.556246 0.805226 + outer loop + vertex 840.507 245.707 49.0064 + vertex 840.299 245.382 48.7283 + vertex 841.708 244.379 48.395 + endloop + endfacet + facet normal -0.232619 -0.585041 0.776927 + outer loop + vertex 841.708 244.379 48.395 + vertex 840.299 245.382 48.7283 + vertex 841.488 244.095 48.1153 + endloop + endfacet + facet normal -0.193734 -0.522205 0.830523 + outer loop + vertex 840.507 246.041 49.2164 + vertex 840.507 245.707 49.0064 + vertex 841.672 244.66 48.6194 + endloop + endfacet + facet normal -0.31484 -0.616618 0.721566 + outer loop + vertex 841.672 244.66 48.6194 + vertex 840.507 245.707 49.0064 + vertex 841.708 244.379 48.395 + endloop + endfacet + facet normal -0.123028 -0.629017 0.767594 + outer loop + vertex 841.672 244.66 48.6194 + vertex 841.708 244.379 48.395 + vertex 843.013 243.611 47.9746 + endloop + endfacet + facet normal -0.188905 -0.698549 0.690176 + outer loop + vertex 843.013 243.611 47.9746 + vertex 841.708 244.379 48.395 + vertex 843.044 243.381 47.7509 + endloop + endfacet + facet normal -0.120705 -0.647424 0.752511 + outer loop + vertex 841.708 244.379 48.395 + vertex 841.488 244.095 48.1153 + vertex 843.044 243.381 47.7509 + endloop + endfacet + facet normal -0.109659 -0.631174 0.767851 + outer loop + vertex 843.044 243.381 47.7509 + vertex 841.488 244.095 48.1153 + vertex 842.799 243.077 47.466 + endloop + endfacet + facet normal -0.0362638 -0.390833 0.919747 + outer loop + vertex 840.449 246.372 49.3546 + vertex 840.507 246.041 49.2164 + vertex 841.439 245.053 48.8333 + endloop + endfacet + facet normal -0.325327 -0.592691 0.736804 + outer loop + vertex 841.439 245.053 48.8333 + vertex 840.507 246.041 49.2164 + vertex 841.672 244.66 48.6194 + endloop + endfacet + facet normal 0.0239611 -0.466276 0.884314 + outer loop + vertex 841.439 245.053 48.8333 + vertex 841.672 244.66 48.6194 + vertex 842.683 243.986 48.2369 + endloop + endfacet + facet normal -0.155399 -0.653767 0.740567 + outer loop + vertex 842.683 243.986 48.2369 + vertex 841.672 244.66 48.6194 + vertex 843.013 243.611 47.9746 + endloop + endfacet + facet normal 0.0650882 -0.532374 0.844003 + outer loop + vertex 842.683 243.986 48.2369 + vertex 843.013 243.611 47.9746 + vertex 844.178 243.065 47.5407 + endloop + endfacet + facet normal -0.0574445 -0.693887 0.717789 + outer loop + vertex 844.178 243.065 47.5407 + vertex 843.013 243.611 47.9746 + vertex 844.364 242.838 47.3362 + endloop + endfacet + facet normal 0.0892204 -0.62562 0.77501 + outer loop + vertex 844.178 243.065 47.5407 + vertex 844.364 242.838 47.3362 + vertex 845.459 242.464 46.9082 + endloop + endfacet + facet normal 0.10549 -0.599231 0.793596 + outer loop + vertex 845.459 242.464 46.9082 + vertex 844.364 242.838 47.3362 + vertex 845.245 242.301 46.8136 + endloop + endfacet + facet normal -0.0330075 -0.669208 0.742342 + outer loop + vertex 843.044 243.381 47.7509 + vertex 842.799 243.077 47.466 + vertex 844.304 242.613 47.1149 + endloop + endfacet + facet normal -0.0120395 -0.628137 0.778009 + outer loop + vertex 844.304 242.613 47.1149 + vertex 842.799 243.077 47.466 + vertex 843.983 242.232 46.8018 + endloop + endfacet + facet normal -0.065006 -0.700911 0.71028 + outer loop + vertex 843.013 243.611 47.9746 + vertex 843.044 243.381 47.7509 + vertex 844.364 242.838 47.3362 + endloop + endfacet + facet normal -0.0584801 -0.692063 0.719465 + outer loop + vertex 844.364 242.838 47.3362 + vertex 843.044 243.381 47.7509 + vertex 844.304 242.613 47.1149 + endloop + endfacet + facet normal -0.00380107 -0.700627 0.713517 + outer loop + vertex 844.364 242.838 47.3362 + vertex 844.304 242.613 47.1149 + vertex 845.245 242.301 46.8136 + endloop + endfacet + facet normal 0.0280023 -0.6495 0.759846 + outer loop + vertex 845.245 242.301 46.8136 + vertex 844.304 242.613 47.1149 + vertex 845.127 241.922 46.4934 + endloop + endfacet + facet normal 0.0293066 -0.648597 0.760567 + outer loop + vertex 844.304 242.613 47.1149 + vertex 843.983 242.232 46.8018 + vertex 845.127 241.922 46.4934 + endloop + endfacet + facet normal 0.0515838 -0.602281 0.796616 + outer loop + vertex 845.127 241.922 46.4934 + vertex 843.983 242.232 46.8018 + vertex 844.624 241.5 46.2075 + endloop + endfacet + facet normal -0.911136 -0.40175 -0.0918017 + outer loop + vertex 838.708 249.577 50.2758 + vertex 838.462 250.13 50.3006 + vertex 839.356 248.189 49.9272 + endloop + endfacet + facet normal -0.757475 -0.441225 0.481199 + outer loop + vertex 839.356 248.189 49.9272 + vertex 838.462 250.13 50.3006 + vertex 839.424 247.912 49.7813 + endloop + endfacet + facet normal -0.44459 -0.501558 0.742145 + outer loop + vertex 839.356 248.189 49.9272 + vertex 839.424 247.912 49.7813 + vertex 840.449 246.372 49.3546 + endloop + endfacet + facet normal -0.251383 -0.410209 0.876661 + outer loop + vertex 840.449 246.372 49.3546 + vertex 839.424 247.912 49.7813 + vertex 840.507 246.041 49.2164 + endloop + endfacet + facet normal -0.344141 -0.335084 0.877089 + outer loop + vertex 838.287 250.084 50.118 + vertex 838.382 249.074 49.7692 + vertex 839.43 247.488 49.5747 + endloop + endfacet + facet normal -0.425366 -0.381845 0.820523 + outer loop + vertex 839.43 247.488 49.5747 + vertex 838.382 249.074 49.7692 + vertex 839.257 247.065 49.2882 + endloop + endfacet + facet normal -0.600512 -0.419814 0.680545 + outer loop + vertex 838.462 250.13 50.3006 + vertex 838.287 250.084 50.118 + vertex 839.424 247.912 49.7813 + endloop + endfacet + facet normal -0.504643 -0.384006 0.773224 + outer loop + vertex 839.424 247.912 49.7813 + vertex 838.287 250.084 50.118 + vertex 839.43 247.488 49.5747 + endloop + endfacet + facet normal -0.282443 -0.423395 0.860792 + outer loop + vertex 839.424 247.912 49.7813 + vertex 839.43 247.488 49.5747 + vertex 840.507 246.041 49.2164 + endloop + endfacet + facet normal -0.397952 -0.488496 0.776534 + outer loop + vertex 840.507 246.041 49.2164 + vertex 839.43 247.488 49.5747 + vertex 840.507 245.707 49.0064 + endloop + endfacet + facet normal -0.297706 -0.448924 0.842519 + outer loop + vertex 839.43 247.488 49.5747 + vertex 839.257 247.065 49.2882 + vertex 840.507 245.707 49.0064 + endloop + endfacet + facet normal -0.336162 -0.477901 0.811545 + outer loop + vertex 840.507 245.707 49.0064 + vertex 839.257 247.065 49.2882 + vertex 840.299 245.382 48.7283 + endloop + endfacet + facet normal -0.898763 -0.236506 0.369174 + outer loop + vertex 834.709 263.449 51.9005 + vertex 834.07 265.398 51.5931 + vertex 835.486 259.963 51.558 + endloop + endfacet + facet normal -0.802812 -0.212727 0.556993 + outer loop + vertex 835.486 259.963 51.558 + vertex 834.07 265.398 51.5931 + vertex 835.283 258.975 50.8888 + endloop + endfacet + facet normal -0.730356 -0.274094 0.625661 + outer loop + vertex 835.486 259.963 51.558 + vertex 835.283 258.975 50.8888 + vertex 837.012 254.123 50.7815 + endloop + endfacet + facet normal -0.665414 -0.252648 0.702419 + outer loop + vertex 837.012 254.123 50.7815 + vertex 835.283 258.975 50.8888 + vertex 836.842 252.675 50.0992 + endloop + endfacet + facet normal 0.0971905 -0.54455 0.833078 + outer loop + vertex 843.087 239.552 45.0272 + vertex 842.234 238.309 44.3142 + vertex 843.651 239.187 44.7225 + endloop + endfacet + facet normal 0.0913199 -0.531753 0.841962 + outer loop + vertex 841.198 237.2 43.7262 + vertex 841.928 237.446 43.8027 + vertex 842.234 238.309 44.3142 + endloop + endfacet + facet normal 0.0855444 -0.530522 0.843344 + outer loop + vertex 841.928 237.446 43.8027 + vertex 843.651 239.187 44.7225 + vertex 842.234 238.309 44.3142 + endloop + endfacet + facet normal 0.0924936 -0.579687 0.809573 + outer loop + vertex 844.624 241.5 46.2075 + vertex 844.026 240.582 45.6184 + vertex 845.032 240.933 45.7542 + endloop + endfacet + facet normal 0.0876455 -0.55462 0.827475 + outer loop + vertex 843.087 239.552 45.0272 + vertex 843.651 239.187 44.7225 + vertex 844.026 240.582 45.6184 + endloop + endfacet + facet normal 0.0808411 -0.553653 0.828814 + outer loop + vertex 843.651 239.187 44.7225 + vertex 845.032 240.933 45.7542 + vertex 844.026 240.582 45.6184 + endloop + endfacet + facet normal -0.140638 -0.476885 0.867642 + outer loop + vertex 838.57 243.134 47.0434 + vertex 837.93 241.852 46.2347 + vertex 839.692 241.652 46.4103 + endloop + endfacet + facet normal -0.140746 -0.478746 0.866598 + outer loop + vertex 839.692 241.652 46.4103 + vertex 837.93 241.852 46.2347 + vertex 838.726 240.246 45.477 + endloop + endfacet + facet normal -0.136713 -0.490604 0.860591 + outer loop + vertex 839.275 244.217 47.7728 + vertex 838.57 243.134 47.0434 + vertex 840.432 242.803 47.1504 + endloop + endfacet + facet normal -0.13421 -0.473292 0.870622 + outer loop + vertex 840.432 242.803 47.1504 + vertex 838.57 243.134 47.0434 + vertex 839.692 241.652 46.4103 + endloop + endfacet + facet normal -0.029882 -0.526756 0.849491 + outer loop + vertex 840.432 242.803 47.1504 + vertex 839.692 241.652 46.4103 + vertex 841.628 241.599 46.4462 + endloop + endfacet + facet normal -0.0296868 -0.514248 0.857128 + outer loop + vertex 841.628 241.599 46.4462 + vertex 839.692 241.652 46.4103 + vertex 840.796 240.358 45.6726 + endloop + endfacet + facet normal -0.05157 -0.52765 0.847895 + outer loop + vertex 839.692 241.652 46.4103 + vertex 838.726 240.246 45.477 + vertex 840.796 240.358 45.6726 + endloop + endfacet + facet normal -0.0551062 -0.495477 0.866871 + outer loop + vertex 840.796 240.358 45.6726 + vertex 838.726 240.246 45.477 + vertex 839.979 239.033 44.8631 + endloop + endfacet + facet normal -0.153904 -0.524095 0.837638 + outer loop + vertex 839.875 244.935 48.3324 + vertex 839.275 244.217 47.7728 + vertex 841.048 243.611 47.7194 + endloop + endfacet + facet normal -0.143182 -0.49446 0.857326 + outer loop + vertex 841.048 243.611 47.7194 + vertex 839.275 244.217 47.7728 + vertex 840.432 242.803 47.1504 + endloop + endfacet + facet normal -0.178551 -0.55272 0.814015 + outer loop + vertex 840.299 245.382 48.7283 + vertex 839.875 244.935 48.3324 + vertex 841.488 244.095 48.1153 + endloop + endfacet + facet normal -0.164811 -0.530822 0.831303 + outer loop + vertex 841.488 244.095 48.1153 + vertex 839.875 244.935 48.3324 + vertex 841.048 243.611 47.7194 + endloop + endfacet + facet normal -0.0659207 -0.595689 0.800505 + outer loop + vertex 841.488 244.095 48.1153 + vertex 841.048 243.611 47.7194 + vertex 842.799 243.077 47.466 + endloop + endfacet + facet normal -0.054489 -0.56804 0.821195 + outer loop + vertex 842.799 243.077 47.466 + vertex 841.048 243.611 47.7194 + vertex 842.311 242.514 47.0445 + endloop + endfacet + facet normal -0.0384977 -0.555449 0.830659 + outer loop + vertex 841.048 243.611 47.7194 + vertex 840.432 242.803 47.1504 + vertex 842.311 242.514 47.0445 + endloop + endfacet + facet normal -0.0335271 -0.529354 0.847738 + outer loop + vertex 842.311 242.514 47.0445 + vertex 840.432 242.803 47.1504 + vertex 841.628 241.599 46.4462 + endloop + endfacet + facet normal 0.0342818 -0.564769 0.824537 + outer loop + vertex 842.311 242.514 47.0445 + vertex 841.628 241.599 46.4462 + vertex 843.406 241.543 46.3333 + endloop + endfacet + facet normal 0.0357615 -0.544825 0.837787 + outer loop + vertex 843.406 241.543 46.3333 + vertex 841.628 241.599 46.4462 + vertex 842.617 240.501 45.6894 + endloop + endfacet + facet normal 0.012769 -0.606632 0.79488 + outer loop + vertex 842.799 243.077 47.466 + vertex 842.311 242.514 47.0445 + vertex 843.983 242.232 46.8018 + endloop + endfacet + facet normal 0.0216029 -0.574456 0.81825 + outer loop + vertex 843.983 242.232 46.8018 + vertex 842.311 242.514 47.0445 + vertex 843.406 241.543 46.3333 + endloop + endfacet + facet normal 0.0620509 -0.596214 0.800424 + outer loop + vertex 843.983 242.232 46.8018 + vertex 843.406 241.543 46.3333 + vertex 844.624 241.5 46.2075 + endloop + endfacet + facet normal 0.0650412 -0.568551 0.820073 + outer loop + vertex 844.624 241.5 46.2075 + vertex 843.406 241.543 46.3333 + vertex 844.026 240.582 45.6184 + endloop + endfacet + facet normal 0.0741392 -0.564293 0.822239 + outer loop + vertex 843.406 241.543 46.3333 + vertex 842.617 240.501 45.6894 + vertex 844.026 240.582 45.6184 + endloop + endfacet + facet normal 0.0736988 -0.545973 0.834555 + outer loop + vertex 844.026 240.582 45.6184 + vertex 842.617 240.501 45.6894 + vertex 843.087 239.552 45.0272 + endloop + endfacet + facet normal 0.0227263 -0.531234 0.84692 + outer loop + vertex 840.796 240.358 45.6726 + vertex 839.979 239.033 44.8631 + vertex 841.689 239.209 44.928 + endloop + endfacet + facet normal 0.0204676 -0.513406 0.857902 + outer loop + vertex 841.689 239.209 44.928 + vertex 839.979 239.033 44.8631 + vertex 840.505 237.805 44.1159 + endloop + endfacet + facet normal 0.0349264 -0.545361 0.837473 + outer loop + vertex 841.628 241.599 46.4462 + vertex 840.796 240.358 45.6726 + vertex 842.617 240.501 45.6894 + endloop + endfacet + facet normal 0.0332354 -0.52525 0.850298 + outer loop + vertex 842.617 240.501 45.6894 + vertex 840.796 240.358 45.6726 + vertex 841.689 239.209 44.928 + endloop + endfacet + facet normal 0.0744782 -0.545675 0.834681 + outer loop + vertex 842.617 240.501 45.6894 + vertex 841.689 239.209 44.928 + vertex 843.087 239.552 45.0272 + endloop + endfacet + facet normal 0.0705728 -0.532321 0.843596 + outer loop + vertex 843.087 239.552 45.0272 + vertex 841.689 239.209 44.928 + vertex 842.234 238.309 44.3142 + endloop + endfacet + facet normal 0.060018 -0.537169 0.841337 + outer loop + vertex 841.689 239.209 44.928 + vertex 840.505 237.805 44.1159 + vertex 842.234 238.309 44.3142 + endloop + endfacet + facet normal 0.0472205 -0.501999 0.863578 + outer loop + vertex 842.234 238.309 44.3142 + vertex 840.505 237.805 44.1159 + vertex 841.198 237.2 43.7262 + endloop + endfacet + facet normal -0.368788 -0.349179 0.861435 + outer loop + vertex 837.862 248.943 49.4131 + vertex 837.561 247.932 48.8743 + vertex 838.873 246.6 48.8961 + endloop + endfacet + facet normal -0.387758 -0.368134 0.845057 + outer loop + vertex 838.873 246.6 48.8961 + vertex 837.561 247.932 48.8743 + vertex 838.287 245.97 48.3525 + endloop + endfacet + facet normal -0.452084 -0.389196 0.802587 + outer loop + vertex 838.382 249.074 49.7692 + vertex 837.862 248.943 49.4131 + vertex 839.257 247.065 49.2882 + endloop + endfacet + facet normal -0.413417 -0.362645 0.83521 + outer loop + vertex 839.257 247.065 49.2882 + vertex 837.862 248.943 49.4131 + vertex 838.873 246.6 48.8961 + endloop + endfacet + facet normal -0.295603 -0.461154 0.836633 + outer loop + vertex 839.257 247.065 49.2882 + vertex 838.873 246.6 48.8961 + vertex 840.299 245.382 48.7283 + endloop + endfacet + facet normal -0.29584 -0.4614 0.836414 + outer loop + vertex 840.299 245.382 48.7283 + vertex 838.873 246.6 48.8961 + vertex 839.875 244.935 48.3324 + endloop + endfacet + facet normal -0.287599 -0.458033 0.841126 + outer loop + vertex 838.873 246.6 48.8961 + vertex 838.287 245.97 48.3525 + vertex 839.875 244.935 48.3324 + endloop + endfacet + facet normal -0.274298 -0.4379 0.856157 + outer loop + vertex 839.875 244.935 48.3324 + vertex 838.287 245.97 48.3525 + vertex 839.275 244.217 47.7728 + endloop + endfacet + facet normal -0.39512 -0.34253 0.852381 + outer loop + vertex 836.6 247.67 48.2517 + vertex 835.482 246.471 47.2515 + vertex 837.485 245.05 47.6088 + endloop + endfacet + facet normal -0.391399 -0.336227 0.856597 + outer loop + vertex 837.485 245.05 47.6088 + vertex 835.482 246.471 47.2515 + vertex 836.637 243.553 46.6337 + endloop + endfacet + facet normal -0.429271 -0.377021 0.82072 + outer loop + vertex 837.561 247.932 48.8743 + vertex 836.6 247.67 48.2517 + vertex 838.287 245.97 48.3525 + endloop + endfacet + facet normal -0.396649 -0.342841 0.851546 + outer loop + vertex 838.287 245.97 48.3525 + vertex 836.6 247.67 48.2517 + vertex 837.485 245.05 47.6088 + endloop + endfacet + facet normal -0.283325 -0.441417 0.851398 + outer loop + vertex 838.287 245.97 48.3525 + vertex 837.485 245.05 47.6088 + vertex 839.275 244.217 47.7728 + endloop + endfacet + facet normal -0.270638 -0.410308 0.870863 + outer loop + vertex 839.275 244.217 47.7728 + vertex 837.485 245.05 47.6088 + vertex 838.57 243.134 47.0434 + endloop + endfacet + facet normal -0.273421 -0.411466 0.869446 + outer loop + vertex 837.485 245.05 47.6088 + vertex 836.637 243.553 46.6337 + vertex 838.57 243.134 47.0434 + endloop + endfacet + facet normal -0.273447 -0.411704 0.869325 + outer loop + vertex 838.57 243.134 47.0434 + vertex 836.637 243.553 46.6337 + vertex 837.93 241.852 46.2347 + endloop + endfacet + facet normal -0.603929 -0.184585 0.77537 + outer loop + vertex 833.253 264.531 50.4954 + vertex 832.721 261.539 49.3688 + vertex 834.716 257.31 49.9158 + endloop + endfacet + facet normal -0.598725 -0.181517 0.780115 + outer loop + vertex 834.716 257.31 49.9158 + vertex 832.721 261.539 49.3688 + vertex 833.659 255.719 48.7346 + endloop + endfacet + facet normal -0.699339 -0.207124 0.684123 + outer loop + vertex 834.07 265.398 51.5931 + vertex 833.253 264.531 50.4954 + vertex 835.283 258.975 50.8888 + endloop + endfacet + facet normal -0.667318 -0.192929 0.719351 + outer loop + vertex 835.283 258.975 50.8888 + vertex 833.253 264.531 50.4954 + vertex 834.716 257.31 49.9158 + endloop + endfacet + facet normal -0.596745 -0.243454 0.764608 + outer loop + vertex 835.283 258.975 50.8888 + vertex 834.716 257.31 49.9158 + vertex 836.842 252.675 50.0992 + endloop + endfacet + facet normal -0.567516 -0.229008 0.790873 + outer loop + vertex 836.842 252.675 50.0992 + vertex 834.716 257.31 49.9158 + vertex 836.026 251.309 49.1185 + endloop + endfacet + facet normal -0.553414 -0.227312 0.801288 + outer loop + vertex 834.716 257.31 49.9158 + vertex 833.659 255.719 48.7346 + vertex 836.026 251.309 49.1185 + endloop + endfacet + facet normal -0.526009 -0.210626 0.823985 + outer loop + vertex 836.026 251.309 49.1185 + vertex 833.659 255.719 48.7346 + vertex 834.576 250.446 47.9719 + endloop + endfacet + facet normal -0.646665 -0.165409 0.744624 + outer loop + vertex 832.721 261.539 49.3688 + vertex 833.253 264.531 50.4954 + vertex 830.173 269.766 48.9833 + endloop + endfacet + facet normal -0.726383 -0.161324 0.668088 + outer loop + vertex 834.07 265.398 51.5931 + vertex 831.746 274.129 51.1747 + vertex 833.253 264.531 50.4954 + endloop + endfacet + facet normal -0.632772 -0.153065 0.759059 + outer loop + vertex 831.746 274.129 51.1747 + vertex 830.173 269.766 48.9833 + vertex 833.253 264.531 50.4954 + endloop + endfacet + facet normal -0.639607 -0.132282 0.757235 + outer loop + vertex 829.529 285.828 51.346 + vertex 827.985 281.97 49.3675 + vertex 831.746 274.129 51.1747 + endloop + endfacet + facet normal -0.650742 -0.140155 0.746252 + outer loop + vertex 831.746 274.129 51.1747 + vertex 827.985 281.97 49.3675 + vertex 830.173 269.766 48.9833 + endloop + endfacet + facet normal -0.634094 -0.143769 0.759773 + outer loop + vertex 827.282 296.269 51.4465 + vertex 825.768 292.888 49.5429 + vertex 829.529 285.828 51.346 + endloop + endfacet + facet normal -0.629351 -0.140062 0.764395 + outer loop + vertex 829.529 285.828 51.346 + vertex 825.768 292.888 49.5429 + vertex 827.985 281.97 49.3675 + endloop + endfacet + facet normal -0.630196 -0.169998 0.757597 + outer loop + vertex 824.713 305.873 51.464 + vertex 823.306 302.833 49.6118 + vertex 827.282 296.269 51.4465 + endloop + endfacet + facet normal -0.616674 -0.158006 0.771199 + outer loop + vertex 827.282 296.269 51.4465 + vertex 823.306 302.833 49.6118 + vertex 825.768 292.888 49.5429 + endloop + endfacet + facet normal -0.624046 -0.194142 0.756885 + outer loop + vertex 821.71 315.4 51.4319 + vertex 820.499 312.205 49.6143 + vertex 824.713 305.873 51.464 + endloop + endfacet + facet normal -0.613584 -0.183963 0.767901 + outer loop + vertex 824.713 305.873 51.464 + vertex 820.499 312.205 49.6143 + vertex 823.306 302.833 49.6118 + endloop + endfacet + facet normal -0.617596 -0.215342 0.756441 + outer loop + vertex 818.548 323.884 51.2652 + vertex 817.465 321.08 49.5834 + vertex 821.71 315.4 51.4319 + endloop + endfacet + facet normal -0.60863 -0.205397 0.766408 + outer loop + vertex 821.71 315.4 51.4319 + vertex 817.465 321.08 49.5834 + vertex 820.499 312.205 49.6143 + endloop + endfacet + facet normal -0.619125 -0.238077 0.748334 + outer loop + vertex 815.634 331.844 51.3876 + vertex 814.383 329.439 49.5867 + vertex 818.548 323.884 51.2652 + endloop + endfacet + facet normal -0.606128 -0.223834 0.763221 + outer loop + vertex 818.548 323.884 51.2652 + vertex 814.383 329.439 49.5867 + vertex 817.465 321.08 49.5834 + endloop + endfacet + facet normal -0.622034 -0.253944 0.740666 + outer loop + vertex 812.237 339.803 51.2636 + vertex 811.16 337.528 49.5785 + vertex 815.634 331.844 51.3876 + endloop + endfacet + facet normal -0.613172 -0.243527 0.751475 + outer loop + vertex 815.634 331.844 51.3876 + vertex 811.16 337.528 49.5785 + vertex 814.383 329.439 49.5867 + endloop + endfacet + facet normal -0.631956 -0.274089 0.724918 + outer loop + vertex 809.036 347.547 51.4 + vertex 807.834 345.49 49.5752 + vertex 812.237 339.803 51.2636 + endloop + endfacet + facet normal -0.617716 -0.257701 0.742979 + outer loop + vertex 812.237 339.803 51.2636 + vertex 807.834 345.49 49.5752 + vertex 811.16 337.528 49.5785 + endloop + endfacet + facet normal -0.644316 -0.289202 0.707968 + outer loop + vertex 805.377 355.478 51.31 + vertex 804.405 353.431 49.5895 + vertex 809.036 347.547 51.4 + endloop + endfacet + facet normal -0.631869 -0.274178 0.724961 + outer loop + vertex 809.036 347.547 51.4 + vertex 804.405 353.431 49.5895 + vertex 807.834 345.49 49.5752 + endloop + endfacet + facet normal -0.660855 -0.304644 0.685903 + outer loop + vertex 802.026 363.203 51.5122 + vertex 800.941 361.379 49.6568 + vertex 805.377 355.478 51.31 + endloop + endfacet + facet normal -0.646053 -0.287596 0.707039 + outer loop + vertex 805.377 355.478 51.31 + vertex 800.941 361.379 49.6568 + vertex 804.405 353.431 49.5895 + endloop + endfacet + facet normal -0.672652 -0.304103 0.674582 + outer loop + vertex 798.401 370.824 51.3339 + vertex 797.459 369.288 49.7024 + vertex 802.026 363.203 51.5122 + endloop + endfacet + facet normal -0.667271 -0.297632 0.682763 + outer loop + vertex 802.026 363.203 51.5122 + vertex 797.459 369.288 49.7024 + vertex 800.941 361.379 49.6568 + endloop + endfacet + facet normal -0.69695 -0.29156 0.655174 + outer loop + vertex 795.676 376.842 51.1135 + vertex 794.196 376.978 49.5989 + vertex 798.401 370.824 51.3339 + endloop + endfacet + facet normal -0.690119 -0.283932 0.665671 + outer loop + vertex 798.401 370.824 51.3339 + vertex 794.196 376.978 49.5989 + vertex 797.459 369.288 49.7024 + endloop + endfacet + facet normal -0.135323 -0.417776 0.898416 + outer loop + vertex 836.036 241.103 45.3137 + vertex 834.131 238.415 43.7769 + vertex 837.785 238.04 44.1527 + endloop + endfacet + facet normal -0.0560171 -0.496183 0.866409 + outer loop + vertex 839.979 239.033 44.8631 + vertex 838.726 240.246 45.477 + vertex 837.785 238.04 44.1527 + endloop + endfacet + facet normal -0.210468 -0.500607 0.8397 + outer loop + vertex 837.93 241.852 46.2347 + vertex 836.036 241.103 45.3137 + vertex 838.726 240.246 45.477 + endloop + endfacet + facet normal -0.194178 -0.442668 0.875408 + outer loop + vertex 836.036 241.103 45.3137 + vertex 837.785 238.04 44.1527 + vertex 838.726 240.246 45.477 + endloop + endfacet + facet normal 0.0538205 -0.496311 0.866475 + outer loop + vertex 841.198 237.2 43.7262 + vertex 840.505 237.805 44.1159 + vertex 839.294 235.903 43.1017 + endloop + endfacet + facet normal -0.0343213 -0.53032 0.847102 + outer loop + vertex 839.979 239.033 44.8631 + vertex 837.785 238.04 44.1527 + vertex 840.505 237.805 44.1159 + endloop + endfacet + facet normal -0.0273934 -0.4567 0.889199 + outer loop + vertex 837.785 238.04 44.1527 + vertex 839.294 235.903 43.1017 + vertex 840.505 237.805 44.1159 + endloop + endfacet + facet normal -0.0151166 -0.449881 0.89296 + outer loop + vertex 837.785 238.04 44.1527 + vertex 835.364 235.181 42.6713 + vertex 839.294 235.903 43.1017 + endloop + endfacet + facet normal -0.0329859 -0.373066 0.927218 + outer loop + vertex 839.294 235.903 43.1017 + vertex 835.364 235.181 42.6713 + vertex 835.663 232.449 41.5829 + endloop + endfacet + facet normal -0.264684 -0.406275 0.874576 + outer loop + vertex 837.93 241.852 46.2347 + vertex 836.637 243.553 46.6337 + vertex 836.036 241.103 45.3137 + endloop + endfacet + facet normal -0.36632 -0.329205 0.870307 + outer loop + vertex 835.482 246.471 47.2515 + vertex 834.268 244.624 46.0418 + vertex 836.637 243.553 46.6337 + endloop + endfacet + facet normal -0.377856 -0.365597 0.850625 + outer loop + vertex 834.268 244.624 46.0418 + vertex 836.036 241.103 45.3137 + vertex 836.637 243.553 46.6337 + endloop + endfacet + facet normal -0.529501 -0.162949 0.832512 + outer loop + vertex 831.146 260.844 48.0383 + vertex 829.889 258.135 46.7087 + vertex 832.24 254.177 47.4296 + endloop + endfacet + facet normal -0.513648 -0.151338 0.844549 + outer loop + vertex 832.24 254.177 47.4296 + vertex 829.889 258.135 46.7087 + vertex 830.534 252.411 46.0752 + endloop + endfacet + facet normal -0.586969 -0.180612 0.789206 + outer loop + vertex 832.721 261.539 49.3688 + vertex 831.146 260.844 48.0383 + vertex 833.659 255.719 48.7346 + endloop + endfacet + facet normal -0.563523 -0.166404 0.809167 + outer loop + vertex 833.659 255.719 48.7346 + vertex 831.146 260.844 48.0383 + vertex 832.24 254.177 47.4296 + endloop + endfacet + facet normal -0.527832 -0.210769 0.822782 + outer loop + vertex 833.659 255.719 48.7346 + vertex 832.24 254.177 47.4296 + vertex 834.576 250.446 47.9719 + endloop + endfacet + facet normal -0.509897 -0.197437 0.837272 + outer loop + vertex 834.576 250.446 47.9719 + vertex 832.24 254.177 47.4296 + vertex 833.144 248.891 46.7333 + endloop + endfacet + facet normal -0.478311 -0.194554 0.856369 + outer loop + vertex 832.24 254.177 47.4296 + vertex 830.534 252.411 46.0752 + vertex 833.144 248.891 46.7333 + endloop + endfacet + facet normal -0.463617 -0.181629 0.86722 + outer loop + vertex 833.144 248.891 46.7333 + vertex 830.534 252.411 46.0752 + vertex 831.493 246.845 45.4221 + endloop + endfacet + facet normal -0.550691 -0.147731 0.821532 + outer loop + vertex 829.889 258.135 46.7087 + vertex 831.146 260.844 48.0383 + vertex 827.278 266.362 46.4379 + endloop + endfacet + facet normal -0.599029 -0.148677 0.786803 + outer loop + vertex 832.721 261.539 49.3688 + vertex 830.173 269.766 48.9833 + vertex 831.146 260.844 48.0383 + endloop + endfacet + facet normal -0.549989 -0.147069 0.822121 + outer loop + vertex 830.173 269.766 48.9833 + vertex 827.278 266.362 46.4379 + vertex 831.146 260.844 48.0383 + endloop + endfacet + facet normal -0.575457 -0.128591 0.807659 + outer loop + vertex 827.985 281.97 49.3675 + vertex 825.408 278.415 46.9657 + vertex 830.173 269.766 48.9833 + endloop + endfacet + facet normal -0.569117 -0.123883 0.81287 + outer loop + vertex 830.173 269.766 48.9833 + vertex 825.408 278.415 46.9657 + vertex 827.278 266.362 46.4379 + endloop + endfacet + facet normal -0.580785 -0.13083 0.803475 + outer loop + vertex 825.768 292.888 49.5429 + vertex 823.27 289.61 47.2036 + vertex 827.985 281.97 49.3675 + endloop + endfacet + facet normal -0.576658 -0.127282 0.80701 + outer loop + vertex 827.985 281.97 49.3675 + vertex 823.27 289.61 47.2036 + vertex 825.408 278.415 46.9657 + endloop + endfacet + facet normal -0.576154 -0.1482 0.803793 + outer loop + vertex 823.306 302.833 49.6118 + vertex 820.816 299.842 47.2752 + vertex 825.768 292.888 49.5429 + endloop + endfacet + facet normal -0.570485 -0.142513 0.808849 + outer loop + vertex 825.768 292.888 49.5429 + vertex 820.816 299.842 47.2752 + vertex 823.27 289.61 47.2036 + endloop + endfacet + facet normal -0.572162 -0.171567 0.801995 + outer loop + vertex 820.499 312.205 49.6143 + vertex 818.082 309.374 47.2843 + vertex 823.306 302.833 49.6118 + endloop + endfacet + facet normal -0.564218 -0.162565 0.809463 + outer loop + vertex 823.306 302.833 49.6118 + vertex 818.082 309.374 47.2843 + vertex 820.816 299.842 47.2752 + endloop + endfacet + facet normal -0.567923 -0.191362 0.800527 + outer loop + vertex 817.465 321.08 49.5834 + vertex 815.104 318.434 47.2761 + vertex 820.499 312.205 49.6143 + endloop + endfacet + facet normal -0.561947 -0.183961 0.806457 + outer loop + vertex 820.499 312.205 49.6143 + vertex 815.104 318.434 47.2761 + vertex 818.082 309.374 47.2843 + endloop + endfacet + facet normal -0.565664 -0.208925 0.797731 + outer loop + vertex 814.383 329.439 49.5867 + vertex 811.978 327.13 47.2771 + vertex 817.465 321.08 49.5834 + endloop + endfacet + facet normal -0.55986 -0.201368 0.803746 + outer loop + vertex 817.465 321.08 49.5834 + vertex 811.978 327.13 47.2771 + vertex 815.104 318.434 47.2761 + endloop + endfacet + facet normal -0.570754 -0.226589 0.789238 + outer loop + vertex 811.16 337.528 49.5785 + vertex 808.768 335.542 47.2787 + vertex 814.383 329.439 49.5867 + endloop + endfacet + facet normal -0.561643 -0.214479 0.799097 + outer loop + vertex 814.383 329.439 49.5867 + vertex 808.768 335.542 47.2787 + vertex 811.978 327.13 47.2771 + endloop + endfacet + facet normal -0.577869 -0.241043 0.779721 + outer loop + vertex 807.834 345.49 49.5752 + vertex 805.431 343.783 47.2664 + vertex 811.16 337.528 49.5785 + endloop + endfacet + facet normal -0.56902 -0.229241 0.789724 + outer loop + vertex 811.16 337.528 49.5785 + vertex 805.431 343.783 47.2664 + vertex 808.768 335.542 47.2787 + endloop + endfacet + facet normal -0.591679 -0.256893 0.764148 + outer loop + vertex 804.405 353.431 49.5895 + vertex 802.036 351.935 47.2523 + vertex 807.834 345.49 49.5752 + endloop + endfacet + facet normal -0.578686 -0.239653 0.779544 + outer loop + vertex 807.834 345.49 49.5752 + vertex 802.036 351.935 47.2523 + vertex 805.431 343.783 47.2664 + endloop + endfacet + facet normal -0.60793 -0.271311 0.746199 + outer loop + vertex 800.941 361.379 49.6568 + vertex 798.59 360.089 47.2723 + vertex 804.405 353.431 49.5895 + endloop + endfacet + facet normal -0.593855 -0.252894 0.763794 + outer loop + vertex 804.405 353.431 49.5895 + vertex 798.59 360.089 47.2723 + vertex 802.036 351.935 47.2523 + endloop + endfacet + facet normal -0.622673 -0.278283 0.731325 + outer loop + vertex 797.459 369.288 49.7024 + vertex 795.146 368.289 47.3523 + vertex 800.941 361.379 49.6568 + endloop + endfacet + facet normal -0.61153 -0.264095 0.745845 + outer loop + vertex 800.941 361.379 49.6568 + vertex 795.146 368.289 47.3523 + vertex 798.59 360.089 47.2723 + endloop + endfacet + facet normal -0.63833 -0.261166 0.724104 + outer loop + vertex 794.196 376.978 49.5989 + vertex 791.807 376.548 47.3379 + vertex 797.459 369.288 49.7024 + endloop + endfacet + facet normal -0.632836 -0.254563 0.731243 + outer loop + vertex 797.459 369.288 49.7024 + vertex 791.807 376.548 47.3379 + vertex 795.146 368.289 47.3523 + endloop + endfacet + facet normal -0.684159 -0.216108 0.69658 + outer loop + vertex 792.003 384.848 49.887 + vertex 789.072 384.933 47.0349 + vertex 794.196 376.978 49.5989 + endloop + endfacet + facet normal -0.657111 -0.187918 0.729994 + outer loop + vertex 794.196 376.978 49.5989 + vertex 789.072 384.933 47.0349 + vertex 791.807 376.548 47.3379 + endloop + endfacet + facet normal -0.0348772 -0.373221 0.927087 + outer loop + vertex 835.364 235.181 42.6713 + vertex 832.798 232.382 41.4481 + vertex 835.663 232.449 41.5829 + endloop + endfacet + facet normal -0.0366245 -0.33068 0.943032 + outer loop + vertex 835.663 232.449 41.5829 + vertex 832.798 232.382 41.4481 + vertex 832.986 229.993 40.6177 + endloop + endfacet + facet normal -0.0252703 -0.329997 0.943644 + outer loop + vertex 832.798 232.382 41.4481 + vertex 830.425 229.84 40.4956 + vertex 832.986 229.993 40.6177 + endloop + endfacet + facet normal -0.0273348 -0.302637 0.952714 + outer loop + vertex 832.986 229.993 40.6177 + vertex 830.425 229.84 40.4956 + vertex 830.905 227.551 39.7821 + endloop + endfacet + facet normal -0.385877 -0.126167 0.913882 + outer loop + vertex 827.504 257.516 45.2978 + vertex 824.59 254.148 43.6026 + vertex 828.439 250.085 44.6667 + endloop + endfacet + facet normal -0.382108 -0.122036 0.916024 + outer loop + vertex 828.439 250.085 44.6667 + vertex 824.59 254.148 43.6026 + vertex 826.427 246.171 43.306 + endloop + endfacet + facet normal -0.474373 -0.149458 0.867544 + outer loop + vertex 829.889 258.135 46.7087 + vertex 827.504 257.516 45.2978 + vertex 830.534 252.411 46.0752 + endloop + endfacet + facet normal -0.448379 -0.131503 0.884117 + outer loop + vertex 830.534 252.411 46.0752 + vertex 827.504 257.516 45.2978 + vertex 828.439 250.085 44.6667 + endloop + endfacet + facet normal -0.407719 -0.175388 0.896105 + outer loop + vertex 830.534 252.411 46.0752 + vertex 828.439 250.085 44.6667 + vertex 831.493 246.845 45.4221 + endloop + endfacet + facet normal -0.400659 -0.167649 0.900759 + outer loop + vertex 831.493 246.845 45.4221 + vertex 828.439 250.085 44.6667 + vertex 829.699 244.234 44.1381 + endloop + endfacet + facet normal -0.328665 -0.154936 0.931651 + outer loop + vertex 828.439 250.085 44.6667 + vertex 826.427 246.171 43.306 + vertex 829.699 244.234 44.1381 + endloop + endfacet + facet normal -0.335121 -0.167796 0.927113 + outer loop + vertex 829.699 244.234 44.1381 + vertex 826.427 246.171 43.306 + vertex 828.293 241.487 43.1329 + endloop + endfacet + facet normal -0.412259 -0.0992025 0.90565 + outer loop + vertex 824.59 254.148 43.6026 + vertex 827.504 257.516 45.2978 + vertex 823.304 264.227 44.1213 + endloop + endfacet + facet normal -0.481113 -0.124127 0.867826 + outer loop + vertex 829.889 258.135 46.7087 + vertex 827.278 266.362 46.4379 + vertex 827.504 257.516 45.2978 + endloop + endfacet + facet normal -0.448482 -0.125499 0.884937 + outer loop + vertex 827.278 266.362 46.4379 + vertex 823.304 264.227 44.1213 + vertex 827.504 257.516 45.2978 + endloop + endfacet + facet normal -0.479629 -0.112512 0.870228 + outer loop + vertex 825.408 278.415 46.9657 + vertex 821.834 275.122 44.5702 + vertex 827.278 266.362 46.4379 + endloop + endfacet + facet normal -0.46115 -0.0985545 0.881832 + outer loop + vertex 827.278 266.362 46.4379 + vertex 821.834 275.122 44.5702 + vertex 823.304 264.227 44.1213 + endloop + endfacet + facet normal -0.493468 -0.112572 0.862448 + outer loop + vertex 823.27 289.61 47.2036 + vertex 819.807 286.244 44.7826 + vertex 825.408 278.415 46.9657 + endloop + endfacet + facet normal -0.485119 -0.105018 0.868119 + outer loop + vertex 825.408 278.415 46.9657 + vertex 819.807 286.244 44.7826 + vertex 821.834 275.122 44.5702 + endloop + endfacet + facet normal -0.495387 -0.124853 0.859653 + outer loop + vertex 820.816 299.842 47.2752 + vertex 817.377 296.722 44.8405 + vertex 823.27 289.61 47.2036 + endloop + endfacet + facet normal -0.48917 -0.118211 0.86414 + outer loop + vertex 823.27 289.61 47.2036 + vertex 817.377 296.722 44.8405 + vertex 819.807 286.244 44.7826 + endloop + endfacet + facet normal -0.491512 -0.141764 0.859255 + outer loop + vertex 818.082 309.374 47.2843 + vertex 814.626 306.512 44.8351 + vertex 820.816 299.842 47.2752 + endloop + endfacet + facet normal -0.487055 -0.136384 0.862657 + outer loop + vertex 820.816 299.842 47.2752 + vertex 814.626 306.512 44.8351 + vertex 817.377 296.722 44.8405 + endloop + endfacet + facet normal -0.489719 -0.160176 0.857041 + outer loop + vertex 815.104 318.434 47.2761 + vertex 811.657 315.826 44.8188 + vertex 818.082 309.374 47.2843 + endloop + endfacet + facet normal -0.484046 -0.152785 0.861601 + outer loop + vertex 818.082 309.374 47.2843 + vertex 811.657 315.826 44.8188 + vertex 814.626 306.512 44.8351 + endloop + endfacet + facet normal -0.493365 -0.177467 0.851526 + outer loop + vertex 811.978 327.13 47.2771 + vertex 808.55 324.823 44.8103 + vertex 815.104 318.434 47.2761 + endloop + endfacet + facet normal -0.485494 -0.166827 0.858175 + outer loop + vertex 815.104 318.434 47.2761 + vertex 808.55 324.823 44.8103 + vertex 811.657 315.826 44.8188 + endloop + endfacet + facet normal -0.496326 -0.189563 0.847187 + outer loop + vertex 808.768 335.542 47.2787 + vertex 805.313 333.59 44.8176 + vertex 811.978 327.13 47.2771 + endloop + endfacet + facet normal -0.490755 -0.181948 0.852089 + outer loop + vertex 811.978 327.13 47.2771 + vertex 805.313 333.59 44.8176 + vertex 808.55 324.823 44.8103 + endloop + endfacet + facet normal -0.503037 -0.202447 0.840219 + outer loop + vertex 805.431 343.783 47.2664 + vertex 801.975 342.187 44.8124 + vertex 808.768 335.542 47.2787 + endloop + endfacet + facet normal -0.495192 -0.191778 0.847352 + outer loop + vertex 808.768 335.542 47.2787 + vertex 801.975 342.187 44.8124 + vertex 805.313 333.59 44.8176 + endloop + endfacet + facet normal -0.513749 -0.21252 0.831203 + outer loop + vertex 802.036 351.935 47.2523 + vertex 798.563 350.674 44.7835 + vertex 805.431 343.783 47.2664 + endloop + endfacet + facet normal -0.504214 -0.199793 0.84015 + outer loop + vertex 805.431 343.783 47.2664 + vertex 798.563 350.674 44.7835 + vertex 801.975 342.187 44.8124 + endloop + endfacet + facet normal -0.531049 -0.226475 0.816515 + outer loop + vertex 798.59 360.089 47.2723 + vertex 795.133 359.118 44.755 + vertex 802.036 351.935 47.2523 + endloop + endfacet + facet normal -0.515909 -0.206782 0.831312 + outer loop + vertex 802.036 351.935 47.2523 + vertex 795.133 359.118 44.755 + vertex 798.563 350.674 44.7835 + endloop + endfacet + facet normal -0.550463 -0.238977 0.799926 + outer loop + vertex 795.146 368.289 47.3523 + vertex 791.735 367.596 44.7983 + vertex 798.59 360.089 47.2723 + endloop + endfacet + facet normal -0.533768 -0.218101 0.817021 + outer loop + vertex 798.59 360.089 47.2723 + vertex 791.735 367.596 44.7983 + vertex 795.133 359.118 44.755 + endloop + endfacet + facet normal -0.563488 -0.226416 0.794491 + outer loop + vertex 791.807 376.548 47.3379 + vertex 788.464 376.212 44.8716 + vertex 795.146 368.289 47.3523 + endloop + endfacet + facet normal -0.556232 -0.217968 0.801933 + outer loop + vertex 795.146 368.289 47.3523 + vertex 788.464 376.212 44.8716 + vertex 791.735 367.596 44.7983 + endloop + endfacet + facet normal -0.578394 -0.15972 0.799969 + outer loop + vertex 789.072 384.933 47.0349 + vertex 785.694 385.025 44.6108 + vertex 791.807 376.548 47.3379 + endloop + endfacet + facet normal -0.576051 -0.157335 0.802129 + outer loop + vertex 791.807 376.548 47.3379 + vertex 785.694 385.025 44.6108 + vertex 788.464 376.212 44.8716 + endloop + endfacet + facet normal -0.00624512 -0.298716 0.954322 + outer loop + vertex 830.425 229.84 40.4956 + vertex 827.949 227.291 39.6815 + vertex 830.905 227.551 39.7821 + endloop + endfacet + facet normal -0.00841621 -0.276564 0.960959 + outer loop + vertex 830.905 227.551 39.7821 + vertex 827.949 227.291 39.6815 + vertex 828.052 224.7 38.9367 + endloop + endfacet + facet normal 0.0181101 -0.27555 0.961116 + outer loop + vertex 827.949 227.291 39.6815 + vertex 825.261 224.576 38.9537 + vertex 828.052 224.7 38.9367 + endloop + endfacet + facet normal 0.0172407 -0.255178 0.96674 + outer loop + vertex 828.052 224.7 38.9367 + vertex 825.261 224.576 38.9537 + vertex 825.041 221.872 38.2438 + endloop + endfacet + facet normal -0.292351 -0.151385 0.944253 + outer loop + vertex 828.293 241.487 43.1329 + vertex 826.427 246.171 43.306 + vertex 825.866 240.842 42.2781 + endloop + endfacet + facet normal -0.264444 -0.119448 0.956975 + outer loop + vertex 823.704 238.577 41.3979 + vertex 825.866 240.842 42.2781 + vertex 821.512 246.993 41.8424 + endloop + endfacet + facet normal -0.299791 -0.104284 0.948288 + outer loop + vertex 824.59 254.148 43.6026 + vertex 821.512 246.993 41.8424 + vertex 826.427 246.171 43.306 + endloop + endfacet + facet normal -0.305023 -0.149341 0.940563 + outer loop + vertex 825.866 240.842 42.2781 + vertex 826.427 246.171 43.306 + vertex 821.512 246.993 41.8424 + endloop + endfacet + facet normal -0.341613 -0.0917182 0.935355 + outer loop + vertex 823.304 264.227 44.1213 + vertex 819.415 260.018 42.288 + vertex 824.59 254.148 43.6026 + endloop + endfacet + facet normal -0.335969 -0.0861677 0.937923 + outer loop + vertex 824.59 254.148 43.6026 + vertex 819.415 260.018 42.288 + vertex 821.512 246.993 41.8424 + endloop + endfacet + facet normal -0.374935 -0.0886104 0.922806 + outer loop + vertex 821.834 275.122 44.5702 + vertex 817.694 271.534 42.5436 + vertex 823.304 264.227 44.1213 + endloop + endfacet + facet normal -0.358353 -0.0741902 0.930634 + outer loop + vertex 823.304 264.227 44.1213 + vertex 817.694 271.534 42.5436 + vertex 819.415 260.018 42.288 + endloop + endfacet + facet normal -0.39059 -0.0887038 0.916281 + outer loop + vertex 819.807 286.244 44.7826 + vertex 815.658 282.657 42.667 + vertex 821.834 275.122 44.5702 + endloop + endfacet + facet normal -0.381444 -0.0800352 0.920921 + outer loop + vertex 821.834 275.122 44.5702 + vertex 815.658 282.657 42.667 + vertex 817.694 271.534 42.5436 + endloop + endfacet + facet normal -0.394218 -0.0964674 0.91394 + outer loop + vertex 817.377 296.722 44.8405 + vertex 813.212 293.319 42.6848 + vertex 819.807 286.244 44.7826 + endloop + endfacet + facet normal -0.389021 -0.0907914 0.916744 + outer loop + vertex 819.807 286.244 44.7826 + vertex 813.212 293.319 42.6848 + vertex 815.658 282.657 42.667 + endloop + endfacet + facet normal -0.395068 -0.110509 0.911981 + outer loop + vertex 814.626 306.512 44.8351 + vertex 810.457 303.419 42.6543 + vertex 817.377 296.722 44.8405 + endloop + endfacet + facet normal -0.389252 -0.103413 0.915308 + outer loop + vertex 817.377 296.722 44.8405 + vertex 810.457 303.419 42.6543 + vertex 813.212 293.319 42.6848 + endloop + endfacet + facet normal -0.395954 -0.124621 0.909775 + outer loop + vertex 811.657 315.826 44.8188 + vertex 807.485 313.057 42.6239 + vertex 814.626 306.512 44.8351 + endloop + endfacet + facet normal -0.390459 -0.117506 0.91309 + outer loop + vertex 814.626 306.512 44.8351 + vertex 807.485 313.057 42.6239 + vertex 810.457 303.419 42.6543 + endloop + endfacet + facet normal -0.396845 -0.13617 0.907729 + outer loop + vertex 808.55 324.823 44.8103 + vertex 804.363 322.385 42.6141 + vertex 811.657 315.826 44.8188 + endloop + endfacet + facet normal -0.392484 -0.1304 0.910468 + outer loop + vertex 811.657 315.826 44.8188 + vertex 804.363 322.385 42.6141 + vertex 807.485 313.057 42.6239 + endloop + endfacet + facet normal -0.400892 -0.148804 0.90396 + outer loop + vertex 805.313 333.59 44.8176 + vertex 801.132 331.512 42.6212 + vertex 808.55 324.823 44.8103 + endloop + endfacet + facet normal -0.394552 -0.140424 0.90808 + outer loop + vertex 808.55 324.823 44.8103 + vertex 801.132 331.512 42.6212 + vertex 804.363 322.385 42.6141 + endloop + endfacet + facet normal -0.407331 -0.157629 0.899574 + outer loop + vertex 801.975 342.187 44.8124 + vertex 797.806 340.493 42.6279 + vertex 805.313 333.59 44.8176 + endloop + endfacet + facet normal -0.400758 -0.149086 0.903973 + outer loop + vertex 805.313 333.59 44.8176 + vertex 797.806 340.493 42.6279 + vertex 801.132 331.512 42.6212 + endloop + endfacet + facet normal -0.417279 -0.16467 0.893735 + outer loop + vertex 798.563 350.674 44.7835 + vertex 794.407 349.368 42.6023 + vertex 801.975 342.187 44.8124 + endloop + endfacet + facet normal -0.408807 -0.153956 0.899541 + outer loop + vertex 801.975 342.187 44.8124 + vertex 794.407 349.368 42.6023 + vertex 797.806 340.493 42.6279 + endloop + endfacet + facet normal -0.430587 -0.171935 0.886021 + outer loop + vertex 795.133 359.118 44.755 + vertex 790.967 358.195 42.5511 + vertex 798.563 350.674 44.7835 + endloop + endfacet + facet normal -0.419379 -0.158272 0.893908 + outer loop + vertex 798.563 350.674 44.7835 + vertex 790.967 358.195 42.5511 + vertex 794.407 349.368 42.6023 + endloop + endfacet + facet normal -0.450202 -0.184898 0.873574 + outer loop + vertex 791.735 367.596 44.7983 + vertex 787.567 367.031 42.5308 + vertex 795.133 359.118 44.755 + endloop + endfacet + facet normal -0.432527 -0.164362 0.886513 + outer loop + vertex 795.133 359.118 44.755 + vertex 787.567 367.031 42.5308 + vertex 790.967 358.195 42.5511 + endloop + endfacet + facet normal -0.466949 -0.18461 0.864799 + outer loop + vertex 788.464 376.212 44.8716 + vertex 784.379 375.974 42.6148 + vertex 791.735 367.596 44.7983 + endloop + endfacet + facet normal -0.453108 -0.169761 0.875143 + outer loop + vertex 791.735 367.596 44.7983 + vertex 784.379 375.974 42.6148 + vertex 787.567 367.031 42.5308 + endloop + endfacet + facet normal -0.460995 -0.118882 0.879403 + outer loop + vertex 785.694 385.025 44.6108 + vertex 781.763 385.127 42.5637 + vertex 788.464 376.212 44.8716 + endloop + endfacet + facet normal -0.473559 -0.130492 0.871042 + outer loop + vertex 788.464 376.212 44.8716 + vertex 781.763 385.127 42.5637 + vertex 784.379 375.974 42.6148 + endloop + endfacet + facet normal 0.0370695 -0.25655 0.96582 + outer loop + vertex 825.261 224.576 38.9537 + vertex 822.646 221.92 38.3485 + vertex 825.041 221.872 38.2438 + endloop + endfacet + facet normal 0.0375913 -0.239873 0.970076 + outer loop + vertex 825.041 221.872 38.2438 + vertex 822.646 221.92 38.3485 + vertex 822.42 219.637 37.7927 + endloop + endfacet + facet normal 0.0340294 -0.239571 0.970282 + outer loop + vertex 822.646 221.92 38.3485 + vertex 819.959 219.532 37.8531 + vertex 822.42 219.637 37.7927 + endloop + endfacet + facet normal 0.0331975 -0.217034 0.975599 + outer loop + vertex 822.42 219.637 37.7927 + vertex 819.959 219.532 37.8531 + vertex 819.916 216.963 37.2832 + endloop + endfacet + facet normal -0.24347 -0.0722785 0.967211 + outer loop + vertex 819.415 260.018 42.288 + vertex 814.825 255.401 40.7876 + vertex 821.512 246.993 41.8424 + endloop + endfacet + facet normal -0.229596 -0.0607209 0.97139 + outer loop + vertex 821.512 246.993 41.8424 + vertex 814.825 255.401 40.7876 + vertex 815.849 243.929 40.3126 + endloop + endfacet + facet normal -0.270778 -0.0617744 0.960658 + outer loop + vertex 817.694 271.534 42.5436 + vertex 813.098 267.327 40.9777 + vertex 819.415 260.018 42.288 + endloop + endfacet + facet normal -0.261511 -0.0532151 0.963732 + outer loop + vertex 819.415 260.018 42.288 + vertex 813.098 267.327 40.9777 + vertex 814.825 255.401 40.7876 + endloop + endfacet + facet normal -0.285697 -0.0629003 0.956253 + outer loop + vertex 815.658 282.657 42.667 + vertex 811.022 278.746 41.0244 + vertex 817.694 271.534 42.5436 + endloop + endfacet + facet normal -0.277128 -0.0543309 0.959296 + outer loop + vertex 817.694 271.534 42.5436 + vertex 811.022 278.746 41.0244 + vertex 813.098 267.327 40.9777 + endloop + endfacet + facet normal -0.290135 -0.0681674 0.954555 + outer loop + vertex 813.212 293.319 42.6848 + vertex 808.558 289.648 41.0082 + vertex 815.658 282.657 42.667 + endloop + endfacet + facet normal -0.285545 -0.0630945 0.956286 + outer loop + vertex 815.658 282.657 42.667 + vertex 808.558 289.648 41.0082 + vertex 811.022 278.746 41.0244 + endloop + endfacet + facet normal -0.29096 -0.0764841 0.953673 + outer loop + vertex 810.457 303.419 42.6543 + vertex 805.8 300.064 40.9643 + vertex 813.212 293.319 42.6848 + endloop + endfacet + facet normal -0.287273 -0.0720598 0.955134 + outer loop + vertex 813.212 293.319 42.6848 + vertex 805.8 300.064 40.9643 + vertex 808.558 289.648 41.0082 + endloop + endfacet + facet normal -0.290253 -0.0864846 0.953034 + outer loop + vertex 807.485 313.057 42.6239 + vertex 802.83 310.06 40.9342 + vertex 810.457 303.419 42.6543 + endloop + endfacet + facet normal -0.286978 -0.082372 0.954389 + outer loop + vertex 810.457 303.419 42.6543 + vertex 802.83 310.06 40.9342 + vertex 805.8 300.064 40.9643 + endloop + endfacet + facet normal -0.292014 -0.0967328 0.95151 + outer loop + vertex 804.363 322.385 42.6141 + vertex 799.727 319.76 40.9243 + vertex 807.485 313.057 42.6239 + endloop + endfacet + facet normal -0.287492 -0.0910068 0.953449 + outer loop + vertex 807.485 313.057 42.6239 + vertex 799.727 319.76 40.9243 + vertex 802.83 310.06 40.9342 + endloop + endfacet + facet normal -0.2975 -0.106088 0.948809 + outer loop + vertex 801.132 331.512 42.6212 + vertex 796.525 329.26 40.9251 + vertex 804.363 322.385 42.6141 + endloop + endfacet + facet normal -0.291205 -0.0982235 0.951605 + outer loop + vertex 804.363 322.385 42.6141 + vertex 796.525 329.26 40.9251 + vertex 799.727 319.76 40.9243 + endloop + endfacet + facet normal -0.302766 -0.112828 0.946363 + outer loop + vertex 797.806 340.493 42.6279 + vertex 793.228 338.632 40.9416 + vertex 801.132 331.512 42.6212 + endloop + endfacet + facet normal -0.297402 -0.106295 0.948817 + outer loop + vertex 801.132 331.512 42.6212 + vertex 793.228 338.632 40.9416 + vertex 796.525 329.26 40.9251 + endloop + endfacet + facet normal -0.30964 -0.115852 0.94377 + outer loop + vertex 794.407 349.368 42.6023 + vertex 789.859 347.912 40.9314 + vertex 797.806 340.493 42.6279 + endloop + endfacet + facet normal -0.30415 -0.109388 0.946323 + outer loop + vertex 797.806 340.493 42.6279 + vertex 789.859 347.912 40.9314 + vertex 793.228 338.632 40.9416 + endloop + endfacet + facet normal -0.318787 -0.118795 0.940352 + outer loop + vertex 790.967 358.195 42.5511 + vertex 786.435 357.155 40.8836 + vertex 794.407 349.368 42.6023 + endloop + endfacet + facet normal -0.311394 -0.110457 0.943839 + outer loop + vertex 794.407 349.368 42.6023 + vertex 786.435 357.155 40.8836 + vertex 789.859 347.912 40.9314 + endloop + endfacet + facet normal -0.33405 -0.126368 0.934046 + outer loop + vertex 787.567 367.031 42.5308 + vertex 783.028 366.41 40.8235 + vertex 790.967 358.195 42.5511 + endloop + endfacet + facet normal -0.320477 -0.111868 0.940627 + outer loop + vertex 790.967 358.195 42.5511 + vertex 783.028 366.41 40.8235 + vertex 786.435 357.155 40.8836 + endloop + endfacet + facet normal -0.352459 -0.134357 0.926132 + outer loop + vertex 784.379 375.974 42.6148 + vertex 779.842 375.74 40.8544 + vertex 787.567 367.031 42.5308 + endloop + endfacet + facet normal -0.335479 -0.117651 0.934672 + outer loop + vertex 787.567 367.031 42.5308 + vertex 779.842 375.74 40.8544 + vertex 783.028 366.41 40.8235 + endloop + endfacet + facet normal -0.344575 -0.0932735 0.934113 + outer loop + vertex 781.763 385.127 42.5637 + vertex 777.328 385.236 40.9389 + vertex 784.379 375.974 42.6148 + endloop + endfacet + facet normal -0.35528 -0.102321 0.929143 + outer loop + vertex 784.379 375.974 42.6148 + vertex 777.328 385.236 40.9389 + vertex 779.842 375.74 40.8544 + endloop + endfacet + facet normal 0.0323733 -0.217027 0.975629 + outer loop + vertex 819.959 219.532 37.8531 + vertex 816.679 216.882 37.3724 + vertex 819.916 216.963 37.2832 + endloop + endfacet + facet normal 0.0317872 -0.187045 0.981837 + outer loop + vertex 819.916 216.963 37.2832 + vertex 816.679 216.882 37.3724 + vertex 816.535 213.676 36.7664 + endloop + endfacet + facet normal 0.0429348 -0.187454 0.981335 + outer loop + vertex 816.679 216.882 37.3724 + vertex 812.795 213.383 36.8742 + vertex 816.535 213.676 36.7664 + endloop + endfacet + facet normal 0.0414396 -0.166958 0.985093 + outer loop + vertex 816.535 213.676 36.7664 + vertex 812.795 213.383 36.8742 + vertex 813.321 210.663 36.3911 + endloop + endfacet + facet normal 0.0566316 -0.163974 0.984838 + outer loop + vertex 813.321 210.663 36.3911 + vertex 812.795 213.383 36.8742 + vertex 808.166 208.565 36.338 + endloop + endfacet + facet normal 0.509885 -0.17585 0.842077 + outer loop + vertex 707.207 169.978 46.9581 + vertex 704.935 169.413 48.2159 + vertex 706.264 162.991 46.07 + endloop + endfacet + facet normal 0.483213 -0.18587 0.855545 + outer loop + vertex 706.264 162.991 46.07 + vertex 704.935 169.413 48.2159 + vertex 703.828 162.337 47.3042 + endloop + endfacet + facet normal 0.468603 -0.158682 0.869041 + outer loop + vertex 709.85 170.703 45.6654 + vertex 707.207 169.978 46.9581 + vertex 709.155 163.973 44.8115 + endloop + endfacet + facet normal 0.441696 -0.171543 0.880612 + outer loop + vertex 709.155 163.973 44.8115 + vertex 707.207 169.978 46.9581 + vertex 706.264 162.991 46.07 + endloop + endfacet + facet normal 0.451381 -0.220476 0.864665 + outer loop + vertex 709.155 163.973 44.8115 + vertex 706.264 162.991 46.07 + vertex 708.136 157.431 43.6751 + endloop + endfacet + facet normal 0.416992 -0.23751 0.877329 + outer loop + vertex 708.136 157.431 43.6751 + vertex 706.264 162.991 46.07 + vertex 704.889 156.307 44.9146 + endloop + endfacet + facet normal 0.489641 -0.245435 0.836668 + outer loop + vertex 706.264 162.991 46.07 + vertex 703.828 162.337 47.3042 + vertex 704.889 156.307 44.9146 + endloop + endfacet + facet normal 0.460193 -0.25595 0.850125 + outer loop + vertex 704.889 156.307 44.9146 + vertex 703.828 162.337 47.3042 + vertex 702.211 155.495 46.1195 + endloop + endfacet + facet normal 0.522142 -0.0641734 0.850441 + outer loop + vertex 708.393 186.127 47.871 + vertex 706.325 184.223 48.9971 + vertex 707.866 177.422 47.5376 + endloop + endfacet + facet normal 0.51312 -0.0673402 0.855671 + outer loop + vertex 707.866 177.422 47.5376 + vertex 706.325 184.223 48.9971 + vertex 705.689 176.935 48.8049 + endloop + endfacet + facet normal 0.46431 -0.0645615 0.883316 + outer loop + vertex 710.922 185.181 46.4724 + vertex 708.393 186.127 47.871 + vertex 710.383 178.018 46.2325 + endloop + endfacet + facet normal 0.471076 -0.0622105 0.879896 + outer loop + vertex 710.383 178.018 46.2325 + vertex 708.393 186.127 47.871 + vertex 707.866 177.422 47.5376 + endloop + endfacet + facet normal 0.476986 -0.102392 0.872926 + outer loop + vertex 710.383 178.018 46.2325 + vertex 707.866 177.422 47.5376 + vertex 709.85 170.703 45.6654 + endloop + endfacet + facet normal 0.460792 -0.109354 0.880746 + outer loop + vertex 709.85 170.703 45.6654 + vertex 707.866 177.422 47.5376 + vertex 707.207 169.978 46.9581 + endloop + endfacet + facet normal 0.518465 -0.11189 0.847747 + outer loop + vertex 707.866 177.422 47.5376 + vertex 705.689 176.935 48.8049 + vertex 707.207 169.978 46.9581 + endloop + endfacet + facet normal 0.50316 -0.117467 0.856173 + outer loop + vertex 707.207 169.978 46.9581 + vertex 705.689 176.935 48.8049 + vertex 704.935 169.413 48.2159 + endloop + endfacet + facet normal 0.504103 -0.0372408 0.86284 + outer loop + vertex 706.325 184.223 48.9971 + vertex 708.393 186.127 47.871 + vertex 705.883 196.029 49.7651 + endloop + endfacet + facet normal 0.473432 -0.0354538 0.880117 + outer loop + vertex 710.922 185.181 46.4724 + vertex 709.819 196.784 47.5335 + vertex 708.393 186.127 47.871 + endloop + endfacet + facet normal 0.498523 -0.0392572 0.865987 + outer loop + vertex 709.819 196.784 47.5335 + vertex 705.883 196.029 49.7651 + vertex 708.393 186.127 47.871 + endloop + endfacet + facet normal 0.486608 -0.0130942 0.873522 + outer loop + vertex 710.117 212.897 47.6089 + vertex 706.289 212.134 49.7299 + vertex 709.819 196.784 47.5335 + endloop + endfacet + facet normal 0.494722 -0.0105794 0.868987 + outer loop + vertex 709.819 196.784 47.5335 + vertex 706.289 212.134 49.7299 + vertex 705.883 196.029 49.7651 + endloop + endfacet + facet normal 0.492689 0.0059299 0.870185 + outer loop + vertex 709.895 228.239 47.6299 + vertex 706.164 227.643 49.7463 + vertex 710.117 212.897 47.6089 + endloop + endfacet + facet normal 0.4842 0.00296345 0.874952 + outer loop + vertex 710.117 212.897 47.6089 + vertex 706.164 227.643 49.7463 + vertex 706.289 212.134 49.7299 + endloop + endfacet + facet normal 0.504774 0.0153476 0.863115 + outer loop + vertex 709.456 242.893 47.6262 + vertex 705.822 242.48 49.7589 + vertex 709.895 228.239 47.6299 + endloop + endfacet + facet normal 0.492102 0.0106229 0.870472 + outer loop + vertex 709.895 228.239 47.6299 + vertex 705.822 242.48 49.7589 + vertex 706.164 227.643 49.7463 + endloop + endfacet + facet normal 0.519833 0.0173925 0.854091 + outer loop + vertex 708.978 257.205 47.6254 + vertex 705.466 256.905 49.7691 + vertex 709.456 242.893 47.6262 + endloop + endfacet + facet normal 0.505096 0.0118366 0.862982 + outer loop + vertex 709.456 242.893 47.6262 + vertex 705.466 256.905 49.7691 + vertex 705.822 242.48 49.7589 + endloop + endfacet + facet normal 0.534401 0.0141493 0.845113 + outer loop + vertex 708.596 271.478 47.6281 + vertex 705.215 271.22 49.7705 + vertex 708.978 257.205 47.6254 + endloop + endfacet + facet normal 0.520409 0.00905216 0.853869 + outer loop + vertex 708.978 257.205 47.6254 + vertex 705.215 271.22 49.7705 + vertex 705.466 256.905 49.7691 + endloop + endfacet + facet normal 0.55083 0.0117519 0.834535 + outer loop + vertex 708.294 285.772 47.626 + vertex 705.035 285.577 49.7799 + vertex 708.596 271.478 47.6281 + endloop + endfacet + facet normal 0.53488 0.00614056 0.844906 + outer loop + vertex 708.596 271.478 47.6281 + vertex 705.035 285.577 49.7799 + vertex 705.215 271.22 49.7705 + endloop + endfacet + facet normal 0.569501 0.0105507 0.821923 + outer loop + vertex 708.043 300.054 47.617 + vertex 704.936 299.906 49.7715 + vertex 708.294 285.772 47.626 + endloop + endfacet + facet normal 0.551173 0.0043051 0.83438 + outer loop + vertex 708.294 285.772 47.626 + vertex 704.936 299.906 49.7715 + vertex 705.035 285.577 49.7799 + endloop + endfacet + facet normal 0.590297 0.0102938 0.807121 + outer loop + vertex 707.802 314.316 47.6113 + vertex 704.862 314.206 49.7631 + vertex 708.043 300.054 47.617 + endloop + endfacet + facet normal 0.569757 0.00344992 0.821806 + outer loop + vertex 708.043 300.054 47.617 + vertex 704.862 314.206 49.7631 + vertex 704.936 299.906 49.7715 + endloop + endfacet + facet normal 0.613374 0.00993412 0.78973 + outer loop + vertex 707.549 328.577 47.6285 + vertex 704.776 328.53 49.7831 + vertex 707.802 314.316 47.6113 + endloop + endfacet + facet normal 0.590519 0.00242626 0.80702 + outer loop + vertex 707.802 314.316 47.6113 + vertex 704.776 328.53 49.7831 + vertex 704.862 314.206 49.7631 + endloop + endfacet + facet normal 0.638214 0.00876953 0.769809 + outer loop + vertex 707.306 342.853 47.6669 + vertex 704.715 342.851 49.8156 + vertex 707.549 328.577 47.6285 + endloop + endfacet + facet normal 0.613501 0.000815509 0.789694 + outer loop + vertex 707.549 328.577 47.6285 + vertex 704.715 342.851 49.8156 + vertex 704.776 328.53 49.7831 + endloop + endfacet + facet normal 0.664143 0.00719254 0.747571 + outer loop + vertex 707.103 357.185 47.7093 + vertex 704.678 357.204 49.8642 + vertex 707.306 342.853 47.6669 + endloop + endfacet + facet normal 0.638243 -0.000960141 0.769835 + outer loop + vertex 707.306 342.853 47.6669 + vertex 704.678 357.204 49.8642 + vertex 704.715 342.851 49.8156 + endloop + endfacet + facet normal 0.700282 -0.000862931 0.713866 + outer loop + vertex 707.122 371.714 47.7088 + vertex 704.826 371.728 49.9609 + vertex 707.103 357.185 47.7093 + endloop + endfacet + facet normal 0.664029 -0.0117643 0.747614 + outer loop + vertex 707.103 357.185 47.7093 + vertex 704.826 371.728 49.9609 + vertex 704.678 357.204 49.8642 + endloop + endfacet + facet normal 0.748782 -0.017217 0.662592 + outer loop + vertex 707.708 386.624 47.4344 + vertex 705.335 386.645 50.1156 + vertex 707.122 371.714 47.7088 + endloop + endfacet + facet normal 0.699841 -0.0312966 0.713612 + outer loop + vertex 707.122 371.714 47.7088 + vertex 705.335 386.645 50.1156 + vertex 704.826 371.728 49.9609 + endloop + endfacet + facet normal 0.480779 -0.331687 0.811687 + outer loop + vertex 697.361 149.713 46.7182 + vertex 698.32 150.528 46.4835 + vertex 698.866 154.813 47.9109 + endloop + endfacet + facet normal 0.501707 -0.329702 0.799741 + outer loop + vertex 699.173 150.227 45.8241 + vertex 700.186 155.008 47.1598 + vertex 698.32 150.528 46.4835 + endloop + endfacet + facet normal 0.503288 -0.330181 0.798549 + outer loop + vertex 700.186 155.008 47.1598 + vertex 698.866 154.813 47.9109 + vertex 698.32 150.528 46.4835 + endloop + endfacet + facet normal 0.471475 -0.328512 0.818408 + outer loop + vertex 699.173 150.227 45.8241 + vertex 700.475 151.174 45.4544 + vertex 700.186 155.008 47.1598 + endloop + endfacet + facet normal 0.492771 -0.322385 0.808236 + outer loop + vertex 702.211 155.495 46.1195 + vertex 700.186 155.008 47.1598 + vertex 700.475 151.174 45.4544 + endloop + endfacet + facet normal 0.549534 -0.199368 0.811335 + outer loop + vertex 703.216 169.181 49.2936 + vertex 702.122 169.329 50.0712 + vertex 702.015 162.035 48.3507 + endloop + endfacet + facet normal 0.529515 -0.202037 0.82389 + outer loop + vertex 702.015 162.035 48.3507 + vertex 702.122 169.329 50.0712 + vertex 700.848 162.042 49.1027 + endloop + endfacet + facet normal 0.539651 -0.190142 0.820136 + outer loop + vertex 704.935 169.413 48.2159 + vertex 703.216 169.181 49.2936 + vertex 703.828 162.337 47.3042 + endloop + endfacet + facet normal 0.514644 -0.196571 0.834567 + outer loop + vertex 703.828 162.337 47.3042 + vertex 703.216 169.181 49.2936 + vertex 702.015 162.035 48.3507 + endloop + endfacet + facet normal 0.514919 -0.262956 0.815912 + outer loop + vertex 703.828 162.337 47.3042 + vertex 702.015 162.035 48.3507 + vertex 702.211 155.495 46.1195 + endloop + endfacet + facet normal 0.490482 -0.268206 0.829152 + outer loop + vertex 702.211 155.495 46.1195 + vertex 702.015 162.035 48.3507 + vertex 700.186 155.008 47.1598 + endloop + endfacet + facet normal 0.519887 -0.272545 0.809591 + outer loop + vertex 702.015 162.035 48.3507 + vertex 700.848 162.042 49.1027 + vertex 700.186 155.008 47.1598 + endloop + endfacet + facet normal 0.50599 -0.273562 0.818008 + outer loop + vertex 700.186 155.008 47.1598 + vertex 700.848 162.042 49.1027 + vertex 698.866 154.813 47.9109 + endloop + endfacet + facet normal 0.354201 -0.314061 0.880856 + outer loop + vertex 696.531 149.674 47.2269 + vertex 696.736 150.214 47.3372 + vertex 698.17 154.79 48.3922 + endloop + endfacet + facet normal 0.652127 -0.356312 0.669158 + outer loop + vertex 696.581 149.523 47.1204 + vertex 698.285 154.807 48.273 + vertex 696.736 150.214 47.3372 + endloop + endfacet + facet normal 0.694716 -0.361085 0.622083 + outer loop + vertex 698.285 154.807 48.273 + vertex 698.17 154.79 48.3922 + vertex 696.736 150.214 47.3372 + endloop + endfacet + facet normal 0.452224 -0.326886 0.829843 + outer loop + vertex 696.581 149.523 47.1204 + vertex 697.072 150.228 47.1302 + vertex 698.285 154.807 48.273 + endloop + endfacet + facet normal 0.519265 -0.336899 0.785406 + outer loop + vertex 697.361 149.713 46.7182 + vertex 698.866 154.813 47.9109 + vertex 697.072 150.228 47.1302 + endloop + endfacet + facet normal 0.501295 -0.332178 0.798975 + outer loop + vertex 698.866 154.813 47.9109 + vertex 698.285 154.807 48.273 + vertex 697.072 150.228 47.1302 + endloop + endfacet + facet normal 0.679148 -0.215347 0.7017 + outer loop + vertex 701.561 169.486 50.5075 + vertex 701.316 169.17 50.6482 + vertex 700.246 162.126 49.5219 + endloop + endfacet + facet normal 0.602616 -0.214432 0.768682 + outer loop + vertex 700.246 162.126 49.5219 + vertex 701.316 169.17 50.6482 + vertex 699.999 161.917 49.6569 + endloop + endfacet + facet normal 0.565171 -0.204976 0.799104 + outer loop + vertex 702.122 169.329 50.0712 + vertex 701.561 169.486 50.5075 + vertex 700.848 162.042 49.1027 + endloop + endfacet + facet normal 0.539778 -0.205781 0.816269 + outer loop + vertex 700.848 162.042 49.1027 + vertex 701.561 169.486 50.5075 + vertex 700.246 162.126 49.5219 + endloop + endfacet + facet normal 0.522985 -0.276294 0.806318 + outer loop + vertex 700.848 162.042 49.1027 + vertex 700.246 162.126 49.5219 + vertex 698.866 154.813 47.9109 + endloop + endfacet + facet normal 0.510365 -0.275728 0.814556 + outer loop + vertex 698.866 154.813 47.9109 + vertex 700.246 162.126 49.5219 + vertex 698.285 154.807 48.273 + endloop + endfacet + facet normal 0.637887 -0.292468 0.712434 + outer loop + vertex 700.246 162.126 49.5219 + vertex 699.999 161.917 49.6569 + vertex 698.285 154.807 48.273 + endloop + endfacet + facet normal 0.706718 -0.295515 0.642822 + outer loop + vertex 698.285 154.807 48.273 + vertex 699.999 161.917 49.6569 + vertex 698.17 154.79 48.3922 + endloop + endfacet + facet normal 0.62362 -0.368879 0.689221 + outer loop + vertex 696.553 149.857 47.3429 + vertex 696.79 150.449 47.4443 + vertex 698.092 154.473 48.4202 + endloop + endfacet + facet normal 0.936955 -0.242812 -0.25131 + outer loop + vertex 696.531 149.674 47.2269 + vertex 698.17 154.79 48.3922 + vertex 696.79 150.449 47.4443 + endloop + endfacet + facet normal 0.941922 -0.250399 -0.223792 + outer loop + vertex 698.17 154.79 48.3922 + vertex 698.092 154.473 48.4202 + vertex 696.79 150.449 47.4443 + endloop + endfacet + facet normal 0.971925 -0.151856 -0.179729 + outer loop + vertex 701.316 169.17 50.6482 + vertex 701.113 167.948 50.5844 + vertex 699.999 161.917 49.6569 + endloop + endfacet + facet normal 0.976149 -0.194967 0.095507 + outer loop + vertex 699.999 161.917 49.6569 + vertex 701.113 167.948 50.5844 + vertex 699.818 160.995 49.6336 + endloop + endfacet + facet normal 0.917519 -0.171921 -0.358612 + outer loop + vertex 699.999 161.917 49.6569 + vertex 699.818 160.995 49.6336 + vertex 698.17 154.79 48.3922 + endloop + endfacet + facet normal 0.967522 -0.243048 -0.0694951 + outer loop + vertex 698.17 154.79 48.3922 + vertex 699.818 160.995 49.6336 + vertex 698.092 154.473 48.4202 + endloop + endfacet + facet normal -0.768502 -0.248168 0.58976 + outer loop + vertex 795.142 379.773 51.8409 + vertex 794.163 384.78 52.6728 + vertex 792.003 384.848 49.887 + endloop + endfacet + facet normal -0.709384 -0.289035 0.642832 + outer loop + vertex 798.292 372.764 52.1664 + vertex 795.142 379.773 51.8409 + vertex 795.676 376.842 51.1135 + endloop + endfacet + facet normal -0.700713 -0.314256 0.640503 + outer loop + vertex 800.894 367.155 52.2616 + vertex 798.292 372.764 52.1664 + vertex 798.401 370.824 51.3339 + endloop + endfacet + facet normal -0.695362 -0.320897 0.643038 + outer loop + vertex 803.176 362.617 52.4643 + vertex 800.894 367.155 52.2616 + vertex 802.026 363.203 51.5122 + endloop + endfacet + facet normal -0.695558 -0.324896 0.640813 + outer loop + vertex 805.587 357.094 52.2804 + vertex 803.176 362.617 52.4643 + vertex 802.026 363.203 51.5122 + endloop + endfacet + facet normal -0.676076 -0.312763 0.667159 + outer loop + vertex 808.016 351.546 52.142 + vertex 805.587 357.094 52.2804 + vertex 805.377 355.478 51.31 + endloop + endfacet + facet normal -0.661946 -0.296369 0.688471 + outer loop + vertex 810.224 347.04 52.325 + vertex 808.016 351.546 52.142 + vertex 809.036 347.547 51.4 + endloop + endfacet + facet normal -0.661603 -0.29008 0.691473 + outer loop + vertex 812.543 341.501 52.2202 + vertex 810.224 347.04 52.325 + vertex 809.036 347.547 51.4 + endloop + endfacet + facet normal -0.654051 -0.278426 0.703347 + outer loop + vertex 814.828 335.916 52.1336 + vertex 812.543 341.501 52.2202 + vertex 812.237 339.803 51.2636 + endloop + endfacet + facet normal -0.646859 -0.259512 0.717096 + outer loop + vertex 816.928 331.276 52.3489 + vertex 814.828 335.916 52.1336 + vertex 815.634 331.844 51.3876 + endloop + endfacet + facet normal -0.645972 -0.251064 0.720893 + outer loop + vertex 818.975 325.637 52.2193 + vertex 816.928 331.276 52.3489 + vertex 815.634 331.844 51.3876 + endloop + endfacet + facet normal -0.6449 -0.237978 0.726271 + outer loop + vertex 820.969 319.942 52.1238 + vertex 818.975 325.637 52.2193 + vertex 818.548 323.884 51.2652 + endloop + endfacet + facet normal -0.635044 -0.216528 0.741508 + outer loop + vertex 822.847 315.174 52.34 + vertex 820.969 319.942 52.1238 + vertex 821.71 315.4 51.4319 + endloop + endfacet + facet normal -0.635271 -0.201304 0.745592 + outer loop + vertex 824.598 309.419 52.2779 + vertex 822.847 315.174 52.34 + vertex 821.71 315.4 51.4319 + endloop + endfacet + facet normal -0.636847 -0.191978 0.746706 + outer loop + vertex 826.046 304.777 52.3192 + vertex 824.598 309.419 52.2779 + vertex 824.713 305.873 51.464 + endloop + endfacet + facet normal -0.627012 -0.169363 0.760376 + outer loop + vertex 827.275 300.164 52.3057 + vertex 826.046 304.777 52.3192 + vertex 824.713 305.873 51.464 + endloop + endfacet + facet normal -0.644617 -0.165771 0.746317 + outer loop + vertex 828.485 295.498 52.3138 + vertex 827.275 300.164 52.3057 + vertex 827.282 296.269 51.4465 + endloop + endfacet + facet normal -0.637541 -0.142611 0.757102 + outer loop + vertex 829.511 290.687 52.2721 + vertex 828.485 295.498 52.3138 + vertex 827.282 296.269 51.4465 + endloop + endfacet + facet normal -0.673751 -0.140737 0.725433 + outer loop + vertex 830.87 284.433 52.3204 + vertex 829.511 290.687 52.2721 + vertex 829.529 285.828 51.346 + endloop + endfacet + facet normal -0.671057 -0.135747 0.728872 + outer loop + vertex 831.556 279.661 52.0636 + vertex 830.87 284.433 52.3204 + vertex 829.529 285.828 51.346 + endloop + endfacet + facet normal -0.709442 -0.135474 0.691621 + outer loop + vertex 832.606 274.612 52.152 + vertex 831.556 279.661 52.0636 + vertex 831.746 274.129 51.1747 + endloop + endfacet + facet normal -0.70748 -0.140857 0.692554 + outer loop + vertex 833.343 270.095 51.9852 + vertex 832.606 274.612 52.152 + vertex 831.746 274.129 51.1747 + endloop + endfacet + facet normal -0.816332 -0.172432 0.551243 + outer loop + vertex 834.304 265.728 52.0438 + vertex 833.343 270.095 51.9852 + vertex 834.07 265.398 51.5931 + endloop + endfacet + facet normal -0.672416 -0.16471 0.721614 + outer loop + vertex 835.074 261.965 51.9017 + vertex 834.304 265.728 52.0438 + vertex 834.709 263.449 51.9005 + endloop + endfacet + facet normal -0.922585 -0.241458 0.300891 + outer loop + vertex 835.766 259.032 51.6708 + vertex 835.074 261.965 51.9017 + vertex 835.486 259.963 51.558 + endloop + endfacet + facet normal -0.957204 -0.27909 0.0766092 + outer loop + vertex 836.673 255.808 51.252 + vertex 835.766 259.032 51.6708 + vertex 835.486 259.963 51.558 + endloop + endfacet + facet normal -0.709 -0.318512 0.629181 + outer loop + vertex 838.096 251.363 50.6063 + vertex 836.673 255.808 51.252 + vertex 837.012 254.123 50.7815 + endloop + endfacet + facet normal 0.0943821 -0.149829 0.984197 + outer loop + vertex 839.124 248.76 50.1115 + vertex 838.096 251.363 50.6063 + vertex 838.708 249.577 50.2758 + endloop + endfacet + facet normal -0.150022 -0.358268 0.921487 + outer loop + vertex 840.218 246.859 49.5507 + vertex 839.124 248.76 50.1115 + vertex 839.356 248.189 49.9272 + endloop + endfacet + facet normal 0.053538 -0.350763 0.934933 + outer loop + vertex 841.886 244.871 48.7091 + vertex 840.218 246.859 49.5507 + vertex 840.449 246.372 49.3546 + endloop + endfacet + facet normal 0.219675 -0.298004 0.928944 + outer loop + vertex 843.753 243.421 47.8027 + vertex 841.886 244.871 48.7091 + vertex 842.683 243.986 48.2369 + endloop + endfacet + facet normal 0.20057 -0.413638 0.888074 + outer loop + vertex 845.267 242.711 47.1302 + vertex 843.753 243.421 47.8027 + vertex 844.178 243.065 47.5407 + endloop + endfacet + facet normal 0.241898 -0.537177 0.808039 + outer loop + vertex 847.08 242.431 46.4005 + vertex 845.267 242.711 47.1302 + vertex 845.459 242.464 46.9082 + endloop + endfacet + facet normal 0.261828 -0.643801 0.719003 + outer loop + vertex 844.973 240.23 45.1976 + vertex 847.08 242.431 46.4005 + vertex 845.752 241.75 46.2749 + endloop + endfacet + facet normal 0.154139 -0.56437 0.811004 + outer loop + vertex 842.061 237.17 43.6215 + vertex 844.973 240.23 45.1976 + vertex 843.651 239.187 44.7225 + endloop + endfacet + facet normal 0.0215174 -0.419408 0.907543 + outer loop + vertex 838.327 233.455 41.9931 + vertex 842.061 237.17 43.6215 + vertex 839.294 235.903 43.1017 + endloop + endfacet + facet normal -0.0133838 -0.347139 0.937718 + outer loop + vertex 834.007 229.463 40.4539 + vertex 838.327 233.455 41.9931 + vertex 835.663 232.449 41.5829 + endloop + endfacet + facet normal -0.0355218 -0.279401 0.959517 + outer loop + vertex 830.434 225.655 39.2126 + vertex 834.007 229.463 40.4539 + vertex 830.905 227.551 39.7821 + endloop + endfacet + facet normal -0.00675793 -0.262016 0.96504 + outer loop + vertex 826.995 222.477 38.3258 + vertex 830.434 225.655 39.2126 + vertex 828.052 224.7 38.9367 + endloop + endfacet + facet normal 0.0349245 -0.24386 0.969181 + outer loop + vertex 823.192 218.892 37.5607 + vertex 826.995 222.477 38.3258 + vertex 825.041 221.872 38.2438 + endloop + endfacet + facet normal 0.0456957 -0.217888 0.974903 + outer loop + vertex 818.683 214.4 36.7681 + vertex 823.192 218.892 37.5607 + vertex 819.916 216.963 37.2832 + endloop + endfacet + facet normal 0.0682069 -0.204664 0.976453 + outer loop + vertex 815.306 211.303 36.3549 + vertex 818.683 214.4 36.7681 + vertex 816.535 213.676 36.7664 + endloop + endfacet + facet normal 0.0788303 -0.189336 0.978743 + outer loop + vertex 811.285 207.992 36.0382 + vertex 815.306 211.303 36.3549 + vertex 813.321 210.663 36.3911 + endloop + endfacet + facet normal 0.0670836 -0.150949 0.986263 + outer loop + vertex 805.859 203.696 35.7497 + vertex 811.285 207.992 36.0382 + vertex 808.166 208.565 36.338 + endloop + endfacet + facet normal 0.283467 -0.256675 0.923994 + outer loop + vertex 711.974 150.795 40.1474 + vertex 716.64 152.892 39.2984 + vertex 713.632 152.998 40.2506 + endloop + endfacet + facet normal 0.314884 -0.28625 0.904936 + outer loop + vertex 707.841 148.762 40.9425 + vertex 711.974 150.795 40.1474 + vertex 710.048 151.037 40.8944 + endloop + endfacet + facet normal 0.380416 -0.36431 0.850036 + outer loop + vertex 701.58 145.927 42.4275 + vertex 704.065 146.919 41.7404 + vertex 703.146 146.972 42.1742 + endloop + endfacet + facet normal 0.467905 -0.504055 0.725943 + outer loop + vertex 693.15 143.184 45.7555 + vertex 696.23 143.898 44.2665 + vertex 695.17 143.916 44.9621 + endloop + endfacet + facet normal 0.375644 -0.400327 0.835841 + outer loop + vertex 695.4 147.438 46.7823 + vertex 693.15 143.184 45.7555 + vertex 694.716 145.593 46.2058 + endloop + endfacet + facet normal 0.210513 -0.31968 0.923845 + outer loop + vertex 697.154 151.78 47.8849 + vertex 695.4 147.438 46.7823 + vertex 695.916 148.33 46.9732 + endloop + endfacet + facet normal 0.592201 -0.350536 0.72555 + outer loop + vertex 698.903 157.214 49.0828 + vertex 697.154 151.78 47.8849 + vertex 698.092 154.473 48.4202 + endloop + endfacet + facet normal 0.896911 -0.156745 -0.413498 + outer loop + vertex 700.051 161.648 49.893 + vertex 698.903 157.214 49.0828 + vertex 699.818 160.995 49.6336 + endloop + endfacet + facet normal 0.83339 -0.0810951 -0.546703 + outer loop + vertex 700.84 166.038 50.4445 + vertex 700.051 161.648 49.893 + vertex 699.818 160.995 49.6336 + endloop + endfacet + facet normal 0.923727 -0.157638 0.349111 + outer loop + vertex 701.573 171.644 51.0371 + vertex 700.84 166.038 50.4445 + vertex 701.113 167.948 50.5844 + endloop + endfacet + facet normal 0.742695 -0.137779 0.655303 + outer loop + vertex 702.02 175.886 51.4226 + vertex 701.573 171.644 51.0371 + vertex 701.96 175.109 51.3268 + endloop + endfacet + facet normal 0.958899 -0.0388213 -0.28108 + outer loop + vertex 702.249 179.684 51.6803 + vertex 702.02 175.886 51.4226 + vertex 701.96 175.109 51.3268 + endloop + endfacet + facet normal -0.324349 -0.036848 0.945219 + outer loop + vertex 702.51 185.737 52.006 + vertex 702.249 179.684 51.6803 + vertex 702.357 181.116 51.7733 + endloop + endfacet + facet normal 0.998359 -0.0174023 -0.0545625 + outer loop + vertex 702.63 191.946 52.208 + vertex 702.51 185.737 52.006 + vertex 702.501 185.543 51.905 + endloop + endfacet + facet normal 0.910048 -0.000116656 0.414502 + outer loop + vertex 702.597 205.379 52.4295 + vertex 702.631 198.289 52.3535 + vertex 702.723 196.704 52.1505 + endloop + endfacet + facet normal 0.136514 -0.625333 0.768325 + outer loop + vertex 845.245 242.301 46.8136 + vertex 845.752 241.75 46.2749 + vertex 845.459 242.464 46.9082 + endloop + endfacet + facet normal 0.150301 -0.621795 0.768623 + outer loop + vertex 845.752 241.75 46.2749 + vertex 845.032 240.933 45.7542 + vertex 844.973 240.23 45.1976 + endloop + endfacet + facet normal 0.160119 -0.256605 0.953161 + outer loop + vertex 840.449 246.372 49.3546 + vertex 841.439 245.053 48.8333 + vertex 841.886 244.871 48.7091 + endloop + endfacet + facet normal 0.0861046 -0.407694 0.90905 + outer loop + vertex 841.439 245.053 48.8333 + vertex 842.683 243.986 48.2369 + vertex 841.886 244.871 48.7091 + endloop + endfacet + facet normal 0.0392841 -0.561225 0.82673 + outer loop + vertex 842.683 243.986 48.2369 + vertex 844.178 243.065 47.5407 + vertex 843.753 243.421 47.8027 + endloop + endfacet + facet normal 0.0884429 -0.626566 0.774334 + outer loop + vertex 844.178 243.065 47.5407 + vertex 845.459 242.464 46.9082 + vertex 845.267 242.711 47.1302 + endloop + endfacet + facet normal -0.828962 -0.353228 0.43365 + outer loop + vertex 837.012 254.123 50.7815 + vertex 838.462 250.13 50.3006 + vertex 838.096 251.363 50.6063 + endloop + endfacet + facet normal -0.752037 -0.35983 0.552235 + outer loop + vertex 838.462 250.13 50.3006 + vertex 838.708 249.577 50.2758 + vertex 838.096 251.363 50.6063 + endloop + endfacet + facet normal -0.680179 -0.46032 0.570492 + outer loop + vertex 838.708 249.577 50.2758 + vertex 839.356 248.189 49.9272 + vertex 839.124 248.76 50.1115 + endloop + endfacet + facet normal -0.48552 -0.514953 0.706466 + outer loop + vertex 839.356 248.189 49.9272 + vertex 840.449 246.372 49.3546 + vertex 840.218 246.859 49.5507 + endloop + endfacet + facet normal -0.812804 -0.17912 0.554316 + outer loop + vertex 834.07 265.398 51.5931 + vertex 834.709 263.449 51.9005 + vertex 834.304 265.728 52.0438 + endloop + endfacet + facet normal -0.947325 -0.232675 0.220086 + outer loop + vertex 834.709 263.449 51.9005 + vertex 835.486 259.963 51.558 + vertex 835.074 261.965 51.9017 + endloop + endfacet + facet normal -0.888258 -0.280542 0.363722 + outer loop + vertex 835.486 259.963 51.558 + vertex 837.012 254.123 50.7815 + vertex 836.673 255.808 51.252 + endloop + endfacet + facet normal 0.0732038 -0.521784 0.849931 + outer loop + vertex 843.651 239.187 44.7225 + vertex 841.928 237.446 43.8027 + vertex 842.061 237.17 43.6215 + endloop + endfacet + facet normal 0.0957018 -0.542458 0.834614 + outer loop + vertex 841.928 237.446 43.8027 + vertex 841.198 237.2 43.7262 + vertex 839.294 235.903 43.1017 + endloop + endfacet + facet normal 0.215851 -0.617604 0.756289 + outer loop + vertex 845.032 240.933 45.7542 + vertex 843.651 239.187 44.7225 + vertex 844.973 240.23 45.1976 + endloop + endfacet + facet normal -0.751969 -0.169624 0.637002 + outer loop + vertex 831.746 274.129 51.1747 + vertex 834.07 265.398 51.5931 + vertex 833.343 270.095 51.9852 + endloop + endfacet + facet normal -0.678692 -0.139159 0.721119 + outer loop + vertex 829.529 285.828 51.346 + vertex 831.746 274.129 51.1747 + vertex 831.556 279.661 52.0636 + endloop + endfacet + facet normal -0.643151 -0.145641 0.751762 + outer loop + vertex 827.282 296.269 51.4465 + vertex 829.529 285.828 51.346 + vertex 829.511 290.687 52.2721 + endloop + endfacet + facet normal -0.626359 -0.168978 0.761 + outer loop + vertex 824.713 305.873 51.464 + vertex 827.282 296.269 51.4465 + vertex 827.275 300.164 52.3057 + endloop + endfacet + facet normal -0.623556 -0.193986 0.757329 + outer loop + vertex 821.71 315.4 51.4319 + vertex 824.713 305.873 51.464 + vertex 824.598 309.419 52.2779 + endloop + endfacet + facet normal -0.619262 -0.215993 0.754892 + outer loop + vertex 818.548 323.884 51.2652 + vertex 821.71 315.4 51.4319 + vertex 820.969 319.942 52.1238 + endloop + endfacet + facet normal -0.635394 -0.24379 0.732694 + outer loop + vertex 815.634 331.844 51.3876 + vertex 818.548 323.884 51.2652 + vertex 818.975 325.637 52.2193 + endloop + endfacet + facet normal -0.633608 -0.259066 0.728989 + outer loop + vertex 812.237 339.803 51.2636 + vertex 815.634 331.844 51.3876 + vertex 814.828 335.916 52.1336 + endloop + endfacet + facet normal -0.649514 -0.281026 0.70651 + outer loop + vertex 809.036 347.547 51.4 + vertex 812.237 339.803 51.2636 + vertex 812.543 341.501 52.2202 + endloop + endfacet + facet normal -0.658985 -0.296157 0.691397 + outer loop + vertex 805.377 355.478 51.31 + vertex 809.036 347.547 51.4 + vertex 808.016 351.546 52.142 + endloop + endfacet + facet normal -0.678099 -0.311595 0.665651 + outer loop + vertex 802.026 363.203 51.5122 + vertex 805.377 355.478 51.31 + vertex 805.587 357.094 52.2804 + endloop + endfacet + facet normal -0.707533 -0.321753 0.629184 + outer loop + vertex 798.401 370.824 51.3339 + vertex 802.026 363.203 51.5122 + vertex 800.894 367.155 52.2616 + endloop + endfacet + facet normal -0.707154 -0.221593 0.671439 + outer loop + vertex 794.196 376.978 49.5989 + vertex 795.676 376.842 51.1135 + vertex 792.003 384.848 49.887 + endloop + endfacet + facet normal -0.72497 -0.305636 0.617256 + outer loop + vertex 795.676 376.842 51.1135 + vertex 798.401 370.824 51.3339 + vertex 798.292 372.764 52.1664 + endloop + endfacet + facet normal 0.0180253 -0.418296 0.908132 + outer loop + vertex 839.294 235.903 43.1017 + vertex 835.663 232.449 41.5829 + vertex 838.327 233.455 41.9931 + endloop + endfacet + facet normal -0.0261148 -0.340848 0.939756 + outer loop + vertex 835.663 232.449 41.5829 + vertex 832.986 229.993 40.6177 + vertex 834.007 229.463 40.4539 + endloop + endfacet + facet normal -0.0112525 -0.31507 0.949002 + outer loop + vertex 832.986 229.993 40.6177 + vertex 830.905 227.551 39.7821 + vertex 834.007 229.463 40.4539 + endloop + endfacet + facet normal 0.00486605 -0.288793 0.957379 + outer loop + vertex 830.905 227.551 39.7821 + vertex 828.052 224.7 38.9367 + vertex 830.434 225.655 39.2126 + endloop + endfacet + facet normal 0.0485317 -0.286095 0.956971 + outer loop + vertex 828.052 224.7 38.9367 + vertex 825.041 221.872 38.2438 + vertex 826.995 222.477 38.3258 + endloop + endfacet + facet normal 0.0480135 -0.251413 0.966688 + outer loop + vertex 825.041 221.872 38.2438 + vertex 822.42 219.637 37.7927 + vertex 823.192 218.892 37.5607 + endloop + endfacet + facet normal 0.0593987 -0.240296 0.968881 + outer loop + vertex 822.42 219.637 37.7927 + vertex 819.916 216.963 37.2832 + vertex 823.192 218.892 37.5607 + endloop + endfacet + facet normal 0.0774514 -0.23209 0.969606 + outer loop + vertex 819.916 216.963 37.2832 + vertex 816.535 213.676 36.7664 + vertex 818.683 214.4 36.7681 + endloop + endfacet + facet normal 0.0865375 -0.213573 0.973087 + outer loop + vertex 816.535 213.676 36.7664 + vertex 813.321 210.663 36.3911 + vertex 815.306 211.303 36.3549 + endloop + endfacet + facet normal 0.0619297 -0.176922 0.982275 + outer loop + vertex 813.321 210.663 36.3911 + vertex 808.166 208.565 36.338 + vertex 811.285 207.992 36.0382 + endloop + endfacet + facet normal 0.140758 -0.164968 0.976203 + outer loop + vertex 748.367 169.253 36.2974 + vertex 742.144 165.737 36.6006 + vertex 743.883 164.981 36.222 + endloop + endfacet + facet normal 0.316148 -0.280446 0.906311 + outer loop + vertex 713.632 152.998 40.2506 + vertex 710.048 151.037 40.8944 + vertex 711.974 150.795 40.1474 + endloop + endfacet + facet normal 0.379669 -0.367774 0.848878 + outer loop + vertex 705.585 147.92 41.4945 + vertex 703.146 146.972 42.1742 + vertex 704.065 146.919 41.7404 + endloop + endfacet + facet normal 0.470594 -0.495876 0.729827 + outer loop + vertex 697.405 144.737 44.079 + vertex 695.17 143.916 44.9621 + vertex 696.23 143.898 44.2665 + endloop + endfacet + facet normal 0.999784 -0.019702 -0.00656286 + outer loop + vertex 702.501 185.543 51.905 + vertex 702.723 196.704 52.1505 + vertex 702.63 191.946 52.208 + endloop + endfacet + facet normal 0.85093 -0.00453735 0.525259 + outer loop + vertex 702.723 196.704 52.1505 + vertex 702.764 209.679 52.1965 + vertex 702.597 205.379 52.4295 + endloop + endfacet + facet normal 0.853926 -0.370193 0.365742 + outer loop + vertex 696.553 149.857 47.3429 + vertex 698.092 154.473 48.4202 + vertex 697.154 151.78 47.8849 + endloop + endfacet + facet normal 0.335097 -0.351279 0.87425 + outer loop + vertex 695.916 148.33 46.9732 + vertex 696.553 149.857 47.3429 + vertex 697.154 151.78 47.8849 + endloop + endfacet + facet normal 0.390412 -0.403237 0.827634 + outer loop + vertex 694.716 145.593 46.2058 + vertex 695.916 148.33 46.9732 + vertex 695.4 147.438 46.7823 + endloop + endfacet + facet normal 0.447165 -0.436499 0.780712 + outer loop + vertex 694.014 144.04 45.7392 + vertex 694.716 145.593 46.2058 + vertex 693.15 143.184 45.7555 + endloop + endfacet + facet normal 0.823114 -0.076438 -0.562709 + outer loop + vertex 699.818 160.995 49.6336 + vertex 701.113 167.948 50.5844 + vertex 700.84 166.038 50.4445 + endloop + endfacet + facet normal 0.86374 -0.138364 -0.484571 + outer loop + vertex 698.092 154.473 48.4202 + vertex 699.818 160.995 49.6336 + vertex 698.903 157.214 49.0828 + endloop + endfacet + facet normal 0.703698 -0.0987969 0.703597 + outer loop + vertex 701.96 175.109 51.3268 + vertex 702.357 181.116 51.7733 + vertex 702.249 179.684 51.6803 + endloop + endfacet + facet normal 0.948044 -0.0802045 -0.307863 + outer loop + vertex 701.113 167.948 50.5844 + vertex 701.96 175.109 51.3268 + vertex 701.573 171.644 51.0371 + endloop + endfacet + facet normal -0.790895 -0.279477 0.544406 + outer loop + vertex 795.142 379.773 51.8409 + vertex 792.003 384.848 49.887 + vertex 795.676 376.842 51.1135 + endloop + endfacet + facet normal 0.229813 -0.591277 0.773032 + outer loop + vertex 847.08 242.431 46.4005 + vertex 845.459 242.464 46.9082 + vertex 845.752 241.75 46.2749 + endloop + endfacet + facet normal 0.0781972 -0.519867 0.85066 + outer loop + vertex 839.294 235.903 43.1017 + vertex 842.061 237.17 43.6215 + vertex 841.928 237.446 43.8027 + endloop + endfacet + facet normal -0.165294 -0.878173 0.448877 + outer loop + vertex -513.175 69.7578 38.7095 + vertex -505.101 68.193 38.621 + vertex -505.927 68.9316 39.762 + endloop + endfacet + facet normal -0.177245 -0.808707 0.560872 + outer loop + vertex -506.338 66.629 35.7359 + vertex -512.328 66.0567 33.0176 + vertex -506.353 64.3283 32.4139 + endloop + endfacet + facet normal -0.174776 -0.797376 0.57762 + outer loop + vertex -514.315 64.5705 30.3651 + vertex -509.662 63.6807 30.5447 + vertex -512.328 66.0567 33.0176 + endloop + endfacet + facet normal -0.179663 -0.786729 0.590575 + outer loop + vertex -506.107 62.3234 29.818 + vertex -506.353 64.3283 32.4139 + vertex -509.662 63.6807 30.5447 + endloop + endfacet + facet normal -0.171752 -0.796368 0.579913 + outer loop + vertex -506.353 64.3283 32.4139 + vertex -512.328 66.0567 33.0176 + vertex -509.662 63.6807 30.5447 + endloop + endfacet + facet normal -0.185551 -0.806687 0.561094 + outer loop + vertex -525.84 67.2605 30.4385 + vertex -519.482 66.0364 30.7811 + vertex -522.352 68.4303 33.2739 + endloop + endfacet + facet normal -0.178895 -0.795133 0.579448 + outer loop + vertex -514.315 64.5705 30.3651 + vertex -512.328 66.0567 33.0176 + vertex -519.482 66.0364 30.7811 + endloop + endfacet + facet normal -0.175658 -0.803238 0.569169 + outer loop + vertex -512.328 66.0567 33.0176 + vertex -522.352 68.4303 33.2739 + vertex -519.482 66.0364 30.7811 + endloop + endfacet + facet normal -0.201725 -0.814988 0.543232 + outer loop + vertex -538.388 70.3 30.3699 + vertex -531.598 68.9115 30.8084 + vertex -534.428 71.2621 33.2838 + endloop + endfacet + facet normal -0.193029 -0.800312 0.567663 + outer loop + vertex -525.84 67.2605 30.4385 + vertex -522.352 68.4303 33.2739 + vertex -531.598 68.9115 30.8084 + endloop + endfacet + facet normal -0.189748 -0.811116 0.55325 + outer loop + vertex -522.352 68.4303 33.2739 + vertex -534.428 71.2621 33.2838 + vertex -531.598 68.9115 30.8084 + endloop + endfacet + facet normal -0.219731 -0.819278 0.529624 + outer loop + vertex -550.83 73.4595 30.144 + vertex -544.158 72.0036 30.6599 + vertex -547.036 74.3373 33.0757 + endloop + endfacet + facet normal -0.210421 -0.806654 0.552297 + outer loop + vertex -538.388 70.3 30.3699 + vertex -534.428 71.2621 33.2838 + vertex -544.158 72.0036 30.6599 + endloop + endfacet + facet normal -0.207822 -0.815498 0.54016 + outer loop + vertex -534.428 71.2621 33.2838 + vertex -547.036 74.3373 33.0757 + vertex -544.158 72.0036 30.6599 + endloop + endfacet + facet normal -0.237294 -0.818539 0.52315 + outer loop + vertex -562.989 76.7192 29.7853 + vertex -556.496 75.2083 30.3662 + vertex -559.543 77.5763 32.6894 + endloop + endfacet + facet normal -0.229013 -0.81056 0.539023 + outer loop + vertex -550.83 73.4595 30.144 + vertex -547.036 74.3373 33.0757 + vertex -556.496 75.2083 30.3662 + endloop + endfacet + facet normal -0.227583 -0.815244 0.532526 + outer loop + vertex -547.036 74.3373 33.0757 + vertex -559.543 77.5763 32.6894 + vertex -556.496 75.2083 30.3662 + endloop + endfacet + facet normal -0.250897 -0.812277 0.526552 + outer loop + vertex -575.01 80.0736 29.2852 + vertex -568.609 78.5144 29.9297 + vertex -571.94 80.9948 32.1689 + endloop + endfacet + facet normal -0.245474 -0.811233 0.530701 + outer loop + vertex -562.989 76.7192 29.7853 + vertex -559.543 77.5763 32.6894 + vertex -568.609 78.5144 29.9297 + endloop + endfacet + facet normal -0.245769 -0.810299 0.531989 + outer loop + vertex -559.543 77.5763 32.6894 + vertex -571.94 80.9948 32.1689 + vertex -568.609 78.5144 29.9297 + endloop + endfacet + facet normal -0.261136 -0.802317 0.536745 + outer loop + vertex -587.102 83.5958 28.707 + vertex -580.715 81.9637 29.3745 + vertex -584.246 84.5824 31.571 + endloop + endfacet + facet normal -0.258612 -0.805822 0.532702 + outer loop + vertex -575.01 80.0736 29.2852 + vertex -571.94 80.9948 32.1689 + vertex -580.715 81.9637 29.3745 + endloop + endfacet + facet normal -0.259894 -0.801797 0.538123 + outer loop + vertex -571.94 80.9948 32.1689 + vertex -584.246 84.5824 31.571 + vertex -580.715 81.9637 29.3745 + endloop + endfacet + facet normal -0.265269 -0.791944 0.549961 + outer loop + vertex -598.143 86.8856 28.1139 + vertex -592.652 85.5253 28.8032 + vertex -596.013 88.2333 31.082 + endloop + endfacet + facet normal -0.267669 -0.797001 0.541427 + outer loop + vertex -587.102 83.5958 28.707 + vertex -584.246 84.5824 31.571 + vertex -592.652 85.5253 28.8032 + endloop + endfacet + facet normal -0.268849 -0.793285 0.546277 + outer loop + vertex -584.246 84.5824 31.571 + vertex -596.013 88.2333 31.082 + vertex -592.652 85.5253 28.8032 + endloop + endfacet + facet normal -0.336817 -0.761659 0.553561 + outer loop + vertex -606.264 89.1664 27.282 + vertex -605.752 89.1083 27.5136 + vertex -606.451 91.1626 29.9149 + endloop + endfacet + facet normal -0.283164 -0.758085 0.587474 + outer loop + vertex -604.603 88.5036 27.2873 + vertex -603.613 89.8083 29.4482 + vertex -605.752 89.1083 27.5136 + endloop + endfacet + facet normal -0.271711 -0.768925 0.578729 + outer loop + vertex -603.613 89.8083 29.4482 + vertex -606.451 91.1626 29.9149 + vertex -605.752 89.1083 27.5136 + endloop + endfacet + facet normal -0.16347 -0.638374 0.752167 + outer loop + vertex -506.402 60.8599 28.1269 + vertex -507.071 59.2851 26.6451 + vertex -504.881 60.1765 27.8776 + endloop + endfacet + facet normal -0.175439 -0.622989 0.762303 + outer loop + vertex -504.881 60.1765 27.8776 + vertex -507.071 59.2851 26.6451 + vertex -505.469 58.3407 26.2421 + endloop + endfacet + facet normal -0.142508 -0.735954 0.661864 + outer loop + vertex -506.107 62.3234 29.818 + vertex -506.402 60.8599 28.1269 + vertex -504.793 61.3097 28.9737 + endloop + endfacet + facet normal -0.186505 -0.675501 0.713382 + outer loop + vertex -504.793 61.3097 28.9737 + vertex -506.402 60.8599 28.1269 + vertex -504.881 60.1765 27.8776 + endloop + endfacet + facet normal -0.152226 -0.686531 0.710987 + outer loop + vertex -514.038 62.9992 28.5924 + vertex -514.58 61.3402 26.8743 + vertex -509.506 61.871 28.4732 + endloop + endfacet + facet normal -0.158642 -0.669485 0.725688 + outer loop + vertex -509.506 61.871 28.4732 + vertex -514.58 61.3402 26.8743 + vertex -510.155 60.2384 26.8252 + endloop + endfacet + facet normal -0.168195 -0.750562 0.639036 + outer loop + vertex -514.315 64.5705 30.3651 + vertex -514.038 62.9992 28.5924 + vertex -509.662 63.6807 30.5447 + endloop + endfacet + facet normal -0.169478 -0.748448 0.641173 + outer loop + vertex -509.662 63.6807 30.5447 + vertex -514.038 62.9992 28.5924 + vertex -509.506 61.871 28.4732 + endloop + endfacet + facet normal -0.154737 -0.74973 0.643398 + outer loop + vertex -509.662 63.6807 30.5447 + vertex -509.506 61.871 28.4732 + vertex -506.107 62.3234 29.818 + endloop + endfacet + facet normal -0.164446 -0.731434 0.661787 + outer loop + vertex -506.107 62.3234 29.818 + vertex -509.506 61.871 28.4732 + vertex -506.402 60.8599 28.1269 + endloop + endfacet + facet normal -0.139289 -0.675531 0.724056 + outer loop + vertex -509.506 61.871 28.4732 + vertex -510.155 60.2384 26.8252 + vertex -506.402 60.8599 28.1269 + endloop + endfacet + facet normal -0.154412 -0.64151 0.751413 + outer loop + vertex -506.402 60.8599 28.1269 + vertex -510.155 60.2384 26.8252 + vertex -507.071 59.2851 26.6451 + endloop + endfacet + facet normal -0.168598 -0.705185 0.688686 + outer loop + vertex -525.502 65.6942 28.5929 + vertex -525.879 64.0261 26.7927 + vertex -519.484 64.2714 28.6094 + endloop + endfacet + facet normal -0.172289 -0.693011 0.700037 + outer loop + vertex -519.484 64.2714 28.6094 + vertex -525.879 64.0261 26.7927 + vertex -519.989 62.6102 26.8405 + endloop + endfacet + facet normal -0.180721 -0.765959 0.616966 + outer loop + vertex -525.84 67.2605 30.4385 + vertex -525.502 65.6942 28.5929 + vertex -519.482 66.0364 30.7811 + endloop + endfacet + facet normal -0.182076 -0.762995 0.620231 + outer loop + vertex -519.482 66.0364 30.7811 + vertex -525.502 65.6942 28.5929 + vertex -519.484 64.2714 28.6094 + endloop + endfacet + facet normal -0.166951 -0.76508 0.621917 + outer loop + vertex -519.482 66.0364 30.7811 + vertex -519.484 64.2714 28.6094 + vertex -514.315 64.5705 30.3651 + endloop + endfacet + facet normal -0.173269 -0.750288 0.638001 + outer loop + vertex -514.315 64.5705 30.3651 + vertex -519.484 64.2714 28.6094 + vertex -514.038 62.9992 28.5924 + endloop + endfacet + facet normal -0.160447 -0.696221 0.699666 + outer loop + vertex -519.484 64.2714 28.6094 + vertex -519.989 62.6102 26.8405 + vertex -514.038 62.9992 28.5924 + endloop + endfacet + facet normal -0.164813 -0.683017 0.711565 + outer loop + vertex -514.038 62.9992 28.5924 + vertex -519.989 62.6102 26.8405 + vertex -514.58 61.3402 26.8743 + endloop + endfacet + facet normal -0.185307 -0.720088 0.668681 + outer loop + vertex -537.905 68.7493 28.5089 + vertex -537.995 67.0779 26.684 + vertex -531.687 67.1995 28.563 + endloop + endfacet + facet normal -0.188004 -0.711402 0.677171 + outer loop + vertex -531.687 67.1995 28.563 + vertex -537.995 67.0779 26.684 + vertex -531.937 65.5328 26.7427 + endloop + endfacet + facet normal -0.197561 -0.777715 0.596765 + outer loop + vertex -538.388 70.3 30.3699 + vertex -537.905 68.7493 28.5089 + vertex -531.598 68.9115 30.8084 + endloop + endfacet + facet normal -0.198526 -0.775548 0.59926 + outer loop + vertex -531.598 68.9115 30.8084 + vertex -537.905 68.7493 28.5089 + vertex -531.687 67.1995 28.563 + endloop + endfacet + facet normal -0.184516 -0.777994 0.600566 + outer loop + vertex -531.598 68.9115 30.8084 + vertex -531.687 67.1995 28.563 + vertex -525.84 67.2605 30.4385 + endloop + endfacet + facet normal -0.189274 -0.765479 0.614994 + outer loop + vertex -525.84 67.2605 30.4385 + vertex -531.687 67.1995 28.563 + vertex -525.502 65.6942 28.5929 + endloop + endfacet + facet normal -0.176971 -0.713683 0.677745 + outer loop + vertex -531.687 67.1995 28.563 + vertex -531.937 65.5328 26.7427 + vertex -525.502 65.6942 28.5929 + endloop + endfacet + facet normal -0.180363 -0.702393 0.688559 + outer loop + vertex -525.502 65.6942 28.5929 + vertex -531.937 65.5328 26.7427 + vertex -525.879 64.0261 26.7927 + endloop + endfacet + facet normal -0.201489 -0.72529 0.658298 + outer loop + vertex -550.145 71.9018 28.306 + vertex -549.968 70.2142 26.5009 + vertex -544.062 70.3163 28.4208 + endloop + endfacet + facet normal -0.202669 -0.721818 0.661743 + outer loop + vertex -544.062 70.3163 28.4208 + vertex -549.968 70.2142 26.5009 + vertex -544.007 68.6384 26.6077 + endloop + endfacet + facet normal -0.215976 -0.783088 0.583205 + outer loop + vertex -550.83 73.4595 30.144 + vertex -550.145 71.9018 28.306 + vertex -544.158 72.0036 30.6599 + endloop + endfacet + facet normal -0.215417 -0.784259 0.581836 + outer loop + vertex -544.158 72.0036 30.6599 + vertex -550.145 71.9018 28.306 + vertex -544.062 70.3163 28.4208 + endloop + endfacet + facet normal -0.202786 -0.78616 0.583807 + outer loop + vertex -544.158 72.0036 30.6599 + vertex -544.062 70.3163 28.4208 + vertex -538.388 70.3 30.3699 + endloop + endfacet + facet normal -0.206336 -0.777389 0.594215 + outer loop + vertex -538.388 70.3 30.3699 + vertex -544.062 70.3163 28.4208 + vertex -537.905 68.7493 28.5089 + endloop + endfacet + facet normal -0.193491 -0.723041 0.663154 + outer loop + vertex -544.062 70.3163 28.4208 + vertex -544.007 68.6384 26.6077 + vertex -537.905 68.7493 28.5089 + endloop + endfacet + facet normal -0.194982 -0.718465 0.667675 + outer loop + vertex -537.905 68.7493 28.5089 + vertex -544.007 68.6384 26.6077 + vertex -537.995 67.0779 26.684 + endloop + endfacet + facet normal -0.214444 -0.719011 0.661088 + outer loop + vertex -562.131 75.132 27.996 + vertex -561.788 73.4178 26.243 + vertex -556.169 73.5087 28.1642 + endloop + endfacet + facet normal -0.213003 -0.723113 0.657067 + outer loop + vertex -556.169 73.5087 28.1642 + vertex -561.788 73.4178 26.243 + vertex -555.892 71.8069 26.3813 + endloop + endfacet + facet normal -0.233497 -0.780291 0.580194 + outer loop + vertex -562.989 76.7192 29.7853 + vertex -562.131 75.132 27.996 + vertex -556.496 75.2083 30.3662 + endloop + endfacet + facet normal -0.230354 -0.786573 0.572923 + outer loop + vertex -556.496 75.2083 30.3662 + vertex -562.131 75.132 27.996 + vertex -556.169 73.5087 28.1642 + endloop + endfacet + facet normal -0.220536 -0.787691 0.575244 + outer loop + vertex -556.496 75.2083 30.3662 + vertex -556.169 73.5087 28.1642 + vertex -550.83 73.4595 30.144 + endloop + endfacet + facet normal -0.222535 -0.783075 0.580751 + outer loop + vertex -550.83 73.4595 30.144 + vertex -556.169 73.5087 28.1642 + vertex -550.145 71.9018 28.306 + endloop + endfacet + facet normal -0.208459 -0.723478 0.658122 + outer loop + vertex -556.169 73.5087 28.1642 + vertex -555.892 71.8069 26.3813 + vertex -550.145 71.9018 28.306 + endloop + endfacet + facet normal -0.208068 -0.724602 0.657009 + outer loop + vertex -550.145 71.9018 28.306 + vertex -555.892 71.8069 26.3813 + vertex -549.968 70.2142 26.5009 + endloop + endfacet + facet normal -0.222766 -0.704014 0.674344 + outer loop + vertex -573.955 78.4237 27.5802 + vertex -573.492 76.6773 25.9099 + vertex -568.058 76.7698 27.8015 + endloop + endfacet + facet normal -0.219511 -0.713431 0.665455 + outer loop + vertex -568.058 76.7698 27.8015 + vertex -573.492 76.6773 25.9099 + vertex -567.652 75.0421 26.0833 + endloop + endfacet + facet normal -0.246628 -0.76819 0.590812 + outer loop + vertex -575.01 80.0736 29.2852 + vertex -573.955 78.4237 27.5802 + vertex -568.609 78.5144 29.9297 + endloop + endfacet + facet normal -0.240511 -0.780263 0.577359 + outer loop + vertex -568.609 78.5144 29.9297 + vertex -573.955 78.4237 27.5802 + vertex -568.058 76.7698 27.8015 + endloop + endfacet + facet normal -0.234468 -0.780686 0.57927 + outer loop + vertex -568.609 78.5144 29.9297 + vertex -568.058 76.7698 27.8015 + vertex -562.989 76.7192 29.7853 + endloop + endfacet + facet normal -0.234628 -0.780329 0.579686 + outer loop + vertex -562.989 76.7192 29.7853 + vertex -568.058 76.7698 27.8015 + vertex -562.131 75.132 27.996 + endloop + endfacet + facet normal -0.218969 -0.713456 0.665608 + outer loop + vertex -568.058 76.7698 27.8015 + vertex -567.652 75.0421 26.0833 + vertex -562.131 75.132 27.996 + endloop + endfacet + facet normal -0.21708 -0.718844 0.660409 + outer loop + vertex -562.131 75.132 27.996 + vertex -567.652 75.0421 26.0833 + vertex -561.788 73.4178 26.243 + endloop + endfacet + facet normal -0.227976 -0.680549 0.696334 + outer loop + vertex -585.766 81.8237 27.0742 + vertex -585.072 79.9903 25.5096 + vertex -579.862 80.108 27.3305 + endloop + endfacet + facet normal -0.224122 -0.692171 0.686054 + outer loop + vertex -579.862 80.108 27.3305 + vertex -585.072 79.9903 25.5096 + vertex -579.304 78.3265 25.7155 + endloop + endfacet + facet normal -0.255706 -0.752227 0.607263 + outer loop + vertex -587.102 83.5958 28.707 + vertex -585.766 81.8237 27.0742 + vertex -580.715 81.9637 29.3745 + endloop + endfacet + facet normal -0.248443 -0.766544 0.592187 + outer loop + vertex -580.715 81.9637 29.3745 + vertex -585.766 81.8237 27.0742 + vertex -579.862 80.108 27.3305 + endloop + endfacet + facet normal -0.244645 -0.766541 0.593771 + outer loop + vertex -580.715 81.9637 29.3745 + vertex -579.862 80.108 27.3305 + vertex -575.01 80.0736 29.2852 + endloop + endfacet + facet normal -0.244021 -0.767955 0.592198 + outer loop + vertex -575.01 80.0736 29.2852 + vertex -579.862 80.108 27.3305 + vertex -573.955 78.4237 27.5802 + endloop + endfacet + facet normal -0.226351 -0.692189 0.685303 + outer loop + vertex -579.862 80.108 27.3305 + vertex -579.304 78.3265 25.7155 + vertex -573.955 78.4237 27.5802 + endloop + endfacet + facet normal -0.222358 -0.704024 0.674468 + outer loop + vertex -573.955 78.4237 27.5802 + vertex -579.304 78.3265 25.7155 + vertex -573.492 76.6773 25.9099 + endloop + endfacet + facet normal -0.226897 -0.654294 0.7214 + outer loop + vertex -596.772 85.0825 26.575 + vertex -595.818 83.1488 25.1213 + vertex -591.536 83.5357 26.819 + endloop + endfacet + facet normal -0.222532 -0.665077 0.712848 + outer loop + vertex -591.536 83.5357 26.819 + vertex -595.818 83.1488 25.1213 + vertex -590.68 81.6333 25.3113 + endloop + endfacet + facet normal -0.260571 -0.733647 0.627586 + outer loop + vertex -598.143 86.8856 28.1139 + vertex -596.772 85.0825 26.575 + vertex -592.652 85.5253 28.8032 + endloop + endfacet + facet normal -0.250191 -0.750457 0.611734 + outer loop + vertex -592.652 85.5253 28.8032 + vertex -596.772 85.0825 26.575 + vertex -591.536 83.5357 26.819 + endloop + endfacet + facet normal -0.250273 -0.750463 0.611693 + outer loop + vertex -592.652 85.5253 28.8032 + vertex -591.536 83.5357 26.819 + vertex -587.102 83.5958 28.707 + endloop + endfacet + facet normal -0.249926 -0.751223 0.610902 + outer loop + vertex -587.102 83.5958 28.707 + vertex -591.536 83.5357 26.819 + vertex -585.766 81.8237 27.0742 + endloop + endfacet + facet normal -0.228969 -0.665811 0.710119 + outer loop + vertex -591.536 83.5357 26.819 + vertex -590.68 81.6333 25.3113 + vertex -585.766 81.8237 27.0742 + endloop + endfacet + facet normal -0.224001 -0.680327 0.697838 + outer loop + vertex -585.766 81.8237 27.0742 + vertex -590.68 81.6333 25.3113 + vertex -585.072 79.9903 25.5096 + endloop + endfacet + facet normal -0.229384 -0.618557 0.751512 + outer loop + vertex -603.76 86.9825 26.0371 + vertex -602.945 85.1565 24.783 + vertex -600.983 86.2703 26.2986 + endloop + endfacet + facet normal -0.214115 -0.634003 0.743098 + outer loop + vertex -600.983 86.2703 26.2986 + vertex -602.945 85.1565 24.783 + vertex -600.035 84.3644 24.9456 + endloop + endfacet + facet normal -0.277942 -0.697134 0.660873 + outer loop + vertex -604.603 88.5036 27.2873 + vertex -603.76 86.9825 26.0371 + vertex -601.792 88.0623 28.004 + endloop + endfacet + facet normal -0.246359 -0.724174 0.644111 + outer loop + vertex -601.792 88.0623 28.004 + vertex -603.76 86.9825 26.0371 + vertex -600.983 86.2703 26.2986 + endloop + endfacet + facet normal -0.252896 -0.724431 0.641282 + outer loop + vertex -601.792 88.0623 28.004 + vertex -600.983 86.2703 26.2986 + vertex -598.143 86.8856 28.1139 + endloop + endfacet + facet normal -0.247931 -0.731003 0.63574 + outer loop + vertex -598.143 86.8856 28.1139 + vertex -600.983 86.2703 26.2986 + vertex -596.772 85.0825 26.575 + endloop + endfacet + facet normal -0.227898 -0.636448 0.736883 + outer loop + vertex -600.983 86.2703 26.2986 + vertex -600.035 84.3644 24.9456 + vertex -596.772 85.0825 26.575 + endloop + endfacet + facet normal -0.218427 -0.652972 0.725201 + outer loop + vertex -596.772 85.0825 26.575 + vertex -600.035 84.3644 24.9456 + vertex -595.818 83.1488 25.1213 + endloop + endfacet + facet normal -0.301431 -0.617578 0.726455 + outer loop + vertex -605.599 87.5816 25.8973 + vertex -604.92 85.8008 24.6649 + vertex -605.17 87.3462 25.8749 + endloop + endfacet + facet normal -0.323379 -0.615256 0.718948 + outer loop + vertex -605.17 87.3462 25.8749 + vertex -604.92 85.8008 24.6649 + vertex -604.446 85.5602 24.6724 + endloop + endfacet + facet normal -0.360313 -0.694985 0.62223 + outer loop + vertex -606.264 89.1664 27.282 + vertex -605.599 87.5816 25.8973 + vertex -605.752 89.1083 27.5136 + endloop + endfacet + facet normal -0.350499 -0.697247 0.625297 + outer loop + vertex -605.752 89.1083 27.5136 + vertex -605.599 87.5816 25.8973 + vertex -605.17 87.3462 25.8749 + endloop + endfacet + facet normal -0.237431 -0.702415 0.670999 + outer loop + vertex -605.752 89.1083 27.5136 + vertex -605.17 87.3462 25.8749 + vertex -604.603 88.5036 27.2873 + endloop + endfacet + facet normal -0.256462 -0.694538 0.672193 + outer loop + vertex -604.603 88.5036 27.2873 + vertex -605.17 87.3462 25.8749 + vertex -603.76 86.9825 26.0371 + endloop + endfacet + facet normal -0.243701 -0.607749 0.755812 + outer loop + vertex -605.17 87.3462 25.8749 + vertex -604.446 85.5602 24.6724 + vertex -603.76 86.9825 26.0371 + endloop + endfacet + facet normal -0.221694 -0.617373 0.754786 + outer loop + vertex -603.76 86.9825 26.0371 + vertex -604.446 85.5602 24.6724 + vertex -602.945 85.1565 24.783 + endloop + endfacet + facet normal -0.687195 -0.624448 0.371252 + outer loop + vertex -606.258 88.9872 26.9925 + vertex -605.806 88.0584 26.2672 + vertex -606.264 89.1664 27.282 + endloop + endfacet + facet normal -0.871444 -0.474489 0.12428 + outer loop + vertex -606.264 89.1664 27.282 + vertex -605.806 88.0584 26.2672 + vertex -605.599 87.5816 25.8973 + endloop + endfacet + facet normal 0.94414 0.293801 0.149265 + outer loop + vertex -605.806 88.0584 26.2672 + vertex -604.975 86.0924 24.8794 + vertex -605.599 87.5816 25.8973 + endloop + endfacet + facet normal 0.173765 0.604296 -0.777581 + outer loop + vertex -605.599 87.5816 25.8973 + vertex -604.975 86.0924 24.8794 + vertex -604.92 85.8008 24.6649 + endloop + endfacet + facet normal -0.0939961 -0.468644 0.878372 + outer loop + vertex -507.631 57.5266 25.3303 + vertex -507.801 55.6061 24.2875 + vertex -506.004 56.6816 25.0537 + endloop + endfacet + facet normal -0.114155 -0.442773 0.889337 + outer loop + vertex -506.004 56.6816 25.0537 + vertex -507.801 55.6061 24.2875 + vertex -506.007 54.9552 24.1937 + endloop + endfacet + facet normal -0.129543 -0.566965 0.813492 + outer loop + vertex -507.071 59.2851 26.6451 + vertex -507.631 57.5266 25.3303 + vertex -505.469 58.3407 26.2421 + endloop + endfacet + facet normal -0.142836 -0.545499 0.82585 + outer loop + vertex -505.469 58.3407 26.2421 + vertex -507.631 57.5266 25.3303 + vertex -506.004 56.6816 25.0537 + endloop + endfacet + facet normal -0.119203 -0.482939 0.867502 + outer loop + vertex -515.362 59.632 25.4742 + vertex -515.741 57.7143 24.3545 + vertex -510.862 58.5191 25.4729 + endloop + endfacet + facet normal -0.120689 -0.477684 0.870203 + outer loop + vertex -510.862 58.5191 25.4729 + vertex -515.741 57.7143 24.3545 + vertex -511.132 56.5763 24.3691 + endloop + endfacet + facet normal -0.137909 -0.589362 0.796011 + outer loop + vertex -514.58 61.3402 26.8743 + vertex -515.362 59.632 25.4742 + vertex -510.155 60.2384 26.8252 + endloop + endfacet + facet normal -0.142042 -0.575203 0.805584 + outer loop + vertex -510.155 60.2384 26.8252 + vertex -515.362 59.632 25.4742 + vertex -510.862 58.5191 25.4729 + endloop + endfacet + facet normal -0.131897 -0.578739 0.804776 + outer loop + vertex -510.155 60.2384 26.8252 + vertex -510.862 58.5191 25.4729 + vertex -507.071 59.2851 26.6451 + endloop + endfacet + facet normal -0.137532 -0.564645 0.813794 + outer loop + vertex -507.071 59.2851 26.6451 + vertex -510.862 58.5191 25.4729 + vertex -507.631 57.5266 25.3303 + endloop + endfacet + facet normal -0.108901 -0.479602 0.870703 + outer loop + vertex -510.862 58.5191 25.4729 + vertex -511.132 56.5763 24.3691 + vertex -507.631 57.5266 25.3303 + endloop + endfacet + facet normal -0.114325 -0.466233 0.877244 + outer loop + vertex -507.631 57.5266 25.3303 + vertex -511.132 56.5763 24.3691 + vertex -507.801 55.6061 24.2875 + endloop + endfacet + facet normal -0.131362 -0.490435 0.861521 + outer loop + vertex -526.495 62.3224 25.3321 + vertex -526.922 60.4428 24.197 + vertex -520.707 60.9044 25.4074 + endloop + endfacet + facet normal -0.132301 -0.485189 0.864343 + outer loop + vertex -520.707 60.9044 25.4074 + vertex -526.922 60.4428 24.197 + vertex -521.144 59.0088 24.2765 + endloop + endfacet + facet normal -0.153121 -0.610684 0.776929 + outer loop + vertex -525.879 64.0261 26.7927 + vertex -526.495 62.3224 25.3321 + vertex -519.989 62.6102 26.8405 + endloop + endfacet + facet normal -0.156258 -0.595977 0.787651 + outer loop + vertex -519.989 62.6102 26.8405 + vertex -526.495 62.3224 25.3321 + vertex -520.707 60.9044 25.4074 + endloop + endfacet + facet normal -0.145727 -0.599718 0.78683 + outer loop + vertex -519.989 62.6102 26.8405 + vertex -520.707 60.9044 25.4074 + vertex -514.58 61.3402 26.8743 + endloop + endfacet + facet normal -0.149231 -0.585089 0.79712 + outer loop + vertex -514.58 61.3402 26.8743 + vertex -520.707 60.9044 25.4074 + vertex -515.362 59.632 25.4742 + endloop + endfacet + facet normal -0.126617 -0.486551 0.864429 + outer loop + vertex -520.707 60.9044 25.4074 + vertex -521.144 59.0088 24.2765 + vertex -515.362 59.632 25.4742 + endloop + endfacet + facet normal -0.127796 -0.481118 0.867291 + outer loop + vertex -515.362 59.632 25.4742 + vertex -521.144 59.0088 24.2765 + vertex -515.741 57.7143 24.3545 + endloop + endfacet + facet normal -0.137661 -0.497325 0.856573 + outer loop + vertex -538.318 65.3676 25.2221 + vertex -538.594 63.5002 24.0936 + vertex -532.41 63.8274 25.2773 + endloop + endfacet + facet normal -0.138224 -0.49378 0.858531 + outer loop + vertex -532.41 63.8274 25.2773 + vertex -538.594 63.5002 24.0936 + vertex -532.774 61.9567 24.1429 + endloop + endfacet + facet normal -0.166151 -0.622385 0.764873 + outer loop + vertex -537.995 67.0779 26.684 + vertex -538.318 65.3676 25.2221 + vertex -531.937 65.5328 26.7427 + endloop + endfacet + facet normal -0.167615 -0.615322 0.770249 + outer loop + vertex -531.937 65.5328 26.7427 + vertex -538.318 65.3676 25.2221 + vertex -532.41 63.8274 25.2773 + endloop + endfacet + facet normal -0.159905 -0.617425 0.770206 + outer loop + vertex -531.937 65.5328 26.7427 + vertex -532.41 63.8274 25.2773 + vertex -525.879 64.0261 26.7927 + endloop + endfacet + facet normal -0.161853 -0.607888 0.777351 + outer loop + vertex -525.879 64.0261 26.7927 + vertex -532.41 63.8274 25.2773 + vertex -526.495 62.3224 25.3321 + endloop + endfacet + facet normal -0.133816 -0.494728 0.858684 + outer loop + vertex -532.41 63.8274 25.2773 + vertex -532.774 61.9567 24.1429 + vertex -526.495 62.3224 25.3321 + endloop + endfacet + facet normal -0.134637 -0.489653 0.86146 + outer loop + vertex -526.495 62.3224 25.3321 + vertex -532.774 61.9567 24.1429 + vertex -526.922 60.4428 24.197 + endloop + endfacet + facet normal -0.146089 -0.495304 0.856348 + outer loop + vertex -550.054 68.4885 25.0579 + vertex -550.18 66.6155 23.9531 + vertex -544.196 66.9211 25.1507 + endloop + endfacet + facet normal -0.145688 -0.497782 0.854978 + outer loop + vertex -544.196 66.9211 25.1507 + vertex -550.18 66.6155 23.9531 + vertex -544.389 65.054 24.0308 + endloop + endfacet + facet normal -0.179033 -0.625806 0.759154 + outer loop + vertex -549.968 70.2142 26.5009 + vertex -550.054 68.4885 25.0579 + vertex -544.007 68.6384 26.6077 + endloop + endfacet + facet normal -0.179235 -0.6249 0.759852 + outer loop + vertex -544.007 68.6384 26.6077 + vertex -550.054 68.4885 25.0579 + vertex -544.196 66.9211 25.1507 + endloop + endfacet + facet normal -0.1722 -0.626169 0.760434 + outer loop + vertex -544.007 68.6384 26.6077 + vertex -544.196 66.9211 25.1507 + vertex -537.995 67.0779 26.684 + endloop + endfacet + facet normal -0.173362 -0.620774 0.764582 + outer loop + vertex -537.995 67.0779 26.684 + vertex -544.196 66.9211 25.1507 + vertex -538.318 65.3676 25.2221 + endloop + endfacet + facet normal -0.142099 -0.498325 0.855266 + outer loop + vertex -544.196 66.9211 25.1507 + vertex -544.389 65.054 24.0308 + vertex -538.318 65.3676 25.2221 + endloop + endfacet + facet normal -0.142399 -0.496461 0.8563 + outer loop + vertex -538.318 65.3676 25.2221 + vertex -544.389 65.054 24.0308 + vertex -538.594 63.5002 24.0936 + endloop + endfacet + facet normal -0.148821 -0.482865 0.862956 + outer loop + vertex -561.75 71.6708 24.8421 + vertex -561.808 69.7825 23.7753 + vertex -555.903 70.0707 24.9551 + endloop + endfacet + facet normal -0.14772 -0.489907 0.859168 + outer loop + vertex -555.903 70.0707 24.9551 + vertex -561.808 69.7825 23.7753 + vertex -555.984 68.1896 23.8685 + endloop + endfacet + facet normal -0.186548 -0.617067 0.764479 + outer loop + vertex -561.788 73.4178 26.243 + vertex -561.75 71.6708 24.8421 + vertex -555.892 71.8069 26.3813 + endloop + endfacet + facet normal -0.185205 -0.623096 0.759902 + outer loop + vertex -555.892 71.8069 26.3813 + vertex -561.75 71.6708 24.8421 + vertex -555.903 70.0707 24.9551 + endloop + endfacet + facet normal -0.182936 -0.623374 0.760223 + outer loop + vertex -555.892 71.8069 26.3813 + vertex -555.903 70.0707 24.9551 + vertex -549.968 70.2142 26.5009 + endloop + endfacet + facet normal -0.182506 -0.625293 0.758749 + outer loop + vertex -549.968 70.2142 26.5009 + vertex -555.903 70.0707 24.9551 + vertex -550.054 68.4885 25.0579 + endloop + endfacet + facet normal -0.147644 -0.489915 0.859176 + outer loop + vertex -555.903 70.0707 24.9551 + vertex -555.984 68.1896 23.8685 + vertex -550.054 68.4885 25.0579 + endloop + endfacet + facet normal -0.146796 -0.495215 0.856278 + outer loop + vertex -550.054 68.4885 25.0579 + vertex -555.984 68.1896 23.8685 + vertex -550.18 66.6155 23.9531 + endloop + endfacet + facet normal -0.148175 -0.460688 0.875106 + outer loop + vertex -573.423 74.9155 24.5801 + vertex -573.505 73.022 23.5692 + vertex -567.589 73.2874 24.7107 + endloop + endfacet + facet normal -0.14654 -0.472092 0.869285 + outer loop + vertex -567.589 73.2874 24.7107 + vertex -573.505 73.022 23.5692 + vertex -567.653 71.3953 23.6724 + endloop + endfacet + facet normal -0.1901 -0.596247 0.779969 + outer loop + vertex -573.492 76.6773 25.9099 + vertex -573.423 74.9155 24.5801 + vertex -567.652 75.0421 26.0833 + endloop + endfacet + facet normal -0.187329 -0.609376 0.770434 + outer loop + vertex -567.652 75.0421 26.0833 + vertex -573.423 74.9155 24.5801 + vertex -567.589 73.2874 24.7107 + endloop + endfacet + facet normal -0.189684 -0.60915 0.770037 + outer loop + vertex -567.652 75.0421 26.0833 + vertex -567.589 73.2874 24.7107 + vertex -561.788 73.4178 26.243 + endloop + endfacet + facet normal -0.187981 -0.616915 0.764251 + outer loop + vertex -561.788 73.4178 26.243 + vertex -567.589 73.2874 24.7107 + vertex -561.75 71.6708 24.8421 + endloop + endfacet + facet normal -0.150145 -0.471738 0.868861 + outer loop + vertex -567.589 73.2874 24.7107 + vertex -567.653 71.3953 23.6724 + vertex -561.75 71.6708 24.8421 + endloop + endfacet + facet normal -0.148462 -0.4829 0.862998 + outer loop + vertex -561.75 71.6708 24.8421 + vertex -567.653 71.3953 23.6724 + vertex -561.808 69.7825 23.7753 + endloop + endfacet + facet normal -0.147534 -0.433182 0.889149 + outer loop + vertex -584.957 78.2069 24.286 + vertex -585.097 76.3298 23.3482 + vertex -579.224 76.5586 24.4341 + endloop + endfacet + facet normal -0.145804 -0.446814 0.882666 + outer loop + vertex -579.224 76.5586 24.4341 + vertex -585.097 76.3298 23.3482 + vertex -579.341 74.6715 23.4595 + endloop + endfacet + facet normal -0.191258 -0.563698 0.803533 + outer loop + vertex -585.072 79.9903 25.5096 + vertex -584.957 78.2069 24.286 + vertex -579.304 78.3265 25.7155 + endloop + endfacet + facet normal -0.187772 -0.581923 0.79127 + outer loop + vertex -579.304 78.3265 25.7155 + vertex -584.957 78.2069 24.286 + vertex -579.224 76.5586 24.4341 + endloop + endfacet + facet normal -0.191504 -0.581608 0.790606 + outer loop + vertex -579.304 78.3265 25.7155 + vertex -579.224 76.5586 24.4341 + vertex -573.492 76.6773 25.9099 + endloop + endfacet + facet normal -0.188529 -0.59639 0.78024 + outer loop + vertex -573.492 76.6773 25.9099 + vertex -579.224 76.5586 24.4341 + vertex -573.423 74.9155 24.5801 + endloop + endfacet + facet normal -0.148643 -0.446481 0.882361 + outer loop + vertex -579.224 76.5586 24.4341 + vertex -579.341 74.6715 23.4595 + vertex -573.423 74.9155 24.5801 + endloop + endfacet + facet normal -0.146709 -0.460841 0.875273 + outer loop + vertex -573.423 74.9155 24.5801 + vertex -579.341 74.6715 23.4595 + vertex -573.505 73.022 23.5692 + endloop + endfacet + facet normal -0.141761 -0.395582 0.907424 + outer loop + vertex -595.527 81.3079 23.9947 + vertex -595.646 79.4141 23.1505 + vertex -590.487 79.8232 24.1349 + endloop + endfacet + facet normal -0.138769 -0.414276 0.89951 + outer loop + vertex -590.487 79.8232 24.1349 + vertex -595.646 79.4141 23.1505 + vertex -590.628 77.9425 23.2468 + endloop + endfacet + facet normal -0.188033 -0.534145 0.824216 + outer loop + vertex -595.818 83.1488 25.1213 + vertex -595.527 81.3079 23.9947 + vertex -590.68 81.6333 25.3113 + endloop + endfacet + facet normal -0.184492 -0.549387 0.814946 + outer loop + vertex -590.68 81.6333 25.3113 + vertex -595.527 81.3079 23.9947 + vertex -590.487 79.8232 24.1349 + endloop + endfacet + facet normal -0.189694 -0.549233 0.813855 + outer loop + vertex -590.68 81.6333 25.3113 + vertex -590.487 79.8232 24.1349 + vertex -585.072 79.9903 25.5096 + endloop + endfacet + facet normal -0.186831 -0.563987 0.804371 + outer loop + vertex -585.072 79.9903 25.5096 + vertex -590.487 79.8232 24.1349 + vertex -584.957 78.2069 24.286 + endloop + endfacet + facet normal -0.145411 -0.413458 0.898837 + outer loop + vertex -590.487 79.8232 24.1349 + vertex -590.628 77.9425 23.2468 + vertex -584.957 78.2069 24.286 + endloop + endfacet + facet normal -0.142778 -0.433779 0.889635 + outer loop + vertex -584.957 78.2069 24.286 + vertex -590.628 77.9425 23.2468 + vertex -585.097 76.3298 23.3482 + endloop + endfacet + facet normal -0.137297 -0.375301 0.916678 + outer loop + vertex -602.513 83.3105 23.7799 + vertex -602.562 81.433 23.004 + vertex -599.652 82.507 23.8794 + endloop + endfacet + facet normal -0.132335 -0.385784 0.913049 + outer loop + vertex -599.652 82.507 23.8794 + vertex -602.562 81.433 23.004 + vertex -599.75 80.6177 23.0669 + endloop + endfacet + facet normal -0.183928 -0.502185 0.844974 + outer loop + vertex -602.945 85.1565 24.783 + vertex -602.513 83.3105 23.7799 + vertex -600.035 84.3644 24.9456 + endloop + endfacet + facet normal -0.174363 -0.517004 0.838036 + outer loop + vertex -600.035 84.3644 24.9456 + vertex -602.513 83.3105 23.7799 + vertex -599.652 82.507 23.8794 + endloop + endfacet + facet normal -0.184003 -0.517596 0.835606 + outer loop + vertex -600.035 84.3644 24.9456 + vertex -599.652 82.507 23.8794 + vertex -595.818 83.1488 25.1213 + endloop + endfacet + facet normal -0.178302 -0.533989 0.826477 + outer loop + vertex -595.818 83.1488 25.1213 + vertex -599.652 82.507 23.8794 + vertex -595.527 81.3079 23.9947 + endloop + endfacet + facet normal -0.137484 -0.385281 0.9125 + outer loop + vertex -599.652 82.507 23.8794 + vertex -599.75 80.6177 23.0669 + vertex -595.527 81.3079 23.9947 + endloop + endfacet + facet normal -0.134721 -0.396352 0.90816 + outer loop + vertex -595.527 81.3079 23.9947 + vertex -599.75 80.6177 23.0669 + vertex -595.646 79.4141 23.1505 + endloop + endfacet + facet normal -0.20225 -0.364238 0.90908 + outer loop + vertex -604.452 84.0313 23.7376 + vertex -604.341 82.1276 22.9996 + vertex -604.005 83.7404 23.7206 + endloop + endfacet + facet normal -0.201512 -0.364431 0.909166 + outer loop + vertex -604.005 83.7404 23.7206 + vertex -604.341 82.1276 22.9996 + vertex -603.994 81.8633 22.9706 + endloop + endfacet + facet normal -0.26747 -0.501835 0.82257 + outer loop + vertex -604.92 85.8008 24.6649 + vertex -604.452 84.0313 23.7376 + vertex -604.446 85.5602 24.6724 + endloop + endfacet + facet normal -0.292706 -0.497918 0.816334 + outer loop + vertex -604.446 85.5602 24.6724 + vertex -604.452 84.0313 23.7376 + vertex -604.005 83.7404 23.7206 + endloop + endfacet + facet normal -0.194708 -0.49124 0.848983 + outer loop + vertex -604.446 85.5602 24.6724 + vertex -604.005 83.7404 23.7206 + vertex -602.945 85.1565 24.783 + endloop + endfacet + facet normal -0.178254 -0.501681 0.846488 + outer loop + vertex -602.945 85.1565 24.783 + vertex -604.005 83.7404 23.7206 + vertex -602.513 83.3105 23.7799 + endloop + endfacet + facet normal -0.142585 -0.367954 0.918847 + outer loop + vertex -604.005 83.7404 23.7206 + vertex -603.994 81.8633 22.9706 + vertex -602.513 83.3105 23.7799 + endloop + endfacet + facet normal -0.134191 -0.375531 0.917044 + outer loop + vertex -602.513 83.3105 23.7799 + vertex -603.994 81.8633 22.9706 + vertex -602.562 81.433 23.004 + endloop + endfacet + facet normal 0.66592 0.518662 -0.536228 + outer loop + vertex -604.975 86.0924 24.8794 + vertex -604.471 84.4572 23.9237 + vertex -604.92 85.8008 24.6649 + endloop + endfacet + facet normal -0.341464 0.363851 -0.866611 + outer loop + vertex -604.92 85.8008 24.6649 + vertex -604.471 84.4572 23.9237 + vertex -604.452 84.0313 23.7376 + endloop + endfacet + facet normal 0.274483 0.394941 -0.876745 + outer loop + vertex -604.471 84.4572 23.9237 + vertex -604.208 82.6724 23.2018 + vertex -604.452 84.0313 23.7376 + endloop + endfacet + facet normal -0.0511562 0.35838 -0.932173 + outer loop + vertex -604.452 84.0313 23.7376 + vertex -604.208 82.6724 23.2018 + vertex -604.341 82.1276 22.9996 + endloop + endfacet + facet normal -0.063995 -0.287778 0.955557 + outer loop + vertex -507.814 53.4705 23.436 + vertex -508.251 51.4378 22.7946 + vertex -506.483 52.7364 23.304 + endloop + endfacet + facet normal -0.0978257 -0.245247 0.964512 + outer loop + vertex -506.483 52.7364 23.304 + vertex -508.251 51.4378 22.7946 + vertex -507.809 50.501 22.6012 + endloop + endfacet + facet normal -0.0853294 -0.368581 0.925671 + outer loop + vertex -507.801 55.6061 24.2875 + vertex -507.814 53.4705 23.436 + vertex -506.007 54.9552 24.1937 + endloop + endfacet + facet normal -0.101554 -0.351404 0.9307 + outer loop + vertex -506.007 54.9552 24.1937 + vertex -507.814 53.4705 23.436 + vertex -506.483 52.7364 23.304 + endloop + endfacet + facet normal -0.0787703 -0.297146 0.951577 + outer loop + vertex -515.544 55.5388 23.4666 + vertex -515.012 53.3826 22.8374 + vertex -510.986 54.4041 23.4896 + endloop + endfacet + facet normal -0.0826097 -0.284307 0.955168 + outer loop + vertex -510.986 54.4041 23.4896 + vertex -515.012 53.3826 22.8374 + vertex -511.383 52.0048 22.7411 + endloop + endfacet + facet normal -0.097614 -0.383615 0.91832 + outer loop + vertex -515.741 57.7143 24.3545 + vertex -515.544 55.5388 23.4666 + vertex -511.132 56.5763 24.3691 + endloop + endfacet + facet normal -0.0990203 -0.379124 0.920033 + outer loop + vertex -511.132 56.5763 24.3691 + vertex -515.544 55.5388 23.4666 + vertex -510.986 54.4041 23.4896 + endloop + endfacet + facet normal -0.0878014 -0.378875 0.921273 + outer loop + vertex -511.132 56.5763 24.3691 + vertex -510.986 54.4041 23.4896 + vertex -507.801 55.6061 24.2875 + endloop + endfacet + facet normal -0.0927449 -0.368296 0.925071 + outer loop + vertex -507.801 55.6061 24.2875 + vertex -510.986 54.4041 23.4896 + vertex -507.814 53.4705 23.436 + endloop + endfacet + facet normal -0.0682469 -0.286802 0.955556 + outer loop + vertex -510.986 54.4041 23.4896 + vertex -511.383 52.0048 22.7411 + vertex -507.814 53.4705 23.436 + endloop + endfacet + facet normal -0.0682172 -0.286866 0.955539 + outer loop + vertex -507.814 53.4705 23.436 + vertex -511.383 52.0048 22.7411 + vertex -508.251 51.4378 22.7946 + endloop + endfacet + facet normal -0.0837556 -0.289313 0.953563 + outer loop + vertex -526.842 58.2884 23.3226 + vertex -526.094 56.0794 22.718 + vertex -521.004 56.8434 23.3969 + endloop + endfacet + facet normal -0.0846382 -0.284619 0.954897 + outer loop + vertex -521.004 56.8434 23.3969 + vertex -526.094 56.0794 22.718 + vertex -520.752 54.3589 22.6787 + endloop + endfacet + facet normal -0.106307 -0.377361 0.919944 + outer loop + vertex -526.922 60.4428 24.197 + vertex -526.842 58.2884 23.3226 + vertex -521.144 59.0088 24.2765 + endloop + endfacet + facet normal -0.105784 -0.380087 0.918882 + outer loop + vertex -521.144 59.0088 24.2765 + vertex -526.842 58.2884 23.3226 + vertex -521.004 56.8434 23.3969 + endloop + endfacet + facet normal -0.104333 -0.380065 0.919057 + outer loop + vertex -521.144 59.0088 24.2765 + vertex -521.004 56.8434 23.3969 + vertex -515.741 57.7143 24.3545 + endloop + endfacet + facet normal -0.103441 -0.383842 0.917587 + outer loop + vertex -515.741 57.7143 24.3545 + vertex -521.004 56.8434 23.3969 + vertex -515.544 55.5388 23.4666 + endloop + endfacet + facet normal -0.0801389 -0.284301 0.95538 + outer loop + vertex -521.004 56.8434 23.3969 + vertex -520.752 54.3589 22.6787 + vertex -515.544 55.5388 23.4666 + endloop + endfacet + facet normal -0.0767889 -0.296741 0.951866 + outer loop + vertex -515.544 55.5388 23.4666 + vertex -520.752 54.3589 22.6787 + vertex -515.012 53.3826 22.8374 + endloop + endfacet + facet normal -0.0825253 -0.282081 0.955835 + outer loop + vertex -538.58 61.3806 23.2253 + vertex -537.962 59.1698 22.6263 + vertex -532.744 59.8214 23.269 + endloop + endfacet + facet normal -0.0835857 -0.275415 0.957685 + outer loop + vertex -532.744 59.8214 23.269 + vertex -537.962 59.1698 22.6263 + vertex -532.461 57.3006 22.5688 + endloop + endfacet + facet normal -0.107898 -0.377469 0.919715 + outer loop + vertex -538.594 63.5002 24.0936 + vertex -538.58 61.3806 23.2253 + vertex -532.774 61.9567 24.1429 + endloop + endfacet + facet normal -0.107838 -0.377842 0.919568 + outer loop + vertex -532.774 61.9567 24.1429 + vertex -538.58 61.3806 23.2253 + vertex -532.744 59.8214 23.269 + endloop + endfacet + facet normal -0.106259 -0.377888 0.919733 + outer loop + vertex -532.774 61.9567 24.1429 + vertex -532.744 59.8214 23.269 + vertex -526.922 60.4428 24.197 + endloop + endfacet + facet normal -0.106348 -0.377361 0.91994 + outer loop + vertex -526.922 60.4428 24.197 + vertex -532.744 59.8214 23.269 + vertex -526.842 58.2884 23.3226 + endloop + endfacet + facet normal -0.0801438 -0.275132 0.95806 + outer loop + vertex -532.744 59.8214 23.269 + vertex -532.461 57.3006 22.5688 + vertex -526.842 58.2884 23.3226 + endloop + endfacet + facet normal -0.077512 -0.287494 0.954641 + outer loop + vertex -526.842 58.2884 23.3226 + vertex -532.461 57.3006 22.5688 + vertex -526.094 56.0794 22.718 + endloop + endfacet + facet normal -0.0842547 -0.275208 0.957686 + outer loop + vertex -550.118 64.4947 23.1178 + vertex -549.594 62.3064 22.5351 + vertex -544.35 62.9365 23.1775 + endloop + endfacet + facet normal -0.0853413 -0.268115 0.959599 + outer loop + vertex -544.35 62.9365 23.1775 + vertex -549.594 62.3064 22.5351 + vertex -544.225 60.4336 22.4893 + endloop + endfacet + facet normal -0.111342 -0.366989 0.923538 + outer loop + vertex -550.18 66.6155 23.9531 + vertex -550.118 64.4947 23.1178 + vertex -544.389 65.054 24.0308 + endloop + endfacet + facet normal -0.110355 -0.373221 0.921156 + outer loop + vertex -544.389 65.054 24.0308 + vertex -550.118 64.4947 23.1178 + vertex -544.35 62.9365 23.1775 + endloop + endfacet + facet normal -0.110057 -0.373228 0.921188 + outer loop + vertex -544.389 65.054 24.0308 + vertex -544.35 62.9365 23.1775 + vertex -538.594 63.5002 24.0936 + endloop + endfacet + facet normal -0.109388 -0.377415 0.919561 + outer loop + vertex -538.594 63.5002 24.0936 + vertex -544.35 62.9365 23.1775 + vertex -538.58 61.3806 23.2253 + endloop + endfacet + facet normal -0.080216 -0.267991 0.960076 + outer loop + vertex -544.35 62.9365 23.1775 + vertex -544.225 60.4336 22.4893 + vertex -538.58 61.3806 23.2253 + endloop + endfacet + facet normal -0.0775953 -0.280907 0.956593 + outer loop + vertex -538.58 61.3806 23.2253 + vertex -544.225 60.4336 22.4893 + vertex -537.962 59.1698 22.6263 + endloop + endfacet + facet normal -0.0834198 -0.261315 0.961642 + outer loop + vertex -561.737 67.6572 22.9714 + vertex -561.241 65.4677 22.4195 + vertex -555.91 66.0678 23.045 + endloop + endfacet + facet normal -0.0840686 -0.256768 0.96281 + outer loop + vertex -555.91 66.0678 23.045 + vertex -561.241 65.4677 22.4195 + vertex -555.861 63.5793 22.3856 + endloop + endfacet + facet normal -0.111893 -0.35486 0.9282 + outer loop + vertex -561.808 69.7825 23.7753 + vertex -561.737 67.6572 22.9714 + vertex -555.984 68.1896 23.8685 + endloop + endfacet + facet normal -0.11068 -0.362938 0.925217 + outer loop + vertex -555.984 68.1896 23.8685 + vertex -561.737 67.6572 22.9714 + vertex -555.91 66.0678 23.045 + endloop + endfacet + facet normal -0.111919 -0.362925 0.925073 + outer loop + vertex -555.984 68.1896 23.8685 + vertex -555.91 66.0678 23.045 + vertex -550.18 66.6155 23.9531 + endloop + endfacet + facet normal -0.111288 -0.36699 0.923544 + outer loop + vertex -550.18 66.6155 23.9531 + vertex -555.91 66.0678 23.045 + vertex -550.118 64.4947 23.1178 + endloop + endfacet + facet normal -0.0818509 -0.256775 0.962999 + outer loop + vertex -555.91 66.0678 23.045 + vertex -555.861 63.5793 22.3856 + vertex -550.118 64.4947 23.1178 + endloop + endfacet + facet normal -0.0785237 -0.274054 0.958503 + outer loop + vertex -550.118 64.4947 23.1178 + vertex -555.861 63.5793 22.3856 + vertex -549.594 62.3064 22.5351 + endloop + endfacet + facet normal -0.0819988 -0.248088 0.965261 + outer loop + vertex -573.481 70.8997 22.8099 + vertex -573.013 68.7157 22.2883 + vertex -567.6 69.2688 22.8903 + endloop + endfacet + facet normal -0.0824797 -0.244369 0.966168 + outer loop + vertex -567.6 69.2688 22.8903 + vertex -573.013 68.7157 22.2883 + vertex -567.586 66.7889 22.2643 + endloop + endfacet + facet normal -0.109867 -0.335958 0.935447 + outer loop + vertex -573.505 73.022 23.5692 + vertex -573.481 70.8997 22.8099 + vertex -567.653 71.3953 23.6724 + endloop + endfacet + facet normal -0.108561 -0.345512 0.932114 + outer loop + vertex -567.653 71.3953 23.6724 + vertex -573.481 70.8997 22.8099 + vertex -567.6 69.2688 22.8903 + endloop + endfacet + facet normal -0.111745 -0.34546 0.931757 + outer loop + vertex -567.653 71.3953 23.6724 + vertex -567.6 69.2688 22.8903 + vertex -561.808 69.7825 23.7753 + endloop + endfacet + facet normal -0.110393 -0.354875 0.928373 + outer loop + vertex -561.808 69.7825 23.7753 + vertex -567.6 69.2688 22.8903 + vertex -561.737 67.6572 22.9714 + endloop + endfacet + facet normal -0.0805491 -0.244398 0.966324 + outer loop + vertex -567.6 69.2688 22.8903 + vertex -567.586 66.7889 22.2643 + vertex -561.737 67.6572 22.9714 + endloop + endfacet + facet normal -0.0777278 -0.26022 0.962416 + outer loop + vertex -561.737 67.6572 22.9714 + vertex -567.586 66.7889 22.2643 + vertex -561.241 65.4677 22.4195 + endloop + endfacet + facet normal -0.0795726 -0.231295 0.969624 + outer loop + vertex -585.083 74.217 22.6511 + vertex -584.57 72.0343 22.1725 + vertex -579.352 72.5559 22.7252 + endloop + endfacet + facet normal -0.0799154 -0.228531 0.970251 + outer loop + vertex -579.352 72.5559 22.7252 + vertex -584.57 72.0343 22.1725 + vertex -579.285 70.0782 22.1471 + endloop + endfacet + facet normal -0.108186 -0.312149 0.943853 + outer loop + vertex -585.097 76.3298 23.3482 + vertex -585.083 74.217 22.6511 + vertex -579.341 74.6715 23.4595 + endloop + endfacet + facet normal -0.10651 -0.325579 0.939497 + outer loop + vertex -579.341 74.6715 23.4595 + vertex -585.083 74.217 22.6511 + vertex -579.352 72.5559 22.7252 + endloop + endfacet + facet normal -0.109647 -0.325454 0.939179 + outer loop + vertex -579.341 74.6715 23.4595 + vertex -579.352 72.5559 22.7252 + vertex -573.505 73.022 23.5692 + endloop + endfacet + facet normal -0.108291 -0.336001 0.935616 + outer loop + vertex -573.505 73.022 23.5692 + vertex -579.352 72.5559 22.7252 + vertex -573.481 70.8997 22.8099 + endloop + endfacet + facet normal -0.0784723 -0.22852 0.970371 + outer loop + vertex -579.352 72.5559 22.7252 + vertex -579.285 70.0782 22.1471 + vertex -573.481 70.8997 22.8099 + endloop + endfacet + facet normal -0.0753875 -0.246876 0.96611 + outer loop + vertex -573.481 70.8997 22.8099 + vertex -579.285 70.0782 22.1471 + vertex -573.013 68.7157 22.2883 + endloop + endfacet + facet normal -0.0773049 -0.22125 0.972148 + outer loop + vertex -595.589 77.2928 22.511 + vertex -594.776 75.145 22.0869 + vertex -590.599 75.8431 22.5779 + endloop + endfacet + facet normal -0.077982 -0.217721 0.972891 + outer loop + vertex -590.599 75.8431 22.5779 + vertex -594.776 75.145 22.0869 + vertex -590.149 73.3562 22.0574 + endloop + endfacet + facet normal -0.103207 -0.289622 0.95156 + outer loop + vertex -595.646 79.4141 23.1505 + vertex -595.589 77.2928 22.511 + vertex -590.628 77.9425 23.2468 + endloop + endfacet + facet normal -0.100817 -0.303325 0.947539 + outer loop + vertex -590.628 77.9425 23.2468 + vertex -595.589 77.2928 22.511 + vertex -590.599 75.8431 22.5779 + endloop + endfacet + facet normal -0.105767 -0.303232 0.947029 + outer loop + vertex -590.628 77.9425 23.2468 + vertex -590.599 75.8431 22.5779 + vertex -585.097 76.3298 23.3482 + endloop + endfacet + facet normal -0.104577 -0.312249 0.944227 + outer loop + vertex -585.097 76.3298 23.3482 + vertex -590.599 75.8431 22.5779 + vertex -585.083 74.217 22.6511 + endloop + endfacet + facet normal -0.0770458 -0.217574 0.972998 + outer loop + vertex -590.599 75.8431 22.5779 + vertex -590.149 73.3562 22.0574 + vertex -585.083 74.217 22.6511 + endloop + endfacet + facet normal -0.0745705 -0.23026 0.970268 + outer loop + vertex -585.083 74.217 22.6511 + vertex -590.149 73.3562 22.0574 + vertex -584.57 72.0343 22.1725 + endloop + endfacet + facet normal -0.0732988 -0.200834 0.976879 + outer loop + vertex -602.636 79.3332 22.4087 + vertex -602.142 77.0613 21.9787 + vertex -599.75 78.4816 22.4502 + endloop + endfacet + facet normal -0.0723318 -0.20238 0.976632 + outer loop + vertex -599.75 78.4816 22.4502 + vertex -602.142 77.0613 21.9787 + vertex -598.956 75.8347 21.9605 + endloop + endfacet + facet normal -0.099223 -0.268137 0.958257 + outer loop + vertex -602.562 81.433 23.004 + vertex -602.636 79.3332 22.4087 + vertex -599.75 80.6177 23.0669 + endloop + endfacet + facet normal -0.0952284 -0.276151 0.956385 + outer loop + vertex -599.75 80.6177 23.0669 + vertex -602.636 79.3332 22.4087 + vertex -599.75 78.4816 22.4502 + endloop + endfacet + facet normal -0.100408 -0.276012 0.955895 + outer loop + vertex -599.75 80.6177 23.0669 + vertex -599.75 78.4816 22.4502 + vertex -595.646 79.4141 23.1505 + endloop + endfacet + facet normal -0.0966837 -0.289652 0.952236 + outer loop + vertex -595.646 79.4141 23.1505 + vertex -599.75 78.4816 22.4502 + vertex -595.589 77.2928 22.511 + endloop + endfacet + facet normal -0.0720851 -0.202312 0.976664 + outer loop + vertex -599.75 78.4816 22.4502 + vertex -598.956 75.8347 21.9605 + vertex -595.589 77.2928 22.511 + endloop + endfacet + facet normal -0.0652632 -0.21705 0.973976 + outer loop + vertex -595.589 77.2928 22.511 + vertex -598.956 75.8347 21.9605 + vertex -594.776 75.145 22.0869 + endloop + endfacet + facet normal -0.0618924 -0.20087 0.977661 + outer loop + vertex -604.554 80.0385 22.4072 + vertex -604.683 78.0935 21.9994 + vertex -604.161 79.8304 22.3893 + endloop + endfacet + facet normal -0.0877503 -0.193014 0.977264 + outer loop + vertex -604.161 79.8304 22.3893 + vertex -604.683 78.0935 21.9994 + vertex -603.886 77.2982 21.9139 + endloop + endfacet + facet normal -0.117722 -0.259822 0.958454 + outer loop + vertex -604.341 82.1276 22.9996 + vertex -604.554 80.0385 22.4072 + vertex -603.994 81.8633 22.9706 + endloop + endfacet + facet normal -0.0973668 -0.266229 0.95898 + outer loop + vertex -603.994 81.8633 22.9706 + vertex -604.554 80.0385 22.4072 + vertex -604.161 79.8304 22.3893 + endloop + endfacet + facet normal -0.102177 -0.26573 0.958617 + outer loop + vertex -603.994 81.8633 22.9706 + vertex -604.161 79.8304 22.3893 + vertex -602.562 81.433 23.004 + endloop + endfacet + facet normal -0.0996379 -0.268112 0.958221 + outer loop + vertex -602.562 81.433 23.004 + vertex -604.161 79.8304 22.3893 + vertex -602.636 79.3332 22.4087 + endloop + endfacet + facet normal -0.0750397 -0.191874 0.978547 + outer loop + vertex -604.161 79.8304 22.3893 + vertex -603.886 77.2982 21.9139 + vertex -602.636 79.3332 22.4087 + endloop + endfacet + facet normal -0.0633933 -0.198887 0.97797 + outer loop + vertex -602.636 79.3332 22.4087 + vertex -603.886 77.2982 21.9139 + vertex -602.142 77.0613 21.9787 + endloop + endfacet + facet normal 0.372476 0.241905 -0.895959 + outer loop + vertex -604.208 82.6724 23.2018 + vertex -604.374 80.3357 22.502 + vertex -604.341 82.1276 22.9996 + endloop + endfacet + facet normal 0.0677517 0.265814 -0.961641 + outer loop + vertex -604.341 82.1276 22.9996 + vertex -604.374 80.3357 22.502 + vertex -604.554 80.0385 22.4072 + endloop + endfacet + facet normal 0.255261 0.150563 -0.955077 + outer loop + vertex -604.374 80.3357 22.502 + vertex -604.883 77.6955 21.9498 + vertex -604.554 80.0385 22.4072 + endloop + endfacet + facet normal 0.186454 -0.213432 0.959 + outer loop + vertex -604.554 80.0385 22.4072 + vertex -604.883 77.6955 21.9498 + vertex -604.683 78.0935 21.9994 + endloop + endfacet + facet normal -0.0807852 -0.303239 0.949484 + outer loop + vertex -518.786 33.9419 17.8412 + vertex -514.355 33.1323 17.9597 + vertex -517.403 36.6413 18.8211 + endloop + endfacet + facet normal -0.0769646 -0.307631 0.948388 + outer loop + vertex -511.131 31.9264 17.8302 + vertex -511.777 34.6922 18.6749 + vertex -514.355 33.1323 17.9597 + endloop + endfacet + facet normal -0.0802382 -0.302808 0.949668 + outer loop + vertex -511.777 34.6922 18.6749 + vertex -517.403 36.6413 18.8211 + vertex -514.355 33.1323 17.9597 + endloop + endfacet + facet normal -0.0785922 -0.298987 0.951015 + outer loop + vertex -529.921 36.8145 17.8372 + vertex -523.85 35.6513 17.9732 + vertex -526.84 39.2784 18.8664 + endloop + endfacet + facet normal -0.0780795 -0.304554 0.949289 + outer loop + vertex -518.786 33.9419 17.8412 + vertex -517.403 36.6413 18.8211 + vertex -523.85 35.6513 17.9732 + endloop + endfacet + facet normal -0.0790843 -0.299355 0.950859 + outer loop + vertex -517.403 36.6413 18.8211 + vertex -526.84 39.2784 18.8664 + vertex -523.85 35.6513 17.9732 + endloop + endfacet + facet normal -0.0793209 -0.295836 0.95194 + outer loop + vertex -541.927 39.9162 17.827 + vertex -535.453 38.6466 17.9719 + vertex -538.181 42.2482 18.8638 + endloop + endfacet + facet normal -0.0766189 -0.301227 0.950469 + outer loop + vertex -529.921 36.8145 17.8372 + vertex -526.84 39.2784 18.8664 + vertex -535.453 38.6466 17.9719 + endloop + endfacet + facet normal -0.0773281 -0.294472 0.952526 + outer loop + vertex -526.84 39.2784 18.8664 + vertex -538.181 42.2482 18.8638 + vertex -535.453 38.6466 17.9719 + endloop + endfacet + facet normal -0.0809927 -0.294287 0.952279 + outer loop + vertex -553.857 43.0906 17.8201 + vertex -547.442 41.7838 17.9618 + vertex -550.111 45.3817 18.8467 + endloop + endfacet + facet normal -0.077704 -0.298168 0.951345 + outer loop + vertex -541.927 39.9162 17.827 + vertex -538.181 42.2482 18.8638 + vertex -547.442 41.7838 17.9618 + endloop + endfacet + facet normal -0.0781646 -0.292391 0.953099 + outer loop + vertex -538.181 42.2482 18.8638 + vertex -550.111 45.3817 18.8467 + vertex -547.442 41.7838 17.9618 + endloop + endfacet + facet normal -0.0825107 -0.292504 0.952698 + outer loop + vertex -565.542 46.2893 17.8176 + vertex -559.27 44.9728 17.9566 + vertex -561.985 48.5801 18.8291 + endloop + endfacet + facet normal -0.0792239 -0.296884 0.951621 + outer loop + vertex -553.857 43.0906 17.8201 + vertex -550.111 45.3817 18.8467 + vertex -559.27 44.9728 17.9566 + endloop + endfacet + facet normal -0.0796903 -0.290582 0.953526 + outer loop + vertex -550.111 45.3817 18.8467 + vertex -561.985 48.5801 18.8291 + vertex -559.27 44.9728 17.9566 + endloop + endfacet + facet normal -0.0846713 -0.293978 0.952054 + outer loop + vertex -577.08 49.5091 17.8071 + vertex -570.888 48.1805 17.9476 + vertex -573.725 51.8298 18.822 + endloop + endfacet + facet normal -0.0810603 -0.294535 0.952197 + outer loop + vertex -565.542 46.2893 17.8176 + vertex -561.985 48.5801 18.8291 + vertex -570.888 48.1805 17.9476 + endloop + endfacet + facet normal -0.0812805 -0.291588 0.953084 + outer loop + vertex -561.985 48.5801 18.8291 + vertex -573.725 51.8298 18.822 + vertex -570.888 48.1805 17.9476 + endloop + endfacet + facet normal -0.0837494 -0.290446 0.953219 + outer loop + vertex -588.635 52.8324 17.8285 + vertex -582.456 51.4472 17.9492 + vertex -585.31 55.2074 18.8442 + endloop + endfacet + facet normal -0.082062 -0.297387 0.951224 + outer loop + vertex -577.08 49.5091 17.8071 + vertex -573.725 51.8298 18.822 + vertex -582.456 51.4472 17.9492 + endloop + endfacet + facet normal -0.0826324 -0.289677 0.953551 + outer loop + vertex -573.725 51.8298 18.822 + vertex -585.31 55.2074 18.8442 + vertex -582.456 51.4472 17.9492 + endloop + endfacet + facet normal -0.0863372 -0.281611 0.955637 + outer loop + vertex -599.142 55.9585 17.8418 + vertex -593.794 54.817 17.9886 + vertex -596.137 58.7895 18.9476 + endloop + endfacet + facet normal -0.0826691 -0.291819 0.952894 + outer loop + vertex -588.635 52.8324 17.8285 + vertex -585.31 55.2074 18.8442 + vertex -593.794 54.817 17.9886 + endloop + endfacet + facet normal -0.0835523 -0.280133 0.956318 + outer loop + vertex -585.31 55.2074 18.8442 + vertex -596.137 58.7895 18.9476 + vertex -593.794 54.817 17.9886 + endloop + endfacet + facet normal -0.0308185 -0.303495 0.952334 + outer loop + vertex -606.548 58.4467 17.9369 + vertex -606.143 58.3375 17.9152 + vertex -605.376 61.5303 18.9576 + endloop + endfacet + facet normal -0.0923056 -0.308418 0.946762 + outer loop + vertex -605.38 57.4854 17.712 + vertex -603.359 59.6148 18.6028 + vertex -606.143 58.3375 17.9152 + endloop + endfacet + facet normal -0.104033 -0.285977 0.952572 + outer loop + vertex -603.359 59.6148 18.6028 + vertex -605.376 61.5303 18.9576 + vertex -606.143 58.3375 17.9152 + endloop + endfacet + facet normal -0.114725 -0.485857 0.866476 + outer loop + vertex -510.53 29.9074 17.0179 + vertex -510.531 27.8523 15.8653 + vertex -508.967 29.2652 16.8647 + endloop + endfacet + facet normal -0.101349 -0.497259 0.861662 + outer loop + vertex -508.967 29.2652 16.8647 + vertex -510.531 27.8523 15.8653 + vertex -508.924 27.055 15.5943 + endloop + endfacet + facet normal -0.0480374 -0.385082 0.921631 + outer loop + vertex -511.131 31.9264 17.8302 + vertex -510.53 29.9074 17.0179 + vertex -509.564 32.0462 17.9619 + endloop + endfacet + facet normal -0.0649166 -0.378251 0.923424 + outer loop + vertex -509.564 32.0462 17.9619 + vertex -510.53 29.9074 17.0179 + vertex -508.967 29.2652 16.8647 + endloop + endfacet + facet normal -0.124287 -0.485763 0.865209 + outer loop + vertex -518.091 31.8445 17.0278 + vertex -518.092 29.8909 15.9308 + vertex -513.625 30.7205 17.0383 + endloop + endfacet + facet normal -0.125357 -0.482345 0.866965 + outer loop + vertex -513.625 30.7205 17.0383 + vertex -518.092 29.8909 15.9308 + vertex -513.611 28.7566 15.9477 + endloop + endfacet + facet normal -0.0952667 -0.38726 0.917036 + outer loop + vertex -518.786 33.9419 17.8412 + vertex -518.091 31.8445 17.0278 + vertex -514.355 33.1323 17.9597 + endloop + endfacet + facet normal -0.0980336 -0.380936 0.91939 + outer loop + vertex -514.355 33.1323 17.9597 + vertex -518.091 31.8445 17.0278 + vertex -513.625 30.7205 17.0383 + endloop + endfacet + facet normal -0.106316 -0.382796 0.917695 + outer loop + vertex -514.355 33.1323 17.9597 + vertex -513.625 30.7205 17.0383 + vertex -511.131 31.9264 17.8302 + endloop + endfacet + facet normal -0.098154 -0.396454 0.912792 + outer loop + vertex -511.131 31.9264 17.8302 + vertex -513.625 30.7205 17.0383 + vertex -510.53 29.9074 17.0179 + endloop + endfacet + facet normal -0.121079 -0.48258 0.867443 + outer loop + vertex -513.625 30.7205 17.0383 + vertex -513.611 28.7566 15.9477 + vertex -510.53 29.9074 17.0179 + endloop + endfacet + facet normal -0.119454 -0.485581 0.865992 + outer loop + vertex -510.53 29.9074 17.0179 + vertex -513.611 28.7566 15.9477 + vertex -510.531 27.8523 15.8653 + endloop + endfacet + facet normal -0.12374 -0.486174 0.865057 + outer loop + vertex -529.371 34.7027 17.0113 + vertex -529.355 32.7181 15.8983 + vertex -523.494 33.2116 17.0139 + endloop + endfacet + facet normal -0.124115 -0.484156 0.866134 + outer loop + vertex -523.494 33.2116 17.0139 + vertex -529.355 32.7181 15.8983 + vertex -523.489 31.2324 15.9084 + endloop + endfacet + facet normal -0.094109 -0.383752 0.918628 + outer loop + vertex -529.921 36.8145 17.8372 + vertex -529.371 34.7027 17.0113 + vertex -523.85 35.6513 17.9732 + endloop + endfacet + facet normal -0.0958907 -0.376313 0.921517 + outer loop + vertex -523.85 35.6513 17.9732 + vertex -529.371 34.7027 17.0113 + vertex -523.494 33.2116 17.0139 + endloop + endfacet + facet normal -0.103276 -0.376971 0.920449 + outer loop + vertex -523.85 35.6513 17.9732 + vertex -523.494 33.2116 17.0139 + vertex -518.786 33.9419 17.8412 + endloop + endfacet + facet normal -0.10067 -0.388605 0.915888 + outer loop + vertex -518.786 33.9419 17.8412 + vertex -523.494 33.2116 17.0139 + vertex -518.091 31.8445 17.0278 + endloop + endfacet + facet normal -0.124709 -0.484121 0.866068 + outer loop + vertex -523.494 33.2116 17.0139 + vertex -523.489 31.2324 15.9084 + vertex -518.091 31.8445 17.0278 + endloop + endfacet + facet normal -0.124344 -0.48576 0.865203 + outer loop + vertex -518.091 31.8445 17.0278 + vertex -523.489 31.2324 15.9084 + vertex -518.092 29.8909 15.9308 + endloop + endfacet + facet normal -0.126168 -0.48269 0.866656 + outer loop + vertex -541.41 37.8157 17.0016 + vertex -541.297 35.8127 15.9025 + vertex -535.39 36.2496 17.0058 + endloop + endfacet + facet normal -0.125877 -0.484362 0.865764 + outer loop + vertex -535.39 36.2496 17.0058 + vertex -541.297 35.8127 15.9025 + vertex -535.339 34.258 15.899 + endloop + endfacet + facet normal -0.0959275 -0.384368 0.918183 + outer loop + vertex -541.927 39.9162 17.827 + vertex -541.41 37.8157 17.0016 + vertex -535.453 38.6466 17.9719 + endloop + endfacet + facet normal -0.0979878 -0.374224 0.922147 + outer loop + vertex -535.453 38.6466 17.9719 + vertex -541.41 37.8157 17.0016 + vertex -535.39 36.2496 17.0058 + endloop + endfacet + facet normal -0.101474 -0.374172 0.921791 + outer loop + vertex -535.453 38.6466 17.9719 + vertex -535.39 36.2496 17.0058 + vertex -529.921 36.8145 17.8372 + endloop + endfacet + facet normal -0.0997366 -0.384811 0.917591 + outer loop + vertex -529.921 36.8145 17.8372 + vertex -535.39 36.2496 17.0058 + vertex -529.371 34.7027 17.0113 + endloop + endfacet + facet normal -0.125278 -0.484387 0.865837 + outer loop + vertex -535.39 36.2496 17.0058 + vertex -535.339 34.258 15.899 + vertex -529.371 34.7027 17.0113 + endloop + endfacet + facet normal -0.124979 -0.486105 0.864917 + outer loop + vertex -529.371 34.7027 17.0113 + vertex -535.339 34.258 15.899 + vertex -529.355 32.7181 15.8983 + endloop + endfacet + facet normal -0.13073 -0.484167 0.865155 + outer loop + vertex -553.274 40.9791 16.9992 + vertex -553.064 38.9619 15.9021 + vertex -547.373 39.3893 17.0014 + endloop + endfacet + facet normal -0.130387 -0.486092 0.864126 + outer loop + vertex -547.373 39.3893 17.0014 + vertex -553.064 38.9619 15.9021 + vertex -547.204 37.3853 15.8995 + endloop + endfacet + facet normal -0.0985264 -0.38407 0.918032 + outer loop + vertex -553.857 43.0906 17.8201 + vertex -553.274 40.9791 16.9992 + vertex -547.442 41.7838 17.9618 + endloop + endfacet + facet normal -0.100783 -0.372913 0.922377 + outer loop + vertex -547.442 41.7838 17.9618 + vertex -553.274 40.9791 16.9992 + vertex -547.373 39.3893 17.0014 + endloop + endfacet + facet normal -0.103715 -0.372874 0.922067 + outer loop + vertex -547.442 41.7838 17.9618 + vertex -547.373 39.3893 17.0014 + vertex -541.927 39.9162 17.827 + endloop + endfacet + facet normal -0.101756 -0.385385 0.917128 + outer loop + vertex -541.927 39.9162 17.827 + vertex -547.373 39.3893 17.0014 + vertex -541.41 37.8157 17.0016 + endloop + endfacet + facet normal -0.128332 -0.486089 0.864435 + outer loop + vertex -547.373 39.3893 17.0014 + vertex -547.204 37.3853 15.8995 + vertex -541.41 37.8157 17.0016 + endloop + endfacet + facet normal -0.128939 -0.482639 0.866276 + outer loop + vertex -541.41 37.8157 17.0016 + vertex -547.204 37.3853 15.8995 + vertex -541.297 35.8127 15.9025 + endloop + endfacet + facet normal -0.133778 -0.482926 0.865382 + outer loop + vertex -564.922 44.179 16.9979 + vertex -564.696 42.1557 15.9038 + vertex -559.124 42.5754 16.9993 + endloop + endfacet + facet normal -0.133309 -0.485532 0.863995 + outer loop + vertex -559.124 42.5754 16.9993 + vertex -564.696 42.1557 15.9038 + vertex -558.896 40.5573 15.9004 + endloop + endfacet + facet normal -0.101334 -0.385957 0.916934 + outer loop + vertex -565.542 46.2893 17.8176 + vertex -564.922 44.179 16.9979 + vertex -559.27 44.9728 17.9566 + endloop + endfacet + facet normal -0.103744 -0.3743 0.921486 + outer loop + vertex -559.27 44.9728 17.9566 + vertex -564.922 44.179 16.9979 + vertex -559.124 42.5754 16.9993 + endloop + endfacet + facet normal -0.106925 -0.374342 0.921105 + outer loop + vertex -559.27 44.9728 17.9566 + vertex -559.124 42.5754 16.9993 + vertex -553.857 43.0906 17.8201 + endloop + endfacet + facet normal -0.105163 -0.385398 0.916738 + outer loop + vertex -553.857 43.0906 17.8201 + vertex -559.124 42.5754 16.9993 + vertex -553.274 40.9791 16.9992 + endloop + endfacet + facet normal -0.132482 -0.485514 0.864132 + outer loop + vertex -559.124 42.5754 16.9993 + vertex -558.896 40.5573 15.9004 + vertex -553.274 40.9791 16.9992 + endloop + endfacet + facet normal -0.132718 -0.484199 0.864834 + outer loop + vertex -553.274 40.9791 16.9992 + vertex -558.896 40.5573 15.9004 + vertex -553.064 38.9619 15.9021 + endloop + endfacet + facet normal -0.136368 -0.486827 0.862788 + outer loop + vertex -576.395 47.3824 16.9977 + vertex -576.193 45.3805 15.9 + vertex -570.676 45.7806 16.9977 + endloop + endfacet + facet normal -0.136802 -0.484401 0.864084 + outer loop + vertex -570.676 45.7806 16.9977 + vertex -576.193 45.3805 15.9 + vertex -570.463 43.7666 15.9024 + endloop + endfacet + facet normal -0.102919 -0.382612 0.918159 + outer loop + vertex -577.08 49.5091 17.8071 + vertex -576.395 47.3824 16.9977 + vertex -570.888 48.1805 17.9476 + endloop + endfacet + facet normal -0.104751 -0.37396 0.92151 + outer loop + vertex -570.888 48.1805 17.9476 + vertex -576.395 47.3824 16.9977 + vertex -570.676 45.7806 16.9977 + endloop + endfacet + facet normal -0.109991 -0.374149 0.920823 + outer loop + vertex -570.888 48.1805 17.9476 + vertex -570.676 45.7806 16.9977 + vertex -565.542 46.2893 17.8176 + endloop + endfacet + facet normal -0.107849 -0.387355 0.915601 + outer loop + vertex -565.542 46.2893 17.8176 + vertex -570.676 45.7806 16.9977 + vertex -564.922 44.179 16.9979 + endloop + endfacet + facet normal -0.134848 -0.484371 0.864408 + outer loop + vertex -570.676 45.7806 16.9977 + vertex -570.463 43.7666 15.9024 + vertex -564.922 44.179 16.9979 + endloop + endfacet + facet normal -0.135102 -0.482954 0.865161 + outer loop + vertex -564.922 44.179 16.9979 + vertex -570.463 43.7666 15.9024 + vertex -564.696 42.1557 15.9038 + endloop + endfacet + facet normal -0.137307 -0.484702 0.863835 + outer loop + vertex -587.829 50.6408 17.0064 + vertex -587.544 48.6089 15.9116 + vertex -582.119 49.004 16.9956 + endloop + endfacet + facet normal -0.137068 -0.486034 0.863124 + outer loop + vertex -582.119 49.004 16.9956 + vertex -587.544 48.6089 15.9116 + vertex -581.892 46.9961 15.9011 + endloop + endfacet + facet normal -0.103699 -0.382482 0.918125 + outer loop + vertex -588.635 52.8324 17.8285 + vertex -587.829 50.6408 17.0064 + vertex -582.456 51.4472 17.9492 + endloop + endfacet + facet normal -0.105513 -0.374158 0.921343 + outer loop + vertex -582.456 51.4472 17.9492 + vertex -587.829 50.6408 17.0064 + vertex -582.119 49.004 16.9956 + endloop + endfacet + facet normal -0.110695 -0.37457 0.920567 + outer loop + vertex -582.456 51.4472 17.9492 + vertex -582.119 49.004 16.9956 + vertex -577.08 49.5091 17.8071 + endloop + endfacet + facet normal -0.109135 -0.384104 0.916817 + outer loop + vertex -577.08 49.5091 17.8071 + vertex -582.119 49.004 16.9956 + vertex -576.395 47.3824 16.9977 + endloop + endfacet + facet normal -0.137995 -0.486053 0.862966 + outer loop + vertex -582.119 49.004 16.9956 + vertex -581.892 46.9961 15.9011 + vertex -576.395 47.3824 16.9977 + endloop + endfacet + facet normal -0.137855 -0.486842 0.862543 + outer loop + vertex -576.395 47.3824 16.9977 + vertex -581.892 46.9961 15.9011 + vertex -576.193 45.3805 15.9 + endloop + endfacet + facet normal -0.142641 -0.484141 0.863285 + outer loop + vertex -598.473 53.7677 17.0193 + vertex -598.077 51.6851 15.9167 + vertex -593.397 52.2741 17.0204 + endloop + endfacet + facet normal -0.14272 -0.483823 0.86345 + outer loop + vertex -593.397 52.2741 17.0204 + vertex -598.077 51.6851 15.9167 + vertex -593.04 50.2051 15.9201 + endloop + endfacet + facet normal -0.105862 -0.377688 0.919861 + outer loop + vertex -599.142 55.9585 17.8418 + vertex -598.473 53.7677 17.0193 + vertex -593.794 54.817 17.9886 + endloop + endfacet + facet normal -0.108627 -0.368497 0.923261 + outer loop + vertex -593.794 54.817 17.9886 + vertex -598.473 53.7677 17.0193 + vertex -593.397 52.2741 17.0204 + endloop + endfacet + facet normal -0.113277 -0.368942 0.922524 + outer loop + vertex -593.794 54.817 17.9886 + vertex -593.397 52.2741 17.0204 + vertex -588.635 52.8324 17.8285 + endloop + endfacet + facet normal -0.110454 -0.384371 0.916547 + outer loop + vertex -588.635 52.8324 17.8285 + vertex -593.397 52.2741 17.0204 + vertex -587.829 50.6408 17.0064 + endloop + endfacet + facet normal -0.139702 -0.483624 0.864055 + outer loop + vertex -593.397 52.2741 17.0204 + vertex -593.04 50.2051 15.9201 + vertex -587.829 50.6408 17.0064 + endloop + endfacet + facet normal -0.139475 -0.484791 0.863437 + outer loop + vertex -587.829 50.6408 17.0064 + vertex -593.04 50.2051 15.9201 + vertex -587.544 48.6089 15.9116 + endloop + endfacet + facet normal -0.152055 -0.495139 0.855404 + outer loop + vertex -605.361 55.6832 16.9275 + vertex -605.182 53.7452 15.8376 + vertex -602.595 54.9278 16.9819 + endloop + endfacet + facet normal -0.155191 -0.490384 0.857578 + outer loop + vertex -602.595 54.9278 16.9819 + vertex -605.182 53.7452 15.8376 + vertex -602.251 52.9028 15.8861 + endloop + endfacet + facet normal -0.106469 -0.397833 0.911259 + outer loop + vertex -605.38 57.4854 17.712 + vertex -605.361 55.6832 16.9275 + vertex -602.571 57.1775 17.9059 + endloop + endfacet + facet normal -0.120767 -0.376013 0.918711 + outer loop + vertex -602.571 57.1775 17.9059 + vertex -605.361 55.6832 16.9275 + vertex -602.595 54.9278 16.9819 + endloop + endfacet + facet normal -0.116593 -0.376241 0.919156 + outer loop + vertex -602.571 57.1775 17.9059 + vertex -602.595 54.9278 16.9819 + vertex -599.142 55.9585 17.8418 + endloop + endfacet + facet normal -0.115212 -0.379794 0.917868 + outer loop + vertex -599.142 55.9585 17.8418 + vertex -602.595 54.9278 16.9819 + vertex -598.473 53.7677 17.0193 + endloop + endfacet + facet normal -0.145656 -0.489838 0.85956 + outer loop + vertex -602.595 54.9278 16.9819 + vertex -602.251 52.9028 15.8861 + vertex -598.473 53.7677 17.0193 + endloop + endfacet + facet normal -0.147668 -0.484533 0.862219 + outer loop + vertex -598.473 53.7677 17.0193 + vertex -602.251 52.9028 15.8861 + vertex -598.077 51.6851 15.9167 + endloop + endfacet + facet normal -0.21365 -0.460915 0.861343 + outer loop + vertex -606.918 56.4625 17.0541 + vertex -607.194 54.528 15.9504 + vertex -606.72 56.1531 16.9376 + endloop + endfacet + facet normal -0.108044 -0.492935 0.863332 + outer loop + vertex -606.72 56.1531 16.9376 + vertex -607.194 54.528 15.9504 + vertex -606.769 54.2367 15.8373 + endloop + endfacet + facet normal -0.0578955 -0.396792 0.916081 + outer loop + vertex -606.548 58.4467 17.9369 + vertex -606.918 56.4625 17.0541 + vertex -606.143 58.3375 17.9152 + endloop + endfacet + facet normal -0.0720683 -0.391518 0.917344 + outer loop + vertex -606.143 58.3375 17.9152 + vertex -606.918 56.4625 17.0541 + vertex -606.72 56.1531 16.9376 + endloop + endfacet + facet normal -0.165141 -0.366233 0.915752 + outer loop + vertex -606.143 58.3375 17.9152 + vertex -606.72 56.1531 16.9376 + vertex -605.38 57.4854 17.712 + endloop + endfacet + facet normal -0.130468 -0.396906 0.908539 + outer loop + vertex -605.38 57.4854 17.712 + vertex -606.72 56.1531 16.9376 + vertex -605.361 55.6832 16.9275 + endloop + endfacet + facet normal -0.162409 -0.488187 0.857494 + outer loop + vertex -606.72 56.1531 16.9376 + vertex -606.769 54.2367 15.8373 + vertex -605.361 55.6832 16.9275 + endloop + endfacet + facet normal -0.153466 -0.495131 0.855157 + outer loop + vertex -605.361 55.6832 16.9275 + vertex -606.769 54.2367 15.8373 + vertex -605.182 53.7452 15.8376 + endloop + endfacet + facet normal 0.997878 -0.0530026 -0.0378229 + outer loop + vertex -606.579 57.9644 17.8012 + vertex -606.673 56.6212 17.2052 + vertex -606.548 58.4467 17.9369 + endloop + endfacet + facet normal 0.330455 0.331628 -0.883642 + outer loop + vertex -606.548 58.4467 17.9369 + vertex -606.673 56.6212 17.2052 + vertex -606.918 56.4625 17.0541 + endloop + endfacet + facet normal 0.241847 0.446892 -0.861277 + outer loop + vertex -606.673 56.6212 17.2052 + vertex -606.951 54.8011 16.1827 + vertex -606.918 56.4625 17.0541 + endloop + endfacet + facet normal 0.316042 0.435698 -0.842784 + outer loop + vertex -606.918 56.4625 17.0541 + vertex -606.951 54.8011 16.1827 + vertex -607.194 54.528 15.9504 + endloop + endfacet + facet normal -0.228288 -0.762818 0.604974 + outer loop + vertex -510.746 26.1846 14.4814 + vertex -510.936 24.9694 12.8772 + vertex -509.046 25.4104 14.1468 + endloop + endfacet + facet normal -0.19475 -0.799752 0.567863 + outer loop + vertex -509.046 25.4104 14.1468 + vertex -510.936 24.9694 12.8772 + vertex -509.197 24.281 12.5041 + endloop + endfacet + facet normal -0.175559 -0.615232 0.76855 + outer loop + vertex -510.531 27.8523 15.8653 + vertex -510.746 26.1846 14.4814 + vertex -508.924 27.055 15.5943 + endloop + endfacet + facet normal -0.147577 -0.647294 0.747818 + outer loop + vertex -508.924 27.055 15.5943 + vertex -510.746 26.1846 14.4814 + vertex -509.046 25.4104 14.1468 + endloop + endfacet + facet normal -0.194529 -0.762389 0.617188 + outer loop + vertex -518.329 28.2668 14.6093 + vertex -518.582 27.0554 13.0334 + vertex -513.887 27.1333 14.6095 + endloop + endfacet + facet normal -0.194771 -0.761768 0.617879 + outer loop + vertex -513.887 27.1333 14.6095 + vertex -518.582 27.0554 13.0334 + vertex -514.135 25.9132 13.027 + endloop + endfacet + facet normal -0.157167 -0.609358 0.777162 + outer loop + vertex -518.092 29.8909 15.9308 + vertex -518.329 28.2668 14.6093 + vertex -513.611 28.7566 15.9477 + endloop + endfacet + facet normal -0.15625 -0.612323 0.775014 + outer loop + vertex -513.611 28.7566 15.9477 + vertex -518.329 28.2668 14.6093 + vertex -513.887 27.1333 14.6095 + endloop + endfacet + facet normal -0.158949 -0.611771 0.774901 + outer loop + vertex -513.611 28.7566 15.9477 + vertex -513.887 27.1333 14.6095 + vertex -510.531 27.8523 15.8653 + endloop + endfacet + facet normal -0.155543 -0.618924 0.769896 + outer loop + vertex -510.531 27.8523 15.8653 + vertex -513.887 27.1333 14.6095 + vertex -510.746 26.1846 14.4814 + endloop + endfacet + facet normal -0.204222 -0.759503 0.617615 + outer loop + vertex -513.887 27.1333 14.6095 + vertex -514.135 25.9132 13.027 + vertex -510.746 26.1846 14.4814 + endloop + endfacet + facet normal -0.198713 -0.769707 0.606683 + outer loop + vertex -510.746 26.1846 14.4814 + vertex -514.135 25.9132 13.027 + vertex -510.936 24.9694 12.8772 + endloop + endfacet + facet normal -0.194933 -0.764593 0.614328 + outer loop + vertex -529.506 31.0665 14.5604 + vertex -529.677 29.8331 12.9712 + vertex -523.693 29.5969 14.5761 + endloop + endfacet + facet normal -0.195854 -0.761178 0.618263 + outer loop + vertex -523.693 29.5969 14.5761 + vertex -529.677 29.8331 12.9712 + vertex -523.903 28.368 12.9966 + endloop + endfacet + facet normal -0.156573 -0.612933 0.774466 + outer loop + vertex -529.355 32.7181 15.8983 + vertex -529.506 31.0665 14.5604 + vertex -523.489 31.2324 15.9084 + endloop + endfacet + facet normal -0.156772 -0.611917 0.775229 + outer loop + vertex -523.489 31.2324 15.9084 + vertex -529.506 31.0665 14.5604 + vertex -523.693 29.5969 14.5761 + endloop + endfacet + facet normal -0.155392 -0.61216 0.775315 + outer loop + vertex -523.489 31.2324 15.9084 + vertex -523.693 29.5969 14.5761 + vertex -518.092 29.8909 15.9308 + endloop + endfacet + facet normal -0.155989 -0.609581 0.777225 + outer loop + vertex -518.092 29.8909 15.9308 + vertex -523.693 29.5969 14.5761 + vertex -518.329 28.2668 14.6093 + endloop + endfacet + facet normal -0.192769 -0.761865 0.618386 + outer loop + vertex -523.693 29.5969 14.5761 + vertex -523.903 28.368 12.9966 + vertex -518.329 28.2668 14.6093 + endloop + endfacet + facet normal -0.192454 -0.76288 0.617232 + outer loop + vertex -518.329 28.2668 14.6093 + vertex -523.903 28.368 12.9966 + vertex -518.582 27.0554 13.0334 + endloop + endfacet + facet normal -0.20029 -0.765122 0.611942 + outer loop + vertex -541.338 34.1559 14.5664 + vertex -541.446 32.9144 12.9785 + vertex -535.436 32.6053 14.5592 + endloop + endfacet + facet normal -0.201365 -0.76088 0.616858 + outer loop + vertex -535.436 32.6053 14.5592 + vertex -541.446 32.9144 12.9785 + vertex -535.57 31.355 12.9731 + endloop + endfacet + facet normal -0.160603 -0.617224 0.770221 + outer loop + vertex -541.297 35.8127 15.9025 + vertex -541.338 34.1559 14.5664 + vertex -535.339 34.258 15.899 + endloop + endfacet + facet normal -0.160867 -0.615807 0.7713 + outer loop + vertex -535.339 34.258 15.899 + vertex -541.338 34.1559 14.5664 + vertex -535.436 32.6053 14.5592 + endloop + endfacet + facet normal -0.158452 -0.616139 0.771535 + outer loop + vertex -535.339 34.258 15.899 + vertex -535.436 32.6053 14.5592 + vertex -529.355 32.7181 15.8983 + endloop + endfacet + facet normal -0.15912 -0.612535 0.774262 + outer loop + vertex -529.355 32.7181 15.8983 + vertex -535.436 32.6053 14.5592 + vertex -529.506 31.0665 14.5604 + endloop + endfacet + facet normal -0.197774 -0.761605 0.617125 + outer loop + vertex -535.436 32.6053 14.5592 + vertex -535.57 31.355 12.9731 + vertex -529.506 31.0665 14.5604 + endloop + endfacet + facet normal -0.197129 -0.764129 0.614204 + outer loop + vertex -529.506 31.0665 14.5604 + vertex -535.57 31.355 12.9731 + vertex -529.677 29.8331 12.9712 + endloop + endfacet + facet normal -0.204687 -0.762035 0.614333 + outer loop + vertex -553.034 37.2946 14.5687 + vertex -553.123 36.0435 12.9868 + vertex -547.197 35.7243 14.5655 + endloop + endfacet + facet normal -0.204477 -0.762859 0.61338 + outer loop + vertex -547.197 35.7243 14.5655 + vertex -553.123 36.0435 12.9868 + vertex -547.29 34.4771 12.9833 + endloop + endfacet + facet normal -0.165853 -0.617776 0.768665 + outer loop + vertex -553.064 38.9619 15.9021 + vertex -553.034 37.2946 14.5687 + vertex -547.204 37.3853 15.8995 + endloop + endfacet + facet normal -0.165827 -0.617913 0.76856 + outer loop + vertex -547.204 37.3853 15.8995 + vertex -553.034 37.2946 14.5687 + vertex -547.197 35.7243 14.5655 + endloop + endfacet + facet normal -0.16493 -0.618005 0.768679 + outer loop + vertex -547.204 37.3853 15.8995 + vertex -547.197 35.7243 14.5655 + vertex -541.297 35.8127 15.9025 + endloop + endfacet + facet normal -0.165179 -0.616682 0.769688 + outer loop + vertex -541.297 35.8127 15.9025 + vertex -547.197 35.7243 14.5655 + vertex -541.338 34.1559 14.5664 + endloop + endfacet + facet normal -0.204293 -0.762895 0.613397 + outer loop + vertex -547.197 35.7243 14.5655 + vertex -547.29 34.4771 12.9833 + vertex -541.338 34.1559 14.5664 + endloop + endfacet + facet normal -0.203906 -0.764412 0.611634 + outer loop + vertex -541.338 34.1559 14.5664 + vertex -547.29 34.4771 12.9833 + vertex -541.446 32.9144 12.9785 + endloop + endfacet + facet normal -0.209241 -0.7586 0.617045 + outer loop + vertex -564.675 40.4872 14.5671 + vertex -564.78 39.2297 12.9854 + vertex -558.861 38.8844 14.5681 + endloop + endfacet + facet normal -0.20839 -0.76201 0.613118 + outer loop + vertex -558.861 38.8844 14.5681 + vertex -564.78 39.2297 12.9854 + vertex -558.956 37.636 12.9842 + endloop + endfacet + facet normal -0.169727 -0.617457 0.768075 + outer loop + vertex -564.696 42.1557 15.9038 + vertex -564.675 40.4872 14.5671 + vertex -558.896 40.5573 15.9004 + endloop + endfacet + facet normal -0.169983 -0.616093 0.769113 + outer loop + vertex -558.896 40.5573 15.9004 + vertex -564.675 40.4872 14.5671 + vertex -558.861 38.8844 14.5681 + endloop + endfacet + facet normal -0.168803 -0.616204 0.769284 + outer loop + vertex -558.896 40.5573 15.9004 + vertex -558.861 38.8844 14.5681 + vertex -553.064 38.9619 15.9021 + endloop + endfacet + facet normal -0.168555 -0.617521 0.768282 + outer loop + vertex -553.064 38.9619 15.9021 + vertex -558.861 38.8844 14.5681 + vertex -553.034 37.2946 14.5687 + endloop + endfacet + facet normal -0.207983 -0.76209 0.613157 + outer loop + vertex -558.861 38.8844 14.5681 + vertex -558.956 37.636 12.9842 + vertex -553.034 37.2946 14.5687 + endloop + endfacet + facet normal -0.208166 -0.761362 0.613999 + outer loop + vertex -553.034 37.2946 14.5687 + vertex -558.956 37.636 12.9842 + vertex -553.123 36.0435 12.9868 + endloop + endfacet + facet normal -0.213118 -0.75404 0.621293 + outer loop + vertex -576.219 43.7222 14.5645 + vertex -576.351 42.4583 12.985 + vertex -570.463 42.0978 14.5674 + endloop + endfacet + facet normal -0.211865 -0.759158 0.615461 + outer loop + vertex -570.463 42.0978 14.5674 + vertex -576.351 42.4583 12.985 + vertex -570.581 40.8457 12.9822 + endloop + endfacet + facet normal -0.173839 -0.616037 0.768296 + outer loop + vertex -576.193 45.3805 15.9 + vertex -576.219 43.7222 14.5645 + vertex -570.463 43.7666 15.9024 + endloop + endfacet + facet normal -0.174001 -0.615158 0.768963 + outer loop + vertex -570.463 43.7666 15.9024 + vertex -576.219 43.7222 14.5645 + vertex -570.463 42.0978 14.5674 + endloop + endfacet + facet normal -0.172063 -0.615371 0.769229 + outer loop + vertex -570.463 43.7666 15.9024 + vertex -570.463 42.0978 14.5674 + vertex -564.696 42.1557 15.9038 + endloop + endfacet + facet normal -0.171712 -0.617257 0.767795 + outer loop + vertex -564.696 42.1557 15.9038 + vertex -570.463 42.0978 14.5674 + vertex -564.675 40.4872 14.5671 + endloop + endfacet + facet normal -0.211242 -0.759286 0.615517 + outer loop + vertex -570.463 42.0978 14.5674 + vertex -570.581 40.8457 12.9822 + vertex -564.675 40.4872 14.5671 + endloop + endfacet + facet normal -0.211526 -0.75814 0.616832 + outer loop + vertex -564.675 40.4872 14.5671 + vertex -570.581 40.8457 12.9822 + vertex -564.78 39.2297 12.9854 + endloop + endfacet + facet normal -0.214979 -0.753693 0.621073 + outer loop + vertex -587.588 46.9596 14.5781 + vertex -587.76 45.7075 12.999 + vertex -581.936 45.3411 14.5702 + endloop + endfacet + facet normal -0.21433 -0.756363 0.618043 + outer loop + vertex -581.936 45.3411 14.5702 + vertex -587.76 45.7075 12.999 + vertex -582.088 44.0899 12.9864 + endloop + endfacet + facet normal -0.174417 -0.616317 0.76794 + outer loop + vertex -587.544 48.6089 15.9116 + vertex -587.588 46.9596 14.5781 + vertex -581.892 46.9961 15.9011 + endloop + endfacet + facet normal -0.17481 -0.614164 0.769574 + outer loop + vertex -581.892 46.9961 15.9011 + vertex -587.588 46.9596 14.5781 + vertex -581.936 45.3411 14.5702 + endloop + endfacet + facet normal -0.173997 -0.614268 0.769676 + outer loop + vertex -581.892 46.9961 15.9011 + vertex -581.936 45.3411 14.5702 + vertex -576.193 45.3805 15.9 + endloop + endfacet + facet normal -0.17367 -0.616057 0.768318 + outer loop + vertex -576.193 45.3805 15.9 + vertex -581.936 45.3411 14.5702 + vertex -576.219 43.7222 14.5645 + endloop + endfacet + facet normal -0.213592 -0.756525 0.6181 + outer loop + vertex -581.936 45.3411 14.5702 + vertex -582.088 44.0899 12.9864 + vertex -576.219 43.7222 14.5645 + endloop + endfacet + facet normal -0.214254 -0.753798 0.621195 + outer loop + vertex -576.219 43.7222 14.5645 + vertex -582.088 44.0899 12.9864 + vertex -576.351 42.4583 12.985 + endloop + endfacet + facet normal -0.222608 -0.753502 0.618611 + outer loop + vertex -598.035 49.9979 14.5823 + vertex -598.213 48.7514 13.0001 + vertex -593.051 48.5328 14.5914 + endloop + endfacet + facet normal -0.221688 -0.756554 0.615208 + outer loop + vertex -593.051 48.5328 14.5914 + vertex -598.213 48.7514 13.0001 + vertex -593.223 47.2936 13.0053 + endloop + endfacet + facet normal -0.180577 -0.612896 0.769253 + outer loop + vertex -598.077 51.6851 15.9167 + vertex -598.035 49.9979 14.5823 + vertex -593.04 50.2051 15.9201 + endloop + endfacet + facet normal -0.181018 -0.611054 0.770613 + outer loop + vertex -593.04 50.2051 15.9201 + vertex -598.035 49.9979 14.5823 + vertex -593.051 48.5328 14.5914 + endloop + endfacet + facet normal -0.176448 -0.61159 0.771248 + outer loop + vertex -593.04 50.2051 15.9201 + vertex -593.051 48.5328 14.5914 + vertex -587.544 48.6089 15.9116 + endloop + endfacet + facet normal -0.175557 -0.616172 0.767797 + outer loop + vertex -587.544 48.6089 15.9116 + vertex -593.051 48.5328 14.5914 + vertex -587.588 46.9596 14.5781 + endloop + endfacet + facet normal -0.216685 -0.75771 0.615567 + outer loop + vertex -593.051 48.5328 14.5914 + vertex -593.223 47.2936 13.0053 + vertex -587.588 46.9596 14.5781 + endloop + endfacet + facet normal -0.217886 -0.75303 0.620864 + outer loop + vertex -587.588 46.9596 14.5781 + vertex -593.223 47.2936 13.0053 + vertex -587.76 45.7075 12.999 + endloop + endfacet + facet normal -0.232329 -0.762999 0.603205 + outer loop + vertex -605.123 52.0781 14.5098 + vertex -605.206 50.8455 12.9187 + vertex -602.177 51.2155 14.5532 + endloop + endfacet + facet normal -0.236007 -0.757438 0.60876 + outer loop + vertex -602.177 51.2155 14.5532 + vertex -605.206 50.8455 12.9187 + vertex -602.31 49.9771 12.961 + endloop + endfacet + facet normal -0.189706 -0.615771 0.764747 + outer loop + vertex -605.182 53.7452 15.8376 + vertex -605.123 52.0781 14.5098 + vertex -602.251 52.9028 15.8861 + endloop + endfacet + facet normal -0.190984 -0.613643 0.766138 + outer loop + vertex -602.251 52.9028 15.8861 + vertex -605.123 52.0781 14.5098 + vertex -602.177 51.2155 14.5532 + endloop + endfacet + facet normal -0.184804 -0.61421 0.767199 + outer loop + vertex -602.251 52.9028 15.8861 + vertex -602.177 51.2155 14.5532 + vertex -598.077 51.6851 15.9167 + endloop + endfacet + facet normal -0.185437 -0.612409 0.768484 + outer loop + vertex -598.077 51.6851 15.9167 + vertex -602.177 51.2155 14.5532 + vertex -598.035 49.9979 14.5823 + endloop + endfacet + facet normal -0.227525 -0.759381 0.609567 + outer loop + vertex -602.177 51.2155 14.5532 + vertex -602.31 49.9771 12.961 + vertex -598.035 49.9979 14.5823 + endloop + endfacet + facet normal -0.230759 -0.751556 0.617992 + outer loop + vertex -598.035 49.9979 14.5823 + vertex -602.31 49.9771 12.961 + vertex -598.213 48.7514 13.0001 + endloop + endfacet + facet normal -0.205978 -0.743674 0.636021 + outer loop + vertex -607.276 52.8254 14.6349 + vertex -607.338 51.5157 13.0834 + vertex -606.745 52.5725 14.5113 + endloop + endfacet + facet normal -0.115542 -0.774844 0.621504 + outer loop + vertex -606.745 52.5725 14.5113 + vertex -607.338 51.5157 13.0834 + vertex -606.823 51.3215 12.9369 + endloop + endfacet + facet normal -0.198942 -0.59319 0.780095 + outer loop + vertex -607.194 54.528 15.9504 + vertex -607.276 52.8254 14.6349 + vertex -606.769 54.2367 15.8373 + endloop + endfacet + facet normal -0.114576 -0.620094 0.776116 + outer loop + vertex -606.769 54.2367 15.8373 + vertex -607.276 52.8254 14.6349 + vertex -606.745 52.5725 14.5113 + endloop + endfacet + facet normal -0.190092 -0.613517 0.76646 + outer loop + vertex -606.769 54.2367 15.8373 + vertex -606.745 52.5725 14.5113 + vertex -605.182 53.7452 15.8376 + endloop + endfacet + facet normal -0.187123 -0.616025 0.765179 + outer loop + vertex -605.182 53.7452 15.8376 + vertex -606.745 52.5725 14.5113 + vertex -605.123 52.0781 14.5098 + endloop + endfacet + facet normal -0.230018 -0.756288 0.61247 + outer loop + vertex -606.745 52.5725 14.5113 + vertex -606.823 51.3215 12.9369 + vertex -605.123 52.0781 14.5098 + endloop + endfacet + facet normal -0.218575 -0.765867 0.604709 + outer loop + vertex -605.123 52.0781 14.5098 + vertex -606.823 51.3215 12.9369 + vertex -605.206 50.8455 12.9187 + endloop + endfacet + facet normal 0.120681 0.578686 -0.806572 + outer loop + vertex -606.951 54.8011 16.1827 + vertex -607.145 53.0548 14.9008 + vertex -607.194 54.528 15.9504 + endloop + endfacet + facet normal 0.51122 0.50996 -0.691806 + outer loop + vertex -607.194 54.528 15.9504 + vertex -607.145 53.0548 14.9008 + vertex -607.276 52.8254 14.6349 + endloop + endfacet + facet normal 0.113964 0.723812 -0.68052 + outer loop + vertex -607.145 53.0548 14.9008 + vertex -607.251 51.6439 13.3823 + vertex -607.276 52.8254 14.6349 + endloop + endfacet + facet normal 0.775592 0.466714 -0.425012 + outer loop + vertex -607.276 52.8254 14.6349 + vertex -607.251 51.6439 13.3823 + vertex -607.338 51.5157 13.0834 + endloop + endfacet + facet normal -0.302976 -0.949118 0.0859137 + outer loop + vertex -511.108 24.2663 11.0765 + vertex -511.23 24.1351 9.19569 + vertex -509.304 23.6602 10.7414 + endloop + endfacet + facet normal -0.263634 -0.964082 0.0322968 + outer loop + vertex -509.304 23.6602 10.7414 + vertex -511.23 24.1351 9.19569 + vertex -509.375 23.6204 8.9769 + endloop + endfacet + facet normal -0.27143 -0.887501 0.372382 + outer loop + vertex -510.936 24.9694 12.8772 + vertex -511.108 24.2663 11.0765 + vertex -509.197 24.281 12.5041 + endloop + endfacet + facet normal -0.243536 -0.910096 0.335283 + outer loop + vertex -509.197 24.281 12.5041 + vertex -511.108 24.2663 11.0765 + vertex -509.304 23.6602 10.7414 + endloop + endfacet + facet normal -0.24587 -0.963792 0.103211 + outer loop + vertex -518.746 26.3087 11.2446 + vertex -518.871 26.1365 9.33923 + vertex -514.315 25.1769 11.2316 + endloop + endfacet + facet normal -0.247928 -0.962656 0.108743 + outer loop + vertex -514.315 25.1769 11.2316 + vertex -518.871 26.1365 9.33923 + vertex -514.431 24.9915 9.32649 + endloop + endfacet + facet normal -0.228241 -0.890835 0.392835 + outer loop + vertex -518.582 27.0554 13.0334 + vertex -518.746 26.3087 11.2446 + vertex -514.135 25.9132 13.027 + endloop + endfacet + facet normal -0.226918 -0.89287 0.388961 + outer loop + vertex -514.135 25.9132 13.027 + vertex -518.746 26.3087 11.2446 + vertex -514.315 25.1769 11.2316 + endloop + endfacet + facet normal -0.243947 -0.888419 0.388846 + outer loop + vertex -514.135 25.9132 13.027 + vertex -514.315 25.1769 11.2316 + vertex -510.936 24.9694 12.8772 + endloop + endfacet + facet normal -0.236698 -0.897192 0.372855 + outer loop + vertex -510.936 24.9694 12.8772 + vertex -514.315 25.1769 11.2316 + vertex -511.108 24.2663 11.0765 + endloop + endfacet + facet normal -0.26659 -0.957583 0.109385 + outer loop + vertex -514.315 25.1769 11.2316 + vertex -514.431 24.9915 9.32649 + vertex -511.108 24.2663 11.0765 + endloop + endfacet + facet normal -0.254379 -0.963471 0.0837562 + outer loop + vertex -511.108 24.2663 11.0765 + vertex -514.431 24.9915 9.32649 + vertex -511.23 24.1351 9.19569 + endloop + endfacet + facet normal -0.244295 -0.96435 0.101726 + outer loop + vertex -529.797 29.0697 11.1756 + vertex -529.885 28.8907 9.26774 + vertex -524.041 27.6147 11.2052 + endloop + endfacet + facet normal -0.243272 -0.964971 0.0982338 + outer loop + vertex -524.041 27.6147 11.2052 + vertex -529.885 28.8907 9.26774 + vertex -524.151 27.4482 9.29841 + endloop + endfacet + facet normal -0.22769 -0.890534 0.393835 + outer loop + vertex -529.677 29.8331 12.9712 + vertex -529.797 29.0697 11.1756 + vertex -523.903 28.368 12.9966 + endloop + endfacet + facet normal -0.227318 -0.89129 0.392338 + outer loop + vertex -523.903 28.368 12.9966 + vertex -529.797 29.0697 11.1756 + vertex -524.041 27.6147 11.2052 + endloop + endfacet + facet normal -0.222842 -0.892371 0.392448 + outer loop + vertex -523.903 28.368 12.9966 + vertex -524.041 27.6147 11.2052 + vertex -518.582 27.0554 13.0334 + endloop + endfacet + facet normal -0.222969 -0.892142 0.392896 + outer loop + vertex -518.582 27.0554 13.0334 + vertex -524.041 27.6147 11.2052 + vertex -518.746 26.3087 11.2446 + endloop + endfacet + facet normal -0.239004 -0.966052 0.0980829 + outer loop + vertex -524.041 27.6147 11.2052 + vertex -524.151 27.4482 9.29841 + vertex -518.746 26.3087 11.2446 + endloop + endfacet + facet normal -0.24058 -0.96515 0.102988 + outer loop + vertex -518.746 26.3087 11.2446 + vertex -524.151 27.4482 9.29841 + vertex -518.871 26.1365 9.33923 + endloop + endfacet + facet normal -0.25505 -0.960937 0.10747 + outer loop + vertex -541.554 32.1531 11.1802 + vertex -541.635 31.9612 9.27264 + vertex -535.68 30.5931 11.1728 + endloop + endfacet + facet normal -0.252485 -0.962601 0.0982333 + outer loop + vertex -535.68 30.5931 11.1728 + vertex -541.635 31.9612 9.27264 + vertex -535.76 30.4193 9.26428 + endloop + endfacet + facet normal -0.235773 -0.889749 0.390842 + outer loop + vertex -541.446 32.9144 12.9785 + vertex -541.554 32.1531 11.1802 + vertex -535.57 31.355 12.9731 + endloop + endfacet + facet normal -0.235784 -0.889726 0.390888 + outer loop + vertex -535.57 31.355 12.9731 + vertex -541.554 32.1531 11.1802 + vertex -535.68 30.5931 11.1728 + endloop + endfacet + facet normal -0.229999 -0.891132 0.391131 + outer loop + vertex -535.57 31.355 12.9731 + vertex -535.68 30.5931 11.1728 + vertex -529.677 29.8331 12.9712 + endloop + endfacet + facet normal -0.230613 -0.889828 0.39373 + outer loop + vertex -529.677 29.8331 12.9712 + vertex -535.68 30.5931 11.1728 + vertex -529.797 29.0697 11.1756 + endloop + endfacet + facet normal -0.249519 -0.96338 0.0981798 + outer loop + vertex -535.68 30.5931 11.1728 + vertex -535.76 30.4193 9.26428 + vertex -529.797 29.0697 11.1756 + endloop + endfacet + facet normal -0.250552 -0.962729 0.101863 + outer loop + vertex -529.797 29.0697 11.1756 + vertex -535.76 30.4193 9.26428 + vertex -529.885 28.8907 9.26774 + endloop + endfacet + facet normal -0.259074 -0.960368 0.102824 + outer loop + vertex -553.244 35.2838 11.1889 + vertex -553.326 35.1019 9.2829 + vertex -547.404 33.7082 11.1884 + endloop + endfacet + facet normal -0.258983 -0.960429 0.102494 + outer loop + vertex -547.404 33.7082 11.1884 + vertex -553.326 35.1019 9.2829 + vertex -547.486 33.5267 9.27951 + endloop + endfacet + facet normal -0.238418 -0.888755 0.391499 + outer loop + vertex -553.123 36.0435 12.9868 + vertex -553.244 35.2838 11.1889 + vertex -547.29 34.4771 12.9833 + endloop + endfacet + facet normal -0.239244 -0.886961 0.395048 + outer loop + vertex -547.29 34.4771 12.9833 + vertex -553.244 35.2838 11.1889 + vertex -547.404 33.7082 11.1884 + endloop + endfacet + facet normal -0.237004 -0.887519 0.395145 + outer loop + vertex -547.29 34.4771 12.9833 + vertex -547.404 33.7082 11.1884 + vertex -541.446 32.9144 12.9785 + endloop + endfacet + facet normal -0.235998 -0.889694 0.390832 + outer loop + vertex -541.446 32.9144 12.9785 + vertex -547.404 33.7082 11.1884 + vertex -541.554 32.1531 11.1802 + endloop + endfacet + facet normal -0.255461 -0.961378 0.102433 + outer loop + vertex -547.404 33.7082 11.1884 + vertex -547.486 33.5267 9.27951 + vertex -541.554 32.1531 11.1802 + endloop + endfacet + facet normal -0.256869 -0.960449 0.107498 + outer loop + vertex -541.554 32.1531 11.1802 + vertex -547.486 33.5267 9.27951 + vertex -541.635 31.9612 9.27264 + endloop + endfacet + facet normal -0.261606 -0.958669 0.111873 + outer loop + vertex -564.909 38.463 11.1885 + vertex -564.989 38.2621 9.28119 + vertex -559.082 36.8727 11.1876 + endloop + endfacet + facet normal -0.261265 -0.958905 0.110646 + outer loop + vertex -559.082 36.8727 11.1876 + vertex -564.989 38.2621 9.28119 + vertex -559.165 36.6755 9.28134 + endloop + endfacet + facet normal -0.242348 -0.885944 0.395437 + outer loop + vertex -564.78 39.2297 12.9854 + vertex -564.909 38.463 11.1885 + vertex -558.956 37.636 12.9842 + endloop + endfacet + facet normal -0.241952 -0.886814 0.393726 + outer loop + vertex -558.956 37.636 12.9842 + vertex -564.909 38.463 11.1885 + vertex -559.082 36.8727 11.1876 + endloop + endfacet + facet normal -0.242294 -0.886727 0.393712 + outer loop + vertex -558.956 37.636 12.9842 + vertex -559.082 36.8727 11.1876 + vertex -553.123 36.0435 12.9868 + endloop + endfacet + facet normal -0.241751 -0.887913 0.391366 + outer loop + vertex -553.123 36.0435 12.9868 + vertex -559.082 36.8727 11.1876 + vertex -553.244 35.2838 11.1889 + endloop + endfacet + facet normal -0.261025 -0.95897 0.110642 + outer loop + vertex -559.082 36.8727 11.1876 + vertex -559.165 36.6755 9.28134 + vertex -553.244 35.2838 11.1889 + endloop + endfacet + facet normal -0.258848 -0.96043 0.10282 + outer loop + vertex -553.244 35.2838 11.1889 + vertex -559.165 36.6755 9.28134 + vertex -553.326 35.1019 9.2829 + endloop + endfacet + facet normal -0.269324 -0.957294 0.105131 + outer loop + vertex -576.481 41.6951 11.1837 + vertex -576.555 41.5064 9.27687 + vertex -570.711 40.072 11.1864 + endloop + endfacet + facet normal -0.270109 -0.956761 0.107932 + outer loop + vertex -570.711 40.072 11.1864 + vertex -576.555 41.5064 9.27687 + vertex -570.785 39.8778 9.27873 + endloop + endfacet + facet normal -0.24732 -0.885625 0.393066 + outer loop + vertex -576.351 42.4583 12.985 + vertex -576.481 41.6951 11.1837 + vertex -570.581 40.8457 12.9822 + endloop + endfacet + facet normal -0.248539 -0.882922 0.398342 + outer loop + vertex -570.581 40.8457 12.9822 + vertex -576.481 41.6951 11.1837 + vertex -570.711 40.072 11.1864 + endloop + endfacet + facet normal -0.246327 -0.883502 0.398432 + outer loop + vertex -570.581 40.8457 12.9822 + vertex -570.711 40.072 11.1864 + vertex -564.78 39.2297 12.9854 + endloop + endfacet + facet normal -0.245608 -0.885102 0.395312 + outer loop + vertex -564.78 39.2297 12.9854 + vertex -570.711 40.072 11.1864 + vertex -564.909 38.463 11.1885 + endloop + endfacet + facet normal -0.265719 -0.957995 0.107887 + outer loop + vertex -570.711 40.072 11.1864 + vertex -570.785 39.8778 9.27873 + vertex -564.909 38.463 11.1885 + endloop + endfacet + facet normal -0.266848 -0.957216 0.111938 + outer loop + vertex -564.909 38.463 11.1885 + vertex -570.785 39.8778 9.27873 + vertex -564.989 38.2621 9.28119 + endloop + endfacet + facet normal -0.273333 -0.956097 0.105678 + outer loop + vertex -587.9 44.9414 11.1964 + vertex -587.986 44.7548 9.28642 + vertex -582.222 43.3172 11.1871 + endloop + endfacet + facet normal -0.273316 -0.956108 0.105618 + outer loop + vertex -582.222 43.3172 11.1871 + vertex -587.986 44.7548 9.28642 + vertex -582.301 43.1287 9.27679 + endloop + endfacet + facet normal -0.251129 -0.883648 0.395096 + outer loop + vertex -587.76 45.7075 12.999 + vertex -587.9 44.9414 11.1964 + vertex -582.088 44.0899 12.9864 + endloop + endfacet + facet normal -0.251743 -0.882287 0.397738 + outer loop + vertex -582.088 44.0899 12.9864 + vertex -587.9 44.9414 11.1964 + vertex -582.222 43.3172 11.1871 + endloop + endfacet + facet normal -0.250912 -0.882508 0.397772 + outer loop + vertex -582.088 44.0899 12.9864 + vertex -582.222 43.3172 11.1871 + vertex -576.351 42.4583 12.985 + endloop + endfacet + facet normal -0.249802 -0.884972 0.392968 + outer loop + vertex -576.351 42.4583 12.985 + vertex -582.222 43.3172 11.1871 + vertex -576.481 41.6951 11.1837 + endloop + endfacet + facet normal -0.270313 -0.956966 0.105579 + outer loop + vertex -582.222 43.3172 11.1871 + vertex -582.301 43.1287 9.27679 + vertex -576.481 41.6951 11.1837 + endloop + endfacet + facet normal -0.27019 -0.957049 0.10514 + outer loop + vertex -576.481 41.6951 11.1837 + vertex -582.301 43.1287 9.27679 + vertex -576.555 41.5064 9.27687 + endloop + endfacet + facet normal -0.280791 -0.954103 0.104132 + outer loop + vertex -598.374 47.9894 11.1983 + vertex -598.456 47.8052 9.28874 + vertex -593.381 46.521 11.2069 + endloop + endfacet + facet normal -0.28273 -0.952861 0.110093 + outer loop + vertex -593.381 46.521 11.2069 + vertex -598.456 47.8052 9.28874 + vertex -593.476 46.3284 9.29679 + endloop + endfacet + facet normal -0.257936 -0.881397 0.395738 + outer loop + vertex -598.213 48.7514 13.0001 + vertex -598.374 47.9894 11.1983 + vertex -593.223 47.2936 13.0053 + endloop + endfacet + facet normal -0.259203 -0.87897 0.400282 + outer loop + vertex -593.223 47.2936 13.0053 + vertex -598.374 47.9894 11.1983 + vertex -593.381 46.521 11.2069 + endloop + endfacet + facet normal -0.255037 -0.880127 0.400415 + outer loop + vertex -593.223 47.2936 13.0053 + vertex -593.381 46.521 11.2069 + vertex -587.76 45.7075 12.999 + endloop + endfacet + facet normal -0.253719 -0.88295 0.395002 + outer loop + vertex -587.76 45.7075 12.999 + vertex -593.381 46.521 11.2069 + vertex -587.9 44.9414 11.1964 + endloop + endfacet + facet normal -0.275067 -0.955118 0.10994 + outer loop + vertex -593.381 46.521 11.2069 + vertex -593.476 46.3284 9.29679 + vertex -587.9 44.9414 11.1964 + endloop + endfacet + facet normal -0.273826 -0.955955 0.105686 + outer loop + vertex -587.9 44.9414 11.1964 + vertex -593.476 46.3284 9.29679 + vertex -587.986 44.7548 9.28642 + endloop + endfacet + facet normal -0.293432 -0.952298 0.0838202 + outer loop + vertex -605.346 50.1202 11.1105 + vertex -605.406 49.9698 9.19441 + vertex -602.46 49.2346 11.1548 + endloop + endfacet + facet normal -0.304485 -0.946995 0.102418 + outer loop + vertex -602.46 49.2346 11.1548 + vertex -605.406 49.9698 9.19441 + vertex -602.555 49.0584 9.24369 + endloop + endfacet + facet normal -0.271131 -0.8859 0.376389 + outer loop + vertex -605.206 50.8455 12.9187 + vertex -605.346 50.1202 11.1105 + vertex -602.31 49.9771 12.961 + endloop + endfacet + facet normal -0.27609 -0.880683 0.384931 + outer loop + vertex -602.31 49.9771 12.961 + vertex -605.346 50.1202 11.1105 + vertex -602.46 49.2346 11.1548 + endloop + endfacet + facet normal -0.267886 -0.88308 0.385235 + outer loop + vertex -602.31 49.9771 12.961 + vertex -602.46 49.2346 11.1548 + vertex -598.213 48.7514 13.0001 + endloop + endfacet + facet normal -0.271621 -0.877474 0.395298 + outer loop + vertex -598.213 48.7514 13.0001 + vertex -602.46 49.2346 11.1548 + vertex -598.374 47.9894 11.1983 + endloop + endfacet + facet normal -0.290985 -0.95126 0.102141 + outer loop + vertex -602.46 49.2346 11.1548 + vertex -602.555 49.0584 9.24369 + vertex -598.374 47.9894 11.1983 + endloop + endfacet + facet normal -0.29186 -0.950759 0.104287 + outer loop + vertex -598.374 47.9894 11.1983 + vertex -602.555 49.0584 9.24369 + vertex -598.456 47.8052 9.28874 + endloop + endfacet + facet normal -0.20655 -0.971966 0.112334 + outer loop + vertex -607.431 50.7201 11.3108 + vertex -607.481 50.5115 9.41346 + vertex -606.92 50.5916 11.1375 + endloop + endfacet + facet normal -0.10973 -0.990596 0.0817213 + outer loop + vertex -606.92 50.5916 11.1375 + vertex -607.481 50.5115 9.41346 + vertex -606.974 50.4397 9.22397 + endloop + endfacet + facet normal -0.217929 -0.886088 0.409091 + outer loop + vertex -607.338 51.5157 13.0834 + vertex -607.431 50.7201 11.3108 + vertex -606.823 51.3215 12.9369 + endloop + endfacet + facet normal -0.103051 -0.919791 0.378635 + outer loop + vertex -606.823 51.3215 12.9369 + vertex -607.431 50.7201 11.3108 + vertex -606.92 50.5916 11.1375 + endloop + endfacet + facet normal -0.257822 -0.89042 0.375075 + outer loop + vertex -606.823 51.3215 12.9369 + vertex -606.92 50.5916 11.1375 + vertex -605.206 50.8455 12.9187 + endloop + endfacet + facet normal -0.259808 -0.889113 0.3768 + outer loop + vertex -605.206 50.8455 12.9187 + vertex -606.92 50.5916 11.1375 + vertex -605.346 50.1202 11.1105 + endloop + endfacet + facet normal -0.284578 -0.95498 0.0838414 + outer loop + vertex -606.92 50.5916 11.1375 + vertex -606.974 50.4397 9.22397 + vertex -605.346 50.1202 11.1105 + endloop + endfacet + facet normal -0.284486 -0.955014 0.0837561 + outer loop + vertex -605.346 50.1202 11.1105 + vertex -606.974 50.4397 9.22397 + vertex -605.406 49.9698 9.19441 + endloop + endfacet + facet normal 0.343754 0.822846 -0.452501 + outer loop + vertex -607.251 51.6439 13.3823 + vertex -607.336 50.7235 11.6448 + vertex -607.338 51.5157 13.0834 + endloop + endfacet + facet normal 0.855727 0.453881 -0.248441 + outer loop + vertex -607.338 51.5157 13.0834 + vertex -607.336 50.7235 11.6448 + vertex -607.431 50.7201 11.3108 + endloop + endfacet + facet normal 0.536198 0.828539 -0.16129 + outer loop + vertex -607.336 50.7235 11.6448 + vertex -607.396 50.397 9.76656 + vertex -607.431 50.7201 11.3108 + endloop + endfacet + facet normal 0.894616 0.440978 -0.0721186 + outer loop + vertex -607.431 50.7201 11.3108 + vertex -607.396 50.397 9.76656 + vertex -607.481 50.5115 9.41346 + endloop + endfacet + facet normal -0.224226 -0.805107 -0.549113 + outer loop + vertex -511.174 24.5974 7.36634 + vertex -510.811 25.6377 5.69289 + vertex -509.284 24.1625 7.23215 + endloop + endfacet + facet normal -0.195163 -0.797595 -0.570748 + outer loop + vertex -509.284 24.1625 7.23215 + vertex -510.811 25.6377 5.69289 + vertex -508.961 25.2557 5.59386 + endloop + endfacet + facet normal -0.285805 -0.926956 -0.243041 + outer loop + vertex -511.23 24.1351 9.19569 + vertex -511.174 24.5974 7.36634 + vertex -509.375 23.6204 8.9769 + endloop + endfacet + facet normal -0.234077 -0.924908 -0.299587 + outer loop + vertex -509.375 23.6204 8.9769 + vertex -511.174 24.5974 7.36634 + vertex -509.284 24.1625 7.23215 + endloop + endfacet + facet normal -0.211211 -0.827805 -0.51974 + outer loop + vertex -518.88 26.5561 7.46132 + vertex -518.594 27.5505 5.76157 + vertex -514.428 25.4235 7.45613 + endloop + endfacet + facet normal -0.208032 -0.8255 -0.524663 + outer loop + vertex -514.428 25.4235 7.45613 + vertex -518.594 27.5505 5.76157 + vertex -514.093 26.4175 5.75929 + endloop + endfacet + facet normal -0.244679 -0.946507 -0.210372 + outer loop + vertex -518.871 26.1365 9.33923 + vertex -518.88 26.5561 7.46132 + vertex -514.431 24.9915 9.32649 + endloop + endfacet + facet normal -0.240826 -0.945586 -0.218791 + outer loop + vertex -514.431 24.9915 9.32649 + vertex -518.88 26.5561 7.46132 + vertex -514.428 25.4235 7.45613 + endloop + endfacet + facet normal -0.260575 -0.940595 -0.217673 + outer loop + vertex -514.431 24.9915 9.32649 + vertex -514.428 25.4235 7.45613 + vertex -511.23 24.1351 9.19569 + endloop + endfacet + facet normal -0.244937 -0.938171 -0.244625 + outer loop + vertex -511.23 24.1351 9.19569 + vertex -514.428 25.4235 7.45613 + vertex -511.174 24.5974 7.36634 + endloop + endfacet + facet normal -0.223 -0.821276 -0.525144 + outer loop + vertex -514.428 25.4235 7.45613 + vertex -514.093 26.4175 5.75929 + vertex -511.174 24.5974 7.36634 + endloop + endfacet + facet normal -0.203821 -0.811022 -0.548362 + outer loop + vertex -511.174 24.5974 7.36634 + vertex -514.093 26.4175 5.75929 + vertex -510.811 25.6377 5.69289 + endloop + endfacet + facet normal -0.206796 -0.820594 -0.532786 + outer loop + vertex -529.918 29.3668 7.39681 + vertex -529.722 30.4189 5.70051 + vertex -524.184 27.9039 7.42448 + endloop + endfacet + facet normal -0.208834 -0.822506 -0.52903 + outer loop + vertex -524.184 27.9039 7.42448 + vertex -529.722 30.4189 5.70051 + vertex -523.951 28.9346 5.72989 + endloop + endfacet + facet normal -0.235895 -0.942744 -0.235769 + outer loop + vertex -529.885 28.8907 9.26774 + vertex -529.918 29.3668 7.39681 + vertex -524.151 27.4482 9.29841 + endloop + endfacet + facet normal -0.23984 -0.944292 -0.225365 + outer loop + vertex -524.151 27.4482 9.29841 + vertex -529.918 29.3668 7.39681 + vertex -524.184 27.9039 7.42448 + endloop + endfacet + facet normal -0.233237 -0.945827 -0.225856 + outer loop + vertex -524.151 27.4482 9.29841 + vertex -524.184 27.9039 7.42448 + vertex -518.871 26.1365 9.33923 + endloop + endfacet + facet normal -0.239359 -0.947797 -0.210685 + outer loop + vertex -518.871 26.1365 9.33923 + vertex -524.184 27.9039 7.42448 + vertex -518.88 26.5561 7.46132 + endloop + endfacet + facet normal -0.20552 -0.823316 -0.529067 + outer loop + vertex -524.184 27.9039 7.42448 + vertex -523.951 28.9346 5.72989 + vertex -518.88 26.5561 7.46132 + endloop + endfacet + facet normal -0.210855 -0.827899 -0.519735 + outer loop + vertex -518.88 26.5561 7.46132 + vertex -523.951 28.9346 5.72989 + vertex -518.594 27.5505 5.76157 + endloop + endfacet + facet normal -0.214487 -0.817484 -0.534524 + outer loop + vertex -541.638 32.4154 7.40227 + vertex -541.439 33.4714 5.70766 + vertex -535.778 30.8835 7.39395 + endloop + endfacet + facet normal -0.213135 -0.816177 -0.537055 + outer loop + vertex -535.778 30.8835 7.39395 + vertex -541.439 33.4714 5.70766 + vertex -535.592 31.9492 5.70053 + endloop + endfacet + facet normal -0.247441 -0.941609 -0.228355 + outer loop + vertex -541.635 31.9612 9.27264 + vertex -541.638 32.4154 7.40227 + vertex -535.76 30.4193 9.26428 + endloop + endfacet + facet normal -0.246398 -0.941189 -0.231195 + outer loop + vertex -535.76 30.4193 9.26428 + vertex -541.638 32.4154 7.40227 + vertex -535.778 30.8835 7.39395 + endloop + endfacet + facet normal -0.244849 -0.941566 -0.231304 + outer loop + vertex -535.76 30.4193 9.26428 + vertex -535.778 30.8835 7.39395 + vertex -529.885 28.8907 9.26774 + endloop + endfacet + facet normal -0.243415 -0.940976 -0.235188 + outer loop + vertex -529.885 28.8907 9.26774 + vertex -535.778 30.8835 7.39395 + vertex -529.918 29.3668 7.39681 + endloop + endfacet + facet normal -0.211093 -0.816657 -0.537133 + outer loop + vertex -535.778 30.8835 7.39395 + vertex -535.592 31.9492 5.70053 + vertex -529.918 29.3668 7.39681 + endloop + endfacet + facet normal -0.213524 -0.819006 -0.532576 + outer loop + vertex -529.918 29.3668 7.39681 + vertex -535.592 31.9492 5.70053 + vertex -529.722 30.4189 5.70051 + endloop + endfacet + facet normal -0.217162 -0.814946 -0.537312 + outer loop + vertex -553.304 35.5271 7.41258 + vertex -553.046 36.5702 5.72618 + vertex -547.472 33.9731 7.41222 + endloop + endfacet + facet normal -0.220448 -0.818047 -0.531227 + outer loop + vertex -547.472 33.9731 7.41222 + vertex -553.046 36.5702 5.72618 + vertex -547.246 35.012 5.7187 + endloop + endfacet + facet normal -0.254309 -0.942413 -0.217219 + outer loop + vertex -553.326 35.1019 9.2829 + vertex -553.304 35.5271 7.41258 + vertex -547.486 33.5267 9.27951 + endloop + endfacet + facet normal -0.250752 -0.941088 -0.226887 + outer loop + vertex -547.486 33.5267 9.27951 + vertex -553.304 35.5271 7.41258 + vertex -547.472 33.9731 7.41222 + endloop + endfacet + facet normal -0.251996 -0.940771 -0.226821 + outer loop + vertex -547.486 33.5267 9.27951 + vertex -547.472 33.9731 7.41222 + vertex -541.635 31.9612 9.27264 + endloop + endfacet + facet normal -0.251524 -0.940588 -0.228102 + outer loop + vertex -541.635 31.9612 9.27264 + vertex -547.472 33.9731 7.41222 + vertex -541.638 32.4154 7.40227 + endloop + endfacet + facet normal -0.219395 -0.818315 -0.531251 + outer loop + vertex -547.472 33.9731 7.41222 + vertex -547.246 35.012 5.7187 + vertex -541.638 32.4154 7.40227 + endloop + endfacet + facet normal -0.2177 -0.816705 -0.534415 + outer loop + vertex -541.638 32.4154 7.40227 + vertex -547.246 35.012 5.7187 + vertex -541.439 33.4714 5.70766 + endloop + endfacet + facet normal -0.223539 -0.813802 -0.53643 + outer loop + vertex -564.945 38.7022 7.41245 + vertex -564.679 39.7419 5.72392 + vertex -559.13 37.1044 7.41289 + endloop + endfacet + facet normal -0.225405 -0.815535 -0.533007 + outer loop + vertex -559.13 37.1044 7.41289 + vertex -564.679 39.7419 5.72392 + vertex -558.863 38.1361 5.72149 + endloop + endfacet + facet normal -0.255997 -0.939598 -0.227202 + outer loop + vertex -564.989 38.2621 9.28119 + vertex -564.945 38.7022 7.41245 + vertex -559.165 36.6755 9.28134 + endloop + endfacet + facet normal -0.258363 -0.94047 -0.220829 + outer loop + vertex -559.165 36.6755 9.28134 + vertex -564.945 38.7022 7.41245 + vertex -559.13 37.1044 7.41289 + endloop + endfacet + facet normal -0.253712 -0.94169 -0.221021 + outer loop + vertex -559.165 36.6755 9.28134 + vertex -559.13 37.1044 7.41289 + vertex -553.326 35.1019 9.2829 + endloop + endfacet + facet normal -0.255125 -0.942201 -0.217181 + outer loop + vertex -553.326 35.1019 9.2829 + vertex -559.13 37.1044 7.41289 + vertex -553.304 35.5271 7.41258 + endloop + endfacet + facet normal -0.221155 -0.816679 -0.533034 + outer loop + vertex -559.13 37.1044 7.41289 + vertex -558.863 38.1361 5.72149 + vertex -553.304 35.5271 7.41258 + endloop + endfacet + facet normal -0.218839 -0.814507 -0.537297 + outer loop + vertex -553.304 35.5271 7.41258 + vertex -558.863 38.1361 5.72149 + vertex -553.046 36.5702 5.72618 + endloop + endfacet + facet normal -0.230446 -0.813194 -0.534425 + outer loop + vertex -576.535 41.9566 7.40624 + vertex -576.34 43.0173 5.70824 + vertex -570.749 40.315 7.40902 + endloop + endfacet + facet normal -0.228591 -0.811486 -0.537808 + outer loop + vertex -570.749 40.315 7.40902 + vertex -576.34 43.0173 5.70824 + vertex -570.507 41.3678 5.71755 + endloop + endfacet + facet normal -0.264421 -0.936995 -0.228304 + outer loop + vertex -576.555 41.5064 9.27687 + vertex -576.535 41.9566 7.40624 + vertex -570.785 39.8778 9.27873 + endloop + endfacet + facet normal -0.265865 -0.937517 -0.224449 + outer loop + vertex -570.785 39.8778 9.27873 + vertex -576.535 41.9566 7.40624 + vertex -570.749 40.315 7.40902 + endloop + endfacet + facet normal -0.261541 -0.938688 -0.224638 + outer loop + vertex -570.785 39.8778 9.27873 + vertex -570.749 40.315 7.40902 + vertex -564.989 38.2621 9.28119 + endloop + endfacet + facet normal -0.260651 -0.938362 -0.227019 + outer loop + vertex -564.989 38.2621 9.28119 + vertex -570.749 40.315 7.40902 + vertex -564.945 38.7022 7.41245 + endloop + endfacet + facet normal -0.225438 -0.812322 -0.537876 + outer loop + vertex -570.749 40.315 7.40902 + vertex -570.507 41.3678 5.71755 + vertex -564.945 38.7022 7.41245 + endloop + endfacet + facet normal -0.226245 -0.813069 -0.536406 + outer loop + vertex -564.945 38.7022 7.41245 + vertex -570.507 41.3678 5.71755 + vertex -564.679 39.7419 5.72392 + endloop + endfacet + facet normal -0.231031 -0.809758 -0.539367 + outer loop + vertex -588.021 45.2216 7.41005 + vertex -587.916 46.3244 5.7093 + vertex -582.305 43.5949 7.40409 + endloop + endfacet + facet normal -0.229448 -0.808289 -0.542239 + outer loop + vertex -582.305 43.5949 7.40409 + vertex -587.916 46.3244 5.7093 + vertex -582.154 44.6898 5.70816 + endloop + endfacet + facet normal -0.268141 -0.936039 -0.227886 + outer loop + vertex -587.986 44.7548 9.28642 + vertex -588.021 45.2216 7.41005 + vertex -582.301 43.1287 9.27679 + endloop + endfacet + facet normal -0.266479 -0.935429 -0.232295 + outer loop + vertex -582.301 43.1287 9.27679 + vertex -588.021 45.2216 7.41005 + vertex -582.305 43.5949 7.40409 + endloop + endfacet + facet normal -0.264249 -0.936024 -0.232448 + outer loop + vertex -582.301 43.1287 9.27679 + vertex -582.305 43.5949 7.40409 + vertex -576.555 41.5064 9.27687 + endloop + endfacet + facet normal -0.265838 -0.936612 -0.228227 + outer loop + vertex -576.555 41.5064 9.27687 + vertex -582.305 43.5949 7.40409 + vertex -576.535 41.9566 7.40624 + endloop + endfacet + facet normal -0.229297 -0.808325 -0.542249 + outer loop + vertex -582.305 43.5949 7.40409 + vertex -582.154 44.6898 5.70816 + vertex -576.535 41.9566 7.40624 + endloop + endfacet + facet normal -0.233672 -0.812368 -0.53428 + outer loop + vertex -576.535 41.9566 7.40624 + vertex -582.154 44.6898 5.70816 + vertex -576.34 43.0173 5.70824 + endloop + endfacet + facet normal -0.234631 -0.807228 -0.5416 + outer loop + vertex -598.548 48.2705 7.41622 + vertex -598.509 49.3961 5.72156 + vertex -593.529 46.8075 7.42242 + endloop + endfacet + facet normal -0.235638 -0.808061 -0.539919 + outer loop + vertex -593.529 46.8075 7.42242 + vertex -598.509 49.3961 5.72156 + vertex -593.454 47.9201 5.72443 + endloop + endfacet + facet normal -0.277081 -0.935604 -0.218797 + outer loop + vertex -598.456 47.8052 9.28874 + vertex -598.548 48.2705 7.41622 + vertex -593.476 46.3284 9.29679 + endloop + endfacet + facet normal -0.272015 -0.934162 -0.230972 + outer loop + vertex -593.476 46.3284 9.29679 + vertex -598.548 48.2705 7.41622 + vertex -593.529 46.8075 7.42242 + endloop + endfacet + facet normal -0.268484 -0.935099 -0.231313 + outer loop + vertex -593.476 46.3284 9.29679 + vertex -593.529 46.8075 7.42242 + vertex -587.986 44.7548 9.28642 + endloop + endfacet + facet normal -0.269864 -0.935579 -0.227739 + outer loop + vertex -587.986 44.7548 9.28642 + vertex -593.529 46.8075 7.42242 + vertex -588.021 45.2216 7.41005 + endloop + endfacet + facet normal -0.23396 -0.808434 -0.54009 + outer loop + vertex -593.529 46.8075 7.42242 + vertex -593.454 47.9201 5.72443 + vertex -588.021 45.2216 7.41005 + endloop + endfacet + facet normal -0.234537 -0.808953 -0.539062 + outer loop + vertex -588.021 45.2216 7.41005 + vertex -593.454 47.9201 5.72443 + vertex -587.916 46.3244 5.7093 + endloop + endfacet + facet normal -0.253342 -0.805476 -0.535749 + outer loop + vertex -605.432 50.4519 7.32931 + vertex -605.442 51.5733 5.64803 + vertex -602.621 49.5353 7.37777 + endloop + endfacet + facet normal -0.248118 -0.803196 -0.541584 + outer loop + vertex -602.621 49.5353 7.37777 + vertex -605.442 51.5733 5.64803 + vertex -602.608 50.6659 5.69524 + endloop + endfacet + facet normal -0.292231 -0.926925 -0.235395 + outer loop + vertex -605.406 49.9698 9.19441 + vertex -605.432 50.4519 7.32931 + vertex -602.555 49.0584 9.24369 + endloop + endfacet + facet normal -0.298359 -0.927215 -0.226392 + outer loop + vertex -602.555 49.0584 9.24369 + vertex -605.432 50.4519 7.32931 + vertex -602.621 49.5353 7.37777 + endloop + endfacet + facet normal -0.282402 -0.931777 -0.228125 + outer loop + vertex -602.555 49.0584 9.24369 + vertex -602.621 49.5353 7.37777 + vertex -598.456 47.8052 9.28874 + endloop + endfacet + facet normal -0.287636 -0.932703 -0.217556 + outer loop + vertex -598.456 47.8052 9.28874 + vertex -602.621 49.5353 7.37777 + vertex -598.548 48.2705 7.41622 + endloop + endfacet + facet normal -0.244584 -0.803954 -0.542067 + outer loop + vertex -602.621 49.5353 7.37777 + vertex -602.608 50.6659 5.69524 + vertex -598.548 48.2705 7.41622 + endloop + endfacet + facet normal -0.245854 -0.804795 -0.540242 + outer loop + vertex -598.548 48.2705 7.41622 + vertex -602.608 50.6659 5.69524 + vertex -598.509 49.3961 5.72156 + endloop + endfacet + facet normal -0.20498 -0.84187 -0.499238 + outer loop + vertex -607.471 50.9123 7.55079 + vertex -607.407 51.894 5.86925 + vertex -606.97 50.9074 7.35335 + endloop + endfacet + facet normal -0.059053 -0.839265 -0.540507 + outer loop + vertex -606.97 50.9074 7.35335 + vertex -607.407 51.894 5.86925 + vertex -606.927 51.9855 5.67461 + endloop + endfacet + facet normal -0.212596 -0.955038 -0.206654 + outer loop + vertex -607.481 50.5115 9.41346 + vertex -607.471 50.9123 7.55079 + vertex -606.974 50.4397 9.22397 + endloop + endfacet + facet normal -0.104583 -0.964761 -0.24145 + outer loop + vertex -606.974 50.4397 9.22397 + vertex -607.471 50.9123 7.55079 + vertex -606.97 50.9074 7.35335 + endloop + endfacet + facet normal -0.283059 -0.930304 -0.233266 + outer loop + vertex -606.974 50.4397 9.22397 + vertex -606.97 50.9074 7.35335 + vertex -605.406 49.9698 9.19441 + endloop + endfacet + facet normal -0.279391 -0.930589 -0.236527 + outer loop + vertex -605.406 49.9698 9.19441 + vertex -606.97 50.9074 7.35335 + vertex -605.432 50.4519 7.32931 + endloop + endfacet + facet normal -0.24883 -0.81206 -0.527865 + outer loop + vertex -606.97 50.9074 7.35335 + vertex -606.927 51.9855 5.67461 + vertex -605.432 50.4519 7.32931 + endloop + endfacet + facet normal -0.234353 -0.809397 -0.538474 + outer loop + vertex -605.432 50.4519 7.32931 + vertex -606.927 51.9855 5.67461 + vertex -605.442 51.5733 5.64803 + endloop + endfacet + facet normal 0.591406 0.797911 0.11652 + outer loop + vertex -607.396 50.397 9.76656 + vertex -607.398 50.6649 7.93974 + vertex -607.481 50.5115 9.41346 + endloop + endfacet + facet normal 0.90411 0.416717 0.0945042 + outer loop + vertex -607.481 50.5115 9.41346 + vertex -607.398 50.6649 7.93974 + vertex -607.471 50.9123 7.55079 + endloop + endfacet + facet normal 0.480814 0.778105 0.404192 + outer loop + vertex -607.398 50.6649 7.93974 + vertex -607.335 51.4788 6.29862 + vertex -607.471 50.9123 7.55079 + endloop + endfacet + facet normal 0.841409 0.452217 0.295855 + outer loop + vertex -607.471 50.9123 7.55079 + vertex -607.335 51.4788 6.29862 + vertex -607.407 51.894 5.86925 + endloop + endfacet + facet normal -0.140464 -0.456708 -0.878458 + outer loop + vertex -510.25 27.2106 4.27527 + vertex -509.668 29.0265 3.23818 + vertex -508.568 26.7236 4.25943 + endloop + endfacet + facet normal -0.254996 -0.491231 -0.832868 + outer loop + vertex -508.568 26.7236 4.25943 + vertex -509.668 29.0265 3.23818 + vertex -508.421 27.9357 3.4995 + endloop + endfacet + facet normal -0.169875 -0.62564 -0.761391 + outer loop + vertex -510.811 25.6377 5.69289 + vertex -510.25 27.2106 4.27527 + vertex -508.961 25.2557 5.59386 + endloop + endfacet + facet normal -0.190031 -0.632086 -0.751236 + outer loop + vertex -508.961 25.2557 5.59386 + vertex -510.25 27.2106 4.27527 + vertex -508.568 26.7236 4.25943 + endloop + endfacet + facet normal -0.116135 -0.465961 -0.877151 + outer loop + vertex -517.904 29.019 4.34666 + vertex -516.94 30.67 3.34192 + vertex -513.44 27.9369 4.33041 + endloop + endfacet + facet normal -0.0936317 -0.442471 -0.891881 + outer loop + vertex -513.44 27.9369 4.33041 + vertex -516.94 30.67 3.34192 + vertex -513.105 30.2703 3.13771 + endloop + endfacet + facet normal -0.162451 -0.643948 -0.747623 + outer loop + vertex -518.594 27.5505 5.76157 + vertex -517.904 29.019 4.34666 + vertex -514.093 26.4175 5.75929 + endloop + endfacet + facet normal -0.15778 -0.639646 -0.752303 + outer loop + vertex -514.093 26.4175 5.75929 + vertex -517.904 29.019 4.34666 + vertex -513.44 27.9369 4.33041 + endloop + endfacet + facet normal -0.166508 -0.636574 -0.753026 + outer loop + vertex -514.093 26.4175 5.75929 + vertex -513.44 27.9369 4.33041 + vertex -510.811 25.6377 5.69289 + endloop + endfacet + facet normal -0.156589 -0.629832 -0.760784 + outer loop + vertex -510.811 25.6377 5.69289 + vertex -513.44 27.9369 4.33041 + vertex -510.25 27.2106 4.27527 + endloop + endfacet + facet normal -0.115369 -0.438946 -0.891076 + outer loop + vertex -513.44 27.9369 4.33041 + vertex -513.105 30.2703 3.13771 + vertex -510.25 27.2106 4.27527 + endloop + endfacet + facet normal -0.139693 -0.456952 -0.878454 + outer loop + vertex -510.25 27.2106 4.27527 + vertex -513.105 30.2703 3.13771 + vertex -509.668 29.0265 3.23818 + endloop + endfacet + facet normal -0.117508 -0.467721 -0.87603 + outer loop + vertex -529.082 31.9078 4.29544 + vertex -527.862 33.4269 3.32071 + vertex -523.268 30.3947 4.3235 + endloop + endfacet + facet normal -0.105154 -0.452203 -0.885695 + outer loop + vertex -523.268 30.3947 4.3235 + vertex -527.862 33.4269 3.32071 + vertex -522.465 32.4432 3.18223 + endloop + endfacet + facet normal -0.160752 -0.639947 -0.751417 + outer loop + vertex -529.722 30.4189 5.70051 + vertex -529.082 31.9078 4.29544 + vertex -523.951 28.9346 5.72989 + endloop + endfacet + facet normal -0.163891 -0.643548 -0.747653 + outer loop + vertex -523.951 28.9346 5.72989 + vertex -529.082 31.9078 4.29544 + vertex -523.268 30.3947 4.3235 + endloop + endfacet + facet normal -0.162048 -0.644231 -0.747467 + outer loop + vertex -523.951 28.9346 5.72989 + vertex -523.268 30.3947 4.3235 + vertex -518.594 27.5505 5.76157 + endloop + endfacet + facet normal -0.161956 -0.644132 -0.747572 + outer loop + vertex -518.594 27.5505 5.76157 + vertex -523.268 30.3947 4.3235 + vertex -517.904 29.019 4.34666 + endloop + endfacet + facet normal -0.111551 -0.449909 -0.88608 + outer loop + vertex -523.268 30.3947 4.3235 + vertex -522.465 32.4432 3.18223 + vertex -517.904 29.019 4.34666 + endloop + endfacet + facet normal -0.123037 -0.462479 -0.878052 + outer loop + vertex -517.904 29.019 4.34666 + vertex -522.465 32.4432 3.18223 + vertex -516.94 30.67 3.34192 + endloop + endfacet + facet normal -0.123765 -0.464668 -0.876793 + outer loop + vertex -540.869 35.006 4.3014 + vertex -539.732 36.5629 3.31569 + vertex -535.004 33.4621 4.2917 + endloop + endfacet + facet normal -0.110511 -0.447768 -0.887294 + outer loop + vertex -535.004 33.4621 4.2917 + vertex -539.732 36.5629 3.31569 + vertex -534.121 35.4803 3.16325 + endloop + endfacet + facet normal -0.165503 -0.632185 -0.756935 + outer loop + vertex -541.439 33.4714 5.70766 + vertex -540.869 35.006 4.3014 + vertex -535.592 31.9492 5.70053 + endloop + endfacet + facet normal -0.168618 -0.635842 -0.753176 + outer loop + vertex -535.592 31.9492 5.70053 + vertex -540.869 35.006 4.3014 + vertex -535.004 33.4621 4.2917 + endloop + endfacet + facet normal -0.166 -0.636714 -0.75302 + outer loop + vertex -535.592 31.9492 5.70053 + vertex -535.004 33.4621 4.2917 + vertex -529.722 30.4189 5.70051 + endloop + endfacet + facet normal -0.166905 -0.637776 -0.751921 + outer loop + vertex -529.722 30.4189 5.70051 + vertex -535.004 33.4621 4.2917 + vertex -529.082 31.9078 4.29544 + endloop + endfacet + facet normal -0.116345 -0.44545 -0.887715 + outer loop + vertex -535.004 33.4621 4.2917 + vertex -534.121 35.4803 3.16325 + vertex -529.082 31.9078 4.29544 + endloop + endfacet + facet normal -0.128853 -0.460154 -0.878439 + outer loop + vertex -529.082 31.9078 4.29544 + vertex -534.121 35.4803 3.16325 + vertex -527.862 33.4269 3.32071 + endloop + endfacet + facet normal -0.123521 -0.461934 -0.878271 + outer loop + vertex -552.465 38.0837 4.31046 + vertex -551.391 39.6766 3.32158 + vertex -546.672 36.5379 4.30879 + endloop + endfacet + facet normal -0.110209 -0.445183 -0.888632 + outer loop + vertex -546.672 36.5379 4.30879 + vertex -551.391 39.6766 3.32158 + vertex -545.902 38.6156 3.17235 + endloop + endfacet + facet normal -0.172064 -0.636887 -0.751511 + outer loop + vertex -553.046 36.5702 5.72618 + vertex -552.465 38.0837 4.31046 + vertex -547.246 35.012 5.7187 + endloop + endfacet + facet normal -0.169332 -0.633743 -0.754782 + outer loop + vertex -547.246 35.012 5.7187 + vertex -552.465 38.0837 4.31046 + vertex -546.672 36.5379 4.30879 + endloop + endfacet + facet normal -0.169557 -0.63367 -0.754794 + outer loop + vertex -547.246 35.012 5.7187 + vertex -546.672 36.5379 4.30879 + vertex -541.439 33.4714 5.70766 + endloop + endfacet + facet normal -0.167672 -0.63148 -0.757046 + outer loop + vertex -541.439 33.4714 5.70766 + vertex -546.672 36.5379 4.30879 + vertex -540.869 35.006 4.3014 + endloop + endfacet + facet normal -0.11795 -0.442501 -0.888977 + outer loop + vertex -546.672 36.5379 4.30879 + vertex -545.902 38.6156 3.17235 + vertex -540.869 35.006 4.3014 + endloop + endfacet + facet normal -0.132409 -0.459332 -0.878341 + outer loop + vertex -540.869 35.006 4.3014 + vertex -545.902 38.6156 3.17235 + vertex -539.732 36.5629 3.31569 + endloop + endfacet + facet normal -0.125121 -0.457366 -0.880432 + outer loop + vertex -564.108 41.2663 4.3073 + vertex -563.074 42.8824 3.32093 + vertex -558.268 39.6592 4.31233 + endloop + endfacet + facet normal -0.112471 -0.441503 -0.890183 + outer loop + vertex -558.268 39.6592 4.31233 + vertex -563.074 42.8824 3.32093 + vertex -557.565 41.7765 3.17337 + endloop + endfacet + facet normal -0.17541 -0.634137 -0.753061 + outer loop + vertex -564.679 39.7419 5.72392 + vertex -564.108 41.2663 4.3073 + vertex -558.863 38.1361 5.72149 + endloop + endfacet + facet normal -0.173183 -0.631599 -0.755705 + outer loop + vertex -558.863 38.1361 5.72149 + vertex -564.108 41.2663 4.3073 + vertex -558.268 39.6592 4.31233 + endloop + endfacet + facet normal -0.169736 -0.632765 -0.755512 + outer loop + vertex -558.863 38.1361 5.72149 + vertex -558.268 39.6592 4.31233 + vertex -553.046 36.5702 5.72618 + endloop + endfacet + facet normal -0.173049 -0.636558 -0.751564 + outer loop + vertex -553.046 36.5702 5.72618 + vertex -558.268 39.6592 4.31233 + vertex -552.465 38.0837 4.31046 + endloop + endfacet + facet normal -0.119533 -0.43926 -0.890372 + outer loop + vertex -558.268 39.6592 4.31233 + vertex -557.565 41.7765 3.17337 + vertex -552.465 38.0837 4.31046 + endloop + endfacet + facet normal -0.13393 -0.455916 -0.879888 + outer loop + vertex -552.465 38.0837 4.31046 + vertex -557.565 41.7765 3.17337 + vertex -551.391 39.6766 3.32158 + endloop + endfacet + facet normal -0.128532 -0.458281 -0.879465 + outer loop + vertex -575.858 44.5886 4.29666 + vertex -574.899 46.218 3.30738 + vertex -569.97 42.9164 4.30746 + endloop + endfacet + facet normal -0.114856 -0.441083 -0.890087 + outer loop + vertex -569.97 42.9164 4.30746 + vertex -574.899 46.218 3.30738 + vertex -569.341 45.0582 3.16501 + endloop + endfacet + facet normal -0.176177 -0.627358 -0.75854 + outer loop + vertex -576.34 43.0173 5.70824 + vertex -575.858 44.5886 4.29666 + vertex -570.507 41.3678 5.71755 + endloop + endfacet + facet normal -0.177056 -0.628363 -0.757503 + outer loop + vertex -570.507 41.3678 5.71755 + vertex -575.858 44.5886 4.29666 + vertex -569.97 42.9164 4.30746 + endloop + endfacet + facet normal -0.174684 -0.629117 -0.757428 + outer loop + vertex -570.507 41.3678 5.71755 + vertex -569.97 42.9164 4.30746 + vertex -564.679 39.7419 5.72392 + endloop + endfacet + facet normal -0.178261 -0.633189 -0.75319 + outer loop + vertex -564.679 39.7419 5.72392 + vertex -569.97 42.9164 4.30746 + vertex -564.108 41.2663 4.3073 + endloop + endfacet + facet normal -0.123486 -0.438591 -0.890162 + outer loop + vertex -569.97 42.9164 4.30746 + vertex -569.341 45.0582 3.16501 + vertex -564.108 41.2663 4.3073 + endloop + endfacet + facet normal -0.13496 -0.451908 -0.881797 + outer loop + vertex -564.108 41.2663 4.3073 + vertex -569.341 45.0582 3.16501 + vertex -563.074 42.8824 3.32093 + endloop + endfacet + facet normal -0.131283 -0.462706 -0.876737 + outer loop + vertex -587.489 47.9021 4.30153 + vertex -586.548 49.506 3.31417 + vertex -581.726 46.2742 4.29779 + endloop + endfacet + facet normal -0.11462 -0.441809 -0.889757 + outer loop + vertex -581.726 46.2742 4.29779 + vertex -586.548 49.506 3.31417 + vertex -581.119 48.3969 3.16558 + endloop + endfacet + facet normal -0.178284 -0.627815 -0.75767 + outer loop + vertex -587.916 46.3244 5.7093 + vertex -587.489 47.9021 4.30153 + vertex -582.154 44.6898 5.70816 + endloop + endfacet + facet normal -0.177641 -0.62708 -0.758429 + outer loop + vertex -582.154 44.6898 5.70816 + vertex -587.489 47.9021 4.30153 + vertex -581.726 46.2742 4.29779 + endloop + endfacet + facet normal -0.180169 -0.62638 -0.758411 + outer loop + vertex -582.154 44.6898 5.70816 + vertex -581.726 46.2742 4.29779 + vertex -576.34 43.0173 5.70824 + endloop + endfacet + facet normal -0.180025 -0.626215 -0.758582 + outer loop + vertex -576.34 43.0173 5.70824 + vertex -581.726 46.2742 4.29779 + vertex -575.858 44.5886 4.29666 + endloop + endfacet + facet normal -0.126142 -0.438545 -0.889813 + outer loop + vertex -581.726 46.2742 4.29779 + vertex -581.119 48.3969 3.16558 + vertex -575.858 44.5886 4.29666 + endloop + endfacet + facet normal -0.138618 -0.453057 -0.880639 + outer loop + vertex -575.858 44.5886 4.29666 + vertex -581.119 48.3969 3.16558 + vertex -574.899 46.218 3.30738 + endloop + endfacet + facet normal -0.140917 -0.473936 -0.869211 + outer loop + vertex -598.044 50.9522 4.3174 + vertex -596.838 52.3418 3.36425 + vertex -593.034 49.469 4.31394 + endloop + endfacet + facet normal -0.120042 -0.451274 -0.884275 + outer loop + vertex -593.034 49.469 4.31394 + vertex -596.838 52.3418 3.36425 + vertex -592.101 51.3919 3.20595 + endloop + endfacet + facet normal -0.182909 -0.627896 -0.756499 + outer loop + vertex -598.509 49.3961 5.72156 + vertex -598.044 50.9522 4.3174 + vertex -593.454 47.9201 5.72443 + endloop + endfacet + facet normal -0.187912 -0.632939 -0.751051 + outer loop + vertex -593.454 47.9201 5.72443 + vertex -598.044 50.9522 4.3174 + vertex -593.034 49.469 4.31394 + endloop + endfacet + facet normal -0.184668 -0.633852 -0.751086 + outer loop + vertex -593.454 47.9201 5.72443 + vertex -593.034 49.469 4.31394 + vertex -587.916 46.3244 5.7093 + endloop + endfacet + facet normal -0.179038 -0.627606 -0.757665 + outer loop + vertex -587.916 46.3244 5.7093 + vertex -593.034 49.469 4.31394 + vertex -587.489 47.9021 4.30153 + endloop + endfacet + facet normal -0.128455 -0.447589 -0.884965 + outer loop + vertex -593.034 49.469 4.31394 + vertex -592.101 51.3919 3.20595 + vertex -587.489 47.9021 4.30153 + endloop + endfacet + facet normal -0.138737 -0.458867 -0.877606 + outer loop + vertex -587.489 47.9021 4.30153 + vertex -592.101 51.3919 3.20595 + vertex -586.548 49.506 3.31417 + endloop + endfacet + facet normal -0.132615 -0.446796 -0.884752 + outer loop + vertex -605.136 53.2087 4.25299 + vertex -604.17 54.8929 3.25777 + vertex -602.223 52.2666 4.29215 + endloop + endfacet + facet normal -0.126035 -0.443038 -0.887599 + outer loop + vertex -602.223 52.2666 4.29215 + vertex -604.17 54.8929 3.25777 + vertex -600.935 54.1374 3.1755 + endloop + endfacet + facet normal -0.18495 -0.617487 -0.764528 + outer loop + vertex -605.442 51.5733 5.64803 + vertex -605.136 53.2087 4.25299 + vertex -602.608 50.6659 5.69524 + endloop + endfacet + facet normal -0.190551 -0.620763 -0.760489 + outer loop + vertex -602.608 50.6659 5.69524 + vertex -605.136 53.2087 4.25299 + vertex -602.223 52.2666 4.29215 + endloop + endfacet + facet normal -0.187666 -0.621535 -0.760576 + outer loop + vertex -602.608 50.6659 5.69524 + vertex -602.223 52.2666 4.29215 + vertex -598.509 49.3961 5.72156 + endloop + endfacet + facet normal -0.19204 -0.625164 -0.756499 + outer loop + vertex -598.509 49.3961 5.72156 + vertex -602.223 52.2666 4.29215 + vertex -598.044 50.9522 4.3174 + endloop + endfacet + facet normal -0.132709 -0.439047 -0.888609 + outer loop + vertex -602.223 52.2666 4.29215 + vertex -600.935 54.1374 3.1755 + vertex -598.044 50.9522 4.3174 + endloop + endfacet + facet normal -0.16108 -0.459389 -0.873507 + outer loop + vertex -598.044 50.9522 4.3174 + vertex -600.935 54.1374 3.1755 + vertex -596.838 52.3418 3.36425 + endloop + endfacet + facet normal -0.0937851 -0.4837 -0.870194 + outer loop + vertex -607.238 53.3489 4.4724 + vertex -606.768 55.2726 3.35241 + vertex -606.691 53.6112 4.26761 + endloop + endfacet + facet normal 0.0215063 -0.481624 -0.876114 + outer loop + vertex -606.691 53.6112 4.26761 + vertex -606.768 55.2726 3.35241 + vertex -605.812 55.7529 3.11183 + endloop + endfacet + facet normal -0.163935 -0.673208 -0.721052 + outer loop + vertex -607.407 51.894 5.86925 + vertex -607.238 53.3489 4.4724 + vertex -606.927 51.9855 5.67461 + endloop + endfacet + facet normal 0.0329226 -0.656805 -0.753341 + outer loop + vertex -606.927 51.9855 5.67461 + vertex -607.238 53.3489 4.4724 + vertex -606.691 53.6112 4.26761 + endloop + endfacet + facet normal -0.187626 -0.62706 -0.756037 + outer loop + vertex -606.927 51.9855 5.67461 + vertex -606.691 53.6112 4.26761 + vertex -605.442 51.5733 5.64803 + endloop + endfacet + facet normal -0.168018 -0.621335 -0.765319 + outer loop + vertex -605.442 51.5733 5.64803 + vertex -606.691 53.6112 4.26761 + vertex -605.136 53.2087 4.25299 + endloop + endfacet + facet normal -0.120412 -0.432764 -0.893429 + outer loop + vertex -606.691 53.6112 4.26761 + vertex -605.812 55.7529 3.11183 + vertex -605.136 53.2087 4.25299 + endloop + endfacet + facet normal -0.150401 -0.437627 -0.886489 + outer loop + vertex -605.136 53.2087 4.25299 + vertex -605.812 55.7529 3.11183 + vertex -604.17 54.8929 3.25777 + endloop + endfacet + facet normal 0.16441 0.722795 0.67122 + outer loop + vertex -607.335 51.4788 6.29862 + vertex -607.194 52.7697 4.87386 + vertex -607.407 51.894 5.86925 + endloop + endfacet + facet normal 0.733925 0.424049 0.5306 + outer loop + vertex -607.407 51.894 5.86925 + vertex -607.194 52.7697 4.87386 + vertex -607.238 53.3489 4.4724 + endloop + endfacet + facet normal 0.099849 0.57202 0.81414 + outer loop + vertex -607.194 52.7697 4.87386 + vertex -606.97 54.2093 3.83505 + vertex -607.238 53.3489 4.4724 + endloop + endfacet + facet normal 0.922327 -0.000536066 0.38641 + outer loop + vertex -607.238 53.3489 4.4724 + vertex -606.97 54.2093 3.83505 + vertex -606.768 55.2726 3.35241 + endloop + endfacet + facet normal -0.0784167 -0.293631 -0.952697 + outer loop + vertex -509.668 29.0265 3.23818 + vertex -513.105 30.2703 3.13771 + vertex -512.056 33.4902 2.05892 + endloop + endfacet + facet normal -0.0826907 -0.309153 -0.94741 + outer loop + vertex -516.94 30.67 3.34192 + vertex -519.779 34.7733 2.25078 + vertex -513.105 30.2703 3.13771 + endloop + endfacet + facet normal -0.0727501 -0.295441 -0.952587 + outer loop + vertex -519.779 34.7733 2.25078 + vertex -512.056 33.4902 2.05892 + vertex -513.105 30.2703 3.13771 + endloop + endfacet + facet normal -0.0690051 -0.300696 -0.95122 + outer loop + vertex -516.94 30.67 3.34192 + vertex -522.465 32.4432 3.18223 + vertex -519.779 34.7733 2.25078 + endloop + endfacet + facet normal -0.0794673 -0.302243 -0.949913 + outer loop + vertex -527.862 33.4269 3.32071 + vertex -530.519 37.3934 2.28094 + vertex -522.465 32.4432 3.18223 + endloop + endfacet + facet normal -0.0745973 -0.294816 -0.952638 + outer loop + vertex -530.519 37.3934 2.28094 + vertex -519.779 34.7733 2.25078 + vertex -522.465 32.4432 3.18223 + endloop + endfacet + facet normal -0.0741776 -0.299075 -0.951342 + outer loop + vertex -527.862 33.4269 3.32071 + vertex -534.121 35.4803 3.16325 + vertex -530.519 37.3934 2.28094 + endloop + endfacet + facet normal -0.0844962 -0.304287 -0.948826 + outer loop + vertex -539.732 36.5629 3.31569 + vertex -542.309 40.523 2.27523 + vertex -534.121 35.4803 3.16325 + endloop + endfacet + facet normal -0.0774612 -0.293563 -0.952796 + outer loop + vertex -542.309 40.523 2.27523 + vertex -530.519 37.3934 2.28094 + vertex -534.121 35.4803 3.16325 + endloop + endfacet + facet normal -0.0778701 -0.300444 -0.950615 + outer loop + vertex -539.732 36.5629 3.31569 + vertex -545.902 38.6156 3.17235 + vertex -542.309 40.523 2.27523 + endloop + endfacet + facet normal -0.0838861 -0.300346 -0.950134 + outer loop + vertex -551.391 39.6766 3.32158 + vertex -554.155 43.7582 2.27541 + vertex -545.902 38.6156 3.17235 + endloop + endfacet + facet normal -0.0807497 -0.295618 -0.951887 + outer loop + vertex -554.155 43.7582 2.27541 + vertex -542.309 40.523 2.27523 + vertex -545.902 38.6156 3.17235 + endloop + endfacet + facet normal -0.0781061 -0.29684 -0.951728 + outer loop + vertex -551.391 39.6766 3.32158 + vertex -557.565 41.7765 3.17337 + vertex -554.155 43.7582 2.27541 + endloop + endfacet + facet normal -0.0856301 -0.299789 -0.950155 + outer loop + vertex -563.074 42.8824 3.32093 + vertex -566.009 47.0593 2.26747 + vertex -557.565 41.7765 3.17337 + endloop + endfacet + facet normal -0.080851 -0.292606 -0.952809 + outer loop + vertex -566.009 47.0593 2.26747 + vertex -554.155 43.7582 2.27541 + vertex -557.565 41.7765 3.17337 + endloop + endfacet + facet normal -0.0789303 -0.295563 -0.952057 + outer loop + vertex -563.074 42.8824 3.32093 + vertex -569.341 45.0582 3.16501 + vertex -566.009 47.0593 2.26747 + endloop + endfacet + facet normal -0.0867971 -0.299252 -0.950218 + outer loop + vertex -574.899 46.218 3.30738 + vertex -577.774 50.3508 2.26849 + vertex -569.341 45.0582 3.16501 + endloop + endfacet + facet normal -0.081636 -0.291514 -0.953077 + outer loop + vertex -577.774 50.3508 2.26849 + vertex -566.009 47.0593 2.26747 + vertex -569.341 45.0582 3.16501 + endloop + endfacet + facet normal -0.0821019 -0.296321 -0.951553 + outer loop + vertex -574.899 46.218 3.30738 + vertex -581.119 48.3969 3.16558 + vertex -577.774 50.3508 2.26849 + endloop + endfacet + facet normal -0.0874105 -0.300593 -0.949738 + outer loop + vertex -586.548 49.506 3.31417 + vertex -588.794 53.3252 2.31213 + vertex -581.119 48.3969 3.16558 + endloop + endfacet + facet normal -0.0832674 -0.294534 -0.952006 + outer loop + vertex -588.794 53.3252 2.31213 + vertex -577.774 50.3508 2.26849 + vertex -581.119 48.3969 3.16558 + endloop + endfacet + facet normal -0.082725 -0.29815 -0.950928 + outer loop + vertex -586.548 49.506 3.31417 + vertex -592.101 51.3919 3.20595 + vertex -588.794 53.3252 2.31213 + endloop + endfacet + facet normal -0.0945815 -0.314246 -0.944618 + outer loop + vertex -596.838 52.3418 3.36425 + vertex -597.057 55.1115 2.46483 + vertex -592.101 51.3919 3.20595 + endloop + endfacet + facet normal -0.0821963 -0.298958 -0.95072 + outer loop + vertex -597.057 55.1115 2.46483 + vertex -588.794 53.3252 2.31213 + vertex -592.101 51.3919 3.20595 + endloop + endfacet + facet normal -0.0700407 -0.295437 -0.952791 + outer loop + vertex -604.17 54.8929 3.25777 + vertex -605.812 55.7529 3.11183 + vertex -602.912 58.2321 2.12985 + endloop + endfacet + facet normal -0.0836157 -0.308351 -0.947591 + outer loop + vertex -606.768 55.2726 3.35241 + vertex -605.996 58.4054 2.26488 + vertex -605.812 55.7529 3.11183 + endloop + endfacet + facet normal -0.0588514 -0.307336 -0.94978 + outer loop + vertex -605.996 58.4054 2.26488 + vertex -602.912 58.2321 2.12985 + vertex -605.812 55.7529 3.11183 + endloop + endfacet + facet normal -0.0583421 -0.205067 -0.977007 + outer loop + vertex -519.779 34.7733 2.25078 + vertex -518.781 39.2568 1.25013 + vertex -512.056 33.4902 2.05892 + endloop + endfacet + facet normal -0.0448565 -0.18987 -0.980784 + outer loop + vertex -512.056 33.4902 2.05892 + vertex -518.781 39.2568 1.25013 + vertex -512.393 38.7322 1.05952 + endloop + endfacet + facet normal -0.0533251 -0.207341 -0.976814 + outer loop + vertex -530.519 37.3934 2.28094 + vertex -528.609 41.4241 1.32113 + vertex -519.779 34.7733 2.25078 + endloop + endfacet + facet normal -0.0525644 -0.206366 -0.977062 + outer loop + vertex -519.779 34.7733 2.25078 + vertex -528.609 41.4241 1.32113 + vertex -518.781 39.2568 1.25013 + endloop + endfacet + facet normal -0.0546694 -0.207741 -0.976655 + outer loop + vertex -542.309 40.523 2.27523 + vertex -540.184 44.4479 1.32141 + vertex -530.519 37.3934 2.28094 + endloop + endfacet + facet normal -0.0540969 -0.206983 -0.976848 + outer loop + vertex -530.519 37.3934 2.28094 + vertex -540.184 44.4479 1.32141 + vertex -528.609 41.4241 1.32113 + endloop + endfacet + facet normal -0.0565763 -0.207104 -0.976682 + outer loop + vertex -554.155 43.7582 2.27541 + vertex -552.223 47.7745 1.31184 + vertex -542.309 40.523 2.27523 + endloop + endfacet + facet normal -0.0563763 -0.20684 -0.976749 + outer loop + vertex -542.309 40.523 2.27523 + vertex -552.223 47.7745 1.31184 + vertex -540.184 44.4479 1.32141 + endloop + endfacet + facet normal -0.0568083 -0.206333 -0.976831 + outer loop + vertex -566.009 47.0593 2.26747 + vertex -564.271 51.171 1.29792 + vertex -554.155 43.7582 2.27541 + endloop + endfacet + facet normal -0.0571781 -0.206821 -0.976707 + outer loop + vertex -554.155 43.7582 2.27541 + vertex -564.271 51.171 1.29792 + vertex -552.223 47.7745 1.31184 + endloop + endfacet + facet normal -0.0576661 -0.205825 -0.976888 + outer loop + vertex -577.774 50.3508 2.26849 + vertex -576.081 54.4531 1.3042 + vertex -566.009 47.0593 2.26747 + endloop + endfacet + facet normal -0.0577529 -0.20594 -0.976859 + outer loop + vertex -566.009 47.0593 2.26747 + vertex -576.081 54.4531 1.3042 + vertex -564.271 51.171 1.29792 + endloop + endfacet + facet normal -0.0608288 -0.211055 -0.97558 + outer loop + vertex -588.794 53.3252 2.31213 + vertex -586.964 57.3236 1.33304 + vertex -577.774 50.3508 2.26849 + endloop + endfacet + facet normal -0.0569505 -0.206116 -0.976869 + outer loop + vertex -577.774 50.3508 2.26849 + vertex -586.964 57.3236 1.33304 + vertex -576.081 54.4531 1.3042 + endloop + endfacet + facet normal -0.0639686 -0.212558 -0.975052 + outer loop + vertex -597.057 55.1115 2.46483 + vertex -596.706 59.8171 1.41601 + vertex -588.794 53.3252 2.31213 + endloop + endfacet + facet normal -0.0621743 -0.210451 -0.975625 + outer loop + vertex -588.794 53.3252 2.31213 + vertex -596.706 59.8171 1.41601 + vertex -586.964 57.3236 1.33304 + endloop + endfacet + facet normal -0.054353 -0.206052 -0.97703 + outer loop + vertex -605.996 58.4054 2.26488 + vertex -604.973 62.6766 1.30718 + vertex -602.912 58.2321 2.12985 + endloop + endfacet + facet normal -0.0381766 -0.198964 -0.979263 + outer loop + vertex -602.912 58.2321 2.12985 + vertex -604.973 62.6766 1.30718 + vertex -602.368 63.0885 1.12195 + endloop + endfacet + facet normal -0.16034 -0.813707 0.558724 + outer loop + vertex -502.812 64.9071 34.2401 + vertex -501.789 67.029 37.6239 + vertex -506.338 66.629 35.7359 + endloop + endfacet + facet normal -0.188363 -0.770205 0.609347 + outer loop + vertex -504.152 61.7843 29.8788 + vertex -502.812 64.9071 34.2401 + vertex -506.353 64.3283 32.4139 + endloop + endfacet + facet normal -0.44344 -0.61287 0.654026 + outer loop + vertex -504.614 59.3872 27.319 + vertex -504.152 61.7843 29.8788 + vertex -504.881 60.1765 27.8776 + endloop + endfacet + facet normal -0.336475 -0.527811 0.779872 + outer loop + vertex -505.324 56.9938 25.3929 + vertex -504.614 59.3872 27.319 + vertex -505.469 58.3407 26.2421 + endloop + endfacet + facet normal -0.247654 -0.428234 0.86907 + outer loop + vertex -505.856 54.4532 23.9895 + vertex -505.324 56.9938 25.3929 + vertex -506.007 54.9552 24.1937 + endloop + endfacet + facet normal -0.656371 0.474161 -0.586812 + outer loop + vertex -506.854 51.9309 23.0685 + vertex -505.856 54.4532 23.9895 + vertex -506.483 52.7364 23.304 + endloop + endfacet + facet normal -0.273076 -0.129277 0.953266 + outer loop + vertex -508.767 47.7226 21.9498 + vertex -506.854 51.9309 23.0685 + vertex -507.809 50.501 22.6012 + endloop + endfacet + facet normal -0.0443018 -0.242852 0.969051 + outer loop + vertex -509.363 35.8267 19.1212 + vertex -509.268 41.9962 20.6717 + vertex -512.755 39.125 19.7927 + endloop + endfacet + facet normal 0.00563382 -0.293455 0.955956 + outer loop + vertex -508.729 31.2422 17.7102 + vertex -509.363 35.8267 19.1212 + vertex -509.564 32.0462 17.9619 + endloop + endfacet + facet normal 0.0441454 -0.397319 0.916618 + outer loop + vertex -508.626 28.4243 16.4838 + vertex -508.729 31.2422 17.7102 + vertex -508.967 29.2652 16.8647 + endloop + endfacet + facet normal 0.00279254 -0.54516 0.838328 + outer loop + vertex -508.544 26.3272 15.1198 + vertex -508.626 28.4243 16.4838 + vertex -508.924 27.055 15.5943 + endloop + endfacet + facet normal -0.0650192 -0.709312 0.701889 + outer loop + vertex -508.602 24.8527 13.6242 + vertex -508.544 26.3272 15.1198 + vertex -509.046 25.4104 14.1468 + endloop + endfacet + facet normal -0.116677 -0.858133 0.499994 + outer loop + vertex -508.693 23.8672 11.9117 + vertex -508.602 24.8527 13.6242 + vertex -509.197 24.281 12.5041 + endloop + endfacet + facet normal -0.204725 -0.93991 0.273235 + outer loop + vertex -508.72 23.4109 10.3219 + vertex -508.693 23.8672 11.9117 + vertex -509.304 23.6602 10.7414 + endloop + endfacet + facet normal -0.169379 -0.98302 -0.0705932 + outer loop + vertex -508.783 23.5251 8.88255 + vertex -508.72 23.4109 10.3219 + vertex -509.375 23.6204 8.9769 + endloop + endfacet + facet normal -0.151747 -0.936662 -0.315654 + outer loop + vertex -508.686 24.1074 7.10827 + vertex -508.783 23.5251 8.88255 + vertex -509.284 24.1625 7.23215 + endloop + endfacet + facet normal -0.152829 -0.800609 -0.579369 + outer loop + vertex -508.463 25.236 5.48987 + vertex -508.686 24.1074 7.10827 + vertex -508.961 25.2557 5.59386 + endloop + endfacet + facet normal 0.0735207 -0.632569 -0.771007 + outer loop + vertex -508.44 26.9019 4.12532 + vertex -508.463 25.236 5.48987 + vertex -508.568 26.7236 4.25943 + endloop + endfacet + facet normal 0.578384 0.414599 0.702552 + outer loop + vertex -508.951 29.7198 2.88291 + vertex -508.44 26.9019 4.12532 + vertex -508.421 27.9357 3.4995 + endloop + endfacet + facet normal -0.117243 -0.303231 -0.945677 + outer loop + vertex -509.326 32.5063 2.03593 + vertex -508.951 29.7198 2.88291 + vertex -512.056 33.4902 2.05892 + endloop + endfacet + facet normal -0.0803029 -0.20001 -0.976497 + outer loop + vertex -509.269 35.1963 1.48026 + vertex -509.326 32.5063 2.03593 + vertex -512.056 33.4902 2.05892 + endloop + endfacet + facet normal -0.0373262 -0.209078 -0.977186 + outer loop + vertex -607.221 58.5027 2.29088 + vertex -607.26 62.3015 1.47955 + vertex -605.996 58.4054 2.26488 + endloop + endfacet + facet normal -0.0433822 -0.291162 -0.95569 + outer loop + vertex -606.63 55.8616 3.06863 + vertex -607.221 58.5027 2.29088 + vertex -605.996 58.4054 2.26488 + endloop + endfacet + facet normal -0.615437 0.432559 0.658885 + outer loop + vertex -606.94 53.7528 4.16293 + vertex -606.63 55.8616 3.06863 + vertex -606.97 54.2093 3.83505 + endloop + endfacet + facet normal -0.625328 0.556654 0.546902 + outer loop + vertex -607.206 52.1336 5.50727 + vertex -606.94 53.7528 4.16293 + vertex -607.194 52.7697 4.87386 + endloop + endfacet + facet normal -0.282345 0.761248 0.583766 + outer loop + vertex -607.29 51.0675 6.85674 + vertex -607.206 52.1336 5.50727 + vertex -607.335 51.4788 6.29862 + endloop + endfacet + facet normal -0.32463 0.896631 0.301113 + outer loop + vertex -607.388 50.5431 8.31261 + vertex -607.29 51.0675 6.85674 + vertex -607.398 50.6649 7.93974 + endloop + endfacet + facet normal -0.610223 0.788576 0.0759924 + outer loop + vertex -607.374 50.3724 10.1998 + vertex -607.388 50.5431 8.31261 + vertex -607.396 50.397 9.76656 + endloop + endfacet + facet normal -0.929306 0.363753 -0.0638291 + outer loop + vertex -607.312 50.8586 12.0667 + vertex -607.374 50.3724 10.1998 + vertex -607.336 50.7235 11.6448 + endloop + endfacet + facet normal -0.878024 0.427603 -0.215008 + outer loop + vertex -607.209 51.9269 13.7712 + vertex -607.312 50.8586 12.0667 + vertex -607.251 51.6439 13.3823 + endloop + endfacet + facet normal -0.314848 0.680485 -0.661673 + outer loop + vertex -607.038 53.4482 15.2547 + vertex -607.209 51.9269 13.7712 + vertex -607.145 53.0548 14.9008 + endloop + endfacet + facet normal 0.0363433 0.56368 -0.825193 + outer loop + vertex -606.797 55.2383 16.4882 + vertex -607.038 53.4482 15.2547 + vertex -606.951 54.8011 16.1827 + endloop + endfacet + facet normal -0.442432 -0.3812 0.811752 + outer loop + vertex -606.673 57.1499 17.4537 + vertex -606.797 55.2383 16.4882 + vertex -606.673 56.6212 17.2052 + endloop + endfacet + facet normal -0.292092 -0.346678 0.891346 + outer loop + vertex -607.085 59.8132 18.3546 + vertex -606.673 57.1499 17.4537 + vertex -606.579 57.9644 17.8012 + endloop + endfacet + facet normal -0.0832336 -0.255417 0.963242 + outer loop + vertex -607.214 64.2598 19.5225 + vertex -607.085 59.8132 18.3546 + vertex -605.376 61.5303 18.9576 + endloop + endfacet + facet normal -0.0676805 -0.197883 0.977886 + outer loop + vertex -607.088 68.947 20.4797 + vertex -607.214 64.2598 19.5225 + vertex -604.748 66.3269 20.1115 + endloop + endfacet + facet normal -0.0520548 -0.156997 0.986226 + outer loop + vertex -606.422 74.18 21.3479 + vertex -607.088 68.947 20.4797 + vertex -604.614 71.0596 20.9466 + endloop + endfacet + facet normal -0.00449681 -0.166821 0.985977 + outer loop + vertex -605.271 78.4781 22.0804 + vertex -606.422 74.18 21.3479 + vertex -604.883 77.6955 21.9498 + endloop + endfacet + facet normal 0.189291 -0.303322 0.933898 + outer loop + vertex -604.133 81.3022 22.767 + vertex -605.271 78.4781 22.0804 + vertex -604.374 80.3357 22.502 + endloop + endfacet + facet normal 0.779774 -0.150128 0.607795 + outer loop + vertex -604.464 84.2129 23.9101 + vertex -604.133 81.3022 22.767 + vertex -604.208 82.6724 23.2018 + endloop + endfacet + facet normal 0.789985 -0.0975169 0.605321 + outer loop + vertex -605.498 87.135 25.7302 + vertex -604.464 84.2129 23.9101 + vertex -604.975 86.0924 24.8794 + endloop + endfacet + facet normal 0.912636 0.070227 0.402695 + outer loop + vertex -606.715 89.8493 28.0151 + vertex -605.498 87.135 25.7302 + vertex -605.806 88.0584 26.2672 + endloop + endfacet + facet normal -0.270579 -0.773932 0.572552 + outer loop + vertex -608.351 92.8001 31.2306 + vertex -606.715 89.8493 28.0151 + vertex -606.451 91.1626 29.9149 + endloop + endfacet + facet normal -0.302338 -0.808606 0.504725 + outer loop + vertex -610.077 95.1542 33.968 + vertex -608.351 92.8001 31.2306 + vertex -607.804 93.731 33.0494 + endloop + endfacet + facet normal -0.304445 -0.892975 0.331525 + outer loop + vertex -591.631 90.1917 37.259 + vertex -595.666 91.5508 37.215 + vertex -596.134 91.5136 36.6847 + endloop + endfacet + facet normal -0.28612 -0.913232 0.290074 + outer loop + vertex -573.6 84.8914 38.6533 + vertex -579.818 86.7187 38.2727 + vertex -575.75 85.3237 37.8938 + endloop + endfacet + facet normal -0.275083 -0.928273 0.250278 + outer loop + vertex -567.318 83.1471 39.0887 + vertex -573.6 84.8914 38.6533 + vertex -575.75 85.3237 37.8938 + endloop + endfacet + facet normal -0.270926 -0.920637 0.281115 + outer loop + vertex -560.702 81.2948 39.399 + vertex -567.318 83.1471 39.0887 + vertex -562.955 81.698 38.5475 + endloop + endfacet + facet normal -0.256458 -0.937606 0.234785 + outer loop + vertex -554.293 79.6214 39.7159 + vertex -560.702 81.2948 39.399 + vertex -562.955 81.698 38.5475 + endloop + endfacet + facet normal -0.250522 -0.929335 0.271248 + outer loop + vertex -547.576 77.863 39.8959 + vertex -554.293 79.6214 39.7159 + vertex -549.96 78.2621 39.061 + endloop + endfacet + facet normal -0.231948 -0.950177 0.208242 + outer loop + vertex -541.103 76.3366 40.1413 + vertex -547.576 77.863 39.8959 + vertex -549.96 78.2621 39.061 + endloop + endfacet + facet normal -0.22661 -0.937851 0.262839 + outer loop + vertex -534.461 74.7548 40.2228 + vertex -541.103 76.3366 40.1413 + vertex -537.102 75.1773 39.4541 + endloop + endfacet + facet normal -0.213768 -0.954087 0.209812 + outer loop + vertex -528.458 73.3982 40.171 + vertex -534.461 74.7548 40.2228 + vertex -537.102 75.1773 39.4541 + endloop + endfacet + facet normal -0.187387 -0.982234 0.010152 + outer loop + vertex -516.301 70.8757 40.0959 + vertex -522.28 72.0156 40.024 + vertex -524.665 72.4667 39.6363 + endloop + endfacet + facet normal -0.14038 -0.933926 0.328747 + outer loop + vertex -502.937 68.7502 40.5391 + vertex -506.857 69.3045 40.4395 + vertex -505.846 69.034 40.1029 + endloop + endfacet + facet normal -0.144359 -0.920009 0.364341 + outer loop + vertex -505.846 69.034 40.1029 + vertex -502.226 68.4673 40.1063 + vertex -502.937 68.7502 40.5391 + endloop + endfacet + facet normal -0.190942 -0.97728 0.09201 + outer loop + vertex -524.665 72.4667 39.6363 + vertex -513.308 70.2585 39.7509 + vertex -516.301 70.8757 40.0959 + endloop + endfacet + facet normal -0.212212 -0.962131 0.171088 + outer loop + vertex -537.102 75.1773 39.4541 + vertex -524.665 72.4667 39.6363 + vertex -528.458 73.3982 40.171 + endloop + endfacet + facet normal -0.233601 -0.944088 0.232654 + outer loop + vertex -549.96 78.2621 39.061 + vertex -537.102 75.1773 39.4541 + vertex -541.103 76.3366 40.1413 + endloop + endfacet + facet normal -0.25695 -0.935669 0.241867 + outer loop + vertex -562.955 81.698 38.5475 + vertex -549.96 78.2621 39.061 + vertex -554.293 79.6214 39.7159 + endloop + endfacet + facet normal -0.275589 -0.926021 0.257947 + outer loop + vertex -575.75 85.3237 37.8938 + vertex -562.955 81.698 38.5475 + vertex -567.318 83.1471 39.0887 + endloop + endfacet + facet normal -0.289047 -0.917337 0.273758 + outer loop + vertex -587.729 88.8735 37.1406 + vertex -575.75 85.3237 37.8938 + vertex -579.818 86.7187 38.2727 + endloop + endfacet + facet normal -0.302271 -0.917876 0.25717 + outer loop + vertex -596.134 91.5136 36.6847 + vertex -587.729 88.8735 37.1406 + vertex -591.631 90.1917 37.259 + endloop + endfacet + facet normal -0.157567 -0.811495 0.562715 + outer loop + vertex -506.338 66.629 35.7359 + vertex -506.353 64.3283 32.4139 + vertex -502.812 64.9071 34.2401 + endloop + endfacet + facet normal -0.333808 -0.794655 0.507046 + outer loop + vertex -606.451 91.1626 29.9149 + vertex -607.804 93.731 33.0494 + vertex -608.351 92.8001 31.2306 + endloop + endfacet + facet normal -0.233185 -0.780194 0.58045 + outer loop + vertex -506.353 64.3283 32.4139 + vertex -506.107 62.3234 29.818 + vertex -504.152 61.7843 29.8788 + endloop + endfacet + facet normal -0.270841 -0.78839 0.552346 + outer loop + vertex -598.143 86.8856 28.1139 + vertex -596.013 88.2333 31.082 + vertex -601.792 88.0623 28.004 + endloop + endfacet + facet normal -0.24883 -0.78022 0.573882 + outer loop + vertex -606.264 89.1664 27.282 + vertex -606.451 91.1626 29.9149 + vertex -606.715 89.8493 28.0151 + endloop + endfacet + facet normal -0.269284 -0.764865 0.585207 + outer loop + vertex -603.613 89.8083 29.4482 + vertex -604.603 88.5036 27.2873 + vertex -601.792 88.0623 28.004 + endloop + endfacet + facet normal -0.212188 -0.611321 0.762406 + outer loop + vertex -504.881 60.1765 27.8776 + vertex -505.469 58.3407 26.2421 + vertex -504.614 59.3872 27.319 + endloop + endfacet + facet normal -0.233852 -0.783082 0.576278 + outer loop + vertex -506.107 62.3234 29.818 + vertex -504.793 61.3097 28.9737 + vertex -504.152 61.7843 29.8788 + endloop + endfacet + facet normal -0.479329 -0.59058 0.649199 + outer loop + vertex -504.793 61.3097 28.9737 + vertex -504.881 60.1765 27.8776 + vertex -504.152 61.7843 29.8788 + endloop + endfacet + facet normal 0.922886 0.372237 0.098594 + outer loop + vertex -605.806 88.0584 26.2672 + vertex -606.258 88.9872 26.9925 + vertex -606.715 89.8493 28.0151 + endloop + endfacet + facet normal -0.411044 -0.779173 0.473215 + outer loop + vertex -606.258 88.9872 26.9925 + vertex -606.264 89.1664 27.282 + vertex -606.715 89.8493 28.0151 + endloop + endfacet + facet normal 0.810571 -0.0679037 0.58169 + outer loop + vertex -604.975 86.0924 24.8794 + vertex -605.806 88.0584 26.2672 + vertex -605.498 87.135 25.7302 + endloop + endfacet + facet normal -0.235414 -0.432959 0.87013 + outer loop + vertex -506.004 56.6816 25.0537 + vertex -506.007 54.9552 24.1937 + vertex -505.324 56.9938 25.3929 + endloop + endfacet + facet normal -0.16495 -0.53864 0.826232 + outer loop + vertex -505.469 58.3407 26.2421 + vertex -506.004 56.6816 25.0537 + vertex -505.324 56.9938 25.3929 + endloop + endfacet + facet normal 0.88328 -0.00177732 0.468842 + outer loop + vertex -604.471 84.4572 23.9237 + vertex -604.975 86.0924 24.8794 + vertex -604.464 84.2129 23.9101 + endloop + endfacet + facet normal 0.946074 0.00800657 0.323852 + outer loop + vertex -604.208 82.6724 23.2018 + vertex -604.471 84.4572 23.9237 + vertex -604.464 84.2129 23.9101 + endloop + endfacet + facet normal -0.160695 -0.208061 0.964825 + outer loop + vertex -506.483 52.7364 23.304 + vertex -507.809 50.501 22.6012 + vertex -506.854 51.9309 23.0685 + endloop + endfacet + facet normal 0.0103793 -0.374064 0.927345 + outer loop + vertex -506.007 54.9552 24.1937 + vertex -506.483 52.7364 23.304 + vertex -505.856 54.4532 23.9895 + endloop + endfacet + facet normal -0.133964 0.293034 -0.94667 + outer loop + vertex -604.374 80.3357 22.502 + vertex -604.208 82.6724 23.2018 + vertex -604.133 81.3022 22.767 + endloop + endfacet + facet normal -0.0600407 -0.193252 0.97931 + outer loop + vertex -604.883 77.6955 21.9498 + vertex -604.374 80.3357 22.502 + vertex -605.271 78.4781 22.0804 + endloop + endfacet + facet normal -0.0383661 -0.172593 0.984246 + outer loop + vertex -604.748 66.3269 20.1115 + vertex -604.614 71.0596 20.9466 + vertex -607.088 68.947 20.4797 + endloop + endfacet + facet normal -0.0567283 -0.303722 0.95107 + outer loop + vertex -511.777 34.6922 18.6749 + vertex -511.131 31.9264 17.8302 + vertex -509.564 32.0462 17.9619 + endloop + endfacet + facet normal -0.0833296 -0.284566 0.955028 + outer loop + vertex -599.142 55.9585 17.8418 + vertex -596.137 58.7895 18.9476 + vertex -602.571 57.1775 17.9059 + endloop + endfacet + facet normal -0.0312224 -0.303352 0.952367 + outer loop + vertex -606.548 58.4467 17.9369 + vertex -605.376 61.5303 18.9576 + vertex -607.085 59.8132 18.3546 + endloop + endfacet + facet normal -0.0985965 -0.302922 0.947901 + outer loop + vertex -603.359 59.6148 18.6028 + vertex -605.38 57.4854 17.712 + vertex -602.571 57.1775 17.9059 + endloop + endfacet + facet normal -0.262895 -0.484669 0.834255 + outer loop + vertex -508.967 29.2652 16.8647 + vertex -508.924 27.055 15.5943 + vertex -508.626 28.4243 16.4838 + endloop + endfacet + facet normal -0.0908134 -0.382288 0.91957 + outer loop + vertex -509.564 32.0462 17.9619 + vertex -508.967 29.2652 16.8647 + vertex -508.729 31.2422 17.7102 + endloop + endfacet + facet normal 0.328468 -0.402157 0.854622 + outer loop + vertex -606.673 56.6212 17.2052 + vertex -606.579 57.9644 17.8012 + vertex -606.673 57.1499 17.4537 + endloop + endfacet + facet normal 0.0508702 -0.273627 0.96049 + outer loop + vertex -606.579 57.9644 17.8012 + vertex -606.548 58.4467 17.9369 + vertex -607.085 59.8132 18.3546 + endloop + endfacet + facet normal 0.529474 0.352567 -0.771592 + outer loop + vertex -606.951 54.8011 16.1827 + vertex -606.673 56.6212 17.2052 + vertex -606.797 55.2383 16.4882 + endloop + endfacet + facet normal -0.310578 -0.76964 0.557849 + outer loop + vertex -509.046 25.4104 14.1468 + vertex -509.197 24.281 12.5041 + vertex -508.602 24.8527 13.6242 + endloop + endfacet + facet normal -0.279438 -0.622648 0.730906 + outer loop + vertex -508.924 27.055 15.5943 + vertex -509.046 25.4104 14.1468 + vertex -508.544 26.3272 15.1198 + endloop + endfacet + facet normal 0.660921 0.395053 -0.638057 + outer loop + vertex -607.145 53.0548 14.9008 + vertex -606.951 54.8011 16.1827 + vertex -607.038 53.4482 15.2547 + endloop + endfacet + facet normal 0.952663 0.186524 -0.240089 + outer loop + vertex -607.251 51.6439 13.3823 + vertex -607.145 53.0548 14.9008 + vertex -607.209 51.9269 13.7712 + endloop + endfacet + facet normal -0.37013 -0.928292 0.0357537 + outer loop + vertex -509.304 23.6602 10.7414 + vertex -509.375 23.6204 8.9769 + vertex -508.72 23.4109 10.3219 + endloop + endfacet + facet normal -0.334769 -0.882247 0.331012 + outer loop + vertex -509.197 24.281 12.5041 + vertex -509.304 23.6602 10.7414 + vertex -508.693 23.8672 11.9117 + endloop + endfacet + facet normal 0.996888 0.0385986 -0.0687359 + outer loop + vertex -607.336 50.7235 11.6448 + vertex -607.251 51.6439 13.3823 + vertex -607.312 50.8586 12.0667 + endloop + endfacet + facet normal 0.995557 0.0820127 -0.0462551 + outer loop + vertex -607.396 50.397 9.76656 + vertex -607.336 50.7235 11.6448 + vertex -607.374 50.3724 10.1998 + endloop + endfacet + facet normal -0.191834 -0.79846 -0.570668 + outer loop + vertex -509.284 24.1625 7.23215 + vertex -508.961 25.2557 5.59386 + vertex -508.686 24.1074 7.10827 + endloop + endfacet + facet normal -0.19794 -0.933097 -0.300248 + outer loop + vertex -509.375 23.6204 8.9769 + vertex -509.284 24.1625 7.23215 + vertex -508.783 23.5251 8.88255 + endloop + endfacet + facet normal 0.990936 0.133032 0.0186517 + outer loop + vertex -607.398 50.6649 7.93974 + vertex -607.396 50.397 9.76656 + vertex -607.388 50.5431 8.31261 + endloop + endfacet + facet normal 0.870413 0.427076 0.244923 + outer loop + vertex -607.335 51.4788 6.29862 + vertex -607.398 50.6649 7.93974 + vertex -607.29 51.0675 6.85674 + endloop + endfacet + facet normal -0.176934 -0.507312 -0.843403 + outer loop + vertex -508.568 26.7236 4.25943 + vertex -508.421 27.9357 3.4995 + vertex -508.44 26.9019 4.12532 + endloop + endfacet + facet normal -0.116129 -0.355071 -0.927599 + outer loop + vertex -508.421 27.9357 3.4995 + vertex -509.668 29.0265 3.23818 + vertex -508.951 29.7198 2.88291 + endloop + endfacet + facet normal -0.18219 -0.634274 -0.751334 + outer loop + vertex -508.961 25.2557 5.59386 + vertex -508.568 26.7236 4.25943 + vertex -508.463 25.236 5.48987 + endloop + endfacet + facet normal -0.0914053 -0.287585 -0.953384 + outer loop + vertex -600.935 54.1374 3.1755 + vertex -604.17 54.8929 3.25777 + vertex -602.912 58.2321 2.12985 + endloop + endfacet + facet normal -0.0941874 -0.31423 -0.944663 + outer loop + vertex -596.838 52.3418 3.36425 + vertex -600.935 54.1374 3.1755 + vertex -597.057 55.1115 2.46483 + endloop + endfacet + facet normal 0.6513 0.529027 0.544003 + outer loop + vertex -607.194 52.7697 4.87386 + vertex -607.335 51.4788 6.29862 + vertex -607.206 52.1336 5.50727 + endloop + endfacet + facet normal 0.012594 0.583837 0.811773 + outer loop + vertex -606.97 54.2093 3.83505 + vertex -607.194 52.7697 4.87386 + vertex -606.94 53.7528 4.16293 + endloop + endfacet + facet normal 0.518844 0.26931 0.81134 + outer loop + vertex -606.768 55.2726 3.35241 + vertex -606.97 54.2093 3.83505 + vertex -606.63 55.8616 3.06863 + endloop + endfacet + facet normal -0.147628 -0.325678 -0.933884 + outer loop + vertex -509.668 29.0265 3.23818 + vertex -512.056 33.4902 2.05892 + vertex -508.951 29.7198 2.88291 + endloop + endfacet + facet normal 0.960055 -0.266298 -0.0859083 + outer loop + vertex -605.996 58.4054 2.26488 + vertex -606.768 55.2726 3.35241 + vertex -606.63 55.8616 3.06863 + endloop + endfacet + facet normal -0.0855187 -0.191892 -0.977683 + outer loop + vertex -512.056 33.4902 2.05892 + vertex -512.393 38.7322 1.05952 + vertex -509.269 35.1963 1.48026 + endloop + endfacet + facet normal -0.0577721 -0.213081 -0.975325 + outer loop + vertex -596.706 59.8171 1.41601 + vertex -597.057 55.1115 2.46483 + vertex -602.912 58.2321 2.12985 + endloop + endfacet + facet normal -0.0392472 -0.209661 -0.976986 + outer loop + vertex -604.973 62.6766 1.30718 + vertex -605.996 58.4054 2.26488 + vertex -607.26 62.3015 1.47955 + endloop + endfacet + facet normal -0.0624839 -0.196104 -0.97859 + outer loop + vertex -602.912 58.2321 2.12985 + vertex -602.368 63.0885 1.12195 + vertex -596.706 59.8171 1.41601 + endloop + endfacet + facet normal -0.0399724 -0.291004 0.955886 + outer loop + vertex -509.564 32.0462 17.9619 + vertex -509.363 35.8267 19.1212 + vertex -511.777 34.6922 18.6749 + endloop + endfacet + facet normal -0.28262 -0.768995 0.573386 + outer loop + vertex -596.013 88.2333 31.082 + vertex -603.613 89.8083 29.4482 + vertex -601.792 88.0623 28.004 + endloop + endfacet + facet normal -0.0794388 -0.297714 0.951344 + outer loop + vertex -596.137 58.7895 18.9476 + vertex -603.359 59.6148 18.6028 + vertex -602.571 57.1775 17.9059 + endloop + endfacet + facet normal -0.101046 -0.291672 -0.951166 + outer loop + vertex -600.935 54.1374 3.1755 + vertex -602.912 58.2321 2.12985 + vertex -597.057 55.1115 2.46483 + endloop + endfacet + facet normal -0.274707 -0.738503 0.615751 + outer loop + vertex -608.129 92.2737 30.509 + vertex -608.496 92.2494 30.3162 + vertex -607.112 89.5333 27.6761 + endloop + endfacet + facet normal -0.268395 -0.743621 0.612365 + outer loop + vertex -609.575 93.0693 30.839 + vertex -609.518 90.6719 27.9525 + vertex -608.496 92.2494 30.3162 + endloop + endfacet + facet normal -0.279017 -0.738646 0.613638 + outer loop + vertex -609.518 90.6719 27.9525 + vertex -607.112 89.5333 27.6761 + vertex -608.496 92.2494 30.3162 + endloop + endfacet + facet normal -0.343276 -0.825107 0.448731 + outer loop + vertex -609.64 94.2155 32.5415 + vertex -610.963 95.57 34.0205 + vertex -610.677 94.9837 33.161 + endloop + endfacet + facet normal -0.314212 -0.708862 0.631494 + outer loop + vertex -614.004 94.1024 29.808 + vertex -616.248 94.1909 28.7908 + vertex -613.638 91.8379 27.4484 + endloop + endfacet + facet normal -0.281644 -0.676569 0.68039 + outer loop + vertex -618.738 95.077 28.6412 + vertex -618.718 93.203 26.786 + vertex -616.248 94.1909 28.7908 + endloop + endfacet + facet normal -0.272389 -0.686699 0.67398 + outer loop + vertex -618.718 93.203 26.786 + vertex -613.638 91.8379 27.4484 + vertex -616.248 94.1909 28.7908 + endloop + endfacet + facet normal -0.314324 -0.733296 0.60289 + outer loop + vertex -609.575 93.0693 30.839 + vertex -611.474 93.2586 30.0794 + vertex -609.518 90.6719 27.9525 + endloop + endfacet + facet normal -0.30488 -0.710359 0.63438 + outer loop + vertex -614.004 94.1024 29.808 + vertex -613.638 91.8379 27.4484 + vertex -611.474 93.2586 30.0794 + endloop + endfacet + facet normal -0.282446 -0.727555 0.625211 + outer loop + vertex -613.638 91.8379 27.4484 + vertex -609.518 90.6719 27.9525 + vertex -611.474 93.2586 30.0794 + endloop + endfacet + facet normal -0.288156 -0.642512 0.710031 + outer loop + vertex -624.306 96.6838 27.8956 + vertex -627.093 97.2481 27.2752 + vertex -624.274 94.8318 26.2329 + endloop + endfacet + facet normal -0.270639 -0.591051 0.759877 + outer loop + vertex -629.895 98.2546 27.0601 + vertex -629.846 96.4211 25.6515 + vertex -627.093 97.2481 27.2752 + endloop + endfacet + facet normal -0.253768 -0.617323 0.744657 + outer loop + vertex -629.846 96.4211 25.6515 + vertex -624.274 94.8318 26.2329 + vertex -627.093 97.2481 27.2752 + endloop + endfacet + facet normal -0.286972 -0.675486 0.679239 + outer loop + vertex -618.738 95.077 28.6412 + vertex -621.414 95.6196 28.0505 + vertex -618.718 93.203 26.786 + endloop + endfacet + facet normal -0.275419 -0.644888 0.712926 + outer loop + vertex -624.306 96.6838 27.8956 + vertex -624.274 94.8318 26.2329 + vertex -621.414 95.6196 28.0505 + endloop + endfacet + facet normal -0.263843 -0.661567 0.701937 + outer loop + vertex -624.274 94.8318 26.2329 + vertex -618.718 93.203 26.786 + vertex -621.414 95.6196 28.0505 + endloop + endfacet + facet normal -0.231197 -0.508883 0.829208 + outer loop + vertex -641.018 101.132 25.5267 + vertex -639.873 99.055 24.5712 + vertex -636.679 99.8049 25.9221 + endloop + endfacet + facet normal -0.221074 -0.531394 0.817769 + outer loop + vertex -636.679 99.8049 25.9221 + vertex -639.873 99.055 24.5712 + vertex -634.985 97.6047 24.9501 + endloop + endfacet + facet normal -0.271622 -0.590899 0.759645 + outer loop + vertex -629.895 98.2546 27.0601 + vertex -632.753 98.7463 26.4207 + vertex -629.846 96.4211 25.6515 + endloop + endfacet + facet normal -0.248691 -0.545086 0.800646 + outer loop + vertex -636.679 99.8049 25.9221 + vertex -634.985 97.6047 24.9501 + vertex -632.753 98.7463 26.4207 + endloop + endfacet + facet normal -0.237211 -0.559332 0.794279 + outer loop + vertex -634.985 97.6047 24.9501 + vertex -629.846 96.4211 25.6515 + vertex -632.753 98.7463 26.4207 + endloop + endfacet + facet normal -0.204824 -0.414419 0.886738 + outer loop + vertex -651.454 104.397 24.6366 + vertex -650.233 102.32 23.948 + vertex -645.981 102.681 25.0986 + endloop + endfacet + facet normal -0.195323 -0.460313 0.866003 + outer loop + vertex -645.981 102.681 25.0986 + vertex -650.233 102.32 23.948 + vertex -644.932 100.651 24.2561 + endloop + endfacet + facet normal -0.220046 -0.468724 0.855498 + outer loop + vertex -645.981 102.681 25.0986 + vertex -644.932 100.651 24.2561 + vertex -641.018 101.132 25.5267 + endloop + endfacet + facet normal -0.210561 -0.501955 0.838872 + outer loop + vertex -641.018 101.132 25.5267 + vertex -644.932 100.651 24.2561 + vertex -639.873 99.055 24.5712 + endloop + endfacet + facet normal -0.158945 -0.337341 0.927867 + outer loop + vertex -661.874 107.87 24.0339 + vertex -660.841 105.835 23.4709 + vertex -656.81 106.14 24.2723 + endloop + endfacet + facet normal -0.156189 -0.356305 0.921223 + outer loop + vertex -656.81 106.14 24.2723 + vertex -660.841 105.835 23.4709 + vertex -655.588 104.05 23.6715 + endloop + endfacet + facet normal -0.181926 -0.3686 0.911612 + outer loop + vertex -656.81 106.14 24.2723 + vertex -655.588 104.05 23.6715 + vertex -651.454 104.397 24.6366 + endloop + endfacet + facet normal -0.176158 -0.401546 0.898738 + outer loop + vertex -651.454 104.397 24.6366 + vertex -655.588 104.05 23.6715 + vertex -650.233 102.32 23.948 + endloop + endfacet + facet normal -0.129291 -0.306429 0.943072 + outer loop + vertex -672.138 111.511 23.7667 + vertex -671.266 109.554 23.2503 + vertex -666.934 109.654 23.8767 + endloop + endfacet + facet normal -0.128924 -0.311745 0.941379 + outer loop + vertex -666.934 109.654 23.8767 + vertex -671.266 109.554 23.2503 + vertex -666.036 107.669 23.3425 + endloop + endfacet + facet normal -0.140603 -0.316181 0.938222 + outer loop + vertex -666.934 109.654 23.8767 + vertex -666.036 107.669 23.3425 + vertex -661.874 107.87 24.0339 + endloop + endfacet + facet normal -0.139279 -0.329051 0.933984 + outer loop + vertex -661.874 107.87 24.0339 + vertex -666.036 107.669 23.3425 + vertex -660.841 105.835 23.4709 + endloop + endfacet + facet normal -0.115694 -0.301766 0.946336 + outer loop + vertex -682.608 115.369 23.6854 + vertex -682.029 113.485 23.1552 + vertex -677.388 113.404 23.6967 + endloop + endfacet + facet normal -0.115755 -0.298612 0.947329 + outer loop + vertex -677.388 113.404 23.6967 + vertex -682.029 113.485 23.1552 + vertex -676.59 111.468 23.1841 + endloop + endfacet + facet normal -0.120941 -0.300426 0.946106 + outer loop + vertex -677.388 113.404 23.6967 + vertex -676.59 111.468 23.1841 + vertex -672.138 111.511 23.7667 + endloop + endfacet + facet normal -0.1208 -0.303217 0.945234 + outer loop + vertex -672.138 111.511 23.7667 + vertex -676.59 111.468 23.1841 + vertex -671.266 109.554 23.2503 + endloop + endfacet + facet normal -0.119566 -0.316961 0.940872 + outer loop + vertex -692.877 119.323 23.7116 + vertex -691.592 117.62 23.3009 + vertex -687.715 117.381 23.7132 + endloop + endfacet + facet normal -0.119299 -0.306705 0.944298 + outer loop + vertex -687.715 117.381 23.7132 + vertex -691.592 117.62 23.3009 + vertex -687.385 115.658 23.1954 + endloop + endfacet + facet normal -0.115421 -0.306162 0.944957 + outer loop + vertex -687.715 117.381 23.7132 + vertex -687.385 115.658 23.1954 + vertex -682.608 115.369 23.6854 + endloop + endfacet + facet normal -0.1153 -0.301668 0.946416 + outer loop + vertex -682.608 115.369 23.6854 + vertex -687.385 115.658 23.1954 + vertex -682.029 113.485 23.1552 + endloop + endfacet + facet normal -0.107863 -0.27529 0.955291 + outer loop + vertex -703.318 123.308 23.6947 + vertex -701.975 121.183 23.2338 + vertex -698.114 121.279 23.6976 + endloop + endfacet + facet normal -0.107472 -0.281869 0.953415 + outer loop + vertex -698.114 121.279 23.6976 + vertex -701.975 121.183 23.2338 + vertex -696.954 119.138 23.1954 + endloop + endfacet + facet normal -0.107899 -0.282075 0.953305 + outer loop + vertex -698.114 121.279 23.6976 + vertex -696.954 119.138 23.1954 + vertex -692.877 119.323 23.7116 + endloop + endfacet + facet normal -0.10576 -0.307686 0.945592 + outer loop + vertex -692.877 119.323 23.7116 + vertex -696.954 119.138 23.1954 + vertex -691.592 117.62 23.3009 + endloop + endfacet + facet normal -0.109208 -0.265951 0.957781 + outer loop + vertex -713.621 127.619 23.7219 + vertex -712.791 125.564 23.2459 + vertex -708.481 125.441 23.7032 + endloop + endfacet + facet normal -0.109212 -0.259517 0.959543 + outer loop + vertex -708.481 125.441 23.7032 + vertex -712.791 125.564 23.2459 + vertex -707.71 123.06 23.147 + endloop + endfacet + facet normal -0.105163 -0.258383 0.960301 + outer loop + vertex -708.481 125.441 23.7032 + vertex -707.71 123.06 23.147 + vertex -703.318 123.308 23.6947 + endloop + endfacet + facet normal -0.103853 -0.272996 0.956393 + outer loop + vertex -703.318 123.308 23.6947 + vertex -707.71 123.06 23.147 + vertex -701.975 121.183 23.2338 + endloop + endfacet + facet normal -0.114586 -0.264952 0.957429 + outer loop + vertex -723.925 132.127 23.7564 + vertex -723.208 130.11 23.2842 + vertex -718.742 129.846 23.7455 + endloop + endfacet + facet normal -0.114368 -0.257836 0.959396 + outer loop + vertex -718.742 129.846 23.7455 + vertex -723.208 130.11 23.2842 + vertex -718.416 127.596 23.1796 + endloop + endfacet + facet normal -0.107373 -0.257078 0.960407 + outer loop + vertex -718.742 129.846 23.7455 + vertex -718.416 127.596 23.1796 + vertex -713.621 127.619 23.7219 + endloop + endfacet + facet normal -0.107088 -0.265198 0.958229 + outer loop + vertex -713.621 127.619 23.7219 + vertex -718.416 127.596 23.1796 + vertex -712.791 125.564 23.2459 + endloop + endfacet + facet normal -0.121424 -0.26393 0.956869 + outer loop + vertex -734.363 136.888 23.7548 + vertex -733.733 134.885 23.2823 + vertex -729.111 134.466 23.7531 + endloop + endfacet + facet normal -0.120693 -0.252234 0.96011 + outer loop + vertex -729.111 134.466 23.7531 + vertex -733.733 134.885 23.2823 + vertex -728.873 132.257 23.203 + endloop + endfacet + facet normal -0.114121 -0.251756 0.961039 + outer loop + vertex -729.111 134.466 23.7531 + vertex -728.873 132.257 23.203 + vertex -723.925 132.127 23.7564 + endloop + endfacet + facet normal -0.114073 -0.264793 0.957534 + outer loop + vertex -723.925 132.127 23.7564 + vertex -728.873 132.257 23.203 + vertex -723.208 130.11 23.2842 + endloop + endfacet + facet normal -0.139401 -0.276994 0.950706 + outer loop + vertex -744.998 141.934 23.7016 + vertex -744.319 139.86 23.1968 + vertex -739.697 139.403 23.7415 + endloop + endfacet + facet normal -0.138447 -0.26217 0.955039 + outer loop + vertex -739.697 139.403 23.7415 + vertex -744.319 139.86 23.1968 + vertex -739.467 137.157 23.1582 + endloop + endfacet + facet normal -0.125634 -0.261376 0.957026 + outer loop + vertex -739.697 139.403 23.7415 + vertex -739.467 137.157 23.1582 + vertex -734.363 136.888 23.7548 + endloop + endfacet + facet normal -0.125708 -0.265072 0.955999 + outer loop + vertex -734.363 136.888 23.7548 + vertex -739.467 137.157 23.1582 + vertex -733.733 134.885 23.2823 + endloop + endfacet + facet normal -0.152698 -0.284323 0.94649 + outer loop + vertex -755.11 146.997 23.6148 + vertex -754.432 144.866 23.084 + vertex -750.125 144.455 23.6557 + endloop + endfacet + facet normal -0.151856 -0.269114 0.951061 + outer loop + vertex -750.125 144.455 23.6557 + vertex -754.432 144.866 23.084 + vertex -749.845 142.153 23.049 + endloop + endfacet + facet normal -0.140489 -0.268254 0.953049 + outer loop + vertex -750.125 144.455 23.6557 + vertex -749.845 142.153 23.049 + vertex -744.998 141.934 23.7016 + endloop + endfacet + facet normal -0.140548 -0.277307 0.950446 + outer loop + vertex -744.998 141.934 23.7016 + vertex -749.845 142.153 23.049 + vertex -744.319 139.86 23.1968 + endloop + endfacet + facet normal -0.163059 -0.287986 0.94365 + outer loop + vertex -765.107 152.366 23.5504 + vertex -764.354 150.145 23.0024 + vertex -760.066 149.615 23.5818 + endloop + endfacet + facet normal -0.161884 -0.27356 0.948134 + outer loop + vertex -760.066 149.615 23.5818 + vertex -764.354 150.145 23.0024 + vertex -759.794 147.267 22.9506 + endloop + endfacet + facet normal -0.15045 -0.272801 0.950234 + outer loop + vertex -760.066 149.615 23.5818 + vertex -759.794 147.267 22.9506 + vertex -755.11 146.997 23.6148 + endloop + endfacet + facet normal -0.150621 -0.283785 0.946984 + outer loop + vertex -755.11 146.997 23.6148 + vertex -759.794 147.267 22.9506 + vertex -754.432 144.866 23.084 + endloop + endfacet + facet normal -0.175195 -0.27929 0.944089 + outer loop + vertex -774.779 157.824 23.4041 + vertex -774.387 155.815 22.8823 + vertex -770.069 155.114 23.4762 + endloop + endfacet + facet normal -0.174265 -0.271488 0.946534 + outer loop + vertex -770.069 155.114 23.4762 + vertex -774.387 155.815 22.8823 + vertex -769.814 152.782 22.8545 + endloop + endfacet + facet normal -0.164159 -0.270907 0.948505 + outer loop + vertex -770.069 155.114 23.4762 + vertex -769.814 152.782 22.8545 + vertex -765.107 152.366 23.5504 + endloop + endfacet + facet normal -0.164925 -0.288499 0.943169 + outer loop + vertex -765.107 152.366 23.5504 + vertex -769.814 152.782 22.8545 + vertex -764.354 150.145 23.0024 + endloop + endfacet + facet normal -0.198072 -0.28651 0.937379 + outer loop + vertex -784.125 163.539 23.2354 + vertex -784.12 161.72 22.6804 + vertex -779.425 160.634 23.3404 + endloop + endfacet + facet normal -0.195098 -0.270382 0.942778 + outer loop + vertex -779.425 160.634 23.3404 + vertex -784.12 161.72 22.6804 + vertex -779.781 158.613 22.6874 + endloop + endfacet + facet normal -0.178634 -0.273995 0.944996 + outer loop + vertex -779.425 160.634 23.3404 + vertex -779.781 158.613 22.6874 + vertex -774.779 157.824 23.4041 + endloop + endfacet + facet normal -0.179294 -0.279845 0.943154 + outer loop + vertex -774.779 157.824 23.4041 + vertex -779.781 158.613 22.6874 + vertex -774.387 155.815 22.8823 + endloop + endfacet + facet normal -0.221885 -0.296563 0.92888 + outer loop + vertex -793.654 169.753 22.9841 + vertex -794.001 167.938 22.3214 + vertex -788.909 166.565 23.0998 + endloop + endfacet + facet normal -0.218251 -0.279624 0.934974 + outer loop + vertex -788.909 166.565 23.0998 + vertex -794.001 167.938 22.3214 + vertex -788.986 164.477 22.4572 + endloop + endfacet + facet normal -0.204329 -0.280979 0.93771 + outer loop + vertex -788.909 166.565 23.0998 + vertex -788.986 164.477 22.4572 + vertex -784.125 163.539 23.2354 + endloop + endfacet + facet normal -0.205045 -0.286107 0.936002 + outer loop + vertex -784.125 163.539 23.2354 + vertex -788.986 164.477 22.4572 + vertex -784.12 161.72 22.6804 + endloop + endfacet + facet normal -0.240633 -0.298952 0.92343 + outer loop + vertex -802.909 176.17 22.6992 + vertex -803.289 174.514 22.0643 + vertex -798.326 172.968 22.8573 + endloop + endfacet + facet normal -0.241176 -0.301135 0.922579 + outer loop + vertex -798.326 172.968 22.8573 + vertex -803.289 174.514 22.0643 + vertex -798.733 171.272 22.197 + endloop + endfacet + facet normal -0.233835 -0.303353 0.923741 + outer loop + vertex -798.326 172.968 22.8573 + vertex -798.733 171.272 22.197 + vertex -793.654 169.753 22.9841 + endloop + endfacet + facet normal -0.231621 -0.294114 0.92728 + outer loop + vertex -793.654 169.753 22.9841 + vertex -798.733 171.272 22.197 + vertex -794.001 167.938 22.3214 + endloop + endfacet + facet normal -0.245571 -0.286942 0.925937 + outer loop + vertex -811.746 182.686 22.3983 + vertex -812.168 181.045 21.7777 + vertex -807.364 179.387 22.5378 + endloop + endfacet + facet normal -0.246108 -0.288832 0.925207 + outer loop + vertex -807.364 179.387 22.5378 + vertex -812.168 181.045 21.7777 + vertex -807.754 177.749 21.923 + endloop + endfacet + facet normal -0.242827 -0.289821 0.925764 + outer loop + vertex -807.364 179.387 22.5378 + vertex -807.754 177.749 21.923 + vertex -802.909 176.17 22.6992 + endloop + endfacet + facet normal -0.244906 -0.297697 0.922712 + outer loop + vertex -802.909 176.17 22.6992 + vertex -807.754 177.749 21.923 + vertex -803.289 174.514 22.0643 + endloop + endfacet + facet normal -0.259111 -0.286769 0.922294 + outer loop + vertex -820.29 189.451 22.1323 + vertex -820.744 187.753 21.4766 + vertex -816.058 186.054 22.2649 + endloop + endfacet + facet normal -0.258403 -0.28438 0.923231 + outer loop + vertex -816.058 186.054 22.2649 + vertex -820.744 187.753 21.4766 + vertex -816.512 184.401 21.6285 + endloop + endfacet + facet normal -0.252326 -0.286448 0.924272 + outer loop + vertex -816.058 186.054 22.2649 + vertex -816.512 184.401 21.6285 + vertex -811.746 182.686 22.3983 + endloop + endfacet + facet normal -0.251872 -0.284916 0.924869 + outer loop + vertex -811.746 182.686 22.3983 + vertex -816.512 184.401 21.6285 + vertex -812.168 181.045 21.7777 + endloop + endfacet + facet normal -0.269819 -0.284208 0.920013 + outer loop + vertex -828.325 196.187 21.8809 + vertex -828.782 194.397 21.194 + vertex -824.38 192.838 22.0033 + endloop + endfacet + facet normal -0.270062 -0.285068 0.919676 + outer loop + vertex -824.38 192.838 22.0033 + vertex -828.782 194.397 21.194 + vertex -824.834 191.088 21.3275 + endloop + endfacet + facet normal -0.266143 -0.286368 0.920414 + outer loop + vertex -824.38 192.838 22.0033 + vertex -824.834 191.088 21.3275 + vertex -820.29 189.451 22.1323 + endloop + endfacet + facet normal -0.265622 -0.284573 0.921121 + outer loop + vertex -820.29 189.451 22.1323 + vertex -824.834 191.088 21.3275 + vertex -820.744 187.753 21.4766 + endloop + endfacet + facet normal -0.267908 -0.269788 0.9249 + outer loop + vertex -835.741 202.631 21.6344 + vertex -836.383 201.001 20.9731 + vertex -832.116 199.473 21.7634 + endloop + endfacet + facet normal -0.270523 -0.278884 0.921434 + outer loop + vertex -832.116 199.473 21.7634 + vertex -836.383 201.001 20.9731 + vertex -832.617 197.7 21.0796 + endloop + endfacet + facet normal -0.270352 -0.278944 0.921466 + outer loop + vertex -832.116 199.473 21.7634 + vertex -832.617 197.7 21.0796 + vertex -828.325 196.187 21.8809 + endloop + endfacet + facet normal -0.271657 -0.283604 0.919658 + outer loop + vertex -828.325 196.187 21.8809 + vertex -832.617 197.7 21.0796 + vertex -828.782 194.397 21.194 + endloop + endfacet + facet normal -0.272786 -0.276325 0.921538 + outer loop + vertex -843.01 209.261 21.4645 + vertex -843.932 207.803 20.7543 + vertex -839.243 205.769 21.5323 + endloop + endfacet + facet normal -0.269495 -0.26736 0.925144 + outer loop + vertex -839.243 205.769 21.5323 + vertex -843.932 207.803 20.7543 + vertex -840.123 204.337 20.8622 + endloop + endfacet + facet normal -0.267638 -0.268588 0.925327 + outer loop + vertex -839.243 205.769 21.5323 + vertex -840.123 204.337 20.8622 + vertex -835.741 202.631 21.6344 + endloop + endfacet + facet normal -0.268009 -0.269742 0.924884 + outer loop + vertex -835.741 202.631 21.6344 + vertex -840.123 204.337 20.8622 + vertex -836.383 201.001 20.9731 + endloop + endfacet + facet normal -0.282546 -0.284666 0.916042 + outer loop + vertex -851.265 217.537 21.4897 + vertex -851.678 215.378 20.6913 + vertex -847.148 213.25 21.4273 + endloop + endfacet + facet normal -0.280138 -0.278647 0.918629 + outer loop + vertex -847.148 213.25 21.4273 + vertex -851.678 215.378 20.6913 + vertex -847.862 211.5 20.6787 + endloop + endfacet + facet normal -0.27789 -0.279718 0.918986 + outer loop + vertex -847.148 213.25 21.4273 + vertex -847.862 211.5 20.6787 + vertex -843.01 209.261 21.4645 + endloop + endfacet + facet normal -0.27576 -0.274306 0.921256 + outer loop + vertex -843.01 209.261 21.4645 + vertex -847.862 211.5 20.6787 + vertex -843.932 207.803 20.7543 + endloop + endfacet + facet normal -0.286991 -0.277258 0.916932 + outer loop + vertex -853.682 219.794 21.4155 + vertex -854.855 219.181 20.8631 + vertex -851.265 217.537 21.4897 + endloop + endfacet + facet normal -0.289136 -0.282853 0.914546 + outer loop + vertex -851.265 217.537 21.4897 + vertex -854.855 219.181 20.8631 + vertex -851.678 215.378 20.6913 + endloop + endfacet + facet normal -0.147919 -0.532309 0.833527 + outer loop + vertex -608.072 87.2563 25.2404 + vertex -607.055 84.3011 23.5336 + vertex -605.656 85.761 24.7142 + endloop + endfacet + facet normal -0.190543 -0.500401 0.844566 + outer loop + vertex -605.656 85.761 24.7142 + vertex -607.055 84.3011 23.5336 + vertex -604.838 82.9711 23.2458 + endloop + endfacet + facet normal -0.232111 -0.663268 0.711477 + outer loop + vertex -609.518 90.6719 27.9525 + vertex -608.072 87.2563 25.2404 + vertex -607.112 89.5333 27.6761 + endloop + endfacet + facet normal -0.250888 -0.655872 0.71196 + outer loop + vertex -607.112 89.5333 27.6761 + vertex -608.072 87.2563 25.2404 + vertex -605.656 85.761 24.7142 + endloop + endfacet + facet normal -0.201433 -0.504762 0.839429 + outer loop + vertex -616.808 90.0517 24.8826 + vertex -615.587 87.1799 23.4486 + vertex -611.853 88.5868 25.1907 + endloop + endfacet + facet normal -0.185289 -0.531587 0.826489 + outer loop + vertex -611.853 88.5868 25.1907 + vertex -615.587 87.1799 23.4486 + vertex -610.683 85.6683 23.5757 + endloop + endfacet + facet normal -0.26147 -0.610225 0.747836 + outer loop + vertex -618.718 93.203 26.786 + vertex -616.808 90.0517 24.8826 + vertex -613.638 91.8379 27.4484 + endloop + endfacet + facet normal -0.234242 -0.638007 0.733538 + outer loop + vertex -613.638 91.8379 27.4484 + vertex -616.808 90.0517 24.8826 + vertex -611.853 88.5868 25.1907 + endloop + endfacet + facet normal -0.270022 -0.644814 0.715055 + outer loop + vertex -613.638 91.8379 27.4484 + vertex -611.853 88.5868 25.1907 + vertex -609.518 90.6719 27.9525 + endloop + endfacet + facet normal -0.243014 -0.664254 0.706902 + outer loop + vertex -609.518 90.6719 27.9525 + vertex -611.853 88.5868 25.1907 + vertex -608.072 87.2563 25.2404 + endloop + endfacet + facet normal -0.198794 -0.53429 0.821593 + outer loop + vertex -611.853 88.5868 25.1907 + vertex -610.683 85.6683 23.5757 + vertex -608.072 87.2563 25.2404 + endloop + endfacet + facet normal -0.193875 -0.539819 0.819151 + outer loop + vertex -608.072 87.2563 25.2404 + vertex -610.683 85.6683 23.5757 + vertex -607.055 84.3011 23.5336 + endloop + endfacet + facet normal -0.178638 -0.429534 0.885206 + outer loop + vertex -627.953 93.4015 24.2384 + vertex -626.858 90.6079 23.1039 + vertex -622.329 91.6927 24.5443 + endloop + endfacet + facet normal -0.166242 -0.462374 0.870962 + outer loop + vertex -622.329 91.6927 24.5443 + vertex -626.858 90.6079 23.1039 + vertex -621.148 88.8476 23.2592 + endloop + endfacet + facet normal -0.236 -0.529314 0.814942 + outer loop + vertex -629.846 96.4211 25.6515 + vertex -627.953 93.4015 24.2384 + vertex -624.274 94.8318 26.2329 + endloop + endfacet + facet normal -0.214292 -0.562392 0.79862 + outer loop + vertex -624.274 94.8318 26.2329 + vertex -627.953 93.4015 24.2384 + vertex -622.329 91.6927 24.5443 + endloop + endfacet + facet normal -0.245812 -0.57292 0.781881 + outer loop + vertex -624.274 94.8318 26.2329 + vertex -622.329 91.6927 24.5443 + vertex -618.718 93.203 26.786 + endloop + endfacet + facet normal -0.225422 -0.600203 0.767425 + outer loop + vertex -618.718 93.203 26.786 + vertex -622.329 91.6927 24.5443 + vertex -616.808 90.0517 24.8826 + endloop + endfacet + facet normal -0.192247 -0.469101 0.861966 + outer loop + vertex -622.329 91.6927 24.5443 + vertex -621.148 88.8476 23.2592 + vertex -616.808 90.0517 24.8826 + endloop + endfacet + facet normal -0.178599 -0.49926 0.847845 + outer loop + vertex -616.808 90.0517 24.8826 + vertex -621.148 88.8476 23.2592 + vertex -615.587 87.1799 23.4486 + endloop + endfacet + facet normal -0.154608 -0.339456 0.927829 + outer loop + vertex -638.714 96.6423 23.62 + vertex -638.032 94.1252 22.8128 + vertex -633.415 95.021 23.91 + endloop + endfacet + facet normal -0.144007 -0.377876 0.914588 + outer loop + vertex -633.415 95.021 23.91 + vertex -638.032 94.1252 22.8128 + vertex -632.456 92.3534 22.9587 + endloop + endfacet + facet normal -0.198593 -0.440541 0.875491 + outer loop + vertex -639.873 99.055 24.5712 + vertex -638.714 96.6423 23.62 + vertex -634.985 97.6047 24.9501 + endloop + endfacet + facet normal -0.189159 -0.46351 0.865666 + outer loop + vertex -634.985 97.6047 24.9501 + vertex -638.714 96.6423 23.62 + vertex -633.415 95.021 23.91 + endloop + endfacet + facet normal -0.226059 -0.478929 0.848248 + outer loop + vertex -634.985 97.6047 24.9501 + vertex -633.415 95.021 23.91 + vertex -629.846 96.4211 25.6515 + endloop + endfacet + facet normal -0.203217 -0.516627 0.831745 + outer loop + vertex -629.846 96.4211 25.6515 + vertex -633.415 95.021 23.91 + vertex -627.953 93.4015 24.2384 + endloop + endfacet + facet normal -0.168528 -0.38424 0.907721 + outer loop + vertex -633.415 95.021 23.91 + vertex -632.456 92.3534 22.9587 + vertex -627.953 93.4015 24.2384 + endloop + endfacet + facet normal -0.155135 -0.423321 0.892599 + outer loop + vertex -627.953 93.4015 24.2384 + vertex -632.456 92.3534 22.9587 + vertex -626.858 90.6079 23.1039 + endloop + endfacet + facet normal -0.132427 -0.309466 0.941644 + outer loop + vertex -649.076 99.9999 23.2289 + vertex -647.832 97.8812 22.7075 + vertex -643.854 98.35 23.4211 + endloop + endfacet + facet normal -0.132271 -0.310373 0.941368 + outer loop + vertex -643.854 98.35 23.4211 + vertex -647.832 97.8812 22.7075 + vertex -643.504 96.0543 22.7133 + endloop + endfacet + facet normal -0.168958 -0.367658 0.914484 + outer loop + vertex -650.233 102.32 23.948 + vertex -649.076 99.9999 23.2289 + vertex -644.932 100.651 24.2561 + endloop + endfacet + facet normal -0.160273 -0.402283 0.901377 + outer loop + vertex -644.932 100.651 24.2561 + vertex -649.076 99.9999 23.2289 + vertex -643.854 98.35 23.4211 + endloop + endfacet + facet normal -0.185166 -0.410807 0.892721 + outer loop + vertex -644.932 100.651 24.2561 + vertex -643.854 98.35 23.4211 + vertex -639.873 99.055 24.5712 + endloop + endfacet + facet normal -0.178329 -0.433831 0.88317 + outer loop + vertex -639.873 99.055 24.5712 + vertex -643.854 98.35 23.4211 + vertex -638.714 96.6423 23.62 + endloop + endfacet + facet normal -0.139756 -0.311106 0.940043 + outer loop + vertex -643.854 98.35 23.4211 + vertex -643.504 96.0543 22.7133 + vertex -638.714 96.6423 23.62 + endloop + endfacet + facet normal -0.135267 -0.335626 0.932233 + outer loop + vertex -638.714 96.6423 23.62 + vertex -643.504 96.0543 22.7133 + vertex -638.032 94.1252 22.8128 + endloop + endfacet + facet normal -0.0978155 -0.222605 0.969989 + outer loop + vertex -659.878 103.437 22.9013 + vertex -658.527 100.94 22.4645 + vertex -654.459 101.673 23.0432 + endloop + endfacet + facet normal -0.0938242 -0.241483 0.965859 + outer loop + vertex -654.459 101.673 23.0432 + vertex -658.527 100.94 22.4645 + vertex -653.339 99.0904 22.5062 + endloop + endfacet + facet normal -0.130948 -0.278591 0.951441 + outer loop + vertex -660.841 105.835 23.4709 + vertex -659.878 103.437 22.9013 + vertex -655.588 104.05 23.6715 + endloop + endfacet + facet normal -0.125112 -0.308678 0.942902 + outer loop + vertex -655.588 104.05 23.6715 + vertex -659.878 103.437 22.9013 + vertex -654.459 101.673 23.0432 + endloop + endfacet + facet normal -0.151457 -0.319233 0.935495 + outer loop + vertex -655.588 104.05 23.6715 + vertex -654.459 101.673 23.0432 + vertex -650.233 102.32 23.948 + endloop + endfacet + facet normal -0.142948 -0.35732 0.922978 + outer loop + vertex -650.233 102.32 23.948 + vertex -654.459 101.673 23.0432 + vertex -649.076 99.9999 23.2289 + endloop + endfacet + facet normal -0.1103 -0.247926 0.962479 + outer loop + vertex -654.459 101.673 23.0432 + vertex -653.339 99.0904 22.5062 + vertex -649.076 99.9999 23.2289 + endloop + endfacet + facet normal -0.0989509 -0.292176 0.951232 + outer loop + vertex -649.076 99.9999 23.2289 + vertex -653.339 99.0904 22.5062 + vertex -647.832 97.8812 22.7075 + endloop + endfacet + facet normal -0.078162 -0.185494 0.979532 + outer loop + vertex -670.631 107.247 22.7454 + vertex -669.769 104.811 22.3529 + vertex -665.268 105.317 22.8079 + endloop + endfacet + facet normal -0.0778272 -0.188058 0.97907 + outer loop + vertex -665.268 105.317 22.8079 + vertex -669.769 104.811 22.3529 + vertex -664.465 102.497 22.3301 + endloop + endfacet + facet normal -0.103408 -0.239758 0.96531 + outer loop + vertex -671.266 109.554 23.2503 + vertex -670.631 107.247 22.7454 + vertex -666.036 107.669 23.3425 + endloop + endfacet + facet normal -0.101896 -0.252016 0.962343 + outer loop + vertex -666.036 107.669 23.3425 + vertex -670.631 107.247 22.7454 + vertex -665.268 105.317 22.8079 + endloop + endfacet + facet normal -0.113931 -0.255434 0.96009 + outer loop + vertex -666.036 107.669 23.3425 + vertex -665.268 105.317 22.8079 + vertex -660.841 105.835 23.4709 + endloop + endfacet + facet normal -0.111388 -0.271795 0.955887 + outer loop + vertex -660.841 105.835 23.4709 + vertex -665.268 105.317 22.8079 + vertex -659.878 103.437 22.9013 + endloop + endfacet + facet normal -0.0830423 -0.189426 0.978377 + outer loop + vertex -665.268 105.317 22.8079 + vertex -664.465 102.497 22.3301 + vertex -659.878 103.437 22.9013 + endloop + endfacet + facet normal -0.0777821 -0.21248 0.974065 + outer loop + vertex -659.878 103.437 22.9013 + vertex -664.465 102.497 22.3301 + vertex -658.527 100.94 22.4645 + endloop + endfacet + facet normal -0.0687424 -0.172845 0.982547 + outer loop + vertex -681.587 111.195 22.6591 + vertex -680.812 108.768 22.2864 + vertex -676.005 109.183 22.6957 + endloop + endfacet + facet normal -0.0692068 -0.168225 0.983316 + outer loop + vertex -676.005 109.183 22.6957 + vertex -680.812 108.768 22.2864 + vertex -675.652 106.484 22.2587 + endloop + endfacet + facet normal -0.0894516 -0.227345 0.969697 + outer loop + vertex -682.029 113.485 23.1552 + vertex -681.587 111.195 22.6591 + vertex -676.59 111.468 23.1841 + endloop + endfacet + facet normal -0.0892443 -0.229978 0.969095 + outer loop + vertex -676.59 111.468 23.1841 + vertex -681.587 111.195 22.6591 + vertex -676.005 109.183 22.6957 + endloop + endfacet + facet normal -0.0952266 -0.231318 0.968206 + outer loop + vertex -676.59 111.468 23.1841 + vertex -676.005 109.183 22.6957 + vertex -671.266 109.554 23.2503 + endloop + endfacet + facet normal -0.0945616 -0.237636 0.966741 + outer loop + vertex -671.266 109.554 23.2503 + vertex -676.005 109.183 22.6957 + vertex -670.631 107.247 22.7454 + endloop + endfacet + facet normal -0.069724 -0.168285 0.983269 + outer loop + vertex -676.005 109.183 22.6957 + vertex -675.652 106.484 22.2587 + vertex -670.631 107.247 22.7454 + endloop + endfacet + facet normal -0.0674298 -0.181931 0.980997 + outer loop + vertex -670.631 107.247 22.7454 + vertex -675.652 106.484 22.2587 + vertex -669.769 104.811 22.3529 + endloop + endfacet + facet normal -0.0597526 -0.174739 0.9828 + outer loop + vertex -693.67 116.416 22.8236 + vertex -695.308 113.827 22.2637 + vertex -687.699 113.517 22.6713 + endloop + endfacet + facet normal -0.0594457 -0.164955 0.984508 + outer loop + vertex -687.699 113.517 22.6713 + vertex -695.308 113.827 22.2637 + vertex -687.279 110.567 22.2023 + endloop + endfacet + facet normal -0.0856952 -0.2359 0.967991 + outer loop + vertex -691.592 117.62 23.3009 + vertex -693.67 116.416 22.8236 + vertex -687.385 115.658 23.1954 + endloop + endfacet + facet normal -0.0845629 -0.225209 0.970634 + outer loop + vertex -687.385 115.658 23.1954 + vertex -693.67 116.416 22.8236 + vertex -687.699 113.517 22.6713 + endloop + endfacet + facet normal -0.0841221 -0.225279 0.970656 + outer loop + vertex -687.385 115.658 23.1954 + vertex -687.699 113.517 22.6713 + vertex -682.029 113.485 23.1552 + endloop + endfacet + facet normal -0.0841054 -0.22646 0.970382 + outer loop + vertex -682.029 113.485 23.1552 + vertex -687.699 113.517 22.6713 + vertex -681.587 111.195 22.6591 + endloop + endfacet + facet normal -0.0607751 -0.165126 0.984398 + outer loop + vertex -687.699 113.517 22.6713 + vertex -687.279 110.567 22.2023 + vertex -681.587 111.195 22.6591 + endloop + endfacet + facet normal -0.0601421 -0.170256 0.983563 + outer loop + vertex -681.587 111.195 22.6591 + vertex -687.279 110.567 22.2023 + vertex -680.812 108.768 22.2864 + endloop + endfacet + facet normal -0.0858152 -0.235708 0.968028 + outer loop + vertex -691.592 117.62 23.3009 + vertex -696.954 119.138 23.1954 + vertex -693.67 116.416 22.8236 + endloop + endfacet + facet normal -0.0626155 -0.172957 0.982937 + outer loop + vertex -695.308 113.827 22.2637 + vertex -693.67 116.416 22.8236 + vertex -703.947 118.756 22.5807 + endloop + endfacet + facet normal -0.0747894 -0.202034 0.976519 + outer loop + vertex -701.975 121.183 23.2338 + vertex -703.947 118.756 22.5807 + vertex -696.954 119.138 23.1954 + endloop + endfacet + facet normal -0.0733774 -0.221306 0.97244 + outer loop + vertex -693.67 116.416 22.8236 + vertex -696.954 119.138 23.1954 + vertex -703.947 118.756 22.5807 + endloop + endfacet + facet normal -0.0796659 -0.198181 0.976923 + outer loop + vertex -701.975 121.183 23.2338 + vertex -707.71 123.06 23.147 + vertex -703.947 118.756 22.5807 + endloop + endfacet + facet normal -0.0780627 -0.197009 0.977289 + outer loop + vertex -712.791 125.564 23.2459 + vertex -715.913 123.661 22.613 + vertex -707.71 123.06 23.147 + endloop + endfacet + facet normal -0.0780516 -0.196823 0.977327 + outer loop + vertex -715.913 123.661 22.613 + vertex -703.947 118.756 22.5807 + vertex -707.71 123.06 23.147 + endloop + endfacet + facet normal -0.0810182 -0.192386 0.977969 + outer loop + vertex -712.791 125.564 23.2459 + vertex -718.416 127.596 23.1796 + vertex -715.913 123.661 22.613 + endloop + endfacet + facet normal -0.0837388 -0.200164 0.976177 + outer loop + vertex -723.208 130.11 23.2842 + vertex -726.693 128.371 22.6286 + vertex -718.416 127.596 23.1796 + endloop + endfacet + facet normal -0.0832251 -0.193725 0.977519 + outer loop + vertex -726.693 128.371 22.6286 + vertex -715.913 123.661 22.613 + vertex -718.416 127.596 23.1796 + endloop + endfacet + facet normal -0.0873042 -0.193414 0.977225 + outer loop + vertex -723.208 130.11 23.2842 + vertex -728.873 132.257 23.203 + vertex -726.693 128.371 22.6286 + endloop + endfacet + facet normal -0.0921559 -0.199913 0.97547 + outer loop + vertex -733.733 134.885 23.2823 + vertex -737.253 133.209 22.6062 + vertex -728.873 132.257 23.203 + endloop + endfacet + facet normal -0.0917489 -0.195777 0.976347 + outer loop + vertex -737.253 133.209 22.6062 + vertex -726.693 128.371 22.6286 + vertex -728.873 132.257 23.203 + endloop + endfacet + facet normal -0.0967453 -0.190828 0.976844 + outer loop + vertex -733.733 134.885 23.2823 + vertex -739.467 137.157 23.1582 + vertex -737.253 133.209 22.6062 + endloop + endfacet + facet normal -0.0999609 -0.193382 0.976018 + outer loop + vertex -744.319 139.86 23.1968 + vertex -747.693 138.199 22.5223 + vertex -739.467 137.157 23.1582 + endloop + endfacet + facet normal -0.099862 -0.192487 0.976205 + outer loop + vertex -747.693 138.199 22.5223 + vertex -737.253 133.209 22.6062 + vertex -739.467 137.157 23.1582 + endloop + endfacet + facet normal -0.103551 -0.186481 0.976986 + outer loop + vertex -744.319 139.86 23.1968 + vertex -749.845 142.153 23.049 + vertex -747.693 138.199 22.5223 + endloop + endfacet + facet normal -0.105159 -0.190449 0.976048 + outer loop + vertex -754.432 144.866 23.084 + vertex -757.841 143.313 22.4138 + vertex -749.845 142.153 23.049 + endloop + endfacet + facet normal -0.104727 -0.187089 0.976745 + outer loop + vertex -757.841 143.313 22.4138 + vertex -747.693 138.199 22.5223 + vertex -749.845 142.153 23.049 + endloop + endfacet + facet normal -0.107447 -0.185713 0.976712 + outer loop + vertex -754.432 144.866 23.084 + vertex -759.794 147.267 22.9506 + vertex -757.841 143.313 22.4138 + endloop + endfacet + facet normal -0.113926 -0.198028 0.973553 + outer loop + vertex -764.354 150.145 23.0024 + vertex -767.861 148.702 22.2988 + vertex -759.794 147.267 22.9506 + endloop + endfacet + facet normal -0.112314 -0.187985 0.975729 + outer loop + vertex -767.861 148.702 22.2988 + vertex -757.841 143.313 22.4138 + vertex -759.794 147.267 22.9506 + endloop + endfacet + facet normal -0.117814 -0.189205 0.974844 + outer loop + vertex -764.354 150.145 23.0024 + vertex -769.814 152.782 22.8545 + vertex -767.861 148.702 22.2988 + endloop + endfacet + facet normal -0.12832 -0.202419 0.970856 + outer loop + vertex -774.387 155.815 22.8823 + vertex -777.956 154.506 22.1377 + vertex -769.814 152.782 22.8545 + endloop + endfacet + facet normal -0.12654 -0.19313 0.972979 + outer loop + vertex -777.956 154.506 22.1377 + vertex -767.861 148.702 22.2988 + vertex -769.814 152.782 22.8545 + endloop + endfacet + facet normal -0.133468 -0.189473 0.972772 + outer loop + vertex -774.387 155.815 22.8823 + vertex -779.781 158.613 22.6874 + vertex -777.956 154.506 22.1377 + endloop + endfacet + facet normal -0.146817 -0.202892 0.968132 + outer loop + vertex -784.12 161.72 22.6804 + vertex -788.237 160.801 21.8634 + vertex -779.781 158.613 22.6874 + endloop + endfacet + facet normal -0.14476 -0.19415 0.970232 + outer loop + vertex -788.237 160.801 21.8634 + vertex -777.956 154.506 22.1377 + vertex -779.781 158.613 22.6874 + endloop + endfacet + facet normal -0.16857 -0.206494 0.963818 + outer loop + vertex -794.001 167.938 22.3214 + vertex -794.236 165.539 21.7665 + vertex -788.986 164.477 22.4572 + endloop + endfacet + facet normal -0.150756 -0.187476 0.970631 + outer loop + vertex -784.12 161.72 22.6804 + vertex -788.986 164.477 22.4572 + vertex -788.237 160.801 21.8634 + endloop + endfacet + facet normal -0.135105 -0.151017 0.979255 + outer loop + vertex -794.976 163.731 21.3857 + vertex -788.237 160.801 21.8634 + vertex -794.236 165.539 21.7665 + endloop + endfacet + facet normal -0.165751 -0.190052 0.967681 + outer loop + vertex -788.986 164.477 22.4572 + vertex -794.236 165.539 21.7665 + vertex -788.237 160.801 21.8634 + endloop + endfacet + facet normal -0.142503 -0.158933 0.976951 + outer loop + vertex -803.778 172.451 21.5064 + vertex -803.82 170.02 21.1049 + vertex -799.133 169.113 21.6409 + endloop + endfacet + facet normal -0.140853 -0.149384 0.978695 + outer loop + vertex -799.133 169.113 21.6409 + vertex -803.82 170.02 21.1049 + vertex -799.591 166.521 21.1794 + endloop + endfacet + facet normal -0.181868 -0.216293 0.95924 + outer loop + vertex -803.289 174.514 22.0643 + vertex -803.778 172.451 21.5064 + vertex -798.733 171.272 22.197 + endloop + endfacet + facet normal -0.18135 -0.213676 0.959924 + outer loop + vertex -798.733 171.272 22.197 + vertex -803.778 172.451 21.5064 + vertex -799.133 169.113 21.6409 + endloop + endfacet + facet normal -0.17656 -0.214732 0.960581 + outer loop + vertex -798.733 171.272 22.197 + vertex -799.133 169.113 21.6409 + vertex -794.001 167.938 22.3214 + endloop + endfacet + facet normal -0.174791 -0.205671 0.962885 + outer loop + vertex -794.001 167.938 22.3214 + vertex -799.133 169.113 21.6409 + vertex -794.236 165.539 21.7665 + endloop + endfacet + facet normal -0.134979 -0.150537 0.979346 + outer loop + vertex -799.133 169.113 21.6409 + vertex -799.591 166.521 21.1794 + vertex -794.236 165.539 21.7665 + endloop + endfacet + facet normal -0.135061 -0.151036 0.979258 + outer loop + vertex -794.236 165.539 21.7665 + vertex -799.591 166.521 21.1794 + vertex -794.976 163.731 21.3857 + endloop + endfacet + facet normal -0.152353 -0.159173 0.975424 + outer loop + vertex -812.721 179.009 21.2043 + vertex -812.891 176.625 20.7887 + vertex -808.287 175.722 21.3605 + endloop + endfacet + facet normal -0.151249 -0.15279 0.976616 + outer loop + vertex -808.287 175.722 21.3605 + vertex -812.891 176.625 20.7887 + vertex -808.844 173.142 20.8706 + endloop + endfacet + facet normal -0.193469 -0.21694 0.956821 + outer loop + vertex -812.168 181.045 21.7777 + vertex -812.721 179.009 21.2043 + vertex -807.754 177.749 21.923 + endloop + endfacet + facet normal -0.193033 -0.214909 0.957367 + outer loop + vertex -807.754 177.749 21.923 + vertex -812.721 179.009 21.2043 + vertex -808.287 175.722 21.3605 + endloop + endfacet + facet normal -0.187288 -0.216631 0.95812 + outer loop + vertex -807.754 177.749 21.923 + vertex -808.287 175.722 21.3605 + vertex -803.289 174.514 22.0643 + endloop + endfacet + facet normal -0.186937 -0.214911 0.958576 + outer loop + vertex -803.289 174.514 22.0643 + vertex -808.287 175.722 21.3605 + vertex -803.778 172.451 21.5064 + endloop + endfacet + facet normal -0.143769 -0.154566 0.977466 + outer loop + vertex -808.287 175.722 21.3605 + vertex -808.844 173.142 20.8706 + vertex -803.778 172.451 21.5064 + endloop + endfacet + facet normal -0.14426 -0.158862 0.976705 + outer loop + vertex -803.778 172.451 21.5064 + vertex -808.844 173.142 20.8706 + vertex -803.82 170.02 21.1049 + endloop + endfacet + facet normal -0.160725 -0.156457 0.97452 + outer loop + vertex -821.361 185.692 20.8767 + vertex -821.621 183.287 20.4476 + vertex -817.086 182.336 21.0429 + endloop + endfacet + facet normal -0.159612 -0.150443 0.975649 + outer loop + vertex -817.086 182.336 21.0429 + vertex -821.621 183.287 20.4476 + vertex -817.744 179.759 20.5378 + endloop + endfacet + facet normal -0.205595 -0.216303 0.954434 + outer loop + vertex -820.744 187.753 21.4766 + vertex -821.361 185.692 20.8767 + vertex -816.512 184.401 21.6285 + endloop + endfacet + facet normal -0.205054 -0.213885 0.955095 + outer loop + vertex -816.512 184.401 21.6285 + vertex -821.361 185.692 20.8767 + vertex -817.086 182.336 21.0429 + endloop + endfacet + facet normal -0.199446 -0.215669 0.955881 + outer loop + vertex -816.512 184.401 21.6285 + vertex -817.086 182.336 21.0429 + vertex -812.168 181.045 21.7777 + endloop + endfacet + facet normal -0.199326 -0.215128 0.956028 + outer loop + vertex -812.168 181.045 21.7777 + vertex -817.086 182.336 21.0429 + vertex -812.721 179.009 21.2043 + endloop + endfacet + facet normal -0.152323 -0.15247 0.976499 + outer loop + vertex -817.086 182.336 21.0429 + vertex -817.744 179.759 20.5378 + vertex -812.721 179.009 21.2043 + endloop + endfacet + facet normal -0.153154 -0.159096 0.975311 + outer loop + vertex -812.721 179.009 21.2043 + vertex -817.744 179.759 20.5378 + vertex -812.891 176.625 20.7887 + endloop + endfacet + facet normal -0.163437 -0.154856 0.974324 + outer loop + vertex -829.512 192.33 20.5673 + vertex -829.941 189.983 20.1224 + vertex -825.5 189.023 20.7146 + endloop + endfacet + facet normal -0.161742 -0.146005 0.975972 + outer loop + vertex -825.5 189.023 20.7146 + vertex -829.941 189.983 20.1224 + vertex -826.292 186.463 20.2005 + endloop + endfacet + facet normal -0.211821 -0.214223 0.953541 + outer loop + vertex -828.782 194.397 21.194 + vertex -829.512 192.33 20.5673 + vertex -824.834 191.088 21.3275 + endloop + endfacet + facet normal -0.211896 -0.214563 0.953448 + outer loop + vertex -824.834 191.088 21.3275 + vertex -829.512 192.33 20.5673 + vertex -825.5 189.023 20.7146 + endloop + endfacet + facet normal -0.210219 -0.215173 0.953682 + outer loop + vertex -824.834 191.088 21.3275 + vertex -825.5 189.023 20.7146 + vertex -820.744 187.753 21.4766 + endloop + endfacet + facet normal -0.210127 -0.214761 0.953795 + outer loop + vertex -820.744 187.753 21.4766 + vertex -825.5 189.023 20.7146 + vertex -821.361 185.692 20.8767 + endloop + endfacet + facet normal -0.156972 -0.147589 0.976513 + outer loop + vertex -825.5 189.023 20.7146 + vertex -826.292 186.463 20.2005 + vertex -821.361 185.692 20.8767 + endloop + endfacet + facet normal -0.158188 -0.156797 0.97488 + outer loop + vertex -821.361 185.692 20.8767 + vertex -826.292 186.463 20.2005 + vertex -821.621 183.287 20.4476 + endloop + endfacet + facet normal -0.1652 -0.157956 0.973529 + outer loop + vertex -837.286 199.02 20.3308 + vertex -837.882 196.755 19.862 + vertex -833.422 195.649 20.4394 + endloop + endfacet + facet normal -0.162393 -0.14537 0.975959 + outer loop + vertex -833.422 195.649 20.4394 + vertex -837.882 196.755 19.862 + vertex -834.414 193.193 19.9086 + endloop + endfacet + facet normal -0.212979 -0.212196 0.953736 + outer loop + vertex -836.383 201.001 20.9731 + vertex -837.286 199.02 20.3308 + vertex -832.617 197.7 21.0796 + endloop + endfacet + facet normal -0.213362 -0.2138 0.953292 + outer loop + vertex -832.617 197.7 21.0796 + vertex -837.286 199.02 20.3308 + vertex -833.422 195.649 20.4394 + endloop + endfacet + facet normal -0.212773 -0.214055 0.953367 + outer loop + vertex -832.617 197.7 21.0796 + vertex -833.422 195.649 20.4394 + vertex -828.782 194.397 21.194 + endloop + endfacet + facet normal -0.21273 -0.213864 0.953419 + outer loop + vertex -828.782 194.397 21.194 + vertex -833.422 195.649 20.4394 + vertex -829.512 192.33 20.5673 + endloop + endfacet + facet normal -0.157214 -0.147574 0.976476 + outer loop + vertex -833.422 195.649 20.4394 + vertex -834.414 193.193 19.9086 + vertex -829.512 192.33 20.5673 + endloop + endfacet + facet normal -0.158476 -0.155886 0.974979 + outer loop + vertex -829.512 192.33 20.5673 + vertex -834.414 193.193 19.9086 + vertex -829.941 189.983 20.1224 + endloop + endfacet + facet normal -0.169564 -0.156751 0.972973 + outer loop + vertex -845.002 206.013 20.1241 + vertex -845.628 203.841 19.6652 + vertex -841.144 202.474 20.2263 + endloop + endfacet + facet normal -0.166651 -0.146325 0.975098 + outer loop + vertex -841.144 202.474 20.2263 + vertex -845.628 203.841 19.6652 + vertex -842.24 200.136 19.6883 + endloop + endfacet + facet normal -0.215517 -0.207128 0.95428 + outer loop + vertex -843.932 207.803 20.7543 + vertex -845.002 206.013 20.1241 + vertex -840.123 204.337 20.8622 + endloop + endfacet + facet normal -0.215632 -0.207509 0.954171 + outer loop + vertex -840.123 204.337 20.8622 + vertex -845.002 206.013 20.1241 + vertex -841.144 202.474 20.2263 + endloop + endfacet + facet normal -0.214143 -0.208375 0.954318 + outer loop + vertex -840.123 204.337 20.8622 + vertex -841.144 202.474 20.2263 + vertex -836.383 201.001 20.9731 + endloop + endfacet + facet normal -0.214905 -0.211246 0.953515 + outer loop + vertex -836.383 201.001 20.9731 + vertex -841.144 202.474 20.2263 + vertex -837.286 199.02 20.3308 + endloop + endfacet + facet normal -0.160221 -0.149475 0.975698 + outer loop + vertex -841.144 202.474 20.2263 + vertex -842.24 200.136 19.6883 + vertex -837.286 199.02 20.3308 + endloop + endfacet + facet normal -0.1621 -0.158849 0.973905 + outer loop + vertex -837.286 199.02 20.3308 + vertex -842.24 200.136 19.6883 + vertex -837.882 196.755 19.862 + endloop + endfacet + facet normal -0.176315 -0.16641 0.970165 + outer loop + vertex -852.579 213.27 19.9775 + vertex -852.872 210.915 19.5203 + vertex -848.866 209.643 20.0303 + endloop + endfacet + facet normal -0.171765 -0.150721 0.97354 + outer loop + vertex -848.866 209.643 20.0303 + vertex -852.872 210.915 19.5203 + vertex -849.68 207.261 19.5178 + endloop + endfacet + facet normal -0.225269 -0.224748 0.94802 + outer loop + vertex -851.678 215.378 20.6913 + vertex -852.579 213.27 19.9775 + vertex -847.862 211.5 20.6787 + endloop + endfacet + facet normal -0.221317 -0.212754 0.951711 + outer loop + vertex -847.862 211.5 20.6787 + vertex -852.579 213.27 19.9775 + vertex -848.866 209.643 20.0303 + endloop + endfacet + facet normal -0.219454 -0.213827 0.951902 + outer loop + vertex -847.862 211.5 20.6787 + vertex -848.866 209.643 20.0303 + vertex -843.932 207.803 20.7543 + endloop + endfacet + facet normal -0.216948 -0.206226 0.954151 + outer loop + vertex -843.932 207.803 20.7543 + vertex -848.866 209.643 20.0303 + vertex -845.002 206.013 20.1241 + endloop + endfacet + facet normal -0.166943 -0.152491 0.974103 + outer loop + vertex -848.866 209.643 20.0303 + vertex -849.68 207.261 19.5178 + vertex -845.002 206.013 20.1241 + endloop + endfacet + facet normal -0.168081 -0.157216 0.973156 + outer loop + vertex -845.002 206.013 20.1241 + vertex -849.68 207.261 19.5178 + vertex -845.628 203.841 19.6652 + endloop + endfacet + facet normal -0.231529 -0.236053 0.943755 + outer loop + vertex -854.855 219.181 20.8631 + vertex -855.861 216.758 20.0103 + vertex -851.678 215.378 20.6913 + endloop + endfacet + facet normal -0.228012 -0.223458 0.947669 + outer loop + vertex -851.678 215.378 20.6913 + vertex -855.861 216.758 20.0103 + vertex -852.579 213.27 19.9775 + endloop + endfacet + facet normal -0.165482 -0.164846 0.972338 + outer loop + vertex -855.861 216.758 20.0103 + vertex -856.428 213.816 19.4149 + vertex -852.579 213.27 19.9775 + endloop + endfacet + facet normal -0.165843 -0.168018 0.971734 + outer loop + vertex -852.579 213.27 19.9775 + vertex -856.428 213.816 19.4149 + vertex -852.872 210.915 19.5203 + endloop + endfacet + facet normal -0.0927836 -0.286108 0.953695 + outer loop + vertex -618.603 62.2341 17.9626 + vertex -613.62 61.0907 18.1044 + vertex -616.658 64.8621 18.9403 + endloop + endfacet + facet normal -0.0900998 -0.291846 0.952212 + outer loop + vertex -609.455 59.3261 17.9576 + vertex -610.166 62.5844 18.889 + vertex -613.62 61.0907 18.1044 + endloop + endfacet + facet normal -0.0928804 -0.286179 0.953664 + outer loop + vertex -610.166 62.5844 18.889 + vertex -616.658 64.8621 18.9403 + vertex -613.62 61.0907 18.1044 + endloop + endfacet + facet normal -0.090518 -0.279423 0.955892 + outer loop + vertex -629.933 65.7511 17.948 + vertex -623.764 64.2499 18.0933 + vertex -626.556 68.1382 18.9655 + endloop + endfacet + facet normal -0.0887195 -0.288942 0.953227 + outer loop + vertex -618.603 62.2341 17.9626 + vertex -616.658 64.8621 18.9403 + vertex -623.764 64.2499 18.0933 + endloop + endfacet + facet normal -0.0899119 -0.279027 0.956065 + outer loop + vertex -616.658 64.8621 18.9403 + vertex -626.556 68.1382 18.9655 + vertex -623.764 64.2499 18.0933 + endloop + endfacet + facet normal -0.0902635 -0.276441 0.956783 + outer loop + vertex -641.521 69.4471 17.9506 + vertex -635.295 67.8904 18.0882 + vertex -637.776 71.7743 18.9764 + endloop + endfacet + facet normal -0.0878642 -0.282853 0.955131 + outer loop + vertex -629.933 65.7511 17.948 + vertex -626.556 68.1382 18.9655 + vertex -635.295 67.8904 18.0882 + endloop + endfacet + facet normal -0.0882956 -0.275301 0.957295 + outer loop + vertex -626.556 68.1382 18.9655 + vertex -637.776 71.7743 18.9764 + vertex -635.295 67.8904 18.0882 + endloop + endfacet + facet normal -0.093479 -0.27494 0.956906 + outer loop + vertex -652.781 73.1599 17.9464 + vertex -646.723 71.5912 18.0875 + vertex -649.189 75.5122 18.9733 + endloop + endfacet + facet normal -0.0893317 -0.277805 0.956475 + outer loop + vertex -641.521 69.4471 17.9506 + vertex -637.776 71.7743 18.9764 + vertex -646.723 71.5912 18.0875 + endloop + endfacet + facet normal -0.089579 -0.272716 0.957915 + outer loop + vertex -637.776 71.7743 18.9764 + vertex -649.189 75.5122 18.9733 + vertex -646.723 71.5912 18.0875 + endloop + endfacet + facet normal -0.0976013 -0.275141 0.956437 + outer loop + vertex -663.903 76.9815 17.9432 + vertex -657.906 75.3482 18.0854 + vertex -660.458 79.3242 18.9687 + endloop + endfacet + facet normal -0.0922194 -0.276696 0.956522 + outer loop + vertex -652.781 73.1599 17.9464 + vertex -649.189 75.5122 18.9733 + vertex -657.906 75.3482 18.0854 + endloop + endfacet + facet normal -0.0924365 -0.27213 0.95781 + outer loop + vertex -649.189 75.5122 18.9733 + vertex -660.458 79.3242 18.9687 + vertex -657.906 75.3482 18.0854 + endloop + endfacet + facet normal -0.100623 -0.274996 0.956165 + outer loop + vertex -675.118 80.974 17.9466 + vertex -669.074 79.2503 18.0868 + vertex -671.667 83.2627 18.968 + endloop + endfacet + facet normal -0.0954405 -0.278046 0.955815 + outer loop + vertex -663.903 76.9815 17.9432 + vertex -660.458 79.3242 18.9687 + vertex -669.074 79.2503 18.0868 + endloop + endfacet + facet normal -0.0956647 -0.272087 0.957506 + outer loop + vertex -660.458 79.3242 18.9687 + vertex -671.667 83.2627 18.968 + vertex -669.074 79.2503 18.0868 + endloop + endfacet + facet normal -0.103647 -0.273276 0.956335 + outer loop + vertex -686.365 85.1181 17.9477 + vertex -680.32 83.3186 18.0886 + vertex -682.884 87.3562 18.9645 + endloop + endfacet + facet normal -0.098908 -0.277357 0.955662 + outer loop + vertex -675.118 80.974 17.9466 + vertex -671.667 83.2627 18.968 + vertex -680.32 83.3186 18.0886 + endloop + endfacet + facet normal -0.0990587 -0.270631 0.957573 + outer loop + vertex -671.667 83.2627 18.968 + vertex -682.884 87.3562 18.9645 + vertex -680.32 83.3186 18.0886 + endloop + endfacet + facet normal -0.106831 -0.272846 0.956108 + outer loop + vertex -697.594 89.4146 17.9482 + vertex -691.554 87.5306 18.0854 + vertex -694.106 91.6117 18.9648 + endloop + endfacet + facet normal -0.102467 -0.274951 0.955982 + outer loop + vertex -686.365 85.1181 17.9477 + vertex -682.884 87.3562 18.9645 + vertex -691.554 87.5306 18.0854 + endloop + endfacet + facet normal -0.102507 -0.270393 0.957277 + outer loop + vertex -682.884 87.3562 18.9645 + vertex -694.106 91.6117 18.9648 + vertex -691.554 87.5306 18.0854 + endloop + endfacet + facet normal -0.111548 -0.271134 0.956056 + outer loop + vertex -708.732 93.8557 17.9468 + vertex -702.764 91.9025 18.0892 + vertex -705.234 96.0047 18.9643 + endloop + endfacet + facet normal -0.105884 -0.274216 0.955821 + outer loop + vertex -697.594 89.4146 17.9482 + vertex -694.106 91.6117 18.9648 + vertex -702.764 91.9025 18.0892 + endloop + endfacet + facet normal -0.105854 -0.268029 0.957578 + outer loop + vertex -694.106 91.6117 18.9648 + vertex -705.234 96.0047 18.9643 + vertex -702.764 91.9025 18.0892 + endloop + endfacet + facet normal -0.114387 -0.268656 0.95642 + outer loop + vertex -719.52 98.3334 17.951 + vertex -713.748 96.3662 18.0888 + vertex -716.122 100.483 18.9612 + endloop + endfacet + facet normal -0.109887 -0.273597 0.955547 + outer loop + vertex -708.732 93.8557 17.9468 + vertex -705.234 96.0047 18.9643 + vertex -713.748 96.3662 18.0888 + endloop + endfacet + facet normal -0.109789 -0.26626 0.957628 + outer loop + vertex -705.234 96.0047 18.9643 + vertex -716.122 100.483 18.9612 + vertex -713.748 96.3662 18.0888 + endloop + endfacet + facet normal -0.11925 -0.268353 0.955911 + outer loop + vertex -730.142 102.937 17.9442 + vertex -724.417 100.888 18.0831 + vertex -726.859 105.088 18.9575 + endloop + endfacet + facet normal -0.114367 -0.268685 0.956414 + outer loop + vertex -719.52 98.3334 17.951 + vertex -716.122 100.483 18.9612 + vertex -724.417 100.888 18.0831 + endloop + endfacet + facet normal -0.114311 -0.265757 0.957239 + outer loop + vertex -716.122 100.483 18.9612 + vertex -726.859 105.088 18.9575 + vertex -724.417 100.888 18.0831 + endloop + endfacet + facet normal -0.125186 -0.264804 0.956142 + outer loop + vertex -740.939 107.827 17.9284 + vertex -735.127 105.625 18.0792 + vertex -737.597 109.896 18.9386 + endloop + endfacet + facet normal -0.118983 -0.268727 0.955839 + outer loop + vertex -730.142 102.937 17.9442 + vertex -726.859 105.088 18.9575 + vertex -735.127 105.625 18.0792 + endloop + endfacet + facet normal -0.118728 -0.261422 0.957895 + outer loop + vertex -726.859 105.088 18.9575 + vertex -737.597 109.896 18.9386 + vertex -735.127 105.625 18.0792 + endloop + endfacet + facet normal -0.129319 -0.261774 0.956426 + outer loop + vertex -751.604 112.867 17.9089 + vertex -745.896 110.599 18.06 + vertex -748.25 114.879 18.9132 + endloop + endfacet + facet normal -0.123805 -0.266847 0.955754 + outer loop + vertex -740.939 107.827 17.9284 + vertex -737.597 109.896 18.9386 + vertex -745.896 110.599 18.06 + endloop + endfacet + facet normal -0.123364 -0.258817 0.958016 + outer loop + vertex -737.597 109.896 18.9386 + vertex -748.25 114.879 18.9132 + vertex -745.896 110.599 18.06 + endloop + endfacet + facet normal -0.134834 -0.256526 0.957086 + outer loop + vertex -762.052 118.047 17.8704 + vertex -756.429 115.69 18.0306 + vertex -758.751 120.033 18.8676 + endloop + endfacet + facet normal -0.129163 -0.262011 0.956382 + outer loop + vertex -751.604 112.867 17.9089 + vertex -748.25 114.879 18.9132 + vertex -756.429 115.69 18.0306 + endloop + endfacet + facet normal -0.128575 -0.253501 0.958752 + outer loop + vertex -748.25 114.879 18.9132 + vertex -758.751 120.033 18.8676 + vertex -756.429 115.69 18.0306 + endloop + endfacet + facet normal -0.13851 -0.250376 0.958189 + outer loop + vertex -772.527 123.496 17.8206 + vertex -766.885 120.996 17.9829 + vertex -769.183 125.412 18.8045 + endloop + endfacet + facet normal -0.13453 -0.25699 0.957005 + outer loop + vertex -762.052 118.047 17.8704 + vertex -758.751 120.033 18.8676 + vertex -766.885 120.996 17.9829 + endloop + endfacet + facet normal -0.133746 -0.248131 0.959449 + outer loop + vertex -758.751 120.033 18.8676 + vertex -769.183 125.412 18.8045 + vertex -766.885 120.996 17.9829 + endloop + endfacet + facet normal -0.142579 -0.242085 0.959722 + outer loop + vertex -782.849 129.135 17.7465 + vertex -777.309 126.548 17.917 + vertex -779.465 130.98 18.7146 + endloop + endfacet + facet normal -0.139474 -0.24883 0.958452 + outer loop + vertex -772.527 123.496 17.8206 + vertex -769.183 125.412 18.8045 + vertex -777.309 126.548 17.917 + endloop + endfacet + facet normal -0.138533 -0.240303 0.960762 + outer loop + vertex -769.183 125.412 18.8045 + vertex -779.465 130.98 18.7146 + vertex -777.309 126.548 17.917 + endloop + endfacet + facet normal -0.146125 -0.232214 0.961626 + outer loop + vertex -792.885 134.899 17.6512 + vertex -787.481 132.239 17.83 + vertex -789.517 136.704 18.5987 + endloop + endfacet + facet normal -0.143684 -0.240217 0.960026 + outer loop + vertex -782.849 129.135 17.7465 + vertex -779.465 130.98 18.7146 + vertex -787.481 132.239 17.83 + endloop + endfacet + facet normal -0.142467 -0.230703 0.962538 + outer loop + vertex -779.465 130.98 18.7146 + vertex -789.517 136.704 18.5987 + vertex -787.481 132.239 17.83 + endloop + endfacet + facet normal -0.148527 -0.219629 0.964211 + outer loop + vertex -802.762 140.88 17.5314 + vertex -797.421 138.093 17.7193 + vertex -799.382 142.63 18.4508 + endloop + endfacet + facet normal -0.147437 -0.229947 0.96197 + outer loop + vertex -792.885 134.899 17.6512 + vertex -789.517 136.704 18.5987 + vertex -797.421 138.093 17.7193 + endloop + endfacet + facet normal -0.145756 -0.218539 0.964881 + outer loop + vertex -789.517 136.704 18.5987 + vertex -799.382 142.63 18.4508 + vertex -797.421 138.093 17.7193 + endloop + endfacet + facet normal -0.148411 -0.205017 0.967441 + outer loop + vertex -812.61 147.195 17.3961 + vertex -807.267 144.221 17.5853 + vertex -809.152 148.855 18.2783 + endloop + endfacet + facet normal -0.149729 -0.217467 0.964515 + outer loop + vertex -802.762 140.88 17.5314 + vertex -799.382 142.63 18.4508 + vertex -807.267 144.221 17.5853 + endloop + endfacet + facet normal -0.147493 -0.204675 0.967654 + outer loop + vertex -799.382 142.63 18.4508 + vertex -809.152 148.855 18.2783 + vertex -807.267 144.221 17.5853 + endloop + endfacet + facet normal -0.148687 -0.19067 0.970328 + outer loop + vertex -822.42 153.901 17.2461 + vertex -817.095 150.719 17.4368 + vertex -818.824 155.418 18.0951 + endloop + endfacet + facet normal -0.149949 -0.202021 0.967834 + outer loop + vertex -812.61 147.195 17.3961 + vertex -809.152 148.855 18.2783 + vertex -817.095 150.719 17.4368 + endloop + endfacet + facet normal -0.147482 -0.190264 0.970592 + outer loop + vertex -809.152 148.855 18.2783 + vertex -818.824 155.418 18.0951 + vertex -817.095 150.719 17.4368 + endloop + endfacet + facet normal -0.146924 -0.176325 0.973305 + outer loop + vertex -831.965 160.878 17.1025 + vertex -826.787 157.561 17.2833 + vertex -828.241 162.237 17.9109 + endloop + endfacet + facet normal -0.149675 -0.18848 0.970604 + outer loop + vertex -822.42 153.901 17.2461 + vertex -818.824 155.418 18.0951 + vertex -826.787 157.561 17.2833 + endloop + endfacet + facet normal -0.146665 -0.176251 0.973358 + outer loop + vertex -818.824 155.418 18.0951 + vertex -828.241 162.237 17.9109 + vertex -826.787 157.561 17.2833 + endloop + endfacet + facet normal -0.142817 -0.164473 0.975988 + outer loop + vertex -840.947 167.898 16.9965 + vertex -836.069 164.568 17.1493 + vertex -837.246 169.176 17.7535 + endloop + endfacet + facet normal -0.147097 -0.175882 0.973359 + outer loop + vertex -831.965 160.878 17.1025 + vertex -828.241 162.237 17.9109 + vertex -836.069 164.568 17.1493 + endloop + endfacet + facet normal -0.144015 -0.16475 0.975765 + outer loop + vertex -828.241 162.237 17.9109 + vertex -837.246 169.176 17.7535 + vertex -836.069 164.568 17.1493 + endloop + endfacet + facet normal -0.139252 -0.149148 0.978961 + outer loop + vertex -849.463 174.923 16.9026 + vertex -844.767 171.555 17.0575 + vertex -845.931 176.25 17.6072 + endloop + endfacet + facet normal -0.142556 -0.165183 0.975906 + outer loop + vertex -840.947 167.898 16.9965 + vertex -837.246 169.176 17.7535 + vertex -844.767 171.555 17.0575 + endloop + endfacet + facet normal -0.137678 -0.14879 0.979238 + outer loop + vertex -837.246 169.176 17.7535 + vertex -845.931 176.25 17.6072 + vertex -844.767 171.555 17.0575 + endloop + endfacet + facet normal -0.143446 -0.141477 0.979493 + outer loop + vertex -858.393 182.652 16.7419 + vertex -853.414 178.833 16.9195 + vertex -854.597 183.747 17.4561 + endloop + endfacet + facet normal -0.140442 -0.146133 0.979245 + outer loop + vertex -849.463 174.923 16.9026 + vertex -845.931 176.25 17.6072 + vertex -853.414 178.833 16.9195 + endloop + endfacet + facet normal -0.138563 -0.140396 0.980352 + outer loop + vertex -845.931 176.25 17.6072 + vertex -854.597 183.747 17.4561 + vertex -853.414 178.833 16.9195 + endloop + endfacet + facet normal -0.131228 -0.135763 0.982012 + outer loop + vertex -866.658 190.807 16.7698 + vertex -862.32 186.928 16.8133 + vertex -862.573 191.375 17.3942 + endloop + endfacet + facet normal -0.141864 -0.14662 0.978968 + outer loop + vertex -858.393 182.652 16.7419 + vertex -854.597 183.747 17.4561 + vertex -862.32 186.928 16.8133 + endloop + endfacet + facet normal -0.137671 -0.13601 0.981095 + outer loop + vertex -854.597 183.747 17.4561 + vertex -862.573 191.375 17.3942 + vertex -862.32 186.928 16.8133 + endloop + endfacet + facet normal -0.172556 -0.493454 0.852483 + outer loop + vertex -609.396 57.0055 16.9889 + vertex -609.595 55.0598 15.8225 + vertex -607.452 55.9424 16.7671 + endloop + endfacet + facet normal -0.155913 -0.520177 0.839707 + outer loop + vertex -607.452 55.9424 16.7671 + vertex -609.595 55.0598 15.8225 + vertex -607.673 54.1071 15.5891 + endloop + endfacet + facet normal -0.144629 -0.384297 0.91181 + outer loop + vertex -609.455 59.3261 17.9576 + vertex -609.396 57.0055 16.9889 + vertex -607.487 57.7573 17.6086 + endloop + endfacet + facet normal -0.126688 -0.419274 0.898977 + outer loop + vertex -607.487 57.7573 17.6086 + vertex -609.396 57.0055 16.9889 + vertex -607.452 55.9424 16.7671 + endloop + endfacet + facet normal -0.148278 -0.476722 0.866458 + outer loop + vertex -617.946 59.9736 17.1116 + vertex -617.896 57.8243 15.9376 + vertex -612.986 58.4361 17.1143 + endloop + endfacet + facet normal -0.147546 -0.479689 0.864944 + outer loop + vertex -612.986 58.4361 17.1143 + vertex -617.896 57.8243 15.9376 + vertex -613.075 56.3215 15.9265 + endloop + endfacet + facet normal -0.11303 -0.3787 0.918592 + outer loop + vertex -618.603 62.2341 17.9626 + vertex -617.946 59.9736 17.1116 + vertex -613.62 61.0907 18.1044 + endloop + endfacet + facet normal -0.115595 -0.371202 0.921329 + outer loop + vertex -613.62 61.0907 18.1044 + vertex -617.946 59.9736 17.1116 + vertex -612.986 58.4361 17.1143 + endloop + endfacet + facet normal -0.125579 -0.372848 0.919355 + outer loop + vertex -613.62 61.0907 18.1044 + vertex -612.986 58.4361 17.1143 + vertex -609.455 59.3261 17.9576 + endloop + endfacet + facet normal -0.121451 -0.384996 0.914892 + outer loop + vertex -609.455 59.3261 17.9576 + vertex -612.986 58.4361 17.1143 + vertex -609.396 57.0055 16.9889 + endloop + endfacet + facet normal -0.16043 -0.478295 0.863421 + outer loop + vertex -612.986 58.4361 17.1143 + vertex -613.075 56.3215 15.9265 + vertex -609.396 57.0055 16.9889 + endloop + endfacet + facet normal -0.154425 -0.496371 0.854265 + outer loop + vertex -609.396 57.0055 16.9889 + vertex -613.075 56.3215 15.9265 + vertex -609.595 55.0598 15.8225 + endloop + endfacet + facet normal -0.147778 -0.47543 0.867253 + outer loop + vertex -629.474 63.4806 17.0781 + vertex -629.471 61.3129 15.8903 + vertex -623.56 61.6644 17.0901 + endloop + endfacet + facet normal -0.147415 -0.477626 0.866107 + outer loop + vertex -623.56 61.6644 17.0901 + vertex -629.471 61.3129 15.8903 + vertex -623.561 59.5155 15.9051 + endloop + endfacet + facet normal -0.113004 -0.375293 0.919992 + outer loop + vertex -629.933 65.7511 17.948 + vertex -629.474 63.4806 17.0781 + vertex -623.764 64.2499 18.0933 + endloop + endfacet + facet normal -0.114645 -0.367166 0.923063 + outer loop + vertex -623.764 64.2499 18.0933 + vertex -629.474 63.4806 17.0781 + vertex -623.56 61.6644 17.0901 + endloop + endfacet + facet normal -0.120108 -0.367305 0.922313 + outer loop + vertex -623.764 64.2499 18.0933 + vertex -623.56 61.6644 17.0901 + vertex -618.603 62.2341 17.9626 + endloop + endfacet + facet normal -0.117847 -0.379714 0.917567 + outer loop + vertex -618.603 62.2341 17.9626 + vertex -623.56 61.6644 17.0901 + vertex -617.946 59.9736 17.1116 + endloop + endfacet + facet normal -0.14714 -0.477646 0.866143 + outer loop + vertex -623.56 61.6644 17.0901 + vertex -623.561 59.5155 15.9051 + vertex -617.946 59.9736 17.1116 + endloop + endfacet + facet normal -0.147308 -0.476774 0.866595 + outer loop + vertex -617.946 59.9736 17.1116 + vertex -623.561 59.5155 15.9051 + vertex -617.896 57.8243 15.9376 + endloop + endfacet + facet normal -0.154412 -0.478399 0.86446 + outer loop + vertex -641.083 67.1737 17.077 + vertex -641.02 65.002 15.8866 + vertex -635.338 65.3259 17.0806 + endloop + endfacet + facet normal -0.154469 -0.478061 0.864637 + outer loop + vertex -635.338 65.3259 17.0806 + vertex -641.02 65.002 15.8866 + vertex -635.329 63.1614 15.8855 + endloop + endfacet + facet normal -0.114197 -0.37544 0.919785 + outer loop + vertex -641.521 69.4471 17.9506 + vertex -641.083 67.1737 17.077 + vertex -635.295 67.8904 18.0882 + endloop + endfacet + facet normal -0.116843 -0.361472 0.925033 + outer loop + vertex -635.295 67.8904 18.0882 + vertex -641.083 67.1737 17.077 + vertex -635.338 65.3259 17.0806 + endloop + endfacet + facet normal -0.119955 -0.36129 0.924705 + outer loop + vertex -635.295 67.8904 18.0882 + vertex -635.338 65.3259 17.0806 + vertex -629.933 65.7511 17.948 + endloop + endfacet + facet normal -0.117904 -0.375945 0.919111 + outer loop + vertex -629.933 65.7511 17.948 + vertex -635.338 65.3259 17.0806 + vertex -629.474 63.4806 17.0781 + endloop + endfacet + facet normal -0.150161 -0.478368 0.865226 + outer loop + vertex -635.338 65.3259 17.0806 + vertex -635.329 63.1614 15.8855 + vertex -629.474 63.4806 17.0781 + endloop + endfacet + facet normal -0.150667 -0.475224 0.866869 + outer loop + vertex -629.474 63.4806 17.0781 + vertex -635.329 63.1614 15.8855 + vertex -629.471 61.3129 15.8903 + endloop + endfacet + facet normal -0.159931 -0.479497 0.862847 + outer loop + vertex -652.248 70.8529 17.0757 + vertex -652.088 68.6629 15.8884 + vertex -646.706 69.0082 17.0779 + endloop + endfacet + facet normal -0.160256 -0.477687 0.86379 + outer loop + vertex -646.706 69.0082 17.0779 + vertex -652.088 68.6629 15.8884 + vertex -646.584 66.823 15.892 + endloop + endfacet + facet normal -0.11838 -0.374457 0.919657 + outer loop + vertex -652.781 73.1599 17.9464 + vertex -652.248 70.8529 17.0757 + vertex -646.723 71.5912 18.0875 + endloop + endfacet + facet normal -0.120878 -0.362088 0.924273 + outer loop + vertex -646.723 71.5912 18.0875 + vertex -652.248 70.8529 17.0757 + vertex -646.706 69.0082 17.0779 + endloop + endfacet + facet normal -0.124867 -0.361932 0.923804 + outer loop + vertex -646.723 71.5912 18.0875 + vertex -646.706 69.0082 17.0779 + vertex -641.521 69.4471 17.9506 + endloop + endfacet + facet normal -0.122701 -0.376491 0.918259 + outer loop + vertex -641.521 69.4471 17.9506 + vertex -646.706 69.0082 17.0779 + vertex -641.083 67.1737 17.077 + endloop + endfacet + facet normal -0.155777 -0.477837 0.864526 + outer loop + vertex -646.706 69.0082 17.0779 + vertex -646.584 66.823 15.892 + vertex -641.083 67.1737 17.077 + endloop + endfacet + facet normal -0.15569 -0.478331 0.864268 + outer loop + vertex -641.083 67.1737 17.077 + vertex -646.584 66.823 15.892 + vertex -641.02 65.002 15.8866 + endloop + endfacet + facet normal -0.164749 -0.477463 0.863068 + outer loop + vertex -663.298 74.6371 17.0778 + vertex -663.103 72.4266 15.8921 + vertex -657.768 72.7253 17.0757 + endloop + endfacet + facet normal -0.164508 -0.478867 0.862336 + outer loop + vertex -657.768 72.7253 17.0757 + vertex -663.103 72.4266 15.8921 + vertex -657.582 70.5245 15.8892 + endloop + endfacet + facet normal -0.122975 -0.371466 0.920266 + outer loop + vertex -663.903 76.9815 17.9432 + vertex -663.298 74.6371 17.0778 + vertex -657.906 75.3482 18.0854 + endloop + endfacet + facet normal -0.124852 -0.362133 0.923727 + outer loop + vertex -657.906 75.3482 18.0854 + vertex -663.298 74.6371 17.0778 + vertex -657.768 72.7253 17.0757 + endloop + endfacet + facet normal -0.12961 -0.36213 0.923073 + outer loop + vertex -657.906 75.3482 18.0854 + vertex -657.768 72.7253 17.0757 + vertex -652.781 73.1599 17.9464 + endloop + endfacet + facet normal -0.1275 -0.375884 0.917853 + outer loop + vertex -652.781 73.1599 17.9464 + vertex -657.768 72.7253 17.0757 + vertex -652.248 70.8529 17.0757 + endloop + endfacet + facet normal -0.162442 -0.478895 0.862712 + outer loop + vertex -657.768 72.7253 17.0757 + vertex -657.582 70.5245 15.8892 + vertex -652.248 70.8529 17.0757 + endloop + endfacet + facet normal -0.162344 -0.479445 0.862425 + outer loop + vertex -652.248 70.8529 17.0757 + vertex -657.582 70.5245 15.8892 + vertex -652.088 68.6629 15.8884 + endloop + endfacet + facet normal -0.171189 -0.47721 0.861954 + outer loop + vertex -674.504 78.618 17.0771 + vertex -674.314 76.4021 15.8882 + vertex -668.879 76.6018 17.0782 + endloop + endfacet + facet normal -0.171038 -0.478211 0.861429 + outer loop + vertex -668.879 76.6018 17.0782 + vertex -674.314 76.4021 15.8882 + vertex -668.683 74.3901 15.8892 + endloop + endfacet + facet normal -0.127563 -0.372449 0.919244 + outer loop + vertex -675.118 80.974 17.9466 + vertex -674.504 78.618 17.0771 + vertex -669.074 79.2503 18.0868 + endloop + endfacet + facet normal -0.129642 -0.361251 0.923412 + outer loop + vertex -669.074 79.2503 18.0868 + vertex -674.504 78.618 17.0771 + vertex -668.879 76.6018 17.0782 + endloop + endfacet + facet normal -0.132884 -0.361307 0.92293 + outer loop + vertex -669.074 79.2503 18.0868 + vertex -668.879 76.6018 17.0782 + vertex -663.903 76.9815 17.9432 + endloop + endfacet + facet normal -0.13123 -0.372954 0.918523 + outer loop + vertex -663.903 76.9815 17.9432 + vertex -668.879 76.6018 17.0782 + vertex -663.298 74.6371 17.0778 + endloop + endfacet + facet normal -0.168301 -0.478248 0.861947 + outer loop + vertex -668.879 76.6018 17.0782 + vertex -668.683 74.3901 15.8892 + vertex -663.298 74.6371 17.0778 + endloop + endfacet + facet normal -0.168435 -0.477419 0.862381 + outer loop + vertex -663.298 74.6371 17.0778 + vertex -668.683 74.3901 15.8892 + vertex -663.103 72.4266 15.8921 + endloop + endfacet + facet normal -0.176162 -0.474494 0.862452 + outer loop + vertex -685.769 82.7556 17.0783 + vertex -685.596 80.533 15.8908 + vertex -680.141 80.6685 17.0795 + endloop + endfacet + facet normal -0.175851 -0.476736 0.861278 + outer loop + vertex -680.141 80.6685 17.0795 + vertex -685.596 80.533 15.8908 + vertex -679.962 78.4521 15.8893 + endloop + endfacet + facet normal -0.132022 -0.371523 0.918989 + outer loop + vertex -686.365 85.1181 17.9477 + vertex -685.769 82.7556 17.0783 + vertex -680.32 83.3186 18.0886 + endloop + endfacet + facet normal -0.133914 -0.360549 0.923077 + outer loop + vertex -680.32 83.3186 18.0886 + vertex -685.769 82.7556 17.0783 + vertex -680.141 80.6685 17.0795 + endloop + endfacet + facet normal -0.137318 -0.360583 0.922564 + outer loop + vertex -680.32 83.3186 18.0886 + vertex -680.141 80.6685 17.0795 + vertex -675.118 80.974 17.9466 + endloop + endfacet + facet normal -0.135633 -0.373905 0.917496 + outer loop + vertex -675.118 80.974 17.9466 + vertex -680.141 80.6685 17.0795 + vertex -674.504 78.618 17.0771 + endloop + endfacet + facet normal -0.173083 -0.476795 0.861805 + outer loop + vertex -680.141 80.6685 17.0795 + vertex -679.962 78.4521 15.8893 + vertex -674.504 78.618 17.0771 + endloop + endfacet + facet normal -0.173027 -0.47718 0.861603 + outer loop + vertex -674.504 78.618 17.0771 + vertex -679.962 78.4521 15.8893 + vertex -674.314 76.4021 15.8882 + endloop + endfacet + facet normal -0.182246 -0.473057 0.861976 + outer loop + vertex -696.986 87.0337 17.078 + vertex -696.806 84.8015 15.891 + vertex -691.378 84.8736 17.0781 + endloop + endfacet + facet normal -0.182336 -0.472351 0.862345 + outer loop + vertex -691.378 84.8736 17.0781 + vertex -696.806 84.8015 15.891 + vertex -691.204 82.6436 15.8935 + endloop + endfacet + facet normal -0.136478 -0.370623 0.918701 + outer loop + vertex -697.594 89.4146 17.9482 + vertex -696.986 87.0337 17.078 + vertex -691.554 87.5306 18.0854 + endloop + endfacet + facet normal -0.138334 -0.359067 0.923003 + outer loop + vertex -691.554 87.5306 18.0854 + vertex -696.986 87.0337 17.078 + vertex -691.378 84.8736 17.0781 + endloop + endfacet + facet normal -0.142486 -0.359098 0.922359 + outer loop + vertex -691.554 87.5306 18.0854 + vertex -691.378 84.8736 17.0781 + vertex -686.365 85.1181 17.9477 + endloop + endfacet + facet normal -0.140885 -0.373048 0.917053 + outer loop + vertex -686.365 85.1181 17.9477 + vertex -691.378 84.8736 17.0781 + vertex -685.769 82.7556 17.0783 + endloop + endfacet + facet normal -0.178413 -0.47245 0.86311 + outer loop + vertex -691.378 84.8736 17.0781 + vertex -691.204 82.6436 15.8935 + vertex -685.769 82.7556 17.0783 + endloop + endfacet + facet normal -0.178146 -0.474444 0.862071 + outer loop + vertex -685.769 82.7556 17.0783 + vertex -691.204 82.6436 15.8935 + vertex -685.596 80.533 15.8908 + endloop + endfacet + facet normal -0.190343 -0.473439 0.860015 + outer loop + vertex -708.152 91.4686 17.0785 + vertex -707.974 89.2351 15.8883 + vertex -702.588 89.2344 17.0801 + endloop + endfacet + facet normal -0.190241 -0.474319 0.859552 + outer loop + vertex -702.588 89.2344 17.0801 + vertex -707.974 89.2351 15.8883 + vertex -702.405 87.003 15.8893 + endloop + endfacet + facet normal -0.1426 -0.368743 0.918528 + outer loop + vertex -708.732 93.8557 17.9468 + vertex -708.152 91.4686 17.0785 + vertex -702.764 91.9025 18.0892 + endloop + endfacet + facet normal -0.144158 -0.358372 0.922382 + outer loop + vertex -702.764 91.9025 18.0892 + vertex -708.152 91.4686 17.0785 + vertex -702.588 89.2344 17.0801 + endloop + endfacet + facet normal -0.147314 -0.358389 0.921876 + outer loop + vertex -702.764 91.9025 18.0892 + vertex -702.588 89.2344 17.0801 + vertex -697.594 89.4146 17.9482 + endloop + endfacet + facet normal -0.145895 -0.372257 0.916591 + outer loop + vertex -697.594 89.4146 17.9482 + vertex -702.588 89.2344 17.0801 + vertex -696.986 87.0337 17.078 + endloop + endfacet + facet normal -0.186051 -0.474431 0.860407 + outer loop + vertex -702.588 89.2344 17.0801 + vertex -702.405 87.003 15.8893 + vertex -696.986 87.0337 17.078 + endloop + endfacet + facet normal -0.186229 -0.472955 0.861181 + outer loop + vertex -696.986 87.0337 17.078 + vertex -702.405 87.003 15.8893 + vertex -696.806 84.8015 15.891 + endloop + endfacet + facet normal -0.196254 -0.468478 0.861402 + outer loop + vertex -718.978 95.9447 17.0781 + vertex -718.835 93.7067 15.8935 + vertex -713.622 93.7055 17.0806 + endloop + endfacet + facet normal -0.195746 -0.472778 0.859165 + outer loop + vertex -713.622 93.7055 17.0806 + vertex -718.835 93.7067 15.8935 + vertex -713.461 91.4744 15.8894 + endloop + endfacet + facet normal -0.147618 -0.368875 0.917682 + outer loop + vertex -719.52 98.3334 17.951 + vertex -718.978 95.9447 17.0781 + vertex -713.748 96.3662 18.0888 + endloop + endfacet + facet normal -0.149491 -0.356552 0.922238 + outer loop + vertex -713.748 96.3662 18.0888 + vertex -718.978 95.9447 17.0781 + vertex -713.622 93.7055 17.0806 + endloop + endfacet + facet normal -0.152345 -0.356516 0.921785 + outer loop + vertex -713.748 96.3662 18.0888 + vertex -713.622 93.7055 17.0806 + vertex -708.732 93.8557 17.9468 + endloop + endfacet + facet normal -0.151015 -0.370099 0.916636 + outer loop + vertex -708.732 93.8557 17.9468 + vertex -713.622 93.7055 17.0806 + vertex -708.152 91.4686 17.0785 + endloop + endfacet + facet normal -0.193072 -0.472879 0.859714 + outer loop + vertex -713.622 93.7055 17.0806 + vertex -713.461 91.4744 15.8894 + vertex -708.152 91.4686 17.0785 + endloop + endfacet + facet normal -0.193016 -0.473358 0.859463 + outer loop + vertex -708.152 91.4686 17.0785 + vertex -713.461 91.4744 15.8894 + vertex -707.974 89.2351 15.8883 + endloop + endfacet + facet normal -0.204809 -0.469228 0.858999 + outer loop + vertex -729.557 100.505 17.0777 + vertex -729.418 98.2643 15.8871 + vertex -724.265 98.1975 17.0792 + endloop + endfacet + facet normal -0.204774 -0.469557 0.858827 + outer loop + vertex -724.265 98.1975 17.0792 + vertex -729.418 98.2643 15.8871 + vertex -724.129 95.9627 15.8897 + endloop + endfacet + facet normal -0.152582 -0.363988 0.918821 + outer loop + vertex -730.142 102.937 17.9442 + vertex -729.557 100.505 17.0777 + vertex -724.417 100.888 18.0831 + endloop + endfacet + facet normal -0.154179 -0.353049 0.922814 + outer loop + vertex -724.417 100.888 18.0831 + vertex -729.557 100.505 17.0777 + vertex -724.265 98.1975 17.0792 + endloop + endfacet + facet normal -0.159292 -0.353019 0.921957 + outer loop + vertex -724.417 100.888 18.0831 + vertex -724.265 98.1975 17.0792 + vertex -719.52 98.3334 17.951 + endloop + endfacet + facet normal -0.157599 -0.370319 0.915438 + outer loop + vertex -719.52 98.3334 17.951 + vertex -724.265 98.1975 17.0792 + vertex -718.978 95.9447 17.0781 + endloop + endfacet + facet normal -0.200001 -0.469796 0.859821 + outer loop + vertex -724.265 98.1975 17.0792 + vertex -724.129 95.9627 15.8897 + vertex -718.978 95.9447 17.0781 + endloop + endfacet + facet normal -0.200174 -0.468302 0.860595 + outer loop + vertex -718.978 95.9447 17.0781 + vertex -724.129 95.9627 15.8897 + vertex -718.835 93.7067 15.8935 + endloop + endfacet + facet normal -0.211686 -0.463822 0.860266 + outer loop + vertex -740.352 105.372 17.0678 + vertex -740.195 103.105 15.8839 + vertex -734.926 102.902 17.071 + endloop + endfacet + facet normal -0.211544 -0.465625 0.859327 + outer loop + vertex -734.926 102.902 17.071 + vertex -740.195 103.105 15.8839 + vertex -734.77 100.643 15.8853 + endloop + endfacet + facet normal -0.160455 -0.360398 0.918895 + outer loop + vertex -740.939 107.827 17.9284 + vertex -740.352 105.372 17.0678 + vertex -735.127 105.625 18.0792 + endloop + endfacet + facet normal -0.161322 -0.353134 0.921559 + outer loop + vertex -735.127 105.625 18.0792 + vertex -740.352 105.372 17.0678 + vertex -734.926 102.902 17.071 + endloop + endfacet + facet normal -0.165447 -0.353164 0.920816 + outer loop + vertex -735.127 105.625 18.0792 + vertex -734.926 102.902 17.071 + vertex -730.142 102.937 17.9442 + endloop + endfacet + facet normal -0.164477 -0.365853 0.916023 + outer loop + vertex -730.142 102.937 17.9442 + vertex -734.926 102.902 17.071 + vertex -729.557 100.505 17.0777 + endloop + endfacet + facet normal -0.208999 -0.465743 0.859886 + outer loop + vertex -734.926 102.902 17.071 + vertex -734.77 100.643 15.8853 + vertex -729.557 100.505 17.0777 + endloop + endfacet + facet normal -0.208693 -0.46903 0.858171 + outer loop + vertex -729.557 100.505 17.0777 + vertex -734.77 100.643 15.8853 + vertex -729.418 98.2643 15.8871 + endloop + endfacet + facet normal -0.221464 -0.460845 0.859404 + outer loop + vertex -751.094 110.429 17.0475 + vertex -750.993 108.178 15.8664 + vertex -745.763 107.89 17.0598 + endloop + endfacet + facet normal -0.221332 -0.462909 0.858328 + outer loop + vertex -745.763 107.89 17.0598 + vertex -750.993 108.178 15.8664 + vertex -745.633 105.632 15.8755 + endloop + endfacet + facet normal -0.167105 -0.359436 0.918086 + outer loop + vertex -751.604 112.867 17.9089 + vertex -751.094 110.429 17.0475 + vertex -745.896 110.599 18.06 + endloop + endfacet + facet normal -0.168216 -0.348741 0.921999 + outer loop + vertex -745.896 110.599 18.06 + vertex -751.094 110.429 17.0475 + vertex -745.763 107.89 17.0598 + endloop + endfacet + facet normal -0.170476 -0.348704 0.921598 + outer loop + vertex -745.896 110.599 18.06 + vertex -745.763 107.89 17.0598 + vertex -740.939 107.827 17.9284 + endloop + endfacet + facet normal -0.169758 -0.361838 0.916655 + outer loop + vertex -740.939 107.827 17.9284 + vertex -745.763 107.89 17.0598 + vertex -740.352 105.372 17.0678 + endloop + endfacet + facet normal -0.216832 -0.463176 0.859332 + outer loop + vertex -745.763 107.89 17.0598 + vertex -745.633 105.632 15.8755 + vertex -740.352 105.372 17.0678 + endloop + endfacet + facet normal -0.216805 -0.463579 0.859122 + outer loop + vertex -740.352 105.372 17.0678 + vertex -745.633 105.632 15.8755 + vertex -740.195 103.105 15.8839 + endloop + endfacet + facet normal -0.229412 -0.456086 0.859858 + outer loop + vertex -761.54 115.574 17.0233 + vertex -761.465 113.319 15.8473 + vertex -756.335 112.98 17.0361 + endloop + endfacet + facet normal -0.229409 -0.456138 0.859831 + outer loop + vertex -756.335 112.98 17.0361 + vertex -761.465 113.319 15.8473 + vertex -756.252 110.724 15.8615 + endloop + endfacet + facet normal -0.173392 -0.350998 0.920183 + outer loop + vertex -762.052 118.047 17.8704 + vertex -761.54 115.574 17.0233 + vertex -756.429 115.69 18.0306 + endloop + endfacet + facet normal -0.173994 -0.344573 0.922494 + outer loop + vertex -756.429 115.69 18.0306 + vertex -761.54 115.574 17.0233 + vertex -756.335 112.98 17.0361 + endloop + endfacet + facet normal -0.178261 -0.344439 0.921729 + outer loop + vertex -756.429 115.69 18.0306 + vertex -756.335 112.98 17.0361 + vertex -751.604 112.867 17.9089 + endloop + endfacet + facet normal -0.177522 -0.360742 0.915615 + outer loop + vertex -751.604 112.867 17.9089 + vertex -756.335 112.98 17.0361 + vertex -751.094 110.429 17.0475 + endloop + endfacet + facet normal -0.224029 -0.45656 0.861025 + outer loop + vertex -756.335 112.98 17.0361 + vertex -756.252 110.724 15.8615 + vertex -751.094 110.429 17.0475 + endloop + endfacet + facet normal -0.223774 -0.460681 0.858894 + outer loop + vertex -751.094 110.429 17.0475 + vertex -756.252 110.724 15.8615 + vertex -750.993 108.178 15.8664 + endloop + endfacet + facet normal -0.237806 -0.448623 0.861502 + outer loop + vertex -772.031 120.999 16.982 + vertex -771.957 118.723 15.8171 + vertex -766.775 118.251 17.0016 + endloop + endfacet + facet normal -0.237765 -0.450179 0.860701 + outer loop + vertex -766.775 118.251 17.0016 + vertex -771.957 118.723 15.8171 + vertex -766.691 115.976 15.8351 + endloop + endfacet + facet normal -0.179398 -0.345044 0.921282 + outer loop + vertex -772.527 123.496 17.8206 + vertex -772.031 120.999 16.982 + vertex -766.885 120.996 17.9829 + endloop + endfacet + facet normal -0.179918 -0.337473 0.923981 + outer loop + vertex -766.885 120.996 17.9829 + vertex -772.031 120.999 16.982 + vertex -766.775 118.251 17.0016 + endloop + endfacet + facet normal -0.184354 -0.337354 0.92315 + outer loop + vertex -766.885 120.996 17.9829 + vertex -766.775 118.251 17.0016 + vertex -762.052 118.047 17.8704 + endloop + endfacet + facet normal -0.183981 -0.35231 0.917621 + outer loop + vertex -762.052 118.047 17.8704 + vertex -766.775 118.251 17.0016 + vertex -761.54 115.574 17.0233 + endloop + endfacet + facet normal -0.233961 -0.450489 0.861581 + outer loop + vertex -766.775 118.251 17.0016 + vertex -766.691 115.976 15.8351 + vertex -761.54 115.574 17.0233 + endloop + endfacet + facet normal -0.233747 -0.455723 0.858882 + outer loop + vertex -761.54 115.574 17.0233 + vertex -766.691 115.976 15.8351 + vertex -761.465 113.319 15.8473 + endloop + endfacet + facet normal -0.245543 -0.437365 0.865113 + outer loop + vertex -782.429 126.64 16.9227 + vertex -782.406 124.361 15.7766 + vertex -777.265 123.805 16.9545 + endloop + endfacet + facet normal -0.2455 -0.442742 0.862386 + outer loop + vertex -777.265 123.805 16.9545 + vertex -782.406 124.361 15.7766 + vertex -777.213 121.524 15.7988 + endloop + endfacet + facet normal -0.1854 -0.336186 0.923367 + outer loop + vertex -782.849 129.135 17.7465 + vertex -782.429 126.64 16.9227 + vertex -777.309 126.548 17.917 + endloop + endfacet + facet normal -0.185811 -0.327928 0.926249 + outer loop + vertex -777.309 126.548 17.917 + vertex -782.429 126.64 16.9227 + vertex -777.265 123.805 16.9545 + endloop + endfacet + facet normal -0.190474 -0.327699 0.925383 + outer loop + vertex -777.309 126.548 17.917 + vertex -777.265 123.805 16.9545 + vertex -772.527 123.496 17.8206 + endloop + endfacet + facet normal -0.190442 -0.346331 0.918578 + outer loop + vertex -772.527 123.496 17.8206 + vertex -777.265 123.805 16.9545 + vertex -772.031 120.999 16.982 + endloop + endfacet + facet normal -0.242 -0.443075 0.863203 + outer loop + vertex -777.265 123.805 16.9545 + vertex -777.213 121.524 15.7988 + vertex -772.031 120.999 16.982 + endloop + endfacet + facet normal -0.241919 -0.448266 0.860542 + outer loop + vertex -772.031 120.999 16.982 + vertex -777.213 121.524 15.7988 + vertex -771.957 118.723 15.8171 + endloop + endfacet + facet normal -0.25134 -0.425171 0.869516 + outer loop + vertex -792.52 132.392 16.8506 + vertex -792.548 130.107 15.725 + vertex -787.509 129.503 16.8861 + endloop + endfacet + facet normal -0.251371 -0.430431 0.866915 + outer loop + vertex -787.509 129.503 16.8861 + vertex -792.548 130.107 15.725 + vertex -787.513 127.22 15.7514 + endloop + endfacet + facet normal -0.189982 -0.323647 0.926908 + outer loop + vertex -792.885 134.899 17.6512 + vertex -792.52 132.392 16.8506 + vertex -787.481 132.239 17.83 + endloop + endfacet + facet normal -0.190169 -0.318363 0.928698 + outer loop + vertex -787.481 132.239 17.83 + vertex -792.52 132.392 16.8506 + vertex -787.509 129.503 16.8861 + endloop + endfacet + facet normal -0.196337 -0.317911 0.927569 + outer loop + vertex -787.481 132.239 17.83 + vertex -787.509 129.503 16.8861 + vertex -782.849 129.135 17.7465 + endloop + endfacet + facet normal -0.196587 -0.337184 0.920685 + outer loop + vertex -782.849 129.135 17.7465 + vertex -787.509 129.503 16.8861 + vertex -782.429 126.64 16.9227 + endloop + endfacet + facet normal -0.248897 -0.43072 0.867485 + outer loop + vertex -787.509 129.503 16.8861 + vertex -787.513 127.22 15.7514 + vertex -782.429 126.64 16.9227 + endloop + endfacet + facet normal -0.248888 -0.437007 0.864338 + outer loop + vertex -782.429 126.64 16.9227 + vertex -787.513 127.22 15.7514 + vertex -782.406 124.361 15.7766 + endloop + endfacet + facet normal -0.258522 -0.412342 0.873579 + outer loop + vertex -802.442 138.348 16.7591 + vertex -802.523 136.061 15.6558 + vertex -797.493 135.34 16.8038 + endloop + endfacet + facet normal -0.258687 -0.417416 0.871117 + outer loop + vertex -797.493 135.34 16.8038 + vertex -802.523 136.061 15.6558 + vertex -797.544 133.051 15.6916 + endloop + endfacet + facet normal -0.193791 -0.30859 0.931245 + outer loop + vertex -802.762 140.88 17.5314 + vertex -802.442 138.348 16.7591 + vertex -797.421 138.093 17.7193 + endloop + endfacet + facet normal -0.193832 -0.305045 0.932404 + outer loop + vertex -797.421 138.093 17.7193 + vertex -802.442 138.348 16.7591 + vertex -797.493 135.34 16.8038 + endloop + endfacet + facet normal -0.200368 -0.304476 0.931207 + outer loop + vertex -797.421 138.093 17.7193 + vertex -797.493 135.34 16.8038 + vertex -792.885 134.899 17.6512 + endloop + endfacet + facet normal -0.201008 -0.324422 0.924309 + outer loop + vertex -792.885 134.899 17.6512 + vertex -797.493 135.34 16.8038 + vertex -792.52 132.392 16.8506 + endloop + endfacet + facet normal -0.255864 -0.417796 0.871769 + outer loop + vertex -797.493 135.34 16.8038 + vertex -797.544 133.051 15.6916 + vertex -792.52 132.392 16.8506 + endloop + endfacet + facet normal -0.255987 -0.424587 0.868445 + outer loop + vertex -792.52 132.392 16.8506 + vertex -797.544 133.051 15.6916 + vertex -792.548 130.107 15.725 + endloop + endfacet + facet normal -0.263464 -0.394076 0.880506 + outer loop + vertex -812.344 144.639 16.6506 + vertex -812.479 142.338 15.5801 + vertex -807.391 141.447 16.7041 + endloop + endfacet + facet normal -0.264019 -0.401963 0.876767 + outer loop + vertex -807.391 141.447 16.7041 + vertex -812.479 142.338 15.5801 + vertex -807.497 139.151 15.6192 + endloop + endfacet + facet normal -0.196442 -0.293304 0.935619 + outer loop + vertex -812.61 147.195 17.3961 + vertex -812.344 144.639 16.6506 + vertex -807.267 144.221 17.5853 + endloop + endfacet + facet normal -0.196336 -0.288959 0.936992 + outer loop + vertex -807.267 144.221 17.5853 + vertex -812.344 144.639 16.6506 + vertex -807.391 141.447 16.7041 + endloop + endfacet + facet normal -0.202609 -0.288318 0.935854 + outer loop + vertex -807.267 144.221 17.5853 + vertex -807.391 141.447 16.7041 + vertex -802.762 140.88 17.5314 + endloop + endfacet + facet normal -0.20392 -0.30915 0.928893 + outer loop + vertex -802.762 140.88 17.5314 + vertex -807.391 141.447 16.7041 + vertex -802.442 138.348 16.7591 + endloop + endfacet + facet normal -0.261692 -0.402323 0.877299 + outer loop + vertex -807.391 141.447 16.7041 + vertex -807.497 139.151 15.6192 + vertex -802.442 138.348 16.7591 + endloop + endfacet + facet normal -0.26217 -0.41181 0.872742 + outer loop + vertex -802.442 138.348 16.7591 + vertex -807.497 139.151 15.6192 + vertex -802.523 136.061 15.6558 + endloop + endfacet + facet normal -0.268998 -0.376858 0.886351 + outer loop + vertex -822.244 151.333 16.5337 + vertex -822.446 149.03 15.493 + vertex -817.303 147.94 16.5905 + endloop + endfacet + facet normal -0.269799 -0.383954 0.883056 + outer loop + vertex -817.303 147.94 16.5905 + vertex -822.446 149.03 15.493 + vertex -817.469 145.634 15.5371 + endloop + endfacet + facet normal -0.197785 -0.274591 0.941 + outer loop + vertex -822.42 153.901 17.2461 + vertex -822.244 151.333 16.5337 + vertex -817.095 150.719 17.4368 + endloop + endfacet + facet normal -0.197612 -0.27198 0.941794 + outer loop + vertex -817.095 150.719 17.4368 + vertex -822.244 151.333 16.5337 + vertex -817.303 147.94 16.5905 + endloop + endfacet + facet normal -0.204468 -0.271098 0.940584 + outer loop + vertex -817.095 150.719 17.4368 + vertex -817.303 147.94 16.5905 + vertex -812.61 147.195 17.3961 + endloop + endfacet + facet normal -0.206798 -0.293693 0.933263 + outer loop + vertex -812.61 147.195 17.3961 + vertex -817.303 147.94 16.5905 + vertex -812.344 144.639 16.6506 + endloop + endfacet + facet normal -0.266649 -0.384508 0.883771 + outer loop + vertex -817.303 147.94 16.5905 + vertex -817.469 145.634 15.5371 + vertex -812.344 144.639 16.6506 + endloop + endfacet + facet normal -0.267471 -0.393416 0.879593 + outer loop + vertex -812.344 144.639 16.6506 + vertex -817.469 145.634 15.5371 + vertex -812.479 142.338 15.5801 + endloop + endfacet + facet normal -0.273686 -0.358514 0.892504 + outer loop + vertex -831.93 158.337 16.4165 + vertex -832.219 156.042 15.4059 + vertex -827.133 154.811 16.4711 + endloop + endfacet + facet normal -0.27454 -0.364291 0.889899 + outer loop + vertex -827.133 154.811 16.4711 + vertex -832.219 156.042 15.4059 + vertex -827.375 152.502 15.4512 + endloop + endfacet + facet normal -0.198311 -0.258062 0.945556 + outer loop + vertex -831.965 160.878 17.1025 + vertex -831.93 158.337 16.4165 + vertex -826.787 157.561 17.2833 + endloop + endfacet + facet normal -0.197966 -0.254663 0.94655 + outer loop + vertex -826.787 157.561 17.2833 + vertex -831.93 158.337 16.4165 + vertex -827.133 154.811 16.4711 + endloop + endfacet + facet normal -0.204407 -0.253537 0.945482 + outer loop + vertex -826.787 157.561 17.2833 + vertex -827.133 154.811 16.4711 + vertex -822.42 153.901 17.2461 + endloop + endfacet + facet normal -0.207403 -0.274667 0.938905 + outer loop + vertex -822.42 153.901 17.2461 + vertex -827.133 154.811 16.4711 + vertex -822.244 151.333 16.5337 + endloop + endfacet + facet normal -0.271043 -0.365003 0.890679 + outer loop + vertex -827.133 154.811 16.4711 + vertex -827.375 152.502 15.4512 + vertex -822.244 151.333 16.5337 + endloop + endfacet + facet normal -0.27251 -0.376193 0.88556 + outer loop + vertex -822.244 151.333 16.5337 + vertex -827.375 152.502 15.4512 + vertex -822.446 149.03 15.493 + endloop + endfacet + facet normal -0.27438 -0.340191 0.899436 + outer loop + vertex -841.073 165.414 16.3317 + vertex -841.492 163.15 15.3473 + vertex -836.589 161.885 16.365 + endloop + endfacet + facet normal -0.275599 -0.347454 0.896282 + outer loop + vertex -836.589 161.885 16.365 + vertex -841.492 163.15 15.3473 + vertex -836.937 159.599 15.3714 + endloop + endfacet + facet normal -0.196403 -0.244193 0.949629 + outer loop + vertex -840.947 167.898 16.9965 + vertex -841.073 165.414 16.3317 + vertex -836.069 164.568 17.1493 + endloop + endfacet + facet normal -0.19588 -0.239954 0.950817 + outer loop + vertex -836.069 164.568 17.1493 + vertex -841.073 165.414 16.3317 + vertex -836.589 161.885 16.365 + endloop + endfacet + facet normal -0.203387 -0.238169 0.949689 + outer loop + vertex -836.069 164.568 17.1493 + vertex -836.589 161.885 16.365 + vertex -831.965 160.878 17.1025 + endloop + endfacet + facet normal -0.206714 -0.257716 0.943849 + outer loop + vertex -831.965 160.878 17.1025 + vertex -836.589 161.885 16.365 + vertex -831.93 158.337 16.4165 + endloop + endfacet + facet normal -0.274703 -0.347673 0.896472 + outer loop + vertex -836.589 161.885 16.365 + vertex -836.937 159.599 15.3714 + vertex -831.93 158.337 16.4165 + endloop + endfacet + facet normal -0.276336 -0.357925 0.891924 + outer loop + vertex -831.93 158.337 16.4165 + vertex -836.937 159.599 15.3714 + vertex -832.219 156.042 15.4059 + endloop + endfacet + facet normal -0.279263 -0.326374 0.903046 + outer loop + vertex -849.601 172.424 16.2639 + vertex -850.13 170.207 15.299 + vertex -845.383 168.916 16.3004 + endloop + endfacet + facet normal -0.280231 -0.331666 0.900815 + outer loop + vertex -845.383 168.916 16.3004 + vertex -850.13 170.207 15.299 + vertex -845.871 166.682 15.326 + endloop + endfacet + facet normal -0.198123 -0.232477 0.952209 + outer loop + vertex -849.463 174.923 16.9026 + vertex -849.601 172.424 16.2639 + vertex -844.767 171.555 17.0575 + endloop + endfacet + facet normal -0.197444 -0.227473 0.953557 + outer loop + vertex -844.767 171.555 17.0575 + vertex -849.601 172.424 16.2639 + vertex -845.383 168.916 16.3004 + endloop + endfacet + facet normal -0.201492 -0.226361 0.952975 + outer loop + vertex -844.767 171.555 17.0575 + vertex -845.383 168.916 16.3004 + vertex -840.947 167.898 16.9965 + endloop + endfacet + facet normal -0.20463 -0.243366 0.948103 + outer loop + vertex -840.947 167.898 16.9965 + vertex -845.383 168.916 16.3004 + vertex -841.073 165.414 16.3317 + endloop + endfacet + facet normal -0.276871 -0.33269 0.901476 + outer loop + vertex -845.383 168.916 16.3004 + vertex -845.871 166.682 15.326 + vertex -841.073 165.414 16.3317 + endloop + endfacet + facet normal -0.278009 -0.339198 0.898697 + outer loop + vertex -841.073 165.414 16.3317 + vertex -845.871 166.682 15.326 + vertex -841.492 163.15 15.3473 + endloop + endfacet + facet normal -0.294526 -0.319594 0.900619 + outer loop + vertex -858.459 180.035 16.1126 + vertex -858.904 177.763 15.1605 + vertex -853.918 176.082 16.1948 + endloop + endfacet + facet normal -0.294853 -0.320919 0.900041 + outer loop + vertex -853.918 176.082 16.1948 + vertex -858.904 177.763 15.1605 + vertex -854.423 173.858 15.2362 + endloop + endfacet + facet normal -0.205736 -0.223941 0.95264 + outer loop + vertex -858.393 182.652 16.7419 + vertex -858.459 180.035 16.1126 + vertex -853.414 178.833 16.9195 + endloop + endfacet + facet normal -0.203858 -0.214302 0.955257 + outer loop + vertex -853.414 178.833 16.9195 + vertex -858.459 180.035 16.1126 + vertex -853.918 176.082 16.1948 + endloop + endfacet + facet normal -0.207259 -0.213532 0.954698 + outer loop + vertex -853.414 178.833 16.9195 + vertex -853.918 176.082 16.1948 + vertex -849.463 174.923 16.9026 + endloop + endfacet + facet normal -0.211056 -0.231137 0.949753 + outer loop + vertex -849.463 174.923 16.9026 + vertex -853.918 176.082 16.1948 + vertex -849.601 172.424 16.2639 + endloop + endfacet + facet normal -0.288166 -0.323044 0.901445 + outer loop + vertex -853.918 176.082 16.1948 + vertex -854.423 173.858 15.2362 + vertex -849.601 172.424 16.2639 + endloop + endfacet + facet normal -0.288251 -0.323456 0.90127 + outer loop + vertex -849.601 172.424 16.2639 + vertex -854.423 173.858 15.2362 + vertex -850.13 170.207 15.299 + endloop + endfacet + facet normal -0.286818 -0.297722 0.910548 + outer loop + vertex -867.302 188.588 16.148 + vertex -867.942 186.378 15.2242 + vertex -863.08 184.293 16.0739 + endloop + endfacet + facet normal -0.292305 -0.313382 0.903521 + outer loop + vertex -863.08 184.293 16.0739 + vertex -867.942 186.378 15.2242 + vertex -863.541 182.001 15.1295 + endloop + endfacet + facet normal -0.198034 -0.21076 0.957269 + outer loop + vertex -866.658 190.807 16.7698 + vertex -867.302 188.588 16.148 + vertex -862.32 186.928 16.8133 + endloop + endfacet + facet normal -0.19823 -0.211423 0.957082 + outer loop + vertex -862.32 186.928 16.8133 + vertex -867.302 188.588 16.148 + vertex -863.08 184.293 16.0739 + endloop + endfacet + facet normal -0.209006 -0.207887 0.955562 + outer loop + vertex -862.32 186.928 16.8133 + vertex -863.08 184.293 16.0739 + vertex -858.393 182.652 16.7419 + endloop + endfacet + facet normal -0.213771 -0.223346 0.951009 + outer loop + vertex -858.393 182.652 16.7419 + vertex -863.08 184.293 16.0739 + vertex -858.459 180.035 16.1126 + endloop + endfacet + facet normal -0.295477 -0.312452 0.902811 + outer loop + vertex -863.08 184.293 16.0739 + vertex -863.541 182.001 15.1295 + vertex -858.459 180.035 16.1126 + endloop + endfacet + facet normal -0.297371 -0.318768 0.899976 + outer loop + vertex -858.459 180.035 16.1126 + vertex -863.541 182.001 15.1295 + vertex -858.904 177.763 15.1605 + endloop + endfacet + facet normal -0.181396 -0.175431 0.967636 + outer loop + vertex -868.664 193.918 16.9579 + vertex -870.458 192.404 16.347 + vertex -866.658 190.807 16.7698 + endloop + endfacet + facet normal -0.195478 -0.211597 0.957609 + outer loop + vertex -866.658 190.807 16.7698 + vertex -870.458 192.404 16.347 + vertex -867.302 188.588 16.148 + endloop + endfacet + facet normal -0.266193 -0.268421 0.925792 + outer loop + vertex -870.458 192.404 16.347 + vertex -871.485 190.426 15.4781 + vertex -867.302 188.588 16.148 + endloop + endfacet + facet normal -0.278268 -0.300872 0.912164 + outer loop + vertex -867.302 188.588 16.148 + vertex -871.485 190.426 15.4781 + vertex -867.942 186.378 15.2242 + endloop + endfacet + facet normal -0.264494 -0.750919 0.605114 + outer loop + vertex -609.838 53.3886 14.395 + vertex -609.987 52.1004 12.7314 + vertex -607.889 52.4971 14.1406 + endloop + endfacet + facet normal -0.242441 -0.777812 0.579854 + outer loop + vertex -607.889 52.4971 14.1406 + vertex -609.987 52.1004 12.7314 + vertex -608.006 51.2846 12.4652 + endloop + endfacet + facet normal -0.213533 -0.616371 0.757951 + outer loop + vertex -609.595 55.0598 15.8225 + vertex -609.838 53.3886 14.395 + vertex -607.673 54.1071 15.5891 + endloop + endfacet + facet normal -0.196432 -0.641142 0.741857 + outer loop + vertex -607.673 54.1071 15.5891 + vertex -609.838 53.3886 14.395 + vertex -607.889 52.4971 14.1406 + endloop + endfacet + facet normal -0.230846 -0.752176 0.617205 + outer loop + vertex -618.131 56.0765 14.5029 + vertex -618.319 54.7669 12.8366 + vertex -613.324 54.5986 14.4994 + endloop + endfacet + facet normal -0.230169 -0.754215 0.614965 + outer loop + vertex -613.324 54.5986 14.4994 + vertex -618.319 54.7669 12.8366 + vertex -613.512 53.2973 12.8332 + endloop + endfacet + facet normal -0.187756 -0.607998 0.771419 + outer loop + vertex -617.896 57.8243 15.9376 + vertex -618.131 56.0765 14.5029 + vertex -613.075 56.3215 15.9265 + endloop + endfacet + facet normal -0.187145 -0.610404 0.769665 + outer loop + vertex -613.075 56.3215 15.9265 + vertex -618.131 56.0765 14.5029 + vertex -613.324 54.5986 14.4994 + endloop + endfacet + facet normal -0.197524 -0.608197 0.768817 + outer loop + vertex -613.075 56.3215 15.9265 + vertex -613.324 54.5986 14.4994 + vertex -609.595 55.0598 15.8225 + endloop + endfacet + facet normal -0.19274 -0.620957 0.759778 + outer loop + vertex -609.595 55.0598 15.8225 + vertex -613.324 54.5986 14.4994 + vertex -609.838 53.3886 14.395 + endloop + endfacet + facet normal -0.242312 -0.751206 0.613982 + outer loop + vertex -613.324 54.5986 14.4994 + vertex -613.512 53.2973 12.8332 + vertex -609.838 53.3886 14.395 + endloop + endfacet + facet normal -0.239503 -0.757174 0.607722 + outer loop + vertex -609.838 53.3886 14.395 + vertex -613.512 53.2973 12.8332 + vertex -609.987 52.1004 12.7314 + endloop + endfacet + facet normal -0.233065 -0.755707 0.612035 + outer loop + vertex -629.635 59.5463 14.4489 + vertex -629.814 58.2493 12.7791 + vertex -623.748 57.7495 14.472 + endloop + endfacet + facet normal -0.233052 -0.755761 0.611974 + outer loop + vertex -623.748 57.7495 14.472 + vertex -629.814 58.2493 12.7791 + vertex -623.941 56.4557 12.8008 + endloop + endfacet + facet normal -0.187577 -0.610481 0.769498 + outer loop + vertex -629.471 61.3129 15.8903 + vertex -629.635 59.5463 14.4489 + vertex -623.561 59.5155 15.9051 + endloop + endfacet + facet normal -0.188226 -0.606753 0.772283 + outer loop + vertex -623.561 59.5155 15.9051 + vertex -629.635 59.5463 14.4489 + vertex -623.748 57.7495 14.472 + endloop + endfacet + facet normal -0.185711 -0.607218 0.772527 + outer loop + vertex -623.561 59.5155 15.9051 + vertex -623.748 57.7495 14.472 + vertex -617.896 57.8243 15.9376 + endloop + endfacet + facet normal -0.185464 -0.608461 0.771608 + outer loop + vertex -617.896 57.8243 15.9376 + vertex -623.748 57.7495 14.472 + vertex -618.131 56.0765 14.5029 + endloop + endfacet + facet normal -0.228771 -0.75681 0.612293 + outer loop + vertex -623.748 57.7495 14.472 + vertex -623.941 56.4557 12.8008 + vertex -618.131 56.0765 14.5029 + endloop + endfacet + facet normal -0.229943 -0.752395 0.617275 + outer loop + vertex -618.131 56.0765 14.5029 + vertex -623.941 56.4557 12.8008 + vertex -618.319 54.7669 12.8366 + endloop + endfacet + facet normal -0.245122 -0.75326 0.61034 + outer loop + vertex -641.092 63.215 14.4506 + vertex -641.23 61.91 12.7847 + vertex -635.449 61.3767 14.4482 + endloop + endfacet + facet normal -0.244769 -0.754751 0.608637 + outer loop + vertex -635.449 61.3767 14.4482 + vertex -641.23 61.91 12.7847 + vertex -635.608 60.0809 12.7775 + endloop + endfacet + facet normal -0.196921 -0.60925 0.768138 + outer loop + vertex -641.02 65.002 15.8866 + vertex -641.092 63.215 14.4506 + vertex -635.329 63.1614 15.8855 + endloop + endfacet + facet normal -0.197349 -0.606821 0.769949 + outer loop + vertex -635.329 63.1614 15.8855 + vertex -641.092 63.215 14.4506 + vertex -635.449 61.3767 14.4482 + endloop + endfacet + facet normal -0.192372 -0.607645 0.770559 + outer loop + vertex -635.329 63.1614 15.8855 + vertex -635.449 61.3767 14.4482 + vertex -629.471 61.3129 15.8903 + endloop + endfacet + facet normal -0.192025 -0.609687 0.76903 + outer loop + vertex -629.471 61.3129 15.8903 + vertex -635.449 61.3767 14.4482 + vertex -629.635 59.5463 14.4489 + endloop + endfacet + facet normal -0.23818 -0.756357 0.609257 + outer loop + vertex -635.449 61.3767 14.4482 + vertex -635.608 60.0809 12.7775 + vertex -629.635 59.5463 14.4489 + endloop + endfacet + facet normal -0.238647 -0.754339 0.611572 + outer loop + vertex -629.635 59.5463 14.4489 + vertex -635.608 60.0809 12.7775 + vertex -629.814 58.2493 12.7791 + endloop + endfacet + facet normal -0.25344 -0.755451 0.604204 + outer loop + vertex -652.104 66.8721 14.4558 + vertex -652.229 65.5805 12.7885 + vertex -646.618 65.033 14.4573 + endloop + endfacet + facet normal -0.253468 -0.755336 0.604335 + outer loop + vertex -646.618 65.033 14.4573 + vertex -652.229 65.5805 12.7885 + vertex -646.742 63.7388 12.7881 + endloop + endfacet + facet normal -0.204539 -0.610352 0.765267 + outer loop + vertex -652.088 68.6629 15.8884 + vertex -652.104 66.8721 14.4558 + vertex -646.584 66.823 15.892 + endloop + endfacet + facet normal -0.204647 -0.609772 0.765701 + outer loop + vertex -646.584 66.823 15.892 + vertex -652.104 66.8721 14.4558 + vertex -646.618 65.033 14.4573 + endloop + endfacet + facet normal -0.199058 -0.610557 0.766548 + outer loop + vertex -646.584 66.823 15.892 + vertex -646.618 65.033 14.4573 + vertex -641.02 65.002 15.8866 + endloop + endfacet + facet normal -0.199368 -0.60888 0.7678 + outer loop + vertex -641.02 65.002 15.8866 + vertex -646.618 65.033 14.4573 + vertex -641.092 63.215 14.4506 + endloop + endfacet + facet normal -0.248165 -0.756616 0.604935 + outer loop + vertex -646.618 65.033 14.4573 + vertex -646.742 63.7388 12.7881 + vertex -641.092 63.215 14.4506 + endloop + endfacet + facet normal -0.249224 -0.752267 0.609903 + outer loop + vertex -641.092 63.215 14.4506 + vertex -646.742 63.7388 12.7881 + vertex -641.23 61.91 12.7847 + endloop + endfacet + facet normal -0.259179 -0.753446 0.604272 + outer loop + vertex -663.135 70.6396 14.4577 + vertex -663.293 69.3558 12.7893 + vertex -657.6 68.7346 14.4564 + endloop + endfacet + facet normal -0.259223 -0.753253 0.604495 + outer loop + vertex -657.6 68.7346 14.4564 + vertex -663.293 69.3558 12.7893 + vertex -657.739 67.4444 12.7893 + endloop + endfacet + facet normal -0.209658 -0.609774 0.764342 + outer loop + vertex -663.103 72.4266 15.8921 + vertex -663.135 70.6396 14.4577 + vertex -657.582 70.5245 15.8892 + endloop + endfacet + facet normal -0.209671 -0.609703 0.764395 + outer loop + vertex -657.582 70.5245 15.8892 + vertex -663.135 70.6396 14.4577 + vertex -657.6 68.7346 14.4564 + endloop + endfacet + facet normal -0.20664 -0.610126 0.764883 + outer loop + vertex -657.582 70.5245 15.8892 + vertex -657.6 68.7346 14.4564 + vertex -652.088 68.6629 15.8884 + endloop + endfacet + facet normal -0.206652 -0.610063 0.76493 + outer loop + vertex -652.088 68.6629 15.8884 + vertex -657.6 68.7346 14.4564 + vertex -652.104 66.8721 14.4558 + endloop + endfacet + facet normal -0.255514 -0.754187 0.604909 + outer loop + vertex -657.6 68.7346 14.4564 + vertex -657.739 67.4444 12.7893 + vertex -652.104 66.8721 14.4558 + endloop + endfacet + facet normal -0.255323 -0.75499 0.603987 + outer loop + vertex -652.104 66.8721 14.4558 + vertex -657.739 67.4444 12.7893 + vertex -652.229 65.5805 12.7885 + endloop + endfacet + facet normal -0.267358 -0.753235 0.600963 + outer loop + vertex -674.361 74.6044 14.4592 + vertex -674.545 73.3364 12.7879 + vertex -668.726 72.6019 14.4562 + endloop + endfacet + facet normal -0.268212 -0.749061 0.605781 + outer loop + vertex -668.726 72.6019 14.4562 + vertex -674.545 73.3364 12.7879 + vertex -668.898 71.316 12.7898 + endloop + endfacet + facet normal -0.216006 -0.604099 0.767076 + outer loop + vertex -674.314 76.4021 15.8882 + vertex -674.361 74.6044 14.4592 + vertex -668.683 74.3901 15.8892 + endloop + endfacet + facet normal -0.215489 -0.607524 0.764512 + outer loop + vertex -668.683 74.3901 15.8892 + vertex -674.361 74.6044 14.4592 + vertex -668.726 72.6019 14.4562 + endloop + endfacet + facet normal -0.214228 -0.607716 0.764714 + outer loop + vertex -668.683 74.3901 15.8892 + vertex -668.726 72.6019 14.4562 + vertex -663.103 72.4266 15.8921 + endloop + endfacet + facet normal -0.214 -0.609138 0.763646 + outer loop + vertex -663.103 72.4266 15.8921 + vertex -668.726 72.6019 14.4562 + vertex -663.135 70.6396 14.4577 + endloop + endfacet + facet normal -0.263512 -0.750329 0.606274 + outer loop + vertex -668.726 72.6019 14.4562 + vertex -668.898 71.316 12.7898 + vertex -663.135 70.6396 14.4577 + endloop + endfacet + facet normal -0.26306 -0.752432 0.603859 + outer loop + vertex -663.135 70.6396 14.4577 + vertex -668.898 71.316 12.7898 + vertex -663.293 69.3558 12.7893 + endloop + endfacet + facet normal -0.274857 -0.746502 0.60596 + outer loop + vertex -685.662 78.7431 14.458 + vertex -685.854 77.4612 12.7915 + vertex -680.021 76.6641 14.4554 + endloop + endfacet + facet normal -0.274806 -0.746773 0.60565 + outer loop + vertex -680.021 76.6641 14.4554 + vertex -685.854 77.4612 12.7915 + vertex -680.208 75.3815 12.7892 + endloop + endfacet + facet normal -0.222941 -0.604169 0.765034 + outer loop + vertex -685.596 80.533 15.8908 + vertex -685.662 78.7431 14.458 + vertex -679.962 78.4521 15.8893 + endloop + endfacet + facet normal -0.222774 -0.605379 0.764125 + outer loop + vertex -679.962 78.4521 15.8893 + vertex -685.662 78.7431 14.458 + vertex -680.021 76.6641 14.4554 + endloop + endfacet + facet normal -0.219756 -0.605869 0.764611 + outer loop + vertex -679.962 78.4521 15.8893 + vertex -680.021 76.6641 14.4554 + vertex -674.314 76.4021 15.8882 + endloop + endfacet + facet normal -0.220098 -0.603464 0.766413 + outer loop + vertex -674.314 76.4021 15.8882 + vertex -680.021 76.6641 14.4554 + vertex -674.361 74.6044 14.4592 + endloop + endfacet + facet normal -0.272387 -0.747454 0.605903 + outer loop + vertex -680.021 76.6641 14.4554 + vertex -680.208 75.3815 12.7892 + vertex -674.361 74.6044 14.4592 + endloop + endfacet + facet normal -0.271474 -0.752092 0.60055 + outer loop + vertex -674.361 74.6044 14.4592 + vertex -680.208 75.3815 12.7892 + vertex -674.545 73.3364 12.7879 + endloop + endfacet + facet normal -0.285792 -0.745439 0.602198 + outer loop + vertex -696.878 83.0091 14.4584 + vertex -697.078 81.7373 12.7893 + vertex -691.279 80.861 14.4565 + endloop + endfacet + facet normal -0.285792 -0.745442 0.602195 + outer loop + vertex -691.279 80.861 14.4565 + vertex -697.078 81.7373 12.7893 + vertex -691.474 79.5883 12.7883 + endloop + endfacet + facet normal -0.23207 -0.601587 0.764354 + outer loop + vertex -696.806 84.8015 15.891 + vertex -696.878 83.0091 14.4584 + vertex -691.204 82.6436 15.8935 + endloop + endfacet + facet normal -0.231694 -0.604577 0.762105 + outer loop + vertex -691.204 82.6436 15.8935 + vertex -696.878 83.0091 14.4584 + vertex -691.279 80.861 14.4565 + endloop + endfacet + facet normal -0.227451 -0.605315 0.762797 + outer loop + vertex -691.204 82.6436 15.8935 + vertex -691.279 80.861 14.4565 + vertex -685.596 80.533 15.8908 + endloop + endfacet + facet normal -0.227708 -0.603372 0.764259 + outer loop + vertex -685.596 80.533 15.8908 + vertex -691.279 80.861 14.4565 + vertex -685.662 78.7431 14.458 + endloop + endfacet + facet normal -0.281688 -0.746648 0.602634 + outer loop + vertex -691.279 80.861 14.4565 + vertex -691.474 79.5883 12.7883 + vertex -685.662 78.7431 14.458 + endloop + endfacet + facet normal -0.282099 -0.74442 0.605194 + outer loop + vertex -685.662 78.7431 14.458 + vertex -691.474 79.5883 12.7883 + vertex -685.854 77.4612 12.7915 + endloop + endfacet + facet normal -0.296807 -0.743737 0.598966 + outer loop + vertex -708.037 87.4293 14.4601 + vertex -708.237 86.163 12.7888 + vertex -702.471 85.2061 14.4576 + endloop + endfacet + facet normal -0.297352 -0.740487 0.602712 + outer loop + vertex -702.471 85.2061 14.4576 + vertex -708.237 86.163 12.7888 + vertex -702.672 83.9295 12.7902 + endloop + endfacet + facet normal -0.23945 -0.597142 0.765562 + outer loop + vertex -707.974 89.2351 15.8883 + vertex -708.037 87.4293 14.4601 + vertex -702.405 87.003 15.8893 + endloop + endfacet + facet normal -0.239168 -0.599618 0.763713 + outer loop + vertex -702.405 87.003 15.8893 + vertex -708.037 87.4293 14.4601 + vertex -702.471 85.2061 14.4576 + endloop + endfacet + facet normal -0.236209 -0.600137 0.764226 + outer loop + vertex -702.405 87.003 15.8893 + vertex -702.471 85.2061 14.4576 + vertex -696.806 84.8015 15.891 + endloop + endfacet + facet normal -0.236121 -0.600878 0.763671 + outer loop + vertex -696.806 84.8015 15.891 + vertex -702.471 85.2061 14.4576 + vertex -696.878 83.0091 14.4584 + endloop + endfacet + facet normal -0.29162 -0.742236 0.603361 + outer loop + vertex -702.471 85.2061 14.4576 + vertex -702.672 83.9295 12.7902 + vertex -696.878 83.0091 14.4584 + endloop + endfacet + facet normal -0.291356 -0.743772 0.601594 + outer loop + vertex -696.878 83.0091 14.4584 + vertex -702.672 83.9295 12.7902 + vertex -697.078 81.7373 12.7893 + endloop + endfacet + facet normal -0.307279 -0.739706 0.598678 + outer loop + vertex -718.92 91.9166 14.4591 + vertex -719.121 90.6487 12.7889 + vertex -713.531 89.6772 14.4578 + endloop + endfacet + facet normal -0.307806 -0.736564 0.60227 + outer loop + vertex -713.531 89.6772 14.4578 + vertex -719.121 90.6487 12.7889 + vertex -713.731 88.3979 12.7912 + endloop + endfacet + facet normal -0.248083 -0.598595 0.761668 + outer loop + vertex -718.835 93.7067 15.8935 + vertex -718.92 91.9166 14.4591 + vertex -713.461 91.4744 15.8894 + endloop + endfacet + facet normal -0.248193 -0.597632 0.762388 + outer loop + vertex -713.461 91.4744 15.8894 + vertex -718.92 91.9166 14.4591 + vertex -713.531 89.6772 14.4578 + endloop + endfacet + facet normal -0.244061 -0.598385 0.763131 + outer loop + vertex -713.461 91.4744 15.8894 + vertex -713.531 89.6772 14.4578 + vertex -707.974 89.2351 15.8883 + endloop + endfacet + facet normal -0.244297 -0.596287 0.764696 + outer loop + vertex -707.974 89.2351 15.8883 + vertex -713.531 89.6772 14.4578 + vertex -708.037 87.4293 14.4601 + endloop + endfacet + facet normal -0.30233 -0.738285 0.602935 + outer loop + vertex -713.531 89.6772 14.4578 + vertex -713.731 88.3979 12.7912 + vertex -708.037 87.4293 14.4601 + endloop + endfacet + facet normal -0.301673 -0.74223 0.598405 + outer loop + vertex -708.037 87.4293 14.4601 + vertex -713.731 88.3979 12.7912 + vertex -708.237 86.163 12.7888 + endloop + endfacet + facet normal -0.319872 -0.734625 0.598337 + outer loop + vertex -729.521 96.4796 14.454 + vertex -729.734 95.2148 12.787 + vertex -724.225 94.1759 14.4566 + endloop + endfacet + facet normal -0.320067 -0.733381 0.599757 + outer loop + vertex -724.225 94.1759 14.4566 + vertex -729.734 95.2148 12.787 + vertex -724.433 92.9033 12.7897 + endloop + endfacet + facet normal -0.259529 -0.595484 0.760292 + outer loop + vertex -729.418 98.2643 15.8871 + vertex -729.521 96.4796 14.454 + vertex -724.129 95.9627 15.8897 + endloop + endfacet + facet normal -0.259508 -0.595687 0.76014 + outer loop + vertex -724.129 95.9627 15.8897 + vertex -729.521 96.4796 14.454 + vertex -724.225 94.1759 14.4566 + endloop + endfacet + facet normal -0.25479 -0.596628 0.760997 + outer loop + vertex -724.129 95.9627 15.8897 + vertex -724.225 94.1759 14.4566 + vertex -718.835 93.7067 15.8935 + endloop + endfacet + facet normal -0.254712 -0.597326 0.760476 + outer loop + vertex -718.835 93.7067 15.8935 + vertex -724.225 94.1759 14.4566 + vertex -718.92 91.9166 14.4591 + endloop + endfacet + facet normal -0.313493 -0.735539 0.600586 + outer loop + vertex -724.225 94.1759 14.4566 + vertex -724.433 92.9033 12.7897 + vertex -718.92 91.9166 14.4591 + endloop + endfacet + facet normal -0.31311 -0.737836 0.597963 + outer loop + vertex -718.92 91.9166 14.4591 + vertex -724.433 92.9033 12.7897 + vertex -719.121 90.6487 12.7889 + endloop + endfacet + facet normal -0.331798 -0.731283 0.595932 + outer loop + vertex -740.301 101.316 14.4512 + vertex -740.524 100.059 12.7839 + vertex -734.875 98.8558 14.453 + endloop + endfacet + facet normal -0.332073 -0.729128 0.598415 + outer loop + vertex -734.875 98.8558 14.453 + vertex -740.524 100.059 12.7839 + vertex -735.095 97.5889 12.7873 + endloop + endfacet + facet normal -0.269056 -0.592413 0.759378 + outer loop + vertex -740.195 103.105 15.8839 + vertex -740.301 101.316 14.4512 + vertex -734.77 100.643 15.8853 + endloop + endfacet + facet normal -0.269031 -0.592746 0.759127 + outer loop + vertex -734.77 100.643 15.8853 + vertex -740.301 101.316 14.4512 + vertex -734.875 98.8558 14.453 + endloop + endfacet + facet normal -0.264091 -0.593779 0.760054 + outer loop + vertex -734.77 100.643 15.8853 + vertex -734.875 98.8558 14.453 + vertex -729.418 98.2643 15.8871 + endloop + endfacet + facet normal -0.264022 -0.594561 0.759466 + outer loop + vertex -729.418 98.2643 15.8871 + vertex -734.875 98.8558 14.453 + vertex -729.521 96.4796 14.454 + endloop + endfacet + facet normal -0.324818 -0.731621 0.599352 + outer loop + vertex -734.875 98.8558 14.453 + vertex -735.095 97.5889 12.7873 + vertex -729.521 96.4796 14.454 + endloop + endfacet + facet normal -0.324616 -0.733032 0.597736 + outer loop + vertex -729.521 96.4796 14.454 + vertex -735.095 97.5889 12.7873 + vertex -729.734 95.2148 12.787 + endloop + endfacet + facet normal -0.343388 -0.722916 0.599564 + outer loop + vertex -751.117 106.388 14.4402 + vertex -751.346 105.119 12.7798 + vertex -745.742 103.84 14.4465 + endloop + endfacet + facet normal -0.34308 -0.725655 0.596423 + outer loop + vertex -745.742 103.84 14.4465 + vertex -751.346 105.119 12.7798 + vertex -745.966 102.578 12.7821 + endloop + endfacet + facet normal -0.279751 -0.586256 0.760292 + outer loop + vertex -750.993 108.178 15.8664 + vertex -751.117 106.388 14.4402 + vertex -745.633 105.632 15.8755 + endloop + endfacet + facet normal -0.279645 -0.588056 0.758939 + outer loop + vertex -745.633 105.632 15.8755 + vertex -751.117 106.388 14.4402 + vertex -745.742 103.84 14.4465 + endloop + endfacet + facet normal -0.274985 -0.589071 0.759854 + outer loop + vertex -745.633 105.632 15.8755 + vertex -745.742 103.84 14.4465 + vertex -740.195 103.105 15.8839 + endloop + endfacet + facet normal -0.274852 -0.591177 0.758265 + outer loop + vertex -740.195 103.105 15.8839 + vertex -745.742 103.84 14.4465 + vertex -740.301 101.316 14.4512 + endloop + endfacet + facet normal -0.337935 -0.72749 0.597124 + outer loop + vertex -745.742 103.84 14.4465 + vertex -745.966 102.578 12.7821 + vertex -740.301 101.316 14.4512 + endloop + endfacet + facet normal -0.337735 -0.729197 0.595154 + outer loop + vertex -740.301 101.316 14.4512 + vertex -745.966 102.578 12.7821 + vertex -740.524 100.059 12.7839 + endloop + endfacet + facet normal -0.356366 -0.714726 0.601805 + outer loop + vertex -761.615 111.536 14.426 + vertex -761.859 110.265 12.7728 + vertex -756.393 108.941 14.4361 + endloop + endfacet + facet normal -0.355838 -0.719832 0.596004 + outer loop + vertex -756.393 108.941 14.4361 + vertex -761.859 110.265 12.7728 + vertex -756.63 107.682 12.7746 + endloop + endfacet + facet normal -0.291374 -0.581168 0.759832 + outer loop + vertex -761.465 113.319 15.8473 + vertex -761.615 111.536 14.426 + vertex -756.252 110.724 15.8615 + endloop + endfacet + facet normal -0.291277 -0.583155 0.758346 + outer loop + vertex -756.252 110.724 15.8615 + vertex -761.615 111.536 14.426 + vertex -756.393 108.941 14.4361 + endloop + endfacet + facet normal -0.283817 -0.584921 0.759813 + outer loop + vertex -756.252 110.724 15.8615 + vertex -756.393 108.941 14.4361 + vertex -750.993 108.178 15.8664 + endloop + endfacet + facet normal -0.283793 -0.585343 0.759497 + outer loop + vertex -750.993 108.178 15.8664 + vertex -756.393 108.941 14.4361 + vertex -751.117 106.388 14.4402 + endloop + endfacet + facet normal -0.349819 -0.722078 0.596849 + outer loop + vertex -756.393 108.941 14.4361 + vertex -756.63 107.682 12.7746 + vertex -751.117 106.388 14.4402 + endloop + endfacet + facet normal -0.349992 -0.720513 0.598637 + outer loop + vertex -751.117 106.388 14.4402 + vertex -756.63 107.682 12.7746 + vertex -751.346 105.119 12.7798 + endloop + endfacet + facet normal -0.371224 -0.709923 0.5985 + outer loop + vertex -772.114 116.932 14.4053 + vertex -772.371 115.675 12.7559 + vertex -766.846 114.188 14.4186 + endloop + endfacet + facet normal -0.371054 -0.712191 0.595906 + outer loop + vertex -766.846 114.188 14.4186 + vertex -772.371 115.675 12.7559 + vertex -767.097 112.934 12.7639 + endloop + endfacet + facet normal -0.301819 -0.573633 0.761479 + outer loop + vertex -771.957 118.723 15.8171 + vertex -772.114 116.932 14.4053 + vertex -766.691 115.976 15.8351 + endloop + endfacet + facet normal -0.301774 -0.575784 0.759872 + outer loop + vertex -766.691 115.976 15.8351 + vertex -772.114 116.932 14.4053 + vertex -766.846 114.188 14.4186 + endloop + endfacet + facet normal -0.295383 -0.577372 0.761177 + outer loop + vertex -766.691 115.976 15.8351 + vertex -766.846 114.188 14.4186 + vertex -761.465 113.319 15.8473 + endloop + endfacet + facet normal -0.295278 -0.580216 0.759052 + outer loop + vertex -761.465 113.319 15.8473 + vertex -766.846 114.188 14.4186 + vertex -761.615 111.536 14.426 + endloop + endfacet + facet normal -0.363474 -0.715169 0.59701 + outer loop + vertex -766.846 114.188 14.4186 + vertex -767.097 112.934 12.7639 + vertex -761.615 111.536 14.426 + endloop + endfacet + facet normal -0.363767 -0.711901 0.600725 + outer loop + vertex -761.615 111.536 14.426 + vertex -767.097 112.934 12.7639 + vertex -761.859 110.265 12.7728 + endloop + endfacet + facet normal -0.38355 -0.700171 0.602205 + outer loop + vertex -782.596 122.569 14.3778 + vertex -782.873 121.311 12.7387 + vertex -777.383 119.728 14.3945 + endloop + endfacet + facet normal -0.383467 -0.701736 0.600433 + outer loop + vertex -777.383 119.728 14.3945 + vertex -782.873 121.311 12.7387 + vertex -777.649 118.466 12.7505 + endloop + endfacet + facet normal -0.311316 -0.564015 0.764833 + outer loop + vertex -782.406 124.361 15.7766 + vertex -782.596 122.569 14.3778 + vertex -777.213 121.524 15.7988 + endloop + endfacet + facet normal -0.311313 -0.566694 0.762852 + outer loop + vertex -777.213 121.524 15.7988 + vertex -782.596 122.569 14.3778 + vertex -777.383 119.728 14.3945 + endloop + endfacet + facet normal -0.30551 -0.568201 0.764076 + outer loop + vertex -777.213 121.524 15.7988 + vertex -777.383 119.728 14.3945 + vertex -771.957 118.723 15.8171 + endloop + endfacet + facet normal -0.305465 -0.572713 0.760718 + outer loop + vertex -771.957 118.723 15.8171 + vertex -777.383 119.728 14.3945 + vertex -772.114 116.932 14.4053 + endloop + endfacet + facet normal -0.375362 -0.705053 0.601668 + outer loop + vertex -777.383 119.728 14.3945 + vertex -777.649 118.466 12.7505 + vertex -772.114 116.932 14.4053 + endloop + endfacet + facet normal -0.375154 -0.70835 0.597913 + outer loop + vertex -772.114 116.932 14.4053 + vertex -777.649 118.466 12.7505 + vertex -772.371 115.675 12.7559 + endloop + endfacet + facet normal -0.396638 -0.688583 0.607068 + outer loop + vertex -792.777 128.317 14.3415 + vertex -793.08 127.059 12.7161 + vertex -787.722 125.424 14.3623 + endloop + endfacet + facet normal -0.396506 -0.692068 0.603179 + outer loop + vertex -787.722 125.424 14.3623 + vertex -793.08 127.059 12.7161 + vertex -788.013 124.167 12.729 + endloop + endfacet + facet normal -0.321223 -0.553139 0.76867 + outer loop + vertex -792.548 130.107 15.725 + vertex -792.777 128.317 14.3415 + vertex -787.513 127.22 15.7514 + endloop + endfacet + facet normal -0.321258 -0.555745 0.766773 + outer loop + vertex -787.513 127.22 15.7514 + vertex -792.777 128.317 14.3415 + vertex -787.722 125.424 14.3623 + endloop + endfacet + facet normal -0.315743 -0.557291 0.767941 + outer loop + vertex -787.513 127.22 15.7514 + vertex -787.722 125.424 14.3623 + vertex -782.406 124.361 15.7766 + endloop + endfacet + facet normal -0.31577 -0.562811 0.763893 + outer loop + vertex -782.406 124.361 15.7766 + vertex -787.722 125.424 14.3623 + vertex -782.596 122.569 14.3778 + endloop + endfacet + facet normal -0.389069 -0.69528 0.604327 + outer loop + vertex -787.722 125.424 14.3623 + vertex -788.013 124.167 12.729 + vertex -782.596 122.569 14.3778 + endloop + endfacet + facet normal -0.388944 -0.697904 0.601376 + outer loop + vertex -782.596 122.569 14.3778 + vertex -788.013 124.167 12.729 + vertex -782.873 121.311 12.7387 + endloop + endfacet + facet normal -0.410691 -0.675996 0.611852 + outer loop + vertex -802.792 134.268 14.2954 + vertex -803.123 133.013 12.6863 + vertex -797.791 131.253 14.3216 + endloop + endfacet + facet normal -0.410651 -0.680259 0.607136 + outer loop + vertex -797.791 131.253 14.3216 + vertex -803.123 133.013 12.6863 + vertex -798.107 129.999 12.7023 + endloop + endfacet + facet normal -0.331034 -0.538193 0.77509 + outer loop + vertex -802.523 136.061 15.6558 + vertex -802.792 134.268 14.2954 + vertex -797.544 133.051 15.6916 + endloop + endfacet + facet normal -0.331223 -0.542782 0.771802 + outer loop + vertex -797.544 133.051 15.6916 + vertex -802.792 134.268 14.2954 + vertex -797.791 131.253 14.3216 + endloop + endfacet + facet normal -0.325929 -0.544371 0.772936 + outer loop + vertex -797.544 133.051 15.6916 + vertex -797.791 131.253 14.3216 + vertex -792.548 130.107 15.725 + endloop + endfacet + facet normal -0.326115 -0.551712 0.767635 + outer loop + vertex -792.548 130.107 15.725 + vertex -797.791 131.253 14.3216 + vertex -792.777 128.317 14.3415 + endloop + endfacet + facet normal -0.402838 -0.683821 0.608367 + outer loop + vertex -797.791 131.253 14.3216 + vertex -798.107 129.999 12.7023 + vertex -792.777 128.317 14.3415 + endloop + endfacet + facet normal -0.402785 -0.685859 0.606104 + outer loop + vertex -792.777 128.317 14.3415 + vertex -798.107 129.999 12.7023 + vertex -793.08 127.059 12.7161 + endloop + endfacet + facet normal -0.424894 -0.661404 0.618069 + outer loop + vertex -812.802 140.548 14.2433 + vertex -813.175 139.301 12.6526 + vertex -807.792 137.356 14.2715 + endloop + endfacet + facet normal -0.424943 -0.662936 0.616392 + outer loop + vertex -807.792 137.356 14.2715 + vertex -813.175 139.301 12.6526 + vertex -808.145 136.096 12.6735 + endloop + endfacet + facet normal -0.340386 -0.522512 0.781741 + outer loop + vertex -812.479 142.338 15.5801 + vertex -812.802 140.548 14.2433 + vertex -807.497 139.151 15.6192 + endloop + endfacet + facet normal -0.340827 -0.528053 0.777815 + outer loop + vertex -807.497 139.151 15.6192 + vertex -812.802 140.548 14.2433 + vertex -807.792 137.356 14.2715 + endloop + endfacet + facet normal -0.334873 -0.529986 0.779086 + outer loop + vertex -807.497 139.151 15.6192 + vertex -807.792 137.356 14.2715 + vertex -802.523 136.061 15.6558 + endloop + endfacet + facet normal -0.335277 -0.53687 0.774184 + outer loop + vertex -802.523 136.061 15.6558 + vertex -807.792 137.356 14.2715 + vertex -802.792 134.268 14.2954 + endloop + endfacet + facet normal -0.415271 -0.667607 0.617942 + outer loop + vertex -807.792 137.356 14.2715 + vertex -808.145 136.096 12.6735 + vertex -802.792 134.268 14.2954 + endloop + endfacet + facet normal -0.415327 -0.673826 0.611115 + outer loop + vertex -802.792 134.268 14.2954 + vertex -808.145 136.096 12.6735 + vertex -803.123 133.013 12.6863 + endloop + endfacet + facet normal -0.439196 -0.640551 0.629921 + outer loop + vertex -822.818 147.238 14.1846 + vertex -823.235 145.985 12.6193 + vertex -817.816 143.839 14.216 + endloop + endfacet + facet normal -0.439814 -0.648632 0.62116 + outer loop + vertex -817.816 143.839 14.216 + vertex -823.235 145.985 12.6193 + vertex -818.212 142.594 12.6355 + endloop + endfacet + facet normal -0.350682 -0.503714 0.78949 + outer loop + vertex -822.446 149.03 15.493 + vertex -822.818 147.238 14.1846 + vertex -817.469 145.634 15.5371 + endloop + endfacet + facet normal -0.351455 -0.509986 0.785108 + outer loop + vertex -817.469 145.634 15.5371 + vertex -822.818 147.238 14.1846 + vertex -817.816 143.839 14.216 + endloop + endfacet + facet normal -0.345144 -0.512202 0.786463 + outer loop + vertex -817.469 145.634 15.5371 + vertex -817.816 143.839 14.216 + vertex -812.479 142.338 15.5801 + endloop + endfacet + facet normal -0.345997 -0.520608 0.780547 + outer loop + vertex -812.479 142.338 15.5801 + vertex -817.816 143.839 14.216 + vertex -812.802 140.548 14.2433 + endloop + endfacet + facet normal -0.43188 -0.652748 0.622415 + outer loop + vertex -817.816 143.839 14.216 + vertex -818.212 142.594 12.6355 + vertex -812.802 140.548 14.2433 + endloop + endfacet + facet normal -0.432146 -0.657769 0.61692 + outer loop + vertex -812.802 140.548 14.2433 + vertex -818.212 142.594 12.6355 + vertex -813.175 139.301 12.6526 + endloop + endfacet + facet normal -0.457364 -0.626206 0.631415 + outer loop + vertex -832.645 154.24 14.129 + vertex -833.1 153.009 12.5785 + vertex -827.774 150.71 14.1563 + endloop + endfacet + facet normal -0.457916 -0.631162 0.626057 + outer loop + vertex -827.774 150.71 14.1563 + vertex -833.1 153.009 12.5785 + vertex -828.209 149.478 12.5961 + endloop + endfacet + facet normal -0.359391 -0.481551 0.799341 + outer loop + vertex -832.219 156.042 15.4059 + vertex -832.645 154.24 14.129 + vertex -827.375 152.502 15.4512 + endloop + endfacet + facet normal -0.361058 -0.492075 0.792149 + outer loop + vertex -827.375 152.502 15.4512 + vertex -832.645 154.24 14.129 + vertex -827.774 150.71 14.1563 + endloop + endfacet + facet normal -0.354977 -0.494379 0.793461 + outer loop + vertex -827.375 152.502 15.4512 + vertex -827.774 150.71 14.1563 + vertex -822.446 149.03 15.493 + endloop + endfacet + facet normal -0.356021 -0.501766 0.78834 + outer loop + vertex -822.446 149.03 15.493 + vertex -827.774 150.71 14.1563 + vertex -822.818 147.238 14.1846 + endloop + endfacet + facet normal -0.449163 -0.636033 0.627467 + outer loop + vertex -827.774 150.71 14.1563 + vertex -828.209 149.478 12.5961 + vertex -822.818 147.238 14.1846 + endloop + endfacet + facet normal -0.449087 -0.635252 0.628312 + outer loop + vertex -822.818 147.238 14.1846 + vertex -828.209 149.478 12.5961 + vertex -823.235 145.985 12.6193 + endloop + endfacet + facet normal -0.469582 -0.605731 0.642326 + outer loop + vertex -841.992 161.366 14.0882 + vertex -842.486 160.125 12.5574 + vertex -837.393 157.813 14.1002 + endloop + endfacet + facet normal -0.470005 -0.608825 0.639084 + outer loop + vertex -837.393 157.813 14.1002 + vertex -842.486 160.125 12.5574 + vertex -837.868 156.567 12.5643 + endloop + endfacet + facet normal -0.367169 -0.465539 0.80527 + outer loop + vertex -841.492 163.15 15.3473 + vertex -841.992 161.366 14.0882 + vertex -836.937 159.599 15.3714 + endloop + endfacet + facet normal -0.368829 -0.474771 0.799098 + outer loop + vertex -836.937 159.599 15.3714 + vertex -841.992 161.366 14.0882 + vertex -837.393 157.813 14.1002 + endloop + endfacet + facet normal -0.364942 -0.47636 0.799936 + outer loop + vertex -836.937 159.599 15.3714 + vertex -837.393 157.813 14.1002 + vertex -832.219 156.042 15.4059 + endloop + endfacet + facet normal -0.365427 -0.479189 0.798023 + outer loop + vertex -832.219 156.042 15.4059 + vertex -837.393 157.813 14.1002 + vertex -832.645 154.24 14.129 + endloop + endfacet + facet normal -0.464474 -0.612082 0.640015 + outer loop + vertex -837.393 157.813 14.1002 + vertex -837.868 156.567 12.5643 + vertex -832.645 154.24 14.129 + endloop + endfacet + facet normal -0.465661 -0.621438 0.63006 + outer loop + vertex -832.645 154.24 14.129 + vertex -837.868 156.567 12.5643 + vertex -833.1 153.009 12.5785 + endloop + endfacet + facet normal -0.485812 -0.584062 0.650275 + outer loop + vertex -850.744 168.473 14.053 + vertex -851.304 167.252 12.538 + vertex -846.427 164.91 14.0782 + endloop + endfacet + facet normal -0.486874 -0.590858 0.643305 + outer loop + vertex -846.427 164.91 14.0782 + vertex -851.304 167.252 12.538 + vertex -846.948 163.679 12.5526 + endloop + endfacet + facet normal -0.376712 -0.448931 0.810277 + outer loop + vertex -850.13 170.207 15.299 + vertex -850.744 168.473 14.053 + vertex -845.871 166.682 15.326 + endloop + endfacet + facet normal -0.377185 -0.451321 0.808728 + outer loop + vertex -845.871 166.682 15.326 + vertex -850.744 168.473 14.053 + vertex -846.427 164.91 14.0782 + endloop + endfacet + facet normal -0.370501 -0.454384 0.810102 + outer loop + vertex -845.871 166.682 15.326 + vertex -846.427 164.91 14.0782 + vertex -841.492 163.15 15.3473 + endloop + endfacet + facet normal -0.372195 -0.46338 0.804208 + outer loop + vertex -841.492 163.15 15.3473 + vertex -846.427 164.91 14.0782 + vertex -841.992 161.366 14.0882 + endloop + endfacet + facet normal -0.478135 -0.596371 0.64477 + outer loop + vertex -846.427 164.91 14.0782 + vertex -846.948 163.679 12.5526 + vertex -841.992 161.366 14.0882 + endloop + endfacet + facet normal -0.47869 -0.600206 0.640787 + outer loop + vertex -841.992 161.366 14.0882 + vertex -846.948 163.679 12.5526 + vertex -842.486 160.125 12.5574 + endloop + endfacet + facet normal -0.511113 -0.572087 0.641467 + outer loop + vertex -859.527 176.052 13.9301 + vertex -860.137 174.91 12.4253 + vertex -855.065 172.143 13.9993 + endloop + endfacet + facet normal -0.509793 -0.566031 0.647857 + outer loop + vertex -855.065 172.143 13.9993 + vertex -860.137 174.91 12.4253 + vertex -855.66 170.952 12.4905 + endloop + endfacet + facet normal -0.394822 -0.437424 0.807945 + outer loop + vertex -858.904 177.763 15.1605 + vertex -859.527 176.052 13.9301 + vertex -854.423 173.858 15.2362 + endloop + endfacet + facet normal -0.394434 -0.43593 0.808942 + outer loop + vertex -854.423 173.858 15.2362 + vertex -859.527 176.052 13.9301 + vertex -855.065 172.143 13.9993 + endloop + endfacet + facet normal -0.386207 -0.440202 0.810596 + outer loop + vertex -854.423 173.858 15.2362 + vertex -855.065 172.143 13.9993 + vertex -850.13 170.207 15.299 + endloop + endfacet + facet normal -0.387006 -0.443821 0.808238 + outer loop + vertex -850.13 170.207 15.299 + vertex -855.065 172.143 13.9993 + vertex -850.744 168.473 14.053 + endloop + endfacet + facet normal -0.496658 -0.57524 0.649946 + outer loop + vertex -855.065 172.143 13.9993 + vertex -855.66 170.952 12.4905 + vertex -850.744 168.473 14.053 + endloop + endfacet + facet normal -0.49692 -0.576704 0.648447 + outer loop + vertex -850.744 168.473 14.053 + vertex -855.66 170.952 12.4905 + vertex -851.304 167.252 12.538 + endloop + endfacet + facet normal -0.511723 -0.54124 0.667233 + outer loop + vertex -868.563 184.614 14.0377 + vertex -869.177 183.414 12.5934 + vertex -864.131 180.269 13.9118 + endloop + endfacet + facet normal -0.518213 -0.560591 0.645905 + outer loop + vertex -864.131 180.269 13.9118 + vertex -869.177 183.414 12.5934 + vertex -864.735 179.117 12.4269 + endloop + endfacet + facet normal -0.393768 -0.41359 0.820908 + outer loop + vertex -867.942 186.378 15.2242 + vertex -868.563 184.614 14.0377 + vertex -863.541 182.001 15.1295 + endloop + endfacet + facet normal -0.400516 -0.431899 0.808115 + outer loop + vertex -863.541 182.001 15.1295 + vertex -868.563 184.614 14.0377 + vertex -864.131 180.269 13.9118 + endloop + endfacet + facet normal -0.40027 -0.432022 0.808171 + outer loop + vertex -863.541 182.001 15.1295 + vertex -864.131 180.269 13.9118 + vertex -858.904 177.763 15.1605 + endloop + endfacet + facet normal -0.400968 -0.434243 0.806633 + outer loop + vertex -858.904 177.763 15.1605 + vertex -864.131 180.269 13.9118 + vertex -859.527 176.052 13.9301 + endloop + endfacet + facet normal -0.516928 -0.561535 0.646115 + outer loop + vertex -864.131 180.269 13.9118 + vertex -864.735 179.117 12.4269 + vertex -859.527 176.052 13.9301 + endloop + endfacet + facet normal -0.518353 -0.566774 0.640373 + outer loop + vertex -859.527 176.052 13.9301 + vertex -864.735 179.117 12.4269 + vertex -860.137 174.91 12.4253 + endloop + endfacet + facet normal -0.37277 -0.379513 0.846766 + outer loop + vertex -871.485 190.426 15.4781 + vertex -872.292 188.678 14.3396 + vertex -867.942 186.378 15.2242 + endloop + endfacet + facet normal -0.387476 -0.416745 0.822305 + outer loop + vertex -867.942 186.378 15.2242 + vertex -872.292 188.678 14.3396 + vertex -868.563 184.614 14.0377 + endloop + endfacet + facet normal -0.49203 -0.504339 0.709612 + outer loop + vertex -872.292 188.678 14.3396 + vertex -872.998 187.416 12.9533 + vertex -868.563 184.614 14.0377 + endloop + endfacet + facet normal -0.507224 -0.544492 0.668022 + outer loop + vertex -868.563 184.614 14.0377 + vertex -872.998 187.416 12.9533 + vertex -869.177 183.414 12.5934 + endloop + endfacet + facet normal -0.32852 -0.943468 0.0440678 + outer loop + vertex -610.104 51.367 10.8875 + vertex -610.195 51.3089 8.95965 + vertex -608.104 50.6579 10.6094 + endloop + endfacet + facet normal -0.275414 -0.960854 -0.0301023 + outer loop + vertex -608.104 50.6579 10.6094 + vertex -610.195 51.3089 8.95965 + vertex -608.149 50.7319 8.65503 + endloop + endfacet + facet normal -0.311356 -0.876057 0.368214 + outer loop + vertex -609.987 52.1004 12.7314 + vertex -610.104 51.367 10.8875 + vertex -608.006 51.2846 12.4652 + endloop + endfacet + facet normal -0.276713 -0.905895 0.320598 + outer loop + vertex -608.006 51.2846 12.4652 + vertex -610.104 51.367 10.8875 + vertex -608.104 50.6579 10.6094 + endloop + endfacet + facet normal -0.294897 -0.953457 0.062888 + outer loop + vertex -618.454 54.0238 10.9799 + vertex -618.553 53.9272 9.04862 + vertex -613.635 52.534 10.9877 + endloop + endfacet + facet normal -0.299279 -0.951162 0.0756531 + outer loop + vertex -613.635 52.534 10.9877 + vertex -618.553 53.9272 9.04862 + vertex -613.719 52.4079 9.06892 + endloop + endfacet + facet normal -0.270859 -0.886735 0.374615 + outer loop + vertex -618.319 54.7669 12.8366 + vertex -618.454 54.0238 10.9799 + vertex -613.512 53.2973 12.8332 + endloop + endfacet + facet normal -0.273413 -0.882285 0.383169 + outer loop + vertex -613.512 53.2973 12.8332 + vertex -618.454 54.0238 10.9799 + vertex -613.635 52.534 10.9877 + endloop + endfacet + facet normal -0.287115 -0.87825 0.382415 + outer loop + vertex -613.512 53.2973 12.8332 + vertex -613.635 52.534 10.9877 + vertex -609.987 52.1004 12.7314 + endloop + endfacet + facet normal -0.282004 -0.885201 0.369991 + outer loop + vertex -609.987 52.1004 12.7314 + vertex -613.635 52.534 10.9877 + vertex -610.104 51.367 10.8875 + endloop + endfacet + facet normal -0.3109 -0.947406 0.0759168 + outer loop + vertex -613.635 52.534 10.9877 + vertex -613.719 52.4079 9.06892 + vertex -610.104 51.367 10.8875 + endloop + endfacet + facet normal -0.296215 -0.954159 0.0428528 + outer loop + vertex -610.104 51.367 10.8875 + vertex -613.719 52.4079 9.06892 + vertex -610.195 51.3089 8.95965 + endloop + endfacet + facet normal -0.294554 -0.954519 0.0461691 + outer loop + vertex -629.94 57.5284 10.9226 + vertex -630.02 57.459 8.98098 + vertex -624.066 55.7168 10.944 + endloop + endfacet + facet normal -0.295046 -0.954283 0.0478681 + outer loop + vertex -624.066 55.7168 10.944 + vertex -630.02 57.459 8.98098 + vertex -624.156 55.6472 9.00261 + endloop + endfacet + facet normal -0.273222 -0.890302 0.364297 + outer loop + vertex -629.814 58.2493 12.7791 + vertex -629.94 57.5284 10.9226 + vertex -623.941 56.4557 12.8008 + endloop + endfacet + facet normal -0.274859 -0.886804 0.371524 + outer loop + vertex -623.941 56.4557 12.8008 + vertex -629.94 57.5284 10.9226 + vertex -624.066 55.7168 10.944 + endloop + endfacet + facet normal -0.269239 -0.888418 0.371785 + outer loop + vertex -623.941 56.4557 12.8008 + vertex -624.066 55.7168 10.944 + vertex -618.319 54.7669 12.8366 + endloop + endfacet + facet normal -0.269948 -0.886996 0.374654 + outer loop + vertex -618.319 54.7669 12.8366 + vertex -624.066 55.7168 10.944 + vertex -618.454 54.0238 10.9799 + endloop + endfacet + facet normal -0.288742 -0.956221 0.0476459 + outer loop + vertex -624.066 55.7168 10.944 + vertex -624.156 55.6472 9.00261 + vertex -618.454 54.0238 10.9799 + endloop + endfacet + facet normal -0.293357 -0.953936 0.0628326 + outer loop + vertex -618.454 54.0238 10.9799 + vertex -624.156 55.6472 9.00261 + vertex -618.553 53.9272 9.04862 + endloop + endfacet + facet normal -0.310008 -0.949438 0.04962 + outer loop + vertex -641.352 61.192 10.9301 + vertex -641.423 61.1139 8.99348 + vertex -635.732 59.3564 10.9227 + endloop + endfacet + facet normal -0.309323 -0.949781 0.0472883 + outer loop + vertex -635.732 59.3564 10.9227 + vertex -641.423 61.1139 8.99348 + vertex -635.804 59.2835 8.98352 + endloop + endfacet + facet normal -0.287948 -0.886508 0.3622 + outer loop + vertex -641.23 61.91 12.7847 + vertex -641.352 61.192 10.9301 + vertex -635.608 60.0809 12.7775 + endloop + endfacet + facet normal -0.288593 -0.885138 0.365028 + outer loop + vertex -635.608 60.0809 12.7775 + vertex -641.352 61.192 10.9301 + vertex -635.732 59.3564 10.9227 + endloop + endfacet + facet normal -0.280683 -0.887513 0.365428 + outer loop + vertex -635.608 60.0809 12.7775 + vertex -635.732 59.3564 10.9227 + vertex -629.814 58.2493 12.7791 + endloop + endfacet + facet normal -0.280357 -0.888214 0.363971 + outer loop + vertex -629.814 58.2493 12.7791 + vertex -635.732 59.3564 10.9227 + vertex -629.94 57.5284 10.9226 + endloop + endfacet + facet normal -0.300674 -0.952565 0.0470684 + outer loop + vertex -635.732 59.3564 10.9227 + vertex -635.804 59.2835 8.98352 + vertex -629.94 57.5284 10.9226 + endloop + endfacet + facet normal -0.300465 -0.952666 0.0463444 + outer loop + vertex -629.94 57.5284 10.9226 + vertex -635.804 59.2835 8.98352 + vertex -630.02 57.459 8.98098 + endloop + endfacet + facet normal -0.317699 -0.946907 0.0493325 + outer loop + vertex -652.369 64.8595 10.9369 + vertex -652.455 64.7877 9.00149 + vertex -646.871 63.0148 10.9363 + endloop + endfacet + facet normal -0.317194 -0.947163 0.04764 + outer loop + vertex -646.871 63.0148 10.9363 + vertex -652.455 64.7877 9.00149 + vertex -646.946 62.9426 9.00022 + endloop + endfacet + facet normal -0.29609 -0.882282 0.365937 + outer loop + vertex -652.229 65.5805 12.7885 + vertex -652.369 64.8595 10.9369 + vertex -646.742 63.7388 12.7881 + endloop + endfacet + facet normal -0.296027 -0.882415 0.365667 + outer loop + vertex -646.742 63.7388 12.7881 + vertex -652.369 64.8595 10.9369 + vertex -646.871 63.0148 10.9363 + endloop + endfacet + facet normal -0.292883 -0.883395 0.365831 + outer loop + vertex -646.742 63.7388 12.7881 + vertex -646.871 63.0148 10.9363 + vertex -641.23 61.91 12.7847 + endloop + endfacet + facet normal -0.291991 -0.885272 0.361988 + outer loop + vertex -641.23 61.91 12.7847 + vertex -646.871 63.0148 10.9363 + vertex -641.352 61.192 10.9301 + endloop + endfacet + facet normal -0.313228 -0.948488 0.0475351 + outer loop + vertex -646.871 63.0148 10.9363 + vertex -646.946 62.9426 9.00022 + vertex -641.352 61.192 10.9301 + endloop + endfacet + facet normal -0.313877 -0.948162 0.0497104 + outer loop + vertex -641.352 61.192 10.9301 + vertex -646.946 62.9426 9.00022 + vertex -641.423 61.1139 8.99348 + endloop + endfacet + facet normal -0.325898 -0.944122 0.0492386 + outer loop + vertex -663.462 68.6467 10.9359 + vertex -663.567 68.582 9.00003 + vertex -657.894 66.7247 10.9377 + endloop + endfacet + facet normal -0.326379 -0.943868 0.0508894 + outer loop + vertex -657.894 66.7247 10.9377 + vertex -663.567 68.582 9.00003 + vertex -657.993 66.6546 8.99942 + endloop + endfacet + facet normal -0.303019 -0.880518 0.36451 + outer loop + vertex -663.293 69.3558 12.7893 + vertex -663.462 68.6467 10.9359 + vertex -657.739 67.4444 12.7893 + endloop + endfacet + facet normal -0.303602 -0.879218 0.367153 + outer loop + vertex -657.739 67.4444 12.7893 + vertex -663.462 68.6467 10.9359 + vertex -657.894 66.7247 10.9377 + endloop + endfacet + facet normal -0.297996 -0.881035 0.36739 + outer loop + vertex -657.739 67.4444 12.7893 + vertex -657.894 66.7247 10.9377 + vertex -652.229 65.5805 12.7885 + endloop + endfacet + facet normal -0.297649 -0.881787 0.365863 + outer loop + vertex -652.229 65.5805 12.7885 + vertex -657.894 66.7247 10.9377 + vertex -652.369 64.8595 10.9369 + endloop + endfacet + facet normal -0.319459 -0.946247 0.050621 + outer loop + vertex -657.894 66.7247 10.9377 + vertex -657.993 66.6546 8.99942 + vertex -652.369 64.8595 10.9369 + endloop + endfacet + facet normal -0.319091 -0.946437 0.0493773 + outer loop + vertex -652.369 64.8595 10.9369 + vertex -657.993 66.6546 8.99942 + vertex -652.455 64.7877 9.00149 + endloop + endfacet + facet normal -0.335533 -0.940446 0.0545753 + outer loop + vertex -674.73 72.6227 10.9366 + vertex -674.843 72.5503 8.99798 + vertex -669.078 70.606 10.9362 + endloop + endfacet + facet normal -0.334316 -0.941119 0.0502795 + outer loop + vertex -669.078 70.606 10.9362 + vertex -674.843 72.5503 8.99798 + vertex -669.188 70.5415 8.99814 + endloop + endfacet + facet normal -0.313254 -0.875182 0.368685 + outer loop + vertex -674.545 73.3364 12.7879 + vertex -674.73 72.6227 10.9366 + vertex -668.898 71.316 12.7898 + endloop + endfacet + facet normal -0.312699 -0.876504 0.366006 + outer loop + vertex -668.898 71.316 12.7898 + vertex -674.73 72.6227 10.9366 + vertex -669.078 70.606 10.9362 + endloop + endfacet + facet normal -0.307131 -0.878394 0.36619 + outer loop + vertex -668.898 71.316 12.7898 + vertex -669.078 70.606 10.9362 + vertex -663.293 69.3558 12.7893 + endloop + endfacet + facet normal -0.306743 -0.879283 0.364377 + outer loop + vertex -663.293 69.3558 12.7893 + vertex -669.078 70.606 10.9362 + vertex -663.462 68.6467 10.9359 + endloop + endfacet + facet normal -0.328992 -0.943006 0.0500403 + outer loop + vertex -669.078 70.606 10.9362 + vertex -669.188 70.5415 8.99814 + vertex -663.462 68.6467 10.9359 + endloop + endfacet + facet normal -0.328796 -0.94311 0.0493619 + outer loop + vertex -663.462 68.6467 10.9359 + vertex -669.188 70.5415 8.99814 + vertex -663.567 68.582 9.00003 + endloop + endfacet + facet normal -0.34523 -0.937079 0.0519498 + outer loop + vertex -686.042 76.76 10.9362 + vertex -686.152 76.6929 8.99795 + vertex -680.394 74.6791 10.9362 + endloop + endfacet + facet normal -0.345256 -0.937064 0.0520437 + outer loop + vertex -680.394 74.6791 10.9362 + vertex -686.152 76.6929 8.99795 + vertex -680.505 74.6125 8.99783 + endloop + endfacet + facet normal -0.321916 -0.874409 0.363013 + outer loop + vertex -685.854 77.4612 12.7915 + vertex -686.042 76.76 10.9362 + vertex -680.208 75.3815 12.7892 + endloop + endfacet + facet normal -0.322033 -0.874125 0.363592 + outer loop + vertex -680.208 75.3815 12.7892 + vertex -686.042 76.76 10.9362 + vertex -680.394 74.6791 10.9362 + endloop + endfacet + facet normal -0.316328 -0.876128 0.36378 + outer loop + vertex -680.208 75.3815 12.7892 + vertex -680.394 74.6791 10.9362 + vertex -674.545 73.3364 12.7879 + endloop + endfacet + facet normal -0.317299 -0.873781 0.368549 + outer loop + vertex -674.545 73.3364 12.7879 + vertex -680.394 74.6791 10.9362 + vertex -674.73 72.6227 10.9366 + endloop + endfacet + facet normal -0.340845 -0.938689 0.051846 + outer loop + vertex -680.394 74.6791 10.9362 + vertex -680.505 74.6125 8.99783 + vertex -674.73 72.6227 10.9366 + endloop + endfacet + facet normal -0.341689 -0.938211 0.0548491 + outer loop + vertex -674.73 72.6227 10.9366 + vertex -680.505 74.6125 8.99783 + vertex -674.843 72.5503 8.99798 + endloop + endfacet + facet normal -0.357412 -0.932429 0.0532223 + outer loop + vertex -697.267 81.0339 10.937 + vertex -697.375 80.9646 8.99839 + vertex -691.662 78.8851 10.9358 + endloop + endfacet + facet normal -0.356756 -0.932811 0.0508765 + outer loop + vertex -691.662 78.8851 10.9358 + vertex -697.375 80.9646 8.99839 + vertex -691.769 78.8204 8.9986 + endloop + endfacet + facet normal -0.333427 -0.869534 0.36433 + outer loop + vertex -697.078 81.7373 12.7893 + vertex -697.267 81.0339 10.937 + vertex -691.474 79.5883 12.7883 + endloop + endfacet + facet normal -0.333331 -0.869777 0.363839 + outer loop + vertex -691.474 79.5883 12.7883 + vertex -697.267 81.0339 10.937 + vertex -691.662 78.8851 10.9358 + endloop + endfacet + facet normal -0.329883 -0.871036 0.363969 + outer loop + vertex -691.474 79.5883 12.7883 + vertex -691.662 78.8851 10.9358 + vertex -685.854 77.4612 12.7915 + endloop + endfacet + facet normal -0.32964 -0.871638 0.362746 + outer loop + vertex -685.854 77.4612 12.7915 + vertex -691.662 78.8851 10.9358 + vertex -686.042 76.76 10.9362 + endloop + endfacet + facet normal -0.353255 -0.934151 0.0507277 + outer loop + vertex -691.662 78.8851 10.9358 + vertex -691.769 78.8204 8.9986 + vertex -686.042 76.76 10.9362 + endloop + endfacet + facet normal -0.353701 -0.933894 0.0523193 + outer loop + vertex -686.042 76.76 10.9362 + vertex -691.769 78.8204 8.9986 + vertex -686.152 76.6929 8.99795 + endloop + endfacet + facet normal -0.370191 -0.92775 0.0473075 + outer loop + vertex -708.43 85.4551 10.937 + vertex -708.534 85.3978 8.99812 + vertex -702.863 83.2336 10.9357 + endloop + endfacet + facet normal -0.370938 -0.927312 0.0499822 + outer loop + vertex -702.863 83.2336 10.9357 + vertex -708.534 85.3978 8.99812 + vertex -702.968 83.1714 8.9983 + endloop + endfacet + facet normal -0.346678 -0.863528 0.366243 + outer loop + vertex -708.237 86.163 12.7888 + vertex -708.43 85.4551 10.937 + vertex -702.672 83.9295 12.7902 + endloop + endfacet + facet normal -0.345608 -0.866319 0.360621 + outer loop + vertex -702.672 83.9295 12.7902 + vertex -708.43 85.4551 10.937 + vertex -702.863 83.2336 10.9357 + endloop + endfacet + facet normal -0.340215 -0.868362 0.360833 + outer loop + vertex -702.672 83.9295 12.7902 + vertex -702.863 83.2336 10.9357 + vertex -697.078 81.7373 12.7893 + endloop + endfacet + facet normal -0.340834 -0.866779 0.364042 + outer loop + vertex -697.078 81.7373 12.7893 + vertex -702.863 83.2336 10.9357 + vertex -697.267 81.0339 10.937 + endloop + endfacet + facet normal -0.365424 -0.929511 0.049752 + outer loop + vertex -702.863 83.2336 10.9357 + vertex -702.968 83.1714 8.9983 + vertex -697.267 81.0339 10.937 + endloop + endfacet + facet normal -0.366494 -0.928875 0.0536001 + outer loop + vertex -697.267 81.0339 10.937 + vertex -702.968 83.1714 8.9983 + vertex -697.375 80.9646 8.99839 + endloop + endfacet + facet normal -0.384521 -0.921714 0.0508555 + outer loop + vertex -719.311 89.9505 10.9356 + vertex -719.414 89.8867 8.99779 + vertex -713.921 87.702 10.936 + endloop + endfacet + facet normal -0.384707 -0.9216 0.0515119 + outer loop + vertex -713.921 87.702 10.936 + vertex -719.414 89.8867 8.99779 + vertex -714.026 87.6375 8.99775 + endloop + endfacet + facet normal -0.359456 -0.860515 0.360977 + outer loop + vertex -719.121 90.6487 12.7889 + vertex -719.311 89.9505 10.9356 + vertex -713.731 88.3979 12.7912 + endloop + endfacet + facet normal -0.359243 -0.861065 0.359878 + outer loop + vertex -713.731 88.3979 12.7912 + vertex -719.311 89.9505 10.9356 + vertex -713.921 87.702 10.936 + endloop + endfacet + facet normal -0.351375 -0.864158 0.360231 + outer loop + vertex -713.731 88.3979 12.7912 + vertex -713.921 87.702 10.936 + vertex -708.237 86.163 12.7888 + endloop + endfacet + facet normal -0.352475 -0.861285 0.36599 + outer loop + vertex -708.237 86.163 12.7888 + vertex -713.921 87.702 10.936 + vertex -708.43 85.4551 10.937 + endloop + endfacet + facet normal -0.378204 -0.924302 0.0512497 + outer loop + vertex -713.921 87.702 10.936 + vertex -714.026 87.6375 8.99775 + vertex -708.43 85.4551 10.937 + endloop + endfacet + facet normal -0.377179 -0.924916 0.0475998 + outer loop + vertex -708.43 85.4551 10.937 + vertex -714.026 87.6375 8.99775 + vertex -708.534 85.3978 8.99812 + endloop + endfacet + facet normal -0.398239 -0.916007 0.04834 + outer loop + vertex -729.928 94.5112 10.9359 + vertex -730.031 94.4539 8.99763 + vertex -724.624 92.2055 10.936 + endloop + endfacet + facet normal -0.397817 -0.916268 0.04686 + outer loop + vertex -724.624 92.2055 10.936 + vertex -730.031 94.4539 8.99763 + vertex -724.725 92.1503 8.99803 + endloop + endfacet + facet normal -0.372494 -0.8539 0.36346 + outer loop + vertex -729.734 95.2148 12.787 + vertex -729.928 94.5112 10.9359 + vertex -724.433 92.9033 12.7897 + endloop + endfacet + facet normal -0.371916 -0.855444 0.360407 + outer loop + vertex -724.433 92.9033 12.7897 + vertex -729.928 94.5112 10.9359 + vertex -724.624 92.2055 10.936 + endloop + endfacet + facet normal -0.364376 -0.858523 0.360788 + outer loop + vertex -724.433 92.9033 12.7897 + vertex -724.624 92.2055 10.936 + vertex -719.121 90.6487 12.7889 + endloop + endfacet + facet normal -0.364366 -0.858548 0.360739 + outer loop + vertex -719.121 90.6487 12.7889 + vertex -724.624 92.2055 10.936 + vertex -719.311 89.9505 10.9356 + endloop + endfacet + facet normal -0.39027 -0.919522 0.0465587 + outer loop + vertex -724.624 92.2055 10.936 + vertex -724.725 92.1503 8.99803 + vertex -719.311 89.9505 10.9356 + endloop + endfacet + facet normal -0.391582 -0.918721 0.0511332 + outer loop + vertex -719.311 89.9505 10.9356 + vertex -724.725 92.1503 8.99803 + vertex -719.414 89.8867 8.99779 + endloop + endfacet + facet normal -0.411826 -0.91017 0.0446149 + outer loop + vertex -740.725 99.3577 10.9345 + vertex -740.829 99.3097 8.99764 + vertex -735.292 96.8994 10.9342 + endloop + endfacet + facet normal -0.413871 -0.908843 0.0521129 + outer loop + vertex -735.292 96.8994 10.9342 + vertex -740.829 99.3097 8.99764 + vertex -735.396 96.8359 8.99712 + endloop + endfacet + facet normal -0.385977 -0.847938 0.36335 + outer loop + vertex -740.524 100.059 12.7839 + vertex -740.725 99.3577 10.9345 + vertex -735.095 97.5889 12.7873 + endloop + endfacet + facet normal -0.384978 -0.850865 0.35752 + outer loop + vertex -735.095 97.5889 12.7873 + vertex -740.725 99.3577 10.9345 + vertex -735.292 96.8994 10.9342 + endloop + endfacet + facet normal -0.378112 -0.853788 0.357878 + outer loop + vertex -735.095 97.5889 12.7873 + vertex -735.292 96.8994 10.9342 + vertex -729.734 95.2148 12.787 + endloop + endfacet + facet normal -0.379057 -0.851159 0.363104 + outer loop + vertex -729.734 95.2148 12.787 + vertex -735.292 96.8994 10.9342 + vertex -729.928 94.5112 10.9359 + endloop + endfacet + facet normal -0.40619 -0.912319 0.0518122 + outer loop + vertex -735.292 96.8994 10.9342 + vertex -735.396 96.8359 8.99712 + vertex -729.928 94.5112 10.9359 + endloop + endfacet + facet normal -0.405302 -0.912889 0.048624 + outer loop + vertex -729.928 94.5112 10.9359 + vertex -735.396 96.8359 8.99712 + vertex -730.031 94.4539 8.99763 + endloop + endfacet + facet normal -0.426319 -0.903256 0.048787 + outer loop + vertex -751.548 104.425 10.9313 + vertex -751.654 104.371 8.9949 + vertex -746.168 101.886 10.9316 + endloop + endfacet + facet normal -0.426918 -0.902851 0.0510023 + outer loop + vertex -746.168 101.886 10.9316 + vertex -751.654 104.371 8.9949 + vertex -746.274 101.827 8.99594 + endloop + endfacet + facet normal -0.398614 -0.843419 0.360211 + outer loop + vertex -751.346 105.119 12.7798 + vertex -751.548 104.425 10.9313 + vertex -745.966 102.578 12.7821 + endloop + endfacet + facet normal -0.398402 -0.844067 0.358924 + outer loop + vertex -745.966 102.578 12.7821 + vertex -751.548 104.425 10.9313 + vertex -746.168 101.886 10.9316 + endloop + endfacet + facet normal -0.39212 -0.846853 0.35928 + outer loop + vertex -745.966 102.578 12.7821 + vertex -746.168 101.886 10.9316 + vertex -740.524 100.059 12.7839 + endloop + endfacet + facet normal -0.392729 -0.844996 0.362967 + outer loop + vertex -740.524 100.059 12.7839 + vertex -746.168 101.886 10.9316 + vertex -740.725 99.3577 10.9345 + endloop + endfacet + facet normal -0.420784 -0.90574 0.0507521 + outer loop + vertex -746.168 101.886 10.9316 + vertex -746.274 101.827 8.99594 + vertex -740.725 99.3577 10.9345 + endloop + endfacet + facet normal -0.41921 -0.906777 0.0449261 + outer loop + vertex -740.725 99.3577 10.9345 + vertex -746.274 101.827 8.99594 + vertex -740.829 99.3097 8.99764 + endloop + endfacet + facet normal -0.443594 -0.894486 0.0558436 + outer loop + vertex -762.067 109.587 10.9251 + vertex -762.175 109.519 8.9931 + vertex -756.833 106.991 10.9282 + endloop + endfacet + facet normal -0.441411 -0.896031 0.0478 + outer loop + vertex -756.833 106.991 10.9282 + vertex -762.175 109.519 8.9931 + vertex -756.936 106.939 8.9955 + endloop + endfacet + facet normal -0.414255 -0.838244 0.354599 + outer loop + vertex -761.859 110.265 12.7728 + vertex -762.067 109.587 10.9251 + vertex -756.63 107.682 12.7746 + endloop + endfacet + facet normal -0.414895 -0.836252 0.358532 + outer loop + vertex -756.63 107.682 12.7746 + vertex -762.067 109.587 10.9251 + vertex -756.833 106.991 10.9282 + endloop + endfacet + facet normal -0.407536 -0.839664 0.358998 + outer loop + vertex -756.63 107.682 12.7746 + vertex -756.833 106.991 10.9282 + vertex -751.346 105.119 12.7798 + endloop + endfacet + facet normal -0.407645 -0.839326 0.359662 + outer loop + vertex -751.346 105.119 12.7798 + vertex -756.833 106.991 10.9282 + vertex -751.548 104.425 10.9313 + endloop + endfacet + facet normal -0.436224 -0.898579 0.0475933 + outer loop + vertex -756.833 106.991 10.9282 + vertex -756.936 106.939 8.9955 + vertex -751.548 104.425 10.9313 + endloop + endfacet + facet normal -0.436664 -0.898278 0.0492111 + outer loop + vertex -751.548 104.425 10.9313 + vertex -756.936 106.939 8.9955 + vertex -751.654 104.371 8.9949 + endloop + endfacet + facet normal -0.460166 -0.886418 0.0501025 + outer loop + vertex -772.593 114.978 10.919 + vertex -772.708 114.928 8.98896 + vertex -767.312 112.237 10.9229 + endloop + endfacet + facet normal -0.459319 -0.887033 0.046884 + outer loop + vertex -767.312 112.237 10.9229 + vertex -772.708 114.928 8.98896 + vertex -767.421 112.191 8.99116 + endloop + endfacet + facet normal -0.429698 -0.825691 0.365506 + outer loop + vertex -772.371 115.675 12.7559 + vertex -772.593 114.978 10.919 + vertex -767.097 112.934 12.7639 + endloop + endfacet + facet normal -0.429411 -0.826718 0.363515 + outer loop + vertex -767.097 112.934 12.7639 + vertex -772.593 114.978 10.919 + vertex -767.312 112.237 10.9229 + endloop + endfacet + facet normal -0.423364 -0.829654 0.36392 + outer loop + vertex -767.097 112.934 12.7639 + vertex -767.312 112.237 10.9229 + vertex -761.859 110.265 12.7728 + endloop + endfacet + facet normal -0.421848 -0.834646 0.354132 + outer loop + vertex -761.859 110.265 12.7728 + vertex -767.312 112.237 10.9229 + vertex -762.067 109.587 10.9251 + endloop + endfacet + facet normal -0.450484 -0.891573 0.0464941 + outer loop + vertex -767.312 112.237 10.9229 + vertex -767.421 112.191 8.99116 + vertex -762.067 109.587 10.9251 + endloop + endfacet + facet normal -0.45308 -0.889696 0.056206 + outer loop + vertex -762.067 109.587 10.9251 + vertex -767.421 112.191 8.99116 + vertex -762.175 109.519 8.9931 + endloop + endfacet + facet normal -0.476158 -0.877812 0.0521536 + outer loop + vertex -783.108 120.623 10.9074 + vertex -783.23 120.575 8.98349 + vertex -777.876 117.786 10.9132 + endloop + endfacet + facet normal -0.475747 -0.878128 0.0505578 + outer loop + vertex -777.876 117.786 10.9132 + vertex -783.23 120.575 8.98349 + vertex -777.994 117.739 8.98679 + endloop + endfacet + facet normal -0.446038 -0.817627 0.364056 + outer loop + vertex -782.873 121.311 12.7387 + vertex -783.108 120.623 10.9074 + vertex -777.649 118.466 12.7505 + endloop + endfacet + facet normal -0.445327 -0.820348 0.358765 + outer loop + vertex -777.649 118.466 12.7505 + vertex -783.108 120.623 10.9074 + vertex -777.876 117.786 10.9132 + endloop + endfacet + facet normal -0.436495 -0.824833 0.359336 + outer loop + vertex -777.649 118.466 12.7505 + vertex -777.876 117.786 10.9132 + vertex -772.371 115.675 12.7559 + endloop + endfacet + facet normal -0.437276 -0.82193 0.364994 + outer loop + vertex -772.371 115.675 12.7559 + vertex -777.876 117.786 10.9132 + vertex -772.593 114.978 10.919 + endloop + endfacet + facet normal -0.468794 -0.881879 0.0502197 + outer loop + vertex -777.876 117.786 10.9132 + vertex -777.994 117.739 8.98679 + vertex -772.593 114.978 10.919 + endloop + endfacet + facet normal -0.468867 -0.881824 0.050504 + outer loop + vertex -772.593 114.978 10.919 + vertex -777.994 117.739 8.98679 + vertex -772.708 114.928 8.98896 + endloop + endfacet + facet normal -0.493559 -0.868012 0.0543608 + outer loop + vertex -793.331 126.376 10.8939 + vertex -793.46 126.329 8.97644 + vertex -788.254 123.49 10.9003 + endloop + endfacet + facet normal -0.493351 -0.86818 0.05355 + outer loop + vertex -788.254 123.49 10.9003 + vertex -793.46 126.329 8.97644 + vertex -788.378 123.442 8.98038 + endloop + endfacet + facet normal -0.461941 -0.807781 0.366198 + outer loop + vertex -793.08 127.059 12.7161 + vertex -793.331 126.376 10.8939 + vertex -788.013 124.167 12.729 + endloop + endfacet + facet normal -0.461267 -0.81053 0.360935 + outer loop + vertex -788.013 124.167 12.729 + vertex -793.331 126.376 10.8939 + vertex -788.254 123.49 10.9003 + endloop + endfacet + facet normal -0.45341 -0.814722 0.361452 + outer loop + vertex -788.013 124.167 12.729 + vertex -788.254 123.49 10.9003 + vertex -782.873 121.311 12.7387 + endloop + endfacet + facet normal -0.453685 -0.813639 0.36354 + outer loop + vertex -782.873 121.311 12.7387 + vertex -788.254 123.49 10.9003 + vertex -783.108 120.623 10.9074 + endloop + endfacet + facet normal -0.485962 -0.872361 0.0531752 + outer loop + vertex -788.254 123.49 10.9003 + vertex -788.378 123.442 8.98038 + vertex -783.108 120.623 10.9074 + endloop + endfacet + facet normal -0.485822 -0.872471 0.0526329 + outer loop + vertex -783.108 120.623 10.9074 + vertex -788.378 123.442 8.98038 + vertex -783.23 120.575 8.98349 + endloop + endfacet + facet normal -0.513352 -0.85605 0.0604096 + outer loop + vertex -803.393 132.333 10.8763 + vertex -803.536 132.283 8.96766 + vertex -798.367 129.319 10.8855 + endloop + endfacet + facet normal -0.512082 -0.857156 0.0552769 + outer loop + vertex -798.367 129.319 10.8855 + vertex -803.536 132.283 8.96766 + vertex -798.501 129.276 8.97256 + endloop + endfacet + facet normal -0.479244 -0.795681 0.370427 + outer loop + vertex -803.123 133.013 12.6863 + vertex -803.393 132.333 10.8763 + vertex -798.107 129.999 12.7023 + endloop + endfacet + facet normal -0.478848 -0.797564 0.366874 + outer loop + vertex -798.107 129.999 12.7023 + vertex -803.393 132.333 10.8763 + vertex -798.367 129.319 10.8855 + endloop + endfacet + facet normal -0.470275 -0.802383 0.367454 + outer loop + vertex -798.107 129.999 12.7023 + vertex -798.367 129.319 10.8855 + vertex -793.08 127.059 12.7161 + endloop + endfacet + facet normal -0.470057 -0.803335 0.365649 + outer loop + vertex -793.08 127.059 12.7161 + vertex -798.367 129.319 10.8855 + vertex -793.331 126.376 10.8939 + endloop + endfacet + facet normal -0.50385 -0.86205 0.0548109 + outer loop + vertex -798.367 129.319 10.8855 + vertex -798.501 129.276 8.97256 + vertex -793.331 126.376 10.8939 + endloop + endfacet + facet normal -0.503875 -0.86203 0.0549079 + outer loop + vertex -793.331 126.376 10.8939 + vertex -798.501 129.276 8.97256 + vertex -793.46 126.329 8.97644 + endloop + endfacet + facet normal -0.534031 -0.843516 0.0573662 + outer loop + vertex -813.473 138.619 10.8584 + vertex -813.63 138.589 8.95796 + vertex -808.427 135.425 10.8681 + endloop + endfacet + facet normal -0.534124 -0.84343 0.0577622 + outer loop + vertex -808.427 135.425 10.8681 + vertex -813.63 138.589 8.95796 + vertex -808.576 135.388 8.96351 + endloop + endfacet + facet normal -0.498301 -0.779619 0.379329 + outer loop + vertex -813.175 139.301 12.6526 + vertex -813.473 138.619 10.8584 + vertex -808.145 136.096 12.6735 + endloop + endfacet + facet normal -0.497456 -0.784775 0.369682 + outer loop + vertex -808.145 136.096 12.6735 + vertex -813.473 138.619 10.8584 + vertex -808.427 135.425 10.8681 + endloop + endfacet + facet normal -0.486752 -0.791137 0.370371 + outer loop + vertex -808.145 136.096 12.6735 + vertex -808.427 135.425 10.8681 + vertex -803.123 133.013 12.6863 + endloop + endfacet + facet normal -0.486706 -0.791376 0.369921 + outer loop + vertex -803.123 133.013 12.6863 + vertex -808.427 135.425 10.8681 + vertex -803.393 132.333 10.8763 + endloop + endfacet + facet normal -0.522615 -0.850661 0.0570046 + outer loop + vertex -808.427 135.425 10.8681 + vertex -808.576 135.388 8.96351 + vertex -803.393 132.333 10.8763 + endloop + endfacet + facet normal -0.52358 -0.849789 0.0610119 + outer loop + vertex -803.393 132.333 10.8763 + vertex -808.576 135.388 8.96351 + vertex -803.536 132.283 8.96766 + endloop + endfacet + facet normal -0.558371 -0.827053 0.0648491 + outer loop + vertex -823.562 145.327 10.8357 + vertex -823.735 145.295 8.94684 + vertex -818.524 141.926 10.8464 + endloop + endfacet + facet normal -0.558604 -0.826811 0.065915 + outer loop + vertex -818.524 141.926 10.8464 + vertex -823.735 145.295 8.94684 + vertex -818.691 141.888 8.95228 + endloop + endfacet + facet normal -0.518782 -0.76679 0.378019 + outer loop + vertex -823.235 145.985 12.6193 + vertex -823.562 145.327 10.8357 + vertex -818.212 142.594 12.6355 + endloop + endfacet + facet normal -0.518719 -0.767322 0.377024 + outer loop + vertex -818.212 142.594 12.6355 + vertex -823.562 145.327 10.8357 + vertex -818.524 141.926 10.8464 + endloop + endfacet + facet normal -0.507584 -0.774394 0.37772 + outer loop + vertex -818.212 142.594 12.6355 + vertex -818.524 141.926 10.8464 + vertex -813.175 139.301 12.6526 + endloop + endfacet + facet normal -0.507657 -0.773869 0.378698 + outer loop + vertex -813.175 139.301 12.6526 + vertex -818.524 141.926 10.8464 + vertex -813.473 138.619 10.8584 + endloop + endfacet + facet normal -0.546779 -0.834747 0.0650347 + outer loop + vertex -818.524 141.926 10.8464 + vertex -818.691 141.888 8.95228 + vertex -813.473 138.619 10.8584 + endloop + endfacet + facet normal -0.545226 -0.836268 0.058172 + outer loop + vertex -813.473 138.619 10.8584 + vertex -818.691 141.888 8.95228 + vertex -813.63 138.589 8.95796 + endloop + endfacet + facet normal -0.582816 -0.809403 0.0720566 + outer loop + vertex -833.456 152.339 10.815 + vertex -833.634 152.3 8.93534 + vertex -828.552 148.808 10.8248 + endloop + endfacet + facet normal -0.582525 -0.809735 0.0706616 + outer loop + vertex -828.552 148.808 10.8248 + vertex -833.634 152.3 8.93534 + vertex -828.73 148.772 8.94105 + endloop + endfacet + facet normal -0.539368 -0.745145 0.392227 + outer loop + vertex -833.1 153.009 12.5785 + vertex -833.456 152.339 10.815 + vertex -828.209 149.478 12.5961 + endloop + endfacet + facet normal -0.539171 -0.7479 0.387221 + outer loop + vertex -828.209 149.478 12.5961 + vertex -833.456 152.339 10.815 + vertex -828.552 148.808 10.8248 + endloop + endfacet + facet normal -0.530987 -0.753467 0.387738 + outer loop + vertex -828.209 149.478 12.5961 + vertex -828.552 148.808 10.8248 + vertex -823.235 145.985 12.6193 + endloop + endfacet + facet normal -0.530465 -0.7591 0.377325 + outer loop + vertex -823.235 145.985 12.6193 + vertex -828.552 148.808 10.8248 + vertex -823.562 145.327 10.8357 + endloop + endfacet + facet normal -0.57092 -0.818039 0.0697259 + outer loop + vertex -828.552 148.808 10.8248 + vertex -828.73 148.772 8.94105 + vertex -823.562 145.327 10.8357 + endloop + endfacet + facet normal -0.570082 -0.81895 0.0657822 + outer loop + vertex -823.562 145.327 10.8357 + vertex -828.73 148.772 8.94105 + vertex -823.735 145.295 8.94684 + endloop + endfacet + facet normal -0.607396 -0.789496 0.0881291 + outer loop + vertex -842.852 159.463 10.8015 + vertex -843.031 159.392 8.93121 + vertex -838.229 155.906 10.8045 + endloop + endfacet + facet normal -0.60561 -0.791805 0.0792555 + outer loop + vertex -838.229 155.906 10.8045 + vertex -843.031 159.392 8.93121 + vertex -838.405 155.854 8.93093 + endloop + endfacet + facet normal -0.561853 -0.728524 0.391886 + outer loop + vertex -842.486 160.125 12.5574 + vertex -842.852 159.463 10.8015 + vertex -837.868 156.567 12.5643 + endloop + endfacet + facet normal -0.561778 -0.72994 0.38935 + outer loop + vertex -837.868 156.567 12.5643 + vertex -842.852 159.463 10.8015 + vertex -838.229 155.906 10.8045 + endloop + endfacet + facet normal -0.55148 -0.737387 0.390038 + outer loop + vertex -837.868 156.567 12.5643 + vertex -838.229 155.906 10.8045 + vertex -833.1 153.009 12.5785 + endloop + endfacet + facet normal -0.551526 -0.736609 0.391441 + outer loop + vertex -833.1 153.009 12.5785 + vertex -838.229 155.906 10.8045 + vertex -833.456 152.339 10.815 + endloop + endfacet + facet normal -0.597008 -0.798373 0.0786265 + outer loop + vertex -838.229 155.906 10.8045 + vertex -838.405 155.854 8.93093 + vertex -833.456 152.339 10.815 + endloop + endfacet + facet normal -0.595875 -0.799744 0.0730924 + outer loop + vertex -833.456 152.339 10.815 + vertex -838.405 155.854 8.93093 + vertex -833.634 152.3 8.93534 + endloop + endfacet + facet normal -0.631291 -0.771226 0.081742 + outer loop + vertex -851.701 166.582 10.7979 + vertex -851.879 166.531 8.93515 + vertex -847.329 163.004 10.8045 + endloop + endfacet + facet normal -0.631967 -0.770306 0.0851223 + outer loop + vertex -847.329 163.004 10.8045 + vertex -851.879 166.531 8.93515 + vertex -847.502 162.94 8.93578 + endloop + endfacet + facet normal -0.580893 -0.706447 0.404347 + outer loop + vertex -851.304 167.252 12.538 + vertex -851.701 166.582 10.7979 + vertex -846.948 163.679 12.5526 + endloop + endfacet + facet normal -0.580829 -0.708979 0.399982 + outer loop + vertex -846.948 163.679 12.5526 + vertex -851.701 166.582 10.7979 + vertex -847.329 163.004 10.8045 + endloop + endfacet + facet normal -0.571028 -0.716475 0.400737 + outer loop + vertex -846.948 163.679 12.5526 + vertex -847.329 163.004 10.8045 + vertex -842.486 160.125 12.5574 + endloop + endfacet + facet normal -0.570804 -0.72188 0.391244 + outer loop + vertex -842.486 160.125 12.5574 + vertex -847.329 163.004 10.8045 + vertex -842.852 159.463 10.8015 + endloop + endfacet + facet normal -0.618186 -0.781506 0.0842353 + outer loop + vertex -847.329 163.004 10.8045 + vertex -847.502 162.94 8.93578 + vertex -842.852 159.463 10.8015 + endloop + endfacet + facet normal -0.619118 -0.78025 0.0888999 + outer loop + vertex -842.852 159.463 10.8015 + vertex -847.502 162.94 8.93578 + vertex -843.031 159.392 8.93121 + endloop + endfacet + facet normal -0.661696 -0.74584 0.0766903 + outer loop + vertex -860.566 174.286 10.7002 + vertex -860.748 174.258 8.85316 + vertex -856.073 170.307 10.7585 + endloop + endfacet + facet normal -0.662738 -0.744299 0.0824459 + outer loop + vertex -856.073 170.307 10.7585 + vertex -860.748 174.258 8.85316 + vertex -856.26 170.267 8.90717 + endloop + endfacet + facet normal -0.610541 -0.684099 0.39906 + outer loop + vertex -860.137 174.91 12.4253 + vertex -860.566 174.286 10.7002 + vertex -855.66 170.952 12.4905 + endloop + endfacet + facet normal -0.610513 -0.68332 0.400434 + outer loop + vertex -855.66 170.952 12.4905 + vertex -860.566 174.286 10.7002 + vertex -856.073 170.307 10.7585 + endloop + endfacet + facet normal -0.595447 -0.695865 0.401517 + outer loop + vertex -855.66 170.952 12.4905 + vertex -856.073 170.307 10.7585 + vertex -851.304 167.252 12.538 + endloop + endfacet + facet normal -0.595449 -0.694879 0.403216 + outer loop + vertex -851.304 167.252 12.538 + vertex -856.073 170.307 10.7585 + vertex -851.701 166.582 10.7979 + endloop + endfacet + facet normal -0.646677 -0.758437 0.0811284 + outer loop + vertex -856.073 170.307 10.7585 + vertex -856.26 170.267 8.90717 + vertex -851.701 166.582 10.7979 + endloop + endfacet + facet normal -0.647017 -0.757958 0.0828811 + outer loop + vertex -851.701 166.582 10.7979 + vertex -856.26 170.267 8.90717 + vertex -851.879 166.531 8.93515 + endloop + endfacet + facet normal -0.685516 -0.722475 0.0899933 + outer loop + vertex -869.65 182.786 10.9097 + vertex -869.934 182.82 9.02299 + vertex -865.184 178.523 10.7062 + endloop + endfacet + facet normal -0.68223 -0.728125 0.0662948 + outer loop + vertex -865.184 178.523 10.7062 + vertex -869.934 182.82 9.02299 + vertex -865.365 178.523 8.84546 + endloop + endfacet + facet normal -0.622416 -0.659586 0.42136 + outer loop + vertex -869.177 183.414 12.5934 + vertex -869.65 182.786 10.9097 + vertex -864.735 179.117 12.4269 + endloop + endfacet + facet normal -0.624682 -0.673318 0.395494 + outer loop + vertex -864.735 179.117 12.4269 + vertex -869.65 182.786 10.9097 + vertex -865.184 178.523 10.7062 + endloop + endfacet + facet normal -0.619862 -0.677624 0.395723 + outer loop + vertex -864.735 179.117 12.4269 + vertex -865.184 178.523 10.7062 + vertex -860.137 174.91 12.4253 + endloop + endfacet + facet normal -0.619731 -0.676136 0.398465 + outer loop + vertex -860.137 174.91 12.4253 + vertex -865.184 178.523 10.7062 + vertex -860.566 174.286 10.7002 + endloop + endfacet + facet normal -0.674495 -0.735364 0.0655434 + outer loop + vertex -865.184 178.523 10.7062 + vertex -865.365 178.523 8.84546 + vertex -860.566 174.286 10.7002 + endloop + endfacet + facet normal -0.67655 -0.73226 0.0779475 + outer loop + vertex -860.566 174.286 10.7002 + vertex -865.365 178.523 8.84546 + vertex -860.748 174.258 8.85316 + endloop + endfacet + facet normal -0.606873 -0.623867 0.492438 + outer loop + vertex -872.998 187.416 12.9533 + vertex -873.487 186.632 11.3578 + vertex -869.177 183.414 12.5934 + endloop + endfacet + facet normal -0.616935 -0.664525 0.421662 + outer loop + vertex -869.177 183.414 12.5934 + vertex -873.487 186.632 11.3578 + vertex -869.65 182.786 10.9097 + endloop + endfacet + facet normal -0.686848 -0.705489 0.174713 + outer loop + vertex -873.487 186.632 11.3578 + vertex -873.829 186.519 9.55772 + vertex -869.65 182.786 10.9097 + endloop + endfacet + facet normal -0.679474 -0.728284 0.088979 + outer loop + vertex -869.65 182.786 10.9097 + vertex -873.829 186.519 9.55772 + vertex -869.934 182.82 9.02299 + endloop + endfacet + facet normal -0.262224 -0.742802 -0.616023 + outer loop + vertex -610.112 51.9583 7.04995 + vertex -609.716 53.2762 5.29227 + vertex -607.896 51.5363 6.6155 + endloop + endfacet + facet normal -0.189541 -0.71226 -0.67584 + outer loop + vertex -607.896 51.5363 6.6155 + vertex -609.716 53.2762 5.29227 + vertex -607.653 53.2149 4.77826 + endloop + endfacet + facet normal -0.300891 -0.898797 -0.318793 + outer loop + vertex -610.195 51.3089 8.95965 + vertex -610.112 51.9583 7.04995 + vertex -608.149 50.7319 8.65503 + endloop + endfacet + facet normal -0.24459 -0.891259 -0.381882 + outer loop + vertex -608.149 50.7319 8.65503 + vertex -610.112 51.9583 7.04995 + vertex -607.896 51.5363 6.6155 + endloop + endfacet + facet normal -0.240806 -0.782262 -0.574525 + outer loop + vertex -618.547 54.485 7.17537 + vertex -618.228 55.6253 5.48907 + vertex -613.7 52.9757 7.19863 + endloop + endfacet + facet normal -0.233069 -0.77627 -0.585734 + outer loop + vertex -613.7 52.9757 7.19863 + vertex -618.228 55.6253 5.48907 + vertex -613.343 54.1526 5.49701 + endloop + endfacet + facet normal -0.287307 -0.917747 -0.274217 + outer loop + vertex -618.553 53.9272 9.04862 + vertex -618.547 54.485 7.17537 + vertex -613.719 52.4079 9.06892 + endloop + endfacet + facet normal -0.284046 -0.91662 -0.281294 + outer loop + vertex -613.719 52.4079 9.06892 + vertex -618.547 54.485 7.17537 + vertex -613.7 52.9757 7.19863 + endloop + endfacet + facet normal -0.293662 -0.913815 -0.280544 + outer loop + vertex -613.719 52.4079 9.06892 + vertex -613.7 52.9757 7.19863 + vertex -610.195 51.3089 8.95965 + endloop + endfacet + facet normal -0.270689 -0.907744 -0.320514 + outer loop + vertex -610.195 51.3089 8.95965 + vertex -613.7 52.9757 7.19863 + vertex -610.112 51.9583 7.04995 + endloop + endfacet + facet normal -0.243491 -0.77308 -0.585713 + outer loop + vertex -613.7 52.9757 7.19863 + vertex -613.343 54.1526 5.49701 + vertex -610.112 51.9583 7.04995 + endloop + endfacet + facet normal -0.21763 -0.756737 -0.61643 + outer loop + vertex -610.112 51.9583 7.04995 + vertex -613.343 54.1526 5.49701 + vertex -609.716 53.2762 5.29227 + endloop + endfacet + facet normal -0.236095 -0.76964 -0.593223 + outer loop + vertex -630.032 58.0817 7.08565 + vertex -629.81 59.3301 5.37766 + vertex -624.172 56.2604 7.11633 + endloop + endfacet + facet normal -0.242549 -0.775583 -0.582787 + outer loop + vertex -624.172 56.2604 7.11633 + vertex -629.81 59.3301 5.37766 + vertex -623.909 57.4524 5.4205 + endloop + endfacet + facet normal -0.280813 -0.912351 -0.297924 + outer loop + vertex -630.02 57.459 8.98098 + vertex -630.032 58.0817 7.08565 + vertex -624.156 55.6472 9.00261 + endloop + endfacet + facet normal -0.282227 -0.913038 -0.294463 + outer loop + vertex -624.156 55.6472 9.00261 + vertex -630.032 58.0817 7.08565 + vertex -624.172 56.2604 7.11633 + endloop + endfacet + facet normal -0.278205 -0.914145 -0.294857 + outer loop + vertex -624.156 55.6472 9.00261 + vertex -624.172 56.2604 7.11633 + vertex -618.553 53.9272 9.04862 + endloop + endfacet + facet normal -0.286841 -0.917881 -0.274256 + outer loop + vertex -618.553 53.9272 9.04862 + vertex -624.172 56.2604 7.11633 + vertex -618.547 54.485 7.17537 + endloop + endfacet + facet normal -0.238999 -0.776574 -0.582934 + outer loop + vertex -624.172 56.2604 7.11633 + vertex -623.909 57.4524 5.4205 + vertex -618.547 54.485 7.17537 + endloop + endfacet + facet normal -0.244329 -0.781204 -0.574477 + outer loop + vertex -618.547 54.485 7.17537 + vertex -623.909 57.4524 5.4205 + vertex -618.228 55.6253 5.48907 + endloop + endfacet + facet normal -0.250345 -0.768695 -0.588588 + outer loop + vertex -641.394 61.7273 7.10751 + vertex -641.171 62.9641 5.39749 + vertex -635.794 59.9144 7.0933 + endloop + endfacet + facet normal -0.24673 -0.765483 -0.594272 + outer loop + vertex -635.794 59.9144 7.0933 + vertex -641.171 62.9641 5.39749 + vertex -635.582 61.1735 5.38348 + endloop + endfacet + facet normal -0.295999 -0.906991 -0.299587 + outer loop + vertex -641.423 61.1139 8.99348 + vertex -641.394 61.7273 7.10751 + vertex -635.804 59.2835 8.98352 + endloop + endfacet + facet normal -0.294109 -0.906113 -0.304072 + outer loop + vertex -635.804 59.2835 8.98352 + vertex -641.394 61.7273 7.10751 + vertex -635.794 59.9144 7.0933 + endloop + endfacet + facet normal -0.286619 -0.908281 -0.304754 + outer loop + vertex -635.804 59.2835 8.98352 + vertex -635.794 59.9144 7.0933 + vertex -630.02 57.459 8.98098 + endloop + endfacet + facet normal -0.289801 -0.909827 -0.297035 + outer loop + vertex -630.02 57.459 8.98098 + vertex -635.794 59.9144 7.0933 + vertex -630.032 58.0817 7.08565 + endloop + endfacet + facet normal -0.244471 -0.766083 -0.594434 + outer loop + vertex -635.794 59.9144 7.0933 + vertex -635.582 61.1735 5.38348 + vertex -630.032 58.0817 7.08565 + endloop + endfacet + facet normal -0.245607 -0.767123 -0.592621 + outer loop + vertex -630.032 58.0817 7.08565 + vertex -635.582 61.1735 5.38348 + vertex -629.81 59.3301 5.37766 + endloop + endfacet + facet normal -0.257069 -0.765554 -0.589782 + outer loop + vertex -652.416 65.3828 7.11528 + vertex -652.137 66.5995 5.41455 + vertex -646.91 63.5357 7.11291 + endloop + endfacet + facet normal -0.25572 -0.764403 -0.591858 + outer loop + vertex -646.91 63.5357 7.11291 + vertex -652.137 66.5995 5.41455 + vertex -646.652 64.7677 5.41036 + endloop + endfacet + facet normal -0.303744 -0.90677 -0.292419 + outer loop + vertex -652.455 64.7877 9.00149 + vertex -652.416 65.3828 7.11528 + vertex -646.946 62.9426 9.00022 + endloop + endfacet + facet normal -0.304406 -0.907049 -0.290859 + outer loop + vertex -646.946 62.9426 9.00022 + vertex -652.416 65.3828 7.11528 + vertex -646.91 63.5357 7.11291 + endloop + endfacet + facet normal -0.301026 -0.908092 -0.291122 + outer loop + vertex -646.946 62.9426 9.00022 + vertex -646.91 63.5357 7.11291 + vertex -641.423 61.1139 8.99348 + endloop + endfacet + facet normal -0.297484 -0.906545 -0.299465 + outer loop + vertex -641.423 61.1139 8.99348 + vertex -646.91 63.5357 7.11291 + vertex -641.394 61.7273 7.10751 + endloop + endfacet + facet normal -0.251564 -0.765599 -0.592093 + outer loop + vertex -646.91 63.5357 7.11291 + vertex -646.652 64.7677 5.41036 + vertex -641.394 61.7273 7.10751 + endloop + endfacet + facet normal -0.253986 -0.767692 -0.588337 + outer loop + vertex -641.394 61.7273 7.10751 + vertex -646.652 64.7677 5.41036 + vertex -641.171 62.9641 5.39749 + endloop + endfacet + facet normal -0.261695 -0.762693 -0.591452 + outer loop + vertex -663.537 69.1695 7.11053 + vertex -663.243 70.3868 5.41062 + vertex -657.957 67.2532 7.11281 + endloop + endfacet + facet normal -0.262773 -0.763609 -0.58979 + outer loop + vertex -657.957 67.2532 7.11281 + vertex -663.243 70.3868 5.41062 + vertex -657.669 68.4678 5.41181 + endloop + endfacet + facet normal -0.313134 -0.905461 -0.286508 + outer loop + vertex -663.567 68.582 9.00003 + vertex -663.537 69.1695 7.11053 + vertex -657.993 66.6546 8.99942 + endloop + endfacet + facet normal -0.310466 -0.904348 -0.292857 + outer loop + vertex -657.993 66.6546 8.99942 + vertex -663.537 69.1695 7.11053 + vertex -657.957 67.2532 7.11281 + endloop + endfacet + facet normal -0.305318 -0.905965 -0.293272 + outer loop + vertex -657.993 66.6546 8.99942 + vertex -657.957 67.2532 7.11281 + vertex -652.455 64.7877 9.00149 + endloop + endfacet + facet normal -0.305746 -0.906146 -0.292264 + outer loop + vertex -652.455 64.7877 9.00149 + vertex -657.957 67.2532 7.11281 + vertex -652.416 65.3828 7.11528 + endloop + endfacet + facet normal -0.257989 -0.765063 -0.590017 + outer loop + vertex -657.957 67.2532 7.11281 + vertex -657.669 68.4678 5.41181 + vertex -652.416 65.3828 7.11528 + endloop + endfacet + facet normal -0.258177 -0.765223 -0.589727 + outer loop + vertex -652.416 65.3828 7.11528 + vertex -657.669 68.4678 5.41181 + vertex -652.137 66.5995 5.41455 + endloop + endfacet + facet normal -0.272428 -0.762445 -0.586908 + outer loop + vertex -674.808 73.1612 7.11195 + vertex -674.515 74.3679 5.40821 + vertex -669.155 71.1417 7.11152 + endloop + endfacet + facet normal -0.273217 -0.763107 -0.585679 + outer loop + vertex -669.155 71.1417 7.11152 + vertex -674.515 74.3679 5.40821 + vertex -668.864 72.3465 5.40599 + endloop + endfacet + facet normal -0.319594 -0.899705 -0.297305 + outer loop + vertex -674.843 72.5503 8.99798 + vertex -674.808 73.1612 7.11195 + vertex -669.188 70.5415 8.99814 + endloop + endfacet + facet normal -0.321773 -0.900633 -0.292101 + outer loop + vertex -669.188 70.5415 8.99814 + vertex -674.808 73.1612 7.11195 + vertex -669.155 71.1417 7.11152 + endloop + endfacet + facet normal -0.314677 -0.902939 -0.292711 + outer loop + vertex -669.188 70.5415 8.99814 + vertex -669.155 71.1417 7.11152 + vertex -663.567 68.582 9.00003 + endloop + endfacet + facet normal -0.317419 -0.904082 -0.286147 + outer loop + vertex -663.567 68.582 9.00003 + vertex -669.155 71.1417 7.11152 + vertex -663.537 69.1695 7.11053 + endloop + endfacet + facet normal -0.268505 -0.764591 -0.585923 + outer loop + vertex -669.155 71.1417 7.11152 + vertex -668.864 72.3465 5.40599 + vertex -663.537 69.1695 7.11053 + endloop + endfacet + facet normal -0.26504 -0.761661 -0.591293 + outer loop + vertex -663.537 69.1695 7.11053 + vertex -668.864 72.3465 5.40599 + vertex -663.243 70.3868 5.41062 + endloop + endfacet + facet normal -0.281326 -0.759253 -0.586847 + outer loop + vertex -686.12 77.3018 7.11015 + vertex -685.835 78.5128 5.40655 + vertex -680.476 75.211 7.10936 + endloop + endfacet + facet normal -0.28166 -0.759529 -0.586331 + outer loop + vertex -680.476 75.211 7.10936 + vertex -685.835 78.5128 5.40655 + vertex -680.186 76.4193 5.40508 + endloop + endfacet + facet normal -0.330375 -0.896655 -0.294723 + outer loop + vertex -686.152 76.6929 8.99795 + vertex -686.12 77.3018 7.11015 + vertex -680.505 74.6125 8.99783 + endloop + endfacet + facet normal -0.332504 -0.897527 -0.289631 + outer loop + vertex -680.505 74.6125 8.99783 + vertex -686.12 77.3018 7.11015 + vertex -680.476 75.211 7.10936 + endloop + endfacet + facet normal -0.327481 -0.899224 -0.29009 + outer loop + vertex -680.505 74.6125 8.99783 + vertex -680.476 75.211 7.10936 + vertex -674.843 72.5503 8.99798 + endloop + endfacet + facet normal -0.324653 -0.89804 -0.296859 + outer loop + vertex -674.843 72.5503 8.99798 + vertex -680.476 75.211 7.10936 + vertex -674.808 73.1612 7.11195 + endloop + endfacet + facet normal -0.275179 -0.761612 -0.586706 + outer loop + vertex -680.476 75.211 7.10936 + vertex -680.186 76.4193 5.40508 + vertex -674.808 73.1612 7.11195 + endloop + endfacet + facet normal -0.275142 -0.761581 -0.586764 + outer loop + vertex -674.808 73.1612 7.11195 + vertex -680.186 76.4193 5.40508 + vertex -674.515 74.3679 5.40821 + endloop + endfacet + facet normal -0.288946 -0.754127 -0.589747 + outer loop + vertex -697.339 81.5709 7.10959 + vertex -697.046 82.7882 5.40933 + vertex -691.736 79.423 7.11106 + endloop + endfacet + facet normal -0.291204 -0.755946 -0.586298 + outer loop + vertex -691.736 79.423 7.11106 + vertex -697.046 82.7882 5.40933 + vertex -691.451 80.6337 5.40842 + endloop + endfacet + facet normal -0.341504 -0.892965 -0.293238 + outer loop + vertex -697.375 80.9646 8.99839 + vertex -697.339 81.5709 7.10959 + vertex -691.769 78.8204 8.9986 + endloop + endfacet + facet normal -0.342381 -0.893311 -0.291154 + outer loop + vertex -691.769 78.8204 8.9986 + vertex -697.339 81.5709 7.10959 + vertex -691.736 79.423 7.11106 + endloop + endfacet + facet normal -0.33884 -0.894551 -0.291489 + outer loop + vertex -691.769 78.8204 8.9986 + vertex -691.736 79.423 7.11106 + vertex -686.152 76.6929 8.99795 + endloop + endfacet + facet normal -0.337772 -0.894123 -0.29403 + outer loop + vertex -686.152 76.6929 8.99795 + vertex -691.736 79.423 7.11106 + vertex -686.12 77.3018 7.11015 + endloop + endfacet + facet normal -0.286245 -0.757581 -0.58663 + outer loop + vertex -691.736 79.423 7.11106 + vertex -691.451 80.6337 5.40842 + vertex -686.12 77.3018 7.11015 + endloop + endfacet + facet normal -0.28631 -0.757634 -0.58653 + outer loop + vertex -686.12 77.3018 7.11015 + vertex -691.451 80.6337 5.40842 + vertex -685.835 78.5128 5.40655 + endloop + endfacet + facet normal -0.303954 -0.756272 -0.579365 + outer loop + vertex -708.488 86.0065 7.113 + vertex -708.198 87.1986 5.40441 + vertex -702.928 83.7731 7.11124 + endloop + endfacet + facet normal -0.300651 -0.753705 -0.584412 + outer loop + vertex -702.928 83.7731 7.11124 + vertex -708.198 87.1986 5.40441 + vertex -702.634 84.9776 5.40662 + endloop + endfacet + facet normal -0.354859 -0.887144 -0.295043 + outer loop + vertex -708.534 85.3978 8.99812 + vertex -708.488 86.0065 7.113 + vertex -702.968 83.1714 8.9983 + endloop + endfacet + facet normal -0.356711 -0.887843 -0.290674 + outer loop + vertex -702.968 83.1714 8.9983 + vertex -708.488 86.0065 7.113 + vertex -702.928 83.7731 7.11124 + endloop + endfacet + facet normal -0.35111 -0.889898 -0.29121 + outer loop + vertex -702.968 83.1714 8.9983 + vertex -702.928 83.7731 7.11124 + vertex -697.375 80.9646 8.99839 + endloop + endfacet + facet normal -0.350621 -0.889711 -0.292369 + outer loop + vertex -697.375 80.9646 8.99839 + vertex -702.928 83.7731 7.11124 + vertex -697.339 81.5709 7.10959 + endloop + endfacet + facet normal -0.297542 -0.75477 -0.584629 + outer loop + vertex -702.928 83.7731 7.11124 + vertex -702.634 84.9776 5.40662 + vertex -697.339 81.5709 7.10959 + endloop + endfacet + facet normal -0.294422 -0.752295 -0.589379 + outer loop + vertex -697.339 81.5709 7.10959 + vertex -702.634 84.9776 5.40662 + vertex -697.046 82.7882 5.40933 + endloop + endfacet + facet normal -0.310953 -0.747898 -0.586478 + outer loop + vertex -719.371 90.4878 7.10983 + vertex -719.072 91.6972 5.40925 + vertex -713.981 88.2455 7.11149 + endloop + endfacet + facet normal -0.314462 -0.750501 -0.581259 + outer loop + vertex -713.981 88.2455 7.11149 + vertex -719.072 91.6972 5.40925 + vertex -713.688 89.4438 5.40573 + endloop + endfacet + facet normal -0.368692 -0.88323 -0.289779 + outer loop + vertex -719.414 89.8867 8.99779 + vertex -719.371 90.4878 7.10983 + vertex -714.026 87.6375 8.99775 + endloop + endfacet + facet normal -0.367116 -0.882685 -0.293417 + outer loop + vertex -714.026 87.6375 8.99775 + vertex -719.371 90.4878 7.10983 + vertex -713.981 88.2455 7.11149 + endloop + endfacet + facet normal -0.360896 -0.885043 -0.294027 + outer loop + vertex -714.026 87.6375 8.99775 + vertex -713.981 88.2455 7.11149 + vertex -708.534 85.3978 8.99812 + endloop + endfacet + facet normal -0.360701 -0.884972 -0.294483 + outer loop + vertex -708.534 85.3978 8.99812 + vertex -713.981 88.2455 7.11149 + vertex -708.488 86.0065 7.113 + endloop + endfacet + facet normal -0.306893 -0.753179 -0.58184 + outer loop + vertex -713.981 88.2455 7.11149 + vertex -713.688 89.4438 5.40573 + vertex -708.488 86.0065 7.113 + endloop + endfacet + facet normal -0.308758 -0.754595 -0.579012 + outer loop + vertex -708.488 86.0065 7.113 + vertex -713.688 89.4438 5.40573 + vertex -708.198 87.1986 5.40441 + endloop + endfacet + facet normal -0.325844 -0.748031 -0.578165 + outer loop + vertex -729.979 95.0608 7.11184 + vertex -729.679 96.2496 5.40492 + vertex -724.677 92.752 7.11126 + endloop + endfacet + facet normal -0.322756 -0.745836 -0.582716 + outer loop + vertex -724.677 92.752 7.11126 + vertex -729.679 96.2496 5.40492 + vertex -724.381 93.9543 5.4082 + endloop + endfacet + facet normal -0.380772 -0.87707 -0.292848 + outer loop + vertex -730.031 94.4539 8.99763 + vertex -729.979 95.0608 7.11184 + vertex -724.725 92.1503 8.99803 + endloop + endfacet + facet normal -0.382215 -0.877537 -0.289552 + outer loop + vertex -724.725 92.1503 8.99803 + vertex -729.979 95.0608 7.11184 + vertex -724.677 92.752 7.11126 + endloop + endfacet + facet normal -0.375228 -0.880315 -0.290259 + outer loop + vertex -724.725 92.1503 8.99803 + vertex -724.677 92.752 7.11126 + vertex -719.414 89.8867 8.99779 + endloop + endfacet + facet normal -0.375747 -0.880485 -0.289068 + outer loop + vertex -719.414 89.8867 8.99779 + vertex -724.677 92.752 7.11126 + vertex -719.371 90.4878 7.10983 + endloop + endfacet + facet normal -0.318966 -0.747218 -0.583032 + outer loop + vertex -724.677 92.752 7.11126 + vertex -724.381 93.9543 5.4082 + vertex -719.371 90.4878 7.10983 + endloop + endfacet + facet normal -0.316943 -0.745752 -0.586004 + outer loop + vertex -719.371 90.4878 7.10983 + vertex -724.381 93.9543 5.4082 + vertex -719.072 91.6972 5.40925 + endloop + endfacet + facet normal -0.338486 -0.742876 -0.577548 + outer loop + vertex -740.778 99.912 7.11143 + vertex -740.464 101.095 5.40536 + vertex -735.345 97.4382 7.10942 + endloop + endfacet + facet normal -0.334604 -0.740127 -0.583312 + outer loop + vertex -735.345 97.4382 7.10942 + vertex -740.464 101.095 5.40536 + vertex -735.03 98.6363 5.40808 + endloop + endfacet + facet normal -0.396797 -0.871279 -0.288833 + outer loop + vertex -740.829 99.3097 8.99764 + vertex -740.778 99.912 7.11143 + vertex -735.396 96.8359 8.99712 + endloop + endfacet + facet normal -0.396857 -0.871298 -0.288695 + outer loop + vertex -735.396 96.8359 8.99712 + vertex -740.778 99.912 7.11143 + vertex -735.345 97.4382 7.10942 + endloop + endfacet + facet normal -0.388368 -0.874819 -0.289589 + outer loop + vertex -735.396 96.8359 8.99712 + vertex -735.345 97.4382 7.10942 + vertex -730.031 94.4539 8.99763 + endloop + endfacet + facet normal -0.387241 -0.874455 -0.292186 + outer loop + vertex -730.031 94.4539 8.99763 + vertex -735.345 97.4382 7.10942 + vertex -729.979 95.0608 7.11184 + endloop + endfacet + facet normal -0.328616 -0.742413 -0.583811 + outer loop + vertex -735.345 97.4382 7.10942 + vertex -735.03 98.6363 5.40808 + vertex -729.979 95.0608 7.11184 + endloop + endfacet + facet normal -0.332842 -0.745408 -0.577567 + outer loop + vertex -729.979 95.0608 7.11184 + vertex -735.03 98.6363 5.40808 + vertex -729.679 96.2496 5.40492 + endloop + endfacet + facet normal -0.348108 -0.735737 -0.580957 + outer loop + vertex -751.608 104.977 7.10842 + vertex -751.303 106.176 5.40698 + vertex -746.227 102.43 7.1094 + endloop + endfacet + facet normal -0.348267 -0.735847 -0.580723 + outer loop + vertex -746.227 102.43 7.1094 + vertex -751.303 106.176 5.40698 + vertex -745.915 103.626 5.40696 + endloop + endfacet + facet normal -0.409311 -0.865755 -0.28798 + outer loop + vertex -751.654 104.371 8.9949 + vertex -751.608 104.977 7.10842 + vertex -746.274 101.827 8.99594 + endloop + endfacet + facet normal -0.40976 -0.86589 -0.286935 + outer loop + vertex -746.274 101.827 8.99594 + vertex -751.608 104.977 7.10842 + vertex -746.227 102.43 7.1094 + endloop + endfacet + facet normal -0.40179 -0.869319 -0.287834 + outer loop + vertex -746.274 101.827 8.99594 + vertex -746.227 102.43 7.1094 + vertex -740.829 99.3097 8.99764 + endloop + endfacet + facet normal -0.401585 -0.869255 -0.288315 + outer loop + vertex -740.829 99.3097 8.99764 + vertex -746.227 102.43 7.1094 + vertex -740.778 99.912 7.11143 + endloop + endfacet + facet normal -0.341127 -0.738662 -0.581388 + outer loop + vertex -746.227 102.43 7.1094 + vertex -745.915 103.626 5.40696 + vertex -740.778 99.912 7.11143 + endloop + endfacet + facet normal -0.344038 -0.740702 -0.577061 + outer loop + vertex -740.778 99.912 7.11143 + vertex -745.915 103.626 5.40696 + vertex -740.464 101.095 5.40536 + endloop + endfacet + facet normal -0.361954 -0.730522 -0.579074 + outer loop + vertex -762.122 110.128 7.10794 + vertex -761.818 111.325 5.40663 + vertex -756.891 107.535 7.10854 + endloop + endfacet + facet normal -0.361241 -0.730058 -0.580103 + outer loop + vertex -756.891 107.535 7.10854 + vertex -761.818 111.325 5.40663 + vertex -756.59 108.737 5.40792 + endloop + endfacet + facet normal -0.422953 -0.858875 -0.288868 + outer loop + vertex -762.175 109.519 8.9931 + vertex -762.122 110.128 7.10794 + vertex -756.936 106.939 8.9955 + endloop + endfacet + facet normal -0.425999 -0.859691 -0.281879 + outer loop + vertex -756.936 106.939 8.9955 + vertex -762.122 110.128 7.10794 + vertex -756.891 107.535 7.10854 + endloop + endfacet + facet normal -0.419395 -0.862675 -0.282664 + outer loop + vertex -756.936 106.939 8.9955 + vertex -756.891 107.535 7.10854 + vertex -751.654 104.371 8.9949 + endloop + endfacet + facet normal -0.41751 -0.862151 -0.28702 + outer loop + vertex -751.654 104.371 8.9949 + vertex -756.891 107.535 7.10854 + vertex -751.608 104.977 7.10842 + endloop + endfacet + facet normal -0.354807 -0.732655 -0.5808 + outer loop + vertex -756.891 107.535 7.10854 + vertex -756.59 108.737 5.40792 + vertex -751.608 104.977 7.10842 + endloop + endfacet + facet normal -0.355194 -0.732914 -0.580237 + outer loop + vertex -751.608 104.977 7.10842 + vertex -756.59 108.737 5.40792 + vertex -751.303 106.176 5.40698 + endloop + endfacet + facet normal -0.377023 -0.72489 -0.576531 + outer loop + vertex -772.656 115.542 7.1086 + vertex -772.337 116.727 5.40956 + vertex -767.369 112.793 7.1077 + endloop + endfacet + facet normal -0.37792 -0.72546 -0.575225 + outer loop + vertex -767.369 112.793 7.1077 + vertex -772.337 116.727 5.40956 + vertex -767.057 113.98 5.40523 + endloop + endfacet + facet normal -0.440022 -0.850036 -0.289514 + outer loop + vertex -772.708 114.928 8.98896 + vertex -772.656 115.542 7.1086 + vertex -767.421 112.191 8.99116 + endloop + endfacet + facet normal -0.442364 -0.85065 -0.284094 + outer loop + vertex -767.421 112.191 8.99116 + vertex -772.656 115.542 7.1086 + vertex -767.369 112.793 7.1077 + endloop + endfacet + facet normal -0.434875 -0.854194 -0.28502 + outer loop + vertex -767.421 112.191 8.99116 + vertex -767.369 112.793 7.1077 + vertex -762.175 109.519 8.9931 + endloop + endfacet + facet normal -0.433768 -0.853904 -0.287565 + outer loop + vertex -762.175 109.519 8.9931 + vertex -767.369 112.793 7.1077 + vertex -762.122 110.128 7.10794 + endloop + endfacet + facet normal -0.370177 -0.728751 -0.5761 + outer loop + vertex -767.369 112.793 7.1077 + vertex -767.057 113.98 5.40523 + vertex -762.122 110.128 7.10794 + endloop + endfacet + facet normal -0.368638 -0.727765 -0.578329 + outer loop + vertex -762.122 110.128 7.10794 + vertex -767.057 113.98 5.40523 + vertex -761.818 111.325 5.40663 + endloop + endfacet + facet normal -0.393077 -0.722922 -0.568221 + outer loop + vertex -783.182 121.191 7.10709 + vertex -782.882 122.368 5.40294 + vertex -777.949 118.346 7.10707 + endloop + endfacet + facet normal -0.39075 -0.721506 -0.571615 + outer loop + vertex -777.949 118.346 7.10707 + vertex -782.882 122.368 5.40294 + vertex -777.639 119.527 5.40444 + endloop + endfacet + facet normal -0.455991 -0.842054 -0.288127 + outer loop + vertex -783.23 120.575 8.98349 + vertex -783.182 121.191 7.10709 + vertex -777.994 117.739 8.98679 + endloop + endfacet + facet normal -0.458133 -0.842573 -0.28317 + outer loop + vertex -777.994 117.739 8.98679 + vertex -783.182 121.191 7.10709 + vertex -777.949 118.346 7.10707 + endloop + endfacet + facet normal -0.449992 -0.846581 -0.284266 + outer loop + vertex -777.994 117.739 8.98679 + vertex -777.949 118.346 7.10707 + vertex -772.708 114.928 8.98896 + endloop + endfacet + facet normal -0.448184 -0.84612 -0.288463 + outer loop + vertex -772.708 114.928 8.98896 + vertex -777.949 118.346 7.10707 + vertex -772.656 115.542 7.1086 + endloop + endfacet + facet normal -0.383717 -0.724592 -0.572475 + outer loop + vertex -777.949 118.346 7.10707 + vertex -777.639 119.527 5.40444 + vertex -772.656 115.542 7.1086 + endloop + endfacet + facet normal -0.381266 -0.723054 -0.576046 + outer loop + vertex -772.656 115.542 7.1086 + vertex -777.639 119.527 5.40444 + vertex -772.337 116.727 5.40956 + endloop + endfacet + facet normal -0.40635 -0.712711 -0.571771 + outer loop + vertex -793.41 126.942 7.10333 + vertex -793.098 128.124 5.40802 + vertex -788.334 124.047 7.1038 + endloop + endfacet + facet normal -0.408154 -0.713746 -0.56919 + outer loop + vertex -788.334 124.047 7.1038 + vertex -793.098 128.124 5.40802 + vertex -788.029 125.229 5.40366 + endloop + endfacet + facet normal -0.47337 -0.833478 -0.285017 + outer loop + vertex -793.46 126.329 8.97644 + vertex -793.41 126.942 7.10333 + vertex -788.378 123.442 8.98038 + endloop + endfacet + facet normal -0.475492 -0.83392 -0.280153 + outer loop + vertex -788.378 123.442 8.98038 + vertex -793.41 126.942 7.10333 + vertex -788.334 124.047 7.1038 + endloop + endfacet + facet normal -0.466684 -0.838461 -0.281407 + outer loop + vertex -788.378 123.442 8.98038 + vertex -788.334 124.047 7.1038 + vertex -783.23 120.575 8.98349 + endloop + endfacet + facet normal -0.464261 -0.837917 -0.286979 + outer loop + vertex -783.23 120.575 8.98349 + vertex -788.334 124.047 7.1038 + vertex -783.182 121.191 7.10709 + endloop + endfacet + facet normal -0.397848 -0.718425 -0.570598 + outer loop + vertex -788.334 124.047 7.1038 + vertex -788.029 125.229 5.40366 + vertex -783.182 121.191 7.10709 + endloop + endfacet + facet normal -0.400133 -0.719774 -0.567291 + outer loop + vertex -783.182 121.191 7.10709 + vertex -788.029 125.229 5.40366 + vertex -782.882 122.368 5.40294 + endloop + endfacet + facet normal -0.422573 -0.705856 -0.568507 + outer loop + vertex -803.494 132.896 7.09851 + vertex -803.181 134.074 5.40453 + vertex -798.457 129.879 7.10016 + endloop + endfacet + facet normal -0.424279 -0.706792 -0.566068 + outer loop + vertex -798.457 129.879 7.10016 + vertex -803.181 134.074 5.40453 + vertex -798.146 131.053 5.40194 + endloop + endfacet + facet normal -0.491925 -0.823961 -0.281242 + outer loop + vertex -803.536 132.283 8.96766 + vertex -803.494 132.896 7.09851 + vertex -798.501 129.276 8.97256 + endloop + endfacet + facet normal -0.493588 -0.824268 -0.277403 + outer loop + vertex -798.501 129.276 8.97256 + vertex -803.494 132.896 7.09851 + vertex -798.457 129.879 7.10016 + endloop + endfacet + facet normal -0.484439 -0.829216 -0.278784 + outer loop + vertex -798.501 129.276 8.97256 + vertex -798.457 129.879 7.10016 + vertex -793.46 126.329 8.97644 + endloop + endfacet + facet normal -0.482287 -0.828796 -0.28372 + outer loop + vertex -793.46 126.329 8.97644 + vertex -798.457 129.879 7.10016 + vertex -793.41 126.942 7.10333 + endloop + endfacet + facet normal -0.413943 -0.711699 -0.567571 + outer loop + vertex -798.457 129.879 7.10016 + vertex -798.146 131.053 5.40194 + vertex -793.41 126.942 7.10333 + endloop + endfacet + facet normal -0.411498 -0.710326 -0.571057 + outer loop + vertex -793.41 126.942 7.10333 + vertex -798.146 131.053 5.40194 + vertex -793.098 128.124 5.40802 + endloop + endfacet + facet normal -0.442568 -0.698166 -0.562759 + outer loop + vertex -813.601 139.198 7.09349 + vertex -813.295 140.368 5.40106 + vertex -808.543 135.991 7.09488 + endloop + endfacet + facet normal -0.439069 -0.696309 -0.567778 + outer loop + vertex -808.543 135.991 7.09488 + vertex -813.295 140.368 5.40106 + vertex -808.231 137.173 5.40388 + endloop + endfacet + facet normal -0.514336 -0.812753 -0.273663 + outer loop + vertex -813.63 138.589 8.95796 + vertex -813.601 139.198 7.09349 + vertex -808.576 135.388 8.96351 + endloop + endfacet + facet normal -0.51542 -0.812925 -0.2711 + outer loop + vertex -808.576 135.388 8.96351 + vertex -813.601 139.198 7.09349 + vertex -808.543 135.991 7.09488 + endloop + endfacet + facet normal -0.504444 -0.819175 -0.272925 + outer loop + vertex -808.576 135.388 8.96351 + vertex -808.543 135.991 7.09488 + vertex -803.536 132.283 8.96766 + endloop + endfacet + facet normal -0.50153 -0.818672 -0.279721 + outer loop + vertex -803.536 132.283 8.96766 + vertex -808.543 135.991 7.09488 + vertex -803.494 132.896 7.09851 + endloop + endfacet + facet normal -0.429281 -0.701123 -0.569337 + outer loop + vertex -808.543 135.991 7.09488 + vertex -808.231 137.173 5.40388 + vertex -803.494 132.896 7.09851 + endloop + endfacet + facet normal -0.43073 -0.701909 -0.56727 + outer loop + vertex -803.494 132.896 7.09851 + vertex -808.231 137.173 5.40388 + vertex -803.181 134.074 5.40453 + endloop + endfacet + facet normal -0.464949 -0.689459 -0.5554 + outer loop + vertex -823.708 145.905 7.09063 + vertex -823.4 147.058 5.40101 + vertex -818.665 142.503 7.09143 + endloop + endfacet + facet normal -0.461219 -0.687588 -0.560803 + outer loop + vertex -818.665 142.503 7.09143 + vertex -823.4 147.058 5.40101 + vertex -818.354 143.671 5.40382 + endloop + endfacet + facet normal -0.53881 -0.798045 -0.269829 + outer loop + vertex -823.735 145.295 8.94684 + vertex -823.708 145.905 7.09063 + vertex -818.691 141.888 8.95228 + endloop + endfacet + facet normal -0.538176 -0.797958 -0.271349 + outer loop + vertex -818.691 141.888 8.95228 + vertex -823.708 145.905 7.09063 + vertex -818.665 142.503 7.09143 + endloop + endfacet + facet normal -0.525025 -0.805852 -0.273772 + outer loop + vertex -818.691 141.888 8.95228 + vertex -818.665 142.503 7.09143 + vertex -813.63 138.589 8.95796 + endloop + endfacet + facet normal -0.525925 -0.80599 -0.271632 + outer loop + vertex -813.63 138.589 8.95796 + vertex -818.665 142.503 7.09143 + vertex -813.601 139.198 7.09349 + endloop + endfacet + facet normal -0.45174 -0.692506 -0.562465 + outer loop + vertex -818.665 142.503 7.09143 + vertex -818.354 143.671 5.40382 + vertex -813.601 139.198 7.09349 + endloop + endfacet + facet normal -0.452731 -0.693018 -0.561035 + outer loop + vertex -813.601 139.198 7.09349 + vertex -818.354 143.671 5.40382 + vertex -813.295 140.368 5.40106 + endloop + endfacet + facet normal -0.489787 -0.680307 -0.545244 + outer loop + vertex -833.591 152.894 7.08596 + vertex -833.267 154.013 5.39749 + vertex -828.701 149.372 7.08708 + endloop + endfacet + facet normal -0.486086 -0.678625 -0.550626 + outer loop + vertex -828.701 149.372 7.08708 + vertex -833.267 154.013 5.39749 + vertex -828.384 150.514 5.39967 + endloop + endfacet + facet normal -0.562916 -0.783016 -0.264597 + outer loop + vertex -833.634 152.3 8.93534 + vertex -833.591 152.894 7.08596 + vertex -828.73 148.772 8.94105 + endloop + endfacet + facet normal -0.563881 -0.783106 -0.262267 + outer loop + vertex -828.73 148.772 8.94105 + vertex -833.591 152.894 7.08596 + vertex -828.701 149.372 7.08708 + endloop + endfacet + facet normal -0.550666 -0.791606 -0.264815 + outer loop + vertex -828.73 148.772 8.94105 + vertex -828.701 149.372 7.08708 + vertex -823.735 145.295 8.94684 + endloop + endfacet + facet normal -0.549422 -0.79146 -0.267817 + outer loop + vertex -823.735 145.295 8.94684 + vertex -828.701 149.372 7.08708 + vertex -823.708 145.905 7.09063 + endloop + endfacet + facet normal -0.475092 -0.684714 -0.552679 + outer loop + vertex -828.701 149.372 7.08708 + vertex -828.384 150.514 5.39967 + vertex -823.708 145.905 7.09063 + endloop + endfacet + facet normal -0.474414 -0.684388 -0.553665 + outer loop + vertex -823.708 145.905 7.09063 + vertex -828.384 150.514 5.39967 + vertex -823.4 147.058 5.40101 + endloop + endfacet + facet normal -0.511169 -0.66562 -0.543743 + outer loop + vertex -842.96 159.963 7.0835 + vertex -842.603 161.067 5.39617 + vertex -838.354 156.426 7.08273 + endloop + endfacet + facet normal -0.508845 -0.664692 -0.547047 + outer loop + vertex -838.354 156.426 7.08273 + vertex -842.603 161.067 5.39617 + vertex -838.003 157.543 5.39971 + endloop + endfacet + facet normal -0.586726 -0.767087 -0.25948 + outer loop + vertex -843.031 159.392 8.93121 + vertex -842.96 159.963 7.0835 + vertex -838.405 155.854 8.93093 + endloop + endfacet + facet normal -0.589091 -0.767167 -0.253826 + outer loop + vertex -838.405 155.854 8.93093 + vertex -842.96 159.963 7.0835 + vertex -838.354 156.426 7.08273 + endloop + endfacet + facet normal -0.577367 -0.775308 -0.256019 + outer loop + vertex -838.405 155.854 8.93093 + vertex -838.354 156.426 7.08273 + vertex -833.634 152.3 8.93534 + endloop + endfacet + facet normal -0.574741 -0.775144 -0.262344 + outer loop + vertex -833.634 152.3 8.93534 + vertex -838.354 156.426 7.08273 + vertex -833.591 152.894 7.08596 + endloop + endfacet + facet normal -0.497611 -0.671416 -0.549166 + outer loop + vertex -838.354 156.426 7.08273 + vertex -838.003 157.543 5.39971 + vertex -833.591 152.894 7.08596 + endloop + endfacet + facet normal -0.501952 -0.673267 -0.542915 + outer loop + vertex -833.591 152.894 7.08596 + vertex -838.003 157.543 5.39971 + vertex -833.267 154.013 5.39749 + endloop + endfacet + facet normal -0.530103 -0.643355 -0.552345 + outer loop + vertex -851.808 167.109 7.09083 + vertex -851.437 168.251 5.40608 + vertex -847.428 163.504 7.08749 + endloop + endfacet + facet normal -0.534935 -0.645065 -0.545652 + outer loop + vertex -847.428 163.504 7.08749 + vertex -851.437 168.251 5.40608 + vertex -847.058 164.623 5.40064 + endloop + endfacet + facet normal -0.612786 -0.746986 -0.257887 + outer loop + vertex -851.879 166.531 8.93515 + vertex -851.808 167.109 7.09083 + vertex -847.502 162.94 8.93578 + endloop + endfacet + facet normal -0.615168 -0.746953 -0.252251 + outer loop + vertex -847.502 162.94 8.93578 + vertex -851.808 167.109 7.09083 + vertex -847.428 163.504 7.08749 + endloop + endfacet + facet normal -0.601267 -0.757313 -0.25486 + outer loop + vertex -847.502 162.94 8.93578 + vertex -847.428 163.504 7.08749 + vertex -843.031 159.392 8.93121 + endloop + endfacet + facet normal -0.600371 -0.757307 -0.256983 + outer loop + vertex -843.031 159.392 8.93121 + vertex -847.428 163.504 7.08749 + vertex -842.96 159.963 7.0835 + endloop + endfacet + facet normal -0.519499 -0.654928 -0.548808 + outer loop + vertex -847.428 163.504 7.08749 + vertex -847.058 164.623 5.40064 + vertex -842.96 159.963 7.0835 + endloop + endfacet + facet normal -0.525035 -0.656985 -0.541025 + outer loop + vertex -842.96 159.963 7.0835 + vertex -847.058 164.623 5.40064 + vertex -842.603 161.067 5.39617 + endloop + endfacet + facet normal -0.550664 -0.620057 -0.558837 + outer loop + vertex -860.672 174.881 7.02864 + vertex -860.295 176.045 5.36594 + vertex -856.196 170.866 7.07254 + endloop + endfacet + facet normal -0.553706 -0.621091 -0.554667 + outer loop + vertex -856.196 170.866 7.07254 + vertex -860.295 176.045 5.36594 + vertex -855.827 172.032 5.39851 + endloop + endfacet + facet normal -0.637424 -0.720634 -0.272721 + outer loop + vertex -860.748 174.258 8.85316 + vertex -860.672 174.881 7.02864 + vertex -856.26 170.267 8.90717 + endloop + endfacet + facet normal -0.643755 -0.720552 -0.257652 + outer loop + vertex -856.26 170.267 8.90717 + vertex -860.672 174.881 7.02864 + vertex -856.196 170.866 7.07254 + endloop + endfacet + facet normal -0.625346 -0.735131 -0.261772 + outer loop + vertex -856.26 170.267 8.90717 + vertex -856.196 170.866 7.07254 + vertex -851.879 166.531 8.93515 + endloop + endfacet + facet normal -0.628314 -0.735068 -0.254747 + outer loop + vertex -851.879 166.531 8.93515 + vertex -856.196 170.866 7.07254 + vertex -851.808 167.109 7.09083 + endloop + endfacet + facet normal -0.53821 -0.631311 -0.558369 + outer loop + vertex -856.196 170.866 7.07254 + vertex -855.827 172.032 5.39851 + vertex -851.808 167.109 7.09083 + endloop + endfacet + facet normal -0.545002 -0.633652 -0.549051 + outer loop + vertex -851.808 167.109 7.09083 + vertex -855.827 172.032 5.39851 + vertex -851.437 168.251 5.40608 + endloop + endfacet + facet normal -0.582138 -0.608193 -0.539645 + outer loop + vertex -869.814 183.384 7.1074 + vertex -869.256 184.376 5.38771 + vertex -865.253 179.113 7.00114 + endloop + endfacet + facet normal -0.570552 -0.604404 -0.556028 + outer loop + vertex -865.253 179.113 7.00114 + vertex -869.256 184.376 5.38771 + vertex -864.822 180.24 5.33431 + endloop + endfacet + facet normal -0.668739 -0.700781 -0.248382 + outer loop + vertex -869.934 182.82 9.02299 + vertex -869.814 183.384 7.1074 + vertex -865.365 178.523 8.84546 + endloop + endfacet + facet normal -0.662473 -0.700822 -0.264534 + outer loop + vertex -865.365 178.523 8.84546 + vertex -869.814 183.384 7.1074 + vertex -865.253 179.113 7.00114 + endloop + endfacet + facet normal -0.653787 -0.708239 -0.266383 + outer loop + vertex -865.365 178.523 8.84546 + vertex -865.253 179.113 7.00114 + vertex -860.748 174.258 8.85316 + endloop + endfacet + facet normal -0.652658 -0.708241 -0.269132 + outer loop + vertex -860.748 174.258 8.85316 + vertex -865.253 179.113 7.00114 + vertex -860.672 174.881 7.02864 + endloop + endfacet + facet normal -0.561217 -0.611135 -0.558166 + outer loop + vertex -865.253 179.113 7.00114 + vertex -864.822 180.24 5.33431 + vertex -860.672 174.881 7.02864 + endloop + endfacet + facet normal -0.562947 -0.61172 -0.555778 + outer loop + vertex -860.672 174.881 7.02864 + vertex -864.822 180.24 5.33431 + vertex -860.295 176.045 5.36594 + endloop + endfacet + facet normal -0.690423 -0.70128 -0.177548 + outer loop + vertex -873.829 186.519 9.55772 + vertex -874.273 187.493 7.43916 + vertex -869.934 182.82 9.02299 + endloop + endfacet + facet normal -0.66623 -0.702993 -0.248876 + outer loop + vertex -869.934 182.82 9.02299 + vertex -874.273 187.493 7.43916 + vertex -869.814 183.384 7.1074 + endloop + endfacet + facet normal -0.60704 -0.618564 -0.49888 + outer loop + vertex -874.273 187.493 7.43916 + vertex -873.306 188.017 5.61211 + vertex -869.814 183.384 7.1074 + endloop + endfacet + facet normal -0.579021 -0.610751 -0.54011 + outer loop + vertex -869.814 183.384 7.1074 + vertex -873.306 188.017 5.61211 + vertex -869.256 184.376 5.38771 + endloop + endfacet + facet normal -0.177385 -0.384757 -0.905813 + outer loop + vertex -609.109 55.1741 3.8471 + vertex -608.325 57.2721 2.8025 + vertex -607.161 55.0504 3.51829 + endloop + endfacet + facet normal -0.196277 -0.39234 -0.898635 + outer loop + vertex -607.161 55.0504 3.51829 + vertex -608.325 57.2721 2.8025 + vertex -606.826 56.4421 2.83749 + endloop + endfacet + facet normal -0.217739 -0.546248 -0.808828 + outer loop + vertex -609.716 53.2762 5.29227 + vertex -609.109 55.1741 3.8471 + vertex -607.653 53.2149 4.77826 + endloop + endfacet + facet normal -0.174011 -0.525227 -0.83298 + outer loop + vertex -607.653 53.2149 4.77826 + vertex -609.109 55.1741 3.8471 + vertex -607.161 55.0504 3.51829 + endloop + endfacet + facet normal -0.124928 -0.426558 -0.895791 + outer loop + vertex -617.467 57.2413 4.09178 + vertex -616.365 58.9993 3.10085 + vertex -612.644 55.8812 4.06672 + endloop + endfacet + facet normal -0.100668 -0.402032 -0.910075 + outer loop + vertex -612.644 55.8812 4.06672 + vertex -616.365 58.9993 3.10085 + vertex -612.224 58.4658 2.87853 + endloop + endfacet + facet normal -0.177907 -0.594364 -0.784271 + outer loop + vertex -618.228 55.6253 5.48907 + vertex -617.467 57.2413 4.09178 + vertex -613.343 54.1526 5.49701 + endloop + endfacet + facet normal -0.169527 -0.586646 -0.791901 + outer loop + vertex -613.343 54.1526 5.49701 + vertex -617.467 57.2413 4.09178 + vertex -612.644 55.8812 4.06672 + endloop + endfacet + facet normal -0.185102 -0.58094 -0.79262 + outer loop + vertex -613.343 54.1526 5.49701 + vertex -612.644 55.8812 4.06672 + vertex -609.716 53.2762 5.29227 + endloop + endfacet + facet normal -0.163137 -0.564147 -0.809398 + outer loop + vertex -609.716 53.2762 5.29227 + vertex -612.644 55.8812 4.06672 + vertex -609.109 55.1741 3.8471 + endloop + endfacet + facet normal -0.135567 -0.395583 -0.90837 + outer loop + vertex -612.644 55.8812 4.06672 + vertex -612.224 58.4658 2.87853 + vertex -609.109 55.1741 3.8471 + endloop + endfacet + facet normal -0.139834 -0.398992 -0.90623 + outer loop + vertex -609.109 55.1741 3.8471 + vertex -612.224 58.4658 2.87853 + vertex -608.325 57.2721 2.8025 + endloop + endfacet + facet normal -0.129921 -0.42611 -0.895293 + outer loop + vertex -629.124 60.9895 3.97136 + vertex -627.806 62.6011 3.01312 + vertex -623.159 59.0552 4.02631 + endloop + endfacet + facet normal -0.112934 -0.407022 -0.90641 + outer loop + vertex -623.159 59.0552 4.02631 + vertex -627.806 62.6011 3.01312 + vertex -622.214 61.2518 2.92222 + endloop + endfacet + facet normal -0.182262 -0.590747 -0.786002 + outer loop + vertex -629.81 59.3301 5.37766 + vertex -629.124 60.9895 3.97136 + vertex -623.909 57.4524 5.4205 + endloop + endfacet + facet normal -0.185421 -0.594072 -0.78275 + outer loop + vertex -623.909 57.4524 5.4205 + vertex -629.124 60.9895 3.97136 + vertex -623.159 59.0552 4.02631 + endloop + endfacet + facet normal -0.182067 -0.59543 -0.782505 + outer loop + vertex -623.909 57.4524 5.4205 + vertex -623.159 59.0552 4.02631 + vertex -618.228 55.6253 5.48907 + endloop + endfacet + facet normal -0.180127 -0.593468 -0.784443 + outer loop + vertex -618.228 55.6253 5.48907 + vertex -623.159 59.0552 4.02631 + vertex -617.467 57.2413 4.09178 + endloop + endfacet + facet normal -0.118571 -0.404747 -0.906709 + outer loop + vertex -623.159 59.0552 4.02631 + vertex -622.214 61.2518 2.92222 + vertex -617.467 57.2413 4.09178 + endloop + endfacet + facet normal -0.134754 -0.421058 -0.896968 + outer loop + vertex -617.467 57.2413 4.09178 + vertex -622.214 61.2518 2.92222 + vertex -616.365 58.9993 3.10085 + endloop + endfacet + facet normal -0.139672 -0.423894 -0.894877 + outer loop + vertex -640.593 64.6943 3.98316 + vertex -639.459 66.3971 2.99957 + vertex -634.972 62.8785 3.96589 + endloop + endfacet + facet normal -0.122683 -0.405262 -0.905931 + outer loop + vertex -634.972 62.8785 3.96589 + vertex -639.459 66.3971 2.99957 + vertex -634 65.0677 2.85501 + endloop + endfacet + facet normal -0.188755 -0.582988 -0.790251 + outer loop + vertex -641.171 62.9641 5.39749 + vertex -640.593 64.6943 3.98316 + vertex -635.582 61.1735 5.38348 + endloop + endfacet + facet normal -0.191708 -0.586016 -0.787295 + outer loop + vertex -635.582 61.1735 5.38348 + vertex -640.593 64.6943 3.98316 + vertex -634.972 62.8785 3.96589 + endloop + endfacet + facet normal -0.188332 -0.58718 -0.787243 + outer loop + vertex -635.582 61.1735 5.38348 + vertex -634.972 62.8785 3.96589 + vertex -629.81 59.3301 5.37766 + endloop + endfacet + facet normal -0.189238 -0.588129 -0.786316 + outer loop + vertex -629.81 59.3301 5.37766 + vertex -634.972 62.8785 3.96589 + vertex -629.124 60.9895 3.97136 + endloop + endfacet + facet normal -0.129177 -0.402538 -0.906243 + outer loop + vertex -634.972 62.8785 3.96589 + vertex -634 65.0677 2.85501 + vertex -629.124 60.9895 3.97136 + endloop + endfacet + facet normal -0.143055 -0.416788 -0.897676 + outer loop + vertex -629.124 60.9895 3.97136 + vertex -634 65.0677 2.85501 + vertex -627.806 62.6011 3.01312 + endloop + endfacet + facet normal -0.142395 -0.424626 -0.894101 + outer loop + vertex -651.533 68.2972 4.00244 + vertex -650.472 70.0167 3.0168 + vertex -646.074 66.4807 3.99559 + endloop + endfacet + facet normal -0.123722 -0.404703 -0.90604 + outer loop + vertex -646.074 66.4807 3.99559 + vertex -650.472 70.0167 3.0168 + vertex -645.283 68.7543 2.8721 + endloop + endfacet + facet normal -0.195938 -0.58494 -0.787054 + outer loop + vertex -652.137 66.5995 5.41455 + vertex -651.533 68.2972 4.00244 + vertex -646.652 64.7677 5.41036 + endloop + endfacet + facet normal -0.19543 -0.584436 -0.787554 + outer loop + vertex -646.652 64.7677 5.41036 + vertex -651.533 68.2972 4.00244 + vertex -646.074 66.4807 3.99559 + endloop + endfacet + facet normal -0.194282 -0.584822 -0.787552 + outer loop + vertex -646.652 64.7677 5.41036 + vertex -646.074 66.4807 3.99559 + vertex -641.171 62.9641 5.39749 + endloop + endfacet + facet normal -0.191532 -0.582068 -0.790261 + outer loop + vertex -641.171 62.9641 5.39749 + vertex -646.074 66.4807 3.99559 + vertex -640.593 64.6943 3.98316 + endloop + endfacet + facet normal -0.132948 -0.401544 -0.906138 + outer loop + vertex -646.074 66.4807 3.99559 + vertex -645.283 68.7543 2.8721 + vertex -640.593 64.6943 3.98316 + endloop + endfacet + facet normal -0.149569 -0.417984 -0.896057 + outer loop + vertex -640.593 64.6943 3.98316 + vertex -645.283 68.7543 2.8721 + vertex -639.459 66.3971 2.99957 + endloop + endfacet + facet normal -0.143355 -0.419259 -0.896477 + outer loop + vertex -662.602 72.0575 3.99358 + vertex -661.49 73.7604 3.01939 + vertex -657.043 70.1498 3.99676 + endloop + endfacet + facet normal -0.126668 -0.401561 -0.90703 + outer loop + vertex -657.043 70.1498 3.99676 + vertex -661.49 73.7604 3.01939 + vertex -656.262 72.4264 2.87986 + endloop + endfacet + facet normal -0.202032 -0.5873 -0.783749 + outer loop + vertex -663.243 70.3868 5.41062 + vertex -662.602 72.0575 3.99358 + vertex -657.669 68.4678 5.41181 + endloop + endfacet + facet normal -0.200597 -0.58589 -0.785171 + outer loop + vertex -657.669 68.4678 5.41181 + vertex -662.602 72.0575 3.99358 + vertex -657.043 70.1498 3.99676 + endloop + endfacet + facet normal -0.197842 -0.586881 -0.78513 + outer loop + vertex -657.669 68.4678 5.41181 + vertex -657.043 70.1498 3.99676 + vertex -652.137 66.5995 5.41455 + endloop + endfacet + facet normal -0.195892 -0.584956 -0.787053 + outer loop + vertex -652.137 66.5995 5.41455 + vertex -657.043 70.1498 3.99676 + vertex -651.533 68.2972 4.00244 + endloop + endfacet + facet normal -0.133337 -0.399297 -0.907074 + outer loop + vertex -657.043 70.1498 3.99676 + vertex -656.262 72.4264 2.87986 + vertex -651.533 68.2972 4.00244 + endloop + endfacet + facet normal -0.153063 -0.418647 -0.895157 + outer loop + vertex -651.533 68.2972 4.00244 + vertex -656.262 72.4264 2.87986 + vertex -650.472 70.0167 3.0168 + endloop + endfacet + facet normal -0.149491 -0.419011 -0.89559 + outer loop + vertex -673.85 76.0343 3.99707 + vertex -672.7 77.7073 3.02231 + vertex -668.205 74.0223 3.99619 + endloop + endfacet + facet normal -0.133086 -0.40176 -0.906022 + outer loop + vertex -668.205 74.0223 3.99619 + vertex -672.7 77.7073 3.02231 + vertex -667.381 76.2726 2.87732 + endloop + endfacet + facet normal -0.208593 -0.582237 -0.785805 + outer loop + vertex -674.515 74.3679 5.40821 + vertex -673.85 76.0343 3.99707 + vertex -668.864 72.3465 5.40599 + endloop + endfacet + facet normal -0.207154 -0.580833 -0.787223 + outer loop + vertex -668.864 72.3465 5.40599 + vertex -673.85 76.0343 3.99707 + vertex -668.205 74.0223 3.99619 + endloop + endfacet + facet normal -0.202457 -0.582605 -0.787135 + outer loop + vertex -668.864 72.3465 5.40599 + vertex -668.205 74.0223 3.99619 + vertex -663.243 70.3868 5.41062 + endloop + endfacet + facet normal -0.205818 -0.5859 -0.783811 + outer loop + vertex -663.243 70.3868 5.41062 + vertex -668.205 74.0223 3.99619 + vertex -662.602 72.0575 3.99358 + endloop + endfacet + facet normal -0.140379 -0.399123 -0.906088 + outer loop + vertex -668.205 74.0223 3.99619 + vertex -667.381 76.2726 2.87732 + vertex -662.602 72.0575 3.99358 + endloop + endfacet + facet normal -0.154366 -0.412752 -0.897668 + outer loop + vertex -662.602 72.0575 3.99358 + vertex -667.381 76.2726 2.87732 + vertex -661.49 73.7604 3.01939 + endloop + endfacet + facet normal -0.153736 -0.417038 -0.895793 + outer loop + vertex -685.18 80.1777 3.9939 + vertex -684.016 81.8379 3.0213 + vertex -679.52 78.0884 3.99533 + endloop + endfacet + facet normal -0.138377 -0.401145 -0.905502 + outer loop + vertex -679.52 78.0884 3.99533 + vertex -684.016 81.8379 3.0213 + vertex -678.657 80.3185 2.87542 + endloop + endfacet + facet normal -0.215568 -0.581068 -0.784787 + outer loop + vertex -685.835 78.5128 5.40655 + vertex -685.18 80.1777 3.9939 + vertex -680.186 76.4193 5.40508 + endloop + endfacet + facet normal -0.213635 -0.579212 -0.786685 + outer loop + vertex -680.186 76.4193 5.40508 + vertex -685.18 80.1777 3.9939 + vertex -679.52 78.0884 3.99533 + endloop + endfacet + facet normal -0.209628 -0.580758 -0.786623 + outer loop + vertex -680.186 76.4193 5.40508 + vertex -679.52 78.0884 3.99533 + vertex -674.515 74.3679 5.40821 + endloop + endfacet + facet normal -0.210426 -0.581533 -0.785837 + outer loop + vertex -674.515 74.3679 5.40821 + vertex -679.52 78.0884 3.99533 + vertex -673.85 76.0343 3.99707 + endloop + endfacet + facet normal -0.144233 -0.398913 -0.905574 + outer loop + vertex -679.52 78.0884 3.99533 + vertex -678.657 80.3185 2.87542 + vertex -673.85 76.0343 3.99707 + endloop + endfacet + facet normal -0.158977 -0.413129 -0.896689 + outer loop + vertex -673.85 76.0343 3.99707 + vertex -678.657 80.3185 2.87542 + vertex -672.7 77.7073 3.02231 + endloop + endfacet + facet normal -0.161042 -0.417337 -0.894369 + outer loop + vertex -696.396 84.4491 3.99645 + vertex -695.246 86.0988 3.01965 + vertex -690.805 82.2962 3.99429 + endloop + endfacet + facet normal -0.142175 -0.398322 -0.90616 + outer loop + vertex -690.805 82.2962 3.99429 + vertex -695.246 86.0988 3.01965 + vertex -689.938 84.5235 2.87917 + endloop + endfacet + facet normal -0.223275 -0.579465 -0.783817 + outer loop + vertex -697.046 82.7882 5.40933 + vertex -696.396 84.4491 3.99645 + vertex -691.451 80.6337 5.40842 + endloop + endfacet + facet normal -0.223512 -0.579687 -0.783585 + outer loop + vertex -691.451 80.6337 5.40842 + vertex -696.396 84.4491 3.99645 + vertex -690.805 82.2962 3.99429 + endloop + endfacet + facet normal -0.219727 -0.581148 -0.783573 + outer loop + vertex -691.451 80.6337 5.40842 + vertex -690.805 82.2962 3.99429 + vertex -685.835 78.5128 5.40655 + endloop + endfacet + facet normal -0.218464 -0.579951 -0.784813 + outer loop + vertex -685.835 78.5128 5.40655 + vertex -690.805 82.2962 3.99429 + vertex -685.18 80.1777 3.9939 + endloop + endfacet + facet normal -0.149071 -0.395666 -0.906215 + outer loop + vertex -690.805 82.2962 3.99429 + vertex -689.938 84.5235 2.87917 + vertex -685.18 80.1777 3.9939 + endloop + endfacet + facet normal -0.164508 -0.410212 -0.89703 + outer loop + vertex -685.18 80.1777 3.9939 + vertex -689.938 84.5235 2.87917 + vertex -684.016 81.8379 3.0213 + endloop + endfacet + facet normal -0.166391 -0.414605 -0.89466 + outer loop + vertex -707.526 88.8544 3.99467 + vertex -706.358 90.4871 3.02077 + vertex -701.977 86.6315 3.99278 + endloop + endfacet + facet normal -0.149153 -0.397703 -0.90531 + outer loop + vertex -701.977 86.6315 3.99278 + vertex -706.358 90.4871 3.02077 + vertex -701.1 88.8479 2.87468 + endloop + endfacet + facet normal -0.229378 -0.575367 -0.785072 + outer loop + vertex -708.198 87.1986 5.40441 + vertex -707.526 88.8544 3.99467 + vertex -702.634 84.9776 5.40662 + endloop + endfacet + facet normal -0.231543 -0.57734 -0.782986 + outer loop + vertex -702.634 84.9776 5.40662 + vertex -707.526 88.8544 3.99467 + vertex -701.977 86.6315 3.99278 + endloop + endfacet + facet normal -0.226564 -0.579315 -0.782983 + outer loop + vertex -702.634 84.9776 5.40662 + vertex -701.977 86.6315 3.99278 + vertex -697.046 82.7882 5.40933 + endloop + endfacet + facet normal -0.225703 -0.578519 -0.78382 + outer loop + vertex -697.046 82.7882 5.40933 + vertex -701.977 86.6315 3.99278 + vertex -696.396 84.4491 3.99645 + endloop + endfacet + facet normal -0.15415 -0.395738 -0.905334 + outer loop + vertex -701.977 86.6315 3.99278 + vertex -701.1 88.8479 2.87468 + vertex -696.396 84.4491 3.99645 + endloop + endfacet + facet normal -0.170882 -0.411105 -0.895428 + outer loop + vertex -696.396 84.4491 3.99645 + vertex -701.1 88.8479 2.87468 + vertex -695.246 86.0988 3.01965 + endloop + endfacet + facet normal -0.173059 -0.414508 -0.893439 + outer loop + vertex -718.422 93.347 3.99652 + vertex -717.28 94.9755 3.01983 + vertex -713.022 91.0961 3.99478 + endloop + endfacet + facet normal -0.15497 -0.39742 -0.904456 + outer loop + vertex -713.022 91.0961 3.99478 + vertex -717.28 94.9755 3.01983 + vertex -712.127 93.2961 2.87484 + endloop + endfacet + facet normal -0.241029 -0.574717 -0.782052 + outer loop + vertex -719.072 91.6972 5.40925 + vertex -718.422 93.347 3.99652 + vertex -713.688 89.4438 5.40573 + endloop + endfacet + facet normal -0.239099 -0.573035 -0.783877 + outer loop + vertex -713.688 89.4438 5.40573 + vertex -718.422 93.347 3.99652 + vertex -713.022 91.0961 3.99478 + endloop + endfacet + facet normal -0.235201 -0.574621 -0.783895 + outer loop + vertex -713.688 89.4438 5.40573 + vertex -713.022 91.0961 3.99478 + vertex -708.198 87.1986 5.40441 + endloop + endfacet + facet normal -0.233959 -0.573513 -0.785077 + outer loop + vertex -708.198 87.1986 5.40441 + vertex -713.022 91.0961 3.99478 + vertex -707.526 88.8544 3.99467 + endloop + endfacet + facet normal -0.161115 -0.39493 -0.904473 + outer loop + vertex -713.022 91.0961 3.99478 + vertex -712.127 93.2961 2.87484 + vertex -707.526 88.8544 3.99467 + endloop + endfacet + facet normal -0.176124 -0.408268 -0.895711 + outer loop + vertex -707.526 88.8544 3.99467 + vertex -712.127 93.2961 2.87484 + vertex -706.358 90.4871 3.02077 + endloop + endfacet + facet normal -0.180967 -0.413124 -0.892513 + outer loop + vertex -729.029 97.9048 3.9976 + vertex -727.925 99.5351 3.01912 + vertex -723.743 95.6011 3.99215 + endloop + endfacet + facet normal -0.159122 -0.393142 -0.905604 + outer loop + vertex -723.743 95.6011 3.99215 + vertex -727.925 99.5351 3.01912 + vertex -722.894 97.8214 2.8791 + endloop + endfacet + facet normal -0.246373 -0.56981 -0.783975 + outer loop + vertex -729.679 96.2496 5.40492 + vertex -729.029 97.9048 3.9976 + vertex -724.381 93.9543 5.4082 + endloop + endfacet + facet normal -0.250742 -0.573493 -0.779893 + outer loop + vertex -724.381 93.9543 5.4082 + vertex -729.029 97.9048 3.9976 + vertex -723.743 95.6011 3.99215 + endloop + endfacet + facet normal -0.244705 -0.575934 -0.780013 + outer loop + vertex -724.381 93.9543 5.4082 + vertex -723.743 95.6011 3.99215 + vertex -719.072 91.6972 5.40925 + endloop + endfacet + facet normal -0.242559 -0.574099 -0.782033 + outer loop + vertex -719.072 91.6972 5.40925 + vertex -723.743 95.6011 3.99215 + vertex -718.422 93.347 3.99652 + endloop + endfacet + facet normal -0.164857 -0.390917 -0.905542 + outer loop + vertex -723.743 95.6011 3.99215 + vertex -722.894 97.8214 2.8791 + vertex -718.422 93.347 3.99652 + endloop + endfacet + facet normal -0.184106 -0.407398 -0.894501 + outer loop + vertex -718.422 93.347 3.99652 + vertex -722.894 97.8214 2.8791 + vertex -717.28 94.9755 3.01983 + endloop + endfacet + facet normal -0.188785 -0.414918 -0.890058 + outer loop + vertex -739.773 102.725 3.99928 + vertex -738.624 104.315 3.01447 + vertex -734.366 100.27 3.99656 + endloop + endfacet + facet normal -0.167658 -0.395793 -0.902906 + outer loop + vertex -734.366 100.27 3.99656 + vertex -738.624 104.315 3.01447 + vertex -733.528 102.478 2.8731 + endloop + endfacet + facet normal -0.256149 -0.566962 -0.782906 + outer loop + vertex -740.464 101.095 5.40536 + vertex -739.773 102.725 3.99928 + vertex -735.03 98.6363 5.40808 + endloop + endfacet + facet normal -0.258722 -0.569116 -0.780493 + outer loop + vertex -735.03 98.6363 5.40808 + vertex -739.773 102.725 3.99928 + vertex -734.366 100.27 3.99656 + endloop + endfacet + facet normal -0.255024 -0.570682 -0.780567 + outer loop + vertex -735.03 98.6363 5.40808 + vertex -734.366 100.27 3.99656 + vertex -729.679 96.2496 5.40492 + endloop + endfacet + facet normal -0.251484 -0.567715 -0.783872 + outer loop + vertex -729.679 96.2496 5.40492 + vertex -734.366 100.27 3.99656 + vertex -729.029 97.9048 3.9976 + endloop + endfacet + facet normal -0.17414 -0.39327 -0.902781 + outer loop + vertex -734.366 100.27 3.99656 + vertex -733.528 102.478 2.8731 + vertex -729.029 97.9048 3.9976 + endloop + endfacet + facet normal -0.190562 -0.407091 -0.893288 + outer loop + vertex -729.029 97.9048 3.9976 + vertex -733.528 102.478 2.8731 + vertex -727.925 99.5351 3.01912 + endloop + endfacet + facet normal -0.19617 -0.412839 -0.889427 + outer loop + vertex -750.625 107.8 3.99924 + vertex -749.459 109.368 3.01432 + vertex -745.226 105.243 3.99529 + endloop + endfacet + facet normal -0.173453 -0.392783 -0.903126 + outer loop + vertex -745.226 105.243 3.99529 + vertex -749.459 109.368 3.01432 + vertex -744.315 107.415 2.87578 + endloop + endfacet + facet normal -0.267379 -0.564936 -0.780612 + outer loop + vertex -751.303 106.176 5.40698 + vertex -750.625 107.8 3.99924 + vertex -745.915 103.626 5.40696 + endloop + endfacet + facet normal -0.268588 -0.56592 -0.779484 + outer loop + vertex -745.915 103.626 5.40696 + vertex -750.625 107.8 3.99924 + vertex -745.226 105.243 3.99529 + endloop + endfacet + facet normal -0.263916 -0.56799 -0.779574 + outer loop + vertex -745.915 103.626 5.40696 + vertex -745.226 105.243 3.99529 + vertex -740.464 101.095 5.40536 + endloop + endfacet + facet normal -0.260425 -0.565095 -0.782845 + outer loop + vertex -740.464 101.095 5.40536 + vertex -745.226 105.243 3.99529 + vertex -739.773 102.725 3.99928 + endloop + endfacet + facet normal -0.179554 -0.390189 -0.903057 + outer loop + vertex -745.226 105.243 3.99529 + vertex -744.315 107.415 2.87578 + vertex -739.773 102.725 3.99928 + endloop + endfacet + facet normal -0.200194 -0.407306 -0.891081 + outer loop + vertex -739.773 102.725 3.99928 + vertex -744.315 107.415 2.87578 + vertex -738.624 104.315 3.01447 + endloop + endfacet + facet normal -0.204041 -0.410884 -0.888562 + outer loop + vertex -761.166 112.956 3.99953 + vertex -760.053 114.532 3.0147 + vertex -755.935 110.364 3.99699 + endloop + endfacet + facet normal -0.181424 -0.391718 -0.902021 + outer loop + vertex -755.935 110.364 3.99699 + vertex -760.053 114.532 3.0147 + vertex -755.05 112.538 2.87454 + endloop + endfacet + facet normal -0.277804 -0.5616 -0.779378 + outer loop + vertex -761.818 111.325 5.40663 + vertex -761.166 112.956 3.99953 + vertex -756.59 108.737 5.40792 + endloop + endfacet + facet normal -0.279218 -0.5627 -0.778078 + outer loop + vertex -756.59 108.737 5.40792 + vertex -761.166 112.956 3.99953 + vertex -755.935 110.364 3.99699 + endloop + endfacet + facet normal -0.273889 -0.565026 -0.778287 + outer loop + vertex -756.59 108.737 5.40792 + vertex -755.935 110.364 3.99699 + vertex -751.303 106.176 5.40698 + endloop + endfacet + facet normal -0.271493 -0.563123 -0.780503 + outer loop + vertex -751.303 106.176 5.40698 + vertex -755.935 110.364 3.99699 + vertex -750.625 107.8 3.99924 + endloop + endfacet + facet normal -0.187478 -0.38918 -0.901882 + outer loop + vertex -755.935 110.364 3.99699 + vertex -755.05 112.538 2.87454 + vertex -750.625 107.8 3.99924 + endloop + endfacet + facet normal -0.207431 -0.405096 -0.890432 + outer loop + vertex -750.625 107.8 3.99924 + vertex -755.05 112.538 2.87454 + vertex -749.459 109.368 3.01432 + endloop + endfacet + facet normal -0.210036 -0.406723 -0.889079 + outer loop + vertex -771.661 118.325 3.99402 + vertex -770.518 119.876 3.01428 + vertex -766.393 115.599 3.99634 + endloop + endfacet + facet normal -0.188713 -0.389051 -0.90168 + outer loop + vertex -766.393 115.599 3.99634 + vertex -770.518 119.876 3.01428 + vertex -765.537 117.781 2.87587 + endloop + endfacet + facet normal -0.292882 -0.561703 -0.773763 + outer loop + vertex -772.337 116.727 5.40956 + vertex -771.661 118.325 3.99402 + vertex -767.057 113.98 5.40523 + endloop + endfacet + facet normal -0.288575 -0.55843 -0.77774 + outer loop + vertex -767.057 113.98 5.40523 + vertex -771.661 118.325 3.99402 + vertex -766.393 115.599 3.99634 + endloop + endfacet + facet normal -0.28385 -0.560552 -0.777953 + outer loop + vertex -767.057 113.98 5.40523 + vertex -766.393 115.599 3.99634 + vertex -761.818 111.325 5.40663 + endloop + endfacet + facet normal -0.282523 -0.559533 -0.779168 + outer loop + vertex -761.818 111.325 5.40663 + vertex -766.393 115.599 3.99634 + vertex -761.166 112.956 3.99953 + endloop + endfacet + facet normal -0.194931 -0.386498 -0.901455 + outer loop + vertex -766.393 115.599 3.99634 + vertex -765.537 117.781 2.87587 + vertex -761.166 112.956 3.99953 + endloop + endfacet + facet normal -0.21611 -0.40287 -0.889377 + outer loop + vertex -761.166 112.956 3.99953 + vertex -765.537 117.781 2.87587 + vertex -760.053 114.532 3.0147 + endloop + endfacet + facet normal -0.218942 -0.403088 -0.888586 + outer loop + vertex -782.196 123.97 3.99625 + vertex -781.029 125.493 3.01815 + vertex -776.951 121.126 3.9941 + endloop + endfacet + facet normal -0.196264 -0.384875 -0.90186 + outer loop + vertex -776.951 121.126 3.9941 + vertex -781.029 125.493 3.01815 + vertex -776.035 123.273 2.87838 + endloop + endfacet + facet normal -0.299748 -0.553653 -0.776929 + outer loop + vertex -782.882 122.368 5.40294 + vertex -782.196 123.97 3.99625 + vertex -777.639 119.527 5.40444 + endloop + endfacet + facet normal -0.301068 -0.554625 -0.775725 + outer loop + vertex -777.639 119.527 5.40444 + vertex -782.196 123.97 3.99625 + vertex -776.951 121.126 3.9941 + endloop + endfacet + facet normal -0.293909 -0.557993 -0.776055 + outer loop + vertex -777.639 119.527 5.40444 + vertex -776.951 121.126 3.9941 + vertex -772.337 116.727 5.40956 + endloop + endfacet + facet normal -0.296572 -0.559995 -0.773596 + outer loop + vertex -772.337 116.727 5.40956 + vertex -776.951 121.126 3.9941 + vertex -771.661 118.325 3.99402 + endloop + endfacet + facet normal -0.202394 -0.382156 -0.901661 + outer loop + vertex -776.951 121.126 3.9941 + vertex -776.035 123.273 2.87838 + vertex -771.661 118.325 3.99402 + endloop + endfacet + facet normal -0.223002 -0.397738 -0.889986 + outer loop + vertex -771.661 118.325 3.99402 + vertex -776.035 123.273 2.87838 + vertex -770.518 119.876 3.01428 + endloop + endfacet + facet normal -0.227484 -0.401702 -0.887066 + outer loop + vertex -792.441 129.714 3.99377 + vertex -791.315 131.238 3.01467 + vertex -787.358 126.83 3.99604 + endloop + endfacet + facet normal -0.203389 -0.383173 -0.901006 + outer loop + vertex -787.358 126.83 3.99604 + vertex -791.315 131.238 3.01467 + vertex -786.449 128.971 2.88042 + endloop + endfacet + facet normal -0.317011 -0.553869 -0.769892 + outer loop + vertex -793.098 128.124 5.40802 + vertex -792.441 129.714 3.99377 + vertex -788.029 125.229 5.40366 + endloop + endfacet + facet normal -0.311785 -0.550217 -0.774629 + outer loop + vertex -788.029 125.229 5.40366 + vertex -792.441 129.714 3.99377 + vertex -787.358 126.83 3.99604 + endloop + endfacet + facet normal -0.307145 -0.552418 -0.774917 + outer loop + vertex -788.029 125.229 5.40366 + vertex -787.358 126.83 3.99604 + vertex -782.882 122.368 5.40294 + endloop + endfacet + facet normal -0.30524 -0.55105 -0.776642 + outer loop + vertex -782.882 122.368 5.40294 + vertex -787.358 126.83 3.99604 + vertex -782.196 123.97 3.99625 + endloop + endfacet + facet normal -0.210482 -0.38001 -0.900716 + outer loop + vertex -787.358 126.83 3.99604 + vertex -786.449 128.971 2.88042 + vertex -782.196 123.97 3.99625 + endloop + endfacet + facet normal -0.230656 -0.394646 -0.889411 + outer loop + vertex -782.196 123.97 3.99625 + vertex -786.449 128.971 2.88042 + vertex -781.029 125.493 3.01815 + endloop + endfacet + facet normal -0.23975 -0.400514 -0.884369 + outer loop + vertex -802.515 135.656 3.99736 + vertex -801.405 137.16 3.01498 + vertex -797.48 132.647 3.99503 + endloop + endfacet + facet normal -0.213654 -0.381108 -0.899505 + outer loop + vertex -797.48 132.647 3.99503 + vertex -801.405 137.16 3.01498 + vertex -796.608 134.797 2.87704 + endloop + endfacet + facet normal -0.32836 -0.546718 -0.770247 + outer loop + vertex -803.181 134.074 5.40453 + vertex -802.515 135.656 3.99736 + vertex -798.146 131.053 5.40194 + endloop + endfacet + facet normal -0.326195 -0.545259 -0.772198 + outer loop + vertex -798.146 131.053 5.40194 + vertex -802.515 135.656 3.99736 + vertex -797.48 132.647 3.99503 + endloop + endfacet + facet normal -0.317821 -0.549309 -0.772819 + outer loop + vertex -798.146 131.053 5.40194 + vertex -797.48 132.647 3.99503 + vertex -793.098 128.124 5.40802 + endloop + endfacet + facet normal -0.321407 -0.55177 -0.769576 + outer loop + vertex -793.098 128.124 5.40802 + vertex -797.48 132.647 3.99503 + vertex -792.441 129.714 3.99377 + endloop + endfacet + facet normal -0.220383 -0.378179 -0.899118 + outer loop + vertex -797.48 132.647 3.99503 + vertex -796.608 134.797 2.87704 + vertex -792.441 129.714 3.99377 + endloop + endfacet + facet normal -0.240731 -0.392362 -0.88775 + outer loop + vertex -792.441 129.714 3.99377 + vertex -796.608 134.797 2.87704 + vertex -791.315 131.238 3.01467 + endloop + endfacet + facet normal -0.249362 -0.397124 -0.883239 + outer loop + vertex -812.624 141.928 3.99368 + vertex -811.493 143.395 3.01495 + vertex -807.564 138.746 3.99614 + endloop + endfacet + facet normal -0.224414 -0.379101 -0.897731 + outer loop + vertex -807.564 138.746 3.99614 + vertex -811.493 143.395 3.01495 + vertex -806.687 140.875 2.87767 + endloop + endfacet + facet normal -0.342664 -0.54371 -0.766134 + outer loop + vertex -813.295 140.368 5.40106 + vertex -812.624 141.928 3.99368 + vertex -808.231 137.173 5.40388 + endloop + endfacet + facet normal -0.340893 -0.542551 -0.767744 + outer loop + vertex -808.231 137.173 5.40388 + vertex -812.624 141.928 3.99368 + vertex -807.564 138.746 3.99614 + endloop + endfacet + facet normal -0.334775 -0.545612 -0.768266 + outer loop + vertex -808.231 137.173 5.40388 + vertex -807.564 138.746 3.99614 + vertex -803.181 134.074 5.40453 + endloop + endfacet + facet normal -0.333 -0.544431 -0.769874 + outer loop + vertex -803.181 134.074 5.40453 + vertex -807.564 138.746 3.99614 + vertex -802.515 135.656 3.99736 + endloop + endfacet + facet normal -0.230208 -0.376517 -0.897351 + outer loop + vertex -807.564 138.746 3.99614 + vertex -806.687 140.875 2.87767 + vertex -802.515 135.656 3.99736 + endloop + endfacet + facet normal -0.252356 -0.391546 -0.884878 + outer loop + vertex -802.515 135.656 3.99736 + vertex -806.687 140.875 2.87767 + vertex -801.405 137.16 3.01498 + endloop + endfacet + facet normal -0.263072 -0.394291 -0.880527 + outer loop + vertex -822.711 148.579 3.99399 + vertex -821.545 149.986 3.01558 + vertex -817.677 145.213 3.99736 + endloop + endfacet + facet normal -0.237684 -0.376756 -0.8953 + outer loop + vertex -817.677 145.213 3.99736 + vertex -821.545 149.986 3.01558 + vertex -816.757 147.293 2.87783 + endloop + endfacet + facet normal -0.361653 -0.53942 -0.760416 + outer loop + vertex -823.4 147.058 5.40101 + vertex -822.711 148.579 3.99399 + vertex -818.354 143.671 5.40382 + endloop + endfacet + facet normal -0.359156 -0.53786 -0.762702 + outer loop + vertex -818.354 143.671 5.40382 + vertex -822.711 148.579 3.99399 + vertex -817.677 145.213 3.99736 + endloop + endfacet + facet normal -0.353494 -0.54084 -0.763239 + outer loop + vertex -818.354 143.671 5.40382 + vertex -817.677 145.213 3.99736 + vertex -813.295 140.368 5.40106 + endloop + endfacet + facet normal -0.351169 -0.539353 -0.765362 + outer loop + vertex -813.295 140.368 5.40106 + vertex -817.677 145.213 3.99736 + vertex -812.624 141.928 3.99368 + endloop + endfacet + facet normal -0.243696 -0.373878 -0.89489 + outer loop + vertex -817.677 145.213 3.99736 + vertex -816.757 147.293 2.87783 + vertex -812.624 141.928 3.99368 + endloop + endfacet + facet normal -0.263347 -0.386712 -0.8838 + outer loop + vertex -812.624 141.928 3.99368 + vertex -816.757 147.293 2.87783 + vertex -811.493 143.395 3.01495 + endloop + endfacet + facet normal -0.27604 -0.385286 -0.880543 + outer loop + vertex -832.549 155.51 3.99468 + vertex -831.361 156.881 3.02206 + vertex -827.682 152.021 3.9951 + endloop + endfacet + facet normal -0.252995 -0.370478 -0.893722 + outer loop + vertex -827.682 152.021 3.9951 + vertex -831.361 156.881 3.02206 + vertex -826.701 154.049 2.8769 + endloop + endfacet + facet normal -0.379164 -0.529557 -0.758817 + outer loop + vertex -833.267 154.013 5.39749 + vertex -832.549 155.51 3.99468 + vertex -828.384 150.514 5.39967 + endloop + endfacet + facet normal -0.37964 -0.529833 -0.758387 + outer loop + vertex -828.384 150.514 5.39967 + vertex -832.549 155.51 3.99468 + vertex -827.682 152.021 3.9951 + endloop + endfacet + facet normal -0.370673 -0.534857 -0.759295 + outer loop + vertex -828.384 150.514 5.39967 + vertex -827.682 152.021 3.9951 + vertex -823.4 147.058 5.40101 + endloop + endfacet + facet normal -0.370379 -0.534679 -0.759564 + outer loop + vertex -823.4 147.058 5.40101 + vertex -827.682 152.021 3.9951 + vertex -822.711 148.579 3.99399 + endloop + endfacet + facet normal -0.25573 -0.369052 -0.893534 + outer loop + vertex -827.682 152.021 3.9951 + vertex -826.701 154.049 2.8769 + vertex -822.711 148.579 3.99399 + endloop + endfacet + facet normal -0.277742 -0.38259 -0.881184 + outer loop + vertex -822.711 148.579 3.99399 + vertex -826.701 154.049 2.8769 + vertex -821.545 149.986 3.01558 + endloop + endfacet + facet normal -0.290938 -0.377011 -0.879328 + outer loop + vertex -841.877 162.569 3.99415 + vertex -840.725 163.957 3.01755 + vertex -837.286 159.026 3.99395 + endloop + endfacet + facet normal -0.266769 -0.362834 -0.892853 + outer loop + vertex -837.286 159.026 3.99395 + vertex -840.725 163.957 3.01755 + vertex -836.293 161.052 2.87408 + endloop + endfacet + facet normal -0.395655 -0.51717 -0.758941 + outer loop + vertex -842.603 161.067 5.39617 + vertex -841.877 162.569 3.99415 + vertex -838.003 157.543 5.39971 + endloop + endfacet + facet normal -0.401395 -0.520173 -0.753858 + outer loop + vertex -838.003 157.543 5.39971 + vertex -841.877 162.569 3.99415 + vertex -837.286 159.026 3.99395 + endloop + endfacet + facet normal -0.392082 -0.525691 -0.754931 + outer loop + vertex -838.003 157.543 5.39971 + vertex -837.286 159.026 3.99395 + vertex -833.267 154.013 5.39749 + endloop + endfacet + facet normal -0.388893 -0.523936 -0.757796 + outer loop + vertex -833.267 154.013 5.39749 + vertex -837.286 159.026 3.99395 + vertex -832.549 155.51 3.99468 + endloop + endfacet + facet normal -0.26855 -0.36188 -0.892706 + outer loop + vertex -837.286 159.026 3.99395 + vertex -836.293 161.052 2.87408 + vertex -832.549 155.51 3.99468 + endloop + endfacet + facet normal -0.289716 -0.373827 -0.881089 + outer loop + vertex -832.549 155.51 3.99468 + vertex -836.293 161.052 2.87408 + vertex -831.361 156.881 3.02206 + endloop + endfacet + facet normal -0.306087 -0.366733 -0.878531 + outer loop + vertex -850.732 169.788 3.99528 + vertex -849.625 171.215 3.0143 + vertex -846.346 166.138 3.99112 + endloop + endfacet + facet normal -0.277403 -0.351231 -0.894251 + outer loop + vertex -846.346 166.138 3.99112 + vertex -849.625 171.215 3.0143 + vertex -845.393 168.227 2.87509 + endloop + endfacet + facet normal -0.417408 -0.502845 -0.756913 + outer loop + vertex -851.437 168.251 5.40608 + vertex -850.732 169.788 3.99528 + vertex -847.058 164.623 5.40064 + endloop + endfacet + facet normal -0.420473 -0.504299 -0.754244 + outer loop + vertex -847.058 164.623 5.40064 + vertex -850.732 169.788 3.99528 + vertex -846.346 166.138 3.99112 + endloop + endfacet + facet normal -0.40892 -0.511269 -0.755903 + outer loop + vertex -847.058 164.623 5.40064 + vertex -846.346 166.138 3.99112 + vertex -842.603 161.067 5.39617 + endloop + endfacet + facet normal -0.407057 -0.510345 -0.757531 + outer loop + vertex -842.603 161.067 5.39617 + vertex -846.346 166.138 3.99112 + vertex -841.877 162.569 3.99415 + endloop + endfacet + facet normal -0.279168 -0.350322 -0.894058 + outer loop + vertex -846.346 166.138 3.99112 + vertex -845.393 168.227 2.87509 + vertex -841.877 162.569 3.99415 + endloop + endfacet + facet normal -0.306335 -0.364314 -0.879451 + outer loop + vertex -841.877 162.569 3.99415 + vertex -845.393 168.227 2.87509 + vertex -840.725 163.957 3.01755 + endloop + endfacet + facet normal -0.318659 -0.357245 -0.877971 + outer loop + vertex -859.547 177.547 3.97827 + vertex -858.364 178.856 3.01577 + vertex -855.12 173.57 3.98949 + endloop + endfacet + facet normal -0.290871 -0.342994 -0.893168 + outer loop + vertex -855.12 173.57 3.98949 + vertex -858.364 178.856 3.01577 + vertex -854.158 175.647 2.87849 + endloop + endfacet + facet normal -0.431626 -0.486808 -0.759419 + outer loop + vertex -860.295 176.045 5.36594 + vertex -859.547 177.547 3.97827 + vertex -855.827 172.032 5.39851 + endloop + endfacet + facet normal -0.43789 -0.489637 -0.753995 + outer loop + vertex -855.827 172.032 5.39851 + vertex -859.547 177.547 3.97827 + vertex -855.12 173.57 3.98949 + endloop + endfacet + facet normal -0.42657 -0.496609 -0.755922 + outer loop + vertex -855.827 172.032 5.39851 + vertex -855.12 173.57 3.98949 + vertex -851.437 168.251 5.40608 + endloop + endfacet + facet normal -0.427223 -0.49691 -0.755355 + outer loop + vertex -851.437 168.251 5.40608 + vertex -855.12 173.57 3.98949 + vertex -850.732 169.788 3.99528 + endloop + endfacet + facet normal -0.293295 -0.34171 -0.892867 + outer loop + vertex -855.12 173.57 3.98949 + vertex -854.158 175.647 2.87849 + vertex -850.732 169.788 3.99528 + endloop + endfacet + facet normal -0.320832 -0.354997 -0.878091 + outer loop + vertex -850.732 169.788 3.99528 + vertex -854.158 175.647 2.87849 + vertex -849.625 171.215 3.0143 + endloop + endfacet + facet normal -0.334906 -0.355957 -0.872429 + outer loop + vertex -868.326 185.69 3.97949 + vertex -866.913 186.694 3.02751 + vertex -864.007 181.673 3.9606 + endloop + endfacet + facet normal -0.306651 -0.34251 -0.888061 + outer loop + vertex -864.007 181.673 3.9606 + vertex -866.913 186.694 3.02751 + vertex -862.81 183.41 2.87719 + endloop + endfacet + facet normal -0.456612 -0.479777 -0.749213 + outer loop + vertex -869.256 184.376 5.38771 + vertex -868.326 185.69 3.97949 + vertex -864.822 180.24 5.33431 + endloop + endfacet + facet normal -0.444947 -0.474794 -0.759337 + outer loop + vertex -864.822 180.24 5.33431 + vertex -868.326 185.69 3.97949 + vertex -864.007 181.673 3.9606 + endloop + endfacet + facet normal -0.438707 -0.479182 -0.760211 + outer loop + vertex -864.822 180.24 5.33431 + vertex -864.007 181.673 3.9606 + vertex -860.295 176.045 5.36594 + endloop + endfacet + facet normal -0.441486 -0.480418 -0.757819 + outer loop + vertex -860.295 176.045 5.36594 + vertex -864.007 181.673 3.9606 + vertex -859.547 177.547 3.97827 + endloop + endfacet + facet normal -0.310664 -0.339577 -0.887792 + outer loop + vertex -864.007 181.673 3.9606 + vertex -862.81 183.41 2.87719 + vertex -859.547 177.547 3.97827 + endloop + endfacet + facet normal -0.328957 -0.347903 -0.877924 + outer loop + vertex -859.547 177.547 3.97827 + vertex -862.81 183.41 2.87719 + vertex -858.364 178.856 3.01577 + endloop + endfacet + facet normal -0.477144 -0.485577 -0.732495 + outer loop + vertex -873.306 188.017 5.61211 + vertex -872.327 189.287 4.13225 + vertex -869.256 184.376 5.38771 + endloop + endfacet + facet normal -0.458572 -0.478192 -0.749029 + outer loop + vertex -869.256 184.376 5.38771 + vertex -872.327 189.287 4.13225 + vertex -868.326 185.69 3.97949 + endloop + endfacet + facet normal -0.345265 -0.346955 -0.872017 + outer loop + vertex -872.327 189.287 4.13225 + vertex -870.688 190.629 2.94985 + vertex -868.326 185.69 3.97949 + endloop + endfacet + facet normal -0.342652 -0.345999 -0.873427 + outer loop + vertex -868.326 185.69 3.97949 + vertex -870.688 190.629 2.94985 + vertex -866.913 186.694 3.02751 + endloop + endfacet + facet normal -0.0983192 -0.259937 -0.960607 + outer loop + vertex -608.325 57.2721 2.8025 + vertex -612.224 58.4658 2.87853 + vertex -611.115 61.851 1.84895 + endloop + endfacet + facet normal -0.0869867 -0.276239 -0.957144 + outer loop + vertex -616.365 58.9993 3.10085 + vertex -619.215 63.5924 2.0343 + vertex -612.224 58.4658 2.87853 + endloop + endfacet + facet normal -0.0792109 -0.266214 -0.960654 + outer loop + vertex -619.215 63.5924 2.0343 + vertex -611.115 61.851 1.84895 + vertex -612.224 58.4658 2.87853 + endloop + endfacet + facet normal -0.0742965 -0.269085 -0.960247 + outer loop + vertex -616.365 58.9993 3.10085 + vertex -622.214 61.2518 2.92222 + vertex -619.215 63.5924 2.0343 + endloop + endfacet + facet normal -0.0789462 -0.262423 -0.961718 + outer loop + vertex -627.806 62.6011 3.01312 + vertex -630.211 66.9544 2.02264 + vertex -622.214 61.2518 2.92222 + endloop + endfacet + facet normal -0.0794002 -0.263027 -0.961516 + outer loop + vertex -630.211 66.9544 2.02264 + vertex -619.215 63.5924 2.0343 + vertex -622.214 61.2518 2.92222 + endloop + endfacet + facet normal -0.0802109 -0.263058 -0.96144 + outer loop + vertex -627.806 62.6011 3.01312 + vertex -634 65.0677 2.85501 + vertex -630.211 66.9544 2.02264 + endloop + endfacet + facet normal -0.0906142 -0.267784 -0.959208 + outer loop + vertex -639.459 66.3971 2.99957 + vertex -641.725 70.7191 2.00702 + vertex -634 65.0677 2.85501 + endloop + endfacet + facet normal -0.0830237 -0.257917 -0.962593 + outer loop + vertex -641.725 70.7191 2.00702 + vertex -630.211 66.9544 2.02264 + vertex -634 65.0677 2.85501 + endloop + endfacet + facet normal -0.0866056 -0.265889 -0.960105 + outer loop + vertex -639.459 66.3971 2.99957 + vertex -645.283 68.7543 2.8721 + vertex -641.725 70.7191 2.00702 + endloop + endfacet + facet normal -0.0916877 -0.266918 -0.959348 + outer loop + vertex -650.472 70.0167 3.0168 + vertex -652.898 74.4498 2.01524 + vertex -645.283 68.7543 2.8721 + endloop + endfacet + facet normal -0.0884632 -0.262822 -0.96078 + outer loop + vertex -652.898 74.4498 2.01524 + vertex -641.725 70.7191 2.00702 + vertex -645.283 68.7543 2.8721 + endloop + endfacet + facet normal -0.0875153 -0.264852 -0.96031 + outer loop + vertex -650.472 70.0167 3.0168 + vertex -656.262 72.4264 2.87986 + vertex -652.898 74.4498 2.01524 + endloop + endfacet + facet normal -0.0933558 -0.26551 -0.959578 + outer loop + vertex -661.49 73.7604 3.01939 + vertex -663.978 78.2541 2.01802 + vertex -656.262 72.4264 2.87986 + endloop + endfacet + facet normal -0.0899211 -0.261186 -0.961091 + outer loop + vertex -663.978 78.2541 2.01802 + vertex -652.898 74.4498 2.01524 + vertex -656.262 72.4264 2.87986 + endloop + endfacet + facet normal -0.0891624 -0.263406 -0.960556 + outer loop + vertex -661.49 73.7604 3.01939 + vertex -667.381 76.2726 2.87732 + vertex -663.978 78.2541 2.01802 + endloop + endfacet + facet normal -0.0979006 -0.265981 -0.958994 + outer loop + vertex -672.7 77.7073 3.02231 + vertex -675.16 82.2299 2.01917 + vertex -667.381 76.2726 2.87732 + endloop + endfacet + facet normal -0.0921043 -0.258779 -0.961535 + outer loop + vertex -675.16 82.2299 2.01917 + vertex -663.978 78.2541 2.01802 + vertex -667.381 76.2726 2.87732 + endloop + endfacet + facet normal -0.0915299 -0.262846 -0.960486 + outer loop + vertex -672.7 77.7073 3.02231 + vertex -678.657 80.3185 2.87542 + vertex -675.16 82.2299 2.01917 + endloop + endfacet + facet normal -0.101534 -0.266097 -0.958584 + outer loop + vertex -684.016 81.8379 3.0213 + vertex -686.406 86.3789 2.01396 + vertex -678.657 80.3185 2.87542 + endloop + endfacet + facet normal -0.0946212 -0.257684 -0.961585 + outer loop + vertex -686.406 86.3789 2.01396 + vertex -675.16 82.2299 2.01917 + vertex -678.657 80.3185 2.87542 + endloop + endfacet + facet normal -0.0965779 -0.263745 -0.959745 + outer loop + vertex -684.016 81.8379 3.0213 + vertex -689.938 84.5235 2.87917 + vertex -686.406 86.3789 2.01396 + endloop + endfacet + facet normal -0.10352 -0.26333 -0.959135 + outer loop + vertex -695.246 86.0988 3.01965 + vertex -697.58 90.6676 2.0172 + vertex -689.938 84.5235 2.87917 + endloop + endfacet + facet normal -0.0995398 -0.258618 -0.960837 + outer loop + vertex -697.58 90.6676 2.0172 + vertex -686.406 86.3789 2.01396 + vertex -689.938 84.5235 2.87917 + endloop + endfacet + facet normal -0.0988792 -0.261195 -0.960208 + outer loop + vertex -695.246 86.0988 3.01965 + vertex -701.1 88.8479 2.87468 + vertex -697.58 90.6676 2.0172 + endloop + endfacet + facet normal -0.108723 -0.263286 -0.958572 + outer loop + vertex -706.358 90.4871 3.02077 + vertex -708.616 95.0737 2.01706 + vertex -701.1 88.8479 2.87468 + endloop + endfacet + facet normal -0.102048 -0.255615 -0.961378 + outer loop + vertex -708.616 95.0737 2.01706 + vertex -697.58 90.6676 2.0172 + vertex -701.1 88.8479 2.87468 + endloop + endfacet + facet normal -0.102589 -0.260577 -0.959987 + outer loop + vertex -706.358 90.4871 3.02077 + vertex -712.127 93.2961 2.87484 + vertex -708.616 95.0737 2.01706 + endloop + endfacet + facet normal -0.112089 -0.261155 -0.958767 + outer loop + vertex -717.28 94.9755 3.01983 + vertex -719.473 99.5888 2.01959 + vertex -712.127 93.2961 2.87484 + endloop + endfacet + facet normal -0.106022 -0.254413 -0.961267 + outer loop + vertex -719.473 99.5888 2.01959 + vertex -708.616 95.0737 2.01706 + vertex -712.127 93.2961 2.87484 + endloop + endfacet + facet normal -0.107296 -0.259115 -0.959868 + outer loop + vertex -717.28 94.9755 3.01983 + vertex -722.894 97.8214 2.8791 + vertex -719.473 99.5888 2.01959 + endloop + endfacet + facet normal -0.115386 -0.260419 -0.958576 + outer loop + vertex -727.925 99.5351 3.01912 + vertex -730.167 104.226 2.0146 + vertex -722.894 97.8214 2.8791 + endloop + endfacet + facet normal -0.109913 -0.254505 -0.960805 + outer loop + vertex -730.167 104.226 2.0146 + vertex -719.473 99.5888 2.01959 + vertex -722.894 97.8214 2.8791 + endloop + endfacet + facet normal -0.110743 -0.258432 -0.959661 + outer loop + vertex -727.925 99.5351 3.01912 + vertex -733.528 102.478 2.8731 + vertex -730.167 104.226 2.0146 + endloop + endfacet + facet normal -0.119285 -0.257227 -0.958961 + outer loop + vertex -738.624 104.315 3.01447 + vertex -740.866 109.071 2.01753 + vertex -733.528 102.478 2.8731 + endloop + endfacet + facet normal -0.114393 -0.252038 -0.960932 + outer loop + vertex -740.866 109.071 2.01753 + vertex -730.167 104.226 2.0146 + vertex -733.528 102.478 2.8731 + endloop + endfacet + facet normal -0.115998 -0.25584 -0.959735 + outer loop + vertex -738.624 104.315 3.01447 + vertex -744.315 107.415 2.87578 + vertex -740.866 109.071 2.01753 + endloop + endfacet + facet normal -0.122912 -0.255711 -0.958908 + outer loop + vertex -749.459 109.368 3.01432 + vertex -751.584 114.135 2.01547 + vertex -744.315 107.415 2.87578 + endloop + endfacet + facet normal -0.118484 -0.251146 -0.96067 + outer loop + vertex -751.584 114.135 2.01547 + vertex -740.866 109.071 2.01753 + vertex -744.315 107.415 2.87578 + endloop + endfacet + facet normal -0.120446 -0.254731 -0.959482 + outer loop + vertex -749.459 109.368 3.01432 + vertex -755.05 112.538 2.87454 + vertex -751.584 114.135 2.01547 + endloop + endfacet + facet normal -0.128077 -0.253911 -0.95871 + outer loop + vertex -760.053 114.532 3.0147 + vertex -762.164 119.362 2.01772 + vertex -755.05 112.538 2.87454 + endloop + endfacet + facet normal -0.12329 -0.249155 -0.960584 + outer loop + vertex -762.164 119.362 2.01772 + vertex -751.584 114.135 2.01547 + vertex -755.05 112.538 2.87454 + endloop + endfacet + facet normal -0.125522 -0.252918 -0.959311 + outer loop + vertex -760.053 114.532 3.0147 + vertex -765.537 117.781 2.87587 + vertex -762.164 119.362 2.01772 + endloop + endfacet + facet normal -0.13313 -0.253179 -0.958215 + outer loop + vertex -770.518 119.876 3.01428 + vertex -772.628 124.771 2.01417 + vertex -765.537 117.781 2.87587 + endloop + endfacet + facet normal -0.127968 -0.24819 -0.960222 + outer loop + vertex -772.628 124.771 2.01417 + vertex -762.164 119.362 2.01772 + vertex -765.537 117.781 2.87587 + endloop + endfacet + facet normal -0.13204 -0.252762 -0.958476 + outer loop + vertex -770.518 119.876 3.01428 + vertex -776.035 123.273 2.87838 + vertex -772.628 124.771 2.01417 + endloop + endfacet + facet normal -0.138939 -0.252359 -0.957607 + outer loop + vertex -781.029 125.493 3.01815 + vertex -783.036 130.401 2.01577 + vertex -776.035 123.273 2.87838 + endloop + endfacet + facet normal -0.134339 -0.248057 -0.959386 + outer loop + vertex -783.036 130.401 2.01577 + vertex -772.628 124.771 2.01417 + vertex -776.035 123.273 2.87838 + endloop + endfacet + facet normal -0.137199 -0.251733 -0.958022 + outer loop + vertex -781.029 125.493 3.01815 + vertex -786.449 128.971 2.88042 + vertex -783.036 130.401 2.01577 + endloop + endfacet + facet normal -0.142472 -0.249061 -0.957951 + outer loop + vertex -791.315 131.238 3.01467 + vertex -793.287 136.208 2.01569 + vertex -786.449 128.971 2.88042 + endloop + endfacet + facet normal -0.139641 -0.246515 -0.959026 + outer loop + vertex -793.287 136.208 2.01569 + vertex -783.036 130.401 2.01577 + vertex -786.449 128.971 2.88042 + endloop + endfacet + facet normal -0.142579 -0.249098 -0.957926 + outer loop + vertex -791.315 131.238 3.01467 + vertex -796.608 134.797 2.87704 + vertex -793.287 136.208 2.01569 + endloop + endfacet + facet normal -0.149292 -0.247104 -0.957419 + outer loop + vertex -801.405 137.16 3.01498 + vertex -803.391 142.222 2.01853 + vertex -796.608 134.797 2.87704 + endloop + endfacet + facet normal -0.145204 -0.243548 -0.958958 + outer loop + vertex -803.391 142.222 2.01853 + vertex -793.287 136.208 2.01569 + vertex -796.608 134.797 2.87704 + endloop + endfacet + facet normal -0.148758 -0.24692 -0.95755 + outer loop + vertex -801.405 137.16 3.01498 + vertex -806.687 140.875 2.87767 + vertex -803.391 142.222 2.01853 + endloop + endfacet + facet normal -0.155845 -0.245098 -0.95689 + outer loop + vertex -811.493 143.395 3.01495 + vertex -813.415 148.516 2.01643 + vertex -806.687 140.875 2.87767 + endloop + endfacet + facet normal -0.15132 -0.241304 -0.95858 + outer loop + vertex -813.415 148.516 2.01643 + vertex -803.391 142.222 2.01853 + vertex -806.687 140.875 2.87767 + endloop + endfacet + facet normal -0.156817 -0.245416 -0.95665 + outer loop + vertex -811.493 143.395 3.01495 + vertex -816.757 147.293 2.87783 + vertex -813.415 148.516 2.01643 + endloop + endfacet + facet normal -0.16319 -0.241181 -0.956661 + outer loop + vertex -821.545 149.986 3.01558 + vertex -823.309 155.14 2.01728 + vertex -816.757 147.293 2.87783 + endloop + endfacet + facet normal -0.159709 -0.238415 -0.957941 + outer loop + vertex -823.309 155.14 2.01728 + vertex -813.415 148.516 2.01643 + vertex -816.757 147.293 2.87783 + endloop + endfacet + facet normal -0.164645 -0.24161 -0.956304 + outer loop + vertex -821.545 149.986 3.01558 + vertex -826.701 154.049 2.8769 + vertex -823.309 155.14 2.01728 + endloop + endfacet + facet normal -0.174214 -0.237677 -0.955594 + outer loop + vertex -831.361 156.881 3.02206 + vertex -832.94 162.08 2.01681 + vertex -826.701 154.049 2.8769 + endloop + endfacet + facet normal -0.167828 -0.232963 -0.957895 + outer loop + vertex -832.94 162.08 2.01681 + vertex -823.309 155.14 2.01728 + vertex -826.701 154.049 2.8769 + endloop + endfacet + facet normal -0.171792 -0.237056 -0.956186 + outer loop + vertex -831.361 156.881 3.02206 + vertex -836.293 161.052 2.87408 + vertex -832.94 162.08 2.01681 + endloop + endfacet + facet normal -0.182539 -0.231252 -0.955616 + outer loop + vertex -840.725 163.957 3.01755 + vertex -842.183 169.264 2.01211 + vertex -836.293 161.052 2.87408 + endloop + endfacet + facet normal -0.175518 -0.226474 -0.958073 + outer loop + vertex -842.183 169.264 2.01211 + vertex -832.94 162.08 2.01681 + vertex -836.293 161.052 2.87408 + endloop + endfacet + facet normal -0.182261 -0.231188 -0.955684 + outer loop + vertex -840.725 163.957 3.01755 + vertex -845.393 168.227 2.87509 + vertex -842.183 169.264 2.01211 + endloop + endfacet + facet normal -0.191836 -0.227223 -0.954761 + outer loop + vertex -849.625 171.215 3.0143 + vertex -851.019 176.603 2.01207 + vertex -845.393 168.227 2.87509 + endloop + endfacet + facet normal -0.185259 -0.22304 -0.957043 + outer loop + vertex -851.019 176.603 2.01207 + vertex -842.183 169.264 2.01211 + vertex -845.393 168.227 2.87509 + endloop + endfacet + facet normal -0.194067 -0.227696 -0.954197 + outer loop + vertex -849.625 171.215 3.0143 + vertex -854.158 175.647 2.87849 + vertex -851.019 176.603 2.01207 + endloop + endfacet + facet normal -0.20384 -0.226399 -0.952467 + outer loop + vertex -858.364 178.856 3.01577 + vertex -859.456 183.94 2.04109 + vertex -854.158 175.647 2.87849 + endloop + endfacet + facet normal -0.196145 -0.221756 -0.955171 + outer loop + vertex -859.456 183.94 2.04109 + vertex -851.019 176.603 2.01207 + vertex -854.158 175.647 2.87849 + endloop + endfacet + facet normal -0.201833 -0.226065 -0.952973 + outer loop + vertex -858.364 178.856 3.01577 + vertex -862.81 183.41 2.87719 + vertex -859.456 183.94 2.04109 + endloop + endfacet + facet normal -0.221541 -0.233475 -0.946789 + outer loop + vertex -866.913 186.694 3.02751 + vertex -867.176 190.747 2.08965 + vertex -862.81 183.41 2.87719 + endloop + endfacet + facet normal -0.202491 -0.222868 -0.953587 + outer loop + vertex -867.176 190.747 2.08965 + vertex -859.456 183.94 2.04109 + vertex -862.81 183.41 2.87719 + endloop + endfacet + facet normal -0.0617774 -0.182934 -0.981182 + outer loop + vertex -619.215 63.5924 2.0343 + vertex -617.869 68.1713 1.09582 + vertex -611.115 61.851 1.84895 + endloop + endfacet + facet normal -0.0518681 -0.172635 -0.983619 + outer loop + vertex -611.115 61.851 1.84895 + vertex -617.869 68.1713 1.09582 + vertex -610.632 66.7398 0.9655 + endloop + endfacet + facet normal -0.0544366 -0.181451 -0.981892 + outer loop + vertex -630.211 66.9544 2.02264 + vertex -628.028 71.1151 1.13273 + vertex -619.215 63.5924 2.0343 + endloop + endfacet + facet normal -0.0569809 -0.184349 -0.981208 + outer loop + vertex -619.215 63.5924 2.0343 + vertex -628.028 71.1151 1.13273 + vertex -617.869 68.1713 1.09582 + endloop + endfacet + facet normal -0.0574598 -0.179812 -0.982021 + outer loop + vertex -641.725 70.7191 2.00702 + vertex -639.437 74.8135 1.12342 + vertex -630.211 66.9544 2.02264 + endloop + endfacet + facet normal -0.0575063 -0.179865 -0.982009 + outer loop + vertex -630.211 66.9544 2.02264 + vertex -639.437 74.8135 1.12342 + vertex -628.028 71.1151 1.13273 + endloop + endfacet + facet normal -0.0607938 -0.179909 -0.981803 + outer loop + vertex -652.898 74.4498 2.01524 + vertex -650.828 78.6382 1.11958 + vertex -641.725 70.7191 2.00702 + endloop + endfacet + facet normal -0.0596377 -0.178614 -0.98211 + outer loop + vertex -641.725 70.7191 2.00702 + vertex -650.828 78.6382 1.11958 + vertex -639.437 74.8135 1.12342 + endloop + endfacet + facet normal -0.0618331 -0.179367 -0.981837 + outer loop + vertex -663.978 78.2541 2.01802 + vertex -661.983 82.4708 1.12206 + vertex -652.898 74.4498 2.01524 + endloop + endfacet + facet normal -0.0618546 -0.17939 -0.981831 + outer loop + vertex -652.898 74.4498 2.01524 + vertex -661.983 82.4708 1.12206 + vertex -650.828 78.6382 1.11958 + endloop + endfacet + facet normal -0.0636398 -0.178712 -0.981841 + outer loop + vertex -675.16 82.2299 2.01917 + vertex -673.105 86.4124 1.12467 + vertex -663.978 78.2541 2.01802 + endloop + endfacet + facet normal -0.0635167 -0.178578 -0.981873 + outer loop + vertex -663.978 78.2541 2.01802 + vertex -673.105 86.4124 1.12467 + vertex -661.983 82.4708 1.12206 + endloop + endfacet + facet normal -0.0651574 -0.177846 -0.981899 + outer loop + vertex -686.406 86.3789 2.01396 + vertex -684.275 90.5201 1.12243 + vertex -675.16 82.2299 2.01917 + endloop + endfacet + facet normal -0.0652391 -0.177934 -0.981877 + outer loop + vertex -675.16 82.2299 2.01917 + vertex -684.275 90.5201 1.12243 + vertex -673.105 86.4124 1.12467 + endloop + endfacet + facet normal -0.0683313 -0.17729 -0.981784 + outer loop + vertex -697.58 90.6676 2.0172 + vertex -695.422 94.7807 1.12424 + vertex -686.406 86.3789 2.01396 + endloop + endfacet + facet normal -0.0676493 -0.176577 -0.981959 + outer loop + vertex -686.406 86.3789 2.01396 + vertex -695.422 94.7807 1.12424 + vertex -684.275 90.5201 1.12243 + endloop + endfacet + facet normal -0.0707585 -0.177249 -0.981619 + outer loop + vertex -708.616 95.0737 2.01706 + vertex -706.441 99.1646 1.12164 + vertex -697.58 90.6676 2.0172 + endloop + endfacet + facet normal -0.0699635 -0.176442 -0.981821 + outer loop + vertex -697.58 90.6676 2.0172 + vertex -706.441 99.1646 1.12164 + vertex -695.422 94.7807 1.12424 + endloop + endfacet + facet normal -0.0738095 -0.17694 -0.98145 + outer loop + vertex -719.473 99.5888 2.01959 + vertex -717.308 103.667 1.12158 + vertex -708.616 95.0737 2.01706 + endloop + endfacet + facet normal -0.0729514 -0.176094 -0.981666 + outer loop + vertex -708.616 95.0737 2.01706 + vertex -717.308 103.667 1.12158 + vertex -706.441 99.1646 1.12164 + endloop + endfacet + facet normal -0.0753704 -0.174868 -0.981703 + outer loop + vertex -730.167 104.226 2.0146 + vertex -728.046 108.307 1.12478 + vertex -719.473 99.5888 2.01959 + endloop + endfacet + facet normal -0.076212 -0.175674 -0.981494 + outer loop + vertex -719.473 99.5888 2.01959 + vertex -728.046 108.307 1.12478 + vertex -717.308 103.667 1.12158 + endloop + endfacet + facet normal -0.0794937 -0.174956 -0.981362 + outer loop + vertex -740.866 109.071 2.01753 + vertex -738.72 113.123 1.12125 + vertex -730.167 104.226 2.0146 + endloop + endfacet + facet normal -0.0779671 -0.173526 -0.981738 + outer loop + vertex -730.167 104.226 2.0146 + vertex -738.72 113.123 1.12125 + vertex -728.046 108.307 1.12478 + endloop + endfacet + facet normal -0.0818173 -0.173554 -0.98142 + outer loop + vertex -751.584 114.135 2.01547 + vertex -749.382 118.146 1.12267 + vertex -740.866 109.071 2.01753 + endloop + endfacet + facet normal -0.0819405 -0.173667 -0.98139 + outer loop + vertex -740.866 109.071 2.01753 + vertex -749.382 118.146 1.12267 + vertex -738.72 113.123 1.12125 + endloop + endfacet + facet normal -0.0854618 -0.172573 -0.981282 + outer loop + vertex -762.164 119.362 2.01772 + vertex -759.972 123.358 1.12401 + vertex -751.584 114.135 2.01547 + endloop + endfacet + facet normal -0.0847561 -0.171947 -0.981453 + outer loop + vertex -751.584 114.135 2.01547 + vertex -759.972 123.358 1.12401 + vertex -749.382 118.146 1.12267 + endloop + endfacet + facet normal -0.0883993 -0.171656 -0.981183 + outer loop + vertex -772.628 124.771 2.01417 + vertex -770.44 128.747 1.12136 + vertex -762.164 119.362 2.01772 + endloop + endfacet + facet normal -0.0879088 -0.171235 -0.981301 + outer loop + vertex -762.164 119.362 2.01772 + vertex -770.44 128.747 1.12136 + vertex -759.972 123.358 1.12401 + endloop + endfacet + facet normal -0.0922913 -0.170324 -0.981057 + outer loop + vertex -783.036 130.401 2.01577 + vertex -780.809 134.334 1.12347 + vertex -772.628 124.771 2.01417 + endloop + endfacet + facet normal -0.0917077 -0.169838 -0.981196 + outer loop + vertex -772.628 124.771 2.01417 + vertex -780.809 134.334 1.12347 + vertex -770.44 128.747 1.12136 + endloop + endfacet + facet normal -0.0961555 -0.169752 -0.980785 + outer loop + vertex -793.287 136.208 2.01569 + vertex -791.071 140.121 1.12115 + vertex -783.036 130.401 2.01577 + endloop + endfacet + facet normal -0.0949784 -0.168805 -0.981063 + outer loop + vertex -783.036 130.401 2.01577 + vertex -791.071 140.121 1.12115 + vertex -780.809 134.334 1.12347 + endloop + endfacet + facet normal -0.100805 -0.168929 -0.98046 + outer loop + vertex -803.391 142.222 2.01853 + vertex -801.205 146.115 1.12289 + vertex -793.287 136.208 2.01569 + endloop + endfacet + facet normal -0.0994576 -0.167881 -0.980777 + outer loop + vertex -793.287 136.208 2.01569 + vertex -801.205 146.115 1.12289 + vertex -791.071 140.121 1.12115 + endloop + endfacet + facet normal -0.104727 -0.167109 -0.980361 + outer loop + vertex -813.415 148.516 2.01643 + vertex -811.193 152.35 1.12548 + vertex -803.391 142.222 2.01853 + endloop + endfacet + facet normal -0.10443 -0.166887 -0.98043 + outer loop + vertex -803.391 142.222 2.01853 + vertex -811.193 152.35 1.12548 + vertex -801.205 146.115 1.12289 + endloop + endfacet + facet normal -0.111142 -0.165874 -0.979864 + outer loop + vertex -823.309 155.14 2.01728 + vertex -820.998 158.881 1.1218 + vertex -813.415 148.516 2.01643 + endloop + endfacet + facet normal -0.109211 -0.1645 -0.980313 + outer loop + vertex -813.415 148.516 2.01643 + vertex -820.998 158.881 1.1218 + vertex -811.193 152.35 1.12548 + endloop + endfacet + facet normal -0.117007 -0.16244 -0.979756 + outer loop + vertex -832.94 162.08 2.01681 + vertex -830.559 165.769 1.12097 + vertex -823.309 155.14 2.01728 + endloop + endfacet + facet normal -0.116846 -0.162333 -0.979793 + outer loop + vertex -823.309 155.14 2.01728 + vertex -830.559 165.769 1.12097 + vertex -820.998 158.881 1.1218 + endloop + endfacet + facet normal -0.12243 -0.158178 -0.979791 + outer loop + vertex -842.183 169.264 2.01211 + vertex -839.806 172.97 1.11673 + vertex -832.94 162.08 2.01681 + endloop + endfacet + facet normal -0.123019 -0.158538 -0.979659 + outer loop + vertex -832.94 162.08 2.01681 + vertex -839.806 172.97 1.11673 + vertex -830.559 165.769 1.12097 + endloop + endfacet + facet normal -0.128366 -0.154546 -0.979611 + outer loop + vertex -851.019 176.603 2.01207 + vertex -848.636 180.286 1.11878 + vertex -842.183 169.264 2.01211 + endloop + endfacet + facet normal -0.128192 -0.154447 -0.979649 + outer loop + vertex -842.183 169.264 2.01211 + vertex -848.636 180.286 1.11878 + vertex -839.806 172.97 1.11673 + endloop + endfacet + facet normal -0.137912 -0.154707 -0.978287 + outer loop + vertex -859.456 183.94 2.04109 + vertex -856.908 187.364 1.14041 + vertex -851.019 176.603 2.01207 + endloop + endfacet + facet normal -0.132498 -0.151841 -0.979484 + outer loop + vertex -851.019 176.603 2.01207 + vertex -856.908 187.364 1.14041 + vertex -848.636 180.286 1.11878 + endloop + endfacet + facet normal -0.142417 -0.154559 -0.977665 + outer loop + vertex -867.176 190.747 2.08965 + vertex -864.38 193.692 1.21666 + vertex -859.456 183.94 2.04109 + endloop + endfacet + facet normal -0.139803 -0.153288 -0.978242 + outer loop + vertex -859.456 183.94 2.04109 + vertex -864.38 193.692 1.21666 + vertex -856.908 187.364 1.14041 + endloop + endfacet + facet normal -0.670586 -0.716256 0.193112 + outer loop + vertex -608.351 92.8001 31.2306 + vertex -610.077 95.1542 33.968 + vertex -609.038 93.668 32.0656 + endloop + endfacet + facet normal -0.591265 -0.721184 0.360969 + outer loop + vertex -606.715 89.8493 28.0151 + vertex -608.351 92.8001 31.2306 + vertex -607.836 91.7162 29.9081 + endloop + endfacet + facet normal -0.0999777 -0.666631 0.738652 + outer loop + vertex -605.498 87.135 25.7302 + vertex -606.715 89.8493 28.0151 + vertex -607.112 89.5333 27.6761 + endloop + endfacet + facet normal -0.198618 -0.567838 0.798818 + outer loop + vertex -604.464 84.2129 23.9101 + vertex -605.498 87.135 25.7302 + vertex -605.656 85.761 24.7142 + endloop + endfacet + facet normal -0.300503 -0.378012 0.875674 + outer loop + vertex -604.133 81.3022 22.767 + vertex -604.464 84.2129 23.9101 + vertex -604.838 82.9711 23.2458 + endloop + endfacet + facet normal -0.0534244 -0.198423 0.978659 + outer loop + vertex -607.214 64.2598 19.5225 + vertex -607.088 68.947 20.4797 + vertex -610.924 66.88 19.8512 + endloop + endfacet + facet normal -0.0622053 -0.255236 0.964876 + outer loop + vertex -607.085 59.8132 18.3546 + vertex -607.214 64.2598 19.5225 + vertex -610.166 62.5844 18.889 + endloop + endfacet + facet normal -0.0661903 -0.328884 0.942048 + outer loop + vertex -606.673 57.1499 17.4537 + vertex -607.085 59.8132 18.3546 + vertex -607.487 57.7573 17.6086 + endloop + endfacet + facet normal -0.0975602 -0.443653 0.890873 + outer loop + vertex -606.797 55.2383 16.4882 + vertex -606.673 57.1499 17.4537 + vertex -607.452 55.9424 16.7671 + endloop + endfacet + facet normal -0.136267 -0.549572 0.824258 + outer loop + vertex -607.038 53.4482 15.2547 + vertex -606.797 55.2383 16.4882 + vertex -607.673 54.1071 15.5891 + endloop + endfacet + facet normal -0.179267 -0.676481 0.714308 + outer loop + vertex -607.209 51.9269 13.7712 + vertex -607.038 53.4482 15.2547 + vertex -607.889 52.4971 14.1406 + endloop + endfacet + facet normal -0.202337 -0.824248 0.528843 + outer loop + vertex -607.312 50.8586 12.0667 + vertex -607.209 51.9269 13.7712 + vertex -608.006 51.2846 12.4652 + endloop + endfacet + facet normal -0.226118 -0.9408 0.252518 + outer loop + vertex -607.374 50.3724 10.1998 + vertex -607.312 50.8586 12.0667 + vertex -608.104 50.6579 10.6094 + endloop + endfacet + facet normal -0.275684 -0.957526 -0.0845137 + outer loop + vertex -607.388 50.5431 8.31261 + vertex -607.374 50.3724 10.1998 + vertex -608.149 50.7319 8.65503 + endloop + endfacet + facet normal -0.4953 -0.806174 -0.323669 + outer loop + vertex -607.29 51.0675 6.85674 + vertex -607.388 50.5431 8.31261 + vertex -607.896 51.5363 6.6155 + endloop + endfacet + facet normal -0.327881 -0.731214 -0.598181 + outer loop + vertex -607.206 52.1336 5.50727 + vertex -607.29 51.0675 6.85674 + vertex -607.896 51.5363 6.6155 + endloop + endfacet + facet normal -0.207958 -0.604402 -0.769059 + outer loop + vertex -606.94 53.7528 4.16293 + vertex -607.206 52.1336 5.50727 + vertex -607.653 53.2149 4.77826 + endloop + endfacet + facet normal -0.0619162 -0.452499 -0.889613 + outer loop + vertex -606.63 55.8616 3.06863 + vertex -606.94 53.7528 4.16293 + vertex -607.161 55.0504 3.51829 + endloop + endfacet + facet normal 0.669582 -0.0677605 -0.739641 + outer loop + vertex -607.221 58.5027 2.29088 + vertex -606.63 55.8616 3.06863 + vertex -606.826 56.4421 2.83749 + endloop + endfacet + facet normal -0.0690499 -0.20903 -0.975468 + outer loop + vertex -607.26 62.3015 1.47955 + vertex -607.221 58.5027 2.29088 + vertex -611.115 61.851 1.84895 + endloop + endfacet + facet normal -0.0421101 -0.146468 -0.988319 + outer loop + vertex -606.462 66.649 0.80127 + vertex -607.26 62.3015 1.47955 + vertex -610.632 66.7398 0.9655 + endloop + endfacet + facet normal -0.150383 -0.160677 -0.975483 + outer loop + vertex -872.765 195.767 2.12426 + vertex -870.893 198.696 1.35327 + vertex -867.176 190.747 2.08965 + endloop + endfacet + facet normal -0.268941 -0.257777 -0.92802 + outer loop + vertex -874.353 193.476 3.2211 + vertex -872.765 195.767 2.12426 + vertex -870.688 190.629 2.94985 + endloop + endfacet + facet normal -0.374943 -0.366637 -0.851466 + outer loop + vertex -875.759 191.811 4.55684 + vertex -874.353 193.476 3.2211 + vertex -872.327 189.287 4.13225 + endloop + endfacet + facet normal -0.486785 -0.511643 -0.707998 + outer loop + vertex -876.287 190.534 5.84283 + vertex -875.759 191.811 4.55684 + vertex -873.306 188.017 5.61211 + endloop + endfacet + facet normal -0.571206 -0.644808 -0.507884 + outer loop + vertex -877.251 190.513 6.95339 + vertex -876.287 190.534 5.84283 + vertex -874.273 187.493 7.43916 + endloop + endfacet + facet normal -0.657633 -0.69506 -0.290534 + outer loop + vertex -876.975 189.579 8.56213 + vertex -877.251 190.513 6.95339 + vertex -874.273 187.493 7.43916 + endloop + endfacet + facet normal -0.697155 -0.71692 -0.000966577 + outer loop + vertex -876.537 189.151 10.3037 + vertex -876.975 189.579 8.56213 + vertex -873.829 186.519 9.55772 + endloop + endfacet + facet normal -0.666964 -0.679626 0.305398 + outer loop + vertex -876.448 189.783 11.9043 + vertex -876.537 189.151 10.3037 + vertex -873.487 186.632 11.3578 + endloop + endfacet + facet normal -0.572906 -0.576796 0.58231 + outer loop + vertex -875.862 190.721 13.4095 + vertex -876.448 189.783 11.9043 + vertex -872.998 187.416 12.9533 + endloop + endfacet + facet normal -0.457072 -0.44909 0.767726 + outer loop + vertex -874.798 191.969 14.7729 + vertex -875.862 190.721 13.4095 + vertex -872.292 188.678 14.3396 + endloop + endfacet + facet normal -0.341563 -0.331241 0.879553 + outer loop + vertex -873.811 193.755 15.8289 + vertex -874.798 191.969 14.7729 + vertex -871.485 190.426 15.4781 + endloop + endfacet + facet normal -0.234112 -0.217559 0.947555 + outer loop + vertex -872.265 195.681 16.6531 + vertex -873.811 193.755 15.8289 + vertex -870.458 192.404 16.347 + endloop + endfacet + facet normal -0.142917 -0.122102 0.982174 + outer loop + vertex -869.353 198.16 17.385 + vertex -872.265 195.681 16.6531 + vertex -868.664 193.918 16.9579 + endloop + endfacet + facet normal -0.17996 -0.179375 0.967181 + outer loop + vertex -858.237 219.761 20.1253 + vertex -859.276 217.18 19.4532 + vertex -855.861 216.758 20.0103 + endloop + endfacet + facet normal -0.247123 -0.249514 0.936308 + outer loop + vertex -857.15 222.198 21.0616 + vertex -858.237 219.761 20.1253 + vertex -854.855 219.181 20.8631 + endloop + endfacet + facet normal -0.315867 -0.324694 0.891517 + outer loop + vertex -856.362 223.72 21.8949 + vertex -857.15 222.198 21.0616 + vertex -855.721 222.723 21.7589 + endloop + endfacet + facet normal -0.408632 -0.450178 0.793952 + outer loop + vertex -821.451 193.678 23.7581 + vertex -825.885 197.226 23.4882 + vertex -824.597 194.71 22.7249 + endloop + endfacet + facet normal -0.39807 -0.460214 0.793564 + outer loop + vertex -816.959 189.753 23.7352 + vertex -821.451 193.678 23.7581 + vertex -820.399 191.194 22.846 + endloop + endfacet + facet normal -0.390061 -0.461184 0.79697 + outer loop + vertex -812.65 186.278 23.8337 + vertex -816.959 189.753 23.7352 + vertex -816.125 187.679 22.9435 + endloop + endfacet + facet normal -0.383997 -0.466752 0.796673 + outer loop + vertex -808.234 182.878 23.97 + vertex -812.65 186.278 23.8337 + vertex -811.802 184.26 23.0603 + endloop + endfacet + facet normal -0.377849 -0.474935 0.794775 + outer loop + vertex -804.511 179.944 23.9871 + vertex -808.234 182.878 23.97 + vertex -807.513 180.973 23.1746 + endloop + endfacet + facet normal -0.384856 -0.478707 0.789129 + outer loop + vertex -800.482 177.601 24.5307 + vertex -804.511 179.944 23.9871 + vertex -803.25 177.916 23.3721 + endloop + endfacet + facet normal -0.378294 -0.499121 0.779597 + outer loop + vertex -795.101 174.189 24.9571 + vertex -800.482 177.601 24.5307 + vertex -798.627 174.803 23.639 + endloop + endfacet + facet normal -0.363833 -0.512401 0.777863 + outer loop + vertex -789.423 170.328 25.0697 + vertex -795.101 174.189 24.9571 + vertex -793.695 171.482 23.8315 + endloop + endfacet + facet normal -0.34925 -0.520304 0.7793 + outer loop + vertex -785.051 167.11 24.8807 + vertex -789.423 170.328 25.0697 + vertex -788.875 168.217 23.9059 + endloop + endfacet + facet normal -0.339067 -0.514654 0.787506 + outer loop + vertex -780.379 164.488 25.1782 + vertex -785.051 167.11 24.8807 + vertex -784.22 165.223 24.0052 + endloop + endfacet + facet normal -0.322852 -0.521676 0.789697 + outer loop + vertex -775.733 161.407 25.0424 + vertex -780.379 164.488 25.1782 + vertex -779.528 162.342 24.1085 + endloop + endfacet + facet normal -0.314418 -0.515884 0.796872 + outer loop + vertex -770.223 158.36 25.244 + vertex -775.733 161.407 25.0424 + vertex -774.849 159.505 24.1603 + endloop + endfacet + facet normal -0.306107 -0.52629 0.793296 + outer loop + vertex -763.316 154.734 25.5035 + vertex -770.223 158.36 25.244 + vertex -766.488 154.788 24.3155 + endloop + endfacet + facet normal -0.291473 -0.535462 0.792669 + outer loop + vertex -758.223 151.638 25.2852 + vertex -763.316 154.734 25.5035 + vertex -761.216 151.902 24.3626 + endloop + endfacet + facet normal -0.293505 -0.537571 0.790489 + outer loop + vertex -753.471 149.482 25.5831 + vertex -758.223 151.638 25.2852 + vertex -756.218 149.224 24.3881 + endloop + endfacet + facet normal -0.279584 -0.543182 0.791698 + outer loop + vertex -747.382 146.386 25.6092 + vertex -753.471 149.482 25.5831 + vertex -751.136 146.638 24.4566 + endloop + endfacet + facet normal -0.26387 -0.54653 0.794782 + outer loop + vertex -742.105 143.456 25.3466 + vertex -747.382 146.386 25.6092 + vertex -745.877 143.974 24.4502 + endloop + endfacet + facet normal -0.26027 -0.537977 0.801773 + outer loop + vertex -735.653 140.691 25.5857 + vertex -742.105 143.456 25.3466 + vertex -740.413 141.328 24.4677 + endloop + endfacet + facet normal -0.236621 -0.550483 0.800612 + outer loop + vertex -730.588 137.554 24.9258 + vertex -735.653 140.691 25.5857 + vertex -734.914 138.662 24.4091 + endloop + endfacet + facet normal -0.223921 -0.507973 0.831759 + outer loop + vertex -726.666 135.654 24.8214 + vertex -730.588 137.554 24.9258 + vertex -729.845 136.186 24.2905 + endloop + endfacet + facet normal -0.234468 -0.503409 0.831627 + outer loop + vertex -722.263 133.963 25.0391 + vertex -726.666 135.654 24.8214 + vertex -724.951 133.986 24.295 + endloop + endfacet + facet normal -0.231363 -0.520208 0.822104 + outer loop + vertex -716.309 131.603 25.2216 + vertex -722.263 133.963 25.0391 + vertex -719.813 131.78 24.3469 + endloop + endfacet + facet normal -0.212172 -0.527968 0.822333 + outer loop + vertex -710.776 129.047 25.0078 + vertex -716.309 131.603 25.2216 + vertex -714.526 129.501 24.332 + endloop + endfacet + facet normal -0.238448 -0.551924 0.799076 + outer loop + vertex -657.13 108.66 25.6911 + vertex -661.677 109.992 25.254 + vertex -658.708 108.046 24.7961 + endloop + endfacet + facet normal -0.322852 -0.770498 0.549636 + outer loop + vertex -630.035 100.51 29.5634 + vertex -632.906 101.278 28.9542 + vertex -632.645 100.96 28.662 + endloop + endfacet + facet normal -0.322222 -0.772912 0.546608 + outer loop + vertex -632.645 100.96 28.662 + vertex -627.113 99.5522 29.9319 + vertex -630.035 100.51 29.5634 + endloop + endfacet + facet normal -0.297642 -0.672232 0.677875 + outer loop + vertex -642.646 103.529 26.7031 + vertex -638.064 102.343 27.5397 + vertex -641.357 103.509 27.2496 + endloop + endfacet + facet normal 0.20538 -0.665525 0.717562 + outer loop + vertex -608.129 92.2737 30.509 + vertex -607.112 89.5333 27.6761 + vertex -607.836 91.7162 29.9081 + endloop + endfacet + facet normal -0.212027 -0.509539 0.833915 + outer loop + vertex -714.526 129.501 24.332 + vertex -709.439 127.311 24.2869 + vertex -710.776 129.047 25.0078 + endloop + endfacet + facet normal -0.231865 -0.520639 0.821689 + outer loop + vertex -724.951 133.986 24.295 + vertex -719.813 131.78 24.3469 + vertex -722.263 133.963 25.0391 + endloop + endfacet + facet normal -0.229519 -0.537939 0.811137 + outer loop + vertex -719.813 131.78 24.3469 + vertex -714.526 129.501 24.332 + vertex -716.309 131.603 25.2216 + endloop + endfacet + facet normal -0.229604 -0.509814 0.829079 + outer loop + vertex -734.914 138.662 24.4091 + vertex -729.845 136.186 24.2905 + vertex -730.588 137.554 24.9258 + endloop + endfacet + facet normal -0.223045 -0.494358 0.840156 + outer loop + vertex -729.845 136.186 24.2905 + vertex -724.951 133.986 24.295 + vertex -726.666 135.654 24.8214 + endloop + endfacet + facet normal -0.264022 -0.539913 0.799241 + outer loop + vertex -745.877 143.974 24.4502 + vertex -740.413 141.328 24.4677 + vertex -742.105 143.456 25.3466 + endloop + endfacet + facet normal -0.259878 -0.553523 0.791249 + outer loop + vertex -740.413 141.328 24.4677 + vertex -734.914 138.662 24.4091 + vertex -735.653 140.691 25.5857 + endloop + endfacet + facet normal -0.289767 -0.548598 0.784268 + outer loop + vertex -756.218 149.224 24.3881 + vertex -751.136 146.638 24.4566 + vertex -753.471 149.482 25.5831 + endloop + endfacet + facet normal -0.278483 -0.551562 0.786274 + outer loop + vertex -751.136 146.638 24.4566 + vertex -745.877 143.974 24.4502 + vertex -747.382 146.386 25.6092 + endloop + endfacet + facet normal -0.303106 -0.540841 0.784613 + outer loop + vertex -766.488 154.788 24.3155 + vertex -761.216 151.902 24.3626 + vertex -763.316 154.734 25.5035 + endloop + endfacet + facet normal -0.291373 -0.536391 0.792078 + outer loop + vertex -761.216 151.902 24.3626 + vertex -756.218 149.224 24.3881 + vertex -758.223 151.638 25.2852 + endloop + endfacet + facet normal -0.314731 -0.519479 0.794409 + outer loop + vertex -774.849 159.505 24.1603 + vertex -770.997 157.044 24.0766 + vertex -770.223 158.36 25.244 + endloop + endfacet + facet normal -0.304871 -0.525293 0.794431 + outer loop + vertex -770.997 157.044 24.0766 + vertex -766.488 154.788 24.3155 + vertex -770.223 158.36 25.244 + endloop + endfacet + facet normal -0.33898 -0.523937 0.781398 + outer loop + vertex -784.22 165.223 24.0052 + vertex -779.528 162.342 24.1085 + vertex -780.379 164.488 25.1782 + endloop + endfacet + facet normal -0.32254 -0.517624 0.792486 + outer loop + vertex -779.528 162.342 24.1085 + vertex -774.849 159.505 24.1603 + vertex -775.733 161.407 25.0424 + endloop + endfacet + facet normal -0.364374 -0.520369 0.7723 + outer loop + vertex -793.695 171.482 23.8315 + vertex -788.875 168.217 23.9059 + vertex -789.423 170.328 25.0697 + endloop + endfacet + facet normal -0.348831 -0.516425 0.782062 + outer loop + vertex -788.875 168.217 23.9059 + vertex -784.22 165.223 24.0052 + vertex -785.051 167.11 24.8807 + endloop + endfacet + facet normal -0.382149 -0.500743 0.776672 + outer loop + vertex -803.25 177.916 23.3721 + vertex -798.627 174.803 23.639 + vertex -800.482 177.601 24.5307 + endloop + endfacet + facet normal -0.377297 -0.515776 0.76917 + outer loop + vertex -798.627 174.803 23.639 + vertex -793.695 171.482 23.8315 + vertex -795.101 174.189 24.9571 + endloop + endfacet + facet normal -0.385957 -0.476085 0.790177 + outer loop + vertex -811.802 184.26 23.0603 + vertex -807.513 180.973 23.1746 + vertex -808.234 182.878 23.97 + endloop + endfacet + facet normal -0.378012 -0.475954 0.794087 + outer loop + vertex -807.513 180.973 23.1746 + vertex -803.25 177.916 23.3721 + vertex -804.511 179.944 23.9871 + endloop + endfacet + facet normal -0.398656 -0.462681 0.791833 + outer loop + vertex -820.399 191.194 22.846 + vertex -816.125 187.679 22.9435 + vertex -816.959 189.753 23.7352 + endloop + endfacet + facet normal -0.39164 -0.468208 0.792086 + outer loop + vertex -816.125 187.679 22.9435 + vertex -811.802 184.26 23.0603 + vertex -812.65 186.278 23.8337 + endloop + endfacet + facet normal -0.410903 -0.450866 0.792388 + outer loop + vertex -828.608 198.111 22.5795 + vertex -824.597 194.71 22.7249 + vertex -825.885 197.226 23.4882 + endloop + endfacet + facet normal -0.410097 -0.462551 0.786045 + outer loop + vertex -824.597 194.71 22.7249 + vertex -820.399 191.194 22.846 + vertex -821.451 193.678 23.7581 + endloop + endfacet + facet normal -0.280333 -0.288663 0.915471 + outer loop + vertex -853.682 219.794 21.4155 + vertex -855.06 221.312 21.4722 + vertex -854.855 219.181 20.8631 + endloop + endfacet + facet normal -0.0128316 -0.468647 0.883292 + outer loop + vertex -605.656 85.761 24.7142 + vertex -604.838 82.9711 23.2458 + vertex -604.464 84.2129 23.9101 + endloop + endfacet + facet normal 0.0727905 -0.598398 0.797885 + outer loop + vertex -607.112 89.5333 27.6761 + vertex -605.656 85.761 24.7142 + vertex -605.498 87.135 25.7302 + endloop + endfacet + facet normal -0.244962 -0.229821 0.9419 + outer loop + vertex -855.861 216.758 20.0103 + vertex -854.855 219.181 20.8631 + vertex -858.237 219.761 20.1253 + endloop + endfacet + facet normal -0.178358 -0.161999 0.970538 + outer loop + vertex -856.428 213.816 19.4149 + vertex -855.861 216.758 20.0103 + vertex -859.276 217.18 19.4532 + endloop + endfacet + facet normal -0.064411 -0.154103 0.985953 + outer loop + vertex -604.451 80.0418 22.3784 + vertex -606.196 79.6874 22.209 + vertex -605.271 78.4781 22.0804 + endloop + endfacet + facet normal -0.0989496 -0.293389 0.950858 + outer loop + vertex -610.166 62.5844 18.889 + vertex -609.455 59.3261 17.9576 + vertex -607.085 59.8132 18.3546 + endloop + endfacet + facet normal -0.130064 -0.143149 0.981118 + outer loop + vertex -866.658 190.807 16.7698 + vertex -862.573 191.375 17.3942 + vertex -868.664 193.918 16.9579 + endloop + endfacet + facet normal -0.195476 -0.512948 0.835867 + outer loop + vertex -607.452 55.9424 16.7671 + vertex -607.673 54.1071 15.5891 + vertex -606.797 55.2383 16.4882 + endloop + endfacet + facet normal -0.0911532 -0.323869 0.9417 + outer loop + vertex -609.455 59.3261 17.9576 + vertex -607.487 57.7573 17.6086 + vertex -607.085 59.8132 18.3546 + endloop + endfacet + facet normal -0.141691 -0.418657 0.897023 + outer loop + vertex -607.487 57.7573 17.6086 + vertex -607.452 55.9424 16.7671 + vertex -606.673 57.1499 17.4537 + endloop + endfacet + facet normal -0.172733 -0.18557 0.96733 + outer loop + vertex -870.458 192.404 16.347 + vertex -868.664 193.918 16.9579 + vertex -872.265 195.681 16.6531 + endloop + endfacet + facet normal -0.254211 -0.275243 0.927156 + outer loop + vertex -871.485 190.426 15.4781 + vertex -870.458 192.404 16.347 + vertex -873.811 193.755 15.8289 + endloop + endfacet + facet normal -0.32419 -0.755446 0.569388 + outer loop + vertex -607.889 52.4971 14.1406 + vertex -608.006 51.2846 12.4652 + vertex -607.209 51.9269 13.7712 + endloop + endfacet + facet normal -0.262569 -0.625705 0.734541 + outer loop + vertex -607.673 54.1071 15.5891 + vertex -607.889 52.4971 14.1406 + vertex -607.038 53.4482 15.2547 + endloop + endfacet + facet normal -0.360733 -0.386426 0.84885 + outer loop + vertex -872.292 188.678 14.3396 + vertex -871.485 190.426 15.4781 + vertex -874.798 191.969 14.7729 + endloop + endfacet + facet normal -0.479386 -0.513611 0.711613 + outer loop + vertex -872.998 187.416 12.9533 + vertex -872.292 188.678 14.3396 + vertex -875.862 190.721 13.4095 + endloop + endfacet + facet normal -0.376711 -0.925952 -0.0264713 + outer loop + vertex -608.104 50.6579 10.6094 + vertex -608.149 50.7319 8.65503 + vertex -607.374 50.3724 10.1998 + endloop + endfacet + facet normal -0.358048 -0.878703 0.315724 + outer loop + vertex -608.006 51.2846 12.4652 + vertex -608.104 50.6579 10.6094 + vertex -607.312 50.8586 12.0667 + endloop + endfacet + facet normal -0.589011 -0.639177 0.49449 + outer loop + vertex -873.487 186.632 11.3578 + vertex -872.998 187.416 12.9533 + vertex -876.448 189.783 11.9043 + endloop + endfacet + facet normal -0.661992 -0.729623 0.171512 + outer loop + vertex -873.829 186.519 9.55772 + vertex -873.487 186.632 11.3578 + vertex -876.537 189.151 10.3037 + endloop + endfacet + facet normal -0.472808 -0.618487 -0.627636 + outer loop + vertex -607.896 51.5363 6.6155 + vertex -607.653 53.2149 4.77826 + vertex -607.206 52.1336 5.50727 + endloop + endfacet + facet normal -0.380251 -0.843301 -0.379807 + outer loop + vertex -608.149 50.7319 8.65503 + vertex -607.896 51.5363 6.6155 + vertex -607.388 50.5431 8.31261 + endloop + endfacet + facet normal -0.649745 -0.73317 -0.200732 + outer loop + vertex -874.273 187.493 7.43916 + vertex -873.829 186.519 9.55772 + vertex -876.975 189.579 8.56213 + endloop + endfacet + facet normal -0.582981 -0.645212 -0.493796 + outer loop + vertex -873.306 188.017 5.61211 + vertex -874.273 187.493 7.43916 + vertex -876.287 190.534 5.84283 + endloop + endfacet + facet normal -0.1416 -0.407281 -0.902259 + outer loop + vertex -607.161 55.0504 3.51829 + vertex -606.826 56.4421 2.83749 + vertex -606.63 55.8616 3.06863 + endloop + endfacet + facet normal -0.131539 -0.277665 -0.95163 + outer loop + vertex -606.826 56.4421 2.83749 + vertex -608.325 57.2721 2.8025 + vertex -607.221 58.5027 2.29088 + endloop + endfacet + facet normal -0.352007 -0.46385 -0.812979 + outer loop + vertex -607.653 53.2149 4.77826 + vertex -607.161 55.0504 3.51829 + vertex -606.94 53.7528 4.16293 + endloop + endfacet + facet normal -0.459101 -0.500896 -0.73371 + outer loop + vertex -872.327 189.287 4.13225 + vertex -873.306 188.017 5.61211 + vertex -875.759 191.811 4.55684 + endloop + endfacet + facet normal -0.339354 -0.353796 -0.871589 + outer loop + vertex -870.688 190.629 2.94985 + vertex -872.327 189.287 4.13225 + vertex -874.353 193.476 3.2211 + endloop + endfacet + facet normal -0.223901 -0.233499 -0.946228 + outer loop + vertex -866.913 186.694 3.02751 + vertex -870.688 190.629 2.94985 + vertex -867.176 190.747 2.08965 + endloop + endfacet + facet normal -0.131107 -0.278032 -0.951582 + outer loop + vertex -608.325 57.2721 2.8025 + vertex -611.115 61.851 1.84895 + vertex -607.221 58.5027 2.29088 + endloop + endfacet + facet normal -0.0742661 -0.170242 -0.9826 + outer loop + vertex -611.115 61.851 1.84895 + vertex -610.632 66.7398 0.9655 + vertex -607.26 62.3015 1.47955 + endloop + endfacet + facet normal -0.140584 -0.156296 -0.977654 + outer loop + vertex -864.38 193.692 1.21666 + vertex -867.176 190.747 2.08965 + vertex -870.893 198.696 1.35327 + endloop + endfacet + facet normal -0.0219816 -0.718292 0.695395 + outer loop + vertex -606.715 89.8493 28.0151 + vertex -607.836 91.7162 29.9081 + vertex -607.112 89.5333 27.6761 + endloop + endfacet + facet normal -0.223146 -0.241889 -0.944296 + outer loop + vertex -872.765 195.767 2.12426 + vertex -867.176 190.747 2.08965 + vertex -870.688 190.629 2.94985 + endloop + endfacet + facet normal -0.120202 -0.118759 0.98562 + outer loop + vertex -869.353 198.16 17.385 + vertex -868.664 193.918 16.9579 + vertex -862.573 191.375 17.3942 + endloop + endfacet + facet normal -0.301107 -0.288765 0.908818 + outer loop + vertex -857.15 222.198 21.0616 + vertex -854.855 219.181 20.8631 + vertex -855.06 221.312 21.4722 + endloop + endfacet + facet normal -0.31427 -0.328123 0.890825 + outer loop + vertex -855.721 222.723 21.7589 + vertex -857.15 222.198 21.0616 + vertex -855.06 221.312 21.4722 + endloop + endfacet + facet normal -0.265916 -0.55039 0.791429 + outer loop + vertex -645.372 104.448 26.4266 + vertex -647.238 104.414 25.7762 + vertex -642.646 103.529 26.7031 + endloop + endfacet + facet normal -0.506095 -0.693073 0.51334 + outer loop + vertex -854.715 246.893 45.8298 + vertex -854.264 244.788 43.4319 + vertex -850.232 243.199 45.2624 + endloop + endfacet + facet normal -0.571255 -0.696053 0.434946 + outer loop + vertex -859.828 251.489 46.4699 + vertex -859.311 249.599 44.1236 + vertex -854.715 246.893 45.8298 + endloop + endfacet + facet normal -0.570577 -0.667354 0.478624 + outer loop + vertex -854.715 246.893 45.8298 + vertex -859.311 249.599 44.1236 + vertex -854.264 244.788 43.4319 + endloop + endfacet + facet normal -0.72893 -0.604931 0.320498 + outer loop + vertex -875.373 268.602 47.9891 + vertex -875.211 267.012 45.3553 + vertex -870.222 262.245 47.7049 + endloop + endfacet + facet normal -0.729045 -0.60982 0.310825 + outer loop + vertex -870.222 262.245 47.7049 + vertex -875.211 267.012 45.3553 + vertex -870.211 260.872 45.0383 + endloop + endfacet + facet normal -0.773241 -0.555002 0.306712 + outer loop + vertex -879.81 274.836 48.0829 + vertex -879.756 273.407 45.6327 + vertex -875.373 268.602 47.9891 + endloop + endfacet + facet normal -0.77353 -0.562434 0.292094 + outer loop + vertex -875.373 268.602 47.9891 + vertex -879.756 273.407 45.6327 + vertex -875.211 267.012 45.3553 + endloop + endfacet + facet normal -0.847001 -0.454375 0.27592 + outer loop + vertex -887.53 288.349 48.3842 + vertex -887.57 286.982 46.0111 + vertex -883.662 281.128 48.3675 + endloop + endfacet + facet normal -0.847699 -0.458533 0.266747 + outer loop + vertex -883.662 281.128 48.3675 + vertex -887.57 286.982 46.0111 + vertex -883.839 280.001 45.8669 + endloop + endfacet + facet normal -0.882035 -0.393982 0.258441 + outer loop + vertex -890.636 295.43 48.5783 + vertex -890.882 294.351 46.0936 + vertex -887.53 288.349 48.3842 + endloop + endfacet + facet normal -0.883249 -0.39976 0.245077 + outer loop + vertex -887.53 288.349 48.3842 + vertex -890.882 294.351 46.0936 + vertex -887.57 286.982 46.0111 + endloop + endfacet + facet normal -0.910588 -0.323725 0.256965 + outer loop + vertex -893.555 303.588 48.5117 + vertex -893.683 302.082 46.1601 + vertex -890.636 295.43 48.5783 + endloop + endfacet + facet normal -0.913205 -0.332903 0.235017 + outer loop + vertex -890.636 295.43 48.5783 + vertex -893.683 302.082 46.1601 + vertex -890.882 294.351 46.0936 + endloop + endfacet + facet normal -0.938509 -0.257616 0.22986 + outer loop + vertex -895.645 311.356 48.6866 + vertex -895.903 310.083 46.2052 + vertex -893.555 303.588 48.5117 + endloop + endfacet + facet normal -0.939898 -0.261973 0.219003 + outer loop + vertex -893.555 303.588 48.5117 + vertex -895.903 310.083 46.2052 + vertex -893.683 302.082 46.1601 + endloop + endfacet + facet normal -0.958186 -0.175379 0.2261 + outer loop + vertex -897.164 319.507 48.5707 + vertex -897.471 318.198 46.2553 + vertex -895.645 311.356 48.6866 + endloop + endfacet + facet normal -0.962532 -0.187152 0.196232 + outer loop + vertex -895.645 311.356 48.6866 + vertex -897.471 318.198 46.2553 + vertex -895.903 310.083 46.2052 + endloop + endfacet + facet normal -0.971042 -0.1049 0.214648 + outer loop + vertex -898.028 327.531 48.5837 + vertex -898.422 326.444 46.2674 + vertex -897.164 319.507 48.5707 + endloop + endfacet + facet normal -0.974714 -0.112787 0.192903 + outer loop + vertex -897.164 319.507 48.5707 + vertex -898.422 326.444 46.2674 + vertex -897.471 318.198 46.2553 + endloop + endfacet + facet normal -0.978224 -0.0419796 0.203264 + outer loop + vertex -898.355 335.936 48.7441 + vertex -898.813 334.825 46.3106 + vertex -898.028 327.531 48.5837 + endloop + endfacet + facet normal -0.980863 -0.0467049 0.189013 + outer loop + vertex -898.028 327.531 48.5837 + vertex -898.813 334.825 46.3106 + vertex -898.422 326.444 46.2674 + endloop + endfacet + facet normal -0.543658 -0.660469 0.517896 + outer loop + vertex -854.264 244.788 43.4319 + vertex -854.656 242.475 40.07 + vertex -850.649 241.009 42.4073 + endloop + endfacet + facet normal -0.577687 -0.672509 0.462611 + outer loop + vertex -859.311 249.599 44.1236 + vertex -859.533 247.504 40.801 + vertex -854.264 244.788 43.4319 + endloop + endfacet + facet normal -0.581221 -0.637125 0.506216 + outer loop + vertex -854.264 244.788 43.4319 + vertex -859.533 247.504 40.801 + vertex -854.656 242.475 40.07 + endloop + endfacet + facet normal -0.709685 -0.597295 0.373612 + outer loop + vertex -875.211 267.012 45.3553 + vertex -875.722 265.333 41.7012 + vertex -870.211 260.872 45.0383 + endloop + endfacet + facet normal -0.709708 -0.596989 0.374057 + outer loop + vertex -870.211 260.872 45.0383 + vertex -875.722 265.333 41.7012 + vertex -870.579 259.112 41.5291 + endloop + endfacet + facet normal -0.754004 -0.551372 0.357025 + outer loop + vertex -879.756 273.407 45.6327 + vertex -880.301 271.822 42.0337 + vertex -875.211 267.012 45.3553 + endloop + endfacet + facet normal -0.754026 -0.5505 0.358322 + outer loop + vertex -875.211 267.012 45.3553 + vertex -880.301 271.822 42.0337 + vertex -875.722 265.333 41.7012 + endloop + endfacet + facet normal -0.83154 -0.451083 0.324139 + outer loop + vertex -887.57 286.982 46.0111 + vertex -888.185 285.66 42.5929 + vertex -883.839 280.001 45.8669 + endloop + endfacet + facet normal -0.831546 -0.451159 0.324017 + outer loop + vertex -883.839 280.001 45.8669 + vertex -888.185 285.66 42.5929 + vertex -884.427 278.585 42.3855 + endloop + endfacet + facet normal -0.865077 -0.392347 0.312579 + outer loop + vertex -890.882 294.351 46.0936 + vertex -891.525 293.072 42.7099 + vertex -887.57 286.982 46.0111 + endloop + endfacet + facet normal -0.865434 -0.394812 0.308459 + outer loop + vertex -887.57 286.982 46.0111 + vertex -891.525 293.072 42.7099 + vertex -888.185 285.66 42.5929 + endloop + endfacet + facet normal -0.895878 -0.327188 0.300584 + outer loop + vertex -893.683 302.082 46.1601 + vertex -894.353 300.8 42.7682 + vertex -890.882 294.351 46.0936 + endloop + endfacet + facet normal -0.896532 -0.330363 0.295112 + outer loop + vertex -890.882 294.351 46.0936 + vertex -894.353 300.8 42.7682 + vertex -891.525 293.072 42.7099 + endloop + endfacet + facet normal -0.922465 -0.257524 0.287646 + outer loop + vertex -895.903 310.083 46.2052 + vertex -896.597 308.795 42.8254 + vertex -893.683 302.082 46.1601 + endloop + endfacet + facet normal -0.923449 -0.261206 0.281095 + outer loop + vertex -893.683 302.082 46.1601 + vertex -896.597 308.795 42.8254 + vertex -894.353 300.8 42.7682 + endloop + endfacet + facet normal -0.944216 -0.184088 0.27307 + outer loop + vertex -897.471 318.198 46.2553 + vertex -898.211 316.995 42.8837 + vertex -895.903 310.083 46.2052 + endloop + endfacet + facet normal -0.945505 -0.187982 0.265863 + outer loop + vertex -895.903 310.083 46.2052 + vertex -898.211 316.995 42.8837 + vertex -896.597 308.795 42.8254 + endloop + endfacet + facet normal -0.959642 -0.111143 0.25833 + outer loop + vertex -898.422 326.444 46.2674 + vertex -899.198 325.353 42.917 + vertex -897.471 318.198 46.2553 + endloop + endfacet + facet normal -0.96096 -0.11446 0.251903 + outer loop + vertex -897.471 318.198 46.2553 + vertex -899.198 325.353 42.917 + vertex -898.211 316.995 42.8837 + endloop + endfacet + facet normal -0.967955 -0.0464011 0.2468 + outer loop + vertex -898.813 334.825 46.3106 + vertex -899.619 333.834 42.963 + vertex -898.422 326.444 46.2674 + endloop + endfacet + facet normal -0.969389 -0.0494504 0.2405 + outer loop + vertex -898.422 326.444 46.2674 + vertex -899.619 333.834 42.963 + vertex -899.198 325.353 42.917 + endloop + endfacet + facet normal -0.565392 -0.628461 0.5342 + outer loop + vertex -854.656 242.475 40.07 + vertex -855.573 240.009 36.1992 + vertex -851.247 238.502 39.0045 + endloop + endfacet + facet normal -0.58864 -0.642122 0.491104 + outer loop + vertex -859.533 247.504 40.801 + vertex -860.474 245.342 36.8465 + vertex -854.656 242.475 40.07 + endloop + endfacet + facet normal -0.695292 -0.586229 0.415818 + outer loop + vertex -875.722 265.333 41.7012 + vertex -876.587 263.219 37.2733 + vertex -870.579 259.112 41.5291 + endloop + endfacet + facet normal -0.695557 -0.584373 0.417982 + outer loop + vertex -870.579 259.112 41.5291 + vertex -876.587 263.219 37.2733 + vertex -871.125 257.02 37.6972 + endloop + endfacet + facet normal -0.740216 -0.54273 0.396894 + outer loop + vertex -880.301 271.822 42.0337 + vertex -881.351 269.834 37.3584 + vertex -875.722 265.333 41.7012 + endloop + endfacet + facet normal -0.740645 -0.538464 0.401872 + outer loop + vertex -875.722 265.333 41.7012 + vertex -881.351 269.834 37.3584 + vertex -876.587 263.219 37.2733 + endloop + endfacet + facet normal -0.819078 -0.445629 0.361283 + outer loop + vertex -888.185 285.66 42.5929 + vertex -889.159 283.966 38.2963 + vertex -884.427 278.585 42.3855 + endloop + endfacet + facet normal -0.819048 -0.444424 0.362833 + outer loop + vertex -884.427 278.585 42.3855 + vertex -889.159 283.966 38.2963 + vertex -885.377 276.728 37.9664 + endloop + endfacet + facet normal -0.853342 -0.389957 0.346035 + outer loop + vertex -891.525 293.072 42.7099 + vertex -892.525 291.485 38.4539 + vertex -888.185 285.66 42.5929 + endloop + endfacet + facet normal -0.853293 -0.389343 0.346847 + outer loop + vertex -888.185 285.66 42.5929 + vertex -892.525 291.485 38.4539 + vertex -889.159 283.966 38.2963 + endloop + endfacet + facet normal -0.884219 -0.326152 0.334339 + outer loop + vertex -894.353 300.8 42.7682 + vertex -895.385 299.264 38.5424 + vertex -891.525 293.072 42.7099 + endloop + endfacet + facet normal -0.884601 -0.328894 0.330619 + outer loop + vertex -891.525 293.072 42.7099 + vertex -895.385 299.264 38.5424 + vertex -892.525 291.485 38.4539 + endloop + endfacet + facet normal -0.911123 -0.258034 0.321363 + outer loop + vertex -896.597 308.795 42.8254 + vertex -897.654 307.268 38.6029 + vertex -894.353 300.8 42.7682 + endloop + endfacet + facet normal -0.911708 -0.260918 0.317349 + outer loop + vertex -894.353 300.8 42.7682 + vertex -897.654 307.268 38.6029 + vertex -895.385 299.264 38.5424 + endloop + endfacet + facet normal -0.93355 -0.185917 0.306463 + outer loop + vertex -898.211 316.995 42.8837 + vertex -899.298 315.493 38.6626 + vertex -896.597 308.795 42.8254 + endloop + endfacet + facet normal -0.934347 -0.188903 0.302176 + outer loop + vertex -896.597 308.795 42.8254 + vertex -899.298 315.493 38.6626 + vertex -897.654 307.268 38.6029 + endloop + endfacet + facet normal -0.949807 -0.113301 0.291597 + outer loop + vertex -899.198 325.353 42.917 + vertex -900.317 323.924 38.7163 + vertex -898.211 316.995 42.8837 + endloop + endfacet + facet normal -0.950976 -0.116808 0.286357 + outer loop + vertex -898.211 316.995 42.8837 + vertex -900.317 323.924 38.7163 + vertex -899.298 315.493 38.6626 + endloop + endfacet + facet normal -0.959763 -0.0491674 0.276473 + outer loop + vertex -899.619 333.834 42.963 + vertex -900.758 332.501 38.7711 + vertex -899.198 325.353 42.917 + endloop + endfacet + facet normal -0.960561 -0.051169 0.273322 + outer loop + vertex -899.198 325.353 42.917 + vertex -900.758 332.501 38.7711 + vertex -900.317 323.924 38.7163 + endloop + endfacet + facet normal -0.804137 -0.438395 0.401465 + outer loop + vertex -889.159 283.966 38.2963 + vertex -890.372 281.791 33.491 + vertex -885.377 276.728 37.9664 + endloop + endfacet + facet normal -0.804117 -0.436965 0.403061 + outer loop + vertex -885.377 276.728 37.9664 + vertex -890.372 281.791 33.491 + vertex -886.455 274.272 33.1544 + endloop + endfacet + facet normal -0.838346 -0.383502 0.38743 + outer loop + vertex -892.525 291.485 38.4539 + vertex -893.801 289.467 33.6964 + vertex -889.159 283.966 38.2963 + endloop + endfacet + facet normal -0.838433 -0.384858 0.385895 + outer loop + vertex -889.159 283.966 38.2963 + vertex -893.801 289.467 33.6964 + vertex -890.372 281.791 33.491 + endloop + endfacet + facet normal -0.869492 -0.323822 0.372992 + outer loop + vertex -895.385 299.264 38.5424 + vertex -896.708 297.368 33.8109 + vertex -892.525 291.485 38.4539 + endloop + endfacet + facet normal -0.869683 -0.325388 0.37118 + outer loop + vertex -892.525 291.485 38.4539 + vertex -896.708 297.368 33.8109 + vertex -893.801 289.467 33.6964 + endloop + endfacet + facet normal -0.896548 -0.256948 0.360804 + outer loop + vertex -897.654 307.268 38.6029 + vertex -899.013 305.398 33.8936 + vertex -895.385 299.264 38.5424 + endloop + endfacet + facet normal -0.897332 -0.261271 0.355714 + outer loop + vertex -895.385 299.264 38.5424 + vertex -899.013 305.398 33.8936 + vertex -896.708 297.368 33.8109 + endloop + endfacet + facet normal -0.91925 -0.18621 0.346851 + outer loop + vertex -899.298 315.493 38.6626 + vertex -900.684 313.594 33.968 + vertex -897.654 307.268 38.6029 + endloop + endfacet + facet normal -0.920364 -0.190747 0.341387 + outer loop + vertex -897.654 307.268 38.6029 + vertex -900.684 313.594 33.968 + vertex -899.013 305.398 33.8936 + endloop + endfacet + facet normal -0.936745 -0.115369 0.330453 + outer loop + vertex -900.317 323.924 38.7163 + vertex -901.736 322.04 34.0364 + vertex -899.298 315.493 38.6626 + endloop + endfacet + facet normal -0.938013 -0.11943 0.325374 + outer loop + vertex -899.298 315.493 38.6626 + vertex -901.736 322.04 34.0364 + vertex -900.684 313.594 33.968 + endloop + endfacet + facet normal -0.948728 -0.050807 0.311984 + outer loop + vertex -900.758 332.501 38.7711 + vertex -902.198 330.681 34.0982 + vertex -900.317 323.924 38.7163 + endloop + endfacet + facet normal -0.949525 -0.0529361 0.309193 + outer loop + vertex -900.317 323.924 38.7163 + vertex -902.198 330.681 34.0982 + vertex -901.736 322.04 34.0364 + endloop + endfacet + facet normal -0.551697 -0.535804 0.639175 + outer loop + vertex -860.229 233.398 25.4401 + vertex -857.531 230.963 25.7278 + vertex -858.028 234.308 28.1027 + endloop + endfacet + facet normal -0.549667 -0.530769 0.645097 + outer loop + vertex -855.655 228.495 25.2954 + vertex -854.705 230.597 27.834 + vertex -857.531 230.963 25.7278 + endloop + endfacet + facet normal -0.547828 -0.536922 0.64156 + outer loop + vertex -854.705 230.597 27.834 + vertex -858.028 234.308 28.1027 + vertex -857.531 230.963 25.7278 + endloop + endfacet + facet normal -0.564576 -0.528102 0.63432 + outer loop + vertex -866.183 239.644 25.3703 + vertex -862.828 236.544 25.7756 + vertex -863.764 240.478 28.2176 + endloop + endfacet + facet normal -0.556819 -0.528414 0.640883 + outer loop + vertex -860.229 233.398 25.4401 + vertex -858.028 234.308 28.1027 + vertex -862.828 236.544 25.7756 + endloop + endfacet + facet normal -0.556877 -0.529669 0.639796 + outer loop + vertex -858.028 234.308 28.1027 + vertex -863.764 240.478 28.2176 + vertex -862.828 236.544 25.7756 + endloop + endfacet + facet normal -0.575819 -0.500017 0.646851 + outer loop + vertex -872.079 245.81 24.9418 + vertex -868.89 242.765 25.4265 + vertex -869.901 245.589 26.7099 + endloop + endfacet + facet normal -0.575581 -0.51079 0.638592 + outer loop + vertex -866.183 239.644 25.3703 + vertex -863.764 240.478 28.2176 + vertex -868.89 242.765 25.4265 + endloop + endfacet + facet normal -0.575451 -0.50003 0.647168 + outer loop + vertex -869.901 245.589 26.7099 + vertex -868.89 242.765 25.4265 + vertex -863.764 240.478 28.2176 + endloop + endfacet + facet normal -0.602719 -0.496156 0.624947 + outer loop + vertex -876.264 253.602 27.0893 + vertex -876.905 252.291 25.4306 + vertex -872.995 249.709 27.1518 + endloop + endfacet + facet normal -0.6015 -0.490642 0.630451 + outer loop + vertex -872.995 249.709 27.1518 + vertex -876.905 252.291 25.4306 + vertex -874.145 248.703 25.2712 + endloop + endfacet + facet normal -0.586563 -0.508136 0.630668 + outer loop + vertex -872.995 249.709 27.1518 + vertex -874.145 248.703 25.2712 + vertex -869.901 245.589 26.7099 + endloop + endfacet + facet normal -0.579373 -0.488149 0.652715 + outer loop + vertex -869.901 245.589 26.7099 + vertex -874.145 248.703 25.2712 + vertex -872.079 245.81 24.9418 + endloop + endfacet + facet normal -0.637583 -0.472118 0.608763 + outer loop + vertex -881.244 260.283 27.1981 + vertex -882.053 259.275 25.5682 + vertex -878.949 257.006 27.0593 + endloop + endfacet + facet normal -0.636481 -0.467543 0.61343 + outer loop + vertex -878.949 257.006 27.0593 + vertex -882.053 259.275 25.5682 + vertex -879.613 255.849 25.4889 + endloop + endfacet + facet normal -0.619825 -0.483461 0.618128 + outer loop + vertex -878.949 257.006 27.0593 + vertex -879.613 255.849 25.4889 + vertex -876.264 253.602 27.0893 + endloop + endfacet + facet normal -0.619455 -0.481625 0.61993 + outer loop + vertex -876.264 253.602 27.0893 + vertex -879.613 255.849 25.4889 + vertex -876.905 252.291 25.4306 + endloop + endfacet + facet normal -0.67541 -0.448118 0.585672 + outer loop + vertex -885.622 267.086 27.4888 + vertex -886.479 266.109 25.7531 + vertex -883.471 263.645 27.3361 + endloop + endfacet + facet normal -0.673143 -0.439547 0.594708 + outer loop + vertex -883.471 263.645 27.3361 + vertex -886.479 266.109 25.7531 + vertex -884.314 262.672 25.6633 + endloop + endfacet + facet normal -0.656585 -0.459622 0.598034 + outer loop + vertex -883.471 263.645 27.3361 + vertex -884.314 262.672 25.6633 + vertex -881.244 260.283 27.1981 + endloop + endfacet + facet normal -0.654787 -0.452664 0.605268 + outer loop + vertex -881.244 260.283 27.1981 + vertex -884.314 262.672 25.6633 + vertex -882.053 259.275 25.5682 + endloop + endfacet + facet normal -0.713943 -0.418984 0.561015 + outer loop + vertex -889.714 274.239 27.7976 + vertex -890.574 273.239 25.9575 + vertex -887.701 270.636 27.6689 + endloop + endfacet + facet normal -0.71217 -0.412341 0.568145 + outer loop + vertex -887.701 270.636 27.6689 + vertex -890.574 273.239 25.9575 + vertex -888.564 269.626 25.8537 + endloop + endfacet + facet normal -0.694343 -0.435773 0.572704 + outer loop + vertex -887.701 270.636 27.6689 + vertex -888.564 269.626 25.8537 + vertex -885.622 267.086 27.4888 + endloop + endfacet + facet normal -0.692005 -0.427071 0.582013 + outer loop + vertex -885.622 267.086 27.4888 + vertex -888.564 269.626 25.8537 + vertex -886.479 266.109 25.7531 + endloop + endfacet + facet normal -0.752524 -0.378152 0.539174 + outer loop + vertex -893.407 281.661 28.063 + vertex -894.324 280.762 26.1519 + vertex -891.589 277.874 27.9441 + endloop + endfacet + facet normal -0.751161 -0.373824 0.54407 + outer loop + vertex -891.589 277.874 27.9441 + vertex -894.324 280.762 26.1519 + vertex -892.495 276.944 26.0547 + endloop + endfacet + facet normal -0.73375 -0.400481 0.54884 + outer loop + vertex -891.589 277.874 27.9441 + vertex -892.495 276.944 26.0547 + vertex -889.714 274.239 27.7976 + endloop + endfacet + facet normal -0.731922 -0.394067 0.555879 + outer loop + vertex -889.714 274.239 27.7976 + vertex -892.495 276.944 26.0547 + vertex -890.574 273.239 25.9575 + endloop + endfacet + facet normal -0.788067 -0.325331 0.522599 + outer loop + vertex -896.741 289.558 28.217 + vertex -897.67 288.734 26.3028 + vertex -895.134 285.559 28.1498 + endloop + endfacet + facet normal -0.787636 -0.324202 0.523949 + outer loop + vertex -895.134 285.559 28.1498 + vertex -897.67 288.734 26.3028 + vertex -896.056 284.693 26.2287 + endloop + endfacet + facet normal -0.771205 -0.353627 0.52933 + outer loop + vertex -895.134 285.559 28.1498 + vertex -896.056 284.693 26.2287 + vertex -893.407 281.661 28.063 + endloop + endfacet + facet normal -0.769813 -0.349567 0.534032 + outer loop + vertex -893.407 281.661 28.063 + vertex -896.056 284.693 26.2287 + vertex -894.324 280.762 26.1519 + endloop + endfacet + facet normal -0.817357 -0.269489 0.509218 + outer loop + vertex -899.532 297.745 28.3392 + vertex -900.472 297.008 26.44 + vertex -898.213 293.637 28.2814 + endloop + endfacet + facet normal -0.817306 -0.269379 0.509359 + outer loop + vertex -898.213 293.637 28.2814 + vertex -900.472 297.008 26.44 + vertex -899.147 292.853 26.368 + endloop + endfacet + facet normal -0.803845 -0.298306 0.514632 + outer loop + vertex -898.213 293.637 28.2814 + vertex -899.147 292.853 26.368 + vertex -896.741 289.558 28.217 + endloop + endfacet + facet normal -0.802943 -0.296166 0.51727 + outer loop + vertex -896.741 289.558 28.217 + vertex -899.147 292.853 26.368 + vertex -897.67 288.734 26.3028 + endloop + endfacet + facet normal -0.842232 -0.210243 0.49643 + outer loop + vertex -901.662 305.884 28.4581 + vertex -902.612 305.215 26.5644 + vertex -900.685 301.831 28.4003 + endloop + endfacet + facet normal -0.842234 -0.210248 0.496424 + outer loop + vertex -900.685 301.831 28.4003 + vertex -902.612 305.215 26.5644 + vertex -901.629 301.135 26.5035 + endloop + endfacet + facet normal -0.830322 -0.241836 0.502077 + outer loop + vertex -900.685 301.831 28.4003 + vertex -901.629 301.135 26.5035 + vertex -899.532 297.745 28.3392 + endloop + endfacet + facet normal -0.829601 -0.240363 0.503973 + outer loop + vertex -899.532 297.745 28.3392 + vertex -901.629 301.135 26.5035 + vertex -900.472 297.008 26.44 + endloop + endfacet + facet normal -0.863056 -0.143688 0.48424 + outer loop + vertex -903.137 314.058 28.5565 + vertex -904.078 313.403 26.6856 + vertex -902.479 309.942 28.508 + endloop + endfacet + facet normal -0.863225 -0.143969 0.483855 + outer loop + vertex -902.479 309.942 28.508 + vertex -904.078 313.403 26.6856 + vertex -903.423 309.289 26.6304 + endloop + endfacet + facet normal -0.853095 -0.177802 0.490526 + outer loop + vertex -902.479 309.942 28.508 + vertex -903.423 309.289 26.6304 + vertex -901.662 305.884 28.4581 + endloop + endfacet + facet normal -0.853126 -0.177859 0.49045 + outer loop + vertex -901.662 305.884 28.4581 + vertex -903.423 309.289 26.6304 + vertex -902.612 305.215 26.5644 + endloop + endfacet + facet normal -0.878067 -0.0787936 0.472006 + outer loop + vertex -904.008 322.57 28.6558 + vertex -904.95 321.898 26.7907 + vertex -903.649 318.268 28.6058 + endloop + endfacet + facet normal -0.878803 -0.0798305 0.47046 + outer loop + vertex -903.649 318.268 28.6058 + vertex -904.95 321.898 26.7907 + vertex -904.586 317.606 26.7427 + endloop + endfacet + facet normal -0.871318 -0.111401 0.477907 + outer loop + vertex -903.649 318.268 28.6058 + vertex -904.586 317.606 26.7427 + vertex -903.137 314.058 28.5565 + endloop + endfacet + facet normal -0.871572 -0.111787 0.477354 + outer loop + vertex -903.137 314.058 28.5565 + vertex -904.586 317.606 26.7427 + vertex -904.078 313.403 26.6856 + endloop + endfacet + facet normal -0.887735 -0.018243 0.459993 + outer loop + vertex -904.292 331.314 28.7373 + vertex -905.235 330.668 26.8905 + vertex -904.224 326.923 28.6929 + endloop + endfacet + facet normal -0.888519 -0.0192029 0.458437 + outer loop + vertex -904.224 326.923 28.6929 + vertex -905.235 330.668 26.8905 + vertex -905.166 326.265 26.84 + endloop + endfacet + facet normal -0.883454 -0.047919 0.466061 + outer loop + vertex -904.224 326.923 28.6929 + vertex -905.166 326.265 26.84 + vertex -904.008 322.57 28.6558 + endloop + endfacet + facet normal -0.88427 -0.0489922 0.464398 + outer loop + vertex -904.008 322.57 28.6558 + vertex -905.166 326.265 26.84 + vertex -904.95 321.898 26.7907 + endloop + endfacet + facet normal -0.897415 0.0330548 0.439947 + outer loop + vertex -904.055 340.058 28.8082 + vertex -904.978 339.436 26.9731 + vertex -904.233 335.695 28.7734 + endloop + endfacet + facet normal -0.896194 0.0344409 0.442323 + outer loop + vertex -904.233 335.695 28.7734 + vertex -904.978 339.436 26.9731 + vertex -905.167 335.065 26.9302 + endloop + endfacet + facet normal -0.893127 0.00820755 0.449731 + outer loop + vertex -904.233 335.695 28.7734 + vertex -905.167 335.065 26.9302 + vertex -904.292 331.314 28.7373 + endloop + endfacet + facet normal -0.891818 0.00974583 0.452289 + outer loop + vertex -904.292 331.314 28.7373 + vertex -905.167 335.065 26.9302 + vertex -905.235 330.668 26.8905 + endloop + endfacet + facet normal -0.90471 0.075669 0.419254 + outer loop + vertex -903.394 348.781 28.8766 + vertex -904.294 348.133 27.0503 + vertex -903.774 344.416 28.8437 + endloop + endfacet + facet normal -0.903192 0.0773114 0.422218 + outer loop + vertex -903.774 344.416 28.8437 + vertex -904.294 348.133 27.0503 + vertex -904.683 343.785 27.0142 + endloop + endfacet + facet normal -0.901548 0.0547061 0.429207 + outer loop + vertex -903.774 344.416 28.8437 + vertex -904.683 343.785 27.0142 + vertex -904.055 340.058 28.8082 + endloop + endfacet + facet normal -0.899608 0.0568501 0.432981 + outer loop + vertex -904.055 340.058 28.8082 + vertex -904.683 343.785 27.0142 + vertex -904.978 339.436 26.9731 + endloop + endfacet + facet normal -0.907865 0.112148 0.403986 + outer loop + vertex -902.382 357.523 28.9192 + vertex -903.266 356.886 27.1094 + vertex -902.927 353.156 28.9071 + endloop + endfacet + facet normal -0.907371 0.112659 0.404951 + outer loop + vertex -902.927 353.156 28.9071 + vertex -903.266 356.886 27.1094 + vertex -903.819 352.507 27.0888 + endloop + endfacet + facet normal -0.90665 0.0938811 0.411306 + outer loop + vertex -902.927 353.156 28.9071 + vertex -903.819 352.507 27.0888 + vertex -903.394 348.781 28.8766 + endloop + endfacet + facet normal -0.905786 0.0947904 0.412996 + outer loop + vertex -903.394 348.781 28.8766 + vertex -903.819 352.507 27.0888 + vertex -904.294 348.133 27.0503 + endloop + endfacet + facet normal -0.907651 0.144814 0.393953 + outer loop + vertex -901.023 366.4 28.9695 + vertex -901.93 365.7 27.1368 + vertex -901.755 361.914 28.9322 + endloop + endfacet + facet normal -0.907397 0.145061 0.394448 + outer loop + vertex -901.755 361.914 28.9322 + vertex -901.93 365.7 27.1368 + vertex -902.641 361.277 27.1294 + endloop + endfacet + facet normal -0.907341 0.12838 0.400313 + outer loop + vertex -901.755 361.914 28.9322 + vertex -902.641 361.277 27.1294 + vertex -902.382 357.523 28.9192 + endloop + endfacet + facet normal -0.908165 0.127557 0.398705 + outer loop + vertex -902.382 357.523 28.9192 + vertex -902.641 361.277 27.1294 + vertex -903.266 356.886 27.1094 + endloop + endfacet + facet normal -0.910141 0.168997 0.378262 + outer loop + vertex -899.123 376.02 29.3654 + vertex -900.15 375.054 27.3253 + vertex -900.161 371.071 29.0786 + endloop + endfacet + facet normal -0.907818 0.171033 0.382902 + outer loop + vertex -900.161 371.071 29.0786 + vertex -900.15 375.054 27.3253 + vertex -901.108 370.268 27.1922 + endloop + endfacet + facet normal -0.907827 0.158535 0.388223 + outer loop + vertex -900.161 371.071 29.0786 + vertex -901.108 370.268 27.1922 + vertex -901.023 366.4 28.9695 + endloop + endfacet + facet normal -0.907623 0.158722 0.388622 + outer loop + vertex -901.023 366.4 28.9695 + vertex -901.108 370.268 27.1922 + vertex -901.93 365.7 27.1368 + endloop + endfacet + facet normal -0.910173 0.1808 0.372688 + outer loop + vertex -900.15 375.054 27.3253 + vertex -899.123 376.02 29.3654 + vertex -899.065 380.077 27.5391 + endloop + endfacet + facet normal -0.917716 0.192605 0.347421 + outer loop + vertex -898.177 384.639 27.3535 + vertex -899.065 380.077 27.5391 + vertex -897.624 382.075 30.2367 + endloop + endfacet + facet normal -0.916478 0.175066 0.359749 + outer loop + vertex -899.065 380.077 27.5391 + vertex -899.123 376.02 29.3654 + vertex -897.624 382.075 30.2367 + endloop + endfacet + facet normal -0.917307 0.214386 0.335539 + outer loop + vertex -896.015 393.73 27.4759 + vertex -897.036 388.891 27.7761 + vertex -895.476 391.504 30.3727 + endloop + endfacet + facet normal -0.909431 0.208391 0.359871 + outer loop + vertex -898.177 384.639 27.3535 + vertex -897.624 382.075 30.2367 + vertex -897.036 388.891 27.7761 + endloop + endfacet + facet normal -0.916041 0.203762 0.345469 + outer loop + vertex -897.624 382.075 30.2367 + vertex -895.476 391.504 30.3727 + vertex -897.036 388.891 27.7761 + endloop + endfacet + facet normal -0.915932 0.233415 0.326476 + outer loop + vertex -893.751 402.601 27.4938 + vertex -894.822 397.916 27.8377 + vertex -893.258 400.438 30.4217 + endloop + endfacet + facet normal -0.909889 0.22937 0.345675 + outer loop + vertex -896.015 393.73 27.4759 + vertex -895.476 391.504 30.3727 + vertex -894.822 397.916 27.8377 + endloop + endfacet + facet normal -0.915255 0.225297 0.33399 + outer loop + vertex -895.476 391.504 30.3727 + vertex -893.258 400.438 30.4217 + vertex -894.822 397.916 27.8377 + endloop + endfacet + facet normal -0.913753 0.248684 0.321264 + outer loop + vertex -891.339 411.472 27.4983 + vertex -892.499 406.756 27.8502 + vertex -890.924 409.213 30.4261 + endloop + endfacet + facet normal -0.909899 0.245495 0.334389 + outer loop + vertex -893.751 402.601 27.4938 + vertex -893.258 400.438 30.4217 + vertex -892.499 406.756 27.8502 + endloop + endfacet + facet normal -0.913417 0.242784 0.326687 + outer loop + vertex -893.258 400.438 30.4217 + vertex -890.924 409.213 30.4261 + vertex -892.499 406.756 27.8502 + endloop + endfacet + facet normal -0.912487 0.25947 0.316295 + outer loop + vertex -888.82 420.297 27.5042 + vertex -890.03 415.619 27.8517 + vertex -888.49 417.893 30.4288 + endloop + endfacet + facet normal -0.908429 0.258789 0.328305 + outer loop + vertex -891.339 411.472 27.4983 + vertex -890.924 409.213 30.4261 + vertex -890.03 415.619 27.8517 + endloop + endfacet + facet normal -0.912411 0.255801 0.319486 + outer loop + vertex -890.924 409.213 30.4261 + vertex -888.49 417.893 30.4288 + vertex -890.03 415.619 27.8517 + endloop + endfacet + facet normal -0.911214 0.268643 0.312281 + outer loop + vertex -886.28 428.877 27.4998 + vertex -887.507 424.305 27.8539 + vertex -885.997 426.434 30.4275 + endloop + endfacet + facet normal -0.907152 0.26904 0.323561 + outer loop + vertex -888.82 420.297 27.5042 + vertex -888.49 417.893 30.4288 + vertex -887.507 424.305 27.8539 + endloop + endfacet + facet normal -0.911234 0.266014 0.314467 + outer loop + vertex -888.49 417.893 30.4288 + vertex -885.997 426.434 30.4275 + vertex -887.507 424.305 27.8539 + endloop + endfacet + facet normal -0.91108 0.272768 0.309082 + outer loop + vertex -883.678 437.509 27.5059 + vertex -884.951 432.861 27.8564 + vertex -883.451 434.951 30.4322 + endloop + endfacet + facet normal -0.90783 0.274598 0.316923 + outer loop + vertex -886.28 428.877 27.4998 + vertex -885.997 426.434 30.4275 + vertex -884.951 432.861 27.8564 + endloop + endfacet + facet normal -0.911091 0.272184 0.309562 + outer loop + vertex -885.997 426.434 30.4275 + vertex -883.451 434.951 30.4322 + vertex -884.951 432.861 27.8564 + endloop + endfacet + facet normal -0.911649 0.274515 0.30584 + outer loop + vertex -881.014 446.271 27.5067 + vertex -882.315 441.56 27.8575 + vertex -880.869 443.488 30.4363 + endloop + endfacet + facet normal -0.907886 0.278212 0.313594 + outer loop + vertex -883.678 437.509 27.5059 + vertex -883.451 434.951 30.4322 + vertex -882.315 441.56 27.8575 + endloop + endfacet + facet normal -0.911605 0.275526 0.30506 + outer loop + vertex -883.451 434.951 30.4322 + vertex -880.869 443.488 30.4363 + vertex -882.315 441.56 27.8575 + endloop + endfacet + facet normal -0.911858 0.274525 0.305207 + outer loop + vertex -878.416 454.843 27.5021 + vertex -879.684 450.23 27.8619 + vertex -878.317 451.919 30.4287 + endloop + endfacet + facet normal -0.90961 0.277837 0.308895 + outer loop + vertex -881.014 446.271 27.5067 + vertex -880.869 443.488 30.4363 + vertex -879.684 450.23 27.8619 + endloop + endfacet + facet normal -0.911732 0.276324 0.303956 + outer loop + vertex -880.869 443.488 30.4363 + vertex -878.317 451.919 30.4287 + vertex -879.684 450.23 27.8619 + endloop + endfacet + facet normal -0.91179 0.274729 0.305225 + outer loop + vertex -875.841 463.328 27.5182 + vertex -877.122 458.699 27.8568 + vertex -875.792 460.294 30.3954 + endloop + endfacet + facet normal -0.910231 0.2771 0.307724 + outer loop + vertex -878.416 454.843 27.5021 + vertex -878.317 451.919 30.4287 + vertex -877.122 458.699 27.8568 + endloop + endfacet + facet normal -0.911685 0.276069 0.304329 + outer loop + vertex -878.317 451.919 30.4287 + vertex -875.792 460.294 30.3954 + vertex -877.122 458.699 27.8568 + endloop + endfacet + facet normal -0.918036 0.271452 0.289005 + outer loop + vertex -873.335 471.462 27.6729 + vertex -874.516 467.234 27.8906 + vertex -873.282 468.855 30.2869 + endloop + endfacet + facet normal -0.909118 0.278802 0.309474 + outer loop + vertex -875.841 463.328 27.5182 + vertex -875.792 460.294 30.3954 + vertex -874.516 467.234 27.8906 + endloop + endfacet + facet normal -0.917945 0.272712 0.288106 + outer loop + vertex -875.792 460.294 30.3954 + vertex -873.282 468.855 30.2869 + vertex -874.516 467.234 27.8906 + endloop + endfacet + facet normal -0.930117 0.242778 0.275574 + outer loop + vertex -870.966 477.251 30.7068 + vertex -871.977 477.699 26.9008 + vertex -873.282 468.855 30.2869 + endloop + endfacet + facet normal -0.938184 0.235562 0.253617 + outer loop + vertex -873.282 468.855 30.2869 + vertex -871.977 477.699 26.9008 + vertex -873.335 471.462 27.6729 + endloop + endfacet + facet normal -0.957083 0.16103 0.24096 + outer loop + vertex -869.457 485.556 31.1534 + vertex -870.02 488.074 27.2322 + vertex -870.966 477.251 30.7068 + endloop + endfacet + facet normal -0.947285 0.170002 0.271571 + outer loop + vertex -870.966 477.251 30.7068 + vertex -870.02 488.074 27.2322 + vertex -871.977 477.699 26.9008 + endloop + endfacet + facet normal -0.421995 -0.455675 0.783761 + outer loop + vertex -856.763 227.09 23.5153 + vertex -857.924 225.801 22.1412 + vertex -855.836 225.799 23.2642 + endloop + endfacet + facet normal -0.413714 -0.488416 0.768304 + outer loop + vertex -855.836 225.799 23.2642 + vertex -857.924 225.801 22.1412 + vertex -856.533 224.99 22.3746 + endloop + endfacet + facet normal -0.454216 -0.440593 0.774316 + outer loop + vertex -860.895 231.868 23.8779 + vertex -862.138 230.557 22.4033 + vertex -858.432 229.215 23.8133 + endloop + endfacet + facet normal -0.454152 -0.440054 0.77466 + outer loop + vertex -858.432 229.215 23.8133 + vertex -862.138 230.557 22.4033 + vertex -859.708 227.907 22.3223 + endloop + endfacet + facet normal -0.439953 -0.454046 0.77478 + outer loop + vertex -858.432 229.215 23.8133 + vertex -859.708 227.907 22.3223 + vertex -856.763 227.09 23.5153 + endloop + endfacet + facet normal -0.43942 -0.439568 0.783384 + outer loop + vertex -856.763 227.09 23.5153 + vertex -859.708 227.907 22.3223 + vertex -857.924 225.801 22.1412 + endloop + endfacet + facet normal -0.465477 -0.432337 0.77228 + outer loop + vertex -866.718 238.047 23.8719 + vertex -867.91 236.745 22.4245 + vertex -863.739 234.86 23.8836 + endloop + endfacet + facet normal -0.465577 -0.432809 0.771955 + outer loop + vertex -863.739 234.86 23.8836 + vertex -867.91 236.745 22.4245 + vertex -864.978 233.569 22.4126 + endloop + endfacet + facet normal -0.45984 -0.438545 0.772156 + outer loop + vertex -863.739 234.86 23.8836 + vertex -864.978 233.569 22.4126 + vertex -860.895 231.868 23.8779 + endloop + endfacet + facet normal -0.459316 -0.435569 0.77415 + outer loop + vertex -860.895 231.868 23.8779 + vertex -864.978 233.569 22.4126 + vertex -862.138 230.557 22.4033 + endloop + endfacet + facet normal -0.470437 -0.404953 0.784029 + outer loop + vertex -872.572 244.545 23.7827 + vertex -873.629 243.315 22.5132 + vertex -869.69 241.288 23.8302 + endloop + endfacet + facet normal -0.473121 -0.41447 0.777413 + outer loop + vertex -869.69 241.288 23.8302 + vertex -873.629 243.315 22.5132 + vertex -870.805 240.003 22.4663 + endloop + endfacet + facet normal -0.468209 -0.419197 0.777852 + outer loop + vertex -869.69 241.288 23.8302 + vertex -870.805 240.003 22.4663 + vertex -866.718 238.047 23.8719 + endloop + endfacet + facet normal -0.470244 -0.427657 0.771997 + outer loop + vertex -866.718 238.047 23.8719 + vertex -870.805 240.003 22.4663 + vertex -867.91 236.745 22.4245 + endloop + endfacet + facet normal -0.482958 -0.399196 0.779355 + outer loop + vertex -877.894 251.199 23.9273 + vertex -879.067 250.131 22.6532 + vertex -875.299 247.811 23.7999 + endloop + endfacet + facet normal -0.479959 -0.391486 0.785097 + outer loop + vertex -875.299 247.811 23.7999 + vertex -879.067 250.131 22.6532 + vertex -876.391 246.69 22.5733 + endloop + endfacet + facet normal -0.472913 -0.39893 0.785626 + outer loop + vertex -875.299 247.811 23.7999 + vertex -876.391 246.69 22.5733 + vertex -872.572 244.545 23.7827 + endloop + endfacet + facet normal -0.473833 -0.401669 0.783674 + outer loop + vertex -872.572 244.545 23.7827 + vertex -876.391 246.69 22.5733 + vertex -873.629 243.315 22.5132 + endloop + endfacet + facet normal -0.508641 -0.378099 0.773515 + outer loop + vertex -882.984 258.226 24.1174 + vertex -884.139 257.167 22.8396 + vertex -880.505 254.718 24.0324 + endloop + endfacet + facet normal -0.507895 -0.376336 0.774863 + outer loop + vertex -880.505 254.718 24.0324 + vertex -884.139 257.167 22.8396 + vertex -881.658 253.634 22.7502 + endloop + endfacet + facet normal -0.495374 -0.390778 0.775821 + outer loop + vertex -880.505 254.718 24.0324 + vertex -881.658 253.634 22.7502 + vertex -877.894 251.199 23.9273 + endloop + endfacet + facet normal -0.493736 -0.386775 0.778864 + outer loop + vertex -877.894 251.199 23.9273 + vertex -881.658 253.634 22.7502 + vertex -879.067 250.131 22.6532 + endloop + endfacet + facet normal -0.532908 -0.353023 0.769015 + outer loop + vertex -887.508 265.212 24.2861 + vertex -888.714 264.262 23.0144 + vertex -885.307 261.713 24.2053 + endloop + endfacet + facet normal -0.531796 -0.350678 0.770855 + outer loop + vertex -885.307 261.713 24.2053 + vertex -888.714 264.262 23.0144 + vertex -886.49 260.706 22.9311 + endloop + endfacet + facet normal -0.519958 -0.365876 0.771867 + outer loop + vertex -885.307 261.713 24.2053 + vertex -886.49 260.706 22.9311 + vertex -882.984 258.226 24.1174 + endloop + endfacet + facet normal -0.51957 -0.365006 0.77254 + outer loop + vertex -882.984 258.226 24.1174 + vertex -886.49 260.706 22.9311 + vertex -884.139 257.167 22.8396 + endloop + endfacet + facet normal -0.555378 -0.324006 0.765882 + outer loop + vertex -891.625 272.392 24.4312 + vertex -892.853 271.526 23.1744 + vertex -889.61 268.76 24.3556 + endloop + endfacet + facet normal -0.554306 -0.32207 0.767474 + outer loop + vertex -889.61 268.76 24.3556 + vertex -892.853 271.526 23.1744 + vertex -890.832 267.858 23.0949 + endloop + endfacet + facet normal -0.543907 -0.33737 0.76834 + outer loop + vertex -889.61 268.76 24.3556 + vertex -890.832 267.858 23.0949 + vertex -887.508 265.212 24.2861 + endloop + endfacet + facet normal -0.544055 -0.337661 0.768108 + outer loop + vertex -887.508 265.212 24.2861 + vertex -890.832 267.858 23.0949 + vertex -888.714 264.262 23.0144 + endloop + endfacet + facet normal -0.585028 -0.294364 0.755706 + outer loop + vertex -895.391 279.994 24.5885 + vertex -896.621 279.203 23.3288 + vertex -893.552 276.131 24.5074 + endloop + endfacet + facet normal -0.581481 -0.288979 0.760507 + outer loop + vertex -893.552 276.131 24.5074 + vertex -896.621 279.203 23.3288 + vertex -894.782 275.301 23.2517 + endloop + endfacet + facet normal -0.569337 -0.308981 0.761831 + outer loop + vertex -893.552 276.131 24.5074 + vertex -894.782 275.301 23.2517 + vertex -891.625 272.392 24.4312 + endloop + endfacet + facet normal -0.567258 -0.305536 0.764765 + outer loop + vertex -891.625 272.392 24.4312 + vertex -894.782 275.301 23.2517 + vertex -892.853 271.526 23.1744 + endloop + endfacet + facet normal -0.611637 -0.25638 0.748444 + outer loop + vertex -898.745 288.065 24.7419 + vertex -899.977 287.371 23.4977 + vertex -897.127 283.974 24.6625 + endloop + endfacet + facet normal -0.60839 -0.252275 0.752475 + outer loop + vertex -897.127 283.974 24.6625 + vertex -899.977 287.371 23.4977 + vertex -898.36 283.231 23.4171 + endloop + endfacet + facet normal -0.596747 -0.274305 0.754088 + outer loop + vertex -897.127 283.974 24.6625 + vertex -898.36 283.231 23.4171 + vertex -895.391 279.994 24.5885 + endloop + endfacet + facet normal -0.5966 -0.274101 0.754279 + outer loop + vertex -895.391 279.994 24.5885 + vertex -898.36 283.231 23.4171 + vertex -896.621 279.203 23.3288 + endloop + endfacet + facet normal -0.632325 -0.21258 0.744967 + outer loop + vertex -901.547 296.426 24.8882 + vertex -902.773 295.822 23.6751 + vertex -900.223 292.231 24.8146 + endloop + endfacet + facet normal -0.632484 -0.212751 0.744782 + outer loop + vertex -900.223 292.231 24.8146 + vertex -902.773 295.822 23.6751 + vertex -901.454 291.587 23.5852 + endloop + endfacet + facet normal -0.62296 -0.234056 0.746418 + outer loop + vertex -900.223 292.231 24.8146 + vertex -901.454 291.587 23.5852 + vertex -898.745 288.065 24.7419 + endloop + endfacet + facet normal -0.622681 -0.233732 0.746751 + outer loop + vertex -898.745 288.065 24.7419 + vertex -901.454 291.587 23.5852 + vertex -899.977 287.371 23.4977 + endloop + endfacet + facet normal -0.654791 -0.168253 0.736845 + outer loop + vertex -903.68 304.714 25.0385 + vertex -904.892 304.181 23.8389 + vertex -902.701 300.595 24.9677 + endloop + endfacet + facet normal -0.653874 -0.167374 0.737858 + outer loop + vertex -902.701 300.595 24.9677 + vertex -904.892 304.181 23.8389 + vertex -903.921 300.027 23.7577 + endloop + endfacet + facet normal -0.644376 -0.192522 0.740078 + outer loop + vertex -902.701 300.595 24.9677 + vertex -903.921 300.027 23.7577 + vertex -901.547 296.426 24.8882 + endloop + endfacet + facet normal -0.641697 -0.189807 0.7431 + outer loop + vertex -901.547 296.426 24.8882 + vertex -903.921 300.027 23.7577 + vertex -902.773 295.822 23.6751 + endloop + endfacet + facet normal -0.677113 -0.117685 0.726408 + outer loop + vertex -905.133 312.949 25.1752 + vertex -906.33 312.487 23.9847 + vertex -904.486 308.814 25.1082 + endloop + endfacet + facet normal -0.675193 -0.116098 0.728447 + outer loop + vertex -904.486 308.814 25.1082 + vertex -906.33 312.487 23.9847 + vertex -905.692 308.32 23.9119 + endloop + endfacet + facet normal -0.666775 -0.143538 0.731306 + outer loop + vertex -904.486 308.814 25.1082 + vertex -905.692 308.32 23.9119 + vertex -903.68 304.714 25.0385 + endloop + endfacet + facet normal -0.664104 -0.141144 0.734196 + outer loop + vertex -903.68 304.714 25.0385 + vertex -905.692 308.32 23.9119 + vertex -904.892 304.181 23.8389 + endloop + endfacet + facet normal -0.691443 -0.0678238 0.719241 + outer loop + vertex -905.994 321.452 25.2909 + vertex -907.178 321.014 24.1113 + vertex -905.633 317.157 25.2329 + endloop + endfacet + facet normal -0.691844 -0.0681047 0.718828 + outer loop + vertex -905.633 317.157 25.2329 + vertex -907.178 321.014 24.1113 + vertex -906.821 316.717 24.0479 + endloop + endfacet + facet normal -0.686072 -0.0915546 0.72175 + outer loop + vertex -905.633 317.157 25.2329 + vertex -906.821 316.717 24.0479 + vertex -905.133 312.949 25.1752 + endloop + endfacet + facet normal -0.684563 -0.0904066 0.723326 + outer loop + vertex -905.133 312.949 25.1752 + vertex -906.821 316.717 24.0479 + vertex -906.33 312.487 23.9847 + endloop + endfacet + facet normal -0.701479 -0.0186255 0.712447 + outer loop + vertex -906.282 330.231 25.3865 + vertex -907.462 329.787 24.2127 + vertex -906.211 325.82 25.3406 + endloop + endfacet + facet normal -0.701695 -0.0187554 0.71223 + outer loop + vertex -906.211 325.82 25.3406 + vertex -907.462 329.787 24.2127 + vertex -907.395 325.384 24.1631 + endloop + endfacet + facet normal -0.6967 -0.0427413 0.716088 + outer loop + vertex -906.211 325.82 25.3406 + vertex -907.395 325.384 24.1631 + vertex -905.994 321.452 25.2909 + endloop + endfacet + facet normal -0.697088 -0.0429922 0.715695 + outer loop + vertex -905.994 321.452 25.2909 + vertex -907.395 325.384 24.1631 + vertex -907.178 321.014 24.1113 + endloop + endfacet + facet normal -0.702873 0.0235963 0.710924 + outer loop + vertex -906.018 339.041 25.4807 + vertex -907.227 338.577 24.3006 + vertex -906.213 334.648 25.4337 + endloop + endfacet + facet normal -0.70775 0.0209617 0.706152 + outer loop + vertex -906.213 334.648 25.4337 + vertex -907.227 338.577 24.3006 + vertex -907.399 334.186 24.2584 + endloop + endfacet + facet normal -0.704458 0.00338071 0.709738 + outer loop + vertex -906.213 334.648 25.4337 + vertex -907.399 334.186 24.2584 + vertex -906.282 330.231 25.3865 + endloop + endfacet + facet normal -0.705642 0.00271114 0.708563 + outer loop + vertex -906.282 330.231 25.3865 + vertex -907.399 334.186 24.2584 + vertex -907.462 329.787 24.2127 + endloop + endfacet + facet normal -0.701212 0.0581945 0.710574 + outer loop + vertex -905.305 347.75 25.5654 + vertex -906.538 347.341 24.3819 + vertex -905.71 343.402 25.5219 + endloop + endfacet + facet normal -0.701771 0.0579237 0.710044 + outer loop + vertex -905.71 343.402 25.5219 + vertex -906.538 347.341 24.3819 + vertex -906.94 342.961 24.3417 + endloop + endfacet + facet normal -0.699496 0.0426921 0.713361 + outer loop + vertex -905.71 343.402 25.5219 + vertex -906.94 342.961 24.3417 + vertex -906.018 339.041 25.4807 + endloop + endfacet + facet normal -0.705627 0.039541 0.70748 + outer loop + vertex -906.018 339.041 25.4807 + vertex -906.94 342.961 24.3417 + vertex -907.227 338.577 24.3006 + endloop + endfacet + facet normal -0.711287 0.087025 0.697494 + outer loop + vertex -904.244 356.507 25.6372 + vertex -905.448 356.141 24.4551 + vertex -904.813 352.115 25.6045 + endloop + endfacet + facet normal -0.70779 0.0885349 0.700853 + outer loop + vertex -904.813 352.115 25.6045 + vertex -905.448 356.141 24.4551 + vertex -906.034 351.731 24.4201 + endloop + endfacet + facet normal -0.70622 0.0732176 0.704196 + outer loop + vertex -904.813 352.115 25.6045 + vertex -906.034 351.731 24.4201 + vertex -905.305 347.75 25.5654 + endloop + endfacet + facet normal -0.703241 0.0745783 0.707029 + outer loop + vertex -905.305 347.75 25.5654 + vertex -906.034 351.731 24.4201 + vertex -906.538 347.341 24.3819 + endloop + endfacet + facet normal -0.714514 0.113361 0.690376 + outer loop + vertex -902.893 365.34 25.6742 + vertex -904.066 365.03 24.5113 + vertex -903.605 360.916 25.6635 + endloop + endfacet + facet normal -0.713387 0.113794 0.69147 + outer loop + vertex -903.605 360.916 25.6635 + vertex -904.066 365.03 24.5113 + vertex -904.795 360.573 24.4926 + endloop + endfacet + facet normal -0.71238 0.0990485 0.694769 + outer loop + vertex -903.605 360.916 25.6635 + vertex -904.795 360.573 24.4926 + vertex -904.244 356.507 25.6372 + endloop + endfacet + facet normal -0.712326 0.0990707 0.694822 + outer loop + vertex -904.244 356.507 25.6372 + vertex -904.795 360.573 24.4926 + vertex -905.448 356.141 24.4551 + endloop + endfacet + facet normal -0.722281 0.133476 0.678597 + outer loop + vertex -901.199 374.438 25.7406 + vertex -902.396 374.054 24.5427 + vertex -902.097 369.827 25.6923 + endloop + endfacet + facet normal -0.715425 0.135802 0.685364 + outer loop + vertex -902.097 369.827 25.6923 + vertex -902.396 374.054 24.5427 + vertex -903.271 369.514 24.5285 + endloop + endfacet + facet normal -0.714967 0.124062 0.688063 + outer loop + vertex -902.097 369.827 25.6923 + vertex -903.271 369.514 24.5285 + vertex -902.893 365.34 25.6742 + endloop + endfacet + facet normal -0.715006 0.124049 0.688025 + outer loop + vertex -902.893 365.34 25.6742 + vertex -903.271 369.514 24.5285 + vertex -904.066 365.03 24.5113 + endloop + endfacet + facet normal -0.737102 0.154857 0.657799 + outer loop + vertex -899.18 383.875 25.8607 + vertex -900.429 383.284 24.5996 + vertex -900.204 379.176 25.819 + endloop + endfacet + facet normal -0.733687 0.156088 0.661317 + outer loop + vertex -900.204 379.176 25.819 + vertex -900.429 383.284 24.5996 + vertex -901.442 378.66 24.5679 + endloop + endfacet + facet normal -0.732503 0.142849 0.665608 + outer loop + vertex -900.204 379.176 25.819 + vertex -901.442 378.66 24.5679 + vertex -901.199 374.438 25.7406 + endloop + endfacet + facet normal -0.72298 0.146075 0.675249 + outer loop + vertex -901.199 374.438 25.7406 + vertex -901.442 378.66 24.5679 + vertex -902.396 374.054 24.5427 + endloop + endfacet + facet normal -0.746969 0.175988 0.641143 + outer loop + vertex -897.03 392.925 25.9586 + vertex -898.284 392.371 24.6496 + vertex -898.124 388.41 25.9229 + endloop + endfacet + facet normal -0.745794 0.176435 0.642387 + outer loop + vertex -898.124 388.41 25.9229 + vertex -898.284 392.371 24.6496 + vertex -899.372 387.859 24.6251 + endloop + endfacet + facet normal -0.744896 0.164548 0.646571 + outer loop + vertex -898.124 388.41 25.9229 + vertex -899.372 387.859 24.6251 + vertex -899.18 383.875 25.8607 + endloop + endfacet + facet normal -0.738379 0.166977 0.653388 + outer loop + vertex -899.18 383.875 25.8607 + vertex -899.372 387.859 24.6251 + vertex -900.429 383.284 24.5996 + endloop + endfacet + facet normal -0.748849 0.19422 0.633644 + outer loop + vertex -894.765 401.813 25.9754 + vertex -896.01 401.29 24.6644 + vertex -895.912 397.392 25.9751 + endloop + endfacet + facet normal -0.750831 0.193459 0.631527 + outer loop + vertex -895.912 397.392 25.9751 + vertex -896.01 401.29 24.6644 + vertex -897.161 396.843 24.6582 + endloop + endfacet + facet normal -0.75039 0.185416 0.634457 + outer loop + vertex -895.912 397.392 25.9751 + vertex -897.161 396.843 24.6582 + vertex -897.03 392.925 25.9586 + endloop + endfacet + facet normal -0.747656 0.186473 0.637368 + outer loop + vertex -897.03 392.925 25.9586 + vertex -897.161 396.843 24.6582 + vertex -898.284 392.371 24.6496 + endloop + endfacet + facet normal -0.751457 0.206225 0.626725 + outer loop + vertex -892.345 410.731 25.9836 + vertex -893.572 410.252 24.6698 + vertex -893.579 406.251 25.9784 + endloop + endfacet + facet normal -0.751501 0.206209 0.626677 + outer loop + vertex -893.579 406.251 25.9784 + vertex -893.572 410.252 24.6698 + vertex -894.814 405.748 24.6631 + endloop + endfacet + facet normal -0.751343 0.200418 0.628742 + outer loop + vertex -893.579 406.251 25.9784 + vertex -894.814 405.748 24.6631 + vertex -894.765 401.813 25.9754 + endloop + endfacet + facet normal -0.749132 0.201237 0.631114 + outer loop + vertex -894.765 401.813 25.9754 + vertex -894.814 405.748 24.6631 + vertex -896.01 401.29 24.6644 + endloop + endfacet + facet normal -0.752419 0.216112 0.622223 + outer loop + vertex -889.788 419.683 25.9875 + vertex -890.98 419.3 24.6786 + vertex -891.073 415.225 25.9815 + endloop + endfacet + facet normal -0.751349 0.216462 0.623394 + outer loop + vertex -891.073 415.225 25.9815 + vertex -890.98 419.3 24.6786 + vertex -892.286 414.788 24.6723 + endloop + endfacet + facet normal -0.751365 0.212885 0.624604 + outer loop + vertex -891.073 415.225 25.9815 + vertex -892.286 414.788 24.6723 + vertex -892.345 410.731 25.9836 + endloop + endfacet + facet normal -0.75155 0.212823 0.624403 + outer loop + vertex -892.345 410.731 25.9836 + vertex -892.286 414.788 24.6723 + vertex -893.572 410.252 24.6698 + endloop + endfacet + facet normal -0.755047 0.225194 0.615786 + outer loop + vertex -887.222 428.351 25.9927 + vertex -888.371 428.077 24.6848 + vertex -888.506 424.051 25.9915 + endloop + endfacet + facet normal -0.755227 0.225135 0.615586 + outer loop + vertex -888.506 424.051 25.9915 + vertex -888.371 428.077 24.6848 + vertex -889.671 423.731 24.6787 + endloop + endfacet + facet normal -0.755448 0.221216 0.616735 + outer loop + vertex -888.506 424.051 25.9915 + vertex -889.671 423.731 24.6787 + vertex -889.788 419.683 25.9875 + endloop + endfacet + facet normal -0.752244 0.222265 0.620264 + outer loop + vertex -889.788 419.683 25.9875 + vertex -889.671 423.731 24.6787 + vertex -890.98 419.3 24.6786 + endloop + endfacet + facet normal -0.760178 0.23063 0.607404 + outer loop + vertex -884.601 437.015 25.9942 + vertex -885.718 436.781 24.6845 + vertex -885.925 432.652 25.9931 + endloop + endfacet + facet normal -0.758251 0.231224 0.609583 + outer loop + vertex -885.925 432.652 25.9931 + vertex -885.718 436.781 24.6845 + vertex -887.056 432.402 24.682 + endloop + endfacet + facet normal -0.758476 0.22867 0.610265 + outer loop + vertex -885.925 432.652 25.9931 + vertex -887.056 432.402 24.682 + vertex -887.222 428.351 25.9927 + endloop + endfacet + facet normal -0.75469 0.229882 0.61449 + outer loop + vertex -887.222 428.351 25.9927 + vertex -887.056 432.402 24.682 + vertex -888.371 428.077 24.6848 + endloop + endfacet + facet normal -0.766391 0.233307 0.598508 + outer loop + vertex -881.889 445.9 25.9936 + vertex -882.959 445.752 24.6816 + vertex -883.249 441.443 25.99 + endloop + endfacet + facet normal -0.762913 0.2343 0.60255 + outer loop + vertex -883.249 441.443 25.99 + vertex -882.959 445.752 24.6816 + vertex -884.345 441.243 24.6797 + endloop + endfacet + facet normal -0.763004 0.233492 0.602749 + outer loop + vertex -883.249 441.443 25.99 + vertex -884.345 441.243 24.6797 + vertex -884.601 437.015 25.9942 + endloop + endfacet + facet normal -0.759808 0.234437 0.606408 + outer loop + vertex -884.601 437.015 25.9942 + vertex -884.345 441.243 24.6797 + vertex -885.718 436.781 24.6845 + endloop + endfacet + facet normal -0.774529 0.236509 0.586659 + outer loop + vertex -879.232 454.626 25.9897 + vertex -880.223 454.637 24.6773 + vertex -880.547 450.305 25.9953 + endloop + endfacet + facet normal -0.771461 0.237397 0.590331 + outer loop + vertex -880.547 450.305 25.9953 + vertex -880.223 454.637 24.6773 + vertex -881.576 450.237 24.678 + endloop + endfacet + facet normal -0.771866 0.234972 0.590772 + outer loop + vertex -880.547 450.305 25.9953 + vertex -881.576 450.237 24.678 + vertex -881.889 445.9 25.9936 + endloop + endfacet + facet normal -0.765943 0.236665 0.597763 + outer loop + vertex -881.889 445.9 25.9936 + vertex -881.576 450.237 24.678 + vertex -882.959 445.752 24.6816 + endloop + endfacet + facet normal -0.78995 0.239527 0.564452 + outer loop + vertex -876.628 463.159 26.0082 + vertex -877.556 463.243 24.6746 + vertex -877.938 458.884 25.9895 + endloop + endfacet + facet normal -0.779904 0.242442 0.577038 + outer loop + vertex -877.938 458.884 25.9895 + vertex -877.556 463.243 24.6746 + vertex -878.891 458.954 24.6719 + endloop + endfacet + facet normal -0.781057 0.237335 0.577601 + outer loop + vertex -877.938 458.884 25.9895 + vertex -878.891 458.954 24.6719 + vertex -879.232 454.626 25.9897 + endloop + endfacet + facet normal -0.77395 0.239408 0.586246 + outer loop + vertex -879.232 454.626 25.9897 + vertex -878.891 458.954 24.6719 + vertex -880.223 454.637 24.6773 + endloop + endfacet + facet normal -0.819905 0.244903 0.517472 + outer loop + vertex -873.781 472.139 26.2185 + vertex -874.688 472.151 24.7767 + vertex -875.257 467.543 26.0555 + endloop + endfacet + facet normal -0.795066 0.251406 0.551965 + outer loop + vertex -875.257 467.543 26.0555 + vertex -874.688 472.151 24.7767 + vertex -876.169 467.61 24.7112 + endloop + endfacet + facet normal -0.796959 0.243346 0.552846 + outer loop + vertex -875.257 467.543 26.0555 + vertex -876.169 467.61 24.7112 + vertex -876.628 463.159 26.0082 + endloop + endfacet + facet normal -0.788503 0.245675 0.563832 + outer loop + vertex -876.628 463.159 26.0082 + vertex -876.169 467.61 24.7112 + vertex -877.556 463.243 24.6746 + endloop + endfacet + facet normal -0.816696 0.25922 0.515571 + outer loop + vertex -874.688 472.151 24.7767 + vertex -873.781 472.139 26.2185 + vertex -873.119 476.946 24.8509 + endloop + endfacet + facet normal -0.253261 -0.264721 0.930474 + outer loop + vertex -859.555 224.74 21.0507 + vertex -860.922 223.266 20.2595 + vertex -858.516 223.534 20.9907 + endloop + endfacet + facet normal -0.258515 -0.235217 0.936933 + outer loop + vertex -858.516 223.534 20.9907 + vertex -860.922 223.266 20.2595 + vertex -859.741 221.779 20.212 + endloop + endfacet + facet normal -0.312046 -0.313719 0.896776 + outer loop + vertex -858.516 223.534 20.9907 + vertex -857.658 224.575 21.6535 + vertex -859.555 224.74 21.0507 + endloop + endfacet + facet normal -0.308269 -0.408711 0.859026 + outer loop + vertex -857.924 225.801 22.1412 + vertex -859.555 224.74 21.0507 + vertex -857.658 224.575 21.6535 + endloop + endfacet + facet normal -0.284505 -0.336903 0.897526 + outer loop + vertex -857.658 224.575 21.6535 + vertex -858.516 223.534 20.9907 + vertex -857.361 224.074 21.5592 + endloop + endfacet + facet normal -0.298674 -0.311404 0.902121 + outer loop + vertex -857.361 224.074 21.5592 + vertex -858.516 223.534 20.9907 + vertex -857.439 223.553 21.3536 + endloop + endfacet + facet normal -0.279465 -0.277786 0.919094 + outer loop + vertex -863.509 229.217 21.2379 + vertex -864.799 227.586 20.3528 + vertex -861.1 226.616 21.1844 + endloop + endfacet + facet normal -0.277902 -0.269238 0.922107 + outer loop + vertex -861.1 226.616 21.1844 + vertex -864.799 227.586 20.3528 + vertex -862.486 225.088 20.3207 + endloop + endfacet + facet normal -0.369467 -0.36486 0.854617 + outer loop + vertex -862.138 230.557 22.4033 + vertex -863.509 229.217 21.2379 + vertex -859.708 227.907 22.3223 + endloop + endfacet + facet normal -0.368253 -0.358773 0.857713 + outer loop + vertex -859.708 227.907 22.3223 + vertex -863.509 229.217 21.2379 + vertex -861.1 226.616 21.1844 + endloop + endfacet + facet normal -0.354114 -0.373669 0.857307 + outer loop + vertex -859.708 227.907 22.3223 + vertex -861.1 226.616 21.1844 + vertex -857.924 225.801 22.1412 + endloop + endfacet + facet normal -0.351522 -0.351266 0.867781 + outer loop + vertex -857.924 225.801 22.1412 + vertex -861.1 226.616 21.1844 + vertex -859.555 224.74 21.0507 + endloop + endfacet + facet normal -0.263372 -0.28257 0.922382 + outer loop + vertex -861.1 226.616 21.1844 + vertex -862.486 225.088 20.3207 + vertex -859.555 224.74 21.0507 + endloop + endfacet + facet normal -0.262232 -0.256326 0.930339 + outer loop + vertex -859.555 224.74 21.0507 + vertex -862.486 225.088 20.3207 + vertex -860.922 223.266 20.2595 + endloop + endfacet + facet normal -0.282399 -0.264983 0.921973 + outer loop + vertex -869.349 235.475 21.2624 + vertex -870.753 233.902 20.3804 + vertex -866.385 232.26 21.246 + endloop + endfacet + facet normal -0.283239 -0.267779 0.920907 + outer loop + vertex -866.385 232.26 21.246 + vertex -870.753 233.902 20.3804 + vertex -867.707 230.628 20.3649 + endloop + endfacet + facet normal -0.379145 -0.35331 0.855232 + outer loop + vertex -867.91 236.745 22.4245 + vertex -869.349 235.475 21.2624 + vertex -864.978 233.569 22.4126 + endloop + endfacet + facet normal -0.37935 -0.35401 0.854852 + outer loop + vertex -864.978 233.569 22.4126 + vertex -869.349 235.475 21.2624 + vertex -866.385 232.26 21.246 + endloop + endfacet + facet normal -0.376177 -0.357408 0.854839 + outer loop + vertex -864.978 233.569 22.4126 + vertex -866.385 232.26 21.246 + vertex -862.138 230.557 22.4033 + endloop + endfacet + facet normal -0.376293 -0.357861 0.854599 + outer loop + vertex -862.138 230.557 22.4033 + vertex -866.385 232.26 21.246 + vertex -863.509 229.217 21.2379 + endloop + endfacet + facet normal -0.281936 -0.268878 0.920987 + outer loop + vertex -866.385 232.26 21.246 + vertex -867.707 230.628 20.3649 + vertex -863.509 229.217 21.2379 + endloop + endfacet + facet normal -0.2834 -0.274548 0.918862 + outer loop + vertex -863.509 229.217 21.2379 + vertex -867.707 230.628 20.3649 + vertex -864.799 227.586 20.3528 + endloop + endfacet + facet normal -0.287357 -0.264037 0.920712 + outer loop + vertex -874.987 242.049 21.403 + vertex -876.462 240.552 20.5136 + vertex -872.214 238.736 21.3186 + endloop + endfacet + facet normal -0.286357 -0.261204 0.921831 + outer loop + vertex -872.214 238.736 21.3186 + vertex -876.462 240.552 20.5136 + vertex -873.677 237.214 20.4329 + endloop + endfacet + facet normal -0.38452 -0.340058 0.858198 + outer loop + vertex -873.629 243.315 22.5132 + vertex -874.987 242.049 21.403 + vertex -870.805 240.003 22.4663 + endloop + endfacet + facet normal -0.386313 -0.345212 0.855331 + outer loop + vertex -870.805 240.003 22.4663 + vertex -874.987 242.049 21.403 + vertex -872.214 238.736 21.3186 + endloop + endfacet + facet normal -0.381833 -0.350185 0.855321 + outer loop + vertex -870.805 240.003 22.4663 + vertex -872.214 238.736 21.3186 + vertex -867.91 236.745 22.4245 + endloop + endfacet + facet normal -0.381861 -0.350271 0.855273 + outer loop + vertex -867.91 236.745 22.4245 + vertex -872.214 238.736 21.3186 + vertex -869.349 235.475 21.2624 + endloop + endfacet + facet normal -0.282964 -0.264524 0.921932 + outer loop + vertex -872.214 238.736 21.3186 + vertex -873.677 237.214 20.4329 + vertex -869.349 235.475 21.2624 + endloop + endfacet + facet normal -0.28295 -0.264479 0.921949 + outer loop + vertex -869.349 235.475 21.2624 + vertex -873.677 237.214 20.4329 + vertex -870.753 233.902 20.3804 + endloop + endfacet + facet normal -0.296177 -0.252559 0.921137 + outer loop + vertex -880.401 248.922 21.584 + vertex -881.854 247.445 20.7119 + vertex -877.716 245.446 21.4941 + endloop + endfacet + facet normal -0.296687 -0.253813 0.920628 + outer loop + vertex -877.716 245.446 21.4941 + vertex -881.854 247.445 20.7119 + vertex -879.176 243.955 20.6129 + endloop + endfacet + facet normal -0.393513 -0.325986 0.859582 + outer loop + vertex -879.067 250.131 22.6532 + vertex -880.401 248.922 21.584 + vertex -876.391 246.69 22.5733 + endloop + endfacet + facet normal -0.393603 -0.326202 0.859458 + outer loop + vertex -876.391 246.69 22.5733 + vertex -880.401 248.922 21.584 + vertex -877.716 245.446 21.4941 + endloop + endfacet + facet normal -0.387763 -0.332597 0.859662 + outer loop + vertex -876.391 246.69 22.5733 + vertex -877.716 245.446 21.4941 + vertex -873.629 243.315 22.5132 + endloop + endfacet + facet normal -0.38882 -0.335367 0.858107 + outer loop + vertex -873.629 243.315 22.5132 + vertex -877.716 245.446 21.4941 + vertex -874.987 242.049 21.403 + endloop + endfacet + facet normal -0.291584 -0.258931 0.920833 + outer loop + vertex -877.716 245.446 21.4941 + vertex -879.176 243.955 20.6129 + vertex -874.987 242.049 21.403 + endloop + endfacet + facet normal -0.291823 -0.259561 0.92058 + outer loop + vertex -874.987 242.049 21.403 + vertex -879.176 243.955 20.6129 + vertex -876.462 240.552 20.5136 + endloop + endfacet + facet normal -0.309341 -0.240688 0.919988 + outer loop + vertex -885.496 255.995 21.7645 + vertex -886.97 254.566 20.8949 + vertex -883.006 252.448 21.6738 + endloop + endfacet + facet normal -0.308859 -0.239623 0.920428 + outer loop + vertex -883.006 252.448 21.6738 + vertex -886.97 254.566 20.8949 + vertex -884.466 250.993 20.8053 + endloop + endfacet + facet normal -0.411078 -0.31042 0.85712 + outer loop + vertex -884.139 257.167 22.8396 + vertex -885.496 255.995 21.7645 + vertex -881.658 253.634 22.7502 + endloop + endfacet + facet normal -0.411133 -0.310539 0.85705 + outer loop + vertex -881.658 253.634 22.7502 + vertex -885.496 255.995 21.7645 + vertex -883.006 252.448 21.6738 + endloop + endfacet + facet normal -0.40209 -0.321162 0.857426 + outer loop + vertex -881.658 253.634 22.7502 + vertex -883.006 252.448 21.6738 + vertex -879.067 250.131 22.6532 + endloop + endfacet + facet normal -0.400637 -0.317891 0.859323 + outer loop + vertex -879.067 250.131 22.6532 + vertex -883.006 252.448 21.6738 + vertex -880.401 248.922 21.584 + endloop + endfacet + facet normal -0.302093 -0.246647 0.920818 + outer loop + vertex -883.006 252.448 21.6738 + vertex -884.466 250.993 20.8053 + vertex -880.401 248.922 21.584 + endloop + endfacet + facet normal -0.302068 -0.24659 0.920841 + outer loop + vertex -880.401 248.922 21.584 + vertex -884.466 250.993 20.8053 + vertex -881.854 247.445 20.7119 + endloop + endfacet + facet normal -0.31922 -0.222915 0.92109 + outer loop + vertex -890.09 263.139 21.9468 + vertex -891.585 261.731 21.088 + vertex -887.856 259.558 21.8542 + endloop + endfacet + facet normal -0.320069 -0.224623 0.92038 + outer loop + vertex -887.856 259.558 21.8542 + vertex -891.585 261.731 21.088 + vertex -889.342 258.138 20.9912 + endloop + endfacet + facet normal -0.428865 -0.2883 0.856129 + outer loop + vertex -888.714 264.262 23.0144 + vertex -890.09 263.139 21.9468 + vertex -886.49 260.706 22.9311 + endloop + endfacet + facet normal -0.429838 -0.290197 0.855 + outer loop + vertex -886.49 260.706 22.9311 + vertex -890.09 263.139 21.9468 + vertex -887.856 259.558 21.8542 + endloop + endfacet + facet normal -0.42077 -0.301536 0.855587 + outer loop + vertex -886.49 260.706 22.9311 + vertex -887.856 259.558 21.8542 + vertex -884.139 257.167 22.8396 + endloop + endfacet + facet normal -0.419905 -0.29976 0.856635 + outer loop + vertex -884.139 257.167 22.8396 + vertex -887.856 259.558 21.8542 + vertex -885.496 255.995 21.7645 + endloop + endfacet + facet normal -0.314022 -0.231224 0.920829 + outer loop + vertex -887.856 259.558 21.8542 + vertex -889.342 258.138 20.9912 + vertex -885.496 255.995 21.7645 + endloop + endfacet + facet normal -0.315423 -0.23418 0.919602 + outer loop + vertex -885.496 255.995 21.7645 + vertex -889.342 258.138 20.9912 + vertex -886.97 254.566 20.8949 + endloop + endfacet + facet normal -0.327728 -0.202298 0.92286 + outer loop + vertex -894.234 270.46 22.1333 + vertex -895.738 269.073 21.2951 + vertex -892.212 266.762 22.0407 + endloop + endfacet + facet normal -0.329445 -0.205333 0.921577 + outer loop + vertex -892.212 266.762 22.0407 + vertex -895.738 269.073 21.2951 + vertex -893.711 265.361 21.1926 + endloop + endfacet + facet normal -0.443302 -0.262843 0.85697 + outer loop + vertex -892.853 271.526 23.1744 + vertex -894.234 270.46 22.1333 + vertex -890.832 267.858 23.0949 + endloop + endfacet + facet normal -0.444159 -0.264292 0.85608 + outer loop + vertex -890.832 267.858 23.0949 + vertex -894.234 270.46 22.1333 + vertex -892.212 266.762 22.0407 + endloop + endfacet + facet normal -0.435619 -0.275776 0.856845 + outer loop + vertex -890.832 267.858 23.0949 + vertex -892.212 266.762 22.0407 + vertex -888.714 264.262 23.0144 + endloop + endfacet + facet normal -0.436821 -0.277974 0.855522 + outer loop + vertex -888.714 264.262 23.0144 + vertex -892.212 266.762 22.0407 + vertex -890.09 263.139 21.9468 + endloop + endfacet + facet normal -0.322742 -0.212902 0.922231 + outer loop + vertex -892.212 266.762 22.0407 + vertex -893.711 265.361 21.1926 + vertex -890.09 263.139 21.9468 + endloop + endfacet + facet normal -0.324765 -0.216745 0.920624 + outer loop + vertex -890.09 263.139 21.9468 + vertex -893.711 265.361 21.1926 + vertex -891.585 261.731 21.088 + endloop + endfacet + facet normal -0.332562 -0.177847 0.92616 + outer loop + vertex -898.007 278.201 22.3203 + vertex -899.527 276.849 21.5151 + vertex -896.165 274.266 22.226 + endloop + endfacet + facet normal -0.336177 -0.183198 0.923809 + outer loop + vertex -896.165 274.266 22.226 + vertex -899.527 276.849 21.5151 + vertex -897.676 272.893 21.4043 + endloop + endfacet + facet normal -0.456766 -0.232162 0.858758 + outer loop + vertex -896.621 279.203 23.3288 + vertex -898.007 278.201 22.3203 + vertex -894.782 275.301 23.2517 + endloop + endfacet + facet normal -0.459052 -0.235379 0.856661 + outer loop + vertex -894.782 275.301 23.2517 + vertex -898.007 278.201 22.3203 + vertex -896.165 274.266 22.226 + endloop + endfacet + facet normal -0.450523 -0.247785 0.85769 + outer loop + vertex -894.782 275.301 23.2517 + vertex -896.165 274.266 22.226 + vertex -892.853 271.526 23.1744 + endloop + endfacet + facet normal -0.452211 -0.250397 0.856041 + outer loop + vertex -892.853 271.526 23.1744 + vertex -896.165 274.266 22.226 + vertex -894.234 270.46 22.1333 + endloop + endfacet + facet normal -0.330251 -0.190157 0.92454 + outer loop + vertex -896.165 274.266 22.226 + vertex -897.676 272.893 21.4043 + vertex -894.234 270.46 22.1333 + endloop + endfacet + facet normal -0.33358 -0.195564 0.922214 + outer loop + vertex -894.234 270.46 22.1333 + vertex -897.676 272.893 21.4043 + vertex -895.738 269.073 21.2951 + endloop + endfacet + facet normal -0.340989 -0.15474 0.927244 + outer loop + vertex -901.369 286.441 22.5196 + vertex -902.912 285.15 21.7366 + vertex -899.748 282.265 22.4186 + endloop + endfacet + facet normal -0.343777 -0.158178 0.925633 + outer loop + vertex -899.748 282.265 22.4186 + vertex -902.912 285.15 21.7366 + vertex -901.279 280.942 21.624 + endloop + endfacet + facet normal -0.470072 -0.200335 0.859592 + outer loop + vertex -899.977 287.371 23.4977 + vertex -901.369 286.441 22.5196 + vertex -898.36 283.231 23.4171 + endloop + endfacet + facet normal -0.473643 -0.204506 0.856644 + outer loop + vertex -898.36 283.231 23.4171 + vertex -901.369 286.441 22.5196 + vertex -899.748 282.265 22.4186 + endloop + endfacet + facet normal -0.464374 -0.21929 0.858061 + outer loop + vertex -898.36 283.231 23.4171 + vertex -899.748 282.265 22.4186 + vertex -896.621 279.203 23.3288 + endloop + endfacet + facet normal -0.464839 -0.219886 0.857657 + outer loop + vertex -896.621 279.203 23.3288 + vertex -899.748 282.265 22.4186 + vertex -898.007 278.201 22.3203 + endloop + endfacet + facet normal -0.336906 -0.166747 0.926655 + outer loop + vertex -899.748 282.265 22.4186 + vertex -901.279 280.942 21.624 + vertex -898.007 278.201 22.3203 + endloop + endfacet + facet normal -0.339202 -0.169844 0.925254 + outer loop + vertex -898.007 278.201 22.3203 + vertex -901.279 280.942 21.624 + vertex -899.527 276.849 21.5151 + endloop + endfacet + facet normal -0.352551 -0.129443 0.926797 + outer loop + vertex -904.166 294.977 22.7139 + vertex -905.733 293.762 21.948 + vertex -902.847 290.698 22.6178 + endloop + endfacet + facet normal -0.35471 -0.131727 0.925651 + outer loop + vertex -902.847 290.698 22.6178 + vertex -905.733 293.762 21.948 + vertex -904.404 289.444 21.843 + endloop + endfacet + facet normal -0.487687 -0.17003 0.856301 + outer loop + vertex -902.773 295.822 23.6751 + vertex -904.166 294.977 22.7139 + vertex -901.454 291.587 23.5852 + endloop + endfacet + facet normal -0.486932 -0.169278 0.856879 + outer loop + vertex -901.454 291.587 23.5852 + vertex -904.166 294.977 22.7139 + vertex -902.847 290.698 22.6178 + endloop + endfacet + facet normal -0.477917 -0.18532 0.858634 + outer loop + vertex -901.454 291.587 23.5852 + vertex -902.847 290.698 22.6178 + vertex -899.977 287.371 23.4977 + endloop + endfacet + facet normal -0.478582 -0.186033 0.858109 + outer loop + vertex -899.977 287.371 23.4977 + vertex -902.847 290.698 22.6178 + vertex -901.369 286.441 22.5196 + endloop + endfacet + facet normal -0.347139 -0.14196 0.927007 + outer loop + vertex -902.847 290.698 22.6178 + vertex -904.404 289.444 21.843 + vertex -901.369 286.441 22.5196 + endloop + endfacet + facet normal -0.349125 -0.144213 0.925913 + outer loop + vertex -901.369 286.441 22.5196 + vertex -904.404 289.444 21.843 + vertex -902.912 285.15 21.7366 + endloop + endfacet + facet normal -0.366847 -0.103821 0.92447 + outer loop + vertex -906.276 303.405 22.8943 + vertex -907.856 302.28 22.1409 + vertex -905.31 299.216 22.8073 + endloop + endfacet + facet normal -0.366755 -0.103735 0.924516 + outer loop + vertex -905.31 299.216 22.8073 + vertex -907.856 302.28 22.1409 + vertex -906.886 298.042 22.0504 + endloop + endfacet + facet normal -0.505898 -0.13499 0.851965 + outer loop + vertex -904.892 304.181 23.8389 + vertex -906.276 303.405 22.8943 + vertex -903.921 300.027 23.7577 + endloop + endfacet + facet normal -0.505002 -0.134198 0.852622 + outer loop + vertex -903.921 300.027 23.7577 + vertex -906.276 303.405 22.8943 + vertex -905.31 299.216 22.8073 + endloop + endfacet + facet normal -0.496011 -0.15223 0.854868 + outer loop + vertex -903.921 300.027 23.7577 + vertex -905.31 299.216 22.8073 + vertex -902.773 295.822 23.6751 + endloop + endfacet + facet normal -0.496727 -0.152902 0.854332 + outer loop + vertex -902.773 295.822 23.6751 + vertex -905.31 299.216 22.8073 + vertex -904.166 294.977 22.7139 + endloop + endfacet + facet normal -0.357802 -0.11699 0.92644 + outer loop + vertex -905.31 299.216 22.8073 + vertex -906.886 298.042 22.0504 + vertex -904.166 294.977 22.7139 + endloop + endfacet + facet normal -0.359887 -0.119073 0.925366 + outer loop + vertex -904.166 294.977 22.7139 + vertex -906.886 298.042 22.0504 + vertex -905.733 293.762 21.948 + endloop + endfacet + facet normal -0.382418 -0.0744355 0.920986 + outer loop + vertex -907.7 311.797 23.0518 + vertex -909.276 310.759 22.3134 + vertex -907.069 307.586 22.9734 + endloop + endfacet + facet normal -0.382185 -0.07425 0.921098 + outer loop + vertex -907.069 307.586 22.9734 + vertex -909.276 310.759 22.3134 + vertex -908.649 306.496 22.2298 + endloop + endfacet + facet normal -0.526895 -0.095427 0.844556 + outer loop + vertex -906.33 312.487 23.9847 + vertex -907.7 311.797 23.0518 + vertex -905.692 308.32 23.9119 + endloop + endfacet + facet normal -0.525646 -0.0944867 0.84544 + outer loop + vertex -905.692 308.32 23.9119 + vertex -907.7 311.797 23.0518 + vertex -907.069 307.586 22.9734 + endloop + endfacet + facet normal -0.516848 -0.114727 0.848355 + outer loop + vertex -905.692 308.32 23.9119 + vertex -907.069 307.586 22.9734 + vertex -904.892 304.181 23.8389 + endloop + endfacet + facet normal -0.51579 -0.113857 0.849115 + outer loop + vertex -904.892 304.181 23.8389 + vertex -907.069 307.586 22.9734 + vertex -906.276 303.405 22.8943 + endloop + endfacet + facet normal -0.373571 -0.0883004 0.923389 + outer loop + vertex -907.069 307.586 22.9734 + vertex -908.649 306.496 22.2298 + vertex -906.276 303.405 22.8943 + endloop + endfacet + facet normal -0.37563 -0.090098 0.92238 + outer loop + vertex -906.276 303.405 22.8943 + vertex -908.649 306.496 22.2298 + vertex -907.856 302.28 22.1409 + endloop + endfacet + facet normal -0.396455 -0.0453958 0.916931 + outer loop + vertex -908.536 320.385 23.1847 + vertex -910.1 319.442 22.4617 + vertex -908.184 316.065 23.123 + endloop + endfacet + facet normal -0.397346 -0.0459821 0.916516 + outer loop + vertex -908.184 316.065 23.123 + vertex -910.1 319.442 22.4617 + vertex -909.753 315.079 22.3931 + endloop + endfacet + facet normal -0.544584 -0.0576056 0.836726 + outer loop + vertex -907.178 321.014 24.1113 + vertex -908.536 320.385 23.1847 + vertex -906.821 316.717 24.0479 + endloop + endfacet + facet normal -0.542284 -0.056156 0.838317 + outer loop + vertex -906.821 316.717 24.0479 + vertex -908.536 320.385 23.1847 + vertex -908.184 316.065 23.123 + endloop + endfacet + facet normal -0.535374 -0.0748224 0.841294 + outer loop + vertex -906.821 316.717 24.0479 + vertex -908.184 316.065 23.123 + vertex -906.33 312.487 23.9847 + endloop + endfacet + facet normal -0.535195 -0.0746991 0.841419 + outer loop + vertex -906.33 312.487 23.9847 + vertex -908.184 316.065 23.123 + vertex -907.7 311.797 23.0518 + endloop + endfacet + facet normal -0.389953 -0.0595311 0.918909 + outer loop + vertex -908.184 316.065 23.123 + vertex -909.753 315.079 22.3931 + vertex -907.7 311.797 23.0518 + endloop + endfacet + facet normal -0.390725 -0.0600872 0.918544 + outer loop + vertex -907.7 311.797 23.0518 + vertex -909.753 315.079 22.3931 + vertex -909.276 310.759 22.3134 + endloop + endfacet + facet normal -0.408852 -0.0173787 0.912435 + outer loop + vertex -908.814 329.207 23.2982 + vertex -910.399 328.45 22.5736 + vertex -908.756 324.772 23.2396 + endloop + endfacet + facet normal -0.40794 -0.0168959 0.912852 + outer loop + vertex -908.756 324.772 23.2396 + vertex -910.399 328.45 22.5736 + vertex -910.328 323.87 22.5205 + endloop + endfacet + facet normal -0.555039 -0.0178583 0.831633 + outer loop + vertex -907.462 329.787 24.2127 + vertex -908.814 329.207 23.2982 + vertex -907.395 325.384 24.1631 + endloop + endfacet + facet normal -0.555712 -0.0182117 0.831175 + outer loop + vertex -907.395 325.384 24.1631 + vertex -908.814 329.207 23.2982 + vertex -908.756 324.772 23.2396 + endloop + endfacet + facet normal -0.549559 -0.0370967 0.834631 + outer loop + vertex -907.395 325.384 24.1631 + vertex -908.756 324.772 23.2396 + vertex -907.178 321.014 24.1113 + endloop + endfacet + facet normal -0.55135 -0.0381338 0.833402 + outer loop + vertex -907.178 321.014 24.1113 + vertex -908.756 324.772 23.2396 + vertex -908.536 320.385 23.1847 + endloop + endfacet + facet normal -0.400777 -0.0315965 0.915631 + outer loop + vertex -908.756 324.772 23.2396 + vertex -910.328 323.87 22.5205 + vertex -908.536 320.385 23.1847 + endloop + endfacet + facet normal -0.40293 -0.0328926 0.914639 + outer loop + vertex -908.536 320.385 23.1847 + vertex -910.328 323.87 22.5205 + vertex -910.1 319.442 22.4617 + endloop + endfacet + facet normal -0.441311 0.00543237 0.897338 + outer loop + vertex -908.571 337.793 23.401 + vertex -909.783 336.671 22.8118 + vertex -908.705 333.525 23.3609 + endloop + endfacet + facet normal -0.423743 0.0129104 0.90569 + outer loop + vertex -908.705 333.525 23.3609 + vertex -909.783 336.671 22.8118 + vertex -910.21 333.029 22.6637 + endloop + endfacet + facet normal -0.561956 0.0140802 0.827047 + outer loop + vertex -907.227 338.577 24.3006 + vertex -908.571 337.793 23.401 + vertex -907.399 334.186 24.2584 + endloop + endfacet + facet normal -0.569976 0.01018 0.821598 + outer loop + vertex -907.399 334.186 24.2584 + vertex -908.571 337.793 23.401 + vertex -908.705 333.525 23.3609 + endloop + endfacet + facet normal -0.56635 -0.00047547 0.824165 + outer loop + vertex -907.399 334.186 24.2584 + vertex -908.705 333.525 23.3609 + vertex -907.462 329.787 24.2127 + endloop + endfacet + facet normal -0.561017 0.00212577 0.827801 + outer loop + vertex -907.462 329.787 24.2127 + vertex -908.705 333.525 23.3609 + vertex -908.814 329.207 23.2982 + endloop + endfacet + facet normal -0.41957 -0.00260161 0.907719 + outer loop + vertex -908.705 333.525 23.3609 + vertex -910.21 333.029 22.6637 + vertex -908.814 329.207 23.2982 + endloop + endfacet + facet normal -0.415479 -0.000794124 0.909603 + outer loop + vertex -908.814 329.207 23.2982 + vertex -910.21 333.029 22.6637 + vertex -910.399 328.45 22.5736 + endloop + endfacet + facet normal -0.39931 0.0246294 0.916485 + outer loop + vertex -908.034 346.576 23.4521 + vertex -909.58 345.201 22.8158 + vertex -908.369 342.149 23.4254 + endloop + endfacet + facet normal -0.409623 0.0196496 0.912043 + outer loop + vertex -908.369 342.149 23.4254 + vertex -909.58 345.201 22.8158 + vertex -909.972 340.982 22.7303 + endloop + endfacet + facet normal -0.542816 0.0421433 0.838793 + outer loop + vertex -906.538 347.341 24.3819 + vertex -908.034 346.576 23.4521 + vertex -906.94 342.961 24.3417 + endloop + endfacet + facet normal -0.554343 0.0368521 0.831472 + outer loop + vertex -906.94 342.961 24.3417 + vertex -908.034 346.576 23.4521 + vertex -908.369 342.149 23.4254 + endloop + endfacet + facet normal -0.551061 0.0282446 0.833987 + outer loop + vertex -906.94 342.961 24.3417 + vertex -908.369 342.149 23.4254 + vertex -907.227 338.577 24.3006 + endloop + endfacet + facet normal -0.564892 0.0215923 0.824882 + outer loop + vertex -907.227 338.577 24.3006 + vertex -908.369 342.149 23.4254 + vertex -908.571 337.793 23.401 + endloop + endfacet + facet normal -0.406049 0.0137229 0.913748 + outer loop + vertex -908.369 342.149 23.4254 + vertex -909.972 340.982 22.7303 + vertex -908.571 337.793 23.401 + endloop + endfacet + facet normal -0.435642 -0.00215009 0.900117 + outer loop + vertex -908.571 337.793 23.401 + vertex -909.972 340.982 22.7303 + vertex -909.783 336.671 22.8118 + endloop + endfacet + facet normal -0.396984 0.0449686 0.916723 + outer loop + vertex -906.966 355.523 23.5264 + vertex -908.593 354.455 22.8739 + vertex -907.554 351.037 23.4917 + endloop + endfacet + facet normal -0.389252 0.047892 0.919886 + outer loop + vertex -907.554 351.037 23.4917 + vertex -908.593 354.455 22.8739 + vertex -909.447 349.96 22.7467 + endloop + endfacet + facet normal -0.540012 0.0651334 0.839133 + outer loop + vertex -905.448 356.141 24.4551 + vertex -906.966 355.523 23.5264 + vertex -906.034 351.731 24.4201 + endloop + endfacet + facet normal -0.541551 0.0645321 0.838187 + outer loop + vertex -906.034 351.731 24.4201 + vertex -906.966 355.523 23.5264 + vertex -907.554 351.037 23.4917 + endloop + endfacet + facet normal -0.538578 0.0545126 0.84081 + outer loop + vertex -906.034 351.731 24.4201 + vertex -907.554 351.037 23.4917 + vertex -906.538 347.341 24.3819 + endloop + endfacet + facet normal -0.545955 0.0513842 0.836237 + outer loop + vertex -906.538 347.341 24.3819 + vertex -907.554 351.037 23.4917 + vertex -908.034 346.576 23.4521 + endloop + endfacet + facet normal -0.382182 0.032969 0.923499 + outer loop + vertex -907.554 351.037 23.4917 + vertex -909.447 349.96 22.7467 + vertex -908.034 346.576 23.4521 + endloop + endfacet + facet normal -0.399164 0.0244337 0.916554 + outer loop + vertex -908.034 346.576 23.4521 + vertex -909.447 349.96 22.7467 + vertex -909.58 345.201 22.8158 + endloop + endfacet + facet normal -0.397141 0.0584764 0.915893 + outer loop + vertex -905.566 364.493 23.5926 + vertex -907.203 363.576 22.9417 + vertex -906.302 359.998 23.5608 + endloop + endfacet + facet normal -0.385433 0.062244 0.920634 + outer loop + vertex -906.302 359.998 23.5608 + vertex -907.203 363.576 22.9417 + vertex -908.208 359.256 22.8129 + endloop + endfacet + facet normal -0.542226 0.0851884 0.835903 + outer loop + vertex -904.066 365.03 24.5113 + vertex -905.566 364.493 23.5926 + vertex -904.795 360.573 24.4926 + endloop + endfacet + facet normal -0.546985 0.0835759 0.83296 + outer loop + vertex -904.795 360.573 24.4926 + vertex -905.566 364.493 23.5926 + vertex -906.302 359.998 23.5608 + endloop + endfacet + facet normal -0.544585 0.0731655 0.835508 + outer loop + vertex -904.795 360.573 24.4926 + vertex -906.302 359.998 23.5608 + vertex -905.448 356.141 24.4551 + endloop + endfacet + facet normal -0.54228 0.0740059 0.836932 + outer loop + vertex -905.448 356.141 24.4551 + vertex -906.302 359.998 23.5608 + vertex -906.966 355.523 23.5264 + endloop + endfacet + facet normal -0.381423 0.0494814 0.923075 + outer loop + vertex -906.302 359.998 23.5608 + vertex -908.208 359.256 22.8129 + vertex -906.966 355.523 23.5264 + endloop + endfacet + facet normal -0.396157 0.0434461 0.917154 + outer loop + vertex -906.966 355.523 23.5264 + vertex -908.208 359.256 22.8129 + vertex -908.593 354.455 22.8739 + endloop + endfacet + facet normal -0.396355 0.0728542 0.915202 + outer loop + vertex -903.884 373.562 23.6303 + vertex -905.519 372.712 22.99 + vertex -904.759 369.014 23.6136 + endloop + endfacet + facet normal -0.385436 0.0758428 0.919612 + outer loop + vertex -904.759 369.014 23.6136 + vertex -905.519 372.712 22.99 + vertex -906.655 368.396 22.8697 + endloop + endfacet + facet normal -0.544291 0.102347 0.83263 + outer loop + vertex -902.396 374.054 24.5427 + vertex -903.884 373.562 23.6303 + vertex -903.271 369.514 24.5285 + endloop + endfacet + facet normal -0.54583 0.101902 0.831676 + outer loop + vertex -903.271 369.514 24.5285 + vertex -903.884 373.562 23.6303 + vertex -904.759 369.014 23.6136 + endloop + endfacet + facet normal -0.544195 0.0932225 0.833763 + outer loop + vertex -903.271 369.514 24.5285 + vertex -904.759 369.014 23.6136 + vertex -904.066 365.03 24.5113 + endloop + endfacet + facet normal -0.543924 0.0933076 0.833931 + outer loop + vertex -904.066 365.03 24.5113 + vertex -904.759 369.014 23.6136 + vertex -905.566 364.493 23.5926 + endloop + endfacet + facet normal -0.38244 0.0640486 0.921758 + outer loop + vertex -904.759 369.014 23.6136 + vertex -906.655 368.396 22.8697 + vertex -905.566 364.493 23.5926 + endloop + endfacet + facet normal -0.39729 0.0588038 0.915807 + outer loop + vertex -905.566 364.493 23.5926 + vertex -906.655 368.396 22.8697 + vertex -907.203 363.576 22.9417 + endloop + endfacet + facet normal -0.398079 0.0843392 0.913466 + outer loop + vertex -901.94 382.726 23.6518 + vertex -903.579 381.9 23.0138 + vertex -902.941 378.141 23.639 + endloop + endfacet + facet normal -0.384324 0.0875991 0.919033 + outer loop + vertex -902.941 378.141 23.639 + vertex -903.579 381.9 23.0138 + vertex -904.826 377.579 22.9044 + endloop + endfacet + facet normal -0.558371 0.116609 0.821355 + outer loop + vertex -900.429 383.284 24.5996 + vertex -901.94 382.726 23.6518 + vertex -901.442 378.66 24.5679 + endloop + endfacet + facet normal -0.552243 0.118239 0.825256 + outer loop + vertex -901.442 378.66 24.5679 + vertex -901.94 382.726 23.6518 + vertex -902.941 378.141 23.639 + endloop + endfacet + facet normal -0.550638 0.109541 0.827526 + outer loop + vertex -901.442 378.66 24.5679 + vertex -902.941 378.141 23.639 + vertex -902.396 374.054 24.5427 + endloop + endfacet + facet normal -0.545819 0.11085 0.830538 + outer loop + vertex -902.396 374.054 24.5427 + vertex -902.941 378.141 23.639 + vertex -903.884 373.562 23.6303 + endloop + endfacet + facet normal -0.381906 0.0769182 0.920995 + outer loop + vertex -902.941 378.141 23.639 + vertex -904.826 377.579 22.9044 + vertex -903.884 373.562 23.6303 + endloop + endfacet + facet normal -0.396221 0.0725319 0.915286 + outer loop + vertex -903.884 373.562 23.6303 + vertex -904.826 377.579 22.9044 + vertex -905.519 372.712 22.99 + endloop + endfacet + facet normal -0.408662 0.0962627 0.907595 + outer loop + vertex -899.801 391.816 23.6754 + vertex -901.434 391.026 23.0237 + vertex -900.891 387.29 23.6643 + endloop + endfacet + facet normal -0.389732 0.100357 0.915444 + outer loop + vertex -900.891 387.29 23.6643 + vertex -901.434 391.026 23.0237 + vertex -902.768 386.755 22.9242 + endloop + endfacet + facet normal -0.569658 0.133028 0.811044 + outer loop + vertex -898.284 392.371 24.6496 + vertex -899.801 391.816 23.6754 + vertex -899.372 387.859 24.6251 + endloop + endfacet + facet normal -0.565195 0.134212 0.813967 + outer loop + vertex -899.372 387.859 24.6251 + vertex -899.801 391.816 23.6754 + vertex -900.891 387.29 23.6643 + endloop + endfacet + facet normal -0.563567 0.125672 0.816455 + outer loop + vertex -899.372 387.859 24.6251 + vertex -900.891 387.29 23.6643 + vertex -900.429 383.284 24.5996 + endloop + endfacet + facet normal -0.560294 0.126544 0.81857 + outer loop + vertex -900.429 383.284 24.5996 + vertex -900.891 387.29 23.6643 + vertex -901.94 382.726 23.6518 + endloop + endfacet + facet normal -0.386801 0.0863911 0.918108 + outer loop + vertex -900.891 387.29 23.6643 + vertex -902.768 386.755 22.9242 + vertex -901.94 382.726 23.6518 + endloop + endfacet + facet normal -0.397688 0.0833635 0.913726 + outer loop + vertex -901.94 382.726 23.6518 + vertex -902.768 386.755 22.9242 + vertex -903.579 381.9 23.0138 + endloop + endfacet + facet normal -0.410722 0.105677 0.905616 + outer loop + vertex -897.508 400.787 23.6847 + vertex -899.123 400.057 23.0375 + vertex -898.672 396.309 23.6793 + endloop + endfacet + facet normal -0.394006 0.108888 0.912635 + outer loop + vertex -898.672 396.309 23.6793 + vertex -899.123 400.057 23.0375 + vertex -900.525 395.835 22.9359 + endloop + endfacet + facet normal -0.575624 0.147869 0.804234 + outer loop + vertex -896.01 401.29 24.6644 + vertex -897.508 400.787 23.6847 + vertex -897.161 396.843 24.6582 + endloop + endfacet + facet normal -0.574057 0.148265 0.80528 + outer loop + vertex -897.161 396.843 24.6582 + vertex -897.508 400.787 23.6847 + vertex -898.672 396.309 23.6793 + endloop + endfacet + facet normal -0.573093 0.142326 0.807036 + outer loop + vertex -897.161 396.843 24.6582 + vertex -898.672 396.309 23.6793 + vertex -898.284 392.371 24.6496 + endloop + endfacet + facet normal -0.571382 0.142774 0.80817 + outer loop + vertex -898.284 392.371 24.6496 + vertex -898.672 396.309 23.6793 + vertex -899.801 391.816 23.6754 + endloop + endfacet + facet normal -0.39199 0.0976363 0.914774 + outer loop + vertex -898.672 396.309 23.6793 + vertex -900.525 395.835 22.9359 + vertex -899.801 391.816 23.6754 + endloop + endfacet + facet normal -0.407673 0.0936221 0.908316 + outer loop + vertex -899.801 391.816 23.6754 + vertex -900.525 395.835 22.9359 + vertex -901.434 391.026 23.0237 + endloop + endfacet + facet normal -0.416884 0.113839 0.901803 + outer loop + vertex -895.046 409.797 23.6938 + vertex -896.638 409.105 23.0452 + vertex -896.3 405.275 23.6853 + endloop + endfacet + facet normal -0.397022 0.117017 0.910319 + outer loop + vertex -896.3 405.275 23.6853 + vertex -896.638 409.105 23.0452 + vertex -898.115 404.872 22.9456 + endloop + endfacet + facet normal -0.578595 0.15829 0.800107 + outer loop + vertex -893.572 410.252 24.6698 + vertex -895.046 409.797 23.6938 + vertex -894.814 405.748 24.6631 + endloop + endfacet + facet normal -0.577466 0.158539 0.800874 + outer loop + vertex -894.814 405.748 24.6631 + vertex -895.046 409.797 23.6938 + vertex -896.3 405.275 23.6853 + endloop + endfacet + facet normal -0.577022 0.155095 0.801867 + outer loop + vertex -894.814 405.748 24.6631 + vertex -896.3 405.275 23.6853 + vertex -896.01 401.29 24.6644 + endloop + endfacet + facet normal -0.576681 0.155177 0.802097 + outer loop + vertex -896.01 401.29 24.6644 + vertex -896.3 405.275 23.6853 + vertex -897.508 400.787 23.6847 + endloop + endfacet + facet normal -0.395463 0.106372 0.912301 + outer loop + vertex -896.3 405.275 23.6853 + vertex -898.115 404.872 22.9456 + vertex -897.508 400.787 23.6847 + endloop + endfacet + facet normal -0.409853 0.103149 0.906301 + outer loop + vertex -897.508 400.787 23.6847 + vertex -898.115 404.872 22.9456 + vertex -899.123 400.057 23.0375 + endloop + endfacet + facet normal -0.421103 0.122518 0.8987 + outer loop + vertex -892.423 418.899 23.7036 + vertex -893.991 418.222 23.061 + vertex -893.75 414.352 23.7015 + endloop + endfacet + facet normal -0.405529 0.124621 0.905547 + outer loop + vertex -893.75 414.352 23.7015 + vertex -893.991 418.222 23.061 + vertex -895.531 413.966 22.9571 + endloop + endfacet + facet normal -0.583799 0.167754 0.794378 + outer loop + vertex -890.98 419.3 24.6786 + vertex -892.423 418.899 23.7036 + vertex -892.286 414.788 24.6723 + endloop + endfacet + facet normal -0.57907 0.16868 0.797637 + outer loop + vertex -892.286 414.788 24.6723 + vertex -892.423 418.899 23.7036 + vertex -893.75 414.352 23.7015 + endloop + endfacet + facet normal -0.578528 0.163654 0.799076 + outer loop + vertex -892.286 414.788 24.6723 + vertex -893.75 414.352 23.7015 + vertex -893.572 410.252 24.6698 + endloop + endfacet + facet normal -0.579214 0.163514 0.798608 + outer loop + vertex -893.572 410.252 24.6698 + vertex -893.75 414.352 23.7015 + vertex -895.046 409.797 23.6938 + endloop + endfacet + facet normal -0.404007 0.113461 0.907692 + outer loop + vertex -893.75 414.352 23.7015 + vertex -895.531 413.966 22.9571 + vertex -895.046 409.797 23.6938 + endloop + endfacet + facet normal -0.416017 0.111154 0.902538 + outer loop + vertex -895.046 409.797 23.6938 + vertex -895.531 413.966 22.9571 + vertex -896.638 409.105 23.0452 + endloop + endfacet + facet normal -0.431895 0.130217 0.892474 + outer loop + vertex -889.76 427.779 23.7096 + vertex -891.277 427.189 23.0618 + vertex -891.091 423.38 23.7074 + endloop + endfacet + facet normal -0.41246 0.132654 0.901266 + outer loop + vertex -891.091 423.38 23.7074 + vertex -891.277 427.189 23.0618 + vertex -892.827 423.036 22.9636 + endloop + endfacet + facet normal -0.590455 0.175579 0.78774 + outer loop + vertex -888.371 428.077 24.6848 + vertex -889.76 427.779 23.7096 + vertex -889.671 423.731 24.6787 + endloop + endfacet + facet normal -0.585053 0.176606 0.791532 + outer loop + vertex -889.671 423.731 24.6787 + vertex -889.76 427.779 23.7096 + vertex -891.091 423.38 23.7074 + endloop + endfacet + facet normal -0.584809 0.17279 0.792554 + outer loop + vertex -889.671 423.731 24.6787 + vertex -891.091 423.38 23.7074 + vertex -890.98 419.3 24.6786 + endloop + endfacet + facet normal -0.584257 0.172896 0.792938 + outer loop + vertex -890.98 419.3 24.6786 + vertex -891.091 423.38 23.7074 + vertex -892.423 418.899 23.7036 + endloop + endfacet + facet normal -0.41116 0.121379 0.903446 + outer loop + vertex -891.091 423.38 23.7074 + vertex -892.827 423.036 22.9636 + vertex -892.423 418.899 23.7036 + endloop + endfacet + facet normal -0.420239 0.11978 0.899473 + outer loop + vertex -892.423 418.899 23.7036 + vertex -892.827 423.036 22.9636 + vertex -893.991 418.222 23.061 + endloop + endfacet + facet normal -0.442383 0.137057 0.886292 + outer loop + vertex -887.062 436.531 23.7057 + vertex -888.528 435.999 23.0564 + vertex -888.423 432.137 23.7063 + endloop + endfacet + facet normal -0.420153 0.139414 0.89668 + outer loop + vertex -888.423 432.137 23.7063 + vertex -888.528 435.999 23.0564 + vertex -890.087 431.902 22.9631 + endloop + endfacet + facet normal -0.600696 0.183005 0.77825 + outer loop + vertex -885.718 436.781 24.6845 + vertex -887.062 436.531 23.7057 + vertex -887.056 432.402 24.682 + endloop + endfacet + facet normal -0.594394 0.184096 0.782818 + outer loop + vertex -887.056 432.402 24.682 + vertex -887.062 436.531 23.7057 + vertex -888.423 432.137 23.7063 + endloop + endfacet + facet normal -0.594344 0.181238 0.783523 + outer loop + vertex -887.056 432.402 24.682 + vertex -888.423 432.137 23.7063 + vertex -888.371 428.077 24.6848 + endloop + endfacet + facet normal -0.590683 0.181914 0.78613 + outer loop + vertex -888.371 428.077 24.6848 + vertex -888.423 432.137 23.7063 + vertex -889.76 427.779 23.7096 + endloop + endfacet + facet normal -0.41954 0.129469 0.898456 + outer loop + vertex -888.423 432.137 23.7063 + vertex -890.087 431.902 22.9631 + vertex -889.76 427.779 23.7096 + endloop + endfacet + facet normal -0.431183 0.127594 0.893197 + outer loop + vertex -889.76 427.779 23.7096 + vertex -890.087 431.902 22.9631 + vertex -891.277 427.189 23.0618 + endloop + endfacet + facet normal -0.456252 0.143835 0.878149 + outer loop + vertex -884.255 445.54 23.6996 + vertex -885.676 444.997 23.0498 + vertex -885.673 441.004 23.7055 + endloop + endfacet + facet normal -0.435267 0.145546 0.888459 + outer loop + vertex -885.673 441.004 23.7055 + vertex -885.676 444.997 23.0498 + vertex -887.275 440.794 22.9553 + endloop + endfacet + facet normal -0.612683 0.188039 0.767634 + outer loop + vertex -882.959 445.752 24.6816 + vertex -884.255 445.54 23.6996 + vertex -884.345 441.243 24.6797 + endloop + endfacet + facet normal -0.602775 0.189528 0.775075 + outer loop + vertex -884.345 441.243 24.6797 + vertex -884.255 445.54 23.6996 + vertex -885.673 441.004 23.7055 + endloop + endfacet + facet normal -0.602771 0.186307 0.775859 + outer loop + vertex -884.345 441.243 24.6797 + vertex -885.673 441.004 23.7055 + vertex -885.718 436.781 24.6845 + endloop + endfacet + facet normal -0.600726 0.186634 0.777365 + outer loop + vertex -885.718 436.781 24.6845 + vertex -885.673 441.004 23.7055 + vertex -887.062 436.531 23.7057 + endloop + endfacet + facet normal -0.434776 0.135091 0.890348 + outer loop + vertex -885.673 441.004 23.7055 + vertex -887.275 440.794 22.9553 + vertex -887.062 436.531 23.7057 + endloop + endfacet + facet normal -0.441684 0.134172 0.887081 + outer loop + vertex -887.062 436.531 23.7057 + vertex -887.275 440.794 22.9553 + vertex -888.528 435.999 23.0564 + endloop + endfacet + facet normal -0.477179 0.151076 0.865723 + outer loop + vertex -881.428 454.548 23.6966 + vertex -882.757 454.07 23.0473 + vertex -882.837 450.073 23.7005 + endloop + endfacet + facet normal -0.453568 0.152617 0.878057 + outer loop + vertex -882.837 450.073 23.7005 + vertex -882.757 454.07 23.0473 + vertex -884.362 449.87 22.9482 + endloop + endfacet + facet normal -0.627821 0.193242 0.753988 + outer loop + vertex -880.223 454.637 24.6773 + vertex -881.428 454.548 23.6966 + vertex -881.576 450.237 24.678 + endloop + endfacet + facet normal -0.61648 0.194874 0.762874 + outer loop + vertex -881.576 450.237 24.678 + vertex -881.428 454.548 23.6966 + vertex -882.837 450.073 23.7005 + endloop + endfacet + facet normal -0.616647 0.190761 0.763778 + outer loop + vertex -881.576 450.237 24.678 + vertex -882.837 450.073 23.7005 + vertex -882.959 445.752 24.6816 + endloop + endfacet + facet normal -0.612634 0.191347 0.766855 + outer loop + vertex -882.959 445.752 24.6816 + vertex -882.837 450.073 23.7005 + vertex -884.255 445.54 23.6996 + endloop + endfacet + facet normal -0.453116 0.141462 0.880156 + outer loop + vertex -882.837 450.073 23.7005 + vertex -884.362 449.87 22.9482 + vertex -884.255 445.54 23.6996 + endloop + endfacet + facet normal -0.455594 0.141187 0.87892 + outer loop + vertex -884.255 445.54 23.6996 + vertex -884.362 449.87 22.9482 + vertex -885.676 444.997 23.0498 + endloop + endfacet + facet normal -0.510787 0.16361 0.843996 + outer loop + vertex -878.647 463.274 23.6987 + vertex -879.832 462.932 23.0473 + vertex -880.041 458.934 23.6961 + endloop + endfacet + facet normal -0.479264 0.164892 0.862042 + outer loop + vertex -880.041 458.934 23.6961 + vertex -879.832 462.932 23.0473 + vertex -881.412 458.856 22.9485 + endloop + endfacet + facet normal -0.649997 0.201901 0.732626 + outer loop + vertex -877.556 463.243 24.6746 + vertex -878.647 463.274 23.6987 + vertex -878.891 458.954 24.6719 + endloop + endfacet + facet normal -0.635644 0.203785 0.7446 + outer loop + vertex -878.891 458.954 24.6719 + vertex -878.647 463.274 23.6987 + vertex -880.041 458.934 23.6961 + endloop + endfacet + facet normal -0.636451 0.1972 0.745682 + outer loop + vertex -878.891 458.954 24.6719 + vertex -880.041 458.934 23.6961 + vertex -880.223 454.637 24.6773 + endloop + endfacet + facet normal -0.627389 0.198484 0.752985 + outer loop + vertex -880.223 454.637 24.6773 + vertex -880.041 458.934 23.6961 + vertex -881.428 454.548 23.6966 + endloop + endfacet + facet normal -0.479695 0.151795 0.864205 + outer loop + vertex -880.041 458.934 23.6961 + vertex -881.412 458.856 22.9485 + vertex -881.428 454.548 23.6966 + endloop + endfacet + facet normal -0.47738 0.152003 0.86545 + outer loop + vertex -881.428 454.548 23.6966 + vertex -881.412 458.856 22.9485 + vertex -882.757 454.07 23.0473 + endloop + endfacet + facet normal -0.559309 0.183775 0.808332 + outer loop + vertex -875.712 472.088 23.7445 + vertex -876.77 471.749 23.0891 + vertex -877.219 467.63 23.7149 + endloop + endfacet + facet normal -0.519928 0.183426 0.834284 + outer loop + vertex -877.219 467.63 23.7149 + vertex -876.77 471.749 23.0891 + vertex -878.396 467.672 22.9723 + endloop + endfacet + facet normal -0.699454 0.218363 0.680501 + outer loop + vertex -874.688 472.151 24.7767 + vertex -875.712 472.088 23.7445 + vertex -876.169 467.61 24.7112 + endloop + endfacet + facet normal -0.668969 0.221511 0.709516 + outer loop + vertex -876.169 467.61 24.7112 + vertex -875.712 472.088 23.7445 + vertex -877.219 467.63 23.7149 + endloop + endfacet + facet normal -0.671274 0.207209 0.711657 + outer loop + vertex -876.169 467.61 24.7112 + vertex -877.219 467.63 23.7149 + vertex -877.556 463.243 24.6746 + endloop + endfacet + facet normal -0.648763 0.209821 0.731493 + outer loop + vertex -877.556 463.243 24.6746 + vertex -877.219 467.63 23.7149 + vertex -878.647 463.274 23.6987 + endloop + endfacet + facet normal -0.521814 0.167838 0.836385 + outer loop + vertex -877.219 467.63 23.7149 + vertex -878.396 467.672 22.9723 + vertex -878.647 463.274 23.6987 + endloop + endfacet + facet normal -0.511417 0.168287 0.842693 + outer loop + vertex -878.647 463.274 23.6987 + vertex -878.396 467.672 22.9723 + vertex -879.832 462.932 23.0473 + endloop + endfacet + facet normal -0.61699 0.217372 0.756355 + outer loop + vertex -872.599 481.376 23.6599 + vertex -873.542 480.865 23.0384 + vertex -874.135 476.695 23.7522 + endloop + endfacet + facet normal -0.57537 0.216962 0.788592 + outer loop + vertex -874.135 476.695 23.7522 + vertex -873.542 480.865 23.0384 + vertex -875.198 476.62 22.9977 + endloop + endfacet + facet normal -0.769213 0.248495 0.588695 + outer loop + vertex -871.808 481.558 24.6172 + vertex -872.599 481.376 23.6599 + vertex -873.119 476.946 24.8509 + endloop + endfacet + facet normal -0.738176 0.254545 0.624742 + outer loop + vertex -873.119 476.946 24.8509 + vertex -872.599 481.376 23.6599 + vertex -874.135 476.695 23.7522 + endloop + endfacet + facet normal -0.739867 0.232288 0.631379 + outer loop + vertex -873.119 476.946 24.8509 + vertex -874.135 476.695 23.7522 + vertex -874.688 472.151 24.7767 + endloop + endfacet + facet normal -0.696878 0.237303 0.676793 + outer loop + vertex -874.688 472.151 24.7767 + vertex -874.135 476.695 23.7522 + vertex -875.712 472.088 23.7445 + endloop + endfacet + facet normal -0.57695 0.196077 0.792895 + outer loop + vertex -874.135 476.695 23.7522 + vertex -875.198 476.62 22.9977 + vertex -875.712 472.088 23.7445 + endloop + endfacet + facet normal -0.56082 0.196139 0.80437 + outer loop + vertex -875.712 472.088 23.7445 + vertex -875.198 476.62 22.9977 + vertex -876.77 471.749 23.0891 + endloop + endfacet + facet normal -0.858742 0.0665428 0.508069 + outer loop + vertex -870.882 490.904 23.7635 + vertex -871.258 491.534 23.0455 + vertex -871.334 486.116 23.6258 + endloop + endfacet + facet normal -0.662062 0.0890525 0.74414 + outer loop + vertex -871.334 486.116 23.6258 + vertex -871.258 491.534 23.0455 + vertex -872.229 485.932 22.852 + endloop + endfacet + facet normal -0.920921 0.0688176 0.383625 + outer loop + vertex -870.541 490.071 24.7314 + vertex -870.882 490.904 23.7635 + vertex -870.772 485.621 24.9747 + endloop + endfacet + facet normal -0.910489 0.074346 0.406795 + outer loop + vertex -870.772 485.621 24.9747 + vertex -870.882 490.904 23.7635 + vertex -871.334 486.116 23.6258 + endloop + endfacet + facet normal -0.880732 0.186236 0.435461 + outer loop + vertex -870.772 485.621 24.9747 + vertex -871.334 486.116 23.6258 + vertex -871.808 481.558 24.6172 + endloop + endfacet + facet normal -0.772726 0.210535 0.598806 + outer loop + vertex -871.808 481.558 24.6172 + vertex -871.334 486.116 23.6258 + vertex -872.599 481.376 23.6599 + endloop + endfacet + facet normal -0.66445 0.182545 0.724695 + outer loop + vertex -871.334 486.116 23.6258 + vertex -872.229 485.932 22.852 + vertex -872.599 481.376 23.6599 + endloop + endfacet + facet normal -0.609488 0.186216 0.770616 + outer loop + vertex -872.599 481.376 23.6599 + vertex -872.229 485.932 22.852 + vertex -873.542 480.865 23.0384 + endloop + endfacet + facet normal -0.113455 -0.129515 0.985065 + outer loop + vertex -862.307 221.246 19.5987 + vertex -863.031 218.311 19.1295 + vertex -860.876 219.567 19.5429 + endloop + endfacet + facet normal -0.101646 -0.149295 0.983554 + outer loop + vertex -860.876 219.567 19.5429 + vertex -863.031 218.311 19.1295 + vertex -861.282 217.48 19.1841 + endloop + endfacet + facet normal -0.19225 -0.183458 0.964045 + outer loop + vertex -860.922 223.266 20.2595 + vertex -862.307 221.246 19.5987 + vertex -859.741 221.779 20.212 + endloop + endfacet + facet normal -0.189734 -0.193799 0.962519 + outer loop + vertex -859.741 221.779 20.212 + vertex -862.307 221.246 19.5987 + vertex -860.876 219.567 19.5429 + endloop + endfacet + facet normal -0.12962 -0.131317 0.98283 + outer loop + vertex -866.054 225.64 19.7027 + vertex -867.184 223.571 19.2773 + vertex -863.87 223.195 19.664 + endloop + endfacet + facet normal -0.127923 -0.113937 0.985218 + outer loop + vertex -863.87 223.195 19.664 + vertex -867.184 223.571 19.2773 + vertex -865.597 220.799 19.1626 + endloop + endfacet + facet normal -0.196536 -0.194388 0.961034 + outer loop + vertex -864.799 227.586 20.3528 + vertex -866.054 225.64 19.7027 + vertex -862.486 225.088 20.3207 + endloop + endfacet + facet normal -0.196065 -0.190325 0.961943 + outer loop + vertex -862.486 225.088 20.3207 + vertex -866.054 225.64 19.7027 + vertex -863.87 223.195 19.664 + endloop + endfacet + facet normal -0.189667 -0.195113 0.962267 + outer loop + vertex -862.486 225.088 20.3207 + vertex -863.87 223.195 19.664 + vertex -860.922 223.266 20.2595 + endloop + endfacet + facet normal -0.1903 -0.184836 0.964169 + outer loop + vertex -860.922 223.266 20.2595 + vertex -863.87 223.195 19.664 + vertex -862.307 221.246 19.5987 + endloop + endfacet + facet normal -0.113801 -0.124223 0.985707 + outer loop + vertex -863.87 223.195 19.664 + vertex -865.597 220.799 19.1626 + vertex -862.307 221.246 19.5987 + endloop + endfacet + facet normal -0.112986 -0.129637 0.985103 + outer loop + vertex -862.307 221.246 19.5987 + vertex -865.597 220.799 19.1626 + vertex -863.031 218.311 19.1295 + endloop + endfacet + facet normal -0.13156 -0.128706 0.982917 + outer loop + vertex -871.974 231.912 19.739 + vertex -872.823 229.718 19.3381 + vertex -868.883 228.618 19.7213 + endloop + endfacet + facet normal -0.129224 -0.11985 0.984346 + outer loop + vertex -868.883 228.618 19.7213 + vertex -872.823 229.718 19.3381 + vertex -870.328 226.376 19.2588 + endloop + endfacet + facet normal -0.197831 -0.188536 0.961934 + outer loop + vertex -870.753 233.902 20.3804 + vertex -871.974 231.912 19.739 + vertex -867.707 230.628 20.3649 + endloop + endfacet + facet normal -0.198612 -0.191494 0.961189 + outer loop + vertex -867.707 230.628 20.3649 + vertex -871.974 231.912 19.739 + vertex -868.883 228.618 19.7213 + endloop + endfacet + facet normal -0.197226 -0.192341 0.961305 + outer loop + vertex -867.707 230.628 20.3649 + vertex -868.883 228.618 19.7213 + vertex -864.799 227.586 20.3528 + endloop + endfacet + facet normal -0.197524 -0.193728 0.960965 + outer loop + vertex -864.799 227.586 20.3528 + vertex -868.883 228.618 19.7213 + vertex -866.054 225.64 19.7027 + endloop + endfacet + facet normal -0.123542 -0.123567 0.984616 + outer loop + vertex -868.883 228.618 19.7213 + vertex -870.328 226.376 19.2588 + vertex -866.054 225.64 19.7027 + endloop + endfacet + facet normal -0.125146 -0.13381 0.983073 + outer loop + vertex -866.054 225.64 19.7027 + vertex -870.328 226.376 19.2588 + vertex -867.184 223.571 19.2773 + endloop + endfacet + facet normal -0.128919 -0.129455 0.983169 + outer loop + vertex -877.871 238.691 19.8607 + vertex -878.871 236.579 19.4515 + vertex -875.003 235.291 19.7891 + endloop + endfacet + facet normal -0.126046 -0.120424 0.984688 + outer loop + vertex -875.003 235.291 19.7891 + vertex -878.871 236.579 19.4515 + vertex -876.367 233.027 19.3377 + endloop + endfacet + facet normal -0.197453 -0.188001 0.962116 + outer loop + vertex -876.462 240.552 20.5136 + vertex -877.871 238.691 19.8607 + vertex -873.677 237.214 20.4329 + endloop + endfacet + facet normal -0.196947 -0.186402 0.962531 + outer loop + vertex -873.677 237.214 20.4329 + vertex -877.871 238.691 19.8607 + vertex -875.003 235.291 19.7891 + endloop + endfacet + facet normal -0.195205 -0.187642 0.962645 + outer loop + vertex -873.677 237.214 20.4329 + vertex -875.003 235.291 19.7891 + vertex -870.753 233.902 20.3804 + endloop + endfacet + facet normal -0.195837 -0.189812 0.962091 + outer loop + vertex -870.753 233.902 20.3804 + vertex -875.003 235.291 19.7891 + vertex -871.974 231.912 19.739 + endloop + endfacet + facet normal -0.121295 -0.12333 0.984925 + outer loop + vertex -875.003 235.291 19.7891 + vertex -876.367 233.027 19.3377 + vertex -871.974 231.912 19.739 + endloop + endfacet + facet normal -0.123367 -0.13199 0.983544 + outer loop + vertex -871.974 231.912 19.739 + vertex -876.367 233.027 19.3377 + vertex -872.823 229.718 19.3381 + endloop + endfacet + facet normal -0.135319 -0.130755 0.982136 + outer loop + vertex -883.31 245.634 20.0505 + vertex -884.436 243.601 19.6246 + vertex -880.618 242.124 19.954 + endloop + endfacet + facet normal -0.131709 -0.121032 0.983872 + outer loop + vertex -880.618 242.124 19.954 + vertex -884.436 243.601 19.6246 + vertex -882.166 239.987 19.484 + endloop + endfacet + facet normal -0.205971 -0.185336 0.960847 + outer loop + vertex -881.854 247.445 20.7119 + vertex -883.31 245.634 20.0505 + vertex -879.176 243.955 20.6129 + endloop + endfacet + facet normal -0.205468 -0.183974 0.961216 + outer loop + vertex -879.176 243.955 20.6129 + vertex -883.31 245.634 20.0505 + vertex -880.618 242.124 19.954 + endloop + endfacet + facet normal -0.200532 -0.18796 0.961487 + outer loop + vertex -879.176 243.955 20.6129 + vertex -880.618 242.124 19.954 + vertex -876.462 240.552 20.5136 + endloop + endfacet + facet normal -0.199896 -0.186104 0.961981 + outer loop + vertex -876.462 240.552 20.5136 + vertex -880.618 242.124 19.954 + vertex -877.871 238.691 19.8607 + endloop + endfacet + facet normal -0.124461 -0.126343 0.984148 + outer loop + vertex -880.618 242.124 19.954 + vertex -882.166 239.987 19.484 + vertex -877.871 238.691 19.8607 + endloop + endfacet + facet normal -0.125791 -0.130975 0.983373 + outer loop + vertex -877.871 238.691 19.8607 + vertex -882.166 239.987 19.484 + vertex -878.871 236.579 19.4515 + endloop + endfacet + facet normal -0.142288 -0.125454 0.981843 + outer loop + vertex -888.462 252.802 20.2391 + vertex -889.651 250.819 19.8133 + vertex -885.937 249.204 20.1452 + endloop + endfacet + facet normal -0.138945 -0.117466 0.983309 + outer loop + vertex -885.937 249.204 20.1452 + vertex -889.651 250.819 19.8133 + vertex -887.559 247.14 19.6695 + endloop + endfacet + facet normal -0.215362 -0.17508 0.960711 + outer loop + vertex -886.97 254.566 20.8949 + vertex -888.462 252.802 20.2391 + vertex -884.466 250.993 20.8053 + endloop + endfacet + facet normal -0.215989 -0.176595 0.960293 + outer loop + vertex -884.466 250.993 20.8053 + vertex -888.462 252.802 20.2391 + vertex -885.937 249.204 20.1452 + endloop + endfacet + facet normal -0.211137 -0.180702 0.960608 + outer loop + vertex -884.466 250.993 20.8053 + vertex -885.937 249.204 20.1452 + vertex -881.854 247.445 20.7119 + endloop + endfacet + facet normal -0.211246 -0.18098 0.960532 + outer loop + vertex -881.854 247.445 20.7119 + vertex -885.937 249.204 20.1452 + vertex -883.31 245.634 20.0505 + endloop + endfacet + facet normal -0.131821 -0.123129 0.983597 + outer loop + vertex -885.937 249.204 20.1452 + vertex -887.559 247.14 19.6695 + vertex -883.31 245.634 20.0505 + endloop + endfacet + facet normal -0.134551 -0.13119 0.982184 + outer loop + vertex -883.31 245.634 20.0505 + vertex -887.559 247.14 19.6695 + vertex -884.436 243.601 19.6246 + endloop + endfacet + facet normal -0.148571 -0.121257 0.981439 + outer loop + vertex -893.121 260.011 20.4429 + vertex -894.393 258.101 20.0142 + vertex -890.856 256.399 20.3394 + endloop + endfacet + facet normal -0.14457 -0.112634 0.983063 + outer loop + vertex -890.856 256.399 20.3394 + vertex -894.393 258.101 20.0142 + vertex -892.545 254.419 19.8641 + endloop + endfacet + facet normal -0.220647 -0.16366 0.961525 + outer loop + vertex -891.585 261.731 21.088 + vertex -893.121 260.011 20.4429 + vertex -889.342 258.138 20.9912 + endloop + endfacet + facet normal -0.222042 -0.166723 0.960677 + outer loop + vertex -889.342 258.138 20.9912 + vertex -893.121 260.011 20.4429 + vertex -890.856 256.399 20.3394 + endloop + endfacet + facet normal -0.217824 -0.170508 0.960979 + outer loop + vertex -889.342 258.138 20.9912 + vertex -890.856 256.399 20.3394 + vertex -886.97 254.566 20.8949 + endloop + endfacet + facet normal -0.218586 -0.172272 0.960491 + outer loop + vertex -886.97 254.566 20.8949 + vertex -890.856 256.399 20.3394 + vertex -888.462 252.802 20.2391 + endloop + endfacet + facet normal -0.137371 -0.118847 0.983364 + outer loop + vertex -890.856 256.399 20.3394 + vertex -892.545 254.419 19.8641 + vertex -888.462 252.802 20.2391 + endloop + endfacet + facet normal -0.140333 -0.126654 0.98197 + outer loop + vertex -888.462 252.802 20.2391 + vertex -892.545 254.419 19.8641 + vertex -889.651 250.819 19.8133 + endloop + endfacet + facet normal -0.153028 -0.113808 0.981647 + outer loop + vertex -897.312 267.373 20.659 + vertex -898.656 265.513 20.2337 + vertex -895.269 263.655 20.5464 + endloop + endfacet + facet normal -0.149468 -0.1071 0.982949 + outer loop + vertex -895.269 263.655 20.5464 + vertex -898.656 265.513 20.2337 + vertex -897.036 261.771 20.0724 + endloop + endfacet + facet normal -0.226557 -0.150282 0.962334 + outer loop + vertex -895.738 269.073 21.2951 + vertex -897.312 267.373 20.659 + vertex -893.711 265.361 21.1926 + endloop + endfacet + facet normal -0.228941 -0.154891 0.961039 + outer loop + vertex -893.711 265.361 21.1926 + vertex -897.312 267.373 20.659 + vertex -895.269 263.655 20.5464 + endloop + endfacet + facet normal -0.224428 -0.159151 0.961407 + outer loop + vertex -893.711 265.361 21.1926 + vertex -895.269 263.655 20.5464 + vertex -891.585 261.731 21.088 + endloop + endfacet + facet normal -0.22477 -0.159861 0.961209 + outer loop + vertex -891.585 261.731 21.088 + vertex -895.269 263.655 20.5464 + vertex -893.121 260.011 20.4429 + endloop + endfacet + facet normal -0.143633 -0.112638 0.9832 + outer loop + vertex -895.269 263.655 20.5464 + vertex -897.036 261.771 20.0724 + vertex -893.121 260.011 20.4429 + endloop + endfacet + facet normal -0.147633 -0.121897 0.981502 + outer loop + vertex -893.121 260.011 20.4429 + vertex -897.036 261.771 20.0724 + vertex -894.393 258.101 20.0142 + endloop + endfacet + facet normal -0.161556 -0.105148 0.981246 + outer loop + vertex -901.135 275.172 20.89 + vertex -902.54 273.32 20.4603 + vertex -899.267 271.202 20.7722 + endloop + endfacet + facet normal -0.15755 -0.0987651 0.98256 + outer loop + vertex -899.267 271.202 20.7722 + vertex -902.54 273.32 20.4603 + vertex -901.097 269.386 20.2961 + endloop + endfacet + facet normal -0.232627 -0.135838 0.963033 + outer loop + vertex -899.527 276.849 21.5151 + vertex -901.135 275.172 20.89 + vertex -897.676 272.893 21.4043 + endloop + endfacet + facet normal -0.234525 -0.138922 0.962132 + outer loop + vertex -897.676 272.893 21.4043 + vertex -901.135 275.172 20.89 + vertex -899.267 271.202 20.7722 + endloop + endfacet + facet normal -0.229442 -0.143892 0.962627 + outer loop + vertex -897.676 272.893 21.4043 + vertex -899.267 271.202 20.7722 + vertex -895.738 269.073 21.2951 + endloop + endfacet + facet normal -0.230762 -0.146244 0.961957 + outer loop + vertex -895.738 269.073 21.2951 + vertex -899.267 271.202 20.7722 + vertex -897.312 267.373 20.659 + endloop + endfacet + facet normal -0.15055 -0.105912 0.982913 + outer loop + vertex -899.267 271.202 20.7722 + vertex -901.097 269.386 20.2961 + vertex -897.312 267.373 20.659 + endloop + endfacet + facet normal -0.154171 -0.112964 0.981565 + outer loop + vertex -897.312 267.373 20.659 + vertex -901.097 269.386 20.2961 + vertex -898.656 265.513 20.2337 + endloop + endfacet + facet normal -0.168871 -0.0936477 0.981179 + outer loop + vertex -904.565 283.513 21.1248 + vertex -906.027 281.673 20.6977 + vertex -902.911 279.281 21.0058 + endloop + endfacet + facet normal -0.165735 -0.0894425 0.982106 + outer loop + vertex -902.911 279.281 21.0058 + vertex -906.027 281.673 20.6977 + vertex -904.785 277.495 20.5268 + endloop + endfacet + facet normal -0.239142 -0.118594 0.963715 + outer loop + vertex -902.912 285.15 21.7366 + vertex -904.565 283.513 21.1248 + vertex -901.279 280.942 21.624 + endloop + endfacet + facet normal -0.241225 -0.121426 0.962843 + outer loop + vertex -901.279 280.942 21.624 + vertex -904.565 283.513 21.1248 + vertex -902.911 279.281 21.0058 + endloop + endfacet + facet normal -0.236072 -0.126707 0.963439 + outer loop + vertex -901.279 280.942 21.624 + vertex -902.911 279.281 21.0058 + vertex -899.527 276.849 21.5151 + endloop + endfacet + facet normal -0.238363 -0.130108 0.962421 + outer loop + vertex -899.527 276.849 21.5151 + vertex -902.911 279.281 21.0058 + vertex -901.135 275.172 20.89 + endloop + endfacet + facet normal -0.15916 -0.0964549 0.98253 + outer loop + vertex -902.911 279.281 21.0058 + vertex -904.785 277.495 20.5268 + vertex -901.135 275.172 20.89 + endloop + endfacet + facet normal -0.163557 -0.103592 0.98108 + outer loop + vertex -901.135 275.172 20.89 + vertex -904.785 277.495 20.5268 + vertex -902.54 273.32 20.4603 + endloop + endfacet + facet normal -0.177713 -0.08035 0.980797 + outer loop + vertex -907.437 292.186 21.3497 + vertex -908.964 290.385 20.9254 + vertex -906.083 287.833 21.2382 + endloop + endfacet + facet normal -0.174994 -0.0771906 0.981539 + outer loop + vertex -906.083 287.833 21.2382 + vertex -908.964 290.385 20.9254 + vertex -907.997 286.077 20.759 + endloop + endfacet + facet normal -0.246633 -0.099379 0.964 + outer loop + vertex -905.733 293.762 21.948 + vertex -907.437 292.186 21.3497 + vertex -904.404 289.444 21.843 + endloop + endfacet + facet normal -0.248878 -0.102015 0.963147 + outer loop + vertex -904.404 289.444 21.843 + vertex -907.437 292.186 21.3497 + vertex -906.083 287.833 21.2382 + endloop + endfacet + facet normal -0.243104 -0.10833 0.963932 + outer loop + vertex -904.404 289.444 21.843 + vertex -906.083 287.833 21.2382 + vertex -902.912 285.15 21.7366 + endloop + endfacet + facet normal -0.245732 -0.11163 0.962889 + outer loop + vertex -902.912 285.15 21.7366 + vertex -906.083 287.833 21.2382 + vertex -904.565 283.513 21.1248 + endloop + endfacet + facet normal -0.168106 -0.0848555 0.98211 + outer loop + vertex -906.083 287.833 21.2382 + vertex -907.997 286.077 20.759 + vertex -904.565 283.513 21.1248 + endloop + endfacet + facet normal -0.172392 -0.0907718 0.980837 + outer loop + vertex -904.565 283.513 21.1248 + vertex -907.997 286.077 20.759 + vertex -906.027 281.673 20.6977 + endloop + endfacet + facet normal -0.187812 -0.0658046 0.979998 + outer loop + vertex -909.604 300.814 21.5536 + vertex -911.21 299.118 21.1321 + vertex -908.614 296.521 21.4551 + endloop + endfacet + facet normal -0.185105 -0.0630127 0.980697 + outer loop + vertex -908.614 296.521 21.4551 + vertex -911.21 299.118 21.1321 + vertex -910.576 294.845 20.9771 + endloop + endfacet + facet normal -0.257009 -0.0794319 0.963139 + outer loop + vertex -907.856 302.28 22.1409 + vertex -909.604 300.814 21.5536 + vertex -906.886 298.042 22.0504 + endloop + endfacet + facet normal -0.259372 -0.081899 0.962299 + outer loop + vertex -906.886 298.042 22.0504 + vertex -909.604 300.814 21.5536 + vertex -908.614 296.521 21.4551 + endloop + endfacet + facet normal -0.251869 -0.0908894 0.963484 + outer loop + vertex -906.886 298.042 22.0504 + vertex -908.614 296.521 21.4551 + vertex -905.733 293.762 21.948 + endloop + endfacet + facet normal -0.252999 -0.0921434 0.963069 + outer loop + vertex -905.733 293.762 21.948 + vertex -908.614 296.521 21.4551 + vertex -907.437 292.186 21.3497 + endloop + endfacet + facet normal -0.177543 -0.0720875 0.981469 + outer loop + vertex -908.614 296.521 21.4551 + vertex -910.576 294.845 20.9771 + vertex -907.437 292.186 21.3497 + endloop + endfacet + facet normal -0.181559 -0.0769852 0.980362 + outer loop + vertex -907.437 292.186 21.3497 + vertex -910.576 294.845 20.9771 + vertex -908.964 290.385 20.9254 + endloop + endfacet + facet normal -0.195509 -0.0490431 0.979475 + outer loop + vertex -911.049 309.404 21.7341 + vertex -912.728 307.819 21.3196 + vertex -910.415 305.086 21.6443 + endloop + endfacet + facet normal -0.19352 -0.0473027 0.979955 + outer loop + vertex -910.415 305.086 21.6443 + vertex -912.728 307.819 21.3196 + vertex -912.443 303.559 21.1702 + endloop + endfacet + facet normal -0.269448 -0.0584609 0.961239 + outer loop + vertex -909.276 310.759 22.3134 + vertex -911.049 309.404 21.7341 + vertex -908.649 306.496 22.2298 + endloop + endfacet + facet normal -0.270857 -0.0597035 0.960766 + outer loop + vertex -908.649 306.496 22.2298 + vertex -911.049 309.404 21.7341 + vertex -910.415 305.086 21.6443 + endloop + endfacet + facet normal -0.263269 -0.0698012 0.962194 + outer loop + vertex -908.649 306.496 22.2298 + vertex -910.415 305.086 21.6443 + vertex -907.856 302.28 22.1409 + endloop + endfacet + facet normal -0.264043 -0.0705541 0.961927 + outer loop + vertex -907.856 302.28 22.1409 + vertex -910.415 305.086 21.6443 + vertex -909.604 300.814 21.5536 + endloop + endfacet + facet normal -0.186924 -0.0563132 0.980759 + outer loop + vertex -910.415 305.086 21.6443 + vertex -912.443 303.559 21.1702 + vertex -909.604 300.814 21.5536 + endloop + endfacet + facet normal -0.19198 -0.0617244 0.979456 + outer loop + vertex -909.604 300.814 21.5536 + vertex -912.443 303.559 21.1702 + vertex -911.21 299.118 21.1321 + endloop + endfacet + facet normal -0.204736 -0.0331249 0.978257 + outer loop + vertex -911.863 318.217 21.8987 + vertex -913.571 316.757 21.4917 + vertex -911.524 313.788 21.8195 + endloop + endfacet + facet normal -0.201495 -0.030808 0.979005 + outer loop + vertex -911.524 313.788 21.8195 + vertex -913.571 316.757 21.4917 + vertex -913.596 312.402 21.3495 + endloop + endfacet + facet normal -0.280369 -0.0373625 0.959165 + outer loop + vertex -910.1 319.442 22.4617 + vertex -911.863 318.217 21.8987 + vertex -909.753 315.079 22.3931 + endloop + endfacet + facet normal -0.282202 -0.0386876 0.958574 + outer loop + vertex -909.753 315.079 22.3931 + vertex -911.863 318.217 21.8987 + vertex -911.524 313.788 21.8195 + endloop + endfacet + facet normal -0.275763 -0.0481578 0.960018 + outer loop + vertex -909.753 315.079 22.3931 + vertex -911.524 313.788 21.8195 + vertex -909.276 310.759 22.3134 + endloop + endfacet + facet normal -0.27644 -0.0486967 0.959796 + outer loop + vertex -909.276 310.759 22.3134 + vertex -911.524 313.788 21.8195 + vertex -911.049 309.404 21.7341 + endloop + endfacet + facet normal -0.195356 -0.0402887 0.979904 + outer loop + vertex -911.524 313.788 21.8195 + vertex -913.596 312.402 21.3495 + vertex -911.049 309.404 21.7341 + endloop + endfacet + facet normal -0.199865 -0.0442599 0.978823 + outer loop + vertex -911.049 309.404 21.7341 + vertex -913.596 312.402 21.3495 + vertex -912.728 307.819 21.3196 + endloop + endfacet + facet normal -0.209247 -0.0166367 0.977721 + outer loop + vertex -912.205 327.371 22.0174 + vertex -913.923 325.941 21.6252 + vertex -912.092 322.692 21.9619 + endloop + endfacet + facet normal -0.206642 -0.0151086 0.9783 + outer loop + vertex -912.092 322.692 21.9619 + vertex -913.923 325.941 21.6252 + vertex -914.147 321.469 21.5088 + endloop + endfacet + facet normal -0.285842 -0.0155341 0.958151 + outer loop + vertex -910.399 328.45 22.5736 + vertex -912.205 327.371 22.0174 + vertex -910.328 323.87 22.5205 + endloop + endfacet + facet normal -0.290695 -0.0183524 0.95664 + outer loop + vertex -910.328 323.87 22.5205 + vertex -912.205 327.371 22.0174 + vertex -912.092 322.692 21.9619 + endloop + endfacet + facet normal -0.285114 -0.0274005 0.958102 + outer loop + vertex -910.328 323.87 22.5205 + vertex -912.092 322.692 21.9619 + vertex -910.1 319.442 22.4617 + endloop + endfacet + facet normal -0.286291 -0.0281793 0.957728 + outer loop + vertex -910.1 319.442 22.4617 + vertex -912.092 322.692 21.9619 + vertex -911.863 318.217 21.8987 + endloop + endfacet + facet normal -0.201466 -0.0241388 0.979198 + outer loop + vertex -912.092 322.692 21.9619 + vertex -914.147 321.469 21.5088 + vertex -911.863 318.217 21.8987 + endloop + endfacet + facet normal -0.208123 -0.0289993 0.977673 + outer loop + vertex -911.863 318.217 21.8987 + vertex -914.147 321.469 21.5088 + vertex -913.571 316.757 21.4917 + endloop + endfacet + facet normal -0.219107 -0.00591437 0.975683 + outer loop + vertex -911.369 337.826 22.2845 + vertex -913.823 338.135 21.7353 + vertex -912.095 332.555 22.0895 + endloop + endfacet + facet normal -0.20838 -0.002443 0.978045 + outer loop + vertex -912.095 332.555 22.0895 + vertex -913.823 338.135 21.7353 + vertex -914.312 331.218 21.6138 + endloop + endfacet + facet normal -0.316351 -0.00143974 0.948641 + outer loop + vertex -909.783 336.671 22.8118 + vertex -911.369 337.826 22.2845 + vertex -910.21 333.029 22.6637 + endloop + endfacet + facet normal -0.292523 0.00491898 0.956246 + outer loop + vertex -910.21 333.029 22.6637 + vertex -911.369 337.826 22.2845 + vertex -912.095 332.555 22.0895 + endloop + endfacet + facet normal -0.289797 -0.00690125 0.957063 + outer loop + vertex -910.21 333.029 22.6637 + vertex -912.095 332.555 22.0895 + vertex -910.399 328.45 22.5736 + endloop + endfacet + facet normal -0.290435 -0.00718802 0.956868 + outer loop + vertex -910.399 328.45 22.5736 + vertex -912.095 332.555 22.0895 + vertex -912.205 327.371 22.0174 + endloop + endfacet + facet normal -0.204411 -0.00930778 0.978841 + outer loop + vertex -912.095 332.555 22.0895 + vertex -914.312 331.218 21.6138 + vertex -912.205 327.371 22.0174 + endloop + endfacet + facet normal -0.211748 -0.0134967 0.977231 + outer loop + vertex -912.205 327.371 22.0174 + vertex -914.312 331.218 21.6138 + vertex -913.923 325.941 21.6252 + endloop + endfacet + facet normal -0.312651 0.00420071 0.949859 + outer loop + vertex -909.783 336.671 22.8118 + vertex -909.972 340.982 22.7303 + vertex -911.369 337.826 22.2845 + endloop + endfacet + facet normal -0.217826 0.00475462 0.975976 + outer loop + vertex -913.823 338.135 21.7353 + vertex -911.369 337.826 22.2845 + vertex -912.004 345.982 22.103 + endloop + endfacet + facet normal -0.280063 0.00661944 0.959959 + outer loop + vertex -909.58 345.201 22.8158 + vertex -912.004 345.982 22.103 + vertex -909.972 340.982 22.7303 + endloop + endfacet + facet normal -0.299716 -0.00211201 0.954026 + outer loop + vertex -911.369 337.826 22.2845 + vertex -909.972 340.982 22.7303 + vertex -912.004 345.982 22.103 + endloop + endfacet + facet normal -0.275547 0.0216331 0.961044 + outer loop + vertex -909.58 345.201 22.8158 + vertex -909.447 349.96 22.7467 + vertex -912.004 345.982 22.103 + endloop + endfacet + facet normal -0.277309 0.0254793 0.960443 + outer loop + vertex -908.593 354.455 22.8739 + vertex -910.805 356.252 22.1876 + vertex -909.447 349.96 22.7467 + endloop + endfacet + facet normal -0.280123 0.0248009 0.959644 + outer loop + vertex -910.805 356.252 22.1876 + vertex -912.004 345.982 22.103 + vertex -909.447 349.96 22.7467 + endloop + endfacet + facet normal -0.270897 0.0339665 0.962009 + outer loop + vertex -908.593 354.455 22.8739 + vertex -908.208 359.256 22.8129 + vertex -910.805 356.252 22.1876 + endloop + endfacet + facet normal -0.281042 0.0368047 0.958989 + outer loop + vertex -907.203 363.576 22.9417 + vertex -909.307 365.679 22.2442 + vertex -908.208 359.256 22.8129 + endloop + endfacet + facet normal -0.275179 0.0379545 0.960643 + outer loop + vertex -909.307 365.679 22.2442 + vertex -910.805 356.252 22.1876 + vertex -908.208 359.256 22.8129 + endloop + endfacet + facet normal -0.273111 0.0453784 0.960912 + outer loop + vertex -907.203 363.576 22.9417 + vertex -906.655 368.396 22.8697 + vertex -909.307 365.679 22.2442 + endloop + endfacet + facet normal -0.281986 0.0475276 0.958241 + outer loop + vertex -905.519 372.712 22.99 + vertex -907.519 374.953 22.2904 + vertex -906.655 368.396 22.8697 + endloop + endfacet + facet normal -0.276036 0.04846 0.959925 + outer loop + vertex -907.519 374.953 22.2904 + vertex -909.307 365.679 22.2442 + vertex -906.655 368.396 22.8697 + endloop + endfacet + facet normal -0.273396 0.0558271 0.96028 + outer loop + vertex -905.519 372.712 22.99 + vertex -904.826 377.579 22.9044 + vertex -907.519 374.953 22.2904 + endloop + endfacet + facet normal -0.281033 0.0568147 0.958015 + outer loop + vertex -903.579 381.9 23.0138 + vertex -905.48 384.195 22.3202 + vertex -904.826 377.579 22.9044 + endloop + endfacet + facet normal -0.274966 0.0575657 0.959729 + outer loop + vertex -905.48 384.195 22.3202 + vertex -907.519 374.953 22.2904 + vertex -904.826 377.579 22.9044 + endloop + endfacet + facet normal -0.273624 0.0634714 0.95974 + outer loop + vertex -903.579 381.9 23.0138 + vertex -902.768 386.755 22.9242 + vertex -905.48 384.195 22.3202 + endloop + endfacet + facet normal -0.280354 0.0652216 0.957678 + outer loop + vertex -901.434 391.026 23.0237 + vertex -903.234 393.371 22.3371 + vertex -902.768 386.755 22.9242 + endloop + endfacet + facet normal -0.275554 0.0656807 0.959039 + outer loop + vertex -903.234 393.371 22.3371 + vertex -905.48 384.195 22.3202 + vertex -902.768 386.755 22.9242 + endloop + endfacet + facet normal -0.275217 0.0695132 0.958866 + outer loop + vertex -901.434 391.026 23.0237 + vertex -900.525 395.835 22.9359 + vertex -903.234 393.371 22.3371 + endloop + endfacet + facet normal -0.286752 0.0722428 0.955277 + outer loop + vertex -899.123 400.057 23.0375 + vertex -900.807 402.483 22.3484 + vertex -900.525 395.835 22.9359 + endloop + endfacet + facet normal -0.278009 0.0728383 0.957813 + outer loop + vertex -900.807 402.483 22.3484 + vertex -903.234 393.371 22.3371 + vertex -900.525 395.835 22.9359 + endloop + endfacet + facet normal -0.280489 0.0770132 0.956763 + outer loop + vertex -899.123 400.057 23.0375 + vertex -898.115 404.872 22.9456 + vertex -900.807 402.483 22.3484 + endloop + endfacet + facet normal -0.291504 0.079218 0.953284 + outer loop + vertex -896.638 409.105 23.0452 + vertex -898.212 411.584 22.3579 + vertex -898.115 404.872 22.9456 + endloop + endfacet + facet normal -0.282582 0.07958 0.955936 + outer loop + vertex -898.212 411.584 22.3579 + vertex -900.807 402.483 22.3484 + vertex -898.115 404.872 22.9456 + endloop + endfacet + facet normal -0.28666 0.0826203 0.954463 + outer loop + vertex -896.638 409.105 23.0452 + vertex -895.531 413.966 22.9571 + vertex -898.212 411.584 22.3579 + endloop + endfacet + facet normal -0.303474 0.0866349 0.948893 + outer loop + vertex -893.991 418.222 23.061 + vertex -895.479 420.674 22.3611 + vertex -895.531 413.966 22.9571 + endloop + endfacet + facet normal -0.290141 0.0869001 0.95303 + outer loop + vertex -895.479 420.674 22.3611 + vertex -898.212 411.584 22.3579 + vertex -895.531 413.966 22.9571 + endloop + endfacet + facet normal -0.297005 0.0910284 0.950527 + outer loop + vertex -893.991 418.222 23.061 + vertex -892.827 423.036 22.9636 + vertex -895.479 420.674 22.3611 + endloop + endfacet + facet normal -0.311844 0.0940456 0.945467 + outer loop + vertex -891.277 427.189 23.0618 + vertex -892.659 429.671 22.359 + vertex -892.827 423.036 22.9636 + endloop + endfacet + facet normal -0.299491 0.0940954 0.949448 + outer loop + vertex -892.659 429.671 22.359 + vertex -895.479 420.674 22.3611 + vertex -892.827 423.036 22.9636 + endloop + endfacet + facet normal -0.306712 0.0972867 0.946817 + outer loop + vertex -891.277 427.189 23.0618 + vertex -890.087 431.902 22.9631 + vertex -892.659 429.671 22.359 + endloop + endfacet + facet normal -0.322221 0.101144 0.941246 + outer loop + vertex -888.528 435.999 23.0564 + vertex -889.773 438.605 22.3502 + vertex -890.087 431.902 22.9631 + endloop + endfacet + facet normal -0.309573 0.100941 0.945503 + outer loop + vertex -889.773 438.605 22.3502 + vertex -892.659 429.671 22.359 + vertex -890.087 431.902 22.9631 + endloop + endfacet + facet normal -0.318588 0.103155 0.942264 + outer loop + vertex -888.528 435.999 23.0564 + vertex -887.275 440.794 22.9553 + vertex -889.773 438.605 22.3502 + endloop + endfacet + facet normal -0.340183 0.108359 0.934095 + outer loop + vertex -885.676 444.997 23.0498 + vertex -886.789 447.623 22.3399 + vertex -887.275 440.794 22.9553 + endloop + endfacet + facet normal -0.322119 0.107657 0.940558 + outer loop + vertex -886.789 447.623 22.3399 + vertex -889.773 438.605 22.3502 + vertex -887.275 440.794 22.9553 + endloop + endfacet + facet normal -0.336471 0.110236 0.93522 + outer loop + vertex -885.676 444.997 23.0498 + vertex -884.362 449.87 22.9482 + vertex -886.789 447.623 22.3399 + endloop + endfacet + facet normal -0.366691 0.118361 0.922783 + outer loop + vertex -882.757 454.07 23.0473 + vertex -883.692 456.68 22.3412 + vertex -884.362 449.87 22.9482 + endloop + endfacet + facet normal -0.34184 0.116778 0.932474 + outer loop + vertex -883.692 456.68 22.3412 + vertex -886.789 447.623 22.3399 + vertex -884.362 449.87 22.9482 + endloop + endfacet + facet normal -0.361541 0.120673 0.924514 + outer loop + vertex -882.757 454.07 23.0473 + vertex -881.412 458.856 22.9485 + vertex -883.692 456.68 22.3412 + endloop + endfacet + facet normal -0.400849 0.13342 0.906377 + outer loop + vertex -879.832 462.932 23.0473 + vertex -880.456 465.663 22.3695 + vertex -881.412 458.856 22.9485 + endloop + endfacet + facet normal -0.369431 0.130172 0.920095 + outer loop + vertex -880.456 465.663 22.3695 + vertex -883.692 456.68 22.3412 + vertex -881.412 458.856 22.9485 + endloop + endfacet + facet normal -0.397036 0.134662 0.90787 + outer loop + vertex -879.832 462.932 23.0473 + vertex -878.396 467.672 22.9723 + vertex -880.456 465.663 22.3695 + endloop + endfacet + facet normal -0.459186 0.158063 0.874165 + outer loop + vertex -876.77 471.749 23.0891 + vertex -877.069 474.64 22.4093 + vertex -878.396 467.672 22.9723 + endloop + endfacet + facet normal -0.410289 0.150793 0.899402 + outer loop + vertex -877.069 474.64 22.4093 + vertex -880.456 465.663 22.3695 + vertex -878.396 467.672 22.9723 + endloop + endfacet + facet normal -0.446766 0.160741 0.880092 + outer loop + vertex -876.77 471.749 23.0891 + vertex -875.198 476.62 22.9977 + vertex -877.069 474.64 22.4093 + endloop + endfacet + facet normal -0.437071 0.162075 0.884704 + outer loop + vertex -873.542 480.865 23.0384 + vertex -873.888 483.676 22.3521 + vertex -875.198 476.62 22.9977 + endloop + endfacet + facet normal -0.44937 0.163763 0.878207 + outer loop + vertex -873.888 483.676 22.3521 + vertex -877.069 474.64 22.4093 + vertex -875.198 476.62 22.9977 + endloop + endfacet + facet normal -0.471029 0.153952 0.868579 + outer loop + vertex -873.542 480.865 23.0384 + vertex -872.229 485.932 22.852 + vertex -873.888 483.676 22.3521 + endloop + endfacet + facet normal -0.694767 0.0958027 0.712826 + outer loop + vertex -871.258 491.534 23.0455 + vertex -872.094 492.324 22.1242 + vertex -872.229 485.932 22.852 + endloop + endfacet + facet normal -0.422402 0.111331 0.899545 + outer loop + vertex -872.094 492.324 22.1242 + vertex -873.888 483.676 22.3521 + vertex -872.229 485.932 22.852 + endloop + endfacet + facet normal -0.40691 0.148961 0.901241 + outer loop + vertex -873.888 483.676 22.3521 + vertex -875.36 483.35 21.7412 + vertex -877.069 474.64 22.4093 + endloop + endfacet + facet normal -0.519549 0.130032 0.844488 + outer loop + vertex -872.094 492.324 22.1242 + vertex -872.84 492.666 21.6128 + vertex -873.888 483.676 22.3521 + endloop + endfacet + facet normal -0.403238 0.121608 0.906979 + outer loop + vertex -873.888 483.676 22.3521 + vertex -872.84 492.666 21.6128 + vertex -875.36 483.35 21.7412 + endloop + endfacet + facet normal -0.4245 0.164067 0.890439 + outer loop + vertex -875.36 483.35 21.7412 + vertex -876.631 483.191 21.1648 + vertex -878.971 474.126 21.7198 + endloop + endfacet + facet normal -0.549286 0.159928 0.820187 + outer loop + vertex -872.84 492.666 21.6128 + vertex -873.484 492.862 21.1434 + vertex -875.36 483.35 21.7412 + endloop + endfacet + facet normal -0.423545 0.139821 0.895019 + outer loop + vertex -875.36 483.35 21.7412 + vertex -873.484 492.862 21.1434 + vertex -876.631 483.191 21.1648 + endloop + endfacet + facet normal -0.456184 0.193501 0.868593 + outer loop + vertex -880.604 473.84 21.1235 + vertex -881.806 473.901 20.4787 + vertex -884.563 464.706 21.0793 + endloop + endfacet + facet normal -0.532168 0.222519 0.816873 + outer loop + vertex -876.631 483.191 21.1648 + vertex -877.648 483.235 20.4903 + vertex -880.604 473.84 21.1235 + endloop + endfacet + facet normal -0.455085 0.201661 0.867312 + outer loop + vertex -880.604 473.84 21.1235 + vertex -877.648 483.235 20.4903 + vertex -881.806 473.901 20.4787 + endloop + endfacet + facet normal -0.672324 0.220368 0.706695 + outer loop + vertex -873.484 492.862 21.1434 + vertex -874.139 493.056 20.4593 + vertex -876.631 483.191 21.1648 + endloop + endfacet + facet normal -0.536355 0.194224 0.82134 + outer loop + vertex -876.631 483.191 21.1648 + vertex -874.139 493.056 20.4593 + vertex -877.648 483.235 20.4903 + endloop + endfacet + facet normal -0.606484 0.2385 0.758482 + outer loop + vertex -889.678 455.752 20.4631 + vertex -890.872 455.757 19.5074 + vertex -893.302 446.619 20.4373 + endloop + endfacet + facet normal -0.635259 0.266315 0.724929 + outer loop + vertex -885.874 464.811 20.4691 + vertex -886.885 464.939 19.5361 + vertex -889.678 455.752 20.4631 + endloop + endfacet + facet normal -0.603057 0.259488 0.754313 + outer loop + vertex -889.678 455.752 20.4631 + vertex -886.885 464.939 19.5361 + vertex -890.872 455.757 19.5074 + endloop + endfacet + facet normal -0.666755 0.297619 0.683272 + outer loop + vertex -881.806 473.901 20.4787 + vertex -882.692 474.076 19.5382 + vertex -885.874 464.811 20.4691 + endloop + endfacet + facet normal -0.62933 0.288614 0.721558 + outer loop + vertex -885.874 464.811 20.4691 + vertex -882.692 474.076 19.5382 + vertex -886.885 464.939 19.5361 + endloop + endfacet + facet normal -0.704738 0.313172 0.636607 + outer loop + vertex -877.648 483.235 20.4903 + vertex -878.422 483.406 19.5488 + vertex -881.806 473.901 20.4787 + endloop + endfacet + facet normal -0.664846 0.303466 0.682561 + outer loop + vertex -881.806 473.901 20.4787 + vertex -878.422 483.406 19.5488 + vertex -882.692 474.076 19.5382 + endloop + endfacet + facet normal -0.780274 0.280539 0.55899 + outer loop + vertex -874.139 493.056 20.4593 + vertex -874.685 493.221 19.6154 + vertex -877.648 483.235 20.4903 + endloop + endfacet + facet normal -0.719098 0.269527 0.64051 + outer loop + vertex -877.648 483.235 20.4903 + vertex -874.685 493.221 19.6154 + vertex -878.422 483.406 19.5488 + endloop + endfacet + facet normal -0.678283 0.259924 0.687293 + outer loop + vertex -898.517 437.019 19.4018 + vertex -900.395 435.985 17.9391 + vertex -902.139 427.64 19.374 + endloop + endfacet + facet normal -0.728939 0.28942 0.62039 + outer loop + vertex -894.742 446.435 19.4451 + vertex -896.37 445.685 17.8816 + vertex -898.517 437.019 19.4018 + endloop + endfacet + facet normal -0.681887 0.286959 0.672819 + outer loop + vertex -898.517 437.019 19.4018 + vertex -896.37 445.685 17.8816 + vertex -900.395 435.985 17.9391 + endloop + endfacet + facet normal -0.782507 0.3213 0.533337 + outer loop + vertex -890.872 455.757 19.5074 + vertex -892.199 455.167 17.9157 + vertex -894.742 446.435 19.4451 + endloop + endfacet + facet normal -0.728726 0.318413 0.606276 + outer loop + vertex -894.742 446.435 19.4451 + vertex -892.199 455.167 17.9157 + vertex -896.37 445.685 17.8816 + endloop + endfacet + facet normal -0.808092 0.34939 0.47425 + outer loop + vertex -886.885 464.939 19.5361 + vertex -887.969 464.578 17.9538 + vertex -890.872 455.757 19.5074 + endloop + endfacet + facet normal -0.779439 0.348165 0.520823 + outer loop + vertex -890.872 455.757 19.5074 + vertex -887.969 464.578 17.9538 + vertex -892.199 455.167 17.9157 + endloop + endfacet + facet normal -0.821244 0.376748 0.428508 + outer loop + vertex -882.692 474.076 19.5382 + vertex -883.606 473.86 17.9761 + vertex -886.885 464.939 19.5361 + endloop + endfacet + facet normal -0.802069 0.375921 0.464078 + outer loop + vertex -886.885 464.939 19.5361 + vertex -883.606 473.86 17.9761 + vertex -887.969 464.578 17.9538 + endloop + endfacet + facet normal -0.830957 0.379793 0.406531 + outer loop + vertex -878.422 483.406 19.5488 + vertex -879.148 483.399 18.0727 + vertex -882.692 474.076 19.5382 + endloop + endfacet + facet normal -0.820525 0.379163 0.427754 + outer loop + vertex -882.692 474.076 19.5382 + vertex -879.148 483.399 18.0727 + vertex -883.606 473.86 17.9761 + endloop + endfacet + facet normal -0.853262 0.322187 0.410048 + outer loop + vertex -874.685 493.221 19.6154 + vertex -875.213 493.382 18.3889 + vertex -878.422 483.406 19.5488 + endloop + endfacet + facet normal -0.850309 0.321965 0.416308 + outer loop + vertex -878.422 483.406 19.5488 + vertex -875.213 493.382 18.3889 + vertex -879.148 483.399 18.0727 + endloop + endfacet + facet normal -0.308765 -0.266672 0.91299 + outer loop + vertex -876.676 198.686 16.3617 + vertex -877.762 196.586 15.3808 + vertex -875.306 196.344 16.1406 + endloop + endfacet + facet normal -0.30883 -0.29888 0.902937 + outer loop + vertex -875.306 196.344 16.1406 + vertex -877.762 196.586 15.3808 + vertex -876.335 194.419 15.1516 + endloop + endfacet + facet normal -0.193111 -0.163872 0.967396 + outer loop + vertex -874.862 200.735 17.0708 + vertex -876.676 198.686 16.3617 + vertex -873.852 198.06 16.8193 + endloop + endfacet + facet normal -0.201237 -0.20798 0.957209 + outer loop + vertex -873.852 198.06 16.8193 + vertex -876.676 198.686 16.3617 + vertex -875.306 196.344 16.1406 + endloop + endfacet + facet normal -0.281258 -0.263313 0.9228 + outer loop + vertex -881.427 204.37 16.4829 + vertex -882.369 202.033 15.5291 + vertex -878.629 201.353 16.4747 + endloop + endfacet + facet normal -0.28101 -0.260892 0.923563 + outer loop + vertex -878.629 201.353 16.4747 + vertex -882.369 202.033 15.5291 + vertex -879.7 199.054 15.4995 + endloop + endfacet + facet normal -0.180501 -0.184507 0.966114 + outer loop + vertex -880.801 206.827 17.0692 + vertex -881.427 204.37 16.4829 + vertex -877.616 204.159 17.1546 + endloop + endfacet + facet normal -0.18017 -0.1697 0.968886 + outer loop + vertex -877.616 204.159 17.1546 + vertex -881.427 204.37 16.4829 + vertex -878.629 201.353 16.4747 + endloop + endfacet + facet normal -0.181059 -0.169354 0.968781 + outer loop + vertex -877.616 204.159 17.1546 + vertex -878.629 201.353 16.4747 + vertex -874.862 200.735 17.0708 + endloop + endfacet + facet normal -0.181689 -0.174126 0.967817 + outer loop + vertex -874.862 200.735 17.0708 + vertex -878.629 201.353 16.4747 + vertex -876.676 198.686 16.3617 + endloop + endfacet + facet normal -0.293607 -0.254158 0.92152 + outer loop + vertex -878.629 201.353 16.4747 + vertex -879.7 199.054 15.4995 + vertex -876.676 198.686 16.3617 + endloop + endfacet + facet normal -0.294367 -0.275164 0.915223 + outer loop + vertex -876.676 198.686 16.3617 + vertex -879.7 199.054 15.4995 + vertex -877.762 196.586 15.3808 + endloop + endfacet + facet normal -0.287437 -0.261068 0.921533 + outer loop + vertex -887.931 211.442 16.4807 + vertex -888.943 209.185 15.5256 + vertex -884.58 207.732 16.475 + endloop + endfacet + facet normal -0.287465 -0.261179 0.921493 + outer loop + vertex -884.58 207.732 16.475 + vertex -888.943 209.185 15.5256 + vertex -885.554 205.452 15.5248 + endloop + endfacet + facet normal -0.18781 -0.179411 0.965681 + outer loop + vertex -887.142 213.83 17.0777 + vertex -887.931 211.442 16.4807 + vertex -883.482 210.372 17.1471 + endloop + endfacet + facet normal -0.185698 -0.169237 0.967923 + outer loop + vertex -883.482 210.372 17.1471 + vertex -887.931 211.442 16.4807 + vertex -884.58 207.732 16.475 + endloop + endfacet + facet normal -0.191943 -0.166452 0.967188 + outer loop + vertex -883.482 210.372 17.1471 + vertex -884.58 207.732 16.475 + vertex -880.801 206.827 17.0692 + endloop + endfacet + facet normal -0.194798 -0.180387 0.964113 + outer loop + vertex -880.801 206.827 17.0692 + vertex -884.58 207.732 16.475 + vertex -881.427 204.37 16.4829 + endloop + endfacet + facet normal -0.283145 -0.263328 0.922219 + outer loop + vertex -884.58 207.732 16.475 + vertex -885.554 205.452 15.5248 + vertex -881.427 204.37 16.4829 + endloop + endfacet + facet normal -0.282992 -0.262492 0.922504 + outer loop + vertex -881.427 204.37 16.4829 + vertex -885.554 205.452 15.5248 + vertex -882.369 202.033 15.5291 + endloop + endfacet + facet normal -0.304969 -0.258033 0.91674 + outer loop + vertex -894.645 219.399 16.5254 + vertex -895.71 217.194 15.5508 + vertex -891.304 215.354 16.4985 + endloop + endfacet + facet normal -0.303677 -0.25416 0.91825 + outer loop + vertex -891.304 215.354 16.4985 + vertex -895.71 217.194 15.5508 + vertex -892.352 213.124 15.5347 + endloop + endfacet + facet normal -0.197542 -0.18138 0.963368 + outer loop + vertex -893.723 221.668 17.1417 + vertex -894.645 219.399 16.5254 + vertex -889.945 217.797 17.1875 + endloop + endfacet + facet normal -0.192713 -0.165636 0.967175 + outer loop + vertex -889.945 217.797 17.1875 + vertex -894.645 219.399 16.5254 + vertex -891.304 215.354 16.4985 + endloop + endfacet + facet normal -0.194808 -0.16441 0.966964 + outer loop + vertex -889.945 217.797 17.1875 + vertex -891.304 215.354 16.4985 + vertex -887.142 213.83 17.0777 + endloop + endfacet + facet normal -0.198502 -0.175521 0.964256 + outer loop + vertex -887.142 213.83 17.0777 + vertex -891.304 215.354 16.4985 + vertex -887.931 211.442 16.4807 + endloop + endfacet + facet normal -0.295266 -0.258743 0.919712 + outer loop + vertex -891.304 215.354 16.4985 + vertex -892.352 213.124 15.5347 + vertex -887.931 211.442 16.4807 + endloop + endfacet + facet normal -0.294813 -0.257232 0.920281 + outer loop + vertex -887.931 211.442 16.4807 + vertex -892.352 213.124 15.5347 + vertex -888.943 209.185 15.5256 + endloop + endfacet + facet normal -0.323283 -0.252209 0.912074 + outer loop + vertex -901.043 227.669 16.5938 + vertex -902.166 225.536 15.6059 + vertex -897.899 223.507 16.5573 + endloop + endfacet + facet normal -0.322388 -0.249876 0.913032 + outer loop + vertex -897.899 223.507 16.5573 + vertex -902.166 225.536 15.6059 + vertex -898.997 221.346 15.5781 + endloop + endfacet + facet normal -0.210249 -0.177004 0.961491 + outer loop + vertex -900.04 229.858 17.216 + vertex -901.043 227.669 16.5938 + vertex -896.411 225.792 17.2611 + endloop + endfacet + facet normal -0.205291 -0.163544 0.96494 + outer loop + vertex -896.411 225.792 17.2611 + vertex -901.043 227.669 16.5938 + vertex -897.899 223.507 16.5573 + endloop + endfacet + facet normal -0.206648 -0.162619 0.964806 + outer loop + vertex -896.411 225.792 17.2611 + vertex -897.899 223.507 16.5573 + vertex -893.723 221.668 17.1417 + endloop + endfacet + facet normal -0.211697 -0.17513 0.961516 + outer loop + vertex -893.723 221.668 17.1417 + vertex -897.899 223.507 16.5573 + vertex -894.645 219.399 16.5254 + endloop + endfacet + facet normal -0.313311 -0.255246 0.914705 + outer loop + vertex -897.899 223.507 16.5573 + vertex -898.997 221.346 15.5781 + vertex -894.645 219.399 16.5254 + endloop + endfacet + facet normal -0.31274 -0.25366 0.915342 + outer loop + vertex -894.645 219.399 16.5254 + vertex -898.997 221.346 15.5781 + vertex -895.71 217.194 15.5508 + endloop + endfacet + facet normal -0.346201 -0.24194 0.906427 + outer loop + vertex -906.901 236.076 16.6645 + vertex -908.095 234.01 15.6574 + vertex -904.048 231.862 16.6295 + endloop + endfacet + facet normal -0.346604 -0.242883 0.906021 + outer loop + vertex -904.048 231.862 16.6295 + vertex -908.095 234.01 15.6574 + vertex -905.193 229.756 15.6268 + endloop + endfacet + facet normal -0.229189 -0.176315 0.95728 + outer loop + vertex -905.81 238.155 17.3087 + vertex -906.901 236.076 16.6645 + vertex -902.477 234.025 17.3463 + endloop + endfacet + facet normal -0.221445 -0.157934 0.962299 + outer loop + vertex -902.477 234.025 17.3463 + vertex -906.901 236.076 16.6645 + vertex -904.048 231.862 16.6295 + endloop + endfacet + facet normal -0.220253 -0.158841 0.962423 + outer loop + vertex -902.477 234.025 17.3463 + vertex -904.048 231.862 16.6295 + vertex -900.04 229.858 17.216 + endloop + endfacet + facet normal -0.225187 -0.169582 0.959444 + outer loop + vertex -900.04 229.858 17.216 + vertex -904.048 231.862 16.6295 + vertex -901.043 227.669 16.5938 + endloop + endfacet + facet normal -0.336806 -0.249157 0.90801 + outer loop + vertex -904.048 231.862 16.6295 + vertex -905.193 229.756 15.6268 + vertex -901.043 227.669 16.5938 + endloop + endfacet + facet normal -0.335096 -0.244932 0.909791 + outer loop + vertex -901.043 227.669 16.5938 + vertex -905.193 229.756 15.6268 + vertex -902.166 225.536 15.6059 + endloop + endfacet + facet normal -0.366648 -0.229735 0.901549 + outer loop + vertex -912.122 244.439 16.7437 + vertex -913.436 242.516 15.7192 + vertex -909.599 240.269 16.7072 + endloop + endfacet + facet normal -0.367402 -0.231338 0.900832 + outer loop + vertex -909.599 240.269 16.7072 + vertex -913.436 242.516 15.7192 + vertex -910.849 238.279 15.6865 + endloop + endfacet + facet normal -0.24848 -0.173035 0.953056 + outer loop + vertex -910.934 246.405 17.4102 + vertex -912.122 244.439 16.7437 + vertex -907.934 242.281 17.4438 + endloop + endfacet + facet normal -0.239176 -0.153109 0.958829 + outer loop + vertex -907.934 242.281 17.4438 + vertex -912.122 244.439 16.7437 + vertex -909.599 240.269 16.7072 + endloop + endfacet + facet normal -0.238175 -0.153977 0.958939 + outer loop + vertex -907.934 242.281 17.4438 + vertex -909.599 240.269 16.7072 + vertex -905.81 238.155 17.3087 + endloop + endfacet + facet normal -0.244989 -0.167316 0.95498 + outer loop + vertex -905.81 238.155 17.3087 + vertex -909.599 240.269 16.7072 + vertex -906.901 236.076 16.6645 + endloop + endfacet + facet normal -0.357111 -0.238909 0.902992 + outer loop + vertex -909.599 240.269 16.7072 + vertex -910.849 238.279 15.6865 + vertex -906.901 236.076 16.6645 + endloop + endfacet + facet normal -0.355603 -0.235551 0.904468 + outer loop + vertex -906.901 236.076 16.6645 + vertex -910.849 238.279 15.6865 + vertex -908.095 234.01 15.6574 + endloop + endfacet + facet normal -0.390891 -0.215175 0.894932 + outer loop + vertex -916.763 252.893 16.8253 + vertex -918.158 251.049 15.7726 + vertex -914.504 248.622 16.7849 + endloop + endfacet + facet normal -0.390892 -0.215177 0.894931 + outer loop + vertex -914.504 248.622 16.7849 + vertex -918.158 251.049 15.7726 + vertex -915.857 246.746 15.7429 + endloop + endfacet + facet normal -0.26714 -0.161877 0.949964 + outer loop + vertex -915.54 254.882 17.5082 + vertex -916.763 252.893 16.8253 + vertex -912.792 250.575 17.547 + endloop + endfacet + facet normal -0.258665 -0.145821 0.954897 + outer loop + vertex -912.792 250.575 17.547 + vertex -916.763 252.893 16.8253 + vertex -914.504 248.622 16.7849 + endloop + endfacet + facet normal -0.258154 -0.146295 0.954963 + outer loop + vertex -912.792 250.575 17.547 + vertex -914.504 248.622 16.7849 + vertex -910.934 246.405 17.4102 + endloop + endfacet + facet normal -0.266559 -0.161159 0.950249 + outer loop + vertex -910.934 246.405 17.4102 + vertex -914.504 248.622 16.7849 + vertex -912.122 244.439 16.7437 + endloop + endfacet + facet normal -0.379387 -0.224896 0.89749 + outer loop + vertex -914.504 248.622 16.7849 + vertex -915.857 246.746 15.7429 + vertex -912.122 244.439 16.7437 + endloop + endfacet + facet normal -0.377501 -0.221088 0.899229 + outer loop + vertex -912.122 244.439 16.7437 + vertex -915.857 246.746 15.7429 + vertex -913.436 242.516 15.7192 + endloop + endfacet + facet normal -0.414228 -0.195006 0.889037 + outer loop + vertex -921.013 261.915 16.9096 + vertex -922.433 260.074 15.8442 + vertex -918.933 257.321 16.8713 + endloop + endfacet + facet normal -0.414323 -0.195155 0.888961 + outer loop + vertex -918.933 257.321 16.8713 + vertex -922.433 260.074 15.8442 + vertex -920.352 255.487 15.8071 + endloop + endfacet + facet normal -0.291628 -0.154342 0.943998 + outer loop + vertex -919.902 264.021 17.5972 + vertex -921.013 261.915 16.9096 + vertex -917.295 259.425 17.6513 + endloop + endfacet + facet normal -0.279729 -0.134606 0.950596 + outer loop + vertex -917.295 259.425 17.6513 + vertex -921.013 261.915 16.9096 + vertex -918.933 257.321 16.8713 + endloop + endfacet + facet normal -0.276943 -0.136953 0.951076 + outer loop + vertex -917.295 259.425 17.6513 + vertex -918.933 257.321 16.8713 + vertex -915.54 254.882 17.5082 + endloop + endfacet + facet normal -0.285236 -0.149633 0.946705 + outer loop + vertex -915.54 254.882 17.5082 + vertex -918.933 257.321 16.8713 + vertex -916.763 252.893 16.8253 + endloop + endfacet + facet normal -0.40214 -0.206361 0.892019 + outer loop + vertex -918.933 257.321 16.8713 + vertex -920.352 255.487 15.8071 + vertex -916.763 252.893 16.8253 + endloop + endfacet + facet normal -0.401679 -0.205571 0.892409 + outer loop + vertex -916.763 252.893 16.8253 + vertex -920.352 255.487 15.8071 + vertex -918.158 251.049 15.7726 + endloop + endfacet + facet normal -0.453756 -0.181521 0.872442 + outer loop + vertex -924.886 271.316 16.9471 + vertex -926.241 269.683 15.9024 + vertex -923.02 266.596 16.9356 + endloop + endfacet + facet normal -0.449248 -0.175635 0.875973 + outer loop + vertex -923.02 266.596 16.9356 + vertex -926.241 269.683 15.9024 + vertex -924.396 264.814 15.8726 + endloop + endfacet + facet normal -0.34808 -0.160937 0.923547 + outer loop + vertex -923.889 272.87 17.5933 + vertex -924.886 271.316 16.9471 + vertex -921.621 268.444 17.677 + endloop + endfacet + facet normal -0.324286 -0.130492 0.936915 + outer loop + vertex -921.621 268.444 17.677 + vertex -924.886 271.316 16.9471 + vertex -923.02 266.596 16.9356 + endloop + endfacet + facet normal -0.314183 -0.139025 0.939128 + outer loop + vertex -921.621 268.444 17.677 + vertex -923.02 266.596 16.9356 + vertex -919.902 264.021 17.5972 + endloop + endfacet + facet normal -0.315076 -0.140229 0.93865 + outer loop + vertex -919.902 264.021 17.5972 + vertex -923.02 266.596 16.9356 + vertex -921.013 261.915 16.9096 + endloop + endfacet + facet normal -0.433491 -0.190656 0.880759 + outer loop + vertex -923.02 266.596 16.9356 + vertex -924.396 264.814 15.8726 + vertex -921.013 261.915 16.9096 + endloop + endfacet + facet normal -0.427786 -0.182379 0.885289 + outer loop + vertex -921.013 261.915 16.9096 + vertex -924.396 264.814 15.8726 + vertex -922.433 260.074 15.8442 + endloop + endfacet + facet normal -0.484255 -0.144374 0.862933 + outer loop + vertex -927.85 280.843 17.0347 + vertex -929.404 279.575 15.9508 + vertex -926.512 276.001 16.9758 + endloop + endfacet + facet normal -0.492133 -0.152431 0.857071 + outer loop + vertex -926.512 276.001 16.9758 + vertex -929.404 279.575 15.9508 + vertex -927.925 274.625 15.9194 + endloop + endfacet + facet normal -0.362507 -0.109352 0.925543 + outer loop + vertex -926.168 282.226 17.8568 + vertex -927.85 280.843 17.0347 + vertex -924.848 276.901 17.7449 + endloop + endfacet + facet normal -0.366169 -0.112467 0.923727 + outer loop + vertex -924.848 276.901 17.7449 + vertex -927.85 280.843 17.0347 + vertex -926.512 276.001 16.9758 + endloop + endfacet + facet normal -0.361936 -0.12082 0.92434 + outer loop + vertex -924.848 276.901 17.7449 + vertex -926.512 276.001 16.9758 + vertex -923.889 272.87 17.5933 + endloop + endfacet + facet normal -0.379405 -0.137293 0.914988 + outer loop + vertex -923.889 272.87 17.5933 + vertex -926.512 276.001 16.9758 + vertex -924.886 271.316 16.9471 + endloop + endfacet + facet normal -0.477552 -0.171027 0.861797 + outer loop + vertex -926.512 276.001 16.9758 + vertex -927.925 274.625 15.9194 + vertex -924.886 271.316 16.9471 + endloop + endfacet + facet normal -0.471083 -0.163531 0.866798 + outer loop + vertex -924.886 271.316 16.9471 + vertex -927.925 274.625 15.9194 + vertex -926.241 269.683 15.9024 + endloop + endfacet + facet normal -0.50164 -0.110126 0.858038 + outer loop + vertex -930.111 290.988 17.1329 + vertex -931.683 289.436 16.0146 + vertex -929.068 285.962 17.0975 + endloop + endfacet + facet normal -0.504101 -0.112526 0.856283 + outer loop + vertex -929.068 285.962 17.0975 + vertex -931.683 289.436 16.0146 + vertex -930.651 284.525 15.9771 + endloop + endfacet + facet normal -0.371714 -0.0872775 0.924235 + outer loop + vertex -928.706 292.937 17.8821 + vertex -930.111 290.988 17.1329 + vertex -927.419 288.113 17.9441 + endloop + endfacet + facet normal -0.36754 -0.082782 0.926316 + outer loop + vertex -927.419 288.113 17.9441 + vertex -930.111 290.988 17.1329 + vertex -929.068 285.962 17.0975 + endloop + endfacet + facet normal -0.359288 -0.0901116 0.928866 + outer loop + vertex -927.419 288.113 17.9441 + vertex -929.068 285.962 17.0975 + vertex -926.168 282.226 17.8568 + endloop + endfacet + facet normal -0.369857 -0.0993534 0.923761 + outer loop + vertex -926.168 282.226 17.8568 + vertex -929.068 285.962 17.0975 + vertex -927.85 280.843 17.0347 + endloop + endfacet + facet normal -0.493116 -0.127916 0.860508 + outer loop + vertex -929.068 285.962 17.0975 + vertex -930.651 284.525 15.9771 + vertex -927.85 280.843 17.0347 + endloop + endfacet + facet normal -0.494373 -0.129132 0.859604 + outer loop + vertex -927.85 280.843 17.0347 + vertex -930.651 284.525 15.9771 + vertex -929.404 279.575 15.9508 + endloop + endfacet + facet normal -0.533166 -0.0738108 0.842784 + outer loop + vertex -931.531 300.611 17.1852 + vertex -933.089 299.221 16.0779 + vertex -930.904 295.806 17.1615 + endloop + endfacet + facet normal -0.529728 -0.0708425 0.845204 + outer loop + vertex -930.904 295.806 17.1615 + vertex -933.089 299.221 16.0779 + vertex -932.484 294.304 16.045 + endloop + endfacet + facet normal -0.420673 -0.0756303 0.904054 + outer loop + vertex -930.347 302.088 17.8598 + vertex -931.531 300.611 17.1852 + vertex -929.288 297.482 17.9674 + endloop + endfacet + facet normal -0.398048 -0.0565203 0.915622 + outer loop + vertex -929.288 297.482 17.9674 + vertex -931.531 300.611 17.1852 + vertex -930.904 295.806 17.1615 + endloop + endfacet + facet normal -0.388783 -0.0670252 0.918888 + outer loop + vertex -929.288 297.482 17.9674 + vertex -930.904 295.806 17.1615 + vertex -928.706 292.937 17.8821 + endloop + endfacet + facet normal -0.392056 -0.0699359 0.917279 + outer loop + vertex -928.706 292.937 17.8821 + vertex -930.904 295.806 17.1615 + vertex -930.111 290.988 17.1329 + endloop + endfacet + facet normal -0.516181 -0.089961 0.851742 + outer loop + vertex -930.904 295.806 17.1615 + vertex -932.484 294.304 16.045 + vertex -930.111 290.988 17.1329 + endloop + endfacet + facet normal -0.51655 -0.0903108 0.851481 + outer loop + vertex -930.111 290.988 17.1329 + vertex -932.484 294.304 16.045 + vertex -931.683 289.436 16.0146 + endloop + endfacet + facet normal -0.560694 -0.0270537 0.827581 + outer loop + vertex -932.125 310.444 17.2508 + vertex -933.756 309.323 16.1091 + vertex -931.957 305.436 17.2011 + endloop + endfacet + facet normal -0.564008 -0.0292422 0.825252 + outer loop + vertex -931.957 305.436 17.2011 + vertex -933.756 309.323 16.1091 + vertex -933.515 304.238 16.0938 + endloop + endfacet + facet normal -0.440926 -0.0220303 0.897273 + outer loop + vertex -930.464 311.522 18.0937 + vertex -932.125 310.444 17.2508 + vertex -930.382 306.207 18.0034 + endloop + endfacet + facet normal -0.444502 -0.0238231 0.895461 + outer loop + vertex -930.382 306.207 18.0034 + vertex -932.125 310.444 17.2508 + vertex -931.957 305.436 17.2011 + endloop + endfacet + facet normal -0.439985 -0.0349913 0.897323 + outer loop + vertex -930.382 306.207 18.0034 + vertex -931.957 305.436 17.2011 + vertex -930.347 302.088 17.8598 + endloop + endfacet + facet normal -0.45356 -0.0429208 0.890192 + outer loop + vertex -930.347 302.088 17.8598 + vertex -931.957 305.436 17.2011 + vertex -931.531 300.611 17.1852 + endloop + endfacet + facet normal -0.551961 -0.0514083 0.832284 + outer loop + vertex -931.957 305.436 17.2011 + vertex -933.515 304.238 16.0938 + vertex -931.531 300.611 17.1852 + endloop + endfacet + facet normal -0.549089 -0.049227 0.834313 + outer loop + vertex -931.531 300.611 17.1852 + vertex -933.515 304.238 16.0938 + vertex -933.089 299.221 16.0779 + endloop + endfacet + facet normal -0.580963 0.00476763 0.813916 + outer loop + vertex -932.083 321.012 17.3102 + vertex -933.716 319.72 16.1526 + vertex -932.161 315.742 17.2857 + endloop + endfacet + facet normal -0.576285 0.00753544 0.817214 + outer loop + vertex -932.161 315.742 17.2857 + vertex -933.716 319.72 16.1526 + vertex -933.818 314.488 16.1283 + endloop + endfacet + facet normal -0.451098 0.00199585 0.892472 + outer loop + vertex -930.535 322.284 18.0897 + vertex -932.083 321.012 17.3102 + vertex -930.413 317.218 18.1631 + endloop + endfacet + facet normal -0.450231 0.00247587 0.892909 + outer loop + vertex -930.413 317.218 18.1631 + vertex -932.083 321.012 17.3102 + vertex -932.161 315.742 17.2857 + endloop + endfacet + facet normal -0.44387 -0.00693415 0.896064 + outer loop + vertex -930.413 317.218 18.1631 + vertex -932.161 315.742 17.2857 + vertex -930.464 311.522 18.0937 + endloop + endfacet + facet normal -0.447825 -0.00890535 0.894077 + outer loop + vertex -930.464 311.522 18.0937 + vertex -932.161 315.742 17.2857 + vertex -932.125 310.444 17.2508 + endloop + endfacet + facet normal -0.567743 -0.00924474 0.823154 + outer loop + vertex -932.161 315.742 17.2857 + vertex -933.818 314.488 16.1283 + vertex -932.125 310.444 17.2508 + endloop + endfacet + facet normal -0.568839 -0.00991545 0.822389 + outer loop + vertex -932.125 310.444 17.2508 + vertex -933.818 314.488 16.1283 + vertex -933.756 309.323 16.1091 + endloop + endfacet + facet normal -0.609964 0.0452303 0.791137 + outer loop + vertex -931.338 331.187 17.4072 + vertex -932.951 330.12 16.2252 + vertex -931.787 326.109 17.3517 + endloop + endfacet + facet normal -0.603771 0.0483059 0.795693 + outer loop + vertex -931.787 326.109 17.3517 + vertex -932.951 330.12 16.2252 + vertex -933.428 324.95 16.1771 + endloop + endfacet + facet normal -0.448743 0.0256554 0.893293 + outer loop + vertex -929.739 332.377 18.1764 + vertex -931.338 331.187 17.4072 + vertex -929.898 327.045 18.2498 + endloop + endfacet + facet normal -0.440926 0.0291431 0.89707 + outer loop + vertex -929.898 327.045 18.2498 + vertex -931.338 331.187 17.4072 + vertex -931.787 326.109 17.3517 + endloop + endfacet + facet normal -0.44082 0.028873 0.897131 + outer loop + vertex -929.898 327.045 18.2498 + vertex -931.787 326.109 17.3517 + vertex -930.535 322.284 18.0897 + endloop + endfacet + facet normal -0.462565 0.0196799 0.886367 + outer loop + vertex -930.535 322.284 18.0897 + vertex -931.787 326.109 17.3517 + vertex -932.083 321.012 17.3102 + endloop + endfacet + facet normal -0.59491 0.0280502 0.803303 + outer loop + vertex -931.787 326.109 17.3517 + vertex -933.428 324.95 16.1771 + vertex -932.083 321.012 17.3102 + endloop + endfacet + facet normal -0.593343 0.0289096 0.804431 + outer loop + vertex -932.083 321.012 17.3102 + vertex -933.428 324.95 16.1771 + vertex -933.716 319.72 16.1526 + endloop + endfacet + facet normal -0.624188 0.0823798 0.776919 + outer loop + vertex -930.084 341.191 17.4646 + vertex -931.628 340.256 16.3229 + vertex -930.766 336.215 17.444 + endloop + endfacet + facet normal -0.624498 0.0822483 0.776683 + outer loop + vertex -930.766 336.215 17.444 + vertex -931.628 340.256 16.3229 + vertex -932.338 335.219 16.2858 + endloop + endfacet + facet normal -0.459674 0.0511489 0.886613 + outer loop + vertex -928.49 342.358 18.2237 + vertex -930.084 341.191 17.4646 + vertex -928.883 337.127 18.3218 + endloop + endfacet + facet normal -0.444358 0.0572375 0.894019 + outer loop + vertex -928.883 337.127 18.3218 + vertex -930.084 341.191 17.4646 + vertex -930.766 336.215 17.444 + endloop + endfacet + facet normal -0.44257 0.0524028 0.895202 + outer loop + vertex -928.883 337.127 18.3218 + vertex -930.766 336.215 17.444 + vertex -929.739 332.377 18.1764 + endloop + endfacet + facet normal -0.460536 0.0459272 0.886452 + outer loop + vertex -929.739 332.377 18.1764 + vertex -930.766 336.215 17.444 + vertex -931.338 331.187 17.4072 + endloop + endfacet + facet normal -0.618231 0.0646335 0.783335 + outer loop + vertex -930.766 336.215 17.444 + vertex -932.338 335.219 16.2858 + vertex -931.338 331.187 17.4072 + endloop + endfacet + facet normal -0.61761 0.0649169 0.783801 + outer loop + vertex -931.338 331.187 17.4072 + vertex -932.338 335.219 16.2858 + vertex -932.951 330.12 16.2252 + endloop + endfacet + facet normal -0.637361 0.118278 0.761433 + outer loop + vertex -928.366 351.091 17.4692 + vertex -929.867 350.237 16.3449 + vertex -929.283 346.147 17.4695 + endloop + endfacet + facet normal -0.636985 0.118413 0.761727 + outer loop + vertex -929.283 346.147 17.4695 + vertex -929.867 350.237 16.3449 + vertex -930.803 345.258 16.3362 + endloop + endfacet + facet normal -0.493224 0.0772534 0.866465 + outer loop + vertex -926.819 352.217 18.2492 + vertex -928.366 351.091 17.4692 + vertex -927.441 347.046 18.3565 + endloop + endfacet + facet normal -0.466136 0.0865209 0.880473 + outer loop + vertex -927.441 347.046 18.3565 + vertex -928.366 351.091 17.4692 + vertex -929.283 346.147 17.4695 + endloop + endfacet + facet normal -0.463372 0.0786941 0.882663 + outer loop + vertex -927.441 347.046 18.3565 + vertex -929.283 346.147 17.4695 + vertex -928.49 342.358 18.2237 + endloop + endfacet + facet normal -0.473308 0.0756161 0.877645 + outer loop + vertex -928.49 342.358 18.2237 + vertex -929.283 346.147 17.4695 + vertex -930.084 341.191 17.4646 + endloop + endfacet + facet normal -0.631946 0.101358 0.768356 + outer loop + vertex -929.283 346.147 17.4695 + vertex -930.803 345.258 16.3362 + vertex -930.084 341.191 17.4646 + endloop + endfacet + facet normal -0.630506 0.101921 0.769464 + outer loop + vertex -930.084 341.191 17.4646 + vertex -930.803 345.258 16.3362 + vertex -931.628 340.256 16.3229 + endloop + endfacet + facet normal -0.665187 0.148699 0.731721 + outer loop + vertex -926.273 360.917 17.4676 + vertex -927.695 360.137 16.3327 + vertex -927.364 356.011 17.4723 + endloop + endfacet + facet normal -0.658114 0.150901 0.737641 + outer loop + vertex -927.364 356.011 17.4723 + vertex -927.695 360.137 16.3327 + vertex -928.822 355.196 16.3387 + endloop + endfacet + facet normal -0.523518 0.104187 0.84562 + outer loop + vertex -924.779 362.008 18.2579 + vertex -926.273 360.917 17.4676 + vertex -925.61 356.86 18.3779 + endloop + endfacet + facet normal -0.497913 0.111603 0.860016 + outer loop + vertex -925.61 356.86 18.3779 + vertex -926.273 360.917 17.4676 + vertex -927.364 356.011 17.4723 + endloop + endfacet + facet normal -0.495868 0.105269 0.861994 + outer loop + vertex -925.61 356.86 18.3779 + vertex -927.364 356.011 17.4723 + vertex -926.819 352.217 18.2492 + endloop + endfacet + facet normal -0.50644 0.102554 0.856155 + outer loop + vertex -926.819 352.217 18.2492 + vertex -927.364 356.011 17.4723 + vertex -928.366 351.091 17.4692 + endloop + endfacet + facet normal -0.653661 0.132592 0.745082 + outer loop + vertex -927.364 356.011 17.4723 + vertex -928.822 355.196 16.3387 + vertex -928.366 351.091 17.4692 + endloop + endfacet + facet normal -0.642274 0.136381 0.754245 + outer loop + vertex -928.366 351.091 17.4692 + vertex -928.822 355.196 16.3387 + vertex -929.867 350.237 16.3449 + endloop + endfacet + facet normal -0.681203 0.173995 0.711117 + outer loop + vertex -923.792 370.866 17.4924 + vertex -925.179 370.093 16.3521 + vertex -925.097 365.845 17.4708 + endloop + endfacet + facet normal -0.677558 0.174922 0.714365 + outer loop + vertex -925.097 365.845 17.4708 + vertex -925.179 370.093 16.3521 + vertex -926.488 365.091 16.3359 + endloop + endfacet + facet normal -0.549736 0.127722 0.825517 + outer loop + vertex -922.297 372.023 18.3087 + vertex -923.792 370.866 17.4924 + vertex -923.397 366.715 18.3975 + endloop + endfacet + facet normal -0.526061 0.133122 0.839963 + outer loop + vertex -923.397 366.715 18.3975 + vertex -923.792 370.866 17.4924 + vertex -925.097 365.845 17.4708 + endloop + endfacet + facet normal -0.524798 0.129152 0.841372 + outer loop + vertex -923.397 366.715 18.3975 + vertex -925.097 365.845 17.4708 + vertex -924.779 362.008 18.2579 + endloop + endfacet + facet normal -0.534816 0.12709 0.835356 + outer loop + vertex -924.779 362.008 18.2579 + vertex -925.097 365.845 17.4708 + vertex -926.273 360.917 17.4676 + endloop + endfacet + facet normal -0.674707 0.160552 0.720412 + outer loop + vertex -925.097 365.845 17.4708 + vertex -926.488 365.091 16.3359 + vertex -926.273 360.917 17.4676 + endloop + endfacet + facet normal -0.668183 0.162417 0.726053 + outer loop + vertex -926.273 360.917 17.4676 + vertex -926.488 365.091 16.3359 + vertex -927.695 360.137 16.3327 + endloop + endfacet + facet normal -0.680522 0.204707 0.703551 + outer loop + vertex -920.588 381.435 17.6492 + vertex -922.131 380.426 16.4497 + vertex -922.314 376.045 17.5475 + endloop + endfacet + facet normal -0.690992 0.202714 0.693856 + outer loop + vertex -922.314 376.045 17.5475 + vertex -922.131 380.426 16.4497 + vertex -923.733 375.193 16.383 + endloop + endfacet + facet normal -0.569349 0.158824 0.806608 + outer loop + vertex -919.449 381.621 18.4164 + vertex -920.588 381.435 17.6492 + vertex -920.68 376.854 18.486 + endloop + endfacet + facet normal -0.550196 0.160778 0.819411 + outer loop + vertex -920.68 376.854 18.486 + vertex -920.588 381.435 17.6492 + vertex -922.314 376.045 17.5475 + endloop + endfacet + facet normal -0.548106 0.153274 0.822245 + outer loop + vertex -920.68 376.854 18.486 + vertex -922.314 376.045 17.5475 + vertex -922.297 372.023 18.3087 + endloop + endfacet + facet normal -0.561575 0.151548 0.813429 + outer loop + vertex -922.297 372.023 18.3087 + vertex -922.314 376.045 17.5475 + vertex -923.792 370.866 17.4924 + endloop + endfacet + facet normal -0.688166 0.188866 0.70054 + outer loop + vertex -922.314 376.045 17.5475 + vertex -923.733 375.193 16.383 + vertex -923.792 370.866 17.4924 + endloop + endfacet + facet normal -0.68424 0.189737 0.704142 + outer loop + vertex -923.792 370.866 17.4924 + vertex -923.733 375.193 16.383 + vertex -925.179 370.093 16.3521 + endloop + endfacet + facet normal -0.683844 0.218648 0.696097 + outer loop + vertex -922.131 380.426 16.4497 + vertex -920.588 381.435 17.6492 + vertex -920.345 385.831 16.507 + endloop + endfacet + facet normal -0.651563 0.222548 0.725216 + outer loop + vertex -918.875 390.706 16.3312 + vertex -920.345 385.831 16.507 + vertex -918.112 387.923 17.8708 + endloop + endfacet + facet normal -0.569712 0.190057 0.799567 + outer loop + vertex -919.449 381.621 18.4164 + vertex -918.112 387.923 17.8708 + vertex -920.588 381.435 17.6492 + endloop + endfacet + facet normal -0.652343 0.224163 0.724016 + outer loop + vertex -920.345 385.831 16.507 + vertex -920.588 381.435 17.6492 + vertex -918.112 387.923 17.8708 + endloop + endfacet + facet normal -0.669511 0.237186 0.703917 + outer loop + vertex -915.445 400.476 16.3929 + vertex -917.097 395.261 16.5795 + vertex -914.725 398.11 17.8753 + endloop + endfacet + facet normal -0.658573 0.217894 0.720281 + outer loop + vertex -918.875 390.706 16.3312 + vertex -918.112 387.923 17.8708 + vertex -917.097 395.261 16.5795 + endloop + endfacet + facet normal -0.656401 0.21794 0.722246 + outer loop + vertex -918.112 387.923 17.8708 + vertex -914.725 398.11 17.8753 + vertex -917.097 395.261 16.5795 + endloop + endfacet + facet normal -0.696056 0.261267 0.668764 + outer loop + vertex -911.863 410.169 16.4173 + vertex -913.594 405.051 16.6148 + vertex -911.308 407.831 17.9083 + endloop + endfacet + facet normal -0.669884 0.236908 0.703655 + outer loop + vertex -915.445 400.476 16.3929 + vertex -914.725 398.11 17.8753 + vertex -913.594 405.051 16.6148 + endloop + endfacet + facet normal -0.680333 0.236784 0.693599 + outer loop + vertex -914.725 398.11 17.8753 + vertex -911.308 407.831 17.9083 + vertex -913.594 405.051 16.6148 + endloop + endfacet + facet normal -0.7231 0.286847 0.628367 + outer loop + vertex -908.151 419.684 16.4088 + vertex -909.957 414.673 16.6183 + vertex -907.799 417.286 17.9083 + endloop + endfacet + facet normal -0.693117 0.26338 0.670984 + outer loop + vertex -911.863 410.169 16.4173 + vertex -911.308 407.831 17.9083 + vertex -909.957 414.673 16.6183 + endloop + endfacet + facet normal -0.709657 0.263346 0.65348 + outer loop + vertex -911.308 407.831 17.9083 + vertex -907.799 417.286 17.9083 + vertex -909.957 414.673 16.6183 + endloop + endfacet + facet normal -0.750396 0.310255 0.58365 + outer loop + vertex -904.406 428.899 16.3942 + vertex -906.254 424.024 16.6102 + vertex -904.194 426.571 17.9047 + endloop + endfacet + facet normal -0.723011 0.286907 0.628443 + outer loop + vertex -908.151 419.684 16.4088 + vertex -907.799 417.286 17.9083 + vertex -906.254 424.024 16.6102 + endloop + endfacet + facet normal -0.738341 0.286937 0.610345 + outer loop + vertex -907.799 417.286 17.9083 + vertex -904.194 426.571 17.9047 + vertex -906.254 424.024 16.6102 + endloop + endfacet + facet normal -0.779642 0.328302 0.53327 + outer loop + vertex -900.426 438.338 16.4462 + vertex -902.445 433.272 16.6123 + vertex -900.395 435.985 17.9391 + endloop + endfacet + facet normal -0.752823 0.308579 0.581409 + outer loop + vertex -904.406 428.899 16.3942 + vertex -904.194 426.571 17.9047 + vertex -902.445 433.272 16.6123 + endloop + endfacet + facet normal -0.769944 0.308631 0.55851 + outer loop + vertex -904.194 426.571 17.9047 + vertex -900.395 435.985 17.9391 + vertex -902.445 433.272 16.6123 + endloop + endfacet + facet normal -0.788374 0.346726 0.508181 + outer loop + vertex -896.385 447.544 16.5906 + vertex -898.328 442.921 16.731 + vertex -896.37 445.685 17.8816 + endloop + endfacet + facet normal -0.783366 0.325767 0.529352 + outer loop + vertex -900.426 438.338 16.4462 + vertex -900.395 435.985 17.9391 + vertex -898.328 442.921 16.731 + endloop + endfacet + facet normal -0.776675 0.325502 0.539282 + outer loop + vertex -900.395 435.985 17.9391 + vertex -896.37 445.685 17.8816 + vertex -898.328 442.921 16.731 + endloop + endfacet + facet normal -0.848649 0.372 0.376046 + outer loop + vertex -892.199 455.167 17.9157 + vertex -893.823 453.78 15.6215 + vertex -896.37 445.685 17.8816 + endloop + endfacet + facet normal -0.728283 0.387034 0.565516 + outer loop + vertex -896.37 445.685 17.8816 + vertex -893.823 453.78 15.6215 + vertex -896.385 447.544 16.5906 + endloop + endfacet + facet normal -0.864215 0.387069 0.321417 + outer loop + vertex -887.969 464.578 17.9538 + vertex -889.287 463.608 15.5788 + vertex -892.199 455.167 17.9157 + endloop + endfacet + facet normal -0.845791 0.39194 0.361968 + outer loop + vertex -892.199 455.167 17.9157 + vertex -889.287 463.608 15.5788 + vertex -893.823 453.78 15.6215 + endloop + endfacet + facet normal -0.869267 0.407953 0.279194 + outer loop + vertex -883.606 473.86 17.9761 + vertex -884.77 473.009 15.5965 + vertex -887.969 464.578 17.9538 + endloop + endfacet + facet normal -0.857798 0.411609 0.307833 + outer loop + vertex -887.969 464.578 17.9538 + vertex -884.77 473.009 15.5965 + vertex -889.287 463.608 15.5788 + endloop + endfacet + facet normal -0.887768 0.412864 0.203499 + outer loop + vertex -879.148 483.399 18.0727 + vertex -880.112 482.514 15.6617 + vertex -883.606 473.86 17.9761 + endloop + endfacet + facet normal -0.86485 0.421939 0.272032 + outer loop + vertex -883.606 473.86 17.9761 + vertex -880.112 482.514 15.6617 + vertex -884.77 473.009 15.5965 + endloop + endfacet + facet normal -0.899544 0.346117 0.266504 + outer loop + vertex -875.213 493.382 18.3889 + vertex -875.708 493.534 16.5196 + vertex -879.148 483.399 18.0727 + endloop + endfacet + facet normal -0.908395 0.344573 0.236828 + outer loop + vertex -879.148 483.399 18.0727 + vertex -875.708 493.534 16.5196 + vertex -880.112 482.514 15.6617 + endloop + endfacet + facet normal -0.524877 -0.458637 0.717047 + outer loop + vertex -878.936 193.441 13.0615 + vertex -878.187 192.787 13.1916 + vertex -878.303 194.413 14.1466 + endloop + endfacet + facet normal -0.511209 -0.479488 0.713272 + outer loop + vertex -877.704 191.946 12.9723 + vertex -877.02 192.798 14.0353 + vertex -878.187 192.787 13.1916 + endloop + endfacet + facet normal -0.517212 -0.460609 0.72134 + outer loop + vertex -877.02 192.798 14.0353 + vertex -878.303 194.413 14.1466 + vertex -878.187 192.787 13.1916 + endloop + endfacet + facet normal -0.42245 -0.365914 0.829242 + outer loop + vertex -877.762 196.586 15.3808 + vertex -878.303 194.413 14.1466 + vertex -876.335 194.419 15.1516 + endloop + endfacet + facet normal -0.418159 -0.388781 0.820971 + outer loop + vertex -876.335 194.419 15.1516 + vertex -878.303 194.413 14.1466 + vertex -877.02 192.798 14.0353 + endloop + endfacet + facet normal -0.479873 -0.445567 0.755773 + outer loop + vertex -884.713 199.473 13.0602 + vertex -882.842 197.734 13.223 + vertex -883.154 199.794 14.2392 + endloop + endfacet + facet normal -0.479645 -0.470333 0.740762 + outer loop + vertex -881.41 196.02 13.0617 + vertex -880.32 196.731 14.219 + vertex -882.842 197.734 13.223 + endloop + endfacet + facet normal -0.476605 -0.445973 0.757599 + outer loop + vertex -880.32 196.731 14.219 + vertex -883.154 199.794 14.2392 + vertex -882.842 197.734 13.223 + endloop + endfacet + facet normal -0.386635 -0.354794 0.851255 + outer loop + vertex -882.369 202.033 15.5291 + vertex -883.154 199.794 14.2392 + vertex -879.7 199.054 15.4995 + endloop + endfacet + facet normal -0.387095 -0.363745 0.847258 + outer loop + vertex -879.7 199.054 15.4995 + vertex -883.154 199.794 14.2392 + vertex -880.32 196.731 14.219 + endloop + endfacet + facet normal -0.403012 -0.356985 0.8427 + outer loop + vertex -879.7 199.054 15.4995 + vertex -880.32 196.731 14.219 + vertex -877.762 196.586 15.3808 + endloop + endfacet + facet normal -0.400919 -0.375022 0.835837 + outer loop + vertex -877.762 196.586 15.3808 + vertex -880.32 196.731 14.219 + vertex -878.303 194.413 14.1466 + endloop + endfacet + facet normal -0.488642 -0.458765 0.742134 + outer loop + vertex -881.41 196.02 13.0617 + vertex -879.919 194.683 13.2166 + vertex -880.32 196.731 14.219 + endloop + endfacet + facet normal -0.495786 -0.482882 0.721818 + outer loop + vertex -878.936 193.441 13.0615 + vertex -878.303 194.413 14.1466 + vertex -879.919 194.683 13.2166 + endloop + endfacet + facet normal -0.499492 -0.457669 0.735559 + outer loop + vertex -878.303 194.413 14.1466 + vertex -880.32 196.731 14.219 + vertex -879.919 194.683 13.2166 + endloop + endfacet + facet normal -0.499915 -0.432526 0.750337 + outer loop + vertex -891.698 207.176 13.0537 + vertex -889.764 205.217 13.2132 + vertex -889.879 207.122 14.235 + endloop + endfacet + facet normal -0.484437 -0.443048 0.75434 + outer loop + vertex -888.237 203.277 13.0545 + vertex -886.446 203.332 14.2367 + vertex -889.764 205.217 13.2132 + endloop + endfacet + facet normal -0.482282 -0.436411 0.759572 + outer loop + vertex -886.446 203.332 14.2367 + vertex -889.879 207.122 14.235 + vertex -889.764 205.217 13.2132 + endloop + endfacet + facet normal -0.390339 -0.354552 0.849664 + outer loop + vertex -888.943 209.185 15.5256 + vertex -889.879 207.122 14.235 + vertex -885.554 205.452 15.5248 + endloop + endfacet + facet normal -0.389919 -0.352731 0.850614 + outer loop + vertex -885.554 205.452 15.5248 + vertex -889.879 207.122 14.235 + vertex -886.446 203.332 14.2367 + endloop + endfacet + facet normal -0.383555 -0.35627 0.852031 + outer loop + vertex -885.554 205.452 15.5248 + vertex -886.446 203.332 14.2367 + vertex -882.369 202.033 15.5291 + endloop + endfacet + facet normal -0.383561 -0.356308 0.852013 + outer loop + vertex -882.369 202.033 15.5291 + vertex -886.446 203.332 14.2367 + vertex -883.154 199.794 14.2392 + endloop + endfacet + facet normal -0.485293 -0.440129 0.755498 + outer loop + vertex -888.237 203.277 13.0545 + vertex -886.258 201.368 13.213 + vertex -886.446 203.332 14.2367 + endloop + endfacet + facet normal -0.47769 -0.450498 0.754231 + outer loop + vertex -884.713 199.473 13.0602 + vertex -883.154 199.794 14.2392 + vertex -886.258 201.368 13.213 + endloop + endfacet + facet normal -0.475467 -0.441896 0.760696 + outer loop + vertex -883.154 199.794 14.2392 + vertex -886.446 203.332 14.2367 + vertex -886.258 201.368 13.213 + endloop + endfacet + facet normal -0.522367 -0.41827 0.74309 + outer loop + vertex -898.314 215.096 13.0736 + vertex -896.446 213.037 13.2279 + vertex -896.608 215.065 14.2554 + endloop + endfacet + facet normal -0.508764 -0.429416 0.746164 + outer loop + vertex -895.01 211.053 13.0654 + vertex -893.263 211.027 14.2413 + vertex -896.446 213.037 13.2279 + endloop + endfacet + facet normal -0.505908 -0.421712 0.752474 + outer loop + vertex -893.263 211.027 14.2413 + vertex -896.608 215.065 14.2554 + vertex -896.446 213.037 13.2279 + endloop + endfacet + facet normal -0.409941 -0.341546 0.845751 + outer loop + vertex -895.71 217.194 15.5508 + vertex -896.608 215.065 14.2554 + vertex -892.352 213.124 15.5347 + endloop + endfacet + facet normal -0.410324 -0.342859 0.845033 + outer loop + vertex -892.352 213.124 15.5347 + vertex -896.608 215.065 14.2554 + vertex -893.263 211.027 14.2413 + endloop + endfacet + facet normal -0.40055 -0.348561 0.847387 + outer loop + vertex -892.352 213.124 15.5347 + vertex -893.263 211.027 14.2413 + vertex -888.943 209.185 15.5256 + endloop + endfacet + facet normal -0.400538 -0.348515 0.847412 + outer loop + vertex -888.943 209.185 15.5256 + vertex -893.263 211.027 14.2413 + vertex -889.879 207.122 14.235 + endloop + endfacet + facet normal -0.509338 -0.427159 0.747068 + outer loop + vertex -895.01 211.053 13.0654 + vertex -893.149 209.099 13.2166 + vertex -893.263 211.027 14.2413 + endloop + endfacet + facet normal -0.498279 -0.439248 0.747515 + outer loop + vertex -891.698 207.176 13.0537 + vertex -889.879 207.122 14.235 + vertex -893.149 209.099 13.2166 + endloop + endfacet + facet normal -0.49516 -0.430382 0.75471 + outer loop + vertex -889.879 207.122 14.235 + vertex -893.263 211.027 14.2413 + vertex -893.149 209.099 13.2166 + endloop + endfacet + facet normal -0.545353 -0.399936 0.736642 + outer loop + vertex -904.916 223.703 13.0938 + vertex -903.109 221.527 13.2499 + vertex -903.154 223.502 14.289 + endloop + endfacet + facet normal -0.532578 -0.413317 0.7386 + outer loop + vertex -901.678 219.387 13.084 + vertex -899.931 219.257 14.2713 + vertex -903.109 221.527 13.2499 + endloop + endfacet + facet normal -0.528755 -0.404564 0.746154 + outer loop + vertex -899.931 219.257 14.2713 + vertex -903.154 223.502 14.289 + vertex -903.109 221.527 13.2499 + endloop + endfacet + facet normal -0.432408 -0.332593 0.838096 + outer loop + vertex -902.166 225.536 15.6059 + vertex -903.154 223.502 14.289 + vertex -898.997 221.346 15.5781 + endloop + endfacet + facet normal -0.432045 -0.331527 0.838705 + outer loop + vertex -898.997 221.346 15.5781 + vertex -903.154 223.502 14.289 + vertex -899.931 219.257 14.2713 + endloop + endfacet + facet normal -0.420568 -0.338552 0.841728 + outer loop + vertex -898.997 221.346 15.5781 + vertex -899.931 219.257 14.2713 + vertex -895.71 217.194 15.5508 + endloop + endfacet + facet normal -0.419717 -0.335886 0.843219 + outer loop + vertex -895.71 217.194 15.5508 + vertex -899.931 219.257 14.2713 + vertex -896.608 215.065 14.2554 + endloop + endfacet + facet normal -0.533078 -0.410873 0.739602 + outer loop + vertex -901.678 219.387 13.084 + vertex -899.788 217.209 13.2368 + vertex -899.931 219.257 14.2713 + endloop + endfacet + facet normal -0.521656 -0.421108 0.741986 + outer loop + vertex -898.314 215.096 13.0736 + vertex -896.608 215.065 14.2554 + vertex -899.788 217.209 13.2368 + endloop + endfacet + facet normal -0.518811 -0.414074 0.747915 + outer loop + vertex -896.608 215.065 14.2554 + vertex -899.931 219.257 14.2713 + vertex -899.788 217.209 13.2368 + endloop + endfacet + facet normal -0.566828 -0.376494 0.732774 + outer loop + vertex -910.835 232.193 13.1188 + vertex -909.182 230.006 13.2737 + vertex -909.142 231.992 14.325 + endloop + endfacet + facet normal -0.555275 -0.391809 0.733591 + outer loop + vertex -907.931 227.917 13.1051 + vertex -906.211 227.727 14.3054 + vertex -909.182 230.006 13.2737 + endloop + endfacet + facet normal -0.550651 -0.381849 0.742277 + outer loop + vertex -906.211 227.727 14.3054 + vertex -909.142 231.992 14.325 + vertex -909.182 230.006 13.2737 + endloop + endfacet + facet normal -0.453379 -0.315178 0.833733 + outer loop + vertex -908.095 234.01 15.6574 + vertex -909.142 231.992 14.325 + vertex -905.193 229.756 15.6268 + endloop + endfacet + facet normal -0.453499 -0.315499 0.833546 + outer loop + vertex -905.193 229.756 15.6268 + vertex -909.142 231.992 14.325 + vertex -906.211 227.727 14.3054 + endloop + endfacet + facet normal -0.443483 -0.322327 0.836318 + outer loop + vertex -905.193 229.756 15.6268 + vertex -906.211 227.727 14.3054 + vertex -902.166 225.536 15.6059 + endloop + endfacet + facet normal -0.444344 -0.324743 0.834925 + outer loop + vertex -902.166 225.536 15.6059 + vertex -906.211 227.727 14.3054 + vertex -903.154 223.502 14.289 + endloop + endfacet + facet normal -0.555971 -0.38771 0.735239 + outer loop + vertex -907.931 227.917 13.1051 + vertex -906.234 225.781 13.2619 + vertex -906.211 227.727 14.3054 + endloop + endfacet + facet normal -0.54452 -0.404807 0.734595 + outer loop + vertex -904.916 223.703 13.0938 + vertex -903.154 223.502 14.289 + vertex -906.234 225.781 13.2619 + endloop + endfacet + facet normal -0.539225 -0.393046 0.744817 + outer loop + vertex -903.154 223.502 14.289 + vertex -906.211 227.727 14.3054 + vertex -906.234 225.781 13.2619 + endloop + endfacet + facet normal -0.589561 -0.349849 0.728027 + outer loop + vertex -916.315 240.985 13.1449 + vertex -914.813 238.777 13.2996 + vertex -914.617 240.654 14.3604 + endloop + endfacet + facet normal -0.57774 -0.362069 0.73152 + outer loop + vertex -913.672 236.618 13.1322 + vertex -911.963 236.335 14.342 + vertex -914.813 238.777 13.2996 + endloop + endfacet + facet normal -0.574707 -0.35631 0.736719 + outer loop + vertex -911.963 236.335 14.342 + vertex -914.617 240.654 14.3604 + vertex -914.813 238.777 13.2996 + endloop + endfacet + facet normal -0.478745 -0.298755 0.82556 + outer loop + vertex -913.436 242.516 15.7192 + vertex -914.617 240.654 14.3604 + vertex -910.849 238.279 15.6865 + endloop + endfacet + facet normal -0.478165 -0.297368 0.826396 + outer loop + vertex -910.849 238.279 15.6865 + vertex -914.617 240.654 14.3604 + vertex -911.963 236.335 14.342 + endloop + endfacet + facet normal -0.466359 -0.306489 0.829804 + outer loop + vertex -910.849 238.279 15.6865 + vertex -911.963 236.335 14.342 + vertex -908.095 234.01 15.6574 + endloop + endfacet + facet normal -0.466199 -0.306089 0.830041 + outer loop + vertex -908.095 234.01 15.6574 + vertex -911.963 236.335 14.342 + vertex -909.142 231.992 14.325 + endloop + endfacet + facet normal -0.577645 -0.362871 0.731198 + outer loop + vertex -913.672 236.618 13.1322 + vertex -912.059 234.361 13.2869 + vertex -911.963 236.335 14.342 + endloop + endfacet + facet normal -0.566784 -0.376769 0.732667 + outer loop + vertex -910.835 232.193 13.1188 + vertex -909.142 231.992 14.325 + vertex -912.059 234.361 13.2869 + endloop + endfacet + facet normal -0.562612 -0.368367 0.740117 + outer loop + vertex -909.142 231.992 14.325 + vertex -911.963 236.335 14.342 + vertex -912.059 234.361 13.2869 + endloop + endfacet + facet normal -0.615309 -0.319816 0.720495 + outer loop + vertex -921.029 249.562 13.1722 + vertex -919.679 247.313 13.3275 + vertex -919.418 249.231 14.4014 + endloop + endfacet + facet normal -0.604207 -0.335326 0.722835 + outer loop + vertex -918.717 245.211 13.1567 + vertex -917.081 244.907 14.3824 + vertex -919.679 247.313 13.3275 + endloop + endfacet + facet normal -0.599775 -0.327336 0.730151 + outer loop + vertex -917.081 244.907 14.3824 + vertex -919.418 249.231 14.4014 + vertex -919.679 247.313 13.3275 + endloop + endfacet + facet normal -0.500099 -0.273062 0.821789 + outer loop + vertex -918.158 251.049 15.7726 + vertex -919.418 249.231 14.4014 + vertex -915.857 246.746 15.7429 + endloop + endfacet + facet normal -0.500604 -0.274145 0.821122 + outer loop + vertex -915.857 246.746 15.7429 + vertex -919.418 249.231 14.4014 + vertex -917.081 244.907 14.3824 + endloop + endfacet + facet normal -0.488975 -0.284467 0.82461 + outer loop + vertex -915.857 246.746 15.7429 + vertex -917.081 244.907 14.3824 + vertex -913.436 242.516 15.7192 + endloop + endfacet + facet normal -0.490768 -0.288602 0.822104 + outer loop + vertex -913.436 242.516 15.7192 + vertex -917.081 244.907 14.3824 + vertex -914.617 240.654 14.3604 + endloop + endfacet + facet normal -0.604133 -0.336074 0.72255 + outer loop + vertex -918.717 245.211 13.1567 + vertex -917.332 243.058 13.3129 + vertex -917.081 244.907 14.3824 + endloop + endfacet + facet normal -0.589694 -0.34844 0.728595 + outer loop + vertex -916.315 240.985 13.1449 + vertex -914.617 240.654 14.3604 + vertex -917.332 243.058 13.3129 + endloop + endfacet + facet normal -0.587375 -0.344115 0.732513 + outer loop + vertex -914.617 240.654 14.3604 + vertex -917.081 244.907 14.3824 + vertex -917.332 243.058 13.3129 + endloop + endfacet + facet normal -0.640453 -0.280133 0.715084 + outer loop + vertex -925.456 258.942 13.1985 + vertex -924.206 256.495 13.3595 + vertex -923.815 258.373 14.4454 + endloop + endfacet + facet normal -0.626692 -0.299433 0.719442 + outer loop + vertex -923.308 254.196 13.185 + vertex -921.672 253.737 14.4184 + vertex -924.206 256.495 13.3595 + endloop + endfacet + facet normal -0.621212 -0.291313 0.727484 + outer loop + vertex -921.672 253.737 14.4184 + vertex -923.815 258.373 14.4454 + vertex -924.206 256.495 13.3595 + endloop + endfacet + facet normal -0.524551 -0.244569 0.815495 + outer loop + vertex -922.433 260.074 15.8442 + vertex -923.815 258.373 14.4454 + vertex -920.352 255.487 15.8071 + endloop + endfacet + facet normal -0.526544 -0.248066 0.813151 + outer loop + vertex -920.352 255.487 15.8071 + vertex -923.815 258.373 14.4454 + vertex -921.672 253.737 14.4184 + endloop + endfacet + facet normal -0.51414 -0.260599 0.817159 + outer loop + vertex -920.352 255.487 15.8071 + vertex -921.672 253.737 14.4184 + vertex -918.158 251.049 15.7726 + endloop + endfacet + facet normal -0.513927 -0.260186 0.817424 + outer loop + vertex -918.158 251.049 15.7726 + vertex -921.672 253.737 14.4184 + vertex -919.418 249.231 14.4014 + endloop + endfacet + facet normal -0.626669 -0.300554 0.718994 + outer loop + vertex -923.308 254.196 13.185 + vertex -921.979 251.801 13.342 + vertex -921.672 253.737 14.4184 + endloop + endfacet + facet normal -0.615629 -0.315777 0.722002 + outer loop + vertex -921.029 249.562 13.1722 + vertex -919.418 249.231 14.4014 + vertex -921.979 251.801 13.342 + endloop + endfacet + facet normal -0.611183 -0.308509 0.728888 + outer loop + vertex -919.418 249.231 14.4014 + vertex -921.672 253.737 14.4184 + vertex -921.979 251.801 13.342 + endloop + endfacet + facet normal -0.660914 -0.233043 0.713361 + outer loop + vertex -929.225 268.625 13.231 + vertex -928.144 266.057 13.3933 + vertex -927.645 268.002 14.4914 + endloop + endfacet + facet normal -0.650106 -0.255951 0.715438 + outer loop + vertex -927.416 263.705 13.2143 + vertex -925.801 263.112 14.4693 + vertex -928.144 266.057 13.3933 + endloop + endfacet + facet normal -0.641866 -0.245351 0.726506 + outer loop + vertex -925.801 263.112 14.4693 + vertex -927.645 268.002 14.4914 + vertex -928.144 266.057 13.3933 + endloop + endfacet + facet normal -0.552591 -0.214371 0.805412 + outer loop + vertex -926.241 269.683 15.9024 + vertex -927.645 268.002 14.4914 + vertex -924.396 264.814 15.8726 + endloop + endfacet + facet normal -0.550496 -0.21126 0.807665 + outer loop + vertex -924.396 264.814 15.8726 + vertex -927.645 268.002 14.4914 + vertex -925.801 263.112 14.4693 + endloop + endfacet + facet normal -0.536556 -0.226972 0.812768 + outer loop + vertex -924.396 264.814 15.8726 + vertex -925.801 263.112 14.4693 + vertex -922.433 260.074 15.8442 + endloop + endfacet + facet normal -0.538232 -0.229677 0.810898 + outer loop + vertex -922.433 260.074 15.8442 + vertex -925.801 263.112 14.4693 + vertex -923.815 258.373 14.4454 + endloop + endfacet + facet normal -0.650332 -0.260414 0.71362 + outer loop + vertex -927.416 263.705 13.2143 + vertex -926.256 261.241 13.3718 + vertex -925.801 263.112 14.4693 + endloop + endfacet + facet normal -0.640355 -0.276917 0.716423 + outer loop + vertex -925.456 258.942 13.1985 + vertex -923.815 258.373 14.4454 + vertex -926.256 261.241 13.3718 + endloop + endfacet + facet normal -0.635279 -0.269916 0.723579 + outer loop + vertex -923.815 258.373 14.4454 + vertex -925.801 263.112 14.4693 + vertex -926.256 261.241 13.3718 + endloop + endfacet + facet normal -0.691699 -0.190105 0.696715 + outer loop + vertex -932.365 278.928 13.2647 + vertex -931.469 276.254 13.4249 + vertex -930.871 278.146 14.5345 + endloop + endfacet + facet normal -0.67573 -0.206288 0.707697 + outer loop + vertex -930.893 273.757 13.2474 + vertex -929.35 273.049 14.5143 + vertex -931.469 276.254 13.4249 + endloop + endfacet + facet normal -0.673544 -0.2039 0.710467 + outer loop + vertex -929.35 273.049 14.5143 + vertex -930.871 278.146 14.5345 + vertex -931.469 276.254 13.4249 + endloop + endfacet + facet normal -0.586493 -0.180188 0.789657 + outer loop + vertex -929.404 279.575 15.9508 + vertex -930.871 278.146 14.5345 + vertex -927.925 274.625 15.9194 + endloop + endfacet + facet normal -0.584415 -0.177615 0.791778 + outer loop + vertex -927.925 274.625 15.9194 + vertex -930.871 278.146 14.5345 + vertex -929.35 273.049 14.5143 + endloop + endfacet + facet normal -0.56944 -0.196814 0.798124 + outer loop + vertex -927.925 274.625 15.9194 + vertex -929.35 273.049 14.5143 + vertex -926.241 269.683 15.9024 + endloop + endfacet + facet normal -0.568581 -0.195651 0.799022 + outer loop + vertex -926.241 269.683 15.9024 + vertex -929.35 273.049 14.5143 + vertex -927.645 268.002 14.4914 + endloop + endfacet + facet normal -0.676554 -0.213137 0.704874 + outer loop + vertex -930.893 273.757 13.2474 + vertex -929.886 271.091 13.4071 + vertex -929.35 273.049 14.5143 + endloop + endfacet + facet normal -0.66053 -0.228168 0.715289 + outer loop + vertex -929.225 268.625 13.231 + vertex -927.645 268.002 14.4914 + vertex -929.886 271.091 13.4071 + endloop + endfacet + facet normal -0.658357 -0.225605 0.718101 + outer loop + vertex -927.645 268.002 14.4914 + vertex -929.35 273.049 14.5143 + vertex -929.886 271.091 13.4071 + endloop + endfacet + facet normal -0.724379 -0.137823 0.675485 + outer loop + vertex -934.587 288.931 13.2877 + vertex -933.95 286.389 13.4516 + vertex -933.23 288.095 14.5713 + endloop + endfacet + facet normal -0.706078 -0.155837 0.690774 + outer loop + vertex -933.597 284.012 13.2765 + vertex -932.168 283.18 14.5495 + vertex -933.95 286.389 13.4516 + endloop + endfacet + facet normal -0.705962 -0.155723 0.690918 + outer loop + vertex -932.168 283.18 14.5495 + vertex -933.23 288.095 14.5713 + vertex -933.95 286.389 13.4516 + endloop + endfacet + facet normal -0.611138 -0.134448 0.780022 + outer loop + vertex -931.683 289.436 16.0146 + vertex -933.23 288.095 14.5713 + vertex -930.651 284.525 15.9771 + endloop + endfacet + facet normal -0.612439 -0.135889 0.77875 + outer loop + vertex -930.651 284.525 15.9771 + vertex -933.23 288.095 14.5713 + vertex -932.168 283.18 14.5495 + endloop + endfacet + facet normal -0.600434 -0.155455 0.784419 + outer loop + vertex -930.651 284.525 15.9771 + vertex -932.168 283.18 14.5495 + vertex -929.404 279.575 15.9508 + endloop + endfacet + facet normal -0.602081 -0.157357 0.782775 + outer loop + vertex -929.404 279.575 15.9508 + vertex -932.168 283.18 14.5495 + vertex -930.871 278.146 14.5345 + endloop + endfacet + facet normal -0.70773 -0.164274 0.687119 + outer loop + vertex -933.597 284.012 13.2765 + vertex -932.829 281.383 13.4385 + vertex -932.168 283.18 14.5495 + endloop + endfacet + facet normal -0.69006 -0.179987 0.701015 + outer loop + vertex -932.365 278.928 13.2647 + vertex -930.871 278.146 14.5345 + vertex -932.829 281.383 13.4385 + endloop + endfacet + facet normal -0.689773 -0.179692 0.701373 + outer loop + vertex -930.871 278.146 14.5345 + vertex -932.168 283.18 14.5495 + vertex -932.829 281.383 13.4385 + endloop + endfacet + facet normal -0.746318 -0.078517 0.660942 + outer loop + vertex -935.92 298.661 13.3091 + vertex -935.5 296.061 13.4747 + vertex -934.68 297.841 14.6128 + endloop + endfacet + facet normal -0.731371 -0.0979086 0.674915 + outer loop + vertex -935.349 293.722 13.2987 + vertex -934.053 292.927 14.5877 + vertex -935.5 296.061 13.4747 + endloop + endfacet + facet normal -0.729693 -0.0964137 0.676944 + outer loop + vertex -934.053 292.927 14.5877 + vertex -934.68 297.841 14.6128 + vertex -935.5 296.061 13.4747 + endloop + endfacet + facet normal -0.635197 -0.0833011 0.767845 + outer loop + vertex -933.089 299.221 16.0779 + vertex -934.68 297.841 14.6128 + vertex -932.484 294.304 16.045 + endloop + endfacet + facet normal -0.636949 -0.0850554 0.766199 + outer loop + vertex -932.484 294.304 16.045 + vertex -934.68 297.841 14.6128 + vertex -934.053 292.927 14.5877 + endloop + endfacet + facet normal -0.624251 -0.107549 0.773785 + outer loop + vertex -932.484 294.304 16.045 + vertex -934.053 292.927 14.5877 + vertex -931.683 289.436 16.0146 + endloop + endfacet + facet normal -0.625805 -0.109213 0.772296 + outer loop + vertex -931.683 289.436 16.0146 + vertex -934.053 292.927 14.5877 + vertex -933.23 288.095 14.5713 + endloop + endfacet + facet normal -0.733626 -0.108092 0.670902 + outer loop + vertex -935.349 293.722 13.2987 + vertex -934.831 291.226 13.4634 + vertex -934.053 292.927 14.5877 + endloop + endfacet + facet normal -0.722486 -0.128985 0.679247 + outer loop + vertex -934.587 288.931 13.2877 + vertex -933.23 288.095 14.5713 + vertex -934.831 291.226 13.4634 + endloop + endfacet + facet normal -0.71785 -0.124595 0.684958 + outer loop + vertex -933.23 288.095 14.5713 + vertex -934.053 292.927 14.5877 + vertex -934.831 291.226 13.4634 + endloop + endfacet + facet normal -0.763328 -0.0189761 0.645733 + outer loop + vertex -936.496 309.109 13.3322 + vertex -936.286 306.376 13.5002 + vertex -935.366 308.108 14.6394 + endloop + endfacet + facet normal -0.754689 -0.0417369 0.654754 + outer loop + vertex -936.305 303.869 13.3192 + vertex -935.116 302.937 14.6298 + vertex -936.286 306.376 13.5002 + endloop + endfacet + facet normal -0.748696 -0.0373635 0.66186 + outer loop + vertex -935.116 302.937 14.6298 + vertex -935.366 308.108 14.6394 + vertex -936.286 306.376 13.5002 + endloop + endfacet + facet normal -0.66 -0.0335703 0.750515 + outer loop + vertex -933.756 309.323 16.1091 + vertex -935.366 308.108 14.6394 + vertex -933.515 304.238 16.0938 + endloop + endfacet + facet normal -0.659583 -0.0332276 0.750897 + outer loop + vertex -933.515 304.238 16.0938 + vertex -935.366 308.108 14.6394 + vertex -935.116 302.937 14.6298 + endloop + endfacet + facet normal -0.647892 -0.0573744 0.759568 + outer loop + vertex -933.515 304.238 16.0938 + vertex -935.116 302.937 14.6298 + vertex -933.089 299.221 16.0779 + endloop + endfacet + facet normal -0.648714 -0.0581184 0.75881 + outer loop + vertex -933.089 299.221 16.0779 + vertex -935.116 302.937 14.6298 + vertex -934.68 297.841 14.6128 + endloop + endfacet + facet normal -0.755898 -0.0456023 0.6531 + outer loop + vertex -936.305 303.869 13.3192 + vertex -935.992 301.132 13.4897 + vertex -935.116 302.937 14.6298 + endloop + endfacet + facet normal -0.744256 -0.0702291 0.664192 + outer loop + vertex -935.92 298.661 13.3091 + vertex -934.68 297.841 14.6128 + vertex -935.992 301.132 13.4897 + endloop + endfacet + facet normal -0.738402 -0.0655119 0.671171 + outer loop + vertex -934.68 297.841 14.6128 + vertex -935.116 302.937 14.6298 + vertex -935.992 301.132 13.4897 + endloop + endfacet + facet normal -0.791254 0.0417853 0.610058 + outer loop + vertex -936.284 319.378 13.3325 + vertex -936.288 316.675 13.5134 + vertex -935.313 318.425 14.6579 + endloop + endfacet + facet normal -0.774732 0.0158867 0.63209 + outer loop + vertex -936.482 314.24 13.3369 + vertex -935.431 313.256 14.6494 + vertex -936.288 316.675 13.5134 + endloop + endfacet + facet normal -0.773588 0.0166318 0.63347 + outer loop + vertex -935.431 313.256 14.6494 + vertex -935.313 318.425 14.6579 + vertex -936.288 316.675 13.5134 + endloop + endfacet + facet normal -0.687614 0.0101454 0.726006 + outer loop + vertex -933.716 319.72 16.1526 + vertex -935.313 318.425 14.6579 + vertex -933.818 314.488 16.1283 + endloop + endfacet + facet normal -0.681793 0.014371 0.731404 + outer loop + vertex -933.818 314.488 16.1283 + vertex -935.313 318.425 14.6579 + vertex -935.431 313.256 14.6494 + endloop + endfacet + facet normal -0.671361 -0.0108485 0.741051 + outer loop + vertex -933.818 314.488 16.1283 + vertex -935.431 313.256 14.6494 + vertex -933.756 309.323 16.1091 + endloop + endfacet + facet normal -0.670181 -0.00994526 0.742131 + outer loop + vertex -933.756 309.323 16.1091 + vertex -935.431 313.256 14.6494 + vertex -935.366 308.108 14.6394 + endloop + endfacet + facet normal -0.776966 0.0100014 0.629463 + outer loop + vertex -936.482 314.24 13.3369 + vertex -936.378 311.561 13.5078 + vertex -935.431 313.256 14.6494 + endloop + endfacet + facet normal -0.759965 -0.00975242 0.649891 + outer loop + vertex -936.496 309.109 13.3322 + vertex -935.366 308.108 14.6394 + vertex -936.378 311.561 13.5078 + endloop + endfacet + facet normal -0.761684 -0.0109228 0.647857 + outer loop + vertex -935.366 308.108 14.6394 + vertex -935.431 313.256 14.6494 + vertex -936.378 311.561 13.5078 + endloop + endfacet + facet normal -0.798988 0.0984855 0.593228 + outer loop + vertex -935.296 329.724 13.4981 + vertex -935.523 327.246 13.6041 + vertex -934.527 329.003 14.6534 + endloop + endfacet + facet normal -0.798553 0.064552 0.598453 + outer loop + vertex -935.9 324.698 13.3752 + vertex -935.003 323.695 14.68 + vertex -935.523 327.246 13.6041 + endloop + endfacet + facet normal -0.781833 0.0732713 0.619167 + outer loop + vertex -935.003 323.695 14.68 + vertex -934.527 329.003 14.6534 + vertex -935.523 327.246 13.6041 + endloop + endfacet + facet normal -0.72598 0.0606069 0.68504 + outer loop + vertex -932.951 330.12 16.2252 + vertex -934.527 329.003 14.6534 + vertex -933.428 324.95 16.1771 + endloop + endfacet + facet normal -0.714987 0.067655 0.695857 + outer loop + vertex -933.428 324.95 16.1771 + vertex -934.527 329.003 14.6534 + vertex -935.003 323.695 14.68 + endloop + endfacet + facet normal -0.703015 0.0353948 0.710294 + outer loop + vertex -933.428 324.95 16.1771 + vertex -935.003 323.695 14.68 + vertex -933.716 319.72 16.1526 + endloop + endfacet + facet normal -0.69906 0.0380673 0.714049 + outer loop + vertex -933.716 319.72 16.1526 + vertex -935.003 323.695 14.68 + vertex -935.313 318.425 14.6579 + endloop + endfacet + facet normal -0.799991 0.0612205 0.596881 + outer loop + vertex -935.9 324.698 13.3752 + vertex -936.008 321.891 13.5188 + vertex -935.003 323.695 14.68 + endloop + endfacet + facet normal -0.791219 0.0418764 0.610098 + outer loop + vertex -936.284 319.378 13.3325 + vertex -935.313 318.425 14.6579 + vertex -936.008 321.891 13.5188 + endloop + endfacet + facet normal -0.788199 0.0437201 0.613866 + outer loop + vertex -935.313 318.425 14.6579 + vertex -935.003 323.695 14.68 + vertex -936.008 321.891 13.5188 + endloop + endfacet + facet normal -0.870238 0.125327 0.476423 + outer loop + vertex -933.006 339.342 14.7927 + vertex -934.2 338.339 12.8752 + vertex -933.776 334.186 14.7413 + endloop + endfacet + facet normal -0.857675 0.135422 0.496039 + outer loop + vertex -933.776 334.186 14.7413 + vertex -934.2 338.339 12.8752 + vertex -935.045 332.993 12.8736 + endloop + endfacet + facet normal -0.76921 0.103714 0.630523 + outer loop + vertex -931.628 340.256 16.3229 + vertex -933.006 339.342 14.7927 + vertex -932.338 335.219 16.2858 + endloop + endfacet + facet normal -0.762347 0.107593 0.638162 + outer loop + vertex -932.338 335.219 16.2858 + vertex -933.006 339.342 14.7927 + vertex -933.776 334.186 14.7413 + endloop + endfacet + facet normal -0.756329 0.0831936 0.64888 + outer loop + vertex -932.338 335.219 16.2858 + vertex -933.776 334.186 14.7413 + vertex -932.951 330.12 16.2252 + endloop + endfacet + facet normal -0.735884 0.0951955 0.670382 + outer loop + vertex -932.951 330.12 16.2252 + vertex -933.776 334.186 14.7413 + vertex -934.527 329.003 14.6534 + endloop + endfacet + facet normal -0.854371 0.115131 0.506749 + outer loop + vertex -933.776 334.186 14.7413 + vertex -935.045 332.993 12.8736 + vertex -934.527 329.003 14.6534 + endloop + endfacet + facet normal -0.764772 0.177052 0.619497 + outer loop + vertex -934.527 329.003 14.6534 + vertex -935.045 332.993 12.8736 + vertex -935.296 329.724 13.4981 + endloop + endfacet + facet normal -0.875174 0.165721 0.454541 + outer loop + vertex -931.173 349.505 14.838 + vertex -932.307 348.743 12.9334 + vertex -932.142 344.446 14.818 + endloop + endfacet + facet normal -0.875714 0.165309 0.45365 + outer loop + vertex -932.142 344.446 14.818 + vertex -932.307 348.743 12.9334 + vertex -933.301 343.568 12.9005 + endloop + endfacet + facet normal -0.781555 0.145866 0.606543 + outer loop + vertex -929.867 350.237 16.3449 + vertex -931.173 349.505 14.838 + vertex -930.803 345.258 16.3362 + endloop + endfacet + facet normal -0.779635 0.146822 0.60878 + outer loop + vertex -930.803 345.258 16.3362 + vertex -931.173 349.505 14.838 + vertex -932.142 344.446 14.818 + endloop + endfacet + facet normal -0.776682 0.126425 0.617075 + outer loop + vertex -930.803 345.258 16.3362 + vertex -932.142 344.446 14.818 + vertex -931.628 340.256 16.3229 + endloop + endfacet + facet normal -0.773885 0.127917 0.620274 + outer loop + vertex -931.628 340.256 16.3229 + vertex -932.142 344.446 14.818 + vertex -933.006 339.342 14.7927 + endloop + endfacet + facet normal -0.874795 0.145783 0.46204 + outer loop + vertex -932.142 344.446 14.818 + vertex -933.301 343.568 12.9005 + vertex -933.006 339.342 14.7927 + endloop + endfacet + facet normal -0.872353 0.147735 0.46602 + outer loop + vertex -933.006 339.342 14.7927 + vertex -933.301 343.568 12.9005 + vertex -934.2 338.339 12.8752 + endloop + endfacet + facet normal -0.876701 0.202278 0.43644 + outer loop + vertex -928.957 359.461 14.8546 + vertex -930.056 358.739 12.9827 + vertex -930.105 354.501 14.8475 + endloop + endfacet + facet normal -0.874464 0.203889 0.440161 + outer loop + vertex -930.105 354.501 14.8475 + vertex -930.056 358.739 12.9827 + vertex -931.215 353.808 12.9646 + endloop + endfacet + facet normal -0.787244 0.180159 0.589737 + outer loop + vertex -927.695 360.137 16.3327 + vertex -928.957 359.461 14.8546 + vertex -928.822 355.196 16.3387 + endloop + endfacet + facet normal -0.785487 0.180945 0.591835 + outer loop + vertex -928.822 355.196 16.3387 + vertex -928.957 359.461 14.8546 + vertex -930.105 354.501 14.8475 + endloop + endfacet + facet normal -0.784304 0.16613 0.597719 + outer loop + vertex -928.822 355.196 16.3387 + vertex -930.105 354.501 14.8475 + vertex -929.867 350.237 16.3449 + endloop + endfacet + facet normal -0.783707 0.166411 0.598424 + outer loop + vertex -929.867 350.237 16.3449 + vertex -930.105 354.501 14.8475 + vertex -931.173 349.505 14.838 + endloop + endfacet + facet normal -0.874959 0.186208 0.446961 + outer loop + vertex -930.105 354.501 14.8475 + vertex -931.215 353.808 12.9646 + vertex -931.173 349.505 14.838 + endloop + endfacet + facet normal -0.875253 0.185993 0.446475 + outer loop + vertex -931.173 349.505 14.838 + vertex -931.215 353.808 12.9646 + vertex -932.307 348.743 12.9334 + endloop + endfacet + facet normal -0.884568 0.235627 0.402516 + outer loop + vertex -926.337 369.566 14.8818 + vertex -927.336 369.06 12.9834 + vertex -927.705 364.48 14.8526 + endloop + endfacet + facet normal -0.875582 0.241397 0.41843 + outer loop + vertex -927.705 364.48 14.8526 + vertex -927.336 369.06 12.9834 + vertex -928.795 363.749 12.9934 + endloop + endfacet + facet normal -0.803341 0.208329 0.557891 + outer loop + vertex -925.179 370.093 16.3521 + vertex -926.337 369.566 14.8818 + vertex -926.488 365.091 16.3359 + endloop + endfacet + facet normal -0.796423 0.210974 0.566745 + outer loop + vertex -926.488 365.091 16.3359 + vertex -926.337 369.566 14.8818 + vertex -927.705 364.48 14.8526 + endloop + endfacet + facet normal -0.795977 0.193669 0.57351 + outer loop + vertex -926.488 365.091 16.3359 + vertex -927.705 364.48 14.8526 + vertex -927.695 360.137 16.3327 + endloop + endfacet + facet normal -0.788278 0.196908 0.582962 + outer loop + vertex -927.695 360.137 16.3327 + vertex -927.705 364.48 14.8526 + vertex -928.957 359.461 14.8546 + endloop + endfacet + facet normal -0.876857 0.218943 0.428002 + outer loop + vertex -927.705 364.48 14.8526 + vertex -928.795 363.749 12.9934 + vertex -928.957 359.461 14.8546 + endloop + endfacet + facet normal -0.876032 0.219517 0.429396 + outer loop + vertex -928.957 359.461 14.8546 + vertex -928.795 363.749 12.9934 + vertex -930.056 358.739 12.9827 + endloop + endfacet + facet normal -0.895732 0.269101 0.353905 + outer loop + vertex -923.33 379.776 14.97 + vertex -924.121 379.471 13.1978 + vertex -924.88 374.664 14.9335 + endloop + endfacet + facet normal -0.892974 0.27072 0.359595 + outer loop + vertex -924.88 374.664 14.9335 + vertex -924.121 379.471 13.1978 + vertex -925.713 374.3 13.1387 + endloop + endfacet + facet normal -0.803286 0.238982 0.545544 + outer loop + vertex -922.131 380.426 16.4497 + vertex -923.33 379.776 14.97 + vertex -923.733 375.193 16.383 + endloop + endfacet + facet normal -0.802159 0.239345 0.547042 + outer loop + vertex -923.733 375.193 16.383 + vertex -923.33 379.776 14.97 + vertex -924.88 374.664 14.9335 + endloop + endfacet + facet normal -0.802541 0.224196 0.552869 + outer loop + vertex -923.733 375.193 16.383 + vertex -924.88 374.664 14.9335 + vertex -925.179 370.093 16.3521 + endloop + endfacet + facet normal -0.803125 0.223996 0.552102 + outer loop + vertex -925.179 370.093 16.3521 + vertex -924.88 374.664 14.9335 + vertex -926.337 369.566 14.8818 + endloop + endfacet + facet normal -0.896199 0.252503 0.364788 + outer loop + vertex -924.88 374.664 14.9335 + vertex -925.713 374.3 13.1387 + vertex -926.337 369.566 14.8818 + endloop + endfacet + facet normal -0.881229 0.261257 0.393929 + outer loop + vertex -926.337 369.566 14.8818 + vertex -925.713 374.3 13.1387 + vertex -927.336 369.06 12.9834 + endloop + endfacet + facet normal -0.893722 0.29629 0.336858 + outer loop + vertex -920.018 389.902 15.0084 + vertex -920.846 389.432 13.2246 + vertex -921.68 384.896 15.0018 + endloop + endfacet + facet normal -0.890041 0.298598 0.344479 + outer loop + vertex -921.68 384.896 15.0018 + vertex -920.846 389.432 13.2246 + vertex -922.503 384.504 13.2154 + endloop + endfacet + facet normal -0.80339 0.261453 0.534982 + outer loop + vertex -918.875 390.706 16.3312 + vertex -920.018 389.902 15.0084 + vertex -920.345 385.831 16.507 + endloop + endfacet + facet normal -0.797106 0.263936 0.543101 + outer loop + vertex -920.345 385.831 16.507 + vertex -920.018 389.902 15.0084 + vertex -921.68 384.896 15.0018 + endloop + endfacet + facet normal -0.796718 0.257539 0.54673 + outer loop + vertex -920.345 385.831 16.507 + vertex -921.68 384.896 15.0018 + vertex -922.131 380.426 16.4497 + endloop + endfacet + facet normal -0.803165 0.255433 0.538219 + outer loop + vertex -922.131 380.426 16.4497 + vertex -921.68 384.896 15.0018 + vertex -923.33 379.776 14.97 + endloop + endfacet + facet normal -0.892739 0.285471 0.348603 + outer loop + vertex -921.68 384.896 15.0018 + vertex -922.503 384.504 13.2154 + vertex -923.33 379.776 14.97 + endloop + endfacet + facet normal -0.892301 0.285731 0.349511 + outer loop + vertex -923.33 379.776 14.97 + vertex -922.503 384.504 13.2154 + vertex -924.121 379.471 13.1978 + endloop + endfacet + facet normal -0.892307 0.321105 0.3173 + outer loop + vertex -916.572 399.577 15.0569 + vertex -917.391 399.085 13.2497 + vertex -918.322 394.734 15.0356 + endloop + endfacet + facet normal -0.890314 0.322418 0.321538 + outer loop + vertex -918.322 394.734 15.0356 + vertex -917.391 399.085 13.2497 + vertex -919.138 394.28 13.2324 + endloop + endfacet + facet normal -0.818427 0.277165 0.503345 + outer loop + vertex -915.445 400.476 16.3929 + vertex -916.572 399.577 15.0569 + vertex -917.097 395.261 16.5795 + endloop + endfacet + facet normal -0.795811 0.285276 0.534137 + outer loop + vertex -917.097 395.261 16.5795 + vertex -916.572 399.577 15.0569 + vertex -918.322 394.734 15.0356 + endloop + endfacet + facet normal -0.796109 0.281672 0.535603 + outer loop + vertex -917.097 395.261 16.5795 + vertex -918.322 394.734 15.0356 + vertex -918.875 390.706 16.3312 + endloop + endfacet + facet normal -0.804118 0.27929 0.524777 + outer loop + vertex -918.875 390.706 16.3312 + vertex -918.322 394.734 15.0356 + vertex -920.018 389.902 15.0084 + endloop + endfacet + facet normal -0.892784 0.311531 0.325398 + outer loop + vertex -918.322 394.734 15.0356 + vertex -919.138 394.28 13.2324 + vertex -920.018 389.902 15.0084 + endloop + endfacet + facet normal -0.890222 0.313198 0.330775 + outer loop + vertex -920.018 389.902 15.0084 + vertex -919.138 394.28 13.2324 + vertex -920.846 389.432 13.2246 + endloop + endfacet + facet normal -0.896987 0.34103 0.28127 + outer loop + vertex -912.943 409.259 15.0774 + vertex -913.71 408.747 13.2518 + vertex -914.784 404.419 15.0727 + endloop + endfacet + facet normal -0.891604 0.344833 0.293483 + outer loop + vertex -914.784 404.419 15.0727 + vertex -913.71 408.747 13.2518 + vertex -915.581 403.905 13.2555 + endloop + endfacet + facet normal -0.832022 0.299474 0.466964 + outer loop + vertex -911.863 410.169 16.4173 + vertex -912.943 409.259 15.0774 + vertex -913.594 405.051 16.6148 + endloop + endfacet + facet normal -0.810138 0.307771 0.498953 + outer loop + vertex -913.594 405.051 16.6148 + vertex -912.943 409.259 15.0774 + vertex -914.784 404.419 15.0727 + endloop + endfacet + facet normal -0.810487 0.303628 0.500919 + outer loop + vertex -913.594 405.051 16.6148 + vertex -914.784 404.419 15.0727 + vertex -915.445 400.476 16.3929 + endloop + endfacet + facet normal -0.819285 0.300823 0.488136 + outer loop + vertex -915.445 400.476 16.3929 + vertex -914.784 404.419 15.0727 + vertex -916.572 399.577 15.0569 + endloop + endfacet + facet normal -0.895389 0.329531 0.299479 + outer loop + vertex -914.784 404.419 15.0727 + vertex -915.581 403.905 13.2555 + vertex -916.572 399.577 15.0569 + endloop + endfacet + facet normal -0.889384 0.333607 0.312573 + outer loop + vertex -916.572 399.577 15.0569 + vertex -915.581 403.905 13.2555 + vertex -917.391 399.085 13.2497 + endloop + endfacet + facet normal -0.898229 0.361013 0.250708 + outer loop + vertex -909.133 418.871 15.0677 + vertex -909.826 418.412 13.245 + vertex -911.051 414.092 15.0741 + endloop + endfacet + facet normal -0.894255 0.363995 0.260413 + outer loop + vertex -911.051 414.092 15.0741 + vertex -909.826 418.412 13.245 + vertex -911.785 413.597 13.2481 + endloop + endfacet + facet normal -0.846358 0.322707 0.423719 + outer loop + vertex -908.151 419.684 16.4088 + vertex -909.133 418.871 15.0677 + vertex -909.957 414.673 16.6183 + endloop + endfacet + facet normal -0.824046 0.331507 0.459404 + outer loop + vertex -909.957 414.673 16.6183 + vertex -909.133 418.871 15.0677 + vertex -911.051 414.092 15.0741 + endloop + endfacet + facet normal -0.824477 0.328345 0.460899 + outer loop + vertex -909.957 414.673 16.6183 + vertex -911.051 414.092 15.0741 + vertex -911.863 410.169 16.4173 + endloop + endfacet + facet normal -0.831986 0.325835 0.449032 + outer loop + vertex -911.863 410.169 16.4173 + vertex -911.051 414.092 15.0741 + vertex -912.943 409.259 15.0774 + endloop + endfacet + facet normal -0.897836 0.351476 0.265245 + outer loop + vertex -911.051 414.092 15.0741 + vertex -911.785 413.597 13.2481 + vertex -912.943 409.259 15.0774 + endloop + endfacet + facet normal -0.893328 0.354758 0.275883 + outer loop + vertex -912.943 409.259 15.0774 + vertex -911.785 413.597 13.2481 + vertex -913.71 408.747 13.2518 + endloop + endfacet + facet normal -0.898879 0.375376 0.226074 + outer loop + vertex -905.309 428.132 15.0498 + vertex -905.92 427.758 13.2403 + vertex -907.22 423.546 15.0618 + endloop + endfacet + facet normal -0.895803 0.377858 0.234009 + outer loop + vertex -907.22 423.546 15.0618 + vertex -905.92 427.758 13.2403 + vertex -907.868 423.136 13.2443 + endloop + endfacet + facet normal -0.858842 0.342373 0.381013 + outer loop + vertex -904.406 428.899 16.3942 + vertex -905.309 428.132 15.0498 + vertex -906.254 424.024 16.6102 + endloop + endfacet + facet normal -0.839131 0.350959 0.415557 + outer loop + vertex -906.254 424.024 16.6102 + vertex -905.309 428.132 15.0498 + vertex -907.22 423.546 15.0618 + endloop + endfacet + facet normal -0.839772 0.347771 0.41694 + outer loop + vertex -906.254 424.024 16.6102 + vertex -907.22 423.546 15.0618 + vertex -908.151 419.684 16.4088 + endloop + endfacet + facet normal -0.844701 0.345976 0.408388 + outer loop + vertex -908.151 419.684 16.4088 + vertex -907.22 423.546 15.0618 + vertex -909.133 418.871 15.0677 + endloop + endfacet + facet normal -0.899022 0.367977 0.237387 + outer loop + vertex -907.22 423.546 15.0618 + vertex -907.868 423.136 13.2443 + vertex -909.133 418.871 15.0677 + endloop + endfacet + facet normal -0.895183 0.370967 0.247045 + outer loop + vertex -909.133 418.871 15.0677 + vertex -907.868 423.136 13.2443 + vertex -909.826 418.412 13.245 + endloop + endfacet + facet normal -0.901689 0.386287 0.194268 + outer loop + vertex -901.333 437.447 15.0702 + vertex -901.922 437.004 13.2183 + vertex -903.361 432.729 15.0395 + endloop + endfacet + facet normal -0.896799 0.390493 0.208004 + outer loop + vertex -903.361 432.729 15.0395 + vertex -901.922 437.004 13.2183 + vertex -903.949 432.344 13.2234 + endloop + endfacet + facet normal -0.869182 0.357711 0.341418 + outer loop + vertex -900.426 438.338 16.4462 + vertex -901.333 437.447 15.0702 + vertex -902.445 433.272 16.6123 + endloop + endfacet + facet normal -0.853993 0.364636 0.371128 + outer loop + vertex -902.445 433.272 16.6123 + vertex -901.333 437.447 15.0702 + vertex -903.361 432.729 15.0395 + endloop + endfacet + facet normal -0.854036 0.364445 0.371219 + outer loop + vertex -902.445 433.272 16.6123 + vertex -903.361 432.729 15.0395 + vertex -904.406 428.899 16.3942 + endloop + endfacet + facet normal -0.856172 0.36358 0.367124 + outer loop + vertex -904.406 428.899 16.3942 + vertex -903.361 432.729 15.0395 + vertex -905.309 428.132 15.0498 + endloop + endfacet + facet normal -0.899892 0.381753 0.210855 + outer loop + vertex -903.361 432.729 15.0395 + vertex -903.949 432.344 13.2234 + vertex -905.309 428.132 15.0498 + endloop + endfacet + facet normal -0.895407 0.385489 0.222811 + outer loop + vertex -905.309 428.132 15.0498 + vertex -903.949 432.344 13.2234 + vertex -905.92 427.758 13.2403 + endloop + endfacet + facet normal -0.897933 0.400521 0.182482 + outer loop + vertex -896.825 447.568 15.307 + vertex -897.534 446.87 13.3487 + vertex -899.168 442.386 15.1534 + endloop + endfacet + facet normal -0.898462 0.400065 0.180871 + outer loop + vertex -899.168 442.386 15.1534 + vertex -897.534 446.87 13.3487 + vertex -899.797 441.829 13.2587 + endloop + endfacet + facet normal -0.874071 0.37662 0.306852 + outer loop + vertex -896.385 447.544 16.5906 + vertex -896.825 447.568 15.307 + vertex -898.328 442.921 16.731 + endloop + endfacet + facet normal -0.863533 0.380572 0.33087 + outer loop + vertex -898.328 442.921 16.731 + vertex -896.825 447.568 15.307 + vertex -899.168 442.386 15.1534 + endloop + endfacet + facet normal -0.864885 0.375269 0.333388 + outer loop + vertex -898.328 442.921 16.731 + vertex -899.168 442.386 15.1534 + vertex -900.426 438.338 16.4462 + endloop + endfacet + facet normal -0.866882 0.3745 0.329037 + outer loop + vertex -900.426 438.338 16.4462 + vertex -899.168 442.386 15.1534 + vertex -901.333 437.447 15.0702 + endloop + endfacet + facet normal -0.901323 0.39204 0.18418 + outer loop + vertex -899.168 442.386 15.1534 + vertex -899.797 441.829 13.2587 + vertex -901.333 437.447 15.0702 + endloop + endfacet + facet normal -0.89886 0.394193 0.191475 + outer loop + vertex -901.333 437.447 15.0702 + vertex -899.797 441.829 13.2587 + vertex -901.922 437.004 13.2183 + endloop + endfacet + facet normal -0.895326 0.407901 0.178907 + outer loop + vertex -897.534 446.87 13.3487 + vertex -896.825 447.568 15.307 + vertex -895.137 452.096 13.4305 + endloop + endfacet + facet normal -0.88554 0.412257 0.214157 + outer loop + vertex -892.995 456.846 13.1449 + vertex -895.137 452.096 13.4305 + vertex -893.823 453.78 15.6215 + endloop + endfacet + facet normal -0.863767 0.402013 0.303796 + outer loop + vertex -896.385 447.544 16.5906 + vertex -893.823 453.78 15.6215 + vertex -896.825 447.568 15.307 + endloop + endfacet + facet normal -0.884425 0.416742 0.210043 + outer loop + vertex -895.137 452.096 13.4305 + vertex -896.825 447.568 15.307 + vertex -893.823 453.78 15.6215 + endloop + endfacet + facet normal -0.884055 0.422825 0.199163 + outer loop + vertex -888.561 466.234 13.2278 + vertex -890.91 461.18 13.5291 + vertex -889.287 463.608 15.5788 + endloop + endfacet + facet normal -0.888399 0.408787 0.208905 + outer loop + vertex -892.995 456.846 13.1449 + vertex -893.823 453.78 15.6215 + vertex -890.91 461.18 13.5291 + endloop + endfacet + facet normal -0.886148 0.409933 0.216092 + outer loop + vertex -893.823 453.78 15.6215 + vertex -889.287 463.608 15.5788 + vertex -890.91 461.18 13.5291 + endloop + endfacet + facet normal -0.880195 0.442757 0.170946 + outer loop + vertex -883.964 475.525 13.2313 + vertex -886.388 470.575 13.5697 + vertex -884.77 473.009 15.5965 + endloop + endfacet + facet normal -0.88193 0.425514 0.202822 + outer loop + vertex -888.561 466.234 13.2278 + vertex -889.287 463.608 15.5788 + vertex -886.388 470.575 13.5697 + endloop + endfacet + facet normal -0.884 0.424411 0.19601 + outer loop + vertex -889.287 463.608 15.5788 + vertex -884.77 473.009 15.5965 + vertex -886.388 470.575 13.5697 + endloop + endfacet + facet normal -0.886711 0.451814 0.0980237 + outer loop + vertex -879.197 484.849 13.1753 + vertex -881.693 479.874 13.5289 + vertex -880.112 482.514 15.6617 + endloop + endfacet + facet normal -0.877581 0.446166 0.175464 + outer loop + vertex -883.964 475.525 13.2313 + vertex -884.77 473.009 15.5965 + vertex -881.693 479.874 13.5289 + endloop + endfacet + facet normal -0.891695 0.436129 0.121129 + outer loop + vertex -884.77 473.009 15.5965 + vertex -880.112 482.514 15.6617 + vertex -881.693 479.874 13.5289 + endloop + endfacet + facet normal -0.958435 0.250176 0.137166 + outer loop + vertex -876.111 493.657 13.4843 + vertex -877.216 489.341 13.6336 + vertex -875.708 493.534 16.5196 + endloop + endfacet + facet normal -0.915712 0.399969 0.0386704 + outer loop + vertex -879.197 484.849 13.1753 + vertex -880.112 482.514 15.6617 + vertex -877.216 489.341 13.6336 + endloop + endfacet + facet normal -0.925245 0.374472 -0.0607693 + outer loop + vertex -880.112 482.514 15.6617 + vertex -875.708 493.534 16.5196 + vertex -877.216 489.341 13.6336 + endloop + endfacet + facet normal -0.730133 -0.681998 0.0422478 + outer loop + vertex -879.387 191.932 10.0548 + vertex -879.45 191.933 8.993 + vertex -878.885 191.396 10.0647 + endloop + endfacet + facet normal -0.733195 -0.678486 0.0456223 + outer loop + vertex -878.885 191.396 10.0647 + vertex -879.45 191.933 8.993 + vertex -878.896 191.336 9.0055 + endloop + endfacet + facet normal -0.720149 -0.650103 0.242387 + outer loop + vertex -879.216 192.146 11.135 + vertex -879.387 191.932 10.0548 + vertex -878.744 191.619 11.1254 + endloop + endfacet + facet normal -0.712224 -0.661724 0.234217 + outer loop + vertex -878.744 191.619 11.1254 + vertex -879.387 191.932 10.0548 + vertex -878.885 191.396 10.0647 + endloop + endfacet + facet normal -0.791583 -0.568085 0.225112 + outer loop + vertex -878.744 191.619 11.1254 + vertex -878.885 191.396 10.0647 + vertex -878.538 191.287 11.0117 + endloop + endfacet + facet normal -0.737055 -0.646753 0.196112 + outer loop + vertex -878.538 191.287 11.0117 + vertex -878.885 191.396 10.0647 + vertex -878.615 191.051 9.94593 + endloop + endfacet + facet normal -0.778283 -0.626431 0.0431265 + outer loop + vertex -878.885 191.396 10.0647 + vertex -878.896 191.336 9.0055 + vertex -878.615 191.051 9.94593 + endloop + endfacet + facet normal -0.747206 -0.664215 0.0223947 + outer loop + vertex -878.615 191.051 9.94593 + vertex -878.896 191.336 9.0055 + vertex -878.619 191.02 8.86883 + endloop + endfacet + facet normal -0.678809 -0.60576 0.415059 + outer loop + vertex -879.013 192.642 12.1916 + vertex -879.216 192.146 11.135 + vertex -878.468 192.019 12.1741 + endloop + endfacet + facet normal -0.67489 -0.612597 0.411398 + outer loop + vertex -878.468 192.019 12.1741 + vertex -879.216 192.146 11.135 + vertex -878.744 191.619 11.1254 + endloop + endfacet + facet normal -0.593352 -0.565835 0.572507 + outer loop + vertex -878.936 193.441 13.0615 + vertex -879.013 192.642 12.1916 + vertex -878.187 192.787 13.1916 + endloop + endfacet + facet normal -0.605192 -0.545921 0.579408 + outer loop + vertex -878.187 192.787 13.1916 + vertex -879.013 192.642 12.1916 + vertex -878.468 192.019 12.1741 + endloop + endfacet + facet normal -0.641704 -0.516319 0.567125 + outer loop + vertex -878.187 192.787 13.1916 + vertex -878.468 192.019 12.1741 + vertex -877.704 191.946 12.9723 + endloop + endfacet + facet normal -0.641482 -0.516885 0.566861 + outer loop + vertex -877.704 191.946 12.9723 + vertex -878.468 192.019 12.1741 + vertex -878.291 191.605 11.9971 + endloop + endfacet + facet normal -0.772281 -0.498653 0.393609 + outer loop + vertex -878.468 192.019 12.1741 + vertex -878.744 191.619 11.1254 + vertex -878.291 191.605 11.9971 + endloop + endfacet + facet normal -0.727787 -0.577929 0.369221 + outer loop + vertex -878.291 191.605 11.9971 + vertex -878.744 191.619 11.1254 + vertex -878.538 191.287 11.0117 + endloop + endfacet + facet normal -0.723117 -0.58339 0.369808 + outer loop + vertex -878.291 191.605 11.9971 + vertex -878.538 191.287 11.0117 + vertex -878.027 191.099 11.7145 + endloop + endfacet + facet normal -0.667645 -0.679751 0.303626 + outer loop + vertex -878.027 191.099 11.7145 + vertex -878.538 191.287 11.0117 + vertex -877.987 190.65 10.7974 + endloop + endfacet + facet normal -0.634164 -0.526833 0.565935 + outer loop + vertex -877.704 191.946 12.9723 + vertex -878.291 191.605 11.9971 + vertex -877.549 191.23 12.4794 + endloop + endfacet + facet normal -0.62614 -0.602615 0.494777 + outer loop + vertex -877.549 191.23 12.4794 + vertex -878.291 191.605 11.9971 + vertex -878.027 191.099 11.7145 + endloop + endfacet + facet normal -0.723842 -0.689581 0.0230382 + outer loop + vertex -878.615 191.051 9.94593 + vertex -878.619 191.02 8.86883 + vertex -878.098 190.495 9.55247 + endloop + endfacet + facet normal -0.679106 -0.732712 -0.0441332 + outer loop + vertex -878.098 190.495 9.55247 + vertex -878.619 191.02 8.86883 + vertex -878.286 190.731 8.5342 + endloop + endfacet + facet normal -0.706355 -0.678723 0.200992 + outer loop + vertex -878.538 191.287 11.0117 + vertex -878.615 191.051 9.94593 + vertex -877.987 190.65 10.7974 + endloop + endfacet + facet normal -0.668742 -0.728217 0.14995 + outer loop + vertex -877.987 190.65 10.7974 + vertex -878.615 191.051 9.94593 + vertex -878.098 190.495 9.55247 + endloop + endfacet + facet normal -0.72841 -0.684934 0.0168547 + outer loop + vertex -885.245 197.984 9.98161 + vertex -885.334 198.051 8.91917 + vertex -883.493 196.12 9.97624 + endloop + endfacet + facet normal -0.730291 -0.682707 0.0242012 + outer loop + vertex -883.493 196.12 9.97624 + vertex -885.334 198.051 8.91917 + vertex -883.596 196.192 8.90895 + endloop + endfacet + facet normal -0.706387 -0.669383 0.230095 + outer loop + vertex -885.068 198.172 11.0742 + vertex -885.245 197.984 9.98161 + vertex -883.311 196.317 11.073 + endloop + endfacet + facet normal -0.707381 -0.665798 0.237329 + outer loop + vertex -883.311 196.317 11.073 + vertex -885.245 197.984 9.98161 + vertex -883.493 196.12 9.97624 + endloop + endfacet + facet normal -0.698643 -0.674894 0.23752 + outer loop + vertex -883.311 196.317 11.073 + vertex -883.493 196.12 9.97624 + vertex -881.634 194.584 11.0795 + endloop + endfacet + facet normal -0.699116 -0.673369 0.240438 + outer loop + vertex -881.634 194.584 11.0795 + vertex -883.493 196.12 9.97624 + vertex -881.813 194.377 9.981 + endloop + endfacet + facet normal -0.719756 -0.693864 0.0224328 + outer loop + vertex -883.493 196.12 9.97624 + vertex -883.596 196.192 8.90895 + vertex -881.813 194.377 9.981 + endloop + endfacet + facet normal -0.720584 -0.6929 0.0254419 + outer loop + vertex -881.813 194.377 9.981 + vertex -883.596 196.192 8.90895 + vertex -881.918 194.448 8.91105 + endloop + endfacet + facet normal -0.657608 -0.625843 0.419371 + outer loop + vertex -884.851 198.668 12.1545 + vertex -885.068 198.172 11.0742 + vertex -883.103 196.833 12.157 + endloop + endfacet + facet normal -0.657783 -0.623459 0.422635 + outer loop + vertex -883.103 196.833 12.157 + vertex -885.068 198.172 11.0742 + vertex -883.311 196.317 11.073 + endloop + endfacet + facet normal -0.576505 -0.565035 0.590235 + outer loop + vertex -884.713 199.473 13.0602 + vertex -884.851 198.668 12.1545 + vertex -882.842 197.734 13.223 + endloop + endfacet + facet normal -0.576835 -0.548653 0.605178 + outer loop + vertex -882.842 197.734 13.223 + vertex -884.851 198.668 12.1545 + vertex -883.103 196.833 12.157 + endloop + endfacet + facet normal -0.58347 -0.544083 0.60294 + outer loop + vertex -882.842 197.734 13.223 + vertex -883.103 196.833 12.157 + vertex -881.41 196.02 13.0617 + endloop + endfacet + facet normal -0.583282 -0.561456 0.586983 + outer loop + vertex -881.41 196.02 13.0617 + vertex -883.103 196.833 12.157 + vertex -881.457 195.128 12.1619 + endloop + endfacet + facet normal -0.652179 -0.628447 0.423931 + outer loop + vertex -883.103 196.833 12.157 + vertex -883.311 196.317 11.073 + vertex -881.457 195.128 12.1619 + endloop + endfacet + facet normal -0.652091 -0.629171 0.422991 + outer loop + vertex -881.457 195.128 12.1619 + vertex -883.311 196.317 11.073 + vertex -881.634 194.584 11.0795 + endloop + endfacet + facet normal -0.646056 -0.634306 0.42458 + outer loop + vertex -881.457 195.128 12.1619 + vertex -881.634 194.584 11.0795 + vertex -880.035 193.687 12.1739 + endloop + endfacet + facet normal -0.64611 -0.634067 0.424855 + outer loop + vertex -880.035 193.687 12.1739 + vertex -881.634 194.584 11.0795 + vertex -880.209 193.147 11.1018 + endloop + endfacet + facet normal -0.571048 -0.567922 0.592764 + outer loop + vertex -881.41 196.02 13.0617 + vertex -881.457 195.128 12.1619 + vertex -879.919 194.683 13.2166 + endloop + endfacet + facet normal -0.572679 -0.560415 0.598309 + outer loop + vertex -879.919 194.683 13.2166 + vertex -881.457 195.128 12.1619 + vertex -880.035 193.687 12.1739 + endloop + endfacet + facet normal -0.596992 -0.546289 0.587511 + outer loop + vertex -879.919 194.683 13.2166 + vertex -880.035 193.687 12.1739 + vertex -878.936 193.441 13.0615 + endloop + endfacet + facet normal -0.590613 -0.567448 0.573742 + outer loop + vertex -878.936 193.441 13.0615 + vertex -880.035 193.687 12.1739 + vertex -879.013 192.642 12.1916 + endloop + endfacet + facet normal -0.651498 -0.629491 0.423429 + outer loop + vertex -880.035 193.687 12.1739 + vertex -880.209 193.147 11.1018 + vertex -879.013 192.642 12.1916 + endloop + endfacet + facet normal -0.650751 -0.631408 0.42172 + outer loop + vertex -879.013 192.642 12.1916 + vertex -880.209 193.147 11.1018 + vertex -879.216 192.146 11.135 + endloop + endfacet + facet normal -0.710343 -0.703455 0.0237416 + outer loop + vertex -881.813 194.377 9.981 + vertex -881.918 194.448 8.91105 + vertex -880.384 192.935 10.0096 + endloop + endfacet + facet normal -0.714894 -0.698238 0.0372813 + outer loop + vertex -880.384 192.935 10.0096 + vertex -881.918 194.448 8.91105 + vertex -880.47 192.966 8.94089 + endloop + endfacet + facet normal -0.691083 -0.68153 0.240668 + outer loop + vertex -881.634 194.584 11.0795 + vertex -881.813 194.377 9.981 + vertex -880.209 193.147 11.1018 + endloop + endfacet + facet normal -0.691514 -0.680455 0.242466 + outer loop + vertex -880.209 193.147 11.1018 + vertex -881.813 194.377 9.981 + vertex -880.384 192.935 10.0096 + endloop + endfacet + facet normal -0.692859 -0.679102 0.242418 + outer loop + vertex -880.209 193.147 11.1018 + vertex -880.384 192.935 10.0096 + vertex -879.216 192.146 11.135 + endloop + endfacet + facet normal -0.693398 -0.6781 0.24368 + outer loop + vertex -879.216 192.146 11.135 + vertex -880.384 192.935 10.0096 + vertex -879.387 191.932 10.0548 + endloop + endfacet + facet normal -0.70966 -0.703588 0.0367031 + outer loop + vertex -880.384 192.935 10.0096 + vertex -880.47 192.966 8.94089 + vertex -879.387 191.932 10.0548 + endloop + endfacet + facet normal -0.711874 -0.7011 0.0411638 + outer loop + vertex -879.387 191.932 10.0548 + vertex -880.47 192.966 8.94089 + vertex -879.45 191.933 8.993 + endloop + endfacet + facet normal -0.753104 -0.65779 0.0121043 + outer loop + vertex -892.134 205.666 9.9933 + vertex -892.166 205.683 8.93198 + vertex -890.441 203.727 9.99121 + endloop + endfacet + facet normal -0.75256 -0.658447 0.0100057 + outer loop + vertex -890.441 203.727 9.99121 + vertex -892.166 205.683 8.93198 + vertex -890.478 203.754 8.93123 + endloop + endfacet + facet normal -0.735718 -0.643306 0.211841 + outer loop + vertex -892.028 205.903 11.0808 + vertex -892.134 205.666 9.9933 + vertex -890.325 203.955 11.0789 + endloop + endfacet + facet normal -0.735828 -0.642918 0.212636 + outer loop + vertex -890.325 203.955 11.0789 + vertex -892.134 205.666 9.9933 + vertex -890.441 203.727 9.99121 + endloop + endfacet + facet normal -0.727709 -0.651769 0.213626 + outer loop + vertex -890.325 203.955 11.0789 + vertex -890.441 203.727 9.99121 + vertex -888.586 202.012 11.0764 + endloop + endfacet + facet normal -0.728532 -0.648837 0.219664 + outer loop + vertex -888.586 202.012 11.0764 + vertex -890.441 203.727 9.99121 + vertex -888.722 201.798 9.98939 + endloop + endfacet + facet normal -0.746837 -0.664937 0.009639 + outer loop + vertex -890.441 203.727 9.99121 + vertex -890.478 203.754 8.93123 + vertex -888.722 201.798 9.98939 + endloop + endfacet + facet normal -0.747385 -0.664287 0.0117501 + outer loop + vertex -888.722 201.798 9.98939 + vertex -890.478 203.754 8.93123 + vertex -888.774 201.836 8.93022 + endloop + endfacet + facet normal -0.689665 -0.605161 0.39767 + outer loop + vertex -891.858 206.415 12.1542 + vertex -892.028 205.903 11.0808 + vertex -890.147 204.463 12.1523 + endloop + endfacet + facet normal -0.689756 -0.603316 0.400309 + outer loop + vertex -890.147 204.463 12.1523 + vertex -892.028 205.903 11.0808 + vertex -890.325 203.955 11.0789 + endloop + endfacet + facet normal -0.605531 -0.551166 0.574063 + outer loop + vertex -891.698 207.176 13.0537 + vertex -891.858 206.415 12.1542 + vertex -889.764 205.217 13.2132 + endloop + endfacet + facet normal -0.604104 -0.530317 0.59483 + outer loop + vertex -889.764 205.217 13.2132 + vertex -891.858 206.415 12.1542 + vertex -890.147 204.463 12.1523 + endloop + endfacet + facet normal -0.60786 -0.527074 0.593884 + outer loop + vertex -889.764 205.217 13.2132 + vertex -890.147 204.463 12.1523 + vertex -888.237 203.277 13.0545 + endloop + endfacet + facet normal -0.610387 -0.547334 0.572585 + outer loop + vertex -888.237 203.277 13.0545 + vertex -890.147 204.463 12.1523 + vertex -888.394 202.508 12.1516 + endloop + endfacet + facet normal -0.681553 -0.611055 0.402614 + outer loop + vertex -890.147 204.463 12.1523 + vertex -890.325 203.955 11.0789 + vertex -888.394 202.508 12.1516 + endloop + endfacet + facet normal -0.681569 -0.610707 0.403112 + outer loop + vertex -888.394 202.508 12.1516 + vertex -890.325 203.955 11.0789 + vertex -888.586 202.012 11.0764 + endloop + endfacet + facet normal -0.674735 -0.617117 0.404844 + outer loop + vertex -888.394 202.508 12.1516 + vertex -888.586 202.012 11.0764 + vertex -886.62 200.568 12.1514 + endloop + endfacet + facet normal -0.674942 -0.612715 0.411136 + outer loop + vertex -886.62 200.568 12.1514 + vertex -888.586 202.012 11.0764 + vertex -886.833 200.08 11.0751 + endloop + endfacet + facet normal -0.58875 -0.56182 0.581148 + outer loop + vertex -888.237 203.277 13.0545 + vertex -888.394 202.508 12.1516 + vertex -886.258 201.368 13.213 + endloop + endfacet + facet normal -0.587553 -0.537398 0.604967 + outer loop + vertex -886.258 201.368 13.213 + vertex -888.394 202.508 12.1516 + vertex -886.62 200.568 12.1514 + endloop + endfacet + facet normal -0.593385 -0.532707 0.603422 + outer loop + vertex -886.258 201.368 13.213 + vertex -886.62 200.568 12.1514 + vertex -884.713 199.473 13.0602 + endloop + endfacet + facet normal -0.595306 -0.553277 0.582662 + outer loop + vertex -884.713 199.473 13.0602 + vertex -886.62 200.568 12.1514 + vertex -884.851 198.668 12.1545 + endloop + endfacet + facet normal -0.666922 -0.620225 0.41296 + outer loop + vertex -886.62 200.568 12.1514 + vertex -886.833 200.08 11.0751 + vertex -884.851 198.668 12.1545 + endloop + endfacet + facet normal -0.667085 -0.617153 0.417277 + outer loop + vertex -884.851 198.668 12.1545 + vertex -886.833 200.08 11.0751 + vertex -885.068 198.172 11.0742 + endloop + endfacet + facet normal -0.741031 -0.671377 0.0111827 + outer loop + vertex -888.722 201.798 9.98939 + vertex -888.774 201.836 8.93022 + vertex -886.99 199.886 9.98687 + endloop + endfacet + facet normal -0.742677 -0.669419 0.0175762 + outer loop + vertex -886.99 199.886 9.98687 + vertex -888.774 201.836 8.93022 + vertex -887.061 199.936 8.92696 + endloop + endfacet + facet normal -0.722308 -0.655573 0.220216 + outer loop + vertex -888.586 202.012 11.0764 + vertex -888.722 201.798 9.98939 + vertex -886.833 200.08 11.0751 + endloop + endfacet + facet normal -0.722503 -0.654869 0.221667 + outer loop + vertex -886.833 200.08 11.0751 + vertex -888.722 201.798 9.98939 + vertex -886.99 199.886 9.98687 + endloop + endfacet + facet normal -0.715787 -0.662097 0.221983 + outer loop + vertex -886.833 200.08 11.0751 + vertex -886.99 199.886 9.98687 + vertex -885.068 198.172 11.0742 + endloop + endfacet + facet normal -0.716833 -0.65826 0.229878 + outer loop + vertex -885.068 198.172 11.0742 + vertex -886.99 199.886 9.98687 + vertex -885.245 197.984 9.98161 + endloop + endfacet + facet normal -0.736755 -0.675949 0.0168681 + outer loop + vertex -886.99 199.886 9.98687 + vertex -887.061 199.936 8.92696 + vertex -885.245 197.984 9.98161 + endloop + endfacet + facet normal -0.737088 -0.675553 0.0181745 + outer loop + vertex -885.245 197.984 9.98161 + vertex -887.061 199.936 8.92696 + vertex -885.334 198.051 8.91917 + endloop + endfacet + facet normal -0.774637 -0.632365 0.00722386 + outer loop + vertex -898.727 213.525 9.99958 + vertex -898.763 213.557 8.93465 + vertex -897.069 211.494 9.99837 + endloop + endfacet + facet normal -0.77562 -0.6311 0.011243 + outer loop + vertex -897.069 211.494 9.99837 + vertex -898.763 213.557 8.93465 + vertex -897.104 211.518 8.93396 + endloop + endfacet + facet normal -0.758529 -0.617156 0.20917 + outer loop + vertex -898.61 213.752 11.0913 + vertex -898.727 213.525 9.99958 + vertex -896.956 211.718 11.0897 + endloop + endfacet + facet normal -0.758076 -0.618964 0.205437 + outer loop + vertex -896.956 211.718 11.0897 + vertex -898.727 213.525 9.99958 + vertex -897.069 211.494 9.99837 + endloop + endfacet + facet normal -0.751345 -0.626817 0.20635 + outer loop + vertex -896.956 211.718 11.0897 + vertex -897.069 211.494 9.99837 + vertex -895.325 209.762 11.0866 + endloop + endfacet + facet normal -0.751917 -0.624705 0.210627 + outer loop + vertex -895.325 209.762 11.0866 + vertex -897.069 211.494 9.99837 + vertex -895.435 209.527 9.99684 + endloop + endfacet + facet normal -0.769205 -0.63891 0.0108651 + outer loop + vertex -897.069 211.494 9.99837 + vertex -897.104 211.518 8.93396 + vertex -895.435 209.527 9.99684 + endloop + endfacet + facet normal -0.768915 -0.639277 0.00972221 + outer loop + vertex -895.435 209.527 9.99684 + vertex -897.104 211.518 8.93396 + vertex -895.466 209.548 8.93349 + endloop + endfacet + facet normal -0.712937 -0.581061 0.392542 + outer loop + vertex -898.444 214.276 12.1698 + vertex -898.61 213.752 11.0913 + vertex -896.788 212.242 12.166 + endloop + endfacet + facet normal -0.712954 -0.580232 0.393736 + outer loop + vertex -896.788 212.242 12.166 + vertex -898.61 213.752 11.0913 + vertex -896.956 211.718 11.0897 + endloop + endfacet + facet normal -0.629412 -0.528378 0.569787 + outer loop + vertex -898.314 215.096 13.0736 + vertex -898.444 214.276 12.1698 + vertex -896.446 213.037 13.2279 + endloop + endfacet + facet normal -0.627946 -0.512242 0.585911 + outer loop + vertex -896.446 213.037 13.2279 + vertex -898.444 214.276 12.1698 + vertex -896.788 212.242 12.166 + endloop + endfacet + facet normal -0.634141 -0.506883 0.583896 + outer loop + vertex -896.446 213.037 13.2279 + vertex -896.788 212.242 12.166 + vertex -895.01 211.053 13.0654 + endloop + endfacet + facet normal -0.637259 -0.530122 0.559349 + outer loop + vertex -895.01 211.053 13.0654 + vertex -896.788 212.242 12.166 + vertex -895.156 210.276 12.1621 + endloop + endfacet + facet normal -0.706157 -0.586988 0.395964 + outer loop + vertex -896.788 212.242 12.166 + vertex -896.956 211.718 11.0897 + vertex -895.156 210.276 12.1621 + endloop + endfacet + facet normal -0.706057 -0.58935 0.39262 + outer loop + vertex -895.156 210.276 12.1621 + vertex -896.956 211.718 11.0897 + vertex -895.325 209.762 11.0866 + endloop + endfacet + facet normal -0.701446 -0.593878 0.394059 + outer loop + vertex -895.156 210.276 12.1621 + vertex -895.325 209.762 11.0866 + vertex -893.525 208.346 12.1579 + endloop + endfacet + facet normal -0.701403 -0.594672 0.392938 + outer loop + vertex -893.525 208.346 12.1579 + vertex -895.325 209.762 11.0866 + vertex -893.692 207.834 11.0838 + endloop + endfacet + facet normal -0.617516 -0.544007 0.568094 + outer loop + vertex -895.01 211.053 13.0654 + vertex -895.156 210.276 12.1621 + vertex -893.149 209.099 13.2166 + endloop + endfacet + facet normal -0.616076 -0.522127 0.589774 + outer loop + vertex -893.149 209.099 13.2166 + vertex -895.156 210.276 12.1621 + vertex -893.525 208.346 12.1579 + endloop + endfacet + facet normal -0.620646 -0.518102 0.588531 + outer loop + vertex -893.149 209.099 13.2166 + vertex -893.525 208.346 12.1579 + vertex -891.698 207.176 13.0537 + endloop + endfacet + facet normal -0.623252 -0.538815 0.566777 + outer loop + vertex -891.698 207.176 13.0537 + vertex -893.525 208.346 12.1579 + vertex -891.858 206.415 12.1542 + endloop + endfacet + facet normal -0.695262 -0.600611 0.394812 + outer loop + vertex -893.525 208.346 12.1579 + vertex -893.692 207.834 11.0838 + vertex -891.858 206.415 12.1542 + endloop + endfacet + facet normal -0.695308 -0.599777 0.395998 + outer loop + vertex -891.858 206.415 12.1542 + vertex -893.692 207.834 11.0838 + vertex -892.028 205.903 11.0808 + endloop + endfacet + facet normal -0.76318 -0.646117 0.00942233 + outer loop + vertex -895.435 209.527 9.99684 + vertex -895.466 209.548 8.93349 + vertex -893.798 207.594 9.9951 + endloop + endfacet + facet normal -0.763212 -0.646077 0.00954597 + outer loop + vertex -893.798 207.594 9.9951 + vertex -895.466 209.548 8.93349 + vertex -893.827 207.612 8.93277 + endloop + endfacet + facet normal -0.745641 -0.631876 0.211546 + outer loop + vertex -895.325 209.762 11.0866 + vertex -895.435 209.527 9.99684 + vertex -893.692 207.834 11.0838 + endloop + endfacet + facet normal -0.745737 -0.631532 0.212235 + outer loop + vertex -893.692 207.834 11.0838 + vertex -895.435 209.527 9.99684 + vertex -893.798 207.594 9.9951 + endloop + endfacet + facet normal -0.739975 -0.637986 0.213099 + outer loop + vertex -893.692 207.834 11.0838 + vertex -893.798 207.594 9.9951 + vertex -892.028 205.903 11.0808 + endloop + endfacet + facet normal -0.739718 -0.638891 0.21127 + outer loop + vertex -892.028 205.903 11.0808 + vertex -893.798 207.594 9.9951 + vertex -892.134 205.666 9.9933 + endloop + endfacet + facet normal -0.756864 -0.653507 0.00924992 + outer loop + vertex -893.798 207.594 9.9951 + vertex -893.827 207.612 8.93277 + vertex -892.134 205.666 9.9933 + endloop + endfacet + facet normal -0.757664 -0.652529 0.0123203 + outer loop + vertex -892.134 205.666 9.9933 + vertex -893.827 207.612 8.93277 + vertex -892.166 205.683 8.93198 + endloop + endfacet + facet normal -0.80164 -0.597768 -0.00682791 + outer loop + vertex -905.437 222.221 10.0064 + vertex -905.452 222.254 8.93947 + vertex -903.805 220.034 10.0046 + endloop + endfacet + facet normal -0.802498 -0.596646 -0.00316289 + outer loop + vertex -903.805 220.034 10.0046 + vertex -905.452 222.254 8.93947 + vertex -903.828 220.07 8.93822 + endloop + endfacet + facet normal -0.785162 -0.584979 0.203272 + outer loop + vertex -905.317 222.442 11.1021 + vertex -905.437 222.221 10.0064 + vertex -903.689 220.255 11.0997 + endloop + endfacet + facet normal -0.785046 -0.585565 0.202032 + outer loop + vertex -903.689 220.255 11.0997 + vertex -905.437 222.221 10.0064 + vertex -903.805 220.034 10.0046 + endloop + endfacet + facet normal -0.778168 -0.594322 0.203067 + outer loop + vertex -903.689 220.255 11.0997 + vertex -903.805 220.034 10.0046 + vertex -902.004 218.048 11.097 + endloop + endfacet + facet normal -0.778123 -0.594541 0.202597 + outer loop + vertex -902.004 218.048 11.097 + vertex -903.805 220.034 10.0046 + vertex -902.12 217.828 10.0027 + endloop + endfacet + facet normal -0.794683 -0.607014 -0.00368487 + outer loop + vertex -903.805 220.034 10.0046 + vertex -903.828 220.07 8.93822 + vertex -902.12 217.828 10.0027 + endloop + endfacet + facet normal -0.795671 -0.605729 0.000607983 + outer loop + vertex -902.12 217.828 10.0027 + vertex -903.828 220.07 8.93822 + vertex -902.15 217.866 8.93703 + endloop + endfacet + facet normal -0.739535 -0.550587 0.387224 + outer loop + vertex -905.119 222.937 12.1859 + vertex -905.317 222.442 11.1021 + vertex -903.503 220.765 12.1831 + endloop + endfacet + facet normal -0.739556 -0.551208 0.386298 + outer loop + vertex -903.503 220.765 12.1831 + vertex -905.317 222.442 11.1021 + vertex -903.689 220.255 11.0997 + endloop + endfacet + facet normal -0.65258 -0.501025 0.568431 + outer loop + vertex -904.916 223.703 13.0938 + vertex -905.119 222.937 12.1859 + vertex -903.109 221.527 13.2499 + endloop + endfacet + facet normal -0.649949 -0.484212 0.585752 + outer loop + vertex -903.109 221.527 13.2499 + vertex -905.119 222.937 12.1859 + vertex -903.503 220.765 12.1831 + endloop + endfacet + facet normal -0.652603 -0.481656 0.584908 + outer loop + vertex -903.109 221.527 13.2499 + vertex -903.503 220.765 12.1831 + vertex -901.678 219.387 13.084 + endloop + endfacet + facet normal -0.657316 -0.503964 0.560318 + outer loop + vertex -901.678 219.387 13.084 + vertex -903.503 220.765 12.1831 + vertex -901.829 218.576 12.1778 + endloop + endfacet + facet normal -0.731325 -0.560148 0.3891 + outer loop + vertex -903.503 220.765 12.1831 + vertex -903.689 220.255 11.0997 + vertex -901.829 218.576 12.1778 + endloop + endfacet + facet normal -0.731277 -0.558755 0.391187 + outer loop + vertex -901.829 218.576 12.1778 + vertex -903.689 220.255 11.0997 + vertex -902.004 218.048 11.097 + endloop + endfacet + facet normal -0.724411 -0.56596 0.393597 + outer loop + vertex -901.829 218.576 12.1778 + vertex -902.004 218.048 11.097 + vertex -900.13 216.398 12.1728 + endloop + endfacet + facet normal -0.72445 -0.567541 0.391241 + outer loop + vertex -900.13 216.398 12.1728 + vertex -902.004 218.048 11.097 + vertex -900.298 215.869 11.0937 + endloop + endfacet + facet normal -0.640591 -0.516206 0.568484 + outer loop + vertex -901.678 219.387 13.084 + vertex -901.829 218.576 12.1778 + vertex -899.788 217.209 13.2368 + endloop + endfacet + facet normal -0.638292 -0.499228 0.585965 + outer loop + vertex -899.788 217.209 13.2368 + vertex -901.829 218.576 12.1778 + vertex -900.13 216.398 12.1728 + endloop + endfacet + facet normal -0.643986 -0.494221 0.583976 + outer loop + vertex -899.788 217.209 13.2368 + vertex -900.13 216.398 12.1728 + vertex -898.314 215.096 13.0736 + endloop + endfacet + facet normal -0.64781 -0.515589 0.560812 + outer loop + vertex -898.314 215.096 13.0736 + vertex -900.13 216.398 12.1728 + vertex -898.444 214.276 12.1698 + endloop + endfacet + facet normal -0.719669 -0.572456 0.3929 + outer loop + vertex -900.13 216.398 12.1728 + vertex -900.298 215.869 11.0937 + vertex -898.444 214.276 12.1698 + endloop + endfacet + facet normal -0.719677 -0.574241 0.390272 + outer loop + vertex -898.444 214.276 12.1698 + vertex -900.298 215.869 11.0937 + vertex -898.61 213.752 11.0913 + endloop + endfacet + facet normal -0.787872 -0.615839 2.89771e-05 + outer loop + vertex -902.12 217.828 10.0027 + vertex -902.15 217.866 8.93703 + vertex -900.416 215.647 10.0011 + endloop + endfacet + facet normal -0.788726 -0.614734 0.00372535 + outer loop + vertex -900.416 215.647 10.0011 + vertex -902.15 217.866 8.93703 + vertex -900.449 215.683 8.93611 + endloop + endfacet + facet normal -0.770863 -0.603573 0.203642 + outer loop + vertex -902.004 218.048 11.097 + vertex -902.12 217.828 10.0027 + vertex -900.298 215.869 11.0937 + endloop + endfacet + facet normal -0.771022 -0.602822 0.205257 + outer loop + vertex -900.298 215.869 11.0937 + vertex -902.12 217.828 10.0027 + vertex -900.416 215.647 10.0011 + endloop + endfacet + facet normal -0.764993 -0.61017 0.206101 + outer loop + vertex -900.298 215.869 11.0937 + vertex -900.416 215.647 10.0011 + vertex -898.61 213.752 11.0913 + endloop + endfacet + facet normal -0.76522 -0.609164 0.208226 + outer loop + vertex -898.61 213.752 11.0913 + vertex -900.416 215.647 10.0011 + vertex -898.727 213.525 9.99958 + endloop + endfacet + facet normal -0.782438 -0.622721 0.00326484 + outer loop + vertex -900.416 215.647 10.0011 + vertex -900.449 215.683 8.93611 + vertex -898.727 213.525 9.99958 + endloop + endfacet + facet normal -0.783517 -0.621321 0.00785159 + outer loop + vertex -898.727 213.525 9.99958 + vertex -900.449 215.683 8.93611 + vertex -898.763 213.557 8.93465 + endloop + endfacet + facet normal -0.830856 -0.556341 -0.0127821 + outer loop + vertex -911.391 230.744 10.0149 + vertex -911.393 230.772 8.94442 + vertex -909.95 228.592 10.0125 + endloop + endfacet + facet normal -0.829888 -0.557677 -0.0168182 + outer loop + vertex -909.95 228.592 10.0125 + vertex -911.393 230.772 8.94442 + vertex -909.95 228.624 8.94361 + endloop + endfacet + facet normal -0.815638 -0.548439 0.184251 + outer loop + vertex -911.275 230.941 11.1145 + vertex -911.391 230.744 10.0149 + vertex -909.832 228.793 11.1115 + endloop + endfacet + facet normal -0.816003 -0.546621 0.188003 + outer loop + vertex -909.832 228.793 11.1115 + vertex -911.391 230.744 10.0149 + vertex -909.95 228.592 10.0125 + endloop + endfacet + facet normal -0.806515 -0.560042 0.189438 + outer loop + vertex -909.832 228.793 11.1115 + vertex -909.95 228.592 10.0125 + vertex -908.372 226.69 11.1079 + endloop + endfacet + facet normal -0.807148 -0.556979 0.195669 + outer loop + vertex -908.372 226.69 11.1079 + vertex -909.95 228.592 10.0125 + vertex -908.493 226.479 10.0105 + endloop + endfacet + facet normal -0.823035 -0.567733 -0.0171102 + outer loop + vertex -909.95 228.592 10.0125 + vertex -909.95 228.624 8.94361 + vertex -908.493 226.479 10.0105 + endloop + endfacet + facet normal -0.824741 -0.56542 -0.0101301 + outer loop + vertex -908.493 226.479 10.0105 + vertex -909.95 228.624 8.94361 + vertex -908.498 226.506 8.94185 + endloop + endfacet + facet normal -0.766359 -0.514142 0.385165 + outer loop + vertex -911.056 231.429 12.202 + vertex -911.275 230.941 11.1145 + vertex -909.613 229.276 12.1989 + endloop + endfacet + facet normal -0.766442 -0.515656 0.382969 + outer loop + vertex -909.613 229.276 12.1989 + vertex -911.275 230.941 11.1145 + vertex -909.832 228.793 11.1115 + endloop + endfacet + facet normal -0.679873 -0.474215 0.559369 + outer loop + vertex -910.835 232.193 13.1188 + vertex -911.056 231.429 12.202 + vertex -909.182 230.006 13.2737 + endloop + endfacet + facet normal -0.676366 -0.454119 0.579919 + outer loop + vertex -909.182 230.006 13.2737 + vertex -911.056 231.429 12.202 + vertex -909.613 229.276 12.1989 + endloop + endfacet + facet normal -0.677692 -0.452695 0.579483 + outer loop + vertex -909.182 230.006 13.2737 + vertex -909.613 229.276 12.1989 + vertex -907.931 227.917 13.1051 + endloop + endfacet + facet normal -0.682144 -0.472517 0.558038 + outer loop + vertex -907.931 227.917 13.1051 + vertex -909.613 229.276 12.1989 + vertex -908.156 227.166 12.1942 + endloop + endfacet + facet normal -0.758719 -0.525046 0.385581 + outer loop + vertex -909.613 229.276 12.1989 + vertex -909.832 228.793 11.1115 + vertex -908.156 227.166 12.1942 + endloop + endfacet + facet normal -0.758802 -0.527253 0.382392 + outer loop + vertex -908.156 227.166 12.1942 + vertex -909.832 228.793 11.1115 + vertex -908.372 226.69 11.1079 + endloop + endfacet + facet normal -0.752585 -0.534652 0.384399 + outer loop + vertex -908.156 227.166 12.1942 + vertex -908.372 226.69 11.1079 + vertex -906.666 225.065 12.1897 + endloop + endfacet + facet normal -0.752584 -0.534635 0.384425 + outer loop + vertex -906.666 225.065 12.1897 + vertex -908.372 226.69 11.1079 + vertex -906.876 224.582 11.1049 + endloop + endfacet + facet normal -0.665313 -0.487012 0.565843 + outer loop + vertex -907.931 227.917 13.1051 + vertex -908.156 227.166 12.1942 + vertex -906.234 225.781 13.2619 + endloop + endfacet + facet normal -0.662885 -0.471453 0.581649 + outer loop + vertex -906.234 225.781 13.2619 + vertex -908.156 227.166 12.1942 + vertex -906.666 225.065 12.1897 + endloop + endfacet + facet normal -0.665263 -0.468965 0.580945 + outer loop + vertex -906.234 225.781 13.2619 + vertex -906.666 225.065 12.1897 + vertex -904.916 223.703 13.0938 + endloop + endfacet + facet normal -0.669258 -0.487498 0.560749 + outer loop + vertex -904.916 223.703 13.0938 + vertex -906.666 225.065 12.1897 + vertex -905.119 222.937 12.1859 + endloop + endfacet + facet normal -0.745628 -0.542702 0.38667 + outer loop + vertex -906.666 225.065 12.1897 + vertex -906.876 224.582 11.1049 + vertex -905.119 222.937 12.1859 + endloop + endfacet + facet normal -0.74566 -0.543702 0.385202 + outer loop + vertex -905.119 222.937 12.1859 + vertex -906.876 224.582 11.1049 + vertex -905.317 222.442 11.1021 + endloop + endfacet + facet normal -0.814844 -0.579584 -0.0105393 + outer loop + vertex -908.493 226.479 10.0105 + vertex -908.498 226.506 8.94185 + vertex -906.993 224.371 10.0087 + endloop + endfacet + facet normal -0.816524 -0.577301 -0.00359778 + outer loop + vertex -906.993 224.371 10.0087 + vertex -908.498 226.506 8.94185 + vertex -907.006 224.395 8.94064 + endloop + endfacet + facet normal -0.799424 -0.5676 0.196853 + outer loop + vertex -908.372 226.69 11.1079 + vertex -908.493 226.479 10.0105 + vertex -906.876 224.582 11.1049 + endloop + endfacet + facet normal -0.799207 -0.568632 0.194743 + outer loop + vertex -906.876 224.582 11.1049 + vertex -908.493 226.479 10.0105 + vertex -906.993 224.371 10.0087 + endloop + endfacet + facet normal -0.792512 -0.577584 0.195757 + outer loop + vertex -906.876 224.582 11.1049 + vertex -906.993 224.371 10.0087 + vertex -905.317 222.442 11.1021 + endloop + endfacet + facet normal -0.793132 -0.574561 0.202041 + outer loop + vertex -905.317 222.442 11.1021 + vertex -906.993 224.371 10.0087 + vertex -905.437 222.221 10.0064 + endloop + endfacet + facet normal -0.809936 -0.586506 -0.0038882 + outer loop + vertex -906.993 224.371 10.0087 + vertex -907.006 224.395 8.94064 + vertex -905.437 222.221 10.0064 + endloop + endfacet + facet normal -0.809339 -0.587307 -0.00640013 + outer loop + vertex -905.437 222.221 10.0064 + vertex -907.006 224.395 8.94064 + vertex -905.452 222.254 8.93947 + endloop + endfacet + facet normal -0.858635 -0.511653 -0.03093 + outer loop + vertex -916.948 239.63 10.0239 + vertex -916.926 239.657 8.95089 + vertex -915.633 237.422 10.0213 + endloop + endfacet + facet normal -0.85928 -0.510726 -0.0282144 + outer loop + vertex -915.633 237.422 10.0213 + vertex -916.926 239.657 8.95089 + vertex -915.617 237.455 8.94901 + endloop + endfacet + facet normal -0.844073 -0.507298 0.173751 + outer loop + vertex -916.838 239.825 11.1279 + vertex -916.948 239.63 10.0239 + vertex -915.518 237.626 11.1239 + endloop + endfacet + facet normal -0.8447 -0.503599 0.181302 + outer loop + vertex -915.518 237.626 11.1239 + vertex -916.948 239.63 10.0239 + vertex -915.633 237.422 10.0213 + endloop + endfacet + facet normal -0.836383 -0.516743 0.182866 + outer loop + vertex -915.518 237.626 11.1239 + vertex -915.633 237.422 10.0213 + vertex -914.134 235.386 11.1204 + endloop + endfacet + facet normal -0.836286 -0.517331 0.181644 + outer loop + vertex -914.134 235.386 11.1204 + vertex -915.633 237.422 10.0213 + vertex -914.249 235.184 10.0193 + endloop + endfacet + facet normal -0.850172 -0.525731 -0.0285369 + outer loop + vertex -915.633 237.422 10.0213 + vertex -915.617 237.455 8.94901 + vertex -914.249 235.184 10.0193 + endloop + endfacet + facet normal -0.851021 -0.52454 -0.0249254 + outer loop + vertex -914.249 235.184 10.0193 + vertex -915.617 237.455 8.94901 + vertex -914.238 235.218 8.94796 + endloop + endfacet + facet normal -0.795317 -0.475564 0.375911 + outer loop + vertex -916.596 240.283 12.2211 + vertex -916.838 239.825 11.1279 + vertex -915.289 238.095 12.217 + endloop + endfacet + facet normal -0.795578 -0.47853 0.371572 + outer loop + vertex -915.289 238.095 12.217 + vertex -916.838 239.825 11.1279 + vertex -915.518 237.626 11.1239 + endloop + endfacet + facet normal -0.707407 -0.442361 0.551264 + outer loop + vertex -916.315 240.985 13.1449 + vertex -916.596 240.283 12.2211 + vertex -914.813 238.777 13.2996 + endloop + endfacet + facet normal -0.702701 -0.420641 0.573823 + outer loop + vertex -914.813 238.777 13.2996 + vertex -916.596 240.283 12.2211 + vertex -915.289 238.095 12.217 + endloop + endfacet + facet normal -0.705454 -0.417265 0.572908 + outer loop + vertex -914.813 238.777 13.2996 + vertex -915.289 238.095 12.217 + vertex -913.672 236.618 13.1322 + endloop + endfacet + facet normal -0.711849 -0.440118 0.547327 + outer loop + vertex -913.672 236.618 13.1322 + vertex -915.289 238.095 12.217 + vertex -913.915 235.866 12.2118 + endloop + endfacet + facet normal -0.78908 -0.487326 0.373986 + outer loop + vertex -915.289 238.095 12.217 + vertex -915.518 237.626 11.1239 + vertex -913.915 235.866 12.2118 + endloop + endfacet + facet normal -0.789127 -0.48786 0.373192 + outer loop + vertex -913.915 235.866 12.2118 + vertex -915.518 237.626 11.1239 + vertex -914.134 235.386 11.1204 + endloop + endfacet + facet normal -0.781981 -0.497221 0.375868 + outer loop + vertex -913.915 235.866 12.2118 + vertex -914.134 235.386 11.1204 + vertex -912.495 233.629 12.207 + endloop + endfacet + facet normal -0.781831 -0.495435 0.37853 + outer loop + vertex -912.495 233.629 12.207 + vertex -914.134 235.386 11.1204 + vertex -912.714 233.142 11.1176 + endloop + endfacet + facet normal -0.69335 -0.457547 0.556702 + outer loop + vertex -913.672 236.618 13.1322 + vertex -913.915 235.866 12.2118 + vertex -912.059 234.361 13.2869 + endloop + endfacet + facet normal -0.689512 -0.438956 0.576099 + outer loop + vertex -912.059 234.361 13.2869 + vertex -913.915 235.866 12.2118 + vertex -912.495 233.629 12.207 + endloop + endfacet + facet normal -0.692562 -0.435551 0.575025 + outer loop + vertex -912.059 234.361 13.2869 + vertex -912.495 233.629 12.207 + vertex -910.835 232.193 13.1188 + endloop + endfacet + facet normal -0.698273 -0.457903 0.550218 + outer loop + vertex -910.835 232.193 13.1188 + vertex -912.495 233.629 12.207 + vertex -911.056 231.429 12.202 + endloop + endfacet + facet normal -0.773143 -0.506488 0.381732 + outer loop + vertex -912.495 233.629 12.207 + vertex -912.714 233.142 11.1176 + vertex -911.056 231.429 12.202 + endloop + endfacet + facet normal -0.773092 -0.505782 0.38277 + outer loop + vertex -911.056 231.429 12.202 + vertex -912.714 233.142 11.1176 + vertex -911.275 230.941 11.1145 + endloop + endfacet + facet normal -0.844737 -0.534589 -0.0251815 + outer loop + vertex -914.249 235.184 10.0193 + vertex -914.238 235.218 8.94796 + vertex -912.83 232.942 10.0167 + endloop + endfacet + facet normal -0.845829 -0.53306 -0.0204844 + outer loop + vertex -912.83 232.942 10.0167 + vertex -914.238 235.218 8.94796 + vertex -912.826 232.977 8.94609 + endloop + endfacet + facet normal -0.830597 -0.526065 0.182658 + outer loop + vertex -914.134 235.386 11.1204 + vertex -914.249 235.184 10.0193 + vertex -912.714 233.142 11.1176 + endloop + endfacet + facet normal -0.830626 -0.525896 0.183012 + outer loop + vertex -912.714 233.142 11.1176 + vertex -914.249 235.184 10.0193 + vertex -912.83 232.942 10.0167 + endloop + endfacet + facet normal -0.822625 -0.537872 0.184341 + outer loop + vertex -912.714 233.142 11.1176 + vertex -912.83 232.942 10.0167 + vertex -911.275 230.941 11.1145 + endloop + endfacet + facet normal -0.822521 -0.538425 0.183186 + outer loop + vertex -911.275 230.941 11.1145 + vertex -912.83 232.942 10.0167 + vertex -911.391 230.744 10.0149 + endloop + endfacet + facet normal -0.836572 -0.547457 -0.020915 + outer loop + vertex -912.83 232.942 10.0167 + vertex -912.826 232.977 8.94609 + vertex -911.391 230.744 10.0149 + endloop + endfacet + facet normal -0.83855 -0.544682 -0.0124656 + outer loop + vertex -911.391 230.744 10.0149 + vertex -912.826 232.977 8.94609 + vertex -911.393 230.772 8.94442 + endloop + endfacet + facet normal -0.8852 -0.462885 -0.0464509 + outer loop + vertex -921.676 248.206 10.0328 + vertex -921.638 248.242 8.95647 + vertex -920.531 246.017 10.0308 + endloop + endfacet + facet normal -0.885718 -0.462105 -0.0443018 + outer loop + vertex -920.531 246.017 10.0308 + vertex -921.638 248.242 8.95647 + vertex -920.494 246.049 8.95535 + endloop + endfacet + facet normal -0.873622 -0.457739 0.165104 + outer loop + vertex -921.562 248.388 11.1413 + vertex -921.676 248.206 10.0328 + vertex -920.416 246.2 11.1384 + endloop + endfacet + facet normal -0.873719 -0.457079 0.166413 + outer loop + vertex -920.416 246.2 11.1384 + vertex -921.676 248.206 10.0328 + vertex -920.531 246.017 10.0308 + endloop + endfacet + facet normal -0.86635 -0.470392 0.16784 + outer loop + vertex -920.416 246.2 11.1384 + vertex -920.531 246.017 10.0308 + vertex -919.264 244.078 11.135 + endloop + endfacet + facet normal -0.866556 -0.469122 0.170306 + outer loop + vertex -919.264 244.078 11.135 + vertex -920.531 246.017 10.0308 + vertex -919.38 243.891 10.0284 + endloop + endfacet + facet normal -0.878636 -0.475418 -0.0444496 + outer loop + vertex -920.531 246.017 10.0308 + vertex -920.494 246.049 8.95535 + vertex -919.38 243.891 10.0284 + endloop + endfacet + facet normal -0.879621 -0.473951 -0.0404761 + outer loop + vertex -919.38 243.891 10.0284 + vertex -920.494 246.049 8.95535 + vertex -919.346 243.919 8.95383 + endloop + endfacet + facet normal -0.82598 -0.434151 0.359541 + outer loop + vertex -921.317 248.834 12.2419 + vertex -921.562 248.388 11.1413 + vertex -920.167 246.641 12.2366 + endloop + endfacet + facet normal -0.825852 -0.432985 0.361238 + outer loop + vertex -920.167 246.641 12.2366 + vertex -921.562 248.388 11.1413 + vertex -920.416 246.2 11.1384 + endloop + endfacet + facet normal -0.73551 -0.404221 0.543719 + outer loop + vertex -921.029 249.562 13.1722 + vertex -921.317 248.834 12.2419 + vertex -919.679 247.313 13.3275 + endloop + endfacet + facet normal -0.730761 -0.38469 0.563917 + outer loop + vertex -919.679 247.313 13.3275 + vertex -921.317 248.834 12.2419 + vertex -920.167 246.641 12.2366 + endloop + endfacet + facet normal -0.733211 -0.381387 0.562979 + outer loop + vertex -919.679 247.313 13.3275 + vertex -920.167 246.641 12.2366 + vertex -918.717 245.211 13.1567 + endloop + endfacet + facet normal -0.739344 -0.402565 0.539733 + outer loop + vertex -918.717 245.211 13.1567 + vertex -920.167 246.641 12.2366 + vertex -919.013 244.515 12.2318 + endloop + endfacet + facet normal -0.818126 -0.444932 0.364288 + outer loop + vertex -920.167 246.641 12.2366 + vertex -920.416 246.2 11.1384 + vertex -919.013 244.515 12.2318 + endloop + endfacet + facet normal -0.818088 -0.444516 0.36488 + outer loop + vertex -919.013 244.515 12.2318 + vertex -920.416 246.2 11.1384 + vertex -919.264 244.078 11.135 + endloop + endfacet + facet normal -0.810468 -0.455996 0.367708 + outer loop + vertex -919.013 244.515 12.2318 + vertex -919.264 244.078 11.135 + vertex -917.833 242.413 12.2263 + endloop + endfacet + facet normal -0.810545 -0.456955 0.366346 + outer loop + vertex -917.833 242.413 12.2263 + vertex -919.264 244.078 11.135 + vertex -918.079 241.972 11.1308 + endloop + endfacet + facet normal -0.720382 -0.423398 0.549349 + outer loop + vertex -918.717 245.211 13.1567 + vertex -919.013 244.515 12.2318 + vertex -917.332 243.058 13.3129 + endloop + endfacet + facet normal -0.716129 -0.403551 0.569479 + outer loop + vertex -917.332 243.058 13.3129 + vertex -919.013 244.515 12.2318 + vertex -917.833 242.413 12.2263 + endloop + endfacet + facet normal -0.71946 -0.399135 0.568391 + outer loop + vertex -917.332 243.058 13.3129 + vertex -917.833 242.413 12.2263 + vertex -916.315 240.985 13.1449 + endloop + endfacet + facet normal -0.726033 -0.422972 0.542191 + outer loop + vertex -916.315 240.985 13.1449 + vertex -917.833 242.413 12.2263 + vertex -916.596 240.283 12.2211 + endloop + endfacet + facet normal -0.803346 -0.46745 0.368952 + outer loop + vertex -917.833 242.413 12.2263 + vertex -918.079 241.972 11.1308 + vertex -916.596 240.283 12.2211 + endloop + endfacet + facet normal -0.803109 -0.4646 0.373044 + outer loop + vertex -916.596 240.283 12.2211 + vertex -918.079 241.972 11.1308 + vertex -916.838 239.825 11.1279 + endloop + endfacet + facet normal -0.871209 -0.489229 -0.0406073 + outer loop + vertex -919.38 243.891 10.0284 + vertex -919.346 243.919 8.95383 + vertex -918.194 241.779 10.0261 + endloop + endfacet + facet normal -0.872514 -0.487308 -0.0353699 + outer loop + vertex -918.194 241.779 10.0261 + vertex -919.346 243.919 8.95383 + vertex -918.165 241.804 8.95238 + endloop + endfacet + facet normal -0.858329 -0.483459 0.17187 + outer loop + vertex -919.264 244.078 11.135 + vertex -919.38 243.891 10.0284 + vertex -918.079 241.972 11.1308 + endloop + endfacet + facet normal -0.85852 -0.482339 0.174046 + outer loop + vertex -918.079 241.972 11.1308 + vertex -919.38 243.891 10.0284 + vertex -918.194 241.779 10.0261 + endloop + endfacet + facet normal -0.852328 -0.49278 0.175229 + outer loop + vertex -918.079 241.972 11.1308 + vertex -918.194 241.779 10.0261 + vertex -916.838 239.825 11.1279 + endloop + endfacet + facet normal -0.852067 -0.49428 0.172248 + outer loop + vertex -916.838 239.825 11.1279 + vertex -918.194 241.779 10.0261 + vertex -916.948 239.63 10.0239 + endloop + endfacet + facet normal -0.864544 -0.501303 -0.0354901 + outer loop + vertex -918.194 241.779 10.0261 + vertex -918.165 241.804 8.95238 + vertex -916.948 239.63 10.0239 + endloop + endfacet + facet normal -0.865697 -0.499622 -0.0307701 + outer loop + vertex -916.948 239.63 10.0239 + vertex -918.165 241.804 8.95238 + vertex -916.926 239.657 8.95089 + endloop + endfacet + facet normal -0.911959 -0.405477 -0.0625981 + outer loop + vertex -926.15 257.655 10.0427 + vertex -926.09 257.688 8.96316 + vertex -925.079 255.248 10.0404 + endloop + endfacet + facet normal -0.912443 -0.404718 -0.0604226 + outer loop + vertex -925.079 255.248 10.0404 + vertex -926.09 257.688 8.96316 + vertex -925.024 255.285 8.96178 + endloop + endfacet + facet normal -0.903224 -0.401423 0.15181 + outer loop + vertex -926.044 257.839 11.1552 + vertex -926.15 257.655 10.0427 + vertex -924.974 255.43 11.1525 + endloop + endfacet + facet normal -0.90319 -0.401787 0.151045 + outer loop + vertex -924.974 255.43 11.1525 + vertex -926.15 257.655 10.0427 + vertex -925.079 255.248 10.0404 + endloop + endfacet + facet normal -0.895756 -0.417422 0.152905 + outer loop + vertex -924.974 255.43 11.1525 + vertex -925.079 255.248 10.0404 + vertex -923.856 253.029 11.1486 + endloop + endfacet + facet normal -0.895826 -0.416742 0.154343 + outer loop + vertex -923.856 253.029 11.1486 + vertex -925.079 255.248 10.0404 + vertex -923.963 252.848 10.0378 + endloop + endfacet + facet normal -0.905113 -0.420829 -0.0606072 + outer loop + vertex -925.079 255.248 10.0404 + vertex -925.024 255.285 8.96178 + vertex -923.963 252.848 10.0378 + endloop + endfacet + facet normal -0.90701 -0.41788 -0.0520551 + outer loop + vertex -923.963 252.848 10.0378 + vertex -925.024 255.285 8.96178 + vertex -923.918 252.884 8.95969 + endloop + endfacet + facet normal -0.857429 -0.382336 0.344432 + outer loop + vertex -925.79 258.265 12.261 + vertex -926.044 257.839 11.1552 + vertex -924.724 255.87 12.2566 + endloop + endfacet + facet normal -0.85722 -0.381209 0.346198 + outer loop + vertex -924.724 255.87 12.2566 + vertex -926.044 257.839 11.1552 + vertex -924.974 255.43 11.1525 + endloop + endfacet + facet normal -0.767865 -0.357281 0.531727 + outer loop + vertex -925.456 258.942 13.1985 + vertex -925.79 258.265 12.261 + vertex -924.206 256.495 13.3595 + endloop + endfacet + facet normal -0.762109 -0.340281 0.550816 + outer loop + vertex -924.206 256.495 13.3595 + vertex -925.79 258.265 12.261 + vertex -924.724 255.87 12.2566 + endloop + endfacet + facet normal -0.762497 -0.339675 0.550654 + outer loop + vertex -924.206 256.495 13.3595 + vertex -924.724 255.87 12.2566 + vertex -923.308 254.196 13.185 + endloop + endfacet + facet normal -0.770789 -0.360935 0.524986 + outer loop + vertex -923.308 254.196 13.185 + vertex -924.724 255.87 12.2566 + vertex -923.609 253.481 12.2509 + endloop + endfacet + facet normal -0.848423 -0.396746 0.350388 + outer loop + vertex -924.724 255.87 12.2566 + vertex -924.974 255.43 11.1525 + vertex -923.609 253.481 12.2509 + endloop + endfacet + facet normal -0.84822 -0.3956 0.352169 + outer loop + vertex -923.609 253.481 12.2509 + vertex -924.974 255.43 11.1525 + vertex -923.856 253.029 11.1486 + endloop + endfacet + facet normal -0.840753 -0.408206 0.35567 + outer loop + vertex -923.609 253.481 12.2509 + vertex -923.856 253.029 11.1486 + vertex -922.467 251.123 12.2456 + endloop + endfacet + facet normal -0.840983 -0.409639 0.353472 + outer loop + vertex -922.467 251.123 12.2456 + vertex -923.856 253.029 11.1486 + vertex -922.71 250.673 11.1444 + endloop + endfacet + facet normal -0.752772 -0.382541 0.53572 + outer loop + vertex -923.308 254.196 13.185 + vertex -923.609 253.481 12.2509 + vertex -921.979 251.801 13.342 + endloop + endfacet + facet normal -0.747 -0.36323 0.556826 + outer loop + vertex -921.979 251.801 13.342 + vertex -923.609 253.481 12.2509 + vertex -922.467 251.123 12.2456 + endloop + endfacet + facet normal -0.749369 -0.359887 0.555813 + outer loop + vertex -921.979 251.801 13.342 + vertex -922.467 251.123 12.2456 + vertex -921.029 249.562 13.1722 + endloop + endfacet + facet normal -0.756481 -0.380677 0.531809 + outer loop + vertex -921.029 249.562 13.1722 + vertex -922.467 251.123 12.2456 + vertex -921.317 248.834 12.2419 + endloop + endfacet + facet normal -0.834821 -0.419726 0.356235 + outer loop + vertex -922.467 251.123 12.2456 + vertex -922.71 250.673 11.1444 + vertex -921.317 248.834 12.2419 + endloop + endfacet + facet normal -0.834862 -0.420023 0.35579 + outer loop + vertex -921.317 248.834 12.2419 + vertex -922.71 250.673 11.1444 + vertex -921.562 248.388 11.1413 + endloop + endfacet + facet normal -0.898495 -0.435857 -0.0523084 + outer loop + vertex -923.963 252.848 10.0378 + vertex -923.918 252.884 8.95969 + vertex -922.82 250.492 10.0355 + endloop + endfacet + facet normal -0.899233 -0.434715 -0.0490171 + outer loop + vertex -922.82 250.492 10.0355 + vertex -923.918 252.884 8.95969 + vertex -922.779 250.528 8.95848 + endloop + endfacet + facet normal -0.888148 -0.432224 0.156127 + outer loop + vertex -923.856 253.029 11.1486 + vertex -923.963 252.848 10.0378 + vertex -922.71 250.673 11.1444 + endloop + endfacet + facet normal -0.888277 -0.431104 0.158474 + outer loop + vertex -922.71 250.673 11.1444 + vertex -923.963 252.848 10.0378 + vertex -922.82 250.492 10.0355 + endloop + endfacet + facet normal -0.881946 -0.443417 0.159854 + outer loop + vertex -922.71 250.673 11.1444 + vertex -922.82 250.492 10.0355 + vertex -921.562 248.388 11.1413 + endloop + endfacet + facet normal -0.882162 -0.441709 0.163349 + outer loop + vertex -921.562 248.388 11.1413 + vertex -922.82 250.492 10.0355 + vertex -921.676 248.206 10.0328 + endloop + endfacet + facet normal -0.893191 -0.446979 -0.0491877 + outer loop + vertex -922.82 250.492 10.0355 + vertex -922.779 250.528 8.95848 + vertex -921.676 248.206 10.0328 + endloop + endfacet + facet normal -0.893878 -0.445923 -0.0462013 + outer loop + vertex -921.676 248.206 10.0328 + vertex -922.779 250.528 8.95848 + vertex -921.638 248.242 8.95647 + endloop + endfacet + facet normal -0.937297 -0.338419 -0.0833519 + outer loop + vertex -929.95 267.335 10.052 + vertex -929.866 267.369 8.96973 + vertex -929.058 264.864 10.0497 + endloop + endfacet + facet normal -0.938795 -0.335899 -0.0763873 + outer loop + vertex -929.058 264.864 10.0497 + vertex -929.866 267.369 8.96973 + vertex -928.98 264.894 8.96783 + endloop + endfacet + facet normal -0.932312 -0.338192 0.128147 + outer loop + vertex -929.857 267.504 11.1696 + vertex -929.95 267.335 10.052 + vertex -928.963 265.035 11.1663 + endloop + endfacet + facet normal -0.932401 -0.336851 0.130993 + outer loop + vertex -928.963 265.035 11.1663 + vertex -929.95 267.335 10.052 + vertex -929.058 264.864 10.0497 + endloop + endfacet + facet normal -0.925027 -0.35576 0.133264 + outer loop + vertex -928.963 265.035 11.1663 + vertex -929.058 264.864 10.0497 + vertex -928.035 262.621 11.1629 + endloop + endfacet + facet normal -0.924965 -0.356488 0.13174 + outer loop + vertex -928.035 262.621 11.1629 + vertex -929.058 264.864 10.0497 + vertex -928.128 262.451 10.0479 + endloop + endfacet + facet normal -0.930422 -0.358436 -0.0764118 + outer loop + vertex -929.058 264.864 10.0497 + vertex -928.98 264.894 8.96783 + vertex -928.128 262.451 10.0479 + endloop + endfacet + facet normal -0.932661 -0.354649 -0.0660789 + outer loop + vertex -928.128 262.451 10.0479 + vertex -928.98 264.894 8.96783 + vertex -928.06 262.474 8.96629 + endloop + endfacet + facet normal -0.886218 -0.320075 0.334918 + outer loop + vertex -929.59 267.927 12.2829 + vertex -929.857 267.504 11.1696 + vertex -928.697 265.451 12.2778 + endloop + endfacet + facet normal -0.886657 -0.321904 0.331991 + outer loop + vertex -928.697 265.451 12.2778 + vertex -929.857 267.504 11.1696 + vertex -928.963 265.035 11.1663 + endloop + endfacet + facet normal -0.794724 -0.301133 0.527003 + outer loop + vertex -929.225 268.625 13.231 + vertex -929.59 267.927 12.2829 + vertex -928.144 266.057 13.3933 + endloop + endfacet + facet normal -0.788189 -0.285177 0.545373 + outer loop + vertex -928.144 266.057 13.3933 + vertex -929.59 267.927 12.2829 + vertex -928.697 265.451 12.2778 + endloop + endfacet + facet normal -0.78789 -0.285721 0.545521 + outer loop + vertex -928.144 266.057 13.3933 + vertex -928.697 265.451 12.2778 + vertex -927.416 263.705 13.2143 + endloop + endfacet + facet normal -0.797688 -0.307126 0.519006 + outer loop + vertex -927.416 263.705 13.2143 + vertex -928.697 265.451 12.2778 + vertex -927.771 263.035 12.2724 + endloop + endfacet + facet normal -0.87908 -0.337935 0.336183 + outer loop + vertex -928.697 265.451 12.2778 + vertex -928.963 265.035 11.1663 + vertex -927.771 263.035 12.2724 + endloop + endfacet + facet normal -0.879187 -0.338431 0.335402 + outer loop + vertex -927.771 263.035 12.2724 + vertex -928.963 265.035 11.1663 + vertex -928.035 262.621 11.1629 + endloop + endfacet + facet normal -0.871853 -0.353294 0.3392 + outer loop + vertex -927.771 263.035 12.2724 + vertex -928.035 262.621 11.1629 + vertex -926.805 260.648 12.267 + endloop + endfacet + facet normal -0.872112 -0.354588 0.337175 + outer loop + vertex -926.805 260.648 12.267 + vertex -928.035 262.621 11.1629 + vertex -927.065 260.232 11.1586 + endloop + endfacet + facet normal -0.779555 -0.332934 0.530518 + outer loop + vertex -927.416 263.705 13.2143 + vertex -927.771 263.035 12.2724 + vertex -926.256 261.241 13.3718 + endloop + endfacet + facet normal -0.772423 -0.313565 0.552303 + outer loop + vertex -926.256 261.241 13.3718 + vertex -927.771 263.035 12.2724 + vertex -926.805 260.648 12.267 + endloop + endfacet + facet normal -0.773922 -0.310984 0.551665 + outer loop + vertex -926.256 261.241 13.3718 + vertex -926.805 260.648 12.267 + vertex -925.456 258.942 13.1985 + endloop + endfacet + facet normal -0.784304 -0.335476 0.521846 + outer loop + vertex -925.456 258.942 13.1985 + vertex -926.805 260.648 12.267 + vertex -925.79 258.265 12.261 + endloop + endfacet + facet normal -0.864564 -0.369207 0.340903 + outer loop + vertex -926.805 260.648 12.267 + vertex -927.065 260.232 11.1586 + vertex -925.79 258.265 12.261 + endloop + endfacet + facet normal -0.864554 -0.369151 0.34099 + outer loop + vertex -925.79 258.265 12.261 + vertex -927.065 260.232 11.1586 + vertex -926.044 257.839 11.1552 + endloop + endfacet + facet normal -0.925578 -0.372754 -0.0660295 + outer loop + vertex -928.128 262.451 10.0479 + vertex -928.06 262.474 8.96629 + vertex -927.163 260.055 10.0453 + endloop + endfacet + facet normal -0.925364 -0.37311 -0.067007 + outer loop + vertex -927.163 260.055 10.0453 + vertex -928.06 262.474 8.96629 + vertex -927.096 260.083 8.96522 + endloop + endfacet + facet normal -0.91818 -0.372927 0.133685 + outer loop + vertex -928.035 262.621 11.1629 + vertex -928.128 262.451 10.0479 + vertex -927.065 260.232 11.1586 + endloop + endfacet + facet normal -0.918445 -0.370104 0.139578 + outer loop + vertex -927.065 260.232 11.1586 + vertex -928.128 262.451 10.0479 + vertex -927.163 260.055 10.0453 + endloop + endfacet + facet normal -0.910493 -0.388457 0.141787 + outer loop + vertex -927.065 260.232 11.1586 + vertex -927.163 260.055 10.0453 + vertex -926.044 257.839 11.1552 + endloop + endfacet + facet normal -0.910838 -0.384641 0.149755 + outer loop + vertex -926.044 257.839 11.1552 + vertex -927.163 260.055 10.0453 + vertex -926.15 257.655 10.0427 + endloop + endfacet + facet normal -0.919241 -0.387951 -0.0670062 + outer loop + vertex -927.163 260.055 10.0453 + vertex -927.096 260.083 8.96522 + vertex -926.15 257.655 10.0427 + endloop + endfacet + facet normal -0.920243 -0.386329 -0.0624697 + outer loop + vertex -926.15 257.655 10.0427 + vertex -927.096 260.083 8.96522 + vertex -926.09 257.688 8.96316 + endloop + endfacet + facet normal -0.959916 -0.263017 -0.0968693 + outer loop + vertex -933.123 277.645 10.0613 + vertex -933.024 277.683 8.97555 + vertex -932.411 275.05 10.0586 + endloop + endfacet + facet normal -0.959528 -0.263716 -0.098788 + outer loop + vertex -932.411 275.05 10.0586 + vertex -933.024 277.683 8.97555 + vertex -932.311 275.091 8.97424 + endloop + endfacet + facet normal -0.958041 -0.2638 0.112102 + outer loop + vertex -933.037 277.809 11.1841 + vertex -933.123 277.645 10.0613 + vertex -932.323 275.216 11.1805 + endloop + endfacet + facet normal -0.958059 -0.262731 0.114435 + outer loop + vertex -932.323 275.216 11.1805 + vertex -933.123 277.645 10.0613 + vertex -932.411 275.05 10.0586 + endloop + endfacet + facet normal -0.951389 -0.284828 0.117181 + outer loop + vertex -932.323 275.216 11.1805 + vertex -932.411 275.05 10.0586 + vertex -931.546 272.617 11.1767 + endloop + endfacet + facet normal -0.95141 -0.284042 0.118907 + outer loop + vertex -931.546 272.617 11.1767 + vertex -932.411 275.05 10.0586 + vertex -931.635 272.449 10.0565 + endloop + endfacet + facet normal -0.953548 -0.284501 -0.0990226 + outer loop + vertex -932.411 275.05 10.0586 + vertex -932.311 275.091 8.97424 + vertex -931.635 272.449 10.0565 + endloop + endfacet + facet normal -0.954676 -0.282556 -0.093571 + outer loop + vertex -931.635 272.449 10.0565 + vertex -932.311 275.091 8.97424 + vertex -931.541 272.489 8.97284 + endloop + endfacet + facet normal -0.914045 -0.2514 0.318309 + outer loop + vertex -932.762 278.233 12.3077 + vertex -933.037 277.809 11.1841 + vertex -932.051 275.641 12.3028 + endloop + endfacet + facet normal -0.914236 -0.25203 0.317258 + outer loop + vertex -932.051 275.641 12.3028 + vertex -933.037 277.809 11.1841 + vertex -932.323 275.216 11.1805 + endloop + endfacet + facet normal -0.820372 -0.243981 0.517169 + outer loop + vertex -932.365 278.928 13.2647 + vertex -932.762 278.233 12.3077 + vertex -931.469 276.254 13.4249 + endloop + endfacet + facet normal -0.81018 -0.22332 0.541975 + outer loop + vertex -931.469 276.254 13.4249 + vertex -932.762 278.233 12.3077 + vertex -932.051 275.641 12.3028 + endloop + endfacet + facet normal -0.809207 -0.225361 0.542584 + outer loop + vertex -931.469 276.254 13.4249 + vertex -932.051 275.641 12.3028 + vertex -930.893 273.757 13.2474 + endloop + endfacet + facet normal -0.821496 -0.247359 0.513767 + outer loop + vertex -930.893 273.757 13.2474 + vertex -932.051 275.641 12.3028 + vertex -931.274 273.047 12.2955 + endloop + endfacet + facet normal -0.906393 -0.272237 0.323014 + outer loop + vertex -932.051 275.641 12.3028 + vertex -932.323 275.216 11.1805 + vertex -931.274 273.047 12.2955 + endloop + endfacet + facet normal -0.906208 -0.271608 0.324062 + outer loop + vertex -931.274 273.047 12.2955 + vertex -932.323 275.216 11.1805 + vertex -931.546 272.617 11.1767 + endloop + endfacet + facet normal -0.900398 -0.28574 0.328078 + outer loop + vertex -931.274 273.047 12.2955 + vertex -931.546 272.617 11.1767 + vertex -930.455 270.459 12.2899 + endloop + endfacet + facet normal -0.901303 -0.28895 0.32274 + outer loop + vertex -930.455 270.459 12.2899 + vertex -931.546 272.617 11.1767 + vertex -930.72 270.037 11.1728 + endloop + endfacet + facet normal -0.80554 -0.272533 0.526148 + outer loop + vertex -930.893 273.757 13.2474 + vertex -931.274 273.047 12.2955 + vertex -929.886 271.091 13.4071 + endloop + endfacet + facet normal -0.796657 -0.253378 0.54876 + outer loop + vertex -929.886 271.091 13.4071 + vertex -931.274 273.047 12.2955 + vertex -930.455 270.459 12.2899 + endloop + endfacet + facet normal -0.796941 -0.252835 0.548598 + outer loop + vertex -929.886 271.091 13.4071 + vertex -930.455 270.459 12.2899 + vertex -929.225 268.625 13.231 + endloop + endfacet + facet normal -0.810059 -0.278307 0.516091 + outer loop + vertex -929.225 268.625 13.231 + vertex -930.455 270.459 12.2899 + vertex -929.59 267.927 12.2829 + endloop + endfacet + facet normal -0.893774 -0.306396 0.32755 + outer loop + vertex -930.455 270.459 12.2899 + vertex -930.72 270.037 11.1728 + vertex -929.59 267.927 12.2829 + endloop + endfacet + facet normal -0.893274 -0.304479 0.330687 + outer loop + vertex -929.59 267.927 12.2829 + vertex -930.72 270.037 11.1728 + vertex -929.857 267.504 11.1696 + endloop + endfacet + facet normal -0.948138 -0.30371 -0.0937787 + outer loop + vertex -931.635 272.449 10.0565 + vertex -931.541 272.489 8.97284 + vertex -930.809 269.871 10.0544 + endloop + endfacet + facet normal -0.950223 -0.300122 -0.083683 + outer loop + vertex -930.809 269.871 10.0544 + vertex -931.541 272.489 8.97284 + vertex -930.724 269.904 8.97104 + endloop + endfacet + facet normal -0.945332 -0.302741 0.121224 + outer loop + vertex -931.546 272.617 11.1767 + vertex -931.635 272.449 10.0565 + vertex -930.72 270.037 11.1728 + endloop + endfacet + facet normal -0.945323 -0.30298 0.120699 + outer loop + vertex -930.72 270.037 11.1728 + vertex -931.635 272.449 10.0565 + vertex -930.809 269.871 10.0544 + endloop + endfacet + facet normal -0.939457 -0.319928 0.122748 + outer loop + vertex -930.72 270.037 11.1728 + vertex -930.809 269.871 10.0544 + vertex -929.857 267.504 11.1696 + endloop + endfacet + facet normal -0.939531 -0.318532 0.125776 + outer loop + vertex -929.857 267.504 11.1696 + vertex -930.809 269.871 10.0544 + vertex -929.95 267.335 10.052 + endloop + endfacet + facet normal -0.943781 -0.319779 -0.0837817 + outer loop + vertex -930.809 269.871 10.0544 + vertex -930.724 269.904 8.97104 + vertex -929.95 267.335 10.052 + endloop + endfacet + facet normal -0.943887 -0.319597 -0.0832726 + outer loop + vertex -929.95 267.335 10.052 + vertex -930.724 269.904 8.97104 + vertex -929.866 267.369 8.96973 + endloop + endfacet + facet normal -0.976537 -0.184217 -0.111533 + outer loop + vertex -935.363 287.742 10.0707 + vertex -935.244 287.771 8.98161 + vertex -934.895 285.263 10.0681 + endloop + endfacet + facet normal -0.976967 -0.183294 -0.109265 + outer loop + vertex -934.895 285.263 10.0681 + vertex -935.244 287.771 8.98161 + vertex -934.78 285.297 8.97984 + endloop + endfacet + facet normal -0.977777 -0.185326 0.0980103 + outer loop + vertex -935.282 287.911 11.198 + vertex -935.363 287.742 10.0707 + vertex -934.813 285.434 11.1954 + endloop + endfacet + facet normal -0.977766 -0.184668 0.0993546 + outer loop + vertex -934.813 285.434 11.1954 + vertex -935.363 287.742 10.0707 + vertex -934.895 285.263 10.0681 + endloop + endfacet + facet normal -0.973498 -0.204652 0.102072 + outer loop + vertex -934.813 285.434 11.1954 + vertex -934.895 285.263 10.0681 + vertex -934.284 282.918 11.1917 + endloop + endfacet + facet normal -0.973505 -0.206051 0.0991558 + outer loop + vertex -934.284 282.918 11.1917 + vertex -934.895 285.263 10.0681 + vertex -934.364 282.753 10.066 + endloop + endfacet + facet normal -0.97248 -0.205658 -0.109486 + outer loop + vertex -934.895 285.263 10.0681 + vertex -934.78 285.297 8.97984 + vertex -934.364 282.753 10.066 + endloop + endfacet + facet normal -0.973022 -0.204557 -0.106699 + outer loop + vertex -934.364 282.753 10.066 + vertex -934.78 285.297 8.97984 + vertex -934.252 282.789 8.97871 + endloop + endfacet + facet normal -0.93815 -0.180576 0.29541 + outer loop + vertex -935.004 288.31 12.3256 + vertex -935.282 287.911 11.198 + vertex -934.532 285.851 12.3214 + endloop + endfacet + facet normal -0.937276 -0.177865 0.299796 + outer loop + vertex -934.532 285.851 12.3214 + vertex -935.282 287.911 11.198 + vertex -934.813 285.434 11.1954 + endloop + endfacet + facet normal -0.853601 -0.18226 0.488003 + outer loop + vertex -934.587 288.931 13.2877 + vertex -935.004 288.31 12.3256 + vertex -933.95 286.389 13.4516 + endloop + endfacet + facet normal -0.843535 -0.162789 0.511808 + outer loop + vertex -933.95 286.389 13.4516 + vertex -935.004 288.31 12.3256 + vertex -934.532 285.851 12.3214 + endloop + endfacet + facet normal -0.843428 -0.163082 0.511892 + outer loop + vertex -933.95 286.389 13.4516 + vertex -934.532 285.851 12.3214 + vertex -933.597 284.012 13.2765 + endloop + endfacet + facet normal -0.854653 -0.182123 0.486209 + outer loop + vertex -933.597 284.012 13.2765 + vertex -934.532 285.851 12.3214 + vertex -934 283.345 12.3169 + endloop + endfacet + facet normal -0.931279 -0.19805 0.305771 + outer loop + vertex -934.532 285.851 12.3214 + vertex -934.813 285.434 11.1954 + vertex -934 283.345 12.3169 + endloop + endfacet + facet normal -0.93059 -0.195937 0.309208 + outer loop + vertex -934 283.345 12.3169 + vertex -934.813 285.434 11.1954 + vertex -934.284 282.918 11.1917 + endloop + endfacet + facet normal -0.924466 -0.214964 0.314885 + outer loop + vertex -934 283.345 12.3169 + vertex -934.284 282.918 11.1917 + vertex -933.411 280.803 12.3118 + endloop + endfacet + facet normal -0.924931 -0.216406 0.312524 + outer loop + vertex -933.411 280.803 12.3118 + vertex -934.284 282.918 11.1917 + vertex -933.691 280.376 11.1875 + endloop + endfacet + facet normal -0.838375 -0.213858 0.501391 + outer loop + vertex -933.597 284.012 13.2765 + vertex -934 283.345 12.3169 + vertex -932.829 281.383 13.4385 + endloop + endfacet + facet normal -0.827758 -0.192964 0.52686 + outer loop + vertex -932.829 281.383 13.4385 + vertex -934 283.345 12.3169 + vertex -933.411 280.803 12.3118 + endloop + endfacet + facet normal -0.827471 -0.193644 0.527062 + outer loop + vertex -932.829 281.383 13.4385 + vertex -933.411 280.803 12.3118 + vertex -932.365 278.928 13.2647 + endloop + endfacet + facet normal -0.83843 -0.212572 0.501846 + outer loop + vertex -932.365 278.928 13.2647 + vertex -933.411 280.803 12.3118 + vertex -932.762 278.233 12.3077 + endloop + endfacet + facet normal -0.91933 -0.232704 0.317304 + outer loop + vertex -933.411 280.803 12.3118 + vertex -933.691 280.376 11.1875 + vertex -932.762 278.233 12.3077 + endloop + endfacet + facet normal -0.920035 -0.234956 0.313578 + outer loop + vertex -932.762 278.233 12.3077 + vertex -933.691 280.376 11.1875 + vertex -933.037 277.809 11.1841 + endloop + endfacet + facet normal -0.968859 -0.223351 -0.10689 + outer loop + vertex -934.364 282.753 10.066 + vertex -934.252 282.789 8.97871 + vertex -933.778 280.21 10.0633 + endloop + endfacet + facet normal -0.9699 -0.221308 -0.101576 + outer loop + vertex -933.778 280.21 10.0633 + vertex -934.252 282.789 8.97871 + vertex -933.673 280.249 8.97672 + endloop + endfacet + facet normal -0.968729 -0.226282 0.101785 + outer loop + vertex -934.284 282.918 11.1917 + vertex -934.364 282.753 10.066 + vertex -933.691 280.376 11.1875 + endloop + endfacet + facet normal -0.968737 -0.223551 0.107576 + outer loop + vertex -933.691 280.376 11.1875 + vertex -934.364 282.753 10.066 + vertex -933.778 280.21 10.0633 + endloop + endfacet + facet normal -0.963052 -0.245646 0.110405 + outer loop + vertex -933.691 280.376 11.1875 + vertex -933.778 280.21 10.0633 + vertex -933.037 277.809 11.1841 + endloop + endfacet + facet normal -0.963049 -0.245898 0.109866 + outer loop + vertex -933.037 277.809 11.1841 + vertex -933.778 280.21 10.0633 + vertex -933.123 277.645 10.0613 + endloop + endfacet + facet normal -0.963911 -0.245958 -0.101886 + outer loop + vertex -933.778 280.21 10.0633 + vertex -933.673 280.249 8.97672 + vertex -933.123 277.645 10.0613 + endloop + endfacet + facet normal -0.964947 -0.243998 -0.0966563 + outer loop + vertex -933.123 277.645 10.0613 + vertex -933.673 280.249 8.97672 + vertex -933.024 277.683 8.97555 + endloop + endfacet + facet normal -0.986887 -0.105837 -0.121873 + outer loop + vertex -936.728 297.521 10.0781 + vertex -936.597 297.558 8.98652 + vertex -936.46 295.027 10.0762 + endloop + endfacet + facet normal -0.9868 -0.106054 -0.122387 + outer loop + vertex -936.46 295.027 10.0762 + vertex -936.597 297.558 8.98652 + vertex -936.328 295.062 8.98546 + endloop + endfacet + facet normal -0.990979 -0.110148 0.0763399 + outer loop + vertex -936.656 297.658 11.2087 + vertex -936.728 297.521 10.0781 + vertex -936.38 295.174 11.2063 + endloop + endfacet + facet normal -0.990764 -0.106408 0.084053 + outer loop + vertex -936.38 295.174 11.2063 + vertex -936.728 297.521 10.0781 + vertex -936.46 295.027 10.0762 + endloop + endfacet + facet normal -0.987985 -0.127963 0.0866718 + outer loop + vertex -936.38 295.174 11.2063 + vertex -936.46 295.027 10.0762 + vertex -936.066 292.747 11.204 + endloop + endfacet + facet normal -0.98802 -0.128768 0.0850563 + outer loop + vertex -936.066 292.747 11.204 + vertex -936.46 295.027 10.0762 + vertex -936.143 292.596 10.0746 + endloop + endfacet + facet normal -0.984129 -0.128122 -0.122781 + outer loop + vertex -936.46 295.027 10.0762 + vertex -936.328 295.062 8.98546 + vertex -936.143 292.596 10.0746 + endloop + endfacet + facet normal -0.985193 -0.125544 -0.11676 + outer loop + vertex -936.143 292.596 10.0746 + vertex -936.328 295.062 8.98546 + vertex -936.018 292.625 8.98413 + endloop + endfacet + facet normal -0.954688 -0.103746 0.278939 + outer loop + vertex -936.365 298.032 12.3411 + vertex -936.656 297.658 11.2087 + vertex -936.096 295.541 12.3378 + endloop + endfacet + facet normal -0.955703 -0.106425 0.274418 + outer loop + vertex -936.096 295.541 12.3378 + vertex -936.656 297.658 11.2087 + vertex -936.38 295.174 11.2063 + endloop + endfacet + facet normal -0.873567 -0.111007 0.473876 + outer loop + vertex -935.92 298.661 13.3091 + vertex -936.365 298.032 12.3411 + vertex -935.5 296.061 13.4747 + endloop + endfacet + facet normal -0.863504 -0.0941613 0.495475 + outer loop + vertex -935.5 296.061 13.4747 + vertex -936.365 298.032 12.3411 + vertex -936.096 295.541 12.3378 + endloop + endfacet + facet normal -0.863859 -0.0929158 0.49509 + outer loop + vertex -935.5 296.061 13.4747 + vertex -936.096 295.541 12.3378 + vertex -935.349 293.722 13.2987 + endloop + endfacet + facet normal -0.879107 -0.116581 0.462146 + outer loop + vertex -935.349 293.722 13.2987 + vertex -936.096 295.541 12.3378 + vertex -935.777 293.121 12.333 + endloop + endfacet + facet normal -0.951809 -0.125792 0.279707 + outer loop + vertex -936.096 295.541 12.3378 + vertex -936.38 295.174 11.2063 + vertex -935.777 293.121 12.333 + endloop + endfacet + facet normal -0.95095 -0.123356 0.283686 + outer loop + vertex -935.777 293.121 12.333 + vertex -936.38 295.174 11.2063 + vertex -936.066 292.747 11.204 + endloop + endfacet + facet normal -0.946465 -0.143424 0.289193 + outer loop + vertex -935.777 293.121 12.333 + vertex -936.066 292.747 11.204 + vertex -935.416 290.727 12.329 + endloop + endfacet + facet normal -0.947018 -0.145075 0.286548 + outer loop + vertex -935.416 290.727 12.329 + vertex -936.066 292.747 11.204 + vertex -935.698 290.342 11.2009 + endloop + endfacet + facet normal -0.866556 -0.148537 0.476464 + outer loop + vertex -935.349 293.722 13.2987 + vertex -935.777 293.121 12.333 + vertex -934.831 291.226 13.4634 + endloop + endfacet + facet normal -0.856781 -0.130234 0.498964 + outer loop + vertex -934.831 291.226 13.4634 + vertex -935.777 293.121 12.333 + vertex -935.416 290.727 12.329 + endloop + endfacet + facet normal -0.857014 -0.129491 0.498757 + outer loop + vertex -934.831 291.226 13.4634 + vertex -935.416 290.727 12.329 + vertex -934.587 288.931 13.2877 + endloop + endfacet + facet normal -0.868538 -0.148677 0.472797 + outer loop + vertex -934.587 288.931 13.2877 + vertex -935.416 290.727 12.329 + vertex -935.004 288.31 12.3256 + endloop + endfacet + facet normal -0.943052 -0.161122 0.29102 + outer loop + vertex -935.416 290.727 12.329 + vertex -935.698 290.342 11.2009 + vertex -935.004 288.31 12.3256 + endloop + endfacet + facet normal -0.943256 -0.161752 0.290007 + outer loop + vertex -935.004 288.31 12.3256 + vertex -935.698 290.342 11.2009 + vertex -935.282 287.911 11.198 + endloop + endfacet + facet normal -0.982177 -0.147102 -0.117004 + outer loop + vertex -936.143 292.596 10.0746 + vertex -936.018 292.625 8.98413 + vertex -935.781 290.179 10.0726 + endloop + endfacet + facet normal -0.982573 -0.146171 -0.114825 + outer loop + vertex -935.781 290.179 10.0726 + vertex -936.018 292.625 8.98413 + vertex -935.658 290.207 8.98283 + endloop + endfacet + facet normal -0.984695 -0.150583 0.0877494 + outer loop + vertex -936.066 292.747 11.204 + vertex -936.143 292.596 10.0746 + vertex -935.698 290.342 11.2009 + endloop + endfacet + facet normal -0.984602 -0.14764 0.0936005 + outer loop + vertex -935.698 290.342 11.2009 + vertex -936.143 292.596 10.0746 + vertex -935.781 290.179 10.0726 + endloop + endfacet + facet normal -0.981075 -0.167986 0.0962958 + outer loop + vertex -935.698 290.342 11.2009 + vertex -935.781 290.179 10.0726 + vertex -935.282 287.911 11.198 + endloop + endfacet + facet normal -0.981082 -0.168285 0.0956953 + outer loop + vertex -935.282 287.911 11.198 + vertex -935.781 290.179 10.0726 + vertex -935.363 287.742 10.0707 + endloop + endfacet + facet normal -0.979093 -0.167779 -0.115006 + outer loop + vertex -935.781 290.179 10.0726 + vertex -935.658 290.207 8.98283 + vertex -935.363 287.742 10.0707 + endloop + endfacet + facet normal -0.979765 -0.166275 -0.111417 + outer loop + vertex -935.363 287.742 10.0707 + vertex -935.658 290.207 8.98283 + vertex -935.244 287.771 8.98161 + endloop + endfacet + facet normal -0.990747 -0.0269035 -0.133026 + outer loop + vertex -937.325 308.018 10.0843 + vertex -937.179 308.052 8.99041 + vertex -937.253 305.381 10.083 + endloop + endfacet + facet normal -0.990846 -0.0266236 -0.132348 + outer loop + vertex -937.253 305.381 10.083 + vertex -937.179 308.052 8.99041 + vertex -937.108 305.419 8.99006 + endloop + endfacet + facet normal -0.997504 -0.0254761 0.0658558 + outer loop + vertex -937.253 308.16 11.2184 + vertex -937.325 308.018 10.0843 + vertex -937.186 305.521 11.2162 + endloop + endfacet + facet normal -0.9977 -0.0271963 0.0620857 + outer loop + vertex -937.186 305.521 11.2162 + vertex -937.325 308.018 10.0843 + vertex -937.253 305.381 10.083 + endloop + endfacet + facet normal -0.996696 -0.0490757 0.0647256 + outer loop + vertex -937.186 305.521 11.2162 + vertex -937.253 305.381 10.083 + vertex -937.056 302.868 11.2133 + endloop + endfacet + facet normal -0.996411 -0.0462917 0.0708656 + outer loop + vertex -937.056 302.868 11.2133 + vertex -937.253 305.381 10.083 + vertex -937.13 302.725 10.0812 + endloop + endfacet + facet normal -0.990066 -0.0458649 -0.132912 + outer loop + vertex -937.253 305.381 10.083 + vertex -937.108 305.419 8.99006 + vertex -937.13 302.725 10.0812 + endloop + endfacet + facet normal -0.990979 -0.0433815 -0.126799 + outer loop + vertex -937.13 302.725 10.0812 + vertex -937.108 305.419 8.99006 + vertex -936.992 302.763 8.98854 + endloop + endfacet + facet normal -0.966027 -0.0250026 0.257229 + outer loop + vertex -936.96 308.518 12.3562 + vertex -937.253 308.16 11.2184 + vertex -936.893 305.889 12.3532 + endloop + endfacet + facet normal -0.965945 -0.0248275 0.257553 + outer loop + vertex -936.893 305.889 12.3532 + vertex -937.253 308.16 11.2184 + vertex -937.186 305.521 11.2162 + endloop + endfacet + facet normal -0.892748 -0.0410282 0.448685 + outer loop + vertex -936.496 309.109 13.3322 + vertex -936.96 308.518 12.3562 + vertex -936.286 306.376 13.5002 + endloop + endfacet + facet normal -0.879818 -0.0230438 0.474751 + outer loop + vertex -936.286 306.376 13.5002 + vertex -936.96 308.518 12.3562 + vertex -936.893 305.889 12.3532 + endloop + endfacet + facet normal -0.878832 -0.0279449 0.476312 + outer loop + vertex -936.286 306.376 13.5002 + vertex -936.893 305.889 12.3532 + vertex -936.305 303.869 13.3192 + endloop + endfacet + facet normal -0.890776 -0.0428507 0.452418 + outer loop + vertex -936.305 303.869 13.3192 + vertex -936.893 305.889 12.3532 + vertex -936.767 303.24 12.349 + endloop + endfacet + facet normal -0.96349 -0.0459936 0.263765 + outer loop + vertex -936.893 305.889 12.3532 + vertex -937.186 305.521 11.2162 + vertex -936.767 303.24 12.349 + endloop + endfacet + facet normal -0.964263 -0.0476979 0.260619 + outer loop + vertex -936.767 303.24 12.349 + vertex -937.186 305.521 11.2162 + vertex -937.056 302.868 11.2133 + endloop + endfacet + facet normal -0.961794 -0.0655085 0.265823 + outer loop + vertex -936.767 303.24 12.349 + vertex -937.056 302.868 11.2133 + vertex -936.589 300.607 12.3442 + endloop + endfacet + facet normal -0.961088 -0.063899 0.26875 + outer loop + vertex -936.589 300.607 12.3442 + vertex -937.056 302.868 11.2133 + vertex -936.881 300.23 11.2108 + endloop + endfacet + facet normal -0.881546 -0.0715596 0.466643 + outer loop + vertex -936.305 303.869 13.3192 + vertex -936.767 303.24 12.349 + vertex -935.992 301.132 13.4897 + endloop + endfacet + facet normal -0.873694 -0.0599466 0.482767 + outer loop + vertex -935.992 301.132 13.4897 + vertex -936.767 303.24 12.349 + vertex -936.589 300.607 12.3442 + endloop + endfacet + facet normal -0.873493 -0.0607494 0.483031 + outer loop + vertex -935.992 301.132 13.4897 + vertex -936.589 300.607 12.3442 + vertex -935.92 298.661 13.3091 + endloop + endfacet + facet normal -0.885723 -0.0775191 0.457697 + outer loop + vertex -935.92 298.661 13.3091 + vertex -936.589 300.607 12.3442 + vertex -936.365 298.032 12.3411 + endloop + endfacet + facet normal -0.957956 -0.0835703 0.274476 + outer loop + vertex -936.589 300.607 12.3442 + vertex -936.881 300.23 11.2108 + vertex -936.365 298.032 12.3411 + endloop + endfacet + facet normal -0.958213 -0.0841912 0.273386 + outer loop + vertex -936.365 298.032 12.3411 + vertex -936.881 300.23 11.2108 + vertex -936.656 297.658 11.2087 + endloop + endfacet + facet normal -0.989569 -0.0671318 -0.127459 + outer loop + vertex -937.13 302.725 10.0812 + vertex -936.992 302.763 8.98854 + vertex -936.951 300.093 10.0799 + endloop + endfacet + facet normal -0.990206 -0.0654504 -0.123322 + outer loop + vertex -936.951 300.093 10.0799 + vertex -936.992 302.763 8.98854 + vertex -936.817 300.13 8.98772 + endloop + endfacet + facet normal -0.995128 -0.0659649 0.0732734 + outer loop + vertex -937.056 302.868 11.2133 + vertex -937.13 302.725 10.0812 + vertex -936.881 300.23 11.2108 + endloop + endfacet + facet normal -0.995277 -0.067615 0.0696618 + outer loop + vertex -936.881 300.23 11.2108 + vertex -937.13 302.725 10.0812 + vertex -936.951 300.093 10.0799 + endloop + endfacet + facet normal -0.993597 -0.0871331 0.0719268 + outer loop + vertex -936.881 300.23 11.2108 + vertex -936.951 300.093 10.0799 + vertex -936.656 297.658 11.2087 + endloop + endfacet + facet normal -0.993542 -0.0863399 0.0736234 + outer loop + vertex -936.656 297.658 11.2087 + vertex -936.951 300.093 10.0799 + vertex -936.728 297.521 10.0781 + endloop + endfacet + facet normal -0.988591 -0.0857661 -0.123823 + outer loop + vertex -936.951 300.093 10.0799 + vertex -936.817 300.13 8.98772 + vertex -936.728 297.521 10.0781 + endloop + endfacet + facet normal -0.988973 -0.0847774 -0.121426 + outer loop + vertex -936.728 297.521 10.0781 + vertex -936.817 300.13 8.98772 + vertex -936.597 297.558 8.98652 + endloop + endfacet + facet normal -0.98924 0.0490711 -0.137827 + outer loop + vertex -937.103 318.341 10.0939 + vertex -936.948 318.376 8.99759 + vertex -937.231 315.749 10.0918 + endloop + endfacet + facet normal -0.988943 0.0480053 -0.14031 + outer loop + vertex -937.231 315.749 10.0918 + vertex -936.948 318.376 8.99759 + vertex -937.074 315.781 8.99507 + endloop + endfacet + facet normal -0.997844 0.0461722 0.0466518 + outer loop + vertex -937.045 318.456 11.227 + vertex -937.103 318.341 10.0939 + vertex -937.164 315.881 11.2283 + endloop + endfacet + facet normal -0.99735 0.0493135 0.0534903 + outer loop + vertex -937.164 315.881 11.2283 + vertex -937.103 318.341 10.0939 + vertex -937.231 315.749 10.0918 + endloop + endfacet + facet normal -0.99799 0.0300856 0.055769 + outer loop + vertex -937.164 315.881 11.2283 + vertex -937.231 315.749 10.0918 + vertex -937.241 313.321 11.2253 + endloop + endfacet + facet normal -0.998047 0.0297052 0.0549541 + outer loop + vertex -937.241 313.321 11.2253 + vertex -937.231 315.749 10.0918 + vertex -937.308 313.185 10.0887 + endloop + endfacet + facet normal -0.989573 0.0296875 -0.140938 + outer loop + vertex -937.231 315.749 10.0918 + vertex -937.074 315.781 8.99507 + vertex -937.308 313.185 10.0887 + endloop + endfacet + facet normal -0.989916 0.0308479 -0.138257 + outer loop + vertex -937.308 313.185 10.0887 + vertex -937.074 315.781 8.99507 + vertex -937.154 313.215 8.99328 + endloop + endfacet + facet normal -0.970107 0.047221 0.238038 + outer loop + vertex -936.75 318.79 12.3601 + vertex -937.045 318.456 11.227 + vertex -936.874 316.217 12.3654 + endloop + endfacet + facet normal -0.971213 0.0450406 0.233915 + outer loop + vertex -936.874 316.217 12.3654 + vertex -937.045 318.456 11.227 + vertex -937.164 315.881 11.2283 + endloop + endfacet + facet normal -0.908218 0.0290344 0.417489 + outer loop + vertex -936.284 319.378 13.3325 + vertex -936.75 318.79 12.3601 + vertex -936.288 316.675 13.5134 + endloop + endfacet + facet normal -0.896676 0.0440991 0.440486 + outer loop + vertex -936.288 316.675 13.5134 + vertex -936.75 318.79 12.3601 + vertex -936.874 316.217 12.3654 + endloop + endfacet + facet normal -0.896103 0.0393199 0.442102 + outer loop + vertex -936.288 316.675 13.5134 + vertex -936.874 316.217 12.3654 + vertex -936.482 314.24 13.3369 + endloop + endfacet + facet normal -0.906461 0.0270968 0.421419 + outer loop + vertex -936.482 314.24 13.3369 + vertex -936.874 316.217 12.3654 + vertex -936.951 313.663 12.365 + endloop + endfacet + facet normal -0.970707 0.0290551 0.238505 + outer loop + vertex -936.874 316.217 12.3654 + vertex -937.164 315.881 11.2283 + vertex -936.951 313.663 12.365 + endloop + endfacet + facet normal -0.970711 0.0290462 0.238488 + outer loop + vertex -936.951 313.663 12.365 + vertex -937.164 315.881 11.2283 + vertex -937.241 313.321 11.2253 + endloop + endfacet + facet normal -0.969824 0.0114649 0.243537 + outer loop + vertex -936.951 313.663 12.365 + vertex -937.241 313.321 11.2253 + vertex -936.982 311.105 12.3612 + endloop + endfacet + facet normal -0.969224 0.0127208 0.245851 + outer loop + vertex -936.982 311.105 12.3612 + vertex -937.241 313.321 11.2253 + vertex -937.276 310.754 11.2215 + endloop + endfacet + facet normal -0.898952 -0.00694195 0.437992 + outer loop + vertex -936.482 314.24 13.3369 + vertex -936.951 313.663 12.365 + vertex -936.378 311.561 13.5078 + endloop + endfacet + facet normal -0.886282 0.0101239 0.463036 + outer loop + vertex -936.378 311.561 13.5078 + vertex -936.951 313.663 12.365 + vertex -936.982 311.105 12.3612 + endloop + endfacet + facet normal -0.886222 0.00973837 0.463158 + outer loop + vertex -936.378 311.561 13.5078 + vertex -936.982 311.105 12.3612 + vertex -936.496 309.109 13.3322 + endloop + endfacet + facet normal -0.90131 -0.00856329 0.433089 + outer loop + vertex -936.496 309.109 13.3322 + vertex -936.982 311.105 12.3612 + vertex -936.96 308.518 12.3562 + endloop + endfacet + facet normal -0.967669 -0.00877923 0.252071 + outer loop + vertex -936.982 311.105 12.3612 + vertex -937.276 310.754 11.2215 + vertex -936.96 308.518 12.3562 + endloop + endfacet + facet normal -0.96757 -0.00857017 0.252456 + outer loop + vertex -936.96 308.518 12.3562 + vertex -937.276 310.754 11.2215 + vertex -937.253 308.16 11.2184 + endloop + endfacet + facet normal -0.990244 0.0121336 -0.138817 + outer loop + vertex -937.308 313.185 10.0887 + vertex -937.154 313.215 8.99328 + vertex -937.339 310.618 10.0864 + endloop + endfacet + facet normal -0.990875 0.0141923 -0.134033 + outer loop + vertex -937.339 310.618 10.0864 + vertex -937.154 313.215 8.99328 + vertex -937.19 310.649 8.99184 + endloop + endfacet + facet normal -0.998288 0.0133947 0.0569289 + outer loop + vertex -937.241 313.321 11.2253 + vertex -937.308 313.185 10.0887 + vertex -937.276 310.754 11.2215 + endloop + endfacet + facet normal -0.998464 0.0120591 0.0540678 + outer loop + vertex -937.276 310.754 11.2215 + vertex -937.308 313.185 10.0887 + vertex -937.339 310.618 10.0864 + endloop + endfacet + facet normal -0.998363 -0.00859635 0.0565379 + outer loop + vertex -937.276 310.754 11.2215 + vertex -937.339 310.618 10.0864 + vertex -937.253 308.16 11.2184 + endloop + endfacet + facet normal -0.997976 -0.00543771 0.0633666 + outer loop + vertex -937.253 308.16 11.2184 + vertex -937.339 310.618 10.0864 + vertex -937.325 308.018 10.0843 + endloop + endfacet + facet normal -0.990889 -0.00524358 -0.134581 + outer loop + vertex -937.339 310.618 10.0864 + vertex -937.19 310.649 8.99184 + vertex -937.325 308.018 10.0843 + endloop + endfacet + facet normal -0.991192 -0.00430836 -0.132366 + outer loop + vertex -937.325 308.018 10.0843 + vertex -937.19 310.649 8.99184 + vertex -937.179 308.052 8.99041 + endloop + endfacet + facet normal -0.984117 0.108133 -0.140785 + outer loop + vertex -936.198 328.862 10.1008 + vertex -936.039 328.854 8.98319 + vertex -936.485 326.224 10.0806 + endloop + endfacet + facet normal -0.983595 0.105835 -0.14608 + outer loop + vertex -936.485 326.224 10.0806 + vertex -936.039 328.854 8.98319 + vertex -936.318 326.269 8.98654 + endloop + endfacet + facet normal -0.991597 0.11484 0.059565 + outer loop + vertex -936.095 329.127 11.3083 + vertex -936.198 328.862 10.1008 + vertex -936.416 326.392 11.2424 + endloop + endfacet + facet normal -0.993216 0.107707 0.0438246 + outer loop + vertex -936.416 326.392 11.2424 + vertex -936.198 328.862 10.1008 + vertex -936.485 326.224 10.0806 + endloop + endfacet + facet normal -0.994481 0.0943816 0.0458309 + outer loop + vertex -936.416 326.392 11.2424 + vertex -936.485 326.224 10.0806 + vertex -936.672 323.706 11.218 + endloop + endfacet + facet normal -0.994948 0.0919328 0.0403321 + outer loop + vertex -936.672 323.706 11.218 + vertex -936.485 326.224 10.0806 + vertex -936.729 323.59 10.0823 + endloop + endfacet + facet normal -0.984965 0.0908925 -0.146908 + outer loop + vertex -936.485 326.224 10.0806 + vertex -936.318 326.269 8.98654 + vertex -936.729 323.59 10.0823 + endloop + endfacet + facet normal -0.985263 0.0920623 -0.144159 + outer loop + vertex -936.729 323.59 10.0823 + vertex -936.318 326.269 8.98654 + vertex -936.564 323.647 8.99438 + endloop + endfacet + facet normal -0.963887 0.118634 0.238426 + outer loop + vertex -935.726 329.615 12.5598 + vertex -936.095 329.127 11.3083 + vertex -936.103 326.806 12.4335 + endloop + endfacet + facet normal -0.970012 0.108505 0.217494 + outer loop + vertex -936.103 326.806 12.4335 + vertex -936.095 329.127 11.3083 + vertex -936.416 326.392 11.2424 + endloop + endfacet + facet normal -0.908956 0.100471 0.404603 + outer loop + vertex -935.296 329.724 13.4981 + vertex -935.726 329.615 12.5598 + vertex -935.523 327.246 13.6041 + endloop + endfacet + facet normal -0.906158 0.103163 0.410165 + outer loop + vertex -935.523 327.246 13.6041 + vertex -935.726 329.615 12.5598 + vertex -936.103 326.806 12.4335 + endloop + endfacet + facet normal -0.905864 0.0971733 0.41227 + outer loop + vertex -935.523 327.246 13.6041 + vertex -936.103 326.806 12.4335 + vertex -935.9 324.698 13.3752 + endloop + endfacet + facet normal -0.919401 0.0834156 0.384375 + outer loop + vertex -935.9 324.698 13.3752 + vertex -936.103 326.806 12.4335 + vertex -936.375 324.074 12.3745 + endloop + endfacet + facet normal -0.970392 0.0919849 0.223334 + outer loop + vertex -936.103 326.806 12.4335 + vertex -936.416 326.392 11.2424 + vertex -936.375 324.074 12.3745 + endloop + endfacet + facet normal -0.97118 0.090572 0.220469 + outer loop + vertex -936.375 324.074 12.3745 + vertex -936.416 326.392 11.2424 + vertex -936.672 323.706 11.218 + endloop + endfacet + facet normal -0.971354 0.076155 0.225105 + outer loop + vertex -936.375 324.074 12.3745 + vertex -936.672 323.706 11.218 + vertex -936.589 321.401 12.3573 + endloop + endfacet + facet normal -0.971597 0.0757013 0.224205 + outer loop + vertex -936.589 321.401 12.3573 + vertex -936.672 323.706 11.218 + vertex -936.877 321.065 11.2197 + endloop + endfacet + facet normal -0.914985 0.0555432 0.399648 + outer loop + vertex -935.9 324.698 13.3752 + vertex -936.375 324.074 12.3745 + vertex -936.008 321.891 13.5188 + endloop + endfacet + facet normal -0.903652 0.0694786 0.422594 + outer loop + vertex -936.008 321.891 13.5188 + vertex -936.375 324.074 12.3745 + vertex -936.589 321.401 12.3573 + endloop + endfacet + facet normal -0.903516 0.0680966 0.423109 + outer loop + vertex -936.008 321.891 13.5188 + vertex -936.589 321.401 12.3573 + vertex -936.284 319.378 13.3325 + endloop + endfacet + facet normal -0.913387 0.0569616 0.403087 + outer loop + vertex -936.284 319.378 13.3325 + vertex -936.589 321.401 12.3573 + vertex -936.75 318.79 12.3601 + endloop + endfacet + facet normal -0.971615 0.0603744 0.228736 + outer loop + vertex -936.589 321.401 12.3573 + vertex -936.877 321.065 11.2197 + vertex -936.75 318.79 12.3601 + endloop + endfacet + facet normal -0.970326 0.0628315 0.233493 + outer loop + vertex -936.75 318.79 12.3601 + vertex -936.877 321.065 11.2197 + vertex -937.045 318.456 11.227 + endloop + endfacet + facet normal -0.986401 0.0771647 -0.145119 + outer loop + vertex -936.729 323.59 10.0823 + vertex -936.564 323.647 8.99438 + vertex -936.936 320.957 10.0903 + endloop + endfacet + facet normal -0.987032 0.0795791 -0.139407 + outer loop + vertex -936.936 320.957 10.0903 + vertex -936.564 323.647 8.99438 + vertex -936.778 321.005 8.99829 + endloop + endfacet + facet normal -0.996113 0.0774941 0.0418658 + outer loop + vertex -936.672 323.706 11.218 + vertex -936.729 323.59 10.0823 + vertex -936.877 321.065 11.2197 + endloop + endfacet + facet normal -0.995939 0.0784912 0.044102 + outer loop + vertex -936.877 321.065 11.2197 + vertex -936.729 323.59 10.0823 + vertex -936.936 320.957 10.0903 + endloop + endfacet + facet normal -0.99691 0.0640081 0.0455291 + outer loop + vertex -936.877 321.065 11.2197 + vertex -936.936 320.957 10.0903 + vertex -937.045 318.456 11.227 + endloop + endfacet + facet normal -0.996962 0.0636925 0.0448298 + outer loop + vertex -937.045 318.456 11.227 + vertex -936.936 320.957 10.0903 + vertex -937.103 318.341 10.0939 + endloop + endfacet + facet normal -0.988112 0.0628692 -0.140294 + outer loop + vertex -936.936 320.957 10.0903 + vertex -936.778 321.005 8.99829 + vertex -937.103 318.341 10.0939 + endloop + endfacet + facet normal -0.988458 0.0641683 -0.137237 + outer loop + vertex -937.103 318.341 10.0939 + vertex -936.778 321.005 8.99829 + vertex -936.948 318.376 8.99759 + endloop + endfacet + facet normal -0.980309 0.16305 -0.111398 + outer loop + vertex -934.714 339.088 10.1954 + vertex -934.61 338.919 9.02827 + vertex -935.136 336.543 10.1841 + endloop + endfacet + facet normal -0.980008 0.158995 -0.1196 + outer loop + vertex -935.136 336.543 10.1841 + vertex -934.61 338.919 9.02827 + vertex -935.017 336.408 9.02355 + endloop + endfacet + facet normal -0.98432 0.150159 0.0925525 + outer loop + vertex -934.545 339.532 11.2771 + vertex -934.714 339.088 10.1954 + vertex -934.946 336.776 11.4779 + endloop + endfacet + facet normal -0.980101 0.162013 0.114691 + outer loop + vertex -934.946 336.776 11.4779 + vertex -934.714 339.088 10.1954 + vertex -935.136 336.543 10.1841 + endloop + endfacet + facet normal -0.979762 0.164384 0.114214 + outer loop + vertex -934.946 336.776 11.4779 + vertex -935.136 336.543 10.1841 + vertex -935.371 334.414 11.2353 + endloop + endfacet + facet normal -0.985702 0.148215 0.0801493 + outer loop + vertex -935.371 334.414 11.2353 + vertex -935.136 336.543 10.1841 + vertex -935.512 334.058 10.1536 + endloop + endfacet + facet normal -0.981529 0.150025 -0.118714 + outer loop + vertex -935.136 336.543 10.1841 + vertex -935.017 336.408 9.02355 + vertex -935.512 334.058 10.1536 + endloop + endfacet + facet normal -0.981334 0.148041 -0.122753 + outer loop + vertex -935.512 334.058 10.1536 + vertex -935.017 336.408 9.02355 + vertex -935.391 333.916 9.00696 + endloop + endfacet + facet normal -0.93373 0.159403 0.320529 + outer loop + vertex -934.545 339.532 11.2771 + vertex -934.946 336.776 11.4779 + vertex -934.2 338.339 12.8752 + endloop + endfacet + facet normal -0.941726 0.13775 0.306883 + outer loop + vertex -935.371 334.414 11.2353 + vertex -935.045 332.993 12.8736 + vertex -934.946 336.776 11.4779 + endloop + endfacet + facet normal -0.931375 0.14712 0.333011 + outer loop + vertex -935.045 332.993 12.8736 + vertex -934.2 338.339 12.8752 + vertex -934.946 336.776 11.4779 + endloop + endfacet + facet normal -0.963544 0.129675 0.234024 + outer loop + vertex -936.095 329.127 11.3083 + vertex -935.726 329.615 12.5598 + vertex -935.7 331.912 11.3906 + endloop + endfacet + facet normal -0.939574 0.143029 0.311035 + outer loop + vertex -935.371 334.414 11.2353 + vertex -935.7 331.912 11.3906 + vertex -935.045 332.993 12.8736 + endloop + endfacet + facet normal -0.90581 0.14555 0.397898 + outer loop + vertex -935.296 329.724 13.4981 + vertex -935.045 332.993 12.8736 + vertex -935.726 329.615 12.5598 + endloop + endfacet + facet normal -0.940794 0.161894 0.29782 + outer loop + vertex -935.7 331.912 11.3906 + vertex -935.726 329.615 12.5598 + vertex -935.045 332.993 12.8736 + endloop + endfacet + facet normal -0.983384 0.135022 -0.121349 + outer loop + vertex -935.512 334.058 10.1536 + vertex -935.391 333.916 9.00696 + vertex -935.863 331.497 10.1408 + endloop + endfacet + facet normal -0.982978 0.131852 -0.127943 + outer loop + vertex -935.863 331.497 10.1408 + vertex -935.391 333.916 9.00696 + vertex -935.726 331.403 8.99257 + endloop + endfacet + facet normal -0.987193 0.135244 0.0846131 + outer loop + vertex -935.371 334.414 11.2353 + vertex -935.512 334.058 10.1536 + vertex -935.7 331.912 11.3906 + endloop + endfacet + facet normal -0.987394 0.134544 0.0833677 + outer loop + vertex -935.7 331.912 11.3906 + vertex -935.512 334.058 10.1536 + vertex -935.863 331.497 10.1408 + endloop + endfacet + facet normal -0.987074 0.137494 0.0823461 + outer loop + vertex -935.7 331.912 11.3906 + vertex -935.863 331.497 10.1408 + vertex -936.095 329.127 11.3083 + endloop + endfacet + facet normal -0.990458 0.125411 0.0571487 + outer loop + vertex -936.095 329.127 11.3083 + vertex -935.863 331.497 10.1408 + vertex -936.198 328.862 10.1008 + endloop + endfacet + facet normal -0.983611 0.127339 -0.12765 + outer loop + vertex -935.863 331.497 10.1408 + vertex -935.726 331.403 8.99257 + vertex -936.198 328.862 10.1008 + endloop + endfacet + facet normal -0.982578 0.121471 -0.140662 + outer loop + vertex -936.198 328.862 10.1008 + vertex -935.726 331.403 8.99257 + vertex -936.039 328.854 8.98319 + endloop + endfacet + facet normal -0.974989 0.206577 -0.0819945 + outer loop + vertex -932.785 349.223 10.1914 + vertex -932.855 348.518 9.24716 + vertex -933.303 346.79 10.2192 + endloop + endfacet + facet normal -0.975413 0.189693 -0.112192 + outer loop + vertex -933.303 346.79 10.2192 + vertex -932.855 348.518 9.24716 + vertex -933.212 346.575 9.0621 + endloop + endfacet + facet normal -0.977842 0.19193 0.0835993 + outer loop + vertex -932.553 349.929 11.2862 + vertex -932.785 349.223 10.1914 + vertex -933.067 347.215 11.5039 + endloop + endfacet + facet normal -0.971941 0.208114 0.109633 + outer loop + vertex -933.067 347.215 11.5039 + vertex -932.785 349.223 10.1914 + vertex -933.303 346.79 10.2192 + endloop + endfacet + facet normal -0.972741 0.203424 0.111329 + outer loop + vertex -933.067 347.215 11.5039 + vertex -933.303 346.79 10.2192 + vertex -933.602 344.778 11.2837 + endloop + endfacet + facet normal -0.979623 0.185843 0.0761663 + outer loop + vertex -933.602 344.778 11.2837 + vertex -933.303 346.79 10.2192 + vertex -933.778 344.298 10.1867 + endloop + endfacet + facet normal -0.975863 0.187577 -0.111834 + outer loop + vertex -933.303 346.79 10.2192 + vertex -933.212 346.575 9.0621 + vertex -933.778 344.298 10.1867 + endloop + endfacet + facet normal -0.975732 0.184662 -0.117671 + outer loop + vertex -933.778 344.298 10.1867 + vertex -933.212 346.575 9.0621 + vertex -933.673 344.096 9.0007 + endloop + endfacet + facet normal -0.937554 0.200392 0.284317 + outer loop + vertex -932.553 349.929 11.2862 + vertex -933.067 347.215 11.5039 + vertex -932.307 348.743 12.9334 + endloop + endfacet + facet normal -0.935046 0.177483 0.306901 + outer loop + vertex -933.602 344.778 11.2837 + vertex -933.301 343.568 12.9005 + vertex -933.067 347.215 11.5039 + endloop + endfacet + facet normal -0.934905 0.17761 0.307257 + outer loop + vertex -933.301 343.568 12.9005 + vertex -932.307 348.743 12.9334 + vertex -933.067 347.215 11.5039 + endloop + endfacet + facet normal -0.935882 0.175439 0.305527 + outer loop + vertex -933.602 344.778 11.2837 + vertex -934.054 342.008 11.4889 + vertex -933.301 343.568 12.9005 + endloop + endfacet + facet normal -0.934347 0.157847 0.3195 + outer loop + vertex -934.545 339.532 11.2771 + vertex -934.2 338.339 12.8752 + vertex -934.054 342.008 11.4889 + endloop + endfacet + facet normal -0.933183 0.158887 0.322374 + outer loop + vertex -934.2 338.339 12.8752 + vertex -933.301 343.568 12.9005 + vertex -934.054 342.008 11.4889 + endloop + endfacet + facet normal -0.976873 0.179087 -0.116823 + outer loop + vertex -933.778 344.298 10.1867 + vertex -933.673 344.096 9.0007 + vertex -934.256 341.693 10.1872 + endloop + endfacet + facet normal -0.976979 0.181187 -0.112622 + outer loop + vertex -934.256 341.693 10.1872 + vertex -933.673 344.096 9.0007 + vertex -934.158 341.492 9.01185 + endloop + endfacet + facet normal -0.982339 0.166693 0.0849905 + outer loop + vertex -933.602 344.778 11.2837 + vertex -933.778 344.298 10.1867 + vertex -934.054 342.008 11.4889 + endloop + endfacet + facet normal -0.977833 0.17931 0.108127 + outer loop + vertex -934.054 342.008 11.4889 + vertex -933.778 344.298 10.1867 + vertex -934.256 341.693 10.1872 + endloop + endfacet + facet normal -0.977019 0.184502 0.106743 + outer loop + vertex -934.054 342.008 11.4889 + vertex -934.256 341.693 10.1872 + vertex -934.545 339.532 11.2771 + endloop + endfacet + facet normal -0.981442 0.172988 0.0827401 + outer loop + vertex -934.545 339.532 11.2771 + vertex -934.256 341.693 10.1872 + vertex -934.714 339.088 10.1954 + endloop + endfacet + facet normal -0.978816 0.171916 -0.11119 + outer loop + vertex -934.256 341.693 10.1872 + vertex -934.158 341.492 9.01185 + vertex -934.714 339.088 10.1954 + endloop + endfacet + facet normal -0.978783 0.171285 -0.112455 + outer loop + vertex -934.714 339.088 10.1954 + vertex -934.158 341.492 9.01185 + vertex -934.61 338.919 9.02827 + endloop + endfacet + facet normal -0.952084 0.232844 -0.19829 + outer loop + vertex -930.426 359.111 10.0996 + vertex -930.318 358.327 8.65684 + vertex -931.004 356.738 10.0856 + endloop + endfacet + facet normal -0.952103 0.230869 -0.200497 + outer loop + vertex -931.004 356.738 10.0856 + vertex -930.318 358.327 8.65684 + vertex -930.898 355.924 8.64417 + endloop + endfacet + facet normal -0.974262 0.224415 0.0212316 + outer loop + vertex -930.237 359.819 11.3245 + vertex -930.426 359.111 10.0996 + vertex -930.813 357.294 11.5402 + endloop + endfacet + facet normal -0.971039 0.236071 0.0367959 + outer loop + vertex -930.813 357.294 11.5402 + vertex -930.426 359.111 10.0996 + vertex -931.004 356.738 10.0856 + endloop + endfacet + facet normal -0.968251 0.247939 0.0318899 + outer loop + vertex -930.813 357.294 11.5402 + vertex -931.004 356.738 10.0856 + vertex -931.409 354.998 11.305 + endloop + endfacet + facet normal -0.972614 0.232284 0.00810131 + outer loop + vertex -931.409 354.998 11.305 + vertex -931.004 356.738 10.0856 + vertex -931.59 354.284 10.0762 + endloop + endfacet + facet normal -0.952981 0.22839 -0.199162 + outer loop + vertex -931.004 356.738 10.0856 + vertex -930.898 355.924 8.64417 + vertex -931.59 354.284 10.0762 + endloop + endfacet + facet normal -0.95298 0.229074 -0.198378 + outer loop + vertex -931.59 354.284 10.0762 + vertex -930.898 355.924 8.64417 + vertex -931.522 353.363 8.68455 + endloop + endfacet + facet normal -0.937437 0.236049 0.255916 + outer loop + vertex -930.237 359.819 11.3245 + vertex -930.813 357.294 11.5402 + vertex -930.056 358.739 12.9827 + endloop + endfacet + facet normal -0.939498 0.216565 0.265411 + outer loop + vertex -931.409 354.998 11.305 + vertex -931.215 353.808 12.9646 + vertex -930.813 357.294 11.5402 + endloop + endfacet + facet normal -0.936856 0.219166 0.272519 + outer loop + vertex -931.215 353.808 12.9646 + vertex -930.056 358.739 12.9827 + vertex -930.813 357.294 11.5402 + endloop + endfacet + facet normal -0.938473 0.219 0.267035 + outer loop + vertex -931.409 354.998 11.305 + vertex -931.97 352.346 11.5085 + vertex -931.215 353.808 12.9646 + endloop + endfacet + facet normal -0.937725 0.199977 0.284043 + outer loop + vertex -932.553 349.929 11.2862 + vertex -932.307 348.743 12.9334 + vertex -931.97 352.346 11.5085 + endloop + endfacet + facet normal -0.937309 0.200371 0.285137 + outer loop + vertex -932.307 348.743 12.9334 + vertex -931.215 353.808 12.9646 + vertex -931.97 352.346 11.5085 + endloop + endfacet + facet normal -0.954954 0.223741 -0.194945 + outer loop + vertex -931.59 354.284 10.0762 + vertex -931.522 353.363 8.68455 + vertex -932.192 351.74 10.1067 + endloop + endfacet + facet normal -0.954397 0.245583 -0.169749 + outer loop + vertex -932.192 351.74 10.1067 + vertex -931.522 353.363 8.68455 + vertex -932.239 350.726 8.90017 + endloop + endfacet + facet normal -0.977749 0.208556 0.0226256 + outer loop + vertex -931.409 354.998 11.305 + vertex -931.59 354.284 10.0762 + vertex -931.97 352.346 11.5085 + endloop + endfacet + facet normal -0.971525 0.230655 0.0541906 + outer loop + vertex -931.97 352.346 11.5085 + vertex -931.59 354.284 10.0762 + vertex -932.192 351.74 10.1067 + endloop + endfacet + facet normal -0.971815 0.229279 0.0548315 + outer loop + vertex -931.97 352.346 11.5085 + vertex -932.192 351.74 10.1067 + vertex -932.553 349.929 11.2862 + endloop + endfacet + facet normal -0.971338 0.230721 0.0571906 + outer loop + vertex -932.553 349.929 11.2862 + vertex -932.192 351.74 10.1067 + vertex -932.785 349.223 10.1914 + endloop + endfacet + facet normal -0.963531 0.221926 -0.149522 + outer loop + vertex -932.192 351.74 10.1067 + vertex -932.239 350.726 8.90017 + vertex -932.785 349.223 10.1914 + endloop + endfacet + facet normal -0.961258 0.250226 -0.115625 + outer loop + vertex -932.785 349.223 10.1914 + vertex -932.239 350.726 8.90017 + vertex -932.855 348.518 9.24716 + endloop + endfacet + facet normal -0.934384 0.286046 -0.21238 + outer loop + vertex -927.357 370.449 10.3523 + vertex -927.045 370.166 8.59915 + vertex -928.33 367.119 10.1471 + endloop + endfacet + facet normal -0.933967 0.282728 -0.218566 + outer loop + vertex -928.33 367.119 10.1471 + vertex -927.045 370.166 8.59915 + vertex -928.217 366.322 8.63224 + endloop + endfacet + facet normal -0.963372 0.267925 -0.0114504 + outer loop + vertex -927.454 370.154 11.5933 + vertex -927.357 370.449 10.3523 + vertex -928.19 367.508 11.648 + endloop + endfacet + facet normal -0.960025 0.27941 0.0167704 + outer loop + vertex -928.19 367.508 11.648 + vertex -927.357 370.449 10.3523 + vertex -928.33 367.119 10.1471 + endloop + endfacet + facet normal -0.961014 0.27593 0.0177645 + outer loop + vertex -928.19 367.508 11.648 + vertex -928.33 367.119 10.1471 + vertex -928.951 364.878 11.3556 + endloop + endfacet + facet normal -0.964047 0.265717 -0.00273209 + outer loop + vertex -928.951 364.878 11.3556 + vertex -928.33 367.119 10.1471 + vertex -929.157 364.117 10.1111 + endloop + endfacet + facet normal -0.942256 0.262174 -0.20837 + outer loop + vertex -928.33 367.119 10.1471 + vertex -928.217 366.322 8.63224 + vertex -929.157 364.117 10.1111 + endloop + endfacet + facet normal -0.942561 0.272303 -0.193467 + outer loop + vertex -929.157 364.117 10.1111 + vertex -928.217 366.322 8.63224 + vertex -929.117 363.262 8.71335 + endloop + endfacet + facet normal -0.921901 0.262508 0.284936 + outer loop + vertex -927.454 370.154 11.5933 + vertex -928.19 367.508 11.648 + vertex -927.336 369.06 12.9834 + endloop + endfacet + facet normal -0.935867 0.242176 0.255938 + outer loop + vertex -928.951 364.878 11.3556 + vertex -928.795 363.749 12.9934 + vertex -928.19 367.508 11.648 + endloop + endfacet + facet normal -0.921276 0.253722 0.294748 + outer loop + vertex -928.795 363.749 12.9934 + vertex -927.336 369.06 12.9834 + vertex -928.19 367.508 11.648 + endloop + endfacet + facet normal -0.935264 0.243555 0.25683 + outer loop + vertex -928.951 364.878 11.3556 + vertex -929.609 362.145 11.5501 + vertex -928.795 363.749 12.9934 + endloop + endfacet + facet normal -0.940266 0.229177 0.25175 + outer loop + vertex -930.237 359.819 11.3245 + vertex -930.056 358.739 12.9827 + vertex -929.609 362.145 11.5501 + endloop + endfacet + facet normal -0.934838 0.234661 0.266479 + outer loop + vertex -930.056 358.739 12.9827 + vertex -928.795 363.749 12.9934 + vertex -929.609 362.145 11.5501 + endloop + endfacet + facet normal -0.952864 0.245962 -0.177633 + outer loop + vertex -929.157 364.117 10.1111 + vertex -929.117 363.262 8.71335 + vertex -929.829 361.512 10.1089 + endloop + endfacet + facet normal -0.952963 0.237543 -0.188242 + outer loop + vertex -929.829 361.512 10.1089 + vertex -929.117 363.262 8.71335 + vertex -929.743 360.726 8.6837 + endloop + endfacet + facet normal -0.971774 0.23529 0.0171322 + outer loop + vertex -928.951 364.878 11.3556 + vertex -929.157 364.117 10.1111 + vertex -929.609 362.145 11.5501 + endloop + endfacet + facet normal -0.967606 0.249584 0.0380401 + outer loop + vertex -929.609 362.145 11.5501 + vertex -929.157 364.117 10.1111 + vertex -929.829 361.512 10.1089 + endloop + endfacet + facet normal -0.965763 0.257129 0.0344453 + outer loop + vertex -929.609 362.145 11.5501 + vertex -929.829 361.512 10.1089 + vertex -930.237 359.819 11.3245 + endloop + endfacet + facet normal -0.970387 0.241312 0.0108661 + outer loop + vertex -930.237 359.819 11.3245 + vertex -929.829 361.512 10.1089 + vertex -930.426 359.111 10.0996 + endloop + endfacet + facet normal -0.952895 0.237735 -0.188343 + outer loop + vertex -929.829 361.512 10.1089 + vertex -929.743 360.726 8.6837 + vertex -930.426 359.111 10.0996 + endloop + endfacet + facet normal -0.952996 0.23024 -0.196946 + outer loop + vertex -930.426 359.111 10.0996 + vertex -929.743 360.726 8.6837 + vertex -930.318 358.327 8.65684 + endloop + endfacet + facet normal -0.946354 0.306973 -0.100904 + outer loop + vertex -924.469 379.282 11.1659 + vertex -924.24 379.279 9.0169 + vertex -926.227 373.829 11.069 + endloop + endfacet + facet normal -0.946434 0.300634 -0.117819 + outer loop + vertex -926.227 373.829 11.069 + vertex -924.24 379.279 9.0169 + vertex -925.732 374.502 8.81418 + endloop + endfacet + facet normal -0.947453 0.290053 0.134916 + outer loop + vertex -924.121 379.471 13.1978 + vertex -924.469 379.282 11.1659 + vertex -925.713 374.3 13.1387 + endloop + endfacet + facet normal -0.939523 0.300043 0.165141 + outer loop + vertex -925.713 374.3 13.1387 + vertex -924.469 379.282 11.1659 + vertex -926.227 373.829 11.069 + endloop + endfacet + facet normal -0.942906 0.287027 0.168947 + outer loop + vertex -925.713 374.3 13.1387 + vertex -926.227 373.829 11.069 + vertex -927.336 369.06 12.9834 + endloop + endfacet + facet normal -0.875257 0.341119 0.342874 + outer loop + vertex -927.336 369.06 12.9834 + vertex -926.227 373.829 11.069 + vertex -927.454 370.154 11.5933 + endloop + endfacet + facet normal -0.932146 0.292759 -0.213062 + outer loop + vertex -927.045 370.166 8.59915 + vertex -927.357 370.449 10.3523 + vertex -925.732 374.502 8.81418 + endloop + endfacet + facet normal -0.948483 0.316826 0.00130832 + outer loop + vertex -927.454 370.154 11.5933 + vertex -926.227 373.829 11.069 + vertex -927.357 370.449 10.3523 + endloop + endfacet + facet normal -0.936214 0.33531 -0.105217 + outer loop + vertex -926.227 373.829 11.069 + vertex -925.732 374.502 8.81418 + vertex -927.357 370.449 10.3523 + endloop + endfacet + facet normal -0.942139 0.317516 -0.10751 + outer loop + vertex -921.165 389.283 11.1912 + vertex -920.923 389.282 9.06588 + vertex -922.819 384.377 11.193 + endloop + endfacet + facet normal -0.942157 0.317232 -0.108182 + outer loop + vertex -922.819 384.377 11.193 + vertex -920.923 389.282 9.06588 + vertex -922.584 384.348 9.06962 + endloop + endfacet + facet normal -0.94057 0.315997 0.124394 + outer loop + vertex -920.846 389.432 13.2246 + vertex -921.165 389.283 11.1912 + vertex -922.503 384.504 13.2154 + endloop + endfacet + facet normal -0.939949 0.316865 0.126853 + outer loop + vertex -922.503 384.504 13.2154 + vertex -921.165 389.283 11.1912 + vertex -922.819 384.377 11.193 + endloop + endfacet + facet normal -0.944237 0.303209 0.12838 + outer loop + vertex -922.503 384.504 13.2154 + vertex -922.819 384.377 11.193 + vertex -924.121 379.471 13.1978 + endloop + endfacet + facet normal -0.943134 0.304728 0.132814 + outer loop + vertex -924.121 379.471 13.1978 + vertex -922.819 384.377 11.193 + vertex -924.469 379.282 11.1659 + endloop + endfacet + facet normal -0.945577 0.306804 -0.108418 + outer loop + vertex -922.819 384.377 11.193 + vertex -922.584 384.348 9.06962 + vertex -924.469 379.282 11.1659 + endloop + endfacet + facet normal -0.945412 0.309892 -0.100807 + outer loop + vertex -924.469 379.282 11.1659 + vertex -922.584 384.348 9.06962 + vertex -924.24 379.279 9.0169 + endloop + endfacet + facet normal -0.933968 0.343035 -0.100156 + outer loop + vertex -917.7 398.887 11.1856 + vertex -917.475 398.874 9.04564 + vertex -919.459 394.096 11.1859 + endloop + endfacet + facet normal -0.934136 0.341527 -0.103677 + outer loop + vertex -919.459 394.096 11.1859 + vertex -917.475 398.874 9.04564 + vertex -919.223 394.095 9.05283 + endloop + endfacet + facet normal -0.934556 0.33927 0.107243 + outer loop + vertex -917.391 399.085 13.2497 + vertex -917.7 398.887 11.1856 + vertex -919.138 394.28 13.2324 + endloop + endfacet + facet normal -0.932351 0.342454 0.11596 + outer loop + vertex -919.138 394.28 13.2324 + vertex -917.7 398.887 11.1856 + vertex -919.459 394.096 11.1859 + endloop + endfacet + facet normal -0.936643 0.329898 0.117759 + outer loop + vertex -919.138 394.28 13.2324 + vertex -919.459 394.096 11.1859 + vertex -920.846 389.432 13.2246 + endloop + endfacet + facet normal -0.935443 0.331592 0.12245 + outer loop + vertex -920.846 389.432 13.2246 + vertex -919.459 394.096 11.1859 + vertex -921.165 389.283 11.1912 + endloop + endfacet + facet normal -0.937499 0.332071 -0.104044 + outer loop + vertex -919.459 394.096 11.1859 + vertex -919.223 394.095 9.05283 + vertex -921.165 389.283 11.1912 + endloop + endfacet + facet normal -0.937614 0.330801 -0.107006 + outer loop + vertex -921.165 389.283 11.1912 + vertex -919.223 394.095 9.05283 + vertex -920.923 389.282 9.06588 + endloop + endfacet + facet normal -0.92697 0.360209 -0.104769 + outer loop + vertex -914.003 408.537 11.1834 + vertex -913.764 408.531 9.04026 + vertex -915.885 403.695 11.1862 + endloop + endfacet + facet normal -0.92703 0.359699 -0.105977 + outer loop + vertex -915.885 403.695 11.1862 + vertex -913.764 408.531 9.04026 + vertex -915.645 403.683 9.04417 + endloop + endfacet + facet normal -0.928468 0.358931 0.0954751 + outer loop + vertex -913.71 408.747 13.2518 + vertex -914.003 408.537 11.1834 + vertex -915.581 403.905 13.2555 + endloop + endfacet + facet normal -0.927407 0.360498 0.0997854 + outer loop + vertex -915.581 403.905 13.2555 + vertex -914.003 408.537 11.1834 + vertex -915.885 403.695 11.1862 + endloop + endfacet + facet normal -0.931378 0.349628 0.101469 + outer loop + vertex -915.581 403.905 13.2555 + vertex -915.885 403.695 11.1862 + vertex -917.391 399.085 13.2497 + endloop + endfacet + facet normal -0.930379 0.351098 0.105481 + outer loop + vertex -917.391 399.085 13.2497 + vertex -915.885 403.695 11.1862 + vertex -917.7 398.887 11.1856 + endloop + endfacet + facet normal -0.930289 0.35109 -0.106295 + outer loop + vertex -915.885 403.695 11.1862 + vertex -915.645 403.683 9.04417 + vertex -917.7 398.887 11.1856 + endloop + endfacet + facet normal -0.929963 0.353849 -0.0998022 + outer loop + vertex -917.7 398.887 11.1856 + vertex -915.645 403.683 9.04417 + vertex -917.475 398.874 9.04564 + endloop + endfacet + facet normal -0.920823 0.375553 -0.105095 + outer loop + vertex -910.092 418.22 11.1792 + vertex -909.845 418.224 9.03588 + vertex -912.059 413.396 11.1787 + endloop + endfacet + facet normal -0.920758 0.37603 -0.103954 + outer loop + vertex -912.059 413.396 11.1787 + vertex -909.845 418.224 9.03588 + vertex -911.817 413.396 9.03802 + endloop + endfacet + facet normal -0.922989 0.375572 0.0838894 + outer loop + vertex -909.826 418.412 13.245 + vertex -910.092 418.22 11.1792 + vertex -911.785 413.597 13.2481 + endloop + endfacet + facet normal -0.922547 0.376239 0.0857406 + outer loop + vertex -911.785 413.597 13.2481 + vertex -910.092 418.22 11.1792 + vertex -912.059 413.396 11.1787 + endloop + endfacet + facet normal -0.925922 0.36755 0.0870319 + outer loop + vertex -911.785 413.597 13.2481 + vertex -912.059 413.396 11.1787 + vertex -913.71 408.747 13.2518 + endloop + endfacet + facet normal -0.924298 0.369975 0.0937622 + outer loop + vertex -913.71 408.747 13.2518 + vertex -912.059 413.396 11.1787 + vertex -914.003 408.537 11.1834 + endloop + endfacet + facet normal -0.923395 0.369422 -0.104252 + outer loop + vertex -912.059 413.396 11.1787 + vertex -911.817 413.396 9.03802 + vertex -914.003 408.537 11.1834 + endloop + endfacet + facet normal -0.923403 0.369362 -0.104396 + outer loop + vertex -914.003 408.537 11.1834 + vertex -911.817 413.396 9.03802 + vertex -913.764 408.531 9.04026 + endloop + endfacet + facet normal -0.915052 0.390233 -0.10197 + outer loop + vertex -906.116 427.632 11.1774 + vertex -905.872 427.645 9.04031 + vertex -908.105 422.969 11.18 + endloop + endfacet + facet normal -0.915054 0.39022 -0.101999 + outer loop + vertex -908.105 422.969 11.18 + vertex -905.872 427.645 9.04031 + vertex -907.864 422.974 9.03634 + endloop + endfacet + facet normal -0.91956 0.387725 0.0638631 + outer loop + vertex -905.92 427.758 13.2403 + vertex -906.116 427.632 11.1774 + vertex -907.868 423.136 13.2443 + endloop + endfacet + facet normal -0.917322 0.391297 0.0735295 + outer loop + vertex -907.868 423.136 13.2443 + vertex -906.116 427.632 11.1774 + vertex -908.105 422.969 11.18 + endloop + endfacet + facet normal -0.921242 0.381741 0.0747494 + outer loop + vertex -907.868 423.136 13.2443 + vertex -908.105 422.969 11.18 + vertex -909.826 418.412 13.245 + endloop + endfacet + facet normal -0.919385 0.384591 0.082586 + outer loop + vertex -909.826 418.412 13.245 + vertex -908.105 422.969 11.18 + vertex -910.092 418.22 11.1792 + endloop + endfacet + facet normal -0.917685 0.38391 -0.102308 + outer loop + vertex -908.105 422.969 11.18 + vertex -907.864 422.974 9.03634 + vertex -910.092 418.22 11.1792 + endloop + endfacet + facet normal -0.917839 0.382887 -0.104737 + outer loop + vertex -910.092 418.22 11.1792 + vertex -907.864 422.974 9.03634 + vertex -909.845 418.224 9.03588 + endloop + endfacet + facet normal -0.911884 0.398753 -0.0972832 + outer loop + vertex -902.093 436.89 11.1568 + vertex -901.84 436.95 9.03252 + vertex -904.125 432.245 11.1701 + endloop + endfacet + facet normal -0.912133 0.397343 -0.100654 + outer loop + vertex -904.125 432.245 11.1701 + vertex -901.84 436.95 9.03252 + vertex -903.872 432.285 9.03904 + endloop + endfacet + facet normal -0.915589 0.398502 0.0537783 + outer loop + vertex -901.922 437.004 13.2183 + vertex -902.093 436.89 11.1568 + vertex -903.949 432.344 13.2234 + endloop + endfacet + facet normal -0.914478 0.400338 0.0588129 + outer loop + vertex -903.949 432.344 13.2234 + vertex -902.093 436.89 11.1568 + vertex -904.125 432.245 11.1701 + endloop + endfacet + facet normal -0.917105 0.394206 0.059334 + outer loop + vertex -903.949 432.344 13.2234 + vertex -904.125 432.245 11.1701 + vertex -905.92 427.758 13.2403 + endloop + endfacet + facet normal -0.916259 0.395591 0.0630683 + outer loop + vertex -905.92 427.758 13.2403 + vertex -904.125 432.245 11.1701 + vertex -906.116 427.632 11.1774 + endloop + endfacet + facet normal -0.913498 0.39414 -0.100876 + outer loop + vertex -904.125 432.245 11.1701 + vertex -903.872 432.285 9.03904 + vertex -906.116 427.632 11.1774 + endloop + endfacet + facet normal -0.913563 0.393757 -0.101777 + outer loop + vertex -906.116 427.632 11.1774 + vertex -903.872 432.285 9.03904 + vertex -905.872 427.645 9.04031 + endloop + endfacet + facet normal -0.908595 0.407165 -0.0931245 + outer loop + vertex -897.819 446.501 11.1902 + vertex -897.612 446.467 9.02082 + vertex -899.997 441.632 11.157 + endloop + endfacet + facet normal -0.908888 0.40561 -0.0969708 + outer loop + vertex -899.997 441.632 11.157 + vertex -897.612 446.467 9.02082 + vertex -899.748 441.679 9.02213 + endloop + endfacet + facet normal -0.911488 0.408243 0.0502792 + outer loop + vertex -897.534 446.87 13.3487 + vertex -897.819 446.501 11.1902 + vertex -899.797 441.829 13.2587 + endloop + endfacet + facet normal -0.911844 0.407651 0.0486009 + outer loop + vertex -899.797 441.829 13.2587 + vertex -897.819 446.501 11.1902 + vertex -899.997 441.632 11.157 + endloop + endfacet + facet normal -0.914241 0.402155 0.0493442 + outer loop + vertex -899.797 441.829 13.2587 + vertex -899.997 441.632 11.157 + vertex -901.922 437.004 13.2183 + endloop + endfacet + facet normal -0.913393 0.403571 0.0533156 + outer loop + vertex -901.922 437.004 13.2183 + vertex -899.997 441.632 11.157 + vertex -902.093 436.89 11.1568 + endloop + endfacet + facet normal -0.910359 0.402238 -0.0972174 + outer loop + vertex -899.997 441.632 11.157 + vertex -899.748 441.679 9.02213 + vertex -902.093 436.89 11.1568 + endloop + endfacet + facet normal -0.910343 0.402328 -0.0969983 + outer loop + vertex -902.093 436.89 11.1568 + vertex -899.748 441.679 9.02213 + vertex -901.84 436.95 9.03252 + endloop + endfacet + facet normal -0.905866 0.414962 -0.0849298 + outer loop + vertex -893.351 456.306 11.2487 + vertex -893.259 456.06 9.05389 + vertex -895.574 451.452 11.2435 + endloop + endfacet + facet normal -0.905987 0.414447 -0.0861425 + outer loop + vertex -895.574 451.452 11.2435 + vertex -893.259 456.06 9.05389 + vertex -895.442 451.281 9.03371 + endloop + endfacet + facet normal -0.909079 0.413201 0.0532974 + outer loop + vertex -892.995 456.846 13.1449 + vertex -893.351 456.306 11.2487 + vertex -895.137 452.096 13.4305 + endloop + endfacet + facet normal -0.907617 0.415611 0.0591438 + outer loop + vertex -895.137 452.096 13.4305 + vertex -893.351 456.306 11.2487 + vertex -895.574 451.452 11.2435 + endloop + endfacet + facet normal -0.907689 0.415445 0.059207 + outer loop + vertex -895.137 452.096 13.4305 + vertex -895.574 451.452 11.2435 + vertex -897.534 446.87 13.3487 + endloop + endfacet + facet normal -0.909887 0.4119 0.0494434 + outer loop + vertex -897.534 446.87 13.3487 + vertex -895.574 451.452 11.2435 + vertex -897.819 446.501 11.1902 + endloop + endfacet + facet normal -0.907076 0.412083 -0.0860247 + outer loop + vertex -895.574 451.452 11.2435 + vertex -895.442 451.281 9.03371 + vertex -897.819 446.501 11.1902 + endloop + endfacet + facet normal -0.907683 0.409206 -0.0930696 + outer loop + vertex -897.819 446.501 11.1902 + vertex -895.442 451.281 9.03371 + vertex -897.612 446.467 9.02082 + endloop + endfacet + facet normal -0.900233 0.429548 -0.0711976 + outer loop + vertex -888.964 465.598 11.3373 + vertex -888.897 465.368 9.10323 + vertex -891.175 460.957 11.2911 + endloop + endfacet + facet normal -0.901061 0.42663 -0.0779426 + outer loop + vertex -891.175 460.957 11.2911 + vertex -888.897 465.368 9.10323 + vertex -891.083 460.747 9.07673 + endloop + endfacet + facet normal -0.904509 0.423465 0.0504133 + outer loop + vertex -888.561 466.234 13.2278 + vertex -888.964 465.598 11.3373 + vertex -890.91 461.18 13.5291 + endloop + endfacet + facet normal -0.901205 0.428666 0.0638299 + outer loop + vertex -890.91 461.18 13.5291 + vertex -888.964 465.598 11.3373 + vertex -891.175 460.957 11.2911 + endloop + endfacet + facet normal -0.901536 0.427954 0.0639399 + outer loop + vertex -890.91 461.18 13.5291 + vertex -891.175 460.957 11.2911 + vertex -892.995 456.846 13.1449 + endloop + endfacet + facet normal -0.904778 0.422973 0.0497089 + outer loop + vertex -892.995 456.846 13.1449 + vertex -891.175 460.957 11.2911 + vertex -893.351 456.306 11.2487 + endloop + endfacet + facet normal -0.902714 0.42317 -0.0776835 + outer loop + vertex -891.175 460.957 11.2911 + vertex -891.083 460.747 9.07673 + vertex -893.351 456.306 11.2487 + endloop + endfacet + facet normal -0.903571 0.419844 -0.0853815 + outer loop + vertex -893.351 456.306 11.2487 + vertex -891.083 460.747 9.07673 + vertex -893.259 456.06 9.05389 + endloop + endfacet + facet normal -0.892506 0.446833 -0.0614233 + outer loop + vertex -884.389 474.841 11.3596 + vertex -884.375 474.562 9.13311 + vertex -886.697 470.232 11.3589 + endloop + endfacet + facet normal -0.893316 0.444411 -0.0669788 + outer loop + vertex -886.697 470.232 11.3589 + vertex -884.375 474.562 9.13311 + vertex -886.658 469.973 9.12752 + endloop + endfacet + facet normal -0.896133 0.441767 0.0422755 + outer loop + vertex -883.964 475.525 13.2313 + vertex -884.389 474.841 11.3596 + vertex -886.388 470.575 13.5697 + endloop + endfacet + facet normal -0.892833 0.446979 0.0553183 + outer loop + vertex -886.388 470.575 13.5697 + vertex -884.389 474.841 11.3596 + vertex -886.697 470.232 11.3589 + endloop + endfacet + facet normal -0.894569 0.443393 0.0561178 + outer loop + vertex -886.388 470.575 13.5697 + vertex -886.697 470.232 11.3589 + vertex -888.561 466.234 13.2278 + endloop + endfacet + facet normal -0.897454 0.438937 0.0437061 + outer loop + vertex -888.561 466.234 13.2278 + vertex -886.697 470.232 11.3589 + vertex -888.964 465.598 11.3373 + endloop + endfacet + facet normal -0.89613 0.4388 -0.0663761 + outer loop + vertex -886.697 470.232 11.3589 + vertex -886.658 469.973 9.12752 + vertex -888.964 465.598 11.3373 + endloop + endfacet + facet normal -0.896862 0.436443 -0.0718064 + outer loop + vertex -888.964 465.598 11.3373 + vertex -886.658 469.973 9.12752 + vertex -888.897 465.368 9.10323 + endloop + endfacet + facet normal -0.889024 0.45577 -0.0436998 + outer loop + vertex -879.634 484.115 11.2728 + vertex -879.7 483.775 9.07283 + vertex -882.021 479.463 11.3217 + endloop + endfacet + facet normal -0.890697 0.451403 -0.0538005 + outer loop + vertex -882.021 479.463 11.3217 + vertex -879.7 483.775 9.07283 + vertex -882.048 479.148 9.11395 + endloop + endfacet + facet normal -0.892496 0.449971 0.0312693 + outer loop + vertex -879.197 484.849 13.1753 + vertex -879.634 484.115 11.2728 + vertex -881.693 479.874 13.5289 + endloop + endfacet + facet normal -0.888499 0.456455 0.0471042 + outer loop + vertex -881.693 479.874 13.5289 + vertex -879.634 484.115 11.2728 + vertex -882.021 479.463 11.3217 + endloop + endfacet + facet normal -0.886806 0.459825 0.0462248 + outer loop + vertex -881.693 479.874 13.5289 + vertex -882.021 479.463 11.3217 + vertex -883.964 475.525 13.2313 + endloop + endfacet + facet normal -0.889322 0.455897 0.0355663 + outer loop + vertex -883.964 475.525 13.2313 + vertex -882.021 479.463 11.3217 + vertex -884.389 474.841 11.3596 + endloop + endfacet + facet normal -0.888869 0.454929 -0.0543259 + outer loop + vertex -882.021 479.463 11.3217 + vertex -882.048 479.148 9.11395 + vertex -884.389 474.841 11.3596 + endloop + endfacet + facet normal -0.890073 0.451581 -0.0620028 + outer loop + vertex -884.389 474.841 11.3596 + vertex -882.048 479.148 9.11395 + vertex -884.375 474.562 9.13311 + endloop + endfacet + facet normal -0.96623 0.2553 -0.0349461 + outer loop + vertex -876.205 493.68 11.2788 + vertex -876.132 493.64 8.9815 + vertex -877.478 488.861 11.2548 + endloop + endfacet + facet normal -0.964002 0.265628 -0.0119114 + outer loop + vertex -877.478 488.861 11.2548 + vertex -876.132 493.64 8.9815 + vertex -877.537 488.545 9.03707 + endloop + endfacet + facet normal -0.967435 0.24926 0.0440296 + outer loop + vertex -876.111 493.657 13.4843 + vertex -876.205 493.68 11.2788 + vertex -877.216 489.341 13.6336 + endloop + endfacet + facet normal -0.965478 0.254653 0.054809 + outer loop + vertex -877.216 489.341 13.6336 + vertex -876.205 493.68 11.2788 + vertex -877.478 488.861 11.2548 + endloop + endfacet + facet normal -0.915507 0.401823 0.0196138 + outer loop + vertex -877.216 489.341 13.6336 + vertex -877.478 488.861 11.2548 + vertex -879.197 484.849 13.1753 + endloop + endfacet + facet normal -0.90925 0.413326 0.0492468 + outer loop + vertex -879.197 484.849 13.1753 + vertex -877.478 488.861 11.2548 + vertex -879.634 484.115 11.2728 + endloop + endfacet + facet normal -0.909936 0.41332 -0.0344005 + outer loop + vertex -877.478 488.861 11.2548 + vertex -877.537 488.545 9.03707 + vertex -879.634 484.115 11.2728 + endloop + endfacet + facet normal -0.910245 0.412469 -0.0363756 + outer loop + vertex -879.634 484.115 11.2728 + vertex -877.537 488.545 9.03707 + vertex -879.7 483.775 9.07283 + endloop + endfacet + facet normal -0.538685 -0.515542 -0.666359 + outer loop + vertex -878.767 192.851 5.97697 + vertex -878.491 193.646 5.13894 + vertex -878.334 192.442 5.94313 + endloop + endfacet + facet normal -0.470412 -0.5319 -0.704127 + outer loop + vertex -878.334 192.442 5.94313 + vertex -878.491 193.646 5.13894 + vertex -878.014 193.534 4.90488 + endloop + endfacet + facet normal -0.618031 -0.590358 -0.519148 + outer loop + vertex -879.082 192.323 6.95245 + vertex -878.767 192.851 5.97697 + vertex -878.573 191.792 6.9506 + endloop + endfacet + facet normal -0.604205 -0.596382 -0.528456 + outer loop + vertex -878.573 191.792 6.9506 + vertex -878.767 192.851 5.97697 + vertex -878.334 192.442 5.94313 + endloop + endfacet + facet normal -0.697755 -0.5149 -0.498012 + outer loop + vertex -878.573 191.792 6.9506 + vertex -878.334 192.442 5.94313 + vertex -878.391 191.661 6.83113 + endloop + endfacet + facet normal -0.653103 -0.547165 -0.523514 + outer loop + vertex -878.391 191.661 6.83113 + vertex -878.334 192.442 5.94313 + vertex -878.144 192.316 5.83827 + endloop + endfacet + facet normal -0.637385 -0.424721 -0.642924 + outer loop + vertex -878.334 192.442 5.94313 + vertex -878.014 193.534 4.90488 + vertex -878.144 192.316 5.83827 + endloop + endfacet + facet normal -0.575627 -0.457823 -0.677533 + outer loop + vertex -878.144 192.316 5.83827 + vertex -878.014 193.534 4.90488 + vertex -877.51 192.828 4.95408 + endloop + endfacet + facet normal -0.681749 -0.643698 -0.347666 + outer loop + vertex -879.341 192.053 7.9595 + vertex -879.082 192.323 6.95245 + vertex -878.781 191.456 7.96846 + endloop + endfacet + facet normal -0.67646 -0.646924 -0.351982 + outer loop + vertex -878.781 191.456 7.96846 + vertex -879.082 192.323 6.95245 + vertex -878.573 191.792 6.9506 + endloop + endfacet + facet normal -0.723098 -0.673308 -0.154224 + outer loop + vertex -879.45 191.933 8.993 + vertex -879.341 192.053 7.9595 + vertex -878.896 191.336 9.0055 + endloop + endfacet + facet normal -0.719569 -0.676266 -0.157752 + outer loop + vertex -878.896 191.336 9.0055 + vertex -879.341 192.053 7.9595 + vertex -878.781 191.456 7.96846 + endloop + endfacet + facet normal -0.775496 -0.61166 -0.156454 + outer loop + vertex -878.896 191.336 9.0055 + vertex -878.781 191.456 7.96846 + vertex -878.619 191.02 8.86883 + endloop + endfacet + facet normal -0.734607 -0.653097 -0.183893 + outer loop + vertex -878.619 191.02 8.86883 + vertex -878.781 191.456 7.96846 + vertex -878.538 191.216 7.84532 + endloop + endfacet + facet normal -0.740811 -0.577915 -0.342365 + outer loop + vertex -878.781 191.456 7.96846 + vertex -878.573 191.792 6.9506 + vertex -878.538 191.216 7.84532 + endloop + endfacet + facet normal -0.690537 -0.620466 -0.371727 + outer loop + vertex -878.538 191.216 7.84532 + vertex -878.573 191.792 6.9506 + vertex -878.391 191.661 6.83113 + endloop + endfacet + facet normal -0.67496 -0.634958 -0.375841 + outer loop + vertex -878.538 191.216 7.84532 + vertex -878.391 191.661 6.83113 + vertex -878.157 190.965 7.58766 + endloop + endfacet + facet normal -0.647737 -0.649724 -0.397864 + outer loop + vertex -878.157 190.965 7.58766 + vertex -878.391 191.661 6.83113 + vertex -878.156 191.558 6.61693 + endloop + endfacet + facet normal -0.742287 -0.644643 -0.18288 + outer loop + vertex -878.619 191.02 8.86883 + vertex -878.538 191.216 7.84532 + vertex -878.286 190.731 8.5342 + endloop + endfacet + facet normal -0.650366 -0.712256 -0.264036 + outer loop + vertex -878.286 190.731 8.5342 + vertex -878.538 191.216 7.84532 + vertex -878.157 190.965 7.58766 + endloop + endfacet + facet normal -0.544557 -0.495217 -0.676917 + outer loop + vertex -878.144 192.316 5.83827 + vertex -877.51 192.828 4.95408 + vertex -877.71 191.815 5.85503 + endloop + endfacet + facet normal -0.601574 -0.461712 -0.651867 + outer loop + vertex -877.71 191.815 5.85503 + vertex -877.51 192.828 4.95408 + vertex -877.156 192.002 5.21246 + endloop + endfacet + facet normal -0.690227 -0.513039 -0.510272 + outer loop + vertex -878.391 191.661 6.83113 + vertex -878.144 192.316 5.83827 + vertex -878.156 191.558 6.61693 + endloop + endfacet + facet normal -0.62058 -0.557005 -0.55193 + outer loop + vertex -878.156 191.558 6.61693 + vertex -878.144 192.316 5.83827 + vertex -877.71 191.815 5.85503 + endloop + endfacet + facet normal -0.54364 -0.502037 -0.672618 + outer loop + vertex -884.601 199.081 5.90339 + vertex -883.927 199.424 5.1025 + vertex -882.839 197.185 5.89447 + endloop + endfacet + facet normal -0.522942 -0.498598 -0.691326 + outer loop + vertex -882.839 197.185 5.89447 + vertex -883.927 199.424 5.1025 + vertex -882.221 197.826 4.96463 + endloop + endfacet + facet normal -0.61797 -0.572608 -0.538733 + outer loop + vertex -885.054 198.657 6.87447 + vertex -884.601 199.081 5.90339 + vertex -883.313 196.791 6.86018 + endloop + endfacet + facet normal -0.618955 -0.572664 -0.537541 + outer loop + vertex -883.313 196.791 6.86018 + vertex -884.601 199.081 5.90339 + vertex -882.839 197.185 5.89447 + endloop + endfacet + facet normal -0.611932 -0.580419 -0.537264 + outer loop + vertex -883.313 196.791 6.86018 + vertex -882.839 197.185 5.89447 + vertex -881.604 194.986 6.86272 + endloop + endfacet + facet normal -0.614446 -0.580518 -0.53428 + outer loop + vertex -881.604 194.986 6.86272 + vertex -882.839 197.185 5.89447 + vertex -881.135 195.37 5.90679 + endloop + endfacet + facet normal -0.524443 -0.497083 -0.69128 + outer loop + vertex -882.839 197.185 5.89447 + vertex -882.221 197.826 4.96463 + vertex -881.135 195.37 5.90679 + endloop + endfacet + facet normal -0.550169 -0.499877 -0.668908 + outer loop + vertex -881.135 195.37 5.90679 + vertex -882.221 197.826 4.96463 + vertex -880.571 195.802 5.1205 + endloop + endfacet + facet normal -0.677894 -0.629221 -0.380186 + outer loop + vertex -885.286 198.296 7.88601 + vertex -885.054 198.657 6.87447 + vertex -883.556 196.44 7.87185 + endloop + endfacet + facet normal -0.677377 -0.629258 -0.381045 + outer loop + vertex -883.556 196.44 7.87185 + vertex -885.054 198.657 6.87447 + vertex -883.313 196.791 6.86018 + endloop + endfacet + facet normal -0.717611 -0.669672 -0.191242 + outer loop + vertex -885.334 198.051 8.91917 + vertex -885.286 198.296 7.88601 + vertex -883.596 196.192 8.90895 + endloop + endfacet + facet normal -0.719091 -0.669106 -0.187633 + outer loop + vertex -883.596 196.192 8.90895 + vertex -885.286 198.296 7.88601 + vertex -883.556 196.44 7.87185 + endloop + endfacet + facet normal -0.707565 -0.680639 -0.189955 + outer loop + vertex -883.596 196.192 8.90895 + vertex -883.556 196.44 7.87185 + vertex -881.918 194.448 8.91105 + endloop + endfacet + facet normal -0.710474 -0.679476 -0.183139 + outer loop + vertex -881.918 194.448 8.91105 + vertex -883.556 196.44 7.87185 + vertex -881.868 194.676 7.8718 + endloop + endfacet + facet normal -0.667878 -0.638733 -0.382046 + outer loop + vertex -883.556 196.44 7.87185 + vertex -883.313 196.791 6.86018 + vertex -881.868 194.676 7.8718 + endloop + endfacet + facet normal -0.673218 -0.638242 -0.373396 + outer loop + vertex -881.868 194.676 7.8718 + vertex -883.313 196.791 6.86018 + vertex -881.604 194.986 6.86272 + endloop + endfacet + facet normal -0.662284 -0.649276 -0.373926 + outer loop + vertex -881.868 194.676 7.8718 + vertex -881.604 194.986 6.86272 + vertex -880.396 193.155 7.90493 + endloop + endfacet + facet normal -0.670732 -0.647706 -0.36138 + outer loop + vertex -880.396 193.155 7.90493 + vertex -881.604 194.986 6.86272 + vertex -880.124 193.433 6.90074 + endloop + endfacet + facet normal -0.700843 -0.688972 -0.18476 + outer loop + vertex -881.918 194.448 8.91105 + vertex -881.868 194.676 7.8718 + vertex -880.47 192.966 8.94089 + endloop + endfacet + facet normal -0.70547 -0.686754 -0.175159 + outer loop + vertex -880.47 192.966 8.94089 + vertex -881.868 194.676 7.8718 + vertex -880.396 193.155 7.90493 + endloop + endfacet + facet normal -0.695848 -0.696238 -0.176205 + outer loop + vertex -880.47 192.966 8.94089 + vertex -880.396 193.155 7.90493 + vertex -879.45 191.933 8.993 + endloop + endfacet + facet normal -0.709578 -0.687494 -0.154441 + outer loop + vertex -879.45 191.933 8.993 + vertex -880.396 193.155 7.90493 + vertex -879.341 192.053 7.9595 + endloop + endfacet + facet normal -0.664249 -0.654315 -0.36145 + outer loop + vertex -880.396 193.155 7.90493 + vertex -880.124 193.433 6.90074 + vertex -879.341 192.053 7.9595 + endloop + endfacet + facet normal -0.675474 -0.65021 -0.347797 + outer loop + vertex -879.341 192.053 7.9595 + vertex -880.124 193.433 6.90074 + vertex -879.082 192.323 6.95245 + endloop + endfacet + facet normal -0.535386 -0.517131 -0.667786 + outer loop + vertex -881.135 195.37 5.90679 + vertex -880.571 195.802 5.1205 + vertex -879.71 193.849 5.94266 + endloop + endfacet + facet normal -0.5049 -0.514378 -0.693175 + outer loop + vertex -879.71 193.849 5.94266 + vertex -880.571 195.802 5.1205 + vertex -879.37 194.786 4.9994 + endloop + endfacet + facet normal -0.605733 -0.590017 -0.533824 + outer loop + vertex -881.604 194.986 6.86272 + vertex -881.135 195.37 5.90679 + vertex -880.124 193.433 6.90074 + endloop + endfacet + facet normal -0.616363 -0.589531 -0.522063 + outer loop + vertex -880.124 193.433 6.90074 + vertex -881.135 195.37 5.90679 + vertex -879.71 193.849 5.94266 + endloop + endfacet + facet normal -0.609574 -0.596474 -0.522148 + outer loop + vertex -880.124 193.433 6.90074 + vertex -879.71 193.849 5.94266 + vertex -879.082 192.323 6.95245 + endloop + endfacet + facet normal -0.611682 -0.596038 -0.520177 + outer loop + vertex -879.082 192.323 6.95245 + vertex -879.71 193.849 5.94266 + vertex -878.767 192.851 5.97697 + endloop + endfacet + facet normal -0.513388 -0.509003 -0.690904 + outer loop + vertex -879.71 193.849 5.94266 + vertex -879.37 194.786 4.9994 + vertex -878.767 192.851 5.97697 + endloop + endfacet + facet normal -0.552063 -0.506579 -0.662272 + outer loop + vertex -878.767 192.851 5.97697 + vertex -879.37 194.786 4.9994 + vertex -878.491 193.646 5.13894 + endloop + endfacet + facet normal -0.551363 -0.480852 -0.681748 + outer loop + vertex -891.319 206.603 5.91821 + vertex -890.654 206.98 5.11498 + vertex -889.662 204.701 5.91943 + endloop + endfacet + facet normal -0.5303 -0.478161 -0.700102 + outer loop + vertex -889.662 204.701 5.91943 + vertex -890.654 206.98 5.11498 + vertex -889.017 205.368 4.97531 + endloop + endfacet + facet normal -0.632558 -0.552767 -0.542512 + outer loop + vertex -891.796 206.196 6.88906 + vertex -891.319 206.603 5.91821 + vertex -890.124 204.281 6.8904 + endloop + endfacet + facet normal -0.634033 -0.552793 -0.540761 + outer loop + vertex -890.124 204.281 6.8904 + vertex -891.319 206.603 5.91821 + vertex -889.662 204.701 5.91943 + endloop + endfacet + facet normal -0.62969 -0.557683 -0.540814 + outer loop + vertex -890.124 204.281 6.8904 + vertex -889.662 204.701 5.91943 + vertex -888.446 202.386 6.89026 + endloop + endfacet + facet normal -0.628398 -0.557649 -0.54235 + outer loop + vertex -888.446 202.386 6.89026 + vertex -889.662 204.701 5.91943 + vertex -887.996 202.823 5.91977 + endloop + endfacet + facet normal -0.5342 -0.474099 -0.6999 + outer loop + vertex -889.662 204.701 5.91943 + vertex -889.017 205.368 4.97531 + vertex -887.996 202.823 5.91977 + endloop + endfacet + facet normal -0.561616 -0.476406 -0.67648 + outer loop + vertex -887.996 202.823 5.91977 + vertex -889.017 205.368 4.97531 + vertex -887.35 203.208 5.11321 + endloop + endfacet + facet normal -0.69769 -0.608922 -0.377416 + outer loop + vertex -892.069 205.883 7.89959 + vertex -891.796 206.196 6.88906 + vertex -890.389 203.958 7.89987 + endloop + endfacet + facet normal -0.697076 -0.608995 -0.378431 + outer loop + vertex -890.389 203.958 7.89987 + vertex -891.796 206.196 6.88906 + vertex -890.124 204.281 6.8904 + endloop + endfacet + facet normal -0.738328 -0.645916 -0.194073 + outer loop + vertex -892.166 205.683 8.93198 + vertex -892.069 205.883 7.89959 + vertex -890.478 203.754 8.93123 + endloop + endfacet + facet normal -0.739528 -0.645407 -0.191174 + outer loop + vertex -890.478 203.754 8.93123 + vertex -892.069 205.883 7.89959 + vertex -890.389 203.958 7.89987 + endloop + endfacet + facet normal -0.733591 -0.65192 -0.191951 + outer loop + vertex -890.478 203.754 8.93123 + vertex -890.389 203.958 7.89987 + vertex -888.774 201.836 8.93022 + endloop + endfacet + facet normal -0.734203 -0.651666 -0.190468 + outer loop + vertex -888.774 201.836 8.93022 + vertex -890.389 203.958 7.89987 + vertex -888.696 202.05 7.89975 + endloop + endfacet + facet normal -0.692153 -0.614331 -0.378843 + outer loop + vertex -890.389 203.958 7.89987 + vertex -890.124 204.281 6.8904 + vertex -888.696 202.05 7.89975 + endloop + endfacet + facet normal -0.693472 -0.614187 -0.376657 + outer loop + vertex -888.696 202.05 7.89975 + vertex -890.124 204.281 6.8904 + vertex -888.446 202.386 6.89026 + endloop + endfacet + facet normal -0.688487 -0.619455 -0.377176 + outer loop + vertex -888.696 202.05 7.89975 + vertex -888.446 202.386 6.89026 + vertex -886.999 200.166 7.89627 + endloop + endfacet + facet normal -0.689288 -0.619373 -0.375845 + outer loop + vertex -886.999 200.166 7.89627 + vertex -888.446 202.386 6.89026 + vertex -886.764 200.518 6.88582 + endloop + endfacet + facet normal -0.729267 -0.656973 -0.191197 + outer loop + vertex -888.774 201.836 8.93022 + vertex -888.696 202.05 7.89975 + vertex -887.061 199.936 8.92696 + endloop + endfacet + facet normal -0.729604 -0.656836 -0.190378 + outer loop + vertex -887.061 199.936 8.92696 + vertex -888.696 202.05 7.89975 + vertex -886.999 200.166 7.89627 + endloop + endfacet + facet normal -0.724018 -0.66271 -0.191344 + outer loop + vertex -887.061 199.936 8.92696 + vertex -886.999 200.166 7.89627 + vertex -885.334 198.051 8.91917 + endloop + endfacet + facet normal -0.724627 -0.662472 -0.189861 + outer loop + vertex -885.334 198.051 8.91917 + vertex -886.999 200.166 7.89627 + vertex -885.286 198.296 7.88601 + endloop + endfacet + facet normal -0.684289 -0.624513 -0.376473 + outer loop + vertex -886.999 200.166 7.89627 + vertex -886.764 200.518 6.88582 + vertex -885.286 198.296 7.88601 + endloop + endfacet + facet normal -0.682414 -0.624673 -0.379599 + outer loop + vertex -885.286 198.296 7.88601 + vertex -886.764 200.518 6.88582 + vertex -885.054 198.657 6.87447 + endloop + endfacet + facet normal -0.549312 -0.493123 -0.674601 + outer loop + vertex -887.996 202.823 5.91977 + vertex -887.35 203.208 5.11321 + vertex -886.317 200.959 5.91541 + endloop + endfacet + facet normal -0.526655 -0.489889 -0.694726 + outer loop + vertex -886.317 200.959 5.91541 + vertex -887.35 203.208 5.11321 + vertex -885.669 201.602 4.9714 + endloop + endfacet + facet normal -0.625118 -0.561233 -0.542444 + outer loop + vertex -888.446 202.386 6.89026 + vertex -887.996 202.823 5.91977 + vertex -886.764 200.518 6.88582 + endloop + endfacet + facet normal -0.624577 -0.561214 -0.543086 + outer loop + vertex -886.764 200.518 6.88582 + vertex -887.996 202.823 5.91977 + vertex -886.317 200.959 5.91541 + endloop + endfacet + facet normal -0.619904 -0.566241 -0.543222 + outer loop + vertex -886.764 200.518 6.88582 + vertex -886.317 200.959 5.91541 + vertex -885.054 198.657 6.87447 + endloop + endfacet + facet normal -0.623678 -0.566424 -0.538693 + outer loop + vertex -885.054 198.657 6.87447 + vertex -886.317 200.959 5.91541 + vertex -884.601 199.081 5.90339 + endloop + endfacet + facet normal -0.533335 -0.482879 -0.694537 + outer loop + vertex -886.317 200.959 5.91541 + vertex -885.669 201.602 4.9714 + vertex -884.601 199.081 5.90339 + endloop + endfacet + facet normal -0.555463 -0.485158 -0.675338 + outer loop + vertex -884.601 199.081 5.90339 + vertex -885.669 201.602 4.9714 + vertex -883.927 199.424 5.1025 + endloop + endfacet + facet normal -0.565256 -0.454173 -0.688631 + outer loop + vertex -897.804 214.419 5.91841 + vertex -897.088 214.746 5.11532 + vertex -896.18 212.398 5.91811 + endloop + endfacet + facet normal -0.546362 -0.452409 -0.70485 + outer loop + vertex -896.18 212.398 5.91811 + vertex -897.088 214.746 5.11532 + vertex -895.488 213.036 4.97206 + endloop + endfacet + facet normal -0.645941 -0.523414 -0.555696 + outer loop + vertex -898.341 214.052 6.88803 + vertex -897.804 214.419 5.91841 + vertex -896.693 212.018 6.8885 + endloop + endfacet + facet normal -0.651331 -0.523368 -0.549412 + outer loop + vertex -896.693 212.018 6.8885 + vertex -897.804 214.419 5.91841 + vertex -896.18 212.398 5.91811 + endloop + endfacet + facet normal -0.645246 -0.531067 -0.549204 + outer loop + vertex -896.693 212.018 6.8885 + vertex -896.18 212.398 5.91811 + vertex -895.072 210.049 6.88793 + endloop + endfacet + facet normal -0.644726 -0.531072 -0.549809 + outer loop + vertex -895.072 210.049 6.88793 + vertex -896.18 212.398 5.91811 + vertex -894.57 210.443 5.91868 + endloop + endfacet + facet normal -0.547526 -0.451076 -0.704802 + outer loop + vertex -896.18 212.398 5.91811 + vertex -895.488 213.036 4.97206 + vertex -894.57 210.443 5.91868 + endloop + endfacet + facet normal -0.567987 -0.452094 -0.687752 + outer loop + vertex -894.57 210.443 5.91868 + vertex -895.488 213.036 4.97206 + vertex -893.887 210.805 5.11686 + endloop + endfacet + facet normal -0.715788 -0.580694 -0.387868 + outer loop + vertex -898.652 213.76 7.90008 + vertex -898.341 214.052 6.88803 + vertex -896.996 211.719 7.89977 + endloop + endfacet + facet normal -0.716565 -0.580588 -0.386591 + outer loop + vertex -896.996 211.719 7.89977 + vertex -898.341 214.052 6.88803 + vertex -896.693 212.018 6.8885 + endloop + endfacet + facet normal -0.75965 -0.618033 -0.202406 + outer loop + vertex -898.763 213.557 8.93465 + vertex -898.652 213.76 7.90008 + vertex -897.104 211.518 8.93396 + endloop + endfacet + facet normal -0.761029 -0.61743 -0.199032 + outer loop + vertex -897.104 211.518 8.93396 + vertex -898.652 213.76 7.90008 + vertex -896.996 211.719 7.89977 + endloop + endfacet + facet normal -0.753443 -0.626363 -0.199981 + outer loop + vertex -897.104 211.518 8.93396 + vertex -896.996 211.719 7.89977 + vertex -895.466 209.548 8.93349 + endloop + endfacet + facet normal -0.755047 -0.625653 -0.196116 + outer loop + vertex -895.466 209.548 8.93349 + vertex -896.996 211.719 7.89977 + vertex -895.362 209.746 7.89965 + endloop + endfacet + facet normal -0.71003 -0.588338 -0.386931 + outer loop + vertex -896.996 211.719 7.89977 + vertex -896.693 212.018 6.8885 + vertex -895.362 209.746 7.89965 + endloop + endfacet + facet normal -0.714054 -0.587765 -0.380341 + outer loop + vertex -895.362 209.746 7.89965 + vertex -896.693 212.018 6.8885 + vertex -895.072 210.049 6.88793 + endloop + endfacet + facet normal -0.706609 -0.596401 -0.380801 + outer loop + vertex -895.362 209.746 7.89965 + vertex -895.072 210.049 6.88793 + vertex -893.727 207.809 7.89941 + endloop + endfacet + facet normal -0.705691 -0.596527 -0.382303 + outer loop + vertex -893.727 207.809 7.89941 + vertex -895.072 210.049 6.88793 + vertex -893.442 208.12 6.88888 + endloop + endfacet + facet normal -0.748339 -0.63341 -0.196927 + outer loop + vertex -895.466 209.548 8.93349 + vertex -895.362 209.746 7.89965 + vertex -893.827 207.612 8.93277 + endloop + endfacet + facet normal -0.749709 -0.632804 -0.193641 + outer loop + vertex -893.827 207.612 8.93277 + vertex -895.362 209.746 7.89965 + vertex -893.727 207.809 7.89941 + endloop + endfacet + facet normal -0.743305 -0.640079 -0.194413 + outer loop + vertex -893.827 207.612 8.93277 + vertex -893.727 207.809 7.89941 + vertex -892.166 205.683 8.93198 + endloop + endfacet + facet normal -0.743721 -0.639899 -0.193412 + outer loop + vertex -892.166 205.683 8.93198 + vertex -893.727 207.809 7.89941 + vertex -892.069 205.883 7.89959 + endloop + endfacet + facet normal -0.700333 -0.602586 -0.382653 + outer loop + vertex -893.727 207.809 7.89941 + vertex -893.442 208.12 6.88888 + vertex -892.069 205.883 7.89959 + endloop + endfacet + facet normal -0.703794 -0.60214 -0.376964 + outer loop + vertex -892.069 205.883 7.89959 + vertex -893.442 208.12 6.88888 + vertex -891.796 206.196 6.88906 + endloop + endfacet + facet normal -0.557267 -0.468065 -0.685834 + outer loop + vertex -894.57 210.443 5.91868 + vertex -893.887 210.805 5.11686 + vertex -892.953 208.518 5.91876 + endloop + endfacet + facet normal -0.54047 -0.466289 -0.700333 + outer loop + vertex -892.953 208.518 5.91876 + vertex -893.887 210.805 5.11686 + vertex -892.287 209.167 4.97221 + endloop + endfacet + facet normal -0.637941 -0.539358 -0.549657 + outer loop + vertex -895.072 210.049 6.88793 + vertex -894.57 210.443 5.91868 + vertex -893.442 208.12 6.88888 + endloop + endfacet + facet normal -0.642148 -0.53935 -0.544745 + outer loop + vertex -893.442 208.12 6.88888 + vertex -894.57 210.443 5.91868 + vertex -892.953 208.518 5.91876 + endloop + endfacet + facet normal -0.637235 -0.545213 -0.544678 + outer loop + vertex -893.442 208.12 6.88888 + vertex -892.953 208.518 5.91876 + vertex -891.796 206.196 6.88906 + endloop + endfacet + facet normal -0.639048 -0.545223 -0.54254 + outer loop + vertex -891.796 206.196 6.88906 + vertex -892.953 208.518 5.91876 + vertex -891.319 206.603 5.91821 + endloop + endfacet + facet normal -0.543159 -0.463345 -0.700206 + outer loop + vertex -892.953 208.518 5.91876 + vertex -892.287 209.167 4.97221 + vertex -891.319 206.603 5.91821 + endloop + endfacet + facet normal -0.562814 -0.464648 -0.683624 + outer loop + vertex -891.319 206.603 5.91821 + vertex -892.287 209.167 4.97221 + vertex -890.654 206.98 5.11498 + endloop + endfacet + facet normal -0.575881 -0.421756 -0.700345 + outer loop + vertex -904.378 223.05 5.919 + vertex -903.578 223.29 5.11623 + vertex -902.784 220.875 5.91775 + endloop + endfacet + facet normal -0.556395 -0.42072 -0.716533 + outer loop + vertex -902.784 220.875 5.91775 + vertex -903.578 223.29 5.11623 + vertex -901.961 221.397 4.97252 + endloop + endfacet + facet normal -0.662127 -0.489534 -0.567402 + outer loop + vertex -904.971 222.727 6.88959 + vertex -904.378 223.05 5.919 + vertex -903.362 220.551 6.88956 + endloop + endfacet + facet normal -0.667925 -0.489311 -0.56076 + outer loop + vertex -903.362 220.551 6.88956 + vertex -904.378 223.05 5.919 + vertex -902.784 220.875 5.91775 + endloop + endfacet + facet normal -0.660578 -0.500073 -0.559968 + outer loop + vertex -903.362 220.551 6.88956 + vertex -902.784 220.875 5.91775 + vertex -901.697 218.351 6.88954 + endloop + endfacet + facet normal -0.662909 -0.500028 -0.557246 + outer loop + vertex -901.697 218.351 6.88954 + vertex -902.784 220.875 5.91775 + vertex -901.129 218.681 5.91789 + endloop + endfacet + facet normal -0.556858 -0.420051 -0.716566 + outer loop + vertex -902.784 220.875 5.91775 + vertex -901.961 221.397 4.97252 + vertex -901.129 218.681 5.91789 + endloop + endfacet + facet normal -0.577916 -0.420531 -0.699404 + outer loop + vertex -901.129 218.681 5.91789 + vertex -901.961 221.397 4.97252 + vertex -900.353 218.948 5.11624 + endloop + endfacet + facet normal -0.737448 -0.545232 -0.398613 + outer loop + vertex -905.313 222.449 7.90306 + vertex -904.971 222.727 6.88959 + vertex -903.702 220.27 7.90209 + endloop + endfacet + facet normal -0.737457 -0.545231 -0.398599 + outer loop + vertex -903.702 220.27 7.90209 + vertex -904.971 222.727 6.88959 + vertex -903.362 220.551 6.88956 + endloop + endfacet + facet normal -0.783911 -0.582707 -0.214327 + outer loop + vertex -905.452 222.254 8.93947 + vertex -905.313 222.449 7.90306 + vertex -903.828 220.07 8.93822 + endloop + endfacet + facet normal -0.786451 -0.581559 -0.208048 + outer loop + vertex -903.828 220.07 8.93822 + vertex -905.313 222.449 7.90306 + vertex -903.702 220.27 7.90209 + endloop + endfacet + facet normal -0.778137 -0.592267 -0.209097 + outer loop + vertex -903.828 220.07 8.93822 + vertex -903.702 220.27 7.90209 + vertex -902.15 217.866 8.93703 + endloop + endfacet + facet normal -0.77975 -0.591563 -0.205042 + outer loop + vertex -902.15 217.866 8.93703 + vertex -903.702 220.27 7.90209 + vertex -902.03 218.067 7.90136 + endloop + endfacet + facet normal -0.730616 -0.554219 -0.398801 + outer loop + vertex -903.702 220.27 7.90209 + vertex -903.362 220.551 6.88956 + vertex -902.03 218.067 7.90136 + endloop + endfacet + facet normal -0.731874 -0.554048 -0.396726 + outer loop + vertex -902.03 218.067 7.90136 + vertex -903.362 220.551 6.88956 + vertex -901.697 218.351 6.88954 + endloop + endfacet + facet normal -0.725061 -0.562784 -0.39694 + outer loop + vertex -902.03 218.067 7.90136 + vertex -901.697 218.351 6.88954 + vertex -900.336 215.884 7.90073 + endloop + endfacet + facet normal -0.727432 -0.562482 -0.393011 + outer loop + vertex -900.336 215.884 7.90073 + vertex -901.697 218.351 6.88954 + vertex -900.011 216.171 6.88899 + endloop + endfacet + facet normal -0.771848 -0.601491 -0.206056 + outer loop + vertex -902.15 217.866 8.93703 + vertex -902.03 218.067 7.90136 + vertex -900.449 215.683 8.93611 + endloop + endfacet + facet normal -0.773776 -0.600659 -0.201195 + outer loop + vertex -900.449 215.683 8.93611 + vertex -902.03 218.067 7.90136 + vertex -900.336 215.884 7.90073 + endloop + endfacet + facet normal -0.767456 -0.608441 -0.202016 + outer loop + vertex -900.449 215.683 8.93611 + vertex -900.336 215.884 7.90073 + vertex -898.763 213.557 8.93465 + endloop + endfacet + facet normal -0.767718 -0.608328 -0.201362 + outer loop + vertex -898.763 213.557 8.93465 + vertex -900.336 215.884 7.90073 + vertex -898.652 213.76 7.90008 + endloop + endfacet + facet normal -0.720655 -0.570973 -0.393251 + outer loop + vertex -900.336 215.884 7.90073 + vertex -900.011 216.171 6.88899 + vertex -898.652 213.76 7.90008 + endloop + endfacet + facet normal -0.724125 -0.570516 -0.387498 + outer loop + vertex -898.652 213.76 7.90008 + vertex -900.011 216.171 6.88899 + vertex -898.341 214.052 6.88803 + endloop + endfacet + facet normal -0.568306 -0.43865 -0.696142 + outer loop + vertex -901.129 218.681 5.91789 + vertex -900.353 218.948 5.11624 + vertex -899.459 216.517 5.91818 + endloop + endfacet + facet normal -0.549518 -0.437 -0.712082 + outer loop + vertex -899.459 216.517 5.91818 + vertex -900.353 218.948 5.11624 + vertex -898.705 217.106 4.97494 + endloop + endfacet + facet normal -0.657211 -0.508133 -0.556663 + outer loop + vertex -901.697 218.351 6.88954 + vertex -901.129 218.681 5.91789 + vertex -900.011 216.171 6.88899 + endloop + endfacet + facet normal -0.658356 -0.508123 -0.555318 + outer loop + vertex -900.011 216.171 6.88899 + vertex -901.129 218.681 5.91789 + vertex -899.459 216.517 5.91818 + endloop + endfacet + facet normal -0.653498 -0.514778 -0.554928 + outer loop + vertex -900.011 216.171 6.88899 + vertex -899.459 216.517 5.91818 + vertex -898.341 214.052 6.88803 + endloop + endfacet + facet normal -0.652517 -0.514784 -0.556075 + outer loop + vertex -898.341 214.052 6.88803 + vertex -899.459 216.517 5.91818 + vertex -897.804 214.419 5.91841 + endloop + endfacet + facet normal -0.55119 -0.434872 -0.712092 + outer loop + vertex -899.459 216.517 5.91818 + vertex -898.705 217.106 4.97494 + vertex -897.804 214.419 5.91841 + endloop + endfacet + facet normal -0.576398 -0.435973 -0.691154 + outer loop + vertex -897.804 214.419 5.91841 + vertex -898.705 217.106 4.97494 + vertex -897.088 214.746 5.11532 + endloop + endfacet + facet normal -0.590348 -0.387163 -0.708233 + outer loop + vertex -910.198 231.506 5.921 + vertex -909.384 231.739 5.11449 + vertex -908.798 229.375 5.91867 + endloop + endfacet + facet normal -0.564819 -0.387719 -0.72846 + outer loop + vertex -908.798 229.375 5.91867 + vertex -909.384 231.739 5.11449 + vertex -907.941 229.901 4.97402 + endloop + endfacet + facet normal -0.679741 -0.449295 -0.57973 + outer loop + vertex -910.829 231.207 6.89223 + vertex -910.198 231.506 5.921 + vertex -909.41 229.062 6.89131 + endloop + endfacet + facet normal -0.683959 -0.448823 -0.575115 + outer loop + vertex -909.41 229.062 6.89131 + vertex -910.198 231.506 5.921 + vertex -908.798 229.375 5.91867 + endloop + endfacet + facet normal -0.675874 -0.461973 -0.57426 + outer loop + vertex -909.41 229.062 6.89131 + vertex -908.798 229.375 5.91867 + vertex -907.972 226.958 6.89106 + endloop + endfacet + facet normal -0.677969 -0.461762 -0.571957 + outer loop + vertex -907.972 226.958 6.89106 + vertex -908.798 229.375 5.91867 + vertex -907.372 227.281 5.91942 + endloop + endfacet + facet normal -0.566135 -0.385683 -0.728519 + outer loop + vertex -908.798 229.375 5.91867 + vertex -907.941 229.901 4.97402 + vertex -907.372 227.281 5.91942 + endloop + endfacet + facet normal -0.593945 -0.383945 -0.706977 + outer loop + vertex -907.372 227.281 5.91942 + vertex -907.941 229.901 4.97402 + vertex -906.577 227.533 5.1141 + endloop + endfacet + facet normal -0.755732 -0.503371 -0.41891 + outer loop + vertex -911.222 230.954 7.90604 + vertex -910.829 231.207 6.89223 + vertex -909.789 228.802 7.90523 + endloop + endfacet + facet normal -0.759974 -0.502429 -0.412317 + outer loop + vertex -909.789 228.802 7.90523 + vertex -910.829 231.207 6.89223 + vertex -909.41 229.062 6.89131 + endloop + endfacet + facet normal -0.808125 -0.542973 -0.228285 + outer loop + vertex -911.393 230.772 8.94442 + vertex -911.222 230.954 7.90604 + vertex -909.95 228.624 8.94361 + endloop + endfacet + facet normal -0.812041 -0.540964 -0.218969 + outer loop + vertex -909.95 228.624 8.94361 + vertex -911.222 230.954 7.90604 + vertex -909.789 228.802 7.90523 + endloop + endfacet + facet normal -0.804723 -0.551521 -0.219647 + outer loop + vertex -909.95 228.624 8.94361 + vertex -909.789 228.802 7.90523 + vertex -908.498 226.506 8.94185 + endloop + endfacet + facet normal -0.804372 -0.551701 -0.220483 + outer loop + vertex -908.498 226.506 8.94185 + vertex -909.789 228.802 7.90523 + vertex -908.341 226.691 7.90456 + endloop + endfacet + facet normal -0.751316 -0.515246 -0.412365 + outer loop + vertex -909.789 228.802 7.90523 + vertex -909.41 229.062 6.89131 + vertex -908.341 226.691 7.90456 + endloop + endfacet + facet normal -0.753184 -0.514843 -0.409451 + outer loop + vertex -908.341 226.691 7.90456 + vertex -909.41 229.062 6.89131 + vertex -907.972 226.958 6.89106 + endloop + endfacet + facet normal -0.746159 -0.524895 -0.409551 + outer loop + vertex -908.341 226.691 7.90456 + vertex -907.972 226.958 6.89106 + vertex -906.858 224.584 7.9037 + endloop + endfacet + facet normal -0.747339 -0.524658 -0.407698 + outer loop + vertex -906.858 224.584 7.9037 + vertex -907.972 226.958 6.89106 + vertex -906.498 224.859 6.89112 + endloop + endfacet + facet normal -0.796351 -0.562913 -0.221257 + outer loop + vertex -908.498 226.506 8.94185 + vertex -908.341 226.691 7.90456 + vertex -907.006 224.395 8.94064 + endloop + endfacet + facet normal -0.798541 -0.561834 -0.216044 + outer loop + vertex -907.006 224.395 8.94064 + vertex -908.341 226.691 7.90456 + vertex -906.858 224.584 7.9037 + endloop + endfacet + facet normal -0.790137 -0.573257 -0.216933 + outer loop + vertex -907.006 224.395 8.94064 + vertex -906.858 224.584 7.9037 + vertex -905.452 222.254 8.93947 + endloop + endfacet + facet normal -0.791579 -0.572577 -0.213445 + outer loop + vertex -905.452 222.254 8.93947 + vertex -906.858 224.584 7.9037 + vertex -905.313 222.449 7.90306 + endloop + endfacet + facet normal -0.739827 -0.535081 -0.407853 + outer loop + vertex -906.858 224.584 7.9037 + vertex -906.498 224.859 6.89112 + vertex -905.313 222.449 7.90306 + endloop + endfacet + facet normal -0.745764 -0.534006 -0.398338 + outer loop + vertex -905.313 222.449 7.90306 + vertex -906.498 224.859 6.89112 + vertex -904.971 222.727 6.88959 + endloop + endfacet + facet normal -0.58303 -0.406695 -0.703331 + outer loop + vertex -907.372 227.281 5.91942 + vertex -906.577 227.533 5.1141 + vertex -905.909 225.183 5.9193 + endloop + endfacet + facet normal -0.559289 -0.406497 -0.722465 + outer loop + vertex -905.909 225.183 5.9193 + vertex -906.577 227.533 5.1141 + vertex -905.064 225.699 4.97492 + endloop + endfacet + facet normal -0.671707 -0.471567 -0.571344 + outer loop + vertex -907.972 226.958 6.89106 + vertex -907.372 227.281 5.91942 + vertex -906.498 224.859 6.89112 + endloop + endfacet + facet normal -0.675539 -0.471239 -0.567081 + outer loop + vertex -906.498 224.859 6.89112 + vertex -907.372 227.281 5.91942 + vertex -905.909 225.183 5.9193 + endloop + endfacet + facet normal -0.67005 -0.47964 -0.566549 + outer loop + vertex -906.498 224.859 6.89112 + vertex -905.909 225.183 5.9193 + vertex -904.971 222.727 6.88959 + endloop + endfacet + facet normal -0.668649 -0.479729 -0.568127 + outer loop + vertex -904.971 222.727 6.88959 + vertex -905.909 225.183 5.9193 + vertex -904.378 223.05 5.919 + endloop + endfacet + facet normal -0.561653 -0.40293 -0.722629 + outer loop + vertex -905.909 225.183 5.9193 + vertex -905.064 225.699 4.97492 + vertex -904.378 223.05 5.919 + endloop + endfacet + facet normal -0.585296 -0.402385 -0.703928 + outer loop + vertex -904.378 223.05 5.919 + vertex -905.064 225.699 4.97492 + vertex -903.578 223.29 5.11623 + endloop + endfacet + facet normal -0.595107 -0.349375 -0.72373 + outer loop + vertex -915.624 240.317 5.92025 + vertex -914.739 240.474 5.11667 + vertex -914.339 238.128 5.91974 + endloop + endfacet + facet normal -0.575579 -0.35111 -0.738533 + outer loop + vertex -914.339 238.128 5.91974 + vertex -914.739 240.474 5.11667 + vertex -913.38 238.547 4.97384 + endloop + endfacet + facet normal -0.693758 -0.410451 -0.591803 + outer loop + vertex -916.304 240.062 6.89389 + vertex -915.624 240.317 5.92025 + vertex -915.007 237.871 6.8938 + endloop + endfacet + facet normal -0.697849 -0.409754 -0.587459 + outer loop + vertex -915.007 237.871 6.8938 + vertex -915.624 240.317 5.92025 + vertex -914.339 238.128 5.91974 + endloop + endfacet + facet normal -0.692032 -0.420943 -0.586428 + outer loop + vertex -915.007 237.871 6.8938 + vertex -914.339 238.128 5.91974 + vertex -913.649 235.638 6.89304 + endloop + endfacet + facet normal -0.691152 -0.421069 -0.587375 + outer loop + vertex -913.649 235.638 6.89304 + vertex -914.339 238.128 5.91974 + vertex -912.984 235.904 5.92081 + endloop + endfacet + facet normal -0.575708 -0.350858 -0.738552 + outer loop + vertex -914.339 238.128 5.91974 + vertex -913.38 238.547 4.97384 + vertex -912.984 235.904 5.92081 + endloop + endfacet + facet normal -0.603268 -0.34756 -0.717823 + outer loop + vertex -912.984 235.904 5.92081 + vertex -913.38 238.547 4.97384 + vertex -912.128 236.084 5.11431 + endloop + endfacet + facet normal -0.777695 -0.459908 -0.428573 + outer loop + vertex -916.726 239.828 7.91007 + vertex -916.304 240.062 6.89389 + vertex -915.427 237.633 7.90887 + endloop + endfacet + facet normal -0.77745 -0.459975 -0.428945 + outer loop + vertex -915.427 237.633 7.90887 + vertex -916.304 240.062 6.89389 + vertex -915.007 237.871 6.8938 + endloop + endfacet + facet normal -0.83416 -0.495612 -0.241961 + outer loop + vertex -916.926 239.657 8.95089 + vertex -916.726 239.828 7.91007 + vertex -915.617 237.455 8.94901 + endloop + endfacet + facet normal -0.83607 -0.494551 -0.237498 + outer loop + vertex -915.617 237.455 8.94901 + vertex -916.726 239.828 7.91007 + vertex -915.427 237.633 7.90887 + endloop + endfacet + facet normal -0.826794 -0.509507 -0.238355 + outer loop + vertex -915.617 237.455 8.94901 + vertex -915.427 237.633 7.90887 + vertex -914.238 235.218 8.94796 + endloop + endfacet + facet normal -0.830007 -0.5078 -0.230712 + outer loop + vertex -914.238 235.218 8.94796 + vertex -915.427 237.633 7.90887 + vertex -914.058 235.396 7.90802 + endloop + endfacet + facet normal -0.770647 -0.471402 -0.428816 + outer loop + vertex -915.427 237.633 7.90887 + vertex -915.007 237.871 6.8938 + vertex -914.058 235.396 7.90802 + endloop + endfacet + facet normal -0.773641 -0.470663 -0.424211 + outer loop + vertex -914.058 235.396 7.90802 + vertex -915.007 237.871 6.8938 + vertex -913.649 235.638 6.89304 + endloop + endfacet + facet normal -0.766185 -0.48281 -0.424093 + outer loop + vertex -914.058 235.396 7.90802 + vertex -913.649 235.638 6.89304 + vertex -912.648 233.158 7.90722 + endloop + endfacet + facet normal -0.768754 -0.482215 -0.420103 + outer loop + vertex -912.648 233.158 7.90722 + vertex -913.649 235.638 6.89304 + vertex -912.247 233.404 6.8926 + endloop + endfacet + facet normal -0.82313 -0.518578 -0.231375 + outer loop + vertex -914.238 235.218 8.94796 + vertex -914.058 235.396 7.90802 + vertex -912.826 232.977 8.94609 + endloop + endfacet + facet normal -0.82296 -0.518666 -0.231783 + outer loop + vertex -912.826 232.977 8.94609 + vertex -914.058 235.396 7.90802 + vertex -912.648 233.158 7.90722 + endloop + endfacet + facet normal -0.815717 -0.529684 -0.232469 + outer loop + vertex -912.826 232.977 8.94609 + vertex -912.648 233.158 7.90722 + vertex -911.393 230.772 8.94442 + endloop + endfacet + facet normal -0.81786 -0.528592 -0.227367 + outer loop + vertex -911.393 230.772 8.94442 + vertex -912.648 233.158 7.90722 + vertex -911.222 230.954 7.90604 + endloop + endfacet + facet normal -0.76223 -0.492527 -0.420028 + outer loop + vertex -912.648 233.158 7.90722 + vertex -912.247 233.404 6.8926 + vertex -911.222 230.954 7.90604 + endloop + endfacet + facet normal -0.762922 -0.492371 -0.418952 + outer loop + vertex -911.222 230.954 7.90604 + vertex -912.247 233.404 6.8926 + vertex -910.829 231.207 6.89223 + endloop + endfacet + facet normal -0.594779 -0.369828 -0.713769 + outer loop + vertex -912.984 235.904 5.92081 + vertex -912.128 236.084 5.11431 + vertex -911.604 233.685 5.9198 + endloop + endfacet + facet normal -0.570562 -0.370899 -0.73273 + outer loop + vertex -911.604 233.685 5.9198 + vertex -912.128 236.084 5.11431 + vertex -910.701 234.166 4.97391 + endloop + endfacet + facet normal -0.686153 -0.430361 -0.586502 + outer loop + vertex -913.649 235.638 6.89304 + vertex -912.984 235.904 5.92081 + vertex -912.247 233.404 6.8926 + endloop + endfacet + facet normal -0.690965 -0.429749 -0.581278 + outer loop + vertex -912.247 233.404 6.8926 + vertex -912.984 235.904 5.92081 + vertex -911.604 233.685 5.9198 + endloop + endfacet + facet normal -0.684296 -0.441594 -0.580287 + outer loop + vertex -912.247 233.404 6.8926 + vertex -911.604 233.685 5.9198 + vertex -910.829 231.207 6.89223 + endloop + endfacet + facet normal -0.684278 -0.441596 -0.580307 + outer loop + vertex -910.829 231.207 6.89223 + vertex -911.604 233.685 5.9198 + vertex -910.198 231.506 5.921 + endloop + endfacet + facet normal -0.571645 -0.369045 -0.732822 + outer loop + vertex -911.604 233.685 5.9198 + vertex -910.701 234.166 4.97391 + vertex -910.198 231.506 5.921 + endloop + endfacet + facet normal -0.599426 -0.366704 -0.711489 + outer loop + vertex -910.198 231.506 5.921 + vertex -910.701 234.166 4.97391 + vertex -909.384 231.739 5.11449 + endloop + endfacet + facet normal -0.60513 -0.310656 -0.733015 + outer loop + vertex -920.221 248.818 5.92108 + vertex -919.323 248.969 5.11564 + vertex -919.111 246.653 5.92172 + endloop + endfacet + facet normal -0.582796 -0.314303 -0.749375 + outer loop + vertex -919.111 246.653 5.92172 + vertex -919.323 248.969 5.11564 + vertex -918.128 247.087 4.97593 + endloop + endfacet + facet normal -0.707809 -0.365313 -0.604609 + outer loop + vertex -920.939 248.596 6.89599 + vertex -920.221 248.818 5.92108 + vertex -919.812 246.413 6.89598 + endloop + endfacet + facet normal -0.71047 -0.364657 -0.601878 + outer loop + vertex -919.812 246.413 6.89598 + vertex -920.221 248.818 5.92108 + vertex -919.111 246.653 5.92172 + endloop + endfacet + facet normal -0.704819 -0.377073 -0.600871 + outer loop + vertex -919.812 246.413 6.89598 + vertex -919.111 246.653 5.92172 + vertex -918.68 244.297 6.89575 + endloop + endfacet + facet normal -0.708541 -0.376172 -0.597047 + outer loop + vertex -918.68 244.297 6.89575 + vertex -919.111 246.653 5.92172 + vertex -917.993 244.55 5.92108 + endloop + endfacet + facet normal -0.5847 -0.310345 -0.749541 + outer loop + vertex -919.111 246.653 5.92172 + vertex -918.128 247.087 4.97593 + vertex -917.993 244.55 5.92108 + endloop + endfacet + facet normal -0.607908 -0.305389 -0.732929 + outer loop + vertex -917.993 244.55 5.92108 + vertex -918.128 247.087 4.97593 + vertex -917.111 244.723 5.11747 + endloop + endfacet + facet normal -0.79599 -0.410723 -0.444641 + outer loop + vertex -921.406 248.398 7.91356 + vertex -920.939 248.596 6.89599 + vertex -920.272 246.203 7.91244 + endloop + endfacet + facet normal -0.795871 -0.410764 -0.444817 + outer loop + vertex -920.272 246.203 7.91244 + vertex -920.939 248.596 6.89599 + vertex -919.812 246.413 6.89598 + endloop + endfacet + facet normal -0.856599 -0.446803 -0.25808 + outer loop + vertex -921.638 248.242 8.95647 + vertex -921.406 248.398 7.91356 + vertex -920.494 246.049 8.95535 + endloop + endfacet + facet normal -0.860703 -0.444232 -0.248693 + outer loop + vertex -920.494 246.049 8.95535 + vertex -921.406 248.398 7.91356 + vertex -920.272 246.203 7.91244 + endloop + endfacet + facet normal -0.852635 -0.45926 -0.249187 + outer loop + vertex -920.494 246.049 8.95535 + vertex -920.272 246.203 7.91244 + vertex -919.346 243.919 8.95383 + endloop + endfacet + facet normal -0.853378 -0.458792 -0.2475 + outer loop + vertex -919.346 243.919 8.95383 + vertex -920.272 246.203 7.91244 + vertex -919.129 244.077 7.91178 + endloop + endfacet + facet normal -0.789019 -0.424125 -0.444485 + outer loop + vertex -920.272 246.203 7.91244 + vertex -919.812 246.413 6.89598 + vertex -919.129 244.077 7.91178 + endloop + endfacet + facet normal -0.791279 -0.423354 -0.441191 + outer loop + vertex -919.129 244.077 7.91178 + vertex -919.812 246.413 6.89598 + vertex -918.68 244.297 6.89575 + endloop + endfacet + facet normal -0.784574 -0.435902 -0.440946 + outer loop + vertex -919.129 244.077 7.91178 + vertex -918.68 244.297 6.89575 + vertex -917.957 241.969 7.91088 + endloop + endfacet + facet normal -0.788077 -0.434749 -0.435806 + outer loop + vertex -917.957 241.969 7.91088 + vertex -918.68 244.297 6.89575 + vertex -917.521 242.197 6.89474 + endloop + endfacet + facet normal -0.845852 -0.47227 -0.247981 + outer loop + vertex -919.346 243.919 8.95383 + vertex -919.129 244.077 7.91178 + vertex -918.165 241.804 8.95238 + endloop + endfacet + facet normal -0.847753 -0.471104 -0.243673 + outer loop + vertex -918.165 241.804 8.95238 + vertex -919.129 244.077 7.91178 + vertex -917.957 241.969 7.91088 + endloop + endfacet + facet normal -0.83994 -0.484608 -0.244246 + outer loop + vertex -918.165 241.804 8.95238 + vertex -917.957 241.969 7.91088 + vertex -916.926 239.657 8.95089 + endloop + endfacet + facet normal -0.841188 -0.483877 -0.241382 + outer loop + vertex -916.926 239.657 8.95089 + vertex -917.957 241.969 7.91088 + vertex -916.726 239.828 7.91007 + endloop + endfacet + facet normal -0.78029 -0.448767 -0.435609 + outer loop + vertex -917.957 241.969 7.91088 + vertex -917.521 242.197 6.89474 + vertex -916.726 239.828 7.91007 + endloop + endfacet + facet normal -0.784924 -0.447354 -0.428682 + outer loop + vertex -916.726 239.828 7.91007 + vertex -917.521 242.197 6.89474 + vertex -916.304 240.062 6.89389 + endloop + endfacet + facet normal -0.599431 -0.330456 -0.729027 + outer loop + vertex -917.993 244.55 5.92108 + vertex -917.111 244.723 5.11747 + vertex -916.837 242.452 5.92117 + endloop + endfacet + facet normal -0.582 -0.332911 -0.74192 + outer loop + vertex -916.837 242.452 5.92117 + vertex -917.111 244.723 5.11747 + vertex -915.866 242.867 4.9735 + endloop + endfacet + facet normal -0.703032 -0.387733 -0.596161 + outer loop + vertex -918.68 244.297 6.89575 + vertex -917.993 244.55 5.92108 + vertex -917.521 242.197 6.89474 + endloop + endfacet + facet normal -0.703257 -0.387682 -0.595929 + outer loop + vertex -917.521 242.197 6.89474 + vertex -917.993 244.55 5.92108 + vertex -916.837 242.452 5.92117 + endloop + endfacet + facet normal -0.69826 -0.397876 -0.595086 + outer loop + vertex -917.521 242.197 6.89474 + vertex -916.837 242.452 5.92117 + vertex -916.304 240.062 6.89389 + endloop + endfacet + facet normal -0.700294 -0.397466 -0.592966 + outer loop + vertex -916.304 240.062 6.89389 + vertex -916.837 242.452 5.92117 + vertex -915.624 240.317 5.92025 + endloop + endfacet + facet normal -0.58303 -0.330805 -0.742054 + outer loop + vertex -916.837 242.452 5.92117 + vertex -915.866 242.867 4.9735 + vertex -915.624 240.317 5.92025 + endloop + endfacet + facet normal -0.602665 -0.327357 -0.727758 + outer loop + vertex -915.624 240.317 5.92025 + vertex -915.866 242.867 4.9735 + vertex -914.739 240.474 5.11667 + endloop + endfacet + facet normal -0.61614 -0.266822 -0.741065 + outer loop + vertex -924.569 258.186 5.92379 + vertex -923.619 258.238 5.11588 + vertex -923.532 255.795 5.92244 + endloop + endfacet + facet normal -0.590577 -0.272073 -0.759734 + outer loop + vertex -923.532 255.795 5.92244 + vertex -923.619 258.238 5.11588 + vertex -922.461 256.115 4.97534 + endloop + endfacet + facet normal -0.720371 -0.314409 -0.618234 + outer loop + vertex -925.332 258.017 6.89877 + vertex -924.569 258.186 5.92379 + vertex -924.286 255.622 6.89796 + endloop + endfacet + facet normal -0.723601 -0.313503 -0.614913 + outer loop + vertex -924.286 255.622 6.89796 + vertex -924.569 258.186 5.92379 + vertex -923.532 255.795 5.92244 + endloop + endfacet + facet normal -0.718387 -0.328012 -0.613456 + outer loop + vertex -924.286 255.622 6.89796 + vertex -923.532 255.795 5.92244 + vertex -923.192 253.228 6.89712 + endloop + endfacet + facet normal -0.718296 -0.328035 -0.61355 + outer loop + vertex -923.192 253.228 6.89712 + vertex -923.532 255.795 5.92244 + vertex -922.442 253.411 5.92207 + endloop + endfacet + facet normal -0.591327 -0.27001 -0.759886 + outer loop + vertex -923.532 255.795 5.92244 + vertex -922.461 256.115 4.97534 + vertex -922.442 253.411 5.92207 + endloop + endfacet + facet normal -0.616147 -0.263949 -0.742087 + outer loop + vertex -922.442 253.411 5.92207 + vertex -922.461 256.115 4.97534 + vertex -921.508 253.495 5.1158 + endloop + endfacet + facet normal -0.811055 -0.357311 -0.463162 + outer loop + vertex -925.835 257.838 7.91743 + vertex -925.332 258.017 6.89877 + vertex -924.777 255.439 7.91658 + endloop + endfacet + facet normal -0.815076 -0.355825 -0.457208 + outer loop + vertex -924.777 255.439 7.91658 + vertex -925.332 258.017 6.89877 + vertex -924.286 255.622 6.89796 + endloop + endfacet + facet normal -0.879951 -0.390183 -0.271005 + outer loop + vertex -926.09 257.688 8.96316 + vertex -925.835 257.838 7.91743 + vertex -925.024 255.285 8.96178 + endloop + endfacet + facet normal -0.882198 -0.388737 -0.265726 + outer loop + vertex -925.024 255.285 8.96178 + vertex -925.835 257.838 7.91743 + vertex -924.777 255.439 7.91658 + endloop + endfacet + facet normal -0.875521 -0.403185 -0.26628 + outer loop + vertex -925.024 255.285 8.96178 + vertex -924.777 255.439 7.91658 + vertex -923.918 252.884 8.95969 + endloop + endfacet + facet normal -0.875725 -0.403057 -0.2658 + outer loop + vertex -923.918 252.884 8.95969 + vertex -924.777 255.439 7.91658 + vertex -923.674 253.042 7.91568 + endloop + endfacet + facet normal -0.808141 -0.371872 -0.456749 + outer loop + vertex -924.777 255.439 7.91658 + vertex -924.286 255.622 6.89796 + vertex -923.674 253.042 7.91568 + endloop + endfacet + facet normal -0.811595 -0.370655 -0.451584 + outer loop + vertex -923.674 253.042 7.91568 + vertex -924.286 255.622 6.89796 + vertex -923.192 253.228 6.89712 + endloop + endfacet + facet normal -0.804676 -0.385984 -0.451125 + outer loop + vertex -923.674 253.042 7.91568 + vertex -923.192 253.228 6.89712 + vertex -922.542 250.684 7.91476 + endloop + endfacet + facet normal -0.804817 -0.385936 -0.450914 + outer loop + vertex -922.542 250.684 7.91476 + vertex -923.192 253.228 6.89712 + vertex -922.064 250.875 6.89733 + endloop + endfacet + facet normal -0.86782 -0.419417 -0.266416 + outer loop + vertex -923.918 252.884 8.95969 + vertex -923.674 253.042 7.91568 + vertex -922.779 250.528 8.95848 + endloop + endfacet + facet normal -0.870621 -0.417705 -0.259886 + outer loop + vertex -922.779 250.528 8.95848 + vertex -923.674 253.042 7.91568 + vertex -922.542 250.684 7.91476 + endloop + endfacet + facet normal -0.864048 -0.430852 -0.26036 + outer loop + vertex -922.779 250.528 8.95848 + vertex -922.542 250.684 7.91476 + vertex -921.638 248.242 8.95647 + endloop + endfacet + facet normal -0.865282 -0.430091 -0.257504 + outer loop + vertex -921.638 248.242 8.95647 + vertex -922.542 250.684 7.91476 + vertex -921.406 248.398 7.91356 + endloop + endfacet + facet normal -0.799489 -0.397276 -0.450542 + outer loop + vertex -922.542 250.684 7.91476 + vertex -922.064 250.875 6.89733 + vertex -921.406 248.398 7.91356 + endloop + endfacet + facet normal -0.803175 -0.39601 -0.445068 + outer loop + vertex -921.406 248.398 7.91356 + vertex -922.064 250.875 6.89733 + vertex -920.939 248.596 6.89599 + endloop + endfacet + facet normal -0.609794 -0.290286 -0.737486 + outer loop + vertex -922.442 253.411 5.92207 + vertex -921.508 253.495 5.1158 + vertex -921.331 251.075 5.92271 + endloop + endfacet + facet normal -0.587587 -0.294112 -0.753816 + outer loop + vertex -921.331 251.075 5.92271 + vertex -921.508 253.495 5.1158 + vertex -920.31 251.461 4.97603 + endloop + endfacet + facet normal -0.713029 -0.341939 -0.6121 + outer loop + vertex -923.192 253.228 6.89712 + vertex -922.442 253.411 5.92207 + vertex -922.064 250.875 6.89733 + endloop + endfacet + facet normal -0.716594 -0.341056 -0.608419 + outer loop + vertex -922.064 250.875 6.89733 + vertex -922.442 253.411 5.92207 + vertex -921.331 251.075 5.92271 + endloop + endfacet + facet normal -0.712521 -0.351188 -0.607437 + outer loop + vertex -922.064 250.875 6.89733 + vertex -921.331 251.075 5.92271 + vertex -920.939 248.596 6.89599 + endloop + endfacet + facet normal -0.714016 -0.350818 -0.605894 + outer loop + vertex -920.939 248.596 6.89599 + vertex -921.331 251.075 5.92271 + vertex -920.221 248.818 5.92108 + endloop + endfacet + facet normal -0.589564 -0.289488 -0.754063 + outer loop + vertex -921.331 251.075 5.92271 + vertex -920.31 251.461 4.97603 + vertex -920.221 248.818 5.92108 + endloop + endfacet + facet normal -0.613194 -0.284198 -0.737037 + outer loop + vertex -920.221 248.818 5.92108 + vertex -920.31 251.461 4.97603 + vertex -919.323 248.969 5.11564 + endloop + endfacet + facet normal -0.618066 -0.218143 -0.755253 + outer loop + vertex -928.258 267.786 5.92347 + vertex -927.285 267.819 5.11772 + vertex -927.393 265.335 5.92339 + endloop + endfacet + facet normal -0.598791 -0.223472 -0.769097 + outer loop + vertex -927.393 265.335 5.92339 + vertex -927.285 267.819 5.11772 + vertex -926.291 265.646 4.9747 + endloop + endfacet + facet normal -0.733555 -0.258707 -0.628465 + outer loop + vertex -929.048 267.65 6.90094 + vertex -928.258 267.786 5.92347 + vertex -928.178 265.185 6.89996 + endloop + endfacet + facet normal -0.733262 -0.25881 -0.628764 + outer loop + vertex -928.178 265.185 6.89996 + vertex -928.258 267.786 5.92347 + vertex -927.393 265.335 5.92339 + endloop + endfacet + facet normal -0.728798 -0.273998 -0.627518 + outer loop + vertex -928.178 265.185 6.89996 + vertex -927.393 265.335 5.92339 + vertex -927.272 262.778 6.89953 + endloop + endfacet + facet normal -0.730817 -0.273311 -0.625466 + outer loop + vertex -927.272 262.778 6.89953 + vertex -927.393 265.335 5.92339 + vertex -926.497 262.939 5.92323 + endloop + endfacet + facet normal -0.598664 -0.223871 -0.76908 + outer loop + vertex -927.393 265.335 5.92339 + vertex -926.291 265.646 4.9747 + vertex -926.497 262.939 5.92323 + endloop + endfacet + facet normal -0.619588 -0.217105 -0.754305 + outer loop + vertex -926.497 262.939 5.92323 + vertex -926.291 265.646 4.9747 + vertex -925.536 262.993 5.11863 + endloop + endfacet + facet normal -0.829527 -0.295046 -0.474165 + outer loop + vertex -929.579 267.502 7.92183 + vertex -929.048 267.65 6.90094 + vertex -928.699 265.029 7.9207 + endloop + endfacet + facet normal -0.832534 -0.293711 -0.469704 + outer loop + vertex -928.699 265.029 7.9207 + vertex -929.048 267.65 6.90094 + vertex -928.178 265.185 6.89996 + endloop + endfacet + facet normal -0.901708 -0.322464 -0.287994 + outer loop + vertex -929.866 267.369 8.96973 + vertex -929.579 267.502 7.92183 + vertex -928.98 264.894 8.96783 + endloop + endfacet + facet normal -0.903241 -0.32137 -0.284387 + outer loop + vertex -928.98 264.894 8.96783 + vertex -929.579 267.502 7.92183 + vertex -928.699 265.029 7.9207 + endloop + endfacet + facet normal -0.896008 -0.340571 -0.284923 + outer loop + vertex -928.98 264.894 8.96783 + vertex -928.699 265.029 7.9207 + vertex -928.06 262.474 8.96629 + endloop + endfacet + facet normal -0.897261 -0.339693 -0.282012 + outer loop + vertex -928.06 262.474 8.96629 + vertex -928.699 265.029 7.9207 + vertex -927.784 262.613 7.91988 + endloop + endfacet + facet normal -0.82591 -0.312609 -0.4692 + outer loop + vertex -928.699 265.029 7.9207 + vertex -928.178 265.185 6.89996 + vertex -927.784 262.613 7.91988 + endloop + endfacet + facet normal -0.82845 -0.311507 -0.46544 + outer loop + vertex -927.784 262.613 7.91988 + vertex -928.178 265.185 6.89996 + vertex -927.272 262.778 6.89953 + endloop + endfacet + facet normal -0.822665 -0.327042 -0.465044 + outer loop + vertex -927.784 262.613 7.91988 + vertex -927.272 262.778 6.89953 + vertex -926.834 260.225 7.91866 + endloop + endfacet + facet normal -0.82288 -0.326952 -0.464726 + outer loop + vertex -926.834 260.225 7.91866 + vertex -927.272 262.778 6.89953 + vertex -926.327 260.398 6.89914 + endloop + endfacet + facet normal -0.889698 -0.358632 -0.282525 + outer loop + vertex -928.06 262.474 8.96629 + vertex -927.784 262.613 7.91988 + vertex -927.096 260.083 8.96522 + endloop + endfacet + facet normal -0.894134 -0.355572 -0.2722 + outer loop + vertex -927.096 260.083 8.96522 + vertex -927.784 262.613 7.91988 + vertex -926.834 260.225 7.91866 + endloop + endfacet + facet normal -0.887157 -0.372256 -0.272722 + outer loop + vertex -927.096 260.083 8.96522 + vertex -926.834 260.225 7.91866 + vertex -926.09 257.688 8.96316 + endloop + endfacet + facet normal -0.888168 -0.371576 -0.27035 + outer loop + vertex -926.09 257.688 8.96316 + vertex -926.834 260.225 7.91866 + vertex -925.835 257.838 7.91743 + endloop + endfacet + facet normal -0.817075 -0.341722 -0.464344 + outer loop + vertex -926.834 260.225 7.91866 + vertex -926.327 260.398 6.89914 + vertex -925.835 257.838 7.91743 + endloop + endfacet + facet normal -0.817577 -0.341524 -0.463605 + outer loop + vertex -925.835 257.838 7.91743 + vertex -926.327 260.398 6.89914 + vertex -925.332 258.017 6.89877 + endloop + endfacet + facet normal -0.614875 -0.242539 -0.750402 + outer loop + vertex -926.497 262.939 5.92323 + vertex -925.536 262.993 5.11863 + vertex -925.56 260.564 5.9232 + endloop + endfacet + facet normal -0.593986 -0.247707 -0.76539 + outer loop + vertex -925.56 260.564 5.9232 + vertex -925.536 262.993 5.11863 + vertex -924.469 260.872 4.97685 + endloop + endfacet + facet normal -0.726071 -0.288451 -0.624192 + outer loop + vertex -927.272 262.778 6.89953 + vertex -926.497 262.939 5.92323 + vertex -926.327 260.398 6.89914 + endloop + endfacet + facet normal -0.72892 -0.287528 -0.621292 + outer loop + vertex -926.327 260.398 6.89914 + vertex -926.497 262.939 5.92323 + vertex -925.56 260.564 5.9232 + endloop + endfacet + facet normal -0.724014 -0.302408 -0.619963 + outer loop + vertex -926.327 260.398 6.89914 + vertex -925.56 260.564 5.9232 + vertex -925.332 258.017 6.89877 + endloop + endfacet + facet normal -0.724558 -0.302244 -0.619406 + outer loop + vertex -925.332 258.017 6.89877 + vertex -925.56 260.564 5.9232 + vertex -924.569 258.186 5.92379 + endloop + endfacet + facet normal -0.593946 -0.247824 -0.765383 + outer loop + vertex -925.56 260.564 5.9232 + vertex -924.469 260.872 4.97685 + vertex -924.569 258.186 5.92379 + endloop + endfacet + facet normal -0.621577 -0.23987 -0.745724 + outer loop + vertex -924.569 258.186 5.92379 + vertex -924.469 260.872 4.97685 + vertex -923.619 258.238 5.11588 + endloop + endfacet + facet normal -0.622775 -0.167764 -0.764203 + outer loop + vertex -931.342 278.061 5.92463 + vertex -930.342 278.015 5.11913 + vertex -930.646 275.474 5.92486 + endloop + endfacet + facet normal -0.602737 -0.17472 -0.778576 + outer loop + vertex -930.646 275.474 5.92486 + vertex -930.342 278.015 5.11913 + vertex -929.484 275.691 4.97677 + endloop + endfacet + facet normal -0.743354 -0.200093 -0.638269 + outer loop + vertex -932.156 277.96 6.90375 + vertex -931.342 278.061 5.92463 + vertex -931.458 275.37 6.90302 + endloop + endfacet + facet normal -0.743167 -0.200171 -0.638462 + outer loop + vertex -931.458 275.37 6.90302 + vertex -931.342 278.061 5.92463 + vertex -930.646 275.474 5.92486 + endloop + endfacet + facet normal -0.740189 -0.213929 -0.637459 + outer loop + vertex -931.458 275.37 6.90302 + vertex -930.646 275.474 5.92486 + vertex -930.704 272.766 6.90158 + endloop + endfacet + facet normal -0.737706 -0.214901 -0.640005 + outer loop + vertex -930.704 272.766 6.90158 + vertex -930.646 275.474 5.92486 + vertex -929.889 272.876 5.92541 + endloop + endfacet + facet normal -0.602542 -0.17558 -0.778534 + outer loop + vertex -930.646 275.474 5.92486 + vertex -929.484 275.691 4.97677 + vertex -929.889 272.876 5.92541 + endloop + endfacet + facet normal -0.627833 -0.165853 -0.760473 + outer loop + vertex -929.889 272.876 5.92541 + vertex -929.484 275.691 4.97677 + vertex -928.905 272.859 5.11661 + endloop + endfacet + facet normal -0.840865 -0.227774 -0.490984 + outer loop + vertex -932.715 277.82 7.92552 + vertex -932.156 277.96 6.90375 + vertex -932.012 275.228 7.92443 + endloop + endfacet + facet normal -0.842637 -0.226883 -0.488351 + outer loop + vertex -932.012 275.228 7.92443 + vertex -932.156 277.96 6.90375 + vertex -931.458 275.37 6.90302 + endloop + endfacet + facet normal -0.918807 -0.252418 -0.303445 + outer loop + vertex -933.024 277.683 8.97555 + vertex -932.715 277.82 7.92552 + vertex -932.311 275.091 8.97424 + endloop + endfacet + facet normal -0.922065 -0.249872 -0.295567 + outer loop + vertex -932.311 275.091 8.97424 + vertex -932.715 277.82 7.92552 + vertex -932.012 275.228 7.92443 + endloop + endfacet + facet normal -0.915786 -0.270935 -0.296531 + outer loop + vertex -932.311 275.091 8.97424 + vertex -932.012 275.228 7.92443 + vertex -931.541 272.489 8.97284 + endloop + endfacet + facet normal -0.916686 -0.270258 -0.294358 + outer loop + vertex -931.541 272.489 8.97284 + vertex -932.012 275.228 7.92443 + vertex -931.244 272.625 7.92385 + endloop + endfacet + facet normal -0.837155 -0.246762 -0.488139 + outer loop + vertex -932.012 275.228 7.92443 + vertex -931.458 275.37 6.90302 + vertex -931.244 272.625 7.92385 + endloop + endfacet + facet normal -0.843245 -0.243851 -0.479035 + outer loop + vertex -931.244 272.625 7.92385 + vertex -931.458 275.37 6.90302 + vertex -930.704 272.766 6.90158 + endloop + endfacet + facet normal -0.837519 -0.263424 -0.478717 + outer loop + vertex -931.244 272.625 7.92385 + vertex -930.704 272.766 6.90158 + vertex -930.43 270.039 7.92288 + endloop + endfacet + facet normal -0.836656 -0.26382 -0.480006 + outer loop + vertex -930.43 270.039 7.92288 + vertex -930.704 272.766 6.90158 + vertex -929.89 270.182 6.90211 + endloop + endfacet + facet normal -0.911161 -0.287635 -0.295044 + outer loop + vertex -931.541 272.489 8.97284 + vertex -931.244 272.625 7.92385 + vertex -930.724 269.904 8.97104 + endloop + endfacet + facet normal -0.912084 -0.286963 -0.292839 + outer loop + vertex -930.724 269.904 8.97104 + vertex -931.244 272.625 7.92385 + vertex -930.43 270.039 7.92288 + endloop + endfacet + facet normal -0.905496 -0.306487 -0.2935 + outer loop + vertex -930.724 269.904 8.97104 + vertex -930.43 270.039 7.92288 + vertex -929.866 267.369 8.96973 + endloop + endfacet + facet normal -0.908045 -0.30466 -0.287466 + outer loop + vertex -929.866 267.369 8.96973 + vertex -930.43 270.039 7.92288 + vertex -929.579 267.502 7.92183 + endloop + endfacet + facet normal -0.83192 -0.27903 -0.479636 + outer loop + vertex -930.43 270.039 7.92288 + vertex -929.89 270.182 6.90211 + vertex -929.579 267.502 7.92183 + endloop + endfacet + facet normal -0.835296 -0.277514 -0.474622 + outer loop + vertex -929.579 267.502 7.92183 + vertex -929.89 270.182 6.90211 + vertex -929.048 267.65 6.90094 + endloop + endfacet + facet normal -0.624876 -0.19382 -0.756283 + outer loop + vertex -929.889 272.876 5.92541 + vertex -928.905 272.859 5.11661 + vertex -929.091 270.304 5.92486 + endloop + endfacet + facet normal -0.599009 -0.201606 -0.774947 + outer loop + vertex -929.091 270.304 5.92486 + vertex -928.905 272.859 5.11661 + vertex -927.958 270.577 4.97789 + endloop + endfacet + facet normal -0.733861 -0.23145 -0.638654 + outer loop + vertex -930.704 272.766 6.90158 + vertex -929.889 272.876 5.92541 + vertex -929.89 270.182 6.90211 + endloop + endfacet + facet normal -0.739392 -0.229396 -0.63299 + outer loop + vertex -929.89 270.182 6.90211 + vertex -929.889 272.876 5.92541 + vertex -929.091 270.304 5.92486 + endloop + endfacet + facet normal -0.73564 -0.244305 -0.631782 + outer loop + vertex -929.89 270.182 6.90211 + vertex -929.091 270.304 5.92486 + vertex -929.048 267.65 6.90094 + endloop + endfacet + facet normal -0.737673 -0.24357 -0.629692 + outer loop + vertex -929.048 267.65 6.90094 + vertex -929.091 270.304 5.92486 + vertex -928.258 267.786 5.92347 + endloop + endfacet + facet normal -0.600017 -0.197973 -0.775104 + outer loop + vertex -929.091 270.304 5.92486 + vertex -927.958 270.577 4.97789 + vertex -928.258 267.786 5.92347 + endloop + endfacet + facet normal -0.622347 -0.19021 -0.759279 + outer loop + vertex -928.258 267.786 5.92347 + vertex -927.958 270.577 4.97789 + vertex -927.285 267.819 5.11772 + endloop + endfacet + facet normal -0.634866 -0.115915 -0.763877 + outer loop + vertex -933.501 288.076 5.92723 + vertex -932.515 288.01 5.11735 + vertex -933.052 285.622 5.92597 + endloop + endfacet + facet normal -0.609996 -0.127664 -0.782053 + outer loop + vertex -933.052 285.622 5.92597 + vertex -932.515 288.01 5.11735 + vertex -931.87 285.792 4.97598 + endloop + endfacet + facet normal -0.746031 -0.139995 -0.65103 + outer loop + vertex -934.341 288.006 6.90472 + vertex -933.501 288.076 5.92723 + vertex -933.879 285.544 6.90487 + endloop + endfacet + facet normal -0.751017 -0.137255 -0.64586 + outer loop + vertex -933.879 285.544 6.90487 + vertex -933.501 288.076 5.92723 + vertex -933.052 285.622 5.92597 + endloop + endfacet + facet normal -0.748408 -0.154347 -0.645029 + outer loop + vertex -933.879 285.544 6.90487 + vertex -933.052 285.622 5.92597 + vertex -933.364 283.047 6.90454 + endloop + endfacet + facet normal -0.747821 -0.154649 -0.645637 + outer loop + vertex -933.364 283.047 6.90454 + vertex -933.052 285.622 5.92597 + vertex -932.538 283.135 5.92653 + endloop + endfacet + facet normal -0.610233 -0.126253 -0.782097 + outer loop + vertex -933.052 285.622 5.92597 + vertex -931.87 285.792 4.97598 + vertex -932.538 283.135 5.92653 + endloop + endfacet + facet normal -0.628888 -0.11676 -0.768679 + outer loop + vertex -932.538 283.135 5.92653 + vertex -931.87 285.792 4.97598 + vertex -931.542 283.079 5.12042 + endloop + endfacet + facet normal -0.852854 -0.160303 -0.496934 + outer loop + vertex -934.917 287.891 7.92885 + vertex -934.341 288.006 6.90472 + vertex -934.452 285.423 7.92823 + endloop + endfacet + facet normal -0.853188 -0.160089 -0.496429 + outer loop + vertex -934.452 285.423 7.92823 + vertex -934.341 288.006 6.90472 + vertex -933.879 285.544 6.90487 + endloop + endfacet + facet normal -0.934219 -0.175126 -0.310751 + outer loop + vertex -935.244 287.771 8.98161 + vertex -934.917 287.891 7.92885 + vertex -934.78 285.297 8.97984 + endloop + endfacet + facet normal -0.933752 -0.175568 -0.311902 + outer loop + vertex -934.78 285.297 8.97984 + vertex -934.917 287.891 7.92885 + vertex -934.452 285.423 7.92823 + endloop + endfacet + facet normal -0.92948 -0.195309 -0.312924 + outer loop + vertex -934.78 285.297 8.97984 + vertex -934.452 285.423 7.92823 + vertex -934.252 282.789 8.97871 + endloop + endfacet + facet normal -0.932085 -0.192969 -0.306562 + outer loop + vertex -934.252 282.789 8.97871 + vertex -934.452 285.423 7.92823 + vertex -933.934 282.919 7.92731 + endloop + endfacet + facet normal -0.850016 -0.175899 -0.496521 + outer loop + vertex -934.452 285.423 7.92823 + vertex -933.879 285.544 6.90487 + vertex -933.934 282.919 7.92731 + endloop + endfacet + facet normal -0.850712 -0.175477 -0.495476 + outer loop + vertex -933.934 282.919 7.92731 + vertex -933.879 285.544 6.90487 + vertex -933.364 283.047 6.90454 + endloop + endfacet + facet normal -0.846635 -0.194054 -0.495532 + outer loop + vertex -933.934 282.919 7.92731 + vertex -933.364 283.047 6.90454 + vertex -933.352 280.384 7.92673 + endloop + endfacet + facet normal -0.851404 -0.191326 -0.48837 + outer loop + vertex -933.352 280.384 7.92673 + vertex -933.364 283.047 6.90454 + vertex -932.796 280.52 6.90338 + endloop + endfacet + facet normal -0.92773 -0.211521 -0.307533 + outer loop + vertex -934.252 282.789 8.97871 + vertex -933.934 282.919 7.92731 + vertex -933.673 280.249 8.97672 + endloop + endfacet + facet normal -0.926646 -0.212445 -0.310153 + outer loop + vertex -933.673 280.249 8.97672 + vertex -933.934 282.919 7.92731 + vertex -933.352 280.384 7.92673 + endloop + endfacet + facet normal -0.921381 -0.232882 -0.311162 + outer loop + vertex -933.673 280.249 8.97672 + vertex -933.352 280.384 7.92673 + vertex -933.024 277.683 8.97555 + endloop + endfacet + facet normal -0.925052 -0.229909 -0.302357 + outer loop + vertex -933.024 277.683 8.97555 + vertex -933.352 280.384 7.92673 + vertex -932.715 277.82 7.92552 + endloop + endfacet + facet normal -0.846858 -0.210375 -0.48844 + outer loop + vertex -933.352 280.384 7.92673 + vertex -932.796 280.52 6.90338 + vertex -932.715 277.82 7.92552 + endloop + endfacet + facet normal -0.845111 -0.211312 -0.491055 + outer loop + vertex -932.715 277.82 7.92552 + vertex -932.796 280.52 6.90338 + vertex -932.156 277.96 6.90375 + endloop + endfacet + facet normal -0.62771 -0.141063 -0.76556 + outer loop + vertex -932.538 283.135 5.92653 + vertex -931.542 283.079 5.12042 + vertex -931.971 280.616 5.9258 + endloop + endfacet + facet normal -0.60801 -0.149146 -0.779794 + outer loop + vertex -931.971 280.616 5.9258 + vertex -931.542 283.079 5.12042 + vertex -930.799 280.805 4.97559 + endloop + endfacet + facet normal -0.74565 -0.167462 -0.644952 + outer loop + vertex -933.364 283.047 6.90454 + vertex -932.538 283.135 5.92653 + vertex -932.796 280.52 6.90338 + endloop + endfacet + facet normal -0.745393 -0.167586 -0.645216 + outer loop + vertex -932.796 280.52 6.90338 + vertex -932.538 283.135 5.92653 + vertex -931.971 280.616 5.9258 + endloop + endfacet + facet normal -0.742044 -0.185573 -0.644154 + outer loop + vertex -932.796 280.52 6.90338 + vertex -931.971 280.616 5.9258 + vertex -932.156 277.96 6.90375 + endloop + endfacet + facet normal -0.746716 -0.183475 -0.639337 + outer loop + vertex -932.156 277.96 6.90375 + vertex -931.971 280.616 5.9258 + vertex -931.342 278.061 5.92463 + endloop + endfacet + facet normal -0.607987 -0.149269 -0.779789 + outer loop + vertex -931.971 280.616 5.9258 + vertex -930.799 280.805 4.97559 + vertex -931.342 278.061 5.92463 + endloop + endfacet + facet normal -0.624604 -0.141882 -0.767945 + outer loop + vertex -931.342 278.061 5.92463 + vertex -930.799 280.805 4.97559 + vertex -930.342 278.015 5.11913 + endloop + endfacet + facet normal -0.637328 -0.0663284 -0.767733 + outer loop + vertex -934.815 297.793 5.92714 + vertex -933.832 297.71 5.11755 + vertex -934.558 295.321 5.92718 + endloop + endfacet + facet normal -0.613343 -0.0797454 -0.785781 + outer loop + vertex -934.558 295.321 5.92718 + vertex -933.832 297.71 5.11755 + vertex -933.363 295.493 4.97704 + endloop + endfacet + facet normal -0.753101 -0.0799205 -0.653032 + outer loop + vertex -935.66 297.752 6.90639 + vertex -934.815 297.793 5.92714 + vertex -935.397 295.266 6.90686 + endloop + endfacet + facet normal -0.755159 -0.078587 -0.650814 + outer loop + vertex -935.397 295.266 6.90686 + vertex -934.815 297.793 5.92714 + vertex -934.558 295.321 5.92718 + endloop + endfacet + facet normal -0.753663 -0.0945131 -0.65043 + outer loop + vertex -935.397 295.266 6.90686 + vertex -934.558 295.321 5.92718 + vertex -935.092 292.84 6.90628 + endloop + endfacet + facet normal -0.753349 -0.0947126 -0.650765 + outer loop + vertex -935.092 292.84 6.90628 + vertex -934.558 295.321 5.92718 + vertex -934.254 292.904 5.92716 + endloop + endfacet + facet normal -0.613699 -0.077153 -0.785761 + outer loop + vertex -934.558 295.321 5.92718 + vertex -933.363 295.493 4.97704 + vertex -934.254 292.904 5.92716 + endloop + endfacet + facet normal -0.635992 -0.063361 -0.76909 + outer loop + vertex -934.254 292.904 5.92716 + vertex -933.363 295.493 4.97704 + vertex -933.269 292.841 5.11752 + endloop + endfacet + facet normal -0.861167 -0.089746 -0.500338 + outer loop + vertex -936.247 297.665 7.93225 + vertex -935.66 297.752 6.90639 + vertex -935.987 295.17 7.93125 + endloop + endfacet + facet normal -0.859307 -0.0911456 -0.503273 + outer loop + vertex -935.987 295.17 7.93125 + vertex -935.66 297.752 6.90639 + vertex -935.397 295.266 6.90686 + endloop + endfacet + facet normal -0.941222 -0.101068 -0.322314 + outer loop + vertex -936.597 297.558 8.98652 + vertex -936.247 297.665 7.93225 + vertex -936.328 295.062 8.98546 + endloop + endfacet + facet normal -0.943642 -0.0984336 -0.31599 + outer loop + vertex -936.328 295.062 8.98546 + vertex -936.247 297.665 7.93225 + vertex -935.987 295.17 7.93125 + endloop + endfacet + facet normal -0.940755 -0.119768 -0.31723 + outer loop + vertex -936.328 295.062 8.98546 + vertex -935.987 295.17 7.93125 + vertex -936.018 292.625 8.98413 + endloop + endfacet + facet normal -0.940851 -0.119665 -0.316984 + outer loop + vertex -936.018 292.625 8.98413 + vertex -935.987 295.17 7.93125 + vertex -935.677 292.737 7.93074 + endloop + endfacet + facet normal -0.857019 -0.108957 -0.503634 + outer loop + vertex -935.987 295.17 7.93125 + vertex -935.397 295.266 6.90686 + vertex -935.677 292.737 7.93074 + endloop + endfacet + facet normal -0.858671 -0.107739 -0.501076 + outer loop + vertex -935.677 292.737 7.93074 + vertex -935.397 295.266 6.90686 + vertex -935.092 292.84 6.90628 + endloop + endfacet + facet normal -0.85601 -0.125908 -0.501392 + outer loop + vertex -935.677 292.737 7.93074 + vertex -935.092 292.84 6.90628 + vertex -935.321 290.323 7.92989 + endloop + endfacet + facet normal -0.856798 -0.125346 -0.500186 + outer loop + vertex -935.321 290.323 7.92989 + vertex -935.092 292.84 6.90628 + vertex -934.74 290.432 6.90593 + endloop + endfacet + facet normal -0.937764 -0.139394 -0.318068 + outer loop + vertex -936.018 292.625 8.98413 + vertex -935.677 292.737 7.93074 + vertex -935.658 290.207 8.98283 + endloop + endfacet + facet normal -0.938929 -0.138187 -0.315146 + outer loop + vertex -935.658 290.207 8.98283 + vertex -935.677 292.737 7.93074 + vertex -935.321 290.323 7.92989 + endloop + endfacet + facet normal -0.935325 -0.158629 -0.316235 + outer loop + vertex -935.658 290.207 8.98283 + vertex -935.321 290.323 7.92989 + vertex -935.244 287.771 8.98161 + endloop + endfacet + facet normal -0.937937 -0.156026 -0.309726 + outer loop + vertex -935.244 287.771 8.98161 + vertex -935.321 290.323 7.92989 + vertex -934.917 287.891 7.92885 + endloop + endfacet + facet normal -0.854067 -0.14198 -0.50041 + outer loop + vertex -935.321 290.323 7.92989 + vertex -934.74 290.432 6.90593 + vertex -934.917 287.891 7.92885 + endloop + endfacet + facet normal -0.85649 -0.140327 -0.496722 + outer loop + vertex -934.917 287.891 7.92885 + vertex -934.74 290.432 6.90593 + vertex -934.341 288.006 6.90472 + endloop + endfacet + facet normal -0.635664 -0.0926166 -0.76639 + outer loop + vertex -934.254 292.904 5.92716 + vertex -933.269 292.841 5.11752 + vertex -933.904 290.499 5.92715 + endloop + endfacet + facet normal -0.611314 -0.105423 -0.784334 + outer loop + vertex -933.904 290.499 5.92715 + vertex -933.269 292.841 5.11752 + vertex -932.714 290.663 4.97801 + endloop + endfacet + facet normal -0.751662 -0.109934 -0.650322 + outer loop + vertex -935.092 292.84 6.90628 + vertex -934.254 292.904 5.92716 + vertex -934.74 290.432 6.90593 + endloop + endfacet + facet normal -0.752211 -0.109598 -0.649744 + outer loop + vertex -934.74 290.432 6.90593 + vertex -934.254 292.904 5.92716 + vertex -933.904 290.499 5.92715 + endloop + endfacet + facet normal -0.750578 -0.122868 -0.649258 + outer loop + vertex -934.74 290.432 6.90593 + vertex -933.904 290.499 5.92715 + vertex -934.341 288.006 6.90472 + endloop + endfacet + facet normal -0.748176 -0.124271 -0.651759 + outer loop + vertex -934.341 288.006 6.90472 + vertex -933.904 290.499 5.92715 + vertex -933.501 288.076 5.92723 + endloop + endfacet + facet normal -0.611882 -0.10164 -0.784391 + outer loop + vertex -933.904 290.499 5.92715 + vertex -932.714 290.663 4.97801 + vertex -933.501 288.076 5.92723 + endloop + endfacet + facet normal -0.635575 -0.0880555 -0.767001 + outer loop + vertex -933.501 288.076 5.92723 + vertex -932.714 290.663 4.97801 + vertex -932.515 288.01 5.11735 + endloop + endfacet + facet normal -0.640956 -0.0164992 -0.767401 + outer loop + vertex -935.376 308.239 5.92731 + vertex -934.404 308.079 5.11826 + vertex -935.31 305.608 5.92872 + endloop + endfacet + facet normal -0.620748 -0.0291844 -0.783467 + outer loop + vertex -935.31 305.608 5.92872 + vertex -934.404 308.079 5.11826 + vertex -934.112 305.682 4.9763 + endloop + endfacet + facet normal -0.760887 -0.0176102 -0.648646 + outer loop + vertex -936.213 308.233 6.90877 + vertex -935.376 308.239 5.92731 + vertex -936.152 305.604 6.90864 + endloop + endfacet + facet normal -0.758427 -0.0193856 -0.65147 + outer loop + vertex -936.152 305.604 6.90864 + vertex -935.376 308.239 5.92731 + vertex -935.31 305.608 5.92872 + endloop + endfacet + facet normal -0.75817 -0.0313665 -0.651303 + outer loop + vertex -936.152 305.604 6.90864 + vertex -935.31 305.608 5.92872 + vertex -936.041 302.952 6.9074 + endloop + endfacet + facet normal -0.755906 -0.0329282 -0.653851 + outer loop + vertex -936.041 302.952 6.9074 + vertex -935.31 305.608 5.92872 + vertex -935.195 302.96 5.92808 + endloop + endfacet + facet normal -0.62087 -0.0269861 -0.783449 + outer loop + vertex -935.31 305.608 5.92872 + vertex -934.112 305.682 4.9763 + vertex -935.195 302.96 5.92808 + endloop + endfacet + facet normal -0.636446 -0.0164878 -0.771145 + outer loop + vertex -935.195 302.96 5.92808 + vertex -934.112 305.682 4.9763 + vertex -934.211 302.822 5.11951 + endloop + endfacet + facet normal -0.863542 -0.0194526 -0.503902 + outer loop + vertex -936.81 308.157 7.93529 + vertex -936.213 308.233 6.90877 + vertex -936.75 305.527 7.93434 + endloop + endfacet + facet normal -0.862906 -0.0199829 -0.504969 + outer loop + vertex -936.75 305.527 7.93434 + vertex -936.213 308.233 6.90877 + vertex -936.152 305.604 6.90864 + endloop + endfacet + facet normal -0.942999 -0.0253106 -0.331833 + outer loop + vertex -937.179 308.052 8.99041 + vertex -936.81 308.157 7.93529 + vertex -937.108 305.419 8.99006 + endloop + endfacet + facet normal -0.94629 -0.0213997 -0.322609 + outer loop + vertex -937.108 305.419 8.99006 + vertex -936.81 308.157 7.93529 + vertex -936.75 305.527 7.93434 + endloop + endfacet + facet normal -0.945081 -0.0412554 -0.324223 + outer loop + vertex -937.108 305.419 8.99006 + vertex -936.75 305.527 7.93434 + vertex -936.992 302.763 8.98854 + endloop + endfacet + facet normal -0.943592 -0.0429455 -0.328313 + outer loop + vertex -936.992 302.763 8.98854 + vertex -936.75 305.527 7.93434 + vertex -936.63 302.873 7.93417 + endloop + endfacet + facet normal -0.861783 -0.0392087 -0.505759 + outer loop + vertex -936.75 305.527 7.93434 + vertex -936.152 305.604 6.90864 + vertex -936.63 302.873 7.93417 + endloop + endfacet + facet normal -0.865882 -0.0359371 -0.498955 + outer loop + vertex -936.63 302.873 7.93417 + vertex -936.152 305.604 6.90864 + vertex -936.041 302.952 6.9074 + endloop + endfacet + facet normal -0.864532 -0.0545081 -0.499612 + outer loop + vertex -936.63 302.873 7.93417 + vertex -936.041 302.952 6.9074 + vertex -936.463 300.239 7.9332 + endloop + endfacet + facet normal -0.862302 -0.0562349 -0.503262 + outer loop + vertex -936.463 300.239 7.9332 + vertex -936.041 302.952 6.9074 + vertex -935.87 300.32 6.90763 + endloop + endfacet + facet normal -0.942011 -0.0621987 -0.329768 + outer loop + vertex -936.992 302.763 8.98854 + vertex -936.63 302.873 7.93417 + vertex -936.817 300.13 8.98772 + endloop + endfacet + facet normal -0.944354 -0.0596228 -0.323481 + outer loop + vertex -936.817 300.13 8.98772 + vertex -936.63 302.873 7.93417 + vertex -936.463 300.239 7.9332 + endloop + endfacet + facet normal -0.942284 -0.0806779 -0.324951 + outer loop + vertex -936.817 300.13 8.98772 + vertex -936.463 300.239 7.9332 + vertex -936.597 297.558 8.98652 + endloop + endfacet + facet normal -0.943804 -0.0790195 -0.320922 + outer loop + vertex -936.597 297.558 8.98652 + vertex -936.463 300.239 7.9332 + vertex -936.247 297.665 7.93225 + endloop + endfacet + facet normal -0.860881 -0.0719989 -0.503686 + outer loop + vertex -936.463 300.239 7.9332 + vertex -935.87 300.32 6.90763 + vertex -936.247 297.665 7.93225 + endloop + endfacet + facet normal -0.863254 -0.070187 -0.499866 + outer loop + vertex -936.247 297.665 7.93225 + vertex -935.87 300.32 6.90763 + vertex -935.66 297.752 6.90639 + endloop + endfacet + facet normal -0.638034 -0.0407305 -0.76893 + outer loop + vertex -935.195 302.96 5.92808 + vertex -934.211 302.822 5.11951 + vertex -935.027 300.343 5.92773 + endloop + endfacet + facet normal -0.616586 -0.0531893 -0.785489 + outer loop + vertex -935.027 300.343 5.92773 + vertex -934.211 302.822 5.11951 + vertex -933.828 300.475 4.97739 + endloop + endfacet + facet normal -0.755329 -0.0492769 -0.653491 + outer loop + vertex -936.041 302.952 6.9074 + vertex -935.195 302.96 5.92808 + vertex -935.87 300.32 6.90763 + endloop + endfacet + facet normal -0.756729 -0.048343 -0.651939 + outer loop + vertex -935.87 300.32 6.90763 + vertex -935.195 302.96 5.92808 + vertex -935.027 300.343 5.92773 + endloop + endfacet + facet normal -0.756032 -0.0613659 -0.651651 + outer loop + vertex -935.87 300.32 6.90763 + vertex -935.027 300.343 5.92773 + vertex -935.66 297.752 6.90639 + endloop + endfacet + facet normal -0.754408 -0.0624343 -0.653429 + outer loop + vertex -935.66 297.752 6.90639 + vertex -935.027 300.343 5.92773 + vertex -934.815 297.793 5.92714 + endloop + endfacet + facet normal -0.616807 -0.0509887 -0.785462 + outer loop + vertex -935.027 300.343 5.92773 + vertex -933.828 300.475 4.97739 + vertex -934.815 297.793 5.92714 + endloop + endfacet + facet normal -0.636841 -0.0381533 -0.770051 + outer loop + vertex -934.815 297.793 5.92714 + vertex -933.828 300.475 4.97739 + vertex -933.832 297.71 5.11755 + endloop + endfacet + facet normal -0.645012 0.0325144 -0.763481 + outer loop + vertex -935.14 318.509 5.92901 + vertex -934.191 318.354 5.12058 + vertex -935.268 315.935 5.92788 + endloop + endfacet + facet normal -0.625134 0.0180434 -0.780309 + outer loop + vertex -935.268 315.935 5.92788 + vertex -934.191 318.354 5.12058 + vertex -934.078 316.019 4.97647 + endloop + endfacet + facet normal -0.759458 0.0374326 -0.649479 + outer loop + vertex -935.978 318.52 6.90945 + vertex -935.14 318.509 5.92901 + vertex -936.105 315.934 6.90898 + endloop + endfacet + facet normal -0.760397 0.0382209 -0.648333 + outer loop + vertex -936.105 315.934 6.90898 + vertex -935.14 318.509 5.92901 + vertex -935.268 315.935 5.92788 + endloop + endfacet + facet normal -0.760728 0.0239948 -0.648627 + outer loop + vertex -936.105 315.934 6.90898 + vertex -935.268 315.935 5.92788 + vertex -936.186 313.378 6.90934 + endloop + endfacet + facet normal -0.75909 0.0226525 -0.650592 + outer loop + vertex -936.186 313.378 6.90934 + vertex -935.268 315.935 5.92788 + vertex -935.346 313.385 5.92969 + endloop + endfacet + facet normal -0.625148 0.0184822 -0.780287 + outer loop + vertex -935.268 315.935 5.92788 + vertex -934.078 316.019 4.97647 + vertex -935.346 313.385 5.92969 + endloop + endfacet + facet normal -0.642984 0.0325309 -0.765188 + outer loop + vertex -935.346 313.385 5.92969 + vertex -934.078 316.019 4.97647 + vertex -934.389 313.242 5.11935 + endloop + endfacet + facet normal -0.865731 0.0439983 -0.498571 + outer loop + vertex -936.573 318.465 7.93878 + vertex -935.978 318.52 6.90945 + vertex -936.704 315.871 7.93689 + endloop + endfacet + facet normal -0.864256 0.0425551 -0.501249 + outer loop + vertex -936.704 315.871 7.93689 + vertex -935.978 318.52 6.90945 + vertex -936.105 315.934 6.90898 + endloop + endfacet + facet normal -0.942778 0.0459552 -0.330238 + outer loop + vertex -936.948 318.376 8.99759 + vertex -936.573 318.465 7.93878 + vertex -937.074 315.781 8.99507 + endloop + endfacet + facet normal -0.944116 0.0478232 -0.326124 + outer loop + vertex -937.074 315.781 8.99507 + vertex -936.573 318.465 7.93878 + vertex -936.704 315.871 7.93689 + endloop + endfacet + facet normal -0.944301 0.0295628 -0.327753 + outer loop + vertex -937.074 315.781 8.99507 + vertex -936.704 315.871 7.93689 + vertex -937.154 313.215 8.99328 + endloop + endfacet + facet normal -0.943932 0.0290607 -0.328859 + outer loop + vertex -937.154 313.215 8.99328 + vertex -936.704 315.871 7.93689 + vertex -936.783 313.309 7.93662 + endloop + endfacet + facet normal -0.864312 0.0266309 -0.502251 + outer loop + vertex -936.704 315.871 7.93689 + vertex -936.105 315.934 6.90898 + vertex -936.783 313.309 7.93662 + endloop + endfacet + facet normal -0.865033 0.0273178 -0.500972 + outer loop + vertex -936.783 313.309 7.93662 + vertex -936.105 315.934 6.90898 + vertex -936.186 313.378 6.90934 + endloop + endfacet + facet normal -0.864882 0.0139314 -0.501781 + outer loop + vertex -936.783 313.309 7.93662 + vertex -936.186 313.378 6.90934 + vertex -936.823 310.748 7.93569 + endloop + endfacet + facet normal -0.862431 0.011674 -0.506041 + outer loop + vertex -936.823 310.748 7.93569 + vertex -936.186 313.378 6.90934 + vertex -936.22 310.82 6.90974 + endloop + endfacet + facet normal -0.943815 0.0136325 -0.330192 + outer loop + vertex -937.154 313.215 8.99328 + vertex -936.783 313.309 7.93662 + vertex -937.19 310.649 8.99184 + endloop + endfacet + facet normal -0.944962 0.0151413 -0.326831 + outer loop + vertex -937.19 310.649 8.99184 + vertex -936.783 313.309 7.93662 + vertex -936.823 310.748 7.93569 + endloop + endfacet + facet normal -0.944504 -0.0039946 -0.328477 + outer loop + vertex -937.19 310.649 8.99184 + vertex -936.823 310.748 7.93569 + vertex -937.179 308.052 8.99041 + endloop + endfacet + facet normal -0.943931 -0.00470825 -0.330108 + outer loop + vertex -937.179 308.052 8.99041 + vertex -936.823 310.748 7.93569 + vertex -936.81 308.157 7.93529 + endloop + endfacet + facet normal -0.861992 -0.00426808 -0.506904 + outer loop + vertex -936.823 310.748 7.93569 + vertex -936.22 310.82 6.90974 + vertex -936.81 308.157 7.93529 + endloop + endfacet + facet normal -0.864257 -0.00228047 -0.503045 + outer loop + vertex -936.81 308.157 7.93529 + vertex -936.22 310.82 6.90974 + vertex -936.213 308.233 6.90877 + endloop + endfacet + facet normal -0.645212 0.0105721 -0.763931 + outer loop + vertex -935.346 313.385 5.92969 + vertex -934.389 313.242 5.11935 + vertex -935.386 310.829 5.92808 + endloop + endfacet + facet normal -0.621599 -0.0056815 -0.783315 + outer loop + vertex -935.386 310.829 5.92808 + vertex -934.389 313.242 5.11935 + vertex -934.189 310.9 4.97757 + endloop + endfacet + facet normal -0.759199 0.0102447 -0.650778 + outer loop + vertex -936.186 313.378 6.90934 + vertex -935.346 313.385 5.92969 + vertex -936.22 310.82 6.90974 + endloop + endfacet + facet normal -0.761815 0.0123221 -0.647677 + outer loop + vertex -936.22 310.82 6.90974 + vertex -935.346 313.385 5.92969 + vertex -935.386 310.829 5.92808 + endloop + endfacet + facet normal -0.761813 -0.00193421 -0.647794 + outer loop + vertex -936.22 310.82 6.90974 + vertex -935.386 310.829 5.92808 + vertex -936.213 308.233 6.90877 + endloop + endfacet + facet normal -0.761046 -0.0025179 -0.648693 + outer loop + vertex -936.213 308.233 6.90877 + vertex -935.386 310.829 5.92808 + vertex -935.376 308.239 5.92731 + endloop + endfacet + facet normal -0.621743 -0.00198244 -0.783219 + outer loop + vertex -935.386 310.829 5.92808 + vertex -934.189 310.9 4.97757 + vertex -935.376 308.239 5.92731 + endloop + endfacet + facet normal -0.6384 0.0103027 -0.769636 + outer loop + vertex -935.376 308.239 5.92731 + vertex -934.189 310.9 4.97757 + vertex -934.404 308.079 5.11826 + endloop + endfacet + facet normal -0.649329 0.069915 -0.757287 + outer loop + vertex -934.236 328.988 5.93015 + vertex -933.315 328.773 5.12121 + vertex -934.515 326.394 5.93018 + endloop + endfacet + facet normal -0.632188 0.0560007 -0.772789 + outer loop + vertex -934.515 326.394 5.93018 + vertex -933.315 328.773 5.12121 + vertex -933.349 326.394 4.97637 + endloop + endfacet + facet normal -0.765605 0.0852045 -0.637644 + outer loop + vertex -935.049 329.021 6.91122 + vertex -934.236 328.988 5.93015 + vertex -935.338 326.437 6.91274 + endloop + endfacet + facet normal -0.762277 0.082079 -0.642026 + outer loop + vertex -935.338 326.437 6.91274 + vertex -934.236 328.988 5.93015 + vertex -934.515 326.394 5.93018 + endloop + endfacet + facet normal -0.763007 0.0730959 -0.642244 + outer loop + vertex -935.338 326.437 6.91274 + vertex -934.515 326.394 5.93018 + vertex -935.59 323.798 6.91219 + endloop + endfacet + facet normal -0.761362 0.0716143 -0.64436 + outer loop + vertex -935.59 323.798 6.91219 + vertex -934.515 326.394 5.93018 + vertex -934.763 323.759 5.92973 + endloop + endfacet + facet normal -0.632059 0.0594924 -0.772634 + outer loop + vertex -934.515 326.394 5.93018 + vertex -933.349 326.394 4.97637 + vertex -934.763 323.759 5.92973 + endloop + endfacet + facet normal -0.645789 0.0713666 -0.760173 + outer loop + vertex -934.763 323.759 5.92973 + vertex -933.349 326.394 4.97637 + vertex -933.83 323.561 5.11922 + endloop + endfacet + facet normal -0.859673 0.0931816 -0.502274 + outer loop + vertex -935.652 328.957 7.93102 + vertex -935.049 329.021 6.91122 + vertex -935.935 326.38 7.93748 + endloop + endfacet + facet normal -0.862366 0.0961032 -0.497081 + outer loop + vertex -935.935 326.38 7.93748 + vertex -935.049 329.021 6.91122 + vertex -935.338 326.437 6.91274 + endloop + endfacet + facet normal -0.936801 0.100545 -0.335104 + outer loop + vertex -936.039 328.854 8.98319 + vertex -935.652 328.957 7.93102 + vertex -936.318 326.269 8.98654 + endloop + endfacet + facet normal -0.937879 0.102202 -0.331568 + outer loop + vertex -936.318 326.269 8.98654 + vertex -935.652 328.957 7.93102 + vertex -935.935 326.38 7.93748 + endloop + endfacet + facet normal -0.938724 0.0871271 -0.333475 + outer loop + vertex -936.318 326.269 8.98654 + vertex -935.935 326.38 7.93748 + vertex -936.564 323.647 8.99438 + endloop + endfacet + facet normal -0.939986 0.0889922 -0.329403 + outer loop + vertex -936.564 323.647 8.99438 + vertex -935.935 326.38 7.93748 + vertex -936.185 323.749 7.9412 + endloop + endfacet + facet normal -0.863145 0.081441 -0.498345 + outer loop + vertex -935.935 326.38 7.93748 + vertex -935.338 326.437 6.91274 + vertex -936.185 323.749 7.9412 + endloop + endfacet + facet normal -0.864408 0.0827616 -0.495933 + outer loop + vertex -936.185 323.749 7.9412 + vertex -935.338 326.437 6.91274 + vertex -935.59 323.798 6.91219 + endloop + endfacet + facet normal -0.864972 0.0704625 -0.496849 + outer loop + vertex -936.185 323.749 7.9412 + vertex -935.59 323.798 6.91219 + vertex -936.401 321.098 7.94072 + endloop + endfacet + facet normal -0.863153 0.068618 -0.500259 + outer loop + vertex -936.401 321.098 7.94072 + vertex -935.59 323.798 6.91219 + vertex -935.801 321.146 6.91142 + endloop + endfacet + facet normal -0.940625 0.0755446 -0.330934 + outer loop + vertex -936.564 323.647 8.99438 + vertex -936.185 323.749 7.9412 + vertex -936.778 321.005 8.99829 + endloop + endfacet + facet normal -0.94139 0.0766493 -0.328495 + outer loop + vertex -936.778 321.005 8.99829 + vertex -936.185 323.749 7.9412 + vertex -936.401 321.098 7.94072 + endloop + endfacet + facet normal -0.941975 0.0612036 -0.330058 + outer loop + vertex -936.778 321.005 8.99829 + vertex -936.401 321.098 7.94072 + vertex -936.948 318.376 8.99759 + endloop + endfacet + facet normal -0.94239 0.0617904 -0.328761 + outer loop + vertex -936.948 318.376 8.99759 + vertex -936.401 321.098 7.94072 + vertex -936.573 318.465 7.93878 + endloop + endfacet + facet normal -0.863554 0.0567684 -0.50105 + outer loop + vertex -936.401 321.098 7.94072 + vertex -935.801 321.146 6.91142 + vertex -936.573 318.465 7.93878 + endloop + endfacet + facet normal -0.865418 0.0586235 -0.49761 + outer loop + vertex -936.573 318.465 7.93878 + vertex -935.801 321.146 6.91142 + vertex -935.978 318.52 6.90945 + endloop + endfacet + facet normal -0.649125 0.0507939 -0.758984 + outer loop + vertex -934.763 323.759 5.92973 + vertex -933.83 323.561 5.11922 + vertex -934.97 321.121 5.93021 + endloop + endfacet + facet normal -0.630019 0.0363069 -0.775731 + outer loop + vertex -934.97 321.121 5.93021 + vertex -933.83 323.561 5.11922 + vertex -933.793 321.171 4.97667 + endloop + endfacet + facet normal -0.762136 0.0606466 -0.64457 + outer loop + vertex -935.59 323.798 6.91219 + vertex -934.763 323.759 5.92973 + vertex -935.801 321.146 6.91142 + endloop + endfacet + facet normal -0.760919 0.0595859 -0.646106 + outer loop + vertex -935.801 321.146 6.91142 + vertex -934.763 323.759 5.92973 + vertex -934.97 321.121 5.93021 + endloop + endfacet + facet normal -0.761353 0.0517308 -0.646271 + outer loop + vertex -935.801 321.146 6.91142 + vertex -934.97 321.121 5.93021 + vertex -935.978 318.52 6.90945 + endloop + endfacet + facet normal -0.75898 0.0497029 -0.649214 + outer loop + vertex -935.978 318.52 6.90945 + vertex -934.97 321.121 5.93021 + vertex -935.14 318.509 5.92901 + endloop + endfacet + facet normal -0.630024 0.0413672 -0.775473 + outer loop + vertex -934.97 321.121 5.93021 + vertex -933.793 321.171 4.97667 + vertex -935.14 318.509 5.92901 + endloop + endfacet + facet normal -0.64266 0.051721 -0.764403 + outer loop + vertex -935.14 318.509 5.92901 + vertex -933.793 321.171 4.97667 + vertex -934.191 318.354 5.12058 + endloop + endfacet + facet normal -0.654605 0.107351 -0.74831 + outer loop + vertex -932.825 338.948 5.93619 + vertex -931.932 338.773 5.12966 + vertex -933.225 336.464 5.93008 + endloop + endfacet + facet normal -0.633399 0.0883764 -0.768762 + outer loop + vertex -933.225 336.464 5.93008 + vertex -931.932 338.773 5.12966 + vertex -932.072 336.5 4.98385 + endloop + endfacet + facet normal -0.759647 0.12274 -0.638648 + outer loop + vertex -933.64 338.957 6.90695 + vertex -932.825 338.948 5.93619 + vertex -934.04 336.471 6.90497 + endloop + endfacet + facet normal -0.761096 0.124241 -0.636629 + outer loop + vertex -934.04 336.471 6.90497 + vertex -932.825 338.948 5.93619 + vertex -933.225 336.464 5.93008 + endloop + endfacet + facet normal -0.762134 0.113355 -0.637419 + outer loop + vertex -934.04 336.471 6.90497 + vertex -933.225 336.464 5.93008 + vertex -934.404 334.012 6.90348 + endloop + endfacet + facet normal -0.760174 0.111345 -0.640107 + outer loop + vertex -934.404 334.012 6.90348 + vertex -933.225 336.464 5.93008 + vertex -933.586 334 5.92947 + endloop + endfacet + facet normal -0.633225 0.0928091 -0.768383 + outer loop + vertex -933.225 336.464 5.93008 + vertex -932.072 336.5 4.98385 + vertex -933.586 334 5.92947 + endloop + endfacet + facet normal -0.649232 0.108386 -0.752828 + outer loop + vertex -933.586 334 5.92947 + vertex -932.072 336.5 4.98385 + vertex -932.681 333.816 5.12236 + endloop + endfacet + facet normal -0.857756 0.139924 -0.494647 + outer loop + vertex -934.24 338.914 7.93515 + vertex -933.64 338.957 6.90695 + vertex -934.646 336.419 7.93369 + endloop + endfacet + facet normal -0.856351 0.138188 -0.497561 + outer loop + vertex -934.646 336.419 7.93369 + vertex -933.64 338.957 6.90695 + vertex -934.04 336.471 6.90497 + endloop + endfacet + facet normal -0.935952 0.15223 -0.317521 + outer loop + vertex -934.61 338.919 9.02827 + vertex -934.24 338.914 7.93515 + vertex -935.017 336.408 9.02355 + endloop + endfacet + facet normal -0.936126 0.152578 -0.316842 + outer loop + vertex -935.017 336.408 9.02355 + vertex -934.24 338.914 7.93515 + vertex -934.646 336.419 7.93369 + endloop + endfacet + facet normal -0.937485 0.142758 -0.3174 + outer loop + vertex -935.017 336.408 9.02355 + vertex -934.646 336.419 7.93369 + vertex -935.391 333.916 9.00696 + endloop + endfacet + facet normal -0.935404 0.138794 -0.325202 + outer loop + vertex -935.391 333.916 9.00696 + vertex -934.646 336.419 7.93369 + vertex -935.01 333.951 7.92756 + endloop + endfacet + facet normal -0.85733 0.127708 -0.498674 + outer loop + vertex -934.646 336.419 7.93369 + vertex -934.04 336.471 6.90497 + vertex -935.01 333.951 7.92756 + endloop + endfacet + facet normal -0.857022 0.127336 -0.499299 + outer loop + vertex -935.01 333.951 7.92756 + vertex -934.04 336.471 6.90497 + vertex -934.404 334.012 6.90348 + endloop + endfacet + facet normal -0.857953 0.115617 -0.500549 + outer loop + vertex -935.01 333.951 7.92756 + vertex -934.404 334.012 6.90348 + vertex -935.343 331.474 7.92649 + endloop + endfacet + facet normal -0.858052 0.115733 -0.500352 + outer loop + vertex -935.343 331.474 7.92649 + vertex -934.404 334.012 6.90348 + vertex -934.739 331.541 6.90657 + endloop + endfacet + facet normal -0.936795 0.126826 -0.326083 + outer loop + vertex -935.391 333.916 9.00696 + vertex -935.01 333.951 7.92756 + vertex -935.726 331.403 8.99257 + endloop + endfacet + facet normal -0.936379 0.126091 -0.32756 + outer loop + vertex -935.726 331.403 8.99257 + vertex -935.01 333.951 7.92756 + vertex -935.343 331.474 7.92649 + endloop + endfacet + facet normal -0.937277 0.116586 -0.328512 + outer loop + vertex -935.726 331.403 8.99257 + vertex -935.343 331.474 7.92649 + vertex -936.039 328.854 8.98319 + endloop + endfacet + facet normal -0.935835 0.114226 -0.333414 + outer loop + vertex -936.039 328.854 8.98319 + vertex -935.343 331.474 7.92649 + vertex -935.652 328.957 7.93102 + endloop + endfacet + facet normal -0.858803 0.104472 -0.50154 + outer loop + vertex -935.343 331.474 7.92649 + vertex -934.739 331.541 6.90657 + vertex -935.652 328.957 7.93102 + endloop + endfacet + facet normal -0.859002 0.104696 -0.501152 + outer loop + vertex -935.652 328.957 7.93102 + vertex -934.739 331.541 6.90657 + vertex -935.049 329.021 6.91122 + endloop + endfacet + facet normal -0.652714 0.0891456 -0.752342 + outer loop + vertex -933.586 334 5.92947 + vertex -932.681 333.816 5.12236 + vertex -933.925 331.52 5.92973 + endloop + endfacet + facet normal -0.633953 0.0727923 -0.769938 + outer loop + vertex -933.925 331.52 5.92973 + vertex -932.681 333.816 5.12236 + vertex -932.769 331.523 4.97817 + endloop + endfacet + facet normal -0.760965 0.102392 -0.640662 + outer loop + vertex -934.404 334.012 6.90348 + vertex -933.586 334 5.92947 + vertex -934.739 331.541 6.90657 + endloop + endfacet + facet normal -0.762761 0.104201 -0.63823 + outer loop + vertex -934.739 331.541 6.90657 + vertex -933.586 334 5.92947 + vertex -933.925 331.52 5.92973 + endloop + endfacet + facet normal -0.763756 0.0927302 -0.63881 + outer loop + vertex -934.739 331.541 6.90657 + vertex -933.925 331.52 5.92973 + vertex -935.049 329.021 6.91122 + endloop + endfacet + facet normal -0.764868 0.0938168 -0.637319 + outer loop + vertex -935.049 329.021 6.91122 + vertex -933.925 331.52 5.92973 + vertex -934.236 328.988 5.93015 + endloop + endfacet + facet normal -0.633726 0.0776911 -0.769647 + outer loop + vertex -933.925 331.52 5.92973 + vertex -932.769 331.523 4.97817 + vertex -934.236 328.988 5.93015 + endloop + endfacet + facet normal -0.645792 0.0889312 -0.758316 + outer loop + vertex -934.236 328.988 5.93015 + vertex -932.769 331.523 4.97817 + vertex -933.315 328.773 5.12121 + endloop + endfacet + facet normal -0.656376 0.133375 -0.742551 + outer loop + vertex -930.873 349.227 5.88867 + vertex -930.021 348.97 5.08977 + vertex -931.401 346.64 5.89116 + endloop + endfacet + facet normal -0.632266 0.110756 -0.766794 + outer loop + vertex -931.401 346.64 5.89116 + vertex -930.021 348.97 5.08977 + vertex -930.295 346.608 4.97481 + endloop + endfacet + facet normal -0.773541 0.17072 -0.610318 + outer loop + vertex -931.701 349.29 6.95626 + vertex -930.873 349.227 5.88867 + vertex -932.194 346.696 6.85553 + endloop + endfacet + facet normal -0.758745 0.154393 -0.632827 + outer loop + vertex -932.194 346.696 6.85553 + vertex -930.873 349.227 5.88867 + vertex -931.401 346.64 5.89116 + endloop + endfacet + facet normal -0.759861 0.146779 -0.633299 + outer loop + vertex -932.194 346.696 6.85553 + vertex -931.401 346.64 5.89116 + vertex -932.71 344.082 6.86837 + endloop + endfacet + facet normal -0.755351 0.142008 -0.639749 + outer loop + vertex -932.71 344.082 6.86837 + vertex -931.401 346.64 5.89116 + vertex -931.915 344.043 5.9211 + endloop + endfacet + facet normal -0.631785 0.116111 -0.766398 + outer loop + vertex -931.401 346.64 5.89116 + vertex -930.295 346.608 4.97481 + vertex -931.915 344.043 5.9211 + endloop + endfacet + facet normal -0.649642 0.134048 -0.748329 + outer loop + vertex -931.915 344.043 5.9211 + vertex -930.295 346.608 4.97481 + vertex -931.048 343.836 5.13212 + endloop + endfacet + facet normal -0.865814 0.195086 -0.460769 + outer loop + vertex -932.405 349.018 8.16475 + vertex -931.701 349.29 6.95626 + vertex -932.812 346.648 7.92551 + endloop + endfacet + facet normal -0.855048 0.181375 -0.485794 + outer loop + vertex -932.812 346.648 7.92551 + vertex -931.701 349.29 6.95626 + vertex -932.194 346.696 6.85553 + endloop + endfacet + facet normal -0.934129 0.199616 -0.295898 + outer loop + vertex -932.855 348.518 9.24716 + vertex -932.405 349.018 8.16475 + vertex -933.212 346.575 9.0621 + endloop + endfacet + facet normal -0.929747 0.191301 -0.314601 + outer loop + vertex -933.212 346.575 9.0621 + vertex -932.405 349.018 8.16475 + vertex -932.812 346.648 7.92551 + endloop + endfacet + facet normal -0.931341 0.1813 -0.315808 + outer loop + vertex -933.212 346.575 9.0621 + vertex -932.812 346.648 7.92551 + vertex -933.673 344.096 9.0007 + endloop + endfacet + facet normal -0.93078 0.180138 -0.318119 + outer loop + vertex -933.673 344.096 9.0007 + vertex -932.812 346.648 7.92551 + vertex -933.3 344.068 7.89215 + endloop + endfacet + facet normal -0.856804 0.168336 -0.48739 + outer loop + vertex -932.812 346.648 7.92551 + vertex -932.194 346.696 6.85553 + vertex -933.3 344.068 7.89215 + endloop + endfacet + facet normal -0.855209 0.166287 -0.490884 + outer loop + vertex -933.3 344.068 7.89215 + vertex -932.194 346.696 6.85553 + vertex -932.71 344.082 6.86837 + endloop + endfacet + facet normal -0.856528 0.156575 -0.491776 + outer loop + vertex -933.3 344.068 7.89215 + vertex -932.71 344.082 6.86837 + vertex -933.79 341.465 7.91749 + endloop + endfacet + facet normal -0.855108 0.154773 -0.494808 + outer loop + vertex -933.79 341.465 7.91749 + vertex -932.71 344.082 6.86837 + vertex -933.195 341.493 6.89739 + endloop + endfacet + facet normal -0.932223 0.171984 -0.318404 + outer loop + vertex -933.673 344.096 9.0007 + vertex -933.3 344.068 7.89215 + vertex -934.158 341.492 9.01185 + endloop + endfacet + facet normal -0.93251 0.172588 -0.317235 + outer loop + vertex -934.158 341.492 9.01185 + vertex -933.3 344.068 7.89215 + vertex -933.79 341.465 7.91749 + endloop + endfacet + facet normal -0.934267 0.162153 -0.317571 + outer loop + vertex -934.158 341.492 9.01185 + vertex -933.79 341.465 7.91749 + vertex -934.61 338.919 9.02827 + endloop + endfacet + facet normal -0.9344 0.162427 -0.31704 + outer loop + vertex -934.61 338.919 9.02827 + vertex -933.79 341.465 7.91749 + vertex -934.24 338.914 7.93515 + endloop + endfacet + facet normal -0.855998 0.147378 -0.495527 + outer loop + vertex -933.79 341.465 7.91749 + vertex -933.195 341.493 6.89739 + vertex -934.24 338.914 7.93515 + endloop + endfacet + facet normal -0.856837 0.14843 -0.49376 + outer loop + vertex -934.24 338.914 7.93515 + vertex -933.195 341.493 6.89739 + vertex -933.64 338.957 6.90695 + endloop + endfacet + facet normal -0.653393 0.116836 -0.747948 + outer loop + vertex -931.915 344.043 5.9211 + vertex -931.048 343.836 5.13212 + vertex -932.392 341.474 5.93645 + endloop + endfacet + facet normal -0.637923 0.102848 -0.763202 + outer loop + vertex -932.392 341.474 5.93645 + vertex -931.048 343.836 5.13212 + vertex -931.258 341.5 4.99242 + endloop + endfacet + facet normal -0.756295 0.134617 -0.640232 + outer loop + vertex -932.71 344.082 6.86837 + vertex -931.915 344.043 5.9211 + vertex -933.195 341.493 6.89739 + endloop + endfacet + facet normal -0.758618 0.137035 -0.636962 + outer loop + vertex -933.195 341.493 6.89739 + vertex -931.915 344.043 5.9211 + vertex -932.392 341.474 5.93645 + endloop + endfacet + facet normal -0.759327 0.130785 -0.637431 + outer loop + vertex -933.195 341.493 6.89739 + vertex -932.392 341.474 5.93645 + vertex -933.64 338.957 6.90695 + endloop + endfacet + facet normal -0.758871 0.130313 -0.63807 + outer loop + vertex -933.64 338.957 6.90695 + vertex -932.392 341.474 5.93645 + vertex -932.825 338.948 5.93619 + endloop + endfacet + facet normal -0.637559 0.109504 -0.762579 + outer loop + vertex -932.392 341.474 5.93645 + vertex -931.258 341.5 4.99242 + vertex -932.825 338.948 5.93619 + endloop + endfacet + facet normal -0.651608 0.12335 -0.74846 + outer loop + vertex -932.825 338.948 5.93619 + vertex -931.258 341.5 4.99242 + vertex -931.932 338.773 5.12966 + endloop + endfacet + facet normal -0.697726 0.171221 -0.695602 + outer loop + vertex -928.62 359.366 6.01034 + vertex -927.821 358.831 5.07727 + vertex -929.231 356.87 6.00839 + endloop + endfacet + facet normal -0.676079 0.14271 -0.722877 + outer loop + vertex -929.231 356.87 6.00839 + vertex -927.821 358.831 5.07727 + vertex -928.157 356.578 4.94647 + endloop + endfacet + facet normal -0.809615 0.198147 -0.552504 + outer loop + vertex -929.331 359.99 7.27505 + vertex -928.62 359.366 6.01034 + vertex -929.917 357.527 7.25067 + endloop + endfacet + facet normal -0.809782 0.19852 -0.552126 + outer loop + vertex -929.917 357.527 7.25067 + vertex -928.62 359.366 6.01034 + vertex -929.231 356.87 6.00839 + endloop + endfacet + facet normal -0.812791 0.191619 -0.550139 + outer loop + vertex -929.917 357.527 7.25067 + vertex -929.231 356.87 6.00839 + vertex -930.512 355.031 7.26083 + endloop + endfacet + facet normal -0.810516 0.186588 -0.555201 + outer loop + vertex -930.512 355.031 7.26083 + vertex -929.231 356.87 6.00839 + vertex -929.811 354.377 6.01655 + endloop + endfacet + facet normal -0.673256 0.154132 -0.723166 + outer loop + vertex -929.231 356.87 6.00839 + vertex -928.157 356.578 4.94647 + vertex -929.811 354.377 6.01655 + endloop + endfacet + facet normal -0.685752 0.171171 -0.707421 + outer loop + vertex -929.811 354.377 6.01655 + vertex -928.157 356.578 4.94647 + vertex -928.957 353.976 5.09234 + endloop + endfacet + facet normal -0.898999 0.217711 -0.380003 + outer loop + vertex -929.331 359.99 7.27505 + vertex -929.917 357.527 7.25067 + vertex -930.318 358.327 8.65684 + endloop + endfacet + facet normal -0.898495 0.218879 -0.380523 + outer loop + vertex -930.318 358.327 8.65684 + vertex -929.917 357.527 7.25067 + vertex -930.898 355.924 8.64417 + endloop + endfacet + facet normal -0.897209 0.212508 -0.387112 + outer loop + vertex -931.522 353.363 8.68455 + vertex -930.898 355.924 8.64417 + vertex -930.512 355.031 7.26083 + endloop + endfacet + facet normal -0.897247 0.212426 -0.387069 + outer loop + vertex -930.512 355.031 7.26083 + vertex -930.898 355.924 8.64417 + vertex -929.917 357.527 7.25067 + endloop + endfacet + facet normal -0.900909 0.242872 -0.359688 + outer loop + vertex -932.239 350.726 8.90017 + vertex -931.274 352.005 7.34821 + vertex -932.405 349.018 8.16475 + endloop + endfacet + facet normal -0.933059 0.215232 -0.288228 + outer loop + vertex -932.855 348.518 9.24716 + vertex -932.239 350.726 8.90017 + vertex -932.405 349.018 8.16475 + endloop + endfacet + facet normal -0.865211 0.202253 -0.458808 + outer loop + vertex -931.701 349.29 6.95626 + vertex -932.405 349.018 8.16475 + vertex -931.274 352.005 7.34821 + endloop + endfacet + facet normal -0.897696 0.214898 -0.384658 + outer loop + vertex -930.512 355.031 7.26083 + vertex -931.274 352.005 7.34821 + vertex -931.522 353.363 8.68455 + endloop + endfacet + facet normal -0.898849 0.213047 -0.38299 + outer loop + vertex -931.522 353.363 8.68455 + vertex -931.274 352.005 7.34821 + vertex -932.239 350.726 8.90017 + endloop + endfacet + facet normal -0.689096 0.161698 -0.7064 + outer loop + vertex -929.811 354.377 6.01655 + vertex -928.957 353.976 5.09234 + vertex -930.359 351.801 5.96183 + endloop + endfacet + facet normal -0.65914 0.128584 -0.740946 + outer loop + vertex -930.359 351.801 5.96183 + vertex -928.957 353.976 5.09234 + vertex -929.24 351.684 4.94605 + endloop + endfacet + facet normal -0.809967 0.187876 -0.555568 + outer loop + vertex -930.512 355.031 7.26083 + vertex -929.811 354.377 6.01655 + vertex -931.274 352.005 7.34821 + endloop + endfacet + facet normal -0.807673 0.183837 -0.56024 + outer loop + vertex -931.274 352.005 7.34821 + vertex -929.811 354.377 6.01655 + vertex -930.359 351.801 5.96183 + endloop + endfacet + facet normal -0.8022 0.206959 -0.560038 + outer loop + vertex -931.274 352.005 7.34821 + vertex -930.359 351.801 5.96183 + vertex -931.701 349.29 6.95626 + endloop + endfacet + facet normal -0.773384 0.171669 -0.610252 + outer loop + vertex -931.701 349.29 6.95626 + vertex -930.359 351.801 5.96183 + vertex -930.873 349.227 5.88867 + endloop + endfacet + facet normal -0.655586 0.151843 -0.739697 + outer loop + vertex -930.359 351.801 5.96183 + vertex -929.24 351.684 4.94605 + vertex -930.873 349.227 5.88867 + endloop + endfacet + facet normal -0.652429 0.148411 -0.743176 + outer loop + vertex -930.873 349.227 5.88867 + vertex -929.24 351.684 4.94605 + vertex -930.021 348.97 5.08977 + endloop + endfacet + facet normal -0.688174 0.200582 -0.697268 + outer loop + vertex -925.795 365.496 4.88392 + vertex -927.143 365.474 6.20744 + vertex -924.754 369.694 5.06398 + endloop + endfacet + facet normal -0.805882 0.242072 -0.540328 + outer loop + vertex -928.106 365.152 7.50038 + vertex -926.443 369.176 6.82217 + vertex -927.143 365.474 6.20744 + endloop + endfacet + facet normal -0.734326 0.244007 -0.633424 + outer loop + vertex -926.443 369.176 6.82217 + vertex -924.754 369.694 5.06398 + vertex -927.143 365.474 6.20744 + endloop + endfacet + facet normal -0.900385 0.255686 -0.352039 + outer loop + vertex -929.117 363.262 8.71335 + vertex -928.217 366.322 8.63224 + vertex -928.106 365.152 7.50038 + endloop + endfacet + facet normal -0.861752 0.258848 -0.436328 + outer loop + vertex -927.045 370.166 8.59915 + vertex -926.443 369.176 6.82217 + vertex -928.217 366.322 8.63224 + endloop + endfacet + facet normal -0.872373 0.294915 -0.38986 + outer loop + vertex -926.443 369.176 6.82217 + vertex -928.106 365.152 7.50038 + vertex -928.217 366.322 8.63224 + endloop + endfacet + facet normal -0.89472 0.234725 -0.379975 + outer loop + vertex -928.106 365.152 7.50038 + vertex -928.71 362.61 7.35149 + vertex -929.117 363.262 8.71335 + endloop + endfacet + facet normal -0.898185 0.226222 -0.376944 + outer loop + vertex -929.117 363.262 8.71335 + vertex -928.71 362.61 7.35149 + vertex -929.743 360.726 8.6837 + endloop + endfacet + facet normal -0.899349 0.219432 -0.378182 + outer loop + vertex -930.318 358.327 8.65684 + vertex -929.743 360.726 8.6837 + vertex -929.331 359.99 7.27505 + endloop + endfacet + facet normal -0.897546 0.223767 -0.37992 + outer loop + vertex -929.331 359.99 7.27505 + vertex -929.743 360.726 8.6837 + vertex -928.71 362.61 7.35149 + endloop + endfacet + facet normal -0.688741 0.196343 -0.697915 + outer loop + vertex -927.143 365.474 6.20744 + vertex -925.795 365.496 4.88392 + vertex -927.89 362.221 6.02993 + endloop + endfacet + facet normal -0.678205 0.184947 -0.711219 + outer loop + vertex -927.89 362.221 6.02993 + vertex -925.795 365.496 4.88392 + vertex -926.818 361.722 4.87788 + endloop + endfacet + facet normal -0.807357 0.223708 -0.546013 + outer loop + vertex -928.106 365.152 7.50038 + vertex -927.143 365.474 6.20744 + vertex -928.71 362.61 7.35149 + endloop + endfacet + facet normal -0.800466 0.214473 -0.559692 + outer loop + vertex -928.71 362.61 7.35149 + vertex -927.143 365.474 6.20744 + vertex -927.89 362.221 6.02993 + endloop + endfacet + facet normal -0.803039 0.206594 -0.55897 + outer loop + vertex -928.71 362.61 7.35149 + vertex -927.89 362.221 6.02993 + vertex -929.331 359.99 7.27505 + endloop + endfacet + facet normal -0.804708 0.209653 -0.555419 + outer loop + vertex -929.331 359.99 7.27505 + vertex -927.89 362.221 6.02993 + vertex -928.62 359.366 6.01034 + endloop + endfacet + facet normal -0.680405 0.178922 -0.710658 + outer loop + vertex -927.89 362.221 6.02993 + vertex -926.818 361.722 4.87788 + vertex -928.62 359.366 6.01034 + endloop + endfacet + facet normal -0.68888 0.190866 -0.699296 + outer loop + vertex -928.62 359.366 6.01034 + vertex -926.818 361.722 4.87788 + vertex -927.821 358.831 5.07727 + endloop + endfacet + facet normal -0.766552 0.24449 -0.59382 + outer loop + vertex -923.376 379.399 6.99619 + vertex -922.012 379.507 5.27955 + vertex -924.894 374.411 6.90139 + endloop + endfacet + facet normal -0.749874 0.226181 -0.621717 + outer loop + vertex -924.894 374.411 6.90139 + vertex -922.012 379.507 5.27955 + vertex -923.501 374.432 5.22967 + endloop + endfacet + facet normal -0.885549 0.29195 -0.361341 + outer loop + vertex -924.24 379.279 9.0169 + vertex -923.376 379.399 6.99619 + vertex -925.732 374.502 8.81418 + endloop + endfacet + facet normal -0.875899 0.274018 -0.397134 + outer loop + vertex -925.732 374.502 8.81418 + vertex -923.376 379.399 6.99619 + vertex -924.894 374.411 6.90139 + endloop + endfacet + facet normal -0.873072 0.283966 -0.39637 + outer loop + vertex -925.732 374.502 8.81418 + vertex -924.894 374.411 6.90139 + vertex -927.045 370.166 8.59915 + endloop + endfacet + facet normal -0.860548 0.261261 -0.437265 + outer loop + vertex -927.045 370.166 8.59915 + vertex -924.894 374.411 6.90139 + vertex -926.443 369.176 6.82217 + endloop + endfacet + facet normal -0.749028 0.23104 -0.620949 + outer loop + vertex -924.894 374.411 6.90139 + vertex -923.501 374.432 5.22967 + vertex -926.443 369.176 6.82217 + endloop + endfacet + facet normal -0.735183 0.216839 -0.642252 + outer loop + vertex -926.443 369.176 6.82217 + vertex -923.501 374.432 5.22967 + vertex -924.754 369.694 5.06398 + endloop + endfacet + facet normal -0.780652 0.262708 -0.56707 + outer loop + vertex -920.121 389.344 7.03957 + vertex -918.798 389.476 5.27972 + vertex -921.784 384.403 7.03949 + endloop + endfacet + facet normal -0.773483 0.253719 -0.58082 + outer loop + vertex -921.784 384.403 7.03949 + vertex -918.798 389.476 5.27972 + vertex -920.427 384.542 5.29369 + endloop + endfacet + facet normal -0.890287 0.299584 -0.342986 + outer loop + vertex -920.923 389.282 9.06588 + vertex -920.121 389.344 7.03957 + vertex -922.584 384.348 9.06962 + endloop + endfacet + facet normal -0.890293 0.2996 -0.342954 + outer loop + vertex -922.584 384.348 9.06962 + vertex -920.121 389.344 7.03957 + vertex -921.784 384.403 7.03949 + endloop + endfacet + facet normal -0.891626 0.294847 -0.34361 + outer loop + vertex -922.584 384.348 9.06962 + vertex -921.784 384.403 7.03949 + vertex -924.24 379.279 9.0169 + endloop + endfacet + facet normal -0.887214 0.285466 -0.362438 + outer loop + vertex -924.24 379.279 9.0169 + vertex -921.784 384.403 7.03949 + vertex -923.376 379.399 6.99619 + endloop + endfacet + facet normal -0.77389 0.251298 -0.581329 + outer loop + vertex -921.784 384.403 7.03949 + vertex -920.427 384.542 5.29369 + vertex -923.376 379.399 6.99619 + endloop + endfacet + facet normal -0.7668 0.243 -0.594111 + outer loop + vertex -923.376 379.399 6.99619 + vertex -920.427 384.542 5.29369 + vertex -922.012 379.507 5.27955 + endloop + endfacet + facet normal -0.784537 0.283689 -0.551383 + outer loop + vertex -916.686 398.96 7.01444 + vertex -915.403 399.098 5.26034 + vertex -918.423 394.176 7.02543 + endloop + endfacet + facet normal -0.781742 0.27986 -0.557277 + outer loop + vertex -918.423 394.176 7.02543 + vertex -915.403 399.098 5.26034 + vertex -917.121 394.31 5.26665 + endloop + endfacet + facet normal -0.886432 0.323737 -0.330805 + outer loop + vertex -917.475 398.874 9.04564 + vertex -916.686 398.96 7.01444 + vertex -919.223 394.095 9.05283 + endloop + endfacet + facet normal -0.885364 0.320805 -0.336473 + outer loop + vertex -919.223 394.095 9.05283 + vertex -916.686 398.96 7.01444 + vertex -918.423 394.176 7.02543 + endloop + endfacet + facet normal -0.887809 0.312588 -0.337764 + outer loop + vertex -919.223 394.095 9.05283 + vertex -918.423 394.176 7.02543 + vertex -920.923 389.282 9.06588 + endloop + endfacet + facet normal -0.887086 0.310713 -0.341375 + outer loop + vertex -920.923 389.282 9.06588 + vertex -918.423 394.176 7.02543 + vertex -920.121 389.344 7.03957 + endloop + endfacet + facet normal -0.782987 0.273498 -0.558686 + outer loop + vertex -918.423 394.176 7.02543 + vertex -917.121 394.31 5.26665 + vertex -920.121 389.344 7.03957 + endloop + endfacet + facet normal -0.779509 0.268876 -0.565749 + outer loop + vertex -920.121 389.344 7.03957 + vertex -917.121 394.31 5.26665 + vertex -918.798 389.476 5.27972 + endloop + endfacet + facet normal -0.792163 0.306285 -0.527889 + outer loop + vertex -913.005 408.619 7.01357 + vertex -911.789 408.746 5.26253 + vertex -914.88 403.767 7.01298 + endloop + endfacet + facet normal -0.78782 0.300083 -0.537857 + outer loop + vertex -914.88 403.767 7.01298 + vertex -911.789 408.746 5.26253 + vertex -913.631 403.901 5.25775 + endloop + endfacet + facet normal -0.884465 0.34301 -0.316332 + outer loop + vertex -913.764 408.531 9.04026 + vertex -913.005 408.619 7.01357 + vertex -915.645 403.683 9.04417 + endloop + endfacet + facet normal -0.884059 0.341783 -0.318787 + outer loop + vertex -915.645 403.683 9.04417 + vertex -913.005 408.619 7.01357 + vertex -914.88 403.767 7.01298 + endloop + endfacet + facet normal -0.885638 0.336915 -0.319583 + outer loop + vertex -915.645 403.683 9.04417 + vertex -914.88 403.767 7.01298 + vertex -917.475 398.874 9.04564 + endloop + endfacet + facet normal -0.883909 0.331888 -0.329476 + outer loop + vertex -917.475 398.874 9.04564 + vertex -914.88 403.767 7.01298 + vertex -916.686 398.96 7.01444 + endloop + endfacet + facet normal -0.788702 0.296066 -0.53879 + outer loop + vertex -914.88 403.767 7.01298 + vertex -913.631 403.901 5.25775 + vertex -916.686 398.96 7.01444 + endloop + endfacet + facet normal -0.783494 0.288781 -0.550221 + outer loop + vertex -916.686 398.96 7.01444 + vertex -913.631 403.901 5.25775 + vertex -915.403 399.098 5.26034 + endloop + endfacet + facet normal -0.802271 0.324374 -0.501141 + outer loop + vertex -909.123 418.311 7.01203 + vertex -907.983 418.423 5.25928 + vertex -911.076 413.485 7.01483 + endloop + endfacet + facet normal -0.797199 0.316614 -0.514033 + outer loop + vertex -911.076 413.485 7.01483 + vertex -907.983 418.423 5.25928 + vertex -909.898 413.606 5.26251 + endloop + endfacet + facet normal -0.883221 0.360611 -0.299802 + outer loop + vertex -909.845 418.224 9.03588 + vertex -909.123 418.311 7.01203 + vertex -911.817 413.396 9.03802 + endloop + endfacet + facet normal -0.882098 0.356791 -0.307576 + outer loop + vertex -911.817 413.396 9.03802 + vertex -909.123 418.311 7.01203 + vertex -911.076 413.485 7.01483 + endloop + endfacet + facet normal -0.883319 0.353233 -0.30818 + outer loop + vertex -911.817 413.396 9.03802 + vertex -911.076 413.485 7.01483 + vertex -913.764 408.531 9.04026 + endloop + endfacet + facet normal -0.882221 0.349768 -0.315198 + outer loop + vertex -913.764 408.531 9.04026 + vertex -911.076 413.485 7.01483 + vertex -913.005 408.619 7.01357 + endloop + endfacet + facet normal -0.79731 0.316163 -0.514138 + outer loop + vertex -911.076 413.485 7.01483 + vertex -909.898 413.606 5.26251 + vertex -913.005 408.619 7.01357 + endloop + endfacet + facet normal -0.79176 0.308019 -0.527484 + outer loop + vertex -913.005 408.619 7.01357 + vertex -909.898 413.606 5.26251 + vertex -911.789 408.746 5.26253 + endloop + endfacet + facet normal -0.808739 0.33998 -0.479953 + outer loop + vertex -905.198 427.716 7.01194 + vertex -904.127 427.798 5.26432 + vertex -907.16 423.052 7.01279 + endloop + endfacet + facet normal -0.805166 0.333968 -0.490075 + outer loop + vertex -907.16 423.052 7.01279 + vertex -904.127 427.798 5.26432 + vertex -906.054 423.149 5.26305 + endloop + endfacet + facet normal -0.882918 0.37667 -0.280315 + outer loop + vertex -905.872 427.645 9.04031 + vertex -905.198 427.716 7.01194 + vertex -907.864 422.974 9.03634 + endloop + endfacet + facet normal -0.881485 0.370603 -0.29264 + outer loop + vertex -907.864 422.974 9.03634 + vertex -905.198 427.716 7.01194 + vertex -907.16 423.052 7.01279 + endloop + endfacet + facet normal -0.882389 0.368118 -0.29305 + outer loop + vertex -907.864 422.974 9.03634 + vertex -907.16 423.052 7.01279 + vertex -909.845 418.224 9.03588 + endloop + endfacet + facet normal -0.881605 0.365175 -0.29903 + outer loop + vertex -909.845 418.224 9.03588 + vertex -907.16 423.052 7.01279 + vertex -909.123 418.311 7.01203 + endloop + endfacet + facet normal -0.80527 0.333591 -0.490161 + outer loop + vertex -907.16 423.052 7.01279 + vertex -906.054 423.149 5.26305 + vertex -909.123 418.311 7.01203 + endloop + endfacet + facet normal -0.801464 0.327469 -0.500419 + outer loop + vertex -909.123 418.311 7.01203 + vertex -906.054 423.149 5.26305 + vertex -907.983 418.423 5.25928 + endloop + endfacet + facet normal -0.819676 0.354949 -0.449602 + outer loop + vertex -901.183 437.043 7.0189 + vertex -900.193 437.112 5.26872 + vertex -903.209 432.36 7.01632 + endloop + endfacet + facet normal -0.815337 0.347126 -0.463389 + outer loop + vertex -903.209 432.36 7.01632 + vertex -900.193 437.112 5.26872 + vertex -902.182 432.433 5.26278 + endloop + endfacet + facet normal -0.882792 0.38432 -0.270142 + outer loop + vertex -901.84 436.95 9.03252 + vertex -901.183 437.043 7.0189 + vertex -903.872 432.285 9.03904 + endloop + endfacet + facet normal -0.8823 0.381952 -0.275063 + outer loop + vertex -903.872 432.285 9.03904 + vertex -901.183 437.043 7.0189 + vertex -903.209 432.36 7.01632 + endloop + endfacet + facet normal -0.882863 0.380477 -0.275302 + outer loop + vertex -903.872 432.285 9.03904 + vertex -903.209 432.36 7.01632 + vertex -905.872 427.645 9.04031 + endloop + endfacet + facet normal -0.882362 0.378143 -0.280079 + outer loop + vertex -905.872 427.645 9.04031 + vertex -903.209 432.36 7.01632 + vertex -905.198 427.716 7.01194 + endloop + endfacet + facet normal -0.814671 0.349326 -0.462907 + outer loop + vertex -903.209 432.36 7.01632 + vertex -902.182 432.433 5.26278 + vertex -905.198 427.716 7.01194 + endloop + endfacet + facet normal -0.80894 0.339283 -0.480108 + outer loop + vertex -905.198 427.716 7.01194 + vertex -902.182 432.433 5.26278 + vertex -904.127 427.798 5.26432 + endloop + endfacet + facet normal -0.828725 0.365995 -0.423394 + outer loop + vertex -897.002 446.553 7.00306 + vertex -896.089 446.608 5.26501 + vertex -899.113 441.782 7.01239 + endloop + endfacet + facet normal -0.824282 0.357568 -0.43898 + outer loop + vertex -899.113 441.782 7.01239 + vertex -896.089 446.608 5.26501 + vertex -898.159 441.848 5.2733 + endloop + endfacet + facet normal -0.884095 0.394503 -0.250485 + outer loop + vertex -897.612 446.467 9.02082 + vertex -897.002 446.553 7.00306 + vertex -899.748 441.679 9.02213 + endloop + endfacet + facet normal -0.883372 0.390506 -0.259151 + outer loop + vertex -899.748 441.679 9.02213 + vertex -897.002 446.553 7.00306 + vertex -899.113 441.782 7.01239 + endloop + endfacet + facet normal -0.883526 0.390113 -0.25922 + outer loop + vertex -899.748 441.679 9.02213 + vertex -899.113 441.782 7.01239 + vertex -901.84 436.95 9.03252 + endloop + endfacet + facet normal -0.88252 0.385029 -0.270021 + outer loop + vertex -901.84 436.95 9.03252 + vertex -899.113 441.782 7.01239 + vertex -901.183 437.043 7.0189 + endloop + endfacet + facet normal -0.823777 0.359144 -0.438643 + outer loop + vertex -899.113 441.782 7.01239 + vertex -898.159 441.848 5.2733 + vertex -901.183 437.043 7.0189 + endloop + endfacet + facet normal -0.820338 0.352832 -0.450061 + outer loop + vertex -901.183 437.043 7.0189 + vertex -898.159 441.848 5.2733 + vertex -900.193 437.112 5.26872 + endloop + endfacet + facet normal -0.837045 0.378065 -0.395503 + outer loop + vertex -892.738 456.027 6.98823 + vertex -891.922 456.003 5.23725 + vertex -894.871 451.312 6.99471 + endloop + endfacet + facet normal -0.833555 0.370536 -0.409743 + outer loop + vertex -894.871 451.312 6.99471 + vertex -891.922 456.003 5.23725 + vertex -894.001 451.342 5.25175 + endloop + endfacet + facet normal -0.884887 0.405408 -0.229388 + outer loop + vertex -893.259 456.06 9.05389 + vertex -892.738 456.027 6.98823 + vertex -895.442 451.281 9.03371 + endloop + endfacet + facet normal -0.884187 0.399599 -0.24194 + outer loop + vertex -895.442 451.281 9.03371 + vertex -892.738 456.027 6.98823 + vertex -894.871 451.312 6.99471 + endloop + endfacet + facet normal -0.88439 0.39911 -0.242004 + outer loop + vertex -895.442 451.281 9.03371 + vertex -894.871 451.312 6.99471 + vertex -897.612 446.467 9.02082 + endloop + endfacet + facet normal -0.883786 0.395275 -0.250359 + outer loop + vertex -897.612 446.467 9.02082 + vertex -894.871 451.312 6.99471 + vertex -897.002 446.553 7.00306 + endloop + endfacet + facet normal -0.832957 0.372238 -0.409416 + outer loop + vertex -894.871 451.312 6.99471 + vertex -894.001 451.342 5.25175 + vertex -897.002 446.553 7.00306 + endloop + endfacet + facet normal -0.829174 0.364653 -0.423672 + outer loop + vertex -897.002 446.553 7.00306 + vertex -894.001 451.342 5.25175 + vertex -896.089 446.608 5.26501 + endloop + endfacet + facet normal -0.843291 0.396173 -0.36319 + outer loop + vertex -888.427 465.31 7.00137 + vertex -887.713 465.188 5.20924 + vertex -890.594 460.687 6.99053 + endloop + endfacet + facet normal -0.839763 0.386888 -0.380941 + outer loop + vertex -890.594 460.687 6.99053 + vertex -887.713 465.188 5.20924 + vertex -889.838 460.594 5.2278 + endloop + endfacet + facet normal -0.883554 0.419101 -0.209013 + outer loop + vertex -888.897 465.368 9.10323 + vertex -888.427 465.31 7.00137 + vertex -891.083 460.747 9.07673 + endloop + endfacet + facet normal -0.883348 0.414611 -0.218618 + outer loop + vertex -891.083 460.747 9.07673 + vertex -888.427 465.31 7.00137 + vertex -890.594 460.687 6.99053 + endloop + endfacet + facet normal -0.884649 0.41171 -0.218839 + outer loop + vertex -891.083 460.747 9.07673 + vertex -890.594 460.687 6.99053 + vertex -893.259 456.06 9.05389 + endloop + endfacet + facet normal -0.884263 0.406844 -0.229253 + outer loop + vertex -893.259 456.06 9.05389 + vertex -890.594 460.687 6.99053 + vertex -892.738 456.027 6.98823 + endloop + endfacet + facet normal -0.839913 0.386519 -0.380985 + outer loop + vertex -890.594 460.687 6.99053 + vertex -889.838 460.594 5.2278 + vertex -892.738 456.027 6.98823 + endloop + endfacet + facet normal -0.836714 0.378946 -0.395361 + outer loop + vertex -892.738 456.027 6.98823 + vertex -889.838 460.594 5.2278 + vertex -891.922 456.003 5.23725 + endloop + endfacet + facet normal -0.848751 0.416268 -0.326103 + outer loop + vertex -883.983 474.508 7.01945 + vertex -883.333 474.418 5.21468 + vertex -886.229 469.919 7.00791 + endloop + endfacet + facet normal -0.845099 0.404631 -0.349402 + outer loop + vertex -886.229 469.919 7.00791 + vertex -883.333 474.418 5.21468 + vertex -885.539 469.805 5.20578 + endloop + endfacet + facet normal -0.881448 0.43864 -0.175057 + outer loop + vertex -884.375 474.562 9.13311 + vertex -883.983 474.508 7.01945 + vertex -886.658 469.973 9.12752 + endloop + endfacet + facet normal -0.881703 0.432054 -0.189547 + outer loop + vertex -886.658 469.973 9.12752 + vertex -883.983 474.508 7.01945 + vertex -886.229 469.919 7.00791 + endloop + endfacet + facet normal -0.882612 0.430136 -0.189683 + outer loop + vertex -886.658 469.973 9.12752 + vertex -886.229 469.919 7.00791 + vertex -888.897 465.368 9.10323 + endloop + endfacet + facet normal -0.882556 0.421279 -0.208851 + outer loop + vertex -888.897 465.368 9.10323 + vertex -886.229 469.919 7.00791 + vertex -888.427 465.31 7.00137 + endloop + endfacet + facet normal -0.845467 0.403786 -0.349489 + outer loop + vertex -886.229 469.919 7.00791 + vertex -885.539 469.805 5.20578 + vertex -888.427 465.31 7.00137 + endloop + endfacet + facet normal -0.843035 0.396775 -0.363128 + outer loop + vertex -888.427 465.31 7.00137 + vertex -885.539 469.805 5.20578 + vertex -887.713 465.188 5.20924 + endloop + endfacet + facet normal -0.860976 0.426972 -0.276433 + outer loop + vertex -879.433 483.644 6.99635 + vertex -878.902 483.553 5.2013 + vertex -881.707 479.069 7.01551 + endloop + endfacet + facet normal -0.858526 0.415968 -0.299838 + outer loop + vertex -881.707 479.069 7.01551 + vertex -878.902 483.553 5.2013 + vertex -881.114 478.996 5.2162 + endloop + endfacet + facet normal -0.883275 0.446854 -0.141943 + outer loop + vertex -879.7 483.775 9.07283 + vertex -879.433 483.644 6.99635 + vertex -882.048 479.148 9.11395 + endloop + endfacet + facet normal -0.884175 0.438997 -0.159735 + outer loop + vertex -882.048 479.148 9.11395 + vertex -879.433 483.644 6.99635 + vertex -881.707 479.069 7.01551 + endloop + endfacet + facet normal -0.880549 0.446339 -0.159422 + outer loop + vertex -882.048 479.148 9.11395 + vertex -881.707 479.069 7.01551 + vertex -884.375 474.562 9.13311 + endloop + endfacet + facet normal -0.881106 0.439344 -0.175012 + outer loop + vertex -884.375 474.562 9.13311 + vertex -881.707 479.069 7.01551 + vertex -883.983 474.508 7.01945 + endloop + endfacet + facet normal -0.854087 0.42576 -0.298772 + outer loop + vertex -881.707 479.069 7.01551 + vertex -881.114 478.996 5.2162 + vertex -883.983 474.508 7.01945 + endloop + endfacet + facet normal -0.850509 0.412318 -0.32654 + outer loop + vertex -883.983 474.508 7.01945 + vertex -881.114 478.996 5.2162 + vertex -883.333 474.418 5.21468 + endloop + endfacet + facet normal -0.933304 0.259183 -0.248531 + outer loop + vertex -875.886 493.533 6.9396 + vertex -875.435 493.344 5.04799 + vertex -877.325 488.374 6.96293 + endloop + endfacet + facet normal -0.931883 0.254984 -0.258026 + outer loop + vertex -877.325 488.374 6.96293 + vertex -875.435 493.344 5.04799 + vertex -876.87 488.24 5.18751 + endloop + endfacet + facet normal -0.956331 0.262235 -0.129089 + outer loop + vertex -876.132 493.64 8.9815 + vertex -875.886 493.533 6.9396 + vertex -877.537 488.545 9.03707 + endloop + endfacet + facet normal -0.95645 0.266221 -0.119704 + outer loop + vertex -877.537 488.545 9.03707 + vertex -875.886 493.533 6.9396 + vertex -877.325 488.374 6.96293 + endloop + endfacet + facet normal -0.903833 0.408889 -0.126076 + outer loop + vertex -877.537 488.545 9.03707 + vertex -877.325 488.374 6.96293 + vertex -879.7 483.775 9.07283 + endloop + endfacet + facet normal -0.904571 0.402033 -0.14185 + outer loop + vertex -879.7 483.775 9.07283 + vertex -877.325 488.374 6.96293 + vertex -879.433 483.644 6.99635 + endloop + endfacet + facet normal -0.88366 0.39191 -0.256033 + outer loop + vertex -877.325 488.374 6.96293 + vertex -876.87 488.24 5.18751 + vertex -879.433 483.644 6.99635 + endloop + endfacet + facet normal -0.881122 0.381037 -0.280061 + outer loop + vertex -879.433 483.644 6.99635 + vertex -876.87 488.24 5.18751 + vertex -878.902 483.553 5.2013 + endloop + endfacet + facet normal -0.360946 -0.315714 -0.877521 + outer loop + vertex -878.642 195.956 4.02431 + vertex -877.618 198.197 2.79715 + vertex -876.943 194.723 3.76897 + endloop + endfacet + facet normal -0.316281 -0.312154 -0.895838 + outer loop + vertex -876.943 194.723 3.76897 + vertex -877.618 198.197 2.79715 + vertex -875.666 196.976 2.53324 + endloop + endfacet + facet normal -0.445837 -0.374669 -0.812929 + outer loop + vertex -877.51 192.828 4.95408 + vertex -878.014 193.534 4.90488 + vertex -876.943 194.723 3.76897 + endloop + endfacet + facet normal -0.477702 -0.406816 -0.778654 + outer loop + vertex -878.491 193.646 5.13894 + vertex -878.642 195.956 4.02431 + vertex -878.014 193.534 4.90488 + endloop + endfacet + facet normal -0.415546 -0.403911 -0.814971 + outer loop + vertex -878.642 195.956 4.02431 + vertex -876.943 194.723 3.76897 + vertex -878.014 193.534 4.90488 + endloop + endfacet + facet normal -0.346608 -0.319173 -0.882038 + outer loop + vertex -884.047 201.672 4.06312 + vertex -882.456 203.089 2.92487 + vertex -880.913 198.242 4.07255 + endloop + endfacet + facet normal -0.348596 -0.319585 -0.881105 + outer loop + vertex -880.913 198.242 4.07255 + vertex -882.456 203.089 2.92487 + vertex -879.712 200.122 2.91547 + endloop + endfacet + facet normal -0.422822 -0.406934 -0.809708 + outer loop + vertex -880.571 195.802 5.1205 + vertex -882.221 197.826 4.96463 + vertex -880.913 198.242 4.07255 + endloop + endfacet + facet normal -0.436875 -0.396716 -0.807314 + outer loop + vertex -883.927 199.424 5.1025 + vertex -884.047 201.672 4.06312 + vertex -882.221 197.826 4.96463 + endloop + endfacet + facet normal -0.428947 -0.394229 -0.812765 + outer loop + vertex -884.047 201.672 4.06312 + vertex -880.913 198.242 4.07255 + vertex -882.221 197.826 4.96463 + endloop + endfacet + facet normal -0.413031 -0.417427 -0.80942 + outer loop + vertex -878.491 193.646 5.13894 + vertex -879.37 194.786 4.9994 + vertex -878.642 195.956 4.02431 + endloop + endfacet + facet normal -0.425479 -0.406748 -0.808408 + outer loop + vertex -880.571 195.802 5.1205 + vertex -880.913 198.242 4.07255 + vertex -879.37 194.786 4.9994 + endloop + endfacet + facet normal -0.426935 -0.407139 -0.807443 + outer loop + vertex -880.913 198.242 4.07255 + vertex -878.642 195.956 4.02431 + vertex -879.37 194.786 4.9994 + endloop + endfacet + facet normal -0.343837 -0.32301 -0.881726 + outer loop + vertex -880.913 198.242 4.07255 + vertex -879.712 200.122 2.91547 + vertex -878.642 195.956 4.02431 + endloop + endfacet + facet normal -0.34721 -0.323478 -0.880231 + outer loop + vertex -878.642 195.956 4.02431 + vertex -879.712 200.122 2.91547 + vertex -877.618 198.197 2.79715 + endloop + endfacet + facet normal -0.35183 -0.302433 -0.885861 + outer loop + vertex -890.677 209.273 4.05872 + vertex -888.933 210.626 2.904 + vertex -887.399 205.457 4.0595 + endloop + endfacet + facet normal -0.356625 -0.303356 -0.883626 + outer loop + vertex -887.399 205.457 4.0595 + vertex -888.933 210.626 2.904 + vertex -885.662 206.762 2.91034 + endloop + endfacet + facet normal -0.437423 -0.389173 -0.810682 + outer loop + vertex -887.35 203.208 5.11321 + vertex -889.017 205.368 4.97531 + vertex -887.399 205.457 4.0595 + endloop + endfacet + facet normal -0.442155 -0.378811 -0.81302 + outer loop + vertex -890.654 206.98 5.11498 + vertex -890.677 209.273 4.05872 + vertex -889.017 205.368 4.97531 + endloop + endfacet + facet normal -0.440117 -0.378264 -0.814379 + outer loop + vertex -890.677 209.273 4.05872 + vertex -887.399 205.457 4.0595 + vertex -889.017 205.368 4.97531 + endloop + endfacet + facet normal -0.435276 -0.396972 -0.808052 + outer loop + vertex -883.927 199.424 5.1025 + vertex -885.669 201.602 4.9714 + vertex -884.047 201.672 4.06312 + endloop + endfacet + facet normal -0.439709 -0.38874 -0.809652 + outer loop + vertex -887.35 203.208 5.11321 + vertex -887.399 205.457 4.0595 + vertex -885.669 201.602 4.9714 + endloop + endfacet + facet normal -0.437426 -0.388082 -0.811203 + outer loop + vertex -887.399 205.457 4.0595 + vertex -884.047 201.672 4.06312 + vertex -885.669 201.602 4.9714 + endloop + endfacet + facet normal -0.350529 -0.31121 -0.883333 + outer loop + vertex -887.399 205.457 4.0595 + vertex -885.662 206.762 2.91034 + vertex -884.047 201.672 4.06312 + endloop + endfacet + facet normal -0.353213 -0.311774 -0.882064 + outer loop + vertex -884.047 201.672 4.06312 + vertex -885.662 206.762 2.91034 + vertex -882.456 203.089 2.92487 + endloop + endfacet + facet normal -0.358256 -0.283529 -0.88953 + outer loop + vertex -897.021 217.102 4.06234 + vertex -895.198 218.429 2.90535 + vertex -893.869 213.127 4.05987 + endloop + endfacet + facet normal -0.363374 -0.284306 -0.887203 + outer loop + vertex -893.869 213.127 4.05987 + vertex -895.198 218.429 2.90535 + vertex -892.113 214.501 2.90036 + endloop + endfacet + facet normal -0.440469 -0.369093 -0.818387 + outer loop + vertex -893.887 210.805 5.11686 + vertex -895.488 213.036 4.97206 + vertex -893.869 213.127 4.05987 + endloop + endfacet + facet normal -0.450906 -0.35343 -0.819616 + outer loop + vertex -897.088 214.746 5.11532 + vertex -897.021 217.102 4.06234 + vertex -895.488 213.036 4.97206 + endloop + endfacet + facet normal -0.444464 -0.35193 -0.82377 + outer loop + vertex -897.021 217.102 4.06234 + vertex -893.869 213.127 4.05987 + vertex -895.488 213.036 4.97206 + endloop + endfacet + facet normal -0.437524 -0.379721 -0.815098 + outer loop + vertex -890.654 206.98 5.11498 + vertex -892.287 209.167 4.97221 + vertex -890.677 209.273 4.05872 + endloop + endfacet + facet normal -0.449381 -0.367201 -0.814383 + outer loop + vertex -893.887 210.805 5.11686 + vertex -893.869 213.127 4.05987 + vertex -892.287 209.167 4.97221 + endloop + endfacet + facet normal -0.441145 -0.365156 -0.819788 + outer loop + vertex -893.869 213.127 4.05987 + vertex -890.677 209.273 4.05872 + vertex -892.287 209.167 4.97221 + endloop + endfacet + facet normal -0.355553 -0.294239 -0.887133 + outer loop + vertex -893.869 213.127 4.05987 + vertex -892.113 214.501 2.90036 + vertex -890.677 209.273 4.05872 + endloop + endfacet + facet normal -0.357968 -0.294657 -0.886023 + outer loop + vertex -890.677 209.273 4.05872 + vertex -892.113 214.501 2.90036 + vertex -888.933 210.626 2.904 + endloop + endfacet + facet normal -0.36115 -0.261674 -0.895041 + outer loop + vertex -903.26 225.516 4.05982 + vertex -901.206 226.628 2.90584 + vertex -900.178 221.26 4.06071 + endloop + endfacet + facet normal -0.366617 -0.262207 -0.892659 + outer loop + vertex -900.178 221.26 4.06071 + vertex -901.206 226.628 2.90584 + vertex -898.235 222.474 2.90596 + endloop + endfacet + facet normal -0.44852 -0.342955 -0.825355 + outer loop + vertex -900.353 218.948 5.11624 + vertex -901.961 221.397 4.97252 + vertex -900.178 221.26 4.06071 + endloop + endfacet + facet normal -0.45687 -0.327339 -0.827115 + outer loop + vertex -903.578 223.29 5.11623 + vertex -903.26 225.516 4.05982 + vertex -901.961 221.397 4.97252 + endloop + endfacet + facet normal -0.450222 -0.326152 -0.831219 + outer loop + vertex -903.26 225.516 4.05982 + vertex -900.178 221.26 4.06071 + vertex -901.961 221.397 4.97252 + endloop + endfacet + facet normal -0.446153 -0.354516 -0.821746 + outer loop + vertex -897.088 214.746 5.11532 + vertex -898.705 217.106 4.97494 + vertex -897.021 217.102 4.06234 + endloop + endfacet + facet normal -0.45268 -0.341818 -0.823554 + outer loop + vertex -900.353 218.948 5.11624 + vertex -900.178 221.26 4.06071 + vertex -898.705 217.106 4.97494 + endloop + endfacet + facet normal -0.448535 -0.340927 -0.826187 + outer loop + vertex -900.178 221.26 4.06071 + vertex -897.021 217.102 4.06234 + vertex -898.705 217.106 4.97494 + endloop + endfacet + facet normal -0.359442 -0.273299 -0.89225 + outer loop + vertex -900.178 221.26 4.06071 + vertex -898.235 222.474 2.90596 + vertex -897.021 217.102 4.06234 + endloop + endfacet + facet normal -0.365234 -0.274051 -0.889663 + outer loop + vertex -897.021 217.102 4.06234 + vertex -898.235 222.474 2.90596 + vertex -895.198 218.429 2.90535 + endloop + endfacet + facet normal -0.367476 -0.239118 -0.898768 + outer loop + vertex -908.9 233.96 4.06167 + vertex -906.735 234.991 2.90212 + vertex -906.159 229.743 4.06302 + endloop + endfacet + facet normal -0.371058 -0.239181 -0.897278 + outer loop + vertex -906.159 229.743 4.06302 + vertex -906.735 234.991 2.90212 + vertex -904.049 230.814 2.90494 + endloop + endfacet + facet normal -0.454424 -0.311133 -0.834683 + outer loop + vertex -906.577 227.533 5.1141 + vertex -907.941 229.901 4.97402 + vertex -906.159 229.743 4.06302 + endloop + endfacet + facet normal -0.459527 -0.296756 -0.837121 + outer loop + vertex -909.384 231.739 5.11449 + vertex -908.9 233.96 4.06167 + vertex -907.941 229.901 4.97402 + endloop + endfacet + facet normal -0.455545 -0.296337 -0.839442 + outer loop + vertex -908.9 233.96 4.06167 + vertex -906.159 229.743 4.06302 + vertex -907.941 229.901 4.97402 + endloop + endfacet + facet normal -0.453606 -0.328448 -0.82847 + outer loop + vertex -903.578 223.29 5.11623 + vertex -905.064 225.699 4.97492 + vertex -903.26 225.516 4.05982 + endloop + endfacet + facet normal -0.454134 -0.311243 -0.834799 + outer loop + vertex -906.577 227.533 5.1141 + vertex -906.159 229.743 4.06302 + vertex -905.064 225.699 4.97492 + endloop + endfacet + facet normal -0.454863 -0.311343 -0.834365 + outer loop + vertex -906.159 229.743 4.06302 + vertex -903.26 225.516 4.05982 + vertex -905.064 225.699 4.97492 + endloop + endfacet + facet normal -0.365322 -0.249883 -0.896715 + outer loop + vertex -906.159 229.743 4.06302 + vertex -904.049 230.814 2.90494 + vertex -903.26 225.516 4.05982 + endloop + endfacet + facet normal -0.367803 -0.250023 -0.895662 + outer loop + vertex -903.26 225.516 4.05982 + vertex -904.049 230.814 2.90494 + vertex -901.206 226.628 2.90584 + endloop + endfacet + facet normal -0.368932 -0.213708 -0.904554 + outer loop + vertex -914.009 242.535 4.06066 + vertex -911.668 243.386 2.90455 + vertex -911.525 238.239 4.06229 + endloop + endfacet + facet normal -0.373227 -0.213445 -0.902853 + outer loop + vertex -911.525 238.239 4.06229 + vertex -911.668 243.386 2.90455 + vertex -909.267 239.179 2.90658 + endloop + endfacet + facet normal -0.460306 -0.281964 -0.841793 + outer loop + vertex -912.128 236.084 5.11431 + vertex -913.38 238.547 4.97384 + vertex -911.525 238.239 4.06229 + endloop + endfacet + facet normal -0.466846 -0.266684 -0.843169 + outer loop + vertex -914.739 240.474 5.11667 + vertex -914.009 242.535 4.06066 + vertex -913.38 238.547 4.97384 + endloop + endfacet + facet normal -0.460229 -0.266486 -0.846861 + outer loop + vertex -914.009 242.535 4.06066 + vertex -911.525 238.239 4.06229 + vertex -913.38 238.547 4.97384 + endloop + endfacet + facet normal -0.45817 -0.297311 -0.837667 + outer loop + vertex -909.384 231.739 5.11449 + vertex -910.701 234.166 4.97391 + vertex -908.9 233.96 4.06167 + endloop + endfacet + facet normal -0.461182 -0.281552 -0.841451 + outer loop + vertex -912.128 236.084 5.11431 + vertex -911.525 238.239 4.06229 + vertex -910.701 234.166 4.97391 + endloop + endfacet + facet normal -0.458918 -0.281383 -0.842744 + outer loop + vertex -911.525 238.239 4.06229 + vertex -908.9 233.96 4.06167 + vertex -910.701 234.166 4.97391 + endloop + endfacet + facet normal -0.367838 -0.225505 -0.902132 + outer loop + vertex -911.525 238.239 4.06229 + vertex -909.267 239.179 2.90658 + vertex -908.9 233.96 4.06167 + endloop + endfacet + facet normal -0.374394 -0.225376 -0.899464 + outer loop + vertex -908.9 233.96 4.06167 + vertex -909.267 239.179 2.90658 + vertex -906.735 234.991 2.90212 + endloop + endfacet + facet normal -0.372414 -0.186112 -0.909214 + outer loop + vertex -918.468 251.101 4.0626 + vertex -916.034 251.884 2.90557 + vertex -916.307 246.788 4.06061 + endloop + endfacet + facet normal -0.376247 -0.185574 -0.907745 + outer loop + vertex -916.307 246.788 4.06061 + vertex -916.034 251.884 2.90557 + vertex -913.919 247.606 2.90347 + endloop + endfacet + facet normal -0.467379 -0.251796 -0.84744 + outer loop + vertex -917.111 244.723 5.11747 + vertex -918.128 247.087 4.97593 + vertex -916.307 246.788 4.06061 + endloop + endfacet + facet normal -0.46761 -0.233535 -0.852527 + outer loop + vertex -919.323 248.969 5.11564 + vertex -918.468 251.101 4.0626 + vertex -918.128 247.087 4.97593 + endloop + endfacet + facet normal -0.467084 -0.233555 -0.85281 + outer loop + vertex -918.468 251.101 4.0626 + vertex -916.307 246.788 4.06061 + vertex -918.128 247.087 4.97593 + endloop + endfacet + facet normal -0.463213 -0.268673 -0.84454 + outer loop + vertex -914.739 240.474 5.11667 + vertex -915.866 242.867 4.9735 + vertex -914.009 242.535 4.06066 + endloop + endfacet + facet normal -0.470466 -0.249992 -0.846265 + outer loop + vertex -917.111 244.723 5.11747 + vertex -916.307 246.788 4.06061 + vertex -915.866 242.867 4.9735 + endloop + endfacet + facet normal -0.462799 -0.250103 -0.85045 + outer loop + vertex -916.307 246.788 4.06061 + vertex -914.009 242.535 4.06066 + vertex -915.866 242.867 4.9735 + endloop + endfacet + facet normal -0.37075 -0.200361 -0.906863 + outer loop + vertex -916.307 246.788 4.06061 + vertex -913.919 247.606 2.90347 + vertex -914.009 242.535 4.06066 + endloop + endfacet + facet normal -0.374371 -0.199977 -0.905459 + outer loop + vertex -914.009 242.535 4.06066 + vertex -913.919 247.606 2.90347 + vertex -911.668 243.386 2.90455 + endloop + endfacet + facet normal -0.375294 -0.159174 -0.913136 + outer loop + vertex -922.56 260.308 4.06365 + vertex -919.979 260.887 2.90176 + vertex -920.565 255.616 4.06135 + endloop + endfacet + facet normal -0.377094 -0.158825 -0.912456 + outer loop + vertex -920.565 255.616 4.06135 + vertex -919.979 260.887 2.90176 + vertex -918.053 256.3 2.90439 + endloop + endfacet + facet normal -0.46961 -0.216735 -0.855858 + outer loop + vertex -921.508 253.495 5.1158 + vertex -922.461 256.115 4.97534 + vertex -920.565 255.616 4.06135 + endloop + endfacet + facet normal -0.46788 -0.198373 -0.861241 + outer loop + vertex -923.619 258.238 5.11588 + vertex -922.56 260.308 4.06365 + vertex -922.461 256.115 4.97534 + endloop + endfacet + facet normal -0.467481 -0.198409 -0.861449 + outer loop + vertex -922.56 260.308 4.06365 + vertex -920.565 255.616 4.06135 + vertex -922.461 256.115 4.97534 + endloop + endfacet + facet normal -0.468167 -0.233206 -0.852311 + outer loop + vertex -919.323 248.969 5.11564 + vertex -920.31 251.461 4.97603 + vertex -918.468 251.101 4.0626 + endloop + endfacet + facet normal -0.468878 -0.217201 -0.856141 + outer loop + vertex -921.508 253.495 5.1158 + vertex -920.565 255.616 4.06135 + vertex -920.31 251.461 4.97603 + endloop + endfacet + facet normal -0.467359 -0.217286 -0.856949 + outer loop + vertex -920.565 255.616 4.06135 + vertex -918.468 251.101 4.0626 + vertex -920.31 251.461 4.97603 + endloop + endfacet + facet normal -0.37274 -0.173358 -0.911598 + outer loop + vertex -920.565 255.616 4.06135 + vertex -918.053 256.3 2.90439 + vertex -918.468 251.101 4.0626 + endloop + endfacet + facet normal -0.377093 -0.172642 -0.909942 + outer loop + vertex -918.468 251.101 4.0626 + vertex -918.053 256.3 2.90439 + vertex -916.034 251.884 2.90557 + endloop + endfacet + facet normal -0.375584 -0.12916 -0.917744 + outer loop + vertex -926.073 269.944 4.06153 + vertex -923.41 270.439 2.90177 + vertex -924.401 265.077 4.06196 + endloop + endfacet + facet normal -0.37591 -0.129073 -0.917623 + outer loop + vertex -924.401 265.077 4.06196 + vertex -923.41 270.439 2.90177 + vertex -921.766 265.613 2.90733 + endloop + endfacet + facet normal -0.471297 -0.180845 -0.863235 + outer loop + vertex -925.536 262.993 5.11863 + vertex -926.291 265.646 4.9747 + vertex -924.401 265.077 4.06196 + endloop + endfacet + facet normal -0.474007 -0.159981 -0.865866 + outer loop + vertex -927.285 267.819 5.11772 + vertex -926.073 269.944 4.06153 + vertex -926.291 265.646 4.9747 + endloop + endfacet + facet normal -0.468047 -0.160933 -0.868926 + outer loop + vertex -926.073 269.944 4.06153 + vertex -924.401 265.077 4.06196 + vertex -926.291 265.646 4.9747 + endloop + endfacet + facet normal -0.469851 -0.196983 -0.860487 + outer loop + vertex -923.619 258.238 5.11588 + vertex -924.469 260.872 4.97685 + vertex -922.56 260.308 4.06365 + endloop + endfacet + facet normal -0.472404 -0.180021 -0.862801 + outer loop + vertex -925.536 262.993 5.11863 + vertex -924.401 265.077 4.06196 + vertex -924.469 260.872 4.97685 + endloop + endfacet + facet normal -0.467382 -0.180668 -0.865398 + outer loop + vertex -924.401 265.077 4.06196 + vertex -922.56 260.308 4.06365 + vertex -924.469 260.872 4.97685 + endloop + endfacet + facet normal -0.372492 -0.144069 -0.916784 + outer loop + vertex -924.401 265.077 4.06196 + vertex -921.766 265.613 2.90733 + vertex -922.56 260.308 4.06365 + endloop + endfacet + facet normal -0.379507 -0.142446 -0.914157 + outer loop + vertex -922.56 260.308 4.06365 + vertex -921.766 265.613 2.90733 + vertex -919.979 260.887 2.90176 + endloop + endfacet + facet normal -0.375947 -0.0984157 -0.9214 + outer loop + vertex -928.919 280.008 4.06291 + vertex -926.166 280.326 2.90535 + vertex -927.591 274.949 4.06119 + endloop + endfacet + facet normal -0.376704 -0.0981544 -0.921119 + outer loop + vertex -927.591 274.949 4.06119 + vertex -926.166 280.326 2.90535 + vertex -924.874 275.36 2.90632 + endloop + endfacet + facet normal -0.475033 -0.139972 -0.868764 + outer loop + vertex -928.905 272.859 5.11661 + vertex -929.484 275.691 4.97677 + vertex -927.591 274.949 4.06119 + endloop + endfacet + facet normal -0.47572 -0.122184 -0.871069 + outer loop + vertex -930.342 278.015 5.11913 + vertex -928.919 280.008 4.06291 + vertex -929.484 275.691 4.97677 + endloop + endfacet + facet normal -0.470833 -0.12335 -0.873556 + outer loop + vertex -928.919 280.008 4.06291 + vertex -927.591 274.949 4.06119 + vertex -929.484 275.691 4.97677 + endloop + endfacet + facet normal -0.474543 -0.159568 -0.865649 + outer loop + vertex -927.285 267.819 5.11772 + vertex -927.958 270.577 4.97789 + vertex -926.073 269.944 4.06153 + endloop + endfacet + facet normal -0.471543 -0.142887 -0.87019 + outer loop + vertex -928.905 272.859 5.11661 + vertex -927.591 274.949 4.06119 + vertex -927.958 270.577 4.97789 + endloop + endfacet + facet normal -0.471239 -0.142945 -0.870345 + outer loop + vertex -927.591 274.949 4.06119 + vertex -926.073 269.944 4.06153 + vertex -927.958 270.577 4.97789 + endloop + endfacet + facet normal -0.374088 -0.113491 -0.920423 + outer loop + vertex -927.591 274.949 4.06119 + vertex -924.874 275.36 2.90632 + vertex -926.073 269.944 4.06153 + endloop + endfacet + facet normal -0.379125 -0.111975 -0.918546 + outer loop + vertex -926.073 269.944 4.06153 + vertex -924.874 275.36 2.90632 + vertex -923.41 270.439 2.90177 + endloop + endfacet + facet normal -0.377448 -0.0679129 -0.923537 + outer loop + vertex -930.915 289.876 4.06323 + vertex -928.129 290.107 2.9074 + vertex -930.031 284.992 4.06114 + endloop + endfacet + facet normal -0.378794 -0.0672985 -0.923031 + outer loop + vertex -930.031 284.992 4.06114 + vertex -928.129 290.107 2.9074 + vertex -927.257 285.255 2.90341 + endloop + endfacet + facet normal -0.479042 -0.104173 -0.871589 + outer loop + vertex -931.542 283.079 5.12042 + vertex -931.87 285.792 4.97598 + vertex -930.031 284.992 4.06114 + endloop + endfacet + facet normal -0.47847 -0.0835248 -0.874122 + outer loop + vertex -932.515 288.01 5.11735 + vertex -930.915 289.876 4.06323 + vertex -931.87 285.792 4.97598 + endloop + endfacet + facet normal -0.473381 -0.0852942 -0.876718 + outer loop + vertex -930.915 289.876 4.06323 + vertex -930.031 284.992 4.06114 + vertex -931.87 285.792 4.97598 + endloop + endfacet + facet normal -0.475161 -0.122707 -0.871301 + outer loop + vertex -930.342 278.015 5.11913 + vertex -930.799 280.805 4.97559 + vertex -928.919 280.008 4.06291 + endloop + endfacet + facet normal -0.481244 -0.101908 -0.870643 + outer loop + vertex -931.542 283.079 5.12042 + vertex -930.031 284.992 4.06114 + vertex -930.799 280.805 4.97559 + endloop + endfacet + facet normal -0.470147 -0.105179 -0.876299 + outer loop + vertex -930.031 284.992 4.06114 + vertex -928.919 280.008 4.06291 + vertex -930.799 280.805 4.97559 + endloop + endfacet + facet normal -0.376907 -0.0843983 -0.922398 + outer loop + vertex -930.031 284.992 4.06114 + vertex -927.257 285.255 2.90341 + vertex -928.919 280.008 4.06291 + endloop + endfacet + facet normal -0.377879 -0.0840103 -0.922036 + outer loop + vertex -928.919 280.008 4.06291 + vertex -927.257 285.255 2.90341 + vertex -926.166 280.326 2.90535 + endloop + endfacet + facet normal -0.379311 -0.038325 -0.924475 + outer loop + vertex -932.096 299.638 4.06162 + vertex -929.297 299.807 2.90634 + vertex -931.6 294.719 4.06196 + endloop + endfacet + facet normal -0.379962 -0.0379728 -0.924222 + outer loop + vertex -931.6 294.719 4.06196 + vertex -929.297 299.807 2.90634 + vertex -928.807 294.929 2.90543 + endloop + endfacet + facet normal -0.481406 -0.0634287 -0.8742 + outer loop + vertex -933.269 292.841 5.11752 + vertex -933.363 295.493 4.97704 + vertex -931.6 294.719 4.06196 + endloop + endfacet + facet normal -0.481244 -0.0461633 -0.87537 + outer loop + vertex -933.832 297.71 5.11755 + vertex -932.096 299.638 4.06162 + vertex -933.363 295.493 4.97704 + endloop + endfacet + facet normal -0.476572 -0.0481324 -0.877817 + outer loop + vertex -932.096 299.638 4.06162 + vertex -931.6 294.719 4.06196 + vertex -933.363 295.493 4.97704 + endloop + endfacet + facet normal -0.479896 -0.0819447 -0.87349 + outer loop + vertex -932.515 288.01 5.11735 + vertex -932.714 290.663 4.97801 + vertex -930.915 289.876 4.06323 + endloop + endfacet + facet normal -0.479206 -0.0659572 -0.875221 + outer loop + vertex -933.269 292.841 5.11752 + vertex -931.6 294.719 4.06196 + vertex -932.714 290.663 4.97801 + endloop + endfacet + facet normal -0.47542 -0.067438 -0.87717 + outer loop + vertex -931.6 294.719 4.06196 + vertex -930.915 289.876 4.06323 + vertex -932.714 290.663 4.97801 + endloop + endfacet + facet normal -0.37867 -0.053773 -0.923968 + outer loop + vertex -931.6 294.719 4.06196 + vertex -928.807 294.929 2.90543 + vertex -930.915 289.876 4.06323 + endloop + endfacet + facet normal -0.378788 -0.0537137 -0.923924 + outer loop + vertex -930.915 289.876 4.06323 + vertex -928.807 294.929 2.90543 + vertex -928.129 290.107 2.9074 + endloop + endfacet + facet normal -0.382729 -0.00975295 -0.923809 + outer loop + vertex -932.537 309.909 4.06166 + vertex -929.747 309.91 2.9055 + vertex -932.409 304.726 4.06318 + endloop + endfacet + facet normal -0.382909 -0.00964445 -0.923736 + outer loop + vertex -932.409 304.726 4.06318 + vertex -929.747 309.91 2.9055 + vertex -929.614 304.805 2.90365 + endloop + endfacet + facet normal -0.484139 -0.0269613 -0.874576 + outer loop + vertex -934.211 302.822 5.11951 + vertex -934.112 305.682 4.9763 + vertex -932.409 304.726 4.06318 + endloop + endfacet + facet normal -0.487036 -0.0075801 -0.873349 + outer loop + vertex -934.404 308.079 5.11826 + vertex -932.537 309.909 4.06166 + vertex -934.112 305.682 4.9763 + endloop + endfacet + facet normal -0.477828 -0.012096 -0.87837 + outer loop + vertex -932.537 309.909 4.06166 + vertex -932.409 304.726 4.06318 + vertex -934.112 305.682 4.9763 + endloop + endfacet + facet normal -0.483397 -0.043647 -0.874313 + outer loop + vertex -933.832 297.71 5.11755 + vertex -933.828 300.475 4.97739 + vertex -932.096 299.638 4.06162 + endloop + endfacet + facet normal -0.484708 -0.02626 -0.874282 + outer loop + vertex -934.211 302.822 5.11951 + vertex -932.409 304.726 4.06318 + vertex -933.828 300.475 4.97739 + endloop + endfacet + facet normal -0.47822 -0.0291721 -0.877755 + outer loop + vertex -932.409 304.726 4.06318 + vertex -932.096 299.638 4.06162 + vertex -933.828 300.475 4.97739 + endloop + endfacet + facet normal -0.382496 -0.023265 -0.923664 + outer loop + vertex -932.409 304.726 4.06318 + vertex -929.614 304.805 2.90365 + vertex -932.096 299.638 4.06162 + endloop + endfacet + facet normal -0.380185 -0.0245818 -0.924584 + outer loop + vertex -932.096 299.638 4.06162 + vertex -929.614 304.805 2.90365 + vertex -929.297 299.807 2.90634 + endloop + endfacet + facet normal -0.390426 0.0187126 -0.920444 + outer loop + vertex -932.234 320.183 4.0648 + vertex -929.494 320.154 2.90197 + vertex -932.474 315.06 4.06238 + endloop + endfacet + facet normal -0.385835 0.0155731 -0.922436 + outer loop + vertex -932.474 315.06 4.06238 + vertex -929.494 320.154 2.90197 + vertex -929.705 315.042 2.90404 + endloop + endfacet + facet normal -0.490475 0.0100146 -0.871398 + outer loop + vertex -934.389 313.242 5.11935 + vertex -934.078 316.019 4.97647 + vertex -932.474 315.06 4.06238 + endloop + endfacet + facet normal -0.495975 0.0296685 -0.86783 + outer loop + vertex -934.191 318.354 5.12058 + vertex -932.234 320.183 4.0648 + vertex -934.078 316.019 4.97647 + endloop + endfacet + facet normal -0.484435 0.0230922 -0.874522 + outer loop + vertex -932.234 320.183 4.0648 + vertex -932.474 315.06 4.06238 + vertex -934.078 316.019 4.97647 + endloop + endfacet + facet normal -0.487982 -0.0063162 -0.872831 + outer loop + vertex -934.404 308.079 5.11826 + vertex -934.189 310.9 4.97757 + vertex -932.537 309.909 4.06166 + endloop + endfacet + facet normal -0.491032 0.0107891 -0.871075 + outer loop + vertex -934.389 313.242 5.11935 + vertex -932.474 315.06 4.06238 + vertex -934.189 310.9 4.97757 + endloop + endfacet + facet normal -0.482284 0.00610033 -0.875994 + outer loop + vertex -932.474 315.06 4.06238 + vertex -932.537 309.909 4.06166 + vertex -934.189 310.9 4.97757 + endloop + endfacet + facet normal -0.385933 0.00491251 -0.922514 + outer loop + vertex -932.474 315.06 4.06238 + vertex -929.705 315.042 2.90404 + vertex -932.537 309.909 4.06166 + endloop + endfacet + facet normal -0.382748 0.00285355 -0.923849 + outer loop + vertex -932.537 309.909 4.06166 + vertex -929.705 315.042 2.90404 + vertex -929.747 309.91 2.9055 + endloop + endfacet + facet normal -0.393863 0.0407073 -0.918267 + outer loop + vertex -931.31 330.455 4.06176 + vertex -928.624 330.308 2.90331 + vertex -931.842 325.332 4.06277 + endloop + endfacet + facet normal -0.391848 0.039188 -0.919195 + outer loop + vertex -931.842 325.332 4.06277 + vertex -928.624 330.308 2.90331 + vertex -929.128 325.244 2.90194 + endloop + endfacet + facet normal -0.496772 0.0406688 -0.866928 + outer loop + vertex -933.83 323.561 5.11922 + vertex -933.349 326.394 4.97637 + vertex -931.842 325.332 4.06277 + endloop + endfacet + facet normal -0.504864 0.0595722 -0.861141 + outer loop + vertex -933.315 328.773 5.12121 + vertex -931.31 330.455 4.06176 + vertex -933.349 326.394 4.97637 + endloop + endfacet + facet normal -0.491214 0.0508231 -0.869555 + outer loop + vertex -931.31 330.455 4.06176 + vertex -931.842 325.332 4.06277 + vertex -933.349 326.394 4.97637 + endloop + endfacet + facet normal -0.49282 0.0251757 -0.869767 + outer loop + vertex -934.191 318.354 5.12058 + vertex -933.793 321.171 4.97667 + vertex -932.234 320.183 4.0648 + endloop + endfacet + facet normal -0.498807 0.0437415 -0.865608 + outer loop + vertex -933.83 323.561 5.11922 + vertex -931.842 325.332 4.06277 + vertex -933.793 321.171 4.97667 + endloop + endfacet + facet normal -0.487127 0.0367393 -0.872558 + outer loop + vertex -931.842 325.332 4.06277 + vertex -932.234 320.183 4.0648 + vertex -933.793 321.171 4.97667 + endloop + endfacet + facet normal -0.392244 0.0294979 -0.919388 + outer loop + vertex -931.842 325.332 4.06277 + vertex -929.128 325.244 2.90194 + vertex -932.234 320.183 4.0648 + endloop + endfacet + facet normal -0.390255 0.0280727 -0.920279 + outer loop + vertex -932.234 320.183 4.0648 + vertex -929.128 325.244 2.90194 + vertex -929.494 320.154 2.90197 + endloop + endfacet + facet normal -0.402784 0.0629325 -0.913129 + outer loop + vertex -929.883 340.472 4.07122 + vertex -927.265 340.303 2.90506 + vertex -930.652 335.482 4.06682 + endloop + endfacet + facet normal -0.396948 0.0581409 -0.915998 + outer loop + vertex -930.652 335.482 4.06682 + vertex -927.265 340.303 2.90506 + vertex -927.999 335.322 2.90667 + endloop + endfacet + facet normal -0.505257 0.0701988 -0.860109 + outer loop + vertex -932.681 333.816 5.12236 + vertex -932.072 336.5 4.98385 + vertex -930.652 335.482 4.06682 + endloop + endfacet + facet normal -0.512835 0.0864191 -0.854127 + outer loop + vertex -931.932 338.773 5.12966 + vertex -929.883 340.472 4.07122 + vertex -932.072 336.5 4.98385 + endloop + endfacet + facet normal -0.500873 0.0780168 -0.861998 + outer loop + vertex -929.883 340.472 4.07122 + vertex -930.652 335.482 4.06682 + vertex -932.072 336.5 4.98385 + endloop + endfacet + facet normal -0.501989 0.0548899 -0.86313 + outer loop + vertex -933.315 328.773 5.12121 + vertex -932.769 331.523 4.97817 + vertex -931.31 330.455 4.06176 + endloop + endfacet + facet normal -0.507222 0.0734977 -0.858676 + outer loop + vertex -932.681 333.816 5.12236 + vertex -930.652 335.482 4.06682 + vertex -932.769 331.523 4.97817 + endloop + endfacet + facet normal -0.495817 0.0657304 -0.865936 + outer loop + vertex -930.652 335.482 4.06682 + vertex -931.31 330.455 4.06176 + vertex -932.769 331.523 4.97817 + endloop + endfacet + facet normal -0.397331 0.0528975 -0.91615 + outer loop + vertex -930.652 335.482 4.06682 + vertex -927.999 335.322 2.90667 + vertex -931.31 330.455 4.06176 + endloop + endfacet + facet normal -0.393289 0.0496919 -0.918071 + outer loop + vertex -931.31 330.455 4.06176 + vertex -927.999 335.322 2.90667 + vertex -928.624 330.308 2.90331 + endloop + endfacet + facet normal -0.406484 0.0776784 -0.91035 + outer loop + vertex -927.978 350.553 4.05679 + vertex -925.463 350.298 2.91204 + vertex -928.985 345.51 4.07598 + endloop + endfacet + facet normal -0.405286 0.0766461 -0.910971 + outer loop + vertex -928.985 345.51 4.07598 + vertex -925.463 350.298 2.91204 + vertex -926.413 345.294 2.9136 + endloop + endfacet + facet normal -0.510741 0.0902526 -0.854984 + outer loop + vertex -931.048 343.836 5.13212 + vertex -930.295 346.608 4.97481 + vertex -928.985 345.51 4.07598 + endloop + endfacet + facet normal -0.510037 0.100816 -0.854224 + outer loop + vertex -930.021 348.97 5.08977 + vertex -927.978 350.553 4.05679 + vertex -930.295 346.608 4.97481 + endloop + endfacet + facet normal -0.505892 0.0977254 -0.857043 + outer loop + vertex -927.978 350.553 4.05679 + vertex -928.985 345.51 4.07598 + vertex -930.295 346.608 4.97481 + endloop + endfacet + facet normal -0.51092 0.0831958 -0.855593 + outer loop + vertex -931.932 338.773 5.12966 + vertex -931.258 341.5 4.99242 + vertex -929.883 340.472 4.07122 + endloop + endfacet + facet normal -0.514693 0.0970977 -0.851859 + outer loop + vertex -931.048 343.836 5.13212 + vertex -928.985 345.51 4.07598 + vertex -931.258 341.5 4.99242 + endloop + endfacet + facet normal -0.506328 0.0910617 -0.85752 + outer loop + vertex -928.985 345.51 4.07598 + vertex -929.883 340.472 4.07122 + vertex -931.258 341.5 4.99242 + endloop + endfacet + facet normal -0.405637 0.0731644 -0.911101 + outer loop + vertex -928.985 345.51 4.07598 + vertex -926.413 345.294 2.9136 + vertex -929.883 340.472 4.07122 + endloop + endfacet + facet normal -0.40219 0.0702627 -0.912856 + outer loop + vertex -929.883 340.472 4.07122 + vertex -926.413 345.294 2.9136 + vertex -927.265 340.303 2.90506 + endloop + endfacet + facet normal -0.403357 0.0888835 -0.910716 + outer loop + vertex -925.725 360.345 3.98166 + vertex -923.315 360.16 2.89621 + vertex -926.909 355.483 4.03125 + endloop + endfacet + facet normal -0.403727 0.0892154 -0.910519 + outer loop + vertex -926.909 355.483 4.03125 + vertex -923.315 360.16 2.89621 + vertex -924.427 355.26 2.90897 + endloop + endfacet + facet normal -0.52119 0.112814 -0.845951 + outer loop + vertex -928.957 353.976 5.09234 + vertex -928.157 356.578 4.94647 + vertex -926.909 355.483 4.03125 + endloop + endfacet + facet normal -0.5303 0.127678 -0.838141 + outer loop + vertex -927.821 358.831 5.07727 + vertex -925.725 360.345 3.98166 + vertex -928.157 356.578 4.94647 + endloop + endfacet + facet normal -0.518068 0.11745 -0.847237 + outer loop + vertex -925.725 360.345 3.98166 + vertex -926.909 355.483 4.03125 + vertex -928.157 356.578 4.94647 + endloop + endfacet + facet normal -0.51053 0.101715 -0.853823 + outer loop + vertex -930.021 348.97 5.08977 + vertex -929.24 351.684 4.94605 + vertex -927.978 350.553 4.05679 + endloop + endfacet + facet normal -0.524035 0.118464 -0.843417 + outer loop + vertex -928.957 353.976 5.09234 + vertex -926.909 355.483 4.03125 + vertex -929.24 351.684 4.94605 + endloop + endfacet + facet normal -0.507773 0.105701 -0.854982 + outer loop + vertex -926.909 355.483 4.03125 + vertex -927.978 350.553 4.05679 + vertex -929.24 351.684 4.94605 + endloop + endfacet + facet normal -0.404415 0.0829945 -0.910802 + outer loop + vertex -926.909 355.483 4.03125 + vertex -924.427 355.26 2.90897 + vertex -927.978 350.553 4.05679 + endloop + endfacet + facet normal -0.405721 0.0841478 -0.910115 + outer loop + vertex -927.978 350.553 4.05679 + vertex -924.427 355.26 2.90897 + vertex -925.463 350.298 2.91204 + endloop + endfacet + facet normal -0.410788 0.113436 -0.904647 + outer loop + vertex -922.91 369.911 3.80726 + vertex -920.755 369.963 2.83513 + vertex -924.162 365.292 3.79638 + endloop + endfacet + facet normal -0.395971 0.100974 -0.912694 + outer loop + vertex -924.162 365.292 3.79638 + vertex -920.755 369.963 2.83513 + vertex -922.071 365.059 2.86326 + endloop + endfacet + facet normal -0.568536 0.175476 -0.803726 + outer loop + vertex -924.754 369.694 5.06398 + vertex -922.91 369.911 3.80726 + vertex -925.795 365.496 4.88392 + endloop + endfacet + facet normal -0.535442 0.147041 -0.831673 + outer loop + vertex -925.795 365.496 4.88392 + vertex -922.91 369.911 3.80726 + vertex -924.162 365.292 3.79638 + endloop + endfacet + facet normal -0.52944 0.125898 -0.838954 + outer loop + vertex -927.821 358.831 5.07727 + vertex -926.818 361.722 4.87788 + vertex -925.725 360.345 3.98166 + endloop + endfacet + facet normal -0.535539 0.146474 -0.831711 + outer loop + vertex -925.795 365.496 4.88392 + vertex -924.162 365.292 3.79638 + vertex -926.818 361.722 4.87788 + endloop + endfacet + facet normal -0.522424 0.133549 -0.842163 + outer loop + vertex -924.162 365.292 3.79638 + vertex -925.725 360.345 3.98166 + vertex -926.818 361.722 4.87788 + endloop + endfacet + facet normal -0.397249 0.0913346 -0.913155 + outer loop + vertex -924.162 365.292 3.79638 + vertex -922.071 365.059 2.86326 + vertex -925.725 360.345 3.98166 + endloop + endfacet + facet normal -0.402613 0.0961689 -0.910304 + outer loop + vertex -925.725 360.345 3.98166 + vertex -922.071 365.059 2.86326 + vertex -923.315 360.16 2.89621 + endloop + endfacet + facet normal -0.443667 0.134022 -0.886114 + outer loop + vertex -920.176 379.707 3.90663 + vertex -918.007 379.865 2.8446 + vertex -921.613 374.715 3.87104 + endloop + endfacet + facet normal -0.430999 0.123611 -0.893846 + outer loop + vertex -921.613 374.715 3.87104 + vertex -918.007 379.865 2.8446 + vertex -919.424 374.883 2.83913 + endloop + endfacet + facet normal -0.601337 0.18412 -0.777491 + outer loop + vertex -922.012 379.507 5.27955 + vertex -920.176 379.707 3.90663 + vertex -923.501 374.432 5.22967 + endloop + endfacet + facet normal -0.592057 0.176024 -0.786438 + outer loop + vertex -923.501 374.432 5.22967 + vertex -920.176 379.707 3.90663 + vertex -921.613 374.715 3.87104 + endloop + endfacet + facet normal -0.591979 0.183956 -0.784679 + outer loop + vertex -923.501 374.432 5.22967 + vertex -921.613 374.715 3.87104 + vertex -924.754 369.694 5.06398 + endloop + endfacet + facet normal -0.56873 0.16436 -0.805935 + outer loop + vertex -924.754 369.694 5.06398 + vertex -921.613 374.715 3.87104 + vertex -922.91 369.911 3.80726 + endloop + endfacet + facet normal -0.431039 0.128317 -0.893163 + outer loop + vertex -921.613 374.715 3.87104 + vertex -919.424 374.883 2.83913 + vertex -922.91 369.911 3.80726 + endloop + endfacet + facet normal -0.410829 0.111877 -0.904822 + outer loop + vertex -922.91 369.911 3.80726 + vertex -919.424 374.883 2.83913 + vertex -920.755 369.963 2.83513 + endloop + endfacet + facet normal -0.452974 0.144579 -0.879722 + outer loop + vertex -917.035 389.639 3.88163 + vertex -914.953 389.708 2.8211 + vertex -918.636 384.723 3.89825 + endloop + endfacet + facet normal -0.447174 0.139476 -0.883505 + outer loop + vertex -918.636 384.723 3.89825 + vertex -914.953 389.708 2.8211 + vertex -916.505 384.829 2.8365 + endloop + endfacet + facet normal -0.619716 0.202451 -0.758265 + outer loop + vertex -918.798 389.476 5.27972 + vertex -917.035 389.639 3.88163 + vertex -920.427 384.542 5.29369 + endloop + endfacet + facet normal -0.614729 0.197662 -0.763569 + outer loop + vertex -920.427 384.542 5.29369 + vertex -917.035 389.639 3.88163 + vertex -918.636 384.723 3.89825 + endloop + endfacet + facet normal -0.614851 0.195655 -0.763987 + outer loop + vertex -920.427 384.542 5.29369 + vertex -918.636 384.723 3.89825 + vertex -922.012 379.507 5.27955 + endloop + endfacet + facet normal -0.601372 0.183311 -0.777656 + outer loop + vertex -922.012 379.507 5.27955 + vertex -918.636 384.723 3.89825 + vertex -920.176 379.707 3.90663 + endloop + endfacet + facet normal -0.447256 0.135823 -0.884033 + outer loop + vertex -918.636 384.723 3.89825 + vertex -916.505 384.829 2.8365 + vertex -920.176 379.707 3.90663 + endloop + endfacet + facet normal -0.443668 0.132778 -0.886301 + outer loop + vertex -920.176 379.707 3.90663 + vertex -916.505 384.829 2.8365 + vertex -918.007 379.865 2.8446 + endloop + endfacet + facet normal -0.464546 0.161557 -0.870687 + outer loop + vertex -913.727 399.235 3.85763 + vertex -911.75 399.254 2.80659 + vertex -915.401 394.459 3.86467 + endloop + endfacet + facet normal -0.459232 0.156695 -0.874387 + outer loop + vertex -915.401 394.459 3.86467 + vertex -911.75 399.254 2.80659 + vertex -913.371 394.504 2.80658 + endloop + endfacet + facet normal -0.635883 0.227268 -0.737565 + outer loop + vertex -915.403 399.098 5.26034 + vertex -913.727 399.235 3.85763 + vertex -917.121 394.31 5.26665 + endloop + endfacet + facet normal -0.62772 0.218938 -0.747016 + outer loop + vertex -917.121 394.31 5.26665 + vertex -913.727 399.235 3.85763 + vertex -915.401 394.459 3.86467 + endloop + endfacet + facet normal -0.627998 0.215826 -0.747688 + outer loop + vertex -917.121 394.31 5.26665 + vertex -915.401 394.459 3.86467 + vertex -918.798 389.476 5.27972 + endloop + endfacet + facet normal -0.619362 0.207219 -0.757265 + outer loop + vertex -918.798 389.476 5.27972 + vertex -915.401 394.459 3.86467 + vertex -917.035 389.639 3.88163 + endloop + endfacet + facet normal -0.459456 0.152617 -0.87499 + outer loop + vertex -915.401 394.459 3.86467 + vertex -913.371 394.504 2.80658 + vertex -917.035 389.639 3.88163 + endloop + endfacet + facet normal -0.452889 0.146694 -0.879416 + outer loop + vertex -917.035 389.639 3.88163 + vertex -913.371 394.504 2.80658 + vertex -914.953 389.708 2.8211 + endloop + endfacet + facet normal -0.487137 0.181322 -0.854295 + outer loop + vertex -910.206 408.853 3.86632 + vertex -908.358 408.831 2.80811 + vertex -911.996 404.023 3.86222 + endloop + endfacet + facet normal -0.476448 0.171474 -0.862319 + outer loop + vertex -911.996 404.023 3.86222 + vertex -908.358 408.831 2.80811 + vertex -910.084 404.024 2.80596 + endloop + endfacet + facet normal -0.650152 0.247916 -0.71822 + outer loop + vertex -911.789 408.746 5.26253 + vertex -910.206 408.853 3.86632 + vertex -913.631 403.901 5.25775 + endloop + endfacet + facet normal -0.640796 0.238182 -0.729829 + outer loop + vertex -913.631 403.901 5.25775 + vertex -910.206 408.853 3.86632 + vertex -911.996 404.023 3.86222 + endloop + endfacet + facet normal -0.641034 0.236122 -0.730289 + outer loop + vertex -913.631 403.901 5.25775 + vertex -911.996 404.023 3.86222 + vertex -915.403 399.098 5.26034 + endloop + endfacet + facet normal -0.635552 0.230465 -0.736857 + outer loop + vertex -915.403 399.098 5.26034 + vertex -911.996 404.023 3.86222 + vertex -913.727 399.235 3.85763 + endloop + endfacet + facet normal -0.476318 0.173021 -0.862082 + outer loop + vertex -911.996 404.023 3.86222 + vertex -910.084 404.024 2.80596 + vertex -913.727 399.235 3.85763 + endloop + endfacet + facet normal -0.464504 0.162164 -0.870597 + outer loop + vertex -913.727 399.235 3.85763 + vertex -910.084 404.024 2.80596 + vertex -911.75 399.254 2.80659 + endloop + endfacet + facet normal -0.504777 0.196981 -0.840475 + outer loop + vertex -906.497 418.501 3.86792 + vertex -904.769 418.439 2.81577 + vertex -908.366 413.7 3.8655 + endloop + endfacet + facet normal -0.494195 0.187063 -0.848987 + outer loop + vertex -908.366 413.7 3.8655 + vertex -904.769 418.439 2.81577 + vertex -906.577 413.654 2.81369 + endloop + endfacet + facet normal -0.666466 0.264513 -0.697034 + outer loop + vertex -907.983 418.423 5.25928 + vertex -906.497 418.501 3.86792 + vertex -909.898 413.606 5.26251 + endloop + endfacet + facet normal -0.659733 0.257252 -0.706098 + outer loop + vertex -909.898 413.606 5.26251 + vertex -906.497 418.501 3.86792 + vertex -908.366 413.7 3.8655 + endloop + endfacet + facet normal -0.659815 0.256688 -0.706226 + outer loop + vertex -909.898 413.606 5.26251 + vertex -908.366 413.7 3.8655 + vertex -911.789 408.746 5.26253 + endloop + endfacet + facet normal -0.650316 0.246663 -0.718503 + outer loop + vertex -911.789 408.746 5.26253 + vertex -908.366 413.7 3.8655 + vertex -910.206 408.853 3.86632 + endloop + endfacet + facet normal -0.494158 0.187381 -0.848938 + outer loop + vertex -908.366 413.7 3.8655 + vertex -906.577 413.654 2.81369 + vertex -910.206 408.853 3.86632 + endloop + endfacet + facet normal -0.487178 0.180917 -0.854358 + outer loop + vertex -910.206 408.853 3.86632 + vertex -906.577 413.654 2.81369 + vertex -908.358 408.831 2.80811 + endloop + endfacet + facet normal -0.528604 0.21277 -0.821771 + outer loop + vertex -902.753 427.846 3.86158 + vertex -901.148 427.761 2.80709 + vertex -904.625 423.213 3.86631 + endloop + endfacet + facet normal -0.5168 0.201341 -0.832093 + outer loop + vertex -904.625 423.213 3.86631 + vertex -901.148 427.761 2.80709 + vertex -902.957 423.141 2.81341 + endloop + endfacet + facet normal -0.689415 0.286024 -0.665505 + outer loop + vertex -904.127 427.798 5.26432 + vertex -902.753 427.846 3.86158 + vertex -906.054 423.149 5.26305 + endloop + endfacet + facet normal -0.678493 0.273484 -0.681802 + outer loop + vertex -906.054 423.149 5.26305 + vertex -902.753 427.846 3.86158 + vertex -904.625 423.213 3.86631 + endloop + endfacet + facet normal -0.677841 0.277163 -0.680965 + outer loop + vertex -906.054 423.149 5.26305 + vertex -904.625 423.213 3.86631 + vertex -907.983 418.423 5.25928 + endloop + endfacet + facet normal -0.666465 0.264517 -0.697033 + outer loop + vertex -907.983 418.423 5.25928 + vertex -904.625 423.213 3.86631 + vertex -906.497 418.501 3.86792 + endloop + endfacet + facet normal -0.516307 0.20482 -0.83155 + outer loop + vertex -904.625 423.213 3.86631 + vertex -902.957 423.141 2.81341 + vertex -906.497 418.501 3.86792 + endloop + endfacet + facet normal -0.505142 0.194178 -0.840908 + outer loop + vertex -906.497 418.501 3.86792 + vertex -902.957 423.141 2.81341 + vertex -904.769 418.439 2.81577 + endloop + endfacet + facet normal -0.553499 0.230156 -0.800417 + outer loop + vertex -898.924 437.127 3.87071 + vertex -897.454 436.994 2.81595 + vertex -900.856 432.462 3.86523 + endloop + endfacet + facet normal -0.541285 0.218304 -0.812006 + outer loop + vertex -900.856 432.462 3.86523 + vertex -897.454 436.994 2.81595 + vertex -899.318 432.353 2.8102 + endloop + endfacet + facet normal -0.707664 0.301585 -0.638952 + outer loop + vertex -900.193 437.112 5.26872 + vertex -898.924 437.127 3.87071 + vertex -902.182 432.433 5.26278 + endloop + endfacet + facet normal -0.69747 0.289607 -0.655488 + outer loop + vertex -902.182 432.433 5.26278 + vertex -898.924 437.127 3.87071 + vertex -900.856 432.462 3.86523 + endloop + endfacet + facet normal -0.696921 0.29222 -0.654912 + outer loop + vertex -902.182 432.433 5.26278 + vertex -900.856 432.462 3.86523 + vertex -904.127 427.798 5.26432 + endloop + endfacet + facet normal -0.689825 0.283925 -0.665979 + outer loop + vertex -904.127 427.798 5.26432 + vertex -900.856 432.462 3.86523 + vertex -902.753 427.846 3.86158 + endloop + endfacet + facet normal -0.540509 0.222697 -0.81133 + outer loop + vertex -900.856 432.462 3.86523 + vertex -899.318 432.353 2.8102 + vertex -902.753 427.846 3.86158 + endloop + endfacet + facet normal -0.528832 0.211308 -0.822001 + outer loop + vertex -902.753 427.846 3.86158 + vertex -899.318 432.353 2.8102 + vertex -901.148 427.761 2.80709 + endloop + endfacet + facet normal -0.583204 0.246344 -0.774072 + outer loop + vertex -894.952 446.576 3.87156 + vertex -893.641 446.385 2.82316 + vertex -896.955 441.844 3.8749 + endloop + endfacet + facet normal -0.56964 0.23319 -0.78812 + outer loop + vertex -896.955 441.844 3.8749 + vertex -893.641 446.385 2.82316 + vertex -895.56 441.689 2.82089 + endloop + endfacet + facet normal -0.731135 0.316787 -0.604224 + outer loop + vertex -896.089 446.608 5.26501 + vertex -894.952 446.576 3.87156 + vertex -898.159 441.848 5.2733 + endloop + endfacet + facet normal -0.721355 0.304935 -0.621822 + outer loop + vertex -898.159 441.848 5.2733 + vertex -894.952 446.576 3.87156 + vertex -896.955 441.844 3.8749 + endloop + endfacet + facet normal -0.720121 0.309947 -0.620772 + outer loop + vertex -898.159 441.848 5.2733 + vertex -896.955 441.844 3.8749 + vertex -900.193 437.112 5.26872 + endloop + endfacet + facet normal -0.708811 0.29653 -0.640045 + outer loop + vertex -900.193 437.112 5.26872 + vertex -896.955 441.844 3.8749 + vertex -898.924 437.127 3.87071 + endloop + endfacet + facet normal -0.568567 0.238103 -0.787425 + outer loop + vertex -896.955 441.844 3.8749 + vertex -895.56 441.689 2.82089 + vertex -898.924 437.127 3.87071 + endloop + endfacet + facet normal -0.554588 0.224615 -0.801237 + outer loop + vertex -898.924 437.127 3.87071 + vertex -895.56 441.689 2.82089 + vertex -897.454 436.994 2.81595 + endloop + endfacet + facet normal -0.612527 0.264922 -0.744733 + outer loop + vertex -890.899 455.932 3.85365 + vertex -889.683 455.788 2.80283 + vertex -892.919 451.286 3.86288 + endloop + endfacet + facet normal -0.60065 0.253175 -0.758368 + outer loop + vertex -892.919 451.286 3.86288 + vertex -889.683 455.788 2.80283 + vertex -891.685 451.068 2.81254 + endloop + endfacet + facet normal -0.749998 0.332761 -0.57164 + outer loop + vertex -891.922 456.003 5.23725 + vertex -890.899 455.932 3.85365 + vertex -894.001 451.342 5.25175 + endloop + endfacet + facet normal -0.740918 0.32107 -0.589876 + outer loop + vertex -894.001 451.342 5.25175 + vertex -890.899 455.932 3.85365 + vertex -892.919 451.286 3.86288 + endloop + endfacet + facet normal -0.739847 0.324777 -0.589191 + outer loop + vertex -894.001 451.342 5.25175 + vertex -892.919 451.286 3.86288 + vertex -896.089 446.608 5.26501 + endloop + endfacet + facet normal -0.731715 0.314634 -0.604648 + outer loop + vertex -896.089 446.608 5.26501 + vertex -892.919 451.286 3.86288 + vertex -894.952 446.576 3.87156 + endloop + endfacet + facet normal -0.599509 0.257303 -0.757881 + outer loop + vertex -892.919 451.286 3.86288 + vertex -891.685 451.068 2.81254 + vertex -894.952 446.576 3.87156 + endloop + endfacet + facet normal -0.584221 0.242245 -0.774598 + outer loop + vertex -894.952 446.576 3.87156 + vertex -891.685 451.068 2.81254 + vertex -893.641 446.385 2.82316 + endloop + endfacet + facet normal -0.66738 0.300979 -0.681187 + outer loop + vertex -886.951 464.78 3.83768 + vertex -886.427 463.999 2.97957 + vertex -888.967 460.369 3.86411 + endloop + endfacet + facet normal -0.636218 0.268958 -0.72311 + outer loop + vertex -888.967 460.369 3.86411 + vertex -886.427 463.999 2.97957 + vertex -887.786 460.399 2.83663 + endloop + endfacet + facet normal -0.769057 0.353572 -0.532484 + outer loop + vertex -887.713 465.188 5.20924 + vertex -886.951 464.78 3.83768 + vertex -889.838 460.594 5.2278 + endloop + endfacet + facet normal -0.763885 0.345909 -0.544818 + outer loop + vertex -889.838 460.594 5.2278 + vertex -886.951 464.78 3.83768 + vertex -888.967 460.369 3.86411 + endloop + endfacet + facet normal -0.763993 0.345633 -0.544841 + outer loop + vertex -889.838 460.594 5.2278 + vertex -888.967 460.369 3.86411 + vertex -891.922 456.003 5.23725 + endloop + endfacet + facet normal -0.751337 0.3284 -0.572404 + outer loop + vertex -891.922 456.003 5.23725 + vertex -888.967 460.369 3.86411 + vertex -890.899 455.932 3.85365 + endloop + endfacet + facet normal -0.634667 0.277965 -0.721064 + outer loop + vertex -888.967 460.369 3.86411 + vertex -887.786 460.399 2.83663 + vertex -890.899 455.932 3.85365 + endloop + endfacet + facet normal -0.614207 0.258094 -0.745746 + outer loop + vertex -890.899 455.932 3.85365 + vertex -887.786 460.399 2.83663 + vertex -889.683 455.788 2.80283 + endloop + endfacet + facet normal -0.658035 0.308714 -0.686794 + outer loop + vertex -882.629 473.948 3.79821 + vertex -882.178 472.807 2.85319 + vertex -884.813 469.321 3.81138 + endloop + endfacet + facet normal -0.646641 0.295594 -0.703192 + outer loop + vertex -884.813 469.321 3.81138 + vertex -882.178 472.807 2.85319 + vertex -884.086 468.486 2.79143 + endloop + endfacet + facet normal -0.775983 0.371903 -0.509449 + outer loop + vertex -883.333 474.418 5.21468 + vertex -882.629 473.948 3.79821 + vertex -885.539 469.805 5.20578 + endloop + endfacet + facet normal -0.769698 0.361891 -0.525928 + outer loop + vertex -885.539 469.805 5.20578 + vertex -882.629 473.948 3.79821 + vertex -884.813 469.321 3.81138 + endloop + endfacet + facet normal -0.769605 0.362069 -0.525941 + outer loop + vertex -885.539 469.805 5.20578 + vertex -884.813 469.321 3.81138 + vertex -887.713 465.188 5.20924 + endloop + endfacet + facet normal -0.766942 0.357945 -0.532611 + outer loop + vertex -887.713 465.188 5.20924 + vertex -884.813 469.321 3.81138 + vertex -886.951 464.78 3.83768 + endloop + endfacet + facet normal -0.643993 0.299074 -0.704151 + outer loop + vertex -884.813 469.321 3.81138 + vertex -884.086 468.486 2.79143 + vertex -886.951 464.78 3.83768 + endloop + endfacet + facet normal -0.656381 0.313748 -0.686094 + outer loop + vertex -886.951 464.78 3.83768 + vertex -884.086 468.486 2.79143 + vertex -886.427 463.999 2.97957 + endloop + endfacet + facet normal -0.694588 0.324872 -0.641877 + outer loop + vertex -878.287 483.174 3.78052 + vertex -877.864 482.197 2.82813 + vertex -880.444 478.589 3.79415 + endloop + endfacet + facet normal -0.666555 0.293176 -0.685384 + outer loop + vertex -880.444 478.589 3.79415 + vertex -877.864 482.197 2.82813 + vertex -879.722 477.679 2.70269 + endloop + endfacet + facet normal -0.803375 0.388689 -0.45112 + outer loop + vertex -878.902 483.553 5.2013 + vertex -878.287 483.174 3.78052 + vertex -881.114 478.996 5.2162 + endloop + endfacet + facet normal -0.793943 0.372093 -0.480835 + outer loop + vertex -881.114 478.996 5.2162 + vertex -878.287 483.174 3.78052 + vertex -880.444 478.589 3.79415 + endloop + endfacet + facet normal -0.788719 0.382422 -0.481328 + outer loop + vertex -881.114 478.996 5.2162 + vertex -880.444 478.589 3.79415 + vertex -883.333 474.418 5.21468 + endloop + endfacet + facet normal -0.778951 0.366219 -0.509038 + outer loop + vertex -883.333 474.418 5.21468 + vertex -880.444 478.589 3.79415 + vertex -882.629 473.948 3.79821 + endloop + endfacet + facet normal -0.655125 0.307774 -0.68999 + outer loop + vertex -880.444 478.589 3.79415 + vertex -879.722 477.679 2.70269 + vertex -882.629 473.948 3.79821 + endloop + endfacet + facet normal -0.656784 0.309796 -0.687503 + outer loop + vertex -882.629 473.948 3.79821 + vertex -879.722 477.679 2.70269 + vertex -882.178 472.807 2.85319 + endloop + endfacet + facet normal -0.814576 0.211984 -0.539933 + outer loop + vertex -874.945 493.139 3.79698 + vertex -874.31 492.875 2.73455 + vertex -876.277 487.954 3.77034 + endloop + endfacet + facet normal -0.791958 0.194788 -0.578671 + outer loop + vertex -876.277 487.954 3.77034 + vertex -874.31 492.875 2.73455 + vertex -875.673 487.038 2.63576 + endloop + endfacet + facet normal -0.89011 0.239695 -0.387622 + outer loop + vertex -875.435 493.344 5.04799 + vertex -874.945 493.139 3.79698 + vertex -876.87 488.24 5.18751 + endloop + endfacet + facet normal -0.880827 0.228357 -0.414724 + outer loop + vertex -876.87 488.24 5.18751 + vertex -874.945 493.139 3.79698 + vertex -876.277 487.954 3.77034 + endloop + endfacet + facet normal -0.832716 0.359644 -0.420999 + outer loop + vertex -876.87 488.24 5.18751 + vertex -876.277 487.954 3.77034 + vertex -878.902 483.553 5.2013 + endloop + endfacet + facet normal -0.824196 0.345579 -0.448638 + outer loop + vertex -878.902 483.553 5.2013 + vertex -876.277 487.954 3.77034 + vertex -878.287 483.174 3.78052 + endloop + endfacet + facet normal -0.719369 0.301127 -0.625964 + outer loop + vertex -876.277 487.954 3.77034 + vertex -875.673 487.038 2.63576 + vertex -878.287 483.174 3.78052 + endloop + endfacet + facet normal -0.718603 0.30022 -0.627278 + outer loop + vertex -878.287 483.174 3.78052 + vertex -875.673 487.038 2.63576 + vertex -877.864 482.197 2.82813 + endloop + endfacet + facet normal -0.184514 -0.135713 -0.973415 + outer loop + vertex -876.373 200.247 1.94809 + vertex -874.522 201.314 1.44833 + vertex -874.807 198.811 1.85143 + endloop + endfacet + facet normal -0.173842 -0.137212 -0.975168 + outer loop + vertex -874.807 198.811 1.85143 + vertex -874.522 201.314 1.44833 + vertex -873.529 198.903 1.61072 + endloop + endfacet + facet normal -0.267603 -0.225447 -0.936783 + outer loop + vertex -877.618 198.197 2.79715 + vertex -876.373 200.247 1.94809 + vertex -875.666 196.976 2.53324 + endloop + endfacet + facet normal -0.264086 -0.224889 -0.937914 + outer loop + vertex -875.666 196.976 2.53324 + vertex -876.373 200.247 1.94809 + vertex -874.807 198.811 1.85143 + endloop + endfacet + facet normal -0.179071 -0.159144 -0.970879 + outer loop + vertex -880.85 204.736 2.07292 + vertex -879.269 206.318 1.52198 + vertex -878.371 202.101 2.04755 + endloop + endfacet + facet normal -0.161153 -0.155785 -0.974557 + outer loop + vertex -878.371 202.101 2.04755 + vertex -879.269 206.318 1.52198 + vertex -876.836 204.47 1.41507 + endloop + endfacet + facet normal -0.256865 -0.234574 -0.937547 + outer loop + vertex -882.456 203.089 2.92487 + vertex -880.85 204.736 2.07292 + vertex -879.712 200.122 2.91547 + endloop + endfacet + facet normal -0.259394 -0.23505 -0.936732 + outer loop + vertex -879.712 200.122 2.91547 + vertex -880.85 204.736 2.07292 + vertex -878.371 202.101 2.04755 + endloop + endfacet + facet normal -0.265199 -0.230861 -0.936148 + outer loop + vertex -879.712 200.122 2.91547 + vertex -878.371 202.101 2.04755 + vertex -877.618 198.197 2.79715 + endloop + endfacet + facet normal -0.260348 -0.230217 -0.937667 + outer loop + vertex -877.618 198.197 2.79715 + vertex -878.371 202.101 2.04755 + vertex -876.373 200.247 1.94809 + endloop + endfacet + facet normal -0.180842 -0.142648 -0.973112 + outer loop + vertex -878.371 202.101 2.04755 + vertex -876.836 204.47 1.41507 + vertex -876.373 200.247 1.94809 + endloop + endfacet + facet normal -0.180472 -0.142617 -0.973186 + outer loop + vertex -876.373 200.247 1.94809 + vertex -876.836 204.47 1.41507 + vertex -874.522 201.314 1.44833 + endloop + endfacet + facet normal -0.176609 -0.152488 -0.972397 + outer loop + vertex -887.036 212.006 2.03624 + vertex -885.051 213.137 1.49837 + vertex -883.839 208.177 2.05586 + endloop + endfacet + facet normal -0.163125 -0.149508 -0.975212 + outer loop + vertex -883.839 208.177 2.05586 + vertex -885.051 213.137 1.49837 + vertex -881.958 210.144 1.43984 + endloop + endfacet + facet normal -0.264777 -0.225689 -0.937527 + outer loop + vertex -888.933 210.626 2.904 + vertex -887.036 212.006 2.03624 + vertex -885.662 206.762 2.91034 + endloop + endfacet + facet normal -0.264365 -0.225604 -0.937664 + outer loop + vertex -885.662 206.762 2.91034 + vertex -887.036 212.006 2.03624 + vertex -883.839 208.177 2.05586 + endloop + endfacet + facet normal -0.260239 -0.230847 -0.937542 + outer loop + vertex -885.662 206.762 2.91034 + vertex -883.839 208.177 2.05586 + vertex -882.456 203.089 2.92487 + endloop + endfacet + facet normal -0.26056 -0.230916 -0.937436 + outer loop + vertex -882.456 203.089 2.92487 + vertex -883.839 208.177 2.05586 + vertex -880.85 204.736 2.07292 + endloop + endfacet + facet normal -0.164773 -0.147922 -0.975176 + outer loop + vertex -883.839 208.177 2.05586 + vertex -881.958 210.144 1.43984 + vertex -880.85 204.736 2.07292 + endloop + endfacet + facet normal -0.186335 -0.151814 -0.970686 + outer loop + vertex -880.85 204.736 2.07292 + vertex -881.958 210.144 1.43984 + vertex -879.269 206.318 1.52198 + endloop + endfacet + facet normal -0.181432 -0.141456 -0.973177 + outer loop + vertex -893.25 219.829 2.02994 + vertex -891.165 220.918 1.48293 + vertex -890.202 215.915 2.0307 + endloop + endfacet + facet normal -0.168536 -0.139264 -0.975808 + outer loop + vertex -890.202 215.915 2.0307 + vertex -891.165 220.918 1.48293 + vertex -888.015 217.621 1.40957 + endloop + endfacet + facet normal -0.270268 -0.211104 -0.939356 + outer loop + vertex -895.198 218.429 2.90535 + vertex -893.25 219.829 2.02994 + vertex -892.113 214.501 2.90036 + endloop + endfacet + facet normal -0.271052 -0.211229 -0.939102 + outer loop + vertex -892.113 214.501 2.90036 + vertex -893.25 219.829 2.02994 + vertex -890.202 215.915 2.0307 + endloop + endfacet + facet normal -0.265432 -0.218751 -0.938985 + outer loop + vertex -892.113 214.501 2.90036 + vertex -890.202 215.915 2.0307 + vertex -888.933 210.626 2.904 + endloop + endfacet + facet normal -0.269366 -0.219482 -0.937694 + outer loop + vertex -888.933 210.626 2.904 + vertex -890.202 215.915 2.0307 + vertex -887.036 212.006 2.03624 + endloop + endfacet + facet normal -0.1692 -0.138414 -0.975814 + outer loop + vertex -890.202 215.915 2.0307 + vertex -888.015 217.621 1.40957 + vertex -887.036 212.006 2.03624 + endloop + endfacet + facet normal -0.183529 -0.140588 -0.972909 + outer loop + vertex -887.036 212.006 2.03624 + vertex -888.015 217.621 1.40957 + vertex -885.051 213.137 1.49837 + endloop + endfacet + facet normal -0.184091 -0.131099 -0.974127 + outer loop + vertex -899.07 227.863 2.03443 + vertex -896.863 228.839 1.4859 + vertex -896.198 223.804 2.0379 + endloop + endfacet + facet normal -0.171225 -0.129678 -0.97666 + outer loop + vertex -896.198 223.804 2.0379 + vertex -896.863 228.839 1.4859 + vertex -893.875 225.451 1.41195 + endloop + endfacet + facet normal -0.272033 -0.194568 -0.942412 + outer loop + vertex -901.206 226.628 2.90584 + vertex -899.07 227.863 2.03443 + vertex -898.235 222.474 2.90596 + endloop + endfacet + facet normal -0.274135 -0.194788 -0.941758 + outer loop + vertex -898.235 222.474 2.90596 + vertex -899.07 227.863 2.03443 + vertex -896.198 223.804 2.0379 + endloop + endfacet + facet normal -0.269333 -0.202049 -0.941614 + outer loop + vertex -898.235 222.474 2.90596 + vertex -896.198 223.804 2.0379 + vertex -895.198 218.429 2.90535 + endloop + endfacet + facet normal -0.276153 -0.202966 -0.939438 + outer loop + vertex -895.198 218.429 2.90535 + vertex -896.198 223.804 2.0379 + vertex -893.25 219.829 2.02994 + endloop + endfacet + facet normal -0.173377 -0.126652 -0.976678 + outer loop + vertex -896.198 223.804 2.0379 + vertex -893.875 225.451 1.41195 + vertex -893.25 219.829 2.02994 + endloop + endfacet + facet normal -0.188584 -0.128016 -0.973678 + outer loop + vertex -893.25 219.829 2.02994 + vertex -893.875 225.451 1.41195 + vertex -891.165 220.918 1.48293 + endloop + endfacet + facet normal -0.188235 -0.118984 -0.97489 + outer loop + vertex -904.437 236.099 2.03936 + vertex -902.102 236.939 1.48613 + vertex -901.827 231.978 2.03848 + endloop + endfacet + facet normal -0.172721 -0.118452 -0.977822 + outer loop + vertex -901.827 231.978 2.03848 + vertex -902.102 236.939 1.48613 + vertex -899.307 233.457 1.41403 + endloop + endfacet + facet normal -0.27102 -0.174894 -0.946552 + outer loop + vertex -906.735 234.991 2.90212 + vertex -904.437 236.099 2.03936 + vertex -904.049 230.814 2.90494 + endloop + endfacet + facet normal -0.276749 -0.175038 -0.944866 + outer loop + vertex -904.049 230.814 2.90494 + vertex -904.437 236.099 2.03936 + vertex -901.827 231.978 2.03848 + endloop + endfacet + facet normal -0.271571 -0.184668 -0.944535 + outer loop + vertex -904.049 230.814 2.90494 + vertex -901.827 231.978 2.03848 + vertex -901.206 226.628 2.90584 + endloop + endfacet + facet normal -0.277638 -0.185074 -0.94269 + outer loop + vertex -901.206 226.628 2.90584 + vertex -901.827 231.978 2.03848 + vertex -899.07 227.863 2.03443 + endloop + endfacet + facet normal -0.174287 -0.115799 -0.977862 + outer loop + vertex -901.827 231.978 2.03848 + vertex -899.307 233.457 1.41403 + vertex -899.07 227.863 2.03443 + endloop + endfacet + facet normal -0.190853 -0.116151 -0.974723 + outer loop + vertex -899.07 227.863 2.03443 + vertex -899.307 233.457 1.41403 + vertex -896.863 228.839 1.4859 + endloop + endfacet + facet normal -0.185469 -0.104646 -0.977062 + outer loop + vertex -909.223 244.35 2.03539 + vertex -906.76 245.074 1.49026 + vertex -906.905 240.221 2.03756 + endloop + endfacet + facet normal -0.174349 -0.105202 -0.979048 + outer loop + vertex -906.905 240.221 2.03756 + vertex -906.76 245.074 1.49026 + vertex -904.212 241.561 1.41405 + endloop + endfacet + facet normal -0.275093 -0.157459 -0.948436 + outer loop + vertex -911.668 243.386 2.90455 + vertex -909.223 244.35 2.03539 + vertex -909.267 239.179 2.90658 + endloop + endfacet + facet normal -0.279156 -0.157231 -0.947286 + outer loop + vertex -909.267 239.179 2.90658 + vertex -909.223 244.35 2.03539 + vertex -906.905 240.221 2.03756 + endloop + endfacet + facet normal -0.275404 -0.165482 -0.946978 + outer loop + vertex -909.267 239.179 2.90658 + vertex -906.905 240.221 2.03756 + vertex -906.735 234.991 2.90212 + endloop + endfacet + facet normal -0.27569 -0.165478 -0.946896 + outer loop + vertex -906.735 234.991 2.90212 + vertex -906.905 240.221 2.03756 + vertex -904.437 236.099 2.03936 + endloop + endfacet + facet normal -0.174499 -0.104905 -0.979053 + outer loop + vertex -906.905 240.221 2.03756 + vertex -904.212 241.561 1.41405 + vertex -904.437 236.099 2.03936 + endloop + endfacet + facet normal -0.193881 -0.103703 -0.975529 + outer loop + vertex -904.437 236.099 2.03936 + vertex -904.212 241.561 1.41405 + vertex -902.102 236.939 1.48613 + endloop + endfacet + facet normal -0.187381 -0.0910183 -0.978061 + outer loop + vertex -913.455 252.724 2.03855 + vertex -910.885 253.333 1.48951 + vertex -911.403 248.506 2.03803 + endloop + endfacet + facet normal -0.175742 -0.092497 -0.980081 + outer loop + vertex -911.403 248.506 2.03803 + vertex -910.885 253.333 1.48951 + vertex -908.553 249.726 1.41188 + endloop + endfacet + facet normal -0.275614 -0.135799 -0.951628 + outer loop + vertex -916.034 251.884 2.90557 + vertex -913.455 252.724 2.03855 + vertex -913.919 247.606 2.90347 + endloop + endfacet + facet normal -0.278602 -0.13539 -0.950816 + outer loop + vertex -913.919 247.606 2.90347 + vertex -913.455 252.724 2.03855 + vertex -911.403 248.506 2.03803 + endloop + endfacet + facet normal -0.274418 -0.146658 -0.950361 + outer loop + vertex -913.919 247.606 2.90347 + vertex -911.403 248.506 2.03803 + vertex -911.668 243.386 2.90455 + endloop + endfacet + facet normal -0.27972 -0.146136 -0.948895 + outer loop + vertex -911.668 243.386 2.90455 + vertex -911.403 248.506 2.03803 + vertex -909.223 244.35 2.03539 + endloop + endfacet + facet normal -0.176069 -0.0917412 -0.980094 + outer loop + vertex -911.403 248.506 2.03803 + vertex -908.553 249.726 1.41188 + vertex -909.223 244.35 2.03539 + endloop + endfacet + facet normal -0.189992 -0.0897261 -0.977677 + outer loop + vertex -909.223 244.35 2.03539 + vertex -908.553 249.726 1.41188 + vertex -906.76 245.074 1.49026 + endloop + endfacet + facet normal -0.18741 -0.0766139 -0.979289 + outer loop + vertex -917.253 261.552 2.038 + vertex -914.563 261.996 1.48847 + vertex -915.408 257.06 2.03648 + endloop + endfacet + facet normal -0.1735 -0.0792579 -0.981639 + outer loop + vertex -915.408 257.06 2.03648 + vertex -914.563 261.996 1.48847 + vertex -912.394 258.15 1.4157 + endloop + endfacet + facet normal -0.274268 -0.115683 -0.95467 + outer loop + vertex -919.979 260.887 2.90176 + vertex -917.253 261.552 2.038 + vertex -918.053 256.3 2.90439 + endloop + endfacet + facet normal -0.279867 -0.114583 -0.953176 + outer loop + vertex -918.053 256.3 2.90439 + vertex -917.253 261.552 2.038 + vertex -915.408 257.06 2.03648 + endloop + endfacet + facet normal -0.276275 -0.126562 -0.952709 + outer loop + vertex -918.053 256.3 2.90439 + vertex -915.408 257.06 2.03648 + vertex -916.034 251.884 2.90557 + endloop + endfacet + facet normal -0.278891 -0.126127 -0.952004 + outer loop + vertex -916.034 251.884 2.90557 + vertex -915.408 257.06 2.03648 + vertex -913.455 252.724 2.03855 + endloop + endfacet + facet normal -0.17369 -0.0787359 -0.981648 + outer loop + vertex -915.408 257.06 2.03648 + vertex -912.394 258.15 1.4157 + vertex -913.455 252.724 2.03855 + endloop + endfacet + facet normal -0.191317 -0.0749465 -0.978663 + outer loop + vertex -913.455 252.724 2.03855 + vertex -912.394 258.15 1.4157 + vertex -910.885 253.333 1.48951 + endloop + endfacet + facet normal -0.187572 -0.0628392 -0.980239 + outer loop + vertex -920.581 270.957 2.03572 + vertex -917.793 271.22 1.48534 + vertex -918.991 266.195 2.03673 + endloop + endfacet + facet normal -0.173673 -0.0664096 -0.982562 + outer loop + vertex -918.991 266.195 2.03673 + vertex -917.793 271.22 1.48534 + vertex -915.812 267.087 1.41451 + endloop + endfacet + facet normal -0.275534 -0.0949349 -0.956592 + outer loop + vertex -923.41 270.439 2.90177 + vertex -920.581 270.957 2.03572 + vertex -921.766 265.613 2.90733 + endloop + endfacet + facet normal -0.280092 -0.0937276 -0.955386 + outer loop + vertex -921.766 265.613 2.90733 + vertex -920.581 270.957 2.03572 + vertex -918.991 266.195 2.03673 + endloop + endfacet + facet normal -0.277824 -0.103942 -0.954992 + outer loop + vertex -921.766 265.613 2.90733 + vertex -918.991 266.195 2.03673 + vertex -919.979 260.887 2.90176 + endloop + endfacet + facet normal -0.277247 -0.104075 -0.955145 + outer loop + vertex -919.979 260.887 2.90176 + vertex -918.991 266.195 2.03673 + vertex -917.253 261.552 2.038 + endloop + endfacet + facet normal -0.173957 -0.0654062 -0.982579 + outer loop + vertex -918.991 266.195 2.03673 + vertex -915.812 267.087 1.41451 + vertex -917.253 261.552 2.038 + endloop + endfacet + facet normal -0.190123 -0.0608933 -0.97987 + outer loop + vertex -917.253 261.552 2.038 + vertex -915.812 267.087 1.41451 + vertex -914.563 261.996 1.48847 + endloop + endfacet + facet normal -0.186375 -0.0490066 -0.981256 + outer loop + vertex -923.266 280.704 2.034 + vertex -920.413 280.815 1.48667 + vertex -922.008 275.811 2.03949 + endloop + endfacet + facet normal -0.175382 -0.0527116 -0.983088 + outer loop + vertex -922.008 275.811 2.03949 + vertex -920.413 280.815 1.48667 + vertex -918.706 276.505 1.41325 + endloop + endfacet + facet normal -0.278327 -0.0725753 -0.957741 + outer loop + vertex -926.166 280.326 2.90535 + vertex -923.266 280.704 2.034 + vertex -924.874 275.36 2.90632 + endloop + endfacet + facet normal -0.27826 -0.0725983 -0.957758 + outer loop + vertex -924.874 275.36 2.90632 + vertex -923.266 280.704 2.034 + vertex -922.008 275.811 2.03949 + endloop + endfacet + facet normal -0.276777 -0.0814817 -0.957473 + outer loop + vertex -924.874 275.36 2.90632 + vertex -922.008 275.811 2.03949 + vertex -923.41 270.439 2.90177 + endloop + endfacet + facet normal -0.278233 -0.0810402 -0.957089 + outer loop + vertex -923.41 270.439 2.90177 + vertex -922.008 275.811 2.03949 + vertex -920.581 270.957 2.03572 + endloop + endfacet + facet normal -0.175768 -0.0509018 -0.983115 + outer loop + vertex -922.008 275.811 2.03949 + vertex -918.706 276.505 1.41325 + vertex -920.581 270.957 2.03572 + endloop + endfacet + facet normal -0.189268 -0.0460845 -0.980844 + outer loop + vertex -920.581 270.957 2.03572 + vertex -918.706 276.505 1.41325 + vertex -917.793 271.22 1.48534 + endloop + endfacet + facet normal -0.185468 -0.0338114 -0.982068 + outer loop + vertex -925.187 290.396 2.03491 + vertex -922.308 290.432 1.49 + vertex -924.324 285.58 2.0378 + endloop + endfacet + facet normal -0.174918 -0.0383932 -0.983834 + outer loop + vertex -924.324 285.58 2.0378 + vertex -922.308 290.432 1.49 + vertex -920.932 286.125 1.41345 + endloop + endfacet + facet normal -0.279573 -0.0494423 -0.958851 + outer loop + vertex -928.129 290.107 2.9074 + vertex -925.187 290.396 2.03491 + vertex -927.257 285.255 2.90341 + endloop + endfacet + facet normal -0.277638 -0.0503084 -0.959368 + outer loop + vertex -927.257 285.255 2.90341 + vertex -925.187 290.396 2.03491 + vertex -924.324 285.58 2.0378 + endloop + endfacet + facet normal -0.276314 -0.0615421 -0.959095 + outer loop + vertex -927.257 285.255 2.90341 + vertex -924.324 285.58 2.0378 + vertex -926.166 280.326 2.90535 + endloop + endfacet + facet normal -0.280067 -0.0600623 -0.9581 + outer loop + vertex -926.166 280.326 2.90535 + vertex -924.324 285.58 2.0378 + vertex -923.266 280.704 2.034 + endloop + endfacet + facet normal -0.175104 -0.0372522 -0.983845 + outer loop + vertex -924.324 285.58 2.0378 + vertex -920.932 286.125 1.41345 + vertex -923.266 280.704 2.034 + endloop + endfacet + facet normal -0.187151 -0.0318342 -0.981815 + outer loop + vertex -923.266 280.704 2.034 + vertex -920.932 286.125 1.41345 + vertex -920.413 280.815 1.48667 + endloop + endfacet + facet normal -0.186021 -0.0189991 -0.982362 + outer loop + vertex -926.336 299.998 2.03382 + vertex -923.458 299.964 1.48965 + vertex -925.853 295.177 2.03568 + endloop + endfacet + facet normal -0.174994 -0.0247314 -0.984259 + outer loop + vertex -925.853 295.177 2.03568 + vertex -923.458 299.964 1.48965 + vertex -922.418 295.665 1.41261 + endloop + endfacet + facet normal -0.280833 -0.0280142 -0.959348 + outer loop + vertex -929.297 299.807 2.90634 + vertex -926.336 299.998 2.03382 + vertex -928.807 294.929 2.90543 + endloop + endfacet + facet normal -0.280099 -0.0284072 -0.959551 + outer loop + vertex -928.807 294.929 2.90543 + vertex -926.336 299.998 2.03382 + vertex -925.853 295.177 2.03568 + endloop + endfacet + facet normal -0.279117 -0.0396937 -0.959436 + outer loop + vertex -928.807 294.929 2.90543 + vertex -925.853 295.177 2.03568 + vertex -928.129 290.107 2.9074 + endloop + endfacet + facet normal -0.280655 -0.038932 -0.959019 + outer loop + vertex -928.129 290.107 2.9074 + vertex -925.853 295.177 2.03568 + vertex -925.187 290.396 2.03491 + endloop + endfacet + facet normal -0.175066 -0.0242234 -0.984259 + outer loop + vertex -925.853 295.177 2.03568 + vertex -922.418 295.665 1.41261 + vertex -925.187 290.396 2.03491 + endloop + endfacet + facet normal -0.18573 -0.0184021 -0.982428 + outer loop + vertex -925.187 290.396 2.03491 + vertex -922.418 295.665 1.41261 + vertex -922.308 290.432 1.49 + endloop + endfacet + facet normal -0.191048 -0.0051517 -0.981567 + outer loop + vertex -926.779 309.948 2.03894 + vertex -923.93 309.762 1.48554 + vertex -926.641 304.922 2.03847 + endloop + endfacet + facet normal -0.177119 -0.0132401 -0.9841 + outer loop + vertex -926.641 304.922 2.03847 + vertex -923.93 309.762 1.48554 + vertex -923.189 305.289 1.41223 + endloop + endfacet + facet normal -0.280159 -0.00695316 -0.959928 + outer loop + vertex -929.747 309.91 2.9055 + vertex -926.779 309.948 2.03894 + vertex -929.614 304.805 2.90365 + endloop + endfacet + facet normal -0.279129 -0.0075709 -0.960224 + outer loop + vertex -929.614 304.805 2.90365 + vertex -926.779 309.948 2.03894 + vertex -926.641 304.922 2.03847 + endloop + endfacet + facet normal -0.278705 -0.0181727 -0.960205 + outer loop + vertex -929.614 304.805 2.90365 + vertex -926.641 304.922 2.03847 + vertex -929.297 299.807 2.90634 + endloop + endfacet + facet normal -0.281588 -0.0165379 -0.959393 + outer loop + vertex -929.297 299.807 2.90634 + vertex -926.641 304.922 2.03847 + vertex -926.336 299.998 2.03382 + endloop + endfacet + facet normal -0.177453 -0.0100629 -0.984078 + outer loop + vertex -926.641 304.922 2.03847 + vertex -923.189 305.289 1.41223 + vertex -926.336 299.998 2.03382 + endloop + endfacet + facet normal -0.185892 -0.0048641 -0.982558 + outer loop + vertex -926.336 299.998 2.03382 + vertex -923.189 305.289 1.41223 + vertex -923.458 299.964 1.48965 + endloop + endfacet + facet normal -0.190782 0.00690904 -0.981608 + outer loop + vertex -926.562 320.121 2.03563 + vertex -923.755 319.826 1.48799 + vertex -926.753 315.036 2.03703 + endloop + endfacet + facet normal -0.177713 -0.00155377 -0.984081 + outer loop + vertex -926.753 315.036 2.03703 + vertex -923.755 319.826 1.48799 + vertex -923.307 315.232 1.41436 + endloop + endfacet + facet normal -0.28323 0.0113178 -0.958985 + outer loop + vertex -929.494 320.154 2.90197 + vertex -926.562 320.121 2.03563 + vertex -929.705 315.042 2.90404 + endloop + endfacet + facet normal -0.281771 0.0103392 -0.959426 + outer loop + vertex -929.705 315.042 2.90404 + vertex -926.562 320.121 2.03563 + vertex -926.753 315.036 2.03703 + endloop + endfacet + facet normal -0.281802 0.00202113 -0.95947 + outer loop + vertex -929.705 315.042 2.90404 + vertex -926.753 315.036 2.03703 + vertex -929.747 309.91 2.9055 + endloop + endfacet + facet normal -0.280262 0.00104513 -0.959923 + outer loop + vertex -929.747 309.91 2.9055 + vertex -926.753 315.036 2.03703 + vertex -926.779 309.948 2.03894 + endloop + endfacet + facet normal -0.177828 0.000522406 -0.984061 + outer loop + vertex -926.753 315.036 2.03703 + vertex -923.307 315.232 1.41436 + vertex -926.779 309.948 2.03894 + endloop + endfacet + facet normal -0.190159 0.00890163 -0.981713 + outer loop + vertex -926.779 309.948 2.03894 + vertex -923.307 315.232 1.41436 + vertex -923.93 309.762 1.48554 + endloop + endfacet + facet normal -0.193785 0.0184139 -0.980871 + outer loop + vertex -925.746 330.2 2.03694 + vertex -923.004 329.849 1.4888 + vertex -926.22 325.18 2.03643 + endloop + endfacet + facet normal -0.180022 0.00861234 -0.983625 + outer loop + vertex -926.22 325.18 2.03643 + vertex -923.004 329.849 1.4888 + vertex -922.82 325.278 1.4151 + endloop + endfacet + facet normal -0.287076 0.0287869 -0.957475 + outer loop + vertex -928.624 330.308 2.90331 + vertex -925.746 330.2 2.03694 + vertex -929.128 325.244 2.90194 + endloop + endfacet + facet normal -0.284655 0.0269999 -0.95825 + outer loop + vertex -929.128 325.244 2.90194 + vertex -925.746 330.2 2.03694 + vertex -926.22 325.18 2.03643 + endloop + endfacet + facet normal -0.284833 0.0204875 -0.958358 + outer loop + vertex -929.128 325.244 2.90194 + vertex -926.22 325.18 2.03643 + vertex -929.494 320.154 2.90197 + endloop + endfacet + facet normal -0.283114 0.0192759 -0.958893 + outer loop + vertex -929.494 320.154 2.90197 + vertex -926.22 325.18 2.03643 + vertex -926.562 320.121 2.03563 + endloop + endfacet + facet normal -0.180119 0.0123225 -0.983568 + outer loop + vertex -926.22 325.18 2.03643 + vertex -922.82 325.278 1.4151 + vertex -926.562 320.121 2.03563 + endloop + endfacet + facet normal -0.189494 0.0193497 -0.981691 + outer loop + vertex -926.562 320.121 2.03563 + vertex -922.82 325.278 1.4151 + vertex -923.755 319.826 1.48799 + endloop + endfacet + facet normal -0.196996 0.0276796 -0.980013 + outer loop + vertex -924.455 340.133 2.03301 + vertex -921.785 339.73 1.48508 + vertex -925.156 335.182 2.03417 + endloop + endfacet + facet normal -0.183425 0.0172747 -0.982882 + outer loop + vertex -925.156 335.182 2.03417 + vertex -921.785 339.73 1.48508 + vertex -921.82 335.212 1.41208 + endloop + endfacet + facet normal -0.293686 0.0429264 -0.954938 + outer loop + vertex -927.265 340.303 2.90506 + vertex -924.455 340.133 2.03301 + vertex -927.999 335.322 2.90667 + endloop + endfacet + facet normal -0.291338 0.0410507 -0.955739 + outer loop + vertex -927.999 335.322 2.90667 + vertex -924.455 340.133 2.03301 + vertex -925.156 335.182 2.03417 + endloop + endfacet + facet normal -0.291565 0.0370235 -0.955834 + outer loop + vertex -927.999 335.322 2.90667 + vertex -925.156 335.182 2.03417 + vertex -928.624 330.308 2.90331 + endloop + endfacet + facet normal -0.286875 0.0334091 -0.957385 + outer loop + vertex -928.624 330.308 2.90331 + vertex -925.156 335.182 2.03417 + vertex -925.746 330.2 2.03694 + endloop + endfacet + facet normal -0.183445 0.0211576 -0.982802 + outer loop + vertex -925.156 335.182 2.03417 + vertex -921.82 335.212 1.41208 + vertex -925.746 330.2 2.03694 + endloop + endfacet + facet normal -0.192496 0.0284862 -0.980884 + outer loop + vertex -925.746 330.2 2.03694 + vertex -921.82 335.212 1.41208 + vertex -923.004 329.849 1.4888 + endloop + endfacet + facet normal -0.204147 0.03858 -0.97818 + outer loop + vertex -922.734 350.05 2.04346 + vertex -920.156 349.572 1.48649 + vertex -923.644 345.084 2.03744 + endloop + endfacet + facet normal -0.188376 0.0258851 -0.981756 + outer loop + vertex -923.644 345.084 2.03744 + vertex -920.156 349.572 1.48649 + vertex -920.388 345.044 1.41162 + endloop + endfacet + facet normal -0.29817 0.0563003 -0.952851 + outer loop + vertex -925.463 350.298 2.91204 + vertex -922.734 350.05 2.04346 + vertex -926.413 345.294 2.9136 + endloop + endfacet + facet normal -0.297366 0.0556251 -0.953142 + outer loop + vertex -926.413 345.294 2.9136 + vertex -922.734 350.05 2.04346 + vertex -923.644 345.084 2.03744 + endloop + endfacet + facet normal -0.297635 0.0524722 -0.953237 + outer loop + vertex -926.413 345.294 2.9136 + vertex -923.644 345.084 2.03744 + vertex -927.265 340.303 2.90506 + endloop + endfacet + facet normal -0.293276 0.0488906 -0.954777 + outer loop + vertex -927.265 340.303 2.90506 + vertex -923.644 345.084 2.03744 + vertex -924.455 340.133 2.03301 + endloop + endfacet + facet normal -0.188276 0.0317167 -0.981604 + outer loop + vertex -923.644 345.084 2.03744 + vertex -920.388 345.044 1.41162 + vertex -924.455 340.133 2.03301 + endloop + endfacet + facet normal -0.195453 0.0378649 -0.979982 + outer loop + vertex -924.455 340.133 2.03301 + vertex -920.388 345.044 1.41162 + vertex -921.785 339.73 1.48508 + endloop + endfacet + facet normal -0.207746 0.0463524 -0.977084 + outer loop + vertex -920.67 359.958 2.05646 + vertex -918.174 359.452 1.50167 + vertex -921.739 355.017 2.04931 + endloop + endfacet + facet normal -0.194401 0.0352293 -0.980289 + outer loop + vertex -921.739 355.017 2.04931 + vertex -918.174 359.452 1.50167 + vertex -918.576 354.897 1.41761 + endloop + endfacet + facet normal -0.297457 0.0649986 -0.95252 + outer loop + vertex -923.315 360.16 2.89621 + vertex -920.67 359.958 2.05646 + vertex -924.427 355.26 2.90897 + endloop + endfacet + facet normal -0.298569 0.0659623 -0.952106 + outer loop + vertex -924.427 355.26 2.90897 + vertex -920.67 359.958 2.05646 + vertex -921.739 355.017 2.04931 + endloop + endfacet + facet normal -0.298988 0.061837 -0.952251 + outer loop + vertex -924.427 355.26 2.90897 + vertex -921.739 355.017 2.04931 + vertex -925.463 350.298 2.91204 + endloop + endfacet + facet normal -0.297722 0.0607535 -0.952717 + outer loop + vertex -925.463 350.298 2.91204 + vertex -921.739 355.017 2.04931 + vertex -922.734 350.05 2.04346 + endloop + endfacet + facet normal -0.194189 0.0400485 -0.980146 + outer loop + vertex -921.739 355.017 2.04931 + vertex -918.576 354.897 1.41761 + vertex -922.734 350.05 2.04346 + endloop + endfacet + facet normal -0.202496 0.0474348 -0.978134 + outer loop + vertex -922.734 350.05 2.04346 + vertex -918.576 354.897 1.41761 + vertex -920.156 349.572 1.48649 + endloop + endfacet + facet normal -0.207494 0.0517471 -0.976867 + outer loop + vertex -918.283 369.835 2.06133 + vertex -915.895 369.328 1.52709 + vertex -919.52 364.888 2.06191 + endloop + endfacet + facet normal -0.197314 0.0431308 -0.979391 + outer loop + vertex -919.52 364.888 2.06191 + vertex -915.895 369.328 1.52709 + vertex -916.45 364.761 1.43787 + endloop + endfacet + facet normal -0.294458 0.0735155 -0.952833 + outer loop + vertex -920.755 369.963 2.83513 + vertex -918.283 369.835 2.06133 + vertex -922.071 365.059 2.86326 + endloop + endfacet + facet normal -0.294409 0.0734736 -0.952851 + outer loop + vertex -922.071 365.059 2.86326 + vertex -918.283 369.835 2.06133 + vertex -919.52 364.888 2.06191 + endloop + endfacet + facet normal -0.29482 0.0684945 -0.953095 + outer loop + vertex -922.071 365.059 2.86326 + vertex -919.52 364.888 2.06191 + vertex -923.315 360.16 2.89621 + endloop + endfacet + facet normal -0.296975 0.0703665 -0.952289 + outer loop + vertex -923.315 360.16 2.89621 + vertex -919.52 364.888 2.06191 + vertex -920.67 359.958 2.05646 + endloop + endfacet + facet normal -0.197121 0.0470905 -0.979248 + outer loop + vertex -919.52 364.888 2.06191 + vertex -916.45 364.761 1.43787 + vertex -920.67 359.958 2.05646 + endloop + endfacet + facet normal -0.205949 0.0551362 -0.977008 + outer loop + vertex -920.67 359.958 2.05646 + vertex -916.45 364.761 1.43787 + vertex -918.174 359.452 1.50167 + endloop + endfacet + facet normal -0.212764 0.058266 -0.975365 + outer loop + vertex -915.586 379.776 2.05965 + vertex -913.317 379.232 1.53208 + vertex -916.966 374.805 2.06376 + endloop + endfacet + facet normal -0.199732 0.0471193 -0.978717 + outer loop + vertex -916.966 374.805 2.06376 + vertex -913.317 379.232 1.53208 + vertex -914.028 374.639 1.45614 + endloop + endfacet + facet normal -0.304343 0.0876342 -0.948523 + outer loop + vertex -918.007 379.865 2.8446 + vertex -915.586 379.776 2.05965 + vertex -919.424 374.883 2.83913 + endloop + endfacet + facet normal -0.297455 0.0818002 -0.951225 + outer loop + vertex -919.424 374.883 2.83913 + vertex -915.586 379.776 2.05965 + vertex -916.966 374.805 2.06376 + endloop + endfacet + facet normal -0.297484 0.0812517 -0.951263 + outer loop + vertex -919.424 374.883 2.83913 + vertex -916.966 374.805 2.06376 + vertex -920.755 369.963 2.83513 + endloop + endfacet + facet normal -0.294114 0.0784095 -0.952549 + outer loop + vertex -920.755 369.963 2.83513 + vertex -916.966 374.805 2.06376 + vertex -918.283 369.835 2.06133 + endloop + endfacet + facet normal -0.199335 0.0533042 -0.978481 + outer loop + vertex -916.966 374.805 2.06376 + vertex -914.028 374.639 1.45614 + vertex -918.283 369.835 2.06133 + endloop + endfacet + facet normal -0.20587 0.0593075 -0.97678 + outer loop + vertex -918.283 369.835 2.06133 + vertex -914.028 374.639 1.45614 + vertex -915.895 369.328 1.52709 + endloop + endfacet + facet normal -0.217568 0.0647673 -0.973894 + outer loop + vertex -912.649 389.547 2.03955 + vertex -910.503 388.959 1.52112 + vertex -914.138 384.704 2.05012 + endloop + endfacet + facet normal -0.203816 0.0525603 -0.977597 + outer loop + vertex -914.138 384.704 2.05012 + vertex -910.503 388.959 1.52112 + vertex -911.337 384.46 1.45303 + endloop + endfacet + facet normal -0.313665 0.0968078 -0.944586 + outer loop + vertex -914.953 389.708 2.8211 + vertex -912.649 389.547 2.03955 + vertex -916.505 384.829 2.8365 + endloop + endfacet + facet normal -0.309473 0.0930851 -0.946341 + outer loop + vertex -916.505 384.829 2.8365 + vertex -912.649 389.547 2.03955 + vertex -914.138 384.704 2.05012 + endloop + endfacet + facet normal -0.309549 0.0921046 -0.946412 + outer loop + vertex -916.505 384.829 2.8365 + vertex -914.138 384.704 2.05012 + vertex -918.007 379.865 2.8446 + endloop + endfacet + facet normal -0.304345 0.0875968 -0.948526 + outer loop + vertex -918.007 379.865 2.8446 + vertex -914.138 384.704 2.05012 + vertex -915.586 379.776 2.05965 + endloop + endfacet + facet normal -0.203315 0.0578541 -0.977403 + outer loop + vertex -914.138 384.704 2.05012 + vertex -911.337 384.46 1.45303 + vertex -915.586 379.776 2.05965 + endloop + endfacet + facet normal -0.211089 0.0651796 -0.975291 + outer loop + vertex -915.586 379.776 2.05965 + vertex -911.337 384.46 1.45303 + vertex -913.317 379.232 1.53208 + endloop + endfacet + facet normal -0.221536 0.0721474 -0.97248 + outer loop + vertex -909.575 399.047 2.03058 + vertex -907.554 398.427 1.5241 + vertex -911.127 394.314 2.03288 + endloop + endfacet + facet normal -0.209483 0.0612553 -0.975892 + outer loop + vertex -911.127 394.314 2.03288 + vertex -907.554 398.427 1.5241 + vertex -908.47 394.033 1.44492 + endloop + endfacet + facet normal -0.324577 0.11075 -0.939353 + outer loop + vertex -911.75 399.254 2.80659 + vertex -909.575 399.047 2.03058 + vertex -913.371 394.504 2.80658 + endloop + endfacet + facet normal -0.316334 0.103237 -0.943014 + outer loop + vertex -913.371 394.504 2.80658 + vertex -909.575 399.047 2.03058 + vertex -911.127 394.314 2.03288 + endloop + endfacet + facet normal -0.316521 0.101529 -0.943136 + outer loop + vertex -913.371 394.504 2.80658 + vertex -911.127 394.314 2.03288 + vertex -914.953 389.708 2.8211 + endloop + endfacet + facet normal -0.313479 0.0987786 -0.944444 + outer loop + vertex -914.953 389.708 2.8211 + vertex -911.127 394.314 2.03288 + vertex -912.649 389.547 2.03955 + endloop + endfacet + facet normal -0.209011 0.0653764 -0.975726 + outer loop + vertex -911.127 394.314 2.03288 + vertex -908.47 394.033 1.44492 + vertex -912.649 389.547 2.03955 + endloop + endfacet + facet normal -0.215629 0.0717921 -0.973833 + outer loop + vertex -912.649 389.547 2.03955 + vertex -908.47 394.033 1.44492 + vertex -910.503 388.959 1.52112 + endloop + endfacet + facet normal -0.23339 0.0820882 -0.968912 + outer loop + vertex -906.322 408.554 2.04194 + vertex -904.445 407.875 1.53233 + vertex -907.974 403.786 2.036 + endloop + endfacet + facet normal -0.218086 0.0683113 -0.973536 + outer loop + vertex -907.974 403.786 2.036 + vertex -904.445 407.875 1.53233 + vertex -905.467 403.46 1.45143 + endloop + endfacet + facet normal -0.335206 0.120788 -0.93437 + outer loop + vertex -908.358 408.831 2.80811 + vertex -906.322 408.554 2.04194 + vertex -910.084 404.024 2.80596 + endloop + endfacet + facet normal -0.329072 0.115207 -0.937251 + outer loop + vertex -910.084 404.024 2.80596 + vertex -906.322 408.554 2.04194 + vertex -907.974 403.786 2.036 + endloop + endfacet + facet normal -0.329121 0.114858 -0.937276 + outer loop + vertex -910.084 404.024 2.80596 + vertex -907.974 403.786 2.036 + vertex -911.75 399.254 2.80659 + endloop + endfacet + facet normal -0.324581 0.110722 -0.939355 + outer loop + vertex -911.75 399.254 2.80659 + vertex -907.974 403.786 2.036 + vertex -909.575 399.047 2.03058 + endloop + endfacet + facet normal -0.217222 0.0744932 -0.973276 + outer loop + vertex -907.974 403.786 2.036 + vertex -905.467 403.46 1.45143 + vertex -909.575 399.047 2.03058 + endloop + endfacet + facet normal -0.219985 0.0771749 -0.972446 + outer loop + vertex -909.575 399.047 2.03058 + vertex -905.467 403.46 1.45143 + vertex -907.554 398.427 1.5241 + endloop + endfacet + facet normal -0.246472 0.0890486 -0.96505 + outer loop + vertex -902.882 418.122 2.04094 + vertex -901.156 417.38 1.53163 + vertex -904.617 413.35 2.0435 + endloop + endfacet + facet normal -0.230059 0.0742853 -0.970337 + outer loop + vertex -904.617 413.35 2.0435 + vertex -901.156 417.38 1.53163 + vertex -902.285 412.932 1.45889 + endloop + endfacet + facet normal -0.356876 0.13522 -0.924313 + outer loop + vertex -904.769 418.439 2.81577 + vertex -902.882 418.122 2.04094 + vertex -906.577 413.654 2.81369 + endloop + endfacet + facet normal -0.345932 0.12521 -0.929868 + outer loop + vertex -906.577 413.654 2.81369 + vertex -902.882 418.122 2.04094 + vertex -904.617 413.35 2.0435 + endloop + endfacet + facet normal -0.345312 0.128609 -0.929634 + outer loop + vertex -906.577 413.654 2.81369 + vertex -904.617 413.35 2.0435 + vertex -908.358 408.831 2.80811 + endloop + endfacet + facet normal -0.335401 0.119587 -0.934454 + outer loop + vertex -908.358 408.831 2.80811 + vertex -904.617 413.35 2.0435 + vertex -906.322 408.554 2.04194 + endloop + endfacet + facet normal -0.228676 0.081643 -0.970073 + outer loop + vertex -904.617 413.35 2.0435 + vertex -902.285 412.932 1.45889 + vertex -906.322 408.554 2.04194 + endloop + endfacet + facet normal -0.23229 0.0851299 -0.968914 + outer loop + vertex -906.322 408.554 2.04194 + vertex -902.285 412.932 1.45889 + vertex -904.445 407.875 1.53233 + endloop + endfacet + facet normal -0.26012 0.0973094 -0.96066 + outer loop + vertex -899.392 427.433 2.03777 + vertex -897.793 426.699 1.5307 + vertex -901.134 422.816 2.04205 + endloop + endfacet + facet normal -0.24417 0.0828589 -0.966186 + outer loop + vertex -901.134 422.816 2.04205 + vertex -897.793 426.699 1.5307 + vertex -898.971 422.358 1.45612 + endloop + endfacet + facet normal -0.37411 0.145321 -0.915928 + outer loop + vertex -901.148 427.761 2.80709 + vertex -899.392 427.433 2.03777 + vertex -902.957 423.141 2.81341 + endloop + endfacet + facet normal -0.36516 0.137001 -0.920809 + outer loop + vertex -902.957 423.141 2.81341 + vertex -899.392 427.433 2.03777 + vertex -901.134 422.816 2.04205 + endloop + endfacet + facet normal -0.364544 0.139974 -0.920606 + outer loop + vertex -902.957 423.141 2.81341 + vertex -901.134 422.816 2.04205 + vertex -904.769 418.439 2.81577 + endloop + endfacet + facet normal -0.357263 0.133249 -0.92445 + outer loop + vertex -904.769 418.439 2.81577 + vertex -901.134 422.816 2.04205 + vertex -902.882 418.122 2.04094 + endloop + endfacet + facet normal -0.242477 0.0905172 -0.965925 + outer loop + vertex -901.134 422.816 2.04205 + vertex -898.971 422.358 1.45612 + vertex -902.882 418.122 2.04094 + endloop + endfacet + facet normal -0.244861 0.0928317 -0.965104 + outer loop + vertex -902.882 418.122 2.04094 + vertex -898.971 422.358 1.45612 + vertex -901.156 417.38 1.53163 + endloop + endfacet + facet normal -0.277458 0.107287 -0.954729 + outer loop + vertex -895.852 436.619 2.04008 + vertex -894.396 435.86 1.53144 + vertex -897.634 432.006 2.03943 + endloop + endfacet + facet normal -0.2587 0.0906084 -0.961699 + outer loop + vertex -897.634 432.006 2.03943 + vertex -894.396 435.86 1.53144 + vertex -895.622 431.561 1.45633 + endloop + endfacet + facet normal -0.399337 0.161431 -0.90248 + outer loop + vertex -897.454 436.994 2.81595 + vertex -895.852 436.619 2.04008 + vertex -899.318 432.353 2.8102 + endloop + endfacet + facet normal -0.386042 0.149215 -0.910333 + outer loop + vertex -899.318 432.353 2.8102 + vertex -895.852 436.619 2.04008 + vertex -897.634 432.006 2.03943 + endloop + endfacet + facet normal -0.384907 0.154011 -0.910015 + outer loop + vertex -899.318 432.353 2.8102 + vertex -897.634 432.006 2.03943 + vertex -901.148 427.761 2.80709 + endloop + endfacet + facet normal -0.374355 0.144194 -0.916006 + outer loop + vertex -901.148 427.761 2.80709 + vertex -897.634 432.006 2.03943 + vertex -899.392 427.433 2.03777 + endloop + endfacet + facet normal -0.256753 0.0990171 -0.961391 + outer loop + vertex -897.634 432.006 2.03943 + vertex -895.622 431.561 1.45633 + vertex -899.392 427.433 2.03777 + endloop + endfacet + facet normal -0.258558 0.100759 -0.960726 + outer loop + vertex -899.392 427.433 2.03777 + vertex -895.622 431.561 1.45633 + vertex -897.793 426.699 1.5307 + endloop + endfacet + facet normal -0.29987 0.118917 -0.94654 + outer loop + vertex -892.208 445.944 2.05543 + vertex -890.91 445.125 1.54121 + vertex -894.037 441.282 2.04924 + endloop + endfacet + facet normal -0.277399 0.0994311 -0.955596 + outer loop + vertex -894.037 441.282 2.04924 + vertex -890.91 445.125 1.54121 + vertex -892.206 440.763 1.46347 + endloop + endfacet + facet normal -0.423226 0.1734 -0.889276 + outer loop + vertex -893.641 446.385 2.82316 + vertex -892.208 445.944 2.05543 + vertex -895.56 441.689 2.82089 + endloop + endfacet + facet normal -0.411169 0.162521 -0.896954 + outer loop + vertex -895.56 441.689 2.82089 + vertex -892.208 445.944 2.05543 + vertex -894.037 441.282 2.04924 + endloop + endfacet + facet normal -0.410038 0.166391 -0.896762 + outer loop + vertex -895.56 441.689 2.82089 + vertex -894.037 441.282 2.04924 + vertex -897.454 436.994 2.81595 + endloop + endfacet + facet normal -0.400344 0.157604 -0.90271 + outer loop + vertex -897.454 436.994 2.81595 + vertex -894.037 441.282 2.04924 + vertex -895.852 436.619 2.04008 + endloop + endfacet + facet normal -0.274672 0.10879 -0.955364 + outer loop + vertex -894.037 441.282 2.04924 + vertex -892.206 440.763 1.46347 + vertex -895.852 436.619 2.04008 + endloop + endfacet + facet normal -0.276041 0.11007 -0.954823 + outer loop + vertex -895.852 436.619 2.04008 + vertex -892.206 440.763 1.46347 + vertex -894.396 435.86 1.53144 + endloop + endfacet + facet normal -0.318552 0.127221 -0.939329 + outer loop + vertex -888.382 455.329 2.02421 + vertex -887.28 454.37 1.52033 + vertex -890.344 450.589 2.04734 + endloop + endfacet + facet normal -0.298418 0.109681 -0.948112 + outer loop + vertex -890.344 450.589 2.04734 + vertex -887.28 454.37 1.52033 + vertex -888.704 449.986 1.46139 + endloop + endfacet + facet normal -0.453828 0.190678 -0.870449 + outer loop + vertex -889.683 455.788 2.80283 + vertex -888.382 455.329 2.02421 + vertex -891.685 451.068 2.81254 + endloop + endfacet + facet normal -0.43916 0.17741 -0.880718 + outer loop + vertex -891.685 451.068 2.81254 + vertex -888.382 455.329 2.02421 + vertex -890.344 450.589 2.04734 + endloop + endfacet + facet normal -0.437878 0.180884 -0.88065 + outer loop + vertex -891.685 451.068 2.81254 + vertex -890.344 450.589 2.04734 + vertex -893.641 446.385 2.82316 + endloop + endfacet + facet normal -0.424691 0.16892 -0.88944 + outer loop + vertex -893.641 446.385 2.82316 + vertex -890.344 450.589 2.04734 + vertex -892.208 445.944 2.05543 + endloop + endfacet + facet normal -0.295703 0.117043 -0.948083 + outer loop + vertex -890.344 450.589 2.04734 + vertex -888.704 449.986 1.46139 + vertex -892.208 445.944 2.05543 + endloop + endfacet + facet normal -0.299095 0.120197 -0.946623 + outer loop + vertex -892.208 445.944 2.05543 + vertex -888.704 449.986 1.46139 + vertex -890.91 445.125 1.54121 + endloop + endfacet + facet normal -0.356347 0.158359 -0.920836 + outer loop + vertex -884.444 465.589 2.20865 + vertex -882.177 466.281 1.45036 + vertex -886.249 460.473 2.02723 + endloop + endfacet + facet normal -0.320468 0.131492 -0.938088 + outer loop + vertex -886.249 460.473 2.02723 + vertex -882.177 466.281 1.45036 + vertex -884.776 459.595 1.40093 + endloop + endfacet + facet normal -0.503551 0.223289 -0.834613 + outer loop + vertex -886.427 463.999 2.97957 + vertex -884.444 465.589 2.20865 + vertex -887.786 460.399 2.83663 + endloop + endfacet + facet normal -0.46425 0.194411 -0.864104 + outer loop + vertex -887.786 460.399 2.83663 + vertex -884.444 465.589 2.20865 + vertex -886.249 460.473 2.02723 + endloop + endfacet + facet normal -0.464095 0.197216 -0.863552 + outer loop + vertex -887.786 460.399 2.83663 + vertex -886.249 460.473 2.02723 + vertex -889.683 455.788 2.80283 + endloop + endfacet + facet normal -0.454448 0.188996 -0.870493 + outer loop + vertex -889.683 455.788 2.80283 + vertex -886.249 460.473 2.02723 + vertex -888.382 455.329 2.02421 + endloop + endfacet + facet normal -0.319555 0.133087 -0.938175 + outer loop + vertex -886.249 460.473 2.02723 + vertex -884.776 459.595 1.40093 + vertex -888.382 455.329 2.02421 + endloop + endfacet + facet normal -0.316251 0.130069 -0.939717 + outer loop + vertex -888.382 455.329 2.02421 + vertex -884.776 459.595 1.40093 + vertex -887.28 454.37 1.52033 + endloop + endfacet + facet normal -0.507262 0.229878 -0.830567 + outer loop + vertex -886.427 463.999 2.97957 + vertex -884.086 468.486 2.79143 + vertex -884.444 465.589 2.20865 + endloop + endfacet + facet normal -0.355761 0.155692 -0.921517 + outer loop + vertex -882.177 466.281 1.45036 + vertex -884.444 465.589 2.20865 + vertex -879.913 473.832 1.85185 + endloop + endfacet + facet normal -0.47673 0.222668 -0.850381 + outer loop + vertex -882.178 472.807 2.85319 + vertex -879.913 473.832 1.85185 + vertex -884.086 468.486 2.79143 + endloop + endfacet + facet normal -0.484426 0.229776 -0.844118 + outer loop + vertex -884.444 465.589 2.20865 + vertex -884.086 468.486 2.79143 + vertex -879.913 473.832 1.85185 + endloop + endfacet + facet normal -0.473955 0.212487 -0.854527 + outer loop + vertex -882.178 472.807 2.85319 + vertex -879.722 477.679 2.70269 + vertex -879.913 473.832 1.85185 + endloop + endfacet + facet normal -0.573781 0.257576 -0.777451 + outer loop + vertex -877.864 482.197 2.82813 + vertex -875.746 483.852 1.81325 + vertex -879.722 477.679 2.70269 + endloop + endfacet + facet normal -0.51181 0.209632 -0.83313 + outer loop + vertex -875.746 483.852 1.81325 + vertex -879.913 473.832 1.85185 + vertex -879.722 477.679 2.70269 + endloop + endfacet + facet normal -0.555794 0.219617 -0.801786 + outer loop + vertex -877.864 482.197 2.82813 + vertex -875.673 487.038 2.63576 + vertex -875.746 483.852 1.81325 + endloop + endfacet + facet normal -0.628565 0.15971 -0.761182 + outer loop + vertex -874.31 492.875 2.73455 + vertex -872.947 492.317 1.4917 + vertex -875.673 487.038 2.63576 + endloop + endfacet + facet normal -0.679463 0.19784 -0.706533 + outer loop + vertex -872.947 492.317 1.4917 + vertex -875.746 483.852 1.81325 + vertex -875.673 487.038 2.63576 + endloop + endfacet + facet normal -0.108227 -0.0898089 -0.990061 + outer loop + vertex -874.522 201.314 1.44833 + vertex -876.836 204.47 1.41507 + vertex -873.719 206.263 0.911617 + endloop + endfacet + facet normal -0.11467 -0.0937518 -0.98897 + outer loop + vertex -879.269 206.318 1.52198 + vertex -878.774 211.495 0.973875 + vertex -876.836 204.47 1.41507 + endloop + endfacet + facet normal -0.107112 -0.0917317 -0.990006 + outer loop + vertex -878.774 211.495 0.973875 + vertex -873.719 206.263 0.911617 + vertex -876.836 204.47 1.41507 + endloop + endfacet + facet normal -0.104655 -0.0948155 -0.989978 + outer loop + vertex -879.269 206.318 1.52198 + vertex -881.958 210.144 1.43984 + vertex -878.774 211.495 0.973875 + endloop + endfacet + facet normal -0.103082 -0.0871501 -0.990848 + outer loop + vertex -885.051 213.137 1.49837 + vertex -884.205 218.136 0.970622 + vertex -881.958 210.144 1.43984 + endloop + endfacet + facet normal -0.107445 -0.0883432 -0.990278 + outer loop + vertex -884.205 218.136 0.970622 + vertex -878.774 211.495 0.973875 + vertex -881.958 210.144 1.43984 + endloop + endfacet + facet normal -0.102348 -0.087281 -0.990912 + outer loop + vertex -885.051 213.137 1.49837 + vertex -888.015 217.621 1.40957 + vertex -884.205 218.136 0.970622 + endloop + endfacet + facet normal -0.10631 -0.0794897 -0.991151 + outer loop + vertex -891.165 220.918 1.48293 + vertex -889.848 225.699 0.958303 + vertex -888.015 217.621 1.40957 + endloop + endfacet + facet normal -0.103552 -0.0788828 -0.991491 + outer loop + vertex -889.848 225.699 0.958303 + vertex -884.205 218.136 0.970622 + vertex -888.015 217.621 1.40957 + endloop + endfacet + facet normal -0.106763 -0.0793608 -0.991112 + outer loop + vertex -891.165 220.918 1.48293 + vertex -893.875 225.451 1.41195 + vertex -889.848 225.699 0.958303 + endloop + endfacet + facet normal -0.106867 -0.0725973 -0.991619 + outer loop + vertex -896.863 228.839 1.4859 + vertex -895.164 233.516 0.960365 + vertex -893.875 225.451 1.41195 + endloop + endfacet + facet normal -0.107227 -0.0726525 -0.991576 + outer loop + vertex -895.164 233.516 0.960365 + vertex -889.848 225.699 0.958303 + vertex -893.875 225.451 1.41195 + endloop + endfacet + facet normal -0.107557 -0.0723403 -0.991564 + outer loop + vertex -896.863 228.839 1.4859 + vertex -899.307 233.457 1.41403 + vertex -895.164 233.516 0.960365 + endloop + endfacet + facet normal -0.106758 -0.0651831 -0.992146 + outer loop + vertex -902.102 236.939 1.48613 + vertex -899.985 241.441 0.962554 + vertex -899.307 233.457 1.41403 + endloop + endfacet + facet normal -0.10771 -0.0652579 -0.992038 + outer loop + vertex -899.985 241.441 0.962554 + vertex -895.164 233.516 0.960365 + vertex -899.307 233.457 1.41403 + endloop + endfacet + facet normal -0.107812 -0.0646782 -0.992065 + outer loop + vertex -902.102 236.939 1.48613 + vertex -904.212 241.561 1.41405 + vertex -899.985 241.441 0.962554 + endloop + endfacet + facet normal -0.109061 -0.0575663 -0.992367 + outer loop + vertex -906.76 245.074 1.49026 + vertex -904.267 249.461 0.961884 + vertex -904.212 241.561 1.41405 + endloop + endfacet + facet normal -0.107659 -0.0575651 -0.99252 + outer loop + vertex -904.267 249.461 0.961884 + vertex -899.985 241.441 0.962554 + vertex -904.212 241.561 1.41405 + endloop + endfacet + facet normal -0.107808 -0.0582894 -0.992461 + outer loop + vertex -906.76 245.074 1.49026 + vertex -908.553 249.726 1.41188 + vertex -904.267 249.461 0.961884 + endloop + endfacet + facet normal -0.10901 -0.0490925 -0.992828 + outer loop + vertex -910.885 253.333 1.48951 + vertex -908.043 257.696 0.96182 + vertex -908.553 249.726 1.41188 + endloop + endfacet + facet normal -0.107305 -0.0492117 -0.993007 + outer loop + vertex -908.043 257.696 0.96182 + vertex -904.267 249.461 0.961884 + vertex -908.553 249.726 1.41188 + endloop + endfacet + facet normal -0.108722 -0.0492827 -0.99285 + outer loop + vertex -910.885 253.333 1.48951 + vertex -912.394 258.15 1.4157 + vertex -908.043 257.696 0.96182 + endloop + endfacet + facet normal -0.106892 -0.0414773 -0.993405 + outer loop + vertex -914.563 261.996 1.48847 + vertex -911.363 266.328 0.963336 + vertex -912.394 258.15 1.4157 + endloop + endfacet + facet normal -0.10794 -0.0413393 -0.993298 + outer loop + vertex -911.363 266.328 0.963336 + vertex -908.043 257.696 0.96182 + vertex -912.394 258.15 1.4157 + endloop + endfacet + facet normal -0.107711 -0.0408648 -0.993342 + outer loop + vertex -914.563 261.996 1.48847 + vertex -915.812 267.087 1.41451 + vertex -911.363 266.328 0.963336 + endloop + endfacet + facet normal -0.105765 -0.0336652 -0.993821 + outer loop + vertex -917.793 271.22 1.48534 + vertex -914.206 275.407 0.961696 + vertex -915.812 267.087 1.41451 + endloop + endfacet + facet normal -0.1065 -0.0335192 -0.993748 + outer loop + vertex -914.206 275.407 0.961696 + vertex -911.363 266.328 0.963336 + vertex -915.812 267.087 1.41451 + endloop + endfacet + facet normal -0.107531 -0.0321349 -0.993682 + outer loop + vertex -917.793 271.22 1.48534 + vertex -918.706 276.505 1.41325 + vertex -914.206 275.407 0.961696 + endloop + endfacet + facet normal -0.106322 -0.0251746 -0.994013 + outer loop + vertex -920.413 280.815 1.48667 + vertex -916.456 284.785 0.962889 + vertex -918.706 276.505 1.41325 + endloop + endfacet + facet normal -0.105899 -0.025292 -0.994055 + outer loop + vertex -916.456 284.785 0.962889 + vertex -914.206 275.407 0.961696 + vertex -918.706 276.505 1.41325 + endloop + endfacet + facet normal -0.107294 -0.0241951 -0.993933 + outer loop + vertex -920.413 280.815 1.48667 + vertex -920.932 286.125 1.41345 + vertex -916.456 284.785 0.962889 + endloop + endfacet + facet normal -0.107945 -0.016818 -0.994015 + outer loop + vertex -922.308 290.432 1.49 + vertex -918.039 294.246 0.96181 + vertex -920.932 286.125 1.41345 + endloop + endfacet + facet normal -0.105396 -0.0177408 -0.994272 + outer loop + vertex -918.039 294.246 0.96181 + vertex -916.456 284.785 0.962889 + vertex -920.932 286.125 1.41345 + endloop + endfacet + facet normal -0.10783 -0.0169491 -0.994025 + outer loop + vertex -922.308 290.432 1.49 + vertex -922.418 295.665 1.41261 + vertex -918.039 294.246 0.96181 + endloop + endfacet + facet normal -0.10863 -0.00848726 -0.994046 + outer loop + vertex -923.458 299.964 1.48965 + vertex -918.935 303.754 0.962977 + vertex -922.418 295.665 1.41261 + endloop + endfacet + facet normal -0.105556 -0.00982867 -0.994365 + outer loop + vertex -918.935 303.754 0.962977 + vertex -918.039 294.246 0.96181 + vertex -922.418 295.665 1.41261 + endloop + endfacet + facet normal -0.108232 -0.00896855 -0.994085 + outer loop + vertex -923.458 299.964 1.48965 + vertex -923.189 305.289 1.41223 + vertex -918.935 303.754 0.962977 + endloop + endfacet + facet normal -0.10878 -0.00174619 -0.994064 + outer loop + vertex -923.93 309.762 1.48554 + vertex -919.201 313.453 0.961553 + vertex -923.189 305.289 1.41223 + endloop + endfacet + facet normal -0.106127 -0.00305772 -0.994348 + outer loop + vertex -919.201 313.453 0.961553 + vertex -918.935 303.754 0.962977 + vertex -923.189 305.289 1.41223 + endloop + endfacet + facet normal -0.109805 -0.000417358 -0.993953 + outer loop + vertex -923.93 309.762 1.48554 + vertex -923.307 315.232 1.41436 + vertex -919.201 313.453 0.961553 + endloop + endfacet + facet normal -0.111161 0.00508984 -0.993789 + outer loop + vertex -923.755 319.826 1.48799 + vertex -918.889 323.324 0.961603 + vertex -923.307 315.232 1.41436 + endloop + endfacet + facet normal -0.108157 0.00343059 -0.994128 + outer loop + vertex -918.889 323.324 0.961603 + vertex -919.201 313.453 0.961553 + vertex -923.307 315.232 1.41436 + endloop + endfacet + facet normal -0.111706 0.00585708 -0.993724 + outer loop + vertex -923.755 319.826 1.48799 + vertex -922.82 325.278 1.4151 + vertex -918.889 323.324 0.961603 + endloop + endfacet + facet normal -0.113763 0.0114382 -0.993442 + outer loop + vertex -923.004 329.849 1.4888 + vertex -918.066 333.189 0.961726 + vertex -922.82 325.278 1.4151 + endloop + endfacet + facet normal -0.110067 0.00919181 -0.993882 + outer loop + vertex -918.066 333.189 0.961726 + vertex -918.889 323.324 0.961603 + vertex -922.82 325.278 1.4151 + endloop + endfacet + facet normal -0.113354 0.0108256 -0.993496 + outer loop + vertex -923.004 329.849 1.4888 + vertex -921.82 335.212 1.41208 + vertex -918.066 333.189 0.961726 + endloop + endfacet + facet normal -0.116205 0.0169291 -0.993081 + outer loop + vertex -921.785 339.73 1.48508 + vertex -916.814 342.972 0.958591 + vertex -921.82 335.212 1.41208 + endloop + endfacet + facet normal -0.111675 0.0139738 -0.993647 + outer loop + vertex -916.814 342.972 0.958591 + vertex -918.066 333.189 0.961726 + vertex -921.82 335.212 1.41208 + endloop + endfacet + facet normal -0.116134 0.0168194 -0.993091 + outer loop + vertex -921.785 339.73 1.48508 + vertex -920.388 345.044 1.41162 + vertex -916.814 342.972 0.958591 + endloop + endfacet + facet normal -0.119873 0.0225535 -0.992533 + outer loop + vertex -920.156 349.572 1.48649 + vertex -915.189 352.726 0.958348 + vertex -920.388 345.044 1.41162 + endloop + endfacet + facet normal -0.114827 0.0190993 -0.993202 + outer loop + vertex -915.189 352.726 0.958348 + vertex -916.814 342.972 0.958591 + vertex -920.388 345.044 1.41162 + endloop + endfacet + facet normal -0.12001 0.0227734 -0.992511 + outer loop + vertex -920.156 349.572 1.48649 + vertex -918.576 354.897 1.41761 + vertex -915.189 352.726 0.958348 + endloop + endfacet + facet normal -0.125743 0.0293853 -0.991628 + outer loop + vertex -918.174 359.452 1.50167 + vertex -913.244 362.502 0.966903 + vertex -918.576 354.897 1.41761 + endloop + endfacet + facet normal -0.118898 0.0245284 -0.992603 + outer loop + vertex -913.244 362.502 0.966903 + vertex -915.189 352.726 0.958348 + vertex -918.576 354.897 1.41761 + endloop + endfacet + facet normal -0.125387 0.0287984 -0.99169 + outer loop + vertex -918.174 359.452 1.50167 + vertex -916.45 364.761 1.43787 + vertex -913.244 362.502 0.966903 + endloop + endfacet + facet normal -0.132818 0.0355042 -0.990504 + outer loop + vertex -915.895 369.328 1.52709 + vertex -911.021 372.278 0.979355 + vertex -916.45 364.761 1.43787 + endloop + endfacet + facet normal -0.124801 0.0296391 -0.991739 + outer loop + vertex -911.021 372.278 0.979355 + vertex -913.244 362.502 0.966903 + vertex -916.45 364.761 1.43787 + endloop + endfacet + facet normal -0.131277 0.0329038 -0.9908 + outer loop + vertex -915.895 369.328 1.52709 + vertex -914.028 374.639 1.45614 + vertex -911.021 372.278 0.979355 + endloop + endfacet + facet normal -0.134834 0.0372568 -0.990168 + outer loop + vertex -913.317 379.232 1.53208 + vertex -908.552 382.011 0.987778 + vertex -914.028 374.639 1.45614 + endloop + endfacet + facet normal -0.130458 0.0339613 -0.990872 + outer loop + vertex -908.552 382.011 0.987778 + vertex -911.021 372.278 0.979355 + vertex -914.028 374.639 1.45614 + endloop + endfacet + facet normal -0.133978 0.0357554 -0.990339 + outer loop + vertex -913.317 379.232 1.53208 + vertex -911.337 384.46 1.45303 + vertex -908.552 382.011 0.987778 + endloop + endfacet + facet normal -0.137822 0.0405147 -0.989628 + outer loop + vertex -910.503 388.959 1.52112 + vertex -905.887 391.592 0.986024 + vertex -911.337 384.46 1.45303 + endloop + endfacet + facet normal -0.133056 0.0368203 -0.990424 + outer loop + vertex -905.887 391.592 0.986024 + vertex -908.552 382.011 0.987778 + vertex -911.337 384.46 1.45303 + endloop + endfacet + facet normal -0.137721 0.0403324 -0.98965 + outer loop + vertex -910.503 388.959 1.52112 + vertex -908.47 394.033 1.44492 + vertex -905.887 391.592 0.986024 + endloop + endfacet + facet normal -0.145813 0.048203 -0.988137 + outer loop + vertex -907.554 398.427 1.5241 + vertex -903.08 401.014 0.990029 + vertex -908.47 394.033 1.44492 + endloop + endfacet + facet normal -0.136899 0.0412161 -0.989727 + outer loop + vertex -903.08 401.014 0.990029 + vertex -905.887 391.592 0.986024 + vertex -908.47 394.033 1.44492 + endloop + endfacet + facet normal -0.144334 0.0455745 -0.988479 + outer loop + vertex -907.554 398.427 1.5241 + vertex -905.467 403.46 1.45143 + vertex -903.08 401.014 0.990029 + endloop + endfacet + facet normal -0.153742 0.0536593 -0.986653 + outer loop + vertex -904.445 407.875 1.53233 + vertex -900.127 410.39 0.9962 + vertex -905.467 403.46 1.45143 + endloop + endfacet + facet normal -0.14393 0.0459762 -0.988519 + outer loop + vertex -900.127 410.39 0.9962 + vertex -903.08 401.014 0.990029 + vertex -905.467 403.46 1.45143 + endloop + endfacet + facet normal -0.152002 0.0505785 -0.987085 + outer loop + vertex -904.445 407.875 1.53233 + vertex -902.285 412.932 1.45889 + vertex -900.127 410.39 0.9962 + endloop + endfacet + facet normal -0.160692 0.0569181 -0.985362 + outer loop + vertex -901.156 417.38 1.53163 + vertex -897.038 419.749 0.996935 + vertex -902.285 412.932 1.45889 + endloop + endfacet + facet normal -0.152285 0.0503323 -0.987054 + outer loop + vertex -897.038 419.749 0.996935 + vertex -900.127 410.39 0.9962 + vertex -902.285 412.932 1.45889 + endloop + endfacet + facet normal -0.159705 0.0551443 -0.985623 + outer loop + vertex -901.156 417.38 1.53163 + vertex -898.971 422.358 1.45612 + vertex -897.038 419.749 0.996935 + endloop + endfacet + facet normal -0.171362 0.0633921 -0.983167 + outer loop + vertex -897.793 426.699 1.5307 + vertex -893.873 428.999 0.995653 + vertex -898.971 422.358 1.45612 + endloop + endfacet + facet normal -0.160272 0.0547122 -0.985555 + outer loop + vertex -893.873 428.999 0.995653 + vertex -897.038 419.749 0.996935 + vertex -898.971 422.358 1.45612 + endloop + endfacet + facet normal -0.169914 0.0608265 -0.98358 + outer loop + vertex -897.793 426.699 1.5307 + vertex -895.622 431.561 1.45633 + vertex -893.873 428.999 0.995653 + endloop + endfacet + facet normal -0.18257 0.0692217 -0.980753 + outer loop + vertex -894.396 435.86 1.53144 + vertex -890.659 438.16 0.998235 + vertex -895.622 431.561 1.45633 + endloop + endfacet + facet normal -0.170813 0.0601912 -0.983463 + outer loop + vertex -890.659 438.16 0.998235 + vertex -893.873 428.999 0.995653 + vertex -895.622 431.561 1.45633 + endloop + endfacet + facet normal -0.181555 0.0674999 -0.981062 + outer loop + vertex -894.396 435.86 1.53144 + vertex -892.206 440.763 1.46347 + vertex -890.659 438.16 0.998235 + endloop + endfacet + facet normal -0.195408 0.0754723 -0.977814 + outer loop + vertex -890.91 445.125 1.54121 + vertex -887.38 447.304 1.00402 + vertex -892.206 440.763 1.46347 + endloop + endfacet + facet normal -0.183365 0.066378 -0.980801 + outer loop + vertex -887.38 447.304 1.00402 + vertex -890.659 438.16 0.998235 + vertex -892.206 440.763 1.46347 + endloop + endfacet + facet normal -0.193117 0.0715759 -0.978562 + outer loop + vertex -890.91 445.125 1.54121 + vertex -888.704 449.986 1.46139 + vertex -887.38 447.304 1.00402 + endloop + endfacet + facet normal -0.210279 0.0814032 -0.974247 + outer loop + vertex -887.28 454.37 1.52033 + vertex -883.955 456.379 0.970543 + vertex -888.704 449.986 1.46139 + endloop + endfacet + facet normal -0.195666 0.0702481 -0.978151 + outer loop + vertex -883.955 456.379 0.970543 + vertex -887.38 447.304 1.00402 + vertex -888.704 449.986 1.46139 + endloop + endfacet + facet normal -0.207985 0.0773827 -0.975066 + outer loop + vertex -887.28 454.37 1.52033 + vertex -884.776 459.595 1.40093 + vertex -883.955 456.379 0.970543 + endloop + endfacet + facet normal -0.233278 0.0978215 -0.967477 + outer loop + vertex -882.177 466.281 1.45036 + vertex -880.207 465.211 0.86718 + vertex -884.776 459.595 1.40093 + endloop + endfacet + facet normal -0.208758 0.0771657 -0.974918 + outer loop + vertex -880.207 465.211 0.86718 + vertex -883.955 456.379 0.970543 + vertex -884.776 459.595 1.40093 + endloop + endfacet + facet normal -0.306168 0.141873 -0.941347 + outer loop + vertex -879.913 473.832 1.85185 + vertex -877.186 473.496 0.914274 + vertex -882.177 466.281 1.45036 + endloop + endfacet + facet normal -0.236515 0.0917585 -0.967285 + outer loop + vertex -882.177 466.281 1.45036 + vertex -877.186 473.496 0.914274 + vertex -880.207 465.211 0.86718 + endloop + endfacet + facet normal -0.349262 0.141676 -0.926253 + outer loop + vertex -875.746 483.852 1.81325 + vertex -874.079 482.42 0.965843 + vertex -879.913 473.832 1.85185 + endloop + endfacet + facet normal -0.310493 0.113535 -0.943771 + outer loop + vertex -879.913 473.832 1.85185 + vertex -874.079 482.42 0.965843 + vertex -877.186 473.496 0.914274 + endloop + endfacet + facet normal -0.361702 0.0843379 -0.928471 + outer loop + vertex -872.947 492.317 1.4917 + vertex -871.294 491.673 0.789366 + vertex -875.746 483.852 1.81325 + endloop + endfacet + facet normal -0.383037 0.0977808 -0.918543 + outer loop + vertex -875.746 483.852 1.81325 + vertex -871.294 491.673 0.789366 + vertex -874.079 482.42 0.965843 + endloop + endfacet + facet normal -0.397598 -0.273734 0.875777 + outer loop + vertex -857.15 222.198 21.0616 + vertex -856.362 223.72 21.8949 + vertex -857.439 223.553 21.3536 + endloop + endfacet + facet normal -0.267279 -0.23941 0.933405 + outer loop + vertex -858.237 219.761 20.1253 + vertex -857.15 222.198 21.0616 + vertex -859.741 221.779 20.212 + endloop + endfacet + facet normal -0.200325 -0.170547 0.964771 + outer loop + vertex -859.276 217.18 19.4532 + vertex -858.237 219.761 20.1253 + vertex -860.876 219.567 19.5429 + endloop + endfacet + facet normal -0.144713 -0.0834408 0.985949 + outer loop + vertex -860.521 213.567 18.9647 + vertex -859.276 217.18 19.4532 + vertex -861.282 217.48 19.1841 + endloop + endfacet + facet normal -0.12011 -0.148706 0.98156 + outer loop + vertex -872.265 195.681 16.6531 + vertex -869.353 198.16 17.385 + vertex -873.852 198.06 16.8193 + endloop + endfacet + facet normal -0.211281 -0.236264 0.948441 + outer loop + vertex -873.811 193.755 15.8289 + vertex -872.265 195.681 16.6531 + vertex -875.306 196.344 16.1406 + endloop + endfacet + facet normal -0.32624 -0.34095 0.881658 + outer loop + vertex -874.798 191.969 14.7729 + vertex -873.811 193.755 15.8289 + vertex -876.335 194.419 15.1516 + endloop + endfacet + facet normal -0.431413 -0.472115 0.768759 + outer loop + vertex -875.862 190.721 13.4095 + vertex -874.798 191.969 14.7729 + vertex -877.02 192.798 14.0353 + endloop + endfacet + facet normal -0.513129 -0.62452 0.588789 + outer loop + vertex -876.448 189.783 11.9043 + vertex -875.862 190.721 13.4095 + vertex -877.549 191.23 12.4794 + endloop + endfacet + facet normal -0.62771 -0.711512 0.315801 + outer loop + vertex -876.537 189.151 10.3037 + vertex -876.448 189.783 11.9043 + vertex -877.987 190.65 10.7974 + endloop + endfacet + facet normal -0.645151 -0.763629 -0.0255169 + outer loop + vertex -876.975 189.579 8.56213 + vertex -876.537 189.151 10.3037 + vertex -878.098 190.495 9.55247 + endloop + endfacet + facet normal -0.593845 -0.735928 -0.325206 + outer loop + vertex -877.251 190.513 6.95339 + vertex -876.975 189.579 8.56213 + vertex -878.157 190.965 7.58766 + endloop + endfacet + facet normal -0.576925 -0.635859 -0.51268 + outer loop + vertex -876.287 190.534 5.84283 + vertex -877.251 190.513 6.95339 + vertex -877.71 191.815 5.85503 + endloop + endfacet + facet normal -0.41401 -0.555193 -0.721357 + outer loop + vertex -875.759 191.811 4.55684 + vertex -876.287 190.534 5.84283 + vertex -877.156 192.002 5.21246 + endloop + endfacet + facet normal -0.362289 -0.377801 -0.852064 + outer loop + vertex -874.353 193.476 3.2211 + vertex -875.759 191.811 4.55684 + vertex -876.943 194.723 3.76897 + endloop + endfacet + facet normal -0.245536 -0.274773 -0.92963 + outer loop + vertex -872.765 195.767 2.12426 + vertex -874.353 193.476 3.2211 + vertex -875.666 196.976 2.53324 + endloop + endfacet + facet normal -0.109977 -0.186693 -0.976243 + outer loop + vertex -870.893 198.696 1.35327 + vertex -872.765 195.767 2.12426 + vertex -873.529 198.903 1.61072 + endloop + endfacet + facet normal -0.384762 -0.649374 0.65595 + outer loop + vertex -848.112 240.495 43.8286 + vertex -846.708 242.159 46.2995 + vertex -850.232 243.199 45.2624 + endloop + endfacet + facet normal -0.567769 -0.536279 0.624534 + outer loop + vertex -853.943 228.086 26.3702 + vertex -852.326 230.388 29.8169 + vertex -854.705 230.597 27.834 + endloop + endfacet + facet normal -0.4998 -0.47003 0.727511 + outer loop + vertex -854.946 224.63 23.1206 + vertex -854.74 226.316 24.3515 + vertex -855.836 225.799 23.2642 + endloop + endfacet + facet normal -0.96565 0.213871 0.14758 + outer loop + vertex -892.339 386.206 49.7135 + vertex -891.658 389.345 49.6189 + vertex -892.239 387.343 48.7207 + endloop + endfacet + facet normal -0.971066 0.199755 0.130875 + outer loop + vertex -893.119 382.441 49.6752 + vertex -892.339 386.206 49.7135 + vertex -892.239 387.343 48.7207 + endloop + endfacet + facet normal -0.969684 0.194492 0.147939 + outer loop + vertex -893.947 378.312 49.6778 + vertex -893.119 382.441 49.6752 + vertex -893.898 379.323 48.6698 + endloop + endfacet + facet normal -0.975972 0.175738 0.128817 + outer loop + vertex -894.662 374.377 49.6227 + vertex -893.947 378.312 49.6778 + vertex -893.898 379.323 48.6698 + endloop + endfacet + facet normal -0.975567 0.168235 0.141302 + outer loop + vertex -895.363 370.318 49.6163 + vertex -894.662 374.377 49.6227 + vertex -895.375 371.065 48.6447 + endloop + endfacet + facet normal -0.981175 0.147109 0.12512 + outer loop + vertex -895.962 366.345 49.5946 + vertex -895.363 370.318 49.6163 + vertex -895.375 371.065 48.6447 + endloop + endfacet + facet normal -0.98274 0.140712 0.120095 + outer loop + vertex -896.504 362.527 49.6314 + vertex -895.962 366.345 49.5946 + vertex -896.671 362.095 48.7676 + endloop + endfacet + facet normal -0.984316 0.116407 0.132555 + outer loop + vertex -896.836 359.64 49.704 + vertex -896.504 362.527 49.6314 + vertex -896.671 362.095 48.7676 + endloop + endfacet + facet normal -0.986386 0.111938 0.12047 + outer loop + vertex -897.247 356.225 49.5053 + vertex -896.836 359.64 49.704 + vertex -896.671 362.095 48.7676 + endloop + endfacet + facet normal -0.983001 0.090098 0.15997 + outer loop + vertex -897.617 351.887 49.6746 + vertex -897.247 356.225 49.5053 + vertex -897.648 353.386 48.6428 + endloop + endfacet + facet normal -0.987576 0.074958 0.13811 + outer loop + vertex -897.936 348.024 49.4913 + vertex -897.617 351.887 49.6746 + vertex -897.648 353.386 48.6428 + endloop + endfacet + facet normal -0.986886 0.047653 0.154224 + outer loop + vertex -898.114 343.771 49.6702 + vertex -897.936 348.024 49.4913 + vertex -898.219 344.92 48.6404 + endloop + endfacet + facet normal -0.990542 0.0292412 0.134061 + outer loop + vertex -898.255 339.813 49.4908 + vertex -898.114 343.771 49.6702 + vertex -898.219 344.92 48.6404 + endloop + endfacet + facet normal -0.992765 0.0026044 0.120042 + outer loop + vertex -898.242 336 49.676 + vertex -898.255 339.813 49.4908 + vertex -898.355 335.936 48.7441 + endloop + endfacet + facet normal -0.992542 -0.0136979 0.121134 + outer loop + vertex -898.215 333.288 49.5919 + vertex -898.242 336 49.676 + vertex -898.355 335.936 48.7441 + endloop + endfacet + facet normal -0.998721 -0.0494905 0.0103506 + outer loop + vertex -898.041 329.769 49.5393 + vertex -898.215 333.288 49.5919 + vertex -898.355 335.936 48.7441 + endloop + endfacet + facet normal -0.988653 -0.063995 0.135906 + outer loop + vertex -897.789 325.856 49.5307 + vertex -898.041 329.769 49.5393 + vertex -898.028 327.531 48.5837 + endloop + endfacet + facet normal -0.99237 -0.110826 0.0540363 + outer loop + vertex -897.363 322.028 49.506 + vertex -897.789 325.856 49.5307 + vertex -898.028 327.531 48.5837 + endloop + endfacet + facet normal -0.982057 -0.128725 0.137822 + outer loop + vertex -896.844 318.103 49.5374 + vertex -897.363 322.028 49.506 + vertex -897.164 319.507 48.5707 + endloop + endfacet + facet normal -0.981099 -0.185535 0.0549684 + outer loop + vertex -896.128 314.313 49.5331 + vertex -896.844 318.103 49.5374 + vertex -897.164 319.507 48.5707 + endloop + endfacet + facet normal -0.974783 -0.19187 0.113949 + outer loop + vertex -895.467 310.981 49.5775 + vertex -896.128 314.313 49.5331 + vertex -895.645 311.356 48.6866 + endloop + endfacet + facet normal -0.966918 -0.237459 0.0931849 + outer loop + vertex -895.07 309.363 49.5679 + vertex -895.467 310.981 49.5775 + vertex -895.645 311.356 48.6866 + endloop + endfacet + facet normal -0.961204 -0.275824 0.00272991 + outer loop + vertex -894.159 306.188 49.4929 + vertex -895.07 309.363 49.5679 + vertex -895.645 311.356 48.6866 + endloop + endfacet + facet normal -0.945502 -0.281483 0.163687 + outer loop + vertex -893.036 302.396 49.4625 + vertex -894.159 306.188 49.4929 + vertex -893.555 303.588 48.5117 + endloop + endfacet + facet normal -0.937688 -0.334989 0.0923179 + outer loop + vertex -891.721 298.703 49.4161 + vertex -893.036 302.396 49.4625 + vertex -893.555 303.588 48.5117 + endloop + endfacet + facet normal -0.927054 -0.344906 0.147005 + outer loop + vertex -890.406 295.179 49.4389 + vertex -891.721 298.703 49.4161 + vertex -890.636 295.43 48.5783 + endloop + endfacet + facet normal -0.908035 -0.399482 0.126043 + outer loop + vertex -889.233 292.528 49.4891 + vertex -890.406 295.179 49.4389 + vertex -890.636 295.43 48.5783 + endloop + endfacet + facet normal -0.90801 -0.401917 0.118243 + outer loop + vertex -888.213 290.159 49.2735 + vertex -889.233 292.528 49.4891 + vertex -890.636 295.43 48.5783 + endloop + endfacet + facet normal -0.886528 -0.424559 0.183894 + outer loop + vertex -886.924 287.491 49.3253 + vertex -888.213 290.159 49.2735 + vertex -887.53 288.349 48.3842 + endloop + endfacet + facet normal -0.872824 -0.469173 0.134367 + outer loop + vertex -885.216 284.295 49.2613 + vertex -886.924 287.491 49.3253 + vertex -887.53 288.349 48.3842 + endloop + endfacet + facet normal -0.859749 -0.474909 0.187862 + outer loop + vertex -883.427 281.05 49.244 + vertex -885.216 284.295 49.2613 + vertex -883.662 281.128 48.3675 + endloop + endfacet + facet normal -0.835976 -0.519242 0.177573 + outer loop + vertex -881.939 278.659 49.2589 + vertex -883.427 281.05 49.244 + vertex -883.662 281.128 48.3675 + endloop + endfacet + facet normal -0.835982 -0.518975 0.178326 + outer loop + vertex -880.636 276.47 48.9955 + vertex -881.939 278.659 49.2589 + vertex -883.662 281.128 48.3675 + endloop + endfacet + facet normal -0.812112 -0.537509 0.227064 + outer loop + vertex -879.073 274.118 49.0191 + vertex -880.636 276.47 48.9955 + vertex -879.81 274.836 48.0829 + endloop + endfacet + facet normal -0.797557 -0.5731 0.188306 + outer loop + vertex -877.078 271.312 48.9272 + vertex -879.073 274.118 49.0191 + vertex -879.81 274.836 48.0829 + endloop + endfacet + facet normal -0.789248 -0.57311 0.22053 + outer loop + vertex -875.186 268.686 48.874 + vertex -877.078 271.312 48.9272 + vertex -875.373 268.602 47.9891 + endloop + endfacet + facet normal -0.772314 -0.596245 0.219144 + outer loop + vertex -874.226 267.423 48.8228 + vertex -875.186 268.686 48.874 + vertex -875.373 268.602 47.9891 + endloop + endfacet + facet normal -0.760355 -0.631141 0.153365 + outer loop + vertex -872.239 264.998 48.6937 + vertex -874.226 267.423 48.8228 + vertex -875.373 268.602 47.9891 + endloop + endfacet + facet normal -0.744276 -0.627465 0.228783 + outer loop + vertex -869.964 262.27 48.6115 + vertex -872.239 264.998 48.6937 + vertex -870.222 262.245 47.7049 + endloop + endfacet + facet normal -0.70669 -0.672679 0.219298 + outer loop + vertex -867.934 260.125 48.5748 + vertex -869.964 262.27 48.6115 + vertex -870.222 262.245 47.7049 + endloop + endfacet + facet normal -0.707062 -0.668759 0.229835 + outer loop + vertex -866.171 258.152 48.2561 + vertex -867.934 260.125 48.5748 + vertex -870.222 262.245 47.7049 + endloop + endfacet + facet normal -0.668558 -0.686097 0.286881 + outer loop + vertex -863.931 255.938 48.1836 + vertex -866.171 258.152 48.2561 + vertex -865.049 256.611 47.187 + endloop + endfacet + facet normal -0.645085 -0.727947 0.232289 + outer loop + vertex -860.855 253.095 47.8154 + vertex -863.931 255.938 48.1836 + vertex -865.049 256.611 47.187 + endloop + endfacet + facet normal -0.574903 -0.709372 0.407772 + outer loop + vertex -855.884 248.7 47.1782 + vertex -860.855 253.095 47.8154 + vertex -859.828 251.489 46.4699 + endloop + endfacet + facet normal -0.506913 -0.701623 0.500764 + outer loop + vertex -851.539 245.184 46.6509 + vertex -855.884 248.7 47.1782 + vertex -854.715 246.893 45.8298 + endloop + endfacet + facet normal -0.429338 -0.69012 0.582583 + outer loop + vertex -848.646 243.404 46.6731 + vertex -851.539 245.184 46.6509 + vertex -850.232 243.199 45.2624 + endloop + endfacet + facet normal -0.380311 -0.753261 0.53662 + outer loop + vertex -846.708 242.159 46.2995 + vertex -848.646 243.404 46.6731 + vertex -850.232 243.199 45.2624 + endloop + endfacet + facet normal -0.505606 -0.692643 0.514401 + outer loop + vertex -854.715 246.893 45.8298 + vertex -850.232 243.199 45.2624 + vertex -851.539 245.184 46.6509 + endloop + endfacet + facet normal -0.570282 -0.695312 0.4374 + outer loop + vertex -859.828 251.489 46.4699 + vertex -854.715 246.893 45.8298 + vertex -855.884 248.7 47.1782 + endloop + endfacet + facet normal -0.632921 -0.693404 0.344387 + outer loop + vertex -865.049 256.611 47.187 + vertex -859.828 251.489 46.4699 + vertex -860.855 253.095 47.8154 + endloop + endfacet + facet normal -0.707738 -0.670342 0.223046 + outer loop + vertex -870.222 262.245 47.7049 + vertex -865.049 256.611 47.187 + vertex -866.171 258.152 48.2561 + endloop + endfacet + facet normal -0.759116 -0.623432 0.187286 + outer loop + vertex -875.373 268.602 47.9891 + vertex -870.222 262.245 47.7049 + vertex -872.239 264.998 48.6937 + endloop + endfacet + facet normal -0.797103 -0.570356 0.198294 + outer loop + vertex -879.81 274.836 48.0829 + vertex -875.373 268.602 47.9891 + vertex -877.078 271.312 48.9272 + endloop + endfacet + facet normal -0.836412 -0.519898 0.173554 + outer loop + vertex -883.662 281.128 48.3675 + vertex -879.81 274.836 48.0829 + vertex -880.636 276.47 48.9955 + endloop + endfacet + facet normal -0.872639 -0.467796 0.140243 + outer loop + vertex -887.53 288.349 48.3842 + vertex -883.662 281.128 48.3675 + vertex -885.216 284.295 49.2613 + endloop + endfacet + facet normal -0.907864 -0.401533 0.120643 + outer loop + vertex -890.636 295.43 48.5783 + vertex -887.53 288.349 48.3842 + vertex -888.213 290.159 49.2735 + endloop + endfacet + facet normal -0.937652 -0.334744 0.0935704 + outer loop + vertex -893.555 303.588 48.5117 + vertex -890.636 295.43 48.5783 + vertex -891.721 298.703 49.4161 + endloop + endfacet + facet normal -0.960364 -0.260549 0.0990738 + outer loop + vertex -895.645 311.356 48.6866 + vertex -893.555 303.588 48.5117 + vertex -894.159 306.188 49.4929 + endloop + endfacet + facet normal -0.980485 -0.181682 0.0751058 + outer loop + vertex -897.164 319.507 48.5707 + vertex -895.645 311.356 48.6866 + vertex -896.128 314.313 49.5331 + endloop + endfacet + facet normal -0.991293 -0.106858 0.0769353 + outer loop + vertex -898.028 327.531 48.5837 + vertex -897.164 319.507 48.5707 + vertex -897.363 322.028 49.506 + endloop + endfacet + facet normal -0.995951 -0.0403242 0.0803475 + outer loop + vertex -898.355 335.936 48.7441 + vertex -898.028 327.531 48.5837 + vertex -898.041 329.769 49.5393 + endloop + endfacet + facet normal -0.99849 0.0157365 0.0526401 + outer loop + vertex -898.219 344.92 48.6404 + vertex -898.355 335.936 48.7441 + vertex -898.255 339.813 49.4908 + endloop + endfacet + facet normal -0.994048 0.0670393 0.085875 + outer loop + vertex -897.648 353.386 48.6428 + vertex -898.219 344.92 48.6404 + vertex -897.936 348.024 49.4913 + endloop + endfacet + facet normal -0.989053 0.109492 0.0989222 + outer loop + vertex -896.671 362.095 48.7676 + vertex -897.648 353.386 48.6428 + vertex -897.247 356.225 49.5053 + endloop + endfacet + facet normal -0.983925 0.143629 0.106126 + outer loop + vertex -895.375 371.065 48.6447 + vertex -896.671 362.095 48.7676 + vertex -895.962 366.345 49.5946 + endloop + endfacet + facet normal -0.977158 0.174478 0.121325 + outer loop + vertex -893.898 379.323 48.6698 + vertex -895.375 371.065 48.6447 + vertex -894.662 374.377 49.6227 + endloop + endfacet + facet normal -0.97088 0.199936 0.131977 + outer loop + vertex -892.239 387.343 48.7207 + vertex -893.898 379.323 48.6698 + vertex -893.119 382.441 49.6752 + endloop + endfacet + facet normal -0.536338 -0.540537 0.648198 + outer loop + vertex -854.705 230.597 27.834 + vertex -855.655 228.495 25.2954 + vertex -853.943 228.086 26.3702 + endloop + endfacet + facet normal -0.46157 -0.445759 0.766976 + outer loop + vertex -855.836 225.799 23.2642 + vertex -856.533 224.99 22.3746 + vertex -854.946 224.63 23.1206 + endloop + endfacet + facet normal -0.270129 -0.226598 0.93578 + outer loop + vertex -858.516 223.534 20.9907 + vertex -859.741 221.779 20.212 + vertex -857.15 222.198 21.0616 + endloop + endfacet + facet normal -0.394496 -0.285781 0.873328 + outer loop + vertex -857.361 224.074 21.5592 + vertex -857.439 223.553 21.3536 + vertex -856.362 223.72 21.8949 + endloop + endfacet + facet normal -0.304104 -0.262404 0.915786 + outer loop + vertex -857.439 223.553 21.3536 + vertex -858.516 223.534 20.9907 + vertex -857.15 222.198 21.0616 + endloop + endfacet + facet normal -0.151977 -0.138658 0.97861 + outer loop + vertex -860.876 219.567 19.5429 + vertex -861.282 217.48 19.1841 + vertex -859.276 217.18 19.4532 + endloop + endfacet + facet normal -0.0634827 -0.0681902 0.995651 + outer loop + vertex -861.282 217.48 19.1841 + vertex -863.031 218.311 19.1295 + vertex -860.521 213.567 18.9647 + endloop + endfacet + facet normal -0.198276 -0.189177 0.961716 + outer loop + vertex -859.741 221.779 20.212 + vertex -860.876 219.567 19.5429 + vertex -858.237 219.761 20.1253 + endloop + endfacet + facet normal -0.31887 -0.292749 0.901454 + outer loop + vertex -875.306 196.344 16.1406 + vertex -876.335 194.419 15.1516 + vertex -873.811 193.755 15.8289 + endloop + endfacet + facet normal -0.205734 -0.204121 0.957083 + outer loop + vertex -873.852 198.06 16.8193 + vertex -875.306 196.344 16.1406 + vertex -872.265 195.681 16.6531 + endloop + endfacet + facet normal -0.497074 -0.492362 0.714491 + outer loop + vertex -877.02 192.798 14.0353 + vertex -877.704 191.946 12.9723 + vertex -875.862 190.721 13.4095 + endloop + endfacet + facet normal -0.417765 -0.38901 0.821062 + outer loop + vertex -876.335 194.419 15.1516 + vertex -877.02 192.798 14.0353 + vertex -874.798 191.969 14.7729 + endloop + endfacet + facet normal -0.628875 -0.708811 0.319536 + outer loop + vertex -878.027 191.099 11.7145 + vertex -877.987 190.65 10.7974 + vertex -876.448 189.783 11.9043 + endloop + endfacet + facet normal -0.523553 -0.557136 0.644586 + outer loop + vertex -877.704 191.946 12.9723 + vertex -877.549 191.23 12.4794 + vertex -875.862 190.721 13.4095 + endloop + endfacet + facet normal -0.594279 -0.64384 0.481978 + outer loop + vertex -877.549 191.23 12.4794 + vertex -878.027 191.099 11.7145 + vertex -876.448 189.783 11.9043 + endloop + endfacet + facet normal -0.658316 -0.75093 -0.0521952 + outer loop + vertex -878.098 190.495 9.55247 + vertex -878.286 190.731 8.5342 + vertex -876.975 189.579 8.56213 + endloop + endfacet + facet normal -0.685451 -0.712605 0.149502 + outer loop + vertex -877.987 190.65 10.7974 + vertex -878.098 190.495 9.55247 + vertex -876.537 189.151 10.3037 + endloop + endfacet + facet normal -0.619824 -0.669252 -0.40978 + outer loop + vertex -878.157 190.965 7.58766 + vertex -878.156 191.558 6.61693 + vertex -877.251 190.513 6.95339 + endloop + endfacet + facet normal -0.632989 -0.727258 -0.265369 + outer loop + vertex -878.286 190.731 8.5342 + vertex -878.157 190.965 7.58766 + vertex -876.975 189.579 8.56213 + endloop + endfacet + facet normal -0.526993 -0.579364 -0.621784 + outer loop + vertex -877.71 191.815 5.85503 + vertex -877.156 192.002 5.21246 + vertex -876.287 190.534 5.84283 + endloop + endfacet + facet normal -0.430547 -0.43233 -0.792288 + outer loop + vertex -877.156 192.002 5.21246 + vertex -877.51 192.828 4.95408 + vertex -875.759 191.811 4.55684 + endloop + endfacet + facet normal -0.544311 -0.644681 -0.536761 + outer loop + vertex -878.156 191.558 6.61693 + vertex -877.71 191.815 5.85503 + vertex -877.251 190.513 6.95339 + endloop + endfacet + facet normal -0.333914 -0.300782 -0.893326 + outer loop + vertex -876.943 194.723 3.76897 + vertex -875.666 196.976 2.53324 + vertex -874.353 193.476 3.2211 + endloop + endfacet + facet normal -0.41318 -0.390534 -0.822658 + outer loop + vertex -877.51 192.828 4.95408 + vertex -876.943 194.723 3.76897 + vertex -875.759 191.811 4.55684 + endloop + endfacet + facet normal -0.167595 -0.198996 -0.965563 + outer loop + vertex -874.807 198.811 1.85143 + vertex -873.529 198.903 1.61072 + vertex -872.765 195.767 2.12426 + endloop + endfacet + facet normal -0.105134 -0.109827 -0.988375 + outer loop + vertex -873.529 198.903 1.61072 + vertex -874.522 201.314 1.44833 + vertex -870.893 198.696 1.35327 + endloop + endfacet + facet normal -0.233186 -0.240907 -0.942119 + outer loop + vertex -875.666 196.976 2.53324 + vertex -874.807 198.811 1.85143 + vertex -872.765 195.767 2.12426 + endloop + endfacet + facet normal -0.0926929 -0.0924742 -0.991391 + outer loop + vertex -874.522 201.314 1.44833 + vertex -873.719 206.263 0.911617 + vertex -870.893 198.696 1.35327 + endloop + endfacet + facet normal -0.203369 -0.913505 0.352348 + outer loop + vertex -534.461 74.7548 40.2228 + vertex -528.458 73.3982 40.171 + vertex -533.934 75.3626 42.1029 + endloop + endfacet + facet normal -0.220695 -0.908245 0.355506 + outer loop + vertex -541.103 76.3366 40.1413 + vertex -534.461 74.7548 40.2228 + vertex -533.934 75.3626 42.1029 + endloop + endfacet + facet normal -0.227174 -0.905989 0.357177 + outer loop + vertex -547.576 77.863 39.8959 + vertex -541.103 76.3366 40.1413 + vertex -548.126 78.7619 41.8258 + endloop + endfacet + facet normal -0.245918 -0.903613 0.350725 + outer loop + vertex -554.293 79.6214 39.7159 + vertex -547.576 77.863 39.8959 + vertex -548.126 78.7619 41.8258 + endloop + endfacet + facet normal -0.252652 -0.900429 0.354112 + outer loop + vertex -560.702 81.2948 39.399 + vertex -554.293 79.6214 39.7159 + vertex -561.474 82.2221 41.2058 + endloop + endfacet + facet normal -0.267911 -0.898868 0.346786 + outer loop + vertex -567.318 83.1471 39.0887 + vertex -560.702 81.2948 39.399 + vertex -561.474 82.2221 41.2058 + endloop + endfacet + facet normal -0.273181 -0.897437 0.346379 + outer loop + vertex -573.6 84.8914 38.6533 + vertex -567.318 83.1471 39.0887 + vertex -573.735 85.501 40.1263 + endloop + endfacet + facet normal -0.28404 -0.894856 0.344317 + outer loop + vertex -579.818 86.7187 38.2727 + vertex -573.6 84.8914 38.6533 + vertex -573.735 85.501 40.1263 + endloop + endfacet + facet normal -0.324759 -0.887663 0.326474 + outer loop + vertex -606.497 98.2048 44.6816 + vertex -607.931 97.4043 41.0782 + vertex -607.421 97.5895 42.0893 + endloop + endfacet + facet normal 0.36307 0.875672 -0.318401 + outer loop + vertex -605.3 99.1155 48.5514 + vertex -606.497 98.2048 44.6816 + vertex -606.214 98.4897 45.7872 + endloop + endfacet + facet normal -0.417019 -0.90793 -0.0419389 + outer loop + vertex -598.538 116.115 193.211 + vertex -598.477 116.243 189.833 + vertex -597.859 115.815 192.955 + endloop + endfacet + facet normal -0.420756 -0.905524 -0.0546861 + outer loop + vertex -598.558 116.019 194.958 + vertex -598.538 116.115 193.211 + vertex -597.859 115.815 192.955 + endloop + endfacet + facet normal -0.448033 -0.891605 -0.0656259 + outer loop + vertex -598.602 115.784 198.452 + vertex -598.558 116.019 194.958 + vertex -597.859 115.815 192.955 + endloop + endfacet + facet normal -0.411077 -0.909291 -0.0648527 + outer loop + vertex -598.692 115.579 201.895 + vertex -598.602 115.784 198.452 + vertex -597.979 115.301 201.278 + endloop + endfacet + facet normal -0.419929 -0.904254 -0.0773578 + outer loop + vertex -598.728 115.447 203.637 + vertex -598.692 115.579 201.895 + vertex -597.979 115.301 201.278 + endloop + endfacet + facet normal -0.449855 -0.888773 -0.0878246 + outer loop + vertex -598.77 115.131 207.051 + vertex -598.728 115.447 203.637 + vertex -597.979 115.301 201.278 + endloop + endfacet + facet normal -0.397285 -0.913291 -0.0898047 + outer loop + vertex -598.867 114.81 210.741 + vertex -598.77 115.131 207.051 + vertex -597.831 114.528 209.028 + endloop + endfacet + facet normal -0.414754 -0.904213 -0.101873 + outer loop + vertex -598.801 114.463 213.556 + vertex -598.867 114.81 210.741 + vertex -597.831 114.528 209.028 + endloop + endfacet + facet normal -0.403204 -0.908411 -0.110529 + outer loop + vertex -598.949 114.102 217.067 + vertex -598.801 114.463 213.556 + vertex -597.907 113.57 217.637 + endloop + endfacet + facet normal 0.316141 0.942899 0.104867 + outer loop + vertex -606.116 102.99 297.103 + vertex -604.877 103.076 292.589 + vertex -605.204 103.083 293.519 + endloop + endfacet + facet normal 0.299692 0.950894 0.0773595 + outer loop + vertex -607.546 103.093 301.377 + vertex -606.116 102.99 297.103 + vertex -606.52 103.039 298.067 + endloop + endfacet + facet normal -0.0260585 0.997318 -0.068399 + outer loop + vertex -608.898 103.311 305.076 + vertex -607.546 103.093 301.377 + vertex -607.909 103.142 302.232 + endloop + endfacet + facet normal -0.12729 -0.956825 0.261311 + outer loop + vertex -505.497 75.2679 58.2559 + vertex -506.148 76.4215 62.163 + vertex -506.301 76.0989 60.9069 + endloop + endfacet + facet normal -0.136222 -0.950239 0.280161 + outer loop + vertex -504.473 73.8329 53.8865 + vertex -505.497 75.2679 58.2559 + vertex -505.623 74.8421 56.7508 + endloop + endfacet + facet normal -0.143494 -0.942279 0.302521 + outer loop + vertex -503.061 72.1838 49.4197 + vertex -504.473 73.8329 53.8865 + vertex -504.566 73.3393 52.3054 + endloop + endfacet + facet normal -0.137091 -0.93376 0.330604 + outer loop + vertex -501.349 70.4326 45.1838 + vertex -503.061 72.1838 49.4197 + vertex -503.211 71.7301 48.0765 + endloop + endfacet + facet normal -0.0830515 -0.949884 0.30137 + outer loop + vertex -505.623 74.8421 56.7508 + vertex -504.566 73.3393 52.3054 + vertex -504.473 73.8329 53.8865 + endloop + endfacet + facet normal -0.0931861 -0.940114 0.327876 + outer loop + vertex -504.566 73.3393 52.3054 + vertex -503.211 71.7301 48.0765 + vertex -503.061 72.1838 49.4197 + endloop + endfacet + facet normal -0.197732 -0.909902 0.364663 + outer loop + vertex -522.638 72.3789 40.7834 + vertex -533.934 75.3626 42.1029 + vertex -528.458 73.3982 40.171 + endloop + endfacet + facet normal -0.223369 -0.902557 0.3681 + outer loop + vertex -533.934 75.3626 42.1029 + vertex -548.126 78.7619 41.8258 + vertex -541.103 76.3366 40.1413 + endloop + endfacet + facet normal -0.249541 -0.897412 0.363842 + outer loop + vertex -548.126 78.7619 41.8258 + vertex -561.474 82.2221 41.2058 + vertex -554.293 79.6214 39.7159 + endloop + endfacet + facet normal -0.270544 -0.894477 0.355972 + outer loop + vertex -561.474 82.2221 41.2058 + vertex -573.735 85.501 40.1263 + vertex -567.318 83.1471 39.0887 + endloop + endfacet + facet normal -0.285398 -0.891945 0.350687 + outer loop + vertex -573.735 85.501 40.1263 + vertex -583.572 88.2894 39.2125 + vertex -579.818 86.7187 38.2727 + endloop + endfacet + facet normal -0.432069 -0.86307 0.261584 + outer loop + vertex -602.866 101.301 58.6114 + vertex -601.131 103.175 67.6616 + vertex -602.343 102.475 63.3493 + endloop + endfacet + facet normal -0.41201 -0.880463 0.23459 + outer loop + vertex -601.131 103.175 67.6616 + vertex -600.064 105.127 76.8628 + vertex -601.059 104.608 73.1646 + endloop + endfacet + facet normal -0.420714 -0.905072 -0.0620042 + outer loop + vertex -597.859 115.815 192.955 + vertex -597.979 115.301 201.278 + vertex -598.602 115.784 198.452 + endloop + endfacet + facet normal -0.40906 -0.908742 -0.0828184 + outer loop + vertex -597.979 115.301 201.278 + vertex -597.831 114.528 209.028 + vertex -598.77 115.131 207.051 + endloop + endfacet + facet normal -0.424513 -0.899441 -0.103897 + outer loop + vertex -597.831 114.528 209.028 + vertex -597.907 113.57 217.637 + vertex -598.801 114.463 213.556 + endloop + endfacet + facet normal -0.074337 -0.992981 -0.0919904 + outer loop + vertex -602.014 103.927 281.041 + vertex -604.152 103.345 289.052 + vertex -603.751 103.506 286.992 + endloop + endfacet + facet normal -0.341676 -0.86999 0.355494 + outer loop + vertex -609.689 96.6854 37.5618 + vertex -608.692 96.9442 39.1531 + vertex -609.392 96.8695 38.2974 + endloop + endfacet + facet normal 0.255646 0.921248 -0.293168 + outer loop + vertex -606.214 98.4897 45.7872 + vertex -605.268 99.3765 49.3992 + vertex -605.3 99.1155 48.5514 + endloop + endfacet + facet normal 0.188955 0.938175 -0.290041 + outer loop + vertex -607.421 97.5895 42.0893 + vertex -606.214 98.4897 45.7872 + vertex -606.497 98.2048 44.6816 + endloop + endfacet + facet normal 0.418789 0.898751 0.129852 + outer loop + vertex -605.204 103.083 293.519 + vertex -606.52 103.039 298.067 + vertex -606.116 102.99 297.103 + endloop + endfacet + facet normal 0.417404 0.89774 0.140844 + outer loop + vertex -604.425 103.213 290.384 + vertex -605.204 103.083 293.519 + vertex -604.877 103.076 292.589 + endloop + endfacet + facet normal 0.336462 0.937485 0.0889729 + outer loop + vertex -606.52 103.039 298.067 + vertex -607.909 103.142 302.232 + vertex -607.546 103.093 301.377 + endloop + endfacet + facet normal -0.152547 -0.507341 0.848136 + outer loop + vertex -416.134 82.6529 356.164 + vertex -415.63 77.4662 353.152 + vertex -408.287 81.0381 356.609 + endloop + endfacet + facet normal -0.154083 -0.505169 0.849154 + outer loop + vertex -408.287 81.0381 356.609 + vertex -415.63 77.4662 353.152 + vertex -408.033 75.4377 353.324 + endloop + endfacet + facet normal -0.14713 -0.517839 0.842731 + outer loop + vertex -426.748 83.3652 354.749 + vertex -425.554 79.1297 352.354 + vertex -416.134 82.6529 356.164 + endloop + endfacet + facet normal -0.153197 -0.507337 0.848021 + outer loop + vertex -416.134 82.6529 356.164 + vertex -425.554 79.1297 352.354 + vertex -415.63 77.4662 353.152 + endloop + endfacet + facet normal -0.154047 -0.526786 0.835922 + outer loop + vertex -437.076 84.7158 353.696 + vertex -436.478 80.7592 351.313 + vertex -426.748 83.3652 354.749 + endloop + endfacet + facet normal -0.157513 -0.51922 0.84 + outer loop + vertex -426.748 83.3652 354.749 + vertex -436.478 80.7592 351.313 + vertex -425.554 79.1297 352.354 + endloop + endfacet + facet normal -0.160588 -0.537271 0.82798 + outer loop + vertex -447.7 86.4844 352.784 + vertex -447.505 82.6569 350.338 + vertex -437.076 84.7158 353.696 + endloop + endfacet + facet normal -0.164466 -0.527059 0.833762 + outer loop + vertex -437.076 84.7158 353.696 + vertex -447.505 82.6569 350.338 + vertex -436.478 80.7592 351.313 + endloop + endfacet + facet normal -0.164584 -0.552362 0.817195 + outer loop + vertex -458.938 88.6157 351.961 + vertex -458.845 84.8829 349.456 + vertex -447.7 86.4844 352.784 + endloop + endfacet + facet normal -0.1696 -0.536784 0.826498 + outer loop + vertex -447.7 86.4844 352.784 + vertex -458.845 84.8829 349.456 + vertex -447.505 82.6569 350.338 + endloop + endfacet + facet normal -0.166156 -0.568348 0.805837 + outer loop + vertex -470.442 91.0963 351.338 + vertex -470.48 87.4748 348.776 + vertex -458.938 88.6157 351.961 + endloop + endfacet + facet normal -0.17066 -0.551891 0.816267 + outer loop + vertex -458.938 88.6157 351.961 + vertex -470.48 87.4748 348.776 + vertex -458.845 84.8829 349.456 + endloop + endfacet + facet normal -0.167022 -0.576663 0.799727 + outer loop + vertex -480.976 93.7721 351.068 + vertex -481.459 90.3593 348.506 + vertex -470.442 91.0963 351.338 + endloop + endfacet + facet normal -0.169069 -0.568042 0.805447 + outer loop + vertex -470.442 91.0963 351.338 + vertex -481.459 90.3593 348.506 + vertex -470.48 87.4748 348.776 + endloop + endfacet + facet normal -0.167273 -0.575294 0.80066 + outer loop + vertex -488.489 96.1217 351.186 + vertex -490.142 93.3658 348.861 + vertex -480.976 93.7721 351.068 + endloop + endfacet + facet normal -0.166988 -0.576669 0.79973 + outer loop + vertex -480.976 93.7721 351.068 + vertex -490.142 93.3658 348.861 + vertex -481.459 90.3593 348.506 + endloop + endfacet + facet normal -0.171193 -0.583089 0.794166 + outer loop + vertex -500.194 99.4862 351.165 + vertex -500.473 95.1416 347.915 + vertex -495.66 96.8442 350.202 + endloop + endfacet + facet normal -0.155645 -0.607039 0.77928 + outer loop + vertex -495.66 96.8442 350.202 + vertex -500.473 95.1416 347.915 + vertex -496.787 92.6893 346.741 + endloop + endfacet + facet normal -0.165328 -0.549858 0.818733 + outer loop + vertex -415.63 77.4662 353.152 + vertex -415.252 72.9978 350.227 + vertex -408.033 75.4377 353.324 + endloop + endfacet + facet normal -0.162092 -0.555454 0.815596 + outer loop + vertex -408.033 75.4377 353.324 + vertex -415.252 72.9978 350.227 + vertex -408.363 70.9996 350.236 + endloop + endfacet + facet normal -0.159131 -0.559262 0.813574 + outer loop + vertex -425.554 79.1297 352.354 + vertex -424.912 74.9559 349.611 + vertex -415.63 77.4662 353.152 + endloop + endfacet + facet normal -0.163737 -0.549909 0.819018 + outer loop + vertex -415.63 77.4662 353.152 + vertex -424.912 74.9559 349.611 + vertex -415.252 72.9978 350.227 + endloop + endfacet + facet normal -0.162145 -0.574267 0.80245 + outer loop + vertex -436.478 80.7592 351.313 + vertex -435.888 76.9084 348.677 + vertex -425.554 79.1297 352.354 + endloop + endfacet + facet normal -0.168587 -0.5594 0.811572 + outer loop + vertex -425.554 79.1297 352.354 + vertex -435.888 76.9084 348.677 + vertex -424.912 74.9559 349.611 + endloop + endfacet + facet normal -0.171099 -0.587691 0.790787 + outer loop + vertex -447.505 82.6569 350.338 + vertex -447.181 78.9654 347.664 + vertex -436.478 80.7592 351.313 + endloop + endfacet + facet normal -0.176274 -0.574348 0.799407 + outer loop + vertex -436.478 80.7592 351.313 + vertex -447.181 78.9654 347.664 + vertex -435.888 76.9084 348.677 + endloop + endfacet + facet normal -0.178925 -0.604043 0.776607 + outer loop + vertex -458.845 84.8829 349.456 + vertex -458.658 81.2794 346.697 + vertex -447.505 82.6569 350.338 + endloop + endfacet + facet normal -0.184811 -0.587019 0.788197 + outer loop + vertex -447.505 82.6569 350.338 + vertex -458.658 81.2794 346.697 + vertex -447.181 78.9654 347.664 + endloop + endfacet + facet normal -0.182756 -0.62021 0.76285 + outer loop + vertex -470.48 87.4748 348.776 + vertex -470.366 83.9205 345.914 + vertex -458.845 84.8829 349.456 + endloop + endfacet + facet normal -0.187918 -0.603315 0.775047 + outer loop + vertex -458.845 84.8829 349.456 + vertex -470.366 83.9205 345.914 + vertex -458.658 81.2794 346.697 + endloop + endfacet + facet normal -0.183781 -0.628704 0.755616 + outer loop + vertex -481.459 90.3593 348.506 + vertex -481.592 86.8404 345.546 + vertex -470.48 87.4748 348.776 + endloop + endfacet + facet normal -0.186225 -0.619869 0.762288 + outer loop + vertex -470.48 87.4748 348.776 + vertex -481.592 86.8404 345.546 + vertex -470.366 83.9205 345.914 + endloop + endfacet + facet normal -0.185028 -0.623993 0.759209 + outer loop + vertex -490.142 93.3658 348.861 + vertex -490.759 89.8375 345.811 + vertex -481.459 90.3593 348.506 + endloop + endfacet + facet normal -0.183724 -0.628712 0.755623 + outer loop + vertex -481.459 90.3593 348.506 + vertex -490.759 89.8375 345.811 + vertex -481.592 86.8404 345.546 + endloop + endfacet + facet normal -0.19712 -0.648371 0.735363 + outer loop + vertex -500.473 95.1416 347.915 + vertex -500.243 91.309 344.597 + vertex -496.787 92.6893 346.741 + endloop + endfacet + facet normal -0.176083 -0.673681 0.717739 + outer loop + vertex -496.787 92.6893 346.741 + vertex -500.243 91.309 344.597 + vertex -496.924 89.1531 343.388 + endloop + endfacet + facet normal -0.176249 -0.604415 0.776929 + outer loop + vertex -415.252 72.9978 350.227 + vertex -414.846 69.3023 347.445 + vertex -408.363 70.9996 350.236 + endloop + endfacet + facet normal -0.171948 -0.612277 0.77172 + outer loop + vertex -408.363 70.9996 350.236 + vertex -414.846 69.3023 347.445 + vertex -407.381 67.2353 347.468 + endloop + endfacet + facet normal -0.173247 -0.611667 0.771913 + outer loop + vertex -424.912 74.9559 349.611 + vertex -424.436 71.3642 346.872 + vertex -415.252 72.9978 350.227 + endloop + endfacet + facet normal -0.176363 -0.604411 0.776906 + outer loop + vertex -415.252 72.9978 350.227 + vertex -424.436 71.3642 346.872 + vertex -414.846 69.3023 347.445 + endloop + endfacet + facet normal -0.175954 -0.625371 0.760231 + outer loop + vertex -435.888 76.9084 348.677 + vertex -435.386 73.4561 345.953 + vertex -424.912 74.9559 349.611 + endloop + endfacet + facet normal -0.18143 -0.611449 0.770204 + outer loop + vertex -424.912 74.9559 349.611 + vertex -435.386 73.4561 345.953 + vertex -424.436 71.3642 346.872 + endloop + endfacet + facet normal -0.183959 -0.644875 0.741819 + outer loop + vertex -447.181 78.9654 347.664 + vertex -446.776 75.6561 344.888 + vertex -435.888 76.9084 348.677 + endloop + endfacet + facet normal -0.191475 -0.624941 0.756826 + outer loop + vertex -435.888 76.9084 348.677 + vertex -446.776 75.6561 344.888 + vertex -435.386 73.4561 345.953 + endloop + endfacet + facet normal -0.194689 -0.66355 0.722355 + outer loop + vertex -458.658 81.2794 346.697 + vertex -458.316 78.0382 343.812 + vertex -447.181 78.9654 347.664 + endloop + endfacet + facet normal -0.201755 -0.643885 0.738043 + outer loop + vertex -447.181 78.9654 347.664 + vertex -458.316 78.0382 343.812 + vertex -446.776 75.6561 344.888 + endloop + endfacet + facet normal -0.200892 -0.682177 0.703048 + outer loop + vertex -470.366 83.9205 345.914 + vertex -470.054 80.6974 342.876 + vertex -458.658 81.2794 346.697 + endloop + endfacet + facet normal -0.207482 -0.662547 0.71971 + outer loop + vertex -458.658 81.2794 346.697 + vertex -470.054 80.6974 342.876 + vertex -458.316 78.0382 343.812 + endloop + endfacet + facet normal -0.203043 -0.693477 0.691277 + outer loop + vertex -481.592 86.8404 345.546 + vertex -481.357 83.6032 342.367 + vertex -470.366 83.9205 345.914 + endloop + endfacet + facet normal -0.206801 -0.681632 0.701863 + outer loop + vertex -470.366 83.9205 345.914 + vertex -481.357 83.6032 342.367 + vertex -470.054 80.6974 342.876 + endloop + endfacet + facet normal -0.204904 -0.688216 0.695969 + outer loop + vertex -490.759 89.8375 345.811 + vertex -490.719 86.522 342.544 + vertex -481.592 86.8404 345.546 + endloop + endfacet + facet normal -0.20317 -0.693463 0.691253 + outer loop + vertex -481.592 86.8404 345.546 + vertex -490.719 86.522 342.544 + vertex -481.357 83.6032 342.367 + endloop + endfacet + facet normal -0.224152 -0.715959 0.661179 + outer loop + vertex -500.243 91.309 344.597 + vertex -500.234 88.1451 341.174 + vertex -496.924 89.1531 343.388 + endloop + endfacet + facet normal -0.204203 -0.739108 0.641889 + outer loop + vertex -496.924 89.1531 343.388 + vertex -500.234 88.1451 341.174 + vertex -496.741 86.0982 339.928 + endloop + endfacet + facet normal -0.184676 -0.658714 0.729377 + outer loop + vertex -414.846 69.3023 347.445 + vertex -414.281 66.1486 344.739 + vertex -407.381 67.2353 347.468 + endloop + endfacet + facet normal -0.184106 -0.659931 0.72842 + outer loop + vertex -407.381 67.2353 347.468 + vertex -414.281 66.1486 344.739 + vertex -407.216 63.9873 344.567 + endloop + endfacet + facet normal -0.186248 -0.665406 0.722874 + outer loop + vertex -424.436 71.3642 346.872 + vertex -423.882 68.302 344.195 + vertex -414.846 69.3023 347.445 + endloop + endfacet + facet normal -0.188974 -0.658615 0.728365 + outer loop + vertex -414.846 69.3023 347.445 + vertex -423.882 68.302 344.195 + vertex -414.281 66.1486 344.739 + endloop + endfacet + facet normal -0.189683 -0.683215 0.705151 + outer loop + vertex -435.386 73.4561 345.953 + vertex -434.834 70.4957 343.233 + vertex -424.436 71.3642 346.872 + endloop + endfacet + facet normal -0.196535 -0.665116 0.720413 + outer loop + vertex -424.436 71.3642 346.872 + vertex -434.834 70.4957 343.233 + vertex -423.882 68.302 344.195 + endloop + endfacet + facet normal -0.199466 -0.701451 0.684237 + outer loop + vertex -446.776 75.6561 344.888 + vertex -446.217 72.7603 342.082 + vertex -435.386 73.4561 345.953 + endloop + endfacet + facet normal -0.206669 -0.682565 0.700995 + outer loop + vertex -435.386 73.4561 345.953 + vertex -446.217 72.7603 342.082 + vertex -434.834 70.4957 343.233 + endloop + endfacet + facet normal -0.210558 -0.722425 0.65861 + outer loop + vertex -458.316 78.0382 343.812 + vertex -457.736 75.1854 340.868 + vertex -446.776 75.6561 344.888 + endloop + endfacet + facet normal -0.219082 -0.700424 0.679271 + outer loop + vertex -446.776 75.6561 344.888 + vertex -457.736 75.1854 340.868 + vertex -446.217 72.7603 342.082 + endloop + endfacet + facet normal -0.218641 -0.742118 0.633606 + outer loop + vertex -470.054 80.6974 342.876 + vertex -469.443 77.8289 339.727 + vertex -458.316 78.0382 343.812 + endloop + endfacet + facet normal -0.226669 -0.721366 0.65441 + outer loop + vertex -458.316 78.0382 343.812 + vertex -469.443 77.8289 339.727 + vertex -457.736 75.1854 340.868 + endloop + endfacet + facet normal -0.222395 -0.757764 0.613461 + outer loop + vertex -481.357 83.6032 342.367 + vertex -480.909 80.6929 338.935 + vertex -470.054 80.6974 342.876 + endloop + endfacet + facet normal -0.228747 -0.741344 0.630939 + outer loop + vertex -470.054 80.6974 342.876 + vertex -480.909 80.6929 338.935 + vertex -469.443 77.8289 339.727 + endloop + endfacet + facet normal -0.223861 -0.755262 0.616008 + outer loop + vertex -490.719 86.522 342.544 + vertex -490.482 83.5769 339.019 + vertex -481.357 83.6032 342.367 + endloop + endfacet + facet normal -0.222879 -0.75771 0.613352 + outer loop + vertex -481.357 83.6032 342.367 + vertex -490.482 83.5769 339.019 + vertex -480.909 80.6929 338.935 + endloop + endfacet + facet normal -0.245447 -0.77404 0.583625 + outer loop + vertex -500.234 88.1451 341.174 + vertex -499.732 85.2651 337.566 + vertex -496.741 86.0982 339.928 + endloop + endfacet + facet normal -0.224826 -0.794145 0.564611 + outer loop + vertex -496.741 86.0982 339.928 + vertex -499.732 85.2651 337.566 + vertex -496.583 83.5022 336.34 + endloop + endfacet + facet normal -0.199297 -0.705718 0.679884 + outer loop + vertex -414.281 66.1486 344.739 + vertex -413.543 63.426 342.13 + vertex -407.216 63.9873 344.567 + endloop + endfacet + facet normal -0.198415 -0.707722 0.678057 + outer loop + vertex -407.216 63.9873 344.567 + vertex -413.543 63.426 342.13 + vertex -406.461 61.4185 342.107 + endloop + endfacet + facet normal -0.198534 -0.716227 0.669031 + outer loop + vertex -423.882 68.302 344.195 + vertex -423.114 65.6349 341.568 + vertex -414.281 66.1486 344.739 + endloop + endfacet + facet normal -0.202691 -0.705697 0.678902 + outer loop + vertex -414.281 66.1486 344.739 + vertex -423.114 65.6349 341.568 + vertex -413.543 63.426 342.13 + endloop + endfacet + facet normal -0.203843 -0.732889 0.649093 + outer loop + vertex -434.834 70.4957 343.233 + vertex -434.025 67.8931 340.549 + vertex -423.882 68.302 344.195 + endloop + endfacet + facet normal -0.210409 -0.716147 0.665478 + outer loop + vertex -423.882 68.302 344.195 + vertex -434.025 67.8931 340.549 + vertex -423.114 65.6349 341.568 + endloop + endfacet + facet normal -0.212747 -0.752797 0.622924 + outer loop + vertex -446.217 72.7603 342.082 + vertex -445.361 70.2038 339.285 + vertex -434.834 70.4957 343.233 + endloop + endfacet + facet normal -0.221089 -0.732665 0.643678 + outer loop + vertex -434.834 70.4957 343.233 + vertex -445.361 70.2038 339.285 + vertex -434.025 67.8931 340.549 + endloop + endfacet + facet normal -0.22525 -0.772666 0.593507 + outer loop + vertex -457.736 75.1854 340.868 + vertex -456.812 72.6446 337.911 + vertex -446.217 72.7603 342.082 + endloop + endfacet + facet normal -0.234264 -0.752242 0.615834 + outer loop + vertex -446.217 72.7603 342.082 + vertex -456.812 72.6446 337.911 + vertex -445.361 70.2038 339.285 + endloop + endfacet + facet normal -0.23371 -0.79091 0.565545 + outer loop + vertex -469.443 77.8289 339.727 + vertex -468.381 75.2503 336.559 + vertex -457.736 75.1854 340.868 + endloop + endfacet + facet normal -0.242499 -0.772001 0.587545 + outer loop + vertex -457.736 75.1854 340.868 + vertex -468.381 75.2503 336.559 + vertex -456.812 72.6446 337.911 + endloop + endfacet + facet normal -0.238692 -0.805736 0.542047 + outer loop + vertex -480.909 80.6929 338.935 + vertex -479.768 77.9846 335.411 + vertex -469.443 77.8289 339.727 + endloop + endfacet + facet normal -0.246337 -0.790392 0.560891 + outer loop + vertex -469.443 77.8289 339.727 + vertex -479.768 77.9846 335.411 + vertex -468.381 75.2503 336.559 + endloop + endfacet + facet normal -0.239758 -0.811395 0.533062 + outer loop + vertex -490.482 83.5769 339.019 + vertex -490.613 80.8 334.733 + vertex -480.909 80.6929 338.935 + endloop + endfacet + facet normal -0.242917 -0.805509 0.540506 + outer loop + vertex -480.909 80.6929 338.935 + vertex -490.613 80.8 334.733 + vertex -479.768 77.9846 335.411 + endloop + endfacet + facet normal -0.253859 -0.81529 0.52044 + outer loop + vertex -499.732 85.2651 337.566 + vertex -499.474 82.9827 334.116 + vertex -496.583 83.5022 336.34 + endloop + endfacet + facet normal -0.234709 -0.833705 0.499848 + outer loop + vertex -496.583 83.5022 336.34 + vertex -499.474 82.9827 334.116 + vertex -496.92 81.6811 333.145 + endloop + endfacet + facet normal -0.211292 -0.752523 0.623751 + outer loop + vertex -413.543 63.426 342.13 + vertex -412.466 61.09 339.676 + vertex -406.461 61.4185 342.107 + endloop + endfacet + facet normal -0.210223 -0.754755 0.621411 + outer loop + vertex -406.461 61.4185 342.107 + vertex -412.466 61.09 339.676 + vertex -405.39 59.2211 339.8 + endloop + endfacet + facet normal -0.211639 -0.761234 0.61297 + outer loop + vertex -423.114 65.6349 341.568 + vertex -422.01 63.2765 339.021 + vertex -413.543 63.426 342.13 + endloop + endfacet + facet normal -0.215182 -0.752697 0.622209 + outer loop + vertex -413.543 63.426 342.13 + vertex -422.01 63.2765 339.021 + vertex -412.466 61.09 339.676 + endloop + endfacet + facet normal -0.21605 -0.776776 0.591559 + outer loop + vertex -434.025 67.8931 340.549 + vertex -432.837 65.5637 337.924 + vertex -423.114 65.6349 341.568 + endloop + endfacet + facet normal -0.22255 -0.761625 0.608604 + outer loop + vertex -423.114 65.6349 341.568 + vertex -432.837 65.5637 337.924 + vertex -422.01 63.2765 339.021 + endloop + endfacet + facet normal -0.224884 -0.795848 0.562186 + outer loop + vertex -445.361 70.2038 339.285 + vertex -444.081 67.9036 336.541 + vertex -434.025 67.8931 340.549 + endloop + endfacet + facet normal -0.233602 -0.777334 0.584108 + outer loop + vertex -434.025 67.8931 340.549 + vertex -444.081 67.9036 336.541 + vertex -432.837 65.5637 337.924 + endloop + endfacet + facet normal -0.237162 -0.814183 0.529962 + outer loop + vertex -456.812 72.6446 337.911 + vertex -455.458 70.3529 334.996 + vertex -445.361 70.2038 339.285 + endloop + endfacet + facet normal -0.246458 -0.796265 0.552468 + outer loop + vertex -445.361 70.2038 339.285 + vertex -455.458 70.3529 334.996 + vertex -444.081 67.9036 336.541 + endloop + endfacet + facet normal -0.245462 -0.830931 0.499301 + outer loop + vertex -468.381 75.2503 336.559 + vertex -466.925 72.9429 333.435 + vertex -456.812 72.6446 337.911 + endloop + endfacet + facet normal -0.254885 -0.814156 0.521713 + outer loop + vertex -456.812 72.6446 337.911 + vertex -466.925 72.9429 333.435 + vertex -455.458 70.3529 334.996 + endloop + endfacet + facet normal -0.250282 -0.840693 0.480203 + outer loop + vertex -479.768 77.9846 335.411 + vertex -477.925 75.5477 332.106 + vertex -468.381 75.2503 336.559 + endloop + endfacet + facet normal -0.256435 -0.830754 0.494053 + outer loop + vertex -468.381 75.2503 336.559 + vertex -477.925 75.5477 332.106 + vertex -466.925 72.9429 333.435 + endloop + endfacet + facet normal -0.249938 -0.851895 0.460225 + outer loop + vertex -490.613 80.8 334.733 + vertex -487.653 77.8921 330.958 + vertex -479.768 77.9846 335.411 + endloop + endfacet + facet normal -0.258727 -0.840777 0.475556 + outer loop + vertex -479.768 77.9846 335.411 + vertex -487.653 77.8921 330.958 + vertex -477.925 75.5477 332.106 + endloop + endfacet + facet normal -0.262605 -0.852595 0.451796 + outer loop + vertex -499.474 82.9827 334.116 + vertex -498.697 80.9281 330.69 + vertex -496.92 81.6811 333.145 + endloop + endfacet + facet normal -0.238995 -0.866186 0.438865 + outer loop + vertex -496.92 81.6811 333.145 + vertex -498.697 80.9281 330.69 + vertex -494.79 79.6484 330.293 + endloop + endfacet + facet normal -0.221196 -0.800573 0.556916 + outer loop + vertex -412.466 61.09 339.676 + vertex -411.169 59.0918 337.319 + vertex -405.39 59.2211 339.8 + endloop + endfacet + facet normal -0.219793 -0.803131 0.553779 + outer loop + vertex -405.39 59.2211 339.8 + vertex -411.169 59.0918 337.319 + vertex -404.166 57.3303 337.544 + endloop + endfacet + facet normal -0.222445 -0.806887 0.547222 + outer loop + vertex -422.01 63.2765 339.021 + vertex -420.587 61.2203 336.567 + vertex -412.466 61.09 339.676 + endloop + endfacet + facet normal -0.225284 -0.800838 0.554893 + outer loop + vertex -412.466 61.09 339.676 + vertex -420.587 61.2203 336.567 + vertex -411.169 59.0918 337.319 + endloop + endfacet + facet normal -0.226388 -0.818215 0.528463 + outer loop + vertex -432.837 65.5637 337.924 + vertex -431.268 63.4922 335.389 + vertex -422.01 63.2765 339.021 + endloop + endfacet + facet normal -0.231622 -0.807534 0.542439 + outer loop + vertex -422.01 63.2765 339.021 + vertex -431.268 63.4922 335.389 + vertex -420.587 61.2203 336.567 + endloop + endfacet + facet normal -0.234956 -0.8344 0.49857 + outer loop + vertex -444.081 67.9036 336.541 + vertex -442.37 65.8408 333.895 + vertex -432.837 65.5637 337.924 + endloop + endfacet + facet normal -0.243178 -0.819418 0.519055 + outer loop + vertex -432.837 65.5637 337.924 + vertex -442.37 65.8408 333.895 + vertex -431.268 63.4922 335.389 + endloop + endfacet + facet normal -0.246278 -0.848689 0.468053 + outer loop + vertex -455.458 70.3529 334.996 + vertex -453.655 68.2834 332.192 + vertex -444.081 67.9036 336.541 + endloop + endfacet + facet normal -0.254344 -0.835574 0.486955 + outer loop + vertex -444.081 67.9036 336.541 + vertex -453.655 68.2834 332.192 + vertex -442.37 65.8408 333.895 + endloop + endfacet + facet normal -0.254319 -0.863184 0.43616 + outer loop + vertex -466.925 72.9429 333.435 + vertex -465.14 70.8822 330.398 + vertex -455.458 70.3529 334.996 + endloop + endfacet + facet normal -0.263626 -0.84931 0.457355 + outer loop + vertex -455.458 70.3529 334.996 + vertex -465.14 70.8822 330.398 + vertex -453.655 68.2834 332.192 + endloop + endfacet + facet normal -0.256801 -0.874928 0.410554 + outer loop + vertex -477.925 75.5477 332.106 + vertex -476.316 73.5358 328.824 + vertex -466.925 72.9429 333.435 + endloop + endfacet + facet normal -0.265411 -0.863131 0.429607 + outer loop + vertex -466.925 72.9429 333.435 + vertex -476.316 73.5358 328.824 + vertex -465.14 70.8822 330.398 + endloop + endfacet + facet normal -0.259094 -0.876822 0.405035 + outer loop + vertex -487.653 77.8921 330.958 + vertex -484.771 75.768 328.204 + vertex -477.925 75.5477 332.106 + endloop + endfacet + facet normal -0.260941 -0.874714 0.408394 + outer loop + vertex -477.925 75.5477 332.106 + vertex -484.771 75.768 328.204 + vertex -476.316 73.5358 328.824 + endloop + endfacet + facet normal -0.250991 -0.886927 0.387767 + outer loop + vertex -498.697 80.9281 330.69 + vertex -497.134 78.859 326.97 + vertex -494.79 79.6484 330.293 + endloop + endfacet + facet normal -0.244164 -0.890546 0.383811 + outer loop + vertex -494.79 79.6484 330.293 + vertex -497.134 78.859 326.97 + vertex -492.165 77.1324 326.124 + endloop + endfacet + facet normal -0.2286 -0.847739 0.478624 + outer loop + vertex -411.169 59.0918 337.319 + vertex -409.748 57.418 335.033 + vertex -404.166 57.3303 337.544 + endloop + endfacet + facet normal -0.226888 -0.850387 0.474726 + outer loop + vertex -404.166 57.3303 337.544 + vertex -409.748 57.418 335.033 + vertex -402.763 55.7266 335.341 + endloop + endfacet + facet normal -0.230076 -0.851772 0.470691 + outer loop + vertex -420.587 61.2203 336.567 + vertex -419.011 59.4856 334.199 + vertex -411.169 59.0918 337.319 + endloop + endfacet + facet normal -0.232206 -0.847939 0.476528 + outer loop + vertex -411.169 59.0918 337.319 + vertex -419.011 59.4856 334.199 + vertex -409.748 57.418 335.033 + endloop + endfacet + facet normal -0.233027 -0.862022 0.450129 + outer loop + vertex -431.268 63.4922 335.389 + vertex -429.494 61.7313 332.935 + vertex -420.587 61.2203 336.567 + endloop + endfacet + facet normal -0.238685 -0.852328 0.465368 + outer loop + vertex -420.587 61.2203 336.567 + vertex -429.494 61.7313 332.935 + vertex -419.011 59.4856 334.199 + endloop + endfacet + facet normal -0.241762 -0.87151 0.426639 + outer loop + vertex -442.37 65.8408 333.895 + vertex -440.397 64.0516 331.358 + vertex -431.268 63.4922 335.389 + endloop + endfacet + facet normal -0.247353 -0.863013 0.440483 + outer loop + vertex -431.268 63.4922 335.389 + vertex -440.397 64.0516 331.358 + vertex -429.494 61.7313 332.935 + endloop + endfacet + facet normal -0.25077 -0.884903 0.392507 + outer loop + vertex -453.655 68.2834 332.192 + vertex -451.557 66.5001 329.512 + vertex -442.37 65.8408 333.895 + endloop + endfacet + facet normal -0.259856 -0.872687 0.413391 + outer loop + vertex -442.37 65.8408 333.895 + vertex -451.557 66.5001 329.512 + vertex -440.397 64.0516 331.358 + endloop + endfacet + facet normal -0.259366 -0.894006 0.365353 + outer loop + vertex -465.14 70.8822 330.398 + vertex -463.006 69.0869 327.52 + vertex -453.655 68.2834 332.192 + endloop + endfacet + facet normal -0.266319 -0.885504 0.380731 + outer loop + vertex -453.655 68.2834 332.192 + vertex -463.006 69.0869 327.52 + vertex -451.557 66.5001 329.512 + endloop + endfacet + facet normal -0.262531 -0.901093 0.345122 + outer loop + vertex -476.316 73.5358 328.824 + vertex -474.465 71.7668 325.614 + vertex -465.14 70.8822 330.398 + endloop + endfacet + facet normal -0.268701 -0.894042 0.358453 + outer loop + vertex -465.14 70.8822 330.398 + vertex -474.465 71.7668 325.614 + vertex -463.006 69.0869 327.52 + endloop + endfacet + facet normal -0.263504 -0.905491 0.332644 + outer loop + vertex -484.771 75.768 328.204 + vertex -485.519 74.4765 324.096 + vertex -476.316 73.5358 328.824 + endloop + endfacet + facet normal -0.267785 -0.900769 0.341915 + outer loop + vertex -476.316 73.5358 328.824 + vertex -485.519 74.4765 324.096 + vertex -474.465 71.7668 325.614 + endloop + endfacet + facet normal -0.26259 -0.911142 0.317596 + outer loop + vertex -497.134 78.859 326.97 + vertex -495.82 77.0016 322.727 + vertex -492.165 77.1324 326.124 + endloop + endfacet + facet normal -0.251568 -0.91819 0.306009 + outer loop + vertex -492.165 77.1324 326.124 + vertex -495.82 77.0016 322.727 + vertex -492.821 75.6907 321.26 + endloop + endfacet + facet normal -0.319713 -0.937336 0.138512 + outer loop + vertex -494.615 75.4824 318.337 + vertex -492.618 74.2096 314.333 + vertex -492.276 74.4633 316.837 + endloop + endfacet + facet normal -0.276486 -0.956402 0.0940772 + outer loop + vertex -492.618 74.2096 314.333 + vertex -490.416 73.2366 310.911 + vertex -489.427 73.1607 313.046 + endloop + endfacet + facet normal -0.16693 -0.506456 0.845953 + outer loop + vertex -404.343 75.3608 354.006 + vertex -404.744 78.9861 356.097 + vertex -408.033 75.4377 353.324 + endloop + endfacet + facet normal -0.164109 -0.537402 0.827204 + outer loop + vertex -405.098 72.6409 352.089 + vertex -404.343 75.3608 354.006 + vertex -408.033 75.4377 353.324 + endloop + endfacet + facet normal -0.16 -0.582023 0.797276 + outer loop + vertex -404.532 69.498 349.908 + vertex -405.098 72.6409 352.089 + vertex -408.363 70.9996 350.236 + endloop + endfacet + facet normal -0.180434 -0.607289 0.77372 + outer loop + vertex -403.979 67.0337 348.103 + vertex -404.532 69.498 349.908 + vertex -407.381 67.2353 347.468 + endloop + endfacet + facet normal -0.176865 -0.646431 0.74219 + outer loop + vertex -403.527 64.6279 346.115 + vertex -403.979 67.0337 348.103 + vertex -407.381 67.2353 347.468 + endloop + endfacet + facet normal -0.183304 -0.674027 0.715603 + outer loop + vertex -403.158 62.0929 343.822 + vertex -403.527 64.6279 346.115 + vertex -407.216 63.9873 344.567 + endloop + endfacet + facet normal -0.19721 -0.721738 0.663478 + outer loop + vertex -402.374 59.9141 341.685 + vertex -403.158 62.0929 343.822 + vertex -406.461 61.4185 342.107 + endloop + endfacet + facet normal -0.2054 -0.765295 0.610028 + outer loop + vertex -401.385 57.8994 339.49 + vertex -402.374 59.9141 341.685 + vertex -405.39 59.2211 339.8 + endloop + endfacet + facet normal -0.212691 -0.813297 0.541582 + outer loop + vertex -400.206 56.134 337.302 + vertex -401.385 57.8994 339.49 + vertex -404.166 57.3303 337.544 + endloop + endfacet + facet normal -0.218903 -0.858464 0.463811 + outer loop + vertex -398.694 54.5913 335.161 + vertex -400.206 56.134 337.302 + vertex -402.763 55.7266 335.341 + endloop + endfacet + facet normal -0.222833 -0.897563 0.380429 + outer loop + vertex -397.044 53.3045 333.091 + vertex -398.694 54.5913 335.161 + vertex -401.232 54.4059 333.237 + endloop + endfacet + facet normal -0.221741 -0.925889 0.305876 + outer loop + vertex -395.548 52.3116 331.17 + vertex -397.044 53.3045 333.091 + vertex -399.601 53.3481 331.37 + endloop + endfacet + facet normal -0.267582 -0.95423 0.133585 + outer loop + vertex -495.48 75.2273 315.869 + vertex -493.636 74.1878 312.138 + vertex -492.618 74.2096 314.333 + endloop + endfacet + facet normal -0.274871 -0.94176 0.193739 + outer loop + vertex -497.403 76.6627 320.118 + vertex -495.48 75.2273 315.869 + vertex -494.615 75.4824 318.337 + endloop + endfacet + facet normal -0.261438 -0.924125 0.278645 + outer loop + vertex -498.627 78.2894 324.365 + vertex -497.403 76.6627 320.118 + vertex -495.82 77.0016 322.727 + endloop + endfacet + facet normal -0.258094 -0.902328 0.345243 + outer loop + vertex -500.24 80.1705 328.076 + vertex -498.627 78.2894 324.365 + vertex -497.134 78.859 326.97 + endloop + endfacet + facet normal -0.264864 -0.873143 0.409228 + outer loop + vertex -501.404 82.1993 331.651 + vertex -500.24 80.1705 328.076 + vertex -498.697 80.9281 330.69 + endloop + endfacet + facet normal -0.264649 -0.839797 0.474026 + outer loop + vertex -501.911 84.3245 335.133 + vertex -501.404 82.1993 331.651 + vertex -499.474 82.9827 334.116 + endloop + endfacet + facet normal -0.251236 -0.805653 0.536474 + outer loop + vertex -502.217 86.6077 338.418 + vertex -501.911 84.3245 335.133 + vertex -499.732 85.2651 337.566 + endloop + endfacet + facet normal -0.215051 -0.778843 0.5892 + outer loop + vertex -502.589 88.623 340.946 + vertex -502.217 86.6077 338.418 + vertex -500.234 88.1451 341.174 + endloop + endfacet + facet normal -0.212101 -0.742037 0.63592 + outer loop + vertex -501.948 90.1796 342.976 + vertex -502.589 88.623 340.946 + vertex -500.234 88.1451 341.174 + endloop + endfacet + facet normal -0.196294 -0.695506 0.691187 + outer loop + vertex -502.616 92.5775 345.2 + vertex -501.948 90.1796 342.976 + vertex -500.243 91.309 344.597 + endloop + endfacet + facet normal -0.143789 -0.660314 0.737096 + outer loop + vertex -503.322 95.0905 347.313 + vertex -502.616 92.5775 345.2 + vertex -500.473 95.1416 347.915 + endloop + endfacet + facet normal -0.154336 -0.603567 0.782232 + outer loop + vertex -502.942 98.0463 349.669 + vertex -503.322 95.0905 347.313 + vertex -500.473 95.1416 347.915 + endloop + endfacet + facet normal -0.156645 -0.55194 0.819039 + outer loop + vertex -502.386 102.293 352.637 + vertex -502.942 98.0463 349.669 + vertex -500.194 99.4862 351.165 + endloop + endfacet + facet normal -0.145144 -0.512777 0.846164 + outer loop + vertex -501.339 104.481 354.143 + vertex -502.386 102.293 352.637 + vertex -500.567 102.824 353.271 + endloop + endfacet + facet normal -0.132265 -0.539468 0.831553 + outer loop + vertex -500.194 99.4862 351.165 + vertex -500.567 102.824 353.271 + vertex -502.386 102.293 352.637 + endloop + endfacet + facet normal -0.169722 -0.504396 0.846628 + outer loop + vertex -408.287 81.0381 356.609 + vertex -408.033 75.4377 353.324 + vertex -404.744 78.9861 356.097 + endloop + endfacet + facet normal -0.167811 -0.575034 0.800734 + outer loop + vertex -490.142 93.3658 348.861 + vertex -488.489 96.1217 351.186 + vertex -495.66 96.8442 350.202 + endloop + endfacet + facet normal -0.125871 -0.589044 0.798237 + outer loop + vertex -500.473 95.1416 347.915 + vertex -500.194 99.4862 351.165 + vertex -502.942 98.0463 349.669 + endloop + endfacet + facet normal -0.187671 -0.598185 0.779073 + outer loop + vertex -495.66 96.8442 350.202 + vertex -496.787 92.6893 346.741 + vertex -490.142 93.3658 348.861 + endloop + endfacet + facet normal -0.184053 -0.552139 0.813183 + outer loop + vertex -408.033 75.4377 353.324 + vertex -408.363 70.9996 350.236 + vertex -405.098 72.6409 352.089 + endloop + endfacet + facet normal -0.178675 -0.62541 0.759564 + outer loop + vertex -490.759 89.8375 345.811 + vertex -490.142 93.3658 348.861 + vertex -496.787 92.6893 346.741 + endloop + endfacet + facet normal -0.159989 -0.651516 0.741573 + outer loop + vertex -500.243 91.309 344.597 + vertex -500.473 95.1416 347.915 + vertex -502.616 92.5775 345.2 + endloop + endfacet + facet normal -0.206324 -0.669005 0.714046 + outer loop + vertex -496.787 92.6893 346.741 + vertex -496.924 89.1531 343.388 + vertex -490.759 89.8375 345.811 + endloop + endfacet + facet normal -0.174143 -0.61241 0.771122 + outer loop + vertex -408.363 70.9996 350.236 + vertex -407.381 67.2353 347.468 + vertex -404.532 69.498 349.908 + endloop + endfacet + facet normal -0.197421 -0.689248 0.697109 + outer loop + vertex -490.719 86.522 342.544 + vertex -490.759 89.8375 345.811 + vertex -496.924 89.1531 343.388 + endloop + endfacet + facet normal -0.156458 -0.725515 0.670186 + outer loop + vertex -500.234 88.1451 341.174 + vertex -500.243 91.309 344.597 + vertex -501.948 90.1796 342.976 + endloop + endfacet + facet normal -0.225331 -0.736173 0.638181 + outer loop + vertex -496.924 89.1531 343.388 + vertex -496.741 86.0982 339.928 + vertex -490.719 86.522 342.544 + endloop + endfacet + facet normal -0.190777 -0.659271 0.7273 + outer loop + vertex -407.381 67.2353 347.468 + vertex -407.216 63.9873 344.567 + vertex -403.527 64.6279 346.115 + endloop + endfacet + facet normal -0.214982 -0.756505 0.617643 + outer loop + vertex -490.482 83.5769 339.019 + vertex -490.719 86.522 342.544 + vertex -496.741 86.0982 339.928 + endloop + endfacet + facet normal -0.21755 -0.777398 0.590191 + outer loop + vertex -499.732 85.2651 337.566 + vertex -500.234 88.1451 341.174 + vertex -502.217 86.6077 338.418 + endloop + endfacet + facet normal -0.237292 -0.792005 0.562513 + outer loop + vertex -496.741 86.0982 339.928 + vertex -496.583 83.5022 336.34 + vertex -490.482 83.5769 339.019 + endloop + endfacet + facet normal -0.206384 -0.707752 0.675642 + outer loop + vertex -407.216 63.9873 344.567 + vertex -406.461 61.4185 342.107 + vertex -403.158 62.0929 343.822 + endloop + endfacet + facet normal -0.224795 -0.814605 0.534683 + outer loop + vertex -490.613 80.8 334.733 + vertex -490.482 83.5769 339.019 + vertex -496.583 83.5022 336.34 + endloop + endfacet + facet normal -0.232153 -0.819098 0.52458 + outer loop + vertex -499.474 82.9827 334.116 + vertex -499.732 85.2651 337.566 + vertex -501.911 84.3245 335.133 + endloop + endfacet + facet normal -0.242039 -0.831796 0.499532 + outer loop + vertex -496.583 83.5022 336.34 + vertex -496.92 81.6811 333.145 + vertex -490.613 80.8 334.733 + endloop + endfacet + facet normal -0.213935 -0.754964 0.619888 + outer loop + vertex -406.461 61.4185 342.107 + vertex -405.39 59.2211 339.8 + vertex -402.374 59.9141 341.685 + endloop + endfacet + facet normal -0.252452 -0.852122 0.458429 + outer loop + vertex -487.653 77.8921 330.958 + vertex -490.613 80.8 334.733 + vertex -494.79 79.6484 330.293 + endloop + endfacet + facet normal -0.239007 -0.855683 0.459 + outer loop + vertex -498.697 80.9281 330.69 + vertex -499.474 82.9827 334.116 + vertex -501.404 82.1993 331.651 + endloop + endfacet + facet normal -0.232603 -0.86568 0.443277 + outer loop + vertex -496.92 81.6811 333.145 + vertex -494.79 79.6484 330.293 + vertex -490.613 80.8 334.733 + endloop + endfacet + facet normal -0.222386 -0.803293 0.552508 + outer loop + vertex -405.39 59.2211 339.8 + vertex -404.166 57.3303 337.544 + vertex -401.385 57.8994 339.49 + endloop + endfacet + facet normal -0.272435 -0.878528 0.392387 + outer loop + vertex -484.771 75.768 328.204 + vertex -487.653 77.8921 330.958 + vertex -492.165 77.1324 326.124 + endloop + endfacet + facet normal -0.234205 -0.888112 0.395481 + outer loop + vertex -497.134 78.859 326.97 + vertex -498.697 80.9281 330.69 + vertex -500.24 80.1705 328.076 + endloop + endfacet + facet normal -0.254328 -0.890459 0.377359 + outer loop + vertex -494.79 79.6484 330.293 + vertex -492.165 77.1324 326.124 + vertex -487.653 77.8921 330.958 + endloop + endfacet + facet normal -0.228031 -0.850458 0.47405 + outer loop + vertex -404.166 57.3303 337.544 + vertex -402.763 55.7266 335.341 + vertex -400.206 56.134 337.302 + endloop + endfacet + facet normal -0.260712 -0.906382 0.332416 + outer loop + vertex -485.519 74.4765 324.096 + vertex -484.771 75.768 328.204 + vertex -492.165 77.1324 326.124 + endloop + endfacet + facet normal -0.227365 -0.915969 0.330614 + outer loop + vertex -495.82 77.0016 322.727 + vertex -497.134 78.859 326.97 + vertex -498.627 78.2894 324.365 + endloop + endfacet + facet normal -0.270899 -0.912377 0.30689 + outer loop + vertex -492.165 77.1324 326.124 + vertex -492.821 75.6907 321.26 + vertex -485.519 74.4765 324.096 + endloop + endfacet + facet normal -0.240713 -0.953199 0.182946 + outer loop + vertex -492.618 74.2096 314.333 + vertex -494.615 75.4824 318.337 + vertex -495.48 75.2273 315.869 + endloop + endfacet + facet normal -0.238834 -0.963574 0.120344 + outer loop + vertex -490.416 73.2366 310.911 + vertex -492.618 74.2096 314.333 + vertex -493.636 74.1878 312.138 + endloop + endfacet + facet normal -0.222255 -0.965428 0.136204 + outer loop + vertex -397.561 52.1931 328.836 + vertex -401.973 53.1449 328.382 + vertex -399.859 52.6165 328.087 + endloop + endfacet + facet normal -0.160132 -0.546801 0.821807 + outer loop + vertex -515.219 106.451 352.964 + vertex -516.393 102.972 350.42 + vertex -506.391 103.361 352.628 + endloop + endfacet + facet normal -0.159437 -0.550682 0.819347 + outer loop + vertex -506.391 103.361 352.628 + vertex -516.393 102.972 350.42 + vertex -507.441 100.235 350.323 + endloop + endfacet + facet normal -0.157135 -0.55941 0.813861 + outer loop + vertex -531.497 110.856 352.848 + vertex -530.702 107.002 350.353 + vertex -515.219 106.451 352.964 + endloop + endfacet + facet normal -0.158043 -0.547474 0.821763 + outer loop + vertex -515.219 106.451 352.964 + vertex -530.702 107.002 350.353 + vertex -516.393 102.972 350.42 + endloop + endfacet + facet normal -0.15898 -0.564079 0.810272 + outer loop + vertex -549.666 115.847 352.758 + vertex -548.361 111.962 350.31 + vertex -531.497 110.856 352.848 + endloop + endfacet + facet normal -0.15915 -0.559522 0.813392 + outer loop + vertex -531.497 110.856 352.848 + vertex -548.361 111.962 350.31 + vertex -530.702 107.002 350.353 + endloop + endfacet + facet normal -0.160017 -0.559058 0.813541 + outer loop + vertex -567.968 121.272 352.886 + vertex -566.07 117.275 350.513 + vertex -549.666 115.847 352.758 + endloop + endfacet + facet normal -0.159979 -0.564226 0.809972 + outer loop + vertex -549.666 115.847 352.758 + vertex -566.07 117.275 350.513 + vertex -548.361 111.962 350.31 + endloop + endfacet + facet normal -0.159574 -0.545215 0.822968 + outer loop + vertex -582.375 125.995 353.221 + vertex -581.045 122.286 351.023 + vertex -567.968 121.272 352.886 + endloop + endfacet + facet normal -0.159327 -0.558883 0.813797 + outer loop + vertex -567.968 121.272 352.886 + vertex -581.045 122.286 351.023 + vertex -566.07 117.275 350.513 + endloop + endfacet + facet normal -0.162276 -0.566017 0.808264 + outer loop + vertex -597.038 127.851 351.611 + vertex -597.173 125.187 349.718 + vertex -591.689 126.668 351.856 + endloop + endfacet + facet normal -0.162849 -0.564878 0.808946 + outer loop + vertex -591.689 126.668 351.856 + vertex -597.173 125.187 349.718 + vertex -591.398 122.754 349.182 + endloop + endfacet + facet normal -0.172797 -0.593213 0.786282 + outer loop + vertex -516.393 102.972 350.42 + vertex -516.585 99.6542 347.875 + vertex -507.441 100.235 350.323 + endloop + endfacet + facet normal -0.173113 -0.591951 0.787163 + outer loop + vertex -507.441 100.235 350.323 + vertex -516.585 99.6542 347.875 + vertex -507.506 96.8752 347.782 + endloop + endfacet + facet normal -0.171678 -0.596494 0.784042 + outer loop + vertex -530.702 107.002 350.353 + vertex -530.729 103.574 347.739 + vertex -516.393 102.972 350.42 + endloop + endfacet + facet normal -0.171981 -0.59333 0.786373 + outer loop + vertex -516.393 102.972 350.42 + vertex -530.729 103.574 347.739 + vertex -516.585 99.6542 347.875 + endloop + endfacet + facet normal -0.170314 -0.599542 0.782012 + outer loop + vertex -548.361 111.962 350.31 + vertex -548.254 108.484 347.667 + vertex -530.702 107.002 350.353 + endloop + endfacet + facet normal -0.170405 -0.596635 0.784212 + outer loop + vertex -530.702 107.002 350.353 + vertex -548.254 108.484 347.667 + vertex -530.729 103.574 347.739 + endloop + endfacet + facet normal -0.170103 -0.596978 0.784017 + outer loop + vertex -566.07 117.275 350.513 + vertex -566.094 113.821 347.877 + vertex -548.361 111.962 350.31 + endloop + endfacet + facet normal -0.170103 -0.59956 0.782044 + outer loop + vertex -548.361 111.962 350.31 + vertex -566.094 113.821 347.877 + vertex -548.254 108.484 347.667 + endloop + endfacet + facet normal -0.169347 -0.586606 0.791969 + outer loop + vertex -581.045 122.286 351.023 + vertex -581.097 118.798 348.427 + vertex -566.07 117.275 350.513 + endloop + endfacet + facet normal -0.169317 -0.597063 0.784122 + outer loop + vertex -566.07 117.275 350.513 + vertex -581.097 118.798 348.427 + vertex -566.094 113.821 347.877 + endloop + endfacet + facet normal -0.180976 -0.601169 0.77836 + outer loop + vertex -597.173 125.187 349.718 + vertex -597.122 122.241 347.455 + vertex -591.398 122.754 349.182 + endloop + endfacet + facet normal -0.175508 -0.61899 0.765538 + outer loop + vertex -591.398 122.754 349.182 + vertex -597.122 122.241 347.455 + vertex -592.137 119.643 346.497 + endloop + endfacet + facet normal -0.192269 -0.652719 0.732796 + outer loop + vertex -516.585 99.6542 347.875 + vertex -516.499 96.6189 345.194 + vertex -507.506 96.8752 347.782 + endloop + endfacet + facet normal -0.191563 -0.655379 0.730604 + outer loop + vertex -507.506 96.8752 347.782 + vertex -516.499 96.6189 345.194 + vertex -507.226 93.9314 345.214 + endloop + endfacet + facet normal -0.187813 -0.652253 0.734365 + outer loop + vertex -530.729 103.574 347.739 + vertex -530.713 100.491 345.004 + vertex -516.585 99.6542 347.875 + endloop + endfacet + facet normal -0.1877 -0.653231 0.733524 + outer loop + vertex -516.585 99.6542 347.875 + vertex -530.713 100.491 345.004 + vertex -516.499 96.6189 345.194 + endloop + endfacet + facet normal -0.185577 -0.651503 0.735598 + outer loop + vertex -548.254 108.484 347.667 + vertex -548.464 105.395 344.877 + vertex -530.729 103.574 347.739 + endloop + endfacet + facet normal -0.185537 -0.652533 0.734695 + outer loop + vertex -530.729 103.574 347.739 + vertex -548.464 105.395 344.877 + vertex -530.713 100.491 345.004 + endloop + endfacet + facet normal -0.184335 -0.645523 0.741161 + outer loop + vertex -566.094 113.821 347.877 + vertex -566.54 110.719 345.066 + vertex -548.254 108.484 347.667 + endloop + endfacet + facet normal -0.184318 -0.65171 0.735732 + outer loop + vertex -548.254 108.484 347.667 + vertex -566.54 110.719 345.066 + vertex -548.464 105.395 344.877 + endloop + endfacet + facet normal -0.18294 -0.634472 0.750985 + outer loop + vertex -581.097 118.798 348.427 + vertex -581.733 115.675 345.635 + vertex -566.094 113.821 347.877 + endloop + endfacet + facet normal -0.182892 -0.64582 0.74126 + outer loop + vertex -566.094 113.821 347.877 + vertex -581.733 115.675 345.635 + vertex -566.54 110.719 345.066 + endloop + endfacet + facet normal -0.198971 -0.651651 0.731957 + outer loop + vertex -597.122 122.241 347.455 + vertex -598.207 119.645 344.849 + vertex -592.137 119.643 346.497 + endloop + endfacet + facet normal -0.19473 -0.670046 0.716323 + outer loop + vertex -592.137 119.643 346.497 + vertex -598.207 119.645 344.849 + vertex -592.828 116.741 343.594 + endloop + endfacet + facet normal -0.207301 -0.710124 0.672867 + outer loop + vertex -516.499 96.6189 345.194 + vertex -516.209 93.8036 342.312 + vertex -507.226 93.9314 345.214 + endloop + endfacet + facet normal -0.206741 -0.711854 0.67121 + outer loop + vertex -507.226 93.9314 345.214 + vertex -516.209 93.8036 342.312 + vertex -506.314 90.9198 342.301 + endloop + endfacet + facet normal -0.202652 -0.71107 0.673284 + outer loop + vertex -530.713 100.491 345.004 + vertex -530.731 97.7266 342.08 + vertex -516.499 96.6189 345.194 + endloop + endfacet + facet normal -0.202722 -0.710584 0.673776 + outer loop + vertex -516.499 96.6189 345.194 + vertex -530.731 97.7266 342.08 + vertex -516.209 93.8036 342.312 + endloop + endfacet + facet normal -0.200741 -0.709088 0.675942 + outer loop + vertex -548.464 105.395 344.877 + vertex -548.716 102.634 341.907 + vertex -530.713 100.491 345.004 + endloop + endfacet + facet normal -0.200605 -0.711383 0.673567 + outer loop + vertex -530.713 100.491 345.004 + vertex -548.716 102.634 341.907 + vertex -530.731 97.7266 342.08 + endloop + endfacet + facet normal -0.199225 -0.700525 0.685255 + outer loop + vertex -566.54 110.719 345.066 + vertex -567.086 107.945 342.071 + vertex -548.464 105.395 344.877 + endloop + endfacet + facet normal -0.199062 -0.709411 0.676099 + outer loop + vertex -548.464 105.395 344.877 + vertex -567.086 107.945 342.071 + vertex -548.716 102.634 341.907 + endloop + endfacet + facet normal -0.197802 -0.686734 0.699478 + outer loop + vertex -581.733 115.675 345.635 + vertex -582.394 112.844 342.668 + vertex -566.54 110.719 345.066 + endloop + endfacet + facet normal -0.197564 -0.700927 0.685324 + outer loop + vertex -566.54 110.719 345.066 + vertex -582.394 112.844 342.668 + vertex -567.086 107.945 342.071 + endloop + endfacet + facet normal -0.211485 -0.690467 0.691758 + outer loop + vertex -598.207 119.645 344.849 + vertex -598.731 116.68 341.729 + vertex -592.828 116.741 343.594 + endloop + endfacet + facet normal -0.203083 -0.717707 0.666074 + outer loop + vertex -592.828 116.741 343.594 + vertex -598.731 116.68 341.729 + vertex -593.417 114.061 340.528 + endloop + endfacet + facet normal -0.219749 -0.756281 0.616238 + outer loop + vertex -516.209 93.8036 342.312 + vertex -516.124 91.2169 339.167 + vertex -506.314 90.9198 342.301 + endloop + endfacet + facet normal -0.218907 -0.758861 0.613359 + outer loop + vertex -506.314 90.9198 342.301 + vertex -516.124 91.2169 339.167 + vertex -506.827 88.3612 338.953 + endloop + endfacet + facet normal -0.21459 -0.757933 0.616026 + outer loop + vertex -530.731 97.7266 342.08 + vertex -530.759 95.1893 338.948 + vertex -516.209 93.8036 342.312 + endloop + endfacet + facet normal -0.21474 -0.757076 0.617027 + outer loop + vertex -516.209 93.8036 342.312 + vertex -530.759 95.1893 338.948 + vertex -516.124 91.2169 339.167 + endloop + endfacet + facet normal -0.212505 -0.756955 0.617949 + outer loop + vertex -548.716 102.634 341.907 + vertex -548.895 100.102 338.744 + vertex -530.731 97.7266 342.08 + endloop + endfacet + facet normal -0.212384 -0.758317 0.616318 + outer loop + vertex -530.731 97.7266 342.08 + vertex -548.895 100.102 338.744 + vertex -530.759 95.1893 338.948 + endloop + endfacet + facet normal -0.211746 -0.751698 0.62459 + outer loop + vertex -567.086 107.945 342.071 + vertex -567.665 105.413 338.827 + vertex -548.716 102.634 341.907 + endloop + endfacet + facet normal -0.211484 -0.757157 0.618052 + outer loop + vertex -548.716 102.634 341.907 + vertex -567.665 105.413 338.827 + vertex -548.895 100.102 338.744 + endloop + endfacet + facet normal -0.21086 -0.737183 0.64195 + outer loop + vertex -582.394 112.844 342.668 + vertex -583.232 110.296 339.467 + vertex -567.086 107.945 342.071 + endloop + endfacet + facet normal -0.210237 -0.752091 0.624628 + outer loop + vertex -567.086 107.945 342.071 + vertex -583.232 110.296 339.467 + vertex -567.665 105.413 338.827 + endloop + endfacet + facet normal -0.216919 -0.734966 0.642472 + outer loop + vertex -598.731 116.68 341.729 + vertex -599.182 114.177 338.714 + vertex -593.417 114.061 340.528 + endloop + endfacet + facet normal -0.208806 -0.760322 0.61507 + outer loop + vertex -593.417 114.061 340.528 + vertex -599.182 114.177 338.714 + vertex -594.406 111.775 337.366 + endloop + endfacet + facet normal -0.255864 -0.907558 0.332975 + outer loop + vertex -603.341 105.575 322.331 + vertex -604.337 104.504 318.647 + vertex -601.146 104.242 320.385 + endloop + endfacet + facet normal -0.248062 -0.928407 0.276634 + outer loop + vertex -604.337 104.504 318.647 + vertex -605.554 103.889 315.493 + vertex -602.057 103.362 316.858 + endloop + endfacet + facet normal -0.260424 -0.93578 0.237686 + outer loop + vertex -606.754 103.648 313.227 + vertex -605.358 103.511 314.217 + vertex -605.554 103.889 315.493 + endloop + endfacet + facet normal -0.245935 -0.960778 0.128149 + outer loop + vertex -509.815 77.7385 306.749 + vertex -527.638 82.3066 306.792 + vertex -520.504 80.4018 306.202 + endloop + endfacet + facet normal -0.0546106 -0.548155 0.834592 + outer loop + vertex -502.386 102.293 352.637 + vertex -501.339 104.481 354.143 + vertex -501.567 104.351 354.042 + endloop + endfacet + facet normal -0.150037 -0.553115 0.819483 + outer loop + vertex -502.942 98.0463 349.669 + vertex -502.386 102.293 352.637 + vertex -507.441 100.235 350.323 + endloop + endfacet + facet normal -0.168875 -0.600922 0.781264 + outer loop + vertex -503.322 95.0905 347.313 + vertex -502.942 98.0463 349.669 + vertex -507.506 96.8752 347.782 + endloop + endfacet + facet normal -0.192352 -0.662725 0.723738 + outer loop + vertex -502.616 92.5775 345.2 + vertex -503.322 95.0905 347.313 + vertex -507.226 93.9314 345.214 + endloop + endfacet + facet normal -0.223545 -0.695439 0.682929 + outer loop + vertex -501.948 90.1796 342.976 + vertex -502.616 92.5775 345.2 + vertex -506.314 90.9198 342.301 + endloop + endfacet + facet normal -0.223606 -0.738114 0.636544 + outer loop + vertex -502.589 88.623 340.946 + vertex -501.948 90.1796 342.976 + vertex -506.314 90.9198 342.301 + endloop + endfacet + facet normal -0.227782 -0.777466 0.586227 + outer loop + vertex -502.217 86.6077 338.418 + vertex -502.589 88.623 340.946 + vertex -506.827 88.3612 338.953 + endloop + endfacet + facet normal -0.231272 -0.808881 0.540578 + outer loop + vertex -501.911 84.3245 335.133 + vertex -502.217 86.6077 338.418 + vertex -506.647 86.0943 335.755 + endloop + endfacet + facet normal -0.238808 -0.843954 0.480325 + outer loop + vertex -501.404 82.1993 331.651 + vertex -501.911 84.3245 335.133 + vertex -506.325 83.9753 332.325 + endloop + endfacet + facet normal -0.244514 -0.875348 0.417108 + outer loop + vertex -500.24 80.1705 328.076 + vertex -501.404 82.1993 331.651 + vertex -505.362 81.9309 328.767 + endloop + endfacet + facet normal -0.239155 -0.90402 0.354333 + outer loop + vertex -498.627 78.2894 324.365 + vertex -500.24 80.1705 328.076 + vertex -503.122 79.9066 325.457 + endloop + endfacet + facet normal -0.261467 -0.918296 0.297268 + outer loop + vertex -606.003 105.547 320.405 + vertex -606.561 104.377 316.299 + vertex -604.337 104.504 318.647 + endloop + endfacet + facet normal -0.25452 -0.895733 0.364529 + outer loop + vertex -605.262 106.965 324.406 + vertex -606.003 105.547 320.405 + vertex -603.341 105.575 322.331 + endloop + endfacet + facet normal -0.238831 -0.87737 0.416151 + outer loop + vertex -603.846 108.057 327.521 + vertex -605.262 106.965 324.406 + vertex -602.049 106.793 325.887 + endloop + endfacet + facet normal -0.236044 -0.816677 0.526614 + outer loop + vertex -602.779 111.742 334.084 + vertex -603.442 109.65 330.542 + vertex -600.184 109.981 332.515 + endloop + endfacet + facet normal -0.237588 -0.779876 0.57909 + outer loop + vertex -602.109 114.066 337.488 + vertex -602.779 111.742 334.084 + vertex -599.903 112.042 335.668 + endloop + endfacet + facet normal -0.231144 -0.70309 0.672486 + outer loop + vertex -601.354 118.886 343.134 + vertex -601.305 116.049 340.185 + vertex -598.731 116.68 341.729 + endloop + endfacet + facet normal -0.235436 -0.652045 0.720699 + outer loop + vertex -600.547 122.957 347.081 + vertex -601.354 118.886 343.134 + vertex -598.207 119.645 344.849 + endloop + endfacet + facet normal -0.21885 -0.588986 0.777946 + outer loop + vertex -600.311 127.948 350.926 + vertex -600.547 122.957 347.081 + vertex -597.173 125.187 349.718 + endloop + endfacet + facet normal -0.192856 -0.485514 0.852692 + outer loop + vertex -596.799 131.307 353.633 + vertex -600.311 127.948 350.926 + vertex -597.038 127.851 351.611 + endloop + endfacet + facet normal -0.149576 -0.553812 0.819097 + outer loop + vertex -506.391 103.361 352.628 + vertex -507.441 100.235 350.323 + vertex -502.386 102.293 352.637 + endloop + endfacet + facet normal -0.160022 -0.545294 0.822829 + outer loop + vertex -581.045 122.286 351.023 + vertex -582.375 125.995 353.221 + vertex -591.689 126.668 351.856 + endloop + endfacet + facet normal -0.185286 -0.562887 0.805498 + outer loop + vertex -597.173 125.187 349.718 + vertex -597.038 127.851 351.611 + vertex -600.311 127.948 350.926 + endloop + endfacet + facet normal -0.169142 -0.564597 0.80785 + outer loop + vertex -591.689 126.668 351.856 + vertex -591.398 122.754 349.182 + vertex -581.045 122.286 351.023 + endloop + endfacet + facet normal -0.173605 -0.591893 0.787098 + outer loop + vertex -507.441 100.235 350.323 + vertex -507.506 96.8752 347.782 + vertex -502.942 98.0463 349.669 + endloop + endfacet + facet normal -0.167369 -0.586827 0.792226 + outer loop + vertex -581.097 118.798 348.427 + vertex -581.045 122.286 351.023 + vertex -591.398 122.754 349.182 + endloop + endfacet + facet normal -0.209495 -0.59802 0.773617 + outer loop + vertex -597.122 122.241 347.455 + vertex -597.173 125.187 349.718 + vertex -600.547 122.957 347.081 + endloop + endfacet + facet normal -0.181131 -0.617537 0.765401 + outer loop + vertex -591.398 122.754 349.182 + vertex -592.137 119.643 346.497 + vertex -581.097 118.798 348.427 + endloop + endfacet + facet normal -0.197713 -0.654905 0.72939 + outer loop + vertex -507.506 96.8752 347.782 + vertex -507.226 93.9314 345.214 + vertex -503.322 95.0905 347.313 + endloop + endfacet + facet normal -0.179983 -0.635178 0.751102 + outer loop + vertex -581.733 115.675 345.635 + vertex -581.097 118.798 348.427 + vertex -592.137 119.643 346.497 + endloop + endfacet + facet normal -0.215004 -0.645697 0.7327 + outer loop + vertex -598.207 119.645 344.849 + vertex -597.122 122.241 347.455 + vertex -600.547 122.957 347.081 + endloop + endfacet + facet normal -0.196037 -0.669701 0.716289 + outer loop + vertex -592.137 119.643 346.497 + vertex -592.828 116.741 343.594 + vertex -581.733 115.675 345.635 + endloop + endfacet + facet normal -0.206949 -0.711854 0.671145 + outer loop + vertex -507.226 93.9314 345.214 + vertex -506.314 90.9198 342.301 + vertex -502.616 92.5775 345.2 + endloop + endfacet + facet normal -0.194675 -0.687548 0.699557 + outer loop + vertex -582.394 112.844 342.668 + vertex -581.733 115.675 345.635 + vertex -592.828 116.741 343.594 + endloop + endfacet + facet normal -0.210384 -0.690734 0.691827 + outer loop + vertex -598.731 116.68 341.729 + vertex -598.207 119.645 344.849 + vertex -601.354 118.886 343.134 + endloop + endfacet + facet normal -0.208414 -0.716338 0.6659 + outer loop + vertex -592.828 116.741 343.594 + vertex -593.417 114.061 340.528 + vertex -582.394 112.844 342.668 + endloop + endfacet + facet normal -0.241543 -0.752869 0.612246 + outer loop + vertex -506.314 90.9198 342.301 + vertex -506.827 88.3612 338.953 + vertex -502.589 88.623 340.946 + endloop + endfacet + facet normal -0.206201 -0.738587 0.641849 + outer loop + vertex -583.232 110.296 339.467 + vertex -582.394 112.844 342.668 + vertex -593.417 114.061 340.528 + endloop + endfacet + facet normal -0.204993 -0.737851 0.643081 + outer loop + vertex -599.182 114.177 338.714 + vertex -598.731 116.68 341.729 + vertex -601.305 116.049 340.185 + endloop + endfacet + facet normal -0.216069 -0.757879 0.615576 + outer loop + vertex -593.417 114.061 340.528 + vertex -594.406 111.775 337.366 + vertex -583.232 110.296 339.467 + endloop + endfacet + facet normal -0.219391 -0.773725 0.594321 + outer loop + vertex -599.903 112.042 335.668 + vertex -599.182 114.177 338.714 + vertex -602.109 114.066 337.488 + endloop + endfacet + facet normal -0.217371 -0.807945 0.5477 + outer loop + vertex -600.184 109.981 332.515 + vertex -599.903 112.042 335.668 + vertex -602.779 111.742 334.084 + endloop + endfacet + facet normal -0.216728 -0.839349 0.498521 + outer loop + vertex -600.629 108.141 329.225 + vertex -600.184 109.981 332.515 + vertex -603.442 109.65 330.542 + endloop + endfacet + facet normal -0.211346 -0.871746 0.442032 + outer loop + vertex -602.049 106.793 325.887 + vertex -600.629 108.141 329.225 + vertex -603.846 108.057 327.521 + endloop + endfacet + facet normal -0.226877 -0.893132 0.388383 + outer loop + vertex -603.341 105.575 322.331 + vertex -602.049 106.793 325.887 + vertex -605.262 106.965 324.406 + endloop + endfacet + facet normal -0.227946 -0.916731 0.328093 + outer loop + vertex -604.337 104.504 318.647 + vertex -603.341 105.575 322.331 + vertex -606.003 105.547 320.405 + endloop + endfacet + facet normal -0.234188 -0.933297 0.272237 + outer loop + vertex -605.554 103.889 315.493 + vertex -604.337 104.504 318.647 + vertex -606.561 104.377 316.299 + endloop + endfacet + facet normal 0.608093 0.268091 -0.747228 + outer loop + vertex -502.386 102.293 352.637 + vertex -501.567 104.351 354.042 + vertex -501.666 103.955 353.82 + endloop + endfacet + facet normal -0.0905297 -0.551113 0.829505 + outer loop + vertex -501.666 103.955 353.82 + vertex -502.499 103.453 353.395 + vertex -502.386 102.293 352.637 + endloop + endfacet + facet normal -0.203496 -0.899419 0.386826 + outer loop + vertex -614.991 107.006 318.517 + vertex -610.872 106.11 318.6 + vertex -616.778 109.216 322.716 + endloop + endfacet + facet normal -0.216292 -0.909856 0.35409 + outer loop + vertex -607.71 105.293 318.433 + vertex -609.188 107.317 322.73 + vertex -610.872 106.11 318.6 + endloop + endfacet + facet normal -0.227362 -0.905842 0.35743 + outer loop + vertex -609.188 107.317 322.73 + vertex -616.778 109.216 322.716 + vertex -610.872 106.11 318.6 + endloop + endfacet + facet normal -0.239665 -0.87487 0.420908 + outer loop + vertex -607.317 109.357 328.036 + vertex -614.702 111.103 327.461 + vertex -609.188 107.317 322.73 + endloop + endfacet + facet normal -0.218575 -0.870133 0.441694 + outer loop + vertex -609.188 107.317 322.73 + vertex -614.702 111.103 327.461 + vertex -616.778 109.216 322.716 + endloop + endfacet + facet normal -0.149982 -0.497509 0.854395 + outer loop + vertex -603.26 133.519 353.765 + vertex -609.784 135.427 353.731 + vertex -604.559 130.292 351.658 + endloop + endfacet + facet normal -0.171789 -0.51404 0.840387 + outer loop + vertex -604.559 130.292 351.658 + vertex -609.784 135.427 353.731 + vertex -609.932 131.037 351.015 + endloop + endfacet + facet normal -0.129522 -0.433173 0.891956 + outer loop + vertex -601.845 137.994 356.144 + vertex -609.619 140.161 356.067 + vertex -603.26 133.519 353.765 + endloop + endfacet + facet normal -0.131887 -0.435007 0.890716 + outer loop + vertex -603.26 133.519 353.765 + vertex -609.619 140.161 356.067 + vertex -609.784 135.427 353.731 + endloop + endfacet + facet normal -0.105452 -0.356831 0.928198 + outer loop + vertex -601.089 143.3 358.269 + vertex -609.462 145.307 358.09 + vertex -601.845 137.994 356.144 + endloop + endfacet + facet normal -0.109649 -0.360677 0.926223 + outer loop + vertex -601.845 137.994 356.144 + vertex -609.462 145.307 358.09 + vertex -609.619 140.161 356.067 + endloop + endfacet + facet normal -0.0781121 -0.271578 0.959241 + outer loop + vertex -601.126 149.025 359.887 + vertex -609.359 150.645 359.675 + vertex -601.089 143.3 358.269 + endloop + endfacet + facet normal -0.0881089 -0.282086 0.955335 + outer loop + vertex -601.089 143.3 358.269 + vertex -609.359 150.645 359.675 + vertex -609.462 145.307 358.09 + endloop + endfacet + facet normal -0.0553417 -0.193652 0.979508 + outer loop + vertex -601.357 154.74 361.004 + vertex -609.262 155.987 360.804 + vertex -601.126 149.025 359.887 + endloop + endfacet + facet normal -0.0654871 -0.20512 0.976544 + outer loop + vertex -601.126 149.025 359.887 + vertex -609.262 155.987 360.804 + vertex -609.359 150.645 359.675 + endloop + endfacet + facet normal -0.201029 -0.873969 0.442453 + outer loop + vertex -629.242 111.669 321.593 + vertex -620.994 109.056 320.179 + vertex -626.847 112.562 324.444 + endloop + endfacet + facet normal -0.199685 -0.899546 0.388514 + outer loop + vertex -614.991 107.006 318.517 + vertex -616.778 109.216 322.716 + vertex -620.994 109.056 320.179 + endloop + endfacet + facet normal -0.220082 -0.879878 0.421164 + outer loop + vertex -616.778 109.216 322.716 + vertex -626.847 112.562 324.444 + vertex -620.994 109.056 320.179 + endloop + endfacet + facet normal -0.234484 -0.863718 0.446105 + outer loop + vertex -614.702 111.103 327.461 + vertex -624.367 114.004 327.996 + vertex -616.778 109.216 322.716 + endloop + endfacet + facet normal -0.164741 -0.514846 0.841305 + outer loop + vertex -609.784 135.427 353.731 + vertex -618.583 137.961 353.558 + vertex -609.932 131.037 351.015 + endloop + endfacet + facet normal -0.169621 -0.519527 0.837448 + outer loop + vertex -609.932 131.037 351.015 + vertex -618.583 137.961 353.558 + vertex -618.8 133.386 350.676 + endloop + endfacet + facet normal -0.136669 -0.434586 0.8902 + outer loop + vertex -609.619 140.161 356.067 + vertex -618.546 142.834 356.001 + vertex -609.784 135.427 353.731 + endloop + endfacet + facet normal -0.144794 -0.442591 0.884957 + outer loop + vertex -609.784 135.427 353.731 + vertex -618.546 142.834 356.001 + vertex -618.583 137.961 353.558 + endloop + endfacet + facet normal -0.113687 -0.360404 0.925843 + outer loop + vertex -609.462 145.307 358.09 + vertex -618.644 147.982 358.003 + vertex -609.619 140.161 356.067 + endloop + endfacet + facet normal -0.115178 -0.361931 0.925062 + outer loop + vertex -609.619 140.161 356.067 + vertex -618.644 147.982 358.003 + vertex -618.546 142.834 356.001 + endloop + endfacet + facet normal -0.0892682 -0.282036 0.955242 + outer loop + vertex -609.359 150.645 359.675 + vertex -618.659 153.216 359.565 + vertex -609.462 145.307 358.09 + endloop + endfacet + facet normal -0.0919891 -0.284988 0.954107 + outer loop + vertex -609.462 145.307 358.09 + vertex -618.659 153.216 359.565 + vertex -618.644 147.982 358.003 + endloop + endfacet + facet normal -0.0658238 -0.20511 0.976523 + outer loop + vertex -609.262 155.987 360.804 + vertex -618.555 158.44 360.693 + vertex -609.359 150.645 359.675 + endloop + endfacet + facet normal -0.0693457 -0.209121 0.975428 + outer loop + vertex -609.359 150.645 359.675 + vertex -618.555 158.44 360.693 + vertex -618.659 153.216 359.565 + endloop + endfacet + facet normal -0.225772 -0.859435 0.458693 + outer loop + vertex -626.847 112.562 324.444 + vertex -636.815 115.781 325.569 + vertex -629.242 111.669 321.593 + endloop + endfacet + facet normal -0.167593 -0.519782 0.837699 + outer loop + vertex -618.583 137.961 353.558 + vertex -629.39 141.426 353.546 + vertex -618.8 133.386 350.676 + endloop + endfacet + facet normal -0.166223 -0.518384 0.838837 + outer loop + vertex -618.8 133.386 350.676 + vertex -629.39 141.426 353.546 + vertex -629.79 136.924 350.685 + endloop + endfacet + facet normal -0.144155 -0.442637 0.885038 + outer loop + vertex -618.546 142.834 356.001 + vertex -629.172 146.265 355.987 + vertex -618.583 137.961 353.558 + endloop + endfacet + facet normal -0.14226 -0.440606 0.886357 + outer loop + vertex -618.583 137.961 353.558 + vertex -629.172 146.265 355.987 + vertex -629.39 141.426 353.546 + endloop + endfacet + facet normal -0.117613 -0.361868 0.92478 + outer loop + vertex -618.644 147.982 358.003 + vertex -629.099 151.342 357.988 + vertex -618.546 142.834 356.001 + endloop + endfacet + facet normal -0.118417 -0.36276 0.924328 + outer loop + vertex -618.546 142.834 356.001 + vertex -629.099 151.342 357.988 + vertex -629.172 146.265 355.987 + endloop + endfacet + facet normal -0.0939614 -0.284941 0.953929 + outer loop + vertex -618.659 153.216 359.565 + vertex -629.077 156.54 359.532 + vertex -618.644 147.982 358.003 + endloop + endfacet + facet normal -0.0923332 -0.283083 0.954641 + outer loop + vertex -618.644 147.982 358.003 + vertex -629.077 156.54 359.532 + vertex -629.099 151.342 357.988 + endloop + endfacet + facet normal -0.0690558 -0.209131 0.975446 + outer loop + vertex -618.555 158.44 360.693 + vertex -628.988 161.738 360.661 + vertex -618.659 153.216 359.565 + endloop + endfacet + facet normal -0.0703039 -0.210592 0.975043 + outer loop + vertex -618.659 153.216 359.565 + vertex -628.988 161.738 360.661 + vertex -629.077 156.54 359.532 + endloop + endfacet + facet normal -0.170418 -0.517732 0.838398 + outer loop + vertex -629.39 141.426 353.546 + vertex -640.868 145.348 353.635 + vertex -629.79 136.924 350.685 + endloop + endfacet + facet normal -0.167008 -0.514239 0.841229 + outer loop + vertex -629.79 136.924 350.685 + vertex -640.868 145.348 353.635 + vertex -641.304 140.885 350.82 + endloop + endfacet + facet normal -0.145328 -0.440294 0.886014 + outer loop + vertex -629.172 146.265 355.987 + vertex -640.512 150.114 356.039 + vertex -629.39 141.426 353.546 + endloop + endfacet + facet normal -0.142547 -0.437291 0.887951 + outer loop + vertex -629.39 141.426 353.546 + vertex -640.512 150.114 356.039 + vertex -640.868 145.348 353.635 + endloop + endfacet + facet normal -0.120397 -0.362648 0.924116 + outer loop + vertex -629.099 151.342 357.988 + vertex -640.266 155.119 358.016 + vertex -629.172 146.265 355.987 + endloop + endfacet + facet normal -0.117794 -0.359725 0.925593 + outer loop + vertex -629.172 146.265 355.987 + vertex -640.266 155.119 358.016 + vertex -640.512 150.114 356.039 + endloop + endfacet + facet normal -0.0947104 -0.28301 0.954429 + outer loop + vertex -629.077 156.54 359.532 + vertex -640.105 160.272 359.544 + vertex -629.099 151.342 357.988 + endloop + endfacet + facet normal -0.0925286 -0.280488 0.955387 + outer loop + vertex -629.099 151.342 357.988 + vertex -640.105 160.272 359.544 + vertex -640.266 155.119 358.016 + endloop + endfacet + facet normal -0.0710321 -0.210569 0.974995 + outer loop + vertex -628.988 161.738 360.661 + vertex -639.977 165.471 360.667 + vertex -629.077 156.54 359.532 + endloop + endfacet + facet normal -0.0696027 -0.208883 0.975461 + outer loop + vertex -629.077 156.54 359.532 + vertex -639.977 165.471 360.667 + vertex -640.105 160.272 359.544 + endloop + endfacet + facet normal -0.175082 -0.512921 0.840392 + outer loop + vertex -640.868 145.348 353.635 + vertex -652.009 149.254 353.698 + vertex -641.304 140.885 350.82 + endloop + endfacet + facet normal -0.173111 -0.510953 0.841998 + outer loop + vertex -641.304 140.885 350.82 + vertex -652.009 149.254 353.698 + vertex -652.415 144.782 350.901 + endloop + endfacet + facet normal -0.149292 -0.43644 0.887261 + outer loop + vertex -640.512 150.114 356.039 + vertex -651.643 154.005 356.08 + vertex -640.868 145.348 353.635 + endloop + endfacet + facet normal -0.147241 -0.434282 0.888661 + outer loop + vertex -640.868 145.348 353.635 + vertex -651.643 154.005 356.08 + vertex -652.009 149.254 353.698 + endloop + endfacet + facet normal -0.12318 -0.359256 0.925074 + outer loop + vertex -640.266 155.119 358.016 + vertex -651.347 158.98 358.04 + vertex -640.512 150.114 356.039 + endloop + endfacet + facet normal -0.121541 -0.357459 0.925986 + outer loop + vertex -640.512 150.114 356.039 + vertex -651.347 158.98 358.04 + vertex -651.643 154.005 356.08 + endloop + endfacet + facet normal -0.0962861 -0.280279 0.955077 + outer loop + vertex -640.105 160.272 359.544 + vertex -651.111 164.106 359.56 + vertex -640.266 155.119 358.016 + endloop + endfacet + facet normal -0.0951467 -0.278989 0.955569 + outer loop + vertex -640.266 155.119 358.016 + vertex -651.111 164.106 359.56 + vertex -651.347 158.98 358.04 + endloop + endfacet + facet normal -0.0718407 -0.208797 0.975317 + outer loop + vertex -639.977 165.471 360.667 + vertex -650.937 169.303 360.68 + vertex -640.105 160.272 359.544 + endloop + endfacet + facet normal -0.0710326 -0.20786 0.975576 + outer loop + vertex -640.105 160.272 359.544 + vertex -650.937 169.303 360.68 + vertex -651.111 164.106 359.56 + endloop + endfacet + facet normal -0.183032 -0.509347 0.840872 + outer loop + vertex -652.009 149.254 353.698 + vertex -662.662 153.062 353.686 + vertex -652.415 144.782 350.901 + endloop + endfacet + facet normal -0.18177 -0.508125 0.841884 + outer loop + vertex -652.415 144.782 350.901 + vertex -662.662 153.062 353.686 + vertex -663.053 148.572 350.892 + endloop + endfacet + facet normal -0.154436 -0.433346 0.887897 + outer loop + vertex -651.643 154.005 356.08 + vertex -662.33 157.82 356.083 + vertex -652.009 149.254 353.698 + endloop + endfacet + facet normal -0.15676 -0.435709 0.886332 + outer loop + vertex -652.009 149.254 353.698 + vertex -662.33 157.82 356.083 + vertex -662.662 153.062 353.686 + endloop + endfacet + facet normal -0.128002 -0.356827 0.925359 + outer loop + vertex -651.347 158.98 358.04 + vertex -662.046 162.803 358.034 + vertex -651.643 154.005 356.08 + endloop + endfacet + facet normal -0.126569 -0.355306 0.926141 + outer loop + vertex -651.643 154.005 356.08 + vertex -662.046 162.803 358.034 + vertex -662.33 157.82 356.083 + endloop + endfacet + facet normal -0.0994352 -0.278688 0.95522 + outer loop + vertex -651.111 164.106 359.56 + vertex -661.817 167.927 359.56 + vertex -651.347 158.98 358.04 + endloop + endfacet + facet normal -0.100534 -0.279894 0.954753 + outer loop + vertex -651.347 158.98 358.04 + vertex -661.817 167.927 359.56 + vertex -662.046 162.803 358.034 + endloop + endfacet + facet normal -0.0740691 -0.207717 0.975381 + outer loop + vertex -650.937 169.303 360.68 + vertex -661.639 173.13 360.682 + vertex -651.111 164.106 359.56 + endloop + endfacet + facet normal -0.0741245 -0.207779 0.975363 + outer loop + vertex -651.111 164.106 359.56 + vertex -661.639 173.13 360.682 + vertex -661.817 167.927 359.56 + endloop + endfacet + facet normal -0.188996 -0.506947 0.841003 + outer loop + vertex -662.662 153.062 353.686 + vertex -673.121 156.905 353.652 + vertex -663.053 148.572 350.892 + endloop + endfacet + facet normal -0.190124 -0.508013 0.840105 + outer loop + vertex -663.053 148.572 350.892 + vertex -673.121 156.905 353.652 + vertex -673.514 152.418 350.85 + endloop + endfacet + facet normal -0.162936 -0.434914 0.885608 + outer loop + vertex -662.33 157.82 356.083 + vertex -672.793 161.675 356.052 + vertex -662.662 153.062 353.686 + endloop + endfacet + facet normal -0.162511 -0.434492 0.885893 + outer loop + vertex -662.662 153.062 353.686 + vertex -672.793 161.675 356.052 + vertex -673.121 156.905 353.652 + endloop + endfacet + facet normal -0.132044 -0.354775 0.925581 + outer loop + vertex -662.046 162.803 358.034 + vertex -672.528 166.662 358.018 + vertex -662.33 157.82 356.083 + endloop + endfacet + facet normal -0.134439 -0.357253 0.924282 + outer loop + vertex -662.33 157.82 356.083 + vertex -672.528 166.662 358.018 + vertex -672.793 161.675 356.052 + endloop + endfacet + facet normal -0.104014 -0.279648 0.954452 + outer loop + vertex -661.817 167.927 359.56 + vertex -672.317 171.795 359.549 + vertex -662.046 162.803 358.034 + endloop + endfacet + facet normal -0.10469 -0.280372 0.954165 + outer loop + vertex -662.046 162.803 358.034 + vertex -672.317 171.795 359.549 + vertex -672.528 166.662 358.018 + endloop + endfacet + facet normal -0.0772217 -0.207628 0.975155 + outer loop + vertex -661.639 173.13 360.682 + vertex -672.155 177.007 360.675 + vertex -661.817 167.927 359.56 + endloop + endfacet + facet normal -0.0776947 -0.208149 0.975007 + outer loop + vertex -661.817 167.927 359.56 + vertex -672.155 177.007 360.675 + vertex -672.317 171.795 359.549 + endloop + endfacet + facet normal -0.195564 -0.5071 0.839407 + outer loop + vertex -673.121 156.905 353.652 + vertex -683.588 160.907 353.631 + vertex -673.514 152.418 350.85 + endloop + endfacet + facet normal -0.195858 -0.507372 0.839175 + outer loop + vertex -673.514 152.418 350.85 + vertex -683.588 160.907 353.631 + vertex -683.989 156.424 350.827 + endloop + endfacet + facet normal -0.167238 -0.433877 0.885315 + outer loop + vertex -672.793 161.675 356.052 + vertex -683.253 165.674 356.035 + vertex -673.121 156.905 353.652 + endloop + endfacet + facet normal -0.167923 -0.434544 0.884858 + outer loop + vertex -673.121 156.905 353.652 + vertex -683.253 165.674 356.035 + vertex -683.588 160.907 353.631 + endloop + endfacet + facet normal -0.138028 -0.356906 0.923887 + outer loop + vertex -672.528 166.662 358.018 + vertex -682.985 170.665 358.002 + vertex -672.793 161.675 356.052 + endloop + endfacet + facet normal -0.137774 -0.356648 0.924024 + outer loop + vertex -672.793 161.675 356.052 + vertex -682.985 170.665 358.002 + vertex -683.253 165.674 356.035 + endloop + endfacet + facet normal -0.108208 -0.280131 0.953843 + outer loop + vertex -672.317 171.795 359.549 + vertex -682.777 175.8 359.539 + vertex -672.528 166.662 358.018 + endloop + endfacet + facet normal -0.109003 -0.280967 0.953507 + outer loop + vertex -672.528 166.662 358.018 + vertex -682.777 175.8 359.539 + vertex -682.985 170.665 358.002 + endloop + endfacet + facet normal -0.0801774 -0.208033 0.97483 + outer loop + vertex -672.155 177.007 360.675 + vertex -682.623 181.014 360.669 + vertex -672.317 171.795 359.549 + endloop + endfacet + facet normal -0.0809415 -0.208858 0.974591 + outer loop + vertex -672.317 171.795 359.549 + vertex -682.623 181.014 360.669 + vertex -682.777 175.8 359.539 + endloop + endfacet + facet normal -0.201736 -0.506357 0.838394 + outer loop + vertex -683.588 160.907 353.631 + vertex -694.07 165.081 353.629 + vertex -683.989 156.424 350.827 + endloop + endfacet + facet normal -0.201273 -0.505936 0.83876 + outer loop + vertex -683.989 156.424 350.827 + vertex -694.07 165.081 353.629 + vertex -694.475 160.596 350.827 + endloop + endfacet + facet normal -0.17303 -0.433859 0.88421 + outer loop + vertex -683.253 165.674 356.035 + vertex -693.728 169.846 356.033 + vertex -683.588 160.907 353.631 + endloop + endfacet + facet normal -0.17278 -0.43362 0.884376 + outer loop + vertex -683.588 160.907 353.631 + vertex -693.728 169.846 356.033 + vertex -694.07 165.081 353.629 + endloop + endfacet + facet normal -0.141536 -0.356278 0.923598 + outer loop + vertex -682.985 170.665 358.002 + vertex -693.451 174.831 358.005 + vertex -683.253 165.674 356.035 + endloop + endfacet + facet normal -0.142541 -0.357281 0.923056 + outer loop + vertex -683.253 165.674 356.035 + vertex -693.451 174.831 358.005 + vertex -693.728 169.846 356.033 + endloop + endfacet + facet normal -0.111688 -0.280782 0.953251 + outer loop + vertex -682.777 175.8 359.539 + vertex -693.237 179.966 359.54 + vertex -682.985 170.665 358.002 + endloop + endfacet + facet normal -0.11133 -0.280412 0.953402 + outer loop + vertex -682.985 170.665 358.002 + vertex -693.237 179.966 359.54 + vertex -693.451 174.831 358.005 + endloop + endfacet + facet normal -0.0832539 -0.208753 0.974418 + outer loop + vertex -682.623 181.014 360.669 + vertex -693.08 185.181 360.668 + vertex -682.777 175.8 359.539 + endloop + endfacet + facet normal -0.0828093 -0.208281 0.974557 + outer loop + vertex -682.777 175.8 359.539 + vertex -693.08 185.181 360.668 + vertex -693.237 179.966 359.54 + endloop + endfacet + facet normal -0.208675 -0.50463 0.837737 + outer loop + vertex -694.07 165.081 353.629 + vertex -704.519 169.412 353.636 + vertex -694.475 160.596 350.827 + endloop + endfacet + facet normal -0.208239 -0.504242 0.838079 + outer loop + vertex -694.475 160.596 350.827 + vertex -704.519 169.412 353.636 + vertex -704.926 164.925 350.835 + endloop + endfacet + facet normal -0.17852 -0.432828 0.883624 + outer loop + vertex -693.728 169.846 356.033 + vertex -704.17 174.173 356.043 + vertex -694.07 165.081 353.629 + endloop + endfacet + facet normal -0.179108 -0.433378 0.883235 + outer loop + vertex -694.07 165.081 353.629 + vertex -704.17 174.173 356.043 + vertex -704.519 169.412 353.636 + endloop + endfacet + facet normal -0.147123 -0.356813 0.922518 + outer loop + vertex -693.451 174.831 358.005 + vertex -703.887 179.157 358.014 + vertex -693.728 169.846 356.033 + endloop + endfacet + facet normal -0.14689 -0.356586 0.922643 + outer loop + vertex -693.728 169.846 356.033 + vertex -703.887 179.157 358.014 + vertex -704.17 174.173 356.043 + endloop + endfacet + facet normal -0.116025 -0.280079 0.95294 + outer loop + vertex -693.237 179.966 359.54 + vertex -703.666 184.294 359.543 + vertex -693.451 174.831 358.005 + endloop + endfacet + facet normal -0.114755 -0.278794 0.95347 + outer loop + vertex -693.451 174.831 358.005 + vertex -703.666 184.294 359.543 + vertex -703.887 179.157 358.014 + endloop + endfacet + facet normal -0.0861378 -0.208125 0.974302 + outer loop + vertex -693.08 185.181 360.668 + vertex -703.503 189.507 360.671 + vertex -693.237 179.966 359.54 + endloop + endfacet + facet normal -0.0861786 -0.208168 0.974289 + outer loop + vertex -693.237 179.966 359.54 + vertex -703.503 189.507 360.671 + vertex -703.666 184.294 359.543 + endloop + endfacet + facet normal -0.216349 -0.502774 0.836906 + outer loop + vertex -704.519 169.412 353.636 + vertex -714.936 173.909 353.645 + vertex -704.926 164.925 350.835 + endloop + endfacet + facet normal -0.216483 -0.502891 0.836801 + outer loop + vertex -704.926 164.925 350.835 + vertex -714.936 173.909 353.645 + vertex -715.347 169.423 350.842 + endloop + endfacet + facet normal -0.186607 -0.432309 0.882205 + outer loop + vertex -704.17 174.173 356.043 + vertex -714.582 178.675 356.046 + vertex -704.519 169.412 353.636 + endloop + endfacet + facet normal -0.185417 -0.43122 0.882989 + outer loop + vertex -704.519 169.412 353.636 + vertex -714.582 178.675 356.046 + vertex -714.936 173.909 353.645 + endloop + endfacet + facet normal -0.154006 -0.355836 0.921772 + outer loop + vertex -703.887 179.157 358.014 + vertex -714.293 183.659 358.013 + vertex -704.17 174.173 356.043 + endloop + endfacet + facet normal -0.153194 -0.35506 0.922206 + outer loop + vertex -704.17 174.173 356.043 + vertex -714.293 183.659 358.013 + vertex -714.582 178.675 356.046 + endloop + endfacet + facet normal -0.120294 -0.278389 0.952906 + outer loop + vertex -703.666 184.294 359.543 + vertex -714.067 188.792 359.544 + vertex -703.887 179.157 358.014 + endloop + endfacet + facet normal -0.12065 -0.278741 0.952757 + outer loop + vertex -703.887 179.157 358.014 + vertex -714.067 188.792 359.544 + vertex -714.293 183.659 358.013 + endloop + endfacet + facet normal -0.0892002 -0.208021 0.974049 + outer loop + vertex -703.503 189.507 360.671 + vertex -713.899 194 360.678 + vertex -703.666 184.294 359.543 + endloop + endfacet + facet normal -0.090372 -0.209214 0.973685 + outer loop + vertex -703.666 184.294 359.543 + vertex -713.899 194 360.678 + vertex -714.067 188.792 359.544 + endloop + endfacet + facet normal -0.225302 -0.501245 0.83546 + outer loop + vertex -714.936 173.909 353.645 + vertex -725.353 178.601 353.65 + vertex -715.347 169.423 350.842 + endloop + endfacet + facet normal -0.226001 -0.50184 0.834913 + outer loop + vertex -715.347 169.423 350.842 + vertex -725.353 178.601 353.65 + vertex -725.77 174.12 350.844 + endloop + endfacet + facet normal -0.193005 -0.43011 0.881904 + outer loop + vertex -714.582 178.675 356.046 + vertex -724.993 183.363 356.054 + vertex -714.936 173.909 353.645 + endloop + endfacet + facet normal -0.193406 -0.43047 0.88164 + outer loop + vertex -714.936 173.909 353.645 + vertex -724.993 183.363 356.054 + vertex -725.353 178.601 353.65 + endloop + endfacet + facet normal -0.158912 -0.354439 0.921477 + outer loop + vertex -714.293 183.659 358.013 + vertex -724.697 188.346 358.022 + vertex -714.582 178.675 356.046 + endloop + endfacet + facet normal -0.15889 -0.354419 0.921489 + outer loop + vertex -714.582 178.675 356.046 + vertex -724.697 188.346 358.022 + vertex -724.993 183.363 356.054 + endloop + endfacet + facet normal -0.124791 -0.278427 0.952316 + outer loop + vertex -714.067 188.792 359.544 + vertex -724.466 193.479 359.551 + vertex -714.293 183.659 358.013 + endloop + endfacet + facet normal -0.124536 -0.27818 0.952421 + outer loop + vertex -714.293 183.659 358.013 + vertex -724.466 193.479 359.551 + vertex -724.697 188.346 358.022 + endloop + endfacet + facet normal -0.0944139 -0.20901 0.973345 + outer loop + vertex -713.899 194 360.678 + vertex -724.296 198.691 360.677 + vertex -714.067 188.792 359.544 + endloop + endfacet + facet normal -0.0927394 -0.207339 0.973863 + outer loop + vertex -714.067 188.792 359.544 + vertex -724.296 198.691 360.677 + vertex -724.466 193.479 359.551 + endloop + endfacet + facet normal -0.234891 -0.500121 0.83349 + outer loop + vertex -725.353 178.601 353.65 + vertex -735.763 183.494 353.652 + vertex -725.77 174.12 350.844 + endloop + endfacet + facet normal -0.234586 -0.499868 0.833728 + outer loop + vertex -725.77 174.12 350.844 + vertex -735.763 183.494 353.652 + vertex -736.186 179.013 350.847 + endloop + endfacet + facet normal -0.201952 -0.429174 0.880355 + outer loop + vertex -724.993 183.363 356.054 + vertex -735.396 188.257 356.054 + vertex -725.353 178.601 353.65 + endloop + endfacet + facet normal -0.20124 -0.428549 0.880822 + outer loop + vertex -725.353 178.601 353.65 + vertex -735.396 188.257 356.054 + vertex -735.763 183.494 353.652 + endloop + endfacet + facet normal -0.166977 -0.353512 0.920407 + outer loop + vertex -724.697 188.346 358.022 + vertex -735.094 193.242 358.016 + vertex -724.993 183.363 356.054 + endloop + endfacet + facet normal -0.16589 -0.352516 0.920985 + outer loop + vertex -724.993 183.363 356.054 + vertex -735.094 193.242 358.016 + vertex -735.396 188.257 356.054 + endloop + endfacet + facet normal -0.130948 -0.277679 0.951707 + outer loop + vertex -724.466 193.479 359.551 + vertex -734.86 198.372 359.549 + vertex -724.697 188.346 358.022 + endloop + endfacet + facet normal -0.13155 -0.278251 0.951457 + outer loop + vertex -724.697 188.346 358.022 + vertex -734.86 198.372 359.549 + vertex -735.094 193.242 358.016 + endloop + endfacet + facet normal -0.0973284 -0.207103 0.973466 + outer loop + vertex -724.296 198.691 360.677 + vertex -734.685 203.581 360.679 + vertex -724.466 193.479 359.551 + endloop + endfacet + facet normal -0.0980675 -0.207825 0.973238 + outer loop + vertex -724.466 193.479 359.551 + vertex -734.685 203.581 360.679 + vertex -734.86 198.372 359.549 + endloop + endfacet + facet normal -0.244993 -0.497789 0.831976 + outer loop + vertex -735.763 183.494 353.652 + vertex -746.1 188.574 353.648 + vertex -736.186 179.013 350.847 + endloop + endfacet + facet normal -0.24349 -0.496573 0.833144 + outer loop + vertex -736.186 179.013 350.847 + vertex -746.1 188.574 353.648 + vertex -746.53 184.089 350.849 + endloop + endfacet + facet normal -0.209732 -0.427221 0.879485 + outer loop + vertex -735.396 188.257 356.054 + vertex -745.727 193.33 356.054 + vertex -735.763 183.494 353.652 + endloop + endfacet + facet normal -0.210753 -0.428092 0.878818 + outer loop + vertex -735.763 183.494 353.652 + vertex -745.727 193.33 356.054 + vertex -746.1 188.574 353.648 + endloop + endfacet + facet normal -0.172443 -0.351759 0.92007 + outer loop + vertex -735.094 193.242 358.016 + vertex -745.42 198.313 358.02 + vertex -735.396 188.257 356.054 + endloop + endfacet + facet normal -0.172847 -0.35212 0.919856 + outer loop + vertex -735.396 188.257 356.054 + vertex -745.42 198.313 358.02 + vertex -745.727 193.33 356.054 + endloop + endfacet + facet normal -0.136717 -0.277833 0.950851 + outer loop + vertex -734.86 198.372 359.549 + vertex -745.18 203.446 359.547 + vertex -735.094 193.242 358.016 + endloop + endfacet + facet normal -0.135635 -0.27683 0.951298 + outer loop + vertex -735.094 193.242 358.016 + vertex -745.18 203.446 359.547 + vertex -745.42 198.313 358.02 + endloop + endfacet + facet normal -0.10225 -0.207602 0.972855 + outer loop + vertex -734.685 203.581 360.679 + vertex -745.003 208.654 360.677 + vertex -734.86 198.372 359.549 + endloop + endfacet + facet normal -0.102147 -0.207504 0.972887 + outer loop + vertex -734.86 198.372 359.549 + vertex -745.003 208.654 360.677 + vertex -745.18 203.446 359.547 + endloop + endfacet + facet normal -0.253937 -0.494422 0.831302 + outer loop + vertex -746.1 188.574 353.648 + vertex -756.284 193.804 353.648 + vertex -746.53 184.089 350.849 + endloop + endfacet + facet normal -0.253616 -0.494171 0.831549 + outer loop + vertex -746.53 184.089 350.849 + vertex -756.284 193.804 353.648 + vertex -756.721 189.319 350.849 + endloop + endfacet + facet normal -0.219269 -0.42671 0.877405 + outer loop + vertex -745.727 193.33 356.054 + vertex -755.906 198.559 356.054 + vertex -746.1 188.574 353.648 + endloop + endfacet + facet normal -0.2191 -0.42657 0.877515 + outer loop + vertex -746.1 188.574 353.648 + vertex -755.906 198.559 356.054 + vertex -756.284 193.804 353.648 + endloop + endfacet + facet normal -0.180774 -0.351173 0.918694 + outer loop + vertex -745.42 198.313 358.02 + vertex -755.592 203.542 358.017 + vertex -745.727 193.33 356.054 + endloop + endfacet + facet normal -0.180231 -0.350703 0.91898 + outer loop + vertex -745.727 193.33 356.054 + vertex -755.592 203.542 358.017 + vertex -755.906 198.559 356.054 + endloop + endfacet + facet normal -0.142312 -0.276276 0.950483 + outer loop + vertex -745.18 203.446 359.547 + vertex -755.349 208.673 359.544 + vertex -745.42 198.313 358.02 + endloop + endfacet + facet normal -0.142269 -0.276238 0.950501 + outer loop + vertex -745.42 198.313 358.02 + vertex -755.349 208.673 359.544 + vertex -755.592 203.542 358.017 + endloop + endfacet + facet normal -0.106454 -0.207268 0.972475 + outer loop + vertex -745.003 208.654 360.677 + vertex -755.17 213.879 360.678 + vertex -745.18 203.446 359.547 + endloop + endfacet + facet normal -0.107194 -0.207951 0.972248 + outer loop + vertex -745.18 203.446 359.547 + vertex -755.17 213.879 360.678 + vertex -755.349 208.673 359.544 + endloop + endfacet + facet normal -0.264016 -0.491956 0.829623 + outer loop + vertex -756.284 193.804 353.648 + vertex -766.275 199.169 353.65 + vertex -756.721 189.319 350.849 + endloop + endfacet + facet normal -0.265005 -0.4927 0.828866 + outer loop + vertex -756.721 189.319 350.849 + vertex -766.275 199.169 353.65 + vertex -766.717 194.691 350.846 + endloop + endfacet + facet normal -0.228986 -0.424912 0.875794 + outer loop + vertex -755.906 198.559 356.054 + vertex -765.887 203.928 356.049 + vertex -756.284 193.804 353.648 + endloop + endfacet + facet normal -0.227271 -0.423548 0.876901 + outer loop + vertex -756.284 193.804 353.648 + vertex -765.887 203.928 356.049 + vertex -766.275 199.169 353.65 + endloop + endfacet + facet normal -0.187548 -0.349802 0.917859 + outer loop + vertex -755.592 203.542 358.017 + vertex -765.571 208.903 358.021 + vertex -755.906 198.559 356.054 + endloop + endfacet + facet normal -0.189462 -0.351399 0.916855 + outer loop + vertex -755.906 198.559 356.054 + vertex -765.571 208.903 358.021 + vertex -765.887 203.928 356.049 + endloop + endfacet + facet normal -0.147848 -0.27576 0.949788 + outer loop + vertex -755.349 208.673 359.544 + vertex -765.324 214.035 359.548 + vertex -755.592 203.542 358.017 + endloop + endfacet + facet normal -0.147671 -0.275607 0.94986 + outer loop + vertex -755.592 203.542 358.017 + vertex -765.324 214.035 359.548 + vertex -765.571 208.903 358.021 + endloop + endfacet + facet normal -0.11198 -0.207682 0.971766 + outer loop + vertex -755.17 213.879 360.678 + vertex -765.14 219.243 360.675 + vertex -755.349 208.673 359.544 + endloop + endfacet + facet normal -0.110569 -0.206421 0.972196 + outer loop + vertex -755.349 208.673 359.544 + vertex -765.14 219.243 360.675 + vertex -765.324 214.035 359.548 + endloop + endfacet + facet normal -0.275853 -0.4903 0.826747 + outer loop + vertex -766.275 199.169 353.65 + vertex -776.08 204.681 353.647 + vertex -766.717 194.691 350.846 + endloop + endfacet + facet normal -0.274262 -0.489149 0.827958 + outer loop + vertex -766.717 194.691 350.846 + vertex -776.08 204.681 353.647 + vertex -776.532 200.197 350.848 + endloop + endfacet + facet normal -0.237127 -0.421844 0.875111 + outer loop + vertex -765.887 203.928 356.049 + vertex -775.687 209.437 356.049 + vertex -766.275 199.169 353.65 + endloop + endfacet + facet normal -0.237579 -0.42219 0.874821 + outer loop + vertex -766.275 199.169 353.65 + vertex -775.687 209.437 356.049 + vertex -776.08 204.681 353.647 + endloop + endfacet + facet normal -0.197172 -0.350414 0.915605 + outer loop + vertex -765.571 208.903 358.021 + vertex -775.365 214.412 358.02 + vertex -765.887 203.928 356.049 + endloop + endfacet + facet normal -0.196808 -0.350121 0.915796 + outer loop + vertex -765.887 203.928 356.049 + vertex -775.365 214.412 358.02 + vertex -775.687 209.437 356.049 + endloop + endfacet + facet normal -0.154978 -0.274963 0.948882 + outer loop + vertex -765.324 214.035 359.548 + vertex -775.113 219.543 359.546 + vertex -765.571 208.903 358.021 + endloop + endfacet + facet normal -0.154528 -0.274586 0.949065 + outer loop + vertex -765.571 208.903 358.021 + vertex -775.113 219.543 359.546 + vertex -775.365 214.412 358.02 + endloop + endfacet + facet normal -0.115721 -0.206122 0.97166 + outer loop + vertex -765.14 219.243 360.675 + vertex -774.926 224.748 360.677 + vertex -765.324 214.035 359.548 + endloop + endfacet + facet normal -0.116744 -0.207006 0.971349 + outer loop + vertex -765.324 214.035 359.548 + vertex -774.926 224.748 360.677 + vertex -775.113 219.543 359.546 + endloop + endfacet + facet normal -0.2861 -0.486447 0.82554 + outer loop + vertex -776.08 204.681 353.647 + vertex -785.743 210.353 353.64 + vertex -776.532 200.197 350.848 + endloop + endfacet + facet normal -0.286798 -0.486934 0.82501 + outer loop + vertex -776.532 200.197 350.848 + vertex -785.743 210.353 353.64 + vertex -786.198 205.872 350.837 + endloop + endfacet + facet normal -0.247277 -0.420453 0.872968 + outer loop + vertex -775.687 209.437 356.049 + vertex -785.346 215.109 356.045 + vertex -776.08 204.681 353.647 + endloop + endfacet + facet normal -0.24749 -0.420611 0.872832 + outer loop + vertex -776.08 204.681 353.647 + vertex -785.346 215.109 356.045 + vertex -785.743 210.353 353.64 + endloop + endfacet + facet normal -0.205489 -0.348977 0.914325 + outer loop + vertex -775.365 214.412 358.02 + vertex -785.019 220.084 358.015 + vertex -775.687 209.437 356.049 + endloop + endfacet + facet normal -0.205182 -0.348738 0.914485 + outer loop + vertex -775.687 209.437 356.049 + vertex -785.019 220.084 358.015 + vertex -785.346 215.109 356.045 + endloop + endfacet + facet normal -0.16124 -0.273977 0.948124 + outer loop + vertex -775.113 219.543 359.546 + vertex -784.761 225.212 359.543 + vertex -775.365 214.412 358.02 + endloop + endfacet + facet normal -0.16161 -0.274277 0.947974 + outer loop + vertex -775.365 214.412 358.02 + vertex -784.761 225.212 359.543 + vertex -785.019 220.084 358.015 + endloop + endfacet + facet normal -0.121753 -0.206706 0.970798 + outer loop + vertex -774.926 224.748 360.677 + vertex -784.567 230.416 360.675 + vertex -775.113 219.543 359.546 + endloop + endfacet + facet normal -0.12168 -0.206646 0.97082 + outer loop + vertex -775.113 219.543 359.546 + vertex -784.567 230.416 360.675 + vertex -784.761 225.212 359.543 + endloop + endfacet + facet normal -0.297184 -0.484482 0.822775 + outer loop + vertex -785.743 210.353 353.64 + vertex -795.292 216.205 353.637 + vertex -786.198 205.872 350.837 + endloop + endfacet + facet normal -0.297097 -0.484423 0.822842 + outer loop + vertex -786.198 205.872 350.837 + vertex -795.292 216.205 353.637 + vertex -795.747 211.72 350.833 + endloop + endfacet + facet normal -0.257615 -0.418739 0.8708 + outer loop + vertex -785.346 215.109 356.045 + vertex -794.895 220.971 356.039 + vertex -785.743 210.353 353.64 + endloop + endfacet + facet normal -0.256353 -0.417834 0.871607 + outer loop + vertex -785.743 210.353 353.64 + vertex -794.895 220.971 356.039 + vertex -795.292 216.205 353.637 + endloop + endfacet + facet normal -0.213946 -0.347545 0.912929 + outer loop + vertex -785.019 220.084 358.015 + vertex -794.564 225.947 358.011 + vertex -785.346 215.109 356.045 + endloop + endfacet + facet normal -0.213923 -0.347528 0.912941 + outer loop + vertex -785.346 215.109 356.045 + vertex -794.564 225.947 358.011 + vertex -794.895 220.971 356.039 + endloop + endfacet + facet normal -0.168522 -0.273627 0.946958 + outer loop + vertex -784.761 225.212 359.543 + vertex -794.298 231.073 359.539 + vertex -785.019 220.084 358.015 + endloop + endfacet + facet normal -0.168595 -0.273685 0.946928 + outer loop + vertex -785.019 220.084 358.015 + vertex -794.298 231.073 359.539 + vertex -794.564 225.947 358.011 + endloop + endfacet + facet normal -0.127278 -0.206297 0.970176 + outer loop + vertex -784.567 230.416 360.675 + vertex -794.092 236.271 360.67 + vertex -784.761 225.212 359.543 + endloop + endfacet + facet normal -0.127034 -0.206098 0.97025 + outer loop + vertex -784.761 225.212 359.543 + vertex -794.092 236.271 360.67 + vertex -794.298 231.073 359.539 + endloop + endfacet + facet normal -0.311431 -0.48093 0.819583 + outer loop + vertex -795.292 216.205 353.637 + vertex -804.735 222.324 353.64 + vertex -795.747 211.72 350.833 + endloop + endfacet + facet normal -0.311592 -0.481034 0.819461 + outer loop + vertex -795.747 211.72 350.833 + vertex -804.735 222.324 353.64 + vertex -805.193 217.845 350.836 + endloop + endfacet + facet normal -0.268873 -0.41546 0.868965 + outer loop + vertex -794.895 220.971 356.039 + vertex -804.339 227.089 356.042 + vertex -795.292 216.205 353.637 + endloop + endfacet + facet normal -0.269094 -0.415613 0.868823 + outer loop + vertex -795.292 216.205 353.637 + vertex -804.339 227.089 356.042 + vertex -804.735 222.324 353.64 + endloop + endfacet + facet normal -0.224733 -0.346008 0.910919 + outer loop + vertex -794.564 225.947 358.011 + vertex -804.003 232.069 358.007 + vertex -794.895 220.971 356.039 + endloop + endfacet + facet normal -0.223099 -0.344819 0.911771 + outer loop + vertex -794.895 220.971 356.039 + vertex -804.003 232.069 358.007 + vertex -804.339 227.089 356.042 + endloop + endfacet + facet normal -0.176552 -0.272905 0.945702 + outer loop + vertex -794.298 231.073 359.539 + vertex -803.724 237.181 359.542 + vertex -794.564 225.947 358.011 + endloop + endfacet + facet normal -0.178092 -0.274075 0.945075 + outer loop + vertex -794.564 225.947 358.011 + vertex -803.724 237.181 359.542 + vertex -804.003 232.069 358.007 + endloop + endfacet + facet normal -0.133596 -0.205667 0.96946 + outer loop + vertex -794.092 236.271 360.67 + vertex -803.499 242.375 360.669 + vertex -794.298 231.073 359.539 + endloop + endfacet + facet normal -0.132327 -0.204672 0.969845 + outer loop + vertex -794.298 231.073 359.539 + vertex -803.499 242.375 360.669 + vertex -803.724 237.181 359.542 + endloop + endfacet + facet normal -0.328924 -0.476628 0.815251 + outer loop + vertex -804.735 222.324 353.64 + vertex -814.103 228.833 353.666 + vertex -805.193 217.845 350.836 + endloop + endfacet + facet normal -0.326883 -0.475373 0.816804 + outer loop + vertex -805.193 217.845 350.836 + vertex -814.103 228.833 353.666 + vertex -814.578 224.36 350.872 + endloop + endfacet + facet normal -0.284867 -0.412507 0.865268 + outer loop + vertex -804.339 227.089 356.042 + vertex -813.688 233.585 356.06 + vertex -804.735 222.324 353.64 + endloop + endfacet + facet normal -0.283686 -0.411732 0.866025 + outer loop + vertex -804.735 222.324 353.64 + vertex -813.688 233.585 356.06 + vertex -814.103 228.833 353.666 + endloop + endfacet + facet normal -0.236465 -0.342876 0.909132 + outer loop + vertex -804.003 232.069 358.007 + vertex -813.332 238.547 358.024 + vertex -804.339 227.089 356.042 + endloop + endfacet + facet normal -0.236331 -0.342783 0.909201 + outer loop + vertex -804.339 227.089 356.042 + vertex -813.332 238.547 358.024 + vertex -813.688 233.585 356.06 + endloop + endfacet + facet normal -0.189229 -0.272918 0.943243 + outer loop + vertex -803.724 237.181 359.542 + vertex -813.026 243.653 359.549 + vertex -804.003 232.069 358.007 + endloop + endfacet + facet normal -0.1864 -0.270868 0.944397 + outer loop + vertex -804.003 232.069 358.007 + vertex -813.026 243.653 359.549 + vertex -813.332 238.547 358.024 + endloop + endfacet + facet normal -0.141549 -0.20402 0.968679 + outer loop + vertex -803.499 242.375 360.669 + vertex -812.773 248.838 360.675 + vertex -803.724 237.181 359.542 + endloop + endfacet + facet normal -0.140981 -0.203596 0.968851 + outer loop + vertex -803.724 237.181 359.542 + vertex -812.773 248.838 360.675 + vertex -813.026 243.653 359.549 + endloop + endfacet + facet normal -0.34798 -0.469718 0.811341 + outer loop + vertex -814.103 228.833 353.666 + vertex -823.444 235.812 353.7 + vertex -814.578 224.36 350.872 + endloop + endfacet + facet normal -0.344951 -0.467945 0.813656 + outer loop + vertex -814.578 224.36 350.872 + vertex -823.444 235.812 353.7 + vertex -823.949 231.345 350.917 + endloop + endfacet + facet normal -0.302085 -0.407898 0.861605 + outer loop + vertex -813.688 233.585 356.06 + vertex -822.982 240.537 356.093 + vertex -814.103 228.833 353.666 + endloop + endfacet + facet normal -0.301195 -0.407342 0.86218 + outer loop + vertex -814.103 228.833 353.666 + vertex -822.982 240.537 356.093 + vertex -823.444 235.812 353.7 + endloop + endfacet + facet normal -0.253143 -0.340172 0.90565 + outer loop + vertex -813.332 238.547 358.024 + vertex -822.563 245.476 358.046 + vertex -813.688 233.585 356.06 + endloop + endfacet + facet normal -0.249432 -0.337726 0.907593 + outer loop + vertex -813.688 233.585 356.06 + vertex -822.563 245.476 358.046 + vertex -822.982 240.537 356.093 + endloop + endfacet + facet normal -0.200279 -0.26932 0.941995 + outer loop + vertex -813.026 243.653 359.549 + vertex -822.201 250.549 359.57 + vertex -813.332 238.547 358.024 + endloop + endfacet + facet normal -0.199448 -0.26875 0.942334 + outer loop + vertex -813.332 238.547 358.024 + vertex -822.201 250.549 359.57 + vertex -822.563 245.476 358.046 + endloop + endfacet + facet normal -0.151364 -0.202786 0.967454 + outer loop + vertex -812.773 248.838 360.675 + vertex -821.904 255.726 360.69 + vertex -813.026 243.653 359.549 + endloop + endfacet + facet normal -0.148908 -0.20105 0.968197 + outer loop + vertex -813.026 243.653 359.549 + vertex -821.904 255.726 360.69 + vertex -822.201 250.549 359.57 + endloop + endfacet + facet normal -0.364869 -0.462284 0.808186 + outer loop + vertex -823.444 235.812 353.7 + vertex -832.725 243.093 353.674 + vertex -823.949 231.345 350.917 + endloop + endfacet + facet normal -0.365078 -0.462402 0.808024 + outer loop + vertex -823.949 231.345 350.917 + vertex -832.725 243.093 353.674 + vertex -833.237 238.632 350.89 + endloop + endfacet + facet normal -0.320229 -0.403026 0.857335 + outer loop + vertex -822.982 240.537 356.093 + vertex -832.224 247.839 356.074 + vertex -823.444 235.812 353.7 + endloop + endfacet + facet normal -0.31699 -0.401079 0.85945 + outer loop + vertex -823.444 235.812 353.7 + vertex -832.224 247.839 356.074 + vertex -832.725 243.093 353.674 + endloop + endfacet + facet normal -0.267009 -0.3347 0.903705 + outer loop + vertex -822.563 245.476 358.046 + vertex -831.693 252.75 358.043 + vertex -822.982 240.537 356.093 + endloop + endfacet + facet normal -0.265679 -0.333863 0.904406 + outer loop + vertex -822.982 240.537 356.093 + vertex -831.693 252.75 358.043 + vertex -832.224 247.839 356.074 + endloop + endfacet + facet normal -0.21364 -0.266954 0.939731 + outer loop + vertex -822.201 250.549 359.57 + vertex -831.213 257.775 359.573 + vertex -822.563 245.476 358.046 + endloop + endfacet + facet normal -0.212396 -0.266143 0.940243 + outer loop + vertex -822.563 245.476 358.046 + vertex -831.213 257.775 359.573 + vertex -831.693 252.75 358.043 + endloop + endfacet + facet normal -0.160487 -0.200031 0.966557 + outer loop + vertex -821.904 255.726 360.69 + vertex -830.854 262.928 360.695 + vertex -822.201 250.549 359.57 + endloop + endfacet + facet normal -0.159368 -0.19928 0.966897 + outer loop + vertex -822.201 250.549 359.57 + vertex -830.854 262.928 360.695 + vertex -831.213 257.775 359.573 + endloop + endfacet + facet normal -0.379837 -0.458015 0.803708 + outer loop + vertex -832.725 243.093 353.674 + vertex -841.612 250.115 353.476 + vertex -833.237 238.632 350.89 + endloop + endfacet + facet normal -0.383519 -0.460044 0.800795 + outer loop + vertex -833.237 238.632 350.89 + vertex -841.612 250.115 353.476 + vertex -842.148 245.735 350.703 + endloop + endfacet + facet normal -0.331471 -0.397601 0.855594 + outer loop + vertex -832.224 247.839 356.074 + vertex -841.234 255.006 355.914 + vertex -832.725 243.093 353.674 + endloop + endfacet + facet normal -0.334731 -0.399522 0.853427 + outer loop + vertex -832.725 243.093 353.674 + vertex -841.234 255.006 355.914 + vertex -841.612 250.115 353.476 + endloop + endfacet + facet normal -0.279224 -0.331161 0.901314 + outer loop + vertex -831.693 252.75 358.043 + vertex -840.647 260.051 357.951 + vertex -832.224 247.839 356.074 + endloop + endfacet + facet normal -0.279614 -0.331398 0.901106 + outer loop + vertex -832.224 247.839 356.074 + vertex -840.647 260.051 357.951 + vertex -841.234 255.006 355.914 + endloop + endfacet + facet normal -0.224791 -0.264243 0.937894 + outer loop + vertex -831.213 257.775 359.573 + vertex -839.903 264.97 359.518 + vertex -831.693 252.75 358.043 + endloop + endfacet + facet normal -0.225282 -0.264549 0.93769 + outer loop + vertex -831.693 252.75 358.043 + vertex -839.903 264.97 359.518 + vertex -840.647 260.051 357.951 + endloop + endfacet + facet normal -0.169082 -0.198288 0.96545 + outer loop + vertex -830.854 262.928 360.695 + vertex -839.478 270.088 360.655 + vertex -831.213 257.775 359.573 + endloop + endfacet + facet normal -0.171795 -0.200035 0.96461 + outer loop + vertex -831.213 257.775 359.573 + vertex -839.478 270.088 360.655 + vertex -839.903 264.97 359.518 + endloop + endfacet + facet normal -0.390649 -0.457801 0.798631 + outer loop + vertex -841.612 250.115 353.476 + vertex -849.258 255.932 353.07 + vertex -842.148 245.735 350.703 + endloop + endfacet + facet normal -0.406153 -0.46573 0.786216 + outer loop + vertex -842.148 245.735 350.703 + vertex -849.258 255.932 353.07 + vertex -850.638 252.531 350.343 + endloop + endfacet + facet normal -0.338272 -0.398735 0.852398 + outer loop + vertex -841.234 255.006 355.914 + vertex -849.571 261.276 355.538 + vertex -841.612 250.115 353.476 + endloop + endfacet + facet normal -0.355696 -0.408942 0.840385 + outer loop + vertex -841.612 250.115 353.476 + vertex -849.571 261.276 355.538 + vertex -849.258 255.932 353.07 + endloop + endfacet + facet normal -0.285656 -0.330118 0.899679 + outer loop + vertex -840.647 260.051 357.951 + vertex -849.21 266.795 357.707 + vertex -841.234 255.006 355.914 + endloop + endfacet + facet normal -0.291114 -0.333363 0.896728 + outer loop + vertex -841.234 255.006 355.914 + vertex -849.21 266.795 357.707 + vertex -849.571 261.276 355.538 + endloop + endfacet + facet normal -0.232824 -0.262964 0.936292 + outer loop + vertex -839.903 264.97 359.518 + vertex -848.315 272.11 359.432 + vertex -840.647 260.051 357.951 + endloop + endfacet + facet normal -0.234621 -0.264014 0.935548 + outer loop + vertex -840.647 260.051 357.951 + vertex -848.315 272.11 359.432 + vertex -849.21 266.795 357.707 + endloop + endfacet + facet normal -0.176154 -0.199522 0.96393 + outer loop + vertex -839.478 270.088 360.655 + vertex -847.007 276.201 360.544 + vertex -839.903 264.97 359.518 + endloop + endfacet + facet normal -0.182484 -0.203345 0.961951 + outer loop + vertex -839.903 264.97 359.518 + vertex -847.007 276.201 360.544 + vertex -848.315 272.11 359.432 + endloop + endfacet + facet normal -0.158625 -0.513663 0.843201 + outer loop + vertex -600.311 127.948 350.926 + vertex -596.799 131.307 353.633 + vertex -603.26 133.519 353.765 + endloop + endfacet + facet normal -0.1596 -0.597723 0.785656 + outer loop + vertex -600.547 122.957 347.081 + vertex -600.311 127.948 350.926 + vertex -604.113 126.231 348.847 + endloop + endfacet + facet normal -0.193429 -0.662892 0.723297 + outer loop + vertex -601.354 118.886 343.134 + vertex -600.547 122.957 347.081 + vertex -604.45 121.938 345.103 + endloop + endfacet + facet normal -0.226958 -0.703765 0.673205 + outer loop + vertex -601.305 116.049 340.185 + vertex -601.354 118.886 343.134 + vertex -604.515 117.611 340.736 + endloop + endfacet + facet normal -0.233646 -0.781048 0.579115 + outer loop + vertex -602.779 111.742 334.084 + vertex -602.109 114.066 337.488 + vertex -605.644 114.493 336.638 + endloop + endfacet + facet normal -0.232825 -0.817627 0.526573 + outer loop + vertex -603.442 109.65 330.542 + vertex -602.779 111.742 334.084 + vertex -606.495 111.903 332.691 + endloop + endfacet + facet normal -0.261994 -0.867348 0.423162 + outer loop + vertex -605.262 106.965 324.406 + vertex -603.846 108.057 327.521 + vertex -607.317 109.357 328.036 + endloop + endfacet + facet normal -0.235714 -0.901452 0.363074 + outer loop + vertex -606.003 105.547 320.405 + vertex -605.262 106.965 324.406 + vertex -609.188 107.317 322.73 + endloop + endfacet + facet normal -0.20633 -0.952396 0.224431 + outer loop + vertex -607.529 103.813 313.015 + vertex -606.561 104.377 316.299 + vertex -608.525 104.485 314.952 + endloop + endfacet + facet normal -0.141255 -0.849884 0.507684 + outer loop + vertex -636.738 111.367 316.879 + vertex -633.181 110.237 315.976 + vertex -632.144 110.04 315.935 + endloop + endfacet + facet normal -0.141594 -0.826172 0.545335 + outer loop + vertex -640.174 112.396 317.544 + vertex -636.738 111.367 316.879 + vertex -640.996 112.963 318.191 + endloop + endfacet + facet normal -0.142741 -0.826656 0.544302 + outer loop + vertex -641.901 112.949 317.931 + vertex -640.174 112.396 317.544 + vertex -640.996 112.963 318.191 + endloop + endfacet + facet normal -0.15586 -0.793574 0.588173 + outer loop + vertex -643.174 113.365 318.156 + vertex -641.901 112.949 317.931 + vertex -640.996 112.963 318.191 + endloop + endfacet + facet normal -0.148289 -0.747528 0.647466 + outer loop + vertex -646.442 114.453 318.663 + vertex -643.174 113.365 318.156 + vertex -640.996 112.963 318.191 + endloop + endfacet + facet normal -0.134223 -0.718954 0.681974 + outer loop + vertex -649.843 115.552 319.152 + vertex -646.442 114.453 318.663 + vertex -651.678 116.471 319.76 + endloop + endfacet + facet normal -0.301593 -0.784479 0.541881 + outer loop + vertex -687.73 129.026 320.507 + vertex -685.298 128.139 320.576 + vertex -690.567 130.579 321.177 + endloop + endfacet + facet normal -0.403546 -0.797335 0.448783 + outer loop + vertex -757.747 160.448 320.103 + vertex -752.95 157.703 319.54 + vertex -752.782 158.498 321.103 + endloop + endfacet + facet normal -0.414985 -0.774893 0.476789 + outer loop + vertex -768.952 166.273 319.859 + vertex -764.133 163.719 319.902 + vertex -771.016 168.154 321.12 + endloop + endfacet + facet normal -0.503512 -0.76015 0.410667 + outer loop + vertex -804.757 187.881 319.866 + vertex -800.169 184.857 319.893 + vertex -801.016 186.077 321.113 + endloop + endfacet + facet normal -0.532528 -0.753116 0.386302 + outer loop + vertex -813.847 194.051 319.715 + vertex -809.16 190.808 319.855 + vertex -810.342 192.275 321.084 + endloop + endfacet + facet normal -0.550876 -0.75148 0.363061 + outer loop + vertex -824.139 201.669 320.045 + vertex -819.526 198.018 319.489 + vertex -819.88 199.05 321.088 + endloop + endfacet + facet normal -0.588506 -0.733167 0.340773 + outer loop + vertex -835.591 210.495 319.517 + vertex -830.047 206.159 319.763 + vertex -837.023 212.412 321.168 + endloop + endfacet + facet normal -0.625389 -0.72361 0.292024 + outer loop + vertex -844.423 218.018 319.729 + vertex -840.264 214.566 320.083 + vertex -845.391 219.49 321.303 + endloop + endfacet + facet normal -0.658733 -0.671884 0.338589 + outer loop + vertex -860.272 232.729 319.817 + vertex -856.217 228.996 320.299 + vertex -856.976 231.577 323.944 + endloop + endfacet + facet normal -0.406433 -0.45635 0.791553 + outer loop + vertex -855.281 261.032 352.86 + vertex -856.65 259.009 350.991 + vertex -850.638 252.531 350.343 + endloop + endfacet + facet normal -0.393762 -0.431525 0.811627 + outer loop + vertex -854.029 263.161 354.599 + vertex -855.281 261.032 352.86 + vertex -849.258 255.932 353.07 + endloop + endfacet + facet normal -0.340556 -0.376079 0.861734 + outer loop + vertex -855.255 267.411 355.97 + vertex -854.029 263.161 354.599 + vertex -849.571 261.276 355.538 + endloop + endfacet + facet normal -0.311737 -0.350878 0.883009 + outer loop + vertex -853.795 268.718 357.004 + vertex -855.255 267.411 355.97 + vertex -849.571 261.276 355.538 + endloop + endfacet + facet normal -0.263042 -0.290926 0.919875 + outer loop + vertex -854.95 273.153 358.076 + vertex -853.795 268.718 357.004 + vertex -849.21 266.795 357.707 + endloop + endfacet + facet normal -0.228895 -0.261139 0.93777 + outer loop + vertex -853.757 275.811 359.108 + vertex -854.95 273.153 358.076 + vertex -849.21 266.795 357.707 + endloop + endfacet + facet normal -0.215534 -0.234042 0.948034 + outer loop + vertex -853.195 278.364 359.866 + vertex -853.757 275.811 359.108 + vertex -848.315 272.11 359.432 + endloop + endfacet + facet normal -0.152448 -0.186372 0.97058 + outer loop + vertex -852.709 280.903 360.43 + vertex -853.195 278.364 359.866 + vertex -848.315 272.11 359.432 + endloop + endfacet + facet normal -0.0640246 -0.247728 0.966712 + outer loop + vertex -592.865 142.086 358.656 + vertex -593.217 148.147 360.186 + vertex -601.126 149.025 359.887 + endloop + endfacet + facet normal -0.0938486 -0.337312 0.936703 + outer loop + vertex -592.089 135.324 356.299 + vertex -592.865 142.086 358.656 + vertex -601.089 143.3 358.269 + endloop + endfacet + facet normal -0.133191 -0.434884 0.890582 + outer loop + vertex -596.799 131.307 353.633 + vertex -592.089 135.324 356.299 + vertex -601.845 137.994 356.144 + endloop + endfacet + facet normal -0.255983 -0.905517 0.338395 + outer loop + vertex -609.188 107.317 322.73 + vertex -607.71 105.293 318.433 + vertex -606.003 105.547 320.405 + endloop + endfacet + facet normal -0.259041 -0.867401 0.424868 + outer loop + vertex -607.317 109.357 328.036 + vertex -609.188 107.317 322.73 + vertex -605.262 106.965 324.406 + endloop + endfacet + facet normal -0.247031 -0.784899 0.568251 + outer loop + vertex -605.644 114.493 336.638 + vertex -606.495 111.903 332.691 + vertex -602.779 111.742 334.084 + endloop + endfacet + facet normal -0.242217 -0.687455 0.684644 + outer loop + vertex -604.45 121.938 345.103 + vertex -604.515 117.611 340.736 + vertex -601.354 118.886 343.134 + endloop + endfacet + facet normal -0.212116 -0.63282 0.744678 + outer loop + vertex -604.113 126.231 348.847 + vertex -604.45 121.938 345.103 + vertex -600.547 122.957 347.081 + endloop + endfacet + facet normal -0.131284 -0.504402 0.85343 + outer loop + vertex -603.26 133.519 353.765 + vertex -604.559 130.292 351.658 + vertex -600.311 127.948 350.926 + endloop + endfacet + facet normal -0.130029 -0.433014 0.891959 + outer loop + vertex -601.845 137.994 356.144 + vertex -603.26 133.519 353.765 + vertex -596.799 131.307 353.633 + endloop + endfacet + facet normal -0.112118 -0.355737 0.927836 + outer loop + vertex -601.089 143.3 358.269 + vertex -601.845 137.994 356.144 + vertex -592.089 135.324 356.299 + endloop + endfacet + facet normal -0.0851615 -0.271463 0.958674 + outer loop + vertex -601.126 149.025 359.887 + vertex -601.089 143.3 358.269 + vertex -592.865 142.086 358.656 + endloop + endfacet + facet normal -0.0585072 -0.193741 0.979307 + outer loop + vertex -601.357 154.74 361.004 + vertex -601.126 149.025 359.887 + vertex -593.217 148.147 360.186 + endloop + endfacet + facet normal -0.0895606 -0.76416 0.638779 + outer loop + vertex -632.144 110.04 315.935 + vertex -640.996 112.963 318.191 + vertex -636.738 111.367 316.879 + endloop + endfacet + facet normal -0.142221 -0.731488 0.666857 + outer loop + vertex -640.996 112.963 318.191 + vertex -651.678 116.471 319.76 + vertex -646.442 114.453 318.663 + endloop + endfacet + facet normal -0.223765 -0.790049 0.570747 + outer loop + vertex -651.678 116.471 319.76 + vertex -661.458 119.756 320.474 + vertex -655.314 117.131 319.249 + endloop + endfacet + facet normal -0.261338 -0.803704 0.534567 + outer loop + vertex -661.458 119.756 320.474 + vertex -671.241 123.287 321 + vertex -665.033 120.439 319.752 + endloop + endfacet + facet normal -0.281816 -0.788044 0.547327 + outer loop + vertex -671.241 123.287 321 + vertex -681.06 126.932 321.191 + vertex -674.62 124.036 320.338 + endloop + endfacet + facet normal -0.302091 -0.785222 0.540525 + outer loop + vertex -681.06 126.932 321.191 + vertex -690.567 130.579 321.177 + vertex -685.298 128.139 320.576 + endloop + endfacet + facet normal -0.362442 -0.795743 0.48521 + outer loop + vertex -720.69 143.354 321.257 + vertex -731.334 148.139 321.153 + vertex -724.593 144.458 320.151 + endloop + endfacet + facet normal -0.377809 -0.798967 0.467881 + outer loop + vertex -731.334 148.139 321.153 + vertex -742.2 153.248 321.103 + vertex -736.304 149.684 319.779 + endloop + endfacet + facet normal -0.39352 -0.793122 0.464864 + outer loop + vertex -742.2 153.248 321.103 + vertex -752.782 158.498 321.103 + vertex -746.597 154.632 319.743 + endloop + endfacet + facet normal -0.402734 -0.778766 0.480967 + outer loop + vertex -752.782 158.498 321.103 + vertex -762.25 163.53 321.323 + vertex -757.747 160.448 320.103 + endloop + endfacet + facet normal -0.423203 -0.782248 0.457152 + outer loop + vertex -762.25 163.53 321.323 + vertex -771.016 168.154 321.12 + vertex -764.133 163.719 319.902 + endloop + endfacet + facet normal -0.439759 -0.775096 0.453693 + outer loop + vertex -771.016 168.154 321.12 + vertex -781.082 173.851 321.095 + vertex -773.999 169.046 319.752 + endloop + endfacet + facet normal -0.450286 -0.754809 0.476977 + outer loop + vertex -781.082 173.851 321.095 + vertex -791.171 179.878 321.108 + vertex -784.947 175.489 320.039 + endloop + endfacet + facet normal -0.481003 -0.764199 0.429693 + outer loop + vertex -791.171 179.878 321.108 + vertex -801.016 186.077 321.113 + vertex -795.598 181.923 319.789 + endloop + endfacet + facet normal -0.503867 -0.756256 0.417367 + outer loop + vertex -801.016 186.077 321.113 + vertex -810.342 192.275 321.084 + vertex -804.757 187.881 319.866 + endloop + endfacet + facet normal -0.532956 -0.750475 0.390827 + outer loop + vertex -810.342 192.275 321.084 + vertex -819.88 199.05 321.088 + vertex -813.847 194.051 319.715 + endloop + endfacet + facet normal -0.548011 -0.725853 0.415718 + outer loop + vertex -819.88 199.05 321.088 + vertex -828.781 205.912 321.335 + vertex -824.139 201.669 320.045 + endloop + endfacet + facet normal -0.583382 -0.730602 0.354805 + outer loop + vertex -828.781 205.912 321.335 + vertex -837.023 212.412 321.168 + vertex -830.047 206.159 319.763 + endloop + endfacet + facet normal -0.597048 -0.712887 0.367867 + outer loop + vertex -837.023 212.412 321.168 + vertex -845.391 219.49 321.303 + vertex -840.264 214.566 320.083 + endloop + endfacet + facet normal -0.627968 -0.704165 0.331373 + outer loop + vertex -845.391 219.49 321.303 + vertex -852.074 225.556 321.53 + vertex -848.628 221.88 320.249 + endloop + endfacet + facet normal -0.416739 -0.459792 0.784168 + outer loop + vertex -850.638 252.531 350.343 + vertex -849.258 255.932 353.07 + vertex -855.281 261.032 352.86 + endloop + endfacet + facet normal -0.350585 -0.409507 0.842255 + outer loop + vertex -849.258 255.932 353.07 + vertex -849.571 261.276 355.538 + vertex -854.029 263.161 354.599 + endloop + endfacet + facet normal -0.278652 -0.335429 0.899912 + outer loop + vertex -849.571 261.276 355.538 + vertex -849.21 266.795 357.707 + vertex -853.795 268.718 357.004 + endloop + endfacet + facet normal -0.235094 -0.263906 0.935459 + outer loop + vertex -849.21 266.795 357.707 + vertex -848.315 272.11 359.432 + vertex -853.757 275.811 359.108 + endloop + endfacet + facet normal -0.185997 -0.20211 0.961539 + outer loop + vertex -848.315 272.11 359.432 + vertex -847.007 276.201 360.544 + vertex -852.709 280.903 360.43 + endloop + endfacet + facet normal -0.658546 -0.672005 0.338713 + outer loop + vertex -856.217 228.996 320.299 + vertex -852.074 225.556 321.53 + vertex -856.976 231.577 323.944 + endloop + endfacet + facet normal -0.43168 -0.603642 -0.670275 + outer loop + vertex -853.478 241.169 300.187 + vertex -855.829 243.402 299.691 + vertex -852.807 242.811 298.277 + endloop + endfacet + facet normal -0.424475 -0.641374 -0.639109 + outer loop + vertex -852.807 242.811 298.277 + vertex -855.829 243.402 299.691 + vertex -855.335 245.01 297.75 + endloop + endfacet + facet normal -0.414809 -0.582814 -0.698757 + outer loop + vertex -851.962 239.462 300.712 + vertex -853.478 241.169 300.187 + vertex -851.424 241.251 298.9 + endloop + endfacet + facet normal -0.39792 -0.622093 -0.674285 + outer loop + vertex -851.424 241.251 298.9 + vertex -853.478 241.169 300.187 + vertex -852.807 242.811 298.277 + endloop + endfacet + facet normal -0.37466 -0.610763 -0.697566 + outer loop + vertex -851.424 241.251 298.9 + vertex -852.807 242.811 298.277 + vertex -850.754 242.423 297.514 + endloop + endfacet + facet normal -0.368933 -0.654494 -0.659944 + outer loop + vertex -850.754 242.423 297.514 + vertex -852.807 242.811 298.277 + vertex -852.693 244.163 296.873 + endloop + endfacet + facet normal -0.418946 -0.636945 -0.647137 + outer loop + vertex -852.807 242.811 298.277 + vertex -855.335 245.01 297.75 + vertex -852.693 244.163 296.873 + endloop + endfacet + facet normal -0.418308 -0.670045 -0.613236 + outer loop + vertex -852.693 244.163 296.873 + vertex -855.335 245.01 297.75 + vertex -855.438 246.348 296.358 + endloop + endfacet + facet normal -0.423988 -0.587931 -0.688891 + outer loop + vertex -851.962 239.462 300.712 + vertex -854.45 239.254 302.42 + vertex -853.478 241.169 300.187 + endloop + endfacet + facet normal -0.440809 -0.610527 -0.657984 + outer loop + vertex -855.829 243.402 299.691 + vertex -853.478 241.169 300.187 + vertex -856.844 241.625 302.02 + endloop + endfacet + facet normal -0.660277 -0.641511 0.39051 + outer loop + vertex -863.607 240.502 327.871 + vertex -868.418 245.187 327.43 + vertex -863.66 237.604 323.019 + endloop + endfacet + facet normal -0.666582 -0.640317 0.381658 + outer loop + vertex -863.66 237.604 323.019 + vertex -868.418 245.187 327.43 + vertex -868.305 242.258 322.715 + endloop + endfacet + facet normal -0.603221 -0.586634 0.540356 + outer loop + vertex -862.456 246.355 336.263 + vertex -867.694 251.155 335.626 + vertex -863.135 243.187 332.065 + endloop + endfacet + facet normal -0.612696 -0.587042 0.529136 + outer loop + vertex -863.135 243.187 332.065 + vertex -867.694 251.155 335.626 + vertex -868.188 248.127 331.696 + endloop + endfacet + facet normal -0.478455 -0.4482 0.755115 + outer loop + vertex -860.108 265.353 352.591 + vertex -864.516 269.255 352.114 + vertex -860.154 260.501 349.682 + endloop + endfacet + facet normal -0.481085 -0.448926 0.753009 + outer loop + vertex -860.154 260.501 349.682 + vertex -864.516 269.255 352.114 + vertex -865.159 265.15 349.256 + endloop + endfacet + facet normal -0.422368 -0.392661 0.816959 + outer loop + vertex -858.809 268.997 355.014 + vertex -863.84 273.631 354.64 + vertex -860.108 265.353 352.591 + endloop + endfacet + facet normal -0.438968 -0.397394 0.805845 + outer loop + vertex -860.108 265.353 352.591 + vertex -863.84 273.631 354.64 + vertex -864.516 269.255 352.114 + endloop + endfacet + facet normal -0.370974 -0.334907 0.86615 + outer loop + vertex -858.301 274.21 357.247 + vertex -863.067 278.33 356.799 + vertex -858.809 268.997 355.014 + endloop + endfacet + facet normal -0.373548 -0.335803 0.864695 + outer loop + vertex -858.809 268.997 355.014 + vertex -863.067 278.33 356.799 + vertex -863.84 273.631 354.64 + endloop + endfacet + facet normal -0.301434 -0.265758 0.915702 + outer loop + vertex -858.206 279.747 358.886 + vertex -862.444 283.414 358.555 + vertex -858.301 274.21 357.247 + endloop + endfacet + facet normal -0.321748 -0.273586 0.906438 + outer loop + vertex -858.301 274.21 357.247 + vertex -862.444 283.414 358.555 + vertex -863.067 278.33 356.799 + endloop + endfacet + facet normal -0.244637 -0.211902 0.946176 + outer loop + vertex -856.983 283.585 360.061 + vertex -861.801 288.227 359.855 + vertex -858.206 279.747 358.886 + endloop + endfacet + facet normal -0.262713 -0.218829 0.939732 + outer loop + vertex -858.206 279.747 358.886 + vertex -861.801 288.227 359.855 + vertex -862.444 283.414 358.555 + endloop + endfacet + facet normal -0.199392 -0.172804 0.964563 + outer loop + vertex -856.941 288.325 360.919 + vertex -861.236 292.315 360.746 + vertex -856.983 283.585 360.061 + endloop + endfacet + facet normal -0.214169 -0.179656 0.960133 + outer loop + vertex -856.983 283.585 360.061 + vertex -861.236 292.315 360.746 + vertex -861.801 288.227 359.855 + endloop + endfacet + facet normal -0.509611 -0.624346 -0.592022 + outer loop + vertex -858.943 246.192 299.233 + vertex -862.979 249.614 299.098 + vertex -858.672 247.821 297.281 + endloop + endfacet + facet normal -0.508735 -0.649427 -0.565185 + outer loop + vertex -858.672 247.821 297.281 + vertex -862.979 249.614 299.098 + vertex -862.594 251.328 296.782 + endloop + endfacet + facet normal -0.463321 -0.621047 -0.632167 + outer loop + vertex -855.829 243.402 299.691 + vertex -858.943 246.192 299.233 + vertex -855.335 245.01 297.75 + endloop + endfacet + facet normal -0.461345 -0.648508 -0.605473 + outer loop + vertex -855.335 245.01 297.75 + vertex -858.943 246.192 299.233 + vertex -858.672 247.821 297.281 + endloop + endfacet + facet normal -0.467716 -0.654215 -0.594344 + outer loop + vertex -855.335 245.01 297.75 + vertex -858.672 247.821 297.281 + vertex -855.438 246.348 296.358 + endloop + endfacet + facet normal -0.470514 -0.681771 -0.560183 + outer loop + vertex -855.438 246.348 296.358 + vertex -858.672 247.821 297.281 + vertex -858.709 249.031 295.84 + endloop + endfacet + facet normal -0.521424 -0.66013 -0.540689 + outer loop + vertex -858.672 247.821 297.281 + vertex -862.594 251.328 296.782 + vertex -858.709 249.031 295.84 + endloop + endfacet + facet normal -0.527865 -0.689233 -0.496303 + outer loop + vertex -858.709 249.031 295.84 + vertex -862.594 251.328 296.782 + vertex -861.956 251.929 295.269 + endloop + endfacet + facet normal -0.465558 -0.622963 -0.628628 + outer loop + vertex -855.829 243.402 299.691 + vertex -859.774 244.473 301.552 + vertex -858.943 246.192 299.233 + endloop + endfacet + facet normal -0.500845 -0.614694 -0.609348 + outer loop + vertex -862.979 249.614 299.098 + vertex -858.943 246.192 299.233 + vertex -862.725 247.434 301.088 + endloop + endfacet + facet normal -0.68626 -0.625167 0.371771 + outer loop + vertex -868.418 245.187 327.43 + vertex -873.258 250.415 327.288 + vertex -868.305 242.258 322.715 + endloop + endfacet + facet normal -0.682594 -0.625957 0.377152 + outer loop + vertex -868.305 242.258 322.715 + vertex -873.258 250.415 327.288 + vertex -873.54 247.93 322.652 + endloop + endfacet + facet normal -0.631845 -0.573663 0.521232 + outer loop + vertex -867.694 251.155 335.626 + vertex -872.497 256.258 335.421 + vertex -868.188 248.127 331.696 + endloop + endfacet + facet normal -0.633951 -0.573624 0.518712 + outer loop + vertex -868.188 248.127 331.696 + vertex -872.497 256.258 335.421 + vertex -872.937 253.231 331.536 + endloop + endfacet + facet normal -0.500313 -0.440589 0.745365 + outer loop + vertex -864.516 269.255 352.114 + vertex -869.143 274.187 351.924 + vertex -865.159 265.15 349.256 + endloop + endfacet + facet normal -0.502864 -0.441115 0.743334 + outer loop + vertex -865.159 265.15 349.256 + vertex -869.143 274.187 351.924 + vertex -869.844 270.147 349.052 + endloop + endfacet + facet normal -0.450375 -0.393184 0.801604 + outer loop + vertex -863.84 273.631 354.64 + vertex -868.438 278.537 354.463 + vertex -864.516 269.255 352.114 + endloop + endfacet + facet normal -0.452636 -0.393747 0.800052 + outer loop + vertex -864.516 269.255 352.114 + vertex -868.438 278.537 354.463 + vertex -869.143 274.187 351.924 + endloop + endfacet + facet normal -0.384877 -0.332279 0.861081 + outer loop + vertex -863.067 278.33 356.799 + vertex -867.679 283.238 356.631 + vertex -863.84 273.631 354.64 + endloop + endfacet + facet normal -0.388785 -0.333387 0.858894 + outer loop + vertex -863.84 273.631 354.64 + vertex -867.679 283.238 356.631 + vertex -868.438 278.537 354.463 + endloop + endfacet + facet normal -0.324873 -0.272891 0.905532 + outer loop + vertex -862.444 283.414 358.555 + vertex -866.873 288.159 358.396 + vertex -863.067 278.33 356.799 + endloop + endfacet + facet normal -0.322584 -0.272172 0.906566 + outer loop + vertex -863.067 278.33 356.799 + vertex -866.873 288.159 358.396 + vertex -867.679 283.238 356.631 + endloop + endfacet + facet normal -0.261511 -0.219066 0.940012 + outer loop + vertex -861.801 288.227 359.855 + vertex -866.073 292.777 359.727 + vertex -862.444 283.414 358.555 + endloop + endfacet + facet normal -0.27221 -0.222723 0.936107 + outer loop + vertex -862.444 283.414 358.555 + vertex -866.073 292.777 359.727 + vertex -866.873 288.159 358.396 + endloop + endfacet + facet normal -0.216882 -0.179168 0.959615 + outer loop + vertex -861.236 292.315 360.746 + vertex -865.624 297.076 360.643 + vertex -861.801 288.227 359.855 + endloop + endfacet + facet normal -0.221585 -0.181073 0.958182 + outer loop + vertex -861.801 288.227 359.855 + vertex -865.624 297.076 360.643 + vertex -866.073 292.777 359.727 + endloop + endfacet + facet normal -0.569529 -0.652859 -0.499411 + outer loop + vertex -861.956 251.929 295.269 + vertex -862.594 251.328 296.782 + vertex -867.002 255.942 295.777 + endloop + endfacet + facet normal -0.559334 -0.61913 -0.551202 + outer loop + vertex -862.979 249.614 299.098 + vertex -867.87 254.196 298.914 + vertex -862.594 251.328 296.782 + endloop + endfacet + facet normal -0.560617 -0.647891 -0.5157 + outer loop + vertex -867.87 254.196 298.914 + vertex -867.002 255.942 295.777 + vertex -862.594 251.328 296.782 + endloop + endfacet + facet normal -0.545577 -0.605568 -0.579338 + outer loop + vertex -862.979 249.614 299.098 + vertex -868.28 251.043 302.596 + vertex -867.87 254.196 298.914 + endloop + endfacet + facet normal -0.707985 -0.603565 0.366697 + outer loop + vertex -873.258 250.415 327.288 + vertex -878.441 256.492 327.285 + vertex -873.54 247.93 322.652 + endloop + endfacet + facet normal -0.706106 -0.60403 0.369544 + outer loop + vertex -873.54 247.93 322.652 + vertex -878.441 256.492 327.285 + vertex -878.994 254.31 322.66 + endloop + endfacet + facet normal -0.65634 -0.557319 0.508539 + outer loop + vertex -872.497 256.258 335.421 + vertex -877.442 262.087 335.427 + vertex -872.937 253.231 331.536 + endloop + endfacet + facet normal -0.655037 -0.557369 0.510163 + outer loop + vertex -872.937 253.231 331.536 + vertex -877.442 262.087 335.427 + vertex -877.934 259.105 331.538 + endloop + endfacet + facet normal -0.520745 -0.432737 0.73591 + outer loop + vertex -869.143 274.187 351.924 + vertex -873.982 280.019 351.929 + vertex -869.844 270.147 349.052 + endloop + endfacet + facet normal -0.515843 -0.431839 0.739879 + outer loop + vertex -869.844 270.147 349.052 + vertex -873.982 280.019 351.929 + vertex -874.757 276.018 349.053 + endloop + endfacet + facet normal -0.470899 -0.386637 0.792948 + outer loop + vertex -868.438 278.537 354.463 + vertex -873.205 284.351 354.467 + vertex -869.143 274.187 351.924 + endloop + endfacet + facet normal -0.462968 -0.384849 0.798468 + outer loop + vertex -869.143 274.187 351.924 + vertex -873.205 284.351 354.467 + vertex -873.982 280.019 351.929 + endloop + endfacet + facet normal -0.403792 -0.328614 0.853794 + outer loop + vertex -867.679 283.238 356.631 + vertex -872.394 289.046 356.637 + vertex -868.438 278.537 354.463 + endloop + endfacet + facet normal -0.39836 -0.327207 0.856881 + outer loop + vertex -868.438 278.537 354.463 + vertex -872.394 289.046 356.637 + vertex -873.205 284.351 354.467 + endloop + endfacet + facet normal -0.336351 -0.268511 0.902646 + outer loop + vertex -866.873 288.159 358.396 + vertex -871.51 293.995 358.404 + vertex -867.679 283.238 356.631 + endloop + endfacet + facet normal -0.32615 -0.265634 0.907229 + outer loop + vertex -867.679 283.238 356.631 + vertex -871.51 293.995 358.404 + vertex -872.394 289.046 356.637 + endloop + endfacet + facet normal -0.282766 -0.220167 0.933579 + outer loop + vertex -866.073 292.777 359.727 + vertex -870.502 298.546 359.746 + vertex -866.873 288.159 358.396 + endloop + endfacet + facet normal -0.270976 -0.216609 0.937898 + outer loop + vertex -866.873 288.159 358.396 + vertex -870.502 298.546 359.746 + vertex -871.51 293.995 358.404 + endloop + endfacet + facet normal -0.225903 -0.180432 0.957294 + outer loop + vertex -865.624 297.076 360.643 + vertex -869.278 301.111 360.542 + vertex -866.073 292.777 359.727 + endloop + endfacet + facet normal -0.235222 -0.183735 0.954417 + outer loop + vertex -866.073 292.777 359.727 + vertex -869.278 301.111 360.542 + vertex -870.502 298.546 359.746 + endloop + endfacet + facet normal -0.733316 -0.57679 0.359946 + outer loop + vertex -878.441 256.492 327.285 + vertex -883.597 263.06 327.305 + vertex -878.994 254.31 322.66 + endloop + endfacet + facet normal -0.736282 -0.575887 0.355306 + outer loop + vertex -878.994 254.31 322.66 + vertex -883.597 263.06 327.305 + vertex -884.146 260.897 322.66 + endloop + endfacet + facet normal -0.681892 -0.536297 0.497402 + outer loop + vertex -877.442 262.087 335.427 + vertex -882.489 268.558 335.485 + vertex -877.934 259.105 331.538 + endloop + endfacet + facet normal -0.680985 -0.536353 0.498582 + outer loop + vertex -877.934 259.105 331.538 + vertex -882.489 268.558 335.485 + vertex -883.03 265.61 331.575 + endloop + endfacet + facet normal -0.542808 -0.418284 0.728284 + outer loop + vertex -873.982 280.019 351.929 + vertex -878.912 286.542 352.001 + vertex -874.757 276.018 349.053 + endloop + endfacet + facet normal -0.536429 -0.41725 0.733585 + outer loop + vertex -874.757 276.018 349.053 + vertex -878.912 286.542 352.001 + vertex -879.751 282.566 349.126 + endloop + endfacet + facet normal -0.489145 -0.373991 0.787952 + outer loop + vertex -873.205 284.351 354.467 + vertex -878.046 290.829 354.537 + vertex -873.982 280.019 351.929 + endloop + endfacet + facet normal -0.481057 -0.372336 0.793694 + outer loop + vertex -873.982 280.019 351.929 + vertex -878.046 290.829 354.537 + vertex -878.912 286.542 352.001 + endloop + endfacet + facet normal -0.422588 -0.319059 0.848305 + outer loop + vertex -872.394 289.046 356.637 + vertex -877.15 295.509 356.699 + vertex -873.205 284.351 354.467 + endloop + endfacet + facet normal -0.410951 -0.31629 0.855032 + outer loop + vertex -873.205 284.351 354.467 + vertex -877.15 295.509 356.699 + vertex -878.046 290.829 354.537 + endloop + endfacet + facet normal -0.347334 -0.259651 0.901077 + outer loop + vertex -871.51 293.995 358.404 + vertex -876.215 300.51 358.467 + vertex -872.394 289.046 356.637 + endloop + endfacet + facet normal -0.337678 -0.257133 0.905459 + outer loop + vertex -872.394 289.046 356.637 + vertex -876.215 300.51 358.467 + vertex -877.15 295.509 356.699 + endloop + endfacet + facet normal -0.291452 -0.210658 0.933102 + outer loop + vertex -870.502 298.546 359.746 + vertex -875.197 305.369 359.82 + vertex -871.51 293.995 358.404 + endloop + endfacet + facet normal -0.271098 -0.204977 0.940474 + outer loop + vertex -871.51 293.995 358.404 + vertex -875.197 305.369 359.82 + vertex -876.215 300.51 358.467 + endloop + endfacet + facet normal -0.252463 -0.174674 0.95171 + outer loop + vertex -869.278 301.111 360.542 + vertex -873.922 309.224 360.799 + vertex -870.502 298.546 359.746 + endloop + endfacet + facet normal -0.228753 -0.16779 0.958915 + outer loop + vertex -870.502 298.546 359.746 + vertex -873.922 309.224 360.799 + vertex -875.197 305.369 359.82 + endloop + endfacet + facet normal -0.76652 -0.542688 0.343419 + outer loop + vertex -883.597 263.06 327.305 + vertex -888.417 269.871 327.309 + vertex -884.146 260.897 322.66 + endloop + endfacet + facet normal -0.771661 -0.540722 0.334902 + outer loop + vertex -884.146 260.897 322.66 + vertex -888.417 269.871 327.309 + vertex -888.931 267.721 322.654 + endloop + endfacet + facet normal -0.741512 -0.528106 0.41384 + outer loop + vertex -883.03 265.61 331.575 + vertex -887.874 272.424 331.591 + vertex -883.597 263.06 327.305 + endloop + endfacet + facet normal -0.744789 -0.527342 0.408901 + outer loop + vertex -883.597 263.06 327.305 + vertex -887.874 272.424 331.591 + vertex -888.417 269.871 327.309 + endloop + endfacet + facet normal -0.713166 -0.508769 0.482232 + outer loop + vertex -882.489 268.558 335.485 + vertex -887.332 275.375 335.515 + vertex -883.03 265.61 331.575 + endloop + endfacet + facet normal -0.713959 -0.508682 0.48115 + outer loop + vertex -883.03 265.61 331.575 + vertex -887.332 275.375 335.515 + vertex -887.874 272.424 331.591 + endloop + endfacet + facet normal -0.570673 -0.398688 0.717899 + outer loop + vertex -878.912 286.542 352.001 + vertex -883.608 293.343 352.045 + vertex -879.751 282.566 349.126 + endloop + endfacet + facet normal -0.561115 -0.397477 0.72606 + outer loop + vertex -879.751 282.566 349.126 + vertex -883.608 293.343 352.045 + vertex -884.508 289.38 349.18 + endloop + endfacet + facet normal -0.514487 -0.357214 0.779552 + outer loop + vertex -878.046 290.829 354.537 + vertex -882.672 297.592 354.583 + vertex -878.912 286.542 352.001 + endloop + endfacet + facet normal -0.508533 -0.356206 0.783908 + outer loop + vertex -878.912 286.542 352.001 + vertex -882.672 297.592 354.583 + vertex -883.608 293.343 352.045 + endloop + endfacet + facet normal -0.443482 -0.304494 0.842975 + outer loop + vertex -877.15 295.509 356.699 + vertex -881.679 302.219 356.74 + vertex -878.046 290.829 354.537 + endloop + endfacet + facet normal -0.433861 -0.302526 0.848671 + outer loop + vertex -878.046 290.829 354.537 + vertex -881.679 302.219 356.74 + vertex -882.672 297.592 354.583 + endloop + endfacet + facet normal -0.365986 -0.248764 0.896756 + outer loop + vertex -876.215 300.51 358.467 + vertex -880.669 307.19 358.503 + vertex -877.15 295.509 356.699 + endloop + endfacet + facet normal -0.357514 -0.246821 0.900702 + outer loop + vertex -877.15 295.509 356.699 + vertex -880.669 307.19 358.503 + vertex -881.679 302.219 356.74 + endloop + endfacet + facet normal -0.295554 -0.198203 0.934539 + outer loop + vertex -875.197 305.369 359.82 + vertex -879.667 312.147 359.844 + vertex -876.215 300.51 358.467 + endloop + endfacet + facet normal -0.286308 -0.195859 0.937906 + outer loop + vertex -876.215 300.51 358.467 + vertex -879.667 312.147 359.844 + vertex -880.669 307.19 358.503 + endloop + endfacet + facet normal -0.24521 -0.161581 0.95591 + outer loop + vertex -873.922 309.224 360.799 + vertex -878.727 316.32 360.766 + vertex -875.197 305.369 359.82 + endloop + endfacet + facet normal -0.235553 -0.158719 0.958813 + outer loop + vertex -875.197 305.369 359.82 + vertex -878.727 316.32 360.766 + vertex -879.667 312.147 359.844 + endloop + endfacet + facet normal -0.724293 -0.548302 -0.41805 + outer loop + vertex -878.537 266.436 298.07 + vertex -883.573 273.292 297.802 + vertex -878.427 268.758 294.833 + endloop + endfacet + facet normal -0.723939 -0.54307 -0.425425 + outer loop + vertex -878.427 268.758 294.833 + vertex -883.573 273.292 297.802 + vertex -883.384 275.562 294.583 + endloop + endfacet + facet normal -0.69307 -0.522612 -0.496518 + outer loop + vertex -879.531 264.02 301.999 + vertex -884.551 270.877 301.79 + vertex -878.537 266.436 298.07 + endloop + endfacet + facet normal -0.693314 -0.528354 -0.490058 + outer loop + vertex -878.537 266.436 298.07 + vertex -884.551 270.877 301.79 + vertex -883.573 273.292 297.802 + endloop + endfacet + facet normal -0.804203 -0.500819 0.320058 + outer loop + vertex -888.417 269.871 327.309 + vertex -892.807 276.916 327.303 + vertex -888.931 267.721 322.654 + endloop + endfacet + facet normal -0.807276 -0.499345 0.31458 + outer loop + vertex -888.931 267.721 322.654 + vertex -892.807 276.916 327.303 + vertex -893.336 274.838 322.648 + endloop + endfacet + facet normal -0.78011 -0.488857 0.390445 + outer loop + vertex -887.874 272.424 331.591 + vertex -892.272 279.44 331.587 + vertex -888.417 269.871 327.309 + endloop + endfacet + facet normal -0.783404 -0.487807 0.385127 + outer loop + vertex -888.417 269.871 327.309 + vertex -892.272 279.44 331.587 + vertex -892.807 276.916 327.303 + endloop + endfacet + facet normal -0.751434 -0.473298 0.459713 + outer loop + vertex -887.332 275.375 335.515 + vertex -891.741 282.377 335.517 + vertex -887.874 272.424 331.591 + endloop + endfacet + facet normal -0.754459 -0.472738 0.455314 + outer loop + vertex -887.874 272.424 331.591 + vertex -891.741 282.377 335.517 + vertex -892.272 279.44 331.587 + endloop + endfacet + facet normal -0.726758 -0.455521 0.514124 + outer loop + vertex -886.763 278.613 339.188 + vertex -891.152 285.615 339.187 + vertex -887.332 275.375 335.515 + endloop + endfacet + facet normal -0.723674 -0.455827 0.518187 + outer loop + vertex -887.332 275.375 335.515 + vertex -891.152 285.615 339.187 + vertex -891.741 282.377 335.517 + endloop + endfacet + facet normal -0.70021 -0.438531 0.56338 + outer loop + vertex -886.102 282.053 342.688 + vertex -890.469 289.03 342.69 + vertex -886.763 278.613 339.188 + endloop + endfacet + facet normal -0.699708 -0.438556 0.563984 + outer loop + vertex -886.763 278.613 339.188 + vertex -890.469 289.03 342.69 + vertex -891.152 285.615 339.187 + endloop + endfacet + facet normal -0.675111 -0.422072 0.605046 + outer loop + vertex -885.342 285.636 346.034 + vertex -889.68 292.581 346.039 + vertex -886.102 282.053 342.688 + endloop + endfacet + facet normal -0.67391 -0.422086 0.606373 + outer loop + vertex -886.102 282.053 342.688 + vertex -889.68 292.581 346.039 + vertex -890.469 289.03 342.69 + endloop + endfacet + facet normal -0.645487 -0.40185 0.64951 + outer loop + vertex -884.508 289.38 349.18 + vertex -888.804 296.286 349.184 + vertex -885.342 285.636 346.034 + endloop + endfacet + facet normal -0.642547 -0.401769 0.652468 + outer loop + vertex -885.342 285.636 346.034 + vertex -888.804 296.286 349.184 + vertex -889.68 292.581 346.039 + endloop + endfacet + facet normal -0.601797 -0.373634 0.705859 + outer loop + vertex -883.608 293.343 352.045 + vertex -887.862 300.207 352.051 + vertex -884.508 289.38 349.18 + endloop + endfacet + facet normal -0.59983 -0.373489 0.707608 + outer loop + vertex -884.508 289.38 349.18 + vertex -887.862 300.207 352.051 + vertex -888.804 296.286 349.184 + endloop + endfacet + facet normal -0.548859 -0.336211 0.765321 + outer loop + vertex -882.672 297.592 354.583 + vertex -886.855 304.419 354.582 + vertex -883.608 293.343 352.045 + endloop + endfacet + facet normal -0.539518 -0.335099 0.772418 + outer loop + vertex -883.608 293.343 352.045 + vertex -886.855 304.419 354.582 + vertex -887.862 300.207 352.051 + endloop + endfacet + facet normal -0.47294 -0.286872 0.833086 + outer loop + vertex -881.679 302.219 356.74 + vertex -885.775 308.976 356.741 + vertex -882.672 297.592 354.583 + endloop + endfacet + facet normal -0.466764 -0.28591 0.836891 + outer loop + vertex -882.672 297.592 354.583 + vertex -885.775 308.976 356.741 + vertex -886.855 304.419 354.582 + endloop + endfacet + facet normal -0.39291 -0.235456 0.888922 + outer loop + vertex -880.669 307.19 358.503 + vertex -884.654 313.816 358.497 + vertex -881.679 302.219 356.74 + endloop + endfacet + facet normal -0.386031 -0.234197 0.892262 + outer loop + vertex -881.679 302.219 356.74 + vertex -884.654 313.816 358.497 + vertex -885.775 308.976 356.741 + endloop + endfacet + facet normal -0.3162 -0.187665 0.929946 + outer loop + vertex -879.667 312.147 359.844 + vertex -883.592 318.7 359.832 + vertex -880.669 307.19 358.503 + endloop + endfacet + facet normal -0.312071 -0.186798 0.931514 + outer loop + vertex -880.669 307.19 358.503 + vertex -883.592 318.7 359.832 + vertex -884.654 313.816 358.497 + endloop + endfacet + facet normal -0.260568 -0.151893 0.953432 + outer loop + vertex -878.727 316.32 360.766 + vertex -882.665 322.941 360.744 + vertex -879.667 312.147 359.844 + endloop + endfacet + facet normal -0.253628 -0.150145 0.955578 + outer loop + vertex -879.667 312.147 359.844 + vertex -882.665 322.941 360.744 + vertex -883.592 318.7 359.832 + endloop + endfacet + facet normal -0.841698 -0.45099 0.296907 + outer loop + vertex -892.807 276.916 327.303 + vertex -896.734 284.241 327.295 + vertex -893.336 274.838 322.648 + endloop + endfacet + facet normal -0.843751 -0.44976 0.292918 + outer loop + vertex -893.336 274.838 322.648 + vertex -896.734 284.241 327.295 + vertex -897.284 282.241 322.64 + endloop + endfacet + facet normal -0.819448 -0.443245 0.363371 + outer loop + vertex -892.272 279.44 331.587 + vertex -896.195 286.688 331.583 + vertex -892.807 276.916 327.303 + endloop + endfacet + facet normal -0.82387 -0.441364 0.355578 + outer loop + vertex -892.807 276.916 327.303 + vertex -896.195 286.688 331.583 + vertex -896.734 284.241 327.295 + endloop + endfacet + facet normal -0.795147 -0.429273 0.428329 + outer loop + vertex -891.741 282.377 335.517 + vertex -895.639 289.587 335.506 + vertex -892.272 279.44 331.587 + endloop + endfacet + facet normal -0.794186 -0.429539 0.429843 + outer loop + vertex -892.272 279.44 331.587 + vertex -895.639 289.587 335.506 + vertex -896.195 286.688 331.583 + endloop + endfacet + facet normal -0.766619 -0.415529 0.489521 + outer loop + vertex -891.152 285.615 339.187 + vertex -895.041 292.777 339.177 + vertex -891.741 282.377 335.517 + endloop + endfacet + facet normal -0.769063 -0.415084 0.486054 + outer loop + vertex -891.741 282.377 335.517 + vertex -895.041 292.777 339.177 + vertex -895.639 289.587 335.506 + endloop + endfacet + facet normal -0.743175 -0.400864 0.535723 + outer loop + vertex -890.469 289.03 342.69 + vertex -894.322 296.153 342.676 + vertex -891.152 285.615 339.187 + endloop + endfacet + facet normal -0.740377 -0.401215 0.539322 + outer loop + vertex -891.152 285.615 339.187 + vertex -894.322 296.153 342.676 + vertex -895.041 292.777 339.177 + endloop + endfacet + facet normal -0.718446 -0.386025 0.578636 + outer loop + vertex -889.68 292.581 346.039 + vertex -893.494 299.653 346.022 + vertex -890.469 289.03 342.69 + endloop + endfacet + facet normal -0.716255 -0.386212 0.581222 + outer loop + vertex -890.469 289.03 342.69 + vertex -893.494 299.653 346.022 + vertex -894.322 296.153 342.676 + endloop + endfacet + facet normal -0.687472 -0.3685 0.625771 + outer loop + vertex -888.804 296.286 349.184 + vertex -892.578 303.297 349.166 + vertex -889.68 292.581 346.039 + endloop + endfacet + facet normal -0.686262 -0.368551 0.627068 + outer loop + vertex -889.68 292.581 346.039 + vertex -892.578 303.297 349.166 + vertex -893.494 299.653 346.022 + endloop + endfacet + facet normal -0.645391 -0.343871 0.682073 + outer loop + vertex -887.862 300.207 352.051 + vertex -891.586 307.155 352.03 + vertex -888.804 296.286 349.184 + endloop + endfacet + facet normal -0.641954 -0.343842 0.685324 + outer loop + vertex -888.804 296.286 349.184 + vertex -891.586 307.155 352.03 + vertex -892.578 303.297 349.166 + endloop + endfacet + facet normal -0.584742 -0.310481 0.749452 + outer loop + vertex -886.855 304.419 354.582 + vertex -890.532 311.301 354.564 + vertex -887.862 300.207 352.051 + endloop + endfacet + facet normal -0.583333 -0.310398 0.750583 + outer loop + vertex -887.862 300.207 352.051 + vertex -890.532 311.301 354.564 + vertex -891.586 307.155 352.03 + endloop + endfacet + facet normal -0.509655 -0.266789 0.81797 + outer loop + vertex -885.775 308.976 356.741 + vertex -889.375 315.796 356.723 + vertex -886.855 304.419 354.582 + endloop + endfacet + facet normal -0.501884 -0.266016 0.823012 + outer loop + vertex -886.855 304.419 354.582 + vertex -889.375 315.796 356.723 + vertex -890.532 311.301 354.564 + endloop + endfacet + facet normal -0.426075 -0.21961 0.877628 + outer loop + vertex -884.654 313.816 358.497 + vertex -888.136 320.498 358.478 + vertex -885.775 308.976 356.741 + endloop + endfacet + facet normal -0.418855 -0.218688 0.881327 + outer loop + vertex -885.775 308.976 356.741 + vertex -888.136 320.498 358.478 + vertex -889.375 315.796 356.723 + endloop + endfacet + facet normal -0.344049 -0.17726 0.922068 + outer loop + vertex -883.592 318.7 359.832 + vertex -886.923 324.974 359.795 + vertex -884.654 313.816 358.497 + endloop + endfacet + facet normal -0.345448 -0.177479 0.921503 + outer loop + vertex -884.654 313.816 358.497 + vertex -886.923 324.974 359.795 + vertex -888.136 320.498 358.478 + endloop + endfacet + facet normal -0.281562 -0.142602 0.948887 + outer loop + vertex -882.665 322.941 360.744 + vertex -886.012 329.298 360.706 + vertex -883.592 318.7 359.832 + endloop + endfacet + facet normal -0.277555 -0.141794 0.950188 + outer loop + vertex -883.592 318.7 359.832 + vertex -886.012 329.298 360.706 + vertex -886.923 324.974 359.795 + endloop + endfacet + facet normal -0.876471 -0.396078 0.273716 + outer loop + vertex -896.734 284.241 327.295 + vertex -900.172 291.846 327.29 + vertex -897.284 282.241 322.64 + endloop + endfacet + facet normal -0.88032 -0.393202 0.265385 + outer loop + vertex -897.284 282.241 322.64 + vertex -900.172 291.846 327.29 + vertex -900.729 289.949 322.635 + endloop + endfacet + facet normal -0.859394 -0.389959 0.330717 + outer loop + vertex -896.195 286.688 331.583 + vertex -899.612 294.215 331.577 + vertex -896.734 284.241 327.295 + endloop + endfacet + facet normal -0.861017 -0.389062 0.327537 + outer loop + vertex -896.734 284.241 327.295 + vertex -899.612 294.215 331.577 + vertex -900.172 291.846 327.29 + endloop + endfacet + facet normal -0.833402 -0.381483 0.39989 + outer loop + vertex -895.639 289.587 335.506 + vertex -899.046 297.03 335.506 + vertex -896.195 286.688 331.583 + endloop + endfacet + facet normal -0.837436 -0.379935 0.392874 + outer loop + vertex -896.195 286.688 331.583 + vertex -899.046 297.03 335.506 + vertex -899.612 294.215 331.577 + endloop + endfacet + facet normal -0.8117 -0.368882 0.452845 + outer loop + vertex -895.041 292.777 339.177 + vertex -898.404 300.167 339.169 + vertex -895.639 289.587 335.506 + endloop + endfacet + facet normal -0.808069 -0.369886 0.458486 + outer loop + vertex -895.639 289.587 335.506 + vertex -898.404 300.167 339.169 + vertex -899.046 297.03 335.506 + endloop + endfacet + facet normal -0.784331 -0.357975 0.506635 + outer loop + vertex -894.322 296.153 342.676 + vertex -897.668 303.474 342.668 + vertex -895.041 292.777 339.177 + endloop + endfacet + facet normal -0.786729 -0.357464 0.503266 + outer loop + vertex -895.041 292.777 339.177 + vertex -897.668 303.474 342.668 + vertex -898.404 300.167 339.169 + endloop + endfacet + facet normal -0.76044 -0.34568 0.549761 + outer loop + vertex -893.494 299.653 346.022 + vertex -896.801 306.91 346.011 + vertex -894.322 296.153 342.676 + endloop + endfacet + facet normal -0.758306 -0.346031 0.552481 + outer loop + vertex -894.322 296.153 342.676 + vertex -896.801 306.91 346.011 + vertex -897.668 303.474 342.668 + endloop + endfacet + facet normal -0.730527 -0.331509 0.597019 + outer loop + vertex -892.578 303.297 349.166 + vertex -895.848 310.48 349.153 + vertex -893.494 299.653 346.022 + endloop + endfacet + facet normal -0.729722 -0.331604 0.597951 + outer loop + vertex -893.494 299.653 346.022 + vertex -895.848 310.48 349.153 + vertex -896.801 306.91 346.011 + endloop + endfacet + facet normal -0.687211 -0.310865 0.656585 + outer loop + vertex -891.586 307.155 352.03 + vertex -894.811 314.253 352.015 + vertex -892.578 303.297 349.166 + endloop + endfacet + facet normal -0.685631 -0.310961 0.65819 + outer loop + vertex -892.578 303.297 349.166 + vertex -894.811 314.253 352.015 + vertex -895.848 310.48 349.153 + endloop + endfacet + facet normal -0.627958 -0.283316 0.724846 + outer loop + vertex -890.532 311.301 354.564 + vertex -893.709 318.306 354.55 + vertex -891.586 307.155 352.03 + endloop + endfacet + facet normal -0.626901 -0.283321 0.725757 + outer loop + vertex -891.586 307.155 352.03 + vertex -893.709 318.306 354.55 + vertex -894.811 314.253 352.015 + endloop + endfacet + facet normal -0.546359 -0.244093 0.801193 + outer loop + vertex -889.375 315.796 356.723 + vertex -892.492 322.727 356.708 + vertex -890.532 311.301 354.564 + endloop + endfacet + facet normal -0.541381 -0.243883 0.804629 + outer loop + vertex -890.532 311.301 354.564 + vertex -892.492 322.727 356.708 + vertex -893.709 318.306 354.55 + endloop + endfacet + facet normal -0.461031 -0.201204 0.864273 + outer loop + vertex -888.136 320.498 358.478 + vertex -891.162 327.396 358.47 + vertex -889.375 315.796 356.723 + endloop + endfacet + facet normal -0.449458 -0.200365 0.870541 + outer loop + vertex -889.375 315.796 356.723 + vertex -891.162 327.396 358.47 + vertex -892.492 322.727 356.708 + endloop + endfacet + facet normal -0.384434 -0.163129 0.908625 + outer loop + vertex -886.923 324.974 359.795 + vertex -889.773 331.727 359.802 + vertex -888.136 320.498 358.478 + endloop + endfacet + facet normal -0.371618 -0.161912 0.914158 + outer loop + vertex -888.136 320.498 358.478 + vertex -889.773 331.727 359.802 + vertex -891.162 327.396 358.47 + endloop + endfacet + facet normal -0.304212 -0.134671 0.943037 + outer loop + vertex -886.012 329.298 360.706 + vertex -888.488 334.144 360.6 + vertex -886.923 324.974 359.795 + endloop + endfacet + facet normal -0.323228 -0.137327 0.936304 + outer loop + vertex -886.923 324.974 359.795 + vertex -888.488 334.144 360.6 + vertex -889.773 331.727 359.802 + endloop + endfacet + facet normal -0.909824 -0.334855 0.245136 + outer loop + vertex -900.172 291.846 327.29 + vertex -903.064 299.698 327.285 + vertex -900.729 289.949 322.635 + endloop + endfacet + facet normal -0.913988 -0.330913 0.234782 + outer loop + vertex -900.729 289.949 322.635 + vertex -903.064 299.698 327.285 + vertex -903.61 297.912 322.641 + endloop + endfacet + facet normal -0.893109 -0.334017 0.301311 + outer loop + vertex -899.612 294.215 331.577 + vertex -902.509 301.962 331.579 + vertex -900.172 291.846 327.29 + endloop + endfacet + facet normal -0.898054 -0.330492 0.290301 + outer loop + vertex -900.172 291.846 327.29 + vertex -902.509 301.962 331.579 + vertex -903.064 299.698 327.285 + endloop + endfacet + facet normal -0.874189 -0.32622 0.359687 + outer loop + vertex -899.046 297.03 335.506 + vertex -901.911 304.705 335.504 + vertex -899.612 294.215 331.577 + endloop + endfacet + facet normal -0.873354 -0.326649 0.361321 + outer loop + vertex -899.612 294.215 331.577 + vertex -901.911 304.705 335.504 + vertex -902.509 301.962 331.579 + endloop + endfacet + facet normal -0.849293 -0.318081 0.421338 + outer loop + vertex -898.404 300.167 339.169 + vertex -901.248 307.761 339.169 + vertex -899.046 297.03 335.506 + endloop + endfacet + facet normal -0.850836 -0.317486 0.418666 + outer loop + vertex -899.046 297.03 335.506 + vertex -901.248 307.761 339.169 + vertex -901.911 304.705 335.504 + endloop + endfacet + facet normal -0.828643 -0.309294 0.466571 + outer loop + vertex -897.668 303.474 342.668 + vertex -900.476 310.993 342.665 + vertex -898.404 300.167 339.169 + endloop + endfacet + facet normal -0.827106 -0.309775 0.468972 + outer loop + vertex -898.404 300.167 339.169 + vertex -900.476 310.993 342.665 + vertex -901.248 307.761 339.169 + endloop + endfacet + facet normal -0.800826 -0.30134 0.517563 + outer loop + vertex -896.801 306.91 346.011 + vertex -899.599 314.345 346.01 + vertex -897.668 303.474 342.668 + endloop + endfacet + facet normal -0.804725 -0.300343 0.512066 + outer loop + vertex -897.668 303.474 342.668 + vertex -899.599 314.345 346.01 + vertex -900.476 310.993 342.665 + endloop + endfacet + facet normal -0.773176 -0.290094 0.563954 + outer loop + vertex -895.848 310.48 349.153 + vertex -898.611 317.835 349.149 + vertex -896.801 306.91 346.011 + endloop + endfacet + facet normal -0.771712 -0.290383 0.565807 + outer loop + vertex -896.801 306.91 346.011 + vertex -898.611 317.835 349.149 + vertex -899.599 314.345 346.01 + endloop + endfacet + facet normal -0.72864 -0.275502 0.627042 + outer loop + vertex -894.811 314.253 352.015 + vertex -897.551 321.504 352.018 + vertex -895.848 310.48 349.153 + endloop + endfacet + facet normal -0.732883 -0.274932 0.62233 + outer loop + vertex -895.848 310.48 349.153 + vertex -897.551 321.504 352.018 + vertex -898.611 317.835 349.149 + endloop + endfacet + facet normal -0.672686 -0.252057 0.695673 + outer loop + vertex -893.709 318.306 354.55 + vertex -896.39 325.446 354.545 + vertex -894.811 314.253 352.015 + endloop + endfacet + facet normal -0.667484 -0.252422 0.700534 + outer loop + vertex -894.811 314.253 352.015 + vertex -896.39 325.446 354.545 + vertex -897.551 321.504 352.018 + endloop + endfacet + facet normal -0.586009 -0.219572 0.779988 + outer loop + vertex -892.492 322.727 356.708 + vertex -895.127 329.748 356.705 + vertex -893.709 318.306 354.55 + endloop + endfacet + facet normal -0.586306 -0.219567 0.779766 + outer loop + vertex -893.709 318.306 354.55 + vertex -895.127 329.748 356.705 + vertex -896.39 325.446 354.545 + endloop + endfacet + facet normal -0.492354 -0.180918 0.851385 + outer loop + vertex -891.162 327.396 358.47 + vertex -893.739 334.381 358.464 + vertex -892.492 322.727 356.708 + endloop + endfacet + facet normal -0.482564 -0.180719 0.857014 + outer loop + vertex -892.492 322.727 356.708 + vertex -893.739 334.381 358.464 + vertex -895.127 329.748 356.705 + endloop + endfacet + facet normal -0.409623 -0.145541 0.90057 + outer loop + vertex -889.773 331.727 359.802 + vertex -892.293 338.961 359.825 + vertex -891.162 327.396 358.47 + endloop + endfacet + facet normal -0.394796 -0.144877 0.907274 + outer loop + vertex -891.162 327.396 358.47 + vertex -892.293 338.961 359.825 + vertex -893.739 334.381 358.464 + endloop + endfacet + facet normal -0.353699 -0.118342 0.927843 + outer loop + vertex -888.488 334.144 360.6 + vertex -890.778 342.661 360.813 + vertex -889.773 331.727 359.802 + endloop + endfacet + facet normal -0.326752 -0.116792 0.937866 + outer loop + vertex -889.773 331.727 359.802 + vertex -890.778 342.661 360.813 + vertex -892.293 338.961 359.825 + endloop + endfacet + facet normal -0.939271 -0.268478 0.213752 + outer loop + vertex -903.064 299.698 327.285 + vertex -905.355 307.709 327.281 + vertex -903.61 297.912 322.641 + endloop + endfacet + facet normal -0.942577 -0.264448 0.203999 + outer loop + vertex -903.61 297.912 322.641 + vertex -905.355 307.709 327.281 + vertex -905.878 306.007 322.653 + endloop + endfacet + facet normal -0.926643 -0.269687 0.26192 + outer loop + vertex -902.509 301.962 331.579 + vertex -904.814 309.878 331.574 + vertex -903.064 299.698 327.285 + endloop + endfacet + facet normal -0.930594 -0.265976 0.251499 + outer loop + vertex -903.064 299.698 327.285 + vertex -904.814 309.878 331.574 + vertex -905.355 307.709 327.281 + endloop + endfacet + facet normal -0.907409 -0.266811 0.324686 + outer loop + vertex -901.911 304.705 335.504 + vertex -904.211 312.525 335.504 + vertex -902.509 301.962 331.579 + endloop + endfacet + facet normal -0.91025 -0.264879 0.318253 + outer loop + vertex -902.509 301.962 331.579 + vertex -904.211 312.525 335.504 + vertex -904.814 309.878 331.574 + endloop + endfacet + facet normal -0.886794 -0.263187 0.379907 + outer loop + vertex -901.248 307.761 339.169 + vertex -903.539 315.489 339.174 + vertex -901.911 304.705 335.504 + endloop + endfacet + facet normal -0.889763 -0.261624 0.373999 + outer loop + vertex -901.911 304.705 335.504 + vertex -903.539 315.489 339.174 + vertex -904.211 312.525 335.504 + endloop + endfacet + facet normal -0.866047 -0.257049 0.428823 + outer loop + vertex -900.476 310.993 342.665 + vertex -902.742 318.633 342.669 + vertex -901.248 307.761 339.169 + endloop + endfacet + facet normal -0.866021 -0.25706 0.428868 + outer loop + vertex -901.248 307.761 339.169 + vertex -902.742 318.633 342.669 + vertex -903.539 315.489 339.174 + endloop + endfacet + facet normal -0.843891 -0.251838 0.473736 + outer loop + vertex -899.599 314.345 346.01 + vertex -901.849 321.891 346.013 + vertex -900.476 310.993 342.665 + endloop + endfacet + facet normal -0.845921 -0.251098 0.470497 + outer loop + vertex -900.476 310.993 342.665 + vertex -901.849 321.891 346.013 + vertex -902.742 318.633 342.669 + endloop + endfacet + facet normal -0.813829 -0.243941 0.527423 + outer loop + vertex -898.611 317.835 349.149 + vertex -900.842 325.284 349.152 + vertex -899.599 314.345 346.01 + endloop + endfacet + facet normal -0.815601 -0.243423 0.524919 + outer loop + vertex -899.599 314.345 346.01 + vertex -900.842 325.284 349.152 + vertex -901.849 321.891 346.013 + endloop + endfacet + facet normal -0.776603 -0.233284 0.585206 + outer loop + vertex -897.551 321.504 352.018 + vertex -899.756 328.849 352.02 + vertex -898.611 317.835 349.149 + endloop + endfacet + facet normal -0.777514 -0.233083 0.584075 + outer loop + vertex -898.611 317.835 349.149 + vertex -899.756 328.849 352.02 + vertex -900.842 325.284 349.152 + endloop + endfacet + facet normal -0.71485 -0.21578 0.665152 + outer loop + vertex -896.39 325.446 354.545 + vertex -898.562 332.658 354.55 + vertex -897.551 321.504 352.018 + endloop + endfacet + facet normal -0.717128 -0.215453 0.662803 + outer loop + vertex -897.551 321.504 352.018 + vertex -898.562 332.658 354.55 + vertex -899.756 328.849 352.02 + endloop + endfacet + facet normal -0.634796 -0.18988 0.748985 + outer loop + vertex -895.127 329.748 356.705 + vertex -897.241 336.81 356.704 + vertex -896.39 325.446 354.545 + endloop + endfacet + facet normal -0.629953 -0.190273 0.752964 + outer loop + vertex -896.39 325.446 354.545 + vertex -897.241 336.81 356.704 + vertex -898.562 332.658 354.55 + endloop + endfacet + facet normal -0.528113 -0.158436 0.834263 + outer loop + vertex -893.739 334.381 358.464 + vertex -895.818 341.317 358.465 + vertex -895.127 329.748 356.705 + endloop + endfacet + facet normal -0.529611 -0.158383 0.833323 + outer loop + vertex -895.127 329.748 356.705 + vertex -895.818 341.317 358.465 + vertex -897.241 336.81 356.704 + endloop + endfacet + facet normal -0.433196 -0.128249 0.892129 + outer loop + vertex -892.293 338.961 359.825 + vertex -894.368 345.903 359.815 + vertex -893.739 334.381 358.464 + endloop + endfacet + facet normal -0.427386 -0.128259 0.894925 + outer loop + vertex -893.739 334.381 358.464 + vertex -894.368 345.903 359.815 + vertex -895.818 341.317 358.465 + endloop + endfacet + facet normal -0.354035 -0.103385 0.9295 + outer loop + vertex -890.778 342.661 360.813 + vertex -893.049 349.866 360.75 + vertex -892.293 338.961 359.825 + endloop + endfacet + facet normal -0.3497 -0.103225 0.931158 + outer loop + vertex -892.293 338.961 359.825 + vertex -893.049 349.866 360.75 + vertex -894.368 345.903 359.815 + endloop + endfacet + facet normal -0.962501 -0.200506 0.182726 + outer loop + vertex -905.355 307.709 327.281 + vertex -907.041 315.806 327.283 + vertex -905.878 306.007 322.653 + endloop + endfacet + facet normal -0.966352 -0.19428 0.16858 + outer loop + vertex -905.878 306.007 322.653 + vertex -907.041 315.806 327.283 + vertex -907.526 314.208 322.663 + endloop + endfacet + facet normal -0.953789 -0.202239 0.222231 + outer loop + vertex -904.814 309.878 331.574 + vertex -906.512 317.881 331.569 + vertex -905.355 307.709 327.281 + endloop + endfacet + facet normal -0.956222 -0.199205 0.214376 + outer loop + vertex -905.355 307.709 327.281 + vertex -906.512 317.881 331.569 + vertex -907.041 315.806 327.283 + endloop + endfacet + facet normal -0.938273 -0.202428 0.280475 + outer loop + vertex -904.211 312.525 335.504 + vertex -905.915 320.425 335.503 + vertex -904.814 309.878 331.574 + endloop + endfacet + facet normal -0.941393 -0.199573 0.271938 + outer loop + vertex -904.814 309.878 331.574 + vertex -905.915 320.425 335.503 + vertex -906.512 317.881 331.569 + endloop + endfacet + facet normal -0.922714 -0.199487 0.329853 + outer loop + vertex -903.539 315.489 339.174 + vertex -905.226 323.29 339.173 + vertex -904.211 312.525 335.504 + endloop + endfacet + facet normal -0.92317 -0.199162 0.328773 + outer loop + vertex -904.211 312.525 335.504 + vertex -905.226 323.29 339.173 + vertex -905.915 320.425 335.503 + endloop + endfacet + facet normal -0.902089 -0.197637 0.383634 + outer loop + vertex -902.742 318.633 342.669 + vertex -904.426 326.325 342.671 + vertex -903.539 315.489 339.174 + endloop + endfacet + facet normal -0.905346 -0.195725 0.376882 + outer loop + vertex -903.539 315.489 339.174 + vertex -904.426 326.325 342.671 + vertex -905.226 323.29 339.173 + endloop + endfacet + facet normal -0.883368 -0.195232 0.426082 + outer loop + vertex -901.849 321.891 346.013 + vertex -903.523 329.473 346.015 + vertex -902.742 318.633 342.669 + endloop + endfacet + facet normal -0.885707 -0.19406 0.421739 + outer loop + vertex -902.742 318.633 342.669 + vertex -903.523 329.473 346.015 + vertex -904.426 326.325 342.671 + endloop + endfacet + facet normal -0.855068 -0.19178 0.481746 + outer loop + vertex -900.842 325.284 349.152 + vertex -902.514 332.75 349.155 + vertex -901.849 321.891 346.013 + endloop + endfacet + facet normal -0.859484 -0.189969 0.474552 + outer loop + vertex -901.849 321.891 346.013 + vertex -902.514 332.75 349.155 + vertex -903.523 329.473 346.015 + endloop + endfacet + facet normal -0.820629 -0.185036 0.540676 + outer loop + vertex -899.756 328.849 352.02 + vertex -901.411 336.196 352.022 + vertex -900.842 325.284 349.152 + endloop + endfacet + facet normal -0.822366 -0.184481 0.538221 + outer loop + vertex -900.842 325.284 349.152 + vertex -901.411 336.196 352.022 + vertex -902.514 332.75 349.155 + endloop + endfacet + facet normal -0.764306 -0.173027 0.621207 + outer loop + vertex -898.562 332.658 354.55 + vertex -900.192 339.869 354.552 + vertex -899.756 328.849 352.02 + endloop + endfacet + facet normal -0.765768 -0.172692 0.619498 + outer loop + vertex -899.756 328.849 352.02 + vertex -900.192 339.869 354.552 + vertex -901.411 336.196 352.022 + endloop + endfacet + facet normal -0.679828 -0.155582 0.716679 + outer loop + vertex -897.241 336.81 356.704 + vertex -898.843 343.854 356.714 + vertex -898.562 332.658 354.55 + endloop + endfacet + facet normal -0.684136 -0.154923 0.712711 + outer loop + vertex -898.562 332.658 354.55 + vertex -898.843 343.854 356.714 + vertex -900.192 339.869 354.552 + endloop + endfacet + facet normal -0.58074 -0.130606 0.803544 + outer loop + vertex -895.818 341.317 358.465 + vertex -897.359 348.19 358.468 + vertex -897.241 336.81 356.704 + endloop + endfacet + facet normal -0.572838 -0.13138 0.809071 + outer loop + vertex -897.241 336.81 356.704 + vertex -897.359 348.19 358.468 + vertex -898.843 343.854 356.714 + endloop + endfacet + facet normal -0.477851 -0.105584 0.872072 + outer loop + vertex -894.368 345.903 359.815 + vertex -895.87 352.637 359.807 + vertex -895.818 341.317 358.465 + endloop + endfacet + facet normal -0.470847 -0.105997 0.875824 + outer loop + vertex -895.818 341.317 358.465 + vertex -895.87 352.637 359.807 + vertex -897.359 348.19 358.468 + endloop + endfacet + facet normal -0.390552 -0.086174 0.916539 + outer loop + vertex -893.049 349.866 360.75 + vertex -894.568 356.558 360.732 + vertex -894.368 345.903 359.815 + endloop + endfacet + facet normal -0.390999 -0.086166 0.916349 + outer loop + vertex -894.368 345.903 359.815 + vertex -894.568 356.558 360.732 + vertex -895.87 352.637 359.807 + endloop + endfacet + facet normal -0.980472 -0.129782 0.147752 + outer loop + vertex -907.041 315.806 327.283 + vertex -908.124 323.98 327.278 + vertex -907.526 314.208 322.663 + endloop + endfacet + facet normal -0.98366 -0.122504 0.131931 + outer loop + vertex -907.526 314.208 322.663 + vertex -908.124 323.98 327.278 + vertex -908.559 322.498 322.659 + endloop + endfacet + facet normal -0.973583 -0.13394 0.184924 + outer loop + vertex -906.512 317.881 331.569 + vertex -907.622 325.94 331.564 + vertex -907.041 315.806 327.283 + endloop + endfacet + facet normal -0.976341 -0.12922 0.173377 + outer loop + vertex -907.041 315.806 327.283 + vertex -907.622 325.94 331.564 + vertex -908.124 323.98 327.278 + endloop + endfacet + facet normal -0.963007 -0.134801 0.233337 + outer loop + vertex -905.915 320.425 335.503 + vertex -907.028 328.371 335.499 + vertex -906.512 317.881 331.569 + endloop + endfacet + facet normal -0.964696 -0.132694 0.227495 + outer loop + vertex -906.512 317.881 331.569 + vertex -907.028 328.371 335.499 + vertex -907.622 325.94 331.564 + endloop + endfacet + facet normal -0.949175 -0.135601 0.28404 + outer loop + vertex -905.226 323.29 339.173 + vertex -906.344 331.118 339.174 + vertex -905.915 320.425 335.503 + endloop + endfacet + facet normal -0.951671 -0.133193 0.276736 + outer loop + vertex -905.915 320.425 335.503 + vertex -906.344 331.118 339.174 + vertex -907.028 328.371 335.499 + endloop + endfacet + facet normal -0.934082 -0.134839 0.330619 + outer loop + vertex -904.426 326.325 342.671 + vertex -905.539 334.033 342.671 + vertex -905.226 323.29 339.173 + endloop + endfacet + facet normal -0.935569 -0.133663 0.326871 + outer loop + vertex -905.226 323.29 339.173 + vertex -905.539 334.033 342.671 + vertex -906.344 331.118 339.174 + endloop + endfacet + facet normal -0.917305 -0.134934 0.374626 + outer loop + vertex -903.523 329.473 346.015 + vertex -904.638 337.052 346.016 + vertex -904.426 326.325 342.671 + endloop + endfacet + facet normal -0.920368 -0.132862 0.367792 + outer loop + vertex -904.426 326.325 342.671 + vertex -904.638 337.052 346.016 + vertex -905.539 334.033 342.671 + endloop + endfacet + facet normal -0.894201 -0.133885 0.427176 + outer loop + vertex -902.514 332.75 349.155 + vertex -903.629 340.194 349.155 + vertex -903.523 329.473 346.015 + endloop + endfacet + facet normal -0.897525 -0.132031 0.420733 + outer loop + vertex -903.523 329.473 346.015 + vertex -903.629 340.194 349.155 + vertex -904.638 337.052 346.016 + endloop + endfacet + facet normal -0.861612 -0.131924 0.490123 + outer loop + vertex -901.411 336.196 352.022 + vertex -902.529 343.503 352.023 + vertex -902.514 332.75 349.155 + endloop + endfacet + facet normal -0.866552 -0.129744 0.481928 + outer loop + vertex -902.514 332.75 349.155 + vertex -902.529 343.503 352.023 + vertex -903.629 340.194 349.155 + endloop + endfacet + facet normal -0.810302 -0.125478 0.572421 + outer loop + vertex -900.192 339.869 354.552 + vertex -901.3 347.03 354.555 + vertex -901.411 336.196 352.022 + endloop + endfacet + facet normal -0.813185 -0.124538 0.568525 + outer loop + vertex -901.411 336.196 352.022 + vertex -901.3 347.03 354.555 + vertex -902.529 343.503 352.023 + endloop + endfacet + facet normal -0.736184 -0.112685 0.667335 + outer loop + vertex -898.843 343.854 356.714 + vertex -899.916 350.85 356.712 + vertex -900.192 339.869 354.552 + endloop + endfacet + facet normal -0.732663 -0.113506 0.671059 + outer loop + vertex -900.192 339.869 354.552 + vertex -899.916 350.85 356.712 + vertex -901.3 347.03 354.555 + endloop + endfacet + facet normal -0.629488 -0.0965833 0.770984 + outer loop + vertex -897.359 348.19 358.468 + vertex -898.398 354.997 358.473 + vertex -898.843 343.854 356.714 + endloop + endfacet + facet normal -0.630408 -0.0964308 0.770251 + outer loop + vertex -898.843 343.854 356.714 + vertex -898.398 354.997 358.473 + vertex -899.916 350.85 356.712 + endloop + endfacet + facet normal -0.526259 -0.0786671 0.846677 + outer loop + vertex -895.87 352.637 359.807 + vertex -896.857 359.272 359.81 + vertex -897.359 348.19 358.468 + endloop + endfacet + facet normal -0.518067 -0.0796377 0.851625 + outer loop + vertex -897.359 348.19 358.468 + vertex -896.857 359.272 359.81 + vertex -898.398 354.997 358.473 + endloop + endfacet + facet normal -0.441908 -0.0641598 0.894763 + outer loop + vertex -894.568 356.558 360.732 + vertex -895.524 363.077 360.726 + vertex -895.87 352.637 359.807 + endloop + endfacet + facet normal -0.43304 -0.0648302 0.89904 + outer loop + vertex -895.87 352.637 359.807 + vertex -895.524 363.077 360.726 + vertex -896.857 359.272 359.81 + endloop + endfacet + facet normal -0.898644 -0.0758496 0.432072 + outer loop + vertex -902.529 343.503 352.023 + vertex -903.142 350.767 352.023 + vertex -903.629 340.194 349.155 + endloop + endfacet + facet normal -0.902158 -0.073783 0.42505 + outer loop + vertex -903.629 340.194 349.155 + vertex -903.142 350.767 352.023 + vertex -904.236 347.617 349.155 + endloop + endfacet + facet normal -0.852707 -0.0738847 0.517138 + outer loop + vertex -901.3 347.03 354.555 + vertex -901.915 354.132 354.554 + vertex -902.529 343.503 352.023 + endloop + endfacet + facet normal -0.85637 -0.0722782 0.511278 + outer loop + vertex -902.529 343.503 352.023 + vertex -901.915 354.132 354.554 + vertex -903.142 350.767 352.023 + endloop + endfacet + facet normal -0.780172 -0.0684843 0.621805 + outer loop + vertex -899.916 350.85 356.712 + vertex -900.523 357.781 356.713 + vertex -901.3 347.03 354.555 + endloop + endfacet + facet normal -0.782366 -0.0677867 0.619119 + outer loop + vertex -901.3 347.03 354.555 + vertex -900.523 357.781 356.713 + vertex -901.915 354.132 354.554 + endloop + endfacet + facet normal -0.684371 -0.0582305 0.726805 + outer loop + vertex -898.398 354.997 358.473 + vertex -898.974 361.738 358.47 + vertex -899.916 350.85 356.712 + endloop + endfacet + facet normal -0.678559 -0.0595924 0.732124 + outer loop + vertex -899.916 350.85 356.712 + vertex -898.974 361.738 358.47 + vertex -900.523 357.781 356.713 + endloop + endfacet + facet normal -0.575704 -0.0477965 0.81626 + outer loop + vertex -896.857 359.272 359.81 + vertex -897.395 365.822 359.814 + vertex -898.398 354.997 358.473 + endloop + endfacet + facet normal -0.571503 -0.0485453 0.819162 + outer loop + vertex -898.398 354.997 358.473 + vertex -897.395 365.822 359.814 + vertex -898.974 361.738 358.47 + endloop + endfacet + facet normal -0.487812 -0.0391553 0.87207 + outer loop + vertex -895.524 363.077 360.726 + vertex -896.02 369.502 360.738 + vertex -896.857 359.272 359.81 + endloop + endfacet + facet normal -0.48102 -0.0400484 0.875794 + outer loop + vertex -896.857 359.272 359.81 + vertex -896.02 369.502 360.738 + vertex -897.395 365.822 359.814 + endloop + endfacet + facet normal -0.925852 -0.0220401 0.377244 + outer loop + vertex -903.142 350.767 352.023 + vertex -903.315 358 352.022 + vertex -904.236 347.617 349.155 + endloop + endfacet + facet normal -0.927977 -0.0204247 0.372076 + outer loop + vertex -904.236 347.617 349.155 + vertex -903.315 358 352.022 + vertex -904.398 355.023 349.156 + endloop + endfacet + facet normal -0.88743 -0.0226742 0.460385 + outer loop + vertex -901.915 354.132 354.554 + vertex -902.096 361.189 354.553 + vertex -903.142 350.767 352.023 + endloop + endfacet + facet normal -0.890083 -0.0211753 0.455306 + outer loop + vertex -903.142 350.767 352.023 + vertex -902.096 361.189 354.553 + vertex -903.315 358 352.022 + endloop + endfacet + facet normal -0.822407 -0.0225475 0.568453 + outer loop + vertex -900.523 357.781 356.713 + vertex -900.711 364.655 356.714 + vertex -901.915 354.132 354.554 + endloop + endfacet + facet normal -0.826008 -0.021071 0.563265 + outer loop + vertex -901.915 354.132 354.554 + vertex -900.711 364.655 356.714 + vertex -902.096 361.189 354.553 + endloop + endfacet + facet normal -0.727893 -0.0195226 0.685413 + outer loop + vertex -898.974 361.738 358.47 + vertex -899.153 368.42 358.471 + vertex -900.523 357.781 356.713 + endloop + endfacet + facet normal -0.726502 -0.0199435 0.686875 + outer loop + vertex -900.523 357.781 356.713 + vertex -899.153 368.42 358.471 + vertex -900.711 364.655 356.714 + endloop + endfacet + facet normal -0.625864 -0.0145705 0.779796 + outer loop + vertex -897.395 365.822 359.814 + vertex -897.547 372.299 359.814 + vertex -898.974 361.738 358.47 + endloop + endfacet + facet normal -0.617326 -0.0165815 0.786533 + outer loop + vertex -898.974 361.738 358.47 + vertex -897.547 372.299 359.814 + vertex -899.153 368.42 358.471 + endloop + endfacet + facet normal -0.539484 -0.00971532 0.84194 + outer loop + vertex -896.02 369.502 360.738 + vertex -896.141 375.752 360.732 + vertex -897.395 365.822 359.814 + endloop + endfacet + facet normal -0.525865 -0.012224 0.85048 + outer loop + vertex -897.395 365.822 359.814 + vertex -896.141 375.752 360.732 + vertex -897.547 372.299 359.814 + endloop + endfacet + facet normal -0.943596 0.0256566 0.330102 + outer loop + vertex -903.315 358 352.022 + vertex -903.119 365.199 352.023 + vertex -904.398 355.023 349.156 + endloop + endfacet + facet normal -0.946207 0.028174 0.322333 + outer loop + vertex -904.398 355.023 349.156 + vertex -903.119 365.199 352.023 + vertex -904.179 362.401 349.154 + endloop + endfacet + facet normal -0.912 0.0235387 0.409514 + outer loop + vertex -902.096 361.189 354.553 + vertex -901.914 368.201 354.555 + vertex -903.315 358 352.022 + endloop + endfacet + facet normal -0.913838 0.0248326 0.405319 + outer loop + vertex -903.315 358 352.022 + vertex -901.914 368.201 354.555 + vertex -903.119 365.199 352.023 + endloop + endfacet + facet normal -0.857642 0.0224329 0.513757 + outer loop + vertex -900.711 364.655 356.714 + vertex -900.534 371.474 356.712 + vertex -902.096 361.189 354.553 + endloop + endfacet + facet normal -0.85694 0.0220774 0.514942 + outer loop + vertex -902.096 361.189 354.553 + vertex -900.534 371.474 356.712 + vertex -901.914 368.201 354.555 + endloop + endfacet + facet normal -0.768327 0.0193691 0.639764 + outer loop + vertex -899.153 368.42 358.471 + vertex -898.984 375.037 358.474 + vertex -900.711 364.655 356.714 + endloop + endfacet + facet normal -0.770542 0.0201947 0.637069 + outer loop + vertex -900.711 364.655 356.714 + vertex -898.984 375.037 358.474 + vertex -900.534 371.474 356.712 + endloop + endfacet + facet normal -0.666901 0.0183464 0.74492 + outer loop + vertex -897.547 372.299 359.814 + vertex -897.372 378.693 359.812 + vertex -899.153 368.42 358.471 + endloop + endfacet + facet normal -0.660818 0.0165813 0.750363 + outer loop + vertex -899.153 368.42 358.471 + vertex -897.372 378.693 359.812 + vertex -898.984 375.037 358.474 + endloop + endfacet + facet normal -0.575968 0.0169911 0.817296 + outer loop + vertex -896.141 375.752 360.732 + vertex -895.951 381.948 360.738 + vertex -897.547 372.299 359.814 + endloop + endfacet + facet normal -0.570531 0.0157251 0.821126 + outer loop + vertex -897.547 372.299 359.814 + vertex -895.951 381.948 360.738 + vertex -897.372 378.693 359.812 + endloop + endfacet + facet normal -0.880489 0.0615911 0.470049 + outer loop + vertex -900.534 371.474 356.712 + vertex -900.06 378.225 356.714 + vertex -901.914 368.201 354.555 + endloop + endfacet + facet normal -0.88035 0.0615074 0.470319 + outer loop + vertex -901.914 368.201 354.555 + vertex -900.06 378.225 356.714 + vertex -901.427 375.153 354.557 + endloop + endfacet + facet normal -0.803574 0.0566044 0.592508 + outer loop + vertex -898.984 375.037 358.474 + vertex -898.521 381.575 358.477 + vertex -900.534 371.474 356.712 + endloop + endfacet + facet normal -0.802364 0.0560685 0.594195 + outer loop + vertex -900.534 371.474 356.712 + vertex -898.521 381.575 358.477 + vertex -900.06 378.225 356.714 + endloop + endfacet + facet normal -0.703122 0.050272 0.70929 + outer loop + vertex -897.372 378.693 359.812 + vertex -896.915 385.012 359.817 + vertex -898.984 375.037 358.474 + endloop + endfacet + facet normal -0.700037 0.0492123 0.712409 + outer loop + vertex -898.984 375.037 358.474 + vertex -896.915 385.012 359.817 + vertex -898.521 381.575 358.477 + endloop + endfacet + facet normal -0.616998 0.0461022 0.785613 + outer loop + vertex -895.951 381.948 360.738 + vertex -895.504 387.997 360.733 + vertex -897.372 378.693 359.812 + endloop + endfacet + facet normal -0.606758 0.0432453 0.793709 + outer loop + vertex -897.372 378.693 359.812 + vertex -895.504 387.997 360.733 + vertex -896.915 385.012 359.817 + endloop + endfacet + facet normal -0.89715 0.0965705 0.431041 + outer loop + vertex -900.06 378.225 356.714 + vertex -899.343 384.88 356.715 + vertex -901.427 375.153 354.557 + endloop + endfacet + facet normal -0.897689 0.0969545 0.429831 + outer loop + vertex -901.427 375.153 354.557 + vertex -899.343 384.88 356.715 + vertex -900.685 382.026 354.557 + endloop + endfacet + facet normal -0.82836 0.0897025 0.552967 + outer loop + vertex -898.521 381.575 358.477 + vertex -897.826 387.995 358.477 + vertex -900.06 378.225 356.714 + endloop + endfacet + facet normal -0.826969 0.0889887 0.55516 + outer loop + vertex -900.06 378.225 356.714 + vertex -897.826 387.995 358.477 + vertex -899.343 384.88 356.715 + endloop + endfacet + facet normal -0.734174 0.0800516 0.674225 + outer loop + vertex -896.915 385.012 359.817 + vertex -896.236 391.205 359.822 + vertex -898.521 381.575 358.477 + endloop + endfacet + facet normal -0.732264 0.0792963 0.676389 + outer loop + vertex -898.521 381.575 358.477 + vertex -896.236 391.205 359.822 + vertex -897.826 387.995 358.477 + endloop + endfacet + facet normal -0.64521 0.071569 0.760646 + outer loop + vertex -895.504 387.997 360.733 + vertex -894.829 393.986 360.742 + vertex -896.915 385.012 359.817 + endloop + endfacet + facet normal -0.638911 0.0695398 0.766131 + outer loop + vertex -896.915 385.012 359.817 + vertex -894.829 393.986 360.742 + vertex -896.236 391.205 359.822 + endloop + endfacet + facet normal -0.909069 0.12736 0.396702 + outer loop + vertex -899.343 384.88 356.715 + vertex -898.424 391.437 356.716 + vertex -900.685 382.026 354.557 + endloop + endfacet + facet normal -0.909403 0.127636 0.395848 + outer loop + vertex -900.685 382.026 354.557 + vertex -898.424 391.437 356.716 + vertex -899.733 388.815 354.556 + endloop + endfacet + facet normal -0.846412 0.118866 0.519093 + outer loop + vertex -897.826 387.995 358.477 + vertex -896.948 394.263 358.472 + vertex -899.343 384.88 356.715 + endloop + endfacet + facet normal -0.845734 0.118469 0.520288 + outer loop + vertex -899.343 384.88 356.715 + vertex -896.948 394.263 358.472 + vertex -898.424 391.437 356.716 + endloop + endfacet + facet normal -0.75953 0.10739 0.641546 + outer loop + vertex -896.236 391.205 359.822 + vertex -895.397 397.198 359.811 + vertex -897.826 387.995 358.477 + endloop + endfacet + facet normal -0.757608 0.106534 0.643957 + outer loop + vertex -897.826 387.995 358.477 + vertex -895.397 397.198 359.811 + vertex -896.948 394.263 358.472 + endloop + endfacet + facet normal -0.671553 0.096465 0.73465 + outer loop + vertex -894.829 393.986 360.742 + vertex -894.005 399.781 360.735 + vertex -896.236 391.205 359.822 + endloop + endfacet + facet normal -0.666065 0.0944803 0.739886 + outer loop + vertex -896.236 391.205 359.822 + vertex -894.005 399.781 360.735 + vertex -895.397 397.198 359.811 + endloop + endfacet + facet normal -0.917265 0.155655 0.366602 + outer loop + vertex -898.424 391.437 356.716 + vertex -897.325 397.918 356.714 + vertex -899.733 388.815 354.556 + endloop + endfacet + facet normal -0.916347 0.154783 0.369257 + outer loop + vertex -899.733 388.815 354.556 + vertex -897.325 397.918 356.714 + vertex -898.598 395.534 354.556 + endloop + endfacet + facet normal -0.860142 0.145521 0.488856 + outer loop + vertex -896.948 394.263 358.472 + vertex -895.9 400.448 358.475 + vertex -898.424 391.437 356.716 + endloop + endfacet + facet normal -0.861128 0.146175 0.486921 + outer loop + vertex -898.424 391.437 356.716 + vertex -895.9 400.448 358.475 + vertex -897.325 397.918 356.714 + endloop + endfacet + facet normal -0.777424 0.130038 0.615388 + outer loop + vertex -895.397 397.198 359.811 + vertex -894.458 402.896 359.794 + vertex -896.948 394.263 358.472 + endloop + endfacet + facet normal -0.781711 0.13218 0.609472 + outer loop + vertex -896.948 394.263 358.472 + vertex -894.458 402.896 359.794 + vertex -895.9 400.448 358.475 + endloop + endfacet + facet normal -0.691262 0.117686 0.712957 + outer loop + vertex -894.005 399.781 360.735 + vertex -893.089 405.345 360.704 + vertex -895.397 397.198 359.811 + endloop + endfacet + facet normal -0.68465 0.11507 0.719732 + outer loop + vertex -895.397 397.198 359.811 + vertex -893.089 405.345 360.704 + vertex -894.458 402.896 359.794 + endloop + endfacet + facet normal -0.921305 0.179414 0.344976 + outer loop + vertex -897.325 397.918 356.714 + vertex -896.072 404.352 356.717 + vertex -898.598 395.534 354.556 + endloop + endfacet + facet normal -0.92179 0.179938 0.343403 + outer loop + vertex -898.598 395.534 354.556 + vertex -896.072 404.352 356.717 + vertex -897.298 402.204 354.551 + endloop + endfacet + facet normal -0.87211 0.172593 0.457859 + outer loop + vertex -895.9 400.448 358.475 + vertex -894.673 406.645 358.477 + vertex -897.325 397.918 356.714 + endloop + endfacet + facet normal -0.866925 0.168768 0.468997 + outer loop + vertex -897.325 397.918 356.714 + vertex -894.673 406.645 358.477 + vertex -896.072 404.352 356.717 + endloop + endfacet + facet normal -0.800241 0.160087 0.577916 + outer loop + vertex -894.458 402.896 359.794 + vertex -893.275 408.754 359.809 + vertex -895.9 400.448 358.475 + endloop + endfacet + facet normal -0.795382 0.157361 0.585325 + outer loop + vertex -895.9 400.448 358.475 + vertex -893.275 408.754 359.809 + vertex -894.673 406.645 358.477 + endloop + endfacet + facet normal -0.704508 0.134705 0.696795 + outer loop + vertex -893.089 405.345 360.704 + vertex -892.362 409.671 360.603 + vertex -894.458 402.896 359.794 + endloop + endfacet + facet normal -0.72831 0.14531 0.669664 + outer loop + vertex -894.458 402.896 359.794 + vertex -892.362 409.671 360.603 + vertex -893.275 408.754 359.809 + endloop + endfacet + facet normal -0.92443 0.200822 0.324192 + outer loop + vertex -896.072 404.352 356.717 + vertex -894.685 410.735 356.717 + vertex -897.298 402.204 354.551 + endloop + endfacet + facet normal -0.922907 0.198976 0.329623 + outer loop + vertex -897.298 402.204 354.551 + vertex -894.685 410.735 356.717 + vertex -895.864 408.844 354.558 + endloop + endfacet + facet normal -0.874601 0.19156 0.445395 + outer loop + vertex -894.673 406.645 358.477 + vertex -893.321 412.814 358.478 + vertex -896.072 404.352 356.717 + endloop + endfacet + facet normal -0.871891 0.189389 0.451596 + outer loop + vertex -896.072 404.352 356.717 + vertex -893.321 412.814 358.478 + vertex -894.685 410.735 356.717 + endloop + endfacet + facet normal -0.807372 0.180129 0.561875 + outer loop + vertex -893.275 408.754 359.809 + vertex -891.893 414.877 359.832 + vertex -894.673 406.645 358.477 + endloop + endfacet + facet normal -0.798685 0.174907 0.575768 + outer loop + vertex -894.673 406.645 358.477 + vertex -891.893 414.877 359.832 + vertex -893.321 412.814 358.478 + endloop + endfacet + facet normal -0.738144 0.169508 0.653001 + outer loop + vertex -892.362 409.671 360.603 + vertex -890.626 416.383 360.823 + vertex -893.275 408.754 359.809 + endloop + endfacet + facet normal -0.719029 0.159765 0.676367 + outer loop + vertex -893.275 408.754 359.809 + vertex -890.626 416.383 360.823 + vertex -891.893 414.877 359.832 + endloop + endfacet + facet normal -0.924215 0.218793 0.312981 + outer loop + vertex -894.685 410.735 356.717 + vertex -893.186 417.07 356.715 + vertex -895.864 408.844 354.558 + endloop + endfacet + facet normal -0.924388 0.219026 0.312306 + outer loop + vertex -895.864 408.844 354.558 + vertex -893.186 417.07 356.715 + vertex -894.303 415.443 354.548 + endloop + endfacet + facet normal -0.87655 0.206832 0.434604 + outer loop + vertex -893.321 412.814 358.478 + vertex -891.888 418.885 358.479 + vertex -894.685 410.735 356.717 + endloop + endfacet + facet normal -0.877711 0.207843 0.431769 + outer loop + vertex -894.685 410.735 356.717 + vertex -891.888 418.885 358.479 + vertex -893.186 417.07 356.715 + endloop + endfacet + facet normal -0.806491 0.190955 0.559562 + outer loop + vertex -891.893 414.877 359.832 + vertex -890.5 420.79 359.822 + vertex -893.321 412.814 358.478 + endloop + endfacet + facet normal -0.80475 0.189855 0.562435 + outer loop + vertex -893.321 412.814 358.478 + vertex -890.5 420.79 359.822 + vertex -891.888 418.885 358.479 + endloop + endfacet + facet normal -0.725945 0.172568 0.665751 + outer loop + vertex -890.626 416.383 360.823 + vertex -889.249 422.444 360.754 + vertex -891.893 414.877 359.832 + endloop + endfacet + facet normal -0.72436 0.171779 0.667678 + outer loop + vertex -891.893 414.877 359.832 + vertex -889.249 422.444 360.754 + vertex -890.5 420.79 359.822 + endloop + endfacet + facet normal -0.924445 0.233333 0.301592 + outer loop + vertex -893.186 417.07 356.715 + vertex -891.601 423.354 356.712 + vertex -894.303 415.443 354.548 + endloop + endfacet + facet normal -0.923459 0.231869 0.305713 + outer loop + vertex -894.303 415.443 354.548 + vertex -891.601 423.354 356.712 + vertex -892.66 421.988 354.548 + endloop + endfacet + facet normal -0.8804 0.222244 0.418932 + outer loop + vertex -891.888 418.885 358.479 + vertex -890.386 424.851 358.47 + vertex -893.186 417.07 356.715 + endloop + endfacet + facet normal -0.880441 0.222283 0.418825 + outer loop + vertex -893.186 417.07 356.715 + vertex -890.386 424.851 358.47 + vertex -891.601 423.354 356.712 + endloop + endfacet + facet normal -0.810436 0.203132 0.549483 + outer loop + vertex -890.5 420.79 359.822 + vertex -889.083 426.478 359.809 + vertex -891.888 418.885 358.479 + endloop + endfacet + facet normal -0.814415 0.205815 0.542557 + outer loop + vertex -891.888 418.885 358.479 + vertex -889.083 426.478 359.809 + vertex -890.386 424.851 358.47 + endloop + endfacet + facet normal -0.731345 0.183095 0.656971 + outer loop + vertex -889.249 422.444 360.754 + vertex -887.877 427.989 360.736 + vertex -890.5 420.79 359.822 + endloop + endfacet + facet normal -0.733437 0.184193 0.654327 + outer loop + vertex -890.5 420.79 359.822 + vertex -887.877 427.989 360.736 + vertex -889.083 426.478 359.809 + endloop + endfacet + facet normal -0.92293 0.243825 0.297907 + outer loop + vertex -891.601 423.354 356.712 + vertex -889.953 429.59 356.713 + vertex -892.66 421.988 354.548 + endloop + endfacet + facet normal -0.923178 0.244225 0.296811 + outer loop + vertex -892.66 421.988 354.548 + vertex -889.953 429.59 356.713 + vertex -890.949 428.458 354.545 + endloop + endfacet + facet normal -0.88154 0.232484 0.410899 + outer loop + vertex -890.386 424.851 358.47 + vertex -888.823 430.78 358.47 + vertex -891.601 423.354 356.712 + endloop + endfacet + facet normal -0.882057 0.233012 0.409488 + outer loop + vertex -891.601 423.354 356.712 + vertex -888.823 430.78 358.47 + vertex -889.953 429.59 356.713 + endloop + endfacet + facet normal -0.816727 0.212766 0.536365 + outer loop + vertex -889.083 426.478 359.809 + vertex -887.676 431.931 359.789 + vertex -890.386 424.851 358.47 + endloop + endfacet + facet normal -0.822445 0.216911 0.525864 + outer loop + vertex -890.386 424.851 358.47 + vertex -887.676 431.931 359.789 + vertex -888.823 430.78 358.47 + endloop + endfacet + facet normal -0.737223 0.19105 0.648075 + outer loop + vertex -887.877 427.989 360.736 + vertex -886.537 433.28 360.7 + vertex -889.083 426.478 359.809 + endloop + endfacet + facet normal -0.742738 0.194061 0.640844 + outer loop + vertex -889.083 426.478 359.809 + vertex -886.537 433.28 360.7 + vertex -887.676 431.931 359.789 + endloop + endfacet + facet normal -0.922737 0.249264 0.293978 + outer loop + vertex -889.953 429.59 356.713 + vertex -888.265 435.817 356.73 + vertex -890.949 428.458 354.545 + endloop + endfacet + facet normal -0.923109 0.249909 0.29226 + outer loop + vertex -890.949 428.458 354.545 + vertex -888.265 435.817 356.73 + vertex -889.19 434.923 354.574 + endloop + endfacet + facet normal -0.882225 0.237681 0.406432 + outer loop + vertex -888.823 430.78 358.47 + vertex -887.203 436.771 358.483 + vertex -889.953 429.59 356.713 + endloop + endfacet + facet normal -0.882586 0.238069 0.40542 + outer loop + vertex -889.953 429.59 356.713 + vertex -887.203 436.771 358.483 + vertex -888.265 435.817 356.73 + endloop + endfacet + facet normal -0.823241 0.221182 0.522832 + outer loop + vertex -887.676 431.931 359.789 + vertex -886.151 437.556 359.811 + vertex -888.823 430.78 358.47 + endloop + endfacet + facet normal -0.823843 0.221646 0.521685 + outer loop + vertex -888.823 430.78 358.47 + vertex -886.151 437.556 359.811 + vertex -887.203 436.771 358.483 + endloop + endfacet + facet normal -0.742564 0.193707 0.641152 + outer loop + vertex -886.537 433.28 360.7 + vertex -885.504 437.552 360.607 + vertex -887.676 431.931 359.789 + endloop + endfacet + facet normal -0.759138 0.203431 0.618325 + outer loop + vertex -887.676 431.931 359.789 + vertex -885.504 437.552 360.607 + vertex -886.151 437.556 359.811 + endloop + endfacet + facet normal -0.923076 0.250174 0.292136 + outer loop + vertex -888.265 435.817 356.73 + vertex -886.545 442.132 356.758 + vertex -889.19 434.923 354.574 + endloop + endfacet + facet normal -0.924089 0.252004 0.287322 + outer loop + vertex -889.19 434.923 354.574 + vertex -886.545 442.132 356.758 + vertex -887.376 441.523 354.617 + endloop + endfacet + facet normal -0.882608 0.236518 0.406278 + outer loop + vertex -887.203 436.771 358.483 + vertex -885.569 442.844 358.497 + vertex -888.265 435.817 356.73 + endloop + endfacet + facet normal -0.885228 0.239398 0.398823 + outer loop + vertex -888.265 435.817 356.73 + vertex -885.569 442.844 358.497 + vertex -886.545 442.132 356.758 + endloop + endfacet + facet normal -0.823697 0.219598 0.52278 + outer loop + vertex -886.151 437.556 359.811 + vertex -884.548 443.51 359.835 + vertex -887.203 436.771 358.483 + endloop + endfacet + facet normal -0.825279 0.220828 0.519759 + outer loop + vertex -887.203 436.771 358.483 + vertex -884.548 443.51 359.835 + vertex -885.569 442.844 358.497 + endloop + endfacet + facet normal -0.758752 0.205774 0.618023 + outer loop + vertex -885.504 437.552 360.607 + vertex -883.648 443.742 360.824 + vertex -886.151 437.556 359.811 + endloop + endfacet + facet normal -0.747519 0.19864 0.633844 + outer loop + vertex -886.151 437.556 359.811 + vertex -883.648 443.742 360.824 + vertex -884.548 443.51 359.835 + endloop + endfacet + facet normal -0.924573 0.249026 0.288358 + outer loop + vertex -886.545 442.132 356.758 + vertex -884.804 448.62 356.737 + vertex -887.376 441.523 354.617 + endloop + endfacet + facet normal -0.926473 0.252475 0.279112 + outer loop + vertex -887.376 441.523 354.617 + vertex -884.804 448.62 356.737 + vertex -885.524 448.349 354.593 + endloop + endfacet + facet normal -0.885579 0.234064 0.401203 + outer loop + vertex -885.569 442.844 358.497 + vertex -883.951 448.994 358.48 + vertex -886.545 442.132 356.758 + endloop + endfacet + facet normal -0.89127 0.240406 0.384502 + outer loop + vertex -886.545 442.132 356.758 + vertex -883.951 448.994 358.48 + vertex -884.804 448.62 356.737 + endloop + endfacet + facet normal -0.825009 0.213045 0.523423 + outer loop + vertex -884.548 443.51 359.835 + vertex -883.043 449.403 359.809 + vertex -885.569 442.844 358.497 + endloop + endfacet + facet normal -0.835509 0.221174 0.502997 + outer loop + vertex -885.569 442.844 358.497 + vertex -883.043 449.403 359.809 + vertex -883.951 448.994 358.48 + endloop + endfacet + facet normal -0.747829 0.189503 0.636271 + outer loop + vertex -883.648 443.742 360.824 + vertex -882.215 449.715 360.729 + vertex -884.548 443.51 359.835 + endloop + endfacet + facet normal -0.761164 0.197167 0.617863 + outer loop + vertex -884.548 443.51 359.835 + vertex -882.215 449.715 360.729 + vertex -883.043 449.403 359.809 + endloop + endfacet + facet normal -0.927544 0.24738 0.280116 + outer loop + vertex -884.804 448.62 356.737 + vertex -883.131 455.091 356.561 + vertex -885.524 448.349 354.593 + endloop + endfacet + facet normal -0.931466 0.254702 0.259805 + outer loop + vertex -885.524 448.349 354.593 + vertex -883.131 455.091 356.561 + vertex -883.733 455.15 354.347 + endloop + endfacet + facet normal -0.892176 0.234073 0.386305 + outer loop + vertex -883.951 448.994 358.48 + vertex -882.388 455.136 358.368 + vertex -884.804 448.62 356.737 + endloop + endfacet + facet normal -0.899374 0.242363 0.363849 + outer loop + vertex -884.804 448.62 356.737 + vertex -882.388 455.136 358.368 + vertex -883.131 455.091 356.561 + endloop + endfacet + facet normal -0.835892 0.213919 0.505493 + outer loop + vertex -883.043 449.403 359.809 + vertex -881.624 455.129 359.732 + vertex -883.951 448.994 358.48 + endloop + endfacet + facet normal -0.849562 0.224889 0.477148 + outer loop + vertex -883.951 448.994 358.48 + vertex -881.624 455.129 359.732 + vertex -882.388 455.136 358.368 + endloop + endfacet + facet normal -0.761068 0.189422 0.620399 + outer loop + vertex -882.215 449.715 360.729 + vertex -880.966 455.003 360.647 + vertex -883.043 449.403 359.809 + endloop + endfacet + facet normal -0.781759 0.201639 0.59008 + outer loop + vertex -883.043 449.403 359.809 + vertex -880.966 455.003 360.647 + vertex -881.624 455.129 359.732 + endloop + endfacet + facet normal -0.933114 0.248305 0.260082 + outer loop + vertex -883.131 455.091 356.561 + vertex -881.714 460.911 356.089 + vertex -883.733 455.15 354.347 + endloop + endfacet + facet normal -0.937399 0.257569 0.234397 + outer loop + vertex -883.733 455.15 354.347 + vertex -881.714 460.911 356.089 + vertex -882.196 461.248 353.791 + endloop + endfacet + facet normal -0.900832 0.235704 0.364618 + outer loop + vertex -882.388 455.136 358.368 + vertex -881.103 460.609 358.007 + vertex -883.131 455.091 356.561 + endloop + endfacet + facet normal -0.910801 0.248523 0.329662 + outer loop + vertex -883.131 455.091 356.561 + vertex -881.103 460.609 358.007 + vertex -881.714 460.911 356.089 + endloop + endfacet + facet normal -0.851059 0.217411 0.477945 + outer loop + vertex -881.624 455.129 359.732 + vertex -880.27 460.743 359.589 + vertex -882.388 455.136 358.368 + endloop + endfacet + facet normal -0.868667 0.232939 0.437215 + outer loop + vertex -882.388 455.136 358.368 + vertex -880.27 460.743 359.589 + vertex -881.103 460.609 358.007 + endloop + endfacet + facet normal -0.783486 0.194176 0.590293 + outer loop + vertex -880.966 455.003 360.647 + vertex -879.867 459.757 360.541 + vertex -881.624 455.129 359.732 + endloop + endfacet + facet normal -0.804651 0.208198 0.556049 + outer loop + vertex -881.624 455.129 359.732 + vertex -879.867 459.757 360.541 + vertex -880.27 460.743 359.589 + endloop + endfacet + facet normal -0.922605 0.254923 0.289507 + outer loop + vertex -880.281 464.674 357.311 + vertex -879.965 467.102 356.181 + vertex -880.757 465.266 355.274 + endloop + endfacet + facet normal -0.926936 0.27227 0.258184 + outer loop + vertex -880.757 465.266 355.274 + vertex -879.965 467.102 356.181 + vertex -880.357 467.594 354.253 + endloop + endfacet + facet normal -0.894341 0.240367 0.377329 + outer loop + vertex -879.713 464.185 358.97 + vertex -879.484 466.222 358.214 + vertex -880.281 464.674 357.311 + endloop + endfacet + facet normal -0.90348 0.271895 0.331356 + outer loop + vertex -880.281 464.674 357.311 + vertex -879.484 466.222 358.214 + vertex -879.965 467.102 356.181 + endloop + endfacet + facet normal -0.859596 0.228561 0.457007 + outer loop + vertex -879.202 464.159 359.944 + vertex -879.015 465.433 359.658 + vertex -879.713 464.185 358.97 + endloop + endfacet + facet normal -0.870439 0.254131 0.421608 + outer loop + vertex -879.713 464.185 358.97 + vertex -879.015 465.433 359.658 + vertex -879.484 466.222 358.214 + endloop + endfacet + facet normal -0.811874 0.196009 0.549946 + outer loop + vertex -879.096 463.242 360.426 + vertex -878.826 464.8 360.27 + vertex -879.202 464.159 359.944 + endloop + endfacet + facet normal -0.833772 0.234376 0.499891 + outer loop + vertex -879.202 464.159 359.944 + vertex -878.826 464.8 360.27 + vertex -879.015 465.433 359.658 + endloop + endfacet + facet normal -0.694602 0.171023 0.698769 + outer loop + vertex -878.44 463.366 361.121 + vertex -878.361 463.893 361.071 + vertex -878.753 462.816 360.945 + endloop + endfacet + facet normal -0.714049 0.180712 0.676371 + outer loop + vertex -878.753 462.816 360.945 + vertex -878.361 463.893 361.071 + vertex -878.402 464.159 360.956 + endloop + endfacet + facet normal -0.194277 -0.177078 0.964831 + outer loop + vertex -853.195 278.364 359.866 + vertex -852.709 280.903 360.43 + vertex -856.983 283.585 360.061 + endloop + endfacet + facet normal -0.257997 -0.222377 0.940205 + outer loop + vertex -853.757 275.811 359.108 + vertex -853.195 278.364 359.866 + vertex -856.983 283.585 360.061 + endloop + endfacet + facet normal -0.262735 -0.244264 0.933437 + outer loop + vertex -854.95 273.153 358.076 + vertex -853.757 275.811 359.108 + vertex -858.206 279.747 358.886 + endloop + endfacet + facet normal -0.317275 -0.300146 0.899583 + outer loop + vertex -853.795 268.718 357.004 + vertex -854.95 273.153 358.076 + vertex -858.301 274.21 357.247 + endloop + endfacet + facet normal -0.341123 -0.319033 0.884224 + outer loop + vertex -855.255 267.411 355.97 + vertex -853.795 268.718 357.004 + vertex -858.301 274.21 357.247 + endloop + endfacet + facet normal -0.395364 -0.383189 0.834777 + outer loop + vertex -854.029 263.161 354.599 + vertex -855.255 267.411 355.97 + vertex -858.809 268.997 355.014 + endloop + endfacet + facet normal -0.427665 -0.40765 0.806799 + outer loop + vertex -855.281 261.032 352.86 + vertex -854.029 263.161 354.599 + vertex -858.809 268.997 355.014 + endloop + endfacet + facet normal -0.433685 -0.435423 0.788875 + outer loop + vertex -856.65 259.009 350.991 + vertex -855.281 261.032 352.86 + vertex -860.108 265.353 352.591 + endloop + endfacet + facet normal -0.656074 -0.676132 0.33528 + outer loop + vertex -860.272 232.729 319.817 + vertex -856.976 231.577 323.944 + vertex -863.66 237.604 323.019 + endloop + endfacet + facet normal -0.279403 -0.65449 -0.70255 + outer loop + vertex -851.034 243.773 296.368 + vertex -848.286 242.207 296.733 + vertex -850.754 242.423 297.514 + endloop + endfacet + facet normal -0.355625 -0.670955 -0.650654 + outer loop + vertex -853.36 245.421 295.94 + vertex -851.034 243.773 296.368 + vertex -852.693 244.163 296.873 + endloop + endfacet + facet normal -0.425706 -0.690955 -0.584257 + outer loop + vertex -856.224 247.63 295.414 + vertex -853.36 245.421 295.94 + vertex -855.438 246.348 296.358 + endloop + endfacet + facet normal -0.485271 -0.702699 -0.520314 + outer loop + vertex -859.387 250.19 294.906 + vertex -856.224 247.63 295.414 + vertex -858.709 249.031 295.84 + endloop + endfacet + facet normal -0.548909 -0.724039 -0.417692 + outer loop + vertex -861.534 251.971 294.641 + vertex -859.387 250.19 294.906 + vertex -861.956 251.929 295.269 + endloop + endfacet + facet normal -0.577859 -0.690643 -0.434846 + outer loop + vertex -864.065 254.22 294.432 + vertex -861.534 251.971 294.641 + vertex -861.956 251.929 295.269 + endloop + endfacet + facet normal -0.594138 -0.688173 -0.416434 + outer loop + vertex -866.477 256.396 294.278 + vertex -864.065 254.22 294.432 + vertex -867.002 255.942 295.777 + endloop + endfacet + facet normal -0.624483 -0.659527 -0.418384 + outer loop + vertex -868.617 258.414 294.292 + vertex -866.477 256.396 294.278 + vertex -867.002 255.942 295.777 + endloop + endfacet + facet normal -0.65597 -0.655048 -0.374988 + outer loop + vertex -870.663 260.823 293.661 + vertex -868.617 258.414 294.292 + vertex -872.85 262.144 295.179 + endloop + endfacet + facet normal -0.65608 -0.654647 -0.375495 + outer loop + vertex -872.723 262.866 293.7 + vertex -870.663 260.823 293.661 + vertex -872.85 262.144 295.179 + endloop + endfacet + facet normal -0.695588 -0.620458 -0.362201 + outer loop + vertex -875.136 265.618 293.618 + vertex -872.723 262.866 293.7 + vertex -872.85 262.144 295.179 + endloop + endfacet + facet normal -0.713569 -0.626864 -0.312828 + outer loop + vertex -877.193 268.001 293.536 + vertex -875.136 265.618 293.618 + vertex -878.427 268.758 294.833 + endloop + endfacet + facet normal -0.726357 -0.595407 -0.34336 + outer loop + vertex -878.208 269.271 293.48 + vertex -877.193 268.001 293.536 + vertex -878.427 268.758 294.833 + endloop + endfacet + facet normal -0.750635 -0.568305 -0.337013 + outer loop + vertex -880.23 272.014 293.36 + vertex -878.208 269.271 293.48 + vertex -878.427 268.758 294.833 + endloop + endfacet + facet normal -0.762556 -0.576766 -0.293 + outer loop + vertex -882.137 274.588 293.254 + vertex -880.23 272.014 293.36 + vertex -883.384 275.562 294.583 + endloop + endfacet + facet normal -0.772495 -0.545371 -0.325302 + outer loop + vertex -883.096 275.975 293.206 + vertex -882.137 274.588 293.254 + vertex -883.384 275.562 294.583 + endloop + endfacet + facet normal -0.795231 -0.5145 -0.320777 + outer loop + vertex -884.979 278.931 293.133 + vertex -883.096 275.975 293.206 + vertex -883.384 275.562 294.583 + endloop + endfacet + facet normal -0.803075 -0.510501 -0.307342 + outer loop + vertex -887.024 282.189 293.066 + vertex -884.979 278.931 293.133 + vertex -887.903 282.67 294.564 + endloop + endfacet + facet normal -0.81963 -0.467754 -0.330776 + outer loop + vertex -888.961 285.611 293.028 + vertex -887.024 282.189 293.066 + vertex -887.903 282.67 294.564 + endloop + endfacet + facet normal -0.850116 -0.479951 -0.21668 + outer loop + vertex -890.493 288.326 293.021 + vertex -888.961 285.611 293.028 + vertex -891.683 289.858 294.296 + endloop + endfacet + facet normal -0.85646 -0.438451 -0.272464 + outer loop + vertex -891.25 289.806 293.018 + vertex -890.493 288.326 293.021 + vertex -891.683 289.858 294.296 + endloop + endfacet + facet normal -0.873944 -0.397213 -0.280077 + outer loop + vertex -892.704 293.038 292.973 + vertex -891.25 289.806 293.018 + vertex -891.683 289.858 294.296 + endloop + endfacet + facet normal -0.890919 -0.398786 -0.217332 + outer loop + vertex -894.173 296.352 292.913 + vertex -892.704 293.038 292.973 + vertex -895.272 298.092 294.227 + endloop + endfacet + facet normal -0.892759 -0.347648 -0.286571 + outer loop + vertex -895.178 299.092 292.721 + vertex -894.173 296.352 292.913 + vertex -895.272 298.092 294.227 + endloop + endfacet + facet normal -0.901062 -0.333259 -0.277535 + outer loop + vertex -896.501 302.341 293.116 + vertex -895.178 299.092 292.721 + vertex -895.272 298.092 294.227 + endloop + endfacet + facet normal -0.910861 -0.291792 -0.291873 + outer loop + vertex -897.686 306.39 292.763 + vertex -896.501 302.341 293.116 + vertex -898.222 306.47 294.357 + endloop + endfacet + facet normal -0.915591 -0.273946 -0.29436 + outer loop + vertex -898.798 309.702 293.141 + vertex -897.686 306.39 292.763 + vertex -898.222 306.47 294.357 + endloop + endfacet + facet normal -0.948077 -0.241965 -0.206406 + outer loop + vertex -899.359 312.095 292.915 + vertex -898.798 309.702 293.141 + vertex -900.193 314.278 294.184 + endloop + endfacet + facet normal -0.94051 -0.198978 -0.275406 + outer loop + vertex -899.826 314.633 292.677 + vertex -899.359 312.095 292.915 + vertex -900.193 314.278 294.184 + endloop + endfacet + facet normal -0.943051 -0.189067 -0.273695 + outer loop + vertex -900.643 318.156 293.058 + vertex -899.826 314.633 292.677 + vertex -900.193 314.278 294.184 + endloop + endfacet + facet normal -0.953217 -0.148907 -0.263065 + outer loop + vertex -901.172 322.158 292.707 + vertex -900.643 318.156 293.058 + vertex -901.705 322.663 294.352 + endloop + endfacet + facet normal -0.954543 -0.123453 -0.271307 + outer loop + vertex -901.785 326.003 293.115 + vertex -901.172 322.158 292.707 + vertex -901.705 322.663 294.352 + endloop + endfacet + facet normal -0.964153 -0.0836247 -0.251825 + outer loop + vertex -902.025 329.877 292.748 + vertex -901.785 326.003 293.115 + vertex -902.528 330.738 294.386 + endloop + endfacet + facet normal -0.962686 -0.0597263 -0.263946 + outer loop + vertex -902.372 333.802 293.124 + vertex -902.025 329.877 292.748 + vertex -902.528 330.738 294.386 + endloop + endfacet + facet normal -0.97131 -0.0262386 -0.236366 + outer loop + vertex -902.368 337.33 292.715 + vertex -902.372 333.802 293.124 + vertex -902.782 339.214 294.21 + endloop + endfacet + facet normal -0.968872 -0.0172967 -0.246957 + outer loop + vertex -902.463 340.036 292.899 + vertex -902.368 337.33 292.715 + vertex -902.782 339.214 294.21 + endloop + endfacet + facet normal -0.973929 0.0178388 -0.226149 + outer loop + vertex -902.397 343.924 292.924 + vertex -902.463 340.036 292.899 + vertex -902.782 339.214 294.21 + endloop + endfacet + facet normal -0.970071 0.0258646 -0.24144 + outer loop + vertex -902.294 347.906 292.936 + vertex -902.397 343.924 292.924 + vertex -902.641 348.151 294.357 + endloop + endfacet + facet normal -0.967579 0.0566246 -0.246141 + outer loop + vertex -902.042 352.061 292.903 + vertex -902.294 347.906 292.936 + vertex -902.641 348.151 294.357 + endloop + endfacet + facet normal -0.969127 0.0651782 -0.23779 + outer loop + vertex -901.783 355.913 292.9 + vertex -902.042 352.061 292.903 + vertex -902.107 356.363 294.346 + endloop + endfacet + facet normal -0.964708 0.0942815 -0.245863 + outer loop + vertex -901.383 359.952 292.881 + vertex -901.783 355.913 292.9 + vertex -902.107 356.363 294.346 + endloop + endfacet + facet normal -0.966554 0.102191 -0.235226 + outer loop + vertex -900.989 363.699 292.891 + vertex -901.383 359.952 292.881 + vertex -901.28 364.31 294.348 + endloop + endfacet + facet normal -0.961321 0.126816 -0.244497 + outer loop + vertex -900.46 367.704 292.888 + vertex -900.989 363.699 292.891 + vertex -901.28 364.31 294.348 + endloop + endfacet + facet normal -0.963695 0.133646 -0.231151 + outer loop + vertex -899.948 371.435 292.908 + vertex -900.46 367.704 292.888 + vertex -900.188 372.233 294.372 + endloop + endfacet + facet normal -0.957831 0.155095 -0.241878 + outer loop + vertex -899.287 375.516 292.908 + vertex -899.948 371.435 292.908 + vertex -900.188 372.233 294.372 + endloop + endfacet + facet normal -0.958438 0.16182 -0.234969 + outer loop + vertex -898.639 379.369 292.917 + vertex -899.287 375.516 292.908 + vertex -898.845 380.242 294.358 + endloop + endfacet + facet normal -0.953458 0.177492 -0.243751 + outer loop + vertex -897.893 383.378 292.922 + vertex -898.639 379.369 292.917 + vertex -898.845 380.242 294.358 + endloop + endfacet + facet normal -0.939571 0.211778 -0.268992 + outer loop + vertex -879.713 465.967 309.678 + vertex -879.101 464.997 306.777 + vertex -879.743 465.301 309.258 + endloop + endfacet + facet normal -0.955579 0.18674 -0.228027 + outer loop + vertex -880.121 466.697 311.986 + vertex -879.713 465.967 309.678 + vertex -879.743 465.301 309.258 + endloop + endfacet + facet normal -0.972177 0.153724 -0.176752 + outer loop + vertex -880.394 467.558 314.237 + vertex -880.121 466.697 311.986 + vertex -880.47 466.897 314.079 + endloop + endfacet + facet normal -0.981706 0.142651 -0.12611 + outer loop + vertex -880.641 468.445 317.163 + vertex -880.394 467.558 314.237 + vertex -880.47 466.897 314.079 + endloop + endfacet + facet normal -0.968174 0.222549 -0.114501 + outer loop + vertex -880.835 469.159 320.193 + vertex -880.641 468.445 317.163 + vertex -880.881 468.035 318.397 + endloop + endfacet + facet normal -0.971259 0.224016 -0.0804553 + outer loop + vertex -880.913 469.596 322.347 + vertex -880.835 469.159 320.193 + vertex -881.083 468.931 322.547 + endloop + endfacet + facet normal -0.971268 0.231095 -0.0568611 + outer loop + vertex -881.015 469.734 324.651 + vertex -880.913 469.596 322.347 + vertex -881.083 468.931 322.547 + endloop + endfacet + facet normal -0.968778 0.245134 -0.0371437 + outer loop + vertex -881.045 469.926 326.706 + vertex -881.015 469.734 324.651 + vertex -881.216 469.269 326.816 + endloop + endfacet + facet normal -0.962187 0.264063 0.066834 + outer loop + vertex -880.886 469.398 347.139 + vertex -880.995 469.651 344.569 + vertex -881.146 468.77 345.88 + endloop + endfacet + facet normal -0.957066 0.27108 0.102669 + outer loop + vertex -880.688 469.357 349.09 + vertex -880.886 469.398 347.139 + vertex -880.9 468.609 349.087 + endloop + endfacet + facet normal -0.953985 0.270098 0.130231 + outer loop + vertex -880.499 469.022 351.167 + vertex -880.688 469.357 349.09 + vertex -880.9 468.609 349.087 + endloop + endfacet + facet normal -0.924219 0.327092 0.197055 + outer loop + vertex -880.115 468.395 354.01 + vertex -880.499 469.022 351.167 + vertex -880.609 468.161 352.083 + endloop + endfacet + facet normal -0.869157 0.396138 0.296041 + outer loop + vertex -879.615 467.272 356.982 + vertex -880.115 468.395 354.01 + vertex -879.965 467.102 356.181 + endloop + endfacet + facet normal -0.838914 0.367119 0.401804 + outer loop + vertex -879.144 466.083 359.052 + vertex -879.615 467.272 356.982 + vertex -879.484 466.222 358.214 + endloop + endfacet + facet normal -0.642097 0.45124 0.619752 + outer loop + vertex -878.617 464.889 360.467 + vertex -879.144 466.083 359.052 + vertex -879.015 465.433 359.658 + endloop + endfacet + facet normal -0.477818 0.38794 0.788158 + outer loop + vertex -878.305 464.056 361.066 + vertex -878.617 464.889 360.467 + vertex -878.402 464.159 360.956 + endloop + endfacet + facet normal 0.710945 -0.0838185 0.698235 + outer loop + vertex -878.808 461.315 361.25 + vertex -878.305 464.056 361.066 + vertex -878.44 463.366 361.121 + endloop + endfacet + facet normal -0.623432 0.156612 0.766032 + outer loop + vertex -879.569 457.409 361.43 + vertex -878.808 461.315 361.25 + vertex -879.566 457.881 361.336 + endloop + endfacet + facet normal -0.62512 0.142035 0.767496 + outer loop + vertex -890.081 414.915 361.583 + vertex -888.984 419.823 361.569 + vertex -889.604 417.448 361.503 + endloop + endfacet + facet normal -0.582237 0.121391 0.803906 + outer loop + vertex -891.318 408.937 361.59 + vertex -890.081 414.915 361.583 + vertex -890.875 411.697 361.494 + endloop + endfacet + facet normal -0.604994 0.113106 0.788156 + outer loop + vertex -892.208 404.206 361.586 + vertex -891.318 408.937 361.59 + vertex -891.935 406.214 361.507 + endloop + endfacet + facet normal -0.576753 0.0903977 0.811902 + outer loop + vertex -892.985 399.182 361.593 + vertex -892.208 404.206 361.586 + vertex -892.83 400.933 361.509 + endloop + endfacet + facet normal -0.5213 0.0669502 0.850743 + outer loop + vertex -893.77 393.074 361.593 + vertex -892.985 399.182 361.593 + vertex -893.613 395.406 361.506 + endloop + endfacet + facet normal -0.542763 0.0529203 0.838217 + outer loop + vertex -894.265 388.139 361.584 + vertex -893.77 393.074 361.593 + vertex -894.213 389.878 361.508 + endloop + endfacet + facet normal -0.49265 0.0257475 0.869846 + outer loop + vertex -894.523 382.935 361.592 + vertex -894.265 388.139 361.584 + vertex -894.604 384.31 361.505 + endloop + endfacet + facet normal -0.404836 0.00403075 0.91438 + outer loop + vertex -894.598 376.559 361.587 + vertex -894.523 382.935 361.592 + vertex -894.766 378.453 361.504 + endloop + endfacet + facet normal -0.456548 -0.0154673 0.889564 + outer loop + vertex -894.451 371.34 361.571 + vertex -894.598 376.559 361.587 + vertex -894.633 372.356 361.496 + endloop + endfacet + facet normal -0.48038 -0.0461186 0.875847 + outer loop + vertex -894.043 367.38 361.587 + vertex -894.451 371.34 361.571 + vertex -894.053 365.911 361.504 + endloop + endfacet + facet normal -0.358216 -0.0500709 0.932295 + outer loop + vertex -893.311 362.02 361.58 + vertex -894.043 367.38 361.587 + vertex -894.053 365.911 361.504 + endloop + endfacet + facet normal -0.314856 -0.0594564 0.947276 + outer loop + vertex -892.34 356.842 361.578 + vertex -893.311 362.02 361.58 + vertex -892.952 358.912 361.504 + endloop + endfacet + facet normal -0.274983 -0.0677975 0.959056 + outer loop + vertex -891.013 351.536 361.583 + vertex -892.34 356.842 361.578 + vertex -891.599 353.015 361.52 + endloop + endfacet + facet normal -0.294722 -0.0866251 0.951649 + outer loop + vertex -889.219 345.334 361.574 + vertex -891.013 351.536 361.583 + vertex -889.837 346.634 361.501 + endloop + endfacet + facet normal -0.704566 -0.230176 0.671271 + outer loop + vertex -888.048 341.731 361.568 + vertex -889.219 345.334 361.574 + vertex -887.421 339.607 361.498 + endloop + endfacet + facet normal -0.302881 -0.120772 0.945345 + outer loop + vertex -887.016 339.215 361.577 + vertex -888.048 341.731 361.568 + vertex -887.421 339.607 361.498 + endloop + endfacet + facet normal -0.310234 -0.129089 0.941855 + outer loop + vertex -885.907 336.446 361.563 + vertex -887.016 339.215 361.577 + vertex -887.421 339.607 361.498 + endloop + endfacet + facet normal -0.406024 -0.195305 0.892749 + outer loop + vertex -882.055 328.333 361.567 + vertex -883.36 331.072 361.572 + vertex -881.25 326.403 361.51 + endloop + endfacet + facet normal -0.247005 -0.177066 0.952699 + outer loop + vertex -871.391 310.782 361.58 + vertex -873.275 313.384 361.575 + vertex -873.366 313.151 361.508 + endloop + endfacet + facet normal -0.566572 -0.805844 0.17208 + outer loop + vertex -860.362 232.235 317.209 + vertex -860.272 232.729 319.817 + vertex -861.139 233.022 318.335 + endloop + endfacet + facet normal -0.634017 -0.772346 -0.0387763 + outer loop + vertex -859.214 231.432 314.444 + vertex -860.362 232.235 317.209 + vertex -860.816 232.624 316.873 + endloop + endfacet + facet normal -0.517265 -0.837419 -0.176536 + outer loop + vertex -857.746 231.059 311.909 + vertex -859.214 231.432 314.444 + vertex -858.828 231.472 313.12 + endloop + endfacet + facet normal -0.522396 -0.690056 -0.500925 + outer loop + vertex -856.343 231.534 309.792 + vertex -857.746 231.059 311.909 + vertex -857.424 231.518 310.941 + endloop + endfacet + facet normal -0.446022 -0.618529 -0.646905 + outer loop + vertex -854.62 232.704 307.485 + vertex -856.343 231.534 309.792 + vertex -855.984 232.244 308.865 + endloop + endfacet + facet normal -0.284906 -0.622719 -0.728731 + outer loop + vertex -848.286 242.207 296.733 + vertex -850.001 240.376 298.969 + vertex -850.754 242.423 297.514 + endloop + endfacet + facet normal -0.639519 -0.470206 -0.608212 + outer loop + vertex -857.424 231.518 310.941 + vertex -855.984 232.244 308.865 + vertex -856.343 231.534 309.792 + endloop + endfacet + facet normal -0.667326 -0.712613 -0.21647 + outer loop + vertex -860.083 232.036 315.131 + vertex -858.828 231.472 313.12 + vertex -859.214 231.432 314.444 + endloop + endfacet + facet normal -0.723945 -0.498471 -0.476897 + outer loop + vertex -858.828 231.472 313.12 + vertex -857.424 231.518 310.941 + vertex -857.746 231.059 311.909 + endloop + endfacet + facet normal -0.679991 -0.684668 0.262378 + outer loop + vertex -862.096 234.288 319.16 + vertex -861.139 233.022 318.335 + vertex -860.272 232.729 319.817 + endloop + endfacet + facet normal -0.672268 -0.738464 0.0522212 + outer loop + vertex -861.139 233.022 318.335 + vertex -860.816 232.624 316.873 + vertex -860.362 232.235 317.209 + endloop + endfacet + facet normal -0.343892 -0.615057 -0.709537 + outer loop + vertex -851.962 239.462 300.712 + vertex -851.424 241.251 298.9 + vertex -850.001 240.376 298.969 + endloop + endfacet + facet normal -0.350442 -0.624789 -0.697731 + outer loop + vertex -851.424 241.251 298.9 + vertex -850.754 242.423 297.514 + vertex -850.001 240.376 298.969 + endloop + endfacet + facet normal -0.357045 -0.646502 -0.674206 + outer loop + vertex -850.754 242.423 297.514 + vertex -852.693 244.163 296.873 + vertex -851.034 243.773 296.368 + endloop + endfacet + facet normal -0.422428 -0.673623 -0.606455 + outer loop + vertex -852.693 244.163 296.873 + vertex -855.438 246.348 296.358 + vertex -853.36 245.421 295.94 + endloop + endfacet + facet normal -0.680108 -0.669223 0.299323 + outer loop + vertex -863.66 237.604 323.019 + vertex -862.096 234.288 319.16 + vertex -860.272 232.729 319.817 + endloop + endfacet + facet normal -0.64423 -0.653446 0.397462 + outer loop + vertex -863.607 240.502 327.871 + vertex -863.66 237.604 323.019 + vertex -856.976 231.577 323.944 + endloop + endfacet + facet normal -0.591515 -0.594656 0.544513 + outer loop + vertex -862.456 246.355 336.263 + vertex -863.135 243.187 332.065 + vertex -858.715 239.727 333.089 + endloop + endfacet + facet normal -0.474104 -0.449442 0.757118 + outer loop + vertex -860.108 265.353 352.591 + vertex -860.154 260.501 349.682 + vertex -856.65 259.009 350.991 + endloop + endfacet + facet normal -0.405236 -0.401629 0.821266 + outer loop + vertex -858.809 268.997 355.014 + vertex -860.108 265.353 352.591 + vertex -855.281 261.032 352.86 + endloop + endfacet + facet normal -0.380368 -0.332622 0.86295 + outer loop + vertex -858.301 274.21 357.247 + vertex -858.809 268.997 355.014 + vertex -855.255 267.411 355.97 + endloop + endfacet + facet normal -0.309534 -0.264892 0.913247 + outer loop + vertex -858.206 279.747 358.886 + vertex -858.301 274.21 357.247 + vertex -854.95 273.153 358.076 + endloop + endfacet + facet normal -0.237235 -0.214649 0.947441 + outer loop + vertex -856.983 283.585 360.061 + vertex -858.206 279.747 358.886 + vertex -853.757 275.811 359.108 + endloop + endfacet + facet normal -0.191905 -0.173134 0.966021 + outer loop + vertex -856.941 288.325 360.919 + vertex -856.983 283.585 360.061 + vertex -852.709 280.903 360.43 + endloop + endfacet + facet normal -0.481988 -0.69149 -0.53808 + outer loop + vertex -855.438 246.348 296.358 + vertex -858.709 249.031 295.84 + vertex -856.224 247.63 295.414 + endloop + endfacet + facet normal -0.538347 -0.696633 -0.474221 + outer loop + vertex -858.709 249.031 295.84 + vertex -861.956 251.929 295.269 + vertex -859.387 250.19 294.906 + endloop + endfacet + facet normal -0.593424 -0.694646 -0.40659 + outer loop + vertex -861.956 251.929 295.269 + vertex -867.002 255.942 295.777 + vertex -864.065 254.22 294.432 + endloop + endfacet + facet normal -0.655797 -0.654591 -0.376087 + outer loop + vertex -867.002 255.942 295.777 + vertex -872.85 262.144 295.179 + vertex -868.617 258.414 294.292 + endloop + endfacet + facet normal -0.225341 -0.158743 0.961261 + outer loop + vertex -873.366 313.151 361.508 + vertex -868.807 306.517 361.481 + vertex -871.391 310.782 361.58 + endloop + endfacet + facet normal -0.712402 -0.618097 -0.332324 + outer loop + vertex -872.85 262.144 295.179 + vertex -878.427 268.758 294.833 + vertex -875.136 265.618 293.618 + endloop + endfacet + facet normal -0.270029 -0.16878 0.947944 + outer loop + vertex -877.506 319.83 361.518 + vertex -873.366 313.151 361.508 + vertex -875.775 317.351 361.569 + endloop + endfacet + facet normal -0.760289 -0.565662 -0.319354 + outer loop + vertex -878.427 268.758 294.833 + vertex -883.384 275.562 294.583 + vertex -880.23 272.014 293.36 + endloop + endfacet + facet normal -0.261781 -0.148077 0.9537 + outer loop + vertex -881.25 326.403 361.51 + vertex -877.506 319.83 361.518 + vertex -879.765 324.131 361.565 + endloop + endfacet + facet normal -0.803285 -0.511541 -0.305055 + outer loop + vertex -883.384 275.562 294.583 + vertex -887.903 282.67 294.564 + vertex -884.979 278.931 293.133 + endloop + endfacet + facet normal -0.251648 -0.126445 0.959523 + outer loop + vertex -884.452 332.694 361.5 + vertex -881.25 326.403 361.51 + vertex -883.36 331.072 361.572 + endloop + endfacet + facet normal -0.843042 -0.454021 -0.288349 + outer loop + vertex -887.903 282.67 294.564 + vertex -891.683 289.858 294.296 + vertex -888.961 285.611 293.028 + endloop + endfacet + facet normal -0.376286 -0.161345 0.912347 + outer loop + vertex -887.421 339.607 361.498 + vertex -884.452 332.694 361.5 + vertex -885.907 336.446 361.563 + endloop + endfacet + facet normal -0.886888 -0.38871 -0.24967 + outer loop + vertex -891.683 289.858 294.296 + vertex -895.272 298.092 294.227 + vertex -892.704 293.038 292.973 + endloop + endfacet + facet normal -0.392293 -0.135312 0.909833 + outer loop + vertex -889.837 346.634 361.501 + vertex -887.421 339.607 361.498 + vertex -889.219 345.334 361.574 + endloop + endfacet + facet normal -0.923388 -0.321848 -0.209211 + outer loop + vertex -895.272 298.092 294.227 + vertex -898.222 306.47 294.357 + vertex -896.501 302.341 293.116 + endloop + endfacet + facet normal -0.354434 -0.100581 0.929656 + outer loop + vertex -891.599 353.015 361.52 + vertex -889.837 346.634 361.501 + vertex -891.013 351.536 361.583 + endloop + endfacet + facet normal -0.94916 -0.244009 -0.198885 + outer loop + vertex -898.222 306.47 294.357 + vertex -900.193 314.278 294.184 + vertex -898.798 309.702 293.141 + endloop + endfacet + facet normal -0.442699 -0.0992416 0.891162 + outer loop + vertex -892.952 358.912 361.504 + vertex -891.599 353.015 361.52 + vertex -892.34 356.842 361.578 + endloop + endfacet + facet normal -0.965081 -0.170021 -0.199279 + outer loop + vertex -900.193 314.278 294.184 + vertex -901.705 322.663 294.352 + vertex -900.643 318.156 293.058 + endloop + endfacet + facet normal -0.502589 -0.0789957 0.860909 + outer loop + vertex -894.053 365.911 361.504 + vertex -892.952 358.912 361.504 + vertex -893.311 362.02 361.58 + endloop + endfacet + facet normal -0.974314 -0.0984455 -0.202537 + outer loop + vertex -901.705 322.663 294.352 + vertex -902.528 330.738 294.386 + vertex -901.785 326.003 293.115 + endloop + endfacet + facet normal -0.634088 -0.0560936 0.771224 + outer loop + vertex -894.633 372.356 361.496 + vertex -894.053 365.911 361.504 + vertex -894.451 371.34 361.571 + endloop + endfacet + facet normal -0.978713 -0.0336042 -0.202461 + outer loop + vertex -902.528 330.738 294.386 + vertex -902.782 339.214 294.21 + vertex -902.372 333.802 293.124 + endloop + endfacet + facet normal -0.558393 -0.0133203 0.82947 + outer loop + vertex -894.766 378.453 361.504 + vertex -894.633 372.356 361.496 + vertex -894.598 376.559 361.587 + endloop + endfacet + facet normal -0.974843 0.0190255 -0.222077 + outer loop + vertex -902.782 339.214 294.21 + vertex -902.641 348.151 294.357 + vertex -902.397 343.924 292.924 + endloop + endfacet + facet normal -0.510912 0.0149513 0.859503 + outer loop + vertex -895.951 381.948 360.738 + vertex -896.141 375.752 360.732 + vertex -894.998 384.008 361.268 + endloop + endfacet + facet normal -0.588996 0.0161178 0.807976 + outer loop + vertex -894.604 384.31 361.505 + vertex -894.766 378.453 361.504 + vertex -894.523 382.935 361.592 + endloop + endfacet + facet normal -0.521772 0.0168836 0.852918 + outer loop + vertex -895.187 378.065 361.27 + vertex -894.998 384.008 361.268 + vertex -896.141 375.752 360.732 + endloop + endfacet + facet normal -0.970956 0.0628264 -0.230862 + outer loop + vertex -902.641 348.151 294.357 + vertex -902.107 356.363 294.346 + vertex -902.042 352.061 292.903 + endloop + endfacet + facet normal -0.737011 0.0514839 0.673917 + outer loop + vertex -894.213 389.878 361.508 + vertex -894.604 384.31 361.505 + vertex -894.265 388.139 361.584 + endloop + endfacet + facet normal -0.967664 0.100862 -0.231201 + outer loop + vertex -902.107 356.363 294.346 + vertex -901.28 364.31 294.348 + vertex -901.383 359.952 292.881 + endloop + endfacet + facet normal -0.666901 0.0726982 0.741591 + outer loop + vertex -893.613 395.406 361.506 + vertex -894.213 389.878 361.508 + vertex -893.77 393.074 361.593 + endloop + endfacet + facet normal -0.963875 0.133448 -0.230515 + outer loop + vertex -901.28 364.31 294.348 + vertex -900.188 372.233 294.372 + vertex -900.46 367.704 292.888 + endloop + endfacet + facet normal -0.67503 0.0952511 0.731616 + outer loop + vertex -892.83 400.933 361.509 + vertex -893.613 395.406 361.506 + vertex -892.985 399.182 361.593 + endloop + endfacet + facet normal -0.959689 0.160612 -0.230654 + outer loop + vertex -900.188 372.233 294.372 + vertex -898.845 380.242 294.358 + vertex -899.287 375.516 292.908 + endloop + endfacet + facet normal -0.752362 0.127638 0.646266 + outer loop + vertex -891.935 406.214 361.507 + vertex -892.83 400.933 361.509 + vertex -892.208 404.206 361.586 + endloop + endfacet + facet normal -0.695829 0.136201 0.705175 + outer loop + vertex -890.875 411.697 361.494 + vertex -891.935 406.214 361.507 + vertex -891.318 408.937 361.59 + endloop + endfacet + facet normal -0.704473 0.154602 0.692688 + outer loop + vertex -889.604 417.448 361.503 + vertex -890.875 411.697 361.494 + vertex -890.081 414.915 361.583 + endloop + endfacet + facet normal -0.565776 0.143556 0.811966 + outer loop + vertex -881.391 449.517 361.517 + vertex -882.689 444.324 361.531 + vertex -881.615 448.257 361.584 + endloop + endfacet + facet normal -0.939527 0.250275 0.233775 + outer loop + vertex -882.196 461.248 353.791 + vertex -881.714 460.911 356.089 + vertex -880.757 465.266 355.274 + endloop + endfacet + facet normal -0.913055 0.240795 0.329164 + outer loop + vertex -881.714 460.911 356.089 + vertex -881.103 460.609 358.007 + vertex -880.281 464.674 357.311 + endloop + endfacet + facet normal -0.870883 0.220063 0.439471 + outer loop + vertex -881.103 460.609 358.007 + vertex -880.27 460.743 359.589 + vertex -879.713 464.185 358.97 + endloop + endfacet + facet normal -0.812398 0.19778 0.548537 + outer loop + vertex -880.27 460.743 359.589 + vertex -879.867 459.757 360.541 + vertex -879.096 463.242 360.426 + endloop + endfacet + facet normal -0.636763 0.154579 0.755406 + outer loop + vertex -879.566 457.881 361.336 + vertex -880.283 454.337 361.456 + vertex -879.569 457.409 361.43 + endloop + endfacet + facet normal -0.935283 0.228825 -0.269972 + outer loop + vertex -878.718 463.765 304.406 + vertex -879.743 465.301 309.258 + vertex -879.101 464.997 306.777 + endloop + endfacet + facet normal -0.983166 0.0663654 -0.170235 + outer loop + vertex -879.743 465.301 309.258 + vertex -880.47 466.897 314.079 + vertex -880.121 466.697 311.986 + endloop + endfacet + facet normal -0.977206 0.162961 -0.136056 + outer loop + vertex -880.47 466.897 314.079 + vertex -880.881 468.035 318.397 + vertex -880.641 468.445 317.163 + endloop + endfacet + facet normal -0.980378 0.17741 -0.0859315 + outer loop + vertex -880.881 468.035 318.397 + vertex -881.083 468.931 322.547 + vertex -880.835 469.159 320.193 + endloop + endfacet + facet normal -0.977689 0.204815 -0.0466299 + outer loop + vertex -881.083 468.931 322.547 + vertex -881.216 469.269 326.816 + vertex -881.015 469.734 324.651 + endloop + endfacet + facet normal -0.969566 0.229352 0.0856729 + outer loop + vertex -881.146 468.77 345.88 + vertex -880.9 468.609 349.087 + vertex -880.886 469.398 347.139 + endloop + endfacet + facet normal -0.955933 0.262145 0.132183 + outer loop + vertex -880.9 468.609 349.087 + vertex -880.609 468.161 352.083 + vertex -880.499 469.022 351.167 + endloop + endfacet + facet normal -0.92085 0.337712 0.194903 + outer loop + vertex -880.609 468.161 352.083 + vertex -880.357 467.594 354.253 + vertex -880.115 468.395 354.01 + endloop + endfacet + facet normal -0.921922 0.256912 0.289926 + outer loop + vertex -880.281 464.674 357.311 + vertex -880.757 465.266 355.274 + vertex -881.714 460.911 356.089 + endloop + endfacet + facet normal -0.894943 0.353393 0.272377 + outer loop + vertex -880.357 467.594 354.253 + vertex -879.965 467.102 356.181 + vertex -880.115 468.395 354.01 + endloop + endfacet + facet normal -0.892713 0.245073 0.378157 + outer loop + vertex -879.713 464.185 358.97 + vertex -880.281 464.674 357.311 + vertex -881.103 460.609 358.007 + endloop + endfacet + facet normal -0.899991 0.280039 0.334057 + outer loop + vertex -879.965 467.102 356.181 + vertex -879.484 466.222 358.214 + vertex -879.615 467.272 356.982 + endloop + endfacet + facet normal -0.861068 0.221733 0.457598 + outer loop + vertex -879.202 464.159 359.944 + vertex -879.713 464.185 358.97 + vertex -880.27 460.743 359.589 + endloop + endfacet + facet normal -0.897723 0.191992 0.396525 + outer loop + vertex -879.484 466.222 358.214 + vertex -879.015 465.433 359.658 + vertex -879.144 466.083 359.052 + endloop + endfacet + facet normal -0.811226 0.196496 0.550729 + outer loop + vertex -879.096 463.242 360.426 + vertex -879.202 464.159 359.944 + vertex -880.27 460.743 359.589 + endloop + endfacet + facet normal -0.715386 0.363417 0.596784 + outer loop + vertex -879.015 465.433 359.658 + vertex -878.826 464.8 360.27 + vertex -878.617 464.889 360.467 + endloop + endfacet + facet normal -0.322525 0.138193 0.936419 + outer loop + vertex -878.361 463.893 361.071 + vertex -878.44 463.366 361.121 + vertex -878.305 464.056 361.066 + endloop + endfacet + facet normal -0.691736 0.168269 0.702272 + outer loop + vertex -878.44 463.366 361.121 + vertex -878.753 462.816 360.945 + vertex -878.808 461.315 361.25 + endloop + endfacet + facet normal -0.759824 0.193141 0.620778 + outer loop + vertex -878.753 462.816 360.945 + vertex -878.402 464.159 360.956 + vertex -878.617 464.889 360.467 + endloop + endfacet + facet normal -0.608238 0.232545 0.758927 + outer loop + vertex -878.402 464.159 360.956 + vertex -878.361 463.893 361.071 + vertex -878.305 464.056 361.066 + endloop + endfacet + facet normal -0.401958 -0.705572 -0.583607 + outer loop + vertex -854.621 246.762 295.246 + vertex -854.78 247.448 294.526 + vertex -852.452 245.275 295.55 + endloop + endfacet + facet normal -0.38256 -0.696078 -0.607556 + outer loop + vertex -852.452 245.275 295.55 + vertex -854.78 247.448 294.526 + vertex -852.412 245.966 294.733 + endloop + endfacet + facet normal -0.350078 -0.706656 -0.614884 + outer loop + vertex -852.452 245.275 295.55 + vertex -852.412 245.966 294.733 + vertex -850.545 244.199 295.701 + endloop + endfacet + facet normal -0.340254 -0.702105 -0.625521 + outer loop + vertex -850.545 244.199 295.701 + vertex -852.412 245.966 294.733 + vertex -850.953 245.269 294.722 + endloop + endfacet + facet normal -0.302209 -0.743362 -0.596727 + outer loop + vertex -851.04 246.409 293.408 + vertex -851.576 248.453 291.133 + vertex -850.216 246.201 293.25 + endloop + endfacet + facet normal -0.292679 -0.742757 -0.602205 + outer loop + vertex -850.216 246.201 293.25 + vertex -851.576 248.453 291.133 + vertex -851.019 248.709 290.547 + endloop + endfacet + facet normal -0.336915 -0.721951 -0.60438 + outer loop + vertex -850.953 245.269 294.722 + vertex -851.04 246.409 293.408 + vertex -849.804 244.462 295.045 + endloop + endfacet + facet normal -0.301687 -0.718427 -0.626775 + outer loop + vertex -849.804 244.462 295.045 + vertex -851.04 246.409 293.408 + vertex -850.216 246.201 293.25 + endloop + endfacet + facet normal -0.401312 -0.743552 -0.534864 + outer loop + vertex -854.968 248.584 293.169 + vertex -855.268 250.235 291.099 + vertex -852.635 247.221 293.312 + endloop + endfacet + facet normal -0.376983 -0.739277 -0.55799 + outer loop + vertex -852.635 247.221 293.312 + vertex -855.268 250.235 291.099 + vertex -853.021 249.027 291.182 + endloop + endfacet + facet normal -0.40702 -0.727488 -0.552355 + outer loop + vertex -854.78 247.448 294.526 + vertex -854.968 248.584 293.169 + vertex -852.412 245.966 294.733 + endloop + endfacet + facet normal -0.385412 -0.72067 -0.576275 + outer loop + vertex -852.412 245.966 294.733 + vertex -854.968 248.584 293.169 + vertex -852.635 247.221 293.312 + endloop + endfacet + facet normal -0.3524 -0.728066 -0.587992 + outer loop + vertex -852.412 245.966 294.733 + vertex -852.635 247.221 293.312 + vertex -850.953 245.269 294.722 + endloop + endfacet + facet normal -0.331797 -0.723159 -0.605766 + outer loop + vertex -850.953 245.269 294.722 + vertex -852.635 247.221 293.312 + vertex -851.04 246.409 293.408 + endloop + endfacet + facet normal -0.345586 -0.74594 -0.569336 + outer loop + vertex -852.635 247.221 293.312 + vertex -853.021 249.027 291.182 + vertex -851.04 246.409 293.408 + endloop + endfacet + facet normal -0.314054 -0.741803 -0.592536 + outer loop + vertex -851.04 246.409 293.408 + vertex -853.021 249.027 291.182 + vertex -851.576 248.453 291.133 + endloop + endfacet + facet normal -0.533842 -0.720557 -0.442504 + outer loop + vertex -861.737 253.656 292.568 + vertex -860.971 254.045 291.01 + vertex -857.936 250.585 292.982 + endloop + endfacet + facet normal -0.507403 -0.717313 -0.477498 + outer loop + vertex -857.936 250.585 292.982 + vertex -860.971 254.045 291.01 + vertex -858.108 252.013 291.02 + endloop + endfacet + facet normal -0.515458 -0.70213 -0.49124 + outer loop + vertex -861.733 252.631 294.028 + vertex -861.737 253.656 292.568 + vertex -857.839 249.54 294.359 + endloop + endfacet + facet normal -0.512391 -0.701194 -0.495764 + outer loop + vertex -857.839 249.54 294.359 + vertex -861.737 253.656 292.568 + vertex -857.936 250.585 292.982 + endloop + endfacet + facet normal -0.465019 -0.720817 -0.513984 + outer loop + vertex -857.839 249.54 294.359 + vertex -857.936 250.585 292.982 + vertex -854.78 247.448 294.526 + endloop + endfacet + facet normal -0.448449 -0.715094 -0.536222 + outer loop + vertex -854.78 247.448 294.526 + vertex -857.936 250.585 292.982 + vertex -854.968 248.584 293.169 + endloop + endfacet + facet normal -0.46449 -0.73494 -0.494078 + outer loop + vertex -857.936 250.585 292.982 + vertex -858.108 252.013 291.02 + vertex -854.968 248.584 293.169 + endloop + endfacet + facet normal -0.443285 -0.731008 -0.518773 + outer loop + vertex -854.968 248.584 293.169 + vertex -858.108 252.013 291.02 + vertex -855.268 250.235 291.099 + endloop + endfacet + facet normal -0.560113 -0.695986 -0.449307 + outer loop + vertex -860.971 254.045 291.01 + vertex -861.737 253.656 292.568 + vertex -865.543 259.006 289.025 + endloop + endfacet + facet normal -0.57056 -0.67303 -0.470628 + outer loop + vertex -861.733 252.631 294.028 + vertex -866.92 257.937 292.728 + vertex -861.737 253.656 292.568 + endloop + endfacet + facet normal -0.586186 -0.693916 -0.418169 + outer loop + vertex -866.92 257.937 292.728 + vertex -865.543 259.006 289.025 + vertex -861.737 253.656 292.568 + endloop + endfacet + facet normal -0.646194 -0.653345 -0.394427 + outer loop + vertex -872.938 264.271 292.095 + vertex -871.409 264.758 288.783 + vertex -866.92 257.937 292.728 + endloop + endfacet + facet normal -0.625888 -0.655907 -0.421959 + outer loop + vertex -866.92 257.937 292.728 + vertex -871.409 264.758 288.783 + vertex -865.543 259.006 289.025 + endloop + endfacet + facet normal -0.696459 -0.607538 -0.381894 + outer loop + vertex -877.856 269.93 292.063 + vertex -876.531 270.57 288.628 + vertex -872.938 264.271 292.095 + endloop + endfacet + facet normal -0.680806 -0.610866 -0.40416 + outer loop + vertex -872.938 264.271 292.095 + vertex -876.531 270.57 288.628 + vertex -871.409 264.758 288.783 + endloop + endfacet + facet normal -0.743231 -0.557069 -0.370516 + outer loop + vertex -882.579 276.389 291.825 + vertex -881.106 276.656 288.469 + vertex -877.856 269.93 292.063 + endloop + endfacet + facet normal -0.732207 -0.560506 -0.386918 + outer loop + vertex -877.856 269.93 292.063 + vertex -881.106 276.656 288.469 + vertex -876.531 270.57 288.628 + endloop + endfacet + facet normal -0.784769 -0.503033 -0.36207 + outer loop + vertex -886.854 283.301 291.488 + vertex -885.299 283.192 288.269 + vertex -882.579 276.389 291.825 + endloop + endfacet + facet normal -0.773303 -0.507706 -0.379786 + outer loop + vertex -882.579 276.389 291.825 + vertex -885.299 283.192 288.269 + vertex -881.106 276.656 288.469 + endloop + endfacet + facet normal -0.814908 -0.450245 -0.364971 + outer loop + vertex -890.62 290.026 291.601 + vertex -889.062 289.977 288.183 + vertex -886.854 283.301 291.488 + endloop + endfacet + facet normal -0.808563 -0.453231 -0.375243 + outer loop + vertex -886.854 283.301 291.488 + vertex -889.062 289.977 288.183 + vertex -885.299 283.192 288.269 + endloop + endfacet + facet normal -0.849217 -0.38661 -0.359671 + outer loop + vertex -893.78 297.173 291.379 + vertex -892.331 297.001 288.142 + vertex -890.62 290.026 291.601 + endloop + endfacet + facet normal -0.838996 -0.392588 -0.376776 + outer loop + vertex -890.62 290.026 291.601 + vertex -892.331 297.001 288.142 + vertex -889.062 289.977 288.183 + endloop + endfacet + facet normal -0.877468 -0.324384 -0.353305 + outer loop + vertex -896.345 304.139 291.353 + vertex -895.06 304.21 288.098 + vertex -893.78 297.173 291.379 + endloop + endfacet + facet normal -0.867742 -0.330825 -0.370917 + outer loop + vertex -893.78 297.173 291.379 + vertex -895.06 304.21 288.098 + vertex -892.331 297.001 288.142 + endloop + endfacet + facet normal -0.899614 -0.264105 -0.347768 + outer loop + vertex -898.613 311.668 291.502 + vertex -897.27 311.572 288.103 + vertex -896.345 304.139 291.353 + endloop + endfacet + facet normal -0.894118 -0.268181 -0.358653 + outer loop + vertex -896.345 304.139 291.353 + vertex -897.27 311.572 288.103 + vertex -895.06 304.21 288.098 + endloop + endfacet + facet normal -0.922676 -0.194318 -0.333032 + outer loop + vertex -900.181 319.453 291.306 + vertex -898.949 319.117 288.089 + vertex -898.613 311.668 291.502 + endloop + endfacet + facet normal -0.912554 -0.20374 -0.354592 + outer loop + vertex -898.613 311.668 291.502 + vertex -898.949 319.117 288.089 + vertex -897.27 311.572 288.103 + endloop + endfacet + facet normal -0.938882 -0.129339 -0.319017 + outer loop + vertex -901.229 327.087 291.295 + vertex -900.078 326.694 288.066 + vertex -900.181 319.453 291.306 + endloop + endfacet + facet normal -0.929514 -0.139486 -0.341389 + outer loop + vertex -900.181 319.453 291.306 + vertex -900.078 326.694 288.066 + vertex -898.949 319.117 288.089 + endloop + endfacet + facet normal -0.229124 -0.796645 -0.559337 + outer loop + vertex -852.271 250.809 288.355 + vertex -852.939 253.09 285.38 + vertex -851.817 251.049 287.828 + endloop + endfacet + facet normal -0.266937 -0.796772 -0.542124 + outer loop + vertex -851.817 251.049 287.828 + vertex -852.939 253.09 285.38 + vertex -852.375 253.032 285.188 + endloop + endfacet + facet normal -0.263026 -0.767339 -0.584814 + outer loop + vertex -851.576 248.453 291.133 + vertex -852.271 250.809 288.355 + vertex -851.019 248.709 290.547 + endloop + endfacet + facet normal -0.269831 -0.767681 -0.581255 + outer loop + vertex -851.019 248.709 290.547 + vertex -852.271 250.809 288.355 + vertex -851.817 251.049 287.828 + endloop + endfacet + facet normal -0.376411 -0.782019 -0.496751 + outer loop + vertex -855.652 252.233 288.451 + vertex -856.073 254.347 285.442 + vertex -853.557 251.208 288.478 + endloop + endfacet + facet normal -0.35407 -0.781099 -0.514314 + outer loop + vertex -853.557 251.208 288.478 + vertex -856.073 254.347 285.442 + vertex -854.134 253.466 285.446 + endloop + endfacet + facet normal -0.390231 -0.76116 -0.51803 + outer loop + vertex -855.268 250.235 291.099 + vertex -855.652 252.233 288.451 + vertex -853.021 249.027 291.182 + endloop + endfacet + facet normal -0.364455 -0.758692 -0.539962 + outer loop + vertex -853.021 249.027 291.182 + vertex -855.652 252.233 288.451 + vertex -853.557 251.208 288.478 + endloop + endfacet + facet normal -0.322722 -0.766842 -0.554801 + outer loop + vertex -853.021 249.027 291.182 + vertex -853.557 251.208 288.478 + vertex -851.576 248.453 291.133 + endloop + endfacet + facet normal -0.292188 -0.764268 -0.57491 + outer loop + vertex -851.576 248.453 291.133 + vertex -853.557 251.208 288.478 + vertex -852.271 250.809 288.355 + endloop + endfacet + facet normal -0.296845 -0.792077 -0.533382 + outer loop + vertex -853.557 251.208 288.478 + vertex -854.134 253.466 285.446 + vertex -852.271 250.809 288.355 + endloop + endfacet + facet normal -0.279119 -0.79129 -0.544015 + outer loop + vertex -852.271 250.809 288.355 + vertex -854.134 253.466 285.446 + vertex -852.939 253.09 285.38 + endloop + endfacet + facet normal -0.518792 -0.74317 -0.422555 + outer loop + vertex -861.59 256.115 288.376 + vertex -861.138 257.248 285.828 + vertex -858.344 253.794 288.473 + endloop + endfacet + facet normal -0.500722 -0.7439 -0.442595 + outer loop + vertex -858.344 253.794 288.473 + vertex -861.138 257.248 285.828 + vertex -858.59 255.71 285.531 + endloop + endfacet + facet normal -0.515373 -0.728423 -0.451432 + outer loop + vertex -860.971 254.045 291.01 + vertex -861.59 256.115 288.376 + vertex -858.108 252.013 291.02 + endloop + endfacet + facet normal -0.506673 -0.727874 -0.462042 + outer loop + vertex -858.108 252.013 291.02 + vertex -861.59 256.115 288.376 + vertex -858.344 253.794 288.473 + endloop + endfacet + facet normal -0.455484 -0.748828 -0.481448 + outer loop + vertex -858.108 252.013 291.02 + vertex -858.344 253.794 288.473 + vertex -855.268 250.235 291.099 + endloop + endfacet + facet normal -0.43714 -0.747155 -0.500668 + outer loop + vertex -855.268 250.235 291.099 + vertex -858.344 253.794 288.473 + vertex -855.652 252.233 288.451 + endloop + endfacet + facet normal -0.447714 -0.765947 -0.461386 + outer loop + vertex -858.344 253.794 288.473 + vertex -858.59 255.71 285.531 + vertex -855.652 252.233 288.451 + endloop + endfacet + facet normal -0.431204 -0.765538 -0.477509 + outer loop + vertex -855.652 252.233 288.451 + vertex -858.59 255.71 285.531 + vertex -856.073 254.347 285.442 + endloop + endfacet + facet normal -0.557098 -0.717593 -0.417974 + outer loop + vertex -861.138 257.248 285.828 + vertex -861.59 256.115 288.376 + vertex -865.215 261.583 283.819 + endloop + endfacet + facet normal -0.580538 -0.700863 -0.414447 + outer loop + vertex -860.971 254.045 291.01 + vertex -865.543 259.006 289.025 + vertex -861.59 256.115 288.376 + endloop + endfacet + facet normal -0.584483 -0.71189 -0.389348 + outer loop + vertex -865.543 259.006 289.025 + vertex -865.215 261.583 283.819 + vertex -861.59 256.115 288.376 + endloop + endfacet + facet normal -0.644236 -0.672213 -0.364815 + outer loop + vertex -871.409 264.758 288.783 + vertex -870.598 266.566 284.021 + vertex -865.543 259.006 289.025 + endloop + endfacet + facet normal -0.637541 -0.67367 -0.373778 + outer loop + vertex -865.543 259.006 289.025 + vertex -870.598 266.566 284.021 + vertex -865.215 261.583 283.819 + endloop + endfacet + facet normal -0.698088 -0.624647 -0.349986 + outer loop + vertex -876.531 270.57 288.628 + vertex -875.584 272.076 284.05 + vertex -871.409 264.758 288.783 + endloop + endfacet + facet normal -0.693948 -0.626007 -0.35574 + outer loop + vertex -871.409 264.758 288.783 + vertex -875.584 272.076 284.05 + vertex -870.598 266.566 284.021 + endloop + endfacet + facet normal -0.747994 -0.571105 -0.338148 + outer loop + vertex -881.106 276.656 288.469 + vertex -880.072 277.976 283.952 + vertex -876.531 270.57 288.628 + endloop + endfacet + facet normal -0.744994 -0.572425 -0.342511 + outer loop + vertex -876.531 270.57 288.628 + vertex -880.072 277.976 283.952 + vertex -875.584 272.076 284.05 + endloop + endfacet + facet normal -0.789213 -0.516459 -0.332285 + outer loop + vertex -885.299 283.192 288.269 + vertex -884.129 284.289 283.785 + vertex -881.106 276.656 288.469 + endloop + endfacet + facet normal -0.78963 -0.516232 -0.331646 + outer loop + vertex -881.106 276.656 288.469 + vertex -884.129 284.289 283.785 + vertex -880.072 277.976 283.952 + endloop + endfacet + facet normal -0.823601 -0.461 -0.330394 + outer loop + vertex -889.062 289.977 288.183 + vertex -887.8 290.953 283.675 + vertex -885.299 283.192 288.269 + endloop + endfacet + facet normal -0.825168 -0.460005 -0.32786 + outer loop + vertex -885.299 283.192 288.269 + vertex -887.8 290.953 283.675 + vertex -884.129 284.289 283.785 + endloop + endfacet + facet normal -0.856046 -0.40023 -0.327111 + outer loop + vertex -892.331 297.001 288.142 + vertex -891.031 297.917 283.62 + vertex -889.062 289.977 288.183 + endloop + endfacet + facet normal -0.856477 -0.399912 -0.326372 + outer loop + vertex -889.062 289.977 288.183 + vertex -891.031 297.917 283.62 + vertex -887.8 290.953 283.675 + endloop + endfacet + facet normal -0.884959 -0.337048 -0.32132 + outer loop + vertex -895.06 304.21 288.098 + vertex -893.77 305.109 283.6 + vertex -892.331 297.001 288.142 + endloop + endfacet + facet normal -0.884289 -0.337623 -0.322559 + outer loop + vertex -892.331 297.001 288.142 + vertex -893.77 305.109 283.6 + vertex -891.031 297.917 283.62 + endloop + endfacet + facet normal -0.909287 -0.272759 -0.314324 + outer loop + vertex -897.27 311.572 288.103 + vertex -895.976 312.459 283.588 + vertex -895.06 304.21 288.098 + endloop + endfacet + facet normal -0.908758 -0.273286 -0.315396 + outer loop + vertex -895.06 304.21 288.098 + vertex -895.976 312.459 283.588 + vertex -893.77 305.109 283.6 + endloop + endfacet + facet normal -0.929167 -0.207348 -0.306033 + outer loop + vertex -898.949 319.117 288.089 + vertex -897.64 319.903 283.581 + vertex -897.27 311.572 288.103 + endloop + endfacet + facet normal -0.928669 -0.20793 -0.307145 + outer loop + vertex -897.27 311.572 288.103 + vertex -897.64 319.903 283.581 + vertex -895.976 312.459 283.588 + endloop + endfacet + facet normal -0.944477 -0.141577 -0.296513 + outer loop + vertex -900.078 326.694 288.066 + vertex -898.773 327.393 283.578 + vertex -898.949 319.117 288.089 + endloop + endfacet + facet normal -0.943498 -0.142935 -0.298965 + outer loop + vertex -898.949 319.117 288.089 + vertex -898.773 327.393 283.578 + vertex -897.64 319.903 283.581 + endloop + endfacet + facet normal -0.218967 -0.844593 -0.488586 + outer loop + vertex -853.524 255.262 282.202 + vertex -854.015 257.295 278.908 + vertex -853.051 255.392 281.764 + endloop + endfacet + facet normal -0.240057 -0.843401 -0.480673 + outer loop + vertex -853.051 255.392 281.764 + vertex -854.015 257.295 278.908 + vertex -853.562 257.323 278.631 + endloop + endfacet + facet normal -0.258966 -0.819021 -0.511997 + outer loop + vertex -852.939 253.09 285.38 + vertex -853.524 255.262 282.202 + vertex -852.375 253.032 285.188 + endloop + endfacet + facet normal -0.250723 -0.819414 -0.515461 + outer loop + vertex -852.375 253.032 285.188 + vertex -853.524 255.262 282.202 + vertex -853.051 255.392 281.764 + endloop + endfacet + facet normal -0.354309 -0.823993 -0.442154 + outer loop + vertex -856.444 256.384 282.245 + vertex -856.755 258.293 278.937 + vertex -854.64 255.606 282.249 + endloop + endfacet + facet normal -0.336715 -0.824873 -0.454101 + outer loop + vertex -854.64 255.606 282.249 + vertex -856.755 258.293 278.937 + vertex -855.064 257.598 278.945 + endloop + endfacet + facet normal -0.364561 -0.803997 -0.46977 + outer loop + vertex -856.073 254.347 285.442 + vertex -856.444 256.384 282.245 + vertex -854.134 253.466 285.446 + endloop + endfacet + facet normal -0.345666 -0.804166 -0.483562 + outer loop + vertex -854.134 253.466 285.446 + vertex -856.444 256.384 282.245 + vertex -854.64 255.606 282.249 + endloop + endfacet + facet normal -0.284807 -0.816827 -0.501676 + outer loop + vertex -854.134 253.466 285.446 + vertex -854.64 255.606 282.249 + vertex -852.939 253.09 285.38 + endloop + endfacet + facet normal -0.27352 -0.816871 -0.507847 + outer loop + vertex -852.939 253.09 285.38 + vertex -854.64 255.606 282.249 + vertex -853.524 255.262 282.202 + endloop + endfacet + facet normal -0.27837 -0.837926 -0.469457 + outer loop + vertex -854.64 255.606 282.249 + vertex -855.064 257.598 278.945 + vertex -853.524 255.262 282.202 + endloop + endfacet + facet normal -0.259582 -0.838639 -0.478854 + outer loop + vertex -853.524 255.262 282.202 + vertex -855.064 257.598 278.945 + vertex -854.015 257.295 278.908 + endloop + endfacet + facet normal -0.512395 -0.770068 -0.380062 + outer loop + vertex -861.737 259.489 282.491 + vertex -861.309 260.687 279.487 + vertex -858.82 257.611 282.363 + endloop + endfacet + facet normal -0.499697 -0.771907 -0.393018 + outer loop + vertex -858.82 257.611 282.363 + vertex -861.309 260.687 279.487 + vertex -858.999 259.404 279.069 + endloop + endfacet + facet normal -0.504928 -0.755855 -0.416811 + outer loop + vertex -861.138 257.248 285.828 + vertex -861.737 259.489 282.491 + vertex -858.59 255.71 285.531 + endloop + endfacet + facet normal -0.504854 -0.755859 -0.416893 + outer loop + vertex -858.59 255.71 285.531 + vertex -861.737 259.489 282.491 + vertex -858.82 257.611 282.363 + endloop + endfacet + facet normal -0.439741 -0.783845 -0.438423 + outer loop + vertex -858.59 255.71 285.531 + vertex -858.82 257.611 282.363 + vertex -856.073 254.347 285.442 + endloop + endfacet + facet normal -0.427354 -0.784212 -0.449867 + outer loop + vertex -856.073 254.347 285.442 + vertex -858.82 257.611 282.363 + vertex -856.444 256.384 282.245 + endloop + endfacet + facet normal -0.434122 -0.800926 -0.412379 + outer loop + vertex -858.82 257.611 282.363 + vertex -858.999 259.404 279.069 + vertex -856.444 256.384 282.245 + endloop + endfacet + facet normal -0.421999 -0.801856 -0.423018 + outer loop + vertex -856.444 256.384 282.245 + vertex -858.999 259.404 279.069 + vertex -856.755 258.293 278.937 + endloop + endfacet + facet normal -0.563416 -0.736664 -0.374017 + outer loop + vertex -861.309 260.687 279.487 + vertex -861.737 259.489 282.491 + vertex -865.041 264.532 277.534 + endloop + endfacet + facet normal -0.579423 -0.721004 -0.38003 + outer loop + vertex -861.138 257.248 285.828 + vertex -865.215 261.583 283.819 + vertex -861.737 259.489 282.491 + endloop + endfacet + facet normal -0.578378 -0.732254 -0.359559 + outer loop + vertex -865.215 261.583 283.819 + vertex -865.041 264.532 277.534 + vertex -861.737 259.489 282.491 + endloop + endfacet + facet normal -0.645915 -0.684134 -0.338754 + outer loop + vertex -870.598 266.566 284.021 + vertex -870.056 269.015 278.042 + vertex -865.215 261.583 283.819 + endloop + endfacet + facet normal -0.645828 -0.684162 -0.338863 + outer loop + vertex -865.215 261.583 283.819 + vertex -870.056 269.015 278.042 + vertex -865.041 264.532 277.534 + endloop + endfacet + facet normal -0.702275 -0.63371 -0.324378 + outer loop + vertex -875.584 272.076 284.05 + vertex -874.804 274.169 278.273 + vertex -870.598 266.566 284.021 + endloop + endfacet + facet normal -0.703237 -0.633288 -0.323117 + outer loop + vertex -870.598 266.566 284.021 + vertex -874.804 274.169 278.273 + vertex -870.056 269.015 278.042 + endloop + endfacet + facet normal -0.752869 -0.577955 -0.314892 + outer loop + vertex -880.072 277.976 283.952 + vertex -879.13 279.86 278.244 + vertex -875.584 272.076 284.05 + endloop + endfacet + facet normal -0.755858 -0.576265 -0.3108 + outer loop + vertex -875.584 272.076 284.05 + vertex -879.13 279.86 278.244 + vertex -874.804 274.169 278.273 + endloop + endfacet + facet normal -0.796507 -0.520037 -0.308444 + outer loop + vertex -884.129 284.289 283.785 + vertex -883.044 285.998 278.103 + vertex -880.072 277.976 283.952 + endloop + endfacet + facet normal -0.800449 -0.517333 -0.302734 + outer loop + vertex -880.072 277.976 283.952 + vertex -883.044 285.998 278.103 + vertex -879.13 279.86 278.244 + endloop + endfacet + facet normal -0.831773 -0.463281 -0.305816 + outer loop + vertex -887.8 290.953 283.675 + vertex -886.583 292.523 277.985 + vertex -884.129 284.289 283.785 + endloop + endfacet + facet normal -0.836902 -0.459208 -0.297863 + outer loop + vertex -884.129 284.289 283.785 + vertex -886.583 292.523 277.985 + vertex -883.044 285.998 278.103 + endloop + endfacet + facet normal -0.863454 -0.402968 -0.30342 + outer loop + vertex -891.031 297.917 283.62 + vertex -889.712 299.386 277.918 + vertex -887.8 290.953 283.675 + endloop + endfacet + facet normal -0.868036 -0.398787 -0.295773 + outer loop + vertex -887.8 290.953 283.675 + vertex -889.712 299.386 277.918 + vertex -886.583 292.523 277.985 + endloop + endfacet + facet normal -0.891412 -0.340271 -0.299334 + outer loop + vertex -893.77 305.109 283.6 + vertex -892.387 306.507 277.895 + vertex -891.031 297.917 283.62 + endloop + endfacet + facet normal -0.894571 -0.336953 -0.293607 + outer loop + vertex -891.031 297.917 283.62 + vertex -892.387 306.507 277.895 + vertex -889.712 299.386 277.918 + endloop + endfacet + facet normal -0.915606 -0.275306 -0.293038 + outer loop + vertex -895.976 312.459 283.588 + vertex -894.556 313.798 277.894 + vertex -893.77 305.109 283.6 + endloop + endfacet + facet normal -0.917543 -0.272941 -0.28917 + outer loop + vertex -893.77 305.109 283.6 + vertex -894.556 313.798 277.894 + vertex -892.387 306.507 277.895 + endloop + endfacet + facet normal -0.934819 -0.209286 -0.286902 + outer loop + vertex -897.64 319.903 283.581 + vertex -896.175 321.174 277.88 + vertex -895.976 312.459 283.588 + endloop + endfacet + facet normal -0.936962 -0.206196 -0.28211 + outer loop + vertex -895.976 312.459 283.588 + vertex -896.175 321.174 277.88 + vertex -894.556 313.798 277.894 + endloop + endfacet + facet normal -0.94948 -0.14383 -0.278928 + outer loop + vertex -898.773 327.393 283.578 + vertex -897.282 328.583 277.885 + vertex -897.64 319.903 283.581 + endloop + endfacet + facet normal -0.950659 -0.141814 -0.275929 + outer loop + vertex -897.64 319.903 283.581 + vertex -897.282 328.583 277.885 + vertex -896.175 321.174 277.88 + endloop + endfacet + facet normal -0.333315 -0.855143 -0.397029 + outer loop + vertex -857.011 260.072 275.573 + vertex -857.195 261.728 272.162 + vertex -855.396 259.434 275.592 + endloop + endfacet + facet normal -0.323305 -0.856199 -0.402985 + outer loop + vertex -855.396 259.434 275.592 + vertex -857.195 261.728 272.162 + vertex -855.647 261.167 272.112 + endloop + endfacet + facet normal -0.343413 -0.840757 -0.418563 + outer loop + vertex -856.755 258.293 278.937 + vertex -857.011 260.072 275.573 + vertex -855.064 257.598 278.945 + endloop + endfacet + facet normal -0.327738 -0.841996 -0.428522 + outer loop + vertex -855.064 257.598 278.945 + vertex -857.011 260.072 275.573 + vertex -855.396 259.434 275.592 + endloop + endfacet + facet normal -0.263603 -0.856884 -0.443017 + outer loop + vertex -855.064 257.598 278.945 + vertex -855.396 259.434 275.592 + vertex -854.015 257.295 278.908 + endloop + endfacet + facet normal -0.261804 -0.857006 -0.443845 + outer loop + vertex -854.015 257.295 278.908 + vertex -855.396 259.434 275.592 + vertex -854.386 259.127 275.588 + endloop + endfacet + facet normal -0.26579 -0.870489 -0.414251 + outer loop + vertex -855.396 259.434 275.592 + vertex -855.647 261.167 272.112 + vertex -854.386 259.127 275.588 + endloop + endfacet + facet normal -0.269652 -0.870081 -0.41261 + outer loop + vertex -854.386 259.127 275.588 + vertex -855.647 261.167 272.112 + vertex -854.667 260.985 271.854 + endloop + endfacet + facet normal -0.510195 -0.79051 -0.338815 + outer loop + vertex -861.807 262.735 275.885 + vertex -861.367 263.813 272.709 + vertex -859.142 261.095 275.699 + endloop + endfacet + facet normal -0.494163 -0.794048 -0.353965 + outer loop + vertex -859.142 261.095 275.699 + vertex -861.367 263.813 272.709 + vertex -859.244 262.679 272.288 + endloop + endfacet + facet normal -0.50097 -0.780218 -0.374551 + outer loop + vertex -861.309 260.687 279.487 + vertex -861.807 262.735 275.885 + vertex -858.999 259.404 279.069 + endloop + endfacet + facet normal -0.505597 -0.779525 -0.369746 + outer loop + vertex -858.999 259.404 279.069 + vertex -861.807 262.735 275.885 + vertex -859.142 261.095 275.699 + endloop + endfacet + facet normal -0.426817 -0.815407 -0.391073 + outer loop + vertex -858.999 259.404 279.069 + vertex -859.142 261.095 275.699 + vertex -856.755 258.293 278.937 + endloop + endfacet + facet normal -0.415754 -0.816645 -0.4003 + outer loop + vertex -856.755 258.293 278.937 + vertex -859.142 261.095 275.699 + vertex -857.011 260.072 275.573 + endloop + endfacet + facet normal -0.419533 -0.82802 -0.371988 + outer loop + vertex -859.142 261.095 275.699 + vertex -859.244 262.679 272.288 + vertex -857.011 260.072 275.573 + endloop + endfacet + facet normal -0.408707 -0.829541 -0.380552 + outer loop + vertex -857.011 260.072 275.573 + vertex -859.244 262.679 272.288 + vertex -857.195 261.728 272.162 + endloop + endfacet + facet normal -0.573219 -0.748553 -0.333298 + outer loop + vertex -861.367 263.813 272.709 + vertex -861.807 262.735 275.885 + vertex -864.814 267.342 270.709 + endloop + endfacet + facet normal -0.583128 -0.738143 -0.339275 + outer loop + vertex -861.309 260.687 279.487 + vertex -865.041 264.532 277.534 + vertex -861.807 262.735 275.885 + endloop + endfacet + facet normal -0.580793 -0.745749 -0.326402 + outer loop + vertex -865.041 264.532 277.534 + vertex -864.814 267.342 270.709 + vertex -861.807 262.735 275.885 + endloop + endfacet + facet normal -0.650825 -0.693009 -0.310106 + outer loop + vertex -870.056 269.015 278.042 + vertex -869.541 271.529 271.341 + vertex -865.041 264.532 277.534 + endloop + endfacet + facet normal -0.653755 -0.691804 -0.306614 + outer loop + vertex -865.041 264.532 277.534 + vertex -869.541 271.529 271.341 + vertex -864.814 267.342 270.709 + endloop + endfacet + facet normal -0.708322 -0.639012 -0.299906 + outer loop + vertex -874.804 274.169 278.273 + vertex -874.039 276.421 271.669 + vertex -870.056 269.015 278.042 + endloop + endfacet + facet normal -0.713343 -0.636327 -0.293649 + outer loop + vertex -870.056 269.015 278.042 + vertex -874.039 276.421 271.669 + vertex -869.541 271.529 271.341 + endloop + endfacet + facet normal -0.760488 -0.579692 -0.292601 + outer loop + vertex -879.13 279.86 278.244 + vertex -878.169 281.909 271.684 + vertex -874.804 274.169 278.273 + endloop + endfacet + facet normal -0.766279 -0.575803 -0.285073 + outer loop + vertex -874.804 274.169 278.273 + vertex -878.169 281.909 271.684 + vertex -874.039 276.421 271.669 + endloop + endfacet + facet normal -0.804317 -0.519472 -0.288484 + outer loop + vertex -883.044 285.998 278.103 + vertex -881.916 287.89 271.548 + vertex -879.13 279.86 278.244 + endloop + endfacet + facet normal -0.810805 -0.514256 -0.27953 + outer loop + vertex -879.13 279.86 278.244 + vertex -881.916 287.89 271.548 + vertex -878.169 281.909 271.684 + endloop + endfacet + facet normal -0.84007 -0.460719 -0.28639 + outer loop + vertex -886.583 292.523 277.985 + vertex -885.311 294.281 271.425 + vertex -883.044 285.998 278.103 + endloop + endfacet + facet normal -0.846328 -0.454925 -0.277078 + outer loop + vertex -883.044 285.998 278.103 + vertex -885.311 294.281 271.425 + vertex -881.916 287.89 271.548 + endloop + endfacet + facet normal -0.871306 -0.400164 -0.284069 + outer loop + vertex -889.712 299.386 277.918 + vertex -888.327 301.023 271.362 + vertex -886.583 292.523 277.985 + endloop + endfacet + facet normal -0.876432 -0.394744 -0.275761 + outer loop + vertex -886.583 292.523 277.985 + vertex -888.327 301.023 271.362 + vertex -885.311 294.281 271.425 + endloop + endfacet + facet normal -0.897911 -0.33817 -0.281775 + outer loop + vertex -892.387 306.507 277.895 + vertex -890.909 308.043 271.339 + vertex -889.712 299.386 277.918 + endloop + endfacet + facet normal -0.902402 -0.332726 -0.273795 + outer loop + vertex -889.712 299.386 277.918 + vertex -890.909 308.043 271.339 + vertex -888.327 301.023 271.362 + endloop + endfacet + facet normal -0.920751 -0.273893 -0.277849 + outer loop + vertex -894.556 313.798 277.894 + vertex -893.008 315.246 271.337 + vertex -892.387 306.507 277.895 + endloop + endfacet + facet normal -0.923962 -0.26938 -0.271531 + outer loop + vertex -892.387 306.507 277.895 + vertex -893.008 315.246 271.337 + vertex -890.909 308.043 271.339 + endloop + endfacet + facet normal -0.940016 -0.206847 -0.271263 + outer loop + vertex -896.175 321.174 277.88 + vertex -894.588 322.539 271.339 + vertex -894.556 313.798 277.894 + endloop + endfacet + facet normal -0.941773 -0.203924 -0.267357 + outer loop + vertex -894.556 313.798 277.894 + vertex -894.588 322.539 271.339 + vertex -893.008 315.246 271.337 + endloop + endfacet + facet normal -0.953326 -0.142218 -0.266352 + outer loop + vertex -897.282 328.583 277.885 + vertex -895.642 329.864 271.331 + vertex -896.175 321.174 277.88 + endloop + endfacet + facet normal -0.955565 -0.137756 -0.260614 + outer loop + vertex -896.175 321.174 277.88 + vertex -895.642 329.864 271.331 + vertex -894.588 322.539 271.339 + endloop + endfacet + facet normal -0.32248 -0.878999 -0.351236 + outer loop + vertex -857.301 263.299 268.619 + vertex -857.349 264.847 264.791 + vertex -855.8 262.86 268.341 + endloop + endfacet + facet normal -0.333505 -0.87719 -0.345415 + outer loop + vertex -855.8 262.86 268.341 + vertex -857.349 264.847 264.791 + vertex -855.903 264.576 264.081 + endloop + endfacet + facet normal -0.326519 -0.867536 -0.37519 + outer loop + vertex -857.195 261.728 272.162 + vertex -857.301 263.299 268.619 + vertex -855.647 261.167 272.112 + endloop + endfacet + facet normal -0.323932 -0.867883 -0.376626 + outer loop + vertex -855.647 261.167 272.112 + vertex -857.301 263.299 268.619 + vertex -855.8 262.86 268.341 + endloop + endfacet + facet normal -0.265173 -0.883544 -0.386048 + outer loop + vertex -855.647 261.167 272.112 + vertex -855.8 262.86 268.341 + vertex -854.667 260.985 271.854 + endloop + endfacet + facet normal -0.268064 -0.883166 -0.384914 + outer loop + vertex -854.667 260.985 271.854 + vertex -855.8 262.86 268.341 + vertex -854.888 262.849 267.73 + endloop + endfacet + facet normal -0.249408 -0.900293 -0.356747 + outer loop + vertex -855.8 262.86 268.341 + vertex -855.903 264.576 264.081 + vertex -854.888 262.849 267.73 + endloop + endfacet + facet normal -0.25838 -0.89899 -0.353635 + outer loop + vertex -854.888 262.849 267.73 + vertex -855.903 264.576 264.081 + vertex -855.052 264.457 263.764 + endloop + endfacet + facet normal -0.50333 -0.807123 -0.308563 + outer loop + vertex -861.781 265.654 268.991 + vertex -861.31 266.613 265.712 + vertex -859.296 264.169 268.821 + endloop + endfacet + facet normal -0.487832 -0.811397 -0.321956 + outer loop + vertex -859.296 264.169 268.821 + vertex -861.31 266.613 265.712 + vertex -859.288 265.593 265.22 + endloop + endfacet + facet normal -0.494501 -0.799569 -0.34082 + outer loop + vertex -861.367 263.813 272.709 + vertex -861.781 265.654 268.991 + vertex -859.244 262.679 272.288 + endloop + endfacet + facet normal -0.499956 -0.798398 -0.335565 + outer loop + vertex -859.244 262.679 272.288 + vertex -861.781 265.654 268.991 + vertex -859.296 264.169 268.821 + endloop + endfacet + facet normal -0.411735 -0.839501 -0.35456 + outer loop + vertex -859.244 262.679 272.288 + vertex -859.296 264.169 268.821 + vertex -857.195 261.728 272.162 + endloop + endfacet + facet normal -0.403007 -0.840944 -0.361107 + outer loop + vertex -857.195 261.728 272.162 + vertex -859.296 264.169 268.821 + vertex -857.301 263.299 268.619 + endloop + endfacet + facet normal -0.404568 -0.850125 -0.337065 + outer loop + vertex -859.296 264.169 268.821 + vertex -859.288 265.593 265.22 + vertex -857.301 263.299 268.619 + endloop + endfacet + facet normal -0.402218 -0.850573 -0.338742 + outer loop + vertex -857.301 263.299 268.619 + vertex -859.288 265.593 265.22 + vertex -857.349 264.847 264.791 + endloop + endfacet + facet normal -0.574619 -0.759512 -0.304884 + outer loop + vertex -861.31 266.613 265.712 + vertex -861.781 265.654 268.991 + vertex -864.531 269.895 263.607 + endloop + endfacet + facet normal -0.589354 -0.748166 -0.304809 + outer loop + vertex -861.367 263.813 272.709 + vertex -864.814 267.342 270.709 + vertex -861.781 265.654 268.991 + endloop + endfacet + facet normal -0.586872 -0.754235 -0.294466 + outer loop + vertex -864.814 267.342 270.709 + vertex -864.531 269.895 263.607 + vertex -861.781 265.654 268.991 + endloop + endfacet + facet normal -0.656829 -0.698789 -0.283318 + outer loop + vertex -869.541 271.529 271.341 + vertex -868.989 273.889 264.243 + vertex -864.814 267.342 270.709 + endloop + endfacet + facet normal -0.662804 -0.695871 -0.276505 + outer loop + vertex -864.814 267.342 270.709 + vertex -868.989 273.889 264.243 + vertex -864.531 269.895 263.607 + endloop + endfacet + facet normal -0.716571 -0.640459 -0.276294 + outer loop + vertex -874.039 276.421 271.669 + vertex -873.241 278.581 264.593 + vertex -869.541 271.529 271.341 + endloop + endfacet + facet normal -0.723812 -0.635977 -0.267639 + outer loop + vertex -869.541 271.529 271.341 + vertex -873.241 278.581 264.593 + vertex -868.989 273.889 264.243 + endloop + endfacet + facet normal -0.769368 -0.578165 -0.271658 + outer loop + vertex -878.169 281.909 271.684 + vertex -877.166 283.891 264.627 + vertex -874.039 276.421 271.669 + endloop + endfacet + facet normal -0.776811 -0.572491 -0.262334 + outer loop + vertex -874.039 276.421 271.669 + vertex -877.166 283.891 264.627 + vertex -873.241 278.581 264.593 + endloop + endfacet + facet normal -0.813694 -0.515805 -0.268044 + outer loop + vertex -881.916 287.89 271.548 + vertex -880.753 289.718 264.502 + vertex -878.169 281.909 271.684 + endloop + endfacet + facet normal -0.819873 -0.510228 -0.25976 + outer loop + vertex -878.169 281.909 271.684 + vertex -880.753 289.718 264.502 + vertex -877.166 283.891 264.627 + endloop + endfacet + facet normal -0.848712 -0.456013 -0.267842 + outer loop + vertex -885.311 294.281 271.425 + vertex -883.999 295.983 264.372 + vertex -881.916 287.89 271.548 + endloop + endfacet + facet normal -0.855741 -0.448728 -0.257585 + outer loop + vertex -881.916 287.89 271.548 + vertex -883.999 295.983 264.372 + vertex -880.753 289.718 264.502 + endloop + endfacet + facet normal -0.878728 -0.395689 -0.26696 + outer loop + vertex -888.327 301.023 271.362 + vertex -886.9 302.609 264.312 + vertex -885.311 294.281 271.425 + endloop + endfacet + facet normal -0.884116 -0.389356 -0.258342 + outer loop + vertex -885.311 294.281 271.425 + vertex -886.9 302.609 264.312 + vertex -883.999 295.983 264.372 + endloop + endfacet + facet normal -0.904696 -0.33354 -0.265097 + outer loop + vertex -890.909 308.043 271.339 + vertex -889.391 309.522 264.3 + vertex -888.327 301.023 271.362 + endloop + endfacet + facet normal -0.908809 -0.328012 -0.257825 + outer loop + vertex -888.327 301.023 271.362 + vertex -889.391 309.522 264.3 + vertex -886.9 302.609 264.312 + endloop + endfacet + facet normal -0.926438 -0.2701 -0.262218 + outer loop + vertex -893.008 315.246 271.337 + vertex -891.42 316.626 264.304 + vertex -890.909 308.043 271.339 + endloop + endfacet + facet normal -0.929533 -0.265281 -0.256114 + outer loop + vertex -890.909 308.043 271.339 + vertex -891.42 316.626 264.304 + vertex -889.391 309.522 264.3 + endloop + endfacet + facet normal -0.944098 -0.20443 -0.258624 + outer loop + vertex -894.588 322.539 271.339 + vertex -892.939 323.826 264.305 + vertex -893.008 315.246 271.337 + endloop + endfacet + facet normal -0.946622 -0.199778 -0.252974 + outer loop + vertex -893.008 315.246 271.337 + vertex -892.939 323.826 264.305 + vertex -891.42 316.626 264.304 + endloop + endfacet + facet normal -0.957559 -0.138035 -0.253034 + outer loop + vertex -895.642 329.864 271.331 + vertex -893.957 331.062 264.303 + vertex -894.588 322.539 271.339 + endloop + endfacet + facet normal -0.958957 -0.134925 -0.249392 + outer loop + vertex -894.588 322.539 271.339 + vertex -893.957 331.062 264.303 + vertex -892.939 323.826 264.305 + endloop + endfacet + facet normal -0.325855 -0.887471 -0.325906 + outer loop + vertex -857.349 264.847 264.791 + vertex -857.396 266.416 260.565 + vertex -855.903 264.576 264.081 + endloop + endfacet + facet normal -0.249779 -0.911894 -0.325668 + outer loop + vertex -855.052 264.457 263.764 + vertex -855.903 264.576 264.081 + vertex -855.953 266.656 258.297 + endloop + endfacet + facet normal -0.332698 -0.891988 -0.306054 + outer loop + vertex -857.649 267.835 256.705 + vertex -855.953 266.656 258.297 + vertex -857.396 266.416 260.565 + endloop + endfacet + facet normal -0.347496 -0.883347 -0.314556 + outer loop + vertex -855.903 264.576 264.081 + vertex -857.396 266.416 260.565 + vertex -855.953 266.656 258.297 + endloop + endfacet + facet normal -0.499152 -0.82078 -0.27779 + outer loop + vertex -861.619 268.296 261.795 + vertex -861.108 269.169 258.295 + vertex -859.244 266.978 261.419 + endloop + endfacet + facet normal -0.489517 -0.823862 -0.2857 + outer loop + vertex -859.244 266.978 261.419 + vertex -861.108 269.169 258.295 + vertex -859.218 268.308 257.54 + endloop + endfacet + facet normal -0.487467 -0.81559 -0.311751 + outer loop + vertex -861.31 266.613 265.712 + vertex -861.619 268.296 261.795 + vertex -859.288 265.593 265.22 + endloop + endfacet + facet normal -0.498451 -0.812636 -0.301943 + outer loop + vertex -859.288 265.593 265.22 + vertex -861.619 268.296 261.795 + vertex -859.244 266.978 261.419 + endloop + endfacet + facet normal -0.400912 -0.859225 -0.317807 + outer loop + vertex -859.288 265.593 265.22 + vertex -859.244 266.978 261.419 + vertex -857.349 264.847 264.791 + endloop + endfacet + facet normal -0.406242 -0.858087 -0.314091 + outer loop + vertex -857.349 264.847 264.791 + vertex -859.244 266.978 261.419 + vertex -857.396 266.416 260.565 + endloop + endfacet + facet normal -0.401679 -0.865469 -0.29936 + outer loop + vertex -859.244 266.978 261.419 + vertex -859.218 268.308 257.54 + vertex -857.396 266.416 260.565 + endloop + endfacet + facet normal -0.414445 -0.86266 -0.289919 + outer loop + vertex -857.396 266.416 260.565 + vertex -859.218 268.308 257.54 + vertex -857.649 267.835 256.705 + endloop + endfacet + facet normal -0.578736 -0.767364 -0.276073 + outer loop + vertex -861.108 269.169 258.295 + vertex -861.619 268.296 261.795 + vertex -864.166 272.221 256.222 + endloop + endfacet + facet normal -0.589898 -0.757807 -0.278834 + outer loop + vertex -861.31 266.613 265.712 + vertex -864.531 269.895 263.607 + vertex -861.619 268.296 261.795 + endloop + endfacet + facet normal -0.587098 -0.763362 -0.269433 + outer loop + vertex -864.531 269.895 263.607 + vertex -864.166 272.221 256.222 + vertex -861.619 268.296 261.795 + endloop + endfacet + facet normal -0.664847 -0.701161 -0.25759 + outer loop + vertex -868.989 273.889 264.243 + vertex -868.424 276.049 256.905 + vertex -864.531 269.895 263.607 + endloop + endfacet + facet normal -0.668885 -0.69892 -0.253188 + outer loop + vertex -864.531 269.895 263.607 + vertex -868.424 276.049 256.905 + vertex -864.166 272.221 256.222 + endloop + endfacet + facet normal -0.726357 -0.639452 -0.252004 + outer loop + vertex -873.241 278.581 264.593 + vertex -872.457 280.576 257.269 + vertex -868.989 273.889 264.243 + endloop + endfacet + facet normal -0.733922 -0.6342 -0.243207 + outer loop + vertex -868.989 273.889 264.243 + vertex -872.457 280.576 257.269 + vertex -868.424 276.049 256.905 + endloop + endfacet + facet normal -0.779791 -0.574785 -0.248089 + outer loop + vertex -877.166 283.891 264.627 + vertex -876.192 285.723 257.322 + vertex -873.241 278.581 264.593 + endloop + endfacet + facet normal -0.786966 -0.56873 -0.239229 + outer loop + vertex -873.241 278.581 264.593 + vertex -876.192 285.723 257.322 + vertex -872.457 280.576 257.269 + endloop + endfacet + facet normal -0.822628 -0.51167 -0.247946 + outer loop + vertex -880.753 289.718 264.502 + vertex -879.606 291.413 257.199 + vertex -877.166 283.891 264.627 + endloop + endfacet + facet normal -0.830818 -0.503545 -0.23703 + outer loop + vertex -877.166 283.891 264.627 + vertex -879.606 291.413 257.199 + vertex -876.192 285.723 257.322 + endloop + endfacet + facet normal -0.858296 -0.449832 -0.246941 + outer loop + vertex -883.999 295.983 264.372 + vertex -882.723 297.554 257.076 + vertex -880.753 289.718 264.502 + endloop + endfacet + facet normal -0.864004 -0.44336 -0.238597 + outer loop + vertex -880.753 289.718 264.502 + vertex -882.723 297.554 257.076 + vertex -879.606 291.413 257.199 + endloop + endfacet + facet normal -0.886668 -0.390377 -0.247842 + outer loop + vertex -886.9 302.609 264.312 + vertex -885.507 304.076 257.021 + vertex -883.999 295.983 264.372 + endloop + endfacet + facet normal -0.892432 -0.382981 -0.238518 + outer loop + vertex -883.999 295.983 264.372 + vertex -885.507 304.076 257.021 + vertex -882.723 297.554 257.076 + endloop + endfacet + facet normal -0.911538 -0.328976 -0.246725 + outer loop + vertex -889.391 309.522 264.3 + vertex -887.914 310.891 257.019 + vertex -886.9 302.609 264.312 + endloop + endfacet + facet normal -0.915364 -0.323389 -0.239848 + outer loop + vertex -886.9 302.609 264.312 + vertex -887.914 310.891 257.019 + vertex -885.507 304.076 257.021 + endloop + endfacet + facet normal -0.932158 -0.266037 -0.245573 + outer loop + vertex -891.42 316.626 264.304 + vertex -889.867 317.901 257.03 + vertex -889.391 309.522 264.3 + endloop + endfacet + facet normal -0.935575 -0.260251 -0.23868 + outer loop + vertex -889.391 309.522 264.3 + vertex -889.867 317.901 257.03 + vertex -887.914 310.891 257.019 + endloop + endfacet + facet normal -0.94938 -0.200361 -0.241937 + outer loop + vertex -892.939 323.826 264.305 + vertex -891.337 325.011 257.036 + vertex -891.42 316.626 264.304 + endloop + endfacet + facet normal -0.951317 -0.196472 -0.237474 + outer loop + vertex -891.42 316.626 264.304 + vertex -891.337 325.011 257.036 + vertex -889.867 317.901 257.03 + endloop + endfacet + facet normal -0.961812 -0.135323 -0.237917 + outer loop + vertex -893.957 331.062 264.303 + vertex -892.314 332.16 257.035 + vertex -892.939 323.826 264.305 + endloop + endfacet + facet normal -0.963334 -0.131621 -0.233804 + outer loop + vertex -892.939 323.826 264.305 + vertex -892.314 332.16 257.035 + vertex -891.337 325.011 257.036 + endloop + endfacet + facet normal -0.353901 -0.891425 -0.283048 + outer loop + vertex -857.649 267.835 256.705 + vertex -857.357 268.885 253.033 + vertex -855.953 266.656 258.297 + endloop + endfacet + facet normal -0.330787 -0.903556 -0.272336 + outer loop + vertex -857.507 270.169 248.953 + vertex -855.94 269.223 250.19 + vertex -857.357 268.885 253.033 + endloop + endfacet + facet normal -0.354654 -0.891217 -0.282759 + outer loop + vertex -855.94 269.223 250.19 + vertex -855.953 266.656 258.297 + vertex -857.357 268.885 253.033 + endloop + endfacet + facet normal -0.50049 -0.828847 -0.250047 + outer loop + vertex -861.356 270.691 254.241 + vertex -860.824 271.446 250.673 + vertex -859.124 269.499 253.723 + endloop + endfacet + facet normal -0.494002 -0.83118 -0.255153 + outer loop + vertex -859.124 269.499 253.723 + vertex -860.824 271.446 250.673 + vertex -859.007 270.607 249.887 + endloop + endfacet + facet normal -0.48848 -0.826335 -0.280282 + outer loop + vertex -861.108 269.169 258.295 + vertex -861.356 270.691 254.241 + vertex -859.218 268.308 257.54 + endloop + endfacet + facet normal -0.501408 -0.822329 -0.269008 + outer loop + vertex -859.218 268.308 257.54 + vertex -861.356 270.691 254.241 + vertex -859.124 269.499 253.723 + endloop + endfacet + facet normal -0.411007 -0.867301 -0.280823 + outer loop + vertex -859.218 268.308 257.54 + vertex -859.124 269.499 253.723 + vertex -857.649 267.835 256.705 + endloop + endfacet + facet normal -0.411203 -0.867249 -0.280697 + outer loop + vertex -857.649 267.835 256.705 + vertex -859.124 269.499 253.723 + vertex -857.357 268.885 253.033 + endloop + endfacet + facet normal -0.407377 -0.874 -0.264893 + outer loop + vertex -859.124 269.499 253.723 + vertex -859.007 270.607 249.887 + vertex -857.357 268.885 253.033 + endloop + endfacet + facet normal -0.415903 -0.8717 -0.25916 + outer loop + vertex -857.357 268.885 253.033 + vertex -859.007 270.607 249.887 + vertex -857.507 270.169 248.953 + endloop + endfacet + facet normal -0.581321 -0.774149 -0.250517 + outer loop + vertex -860.824 271.446 250.673 + vertex -861.356 270.691 254.241 + vertex -863.75 274.291 248.671 + endloop + endfacet + facet normal -0.593364 -0.764861 -0.250813 + outer loop + vertex -861.108 269.169 258.295 + vertex -864.166 272.221 256.222 + vertex -861.356 270.691 254.241 + endloop + endfacet + facet normal -0.590611 -0.769364 -0.24343 + outer loop + vertex -864.166 272.221 256.222 + vertex -863.75 274.291 248.671 + vertex -861.356 270.691 254.241 + endloop + endfacet + facet normal -0.670375 -0.703813 -0.235042 + outer loop + vertex -868.424 276.049 256.905 + vertex -867.845 278.007 249.391 + vertex -864.166 272.221 256.222 + endloop + endfacet + facet normal -0.675879 -0.700456 -0.229235 + outer loop + vertex -864.166 272.221 256.222 + vertex -867.845 278.007 249.391 + vertex -863.75 274.291 248.671 + endloop + endfacet + facet normal -0.735904 -0.637086 -0.229277 + outer loop + vertex -872.457 280.576 257.269 + vertex -871.706 282.405 249.776 + vertex -868.424 276.049 256.905 + endloop + endfacet + facet normal -0.742367 -0.632172 -0.221921 + outer loop + vertex -868.424 276.049 256.905 + vertex -871.706 282.405 249.776 + vertex -867.845 278.007 249.391 + endloop + endfacet + facet normal -0.789147 -0.570433 -0.227711 + outer loop + vertex -876.192 285.723 257.322 + vertex -875.264 287.422 249.847 + vertex -872.457 280.576 257.269 + endloop + endfacet + facet normal -0.797644 -0.562625 -0.217294 + outer loop + vertex -872.457 280.576 257.269 + vertex -875.264 287.422 249.847 + vertex -871.706 282.405 249.776 + endloop + endfacet + facet normal -0.833142 -0.504704 -0.226159 + outer loop + vertex -879.606 291.413 257.199 + vertex -878.534 292.982 249.748 + vertex -876.192 285.723 257.322 + endloop + endfacet + facet normal -0.839645 -0.497708 -0.217446 + outer loop + vertex -876.192 285.723 257.322 + vertex -878.534 292.982 249.748 + vertex -875.264 287.422 249.847 + endloop + endfacet + facet normal -0.866553 -0.444425 -0.227097 + outer loop + vertex -882.723 297.554 257.076 + vertex -881.522 299.014 249.636 + vertex -879.606 291.413 257.199 + endloop + endfacet + facet normal -0.872991 -0.436536 -0.217539 + outer loop + vertex -879.606 291.413 257.199 + vertex -881.522 299.014 249.636 + vertex -878.534 292.982 249.748 + endloop + endfacet + facet normal -0.894949 -0.38396 -0.227246 + outer loop + vertex -885.507 304.076 257.021 + vertex -884.205 305.439 249.59 + vertex -882.723 297.554 257.076 + endloop + endfacet + facet normal -0.89975 -0.377309 -0.21929 + outer loop + vertex -882.723 297.554 257.076 + vertex -884.205 305.439 249.59 + vertex -881.522 299.014 249.636 + endloop + endfacet + facet normal -0.918135 -0.324366 -0.227628 + outer loop + vertex -887.914 310.891 257.019 + vertex -886.525 312.168 249.596 + vertex -885.507 304.076 257.021 + endloop + endfacet + facet normal -0.922307 -0.317798 -0.219898 + outer loop + vertex -885.507 304.076 257.021 + vertex -886.525 312.168 249.596 + vertex -884.205 305.439 249.59 + endloop + endfacet + facet normal -0.938456 -0.261071 -0.226148 + outer loop + vertex -889.867 317.901 257.03 + vertex -888.412 319.095 249.613 + vertex -887.914 310.891 257.019 + endloop + endfacet + facet normal -0.941307 -0.255857 -0.22018 + outer loop + vertex -887.914 310.891 257.019 + vertex -888.412 319.095 249.613 + vertex -886.525 312.168 249.596 + endloop + endfacet + facet normal -0.95438 -0.197116 -0.224284 + outer loop + vertex -891.337 325.011 257.036 + vertex -889.824 326.122 249.621 + vertex -889.867 317.901 257.03 + endloop + endfacet + facet normal -0.956736 -0.191996 -0.218616 + outer loop + vertex -889.867 317.901 257.03 + vertex -889.824 326.122 249.621 + vertex -888.412 319.095 249.613 + endloop + endfacet + facet normal -0.966445 -0.132044 -0.220335 + outer loop + vertex -892.314 332.16 257.035 + vertex -890.764 333.19 249.622 + vertex -891.337 325.011 257.036 + endloop + endfacet + facet normal -0.967704 -0.128711 -0.216755 + outer loop + vertex -891.337 325.011 257.036 + vertex -890.764 333.19 249.622 + vertex -889.824 326.122 249.621 + endloop + endfacet + facet normal -0.349496 -0.903385 -0.24849 + outer loop + vertex -857.507 270.169 248.953 + vertex -857.221 271.069 245.28 + vertex -855.94 269.223 250.19 + endloop + endfacet + facet normal -0.331089 -0.913489 -0.236469 + outer loop + vertex -857.33 272.123 241.36 + vertex -855.962 271.388 242.285 + vertex -857.221 271.069 245.28 + endloop + endfacet + facet normal -0.356554 -0.901339 -0.24588 + outer loop + vertex -855.962 271.388 242.285 + vertex -855.94 269.223 250.19 + vertex -857.221 271.069 245.28 + endloop + endfacet + facet normal -0.503981 -0.835863 -0.217571 + outer loop + vertex -861.028 272.775 246.642 + vertex -860.496 273.367 243.132 + vertex -858.89 271.632 246.079 + endloop + endfacet + facet normal -0.496149 -0.838938 -0.223651 + outer loop + vertex -858.89 271.632 246.079 + vertex -860.496 273.367 243.132 + vertex -858.759 272.55 242.343 + endloop + endfacet + facet normal -0.492758 -0.833558 -0.249741 + outer loop + vertex -860.824 271.446 250.673 + vertex -861.028 272.775 246.642 + vertex -859.007 270.607 249.887 + endloop + endfacet + facet normal -0.505833 -0.828992 -0.23855 + outer loop + vertex -859.007 270.607 249.887 + vertex -861.028 272.775 246.642 + vertex -858.89 271.632 246.079 + endloop + endfacet + facet normal -0.410894 -0.877145 -0.248562 + outer loop + vertex -859.007 270.607 249.887 + vertex -858.89 271.632 246.079 + vertex -857.507 270.169 248.953 + endloop + endfacet + facet normal -0.413578 -0.87636 -0.246872 + outer loop + vertex -857.507 270.169 248.953 + vertex -858.89 271.632 246.079 + vertex -857.221 271.069 245.28 + endloop + endfacet + facet normal -0.408413 -0.882973 -0.231424 + outer loop + vertex -858.89 271.632 246.079 + vertex -858.759 272.55 242.343 + vertex -857.221 271.069 245.28 + endloop + endfacet + facet normal -0.417831 -0.8802 -0.225091 + outer loop + vertex -857.221 271.069 245.28 + vertex -858.759 272.55 242.343 + vertex -857.33 272.123 241.36 + endloop + endfacet + facet normal -0.590662 -0.776169 -0.220635 + outer loop + vertex -860.496 273.367 243.132 + vertex -861.028 272.775 246.642 + vertex -863.321 276.087 241.126 + endloop + endfacet + facet normal -0.596383 -0.770862 -0.223828 + outer loop + vertex -860.824 271.446 250.673 + vertex -863.75 274.291 248.671 + vertex -861.028 272.775 246.642 + endloop + endfacet + facet normal -0.594038 -0.774304 -0.218111 + outer loop + vertex -863.75 274.291 248.671 + vertex -863.321 276.087 241.126 + vertex -861.028 272.775 246.642 + endloop + endfacet + facet normal -0.676825 -0.704623 -0.213106 + outer loop + vertex -867.845 278.007 249.391 + vertex -867.262 279.744 241.796 + vertex -863.75 274.291 248.671 + endloop + endfacet + facet normal -0.684177 -0.699766 -0.205499 + outer loop + vertex -863.75 274.291 248.671 + vertex -867.262 279.744 241.796 + vertex -863.321 276.087 241.126 + endloop + endfacet + facet normal -0.744012 -0.634786 -0.208549 + outer loop + vertex -871.706 282.405 249.776 + vertex -870.984 284.058 242.172 + vertex -867.845 278.007 249.391 + endloop + endfacet + facet normal -0.750207 -0.629717 -0.201607 + outer loop + vertex -867.845 278.007 249.391 + vertex -870.984 284.058 242.172 + vertex -867.262 279.744 241.796 + endloop + endfacet + facet normal -0.799548 -0.564135 -0.206095 + outer loop + vertex -875.264 287.422 249.847 + vertex -874.407 288.98 242.258 + vertex -871.706 282.405 249.776 + endloop + endfacet + facet normal -0.806452 -0.557295 -0.197632 + outer loop + vertex -871.706 282.405 249.776 + vertex -874.407 288.98 242.258 + vertex -870.984 284.058 242.172 + endloop + endfacet + facet normal -0.841986 -0.498869 -0.205398 + outer loop + vertex -878.534 292.982 249.748 + vertex -877.551 294.438 242.183 + vertex -875.264 287.422 249.847 + endloop + endfacet + facet normal -0.848405 -0.491448 -0.19669 + outer loop + vertex -875.264 287.422 249.847 + vertex -877.551 294.438 242.183 + vertex -874.407 288.98 242.258 + endloop + endfacet + facet normal -0.875247 -0.437446 -0.206357 + outer loop + vertex -881.522 299.014 249.636 + vertex -880.424 300.378 242.087 + vertex -878.534 292.982 249.748 + endloop + endfacet + facet normal -0.881313 -0.429447 -0.197136 + outer loop + vertex -878.534 292.982 249.748 + vertex -880.424 300.378 242.087 + vertex -877.551 294.438 242.183 + endloop + endfacet + facet normal -0.902216 -0.378253 -0.2072 + outer loop + vertex -884.205 305.439 249.59 + vertex -883.011 306.719 242.05 + vertex -881.522 299.014 249.636 + endloop + endfacet + facet normal -0.907025 -0.371094 -0.198983 + outer loop + vertex -881.522 299.014 249.636 + vertex -883.011 306.719 242.05 + vertex -880.424 300.378 242.087 + endloop + endfacet + facet normal -0.924932 -0.318715 -0.207175 + outer loop + vertex -886.525 312.168 249.596 + vertex -885.252 313.37 242.063 + vertex -884.205 305.439 249.59 + endloop + endfacet + facet normal -0.928544 -0.312595 -0.200224 + outer loop + vertex -884.205 305.439 249.59 + vertex -885.252 313.37 242.063 + vertex -883.011 306.719 242.05 + endloop + endfacet + facet normal -0.944165 -0.256668 -0.206576 + outer loop + vertex -888.412 319.095 249.613 + vertex -887.071 320.224 242.083 + vertex -886.525 312.168 249.596 + endloop + endfacet + facet normal -0.947128 -0.250821 -0.200091 + outer loop + vertex -886.525 312.168 249.596 + vertex -887.071 320.224 242.083 + vertex -885.252 313.37 242.063 + endloop + endfacet + facet normal -0.959674 -0.192601 -0.204768 + outer loop + vertex -889.824 326.122 249.621 + vertex -888.429 327.177 242.092 + vertex -888.412 319.095 249.613 + endloop + endfacet + facet normal -0.961807 -0.187574 -0.19936 + outer loop + vertex -888.412 319.095 249.613 + vertex -888.429 327.177 242.092 + vertex -887.071 320.224 242.083 + endloop + endfacet + facet normal -0.970826 -0.129129 -0.202045 + outer loop + vertex -890.764 333.19 249.622 + vertex -889.328 334.171 242.093 + vertex -889.824 326.122 249.621 + endloop + endfacet + facet normal -0.97229 -0.124899 -0.197618 + outer loop + vertex -889.824 326.122 249.621 + vertex -889.328 334.171 242.093 + vertex -888.429 327.177 242.092 + endloop + endfacet + facet normal -0.955049 0.223069 -0.195248 + outer loop + vertex -861.354 462.678 242.586 + vertex -862.086 460.456 243.633 + vertex -862.627 463.772 250.067 + endloop + endfacet + facet normal -0.344567 -0.913456 -0.216496 + outer loop + vertex -857.33 272.123 241.36 + vertex -856.981 272.857 237.71 + vertex -855.962 271.388 242.285 + endloop + endfacet + facet normal -0.304524 -0.930104 -0.205357 + outer loop + vertex -856.987 273.76 233.628 + vertex -855.59 273.106 234.519 + vertex -856.981 272.857 237.71 + endloop + endfacet + facet normal -0.337704 -0.915497 -0.21868 + outer loop + vertex -855.59 273.106 234.519 + vertex -855.962 271.388 242.285 + vertex -856.981 272.857 237.71 + endloop + endfacet + facet normal -0.509411 -0.839493 -0.189084 + outer loop + vertex -860.691 274.526 239.175 + vertex -860.177 275.011 235.636 + vertex -858.613 273.388 238.627 + endloop + endfacet + facet normal -0.500434 -0.843329 -0.19586 + outer loop + vertex -858.613 273.388 238.627 + vertex -860.177 275.011 235.636 + vertex -858.451 274.197 234.734 + endloop + endfacet + facet normal -0.495617 -0.839799 -0.221588 + outer loop + vertex -860.496 273.367 243.132 + vertex -860.691 274.526 239.175 + vertex -858.759 272.55 242.343 + endloop + endfacet + facet normal -0.511328 -0.833771 -0.208252 + outer loop + vertex -858.759 272.55 242.343 + vertex -860.691 274.526 239.175 + vertex -858.613 273.388 238.627 + endloop + endfacet + facet normal -0.412879 -0.884831 -0.215881 + outer loop + vertex -858.759 272.55 242.343 + vertex -858.613 273.388 238.627 + vertex -857.33 272.123 241.36 + endloop + endfacet + facet normal -0.410701 -0.885517 -0.21722 + outer loop + vertex -857.33 272.123 241.36 + vertex -858.613 273.388 238.627 + vertex -856.981 272.857 237.71 + endloop + endfacet + facet normal -0.404273 -0.892053 -0.202002 + outer loop + vertex -858.613 273.388 238.627 + vertex -858.451 274.197 234.734 + vertex -856.981 272.857 237.71 + endloop + endfacet + facet normal -0.413525 -0.889122 -0.19611 + outer loop + vertex -856.981 272.857 237.71 + vertex -858.451 274.197 234.734 + vertex -856.987 273.76 233.628 + endloop + endfacet + facet normal -0.601048 -0.775411 -0.193596 + outer loop + vertex -860.177 275.011 235.636 + vertex -860.691 274.526 239.175 + vertex -862.976 277.697 233.57 + endloop + endfacet + facet normal -0.60409 -0.772313 -0.196491 + outer loop + vertex -860.496 273.367 243.132 + vertex -863.321 276.087 241.126 + vertex -860.691 274.526 239.175 + endloop + endfacet + facet normal -0.602485 -0.774561 -0.192529 + outer loop + vertex -863.321 276.087 241.126 + vertex -862.976 277.697 233.57 + vertex -860.691 274.526 239.175 + endloop + endfacet + facet normal -0.684947 -0.703543 -0.189407 + outer loop + vertex -867.262 279.744 241.796 + vertex -866.718 281.26 234.196 + vertex -863.321 276.087 241.126 + endloop + endfacet + facet normal -0.693942 -0.697117 -0.180201 + outer loop + vertex -863.321 276.087 241.126 + vertex -866.718 281.26 234.196 + vertex -862.976 277.697 233.57 + endloop + endfacet + facet normal -0.751613 -0.632061 -0.188617 + outer loop + vertex -870.984 284.058 242.172 + vertex -870.293 285.522 234.509 + vertex -867.262 279.744 241.796 + endloop + endfacet + facet normal -0.760243 -0.624486 -0.179019 + outer loop + vertex -867.262 279.744 241.796 + vertex -870.293 285.522 234.509 + vertex -866.718 281.26 234.196 + endloop + endfacet + facet normal -0.80824 -0.558744 -0.185887 + outer loop + vertex -874.407 288.98 242.258 + vertex -873.612 290.382 234.59 + vertex -870.984 284.058 242.172 + endloop + endfacet + facet normal -0.813775 -0.552898 -0.179093 + outer loop + vertex -870.984 284.058 242.172 + vertex -873.612 290.382 234.59 + vertex -870.293 285.522 234.509 + endloop + endfacet + facet normal -0.850278 -0.49238 -0.185981 + outer loop + vertex -877.551 294.438 242.183 + vertex -876.651 295.775 234.53 + vertex -874.407 288.98 242.258 + endloop + endfacet + facet normal -0.856546 -0.484638 -0.177353 + outer loop + vertex -874.407 288.98 242.258 + vertex -876.651 295.775 234.53 + vertex -873.612 290.382 234.59 + endloop + endfacet + facet normal -0.88343 -0.430283 -0.185494 + outer loop + vertex -880.424 300.378 242.087 + vertex -879.434 301.636 234.454 + vertex -877.551 294.438 242.183 + endloop + endfacet + facet normal -0.887954 -0.423902 -0.178449 + outer loop + vertex -877.551 294.438 242.183 + vertex -879.434 301.636 234.454 + vertex -876.651 295.775 234.53 + endloop + endfacet + facet normal -0.909352 -0.37197 -0.186326 + outer loop + vertex -883.011 306.719 242.05 + vertex -881.934 307.907 234.425 + vertex -880.424 300.378 242.087 + endloop + endfacet + facet normal -0.913686 -0.365043 -0.178664 + outer loop + vertex -880.424 300.378 242.087 + vertex -881.934 307.907 234.425 + vertex -879.434 301.636 234.454 + endloop + endfacet + facet normal -0.930927 -0.313422 -0.18746 + outer loop + vertex -885.252 313.37 242.063 + vertex -884.094 314.49 234.439 + vertex -883.011 306.719 242.05 + endloop + endfacet + facet normal -0.934799 -0.306363 -0.179701 + outer loop + vertex -883.011 306.719 242.05 + vertex -884.094 314.49 234.439 + vertex -881.934 307.907 234.425 + endloop + endfacet + facet normal -0.949715 -0.251548 -0.186456 + outer loop + vertex -887.071 320.224 242.083 + vertex -885.854 321.278 234.461 + vertex -885.252 313.37 242.063 + endloop + endfacet + facet normal -0.952171 -0.246319 -0.180822 + outer loop + vertex -885.252 313.37 242.063 + vertex -885.854 321.278 234.461 + vertex -884.094 314.49 234.439 + endloop + endfacet + facet normal -0.964533 -0.188124 -0.185163 + outer loop + vertex -888.429 327.177 242.092 + vertex -887.159 328.164 234.47 + vertex -887.071 320.224 242.083 + endloop + endfacet + facet normal -0.966586 -0.182861 -0.17965 + outer loop + vertex -887.071 320.224 242.083 + vertex -887.159 328.164 234.47 + vertex -885.854 321.278 234.461 + endloop + endfacet + facet normal -0.975103 -0.125263 -0.182985 + outer loop + vertex -889.328 334.171 242.093 + vertex -888.016 335.09 234.47 + vertex -888.429 327.177 242.092 + endloop + endfacet + facet normal -0.976506 -0.120811 -0.178439 + outer loop + vertex -888.429 327.177 242.092 + vertex -888.016 335.09 234.47 + vertex -887.159 328.164 234.47 + endloop + endfacet + facet normal -0.952235 0.249593 -0.17593 + outer loop + vertex -860.734 462.158 238.703 + vertex -860.137 461.665 234.773 + vertex -861.395 459.452 238.442 + endloop + endfacet + facet normal -0.953095 0.243328 -0.180002 + outer loop + vertex -861.395 459.452 238.442 + vertex -860.137 461.665 234.773 + vertex -860.655 459.08 234.021 + endloop + endfacet + facet normal -0.956014 0.229051 -0.18323 + outer loop + vertex -861.354 462.678 242.586 + vertex -860.734 462.158 238.703 + vertex -862.086 460.456 243.633 + endloop + endfacet + facet normal -0.952388 0.249556 -0.175155 + outer loop + vertex -862.086 460.456 243.633 + vertex -860.734 462.158 238.703 + vertex -861.395 459.452 238.442 + endloop + endfacet + facet normal -0.316759 -0.93006 -0.186154 + outer loop + vertex -856.987 273.76 233.628 + vertex -856.552 274.422 229.58 + vertex -855.59 273.106 234.519 + endloop + endfacet + facet normal -0.271806 -0.945792 -0.177762 + outer loop + vertex -856.462 275.143 225.609 + vertex -855.347 274.68 226.365 + vertex -856.552 274.422 229.58 + endloop + endfacet + facet normal -0.305182 -0.933295 -0.189272 + outer loop + vertex -855.347 274.68 226.365 + vertex -855.59 273.106 234.519 + vertex -856.552 274.422 229.58 + endloop + endfacet + facet normal -0.516332 -0.838902 -0.17218 + outer loop + vertex -860.466 276.234 231.16 + vertex -860.247 277.288 225.368 + vertex -858.272 275.069 230.261 + endloop + endfacet + facet normal -0.51377 -0.840144 -0.173778 + outer loop + vertex -858.272 275.069 230.261 + vertex -860.247 277.288 225.368 + vertex -857.86 275.85 225.266 + endloop + endfacet + facet normal -0.501074 -0.842486 -0.197845 + outer loop + vertex -860.177 275.011 235.636 + vertex -860.466 276.234 231.16 + vertex -858.451 274.197 234.734 + endloop + endfacet + facet normal -0.518862 -0.834929 -0.183508 + outer loop + vertex -858.451 274.197 234.734 + vertex -860.466 276.234 231.16 + vertex -858.272 275.069 230.261 + endloop + endfacet + facet normal -0.409978 -0.89203 -0.190264 + outer loop + vertex -858.451 274.197 234.734 + vertex -858.272 275.069 230.261 + vertex -856.987 273.76 233.628 + endloop + endfacet + facet normal -0.41053 -0.891837 -0.189978 + outer loop + vertex -856.987 273.76 233.628 + vertex -858.272 275.069 230.261 + vertex -856.552 274.422 229.58 + endloop + endfacet + facet normal -0.406122 -0.897134 -0.173824 + outer loop + vertex -858.272 275.069 230.261 + vertex -857.86 275.85 225.266 + vertex -856.552 274.422 229.58 + endloop + endfacet + facet normal -0.410938 -0.895336 -0.171768 + outer loop + vertex -856.552 274.422 229.58 + vertex -857.86 275.85 225.266 + vertex -856.462 275.143 225.609 + endloop + endfacet + facet normal -0.623366 -0.764807 -0.16274 + outer loop + vertex -860.247 277.288 225.368 + vertex -860.466 276.234 231.16 + vertex -863.078 279.471 225.955 + endloop + endfacet + facet normal -0.613447 -0.770989 -0.171051 + outer loop + vertex -860.177 275.011 235.636 + vertex -862.976 277.697 233.57 + vertex -860.466 276.234 231.16 + endloop + endfacet + facet normal -0.613618 -0.770786 -0.171352 + outer loop + vertex -862.976 277.697 233.57 + vertex -863.078 279.471 225.955 + vertex -860.466 276.234 231.16 + endloop + endfacet + facet normal -0.694427 -0.70004 -0.166478 + outer loop + vertex -866.718 281.26 234.196 + vertex -866.283 282.642 226.573 + vertex -862.976 277.697 233.57 + endloop + endfacet + facet normal -0.709771 -0.688104 -0.150791 + outer loop + vertex -862.976 277.697 233.57 + vertex -866.283 282.642 226.573 + vertex -863.078 279.471 225.955 + endloop + endfacet + facet normal -0.761497 -0.62647 -0.166305 + outer loop + vertex -870.293 285.522 234.509 + vertex -869.663 286.799 226.816 + vertex -866.718 281.26 234.196 + endloop + endfacet + facet normal -0.770885 -0.617601 -0.155902 + outer loop + vertex -866.718 281.26 234.196 + vertex -869.663 286.799 226.816 + vertex -866.283 282.642 226.573 + endloop + endfacet + facet normal -0.815566 -0.554339 -0.166014 + outer loop + vertex -873.612 290.382 234.59 + vertex -872.879 291.616 226.865 + vertex -870.293 285.522 234.509 + endloop + endfacet + facet normal -0.821988 -0.547123 -0.158089 + outer loop + vertex -870.293 285.522 234.509 + vertex -872.879 291.616 226.865 + vertex -869.663 286.799 226.816 + endloop + endfacet + facet normal -0.85859 -0.485644 -0.164237 + outer loop + vertex -876.651 295.775 234.53 + vertex -875.845 296.959 226.814 + vertex -873.612 290.382 234.59 + endloop + endfacet + facet normal -0.862574 -0.480409 -0.158665 + outer loop + vertex -873.612 290.382 234.59 + vertex -875.845 296.959 226.814 + vertex -872.879 291.616 226.865 + endloop + endfacet + facet normal -0.89012 -0.424757 -0.165129 + outer loop + vertex -879.434 301.636 234.454 + vertex -878.546 302.771 226.751 + vertex -876.651 295.775 234.53 + endloop + endfacet + facet normal -0.894837 -0.417651 -0.15759 + outer loop + vertex -876.651 295.775 234.53 + vertex -878.546 302.771 226.751 + vertex -875.845 296.959 226.814 + endloop + endfacet + facet normal -0.915841 -0.365842 -0.165515 + outer loop + vertex -881.934 307.907 234.425 + vertex -880.972 308.98 226.73 + vertex -879.434 301.636 234.454 + endloop + endfacet + facet normal -0.919447 -0.359667 -0.158926 + outer loop + vertex -879.434 301.636 234.454 + vertex -880.972 308.98 226.73 + vertex -878.546 302.771 226.751 + endloop + endfacet + facet normal -0.937138 -0.307161 -0.165606 + outer loop + vertex -884.094 314.49 234.439 + vertex -883.067 315.505 226.745 + vertex -881.934 307.907 234.425 + endloop + endfacet + facet normal -0.940025 -0.301484 -0.159564 + outer loop + vertex -881.934 307.907 234.425 + vertex -883.067 315.505 226.745 + vertex -880.972 308.98 226.73 + endloop + endfacet + facet normal -0.954627 -0.247003 -0.166366 + outer loop + vertex -885.854 321.278 234.461 + vertex -884.76 322.234 226.764 + vertex -884.094 314.49 234.439 + endloop + endfacet + facet normal -0.95746 -0.240464 -0.159523 + outer loop + vertex -884.094 314.49 234.439 + vertex -884.76 322.234 226.764 + vertex -883.067 315.505 226.745 + endloop + endfacet + facet normal -0.969153 -0.183366 -0.164681 + outer loop + vertex -887.159 328.164 234.47 + vertex -886.021 329.062 226.773 + vertex -885.854 321.278 234.461 + endloop + endfacet + facet normal -0.970723 -0.178976 -0.160202 + outer loop + vertex -885.854 321.278 234.461 + vertex -886.021 329.062 226.773 + vertex -884.76 322.234 226.764 + endloop + endfacet + facet normal -0.979074 -0.121129 -0.163531 + outer loop + vertex -888.016 335.09 234.47 + vertex -886.833 335.923 226.772 + vertex -887.159 328.164 234.47 + endloop + endfacet + facet normal -0.980508 -0.116093 -0.158516 + outer loop + vertex -887.159 328.164 234.47 + vertex -886.833 335.923 226.772 + vertex -886.021 329.062 226.773 + endloop + endfacet + facet normal -0.960758 0.229708 -0.155494 + outer loop + vertex -859.589 461.217 230.962 + vertex -859.068 460.795 227.12 + vertex -860.04 458.826 230.217 + endloop + endfacet + facet normal -0.961744 0.221749 -0.160862 + outer loop + vertex -860.04 458.826 230.217 + vertex -859.068 460.795 227.12 + vertex -859.488 458.583 226.584 + endloop + endfacet + facet normal -0.95653 0.239896 -0.165832 + outer loop + vertex -860.137 461.665 234.773 + vertex -859.589 461.217 230.962 + vertex -860.655 459.08 234.021 + endloop + endfacet + facet normal -0.957259 0.233699 -0.170414 + outer loop + vertex -860.655 459.08 234.021 + vertex -859.589 461.217 230.962 + vertex -860.04 458.826 230.217 + endloop + endfacet + facet normal -0.264092 -0.945775 -0.189115 + outer loop + vertex -856.462 275.143 225.609 + vertex -856.993 276.433 219.899 + vertex -855.347 274.68 226.365 + endloop + endfacet + facet normal -0.3377 -0.926644 -0.165195 + outer loop + vertex -855.347 274.68 226.365 + vertex -856.993 276.433 219.899 + vertex -854.965 275.975 218.317 + endloop + endfacet + facet normal -0.413085 -0.895809 -0.16397 + outer loop + vertex -856.462 275.143 225.609 + vertex -857.86 275.85 225.266 + vertex -856.993 276.433 219.899 + endloop + endfacet + facet normal -0.514774 -0.843106 -0.155501 + outer loop + vertex -860.247 277.288 225.368 + vertex -859.752 278.166 218.97 + vertex -857.86 275.85 225.266 + endloop + endfacet + facet normal -0.482256 -0.859145 -0.171168 + outer loop + vertex -859.752 278.166 218.97 + vertex -856.993 276.433 219.899 + vertex -857.86 275.85 225.266 + endloop + endfacet + facet normal -0.622931 -0.768004 -0.148749 + outer loop + vertex -863.078 279.471 225.955 + vertex -862.727 280.565 218.837 + vertex -860.247 277.288 225.368 + endloop + endfacet + facet normal -0.616033 -0.772587 -0.153667 + outer loop + vertex -860.247 277.288 225.368 + vertex -862.727 280.565 218.837 + vertex -859.752 278.166 218.97 + endloop + endfacet + facet normal -0.709841 -0.689658 -0.143169 + outer loop + vertex -866.283 282.642 226.573 + vertex -865.889 283.817 218.956 + vertex -863.078 279.471 225.955 + endloop + endfacet + facet normal -0.712399 -0.687504 -0.140804 + outer loop + vertex -863.078 279.471 225.955 + vertex -865.889 283.817 218.956 + vertex -862.727 280.565 218.837 + endloop + endfacet + facet normal -0.771963 -0.619185 -0.143816 + outer loop + vertex -869.663 286.799 226.816 + vertex -869.108 287.907 219.066 + vertex -866.283 282.642 226.573 + endloop + endfacet + facet normal -0.780412 -0.610603 -0.134617 + outer loop + vertex -866.283 282.642 226.573 + vertex -869.108 287.907 219.066 + vertex -865.889 283.817 218.956 + endloop + endfacet + facet normal -0.8237 -0.548407 -0.144114 + outer loop + vertex -872.879 291.616 226.865 + vertex -872.225 292.681 219.078 + vertex -869.663 286.799 226.816 + endloop + endfacet + facet normal -0.829577 -0.541371 -0.13682 + outer loop + vertex -869.663 286.799 226.816 + vertex -872.225 292.681 219.078 + vertex -869.108 287.907 219.066 + endloop + endfacet + facet normal -0.864633 -0.481408 -0.143723 + outer loop + vertex -875.845 296.959 226.814 + vertex -875.127 297.992 219.031 + vertex -872.879 291.616 226.865 + endloop + endfacet + facet normal -0.868696 -0.475749 -0.137951 + outer loop + vertex -872.879 291.616 226.865 + vertex -875.127 297.992 219.031 + vertex -872.225 292.681 219.078 + endloop + endfacet + facet normal -0.896897 -0.418452 -0.143087 + outer loop + vertex -878.546 302.771 226.751 + vertex -877.769 303.761 218.982 + vertex -875.845 296.959 226.814 + endloop + endfacet + facet normal -0.900015 -0.413444 -0.137972 + outer loop + vertex -875.845 296.959 226.814 + vertex -877.769 303.761 218.982 + vertex -875.127 297.992 219.031 + endloop + endfacet + facet normal -0.921602 -0.360458 -0.143943 + outer loop + vertex -880.972 308.98 226.73 + vertex -880.128 309.924 218.967 + vertex -878.546 302.771 226.751 + endloop + endfacet + facet normal -0.924889 -0.354418 -0.137724 + outer loop + vertex -878.546 302.771 226.751 + vertex -880.128 309.924 218.967 + vertex -877.769 303.761 218.982 + endloop + endfacet + facet normal -0.9422 -0.302217 -0.144654 + outer loop + vertex -883.067 315.505 226.745 + vertex -882.161 316.397 218.981 + vertex -880.972 308.98 226.73 + endloop + endfacet + facet normal -0.94493 -0.29643 -0.138694 + outer loop + vertex -880.972 308.98 226.73 + vertex -882.161 316.397 218.981 + vertex -880.128 309.924 218.967 + endloop + endfacet + facet normal -0.959702 -0.241073 -0.144417 + outer loop + vertex -884.76 322.234 226.764 + vertex -883.803 323.075 218.999 + vertex -883.067 315.505 226.745 + endloop + endfacet + facet normal -0.961699 -0.236057 -0.139325 + outer loop + vertex -883.067 315.505 226.745 + vertex -883.803 323.075 218.999 + vertex -882.161 316.397 218.981 + endloop + endfacet + facet normal -0.973175 -0.17945 -0.143973 + outer loop + vertex -886.021 329.062 226.773 + vertex -885.017 329.849 219.005 + vertex -884.76 322.234 226.764 + endloop + endfacet + facet normal -0.974786 -0.174507 -0.139069 + outer loop + vertex -884.76 322.234 226.764 + vertex -885.017 329.849 219.005 + vertex -883.803 323.075 218.999 + endloop + endfacet + facet normal -0.983001 -0.116384 -0.142 + outer loop + vertex -886.833 335.923 226.772 + vertex -885.798 336.657 219.004 + vertex -886.021 329.062 226.773 + endloop + endfacet + facet normal -0.983891 -0.112893 -0.138613 + outer loop + vertex -886.021 329.062 226.773 + vertex -885.798 336.657 219.004 + vertex -885.017 329.849 219.005 + endloop + endfacet + facet normal -0.967404 0.214773 -0.134173 + outer loop + vertex -858.58 460.402 223.275 + vertex -858.125 460.038 219.41 + vertex -859.004 458.292 222.956 + endloop + endfacet + facet normal -0.965153 0.229024 -0.1266 + outer loop + vertex -859.004 458.292 222.956 + vertex -858.125 460.038 219.41 + vertex -858.605 457.895 219.194 + endloop + endfacet + facet normal -0.965043 0.218476 -0.144774 + outer loop + vertex -859.068 460.795 227.12 + vertex -858.58 460.402 223.275 + vertex -859.488 458.583 226.584 + endloop + endfacet + facet normal -0.965359 0.21617 -0.146129 + outer loop + vertex -859.488 458.583 226.584 + vertex -858.58 460.402 223.275 + vertex -859.004 458.292 222.956 + endloop + endfacet + facet normal -0.320241 -0.936959 -0.139833 + outer loop + vertex -856.993 276.433 219.899 + vertex -856.699 277.62 211.267 + vertex -854.965 275.975 218.317 + endloop + endfacet + facet normal -0.343889 -0.929642 -0.132309 + outer loop + vertex -854.965 275.975 218.317 + vertex -856.699 277.62 211.267 + vertex -854.74 277.084 209.944 + endloop + endfacet + facet normal -0.494605 -0.858759 -0.133785 + outer loop + vertex -859.752 278.166 218.97 + vertex -859.277 279.045 211.576 + vertex -856.993 276.433 219.899 + endloop + endfacet + facet normal -0.491501 -0.86033 -0.13513 + outer loop + vertex -856.993 276.433 219.899 + vertex -859.277 279.045 211.576 + vertex -856.699 277.62 211.267 + endloop + endfacet + facet normal -0.618988 -0.774852 -0.128291 + outer loop + vertex -862.727 280.565 218.837 + vertex -862.285 281.45 211.364 + vertex -859.752 278.166 218.97 + endloop + endfacet + facet normal -0.613262 -0.778789 -0.131898 + outer loop + vertex -859.752 278.166 218.97 + vertex -862.285 281.45 211.364 + vertex -859.277 279.045 211.576 + endloop + endfacet + facet normal -0.71374 -0.68944 -0.123483 + outer loop + vertex -865.889 283.817 218.956 + vertex -865.457 284.751 211.249 + vertex -862.727 280.565 218.837 + endloop + endfacet + facet normal -0.713376 -0.689761 -0.123791 + outer loop + vertex -862.727 280.565 218.837 + vertex -865.457 284.751 211.249 + vertex -862.285 281.45 211.364 + endloop + endfacet + facet normal -0.781638 -0.611943 -0.120695 + outer loop + vertex -869.108 287.907 219.066 + vertex -868.623 288.834 211.226 + vertex -865.889 283.817 218.956 + endloop + endfacet + facet normal -0.784493 -0.608867 -0.117689 + outer loop + vertex -865.889 283.817 218.956 + vertex -868.623 288.834 211.226 + vertex -865.457 284.751 211.249 + endloop + endfacet + facet normal -0.831249 -0.542502 -0.121311 + outer loop + vertex -872.225 292.681 219.078 + vertex -871.667 293.586 211.206 + vertex -869.108 287.907 219.066 + endloop + endfacet + facet normal -0.836226 -0.536168 -0.115114 + outer loop + vertex -869.108 287.907 219.066 + vertex -871.667 293.586 211.206 + vertex -868.623 288.834 211.226 + endloop + endfacet + facet normal -0.870682 -0.476683 -0.121185 + outer loop + vertex -875.127 297.992 219.031 + vertex -874.512 298.867 211.17 + vertex -872.225 292.681 219.078 + endloop + endfacet + facet normal -0.874131 -0.471585 -0.116199 + outer loop + vertex -872.225 292.681 219.078 + vertex -874.512 298.867 211.17 + vertex -871.667 293.586 211.206 + endloop + endfacet + facet normal -0.902077 -0.414245 -0.12107 + outer loop + vertex -877.769 303.761 218.982 + vertex -877.103 304.604 211.137 + vertex -875.127 297.992 219.031 + endloop + endfacet + facet normal -0.904869 -0.409474 -0.116374 + outer loop + vertex -875.127 297.992 219.031 + vertex -877.103 304.604 211.137 + vertex -874.512 298.867 211.17 + endloop + endfacet + facet normal -0.926916 -0.355153 -0.121213 + outer loop + vertex -880.128 309.924 218.967 + vertex -879.411 310.726 211.129 + vertex -877.769 303.761 218.982 + endloop + endfacet + facet normal -0.929311 -0.350433 -0.116525 + outer loop + vertex -877.769 303.761 218.982 + vertex -879.411 310.726 211.129 + vertex -877.103 304.604 211.137 + endloop + endfacet + facet normal -0.947012 -0.29712 -0.122015 + outer loop + vertex -882.161 316.397 218.981 + vertex -881.39 317.157 211.142 + vertex -880.128 309.924 218.967 + endloop + endfacet + facet normal -0.949305 -0.29186 -0.116783 + outer loop + vertex -880.128 309.924 218.967 + vertex -881.39 317.157 211.142 + vertex -879.411 310.726 211.129 + endloop + endfacet + facet normal -0.963883 -0.236638 -0.122195 + outer loop + vertex -883.803 323.075 218.999 + vertex -882.984 323.79 211.156 + vertex -882.161 316.397 218.981 + endloop + endfacet + facet normal -0.965617 -0.231888 -0.117525 + outer loop + vertex -882.161 316.397 218.981 + vertex -882.984 323.79 211.156 + vertex -881.39 317.157 211.142 + endloop + endfacet + facet normal -0.977016 -0.174924 -0.121826 + outer loop + vertex -885.017 329.849 219.005 + vertex -884.158 330.518 211.161 + vertex -883.803 323.075 218.999 + endloop + endfacet + facet normal -0.978285 -0.170619 -0.11768 + outer loop + vertex -883.803 323.075 218.999 + vertex -884.158 330.518 211.161 + vertex -882.984 323.79 211.156 + endloop + endfacet + facet normal -0.986235 -0.113158 -0.120568 + outer loop + vertex -885.798 336.657 219.004 + vertex -884.91 337.28 211.16 + vertex -885.017 329.849 219.005 + endloop + endfacet + facet normal -0.987004 -0.109765 -0.117365 + outer loop + vertex -885.017 329.849 219.005 + vertex -884.91 337.28 211.16 + vertex -884.158 330.518 211.161 + endloop + endfacet + facet normal -0.966649 0.229843 -0.112968 + outer loop + vertex -857.696 459.695 215.447 + vertex -857.306 459.383 211.471 + vertex -858.179 457.562 215.235 + endloop + endfacet + facet normal -0.967141 0.227028 -0.114444 + outer loop + vertex -858.179 457.562 215.235 + vertex -857.306 459.383 211.471 + vertex -857.775 457.289 211.279 + endloop + endfacet + facet normal -0.965517 0.228854 -0.124107 + outer loop + vertex -858.125 460.038 219.41 + vertex -857.696 459.695 215.447 + vertex -858.605 457.895 219.194 + endloop + endfacet + facet normal -0.965228 0.230542 -0.123226 + outer loop + vertex -858.605 457.895 219.194 + vertex -857.696 459.695 215.447 + vertex -858.179 457.562 215.235 + endloop + endfacet + facet normal -0.331136 -0.937102 -0.110399 + outer loop + vertex -856.699 277.62 211.267 + vertex -856.484 278.518 202.999 + vertex -854.74 277.084 209.944 + endloop + endfacet + facet normal -0.349228 -0.931177 -0.104634 + outer loop + vertex -854.74 277.084 209.944 + vertex -856.484 278.518 202.999 + vertex -854.583 277.954 201.681 + endloop + endfacet + facet normal -0.490657 -0.864554 -0.108637 + outer loop + vertex -859.277 279.045 211.576 + vertex -858.978 279.895 203.46 + vertex -856.699 277.62 211.267 + endloop + endfacet + facet normal -0.495445 -0.862083 -0.106519 + outer loop + vertex -856.699 277.62 211.267 + vertex -858.978 279.895 203.46 + vertex -856.484 278.518 202.999 + endloop + endfacet + facet normal -0.616369 -0.780351 -0.105554 + outer loop + vertex -862.285 281.45 211.364 + vertex -861.931 282.24 203.449 + vertex -859.277 279.045 211.576 + endloop + endfacet + facet normal -0.618298 -0.778981 -0.104385 + outer loop + vertex -859.277 279.045 211.576 + vertex -861.931 282.24 203.449 + vertex -858.978 279.895 203.46 + endloop + endfacet + facet normal -0.715676 -0.691164 -0.100497 + outer loop + vertex -865.457 284.751 211.249 + vertex -865.083 285.515 203.326 + vertex -862.285 281.45 211.364 + endloop + endfacet + facet normal -0.714905 -0.691871 -0.101123 + outer loop + vertex -862.285 281.45 211.364 + vertex -865.083 285.515 203.326 + vertex -861.931 282.24 203.449 + endloop + endfacet + facet normal -0.786186 -0.61007 -0.0986236 + outer loop + vertex -868.623 288.834 211.226 + vertex -868.219 289.601 203.26 + vertex -865.457 284.751 211.249 + endloop + endfacet + facet normal -0.788878 -0.60703 -0.0958477 + outer loop + vertex -865.457 284.751 211.249 + vertex -868.219 289.601 203.26 + vertex -865.083 285.515 203.326 + endloop + endfacet + facet normal -0.837826 -0.537122 -0.0977102 + outer loop + vertex -871.667 293.586 211.206 + vertex -871.216 294.331 203.242 + vertex -868.623 288.834 211.226 + endloop + endfacet + facet normal -0.840805 -0.533117 -0.0939859 + outer loop + vertex -868.623 288.834 211.226 + vertex -871.216 294.331 203.242 + vertex -868.219 289.601 203.26 + endloop + endfacet + facet normal -0.875879 -0.472405 -0.0983315 + outer loop + vertex -874.512 298.867 211.17 + vertex -874.009 299.589 203.228 + vertex -871.667 293.586 211.206 + endloop + endfacet + facet normal -0.879145 -0.467288 -0.0935221 + outer loop + vertex -871.667 293.586 211.206 + vertex -874.009 299.589 203.228 + vertex -871.216 294.331 203.242 + endloop + endfacet + facet normal -0.906715 -0.410201 -0.0979982 + outer loop + vertex -877.103 304.604 211.137 + vertex -876.559 305.293 203.216 + vertex -874.512 298.867 211.17 + endloop + endfacet + facet normal -0.90879 -0.40643 -0.0944181 + outer loop + vertex -874.512 298.867 211.17 + vertex -876.559 305.293 203.216 + vertex -874.009 299.589 203.228 + endloop + endfacet + facet normal -0.931135 -0.351097 -0.098583 + outer loop + vertex -879.411 310.726 211.129 + vertex -878.821 311.385 203.215 + vertex -877.103 304.604 211.137 + endloop + endfacet + facet normal -0.933256 -0.346616 -0.0942868 + outer loop + vertex -877.103 304.604 211.137 + vertex -878.821 311.385 203.215 + vertex -876.559 305.293 203.216 + endloop + endfacet + facet normal -0.951101 -0.292448 -0.0993987 + outer loop + vertex -881.39 317.157 211.142 + vertex -880.754 317.78 203.226 + vertex -879.411 310.726 211.129 + endloop + endfacet + facet normal -0.952969 -0.287811 -0.0949427 + outer loop + vertex -879.411 310.726 211.129 + vertex -880.754 317.78 203.226 + vertex -878.821 311.385 203.215 + endloop + endfacet + facet normal -0.967523 -0.232386 -0.0994794 + outer loop + vertex -882.984 323.79 211.156 + vertex -882.31 324.374 203.237 + vertex -881.39 317.157 211.142 + endloop + endfacet + facet normal -0.968816 -0.228515 -0.0957948 + outer loop + vertex -881.39 317.157 211.142 + vertex -882.31 324.374 203.237 + vertex -880.754 317.78 203.226 + endloop + endfacet + facet normal -0.980289 -0.170982 -0.0989878 + outer loop + vertex -884.158 330.518 211.161 + vertex -883.454 331.065 203.24 + vertex -882.984 323.79 211.156 + endloop + endfacet + facet normal -0.981177 -0.167639 -0.0958631 + outer loop + vertex -882.984 323.79 211.156 + vertex -883.454 331.065 203.24 + vertex -882.31 324.374 203.237 + endloop + endfacet + facet normal -0.989039 -0.109987 -0.0985161 + outer loop + vertex -884.91 337.28 211.16 + vertex -884.177 337.788 203.238 + vertex -884.158 330.518 211.161 + endloop + endfacet + facet normal -0.989722 -0.106562 -0.0953713 + outer loop + vertex -884.158 330.518 211.161 + vertex -884.177 337.788 203.238 + vertex -883.454 331.065 203.24 + endloop + endfacet + facet normal -0.969872 0.225982 -0.0909929 + outer loop + vertex -856.957 459.106 207.534 + vertex -856.644 458.86 203.587 + vertex -857.421 457.043 207.358 + endloop + endfacet + facet normal -0.969258 0.229281 -0.0892766 + outer loop + vertex -857.421 457.043 207.358 + vertex -856.644 458.86 203.587 + vertex -857.112 456.819 203.425 + endloop + endfacet + facet normal -0.968742 0.22623 -0.101775 + outer loop + vertex -857.306 459.383 211.471 + vertex -856.957 459.106 207.534 + vertex -857.775 457.289 211.279 + endloop + endfacet + facet normal -0.968674 0.22661 -0.101576 + outer loop + vertex -857.775 457.289 211.279 + vertex -856.957 459.106 207.534 + vertex -857.421 457.043 207.358 + endloop + endfacet + facet normal -0.336479 -0.937998 -0.0833162 + outer loop + vertex -856.484 278.518 202.999 + vertex -856.354 279.183 194.988 + vertex -854.583 277.954 201.681 + endloop + endfacet + facet normal -0.35847 -0.930434 -0.0761091 + outer loop + vertex -854.583 277.954 201.681 + vertex -856.354 279.183 194.988 + vertex -854.579 278.582 193.987 + endloop + endfacet + facet normal -0.493196 -0.865975 -0.08274 + outer loop + vertex -858.978 279.895 203.46 + vertex -858.786 280.558 195.37 + vertex -856.484 278.518 202.999 + endloop + endfacet + facet normal -0.50008 -0.862306 -0.0796813 + outer loop + vertex -856.484 278.518 202.999 + vertex -858.786 280.558 195.37 + vertex -856.354 279.183 194.988 + endloop + endfacet + facet normal -0.619738 -0.780687 -0.0803247 + outer loop + vertex -861.931 282.24 203.449 + vertex -861.695 282.884 195.373 + vertex -858.978 279.895 203.46 + endloop + endfacet + facet normal -0.622518 -0.778644 -0.0786354 + outer loop + vertex -858.978 279.895 203.46 + vertex -861.695 282.884 195.373 + vertex -858.786 280.558 195.37 + endloop + endfacet + facet normal -0.716838 -0.692859 -0.0780357 + outer loop + vertex -865.083 285.515 203.326 + vertex -864.814 286.144 195.273 + vertex -861.931 282.24 203.449 + endloop + endfacet + facet normal -0.71931 -0.690515 -0.0760447 + outer loop + vertex -861.931 282.24 203.449 + vertex -864.814 286.144 195.273 + vertex -861.695 282.884 195.373 + endloop + endfacet + facet normal -0.790423 -0.607891 -0.0755032 + outer loop + vertex -868.219 289.601 203.26 + vertex -867.917 290.207 195.218 + vertex -865.083 285.515 203.326 + endloop + endfacet + facet normal -0.792121 -0.605892 -0.0737531 + outer loop + vertex -865.083 285.515 203.326 + vertex -867.917 290.207 195.218 + vertex -864.814 286.144 195.273 + endloop + endfacet + facet normal -0.842192 -0.53392 -0.0751159 + outer loop + vertex -871.216 294.331 203.242 + vertex -870.873 294.919 195.218 + vertex -868.219 289.601 203.26 + endloop + endfacet + facet normal -0.844912 -0.530081 -0.0716791 + outer loop + vertex -868.219 289.601 203.26 + vertex -870.873 294.919 195.218 + vertex -867.917 290.207 195.218 + endloop + endfacet + facet normal -0.880542 -0.467983 -0.0750879 + outer loop + vertex -874.009 299.589 203.228 + vertex -873.626 300.15 195.232 + vertex -871.216 294.331 203.242 + endloop + endfacet + facet normal -0.882767 -0.464301 -0.0717432 + outer loop + vertex -871.216 294.331 203.242 + vertex -873.626 300.15 195.232 + vertex -870.873 294.919 195.218 + endloop + endfacet + facet normal -0.910261 -0.407047 -0.0757447 + outer loop + vertex -876.559 305.293 203.216 + vertex -876.135 305.83 195.24 + vertex -874.009 299.589 203.228 + endloop + endfacet + facet normal -0.912344 -0.403035 -0.0720557 + outer loop + vertex -874.009 299.589 203.228 + vertex -876.135 305.83 195.24 + vertex -873.626 300.15 195.232 + endloop + endfacet + facet normal -0.934709 -0.347153 -0.0761787 + outer loop + vertex -878.821 311.385 203.215 + vertex -878.361 311.894 195.246 + vertex -876.559 305.293 203.216 + endloop + endfacet + facet normal -0.936294 -0.343578 -0.0728588 + outer loop + vertex -876.559 305.293 203.216 + vertex -878.361 311.894 195.246 + vertex -876.135 305.83 195.24 + endloop + endfacet + facet normal -0.954465 -0.288294 -0.0767081 + outer loop + vertex -880.754 317.78 203.226 + vertex -880.259 318.261 195.255 + vertex -878.821 311.385 203.215 + endloop + endfacet + facet normal -0.955788 -0.284746 -0.0734041 + outer loop + vertex -878.821 311.385 203.215 + vertex -880.259 318.261 195.255 + vertex -878.361 311.894 195.246 + endloop + endfacet + facet normal -0.970396 -0.22892 -0.0769931 + outer loop + vertex -882.31 324.374 203.237 + vertex -881.784 324.827 195.261 + vertex -880.754 317.78 203.226 + endloop + endfacet + facet normal -0.971395 -0.225654 -0.073974 + outer loop + vertex -880.754 317.78 203.226 + vertex -881.784 324.827 195.261 + vertex -880.259 318.261 195.255 + endloop + endfacet + facet normal -0.982779 -0.167923 -0.0771159 + outer loop + vertex -883.454 331.065 203.24 + vertex -882.9 331.488 195.263 + vertex -882.31 324.374 203.237 + endloop + endfacet + facet normal -0.983542 -0.164734 -0.0742146 + outer loop + vertex -882.31 324.374 203.237 + vertex -882.9 331.488 195.263 + vertex -881.784 324.827 195.261 + endloop + endfacet + facet normal -0.991338 -0.106728 -0.0765361 + outer loop + vertex -884.177 337.788 203.238 + vertex -883.604 338.18 195.26 + vertex -883.454 331.065 203.24 + endloop + endfacet + facet normal -0.991761 -0.104306 -0.0743682 + outer loop + vertex -883.454 331.065 203.24 + vertex -883.604 338.18 195.26 + vertex -882.9 331.488 195.263 + endloop + endfacet + facet normal -0.970385 0.231239 -0.0698658 + outer loop + vertex -856.364 458.644 199.595 + vertex -856.12 458.461 195.596 + vertex -856.836 456.624 199.458 + endloop + endfacet + facet normal -0.970128 0.232512 -0.0692126 + outer loop + vertex -856.836 456.624 199.458 + vertex -856.12 458.461 195.596 + vertex -856.59 456.46 195.466 + endloop + endfacet + facet normal -0.970151 0.228784 -0.0804022 + outer loop + vertex -856.644 458.86 203.587 + vertex -856.364 458.644 199.595 + vertex -857.112 456.819 203.425 + endloop + endfacet + facet normal -0.969588 0.23167 -0.0789169 + outer loop + vertex -857.112 456.819 203.425 + vertex -856.364 458.644 199.595 + vertex -856.836 456.624 199.458 + endloop + endfacet + facet normal -0.3498 -0.935029 -0.0579745 + outer loop + vertex -856.354 279.183 194.988 + vertex -856.266 279.636 187.16 + vertex -854.579 278.582 193.987 + endloop + endfacet + facet normal -0.353011 -0.933881 -0.0570035 + outer loop + vertex -854.579 278.582 193.987 + vertex -856.266 279.636 187.16 + vertex -854.413 278.978 186.467 + endloop + endfacet + facet normal -0.498228 -0.865117 -0.057802 + outer loop + vertex -858.786 280.558 195.37 + vertex -858.671 281.024 187.412 + vertex -856.354 279.183 194.988 + endloop + endfacet + facet normal -0.503492 -0.862217 -0.0554873 + outer loop + vertex -856.354 279.183 194.988 + vertex -858.671 281.024 187.412 + vertex -856.266 279.636 187.16 + endloop + endfacet + facet normal -0.623464 -0.779853 -0.0558684 + outer loop + vertex -861.695 282.884 195.373 + vertex -861.548 283.34 187.363 + vertex -858.786 280.558 195.37 + endloop + endfacet + facet normal -0.625624 -0.778215 -0.0545544 + outer loop + vertex -858.786 280.558 195.37 + vertex -861.548 283.34 187.363 + vertex -858.671 281.024 187.412 + endloop + endfacet + facet normal -0.720675 -0.69115 -0.0542094 + outer loop + vertex -864.814 286.144 195.273 + vertex -864.64 286.592 187.246 + vertex -861.695 282.884 195.373 + endloop + endfacet + facet normal -0.722745 -0.689116 -0.0525312 + outer loop + vertex -861.695 282.884 195.373 + vertex -864.64 286.592 187.246 + vertex -861.548 283.34 187.363 + endloop + endfacet + facet normal -0.793298 -0.606512 -0.0531277 + outer loop + vertex -867.917 290.207 195.218 + vertex -867.713 290.644 187.194 + vertex -864.814 286.144 195.273 + endloop + endfacet + facet normal -0.795383 -0.603961 -0.0509591 + outer loop + vertex -864.814 286.144 195.273 + vertex -867.713 290.644 187.194 + vertex -864.64 286.592 187.246 + endloop + endfacet + facet normal -0.845936 -0.530727 -0.052171 + outer loop + vertex -870.873 294.919 195.218 + vertex -870.639 295.333 187.206 + vertex -867.917 290.207 195.218 + endloop + endfacet + facet normal -0.847426 -0.528529 -0.0502586 + outer loop + vertex -867.917 290.207 195.218 + vertex -870.639 295.333 187.206 + vertex -867.713 290.644 187.194 + endloop + endfacet + facet normal -0.883767 -0.464877 -0.053348 + outer loop + vertex -873.626 300.15 195.232 + vertex -873.354 300.551 187.24 + vertex -870.873 294.919 195.218 + endloop + endfacet + facet normal -0.886116 -0.460787 -0.0497309 + outer loop + vertex -870.873 294.919 195.218 + vertex -873.354 300.551 187.24 + vertex -870.639 295.333 187.206 + endloop + endfacet + facet normal -0.913379 -0.403518 -0.0539541 + outer loop + vertex -876.135 305.83 195.24 + vertex -875.832 306.209 187.261 + vertex -873.626 300.15 195.232 + endloop + endfacet + facet normal -0.914903 -0.400417 -0.0511755 + outer loop + vertex -873.626 300.15 195.232 + vertex -875.832 306.209 187.261 + vertex -873.354 300.551 187.24 + endloop + endfacet + facet normal -0.937369 -0.34399 -0.0548696 + outer loop + vertex -878.361 311.894 195.246 + vertex -878.027 312.255 187.27 + vertex -876.135 305.83 195.24 + endloop + endfacet + facet normal -0.93872 -0.340745 -0.0519331 + outer loop + vertex -876.135 305.83 195.24 + vertex -878.027 312.255 187.27 + vertex -875.832 306.209 187.261 + endloop + endfacet + facet normal -0.956918 -0.285107 -0.0549705 + outer loop + vertex -880.259 318.261 195.255 + vertex -879.901 318.601 187.274 + vertex -878.361 311.894 195.246 + endloop + endfacet + facet normal -0.957688 -0.282894 -0.0529604 + outer loop + vertex -878.361 311.894 195.246 + vertex -879.901 318.601 187.274 + vertex -878.027 312.255 187.27 + endloop + endfacet + facet normal -0.97256 -0.225944 -0.0554634 + outer loop + vertex -881.784 324.827 195.261 + vertex -881.403 325.146 187.276 + vertex -880.259 318.261 195.255 + endloop + endfacet + facet normal -0.973303 -0.223301 -0.0530764 + outer loop + vertex -880.259 318.261 195.255 + vertex -881.403 325.146 187.276 + vertex -879.901 318.601 187.274 + endloop + endfacet + facet normal -0.984739 -0.164937 -0.0555404 + outer loop + vertex -882.9 331.488 195.263 + vertex -882.5 331.787 187.275 + vertex -881.784 324.827 195.261 + endloop + endfacet + facet normal -0.985224 -0.16269 -0.0535387 + outer loop + vertex -881.784 324.827 195.261 + vertex -882.5 331.787 187.275 + vertex -881.403 325.146 187.276 + endloop + endfacet + facet normal -0.993 -0.104428 -0.055195 + outer loop + vertex -883.604 338.18 195.26 + vertex -883.189 338.458 187.272 + vertex -882.9 331.488 195.263 + endloop + endfacet + facet normal -0.993269 -0.102657 -0.0536407 + outer loop + vertex -882.9 331.488 195.263 + vertex -883.189 338.458 187.272 + vertex -882.5 331.787 187.275 + endloop + endfacet + facet normal -0.971476 0.232037 -0.0489304 + outer loop + vertex -855.911 458.309 191.58 + vertex -855.736 458.192 187.557 + vertex -856.378 456.328 191.463 + endloop + endfacet + facet normal -0.971482 0.232005 -0.0489466 + outer loop + vertex -856.378 456.328 191.463 + vertex -855.736 458.192 187.557 + vertex -856.201 456.225 187.461 + endloop + endfacet + facet normal -0.970891 0.232049 -0.0593577 + outer loop + vertex -856.12 458.461 195.596 + vertex -855.911 458.309 191.58 + vertex -856.59 456.46 195.466 + endloop + endfacet + facet normal -0.970802 0.232478 -0.0591377 + outer loop + vertex -856.59 456.46 195.466 + vertex -855.911 458.309 191.58 + vertex -856.378 456.328 191.463 + endloop + endfacet + facet normal -0.345986 -0.937598 -0.0346903 + outer loop + vertex -856.266 279.636 187.16 + vertex -856.2 279.903 179.269 + vertex -854.413 278.978 186.467 + endloop + endfacet + facet normal -0.353915 -0.934718 -0.0323506 + outer loop + vertex -854.413 278.978 186.467 + vertex -856.2 279.903 179.269 + vertex -854.365 279.242 178.295 + endloop + endfacet + facet normal -0.502276 -0.864045 -0.0338268 + outer loop + vertex -858.671 281.024 187.412 + vertex -858.602 281.293 179.522 + vertex -856.266 279.636 187.16 + endloop + endfacet + facet normal -0.503039 -0.863614 -0.0335002 + outer loop + vertex -856.266 279.636 187.16 + vertex -858.602 281.293 179.522 + vertex -856.2 279.903 179.269 + endloop + endfacet + facet normal -0.626436 -0.778767 -0.0331724 + outer loop + vertex -861.548 283.34 187.363 + vertex -861.467 283.612 179.446 + vertex -858.671 281.024 187.412 + endloop + endfacet + facet normal -0.628415 -0.777221 -0.0319755 + outer loop + vertex -858.671 281.024 187.412 + vertex -861.467 283.612 179.446 + vertex -858.602 281.293 179.522 + endloop + endfacet + facet normal -0.723757 -0.689329 -0.0316518 + outer loop + vertex -864.64 286.592 187.246 + vertex -864.539 286.85 179.313 + vertex -861.548 283.34 187.363 + endloop + endfacet + facet normal -0.724463 -0.688613 -0.031077 + outer loop + vertex -861.548 283.34 187.363 + vertex -864.539 286.85 179.313 + vertex -861.467 283.612 179.446 + endloop + endfacet + facet normal -0.796153 -0.604288 -0.0312329 + outer loop + vertex -867.713 290.644 187.194 + vertex -867.593 290.896 179.252 + vertex -864.64 286.592 187.246 + endloop + endfacet + facet normal -0.797542 -0.602528 -0.0297724 + outer loop + vertex -864.64 286.592 187.246 + vertex -867.593 290.896 179.252 + vertex -864.539 286.85 179.313 + endloop + endfacet + facet normal -0.848045 -0.528965 -0.0318624 + outer loop + vertex -870.639 295.333 187.206 + vertex -870.495 295.581 179.267 + vertex -867.713 290.644 187.194 + endloop + endfacet + facet normal -0.849804 -0.526269 -0.0295667 + outer loop + vertex -867.713 290.644 187.194 + vertex -870.495 295.581 179.267 + vertex -867.593 290.896 179.252 + endloop + endfacet + facet normal -0.88671 -0.46121 -0.032108 + outer loop + vertex -873.354 300.551 187.24 + vertex -873.188 300.784 179.304 + vertex -870.639 295.333 187.206 + endloop + endfacet + facet normal -0.887785 -0.459253 -0.0304108 + outer loop + vertex -870.639 295.333 187.206 + vertex -873.188 300.784 179.304 + vertex -870.495 295.581 179.267 + endloop + endfacet + facet normal -0.915577 -0.400779 -0.0330912 + outer loop + vertex -875.832 306.209 187.261 + vertex -875.642 306.432 179.329 + vertex -873.354 300.551 187.24 + endloop + endfacet + facet normal -0.916748 -0.398271 -0.0308886 + outer loop + vertex -873.354 300.551 187.24 + vertex -875.642 306.432 179.329 + vertex -873.188 300.784 179.304 + endloop + endfacet + facet normal -0.939462 -0.341044 -0.0331687 + outer loop + vertex -878.027 312.255 187.27 + vertex -877.822 312.464 179.335 + vertex -875.832 306.209 187.261 + endloop + endfacet + facet normal -0.939998 -0.339679 -0.0319573 + outer loop + vertex -875.832 306.209 187.261 + vertex -877.822 312.464 179.335 + vertex -875.642 306.432 179.329 + endloop + endfacet + facet normal -0.958475 -0.283138 -0.0340449 + outer loop + vertex -879.901 318.601 187.274 + vertex -879.678 318.8 179.335 + vertex -878.027 312.255 187.27 + endloop + endfacet + facet normal -0.959185 -0.280952 -0.032094 + outer loop + vertex -878.027 312.255 187.27 + vertex -879.678 318.8 179.335 + vertex -877.822 312.464 179.335 + endloop + endfacet + facet normal -0.97409 -0.223487 -0.0346804 + outer loop + vertex -881.403 325.146 187.276 + vertex -881.163 325.334 179.333 + vertex -879.901 318.601 187.274 + endloop + endfacet + facet normal -0.974593 -0.221545 -0.0329541 + outer loop + vertex -879.901 318.601 187.274 + vertex -881.163 325.334 179.333 + vertex -879.678 318.8 179.335 + endloop + endfacet + facet normal -0.986042 -0.162822 -0.0347914 + outer loop + vertex -882.5 331.787 187.275 + vertex -882.248 331.962 179.33 + vertex -881.403 325.146 187.276 + endloop + endfacet + facet normal -0.986309 -0.16145 -0.0335858 + outer loop + vertex -881.403 325.146 187.276 + vertex -882.248 331.962 179.33 + vertex -881.163 325.334 179.333 + endloop + endfacet + facet normal -0.994093 -0.102734 -0.0350003 + outer loop + vertex -883.189 338.458 187.272 + vertex -882.926 338.62 179.327 + vertex -882.5 331.787 187.275 + endloop + endfacet + facet normal -0.994293 -0.101227 -0.0336942 + outer loop + vertex -882.5 331.787 187.275 + vertex -882.926 338.62 179.327 + vertex -882.248 331.962 179.33 + endloop + endfacet + facet normal -0.972524 0.231038 -0.0285994 + outer loop + vertex -855.598 458.11 183.587 + vertex -855.492 458.061 179.614 + vertex -856.059 456.151 183.462 + endloop + endfacet + facet normal -0.972591 0.230737 -0.0287585 + outer loop + vertex -856.059 456.151 183.462 + vertex -855.492 458.061 179.614 + vertex -855.951 456.107 179.459 + endloop + endfacet + facet normal -0.972034 0.231633 -0.0386934 + outer loop + vertex -855.736 458.192 187.557 + vertex -855.598 458.11 183.587 + vertex -856.201 456.225 187.461 + endloop + endfacet + facet normal -0.972046 0.231574 -0.038724 + outer loop + vertex -856.201 456.225 187.461 + vertex -855.598 458.11 183.587 + vertex -856.059 456.151 183.462 + endloop + endfacet + facet normal -0.34369 -0.939028 -0.0101575 + outer loop + vertex -856.2 279.903 179.269 + vertex -856.167 279.978 171.3 + vertex -854.365 279.242 178.295 + endloop + endfacet + facet normal -0.35439 -0.935072 -0.00698405 + outer loop + vertex -854.365 279.242 178.295 + vertex -856.167 279.978 171.3 + vertex -854.347 279.296 170.164 + endloop + endfacet + facet normal -0.501544 -0.865058 -0.011349 + outer loop + vertex -858.602 281.293 179.522 + vertex -858.574 281.38 171.633 + vertex -856.2 279.903 179.269 + endloop + endfacet + facet normal -0.504464 -0.863374 -0.0101157 + outer loop + vertex -856.2 279.903 179.269 + vertex -858.574 281.38 171.633 + vertex -856.167 279.978 171.3 + endloop + endfacet + facet normal -0.629042 -0.777299 -0.0106037 + outer loop + vertex -861.467 283.612 179.446 + vertex -861.434 283.693 171.584 + vertex -858.602 281.293 179.522 + endloop + endfacet + facet normal -0.628659 -0.777606 -0.0108332 + outer loop + vertex -858.602 281.293 179.522 + vertex -861.434 283.693 171.584 + vertex -858.574 281.38 171.633 + endloop + endfacet + facet normal -0.72519 -0.688465 -0.010769 + outer loop + vertex -864.539 286.85 179.313 + vertex -864.5 286.932 171.456 + vertex -861.467 283.612 179.446 + endloop + endfacet + facet normal -0.726031 -0.687588 -0.0100855 + outer loop + vertex -861.467 283.612 179.446 + vertex -864.5 286.932 171.456 + vertex -861.434 283.693 171.584 + endloop + endfacet + facet normal -0.797993 -0.602578 -0.0103859 + outer loop + vertex -867.593 290.896 179.252 + vertex -867.545 290.968 171.394 + vertex -864.539 286.85 179.313 + endloop + endfacet + facet normal -0.798149 -0.602374 -0.0102207 + outer loop + vertex -864.539 286.85 179.313 + vertex -867.545 290.968 171.394 + vertex -864.5 286.932 171.456 + endloop + endfacet + facet normal -0.850098 -0.526507 -0.0111285 + outer loop + vertex -870.495 295.581 179.267 + vertex -870.437 295.653 171.407 + vertex -867.593 290.896 179.252 + endloop + endfacet + facet normal -0.850951 -0.52515 -0.00999581 + outer loop + vertex -867.593 290.896 179.252 + vertex -870.437 295.653 171.407 + vertex -867.545 290.968 171.394 + endloop + endfacet + facet normal -0.888077 -0.459538 -0.0119597 + outer loop + vertex -873.188 300.784 179.304 + vertex -873.118 300.854 171.444 + vertex -870.495 295.581 179.267 + endloop + endfacet + facet normal -0.888804 -0.45816 -0.010787 + outer loop + vertex -870.495 295.581 179.267 + vertex -873.118 300.854 171.444 + vertex -870.437 295.653 171.407 + endloop + endfacet + facet normal -0.917085 -0.398497 -0.0124204 + outer loop + vertex -875.642 306.432 179.329 + vertex -875.564 306.498 171.465 + vertex -873.188 300.784 179.304 + endloop + endfacet + facet normal -0.917475 -0.397622 -0.0116642 + outer loop + vertex -873.188 300.784 179.304 + vertex -875.564 306.498 171.465 + vertex -873.118 300.854 171.444 + endloop + endfacet + facet normal -0.940388 -0.339841 -0.0133218 + outer loop + vertex -877.822 312.464 179.335 + vertex -877.734 312.528 171.469 + vertex -875.642 306.432 179.329 + endloop + endfacet + facet normal -0.940884 -0.33851 -0.0121576 + outer loop + vertex -875.642 306.432 179.329 + vertex -877.734 312.528 171.469 + vertex -875.564 306.498 171.465 + endloop + endfacet + facet normal -0.959591 -0.281069 -0.0136079 + outer loop + vertex -879.678 318.8 179.335 + vertex -879.584 318.86 171.463 + vertex -877.822 312.464 179.335 + endloop + endfacet + facet normal -0.959782 -0.280443 -0.0130563 + outer loop + vertex -877.822 312.464 179.335 + vertex -879.584 318.86 171.463 + vertex -877.734 312.528 171.469 + endloop + endfacet + facet normal -0.975026 -0.221638 -0.0141953 + outer loop + vertex -881.163 325.334 179.333 + vertex -881.062 325.391 171.458 + vertex -879.678 318.8 179.335 + endloop + endfacet + facet normal -0.975261 -0.220656 -0.0133329 + outer loop + vertex -879.678 318.8 179.335 + vertex -881.062 325.391 171.458 + vertex -879.584 318.86 171.463 + endloop + endfacet + facet normal -0.986765 -0.161516 -0.0143931 + outer loop + vertex -882.248 331.962 179.33 + vertex -882.142 332.016 171.453 + vertex -881.163 325.334 179.333 + endloop + endfacet + facet normal -0.986863 -0.160962 -0.0139109 + outer loop + vertex -881.163 325.334 179.333 + vertex -882.142 332.016 171.453 + vertex -881.062 325.391 171.458 + endloop + endfacet + facet normal -0.994753 -0.101267 -0.014514 + outer loop + vertex -882.926 338.62 179.327 + vertex -882.816 338.671 171.451 + vertex -882.248 331.962 179.33 + endloop + endfacet + facet normal -0.99481 -0.100769 -0.0140865 + outer loop + vertex -882.248 331.962 179.33 + vertex -882.816 338.671 171.451 + vertex -882.142 332.016 171.453 + endloop + endfacet + facet normal -0.973517 0.228457 -0.00855009 + outer loop + vertex -855.419 458.047 175.572 + vertex -855.378 458.068 171.53 + vertex -855.876 456.094 175.468 + endloop + endfacet + facet normal -0.974026 0.226227 -0.00973216 + outer loop + vertex -855.876 456.094 175.468 + vertex -855.378 458.068 171.53 + vertex -855.833 456.11 171.538 + endloop + endfacet + facet normal -0.973008 0.230025 -0.0185541 + outer loop + vertex -855.492 458.061 179.614 + vertex -855.419 458.047 175.572 + vertex -855.951 456.107 179.459 + endloop + endfacet + facet normal -0.973248 0.228959 -0.0191188 + outer loop + vertex -855.951 456.107 179.459 + vertex -855.419 458.047 175.572 + vertex -855.876 456.094 175.468 + endloop + endfacet + facet normal -0.342893 -0.939271 0.0139631 + outer loop + vertex -856.167 279.978 171.3 + vertex -856.193 279.87 163.427 + vertex -854.347 279.296 170.164 + endloop + endfacet + facet normal -0.360542 -0.932542 0.0193716 + outer loop + vertex -854.347 279.296 170.164 + vertex -856.193 279.87 163.427 + vertex -854.459 279.178 162.392 + endloop + endfacet + facet normal -0.502191 -0.864677 0.0117616 + outer loop + vertex -858.574 281.38 171.633 + vertex -858.587 281.281 163.773 + vertex -856.167 279.978 171.3 + endloop + endfacet + facet normal -0.506138 -0.862348 0.0134336 + outer loop + vertex -856.167 279.978 171.3 + vertex -858.587 281.281 163.773 + vertex -856.193 279.87 163.427 + endloop + endfacet + facet normal -0.628887 -0.777414 0.0113545 + outer loop + vertex -861.434 283.693 171.584 + vertex -861.448 283.59 163.747 + vertex -858.574 281.38 171.633 + endloop + endfacet + facet normal -0.628069 -0.778082 0.0108696 + outer loop + vertex -858.574 281.38 171.633 + vertex -861.448 283.59 163.747 + vertex -858.587 281.281 163.773 + endloop + endfacet + facet normal -0.726436 -0.68715 0.0107283 + outer loop + vertex -864.5 286.932 171.456 + vertex -864.522 286.833 163.632 + vertex -861.434 283.693 171.584 + endloop + endfacet + facet normal -0.725971 -0.687648 0.0103513 + outer loop + vertex -861.434 283.693 171.584 + vertex -864.522 286.833 163.632 + vertex -861.448 283.59 163.747 + endloop + endfacet + facet normal -0.7983 -0.602175 0.0100688 + outer loop + vertex -867.545 290.968 171.394 + vertex -867.57 290.87 163.578 + vertex -864.5 286.932 171.456 + endloop + endfacet + facet normal -0.798088 -0.60246 0.00984362 + outer loop + vertex -864.5 286.932 171.456 + vertex -867.57 290.87 163.578 + vertex -864.522 286.833 163.632 + endloop + endfacet + facet normal -0.850934 -0.525193 0.00918784 + outer loop + vertex -870.437 295.653 171.407 + vertex -870.463 295.559 163.593 + vertex -867.545 290.968 171.394 + endloop + endfacet + facet normal -0.850996 -0.525091 0.00927092 + outer loop + vertex -867.545 290.968 171.394 + vertex -870.463 295.559 163.593 + vertex -867.57 290.87 163.578 + endloop + endfacet + facet normal -0.888768 -0.458277 0.00851996 + outer loop + vertex -873.118 300.854 171.444 + vertex -873.147 300.764 163.629 + vertex -870.437 295.653 171.407 + endloop + endfacet + facet normal -0.888764 -0.458286 0.00851309 + outer loop + vertex -870.437 295.653 171.407 + vertex -873.147 300.764 163.629 + vertex -870.463 295.559 163.593 + endloop + endfacet + facet normal -0.917481 -0.3977 0.00790784 + outer loop + vertex -875.564 306.498 171.465 + vertex -875.594 306.411 163.649 + vertex -873.118 300.854 171.444 + endloop + endfacet + facet normal -0.917489 -0.397682 0.00792337 + outer loop + vertex -873.118 300.854 171.444 + vertex -875.594 306.411 163.649 + vertex -873.147 300.764 163.629 + endloop + endfacet + facet normal -0.940924 -0.338535 0.00743941 + outer loop + vertex -877.734 312.528 171.469 + vertex -877.766 312.446 163.648 + vertex -875.564 306.498 171.465 + endloop + endfacet + facet normal -0.940886 -0.338642 0.00734686 + outer loop + vertex -875.564 306.498 171.465 + vertex -877.766 312.446 163.648 + vertex -875.594 306.411 163.649 + endloop + endfacet + facet normal -0.959848 -0.280445 0.00657548 + outer loop + vertex -879.584 318.86 171.463 + vertex -879.616 318.784 163.64 + vertex -877.734 312.528 171.469 + endloop + endfacet + facet normal -0.959957 -0.280061 0.00690827 + outer loop + vertex -877.734 312.528 171.469 + vertex -879.616 318.784 163.64 + vertex -877.766 312.446 163.648 + endloop + endfacet + facet normal -0.97533 -0.220657 0.00641102 + outer loop + vertex -881.062 325.391 171.458 + vertex -881.097 325.319 163.633 + vertex -879.584 318.86 171.463 + endloop + endfacet + facet normal -0.975242 -0.221059 0.00606164 + outer loop + vertex -879.584 318.86 171.463 + vertex -881.097 325.319 163.633 + vertex -879.616 318.784 163.64 + endloop + endfacet + facet normal -0.986945 -0.160962 0.00550887 + outer loop + vertex -882.142 332.016 171.453 + vertex -882.175 331.949 163.629 + vertex -881.062 325.391 171.458 + endloop + endfacet + facet normal -0.98702 -0.16049 0.00591464 + outer loop + vertex -881.062 325.391 171.458 + vertex -882.175 331.949 163.629 + vertex -881.097 325.319 163.633 + endloop + endfacet + facet normal -0.994898 -0.10077 0.00482145 + outer loop + vertex -882.816 338.671 171.451 + vertex -882.848 338.609 163.626 + vertex -882.142 332.016 171.453 + endloop + endfacet + facet normal -0.994921 -0.10053 0.00502611 + outer loop + vertex -882.142 332.016 171.453 + vertex -882.848 338.609 163.626 + vertex -882.175 331.949 163.629 + endloop + endfacet + facet normal -0.974825 0.222737 0.0102083 + outer loop + vertex -855.37 458.121 167.739 + vertex -855.39 458.206 163.949 + vertex -855.82 456.156 167.679 + endloop + endfacet + facet normal -0.975394 0.220294 0.00880016 + outer loop + vertex -855.82 456.156 167.679 + vertex -855.39 458.206 163.949 + vertex -855.837 456.23 163.837 + endloop + endfacet + facet normal -0.974061 0.226281 0.00104516 + outer loop + vertex -855.378 458.068 171.53 + vertex -855.37 458.121 167.739 + vertex -855.833 456.11 171.538 + endloop + endfacet + facet normal -0.974804 0.223063 -0.000749014 + outer loop + vertex -855.833 456.11 171.538 + vertex -855.37 458.121 167.739 + vertex -855.82 456.156 167.679 + endloop + endfacet + facet normal -0.350624 -0.93574 0.0381251 + outer loop + vertex -856.193 279.87 163.427 + vertex -856.237 279.572 155.702 + vertex -854.459 279.178 162.392 + endloop + endfacet + facet normal -0.353618 -0.934577 0.0389897 + outer loop + vertex -854.459 279.178 162.392 + vertex -856.237 279.572 155.702 + vertex -854.397 278.845 154.976 + endloop + endfacet + facet normal -0.503498 -0.863268 0.03546 + outer loop + vertex -858.587 281.281 163.773 + vertex -858.643 280.992 155.965 + vertex -856.193 279.87 163.427 + endloop + endfacet + facet normal -0.505226 -0.862228 0.0361835 + outer loop + vertex -856.193 279.87 163.427 + vertex -858.643 280.992 155.965 + vertex -856.237 279.572 155.702 + endloop + endfacet + facet normal -0.627876 -0.777586 0.0336535 + outer loop + vertex -861.448 283.59 163.747 + vertex -861.515 283.305 155.918 + vertex -858.587 281.281 163.773 + endloop + endfacet + facet normal -0.6271 -0.778231 0.0331978 + outer loop + vertex -858.587 281.281 163.773 + vertex -861.515 283.305 155.918 + vertex -858.643 280.992 155.965 + endloop + endfacet + facet normal -0.726017 -0.686914 0.0323861 + outer loop + vertex -864.522 286.833 163.632 + vertex -864.605 286.552 155.802 + vertex -861.448 283.59 163.747 + endloop + endfacet + facet normal -0.724585 -0.688477 0.0312342 + outer loop + vertex -861.448 283.59 163.747 + vertex -864.605 286.552 155.802 + vertex -861.515 283.305 155.918 + endloop + endfacet + facet normal -0.797887 -0.602028 0.0306417 + outer loop + vertex -867.57 290.87 163.578 + vertex -867.67 290.604 155.753 + vertex -864.522 286.833 163.632 + endloop + endfacet + facet normal -0.797396 -0.602704 0.0301222 + outer loop + vertex -864.522 286.833 163.632 + vertex -867.67 290.604 155.753 + vertex -864.605 286.552 155.802 + endloop + endfacet + facet normal -0.850614 -0.524924 0.0301799 + outer loop + vertex -870.463 295.559 163.593 + vertex -870.578 295.296 155.774 + vertex -867.57 290.87 163.578 + endloop + endfacet + facet normal -0.849537 -0.526746 0.0287318 + outer loop + vertex -867.57 290.87 163.578 + vertex -870.578 295.296 155.774 + vertex -867.67 290.604 155.753 + endloop + endfacet + facet normal -0.888366 -0.458221 0.0289775 + outer loop + vertex -873.147 300.764 163.629 + vertex -873.274 300.516 155.811 + vertex -870.463 295.559 163.593 + endloop + endfacet + facet normal -0.888081 -0.458803 0.0285038 + outer loop + vertex -870.463 295.559 163.593 + vertex -873.274 300.516 155.811 + vertex -870.578 295.296 155.774 + endloop + endfacet + facet normal -0.917124 -0.397595 0.0283014 + outer loop + vertex -875.594 306.411 163.649 + vertex -875.733 306.174 155.83 + vertex -873.147 300.764 163.629 + endloop + endfacet + facet normal -0.916749 -0.398513 0.0275401 + outer loop + vertex -873.147 300.764 163.629 + vertex -875.733 306.174 155.83 + vertex -873.274 300.516 155.811 + endloop + endfacet + facet normal -0.94055 -0.33852 0.0277622 + outer loop + vertex -877.766 312.446 163.648 + vertex -877.916 312.221 155.829 + vertex -875.594 306.411 163.649 + endloop + endfacet + facet normal -0.940225 -0.339485 0.0269486 + outer loop + vertex -875.594 306.411 163.649 + vertex -877.916 312.221 155.829 + vertex -875.733 306.174 155.83 + endloop + endfacet + facet normal -0.959631 -0.27994 0.0272302 + outer loop + vertex -879.616 318.784 163.64 + vertex -879.775 318.571 155.819 + vertex -877.766 312.446 163.648 + endloop + endfacet + facet normal -0.959389 -0.280844 0.026461 + outer loop + vertex -877.766 312.446 163.648 + vertex -879.775 318.571 155.819 + vertex -877.916 312.221 155.829 + endloop + endfacet + facet normal -0.974928 -0.220966 0.026274 + outer loop + vertex -881.097 325.319 163.633 + vertex -881.262 325.12 155.812 + vertex -879.616 318.784 163.64 + endloop + endfacet + facet normal -0.974849 -0.22135 0.0259473 + outer loop + vertex -879.616 318.784 163.64 + vertex -881.262 325.12 155.812 + vertex -879.775 318.571 155.819 + endloop + endfacet + facet normal -0.986723 -0.160429 0.0253023 + outer loop + vertex -882.175 331.949 163.629 + vertex -882.345 331.761 155.808 + vertex -881.097 325.319 163.633 + endloop + endfacet + facet normal -0.98667 -0.160803 0.0249868 + outer loop + vertex -881.097 325.319 163.633 + vertex -882.345 331.761 155.808 + vertex -881.262 325.12 155.812 + endloop + endfacet + facet normal -0.994628 -0.100492 0.0248392 + outer loop + vertex -882.848 338.609 163.626 + vertex -883.026 338.436 155.806 + vertex -882.175 331.949 163.629 + endloop + endfacet + facet normal -0.994552 -0.101422 0.0240596 + outer loop + vertex -882.175 331.949 163.629 + vertex -883.026 338.436 155.806 + vertex -882.345 331.761 155.808 + endloop + endfacet + facet normal -0.975786 0.216853 0.0285784 + outer loop + vertex -855.44 458.328 160.056 + vertex -855.519 458.485 156.165 + vertex -855.885 456.336 159.975 + endloop + endfacet + facet normal -0.976361 0.214432 0.0271582 + outer loop + vertex -855.885 456.336 159.975 + vertex -855.519 458.485 156.165 + vertex -855.962 456.481 156.066 + endloop + endfacet + facet normal -0.975377 0.21969 0.0193762 + outer loop + vertex -855.39 458.206 163.949 + vertex -855.44 458.328 160.056 + vertex -855.837 456.23 163.837 + endloop + endfacet + facet normal -0.975936 0.217312 0.017998 + outer loop + vertex -855.837 456.23 163.837 + vertex -855.44 458.328 160.056 + vertex -855.885 456.336 159.975 + endloop + endfacet + facet normal -0.345508 -0.936407 0.0613781 + outer loop + vertex -856.237 279.572 155.702 + vertex -856.315 279.087 147.874 + vertex -854.397 278.845 154.976 + endloop + endfacet + facet normal -0.354547 -0.932849 0.0639407 + outer loop + vertex -854.397 278.845 154.976 + vertex -856.315 279.087 147.874 + vertex -854.467 278.311 146.787 + endloop + endfacet + facet normal -0.502883 -0.862379 0.0584073 + outer loop + vertex -858.643 280.992 155.965 + vertex -858.745 280.523 148.162 + vertex -856.237 279.572 155.702 + endloop + endfacet + facet normal -0.502766 -0.86245 0.0583593 + outer loop + vertex -856.237 279.572 155.702 + vertex -858.745 280.523 148.162 + vertex -856.315 279.087 147.874 + endloop + endfacet + facet normal -0.626695 -0.777267 0.0557573 + outer loop + vertex -861.515 283.305 155.918 + vertex -861.638 282.842 148.09 + vertex -858.643 280.992 155.965 + endloop + endfacet + facet normal -0.625336 -0.778417 0.0549704 + outer loop + vertex -858.643 280.992 155.965 + vertex -861.638 282.842 148.09 + vertex -858.745 280.523 148.162 + endloop + endfacet + facet normal -0.724296 -0.687397 0.0536739 + outer loop + vertex -864.605 286.552 155.802 + vertex -864.75 286.092 147.949 + vertex -861.515 283.305 155.918 + endloop + endfacet + facet normal -0.722279 -0.689639 0.0520713 + outer loop + vertex -861.515 283.305 155.918 + vertex -864.75 286.092 147.949 + vertex -861.638 282.842 148.09 + endloop + endfacet + facet normal -0.796803 -0.601994 0.0520338 + outer loop + vertex -867.67 290.604 155.753 + vertex -867.844 290.155 147.892 + vertex -864.605 286.552 155.802 + endloop + endfacet + facet normal -0.794993 -0.604544 0.0501311 + outer loop + vertex -864.605 286.552 155.802 + vertex -867.844 290.155 147.892 + vertex -864.75 286.092 147.949 + endloop + endfacet + facet normal -0.848781 -0.526369 0.0500635 + outer loop + vertex -870.578 295.296 155.774 + vertex -870.779 294.872 147.915 + vertex -867.67 290.604 155.753 + endloop + endfacet + facet normal -0.847942 -0.527825 0.0489381 + outer loop + vertex -867.67 290.604 155.753 + vertex -870.779 294.872 147.915 + vertex -867.844 290.155 147.892 + endloop + endfacet + facet normal -0.887302 -0.45855 0.0492661 + outer loop + vertex -873.274 300.516 155.811 + vertex -873.499 300.108 147.956 + vertex -870.578 295.296 155.774 + endloop + endfacet + facet normal -0.886235 -0.460796 0.0474845 + outer loop + vertex -870.578 295.296 155.774 + vertex -873.499 300.108 147.956 + vertex -870.779 294.872 147.915 + endloop + endfacet + facet normal -0.91599 -0.398255 0.048534 + outer loop + vertex -875.733 306.174 155.83 + vertex -875.98 305.786 147.976 + vertex -873.274 300.516 155.811 + endloop + endfacet + facet normal -0.915261 -0.400105 0.0470376 + outer loop + vertex -873.274 300.516 155.811 + vertex -875.98 305.786 147.976 + vertex -873.499 300.108 147.956 + endloop + endfacet + facet normal -0.939497 -0.339216 0.0477307 + outer loop + vertex -877.916 312.221 155.829 + vertex -878.182 311.851 147.974 + vertex -875.733 306.174 155.83 + endloop + endfacet + facet normal -0.938984 -0.340816 0.0464146 + outer loop + vertex -875.733 306.174 155.83 + vertex -878.182 311.851 147.974 + vertex -875.98 305.786 147.976 + endloop + endfacet + facet normal -0.958663 -0.280602 0.0472044 + outer loop + vertex -879.775 318.571 155.819 + vertex -880.059 318.22 147.965 + vertex -877.916 312.221 155.829 + endloop + endfacet + facet normal -0.958202 -0.282422 0.0456901 + outer loop + vertex -877.916 312.221 155.829 + vertex -880.059 318.22 147.965 + vertex -878.182 311.851 147.974 + endloop + endfacet + facet normal -0.974149 -0.221168 0.0460183 + outer loop + vertex -881.262 325.12 155.812 + vertex -881.559 324.79 147.957 + vertex -879.775 318.571 155.819 + endloop + endfacet + facet normal -0.973953 -0.22221 0.0451492 + outer loop + vertex -879.775 318.571 155.819 + vertex -881.559 324.79 147.957 + vertex -880.059 318.22 147.965 + endloop + endfacet + facet normal -0.985966 -0.160674 0.0453312 + outer loop + vertex -882.345 331.761 155.808 + vertex -882.656 331.454 147.954 + vertex -881.262 325.12 155.812 + endloop + endfacet + facet normal -0.985761 -0.162298 0.0439856 + outer loop + vertex -881.262 325.12 155.812 + vertex -882.656 331.454 147.954 + vertex -881.559 324.79 147.957 + endloop + endfacet + facet normal -0.993904 -0.101351 0.0433819 + outer loop + vertex -883.026 338.436 155.806 + vertex -883.339 338.15 147.952 + vertex -882.345 331.761 155.808 + endloop + endfacet + facet normal -0.9939 -0.101416 0.0433285 + outer loop + vertex -882.345 331.761 155.808 + vertex -883.339 338.15 147.952 + vertex -882.656 331.454 147.954 + endloop + endfacet + facet normal -0.976478 0.210441 0.0469502 + outer loop + vertex -855.63 458.682 152.192 + vertex -855.77 458.916 148.224 + vertex -856.068 456.669 152.104 + endloop + endfacet + facet normal -0.977132 0.207742 0.0453363 + outer loop + vertex -856.068 456.669 152.104 + vertex -855.77 458.916 148.224 + vertex -856.203 456.899 148.124 + endloop + endfacet + facet normal -0.976135 0.213857 0.0377662 + outer loop + vertex -855.519 458.485 156.165 + vertex -855.63 458.682 152.192 + vertex -855.962 456.481 156.066 + endloop + endfacet + facet normal -0.976821 0.210994 0.0360805 + outer loop + vertex -855.962 456.481 156.066 + vertex -855.63 458.682 152.192 + vertex -856.068 456.669 152.104 + endloop + endfacet + facet normal -0.343304 -0.935382 0.0848683 + outer loop + vertex -856.315 279.087 147.874 + vertex -856.444 278.408 139.862 + vertex -854.467 278.311 146.787 + endloop + endfacet + facet normal -0.355655 -0.930421 0.0884629 + outer loop + vertex -854.467 278.311 146.787 + vertex -856.444 278.408 139.862 + vertex -854.572 277.566 138.533 + endloop + endfacet + facet normal -0.499981 -0.862251 0.0808821 + outer loop + vertex -858.745 280.523 148.162 + vertex -858.903 279.876 140.288 + vertex -856.315 279.087 147.874 + endloop + endfacet + facet normal -0.50068 -0.861819 0.0811657 + outer loop + vertex -856.315 279.087 147.874 + vertex -858.903 279.876 140.288 + vertex -856.444 278.408 139.862 + endloop + endfacet + facet normal -0.624722 -0.77694 0.0780089 + outer loop + vertex -861.638 282.842 148.09 + vertex -861.822 282.204 140.252 + vertex -858.745 280.523 148.162 + endloop + endfacet + facet normal -0.622087 -0.779201 0.0765035 + outer loop + vertex -858.745 280.523 148.162 + vertex -861.822 282.204 140.252 + vertex -858.903 279.876 140.288 + endloop + endfacet + facet normal -0.721719 -0.68811 0.0750048 + outer loop + vertex -864.75 286.092 147.949 + vertex -864.966 285.461 140.091 + vertex -861.638 282.842 148.09 + endloop + endfacet + facet normal -0.719441 -0.690683 0.0732143 + outer loop + vertex -861.638 282.842 148.09 + vertex -864.966 285.461 140.091 + vertex -861.822 282.204 140.252 + endloop + endfacet + facet normal -0.794074 -0.603532 0.0720822 + outer loop + vertex -867.844 290.155 147.892 + vertex -868.093 289.541 140.007 + vertex -864.75 286.092 147.949 + endloop + endfacet + facet normal -0.792417 -0.605909 0.0703528 + outer loop + vertex -864.75 286.092 147.949 + vertex -868.093 289.541 140.007 + vertex -864.966 285.461 140.091 + endloop + endfacet + facet normal -0.846787 -0.527212 0.0707001 + outer loop + vertex -870.779 294.872 147.915 + vertex -871.066 294.274 140.02 + vertex -867.844 290.155 147.892 + endloop + endfacet + facet normal -0.844781 -0.530773 0.0680161 + outer loop + vertex -867.844 290.155 147.892 + vertex -871.066 294.274 140.02 + vertex -868.093 289.541 140.007 + endloop + endfacet + facet normal -0.885023 -0.460339 0.0694435 + outer loop + vertex -873.499 300.108 147.956 + vertex -873.822 299.539 140.064 + vertex -870.779 294.872 147.915 + endloop + endfacet + facet normal -0.88368 -0.463243 0.0671964 + outer loop + vertex -870.779 294.872 147.915 + vertex -873.822 299.539 140.064 + vertex -871.066 294.274 140.02 + endloop + endfacet + facet normal -0.914102 -0.399676 0.0683897 + outer loop + vertex -875.98 305.786 147.976 + vertex -876.334 305.245 140.089 + vertex -873.499 300.108 147.956 + endloop + endfacet + facet normal -0.913142 -0.402198 0.0663977 + outer loop + vertex -873.499 300.108 147.956 + vertex -876.334 305.245 140.089 + vertex -873.822 299.539 140.064 + endloop + endfacet + facet normal -0.937847 -0.340396 0.0676337 + outer loop + vertex -878.182 311.851 147.974 + vertex -878.564 311.336 140.088 + vertex -875.98 305.786 147.976 + endloop + endfacet + facet normal -0.937045 -0.343004 0.0655356 + outer loop + vertex -875.98 305.786 147.976 + vertex -878.564 311.336 140.088 + vertex -876.334 305.245 140.089 + endloop + endfacet + facet normal -0.957075 -0.282059 0.0667146 + outer loop + vertex -880.059 318.22 147.965 + vertex -880.466 317.733 140.078 + vertex -878.182 311.851 147.974 + endloop + endfacet + facet normal -0.956533 -0.284315 0.0648779 + outer loop + vertex -878.182 311.851 147.974 + vertex -880.466 317.733 140.078 + vertex -878.564 311.336 140.088 + endloop + endfacet + facet normal -0.972858 -0.221936 0.0655161 + outer loop + vertex -881.559 324.79 147.957 + vertex -881.985 324.331 140.071 + vertex -880.059 318.22 147.965 + endloop + endfacet + facet normal -0.972515 -0.223898 0.0639137 + outer loop + vertex -880.059 318.22 147.965 + vertex -881.985 324.331 140.071 + vertex -880.466 317.733 140.078 + endloop + endfacet + facet normal -0.98472 -0.162117 0.0635918 + outer loop + vertex -882.656 331.454 147.954 + vertex -883.095 331.025 140.067 + vertex -881.559 324.79 147.957 + endloop + endfacet + facet normal -0.984601 -0.163175 0.0627327 + outer loop + vertex -881.559 324.79 147.957 + vertex -883.095 331.025 140.067 + vertex -881.985 324.331 140.071 + endloop + endfacet + facet normal -0.992922 -0.101311 0.0619838 + outer loop + vertex -883.339 338.15 147.952 + vertex -883.791 337.752 140.066 + vertex -882.656 331.454 147.954 + endloop + endfacet + facet normal -0.992845 -0.102766 0.0608114 + outer loop + vertex -882.656 331.454 147.954 + vertex -883.791 337.752 140.066 + vertex -883.095 331.025 140.067 + endloop + endfacet + facet normal -0.977719 0.199714 0.0646549 + outer loop + vertex -855.939 459.188 144.27 + vertex -856.137 459.498 140.323 + vertex -856.364 457.145 144.158 + endloop + endfacet + facet normal -0.977228 0.2017 0.0659026 + outer loop + vertex -856.364 457.145 144.158 + vertex -856.137 459.498 140.323 + vertex -856.582 457.383 140.195 + endloop + endfacet + facet normal -0.976711 0.207123 0.0559958 + outer loop + vertex -855.77 458.916 148.224 + vertex -855.939 459.188 144.27 + vertex -856.203 456.899 148.124 + endloop + endfacet + facet normal -0.978308 0.200532 0.0519717 + outer loop + vertex -856.203 456.899 148.124 + vertex -855.939 459.188 144.27 + vertex -856.364 457.145 144.158 + endloop + endfacet + facet normal -0.34158 -0.933374 0.110166 + outer loop + vertex -856.444 278.408 139.862 + vertex -856.616 277.526 131.855 + vertex -854.572 277.566 138.533 + endloop + endfacet + facet normal -0.361362 -0.92516 0.116174 + outer loop + vertex -854.572 277.566 138.533 + vertex -856.616 277.526 131.855 + vertex -854.804 276.689 130.825 + endloop + endfacet + facet normal -0.496577 -0.861692 0.104392 + outer loop + vertex -858.903 279.876 140.288 + vertex -859.109 279.03 132.32 + vertex -856.444 278.408 139.862 + endloop + endfacet + facet normal -0.499261 -0.860007 0.10548 + outer loop + vertex -856.444 278.408 139.862 + vertex -859.109 279.03 132.32 + vertex -856.616 277.526 131.855 + endloop + endfacet + facet normal -0.620979 -0.777447 0.0998083 + outer loop + vertex -861.822 282.204 140.252 + vertex -862.074 281.394 132.381 + vertex -858.903 279.876 140.288 + endloop + endfacet + facet normal -0.619179 -0.779011 0.0987862 + outer loop + vertex -858.903 279.876 140.288 + vertex -862.074 281.394 132.381 + vertex -859.109 279.03 132.32 + endloop + endfacet + facet normal -0.718597 -0.68873 0.0962776 + outer loop + vertex -864.966 285.461 140.091 + vertex -865.255 284.666 132.251 + vertex -861.822 282.204 140.252 + endloop + endfacet + facet normal -0.71574 -0.692006 0.0940438 + outer loop + vertex -861.822 282.204 140.252 + vertex -865.255 284.666 132.251 + vertex -862.074 281.394 132.381 + endloop + endfacet + facet normal -0.791148 -0.604464 0.093322 + outer loop + vertex -868.093 289.541 140.007 + vertex -868.421 288.756 132.143 + vertex -864.966 285.461 140.091 + endloop + endfacet + facet normal -0.788611 -0.608169 0.0906835 + outer loop + vertex -864.966 285.461 140.091 + vertex -868.421 288.756 132.143 + vertex -865.255 284.666 132.251 + endloop + endfacet + facet normal -0.843199 -0.529841 0.0910155 + outer loop + vertex -871.066 294.274 140.02 + vertex -871.437 293.509 132.129 + vertex -868.093 289.541 140.007 + endloop + endfacet + facet normal -0.841183 -0.533488 0.0883224 + outer loop + vertex -868.093 289.541 140.007 + vertex -871.437 293.509 132.129 + vertex -868.421 288.756 132.143 + endloop + endfacet + facet normal -0.882063 -0.462585 0.0893322 + outer loop + vertex -873.822 299.539 140.064 + vertex -874.239 298.808 132.168 + vertex -871.066 294.274 140.02 + endloop + endfacet + facet normal -0.880441 -0.46618 0.086601 + outer loop + vertex -871.066 294.274 140.02 + vertex -874.239 298.808 132.168 + vertex -871.437 293.509 132.129 + endloop + endfacet + facet normal -0.911548 -0.401589 0.0883548 + outer loop + vertex -876.334 305.245 140.089 + vertex -876.793 304.55 132.197 + vertex -873.822 299.539 140.064 + endloop + endfacet + facet normal -0.910197 -0.405252 0.0855114 + outer loop + vertex -873.822 299.539 140.064 + vertex -876.793 304.55 132.197 + vertex -874.239 298.808 132.168 + endloop + endfacet + facet normal -0.935472 -0.342425 0.0873887 + outer loop + vertex -878.564 311.336 140.088 + vertex -879.06 310.678 132.199 + vertex -876.334 305.245 140.089 + endloop + endfacet + facet normal -0.934495 -0.345734 0.0847729 + outer loop + vertex -876.334 305.245 140.089 + vertex -879.06 310.678 132.199 + vertex -876.793 304.55 132.197 + endloop + endfacet + facet normal -0.955016 -0.283832 0.0859315 + outer loop + vertex -880.466 317.733 140.078 + vertex -880.99 317.11 132.191 + vertex -878.564 311.336 140.088 + endloop + endfacet + facet normal -0.954439 -0.286367 0.083901 + outer loop + vertex -878.564 311.336 140.088 + vertex -880.99 317.11 132.191 + vertex -879.06 310.678 132.199 + endloop + endfacet + facet normal -0.970997 -0.223525 0.0848609 + outer loop + vertex -881.985 324.331 140.071 + vertex -882.539 323.744 132.182 + vertex -880.466 317.733 140.078 + endloop + endfacet + facet normal -0.970508 -0.226536 0.0824402 + outer loop + vertex -880.466 317.733 140.078 + vertex -882.539 323.744 132.182 + vertex -880.99 317.11 132.191 + endloop + endfacet + facet normal -0.983108 -0.162917 0.083411 + outer loop + vertex -883.095 331.025 140.067 + vertex -883.673 330.477 132.179 + vertex -881.985 324.331 140.071 + endloop + endfacet + facet normal -0.982853 -0.165462 0.0813747 + outer loop + vertex -881.985 324.331 140.071 + vertex -883.673 330.477 132.179 + vertex -882.539 323.744 132.182 + endloop + endfacet + facet normal -0.991413 -0.102613 0.0810621 + outer loop + vertex -883.791 337.752 140.066 + vertex -884.383 337.244 132.178 + vertex -883.095 331.025 140.067 + endloop + endfacet + facet normal -0.991356 -0.10404 0.0799283 + outer loop + vertex -883.095 331.025 140.067 + vertex -884.383 337.244 132.178 + vertex -883.673 330.477 132.179 + endloop + endfacet + facet normal -0.975532 0.203397 0.0834706 + outer loop + vertex -856.37 459.858 136.269 + vertex -856.632 460.26 132.225 + vertex -856.844 457.613 136.192 + endloop + endfacet + facet normal -0.976284 0.200553 0.081533 + outer loop + vertex -856.844 457.613 136.192 + vertex -856.632 460.26 132.225 + vertex -857.122 457.908 132.141 + endloop + endfacet + facet normal -0.976771 0.201113 0.07398 + outer loop + vertex -856.137 459.498 140.323 + vertex -856.37 459.858 136.269 + vertex -856.582 457.383 140.195 + endloop + endfacet + facet normal -0.976086 0.20378 0.0756984 + outer loop + vertex -856.582 457.383 140.195 + vertex -856.37 459.858 136.269 + vertex -856.844 457.613 136.192 + endloop + endfacet + facet normal -0.349466 -0.926682 0.138329 + outer loop + vertex -856.616 277.526 131.855 + vertex -856.737 276.396 123.981 + vertex -854.804 276.689 130.825 + endloop + endfacet + facet normal -0.347656 -0.927433 0.13785 + outer loop + vertex -854.804 276.689 130.825 + vertex -856.737 276.396 123.981 + vertex -854.812 275.606 123.522 + endloop + endfacet + facet normal -0.494182 -0.859445 0.130911 + outer loop + vertex -859.109 279.03 132.32 + vertex -859.315 277.912 124.202 + vertex -856.616 277.526 131.855 + endloop + endfacet + facet normal -0.494128 -0.85948 0.13089 + outer loop + vertex -856.616 277.526 131.855 + vertex -859.315 277.912 124.202 + vertex -856.737 276.396 123.981 + endloop + endfacet + facet normal -0.617209 -0.777161 0.122774 + outer loop + vertex -862.074 281.394 132.381 + vertex -862.371 280.372 124.412 + vertex -859.109 279.03 132.32 + endloop + endfacet + facet normal -0.617107 -0.777251 0.122716 + outer loop + vertex -859.109 279.03 132.32 + vertex -862.371 280.372 124.412 + vertex -859.315 277.912 124.202 + endloop + endfacet + facet normal -0.714394 -0.689752 0.117825 + outer loop + vertex -865.255 284.666 132.251 + vertex -865.615 283.7 124.413 + vertex -862.074 281.394 132.381 + endloop + endfacet + facet normal -0.711444 -0.693182 0.115521 + outer loop + vertex -862.074 281.394 132.381 + vertex -865.615 283.7 124.413 + vertex -862.371 280.372 124.412 + endloop + endfacet + facet normal -0.786993 -0.606293 0.114239 + outer loop + vertex -868.421 288.756 132.143 + vertex -868.829 287.814 124.33 + vertex -865.255 284.666 132.251 + endloop + endfacet + facet normal -0.784137 -0.610532 0.111265 + outer loop + vertex -865.255 284.666 132.251 + vertex -868.829 287.814 124.33 + vertex -865.615 283.7 124.413 + endloop + endfacet + facet normal -0.839266 -0.532202 0.111329 + outer loop + vertex -871.437 293.509 132.129 + vertex -871.894 292.59 124.287 + vertex -868.421 288.756 132.143 + endloop + endfacet + facet normal -0.837091 -0.536214 0.10841 + outer loop + vertex -868.421 288.756 132.143 + vertex -871.894 292.59 124.287 + vertex -868.829 287.814 124.33 + endloop + endfacet + facet normal -0.878379 -0.465259 0.109474 + outer loop + vertex -874.239 298.808 132.168 + vertex -874.748 297.919 124.305 + vertex -871.437 293.509 132.129 + endloop + endfacet + facet normal -0.876433 -0.469675 0.106161 + outer loop + vertex -871.437 293.509 132.129 + vertex -874.748 297.919 124.305 + vertex -871.894 292.59 124.287 + endloop + endfacet + facet normal -0.908147 -0.404453 0.108109 + outer loop + vertex -876.793 304.55 132.197 + vertex -877.352 303.705 124.333 + vertex -874.239 298.808 132.168 + endloop + endfacet + facet normal -0.90665 -0.408633 0.104902 + outer loop + vertex -874.239 298.808 132.168 + vertex -877.352 303.705 124.333 + vertex -874.748 297.919 124.305 + endloop + endfacet + facet normal -0.932433 -0.344981 0.107498 + outer loop + vertex -879.06 310.678 132.199 + vertex -879.668 309.874 124.34 + vertex -876.793 304.55 132.197 + endloop + endfacet + facet normal -0.931107 -0.349649 0.10385 + outer loop + vertex -876.793 304.55 132.197 + vertex -879.668 309.874 124.34 + vertex -877.352 303.705 124.333 + endloop + endfacet + facet normal -0.952448 -0.285739 0.10581 + outer loop + vertex -880.99 317.11 132.191 + vertex -881.636 316.354 124.334 + vertex -879.06 310.678 132.199 + endloop + endfacet + facet normal -0.951757 -0.288956 0.103263 + outer loop + vertex -879.06 310.678 132.199 + vertex -881.636 316.354 124.334 + vertex -879.668 309.874 124.34 + endloop + endfacet + facet normal -0.968528 -0.226047 0.104189 + outer loop + vertex -882.539 323.744 132.182 + vertex -883.219 323.033 124.326 + vertex -880.99 317.11 132.191 + endloop + endfacet + facet normal -0.968048 -0.229237 0.101651 + outer loop + vertex -880.99 317.11 132.191 + vertex -883.219 323.033 124.326 + vertex -881.636 316.354 124.334 + endloop + endfacet + facet normal -0.981045 -0.165146 0.101383 + outer loop + vertex -883.673 330.477 132.179 + vertex -884.373 329.812 124.322 + vertex -882.539 323.744 132.182 + endloop + endfacet + facet normal -0.980881 -0.167007 0.0999086 + outer loop + vertex -882.539 323.744 132.182 + vertex -884.373 329.812 124.322 + vertex -883.219 323.033 124.326 + endloop + endfacet + facet normal -0.989682 -0.103861 0.0986999 + outer loop + vertex -884.383 337.244 132.178 + vertex -885.102 336.626 124.321 + vertex -883.673 330.477 132.179 + endloop + endfacet + facet normal -0.989626 -0.105856 0.0971286 + outer loop + vertex -883.673 330.477 132.179 + vertex -885.102 336.626 124.321 + vertex -884.373 329.812 124.322 + endloop + endfacet + facet normal -0.971066 0.215624 0.102649 + outer loop + vertex -856.909 460.682 128.379 + vertex -857.212 461.143 124.545 + vertex -857.514 458.167 127.938 + endloop + endfacet + facet normal -0.960358 0.246323 0.130527 + outer loop + vertex -857.514 458.167 127.938 + vertex -857.212 461.143 124.545 + vertex -858.132 458.353 123.039 + endloop + endfacet + facet normal -0.975447 0.199994 0.0922235 + outer loop + vertex -856.632 460.26 132.225 + vertex -856.909 460.682 128.379 + vertex -857.122 457.908 132.141 + endloop + endfacet + facet normal -0.97099 0.215398 0.103835 + outer loop + vertex -857.122 457.908 132.141 + vertex -856.909 460.682 128.379 + vertex -857.514 458.167 127.938 + endloop + endfacet + facet normal -0.339342 -0.925333 0.169136 + outer loop + vertex -856.737 276.396 123.981 + vertex -856.634 275.039 116.766 + vertex -854.812 275.606 123.522 + endloop + endfacet + facet normal -0.331848 -0.928367 0.167369 + outer loop + vertex -854.812 275.606 123.522 + vertex -856.634 275.039 116.766 + vertex -855.008 274.318 115.99 + endloop + endfacet + facet normal -0.489691 -0.856581 0.1627 + outer loop + vertex -859.315 277.912 124.202 + vertex -859.382 276.333 115.691 + vertex -856.737 276.396 123.981 + endloop + endfacet + facet normal -0.470293 -0.868505 0.156599 + outer loop + vertex -856.737 276.396 123.981 + vertex -859.382 276.333 115.691 + vertex -856.634 275.039 116.766 + endloop + endfacet + facet normal -0.613886 -0.775407 0.147947 + outer loop + vertex -862.371 280.372 124.412 + vertex -862.631 279.023 116.268 + vertex -859.315 277.912 124.202 + endloop + endfacet + facet normal -0.614835 -0.774556 0.148462 + outer loop + vertex -859.315 277.912 124.202 + vertex -862.631 279.023 116.268 + vertex -859.382 276.333 115.691 + endloop + endfacet + facet normal -0.709241 -0.69104 0.139426 + outer loop + vertex -865.615 283.7 124.413 + vertex -866.016 282.52 116.521 + vertex -862.371 280.372 124.412 + endloop + endfacet + facet normal -0.706688 -0.69405 0.137428 + outer loop + vertex -862.371 280.372 124.412 + vertex -866.016 282.52 116.521 + vertex -862.631 279.023 116.268 + endloop + endfacet + facet normal -0.782009 -0.60838 0.135412 + outer loop + vertex -868.829 287.814 124.33 + vertex -869.31 286.7 116.553 + vertex -865.615 283.7 124.413 + endloop + endfacet + facet normal -0.77819 -0.614124 0.131425 + outer loop + vertex -865.615 283.7 124.413 + vertex -869.31 286.7 116.553 + vertex -866.016 282.52 116.521 + endloop + endfacet + facet normal -0.834806 -0.534541 0.131776 + outer loop + vertex -871.894 292.59 124.287 + vertex -872.433 291.515 116.514 + vertex -868.829 287.814 124.33 + endloop + endfacet + facet normal -0.832448 -0.538976 0.128588 + outer loop + vertex -868.829 287.814 124.33 + vertex -872.433 291.515 116.514 + vertex -869.31 286.7 116.553 + endloop + endfacet + facet normal -0.873931 -0.468413 0.129747 + outer loop + vertex -874.748 297.919 124.305 + vertex -875.345 296.872 116.502 + vertex -871.894 292.59 124.287 + endloop + endfacet + facet normal -0.871695 -0.4736 0.125902 + outer loop + vertex -871.894 292.59 124.287 + vertex -875.345 296.872 116.502 + vertex -872.433 291.515 116.514 + endloop + endfacet + facet normal -0.904124 -0.407608 0.128121 + outer loop + vertex -877.352 303.705 124.333 + vertex -878.009 302.705 116.518 + vertex -874.748 297.919 124.305 + endloop + endfacet + facet normal -0.902435 -0.412468 0.124427 + outer loop + vertex -874.748 297.919 124.305 + vertex -878.009 302.705 116.518 + vertex -875.345 296.872 116.502 + endloop + endfacet + facet normal -0.92866 -0.348758 0.126324 + outer loop + vertex -879.668 309.874 124.34 + vertex -880.376 308.93 116.53 + vertex -877.352 303.705 124.333 + endloop + endfacet + facet normal -0.927519 -0.352928 0.12309 + outer loop + vertex -877.352 303.705 124.333 + vertex -880.376 308.93 116.53 + vertex -878.009 302.705 116.518 + endloop + endfacet + facet normal -0.949303 -0.288189 0.125581 + outer loop + vertex -881.636 316.354 124.334 + vertex -882.397 315.459 116.526 + vertex -879.668 309.874 124.34 + endloop + endfacet + facet normal -0.948222 -0.293485 0.121418 + outer loop + vertex -879.668 309.874 124.34 + vertex -882.397 315.459 116.526 + vertex -880.376 308.93 116.53 + endloop + endfacet + facet normal -0.965725 -0.22866 0.122843 + outer loop + vertex -883.219 323.033 124.326 + vertex -884.013 322.195 116.52 + vertex -881.636 316.354 124.334 + endloop + endfacet + facet normal -0.965339 -0.231443 0.120645 + outer loop + vertex -881.636 316.354 124.334 + vertex -884.013 322.195 116.52 + vertex -882.397 315.459 116.526 + endloop + endfacet + facet normal -0.978678 -0.16662 0.120112 + outer loop + vertex -884.373 329.812 124.322 + vertex -885.198 329.028 116.516 + vertex -883.219 323.033 124.326 + endloop + endfacet + facet normal -0.978454 -0.169565 0.117794 + outer loop + vertex -883.219 323.033 124.326 + vertex -885.198 329.028 116.516 + vertex -884.013 322.195 116.52 + endloop + endfacet + facet normal -0.98748 -0.105623 0.117159 + outer loop + vertex -885.102 336.626 124.321 + vertex -885.951 335.899 116.514 + vertex -884.373 329.812 124.322 + endloop + endfacet + facet normal -0.987439 -0.108169 0.115166 + outer loop + vertex -884.373 329.812 124.322 + vertex -885.951 335.899 116.514 + vertex -885.198 329.028 116.516 + endloop + endfacet + facet normal -0.96026 0.252143 0.119689 + outer loop + vertex -857.212 461.143 124.545 + vertex -857.9 462.192 116.816 + vertex -858.132 458.353 123.039 + endloop + endfacet + facet normal -0.319094 -0.92775 0.193543 + outer loop + vertex -856.634 275.039 116.766 + vertex -856.525 273.654 110.304 + vertex -855.008 274.318 115.99 + endloop + endfacet + facet normal -0.316222 -0.928865 0.192907 + outer loop + vertex -855.008 274.318 115.99 + vertex -856.525 273.654 110.304 + vertex -855.162 272.802 108.438 + endloop + endfacet + facet normal -0.514009 -0.837035 0.187528 + outer loop + vertex -860.132 275.507 109.945 + vertex -858.432 274.611 110.607 + vertex -859.382 276.333 115.691 + endloop + endfacet + facet normal -0.417522 -0.889891 0.183766 + outer loop + vertex -856.525 273.654 110.304 + vertex -856.634 275.039 116.766 + vertex -858.432 274.611 110.607 + endloop + endfacet + facet normal -0.480313 -0.854084 0.199599 + outer loop + vertex -856.634 275.039 116.766 + vertex -859.382 276.333 115.691 + vertex -858.432 274.611 110.607 + endloop + endfacet + facet normal -0.608649 -0.773321 0.177539 + outer loop + vertex -862.631 279.023 116.268 + vertex -862.652 277.16 108.079 + vertex -859.382 276.333 115.691 + endloop + endfacet + facet normal -0.633181 -0.750171 0.190592 + outer loop + vertex -859.382 276.333 115.691 + vertex -862.652 277.16 108.079 + vertex -860.132 275.507 109.945 + endloop + endfacet + facet normal -0.703198 -0.692409 0.1615 + outer loop + vertex -866.016 282.52 116.521 + vertex -866.398 281.056 108.581 + vertex -862.631 279.023 116.268 + endloop + endfacet + facet normal -0.701235 -0.694764 0.159915 + outer loop + vertex -862.631 279.023 116.268 + vertex -866.398 281.056 108.581 + vertex -862.652 277.16 108.079 + endloop + endfacet + facet normal -0.775359 -0.612078 0.155496 + outer loop + vertex -869.31 286.7 116.553 + vertex -869.832 285.391 108.795 + vertex -866.016 282.52 116.521 + endloop + endfacet + facet normal -0.771233 -0.618352 0.151127 + outer loop + vertex -866.016 282.52 116.521 + vertex -869.832 285.391 108.795 + vertex -866.398 281.056 108.581 + endloop + endfacet + facet normal -0.829766 -0.537051 0.151868 + outer loop + vertex -872.433 291.515 116.514 + vertex -873.036 290.268 108.809 + vertex -869.31 286.7 116.553 + endloop + endfacet + facet normal -0.82644 -0.543403 0.147341 + outer loop + vertex -869.31 286.7 116.553 + vertex -873.036 290.268 108.809 + vertex -869.832 285.391 108.795 + endloop + endfacet + facet normal -0.868859 -0.472005 0.149318 + outer loop + vertex -875.345 296.872 116.502 + vertex -876.018 295.667 108.779 + vertex -872.433 291.515 116.514 + endloop + endfacet + facet normal -0.866446 -0.47771 0.145137 + outer loop + vertex -872.433 291.515 116.514 + vertex -876.018 295.667 108.779 + vertex -873.036 290.268 108.809 + endloop + endfacet + facet normal -0.899542 -0.411209 0.147414 + outer loop + vertex -878.009 302.705 116.518 + vertex -878.749 301.547 108.774 + vertex -875.345 296.872 116.502 + endloop + endfacet + facet normal -0.89765 -0.416793 0.143204 + outer loop + vertex -875.345 296.872 116.502 + vertex -878.749 301.547 108.774 + vertex -876.018 295.667 108.779 + endloop + endfacet + facet normal -0.924633 -0.351872 0.14574 + outer loop + vertex -880.376 308.93 116.53 + vertex -881.179 307.831 108.783 + vertex -878.009 302.705 116.518 + endloop + endfacet + facet normal -0.923217 -0.357237 0.141604 + outer loop + vertex -878.009 302.705 116.518 + vertex -881.179 307.831 108.783 + vertex -878.749 301.547 108.774 + endloop + endfacet + facet normal -0.945335 -0.292579 0.144012 + outer loop + vertex -882.397 315.459 116.526 + vertex -883.256 314.422 108.784 + vertex -880.376 308.93 116.53 + endloop + endfacet + facet normal -0.944356 -0.297603 0.140086 + outer loop + vertex -880.376 308.93 116.53 + vertex -883.256 314.422 108.784 + vertex -881.179 307.831 108.783 + endloop + endfacet + facet normal -0.962663 -0.230782 0.14149 + outer loop + vertex -884.013 322.195 116.52 + vertex -884.917 321.218 108.781 + vertex -882.397 315.459 116.526 + endloop + endfacet + facet normal -0.96212 -0.235028 0.138156 + outer loop + vertex -882.397 315.459 116.526 + vertex -884.917 321.218 108.781 + vertex -883.256 314.422 108.784 + endloop + endfacet + facet normal -0.975847 -0.169101 0.138305 + outer loop + vertex -885.198 329.028 116.516 + vertex -886.136 328.114 108.777 + vertex -884.013 322.195 116.52 + endloop + endfacet + facet normal -0.975625 -0.172492 0.135651 + outer loop + vertex -884.013 322.195 116.52 + vertex -886.136 328.114 108.777 + vertex -884.917 321.218 108.781 + endloop + endfacet + facet normal -0.985046 -0.107901 0.134321 + outer loop + vertex -885.951 335.899 116.514 + vertex -886.913 335.049 108.775 + vertex -885.198 329.028 116.516 + endloop + endfacet + facet normal -0.985033 -0.110273 0.132474 + outer loop + vertex -885.198 329.028 116.516 + vertex -886.913 335.049 108.775 + vertex -886.136 328.114 108.777 + endloop + endfacet + facet normal -0.297084 -0.931862 0.208267 + outer loop + vertex -856.525 273.654 110.304 + vertex -856.672 272.373 104.363 + vertex -855.162 272.802 108.438 + endloop + endfacet + facet normal -0.338085 -0.91449 0.222276 + outer loop + vertex -857.037 271.441 99.9762 + vertex -855.625 271.122 100.808 + vertex -856.672 272.373 104.363 + endloop + endfacet + facet normal -0.338961 -0.914249 0.221934 + outer loop + vertex -855.625 271.122 100.808 + vertex -855.162 272.802 108.438 + vertex -856.672 272.373 104.363 + endloop + endfacet + facet normal -0.511088 -0.83408 0.207605 + outer loop + vertex -860.374 274.742 105.861 + vertex -860.07 273.57 101.902 + vertex -858.287 273.39 105.568 + endloop + endfacet + facet normal -0.503783 -0.839447 0.20379 + outer loop + vertex -858.287 273.39 105.568 + vertex -860.07 273.57 101.902 + vertex -858.401 272.362 101.053 + endloop + endfacet + facet normal -0.513951 -0.837134 0.187245 + outer loop + vertex -860.132 275.507 109.945 + vertex -860.374 274.742 105.861 + vertex -858.432 274.611 110.607 + endloop + endfacet + facet normal -0.515253 -0.836209 0.187803 + outer loop + vertex -858.432 274.611 110.607 + vertex -860.374 274.742 105.861 + vertex -858.287 273.39 105.568 + endloop + endfacet + facet normal -0.413302 -0.887634 0.203193 + outer loop + vertex -858.432 274.611 110.607 + vertex -858.287 273.39 105.568 + vertex -856.525 273.654 110.304 + endloop + endfacet + facet normal -0.409628 -0.889621 0.201937 + outer loop + vertex -856.525 273.654 110.304 + vertex -858.287 273.39 105.568 + vertex -856.672 272.373 104.363 + endloop + endfacet + facet normal -0.402047 -0.890532 0.212865 + outer loop + vertex -858.287 273.39 105.568 + vertex -858.401 272.362 101.053 + vertex -856.672 272.373 104.363 + endloop + endfacet + facet normal -0.419176 -0.880401 0.221778 + outer loop + vertex -856.672 272.373 104.363 + vertex -858.401 272.362 101.053 + vertex -857.037 271.441 99.9762 + endloop + endfacet + facet normal -0.602555 -0.776675 0.183588 + outer loop + vertex -860.07 273.57 101.902 + vertex -860.374 274.742 105.861 + vertex -863.003 275.374 99.9072 + endloop + endfacet + facet normal -0.628834 -0.756663 0.178966 + outer loop + vertex -860.132 275.507 109.945 + vertex -862.652 277.16 108.079 + vertex -860.374 274.742 105.861 + endloop + endfacet + facet normal -0.619697 -0.760781 0.192844 + outer loop + vertex -862.652 277.16 108.079 + vertex -863.003 275.374 99.9072 + vertex -860.374 274.742 105.861 + endloop + endfacet + facet normal -0.696932 -0.693535 0.182466 + outer loop + vertex -866.398 281.056 108.581 + vertex -866.8 279.391 100.719 + vertex -862.652 277.16 108.079 + endloop + endfacet + facet normal -0.696074 -0.694609 0.181657 + outer loop + vertex -862.652 277.16 108.079 + vertex -866.8 279.391 100.719 + vertex -863.003 275.374 99.9072 + endloop + endfacet + facet normal -0.767588 -0.616632 0.174854 + outer loop + vertex -869.832 285.391 108.795 + vertex -870.37 283.879 101.1 + vertex -866.398 281.056 108.581 + endloop + endfacet + facet normal -0.763946 -0.622267 0.170795 + outer loop + vertex -866.398 281.056 108.581 + vertex -870.37 283.879 101.1 + vertex -866.8 279.391 100.719 + endloop + endfacet + facet normal -0.823267 -0.541388 0.170675 + outer loop + vertex -873.036 290.268 108.809 + vertex -873.677 288.841 101.19 + vertex -869.832 285.391 108.795 + endloop + endfacet + facet normal -0.819298 -0.549058 0.165188 + outer loop + vertex -869.832 285.391 108.795 + vertex -873.677 288.841 101.19 + vertex -870.37 283.879 101.1 + endloop + endfacet + facet normal -0.863423 -0.475916 0.167344 + outer loop + vertex -876.018 295.667 108.779 + vertex -876.742 294.302 101.161 + vertex -873.036 290.268 108.809 + endloop + endfacet + facet normal -0.860805 -0.482208 0.162756 + outer loop + vertex -873.036 290.268 108.809 + vertex -876.742 294.302 101.161 + vertex -873.677 288.841 101.19 + endloop + endfacet + facet normal -0.894511 -0.415315 0.165421 + outer loop + vertex -878.749 301.547 108.774 + vertex -879.552 300.235 101.135 + vertex -876.018 295.667 108.779 + endloop + endfacet + facet normal -0.892306 -0.421962 0.160429 + outer loop + vertex -876.018 295.667 108.779 + vertex -879.552 300.235 101.135 + vertex -876.742 294.302 101.161 + endloop + endfacet + facet normal -0.919971 -0.356015 0.164032 + outer loop + vertex -881.179 307.831 108.783 + vertex -882.058 306.579 101.136 + vertex -878.749 301.547 108.774 + endloop + endfacet + facet normal -0.91826 -0.362706 0.158882 + outer loop + vertex -878.749 301.547 108.774 + vertex -882.058 306.579 101.136 + vertex -879.552 300.235 101.135 + endloop + endfacet + facet normal -0.941284 -0.296639 0.161213 + outer loop + vertex -883.256 314.422 108.784 + vertex -884.193 313.242 101.143 + vertex -881.179 307.831 108.783 + endloop + endfacet + facet normal -0.940391 -0.301454 0.15745 + outer loop + vertex -881.179 307.831 108.783 + vertex -884.193 313.242 101.143 + vertex -882.058 306.579 101.136 + endloop + endfacet + facet normal -0.959111 -0.234282 0.1588 + outer loop + vertex -884.917 321.218 108.781 + vertex -885.909 320.105 101.142 + vertex -883.256 314.422 108.784 + endloop + endfacet + facet normal -0.958465 -0.239715 0.154535 + outer loop + vertex -883.256 314.422 108.784 + vertex -885.909 320.105 101.142 + vertex -884.193 313.242 101.143 + endloop + endfacet + facet normal -0.97283 -0.171988 0.15499 + outer loop + vertex -886.136 328.114 108.777 + vertex -887.168 327.069 101.139 + vertex -884.917 321.218 108.781 + endloop + endfacet + facet normal -0.97262 -0.175778 0.152026 + outer loop + vertex -884.917 321.218 108.781 + vertex -887.168 327.069 101.139 + vertex -885.909 320.105 101.142 + endloop + endfacet + facet normal -0.982503 -0.109985 0.150307 + outer loop + vertex -886.913 335.049 108.775 + vertex -887.972 334.073 101.138 + vertex -886.136 328.114 108.777 + endloop + endfacet + facet normal -0.982516 -0.11271 0.148184 + outer loop + vertex -886.136 328.114 108.777 + vertex -887.972 334.073 101.138 + vertex -887.168 327.069 101.139 + endloop + endfacet + facet normal -0.347568 -0.905985 0.241636 + outer loop + vertex -857.037 271.441 99.9762 + vertex -856.883 270.402 96.2996 + vertex -855.625 271.122 100.808 + endloop + endfacet + facet normal -0.34721 -0.902025 0.256506 + outer loop + vertex -857.1 269.396 92.4691 + vertex -855.551 268.989 93.1357 + vertex -856.883 270.402 96.2996 + endloop + endfacet + facet normal -0.367433 -0.896997 0.245743 + outer loop + vertex -855.551 268.989 93.1357 + vertex -855.625 271.122 100.808 + vertex -856.883 270.402 96.2996 + endloop + endfacet + facet normal -0.508091 -0.828447 0.235627 + outer loop + vertex -860.543 272.822 97.7349 + vertex -860.261 271.668 94.2873 + vertex -858.493 271.405 97.1721 + endloop + endfacet + facet normal -0.505492 -0.830539 0.233843 + outer loop + vertex -858.493 271.405 97.1721 + vertex -860.261 271.668 94.2873 + vertex -858.537 270.406 93.5293 + endloop + endfacet + facet normal -0.501918 -0.839609 0.207691 + outer loop + vertex -860.07 273.57 101.902 + vertex -860.543 272.822 97.7349 + vertex -858.401 272.362 101.053 + endloop + endfacet + facet normal -0.514156 -0.829804 0.216953 + outer loop + vertex -858.401 272.362 101.053 + vertex -860.543 272.822 97.7349 + vertex -858.493 271.405 97.1721 + endloop + endfacet + facet normal -0.415233 -0.88089 0.227188 + outer loop + vertex -858.401 272.362 101.053 + vertex -858.493 271.405 97.1721 + vertex -857.037 271.441 99.9762 + endloop + endfacet + facet normal -0.421476 -0.877087 0.230382 + outer loop + vertex -857.037 271.441 99.9762 + vertex -858.493 271.405 97.1721 + vertex -856.883 270.402 96.2996 + endloop + endfacet + facet normal -0.413213 -0.876932 0.245452 + outer loop + vertex -858.493 271.405 97.1721 + vertex -858.537 270.406 93.5293 + vertex -856.883 270.402 96.2996 + endloop + endfacet + facet normal -0.424741 -0.869435 0.252345 + outer loop + vertex -856.883 270.402 96.2996 + vertex -858.537 270.406 93.5293 + vertex -857.1 269.396 92.4691 + endloop + endfacet + facet normal -0.5982 -0.773393 0.209808 + outer loop + vertex -860.261 271.668 94.2873 + vertex -860.543 272.822 97.7349 + vertex -863.288 273.49 92.3698 + endloop + endfacet + facet normal -0.610674 -0.764463 0.206576 + outer loop + vertex -860.07 273.57 101.902 + vertex -863.003 275.374 99.9072 + vertex -860.543 272.822 97.7349 + endloop + endfacet + facet normal -0.60561 -0.766312 0.21448 + outer loop + vertex -863.003 275.374 99.9072 + vertex -863.288 273.49 92.3698 + vertex -860.543 272.822 97.7349 + endloop + endfacet + facet normal -0.691183 -0.694006 0.201548 + outer loop + vertex -866.8 279.391 100.719 + vertex -867.243 277.626 93.1204 + vertex -863.003 275.374 99.9072 + endloop + endfacet + facet normal -0.689767 -0.695845 0.200054 + outer loop + vertex -863.003 275.374 99.9072 + vertex -867.243 277.626 93.1204 + vertex -863.288 273.49 92.3698 + endloop + endfacet + facet normal -0.759736 -0.62083 0.193315 + outer loop + vertex -870.37 283.879 101.1 + vertex -870.929 282.215 93.5608 + vertex -866.8 279.391 100.719 + endloop + endfacet + facet normal -0.756585 -0.625826 0.189527 + outer loop + vertex -866.8 279.391 100.719 + vertex -870.929 282.215 93.5608 + vertex -867.243 277.626 93.1204 + endloop + endfacet + facet normal -0.815853 -0.547157 0.187091 + outer loop + vertex -873.677 288.841 101.19 + vertex -874.345 287.275 93.6974 + vertex -870.37 283.879 101.1 + endloop + endfacet + facet normal -0.812584 -0.553571 0.182393 + outer loop + vertex -870.37 283.879 101.1 + vertex -874.345 287.275 93.6974 + vertex -870.929 282.215 93.5608 + endloop + endfacet + facet normal -0.857659 -0.480334 0.183575 + outer loop + vertex -876.742 294.302 101.161 + vertex -877.508 292.811 93.6771 + vertex -873.677 288.841 101.19 + endloop + endfacet + facet normal -0.854628 -0.487734 0.178119 + outer loop + vertex -873.677 288.841 101.19 + vertex -877.508 292.811 93.6771 + vertex -874.345 287.275 93.6974 + endloop + endfacet + facet normal -0.889044 -0.420325 0.181459 + outer loop + vertex -879.552 300.235 101.135 + vertex -880.409 298.81 93.6379 + vertex -876.742 294.302 101.161 + endloop + endfacet + facet normal -0.88671 -0.427507 0.176018 + outer loop + vertex -876.742 294.302 101.161 + vertex -880.409 298.81 93.6379 + vertex -877.508 292.811 93.6771 + endloop + endfacet + facet normal -0.91504 -0.361436 0.179068 + outer loop + vertex -882.058 306.579 101.136 + vertex -882.994 305.231 93.6334 + vertex -879.552 300.235 101.135 + endloop + endfacet + facet normal -0.913505 -0.367624 0.174243 + outer loop + vertex -879.552 300.235 101.135 + vertex -882.994 305.231 93.6334 + vertex -880.409 298.81 93.6379 + endloop + endfacet + facet normal -0.937259 -0.300472 0.176812 + outer loop + vertex -884.193 313.242 101.143 + vertex -885.199 311.968 93.6444 + vertex -882.058 306.579 101.136 + endloop + endfacet + facet normal -0.936159 -0.306706 0.171867 + outer loop + vertex -882.058 306.579 101.136 + vertex -885.199 311.968 93.6444 + vertex -882.994 305.231 93.6334 + endloop + endfacet + facet normal -0.955354 -0.238932 0.173809 + outer loop + vertex -885.909 320.105 101.142 + vertex -886.972 318.902 93.6476 + vertex -884.193 313.242 101.143 + endloop + endfacet + facet normal -0.954773 -0.244223 0.169599 + outer loop + vertex -884.193 313.242 101.143 + vertex -886.972 318.902 93.6476 + vertex -885.199 311.968 93.6444 + endloop + endfacet + facet normal -0.969798 -0.175261 0.169632 + outer loop + vertex -887.168 327.069 101.139 + vertex -888.275 325.938 93.6457 + vertex -885.909 320.105 101.142 + endloop + endfacet + facet normal -0.969606 -0.179479 0.166289 + outer loop + vertex -885.909 320.105 101.142 + vertex -888.275 325.938 93.6457 + vertex -886.972 318.902 93.6476 + endloop + endfacet + facet normal -0.979913 -0.112409 0.164727 + outer loop + vertex -887.972 334.073 101.138 + vertex -889.11 333.016 93.6437 + vertex -887.168 327.069 101.139 + endloop + endfacet + facet normal -0.979963 -0.115683 0.162142 + outer loop + vertex -887.168 327.069 101.139 + vertex -889.11 333.016 93.6437 + vertex -888.275 325.938 93.6457 + endloop + endfacet + facet normal -0.353994 -0.893051 0.277756 + outer loop + vertex -857.1 269.396 92.4691 + vertex -856.866 268.134 88.7087 + vertex -855.551 268.989 93.1357 + endloop + endfacet + facet normal -0.355582 -0.888409 0.290328 + outer loop + vertex -857.073 266.943 84.8106 + vertex -855.507 266.316 84.8106 + vertex -856.866 268.134 88.7087 + endloop + endfacet + facet normal -0.373722 -0.883695 0.281808 + outer loop + vertex -855.507 266.316 84.8106 + vertex -855.551 268.989 93.1357 + vertex -856.866 268.134 88.7087 + endloop + endfacet + facet normal -0.511233 -0.818286 0.262771 + outer loop + vertex -860.701 270.847 90.4478 + vertex -860.348 269.527 87.0264 + vertex -858.554 269.315 89.8553 + endloop + endfacet + facet normal -0.509007 -0.820169 0.261218 + outer loop + vertex -858.554 269.315 89.8553 + vertex -860.348 269.527 87.0264 + vertex -858.551 268.12 86.1077 + endloop + endfacet + facet normal -0.50472 -0.830521 0.235567 + outer loop + vertex -860.261 271.668 94.2873 + vertex -860.701 270.847 90.4478 + vertex -858.537 270.406 93.5293 + endloop + endfacet + facet normal -0.517077 -0.819898 0.245762 + outer loop + vertex -858.537 270.406 93.5293 + vertex -860.701 270.847 90.4478 + vertex -858.554 269.315 89.8553 + endloop + endfacet + facet normal -0.419244 -0.869804 0.260146 + outer loop + vertex -858.537 270.406 93.5293 + vertex -858.554 269.315 89.8553 + vertex -857.1 269.396 92.4691 + endloop + endfacet + facet normal -0.426268 -0.865244 0.263909 + outer loop + vertex -857.1 269.396 92.4691 + vertex -858.554 269.315 89.8553 + vertex -856.866 268.134 88.7087 + endloop + endfacet + facet normal -0.418375 -0.865418 0.275707 + outer loop + vertex -858.554 269.315 89.8553 + vertex -858.551 268.12 86.1077 + vertex -856.866 268.134 88.7087 + endloop + endfacet + facet normal -0.431953 -0.855863 0.284454 + outer loop + vertex -856.866 268.134 88.7087 + vertex -858.551 268.12 86.1077 + vertex -857.073 266.943 84.8106 + endloop + endfacet + facet normal -0.59993 -0.765315 0.233189 + outer loop + vertex -860.348 269.527 87.0264 + vertex -860.701 270.847 90.4478 + vertex -863.527 271.425 85.0756 + endloop + endfacet + facet normal -0.60523 -0.761402 0.232299 + outer loop + vertex -860.261 271.668 94.2873 + vertex -863.288 273.49 92.3698 + vertex -860.701 270.847 90.4478 + endloop + endfacet + facet normal -0.603423 -0.761885 0.235396 + outer loop + vertex -863.288 273.49 92.3698 + vertex -863.527 271.425 85.0756 + vertex -860.701 270.847 90.4478 + endloop + endfacet + facet normal -0.684785 -0.694716 0.220089 + outer loop + vertex -867.243 277.626 93.1204 + vertex -867.695 275.748 85.7864 + vertex -863.288 273.49 92.3698 + endloop + endfacet + facet normal -0.684078 -0.695665 0.219291 + outer loop + vertex -863.288 273.49 92.3698 + vertex -867.695 275.748 85.7864 + vertex -863.527 271.425 85.0756 + endloop + endfacet + facet normal -0.752539 -0.624458 0.209136 + outer loop + vertex -870.929 282.215 93.5608 + vertex -871.531 280.477 86.2047 + vertex -867.243 277.626 93.1204 + endloop + endfacet + facet normal -0.750795 -0.627301 0.206883 + outer loop + vertex -867.243 277.626 93.1204 + vertex -871.531 280.477 86.2047 + vertex -867.695 275.748 85.7864 + endloop + endfacet + facet normal -0.808987 -0.551696 0.202905 + outer loop + vertex -874.345 287.275 93.6974 + vertex -875.066 285.63 86.3495 + vertex -870.929 282.215 93.5608 + endloop + endfacet + facet normal -0.80568 -0.558327 0.197867 + outer loop + vertex -870.929 282.215 93.5608 + vertex -875.066 285.63 86.3495 + vertex -871.531 280.477 86.2047 + endloop + endfacet + facet normal -0.851179 -0.485686 0.199005 + outer loop + vertex -877.508 292.811 93.6771 + vertex -878.336 291.251 86.3299 + vertex -874.345 287.275 93.6974 + endloop + endfacet + facet normal -0.848313 -0.492836 0.193593 + outer loop + vertex -874.345 287.275 93.6974 + vertex -878.336 291.251 86.3299 + vertex -875.066 285.63 86.3495 + endloop + endfacet + facet normal -0.883514 -0.425837 0.195106 + outer loop + vertex -880.409 298.81 93.6379 + vertex -881.331 297.356 86.2868 + vertex -877.508 292.811 93.6771 + endloop + endfacet + facet normal -0.88181 -0.43124 0.190901 + outer loop + vertex -877.508 292.811 93.6771 + vertex -881.331 297.356 86.2868 + vertex -878.336 291.251 86.3299 + endloop + endfacet + facet normal -0.910268 -0.366308 0.192954 + outer loop + vertex -882.994 305.231 93.6334 + vertex -884.003 303.864 86.2788 + vertex -880.409 298.81 93.6379 + endloop + endfacet + facet normal -0.90873 -0.372765 0.187769 + outer loop + vertex -880.409 298.81 93.6379 + vertex -884.003 303.864 86.2788 + vertex -881.331 297.356 86.2868 + endloop + endfacet + facet normal -0.932974 -0.305694 0.190028 + outer loop + vertex -885.199 311.968 93.6444 + vertex -886.277 310.691 86.2979 + vertex -882.994 305.231 93.6334 + endloop + endfacet + facet normal -0.932092 -0.311017 0.185671 + outer loop + vertex -882.994 305.231 93.6334 + vertex -886.277 310.691 86.2979 + vertex -884.003 303.864 86.2788 + endloop + endfacet + facet normal -0.951834 -0.243479 0.186362 + outer loop + vertex -886.972 318.902 93.6476 + vertex -888.103 317.707 86.3114 + vertex -885.199 311.968 93.6444 + endloop + endfacet + facet normal -0.951393 -0.24794 0.182695 + outer loop + vertex -885.199 311.968 93.6444 + vertex -888.103 317.707 86.3114 + vertex -886.277 310.691 86.2979 + endloop + endfacet + facet normal -0.96687 -0.178969 0.182026 + outer loop + vertex -888.275 325.938 93.6457 + vertex -889.448 324.819 86.3128 + vertex -886.972 318.902 93.6476 + endloop + endfacet + facet normal -0.966734 -0.182915 0.178797 + outer loop + vertex -886.972 318.902 93.6476 + vertex -889.448 324.819 86.3128 + vertex -888.103 317.707 86.3114 + endloop + endfacet + facet normal -0.977525 -0.115391 0.176438 + outer loop + vertex -889.11 333.016 93.6437 + vertex -890.311 331.974 86.3104 + vertex -888.275 325.938 93.6457 + endloop + endfacet + facet normal -0.977592 -0.117868 0.174418 + outer loop + vertex -888.275 325.938 93.6457 + vertex -890.311 331.974 86.3104 + vertex -889.448 324.819 86.3128 + endloop + endfacet + facet normal -0.357233 -0.875889 0.324349 + outer loop + vertex -857.028 264.411 77.8728 + vertex -855.758 264.298 78.9669 + vertex -856.861 265.63 81.3486 + endloop + endfacet + facet normal -0.352947 -0.881829 0.312738 + outer loop + vertex -857.073 266.943 84.8106 + vertex -856.861 265.63 81.3486 + vertex -855.507 266.316 84.8106 + endloop + endfacet + facet normal -0.272759 -0.905727 0.32444 + outer loop + vertex -854.635 263.993 79.0583 + vertex -855.507 266.316 84.8106 + vertex -855.758 264.298 78.9669 + endloop + endfacet + facet normal -0.36921 -0.873451 0.317439 + outer loop + vertex -856.861 265.63 81.3486 + vertex -855.758 264.298 78.9669 + vertex -855.507 266.316 84.8106 + endloop + endfacet + facet normal -0.518894 -0.804243 0.289729 + outer loop + vertex -860.778 268.536 83.0649 + vertex -860.383 267.014 79.5474 + vertex -858.536 266.837 82.3644 + endloop + endfacet + facet normal -0.518011 -0.805037 0.289101 + outer loop + vertex -858.536 266.837 82.3644 + vertex -860.383 267.014 79.5474 + vertex -858.523 265.509 78.6874 + endloop + endfacet + facet normal -0.509359 -0.820169 0.260529 + outer loop + vertex -860.348 269.527 87.0264 + vertex -860.778 268.536 83.0649 + vertex -858.551 268.12 86.1077 + endloop + endfacet + facet normal -0.525007 -0.805804 0.273948 + outer loop + vertex -858.551 268.12 86.1077 + vertex -860.778 268.536 83.0649 + vertex -858.536 266.837 82.3644 + endloop + endfacet + facet normal -0.426035 -0.856397 0.291682 + outer loop + vertex -858.551 268.12 86.1077 + vertex -858.536 266.837 82.3644 + vertex -857.073 266.943 84.8106 + endloop + endfacet + facet normal -0.433789 -0.850977 0.296084 + outer loop + vertex -857.073 266.943 84.8106 + vertex -858.536 266.837 82.3644 + vertex -856.861 265.63 81.3486 + endloop + endfacet + facet normal -0.427601 -0.850641 0.305887 + outer loop + vertex -858.536 266.837 82.3644 + vertex -858.523 265.509 78.6874 + vertex -856.861 265.63 81.3486 + endloop + endfacet + facet normal -0.443822 -0.838747 0.315477 + outer loop + vertex -856.861 265.63 81.3486 + vertex -858.523 265.509 78.6874 + vertex -857.028 264.411 77.8728 + endloop + endfacet + facet normal -0.605644 -0.752837 0.257745 + outer loop + vertex -860.383 267.014 79.5474 + vertex -860.778 268.536 83.0649 + vertex -863.743 269.081 77.6908 + endloop + endfacet + facet normal -0.606005 -0.753681 0.254407 + outer loop + vertex -860.348 269.527 87.0264 + vertex -863.527 271.425 85.0756 + vertex -860.778 268.536 83.0649 + endloop + endfacet + facet normal -0.604484 -0.754028 0.256985 + outer loop + vertex -863.527 271.425 85.0756 + vertex -863.743 269.081 77.6908 + vertex -860.778 268.536 83.0649 + endloop + endfacet + facet normal -0.679679 -0.694281 0.236666 + outer loop + vertex -867.695 275.748 85.7864 + vertex -868.167 273.728 78.5046 + vertex -863.527 271.425 85.0756 + endloop + endfacet + facet normal -0.681889 -0.691201 0.239306 + outer loop + vertex -863.527 271.425 85.0756 + vertex -868.167 273.728 78.5046 + vertex -863.743 269.081 77.6908 + endloop + endfacet + facet normal -0.746658 -0.625637 0.226011 + outer loop + vertex -871.531 280.477 86.2047 + vertex -872.203 278.66 78.9566 + vertex -867.695 275.748 85.7864 + endloop + endfacet + facet normal -0.744386 -0.629453 0.222884 + outer loop + vertex -867.695 275.748 85.7864 + vertex -872.203 278.66 78.9566 + vertex -868.167 273.728 78.5046 + endloop + endfacet + facet normal -0.801943 -0.556321 0.217704 + outer loop + vertex -875.066 285.63 86.3495 + vertex -875.875 283.963 79.1088 + vertex -871.531 280.477 86.2047 + endloop + endfacet + facet normal -0.800018 -0.560294 0.214573 + outer loop + vertex -871.531 280.477 86.2047 + vertex -875.875 283.963 79.1088 + vertex -872.203 278.66 78.9566 + endloop + endfacet + facet normal -0.844897 -0.490781 0.212799 + outer loop + vertex -878.336 291.251 86.3299 + vertex -879.258 289.699 79.0931 + vertex -875.066 285.63 86.3495 + endloop + endfacet + facet normal -0.84274 -0.496326 0.208444 + outer loop + vertex -875.066 285.63 86.3495 + vertex -879.258 289.699 79.0931 + vertex -875.875 283.963 79.1088 + endloop + endfacet + facet normal -0.878552 -0.429514 0.20896 + outer loop + vertex -881.331 297.356 86.2868 + vertex -882.349 295.918 79.0522 + vertex -878.336 291.251 86.3299 + endloop + endfacet + facet normal -0.877012 -0.434615 0.204841 + outer loop + vertex -878.336 291.251 86.3299 + vertex -882.349 295.918 79.0522 + vertex -879.258 289.699 79.0931 + endloop + endfacet + facet normal -0.905299 -0.371334 0.206263 + outer loop + vertex -884.003 303.864 86.2788 + vertex -885.108 302.539 79.0433 + vertex -881.331 297.356 86.2868 + endloop + endfacet + facet normal -0.904149 -0.37644 0.202009 + outer loop + vertex -881.331 297.356 86.2868 + vertex -885.108 302.539 79.0433 + vertex -882.349 295.918 79.0522 + endloop + endfacet + facet normal -0.928869 -0.309991 0.202749 + outer loop + vertex -886.277 310.691 86.2979 + vertex -887.447 309.472 79.0713 + vertex -884.003 303.864 86.2788 + endloop + endfacet + facet normal -0.92825 -0.314067 0.199282 + outer loop + vertex -884.003 303.864 86.2788 + vertex -887.447 309.472 79.0713 + vertex -885.108 302.539 79.0433 + endloop + endfacet + facet normal -0.948341 -0.247177 0.198879 + outer loop + vertex -888.103 317.707 86.3114 + vertex -889.323 316.584 79.0976 + vertex -886.277 310.691 86.2979 + endloop + endfacet + facet normal -0.948041 -0.250718 0.195855 + outer loop + vertex -886.277 310.691 86.2979 + vertex -889.323 316.584 79.0976 + vertex -887.447 309.472 79.0713 + endloop + endfacet + facet normal -0.964068 -0.182413 0.19313 + outer loop + vertex -889.448 324.819 86.3128 + vertex -890.694 323.783 79.112 + vertex -888.103 317.707 86.3114 + endloop + endfacet + facet normal -0.964034 -0.184084 0.191708 + outer loop + vertex -888.103 317.707 86.3114 + vertex -890.694 323.783 79.112 + vertex -889.323 316.584 79.0976 + endloop + endfacet + facet normal -0.975238 -0.11758 0.187313 + outer loop + vertex -890.311 331.974 86.3104 + vertex -891.578 331.019 79.1135 + vertex -889.448 324.819 86.3128 + endloop + endfacet + facet normal -0.975303 -0.119158 0.185972 + outer loop + vertex -889.448 324.819 86.3128 + vertex -891.578 331.019 79.1135 + vertex -890.694 323.783 79.112 + endloop + endfacet + facet normal -0.340866 -0.870157 0.35586 + outer loop + vertex -856.62 263.149 75.0561 + vertex -856.319 261.589 71.5314 + vertex -855.19 262.626 75.1469 + endloop + endfacet + facet normal -0.351158 -0.865305 0.357682 + outer loop + vertex -855.19 262.626 75.1469 + vertex -856.319 261.589 71.5314 + vertex -854.814 260.876 71.2831 + endloop + endfacet + facet normal -0.366403 -0.867737 0.335831 + outer loop + vertex -857.028 264.411 77.8728 + vertex -856.62 263.149 75.0561 + vertex -855.758 264.298 78.9669 + endloop + endfacet + facet normal -0.342435 -0.878301 0.333655 + outer loop + vertex -855.758 264.298 78.9669 + vertex -856.62 263.149 75.0561 + vertex -855.19 262.626 75.1469 + endloop + endfacet + facet normal -0.272238 -0.895657 0.351689 + outer loop + vertex -855.758 264.298 78.9669 + vertex -855.19 262.626 75.1469 + vertex -854.635 263.993 79.0583 + endloop + endfacet + facet normal -0.274703 -0.894874 0.351766 + outer loop + vertex -854.635 263.993 79.0583 + vertex -855.19 262.626 75.1469 + vertex -854.178 262.067 74.5164 + endloop + endfacet + facet normal -0.255511 -0.889811 0.378087 + outer loop + vertex -855.19 262.626 75.1469 + vertex -854.814 260.876 71.2831 + vertex -854.178 262.067 74.5164 + endloop + endfacet + facet normal -0.294723 -0.876404 0.38086 + outer loop + vertex -854.178 262.067 74.5164 + vertex -854.814 260.876 71.2831 + vertex -853.763 260.104 70.319 + endloop + endfacet + facet normal -0.528761 -0.789436 0.311773 + outer loop + vertex -860.814 265.899 75.6097 + vertex -860.356 264.239 72.184 + vertex -858.447 264.134 75.1562 + endloop + endfacet + facet normal -0.523597 -0.794233 0.308287 + outer loop + vertex -858.447 264.134 75.1562 + vertex -860.356 264.239 72.184 + vertex -858.292 262.681 71.6765 + endloop + endfacet + facet normal -0.520019 -0.805194 0.285033 + outer loop + vertex -860.383 267.014 79.5474 + vertex -860.814 265.899 75.6097 + vertex -858.523 265.509 78.6874 + endloop + endfacet + facet normal -0.533545 -0.791996 0.29677 + outer loop + vertex -858.523 265.509 78.6874 + vertex -860.814 265.899 75.6097 + vertex -858.447 264.134 75.1562 + endloop + endfacet + facet normal -0.442983 -0.838656 0.316894 + outer loop + vertex -858.523 265.509 78.6874 + vertex -858.447 264.134 75.1562 + vertex -857.028 264.411 77.8728 + endloop + endfacet + facet normal -0.437262 -0.842622 0.31431 + outer loop + vertex -857.028 264.411 77.8728 + vertex -858.447 264.134 75.1562 + vertex -856.62 263.149 75.0561 + endloop + endfacet + facet normal -0.43393 -0.838098 0.330599 + outer loop + vertex -858.447 264.134 75.1562 + vertex -858.292 262.681 71.6765 + vertex -856.62 263.149 75.0561 + endloop + endfacet + facet normal -0.437911 -0.835393 0.332194 + outer loop + vertex -856.62 263.149 75.0561 + vertex -858.292 262.681 71.6765 + vertex -856.319 261.589 71.5314 + endloop + endfacet + facet normal -0.607653 -0.743579 0.279012 + outer loop + vertex -860.356 264.239 72.184 + vertex -860.814 265.899 75.6097 + vertex -863.901 266.456 70.3715 + endloop + endfacet + facet normal -0.609931 -0.742436 0.277081 + outer loop + vertex -860.383 267.014 79.5474 + vertex -863.743 269.081 77.6908 + vertex -860.814 265.899 75.6097 + endloop + endfacet + facet normal -0.608455 -0.74271 0.279577 + outer loop + vertex -863.743 269.081 77.6908 + vertex -863.901 266.456 70.3715 + vertex -860.814 265.899 75.6097 + endloop + endfacet + facet normal -0.677036 -0.68966 0.256888 + outer loop + vertex -868.167 273.728 78.5046 + vertex -868.612 271.467 71.2613 + vertex -863.743 269.081 77.6908 + endloop + endfacet + facet normal -0.679876 -0.685463 0.260595 + outer loop + vertex -863.743 269.081 77.6908 + vertex -868.612 271.467 71.2613 + vertex -863.901 266.456 70.3715 + endloop + endfacet + facet normal -0.739739 -0.627492 0.242981 + outer loop + vertex -872.203 278.66 78.9566 + vertex -872.889 276.691 71.7809 + vertex -868.167 273.728 78.5046 + endloop + endfacet + facet normal -0.738894 -0.628966 0.241738 + outer loop + vertex -868.167 273.728 78.5046 + vertex -872.889 276.691 71.7809 + vertex -868.612 271.467 71.2613 + endloop + endfacet + facet normal -0.795722 -0.557925 0.235684 + outer loop + vertex -875.875 283.963 79.1088 + vertex -876.743 282.185 71.9697 + vertex -872.203 278.66 78.9566 + endloop + endfacet + facet normal -0.792813 -0.564128 0.230665 + outer loop + vertex -872.203 278.66 78.9566 + vertex -876.743 282.185 71.9697 + vertex -872.889 276.691 71.7809 + endloop + endfacet + facet normal -0.838759 -0.493922 0.229181 + outer loop + vertex -879.258 289.699 79.0931 + vertex -880.253 288.085 71.974 + vertex -875.875 283.963 79.1088 + endloop + endfacet + facet normal -0.837208 -0.498083 0.225825 + outer loop + vertex -875.875 283.963 79.1088 + vertex -880.253 288.085 71.974 + vertex -876.743 282.185 71.9697 + endloop + endfacet + facet normal -0.873006 -0.432488 0.225421 + outer loop + vertex -882.349 295.918 79.0522 + vertex -883.451 294.438 71.9445 + vertex -879.258 289.699 79.0931 + endloop + endfacet + facet normal -0.871493 -0.437774 0.221029 + outer loop + vertex -879.258 289.699 79.0931 + vertex -883.451 294.438 71.9445 + vertex -880.253 288.085 71.974 + endloop + endfacet + facet normal -0.900238 -0.374784 0.221605 + outer loop + vertex -885.108 302.539 79.0433 + vertex -886.292 301.188 71.948 + vertex -882.349 295.918 79.0522 + endloop + endfacet + facet normal -0.899435 -0.378628 0.218307 + outer loop + vertex -882.349 295.918 79.0522 + vertex -886.292 301.188 71.948 + vertex -883.451 294.438 71.9445 + endloop + endfacet + facet normal -0.924457 -0.312862 0.217938 + outer loop + vertex -887.447 309.472 79.0713 + vertex -888.7 308.232 71.9783 + vertex -885.108 302.539 79.0433 + endloop + endfacet + facet normal -0.923924 -0.31678 0.214509 + outer loop + vertex -885.108 302.539 79.0433 + vertex -888.7 308.232 71.9783 + vertex -886.292 301.188 71.948 + endloop + endfacet + facet normal -0.944514 -0.249852 0.213233 + outer loop + vertex -889.323 316.584 79.0976 + vertex -890.623 315.45 72.0105 + vertex -887.447 309.472 79.0713 + endloop + endfacet + facet normal -0.944331 -0.252508 0.210901 + outer loop + vertex -887.447 309.472 79.0713 + vertex -890.623 315.45 72.0105 + vertex -888.7 308.232 71.9783 + endloop + endfacet + facet normal -0.961018 -0.18354 0.20678 + outer loop + vertex -890.694 323.783 79.112 + vertex -892.018 322.745 72.0409 + vertex -889.323 316.584 79.0976 + endloop + endfacet + facet normal -0.961014 -0.184629 0.205827 + outer loop + vertex -889.323 316.584 79.0976 + vertex -892.018 322.745 72.0409 + vertex -890.623 315.45 72.0105 + endloop + endfacet + facet normal -0.972476 -0.118816 0.200431 + outer loop + vertex -891.578 331.019 79.1135 + vertex -892.918 330.071 72.0525 + vertex -890.694 323.783 79.112 + endloop + endfacet + facet normal -0.972532 -0.119794 0.199577 + outer loop + vertex -890.694 323.783 79.112 + vertex -892.918 330.071 72.0525 + vertex -892.018 322.745 72.0409 + endloop + endfacet + facet normal -0.35923 -0.844418 0.39738 + outer loop + vertex -856.073 259.925 67.9626 + vertex -855.811 258.187 64.5058 + vertex -854.481 259.079 67.6018 + endloop + endfacet + facet normal -0.379415 -0.832967 0.402754 + outer loop + vertex -854.481 259.079 67.6018 + vertex -855.811 258.187 64.5058 + vertex -854.136 257.283 64.2129 + endloop + endfacet + facet normal -0.345239 -0.859508 0.376904 + outer loop + vertex -856.319 261.589 71.5314 + vertex -856.073 259.925 67.9626 + vertex -854.814 260.876 71.2831 + endloop + endfacet + facet normal -0.365316 -0.849104 0.381532 + outer loop + vertex -854.814 260.876 71.2831 + vertex -856.073 259.925 67.9626 + vertex -854.481 259.079 67.6018 + endloop + endfacet + facet normal -0.273519 -0.873861 0.401937 + outer loop + vertex -854.814 260.876 71.2831 + vertex -854.481 259.079 67.6018 + vertex -853.763 260.104 70.319 + endloop + endfacet + facet normal -0.311792 -0.858859 0.406384 + outer loop + vertex -853.763 260.104 70.319 + vertex -854.481 259.079 67.6018 + vertex -853.357 258.151 66.5029 + endloop + endfacet + facet normal -0.292692 -0.856922 0.424284 + outer loop + vertex -854.481 259.079 67.6018 + vertex -854.136 257.283 64.2129 + vertex -853.357 258.151 66.5029 + endloop + endfacet + facet normal -0.324699 -0.84256 0.429726 + outer loop + vertex -853.357 258.151 66.5029 + vertex -854.136 257.283 64.2129 + vertex -853.077 256.56 63.5958 + endloop + endfacet + facet normal -0.531147 -0.775187 0.342005 + outer loop + vertex -860.753 263.019 68.3921 + vertex -860.225 261.212 65.1155 + vertex -858.135 261.116 68.143 + endloop + endfacet + facet normal -0.530706 -0.77563 0.341687 + outer loop + vertex -858.135 261.116 68.143 + vertex -860.225 261.212 65.1155 + vertex -857.984 259.485 64.677 + endloop + endfacet + facet normal -0.522912 -0.793944 0.310185 + outer loop + vertex -860.356 264.239 72.184 + vertex -860.753 263.019 68.3921 + vertex -858.292 262.681 71.6765 + endloop + endfacet + facet normal -0.536594 -0.780043 0.321869 + outer loop + vertex -858.292 262.681 71.6765 + vertex -860.753 263.019 68.3921 + vertex -858.135 261.116 68.143 + endloop + endfacet + facet normal -0.434046 -0.830619 0.348821 + outer loop + vertex -858.292 262.681 71.6765 + vertex -858.135 261.116 68.143 + vertex -856.319 261.589 71.5314 + endloop + endfacet + facet normal -0.444155 -0.823381 0.353228 + outer loop + vertex -856.319 261.589 71.5314 + vertex -858.135 261.116 68.143 + vertex -856.073 259.925 67.9626 + endloop + endfacet + facet normal -0.440773 -0.819494 0.366262 + outer loop + vertex -858.135 261.116 68.143 + vertex -857.984 259.485 64.677 + vertex -856.073 259.925 67.9626 + endloop + endfacet + facet normal -0.453974 -0.809376 0.372584 + outer loop + vertex -856.073 259.925 67.9626 + vertex -857.984 259.485 64.677 + vertex -855.811 258.187 64.5058 + endloop + endfacet + facet normal -0.607014 -0.733166 0.306596 + outer loop + vertex -860.225 261.212 65.1155 + vertex -860.753 263.019 68.3921 + vertex -863.885 263.545 63.4473 + endloop + endfacet + facet normal -0.611278 -0.732486 0.299673 + outer loop + vertex -860.356 264.239 72.184 + vertex -863.901 266.456 70.3715 + vertex -860.753 263.019 68.3921 + endloop + endfacet + facet normal -0.607254 -0.732891 0.306778 + outer loop + vertex -863.901 266.456 70.3715 + vertex -863.885 263.545 63.4473 + vertex -860.753 263.019 68.3921 + endloop + endfacet + facet normal -0.673908 -0.68342 0.280686 + outer loop + vertex -868.612 271.467 71.2613 + vertex -868.853 268.864 64.3455 + vertex -863.901 266.456 70.3715 + endloop + endfacet + facet normal -0.676315 -0.67958 0.284199 + outer loop + vertex -863.901 266.456 70.3715 + vertex -868.853 268.864 64.3455 + vertex -863.885 263.545 63.4473 + endloop + endfacet + facet normal -0.733254 -0.626572 0.264096 + outer loop + vertex -872.889 276.691 71.7809 + vertex -873.398 274.387 64.9 + vertex -868.612 271.467 71.2613 + endloop + endfacet + facet normal -0.732037 -0.628806 0.262155 + outer loop + vertex -868.612 271.467 71.2613 + vertex -873.398 274.387 64.9 + vertex -868.853 268.864 64.3455 + endloop + endfacet + facet normal -0.787924 -0.561461 0.252858 + outer loop + vertex -876.743 282.185 71.9697 + vertex -877.466 280.12 65.1326 + vertex -872.889 276.691 71.7809 + endloop + endfacet + facet normal -0.785308 -0.567227 0.248082 + outer loop + vertex -872.889 276.691 71.7809 + vertex -877.466 280.12 65.1326 + vertex -873.398 274.387 64.9 + endloop + endfacet + facet normal -0.833149 -0.495683 0.245278 + outer loop + vertex -880.253 288.085 71.974 + vertex -881.152 286.226 65.1626 + vertex -876.743 282.185 71.9697 + endloop + endfacet + facet normal -0.830676 -0.502569 0.239588 + outer loop + vertex -876.743 282.185 71.9697 + vertex -881.152 286.226 65.1626 + vertex -877.466 280.12 65.1326 + endloop + endfacet + facet normal -0.867391 -0.435618 0.240562 + outer loop + vertex -883.451 294.438 71.9445 + vertex -884.492 292.766 65.1623 + vertex -880.253 288.085 71.974 + endloop + endfacet + facet normal -0.865612 -0.442167 0.234955 + outer loop + vertex -880.253 288.085 71.974 + vertex -884.492 292.766 65.1623 + vertex -881.152 286.226 65.1626 + endloop + endfacet + facet normal -0.895204 -0.376858 0.237883 + outer loop + vertex -886.292 301.188 71.948 + vertex -887.426 299.629 65.2101 + vertex -883.451 294.438 71.9445 + endloop + endfacet + facet normal -0.893885 -0.383697 0.231833 + outer loop + vertex -883.451 294.438 71.9445 + vertex -887.426 299.629 65.2101 + vertex -884.492 292.766 65.1623 + endloop + endfacet + facet normal -0.919539 -0.315367 0.234504 + outer loop + vertex -888.7 308.232 71.9783 + vertex -889.9 306.731 65.2523 + vertex -886.292 301.188 71.948 + endloop + endfacet + facet normal -0.918797 -0.321484 0.22904 + outer loop + vertex -886.292 301.188 71.948 + vertex -889.9 306.731 65.2523 + vertex -887.426 299.629 65.2101 + endloop + endfacet + facet normal -0.940314 -0.25152 0.229231 + outer loop + vertex -890.623 315.45 72.0105 + vertex -891.888 314.032 65.2632 + vertex -888.7 308.232 71.9783 + endloop + endfacet + facet normal -0.940051 -0.256295 0.224983 + outer loop + vertex -888.7 308.232 71.9783 + vertex -891.888 314.032 65.2632 + vertex -889.9 306.731 65.2523 + endloop + endfacet + facet normal -0.957317 -0.183994 0.222915 + outer loop + vertex -892.018 322.745 72.0409 + vertex -893.337 321.424 65.286 + vertex -890.623 315.45 72.0105 + endloop + endfacet + facet normal -0.957358 -0.188275 0.219129 + outer loop + vertex -890.623 315.45 72.0105 + vertex -893.337 321.424 65.286 + vertex -891.888 314.032 65.2632 + endloop + endfacet + facet normal -0.969574 -0.119453 0.213678 + outer loop + vertex -892.918 330.071 72.0525 + vertex -894.248 328.833 65.3235 + vertex -892.018 322.745 72.0409 + endloop + endfacet + facet normal -0.969638 -0.120362 0.212875 + outer loop + vertex -892.018 322.745 72.0409 + vertex -894.248 328.833 65.3235 + vertex -893.337 321.424 65.286 + endloop + endfacet + facet normal -0.278071 -0.824153 0.493405 + outer loop + vertex -852.527 254.928 60.9979 + vertex -851.856 252.737 57.7163 + vertex -851.83 254.483 60.6474 + endloop + endfacet + facet normal -0.317651 -0.81339 0.487334 + outer loop + vertex -851.83 254.483 60.6474 + vertex -851.856 252.737 57.7163 + vertex -851.047 252.089 57.1622 + endloop + endfacet + facet normal -0.303338 -0.834537 0.459928 + outer loop + vertex -853.077 256.56 63.5958 + vertex -852.527 254.928 60.9979 + vertex -852.55 256.619 64.0505 + endloop + endfacet + facet normal -0.301702 -0.834986 0.460189 + outer loop + vertex -852.55 256.619 64.0505 + vertex -852.527 254.928 60.9979 + vertex -851.83 254.483 60.6474 + endloop + endfacet + facet normal -0.390604 -0.809855 0.437679 + outer loop + vertex -855.508 256.352 61.1369 + vertex -855.076 254.357 57.8308 + vertex -853.714 255.435 61.0407 + endloop + endfacet + facet normal -0.408482 -0.798847 0.441572 + outer loop + vertex -853.714 255.435 61.0407 + vertex -855.076 254.357 57.8308 + vertex -853.155 253.383 57.8458 + endloop + endfacet + facet normal -0.374221 -0.828091 0.417401 + outer loop + vertex -855.811 258.187 64.5058 + vertex -855.508 256.352 61.1369 + vertex -854.136 257.283 64.2129 + endloop + endfacet + facet normal -0.394487 -0.815883 0.422746 + outer loop + vertex -854.136 257.283 64.2129 + vertex -855.508 256.352 61.1369 + vertex -853.714 255.435 61.0407 + endloop + endfacet + facet normal -0.311896 -0.838461 0.446882 + outer loop + vertex -854.136 257.283 64.2129 + vertex -853.714 255.435 61.0407 + vertex -853.077 256.56 63.5958 + endloop + endfacet + facet normal -0.33725 -0.827729 0.448472 + outer loop + vertex -853.077 256.56 63.5958 + vertex -853.714 255.435 61.0407 + vertex -852.527 254.928 60.9979 + endloop + endfacet + facet normal -0.332775 -0.818869 0.467668 + outer loop + vertex -853.714 255.435 61.0407 + vertex -853.155 253.383 57.8458 + vertex -852.527 254.928 60.9979 + endloop + endfacet + facet normal -0.35581 -0.809212 0.467521 + outer loop + vertex -852.527 254.928 60.9979 + vertex -853.155 253.383 57.8458 + vertex -851.856 252.737 57.7163 + endloop + endfacet + facet normal -0.536443 -0.75513 0.376838 + outer loop + vertex -860.569 259.858 61.5442 + vertex -859.916 257.856 58.4618 + vertex -857.795 257.754 61.2787 + endloop + endfacet + facet normal -0.536927 -0.754595 0.377221 + outer loop + vertex -857.795 257.754 61.2787 + vertex -859.916 257.856 58.4618 + vertex -857.499 255.885 57.9609 + endloop + endfacet + facet normal -0.529608 -0.774997 0.34481 + outer loop + vertex -860.225 261.212 65.1155 + vertex -860.569 259.858 61.5442 + vertex -857.984 259.485 64.677 + endloop + endfacet + facet normal -0.542382 -0.76047 0.357082 + outer loop + vertex -857.984 259.485 64.677 + vertex -860.569 259.858 61.5442 + vertex -857.795 257.754 61.2787 + endloop + endfacet + facet normal -0.450616 -0.805399 0.385068 + outer loop + vertex -857.984 259.485 64.677 + vertex -857.795 257.754 61.2787 + vertex -855.811 258.187 64.5058 + endloop + endfacet + facet normal -0.463211 -0.79512 0.391433 + outer loop + vertex -855.811 258.187 64.5058 + vertex -857.795 257.754 61.2787 + vertex -855.508 256.352 61.1369 + endloop + endfacet + facet normal -0.459669 -0.790657 0.404433 + outer loop + vertex -857.795 257.754 61.2787 + vertex -857.499 255.885 57.9609 + vertex -855.508 256.352 61.1369 + endloop + endfacet + facet normal -0.470708 -0.781254 0.409971 + outer loop + vertex -855.508 256.352 61.1369 + vertex -857.499 255.885 57.9609 + vertex -855.076 254.357 57.8308 + endloop + endfacet + facet normal -0.608869 -0.717963 0.337355 + outer loop + vertex -859.916 257.856 58.4618 + vertex -860.569 259.858 61.5442 + vertex -863.505 260.361 57.315 + endloop + endfacet + facet normal -0.609882 -0.719778 0.331609 + outer loop + vertex -860.225 261.212 65.1155 + vertex -863.885 263.545 63.4473 + vertex -860.569 259.858 61.5442 + endloop + endfacet + facet normal -0.607366 -0.719827 0.336089 + outer loop + vertex -863.885 263.545 63.4473 + vertex -863.505 260.361 57.315 + vertex -860.569 259.858 61.5442 + endloop + endfacet + facet normal -0.669221 -0.676771 0.306796 + outer loop + vertex -868.853 268.864 64.3455 + vertex -868.637 265.889 58.2549 + vertex -863.885 263.545 63.4473 + endloop + endfacet + facet normal -0.670373 -0.67473 0.308772 + outer loop + vertex -863.885 263.545 63.4473 + vertex -868.637 265.889 58.2549 + vertex -863.505 260.361 57.315 + endloop + endfacet + facet normal -0.725752 -0.625967 0.285395 + outer loop + vertex -873.398 274.387 64.9 + vertex -873.424 271.642 58.8144 + vertex -868.853 268.864 64.3455 + endloop + endfacet + facet normal -0.723833 -0.629758 0.281904 + outer loop + vertex -868.853 268.864 64.3455 + vertex -873.424 271.642 58.8144 + vertex -868.637 265.889 58.2549 + endloop + endfacet + facet normal -0.779772 -0.564241 0.271269 + outer loop + vertex -877.466 280.12 65.1326 + vertex -877.732 277.575 59.0747 + vertex -873.398 274.387 64.9 + endloop + endfacet + facet normal -0.775338 -0.574464 0.262376 + outer loop + vertex -873.398 274.387 64.9 + vertex -877.732 277.575 59.0747 + vertex -873.424 271.642 58.8144 + endloop + endfacet + facet normal -0.825731 -0.499693 0.261677 + outer loop + vertex -881.152 286.226 65.1626 + vertex -881.628 283.853 59.128 + vertex -877.466 280.12 65.1326 + endloop + endfacet + facet normal -0.821497 -0.511933 0.251132 + outer loop + vertex -877.466 280.12 65.1326 + vertex -881.628 283.853 59.128 + vertex -877.732 277.575 59.0747 + endloop + endfacet + facet normal -0.861446 -0.440037 0.253532 + outer loop + vertex -884.492 292.766 65.1623 + vertex -885.23 290.708 59.0818 + vertex -881.152 286.226 65.1626 + endloop + endfacet + facet normal -0.858963 -0.449796 0.244674 + outer loop + vertex -881.152 286.226 65.1626 + vertex -885.23 290.708 59.0818 + vertex -881.628 283.853 59.128 + endloop + endfacet + facet normal -0.889434 -0.381929 0.251072 + outer loop + vertex -887.426 299.629 65.2101 + vertex -888.304 297.766 59.2657 + vertex -884.492 292.766 65.1623 + endloop + endfacet + facet normal -0.887585 -0.392756 0.240697 + outer loop + vertex -884.492 292.766 65.1623 + vertex -888.304 297.766 59.2657 + vertex -885.23 290.708 59.0818 + endloop + endfacet + facet normal -0.913852 -0.319886 0.250097 + outer loop + vertex -889.9 306.731 65.2523 + vertex -890.797 304.741 59.4321 + vertex -887.426 299.629 65.2101 + endloop + endfacet + facet normal -0.912611 -0.33184 0.238795 + outer loop + vertex -887.426 299.629 65.2101 + vertex -890.797 304.741 59.4321 + vertex -888.304 297.766 59.2657 + endloop + endfacet + facet normal -0.935403 -0.255059 0.244878 + outer loop + vertex -891.888 314.032 65.2632 + vertex -892.874 311.981 59.3615 + vertex -889.9 306.731 65.2523 + endloop + endfacet + facet normal -0.934921 -0.265975 0.234906 + outer loop + vertex -889.9 306.731 65.2523 + vertex -892.874 311.981 59.3615 + vertex -890.797 304.741 59.4321 + endloop + endfacet + facet normal -0.952984 -0.187476 0.238064 + outer loop + vertex -893.337 321.424 65.286 + vertex -894.439 319.46 59.3277 + vertex -891.888 314.032 65.2632 + endloop + endfacet + facet normal -0.953194 -0.198399 0.228165 + outer loop + vertex -891.888 314.032 65.2632 + vertex -894.439 319.46 59.3277 + vertex -892.874 311.981 59.3615 + endloop + endfacet + facet normal -0.965882 -0.119985 0.229511 + outer loop + vertex -894.248 328.833 65.3235 + vertex -895.434 326.955 59.3499 + vertex -893.337 321.424 65.286 + endloop + endfacet + facet normal -0.966623 -0.129047 0.221329 + outer loop + vertex -893.337 321.424 65.286 + vertex -895.434 326.955 59.3499 + vertex -894.439 319.46 59.3277 + endloop + endfacet + facet normal -0.324912 -0.783483 0.529704 + outer loop + vertex -851.127 250.399 54.4763 + vertex -850.385 248.159 51.6174 + vertex -850.186 249.637 53.9261 + endloop + endfacet + facet normal -0.376953 -0.76492 0.522305 + outer loop + vertex -850.186 249.637 53.9261 + vertex -850.385 248.159 51.6174 + vertex -849.327 247.327 51.1635 + endloop + endfacet + facet normal -0.291975 -0.805534 0.515622 + outer loop + vertex -851.856 252.737 57.7163 + vertex -851.127 250.399 54.4763 + vertex -851.047 252.089 57.1622 + endloop + endfacet + facet normal -0.343356 -0.790259 0.507541 + outer loop + vertex -851.047 252.089 57.1622 + vertex -851.127 250.399 54.4763 + vertex -850.186 249.637 53.9261 + endloop + endfacet + facet normal -0.41699 -0.777548 0.470678 + outer loop + vertex -854.43 252.256 54.7549 + vertex -853.64 250.462 52.4915 + vertex -852.496 251.215 54.7501 + endloop + endfacet + facet normal -0.426531 -0.77078 0.473255 + outer loop + vertex -852.496 251.215 54.7501 + vertex -853.64 250.462 52.4915 + vertex -851.992 249.251 52.0047 + endloop + endfacet + facet normal -0.405237 -0.792221 0.456255 + outer loop + vertex -855.076 254.357 57.8308 + vertex -854.43 252.256 54.7549 + vertex -853.155 253.383 57.8458 + endloop + endfacet + facet normal -0.419931 -0.782964 0.45894 + outer loop + vertex -853.155 253.383 57.8458 + vertex -854.43 252.256 54.7549 + vertex -852.496 251.215 54.7501 + endloop + endfacet + facet normal -0.349718 -0.800734 0.486335 + outer loop + vertex -853.155 253.383 57.8458 + vertex -852.496 251.215 54.7501 + vertex -851.856 252.737 57.7163 + endloop + endfacet + facet normal -0.373767 -0.789993 0.486014 + outer loop + vertex -851.856 252.737 57.7163 + vertex -852.496 251.215 54.7501 + vertex -851.127 250.399 54.4763 + endloop + endfacet + facet normal -0.369844 -0.786367 0.494815 + outer loop + vertex -852.496 251.215 54.7501 + vertex -851.992 249.251 52.0047 + vertex -851.127 250.399 54.4763 + endloop + endfacet + facet normal -0.402248 -0.768374 0.497792 + outer loop + vertex -851.127 250.399 54.4763 + vertex -851.992 249.251 52.0047 + vertex -850.385 248.159 51.6174 + endloop + endfacet + facet normal -0.541789 -0.741243 0.396261 + outer loop + vertex -859.998 256.348 55.3232 + vertex -858.893 254.077 52.5865 + vertex -856.974 253.862 54.8075 + endloop + endfacet + facet normal -0.53774 -0.746295 0.392274 + outer loop + vertex -856.974 253.862 54.8075 + vertex -858.893 254.077 52.5865 + vertex -856.035 251.768 52.111 + endloop + endfacet + facet normal -0.53717 -0.754734 0.376596 + outer loop + vertex -859.916 257.856 58.4618 + vertex -859.998 256.348 55.3232 + vertex -857.499 255.885 57.9609 + endloop + endfacet + facet normal -0.545499 -0.743714 0.386419 + outer loop + vertex -857.499 255.885 57.9609 + vertex -859.998 256.348 55.3232 + vertex -856.974 253.862 54.8075 + endloop + endfacet + facet normal -0.467618 -0.777285 0.420907 + outer loop + vertex -857.499 255.885 57.9609 + vertex -856.974 253.862 54.8075 + vertex -855.076 254.357 57.8308 + endloop + endfacet + facet normal -0.476934 -0.769124 0.425419 + outer loop + vertex -855.076 254.357 57.8308 + vertex -856.974 253.862 54.8075 + vertex -854.43 252.256 54.7549 + endloop + endfacet + facet normal -0.475662 -0.767266 0.430172 + outer loop + vertex -856.974 253.862 54.8075 + vertex -856.035 251.768 52.111 + vertex -854.43 252.256 54.7549 + endloop + endfacet + facet normal -0.483626 -0.760261 0.433715 + outer loop + vertex -854.43 252.256 54.7549 + vertex -856.035 251.768 52.111 + vertex -853.64 250.462 52.4915 + endloop + endfacet + facet normal -0.609911 -0.713195 0.345488 + outer loop + vertex -858.893 254.077 52.5865 + vertex -859.998 256.348 55.3232 + vertex -862.57 257.32 52.7893 + endloop + endfacet + facet normal -0.608632 -0.708894 0.356421 + outer loop + vertex -859.916 257.856 58.4618 + vertex -863.505 260.361 57.315 + vertex -859.998 256.348 55.3232 + endloop + endfacet + facet normal -0.61247 -0.708925 0.349724 + outer loop + vertex -863.505 260.361 57.315 + vertex -862.57 257.32 52.7893 + vertex -859.998 256.348 55.3232 + endloop + endfacet + facet normal -0.663714 -0.671926 0.328631 + outer loop + vertex -868.637 265.889 58.2549 + vertex -867.685 262.659 53.5723 + vertex -863.505 260.361 57.315 + endloop + endfacet + facet normal -0.660201 -0.679479 0.320069 + outer loop + vertex -863.505 260.361 57.315 + vertex -867.685 262.659 53.5723 + vertex -862.57 257.32 52.7893 + endloop + endfacet + facet normal -0.716759 -0.626278 0.306646 + outer loop + vertex -873.424 271.642 58.8144 + vertex -872.72 268.52 54.0838 + vertex -868.637 265.889 58.2549 + endloop + endfacet + facet normal -0.711925 -0.63731 0.294955 + outer loop + vertex -868.637 265.889 58.2549 + vertex -872.72 268.52 54.0838 + vertex -867.685 262.659 53.5723 + endloop + endfacet + facet normal -0.768826 -0.570866 0.28813 + outer loop + vertex -877.732 277.575 59.0747 + vertex -877.269 274.58 54.3741 + vertex -873.424 271.642 58.8144 + endloop + endfacet + facet normal -0.762975 -0.585896 0.27312 + outer loop + vertex -873.424 271.642 58.8144 + vertex -877.269 274.58 54.3741 + vertex -872.72 268.52 54.0838 + endloop + endfacet + facet normal -0.815126 -0.508208 0.278017 + outer loop + vertex -881.628 283.853 59.128 + vertex -881.383 280.908 54.4614 + vertex -877.732 277.575 59.0747 + endloop + endfacet + facet normal -0.80848 -0.529135 0.257638 + outer loop + vertex -877.732 277.575 59.0747 + vertex -881.383 280.908 54.4614 + vertex -877.269 274.58 54.3741 + endloop + endfacet + facet normal -0.852808 -0.446384 0.271035 + outer loop + vertex -885.23 290.708 59.0818 + vertex -885.188 287.786 54.4036 + vertex -881.628 283.853 59.128 + endloop + endfacet + facet normal -0.848083 -0.467018 0.250298 + outer loop + vertex -881.628 283.853 59.128 + vertex -885.188 287.786 54.4036 + vertex -881.383 280.908 54.4614 + endloop + endfacet + facet normal -0.88383 -0.391521 0.256041 + outer loop + vertex -888.304 297.766 59.2657 + vertex -888.995 295.973 54.1392 + vertex -885.23 290.708 59.0818 + endloop + endfacet + facet normal -0.882491 -0.402484 0.243343 + outer loop + vertex -885.23 290.708 59.0818 + vertex -888.995 295.973 54.1392 + vertex -885.188 287.786 54.4036 + endloop + endfacet + facet normal -0.906662 -0.330278 0.262452 + outer loop + vertex -890.797 304.741 59.4321 + vertex -891.137 302.456 55.3809 + vertex -888.304 297.766 59.2657 + endloop + endfacet + facet normal -0.906187 -0.34599 0.243136 + outer loop + vertex -888.304 297.766 59.2657 + vertex -891.137 302.456 55.3809 + vertex -888.995 295.973 54.1392 + endloop + endfacet + facet normal -0.929681 -0.26426 0.256632 + outer loop + vertex -892.874 311.981 59.3615 + vertex -893.256 309.012 54.9205 + vertex -890.797 304.741 59.4321 + endloop + endfacet + facet normal -0.928959 -0.283557 0.23797 + outer loop + vertex -890.797 304.741 59.4321 + vertex -893.256 309.012 54.9205 + vertex -891.137 302.456 55.3809 + endloop + endfacet + facet normal -0.947795 -0.197168 0.250619 + outer loop + vertex -894.439 319.46 59.3277 + vertex -895.06 316.643 54.7616 + vertex -892.874 311.981 59.3615 + endloop + endfacet + facet normal -0.948517 -0.219503 0.228329 + outer loop + vertex -892.874 311.981 59.3615 + vertex -895.06 316.643 54.7616 + vertex -893.256 309.012 54.9205 + endloop + endfacet + facet normal -0.961761 -0.128462 0.241895 + outer loop + vertex -895.434 326.955 59.3499 + vertex -896.23 324.24 54.7432 + vertex -894.439 319.46 59.3277 + endloop + endfacet + facet normal -0.963678 -0.147897 0.222378 + outer loop + vertex -894.439 319.46 59.3277 + vertex -896.23 324.24 54.7432 + vertex -895.06 316.643 54.7616 + endloop + endfacet + facet normal -0.390914 -0.726285 0.565417 + outer loop + vertex -849.67 246.216 49.3835 + vertex -849.034 244.717 47.8985 + vertex -848.516 245.293 48.9968 + endloop + endfacet + facet normal -0.419064 -0.70762 0.568911 + outer loop + vertex -848.516 245.293 48.9968 + vertex -849.034 244.717 47.8985 + vertex -847.961 243.738 47.4709 + endloop + endfacet + facet normal -0.362378 -0.7576 0.542885 + outer loop + vertex -850.385 248.159 51.6174 + vertex -849.67 246.216 49.3835 + vertex -849.327 247.327 51.1635 + endloop + endfacet + facet normal -0.408288 -0.736875 0.53881 + outer loop + vertex -849.327 247.327 51.1635 + vertex -849.67 246.216 49.3835 + vertex -848.516 245.293 48.9968 + endloop + endfacet + facet normal -0.468158 -0.749554 0.467971 + outer loop + vertex -854.068 249.545 50.4432 + vertex -853.604 248.264 48.8548 + vertex -851.542 247.531 49.7445 + endloop + endfacet + facet normal -0.472531 -0.729335 0.494758 + outer loop + vertex -851.542 247.531 49.7445 + vertex -853.604 248.264 48.8548 + vertex -851.042 246.164 48.2074 + endloop + endfacet + facet normal -0.44287 -0.780294 0.441597 + outer loop + vertex -853.64 250.462 52.4915 + vertex -854.068 249.545 50.4432 + vertex -851.992 249.251 52.0047 + endloop + endfacet + facet normal -0.464001 -0.747109 0.475954 + outer loop + vertex -851.992 249.251 52.0047 + vertex -854.068 249.545 50.4432 + vertex -851.542 247.531 49.7445 + endloop + endfacet + facet normal -0.399439 -0.766214 0.503354 + outer loop + vertex -851.992 249.251 52.0047 + vertex -851.542 247.531 49.7445 + vertex -850.385 248.159 51.6174 + endloop + endfacet + facet normal -0.425359 -0.745897 0.51255 + outer loop + vertex -850.385 248.159 51.6174 + vertex -851.542 247.531 49.7445 + vertex -849.67 246.216 49.3835 + endloop + endfacet + facet normal -0.42043 -0.74166 0.522665 + outer loop + vertex -851.542 247.531 49.7445 + vertex -851.042 246.164 48.2074 + vertex -849.67 246.216 49.3835 + endloop + endfacet + facet normal -0.435972 -0.720068 0.539843 + outer loop + vertex -849.67 246.216 49.3835 + vertex -851.042 246.164 48.2074 + vertex -849.034 244.717 47.8985 + endloop + endfacet + facet normal -0.439395 -0.685474 0.580567 + outer loop + vertex -853.751 247.767 47.9797 + vertex -852.791 246.571 47.2939 + vertex -850.436 245.115 47.3575 + endloop + endfacet + facet normal -0.42888 -0.66722 0.608999 + outer loop + vertex -850.436 245.115 47.3575 + vertex -852.791 246.571 47.2939 + vertex -849.623 244.2 46.9272 + endloop + endfacet + facet normal -0.47316 -0.729735 0.493564 + outer loop + vertex -853.604 248.264 48.8548 + vertex -853.751 247.767 47.9797 + vertex -851.042 246.164 48.2074 + endloop + endfacet + facet normal -0.461725 -0.703833 0.539841 + outer loop + vertex -851.042 246.164 48.2074 + vertex -853.751 247.767 47.9797 + vertex -850.436 245.115 47.3575 + endloop + endfacet + facet normal -0.420457 -0.705176 0.570914 + outer loop + vertex -851.042 246.164 48.2074 + vertex -850.436 245.115 47.3575 + vertex -849.034 244.717 47.8985 + endloop + endfacet + facet normal -0.423205 -0.685369 0.592594 + outer loop + vertex -849.034 244.717 47.8985 + vertex -850.436 245.115 47.3575 + vertex -848.604 243.752 47.089 + endloop + endfacet + facet normal -0.38995 -0.652033 0.650225 + outer loop + vertex -850.436 245.115 47.3575 + vertex -849.623 244.2 46.9272 + vertex -848.604 243.752 47.089 + endloop + endfacet + facet normal -0.389499 -0.650275 0.652253 + outer loop + vertex -848.604 243.752 47.089 + vertex -849.623 244.2 46.9272 + vertex -848.504 243.447 46.8448 + endloop + endfacet + facet normal -0.51016 -0.697753 0.502869 + outer loop + vertex -852.791 246.571 47.2939 + vertex -853.751 247.767 47.9797 + vertex -857.445 250.53 48.0655 + endloop + endfacet + facet normal -0.508788 -0.709258 0.487942 + outer loop + vertex -853.604 248.264 48.8548 + vertex -858.445 252.433 49.8671 + vertex -853.751 247.767 47.9797 + endloop + endfacet + facet normal -0.523574 -0.714485 0.464092 + outer loop + vertex -858.445 252.433 49.8671 + vertex -857.445 250.53 48.0655 + vertex -853.751 247.767 47.9797 + endloop + endfacet + facet normal -0.581975 -0.670646 0.459935 + outer loop + vertex -865.719 259.187 50.512 + vertex -863.77 256.298 48.7646 + vertex -858.445 252.433 49.8671 + endloop + endfacet + facet normal -0.590064 -0.696535 0.408244 + outer loop + vertex -858.445 252.433 49.8671 + vertex -863.77 256.298 48.7646 + vertex -857.445 250.53 48.0655 + endloop + endfacet + facet normal -0.654596 -0.630481 0.41713 + outer loop + vertex -871.242 265.219 50.9607 + vertex -869.41 262.178 49.2398 + vertex -865.719 259.187 50.512 + endloop + endfacet + facet normal -0.659172 -0.661185 0.358226 + outer loop + vertex -865.719 259.187 50.512 + vertex -869.41 262.178 49.2398 + vertex -863.77 256.298 48.7646 + endloop + endfacet + facet normal -0.718802 -0.584691 0.376112 + outer loop + vertex -876.077 271.352 51.2544 + vertex -874.358 268.074 49.4451 + vertex -871.242 265.219 50.9607 + endloop + endfacet + facet normal -0.720006 -0.615381 0.320776 + outer loop + vertex -871.242 265.219 50.9607 + vertex -874.358 268.074 49.4451 + vertex -869.41 262.178 49.2398 + endloop + endfacet + facet normal -0.768882 -0.536077 0.348486 + outer loop + vertex -880.421 277.684 51.4117 + vertex -879.103 274.657 49.6627 + vertex -876.077 271.352 51.2544 + endloop + endfacet + facet normal -0.771325 -0.565654 0.291708 + outer loop + vertex -876.077 271.352 51.2544 + vertex -879.103 274.657 49.6627 + vertex -874.358 268.074 49.4451 + endloop + endfacet + facet normal -0.804211 -0.477029 0.354526 + outer loop + vertex -884.33 284.334 51.4926 + vertex -883.091 281.044 49.8751 + vertex -880.421 277.684 51.4117 + endloop + endfacet + facet normal -0.809769 -0.514986 0.281184 + outer loop + vertex -880.421 277.684 51.4117 + vertex -883.091 281.044 49.8751 + vertex -879.103 274.657 49.6627 + endloop + endfacet + facet normal -0.83052 -0.417111 0.369127 + outer loop + vertex -887.873 291.314 51.4074 + vertex -886.902 288.053 49.9071 + vertex -884.33 284.334 51.4926 + endloop + endfacet + facet normal -0.840572 -0.458354 0.288704 + outer loop + vertex -884.33 284.334 51.4926 + vertex -886.902 288.053 49.9071 + vertex -883.091 281.044 49.8751 + endloop + endfacet + facet normal -0.854052 -0.357242 0.378117 + outer loop + vertex -890.61 297.565 51.1328 + vertex -889.988 294.855 49.9765 + vertex -887.873 291.314 51.4074 + endloop + endfacet + facet normal -0.867407 -0.396558 0.300576 + outer loop + vertex -887.873 291.314 51.4074 + vertex -889.988 294.855 49.9765 + vertex -886.902 288.053 49.9071 + endloop + endfacet + facet normal -0.880687 -0.313656 0.354979 + outer loop + vertex -892.604 304.226 52.0705 + vertex -892.539 301.806 50.092 + vertex -890.61 297.565 51.1328 + endloop + endfacet + facet normal -0.893846 -0.333106 0.300133 + outer loop + vertex -890.61 297.565 51.1328 + vertex -892.539 301.806 50.092 + vertex -889.988 294.855 49.9765 + endloop + endfacet + facet normal -0.899197 -0.241643 0.364764 + outer loop + vertex -895.055 313.028 51.8587 + vertex -894.809 309.568 50.173 + vertex -892.604 304.226 52.0705 + endloop + endfacet + facet normal -0.914408 -0.27053 0.301118 + outer loop + vertex -892.604 304.226 52.0705 + vertex -894.809 309.568 50.173 + vertex -892.539 301.806 50.092 + endloop + endfacet + facet normal -0.928734 -0.170933 0.328991 + outer loop + vertex -896.522 320.884 51.7993 + vertex -896.453 317.459 50.2138 + vertex -895.055 313.028 51.8587 + endloop + endfacet + facet normal -0.942756 -0.197827 0.268468 + outer loop + vertex -895.055 313.028 51.8587 + vertex -896.453 317.459 50.2138 + vertex -894.809 309.568 50.173 + endloop + endfacet + facet normal -0.947987 -0.102143 0.301476 + outer loop + vertex -897.335 328.462 51.811 + vertex -897.486 325.124 50.205 + vertex -896.522 320.884 51.7993 + endloop + endfacet + facet normal -0.962649 -0.12941 0.237825 + outer loop + vertex -896.522 320.884 51.7993 + vertex -897.486 325.124 50.205 + vertex -896.453 317.459 50.2138 + endloop + endfacet + facet normal -0.283407 -0.689743 -0.666285 + outer loop + vertex -849.156 244.251 294.988 + vertex -848.286 242.207 296.733 + vertex -849.804 244.462 295.045 + endloop + endfacet + facet normal -0.311047 -0.720954 -0.619253 + outer loop + vertex -850.063 246.709 292.582 + vertex -849.156 244.251 294.988 + vertex -850.216 246.201 293.25 + endloop + endfacet + facet normal -0.387044 -0.741974 -0.547423 + outer loop + vertex -851.25 250.349 288.488 + vertex -850.063 246.709 292.582 + vertex -851.019 248.709 290.547 + endloop + endfacet + facet normal -0.338828 -0.783259 -0.52125 + outer loop + vertex -852.29 253.649 284.205 + vertex -851.25 250.349 288.488 + vertex -852.375 253.032 285.188 + endloop + endfacet + facet normal -0.323756 -0.814756 -0.480993 + outer loop + vertex -852.995 256.171 280.408 + vertex -852.29 253.649 284.205 + vertex -853.051 255.392 281.764 + endloop + endfacet + facet normal -0.348797 -0.833156 -0.429176 + outer loop + vertex -853.698 258.905 275.671 + vertex -852.995 256.171 280.408 + vertex -853.562 257.323 278.631 + endloop + endfacet + facet normal -0.232272 -0.877645 -0.419271 + outer loop + vertex -854.179 261.427 270.658 + vertex -853.698 258.905 275.671 + vertex -854.667 260.985 271.854 + endloop + endfacet + facet normal -0.2144 -0.897983 -0.384266 + outer loop + vertex -854.427 263.324 266.365 + vertex -854.179 261.427 270.658 + vertex -854.888 262.849 267.73 + endloop + endfacet + facet normal -0.197489 -0.91521 -0.351267 + outer loop + vertex -854.668 265.324 261.287 + vertex -854.427 263.324 266.365 + vertex -855.052 264.457 263.764 + endloop + endfacet + facet normal -0.223264 -0.922513 -0.314837 + outer loop + vertex -854.948 267.358 255.527 + vertex -854.668 265.324 261.287 + vertex -855.953 266.656 258.297 + endloop + endfacet + facet normal -0.157465 -0.941001 -0.299535 + outer loop + vertex -854.854 268.749 251.109 + vertex -854.948 267.358 255.527 + vertex -855.94 269.223 250.19 + endloop + endfacet + facet normal -0.185109 -0.94518 -0.269015 + outer loop + vertex -854.9 270.195 246.059 + vertex -854.854 268.749 251.109 + vertex -855.94 269.223 250.19 + endloop + endfacet + facet normal -0.205212 -0.948321 -0.242024 + outer loop + vertex -854.883 271.774 239.856 + vertex -854.9 270.195 246.059 + vertex -855.962 271.388 242.285 + endloop + endfacet + facet normal -0.121363 -0.966748 -0.2251 + outer loop + vertex -854.574 272.903 234.845 + vertex -854.883 271.774 239.856 + vertex -855.59 273.106 234.519 + endloop + endfacet + facet normal -0.131927 -0.971834 -0.19528 + outer loop + vertex -854.622 273.829 230.264 + vertex -854.574 272.903 234.845 + vertex -855.59 273.106 234.519 + endloop + endfacet + facet normal -0.143469 -0.972132 -0.185407 + outer loop + vertex -854.525 274.442 226.978 + vertex -854.622 273.829 230.264 + vertex -855.347 274.68 226.365 + endloop + endfacet + facet normal -0.153654 -0.973026 -0.172077 + outer loop + vertex -854.426 274.988 223.801 + vertex -854.525 274.442 226.978 + vertex -855.347 274.68 226.365 + endloop + endfacet + facet normal -0.112586 -0.979789 -0.165341 + outer loop + vertex -854.219 275.515 220.536 + vertex -854.426 274.988 223.801 + vertex -854.965 275.975 218.317 + endloop + endfacet + facet normal -0.152095 -0.976696 -0.151435 + outer loop + vertex -854.166 275.927 217.83 + vertex -854.219 275.515 220.536 + vertex -854.965 275.975 218.317 + endloop + endfacet + facet normal -0.141936 -0.980712 -0.13438 + outer loop + vertex -854.256 276.331 214.976 + vertex -854.166 275.927 217.83 + vertex -854.965 275.975 218.317 + endloop + endfacet + facet normal -0.113425 -0.984133 -0.136443 + outer loop + vertex -854.051 276.663 212.407 + vertex -854.256 276.331 214.976 + vertex -854.74 277.084 209.944 + endloop + endfacet + facet normal -0.155913 -0.979978 -0.123833 + outer loop + vertex -853.99 277.001 209.658 + vertex -854.051 276.663 212.407 + vertex -854.74 277.084 209.944 + endloop + endfacet + facet normal -0.150317 -0.982681 -0.108361 + outer loop + vertex -854.01 277.383 206.215 + vertex -853.99 277.001 209.658 + vertex -854.74 277.084 209.944 + endloop + endfacet + facet normal -0.14619 -0.983646 -0.105206 + outer loop + vertex -853.932 277.663 203.498 + vertex -854.01 277.383 206.215 + vertex -854.583 277.954 201.681 + endloop + endfacet + facet normal -0.163228 -0.981632 -0.0987714 + outer loop + vertex -853.838 277.844 201.538 + vertex -853.932 277.663 203.498 + vertex -854.583 277.954 201.681 + endloop + endfacet + facet normal -0.160278 -0.983666 -0.0819313 + outer loop + vertex -853.893 278.135 198.149 + vertex -853.838 277.844 201.538 + vertex -854.583 277.954 201.681 + endloop + endfacet + facet normal -0.179443 -0.980863 -0.0755468 + outer loop + vertex -853.857 278.355 195.208 + vertex -853.893 278.135 198.149 + vertex -854.579 278.582 193.987 + endloop + endfacet + facet normal -0.192883 -0.978916 -0.0672292 + outer loop + vertex -853.839 278.563 192.138 + vertex -853.857 278.355 195.208 + vertex -854.579 278.582 193.987 + endloop + endfacet + facet normal -0.103233 -0.992711 -0.0621934 + outer loop + vertex -853.715 278.749 188.957 + vertex -853.839 278.563 192.138 + vertex -854.413 278.978 186.467 + endloop + endfacet + facet normal -0.149566 -0.98755 -0.0487333 + outer loop + vertex -853.703 278.883 186.204 + vertex -853.715 278.749 188.957 + vertex -854.413 278.978 186.467 + endloop + endfacet + facet normal -0.143746 -0.989083 -0.0324451 + outer loop + vertex -853.821 278.995 183.319 + vertex -853.703 278.883 186.204 + vertex -854.413 278.978 186.467 + endloop + endfacet + facet normal -0.106006 -0.99366 -0.0374525 + outer loop + vertex -853.663 279.075 180.738 + vertex -853.821 278.995 183.319 + vertex -854.365 279.242 178.295 + endloop + endfacet + facet normal -0.153545 -0.987864 -0.0234104 + outer loop + vertex -853.653 279.139 177.981 + vertex -853.663 279.075 180.738 + vertex -854.365 279.242 178.295 + endloop + endfacet + facet normal -0.146211 -0.989233 -0.00636576 + outer loop + vertex -853.785 279.177 175.091 + vertex -853.653 279.139 177.981 + vertex -854.365 279.242 178.295 + endloop + endfacet + facet normal -0.108742 -0.994002 -0.0116078 + outer loop + vertex -853.643 279.191 172.539 + vertex -853.785 279.177 175.091 + vertex -854.347 279.296 170.164 + endloop + endfacet + facet normal -0.152298 -0.988333 0.00154754 + outer loop + vertex -853.632 279.185 169.825 + vertex -853.643 279.191 172.539 + vertex -854.347 279.296 170.164 + endloop + endfacet + facet normal -0.144749 -0.989308 0.0178005 + outer loop + vertex -853.728 279.139 166.453 + vertex -853.632 279.185 169.825 + vertex -854.347 279.296 170.164 + endloop + endfacet + facet normal -0.181115 -0.98319 0.0231161 + outer loop + vertex -853.723 279.07 163.553 + vertex -853.728 279.139 166.453 + vertex -854.459 279.178 162.392 + endloop + endfacet + facet normal -0.193104 -0.98069 0.0309383 + outer loop + vertex -853.744 278.979 160.555 + vertex -853.723 279.07 163.553 + vertex -854.459 279.178 162.392 + endloop + endfacet + facet normal -0.109711 -0.993285 0.0367159 + outer loop + vertex -853.658 278.855 157.461 + vertex -853.744 278.979 160.555 + vertex -854.397 278.845 154.976 + endloop + endfacet + facet normal -0.1541 -0.986795 0.0498906 + outer loop + vertex -853.689 278.723 154.738 + vertex -853.658 278.855 157.461 + vertex -854.397 278.845 154.976 + endloop + endfacet + facet normal -0.148599 -0.986682 0.0661638 + outer loop + vertex -853.855 278.554 151.85 + vertex -853.689 278.723 154.738 + vertex -854.397 278.845 154.976 + endloop + endfacet + facet normal -0.112483 -0.991764 0.0612497 + outer loop + vertex -853.735 278.383 149.303 + vertex -853.855 278.554 151.85 + vertex -854.467 278.311 146.787 + endloop + endfacet + facet normal -0.159514 -0.984362 0.0747392 + outer loop + vertex -853.746 278.175 146.541 + vertex -853.735 278.383 149.303 + vertex -854.467 278.311 146.787 + endloop + endfacet + facet normal -0.15435 -0.983943 0.0896222 + outer loop + vertex -853.86 277.876 143.066 + vertex -853.746 278.175 146.541 + vertex -854.467 278.311 146.787 + endloop + endfacet + facet normal -0.160735 -0.982646 0.0925819 + outer loop + vertex -853.856 277.619 140.338 + vertex -853.86 277.876 143.066 + vertex -854.572 277.566 138.533 + endloop + endfacet + facet normal -0.177819 -0.979045 0.0992499 + outer loop + vertex -853.818 277.41 138.342 + vertex -853.856 277.619 140.338 + vertex -854.572 277.566 138.533 + endloop + endfacet + facet normal -0.173458 -0.978029 0.115641 + outer loop + vertex -853.968 277.035 134.949 + vertex -853.818 277.41 138.342 + vertex -854.572 277.566 138.533 + endloop + endfacet + facet normal -0.196461 -0.972951 0.121529 + outer loop + vertex -854.015 276.678 132.016 + vertex -853.968 277.035 134.949 + vertex -854.804 276.689 130.825 + endloop + endfacet + facet normal -0.210749 -0.968717 0.131042 + outer loop + vertex -854.079 276.284 128.999 + vertex -854.015 276.678 132.016 + vertex -854.804 276.689 130.825 + endloop + endfacet + facet normal -0.12564 -0.982376 0.13839 + outer loop + vertex -854.029 275.842 125.909 + vertex -854.079 276.284 128.999 + vertex -854.812 275.606 123.522 + endloop + endfacet + facet normal -0.165148 -0.974703 0.1506 + outer loop + vertex -854.089 275.441 123.245 + vertex -854.029 275.842 125.909 + vertex -854.812 275.606 123.522 + endloop + endfacet + facet normal -0.158405 -0.973109 0.167235 + outer loop + vertex -854.303 274.995 120.45 + vertex -854.089 275.441 123.245 + vertex -854.812 275.606 123.522 + endloop + endfacet + facet normal -0.134606 -0.976299 0.169474 + outer loop + vertex -854.225 274.494 117.622 + vertex -854.303 274.995 120.45 + vertex -855.008 274.318 115.99 + endloop + endfacet + facet normal -0.171354 -0.96746 0.186169 + outer loop + vertex -854.377 273.728 113.504 + vertex -854.225 274.494 117.622 + vertex -855.008 274.318 115.99 + endloop + endfacet + facet normal -0.12786 -0.971936 0.197464 + outer loop + vertex -854.328 272.803 108.981 + vertex -854.377 273.728 113.504 + vertex -855.162 272.802 108.438 + endloop + endfacet + facet normal -0.144136 -0.964232 0.222445 + outer loop + vertex -854.577 271.705 104.063 + vertex -854.328 272.803 108.981 + vertex -855.162 272.802 108.438 + endloop + endfacet + facet normal -0.219856 -0.945473 0.240299 + outer loop + vertex -854.645 270.297 98.4601 + vertex -854.577 271.705 104.063 + vertex -855.625 271.122 100.808 + endloop + endfacet + facet normal -0.173041 -0.94926 0.262606 + outer loop + vertex -854.426 268.911 93.5945 + vertex -854.645 270.297 98.4601 + vertex -855.551 268.989 93.1357 + endloop + endfacet + facet normal -0.185683 -0.937072 0.295665 + outer loop + vertex -854.535 267.332 88.5223 + vertex -854.426 268.911 93.5945 + vertex -855.551 268.989 93.1357 + endloop + endfacet + facet normal -0.224821 -0.923208 0.311677 + outer loop + vertex -854.2 265.254 82.6085 + vertex -854.535 267.332 88.5223 + vertex -855.507 266.316 84.8106 + endloop + endfacet + facet normal -0.187357 -0.918135 0.349178 + outer loop + vertex -853.863 263.202 77.394 + vertex -854.2 265.254 82.6085 + vertex -854.635 263.993 79.0583 + endloop + endfacet + facet normal -0.216048 -0.899966 0.378661 + outer loop + vertex -853.481 261.229 72.922 + vertex -853.863 263.202 77.394 + vertex -854.178 262.067 74.5164 + endloop + endfacet + facet normal -0.263081 -0.874831 0.406767 + outer loop + vertex -852.864 258.683 67.8459 + vertex -853.481 261.229 72.922 + vertex -853.763 260.104 70.319 + endloop + endfacet + facet normal -0.260266 -0.857068 0.444631 + outer loop + vertex -852.065 256.046 63.2291 + vertex -852.864 258.683 67.8459 + vertex -852.55 256.619 64.0505 + endloop + endfacet + facet normal -0.253616 -0.837627 0.483798 + outer loop + vertex -851.303 253.67 59.5155 + vertex -852.065 256.046 63.2291 + vertex -851.83 254.483 60.6474 + endloop + endfacet + facet normal -0.258261 -0.814741 0.519132 + outer loop + vertex -850.442 251.193 56.0564 + vertex -851.303 253.67 59.5155 + vertex -851.047 252.089 57.1622 + endloop + endfacet + facet normal -0.291096 -0.788868 0.541249 + outer loop + vertex -849.567 248.772 52.9978 + vertex -850.442 251.193 56.0564 + vertex -850.186 249.637 53.9261 + endloop + endfacet + facet normal -0.33998 -0.759975 0.553942 + outer loop + vertex -848.682 246.477 50.3927 + vertex -849.567 248.772 52.9978 + vertex -849.327 247.327 51.1635 + endloop + endfacet + facet normal -0.381541 -0.727003 0.570871 + outer loop + vertex -847.794 244.315 48.2335 + vertex -848.682 246.477 50.3927 + vertex -848.516 245.293 48.9968 + endloop + endfacet + facet normal -0.329004 -0.716934 0.614623 + outer loop + vertex -846.708 242.159 46.2995 + vertex -847.794 244.315 48.2335 + vertex -847.961 243.738 47.4709 + endloop + endfacet + facet normal -0.347074 -0.720599 0.600231 + outer loop + vertex -848.646 243.404 46.6731 + vertex -846.708 242.159 46.2995 + vertex -847.961 243.738 47.4709 + endloop + endfacet + facet normal -0.44593 -0.717665 0.534886 + outer loop + vertex -851.539 245.184 46.6509 + vertex -848.646 243.404 46.6731 + vertex -849.623 244.2 46.9272 + endloop + endfacet + facet normal -0.495563 -0.691349 0.525788 + outer loop + vertex -855.884 248.7 47.1782 + vertex -851.539 245.184 46.6509 + vertex -852.791 246.571 47.2939 + endloop + endfacet + facet normal -0.556417 -0.695298 0.45493 + outer loop + vertex -860.855 253.095 47.8154 + vertex -855.884 248.7 47.1782 + vertex -857.445 250.53 48.0655 + endloop + endfacet + facet normal -0.531892 -0.646281 0.547186 + outer loop + vertex -863.931 255.938 48.1836 + vertex -860.855 253.095 47.8154 + vertex -863.77 256.298 48.7646 + endloop + endfacet + facet normal -0.583581 -0.608309 0.537953 + outer loop + vertex -866.171 258.152 48.2561 + vertex -863.931 255.938 48.1836 + vertex -863.77 256.298 48.7646 + endloop + endfacet + facet normal -0.583541 -0.608217 0.5381 + outer loop + vertex -867.934 260.125 48.5748 + vertex -866.171 258.152 48.2561 + vertex -863.77 256.298 48.7646 + endloop + endfacet + facet normal -0.63619 -0.610266 0.472057 + outer loop + vertex -869.964 262.27 48.6115 + vertex -867.934 260.125 48.5748 + vertex -869.41 262.178 49.2398 + endloop + endfacet + facet normal -0.658393 -0.563981 0.498442 + outer loop + vertex -872.239 264.998 48.6937 + vertex -869.964 262.27 48.6115 + vertex -869.41 262.178 49.2398 + endloop + endfacet + facet normal -0.674343 -0.577033 0.460754 + outer loop + vertex -874.226 267.423 48.8228 + vertex -872.239 264.998 48.6937 + vertex -874.358 268.074 49.4451 + endloop + endfacet + facet normal -0.709196 -0.556901 0.432323 + outer loop + vertex -875.186 268.686 48.874 + vertex -874.226 267.423 48.8228 + vertex -874.358 268.074 49.4451 + endloop + endfacet + facet normal -0.710622 -0.52156 0.47222 + outer loop + vertex -877.078 271.312 48.9272 + vertex -875.186 268.686 48.874 + vertex -874.358 268.074 49.4451 + endloop + endfacet + facet normal -0.735225 -0.536199 0.414651 + outer loop + vertex -879.073 274.118 49.0191 + vertex -877.078 271.312 48.9272 + vertex -879.103 274.657 49.6627 + endloop + endfacet + facet normal -0.769071 -0.507279 0.388843 + outer loop + vertex -880.636 276.47 48.9955 + vertex -879.073 274.118 49.0191 + vertex -879.103 274.657 49.6627 + endloop + endfacet + facet normal -0.768167 -0.504575 0.394111 + outer loop + vertex -881.939 278.659 49.2589 + vertex -880.636 276.47 48.9955 + vertex -879.103 274.657 49.6627 + endloop + endfacet + facet normal -0.776017 -0.480481 0.408576 + outer loop + vertex -883.427 281.05 49.244 + vertex -881.939 278.659 49.2589 + vertex -883.091 281.044 49.8751 + endloop + endfacet + facet normal -0.794352 -0.440096 0.418712 + outer loop + vertex -885.216 284.295 49.2613 + vertex -883.427 281.05 49.244 + vertex -883.091 281.044 49.8751 + endloop + endfacet + facet normal -0.786457 -0.429211 0.444142 + outer loop + vertex -886.924 287.491 49.3253 + vertex -885.216 284.295 49.2613 + vertex -886.902 288.053 49.9071 + endloop + endfacet + facet normal -0.82512 -0.390555 0.408219 + outer loop + vertex -888.213 290.159 49.2735 + vertex -886.924 287.491 49.3253 + vertex -886.902 288.053 49.9071 + endloop + endfacet + facet normal -0.826366 -0.39272 0.403598 + outer loop + vertex -889.233 292.528 49.4891 + vertex -888.213 290.159 49.2735 + vertex -886.902 288.053 49.9071 + endloop + endfacet + facet normal -0.828983 -0.358768 0.429036 + outer loop + vertex -890.406 295.179 49.4389 + vertex -889.233 292.528 49.4891 + vertex -889.988 294.855 49.9765 + endloop + endfacet + facet normal -0.831769 -0.307317 0.462295 + outer loop + vertex -891.721 298.703 49.4161 + vertex -890.406 295.179 49.4389 + vertex -889.988 294.855 49.9765 + endloop + endfacet + facet normal -0.866184 -0.313263 0.389348 + outer loop + vertex -893.036 302.396 49.4625 + vertex -891.721 298.703 49.4161 + vertex -892.539 301.806 50.092 + endloop + endfacet + facet normal -0.861553 -0.258798 0.436749 + outer loop + vertex -894.159 306.188 49.4929 + vertex -893.036 302.396 49.4625 + vertex -892.539 301.806 50.092 + endloop + endfacet + facet normal -0.853174 -0.255511 0.454762 + outer loop + vertex -895.07 309.363 49.5679 + vertex -894.159 306.188 49.4929 + vertex -894.809 309.568 50.173 + endloop + endfacet + facet normal -0.867966 -0.215309 0.447523 + outer loop + vertex -895.467 310.981 49.5775 + vertex -895.07 309.363 49.5679 + vertex -894.809 309.568 50.173 + endloop + endfacet + facet normal -0.826529 -0.156772 0.540622 + outer loop + vertex -896.128 314.313 49.5331 + vertex -895.467 310.981 49.5775 + vertex -894.809 309.568 50.173 + endloop + endfacet + facet normal -0.915227 -0.173434 0.363703 + outer loop + vertex -896.844 318.103 49.5374 + vertex -896.128 314.313 49.5331 + vertex -896.453 317.459 50.2138 + endloop + endfacet + facet normal -0.903907 -0.116205 0.411642 + outer loop + vertex -897.363 322.028 49.506 + vertex -896.844 318.103 49.5374 + vertex -896.453 317.459 50.2138 + endloop + endfacet + facet normal -0.945101 -0.107208 0.308692 + outer loop + vertex -897.789 325.856 49.5307 + vertex -897.363 322.028 49.506 + vertex -897.486 325.124 50.205 + endloop + endfacet + facet normal -0.933377 -0.0609078 0.353692 + outer loop + vertex -898.041 329.769 49.5393 + vertex -897.789 325.856 49.5307 + vertex -897.486 325.124 50.205 + endloop + endfacet + facet normal -0.95742 -0.0515421 0.28406 + outer loop + vertex -898.215 333.288 49.5919 + vertex -898.041 329.769 49.5393 + vertex -897.984 332.47 50.2231 + endloop + endfacet + facet normal -0.946642 -0.019461 0.321699 + outer loop + vertex -898.242 336 49.676 + vertex -898.215 333.288 49.5919 + vertex -897.984 332.47 50.2231 + endloop + endfacet + facet normal -0.965576 0.00948824 0.259947 + outer loop + vertex -898.255 339.813 49.4908 + vertex -898.242 336 49.676 + vertex -898.051 339.745 50.2517 + endloop + endfacet + facet normal -0.96508 0.0225815 0.260981 + outer loop + vertex -898.114 343.771 49.6702 + vertex -898.255 339.813 49.4908 + vertex -898.051 339.745 50.2517 + endloop + endfacet + facet normal -0.965897 0.0509678 0.25386 + outer loop + vertex -897.936 348.024 49.4913 + vertex -898.114 343.771 49.6702 + vertex -897.757 347.575 50.2642 + endloop + endfacet + facet normal -0.962626 0.0670005 0.262416 + outer loop + vertex -897.617 351.887 49.6746 + vertex -897.936 348.024 49.4913 + vertex -897.757 347.575 50.2642 + endloop + endfacet + facet normal -0.966571 0.0917959 0.239402 + outer loop + vertex -897.247 356.225 49.5053 + vertex -897.617 351.887 49.6746 + vertex -897.129 355.471 50.2702 + endloop + endfacet + facet normal -0.963244 0.101688 0.248639 + outer loop + vertex -896.836 359.64 49.704 + vertex -897.247 356.225 49.5053 + vertex -897.129 355.471 50.2702 + endloop + endfacet + facet normal -0.95723 0.116617 0.264785 + outer loop + vertex -896.504 362.527 49.6314 + vertex -896.836 359.64 49.704 + vertex -896.277 362.895 50.2879 + endloop + endfacet + facet normal -0.957593 0.13842 0.252696 + outer loop + vertex -895.962 366.345 49.5946 + vertex -896.504 362.527 49.6314 + vertex -896.277 362.895 50.2879 + endloop + endfacet + facet normal -0.960007 0.14329 0.24053 + outer loop + vertex -895.363 370.318 49.6163 + vertex -895.962 366.345 49.5946 + vertex -895.17 370.46 50.3037 + endloop + endfacet + facet normal -0.957781 0.165016 0.235424 + outer loop + vertex -894.662 374.377 49.6227 + vertex -895.363 370.318 49.6163 + vertex -895.17 370.46 50.3037 + endloop + endfacet + facet normal -0.956048 0.170579 0.238485 + outer loop + vertex -893.947 378.312 49.6778 + vertex -894.662 374.377 49.6227 + vertex -893.77 378.351 50.3593 + endloop + endfacet + facet normal -0.952665 0.191135 0.236424 + outer loop + vertex -893.119 382.441 49.6752 + vertex -893.947 378.312 49.6778 + vertex -893.77 378.351 50.3593 + endloop + endfacet + facet normal -0.949799 0.19419 0.2453 + outer loop + vertex -892.339 386.206 49.7135 + vertex -893.119 382.441 49.6752 + vertex -892.06 386.834 50.2956 + endloop + endfacet + facet normal -0.950686 0.212973 0.225473 + outer loop + vertex -891.658 389.345 49.6189 + vertex -892.339 386.206 49.7135 + vertex -892.06 386.834 50.2956 + endloop + endfacet + facet normal -0.951416 0.212402 0.222918 + outer loop + vertex -890.998 392.102 49.8104 + vertex -891.658 389.345 49.6189 + vertex -892.06 386.834 50.2956 + endloop + endfacet + facet normal -0.944769 0.233492 0.229984 + outer loop + vertex -889.405 398.882 49.639 + vertex -890.314 395.126 49.7174 + vertex -890.32 394.556 50.2727 + endloop + endfacet + facet normal -0.945902 0.176122 -0.272489 + outer loop + vertex -898.639 379.369 292.917 + vertex -897.893 383.378 292.922 + vertex -897.966 380.506 291.318 + endloop + endfacet + facet normal -0.947778 0.153467 -0.279579 + outer loop + vertex -899.948 371.435 292.908 + vertex -899.287 375.516 292.908 + vertex -899.258 372.745 291.289 + endloop + endfacet + facet normal -0.94592 0.131547 -0.296532 + outer loop + vertex -900.46 367.704 292.888 + vertex -899.948 371.435 292.908 + vertex -899.258 372.745 291.289 + endloop + endfacet + facet normal -0.949366 0.125209 -0.288145 + outer loop + vertex -900.989 363.699 292.891 + vertex -900.46 367.704 292.888 + vertex -900.323 365.06 291.286 + endloop + endfacet + facet normal -0.946098 0.100229 -0.307981 + outer loop + vertex -901.383 359.952 292.881 + vertex -900.989 363.699 292.891 + vertex -900.323 365.06 291.286 + endloop + endfacet + facet normal -0.949566 0.0925288 -0.299604 + outer loop + vertex -901.783 355.913 292.9 + vertex -901.383 359.952 292.881 + vertex -901.139 357.349 291.304 + endloop + endfacet + facet normal -0.944078 0.0634367 -0.323562 + outer loop + vertex -902.042 352.061 292.903 + vertex -901.783 355.913 292.9 + vertex -901.139 357.349 291.304 + endloop + endfacet + facet normal -0.949738 0.0550412 -0.308168 + outer loop + vertex -902.294 347.906 292.936 + vertex -902.042 352.061 292.903 + vertex -901.678 349.523 291.326 + endloop + endfacet + facet normal -0.941904 0.0254209 -0.334918 + outer loop + vertex -902.397 343.924 292.924 + vertex -902.294 347.906 292.936 + vertex -901.678 349.523 291.326 + endloop + endfacet + facet normal -0.948808 0.0179866 -0.315342 + outer loop + vertex -902.463 340.036 292.899 + vertex -902.397 343.924 292.924 + vertex -901.905 341.893 291.326 + endloop + endfacet + facet normal -0.93878 -0.00962215 -0.344384 + outer loop + vertex -902.368 337.33 292.715 + vertex -902.463 340.036 292.899 + vertex -901.905 341.893 291.326 + endloop + endfacet + facet normal -0.944897 -0.036581 -0.325319 + outer loop + vertex -902.372 333.802 293.124 + vertex -902.368 337.33 292.715 + vertex -901.783 334.628 291.322 + endloop + endfacet + facet normal -0.942142 -0.0514637 -0.33124 + outer loop + vertex -902.025 329.877 292.748 + vertex -902.372 333.802 293.124 + vertex -901.783 334.628 291.322 + endloop + endfacet + facet normal -0.93623 -0.0902017 -0.339614 + outer loop + vertex -901.785 326.003 293.115 + vertex -902.025 329.877 292.748 + vertex -901.229 327.087 291.295 + endloop + endfacet + facet normal -0.930044 -0.111176 -0.350226 + outer loop + vertex -901.172 322.158 292.707 + vertex -901.785 326.003 293.115 + vertex -901.229 327.087 291.295 + endloop + endfacet + facet normal -0.921753 -0.152934 -0.356345 + outer loop + vertex -900.643 318.156 293.058 + vertex -901.172 322.158 292.707 + vertex -900.181 319.453 291.306 + endloop + endfacet + facet normal -0.913645 -0.17201 -0.368328 + outer loop + vertex -899.826 314.633 292.677 + vertex -900.643 318.156 293.058 + vertex -900.181 319.453 291.306 + endloop + endfacet + facet normal -0.889773 -0.202189 -0.409175 + outer loop + vertex -899.359 312.095 292.915 + vertex -899.826 314.633 292.677 + vertex -898.613 311.668 291.502 + endloop + endfacet + facet normal -0.885782 -0.245055 -0.394129 + outer loop + vertex -898.798 309.702 293.141 + vertex -899.359 312.095 292.915 + vertex -898.613 311.668 291.502 + endloop + endfacet + facet normal -0.881563 -0.250465 -0.400143 + outer loop + vertex -897.686 306.39 292.763 + vertex -898.798 309.702 293.141 + vertex -898.613 311.668 291.502 + endloop + endfacet + facet normal -0.880757 -0.290162 -0.374263 + outer loop + vertex -896.501 302.341 293.116 + vertex -897.686 306.39 292.763 + vertex -896.345 304.139 291.353 + endloop + endfacet + facet normal -0.868499 -0.306354 -0.389688 + outer loop + vertex -895.178 299.092 292.721 + vertex -896.501 302.341 293.116 + vertex -896.345 304.139 291.353 + endloop + endfacet + facet normal -0.850979 -0.340309 -0.40003 + outer loop + vertex -894.173 296.352 292.913 + vertex -895.178 299.092 292.721 + vertex -893.78 297.173 291.379 + endloop + endfacet + facet normal -0.829752 -0.375169 -0.413232 + outer loop + vertex -892.704 293.038 292.973 + vertex -894.173 296.352 292.913 + vertex -893.78 297.173 291.379 + endloop + endfacet + facet normal -0.823555 -0.376558 -0.424219 + outer loop + vertex -891.25 289.806 293.018 + vertex -892.704 293.038 292.973 + vertex -890.62 290.026 291.601 + endloop + endfacet + facet normal -0.806679 -0.413319 -0.422418 + outer loop + vertex -890.493 288.326 293.021 + vertex -891.25 289.806 293.018 + vertex -890.62 290.026 291.601 + endloop + endfacet + facet normal -0.775114 -0.438265 -0.455106 + outer loop + vertex -888.961 285.611 293.028 + vertex -890.493 288.326 293.021 + vertex -890.62 290.026 291.601 + endloop + endfacet + facet normal -0.793549 -0.453804 -0.405391 + outer loop + vertex -887.024 282.189 293.066 + vertex -888.961 285.611 293.028 + vertex -886.854 283.301 291.488 + endloop + endfacet + facet normal -0.762385 -0.487387 -0.425703 + outer loop + vertex -884.979 278.931 293.133 + vertex -887.024 282.189 293.066 + vertex -886.854 283.301 291.488 + endloop + endfacet + facet normal -0.756327 -0.492454 -0.430649 + outer loop + vertex -883.096 275.975 293.206 + vertex -884.979 278.931 293.133 + vertex -882.579 276.389 291.825 + endloop + endfacet + facet normal -0.734869 -0.523016 -0.431765 + outer loop + vertex -882.137 274.588 293.254 + vertex -883.096 275.975 293.206 + vertex -882.579 276.389 291.825 + endloop + endfacet + facet normal -0.703202 -0.53981 -0.462723 + outer loop + vertex -880.23 272.014 293.36 + vertex -882.137 274.588 293.254 + vertex -882.579 276.389 291.825 + endloop + endfacet + facet normal -0.716615 -0.547371 -0.432259 + outer loop + vertex -878.208 269.271 293.48 + vertex -880.23 272.014 293.36 + vertex -877.856 269.93 292.063 + endloop + endfacet + facet normal -0.692762 -0.572797 -0.438161 + outer loop + vertex -877.193 268.001 293.536 + vertex -878.208 269.271 293.48 + vertex -877.856 269.93 292.063 + endloop + endfacet + facet normal -0.659957 -0.585982 -0.470193 + outer loop + vertex -875.136 265.618 293.618 + vertex -877.193 268.001 293.536 + vertex -877.856 269.93 292.063 + endloop + endfacet + facet normal -0.670196 -0.600405 -0.436292 + outer loop + vertex -872.723 262.866 293.7 + vertex -875.136 265.618 293.618 + vertex -872.938 264.271 292.095 + endloop + endfacet + facet normal -0.628273 -0.624936 -0.463388 + outer loop + vertex -870.663 260.823 293.661 + vertex -872.723 262.866 293.7 + vertex -872.938 264.271 292.095 + endloop + endfacet + facet normal -0.609977 -0.640122 -0.467088 + outer loop + vertex -868.617 258.414 294.292 + vertex -870.663 260.823 293.661 + vertex -866.92 257.937 292.728 + endloop + endfacet + facet normal -0.608856 -0.642626 -0.465109 + outer loop + vertex -866.477 256.396 294.278 + vertex -868.617 258.414 294.292 + vertex -866.92 257.937 292.728 + endloop + endfacet + facet normal -0.564065 -0.660435 -0.495637 + outer loop + vertex -864.065 254.22 294.432 + vertex -866.477 256.396 294.278 + vertex -866.92 257.937 292.728 + endloop + endfacet + facet normal -0.538195 -0.654892 -0.530531 + outer loop + vertex -861.534 251.971 294.641 + vertex -864.065 254.22 294.432 + vertex -861.733 252.631 294.028 + endloop + endfacet + facet normal -0.485353 -0.669058 -0.562845 + outer loop + vertex -859.387 250.19 294.906 + vertex -861.534 251.971 294.641 + vertex -861.733 252.631 294.028 + endloop + endfacet + facet normal -0.480545 -0.698765 -0.529909 + outer loop + vertex -856.224 247.63 295.414 + vertex -859.387 250.19 294.906 + vertex -857.839 249.54 294.359 + endloop + endfacet + facet normal -0.439104 -0.702552 -0.560008 + outer loop + vertex -853.36 245.421 295.94 + vertex -856.224 247.63 295.414 + vertex -854.621 246.762 295.246 + endloop + endfacet + facet normal -0.376074 -0.691134 -0.617173 + outer loop + vertex -851.034 243.773 296.368 + vertex -853.36 245.421 295.94 + vertex -852.452 245.275 295.55 + endloop + endfacet + facet normal -0.303245 -0.6866 -0.660775 + outer loop + vertex -848.286 242.207 296.733 + vertex -851.034 243.773 296.368 + vertex -850.545 244.199 295.701 + endloop + endfacet + facet normal -0.877609 0.38132 -0.290513 + outer loop + vertex -874.575 465.405 294.694 + vertex -873.706 467.09 294.282 + vertex -873.436 466.101 292.168 + endloop + endfacet + facet normal -0.880112 0.372788 -0.293995 + outer loop + vertex -875.309 463.089 293.955 + vertex -874.575 465.405 294.694 + vertex -873.436 466.101 292.168 + endloop + endfacet + facet normal -0.444854 -0.695364 -0.564423 + outer loop + vertex -854.78 247.448 294.526 + vertex -854.621 246.762 295.246 + vertex -857.839 249.54 294.359 + endloop + endfacet + facet normal -0.378698 -0.680585 -0.627209 + outer loop + vertex -854.621 246.762 295.246 + vertex -852.452 245.275 295.55 + vertex -853.36 245.421 295.94 + endloop + endfacet + facet normal -0.325542 -0.670416 -0.666757 + outer loop + vertex -852.452 245.275 295.55 + vertex -850.545 244.199 295.701 + vertex -851.034 243.773 296.368 + endloop + endfacet + facet normal -0.314478 -0.703286 -0.637567 + outer loop + vertex -850.545 244.199 295.701 + vertex -850.953 245.269 294.722 + vertex -849.804 244.462 295.045 + endloop + endfacet + facet normal -0.23795 -0.746241 -0.621695 + outer loop + vertex -850.216 246.201 293.25 + vertex -851.019 248.709 290.547 + vertex -850.063 246.709 292.582 + endloop + endfacet + facet normal -0.290014 -0.71976 -0.630743 + outer loop + vertex -849.804 244.462 295.045 + vertex -850.216 246.201 293.25 + vertex -849.156 244.251 294.988 + endloop + endfacet + facet normal -0.481014 -0.667068 -0.568898 + outer loop + vertex -861.733 252.631 294.028 + vertex -857.839 249.54 294.359 + vertex -859.387 250.19 294.906 + endloop + endfacet + facet normal -0.538652 -0.656043 -0.528641 + outer loop + vertex -866.92 257.937 292.728 + vertex -861.733 252.631 294.028 + vertex -864.065 254.22 294.432 + endloop + endfacet + facet normal -0.604468 -0.623802 -0.495469 + outer loop + vertex -872.938 264.271 292.095 + vertex -866.92 257.937 292.728 + vertex -870.663 260.823 293.661 + endloop + endfacet + facet normal -0.672266 -0.586905 -0.451221 + outer loop + vertex -877.856 269.93 292.063 + vertex -872.938 264.271 292.095 + vertex -875.136 265.618 293.618 + endloop + endfacet + facet normal -0.715808 -0.539695 -0.443113 + outer loop + vertex -882.579 276.389 291.825 + vertex -877.856 269.93 292.063 + vertex -880.23 272.014 293.36 + endloop + endfacet + facet normal -0.755434 -0.488524 -0.43665 + outer loop + vertex -886.854 283.301 291.488 + vertex -882.579 276.389 291.825 + vertex -884.979 278.931 293.133 + endloop + endfacet + facet normal -0.79117 -0.43587 -0.429032 + outer loop + vertex -890.62 290.026 291.601 + vertex -886.854 283.301 291.488 + vertex -888.961 285.611 293.028 + endloop + endfacet + facet normal -0.823859 -0.377365 -0.422909 + outer loop + vertex -893.78 297.173 291.379 + vertex -890.62 290.026 291.601 + vertex -892.704 293.038 292.973 + endloop + endfacet + facet normal -0.845198 -0.312799 -0.433356 + outer loop + vertex -896.345 304.139 291.353 + vertex -893.78 297.173 291.379 + vertex -895.178 299.092 292.721 + endloop + endfacet + facet normal -0.870196 -0.25377 -0.422327 + outer loop + vertex -898.613 311.668 291.502 + vertex -896.345 304.139 291.353 + vertex -897.686 306.39 292.763 + endloop + endfacet + facet normal -0.880714 -0.18842 -0.434559 + outer loop + vertex -900.181 319.453 291.306 + vertex -898.613 311.668 291.502 + vertex -899.826 314.633 292.677 + endloop + endfacet + facet normal -0.907887 -0.125196 -0.400083 + outer loop + vertex -901.229 327.087 291.295 + vertex -900.181 319.453 291.306 + vertex -901.172 322.158 292.707 + endloop + endfacet + facet normal -0.923371 -0.0664835 -0.378108 + outer loop + vertex -901.783 334.628 291.322 + vertex -901.229 327.087 291.295 + vertex -902.025 329.877 292.748 + endloop + endfacet + facet normal -0.93237 -0.0153848 -0.361179 + outer loop + vertex -901.905 341.893 291.326 + vertex -901.783 334.628 291.322 + vertex -902.368 337.33 292.715 + endloop + endfacet + facet normal -0.944651 0.0280699 -0.326873 + outer loop + vertex -901.678 349.523 291.326 + vertex -901.905 341.893 291.326 + vertex -902.397 343.924 292.924 + endloop + endfacet + facet normal -0.944693 0.0641274 -0.321624 + outer loop + vertex -901.139 357.349 291.304 + vertex -901.678 349.523 291.326 + vertex -902.042 352.061 292.903 + endloop + endfacet + facet normal -0.94544 0.0993769 -0.310271 + outer loop + vertex -900.323 365.06 291.286 + vertex -901.139 357.349 291.304 + vertex -901.383 359.952 292.881 + endloop + endfacet + facet normal -0.945638 0.131138 -0.297609 + outer loop + vertex -899.258 372.745 291.289 + vertex -900.323 365.06 291.286 + vertex -900.46 367.704 292.888 + endloop + endfacet + facet normal -0.883127 0.342587 -0.3205 + outer loop + vertex -875.339 460.784 291.448 + vertex -877.683 454.466 291.154 + vertex -877.277 457.104 292.855 + endloop + endfacet + facet normal -0.87816 0.357287 -0.318089 + outer loop + vertex -873.436 466.101 292.168 + vertex -875.339 460.784 291.448 + vertex -875.309 463.089 293.955 + endloop + endfacet + facet normal -0.371103 -0.778418 -0.506308 + outer loop + vertex -851.817 251.049 287.828 + vertex -852.375 253.032 285.188 + vertex -851.25 250.349 288.488 + endloop + endfacet + facet normal -0.270966 -0.767592 -0.580845 + outer loop + vertex -851.019 248.709 290.547 + vertex -851.817 251.049 287.828 + vertex -851.25 250.349 288.488 + endloop + endfacet + facet normal -0.176276 -0.850545 -0.495479 + outer loop + vertex -853.051 255.392 281.764 + vertex -853.562 257.323 278.631 + vertex -852.995 256.171 280.408 + endloop + endfacet + facet normal -0.221353 -0.864 -0.452225 + outer loop + vertex -853.562 257.323 278.631 + vertex -854.015 257.295 278.908 + vertex -854.386 259.127 275.588 + endloop + endfacet + facet normal -0.179122 -0.826145 -0.534228 + outer loop + vertex -852.375 253.032 285.188 + vertex -853.051 255.392 281.764 + vertex -852.29 253.649 284.205 + endloop + endfacet + facet normal -0.232712 -0.877595 -0.419132 + outer loop + vertex -854.386 259.127 275.588 + vertex -854.667 260.985 271.854 + vertex -853.698 258.905 275.671 + endloop + endfacet + facet normal -0.161001 -0.90253 -0.399397 + outer loop + vertex -854.667 260.985 271.854 + vertex -854.888 262.849 267.73 + vertex -854.179 261.427 270.658 + endloop + endfacet + facet normal -0.140577 -0.919599 -0.366847 + outer loop + vertex -854.888 262.849 267.73 + vertex -855.052 264.457 263.764 + vertex -854.427 263.324 266.365 + endloop + endfacet + facet normal -0.150248 -0.925539 -0.347569 + outer loop + vertex -855.052 264.457 263.764 + vertex -855.953 266.656 258.297 + vertex -854.668 265.324 261.287 + endloop + endfacet + facet normal -0.164408 -0.940301 -0.298 + outer loop + vertex -855.953 266.656 258.297 + vertex -855.94 269.223 250.19 + vertex -854.948 267.358 255.527 + endloop + endfacet + facet normal -0.144618 -0.954444 -0.261002 + outer loop + vertex -855.94 269.223 250.19 + vertex -855.962 271.388 242.285 + vertex -854.9 270.195 246.059 + endloop + endfacet + facet normal -0.151042 -0.963646 -0.220394 + outer loop + vertex -855.962 271.388 242.285 + vertex -855.59 273.106 234.519 + vertex -854.883 271.774 239.856 + endloop + endfacet + facet normal -0.113435 -0.974897 -0.191595 + outer loop + vertex -855.59 273.106 234.519 + vertex -855.347 274.68 226.365 + vertex -854.622 273.829 230.264 + endloop + endfacet + facet normal -0.128127 -0.978183 -0.163526 + outer loop + vertex -855.347 274.68 226.365 + vertex -854.965 275.975 218.317 + vertex -854.426 274.988 223.801 + endloop + endfacet + facet normal -0.138162 -0.981351 -0.133648 + outer loop + vertex -854.965 275.975 218.317 + vertex -854.74 277.084 209.944 + vertex -854.256 276.331 214.976 + endloop + endfacet + facet normal -0.13881 -0.984602 -0.10626 + outer loop + vertex -854.74 277.084 209.944 + vertex -854.583 277.954 201.681 + vertex -854.01 277.383 206.215 + endloop + endfacet + facet normal -0.152385 -0.985041 -0.0804589 + outer loop + vertex -854.583 277.954 201.681 + vertex -854.579 278.582 193.987 + vertex -853.893 278.135 198.149 + endloop + endfacet + facet normal -0.163762 -0.984938 -0.0554972 + outer loop + vertex -854.579 278.582 193.987 + vertex -854.413 278.978 186.467 + vertex -853.839 278.563 192.138 + endloop + endfacet + facet normal -0.146039 -0.988732 -0.0328745 + outer loop + vertex -854.413 278.978 186.467 + vertex -854.365 279.242 178.295 + vertex -853.821 278.995 183.319 + endloop + endfacet + facet normal -0.149057 -0.988805 -0.006889 + outer loop + vertex -854.365 279.242 178.295 + vertex -854.347 279.296 170.164 + vertex -853.785 279.177 175.091 + endloop + endfacet + facet normal -0.14837 -0.988783 0.0171747 + outer loop + vertex -854.347 279.296 170.164 + vertex -854.459 279.178 162.392 + vertex -853.728 279.139 166.453 + endloop + endfacet + facet normal -0.163807 -0.985561 0.0428584 + outer loop + vertex -854.459 279.178 162.392 + vertex -854.397 278.845 154.976 + vertex -853.744 278.979 160.555 + endloop + endfacet + facet normal -0.15122 -0.986316 0.0656752 + outer loop + vertex -854.397 278.845 154.976 + vertex -854.467 278.311 146.787 + vertex -853.855 278.554 151.85 + endloop + endfacet + facet normal -0.148085 -0.984803 0.0907443 + outer loop + vertex -854.467 278.311 146.787 + vertex -854.572 277.566 138.533 + vertex -853.86 277.876 143.066 + endloop + endfacet + facet normal -0.169131 -0.978688 0.116467 + outer loop + vertex -854.572 277.566 138.533 + vertex -854.804 276.689 130.825 + vertex -853.968 277.035 134.949 + endloop + endfacet + facet normal -0.179451 -0.973105 0.144445 + outer loop + vertex -854.804 276.689 130.825 + vertex -854.812 275.606 123.522 + vertex -854.079 276.284 128.999 + endloop + endfacet + facet normal -0.141657 -0.975137 0.170412 + outer loop + vertex -854.812 275.606 123.522 + vertex -855.008 274.318 115.99 + vertex -854.303 274.995 120.45 + endloop + endfacet + facet normal -0.129791 -0.971631 0.197707 + outer loop + vertex -855.008 274.318 115.99 + vertex -855.162 272.802 108.438 + vertex -854.377 273.728 113.504 + endloop + endfacet + facet normal -0.150962 -0.963442 0.221336 + outer loop + vertex -855.162 272.802 108.438 + vertex -855.625 271.122 100.808 + vertex -854.577 271.705 104.063 + endloop + endfacet + facet normal -0.170702 -0.94976 0.262331 + outer loop + vertex -855.625 271.122 100.808 + vertex -855.551 268.989 93.1357 + vertex -854.645 270.297 98.4601 + endloop + endfacet + facet normal -0.166216 -0.939127 0.300687 + outer loop + vertex -855.551 268.989 93.1357 + vertex -855.507 266.316 84.8106 + vertex -854.535 267.332 88.5223 + endloop + endfacet + facet normal -0.163534 -0.923112 0.348024 + outer loop + vertex -855.507 266.316 84.8106 + vertex -854.635 263.993 79.0583 + vertex -854.2 265.254 82.6085 + endloop + endfacet + facet normal -0.128819 -0.917596 0.376063 + outer loop + vertex -854.635 263.993 79.0583 + vertex -854.178 262.067 74.5164 + vertex -853.863 263.202 77.394 + endloop + endfacet + facet normal -0.154176 -0.900715 0.406132 + outer loop + vertex -854.178 262.067 74.5164 + vertex -853.763 260.104 70.319 + vertex -853.481 261.229 72.922 + endloop + endfacet + facet normal -0.213541 -0.878679 0.426994 + outer loop + vertex -853.763 260.104 70.319 + vertex -853.357 258.151 66.5029 + vertex -852.864 258.683 67.8459 + endloop + endfacet + facet normal -0.283396 -0.852541 0.439159 + outer loop + vertex -853.357 258.151 66.5029 + vertex -853.077 256.56 63.5958 + vertex -852.55 256.619 64.0505 + endloop + endfacet + facet normal -0.109177 -0.830619 0.546033 + outer loop + vertex -851.83 254.483 60.6474 + vertex -851.047 252.089 57.1622 + vertex -851.303 253.67 59.5155 + endloop + endfacet + facet normal -0.158429 -0.851068 0.500584 + outer loop + vertex -852.55 256.619 64.0505 + vertex -851.83 254.483 60.6474 + vertex -852.065 256.046 63.2291 + endloop + endfacet + facet normal -0.210899 -0.7812 0.587579 + outer loop + vertex -850.186 249.637 53.9261 + vertex -849.327 247.327 51.1635 + vertex -849.567 248.772 52.9978 + endloop + endfacet + facet normal -0.151323 -0.806777 0.57115 + outer loop + vertex -851.047 252.089 57.1622 + vertex -850.186 249.637 53.9261 + vertex -850.442 251.193 56.0564 + endloop + endfacet + facet normal -0.547612 -0.752905 0.365041 + outer loop + vertex -856.035 251.768 52.111 + vertex -858.893 254.077 52.5865 + vertex -858.445 252.433 49.8671 + endloop + endfacet + facet normal -0.482941 -0.757272 0.439666 + outer loop + vertex -853.64 250.462 52.4915 + vertex -856.035 251.768 52.111 + vertex -854.068 249.545 50.4432 + endloop + endfacet + facet normal -0.613513 -0.716444 0.332131 + outer loop + vertex -858.893 254.077 52.5865 + vertex -862.57 257.32 52.7893 + vertex -858.445 252.433 49.8671 + endloop + endfacet + facet normal -0.651229 -0.674848 0.347104 + outer loop + vertex -862.57 257.32 52.7893 + vertex -867.685 262.659 53.5723 + vertex -865.719 259.187 50.512 + endloop + endfacet + facet normal -0.69998 -0.630567 0.33528 + outer loop + vertex -867.685 262.659 53.5723 + vertex -872.72 268.52 54.0838 + vertex -871.242 265.219 50.9607 + endloop + endfacet + facet normal -0.752431 -0.579863 0.312422 + outer loop + vertex -872.72 268.52 54.0838 + vertex -877.269 274.58 54.3741 + vertex -876.077 271.352 51.2544 + endloop + endfacet + facet normal -0.797675 -0.522707 0.300818 + outer loop + vertex -877.269 274.58 54.3741 + vertex -881.383 280.908 54.4614 + vertex -880.421 277.684 51.4117 + endloop + endfacet + facet normal -0.83609 -0.459975 0.298958 + outer loop + vertex -881.383 280.908 54.4614 + vertex -885.188 287.786 54.4036 + vertex -884.33 284.334 51.4926 + endloop + endfacet + facet normal -0.864883 -0.392031 0.31351 + outer loop + vertex -885.188 287.786 54.4036 + vertex -888.995 295.973 54.1392 + vertex -887.873 291.314 51.4074 + endloop + endfacet + facet normal -0.91274 -0.343844 0.22063 + outer loop + vertex -888.995 295.973 54.1392 + vertex -891.137 302.456 55.3809 + vertex -892.604 304.226 52.0705 + endloop + endfacet + facet normal -0.924104 -0.280472 0.259553 + outer loop + vertex -891.137 302.456 55.3809 + vertex -893.256 309.012 54.9205 + vertex -892.604 304.226 52.0705 + endloop + endfacet + facet normal -0.938843 -0.216393 0.267857 + outer loop + vertex -893.256 309.012 54.9205 + vertex -895.06 316.643 54.7616 + vertex -895.055 313.028 51.8587 + endloop + endfacet + facet normal -0.954081 -0.146324 0.261378 + outer loop + vertex -895.06 316.643 54.7616 + vertex -896.23 324.24 54.7432 + vertex -896.522 320.884 51.7993 + endloop + endfacet + facet normal -0.323913 -0.718919 0.615009 + outer loop + vertex -848.516 245.293 48.9968 + vertex -847.961 243.738 47.4709 + vertex -847.794 244.315 48.2335 + endloop + endfacet + facet normal -0.381531 -0.687758 0.617595 + outer loop + vertex -847.961 243.738 47.4709 + vertex -849.034 244.717 47.8985 + vertex -848.604 243.752 47.089 + endloop + endfacet + facet normal -0.267066 -0.750527 0.60447 + outer loop + vertex -849.327 247.327 51.1635 + vertex -848.516 245.293 48.9968 + vertex -848.682 246.477 50.3927 + endloop + endfacet + facet normal -0.535979 -0.726689 0.42971 + outer loop + vertex -853.604 248.264 48.8548 + vertex -854.068 249.545 50.4432 + vertex -858.445 252.433 49.8671 + endloop + endfacet + facet normal -0.431369 -0.669828 0.60436 + outer loop + vertex -849.623 244.2 46.9272 + vertex -852.791 246.571 47.2939 + vertex -851.539 245.184 46.6509 + endloop + endfacet + facet normal 0.509277 0.633658 -0.582335 + outer loop + vertex -848.604 243.752 47.089 + vertex -848.504 243.447 46.8448 + vertex -848.646 243.404 46.6731 + endloop + endfacet + facet normal -0.440043 -0.713674 0.545006 + outer loop + vertex -848.504 243.447 46.8448 + vertex -849.623 244.2 46.9272 + vertex -848.646 243.404 46.6731 + endloop + endfacet + facet normal -0.489414 -0.681417 0.544191 + outer loop + vertex -852.791 246.571 47.2939 + vertex -857.445 250.53 48.0655 + vertex -855.884 248.7 47.1782 + endloop + endfacet + facet normal -0.636063 -0.713125 0.294747 + outer loop + vertex -865.719 259.187 50.512 + vertex -858.445 252.433 49.8671 + vertex -862.57 257.32 52.7893 + endloop + endfacet + facet normal -0.52454 -0.642855 0.558207 + outer loop + vertex -857.445 250.53 48.0655 + vertex -863.77 256.298 48.7646 + vertex -860.855 253.095 47.8154 + endloop + endfacet + facet normal -0.69239 -0.656351 0.299666 + outer loop + vertex -871.242 265.219 50.9607 + vertex -865.719 259.187 50.512 + vertex -867.685 262.659 53.5723 + endloop + endfacet + facet normal -0.572022 -0.594336 0.565292 + outer loop + vertex -863.77 256.298 48.7646 + vertex -869.41 262.178 49.2398 + vertex -867.934 260.125 48.5748 + endloop + endfacet + facet normal -0.746525 -0.602097 0.283162 + outer loop + vertex -876.077 271.352 51.2544 + vertex -871.242 265.219 50.9607 + vertex -872.72 268.52 54.0838 + endloop + endfacet + facet normal -0.664857 -0.574552 0.477341 + outer loop + vertex -869.41 262.178 49.2398 + vertex -874.358 268.074 49.4451 + vertex -872.239 264.998 48.6937 + endloop + endfacet + facet normal -0.791779 -0.549739 0.266218 + outer loop + vertex -880.421 277.684 51.4117 + vertex -876.077 271.352 51.2544 + vertex -877.269 274.58 54.3741 + endloop + endfacet + facet normal -0.719416 -0.533303 0.445005 + outer loop + vertex -874.358 268.074 49.4451 + vertex -879.103 274.657 49.6627 + vertex -877.078 271.312 48.9272 + endloop + endfacet + facet normal -0.831629 -0.491966 0.257609 + outer loop + vertex -884.33 284.334 51.4926 + vertex -880.421 277.684 51.4117 + vertex -881.383 280.908 54.4614 + endloop + endfacet + facet normal -0.743225 -0.479595 0.466482 + outer loop + vertex -879.103 274.657 49.6627 + vertex -883.091 281.044 49.8751 + vertex -881.939 278.659 49.2589 + endloop + endfacet + facet normal -0.862049 -0.434437 0.261028 + outer loop + vertex -887.873 291.314 51.4074 + vertex -884.33 284.334 51.4926 + vertex -885.188 287.786 54.4036 + endloop + endfacet + facet normal -0.785413 -0.429081 0.446112 + outer loop + vertex -883.091 281.044 49.8751 + vertex -886.902 288.053 49.9071 + vertex -885.216 284.295 49.2613 + endloop + endfacet + facet normal -0.884752 -0.375144 0.276552 + outer loop + vertex -890.61 297.565 51.1328 + vertex -887.873 291.314 51.4074 + vertex -888.995 295.973 54.1392 + endloop + endfacet + facet normal -0.782615 -0.360207 0.507706 + outer loop + vertex -886.902 288.053 49.9071 + vertex -889.988 294.855 49.9765 + vertex -889.233 292.528 49.4891 + endloop + endfacet + facet normal -0.895893 -0.312667 0.315618 + outer loop + vertex -892.604 304.226 52.0705 + vertex -890.61 297.565 51.1328 + vertex -888.995 295.973 54.1392 + endloop + endfacet + facet normal -0.843692 -0.316908 0.433305 + outer loop + vertex -889.988 294.855 49.9765 + vertex -892.539 301.806 50.092 + vertex -891.721 298.703 49.4161 + endloop + endfacet + facet normal -0.941879 -0.257104 0.216242 + outer loop + vertex -895.055 313.028 51.8587 + vertex -892.604 304.226 52.0705 + vertex -893.256 309.012 54.9205 + endloop + endfacet + facet normal -0.856074 -0.255021 0.449557 + outer loop + vertex -892.539 301.806 50.092 + vertex -894.809 309.568 50.173 + vertex -894.159 306.188 49.4929 + endloop + endfacet + facet normal -0.959362 -0.17748 0.219375 + outer loop + vertex -896.522 320.884 51.7993 + vertex -895.055 313.028 51.8587 + vertex -895.06 316.643 54.7616 + endloop + endfacet + facet normal -0.88012 -0.185647 0.436948 + outer loop + vertex -894.809 309.568 50.173 + vertex -896.453 317.459 50.2138 + vertex -896.128 314.313 49.5331 + endloop + endfacet + facet normal -0.970936 -0.104473 0.215333 + outer loop + vertex -897.335 328.462 51.811 + vertex -896.522 320.884 51.7993 + vertex -896.23 324.24 54.7432 + endloop + endfacet + facet normal -0.9154 -0.122879 0.383333 + outer loop + vertex -896.453 317.459 50.2138 + vertex -897.486 325.124 50.205 + vertex -897.363 322.028 49.506 + endloop + endfacet + facet normal -0.940348 -0.0645588 0.334032 + outer loop + vertex -897.486 325.124 50.205 + vertex -897.984 332.47 50.2231 + vertex -898.041 329.769 49.5393 + endloop + endfacet + facet normal -0.927437 -0.00997433 0.373847 + outer loop + vertex -897.984 332.47 50.2231 + vertex -898.051 339.745 50.2517 + vertex -898.242 336 49.676 + endloop + endfacet + facet normal -0.939063 0.0346898 0.341989 + outer loop + vertex -898.051 339.745 50.2517 + vertex -897.757 347.575 50.2642 + vertex -898.114 343.771 49.6702 + endloop + endfacet + facet normal -0.943354 0.0747 0.323269 + outer loop + vertex -897.757 347.575 50.2642 + vertex -897.129 355.471 50.2702 + vertex -897.617 351.887 49.6746 + endloop + endfacet + facet normal -0.946796 0.10794 0.303193 + outer loop + vertex -897.129 355.471 50.2702 + vertex -896.277 362.895 50.2879 + vertex -896.836 359.64 49.704 + endloop + endfacet + facet normal -0.955917 0.139419 0.258428 + outer loop + vertex -896.277 362.895 50.2879 + vertex -895.17 370.46 50.3037 + vertex -895.962 366.345 49.5946 + endloop + endfacet + facet normal -0.953063 0.167343 0.252325 + outer loop + vertex -895.17 370.46 50.3037 + vertex -893.77 378.351 50.3593 + vertex -894.662 374.377 49.6227 + endloop + endfacet + facet normal -0.948421 0.192981 0.251507 + outer loop + vertex -893.77 378.351 50.3593 + vertex -892.06 386.834 50.2956 + vertex -893.119 382.441 49.6752 + endloop + endfacet + facet normal -0.944027 0.213537 0.251425 + outer loop + vertex -892.06 386.834 50.2956 + vertex -890.32 394.556 50.2727 + vertex -890.998 392.102 49.8104 + endloop + endfacet + facet normal -0.947331 0.232593 0.220147 + outer loop + vertex -890.32 394.556 50.2727 + vertex -888.536 401.808 50.2862 + vertex -889.405 398.882 49.639 + endloop + endfacet + facet normal -0.320666 -0.696554 -0.641861 + outer loop + vertex -849.804 244.462 295.045 + vertex -848.286 242.207 296.733 + vertex -850.545 244.199 295.701 + endloop + endfacet + facet normal -0.224403 -0.863729 -0.451238 + outer loop + vertex -853.698 258.905 275.671 + vertex -853.562 257.323 278.631 + vertex -854.386 259.127 275.588 + endloop + endfacet + facet normal -0.279107 -0.85306 0.440895 + outer loop + vertex -852.55 256.619 64.0505 + vertex -852.864 258.683 67.8459 + vertex -853.357 258.151 66.5029 + endloop + endfacet + facet normal -0.380664 -0.689603 0.61607 + outer loop + vertex -848.646 243.404 46.6731 + vertex -847.961 243.738 47.4709 + vertex -848.604 243.752 47.089 + endloop + endfacet + facet normal -0.433493 -0.687866 -0.582172 + outer loop + vertex -856.224 247.63 295.414 + vertex -857.839 249.54 294.359 + vertex -854.621 246.762 295.246 + endloop + endfacet + facet normal -0.545992 -0.755255 0.362605 + outer loop + vertex -856.035 251.768 52.111 + vertex -858.445 252.433 49.8671 + vertex -854.068 249.545 50.4432 + endloop + endfacet + facet normal -0.371751 -0.851783 0.369143 + outer loop + vertex -610.235 96.8215 37.3726 + vertex -609.168 97.2123 39.3484 + vertex -609.933 97.045 38.1917 + endloop + endfacet + facet normal -0.220662 -0.975178 -0.0183639 + outer loop + vertex -608.639 103.309 302.52 + vertex -609.798 103.523 305.076 + vertex -610.079 103.596 304.574 + endloop + endfacet + facet normal -0.255927 -0.966066 -0.0348893 + outer loop + vertex -616.977 105.418 303.232 + vertex -615.811 105.064 304.481 + vertex -620.377 106.324 303.09 + endloop + endfacet + facet normal -0.268567 -0.96008 -0.0782194 + outer loop + vertex -620.377 106.324 303.09 + vertex -626.756 108.269 301.108 + vertex -622.431 107.042 301.321 + endloop + endfacet + facet normal -0.285613 -0.949979 -0.12635 + outer loop + vertex -626.756 108.269 301.108 + vertex -632.473 110.179 299.677 + vertex -628.485 108.97 299.751 + endloop + endfacet + facet normal -0.305858 -0.93468 -0.181173 + outer loop + vertex -632.473 110.179 299.677 + vertex -637.89 112.163 298.588 + vertex -634.448 111.068 298.423 + endloop + endfacet + facet normal -0.513825 -0.713949 0.475668 + outer loop + vertex -674.939 133.148 51.0584 + vertex -679.254 136.045 50.7439 + vertex -677.326 132.449 47.4302 + endloop + endfacet + facet normal -0.498885 -0.716679 0.487324 + outer loop + vertex -677.326 132.449 47.4302 + vertex -679.254 136.045 50.7439 + vertex -682.606 136.237 47.5955 + endloop + endfacet + facet normal -0.551217 -0.7058 0.444978 + outer loop + vertex -675.93 138.636 58.6489 + vertex -677.044 137.02 54.7063 + vertex -673.041 135.218 56.8061 + endloop + endfacet + facet normal -0.516463 -0.719035 0.465031 + outer loop + vertex -679.254 136.045 50.7439 + vertex -674.939 133.148 51.0584 + vertex -677.044 137.02 54.7063 + endloop + endfacet + facet normal -0.54989 -0.711403 0.437638 + outer loop + vertex -674.939 133.148 51.0584 + vertex -673.041 135.218 56.8061 + vertex -677.044 137.02 54.7063 + endloop + endfacet + facet normal -0.591756 -0.705058 0.390792 + outer loop + vertex -673.152 140.571 66.1065 + vertex -674.163 139.308 62.2978 + vertex -670.717 137.433 64.1325 + endloop + endfacet + facet normal -0.576003 -0.707554 0.409374 + outer loop + vertex -675.93 138.636 58.6489 + vertex -673.041 135.218 56.8061 + vertex -674.163 139.308 62.2978 + endloop + endfacet + facet normal -0.593108 -0.699007 0.399515 + outer loop + vertex -673.041 135.218 56.8061 + vertex -670.717 137.433 64.1325 + vertex -674.163 139.308 62.2978 + endloop + endfacet + facet normal -0.625397 -0.693278 0.358112 + outer loop + vertex -668.346 139.246 71.7835 + vertex -672.413 142.804 71.569 + vertex -670.717 137.433 64.1325 + endloop + endfacet + facet normal -0.606869 -0.703554 0.369758 + outer loop + vertex -670.717 137.433 64.1325 + vertex -672.413 142.804 71.569 + vertex -673.152 140.571 66.1065 + endloop + endfacet + facet normal -0.650638 -0.69101 0.314921 + outer loop + vertex -666.72 141.286 79.6196 + vertex -670.399 144.909 79.9684 + vertex -668.346 139.246 71.7835 + endloop + endfacet + facet normal -0.631837 -0.70248 0.327574 + outer loop + vertex -668.346 139.246 71.7835 + vertex -670.399 144.909 79.9684 + vertex -672.413 142.804 71.569 + endloop + endfacet + facet normal -0.67443 -0.685143 0.275178 + outer loop + vertex -665.629 143.313 87.3382 + vertex -669.141 146.98 87.8606 + vertex -666.72 141.286 79.6196 + endloop + endfacet + facet normal -0.658083 -0.695925 0.287429 + outer loop + vertex -666.72 141.286 79.6196 + vertex -669.141 146.98 87.8606 + vertex -670.399 144.909 79.9684 + endloop + endfacet + facet normal -0.691397 -0.681358 0.240252 + outer loop + vertex -664.875 145.24 94.9743 + vertex -668.337 148.938 95.5007 + vertex -665.629 143.313 87.3382 + endloop + endfacet + facet normal -0.681684 -0.688252 0.248225 + outer loop + vertex -665.629 143.313 87.3382 + vertex -668.337 148.938 95.5007 + vertex -669.141 146.98 87.8606 + endloop + endfacet + facet normal -0.702677 -0.679493 0.211033 + outer loop + vertex -664.345 147.058 102.593 + vertex -667.801 150.778 103.062 + vertex -664.875 145.24 94.9743 + endloop + endfacet + facet normal -0.697392 -0.68347 0.215668 + outer loop + vertex -664.875 145.24 94.9743 + vertex -667.801 150.778 103.062 + vertex -668.337 148.938 95.5007 + endloop + endfacet + facet normal -0.71076 -0.678332 0.186242 + outer loop + vertex -663.953 148.737 110.204 + vertex -667.41 152.476 110.632 + vertex -664.345 147.058 102.593 + endloop + endfacet + facet normal -0.707305 -0.681063 0.189399 + outer loop + vertex -664.345 147.058 102.593 + vertex -667.41 152.476 110.632 + vertex -667.801 150.778 103.062 + endloop + endfacet + facet normal -0.717597 -0.677276 0.16233 + outer loop + vertex -663.672 150.265 117.824 + vertex -667.119 154.017 118.238 + vertex -663.953 148.737 110.204 + endloop + endfacet + facet normal -0.714777 -0.679614 0.164978 + outer loop + vertex -663.953 148.737 110.204 + vertex -667.119 154.017 118.238 + vertex -667.41 152.476 110.632 + endloop + endfacet + facet normal -0.723129 -0.676579 0.139016 + outer loop + vertex -663.47 151.627 125.499 + vertex -666.909 155.386 125.908 + vertex -663.672 150.265 117.824 + endloop + endfacet + facet normal -0.721223 -0.678236 0.140828 + outer loop + vertex -663.672 150.265 117.824 + vertex -666.909 155.386 125.908 + vertex -667.119 154.017 118.238 + endloop + endfacet + facet normal -0.727126 -0.676511 0.11671 + outer loop + vertex -663.316 152.803 133.279 + vertex -666.745 156.558 133.675 + vertex -663.47 151.627 125.499 + endloop + endfacet + facet normal -0.72637 -0.677198 0.117427 + outer loop + vertex -663.47 151.627 125.499 + vertex -666.745 156.558 133.675 + vertex -666.909 155.386 125.908 + endloop + endfacet + facet normal -0.730705 -0.676046 0.0950392 + outer loop + vertex -663.199 153.785 141.168 + vertex -666.608 157.524 141.547 + vertex -663.316 152.803 133.279 + endloop + endfacet + facet normal -0.729884 -0.676823 0.0958098 + outer loop + vertex -663.316 152.803 133.279 + vertex -666.608 157.524 141.547 + vertex -666.745 156.558 133.675 + endloop + endfacet + facet normal -0.734024 -0.675164 0.073233 + outer loop + vertex -663.102 154.544 149.127 + vertex -666.524 158.302 149.48 + vertex -663.199 153.785 141.168 + endloop + endfacet + facet normal -0.733081 -0.676091 0.0741135 + outer loop + vertex -663.199 153.785 141.168 + vertex -666.524 158.302 149.48 + vertex -666.608 157.524 141.547 + endloop + endfacet + facet normal -0.736825 -0.674165 0.0508955 + outer loop + vertex -663.032 155.069 157.102 + vertex -666.444 158.823 157.431 + vertex -663.102 154.544 149.127 + endloop + endfacet + facet normal -0.736037 -0.674969 0.0516274 + outer loop + vertex -663.102 154.544 149.127 + vertex -666.444 158.823 157.431 + vertex -666.524 158.302 149.48 + endloop + endfacet + facet normal -0.738004 -0.674173 0.0289983 + outer loop + vertex -662.968 155.341 165.047 + vertex -666.394 159.105 165.361 + vertex -663.032 155.069 157.102 + endloop + endfacet + facet normal -0.738461 -0.673691 0.0285766 + outer loop + vertex -663.032 155.069 157.102 + vertex -666.394 159.105 165.361 + vertex -666.444 158.823 157.431 + endloop + endfacet + facet normal -0.738678 -0.674021 0.00707673 + outer loop + vertex -662.948 155.402 172.954 + vertex -666.369 159.154 173.243 + vertex -662.968 155.341 165.047 + endloop + endfacet + facet normal -0.73923 -0.673421 0.00656883 + outer loop + vertex -662.968 155.341 165.047 + vertex -666.369 159.154 173.243 + vertex -666.394 159.105 165.361 + endloop + endfacet + facet normal -0.738691 -0.673893 -0.0142328 + outer loop + vertex -662.949 155.236 180.844 + vertex -666.39 159.003 181.104 + vertex -662.948 155.402 172.954 + endloop + endfacet + facet normal -0.73946 -0.673034 -0.014937 + outer loop + vertex -662.948 155.402 172.954 + vertex -666.39 159.003 181.104 + vertex -666.369 159.154 173.243 + endloop + endfacet + facet normal -0.737942 -0.673912 -0.0358491 + outer loop + vertex -662.99 154.861 188.747 + vertex -666.441 158.627 188.984 + vertex -662.949 155.236 180.844 + endloop + endfacet + facet normal -0.739042 -0.672651 -0.0368461 + outer loop + vertex -662.949 155.236 180.844 + vertex -666.441 158.627 188.984 + vertex -666.39 159.003 181.104 + endloop + endfacet + facet normal -0.736017 -0.674543 -0.0571939 + outer loop + vertex -663.064 154.27 196.668 + vertex -666.529 158.032 196.895 + vertex -662.99 154.861 188.747 + endloop + endfacet + facet normal -0.737859 -0.672386 -0.0588334 + outer loop + vertex -662.99 154.861 188.747 + vertex -666.529 158.032 196.895 + vertex -666.441 158.627 188.984 + endloop + endfacet + facet normal -0.732678 -0.676056 -0.078306 + outer loop + vertex -663.162 153.459 204.585 + vertex -666.631 157.195 204.794 + vertex -663.064 154.27 196.668 + endloop + endfacet + facet normal -0.735526 -0.672664 -0.0807764 + outer loop + vertex -663.064 154.27 196.668 + vertex -666.631 157.195 204.794 + vertex -666.529 158.032 196.895 + endloop + endfacet + facet normal -0.729144 -0.676895 -0.100806 + outer loop + vertex -663.308 152.442 212.471 + vertex -666.763 156.137 212.649 + vertex -663.162 153.459 204.585 + endloop + endfacet + facet normal -0.731719 -0.673781 -0.10299 + outer loop + vertex -663.162 153.459 204.585 + vertex -666.763 156.137 212.649 + vertex -666.631 157.195 204.794 + endloop + endfacet + facet normal -0.724555 -0.678144 -0.123045 + outer loop + vertex -663.486 151.212 220.296 + vertex -666.954 154.89 220.447 + vertex -663.308 152.442 212.471 + endloop + endfacet + facet normal -0.727671 -0.674322 -0.125642 + outer loop + vertex -663.308 152.442 212.471 + vertex -666.954 154.89 220.447 + vertex -666.763 156.137 212.649 + endloop + endfacet + facet normal -0.718962 -0.679483 -0.146278 + outer loop + vertex -663.721 149.798 228.025 + vertex -667.208 153.457 228.16 + vertex -663.486 151.212 220.296 + endloop + endfacet + facet normal -0.722475 -0.675109 -0.14919 + outer loop + vertex -663.486 151.212 220.296 + vertex -667.208 153.457 228.16 + vertex -666.954 154.89 220.447 + endloop + endfacet + facet normal -0.712448 -0.680754 -0.170272 + outer loop + vertex -664.055 148.244 235.634 + vertex -667.545 151.867 235.754 + vertex -663.721 149.798 228.025 + endloop + endfacet + facet normal -0.716273 -0.675918 -0.173459 + outer loop + vertex -663.721 149.798 228.025 + vertex -667.545 151.867 235.754 + vertex -667.208 153.457 228.16 + endloop + endfacet + facet normal -0.704615 -0.681704 -0.19697 + outer loop + vertex -664.518 146.553 243.139 + vertex -668.023 150.151 243.228 + vertex -664.055 148.244 235.634 + endloop + endfacet + facet normal -0.708835 -0.676267 -0.20054 + outer loop + vertex -664.055 148.244 235.634 + vertex -668.023 150.151 243.228 + vertex -667.545 151.867 235.754 + endloop + endfacet + facet normal -0.693778 -0.683058 -0.228264 + outer loop + vertex -665.173 144.723 250.606 + vertex -668.692 148.286 250.642 + vertex -664.518 146.553 243.139 + endloop + endfacet + facet normal -0.699366 -0.675696 -0.233073 + outer loop + vertex -664.518 146.553 243.139 + vertex -668.692 148.286 250.642 + vertex -668.023 150.151 243.228 + endloop + endfacet + facet normal -0.677883 -0.686919 -0.26195 + outer loop + vertex -666.043 142.748 258.039 + vertex -669.625 146.267 258.079 + vertex -665.173 144.723 250.606 + endloop + endfacet + facet normal -0.686458 -0.67541 -0.269437 + outer loop + vertex -665.173 144.723 250.606 + vertex -669.625 146.267 258.079 + vertex -668.692 148.286 250.642 + endloop + endfacet + facet normal -0.656518 -0.694606 -0.29412 + outer loop + vertex -667.101 140.7 265.237 + vertex -670.782 144.107 265.407 + vertex -666.043 142.748 258.039 + endloop + endfacet + facet normal -0.669124 -0.677507 -0.305381 + outer loop + vertex -666.043 142.748 258.039 + vertex -670.782 144.107 265.407 + vertex -669.625 146.267 258.079 + endloop + endfacet + facet normal -0.527837 -0.699813 -0.4813 + outer loop + vertex -679.732 136.298 291.879 + vertex -678.203 136.809 289.459 + vertex -675.312 133.668 290.855 + endloop + endfacet + facet normal -0.494406 -0.671386 -0.55209 + outer loop + vertex -678.194 133.424 294.289 + vertex -681.876 134.966 295.712 + vertex -682.345 136.684 294.042 + endloop + endfacet + facet normal -0.547051 -0.640939 0.538453 + outer loop + vertex -683.735 140.746 52.0662 + vertex -684.986 139.55 49.3726 + vertex -682.333 138.775 51.144 + endloop + endfacet + facet normal -0.527513 -0.671361 0.520581 + outer loop + vertex -679.254 136.045 50.7439 + vertex -682.333 138.775 51.144 + vertex -682.606 136.237 47.5955 + endloop + endfacet + facet normal -0.505493 -0.660736 0.554891 + outer loop + vertex -686.882 138.917 46.8917 + vertex -682.606 136.237 47.5955 + vertex -684.986 139.55 49.3726 + endloop + endfacet + facet normal -0.539526 -0.664731 0.516763 + outer loop + vertex -682.333 138.775 51.144 + vertex -684.986 139.55 49.3726 + vertex -682.606 136.237 47.5955 + endloop + endfacet + facet normal -0.606728 -0.640984 0.470128 + outer loop + vertex -678.128 140.267 58.1795 + vertex -680.022 142.039 58.1506 + vertex -679.968 139.196 54.3441 + endloop + endfacet + facet normal -0.58856 -0.651716 0.478398 + outer loop + vertex -679.968 139.196 54.3441 + vertex -680.022 142.039 58.1506 + vertex -681.933 141.16 54.6027 + endloop + endfacet + facet normal -0.593464 -0.671949 0.44304 + outer loop + vertex -675.93 138.636 58.6489 + vertex -678.128 140.267 58.1795 + vertex -677.044 137.02 54.7063 + endloop + endfacet + facet normal -0.565573 -0.683058 0.462124 + outer loop + vertex -677.044 137.02 54.7063 + vertex -678.128 140.267 58.1795 + vertex -679.968 139.196 54.3441 + endloop + endfacet + facet normal -0.561438 -0.67466 0.479187 + outer loop + vertex -677.044 137.02 54.7063 + vertex -679.968 139.196 54.3441 + vertex -679.254 136.045 50.7439 + endloop + endfacet + facet normal -0.541626 -0.682839 0.490277 + outer loop + vertex -679.254 136.045 50.7439 + vertex -679.968 139.196 54.3441 + vertex -682.333 138.775 51.144 + endloop + endfacet + facet normal -0.574192 -0.641358 0.508885 + outer loop + vertex -679.968 139.196 54.3441 + vertex -681.933 141.16 54.6027 + vertex -682.333 138.775 51.144 + endloop + endfacet + facet normal -0.569969 -0.644038 0.510244 + outer loop + vertex -682.333 138.775 51.144 + vertex -681.933 141.16 54.6027 + vertex -683.735 140.746 52.0662 + endloop + endfacet + facet normal -0.653319 -0.643027 0.399613 + outer loop + vertex -674.87 142.472 66.6281 + vertex -676.74 143.902 65.872 + vertex -676.517 141.377 62.1742 + endloop + endfacet + facet normal -0.642486 -0.650358 0.405273 + outer loop + vertex -676.517 141.377 62.1742 + vertex -676.74 143.902 65.872 + vertex -678.303 143.101 62.1102 + endloop + endfacet + facet normal -0.627416 -0.674005 0.389958 + outer loop + vertex -673.152 140.571 66.1065 + vertex -674.87 142.472 66.6281 + vertex -674.163 139.308 62.2978 + endloop + endfacet + facet normal -0.617964 -0.679483 0.395503 + outer loop + vertex -674.163 139.308 62.2978 + vertex -674.87 142.472 66.6281 + vertex -676.517 141.377 62.1742 + endloop + endfacet + facet normal -0.611515 -0.670694 0.419784 + outer loop + vertex -674.163 139.308 62.2978 + vertex -676.517 141.377 62.1742 + vertex -675.93 138.636 58.6489 + endloop + endfacet + facet normal -0.595731 -0.679067 0.428919 + outer loop + vertex -675.93 138.636 58.6489 + vertex -676.517 141.377 62.1742 + vertex -678.128 140.267 58.1795 + endloop + endfacet + facet normal -0.633917 -0.640433 0.433584 + outer loop + vertex -676.517 141.377 62.1742 + vertex -678.303 143.101 62.1102 + vertex -678.128 140.267 58.1795 + endloop + endfacet + facet normal -0.616215 -0.651578 0.442409 + outer loop + vertex -678.128 140.267 58.1795 + vertex -678.303 143.101 62.1102 + vertex -680.022 142.039 58.1506 + endloop + endfacet + facet normal -0.654047 -0.657396 0.374236 + outer loop + vertex -676.74 143.902 65.872 + vertex -674.87 142.472 66.6281 + vertex -675.426 146.056 71.9525 + endloop + endfacet + facet normal -0.63936 -0.677545 0.363527 + outer loop + vertex -673.152 140.571 66.1065 + vertex -672.413 142.804 71.569 + vertex -674.87 142.472 66.6281 + endloop + endfacet + facet normal -0.658739 -0.654201 0.371596 + outer loop + vertex -672.413 142.804 71.569 + vertex -675.426 146.056 71.9525 + vertex -674.87 142.472 66.6281 + endloop + endfacet + facet normal -0.679219 -0.656821 0.327487 + outer loop + vertex -670.399 144.909 79.9684 + vertex -673.219 147.91 80.1373 + vertex -672.413 142.804 71.569 + endloop + endfacet + facet normal -0.672317 -0.662021 0.331237 + outer loop + vertex -672.413 142.804 71.569 + vertex -673.219 147.91 80.1373 + vertex -675.426 146.056 71.9525 + endloop + endfacet + facet normal -0.703061 -0.652325 0.283157 + outer loop + vertex -669.141 146.98 87.8606 + vertex -671.808 149.983 88.1578 + vertex -670.399 144.909 79.9684 + endloop + endfacet + facet normal -0.688497 -0.663578 0.292635 + outer loop + vertex -670.399 144.909 79.9684 + vertex -671.808 149.983 88.1578 + vertex -673.219 147.91 80.1373 + endloop + endfacet + facet normal -0.723127 -0.646933 0.242 + outer loop + vertex -668.337 148.938 95.5007 + vertex -670.936 151.98 95.8646 + vertex -669.141 146.98 87.8606 + endloop + endfacet + facet normal -0.711436 -0.656542 0.250623 + outer loop + vertex -669.141 146.98 87.8606 + vertex -670.936 151.98 95.8646 + vertex -671.808 149.983 88.1578 + endloop + endfacet + facet normal -0.736012 -0.643967 0.208789 + outer loop + vertex -667.801 150.778 103.062 + vertex -670.387 153.841 103.393 + vertex -668.337 148.938 95.5007 + endloop + endfacet + facet normal -0.729877 -0.649315 0.213705 + outer loop + vertex -668.337 148.938 95.5007 + vertex -670.387 153.841 103.393 + vertex -670.936 151.98 95.8646 + endloop + endfacet + facet normal -0.743058 -0.643754 0.182878 + outer loop + vertex -667.41 152.476 110.632 + vertex -669.999 155.544 110.912 + vertex -667.801 150.778 103.062 + endloop + endfacet + facet normal -0.74104 -0.645598 0.184563 + outer loop + vertex -667.801 150.778 103.062 + vertex -669.999 155.544 110.912 + vertex -670.387 153.841 103.393 + endloop + endfacet + facet normal -0.748861 -0.643385 0.158946 + outer loop + vertex -667.119 154.017 118.238 + vertex -669.723 157.115 118.51 + vertex -667.41 152.476 110.632 + endloop + endfacet + facet normal -0.747063 -0.645092 0.160479 + outer loop + vertex -667.41 152.476 110.632 + vertex -669.723 157.115 118.51 + vertex -669.999 155.544 110.912 + endloop + endfacet + facet normal -0.753178 -0.643703 0.135535 + outer loop + vertex -666.909 155.386 125.908 + vertex -669.481 158.451 126.171 + vertex -667.119 154.017 118.238 + endloop + endfacet + facet normal -0.752463 -0.64441 0.136142 + outer loop + vertex -667.119 154.017 118.238 + vertex -669.481 158.451 126.171 + vertex -669.723 157.115 118.51 + endloop + endfacet + facet normal -0.754531 -0.646397 0.113376 + outer loop + vertex -666.745 156.558 133.675 + vertex -669.262 159.541 133.934 + vertex -666.909 155.386 125.908 + endloop + endfacet + facet normal -0.75646 -0.644416 0.111785 + outer loop + vertex -666.909 155.386 125.908 + vertex -669.262 159.541 133.934 + vertex -669.481 158.451 126.171 + endloop + endfacet + facet normal -0.754052 -0.650203 0.0929644 + outer loop + vertex -666.608 157.524 141.547 + vertex -669.084 160.434 141.82 + vertex -666.745 156.558 133.675 + endloop + endfacet + facet normal -0.757324 -0.646755 0.0903841 + outer loop + vertex -666.745 156.558 133.675 + vertex -669.084 160.434 141.82 + vertex -669.262 159.541 133.934 + endloop + endfacet + facet normal -0.755333 -0.651382 0.071926 + outer loop + vertex -666.524 158.302 149.48 + vertex -668.962 161.159 149.752 + vertex -666.608 157.524 141.547 + endloop + endfacet + facet normal -0.756444 -0.650185 0.0710765 + outer loop + vertex -666.608 157.524 141.547 + vertex -668.962 161.159 149.752 + vertex -669.084 160.434 141.82 + endloop + endfacet + facet normal -0.75739 -0.651025 0.0502717 + outer loop + vertex -666.444 158.823 157.431 + vertex -668.878 161.673 157.666 + vertex -666.524 158.302 149.48 + endloop + endfacet + facet normal -0.757362 -0.651056 0.0502929 + outer loop + vertex -666.524 158.302 149.48 + vertex -668.878 161.673 157.666 + vertex -668.962 161.159 149.752 + endloop + endfacet + facet normal -0.759536 -0.649869 0.027861 + outer loop + vertex -666.394 159.105 165.361 + vertex -668.839 161.971 165.571 + vertex -666.444 158.823 157.431 + endloop + endfacet + facet normal -0.758941 -0.650544 0.0282971 + outer loop + vertex -666.444 158.823 157.431 + vertex -668.839 161.971 165.571 + vertex -668.878 161.673 157.666 + endloop + endfacet + facet normal -0.76106 -0.64865 0.00648472 + outer loop + vertex -666.369 159.154 173.243 + vertex -668.836 162.05 173.432 + vertex -666.394 159.105 165.361 + endloop + endfacet + facet normal -0.760574 -0.649215 0.00683761 + outer loop + vertex -666.394 159.105 165.361 + vertex -668.836 162.05 173.432 + vertex -668.839 161.971 165.571 + endloop + endfacet + facet normal -0.763543 -0.645595 -0.0144699 + outer loop + vertex -666.39 159.003 181.104 + vertex -668.884 161.95 181.241 + vertex -666.369 159.154 173.243 + endloop + endfacet + facet normal -0.76164 -0.647869 -0.0130769 + outer loop + vertex -666.369 159.154 173.243 + vertex -668.884 161.95 181.241 + vertex -668.836 162.05 173.432 + endloop + endfacet + facet normal -0.765986 -0.641873 -0.0355536 + outer loop + vertex -666.441 158.627 188.984 + vertex -668.996 161.671 189.084 + vertex -666.39 159.003 181.104 + endloop + endfacet + facet normal -0.763628 -0.64477 -0.0338146 + outer loop + vertex -666.39 159.003 181.104 + vertex -668.996 161.671 189.084 + vertex -668.884 161.95 181.241 + endloop + endfacet + facet normal -0.766433 -0.639817 -0.0567026 + outer loop + vertex -666.529 158.032 196.895 + vertex -669.104 161.108 196.996 + vertex -666.441 158.627 188.984 + endloop + endfacet + facet normal -0.765594 -0.640873 -0.0560964 + outer loop + vertex -666.441 158.627 188.984 + vertex -669.104 161.108 196.996 + vertex -668.996 161.671 189.084 + endloop + endfacet + facet normal -0.764592 -0.639818 -0.0776716 + outer loop + vertex -666.631 157.195 204.794 + vertex -669.227 160.283 204.907 + vertex -666.529 158.032 196.895 + endloop + endfacet + facet normal -0.765657 -0.638452 -0.0784141 + outer loop + vertex -666.529 158.032 196.895 + vertex -669.227 160.283 204.907 + vertex -669.104 161.108 196.996 + endloop + endfacet + facet normal -0.761383 -0.640695 -0.0990293 + outer loop + vertex -666.763 156.137 212.649 + vertex -669.38 159.233 212.746 + vertex -666.631 157.195 204.794 + endloop + endfacet + facet normal -0.763442 -0.638021 -0.100427 + outer loop + vertex -666.631 157.195 204.794 + vertex -669.38 159.233 212.746 + vertex -669.227 160.283 204.907 + endloop + endfacet + facet normal -0.757113 -0.641945 -0.121188 + outer loop + vertex -666.954 154.89 220.447 + vertex -669.556 157.947 220.51 + vertex -666.763 156.137 212.649 + endloop + endfacet + facet normal -0.759716 -0.638535 -0.122898 + outer loop + vertex -666.763 156.137 212.649 + vertex -669.556 157.947 220.51 + vertex -669.38 159.233 212.746 + endloop + endfacet + facet normal -0.751937 -0.643261 -0.144244 + outer loop + vertex -667.208 153.457 228.16 + vertex -669.818 156.497 228.212 + vertex -666.954 154.89 220.447 + endloop + endfacet + facet normal -0.75481 -0.639468 -0.146089 + outer loop + vertex -666.954 154.89 220.447 + vertex -669.818 156.497 228.212 + vertex -669.556 157.947 220.51 + endloop + endfacet + facet normal -0.744849 -0.645636 -0.168386 + outer loop + vertex -667.545 151.867 235.754 + vertex -670.168 154.88 235.801 + vertex -667.208 153.457 228.16 + endloop + endfacet + facet normal -0.748924 -0.640219 -0.170974 + outer loop + vertex -667.208 153.457 228.16 + vertex -670.168 154.88 235.801 + vertex -669.818 156.497 228.212 + endloop + endfacet + facet normal -0.736999 -0.646968 -0.195614 + outer loop + vertex -668.023 150.151 243.228 + vertex -670.666 153.15 243.265 + vertex -667.545 151.867 235.754 + endloop + endfacet + facet normal -0.740895 -0.641732 -0.198128 + outer loop + vertex -667.545 151.867 235.754 + vertex -670.666 153.15 243.265 + vertex -670.168 154.88 235.801 + endloop + endfacet + facet normal -0.728308 -0.64612 -0.228246 + outer loop + vertex -668.692 148.286 250.642 + vertex -671.353 151.292 250.621 + vertex -668.023 150.151 243.228 + endloop + endfacet + facet normal -0.731528 -0.641711 -0.230378 + outer loop + vertex -668.023 150.151 243.228 + vertex -671.353 151.292 250.621 + vertex -670.666 153.15 243.265 + endloop + endfacet + facet normal -0.714465 -0.647403 -0.265346 + outer loop + vertex -669.625 146.267 258.079 + vertex -672.321 149.272 258.007 + vertex -668.692 148.286 250.642 + endloop + endfacet + facet normal -0.720263 -0.639301 -0.269288 + outer loop + vertex -668.692 148.286 250.642 + vertex -672.321 149.272 258.007 + vertex -671.353 151.292 250.621 + endloop + endfacet + facet normal -0.692292 -0.655174 -0.302454 + outer loop + vertex -670.782 144.107 265.407 + vertex -673.652 147.079 265.537 + vertex -669.625 146.267 258.079 + endloop + endfacet + facet normal -0.703829 -0.638941 -0.310451 + outer loop + vertex -669.625 146.267 258.079 + vertex -673.652 147.079 265.537 + vertex -672.321 149.272 258.007 + endloop + endfacet + facet normal -0.666335 -0.666389 -0.334548 + outer loop + vertex -671.941 141.969 271.974 + vertex -675.364 144.853 273.047 + vertex -670.782 144.107 265.407 + endloop + endfacet + facet normal -0.682395 -0.643699 -0.346395 + outer loop + vertex -670.782 144.107 265.407 + vertex -675.364 144.853 273.047 + vertex -673.652 147.079 265.537 + endloop + endfacet + facet normal -0.557534 -0.652809 -0.512832 + outer loop + vertex -682.087 138.129 291.947 + vertex -684.367 140.219 291.765 + vertex -680.74 139.153 289.181 + endloop + endfacet + facet normal -0.564972 -0.630195 -0.532598 + outer loop + vertex -680.74 139.153 289.181 + vertex -684.367 140.219 291.765 + vertex -682.593 141.102 288.839 + endloop + endfacet + facet normal -0.54461 -0.682 -0.488136 + outer loop + vertex -679.732 136.298 291.879 + vertex -682.087 138.129 291.947 + vertex -678.203 136.809 289.459 + endloop + endfacet + facet normal -0.551857 -0.65821 -0.512068 + outer loop + vertex -678.203 136.809 289.459 + vertex -682.087 138.129 291.947 + vertex -680.74 139.153 289.181 + endloop + endfacet + facet normal -0.510725 -0.666769 -0.542751 + outer loop + vertex -681.876 134.966 295.712 + vertex -686.803 138.452 296.066 + vertex -682.345 136.684 294.042 + endloop + endfacet + facet normal -0.514826 -0.616585 -0.595632 + outer loop + vertex -682.345 136.684 294.042 + vertex -686.803 138.452 296.066 + vertex -686.257 138.836 295.196 + endloop + endfacet + facet normal -0.562917 -0.607975 0.559903 + outer loop + vertex -685.135 141.71 51.7126 + vertex -686.232 142.698 51.6821 + vertex -687.131 140.993 48.9265 + endloop + endfacet + facet normal -0.554278 -0.614661 0.561221 + outer loop + vertex -687.131 140.993 48.9265 + vertex -686.232 142.698 51.6821 + vertex -688.357 142.115 48.9446 + endloop + endfacet + facet normal -0.566063 -0.623334 0.53947 + outer loop + vertex -683.735 140.746 52.0662 + vertex -685.135 141.71 51.7126 + vertex -684.986 139.55 49.3726 + endloop + endfacet + facet normal -0.541517 -0.634586 0.551417 + outer loop + vertex -684.986 139.55 49.3726 + vertex -685.135 141.71 51.7126 + vertex -687.131 140.993 48.9265 + endloop + endfacet + facet normal -0.537084 -0.622479 0.569263 + outer loop + vertex -684.986 139.55 49.3726 + vertex -687.131 140.993 48.9265 + vertex -686.882 138.917 46.8917 + endloop + endfacet + facet normal -0.528372 -0.625817 0.573739 + outer loop + vertex -686.882 138.917 46.8917 + vertex -687.131 140.993 48.9265 + vertex -688.766 140.77 47.1781 + endloop + endfacet + facet normal -0.543078 -0.602801 0.584549 + outer loop + vertex -687.131 140.993 48.9265 + vertex -688.357 142.115 48.9446 + vertex -688.766 140.77 47.1781 + endloop + endfacet + facet normal -0.53305 -0.609222 0.587116 + outer loop + vertex -688.766 140.77 47.1781 + vertex -688.357 142.115 48.9446 + vertex -690.14 141.844 47.0441 + endloop + endfacet + facet normal -0.625698 -0.601658 0.496497 + outer loop + vertex -681.308 143.513 58.3759 + vertex -682.056 144.523 58.6571 + vertex -683.195 142.586 54.8741 + endloop + endfacet + facet normal -0.60922 -0.616294 0.499031 + outer loop + vertex -683.195 142.586 54.8741 + vertex -682.056 144.523 58.6571 + vertex -684.063 143.547 55.0015 + endloop + endfacet + facet normal -0.620189 -0.615417 0.486444 + outer loop + vertex -680.022 142.039 58.1506 + vertex -681.308 143.513 58.3759 + vertex -681.933 141.16 54.6027 + endloop + endfacet + facet normal -0.603481 -0.627911 0.491466 + outer loop + vertex -681.933 141.16 54.6027 + vertex -681.308 143.513 58.3759 + vertex -683.195 142.586 54.8741 + endloop + endfacet + facet normal -0.588335 -0.619802 0.519334 + outer loop + vertex -681.933 141.16 54.6027 + vertex -683.195 142.586 54.8741 + vertex -683.735 140.746 52.0662 + endloop + endfacet + facet normal -0.569122 -0.63327 0.52447 + outer loop + vertex -683.735 140.746 52.0662 + vertex -683.195 142.586 54.8741 + vertex -685.135 141.71 51.7126 + endloop + endfacet + facet normal -0.59259 -0.605541 0.531184 + outer loop + vertex -683.195 142.586 54.8741 + vertex -684.063 143.547 55.0015 + vertex -685.135 141.71 51.7126 + endloop + endfacet + facet normal -0.573946 -0.621033 0.533764 + outer loop + vertex -685.135 141.71 51.7126 + vertex -684.063 143.547 55.0015 + vertex -686.232 142.698 51.6821 + endloop + endfacet + facet normal -0.700855 -0.583006 0.410982 + outer loop + vertex -677.792 145.568 66.7315 + vertex -678.818 146.408 66.1741 + vertex -679.564 144.542 62.2548 + endloop + endfacet + facet normal -0.683674 -0.599813 0.41571 + outer loop + vertex -679.564 144.542 62.2548 + vertex -678.818 146.408 66.1741 + vertex -680.285 145.56 62.5379 + endloop + endfacet + facet normal -0.6617 -0.628629 0.408631 + outer loop + vertex -676.74 143.902 65.872 + vertex -677.792 145.568 66.7315 + vertex -678.303 143.101 62.1102 + endloop + endfacet + facet normal -0.666696 -0.624431 0.406944 + outer loop + vertex -678.303 143.101 62.1102 + vertex -677.792 145.568 66.7315 + vertex -679.564 144.542 62.2548 + endloop + endfacet + facet normal -0.650311 -0.614121 0.447159 + outer loop + vertex -678.303 143.101 62.1102 + vertex -679.564 144.542 62.2548 + vertex -680.022 142.039 58.1506 + endloop + endfacet + facet normal -0.636773 -0.624629 0.45206 + outer loop + vertex -680.022 142.039 58.1506 + vertex -679.564 144.542 62.2548 + vertex -681.308 143.513 58.3759 + endloop + endfacet + facet normal -0.661796 -0.595401 0.455548 + outer loop + vertex -679.564 144.542 62.2548 + vertex -680.285 145.56 62.5379 + vertex -681.308 143.513 58.3759 + endloop + endfacet + facet normal -0.648383 -0.607855 0.458379 + outer loop + vertex -681.308 143.513 58.3759 + vertex -680.285 145.56 62.5379 + vertex -682.056 144.523 58.6571 + endloop + endfacet + facet normal -0.700734 -0.609311 0.371096 + outer loop + vertex -678.818 146.408 66.1741 + vertex -677.792 145.568 66.7315 + vertex -677.052 148.011 72.1399 + endloop + endfacet + facet normal -0.687453 -0.624932 0.369958 + outer loop + vertex -676.74 143.902 65.872 + vertex -675.426 146.056 71.9525 + vertex -677.792 145.568 66.7315 + endloop + endfacet + facet normal -0.695556 -0.614284 0.372635 + outer loop + vertex -675.426 146.056 71.9525 + vertex -677.052 148.011 72.1399 + vertex -677.792 145.568 66.7315 + endloop + endfacet + facet normal -0.707406 -0.623944 0.33207 + outer loop + vertex -673.219 147.91 80.1373 + vertex -674.949 149.818 80.0373 + vertex -675.426 146.056 71.9525 + endloop + endfacet + facet normal -0.709536 -0.621949 0.331267 + outer loop + vertex -675.426 146.056 71.9525 + vertex -674.949 149.818 80.0373 + vertex -677.052 148.011 72.1399 + endloop + endfacet + facet normal -0.727053 -0.622847 0.288888 + outer loop + vertex -671.808 149.983 88.1578 + vertex -673.502 151.87 87.9624 + vertex -673.219 147.91 80.1373 + endloop + endfacet + facet normal -0.715602 -0.633339 0.294611 + outer loop + vertex -673.219 147.91 80.1373 + vertex -673.502 151.87 87.9624 + vertex -674.949 149.818 80.0373 + endloop + endfacet + facet normal -0.747897 -0.617129 0.244542 + outer loop + vertex -670.936 151.98 95.8646 + vertex -672.574 153.93 95.7766 + vertex -671.808 149.983 88.1578 + endloop + endfacet + facet normal -0.732688 -0.631569 0.253551 + outer loop + vertex -671.808 149.983 88.1578 + vertex -672.574 153.93 95.7766 + vertex -673.502 151.87 87.9624 + endloop + endfacet + facet normal -0.76295 -0.612423 0.206993 + outer loop + vertex -670.387 153.841 103.393 + vertex -671.99 155.811 103.315 + vertex -670.936 151.98 95.8646 + endloop + endfacet + facet normal -0.752782 -0.622625 0.213678 + outer loop + vertex -670.936 151.98 95.8646 + vertex -671.99 155.811 103.315 + vertex -672.574 153.93 95.7766 + endloop + endfacet + facet normal -0.771129 -0.611196 0.178324 + outer loop + vertex -669.999 155.544 110.912 + vertex -671.602 157.521 110.753 + vertex -670.387 153.841 103.393 + endloop + endfacet + facet normal -0.766361 -0.616203 0.181615 + outer loop + vertex -670.387 153.841 103.393 + vertex -671.602 157.521 110.753 + vertex -671.99 155.811 103.315 + endloop + endfacet + facet normal -0.776006 -0.611488 0.154584 + outer loop + vertex -669.723 157.115 118.51 + vertex -671.316 159.098 118.355 + vertex -669.999 155.544 110.912 + endloop + endfacet + facet normal -0.773159 -0.614583 0.156566 + outer loop + vertex -669.999 155.544 110.912 + vertex -671.316 159.098 118.355 + vertex -671.602 157.521 110.753 + endloop + endfacet + facet normal -0.780614 -0.611083 0.13122 + outer loop + vertex -669.481 158.451 126.171 + vertex -671.084 160.465 126.015 + vertex -669.723 157.115 118.51 + endloop + endfacet + facet normal -0.77762 -0.614449 0.133266 + outer loop + vertex -669.723 157.115 118.51 + vertex -671.084 160.465 126.015 + vertex -671.316 159.098 118.355 + endloop + endfacet + facet normal -0.781018 -0.615037 0.108351 + outer loop + vertex -669.262 159.541 133.934 + vertex -670.834 161.493 133.688 + vertex -669.481 158.451 126.171 + endloop + endfacet + facet normal -0.781946 -0.613962 0.107749 + outer loop + vertex -669.481 158.451 126.171 + vertex -670.834 161.493 133.688 + vertex -671.084 160.465 126.015 + endloop + endfacet + facet normal -0.775361 -0.625306 0.088363 + outer loop + vertex -669.084 160.434 141.82 + vertex -670.6 162.282 141.597 + vertex -669.262 159.541 133.934 + endloop + endfacet + facet normal -0.781362 -0.618289 0.0848052 + outer loop + vertex -669.262 159.541 133.934 + vertex -670.6 162.282 141.597 + vertex -670.834 161.493 133.688 + endloop + endfacet + facet normal -0.768841 -0.635605 0.069934 + outer loop + vertex -668.962 161.159 149.752 + vertex -670.411 162.898 149.618 + vertex -669.084 160.434 141.82 + endloop + endfacet + facet normal -0.775391 -0.627979 0.0664098 + outer loop + vertex -669.084 160.434 141.82 + vertex -670.411 162.898 149.618 + vertex -670.6 162.282 141.597 + endloop + endfacet + facet normal -0.768502 -0.637926 0.0495583 + outer loop + vertex -668.878 161.673 157.666 + vertex -670.308 163.384 157.527 + vertex -668.962 161.159 149.752 + endloop + endfacet + facet normal -0.769007 -0.637336 0.0493021 + outer loop + vertex -668.962 161.159 149.752 + vertex -670.308 163.384 157.527 + vertex -670.411 162.898 149.618 + endloop + endfacet + facet normal -0.770007 -0.637427 0.0278569 + outer loop + vertex -668.839 161.971 165.571 + vertex -670.256 163.673 165.35 + vertex -668.878 161.673 157.666 + endloop + endfacet + facet normal -0.768298 -0.639448 0.0286894 + outer loop + vertex -668.878 161.673 157.666 + vertex -670.256 163.673 165.35 + vertex -670.308 163.384 157.527 + endloop + endfacet + facet normal -0.770794 -0.637049 0.00671955 + outer loop + vertex -668.836 162.05 173.432 + vertex -670.253 163.762 173.226 + vertex -668.839 161.971 165.571 + endloop + endfacet + facet normal -0.768993 -0.639212 0.00755837 + outer loop + vertex -668.839 161.971 165.571 + vertex -670.253 163.762 173.226 + vertex -670.256 163.673 165.35 + endloop + endfacet + facet normal -0.77546 -0.631264 -0.0129489 + outer loop + vertex -668.884 161.95 181.241 + vertex -670.336 163.738 180.999 + vertex -668.836 162.05 173.432 + endloop + endfacet + facet normal -0.769765 -0.638245 -0.0102634 + outer loop + vertex -668.836 162.05 173.432 + vertex -670.336 163.738 180.999 + vertex -670.253 163.762 173.226 + endloop + endfacet + facet normal -0.782934 -0.621216 -0.0332534 + outer loop + vertex -668.996 161.671 189.084 + vertex -670.472 163.55 188.729 + vertex -668.884 161.95 181.241 + endloop + endfacet + facet normal -0.774133 -0.632359 -0.0290067 + outer loop + vertex -668.884 161.95 181.241 + vertex -670.472 163.55 188.729 + vertex -670.336 163.738 180.999 + endloop + endfacet + facet normal -0.788866 -0.612155 -0.0543705 + outer loop + vertex -669.104 161.108 196.996 + vertex -670.64 163.116 196.664 + vertex -668.996 161.671 189.084 + endloop + endfacet + facet normal -0.78076 -0.62278 -0.0505875 + outer loop + vertex -668.996 161.671 189.084 + vertex -670.64 163.116 196.664 + vertex -670.472 163.55 188.729 + endloop + endfacet + facet normal -0.790441 -0.607854 -0.0756099 + outer loop + vertex -669.227 160.283 204.907 + vertex -670.804 162.363 204.669 + vertex -669.104 161.108 196.996 + endloop + endfacet + facet normal -0.78631 -0.61341 -0.0737858 + outer loop + vertex -669.104 161.108 196.996 + vertex -670.804 162.363 204.669 + vertex -670.64 163.116 196.664 + endloop + endfacet + facet normal -0.788807 -0.606977 -0.0967614 + outer loop + vertex -669.38 159.233 212.746 + vertex -670.966 161.331 212.508 + vertex -669.227 160.283 204.907 + endloop + endfacet + facet normal -0.787858 -0.60827 -0.0963662 + outer loop + vertex -669.227 160.283 204.907 + vertex -670.966 161.331 212.508 + vertex -670.804 162.363 204.669 + endloop + endfacet + facet normal -0.785233 -0.607778 -0.118384 + outer loop + vertex -669.556 157.947 220.51 + vertex -671.148 160.061 220.215 + vertex -669.38 159.233 212.746 + endloop + endfacet + facet normal -0.785717 -0.607115 -0.118573 + outer loop + vertex -669.38 159.233 212.746 + vertex -671.148 160.061 220.215 + vertex -670.966 161.331 212.508 + endloop + endfacet + facet normal -0.780607 -0.608863 -0.141205 + outer loop + vertex -669.818 156.497 228.212 + vertex -671.406 158.597 227.935 + vertex -669.556 157.947 220.51 + endloop + endfacet + facet normal -0.781239 -0.607998 -0.141438 + outer loop + vertex -669.556 157.947 220.51 + vertex -671.406 158.597 227.935 + vertex -671.148 160.061 220.215 + endloop + endfacet + facet normal -0.773736 -0.611381 -0.165972 + outer loop + vertex -670.168 154.88 235.801 + vertex -671.755 156.962 235.528 + vertex -669.818 156.497 228.212 + endloop + endfacet + facet normal -0.775784 -0.608582 -0.166692 + outer loop + vertex -669.818 156.497 228.212 + vertex -671.755 156.962 235.528 + vertex -671.406 158.597 227.935 + endloop + endfacet + facet normal -0.7643 -0.615137 -0.193526 + outer loop + vertex -670.666 153.15 243.265 + vertex -672.262 155.216 243.003 + vertex -670.168 154.88 235.801 + endloop + endfacet + facet normal -0.76768 -0.610533 -0.194724 + outer loop + vertex -670.168 154.88 235.801 + vertex -672.262 155.216 243.003 + vertex -671.755 156.962 235.528 + endloop + endfacet + facet normal -0.755545 -0.614932 -0.225855 + outer loop + vertex -671.353 151.292 250.621 + vertex -672.95 153.363 250.326 + vertex -670.666 153.15 243.265 + endloop + endfacet + facet normal -0.756666 -0.613401 -0.226264 + outer loop + vertex -670.666 153.15 243.265 + vertex -672.95 153.363 250.326 + vertex -672.262 155.216 243.003 + endloop + endfacet + facet normal -0.747496 -0.609273 -0.264643 + outer loop + vertex -672.321 149.272 258.007 + vertex -673.905 151.423 257.53 + vertex -671.353 151.292 250.621 + endloop + endfacet + facet normal -0.745255 -0.612395 -0.263757 + outer loop + vertex -671.353 151.292 250.621 + vertex -673.905 151.423 257.53 + vertex -672.95 153.363 250.326 + endloop + endfacet + facet normal -0.727564 -0.61341 -0.307213 + outer loop + vertex -673.652 147.079 265.537 + vertex -675.298 149.278 265.045 + vertex -672.321 149.272 258.007 + endloop + endfacet + facet normal -0.731749 -0.607511 -0.308988 + outer loop + vertex -672.321 149.272 258.007 + vertex -675.298 149.278 265.045 + vertex -673.905 151.423 257.53 + endloop + endfacet + facet normal -0.701116 -0.624109 -0.344854 + outer loop + vertex -675.364 144.853 273.047 + vertex -677.357 147.106 273.023 + vertex -673.652 147.079 265.537 + endloop + endfacet + facet normal -0.71077 -0.610352 -0.349681 + outer loop + vertex -673.652 147.079 265.537 + vertex -677.357 147.106 273.023 + vertex -675.298 149.278 265.045 + endloop + endfacet + facet normal -0.593319 -0.579962 -0.558227 + outer loop + vertex -685.996 141.815 291.657 + vertex -687.015 142.828 291.688 + vertex -683.961 142.557 288.724 + endloop + endfacet + facet normal -0.607117 -0.548059 -0.57536 + outer loop + vertex -683.961 142.557 288.724 + vertex -687.015 142.828 291.688 + vertex -684.865 143.49 288.789 + endloop + endfacet + facet normal -0.57296 -0.621134 -0.534705 + outer loop + vertex -684.367 140.219 291.765 + vertex -685.996 141.815 291.657 + vertex -682.593 141.102 288.839 + endloop + endfacet + facet normal -0.583682 -0.59288 -0.554805 + outer loop + vertex -682.593 141.102 288.839 + vertex -685.996 141.815 291.657 + vertex -683.961 142.557 288.724 + endloop + endfacet + facet normal -0.542531 -0.605717 -0.582037 + outer loop + vertex -688.302 140.288 295.489 + vertex -689.763 141.631 295.455 + vertex -687.574 141.077 293.99 + endloop + endfacet + facet normal -0.529758 -0.631307 -0.566399 + outer loop + vertex -686.257 138.836 295.196 + vertex -688.302 140.288 295.489 + vertex -685.559 139.32 294.003 + endloop + endfacet + facet normal -0.532336 -0.614842 -0.581882 + outer loop + vertex -685.559 139.32 294.003 + vertex -688.302 140.288 295.489 + vertex -687.574 141.077 293.99 + endloop + endfacet + facet normal -0.548368 -0.632974 -0.546477 + outer loop + vertex -685.559 139.32 294.003 + vertex -687.574 141.077 293.99 + vertex -684.367 140.219 291.765 + endloop + endfacet + facet normal -0.556305 -0.606398 -0.568161 + outer loop + vertex -684.367 140.219 291.765 + vertex -687.574 141.077 293.99 + vertex -685.996 141.815 291.657 + endloop + endfacet + facet normal -0.563631 -0.597549 -0.570312 + outer loop + vertex -687.574 141.077 293.99 + vertex -688.847 142.235 294.035 + vertex -685.996 141.815 291.657 + endloop + endfacet + facet normal -0.576878 -0.562377 -0.592405 + outer loop + vertex -685.996 141.815 291.657 + vertex -688.847 142.235 294.035 + vertex -687.015 142.828 291.688 + endloop + endfacet + facet normal -0.519936 -0.61139 -0.596548 + outer loop + vertex -686.257 138.836 295.196 + vertex -686.803 138.452 296.066 + vertex -688.302 140.288 295.489 + endloop + endfacet + facet normal -0.524756 -0.613356 -0.590276 + outer loop + vertex -686.803 138.452 296.066 + vertex -690.646 141.342 296.479 + vertex -688.302 140.288 295.489 + endloop + endfacet + facet normal -0.584102 -0.571422 0.576456 + outer loop + vertex -686.803 143.325 51.7643 + vertex -687.085 143.505 51.6568 + vertex -688.939 142.763 49.0426 + endloop + endfacet + facet normal -0.58598 -0.568878 0.577066 + outer loop + vertex -688.939 142.763 49.0426 + vertex -687.085 143.505 51.6568 + vertex -689.227 142.97 48.9555 + endloop + endfacet + facet normal -0.569396 -0.593793 0.568506 + outer loop + vertex -686.232 142.698 51.6821 + vertex -686.803 143.325 51.7643 + vertex -688.357 142.115 48.9446 + endloop + endfacet + facet normal -0.567193 -0.596108 0.568285 + outer loop + vertex -688.357 142.115 48.9446 + vertex -686.803 143.325 51.7643 + vertex -688.939 142.763 49.0426 + endloop + endfacet + facet normal -0.548708 -0.584006 0.598211 + outer loop + vertex -688.357 142.115 48.9446 + vertex -688.939 142.763 49.0426 + vertex -690.14 141.844 47.0441 + endloop + endfacet + facet normal -0.54717 -0.58563 0.598033 + outer loop + vertex -690.14 141.844 47.0441 + vertex -688.939 142.763 49.0426 + vertex -690.648 142.635 47.3545 + endloop + endfacet + facet normal -0.573901 -0.533657 0.621167 + outer loop + vertex -688.939 142.763 49.0426 + vertex -689.227 142.97 48.9555 + vertex -690.648 142.635 47.3545 + endloop + endfacet + facet normal -0.556804 -0.56177 0.611869 + outer loop + vertex -690.648 142.635 47.3545 + vertex -689.227 142.97 48.9555 + vertex -690.853 142.772 47.294 + endloop + endfacet + facet normal -0.693694 -0.494471 0.523725 + outer loop + vertex -682.454 145.077 58.7751 + vertex -682.647 145.191 58.6266 + vertex -684.539 144.132 55.1214 + endloop + endfacet + facet normal -0.591997 -0.625391 0.508356 + outer loop + vertex -684.539 144.132 55.1214 + vertex -682.647 145.191 58.6266 + vertex -684.751 144.293 55.0727 + endloop + endfacet + facet normal -0.645147 -0.571734 0.506858 + outer loop + vertex -682.056 144.523 58.6571 + vertex -682.454 145.077 58.7751 + vertex -684.063 143.547 55.0015 + endloop + endfacet + facet normal -0.614804 -0.604097 0.507034 + outer loop + vertex -684.063 143.547 55.0015 + vertex -682.454 145.077 58.7751 + vertex -684.539 144.132 55.1214 + endloop + endfacet + facet normal -0.594866 -0.594776 0.540717 + outer loop + vertex -684.063 143.547 55.0015 + vertex -684.539 144.132 55.1214 + vertex -686.232 142.698 51.6821 + endloop + endfacet + facet normal -0.585368 -0.604632 0.540152 + outer loop + vertex -686.232 142.698 51.6821 + vertex -684.539 144.132 55.1214 + vertex -686.803 143.325 51.7643 + endloop + endfacet + facet normal -0.584409 -0.60587 0.539803 + outer loop + vertex -684.539 144.132 55.1214 + vertex -684.751 144.293 55.0727 + vertex -686.803 143.325 51.7643 + endloop + endfacet + facet normal -0.589006 -0.600303 0.541025 + outer loop + vertex -686.803 143.325 51.7643 + vertex -684.751 144.293 55.0727 + vertex -687.085 143.505 51.6568 + endloop + endfacet + facet normal -0.828312 -0.381097 0.410688 + outer loop + vertex -678.891 147.2 67.2148 + vertex -679.151 147.26 66.7457 + vertex -680.602 146.115 62.7581 + endloop + endfacet + facet normal -0.788467 -0.452442 0.416673 + outer loop + vertex -680.602 146.115 62.7581 + vertex -679.151 147.26 66.7457 + vertex -680.889 146.109 62.2072 + endloop + endfacet + facet normal -0.677011 -0.607875 0.414902 + outer loop + vertex -678.818 146.408 66.1741 + vertex -678.891 147.2 67.2148 + vertex -680.285 145.56 62.5379 + endloop + endfacet + facet normal -0.711763 -0.569131 0.411683 + outer loop + vertex -680.285 145.56 62.5379 + vertex -678.891 147.2 67.2148 + vertex -680.602 146.115 62.7581 + endloop + endfacet + facet normal -0.67887 -0.570451 0.4623 + outer loop + vertex -680.285 145.56 62.5379 + vertex -680.602 146.115 62.7581 + vertex -682.056 144.523 58.6571 + endloop + endfacet + facet normal -0.670033 -0.580266 0.462976 + outer loop + vertex -682.056 144.523 58.6571 + vertex -680.602 146.115 62.7581 + vertex -682.454 145.077 58.7751 + endloop + endfacet + facet normal -0.867986 -0.198083 0.455372 + outer loop + vertex -680.602 146.115 62.7581 + vertex -680.889 146.109 62.2072 + vertex -682.454 145.077 58.7751 + endloop + endfacet + facet normal -0.688541 -0.545339 0.478034 + outer loop + vertex -682.454 145.077 58.7751 + vertex -680.889 146.109 62.2072 + vertex -682.647 145.191 58.6266 + endloop + endfacet + facet normal -0.779278 -0.507894 0.367109 + outer loop + vertex -679.151 147.26 66.7457 + vertex -678.891 147.2 67.2148 + vertex -677.416 148.707 72.4304 + endloop + endfacet + facet normal -0.745458 -0.554664 0.369648 + outer loop + vertex -678.818 146.408 66.1741 + vertex -677.052 148.011 72.1399 + vertex -678.891 147.2 67.2148 + endloop + endfacet + facet normal -0.750699 -0.547073 0.370353 + outer loop + vertex -677.052 148.011 72.1399 + vertex -677.416 148.707 72.4304 + vertex -678.891 147.2 67.2148 + endloop + endfacet + facet normal -0.762193 -0.556708 0.33036 + outer loop + vertex -674.949 149.818 80.0373 + vertex -675.703 150.581 79.5834 + vertex -677.052 148.011 72.1399 + endloop + endfacet + facet normal -0.774379 -0.541484 0.327311 + outer loop + vertex -677.052 148.011 72.1399 + vertex -675.703 150.581 79.5834 + vertex -677.416 148.707 72.4304 + endloop + endfacet + facet normal -0.766142 -0.574254 0.288547 + outer loop + vertex -673.502 151.87 87.9624 + vertex -674.356 152.516 86.9812 + vertex -674.949 149.818 80.0373 + endloop + endfacet + facet normal -0.761357 -0.579726 0.290264 + outer loop + vertex -674.949 149.818 80.0373 + vertex -674.356 152.516 86.9812 + vertex -675.703 150.581 79.5834 + endloop + endfacet + facet normal -0.780235 -0.575731 0.244474 + outer loop + vertex -672.574 153.93 95.7766 + vertex -673.407 154.622 94.7492 + vertex -673.502 151.87 87.9624 + endloop + endfacet + facet normal -0.753098 -0.605918 0.256335 + outer loop + vertex -673.502 151.87 87.9624 + vertex -673.407 154.622 94.7492 + vertex -674.356 152.516 86.9812 + endloop + endfacet + facet normal -0.79672 -0.568984 0.203703 + outer loop + vertex -671.99 155.811 103.315 + vertex -672.781 156.703 102.714 + vertex -672.574 153.93 95.7766 + endloop + endfacet + facet normal -0.768577 -0.601619 0.217588 + outer loop + vertex -672.574 153.93 95.7766 + vertex -672.781 156.703 102.714 + vertex -673.407 154.622 94.7492 + endloop + endfacet + facet normal -0.803252 -0.56999 0.17291 + outer loop + vertex -671.602 157.521 110.753 + vertex -672.373 158.336 109.859 + vertex -671.99 155.811 103.315 + endloop + endfacet + facet normal -0.792907 -0.582643 0.178398 + outer loop + vertex -671.99 155.811 103.315 + vertex -672.373 158.336 109.859 + vertex -672.781 156.703 102.714 + endloop + endfacet + facet normal -0.809028 -0.568727 0.148401 + outer loop + vertex -671.316 159.098 118.355 + vertex -672.092 159.952 117.396 + vertex -671.602 157.521 110.753 + endloop + endfacet + facet normal -0.796944 -0.583871 0.154834 + outer loop + vertex -671.602 157.521 110.753 + vertex -672.092 159.952 117.396 + vertex -672.373 158.336 109.859 + endloop + endfacet + facet normal -0.813345 -0.567961 0.126057 + outer loop + vertex -671.084 160.465 126.015 + vertex -671.875 161.449 125.341 + vertex -671.316 159.098 118.355 + endloop + endfacet + facet normal -0.802615 -0.581806 0.131574 + outer loop + vertex -671.316 159.098 118.355 + vertex -671.875 161.449 125.341 + vertex -672.092 159.952 117.396 + endloop + endfacet + facet normal -0.818081 -0.565897 0.102486 + outer loop + vertex -670.834 161.493 133.688 + vertex -671.63 162.459 132.669 + vertex -671.084 160.465 126.015 + endloop + endfacet + facet normal -0.80917 -0.57779 0.106781 + outer loop + vertex -671.084 160.465 126.015 + vertex -671.63 162.459 132.669 + vertex -671.875 161.449 125.341 + endloop + endfacet + facet normal -0.816751 -0.571254 0.0811596 + outer loop + vertex -670.6 162.282 141.597 + vertex -671.46 163.327 140.294 + vertex -670.834 161.493 133.688 + endloop + endfacet + facet normal -0.810734 -0.579359 0.0839803 + outer loop + vertex -670.834 161.493 133.688 + vertex -671.46 163.327 140.294 + vertex -671.63 162.459 132.669 + endloop + endfacet + facet normal -0.811422 -0.580985 0.0636502 + outer loop + vertex -670.411 162.898 149.618 + vertex -671.316 164.051 148.616 + vertex -670.6 162.282 141.597 + endloop + endfacet + facet normal -0.808584 -0.584791 0.0648988 + outer loop + vertex -670.6 162.282 141.597 + vertex -671.316 164.051 148.616 + vertex -671.46 163.327 140.294 + endloop + endfacet + facet normal -0.805309 -0.590996 0.0469242 + outer loop + vertex -670.308 163.384 157.527 + vertex -671.165 164.498 156.824 + vertex -670.411 162.898 149.618 + endloop + endfacet + facet normal -0.805426 -0.59084 0.0468774 + outer loop + vertex -670.411 162.898 149.618 + vertex -671.165 164.498 156.824 + vertex -671.316 164.051 148.616 + endloop + endfacet + facet normal -0.807643 -0.589049 0.0270899 + outer loop + vertex -670.256 163.673 165.35 + vertex -671.088 164.767 164.318 + vertex -670.308 163.384 157.527 + endloop + endfacet + facet normal -0.80072 -0.598298 0.0297678 + outer loop + vertex -670.308 163.384 157.527 + vertex -671.088 164.767 164.318 + vertex -671.165 164.498 156.824 + endloop + endfacet + facet normal -0.807945 -0.589217 0.0070079 + outer loop + vertex -670.253 163.762 173.226 + vertex -671.092 164.901 172.178 + vertex -670.256 163.673 165.35 + endloop + endfacet + facet normal -0.800193 -0.599662 0.00983615 + outer loop + vertex -670.256 163.673 165.35 + vertex -671.092 164.901 172.178 + vertex -671.088 164.767 164.318 + endloop + endfacet + facet normal -0.803997 -0.594541 -0.010489 + outer loop + vertex -670.336 163.738 180.999 + vertex -671.148 164.849 180.217 + vertex -670.253 163.762 173.226 + endloop + endfacet + facet normal -0.800716 -0.59897 -0.00938039 + outer loop + vertex -670.253 163.762 173.226 + vertex -671.148 164.849 180.217 + vertex -671.092 164.901 172.178 + endloop + endfacet + facet normal -0.809837 -0.585962 -0.0285087 + outer loop + vertex -670.472 163.55 188.729 + vertex -671.271 164.709 187.617 + vertex -670.336 163.738 180.999 + endloop + endfacet + facet normal -0.798943 -0.600897 -0.0247769 + outer loop + vertex -670.336 163.738 180.999 + vertex -671.271 164.709 187.617 + vertex -671.148 164.849 180.217 + endloop + endfacet + facet normal -0.815069 -0.577302 -0.0488294 + outer loop + vertex -670.64 163.116 196.664 + vertex -671.362 164.231 195.532 + vertex -670.472 163.55 188.729 + endloop + endfacet + facet normal -0.801546 -0.596225 -0.0451639 + outer loop + vertex -670.472 163.55 188.729 + vertex -671.362 164.231 195.532 + vertex -671.271 164.709 187.617 + endloop + endfacet + facet normal -0.820967 -0.566657 -0.0700977 + outer loop + vertex -670.804 162.363 204.669 + vertex -671.526 163.519 203.782 + vertex -670.64 163.116 196.664 + endloop + endfacet + facet normal -0.805198 -0.589225 -0.0668593 + outer loop + vertex -670.64 163.116 196.664 + vertex -671.526 163.519 203.782 + vertex -671.362 164.231 195.532 + endloop + endfacet + facet normal -0.820258 -0.564661 -0.0912948 + outer loop + vertex -670.966 161.331 212.508 + vertex -671.707 162.517 211.825 + vertex -670.804 162.363 204.669 + endloop + endfacet + facet normal -0.812161 -0.576447 -0.0900193 + outer loop + vertex -670.804 162.363 204.669 + vertex -671.707 162.517 211.825 + vertex -671.526 163.519 203.782 + endloop + endfacet + facet normal -0.816439 -0.566351 -0.112581 + outer loop + vertex -671.148 160.061 220.215 + vertex -671.862 161.283 219.248 + vertex -670.966 161.331 212.508 + endloop + endfacet + facet normal -0.812638 -0.571883 -0.112115 + outer loop + vertex -670.966 161.331 212.508 + vertex -671.862 161.283 219.248 + vertex -671.707 162.517 211.825 + endloop + endfacet + facet normal -0.81674 -0.561286 -0.133763 + outer loop + vertex -671.406 158.597 227.935 + vertex -672.111 159.856 226.955 + vertex -671.148 160.061 220.215 + endloop + endfacet + facet normal -0.80632 -0.576394 -0.132734 + outer loop + vertex -671.148 160.061 220.215 + vertex -672.111 159.856 226.955 + vertex -671.862 161.283 219.248 + endloop + endfacet + facet normal -0.813092 -0.56028 -0.158013 + outer loop + vertex -671.755 156.962 235.528 + vertex -672.451 158.178 234.803 + vertex -671.406 158.597 227.935 + endloop + endfacet + facet normal -0.804416 -0.572819 -0.157457 + outer loop + vertex -671.406 158.597 227.935 + vertex -672.451 158.178 234.803 + vertex -672.111 159.856 226.955 + endloop + endfacet + facet normal -0.803198 -0.565712 -0.18666 + outer loop + vertex -672.262 155.216 243.003 + vertex -672.899 156.43 242.063 + vertex -671.755 156.962 235.528 + endloop + endfacet + facet normal -0.800256 -0.569923 -0.186488 + outer loop + vertex -671.755 156.962 235.528 + vertex -672.899 156.43 242.063 + vertex -672.451 158.178 234.803 + endloop + endfacet + facet normal -0.785111 -0.578888 -0.220204 + outer loop + vertex -672.95 153.363 250.326 + vertex -673.594 154.504 249.626 + vertex -672.262 155.216 243.003 + endloop + endfacet + facet normal -0.783403 -0.581232 -0.220112 + outer loop + vertex -672.262 155.216 243.003 + vertex -673.594 154.504 249.626 + vertex -672.899 156.43 242.063 + endloop + endfacet + facet normal -0.78291 -0.566811 -0.25647 + outer loop + vertex -673.905 151.423 257.53 + vertex -674.478 152.649 256.569 + vertex -672.95 153.363 250.326 + endloop + endfacet + facet normal -0.766343 -0.589643 -0.25503 + outer loop + vertex -672.95 153.363 250.326 + vertex -674.478 152.649 256.569 + vertex -673.594 154.504 249.626 + endloop + endfacet + facet normal -0.782028 -0.545894 -0.300719 + outer loop + vertex -675.298 149.278 265.045 + vertex -675.691 150.741 263.412 + vertex -673.905 151.423 257.53 + endloop + endfacet + facet normal -0.754509 -0.585277 -0.296929 + outer loop + vertex -673.905 151.423 257.53 + vertex -675.691 150.741 263.412 + vertex -674.478 152.649 256.569 + endloop + endfacet + facet normal -0.748022 -0.565653 -0.34713 + outer loop + vertex -677.357 147.106 273.023 + vertex -677.799 148.447 271.789 + vertex -675.298 149.278 265.045 + endloop + endfacet + facet normal -0.735972 -0.582657 -0.344756 + outer loop + vertex -675.298 149.278 265.045 + vertex -677.799 148.447 271.789 + vertex -675.691 150.741 263.412 + endloop + endfacet + facet normal -0.656014 -0.4613 -0.597367 + outer loop + vertex -687.51 143.354 291.742 + vertex -687.516 143.556 291.592 + vertex -685.303 144.006 288.814 + endloop + endfacet + facet normal -0.618009 -0.53228 -0.57857 + outer loop + vertex -685.303 144.006 288.814 + vertex -687.516 143.556 291.592 + vertex -685.213 144.254 288.49 + endloop + endfacet + facet normal -0.621254 -0.526033 -0.580804 + outer loop + vertex -687.015 142.828 291.688 + vertex -687.51 143.354 291.742 + vertex -684.865 143.49 288.789 + endloop + endfacet + facet normal -0.630507 -0.506457 -0.588186 + outer loop + vertex -684.865 143.49 288.789 + vertex -687.51 143.354 291.742 + vertex -685.303 144.006 288.814 + endloop + endfacet + facet normal -0.587901 -0.545998 -0.596875 + outer loop + vertex -688.847 142.235 294.035 + vertex -689.486 142.854 294.098 + vertex -687.015 142.828 291.688 + endloop + endfacet + facet normal -0.604595 -0.506893 -0.61443 + outer loop + vertex -687.015 142.828 291.688 + vertex -689.486 142.854 294.098 + vertex -687.51 143.354 291.742 + endloop + endfacet + facet normal -0.624136 -0.471187 -0.623247 + outer loop + vertex -689.486 142.854 294.098 + vertex -689.634 143.089 294.069 + vertex -687.51 143.354 291.742 + endloop + endfacet + facet normal -0.621006 -0.478019 -0.621168 + outer loop + vertex -687.51 143.354 291.742 + vertex -689.634 143.089 294.069 + vertex -687.516 143.556 291.592 + endloop + endfacet + facet normal 0.511944 0.669452 -0.538282 + outer loop + vertex -687.085 143.505 51.6568 + vertex -687.526 143.358 51.0549 + vertex -689.227 142.97 48.9555 + endloop + endfacet + facet normal 0.437084 -0.878786 -0.191554 + outer loop + vertex -689.227 142.97 48.9555 + vertex -687.526 143.358 51.0549 + vertex -689.658 142.865 48.4544 + endloop + endfacet + facet normal 0.505062 0.646882 -0.571363 + outer loop + vertex -689.227 142.97 48.9555 + vertex -689.658 142.865 48.4544 + vertex -690.853 142.772 47.294 + endloop + endfacet + facet normal 0.685577 0.130996 -0.716118 + outer loop + vertex -690.853 142.772 47.294 + vertex -689.658 142.865 48.4544 + vertex -691.119 142.724 47.0307 + endloop + endfacet + facet normal 0.77465 0.327178 -0.541176 + outer loop + vertex -682.647 145.191 58.6266 + vertex -682.772 145.059 58.3689 + vertex -684.751 144.293 55.0727 + endloop + endfacet + facet normal 0.847261 -0.298363 -0.439463 + outer loop + vertex -684.751 144.293 55.0727 + vertex -682.772 145.059 58.3689 + vertex -685.082 144.128 54.5469 + endloop + endfacet + facet normal 0.689653 0.442334 -0.573341 + outer loop + vertex -684.751 144.293 55.0727 + vertex -685.082 144.128 54.5469 + vertex -687.085 143.505 51.6568 + endloop + endfacet + facet normal 0.561391 -0.798597 -0.216988 + outer loop + vertex -687.085 143.505 51.6568 + vertex -685.082 144.128 54.5469 + vertex -687.526 143.358 51.0549 + endloop + endfacet + facet normal 0.346093 0.869282 -0.352944 + outer loop + vertex -679.151 147.26 66.7457 + vertex -680.094 146.494 63.9342 + vertex -680.889 146.109 62.2072 + endloop + endfacet + facet normal 0.661867 0.606892 -0.440016 + outer loop + vertex -680.889 146.109 62.2072 + vertex -680.094 146.494 63.9342 + vertex -681.246 145.822 61.2736 + endloop + endfacet + facet normal 0.391442 0.826616 -0.404325 + outer loop + vertex -680.889 146.109 62.2072 + vertex -681.246 145.822 61.2736 + vertex -682.647 145.191 58.6266 + endloop + endfacet + facet normal 0.859291 0.146931 -0.489928 + outer loop + vertex -682.647 145.191 58.6266 + vertex -681.246 145.822 61.2736 + vertex -682.772 145.059 58.3689 + endloop + endfacet + facet normal 0.745907 0.261374 0.612623 + outer loop + vertex -687.516 143.556 291.592 + vertex -686.989 143.67 290.902 + vertex -685.213 144.254 288.49 + endloop + endfacet + facet normal 0.195648 -0.976321 -0.0923023 + outer loop + vertex -685.213 144.254 288.49 + vertex -686.989 143.67 290.902 + vertex -684.524 144.494 287.402 + endloop + endfacet + facet normal 0.765087 -0.0831616 0.638535 + outer loop + vertex -689.634 143.089 294.069 + vertex -689.42 143.115 293.816 + vertex -687.516 143.556 291.592 + endloop + endfacet + facet normal 0.343608 -0.932766 0.109003 + outer loop + vertex -687.516 143.556 291.592 + vertex -689.42 143.115 293.816 + vertex -686.989 143.67 290.902 + endloop + endfacet + facet normal 0.00971126 -0.998 0.0624612 + outer loop + vertex -607.546 103.093 301.377 + vertex -608.898 103.311 305.076 + vertex -608.489 103.229 303.709 + endloop + endfacet + facet normal 0.390488 -0.907903 0.152418 + outer loop + vertex -606.116 102.99 297.103 + vertex -607.546 103.093 301.377 + vertex -607.229 103.057 300.352 + endloop + endfacet + facet normal -0.321097 -0.940592 -0.110382 + outer loop + vertex -598.801 114.463 213.556 + vertex -598.949 114.102 217.067 + vertex -599.305 114.677 213.198 + endloop + endfacet + facet normal -0.322344 -0.940384 -0.108503 + outer loop + vertex -598.867 114.81 210.741 + vertex -598.801 114.463 213.556 + vertex -599.305 114.677 213.198 + endloop + endfacet + facet normal -0.20873 -0.973813 -0.090108 + outer loop + vertex -598.77 115.131 207.051 + vertex -598.867 114.81 210.741 + vertex -599.305 114.677 213.198 + endloop + endfacet + facet normal -0.29446 -0.951256 -0.0916822 + outer loop + vertex -598.728 115.447 203.637 + vertex -598.77 115.131 207.051 + vertex -599.126 115.501 204.352 + endloop + endfacet + facet normal -0.271727 -0.959172 -0.0784461 + outer loop + vertex -598.692 115.579 201.895 + vertex -598.728 115.447 203.637 + vertex -599.126 115.501 204.352 + endloop + endfacet + facet normal -0.181253 -0.981405 -0.0631754 + outer loop + vertex -598.602 115.784 198.452 + vertex -598.692 115.579 201.895 + vertex -599.126 115.501 204.352 + endloop + endfacet + facet normal -0.308926 -0.948676 -0.0676727 + outer loop + vertex -598.558 116.019 194.958 + vertex -598.602 115.784 198.452 + vertex -598.967 116.093 195.793 + endloop + endfacet + facet normal -0.286469 -0.956453 -0.0559845 + outer loop + vertex -598.538 116.115 193.211 + vertex -598.558 116.019 194.958 + vertex -598.967 116.093 195.793 + endloop + endfacet + facet normal -0.192625 -0.980432 -0.0406035 + outer loop + vertex -598.477 116.243 189.833 + vertex -598.538 116.115 193.211 + vertex -598.967 116.093 195.793 + endloop + endfacet + facet normal 0.267316 0.916264 -0.298332 + outer loop + vertex -606.497 98.2048 44.6816 + vertex -605.3 99.1155 48.5514 + vertex -605.527 98.828 47.465 + endloop + endfacet + facet normal -0.505865 -0.777295 0.37405 + outer loop + vertex -607.931 97.4043 41.0782 + vertex -606.497 98.2048 44.6816 + vertex -606.946 97.9889 43.626 + endloop + endfacet + facet normal -0.44676 -0.744672 0.495852 + outer loop + vertex -677.188 131.291 45.8155 + vertex -673.971 129.277 45.689 + vertex -677.326 132.449 47.4302 + endloop + endfacet + facet normal -0.479123 -0.732164 0.484126 + outer loop + vertex -679.56 133.02 46.0823 + vertex -677.188 131.291 45.8155 + vertex -677.326 132.449 47.4302 + endloop + endfacet + facet normal -0.482359 -0.702688 0.523029 + outer loop + vertex -682.19 134.59 45.7669 + vertex -679.56 133.02 46.0823 + vertex -682.606 136.237 47.5955 + endloop + endfacet + facet normal -0.484916 -0.701893 0.52173 + outer loop + vertex -685.177 136.806 45.9715 + vertex -682.19 134.59 45.7669 + vertex -682.606 136.237 47.5955 + endloop + endfacet + facet normal -0.497158 -0.651356 0.57321 + outer loop + vertex -686.944 137.951 45.7399 + vertex -685.177 136.806 45.9715 + vertex -686.882 138.917 46.8917 + endloop + endfacet + facet normal -0.520091 -0.640335 0.565222 + outer loop + vertex -688.941 139.7 45.8842 + vertex -686.944 137.951 45.7399 + vertex -686.882 138.917 46.8917 + endloop + endfacet + facet normal -0.515702 -0.612636 0.598939 + outer loop + vertex -693.155 142.971 45.6015 + vertex -688.941 139.7 45.8842 + vertex -690.14 141.844 47.0441 + endloop + endfacet + facet normal -0.339033 -0.880641 0.330949 + outer loop + vertex -690.679 142.706 47.4309 + vertex -693.155 142.971 45.6015 + vertex -691.119 142.724 47.0307 + endloop + endfacet + facet normal -0.192929 -0.921961 0.335808 + outer loop + vertex -688.49 143.135 49.8675 + vertex -690.679 142.706 47.4309 + vertex -689.658 142.865 48.4544 + endloop + endfacet + facet normal -0.39131 -0.793137 0.466701 + outer loop + vertex -686.108 143.887 53.1433 + vertex -688.49 143.135 49.8675 + vertex -687.526 143.358 51.0549 + endloop + endfacet + facet normal -0.470942 -0.745336 0.471898 + outer loop + vertex -683.43 144.917 57.443 + vertex -686.108 143.887 53.1433 + vertex -685.082 144.128 54.5469 + endloop + endfacet + facet normal -0.399084 -0.820574 0.409135 + outer loop + vertex -681.023 146.016 61.9945 + vertex -683.43 144.917 57.443 + vertex -682.772 145.059 58.3689 + endloop + endfacet + facet normal -0.276453 -0.893997 0.352623 + outer loop + vertex -679.336 147.186 66.283 + vertex -681.023 146.016 61.9945 + vertex -680.094 146.494 63.9342 + endloop + endfacet + facet normal -0.722762 -0.576555 0.381051 + outer loop + vertex -677.871 148.582 71.1746 + vertex -679.336 147.186 66.283 + vertex -679.151 147.26 66.7457 + endloop + endfacet + facet normal -0.803329 -0.489301 0.339482 + outer loop + vertex -676.466 150.049 76.6134 + vertex -677.871 148.582 71.1746 + vertex -677.416 148.707 72.4304 + endloop + endfacet + facet normal -0.862247 -0.411609 0.29514 + outer loop + vertex -675.539 151.325 81.1016 + vertex -676.466 150.049 76.6134 + vertex -675.703 150.581 79.5834 + endloop + endfacet + facet normal -0.945722 -0.239375 0.219794 + outer loop + vertex -674.764 152.62 85.8458 + vertex -675.539 151.325 81.1016 + vertex -675.703 150.581 79.5834 + endloop + endfacet + facet normal -0.822332 -0.511885 0.248483 + outer loop + vertex -673.952 154.11 91.6035 + vertex -674.764 152.62 85.8458 + vertex -674.356 152.516 86.9812 + endloop + endfacet + facet normal -0.817028 -0.529698 0.227784 + outer loop + vertex -673.494 155.271 95.9442 + vertex -673.952 154.11 91.6035 + vertex -673.407 154.622 94.7492 + endloop + endfacet + facet normal -0.826512 -0.517431 -0.221684 + outer loop + vertex -673.912 154.419 251.006 + vertex -673.471 155.499 246.843 + vertex -673.594 154.504 249.626 + endloop + endfacet + facet normal -0.882676 -0.410922 -0.22809 + outer loop + vertex -674.56 153.268 255.59 + vertex -673.912 154.419 251.006 + vertex -673.594 154.504 249.626 + endloop + endfacet + facet normal -0.794445 -0.541325 -0.275361 + outer loop + vertex -675.495 151.742 261.285 + vertex -674.56 153.268 255.59 + vertex -674.478 152.649 256.569 + endloop + endfacet + facet normal -0.808156 -0.500645 -0.310223 + outer loop + vertex -676.657 150.152 266.879 + vertex -675.495 151.742 261.285 + vertex -675.691 150.741 263.412 + endloop + endfacet + facet normal -0.851396 -0.369993 -0.371794 + outer loop + vertex -679.431 147.382 276.587 + vertex -677.905 148.861 271.621 + vertex -677.799 148.447 271.789 + endloop + endfacet + facet normal -0.429129 -0.815654 -0.388016 + outer loop + vertex -681.042 146.266 280.714 + vertex -679.431 147.382 276.587 + vertex -680.429 146.494 279.557 + endloop + endfacet + facet normal -0.320525 -0.865222 -0.385558 + outer loop + vertex -683.05 145.228 284.712 + vertex -681.042 146.266 280.714 + vertex -681.438 145.924 281.81 + endloop + endfacet + facet normal -0.360263 -0.830848 -0.42415 + outer loop + vertex -685.911 144.188 289.181 + vertex -683.05 145.228 284.712 + vertex -684.524 144.494 287.402 + endloop + endfacet + facet normal -0.368529 -0.800941 -0.47189 + outer loop + vertex -688.863 143.2 293.162 + vertex -685.911 144.188 289.181 + vertex -686.989 143.67 290.902 + endloop + endfacet + facet normal -0.164862 -0.95006 -0.264964 + outer loop + vertex -691.353 142.932 295.671 + vertex -688.863 143.2 293.162 + vertex -689.42 143.115 293.816 + endloop + endfacet + facet normal -0.490206 -0.587058 -0.644253 + outer loop + vertex -687.249 138.068 296.754 + vertex -689.318 139.552 296.976 + vertex -686.803 138.452 296.066 + endloop + endfacet + facet normal -0.466209 -0.609479 -0.641237 + outer loop + vertex -684.472 136.177 296.533 + vertex -687.249 138.068 296.754 + vertex -686.803 138.452 296.066 + endloop + endfacet + facet normal -0.487916 -0.653247 -0.57897 + outer loop + vertex -681.944 134.466 296.333 + vertex -684.472 136.177 296.533 + vertex -681.876 134.966 295.712 + endloop + endfacet + facet normal -0.469068 -0.662324 -0.58421 + outer loop + vertex -679.864 133.13 296.178 + vertex -681.944 134.466 296.333 + vertex -681.876 134.966 295.712 + endloop + endfacet + facet normal -0.473398 -0.71848 -0.509589 + outer loop + vertex -677.023 131.186 296.279 + vertex -679.864 133.13 296.178 + vertex -676.837 131.593 295.532 + endloop + endfacet + facet normal -0.468265 -0.721556 -0.509986 + outer loop + vertex -674.329 129.597 296.053 + vertex -677.023 131.186 296.279 + vertex -676.837 131.593 295.532 + endloop + endfacet + facet normal -0.447557 -0.735093 -0.509246 + outer loop + vertex -672.217 128.282 296.095 + vertex -674.329 129.597 296.053 + vertex -671.433 128.31 295.367 + endloop + endfacet + facet normal -0.426498 -0.761812 -0.487587 + outer loop + vertex -669.283 126.645 296.087 + vertex -672.217 128.282 296.095 + vertex -671.433 128.31 295.367 + endloop + endfacet + facet normal -0.425975 -0.770186 -0.47472 + outer loop + vertex -666.442 125.085 296.068 + vertex -669.283 126.645 296.087 + vertex -665.775 125.11 295.429 + endloop + endfacet + facet normal -0.407639 -0.790905 -0.456398 + outer loop + vertex -664.209 123.947 296.046 + vertex -666.442 125.085 296.068 + vertex -665.775 125.11 295.429 + endloop + endfacet + facet normal -0.39258 -0.797694 -0.457782 + outer loop + vertex -662.101 122.804 296.23 + vertex -664.209 123.947 296.046 + vertex -660.173 122.111 295.784 + endloop + endfacet + facet normal -0.392432 -0.801512 -0.451194 + outer loop + vertex -660.046 121.79 296.245 + vertex -662.101 122.804 296.23 + vertex -660.173 122.111 295.784 + endloop + endfacet + facet normal -0.362227 -0.808272 -0.464207 + outer loop + vertex -657.638 120.577 296.478 + vertex -660.046 121.79 296.245 + vertex -660.173 122.111 295.784 + endloop + endfacet + facet normal -0.311756 -0.874206 -0.372253 + outer loop + vertex -643.139 114.151 297.89 + vertex -644.959 114.914 297.623 + vertex -643.144 114.296 297.554 + endloop + endfacet + facet normal -0.289517 -0.880536 -0.375281 + outer loop + vertex -641.252 113.397 298.205 + vertex -643.139 114.151 297.89 + vertex -643.144 114.296 297.554 + endloop + endfacet + facet normal -0.295952 -0.902877 -0.311809 + outer loop + vertex -639.067 112.52 298.67 + vertex -641.252 113.397 298.205 + vertex -637.89 112.163 298.588 + endloop + endfacet + facet normal -0.297005 -0.916053 -0.269508 + outer loop + vertex -636.029 111.376 299.21 + vertex -639.067 112.52 298.67 + vertex -637.89 112.163 298.588 + endloop + endfacet + facet normal -0.272669 -0.919826 -0.282085 + outer loop + vertex -633.61 110.485 299.779 + vertex -636.029 111.376 299.21 + vertex -632.473 110.179 299.677 + endloop + endfacet + facet normal -0.271835 -0.935449 -0.225922 + outer loop + vertex -630.562 109.437 300.447 + vertex -633.61 110.485 299.779 + vertex -632.473 110.179 299.677 + endloop + endfacet + facet normal -0.247566 -0.939904 -0.235142 + outer loop + vertex -628.112 108.616 301.15 + vertex -630.562 109.437 300.447 + vertex -626.756 108.269 301.108 + endloop + endfacet + facet normal -0.248885 -0.951896 -0.178746 + outer loop + vertex -624.915 107.621 301.997 + vertex -628.112 108.616 301.15 + vertex -626.756 108.269 301.108 + endloop + endfacet + facet normal -0.204803 -0.94157 -0.2674 + outer loop + vertex -622.771 106.958 302.691 + vertex -624.915 107.621 301.997 + vertex -620.377 106.324 303.09 + endloop + endfacet + facet normal -0.208884 -0.945619 -0.249343 + outer loop + vertex -621.067 106.455 303.17 + vertex -622.771 106.958 302.691 + vertex -620.377 106.324 303.09 + endloop + endfacet + facet normal -0.20534 -0.958705 -0.196775 + outer loop + vertex -620.098 106.185 303.474 + vertex -621.067 106.455 303.17 + vertex -620.377 106.324 303.09 + endloop + endfacet + facet normal -0.184206 -0.959639 -0.212512 + outer loop + vertex -618.05 105.635 304.182 + vertex -620.098 106.185 303.474 + vertex -620.377 106.324 303.09 + endloop + endfacet + facet normal -0.240671 -0.969764 -0.040436 + outer loop + vertex -608.489 103.229 303.709 + vertex -607.229 103.057 300.352 + vertex -607.546 103.093 301.377 + endloop + endfacet + facet normal 0.0421143 -0.971049 0.235137 + outer loop + vertex -603.565 101.523 58.525 + vertex -604.59 99.7241 51.2787 + vertex -604.199 100.26 53.4201 + endloop + endfacet + facet normal -0.315759 -0.947526 -0.0499048 + outer loop + vertex -598.967 116.093 195.793 + vertex -598.971 116.503 188.033 + vertex -598.477 116.243 189.833 + endloop + endfacet + facet normal -0.287571 -0.955098 -0.0713447 + outer loop + vertex -599.126 115.501 204.352 + vertex -598.967 116.093 195.793 + vertex -598.602 115.784 198.452 + endloop + endfacet + facet normal -0.276662 -0.956288 -0.0947159 + outer loop + vertex -599.305 114.677 213.198 + vertex -599.126 115.501 204.352 + vertex -598.77 115.131 207.051 + endloop + endfacet + facet normal -0.255118 -0.959527 -0.119257 + outer loop + vertex -599.441 113.694 221.4 + vertex -599.305 114.677 213.198 + vertex -598.949 114.102 217.067 + endloop + endfacet + facet normal -0.180886 -0.958797 -0.219061 + outer loop + vertex -620.377 106.324 303.09 + vertex -615.382 104.938 305.033 + vertex -618.05 105.635 304.182 + endloop + endfacet + facet normal -0.207559 -0.943512 -0.258271 + outer loop + vertex -626.756 108.269 301.108 + vertex -620.377 106.324 303.09 + vertex -624.915 107.621 301.997 + endloop + endfacet + facet normal -0.225496 -0.918581 -0.324593 + outer loop + vertex -632.473 110.179 299.677 + vertex -626.756 108.269 301.108 + vertex -630.562 109.437 300.447 + endloop + endfacet + facet normal -0.250586 -0.891476 -0.377461 + outer loop + vertex -637.89 112.163 298.588 + vertex -632.473 110.179 299.677 + vertex -636.029 111.376 299.21 + endloop + endfacet + facet normal -0.272912 -0.87048 -0.409614 + outer loop + vertex -643.144 114.296 297.554 + vertex -637.89 112.163 298.588 + vertex -641.252 113.397 298.205 + endloop + endfacet + facet normal -0.302266 -0.852671 -0.426132 + outer loop + vertex -648.587 116.707 296.591 + vertex -643.144 114.296 297.554 + vertex -647.019 115.832 297.23 + endloop + endfacet + facet normal -0.337116 -0.832521 -0.439615 + outer loop + vertex -654.279 119.263 296.116 + vertex -648.587 116.707 296.591 + vertex -652.719 118.172 296.986 + endloop + endfacet + facet normal -0.366417 -0.811291 -0.455572 + outer loop + vertex -660.173 122.111 295.784 + vertex -654.279 119.263 296.116 + vertex -657.638 120.577 296.478 + endloop + endfacet + facet normal -0.387104 -0.781067 -0.489985 + outer loop + vertex -665.775 125.11 295.429 + vertex -660.173 122.111 295.784 + vertex -664.209 123.947 296.046 + endloop + endfacet + facet normal -0.424859 -0.760916 -0.49041 + outer loop + vertex -671.433 128.31 295.367 + vertex -665.775 125.11 295.429 + vertex -669.283 126.645 296.087 + endloop + endfacet + facet normal -0.475343 -0.752729 0.455466 + outer loop + vertex -672.025 129.02 47.2957 + vertex -677.326 132.449 47.4302 + vertex -673.971 129.277 45.689 + endloop + endfacet + facet normal -0.444242 -0.703156 -0.555176 + outer loop + vertex -676.837 131.593 295.532 + vertex -671.433 128.31 295.367 + vertex -674.329 129.597 296.053 + endloop + endfacet + facet normal -0.489655 -0.704939 0.513128 + outer loop + vertex -677.326 132.449 47.4302 + vertex -682.606 136.237 47.5955 + vertex -679.56 133.02 46.0823 + endloop + endfacet + facet normal -0.523826 -0.681501 -0.51104 + outer loop + vertex -679.732 136.298 291.879 + vertex -675.312 133.668 290.855 + vertex -682.345 136.684 294.042 + endloop + endfacet + facet normal -0.46062 -0.656424 -0.597442 + outer loop + vertex -681.876 134.966 295.712 + vertex -676.837 131.593 295.532 + vertex -679.864 133.13 296.178 + endloop + endfacet + facet normal -0.502522 -0.652878 0.566764 + outer loop + vertex -682.606 136.237 47.5955 + vertex -686.882 138.917 46.8917 + vertex -685.177 136.806 45.9715 + endloop + endfacet + facet normal -0.542234 -0.63897 -0.545618 + outer loop + vertex -684.367 140.219 291.765 + vertex -682.087 138.129 291.947 + vertex -685.559 139.32 294.003 + endloop + endfacet + facet normal -0.532254 -0.664762 -0.524211 + outer loop + vertex -682.087 138.129 291.947 + vertex -679.732 136.298 291.879 + vertex -682.345 136.684 294.042 + endloop + endfacet + facet normal -0.48483 -0.622947 -0.613902 + outer loop + vertex -686.803 138.452 296.066 + vertex -681.876 134.966 295.712 + vertex -684.472 136.177 296.533 + endloop + endfacet + facet normal -0.519379 -0.641562 -0.564486 + outer loop + vertex -682.345 136.684 294.042 + vertex -686.257 138.836 295.196 + vertex -685.559 139.32 294.003 + endloop + endfacet + facet normal -0.522172 -0.621158 0.584379 + outer loop + vertex -686.882 138.917 46.8917 + vertex -688.766 140.77 47.1781 + vertex -688.941 139.7 45.8842 + endloop + endfacet + facet normal -0.535794 -0.613624 0.579992 + outer loop + vertex -688.766 140.77 47.1781 + vertex -690.14 141.844 47.0441 + vertex -688.941 139.7 45.8842 + endloop + endfacet + facet normal -0.517855 -0.579191 0.629574 + outer loop + vertex -690.14 141.844 47.0441 + vertex -690.648 142.635 47.3545 + vertex -693.155 142.971 45.6015 + endloop + endfacet + facet normal -0.538436 -0.507438 0.672751 + outer loop + vertex -690.648 142.635 47.3545 + vertex -690.853 142.772 47.294 + vertex -693.155 142.971 45.6015 + endloop + endfacet + facet normal -0.879321 -0.322463 0.350446 + outer loop + vertex -679.151 147.26 66.7457 + vertex -677.416 148.707 72.4304 + vertex -677.871 148.582 71.1746 + endloop + endfacet + facet normal -0.940582 -0.196743 0.276762 + outer loop + vertex -677.416 148.707 72.4304 + vertex -675.703 150.581 79.5834 + vertex -676.466 150.049 76.6134 + endloop + endfacet + facet normal -0.860758 -0.431712 0.269667 + outer loop + vertex -675.703 150.581 79.5834 + vertex -674.356 152.516 86.9812 + vertex -674.764 152.62 85.8458 + endloop + endfacet + facet normal -0.882361 -0.415687 0.220551 + outer loop + vertex -674.356 152.516 86.9812 + vertex -673.407 154.622 94.7492 + vertex -673.952 154.11 91.6035 + endloop + endfacet + facet normal -0.881911 -0.434518 0.182831 + outer loop + vertex -673.407 154.622 94.7492 + vertex -672.781 156.703 102.714 + vertex -673.162 156.204 99.6871 + endloop + endfacet + facet normal -0.873712 -0.466536 -0.137735 + outer loop + vertex -672.111 159.856 226.955 + vertex -672.451 158.178 234.803 + vertex -672.482 159.1 231.871 + endloop + endfacet + facet normal -0.891485 -0.412611 -0.187101 + outer loop + vertex -672.899 156.43 242.063 + vertex -673.594 154.504 249.626 + vertex -673.471 155.499 246.843 + endloop + endfacet + facet normal -0.840663 -0.486928 -0.237037 + outer loop + vertex -673.594 154.504 249.626 + vertex -674.478 152.649 256.569 + vertex -674.56 153.268 255.59 + endloop + endfacet + facet normal -0.881484 -0.390708 -0.265203 + outer loop + vertex -674.478 152.649 256.569 + vertex -675.691 150.741 263.412 + vertex -675.495 151.742 261.285 + endloop + endfacet + facet normal -0.9237 -0.240438 -0.298276 + outer loop + vertex -675.691 150.741 263.412 + vertex -677.799 148.447 271.789 + vertex -676.657 150.152 266.879 + endloop + endfacet + facet normal -0.948899 0.0528549 -0.311121 + outer loop + vertex -677.799 148.447 271.789 + vertex -680.065 146.842 278.428 + vertex -679.431 147.382 276.587 + endloop + endfacet + facet normal -0.215262 0.976516 -0.00883589 + outer loop + vertex -689.658 142.865 48.4544 + vertex -687.526 143.358 51.0549 + vertex -688.49 143.135 49.8675 + endloop + endfacet + facet normal 0.508903 0.594746 -0.62233 + outer loop + vertex -690.853 142.772 47.294 + vertex -691.119 142.724 47.0307 + vertex -693.155 142.971 45.6015 + endloop + endfacet + facet normal 0.645293 0.320442 -0.693479 + outer loop + vertex -691.119 142.724 47.0307 + vertex -689.658 142.865 48.4544 + vertex -690.679 142.706 47.4309 + endloop + endfacet + facet normal -0.56258 -0.658099 0.500409 + outer loop + vertex -685.082 144.128 54.5469 + vertex -682.772 145.059 58.3689 + vertex -683.43 144.917 57.443 + endloop + endfacet + facet normal -0.689573 -0.435489 0.578652 + outer loop + vertex -687.526 143.358 51.0549 + vertex -685.082 144.128 54.5469 + vertex -686.108 143.887 53.1433 + endloop + endfacet + facet normal -0.798736 -0.456346 0.392134 + outer loop + vertex -680.094 146.494 63.9342 + vertex -679.151 147.26 66.7457 + vertex -679.336 147.186 66.283 + endloop + endfacet + facet normal -0.130941 -0.946251 0.295743 + outer loop + vertex -681.246 145.822 61.2736 + vertex -680.094 146.494 63.9342 + vertex -681.023 146.016 61.9945 + endloop + endfacet + facet normal -0.0318091 -0.962481 0.269478 + outer loop + vertex -682.772 145.059 58.3689 + vertex -681.246 145.822 61.2736 + vertex -681.023 146.016 61.9945 + endloop + endfacet + facet normal -0.157248 -0.936956 -0.312069 + outer loop + vertex -681.438 145.924 281.81 + vertex -682.745 145.274 284.421 + vertex -683.05 145.228 284.712 + endloop + endfacet + facet normal -0.512069 -0.749856 -0.418928 + outer loop + vertex -680.429 146.494 279.557 + vertex -681.438 145.924 281.81 + vertex -681.042 146.266 280.714 + endloop + endfacet + facet normal -0.542426 -0.647973 -0.534701 + outer loop + vertex -684.524 144.494 287.402 + vertex -686.989 143.67 290.902 + vertex -685.911 144.188 289.181 + endloop + endfacet + facet normal -0.209962 -0.907902 -0.362808 + outer loop + vertex -682.745 145.274 284.421 + vertex -684.524 144.494 287.402 + vertex -683.05 145.228 284.712 + endloop + endfacet + facet normal 0.728251 0.219187 0.649313 + outer loop + vertex -686.989 143.67 290.902 + vertex -689.42 143.115 293.816 + vertex -688.863 143.2 293.162 + endloop + endfacet + facet normal -0.536758 -0.662128 -0.522951 + outer loop + vertex -685.559 139.32 294.003 + vertex -682.087 138.129 291.947 + vertex -682.345 136.684 294.042 + endloop + endfacet + facet normal -0.299173 -0.596391 0.744858 + outer loop + vertex -701.197 133.382 32.9616 + vertex -705.947 138.799 35.3912 + vertex -707.114 136.037 32.7112 + endloop + endfacet + facet normal -0.341227 -0.556061 0.757866 + outer loop + vertex -700.383 136.962 36.5489 + vertex -705.042 141.619 37.8675 + vertex -705.947 138.799 35.3912 + endloop + endfacet + facet normal -0.369758 -0.531848 0.761851 + outer loop + vertex -699.37 139.607 39.2158 + vertex -704.312 143.927 39.8335 + vertex -705.042 141.619 37.8675 + endloop + endfacet + facet normal -0.397478 -0.507873 0.764248 + outer loop + vertex -697.952 141.607 41.5993 + vertex -703.429 145.519 41.3509 + vertex -704.312 143.927 39.8335 + endloop + endfacet + facet normal -0.397756 -0.445075 0.802308 + outer loop + vertex -704.497 146.822 41.5439 + vertex -703.429 145.519 41.3509 + vertex -699.85 144.859 42.7589 + endloop + endfacet + facet normal -0.398507 -0.399777 0.825452 + outer loop + vertex -703.429 145.519 41.3509 + vertex -697.268 143.298 43.2492 + vertex -699.85 144.859 42.7589 + endloop + endfacet + facet normal -0.37724 -0.163627 0.911546 + outer loop + vertex -696.511 143.729 43.9377 + vertex -697.781 144.27 43.5095 + vertex -699.85 144.859 42.7589 + endloop + endfacet + facet normal -0.412419 -0.415316 0.810816 + outer loop + vertex -697.781 144.27 43.5095 + vertex -701.039 145.533 42.4993 + vertex -699.85 144.859 42.7589 + endloop + endfacet + facet normal -0.348126 -0.268143 0.89828 + outer loop + vertex -699.85 144.859 42.7589 + vertex -701.039 145.533 42.4993 + vertex -704.497 146.822 41.5439 + endloop + endfacet + facet normal -0.322091 -0.585678 0.7438 + outer loop + vertex -705.947 138.799 35.3912 + vertex -713.095 141.867 34.7113 + vertex -707.114 136.037 32.7112 + endloop + endfacet + facet normal -0.283362 -0.558279 0.779764 + outer loop + vertex -707.114 136.037 32.7112 + vertex -713.095 141.867 34.7113 + vertex -713.931 138.872 32.2633 + endloop + endfacet + facet normal -0.344596 -0.554589 0.75742 + outer loop + vertex -705.042 141.619 37.8675 + vertex -712.339 144.658 36.7728 + vertex -705.947 138.799 35.3912 + endloop + endfacet + facet normal -0.297094 -0.513922 0.804748 + outer loop + vertex -705.947 138.799 35.3912 + vertex -712.339 144.658 36.7728 + vertex -713.095 141.867 34.7113 + endloop + endfacet + facet normal -0.365758 -0.533672 0.762506 + outer loop + vertex -704.312 143.927 39.8335 + vertex -711.765 146.971 38.3886 + vertex -705.042 141.619 37.8675 + endloop + endfacet + facet normal -0.324255 -0.486301 0.8114 + outer loop + vertex -705.042 141.619 37.8675 + vertex -711.765 146.971 38.3886 + vertex -712.339 144.658 36.7728 + endloop + endfacet + facet normal -0.379423 -0.519309 0.765739 + outer loop + vertex -703.429 145.519 41.3509 + vertex -711.206 148.495 39.5151 + vertex -704.312 143.927 39.8335 + endloop + endfacet + facet normal -0.349304 -0.47075 0.810173 + outer loop + vertex -704.312 143.927 39.8335 + vertex -711.206 148.495 39.5151 + vertex -711.765 146.971 38.3886 + endloop + endfacet + facet normal -0.360737 -0.419278 0.833111 + outer loop + vertex -704.497 146.822 41.5439 + vertex -710.681 149.385 40.156 + vertex -703.429 145.519 41.3509 + endloop + endfacet + facet normal -0.352879 -0.400696 0.845529 + outer loop + vertex -703.429 145.519 41.3509 + vertex -710.681 149.385 40.156 + vertex -711.206 148.495 39.5151 + endloop + endfacet + facet normal -0.298993 -0.552505 0.778037 + outer loop + vertex -713.095 141.867 34.7113 + vertex -721.345 145.597 34.1899 + vertex -713.931 138.872 32.2633 + endloop + endfacet + facet normal -0.262232 -0.521666 0.811849 + outer loop + vertex -713.931 138.872 32.2633 + vertex -721.345 145.597 34.1899 + vertex -722.133 142.508 31.9508 + endloop + endfacet + facet normal -0.308158 -0.509791 0.803213 + outer loop + vertex -712.339 144.658 36.7728 + vertex -720.779 148.506 35.9773 + vertex -713.095 141.867 34.7113 + endloop + endfacet + facet normal -0.264473 -0.466973 0.843795 + outer loop + vertex -713.095 141.867 34.7113 + vertex -720.779 148.506 35.9773 + vertex -721.345 145.597 34.1899 + endloop + endfacet + facet normal -0.323566 -0.486557 0.811521 + outer loop + vertex -711.765 146.971 38.3886 + vertex -720.313 150.812 37.2838 + vertex -712.339 144.658 36.7728 + endloop + endfacet + facet normal -0.27726 -0.430506 0.858948 + outer loop + vertex -712.339 144.658 36.7728 + vertex -720.313 150.812 37.2838 + vertex -720.779 148.506 35.9773 + endloop + endfacet + facet normal -0.337776 -0.476225 0.811861 + outer loop + vertex -711.206 148.495 39.5151 + vertex -719.648 152.16 38.153 + vertex -711.765 146.971 38.3886 + endloop + endfacet + facet normal -0.295902 -0.410315 0.862603 + outer loop + vertex -711.765 146.971 38.3886 + vertex -719.648 152.16 38.153 + vertex -720.313 150.812 37.2838 + endloop + endfacet + facet normal -0.329231 -0.416149 0.847601 + outer loop + vertex -710.681 149.385 40.156 + vertex -718.284 152.551 38.757 + vertex -711.206 148.495 39.5151 + endloop + endfacet + facet normal -0.278178 -0.516257 0.809998 + outer loop + vertex -721.345 145.597 34.1899 + vertex -730.031 149.651 33.7905 + vertex -722.133 142.508 31.9508 + endloop + endfacet + facet normal -0.27613 -0.463564 0.841938 + outer loop + vertex -720.779 148.506 35.9773 + vertex -729.64 152.677 35.3678 + vertex -721.345 145.597 34.1899 + endloop + endfacet + facet normal -0.238254 -0.424447 0.873545 + outer loop + vertex -721.345 145.597 34.1899 + vertex -729.64 152.677 35.3678 + vertex -730.031 149.651 33.7905 + endloop + endfacet + facet normal -0.281179 -0.429325 0.858264 + outer loop + vertex -720.313 150.812 37.2838 + vertex -729.35 155.059 36.4472 + vertex -720.779 148.506 35.9773 + endloop + endfacet + facet normal -0.289554 -0.413771 0.863106 + outer loop + vertex -719.648 152.16 38.153 + vertex -728.772 156.354 37.1025 + vertex -720.313 150.812 37.2838 + endloop + endfacet + facet normal -0.250333 -0.421796 0.871448 + outer loop + vertex -729.64 152.677 35.3678 + vertex -738.385 156.879 34.8894 + vertex -730.031 149.651 33.7905 + endloop + endfacet + facet normal -0.218495 -0.388599 0.895126 + outer loop + vertex -730.031 149.651 33.7905 + vertex -738.385 156.879 34.8894 + vertex -738.621 153.767 33.4807 + endloop + endfacet + facet normal -0.228987 -0.386939 0.893221 + outer loop + vertex -738.385 156.879 34.8894 + vertex -746.89 161.076 34.5271 + vertex -738.621 153.767 33.4807 + endloop + endfacet + facet normal -0.209208 -0.366479 0.906601 + outer loop + vertex -738.621 153.767 33.4807 + vertex -746.89 161.076 34.5271 + vertex -747.059 157.929 33.2161 + endloop + endfacet + facet normal -0.215624 -0.365647 0.905433 + outer loop + vertex -746.89 161.076 34.5271 + vertex -755.26 165.379 34.2715 + vertex -747.059 157.929 33.2161 + endloop + endfacet + facet normal -0.199605 -0.349431 0.915454 + outer loop + vertex -747.059 157.929 33.2161 + vertex -755.26 165.379 34.2715 + vertex -755.408 162.234 33.0387 + endloop + endfacet + facet normal -0.206073 -0.348678 0.914307 + outer loop + vertex -755.26 165.379 34.2715 + vertex -763.532 169.869 34.1196 + vertex -755.408 162.234 33.0387 + endloop + endfacet + facet normal -0.19592 -0.338719 0.920263 + outer loop + vertex -755.408 162.234 33.0387 + vertex -763.532 169.869 34.1196 + vertex -763.646 166.712 32.9334 + endloop + endfacet + facet normal -0.204301 -0.337852 0.918758 + outer loop + vertex -763.532 169.869 34.1196 + vertex -771.643 174.534 34.0313 + vertex -763.646 166.712 32.9334 + endloop + endfacet + facet normal -0.201069 -0.334803 0.920586 + outer loop + vertex -763.646 166.712 32.9334 + vertex -771.643 174.534 34.0313 + vertex -771.748 171.386 32.8635 + endloop + endfacet + facet normal -0.211254 -0.333755 0.918683 + outer loop + vertex -771.643 174.534 34.0313 + vertex -779.586 179.406 33.9747 + vertex -771.748 171.386 32.8635 + endloop + endfacet + facet normal -0.216456 -0.338433 0.915756 + outer loop + vertex -771.748 171.386 32.8635 + vertex -779.586 179.406 33.9747 + vertex -779.803 176.32 32.7829 + endloop + endfacet + facet normal -0.225927 -0.337076 0.913968 + outer loop + vertex -779.586 179.406 33.9747 + vertex -787.419 184.519 33.9243 + vertex -779.803 176.32 32.7829 + endloop + endfacet + facet normal -0.231064 -0.341442 0.911058 + outer loop + vertex -779.803 176.32 32.7829 + vertex -787.419 184.519 33.9243 + vertex -787.912 181.535 32.6807 + endloop + endfacet + facet normal -0.238296 -0.339737 0.909832 + outer loop + vertex -787.419 184.519 33.9243 + vertex -795.142 189.866 33.8979 + vertex -787.912 181.535 32.6807 + endloop + endfacet + facet normal -0.236654 -0.338445 0.910741 + outer loop + vertex -787.912 181.535 32.6807 + vertex -795.142 189.866 33.8979 + vertex -795.938 186.786 32.5465 + endloop + endfacet + facet normal -0.243323 -0.3363 0.909778 + outer loop + vertex -795.142 189.866 33.8979 + vertex -802.618 195.39 33.9403 + vertex -795.938 186.786 32.5465 + endloop + endfacet + facet normal -0.258734 -0.346924 0.901499 + outer loop + vertex -795.938 186.786 32.5465 + vertex -802.618 195.39 33.9403 + vertex -803.771 192.601 32.5363 + endloop + endfacet + facet normal -0.255056 -0.348637 0.901886 + outer loop + vertex -802.618 195.39 33.9403 + vertex -809.672 200.966 34.1013 + vertex -803.771 192.601 32.5363 + endloop + endfacet + facet normal -0.287221 -0.368043 0.884335 + outer loop + vertex -803.771 192.601 32.5363 + vertex -809.672 200.966 34.1013 + vertex -810.83 198.157 32.556 + endloop + endfacet + facet normal -0.269079 -0.376667 0.886407 + outer loop + vertex -809.672 200.966 34.1013 + vertex -816.348 206.527 34.4375 + vertex -810.83 198.157 32.556 + endloop + endfacet + facet normal -0.309222 -0.398026 0.863688 + outer loop + vertex -810.83 198.157 32.556 + vertex -816.348 206.527 34.4375 + vertex -817.495 203.715 32.731 + endloop + endfacet + facet normal -0.280472 -0.411788 0.867044 + outer loop + vertex -816.348 206.527 34.4375 + vertex -822.895 212.261 35.0431 + vertex -817.495 203.715 32.731 + endloop + endfacet + facet normal -0.338336 -0.438966 0.832369 + outer loop + vertex -817.495 203.715 32.731 + vertex -822.895 212.261 35.0431 + vertex -824.149 209.516 33.0856 + endloop + endfacet + facet normal -0.266753 -0.397288 0.878069 + outer loop + vertex -816.348 206.527 34.4375 + vertex -822.116 214.486 36.2863 + vertex -822.895 212.261 35.0431 + endloop + endfacet + facet normal -0.302004 -0.458157 0.835994 + outer loop + vertex -822.895 212.261 35.0431 + vertex -829.422 218.285 35.9866 + vertex -824.149 209.516 33.0856 + endloop + endfacet + facet normal -0.373944 -0.486143 0.78983 + outer loop + vertex -824.149 209.516 33.0856 + vertex -829.422 218.285 35.9866 + vertex -830.863 215.819 33.7864 + endloop + endfacet + facet normal -0.224178 -0.414419 0.882044 + outer loop + vertex -822.116 214.486 36.2863 + vertex -828.535 220.432 37.4487 + vertex -822.895 212.261 35.0431 + endloop + endfacet + facet normal -0.295034 -0.451555 0.842053 + outer loop + vertex -822.895 212.261 35.0431 + vertex -828.535 220.432 37.4487 + vertex -829.422 218.285 35.9866 + endloop + endfacet + facet normal -0.150953 -0.361128 0.920217 + outer loop + vertex -821.44 215.63 36.8463 + vertex -827.963 221.708 38.1615 + vertex -822.116 214.486 36.2863 + endloop + endfacet + facet normal -0.21168 -0.402594 0.890567 + outer loop + vertex -822.116 214.486 36.2863 + vertex -827.963 221.708 38.1615 + vertex -828.535 220.432 37.4487 + endloop + endfacet + facet normal -0.0323395 -0.244408 0.969133 + outer loop + vertex -821.44 215.63 36.8463 + vertex -826.649 221.402 38.1281 + vertex -827.963 221.708 38.1615 + endloop + endfacet + facet normal -0.339624 -0.50784 0.791678 + outer loop + vertex -829.422 218.285 35.9866 + vertex -835.747 224.482 37.2481 + vertex -830.863 215.819 33.7864 + endloop + endfacet + facet normal -0.251989 -0.471441 0.84513 + outer loop + vertex -828.535 220.432 37.4487 + vertex -834.691 226.407 38.9464 + vertex -829.422 218.285 35.9866 + endloop + endfacet + facet normal -0.341474 -0.509366 0.7899 + outer loop + vertex -829.422 218.285 35.9866 + vertex -834.691 226.407 38.9464 + vertex -835.747 224.482 37.2481 + endloop + endfacet + facet normal -0.166936 -0.422751 0.890738 + outer loop + vertex -827.963 221.708 38.1615 + vertex -834.174 227.786 39.882 + vertex -828.535 220.432 37.4487 + endloop + endfacet + facet normal -0.256399 -0.475132 0.84173 + outer loop + vertex -828.535 220.432 37.4487 + vertex -834.174 227.786 39.882 + vertex -834.691 226.407 38.9464 + endloop + endfacet + facet normal -0.0537679 -0.333351 0.941268 + outer loop + vertex -826.649 221.402 38.1281 + vertex -834.119 228.688 40.2817 + vertex -827.963 221.708 38.1615 + endloop + endfacet + facet normal -0.134318 -0.394585 0.908989 + outer loop + vertex -827.963 221.708 38.1615 + vertex -834.119 228.688 40.2817 + vertex -834.174 227.786 39.882 + endloop + endfacet + facet normal -0.303576 -0.531147 0.791028 + outer loop + vertex -834.691 226.407 38.9464 + vertex -840.164 231.908 40.5393 + vertex -835.747 224.482 37.2481 + endloop + endfacet + facet normal -0.213597 -0.492535 0.843674 + outer loop + vertex -834.174 227.786 39.882 + vertex -839.431 233.144 41.6789 + vertex -834.691 226.407 38.9464 + endloop + endfacet + facet normal -0.312047 -0.537389 0.78348 + outer loop + vertex -834.691 226.407 38.9464 + vertex -839.431 233.144 41.6789 + vertex -840.164 231.908 40.5393 + endloop + endfacet + facet normal -0.0702925 -0.402472 0.912729 + outer loop + vertex -840.039 234.806 42.5235 + vertex -839.262 233.861 42.1668 + vertex -834.119 228.688 40.2817 + endloop + endfacet + facet normal -0.234752 -0.508239 0.828604 + outer loop + vertex -839.431 233.144 41.6789 + vertex -834.174 227.786 39.882 + vertex -839.262 233.861 42.1668 + endloop + endfacet + facet normal -0.0681443 -0.400683 0.913679 + outer loop + vertex -834.174 227.786 39.882 + vertex -834.119 228.688 40.2817 + vertex -839.262 233.861 42.1668 + endloop + endfacet + facet normal -0.294545 -0.610973 0.734816 + outer loop + vertex -842.89 237.926 43.9033 + vertex -844.905 240.103 44.9058 + vertex -842.998 237.831 43.7812 + endloop + endfacet + facet normal -0.305929 -0.616086 0.725841 + outer loop + vertex -842.998 237.831 43.7812 + vertex -844.905 240.103 44.9058 + vertex -845.376 240.138 44.7371 + endloop + endfacet + facet normal 0.56925 0.163834 0.805676 + outer loop + vertex -840.039 234.806 42.5235 + vertex -842.89 237.926 43.9033 + vertex -839.262 233.861 42.1668 + endloop + endfacet + facet normal -0.313353 -0.595649 0.739603 + outer loop + vertex -839.262 233.861 42.1668 + vertex -842.89 237.926 43.9033 + vertex -842.998 237.831 43.7812 + endloop + endfacet + facet normal -0.193305 -0.520205 0.831877 + outer loop + vertex -839.262 233.861 42.1668 + vertex -842.998 237.831 43.7812 + vertex -839.431 233.144 41.6789 + endloop + endfacet + facet normal -0.291811 -0.567414 0.769992 + outer loop + vertex -839.431 233.144 41.6789 + vertex -842.998 237.831 43.7812 + vertex -843.446 237.291 43.2135 + endloop + endfacet + facet normal -0.262131 -0.587435 0.765642 + outer loop + vertex -842.998 237.831 43.7812 + vertex -845.376 240.138 44.7371 + vertex -843.446 237.291 43.2135 + endloop + endfacet + facet normal -0.320137 -0.606498 0.727786 + outer loop + vertex -843.446 237.291 43.2135 + vertex -845.376 240.138 44.7371 + vertex -845.433 239.355 44.0596 + endloop + endfacet + facet normal 0.54775 0.714313 -0.435576 + outer loop + vertex -841.056 235.813 42.8959 + vertex -842.864 237.766 43.8258 + vertex -840.039 234.806 42.5235 + endloop + endfacet + facet normal 0.050785 0.442396 -0.895381 + outer loop + vertex -840.039 234.806 42.5235 + vertex -842.864 237.766 43.8258 + vertex -842.89 237.926 43.9033 + endloop + endfacet + facet normal -0.0273759 0.432392 -0.90127 + outer loop + vertex -842.864 237.766 43.8258 + vertex -844.984 240.158 45.0381 + vertex -842.89 237.926 43.9033 + endloop + endfacet + facet normal -0.762895 -0.616608 -0.194387 + outer loop + vertex -842.89 237.926 43.9033 + vertex -844.984 240.158 45.0381 + vertex -844.905 240.103 44.9058 + endloop + endfacet + facet normal -0.241496 -0.603962 0.759545 + outer loop + vertex -845.433 239.355 44.0596 + vertex -846.458 240.208 44.4117 + vertex -844.535 236.465 42.047 + endloop + endfacet + facet normal -0.262257 -0.620476 0.739074 + outer loop + vertex -845.433 239.355 44.0596 + vertex -845.376 240.138 44.7371 + vertex -846.458 240.208 44.4117 + endloop + endfacet + facet normal -0.294409 -0.668698 0.682764 + outer loop + vertex -844.905 240.103 44.9058 + vertex -846.061 241.107 45.3914 + vertex -845.376 240.138 44.7371 + endloop + endfacet + facet normal -0.2554 -0.658267 0.708135 + outer loop + vertex -846.061 241.107 45.3914 + vertex -846.458 240.208 44.4117 + vertex -845.376 240.138 44.7371 + endloop + endfacet + facet normal -0.408899 -0.530932 0.742235 + outer loop + vertex -804.511 179.944 23.9871 + vertex -800.482 177.601 24.5307 + vertex -804.751 181.954 25.2921 + endloop + endfacet + facet normal -0.420214 -0.529044 0.737247 + outer loop + vertex -808.234 182.878 23.97 + vertex -804.511 179.944 23.9871 + vertex -804.751 181.954 25.2921 + endloop + endfacet + facet normal -0.427321 -0.525454 0.735728 + outer loop + vertex -812.65 186.278 23.8337 + vertex -808.234 182.878 23.97 + vertex -809.977 185.69 24.9666 + endloop + endfacet + facet normal -0.434954 -0.518591 0.736124 + outer loop + vertex -816.959 189.753 23.7352 + vertex -812.65 186.278 23.8337 + vertex -814.311 188.991 24.7638 + endloop + endfacet + facet normal -0.444823 -0.513374 0.73388 + outer loop + vertex -821.451 193.678 23.7581 + vertex -816.959 189.753 23.7352 + vertex -818.273 192.266 24.6971 + endloop + endfacet + facet normal -0.450099 -0.506439 0.73548 + outer loop + vertex -825.885 197.226 23.4882 + vertex -821.451 193.678 23.7581 + vertex -824.281 197.313 24.5299 + endloop + endfacet + facet normal -0.456129 -0.500184 0.736045 + outer loop + vertex -829.897 200.663 23.3374 + vertex -825.885 197.226 23.4882 + vertex -827.919 200.399 24.3841 + endloop + endfacet + facet normal -0.459606 -0.495418 0.737104 + outer loop + vertex -834.402 204.536 23.1313 + vertex -829.897 200.663 23.3374 + vertex -831.747 203.825 24.309 + endloop + endfacet + facet normal -0.467544 -0.489405 0.736129 + outer loop + vertex -839.029 209.265 23.3374 + vertex -834.402 204.536 23.1313 + vertex -835.576 207.428 24.3091 + endloop + endfacet + facet normal -0.471217 -0.488058 0.73468 + outer loop + vertex -843.769 213.536 23.1344 + vertex -839.029 209.265 23.3374 + vertex -841.448 212.924 24.2161 + endloop + endfacet + facet normal -0.480849 -0.487625 0.728702 + outer loop + vertex -847.919 217.561 23.089 + vertex -843.769 213.536 23.1344 + vertex -845.22 216.497 24.1581 + endloop + endfacet + facet normal -0.489013 -0.492002 0.720278 + outer loop + vertex -852.045 221.474 22.9607 + vertex -847.919 217.561 23.089 + vertex -848.993 220.221 24.177 + endloop + endfacet + facet normal -0.494393 -0.490754 0.717451 + outer loop + vertex -854.946 224.63 23.1206 + vertex -852.045 221.474 22.9607 + vertex -852.179 223.517 24.2654 + endloop + endfacet + facet normal 0.934569 0.128008 -0.331956 + outer loop + vertex -854.74 226.316 24.3515 + vertex -854.946 224.63 23.1206 + vertex -854.787 226.076 24.125 + endloop + endfacet + facet normal -0.54808 -0.553688 0.626927 + outer loop + vertex -852.326 230.388 29.8169 + vertex -853.943 228.086 26.3702 + vertex -852.586 228.07 27.542 + endloop + endfacet + facet normal -0.346909 -0.674697 0.651489 + outer loop + vertex -846.708 242.159 46.2995 + vertex -848.112 240.495 43.8286 + vertex -846.458 240.208 44.4117 + endloop + endfacet + facet normal -0.663849 -0.713483 0.224155 + outer loop + vertex -844.46 239.613 44.8554 + vertex -846.708 242.159 46.2995 + vertex -844.984 240.158 45.0381 + endloop + endfacet + facet normal -0.293285 -0.64604 0.704709 + outer loop + vertex -841.883 236.959 43.4941 + vertex -844.46 239.613 44.8554 + vertex -842.864 237.766 43.8258 + endloop + endfacet + facet normal -0.240187 -0.579729 0.778604 + outer loop + vertex -838.262 233.382 41.9478 + vertex -841.883 236.959 43.4941 + vertex -841.056 235.813 42.8959 + endloop + endfacet + facet normal 0.125541 -0.231579 0.964682 + outer loop + vertex -834.007 229.467 40.4542 + vertex -838.262 233.382 41.9478 + vertex -834.119 228.688 40.2817 + endloop + endfacet + facet normal 0.0931571 -0.22792 0.969213 + outer loop + vertex -830.445 225.664 39.2175 + vertex -834.007 229.467 40.4542 + vertex -834.119 228.688 40.2817 + endloop + endfacet + facet normal 0.133036 -0.132585 0.982203 + outer loop + vertex -827.023 222.481 38.3245 + vertex -830.445 225.664 39.2175 + vertex -826.649 221.402 38.1281 + endloop + endfacet + facet normal 0.0422193 -0.164629 0.985452 + outer loop + vertex -823.198 218.891 37.5609 + vertex -827.023 222.481 38.3245 + vertex -826.649 221.402 38.1281 + endloop + endfacet + facet normal -0.0750685 -0.246081 0.966338 + outer loop + vertex -818.683 214.398 36.7674 + vertex -823.198 218.891 37.5609 + vertex -820.229 215.321 36.8824 + endloop + endfacet + facet normal -0.0442989 -0.179522 0.982756 + outer loop + vertex -815.309 211.298 36.3532 + vertex -818.683 214.398 36.7674 + vertex -814.261 209.925 36.1496 + endloop + endfacet + facet normal -0.111706 -0.22866 0.967076 + outer loop + vertex -811.266 208 36.0405 + vertex -815.309 211.298 36.3532 + vertex -814.261 209.925 36.1496 + endloop + endfacet + facet normal -0.112988 -0.208053 0.97157 + outer loop + vertex -805.846 203.709 35.7517 + vertex -811.266 208 36.0405 + vertex -807.575 204.192 35.6543 + endloop + endfacet + facet normal -0.105238 -0.179947 0.978031 + outer loop + vertex -802.286 200.6 35.5629 + vertex -805.846 203.709 35.7517 + vertex -801.041 198.921 35.3879 + endloop + endfacet + facet normal -0.136979 -0.171907 0.975543 + outer loop + vertex -743.865 164.975 36.2243 + vertex -749.458 167.592 35.9001 + vertex -745.142 164.878 36.0278 + endloop + endfacet + facet normal -0.153145 -0.155979 0.975816 + outer loop + vertex -733.056 159.846 37.0278 + vertex -738.456 162.589 36.6188 + vertex -736.787 160.955 36.6194 + endloop + endfacet + facet normal -0.166597 -0.140416 0.975976 + outer loop + vertex -728.023 157.895 37.6062 + vertex -733.056 159.846 37.0278 + vertex -727.166 156.545 37.5583 + endloop + endfacet + facet normal -0.199017 -0.160675 0.966735 + outer loop + vertex -722.89 155.416 38.2507 + vertex -728.023 157.895 37.6062 + vertex -727.166 156.545 37.5583 + endloop + endfacet + facet normal -0.25551 -0.245562 0.935101 + outer loop + vertex -716.679 152.924 39.2936 + vertex -722.89 155.416 38.2507 + vertex -718.284 152.551 38.757 + endloop + endfacet + facet normal -0.278817 -0.246367 0.928205 + outer loop + vertex -711.953 150.747 40.1354 + vertex -716.679 152.924 39.2936 + vertex -710.681 149.385 40.156 + endloop + endfacet + facet normal -0.308828 -0.274667 0.910595 + outer loop + vertex -708.028 148.706 40.8509 + vertex -711.953 150.747 40.1354 + vertex -710.681 149.385 40.156 + endloop + endfacet + facet normal -0.336689 -0.30318 0.891472 + outer loop + vertex -704.198 146.947 41.6992 + vertex -708.028 148.706 40.8509 + vertex -704.497 146.822 41.5439 + endloop + endfacet + facet normal -0.378395 -0.363897 0.851114 + outer loop + vertex -701.52 145.855 42.4231 + vertex -704.198 146.947 41.6992 + vertex -701.039 145.533 42.4993 + endloop + endfacet + facet normal -0.418763 -0.437215 0.795915 + outer loop + vertex -698.863 144.783 43.2318 + vertex -701.52 145.855 42.4231 + vertex -701.039 145.533 42.4993 + endloop + endfacet + facet normal -0.457639 -0.62156 0.635791 + outer loop + vertex -696.119 143.781 44.2272 + vertex -698.863 144.783 43.2318 + vertex -697.781 144.27 43.5095 + endloop + endfacet + facet normal -0.45554 -0.641141 0.617593 + outer loop + vertex -697.781 144.27 43.5095 + vertex -695.675 143.55 44.3153 + vertex -696.119 143.781 44.2272 + endloop + endfacet + facet normal -0.423893 -0.478204 0.769178 + outer loop + vertex -701.039 145.533 42.4993 + vertex -697.781 144.27 43.5095 + vertex -698.863 144.783 43.2318 + endloop + endfacet + facet normal -0.350123 -0.275796 0.895182 + outer loop + vertex -704.497 146.822 41.5439 + vertex -701.039 145.533 42.4993 + vertex -704.198 146.947 41.6992 + endloop + endfacet + facet normal -0.299469 -0.219827 0.928436 + outer loop + vertex -710.681 149.385 40.156 + vertex -704.497 146.822 41.5439 + vertex -708.028 148.706 40.8509 + endloop + endfacet + facet normal -0.263552 -0.217679 0.939764 + outer loop + vertex -718.284 152.551 38.757 + vertex -710.681 149.385 40.156 + vertex -716.679 152.924 39.2936 + endloop + endfacet + facet normal -0.194515 -0.141209 0.970682 + outer loop + vertex -727.166 156.545 37.5583 + vertex -718.284 152.551 38.757 + vertex -722.89 155.416 38.2507 + endloop + endfacet + facet normal -0.129864 -0.0728062 0.988855 + outer loop + vertex -736.787 160.955 36.6194 + vertex -727.166 156.545 37.5583 + vertex -733.056 159.846 37.0278 + endloop + endfacet + facet normal -0.139267 -0.148958 0.978987 + outer loop + vertex -745.142 164.878 36.0278 + vertex -736.787 160.955 36.6194 + vertex -743.865 164.975 36.2243 + endloop + endfacet + facet normal -0.105984 -0.122091 0.986844 + outer loop + vertex -753.484 169.125 35.6574 + vertex -745.142 164.878 36.0278 + vertex -749.458 167.592 35.9001 + endloop + endfacet + facet normal -0.117319 -0.180026 0.976641 + outer loop + vertex -801.041 198.921 35.3879 + vertex -793.442 193.169 35.2405 + vertex -798.399 197.78 35.4949 + endloop + endfacet + facet normal -0.427903 -0.516248 0.74188 + outer loop + vertex -809.977 185.69 24.9666 + vertex -814.311 188.991 24.7638 + vertex -812.65 186.278 23.8337 + endloop + endfacet + facet normal -0.420237 -0.523098 0.741464 + outer loop + vertex -804.751 181.954 25.2921 + vertex -809.977 185.69 24.9666 + vertex -808.234 182.878 23.97 + endloop + endfacet + facet normal -0.105571 -0.180273 0.977935 + outer loop + vertex -807.575 204.192 35.6543 + vertex -801.041 198.921 35.3879 + vertex -805.846 203.709 35.7517 + endloop + endfacet + facet normal -0.444514 -0.511845 0.735134 + outer loop + vertex -818.273 192.266 24.6971 + vertex -821.343 195.082 24.8012 + vertex -821.451 193.678 23.7581 + endloop + endfacet + facet normal -0.434852 -0.511054 0.741436 + outer loop + vertex -814.311 188.991 24.7638 + vertex -818.273 192.266 24.6971 + vertex -816.959 189.753 23.7352 + endloop + endfacet + facet normal -0.074854 -0.17217 0.982219 + outer loop + vertex -814.261 209.925 36.1496 + vertex -807.575 204.192 35.6543 + vertex -811.266 208 36.0405 + endloop + endfacet + facet normal -0.45279 -0.498875 0.738989 + outer loop + vertex -824.281 197.313 24.5299 + vertex -827.919 200.399 24.3841 + vertex -825.885 197.226 23.4882 + endloop + endfacet + facet normal -0.453863 -0.508564 0.73169 + outer loop + vertex -821.343 195.082 24.8012 + vertex -824.281 197.313 24.5299 + vertex -821.451 193.678 23.7581 + endloop + endfacet + facet normal -0.0194542 -0.155631 0.987624 + outer loop + vertex -820.229 215.321 36.8824 + vertex -814.261 209.925 36.1496 + vertex -818.683 214.398 36.7674 + endloop + endfacet + facet normal -0.459755 -0.488484 0.741625 + outer loop + vertex -831.747 203.825 24.309 + vertex -835.576 207.428 24.3091 + vertex -834.402 204.536 23.1313 + endloop + endfacet + facet normal -0.457071 -0.494589 0.739235 + outer loop + vertex -827.919 200.399 24.3841 + vertex -831.747 203.825 24.309 + vertex -829.897 200.663 23.3374 + endloop + endfacet + facet normal 0.0654192 -0.133511 0.988886 + outer loop + vertex -826.649 221.402 38.1281 + vertex -820.229 215.321 36.8824 + vertex -823.198 218.891 37.5609 + endloop + endfacet + facet normal -0.472257 -0.488513 0.733709 + outer loop + vertex -838.506 210.42 24.4424 + vertex -841.448 212.924 24.2161 + vertex -839.029 209.265 23.3374 + endloop + endfacet + facet normal -0.468077 -0.491231 0.734572 + outer loop + vertex -835.576 207.428 24.3091 + vertex -838.506 210.42 24.4424 + vertex -839.029 209.265 23.3374 + endloop + endfacet + facet normal 0.284552 0.00836521 0.958624 + outer loop + vertex -834.119 228.688 40.2817 + vertex -826.649 221.402 38.1281 + vertex -830.445 225.664 39.2175 + endloop + endfacet + facet normal -0.481212 -0.491214 0.726047 + outer loop + vertex -845.22 216.497 24.1581 + vertex -848.993 220.221 24.177 + vertex -847.919 217.561 23.089 + endloop + endfacet + facet normal -0.471302 -0.485565 0.736275 + outer loop + vertex -841.448 212.924 24.2161 + vertex -845.22 216.497 24.1581 + vertex -843.769 213.536 23.1344 + endloop + endfacet + facet normal -0.36029 -0.585752 0.726006 + outer loop + vertex -841.349 230.036 38.441 + vertex -840.164 231.908 40.5393 + vertex -844.535 236.465 42.047 + endloop + endfacet + facet normal -0.276777 -0.557543 0.782649 + outer loop + vertex -840.164 231.908 40.5393 + vertex -839.431 233.144 41.6789 + vertex -843.446 237.291 43.2135 + endloop + endfacet + facet normal 0.1305 -0.227327 0.965035 + outer loop + vertex -840.039 234.806 42.5235 + vertex -834.119 228.688 40.2817 + vertex -838.262 233.382 41.9478 + endloop + endfacet + facet normal -0.494241 -0.489135 0.71866 + outer loop + vertex -852.179 223.517 24.2654 + vertex -853.797 225.571 24.5513 + vertex -854.946 224.63 23.1206 + endloop + endfacet + facet normal -0.489027 -0.492139 0.720174 + outer loop + vertex -848.993 220.221 24.177 + vertex -852.179 223.517 24.2654 + vertex -852.045 221.474 22.9607 + endloop + endfacet + facet normal -0.319906 -0.606364 0.727999 + outer loop + vertex -843.446 237.291 43.2135 + vertex -845.433 239.355 44.0596 + vertex -844.535 236.465 42.047 + endloop + endfacet + facet normal -0.182352 -0.555168 0.811502 + outer loop + vertex -842.864 237.766 43.8258 + vertex -841.056 235.813 42.8959 + vertex -841.883 236.959 43.4941 + endloop + endfacet + facet normal 0.140457 -0.215439 0.966363 + outer loop + vertex -841.056 235.813 42.8959 + vertex -840.039 234.806 42.5235 + vertex -838.262 233.382 41.9478 + endloop + endfacet + facet normal -0.642256 -0.712395 0.282843 + outer loop + vertex -844.984 240.158 45.0381 + vertex -842.864 237.766 43.8258 + vertex -844.46 239.613 44.8554 + endloop + endfacet + facet normal -0.6754 -0.731436 -0.0940069 + outer loop + vertex -844.905 240.103 44.9058 + vertex -844.984 240.158 45.0381 + vertex -846.061 241.107 45.3914 + endloop + endfacet + facet normal -0.58515 -0.42672 0.689572 + outer loop + vertex -854.528 226.279 24.4957 + vertex -854.774 226.319 24.3111 + vertex -854.946 224.63 23.1206 + endloop + endfacet + facet normal -0.510498 -0.470712 0.719599 + outer loop + vertex -853.797 225.571 24.5513 + vertex -854.528 226.279 24.4957 + vertex -854.946 224.63 23.1206 + endloop + endfacet + facet normal -0.447472 -0.59581 0.666918 + outer loop + vertex -844.535 236.465 42.047 + vertex -845.347 233.846 39.1626 + vertex -841.349 230.036 38.441 + endloop + endfacet + facet normal -0.149429 -0.697336 0.700995 + outer loop + vertex -846.458 240.208 44.4117 + vertex -846.061 241.107 45.3914 + vertex -846.708 242.159 46.2995 + endloop + endfacet + facet normal -0.691845 0.461701 -0.555141 + outer loop + vertex -854.774 226.319 24.3111 + vertex -854.787 226.076 24.125 + vertex -854.946 224.63 23.1206 + endloop + endfacet + facet normal -0.473883 -0.724252 0.500893 + outer loop + vertex -844.984 240.158 45.0381 + vertex -846.708 242.159 46.2995 + vertex -846.061 241.107 45.3914 + endloop + endfacet + facet normal -0.349706 -0.579064 0.736472 + outer loop + vertex -844.535 236.465 42.047 + vertex -840.164 231.908 40.5393 + vertex -843.446 237.291 43.2135 + endloop + endfacet + facet normal -0.374665 -0.874435 0.308204 + outer loop + vertex -708.402 136.356 317.948 + vertex -706.815 134.824 315.531 + vertex -702 133.564 317.809 + endloop + endfacet + facet normal -0.375383 -0.873385 0.310301 + outer loop + vertex -702 133.564 317.809 + vertex -706.815 134.824 315.531 + vertex -700.747 132.239 315.594 + endloop + endfacet + facet normal -0.383596 -0.871007 0.306922 + outer loop + vertex -715.785 139.734 318.306 + vertex -714.279 138.101 315.554 + vertex -708.402 136.356 317.948 + endloop + endfacet + facet normal -0.382364 -0.87315 0.302334 + outer loop + vertex -708.402 136.356 317.948 + vertex -714.279 138.101 315.554 + vertex -706.815 134.824 315.531 + endloop + endfacet + facet normal -0.387564 -0.86997 0.304871 + outer loop + vertex -724.924 143.795 318.277 + vertex -722.764 141.888 315.582 + vertex -715.785 139.734 318.306 + endloop + endfacet + facet normal -0.387435 -0.87021 0.304349 + outer loop + vertex -715.785 139.734 318.306 + vertex -722.764 141.888 315.582 + vertex -714.279 138.101 315.554 + endloop + endfacet + facet normal -0.396588 -0.867066 0.301521 + outer loop + vertex -733.87 147.772 317.947 + vertex -731.637 145.909 315.527 + vertex -724.924 143.795 318.277 + endloop + endfacet + facet normal -0.395573 -0.86886 0.297664 + outer loop + vertex -724.924 143.795 318.277 + vertex -731.637 145.909 315.527 + vertex -722.764 141.888 315.582 + endloop + endfacet + facet normal -0.410969 -0.861607 0.297889 + outer loop + vertex -742.298 151.87 318.172 + vertex -740.4 150.044 315.508 + vertex -733.87 147.772 317.947 + endloop + endfacet + facet normal -0.409005 -0.865586 0.288921 + outer loop + vertex -733.87 147.772 317.947 + vertex -740.4 150.044 315.508 + vertex -731.637 145.909 315.527 + endloop + endfacet + facet normal -0.421965 -0.857994 0.292903 + outer loop + vertex -750.931 156.025 317.906 + vertex -749.026 154.267 315.5 + vertex -742.298 151.87 318.172 + endloop + endfacet + facet normal -0.421118 -0.85963 0.289302 + outer loop + vertex -742.298 151.87 318.172 + vertex -749.026 154.267 315.5 + vertex -740.4 150.044 315.508 + endloop + endfacet + facet normal -0.438693 -0.849311 0.293632 + outer loop + vertex -759.307 160.457 318.211 + vertex -757.466 158.568 315.498 + vertex -750.931 156.025 317.906 + endloop + endfacet + facet normal -0.43597 -0.855338 0.27987 + outer loop + vertex -750.931 156.025 317.906 + vertex -757.466 158.568 315.498 + vertex -749.026 154.267 315.5 + endloop + endfacet + facet normal -0.451498 -0.843488 0.290995 + outer loop + vertex -768.747 165.51 318.212 + vertex -765.928 163.078 315.537 + vertex -759.307 160.457 318.211 + endloop + endfacet + facet normal -0.449971 -0.846642 0.284118 + outer loop + vertex -759.307 160.457 318.211 + vertex -765.928 163.078 315.537 + vertex -757.466 158.568 315.498 + endloop + endfacet + facet normal -0.467846 -0.839172 0.277328 + outer loop + vertex -777.202 170.124 317.909 + vertex -774.503 167.825 315.506 + vertex -768.747 165.51 318.212 + endloop + endfacet + facet normal -0.466649 -0.841255 0.272999 + outer loop + vertex -768.747 165.51 318.212 + vertex -774.503 167.825 315.506 + vertex -765.928 163.078 315.537 + endloop + endfacet + facet normal -0.488317 -0.831404 0.265168 + outer loop + vertex -785.201 174.898 318.147 + vertex -782.841 172.668 315.503 + vertex -777.202 170.124 317.909 + endloop + endfacet + facet normal -0.485853 -0.836231 0.25429 + outer loop + vertex -777.202 170.124 317.909 + vertex -782.841 172.668 315.503 + vertex -774.503 167.825 315.506 + endloop + endfacet + facet normal -0.50673 -0.825545 0.248394 + outer loop + vertex -793.235 179.764 317.931 + vertex -790.919 177.613 315.506 + vertex -785.201 174.898 318.147 + endloop + endfacet + facet normal -0.506019 -0.826839 0.245524 + outer loop + vertex -785.201 174.898 318.147 + vertex -790.919 177.613 315.506 + vertex -782.841 172.668 315.503 + endloop + endfacet + facet normal -0.528348 -0.817732 0.228392 + outer loop + vertex -800.954 184.838 318.24 + vertex -798.828 182.703 315.514 + vertex -793.235 179.764 317.931 + endloop + endfacet + facet normal -0.527317 -0.819724 0.223584 + outer loop + vertex -793.235 179.764 317.931 + vertex -798.828 182.703 315.514 + vertex -790.919 177.613 315.506 + endloop + endfacet + facet normal -0.546605 -0.813025 0.20053 + outer loop + vertex -809.33 190.462 318.212 + vertex -806.724 188.052 315.541 + vertex -800.954 184.838 318.24 + endloop + endfacet + facet normal -0.548175 -0.810312 0.207118 + outer loop + vertex -800.954 184.838 318.24 + vertex -806.724 188.052 315.541 + vertex -798.828 182.703 315.514 + endloop + endfacet + facet normal -0.567311 -0.80719 0.163101 + outer loop + vertex -817.129 195.874 317.867 + vertex -814.605 193.617 315.48 + vertex -809.33 190.462 318.212 + endloop + endfacet + facet normal -0.56934 -0.804243 0.170424 + outer loop + vertex -809.33 190.462 318.212 + vertex -814.605 193.617 315.48 + vertex -806.724 188.052 315.541 + endloop + endfacet + facet normal -0.593191 -0.794458 0.130234 + outer loop + vertex -824.714 201.575 318.1 + vertex -822.249 199.299 315.442 + vertex -817.129 195.874 317.867 + endloop + endfacet + facet normal -0.592181 -0.795877 0.126097 + outer loop + vertex -817.129 195.874 317.867 + vertex -822.249 199.299 315.442 + vertex -814.605 193.617 315.48 + endloop + endfacet + facet normal -0.613364 -0.782747 0.105318 + outer loop + vertex -832.514 207.652 317.835 + vertex -829.634 205.069 315.414 + vertex -824.714 201.575 318.1 + endloop + endfacet + facet normal -0.612662 -0.783618 0.102899 + outer loop + vertex -824.714 201.575 318.1 + vertex -829.634 205.069 315.414 + vertex -822.249 199.299 315.442 + endloop + endfacet + facet normal -0.639676 -0.765077 0.0739699 + outer loop + vertex -840.113 214.035 318.139 + vertex -836.972 211.142 315.385 + vertex -832.514 207.652 317.835 + endloop + endfacet + facet normal -0.636459 -0.768741 0.0629017 + outer loop + vertex -832.514 207.652 317.835 + vertex -836.972 211.142 315.385 + vertex -829.634 205.069 315.414 + endloop + endfacet + facet normal -0.658335 -0.751195 0.0479655 + outer loop + vertex -848.094 221.033 318.212 + vertex -844.544 217.743 315.401 + vertex -840.113 214.035 318.139 + endloop + endfacet + facet normal -0.656475 -0.753161 0.0422917 + outer loop + vertex -840.113 214.035 318.139 + vertex -844.544 217.743 315.401 + vertex -836.972 211.142 315.385 + endloop + endfacet + facet normal -0.671951 -0.740347 0.0191683 + outer loop + vertex -854.281 226.642 317.949 + vertex -851.659 224.196 315.353 + vertex -848.094 221.033 318.212 + endloop + endfacet + facet normal -0.671718 -0.740573 0.0186272 + outer loop + vertex -848.094 221.033 318.212 + vertex -851.659 224.196 315.353 + vertex -844.544 217.743 315.401 + endloop + endfacet + facet normal -0.667634 -0.744487 -0.00210193 + outer loop + vertex -859.986 231.889 317.77 + vertex -859.093 231.095 315.687 + vertex -858.286 230.364 317.933 + endloop + endfacet + facet normal -0.678065 -0.734987 0.00473539 + outer loop + vertex -858.286 230.364 317.933 + vertex -859.093 231.095 315.687 + vertex -856.677 228.864 315.35 + endloop + endfacet + facet normal -0.391939 -0.89607 0.208429 + outer loop + vertex -707.942 134.849 313.519 + vertex -704.318 133.338 313.838 + vertex -706.815 134.824 315.531 + endloop + endfacet + facet normal -0.382585 -0.898474 0.215344 + outer loop + vertex -700.896 131.825 313.605 + vertex -700.747 132.239 315.594 + vertex -704.318 133.338 313.838 + endloop + endfacet + facet normal -0.384333 -0.896577 0.220087 + outer loop + vertex -700.747 132.239 315.594 + vertex -706.815 134.824 315.531 + vertex -704.318 133.338 313.838 + endloop + endfacet + facet normal -0.396851 -0.894042 0.20784 + outer loop + vertex -716.147 138.444 313.462 + vertex -711.726 136.547 313.744 + vertex -714.279 138.101 315.554 + endloop + endfacet + facet normal -0.390113 -0.897106 0.207393 + outer loop + vertex -707.942 134.849 313.519 + vertex -706.815 134.824 315.531 + vertex -711.726 136.547 313.744 + endloop + endfacet + facet normal -0.391987 -0.894476 0.215077 + outer loop + vertex -706.815 134.824 315.531 + vertex -714.279 138.101 315.554 + vertex -711.726 136.547 313.744 + endloop + endfacet + facet normal -0.401321 -0.890647 0.213752 + outer loop + vertex -724.915 142.352 313.477 + vertex -720.252 140.313 313.735 + vertex -722.764 141.888 315.582 + endloop + endfacet + facet normal -0.394297 -0.895763 0.205276 + outer loop + vertex -716.147 138.444 313.462 + vertex -714.279 138.101 315.554 + vertex -720.252 140.313 313.735 + endloop + endfacet + facet normal -0.397024 -0.891062 0.219954 + outer loop + vertex -714.279 138.101 315.554 + vertex -722.764 141.888 315.582 + vertex -720.252 140.313 313.735 + endloop + endfacet + facet normal -0.412678 -0.887045 0.207 + outer loop + vertex -733.672 146.38 313.488 + vertex -729.032 144.282 313.745 + vertex -731.637 145.909 315.527 + endloop + endfacet + facet normal -0.402792 -0.889562 0.215495 + outer loop + vertex -724.915 142.352 313.477 + vertex -722.764 141.888 315.582 + vertex -729.032 144.282 313.745 + endloop + endfacet + facet normal -0.4037 -0.887837 0.220843 + outer loop + vertex -722.764 141.888 315.582 + vertex -731.637 145.909 315.527 + vertex -729.032 144.282 313.745 + endloop + endfacet + facet normal -0.425242 -0.88168 0.204476 + outer loop + vertex -742.389 150.539 313.508 + vertex -737.765 148.366 313.754 + vertex -740.4 150.044 315.508 + endloop + endfacet + facet normal -0.415616 -0.884862 0.210434 + outer loop + vertex -733.672 146.38 313.488 + vertex -731.637 145.909 315.527 + vertex -737.765 148.366 313.754 + endloop + endfacet + facet normal -0.416823 -0.882485 0.217897 + outer loop + vertex -731.637 145.909 315.527 + vertex -740.4 150.044 315.508 + vertex -737.765 148.366 313.754 + endloop + endfacet + facet normal -0.438638 -0.876435 0.198641 + outer loop + vertex -751.092 154.852 313.519 + vertex -746.501 152.61 313.768 + vertex -749.026 154.267 315.5 + endloop + endfacet + facet normal -0.429319 -0.878566 0.209299 + outer loop + vertex -742.389 150.539 313.508 + vertex -740.4 150.044 315.508 + vertex -746.501 152.61 313.768 + endloop + endfacet + facet normal -0.429817 -0.87754 0.212556 + outer loop + vertex -740.4 150.044 315.508 + vertex -749.026 154.267 315.5 + vertex -746.501 152.61 313.768 + endloop + endfacet + facet normal -0.451995 -0.869519 0.199089 + outer loop + vertex -759.442 159.141 313.518 + vertex -755.05 156.917 313.771 + vertex -757.466 158.568 315.498 + endloop + endfacet + facet normal -0.442619 -0.87326 0.203729 + outer loop + vertex -751.092 154.852 313.519 + vertex -749.026 154.267 315.5 + vertex -755.05 156.917 313.771 + endloop + endfacet + facet normal -0.443809 -0.870752 0.211719 + outer loop + vertex -749.026 154.267 315.5 + vertex -757.466 158.568 315.498 + vertex -755.05 156.917 313.771 + endloop + endfacet + facet normal -0.469467 -0.86076 0.196708 + outer loop + vertex -767.647 163.557 313.528 + vertex -763.289 161.236 313.775 + vertex -765.928 163.078 315.537 + endloop + endfacet + facet normal -0.457334 -0.865185 0.205669 + outer loop + vertex -759.442 159.141 313.518 + vertex -757.466 158.568 315.498 + vertex -763.289 161.236 313.775 + endloop + endfacet + facet normal -0.458652 -0.862329 0.21454 + outer loop + vertex -757.466 158.568 315.498 + vertex -765.928 163.078 315.537 + vertex -763.289 161.236 313.775 + endloop + endfacet + facet normal -0.487347 -0.853284 0.185471 + outer loop + vertex -776.11 168.312 313.525 + vertex -771.636 165.811 313.777 + vertex -774.503 167.825 315.506 + endloop + endfacet + facet normal -0.472645 -0.858253 0.200024 + outer loop + vertex -767.647 163.557 313.528 + vertex -765.928 163.078 315.537 + vertex -771.636 165.811 313.777 + endloop + endfacet + facet normal -0.474112 -0.855154 0.209592 + outer loop + vertex -765.928 163.078 315.537 + vertex -774.503 167.825 315.506 + vertex -771.636 165.811 313.777 + endloop + endfacet + facet normal -0.506817 -0.845072 0.170264 + outer loop + vertex -784.477 173.252 313.531 + vertex -780.115 170.686 313.777 + vertex -782.841 172.668 315.503 + endloop + endfacet + facet normal -0.491702 -0.849813 0.189857 + outer loop + vertex -776.11 168.312 313.525 + vertex -774.503 167.825 315.506 + vertex -780.115 170.686 313.777 + endloop + endfacet + facet normal -0.492608 -0.847902 0.195958 + outer loop + vertex -774.503 167.825 315.506 + vertex -782.841 172.668 315.503 + vertex -780.115 170.686 313.777 + endloop + endfacet + facet normal -0.527956 -0.834721 0.156536 + outer loop + vertex -792.486 178.233 313.526 + vertex -788.305 175.636 313.78 + vertex -790.919 177.613 315.506 + endloop + endfacet + facet normal -0.512077 -0.840733 0.175912 + outer loop + vertex -784.477 173.252 313.531 + vertex -782.841 172.668 315.503 + vertex -788.305 175.636 313.78 + endloop + endfacet + facet normal -0.513175 -0.838493 0.183254 + outer loop + vertex -782.841 172.668 315.503 + vertex -790.919 177.613 315.506 + vertex -788.305 175.636 313.78 + endloop + endfacet + facet normal -0.548236 -0.825548 0.133817 + outer loop + vertex -800.302 183.357 313.514 + vertex -796.209 180.682 313.774 + vertex -798.828 182.703 315.514 + endloop + endfacet + facet normal -0.534534 -0.829186 0.163473 + outer loop + vertex -792.486 178.233 313.526 + vertex -790.919 177.613 315.506 + vertex -796.209 180.682 313.774 + endloop + endfacet + facet normal -0.534058 -0.830089 0.160421 + outer loop + vertex -790.919 177.613 315.506 + vertex -798.828 182.703 315.514 + vertex -796.209 180.682 313.774 + endloop + endfacet + facet normal -0.571239 -0.814061 0.104836 + outer loop + vertex -808.043 188.715 313.511 + vertex -803.999 185.911 313.767 + vertex -806.724 188.052 315.541 + endloop + endfacet + facet normal -0.555953 -0.819061 0.141621 + outer loop + vertex -800.302 183.357 313.514 + vertex -798.828 182.703 315.514 + vertex -803.999 185.911 313.767 + endloop + endfacet + facet normal -0.555206 -0.820343 0.137056 + outer loop + vertex -798.828 182.703 315.514 + vertex -806.724 188.052 315.541 + vertex -803.999 185.911 313.767 + endloop + endfacet + facet normal -0.591332 -0.804165 0.0603763 + outer loop + vertex -815.807 194.351 313.485 + vertex -811.763 191.398 313.753 + vertex -814.605 193.617 315.48 + endloop + endfacet + facet normal -0.576661 -0.809568 0.109824 + outer loop + vertex -808.043 188.715 313.511 + vertex -806.724 188.052 315.541 + vertex -811.763 191.398 313.753 + endloop + endfacet + facet normal -0.574602 -0.812474 0.098578 + outer loop + vertex -806.724 188.052 315.541 + vertex -814.605 193.617 315.48 + vertex -811.763 191.398 313.753 + endloop + endfacet + facet normal -0.612134 -0.79056 0.0175105 + outer loop + vertex -823.432 200.172 313.461 + vertex -819.506 197.137 313.726 + vertex -822.249 199.299 315.442 + endloop + endfacet + facet normal -0.597494 -0.799159 0.0659294 + outer loop + vertex -815.807 194.351 313.485 + vertex -814.605 193.617 315.48 + vertex -819.506 197.137 313.726 + endloop + endfacet + facet normal -0.595745 -0.801144 0.0570633 + outer loop + vertex -814.605 193.617 315.48 + vertex -822.249 199.299 315.442 + vertex -819.506 197.137 313.726 + endloop + endfacet + facet normal -0.630705 -0.775731 -0.0212856 + outer loop + vertex -830.639 205.941 313.416 + vertex -826.944 202.929 313.695 + vertex -829.634 205.069 315.414 + endloop + endfacet + facet normal -0.6166 -0.786976 0.0217558 + outer loop + vertex -823.432 200.172 313.461 + vertex -822.249 199.299 315.442 + vertex -826.944 202.929 313.695 + endloop + endfacet + facet normal -0.615636 -0.787839 0.0173717 + outer loop + vertex -822.249 199.299 315.442 + vertex -829.634 205.069 315.414 + vertex -826.944 202.929 313.695 + endloop + endfacet + facet normal -0.649727 -0.758051 -0.0566891 + outer loop + vertex -837.681 211.903 313.336 + vertex -834.028 208.75 313.637 + vertex -836.972 211.142 315.385 + endloop + endfacet + facet normal -0.638561 -0.769433 -0.0145815 + outer loop + vertex -830.639 205.941 313.416 + vertex -829.634 205.069 315.414 + vertex -834.028 208.75 313.637 + endloop + endfacet + facet normal -0.637411 -0.770285 -0.0191926 + outer loop + vertex -829.634 205.069 315.414 + vertex -836.972 211.142 315.385 + vertex -834.028 208.75 313.637 + endloop + endfacet + facet normal -0.665614 -0.741483 -0.0846257 + outer loop + vertex -845.111 218.495 313.271 + vertex -841.257 215.002 313.565 + vertex -844.544 217.743 315.401 + endloop + endfacet + facet normal -0.6559 -0.753007 -0.0526779 + outer loop + vertex -837.681 211.903 313.336 + vertex -836.972 211.142 315.385 + vertex -841.257 215.002 313.565 + endloop + endfacet + facet normal -0.656316 -0.75275 -0.0511547 + outer loop + vertex -836.972 211.142 315.385 + vertex -844.544 217.743 315.401 + vertex -841.257 215.002 313.565 + endloop + endfacet + facet normal -0.677897 -0.726326 -0.113608 + outer loop + vertex -852.377 225.201 313.21 + vertex -848.785 221.801 313.516 + vertex -851.659 224.196 315.353 + endloop + endfacet + facet normal -0.669575 -0.73816 -0.0823962 + outer loop + vertex -845.111 218.495 313.271 + vertex -844.544 217.743 315.401 + vertex -848.785 221.801 313.516 + endloop + endfacet + facet normal -0.669082 -0.738419 -0.0840617 + outer loop + vertex -844.544 217.743 315.401 + vertex -851.659 224.196 315.353 + vertex -848.785 221.801 313.516 + endloop + endfacet + facet normal -0.673287 -0.726861 -0.135492 + outer loop + vertex -858.527 231.006 313.351 + vertex -858.117 230.593 313.528 + vertex -859.093 231.095 315.687 + endloop + endfacet + facet normal -0.676263 -0.721208 -0.150089 + outer loop + vertex -857.143 229.755 313.17 + vertex -856.677 228.864 315.35 + vertex -858.117 230.593 313.528 + endloop + endfacet + facet normal -0.682176 -0.717321 -0.141727 + outer loop + vertex -856.677 228.864 315.35 + vertex -859.093 231.095 315.687 + vertex -858.117 230.593 313.528 + endloop + endfacet + facet normal -0.407804 -0.870335 -0.276065 + outer loop + vertex -701.09 131.905 312.087 + vertex -700.371 131.965 310.837 + vertex -699.439 131.196 311.884 + endloop + endfacet + facet normal -0.429166 -0.866671 -0.254357 + outer loop + vertex -699.439 131.196 311.884 + vertex -700.371 131.965 310.837 + vertex -699.078 131.248 311.096 + endloop + endfacet + facet normal -0.425631 -0.90487 0.00696182 + outer loop + vertex -700.896 131.825 313.605 + vertex -701.09 131.905 312.087 + vertex -699.247 131.045 312.994 + endloop + endfacet + facet normal -0.399829 -0.914936 -0.0550351 + outer loop + vertex -699.247 131.045 312.994 + vertex -701.09 131.905 312.087 + vertex -699.439 131.196 311.884 + endloop + endfacet + facet normal -0.381631 -0.894536 -0.232731 + outer loop + vertex -706.887 134.383 312.254 + vertex -706.01 134.318 311.064 + vertex -703.529 132.947 312.266 + endloop + endfacet + facet normal -0.362062 -0.892092 -0.270339 + outer loop + vertex -703.529 132.947 312.266 + vertex -706.01 134.318 311.064 + vertex -703.207 133.273 310.76 + endloop + endfacet + facet normal -0.38613 -0.922265 0.0181946 + outer loop + vertex -707.942 134.849 313.519 + vertex -706.887 134.383 312.254 + vertex -704.318 133.338 313.838 + endloop + endfacet + facet normal -0.393026 -0.918986 0.0315458 + outer loop + vertex -704.318 133.338 313.838 + vertex -706.887 134.383 312.254 + vertex -703.529 132.947 312.266 + endloop + endfacet + facet normal -0.402768 -0.914943 0.0256441 + outer loop + vertex -704.318 133.338 313.838 + vertex -703.529 132.947 312.266 + vertex -700.896 131.825 313.605 + endloop + endfacet + facet normal -0.392735 -0.91965 0.00196916 + outer loop + vertex -700.896 131.825 313.605 + vertex -703.529 132.947 312.266 + vertex -701.09 131.905 312.087 + endloop + endfacet + facet normal -0.394785 -0.876947 -0.274061 + outer loop + vertex -703.529 132.947 312.266 + vertex -703.207 133.273 310.76 + vertex -701.09 131.905 312.087 + endloop + endfacet + facet normal -0.397203 -0.877026 -0.270287 + outer loop + vertex -701.09 131.905 312.087 + vertex -703.207 133.273 310.76 + vertex -700.371 131.965 310.837 + endloop + endfacet + facet normal -0.389255 -0.887048 -0.248246 + outer loop + vertex -715.157 138.005 312.187 + vertex -714.054 137.835 311.062 + vertex -710.835 136.102 312.208 + endloop + endfacet + facet normal -0.3781 -0.88399 -0.274959 + outer loop + vertex -710.835 136.102 312.208 + vertex -714.054 137.835 311.062 + vertex -710.04 136.181 310.861 + endloop + endfacet + facet normal -0.394819 -0.918705 0.00995831 + outer loop + vertex -716.147 138.444 313.462 + vertex -715.157 138.005 312.187 + vertex -711.726 136.547 313.744 + endloop + endfacet + facet normal -0.402818 -0.914745 0.0312885 + outer loop + vertex -711.726 136.547 313.744 + vertex -715.157 138.005 312.187 + vertex -710.835 136.102 312.208 + endloop + endfacet + facet normal -0.407782 -0.912656 0.0278055 + outer loop + vertex -711.726 136.547 313.744 + vertex -710.835 136.102 312.208 + vertex -707.942 134.849 313.519 + endloop + endfacet + facet normal -0.399317 -0.916798 0.00517619 + outer loop + vertex -707.942 134.849 313.519 + vertex -710.835 136.102 312.208 + vertex -706.887 134.383 312.254 + endloop + endfacet + facet normal -0.380957 -0.882267 -0.276543 + outer loop + vertex -710.835 136.102 312.208 + vertex -710.04 136.181 310.861 + vertex -706.887 134.383 312.254 + endloop + endfacet + facet normal -0.396662 -0.884851 -0.24433 + outer loop + vertex -706.887 134.383 312.254 + vertex -710.04 136.181 310.861 + vertex -706.01 134.318 311.064 + endloop + endfacet + facet normal -0.396938 -0.877184 -0.270162 + outer loop + vertex -724.038 141.983 312.226 + vertex -723.012 141.855 311.133 + vertex -719.599 139.984 312.197 + endloop + endfacet + facet normal -0.384244 -0.872328 -0.302326 + outer loop + vertex -719.599 139.984 312.197 + vertex -723.012 141.855 311.133 + vertex -718.746 140.054 310.908 + endloop + endfacet + facet normal -0.400194 -0.916377 -0.0099148 + outer loop + vertex -724.915 142.352 313.477 + vertex -724.038 141.983 312.226 + vertex -720.252 140.313 313.735 + endloop + endfacet + facet normal -0.410523 -0.911602 0.0212752 + outer loop + vertex -720.252 140.313 313.735 + vertex -724.038 141.983 312.226 + vertex -719.599 139.984 312.197 + endloop + endfacet + facet normal -0.413289 -0.910384 0.0198423 + outer loop + vertex -720.252 140.313 313.735 + vertex -719.599 139.984 312.197 + vertex -716.147 138.444 313.462 + endloop + endfacet + facet normal -0.40693 -0.913459 -0.0012431 + outer loop + vertex -716.147 138.444 313.462 + vertex -719.599 139.984 312.197 + vertex -715.157 138.005 312.187 + endloop + endfacet + facet normal -0.388147 -0.869745 -0.304771 + outer loop + vertex -719.599 139.984 312.197 + vertex -718.746 140.054 310.908 + vertex -715.157 138.005 312.187 + endloop + endfacet + facet normal -0.40504 -0.874879 -0.265575 + outer loop + vertex -715.157 138.005 312.187 + vertex -718.746 140.054 310.908 + vertex -714.054 137.835 311.062 + endloop + endfacet + facet normal -0.401683 -0.864659 -0.301687 + outer loop + vertex -732.748 145.981 312.281 + vertex -731.758 145.883 311.245 + vertex -728.418 143.979 312.254 + endloop + endfacet + facet normal -0.3901 -0.859498 -0.330279 + outer loop + vertex -728.418 143.979 312.254 + vertex -731.758 145.883 311.245 + vertex -727.636 144.098 311.021 + endloop + endfacet + facet normal -0.411409 -0.911347 -0.0137634 + outer loop + vertex -733.672 146.38 313.488 + vertex -732.748 145.981 312.281 + vertex -729.032 144.282 313.745 + endloop + endfacet + facet normal -0.419621 -0.907628 0.0113899 + outer loop + vertex -729.032 144.282 313.745 + vertex -732.748 145.981 312.281 + vertex -728.418 143.979 312.254 + endloop + endfacet + facet normal -0.423779 -0.905718 0.00928837 + outer loop + vertex -729.032 144.282 313.745 + vertex -728.418 143.979 312.254 + vertex -724.915 142.352 313.477 + endloop + endfacet + facet normal -0.414687 -0.909697 -0.022045 + outer loop + vertex -724.915 142.352 313.477 + vertex -728.418 143.979 312.254 + vertex -724.038 141.983 312.226 + endloop + endfacet + facet normal -0.392944 -0.857577 -0.331898 + outer loop + vertex -728.418 143.979 312.254 + vertex -727.636 144.098 311.021 + vertex -724.038 141.983 312.226 + endloop + endfacet + facet normal -0.412504 -0.864825 -0.286214 + outer loop + vertex -724.038 141.983 312.226 + vertex -727.636 144.098 311.021 + vertex -723.012 141.855 311.133 + endloop + endfacet + facet normal -0.413605 -0.854722 -0.313659 + outer loop + vertex -741.381 150.1 312.336 + vertex -740.335 149.959 311.339 + vertex -737.054 148.016 312.308 + endloop + endfacet + facet normal -0.397417 -0.847018 -0.353015 + outer loop + vertex -737.054 148.016 312.308 + vertex -740.335 149.959 311.339 + vertex -736.268 148.137 311.134 + endloop + endfacet + facet normal -0.424075 -0.905268 -0.0255056 + outer loop + vertex -742.389 150.539 313.508 + vertex -741.381 150.1 312.336 + vertex -737.765 148.366 313.754 + endloop + endfacet + facet normal -0.433877 -0.90096 0.00474598 + outer loop + vertex -737.765 148.366 313.754 + vertex -741.381 150.1 312.336 + vertex -737.054 148.016 312.308 + endloop + endfacet + facet normal -0.436346 -0.899773 0.00324558 + outer loop + vertex -737.765 148.366 313.754 + vertex -737.054 148.016 312.308 + vertex -733.672 146.38 313.488 + endloop + endfacet + facet normal -0.427218 -0.903703 -0.0283946 + outer loop + vertex -733.672 146.38 313.488 + vertex -737.054 148.016 312.308 + vertex -732.748 145.981 312.281 + endloop + endfacet + facet normal -0.40122 -0.844275 -0.355279 + outer loop + vertex -737.054 148.016 312.308 + vertex -736.268 148.137 311.134 + vertex -732.748 145.981 312.281 + endloop + endfacet + facet normal -0.417538 -0.851152 -0.318123 + outer loop + vertex -732.748 145.981 312.281 + vertex -736.268 148.137 311.134 + vertex -731.758 145.883 311.245 + endloop + endfacet + facet normal -0.423548 -0.845055 -0.326326 + outer loop + vertex -750.105 154.413 312.372 + vertex -749.006 154.234 311.408 + vertex -745.747 152.235 312.354 + endloop + endfacet + facet normal -0.406019 -0.836351 -0.368327 + outer loop + vertex -745.747 152.235 312.354 + vertex -749.006 154.234 311.408 + vertex -744.88 152.312 311.225 + endloop + endfacet + facet normal -0.437051 -0.898865 -0.0320689 + outer loop + vertex -751.092 154.852 313.519 + vertex -750.105 154.413 312.372 + vertex -746.501 152.61 313.768 + endloop + endfacet + facet normal -0.446958 -0.894554 -0.000930523 + outer loop + vertex -746.501 152.61 313.768 + vertex -750.105 154.413 312.372 + vertex -745.747 152.235 312.354 + endloop + endfacet + facet normal -0.450046 -0.893 -0.00298791 + outer loop + vertex -746.501 152.61 313.768 + vertex -745.747 152.235 312.354 + vertex -742.389 150.539 313.508 + endloop + endfacet + facet normal -0.439126 -0.897473 -0.0413645 + outer loop + vertex -742.389 150.539 313.508 + vertex -745.747 152.235 312.354 + vertex -741.381 150.1 312.336 + endloop + endfacet + facet normal -0.409343 -0.833679 -0.3707 + outer loop + vertex -745.747 152.235 312.354 + vertex -744.88 152.312 311.225 + vertex -741.381 150.1 312.336 + endloop + endfacet + facet normal -0.427366 -0.841721 -0.329946 + outer loop + vertex -741.381 150.1 312.336 + vertex -744.88 152.312 311.225 + vertex -740.335 149.959 311.339 + endloop + endfacet + facet normal -0.43178 -0.836038 -0.338538 + outer loop + vertex -758.55 158.732 312.381 + vertex -757.531 158.587 311.44 + vertex -754.388 156.583 312.379 + endloop + endfacet + facet normal -0.417298 -0.829071 -0.37216 + outer loop + vertex -754.388 156.583 312.379 + vertex -757.531 158.587 311.44 + vertex -753.515 156.64 311.274 + endloop + endfacet + facet normal -0.450243 -0.892346 -0.0316088 + outer loop + vertex -759.442 159.141 313.518 + vertex -758.55 158.732 312.381 + vertex -755.05 156.917 313.771 + endloop + endfacet + facet normal -0.458751 -0.888549 -0.00523772 + outer loop + vertex -755.05 156.917 313.771 + vertex -758.55 158.732 312.381 + vertex -754.388 156.583 312.379 + endloop + endfacet + facet normal -0.462936 -0.886358 -0.00775252 + outer loop + vertex -755.05 156.917 313.771 + vertex -754.388 156.583 312.379 + vertex -751.092 154.852 313.519 + endloop + endfacet + facet normal -0.451581 -0.89096 -0.0475853 + outer loop + vertex -751.092 154.852 313.519 + vertex -754.388 156.583 312.379 + vertex -750.105 154.413 312.372 + endloop + endfacet + facet normal -0.419723 -0.82703 -0.373971 + outer loop + vertex -754.388 156.583 312.379 + vertex -753.515 156.64 311.274 + vertex -750.105 154.413 312.372 + endloop + endfacet + facet normal -0.43459 -0.833554 -0.341056 + outer loop + vertex -750.105 154.413 312.372 + vertex -753.515 156.64 311.274 + vertex -749.006 154.234 311.408 + endloop + endfacet + facet normal -0.445301 -0.825477 -0.346834 + outer loop + vertex -766.682 163.08 312.384 + vertex -765.708 162.946 311.453 + vertex -762.619 160.888 312.386 + endloop + endfacet + facet normal -0.42907 -0.817774 -0.383595 + outer loop + vertex -762.619 160.888 312.386 + vertex -765.708 162.946 311.453 + vertex -761.846 160.993 311.298 + endloop + endfacet + facet normal -0.468614 -0.882978 -0.0274138 + outer loop + vertex -767.647 163.557 313.528 + vertex -766.682 163.08 312.384 + vertex -763.289 161.236 313.775 + endloop + endfacet + facet normal -0.474859 -0.880023 -0.00825052 + outer loop + vertex -763.289 161.236 313.775 + vertex -766.682 163.08 312.384 + vertex -762.619 160.888 312.386 + endloop + endfacet + facet normal -0.478703 -0.877913 -0.0106353 + outer loop + vertex -763.289 161.236 313.775 + vertex -762.619 160.888 312.386 + vertex -759.442 159.141 313.518 + endloop + endfacet + facet normal -0.467661 -0.88256 -0.0487934 + outer loop + vertex -759.442 159.141 313.518 + vertex -762.619 160.888 312.386 + vertex -758.55 158.732 312.381 + endloop + endfacet + facet normal -0.432329 -0.815087 -0.385648 + outer loop + vertex -762.619 160.888 312.386 + vertex -761.846 160.993 311.298 + vertex -758.55 158.732 312.381 + endloop + endfacet + facet normal -0.446041 -0.821032 -0.356306 + outer loop + vertex -758.55 158.732 312.381 + vertex -761.846 160.993 311.298 + vertex -757.531 158.587 311.44 + endloop + endfacet + facet normal -0.460957 -0.812839 -0.356105 + outer loop + vertex -775.037 167.768 312.388 + vertex -773.964 167.567 311.459 + vertex -770.82 165.377 312.388 + endloop + endfacet + facet normal -0.443305 -0.804301 -0.395702 + outer loop + vertex -770.82 165.377 312.388 + vertex -773.964 167.567 311.459 + vertex -770.018 165.465 311.309 + endloop + endfacet + facet normal -0.485739 -0.873158 -0.0406625 + outer loop + vertex -776.11 168.312 313.525 + vertex -775.037 167.768 312.388 + vertex -771.636 165.811 313.777 + endloop + endfacet + facet normal -0.493229 -0.869724 -0.0174856 + outer loop + vertex -771.636 165.811 313.777 + vertex -775.037 167.768 312.388 + vertex -770.82 165.377 312.388 + endloop + endfacet + facet normal -0.492802 -0.869972 -0.0171573 + outer loop + vertex -771.636 165.811 313.777 + vertex -770.82 165.377 312.388 + vertex -767.647 163.557 313.528 + endloop + endfacet + facet normal -0.484795 -0.873468 -0.0450229 + outer loop + vertex -767.647 163.557 313.528 + vertex -770.82 165.377 312.388 + vertex -766.682 163.08 312.384 + endloop + endfacet + facet normal -0.445587 -0.802283 -0.397232 + outer loop + vertex -770.82 165.377 312.388 + vertex -770.018 165.465 311.309 + vertex -766.682 163.08 312.384 + endloop + endfacet + facet normal -0.460653 -0.808935 -0.365271 + outer loop + vertex -766.682 163.08 312.384 + vertex -770.018 165.465 311.309 + vertex -765.708 162.946 311.453 + endloop + endfacet + facet normal -0.477283 -0.798001 -0.36796 + outer loop + vertex -783.44 172.725 312.396 + vertex -782.335 172.493 311.465 + vertex -779.273 170.235 312.392 + endloop + endfacet + facet normal -0.45858 -0.789252 -0.408394 + outer loop + vertex -779.273 170.235 312.392 + vertex -782.335 172.493 311.465 + vertex -778.359 170.261 311.314 + endloop + endfacet + facet normal -0.503672 -0.861811 -0.0599746 + outer loop + vertex -784.477 173.252 313.531 + vertex -783.44 172.725 312.396 + vertex -780.115 170.686 313.777 + endloop + endfacet + facet normal -0.512768 -0.857918 -0.0323299 + outer loop + vertex -780.115 170.686 313.777 + vertex -783.44 172.725 312.396 + vertex -779.273 170.235 312.392 + endloop + endfacet + facet normal -0.511037 -0.859002 -0.0309245 + outer loop + vertex -780.115 170.686 313.777 + vertex -779.273 170.235 312.392 + vertex -776.11 168.312 313.525 + endloop + endfacet + facet normal -0.502275 -0.862528 -0.0613633 + outer loop + vertex -776.11 168.312 313.525 + vertex -779.273 170.235 312.392 + vertex -775.037 167.768 312.388 + endloop + endfacet + facet normal -0.459445 -0.78838 -0.409106 + outer loop + vertex -779.273 170.235 312.392 + vertex -778.359 170.261 311.314 + vertex -775.037 167.768 312.388 + endloop + endfacet + facet normal -0.47522 -0.795301 -0.376381 + outer loop + vertex -775.037 167.768 312.388 + vertex -778.359 170.261 311.314 + vertex -773.964 167.567 311.459 + endloop + endfacet + facet normal -0.493622 -0.782949 -0.378586 + outer loop + vertex -791.458 177.707 312.393 + vertex -790.374 177.476 311.457 + vertex -787.501 175.211 312.396 + endloop + endfacet + facet normal -0.471004 -0.773286 -0.42448 + outer loop + vertex -787.501 175.211 312.396 + vertex -790.374 177.476 311.457 + vertex -786.575 175.239 311.317 + endloop + endfacet + facet normal -0.522376 -0.848922 -0.0803421 + outer loop + vertex -792.486 178.233 313.526 + vertex -791.458 177.707 312.393 + vertex -788.305 175.636 313.78 + endloop + endfacet + facet normal -0.532862 -0.844711 -0.0502237 + outer loop + vertex -788.305 175.636 313.78 + vertex -791.458 177.707 312.393 + vertex -787.501 175.211 312.396 + endloop + endfacet + facet normal -0.530242 -0.846477 -0.0481595 + outer loop + vertex -788.305 175.636 313.78 + vertex -787.501 175.211 312.396 + vertex -784.477 173.252 313.531 + endloop + endfacet + facet normal -0.520386 -0.85011 -0.0806919 + outer loop + vertex -784.477 173.252 313.531 + vertex -787.501 175.211 312.396 + vertex -783.44 172.725 312.396 + endloop + endfacet + facet normal -0.47243 -0.771764 -0.425664 + outer loop + vertex -787.501 175.211 312.396 + vertex -786.575 175.239 311.317 + vertex -783.44 172.725 312.396 + endloop + endfacet + facet normal -0.491142 -0.779377 -0.389038 + outer loop + vertex -783.44 172.725 312.396 + vertex -786.575 175.239 311.317 + vertex -782.335 172.493 311.465 + endloop + endfacet + facet normal -0.5054 -0.76234 -0.404239 + outer loop + vertex -799.214 182.799 312.378 + vertex -798.086 182.547 311.443 + vertex -795.354 180.234 312.388 + endloop + endfacet + facet normal -0.484481 -0.75382 -0.443884 + outer loop + vertex -795.354 180.234 312.388 + vertex -798.086 182.547 311.443 + vertex -794.409 180.262 311.31 + endloop + endfacet + facet normal -0.539406 -0.835343 -0.106034 + outer loop + vertex -800.302 183.357 313.514 + vertex -799.214 182.799 312.378 + vertex -796.209 180.682 313.774 + endloop + endfacet + facet normal -0.551825 -0.830809 -0.0724193 + outer loop + vertex -796.209 180.682 313.774 + vertex -799.214 182.799 312.378 + vertex -795.354 180.234 312.388 + endloop + endfacet + facet normal -0.551459 -0.83108 -0.0721057 + outer loop + vertex -796.209 180.682 313.774 + vertex -795.354 180.234 312.388 + vertex -792.486 178.233 313.526 + endloop + endfacet + facet normal -0.541142 -0.834466 -0.104078 + outer loop + vertex -792.486 178.233 313.526 + vertex -795.354 180.234 312.388 + vertex -791.458 177.707 312.393 + endloop + endfacet + facet normal -0.486765 -0.751204 -0.445817 + outer loop + vertex -795.354 180.234 312.388 + vertex -794.409 180.262 311.31 + vertex -791.458 177.707 312.393 + endloop + endfacet + facet normal -0.509926 -0.759891 -0.403164 + outer loop + vertex -791.458 177.707 312.393 + vertex -794.409 180.262 311.31 + vertex -790.374 177.476 311.457 + endloop + endfacet + facet normal -0.514798 -0.737495 -0.437132 + outer loop + vertex -806.866 188.091 312.359 + vertex -805.663 187.806 311.422 + vertex -803.051 185.421 312.37 + endloop + endfacet + facet normal -0.494776 -0.72952 -0.472226 + outer loop + vertex -803.051 185.421 312.37 + vertex -805.663 187.806 311.422 + vertex -802.031 185.428 311.291 + endloop + endfacet + facet normal -0.559737 -0.818751 -0.127832 + outer loop + vertex -808.043 188.715 313.511 + vertex -806.866 188.091 312.359 + vertex -803.999 185.911 313.767 + endloop + endfacet + facet normal -0.570219 -0.815252 -0.101072 + outer loop + vertex -803.999 185.911 313.767 + vertex -806.866 188.091 312.359 + vertex -803.051 185.421 312.37 + endloop + endfacet + facet normal -0.570044 -0.815395 -0.100904 + outer loop + vertex -803.999 185.911 313.767 + vertex -803.051 185.421 312.37 + vertex -800.302 183.357 313.514 + endloop + endfacet + facet normal -0.558967 -0.818446 -0.133046 + outer loop + vertex -800.302 183.357 313.514 + vertex -803.051 185.421 312.37 + vertex -799.214 182.799 312.378 + endloop + endfacet + facet normal -0.496246 -0.727627 -0.473603 + outer loop + vertex -803.051 185.421 312.37 + vertex -802.031 185.428 311.291 + vertex -799.214 182.799 312.378 + endloop + endfacet + facet normal -0.521407 -0.736763 -0.430482 + outer loop + vertex -799.214 182.799 312.378 + vertex -802.031 185.428 311.291 + vertex -798.086 182.547 311.443 + endloop + endfacet + facet normal -0.524808 -0.712763 -0.465344 + outer loop + vertex -814.514 193.67 312.336 + vertex -813.189 193.315 311.386 + vertex -810.683 190.84 312.351 + endloop + endfacet + facet normal -0.505307 -0.705389 -0.497083 + outer loop + vertex -810.683 190.84 312.351 + vertex -813.189 193.315 311.386 + vertex -809.552 190.801 311.257 + endloop + endfacet + facet normal -0.573729 -0.801056 -0.170719 + outer loop + vertex -815.807 194.351 313.485 + vertex -814.514 193.67 312.336 + vertex -811.763 191.398 313.753 + endloop + endfacet + facet normal -0.588398 -0.797072 -0.135882 + outer loop + vertex -811.763 191.398 313.753 + vertex -814.514 193.67 312.336 + vertex -810.683 190.84 312.351 + endloop + endfacet + facet normal -0.585442 -0.799811 -0.132516 + outer loop + vertex -811.763 191.398 313.753 + vertex -810.683 190.84 312.351 + vertex -808.043 188.715 313.511 + endloop + endfacet + facet normal -0.577206 -0.801778 -0.154869 + outer loop + vertex -808.043 188.715 313.511 + vertex -810.683 190.84 312.351 + vertex -806.866 188.091 312.359 + endloop + endfacet + facet normal -0.506152 -0.704133 -0.498003 + outer loop + vertex -810.683 190.84 312.351 + vertex -809.552 190.801 311.257 + vertex -806.866 188.091 312.359 + endloop + endfacet + facet normal -0.52851 -0.711863 -0.462525 + outer loop + vertex -806.866 188.091 312.359 + vertex -809.552 190.801 311.257 + vertex -805.663 187.806 311.422 + endloop + endfacet + facet normal -0.536008 -0.69223 -0.483231 + outer loop + vertex -822.143 199.538 312.301 + vertex -820.74 199.139 311.317 + vertex -818.351 196.587 312.323 + endloop + endfacet + facet normal -0.515328 -0.68526 -0.514642 + outer loop + vertex -818.351 196.587 312.323 + vertex -820.74 199.139 311.317 + vertex -817.073 196.471 311.197 + endloop + endfacet + facet normal -0.585965 -0.778023 -0.226551 + outer loop + vertex -823.432 200.172 313.461 + vertex -822.143 199.538 312.301 + vertex -819.506 197.137 313.726 + endloop + endfacet + facet normal -0.60217 -0.775049 -0.191545 + outer loop + vertex -819.506 197.137 313.726 + vertex -822.143 199.538 312.301 + vertex -818.351 196.587 312.323 + endloop + endfacet + facet normal -0.59866 -0.778828 -0.187174 + outer loop + vertex -819.506 197.137 313.726 + vertex -818.351 196.587 312.323 + vertex -815.807 194.351 313.485 + endloop + endfacet + facet normal -0.591933 -0.779801 -0.203778 + outer loop + vertex -815.807 194.351 313.485 + vertex -818.351 196.587 312.323 + vertex -814.514 193.67 312.336 + endloop + endfacet + facet normal -0.516939 -0.682446 -0.51676 + outer loop + vertex -818.351 196.587 312.323 + vertex -817.073 196.471 311.197 + vertex -814.514 193.67 312.336 + endloop + endfacet + facet normal -0.535494 -0.688279 -0.489406 + outer loop + vertex -814.514 193.67 312.336 + vertex -817.073 196.471 311.197 + vertex -813.189 193.315 311.386 + endloop + endfacet + facet normal -0.54037 -0.666308 -0.513842 + outer loop + vertex -829.425 205.412 312.231 + vertex -828.09 205.119 311.205 + vertex -825.845 202.478 312.27 + endloop + endfacet + facet normal -0.519444 -0.660122 -0.542601 + outer loop + vertex -825.845 202.478 312.27 + vertex -828.09 205.119 311.205 + vertex -824.539 202.413 311.098 + endloop + endfacet + facet normal -0.595485 -0.755791 -0.272356 + outer loop + vertex -830.639 205.941 313.416 + vertex -829.425 205.412 312.231 + vertex -826.944 202.929 313.695 + endloop + endfacet + facet normal -0.614509 -0.752985 -0.235355 + outer loop + vertex -826.944 202.929 313.695 + vertex -829.425 205.412 312.231 + vertex -825.845 202.478 312.27 + endloop + endfacet + facet normal -0.610445 -0.757708 -0.230727 + outer loop + vertex -826.944 202.929 313.695 + vertex -825.845 202.478 312.27 + vertex -823.432 200.172 313.461 + endloop + endfacet + facet normal -0.60032 -0.758658 -0.253091 + outer loop + vertex -823.432 200.172 313.461 + vertex -825.845 202.478 312.27 + vertex -822.143 199.538 312.301 + endloop + endfacet + facet normal -0.519538 -0.659956 -0.542714 + outer loop + vertex -825.845 202.478 312.27 + vertex -824.539 202.413 311.098 + vertex -822.143 199.538 312.301 + endloop + endfacet + facet normal -0.545709 -0.666953 -0.507322 + outer loop + vertex -822.143 199.538 312.301 + vertex -824.539 202.413 311.098 + vertex -820.74 199.139 311.317 + endloop + endfacet + facet normal -0.553283 -0.651267 -0.519355 + outer loop + vertex -836.417 211.36 312.117 + vertex -835.157 211.15 311.037 + vertex -832.928 208.346 312.178 + endloop + endfacet + facet normal -0.528564 -0.644901 -0.552018 + outer loop + vertex -832.928 208.346 312.178 + vertex -835.157 211.15 311.037 + vertex -831.731 208.425 310.94 + endloop + endfacet + facet normal -0.608161 -0.73351 -0.303487 + outer loop + vertex -837.681 211.903 313.336 + vertex -836.417 211.36 312.117 + vertex -834.028 208.75 313.637 + endloop + endfacet + facet normal -0.626565 -0.731003 -0.270279 + outer loop + vertex -834.028 208.75 313.637 + vertex -836.417 211.36 312.117 + vertex -832.928 208.346 312.178 + endloop + endfacet + facet normal -0.62498 -0.733002 -0.268529 + outer loop + vertex -834.028 208.75 313.637 + vertex -832.928 208.346 312.178 + vertex -830.639 205.941 313.416 + endloop + endfacet + facet normal -0.610481 -0.734069 -0.297416 + outer loop + vertex -830.639 205.941 313.416 + vertex -832.928 208.346 312.178 + vertex -829.425 205.412 312.231 + endloop + endfacet + facet normal -0.530042 -0.642585 -0.553299 + outer loop + vertex -832.928 208.346 312.178 + vertex -831.731 208.425 310.94 + vertex -829.425 205.412 312.231 + endloop + endfacet + facet normal -0.548486 -0.646727 -0.530007 + outer loop + vertex -829.425 205.412 312.231 + vertex -831.731 208.425 310.94 + vertex -828.09 205.119 311.205 + endloop + endfacet + facet normal -0.568347 -0.642678 -0.513757 + outer loop + vertex -843.623 217.747 312.008 + vertex -842.242 217.427 310.88 + vertex -839.976 214.484 312.055 + endloop + endfacet + facet normal -0.543588 -0.636799 -0.546809 + outer loop + vertex -839.976 214.484 312.055 + vertex -842.242 217.427 310.88 + vertex -838.781 214.58 310.756 + endloop + endfacet + facet normal -0.62485 -0.715663 -0.312073 + outer loop + vertex -845.111 218.495 313.271 + vertex -843.623 217.747 312.008 + vertex -841.257 215.002 313.565 + endloop + endfacet + facet normal -0.635162 -0.714263 -0.293936 + outer loop + vertex -841.257 215.002 313.565 + vertex -843.623 217.747 312.008 + vertex -839.976 214.484 312.055 + endloop + endfacet + facet normal -0.636387 -0.712491 -0.295583 + outer loop + vertex -841.257 215.002 313.565 + vertex -839.976 214.484 312.055 + vertex -837.681 211.903 313.336 + endloop + endfacet + facet normal -0.620667 -0.713341 -0.325451 + outer loop + vertex -837.681 211.903 313.336 + vertex -839.976 214.484 312.055 + vertex -836.417 211.36 312.117 + endloop + endfacet + facet normal -0.54612 -0.632865 -0.548848 + outer loop + vertex -839.976 214.484 312.055 + vertex -838.781 214.58 310.756 + vertex -836.417 211.36 312.117 + endloop + endfacet + facet normal -0.560465 -0.635752 -0.530753 + outer loop + vertex -836.417 211.36 312.117 + vertex -838.781 214.58 310.756 + vertex -835.157 211.15 311.037 + endloop + endfacet + facet normal -0.586836 -0.636577 -0.500393 + outer loop + vertex -850.882 224.431 311.916 + vertex -849.163 223.72 310.805 + vertex -847.333 221.116 311.972 + endloop + endfacet + facet normal -0.565167 -0.633774 -0.528127 + outer loop + vertex -847.333 221.116 311.972 + vertex -849.163 223.72 310.805 + vertex -845.776 220.824 310.655 + endloop + endfacet + facet normal -0.637115 -0.701668 -0.318977 + outer loop + vertex -852.377 225.201 313.21 + vertex -850.882 224.431 311.916 + vertex -848.785 221.801 313.516 + endloop + endfacet + facet normal -0.648693 -0.699397 -0.30007 + outer loop + vertex -848.785 221.801 313.516 + vertex -850.882 224.431 311.916 + vertex -847.333 221.116 311.972 + endloop + endfacet + facet normal -0.648898 -0.69906 -0.300412 + outer loop + vertex -848.785 221.801 313.516 + vertex -847.333 221.116 311.972 + vertex -845.111 218.495 313.271 + endloop + endfacet + facet normal -0.632748 -0.700287 -0.330497 + outer loop + vertex -845.111 218.495 313.271 + vertex -847.333 221.116 311.972 + vertex -843.623 217.747 312.008 + endloop + endfacet + facet normal -0.566838 -0.629901 -0.530961 + outer loop + vertex -847.333 221.116 311.972 + vertex -845.776 220.824 310.655 + vertex -843.623 217.747 312.008 + endloop + endfacet + facet normal -0.573166 -0.630829 -0.523006 + outer loop + vertex -843.623 217.747 312.008 + vertex -845.776 220.824 310.655 + vertex -842.242 217.427 310.88 + endloop + endfacet + facet normal -0.588734 -0.618817 -0.520056 + outer loop + vertex -856.148 229.528 311.79 + vertex -854.606 229.138 310.507 + vertex -853.927 227.366 311.848 + endloop + endfacet + facet normal -0.580326 -0.620864 -0.52702 + outer loop + vertex -853.927 227.366 311.848 + vertex -854.606 229.138 310.507 + vertex -852.034 226.793 310.438 + endloop + endfacet + facet normal -0.637446 -0.688237 -0.346401 + outer loop + vertex -857.143 229.755 313.17 + vertex -856.148 229.528 311.79 + vertex -855.088 227.706 313.457 + endloop + endfacet + facet normal -0.65451 -0.681244 -0.327907 + outer loop + vertex -855.088 227.706 313.457 + vertex -856.148 229.528 311.79 + vertex -853.927 227.366 311.848 + endloop + endfacet + facet normal -0.656729 -0.677997 -0.330193 + outer loop + vertex -855.088 227.706 313.457 + vertex -853.927 227.366 311.848 + vertex -852.377 225.201 313.21 + endloop + endfacet + facet normal -0.647541 -0.680031 -0.343873 + outer loop + vertex -852.377 225.201 313.21 + vertex -853.927 227.366 311.848 + vertex -850.882 224.431 311.916 + endloop + endfacet + facet normal -0.581801 -0.616146 -0.530916 + outer loop + vertex -853.927 227.366 311.848 + vertex -852.034 226.793 310.438 + vertex -850.882 224.431 311.916 + endloop + endfacet + facet normal -0.591514 -0.614969 -0.521463 + outer loop + vertex -850.882 224.431 311.916 + vertex -852.034 226.793 310.438 + vertex -849.163 223.72 310.805 + endloop + endfacet + facet normal -0.576172 -0.648168 -0.497899 + outer loop + vertex -857.833 230.985 311.965 + vertex -856.811 231.203 310.498 + vertex -857.354 230.688 311.798 + endloop + endfacet + facet normal -0.552057 -0.669915 -0.496434 + outer loop + vertex -857.354 230.688 311.798 + vertex -856.811 231.203 310.498 + vertex -855.85 230.608 310.233 + endloop + endfacet + facet normal -0.611607 -0.733991 -0.295288 + outer loop + vertex -858.527 231.006 313.351 + vertex -857.833 230.985 311.965 + vertex -858.117 230.593 313.528 + endloop + endfacet + facet normal -0.576099 -0.761965 -0.295837 + outer loop + vertex -858.117 230.593 313.528 + vertex -857.833 230.985 311.965 + vertex -857.354 230.688 311.798 + endloop + endfacet + facet normal -0.682424 -0.648882 -0.336526 + outer loop + vertex -858.117 230.593 313.528 + vertex -857.354 230.688 311.798 + vertex -857.143 229.755 313.17 + endloop + endfacet + facet normal -0.648824 -0.67184 -0.357293 + outer loop + vertex -857.143 229.755 313.17 + vertex -857.354 230.688 311.798 + vertex -856.148 229.528 311.79 + endloop + endfacet + facet normal -0.587991 -0.607371 -0.534197 + outer loop + vertex -857.354 230.688 311.798 + vertex -855.85 230.608 310.233 + vertex -856.148 229.528 311.79 + endloop + endfacet + facet normal -0.594707 -0.602592 -0.532171 + outer loop + vertex -856.148 229.528 311.79 + vertex -855.85 230.608 310.233 + vertex -854.606 229.138 310.507 + endloop + endfacet + facet normal 0.357629 -0.902883 0.238547 + outer loop + vertex -858.292 230.961 312.828 + vertex -857.911 230.921 312.105 + vertex -858.527 231.006 313.351 + endloop + endfacet + facet normal 0.888178 -0.106994 0.44687 + outer loop + vertex -858.527 231.006 313.351 + vertex -857.911 230.921 312.105 + vertex -857.833 230.985 311.965 + endloop + endfacet + facet normal 0.833271 0.148404 0.532575 + outer loop + vertex -857.911 230.921 312.105 + vertex -857.305 231.073 311.115 + vertex -857.833 230.985 311.965 + endloop + endfacet + facet normal 0.499944 -0.836642 0.223801 + outer loop + vertex -857.833 230.985 311.965 + vertex -857.305 231.073 311.115 + vertex -856.811 231.203 310.498 + endloop + endfacet + facet normal -0.350503 -0.789467 -0.503874 + outer loop + vertex -700.371 131.965 310.837 + vertex -703.207 133.273 310.76 + vertex -701.881 133.808 308.998 + endloop + endfacet + facet normal -0.347942 -0.782824 -0.515871 + outer loop + vertex -706.01 134.318 311.064 + vertex -707.954 136.237 309.463 + vertex -703.207 133.273 310.76 + endloop + endfacet + facet normal -0.353494 -0.787143 -0.505419 + outer loop + vertex -707.954 136.237 309.463 + vertex -701.881 133.808 308.998 + vertex -703.207 133.273 310.76 + endloop + endfacet + facet normal -0.333788 -0.779871 -0.529515 + outer loop + vertex -706.01 134.318 311.064 + vertex -710.04 136.181 310.861 + vertex -707.954 136.237 309.463 + endloop + endfacet + facet normal -0.336885 -0.747939 -0.571924 + outer loop + vertex -714.054 137.835 311.062 + vertex -715.957 139.753 309.675 + vertex -710.04 136.181 310.861 + endloop + endfacet + facet normal -0.348066 -0.759181 -0.549994 + outer loop + vertex -715.957 139.753 309.675 + vertex -707.954 136.237 309.463 + vertex -710.04 136.181 310.861 + endloop + endfacet + facet normal -0.334585 -0.747265 -0.57415 + outer loop + vertex -714.054 137.835 311.062 + vertex -718.746 140.054 310.908 + vertex -715.957 139.753 309.675 + endloop + endfacet + facet normal -0.334493 -0.715846 -0.612927 + outer loop + vertex -723.012 141.855 311.133 + vertex -724.811 143.78 309.866 + vertex -718.746 140.054 310.908 + endloop + endfacet + facet normal -0.342595 -0.724791 -0.597752 + outer loop + vertex -724.811 143.78 309.866 + vertex -715.957 139.753 309.675 + vertex -718.746 140.054 310.908 + endloop + endfacet + facet normal -0.331888 -0.714994 -0.615333 + outer loop + vertex -723.012 141.855 311.133 + vertex -727.636 144.098 311.021 + vertex -724.811 143.78 309.866 + endloop + endfacet + facet normal -0.333834 -0.690451 -0.641742 + outer loop + vertex -731.758 145.883 311.245 + vertex -733.593 147.874 310.057 + vertex -727.636 144.098 311.021 + endloop + endfacet + facet normal -0.337663 -0.694779 -0.635032 + outer loop + vertex -733.593 147.874 310.057 + vertex -724.811 143.78 309.866 + vertex -727.636 144.098 311.021 + endloop + endfacet + facet normal -0.328043 -0.688275 -0.647044 + outer loop + vertex -731.758 145.883 311.245 + vertex -736.268 148.137 311.134 + vertex -733.593 147.874 310.057 + endloop + endfacet + facet normal -0.334487 -0.671875 -0.660834 + outer loop + vertex -740.335 149.959 311.339 + vertex -742.201 152 310.208 + vertex -736.268 148.137 311.134 + endloop + endfacet + facet normal -0.332878 -0.670043 -0.663502 + outer loop + vertex -742.201 152 310.208 + vertex -733.593 147.874 310.057 + vertex -736.268 148.137 311.134 + endloop + endfacet + facet normal -0.330059 -0.67007 -0.664881 + outer loop + vertex -740.335 149.959 311.339 + vertex -744.88 152.312 311.225 + vertex -742.201 152 310.208 + endloop + endfacet + facet normal -0.336 -0.656715 -0.675151 + outer loop + vertex -749.006 154.234 311.408 + vertex -750.774 156.263 310.315 + vertex -744.88 152.312 311.225 + endloop + endfacet + facet normal -0.333554 -0.653959 -0.679028 + outer loop + vertex -750.774 156.263 310.315 + vertex -742.201 152 310.208 + vertex -744.88 152.312 311.225 + endloop + endfacet + facet normal -0.328417 -0.653687 -0.681788 + outer loop + vertex -749.006 154.234 311.408 + vertex -753.515 156.64 311.274 + vertex -750.774 156.263 310.315 + endloop + endfacet + facet normal -0.337661 -0.637278 -0.692721 + outer loop + vertex -757.531 158.587 311.44 + vertex -759.226 160.64 310.378 + vertex -753.515 156.64 311.274 + endloop + endfacet + facet normal -0.332041 -0.631115 -0.701029 + outer loop + vertex -759.226 160.64 310.378 + vertex -750.774 156.263 310.315 + vertex -753.515 156.64 311.274 + endloop + endfacet + facet normal -0.330834 -0.634605 -0.698445 + outer loop + vertex -757.531 158.587 311.44 + vertex -761.846 160.993 311.298 + vertex -759.226 160.64 310.378 + endloop + endfacet + facet normal -0.343059 -0.622432 -0.703483 + outer loop + vertex -765.708 162.946 311.453 + vertex -767.48 165.108 310.404 + vertex -761.846 160.993 311.298 + endloop + endfacet + facet normal -0.334101 -0.612902 -0.71605 + outer loop + vertex -767.48 165.108 310.404 + vertex -759.226 160.64 310.378 + vertex -761.846 160.993 311.298 + endloop + endfacet + facet normal -0.339268 -0.62088 -0.706686 + outer loop + vertex -765.708 162.946 311.453 + vertex -770.018 165.465 311.309 + vertex -767.48 165.108 310.404 + endloop + endfacet + facet normal -0.350117 -0.606558 -0.713797 + outer loop + vertex -773.964 167.567 311.459 + vertex -775.697 169.793 310.417 + vertex -770.018 165.465 311.309 + endloop + endfacet + facet normal -0.342381 -0.598554 -0.72423 + outer loop + vertex -775.697 169.793 310.417 + vertex -767.48 165.108 310.404 + vertex -770.018 165.465 311.309 + endloop + endfacet + facet normal -0.347713 -0.605611 -0.715773 + outer loop + vertex -773.964 167.567 311.459 + vertex -778.359 170.261 311.314 + vertex -775.697 169.793 310.417 + endloop + endfacet + facet normal -0.360473 -0.593425 -0.719657 + outer loop + vertex -782.335 172.493 311.465 + vertex -783.863 174.692 310.417 + vertex -778.359 170.261 311.314 + endloop + endfacet + facet normal -0.349677 -0.582821 -0.733516 + outer loop + vertex -783.863 174.692 310.417 + vertex -775.697 169.793 310.417 + vertex -778.359 170.261 311.314 + endloop + endfacet + facet normal -0.358815 -0.592881 -0.720932 + outer loop + vertex -782.335 172.493 311.465 + vertex -786.575 175.239 311.317 + vertex -783.863 174.692 310.417 + endloop + endfacet + facet normal -0.362095 -0.568669 -0.738581 + outer loop + vertex -790.374 177.476 311.457 + vertex -791.764 179.718 310.413 + vertex -786.575 175.239 311.317 + endloop + endfacet + facet normal -0.360195 -0.566925 -0.740848 + outer loop + vertex -791.764 179.718 310.413 + vertex -783.863 174.692 310.417 + vertex -786.575 175.239 311.317 + endloop + endfacet + facet normal -0.366748 -0.570004 -0.735249 + outer loop + vertex -790.374 177.476 311.457 + vertex -794.409 180.262 311.31 + vertex -791.764 179.718 310.413 + endloop + endfacet + facet normal -0.370843 -0.55332 -0.745864 + outer loop + vertex -798.086 182.547 311.443 + vertex -799.383 184.84 310.387 + vertex -794.409 180.262 311.31 + endloop + endfacet + facet normal -0.367585 -0.550521 -0.749539 + outer loop + vertex -799.383 184.84 310.387 + vertex -791.764 179.718 310.413 + vertex -794.409 180.262 311.31 + endloop + endfacet + facet normal -0.376384 -0.554699 -0.742054 + outer loop + vertex -798.086 182.547 311.443 + vertex -802.031 185.428 311.291 + vertex -799.383 184.84 310.387 + endloop + endfacet + facet normal -0.378989 -0.537213 -0.753504 + outer loop + vertex -805.663 187.806 311.422 + vertex -806.839 190.149 310.343 + vertex -802.031 185.428 311.291 + endloop + endfacet + facet normal -0.376814 -0.535466 -0.755835 + outer loop + vertex -806.839 190.149 310.343 + vertex -799.383 184.84 310.387 + vertex -802.031 185.428 311.291 + endloop + endfacet + facet normal -0.382271 -0.537878 -0.75137 + outer loop + vertex -805.663 187.806 311.422 + vertex -809.552 190.801 311.257 + vertex -806.839 190.149 310.343 + endloop + endfacet + facet normal -0.391755 -0.527948 -0.753524 + outer loop + vertex -813.189 193.315 311.386 + vertex -814.218 195.697 310.252 + vertex -809.552 190.801 311.257 + endloop + endfacet + facet normal -0.382203 -0.520852 -0.763305 + outer loop + vertex -814.218 195.697 310.252 + vertex -806.839 190.149 310.343 + vertex -809.552 190.801 311.257 + endloop + endfacet + facet normal -0.39245 -0.528044 -0.753095 + outer loop + vertex -813.189 193.315 311.386 + vertex -817.073 196.471 311.197 + vertex -814.218 195.697 310.252 + endloop + endfacet + facet normal -0.406412 -0.525057 -0.747759 + outer loop + vertex -820.74 199.139 311.317 + vertex -821.578 201.538 310.088 + vertex -817.073 196.471 311.197 + endloop + endfacet + facet normal -0.391982 -0.515358 -0.762074 + outer loop + vertex -821.578 201.538 310.088 + vertex -814.218 195.697 310.252 + vertex -817.073 196.471 311.197 + endloop + endfacet + facet normal -0.409803 -0.525231 -0.745784 + outer loop + vertex -820.74 199.139 311.317 + vertex -824.539 202.413 311.098 + vertex -821.578 201.538 310.088 + endloop + endfacet + facet normal -0.425385 -0.529089 -0.734243 + outer loop + vertex -828.09 205.119 311.205 + vertex -828.862 207.621 309.85 + vertex -824.539 202.413 311.098 + endloop + endfacet + facet normal -0.409534 -0.519662 -0.749822 + outer loop + vertex -828.862 207.621 309.85 + vertex -821.578 201.538 310.088 + vertex -824.539 202.413 311.098 + endloop + endfacet + facet normal -0.426897 -0.529082 -0.73337 + outer loop + vertex -828.09 205.119 311.205 + vertex -831.731 208.425 310.94 + vertex -828.862 207.621 309.85 + endloop + endfacet + facet normal -0.445723 -0.534845 -0.717824 + outer loop + vertex -835.157 211.15 311.037 + vertex -835.995 213.812 309.574 + vertex -831.731 208.425 310.94 + endloop + endfacet + facet normal -0.426869 -0.52467 -0.736549 + outer loop + vertex -835.995 213.812 309.574 + vertex -828.862 207.621 309.85 + vertex -831.731 208.425 310.94 + endloop + endfacet + facet normal -0.450569 -0.534745 -0.714868 + outer loop + vertex -835.157 211.15 311.037 + vertex -838.781 214.58 310.756 + vertex -835.995 213.812 309.574 + endloop + endfacet + facet normal -0.473232 -0.544942 -0.692163 + outer loop + vertex -842.242 217.427 310.88 + vertex -842.912 219.943 309.357 + vertex -838.781 214.58 310.756 + endloop + endfacet + facet normal -0.450605 -0.533645 -0.715667 + outer loop + vertex -842.912 219.943 309.357 + vertex -835.995 213.812 309.574 + vertex -838.781 214.58 310.756 + endloop + endfacet + facet normal -0.479446 -0.544305 -0.688377 + outer loop + vertex -842.242 217.427 310.88 + vertex -845.776 220.824 310.655 + vertex -842.912 219.943 309.357 + endloop + endfacet + facet normal -0.506482 -0.558472 -0.656951 + outer loop + vertex -849.163 223.72 310.805 + vertex -848.616 224.851 309.422 + vertex -845.776 220.824 310.655 + endloop + endfacet + facet normal -0.479296 -0.548043 -0.68551 + outer loop + vertex -848.616 224.851 309.422 + vertex -842.912 219.943 309.357 + vertex -845.776 220.824 310.655 + endloop + endfacet + facet normal -0.512823 -0.556018 -0.654107 + outer loop + vertex -854.606 229.138 310.507 + vertex -855.85 230.608 310.233 + vertex -852.667 229.613 308.584 + endloop + endfacet + facet normal -0.526548 -0.568283 -0.632299 + outer loop + vertex -856.811 231.203 310.498 + vertex -855.136 231.595 308.751 + vertex -855.85 230.608 310.233 + endloop + endfacet + facet normal -0.510169 -0.581808 -0.633425 + outer loop + vertex -855.136 231.595 308.751 + vertex -852.667 229.613 308.584 + vertex -855.85 230.608 310.233 + endloop + endfacet + facet normal -0.320735 -0.67476 -0.664701 + outer loop + vertex -707.954 136.237 309.463 + vertex -706.874 137.668 307.49 + vertex -701.881 133.808 308.998 + endloop + endfacet + facet normal -0.349052 -0.696595 -0.626831 + outer loop + vertex -701.881 133.808 308.998 + vertex -706.874 137.668 307.49 + vertex -701.205 135.504 306.737 + endloop + endfacet + facet normal -0.295291 -0.628819 -0.719298 + outer loop + vertex -715.957 139.753 309.675 + vertex -714.453 140.953 308.009 + vertex -707.954 136.237 309.463 + endloop + endfacet + facet normal -0.334504 -0.666502 -0.666245 + outer loop + vertex -707.954 136.237 309.463 + vertex -714.453 140.953 308.009 + vertex -706.874 137.668 307.49 + endloop + endfacet + facet normal -0.280481 -0.58033 -0.764557 + outer loop + vertex -724.811 143.78 309.866 + vertex -723.159 144.918 308.397 + vertex -715.957 139.753 309.675 + endloop + endfacet + facet normal -0.312227 -0.614644 -0.72438 + outer loop + vertex -715.957 139.753 309.675 + vertex -723.159 144.918 308.397 + vertex -714.453 140.953 308.009 + endloop + endfacet + facet normal -0.270555 -0.543378 -0.794695 + outer loop + vertex -733.593 147.874 310.057 + vertex -732.073 149.074 308.719 + vertex -724.811 143.78 309.866 + endloop + endfacet + facet normal -0.292753 -0.568262 -0.769009 + outer loop + vertex -724.811 143.78 309.866 + vertex -732.073 149.074 308.719 + vertex -723.159 144.918 308.397 + endloop + endfacet + facet normal -0.258484 -0.509091 -0.820983 + outer loop + vertex -742.201 152 310.208 + vertex -740.805 153.257 308.99 + vertex -733.593 147.874 310.057 + endloop + endfacet + facet normal -0.280528 -0.533985 -0.797599 + outer loop + vertex -733.593 147.874 310.057 + vertex -740.805 153.257 308.99 + vertex -732.073 149.074 308.719 + endloop + endfacet + facet normal -0.25242 -0.486852 -0.836217 + outer loop + vertex -750.774 156.263 310.315 + vertex -749.358 157.483 309.177 + vertex -742.201 152 310.208 + endloop + endfacet + facet normal -0.266167 -0.50226 -0.822733 + outer loop + vertex -742.201 152 310.208 + vertex -749.358 157.483 309.177 + vertex -740.805 153.257 308.99 + endloop + endfacet + facet normal -0.249808 -0.470229 -0.846452 + outer loop + vertex -759.226 160.64 310.378 + vertex -757.806 161.837 309.293 + vertex -750.774 156.263 310.315 + endloop + endfacet + facet normal -0.259197 -0.480491 -0.837822 + outer loop + vertex -750.774 156.263 310.315 + vertex -757.806 161.837 309.293 + vertex -749.358 157.483 309.177 + endloop + endfacet + facet normal -0.249544 -0.455906 -0.854328 + outer loop + vertex -767.48 165.108 310.404 + vertex -766.122 166.332 309.354 + vertex -759.226 160.64 310.378 + endloop + endfacet + facet normal -0.256734 -0.463495 -0.848092 + outer loop + vertex -759.226 160.64 310.378 + vertex -766.122 166.332 309.354 + vertex -757.806 161.837 309.293 + endloop + endfacet + facet normal -0.25622 -0.447039 -0.857034 + outer loop + vertex -775.697 169.793 310.417 + vertex -774.304 170.987 309.378 + vertex -767.48 165.108 310.404 + endloop + endfacet + facet normal -0.257554 -0.448394 -0.855926 + outer loop + vertex -767.48 165.108 310.404 + vertex -774.304 170.987 309.378 + vertex -766.122 166.332 309.354 + endloop + endfacet + facet normal -0.260164 -0.433649 -0.862707 + outer loop + vertex -783.863 174.692 310.417 + vertex -782.362 175.841 309.387 + vertex -775.697 169.793 310.417 + endloop + endfacet + facet normal -0.265022 -0.438344 -0.858847 + outer loop + vertex -775.697 169.793 310.417 + vertex -782.362 175.841 309.387 + vertex -774.304 170.987 309.378 + endloop + endfacet + facet normal -0.270966 -0.426715 -0.862839 + outer loop + vertex -791.764 179.718 310.413 + vertex -790.205 180.833 309.372 + vertex -783.863 174.692 310.417 + endloop + endfacet + facet normal -0.268521 -0.424505 -0.864692 + outer loop + vertex -783.863 174.692 310.417 + vertex -790.205 180.833 309.372 + vertex -782.362 175.841 309.387 + endloop + endfacet + facet normal -0.27574 -0.414497 -0.867271 + outer loop + vertex -799.383 184.84 310.387 + vertex -797.794 185.97 309.342 + vertex -791.764 179.718 310.413 + endloop + endfacet + facet normal -0.27906 -0.417287 -0.864868 + outer loop + vertex -791.764 179.718 310.413 + vertex -797.794 185.97 309.342 + vertex -790.205 180.833 309.372 + endloop + endfacet + facet normal -0.286795 -0.409968 -0.865838 + outer loop + vertex -806.839 190.149 310.343 + vertex -805.158 191.24 309.27 + vertex -799.383 184.84 310.387 + endloop + endfacet + facet normal -0.282435 -0.406563 -0.868871 + outer loop + vertex -799.383 184.84 310.387 + vertex -805.158 191.24 309.27 + vertex -797.794 185.97 309.342 + endloop + endfacet + facet normal -0.297558 -0.409897 -0.862232 + outer loop + vertex -814.218 195.697 310.252 + vertex -812.386 196.724 309.132 + vertex -806.839 190.149 310.343 + endloop + endfacet + facet normal -0.290703 -0.404971 -0.866885 + outer loop + vertex -806.839 190.149 310.343 + vertex -812.386 196.724 309.132 + vertex -805.158 191.24 309.27 + endloop + endfacet + facet normal -0.315615 -0.421594 -0.850086 + outer loop + vertex -821.578 201.538 310.088 + vertex -819.563 202.476 308.875 + vertex -814.218 195.697 310.252 + endloop + endfacet + facet normal -0.29759 -0.409851 -0.862242 + outer loop + vertex -814.218 195.697 310.252 + vertex -819.563 202.476 308.875 + vertex -812.386 196.724 309.132 + endloop + endfacet + facet normal -0.34417 -0.444417 -0.827067 + outer loop + vertex -828.862 207.621 309.85 + vertex -826.756 208.539 308.48 + vertex -821.578 201.538 310.088 + endloop + endfacet + facet normal -0.312742 -0.42618 -0.84886 + outer loop + vertex -821.578 201.538 310.088 + vertex -826.756 208.539 308.48 + vertex -819.563 202.476 308.875 + endloop + endfacet + facet normal -0.378445 -0.471551 -0.796504 + outer loop + vertex -835.995 213.812 309.574 + vertex -833.893 214.759 308.015 + vertex -828.862 207.621 309.85 + endloop + endfacet + facet normal -0.339715 -0.451589 -0.825022 + outer loop + vertex -828.862 207.621 309.85 + vertex -833.893 214.759 308.015 + vertex -826.756 208.539 308.48 + endloop + endfacet + facet normal -0.416251 -0.496518 -0.761712 + outer loop + vertex -842.912 219.943 309.357 + vertex -840.708 220.774 307.611 + vertex -835.995 213.812 309.574 + endloop + endfacet + facet normal -0.374471 -0.477565 -0.794798 + outer loop + vertex -835.995 213.812 309.574 + vertex -840.708 220.774 307.611 + vertex -833.893 214.759 308.015 + endloop + endfacet + facet normal -0.452577 -0.516447 -0.726951 + outer loop + vertex -848.616 224.851 309.422 + vertex -847.335 226.751 307.275 + vertex -842.912 219.943 309.357 + endloop + endfacet + facet normal -0.413351 -0.50115 -0.760256 + outer loop + vertex -842.912 219.943 309.357 + vertex -847.335 226.751 307.275 + vertex -840.708 220.774 307.611 + endloop + endfacet + facet normal -0.318499 -0.571493 -0.756276 + outer loop + vertex -706.874 137.668 307.49 + vertex -705.883 139.397 305.766 + vertex -701.205 135.504 306.737 + endloop + endfacet + facet normal -0.349571 -0.599732 -0.719807 + outer loop + vertex -701.205 135.504 306.737 + vertex -705.883 139.397 305.766 + vertex -700.221 137.213 304.835 + endloop + endfacet + facet normal -0.280018 -0.518395 -0.807995 + outer loop + vertex -714.453 140.953 308.009 + vertex -713.36 142.623 306.559 + vertex -706.874 137.668 307.49 + endloop + endfacet + facet normal -0.325121 -0.567719 -0.756301 + outer loop + vertex -706.874 137.668 307.49 + vertex -713.36 142.623 306.559 + vertex -705.883 139.397 305.766 + endloop + endfacet + facet normal -0.248004 -0.461159 -0.851954 + outer loop + vertex -723.159 144.918 308.397 + vertex -722.008 146.561 307.172 + vertex -714.453 140.953 308.009 + endloop + endfacet + facet normal -0.2905 -0.511912 -0.808428 + outer loop + vertex -714.453 140.953 308.009 + vertex -722.008 146.561 307.172 + vertex -713.36 142.623 306.559 + endloop + endfacet + facet normal -0.223481 -0.410782 -0.88392 + outer loop + vertex -732.073 149.074 308.719 + vertex -731.025 150.781 307.661 + vertex -723.159 144.918 308.397 + endloop + endfacet + facet normal -0.258713 -0.454114 -0.852554 + outer loop + vertex -723.159 144.918 308.397 + vertex -731.025 150.781 307.661 + vertex -722.008 146.561 307.172 + endloop + endfacet + facet normal -0.208171 -0.376134 -0.902878 + outer loop + vertex -740.805 153.257 308.99 + vertex -739.875 155.01 308.045 + vertex -732.073 149.074 308.719 + endloop + endfacet + facet normal -0.232176 -0.405552 -0.884094 + outer loop + vertex -732.073 149.074 308.719 + vertex -739.875 155.01 308.045 + vertex -731.025 150.781 307.661 + endloop + endfacet + facet normal -0.19193 -0.347804 -0.917712 + outer loop + vertex -749.358 157.483 309.177 + vertex -748.481 159.248 308.324 + vertex -740.805 153.257 308.99 + endloop + endfacet + facet normal -0.213219 -0.373426 -0.902824 + outer loop + vertex -740.805 153.257 308.99 + vertex -748.481 159.248 308.324 + vertex -739.875 155.01 308.045 + endloop + endfacet + facet normal -0.183381 -0.331048 -0.925623 + outer loop + vertex -757.806 161.837 309.293 + vertex -756.915 163.571 308.497 + vertex -749.358 157.483 309.177 + endloop + endfacet + facet normal -0.195956 -0.345763 -0.917632 + outer loop + vertex -749.358 157.483 309.177 + vertex -756.915 163.571 308.497 + vertex -748.481 159.248 308.324 + endloop + endfacet + facet normal -0.179534 -0.31955 -0.930406 + outer loop + vertex -766.122 166.332 309.354 + vertex -765.233 168.055 308.591 + vertex -757.806 161.837 309.293 + endloop + endfacet + facet normal -0.187724 -0.328788 -0.925558 + outer loop + vertex -757.806 161.837 309.293 + vertex -765.233 168.055 308.591 + vertex -756.915 163.571 308.497 + endloop + endfacet + facet normal -0.179368 -0.310544 -0.933483 + outer loop + vertex -774.304 170.987 309.378 + vertex -773.411 172.708 308.634 + vertex -766.122 166.332 309.354 + endloop + endfacet + facet normal -0.185038 -0.316668 -0.930313 + outer loop + vertex -766.122 166.332 309.354 + vertex -773.411 172.708 308.634 + vertex -765.233 168.055 308.591 + endloop + endfacet + facet normal -0.186346 -0.307616 -0.933085 + outer loop + vertex -782.362 175.841 309.387 + vertex -781.411 177.524 308.642 + vertex -774.304 170.987 309.378 + endloop + endfacet + facet normal -0.185859 -0.307115 -0.933347 + outer loop + vertex -774.304 170.987 309.378 + vertex -781.411 177.524 308.642 + vertex -773.411 172.708 308.634 + endloop + endfacet + facet normal -0.189647 -0.300794 -0.934643 + outer loop + vertex -790.205 180.833 309.372 + vertex -789.199 182.51 308.628 + vertex -782.362 175.841 309.387 + endloop + endfacet + facet normal -0.192855 -0.303894 -0.932982 + outer loop + vertex -782.362 175.841 309.387 + vertex -789.199 182.51 308.628 + vertex -781.411 177.524 308.642 + endloop + endfacet + facet normal -0.198715 -0.29899 -0.933337 + outer loop + vertex -797.794 185.97 309.342 + vertex -796.739 187.638 308.583 + vertex -790.205 180.833 309.372 + endloop + endfacet + facet normal -0.19627 -0.296783 -0.934558 + outer loop + vertex -790.205 180.833 309.372 + vertex -796.739 187.638 308.583 + vertex -789.199 182.51 308.628 + endloop + endfacet + facet normal -0.205408 -0.299785 -0.931631 + outer loop + vertex -805.158 191.24 309.27 + vertex -804.043 192.901 308.489 + vertex -797.794 185.97 309.342 + endloop + endfacet + facet normal -0.201986 -0.296906 -0.9333 + outer loop + vertex -797.794 185.97 309.342 + vertex -804.043 192.901 308.489 + vertex -796.739 187.638 308.583 + endloop + endfacet + facet normal -0.216843 -0.309097 -0.925979 + outer loop + vertex -812.386 196.724 309.132 + vertex -811.16 198.328 308.309 + vertex -805.158 191.24 309.27 + endloop + endfacet + facet normal -0.205148 -0.299961 -0.931632 + outer loop + vertex -805.158 191.24 309.27 + vertex -811.16 198.328 308.309 + vertex -804.043 192.901 308.489 + endloop + endfacet + facet normal -0.231785 -0.330117 -0.91504 + outer loop + vertex -819.563 202.476 308.875 + vertex -818.177 203.985 307.979 + vertex -812.386 196.724 309.132 + endloop + endfacet + facet normal -0.209865 -0.314349 -0.925819 + outer loop + vertex -812.386 196.724 309.132 + vertex -818.177 203.985 307.979 + vertex -811.16 198.328 308.309 + endloop + endfacet + facet normal -0.260623 -0.36721 -0.892879 + outer loop + vertex -826.756 208.539 308.48 + vertex -825.221 209.972 307.443 + vertex -819.563 202.476 308.875 + endloop + endfacet + facet normal -0.219885 -0.340526 -0.914162 + outer loop + vertex -819.563 202.476 308.875 + vertex -825.221 209.972 307.443 + vertex -818.177 203.985 307.979 + endloop + endfacet + facet normal -0.306656 -0.415985 -0.856107 + outer loop + vertex -833.893 214.759 308.015 + vertex -832.288 216.185 306.747 + vertex -826.756 208.539 308.48 + endloop + endfacet + facet normal -0.246875 -0.380677 -0.891144 + outer loop + vertex -826.756 208.539 308.48 + vertex -832.288 216.185 306.747 + vertex -825.221 209.972 307.443 + endloop + endfacet + facet normal -0.359467 -0.461649 -0.810965 + outer loop + vertex -840.708 220.774 307.611 + vertex -838.981 222.051 306.119 + vertex -833.893 214.759 308.015 + endloop + endfacet + facet normal -0.294808 -0.427835 -0.854427 + outer loop + vertex -833.893 214.759 308.015 + vertex -838.981 222.051 306.119 + vertex -832.288 216.185 306.747 + endloop + endfacet + facet normal -0.405121 -0.492586 -0.770218 + outer loop + vertex -847.335 226.751 307.275 + vertex -844.226 226.42 305.851 + vertex -840.708 220.774 307.611 + endloop + endfacet + facet normal -0.351035 -0.471051 -0.809249 + outer loop + vertex -840.708 220.774 307.611 + vertex -844.226 226.42 305.851 + vertex -838.981 222.051 306.119 + endloop + endfacet + facet normal -0.321965 -0.489576 -0.810342 + outer loop + vertex -705.883 139.397 305.766 + vertex -705.163 141.416 304.26 + vertex -700.221 137.213 304.835 + endloop + endfacet + facet normal -0.361562 -0.5302 -0.766917 + outer loop + vertex -700.221 137.213 304.835 + vertex -705.163 141.416 304.26 + vertex -699.324 139.152 303.072 + endloop + endfacet + facet normal -0.276342 -0.429189 -0.859902 + outer loop + vertex -713.36 142.623 306.559 + vertex -712.746 144.67 305.339 + vertex -705.883 139.397 305.766 + endloop + endfacet + facet normal -0.324842 -0.488278 -0.809976 + outer loop + vertex -705.883 139.397 305.766 + vertex -712.746 144.67 305.339 + vertex -705.163 141.416 304.26 + endloop + endfacet + facet normal -0.228875 -0.361751 -0.903744 + outer loop + vertex -722.008 146.561 307.172 + vertex -721.468 148.643 306.202 + vertex -713.36 142.623 306.559 + endloop + endfacet + facet normal -0.279894 -0.427839 -0.859426 + outer loop + vertex -713.36 142.623 306.559 + vertex -721.468 148.643 306.202 + vertex -712.746 144.67 305.339 + endloop + endfacet + facet normal -0.234341 -0.360004 -0.90304 + outer loop + vertex -722.008 146.561 307.172 + vertex -730.541 152.905 306.858 + vertex -721.468 148.643 306.202 + endloop + endfacet + facet normal -0.179788 -0.295508 -0.93827 + outer loop + vertex -825.221 209.972 307.443 + vertex -824.226 211.833 306.667 + vertex -818.177 203.985 307.979 + endloop + endfacet + facet normal -0.228366 -0.36108 -0.904141 + outer loop + vertex -832.288 216.185 306.747 + vertex -831.158 218.006 305.734 + vertex -825.221 209.972 307.443 + endloop + endfacet + facet normal -0.150805 -0.311042 -0.938355 + outer loop + vertex -825.221 209.972 307.443 + vertex -831.158 218.006 305.734 + vertex -824.226 211.833 306.667 + endloop + endfacet + facet normal -0.299467 -0.432713 -0.85034 + outer loop + vertex -838.981 222.051 306.119 + vertex -837.979 224.136 304.705 + vertex -832.288 216.185 306.747 + endloop + endfacet + facet normal -0.202435 -0.376989 -0.903825 + outer loop + vertex -832.288 216.185 306.747 + vertex -837.979 224.136 304.705 + vertex -831.158 218.006 305.734 + endloop + endfacet + facet normal -0.360326 -0.481573 -0.798907 + outer loop + vertex -844.226 226.42 305.851 + vertex -843.866 228.944 304.167 + vertex -838.981 222.051 306.119 + endloop + endfacet + facet normal -0.282789 -0.441524 -0.85152 + outer loop + vertex -838.981 222.051 306.119 + vertex -843.866 228.944 304.167 + vertex -837.979 224.136 304.705 + endloop + endfacet + facet normal -0.343846 -0.456248 -0.820736 + outer loop + vertex -705.163 141.416 304.26 + vertex -704.528 143.45 302.863 + vertex -699.324 139.152 303.072 + endloop + endfacet + facet normal -0.381612 -0.499876 -0.777494 + outer loop + vertex -699.324 139.152 303.072 + vertex -704.528 143.45 302.863 + vertex -698.424 141.092 301.383 + endloop + endfacet + facet normal -0.291581 -0.389695 -0.873566 + outer loop + vertex -712.746 144.67 305.339 + vertex -712.453 146.772 304.304 + vertex -705.163 141.416 304.26 + endloop + endfacet + facet normal -0.341055 -0.457457 -0.821227 + outer loop + vertex -705.163 141.416 304.26 + vertex -712.453 146.772 304.304 + vertex -704.528 143.45 302.863 + endloop + endfacet + facet normal -0.232688 -0.310705 -0.921585 + outer loop + vertex -721.468 148.643 306.202 + vertex -721.362 150.795 305.45 + vertex -712.746 144.67 305.339 + endloop + endfacet + facet normal -0.28873 -0.390403 -0.874197 + outer loop + vertex -712.746 144.67 305.339 + vertex -721.362 150.795 305.45 + vertex -712.453 146.772 304.304 + endloop + endfacet + facet normal -0.23042 -0.310983 -0.922061 + outer loop + vertex -721.468 148.643 306.202 + vertex -730.523 155.092 306.29 + vertex -721.362 150.795 305.45 + endloop + endfacet + facet normal -0.150161 -0.310369 -0.938681 + outer loop + vertex -831.158 218.006 305.734 + vertex -830.331 219.835 304.997 + vertex -824.226 211.833 306.667 + endloop + endfacet + facet normal -0.225361 -0.399915 -0.888415 + outer loop + vertex -837.979 224.136 304.705 + vertex -836.993 226.044 303.596 + vertex -831.158 218.006 305.734 + endloop + endfacet + facet normal -0.109071 -0.328708 -0.938112 + outer loop + vertex -831.158 218.006 305.734 + vertex -836.993 226.044 303.596 + vertex -830.331 219.835 304.997 + endloop + endfacet + facet normal -0.321914 -0.48511 -0.813043 + outer loop + vertex -843.866 228.944 304.167 + vertex -843.573 232.187 302.116 + vertex -837.979 224.136 304.705 + endloop + endfacet + facet normal -0.190381 -0.417935 -0.888305 + outer loop + vertex -837.979 224.136 304.705 + vertex -843.573 232.187 302.116 + vertex -836.993 226.044 303.596 + endloop + endfacet + facet normal -0.369765 -0.445411 -0.815404 + outer loop + vertex -704.528 143.45 302.863 + vertex -703.474 145.103 301.482 + vertex -698.424 141.092 301.383 + endloop + endfacet + facet normal -0.400558 -0.485106 -0.777319 + outer loop + vertex -698.424 141.092 301.383 + vertex -703.474 145.103 301.482 + vertex -697.387 142.631 299.889 + endloop + endfacet + facet normal -0.321253 -0.392639 -0.86176 + outer loop + vertex -712.453 146.772 304.304 + vertex -711.989 148.413 303.383 + vertex -704.528 143.45 302.863 + endloop + endfacet + facet normal -0.35841 -0.453266 -0.816144 + outer loop + vertex -704.528 143.45 302.863 + vertex -711.989 148.413 303.383 + vertex -703.474 145.103 301.482 + endloop + endfacet + facet normal -0.256981 -0.308191 -0.915958 + outer loop + vertex -721.362 150.795 305.45 + vertex -721.298 152.46 304.872 + vertex -712.453 146.772 304.304 + endloop + endfacet + facet normal -0.310597 -0.396782 -0.863767 + outer loop + vertex -712.453 146.772 304.304 + vertex -721.298 152.46 304.872 + vertex -711.989 148.413 303.383 + endloop + endfacet + facet normal -0.246053 -0.309498 -0.918514 + outer loop + vertex -721.362 150.795 305.45 + vertex -730.601 156.769 305.912 + vertex -721.298 152.46 304.872 + endloop + endfacet + facet normal -0.143238 -0.361574 -0.921275 + outer loop + vertex -836.993 226.044 303.596 + vertex -836.063 227.32 302.951 + vertex -830.331 219.835 304.997 + endloop + endfacet + facet normal -0.0338153 -0.287585 -0.957158 + outer loop + vertex -830.331 219.835 304.997 + vertex -836.063 227.32 302.951 + vertex -829.783 221.338 304.526 + endloop + endfacet + facet normal -0.235629 -0.458786 -0.856735 + outer loop + vertex -843.573 232.187 302.116 + vertex -841.82 232.994 301.202 + vertex -836.993 226.044 303.596 + endloop + endfacet + facet normal -0.103812 -0.387628 -0.915952 + outer loop + vertex -836.993 226.044 303.596 + vertex -841.82 232.994 301.202 + vertex -836.063 227.32 302.951 + endloop + endfacet + facet normal -0.286029 -0.553375 -0.782281 + outer loop + vertex -847.638 237.083 300.474 + vertex -848.685 239.425 299.201 + vertex -846.407 237.831 299.495 + endloop + endfacet + facet normal -0.384503 -0.419163 -0.822472 + outer loop + vertex -704.39 146.571 301.162 + vertex -700.472 144.968 300.148 + vertex -703.474 145.103 301.482 + endloop + endfacet + facet normal -0.384871 -0.4167 -0.823551 + outer loop + vertex -697.387 142.631 299.889 + vertex -703.474 145.103 301.482 + vertex -700.472 144.968 300.148 + endloop + endfacet + facet normal -0.340487 -0.382614 -0.85888 + outer loop + vertex -711.989 148.413 303.383 + vertex -710.719 149.129 302.561 + vertex -703.474 145.103 301.482 + endloop + endfacet + facet normal -0.349631 -0.402522 -0.84601 + outer loop + vertex -703.474 145.103 301.482 + vertex -710.719 149.129 302.561 + vertex -704.39 146.571 301.162 + endloop + endfacet + facet normal -0.284242 -0.321637 -0.903192 + outer loop + vertex -721.298 152.46 304.872 + vertex -720.711 153.219 304.417 + vertex -711.989 148.413 303.383 + endloop + endfacet + facet normal -0.3247 -0.40555 -0.854458 + outer loop + vertex -711.989 148.413 303.383 + vertex -720.711 153.219 304.417 + vertex -710.719 149.129 302.561 + endloop + endfacet + facet normal -0.267752 -0.334604 -0.90352 + outer loop + vertex -721.298 152.46 304.872 + vertex -730.177 157.464 305.65 + vertex -720.711 153.219 304.417 + endloop + endfacet + facet normal -0.0822608 -0.333684 -0.939089 + outer loop + vertex -836.063 227.32 302.951 + vertex -835.557 228.139 302.615 + vertex -829.783 221.338 304.526 + endloop + endfacet + facet normal -0.00601259 -0.275214 -0.961364 + outer loop + vertex -829.783 221.338 304.526 + vertex -835.557 228.139 302.615 + vertex -829.33 222.109 304.303 + endloop + endfacet + facet normal -0.14946 -0.426573 -0.892018 + outer loop + vertex -841.82 232.994 301.202 + vertex -840.883 233.503 300.801 + vertex -836.063 227.32 302.951 + endloop + endfacet + facet normal -0.0413008 -0.356627 -0.933334 + outer loop + vertex -836.063 227.32 302.951 + vertex -840.883 233.503 300.801 + vertex -835.557 228.139 302.615 + endloop + endfacet + facet normal -0.303575 -0.574369 -0.760225 + outer loop + vertex -848.685 239.425 299.201 + vertex -848.155 240.73 298.003 + vertex -846.407 237.831 299.495 + endloop + endfacet + facet normal -0.174319 -0.53173 -0.82878 + outer loop + vertex -846.407 237.831 299.495 + vertex -848.155 240.73 298.003 + vertex -847.069 239.907 298.302 + endloop + endfacet + facet normal -0.369158 -0.330947 -0.868445 + outer loop + vertex -704.573 147.06 300.978 + vertex -703.301 146.756 300.553 + vertex -699.675 145.183 299.611 + endloop + endfacet + facet normal -0.423886 -0.543197 -0.724747 + outer loop + vertex -699.675 145.183 299.611 + vertex -703.301 146.756 300.553 + vertex -698.886 144.987 299.297 + endloop + endfacet + facet normal -0.391914 -0.449911 -0.802486 + outer loop + vertex -704.39 146.571 301.162 + vertex -704.573 147.06 300.978 + vertex -700.472 144.968 300.148 + endloop + endfacet + facet normal -0.400419 -0.473762 -0.784356 + outer loop + vertex -700.472 144.968 300.148 + vertex -704.573 147.06 300.978 + vertex -699.675 145.183 299.611 + endloop + endfacet + facet normal -0.413335 -0.447564 -0.792995 + outer loop + vertex -700.472 144.968 300.148 + vertex -699.675 145.183 299.611 + vertex -697.056 143.646 299.113 + endloop + endfacet + facet normal -0.425041 -0.467512 -0.775095 + outer loop + vertex -699.675 145.183 299.611 + vertex -698.886 144.987 299.297 + vertex -696.701 143.857 298.78 + endloop + endfacet + facet normal -0.37719 -0.436968 -0.81657 + outer loop + vertex -703.301 146.756 300.553 + vertex -704.573 147.06 300.978 + vertex -710.334 149.551 302.306 + endloop + endfacet + facet normal -0.360899 -0.444781 -0.819708 + outer loop + vertex -704.39 146.571 301.162 + vertex -710.719 149.129 302.561 + vertex -704.573 147.06 300.978 + endloop + endfacet + facet normal -0.321505 -0.257749 -0.911153 + outer loop + vertex -710.719 149.129 302.561 + vertex -710.334 149.551 302.306 + vertex -704.573 147.06 300.978 + endloop + endfacet + facet normal -0.247124 -0.170968 -0.953782 + outer loop + vertex -720.711 153.219 304.417 + vertex -719.668 153.353 304.122 + vertex -710.719 149.129 302.561 + endloop + endfacet + facet normal -0.293452 -0.284293 -0.912723 + outer loop + vertex -710.719 149.129 302.561 + vertex -719.668 153.353 304.122 + vertex -710.334 149.551 302.306 + endloop + endfacet + facet normal -0.235526 -0.236632 -0.94262 + outer loop + vertex -720.711 153.219 304.417 + vertex -728.585 157.163 305.394 + vertex -719.668 153.353 304.122 + endloop + endfacet + facet normal -0.0224905 -0.290869 -0.956499 + outer loop + vertex -835.557 228.139 302.615 + vertex -835.474 228.764 302.423 + vertex -829.33 222.109 304.303 + endloop + endfacet + facet normal -0.00299232 -0.274318 -0.961634 + outer loop + vertex -829.33 222.109 304.303 + vertex -835.474 228.764 302.423 + vertex -827.992 221.421 304.495 + endloop + endfacet + facet normal -0.109712 -0.414441 -0.903439 + outer loop + vertex -840.883 233.503 300.801 + vertex -840.63 233.845 300.614 + vertex -835.557 228.139 302.615 + endloop + endfacet + facet normal 0.0106495 -0.32585 -0.945361 + outer loop + vertex -841.421 234.722 300.303 + vertex -835.474 228.764 302.423 + vertex -840.63 233.845 300.614 + endloop + endfacet + facet normal 0.0406385 -0.298346 -0.953592 + outer loop + vertex -835.474 228.764 302.423 + vertex -835.557 228.139 302.615 + vertex -840.63 233.845 300.614 + endloop + endfacet + facet normal -0.26784 -0.58957 -0.762017 + outer loop + vertex -846.836 240.239 297.997 + vertex -846.275 239.954 298.02 + vertex -844.374 237.789 299.028 + endloop + endfacet + facet normal -0.317402 -0.614557 -0.722202 + outer loop + vertex -844.374 237.789 299.028 + vertex -846.275 239.954 298.02 + vertex -844.259 237.756 299.005 + endloop + endfacet + facet normal -0.244302 -0.558038 -0.793038 + outer loop + vertex -847.069 239.907 298.302 + vertex -846.836 240.239 297.997 + vertex -844.982 237.728 299.193 + endloop + endfacet + facet normal -0.17403 -0.525185 -0.833003 + outer loop + vertex -844.982 237.728 299.193 + vertex -846.836 240.239 297.997 + vertex -844.374 237.789 299.028 + endloop + endfacet + facet normal -0.180757 -0.498254 -0.84798 + outer loop + vertex -844.982 237.728 299.193 + vertex -844.374 237.789 299.028 + vertex -840.883 233.503 300.801 + endloop + endfacet + facet normal -0.0777318 -0.434691 -0.897219 + outer loop + vertex -840.883 233.503 300.801 + vertex -844.374 237.789 299.028 + vertex -840.63 233.845 300.614 + endloop + endfacet + facet normal -0.315401 -0.596358 -0.738159 + outer loop + vertex -844.374 237.789 299.028 + vertex -844.259 237.756 299.005 + vertex -840.63 233.845 300.614 + endloop + endfacet + facet normal 0.753976 0.554905 -0.351569 + outer loop + vertex -840.63 233.845 300.614 + vertex -844.259 237.756 299.005 + vertex -841.421 234.722 300.303 + endloop + endfacet + facet normal -0.299049 -0.646189 -0.702146 + outer loop + vertex -846.275 239.954 298.02 + vertex -846.836 240.239 297.997 + vertex -847.529 241.119 297.482 + endloop + endfacet + facet normal -0.217098 -0.573981 -0.789565 + outer loop + vertex -847.069 239.907 298.302 + vertex -848.155 240.73 298.003 + vertex -846.836 240.239 297.997 + endloop + endfacet + facet normal -0.234719 -0.621832 -0.747149 + outer loop + vertex -848.155 240.73 298.003 + vertex -847.529 241.119 297.482 + vertex -846.836 240.239 297.997 + endloop + endfacet + facet normal 0.438281 0.792441 0.424202 + outer loop + vertex -703.301 146.756 300.553 + vertex -701.366 145.955 300.051 + vertex -698.886 144.987 299.297 + endloop + endfacet + facet normal 0.335089 0.131662 0.932942 + outer loop + vertex -698.886 144.987 299.297 + vertex -701.366 145.955 300.051 + vertex -698.067 144.583 299.06 + endloop + endfacet + facet normal -0.356962 -0.89044 0.282304 + outer loop + vertex -698.886 144.987 299.297 + vertex -698.067 144.583 299.06 + vertex -696.285 143.722 298.598 + endloop + endfacet + facet normal -0.703263 -0.374489 0.604301 + outer loop + vertex -846.275 239.954 298.02 + vertex -846.419 240.047 297.911 + vertex -844.259 237.756 299.005 + endloop + endfacet + facet normal -0.0243839 0.411997 0.910859 + outer loop + vertex -844.259 237.756 299.005 + vertex -846.419 240.047 297.911 + vertex -844.274 237.637 299.058 + endloop + endfacet + facet normal 0.0179355 0.407413 0.913068 + outer loop + vertex -844.259 237.756 299.005 + vertex -844.274 237.637 299.058 + vertex -841.421 234.722 300.303 + endloop + endfacet + facet normal 0.621883 0.729898 0.283745 + outer loop + vertex -841.421 234.722 300.303 + vertex -844.274 237.637 299.058 + vertex -842.439 235.736 299.926 + endloop + endfacet + facet normal -0.456316 -0.522038 -0.720592 + outer loop + vertex -698.453 144.787 299.156 + vertex -696.135 143.944 298.3 + vertex -698.067 144.583 299.06 + endloop + endfacet + facet normal -0.421706 -0.416197 -0.805571 + outer loop + vertex -701.203 145.87 300.036 + vertex -698.453 144.787 299.156 + vertex -698.067 144.583 299.06 + endloop + endfacet + facet normal 0.44691 0.787903 0.423651 + outer loop + vertex -705.532 147.698 301.204 + vertex -701.203 145.87 300.036 + vertex -701.366 145.955 300.051 + endloop + endfacet + facet normal -0.239947 -0.0452696 -0.96973 + outer loop + vertex -710.716 150.329 302.364 + vertex -705.532 147.698 301.204 + vertex -710.334 149.551 302.306 + endloop + endfacet + facet normal -0.214963 -0.032504 -0.976081 + outer loop + vertex -716.102 152.467 303.479 + vertex -710.716 150.329 302.364 + vertex -710.334 149.551 302.306 + endloop + endfacet + facet normal -0.188963 -0.0480926 -0.980806 + outer loop + vertex -721.425 154.915 304.384 + vertex -716.102 152.467 303.479 + vertex -719.668 153.353 304.122 + endloop + endfacet + facet normal -0.138253 0.0105632 -0.990341 + outer loop + vertex -726.637 156.878 305.133 + vertex -721.425 154.915 304.384 + vertex -719.668 153.353 304.122 + endloop + endfacet + facet normal -0.144174 -0.0817194 -0.986172 + outer loop + vertex -733.169 159.983 305.831 + vertex -726.637 156.878 305.133 + vertex -728.585 157.163 305.394 + endloop + endfacet + facet normal -0.128169 -0.0953039 -0.987162 + outer loop + vertex -738.709 163.01 306.258 + vertex -733.169 159.983 305.831 + vertex -737.833 161.525 306.287 + endloop + endfacet + facet normal -0.104988 -0.0817119 -0.991111 + outer loop + vertex -744.4 165.535 306.652 + vertex -738.709 163.01 306.258 + vertex -737.833 161.525 306.287 + endloop + endfacet + facet normal -0.0971486 -0.0990356 -0.99033 + outer loop + vertex -750.354 168.068 306.983 + vertex -744.4 165.535 306.652 + vertex -746.317 165.493 306.845 + endloop + endfacet + facet normal -0.0747127 -0.0825996 -0.993778 + outer loop + vertex -754.527 170.669 307.081 + vertex -750.354 168.068 306.983 + vertex -754.763 169.733 307.176 + endloop + endfacet + facet normal -0.0304163 -0.0756099 -0.996673 + outer loop + vertex -803.077 200.583 307.137 + vertex -799.253 197.958 307.219 + vertex -802.048 199.151 307.214 + endloop + endfacet + facet normal 0.0149113 -0.0431817 -0.998956 + outer loop + vertex -806.511 203.529 306.958 + vertex -803.077 200.583 307.137 + vertex -802.048 199.151 307.214 + endloop + endfacet + facet normal -0.0198424 -0.104131 -0.994366 + outer loop + vertex -812.043 208.211 306.578 + vertex -806.511 203.529 306.958 + vertex -808.581 204.289 306.92 + endloop + endfacet + facet normal -0.0165844 -0.129696 -0.991415 + outer loop + vertex -816.891 212.536 306.094 + vertex -812.043 208.211 306.578 + vertex -815.476 210.131 306.385 + endloop + endfacet + facet normal 0.0180839 -0.109596 -0.993812 + outer loop + vertex -820.245 214.913 305.77 + vertex -816.891 212.536 306.094 + vertex -815.476 210.131 306.385 + endloop + endfacet + facet normal -0.000137096 -0.167409 -0.985888 + outer loop + vertex -824.514 218.826 305.107 + vertex -820.245 214.913 305.77 + vertex -821.6 215.428 305.683 + endloop + endfacet + facet normal 0.117004 -0.0765784 -0.990175 + outer loop + vertex -828.283 222.218 304.399 + vertex -824.514 218.826 305.107 + vertex -827.992 221.421 304.495 + endloop + endfacet + facet normal 0.21444 -0.0393112 -0.975946 + outer loop + vertex -831.731 225.614 303.504 + vertex -828.283 222.218 304.399 + vertex -827.992 221.421 304.495 + endloop + endfacet + facet normal 0.143232 -0.164711 -0.975887 + outer loop + vertex -835.279 229.581 302.314 + vertex -831.731 225.614 303.504 + vertex -835.474 228.764 302.423 + endloop + endfacet + facet normal 0.174276 -0.171283 -0.969686 + outer loop + vertex -839.593 233.414 300.862 + vertex -835.279 229.581 302.314 + vertex -835.474 228.764 302.423 + endloop + endfacet + facet normal -0.115445 -0.489773 -0.864173 + outer loop + vertex -843.232 236.928 299.357 + vertex -839.593 233.414 300.862 + vertex -842.439 235.736 299.926 + endloop + endfacet + facet normal -0.123871 -0.534022 -0.836347 + outer loop + vertex -845.914 239.558 298.075 + vertex -843.232 236.928 299.357 + vertex -844.274 237.637 299.058 + endloop + endfacet + facet normal -0.548252 -0.712393 -0.438082 + outer loop + vertex -848.286 242.207 296.733 + vertex -845.914 239.558 298.075 + vertex -846.419 240.047 297.911 + endloop + endfacet + facet normal -0.254754 -0.643031 -0.722227 + outer loop + vertex -850.001 240.376 298.969 + vertex -848.286 242.207 296.733 + vertex -848.155 240.73 298.003 + endloop + endfacet + facet normal -0.469165 -0.521974 -0.712339 + outer loop + vertex -854.62 232.704 307.485 + vertex -852.742 234.619 304.845 + vertex -853.281 232.637 306.652 + endloop + endfacet + facet normal -0.548537 -0.50545 -0.666054 + outer loop + vertex -856.343 231.534 309.792 + vertex -854.62 232.704 307.485 + vertex -855.136 231.595 308.751 + endloop + endfacet + facet normal -0.798461 0.415065 -0.436098 + outer loop + vertex -857.746 231.059 311.909 + vertex -856.343 231.534 309.792 + vertex -857.305 231.073 311.115 + endloop + endfacet + facet normal -0.860902 0.0512183 -0.506187 + outer loop + vertex -859.214 231.432 314.444 + vertex -857.746 231.059 311.909 + vertex -858.292 230.961 312.828 + endloop + endfacet + facet normal -0.734089 -0.670074 -0.110065 + outer loop + vertex -860.362 232.235 317.209 + vertex -859.214 231.432 314.444 + vertex -859.093 231.095 315.687 + endloop + endfacet + facet normal -0.776522 -0.613652 0.142988 + outer loop + vertex -860.272 232.729 319.817 + vertex -860.362 232.235 317.209 + vertex -859.986 231.889 317.77 + endloop + endfacet + facet normal -0.361535 -0.878736 0.311635 + outer loop + vertex -696.214 129.992 314.516 + vertex -694.287 130.283 317.572 + vertex -700.747 132.239 315.594 + endloop + endfacet + facet normal -0.370181 -0.923752 0.0982231 + outer loop + vertex -697.386 130.26 312.622 + vertex -696.214 129.992 314.516 + vertex -699.247 131.045 312.994 + endloop + endfacet + facet normal -0.362045 -0.91869 -0.157901 + outer loop + vertex -697.93 130.681 311.418 + vertex -697.386 130.26 312.622 + vertex -699.439 131.196 311.884 + endloop + endfacet + facet normal -0.333752 -0.874919 -0.350893 + outer loop + vertex -697.477 131.04 310.093 + vertex -697.93 130.681 311.418 + vertex -699.078 131.248 311.096 + endloop + endfacet + facet normal -0.350002 -0.76855 -0.535564 + outer loop + vertex -697.96 132.78 307.911 + vertex -697.477 131.04 310.093 + vertex -701.881 133.808 308.998 + endloop + endfacet + facet normal -0.352261 -0.691451 -0.63072 + outer loop + vertex -697.199 134.236 305.89 + vertex -697.96 132.78 307.911 + vertex -701.205 135.504 306.737 + endloop + endfacet + facet normal -0.36224 -0.615619 -0.699853 + outer loop + vertex -696.199 135.873 303.933 + vertex -697.199 134.236 305.89 + vertex -700.221 137.213 304.835 + endloop + endfacet + facet normal -0.385567 -0.559892 -0.733388 + outer loop + vertex -695.219 137.722 302.006 + vertex -696.199 135.873 303.933 + vertex -699.324 139.152 303.072 + endloop + endfacet + facet normal -0.410421 -0.527728 -0.743679 + outer loop + vertex -694.412 139.658 300.186 + vertex -695.219 137.722 302.006 + vertex -698.424 141.092 301.383 + endloop + endfacet + facet normal -0.431102 -0.506325 -0.746851 + outer loop + vertex -694.396 142.026 298.572 + vertex -694.412 139.658 300.186 + vertex -697.387 142.631 299.889 + endloop + endfacet + facet normal -0.36279 -0.875649 0.318783 + outer loop + vertex -702 133.564 317.809 + vertex -700.747 132.239 315.594 + vertex -694.287 130.283 317.572 + endloop + endfacet + facet normal -0.68113 -0.732159 0.00218261 + outer loop + vertex -851.659 224.196 315.353 + vertex -854.281 226.642 317.949 + vertex -856.677 228.864 315.35 + endloop + endfacet + facet normal -0.67201 -0.740522 -0.00548914 + outer loop + vertex -859.093 231.095 315.687 + vertex -859.986 231.889 317.77 + vertex -860.362 232.235 317.209 + endloop + endfacet + facet normal -0.680784 -0.732483 0.00158714 + outer loop + vertex -858.286 230.364 317.933 + vertex -856.677 228.864 315.35 + vertex -854.281 226.642 317.949 + endloop + endfacet + facet normal -0.3922 -0.894352 0.215207 + outer loop + vertex -700.747 132.239 315.594 + vertex -700.896 131.825 313.605 + vertex -696.214 129.992 314.516 + endloop + endfacet + facet normal -0.679973 -0.724616 -0.112111 + outer loop + vertex -852.377 225.201 313.21 + vertex -851.659 224.196 315.353 + vertex -855.088 227.706 313.457 + endloop + endfacet + facet normal -0.666849 -0.733101 -0.133696 + outer loop + vertex -858.527 231.006 313.351 + vertex -859.093 231.095 315.687 + vertex -859.214 231.432 314.444 + endloop + endfacet + facet normal -0.688446 -0.710989 -0.143306 + outer loop + vertex -856.677 228.864 315.35 + vertex -857.143 229.755 313.17 + vertex -855.088 227.706 313.457 + endloop + endfacet + facet normal -0.377511 -0.896284 -0.232725 + outer loop + vertex -699.439 131.196 311.884 + vertex -699.078 131.248 311.096 + vertex -697.93 130.681 311.418 + endloop + endfacet + facet normal -0.372662 -0.825806 -0.423281 + outer loop + vertex -699.078 131.248 311.096 + vertex -700.371 131.965 310.837 + vertex -697.477 131.04 310.093 + endloop + endfacet + facet normal -0.383673 -0.914009 0.131842 + outer loop + vertex -700.896 131.825 313.605 + vertex -699.247 131.045 312.994 + vertex -696.214 129.992 314.516 + endloop + endfacet + facet normal -0.39757 -0.915888 -0.0555545 + outer loop + vertex -699.247 131.045 312.994 + vertex -699.439 131.196 311.884 + vertex -697.386 130.26 312.622 + endloop + endfacet + facet normal -0.517574 -0.548192 -0.656965 + outer loop + vertex -852.034 226.793 310.438 + vertex -854.606 229.138 310.507 + vertex -852.667 229.613 308.584 + endloop + endfacet + facet normal -0.51066 -0.555538 -0.656204 + outer loop + vertex -849.163 223.72 310.805 + vertex -852.034 226.793 310.438 + vertex -848.616 224.851 309.422 + endloop + endfacet + facet normal -0.823577 0.341081 -0.453193 + outer loop + vertex -857.911 230.921 312.105 + vertex -858.292 230.961 312.828 + vertex -857.746 231.059 311.909 + endloop + endfacet + facet normal -0.81505 -0.479223 -0.325636 + outer loop + vertex -858.292 230.961 312.828 + vertex -858.527 231.006 313.351 + vertex -859.214 231.432 314.444 + endloop + endfacet + facet normal -0.823522 0.343775 -0.451254 + outer loop + vertex -857.305 231.073 311.115 + vertex -857.911 230.921 312.105 + vertex -857.746 231.059 311.909 + endloop + endfacet + facet normal -0.684609 -0.371376 -0.627208 + outer loop + vertex -856.811 231.203 310.498 + vertex -857.305 231.073 311.115 + vertex -856.343 231.534 309.792 + endloop + endfacet + facet normal -0.376705 -0.790316 -0.483211 + outer loop + vertex -700.371 131.965 310.837 + vertex -701.881 133.808 308.998 + vertex -697.477 131.04 310.093 + endloop + endfacet + facet normal -0.500077 -0.60867 -0.61599 + outer loop + vertex -855.136 231.595 308.751 + vertex -856.811 231.203 310.498 + vertex -856.343 231.534 309.792 + endloop + endfacet + facet normal -0.355568 -0.693578 -0.626514 + outer loop + vertex -701.881 133.808 308.998 + vertex -701.205 135.504 306.737 + vertex -697.96 132.78 307.911 + endloop + endfacet + facet normal -0.454723 -0.514803 -0.726777 + outer loop + vertex -847.335 226.751 307.275 + vertex -848.616 224.851 309.422 + vertex -852.667 229.613 308.584 + endloop + endfacet + facet normal -0.454266 -0.570259 -0.684432 + outer loop + vertex -853.281 232.637 306.652 + vertex -855.136 231.595 308.751 + vertex -854.62 232.704 307.485 + endloop + endfacet + facet normal -0.343226 -0.603385 -0.719807 + outer loop + vertex -701.205 135.504 306.737 + vertex -700.221 137.213 304.835 + vertex -697.199 134.236 305.89 + endloop + endfacet + facet normal -0.402374 -0.510195 -0.760129 + outer loop + vertex -844.226 226.42 305.851 + vertex -847.335 226.751 307.275 + vertex -848.52 231.583 304.658 + endloop + endfacet + facet normal -0.350957 -0.535954 -0.767843 + outer loop + vertex -700.221 137.213 304.835 + vertex -699.324 139.152 303.072 + vertex -696.199 135.873 303.933 + endloop + endfacet + facet normal -0.357925 -0.482331 -0.799529 + outer loop + vertex -843.866 228.944 304.167 + vertex -844.226 226.42 305.851 + vertex -848.52 231.583 304.658 + endloop + endfacet + facet normal -0.37714 -0.50242 -0.778036 + outer loop + vertex -699.324 139.152 303.072 + vertex -698.424 141.092 301.383 + vertex -695.219 137.722 302.006 + endloop + endfacet + facet normal -0.308459 -0.488381 -0.816295 + outer loop + vertex -843.573 232.187 302.116 + vertex -843.866 228.944 304.167 + vertex -847.718 234.487 302.306 + endloop + endfacet + facet normal -0.404205 -0.482431 -0.777096 + outer loop + vertex -698.424 141.092 301.383 + vertex -697.387 142.631 299.889 + vertex -694.412 139.658 300.186 + endloop + endfacet + facet normal -0.21049 -0.49672 -0.842 + outer loop + vertex -841.82 232.994 301.202 + vertex -843.573 232.187 302.116 + vertex -846.407 237.831 299.495 + endloop + endfacet + facet normal -0.290589 -0.586123 -0.756318 + outer loop + vertex -848.685 239.425 299.201 + vertex -849.601 237.948 300.697 + vertex -850.001 240.376 298.969 + endloop + endfacet + facet normal -0.127019 -0.458203 -0.879725 + outer loop + vertex -840.883 233.503 300.801 + vertex -841.82 232.994 301.202 + vertex -844.982 237.728 299.193 + endloop + endfacet + facet normal -0.286736 -0.581934 -0.761009 + outer loop + vertex -848.155 240.73 298.003 + vertex -848.685 239.425 299.201 + vertex -850.001 240.376 298.969 + endloop + endfacet + facet normal -0.212011 -0.536769 -0.816658 + outer loop + vertex -846.407 237.831 299.495 + vertex -847.069 239.907 298.302 + vertex -844.982 237.728 299.193 + endloop + endfacet + facet normal 0.215116 0.846593 -0.486833 + outer loop + vertex -703.301 146.756 300.553 + vertex -710.334 149.551 302.306 + vertex -705.532 147.698 301.204 + endloop + endfacet + facet normal -0.155801 0.0876573 -0.983891 + outer loop + vertex -710.334 149.551 302.306 + vertex -719.668 153.353 304.122 + vertex -716.102 152.467 303.479 + endloop + endfacet + facet normal -0.128527 0.0300528 -0.991251 + outer loop + vertex -719.668 153.353 304.122 + vertex -728.585 157.163 305.394 + vertex -726.637 156.878 305.133 + endloop + endfacet + facet normal -0.100581 -0.00952337 -0.994883 + outer loop + vertex -728.585 157.163 305.394 + vertex -737.833 161.525 306.287 + vertex -733.169 159.983 305.831 + endloop + endfacet + facet normal -0.0980202 -0.0701571 -0.992708 + outer loop + vertex -737.833 161.525 306.287 + vertex -746.317 165.493 306.845 + vertex -744.4 165.535 306.652 + endloop + endfacet + facet normal -0.0574205 -0.0363639 -0.997688 + outer loop + vertex -746.317 165.493 306.845 + vertex -754.763 169.733 307.176 + vertex -750.354 168.068 306.983 + endloop + endfacet + facet normal -0.0578912 -0.0699839 -0.995867 + outer loop + vertex -754.763 169.733 307.176 + vertex -763.793 174.511 307.365 + vertex -760.072 173.417 307.226 + endloop + endfacet + facet normal -0.0257656 -0.0647195 -0.997571 + outer loop + vertex -794.487 193.681 307.374 + vertex -802.048 199.151 307.214 + vertex -799.253 197.958 307.219 + endloop + endfacet + facet normal -0.00472931 -0.0631475 -0.997993 + outer loop + vertex -802.048 199.151 307.214 + vertex -808.581 204.289 306.92 + vertex -806.511 203.529 306.958 + endloop + endfacet + facet normal 0.0151832 -0.0734605 -0.997183 + outer loop + vertex -808.581 204.289 306.92 + vertex -815.476 210.131 306.385 + vertex -812.043 208.211 306.578 + endloop + endfacet + facet normal 0.0249982 -0.102775 -0.99439 + outer loop + vertex -815.476 210.131 306.385 + vertex -821.6 215.428 305.683 + vertex -820.245 214.913 305.77 + endloop + endfacet + facet normal 0.135327 -0.0518465 -0.989444 + outer loop + vertex -821.6 215.428 305.683 + vertex -827.992 221.421 304.495 + vertex -824.514 218.826 305.107 + endloop + endfacet + facet normal 0.338363 0.0802524 -0.937587 + outer loop + vertex -827.992 221.421 304.495 + vertex -835.474 228.764 302.423 + vertex -831.731 225.614 303.504 + endloop + endfacet + facet normal 0.173371 -0.17209 -0.969705 + outer loop + vertex -835.474 228.764 302.423 + vertex -841.421 234.722 300.303 + vertex -839.593 233.414 300.862 + endloop + endfacet + facet normal -0.702093 -0.542745 0.46097 + outer loop + vertex -846.275 239.954 298.02 + vertex -847.529 241.119 297.482 + vertex -846.419 240.047 297.911 + endloop + endfacet + facet normal -0.206631 -0.648058 -0.733024 + outer loop + vertex -847.529 241.119 297.482 + vertex -848.155 240.73 298.003 + vertex -848.286 242.207 296.733 + endloop + endfacet + facet normal 0.324724 0.920347 -0.21798 + outer loop + vertex -701.366 145.955 300.051 + vertex -703.301 146.756 300.553 + vertex -705.532 147.698 301.204 + endloop + endfacet + facet normal 0.451148 0.801434 0.392643 + outer loop + vertex -698.067 144.583 299.06 + vertex -701.366 145.955 300.051 + vertex -701.203 145.87 300.036 + endloop + endfacet + facet normal -0.457048 -0.548432 -0.700235 + outer loop + vertex -695.433 143.453 298.225 + vertex -698.067 144.583 299.06 + vertex -696.135 143.944 298.3 + endloop + endfacet + facet normal -0.507634 -0.694531 -0.509837 + outer loop + vertex -844.274 237.637 299.058 + vertex -846.419 240.047 297.911 + vertex -845.914 239.558 298.075 + endloop + endfacet + facet normal 0.137341 -0.220719 -0.965619 + outer loop + vertex -841.421 234.722 300.303 + vertex -842.439 235.736 299.926 + vertex -839.593 233.414 300.862 + endloop + endfacet + facet normal -0.0626045 -0.46393 -0.883657 + outer loop + vertex -842.439 235.736 299.926 + vertex -844.274 237.637 299.058 + vertex -843.232 236.928 299.357 + endloop + endfacet + facet normal -0.463179 -0.697863 -0.546307 + outer loop + vertex -848.286 242.207 296.733 + vertex -846.419 240.047 297.911 + vertex -847.529 241.119 297.482 + endloop + endfacet + facet normal -0.675896 -0.726626 -0.123202 + outer loop + vertex -851.659 224.196 315.353 + vertex -856.677 228.864 315.35 + vertex -855.088 227.706 313.457 + endloop + endfacet + facet normal -0.509159 -0.549754 -0.662214 + outer loop + vertex -852.034 226.793 310.438 + vertex -852.667 229.613 308.584 + vertex -848.616 224.851 309.422 + endloop + endfacet + facet normal -0.214176 -0.49934 -0.839517 + outer loop + vertex -841.82 232.994 301.202 + vertex -846.407 237.831 299.495 + vertex -844.982 237.728 299.193 + endloop + endfacet + facet normal -0.272238 -0.959865 -0.0674156 + outer loop + vertex -654.117 114.531 310.879 + vertex -656.99 115.42 309.823 + vertex -650.338 113.554 309.534 + endloop + endfacet + facet normal -0.274472 -0.961335 -0.0223485 + outer loop + vertex -657.518 115.481 311.811 + vertex -659.841 116.168 310.764 + vertex -654.117 114.531 310.879 + endloop + endfacet + facet normal -0.273176 -0.95978 -0.0647915 + outer loop + vertex -654.117 114.531 310.879 + vertex -659.841 116.168 310.764 + vertex -656.99 115.42 309.823 + endloop + endfacet + facet normal -0.275283 -0.961301 0.0109091 + outer loop + vertex -659.821 116.147 312.437 + vertex -661.808 116.704 311.379 + vertex -657.518 115.481 311.811 + endloop + endfacet + facet normal -0.271402 -0.962011 -0.0296069 + outer loop + vertex -657.518 115.481 311.811 + vertex -661.808 116.704 311.379 + vertex -659.841 116.168 310.764 + endloop + endfacet + facet normal -0.271801 -0.960891 0.0530394 + outer loop + vertex -660.663 116.414 312.957 + vertex -662.469 116.865 311.864 + vertex -659.821 116.147 312.437 + endloop + endfacet + facet normal -0.255559 -0.966365 -0.0287894 + outer loop + vertex -659.821 116.147 312.437 + vertex -662.469 116.865 311.864 + vertex -661.808 116.704 311.379 + endloop + endfacet + facet normal -0.245437 -0.902631 0.353578 + outer loop + vertex -643.174 113.365 318.156 + vertex -646.442 114.453 318.663 + vertex -644.004 113.509 317.946 + endloop + endfacet + facet normal -0.24094 -0.913237 0.328553 + outer loop + vertex -641.901 112.949 317.931 + vertex -643.174 113.365 318.156 + vertex -644.004 113.509 317.946 + endloop + endfacet + facet normal -0.248765 -0.94004 0.233324 + outer loop + vertex -640.174 112.396 317.544 + vertex -641.901 112.949 317.931 + vertex -644.004 113.509 317.946 + endloop + endfacet + facet normal -0.217743 -0.926422 0.307131 + outer loop + vertex -636.738 111.367 316.879 + vertex -640.174 112.396 317.544 + vertex -638.267 111.705 316.814 + endloop + endfacet + facet normal -0.217858 -0.927711 0.303134 + outer loop + vertex -633.181 110.237 315.976 + vertex -636.738 111.367 316.879 + vertex -638.267 111.705 316.814 + endloop + endfacet + facet normal -0.267395 -0.963254 0.0253248 + outer loop + vertex -620.098 106.185 303.474 + vertex -618.05 105.635 304.182 + vertex -621.404 106.547 303.427 + endloop + endfacet + facet normal -0.266415 -0.963835 -0.00666025 + outer loop + vertex -621.067 106.455 303.17 + vertex -620.098 106.185 303.474 + vertex -621.404 106.547 303.427 + endloop + endfacet + facet normal -0.277136 -0.960583 -0.0218231 + outer loop + vertex -622.771 106.958 302.691 + vertex -621.067 106.455 303.17 + vertex -621.404 106.547 303.427 + endloop + endfacet + facet normal -0.271268 -0.959234 -0.0792741 + outer loop + vertex -624.915 107.621 301.997 + vertex -622.771 106.958 302.691 + vertex -626.648 108.12 301.893 + endloop + endfacet + facet normal -0.268809 -0.956957 -0.109436 + outer loop + vertex -628.112 108.616 301.15 + vertex -624.915 107.621 301.997 + vertex -626.648 108.12 301.893 + endloop + endfacet + facet normal -0.300459 -0.951618 -0.0644048 + outer loop + vertex -630.562 109.437 300.447 + vertex -628.112 108.616 301.15 + vertex -632.103 109.924 300.451 + endloop + endfacet + facet normal -0.299034 -0.946721 -0.119576 + outer loop + vertex -633.61 110.485 299.779 + vertex -630.562 109.437 300.447 + vertex -632.103 109.924 300.451 + endloop + endfacet + facet normal -0.325739 -0.94116 -0.0900665 + outer loop + vertex -636.029 111.376 299.21 + vertex -633.61 110.485 299.779 + vertex -637.601 111.917 299.245 + endloop + endfacet + facet normal -0.324546 -0.933637 -0.151631 + outer loop + vertex -639.067 112.52 298.67 + vertex -636.029 111.376 299.21 + vertex -637.601 111.917 299.245 + endloop + endfacet + facet normal -0.343199 -0.92892 -0.139002 + outer loop + vertex -641.252 113.397 298.205 + vertex -639.067 112.52 298.67 + vertex -643.054 114.062 298.212 + endloop + endfacet + facet normal -0.341745 -0.924686 -0.167827 + outer loop + vertex -643.139 114.151 297.89 + vertex -641.252 113.397 298.205 + vertex -643.054 114.062 298.212 + endloop + endfacet + facet normal -0.361321 -0.918452 -0.160916 + outer loop + vertex -644.959 114.914 297.623 + vertex -643.139 114.151 297.89 + vertex -643.054 114.062 298.212 + endloop + endfacet + facet normal -0.325657 -0.904654 -0.27486 + outer loop + vertex -665.195 118.056 309.527 + vertex -663.734 117.815 308.587 + vertex -664.018 117.78 309.039 + endloop + endfacet + facet normal -0.362662 -0.931772 0.0166588 + outer loop + vertex -663.691 117.265 311.571 + vertex -666.04 118.158 310.344 + vertex -664.261 117.476 310.969 + endloop + endfacet + facet normal -0.322103 -0.945366 0.0503193 + outer loop + vertex -662.096 116.768 312.433 + vertex -663.691 117.265 311.571 + vertex -662.469 116.865 311.864 + endloop + endfacet + facet normal -0.294921 -0.93992 0.171968 + outer loop + vertex -660.546 116.492 313.583 + vertex -662.096 116.768 312.433 + vertex -660.663 116.414 312.957 + endloop + endfacet + facet normal -0.279094 -0.926561 0.252174 + outer loop + vertex -658.725 116.347 315.066 + vertex -660.546 116.492 313.583 + vertex -658.799 116.166 314.319 + endloop + endfacet + facet normal -0.253442 -0.916393 0.309825 + outer loop + vertex -657.328 116.444 316.497 + vertex -658.725 116.347 315.066 + vertex -657.068 116.145 315.825 + endloop + endfacet + facet normal -0.249291 -0.889788 0.38227 + outer loop + vertex -656.976 116.939 317.877 + vertex -657.328 116.444 316.497 + vertex -655.755 116.334 317.265 + endloop + endfacet + facet normal -0.242475 -0.96043 0.137043 + outer loop + vertex -632.442 109.944 315.473 + vertex -626.724 108.273 313.885 + vertex -628.672 108.892 314.774 + endloop + endfacet + facet normal -0.241083 -0.949591 0.200391 + outer loop + vertex -638.267 111.705 316.814 + vertex -632.442 109.944 315.473 + vertex -633.181 110.237 315.976 + endloop + endfacet + facet normal -0.247527 -0.938482 0.240795 + outer loop + vertex -644.004 113.509 317.946 + vertex -638.267 111.705 316.814 + vertex -640.174 112.396 317.544 + endloop + endfacet + facet normal -0.228183 -0.889748 0.395324 + outer loop + vertex -649.589 115.324 318.806 + vertex -644.004 113.509 317.946 + vertex -646.442 114.453 318.663 + endloop + endfacet + facet normal -0.286693 -0.958019 -0.00262686 + outer loop + vertex -621.404 106.547 303.427 + vertex -626.648 108.12 301.893 + vertex -622.771 106.958 302.691 + endloop + endfacet + facet normal -0.222607 -0.919754 0.323262 + outer loop + vertex -657.068 116.145 315.825 + vertex -655.755 116.334 317.265 + vertex -657.328 116.444 316.497 + endloop + endfacet + facet normal -0.306012 -0.951474 -0.0324481 + outer loop + vertex -626.648 108.12 301.893 + vertex -632.103 109.924 300.451 + vertex -628.112 108.616 301.15 + endloop + endfacet + facet normal -0.229237 -0.94056 0.250595 + outer loop + vertex -658.799 116.166 314.319 + vertex -657.068 116.145 315.825 + vertex -658.725 116.347 315.066 + endloop + endfacet + facet normal -0.332787 -0.942152 -0.0400363 + outer loop + vertex -632.103 109.924 300.451 + vertex -637.601 111.917 299.245 + vertex -633.61 110.485 299.779 + endloop + endfacet + facet normal -0.247597 -0.954713 0.164982 + outer loop + vertex -660.663 116.414 312.957 + vertex -658.799 116.166 314.319 + vertex -660.546 116.492 313.583 + endloop + endfacet + facet normal -0.3511 -0.932662 -0.0828829 + outer loop + vertex -637.601 111.917 299.245 + vertex -643.054 114.062 298.212 + vertex -639.067 112.52 298.67 + endloop + endfacet + facet normal -0.23594 -0.971709 -0.0106694 + outer loop + vertex -662.469 116.865 311.864 + vertex -660.663 116.414 312.957 + vertex -662.096 116.768 312.433 + endloop + endfacet + facet normal -0.357355 -0.917833 -0.17286 + outer loop + vertex -643.054 114.062 298.212 + vertex -647.906 116.093 297.453 + vertex -644.959 114.914 297.623 + endloop + endfacet + facet normal -0.300522 -0.952491 -0.0494689 + outer loop + vertex -664.261 117.476 310.969 + vertex -662.469 116.865 311.864 + vertex -663.691 117.265 311.571 + endloop + endfacet + facet normal -0.326965 -0.902913 -0.279001 + outer loop + vertex -664.018 117.78 309.039 + vertex -665.383 118.042 309.793 + vertex -665.195 118.056 309.527 + endloop + endfacet + facet normal -0.305038 -0.731038 0.610357 + outer loop + vertex -652.951 108.385 27.3051 + vertex -658.993 111.454 27.9623 + vertex -655.922 109.109 26.6883 + endloop + endfacet + facet normal -0.314982 -0.737211 0.59775 + outer loop + vertex -658.993 111.454 27.9623 + vertex -659.174 110.941 27.2338 + vertex -655.922 109.109 26.6883 + endloop + endfacet + facet normal -0.300908 -0.72033 0.624963 + outer loop + vertex -655.922 109.109 26.6883 + vertex -659.174 110.941 27.2338 + vertex -657.024 109.158 26.2132 + endloop + endfacet + facet normal -0.407098 -0.871144 0.274554 + outer loop + vertex -644.075 112.55 42.2262 + vertex -648.123 114.705 43.0637 + vertex -642.478 111.408 40.9725 + endloop + endfacet + facet normal -0.385188 -0.879312 0.280072 + outer loop + vertex -635.667 108.436 41.0682 + vertex -638.446 109.871 41.7524 + vertex -639.744 110.329 41.4066 + endloop + endfacet + facet normal -0.313605 -0.733198 0.603384 + outer loop + vertex -661.251 112.225 27.715 + vertex -658.785 110.265 26.6144 + vertex -659.174 110.941 27.2338 + endloop + endfacet + facet normal -0.319824 -0.753958 0.573812 + outer loop + vertex -664.199 114.469 29.0202 + vertex -661.251 112.225 27.715 + vertex -662.491 113.381 28.542 + endloop + endfacet + facet normal -0.270624 -0.883978 0.381243 + outer loop + vertex -664.527 116.096 31.3297 + vertex -666.359 116.166 30.1934 + vertex -665.068 116.071 30.8872 + endloop + endfacet + facet normal -0.325811 -0.853565 0.40654 + outer loop + vertex -659.979 115.909 34.4929 + vertex -662.292 115.947 32.7172 + vertex -660.432 115.607 33.495 + endloop + endfacet + facet normal -0.330601 -0.860956 0.386598 + outer loop + vertex -657.864 116.036 36.583 + vertex -659.979 115.909 34.4929 + vertex -658.314 115.638 35.3122 + endloop + endfacet + facet normal -0.389271 -0.884194 0.258205 + outer loop + vertex -639.744 110.329 41.4066 + vertex -632.609 106.762 39.9469 + vertex -635.667 108.436 41.0682 + endloop + endfacet + facet normal -0.327581 -0.831873 0.447971 + outer loop + vertex -665.068 116.071 30.8872 + vertex -662.735 115.738 31.9752 + vertex -664.527 116.096 31.3297 + endloop + endfacet + facet normal -0.325542 -0.733692 0.596422 + outer loop + vertex -657.024 109.158 26.2132 + vertex -659.174 110.941 27.2338 + vertex -658.785 110.265 26.6144 + endloop + endfacet + facet normal -0.344097 -0.761979 0.548621 + outer loop + vertex -659.174 110.941 27.2338 + vertex -662.491 113.381 28.542 + vertex -661.251 112.225 27.715 + endloop + endfacet + facet normal -0.378448 -0.861943 0.337388 + outer loop + vertex -642.478 111.408 40.9725 + vertex -648.123 114.705 43.0637 + vertex -650.131 115.242 42.1812 + endloop + endfacet + facet normal -0.218152 -0.974509 -0.0523557 + outer loop + vertex -484.804 71.6612 305.521 + vertex -480.356 70.7639 303.688 + vertex -482.177 71.0605 305.754 + endloop + endfacet + facet normal -0.216026 -0.971279 -0.0997531 + outer loop + vertex -480.356 70.7639 303.688 + vertex -473.8 69.5734 301.083 + vertex -476.797 70.001 303.408 + endloop + endfacet + facet normal -0.207317 -0.965194 -0.15944 + outer loop + vertex -473.8 69.5734 301.083 + vertex -465.945 68.3304 298.394 + vertex -469.445 68.7198 300.587 + endloop + endfacet + facet normal -0.184644 -0.964312 -0.189759 + outer loop + vertex -465.945 68.3304 298.394 + vertex -458.067 67.3106 295.911 + vertex -461.088 67.5212 297.78 + endloop + endfacet + facet normal -0.018795 -0.81609 -0.577619 + outer loop + vertex -372.11 55.1799 304.659 + vertex -366.173 56.5601 302.516 + vertex -366.25 54.0845 306.016 + endloop + endfacet + facet normal 0.00219885 -0.816452 -0.57741 + outer loop + vertex -366.25 54.0845 306.016 + vertex -366.173 56.5601 302.516 + vertex -360.862 55.5222 304.003 + endloop + endfacet + facet normal -0.0162019 -0.84161 -0.539842 + outer loop + vertex -378.711 56.6533 302.56 + vertex -372.066 57.9294 300.371 + vertex -372.11 55.1799 304.659 + endloop + endfacet + facet normal 0.000837457 -0.841801 -0.539787 + outer loop + vertex -372.11 55.1799 304.659 + vertex -372.066 57.9294 300.371 + vertex -366.173 56.5601 302.516 + endloop + endfacet + facet normal -0.0102327 -0.868282 -0.495966 + outer loop + vertex -385.202 58.3195 299.777 + vertex -377.998 59.4607 297.63 + vertex -378.711 56.6533 302.56 + endloop + endfacet + facet normal 0.00405712 -0.869209 -0.494427 + outer loop + vertex -378.711 56.6533 302.56 + vertex -377.998 59.4607 297.63 + vertex -372.066 57.9294 300.371 + endloop + endfacet + facet normal 0.0223995 -0.780662 -0.624552 + outer loop + vertex -366.173 56.5601 302.516 + vertex -359.764 58.3554 300.501 + vertex -360.862 55.5222 304.003 + endloop + endfacet + facet normal 0.0364056 -0.78247 -0.621623 + outer loop + vertex -360.862 55.5222 304.003 + vertex -359.764 58.3554 300.501 + vertex -354.944 57.2749 302.144 + endloop + endfacet + facet normal 0.0259348 -0.808718 -0.587624 + outer loop + vertex -372.066 57.9294 300.371 + vertex -365.024 59.6547 298.307 + vertex -366.173 56.5601 302.516 + endloop + endfacet + facet normal 0.0434533 -0.810486 -0.584143 + outer loop + vertex -366.173 56.5601 302.516 + vertex -365.024 59.6547 298.307 + vertex -359.764 58.3554 300.501 + endloop + endfacet + facet normal 0.0322394 -0.841195 -0.539771 + outer loop + vertex -377.998 59.4607 297.63 + vertex -370.343 61.0553 295.602 + vertex -372.066 57.9294 300.371 + endloop + endfacet + facet normal 0.049908 -0.843457 -0.534873 + outer loop + vertex -372.066 57.9294 300.371 + vertex -370.343 61.0553 295.602 + vertex -365.024 59.6547 298.307 + endloop + endfacet + facet normal 0.0401056 -0.870931 -0.489766 + outer loop + vertex -383.483 61.0248 294.4 + vertex -375.347 62.495 292.452 + vertex -377.998 59.4607 297.63 + endloop + endfacet + facet normal 0.0536433 -0.873298 -0.484224 + outer loop + vertex -377.998 59.4607 297.63 + vertex -375.347 62.495 292.452 + vertex -370.343 61.0553 295.602 + endloop + endfacet + facet normal 0.068903 -0.760568 -0.645592 + outer loop + vertex -356.684 60.4433 298.37 + vertex -354.619 59.5224 299.676 + vertex -359.764 58.3554 300.501 + endloop + endfacet + facet normal 0.0741276 -0.742179 -0.666089 + outer loop + vertex -351.692 59.1877 300.374 + vertex -354.944 57.2749 302.144 + vertex -354.619 59.5224 299.676 + endloop + endfacet + facet normal 0.0611527 -0.741985 -0.667621 + outer loop + vertex -354.944 57.2749 302.144 + vertex -359.764 58.3554 300.501 + vertex -354.619 59.5224 299.676 + endloop + endfacet + facet normal 0.0818208 -0.800067 -0.594304 + outer loop + vertex -361.562 61.7411 295.975 + vertex -359.556 60.8106 297.504 + vertex -365.024 59.6547 298.307 + endloop + endfacet + facet normal 0.0903045 -0.773497 -0.627333 + outer loop + vertex -356.684 60.4433 298.37 + vertex -359.764 58.3554 300.501 + vertex -359.556 60.8106 297.504 + endloop + endfacet + facet normal 0.0712091 -0.774047 -0.629111 + outer loop + vertex -359.764 58.3554 300.501 + vertex -365.024 59.6547 298.307 + vertex -359.556 60.8106 297.504 + endloop + endfacet + facet normal 0.0896263 -0.838417 -0.53761 + outer loop + vertex -366.373 63.0625 293.134 + vertex -364.47 62.1285 294.908 + vertex -370.343 61.0553 295.602 + endloop + endfacet + facet normal 0.102602 -0.812191 -0.574299 + outer loop + vertex -361.562 61.7411 295.975 + vertex -365.024 59.6547 298.307 + vertex -364.47 62.1285 294.908 + endloop + endfacet + facet normal 0.0800567 -0.812142 -0.577941 + outer loop + vertex -365.024 59.6547 298.307 + vertex -370.343 61.0553 295.602 + vertex -364.47 62.1285 294.908 + endloop + endfacet + facet normal 0.092247 -0.867142 -0.489444 + outer loop + vertex -370.932 64.4013 289.906 + vertex -369.245 63.4754 291.865 + vertex -375.347 62.495 292.452 + endloop + endfacet + facet normal 0.106956 -0.848638 -0.518049 + outer loop + vertex -366.373 63.0625 293.134 + vertex -370.343 61.0553 295.602 + vertex -369.245 63.4754 291.865 + endloop + endfacet + facet normal 0.0858257 -0.847628 -0.523603 + outer loop + vertex -370.343 61.0553 295.602 + vertex -375.347 62.495 292.452 + vertex -369.245 63.4754 291.865 + endloop + endfacet + facet normal 0.0967375 -0.88923 -0.447115 + outer loop + vertex -375.047 65.6997 286.448 + vertex -373.633 64.8122 288.519 + vertex -379.917 63.8966 288.98 + endloop + endfacet + facet normal 0.107785 -0.876378 -0.469408 + outer loop + vertex -370.932 64.4013 289.906 + vertex -375.347 62.495 292.452 + vertex -373.633 64.8122 288.519 + endloop + endfacet + facet normal 0.0926006 -0.874987 -0.475208 + outer loop + vertex -375.347 62.495 292.452 + vertex -379.917 63.8966 288.98 + vertex -373.633 64.8122 288.519 + endloop + endfacet + facet normal 0.0983628 -0.907739 -0.407842 + outer loop + vertex -378.99 66.9619 282.686 + vertex -377.667 66.1053 284.912 + vertex -384.324 65.2155 285.287 + endloop + endfacet + facet normal 0.110834 -0.897843 -0.426138 + outer loop + vertex -375.047 65.6997 286.448 + vertex -379.917 63.8966 288.98 + vertex -377.667 66.1053 284.912 + endloop + endfacet + facet normal 0.0953368 -0.895997 -0.433706 + outer loop + vertex -379.917 63.8966 288.98 + vertex -384.324 65.2155 285.287 + vertex -377.667 66.1053 284.912 + endloop + endfacet + facet normal 0.090692 -0.921188 -0.378402 + outer loop + vertex -382.627 68.0702 279.056 + vertex -381.688 67.3143 281.121 + vertex -389.055 66.3289 281.754 + endloop + endfacet + facet normal 0.108068 -0.91364 -0.391896 + outer loop + vertex -378.99 66.9619 282.686 + vertex -384.324 65.2155 285.287 + vertex -381.688 67.3143 281.121 + endloop + endfacet + facet normal 0.0871212 -0.910739 -0.403689 + outer loop + vertex -384.324 65.2155 285.287 + vertex -389.055 66.3289 281.754 + vertex -381.688 67.3143 281.121 + endloop + endfacet + facet normal 0.10788 -0.938935 -0.326745 + outer loop + vertex -385.164 68.9105 276.247 + vertex -385.375 68.7763 276.563 + vertex -392.268 67.3729 278.32 + endloop + endfacet + facet normal 0.101163 -0.921616 -0.374687 + outer loop + vertex -383.965 68.8853 276.676 + vertex -388.958 67.567 278.57 + vertex -385.375 68.7763 276.563 + endloop + endfacet + facet normal 0.0837603 -0.912554 -0.400286 + outer loop + vertex -388.958 67.567 278.57 + vertex -392.268 67.3729 278.32 + vertex -385.375 68.7763 276.563 + endloop + endfacet + facet normal 0.122706 -0.631038 -0.765985 + outer loop + vertex -348.58 60.5419 299.496 + vertex -345.653 62.4053 298.43 + vertex -345.879 60.3297 300.103 + endloop + endfacet + facet normal 0.157716 -0.630212 -0.760236 + outer loop + vertex -345.879 60.3297 300.103 + vertex -345.653 62.4053 298.43 + vertex -343.144 62.3264 299.015 + endloop + endfacet + facet normal 0.0957739 -0.687233 -0.720096 + outer loop + vertex -351.692 59.1877 300.374 + vertex -348.58 60.5419 299.496 + vertex -349.526 58.3832 301.43 + endloop + endfacet + facet normal 0.107052 -0.689125 -0.716691 + outer loop + vertex -349.526 58.3832 301.43 + vertex -348.58 60.5419 299.496 + vertex -345.879 60.3297 300.103 + endloop + endfacet + facet normal 0.139182 -0.681502 -0.718459 + outer loop + vertex -353.543 61.7255 297.491 + vertex -350.453 63.4316 296.471 + vertex -351.14 61.0804 298.569 + endloop + endfacet + facet normal 0.153566 -0.682358 -0.714706 + outer loop + vertex -351.14 61.0804 298.569 + vertex -350.453 63.4316 296.471 + vertex -348.154 62.8265 297.543 + endloop + endfacet + facet normal 0.106013 -0.725746 -0.679745 + outer loop + vertex -356.684 60.4433 298.37 + vertex -353.543 61.7255 297.491 + vertex -354.619 59.5224 299.676 + endloop + endfacet + facet normal 0.10931 -0.726276 -0.678656 + outer loop + vertex -354.619 59.5224 299.676 + vertex -353.543 61.7255 297.491 + vertex -351.14 61.0804 298.569 + endloop + endfacet + facet normal 0.0887571 -0.700981 -0.707636 + outer loop + vertex -354.619 59.5224 299.676 + vertex -351.14 61.0804 298.569 + vertex -351.692 59.1877 300.374 + endloop + endfacet + facet normal 0.107058 -0.702476 -0.703609 + outer loop + vertex -351.692 59.1877 300.374 + vertex -351.14 61.0804 298.569 + vertex -348.58 60.5419 299.496 + endloop + endfacet + facet normal 0.130148 -0.658094 -0.741602 + outer loop + vertex -351.14 61.0804 298.569 + vertex -348.154 62.8265 297.543 + vertex -348.58 60.5419 299.496 + endloop + endfacet + facet normal 0.150494 -0.658375 -0.737491 + outer loop + vertex -348.58 60.5419 299.496 + vertex -348.154 62.8265 297.543 + vertex -345.653 62.4053 298.43 + endloop + endfacet + facet normal 0.159391 -0.732807 -0.661505 + outer loop + vertex -358.113 62.986 295.107 + vertex -354.698 64.6435 294.094 + vertex -355.848 62.3664 296.339 + endloop + endfacet + facet normal 0.174603 -0.734655 -0.655588 + outer loop + vertex -355.848 62.3664 296.339 + vertex -354.698 64.6435 294.094 + vertex -352.601 64.0519 295.315 + endloop + endfacet + facet normal 0.120263 -0.770085 -0.626503 + outer loop + vertex -361.562 61.7411 295.975 + vertex -358.113 62.986 295.107 + vertex -359.556 60.8106 297.504 + endloop + endfacet + facet normal 0.127951 -0.771534 -0.623189 + outer loop + vertex -359.556 60.8106 297.504 + vertex -358.113 62.986 295.107 + vertex -355.848 62.3664 296.339 + endloop + endfacet + facet normal 0.10427 -0.74327 -0.660816 + outer loop + vertex -359.556 60.8106 297.504 + vertex -355.848 62.3664 296.339 + vertex -356.684 60.4433 298.37 + endloop + endfacet + facet normal 0.120619 -0.745167 -0.655879 + outer loop + vertex -356.684 60.4433 298.37 + vertex -355.848 62.3664 296.339 + vertex -353.543 61.7255 297.491 + endloop + endfacet + facet normal 0.148963 -0.706997 -0.691351 + outer loop + vertex -355.848 62.3664 296.339 + vertex -352.601 64.0519 295.315 + vertex -353.543 61.7255 297.491 + endloop + endfacet + facet normal 0.164773 -0.708542 -0.686162 + outer loop + vertex -353.543 61.7255 297.491 + vertex -352.601 64.0519 295.315 + vertex -350.453 63.4316 296.471 + endloop + endfacet + facet normal 0.173423 -0.776952 -0.605203 + outer loop + vertex -362.626 64.2302 292.324 + vertex -358.915 65.8144 291.353 + vertex -360.378 63.6003 293.776 + endloop + endfacet + facet normal 0.18655 -0.778767 -0.598933 + outer loop + vertex -360.378 63.6003 293.776 + vertex -358.915 65.8144 291.353 + vertex -356.799 65.2227 292.782 + endloop + endfacet + facet normal 0.130455 -0.812709 -0.567879 + outer loop + vertex -366.373 63.0625 293.134 + vertex -362.626 64.2302 292.324 + vertex -364.47 62.1285 294.908 + endloop + endfacet + facet normal 0.136719 -0.814038 -0.564491 + outer loop + vertex -364.47 62.1285 294.908 + vertex -362.626 64.2302 292.324 + vertex -360.378 63.6003 293.776 + endloop + endfacet + facet normal 0.116628 -0.788477 -0.603906 + outer loop + vertex -364.47 62.1285 294.908 + vertex -360.378 63.6003 293.776 + vertex -361.562 61.7411 295.975 + endloop + endfacet + facet normal 0.135582 -0.791356 -0.596132 + outer loop + vertex -361.562 61.7411 295.975 + vertex -360.378 63.6003 293.776 + vertex -358.113 62.986 295.107 + endloop + endfacet + facet normal 0.166786 -0.75602 -0.632942 + outer loop + vertex -360.378 63.6003 293.776 + vertex -356.799 65.2227 292.782 + vertex -358.113 62.986 295.107 + endloop + endfacet + facet normal 0.182111 -0.758059 -0.626244 + outer loop + vertex -358.113 62.986 295.107 + vertex -356.799 65.2227 292.782 + vertex -354.698 64.6435 294.094 + endloop + endfacet + facet normal 0.182081 -0.810169 -0.5572 + outer loop + vertex -367.02 65.5098 289.132 + vertex -363.113 67.0375 288.188 + vertex -364.857 64.873 290.765 + endloop + endfacet + facet normal 0.190278 -0.811386 -0.552673 + outer loop + vertex -364.857 64.873 290.765 + vertex -363.113 67.0375 288.188 + vertex -361.027 66.4203 289.812 + endloop + endfacet + facet normal 0.137004 -0.844715 -0.517385 + outer loop + vertex -370.932 64.4013 289.906 + vertex -367.02 65.5098 289.132 + vertex -369.245 63.4754 291.865 + endloop + endfacet + facet normal 0.140126 -0.845431 -0.515375 + outer loop + vertex -369.245 63.4754 291.865 + vertex -367.02 65.5098 289.132 + vertex -364.857 64.873 290.765 + endloop + endfacet + facet normal 0.124808 -0.825233 -0.55083 + outer loop + vertex -369.245 63.4754 291.865 + vertex -364.857 64.873 290.765 + vertex -366.373 63.0625 293.134 + endloop + endfacet + facet normal 0.14064 -0.827996 -0.54281 + outer loop + vertex -366.373 63.0625 293.134 + vertex -364.857 64.873 290.765 + vertex -362.626 64.2302 292.324 + endloop + endfacet + facet normal 0.17662 -0.794788 -0.580618 + outer loop + vertex -364.857 64.873 290.765 + vertex -361.027 66.4203 289.812 + vertex -362.626 64.2302 292.324 + endloop + endfacet + facet normal 0.190083 -0.796696 -0.573711 + outer loop + vertex -362.626 64.2302 292.324 + vertex -361.027 66.4203 289.812 + vertex -358.915 65.8144 291.353 + endloop + endfacet + facet normal 0.190504 -0.83521 -0.515881 + outer loop + vertex -371.037 66.7592 285.741 + vertex -367.031 68.2406 284.822 + vertex -369.089 66.1442 287.456 + endloop + endfacet + facet normal 0.19527 -0.836009 -0.512795 + outer loop + vertex -369.089 66.1442 287.456 + vertex -367.031 68.2406 284.822 + vertex -365.121 67.6453 286.52 + endloop + endfacet + facet normal 0.146383 -0.869137 -0.472411 + outer loop + vertex -375.047 65.6997 286.448 + vertex -371.037 66.7592 285.741 + vertex -373.633 64.8122 288.519 + endloop + endfacet + facet normal 0.143609 -0.86845 -0.474522 + outer loop + vertex -373.633 64.8122 288.519 + vertex -371.037 66.7592 285.741 + vertex -369.089 66.1442 287.456 + endloop + endfacet + facet normal 0.131028 -0.851719 -0.507352 + outer loop + vertex -373.633 64.8122 288.519 + vertex -369.089 66.1442 287.456 + vertex -370.932 64.4013 289.906 + endloop + endfacet + facet normal 0.143117 -0.854133 -0.499974 + outer loop + vertex -370.932 64.4013 289.906 + vertex -369.089 66.1442 287.456 + vertex -367.02 65.5098 289.132 + endloop + endfacet + facet normal 0.184036 -0.82232 -0.538443 + outer loop + vertex -369.089 66.1442 287.456 + vertex -365.121 67.6453 286.52 + vertex -367.02 65.5098 289.132 + endloop + endfacet + facet normal 0.193273 -0.82379 -0.532931 + outer loop + vertex -367.02 65.5098 289.132 + vertex -365.121 67.6453 286.52 + vertex -363.113 67.0375 288.188 + endloop + endfacet + facet normal 0.200908 -0.85663 -0.475207 + outer loop + vertex -374.772 67.9813 282.079 + vertex -370.639 69.4093 281.252 + vertex -372.92 67.3769 283.951 + endloop + endfacet + facet normal 0.204949 -0.857288 -0.472286 + outer loop + vertex -372.92 67.3769 283.951 + vertex -370.639 69.4093 281.252 + vertex -368.861 68.8317 283.072 + endloop + endfacet + facet normal 0.152484 -0.888582 -0.432631 + outer loop + vertex -378.99 66.9619 282.686 + vertex -374.772 67.9813 282.079 + vertex -377.667 66.1053 284.912 + endloop + endfacet + facet normal 0.14989 -0.887938 -0.434856 + outer loop + vertex -377.667 66.1053 284.912 + vertex -374.772 67.9813 282.079 + vertex -372.92 67.3769 283.951 + endloop + endfacet + facet normal 0.139158 -0.872788 -0.467841 + outer loop + vertex -377.667 66.1053 284.912 + vertex -372.92 67.3769 283.951 + vertex -375.047 65.6997 286.448 + endloop + endfacet + facet normal 0.150141 -0.87511 -0.460044 + outer loop + vertex -375.047 65.6997 286.448 + vertex -372.92 67.3769 283.951 + vertex -371.037 66.7592 285.741 + endloop + endfacet + facet normal 0.195264 -0.84535 -0.497247 + outer loop + vertex -372.92 67.3769 283.951 + vertex -368.861 68.8317 283.072 + vertex -371.037 66.7592 285.741 + endloop + endfacet + facet normal 0.199444 -0.846053 -0.494384 + outer loop + vertex -371.037 66.7592 285.741 + vertex -368.861 68.8317 283.072 + vertex -367.031 68.2406 284.822 + endloop + endfacet + facet normal 0.202165 -0.871198 -0.447373 + outer loop + vertex -378.27 69.0826 278.419 + vertex -373.969 70.4711 277.659 + vertex -376.614 68.5601 280.185 + endloop + endfacet + facet normal 0.208196 -0.872498 -0.442042 + outer loop + vertex -376.614 68.5601 280.185 + vertex -373.969 70.4711 277.659 + vertex -372.375 69.9671 279.405 + endloop + endfacet + facet normal 0.151684 -0.903956 -0.399819 + outer loop + vertex -382.627 68.0702 279.056 + vertex -378.27 69.0826 278.419 + vertex -381.688 67.3143 281.121 + endloop + endfacet + facet normal 0.146953 -0.902497 -0.40485 + outer loop + vertex -381.688 67.3143 281.121 + vertex -378.27 69.0826 278.419 + vertex -376.614 68.5601 280.185 + endloop + endfacet + facet normal 0.137614 -0.888767 -0.437214 + outer loop + vertex -381.688 67.3143 281.121 + vertex -376.614 68.5601 280.185 + vertex -378.99 66.9619 282.686 + endloop + endfacet + facet normal 0.154798 -0.892636 -0.423366 + outer loop + vertex -378.99 66.9619 282.686 + vertex -376.614 68.5601 280.185 + vertex -374.772 67.9813 282.079 + endloop + endfacet + facet normal 0.202043 -0.864281 -0.460649 + outer loop + vertex -376.614 68.5601 280.185 + vertex -372.375 69.9671 279.405 + vertex -374.772 67.9813 282.079 + endloop + endfacet + facet normal 0.207659 -0.865241 -0.456329 + outer loop + vertex -374.772 67.9813 282.079 + vertex -372.375 69.9671 279.405 + vertex -370.639 69.4093 281.252 + endloop + endfacet + facet normal 0.208969 -0.874024 -0.43865 + outer loop + vertex -380.16 69.8759 275.946 + vertex -376.007 71.2569 275.172 + vertex -379.474 69.5312 276.959 + endloop + endfacet + facet normal 0.203276 -0.871165 -0.446935 + outer loop + vertex -379.474 69.5312 276.959 + vertex -376.007 71.2569 275.172 + vertex -375.228 70.9087 276.205 + endloop + endfacet + facet normal 0.16777 -0.914938 -0.367073 + outer loop + vertex -383.965 68.8853 276.676 + vertex -380.16 69.8759 275.946 + vertex -384.176 68.3362 277.948 + endloop + endfacet + facet normal 0.14438 -0.902948 -0.404772 + outer loop + vertex -384.176 68.3362 277.948 + vertex -380.16 69.8759 275.946 + vertex -379.474 69.5312 276.959 + endloop + endfacet + facet normal 0.141529 -0.899262 -0.41388 + outer loop + vertex -384.176 68.3362 277.948 + vertex -379.474 69.5312 276.959 + vertex -382.627 68.0702 279.056 + endloop + endfacet + facet normal 0.151148 -0.903054 -0.402054 + outer loop + vertex -382.627 68.0702 279.056 + vertex -379.474 69.5312 276.959 + vertex -378.27 69.0826 278.419 + endloop + endfacet + facet normal 0.205946 -0.874797 -0.438539 + outer loop + vertex -379.474 69.5312 276.959 + vertex -375.228 70.9087 276.205 + vertex -378.27 69.0826 278.419 + endloop + endfacet + facet normal 0.204435 -0.87431 -0.440213 + outer loop + vertex -378.27 69.0826 278.419 + vertex -375.228 70.9087 276.205 + vertex -373.969 70.4711 277.659 + endloop + endfacet + facet normal 0.187015 -0.853474 -0.486424 + outer loop + vertex -380.951 70.073 275.271 + vertex -376.701 71.5182 274.369 + vertex -380.575 70.0706 275.419 + endloop + endfacet + facet normal 0.201343 -0.868098 -0.453725 + outer loop + vertex -380.575 70.0706 275.419 + vertex -376.701 71.5182 274.369 + vertex -376.388 71.4814 274.578 + endloop + endfacet + facet normal 0.198089 -0.942869 -0.267877 + outer loop + vertex -385.164 68.9105 276.247 + vertex -380.951 70.073 275.271 + vertex -385.375 68.7763 276.563 + endloop + endfacet + facet normal 0.150378 -0.906428 -0.394683 + outer loop + vertex -385.375 68.7763 276.563 + vertex -380.951 70.073 275.271 + vertex -380.575 70.0706 275.419 + endloop + endfacet + facet normal 0.10688 -0.85087 -0.51439 + outer loop + vertex -385.375 68.7763 276.563 + vertex -380.575 70.0706 275.419 + vertex -383.965 68.8853 276.676 + endloop + endfacet + facet normal 0.145546 -0.884994 -0.442269 + outer loop + vertex -383.965 68.8853 276.676 + vertex -380.575 70.0706 275.419 + vertex -380.16 69.8759 275.946 + endloop + endfacet + facet normal 0.194906 -0.859832 -0.471911 + outer loop + vertex -380.575 70.0706 275.419 + vertex -376.388 71.4814 274.578 + vertex -380.16 69.8759 275.946 + endloop + endfacet + facet normal 0.202809 -0.865908 -0.457244 + outer loop + vertex -380.16 69.8759 275.946 + vertex -376.388 71.4814 274.578 + vertex -376.007 71.2569 275.172 + endloop + endfacet + facet normal 0.308478 -0.362469 0.879464 + outer loop + vertex -383.988 69.1495 275.933 + vertex -381.279 69.9395 275.309 + vertex -385.164 68.9105 276.247 + endloop + endfacet + facet normal 0.335794 -0.62463 0.705039 + outer loop + vertex -385.164 68.9105 276.247 + vertex -381.279 69.9395 275.309 + vertex -380.951 70.073 275.271 + endloop + endfacet + facet normal 0.376373 -0.785945 0.490544 + outer loop + vertex -381.279 69.9395 275.309 + vertex -377.345 71.2844 274.445 + vertex -380.951 70.073 275.271 + endloop + endfacet + facet normal 0.355548 -0.908457 0.219751 + outer loop + vertex -380.951 70.073 275.271 + vertex -377.345 71.2844 274.445 + vertex -376.701 71.5182 274.369 + endloop + endfacet + facet normal 0.215491 -0.520332 -0.826329 + outer loop + vertex -343.089 64.5185 297.452 + vertex -340.71 66.8847 296.582 + vertex -340.688 64.5476 298.059 + endloop + endfacet + facet normal 0.250369 -0.515631 -0.819415 + outer loop + vertex -340.688 64.5476 298.059 + vertex -340.71 66.8847 296.582 + vertex -338.379 67.037 297.199 + endloop + endfacet + facet normal 0.16882 -0.575234 -0.800379 + outer loop + vertex -345.653 62.4053 298.43 + vertex -343.089 64.5185 297.452 + vertex -343.144 62.3264 299.015 + endloop + endfacet + facet normal 0.207879 -0.571538 -0.793808 + outer loop + vertex -343.144 62.3264 299.015 + vertex -343.089 64.5185 297.452 + vertex -340.688 64.5476 298.059 + endloop + endfacet + facet normal 0.236325 -0.575176 -0.783149 + outer loop + vertex -347.656 65.4036 295.506 + vertex -345.059 67.6718 294.624 + vertex -345.479 64.8498 296.57 + endloop + endfacet + facet normal 0.257714 -0.574188 -0.777105 + outer loop + vertex -345.479 64.8498 296.57 + vertex -345.059 67.6718 294.624 + vertex -342.997 67.1554 295.689 + endloop + endfacet + facet normal 0.18497 -0.631229 -0.753217 + outer loop + vertex -350.453 63.4316 296.471 + vertex -347.656 65.4036 295.506 + vertex -348.154 62.8265 297.543 + endloop + endfacet + facet normal 0.205002 -0.631081 -0.748138 + outer loop + vertex -348.154 62.8265 297.543 + vertex -347.656 65.4036 295.506 + vertex -345.479 64.8498 296.57 + endloop + endfacet + facet normal 0.173872 -0.604141 -0.777677 + outer loop + vertex -348.154 62.8265 297.543 + vertex -345.479 64.8498 296.57 + vertex -345.653 62.4053 298.43 + endloop + endfacet + facet normal 0.201654 -0.60217 -0.772481 + outer loop + vertex -345.653 62.4053 298.43 + vertex -345.479 64.8498 296.57 + vertex -343.089 64.5185 297.452 + endloop + endfacet + facet normal 0.222024 -0.5472 -0.807018 + outer loop + vertex -345.479 64.8498 296.57 + vertex -342.997 67.1554 295.689 + vertex -343.089 64.5185 297.452 + endloop + endfacet + facet normal 0.248477 -0.544272 -0.801266 + outer loop + vertex -343.089 64.5185 297.452 + vertex -342.997 67.1554 295.689 + vertex -340.71 66.8847 296.582 + endloop + endfacet + facet normal 0.269749 -0.63131 -0.727106 + outer loop + vertex -351.611 66.5712 293.131 + vertex -348.771 68.8046 292.245 + vertex -349.661 66.0005 294.35 + endloop + endfacet + facet normal 0.288803 -0.631627 -0.719472 + outer loop + vertex -349.661 66.0005 294.35 + vertex -348.771 68.8046 292.245 + vertex -346.941 68.2504 293.467 + endloop + endfacet + facet normal 0.211635 -0.686374 -0.695773 + outer loop + vertex -354.698 64.6435 294.094 + vertex -351.611 66.5712 293.131 + vertex -352.601 64.0519 295.315 + endloop + endfacet + facet normal 0.229479 -0.687494 -0.688978 + outer loop + vertex -352.601 64.0519 295.315 + vertex -351.611 66.5712 293.131 + vertex -349.661 66.0005 294.35 + endloop + endfacet + facet normal 0.199474 -0.659805 -0.724478 + outer loop + vertex -352.601 64.0519 295.315 + vertex -349.661 66.0005 294.35 + vertex -350.453 63.4316 296.471 + endloop + endfacet + facet normal 0.21758 -0.660523 -0.718588 + outer loop + vertex -350.453 63.4316 296.471 + vertex -349.661 66.0005 294.35 + vertex -347.656 65.4036 295.506 + endloop + endfacet + facet normal 0.255012 -0.604571 -0.754627 + outer loop + vertex -349.661 66.0005 294.35 + vertex -346.941 68.2504 293.467 + vertex -347.656 65.4036 295.506 + endloop + endfacet + facet normal 0.273936 -0.604561 -0.747974 + outer loop + vertex -347.656 65.4036 295.506 + vertex -346.941 68.2504 293.467 + vertex -345.059 67.6718 294.624 + endloop + endfacet + facet normal 0.288676 -0.676223 -0.677782 + outer loop + vertex -355.585 67.6819 290.41 + vertex -352.548 69.866 289.525 + vertex -353.579 67.1175 291.828 + endloop + endfacet + facet normal 0.306309 -0.676273 -0.669947 + outer loop + vertex -353.579 67.1175 291.828 + vertex -352.548 69.866 289.525 + vertex -350.635 69.3298 290.941 + endloop + endfacet + facet normal 0.228677 -0.731887 -0.64191 + outer loop + vertex -358.915 65.8144 291.353 + vertex -355.585 67.6819 290.41 + vertex -356.799 65.2227 292.782 + endloop + endfacet + facet normal 0.242929 -0.732819 -0.63558 + outer loop + vertex -356.799 65.2227 292.782 + vertex -355.585 67.6819 290.41 + vertex -353.579 67.1175 291.828 + endloop + endfacet + facet normal 0.220759 -0.711187 -0.667441 + outer loop + vertex -356.799 65.2227 292.782 + vertex -353.579 67.1175 291.828 + vertex -354.698 64.6435 294.094 + endloop + endfacet + facet normal 0.239161 -0.712439 -0.659722 + outer loop + vertex -354.698 64.6435 294.094 + vertex -353.579 67.1175 291.828 + vertex -351.611 66.5712 293.131 + endloop + endfacet + facet normal 0.281791 -0.655828 -0.700345 + outer loop + vertex -353.579 67.1175 291.828 + vertex -350.635 69.3298 290.941 + vertex -351.611 66.5712 293.131 + endloop + endfacet + facet normal 0.299999 -0.656062 -0.692519 + outer loop + vertex -351.611 66.5712 293.131 + vertex -350.635 69.3298 290.941 + vertex -348.771 68.8046 292.245 + endloop + endfacet + facet normal 0.301631 -0.711008 -0.635206 + outer loop + vertex -359.601 68.8592 287.26 + vertex -356.402 71.0037 286.378 + vertex -357.6 68.2615 288.879 + endloop + endfacet + facet normal 0.314503 -0.710959 -0.628987 + outer loop + vertex -357.6 68.2615 288.879 + vertex -356.402 71.0037 286.378 + vertex -354.482 70.4229 287.995 + endloop + endfacet + facet normal 0.238988 -0.765271 -0.5977 + outer loop + vertex -363.113 67.0375 288.188 + vertex -359.601 68.8592 287.26 + vertex -361.027 66.4203 289.812 + endloop + endfacet + facet normal 0.250304 -0.766016 -0.592088 + outer loop + vertex -361.027 66.4203 289.812 + vertex -359.601 68.8592 287.26 + vertex -357.6 68.2615 288.879 + endloop + endfacet + facet normal 0.235163 -0.750671 -0.617407 + outer loop + vertex -361.027 66.4203 289.812 + vertex -357.6 68.2615 288.879 + vertex -358.915 65.8144 291.353 + endloop + endfacet + facet normal 0.248368 -0.751492 -0.611206 + outer loop + vertex -358.915 65.8144 291.353 + vertex -357.6 68.2615 288.879 + vertex -355.585 67.6819 290.41 + endloop + endfacet + facet normal 0.296903 -0.695796 -0.654001 + outer loop + vertex -357.6 68.2615 288.879 + vertex -354.482 70.4229 287.995 + vertex -355.585 67.6819 290.41 + endloop + endfacet + facet normal 0.311618 -0.695721 -0.647199 + outer loop + vertex -355.585 67.6819 290.41 + vertex -354.482 70.4229 287.995 + vertex -352.548 69.866 289.525 + endloop + endfacet + facet normal 0.311809 -0.741154 -0.59453 + outer loop + vertex -363.398 70.0291 283.896 + vertex -360.056 72.1411 283.015 + vertex -361.54 69.4496 285.592 + endloop + endfacet + facet normal 0.323651 -0.741351 -0.587919 + outer loop + vertex -361.54 69.4496 285.592 + vertex -360.056 72.1411 283.015 + vertex -358.265 71.5773 284.712 + endloop + endfacet + facet normal 0.248103 -0.792583 -0.557007 + outer loop + vertex -367.031 68.2406 284.822 + vertex -363.398 70.0291 283.896 + vertex -365.121 67.6453 286.52 + endloop + endfacet + facet normal 0.256716 -0.793325 -0.552026 + outer loop + vertex -365.121 67.6453 286.52 + vertex -363.398 70.0291 283.896 + vertex -361.54 69.4496 285.592 + endloop + endfacet + facet normal 0.243313 -0.779601 -0.577081 + outer loop + vertex -365.121 67.6453 286.52 + vertex -361.54 69.4496 285.592 + vertex -363.113 67.0375 288.188 + endloop + endfacet + facet normal 0.253761 -0.780392 -0.571484 + outer loop + vertex -363.113 67.0375 288.188 + vertex -361.54 69.4496 285.592 + vertex -359.601 68.8592 287.26 + endloop + endfacet + facet normal 0.307037 -0.726761 -0.614449 + outer loop + vertex -361.54 69.4496 285.592 + vertex -358.265 71.5773 284.712 + vertex -359.601 68.8592 287.26 + endloop + endfacet + facet normal 0.319783 -0.726825 -0.607836 + outer loop + vertex -359.601 68.8592 287.26 + vertex -358.265 71.5773 284.712 + vertex -356.402 71.0037 286.378 + endloop + endfacet + facet normal 0.324814 -0.767375 -0.55284 + outer loop + vertex -366.919 71.1562 280.364 + vertex -363.486 73.2381 279.491 + vertex -365.184 70.5985 282.157 + endloop + endfacet + facet normal 0.333245 -0.767513 -0.547606 + outer loop + vertex -365.184 70.5985 282.157 + vertex -363.486 73.2381 279.491 + vertex -361.792 72.6987 281.278 + endloop + endfacet + facet normal 0.260901 -0.817051 -0.514159 + outer loop + vertex -370.639 69.4093 281.252 + vertex -366.919 71.1562 280.364 + vertex -368.861 68.8317 283.072 + endloop + endfacet + facet normal 0.265598 -0.81744 -0.511125 + outer loop + vertex -368.861 68.8317 283.072 + vertex -366.919 71.1562 280.364 + vertex -365.184 70.5985 282.157 + endloop + endfacet + facet normal 0.253202 -0.804885 -0.536702 + outer loop + vertex -368.861 68.8317 283.072 + vertex -365.184 70.5985 282.157 + vertex -367.031 68.2406 284.822 + endloop + endfacet + facet normal 0.260873 -0.805565 -0.531987 + outer loop + vertex -367.031 68.2406 284.822 + vertex -365.184 70.5985 282.157 + vertex -363.398 70.0291 283.896 + endloop + endfacet + facet normal 0.318226 -0.754367 -0.574163 + outer loop + vertex -365.184 70.5985 282.157 + vertex -361.792 72.6987 281.278 + vertex -363.398 70.0291 283.896 + endloop + endfacet + facet normal 0.327016 -0.754551 -0.568958 + outer loop + vertex -363.398 70.0291 283.896 + vertex -361.792 72.6987 281.278 + vertex -360.056 72.1411 283.015 + endloop + endfacet + facet normal 0.332972 -0.78662 -0.519961 + outer loop + vertex -370.12 72.1726 276.84 + vertex -366.6 74.2178 276 + vertex -368.591 71.6878 278.552 + endloop + endfacet + facet normal 0.337956 -0.786883 -0.516334 + outer loop + vertex -368.591 71.6878 278.552 + vertex -366.6 74.2178 276 + vertex -365.117 73.7451 277.691 + endloop + endfacet + facet normal 0.265762 -0.834022 -0.483506 + outer loop + vertex -373.969 70.4711 277.659 + vertex -370.12 72.1726 276.84 + vertex -372.375 69.9671 279.405 + endloop + endfacet + facet normal 0.271716 -0.834759 -0.478903 + outer loop + vertex -372.375 69.9671 279.405 + vertex -370.12 72.1726 276.84 + vertex -368.591 71.6878 278.552 + endloop + endfacet + facet normal 0.263785 -0.826465 -0.497366 + outer loop + vertex -372.375 69.9671 279.405 + vertex -368.591 71.6878 278.552 + vertex -370.639 69.4093 281.252 + endloop + endfacet + facet normal 0.270761 -0.827071 -0.492587 + outer loop + vertex -370.639 69.4093 281.252 + vertex -368.591 71.6878 278.552 + vertex -366.919 71.1562 280.364 + endloop + endfacet + facet normal 0.329476 -0.779463 -0.532807 + outer loop + vertex -368.591 71.6878 278.552 + vertex -365.117 73.7451 277.691 + vertex -366.919 71.1562 280.364 + endloop + endfacet + facet normal 0.338911 -0.77963 -0.526609 + outer loop + vertex -366.919 71.1562 280.364 + vertex -365.117 73.7451 277.691 + vertex -363.486 73.2381 279.491 + endloop + endfacet + facet normal 0.330811 -0.786821 -0.521034 + outer loop + vertex -372.128 72.9465 274.39 + vertex -368.547 74.9803 273.593 + vertex -371.346 72.5998 275.411 + endloop + endfacet + facet normal 0.329351 -0.786351 -0.522667 + outer loop + vertex -371.346 72.5998 275.411 + vertex -368.547 74.9803 273.593 + vertex -367.785 74.6364 274.591 + endloop + endfacet + facet normal 0.266359 -0.834614 -0.482154 + outer loop + vertex -376.007 71.2569 275.172 + vertex -372.128 72.9465 274.39 + vertex -375.228 70.9087 276.205 + endloop + endfacet + facet normal 0.263724 -0.83354 -0.485449 + outer loop + vertex -375.228 70.9087 276.205 + vertex -372.128 72.9465 274.39 + vertex -371.346 72.5998 275.411 + endloop + endfacet + facet normal 0.265391 -0.835416 -0.481298 + outer loop + vertex -375.228 70.9087 276.205 + vertex -371.346 72.5998 275.411 + vertex -373.969 70.4711 277.659 + endloop + endfacet + facet normal 0.267481 -0.835892 -0.47931 + outer loop + vertex -373.969 70.4711 277.659 + vertex -371.346 72.5998 275.411 + vertex -370.12 72.1726 276.84 + endloop + endfacet + facet normal 0.330957 -0.787842 -0.519396 + outer loop + vertex -371.346 72.5998 275.411 + vertex -367.785 74.6364 274.591 + vertex -370.12 72.1726 276.84 + endloop + endfacet + facet normal 0.335021 -0.788455 -0.515849 + outer loop + vertex -370.12 72.1726 276.84 + vertex -367.785 74.6364 274.591 + vertex -366.6 74.2178 276 + endloop + endfacet + facet normal 0.339037 -0.798501 -0.497444 + outer loop + vertex -372.738 73.2269 273.552 + vertex -369.112 75.2444 272.785 + vertex -372.498 73.1793 273.792 + endloop + endfacet + facet normal 0.366086 -0.817283 -0.445005 + outer loop + vertex -372.498 73.1793 273.792 + vertex -369.112 75.2444 272.785 + vertex -368.906 75.2095 273.018 + endloop + endfacet + facet normal 0.247742 -0.820744 -0.514785 + outer loop + vertex -376.701 71.5182 274.369 + vertex -372.738 73.2269 273.552 + vertex -376.388 71.4814 274.578 + endloop + endfacet + facet normal 0.279939 -0.848934 -0.448269 + outer loop + vertex -376.388 71.4814 274.578 + vertex -372.738 73.2269 273.552 + vertex -372.498 73.1793 273.792 + endloop + endfacet + facet normal 0.265591 -0.833132 -0.485131 + outer loop + vertex -376.388 71.4814 274.578 + vertex -372.498 73.1793 273.792 + vertex -376.007 71.2569 275.172 + endloop + endfacet + facet normal 0.26436 -0.832341 -0.487158 + outer loop + vertex -376.007 71.2569 275.172 + vertex -372.498 73.1793 273.792 + vertex -372.128 72.9465 274.39 + endloop + endfacet + facet normal 0.335365 -0.789338 -0.514273 + outer loop + vertex -372.498 73.1793 273.792 + vertex -368.906 75.2095 273.018 + vertex -372.128 72.9465 274.39 + endloop + endfacet + facet normal 0.330982 -0.786983 -0.520681 + outer loop + vertex -372.128 72.9465 274.39 + vertex -368.906 75.2095 273.018 + vertex -368.547 74.9803 273.593 + endloop + endfacet + facet normal 0.241202 -0.829641 -0.503505 + outer loop + vertex -377.345 71.2844 274.445 + vertex -373.341 72.9649 273.595 + vertex -376.701 71.5182 274.369 + endloop + endfacet + facet normal 0.400224 -0.916073 0.0251319 + outer loop + vertex -376.701 71.5182 274.369 + vertex -373.341 72.9649 273.595 + vertex -372.738 73.2269 273.552 + endloop + endfacet + facet normal 0.303091 -0.7857 -0.539269 + outer loop + vertex -373.341 72.9649 273.595 + vertex -369.588 74.9572 272.801 + vertex -372.738 73.2269 273.552 + endloop + endfacet + facet normal 0.509171 -0.832858 0.217008 + outer loop + vertex -372.738 73.2269 273.552 + vertex -369.588 74.9572 272.801 + vertex -369.112 75.2444 272.785 + endloop + endfacet + facet normal 0.286737 -0.416259 -0.86285 + outer loop + vertex -338.461 69.52 295.8 + vertex -336.398 72.3917 295.1 + vertex -336.275 69.713 296.433 + endloop + endfacet + facet normal 0.325389 -0.40929 -0.852411 + outer loop + vertex -336.275 69.713 296.433 + vertex -336.398 72.3917 295.1 + vertex -334.408 72.6031 295.758 + endloop + endfacet + facet normal 0.254356 -0.468256 -0.846191 + outer loop + vertex -340.71 66.8847 296.582 + vertex -338.461 69.52 295.8 + vertex -338.379 67.037 297.199 + endloop + endfacet + facet normal 0.284096 -0.46342 -0.839364 + outer loop + vertex -338.379 67.037 297.199 + vertex -338.461 69.52 295.8 + vertex -336.275 69.713 296.433 + endloop + endfacet + facet normal 0.329898 -0.466344 -0.820787 + outer loop + vertex -342.59 70.2623 293.826 + vertex -340.273 73.1721 293.104 + vertex -340.634 69.7631 294.895 + endloop + endfacet + facet normal 0.344901 -0.465064 -0.815327 + outer loop + vertex -340.634 69.7631 294.895 + vertex -340.273 73.1721 293.104 + vertex -338.429 72.6533 294.18 + endloop + endfacet + facet normal 0.285624 -0.520124 -0.804916 + outer loop + vertex -345.059 67.6718 294.624 + vertex -342.59 70.2623 293.826 + vertex -342.997 67.1554 295.689 + endloop + endfacet + facet normal 0.304446 -0.518909 -0.798777 + outer loop + vertex -342.997 67.1554 295.689 + vertex -342.59 70.2623 293.826 + vertex -340.634 69.7631 294.895 + endloop + endfacet + facet normal 0.265346 -0.492616 -0.828807 + outer loop + vertex -342.997 67.1554 295.689 + vertex -340.634 69.7631 294.895 + vertex -340.71 66.8847 296.582 + endloop + endfacet + facet normal 0.287671 -0.489806 -0.823004 + outer loop + vertex -340.71 66.8847 296.582 + vertex -340.634 69.7631 294.895 + vertex -338.461 69.52 295.8 + endloop + endfacet + facet normal 0.302543 -0.440186 -0.845402 + outer loop + vertex -340.634 69.7631 294.895 + vertex -338.429 72.6533 294.18 + vertex -338.461 69.52 295.8 + endloop + endfacet + facet normal 0.323851 -0.437133 -0.839068 + outer loop + vertex -338.461 69.52 295.8 + vertex -338.429 72.6533 294.18 + vertex -336.398 72.3917 295.1 + endloop + endfacet + facet normal 0.382248 -0.516794 -0.766035 + outer loop + vertex -346.089 71.3729 291.444 + vertex -343.581 74.2929 290.726 + vertex -344.362 70.8367 292.668 + endloop + endfacet + facet normal 0.397418 -0.516122 -0.758734 + outer loop + vertex -344.362 70.8367 292.668 + vertex -343.581 74.2929 290.726 + vertex -341.948 73.7562 291.946 + endloop + endfacet + facet normal 0.32646 -0.574989 -0.750208 + outer loop + vertex -348.771 68.8046 292.245 + vertex -346.089 71.3729 291.444 + vertex -346.941 68.2504 293.467 + endloop + endfacet + facet normal 0.34671 -0.574727 -0.74127 + outer loop + vertex -346.941 68.2504 293.467 + vertex -346.089 71.3729 291.444 + vertex -344.362 70.8367 292.668 + endloop + endfacet + facet normal 0.309112 -0.5483 -0.777057 + outer loop + vertex -346.941 68.2504 293.467 + vertex -344.362 70.8367 292.668 + vertex -345.059 67.6718 294.624 + endloop + endfacet + facet normal 0.325917 -0.547909 -0.770437 + outer loop + vertex -345.059 67.6718 294.624 + vertex -344.362 70.8367 292.668 + vertex -342.59 70.2623 293.826 + endloop + endfacet + facet normal 0.358619 -0.492499 -0.792992 + outer loop + vertex -344.362 70.8367 292.668 + vertex -341.948 73.7562 291.946 + vertex -342.59 70.2623 293.826 + endloop + endfacet + facet normal 0.372417 -0.491826 -0.787028 + outer loop + vertex -342.59 70.2623 293.826 + vertex -341.948 73.7562 291.946 + vertex -340.273 73.1721 293.104 + endloop + endfacet + facet normal 0.406377 -0.556028 -0.725045 + outer loop + vertex -349.696 72.3966 288.718 + vertex -347.026 75.2832 288.001 + vertex -347.863 71.8862 290.137 + endloop + endfacet + facet normal 0.422649 -0.554768 -0.716659 + outer loop + vertex -347.863 71.8862 290.137 + vertex -347.026 75.2832 288.001 + vertex -345.269 74.7895 289.419 + endloop + endfacet + facet normal 0.348658 -0.617631 -0.70496 + outer loop + vertex -352.548 69.866 289.525 + vertex -349.696 72.3966 288.718 + vertex -350.635 69.3298 290.941 + endloop + endfacet + facet normal 0.367079 -0.616911 -0.696185 + outer loop + vertex -350.635 69.3298 290.941 + vertex -349.696 72.3966 288.718 + vertex -347.863 71.8862 290.137 + endloop + endfacet + facet normal 0.340225 -0.597273 -0.7263 + outer loop + vertex -350.635 69.3298 290.941 + vertex -347.863 71.8862 290.137 + vertex -348.771 68.8046 292.245 + endloop + endfacet + facet normal 0.356876 -0.596896 -0.718578 + outer loop + vertex -348.771 68.8046 292.245 + vertex -347.863 71.8862 290.137 + vertex -346.089 71.3729 291.444 + endloop + endfacet + facet normal 0.394402 -0.536746 -0.745889 + outer loop + vertex -347.863 71.8862 290.137 + vertex -345.269 74.7895 289.419 + vertex -346.089 71.3729 291.444 + endloop + endfacet + facet normal 0.412653 -0.535691 -0.736718 + outer loop + vertex -346.089 71.3729 291.444 + vertex -345.269 74.7895 289.419 + vertex -343.581 74.2929 290.726 + endloop + endfacet + facet normal 0.422789 -0.589889 -0.687954 + outer loop + vertex -353.406 73.5017 285.571 + vertex -350.597 76.3467 284.858 + vertex -351.56 72.9412 287.186 + endloop + endfacet + facet normal 0.43752 -0.588523 -0.679866 + outer loop + vertex -351.56 72.9412 287.186 + vertex -350.597 76.3467 284.858 + vertex -348.819 75.8058 286.47 + endloop + endfacet + facet normal 0.363663 -0.65134 -0.665962 + outer loop + vertex -356.402 71.0037 286.378 + vertex -353.406 73.5017 285.571 + vertex -354.482 70.4229 287.995 + endloop + endfacet + facet normal 0.378503 -0.650575 -0.658398 + outer loop + vertex -354.482 70.4229 287.995 + vertex -353.406 73.5017 285.571 + vertex -351.56 72.9412 287.186 + endloop + endfacet + facet normal 0.35823 -0.635314 -0.68414 + outer loop + vertex -354.482 70.4229 287.995 + vertex -351.56 72.9412 287.186 + vertex -352.548 69.866 289.525 + endloop + endfacet + facet normal 0.371472 -0.634646 -0.677667 + outer loop + vertex -352.548 69.866 289.525 + vertex -351.56 72.9412 287.186 + vertex -349.696 72.3966 288.718 + endloop + endfacet + facet normal 0.413967 -0.572879 -0.707418 + outer loop + vertex -351.56 72.9412 287.186 + vertex -348.819 75.8058 286.47 + vertex -349.696 72.3966 288.718 + endloop + endfacet + facet normal 0.430035 -0.571429 -0.698955 + outer loop + vertex -349.696 72.3966 288.718 + vertex -348.819 75.8058 286.47 + vertex -347.026 75.2832 288.001 + endloop + endfacet + facet normal 0.439091 -0.619939 -0.650289 + outer loop + vertex -356.921 74.6124 282.217 + vertex -353.986 77.426 281.517 + vertex -355.197 74.0595 283.909 + endloop + endfacet + facet normal 0.452749 -0.618878 -0.641879 + outer loop + vertex -355.197 74.0595 283.909 + vertex -353.986 77.426 281.517 + vertex -352.325 76.8931 283.202 + endloop + endfacet + facet normal 0.378309 -0.682007 -0.625898 + outer loop + vertex -360.056 72.1411 283.015 + vertex -356.921 74.6124 282.217 + vertex -358.265 71.5773 284.712 + endloop + endfacet + facet normal 0.389197 -0.681642 -0.619588 + outer loop + vertex -358.265 71.5773 284.712 + vertex -356.921 74.6124 282.217 + vertex -355.197 74.0595 283.909 + endloop + endfacet + facet normal 0.371307 -0.66779 -0.645126 + outer loop + vertex -358.265 71.5773 284.712 + vertex -355.197 74.0595 283.909 + vertex -356.402 71.0037 286.378 + endloop + endfacet + facet normal 0.384414 -0.667211 -0.638009 + outer loop + vertex -356.402 71.0037 286.378 + vertex -355.197 74.0595 283.909 + vertex -353.406 73.5017 285.571 + endloop + endfacet + facet normal 0.432339 -0.604887 -0.668727 + outer loop + vertex -355.197 74.0595 283.909 + vertex -352.325 76.8931 283.202 + vertex -353.406 73.5017 285.571 + endloop + endfacet + facet normal 0.443535 -0.60392 -0.662236 + outer loop + vertex -353.406 73.5017 285.571 + vertex -352.325 76.8931 283.202 + vertex -350.597 76.3467 284.858 + endloop + endfacet + facet normal 0.457318 -0.647849 -0.609223 + outer loop + vertex -360.242 75.6662 278.699 + vertex -357.204 78.4515 278.017 + vertex -358.595 75.1494 280.484 + endloop + endfacet + facet normal 0.467284 -0.647026 -0.602497 + outer loop + vertex -358.595 75.1494 280.484 + vertex -357.204 78.4515 278.017 + vertex -355.606 77.951 279.794 + endloop + endfacet + facet normal 0.389853 -0.711668 -0.584417 + outer loop + vertex -363.486 73.2381 279.491 + vertex -360.242 75.6662 278.699 + vertex -361.792 72.6987 281.278 + endloop + endfacet + facet normal 0.402046 -0.711251 -0.576612 + outer loop + vertex -361.792 72.6987 281.278 + vertex -360.242 75.6662 278.699 + vertex -358.595 75.1494 280.484 + endloop + endfacet + facet normal 0.383309 -0.696526 -0.606568 + outer loop + vertex -361.792 72.6987 281.278 + vertex -358.595 75.1494 280.484 + vertex -360.056 72.1411 283.015 + endloop + endfacet + facet normal 0.396409 -0.696136 -0.598544 + outer loop + vertex -360.056 72.1411 283.015 + vertex -358.595 75.1494 280.484 + vertex -356.921 74.6124 282.217 + endloop + endfacet + facet normal 0.448745 -0.633979 -0.62984 + outer loop + vertex -358.595 75.1494 280.484 + vertex -355.606 77.951 279.794 + vertex -356.921 74.6124 282.217 + endloop + endfacet + facet normal 0.458194 -0.633264 -0.623726 + outer loop + vertex -356.921 74.6124 282.217 + vertex -355.606 77.951 279.794 + vertex -353.986 77.426 281.517 + endloop + endfacet + facet normal 0.463846 -0.667209 -0.58282 + outer loop + vertex -363.288 76.6214 275.225 + vertex -360.183 79.366 274.555 + vertex -361.84 76.1615 276.904 + endloop + endfacet + facet normal 0.473546 -0.666808 -0.575431 + outer loop + vertex -361.84 76.1615 276.904 + vertex -360.183 79.366 274.555 + vertex -358.763 78.9269 276.232 + endloop + endfacet + facet normal 0.399833 -0.729738 -0.554631 + outer loop + vertex -366.6 74.2178 276 + vertex -363.288 76.6214 275.225 + vertex -365.117 73.7451 277.691 + endloop + endfacet + facet normal 0.406018 -0.729769 -0.550079 + outer loop + vertex -365.117 73.7451 277.691 + vertex -363.288 76.6214 275.225 + vertex -361.84 76.1615 276.904 + endloop + endfacet + facet normal 0.397918 -0.723392 -0.564238 + outer loop + vertex -365.117 73.7451 277.691 + vertex -361.84 76.1615 276.904 + vertex -363.486 73.2381 279.491 + endloop + endfacet + facet normal 0.404478 -0.723182 -0.559826 + outer loop + vertex -363.486 73.2381 279.491 + vertex -361.84 76.1615 276.904 + vertex -360.242 75.6662 278.699 + endloop + endfacet + facet normal 0.462329 -0.658737 -0.593563 + outer loop + vertex -361.84 76.1615 276.904 + vertex -358.763 78.9269 276.232 + vertex -360.242 75.6662 278.699 + endloop + endfacet + facet normal 0.471606 -0.658007 -0.587038 + outer loop + vertex -360.242 75.6662 278.699 + vertex -358.763 78.9269 276.232 + vertex -357.204 78.4515 278.017 + endloop + endfacet + facet normal 0.462299 -0.668999 -0.581997 + outer loop + vertex -365.192 77.37 272.837 + vertex -362.06 80.1076 272.178 + vertex -364.443 77.0302 273.822 + endloop + endfacet + facet normal 0.459967 -0.66849 -0.584424 + outer loop + vertex -364.443 77.0302 273.822 + vertex -362.06 80.1076 272.178 + vertex -361.318 79.7657 273.153 + endloop + endfacet + facet normal 0.396138 -0.731621 -0.554803 + outer loop + vertex -368.547 74.9803 273.593 + vertex -365.192 77.37 272.837 + vertex -367.785 74.6364 274.591 + endloop + endfacet + facet normal 0.396922 -0.731829 -0.553967 + outer loop + vertex -367.785 74.6364 274.591 + vertex -365.192 77.37 272.837 + vertex -364.443 77.0302 273.822 + endloop + endfacet + facet normal 0.397931 -0.732654 -0.55215 + outer loop + vertex -367.785 74.6364 274.591 + vertex -364.443 77.0302 273.822 + vertex -366.6 74.2178 276 + endloop + endfacet + facet normal 0.404262 -0.733283 -0.546689 + outer loop + vertex -366.6 74.2178 276 + vertex -364.443 77.0302 273.822 + vertex -363.288 76.6214 275.225 + endloop + endfacet + facet normal 0.463968 -0.671448 -0.577833 + outer loop + vertex -364.443 77.0302 273.822 + vertex -361.318 79.7657 273.153 + vertex -363.288 76.6214 275.225 + endloop + endfacet + facet normal 0.470107 -0.671766 -0.572477 + outer loop + vertex -363.288 76.6214 275.225 + vertex -361.318 79.7657 273.153 + vertex -360.183 79.366 274.555 + endloop + endfacet + facet normal 0.509523 -0.71088 -0.484805 + outer loop + vertex -365.772 77.5795 272.068 + vertex -362.705 80.2163 271.426 + vertex -365.565 77.5819 272.282 + endloop + endfacet + facet normal 0.556552 -0.732049 -0.392879 + outer loop + vertex -365.565 77.5819 272.282 + vertex -362.705 80.2163 271.426 + vertex -362.454 80.2976 271.629 + endloop + endfacet + facet normal 0.426561 -0.760404 -0.489727 + outer loop + vertex -369.112 75.2444 272.785 + vertex -365.772 77.5795 272.068 + vertex -368.906 75.2095 273.018 + endloop + endfacet + facet normal 0.456578 -0.777298 -0.432833 + outer loop + vertex -368.906 75.2095 273.018 + vertex -365.772 77.5795 272.068 + vertex -365.565 77.5819 272.282 + endloop + endfacet + facet normal 0.402353 -0.735679 -0.544875 + outer loop + vertex -368.906 75.2095 273.018 + vertex -365.565 77.5819 272.282 + vertex -368.547 74.9803 273.593 + endloop + endfacet + facet normal 0.399375 -0.7343 -0.548911 + outer loop + vertex -368.547 74.9803 273.593 + vertex -365.565 77.5819 272.282 + vertex -365.192 77.37 272.837 + endloop + endfacet + facet normal 0.468027 -0.673726 -0.571878 + outer loop + vertex -365.565 77.5819 272.282 + vertex -362.454 80.2976 271.629 + vertex -365.192 77.37 272.837 + endloop + endfacet + facet normal 0.469433 -0.674289 -0.570059 + outer loop + vertex -365.192 77.37 272.837 + vertex -362.454 80.2976 271.629 + vertex -362.06 80.1076 272.178 + endloop + endfacet + facet normal 0.479925 -0.814799 -0.32523 + outer loop + vertex -369.588 74.9572 272.801 + vertex -366.164 77.2613 272.082 + vertex -369.112 75.2444 272.785 + endloop + endfacet + facet normal 0.576805 -0.69144 0.434978 + outer loop + vertex -369.112 75.2444 272.785 + vertex -366.164 77.2613 272.082 + vertex -365.772 77.5795 272.068 + endloop + endfacet + facet normal 0.626913 -0.775357 -0.0761735 + outer loop + vertex -366.164 77.2613 272.082 + vertex -363.13 79.7749 271.461 + vertex -365.772 77.5795 272.068 + endloop + endfacet + facet normal 0.556515 -0.482554 0.676338 + outer loop + vertex -365.772 77.5795 272.068 + vertex -363.13 79.7749 271.461 + vertex -362.705 80.2163 271.426 + endloop + endfacet + facet normal 0.380779 -0.298673 -0.875101 + outer loop + vertex -334.533 75.5895 294.488 + vertex -332.796 79.2401 293.998 + vertex -332.699 75.958 295.16 + endloop + endfacet + facet normal 0.446559 -0.286946 -0.847494 + outer loop + vertex -332.699 75.958 295.16 + vertex -332.796 79.2401 293.998 + vertex -331.063 80.0515 294.636 + endloop + endfacet + facet normal 0.327242 -0.35816 -0.874434 + outer loop + vertex -336.398 72.3917 295.1 + vertex -334.533 75.5895 294.488 + vertex -334.408 72.6031 295.758 + endloop + endfacet + facet normal 0.383485 -0.347785 -0.855561 + outer loop + vertex -334.408 72.6031 295.758 + vertex -334.533 75.5895 294.488 + vertex -332.699 75.958 295.16 + endloop + endfacet + facet normal 0.414831 -0.348798 -0.84039 + outer loop + vertex -338.182 76.3533 292.467 + vertex -336.308 79.8089 291.958 + vertex -336.431 75.8111 293.556 + endloop + endfacet + facet normal 0.437888 -0.34537 -0.830044 + outer loop + vertex -336.431 75.8111 293.556 + vertex -336.308 79.8089 291.958 + vertex -334.606 79.3045 293.065 + endloop + endfacet + facet normal 0.370676 -0.410423 -0.833158 + outer loop + vertex -340.273 73.1721 293.104 + vertex -338.182 76.3533 292.467 + vertex -338.429 72.6533 294.18 + endloop + endfacet + facet normal 0.387648 -0.408423 -0.826389 + outer loop + vertex -338.429 72.6533 294.18 + vertex -338.182 76.3533 292.467 + vertex -336.431 75.8111 293.556 + endloop + endfacet + facet normal 0.339472 -0.384302 -0.858528 + outer loop + vertex -338.429 72.6533 294.18 + vertex -336.431 75.8111 293.556 + vertex -336.398 72.3917 295.1 + endloop + endfacet + facet normal 0.371789 -0.378976 -0.847437 + outer loop + vertex -336.398 72.3917 295.1 + vertex -336.431 75.8111 293.556 + vertex -334.533 75.5895 294.488 + endloop + endfacet + facet normal 0.386363 -0.323201 -0.863866 + outer loop + vertex -336.431 75.8111 293.556 + vertex -334.606 79.3045 293.065 + vertex -334.533 75.5895 294.488 + endloop + endfacet + facet normal 0.425517 -0.316301 -0.847873 + outer loop + vertex -334.533 75.5895 294.488 + vertex -334.606 79.3045 293.065 + vertex -332.796 79.2401 293.998 + endloop + endfacet + facet normal 0.477814 -0.394098 -0.785099 + outer loop + vertex -341.33 77.5024 290.088 + vertex -339.378 80.9515 289.544 + vertex -339.776 76.9609 291.305 + endloop + endfacet + facet normal 0.494729 -0.391676 -0.775779 + outer loop + vertex -339.776 76.9609 291.305 + vertex -339.378 80.9515 289.544 + vertex -337.869 80.4237 290.773 + endloop + endfacet + facet normal 0.431172 -0.457071 -0.777931 + outer loop + vertex -343.581 74.2929 290.726 + vertex -341.33 77.5024 290.088 + vertex -341.948 73.7562 291.946 + endloop + endfacet + facet normal 0.445091 -0.455824 -0.770791 + outer loop + vertex -341.948 73.7562 291.946 + vertex -341.33 77.5024 290.088 + vertex -339.776 76.9609 291.305 + endloop + endfacet + facet normal 0.404353 -0.434974 -0.804547 + outer loop + vertex -341.948 73.7562 291.946 + vertex -339.776 76.9609 291.305 + vertex -340.273 73.1721 293.104 + endloop + endfacet + facet normal 0.416798 -0.433865 -0.798775 + outer loop + vertex -340.273 73.1721 293.104 + vertex -339.776 76.9609 291.305 + vertex -338.182 76.3533 292.467 + endloop + endfacet + facet normal 0.449715 -0.372427 -0.811822 + outer loop + vertex -339.776 76.9609 291.305 + vertex -337.869 80.4237 290.773 + vertex -338.182 76.3533 292.467 + endloop + endfacet + facet normal 0.46458 -0.370446 -0.804323 + outer loop + vertex -338.182 76.3533 292.467 + vertex -337.869 80.4237 290.773 + vertex -336.308 79.8089 291.958 + endloop + endfacet + facet normal 0.507252 -0.423863 -0.750357 + outer loop + vertex -344.617 78.4768 287.375 + vertex -342.535 81.907 286.845 + vertex -342.934 77.9909 288.788 + endloop + endfacet + facet normal 0.521428 -0.421206 -0.74209 + outer loop + vertex -342.934 77.9909 288.788 + vertex -342.535 81.907 286.845 + vertex -340.924 81.429 288.248 + endloop + endfacet + facet normal 0.459292 -0.491396 -0.739987 + outer loop + vertex -347.026 75.2832 288.001 + vertex -344.617 78.4768 287.375 + vertex -345.269 74.7895 289.419 + endloop + endfacet + facet normal 0.473174 -0.489628 -0.732373 + outer loop + vertex -345.269 74.7895 289.419 + vertex -344.617 78.4768 287.375 + vertex -342.934 77.9909 288.788 + endloop + endfacet + facet normal 0.446772 -0.475405 -0.757882 + outer loop + vertex -345.269 74.7895 289.419 + vertex -342.934 77.9909 288.788 + vertex -343.581 74.2929 290.726 + endloop + endfacet + facet normal 0.463006 -0.47368 -0.749168 + outer loop + vertex -343.581 74.2929 290.726 + vertex -342.934 77.9909 288.788 + vertex -341.33 77.5024 290.088 + endloop + endfacet + facet normal 0.495774 -0.409905 -0.765628 + outer loop + vertex -342.934 77.9909 288.788 + vertex -340.924 81.429 288.248 + vertex -341.33 77.5024 290.088 + endloop + endfacet + facet normal 0.509369 -0.40767 -0.757858 + outer loop + vertex -341.33 77.5024 290.088 + vertex -340.924 81.429 288.248 + vertex -339.378 80.9515 289.544 + endloop + endfacet + facet normal 0.531125 -0.453501 -0.715712 + outer loop + vertex -348.055 79.5031 284.245 + vertex -345.839 82.9086 283.731 + vertex -346.338 78.9793 285.85 + endloop + endfacet + facet normal 0.545877 -0.45041 -0.706505 + outer loop + vertex -346.338 78.9793 285.85 + vertex -345.839 82.9086 283.731 + vertex -344.187 82.4027 285.33 + endloop + endfacet + facet normal 0.479659 -0.523194 -0.704411 + outer loop + vertex -350.597 76.3467 284.858 + vertex -348.055 79.5031 284.245 + vertex -348.819 75.8058 286.47 + endloop + endfacet + facet normal 0.492716 -0.521293 -0.696767 + outer loop + vertex -348.819 75.8058 286.47 + vertex -348.055 79.5031 284.245 + vertex -346.338 78.9793 285.85 + endloop + endfacet + facet normal 0.468886 -0.507735 -0.722739 + outer loop + vertex -348.819 75.8058 286.47 + vertex -346.338 78.9793 285.85 + vertex -347.026 75.2832 288.001 + endloop + endfacet + facet normal 0.484773 -0.505479 -0.713783 + outer loop + vertex -347.026 75.2832 288.001 + vertex -346.338 78.9793 285.85 + vertex -344.617 78.4768 287.375 + endloop + endfacet + facet normal 0.520796 -0.438589 -0.732401 + outer loop + vertex -346.338 78.9793 285.85 + vertex -344.187 82.4027 285.33 + vertex -344.617 78.4768 287.375 + endloop + endfacet + facet normal 0.53372 -0.435955 -0.724629 + outer loop + vertex -344.617 78.4768 287.375 + vertex -344.187 82.4027 285.33 + vertex -342.535 81.907 286.845 + endloop + endfacet + facet normal 0.554138 -0.477359 -0.681952 + outer loop + vertex -351.329 80.5491 280.92 + vertex -349.028 83.9314 280.422 + vertex -349.718 80.0265 282.594 + endloop + endfacet + facet normal 0.563054 -0.475559 -0.67588 + outer loop + vertex -349.718 80.0265 282.594 + vertex -349.028 83.9314 280.422 + vertex -347.458 83.4209 282.09 + endloop + endfacet + facet normal 0.499628 -0.552577 -0.667107 + outer loop + vertex -353.986 77.426 281.517 + vertex -351.329 80.5491 280.92 + vertex -352.325 76.8931 283.202 + endloop + endfacet + facet normal 0.508622 -0.551383 -0.661272 + outer loop + vertex -352.325 76.8931 283.202 + vertex -351.329 80.5491 280.92 + vertex -349.718 80.0265 282.594 + endloop + endfacet + facet normal 0.487667 -0.538912 -0.686844 + outer loop + vertex -352.325 76.8931 283.202 + vertex -349.718 80.0265 282.594 + vertex -350.597 76.3467 284.858 + endloop + endfacet + facet normal 0.503024 -0.536762 -0.677388 + outer loop + vertex -350.597 76.3467 284.858 + vertex -349.718 80.0265 282.594 + vertex -348.055 79.5031 284.245 + endloop + endfacet + facet normal 0.54462 -0.466426 -0.697019 + outer loop + vertex -349.718 80.0265 282.594 + vertex -347.458 83.4209 282.09 + vertex -348.055 79.5031 284.245 + endloop + endfacet + facet normal 0.553794 -0.46453 -0.691031 + outer loop + vertex -348.055 79.5031 284.245 + vertex -347.458 83.4209 282.09 + vertex -345.839 82.9086 283.731 + endloop + endfacet + facet normal 0.574641 -0.501993 -0.646367 + outer loop + vertex -354.46 81.5485 277.443 + vertex -352.075 84.9005 276.959 + vertex -352.902 81.06 279.207 + endloop + endfacet + facet normal 0.583908 -0.500008 -0.639565 + outer loop + vertex -352.902 81.06 279.207 + vertex -352.075 84.9005 276.959 + vertex -350.558 84.4263 278.715 + endloop + endfacet + facet normal 0.519613 -0.577262 -0.629897 + outer loop + vertex -357.204 78.4515 278.017 + vertex -354.46 81.5485 277.443 + vertex -355.606 77.951 279.794 + endloop + endfacet + facet normal 0.526891 -0.576233 -0.624773 + outer loop + vertex -355.606 77.951 279.794 + vertex -354.46 81.5485 277.443 + vertex -352.902 81.06 279.207 + endloop + endfacet + facet normal 0.508328 -0.56486 -0.650028 + outer loop + vertex -355.606 77.951 279.794 + vertex -352.902 81.06 279.207 + vertex -353.986 77.426 281.517 + endloop + endfacet + facet normal 0.517876 -0.563593 -0.643558 + outer loop + vertex -353.986 77.426 281.517 + vertex -352.902 81.06 279.207 + vertex -351.329 80.5491 280.92 + endloop + endfacet + facet normal 0.564392 -0.490028 -0.66433 + outer loop + vertex -352.902 81.06 279.207 + vertex -350.558 84.4263 278.715 + vertex -351.329 80.5491 280.92 + endloop + endfacet + facet normal 0.574995 -0.487854 -0.656795 + outer loop + vertex -351.329 80.5491 280.92 + vertex -350.558 84.4263 278.715 + vertex -349.028 83.9314 280.422 + endloop + endfacet + facet normal 0.587041 -0.515875 -0.623903 + outer loop + vertex -357.37 82.4298 274.004 + vertex -354.931 85.7643 273.541 + vertex -355.978 82.0031 275.666 + endloop + endfacet + facet normal 0.59485 -0.514496 -0.617614 + outer loop + vertex -355.978 82.0031 275.666 + vertex -354.931 85.7643 273.541 + vertex -353.57 85.3504 275.197 + endloop + endfacet + facet normal 0.529829 -0.59508 -0.604285 + outer loop + vertex -360.183 79.366 274.555 + vertex -357.37 82.4298 274.004 + vertex -358.763 78.9269 276.232 + endloop + endfacet + facet normal 0.534806 -0.594578 -0.600382 + outer loop + vertex -358.763 78.9269 276.232 + vertex -357.37 82.4298 274.004 + vertex -355.978 82.0031 275.666 + endloop + endfacet + facet normal 0.524931 -0.588338 -0.615066 + outer loop + vertex -358.763 78.9269 276.232 + vertex -355.978 82.0031 275.666 + vertex -357.204 78.4515 278.017 + endloop + endfacet + facet normal 0.535172 -0.586904 -0.607564 + outer loop + vertex -357.204 78.4515 278.017 + vertex -355.978 82.0031 275.666 + vertex -354.46 81.5485 277.443 + endloop + endfacet + facet normal 0.585372 -0.509504 -0.630671 + outer loop + vertex -355.978 82.0031 275.666 + vertex -353.57 85.3504 275.197 + vertex -354.46 81.5485 277.443 + endloop + endfacet + facet normal 0.587999 -0.508942 -0.628677 + outer loop + vertex -354.46 81.5485 277.443 + vertex -353.57 85.3504 275.197 + vertex -352.075 84.9005 276.959 + endloop + endfacet + facet normal 0.589641 -0.513641 -0.623295 + outer loop + vertex -359.218 83.173 271.634 + vertex -356.747 86.5321 271.204 + vertex -358.483 82.826 272.615 + endloop + endfacet + facet normal 0.578913 -0.512705 -0.634029 + outer loop + vertex -358.483 82.826 272.615 + vertex -356.747 86.5321 271.204 + vertex -356.025 86.1612 272.163 + endloop + endfacet + facet normal 0.525317 -0.59492 -0.608368 + outer loop + vertex -362.06 80.1076 272.178 + vertex -359.218 83.173 271.634 + vertex -361.318 79.7657 273.153 + endloop + endfacet + facet normal 0.527778 -0.595313 -0.605849 + outer loop + vertex -361.318 79.7657 273.153 + vertex -359.218 83.173 271.634 + vertex -358.483 82.826 272.615 + endloop + endfacet + facet normal 0.531126 -0.597515 -0.600734 + outer loop + vertex -361.318 79.7657 273.153 + vertex -358.483 82.826 272.615 + vertex -360.183 79.366 274.555 + endloop + endfacet + facet normal 0.533592 -0.597505 -0.598554 + outer loop + vertex -360.183 79.366 274.555 + vertex -358.483 82.826 272.615 + vertex -357.37 82.4298 274.004 + endloop + endfacet + facet normal 0.588871 -0.518176 -0.620262 + outer loop + vertex -358.483 82.826 272.615 + vertex -356.025 86.1612 272.163 + vertex -357.37 82.4298 274.004 + endloop + endfacet + facet normal 0.591011 -0.51801 -0.618363 + outer loop + vertex -357.37 82.4298 274.004 + vertex -356.025 86.1612 272.163 + vertex -354.931 85.7643 273.541 + endloop + endfacet + facet normal 0.651248 -0.543586 -0.529519 + outer loop + vertex -359.924 83.2012 270.89 + vertex -357.41 86.6396 270.452 + vertex -359.621 83.3683 271.09 + endloop + endfacet + facet normal 0.649423 -0.542921 -0.532434 + outer loop + vertex -359.621 83.3683 271.09 + vertex -357.41 86.6396 270.452 + vertex -357.132 86.7709 270.657 + endloop + endfacet + facet normal 0.597658 -0.64275 -0.479247 + outer loop + vertex -362.705 80.2163 271.426 + vertex -359.924 83.2012 270.89 + vertex -362.454 80.2976 271.629 + endloop + endfacet + facet normal 0.633868 -0.656448 -0.409007 + outer loop + vertex -362.454 80.2976 271.629 + vertex -359.924 83.2012 270.89 + vertex -359.621 83.3683 271.09 + endloop + endfacet + facet normal 0.537359 -0.599672 -0.592991 + outer loop + vertex -362.454 80.2976 271.629 + vertex -359.621 83.3683 271.09 + vertex -362.06 80.1076 272.178 + endloop + endfacet + facet normal 0.527427 -0.596309 -0.605175 + outer loop + vertex -362.06 80.1076 272.178 + vertex -359.621 83.3683 271.09 + vertex -359.218 83.173 271.634 + endloop + endfacet + facet normal 0.591674 -0.512147 -0.622598 + outer loop + vertex -359.621 83.3683 271.09 + vertex -357.132 86.7709 270.657 + vertex -359.218 83.173 271.634 + endloop + endfacet + facet normal 0.582638 -0.509735 -0.633011 + outer loop + vertex -359.218 83.173 271.634 + vertex -357.132 86.7709 270.657 + vertex -356.747 86.5321 271.204 + endloop + endfacet + facet normal 0.720137 -0.687098 0.0964319 + outer loop + vertex -363.13 79.7749 271.461 + vertex -360.459 82.5015 270.937 + vertex -362.705 80.2163 271.426 + endloop + endfacet + facet normal 0.524743 -0.349738 0.776098 + outer loop + vertex -362.705 80.2163 271.426 + vertex -360.459 82.5015 270.937 + vertex -359.924 83.2012 270.89 + endloop + endfacet + facet normal 0.794731 -0.606723 0.01704 + outer loop + vertex -360.459 82.5015 270.937 + vertex -358.01 85.6966 270.492 + vertex -359.924 83.2012 270.89 + endloop + endfacet + facet normal 0.622815 -0.36723 0.690828 + outer loop + vertex -359.924 83.2012 270.89 + vertex -358.01 85.6966 270.492 + vertex -357.41 86.6396 270.452 + endloop + endfacet + facet normal 0.456058 -0.189233 -0.869599 + outer loop + vertex -331.168 83.33 293.664 + vertex -329.707 87.2558 293.577 + vertex -329.825 83.9394 294.236 + endloop + endfacet + facet normal 0.483619 -0.18731 -0.855001 + outer loop + vertex -329.825 83.9394 294.236 + vertex -329.707 87.2558 293.577 + vertex -328.536 87.6327 294.156 + endloop + endfacet + facet normal 0.433554 -0.243308 -0.867659 + outer loop + vertex -332.796 79.2401 293.998 + vertex -331.168 83.33 293.664 + vertex -331.063 80.0515 294.636 + endloop + endfacet + facet normal 0.469598 -0.237051 -0.850462 + outer loop + vertex -331.063 80.0515 294.636 + vertex -331.168 83.33 293.664 + vertex -329.825 83.9394 294.236 + endloop + endfacet + facet normal 0.462875 -0.282996 -0.840036 + outer loop + vertex -336.308 79.8089 291.958 + vertex -334.564 83.5936 291.644 + vertex -334.606 79.3045 293.065 + endloop + endfacet + facet normal 0.484617 -0.279506 -0.828868 + outer loop + vertex -334.606 79.3045 293.065 + vertex -334.564 83.5936 291.644 + vertex -332.876 83.2428 292.749 + endloop + endfacet + facet normal 0.434826 -0.260305 -0.862072 + outer loop + vertex -334.606 79.3045 293.065 + vertex -332.876 83.2428 292.749 + vertex -332.796 79.2401 293.998 + endloop + endfacet + facet normal 0.466926 -0.254884 -0.846767 + outer loop + vertex -332.796 79.2401 293.998 + vertex -332.876 83.2428 292.749 + vertex -331.168 83.33 293.664 + endloop + endfacet + facet normal 0.526487 -0.324392 -0.785864 + outer loop + vertex -339.378 80.9515 289.544 + vertex -337.674 84.6759 289.148 + vertex -337.869 80.4237 290.773 + endloop + endfacet + facet normal 0.542908 -0.321332 -0.775884 + outer loop + vertex -337.869 80.4237 290.773 + vertex -337.674 84.6759 289.148 + vertex -336.133 84.2122 290.419 + endloop + endfacet + facet normal 0.497188 -0.303813 -0.812712 + outer loop + vertex -337.869 80.4237 290.773 + vertex -336.133 84.2122 290.419 + vertex -336.308 79.8089 291.958 + endloop + endfacet + facet normal 0.509923 -0.301813 -0.805536 + outer loop + vertex -336.308 79.8089 291.958 + vertex -336.133 84.2122 290.419 + vertex -334.564 83.5936 291.644 + endloop + endfacet + facet normal 0.552528 -0.353614 -0.754764 + outer loop + vertex -342.535 81.907 286.845 + vertex -340.766 85.5477 286.434 + vertex -340.924 81.429 288.248 + endloop + endfacet + facet normal 0.568001 -0.349887 -0.744952 + outer loop + vertex -340.924 81.429 288.248 + vertex -340.766 85.5477 286.434 + vertex -339.207 85.0975 287.835 + endloop + endfacet + facet normal 0.540353 -0.339742 -0.769801 + outer loop + vertex -340.924 81.429 288.248 + vertex -339.207 85.0975 287.835 + vertex -339.378 80.9515 289.544 + endloop + endfacet + facet normal 0.558019 -0.335931 -0.758791 + outer loop + vertex -339.378 80.9515 289.544 + vertex -339.207 85.0975 287.835 + vertex -337.674 84.6759 289.148 + endloop + endfacet + facet normal 0.5814 -0.378221 -0.720363 + outer loop + vertex -345.839 82.9086 283.731 + vertex -343.96 86.5464 283.337 + vertex -344.187 82.4027 285.33 + endloop + endfacet + facet normal 0.591625 -0.375458 -0.71345 + outer loop + vertex -344.187 82.4027 285.33 + vertex -343.96 86.5464 283.337 + vertex -342.361 86.0419 284.929 + endloop + endfacet + facet normal 0.567028 -0.36582 -0.738008 + outer loop + vertex -344.187 82.4027 285.33 + vertex -342.361 86.0419 284.929 + vertex -342.535 81.907 286.845 + endloop + endfacet + facet normal 0.577526 -0.363097 -0.73118 + outer loop + vertex -342.535 81.907 286.845 + vertex -342.361 86.0419 284.929 + vertex -340.766 85.5477 286.434 + endloop + endfacet + facet normal 0.602217 -0.40143 -0.690065 + outer loop + vertex -349.028 83.9314 280.422 + vertex -347.07 87.5424 280.03 + vertex -347.458 83.4209 282.09 + endloop + endfacet + facet normal 0.613441 -0.398398 -0.681886 + outer loop + vertex -347.458 83.4209 282.09 + vertex -347.07 87.5424 280.03 + vertex -345.536 87.0486 281.698 + endloop + endfacet + facet normal 0.592093 -0.389629 -0.705418 + outer loop + vertex -347.458 83.4209 282.09 + vertex -345.536 87.0486 281.698 + vertex -345.839 82.9086 283.731 + endloop + endfacet + facet normal 0.602633 -0.38677 -0.698027 + outer loop + vertex -345.839 82.9086 283.731 + vertex -345.536 87.0486 281.698 + vertex -343.96 86.5464 283.337 + endloop + endfacet + facet normal 0.627188 -0.420617 -0.655527 + outer loop + vertex -352.075 84.9005 276.959 + vertex -350.072 88.4967 276.568 + vertex -350.558 84.4263 278.715 + endloop + endfacet + facet normal 0.633262 -0.41885 -0.650803 + outer loop + vertex -350.558 84.4263 278.715 + vertex -350.072 88.4967 276.568 + vertex -348.577 88.0296 278.324 + endloop + endfacet + facet normal 0.616089 -0.411665 -0.67154 + outer loop + vertex -350.558 84.4263 278.715 + vertex -348.577 88.0296 278.324 + vertex -349.028 83.9314 280.422 + endloop + endfacet + facet normal 0.622508 -0.409888 -0.66669 + outer loop + vertex -349.028 83.9314 280.422 + vertex -348.577 88.0296 278.324 + vertex -347.07 87.5424 280.03 + endloop + endfacet + facet normal 0.639893 -0.433627 -0.634432 + outer loop + vertex -354.931 85.7643 273.541 + vertex -352.882 89.3511 273.157 + vertex -353.57 85.3504 275.197 + endloop + endfacet + facet normal 0.643596 -0.43268 -0.631326 + outer loop + vertex -353.57 85.3504 275.197 + vertex -352.882 89.3511 273.157 + vertex -351.539 88.9387 274.809 + endloop + endfacet + facet normal 0.63244 -0.42792 -0.645681 + outer loop + vertex -353.57 85.3504 275.197 + vertex -351.539 88.9387 274.809 + vertex -352.075 84.9005 276.959 + endloop + endfacet + facet normal 0.639589 -0.425839 -0.63999 + outer loop + vertex -352.075 84.9005 276.959 + vertex -351.539 88.9387 274.809 + vertex -350.072 88.4967 276.568 + endloop + endfacet + facet normal 0.634488 -0.428476 -0.643299 + outer loop + vertex -356.747 86.5321 271.204 + vertex -354.671 90.1468 270.844 + vertex -356.025 86.1612 272.163 + endloop + endfacet + facet normal 0.630983 -0.428433 -0.646765 + outer loop + vertex -356.025 86.1612 272.163 + vertex -354.671 90.1468 270.844 + vertex -353.961 89.7604 271.792 + endloop + endfacet + facet normal 0.641147 -0.43291 -0.633656 + outer loop + vertex -356.025 86.1612 272.163 + vertex -353.961 89.7604 271.792 + vertex -354.931 85.7643 273.541 + endloop + endfacet + facet normal 0.638996 -0.433239 -0.6356 + outer loop + vertex -354.931 85.7643 273.541 + vertex -353.961 89.7604 271.792 + vertex -352.882 89.3511 273.157 + endloop + endfacet + facet normal 0.658592 -0.436847 -0.612717 + outer loop + vertex -357.41 86.6396 270.452 + vertex -355.239 90.3975 270.106 + vertex -357.132 86.7709 270.657 + endloop + endfacet + facet normal 0.664466 -0.438737 -0.604975 + outer loop + vertex -357.132 86.7709 270.657 + vertex -355.239 90.3975 270.106 + vertex -355.037 90.4181 270.314 + endloop + endfacet + facet normal 0.640299 -0.427954 -0.637865 + outer loop + vertex -357.132 86.7709 270.657 + vertex -355.037 90.4181 270.314 + vertex -356.747 86.5321 271.204 + endloop + endfacet + facet normal 0.628342 -0.425724 -0.651111 + outer loop + vertex -356.747 86.5321 271.204 + vertex -355.037 90.4181 270.314 + vertex -354.671 90.1468 270.844 + endloop + endfacet + facet normal 0.730083 -0.48473 -0.481681 + outer loop + vertex -358.01 85.6966 270.492 + vertex -355.558 89.7887 270.09 + vertex -357.41 86.6396 270.452 + endloop + endfacet + facet normal 0.817175 -0.437524 0.375231 + outer loop + vertex -357.41 86.6396 270.452 + vertex -355.558 89.7887 270.09 + vertex -355.239 90.3975 270.106 + endloop + endfacet + facet normal 0.507735 -0.155919 -0.847287 + outer loop + vertex -329.707 87.2558 293.577 + vertex -331.152 88.1223 292.551 + vertex -328.457 94.2735 293.034 + endloop + endfacet + facet normal 0.519686 -0.182111 -0.834723 + outer loop + vertex -333.002 87.4154 291.553 + vertex -332.137 94.4191 290.564 + vertex -331.152 88.1223 292.551 + endloop + endfacet + facet normal 0.544057 -0.173914 -0.820826 + outer loop + vertex -332.137 94.4191 290.564 + vertex -328.457 94.2735 293.034 + vertex -331.152 88.1223 292.551 + endloop + endfacet + facet normal 0.570198 -0.183549 -0.800739 + outer loop + vertex -333.002 87.4154 291.553 + vertex -334.385 88.5226 290.315 + vertex -332.137 94.4191 290.564 + endloop + endfacet + facet normal 0.549299 -0.127225 -0.825884 + outer loop + vertex -332.137 94.4191 290.564 + vertex -329.693 103.554 290.782 + vertex -328.457 94.2735 293.034 + endloop + endfacet + facet normal 0.568236 -0.121772 -0.813805 + outer loop + vertex -328.457 94.2735 293.034 + vertex -329.693 103.554 290.782 + vertex -326.496 104.249 292.911 + endloop + endfacet + facet normal 0.566489 -0.101563 -0.817787 + outer loop + vertex -329.693 103.554 290.782 + vertex -327.89 112.493 290.921 + vertex -326.496 104.249 292.911 + endloop + endfacet + facet normal 0.582903 -0.0961439 -0.806833 + outer loop + vertex -326.496 104.249 292.911 + vertex -327.89 112.493 290.921 + vertex -324.854 112.841 293.073 + endloop + endfacet + facet normal 0.582785 -0.0906506 -0.807555 + outer loop + vertex -327.89 112.493 290.921 + vertex -326.519 120.93 290.963 + vertex -324.854 112.841 293.073 + endloop + endfacet + facet normal 0.591573 -0.0872652 -0.801515 + outer loop + vertex -324.854 112.841 293.073 + vertex -326.519 120.93 290.963 + vertex -323.783 121.404 292.931 + endloop + endfacet + facet normal 0.591683 -0.0890459 -0.801238 + outer loop + vertex -326.519 120.93 290.963 + vertex -325.336 129.131 290.926 + vertex -323.783 121.404 292.931 + endloop + endfacet + facet normal 0.593958 -0.0881766 -0.799649 + outer loop + vertex -323.783 121.404 292.931 + vertex -325.336 129.131 290.926 + vertex -322.648 129.462 292.885 + endloop + endfacet + facet normal 0.593996 -0.08957 -0.799466 + outer loop + vertex -325.336 129.131 290.926 + vertex -324.129 137.221 290.916 + vertex -322.648 129.462 292.885 + endloop + endfacet + facet normal 0.594671 -0.0893211 -0.798992 + outer loop + vertex -322.648 129.462 292.885 + vertex -324.129 137.221 290.916 + vertex -321.454 137.444 292.882 + endloop + endfacet + facet normal 0.594671 -0.0899576 -0.79892 + outer loop + vertex -324.129 137.221 290.916 + vertex -322.836 145.415 290.956 + vertex -321.454 137.444 292.882 + endloop + endfacet + facet normal 0.596876 -0.0891984 -0.79736 + outer loop + vertex -321.454 137.444 292.882 + vertex -322.836 145.415 290.956 + vertex -320.169 145.549 292.938 + endloop + endfacet + facet normal 0.596921 -0.0870097 -0.797568 + outer loop + vertex -322.836 145.415 290.956 + vertex -321.468 153.836 291.061 + vertex -320.169 145.549 292.938 + endloop + endfacet + facet normal 0.599132 -0.0863044 -0.795985 + outer loop + vertex -320.169 145.549 292.938 + vertex -321.468 153.836 291.061 + vertex -318.688 154.056 293.13 + endloop + endfacet + facet normal 0.599076 -0.0711099 -0.797528 + outer loop + vertex -321.468 153.836 291.061 + vertex -320.324 162.444 291.153 + vertex -318.688 154.056 293.13 + endloop + endfacet + facet normal 0.601371 -0.0702725 -0.795874 + outer loop + vertex -318.688 154.056 293.13 + vertex -320.324 162.444 291.153 + vertex -317.731 162.786 293.082 + endloop + endfacet + facet normal 0.598693 -0.0230375 -0.800647 + outer loop + vertex -320.324 162.444 291.153 + vertex -319.753 170.723 291.342 + vertex -317.731 162.786 293.082 + endloop + endfacet + facet normal 0.61265 -0.0171859 -0.790167 + outer loop + vertex -317.731 162.786 293.082 + vertex -319.753 170.723 291.342 + vertex -317.217 169.899 293.326 + endloop + endfacet + facet normal -0.0258984 -0.832516 -0.553396 + outer loop + vertex -361.486 53.3582 306.885 + vertex -365.905 52.4401 308.473 + vertex -366.25 54.0845 306.016 + endloop + endfacet + facet normal 0.00663577 -0.800341 -0.599508 + outer loop + vertex -356.236 54.9809 304.777 + vertex -361.486 53.3582 306.885 + vertex -360.862 55.5222 304.003 + endloop + endfacet + facet normal 0.0260797 -0.760078 -0.649308 + outer loop + vertex -351.99 56.4949 303.175 + vertex -356.236 54.9809 304.777 + vertex -354.944 57.2749 302.144 + endloop + endfacet + facet normal 0.0389348 -0.705155 -0.707983 + outer loop + vertex -348.442 57.3346 302.534 + vertex -351.99 56.4949 303.175 + vertex -349.526 58.3832 301.43 + endloop + endfacet + facet normal 0.0718536 -0.687015 -0.723082 + outer loop + vertex -346.1 58.8168 301.359 + vertex -348.442 57.3346 302.534 + vertex -349.526 58.3832 301.43 + endloop + endfacet + facet normal 0.11904 -0.644268 -0.755479 + outer loop + vertex -343.535 60.5343 300.298 + vertex -346.1 58.8168 301.359 + vertex -345.879 60.3297 300.103 + endloop + endfacet + facet normal 0.171146 -0.597852 -0.783124 + outer loop + vertex -341.094 62.5517 299.292 + vertex -343.535 60.5343 300.298 + vertex -343.144 62.3264 299.015 + endloop + endfacet + facet normal 0.216506 -0.544337 -0.810446 + outer loop + vertex -338.552 64.9216 298.379 + vertex -341.094 62.5517 299.292 + vertex -340.688 64.5476 298.059 + endloop + endfacet + facet normal 0.254657 -0.487015 -0.835444 + outer loop + vertex -336.318 67.6551 297.466 + vertex -338.552 64.9216 298.379 + vertex -338.379 67.037 297.199 + endloop + endfacet + facet normal 0.288549 -0.434423 -0.853239 + outer loop + vertex -334.462 70.2878 296.754 + vertex -336.318 67.6551 297.466 + vertex -336.275 69.713 296.433 + endloop + endfacet + facet normal 0.339742 -0.378172 -0.861139 + outer loop + vertex -332.846 73.1736 296.124 + vertex -334.462 70.2878 296.754 + vertex -334.408 72.6031 295.758 + endloop + endfacet + facet normal 0.423216 -0.316159 -0.849077 + outer loop + vertex -331.164 76.8562 295.591 + vertex -332.846 73.1736 296.124 + vertex -332.699 75.958 295.16 + endloop + endfacet + facet normal 0.496124 -0.262898 -0.827494 + outer loop + vertex -329.215 82.6108 294.931 + vertex -331.164 76.8562 295.591 + vertex -331.063 80.0515 294.636 + endloop + endfacet + facet normal 0.445291 -0.195057 -0.873881 + outer loop + vertex -327.575 87.2433 294.733 + vertex -329.215 82.6108 294.931 + vertex -328.536 87.6327 294.156 + endloop + endfacet + facet normal 0.45862 -0.161975 -0.873746 + outer loop + vertex -327.239 90.8855 294.234 + vertex -327.575 87.2433 294.733 + vertex -328.536 87.6327 294.156 + endloop + endfacet + facet normal 0.481869 -0.133487 -0.866016 + outer loop + vertex -326.367 94.3462 294.186 + vertex -327.239 90.8855 294.234 + vertex -328.457 94.2735 293.034 + endloop + endfacet + facet normal 0.482708 -0.107162 -0.8692 + outer loop + vertex -326.079 98.4196 293.843 + vertex -326.367 94.3462 294.186 + vertex -328.457 94.2735 293.034 + endloop + endfacet + facet normal 0.509503 -0.100315 -0.854601 + outer loop + vertex -324.96 101.873 294.105 + vertex -326.079 98.4196 293.843 + vertex -326.496 104.249 292.911 + endloop + endfacet + facet normal 0.527695 -0.0838778 -0.845282 + outer loop + vertex -324.36 106.661 294.005 + vertex -324.96 101.873 294.105 + vertex -326.496 104.249 292.911 + endloop + endfacet + facet normal 0.553338 -0.0807559 -0.829033 + outer loop + vertex -323.807 109.976 294.051 + vertex -324.36 106.661 294.005 + vertex -324.854 112.841 293.073 + endloop + endfacet + facet normal 0.547784 -0.0839315 -0.832399 + outer loop + vertex -323.316 112.239 294.146 + vertex -323.807 109.976 294.051 + vertex -324.854 112.841 293.073 + endloop + endfacet + facet normal 0.550242 -0.0761104 -0.831529 + outer loop + vertex -323.227 115.872 293.872 + vertex -323.316 112.239 294.146 + vertex -324.854 112.841 293.073 + endloop + endfacet + facet normal 0.54829 -0.0863996 -0.831813 + outer loop + vertex -322.364 119.052 294.111 + vertex -323.227 115.872 293.872 + vertex -323.783 121.404 292.931 + endloop + endfacet + facet normal 0.554463 -0.0808944 -0.828267 + outer loop + vertex -321.892 123.854 293.958 + vertex -322.364 119.052 294.111 + vertex -323.783 121.404 292.931 + endloop + endfacet + facet normal 0.56694 -0.0803011 -0.819836 + outer loop + vertex -321.396 127.547 293.939 + vertex -321.892 123.854 293.958 + vertex -322.648 129.462 292.885 + endloop + endfacet + facet normal 0.559819 -0.0872556 -0.824008 + outer loop + vertex -320.825 131.189 293.941 + vertex -321.396 127.547 293.939 + vertex -322.648 129.462 292.885 + endloop + endfacet + facet normal 0.554854 -0.0843708 -0.827658 + outer loop + vertex -319.98 135.459 294.073 + vertex -320.825 131.189 293.941 + vertex -321.454 137.444 292.882 + endloop + endfacet + facet normal 0.559763 -0.0790523 -0.824874 + outer loop + vertex -319.801 139.614 293.796 + vertex -319.98 135.459 294.073 + vertex -321.454 137.444 292.882 + endloop + endfacet + facet normal 0.54897 -0.086216 -0.831383 + outer loop + vertex -318.881 142.702 294.083 + vertex -319.801 139.614 293.796 + vertex -320.169 145.549 292.938 + endloop + endfacet + facet normal 0.556772 -0.0808134 -0.826725 + outer loop + vertex -318.3 147.615 293.994 + vertex -318.881 142.702 294.083 + vertex -320.169 145.549 292.938 + endloop + endfacet + facet normal 0.555004 -0.0777179 -0.828209 + outer loop + vertex -317.747 151.056 294.041 + vertex -318.3 147.615 293.994 + vertex -318.688 154.056 293.13 + endloop + endfacet + facet normal 0.549144 -0.080655 -0.831826 + outer loop + vertex -317.233 153.47 294.147 + vertex -317.747 151.056 294.041 + vertex -318.688 154.056 293.13 + endloop + endfacet + facet normal 0.552308 -0.0707294 -0.830634 + outer loop + vertex -317.099 157.247 293.914 + vertex -317.233 153.47 294.147 + vertex -318.688 154.056 293.13 + endloop + endfacet + facet normal 0.518336 -0.0689816 -0.85239 + outer loop + vertex -316.198 160.588 294.192 + vertex -317.099 157.247 293.914 + vertex -317.731 162.786 293.082 + endloop + endfacet + facet normal 0.541839 -0.0459332 -0.839226 + outer loop + vertex -315.729 165.468 294.228 + vertex -316.198 160.588 294.192 + vertex -317.731 162.786 293.082 + endloop + endfacet + facet normal 0.54441 0.0120961 -0.838732 + outer loop + vertex -314.45 169.032 295.109 + vertex -315.729 165.468 294.228 + vertex -317.217 169.899 293.326 + endloop + endfacet + facet normal 0.340155 -0.075694 0.937318 + outer loop + vertex -350.851 102.059 269.485 + vertex -349.967 105.719 269.46 + vertex -350.762 102.67 269.502 + endloop + endfacet + facet normal -0.899129 0.268243 0.345852 + outer loop + vertex -351.761 98.893 269.574 + vertex -350.851 102.059 269.485 + vertex -351.422 100.123 269.501 + endloop + endfacet + facet normal -0.660043 0.252572 0.707497 + outer loop + vertex -352.697 96.1285 269.687 + vertex -351.761 98.893 269.574 + vertex -352.361 97.1786 269.626 + endloop + endfacet + facet normal -0.1488 0.115034 0.982154 + outer loop + vertex -353.905 93.144 269.854 + vertex -352.697 96.1285 269.687 + vertex -353.683 93.7507 269.816 + endloop + endfacet + facet normal 0.122768 0.00953385 0.99239 + outer loop + vertex -355.282 90.151 270.053 + vertex -353.905 93.144 269.854 + vertex -355.558 89.7887 270.09 + endloop + endfacet + facet normal 0.0553013 0.0613739 0.996582 + outer loop + vertex -357.002 87.1707 270.332 + vertex -355.282 90.151 270.053 + vertex -355.558 89.7887 270.09 + endloop + endfacet + facet normal -0.69818 0.414033 -0.584056 + outer loop + vertex -359.302 83.8704 270.741 + vertex -357.002 87.1707 270.332 + vertex -358.01 85.6966 270.492 + endloop + endfacet + facet normal -0.751601 0.594378 -0.286026 + outer loop + vertex -361.417 81.3853 271.134 + vertex -359.302 83.8704 270.741 + vertex -360.459 82.5015 270.937 + endloop + endfacet + facet normal -0.692001 0.710083 -0.130065 + outer loop + vertex -363.913 79.0435 271.631 + vertex -361.417 81.3853 271.134 + vertex -363.13 79.7749 271.461 + endloop + endfacet + facet normal -0.296207 0.134884 -0.945552 + outer loop + vertex -367.235 76.4633 272.304 + vertex -363.913 79.0435 271.631 + vertex -366.164 77.2613 272.082 + endloop + endfacet + facet normal -0.15247 -0.0868909 -0.984481 + outer loop + vertex -370.86 74.2099 273.064 + vertex -367.235 76.4633 272.304 + vertex -369.588 74.9572 272.801 + endloop + endfacet + facet normal -0.312954 0.230903 -0.921273 + outer loop + vertex -374.769 72.2987 273.913 + vertex -370.86 74.2099 273.064 + vertex -373.341 72.9649 273.595 + endloop + endfacet + facet normal -0.377237 0.923785 -0.0656766 + outer loop + vertex -378.792 70.7193 274.806 + vertex -374.769 72.2987 273.913 + vertex -377.345 71.2844 274.445 + endloop + endfacet + facet normal -0.255486 0.945399 0.202354 + outer loop + vertex -382.603 69.5052 275.667 + vertex -378.792 70.7193 274.806 + vertex -381.279 69.9395 275.309 + endloop + endfacet + facet normal -0.303866 0.817016 -0.490051 + outer loop + vertex -387.443 68.3761 276.786 + vertex -382.603 69.5052 275.667 + vertex -383.988 69.1495 275.933 + endloop + endfacet + facet normal 0.143925 -0.972458 -0.183333 + outer loop + vertex -392.892 67.3309 278.053 + vertex -387.443 68.3761 276.786 + vertex -392.268 67.3729 278.32 + endloop + endfacet + facet normal 0.115332 -0.986727 -0.114314 + outer loop + vertex -398.148 66.5694 279.323 + vertex -392.892 67.3309 278.053 + vertex -392.268 67.3729 278.32 + endloop + endfacet + facet normal 0.0536985 -0.968376 -0.243648 + outer loop + vertex -404.293 65.8472 280.84 + vertex -398.148 66.5694 279.323 + vertex -401.694 66.0121 280.757 + endloop + endfacet + facet normal 0.038408 -0.989685 -0.138014 + outer loop + vertex -408.482 65.5527 281.786 + vertex -404.293 65.8472 280.84 + vertex -409.472 65.4177 282.478 + endloop + endfacet + facet normal 0.00394954 -0.982561 -0.185897 + outer loop + vertex -412.645 65.3213 282.92 + vertex -408.482 65.5527 281.786 + vertex -409.472 65.4177 282.478 + endloop + endfacet + facet normal -0.0112749 -0.989327 -0.145273 + outer loop + vertex -416.214 65.2385 283.761 + vertex -412.645 65.3213 282.92 + vertex -417.436 65.1427 284.509 + endloop + endfacet + facet normal -0.0240132 -0.985892 -0.16565 + outer loop + vertex -418.714 65.1863 284.434 + vertex -416.214 65.2385 283.761 + vertex -417.436 65.1427 284.509 + endloop + endfacet + facet normal -0.0275242 -0.993578 -0.109752 + outer loop + vertex -421.37 65.178 285.175 + vertex -418.714 65.1863 284.434 + vertex -417.436 65.1427 284.509 + endloop + endfacet + facet normal -0.0609207 -0.978446 -0.197312 + outer loop + vertex -425.201 65.2355 286.073 + vertex -421.37 65.178 285.175 + vertex -425.617 65.1074 286.837 + endloop + endfacet + facet normal -0.0714992 -0.976613 -0.202768 + outer loop + vertex -429.397 65.2937 287.272 + vertex -425.201 65.2355 286.073 + vertex -425.617 65.1074 286.837 + endloop + endfacet + facet normal -0.0816989 -0.979649 -0.18334 + outer loop + vertex -433.527 65.4537 288.258 + vertex -429.397 65.2937 287.272 + vertex -433.76 65.3195 289.078 + endloop + endfacet + facet normal -0.0932311 -0.978051 -0.186345 + outer loop + vertex -437.3 65.5928 289.415 + vertex -433.527 65.4537 288.258 + vertex -433.76 65.3195 289.078 + endloop + endfacet + facet normal -0.092467 -0.986723 -0.133518 + outer loop + vertex -440.076 65.7541 290.146 + vertex -437.3 65.5928 289.415 + vertex -441.458 65.7326 291.261 + endloop + endfacet + facet normal -0.11673 -0.979626 -0.163422 + outer loop + vertex -443.825 66.013 291.272 + vertex -440.076 65.7541 290.146 + vertex -441.458 65.7326 291.261 + endloop + endfacet + facet normal -0.0839585 -0.995567 -0.0424045 + outer loop + vertex -447.487 66.2752 292.365 + vertex -443.825 66.013 291.272 + vertex -449.614 66.4067 293.491 + endloop + endfacet + facet normal -0.127639 -0.983744 -0.126321 + outer loop + vertex -450.457 66.5503 293.224 + vertex -447.487 66.2752 292.365 + vertex -449.614 66.4067 293.491 + endloop + endfacet + facet normal -0.131788 -0.984727 -0.113777 + outer loop + vertex -454.183 66.9104 294.424 + vertex -450.457 66.5503 293.224 + vertex -449.614 66.4067 293.491 + endloop + endfacet + facet normal -0.155114 -0.977638 -0.141996 + outer loop + vertex -458.682 67.44 295.691 + vertex -454.183 66.9104 294.424 + vertex -458.067 67.3106 295.911 + endloop + endfacet + facet normal -0.160224 -0.978709 -0.128287 + outer loop + vertex -462.608 67.9161 296.963 + vertex -458.682 67.44 295.691 + vertex -458.067 67.3106 295.911 + endloop + endfacet + facet normal -0.175283 -0.976413 -0.126068 + outer loop + vertex -466.815 68.5065 298.24 + vertex -462.608 67.9161 296.963 + vertex -465.945 68.3304 298.394 + endloop + endfacet + facet normal -0.180289 -0.978485 -0.100313 + outer loop + vertex -470.401 69.0413 299.468 + vertex -466.815 68.5065 298.24 + vertex -465.945 68.3304 298.394 + endloop + endfacet + facet normal -0.212422 -0.97538 -0.0592556 + outer loop + vertex -483.723 71.4656 304.21 + vertex -478.6 70.4651 302.314 + vertex -480.356 70.7639 303.688 + endloop + endfacet + facet normal -0.207679 -0.97787 -0.0252987 + outer loop + vertex -480.356 70.7639 303.688 + vertex -484.804 71.6612 305.521 + vertex -483.723 71.4656 304.21 + endloop + endfacet + facet normal -0.160535 -0.986948 -0.0127308 + outer loop + vertex -465.945 68.3304 298.394 + vertex -473.8 69.5734 301.083 + vertex -470.401 69.0413 299.468 + endloop + endfacet + facet normal -0.142534 -0.988712 -0.0461745 + outer loop + vertex -458.067 67.3106 295.911 + vertex -465.945 68.3304 298.394 + vertex -462.608 67.9161 296.963 + endloop + endfacet + facet normal -0.11755 -0.992263 -0.0399433 + outer loop + vertex -449.614 66.4067 293.491 + vertex -458.067 67.3106 295.911 + vertex -454.183 66.9104 294.424 + endloop + endfacet + facet normal -0.117158 -0.98444 -0.130969 + outer loop + vertex -441.458 65.7326 291.261 + vertex -449.614 66.4067 293.491 + vertex -443.825 66.013 291.272 + endloop + endfacet + facet normal -0.0880461 -0.98844 -0.12343 + outer loop + vertex -433.76 65.3195 289.078 + vertex -441.458 65.7326 291.261 + vertex -437.3 65.5928 289.415 + endloop + endfacet + facet normal -0.065192 -0.987521 -0.143358 + outer loop + vertex -425.617 65.1074 286.837 + vertex -433.76 65.3195 289.078 + vertex -429.397 65.2937 287.272 + endloop + endfacet + facet normal -0.028354 -0.992998 -0.114681 + outer loop + vertex -417.436 65.1427 284.509 + vertex -425.617 65.1074 286.837 + vertex -421.37 65.178 285.175 + endloop + endfacet + facet normal 0.0253339 -0.999032 -0.0359606 + outer loop + vertex -409.472 65.4177 282.478 + vertex -417.436 65.1427 284.509 + vertex -412.645 65.3213 282.92 + endloop + endfacet + facet normal -0.0118177 -0.798384 -0.602033 + outer loop + vertex -366.25 54.0845 306.016 + vertex -360.862 55.5222 304.003 + vertex -361.486 53.3582 306.885 + endloop + endfacet + facet normal 0.061004 -0.995805 -0.0681965 + outer loop + vertex -401.694 66.0121 280.757 + vertex -409.472 65.4177 282.478 + vertex -404.293 65.8472 280.84 + endloop + endfacet + facet normal 0.0201272 -0.75875 -0.651071 + outer loop + vertex -360.862 55.5222 304.003 + vertex -354.944 57.2749 302.144 + vertex -356.236 54.9809 304.777 + endloop + endfacet + facet normal 0.120313 -0.988927 -0.0868856 + outer loop + vertex -392.268 67.3729 278.32 + vertex -401.694 66.0121 280.757 + vertex -398.148 66.5694 279.323 + endloop + endfacet + facet normal 0.0599678 -0.730867 -0.67988 + outer loop + vertex -354.944 57.2749 302.144 + vertex -351.692 59.1877 300.374 + vertex -349.526 58.3832 301.43 + endloop + endfacet + facet normal 0.099348 -0.927042 -0.361557 + outer loop + vertex -382.627 68.0702 279.056 + vertex -389.055 66.3289 281.754 + vertex -384.176 68.3362 277.948 + endloop + endfacet + facet normal 0.283988 -0.911631 0.29712 + outer loop + vertex -385.164 68.9105 276.247 + vertex -392.268 67.3729 278.32 + vertex -387.443 68.3761 276.786 + endloop + endfacet + facet normal 0.0983753 -0.919506 -0.380567 + outer loop + vertex -388.958 67.567 278.57 + vertex -383.965 68.8853 276.676 + vertex -384.176 68.3362 277.948 + endloop + endfacet + facet normal 0.11802 -0.594853 -0.795123 + outer loop + vertex -345.879 60.3297 300.103 + vertex -343.144 62.3264 299.015 + vertex -343.535 60.5343 300.298 + endloop + endfacet + facet normal 0.065422 -0.642837 -0.763204 + outer loop + vertex -349.526 58.3832 301.43 + vertex -345.879 60.3297 300.103 + vertex -346.1 58.8168 301.359 + endloop + endfacet + facet normal -0.0612239 0.739658 0.670192 + outer loop + vertex -381.279 69.9395 275.309 + vertex -383.988 69.1495 275.933 + vertex -382.603 69.5052 275.667 + endloop + endfacet + facet normal 0.315954 -0.663387 0.6783 + outer loop + vertex -383.988 69.1495 275.933 + vertex -385.164 68.9105 276.247 + vertex -387.443 68.3761 276.786 + endloop + endfacet + facet normal 0.00884594 0.521836 0.853 + outer loop + vertex -377.345 71.2844 274.445 + vertex -381.279 69.9395 275.309 + vertex -378.792 70.7193 274.806 + endloop + endfacet + facet normal 0.212177 -0.489349 -0.845883 + outer loop + vertex -340.688 64.5476 298.059 + vertex -338.379 67.037 297.199 + vertex -338.552 64.9216 298.379 + endloop + endfacet + facet normal 0.170377 -0.542471 -0.822616 + outer loop + vertex -343.144 62.3264 299.015 + vertex -340.688 64.5476 298.059 + vertex -341.094 62.5517 299.292 + endloop + endfacet + facet normal 0.115988 0.214494 0.969814 + outer loop + vertex -373.341 72.9649 273.595 + vertex -377.345 71.2844 274.445 + vertex -374.769 72.2987 273.913 + endloop + endfacet + facet normal 0.247057 -0.080666 0.965637 + outer loop + vertex -369.588 74.9572 272.801 + vertex -373.341 72.9649 273.595 + vertex -370.86 74.2099 273.064 + endloop + endfacet + facet normal 0.277623 -0.384924 -0.880204 + outer loop + vertex -336.275 69.713 296.433 + vertex -334.408 72.6031 295.758 + vertex -334.462 70.2878 296.754 + endloop + endfacet + facet normal 0.244103 -0.439195 -0.864593 + outer loop + vertex -338.379 67.037 297.199 + vertex -336.275 69.713 296.433 + vertex -336.318 67.6551 297.466 + endloop + endfacet + facet normal 0.231358 -0.0404999 0.972025 + outer loop + vertex -366.164 77.2613 272.082 + vertex -369.588 74.9572 272.801 + vertex -367.235 76.4633 272.304 + endloop + endfacet + facet normal 0.104644 0.117673 0.987524 + outer loop + vertex -363.13 79.7749 271.461 + vertex -366.164 77.2613 272.082 + vertex -363.913 79.0435 271.631 + endloop + endfacet + facet normal 0.404821 -0.273475 -0.872543 + outer loop + vertex -332.699 75.958 295.16 + vertex -331.063 80.0515 294.636 + vertex -331.164 76.8562 295.591 + endloop + endfacet + facet normal 0.326351 -0.324427 -0.88783 + outer loop + vertex -334.408 72.6031 295.758 + vertex -332.699 75.958 295.16 + vertex -332.846 73.1736 296.124 + endloop + endfacet + facet normal 0.126099 0.0667171 0.989772 + outer loop + vertex -360.459 82.5015 270.937 + vertex -363.13 79.7749 271.461 + vertex -361.417 81.3853 271.134 + endloop + endfacet + facet normal 0.0447231 0.104177 0.993553 + outer loop + vertex -358.01 85.6966 270.492 + vertex -360.459 82.5015 270.937 + vertex -359.302 83.8704 270.741 + endloop + endfacet + facet normal 0.51676 -0.198396 -0.832825 + outer loop + vertex -329.825 83.9394 294.236 + vertex -328.536 87.6327 294.156 + vertex -329.215 82.6108 294.931 + endloop + endfacet + facet normal 0.477404 -0.151921 -0.865451 + outer loop + vertex -328.536 87.6327 294.156 + vertex -329.707 87.2558 293.577 + vertex -328.457 94.2735 293.034 + endloop + endfacet + facet normal 0.462069 -0.23513 -0.855106 + outer loop + vertex -331.063 80.0515 294.636 + vertex -329.825 83.9394 294.236 + vertex -329.215 82.6108 294.931 + endloop + endfacet + facet normal 0.122556 0.0238691 0.992175 + outer loop + vertex -355.558 89.7887 270.09 + vertex -358.01 85.6966 270.492 + vertex -357.002 87.1707 270.332 + endloop + endfacet + facet normal 0.0692324 0.0362252 0.996943 + outer loop + vertex -353.683 93.7507 269.816 + vertex -355.558 89.7887 270.09 + vertex -353.905 93.144 269.854 + endloop + endfacet + facet normal -0.0393077 0.0704141 0.996743 + outer loop + vertex -352.361 97.1786 269.626 + vertex -353.683 93.7507 269.816 + vertex -352.697 96.1285 269.687 + endloop + endfacet + facet normal -0.352957 0.151746 0.923252 + outer loop + vertex -351.422 100.123 269.501 + vertex -352.361 97.1786 269.626 + vertex -351.761 98.893 269.574 + endloop + endfacet + facet normal 0.479727 -0.105081 -0.871103 + outer loop + vertex -328.457 94.2735 293.034 + vertex -326.496 104.249 292.911 + vertex -326.079 98.4196 293.843 + endloop + endfacet + facet normal 0.740141 -0.184054 0.646773 + outer loop + vertex -349.213 109.093 269.557 + vertex -350.762 102.67 269.502 + vertex -349.967 105.719 269.46 + endloop + endfacet + facet normal 0.528663 -0.0850636 -0.844559 + outer loop + vertex -326.496 104.249 292.911 + vertex -324.854 112.841 293.073 + vertex -324.36 106.661 294.005 + endloop + endfacet + facet normal 0.913549 -0.184815 -0.362315 + outer loop + vertex -347.465 117.542 269.654 + vertex -349.213 109.093 269.557 + vertex -348.317 113.739 269.448 + endloop + endfacet + facet normal 0.560714 -0.0837794 -0.82376 + outer loop + vertex -324.854 112.841 293.073 + vertex -323.783 121.404 292.931 + vertex -323.227 115.872 293.872 + endloop + endfacet + facet normal 0.556417 -0.0830411 -0.826743 + outer loop + vertex -323.783 121.404 292.931 + vertex -322.648 129.462 292.885 + vertex -321.892 123.854 293.958 + endloop + endfacet + facet normal 0.55761 -0.0837897 -0.825863 + outer loop + vertex -322.648 129.462 292.885 + vertex -321.454 137.444 292.882 + vertex -320.825 131.189 293.941 + endloop + endfacet + facet normal 0.564132 -0.0838375 -0.821417 + outer loop + vertex -321.454 137.444 292.882 + vertex -320.169 145.549 292.938 + vertex -319.801 139.614 293.796 + endloop + endfacet + facet normal 0.554472 -0.0777967 -0.828558 + outer loop + vertex -320.169 145.549 292.938 + vertex -318.688 154.056 293.13 + vertex -318.3 147.615 293.994 + endloop + endfacet + facet normal 0.542351 -0.0640329 -0.837708 + outer loop + vertex -318.688 154.056 293.13 + vertex -317.731 162.786 293.082 + vertex -317.099 157.247 293.914 + endloop + endfacet + facet normal 0.503523 -0.00676462 -0.863955 + outer loop + vertex -317.731 162.786 293.082 + vertex -317.217 169.899 293.326 + vertex -315.729 165.468 294.228 + endloop + endfacet + facet normal 0.0545291 -0.715179 -0.696811 + outer loop + vertex -351.99 56.4949 303.175 + vertex -354.944 57.2749 302.144 + vertex -349.526 58.3832 301.43 + endloop + endfacet + facet normal 0.440858 -0.154648 -0.884154 + outer loop + vertex -327.239 90.8855 294.234 + vertex -328.536 87.6327 294.156 + vertex -328.457 94.2735 293.034 + endloop + endfacet + facet normal 0.102727 -0.928131 -0.3578 + outer loop + vertex -389.055 66.3289 281.754 + vertex -388.958 67.567 278.57 + vertex -384.176 68.3362 277.948 + endloop + endfacet + facet normal 0.78639 -0.58285 0.204639 + outer loop + vertex -434.678 96.1526 66.5519 + vertex -435.605 95.1512 67.2628 + vertex -436.881 92.9104 65.7834 + endloop + endfacet + facet normal 0.749624 -0.604603 0.269293 + outer loop + vertex -436.881 92.9104 65.7834 + vertex -435.605 95.1512 67.2628 + vertex -437.625 92.3441 66.584 + endloop + endfacet + facet normal 0.733169 -0.64046 0.228635 + outer loop + vertex -436.881 92.9104 65.7834 + vertex -437.625 92.3441 66.584 + vertex -438.925 90.3486 65.1634 + endloop + endfacet + facet normal 0.708701 -0.652595 0.268072 + outer loop + vertex -438.925 90.3486 65.1634 + vertex -437.625 92.3441 66.584 + vertex -439.295 90.3419 66.1259 + endloop + endfacet + facet normal 0.858056 -0.477786 0.188308 + outer loop + vertex -431.128 102.456 67.5954 + vertex -431.615 101.933 68.4902 + vertex -432.827 99.2571 67.2233 + endloop + endfacet + facet normal 0.832575 -0.494887 0.248807 + outer loop + vertex -432.827 99.2571 67.2233 + vertex -431.615 101.933 68.4902 + vertex -433.565 98.3826 67.953 + endloop + endfacet + facet normal 0.823619 -0.532837 0.19426 + outer loop + vertex -432.827 99.2571 67.2233 + vertex -433.565 98.3826 67.953 + vertex -434.678 96.1526 66.5519 + endloop + endfacet + facet normal 0.792822 -0.554427 0.25307 + outer loop + vertex -434.678 96.1526 66.5519 + vertex -433.565 98.3826 67.953 + vertex -435.605 95.1512 67.2628 + endloop + endfacet + facet normal 0.358894 -0.905528 0.226306 + outer loop + vertex -453.131 81.035 65.3564 + vertex -455.319 79.8044 63.9021 + vertex -452.404 80.5624 62.3125 + endloop + endfacet + facet normal 0.362076 -0.902395 0.233633 + outer loop + vertex -457.132 77.9972 59.7308 + vertex -452.404 80.5624 62.3125 + vertex -455.319 79.8044 63.9021 + endloop + endfacet + facet normal 0.449914 -0.867698 0.21137 + outer loop + vertex -448.684 83.6203 67.0873 + vertex -450.762 82.2202 65.7637 + vertex -447.75 83.3048 63.8043 + endloop + endfacet + facet normal 0.402622 -0.885064 0.233574 + outer loop + vertex -453.131 81.035 65.3564 + vertex -452.404 80.5624 62.3125 + vertex -450.762 82.2202 65.7637 + endloop + endfacet + facet normal 0.447098 -0.87057 0.205453 + outer loop + vertex -452.404 80.5624 62.3125 + vertex -447.75 83.3048 63.8043 + vertex -450.762 82.2202 65.7637 + endloop + endfacet + facet normal 0.497092 -0.838815 0.222012 + outer loop + vertex -448.684 83.6203 67.0873 + vertex -447.75 83.3048 63.8043 + vertex -446.676 84.9482 67.6095 + endloop + endfacet + facet normal 0.649199 -0.732134 0.206206 + outer loop + vertex -440.216 89.9044 67.4057 + vertex -440.995 89.8824 69.78 + vertex -442.387 87.7535 66.6051 + endloop + endfacet + facet normal 0.633842 -0.741705 0.219358 + outer loop + vertex -442.387 87.7535 66.6051 + vertex -440.995 89.8824 69.78 + vertex -443.124 87.874 69.1396 + endloop + endfacet + facet normal 0.666102 -0.707039 0.237496 + outer loop + vertex -439.295 90.3419 66.1259 + vertex -440.216 89.9044 67.4057 + vertex -441.039 88.3236 65.0075 + endloop + endfacet + facet normal 0.626494 -0.732057 0.267578 + outer loop + vertex -441.039 88.3236 65.0075 + vertex -440.216 89.9044 67.4057 + vertex -442.387 87.7535 66.6051 + endloop + endfacet + facet normal 0.596722 -0.769 0.229263 + outer loop + vertex -441.039 88.3236 65.0075 + vertex -442.387 87.7535 66.6051 + vertex -443.872 85.8956 64.2384 + endloop + endfacet + facet normal 0.574985 -0.778833 0.250621 + outer loop + vertex -443.872 85.8956 64.2384 + vertex -442.387 87.7535 66.6051 + vertex -444.806 85.8748 66.3151 + endloop + endfacet + facet normal 0.584579 -0.784464 0.207084 + outer loop + vertex -442.387 87.7535 66.6051 + vertex -443.124 87.874 69.1396 + vertex -444.806 85.8748 66.3151 + endloop + endfacet + facet normal 0.59206 -0.780693 0.199959 + outer loop + vertex -444.806 85.8748 66.3151 + vertex -443.124 87.874 69.1396 + vertex -444.88 86.4976 68.966 + endloop + endfacet + facet normal 0.764242 -0.617346 0.186595 + outer loop + vertex -436.253 94.9189 68.9141 + vertex -436.737 95.0614 71.3695 + vertex -438.258 92.2217 68.2016 + endloop + endfacet + facet normal 0.748173 -0.630641 0.206225 + outer loop + vertex -438.258 92.2217 68.2016 + vertex -436.737 95.0614 71.3695 + vertex -438.854 92.2955 70.5921 + endloop + endfacet + facet normal 0.766994 -0.604212 0.215979 + outer loop + vertex -435.605 95.1512 67.2628 + vertex -436.253 94.9189 68.9141 + vertex -437.625 92.3441 66.584 + endloop + endfacet + facet normal 0.746047 -0.619223 0.244902 + outer loop + vertex -437.625 92.3441 66.584 + vertex -436.253 94.9189 68.9141 + vertex -438.258 92.2217 68.2016 + endloop + endfacet + facet normal 0.720103 -0.653885 0.232132 + outer loop + vertex -437.625 92.3441 66.584 + vertex -438.258 92.2217 68.2016 + vertex -439.295 90.3419 66.1259 + endloop + endfacet + facet normal 0.689425 -0.673906 0.265603 + outer loop + vertex -439.295 90.3419 66.1259 + vertex -438.258 92.2217 68.2016 + vertex -440.216 89.9044 67.4057 + endloop + endfacet + facet normal 0.713758 -0.671558 0.198897 + outer loop + vertex -438.258 92.2217 68.2016 + vertex -438.854 92.2955 70.5921 + vertex -440.216 89.9044 67.4057 + endloop + endfacet + facet normal 0.691613 -0.687777 0.220531 + outer loop + vertex -440.216 89.9044 67.4057 + vertex -438.854 92.2955 70.5921 + vertex -440.995 89.8824 69.78 + endloop + endfacet + facet normal 0.845579 -0.511122 0.15411 + outer loop + vertex -432.208 101.515 70.1991 + vertex -432.662 101.52 72.7078 + vertex -434.205 98.0333 69.6076 + endloop + endfacet + facet normal 0.832795 -0.524878 0.175945 + outer loop + vertex -434.205 98.0333 69.6076 + vertex -432.662 101.52 72.7078 + vertex -434.655 98.1494 72.0819 + endloop + endfacet + facet normal 0.851663 -0.494144 0.174617 + outer loop + vertex -431.615 101.933 68.4902 + vertex -432.208 101.515 70.1991 + vertex -433.565 98.3826 67.953 + endloop + endfacet + facet normal 0.831452 -0.51306 0.213207 + outer loop + vertex -433.565 98.3826 67.953 + vertex -432.208 101.515 70.1991 + vertex -434.205 98.0333 69.6076 + endloop + endfacet + facet normal 0.80972 -0.552983 0.196376 + outer loop + vertex -433.565 98.3826 67.953 + vertex -434.205 98.0333 69.6076 + vertex -435.605 95.1512 67.2628 + endloop + endfacet + facet normal 0.789049 -0.569865 0.229466 + outer loop + vertex -435.605 95.1512 67.2628 + vertex -434.205 98.0333 69.6076 + vertex -436.253 94.9189 68.9141 + endloop + endfacet + facet normal 0.804892 -0.567681 0.172882 + outer loop + vertex -434.205 98.0333 69.6076 + vertex -434.655 98.1494 72.0819 + vertex -436.253 94.9189 68.9141 + endloop + endfacet + facet normal 0.793103 -0.57868 0.190046 + outer loop + vertex -436.253 94.9189 68.9141 + vertex -434.655 98.1494 72.0819 + vertex -436.737 95.0614 71.3695 + endloop + endfacet + facet normal 0.884928 -0.445594 0.135457 + outer loop + vertex -430.249 105.523 70.5798 + vertex -430.769 105.27 73.1505 + vertex -432.208 101.515 70.1991 + endloop + endfacet + facet normal 0.87364 -0.459834 0.159077 + outer loop + vertex -432.208 101.515 70.1991 + vertex -430.769 105.27 73.1505 + vertex -432.662 101.52 72.7078 + endloop + endfacet + facet normal 0.923787 -0.321035 0.208696 + outer loop + vertex -427.799 110.465 68.9023 + vertex -425.735 117.637 70.7975 + vertex -428.224 110.43 70.7258 + endloop + endfacet + facet normal 0.652021 -0.747328 0.127941 + outer loop + vertex -441.539 90.1094 72.8701 + vertex -441.944 90.3487 76.3338 + vertex -443.657 88.138 72.1494 + endloop + endfacet + facet normal 0.631019 -0.76221 0.1444 + outer loop + vertex -443.657 88.138 72.1494 + vertex -441.944 90.3487 76.3338 + vertex -444.196 88.3362 75.5518 + endloop + endfacet + facet normal 0.766201 -0.634122 0.104043 + outer loop + vertex -437.133 95.2964 74.4383 + vertex -437.45 95.4789 77.8904 + vertex -439.34 92.5017 73.6601 + endloop + endfacet + facet normal 0.754138 -0.646059 0.117833 + outer loop + vertex -439.34 92.5017 73.6601 + vertex -437.45 95.4789 77.8904 + vertex -439.699 92.7145 77.1281 + endloop + endfacet + facet normal 0.765179 -0.626902 0.146612 + outer loop + vertex -436.737 95.0614 71.3695 + vertex -437.133 95.2964 74.4383 + vertex -438.854 92.2955 70.5921 + endloop + endfacet + facet normal 0.751957 -0.639003 0.161972 + outer loop + vertex -438.854 92.2955 70.5921 + vertex -437.133 95.2964 74.4383 + vertex -439.34 92.5017 73.6601 + endloop + endfacet + facet normal 0.71148 -0.684568 0.158627 + outer loop + vertex -438.854 92.2955 70.5921 + vertex -439.34 92.5017 73.6601 + vertex -440.995 89.8824 69.78 + endloop + endfacet + facet normal 0.695832 -0.696901 0.173627 + outer loop + vertex -440.995 89.8824 69.78 + vertex -439.34 92.5017 73.6601 + vertex -441.539 90.1094 72.8701 + endloop + endfacet + facet normal 0.711821 -0.692665 0.116304 + outer loop + vertex -439.34 92.5017 73.6601 + vertex -439.699 92.7145 77.1281 + vertex -441.539 90.1094 72.8701 + endloop + endfacet + facet normal 0.697041 -0.705094 0.130292 + outer loop + vertex -441.539 90.1094 72.8701 + vertex -439.699 92.7145 77.1281 + vertex -441.944 90.3487 76.3338 + endloop + endfacet + facet normal 0.847063 -0.52449 0.0859858 + outer loop + vertex -432.969 101.777 75.8087 + vertex -433.192 101.979 79.2388 + vertex -434.987 98.4102 75.1515 + endloop + endfacet + facet normal 0.841761 -0.531523 0.0944533 + outer loop + vertex -434.987 98.4102 75.1515 + vertex -433.192 101.979 79.2388 + vertex -435.254 98.5988 78.595 + endloop + endfacet + facet normal 0.843479 -0.522031 0.1266 + outer loop + vertex -432.662 101.52 72.7078 + vertex -432.969 101.777 75.8087 + vertex -434.655 98.1494 72.0819 + endloop + endfacet + facet normal 0.837913 -0.528691 0.135602 + outer loop + vertex -434.655 98.1494 72.0819 + vertex -432.969 101.777 75.8087 + vertex -434.987 98.4102 75.1515 + endloop + endfacet + facet normal 0.806527 -0.575303 0.136166 + outer loop + vertex -434.655 98.1494 72.0819 + vertex -434.987 98.4102 75.1515 + vertex -436.737 95.0614 71.3695 + endloop + endfacet + facet normal 0.798297 -0.5839 0.147587 + outer loop + vertex -436.737 95.0614 71.3695 + vertex -434.987 98.4102 75.1515 + vertex -437.133 95.2964 74.4383 + endloop + endfacet + facet normal 0.809487 -0.579471 0.094574 + outer loop + vertex -434.987 98.4102 75.1515 + vertex -435.254 98.5988 78.595 + vertex -437.133 95.2964 74.4383 + endloop + endfacet + facet normal 0.801914 -0.588159 0.104899 + outer loop + vertex -437.133 95.2964 74.4383 + vertex -435.254 98.5988 78.595 + vertex -437.45 95.4789 77.8904 + endloop + endfacet + facet normal 0.881587 -0.45837 0.1127 + outer loop + vertex -430.769 105.27 73.1505 + vertex -431.109 105.392 76.3055 + vertex -432.662 101.52 72.7078 + endloop + endfacet + facet normal 0.875135 -0.4674 0.125201 + outer loop + vertex -432.662 101.52 72.7078 + vertex -431.109 105.392 76.3055 + vertex -432.969 101.777 75.8087 + endloop + endfacet + facet normal 0.881997 -0.464582 0.0790207 + outer loop + vertex -431.109 105.392 76.3055 + vertex -431.316 105.589 79.7701 + vertex -432.969 101.777 75.8087 + endloop + endfacet + facet normal 0.878955 -0.469299 0.0848284 + outer loop + vertex -432.969 101.777 75.8087 + vertex -431.316 105.589 79.7701 + vertex -433.192 101.979 79.2388 + endloop + endfacet + facet normal 0.402081 -0.903414 0.148907 + outer loop + vertex -451.378 83.408 72.5635 + vertex -451.032 84.5951 78.8304 + vertex -453.597 82.3322 72.0288 + endloop + endfacet + facet normal 0.517709 -0.846449 0.124501 + outer loop + vertex -446.559 86.5511 74.8329 + vertex -447.299 86.6919 78.8701 + vertex -449.152 84.8567 74.0965 + endloop + endfacet + facet normal 0.471135 -0.871047 0.138959 + outer loop + vertex -451.378 83.408 72.5635 + vertex -449.152 84.8567 74.0965 + vertex -451.032 84.5951 78.8304 + endloop + endfacet + facet normal 0.487338 -0.8691 0.0846603 + outer loop + vertex -447.224 87.129 82.9254 + vertex -451.032 84.5951 78.8304 + vertex -447.299 86.6919 78.8701 + endloop + endfacet + facet normal 0.48349 -0.863376 0.144289 + outer loop + vertex -449.152 84.8567 74.0965 + vertex -447.299 86.6919 78.8701 + vertex -451.032 84.5951 78.8304 + endloop + endfacet + facet normal 0.633126 -0.772181 0.0537412 + outer loop + vertex -442.233 90.5408 80.0404 + vertex -442.381 90.6866 83.8812 + vertex -444.627 88.5307 79.3639 + endloop + endfacet + facet normal 0.612949 -0.786943 0.0708185 + outer loop + vertex -444.627 88.5307 79.3639 + vertex -442.381 90.6866 83.8812 + vertex -444.831 88.7266 83.3079 + endloop + endfacet + facet normal 0.646196 -0.757895 0.0895852 + outer loop + vertex -441.944 90.3487 76.3338 + vertex -442.233 90.5408 80.0404 + vertex -444.196 88.3362 75.5518 + endloop + endfacet + facet normal 0.620749 -0.776289 0.10975 + outer loop + vertex -444.196 88.3362 75.5518 + vertex -442.233 90.5408 80.0404 + vertex -444.627 88.5307 79.3639 + endloop + endfacet + facet normal 0.578526 -0.808664 0.106631 + outer loop + vertex -444.196 88.3362 75.5518 + vertex -444.627 88.5307 79.3639 + vertex -446.559 86.5511 74.8329 + endloop + endfacet + facet normal 0.54579 -0.827931 0.129007 + outer loop + vertex -446.559 86.5511 74.8329 + vertex -444.627 88.5307 79.3639 + vertex -447.299 86.6919 78.8701 + endloop + endfacet + facet normal 0.556626 -0.827815 0.0699324 + outer loop + vertex -444.627 88.5307 79.3639 + vertex -444.831 88.7266 83.3079 + vertex -447.299 86.6919 78.8701 + endloop + endfacet + facet normal 0.544532 -0.834924 0.0799187 + outer loop + vertex -447.299 86.6919 78.8701 + vertex -444.831 88.7266 83.3079 + vertex -447.224 87.129 82.9254 + endloop + endfacet + facet normal 0.7632 -0.645683 0.0249011 + outer loop + vertex -437.665 95.58 81.5382 + vertex -437.751 95.6225 85.2837 + vertex -439.935 92.8679 80.7954 + endloop + endfacet + facet normal 0.752265 -0.657784 0.0376484 + outer loop + vertex -439.935 92.8679 80.7954 + vertex -437.751 95.6225 85.2837 + vertex -440.037 92.9673 84.5702 + endloop + endfacet + facet normal 0.765622 -0.64022 0.0627785 + outer loop + vertex -437.45 95.4789 77.8904 + vertex -437.665 95.58 81.5382 + vertex -439.699 92.7145 77.1281 + endloop + endfacet + facet normal 0.754291 -0.652154 0.0757606 + outer loop + vertex -439.699 92.7145 77.1281 + vertex -437.665 95.58 81.5382 + vertex -439.935 92.8679 80.7954 + endloop + endfacet + facet normal 0.710712 -0.69948 0.0749408 + outer loop + vertex -439.699 92.7145 77.1281 + vertex -439.935 92.8679 80.7954 + vertex -441.944 90.3487 76.3338 + endloop + endfacet + facet normal 0.693738 -0.714451 0.0910364 + outer loop + vertex -441.944 90.3487 76.3338 + vertex -439.935 92.8679 80.7954 + vertex -442.233 90.5408 80.0404 + endloop + endfacet + facet normal 0.70497 -0.708235 0.0376975 + outer loop + vertex -439.935 92.8679 80.7954 + vertex -440.037 92.9673 84.5702 + vertex -442.233 90.5408 80.0404 + endloop + endfacet + facet normal 0.688189 -0.723518 0.0540177 + outer loop + vertex -442.233 90.5408 80.0404 + vertex -440.037 92.9673 84.5702 + vertex -442.381 90.6866 83.8812 + endloop + endfacet + facet normal 0.848507 -0.529154 0.00569972 + outer loop + vertex -433.347 102.03 82.8501 + vertex -433.4 101.984 86.5649 + vertex -435.444 98.6608 82.2254 + endloop + endfacet + facet normal 0.842784 -0.538037 0.0151986 + outer loop + vertex -435.444 98.6608 82.2254 + vertex -433.4 101.984 86.5649 + vertex -435.518 98.6498 85.9566 + endloop + endfacet + facet normal 0.849124 -0.526372 0.0438357 + outer loop + vertex -433.192 101.979 79.2388 + vertex -433.347 102.03 82.8501 + vertex -435.254 98.5988 78.595 + endloop + endfacet + facet normal 0.84334 -0.534742 0.0531761 + outer loop + vertex -435.254 98.5988 78.595 + vertex -433.347 102.03 82.8501 + vertex -435.444 98.6608 82.2254 + endloop + endfacet + facet normal 0.811012 -0.582687 0.0523073 + outer loop + vertex -435.254 98.5988 78.595 + vertex -435.444 98.6608 82.2254 + vertex -437.45 95.4789 77.8904 + endloop + endfacet + facet normal 0.802739 -0.592923 0.0636503 + outer loop + vertex -437.45 95.4789 77.8904 + vertex -435.444 98.6608 82.2254 + vertex -437.665 95.58 81.5382 + endloop + endfacet + facet normal 0.809564 -0.586855 0.014393 + outer loop + vertex -435.444 98.6608 82.2254 + vertex -435.518 98.6498 85.9566 + vertex -437.665 95.58 81.5382 + endloop + endfacet + facet normal 0.801811 -0.597044 0.0252389 + outer loop + vertex -437.665 95.58 81.5382 + vertex -435.518 98.6498 85.9566 + vertex -437.751 95.6225 85.2837 + endloop + endfacet + facet normal 0.884412 -0.465188 0.0376195 + outer loop + vertex -431.316 105.589 79.7701 + vertex -431.433 105.658 83.3787 + vertex -433.192 101.979 79.2388 + endloop + endfacet + facet normal 0.880923 -0.47117 0.0444194 + outer loop + vertex -433.192 101.979 79.2388 + vertex -431.433 105.658 83.3787 + vertex -433.347 102.03 82.8501 + endloop + endfacet + facet normal 0.884619 -0.466309 -0.00233725 + outer loop + vertex -431.433 105.658 83.3787 + vertex -431.455 105.599 87.0761 + vertex -433.347 102.03 82.8501 + endloop + endfacet + facet normal 0.880098 -0.474743 0.00681044 + outer loop + vertex -433.347 102.03 82.8501 + vertex -431.455 105.599 87.0761 + vertex -433.4 101.984 86.5649 + endloop + endfacet + facet normal 0.338445 -0.937284 0.0833931 + outer loop + vertex -455.303 82.9266 80.3775 + vertex -455.728 83.3535 86.9016 + vertex -459.051 81.5038 79.5983 + endloop + endfacet + facet normal 0.387484 -0.918463 0.0792516 + outer loop + vertex -451.032 84.5951 78.8304 + vertex -450.948 85.3837 87.5583 + vertex -455.303 82.9266 80.3775 + endloop + endfacet + facet normal 0.379545 -0.921258 0.0850234 + outer loop + vertex -455.303 82.9266 80.3775 + vertex -450.948 85.3837 87.5583 + vertex -455.728 83.3535 86.9016 + endloop + endfacet + facet normal 0.516677 -0.854804 0.0485357 + outer loop + vertex -447.224 87.129 82.9254 + vertex -447.777 86.9921 86.4007 + vertex -451.032 84.5951 78.8304 + endloop + endfacet + facet normal 0.46185 -0.886328 0.0334068 + outer loop + vertex -447.255 87.4298 90.798 + vertex -450.948 85.3837 87.5583 + vertex -447.777 86.9921 86.4007 + endloop + endfacet + facet normal 0.472742 -0.878023 0.0747757 + outer loop + vertex -450.948 85.3837 87.5583 + vertex -451.032 84.5951 78.8304 + vertex -447.777 86.9921 86.4007 + endloop + endfacet + facet normal 0.610167 -0.792262 -0.00412217 + outer loop + vertex -442.401 90.7735 87.7342 + vertex -442.313 90.821 91.5467 + vertex -444.921 88.8355 87.1504 + endloop + endfacet + facet normal 0.597052 -0.802161 0.00812817 + outer loop + vertex -444.921 88.8355 87.1504 + vertex -442.313 90.821 91.5467 + vertex -444.875 88.9087 90.9951 + endloop + endfacet + facet normal 0.621553 -0.783094 0.0208887 + outer loop + vertex -442.381 90.6866 83.8812 + vertex -442.401 90.7735 87.7342 + vertex -444.831 88.7266 83.3079 + endloop + endfacet + facet normal 0.603799 -0.79629 0.0367384 + outer loop + vertex -444.831 88.7266 83.3079 + vertex -442.401 90.7735 87.7342 + vertex -444.921 88.8355 87.1504 + endloop + endfacet + facet normal 0.550755 -0.833866 0.0365604 + outer loop + vertex -444.831 88.7266 83.3079 + vertex -444.921 88.8355 87.1504 + vertex -447.224 87.129 82.9254 + endloop + endfacet + facet normal 0.532006 -0.845182 0.051353 + outer loop + vertex -447.224 87.129 82.9254 + vertex -444.921 88.8355 87.1504 + vertex -447.777 86.9921 86.4007 + endloop + endfacet + facet normal 0.540476 -0.841305 0.00954938 + outer loop + vertex -444.921 88.8355 87.1504 + vertex -444.875 88.9087 90.9951 + vertex -447.777 86.9921 86.4007 + endloop + endfacet + facet normal 0.526288 -0.850018 0.0221464 + outer loop + vertex -447.777 86.9921 86.4007 + vertex -444.875 88.9087 90.9951 + vertex -447.255 87.4298 90.798 + endloop + endfacet + facet normal 0.754258 -0.655671 -0.034496 + outer loop + vertex -437.703 95.6405 89.0749 + vertex -437.542 95.6265 92.865 + vertex -440.013 93.0199 88.3872 + endloop + endfacet + facet normal 0.743827 -0.668025 -0.0215486 + outer loop + vertex -440.013 93.0199 88.3872 + vertex -437.542 95.6265 92.865 + vertex -439.879 93.0467 92.1878 + endloop + endfacet + facet normal 0.758667 -0.651447 -0.00644733 + outer loop + vertex -437.751 95.6225 85.2837 + vertex -437.703 95.6405 89.0749 + vertex -440.037 92.9673 84.5702 + endloop + endfacet + facet normal 0.749655 -0.661814 0.00437396 + outer loop + vertex -440.037 92.9673 84.5702 + vertex -437.703 95.6405 89.0749 + vertex -440.013 93.0199 88.3872 + endloop + endfacet + facet normal 0.696571 -0.717467 0.00547708 + outer loop + vertex -440.037 92.9673 84.5702 + vertex -440.013 93.0199 88.3872 + vertex -442.381 90.6866 83.8812 + endloop + endfacet + facet normal 0.682155 -0.730933 0.0200257 + outer loop + vertex -442.381 90.6866 83.8812 + vertex -440.013 93.0199 88.3872 + vertex -442.401 90.7735 87.7342 + endloop + endfacet + facet normal 0.687853 -0.725597 -0.0191661 + outer loop + vertex -440.013 93.0199 88.3872 + vertex -439.879 93.0467 92.1878 + vertex -442.401 90.7735 87.7342 + endloop + endfacet + facet normal 0.675625 -0.737219 -0.0063091 + outer loop + vertex -442.401 90.7735 87.7342 + vertex -439.879 93.0467 92.1878 + vertex -442.313 90.821 91.5467 + endloop + endfacet + facet normal 0.842522 -0.536015 -0.05334 + outer loop + vertex -433.327 101.911 90.3377 + vertex -433.133 101.84 94.1107 + vertex -435.46 98.6173 89.7381 + endloop + endfacet + facet normal 0.83825 -0.543372 -0.045644 + outer loop + vertex -435.46 98.6173 89.7381 + vertex -433.133 101.84 94.1107 + vertex -435.281 98.5755 93.5192 + endloop + endfacet + facet normal 0.846045 -0.532435 -0.0268642 + outer loop + vertex -433.4 101.984 86.5649 + vertex -433.327 101.911 90.3377 + vertex -435.518 98.6498 85.9566 + endloop + endfacet + facet normal 0.840639 -0.541311 -0.0175533 + outer loop + vertex -435.518 98.6498 85.9566 + vertex -433.327 101.911 90.3377 + vertex -435.46 98.6173 89.7381 + endloop + endfacet + facet normal 0.806483 -0.591 -0.0174577 + outer loop + vertex -435.518 98.6498 85.9566 + vertex -435.46 98.6173 89.7381 + vertex -437.751 95.6225 85.2837 + endloop + endfacet + facet normal 0.799361 -0.600808 -0.00720011 + outer loop + vertex -437.751 95.6225 85.2837 + vertex -435.46 98.6173 89.7381 + vertex -437.703 95.6405 89.0749 + endloop + endfacet + facet normal 0.802562 -0.594905 -0.0445258 + outer loop + vertex -435.46 98.6173 89.7381 + vertex -435.281 98.5755 93.5192 + vertex -437.703 95.6405 89.0749 + endloop + endfacet + facet normal 0.796928 -0.602994 -0.0361141 + outer loop + vertex -437.703 95.6405 89.0749 + vertex -435.281 98.5755 93.5192 + vertex -437.542 95.6265 92.865 + endloop + endfacet + facet normal 0.882033 -0.469905 -0.034755 + outer loop + vertex -431.455 105.599 87.0761 + vertex -431.36 105.498 90.8306 + vertex -433.4 101.984 86.5649 + endloop + endfacet + facet normal 0.878105 -0.477737 -0.0264256 + outer loop + vertex -433.4 101.984 86.5649 + vertex -431.36 105.498 90.8306 + vertex -433.327 101.911 90.3377 + endloop + endfacet + facet normal 0.878765 -0.473219 -0.0619344 + outer loop + vertex -431.36 105.498 90.8306 + vertex -431.15 105.396 94.5936 + vertex -433.327 101.911 90.3377 + endloop + endfacet + facet normal 0.875216 -0.480711 -0.0539834 + outer loop + vertex -433.327 101.911 90.3377 + vertex -431.15 105.396 94.5936 + vertex -433.133 101.84 94.1107 + endloop + endfacet + facet normal 0.387019 -0.921535 0.0314697 + outer loop + vertex -450.948 85.3837 87.5583 + vertex -450.84 85.6853 95.0661 + vertex -455.728 83.3535 86.9016 + endloop + endfacet + facet normal 0.35443 -0.933499 0.0543981 + outer loop + vertex -455.728 83.3535 86.9016 + vertex -450.84 85.6853 95.0661 + vertex -456.048 83.6463 94.0081 + endloop + endfacet + facet normal 0.481015 -0.876695 0.00548197 + outer loop + vertex -447.255 87.4298 90.798 + vertex -447.611 87.2556 94.1737 + vertex -450.948 85.3837 87.5583 + endloop + endfacet + facet normal 0.436553 -0.899671 -0.00364476 + outer loop + vertex -446.903 87.5825 98.2807 + vertex -450.84 85.6853 95.0661 + vertex -447.611 87.2556 94.1737 + endloop + endfacet + facet normal 0.443788 -0.895642 0.0296174 + outer loop + vertex -450.84 85.6853 95.0661 + vertex -450.948 85.3837 87.5583 + vertex -447.611 87.2556 94.1737 + endloop + endfacet + facet normal 0.591133 -0.805398 -0.0435413 + outer loop + vertex -442.126 90.8436 95.3004 + vertex -441.843 90.8525 98.979 + vertex -444.723 88.9655 94.7788 + endloop + endfacet + facet normal 0.578895 -0.814816 -0.0309185 + outer loop + vertex -444.723 88.9655 94.7788 + vertex -441.843 90.8525 98.979 + vertex -444.467 89.007 98.4698 + endloop + endfacet + facet normal 0.601496 -0.798475 -0.025292 + outer loop + vertex -442.313 90.821 91.5467 + vertex -442.126 90.8436 95.3004 + vertex -444.875 88.9087 90.9951 + endloop + endfacet + facet normal 0.587438 -0.809187 -0.0114997 + outer loop + vertex -444.875 88.9087 90.9951 + vertex -442.126 90.8436 95.3004 + vertex -444.723 88.9655 94.7788 + endloop + endfacet + facet normal 0.52823 -0.849058 -0.00851704 + outer loop + vertex -444.875 88.9087 90.9951 + vertex -444.723 88.9655 94.7788 + vertex -447.255 87.4298 90.798 + endloop + endfacet + facet normal 0.507959 -0.861333 0.00911586 + outer loop + vertex -447.255 87.4298 90.798 + vertex -444.723 88.9655 94.7788 + vertex -447.611 87.2556 94.1737 + endloop + endfacet + facet normal 0.513234 -0.857858 -0.0258884 + outer loop + vertex -444.723 88.9655 94.7788 + vertex -444.467 89.007 98.4698 + vertex -447.611 87.2556 94.1737 + endloop + endfacet + facet normal 0.505762 -0.862474 -0.0185375 + outer loop + vertex -447.611 87.2556 94.1737 + vertex -444.467 89.007 98.4698 + vertex -446.903 87.5825 98.2807 + endloop + endfacet + facet normal 0.741452 -0.66663 -0.0765043 + outer loop + vertex -437.285 95.5995 96.6006 + vertex -436.946 95.5569 100.261 + vertex -439.652 93.0434 95.9302 + endloop + endfacet + facet normal 0.733422 -0.676591 -0.0657044 + outer loop + vertex -439.652 93.0434 95.9302 + vertex -436.946 95.5569 100.261 + vertex -439.339 93.0266 99.5988 + endloop + endfacet + facet normal 0.747318 -0.662083 -0.0562307 + outer loop + vertex -437.542 95.6265 92.865 + vertex -437.285 95.5995 96.6006 + vertex -439.879 93.0467 92.1878 + endloop + endfacet + facet normal 0.738819 -0.672382 -0.0452774 + outer loop + vertex -439.879 93.0467 92.1878 + vertex -437.285 95.5995 96.6006 + vertex -439.652 93.0434 95.9302 + endloop + endfacet + facet normal 0.680115 -0.731914 -0.0417784 + outer loop + vertex -439.879 93.0467 92.1878 + vertex -439.652 93.0434 95.9302 + vertex -442.313 90.821 91.5467 + endloop + endfacet + facet normal 0.668445 -0.743197 -0.0289741 + outer loop + vertex -442.313 90.821 91.5467 + vertex -439.652 93.0434 95.9302 + vertex -442.126 90.8436 95.3004 + endloop + endfacet + facet normal 0.671979 -0.738075 -0.0607426 + outer loop + vertex -439.652 93.0434 95.9302 + vertex -439.339 93.0266 99.5988 + vertex -442.126 90.8436 95.3004 + endloop + endfacet + facet normal 0.661848 -0.748027 -0.0491207 + outer loop + vertex -442.126 90.8436 95.3004 + vertex -439.339 93.0266 99.5988 + vertex -441.843 90.8525 98.979 + endloop + endfacet + facet normal 0.835535 -0.540305 -0.0997634 + outer loop + vertex -432.839 101.762 97.8307 + vertex -432.464 101.671 101.471 + vertex -435.004 98.5224 97.2477 + endloop + endfacet + facet normal 0.831764 -0.547421 -0.0921908 + outer loop + vertex -435.004 98.5224 97.2477 + vertex -432.464 101.671 101.471 + vertex -434.644 98.4535 100.899 + endloop + endfacet + facet normal 0.839222 -0.538229 -0.0775584 + outer loop + vertex -433.133 101.84 94.1107 + vertex -432.839 101.762 97.8307 + vertex -435.281 98.5755 93.5192 + endloop + endfacet + facet normal 0.835215 -0.545457 -0.0699464 + outer loop + vertex -435.281 98.5755 93.5192 + vertex -432.839 101.762 97.8307 + vertex -435.004 98.5224 97.2477 + endloop + endfacet + facet normal 0.798983 -0.597498 -0.0679896 + outer loop + vertex -435.281 98.5755 93.5192 + vertex -435.004 98.5224 97.2477 + vertex -437.542 95.6265 92.865 + endloop + endfacet + facet normal 0.793221 -0.606071 -0.0589869 + outer loop + vertex -437.542 95.6265 92.865 + vertex -435.004 98.5224 97.2477 + vertex -437.285 95.5995 96.6006 + endloop + endfacet + facet normal 0.794653 -0.600425 -0.0895381 + outer loop + vertex -435.004 98.5224 97.2477 + vertex -434.644 98.4535 100.899 + vertex -437.285 95.5995 96.6006 + endloop + endfacet + facet normal 0.78897 -0.60917 -0.0802403 + outer loop + vertex -437.285 95.5995 96.6006 + vertex -434.644 98.4535 100.899 + vertex -436.946 95.5569 100.261 + endloop + endfacet + facet normal 0.875065 -0.476212 -0.0865033 + outer loop + vertex -431.15 105.396 94.5936 + vertex -430.84 105.292 98.3071 + vertex -433.133 101.84 94.1107 + endloop + endfacet + facet normal 0.871909 -0.483256 -0.0789849 + outer loop + vertex -433.133 101.84 94.1107 + vertex -430.84 105.292 98.3071 + vertex -432.839 101.762 97.8307 + endloop + endfacet + facet normal 0.871206 -0.47902 -0.107419 + outer loop + vertex -430.84 105.292 98.3071 + vertex -430.452 105.185 101.931 + vertex -432.839 101.762 97.8307 + endloop + endfacet + facet normal 0.869007 -0.484214 -0.101803 + outer loop + vertex -432.839 101.762 97.8307 + vertex -430.452 105.185 101.931 + vertex -432.464 101.671 101.471 + endloop + endfacet + facet normal 0.364164 -0.931332 0.00230746 + outer loop + vertex -450.84 85.6853 95.0661 + vertex -450.386 85.8817 102.608 + vertex -456.048 83.6463 94.0081 + endloop + endfacet + facet normal 0.327053 -0.944524 0.0301725 + outer loop + vertex -456.048 83.6463 94.0081 + vertex -450.386 85.8817 102.608 + vertex -455.796 83.9845 101.863 + endloop + endfacet + facet normal 0.450613 -0.892365 -0.0251749 + outer loop + vertex -446.903 87.5825 98.2807 + vertex -447.095 87.3923 101.593 + vertex -450.84 85.6853 95.0661 + endloop + endfacet + facet normal 0.409475 -0.911841 -0.0295941 + outer loop + vertex -446.157 87.6794 105.732 + vertex -450.386 85.8817 102.608 + vertex -447.095 87.3923 101.593 + endloop + endfacet + facet normal 0.416839 -0.908979 -0.00145061 + outer loop + vertex -450.386 85.8817 102.608 + vertex -450.84 85.6853 95.0661 + vertex -447.095 87.3923 101.593 + endloop + endfacet + facet normal 0.572395 -0.816573 -0.074651 + outer loop + vertex -441.469 90.8494 102.614 + vertex -441.01 90.8366 106.276 + vertex -444.12 89.0353 102.13 + endloop + endfacet + facet normal 0.563169 -0.823814 -0.0645824 + outer loop + vertex -444.12 89.0353 102.13 + vertex -441.01 90.8366 106.276 + vertex -443.677 89.0489 105.826 + endloop + endfacet + facet normal 0.581932 -0.810988 -0.0604465 + outer loop + vertex -441.843 90.8525 98.979 + vertex -441.469 90.8494 102.614 + vertex -444.467 89.007 98.4698 + endloop + endfacet + facet normal 0.570001 -0.820259 -0.0476927 + outer loop + vertex -444.467 89.007 98.4698 + vertex -441.469 90.8494 102.614 + vertex -444.12 89.0353 102.13 + endloop + endfacet + facet normal 0.506736 -0.861108 -0.0413812 + outer loop + vertex -444.467 89.007 98.4698 + vertex -444.12 89.0353 102.13 + vertex -446.903 87.5825 98.2807 + endloop + endfacet + facet normal 0.4864 -0.873459 -0.0220181 + outer loop + vertex -446.903 87.5825 98.2807 + vertex -444.12 89.0353 102.13 + vertex -447.095 87.3923 101.593 + endloop + endfacet + facet normal 0.490409 -0.869712 -0.0556797 + outer loop + vertex -444.12 89.0353 102.13 + vertex -443.677 89.0489 105.826 + vertex -447.095 87.3923 101.593 + endloop + endfacet + facet normal 0.48425 -0.873545 -0.0492063 + outer loop + vertex -447.095 87.3923 101.593 + vertex -443.677 89.0489 105.826 + vertex -446.157 87.6794 105.732 + endloop + endfacet + facet normal 0.730357 -0.673515 -0.113823 + outer loop + vertex -436.53 95.5021 103.871 + vertex -436.036 95.4246 107.498 + vertex -438.944 92.9941 103.221 + endloop + endfacet + facet normal 0.723403 -0.682554 -0.103959 + outer loop + vertex -438.944 92.9941 103.221 + vertex -436.036 95.4246 107.498 + vertex -438.468 92.9444 106.86 + endloop + endfacet + facet normal 0.735467 -0.670874 -0.0949523 + outer loop + vertex -436.946 95.5569 100.261 + vertex -436.53 95.5021 103.871 + vertex -439.339 93.0266 99.5988 + endloop + endfacet + facet normal 0.728814 -0.67933 -0.085677 + outer loop + vertex -439.339 93.0266 99.5988 + vertex -436.53 95.5021 103.871 + vertex -438.944 92.9941 103.221 + endloop + endfacet + facet normal 0.664785 -0.742819 -0.0792552 + outer loop + vertex -439.339 93.0266 99.5988 + vertex -438.944 92.9941 103.221 + vertex -441.843 90.8525 98.979 + endloop + endfacet + facet normal 0.65525 -0.752352 -0.0679254 + outer loop + vertex -441.843 90.8525 98.979 + vertex -438.944 92.9941 103.221 + vertex -441.469 90.8494 102.614 + endloop + endfacet + facet normal 0.657642 -0.747158 -0.096238 + outer loop + vertex -438.944 92.9941 103.221 + vertex -438.468 92.9444 106.86 + vertex -441.469 90.8494 102.614 + endloop + endfacet + facet normal 0.647371 -0.757549 -0.0838508 + outer loop + vertex -441.469 90.8494 102.614 + vertex -438.468 92.9444 106.86 + vertex -441.01 90.8366 106.276 + endloop + endfacet + facet normal 0.826616 -0.545075 -0.139996 + outer loop + vertex -432.013 101.558 105.061 + vertex -431.487 101.431 108.662 + vertex -434.211 98.3696 104.498 + endloop + endfacet + facet normal 0.823307 -0.551826 -0.132866 + outer loop + vertex -434.211 98.3696 104.498 + vertex -431.487 101.431 108.662 + vertex -433.699 98.2621 108.112 + endloop + endfacet + facet normal 0.831522 -0.542056 -0.121433 + outer loop + vertex -432.464 101.671 101.471 + vertex -432.013 101.558 105.061 + vertex -434.644 98.4535 100.899 + endloop + endfacet + facet normal 0.827292 -0.550384 -0.112546 + outer loop + vertex -434.644 98.4535 100.899 + vertex -432.013 101.558 105.061 + vertex -434.211 98.3696 104.498 + endloop + endfacet + facet normal 0.789857 -0.603477 -0.109273 + outer loop + vertex -434.644 98.4535 100.899 + vertex -434.211 98.3696 104.498 + vertex -436.946 95.5569 100.261 + endloop + endfacet + facet normal 0.784212 -0.612433 -0.0996849 + outer loop + vertex -436.946 95.5569 100.261 + vertex -434.211 98.3696 104.498 + vertex -436.53 95.5021 103.871 + endloop + endfacet + facet normal 0.784647 -0.606369 -0.129019 + outer loop + vertex -434.211 98.3696 104.498 + vertex -433.699 98.2621 108.112 + vertex -436.53 95.5021 103.871 + endloop + endfacet + facet normal 0.778968 -0.615629 -0.119205 + outer loop + vertex -436.53 95.5021 103.871 + vertex -433.699 98.2621 108.112 + vertex -436.036 95.4246 107.498 + endloop + endfacet + facet normal 0.867779 -0.479984 -0.128746 + outer loop + vertex -430.452 105.185 101.931 + vertex -429.99 105.061 105.503 + vertex -432.464 101.671 101.471 + endloop + endfacet + facet normal 0.866022 -0.484397 -0.123958 + outer loop + vertex -432.464 101.671 101.471 + vertex -429.99 105.061 105.503 + vertex -432.013 101.558 105.061 + endloop + endfacet + facet normal 0.864331 -0.480201 -0.149459 + outer loop + vertex -429.99 105.061 105.503 + vertex -429.451 104.914 109.093 + vertex -432.013 101.558 105.061 + endloop + endfacet + facet normal 0.862089 -0.486134 -0.143097 + outer loop + vertex -432.013 101.558 105.061 + vertex -429.451 104.914 109.093 + vertex -431.487 101.431 108.662 + endloop + endfacet + facet normal 0.333249 -0.942634 -0.0196379 + outer loop + vertex -450.386 85.8817 102.608 + vertex -449.5 86.0315 110.451 + vertex -455.796 83.9845 101.863 + endloop + endfacet + facet normal 0.30128 -0.953514 0.00639315 + outer loop + vertex -455.796 83.9845 101.863 + vertex -449.5 86.0315 110.451 + vertex -455.05 84.2743 109.912 + endloop + endfacet + facet normal 0.421815 -0.905298 -0.0500653 + outer loop + vertex -446.157 87.6794 105.732 + vertex -446.184 87.474 109.213 + vertex -450.386 85.8817 102.608 + endloop + endfacet + facet normal 0.382252 -0.922631 -0.0513365 + outer loop + vertex -445.033 87.7101 113.54 + vertex -449.5 86.0315 110.451 + vertex -446.184 87.474 109.213 + endloop + endfacet + facet normal 0.39047 -0.920233 -0.0265294 + outer loop + vertex -449.5 86.0315 110.451 + vertex -450.386 85.8817 102.608 + vertex -446.184 87.474 109.213 + endloop + endfacet + facet normal 0.553873 -0.826534 -0.100333 + outer loop + vertex -440.466 90.7944 110.023 + vertex -439.841 90.7428 113.899 + vertex -443.148 89.0463 109.621 + endloop + endfacet + facet normal 0.545515 -0.833118 -0.0912611 + outer loop + vertex -443.148 89.0463 109.621 + vertex -439.841 90.7428 113.899 + vertex -442.531 89.0216 113.532 + endloop + endfacet + facet normal 0.565085 -0.819978 -0.0911924 + outer loop + vertex -441.01 90.8366 106.276 + vertex -440.466 90.7944 110.023 + vertex -443.677 89.0489 105.826 + endloop + endfacet + facet normal 0.552608 -0.829825 -0.0775515 + outer loop + vertex -443.677 89.0489 105.826 + vertex -440.466 90.7944 110.023 + vertex -443.148 89.0463 109.621 + endloop + endfacet + facet normal 0.484265 -0.87227 -0.068056 + outer loop + vertex -443.677 89.0489 105.826 + vertex -443.148 89.0463 109.621 + vertex -446.157 87.6794 105.732 + endloop + endfacet + facet normal 0.464425 -0.884284 -0.048487 + outer loop + vertex -446.157 87.6794 105.732 + vertex -443.148 89.0463 109.621 + vertex -446.184 87.474 109.213 + endloop + endfacet + facet normal 0.466759 -0.880836 -0.0791502 + outer loop + vertex -443.148 89.0463 109.621 + vertex -442.531 89.0216 113.532 + vertex -446.184 87.474 109.213 + endloop + endfacet + facet normal 0.462787 -0.883299 -0.0749083 + outer loop + vertex -446.184 87.474 109.213 + vertex -442.531 89.0216 113.532 + vertex -445.033 87.7101 113.54 + endloop + endfacet + facet normal 0.717274 -0.681847 -0.143536 + outer loop + vertex -435.461 95.3225 111.208 + vertex -434.803 95.2087 115.037 + vertex -437.91 92.8769 110.587 + endloop + endfacet + facet normal 0.710674 -0.690573 -0.134355 + outer loop + vertex -437.91 92.8769 110.587 + vertex -434.803 95.2087 115.037 + vertex -437.271 92.7868 114.432 + endloop + endfacet + facet normal 0.724513 -0.676728 -0.130841 + outer loop + vertex -436.036 95.4246 107.498 + vertex -435.461 95.3225 111.208 + vertex -438.468 92.9444 106.86 + endloop + endfacet + facet normal 0.716553 -0.687202 -0.119608 + outer loop + vertex -438.468 92.9444 106.86 + vertex -435.461 95.3225 111.208 + vertex -437.91 92.8769 110.587 + endloop + endfacet + facet normal 0.6493 -0.752428 -0.110732 + outer loop + vertex -438.468 92.9444 106.86 + vertex -437.91 92.8769 110.587 + vertex -441.01 90.8366 106.276 + endloop + endfacet + facet normal 0.64174 -0.760157 -0.101638 + outer loop + vertex -441.01 90.8366 106.276 + vertex -437.91 92.8769 110.587 + vertex -440.466 90.7944 110.023 + endloop + endfacet + facet normal 0.643087 -0.755581 -0.124641 + outer loop + vertex -437.91 92.8769 110.587 + vertex -437.271 92.7868 114.432 + vertex -440.466 90.7944 110.023 + endloop + endfacet + facet normal 0.632632 -0.766278 -0.112231 + outer loop + vertex -440.466 90.7944 110.023 + vertex -437.271 92.7868 114.432 + vertex -439.841 90.7428 113.899 + endloop + endfacet + facet normal 0.817157 -0.549764 -0.173247 + outer loop + vertex -430.878 101.286 112.346 + vertex -430.182 101.123 116.147 + vertex -433.107 98.1423 111.81 + endloop + endfacet + facet normal 0.813923 -0.556652 -0.166334 + outer loop + vertex -433.107 98.1423 111.81 + vertex -430.182 101.123 116.147 + vertex -432.428 97.9949 115.623 + endloop + endfacet + facet normal 0.822294 -0.546871 -0.157368 + outer loop + vertex -431.487 101.431 108.662 + vertex -430.878 101.286 112.346 + vertex -433.699 98.2621 108.112 + endloop + endfacet + facet normal 0.818489 -0.554823 -0.149152 + outer loop + vertex -433.699 98.2621 108.112 + vertex -430.878 101.286 112.346 + vertex -433.107 98.1423 111.81 + endloop + endfacet + facet normal 0.778984 -0.61014 -0.144612 + outer loop + vertex -433.699 98.2621 108.112 + vertex -433.107 98.1423 111.81 + vertex -436.036 95.4246 107.498 + endloop + endfacet + facet normal 0.774552 -0.617504 -0.13696 + outer loop + vertex -436.036 95.4246 107.498 + vertex -433.107 98.1423 111.81 + vertex -435.461 95.3225 111.208 + endloop + endfacet + facet normal 0.774211 -0.612001 -0.161408 + outer loop + vertex -433.107 98.1423 111.81 + vertex -432.428 97.9949 115.623 + vertex -435.461 95.3225 111.208 + endloop + endfacet + facet normal 0.767785 -0.622789 -0.150464 + outer loop + vertex -435.461 95.3225 111.208 + vertex -432.428 97.9949 115.623 + vertex -434.803 95.2087 115.037 + endloop + endfacet + facet normal 0.860162 -0.482129 -0.166353 + outer loop + vertex -429.451 104.914 109.093 + vertex -428.831 104.753 112.766 + vertex -431.487 101.431 108.662 + endloop + endfacet + facet normal 0.858285 -0.487271 -0.160975 + outer loop + vertex -431.487 101.431 108.662 + vertex -428.831 104.753 112.766 + vertex -430.878 101.286 112.346 + endloop + endfacet + facet normal 0.856045 -0.483222 -0.183532 + outer loop + vertex -428.831 104.753 112.766 + vertex -428.121 104.57 116.557 + vertex -430.878 101.286 112.346 + endloop + endfacet + facet normal 0.853883 -0.489311 -0.177367 + outer loop + vertex -430.878 101.286 112.346 + vertex -428.121 104.57 116.557 + vertex -430.182 101.123 116.147 + endloop + endfacet + facet normal 0.304968 -0.951612 -0.0378082 + outer loop + vertex -449.5 86.0315 110.451 + vertex -448.265 86.1081 118.48 + vertex -455.05 84.2743 109.912 + endloop + endfacet + facet normal 0.276754 -0.960846 -0.0134885 + outer loop + vertex -455.05 84.2743 109.912 + vertex -448.265 86.1081 118.48 + vertex -453.905 84.4903 117.998 + endloop + endfacet + facet normal 0.392333 -0.917243 -0.068842 + outer loop + vertex -445.033 87.7101 113.54 + vertex -444.925 87.483 117.182 + vertex -449.5 86.0315 110.451 + endloop + endfacet + facet normal 0.357148 -0.931589 -0.0677221 + outer loop + vertex -443.617 87.663 121.602 + vertex -448.265 86.1081 118.48 + vertex -444.925 87.483 117.182 + endloop + endfacet + facet normal 0.364488 -0.930013 -0.0471643 + outer loop + vertex -448.265 86.1081 118.48 + vertex -449.5 86.0315 110.451 + vertex -444.925 87.483 117.182 + endloop + endfacet + facet normal 0.535097 -0.836153 -0.120495 + outer loop + vertex -439.139 90.66 117.868 + vertex -438.373 90.5706 121.892 + vertex -441.844 88.9775 117.533 + endloop + endfacet + facet normal 0.526483 -0.842885 -0.111175 + outer loop + vertex -441.844 88.9775 117.533 + vertex -438.373 90.5706 121.892 + vertex -441.092 88.9144 121.572 + endloop + endfacet + facet normal 0.546434 -0.829709 -0.113985 + outer loop + vertex -439.841 90.7428 113.899 + vertex -439.139 90.66 117.868 + vertex -442.531 89.0216 113.532 + endloop + endfacet + facet normal 0.534519 -0.839085 -0.101123 + outer loop + vertex -442.531 89.0216 113.532 + vertex -439.139 90.66 117.868 + vertex -441.844 88.9775 117.533 + endloop + endfacet + facet normal 0.462206 -0.882278 -0.0891699 + outer loop + vertex -442.531 89.0216 113.532 + vertex -441.844 88.9775 117.533 + vertex -445.033 87.7101 113.54 + endloop + endfacet + facet normal 0.441681 -0.894523 -0.0688889 + outer loop + vertex -445.033 87.7101 113.54 + vertex -441.844 88.9775 117.533 + vertex -444.925 87.483 117.182 + endloop + endfacet + facet normal 0.443214 -0.891214 -0.0964285 + outer loop + vertex -441.844 88.9775 117.533 + vertex -441.092 88.9144 121.572 + vertex -444.925 87.483 117.182 + endloop + endfacet + facet normal 0.441087 -0.892512 -0.0941483 + outer loop + vertex -444.925 87.483 117.182 + vertex -441.092 88.9144 121.572 + vertex -443.617 87.663 121.602 + endloop + endfacet + facet normal 0.702853 -0.691038 -0.168715 + outer loop + vertex -434.064 95.0681 118.966 + vertex -433.255 94.9207 122.94 + vertex -436.553 92.6798 118.38 + endloop + endfacet + facet normal 0.695583 -0.700696 -0.15871 + outer loop + vertex -436.553 92.6798 118.38 + vertex -433.255 94.9207 122.94 + vertex -435.766 92.5553 122.377 + endloop + endfacet + facet normal 0.711106 -0.685037 -0.158278 + outer loop + vertex -434.803 95.2087 115.037 + vertex -434.064 95.0681 118.966 + vertex -437.271 92.7868 114.432 + endloop + endfacet + facet normal 0.702663 -0.696243 -0.146666 + outer loop + vertex -437.271 92.7868 114.432 + vertex -434.064 95.0681 118.966 + vertex -436.553 92.6798 118.38 + endloop + endfacet + facet normal 0.633751 -0.761506 -0.135901 + outer loop + vertex -437.271 92.7868 114.432 + vertex -436.553 92.6798 118.38 + vertex -439.841 90.7428 113.899 + endloop + endfacet + facet normal 0.626023 -0.769425 -0.126808 + outer loop + vertex -439.841 90.7428 113.899 + vertex -436.553 92.6798 118.38 + vertex -439.139 90.66 117.868 + endloop + endfacet + facet normal 0.626752 -0.765194 -0.147175 + outer loop + vertex -436.553 92.6798 118.38 + vertex -435.766 92.5553 122.377 + vertex -439.139 90.66 117.868 + endloop + endfacet + facet normal 0.616058 -0.776119 -0.134582 + outer loop + vertex -439.139 90.66 117.868 + vertex -435.766 92.5553 122.377 + vertex -438.373 90.5706 121.892 + endloop + endfacet + facet normal 0.806124 -0.556306 -0.201713 + outer loop + vertex -429.402 100.937 120.045 + vertex -428.551 100.742 123.982 + vertex -431.668 97.8376 119.535 + endloop + endfacet + facet normal 0.802788 -0.563615 -0.194601 + outer loop + vertex -431.668 97.8376 119.535 + vertex -428.551 100.742 123.982 + vertex -430.836 97.6577 123.491 + endloop + endfacet + facet normal 0.812343 -0.551731 -0.18892 + outer loop + vertex -430.182 101.123 116.147 + vertex -429.402 100.937 120.045 + vertex -432.428 97.9949 115.623 + endloop + endfacet + facet normal 0.807924 -0.561267 -0.179551 + outer loop + vertex -432.428 97.9949 115.623 + vertex -429.402 100.937 120.045 + vertex -431.668 97.8376 119.535 + endloop + endfacet + facet normal 0.767209 -0.617374 -0.173896 + outer loop + vertex -432.428 97.9949 115.623 + vertex -431.668 97.8376 119.535 + vertex -434.803 95.2087 115.037 + endloop + endfacet + facet normal 0.762404 -0.625502 -0.165796 + outer loop + vertex -434.803 95.2087 115.037 + vertex -431.668 97.8376 119.535 + vertex -434.064 95.0681 118.966 + endloop + endfacet + facet normal 0.761547 -0.620095 -0.188489 + outer loop + vertex -431.668 97.8376 119.535 + vertex -430.836 97.6577 123.491 + vertex -434.064 95.0681 118.966 + endloop + endfacet + facet normal 0.754794 -0.631606 -0.177084 + outer loop + vertex -434.064 95.0681 118.966 + vertex -430.836 97.6577 123.491 + vertex -433.255 94.9207 122.94 + endloop + endfacet + facet normal 0.851341 -0.485148 -0.199625 + outer loop + vertex -428.121 104.57 116.557 + vertex -427.326 104.366 120.445 + vertex -430.182 101.123 116.147 + endloop + endfacet + facet normal 0.849156 -0.491451 -0.193417 + outer loop + vertex -430.182 101.123 116.147 + vertex -427.326 104.366 120.445 + vertex -429.402 100.937 120.045 + endloop + endfacet + facet normal 0.846689 -0.4877 -0.212759 + outer loop + vertex -427.326 104.366 120.445 + vertex -426.462 104.155 124.368 + vertex -429.402 100.937 120.045 + endloop + endfacet + facet normal 0.844671 -0.493664 -0.206947 + outer loop + vertex -429.402 100.937 120.045 + vertex -426.462 104.155 124.368 + vertex -428.551 100.742 123.982 + endloop + endfacet + facet normal 0.279344 -0.958862 -0.0505006 + outer loop + vertex -448.265 86.1081 118.48 + vertex -446.797 86.1121 126.526 + vertex -453.905 84.4903 117.998 + endloop + endfacet + facet normal 0.254565 -0.96664 -0.0283676 + outer loop + vertex -453.905 84.4903 117.998 + vertex -446.797 86.1121 126.526 + vertex -452.526 84.6154 126.118 + endloop + endfacet + facet normal 0.36601 -0.926879 -0.0832594 + outer loop + vertex -443.617 87.663 121.602 + vertex -443.431 87.4102 125.238 + vertex -448.265 86.1081 118.48 + endloop + endfacet + facet normal 0.332317 -0.939881 -0.0786668 + outer loop + vertex -442.023 87.5422 129.607 + vertex -446.797 86.1121 126.526 + vertex -443.431 87.4102 125.238 + endloop + endfacet + facet normal 0.33859 -0.938934 -0.0613206 + outer loop + vertex -446.797 86.1121 126.526 + vertex -448.265 86.1081 118.48 + vertex -443.431 87.4102 125.238 + endloop + endfacet + facet normal 0.514916 -0.845945 -0.138706 + outer loop + vertex -437.554 90.4553 125.896 + vertex -436.692 90.3307 129.854 + vertex -440.296 88.836 125.591 + endloop + endfacet + facet normal 0.504291 -0.854168 -0.12684 + outer loop + vertex -440.296 88.836 125.591 + vertex -436.692 90.3307 129.854 + vertex -439.459 88.7399 129.565 + endloop + endfacet + facet normal 0.526928 -0.839605 -0.131948 + outer loop + vertex -438.373 90.5706 121.892 + vertex -437.554 90.4553 125.896 + vertex -441.092 88.9144 121.572 + endloop + endfacet + facet normal 0.51459 -0.849219 -0.118427 + outer loop + vertex -441.092 88.9144 121.572 + vertex -437.554 90.4553 125.896 + vertex -440.296 88.836 125.591 + endloop + endfacet + facet normal 0.440523 -0.891627 -0.104593 + outer loop + vertex -441.092 88.9144 121.572 + vertex -440.296 88.836 125.591 + vertex -443.617 87.663 121.602 + endloop + endfacet + facet normal 0.420451 -0.903379 -0.0844237 + outer loop + vertex -443.617 87.663 121.602 + vertex -440.296 88.836 125.591 + vertex -443.431 87.4102 125.238 + endloop + endfacet + facet normal 0.421818 -0.899912 -0.110578 + outer loop + vertex -440.296 88.836 125.591 + vertex -439.459 88.7399 129.565 + vertex -443.431 87.4102 125.238 + endloop + endfacet + facet normal 0.419369 -0.901383 -0.107878 + outer loop + vertex -443.431 87.4102 125.238 + vertex -439.459 88.7399 129.565 + vertex -442.023 87.5422 129.607 + endloop + endfacet + facet normal 0.687438 -0.700438 -0.191874 + outer loop + vertex -432.389 94.7557 126.899 + vertex -431.475 94.5811 130.81 + vertex -434.925 92.4145 126.36 + endloop + endfacet + facet normal 0.679135 -0.7116 -0.180003 + outer loop + vertex -434.925 92.4145 126.36 + vertex -431.475 94.5811 130.81 + vertex -434.037 92.2659 130.295 + endloop + endfacet + facet normal 0.695522 -0.695283 -0.181193 + outer loop + vertex -433.255 94.9207 122.94 + vertex -432.389 94.7557 126.899 + vertex -435.766 92.5553 122.377 + endloop + endfacet + facet normal 0.687724 -0.705717 -0.170291 + outer loop + vertex -435.766 92.5553 122.377 + vertex -432.389 94.7557 126.899 + vertex -434.925 92.4145 126.36 + endloop + endfacet + facet normal 0.616665 -0.771291 -0.15759 + outer loop + vertex -435.766 92.5553 122.377 + vertex -434.925 92.4145 126.36 + vertex -438.373 90.5706 121.892 + endloop + endfacet + facet normal 0.607582 -0.780583 -0.146746 + outer loop + vertex -438.373 90.5706 121.892 + vertex -434.925 92.4145 126.36 + vertex -437.554 90.4553 125.896 + endloop + endfacet + facet normal 0.607912 -0.776375 -0.166388 + outer loop + vertex -434.925 92.4145 126.36 + vertex -434.037 92.2659 130.295 + vertex -437.554 90.4553 125.896 + endloop + endfacet + facet normal 0.598607 -0.785897 -0.155031 + outer loop + vertex -437.554 90.4553 125.896 + vertex -434.037 92.2659 130.295 + vertex -436.692 90.3307 129.854 + endloop + endfacet + facet normal 0.794895 -0.56174 -0.229323 + outer loop + vertex -427.643 100.537 127.9 + vertex -426.684 100.314 131.774 + vertex -429.946 97.4709 127.429 + endloop + endfacet + facet normal 0.790451 -0.571909 -0.219331 + outer loop + vertex -429.946 97.4709 127.429 + vertex -426.684 100.314 131.774 + vertex -429.009 97.2751 131.318 + endloop + endfacet + facet normal 0.800882 -0.558992 -0.214746 + outer loop + vertex -428.551 100.742 123.982 + vertex -427.643 100.537 127.9 + vertex -430.836 97.6577 123.491 + endloop + endfacet + facet normal 0.797308 -0.566991 -0.206934 + outer loop + vertex -430.836 97.6577 123.491 + vertex -427.643 100.537 127.9 + vertex -429.946 97.4709 127.429 + endloop + endfacet + facet normal 0.753718 -0.62606 -0.199893 + outer loop + vertex -430.836 97.6577 123.491 + vertex -429.946 97.4709 127.429 + vertex -433.255 94.9207 122.94 + endloop + endfacet + facet normal 0.748071 -0.635774 -0.190213 + outer loop + vertex -433.255 94.9207 122.94 + vertex -429.946 97.4709 127.429 + vertex -432.389 94.7557 126.899 + endloop + endfacet + facet normal 0.746804 -0.630431 -0.211756 + outer loop + vertex -429.946 97.4709 127.429 + vertex -429.009 97.2751 131.318 + vertex -432.389 94.7557 126.899 + endloop + endfacet + facet normal 0.741102 -0.640369 -0.201729 + outer loop + vertex -432.389 94.7557 126.899 + vertex -429.009 97.2751 131.318 + vertex -431.475 94.5811 130.81 + endloop + endfacet + facet normal 0.841779 -0.489583 -0.227413 + outer loop + vertex -426.462 104.155 124.368 + vertex -425.538 103.93 128.273 + vertex -428.551 100.742 123.982 + endloop + endfacet + facet normal 0.839426 -0.496767 -0.220422 + outer loop + vertex -428.551 100.742 123.982 + vertex -425.538 103.93 128.273 + vertex -427.643 100.537 127.9 + endloop + endfacet + facet normal 0.836205 -0.492471 -0.241318 + outer loop + vertex -425.538 103.93 128.273 + vertex -424.564 103.694 132.129 + vertex -427.643 100.537 127.9 + endloop + endfacet + facet normal 0.834309 -0.498493 -0.235443 + outer loop + vertex -427.643 100.537 127.9 + vertex -424.564 103.694 132.129 + vertex -426.684 100.314 131.774 + endloop + endfacet + facet normal 0.256403 -0.964601 -0.0616575 + outer loop + vertex -446.797 86.1121 126.526 + vertex -445.175 86.0287 134.574 + vertex -452.526 84.6154 126.118 + endloop + endfacet + facet normal 0.232546 -0.971774 -0.0397203 + outer loop + vertex -452.526 84.6154 126.118 + vertex -445.175 86.0287 134.574 + vertex -451.007 84.6442 134.306 + endloop + endfacet + facet normal 0.340953 -0.935354 -0.094151 + outer loop + vertex -442.023 87.5422 129.607 + vertex -441.776 87.2703 133.202 + vertex -446.797 86.1121 126.526 + endloop + endfacet + facet normal 0.310117 -0.94659 -0.0882849 + outer loop + vertex -440.274 87.3577 137.541 + vertex -445.175 86.0287 134.574 + vertex -441.776 87.2703 133.202 + endloop + endfacet + facet normal 0.315874 -0.945954 -0.0734487 + outer loop + vertex -445.175 86.0287 134.574 + vertex -446.797 86.1121 126.526 + vertex -441.776 87.2703 133.202 + endloop + endfacet + facet normal 0.495245 -0.855069 -0.153589 + outer loop + vertex -435.79 90.1992 133.769 + vertex -434.842 90.0477 137.67 + vertex -438.585 88.6282 133.503 + endloop + endfacet + facet normal 0.484221 -0.863543 -0.140799 + outer loop + vertex -438.585 88.6282 133.503 + vertex -434.842 90.0477 137.67 + vertex -437.667 88.5023 137.434 + endloop + endfacet + facet normal 0.504462 -0.851205 -0.144801 + outer loop + vertex -436.692 90.3307 129.854 + vertex -435.79 90.1992 133.769 + vertex -439.459 88.7399 129.565 + endloop + endfacet + facet normal 0.495237 -0.858318 -0.134281 + outer loop + vertex -439.459 88.7399 129.565 + vertex -435.79 90.1992 133.769 + vertex -438.585 88.6282 133.503 + endloop + endfacet + facet normal 0.418712 -0.900356 -0.11849 + outer loop + vertex -439.459 88.7399 129.565 + vertex -438.585 88.6282 133.503 + vertex -442.023 87.5422 129.607 + endloop + endfacet + facet normal 0.397422 -0.912569 -0.0962997 + outer loop + vertex -442.023 87.5422 129.607 + vertex -438.585 88.6282 133.503 + vertex -441.776 87.2703 133.202 + endloop + endfacet + facet normal 0.398372 -0.909048 -0.122195 + outer loop + vertex -438.585 88.6282 133.503 + vertex -437.667 88.5023 137.434 + vertex -441.776 87.2703 133.202 + endloop + endfacet + facet normal 0.395045 -0.911 -0.118398 + outer loop + vertex -441.776 87.2703 133.202 + vertex -437.667 88.5023 137.434 + vertex -440.274 87.3577 137.541 + endloop + endfacet + facet normal 0.66992 -0.711784 -0.211117 + outer loop + vertex -430.516 94.3948 134.677 + vertex -429.509 94.1993 138.532 + vertex -433.106 92.1034 134.185 + endloop + endfacet + facet normal 0.662297 -0.7221 -0.199835 + outer loop + vertex -433.106 92.1034 134.185 + vertex -429.509 94.1993 138.532 + vertex -432.127 91.9285 138.061 + endloop + endfacet + facet normal 0.678624 -0.70609 -0.202252 + outer loop + vertex -431.475 94.5811 130.81 + vertex -430.516 94.3948 134.677 + vertex -434.037 92.2659 130.295 + endloop + endfacet + facet normal 0.670581 -0.716956 -0.19051 + outer loop + vertex -434.037 92.2659 130.295 + vertex -430.516 94.3948 134.677 + vertex -433.106 92.1034 134.185 + endloop + endfacet + facet normal 0.598775 -0.781339 -0.176007 + outer loop + vertex -434.037 92.2659 130.295 + vertex -433.106 92.1034 134.185 + vertex -436.692 90.3307 129.854 + endloop + endfacet + facet normal 0.587511 -0.79284 -0.161974 + outer loop + vertex -436.692 90.3307 129.854 + vertex -433.106 92.1034 134.185 + vertex -435.79 90.1992 133.769 + endloop + endfacet + facet normal 0.587508 -0.78804 -0.183924 + outer loop + vertex -433.106 92.1034 134.185 + vertex -432.127 91.9285 138.061 + vertex -435.79 90.1992 133.769 + endloop + endfacet + facet normal 0.57759 -0.798132 -0.171393 + outer loop + vertex -435.79 90.1992 133.769 + vertex -432.127 91.9285 138.061 + vertex -434.842 90.0477 137.67 + endloop + endfacet + facet normal 0.78191 -0.570928 -0.250314 + outer loop + vertex -425.681 100.092 135.601 + vertex -424.628 99.8603 139.42 + vertex -428.026 97.0715 135.164 + endloop + endfacet + facet normal 0.778864 -0.578141 -0.243155 + outer loop + vertex -428.026 97.0715 135.164 + vertex -424.628 99.8603 139.42 + vertex -426.993 96.8505 139 + endloop + endfacet + facet normal 0.788095 -0.567099 -0.239384 + outer loop + vertex -426.684 100.314 131.774 + vertex -425.681 100.092 135.601 + vertex -429.009 97.2751 131.318 + endloop + endfacet + facet normal 0.784405 -0.575679 -0.230874 + outer loop + vertex -429.009 97.2751 131.318 + vertex -425.681 100.092 135.601 + vertex -428.026 97.0715 135.164 + endloop + endfacet + facet normal 0.739654 -0.635111 -0.222587 + outer loop + vertex -429.009 97.2751 131.318 + vertex -428.026 97.0715 135.164 + vertex -431.475 94.5811 130.81 + endloop + endfacet + facet normal 0.734395 -0.644398 -0.213109 + outer loop + vertex -431.475 94.5811 130.81 + vertex -428.026 97.0715 135.164 + vertex -430.516 94.3948 134.677 + endloop + endfacet + facet normal 0.732697 -0.638981 -0.234221 + outer loop + vertex -428.026 97.0715 135.164 + vertex -426.993 96.8505 139 + vertex -430.516 94.3948 134.677 + endloop + endfacet + facet normal 0.726413 -0.650159 -0.22275 + outer loop + vertex -430.516 94.3948 134.677 + vertex -426.993 96.8505 139 + vertex -429.509 94.1993 138.532 + endloop + endfacet + facet normal 0.831382 -0.494825 -0.252888 + outer loop + vertex -424.564 103.694 132.129 + vertex -423.547 103.456 135.939 + vertex -426.684 100.314 131.774 + endloop + endfacet + facet normal 0.829369 -0.501441 -0.246382 + outer loop + vertex -426.684 100.314 131.774 + vertex -423.547 103.456 135.939 + vertex -425.681 100.092 135.601 + endloop + endfacet + facet normal 0.826005 -0.497423 -0.265117 + outer loop + vertex -423.547 103.456 135.939 + vertex -422.476 103.206 139.744 + vertex -425.681 100.092 135.601 + endloop + endfacet + facet normal 0.823813 -0.504816 -0.257863 + outer loop + vertex -425.681 100.092 135.601 + vertex -422.476 103.206 139.744 + vertex -424.628 99.8603 139.42 + endloop + endfacet + facet normal 0.23347 -0.96986 -0.0697404 + outer loop + vertex -445.175 86.0287 134.574 + vertex -443.397 85.8735 142.687 + vertex -451.007 84.6442 134.306 + endloop + endfacet + facet normal 0.210934 -0.976305 -0.04833 + outer loop + vertex -451.007 84.6442 134.306 + vertex -443.397 85.8735 142.687 + vertex -449.358 84.5923 142.552 + endloop + endfacet + facet normal 0.318405 -0.942241 -0.103925 + outer loop + vertex -440.274 87.3577 137.541 + vertex -439.957 87.0634 141.181 + vertex -445.175 86.0287 134.574 + endloop + endfacet + facet normal 0.287011 -0.95296 -0.0974222 + outer loop + vertex -438.341 87.1009 145.574 + vertex -443.397 85.8735 142.687 + vertex -439.957 87.0634 141.181 + endloop + endfacet + facet normal 0.293345 -0.952437 -0.0825349 + outer loop + vertex -443.397 85.8735 142.687 + vertex -445.175 86.0287 134.574 + vertex -439.957 87.0634 141.181 + endloop + endfacet + facet normal 0.471 -0.866543 -0.16511 + outer loop + vertex -433.842 89.8806 141.593 + vertex -432.787 89.6986 145.559 + vertex -436.701 88.3651 141.393 + endloop + endfacet + facet normal 0.460679 -0.874292 -0.152934 + outer loop + vertex -436.701 88.3651 141.393 + vertex -432.787 89.6986 145.559 + vertex -435.679 88.2043 145.39 + endloop + endfacet + facet normal 0.484045 -0.860285 -0.160031 + outer loop + vertex -434.842 90.0477 137.67 + vertex -433.842 89.8806 141.593 + vertex -437.667 88.5023 137.434 + endloop + endfacet + facet normal 0.471385 -0.869892 -0.145203 + outer loop + vertex -437.667 88.5023 137.434 + vertex -433.842 89.8806 141.593 + vertex -436.701 88.3651 141.393 + endloop + endfacet + facet normal 0.394256 -0.910075 -0.127771 + outer loop + vertex -437.667 88.5023 137.434 + vertex -436.701 88.3651 141.393 + vertex -440.274 87.3577 137.541 + endloop + endfacet + facet normal 0.375033 -0.9208 -0.107131 + outer loop + vertex -440.274 87.3577 137.541 + vertex -436.701 88.3651 141.393 + vertex -439.957 87.0634 141.181 + endloop + endfacet + facet normal 0.375315 -0.917328 -0.132844 + outer loop + vertex -436.701 88.3651 141.393 + vertex -435.679 88.2043 145.39 + vertex -439.957 87.0634 141.181 + endloop + endfacet + facet normal 0.372008 -0.919226 -0.128968 + outer loop + vertex -439.957 87.0634 141.181 + vertex -435.679 88.2043 145.39 + vertex -438.341 87.1009 145.574 + endloop + endfacet + facet normal 0.652297 -0.722941 -0.227739 + outer loop + vertex -428.447 93.9904 142.41 + vertex -427.326 93.7659 146.335 + vertex -431.095 91.7426 141.961 + endloop + endfacet + facet normal 0.643971 -0.7341 -0.215402 + outer loop + vertex -431.095 91.7426 141.961 + vertex -427.326 93.7659 146.335 + vertex -430.006 91.5411 145.905 + endloop + endfacet + facet normal 0.661486 -0.717034 -0.219769 + outer loop + vertex -429.509 94.1993 138.532 + vertex -428.447 93.9904 142.41 + vertex -432.127 91.9285 138.061 + endloop + endfacet + facet normal 0.65327 -0.728119 -0.207562 + outer loop + vertex -432.127 91.9285 138.061 + vertex -428.447 93.9904 142.41 + vertex -431.095 91.7426 141.961 + endloop + endfacet + facet normal 0.577416 -0.793884 -0.190627 + outer loop + vertex -432.127 91.9285 138.061 + vertex -431.095 91.7426 141.961 + vertex -434.842 90.0477 137.67 + endloop + endfacet + facet normal 0.568346 -0.803064 -0.179081 + outer loop + vertex -434.842 90.0477 137.67 + vertex -431.095 91.7426 141.961 + vertex -433.842 89.8806 141.593 + endloop + endfacet + facet normal 0.568028 -0.798903 -0.197733 + outer loop + vertex -431.095 91.7426 141.961 + vertex -430.006 91.5411 145.905 + vertex -433.842 89.8806 141.593 + endloop + endfacet + facet normal 0.558659 -0.808325 -0.18577 + outer loop + vertex -433.842 89.8806 141.593 + vertex -430.006 91.5411 145.905 + vertex -432.787 89.6986 145.559 + endloop + endfacet + facet normal 0.769355 -0.578352 -0.271298 + outer loop + vertex -423.515 99.6133 143.266 + vertex -422.339 99.3514 147.159 + vertex -425.905 96.6247 142.86 + endloop + endfacet + facet normal 0.765341 -0.587934 -0.26189 + outer loop + vertex -425.905 96.6247 142.86 + vertex -422.339 99.3514 147.159 + vertex -424.754 96.3816 146.768 + endloop + endfacet + facet normal 0.776318 -0.573603 -0.261361 + outer loop + vertex -424.628 99.8603 139.42 + vertex -423.515 99.6133 143.266 + vertex -426.993 96.8505 139 + endloop + endfacet + facet normal 0.772246 -0.583317 -0.25175 + outer loop + vertex -426.993 96.8505 139 + vertex -423.515 99.6133 143.266 + vertex -425.905 96.6247 142.86 + endloop + endfacet + facet normal 0.724722 -0.645156 -0.241973 + outer loop + vertex -426.993 96.8505 139 + vertex -425.905 96.6247 142.86 + vertex -429.509 94.1993 138.532 + endloop + endfacet + facet normal 0.719417 -0.654593 -0.232268 + outer loop + vertex -429.509 94.1993 138.532 + vertex -425.905 96.6247 142.86 + vertex -428.447 93.9904 142.41 + endloop + endfacet + facet normal 0.717539 -0.64947 -0.251647 + outer loop + vertex -425.905 96.6247 142.86 + vertex -424.754 96.3816 146.768 + vertex -428.447 93.9904 142.41 + endloop + endfacet + facet normal 0.711762 -0.65974 -0.241117 + outer loop + vertex -428.447 93.9904 142.41 + vertex -424.754 96.3816 146.768 + vertex -427.326 93.7659 146.335 + endloop + endfacet + facet normal 0.820441 -0.500931 -0.27558 + outer loop + vertex -422.476 103.206 139.744 + vertex -421.346 102.948 143.577 + vertex -424.628 99.8603 139.42 + endloop + endfacet + facet normal 0.818567 -0.507357 -0.269327 + outer loop + vertex -424.628 99.8603 139.42 + vertex -421.346 102.948 143.577 + vertex -423.515 99.6133 143.266 + endloop + endfacet + facet normal 0.815247 -0.503659 -0.285833 + outer loop + vertex -421.346 102.948 143.577 + vertex -420.153 102.679 147.456 + vertex -423.515 99.6133 143.266 + endloop + endfacet + facet normal 0.813508 -0.509703 -0.280015 + outer loop + vertex -423.515 99.6133 143.266 + vertex -420.153 102.679 147.456 + vertex -422.339 99.3514 147.159 + endloop + endfacet + facet normal 0.211178 -0.974363 -0.0775939 + outer loop + vertex -443.397 85.8735 142.687 + vertex -441.46 85.641 150.878 + vertex -449.358 84.5923 142.552 + endloop + endfacet + facet normal 0.191188 -0.979842 -0.0579426 + outer loop + vertex -449.358 84.5923 142.552 + vertex -441.46 85.641 150.878 + vertex -447.591 84.4468 150.842 + endloop + endfacet + facet normal 0.294804 -0.948876 -0.112805 + outer loop + vertex -438.341 87.1009 145.574 + vertex -437.949 86.7804 149.295 + vertex -443.397 85.8735 142.687 + endloop + endfacet + facet normal 0.263663 -0.958838 -0.10541 + outer loop + vertex -436.222 86.7678 153.73 + vertex -441.46 85.641 150.878 + vertex -437.949 86.7804 149.295 + endloop + endfacet + facet normal 0.270034 -0.958535 -0.09106 + outer loop + vertex -441.46 85.641 150.878 + vertex -443.397 85.8735 142.687 + vertex -437.949 86.7804 149.295 + endloop + endfacet + facet normal 0.448558 -0.876653 -0.173998 + outer loop + vertex -431.676 89.5019 149.574 + vertex -430.516 89.2925 153.618 + vertex -434.606 88.0301 149.434 + endloop + endfacet + facet normal 0.439712 -0.883152 -0.163389 + outer loop + vertex -434.606 88.0301 149.434 + vertex -430.516 89.2925 153.618 + vertex -433.485 87.8359 153.501 + endloop + endfacet + facet normal 0.460179 -0.871393 -0.170031 + outer loop + vertex -432.787 89.6986 145.559 + vertex -431.676 89.5019 149.574 + vertex -435.679 88.2043 145.39 + endloop + endfacet + facet normal 0.449195 -0.879532 -0.156996 + outer loop + vertex -435.679 88.2043 145.39 + vertex -431.676 89.5019 149.574 + vertex -434.606 88.0301 149.434 + endloop + endfacet + facet normal 0.371018 -0.918325 -0.137934 + outer loop + vertex -435.679 88.2043 145.39 + vertex -434.606 88.0301 149.434 + vertex -438.341 87.1009 145.574 + endloop + endfacet + facet normal 0.352046 -0.928629 -0.117098 + outer loop + vertex -438.341 87.1009 145.574 + vertex -434.606 88.0301 149.434 + vertex -437.949 86.7804 149.295 + endloop + endfacet + facet normal 0.351828 -0.925357 -0.141178 + outer loop + vertex -434.606 88.0301 149.434 + vertex -433.485 87.8359 153.501 + vertex -437.949 86.7804 149.295 + endloop + endfacet + facet normal 0.349953 -0.926409 -0.138924 + outer loop + vertex -437.949 86.7804 149.295 + vertex -433.485 87.8359 153.501 + vertex -436.222 86.7678 153.73 + endloop + endfacet + facet normal 0.634328 -0.733778 -0.243305 + outer loop + vertex -426.146 93.5311 150.307 + vertex -424.913 93.2711 154.304 + vertex -428.859 91.3223 149.896 + endloop + endfacet + facet normal 0.625236 -0.745823 -0.229844 + outer loop + vertex -428.859 91.3223 149.896 + vertex -424.913 93.2711 154.304 + vertex -427.662 91.0875 153.914 + endloop + endfacet + facet normal 0.642951 -0.729263 -0.234072 + outer loop + vertex -427.326 93.7659 146.335 + vertex -426.146 93.5311 150.307 + vertex -430.006 91.5411 145.905 + endloop + endfacet + facet normal 0.635585 -0.739069 -0.22318 + outer loop + vertex -430.006 91.5411 145.905 + vertex -426.146 93.5311 150.307 + vertex -428.859 91.3223 149.896 + endloop + endfacet + facet normal 0.558198 -0.804109 -0.204508 + outer loop + vertex -430.006 91.5411 145.905 + vertex -428.859 91.3223 149.896 + vertex -432.787 89.6986 145.559 + endloop + endfacet + facet normal 0.548065 -0.814208 -0.191549 + outer loop + vertex -432.787 89.6986 145.559 + vertex -428.859 91.3223 149.896 + vertex -431.676 89.5019 149.574 + endloop + endfacet + facet normal 0.547463 -0.809943 -0.210421 + outer loop + vertex -428.859 91.3223 149.896 + vertex -427.662 91.0875 153.914 + vertex -431.676 89.5019 149.574 + endloop + endfacet + facet normal 0.53648 -0.820763 -0.19631 + outer loop + vertex -431.676 89.5019 149.574 + vertex -427.662 91.0875 153.914 + vertex -430.516 89.2925 153.618 + endloop + endfacet + facet normal 0.756227 -0.586915 -0.289225 + outer loop + vertex -421.104 99.0831 151.096 + vertex -419.812 98.7948 155.06 + vertex -423.544 96.1243 150.722 + endloop + endfacet + facet normal 0.751838 -0.597417 -0.278984 + outer loop + vertex -423.544 96.1243 150.722 + vertex -419.812 98.7948 155.06 + vertex -422.281 95.8553 154.702 + endloop + endfacet + facet normal 0.762677 -0.583521 -0.278974 + outer loop + vertex -422.339 99.3514 147.159 + vertex -421.104 99.0831 151.096 + vertex -424.754 96.3816 146.768 + endloop + endfacet + facet normal 0.759246 -0.59171 -0.270969 + outer loop + vertex -424.754 96.3816 146.768 + vertex -421.104 99.0831 151.096 + vertex -423.544 96.1243 150.722 + endloop + endfacet + facet normal 0.709797 -0.654696 -0.259925 + outer loop + vertex -424.754 96.3816 146.768 + vertex -423.544 96.1243 150.722 + vertex -427.326 93.7659 146.335 + endloop + endfacet + facet normal 0.703371 -0.666053 -0.24828 + outer loop + vertex -427.326 93.7659 146.335 + vertex -423.544 96.1243 150.722 + vertex -426.146 93.5311 150.307 + endloop + endfacet + facet normal 0.701273 -0.660911 -0.267231 + outer loop + vertex -423.544 96.1243 150.722 + vertex -422.281 95.8553 154.702 + vertex -426.146 93.5311 150.307 + endloop + endfacet + facet normal 0.696322 -0.669659 -0.258249 + outer loop + vertex -426.146 93.5311 150.307 + vertex -422.281 95.8553 154.702 + vertex -424.913 93.2711 154.304 + endloop + endfacet + facet normal 0.809859 -0.505771 -0.297194 + outer loop + vertex -420.153 102.679 147.456 + vertex -418.892 102.388 151.383 + vertex -422.339 99.3514 147.159 + endloop + endfacet + facet normal 0.807177 -0.515135 -0.288273 + outer loop + vertex -422.339 99.3514 147.159 + vertex -418.892 102.388 151.383 + vertex -421.104 99.0831 151.096 + endloop + endfacet + facet normal 0.803392 -0.511106 -0.305503 + outer loop + vertex -418.892 102.388 151.383 + vertex -417.579 102.092 155.333 + vertex -421.104 99.0831 151.096 + endloop + endfacet + facet normal 0.801421 -0.518028 -0.298949 + outer loop + vertex -421.104 99.0831 151.096 + vertex -417.579 102.092 155.333 + vertex -419.812 98.7948 155.06 + endloop + endfacet + facet normal 0.19096 -0.977832 -0.0858979 + outer loop + vertex -441.46 85.641 150.878 + vertex -439.389 85.325 159.078 + vertex -447.591 84.4468 150.842 + endloop + endfacet + facet normal 0.172221 -0.982797 -0.0667076 + outer loop + vertex -447.591 84.4468 150.842 + vertex -439.389 85.325 159.078 + vertex -445.699 84.2157 159.132 + endloop + endfacet + facet normal 0.270702 -0.955182 -0.119781 + outer loop + vertex -436.222 86.7678 153.73 + vertex -435.779 86.4259 157.457 + vertex -441.46 85.641 150.878 + endloop + endfacet + facet normal 0.24312 -0.963411 -0.112838 + outer loop + vertex -433.964 86.3687 161.856 + vertex -439.389 85.325 159.078 + vertex -435.779 86.4259 157.457 + endloop + endfacet + facet normal 0.248882 -0.963361 -0.0999655 + outer loop + vertex -439.389 85.325 159.078 + vertex -441.46 85.641 150.878 + vertex -435.779 86.4259 157.457 + endloop + endfacet + facet normal 0.425999 -0.886084 -0.182699 + outer loop + vertex -429.318 89.0571 157.656 + vertex -428.091 88.8191 161.671 + vertex -432.332 87.6274 157.561 + endloop + endfacet + facet normal 0.417913 -0.891929 -0.172659 + outer loop + vertex -432.332 87.6274 157.561 + vertex -428.091 88.8191 161.671 + vertex -431.147 87.4019 161.594 + endloop + endfacet + facet normal 0.438884 -0.880001 -0.1816 + outer loop + vertex -430.516 89.2925 153.618 + vertex -429.318 89.0571 157.656 + vertex -433.485 87.8359 153.501 + endloop + endfacet + facet normal 0.426799 -0.888815 -0.166885 + outer loop + vertex -433.485 87.8359 153.501 + vertex -429.318 89.0571 157.656 + vertex -432.332 87.6274 157.561 + endloop + endfacet + facet normal 0.348982 -0.925581 -0.14667 + outer loop + vertex -433.485 87.8359 153.501 + vertex -432.332 87.6274 157.561 + vertex -436.222 86.7678 153.73 + endloop + endfacet + facet normal 0.329903 -0.935699 -0.125027 + outer loop + vertex -436.222 86.7678 153.73 + vertex -432.332 87.6274 157.561 + vertex -435.779 86.4259 157.457 + endloop + endfacet + facet normal 0.329455 -0.932352 -0.148926 + outer loop + vertex -432.332 87.6274 157.561 + vertex -431.147 87.4019 161.594 + vertex -435.779 86.4259 157.457 + endloop + endfacet + facet normal 0.328422 -0.932922 -0.147635 + outer loop + vertex -435.779 86.4259 157.457 + vertex -431.147 87.4019 161.594 + vertex -433.964 86.3687 161.856 + endloop + endfacet + facet normal 0.615304 -0.745668 -0.255695 + outer loop + vertex -423.641 93.01 158.3 + vertex -422.335 92.7265 162.27 + vertex -426.425 90.8394 157.931 + endloop + endfacet + facet normal 0.606469 -0.757283 -0.242317 + outer loop + vertex -426.425 90.8394 157.931 + vertex -422.335 92.7265 162.27 + vertex -425.157 90.5779 161.922 + endloop + endfacet + facet normal 0.624065 -0.741247 -0.247176 + outer loop + vertex -424.913 93.2711 154.304 + vertex -423.641 93.01 158.3 + vertex -427.662 91.0875 153.914 + endloop + endfacet + facet normal 0.616766 -0.750848 -0.236278 + outer loop + vertex -427.662 91.0875 153.914 + vertex -423.641 93.01 158.3 + vertex -426.425 90.8394 157.931 + endloop + endfacet + facet normal 0.535742 -0.816451 -0.215381 + outer loop + vertex -427.662 91.0875 153.914 + vertex -426.425 90.8394 157.931 + vertex -430.516 89.2925 153.618 + endloop + endfacet + facet normal 0.527509 -0.824526 -0.204674 + outer loop + vertex -430.516 89.2925 153.618 + vertex -426.425 90.8394 157.931 + vertex -429.318 89.0571 157.656 + endloop + endfacet + facet normal 0.526749 -0.820751 -0.221143 + outer loop + vertex -426.425 90.8394 157.931 + vertex -425.157 90.5779 161.922 + vertex -429.318 89.0571 157.656 + endloop + endfacet + facet normal 0.51602 -0.8312 -0.206956 + outer loop + vertex -429.318 89.0571 157.656 + vertex -425.157 90.5779 161.922 + vertex -428.091 88.8191 161.671 + endloop + endfacet + facet normal 0.741901 -0.59679 -0.305655 + outer loop + vertex -418.479 98.5014 159.018 + vertex -417.109 98.1904 162.951 + vertex -420.975 95.5732 158.677 + endloop + endfacet + facet normal 0.737402 -0.607667 -0.294924 + outer loop + vertex -420.975 95.5732 158.677 + vertex -417.109 98.1904 162.951 + vertex -419.636 95.2806 162.627 + endloop + endfacet + facet normal 0.748885 -0.592842 -0.29616 + outer loop + vertex -419.812 98.7948 155.06 + vertex -418.479 98.5014 159.018 + vertex -422.281 95.8553 154.702 + endloop + endfacet + facet normal 0.745191 -0.601706 -0.287472 + outer loop + vertex -422.281 95.8553 154.702 + vertex -418.479 98.5014 159.018 + vertex -420.975 95.5732 158.677 + endloop + endfacet + facet normal 0.694293 -0.664981 -0.275242 + outer loop + vertex -422.281 95.8553 154.702 + vertex -420.975 95.5732 158.677 + vertex -424.913 93.2711 154.304 + endloop + endfacet + facet normal 0.687723 -0.676573 -0.263223 + outer loop + vertex -424.913 93.2711 154.304 + vertex -420.975 95.5732 158.677 + vertex -423.641 93.01 158.3 + endloop + endfacet + facet normal 0.685376 -0.671364 -0.282013 + outer loop + vertex -420.975 95.5732 158.677 + vertex -419.636 95.2806 162.627 + vertex -423.641 93.01 158.3 + endloop + endfacet + facet normal 0.680189 -0.680547 -0.272394 + outer loop + vertex -423.641 93.01 158.3 + vertex -419.636 95.2806 162.627 + vertex -422.335 92.7265 162.27 + endloop + endfacet + facet normal 0.797678 -0.514145 -0.315223 + outer loop + vertex -417.579 102.092 155.333 + vertex -416.22 101.781 159.279 + vertex -419.812 98.7948 155.06 + endloop + endfacet + facet normal 0.795106 -0.52328 -0.306568 + outer loop + vertex -419.812 98.7948 155.06 + vertex -416.22 101.781 159.279 + vertex -418.479 98.5014 159.018 + endloop + endfacet + facet normal 0.791195 -0.51927 -0.323063 + outer loop + vertex -416.22 101.781 159.279 + vertex -414.828 101.465 163.195 + vertex -418.479 98.5014 159.018 + endloop + endfacet + facet normal 0.789311 -0.526084 -0.316582 + outer loop + vertex -418.479 98.5014 159.018 + vertex -414.828 101.465 163.195 + vertex -417.109 98.1904 162.951 + endloop + endfacet + facet normal 0.171628 -0.980716 -0.0934852 + outer loop + vertex -439.389 85.325 159.078 + vertex -437.198 84.9304 167.241 + vertex -445.699 84.2157 159.132 + endloop + endfacet + facet normal 0.156357 -0.984685 -0.0771265 + outer loop + vertex -445.699 84.2157 159.132 + vertex -437.198 84.9304 167.241 + vertex -443.71 83.8832 167.409 + endloop + endfacet + facet normal 0.250112 -0.959735 -0.127875 + outer loop + vertex -433.964 86.3687 161.856 + vertex -433.486 85.9995 165.562 + vertex -439.389 85.325 159.078 + endloop + endfacet + facet normal 0.224328 -0.96711 -0.119898 + outer loop + vertex -431.589 85.8986 169.925 + vertex -437.198 84.9304 167.241 + vertex -433.486 85.9995 165.562 + endloop + endfacet + facet normal 0.229568 -0.967238 -0.108391 + outer loop + vertex -437.198 84.9304 167.241 + vertex -439.389 85.325 159.078 + vertex -433.486 85.9995 165.562 + endloop + endfacet + facet normal 0.406397 -0.892756 -0.194493 + outer loop + vertex -426.834 88.5593 165.656 + vertex -425.546 88.281 169.625 + vertex -429.935 87.1584 165.606 + endloop + endfacet + facet normal 0.396512 -0.899867 -0.18171 + outer loop + vertex -429.935 87.1584 165.606 + vertex -425.546 88.281 169.625 + vertex -428.69 86.899 169.608 + endloop + endfacet + facet normal 0.416956 -0.888964 -0.189448 + outer loop + vertex -428.091 88.8191 161.671 + vertex -426.834 88.5593 165.656 + vertex -431.147 87.4019 161.594 + endloop + endfacet + facet normal 0.4075 -0.895797 -0.177458 + outer loop + vertex -431.147 87.4019 161.594 + vertex -426.834 88.5593 165.656 + vertex -429.935 87.1584 165.606 + endloop + endfacet + facet normal 0.327367 -0.932022 -0.155451 + outer loop + vertex -431.147 87.4019 161.594 + vertex -429.935 87.1584 165.606 + vertex -433.964 86.3687 161.856 + endloop + endfacet + facet normal 0.308975 -0.94163 -0.133668 + outer loop + vertex -433.964 86.3687 161.856 + vertex -429.935 87.1584 165.606 + vertex -433.486 85.9995 165.562 + endloop + endfacet + facet normal 0.308183 -0.938329 -0.156723 + outer loop + vertex -429.935 87.1584 165.606 + vertex -428.69 86.899 169.608 + vertex -433.486 85.9995 165.562 + endloop + endfacet + facet normal 0.307018 -0.938964 -0.1552 + outer loop + vertex -433.486 85.9995 165.562 + vertex -428.69 86.899 169.608 + vertex -431.589 85.8986 169.925 + endloop + endfacet + facet normal 0.596332 -0.756362 -0.268896 + outer loop + vertex -420.999 92.4398 166.212 + vertex -419.628 92.126 170.134 + vertex -423.858 90.3014 165.884 + endloop + endfacet + facet normal 0.586606 -0.769094 -0.253749 + outer loop + vertex -423.858 90.3014 165.884 + vertex -419.628 92.126 170.134 + vertex -422.529 90.0138 169.83 + endloop + endfacet + facet normal 0.605054 -0.752586 -0.259855 + outer loop + vertex -422.335 92.7265 162.27 + vertex -420.999 92.4398 166.212 + vertex -425.157 90.5779 161.922 + endloop + endfacet + facet normal 0.598082 -0.761731 -0.249127 + outer loop + vertex -425.157 90.5779 161.922 + vertex -420.999 92.4398 166.212 + vertex -423.858 90.3014 165.884 + endloop + endfacet + facet normal 0.515013 -0.826731 -0.226445 + outer loop + vertex -425.157 90.5779 161.922 + vertex -423.858 90.3014 165.884 + vertex -428.091 88.8191 161.671 + endloop + endfacet + facet normal 0.505748 -0.835723 -0.213976 + outer loop + vertex -428.091 88.8191 161.671 + vertex -423.858 90.3014 165.884 + vertex -426.834 88.5593 165.656 + endloop + endfacet + facet normal 0.504766 -0.831845 -0.230746 + outer loop + vertex -423.858 90.3014 165.884 + vertex -422.529 90.0138 169.83 + vertex -426.834 88.5593 165.656 + endloop + endfacet + facet normal 0.497039 -0.839332 -0.220167 + outer loop + vertex -426.834 88.5593 165.656 + vertex -422.529 90.0138 169.83 + vertex -425.546 88.281 169.625 + endloop + endfacet + facet normal 0.726448 -0.607365 -0.321529 + outer loop + vertex -415.706 97.8687 166.855 + vertex -414.267 97.5337 170.74 + vertex -418.264 94.9711 166.55 + endloop + endfacet + facet normal 0.72222 -0.617717 -0.311165 + outer loop + vertex -418.264 94.9711 166.55 + vertex -414.267 97.5337 170.74 + vertex -416.857 94.6498 170.453 + endloop + endfacet + facet normal 0.733944 -0.602612 -0.313345 + outer loop + vertex -417.109 98.1904 162.951 + vertex -415.706 97.8687 166.855 + vertex -419.636 95.2806 162.627 + endloop + endfacet + facet normal 0.729948 -0.612336 -0.303679 + outer loop + vertex -419.636 95.2806 162.627 + vertex -415.706 97.8687 166.855 + vertex -418.264 94.9711 166.55 + endloop + endfacet + facet normal 0.677779 -0.675484 -0.290408 + outer loop + vertex -419.636 95.2806 162.627 + vertex -418.264 94.9711 166.55 + vertex -422.335 92.7265 162.27 + endloop + endfacet + facet normal 0.670891 -0.687697 -0.27745 + outer loop + vertex -422.335 92.7265 162.27 + vertex -418.264 94.9711 166.55 + vertex -420.999 92.4398 166.212 + endloop + endfacet + facet normal 0.668176 -0.682156 -0.296991 + outer loop + vertex -418.264 94.9711 166.55 + vertex -416.857 94.6498 170.453 + vertex -420.999 92.4398 166.212 + endloop + endfacet + facet normal 0.662914 -0.691512 -0.286978 + outer loop + vertex -420.999 92.4398 166.212 + vertex -416.857 94.6498 170.453 + vertex -419.628 92.126 170.134 + endloop + endfacet + facet normal 0.785297 -0.522082 -0.332774 + outer loop + vertex -414.828 101.465 163.195 + vertex -413.401 101.134 167.083 + vertex -417.109 98.1904 162.951 + endloop + endfacet + facet normal 0.783108 -0.530179 -0.32504 + outer loop + vertex -417.109 98.1904 162.951 + vertex -413.401 101.134 167.083 + vertex -415.706 97.8687 166.855 + endloop + endfacet + facet normal 0.778745 -0.525918 -0.342005 + outer loop + vertex -413.401 101.134 167.083 + vertex -411.935 100.789 170.951 + vertex -415.706 97.8687 166.855 + endloop + endfacet + facet normal 0.776463 -0.534506 -0.333779 + outer loop + vertex -415.706 97.8687 166.855 + vertex -411.935 100.789 170.951 + vertex -414.267 97.5337 170.74 + endloop + endfacet + facet normal 0.155372 -0.982569 -0.10207 + outer loop + vertex -437.198 84.9304 167.241 + vertex -434.909 84.4507 175.343 + vertex -443.71 83.8832 167.409 + endloop + endfacet + facet normal 0.141441 -0.986173 -0.0863592 + outer loop + vertex -443.71 83.8832 167.409 + vertex -434.909 84.4507 175.343 + vertex -441.622 83.4641 175.615 + endloop + endfacet + facet normal 0.231705 -0.963127 -0.136747 + outer loop + vertex -431.589 85.8986 169.925 + vertex -431.079 85.4974 173.615 + vertex -437.198 84.9304 167.241 + endloop + endfacet + facet normal 0.20707 -0.969846 -0.128532 + outer loop + vertex -429.114 85.3462 177.922 + vertex -434.909 84.4507 175.343 + vertex -431.079 85.4974 173.615 + endloop + endfacet + facet normal 0.212184 -0.970154 -0.117384 + outer loop + vertex -434.909 84.4507 175.343 + vertex -437.198 84.9304 167.241 + vertex -431.079 85.4974 173.615 + endloop + endfacet + facet normal 0.384631 -0.900801 -0.201535 + outer loop + vertex -424.227 87.9879 173.586 + vertex -422.883 87.6799 177.527 + vertex -427.419 86.6221 173.598 + endloop + endfacet + facet normal 0.375965 -0.906973 -0.189868 + outer loop + vertex -427.419 86.6221 173.598 + vertex -422.883 87.6799 177.527 + vertex -426.124 86.3292 177.562 + endloop + endfacet + facet normal 0.39532 -0.896952 -0.197987 + outer loop + vertex -425.546 88.281 169.625 + vertex -424.227 87.9879 173.586 + vertex -428.69 86.899 169.608 + endloop + endfacet + facet normal 0.385919 -0.90367 -0.185601 + outer loop + vertex -428.69 86.899 169.608 + vertex -424.227 87.9879 173.586 + vertex -427.419 86.6221 173.598 + endloop + endfacet + facet normal 0.305914 -0.938087 -0.162512 + outer loop + vertex -428.69 86.899 169.608 + vertex -427.419 86.6221 173.598 + vertex -431.589 85.8986 169.925 + endloop + endfacet + facet normal 0.290126 -0.946247 -0.142981 + outer loop + vertex -431.589 85.8986 169.925 + vertex -427.419 86.6221 173.598 + vertex -431.079 85.4974 173.615 + endloop + endfacet + facet normal 0.289072 -0.94313 -0.164144 + outer loop + vertex -427.419 86.6221 173.598 + vertex -426.124 86.3292 177.562 + vertex -431.079 85.4974 173.615 + endloop + endfacet + facet normal 0.290006 -0.942619 -0.165424 + outer loop + vertex -431.079 85.4974 173.615 + vertex -426.124 86.3292 177.562 + vertex -429.114 85.3462 177.922 + endloop + endfacet + facet normal 0.576152 -0.768754 -0.277609 + outer loop + vertex -418.225 91.8048 174.045 + vertex -416.794 91.4717 177.936 + vertex -421.167 89.7018 173.763 + endloop + endfacet + facet normal 0.568562 -0.77863 -0.265468 + outer loop + vertex -421.167 89.7018 173.763 + vertex -416.794 91.4717 177.936 + vertex -419.778 89.3809 177.679 + endloop + endfacet + facet normal 0.584852 -0.763967 -0.272585 + outer loop + vertex -419.628 92.126 170.134 + vertex -418.225 91.8048 174.045 + vertex -422.529 90.0138 169.83 + endloop + endfacet + facet normal 0.577776 -0.773191 -0.26144 + outer loop + vertex -422.529 90.0138 169.83 + vertex -418.225 91.8048 174.045 + vertex -421.167 89.7018 173.763 + endloop + endfacet + facet normal 0.495851 -0.835164 -0.237977 + outer loop + vertex -422.529 90.0138 169.83 + vertex -421.167 89.7018 173.763 + vertex -425.546 88.281 169.625 + endloop + endfacet + facet normal 0.486027 -0.844665 -0.224317 + outer loop + vertex -425.546 88.281 169.625 + vertex -421.167 89.7018 173.763 + vertex -424.227 87.9879 173.586 + endloop + endfacet + facet normal 0.484817 -0.840796 -0.240862 + outer loop + vertex -421.167 89.7018 173.763 + vertex -419.778 89.3809 177.679 + vertex -424.227 87.9879 173.586 + endloop + endfacet + facet normal 0.476229 -0.849055 -0.228716 + outer loop + vertex -424.227 87.9879 173.586 + vertex -419.778 89.3809 177.679 + vertex -422.883 87.6799 177.527 + endloop + endfacet + facet normal 0.712226 -0.61759 -0.333643 + outer loop + vertex -412.795 97.1962 174.608 + vertex -411.293 96.8519 178.451 + vertex -415.417 94.3165 174.342 + endloop + endfacet + facet normal 0.70894 -0.625766 -0.325301 + outer loop + vertex -415.417 94.3165 174.342 + vertex -411.293 96.8519 178.451 + vertex -413.947 93.9715 178.21 + endloop + endfacet + facet normal 0.718992 -0.613231 -0.327104 + outer loop + vertex -414.267 97.5337 170.74 + vertex -412.795 97.1962 174.608 + vertex -416.857 94.6498 170.453 + endloop + endfacet + facet normal 0.715452 -0.621942 -0.318303 + outer loop + vertex -416.857 94.6498 170.453 + vertex -412.795 97.1962 174.608 + vertex -415.417 94.3165 174.342 + endloop + endfacet + facet normal 0.660489 -0.686761 -0.303502 + outer loop + vertex -416.857 94.6498 170.453 + vertex -415.417 94.3165 174.342 + vertex -419.628 92.126 170.134 + endloop + endfacet + facet normal 0.654584 -0.697269 -0.292121 + outer loop + vertex -419.628 92.126 170.134 + vertex -415.417 94.3165 174.342 + vertex -418.225 91.8048 174.045 + endloop + endfacet + facet normal 0.65192 -0.692227 -0.309553 + outer loop + vertex -415.417 94.3165 174.342 + vertex -413.947 93.9715 178.21 + vertex -418.225 91.8048 174.045 + endloop + endfacet + facet normal 0.645799 -0.703121 -0.297598 + outer loop + vertex -418.225 91.8048 174.045 + vertex -413.947 93.9715 178.21 + vertex -416.794 91.4717 177.936 + endloop + endfacet + facet normal 0.77263 -0.530827 -0.348233 + outer loop + vertex -411.935 100.789 170.951 + vertex -410.437 100.446 174.799 + vertex -414.267 97.5337 170.74 + endloop + endfacet + facet normal 0.770449 -0.539129 -0.340218 + outer loop + vertex -414.267 97.5337 170.74 + vertex -410.437 100.446 174.799 + vertex -412.795 97.1962 174.608 + endloop + endfacet + facet normal 0.766643 -0.535545 -0.35419 + outer loop + vertex -410.437 100.446 174.799 + vertex -408.911 100.103 178.621 + vertex -412.795 97.1962 174.608 + endloop + endfacet + facet normal 0.764867 -0.542434 -0.347482 + outer loop + vertex -412.795 97.1962 174.608 + vertex -408.911 100.103 178.621 + vertex -411.293 96.8519 178.451 + endloop + endfacet + facet normal 0.140126 -0.983933 -0.110633 + outer loop + vertex -434.909 84.4507 175.343 + vertex -432.542 83.8874 183.35 + vertex -441.622 83.4641 175.615 + endloop + endfacet + facet normal 0.128896 -0.986874 -0.0972897 + outer loop + vertex -441.622 83.4641 175.615 + vertex -432.542 83.8874 183.35 + vertex -439.47 82.9439 183.742 + endloop + endfacet + facet normal 0.213176 -0.966427 -0.143442 + outer loop + vertex -429.114 85.3462 177.922 + vertex -428.589 84.9208 181.568 + vertex -434.909 84.4507 175.343 + endloop + endfacet + facet normal 0.192186 -0.971727 -0.137155 + outer loop + vertex -426.563 84.7236 185.804 + vertex -432.542 83.8874 183.35 + vertex -428.589 84.9208 181.568 + endloop + endfacet + facet normal 0.197047 -0.972181 -0.126633 + outer loop + vertex -432.542 83.8874 183.35 + vertex -434.909 84.4507 175.343 + vertex -428.589 84.9208 181.568 + endloop + endfacet + facet normal 0.364845 -0.907266 -0.209179 + outer loop + vertex -421.519 87.3516 181.431 + vertex -420.137 87.0142 185.305 + vertex -424.812 86.0136 181.492 + endloop + endfacet + facet normal 0.358293 -0.911953 -0.199918 + outer loop + vertex -424.812 86.0136 181.492 + vertex -420.137 87.0142 185.305 + vertex -423.478 85.683 185.391 + endloop + endfacet + facet normal 0.374488 -0.903874 -0.206811 + outer loop + vertex -422.883 87.6799 177.527 + vertex -421.519 87.3516 181.431 + vertex -426.124 86.3292 177.562 + endloop + endfacet + facet normal 0.366142 -0.909833 -0.195306 + outer loop + vertex -426.124 86.3292 177.562 + vertex -421.519 87.3516 181.431 + vertex -424.812 86.0136 181.492 + endloop + endfacet + facet normal 0.288922 -0.941758 -0.172091 + outer loop + vertex -426.124 86.3292 177.562 + vertex -424.812 86.0136 181.492 + vertex -429.114 85.3462 177.922 + endloop + endfacet + facet normal 0.271991 -0.950529 -0.15005 + outer loop + vertex -429.114 85.3462 177.922 + vertex -424.812 86.0136 181.492 + vertex -428.589 84.9208 181.568 + endloop + endfacet + facet normal 0.270528 -0.947064 -0.172869 + outer loop + vertex -424.812 86.0136 181.492 + vertex -423.478 85.683 185.391 + vertex -428.589 84.9208 181.568 + endloop + endfacet + facet normal 0.271138 -0.946728 -0.173752 + outer loop + vertex -428.589 84.9208 181.568 + vertex -423.478 85.683 185.391 + vertex -426.563 84.7236 185.804 + endloop + endfacet + facet normal 0.557312 -0.778614 -0.288381 + outer loop + vertex -415.34 91.1213 181.796 + vertex -413.865 90.7606 185.619 + vertex -418.367 89.041 181.563 + endloop + endfacet + facet normal 0.550481 -0.78755 -0.277013 + outer loop + vertex -418.367 89.041 181.563 + vertex -413.865 90.7606 185.619 + vertex -416.936 88.6876 185.41 + endloop + endfacet + facet normal 0.566607 -0.773593 -0.283744 + outer loop + vertex -416.794 91.4717 177.936 + vertex -415.34 91.1213 181.796 + vertex -419.778 89.3809 177.679 + endloop + endfacet + facet normal 0.559208 -0.783245 -0.271688 + outer loop + vertex -419.778 89.3809 177.679 + vertex -415.34 91.1213 181.796 + vertex -418.367 89.041 181.563 + endloop + endfacet + facet normal 0.474811 -0.844885 -0.246422 + outer loop + vertex -419.778 89.3809 177.679 + vertex -418.367 89.041 181.563 + vertex -422.883 87.6799 177.527 + endloop + endfacet + facet normal 0.466713 -0.852691 -0.234726 + outer loop + vertex -422.883 87.6799 177.527 + vertex -418.367 89.041 181.563 + vertex -421.519 87.3516 181.431 + endloop + endfacet + facet normal 0.465314 -0.84882 -0.250974 + outer loop + vertex -418.367 89.041 181.563 + vertex -416.936 88.6876 185.41 + vertex -421.519 87.3516 181.431 + endloop + endfacet + facet normal 0.456127 -0.857659 -0.237423 + outer loop + vertex -421.519 87.3516 181.431 + vertex -416.936 88.6876 185.41 + vertex -420.137 87.0142 185.305 + endloop + endfacet + facet normal 0.698735 -0.625702 -0.346794 + outer loop + vertex -409.768 96.5009 182.26 + vertex -408.221 96.1387 186.029 + vertex -412.454 93.6211 182.043 + endloop + endfacet + facet normal 0.695226 -0.634686 -0.337394 + outer loop + vertex -412.454 93.6211 182.043 + vertex -408.221 96.1387 186.029 + vertex -410.942 93.2601 185.838 + endloop + endfacet + facet normal 0.705737 -0.621587 -0.339949 + outer loop + vertex -411.293 96.8519 178.451 + vertex -409.768 96.5009 182.26 + vertex -413.947 93.9715 178.21 + endloop + endfacet + facet normal 0.702313 -0.630224 -0.331021 + outer loop + vertex -413.947 93.9715 178.21 + vertex -409.768 96.5009 182.26 + vertex -412.454 93.6211 182.043 + endloop + endfacet + facet normal 0.643159 -0.698294 -0.314216 + outer loop + vertex -413.947 93.9715 178.21 + vertex -412.454 93.6211 182.043 + vertex -416.794 91.4717 177.936 + endloop + endfacet + facet normal 0.638404 -0.706807 -0.304736 + outer loop + vertex -416.794 91.4717 177.936 + vertex -412.454 93.6211 182.043 + vertex -415.34 91.1213 181.796 + endloop + endfacet + facet normal 0.635824 -0.702302 -0.320154 + outer loop + vertex -412.454 93.6211 182.043 + vertex -410.942 93.2601 185.838 + vertex -415.34 91.1213 181.796 + endloop + endfacet + facet normal 0.631073 -0.710898 -0.310437 + outer loop + vertex -415.34 91.1213 181.796 + vertex -410.942 93.2601 185.838 + vertex -413.865 90.7606 185.619 + endloop + endfacet + facet normal 0.760397 -0.538333 -0.36331 + outer loop + vertex -408.911 100.103 178.621 + vertex -407.354 99.743 182.413 + vertex -411.293 96.8519 178.451 + endloop + endfacet + facet normal 0.758026 -0.547742 -0.354085 + outer loop + vertex -411.293 96.8519 178.451 + vertex -407.354 99.743 182.413 + vertex -409.768 96.5009 182.26 + endloop + endfacet + facet normal 0.753649 -0.543766 -0.369232 + outer loop + vertex -407.354 99.743 182.413 + vertex -405.781 99.3749 186.164 + vertex -409.768 96.5009 182.26 + endloop + endfacet + facet normal 0.751688 -0.551679 -0.361406 + outer loop + vertex -409.768 96.5009 182.26 + vertex -405.781 99.3749 186.164 + vertex -408.221 96.1387 186.029 + endloop + endfacet + facet normal 0.127287 -0.984564 -0.120133 + outer loop + vertex -432.542 83.8874 183.35 + vertex -430.109 83.2372 191.257 + vertex -439.47 82.9439 183.742 + endloop + endfacet + facet normal 0.118142 -0.987035 -0.108645 + outer loop + vertex -439.47 82.9439 183.742 + vertex -430.109 83.2372 191.257 + vertex -437.259 82.3249 191.771 + endloop + endfacet + facet normal 0.198291 -0.968085 -0.15327 + outer loop + vertex -426.563 84.7236 185.804 + vertex -426.025 84.2616 189.418 + vertex -432.542 83.8874 183.35 + endloop + endfacet + facet normal 0.178034 -0.973035 -0.146654 + outer loop + vertex -423.941 84.0147 193.586 + vertex -430.109 83.2372 191.257 + vertex -426.025 84.2616 189.418 + endloop + endfacet + facet normal 0.182836 -0.973645 -0.136329 + outer loop + vertex -430.109 83.2372 191.257 + vertex -432.542 83.8874 183.35 + vertex -426.025 84.2616 189.418 + endloop + endfacet + facet normal 0.34784 -0.911264 -0.220466 + outer loop + vertex -418.734 86.6564 189.154 + vertex -417.309 86.2755 192.975 + vertex -422.127 85.333 189.27 + endloop + endfacet + facet normal 0.339196 -0.917515 -0.207637 + outer loop + vertex -422.127 85.333 189.27 + vertex -417.309 86.2755 192.975 + vertex -420.756 84.9683 193.122 + endloop + endfacet + facet normal 0.356808 -0.909173 -0.214691 + outer loop + vertex -420.137 87.0142 185.305 + vertex -418.734 86.6564 189.154 + vertex -423.478 85.683 185.391 + endloop + endfacet + facet normal 0.349602 -0.91436 -0.204264 + outer loop + vertex -423.478 85.683 185.391 + vertex -418.734 86.6564 189.154 + vertex -422.127 85.333 189.27 + endloop + endfacet + facet normal 0.270137 -0.945954 -0.179436 + outer loop + vertex -423.478 85.683 185.391 + vertex -422.127 85.333 189.27 + vertex -426.563 84.7236 185.804 + endloop + endfacet + facet normal 0.255951 -0.95336 -0.159978 + outer loop + vertex -426.563 84.7236 185.804 + vertex -422.127 85.333 189.27 + vertex -426.025 84.2616 189.418 + endloop + endfacet + facet normal 0.254285 -0.950137 -0.180496 + outer loop + vertex -422.127 85.333 189.27 + vertex -420.756 84.9683 193.122 + vertex -426.025 84.2616 189.418 + endloop + endfacet + facet normal 0.257033 -0.948588 -0.184702 + outer loop + vertex -426.025 84.2616 189.418 + vertex -420.756 84.9683 193.122 + vertex -423.941 84.0147 193.586 + endloop + endfacet + facet normal 0.53925 -0.787209 -0.299184 + outer loop + vertex -412.369 90.3819 189.411 + vertex -410.852 89.9895 193.178 + vertex -415.484 88.3167 189.231 + endloop + endfacet + facet normal 0.532 -0.796754 -0.286632 + outer loop + vertex -415.484 88.3167 189.231 + vertex -410.852 89.9895 193.178 + vertex -414.012 87.9339 193.027 + endloop + endfacet + facet normal 0.548366 -0.782647 -0.294548 + outer loop + vertex -413.865 90.7606 185.619 + vertex -412.369 90.3819 189.411 + vertex -416.936 88.6876 185.41 + endloop + endfacet + facet normal 0.541366 -0.791848 -0.282663 + outer loop + vertex -416.936 88.6876 185.41 + vertex -412.369 90.3819 189.411 + vertex -415.484 88.3167 189.231 + endloop + endfacet + facet normal 0.454451 -0.853315 -0.255593 + outer loop + vertex -416.936 88.6876 185.41 + vertex -415.484 88.3167 189.231 + vertex -420.137 87.0142 185.305 + endloop + endfacet + facet normal 0.445931 -0.861515 -0.242771 + outer loop + vertex -420.137 87.0142 185.305 + vertex -415.484 88.3167 189.231 + vertex -418.734 86.6564 189.154 + endloop + endfacet + facet normal 0.444343 -0.857665 -0.258786 + outer loop + vertex -415.484 88.3167 189.231 + vertex -414.012 87.9339 193.027 + vertex -418.734 86.6564 189.154 + endloop + endfacet + facet normal 0.438248 -0.863558 -0.249412 + outer loop + vertex -418.734 86.6564 189.154 + vertex -414.012 87.9339 193.027 + vertex -417.309 86.2755 192.975 + endloop + endfacet + facet normal 0.68443 -0.635087 -0.358078 + outer loop + vertex -406.65 95.76 189.766 + vertex -405.065 95.3811 193.466 + vertex -409.406 92.8828 189.6 + endloop + endfacet + facet normal 0.682261 -0.64083 -0.351932 + outer loop + vertex -409.406 92.8828 189.6 + vertex -405.065 95.3811 193.466 + vertex -407.849 92.4901 193.333 + endloop + endfacet + facet normal 0.691195 -0.62974 -0.354509 + outer loop + vertex -408.221 96.1387 186.029 + vertex -406.65 95.76 189.766 + vertex -410.942 93.2601 185.838 + endloop + endfacet + facet normal 0.687658 -0.638945 -0.344784 + outer loop + vertex -410.942 93.2601 185.838 + vertex -406.65 95.76 189.766 + vertex -409.406 92.8828 189.6 + endloop + endfacet + facet normal 0.62812 -0.705976 -0.327205 + outer loop + vertex -410.942 93.2601 185.838 + vertex -409.406 92.8828 189.6 + vertex -413.865 90.7606 185.619 + endloop + endfacet + facet normal 0.623429 -0.714572 -0.317368 + outer loop + vertex -413.865 90.7606 185.619 + vertex -409.406 92.8828 189.6 + vertex -412.369 90.3819 189.411 + endloop + endfacet + facet normal 0.620455 -0.709837 -0.333417 + outer loop + vertex -409.406 92.8828 189.6 + vertex -407.849 92.4901 193.333 + vertex -412.369 90.3819 189.411 + endloop + endfacet + facet normal 0.615506 -0.718999 -0.322789 + outer loop + vertex -412.369 90.3819 189.411 + vertex -407.849 92.4901 193.333 + vertex -410.852 89.9895 193.178 + endloop + endfacet + facet normal 0.746997 -0.547485 -0.377167 + outer loop + vertex -405.781 99.3749 186.164 + vertex -404.185 98.9881 189.887 + vertex -408.221 96.1387 186.029 + endloop + endfacet + facet normal 0.745158 -0.555074 -0.369637 + outer loop + vertex -408.221 96.1387 186.029 + vertex -404.185 98.9881 189.887 + vertex -406.65 95.76 189.766 + endloop + endfacet + facet normal 0.740653 -0.551083 -0.38437 + outer loop + vertex -404.185 98.9881 189.887 + vertex -402.565 98.5888 193.581 + vertex -406.65 95.76 189.766 + endloop + endfacet + facet normal 0.738045 -0.561922 -0.373541 + outer loop + vertex -406.65 95.76 189.766 + vertex -402.565 98.5888 193.581 + vertex -405.065 95.3811 193.466 + endloop + endfacet + facet normal 0.116216 -0.984545 -0.131013 + outer loop + vertex -430.109 83.2372 191.257 + vertex -427.62 82.4927 199.06 + vertex -437.259 82.3249 191.771 + endloop + endfacet + facet normal 0.108813 -0.986649 -0.121175 + outer loop + vertex -437.259 82.3249 191.771 + vertex -427.62 82.4927 199.06 + vertex -435.003 81.5985 199.711 + endloop + endfacet + facet normal 0.18334 -0.969636 -0.161842 + outer loop + vertex -423.941 84.0147 193.586 + vertex -423.398 83.5216 197.156 + vertex -430.109 83.2372 191.257 + endloop + endfacet + facet normal 0.166645 -0.973514 -0.156527 + outer loop + vertex -421.262 83.2296 201.246 + vertex -427.62 82.4927 199.06 + vertex -423.398 83.5216 197.156 + endloop + endfacet + facet normal 0.170896 -0.974191 -0.147464 + outer loop + vertex -427.62 82.4927 199.06 + vertex -430.109 83.2372 191.257 + vertex -423.398 83.5216 197.156 + endloop + endfacet + facet normal 0.330277 -0.916016 -0.227666 + outer loop + vertex -415.871 85.8841 196.766 + vertex -414.42 85.475 200.518 + vertex -419.373 84.5785 196.939 + endloop + endfacet + facet normal 0.324528 -0.920258 -0.218646 + outer loop + vertex -419.373 84.5785 196.939 + vertex -414.42 85.475 200.518 + vertex -417.974 84.1729 200.722 + endloop + endfacet + facet normal 0.337485 -0.914665 -0.222468 + outer loop + vertex -417.309 86.2755 192.975 + vertex -415.871 85.8841 196.766 + vertex -420.756 84.9683 193.122 + endloop + endfacet + facet normal 0.33195 -0.918694 -0.214036 + outer loop + vertex -420.756 84.9683 193.122 + vertex -415.871 85.8841 196.766 + vertex -419.373 84.5785 196.939 + endloop + endfacet + facet normal 0.256115 -0.94788 -0.18955 + outer loop + vertex -420.756 84.9683 193.122 + vertex -419.373 84.5785 196.939 + vertex -423.941 84.0147 193.586 + endloop + endfacet + facet normal 0.241823 -0.955527 -0.168792 + outer loop + vertex -423.941 84.0147 193.586 + vertex -419.373 84.5785 196.939 + vertex -423.398 83.5216 197.156 + endloop + endfacet + facet normal 0.239702 -0.951937 -0.190682 + outer loop + vertex -419.373 84.5785 196.939 + vertex -417.974 84.1729 200.722 + vertex -423.398 83.5216 197.156 + endloop + endfacet + facet normal 0.241843 -0.95069 -0.194166 + outer loop + vertex -423.398 83.5216 197.156 + vertex -417.974 84.1729 200.722 + vertex -421.262 83.2296 201.246 + endloop + endfacet + facet normal 0.521047 -0.795862 -0.308406 + outer loop + vertex -409.317 89.5781 196.913 + vertex -407.769 89.1586 200.611 + vertex -412.523 87.5276 196.789 + endloop + endfacet + facet normal 0.515557 -0.803201 -0.298444 + outer loop + vertex -412.523 87.5276 196.789 + vertex -407.769 89.1586 200.611 + vertex -411.019 87.1088 200.513 + endloop + endfacet + facet normal 0.529543 -0.791639 -0.304782 + outer loop + vertex -410.852 89.9895 193.178 + vertex -409.317 89.5781 196.913 + vertex -414.012 87.9339 193.027 + endloop + endfacet + facet normal 0.523174 -0.800086 -0.293515 + outer loop + vertex -414.012 87.9339 193.027 + vertex -409.317 89.5781 196.913 + vertex -412.523 87.5276 196.789 + endloop + endfacet + facet normal 0.436506 -0.859594 -0.265631 + outer loop + vertex -414.012 87.9339 193.027 + vertex -412.523 87.5276 196.789 + vertex -417.309 86.2755 192.975 + endloop + endfacet + facet normal 0.42779 -0.868065 -0.251912 + outer loop + vertex -417.309 86.2755 192.975 + vertex -412.523 87.5276 196.789 + vertex -415.871 85.8841 196.766 + endloop + endfacet + facet normal 0.425849 -0.863865 -0.269054 + outer loop + vertex -412.523 87.5276 196.789 + vertex -411.019 87.1088 200.513 + vertex -415.871 85.8841 196.766 + endloop + endfacet + facet normal 0.418269 -0.871259 -0.256824 + outer loop + vertex -415.871 85.8841 196.766 + vertex -411.019 87.1088 200.513 + vertex -414.42 85.475 200.518 + endloop + endfacet + facet normal 0.67091 -0.641064 -0.372715 + outer loop + vertex -403.454 94.9774 197.134 + vertex -401.833 94.5638 200.764 + vertex -406.276 92.0818 197.035 + endloop + endfacet + facet normal 0.668724 -0.647156 -0.366056 + outer loop + vertex -406.276 92.0818 197.035 + vertex -401.833 94.5638 200.764 + vertex -404.684 91.6514 200.704 + endloop + endfacet + facet normal 0.678173 -0.636157 -0.367948 + outer loop + vertex -405.065 95.3811 193.466 + vertex -403.454 94.9774 197.134 + vertex -407.849 92.4901 193.333 + endloop + endfacet + facet normal 0.674793 -0.645348 -0.358023 + outer loop + vertex -407.849 92.4901 193.333 + vertex -403.454 94.9774 197.134 + vertex -406.276 92.0818 197.035 + endloop + endfacet + facet normal 0.612344 -0.71419 -0.33907 + outer loop + vertex -407.849 92.4901 193.333 + vertex -406.276 92.0818 197.035 + vertex -410.852 89.9895 193.178 + endloop + endfacet + facet normal 0.607946 -0.722434 -0.329379 + outer loop + vertex -410.852 89.9895 193.178 + vertex -406.276 92.0818 197.035 + vertex -409.317 89.5781 196.913 + endloop + endfacet + facet normal 0.604462 -0.717374 -0.346412 + outer loop + vertex -406.276 92.0818 197.035 + vertex -404.684 91.6514 200.704 + vertex -409.317 89.5781 196.913 + endloop + endfacet + facet normal 0.598623 -0.728429 -0.33323 + outer loop + vertex -409.317 89.5781 196.913 + vertex -404.684 91.6514 200.704 + vertex -407.769 89.1586 200.611 + endloop + endfacet + facet normal 0.733125 -0.557515 -0.389493 + outer loop + vertex -402.565 98.5888 193.581 + vertex -400.931 98.187 197.233 + vertex -405.065 95.3811 193.466 + endloop + endfacet + facet normal 0.731711 -0.563514 -0.383471 + outer loop + vertex -405.065 95.3811 193.466 + vertex -400.931 98.187 197.233 + vertex -403.454 94.9774 197.134 + endloop + endfacet + facet normal 0.727234 -0.559558 -0.397524 + outer loop + vertex -400.931 98.187 197.233 + vertex -399.276 97.7771 200.836 + vertex -403.454 94.9774 197.134 + endloop + endfacet + facet normal 0.725247 -0.568272 -0.388694 + outer loop + vertex -403.454 94.9774 197.134 + vertex -399.276 97.7771 200.836 + vertex -401.833 94.5638 200.764 + endloop + endfacet + facet normal 0.106576 -0.983985 -0.142879 + outer loop + vertex -427.62 82.4927 199.06 + vertex -425.084 81.6487 206.764 + vertex -435.003 81.5985 199.711 + endloop + endfacet + facet normal 0.100418 -0.985853 -0.134204 + outer loop + vertex -435.003 81.5985 199.711 + vertex -425.084 81.6487 206.764 + vertex -432.707 80.7653 207.55 + endloop + endfacet + facet normal 0.171975 -0.969738 -0.1733 + outer loop + vertex -421.262 83.2296 201.246 + vertex -420.712 82.6943 204.786 + vertex -427.62 82.4927 199.06 + endloop + endfacet + facet normal 0.156727 -0.973226 -0.168131 + outer loop + vertex -418.524 82.3508 208.815 + vertex -425.084 81.6487 206.764 + vertex -420.712 82.6943 204.786 + endloop + endfacet + facet normal 0.160762 -0.974 -0.159624 + outer loop + vertex -425.084 81.6487 206.764 + vertex -427.62 82.4927 199.06 + vertex -420.712 82.6943 204.786 + endloop + endfacet + facet normal 0.313944 -0.919273 -0.237435 + outer loop + vertex -412.951 85.0425 204.24 + vertex -411.466 84.5935 207.942 + vertex -416.562 83.7459 204.486 + endloop + endfacet + facet normal 0.309469 -0.922674 -0.230003 + outer loop + vertex -416.562 83.7459 204.486 + vertex -411.466 84.5935 207.942 + vertex -415.129 83.2942 208.225 + endloop + endfacet + facet normal 0.322541 -0.91722 -0.233828 + outer loop + vertex -414.42 85.475 200.518 + vertex -412.951 85.0425 204.24 + vertex -417.974 84.1729 200.722 + endloop + endfacet + facet normal 0.315946 -0.922152 -0.223192 + outer loop + vertex -417.974 84.1729 200.722 + vertex -412.951 85.0425 204.24 + vertex -416.562 83.7459 204.486 + endloop + endfacet + facet normal 0.241015 -0.950061 -0.198234 + outer loop + vertex -417.974 84.1729 200.722 + vertex -416.562 83.7459 204.486 + vertex -421.262 83.2296 201.246 + endloop + endfacet + facet normal 0.229295 -0.956531 -0.180199 + outer loop + vertex -421.262 83.2296 201.246 + vertex -416.562 83.7459 204.486 + vertex -420.712 82.6943 204.786 + endloop + endfacet + facet normal 0.226768 -0.952779 -0.201961 + outer loop + vertex -416.562 83.7459 204.486 + vertex -415.129 83.2942 208.225 + vertex -420.712 82.6943 204.786 + endloop + endfacet + facet normal 0.228766 -0.951562 -0.205417 + outer loop + vertex -420.712 82.6943 204.786 + vertex -415.129 83.2942 208.225 + vertex -418.524 82.3508 208.815 + endloop + endfacet + facet normal 0.502062 -0.803604 -0.319617 + outer loop + vertex -406.201 88.7097 204.275 + vertex -404.618 88.2542 207.907 + vertex -409.501 86.6762 204.204 + endloop + endfacet + facet normal 0.49667 -0.810924 -0.309387 + outer loop + vertex -409.501 86.6762 204.204 + vertex -404.618 88.2542 207.907 + vertex -407.964 86.22 207.867 + endloop + endfacet + facet normal 0.512716 -0.797803 -0.317226 + outer loop + vertex -407.769 89.1586 200.611 + vertex -406.201 88.7097 204.275 + vertex -411.019 87.1088 200.513 + endloop + endfacet + facet normal 0.504743 -0.808559 -0.302436 + outer loop + vertex -411.019 87.1088 200.513 + vertex -406.201 88.7097 204.275 + vertex -409.501 86.6762 204.204 + endloop + endfacet + facet normal 0.416335 -0.867276 -0.272944 + outer loop + vertex -411.019 87.1088 200.513 + vertex -409.501 86.6762 204.204 + vertex -414.42 85.475 200.518 + endloop + endfacet + facet normal 0.410583 -0.872944 -0.263422 + outer loop + vertex -414.42 85.475 200.518 + vertex -409.501 86.6762 204.204 + vertex -412.951 85.0425 204.24 + endloop + endfacet + facet normal 0.408489 -0.868883 -0.279605 + outer loop + vertex -409.501 86.6762 204.204 + vertex -407.964 86.22 207.867 + vertex -412.951 85.0425 204.24 + endloop + endfacet + facet normal 0.401188 -0.876157 -0.267202 + outer loop + vertex -412.951 85.0425 204.24 + vertex -407.964 86.22 207.867 + vertex -411.466 84.5935 207.942 + endloop + endfacet + facet normal 0.656319 -0.645611 -0.390425 + outer loop + vertex -400.189 94.1226 204.368 + vertex -398.523 93.6512 207.949 + vertex -403.076 91.2043 204.341 + endloop + endfacet + facet normal 0.652697 -0.656194 -0.378676 + outer loop + vertex -403.076 91.2043 204.341 + vertex -398.523 93.6512 207.949 + vertex -401.45 90.741 207.947 + endloop + endfacet + facet normal 0.664392 -0.642594 -0.38165 + outer loop + vertex -401.833 94.5638 200.764 + vertex -400.189 94.1226 204.368 + vertex -404.684 91.6514 200.704 + endloop + endfacet + facet normal 0.661497 -0.650898 -0.372498 + outer loop + vertex -404.684 91.6514 200.704 + vertex -400.189 94.1226 204.368 + vertex -403.076 91.2043 204.341 + endloop + endfacet + facet normal 0.594702 -0.722882 -0.351812 + outer loop + vertex -404.684 91.6514 200.704 + vertex -403.076 91.2043 204.341 + vertex -407.769 89.1586 200.611 + endloop + endfacet + facet normal 0.590607 -0.730739 -0.342351 + outer loop + vertex -407.769 89.1586 200.611 + vertex -403.076 91.2043 204.341 + vertex -406.201 88.7097 204.275 + endloop + endfacet + facet normal 0.58714 -0.72598 -0.358078 + outer loop + vertex -403.076 91.2043 204.341 + vertex -401.45 90.741 207.947 + vertex -406.201 88.7097 204.275 + endloop + endfacet + facet normal 0.582029 -0.735895 -0.345978 + outer loop + vertex -406.201 88.7097 204.275 + vertex -401.45 90.741 207.947 + vertex -404.618 88.2542 207.907 + endloop + endfacet + facet normal 0.720619 -0.564271 -0.402872 + outer loop + vertex -399.276 97.7771 200.836 + vertex -397.611 97.3586 204.402 + vertex -401.833 94.5638 200.764 + endloop + endfacet + facet normal 0.719537 -0.569219 -0.397815 + outer loop + vertex -401.833 94.5638 200.764 + vertex -397.611 97.3586 204.402 + vertex -400.189 94.1226 204.368 + endloop + endfacet + facet normal 0.714328 -0.56491 -0.413052 + outer loop + vertex -397.611 97.3586 204.402 + vertex -395.919 96.9056 207.947 + vertex -400.189 94.1226 204.368 + endloop + endfacet + facet normal 0.713107 -0.570812 -0.407004 + outer loop + vertex -400.189 94.1226 204.368 + vertex -395.919 96.9056 207.947 + vertex -398.523 93.6512 207.949 + endloop + endfacet + facet normal 0.097943 -0.983039 -0.155054 + outer loop + vertex -425.084 81.6487 206.764 + vertex -422.511 80.7113 214.333 + vertex -432.707 80.7653 207.55 + endloop + endfacet + facet normal 0.0939049 -0.984369 -0.148994 + outer loop + vertex -432.707 80.7653 207.55 + vertex -422.511 80.7113 214.333 + vertex -430.38 79.8172 215.28 + endloop + endfacet + facet normal 0.16206 -0.968968 -0.186647 + outer loop + vertex -418.524 82.3508 208.815 + vertex -417.982 81.769 212.306 + vertex -425.084 81.6487 206.764 + endloop + endfacet + facet normal 0.146208 -0.972579 -0.180868 + outer loop + vertex -415.761 81.3743 216.223 + vertex -422.511 80.7113 214.333 + vertex -417.982 81.769 212.306 + endloop + endfacet + facet normal 0.150519 -0.973573 -0.171756 + outer loop + vertex -422.511 80.7113 214.333 + vertex -425.084 81.6487 206.764 + vertex -417.982 81.769 212.306 + endloop + endfacet + facet normal 0.298538 -0.921229 -0.249422 + outer loop + vertex -409.968 84.1162 211.607 + vertex -408.469 83.6242 215.219 + vertex -413.693 82.822 211.93 + endloop + endfacet + facet normal 0.293948 -0.924876 -0.241245 + outer loop + vertex -413.693 82.822 211.93 + vertex -408.469 83.6242 215.219 + vertex -412.251 82.3292 215.575 + endloop + endfacet + facet normal 0.307166 -0.919506 -0.245273 + outer loop + vertex -411.466 84.5935 207.942 + vertex -409.968 84.1162 211.607 + vertex -415.129 83.2942 208.225 + endloop + endfacet + facet normal 0.300911 -0.924359 -0.234549 + outer loop + vertex -415.129 83.2942 208.225 + vertex -409.968 84.1162 211.607 + vertex -413.693 82.822 211.93 + endloop + endfacet + facet normal 0.227849 -0.950872 -0.20959 + outer loop + vertex -415.129 83.2942 208.225 + vertex -413.693 82.822 211.93 + vertex -418.524 82.3508 208.815 + endloop + endfacet + facet normal 0.217884 -0.95665 -0.193257 + outer loop + vertex -418.524 82.3508 208.815 + vertex -413.693 82.822 211.93 + vertex -417.982 81.769 212.306 + endloop + endfacet + facet normal 0.215149 -0.952873 -0.213878 + outer loop + vertex -413.693 82.822 211.93 + vertex -412.251 82.3292 215.575 + vertex -417.982 81.769 212.306 + endloop + endfacet + facet normal 0.218146 -0.950919 -0.219466 + outer loop + vertex -417.982 81.769 212.306 + vertex -412.251 82.3292 215.575 + vertex -415.761 81.3743 216.223 + endloop + endfacet + facet normal 0.485284 -0.808996 -0.331701 + outer loop + vertex -403.023 87.7814 211.5 + vertex -401.423 87.2897 215.039 + vertex -406.416 85.7478 211.496 + endloop + endfacet + facet normal 0.479621 -0.816942 -0.320265 + outer loop + vertex -406.416 85.7478 211.496 + vertex -401.423 87.2897 215.039 + vertex -404.864 85.2572 215.071 + endloop + endfacet + facet normal 0.494031 -0.806269 -0.325366 + outer loop + vertex -404.618 88.2542 207.907 + vertex -403.023 87.7814 211.5 + vertex -407.964 86.22 207.867 + endloop + endfacet + facet normal 0.488333 -0.814114 -0.314245 + outer loop + vertex -407.964 86.22 207.867 + vertex -403.023 87.7814 211.5 + vertex -406.416 85.7478 211.496 + endloop + endfacet + facet normal 0.398913 -0.87202 -0.283635 + outer loop + vertex -407.964 86.22 207.867 + vertex -406.416 85.7478 211.496 + vertex -411.466 84.5935 207.942 + endloop + endfacet + facet normal 0.394132 -0.876862 -0.275268 + outer loop + vertex -411.466 84.5935 207.942 + vertex -406.416 85.7478 211.496 + vertex -409.968 84.1162 211.607 + endloop + endfacet + facet normal 0.391949 -0.873111 -0.289921 + outer loop + vertex -406.416 85.7478 211.496 + vertex -404.864 85.2572 215.071 + vertex -409.968 84.1162 211.607 + endloop + endfacet + facet normal 0.386573 -0.878674 -0.280167 + outer loop + vertex -409.968 84.1162 211.607 + vertex -404.864 85.2572 215.071 + vertex -408.469 83.6242 215.219 + endloop + endfacet + facet normal 0.64021 -0.653951 -0.403087 + outer loop + vertex -396.852 93.1734 211.488 + vertex -395.168 92.6741 214.972 + vertex -399.811 90.2616 211.511 + endloop + endfacet + facet normal 0.636549 -0.665144 -0.390371 + outer loop + vertex -399.811 90.2616 211.511 + vertex -395.168 92.6741 214.972 + vertex -398.171 89.7737 215.018 + endloop + endfacet + facet normal 0.648171 -0.651631 -0.394018 + outer loop + vertex -398.523 93.6512 207.949 + vertex -396.852 93.1734 211.488 + vertex -401.45 90.741 207.947 + endloop + endfacet + facet normal 0.645597 -0.659286 -0.385417 + outer loop + vertex -401.45 90.741 207.947 + vertex -396.852 93.1734 211.488 + vertex -399.811 90.2616 211.511 + endloop + endfacet + facet normal 0.577967 -0.730431 -0.363901 + outer loop + vertex -401.45 90.741 207.947 + vertex -399.811 90.2616 211.511 + vertex -404.618 88.2542 207.907 + endloop + endfacet + facet normal 0.572942 -0.740298 -0.351706 + outer loop + vertex -404.618 88.2542 207.907 + vertex -399.811 90.2616 211.511 + vertex -403.023 87.7814 211.5 + endloop + endfacet + facet normal 0.569016 -0.735133 -0.368512 + outer loop + vertex -399.811 90.2616 211.511 + vertex -398.171 89.7737 215.018 + vertex -403.023 87.7814 211.5 + endloop + endfacet + facet normal 0.565074 -0.743032 -0.358602 + outer loop + vertex -403.023 87.7814 211.5 + vertex -398.171 89.7737 215.018 + vertex -401.423 87.2897 215.039 + endloop + endfacet + facet normal 0.707913 -0.566664 -0.421605 + outer loop + vertex -395.919 96.9056 207.947 + vertex -394.212 96.4226 211.463 + vertex -398.523 93.6512 207.949 + endloop + endfacet + facet normal 0.705896 -0.57676 -0.411168 + outer loop + vertex -398.523 93.6512 207.949 + vertex -394.212 96.4226 211.463 + vertex -396.852 93.1734 211.488 + endloop + endfacet + facet normal 0.700175 -0.572236 -0.426967 + outer loop + vertex -394.212 96.4226 211.463 + vertex -392.506 95.9276 214.924 + vertex -396.852 93.1734 211.488 + endloop + endfacet + facet normal 0.699022 -0.578288 -0.420656 + outer loop + vertex -396.852 93.1734 211.488 + vertex -392.506 95.9276 214.924 + vertex -395.168 92.6741 214.972 + endloop + endfacet + facet normal 0.0910088 -0.98122 -0.170072 + outer loop + vertex -422.511 80.7113 214.333 + vertex -419.909 79.6647 221.763 + vertex -430.38 79.8172 215.28 + endloop + endfacet + facet normal 0.0869566 -0.982693 -0.163562 + outer loop + vertex -430.38 79.8172 215.28 + vertex -419.909 79.6647 221.763 + vertex -428.011 78.7617 222.881 + endloop + endfacet + facet normal 0.150349 -0.968813 -0.196967 + outer loop + vertex -415.761 81.3743 216.223 + vertex -415.235 80.7619 219.637 + vertex -422.511 80.7113 214.333 + endloop + endfacet + facet normal 0.13868 -0.970725 -0.196116 + outer loop + vertex -412.97 80.3148 223.452 + vertex -419.909 79.6647 221.763 + vertex -415.235 80.7619 219.637 + endloop + endfacet + facet normal 0.1431 -0.971882 -0.186995 + outer loop + vertex -419.909 79.6647 221.763 + vertex -422.511 80.7113 214.333 + vertex -415.235 80.7619 219.637 + endloop + endfacet + facet normal 0.284713 -0.922127 -0.261953 + outer loop + vertex -406.971 83.1176 218.771 + vertex -405.463 82.5878 222.274 + vertex -410.813 81.8184 219.168 + endloop + endfacet + facet normal 0.281365 -0.924966 -0.255483 + outer loop + vertex -410.813 81.8184 219.168 + vertex -405.463 82.5878 222.274 + vertex -409.358 81.2809 222.717 + endloop + endfacet + facet normal 0.291714 -0.922007 -0.254571 + outer loop + vertex -408.469 83.6242 215.219 + vertex -406.971 83.1176 218.771 + vertex -412.251 82.3292 215.575 + endloop + endfacet + facet normal 0.287436 -0.925499 -0.246641 + outer loop + vertex -412.251 82.3292 215.575 + vertex -406.971 83.1176 218.771 + vertex -410.813 81.8184 219.168 + endloop + endfacet + facet normal 0.217511 -0.950432 -0.222189 + outer loop + vertex -412.251 82.3292 215.575 + vertex -410.813 81.8184 219.168 + vertex -415.761 81.3743 216.223 + endloop + endfacet + facet normal 0.207017 -0.956923 -0.203573 + outer loop + vertex -415.761 81.3743 216.223 + vertex -410.813 81.8184 219.168 + vertex -415.235 80.7619 219.637 + endloop + endfacet + facet normal 0.203353 -0.952277 -0.22763 + outer loop + vertex -410.813 81.8184 219.168 + vertex -409.358 81.2809 222.717 + vertex -415.235 80.7619 219.637 + endloop + endfacet + facet normal 0.206464 -0.950076 -0.233939 + outer loop + vertex -415.235 80.7619 219.637 + vertex -409.358 81.2809 222.717 + vertex -412.97 80.3148 223.452 + endloop + endfacet + facet normal 0.466912 -0.81441 -0.344571 + outer loop + vertex -399.823 86.784 218.516 + vertex -398.215 86.2567 221.942 + vertex -403.313 84.7545 218.585 + endloop + endfacet + facet normal 0.461982 -0.821658 -0.333843 + outer loop + vertex -403.313 84.7545 218.585 + vertex -398.215 86.2567 221.942 + vertex -401.752 84.225 222.048 + endloop + endfacet + facet normal 0.476477 -0.81189 -0.337348 + outer loop + vertex -401.423 87.2897 215.039 + vertex -399.823 86.784 218.516 + vertex -404.864 85.2572 215.071 + endloop + endfacet + facet normal 0.470666 -0.82021 -0.325159 + outer loop + vertex -404.864 85.2572 215.071 + vertex -399.823 86.784 218.516 + vertex -403.313 84.7545 218.585 + endloop + endfacet + facet normal 0.384254 -0.874884 -0.294834 + outer loop + vertex -404.864 85.2572 215.071 + vertex -403.313 84.7545 218.585 + vertex -408.469 83.6242 215.219 + endloop + endfacet + facet normal 0.379337 -0.880094 -0.28555 + outer loop + vertex -408.469 83.6242 215.219 + vertex -403.313 84.7545 218.585 + vertex -406.971 83.1176 218.771 + endloop + endfacet + facet normal 0.37632 -0.875386 -0.30345 + outer loop + vertex -403.313 84.7545 218.585 + vertex -401.752 84.225 222.048 + vertex -406.971 83.1176 218.771 + endloop + endfacet + facet normal 0.370928 -0.88127 -0.292876 + outer loop + vertex -406.971 83.1176 218.771 + vertex -401.752 84.225 222.048 + vertex -405.463 82.5878 222.274 + endloop + endfacet + facet normal 0.62401 -0.661454 -0.41604 + outer loop + vertex -393.493 92.1753 218.385 + vertex -391.804 91.6539 221.747 + vertex -396.526 89.2655 218.462 + endloop + endfacet + facet normal 0.620976 -0.671443 -0.404417 + outer loop + vertex -396.526 89.2655 218.462 + vertex -391.804 91.6539 221.747 + vertex -394.878 88.7473 221.853 + endloop + endfacet + facet normal 0.631565 -0.660239 -0.40646 + outer loop + vertex -395.168 92.6741 214.972 + vertex -393.493 92.1753 218.385 + vertex -398.171 89.7737 215.018 + endloop + endfacet + facet normal 0.62951 -0.666737 -0.398973 + outer loop + vertex -398.171 89.7737 215.018 + vertex -393.493 92.1753 218.385 + vertex -396.526 89.2655 218.462 + endloop + endfacet + facet normal 0.560693 -0.737452 -0.376547 + outer loop + vertex -398.171 89.7737 215.018 + vertex -396.526 89.2655 218.462 + vertex -401.423 87.2897 215.039 + endloop + endfacet + facet normal 0.556111 -0.746895 -0.36454 + outer loop + vertex -401.423 87.2897 215.039 + vertex -396.526 89.2655 218.462 + vertex -399.823 86.784 218.516 + endloop + endfacet + facet normal 0.551826 -0.741571 -0.381525 + outer loop + vertex -396.526 89.2655 218.462 + vertex -394.878 88.7473 221.853 + vertex -399.823 86.784 218.516 + endloop + endfacet + facet normal 0.548619 -0.748372 -0.372769 + outer loop + vertex -399.823 86.784 218.516 + vertex -394.878 88.7473 221.853 + vertex -398.215 86.2567 221.942 + endloop + endfacet + facet normal 0.6937 -0.574142 -0.434904 + outer loop + vertex -392.506 95.9276 214.924 + vertex -390.797 95.4216 218.318 + vertex -395.168 92.6741 214.972 + endloop + endfacet + facet normal 0.691999 -0.583589 -0.424924 + outer loop + vertex -395.168 92.6741 214.972 + vertex -390.797 95.4216 218.318 + vertex -393.493 92.1753 218.385 + endloop + endfacet + facet normal 0.68555 -0.578586 -0.441883 + outer loop + vertex -390.797 95.4216 218.318 + vertex -389.081 94.9053 221.655 + vertex -393.493 92.1753 218.385 + endloop + endfacet + facet normal 0.684387 -0.585451 -0.434582 + outer loop + vertex -393.493 92.1753 218.385 + vertex -389.081 94.9053 221.655 + vertex -391.804 91.6539 221.747 + endloop + endfacet + facet normal 0.0838372 -0.979432 -0.183532 + outer loop + vertex -419.909 79.6647 221.763 + vertex -417.252 78.5272 229.047 + vertex -428.011 78.7617 222.881 + endloop + endfacet + facet normal 0.0817156 -0.980292 -0.179863 + outer loop + vertex -428.011 78.7617 222.881 + vertex -417.252 78.5272 229.047 + vertex -425.614 77.5911 230.35 + endloop + endfacet + facet normal 0.142194 -0.966861 -0.212041 + outer loop + vertex -412.97 80.3148 223.452 + vertex -412.433 79.6512 226.838 + vertex -419.909 79.6647 221.763 + endloop + endfacet + facet normal 0.130102 -0.969157 -0.209305 + outer loop + vertex -410.11 79.1563 230.574 + vertex -417.252 78.5272 229.047 + vertex -412.433 79.6512 226.838 + endloop + endfacet + facet normal 0.1344 -0.970417 -0.200569 + outer loop + vertex -417.252 78.5272 229.047 + vertex -419.909 79.6647 221.763 + vertex -412.433 79.6512 226.838 + endloop + endfacet + facet normal 0.272751 -0.922079 -0.274549 + outer loop + vertex -403.936 82.0383 225.755 + vertex -402.389 81.4668 229.211 + vertex -407.885 80.7228 226.25 + endloop + endfacet + facet normal 0.269867 -0.924694 -0.268539 + outer loop + vertex -407.885 80.7228 226.25 + vertex -402.389 81.4668 229.211 + vertex -406.39 80.1413 229.754 + endloop + endfacet + facet normal 0.278995 -0.922139 -0.267995 + outer loop + vertex -405.463 82.5878 222.274 + vertex -403.936 82.0383 225.755 + vertex -409.358 81.2809 222.717 + endloop + endfacet + facet normal 0.275493 -0.925198 -0.260982 + outer loop + vertex -409.358 81.2809 222.717 + vertex -403.936 82.0383 225.755 + vertex -407.885 80.7228 226.25 + endloop + endfacet + facet normal 0.205971 -0.949705 -0.235874 + outer loop + vertex -409.358 81.2809 222.717 + vertex -407.885 80.7228 226.25 + vertex -412.97 80.3148 223.452 + endloop + endfacet + facet normal 0.196922 -0.955751 -0.218546 + outer loop + vertex -412.97 80.3148 223.452 + vertex -407.885 80.7228 226.25 + vertex -412.433 79.6512 226.838 + endloop + endfacet + facet normal 0.193079 -0.951328 -0.2402 + outer loop + vertex -407.885 80.7228 226.25 + vertex -406.39 80.1413 229.754 + vertex -412.433 79.6512 226.838 + endloop + endfacet + facet normal 0.196592 -0.94862 -0.247935 + outer loop + vertex -412.433 79.6512 226.838 + vertex -406.39 80.1413 229.754 + vertex -410.11 79.1563 230.574 + endloop + endfacet + facet normal 0.450936 -0.818873 -0.355111 + outer loop + vertex -396.591 85.7173 225.336 + vertex -394.951 85.1618 228.7 + vertex -400.175 83.6806 225.481 + endloop + endfacet + facet normal 0.447552 -0.8241 -0.347212 + outer loop + vertex -400.175 83.6806 225.481 + vertex -394.951 85.1618 228.7 + vertex -398.577 83.1128 228.888 + endloop + endfacet + facet normal 0.458819 -0.816956 -0.349384 + outer loop + vertex -398.215 86.2567 221.942 + vertex -396.591 85.7173 225.336 + vertex -401.752 84.225 222.048 + endloop + endfacet + facet normal 0.454324 -0.823703 -0.339267 + outer loop + vertex -401.752 84.225 222.048 + vertex -396.591 85.7173 225.336 + vertex -400.175 83.6806 225.481 + endloop + endfacet + facet normal 0.368194 -0.877187 -0.308183 + outer loop + vertex -401.752 84.225 222.048 + vertex -400.175 83.6806 225.481 + vertex -405.463 82.5878 222.274 + endloop + endfacet + facet normal 0.363576 -0.882339 -0.298814 + outer loop + vertex -405.463 82.5878 222.274 + vertex -400.175 83.6806 225.481 + vertex -403.936 82.0383 225.755 + endloop + endfacet + facet normal 0.360427 -0.877875 -0.31532 + outer loop + vertex -400.175 83.6806 225.481 + vertex -398.577 83.1128 228.888 + vertex -403.936 82.0383 225.755 + endloop + endfacet + facet normal 0.355644 -0.883365 -0.305258 + outer loop + vertex -403.936 82.0383 225.755 + vertex -398.577 83.1128 228.888 + vertex -402.389 81.4668 229.211 + endloop + endfacet + facet normal 0.608211 -0.668342 -0.42825 + outer loop + vertex -390.105 91.1227 225.073 + vertex -388.389 90.5733 228.368 + vertex -393.211 88.2078 225.211 + endloop + endfacet + facet normal 0.606223 -0.675388 -0.419933 + outer loop + vertex -393.211 88.2078 225.211 + vertex -388.389 90.5733 228.368 + vertex -391.527 87.6505 228.539 + endloop + endfacet + facet normal 0.615554 -0.666308 -0.420865 + outer loop + vertex -391.804 91.6539 221.747 + vertex -390.105 91.1227 225.073 + vertex -394.878 88.7473 221.853 + endloop + endfacet + facet normal 0.613512 -0.673253 -0.412714 + outer loop + vertex -394.878 88.7473 221.853 + vertex -390.105 91.1227 225.073 + vertex -393.211 88.2078 225.211 + endloop + endfacet + facet normal 0.544198 -0.743051 -0.389518 + outer loop + vertex -394.878 88.7473 221.853 + vertex -393.211 88.2078 225.211 + vertex -398.215 86.2567 221.942 + endloop + endfacet + facet normal 0.540112 -0.751953 -0.37795 + outer loop + vertex -398.215 86.2567 221.942 + vertex -393.211 88.2078 225.211 + vertex -396.591 85.7173 225.336 + endloop + endfacet + facet normal 0.535222 -0.746212 -0.395859 + outer loop + vertex -393.211 88.2078 225.211 + vertex -391.527 87.6505 228.539 + vertex -396.591 85.7173 225.336 + endloop + endfacet + facet normal 0.531072 -0.755465 -0.383712 + outer loop + vertex -396.591 85.7173 225.336 + vertex -391.527 87.6505 228.539 + vertex -394.951 85.1618 228.7 + endloop + endfacet + facet normal 0.678095 -0.580636 -0.450611 + outer loop + vertex -389.081 94.9053 221.655 + vertex -387.346 94.3705 224.956 + vertex -391.804 91.6539 221.747 + endloop + endfacet + facet normal 0.676484 -0.590639 -0.439903 + outer loop + vertex -391.804 91.6539 221.747 + vertex -387.346 94.3705 224.956 + vertex -390.105 91.1227 225.073 + endloop + endfacet + facet normal 0.670274 -0.585926 -0.455438 + outer loop + vertex -387.346 94.3705 224.956 + vertex -385.602 93.8257 228.224 + vertex -390.105 91.1227 225.073 + endloop + endfacet + facet normal 0.669138 -0.593311 -0.447477 + outer loop + vertex -390.105 91.1227 225.073 + vertex -385.602 93.8257 228.224 + vertex -388.389 90.5733 228.368 + endloop + endfacet + facet normal 0.0785003 -0.977023 -0.198151 + outer loop + vertex -417.252 78.5272 229.047 + vertex -414.557 77.3081 236.126 + vertex -425.614 77.5911 230.35 + endloop + endfacet + facet normal 0.0764333 -0.977972 -0.194241 + outer loop + vertex -425.614 77.5911 230.35 + vertex -414.557 77.3081 236.126 + vertex -423.156 76.3399 237.617 + endloop + endfacet + facet normal 0.133209 -0.965088 -0.225521 + outer loop + vertex -410.11 79.1563 230.574 + vertex -409.58 78.4582 233.874 + vertex -417.252 78.5272 229.047 + endloop + endfacet + facet normal 0.123449 -0.967375 -0.221237 + outer loop + vertex -407.224 77.9447 237.434 + vertex -414.557 77.3081 236.126 + vertex -409.58 78.4582 233.874 + endloop + endfacet + facet normal 0.126529 -0.968394 -0.21495 + outer loop + vertex -414.557 77.3081 236.126 + vertex -417.252 78.5272 229.047 + vertex -409.58 78.4582 233.874 + endloop + endfacet + facet normal 0.260563 -0.92192 -0.286653 + outer loop + vertex -400.832 80.8764 232.615 + vertex -399.282 80.2821 235.935 + vertex -404.893 79.5462 233.202 + endloop + endfacet + facet normal 0.258444 -0.92403 -0.281736 + outer loop + vertex -404.893 79.5462 233.202 + vertex -399.282 80.2821 235.935 + vertex -403.396 78.9414 236.559 + endloop + endfacet + facet normal 0.266998 -0.92153 -0.281947 + outer loop + vertex -402.389 81.4668 229.211 + vertex -400.832 80.8764 232.615 + vertex -406.39 80.1413 229.754 + endloop + endfacet + facet normal 0.263379 -0.924951 -0.274038 + outer loop + vertex -406.39 80.1413 229.754 + vertex -400.832 80.8764 232.615 + vertex -404.893 79.5462 233.202 + endloop + endfacet + facet normal 0.19631 -0.948409 -0.248962 + outer loop + vertex -406.39 80.1413 229.754 + vertex -404.893 79.5462 233.202 + vertex -410.11 79.1563 230.574 + endloop + endfacet + facet normal 0.188248 -0.954306 -0.232082 + outer loop + vertex -410.11 79.1563 230.574 + vertex -404.893 79.5462 233.202 + vertex -409.58 78.4582 233.874 + endloop + endfacet + facet normal 0.184149 -0.949717 -0.253234 + outer loop + vertex -404.893 79.5462 233.202 + vertex -403.396 78.9414 236.559 + vertex -409.58 78.4582 233.874 + endloop + endfacet + facet normal 0.187074 -0.947197 -0.260425 + outer loop + vertex -409.58 78.4582 233.874 + vertex -403.396 78.9414 236.559 + vertex -407.224 77.9447 237.434 + endloop + endfacet + facet normal 0.435475 -0.820072 -0.371274 + outer loop + vertex -393.302 84.5893 232.013 + vertex -391.656 83.9988 235.249 + vertex -396.973 82.5343 232.246 + endloop + endfacet + facet normal 0.430891 -0.82774 -0.359415 + outer loop + vertex -396.973 82.5343 232.246 + vertex -391.656 83.9988 235.249 + vertex -395.372 81.9444 235.524 + endloop + endfacet + facet normal 0.444077 -0.819363 -0.362547 + outer loop + vertex -394.951 85.1618 228.7 + vertex -393.302 84.5893 232.013 + vertex -398.577 83.1128 228.888 + endloop + endfacet + facet normal 0.43996 -0.825948 -0.352484 + outer loop + vertex -398.577 83.1128 228.888 + vertex -393.302 84.5893 232.013 + vertex -396.973 82.5343 232.246 + endloop + endfacet + facet normal 0.352662 -0.879344 -0.319976 + outer loop + vertex -398.577 83.1128 228.888 + vertex -396.973 82.5343 232.246 + vertex -402.389 81.4668 229.211 + endloop + endfacet + facet normal 0.349501 -0.883103 -0.313014 + outer loop + vertex -402.389 81.4668 229.211 + vertex -396.973 82.5343 232.246 + vertex -400.832 80.8764 232.615 + endloop + endfacet + facet normal 0.346406 -0.879098 -0.327398 + outer loop + vertex -396.973 82.5343 232.246 + vertex -395.372 81.9444 235.524 + vertex -400.832 80.8764 232.615 + endloop + endfacet + facet normal 0.342419 -0.884063 -0.318091 + outer loop + vertex -400.832 80.8764 232.615 + vertex -395.372 81.9444 235.524 + vertex -399.282 80.2821 235.935 + endloop + endfacet + facet normal 0.591892 -0.674664 -0.441013 + outer loop + vertex -386.659 90.0051 231.612 + vertex -384.948 89.4399 234.773 + vertex -389.839 87.0836 231.814 + endloop + endfacet + facet normal 0.590404 -0.680602 -0.433825 + outer loop + vertex -389.839 87.0836 231.814 + vertex -384.948 89.4399 234.773 + vertex -388.156 86.5065 235.01 + endloop + endfacet + facet normal 0.600099 -0.669828 -0.437277 + outer loop + vertex -388.389 90.5733 228.368 + vertex -386.659 90.0051 231.612 + vertex -391.527 87.6505 228.539 + endloop + endfacet + facet normal 0.597461 -0.679656 -0.425567 + outer loop + vertex -391.527 87.6505 228.539 + vertex -386.659 90.0051 231.612 + vertex -389.839 87.0836 231.814 + endloop + endfacet + facet normal 0.5262 -0.749876 -0.400998 + outer loop + vertex -391.527 87.6505 228.539 + vertex -389.839 87.0836 231.814 + vertex -394.951 85.1618 228.7 + endloop + endfacet + facet normal 0.522964 -0.75734 -0.391082 + outer loop + vertex -394.951 85.1618 228.7 + vertex -389.839 87.0836 231.814 + vertex -393.302 84.5893 232.013 + endloop + endfacet + facet normal 0.517869 -0.75165 -0.408454 + outer loop + vertex -389.839 87.0836 231.814 + vertex -388.156 86.5065 235.01 + vertex -393.302 84.5893 232.013 + endloop + endfacet + facet normal 0.515465 -0.757523 -0.400569 + outer loop + vertex -393.302 84.5893 232.013 + vertex -388.156 86.5065 235.01 + vertex -391.656 83.9988 235.249 + endloop + endfacet + facet normal 0.662492 -0.588335 -0.463644 + outer loop + vertex -385.602 93.8257 228.224 + vertex -383.848 93.2665 231.439 + vertex -388.389 90.5733 228.368 + endloop + endfacet + facet normal 0.661621 -0.594562 -0.456895 + outer loop + vertex -388.389 90.5733 228.368 + vertex -383.848 93.2665 231.439 + vertex -386.659 90.0051 231.612 + endloop + endfacet + facet normal 0.656614 -0.590876 -0.468747 + outer loop + vertex -383.848 93.2665 231.439 + vertex -382.114 92.7079 234.572 + vertex -386.659 90.0051 231.612 + endloop + endfacet + facet normal 0.655833 -0.597199 -0.461775 + outer loop + vertex -386.659 90.0051 231.612 + vertex -382.114 92.7079 234.572 + vertex -384.948 89.4399 234.773 + endloop + endfacet + facet normal 0.0728455 -0.974414 -0.212629 + outer loop + vertex -414.557 77.3081 236.126 + vertex -411.806 76.0181 242.98 + vertex -423.156 76.3399 237.617 + endloop + endfacet + facet normal 0.0713397 -0.975205 -0.209489 + outer loop + vertex -423.156 76.3399 237.617 + vertex -411.806 76.0181 242.98 + vertex -420.618 75.0061 244.69 + endloop + endfacet + facet normal 0.126563 -0.962182 -0.241223 + outer loop + vertex -407.224 77.9447 237.434 + vertex -406.706 77.2159 240.613 + vertex -414.557 77.3081 236.126 + endloop + endfacet + facet normal 0.117033 -0.964683 -0.235986 + outer loop + vertex -404.297 76.6735 244.025 + vertex -411.806 76.0181 242.98 + vertex -406.706 77.2159 240.613 + endloop + endfacet + facet normal 0.120084 -0.965763 -0.229959 + outer loop + vertex -411.806 76.0181 242.98 + vertex -414.557 77.3081 236.126 + vertex -406.706 77.2159 240.613 + endloop + endfacet + facet normal 0.24947 -0.920769 -0.299914 + outer loop + vertex -397.733 79.6741 239.163 + vertex -396.176 79.0646 242.33 + vertex -401.9 78.3273 239.832 + endloop + endfacet + facet normal 0.248724 -0.921606 -0.297957 + outer loop + vertex -401.9 78.3273 239.832 + vertex -396.176 79.0646 242.33 + vertex -400.382 77.6976 243.047 + endloop + endfacet + facet normal 0.255167 -0.920529 -0.295831 + outer loop + vertex -399.282 80.2821 235.935 + vertex -397.733 79.6741 239.163 + vertex -403.396 78.9414 236.559 + endloop + endfacet + facet normal 0.252224 -0.923645 -0.288555 + outer loop + vertex -403.396 78.9414 236.559 + vertex -397.733 79.6741 239.163 + vertex -401.9 78.3273 239.832 + endloop + endfacet + facet normal 0.186398 -0.946677 -0.262791 + outer loop + vertex -403.396 78.9414 236.559 + vertex -401.9 78.3273 239.832 + vertex -407.224 77.9447 237.434 + endloop + endfacet + facet normal 0.179937 -0.952007 -0.2476 + outer loop + vertex -407.224 77.9447 237.434 + vertex -401.9 78.3273 239.832 + vertex -406.706 77.2159 240.613 + endloop + endfacet + facet normal 0.175451 -0.9472 -0.268383 + outer loop + vertex -401.9 78.3273 239.832 + vertex -400.382 77.6976 243.047 + vertex -406.706 77.2159 240.613 + endloop + endfacet + facet normal 0.178152 -0.944524 -0.275929 + outer loop + vertex -406.706 77.2159 240.613 + vertex -400.382 77.6976 243.047 + vertex -404.297 76.6735 244.025 + endloop + endfacet + facet normal 0.41941 -0.822815 -0.383499 + outer loop + vertex -390.023 83.4171 238.394 + vertex -388.383 82.8178 241.475 + vertex -393.781 81.3537 238.712 + endloop + endfacet + facet normal 0.416782 -0.827699 -0.375775 + outer loop + vertex -393.781 81.3537 238.712 + vertex -388.383 82.8178 241.475 + vertex -392.178 80.7442 241.832 + endloop + endfacet + facet normal 0.427286 -0.823162 -0.373941 + outer loop + vertex -391.656 83.9988 235.249 + vertex -390.023 83.4171 238.394 + vertex -395.372 81.9444 235.524 + endloop + endfacet + facet normal 0.424153 -0.828649 -0.365288 + outer loop + vertex -395.372 81.9444 235.524 + vertex -390.023 83.4171 238.394 + vertex -393.781 81.3537 238.712 + endloop + endfacet + facet normal 0.339198 -0.880032 -0.332397 + outer loop + vertex -395.372 81.9444 235.524 + vertex -393.781 81.3537 238.712 + vertex -399.282 80.2821 235.935 + endloop + endfacet + facet normal 0.337485 -0.882289 -0.328132 + outer loop + vertex -399.282 80.2821 235.935 + vertex -393.781 81.3537 238.712 + vertex -397.733 79.6741 239.163 + endloop + endfacet + facet normal 0.333942 -0.877957 -0.343035 + outer loop + vertex -393.781 81.3537 238.712 + vertex -392.178 80.7442 241.832 + vertex -397.733 79.6741 239.163 + endloop + endfacet + facet normal 0.329869 -0.883611 -0.332291 + outer loop + vertex -397.733 79.6741 239.163 + vertex -392.178 80.7442 241.832 + vertex -396.176 79.0646 242.33 + endloop + endfacet + facet normal 0.576508 -0.677632 -0.456567 + outer loop + vertex -383.248 88.869 237.847 + vertex -381.547 88.2899 240.854 + vertex -386.488 85.9312 238.116 + endloop + endfacet + facet normal 0.574922 -0.685187 -0.447196 + outer loop + vertex -386.488 85.9312 238.116 + vertex -381.547 88.2899 240.854 + vertex -384.817 85.3479 241.157 + endloop + endfacet + facet normal 0.584746 -0.675639 -0.448982 + outer loop + vertex -384.948 89.4399 234.773 + vertex -383.248 88.869 237.847 + vertex -388.156 86.5065 235.01 + endloop + endfacet + facet normal 0.583006 -0.683244 -0.439638 + outer loop + vertex -388.156 86.5065 235.01 + vertex -383.248 88.869 237.847 + vertex -386.488 85.9312 238.116 + endloop + endfacet + facet normal 0.511335 -0.753045 -0.414076 + outer loop + vertex -388.156 86.5065 235.01 + vertex -386.488 85.9312 238.116 + vertex -391.656 83.9988 235.249 + endloop + endfacet + facet normal 0.508633 -0.760057 -0.404482 + outer loop + vertex -391.656 83.9988 235.249 + vertex -386.488 85.9312 238.116 + vertex -390.023 83.4171 238.394 + endloop + endfacet + facet normal 0.503355 -0.754482 -0.421177 + outer loop + vertex -386.488 85.9312 238.116 + vertex -384.817 85.3479 241.157 + vertex -390.023 83.4171 238.394 + endloop + endfacet + facet normal 0.501722 -0.759017 -0.414931 + outer loop + vertex -390.023 83.4171 238.394 + vertex -384.817 85.3479 241.157 + vertex -388.383 82.8178 241.475 + endloop + endfacet + facet normal 0.649021 -0.592256 -0.477498 + outer loop + vertex -382.114 92.7079 234.572 + vertex -380.388 92.1427 237.619 + vertex -384.948 89.4399 234.773 + endloop + endfacet + facet normal 0.648319 -0.599046 -0.469922 + outer loop + vertex -384.948 89.4399 234.773 + vertex -380.388 92.1427 237.619 + vertex -383.248 88.869 237.847 + endloop + endfacet + facet normal 0.641453 -0.594123 -0.48534 + outer loop + vertex -380.388 92.1427 237.619 + vertex -378.664 91.5703 240.598 + vertex -383.248 88.869 237.847 + endloop + endfacet + facet normal 0.640902 -0.60052 -0.478143 + outer loop + vertex -383.248 88.869 237.847 + vertex -378.664 91.5703 240.598 + vertex -381.547 88.2899 240.854 + endloop + endfacet + facet normal 0.0675821 -0.971612 -0.226722 + outer loop + vertex -411.806 76.0181 242.98 + vertex -408.938 74.6614 249.649 + vertex -420.618 75.0061 244.69 + endloop + endfacet + facet normal 0.0675033 -0.97166 -0.22654 + outer loop + vertex -420.618 75.0061 244.69 + vertex -408.938 74.6614 249.649 + vertex -417.938 73.5891 251.567 + endloop + endfacet + facet normal 0.119218 -0.959598 -0.254869 + outer loop + vertex -404.297 76.6735 244.025 + vertex -403.739 75.9087 247.166 + vertex -411.806 76.0181 242.98 + endloop + endfacet + facet normal 0.111152 -0.961759 -0.250328 + outer loop + vertex -401.236 75.3322 250.492 + vertex -408.938 74.6614 249.649 + vertex -403.739 75.9087 247.166 + endloop + endfacet + facet normal 0.114001 -0.962823 -0.244899 + outer loop + vertex -408.938 74.6614 249.649 + vertex -411.806 76.0181 242.98 + vertex -403.739 75.9087 247.166 + endloop + endfacet + facet normal 0.239111 -0.918054 -0.316232 + outer loop + vertex -394.584 78.4287 245.464 + vertex -392.954 77.7783 248.585 + vertex -398.833 77.0536 246.243 + endloop + endfacet + facet normal 0.237713 -0.919801 -0.312183 + outer loop + vertex -398.833 77.0536 246.243 + vertex -392.954 77.7783 248.585 + vertex -397.242 76.388 249.416 + endloop + endfacet + facet normal 0.245409 -0.918206 -0.310921 + outer loop + vertex -396.176 79.0646 242.33 + vertex -394.584 78.4287 245.464 + vertex -400.382 77.6976 243.047 + endloop + endfacet + facet normal 0.242617 -0.921517 -0.303222 + outer loop + vertex -400.382 77.6976 243.047 + vertex -394.584 78.4287 245.464 + vertex -398.833 77.0536 246.243 + endloop + endfacet + facet normal 0.177973 -0.944389 -0.276504 + outer loop + vertex -400.382 77.6976 243.047 + vertex -398.833 77.0536 246.243 + vertex -404.297 76.6735 244.025 + endloop + endfacet + facet normal 0.172396 -0.949578 -0.26188 + outer loop + vertex -404.297 76.6735 244.025 + vertex -398.833 77.0536 246.243 + vertex -403.739 75.9087 247.166 + endloop + endfacet + facet normal 0.167435 -0.944647 -0.28215 + outer loop + vertex -398.833 77.0536 246.243 + vertex -397.242 76.388 249.416 + vertex -403.739 75.9087 247.166 + endloop + endfacet + facet normal 0.170374 -0.941324 -0.291343 + outer loop + vertex -403.739 75.9087 247.166 + vertex -397.242 76.388 249.416 + vertex -401.236 75.3322 250.492 + endloop + endfacet + facet normal 0.406832 -0.82221 -0.398068 + outer loop + vertex -386.722 82.2143 244.521 + vertex -385.026 81.5876 247.549 + vertex -390.55 80.126 244.922 + endloop + endfacet + facet normal 0.404218 -0.827534 -0.389609 + outer loop + vertex -390.55 80.126 244.922 + vertex -385.026 81.5876 247.549 + vertex -388.888 79.4921 247.993 + endloop + endfacet + facet normal 0.41333 -0.823568 -0.388451 + outer loop + vertex -388.383 82.8178 241.475 + vertex -386.722 82.2143 244.521 + vertex -392.178 80.7442 241.832 + endloop + endfacet + facet normal 0.411337 -0.827441 -0.382288 + outer loop + vertex -392.178 80.7442 241.832 + vertex -386.722 82.2143 244.521 + vertex -390.55 80.126 244.922 + endloop + endfacet + facet normal 0.326053 -0.879089 -0.347694 + outer loop + vertex -392.178 80.7442 241.832 + vertex -390.55 80.126 244.922 + vertex -396.176 79.0646 242.33 + endloop + endfacet + facet normal 0.324591 -0.881219 -0.343647 + outer loop + vertex -396.176 79.0646 242.33 + vertex -390.55 80.126 244.922 + vertex -394.584 78.4287 245.464 + endloop + endfacet + facet normal 0.321564 -0.87773 -0.355228 + outer loop + vertex -390.55 80.126 244.922 + vertex -388.888 79.4921 247.993 + vertex -394.584 78.4287 245.464 + endloop + endfacet + facet normal 0.319952 -0.880193 -0.35056 + outer loop + vertex -394.584 78.4287 245.464 + vertex -388.888 79.4921 247.993 + vertex -392.954 77.7783 248.585 + endloop + endfacet + facet normal 0.562336 -0.679382 -0.471401 + outer loop + vertex -379.829 87.7014 243.829 + vertex -378.084 87.0959 246.783 + vertex -383.12 84.7431 244.166 + endloop + endfacet + facet normal 0.56107 -0.68641 -0.462647 + outer loop + vertex -383.12 84.7431 244.166 + vertex -378.084 87.0959 246.783 + vertex -381.401 84.134 247.155 + endloop + endfacet + facet normal 0.568703 -0.679896 -0.462946 + outer loop + vertex -381.547 88.2899 240.854 + vertex -379.829 87.7014 243.829 + vertex -384.817 85.3479 241.157 + endloop + endfacet + facet normal 0.567904 -0.684025 -0.457815 + outer loop + vertex -384.817 85.3479 241.157 + vertex -379.829 87.7014 243.829 + vertex -383.12 84.7431 244.166 + endloop + endfacet + facet normal 0.496283 -0.753412 -0.431363 + outer loop + vertex -384.817 85.3479 241.157 + vertex -383.12 84.7431 244.166 + vertex -388.383 82.8178 241.475 + endloop + endfacet + facet normal 0.493446 -0.761719 -0.419875 + outer loop + vertex -388.383 82.8178 241.475 + vertex -383.12 84.7431 244.166 + vertex -386.722 82.2143 244.521 + endloop + endfacet + facet normal 0.488287 -0.756502 -0.435065 + outer loop + vertex -383.12 84.7431 244.166 + vertex -381.401 84.134 247.155 + vertex -386.722 82.2143 244.521 + endloop + endfacet + facet normal 0.487139 -0.76003 -0.430174 + outer loop + vertex -386.722 82.2143 244.521 + vertex -381.401 84.134 247.155 + vertex -385.026 81.5876 247.549 + endloop + endfacet + facet normal 0.634262 -0.595818 -0.49266 + outer loop + vertex -378.664 91.5703 240.598 + vertex -376.925 90.9861 243.544 + vertex -381.547 88.2899 240.854 + endloop + endfacet + facet normal 0.633773 -0.602429 -0.485192 + outer loop + vertex -381.547 88.2899 240.854 + vertex -376.925 90.9861 243.544 + vertex -379.829 87.7014 243.829 + endloop + endfacet + facet normal 0.626758 -0.597523 -0.500141 + outer loop + vertex -376.925 90.9861 243.544 + vertex -375.162 90.3881 246.467 + vertex -379.829 87.7014 243.829 + endloop + endfacet + facet normal 0.626397 -0.603275 -0.493647 + outer loop + vertex -379.829 87.7014 243.829 + vertex -375.162 90.3881 246.467 + vertex -378.084 87.0959 246.783 + endloop + endfacet + facet normal 0.0638274 -0.968209 -0.241863 + outer loop + vertex -408.938 74.6614 249.649 + vertex -405.924 73.2521 256.086 + vertex -417.938 73.5891 251.567 + endloop + endfacet + facet normal 0.064632 -0.96763 -0.243959 + outer loop + vertex -417.938 73.5891 251.567 + vertex -405.924 73.2521 256.086 + vertex -415.015 72.1161 258.183 + endloop + endfacet + facet normal 0.112759 -0.956449 -0.269241 + outer loop + vertex -401.236 75.3322 250.492 + vertex -400.642 74.5375 253.563 + vertex -408.938 74.6614 249.649 + endloop + endfacet + facet normal 0.105731 -0.957952 -0.266739 + outer loop + vertex -398.071 73.9419 256.721 + vertex -405.924 73.2521 256.086 + vertex -400.642 74.5375 253.563 + endloop + endfacet + facet normal 0.108803 -0.959203 -0.260944 + outer loop + vertex -405.924 73.2521 256.086 + vertex -408.938 74.6614 249.649 + vertex -400.642 74.5375 253.563 + endloop + endfacet + facet normal 0.231011 -0.915485 -0.329426 + outer loop + vertex -391.296 77.1152 251.666 + vertex -389.632 76.4543 254.67 + vertex -395.627 75.7073 252.542 + endloop + endfacet + facet normal 0.230869 -0.91569 -0.328956 + outer loop + vertex -395.627 75.7073 252.542 + vertex -389.632 76.4543 254.67 + vertex -393.997 75.0262 255.582 + endloop + endfacet + facet normal 0.234527 -0.916716 -0.323463 + outer loop + vertex -392.954 77.7783 248.585 + vertex -391.296 77.1152 251.666 + vertex -397.242 76.388 249.416 + endloop + endfacet + facet normal 0.233598 -0.917956 -0.320608 + outer loop + vertex -397.242 76.388 249.416 + vertex -391.296 77.1152 251.666 + vertex -395.627 75.7073 252.542 + endloop + endfacet + facet normal 0.169915 -0.940982 -0.292713 + outer loop + vertex -397.242 76.388 249.416 + vertex -395.627 75.7073 252.542 + vertex -401.236 75.3322 250.492 + endloop + endfacet + facet normal 0.164461 -0.946768 -0.276735 + outer loop + vertex -401.236 75.3322 250.492 + vertex -395.627 75.7073 252.542 + vertex -400.642 74.5375 253.563 + endloop + endfacet + facet normal 0.159274 -0.941692 -0.296392 + outer loop + vertex -395.627 75.7073 252.542 + vertex -393.997 75.0262 255.582 + vertex -400.642 74.5375 253.563 + endloop + endfacet + facet normal 0.162832 -0.936934 -0.309258 + outer loop + vertex -400.642 74.5375 253.563 + vertex -393.997 75.0262 255.582 + vertex -398.071 73.9419 256.721 + endloop + endfacet + facet normal 0.395157 -0.820505 -0.413065 + outer loop + vertex -383.311 80.9557 250.539 + vertex -381.588 80.316 253.459 + vertex -387.197 78.8389 251.027 + endloop + endfacet + facet normal 0.393527 -0.824315 -0.406991 + outer loop + vertex -387.197 78.8389 251.027 + vertex -381.588 80.316 253.459 + vertex -385.499 78.1879 253.987 + endloop + endfacet + facet normal 0.400141 -0.822928 -0.403333 + outer loop + vertex -385.026 81.5876 247.549 + vertex -383.311 80.9557 250.539 + vertex -388.888 79.4921 247.993 + endloop + endfacet + facet normal 0.399203 -0.82495 -0.400117 + outer loop + vertex -388.888 79.4921 247.993 + vertex -383.311 80.9557 250.539 + vertex -387.197 78.8389 251.027 + endloop + endfacet + facet normal 0.316053 -0.875836 -0.364722 + outer loop + vertex -388.888 79.4921 247.993 + vertex -387.197 78.8389 251.027 + vertex -392.954 77.7783 248.585 + endloop + endfacet + facet normal 0.313893 -0.879333 -0.358113 + outer loop + vertex -392.954 77.7783 248.585 + vertex -387.197 78.8389 251.027 + vertex -391.296 77.1152 251.666 + endloop + endfacet + facet normal 0.310328 -0.87545 -0.370518 + outer loop + vertex -387.197 78.8389 251.027 + vertex -385.499 78.1879 253.987 + vertex -391.296 77.1152 251.666 + endloop + endfacet + facet normal 0.308424 -0.878751 -0.36424 + outer loop + vertex -391.296 77.1152 251.666 + vertex -385.499 78.1879 253.987 + vertex -389.632 76.4543 254.67 + endloop + endfacet + facet normal 0.547166 -0.682169 -0.485032 + outer loop + vertex -376.317 86.4768 249.701 + vertex -374.56 85.8632 252.546 + vertex -379.658 83.5078 250.108 + endloop + endfacet + facet normal 0.546658 -0.685795 -0.480469 + outer loop + vertex -379.658 83.5078 250.108 + vertex -374.56 85.8632 252.546 + vertex -377.914 82.8798 252.988 + endloop + endfacet + facet normal 0.553848 -0.680476 -0.479796 + outer loop + vertex -378.084 87.0959 246.783 + vertex -376.317 86.4768 249.701 + vertex -381.401 84.134 247.155 + endloop + endfacet + facet normal 0.552824 -0.686748 -0.471978 + outer loop + vertex -381.401 84.134 247.155 + vertex -376.317 86.4768 249.701 + vertex -379.658 83.5078 250.108 + endloop + endfacet + facet normal 0.482006 -0.754959 -0.444643 + outer loop + vertex -381.401 84.134 247.155 + vertex -379.658 83.5078 250.108 + vertex -385.026 81.5876 247.549 + endloop + endfacet + facet normal 0.480143 -0.761079 -0.436144 + outer loop + vertex -385.026 81.5876 247.549 + vertex -379.658 83.5078 250.108 + vertex -383.311 80.9557 250.539 + endloop + endfacet + facet normal 0.474374 -0.755487 -0.451895 + outer loop + vertex -379.658 83.5078 250.108 + vertex -377.914 82.8798 252.988 + vertex -383.311 80.9557 250.539 + endloop + endfacet + facet normal 0.47317 -0.759837 -0.445823 + outer loop + vertex -383.311 80.9557 250.539 + vertex -377.914 82.8798 252.988 + vertex -381.588 80.316 253.459 + endloop + endfacet + facet normal 0.620551 -0.59925 -0.505783 + outer loop + vertex -375.162 90.3881 246.467 + vertex -373.393 89.7852 249.352 + vertex -378.084 87.0959 246.783 + endloop + endfacet + facet normal 0.62045 -0.601399 -0.503349 + outer loop + vertex -378.084 87.0959 246.783 + vertex -373.393 89.7852 249.352 + vertex -376.317 86.4768 249.701 + endloop + endfacet + facet normal 0.614182 -0.597182 -0.515901 + outer loop + vertex -373.393 89.7852 249.352 + vertex -371.621 89.1776 252.165 + vertex -376.317 86.4768 249.701 + endloop + endfacet + facet normal 0.614042 -0.602997 -0.509261 + outer loop + vertex -376.317 86.4768 249.701 + vertex -371.621 89.1776 252.165 + vertex -374.56 85.8632 252.546 + endloop + endfacet + facet normal 0.0606164 -0.963883 -0.259335 + outer loop + vertex -405.924 73.2521 256.086 + vertex -402.736 71.8082 262.198 + vertex -415.015 72.1161 258.183 + endloop + endfacet + facet normal 0.0618004 -0.962848 -0.262877 + outer loop + vertex -415.015 72.1161 258.183 + vertex -402.736 71.8082 262.198 + vertex -411.833 70.5975 264.494 + endloop + endfacet + facet normal 0.106706 -0.952729 -0.284466 + outer loop + vertex -398.071 73.9419 256.721 + vertex -397.454 73.1412 259.635 + vertex -405.924 73.2521 256.086 + endloop + endfacet + facet normal 0.10363 -0.953677 -0.28242 + outer loop + vertex -394.826 72.5609 262.559 + vertex -402.736 71.8082 262.198 + vertex -397.454 73.1412 259.635 + endloop + endfacet + facet normal 0.104873 -0.954214 -0.280137 + outer loop + vertex -402.736 71.8082 262.198 + vertex -405.924 73.2521 256.086 + vertex -397.454 73.1412 259.635 + endloop + endfacet + facet normal 0.222622 -0.91099 -0.347184 + outer loop + vertex -387.967 75.7924 257.565 + vertex -386.308 75.1381 260.346 + vertex -392.368 74.3532 258.519 + endloop + endfacet + facet normal 0.222039 -0.912037 -0.344799 + outer loop + vertex -392.368 74.3532 258.519 + vertex -386.308 75.1381 260.346 + vertex -390.731 73.6837 261.344 + endloop + endfacet + facet normal 0.227646 -0.912617 -0.339569 + outer loop + vertex -389.632 76.4543 254.67 + vertex -387.967 75.7924 257.565 + vertex -393.997 75.0262 255.582 + endloop + endfacet + facet normal 0.22642 -0.914578 -0.335084 + outer loop + vertex -393.997 75.0262 255.582 + vertex -387.967 75.7924 257.565 + vertex -392.368 74.3532 258.519 + endloop + endfacet + facet normal 0.164035 -0.93785 -0.305828 + outer loop + vertex -393.997 75.0262 255.582 + vertex -392.368 74.3532 258.519 + vertex -398.071 73.9419 256.721 + endloop + endfacet + facet normal 0.160344 -0.942559 -0.293041 + outer loop + vertex -398.071 73.9419 256.721 + vertex -392.368 74.3532 258.519 + vertex -397.454 73.1412 259.635 + endloop + endfacet + facet normal 0.154965 -0.93738 -0.311938 + outer loop + vertex -392.368 74.3532 258.519 + vertex -390.731 73.6837 261.344 + vertex -397.454 73.1412 259.635 + endloop + endfacet + facet normal 0.15839 -0.931569 -0.32725 + outer loop + vertex -397.454 73.1412 259.635 + vertex -390.731 73.6837 261.344 + vertex -394.826 72.5609 262.559 + endloop + endfacet + facet normal 0.383604 -0.818276 -0.428104 + outer loop + vertex -379.876 79.6854 256.275 + vertex -378.179 79.0657 258.98 + vertex -383.808 77.5446 256.843 + endloop + endfacet + facet normal 0.382967 -0.820137 -0.425102 + outer loop + vertex -383.808 77.5446 256.843 + vertex -378.179 79.0657 258.98 + vertex -382.127 76.9084 259.586 + endloop + endfacet + facet normal 0.389264 -0.819743 -0.420113 + outer loop + vertex -381.588 80.316 253.459 + vertex -379.876 79.6854 256.275 + vertex -385.499 78.1879 253.987 + endloop + endfacet + facet normal 0.388031 -0.822927 -0.414998 + outer loop + vertex -385.499 78.1879 253.987 + vertex -379.876 79.6854 256.275 + vertex -383.808 77.5446 256.843 + endloop + endfacet + facet normal 0.304545 -0.874613 -0.377232 + outer loop + vertex -385.499 78.1879 253.987 + vertex -383.808 77.5446 256.843 + vertex -389.632 76.4543 254.67 + endloop + endfacet + facet normal 0.303934 -0.87578 -0.375012 + outer loop + vertex -389.632 76.4543 254.67 + vertex -383.808 77.5446 256.843 + vertex -387.967 75.7924 257.565 + endloop + endfacet + facet normal 0.300361 -0.872019 -0.38648 + outer loop + vertex -383.808 77.5446 256.843 + vertex -382.127 76.9084 259.586 + vertex -387.967 75.7924 257.565 + endloop + endfacet + facet normal 0.299841 -0.873133 -0.384362 + outer loop + vertex -387.967 75.7924 257.565 + vertex -382.127 76.9084 259.586 + vertex -386.308 75.1381 260.346 + endloop + endfacet + facet normal 0.535651 -0.679815 -0.500929 + outer loop + vertex -372.826 85.2625 255.29 + vertex -371.111 84.6695 257.928 + vertex -376.186 82.2631 255.767 + endloop + endfacet + facet normal 0.535453 -0.682515 -0.497457 + outer loop + vertex -376.186 82.2631 255.767 + vertex -371.111 84.6695 257.928 + vertex -374.478 81.6567 258.438 + endloop + endfacet + facet normal 0.541682 -0.681848 -0.491594 + outer loop + vertex -374.56 85.8632 252.546 + vertex -372.826 85.2625 255.29 + vertex -377.914 82.8798 252.988 + endloop + endfacet + facet normal 0.541417 -0.684294 -0.488477 + outer loop + vertex -377.914 82.8798 252.988 + vertex -372.826 85.2625 255.29 + vertex -376.186 82.2631 255.767 + endloop + endfacet + facet normal 0.468266 -0.755178 -0.45873 + outer loop + vertex -377.914 82.8798 252.988 + vertex -376.186 82.2631 255.767 + vertex -381.588 80.316 253.459 + endloop + endfacet + facet normal 0.467441 -0.758583 -0.453928 + outer loop + vertex -381.588 80.316 253.459 + vertex -376.186 82.2631 255.767 + vertex -379.876 79.6854 256.275 + endloop + endfacet + facet normal 0.462339 -0.75383 -0.466886 + outer loop + vertex -376.186 82.2631 255.767 + vertex -374.478 81.6567 258.438 + vertex -379.876 79.6854 256.275 + endloop + endfacet + facet normal 0.461783 -0.756553 -0.463016 + outer loop + vertex -379.876 79.6854 256.275 + vertex -374.478 81.6567 258.438 + vertex -378.179 79.0657 258.98 + endloop + endfacet + facet normal 0.607503 -0.598667 -0.522052 + outer loop + vertex -371.621 89.1776 252.165 + vertex -369.875 88.5821 254.879 + vertex -374.56 85.8632 252.546 + endloop + endfacet + facet normal 0.607514 -0.603787 -0.516108 + outer loop + vertex -374.56 85.8632 252.546 + vertex -369.875 88.5821 254.879 + vertex -372.826 85.2625 255.29 + endloop + endfacet + facet normal 0.600946 -0.5995 -0.528644 + outer loop + vertex -369.875 88.5821 254.879 + vertex -368.16 88.0009 257.488 + vertex -372.826 85.2625 255.29 + endloop + endfacet + facet normal 0.601022 -0.601846 -0.525883 + outer loop + vertex -372.826 85.2625 255.29 + vertex -368.16 88.0009 257.488 + vertex -371.111 84.6695 257.928 + endloop + endfacet + facet normal 0.0573864 -0.958798 -0.278232 + outer loop + vertex -402.736 71.8082 262.198 + vertex -399.396 70.355 267.894 + vertex -411.833 70.5975 264.494 + endloop + endfacet + facet normal 0.0573777 -0.958808 -0.278201 + outer loop + vertex -411.833 70.5975 264.494 + vertex -399.396 70.355 267.894 + vertex -408.581 69.1096 270.292 + endloop + endfacet + facet normal 0.103993 -0.946649 -0.305027 + outer loop + vertex -394.826 72.5609 262.559 + vertex -394.145 71.7455 265.321 + vertex -402.736 71.8082 262.198 + endloop + endfacet + facet normal 0.0999616 -0.946318 -0.307394 + outer loop + vertex -391.449 71.1491 268.034 + vertex -399.396 70.355 267.894 + vertex -394.145 71.7455 265.321 + endloop + endfacet + facet normal 0.102922 -0.947704 -0.302101 + outer loop + vertex -399.396 70.355 267.894 + vertex -402.736 71.8082 262.198 + vertex -394.145 71.7455 265.321 + endloop + endfacet + facet normal 0.215476 -0.903804 -0.369742 + outer loop + vertex -384.652 74.4938 263.029 + vertex -382.988 73.8302 265.621 + vertex -389.075 73.0079 264.084 + endloop + endfacet + facet normal 0.215486 -0.903781 -0.369791 + outer loop + vertex -389.075 73.0079 264.084 + vertex -382.988 73.8302 265.621 + vertex -387.398 72.3234 266.734 + endloop + endfacet + facet normal 0.219188 -0.909374 -0.353548 + outer loop + vertex -386.308 75.1381 260.346 + vertex -384.652 74.4938 263.029 + vertex -390.731 73.6837 261.344 + endloop + endfacet + facet normal 0.219915 -0.907894 -0.356884 + outer loop + vertex -390.731 73.6837 261.344 + vertex -384.652 74.4938 263.029 + vertex -389.075 73.0079 264.084 + endloop + endfacet + facet normal 0.158887 -0.931948 -0.325925 + outer loop + vertex -390.731 73.6837 261.344 + vertex -389.075 73.0079 264.084 + vertex -394.826 72.5609 262.559 + endloop + endfacet + facet normal 0.156273 -0.936197 -0.314824 + outer loop + vertex -394.826 72.5609 262.559 + vertex -389.075 73.0079 264.084 + vertex -394.145 71.7455 265.321 + endloop + endfacet + facet normal 0.149836 -0.930199 -0.33508 + outer loop + vertex -389.075 73.0079 264.084 + vertex -387.398 72.3234 266.734 + vertex -394.145 71.7455 265.321 + endloop + endfacet + facet normal 0.153345 -0.922152 -0.355134 + outer loop + vertex -394.145 71.7455 265.321 + vertex -387.398 72.3234 266.734 + vertex -391.449 71.1491 268.034 + endloop + endfacet + facet normal 0.371869 -0.812603 -0.448766 + outer loop + vertex -376.485 78.4424 261.587 + vertex -374.811 77.8228 264.096 + vertex -380.45 76.2753 262.226 + endloop + endfacet + facet normal 0.371432 -0.814297 -0.446047 + outer loop + vertex -380.45 76.2753 262.226 + vertex -374.811 77.8228 264.096 + vertex -378.786 75.6402 264.771 + endloop + endfacet + facet normal 0.377655 -0.814642 -0.440154 + outer loop + vertex -378.179 79.0657 258.98 + vertex -376.485 78.4424 261.587 + vertex -382.127 76.9084 259.586 + endloop + endfacet + facet normal 0.376768 -0.817617 -0.435372 + outer loop + vertex -382.127 76.9084 259.586 + vertex -376.485 78.4424 261.587 + vertex -380.45 76.2753 262.226 + endloop + endfacet + facet normal 0.295941 -0.869082 -0.396379 + outer loop + vertex -382.127 76.9084 259.586 + vertex -380.45 76.2753 262.226 + vertex -386.308 75.1381 260.346 + endloop + endfacet + facet normal 0.294805 -0.871818 -0.391182 + outer loop + vertex -386.308 75.1381 260.346 + vertex -380.45 76.2753 262.226 + vertex -384.652 74.4938 263.029 + endloop + endfacet + facet normal 0.289868 -0.866773 -0.40581 + outer loop + vertex -380.45 76.2753 262.226 + vertex -378.786 75.6402 264.771 + vertex -384.652 74.4938 263.029 + endloop + endfacet + facet normal 0.290287 -0.865609 -0.407988 + outer loop + vertex -384.652 74.4938 263.029 + vertex -378.786 75.6402 264.771 + vertex -382.988 73.8302 265.621 + endloop + endfacet + facet normal 0.520161 -0.675713 -0.522345 + outer loop + vertex -369.403 84.07 260.473 + vertex -367.72 83.4672 262.93 + vertex -372.782 81.0533 261.011 + endloop + endfacet + facet normal 0.520153 -0.676482 -0.521357 + outer loop + vertex -372.782 81.0533 261.011 + vertex -367.72 83.4672 262.93 + vertex -371.095 80.4369 263.495 + endloop + endfacet + facet normal 0.527753 -0.676621 -0.51348 + outer loop + vertex -371.111 84.6695 257.928 + vertex -369.403 84.07 260.473 + vertex -374.478 81.6567 258.438 + endloop + endfacet + facet normal 0.52756 -0.681335 -0.507408 + outer loop + vertex -374.478 81.6567 258.438 + vertex -369.403 84.07 260.473 + vertex -372.782 81.0533 261.011 + endloop + endfacet + facet normal 0.456158 -0.7514 -0.476779 + outer loop + vertex -374.478 81.6567 258.438 + vertex -372.782 81.0533 261.011 + vertex -378.179 79.0657 258.98 + endloop + endfacet + facet normal 0.456078 -0.751882 -0.476096 + outer loop + vertex -378.179 79.0657 258.98 + vertex -372.782 81.0533 261.011 + vertex -376.485 78.4424 261.587 + endloop + endfacet + facet normal 0.449769 -0.746183 -0.490835 + outer loop + vertex -372.782 81.0533 261.011 + vertex -371.095 80.4369 263.495 + vertex -376.485 78.4424 261.587 + endloop + endfacet + facet normal 0.449233 -0.750303 -0.485011 + outer loop + vertex -376.485 78.4424 261.587 + vertex -371.095 80.4369 263.495 + vertex -374.811 77.8228 264.096 + endloop + endfacet + facet normal 0.593881 -0.597258 -0.539062 + outer loop + vertex -368.16 88.0009 257.488 + vertex -366.46 87.4191 260.005 + vertex -371.111 84.6695 257.928 + endloop + endfacet + facet normal 0.593877 -0.59719 -0.539143 + outer loop + vertex -371.111 84.6695 257.928 + vertex -366.46 87.4191 260.005 + vertex -369.403 84.07 260.473 + endloop + endfacet + facet normal 0.587264 -0.593017 -0.550865 + outer loop + vertex -366.46 87.4191 260.005 + vertex -364.78 86.8247 262.437 + vertex -369.403 84.07 260.473 + endloop + endfacet + facet normal 0.587443 -0.594909 -0.54863 + outer loop + vertex -369.403 84.07 260.473 + vertex -364.78 86.8247 262.437 + vertex -367.72 83.4672 262.93 + endloop + endfacet + facet normal 0.0530277 -0.954721 -0.292739 + outer loop + vertex -399.396 70.355 267.894 + vertex -396.256 69.0374 272.76 + vertex -408.581 69.1096 270.292 + endloop + endfacet + facet normal 0.0523944 -0.955711 -0.289606 + outer loop + vertex -408.581 69.1096 270.292 + vertex -396.256 69.0374 272.76 + vertex -405.772 67.7907 275.153 + endloop + endfacet + facet normal 0.0995987 -0.938703 -0.330026 + outer loop + vertex -391.449 71.1491 268.034 + vertex -390.775 70.342 270.533 + vertex -399.396 70.355 267.894 + endloop + endfacet + facet normal 0.0937751 -0.94235 -0.321222 + outer loop + vertex -388.221 69.8482 272.727 + vertex -396.256 69.0374 272.76 + vertex -390.775 70.342 270.533 + endloop + endfacet + facet normal 0.0956744 -0.943511 -0.317228 + outer loop + vertex -396.256 69.0374 272.76 + vertex -399.396 70.355 267.894 + vertex -390.775 70.342 270.533 + endloop + endfacet + facet normal 0.210453 -0.895532 -0.392086 + outer loop + vertex -381.357 73.1755 268.09 + vertex -379.812 72.5635 270.318 + vertex -385.731 71.6387 269.252 + endloop + endfacet + facet normal 0.210911 -0.893541 -0.396361 + outer loop + vertex -385.731 71.6387 269.252 + vertex -379.812 72.5635 270.318 + vertex -384.153 71.0147 271.499 + endloop + endfacet + facet normal 0.212137 -0.900763 -0.378977 + outer loop + vertex -382.988 73.8302 265.621 + vertex -381.357 73.1755 268.09 + vertex -387.398 72.3234 266.734 + endloop + endfacet + facet normal 0.213123 -0.897901 -0.385166 + outer loop + vertex -387.398 72.3234 266.734 + vertex -381.357 73.1755 268.09 + vertex -385.731 71.6387 269.252 + endloop + endfacet + facet normal 0.154239 -0.922835 -0.352967 + outer loop + vertex -387.398 72.3234 266.734 + vertex -385.731 71.6387 269.252 + vertex -391.449 71.1491 268.034 + endloop + endfacet + facet normal 0.152041 -0.927813 -0.340656 + outer loop + vertex -391.449 71.1491 268.034 + vertex -385.731 71.6387 269.252 + vertex -390.775 70.342 270.533 + endloop + endfacet + facet normal 0.145977 -0.92199 -0.358645 + outer loop + vertex -385.731 71.6387 269.252 + vertex -384.153 71.0147 271.499 + vertex -390.775 70.342 270.533 + endloop + endfacet + facet normal 0.147969 -0.913942 -0.377909 + outer loop + vertex -390.775 70.342 270.533 + vertex -384.153 71.0147 271.499 + vertex -388.221 69.8482 272.727 + endloop + endfacet + facet normal 0.360602 -0.804766 -0.471506 + outer loop + vertex -373.181 77.199 266.475 + vertex -371.679 76.6185 268.615 + vertex -377.16 74.9991 267.187 + endloop + endfacet + facet normal 0.360222 -0.807757 -0.466656 + outer loop + vertex -377.16 74.9991 267.187 + vertex -371.679 76.6185 268.615 + vertex -375.654 74.4129 269.364 + endloop + endfacet + facet normal 0.365265 -0.808057 -0.462196 + outer loop + vertex -374.811 77.8228 264.096 + vertex -373.181 77.199 266.475 + vertex -378.786 75.6402 264.771 + endloop + endfacet + facet normal 0.365033 -0.809186 -0.460401 + outer loop + vertex -378.786 75.6402 264.771 + vertex -373.181 77.199 266.475 + vertex -377.16 74.9991 267.187 + endloop + endfacet + facet normal 0.285717 -0.860999 -0.420768 + outer loop + vertex -378.786 75.6402 264.771 + vertex -377.16 74.9991 267.187 + vertex -382.988 73.8302 265.621 + endloop + endfacet + facet normal 0.285141 -0.862935 -0.417179 + outer loop + vertex -382.988 73.8302 265.621 + vertex -377.16 74.9991 267.187 + vertex -381.357 73.1755 268.09 + endloop + endfacet + facet normal 0.281721 -0.859588 -0.426311 + outer loop + vertex -377.16 74.9991 267.187 + vertex -375.654 74.4129 269.364 + vertex -381.357 73.1755 268.09 + endloop + endfacet + facet normal 0.282255 -0.856929 -0.431283 + outer loop + vertex -381.357 73.1755 268.09 + vertex -375.654 74.4129 269.364 + vertex -379.812 72.5635 270.318 + endloop + endfacet + facet normal 0.508662 -0.668967 -0.541984 + outer loop + vertex -366.085 82.8629 265.26 + vertex -364.586 82.3061 267.355 + vertex -369.459 79.8222 265.847 + endloop + endfacet + facet normal 0.508842 -0.670806 -0.539536 + outer loop + vertex -369.459 79.8222 265.847 + vertex -364.586 82.3061 267.355 + vertex -367.963 79.2599 267.957 + endloop + endfacet + facet normal 0.513513 -0.671488 -0.534235 + outer loop + vertex -367.72 83.4672 262.93 + vertex -366.085 82.8629 265.26 + vertex -371.095 80.4369 263.495 + endloop + endfacet + facet normal 0.513547 -0.672612 -0.532787 + outer loop + vertex -371.095 80.4369 263.495 + vertex -366.085 82.8629 265.26 + vertex -369.459 79.8222 265.847 + endloop + endfacet + facet normal 0.441924 -0.743725 -0.501573 + outer loop + vertex -371.095 80.4369 263.495 + vertex -369.459 79.8222 265.847 + vertex -374.811 77.8228 264.096 + endloop + endfacet + facet normal 0.44172 -0.746037 -0.498309 + outer loop + vertex -374.811 77.8228 264.096 + vertex -369.459 79.8222 265.847 + vertex -373.181 77.199 266.475 + endloop + endfacet + facet normal 0.437364 -0.742145 -0.507872 + outer loop + vertex -369.459 79.8222 265.847 + vertex -367.963 79.2599 267.957 + vertex -373.181 77.199 266.475 + endloop + endfacet + facet normal 0.437369 -0.741825 -0.508334 + outer loop + vertex -373.181 77.199 266.475 + vertex -367.963 79.2599 267.957 + vertex -371.679 76.6185 268.615 + endloop + endfacet + facet normal 0.579855 -0.590179 -0.561656 + outer loop + vertex -364.78 86.8247 262.437 + vertex -363.151 86.2284 264.745 + vertex -367.72 83.4672 262.93 + endloop + endfacet + facet normal 0.580024 -0.591461 -0.56013 + outer loop + vertex -367.72 83.4672 262.93 + vertex -363.151 86.2284 264.745 + vertex -366.085 82.8629 265.26 + endloop + endfacet + facet normal 0.574489 -0.588049 -0.569352 + outer loop + vertex -363.151 86.2284 264.745 + vertex -361.649 85.6827 266.824 + vertex -366.085 82.8629 265.26 + endloop + endfacet + facet normal 0.574701 -0.589111 -0.568037 + outer loop + vertex -366.085 82.8629 265.26 + vertex -361.649 85.6827 266.824 + vertex -364.586 82.3061 267.355 + endloop + endfacet + facet normal 0.215557 -0.895653 -0.389025 + outer loop + vertex -378.447 72.0786 272.126 + vertex -377.395 71.7953 273.362 + vertex -382.787 70.5305 273.286 + endloop + endfacet + facet normal 0.214893 -0.892353 -0.396896 + outer loop + vertex -382.787 70.5305 273.286 + vertex -377.395 71.7953 273.362 + vertex -381.782 70.2424 274.477 + endloop + endfacet + facet normal 0.210246 -0.892953 -0.398034 + outer loop + vertex -379.812 72.5635 270.318 + vertex -378.447 72.0786 272.126 + vertex -384.153 71.0147 271.499 + endloop + endfacet + facet normal 0.210354 -0.891014 -0.402301 + outer loop + vertex -384.153 71.0147 271.499 + vertex -378.447 72.0786 272.126 + vertex -382.787 70.5305 273.286 + endloop + endfacet + facet normal 0.152853 -0.918102 -0.365685 + outer loop + vertex -384.153 71.0147 271.499 + vertex -382.787 70.5305 273.286 + vertex -388.221 69.8482 272.727 + endloop + endfacet + facet normal 0.151601 -0.927285 -0.342287 + outer loop + vertex -388.221 69.8482 272.727 + vertex -382.787 70.5305 273.286 + vertex -387.97 69.2629 274.424 + endloop + endfacet + facet normal 0.149422 -0.924917 -0.349573 + outer loop + vertex -382.787 70.5305 273.286 + vertex -381.782 70.2424 274.477 + vertex -387.97 69.2629 274.424 + endloop + endfacet + facet normal 0.147211 -0.908728 -0.390567 + outer loop + vertex -387.97 69.2629 274.424 + vertex -381.782 70.2424 274.477 + vertex -386.079 69.0954 275.527 + endloop + endfacet + facet normal 0.361899 -0.807862 -0.465176 + outer loop + vertex -370.404 76.1671 270.353 + vertex -369.433 75.9091 271.557 + vertex -374.344 73.9508 271.137 + endloop + endfacet + facet normal 0.359462 -0.797651 -0.484293 + outer loop + vertex -374.344 73.9508 271.137 + vertex -369.433 75.9091 271.557 + vertex -373.307 73.6663 272.375 + endloop + endfacet + facet normal 0.358123 -0.805714 -0.471777 + outer loop + vertex -371.679 76.6185 268.615 + vertex -370.404 76.1671 270.353 + vertex -375.654 74.4129 269.364 + endloop + endfacet + facet normal 0.358107 -0.804305 -0.474187 + outer loop + vertex -375.654 74.4129 269.364 + vertex -370.404 76.1671 270.353 + vertex -374.344 73.9508 271.137 + endloop + endfacet + facet normal 0.282086 -0.85677 -0.431708 + outer loop + vertex -375.654 74.4129 269.364 + vertex -374.344 73.9508 271.137 + vertex -379.812 72.5635 270.318 + endloop + endfacet + facet normal 0.282266 -0.851789 -0.44134 + outer loop + vertex -379.812 72.5635 270.318 + vertex -374.344 73.9508 271.137 + vertex -378.447 72.0786 272.126 + endloop + endfacet + facet normal 0.284932 -0.85422 -0.434881 + outer loop + vertex -374.344 73.9508 271.137 + vertex -373.307 73.6663 272.375 + vertex -378.447 72.0786 272.126 + endloop + endfacet + facet normal 0.284621 -0.852718 -0.438021 + outer loop + vertex -378.447 72.0786 272.126 + vertex -373.307 73.6663 272.375 + vertex -377.395 71.7953 273.362 + endloop + endfacet + facet normal 0.509526 -0.66869 -0.541513 + outer loop + vertex -363.333 81.8747 269.057 + vertex -362.408 81.6183 270.244 + vertex -366.696 78.8093 269.677 + endloop + endfacet + facet normal 0.50881 -0.667056 -0.544195 + outer loop + vertex -366.696 78.8093 269.677 + vertex -362.408 81.6183 270.244 + vertex -365.759 78.5545 270.866 + endloop + endfacet + facet normal 0.506981 -0.669426 -0.542992 + outer loop + vertex -364.586 82.3061 267.355 + vertex -363.333 81.8747 269.057 + vertex -367.963 79.2599 267.957 + endloop + endfacet + facet normal 0.506287 -0.666333 -0.547425 + outer loop + vertex -367.963 79.2599 267.957 + vertex -363.333 81.8747 269.057 + vertex -366.696 78.8093 269.677 + endloop + endfacet + facet normal 0.434746 -0.739523 -0.513907 + outer loop + vertex -367.963 79.2599 267.957 + vertex -366.696 78.8093 269.677 + vertex -371.679 76.6185 268.615 + endloop + endfacet + facet normal 0.434933 -0.741192 -0.511339 + outer loop + vertex -371.679 76.6185 268.615 + vertex -366.696 78.8093 269.677 + vertex -370.404 76.1671 270.353 + endloop + endfacet + facet normal 0.438003 -0.743837 -0.504836 + outer loop + vertex -366.696 78.8093 269.677 + vertex -365.759 78.5545 270.866 + vertex -370.404 76.1671 270.353 + endloop + endfacet + facet normal 0.436836 -0.740215 -0.511133 + outer loop + vertex -370.404 76.1671 270.353 + vertex -365.759 78.5545 270.866 + vertex -369.433 75.9091 271.557 + endloop + endfacet + facet normal 0.574628 -0.589067 -0.568158 + outer loop + vertex -361.649 85.6827 266.824 + vertex -360.396 85.273 268.516 + vertex -364.586 82.3061 267.355 + endloop + endfacet + facet normal 0.573871 -0.586774 -0.571286 + outer loop + vertex -364.586 82.3061 267.355 + vertex -360.396 85.273 268.516 + vertex -363.333 81.8747 269.057 + endloop + endfacet + facet normal 0.581307 -0.59125 -0.559023 + outer loop + vertex -360.396 85.273 268.516 + vertex -359.495 85.0461 269.693 + vertex -363.333 81.8747 269.057 + endloop + endfacet + facet normal 0.575927 -0.581643 -0.574456 + outer loop + vertex -363.333 81.8747 269.057 + vertex -359.495 85.0461 269.693 + vertex -362.408 81.6183 270.244 + endloop + endfacet + facet normal -0.174615 -0.979777 -0.0977039 + outer loop + vertex -471.833 69.3593 299.326 + vertex -470.179 69.2359 297.607 + vertex -464.625 68.2993 297.074 + endloop + endfacet + facet normal -0.155173 -0.981498 -0.11217 + outer loop + vertex -455.414 67.1713 294.202 + vertex -464.625 68.2993 297.074 + vertex -461.492 68.0592 294.84 + endloop + endfacet + facet normal -0.134904 -0.981144 -0.138413 + outer loop + vertex -447.172 66.3869 291.729 + vertex -455.414 67.1713 294.202 + vertex -452.731 67.074 292.277 + endloop + endfacet + facet normal -0.117186 -0.976976 -0.178287 + outer loop + vertex -438.575 65.8001 289.294 + vertex -447.172 66.3869 291.729 + vertex -443.405 66.3373 289.524 + endloop + endfacet + facet normal 0.0394626 -0.936011 -0.349752 + outer loop + vertex -394.095 68.0921 276.088 + vertex -393.897 67.4379 277.861 + vertex -403.761 66.8167 278.411 + endloop + endfacet + facet normal 0.0401318 -0.939115 -0.341251 + outer loop + vertex -403.761 66.8167 278.411 + vertex -393.897 67.4379 277.861 + vertex -404.324 66.0864 280.354 + endloop + endfacet + facet normal 0.0926178 -0.933637 -0.34604 + outer loop + vertex -386.079 69.0954 275.527 + vertex -386.731 68.7653 276.243 + vertex -394.095 68.0921 276.088 + endloop + endfacet + facet normal 0.0867974 -0.923661 -0.373252 + outer loop + vertex -385.549 68.8326 276.351 + vertex -393.897 67.4379 277.861 + vertex -386.731 68.7653 276.243 + endloop + endfacet + facet normal 0.0925164 -0.930755 -0.353744 + outer loop + vertex -393.897 67.4379 277.861 + vertex -394.095 68.0921 276.088 + vertex -386.731 68.7653 276.243 + endloop + endfacet + facet normal 0.203913 -0.879059 -0.430899 + outer loop + vertex -376.779 71.6603 274.043 + vertex -376.693 71.529 274.352 + vertex -381.239 70.0904 275.135 + endloop + endfacet + facet normal 0.212401 -0.890427 -0.402523 + outer loop + vertex -381.239 70.0904 275.135 + vertex -376.693 71.529 274.352 + vertex -381.168 69.9943 275.385 + endloop + endfacet + facet normal 0.221793 -0.898633 -0.378506 + outer loop + vertex -377.395 71.7953 273.362 + vertex -376.779 71.6603 274.043 + vertex -381.782 70.2424 274.477 + endloop + endfacet + facet normal 0.219851 -0.89484 -0.388494 + outer loop + vertex -381.782 70.2424 274.477 + vertex -376.779 71.6603 274.043 + vertex -381.239 70.0904 275.135 + endloop + endfacet + facet normal 0.16181 -0.923729 -0.347191 + outer loop + vertex -381.782 70.2424 274.477 + vertex -381.239 70.0904 275.135 + vertex -386.079 69.0954 275.527 + endloop + endfacet + facet normal 0.171633 -0.944763 -0.279222 + outer loop + vertex -386.079 69.0954 275.527 + vertex -381.239 70.0904 275.135 + vertex -386.731 68.7653 276.243 + endloop + endfacet + facet normal 0.140923 -0.910007 -0.389907 + outer loop + vertex -381.239 70.0904 275.135 + vertex -381.168 69.9943 275.385 + vertex -386.731 68.7653 276.243 + endloop + endfacet + facet normal 0.0977346 -0.827908 -0.552283 + outer loop + vertex -386.731 68.7653 276.243 + vertex -381.168 69.9943 275.385 + vertex -385.549 68.8326 276.351 + endloop + endfacet + facet normal 0.329964 -0.769296 -0.54709 + outer loop + vertex -368.815 75.7811 272.236 + vertex -368.734 75.597 272.544 + vertex -372.676 73.538 273.062 + endloop + endfacet + facet normal 0.347126 -0.791198 -0.503498 + outer loop + vertex -372.676 73.538 273.062 + vertex -368.734 75.597 272.544 + vertex -372.57 73.3804 273.383 + endloop + endfacet + facet normal 0.361569 -0.799561 -0.479552 + outer loop + vertex -369.433 75.9091 271.557 + vertex -368.815 75.7811 272.236 + vertex -373.307 73.6663 272.375 + endloop + endfacet + facet normal 0.36111 -0.798702 -0.481326 + outer loop + vertex -373.307 73.6663 272.375 + vertex -368.815 75.7811 272.236 + vertex -372.676 73.538 273.062 + endloop + endfacet + facet normal 0.289422 -0.85703 -0.426302 + outer loop + vertex -373.307 73.6663 272.375 + vertex -372.676 73.538 273.062 + vertex -377.395 71.7953 273.362 + endloop + endfacet + facet normal 0.288546 -0.85534 -0.430272 + outer loop + vertex -377.395 71.7953 273.362 + vertex -372.676 73.538 273.062 + vertex -376.779 71.6603 274.043 + endloop + endfacet + facet normal 0.261419 -0.829311 -0.493866 + outer loop + vertex -372.676 73.538 273.062 + vertex -372.57 73.3804 273.383 + vertex -376.779 71.6603 274.043 + endloop + endfacet + facet normal 0.27942 -0.85299 -0.440832 + outer loop + vertex -376.779 71.6603 274.043 + vertex -372.57 73.3804 273.383 + vertex -376.693 71.529 274.352 + endloop + endfacet + facet normal 0.47 -0.634175 -0.61394 + outer loop + vertex -361.859 81.5218 270.896 + vertex -361.657 81.4111 271.165 + vertex -365.181 78.452 271.524 + endloop + endfacet + facet normal 0.483389 -0.647155 -0.589513 + outer loop + vertex -365.181 78.452 271.524 + vertex -361.657 81.4111 271.165 + vertex -365.05 78.2896 271.809 + endloop + endfacet + facet normal 0.515062 -0.671554 -0.53266 + outer loop + vertex -362.408 81.6183 270.244 + vertex -361.859 81.5218 270.896 + vertex -365.759 78.5545 270.866 + endloop + endfacet + facet normal 0.50842 -0.662648 -0.549915 + outer loop + vertex -365.759 78.5545 270.866 + vertex -361.859 81.5218 270.896 + vertex -365.181 78.452 271.524 + endloop + endfacet + facet normal 0.44072 -0.743482 -0.502992 + outer loop + vertex -365.759 78.5545 270.866 + vertex -365.181 78.452 271.524 + vertex -369.433 75.9091 271.557 + endloop + endfacet + facet normal 0.432057 -0.729354 -0.530443 + outer loop + vertex -369.433 75.9091 271.557 + vertex -365.181 78.452 271.524 + vertex -368.815 75.7811 272.236 + endloop + endfacet + facet normal 0.402767 -0.704025 -0.584917 + outer loop + vertex -365.181 78.452 271.524 + vertex -365.05 78.2896 271.809 + vertex -368.815 75.7811 272.236 + endloop + endfacet + facet normal 0.421315 -0.725042 -0.5448 + outer loop + vertex -368.815 75.7811 272.236 + vertex -365.05 78.2896 271.809 + vertex -368.734 75.597 272.544 + endloop + endfacet + facet normal 0.57843 -0.583123 -0.570427 + outer loop + vertex -359.495 85.0461 269.693 + vertex -358.953 84.9342 270.357 + vertex -362.408 81.6183 270.244 + endloop + endfacet + facet normal 0.577653 -0.582257 -0.572096 + outer loop + vertex -362.408 81.6183 270.244 + vertex -358.953 84.9342 270.357 + vertex -361.859 81.5218 270.896 + endloop + endfacet + facet normal 0.542146 -0.560535 -0.626002 + outer loop + vertex -358.953 84.9342 270.357 + vertex -358.785 84.8009 270.622 + vertex -361.859 81.5218 270.896 + endloop + endfacet + facet normal 0.537707 -0.556959 -0.632983 + outer loop + vertex -361.859 81.5218 270.896 + vertex -358.785 84.8009 270.622 + vertex -361.657 81.4111 271.165 + endloop + endfacet + facet normal -0.0365145 -0.482604 -0.875077 + outer loop + vertex -376.693 71.529 274.352 + vertex -377.311 71.2552 274.528 + vertex -381.168 69.9943 275.385 + endloop + endfacet + facet normal -0.104391 -0.320156 -0.941596 + outer loop + vertex -381.168 69.9943 275.385 + vertex -377.311 71.2552 274.528 + vertex -381.3 69.8768 275.439 + endloop + endfacet + facet normal -0.131409 -0.292418 -0.947219 + outer loop + vertex -381.168 69.9943 275.385 + vertex -381.3 69.8768 275.439 + vertex -385.549 68.8326 276.351 + endloop + endfacet + facet normal -0.16098 -0.190583 -0.968382 + outer loop + vertex -385.549 68.8326 276.351 + vertex -381.3 69.8768 275.439 + vertex -384.04 69.0966 276.048 + endloop + endfacet + facet normal 0.0703733 -0.457164 -0.886594 + outer loop + vertex -368.734 75.597 272.544 + vertex -369.352 75.1029 272.75 + vertex -372.57 73.3804 273.383 + endloop + endfacet + facet normal 0.399412 -0.861357 -0.313901 + outer loop + vertex -372.57 73.3804 273.383 + vertex -369.352 75.1029 272.75 + vertex -373.211 73.0065 273.593 + endloop + endfacet + facet normal 0.0624324 -0.568447 -0.820348 + outer loop + vertex -372.57 73.3804 273.383 + vertex -373.211 73.0065 273.593 + vertex -376.693 71.529 274.352 + endloop + endfacet + facet normal 0.333702 -0.910943 -0.242539 + outer loop + vertex -376.693 71.529 274.352 + vertex -373.211 73.0065 273.593 + vertex -377.311 71.2552 274.528 + endloop + endfacet + facet normal 0.0773806 -0.281634 -0.956397 + outer loop + vertex -361.657 81.4111 271.165 + vertex -361.96 80.9727 271.269 + vertex -365.05 78.2896 271.809 + endloop + endfacet + facet normal 0.448883 -0.642007 -0.621556 + outer loop + vertex -365.05 78.2896 271.809 + vertex -361.96 80.9727 271.269 + vertex -365.705 77.6443 272.003 + endloop + endfacet + facet normal 0.0702895 -0.350921 -0.933763 + outer loop + vertex -365.05 78.2896 271.809 + vertex -365.705 77.6443 272.003 + vertex -368.734 75.597 272.544 + endloop + endfacet + facet normal 0.384843 -0.721488 -0.575631 + outer loop + vertex -368.734 75.597 272.544 + vertex -365.705 77.6443 272.003 + vertex -369.352 75.1029 272.75 + endloop + endfacet + facet normal 0.153203 -0.281567 -0.947232 + outer loop + vertex -358.785 84.8009 270.622 + vertex -358.91 84.4751 270.698 + vertex -361.657 81.4111 271.165 + endloop + endfacet + facet normal 0.348711 -0.438726 -0.828203 + outer loop + vertex -361.657 81.4111 271.165 + vertex -358.91 84.4751 270.698 + vertex -361.96 80.9727 271.269 + endloop + endfacet + facet normal 0.953423 -0.236687 0.186985 + outer loop + vertex -422.621 127.202 69.0046 + vertex -421.713 130.924 69.0862 + vertex -422.931 127.265 70.6626 + endloop + endfacet + facet normal 0.949483 -0.25214 0.186834 + outer loop + vertex -423.125 125.318 69.0198 + vertex -422.621 127.202 69.0046 + vertex -422.931 127.265 70.6626 + endloop + endfacet + facet normal 0.938962 -0.271603 0.211147 + outer loop + vertex -424.284 121.405 69.1435 + vertex -423.125 125.318 69.0198 + vertex -422.931 127.265 70.6626 + endloop + endfacet + facet normal 0.940706 -0.275163 0.198388 + outer loop + vertex -425.509 117.193 69.1083 + vertex -424.284 121.405 69.1435 + vertex -425.735 117.637 70.7975 + endloop + endfacet + facet normal 0.930338 -0.304284 0.204653 + outer loop + vertex -426.434 114.236 68.9178 + vertex -425.509 117.193 69.1083 + vertex -425.735 117.637 70.7975 + endloop + endfacet + facet normal 0.914503 -0.332071 0.231114 + outer loop + vertex -427.721 110.223 68.2425 + vertex -426.434 114.236 68.9178 + vertex -427.799 110.465 68.9023 + endloop + endfacet + facet normal 0.845504 -0.254651 -0.469336 + outer loop + vertex -428.862 107.101 67.8793 + vertex -427.721 110.223 68.2425 + vertex -428.257 108.637 68.1367 + endloop + endfacet + facet normal 0.871636 -0.431767 0.232008 + outer loop + vertex -430.606 103.355 67.4573 + vertex -428.862 107.101 67.8793 + vertex -429.258 106.355 67.9773 + endloop + endfacet + facet normal 0.866309 -0.484248 0.122526 + outer loop + vertex -433.2 98.5256 66.7107 + vertex -430.606 103.355 67.4573 + vertex -431.128 102.456 67.5954 + endloop + endfacet + facet normal 0.849002 -0.528364 -0.00520777 + outer loop + vertex -435.946 94.1219 65.7604 + vertex -433.2 98.5256 66.7107 + vertex -434.678 96.1526 66.5519 + endloop + endfacet + facet normal 0.78963 -0.607371 0.0870977 + outer loop + vertex -438.354 90.864 64.8733 + vertex -435.946 94.1219 65.7604 + vertex -436.881 92.9104 65.7834 + endloop + endfacet + facet normal 0.709771 -0.677454 0.193085 + outer loop + vertex -440.209 88.7546 64.2888 + vertex -438.354 90.864 64.8733 + vertex -438.925 90.3486 65.1634 + endloop + endfacet + facet normal 0.611582 -0.74792 0.258037 + outer loop + vertex -442.386 86.7195 63.5504 + vertex -440.209 88.7546 64.2888 + vertex -441.039 88.3236 65.0075 + endloop + endfacet + facet normal 0.556817 -0.789754 0.257377 + outer loop + vertex -445.302 84.3246 62.5116 + vertex -442.386 86.7195 63.5504 + vertex -443.872 85.8956 64.2384 + endloop + endfacet + facet normal 0.491595 -0.824484 0.280287 + outer loop + vertex -447.945 82.3518 61.3426 + vertex -445.302 84.3246 62.5116 + vertex -447.75 83.3048 63.8043 + endloop + endfacet + facet normal 0.424506 -0.855164 0.297471 + outer loop + vertex -450.171 81.1098 60.9486 + vertex -447.945 82.3518 61.3426 + vertex -447.75 83.3048 63.8043 + endloop + endfacet + facet normal 0.385964 -0.879242 0.279223 + outer loop + vertex -453.29 79.2621 59.4419 + vertex -450.171 81.1098 60.9486 + vertex -452.404 80.5624 62.3125 + endloop + endfacet + facet normal 0.317814 -0.89171 0.322254 + outer loop + vertex -456.272 77.5985 57.78 + vertex -453.29 79.2621 59.4419 + vertex -457.132 77.9972 59.7308 + endloop + endfacet + facet normal 0.272229 -0.912162 0.306353 + outer loop + vertex -459.24 76.2785 56.4868 + vertex -456.272 77.5985 57.78 + vertex -457.132 77.9972 59.7308 + endloop + endfacet + facet normal 0.194928 -0.845392 0.497309 + outer loop + vertex -501.349 70.4326 45.1838 + vertex -499.755 69.0167 42.1523 + vertex -500.066 69.4144 42.9501 + endloop + endfacet + facet normal -0.0491294 -0.92988 0.364569 + outer loop + vertex -503.061 72.1838 49.4197 + vertex -501.349 70.4326 45.1838 + vertex -501.827 71.2832 47.2889 + endloop + endfacet + facet normal -0.0710732 -0.942828 0.325614 + outer loop + vertex -504.473 73.8329 53.8865 + vertex -503.061 72.1838 49.4197 + vertex -503.488 73.1043 51.9919 + endloop + endfacet + facet normal -0.0731675 -0.952485 0.295667 + outer loop + vertex -505.497 75.2679 58.2559 + vertex -504.473 73.8329 53.8865 + vertex -504.764 74.6637 56.491 + endloop + endfacet + facet normal -0.0797846 -0.95954 0.270031 + outer loop + vertex -506.148 76.4215 62.163 + vertex -505.497 75.2679 58.2559 + vertex -505.653 75.9638 60.6825 + endloop + endfacet + facet normal -0.237449 -0.927274 -0.289451 + outer loop + vertex -466.815 68.5065 298.24 + vertex -470.401 69.0413 299.468 + vertex -471.411 69.2361 299.673 + endloop + endfacet + facet normal -0.193335 -0.962133 -0.192149 + outer loop + vertex -462.608 67.9161 296.963 + vertex -466.815 68.5065 298.24 + vertex -464.625 68.2993 297.074 + endloop + endfacet + facet normal -0.193923 -0.950462 -0.242932 + outer loop + vertex -458.682 67.44 295.691 + vertex -462.608 67.9161 296.963 + vertex -464.625 68.2993 297.074 + endloop + endfacet + facet normal -0.169163 -0.965733 -0.196832 + outer loop + vertex -454.183 66.9104 294.424 + vertex -458.682 67.44 295.691 + vertex -455.414 67.1713 294.202 + endloop + endfacet + facet normal -0.163952 -0.961469 -0.220674 + outer loop + vertex -450.457 66.5503 293.224 + vertex -454.183 66.9104 294.424 + vertex -455.414 67.1713 294.202 + endloop + endfacet + facet normal -0.159868 -0.955807 -0.24673 + outer loop + vertex -447.487 66.2752 292.365 + vertex -450.457 66.5503 293.224 + vertex -447.172 66.3869 291.729 + endloop + endfacet + facet normal -0.139854 -0.961196 -0.237786 + outer loop + vertex -443.825 66.013 291.272 + vertex -447.487 66.2752 292.365 + vertex -447.172 66.3869 291.729 + endloop + endfacet + facet normal -0.167259 -0.923774 -0.34448 + outer loop + vertex -440.076 65.7541 290.146 + vertex -443.825 66.013 291.272 + vertex -438.575 65.8001 289.294 + endloop + endfacet + facet normal -0.128309 -0.952146 -0.277406 + outer loop + vertex -437.3 65.5928 289.415 + vertex -440.076 65.7541 290.146 + vertex -438.575 65.8001 289.294 + endloop + endfacet + facet normal -0.125697 -0.946917 -0.295886 + outer loop + vertex -433.527 65.4537 288.258 + vertex -437.3 65.5928 289.415 + vertex -438.575 65.8001 289.294 + endloop + endfacet + facet normal -0.105885 -0.951368 -0.289288 + outer loop + vertex -429.397 65.2937 287.272 + vertex -433.527 65.4537 288.258 + vertex -429.885 65.4735 286.859 + endloop + endfacet + facet normal -0.0982187 -0.949628 -0.297591 + outer loop + vertex -425.201 65.2355 286.073 + vertex -429.397 65.2937 287.272 + vertex -429.885 65.4735 286.859 + endloop + endfacet + facet normal -0.086667 -0.947057 -0.309146 + outer loop + vertex -421.37 65.178 285.175 + vertex -425.201 65.2355 286.073 + vertex -421.161 65.3428 284.612 + endloop + endfacet + facet normal -0.082932 -0.947775 -0.307969 + outer loop + vertex -418.714 65.1863 284.434 + vertex -421.37 65.178 285.175 + vertex -421.161 65.3428 284.612 + endloop + endfacet + facet normal -0.0870879 -0.914823 -0.394353 + outer loop + vertex -416.214 65.2385 283.761 + vertex -418.714 65.1863 284.434 + vertex -421.161 65.3428 284.612 + endloop + endfacet + facet normal -0.0636222 -0.930175 -0.361561 + outer loop + vertex -412.645 65.3213 282.92 + vertex -416.214 65.2385 283.761 + vertex -413.053 65.5181 282.486 + endloop + endfacet + facet normal -0.0500712 -0.926601 -0.372697 + outer loop + vertex -408.482 65.5527 281.786 + vertex -412.645 65.3213 282.92 + vertex -413.053 65.5181 282.486 + endloop + endfacet + facet normal -0.0362733 -0.89729 -0.439949 + outer loop + vertex -404.293 65.8472 280.84 + vertex -408.482 65.5527 281.786 + vertex -404.324 66.0864 280.354 + endloop + endfacet + facet normal -0.00360174 -0.897047 -0.44192 + outer loop + vertex -398.148 66.5694 279.323 + vertex -404.293 65.8472 280.84 + vertex -404.324 66.0864 280.354 + endloop + endfacet + facet normal 0.00380289 -0.864593 -0.502458 + outer loop + vertex -392.892 67.3309 278.053 + vertex -398.148 66.5694 279.323 + vertex -393.897 67.4379 277.861 + endloop + endfacet + facet normal 0.0228799 -0.817145 -0.575978 + outer loop + vertex -387.443 68.3761 276.786 + vertex -392.892 67.3309 278.053 + vertex -393.897 67.4379 277.861 + endloop + endfacet + facet normal 0.0636497 0.551481 0.831756 + outer loop + vertex -382.603 69.5052 275.667 + vertex -387.443 68.3761 276.786 + vertex -384.04 69.0966 276.048 + endloop + endfacet + facet normal -0.141824 0.828944 0.541053 + outer loop + vertex -378.792 70.7193 274.806 + vertex -382.603 69.5052 275.667 + vertex -381.3 69.8768 275.439 + endloop + endfacet + facet normal -0.144756 0.740121 0.656709 + outer loop + vertex -374.769 72.2987 273.913 + vertex -378.792 70.7193 274.806 + vertex -377.311 71.2552 274.528 + endloop + endfacet + facet normal 0.0489231 0.320173 0.946095 + outer loop + vertex -370.86 74.2099 273.064 + vertex -374.769 72.2987 273.913 + vertex -373.211 73.0065 273.593 + endloop + endfacet + facet normal 0.180489 0.0412207 0.982713 + outer loop + vertex -367.235 76.4633 272.304 + vertex -370.86 74.2099 273.064 + vertex -369.352 75.1029 272.75 + endloop + endfacet + facet normal -0.431635 0.703021 0.565202 + outer loop + vertex -363.913 79.0435 271.631 + vertex -367.235 76.4633 272.304 + vertex -365.705 77.6443 272.003 + endloop + endfacet + facet normal -0.40308 0.24241 -0.882476 + outer loop + vertex -361.417 81.3853 271.134 + vertex -363.913 79.0435 271.631 + vertex -361.96 80.9727 271.269 + endloop + endfacet + facet normal -0.337381 0.139934 -0.93091 + outer loop + vertex -359.302 83.8704 270.741 + vertex -361.417 81.3853 271.134 + vertex -361.96 80.9727 271.269 + endloop + endfacet + facet normal -0.673023 0.391077 -0.627773 + outer loop + vertex -357.002 87.1707 270.332 + vertex -359.302 83.8704 270.741 + vertex -358.91 84.4751 270.698 + endloop + endfacet + facet normal -0.78031 0.487097 0.392241 + outer loop + vertex -355.282 90.151 270.053 + vertex -357.002 87.1707 270.332 + vertex -356.564 87.914 270.279 + endloop + endfacet + facet normal -0.899059 0.402003 -0.173455 + outer loop + vertex -353.905 93.144 269.854 + vertex -355.282 90.151 270.053 + vertex -354.658 91.5128 269.976 + endloop + endfacet + facet normal -0.783906 0.286563 -0.550793 + outer loop + vertex -352.697 96.1285 269.687 + vertex -353.905 93.144 269.854 + vertex -352.859 95.7808 269.736 + endloop + endfacet + facet normal -0.611743 0.17555 -0.771332 + outer loop + vertex -351.761 98.893 269.574 + vertex -352.697 96.1285 269.687 + vertex -352.859 95.7808 269.736 + endloop + endfacet + facet normal -0.888134 0.265898 0.374855 + outer loop + vertex -350.851 102.059 269.485 + vertex -351.761 98.893 269.574 + vertex -351.48 99.8057 269.592 + endloop + endfacet + facet normal -0.667803 0.16617 0.725553 + outer loop + vertex -349.967 105.719 269.46 + vertex -350.851 102.059 269.485 + vertex -350.549 103.123 269.518 + endloop + endfacet + facet normal -0.0785851 0.0128586 -0.996824 + outer loop + vertex -349.103 109.765 269.444 + vertex -349.967 105.719 269.46 + vertex -349.972 105.923 269.462 + endloop + endfacet + facet normal 0.764059 -0.584102 0.273933 + outer loop + vertex -434.678 96.1526 66.5519 + vertex -436.881 92.9104 65.7834 + vertex -435.946 94.1219 65.7604 + endloop + endfacet + facet normal 0.717583 -0.639473 0.275952 + outer loop + vertex -436.881 92.9104 65.7834 + vertex -438.925 90.3486 65.1634 + vertex -438.354 90.864 64.8733 + endloop + endfacet + facet normal 0.660332 -0.708467 0.24907 + outer loop + vertex -438.925 90.3486 65.1634 + vertex -439.295 90.3419 66.1259 + vertex -441.039 88.3236 65.0075 + endloop + endfacet + facet normal 0.880968 -0.471978 0.0336623 + outer loop + vertex -431.128 102.456 67.5954 + vertex -432.827 99.2571 67.2233 + vertex -433.2 98.5256 66.7107 + endloop + endfacet + facet normal 0.834743 -0.52986 0.149843 + outer loop + vertex -432.827 99.2571 67.2233 + vertex -434.678 96.1526 66.5519 + vertex -433.2 98.5256 66.7107 + endloop + endfacet + facet normal 0.836611 -0.393633 0.380967 + outer loop + vertex -428.257 108.637 68.1367 + vertex -429.258 106.355 67.9773 + vertex -428.862 107.101 67.8793 + endloop + endfacet + facet normal 0.835964 -0.433791 0.336139 + outer loop + vertex -429.258 106.355 67.9773 + vertex -431.128 102.456 67.5954 + vertex -430.606 103.355 67.4573 + endloop + endfacet + facet normal 0.243855 -0.913547 0.325526 + outer loop + vertex -457.132 77.9972 59.7308 + vertex -460.31 76.1114 56.8191 + vertex -459.24 76.2785 56.4868 + endloop + endfacet + facet normal 0.318337 -0.896569 0.307937 + outer loop + vertex -452.404 80.5624 62.3125 + vertex -457.132 77.9972 59.7308 + vertex -453.29 79.2621 59.4419 + endloop + endfacet + facet normal 0.403926 -0.858059 0.317141 + outer loop + vertex -447.75 83.3048 63.8043 + vertex -452.404 80.5624 62.3125 + vertex -450.171 81.1098 60.9486 + endloop + endfacet + facet normal 0.502343 -0.80479 0.316171 + outer loop + vertex -443.872 85.8956 64.2384 + vertex -447.75 83.3048 63.8043 + vertex -445.302 84.3246 62.5116 + endloop + endfacet + facet normal 0.567244 -0.761397 0.313861 + outer loop + vertex -441.039 88.3236 65.0075 + vertex -443.872 85.8956 64.2384 + vertex -442.386 86.7195 63.5504 + endloop + endfacet + facet normal 0.907806 -0.329762 0.259124 + outer loop + vertex -425.735 117.637 70.7975 + vertex -427.799 110.465 68.9023 + vertex -426.434 114.236 68.9178 + endloop + endfacet + facet normal 0.939983 -0.27089 0.207488 + outer loop + vertex -422.931 127.265 70.6626 + vertex -425.735 117.637 70.7975 + vertex -424.284 121.405 69.1435 + endloop + endfacet + facet normal 0.954043 -0.240332 0.179003 + outer loop + vertex -420.636 136.479 70.8041 + vertex -422.931 127.265 70.6626 + vertex -421.713 130.924 69.0862 + endloop + endfacet + facet normal 0.0487688 -0.952026 -0.302108 + outer loop + vertex -405.772 67.7907 275.153 + vertex -396.256 69.0374 272.76 + vertex -394.095 68.0921 276.088 + endloop + endfacet + facet normal 0.0931602 -0.9369 -0.336955 + outer loop + vertex -396.256 69.0374 272.76 + vertex -388.221 69.8482 272.727 + vertex -387.97 69.2629 274.424 + endloop + endfacet + facet normal 0.0967086 -0.945936 -0.3096 + outer loop + vertex -387.97 69.2629 274.424 + vertex -386.079 69.0954 275.527 + vertex -394.095 68.0921 276.088 + endloop + endfacet + facet normal -0.23289 -0.93384 -0.271488 + outer loop + vertex -471.411 69.2361 299.673 + vertex -464.625 68.2993 297.074 + vertex -466.815 68.5065 298.24 + endloop + endfacet + facet normal -0.197809 -0.944143 -0.263561 + outer loop + vertex -464.625 68.2993 297.074 + vertex -455.414 67.1713 294.202 + vertex -458.682 67.44 295.691 + endloop + endfacet + facet normal -0.172957 -0.945284 -0.276631 + outer loop + vertex -455.414 67.1713 294.202 + vertex -447.172 66.3869 291.729 + vertex -450.457 66.5503 293.224 + endloop + endfacet + facet normal -0.144381 -0.948762 -0.281078 + outer loop + vertex -447.172 66.3869 291.729 + vertex -438.575 65.8001 289.294 + vertex -443.825 66.013 291.272 + endloop + endfacet + facet normal -0.140552 -0.914629 -0.379076 + outer loop + vertex -438.575 65.8001 289.294 + vertex -429.885 65.4735 286.859 + vertex -433.527 65.4537 288.258 + endloop + endfacet + facet normal -0.108788 -0.923217 -0.368557 + outer loop + vertex -429.885 65.4735 286.859 + vertex -421.161 65.3428 284.612 + vertex -425.201 65.2355 286.073 + endloop + endfacet + facet normal -0.0921743 -0.900141 -0.425736 + outer loop + vertex -421.161 65.3428 284.612 + vertex -413.053 65.5181 282.486 + vertex -416.214 65.2385 283.761 + endloop + endfacet + facet normal -0.0752359 -0.842869 -0.532834 + outer loop + vertex -413.053 65.5181 282.486 + vertex -404.324 66.0864 280.354 + vertex -408.482 65.5527 281.786 + endloop + endfacet + facet normal 0.049627 -0.948096 -0.314088 + outer loop + vertex -394.095 68.0921 276.088 + vertex -403.761 66.8167 278.411 + vertex -405.772 67.7907 275.153 + endloop + endfacet + facet normal -0.0330787 -0.814153 -0.579707 + outer loop + vertex -404.324 66.0864 280.354 + vertex -393.897 67.4379 277.861 + vertex -398.148 66.5694 279.323 + endloop + endfacet + facet normal -0.0584959 -0.551066 -0.832409 + outer loop + vertex -393.897 67.4379 277.861 + vertex -385.549 68.8326 276.351 + vertex -387.443 68.3761 276.786 + endloop + endfacet + facet normal 0.496478 -0.116434 -0.860205 + outer loop + vertex -349.972 105.923 269.462 + vertex -348.636 112.905 269.289 + vertex -349.103 109.765 269.444 + endloop + endfacet + facet normal -0.37603 0.859691 -0.345734 + outer loop + vertex -381.3 69.8768 275.439 + vertex -377.311 71.2552 274.528 + vertex -378.792 70.7193 274.806 + endloop + endfacet + facet normal -0.112261 -0.401116 -0.909122 + outer loop + vertex -385.549 68.8326 276.351 + vertex -384.04 69.0966 276.048 + vertex -387.443 68.3761 276.786 + endloop + endfacet + facet normal -0.276275 0.96101 -0.0114978 + outer loop + vertex -384.04 69.0966 276.048 + vertex -381.3 69.8768 275.439 + vertex -382.603 69.5052 275.667 + endloop + endfacet + facet normal -0.306874 0.189717 -0.93265 + outer loop + vertex -373.211 73.0065 273.593 + vertex -369.352 75.1029 272.75 + vertex -370.86 74.2099 273.064 + endloop + endfacet + facet normal -0.409454 0.584475 -0.700526 + outer loop + vertex -377.311 71.2552 274.528 + vertex -373.211 73.0065 273.593 + vertex -374.769 72.2987 273.913 + endloop + endfacet + facet normal -0.276666 0.100743 -0.955671 + outer loop + vertex -365.705 77.6443 272.003 + vertex -361.96 80.9727 271.269 + vertex -363.913 79.0435 271.631 + endloop + endfacet + facet normal -0.266892 0.101258 -0.958392 + outer loop + vertex -369.352 75.1029 272.75 + vertex -365.705 77.6443 272.003 + vertex -367.235 76.4633 272.304 + endloop + endfacet + facet normal -0.469226 0.215729 -0.856322 + outer loop + vertex -358.91 84.4751 270.698 + vertex -356.564 87.914 270.279 + vertex -357.002 87.1707 270.332 + endloop + endfacet + facet normal -0.374168 0.177456 -0.910224 + outer loop + vertex -361.96 80.9727 271.269 + vertex -358.91 84.4751 270.698 + vertex -359.302 83.8704 270.741 + endloop + endfacet + facet normal -0.424609 0.128558 -0.896203 + outer loop + vertex -354.658 91.5128 269.976 + vertex -352.859 95.7808 269.736 + vertex -353.905 93.144 269.854 + endloop + endfacet + facet normal -0.362553 0.11423 -0.924936 + outer loop + vertex -356.564 87.914 270.279 + vertex -354.658 91.5128 269.976 + vertex -355.282 90.151 270.053 + endloop + endfacet + facet normal -0.96141 0.270833 0.0483857 + outer loop + vertex -351.48 99.8057 269.592 + vertex -350.549 103.123 269.518 + vertex -350.851 102.059 269.485 + endloop + endfacet + facet normal -0.818118 0.261877 -0.51196 + outer loop + vertex -352.859 95.7808 269.736 + vertex -351.48 99.8057 269.592 + vertex -351.761 98.893 269.574 + endloop + endfacet + facet normal 0.641705 -0.694841 0.32467 + outer loop + vertex -440.209 88.7546 64.2888 + vertex -438.925 90.3486 65.1634 + vertex -441.039 88.3236 65.0075 + endloop + endfacet + facet normal 0.0911551 -0.940812 -0.32644 + outer loop + vertex -394.095 68.0921 276.088 + vertex -396.256 69.0374 272.76 + vertex -387.97 69.2629 274.424 + endloop + endfacet + facet normal -0.0677164 -0.608976 0.790293 + outer loop + vertex -844.592 241.461 46.1852 + vertex -845.138 241.915 46.4882 + vertex -845.174 240.98 45.7648 + endloop + endfacet + facet normal -0.104616 -0.650851 0.751963 + outer loop + vertex -845.28 242.3 46.8022 + vertex -845.808 241.951 46.4259 + vertex -845.138 241.915 46.4882 + endloop + endfacet + facet normal -0.105607 -0.606031 0.788399 + outer loop + vertex -845.808 241.951 46.4259 + vertex -845.174 240.98 45.7648 + vertex -845.138 241.915 46.4882 + endloop + endfacet + facet normal -0.0973401 -0.535758 0.838742 + outer loop + vertex -841.161 237.171 43.7079 + vertex -842.186 238.259 44.2838 + vertex -841.836 237.347 43.7421 + endloop + endfacet + facet normal -0.10089 -0.546644 0.831265 + outer loop + vertex -843.022 239.495 44.9953 + vertex -843.5 239.016 44.6223 + vertex -842.186 238.259 44.2838 + endloop + endfacet + facet normal -0.0915413 -0.534428 0.840242 + outer loop + vertex -843.5 239.016 44.6223 + vertex -841.836 237.347 43.7421 + vertex -842.186 238.259 44.2838 + endloop + endfacet + facet normal -0.0884304 -0.555568 0.826755 + outer loop + vertex -843.022 239.495 44.9953 + vertex -843.972 240.524 45.5853 + vertex -843.5 239.016 44.6223 + endloop + endfacet + facet normal -0.100661 -0.583007 0.806207 + outer loop + vertex -844.592 241.461 46.1852 + vertex -845.174 240.98 45.7648 + vertex -843.972 240.524 45.5853 + endloop + endfacet + facet normal -0.0870567 -0.555333 0.827059 + outer loop + vertex -845.174 240.98 45.7648 + vertex -843.5 239.016 44.6223 + vertex -843.972 240.524 45.5853 + endloop + endfacet + facet normal 0.22456 -0.579445 0.783465 + outer loop + vertex -841.483 244.095 48.117 + vertex -840.294 245.39 48.7338 + vertex -841.713 244.379 48.3934 + endloop + endfacet + facet normal 0.208726 -0.562726 0.799858 + outer loop + vertex -841.713 244.379 48.3934 + vertex -840.294 245.39 48.7338 + vertex -840.503 245.708 49.0125 + endloop + endfacet + facet normal 0.0982413 -0.619975 0.778447 + outer loop + vertex -842.782 243.06 47.4566 + vertex -841.483 244.095 48.117 + vertex -843.053 243.365 47.7341 + endloop + endfacet + facet normal 0.114177 -0.64312 0.757205 + outer loop + vertex -843.053 243.365 47.7341 + vertex -841.483 244.095 48.117 + vertex -841.713 244.379 48.3934 + endloop + endfacet + facet normal 0.161258 -0.6788 0.716399 + outer loop + vertex -843.053 243.365 47.7341 + vertex -841.713 244.379 48.3934 + vertex -843.049 243.599 47.9543 + endloop + endfacet + facet normal 0.10682 -0.61994 0.777344 + outer loop + vertex -843.049 243.599 47.9543 + vertex -841.713 244.379 48.3934 + vertex -841.682 244.664 48.6159 + endloop + endfacet + facet normal 0.29162 -0.609144 0.737497 + outer loop + vertex -841.713 244.379 48.3934 + vertex -840.503 245.708 49.0125 + vertex -841.682 244.664 48.6159 + endloop + endfacet + facet normal 0.175869 -0.516665 0.83793 + outer loop + vertex -841.682 244.664 48.6159 + vertex -840.503 245.708 49.0125 + vertex -840.5 246.045 49.2198 + endloop + endfacet + facet normal 0.0045109 -0.619032 0.785353 + outer loop + vertex -843.945 242.195 46.7819 + vertex -842.782 243.06 47.4566 + vertex -844.304 242.582 47.0886 + endloop + endfacet + facet normal 0.0255333 -0.659637 0.751151 + outer loop + vertex -844.304 242.582 47.0886 + vertex -842.782 243.06 47.4566 + vertex -843.053 243.365 47.7341 + endloop + endfacet + facet normal -0.0555503 -0.599698 0.798296 + outer loop + vertex -844.592 241.461 46.1852 + vertex -843.945 242.195 46.7819 + vertex -845.138 241.915 46.4882 + endloop + endfacet + facet normal -0.0374704 -0.642283 0.765551 + outer loop + vertex -845.138 241.915 46.4882 + vertex -843.945 242.195 46.7819 + vertex -844.304 242.582 47.0886 + endloop + endfacet + facet normal -0.040795 -0.639825 0.767437 + outer loop + vertex -845.138 241.915 46.4882 + vertex -844.304 242.582 47.0886 + vertex -845.28 242.3 46.8022 + endloop + endfacet + facet normal -0.020126 -0.678168 0.734631 + outer loop + vertex -845.28 242.3 46.8022 + vertex -844.304 242.582 47.0886 + vertex -844.403 242.815 47.3016 + endloop + endfacet + facet normal 0.0323673 -0.665819 0.745411 + outer loop + vertex -844.304 242.582 47.0886 + vertex -843.053 243.365 47.7341 + vertex -844.403 242.815 47.3016 + endloop + endfacet + facet normal 0.0467471 -0.685955 0.726141 + outer loop + vertex -844.403 242.815 47.3016 + vertex -843.053 243.365 47.7341 + vertex -843.049 243.599 47.9543 + endloop + endfacet + facet normal 0.0208416 -0.661081 0.750025 + outer loop + vertex -844.403 242.815 47.3016 + vertex -843.049 243.599 47.9543 + vertex -844.253 243.047 47.5018 + endloop + endfacet + facet normal -0.08291 -0.517742 0.85151 + outer loop + vertex -844.253 243.047 47.5018 + vertex -843.049 243.599 47.9543 + vertex -842.723 243.984 48.2202 + endloop + endfacet + facet normal -0.112396 -0.586396 0.802189 + outer loop + vertex -845.28 242.3 46.8022 + vertex -844.403 242.815 47.3016 + vertex -845.484 242.439 46.8749 + endloop + endfacet + facet normal -0.0948767 -0.614856 0.782912 + outer loop + vertex -845.484 242.439 46.8749 + vertex -844.403 242.815 47.3016 + vertex -844.253 243.047 47.5018 + endloop + endfacet + facet normal 0.363446 -0.616216 0.698702 + outer loop + vertex -841.682 244.664 48.6159 + vertex -840.5 246.045 49.2198 + vertex -841.446 245.047 48.8309 + endloop + endfacet + facet normal 0.0389628 -0.394469 0.918083 + outer loop + vertex -841.446 245.047 48.8309 + vertex -840.5 246.045 49.2198 + vertex -840.442 246.37 49.3567 + endloop + endfacet + facet normal 0.121143 -0.631292 0.766026 + outer loop + vertex -843.049 243.599 47.9543 + vertex -841.682 244.664 48.6159 + vertex -842.723 243.984 48.2202 + endloop + endfacet + facet normal -0.0198196 -0.480022 0.877032 + outer loop + vertex -842.723 243.984 48.2202 + vertex -841.682 244.664 48.6159 + vertex -841.446 245.047 48.8309 + endloop + endfacet + facet normal 0.138835 -0.481659 0.865292 + outer loop + vertex -838.746 240.276 45.4897 + vertex -837.945 241.862 46.244 + vertex -839.704 241.669 46.4186 + endloop + endfacet + facet normal 0.138488 -0.475258 0.868879 + outer loop + vertex -839.704 241.669 46.4186 + vertex -837.945 241.862 46.244 + vertex -838.577 243.144 47.0457 + endloop + endfacet + facet normal 0.0586171 -0.495331 0.866724 + outer loop + vertex -839.995 239.064 44.8812 + vertex -838.746 240.276 45.4897 + vertex -840.805 240.377 45.6863 + endloop + endfacet + facet normal 0.0552431 -0.527465 0.847779 + outer loop + vertex -840.805 240.377 45.6863 + vertex -838.746 240.276 45.4897 + vertex -839.704 241.669 46.4186 + endloop + endfacet + facet normal 0.0316126 -0.51301 0.8578 + outer loop + vertex -840.805 240.377 45.6863 + vertex -839.704 241.669 46.4186 + vertex -841.611 241.599 46.4472 + endloop + endfacet + facet normal 0.0320427 -0.528702 0.848203 + outer loop + vertex -841.611 241.599 46.4472 + vertex -839.704 241.669 46.4186 + vertex -840.431 242.811 47.1578 + endloop + endfacet + facet normal 0.137826 -0.474884 0.869189 + outer loop + vertex -839.704 241.669 46.4186 + vertex -838.577 243.144 47.0457 + vertex -840.431 242.811 47.1578 + endloop + endfacet + facet normal 0.140306 -0.492058 0.859182 + outer loop + vertex -840.431 242.811 47.1578 + vertex -838.577 243.144 47.0457 + vertex -839.276 244.224 47.7782 + endloop + endfacet + facet normal -0.0193788 -0.513104 0.858107 + outer loop + vertex -840.503 237.807 44.1185 + vertex -839.995 239.064 44.8812 + vertex -841.677 239.21 44.9305 + endloop + endfacet + facet normal -0.0213807 -0.53221 0.846342 + outer loop + vertex -841.677 239.21 44.9305 + vertex -839.995 239.064 44.8812 + vertex -840.805 240.377 45.6863 + endloop + endfacet + facet normal -0.0504083 -0.503978 0.862245 + outer loop + vertex -841.161 237.171 43.7079 + vertex -840.503 237.807 44.1185 + vertex -842.186 238.259 44.2838 + endloop + endfacet + facet normal -0.0617767 -0.538387 0.840431 + outer loop + vertex -842.186 238.259 44.2838 + vertex -840.503 237.807 44.1185 + vertex -841.677 239.21 44.9305 + endloop + endfacet + facet normal -0.0726319 -0.533929 0.842404 + outer loop + vertex -842.186 238.259 44.2838 + vertex -841.677 239.21 44.9305 + vertex -843.022 239.495 44.9953 + endloop + endfacet + facet normal -0.0756897 -0.546454 0.834062 + outer loop + vertex -843.022 239.495 44.9953 + vertex -841.677 239.21 44.9305 + vertex -842.582 240.484 45.6831 + endloop + endfacet + facet normal -0.0332289 -0.525724 0.850006 + outer loop + vertex -841.677 239.21 44.9305 + vertex -840.805 240.377 45.6863 + vertex -842.582 240.484 45.6831 + endloop + endfacet + facet normal -0.0343271 -0.544282 0.8382 + outer loop + vertex -842.582 240.484 45.6831 + vertex -840.805 240.377 45.6863 + vertex -841.611 241.599 46.4472 + endloop + endfacet + facet normal -0.0337034 -0.54467 0.837973 + outer loop + vertex -842.582 240.484 45.6831 + vertex -841.611 241.599 46.4472 + vertex -843.359 241.51 46.3189 + endloop + endfacet + facet normal -0.0316852 -0.564892 0.824557 + outer loop + vertex -843.359 241.51 46.3189 + vertex -841.611 241.599 46.4472 + vertex -842.285 242.502 47.0398 + endloop + endfacet + facet normal -0.0745411 -0.546854 0.833903 + outer loop + vertex -843.022 239.495 44.9953 + vertex -842.582 240.484 45.6831 + vertex -843.972 240.524 45.5853 + endloop + endfacet + facet normal -0.074208 -0.5652 0.82161 + outer loop + vertex -843.972 240.524 45.5853 + vertex -842.582 240.484 45.6831 + vertex -843.359 241.51 46.3189 + endloop + endfacet + facet normal -0.0661578 -0.568842 0.819782 + outer loop + vertex -843.972 240.524 45.5853 + vertex -843.359 241.51 46.3189 + vertex -844.592 241.461 46.1852 + endloop + endfacet + facet normal -0.0630691 -0.595294 0.801029 + outer loop + vertex -844.592 241.461 46.1852 + vertex -843.359 241.51 46.3189 + vertex -843.945 242.195 46.7819 + endloop + endfacet + facet normal -0.0215208 -0.572373 0.819711 + outer loop + vertex -843.359 241.51 46.3189 + vertex -842.285 242.502 47.0398 + vertex -843.945 242.195 46.7819 + endloop + endfacet + facet normal -0.0117076 -0.605396 0.795838 + outer loop + vertex -843.945 242.195 46.7819 + vertex -842.285 242.502 47.0398 + vertex -842.782 243.06 47.4566 + endloop + endfacet + facet normal 0.142963 -0.49364 0.857835 + outer loop + vertex -840.431 242.811 47.1578 + vertex -839.276 244.224 47.7782 + vertex -841.039 243.614 47.7213 + endloop + endfacet + facet normal 0.153259 -0.521685 0.839259 + outer loop + vertex -841.039 243.614 47.7213 + vertex -839.276 244.224 47.7782 + vertex -839.872 244.945 48.3357 + endloop + endfacet + facet normal 0.0343992 -0.530341 0.847086 + outer loop + vertex -841.611 241.599 46.4472 + vertex -840.431 242.811 47.1578 + vertex -842.285 242.502 47.0398 + endloop + endfacet + facet normal 0.0392809 -0.55378 0.831736 + outer loop + vertex -842.285 242.502 47.0398 + vertex -840.431 242.811 47.1578 + vertex -841.039 243.614 47.7213 + endloop + endfacet + facet normal 0.0550668 -0.565892 0.822639 + outer loop + vertex -842.285 242.502 47.0398 + vertex -841.039 243.614 47.7213 + vertex -842.782 243.06 47.4566 + endloop + endfacet + facet normal 0.06803 -0.595915 0.800161 + outer loop + vertex -842.782 243.06 47.4566 + vertex -841.039 243.614 47.7213 + vertex -841.483 244.095 48.117 + endloop + endfacet + facet normal 0.167022 -0.53009 0.831329 + outer loop + vertex -841.039 243.614 47.7213 + vertex -839.872 244.945 48.3357 + vertex -841.483 244.095 48.117 + endloop + endfacet + facet normal 0.182475 -0.554389 0.812007 + outer loop + vertex -841.483 244.095 48.117 + vertex -839.872 244.945 48.3357 + vertex -840.294 245.39 48.7338 + endloop + endfacet + facet normal 0.134836 -0.417875 0.898443 + outer loop + vertex -837.799 238.058 44.164 + vertex -834.143 238.419 43.7832 + vertex -836.048 241.111 45.3209 + endloop + endfacet + facet normal 0.0314823 -0.373442 0.927119 + outer loop + vertex -835.662 232.446 41.5802 + vertex -835.373 235.195 42.6777 + vertex -839.248 235.871 43.0815 + endloop + endfacet + facet normal 0.014324 -0.451063 0.892377 + outer loop + vertex -839.248 235.871 43.0815 + vertex -835.373 235.195 42.6777 + vertex -837.799 238.058 44.164 + endloop + endfacet + facet normal 0.0347948 -0.528862 0.847994 + outer loop + vertex -839.995 239.064 44.8812 + vertex -840.503 237.807 44.1185 + vertex -837.799 238.058 44.164 + endloop + endfacet + facet normal -0.0562972 -0.499379 0.864552 + outer loop + vertex -841.161 237.171 43.7079 + vertex -839.248 235.871 43.0815 + vertex -840.503 237.807 44.1185 + endloop + endfacet + facet normal 0.027529 -0.45792 0.888567 + outer loop + vertex -839.248 235.871 43.0815 + vertex -837.799 238.058 44.164 + vertex -840.503 237.807 44.1185 + endloop + endfacet + facet normal 0.208284 -0.503887 0.838281 + outer loop + vertex -837.945 241.862 46.244 + vertex -838.746 240.276 45.4897 + vertex -836.048 241.111 45.3209 + endloop + endfacet + facet normal 0.057076 -0.494138 0.867508 + outer loop + vertex -839.995 239.064 44.8812 + vertex -837.799 238.058 44.164 + vertex -838.746 240.276 45.4897 + endloop + endfacet + facet normal 0.191527 -0.442014 0.876323 + outer loop + vertex -837.799 238.058 44.164 + vertex -836.048 241.111 45.3209 + vertex -838.746 240.276 45.4897 + endloop + endfacet + facet normal 0.0275274 -0.302765 0.952668 + outer loop + vertex -830.918 227.562 39.7893 + vertex -830.436 229.848 40.5021 + vertex -832.995 230.018 40.63 + endloop + endfacet + facet normal 0.0252854 -0.329796 0.943714 + outer loop + vertex -832.995 230.018 40.63 + vertex -830.436 229.848 40.5021 + vertex -832.811 232.397 41.4566 + endloop + endfacet + facet normal 0.0352904 -0.330386 0.943186 + outer loop + vertex -832.995 230.018 40.63 + vertex -832.811 232.397 41.4566 + vertex -835.662 232.446 41.5802 + endloop + endfacet + facet normal 0.0338518 -0.373628 0.926961 + outer loop + vertex -835.662 232.446 41.5802 + vertex -832.811 232.397 41.4566 + vertex -835.373 235.195 42.6777 + endloop + endfacet + facet normal -0.0163448 -0.254676 0.966888 + outer loop + vertex -825.037 221.872 38.246 + vertex -825.255 224.581 38.9558 + vertex -828.061 224.704 38.9409 + endloop + endfacet + facet normal -0.0172321 -0.275523 0.96114 + outer loop + vertex -828.061 224.704 38.9409 + vertex -825.255 224.581 38.9558 + vertex -827.957 227.289 39.6837 + endloop + endfacet + facet normal 0.00883305 -0.276524 0.960967 + outer loop + vertex -828.061 224.704 38.9409 + vertex -827.957 227.289 39.6837 + vertex -830.918 227.562 39.7893 + endloop + endfacet + facet normal 0.00654164 -0.298846 0.954279 + outer loop + vertex -830.918 227.562 39.7893 + vertex -827.957 227.289 39.6837 + vertex -830.436 229.848 40.5021 + endloop + endfacet + facet normal -0.0326704 -0.217276 0.975563 + outer loop + vertex -819.915 216.965 37.2821 + vertex -819.954 219.53 37.8523 + vertex -822.409 219.637 37.7937 + endloop + endfacet + facet normal -0.0335091 -0.239543 0.970307 + outer loop + vertex -822.409 219.637 37.7937 + vertex -819.954 219.53 37.8523 + vertex -822.645 221.91 38.3468 + endloop + endfacet + facet normal -0.0370783 -0.239862 0.970099 + outer loop + vertex -822.409 219.637 37.7937 + vertex -822.645 221.91 38.3468 + vertex -825.037 221.872 38.246 + endloop + endfacet + facet normal -0.0366492 -0.256068 0.965964 + outer loop + vertex -825.037 221.872 38.246 + vertex -822.645 221.91 38.3468 + vertex -825.255 224.581 38.9558 + endloop + endfacet + facet normal -0.0412507 -0.166974 0.985098 + outer loop + vertex -813.327 210.661 36.3894 + vertex -812.794 213.386 36.8737 + vertex -816.529 213.674 36.7661 + endloop + endfacet + facet normal -0.0427256 -0.187489 0.981337 + outer loop + vertex -816.529 213.674 36.7661 + vertex -812.794 213.386 36.8737 + vertex -816.684 216.872 37.3703 + endloop + endfacet + facet normal -0.0321669 -0.187067 0.98182 + outer loop + vertex -816.529 213.674 36.7661 + vertex -816.684 216.872 37.3703 + vertex -819.915 216.965 37.2821 + endloop + endfacet + facet normal -0.0328596 -0.217278 0.975557 + outer loop + vertex -819.915 216.965 37.2821 + vertex -816.684 216.872 37.3703 + vertex -819.954 219.53 37.8523 + endloop + endfacet + facet normal -0.0570557 -0.163836 0.984836 + outer loop + vertex -813.327 210.661 36.3894 + vertex -808.186 208.544 36.3351 + vertex -812.794 213.386 36.8737 + endloop + endfacet + facet normal -0.502433 -0.328961 0.799591 + outer loop + vertex -699.187 150.239 45.8259 + vertex -698.336 150.54 46.4842 + vertex -700.207 155.02 47.1515 + endloop + endfacet + facet normal -0.480518 -0.329777 0.812619 + outer loop + vertex -697.374 149.725 46.7224 + vertex -698.886 154.823 47.897 + vertex -698.336 150.54 46.4842 + endloop + endfacet + facet normal -0.500866 -0.328482 0.80077 + outer loop + vertex -698.886 154.823 47.897 + vertex -700.207 155.02 47.1515 + vertex -698.336 150.54 46.4842 + endloop + endfacet + facet normal -0.473134 -0.327744 0.817758 + outer loop + vertex -699.187 150.239 45.8259 + vertex -700.207 155.02 47.1515 + vertex -700.486 151.187 45.454 + endloop + endfacet + facet normal -0.494295 -0.321698 0.807578 + outer loop + vertex -700.207 155.02 47.1515 + vertex -702.229 155.507 46.1079 + vertex -700.486 151.187 45.454 + endloop + endfacet + facet normal -0.645811 -0.356219 0.675305 + outer loop + vertex -696.596 149.538 47.1194 + vertex -696.752 150.214 47.3275 + vertex -698.303 154.806 48.2666 + endloop + endfacet + facet normal -0.333834 -0.308897 0.890583 + outer loop + vertex -696.555 149.678 47.2155 + vertex -698.187 154.789 48.376 + vertex -696.752 150.214 47.3275 + endloop + endfacet + facet normal -0.670103 -0.359162 0.649588 + outer loop + vertex -698.187 154.789 48.376 + vertex -698.303 154.806 48.2666 + vertex -696.752 150.214 47.3275 + endloop + endfacet + facet normal -0.517106 -0.334886 0.787688 + outer loop + vertex -697.374 149.725 46.7224 + vertex -697.086 150.24 47.1303 + vertex -698.886 154.823 47.897 + endloop + endfacet + facet normal -0.45023 -0.326774 0.83097 + outer loop + vertex -696.596 149.538 47.1194 + vertex -698.303 154.806 48.2666 + vertex -697.086 150.24 47.1303 + endloop + endfacet + facet normal -0.511456 -0.333389 0.792 + outer loop + vertex -698.303 154.806 48.2666 + vertex -698.886 154.823 47.897 + vertex -697.086 150.24 47.1303 + endloop + endfacet + facet normal -0.94102 -0.248468 -0.229662 + outer loop + vertex -696.555 149.678 47.2155 + vertex -696.815 150.461 47.4361 + vertex -698.187 154.789 48.376 + endloop + endfacet + facet normal -0.602625 -0.366293 0.708993 + outer loop + vertex -696.562 149.872 47.3473 + vertex -698.11 154.478 48.4106 + vertex -696.815 150.461 47.4361 + endloop + endfacet + facet normal -0.94576 -0.256571 -0.199272 + outer loop + vertex -698.11 154.478 48.4106 + vertex -698.187 154.789 48.376 + vertex -696.815 150.461 47.4361 + endloop + endfacet + facet normal 0.426126 -0.381937 0.820086 + outer loop + vertex -839.253 247.065 49.2935 + vertex -838.38 249.064 49.7706 + vertex -839.423 247.488 49.5788 + endloop + endfacet + facet normal 0.341634 -0.333145 0.878806 + outer loop + vertex -839.423 247.488 49.5788 + vertex -838.38 249.064 49.7706 + vertex -838.285 250.073 50.1167 + endloop + endfacet + facet normal 0.341527 -0.481766 0.807007 + outer loop + vertex -840.294 245.39 48.7338 + vertex -839.253 247.065 49.2935 + vertex -840.503 245.708 49.0125 + endloop + endfacet + facet normal 0.297863 -0.448872 0.842491 + outer loop + vertex -840.503 245.708 49.0125 + vertex -839.253 247.065 49.2935 + vertex -839.423 247.488 49.5788 + endloop + endfacet + facet normal 0.388384 -0.485053 0.783506 + outer loop + vertex -840.503 245.708 49.0125 + vertex -839.423 247.488 49.5788 + vertex -840.5 246.045 49.2198 + endloop + endfacet + facet normal 0.277415 -0.421981 0.863118 + outer loop + vertex -840.5 246.045 49.2198 + vertex -839.423 247.488 49.5788 + vertex -839.416 247.912 49.7841 + endloop + endfacet + facet normal 0.503525 -0.382696 0.774601 + outer loop + vertex -839.423 247.488 49.5788 + vertex -838.285 250.073 50.1167 + vertex -839.416 247.912 49.7841 + endloop + endfacet + facet normal 0.594118 -0.416773 0.687986 + outer loop + vertex -839.416 247.912 49.7841 + vertex -838.285 250.073 50.1167 + vertex -838.462 250.122 50.2989 + endloop + endfacet + facet normal 0.741042 -0.438411 0.508579 + outer loop + vertex -839.416 247.912 49.7841 + vertex -838.462 250.122 50.2989 + vertex -839.351 248.19 49.9277 + endloop + endfacet + facet normal 0.910551 -0.395565 -0.120102 + outer loop + vertex -839.351 248.19 49.9277 + vertex -838.462 250.122 50.2989 + vertex -838.705 249.569 50.2779 + endloop + endfacet + facet normal 0.260803 -0.414922 0.871677 + outer loop + vertex -840.5 246.045 49.2198 + vertex -839.416 247.912 49.7841 + vertex -840.442 246.37 49.3567 + endloop + endfacet + facet normal 0.425217 -0.493014 0.75903 + outer loop + vertex -840.442 246.37 49.3567 + vertex -839.416 247.912 49.7841 + vertex -839.351 248.19 49.9277 + endloop + endfacet + facet normal 0.394413 -0.337322 0.854782 + outer loop + vertex -836.642 243.563 46.6327 + vertex -835.479 246.477 47.2466 + vertex -837.487 245.049 47.6093 + endloop + endfacet + facet normal 0.398484 -0.344226 0.850129 + outer loop + vertex -837.487 245.049 47.6093 + vertex -835.479 246.477 47.2466 + vertex -836.601 247.659 48.2509 + endloop + endfacet + facet normal 0.274283 -0.409183 0.870252 + outer loop + vertex -837.945 241.862 46.244 + vertex -836.642 243.563 46.6327 + vertex -838.577 243.144 47.0457 + endloop + endfacet + facet normal 0.274794 -0.413914 0.86785 + outer loop + vertex -838.577 243.144 47.0457 + vertex -836.642 243.563 46.6327 + vertex -837.487 245.049 47.6093 + endloop + endfacet + facet normal 0.27268 -0.413026 0.868939 + outer loop + vertex -838.577 243.144 47.0457 + vertex -837.487 245.049 47.6093 + vertex -839.276 244.224 47.7782 + endloop + endfacet + facet normal 0.283791 -0.440637 0.851646 + outer loop + vertex -839.276 244.224 47.7782 + vertex -837.487 245.049 47.6093 + vertex -838.286 245.974 48.3541 + endloop + endfacet + facet normal 0.395872 -0.343692 0.851564 + outer loop + vertex -837.487 245.049 47.6093 + vertex -836.601 247.659 48.2509 + vertex -838.286 245.974 48.3541 + endloop + endfacet + facet normal 0.425796 -0.375347 0.823294 + outer loop + vertex -838.286 245.974 48.3541 + vertex -836.601 247.659 48.2509 + vertex -837.559 247.934 48.8717 + endloop + endfacet + facet normal 0.390754 -0.36778 0.84383 + outer loop + vertex -838.286 245.974 48.3541 + vertex -837.559 247.934 48.8717 + vertex -838.871 246.604 48.8994 + endloop + endfacet + facet normal 0.373601 -0.350553 0.858798 + outer loop + vertex -838.871 246.604 48.8994 + vertex -837.559 247.934 48.8717 + vertex -837.862 248.936 49.4124 + endloop + endfacet + facet normal 0.273177 -0.436476 0.857242 + outer loop + vertex -839.276 244.224 47.7782 + vertex -838.286 245.974 48.3541 + vertex -839.872 244.945 48.3357 + endloop + endfacet + facet normal 0.28835 -0.459563 0.840033 + outer loop + vertex -839.872 244.945 48.3357 + vertex -838.286 245.974 48.3541 + vertex -838.871 246.604 48.8994 + endloop + endfacet + facet normal 0.298677 -0.463777 0.834088 + outer loop + vertex -839.872 244.945 48.3357 + vertex -838.871 246.604 48.8994 + vertex -840.294 245.39 48.7338 + endloop + endfacet + facet normal 0.299223 -0.464347 0.833575 + outer loop + vertex -840.294 245.39 48.7338 + vertex -838.871 246.604 48.8994 + vertex -839.253 247.065 49.2935 + endloop + endfacet + facet normal 0.418635 -0.364133 0.831957 + outer loop + vertex -838.871 246.604 48.8994 + vertex -837.862 248.936 49.4124 + vertex -839.253 247.065 49.2935 + endloop + endfacet + facet normal 0.456681 -0.39035 0.799418 + outer loop + vertex -839.253 247.065 49.2935 + vertex -837.862 248.936 49.4124 + vertex -838.38 249.064 49.7706 + endloop + endfacet + facet normal 0.362918 -0.328398 0.872035 + outer loop + vertex -835.479 246.477 47.2466 + vertex -836.642 243.563 46.6327 + vertex -834.269 244.616 46.0419 + endloop + endfacet + facet normal 0.265893 -0.403907 0.875305 + outer loop + vertex -837.945 241.862 46.244 + vertex -836.048 241.111 45.3209 + vertex -836.642 243.563 46.6327 + endloop + endfacet + facet normal 0.374388 -0.365328 0.852273 + outer loop + vertex -836.048 241.111 45.3209 + vertex -834.269 244.616 46.0419 + vertex -836.642 243.563 46.6327 + endloop + endfacet + facet normal -0.483258 -0.185736 0.855549 + outer loop + vertex -703.836 162.334 47.3003 + vertex -704.937 169.411 48.2149 + vertex -706.283 163 46.0625 + endloop + endfacet + facet normal -0.510198 -0.175516 0.841957 + outer loop + vertex -706.283 163 46.0625 + vertex -704.937 169.411 48.2149 + vertex -707.216 169.986 46.9536 + endloop + endfacet + facet normal -0.459062 -0.25659 0.850543 + outer loop + vertex -702.229 155.507 46.1079 + vertex -703.836 162.334 47.3003 + vertex -704.902 156.306 44.9061 + endloop + endfacet + facet normal -0.489881 -0.24556 0.836491 + outer loop + vertex -704.902 156.306 44.9061 + vertex -703.836 162.334 47.3003 + vertex -706.283 163 46.0625 + endloop + endfacet + facet normal -0.416422 -0.237508 0.8776 + outer loop + vertex -704.902 156.306 44.9061 + vertex -706.283 163 46.0625 + vertex -708.153 157.436 43.6696 + endloop + endfacet + facet normal -0.450115 -0.220863 0.865226 + outer loop + vertex -708.153 157.436 43.6696 + vertex -706.283 163 46.0625 + vertex -709.175 163.979 44.808 + endloop + endfacet + facet normal -0.440302 -0.17121 0.881375 + outer loop + vertex -706.283 163 46.0625 + vertex -707.216 169.986 46.9536 + vertex -709.175 163.979 44.808 + endloop + endfacet + facet normal -0.468619 -0.157633 0.869223 + outer loop + vertex -709.175 163.979 44.808 + vertex -707.216 169.986 46.9536 + vertex -709.859 170.719 45.6615 + endloop + endfacet + facet normal -0.531574 -0.200731 0.822883 + outer loop + vertex -700.855 162.039 49.1001 + vertex -702.119 169.33 50.0622 + vertex -702.023 162.037 48.345 + endloop + endfacet + facet normal -0.543921 -0.19908 0.815179 + outer loop + vertex -702.023 162.037 48.345 + vertex -702.119 169.33 50.0622 + vertex -703.213 169.176 49.2946 + endloop + endfacet + facet normal -0.503321 -0.273967 0.819518 + outer loop + vertex -698.886 154.823 47.897 + vertex -700.855 162.039 49.1001 + vertex -700.207 155.02 47.1515 + endloop + endfacet + facet normal -0.521967 -0.272559 0.808246 + outer loop + vertex -700.207 155.02 47.1515 + vertex -700.855 162.039 49.1001 + vertex -702.023 162.037 48.345 + endloop + endfacet + facet normal -0.492069 -0.268217 0.828208 + outer loop + vertex -700.207 155.02 47.1515 + vertex -702.023 162.037 48.345 + vertex -702.229 155.507 46.1079 + endloop + endfacet + facet normal -0.513753 -0.26351 0.816468 + outer loop + vertex -702.229 155.507 46.1079 + vertex -702.023 162.037 48.345 + vertex -703.836 162.334 47.3003 + endloop + endfacet + facet normal -0.513574 -0.196684 0.835199 + outer loop + vertex -702.023 162.037 48.345 + vertex -703.213 169.176 49.2946 + vertex -703.836 162.334 47.3003 + endloop + endfacet + facet normal -0.539642 -0.189936 0.82019 + outer loop + vertex -703.836 162.334 47.3003 + vertex -703.213 169.176 49.2946 + vertex -704.937 169.411 48.2149 + endloop + endfacet + facet normal -0.598819 -0.213771 0.771828 + outer loop + vertex -700.006 161.913 49.651 + vertex -701.311 169.165 50.6472 + vertex -700.252 162.121 49.5178 + endloop + endfacet + facet normal -0.676574 -0.214647 0.704396 + outer loop + vertex -700.252 162.121 49.5178 + vertex -701.311 169.165 50.6472 + vertex -701.557 169.478 50.5068 + endloop + endfacet + facet normal -0.680619 -0.293861 0.671121 + outer loop + vertex -698.187 154.789 48.376 + vertex -700.006 161.913 49.651 + vertex -698.303 154.806 48.2666 + endloop + endfacet + facet normal -0.634361 -0.291509 0.715966 + outer loop + vertex -698.303 154.806 48.2666 + vertex -700.006 161.913 49.651 + vertex -700.252 162.121 49.5178 + endloop + endfacet + facet normal -0.519969 -0.276783 0.808099 + outer loop + vertex -698.303 154.806 48.2666 + vertex -700.252 162.121 49.5178 + vertex -698.886 154.823 47.897 + endloop + endfacet + facet normal -0.521418 -0.276842 0.807144 + outer loop + vertex -698.886 154.823 47.897 + vertex -700.252 162.121 49.5178 + vertex -700.855 162.039 49.1001 + endloop + endfacet + facet normal -0.538274 -0.205313 0.817379 + outer loop + vertex -700.252 162.121 49.5178 + vertex -701.557 169.478 50.5068 + vertex -700.855 162.039 49.1001 + endloop + endfacet + facet normal -0.573422 -0.204099 0.79343 + outer loop + vertex -700.855 162.039 49.1001 + vertex -701.557 169.478 50.5068 + vertex -702.119 169.33 50.0622 + endloop + endfacet + facet normal -0.968118 -0.245479 -0.0498764 + outer loop + vertex -698.11 154.478 48.4106 + vertex -699.823 160.986 49.6246 + vertex -698.187 154.789 48.376 + endloop + endfacet + facet normal -0.919709 -0.171611 -0.353108 + outer loop + vertex -698.187 154.789 48.376 + vertex -699.823 160.986 49.6246 + vertex -700.006 161.913 49.651 + endloop + endfacet + facet normal -0.974009 -0.195633 0.114164 + outer loop + vertex -699.823 160.986 49.6246 + vertex -701.106 167.933 50.5819 + vertex -700.006 161.913 49.651 + endloop + endfacet + facet normal -0.975373 -0.153774 -0.158117 + outer loop + vertex -700.006 161.913 49.651 + vertex -701.106 167.933 50.5819 + vertex -701.311 169.165 50.6472 + endloop + endfacet + facet normal 0.800603 -0.212316 0.560318 + outer loop + vertex -835.286 258.978 50.8867 + vertex -834.062 265.482 51.602 + vertex -835.489 259.975 51.554 + endloop + endfacet + facet normal 0.898162 -0.235939 0.370997 + outer loop + vertex -835.489 259.975 51.554 + vertex -834.062 265.482 51.602 + vertex -834.708 263.517 51.9167 + endloop + endfacet + facet normal 0.665291 -0.252004 0.702768 + outer loop + vertex -836.845 252.658 50.0956 + vertex -835.286 258.978 50.8867 + vertex -837.017 254.105 50.7774 + endloop + endfacet + facet normal 0.728329 -0.272726 0.628616 + outer loop + vertex -837.017 254.105 50.7774 + vertex -835.286 258.978 50.8867 + vertex -835.489 259.975 51.554 + endloop + endfacet + facet normal 0.597503 -0.180929 0.781188 + outer loop + vertex -833.665 255.687 48.7324 + vertex -832.729 261.522 49.3682 + vertex -834.72 257.291 49.911 + endloop + endfacet + facet normal 0.603146 -0.184242 0.776061 + outer loop + vertex -834.72 257.291 49.911 + vertex -832.729 261.522 49.3682 + vertex -833.251 264.569 50.4973 + endloop + endfacet + facet normal 0.526233 -0.21105 0.823733 + outer loop + vertex -834.576 250.434 47.9682 + vertex -833.665 255.687 48.7324 + vertex -836.029 251.289 49.1157 + endloop + endfacet + facet normal 0.551859 -0.22667 0.802542 + outer loop + vertex -836.029 251.289 49.1157 + vertex -833.665 255.687 48.7324 + vertex -834.72 257.291 49.911 + endloop + endfacet + facet normal 0.567151 -0.228512 0.791279 + outer loop + vertex -836.029 251.289 49.1157 + vertex -834.72 257.291 49.911 + vertex -836.845 252.658 50.0956 + endloop + endfacet + facet normal 0.595972 -0.242755 0.765433 + outer loop + vertex -836.845 252.658 50.0956 + vertex -834.72 257.291 49.911 + vertex -835.286 258.978 50.8867 + endloop + endfacet + facet normal 0.666923 -0.192584 0.719809 + outer loop + vertex -834.72 257.291 49.911 + vertex -833.251 264.569 50.4973 + vertex -835.286 258.978 50.8867 + endloop + endfacet + facet normal 0.699387 -0.206882 0.684148 + outer loop + vertex -835.286 258.978 50.8867 + vertex -833.251 264.569 50.4973 + vertex -834.062 265.482 51.602 + endloop + endfacet + facet normal 0.513809 -0.151199 0.844476 + outer loop + vertex -830.533 252.402 46.0734 + vertex -829.888 258.12 46.7045 + vertex -832.245 254.154 47.4284 + endloop + endfacet + facet normal 0.52953 -0.16272 0.832538 + outer loop + vertex -832.245 254.154 47.4284 + vertex -829.888 258.12 46.7045 + vertex -831.154 260.821 48.0375 + endloop + endfacet + facet normal 0.464297 -0.182152 0.866746 + outer loop + vertex -831.489 246.852 45.4191 + vertex -830.533 252.402 46.0734 + vertex -833.142 248.882 46.731 + endloop + endfacet + facet normal 0.478565 -0.194696 0.856194 + outer loop + vertex -833.142 248.882 46.731 + vertex -830.533 252.402 46.0734 + vertex -832.245 254.154 47.4284 + endloop + endfacet + facet normal 0.509163 -0.197458 0.837713 + outer loop + vertex -833.142 248.882 46.731 + vertex -832.245 254.154 47.4284 + vertex -834.576 250.434 47.9682 + endloop + endfacet + facet normal 0.527579 -0.211154 0.822845 + outer loop + vertex -834.576 250.434 47.9682 + vertex -832.245 254.154 47.4284 + vertex -833.665 255.687 48.7324 + endloop + endfacet + facet normal 0.563591 -0.166159 0.80917 + outer loop + vertex -832.245 254.154 47.4284 + vertex -831.154 260.821 48.0375 + vertex -833.665 255.687 48.7324 + endloop + endfacet + facet normal 0.586668 -0.180103 0.789547 + outer loop + vertex -833.665 255.687 48.7324 + vertex -831.154 260.821 48.0375 + vertex -832.729 261.522 49.3682 + endloop + endfacet + facet normal 0.382005 -0.122207 0.916044 + outer loop + vertex -826.424 246.171 43.3042 + vertex -824.583 254.148 43.6006 + vertex -828.44 250.078 44.6661 + endloop + endfacet + facet normal 0.385491 -0.126029 0.914064 + outer loop + vertex -828.44 250.078 44.6661 + vertex -824.583 254.148 43.6006 + vertex -827.506 257.504 45.2961 + endloop + endfacet + facet normal 0.336137 -0.168787 0.926565 + outer loop + vertex -828.291 241.497 43.1303 + vertex -826.424 246.171 43.3042 + vertex -829.695 244.23 44.1374 + endloop + endfacet + facet normal 0.329137 -0.154872 0.931495 + outer loop + vertex -829.695 244.23 44.1374 + vertex -826.424 246.171 43.3042 + vertex -828.44 250.078 44.6661 + endloop + endfacet + facet normal 0.399455 -0.167245 0.901368 + outer loop + vertex -829.695 244.23 44.1374 + vertex -828.44 250.078 44.6661 + vertex -831.489 246.852 45.4191 + endloop + endfacet + facet normal 0.407238 -0.175801 0.896243 + outer loop + vertex -831.489 246.852 45.4191 + vertex -828.44 250.078 44.6661 + vertex -830.533 252.402 46.0734 + endloop + endfacet + facet normal 0.448395 -0.1314 0.884124 + outer loop + vertex -828.44 250.078 44.6661 + vertex -827.506 257.504 45.2961 + vertex -830.533 252.402 46.0734 + endloop + endfacet + facet normal 0.474308 -0.149294 0.867608 + outer loop + vertex -830.533 252.402 46.0734 + vertex -827.506 257.504 45.2961 + vertex -829.888 258.12 46.7045 + endloop + endfacet + facet normal 0.291159 -0.151487 0.944605 + outer loop + vertex -828.291 241.497 43.1303 + vertex -825.862 240.84 42.2763 + vertex -826.424 246.171 43.3042 + endloop + endfacet + facet normal 0.299734 -0.104417 0.948291 + outer loop + vertex -824.583 254.148 43.6006 + vertex -826.424 246.171 43.3042 + vertex -821.51 246.993 41.8415 + endloop + endfacet + facet normal 0.265083 -0.119921 0.956739 + outer loop + vertex -823.699 238.587 41.3944 + vertex -821.51 246.993 41.8415 + vertex -825.862 240.84 42.2763 + endloop + endfacet + facet normal 0.304948 -0.149262 0.9406 + outer loop + vertex -826.424 246.171 43.3042 + vertex -825.862 240.84 42.2763 + vertex -821.51 246.993 41.8415 + endloop + endfacet + facet normal -0.512478 -0.0680516 0.856 + outer loop + vertex -705.689 176.942 48.7997 + vertex -706.312 184.213 49.005 + vertex -707.865 177.423 47.5353 + endloop + endfacet + facet normal -0.523296 -0.0642195 0.849728 + outer loop + vertex -707.865 177.423 47.5353 + vertex -706.312 184.213 49.005 + vertex -708.386 186.126 47.8724 + endloop + endfacet + facet normal -0.503268 -0.116787 0.856202 + outer loop + vertex -704.937 169.411 48.2149 + vertex -705.689 176.942 48.7997 + vertex -707.216 169.986 46.9536 + endloop + endfacet + facet normal -0.517626 -0.11154 0.848306 + outer loop + vertex -707.216 169.986 46.9536 + vertex -705.689 176.942 48.7997 + vertex -707.865 177.423 47.5353 + endloop + endfacet + facet normal -0.46081 -0.10912 0.880765 + outer loop + vertex -707.216 169.986 46.9536 + vertex -707.865 177.423 47.5353 + vertex -709.859 170.719 45.6615 + endloop + endfacet + facet normal -0.476775 -0.102219 0.873062 + outer loop + vertex -709.859 170.719 45.6615 + vertex -707.865 177.423 47.5353 + vertex -710.379 178.016 46.2321 + endloop + endfacet + facet normal -0.470929 -0.0622573 0.879971 + outer loop + vertex -707.865 177.423 47.5353 + vertex -708.386 186.126 47.8724 + vertex -710.379 178.016 46.2321 + endloop + endfacet + facet normal -0.464182 -0.0646048 0.883381 + outer loop + vertex -710.379 178.016 46.2321 + vertex -708.386 186.126 47.8724 + vertex -710.914 185.171 46.4741 + endloop + endfacet + facet normal 0.72715 -0.161684 0.667166 + outer loop + vertex -834.062 265.482 51.602 + vertex -833.251 264.569 50.4973 + vertex -831.722 274.31 51.1907 + endloop + endfacet + facet normal 0.646373 -0.165292 0.744903 + outer loop + vertex -832.729 261.522 49.3682 + vertex -830.169 269.798 48.9827 + vertex -833.251 264.569 50.4973 + endloop + endfacet + facet normal 0.63305 -0.153425 0.758754 + outer loop + vertex -830.169 269.798 48.9827 + vertex -831.722 274.31 51.1907 + vertex -833.251 264.569 50.4973 + endloop + endfacet + facet normal 0.598655 -0.148562 0.78711 + outer loop + vertex -832.729 261.522 49.3682 + vertex -831.154 260.821 48.0375 + vertex -830.169 269.798 48.9827 + endloop + endfacet + facet normal 0.550418 -0.147598 0.821739 + outer loop + vertex -829.888 258.12 46.7045 + vertex -827.284 266.34 46.4369 + vertex -831.154 260.821 48.0375 + endloop + endfacet + facet normal 0.549677 -0.146898 0.82236 + outer loop + vertex -827.284 266.34 46.4369 + vertex -830.169 269.798 48.9827 + vertex -831.154 260.821 48.0375 + endloop + endfacet + facet normal 0.480989 -0.124102 0.867899 + outer loop + vertex -829.888 258.12 46.7045 + vertex -827.506 257.504 45.2961 + vertex -827.284 266.34 46.4369 + endloop + endfacet + facet normal 0.412049 -0.098727 0.905797 + outer loop + vertex -824.583 254.148 43.6006 + vertex -823.313 264.214 44.1202 + vertex -827.506 257.504 45.2961 + endloop + endfacet + facet normal 0.448932 -0.12547 0.884713 + outer loop + vertex -823.313 264.214 44.1202 + vertex -827.284 266.34 46.4369 + vertex -827.506 257.504 45.2961 + endloop + endfacet + facet normal 0.336195 -0.0861874 0.93784 + outer loop + vertex -821.51 246.993 41.8415 + vertex -819.415 260.017 42.2876 + vertex -824.583 254.148 43.6006 + endloop + endfacet + facet normal 0.341453 -0.0913512 0.935449 + outer loop + vertex -824.583 254.148 43.6006 + vertex -819.415 260.017 42.2876 + vertex -823.313 264.214 44.1202 + endloop + endfacet + facet normal 0.229623 -0.0608538 0.971375 + outer loop + vertex -815.849 243.935 40.3118 + vertex -814.821 255.408 40.7875 + vertex -821.51 246.993 41.8415 + endloop + endfacet + facet normal 0.24332 -0.0722592 0.967251 + outer loop + vertex -821.51 246.993 41.8415 + vertex -814.821 255.408 40.7875 + vertex -819.415 260.017 42.2876 + endloop + endfacet + facet normal -0.473383 -0.0355039 0.880141 + outer loop + vertex -710.914 185.171 46.4741 + vertex -708.386 186.126 47.8724 + vertex -709.82 196.787 47.5314 + endloop + endfacet + facet normal -0.504928 -0.0368173 0.862376 + outer loop + vertex -706.312 184.213 49.005 + vertex -705.887 196.03 49.7584 + vertex -708.386 186.126 47.8724 + endloop + endfacet + facet normal -0.498103 -0.039273 0.866228 + outer loop + vertex -705.887 196.03 49.7584 + vertex -709.82 196.787 47.5314 + vertex -708.386 186.126 47.8724 + endloop + endfacet + facet normal 0.652266 -0.140053 0.744939 + outer loop + vertex -830.169 269.798 48.9827 + vertex -827.976 282.101 49.3759 + vertex -831.722 274.31 51.1907 + endloop + endfacet + facet normal 0.642216 -0.132898 0.754915 + outer loop + vertex -831.722 274.31 51.1907 + vertex -827.976 282.101 49.3759 + vertex -829.473 286.114 51.3554 + endloop + endfacet + facet normal 0.568857 -0.124027 0.813031 + outer loop + vertex -827.284 266.34 46.4369 + vertex -825.407 278.402 46.9632 + vertex -830.169 269.798 48.9827 + endloop + endfacet + facet normal 0.574473 -0.128218 0.808419 + outer loop + vertex -830.169 269.798 48.9827 + vertex -825.407 278.402 46.9632 + vertex -827.976 282.101 49.3759 + endloop + endfacet + facet normal 0.461707 -0.0981911 0.881581 + outer loop + vertex -823.313 264.214 44.1202 + vertex -821.851 275.098 44.5668 + vertex -827.284 266.34 46.4369 + endloop + endfacet + facet normal 0.481095 -0.112825 0.869378 + outer loop + vertex -827.284 266.34 46.4369 + vertex -821.851 275.098 44.5668 + vertex -825.407 278.402 46.9632 + endloop + endfacet + facet normal 0.357513 -0.0744671 0.930934 + outer loop + vertex -819.415 260.017 42.2876 + vertex -817.687 271.519 42.544 + vertex -823.313 264.214 44.1202 + endloop + endfacet + facet normal 0.37305 -0.0880104 0.923627 + outer loop + vertex -823.313 264.214 44.1202 + vertex -817.687 271.519 42.544 + vertex -821.851 275.098 44.5668 + endloop + endfacet + facet normal 0.261594 -0.0528989 0.963727 + outer loop + vertex -814.821 255.408 40.7875 + vertex -813.103 267.334 40.9758 + vertex -819.415 260.017 42.2876 + endloop + endfacet + facet normal 0.271712 -0.062232 0.960364 + outer loop + vertex -819.415 260.017 42.2876 + vertex -813.103 267.334 40.9758 + vertex -817.687 271.519 42.544 + endloop + endfacet + facet normal -0.494314 -0.0107749 0.869217 + outer loop + vertex -705.887 196.03 49.7584 + vertex -706.29 212.134 49.7289 + vertex -709.82 196.787 47.5314 + endloop + endfacet + facet normal -0.486722 -0.0131284 0.873458 + outer loop + vertex -709.82 196.787 47.5314 + vertex -706.29 212.134 49.7289 + vertex -710.115 212.898 47.6087 + endloop + endfacet + facet normal 0.631398 -0.140716 0.762585 + outer loop + vertex -827.976 282.101 49.3759 + vertex -825.741 293.052 49.5456 + vertex -829.473 286.114 51.3554 + endloop + endfacet + facet normal 0.634692 -0.14333 0.759357 + outer loop + vertex -829.473 286.114 51.3554 + vertex -825.741 293.052 49.5456 + vertex -827.195 296.551 51.4218 + endloop + endfacet + facet normal 0.575487 -0.127152 0.807866 + outer loop + vertex -825.407 278.402 46.9632 + vertex -823.267 289.618 47.2044 + vertex -827.976 282.101 49.3759 + endloop + endfacet + facet normal 0.579662 -0.1308 0.80429 + outer loop + vertex -827.976 282.101 49.3759 + vertex -823.267 289.618 47.2044 + vertex -825.741 293.052 49.5456 + endloop + endfacet + facet normal 0.486004 -0.106169 0.867484 + outer loop + vertex -821.851 275.098 44.5668 + vertex -819.813 286.199 44.7835 + vertex -825.407 278.402 46.9632 + endloop + endfacet + facet normal 0.493106 -0.112615 0.86265 + outer loop + vertex -825.407 278.402 46.9632 + vertex -819.813 286.199 44.7835 + vertex -823.267 289.618 47.2044 + endloop + endfacet + facet normal 0.37964 -0.0792729 0.921732 + outer loop + vertex -817.687 271.519 42.544 + vertex -815.663 282.633 42.6662 + vertex -821.851 275.098 44.5668 + endloop + endfacet + facet normal 0.390508 -0.0895857 0.91623 + outer loop + vertex -821.851 275.098 44.5668 + vertex -815.663 282.633 42.6662 + vertex -819.813 286.199 44.7835 + endloop + endfacet + facet normal 0.277779 -0.0550982 0.959064 + outer loop + vertex -813.103 267.334 40.9758 + vertex -811.015 278.742 41.0266 + vertex -817.687 271.519 42.544 + endloop + endfacet + facet normal 0.285136 -0.0624423 0.956451 + outer loop + vertex -817.687 271.519 42.544 + vertex -811.015 278.742 41.0266 + vertex -815.663 282.633 42.6662 + endloop + endfacet + facet normal -0.484314 0.00290006 0.874889 + outer loop + vertex -706.29 212.134 49.7289 + vertex -706.174 227.635 49.7415 + vertex -710.115 212.898 47.6087 + endloop + endfacet + facet normal -0.492071 0.00560426 0.870537 + outer loop + vertex -710.115 212.898 47.6087 + vertex -706.174 227.635 49.7415 + vertex -709.906 228.236 47.6281 + endloop + endfacet + facet normal 0.615352 -0.158254 0.772203 + outer loop + vertex -825.741 293.052 49.5456 + vertex -823.262 302.945 49.598 + vertex -827.195 296.551 51.4218 + endloop + endfacet + facet normal 0.625873 -0.16773 0.761675 + outer loop + vertex -827.195 296.551 51.4218 + vertex -823.262 302.945 49.598 + vertex -824.653 306.009 51.4156 + endloop + endfacet + facet normal 0.569296 -0.142006 0.809776 + outer loop + vertex -823.267 289.618 47.2044 + vertex -820.822 299.853 47.2805 + vertex -825.741 293.052 49.5456 + endloop + endfacet + facet normal 0.575632 -0.148473 0.804117 + outer loop + vertex -825.741 293.052 49.5456 + vertex -820.822 299.853 47.2805 + vertex -823.262 302.945 49.598 + endloop + endfacet + facet normal 0.488679 -0.11833 0.864402 + outer loop + vertex -819.813 286.199 44.7835 + vertex -817.384 296.674 44.8445 + vertex -823.267 289.618 47.2044 + endloop + endfacet + facet normal 0.494414 -0.124494 0.860265 + outer loop + vertex -823.267 289.618 47.2044 + vertex -817.384 296.674 44.8445 + vertex -820.822 299.853 47.2805 + endloop + endfacet + facet normal 0.389274 -0.0912374 0.916592 + outer loop + vertex -815.663 282.633 42.6662 + vertex -813.216 293.285 42.6872 + vertex -819.813 286.199 44.7835 + endloop + endfacet + facet normal 0.394319 -0.0967407 0.913867 + outer loop + vertex -819.813 286.199 44.7835 + vertex -813.216 293.285 42.6872 + vertex -817.384 296.674 44.8445 + endloop + endfacet + facet normal 0.285418 -0.0620803 0.95639 + outer loop + vertex -811.015 278.742 41.0266 + vertex -808.566 289.646 41.0035 + vertex -815.663 282.633 42.6662 + endloop + endfacet + facet normal 0.291583 -0.0688703 0.954063 + outer loop + vertex -815.663 282.633 42.6662 + vertex -808.566 289.646 41.0035 + vertex -813.216 293.285 42.6872 + endloop + endfacet + facet normal -0.491411 0.0108307 0.87086 + outer loop + vertex -706.174 227.635 49.7415 + vertex -705.805 242.489 49.7651 + vertex -709.906 228.236 47.6281 + endloop + endfacet + facet normal -0.504391 0.0156943 0.863333 + outer loop + vertex -709.906 228.236 47.6281 + vertex -705.805 242.489 49.7651 + vertex -709.456 242.89 47.6249 + endloop + endfacet + facet normal 0.608245 -0.182187 0.772558 + outer loop + vertex -823.262 302.945 49.598 + vertex -820.483 312.228 49.5991 + vertex -824.653 306.009 51.4156 + endloop + endfacet + facet normal 0.620807 -0.194434 0.759469 + outer loop + vertex -824.653 306.009 51.4156 + vertex -820.483 312.228 49.5991 + vertex -821.678 315.393 51.3862 + endloop + endfacet + facet normal 0.56271 -0.163344 0.810355 + outer loop + vertex -820.822 299.853 47.2805 + vertex -818.07 309.36 47.2856 + vertex -823.262 302.945 49.598 + endloop + endfacet + facet normal 0.568859 -0.170399 0.804589 + outer loop + vertex -823.262 302.945 49.598 + vertex -818.07 309.36 47.2856 + vertex -820.483 312.228 49.5991 + endloop + endfacet + facet normal 0.486429 -0.135357 0.863171 + outer loop + vertex -817.384 296.674 44.8445 + vertex -814.645 306.475 44.8376 + vertex -820.822 299.853 47.2805 + endloop + endfacet + facet normal 0.492833 -0.14314 0.85827 + outer loop + vertex -820.822 299.853 47.2805 + vertex -814.645 306.475 44.8376 + vertex -818.07 309.36 47.2856 + endloop + endfacet + facet normal 0.38943 -0.103606 0.91521 + outer loop + vertex -813.216 293.285 42.6872 + vertex -810.46 303.386 42.658 + vertex -817.384 296.674 44.8445 + endloop + endfacet + facet normal 0.394337 -0.109581 0.912409 + outer loop + vertex -817.384 296.674 44.8445 + vertex -810.46 303.386 42.658 + vertex -814.645 306.475 44.8376 + endloop + endfacet + facet normal 0.288387 -0.0732521 0.954708 + outer loop + vertex -808.566 289.646 41.0035 + vertex -805.798 300.054 40.966 + vertex -813.216 293.285 42.6872 + endloop + endfacet + facet normal 0.29128 -0.0767146 0.953557 + outer loop + vertex -813.216 293.285 42.6872 + vertex -805.798 300.054 40.966 + vertex -810.46 303.386 42.658 + endloop + endfacet + facet normal -0.504743 0.0117255 0.86319 + outer loop + vertex -705.805 242.489 49.7651 + vertex -705.455 256.912 49.7739 + vertex -709.456 242.89 47.6249 + endloop + endfacet + facet normal -0.518955 0.0170922 0.854631 + outer loop + vertex -709.456 242.89 47.6249 + vertex -705.455 256.912 49.7739 + vertex -708.987 257.205 47.6234 + endloop + endfacet + facet normal 0.606 -0.205152 0.768555 + outer loop + vertex -820.483 312.228 49.5991 + vertex -817.484 321.038 49.5859 + vertex -821.678 315.393 51.3862 + endloop + endfacet + facet normal 0.616694 -0.216864 0.756742 + outer loop + vertex -821.678 315.393 51.3862 + vertex -817.484 321.038 49.5859 + vertex -818.563 323.84 51.2687 + endloop + endfacet + facet normal 0.559157 -0.181995 0.808839 + outer loop + vertex -818.07 309.36 47.2856 + vertex -815.121 318.405 47.2821 + vertex -820.483 312.228 49.5991 + endloop + endfacet + facet normal 0.567132 -0.191871 0.800966 + outer loop + vertex -820.483 312.228 49.5991 + vertex -815.121 318.405 47.2821 + vertex -817.484 321.038 49.5859 + endloop + endfacet + facet normal 0.485818 -0.153358 0.860501 + outer loop + vertex -814.645 306.475 44.8376 + vertex -811.671 315.797 44.82 + vertex -818.07 309.36 47.2856 + endloop + endfacet + facet normal 0.490635 -0.159635 0.856618 + outer loop + vertex -818.07 309.36 47.2856 + vertex -811.671 315.797 44.82 + vertex -815.121 318.405 47.2821 + endloop + endfacet + facet normal 0.389254 -0.117327 0.913628 + outer loop + vertex -810.46 303.386 42.658 + vertex -807.484 313.034 42.6289 + vertex -814.645 306.475 44.8376 + endloop + endfacet + facet normal 0.394517 -0.124138 0.910465 + outer loop + vertex -814.645 306.475 44.8376 + vertex -807.484 313.034 42.6289 + vertex -811.671 315.797 44.82 + endloop + endfacet + facet normal 0.287516 -0.0823244 0.954231 + outer loop + vertex -805.798 300.054 40.966 + vertex -802.83 310.054 40.9344 + vertex -810.46 303.386 42.658 + endloop + endfacet + facet normal 0.291228 -0.0869684 0.952692 + outer loop + vertex -810.46 303.386 42.658 + vertex -802.83 310.054 40.9344 + vertex -807.484 313.034 42.6289 + endloop + endfacet + facet normal -0.519498 0.00902434 0.854424 + outer loop + vertex -705.455 256.912 49.7739 + vertex -705.197 271.233 49.7797 + vertex -708.987 257.205 47.6234 + endloop + endfacet + facet normal -0.533592 0.0141854 0.845623 + outer loop + vertex -708.987 257.205 47.6234 + vertex -705.197 271.233 49.7797 + vertex -708.602 271.477 47.6266 + endloop + endfacet + facet normal 0.606027 -0.224754 0.763032 + outer loop + vertex -817.484 321.038 49.5859 + vertex -814.407 329.392 49.6031 + vertex -818.563 323.84 51.2687 + endloop + endfacet + facet normal 0.620052 -0.240086 0.746923 + outer loop + vertex -818.563 323.84 51.2687 + vertex -814.407 329.392 49.6031 + vertex -815.657 331.83 51.4246 + endloop + endfacet + facet normal 0.55982 -0.200973 0.803873 + outer loop + vertex -815.121 318.405 47.2821 + vertex -812.006 327.094 47.2848 + vertex -817.484 321.038 49.5859 + endloop + endfacet + facet normal 0.56716 -0.21051 0.796251 + outer loop + vertex -817.484 321.038 49.5859 + vertex -812.006 327.094 47.2848 + vertex -814.407 329.392 49.6031 + endloop + endfacet + facet normal 0.485294 -0.168053 0.858049 + outer loop + vertex -811.671 315.797 44.82 + vertex -808.548 324.804 44.8179 + vertex -815.121 318.405 47.2821 + endloop + endfacet + facet normal 0.491551 -0.176512 0.852773 + outer loop + vertex -815.121 318.405 47.2821 + vertex -808.548 324.804 44.8179 + vertex -812.006 327.094 47.2848 + endloop + endfacet + facet normal 0.391055 -0.129928 0.91115 + outer loop + vertex -807.484 313.034 42.6289 + vertex -804.359 322.378 42.6204 + vertex -811.671 315.797 44.82 + endloop + endfacet + facet normal 0.39664 -0.137304 0.907648 + outer loop + vertex -811.671 315.797 44.82 + vertex -804.359 322.378 42.6204 + vertex -808.548 324.804 44.8179 + endloop + endfacet + facet normal 0.288805 -0.0909598 0.953057 + outer loop + vertex -802.83 310.054 40.9344 + vertex -799.728 319.76 40.9206 + vertex -807.484 313.034 42.6289 + endloop + endfacet + facet normal 0.293915 -0.0974115 0.950855 + outer loop + vertex -807.484 313.034 42.6289 + vertex -799.728 319.76 40.9206 + vertex -804.359 322.378 42.6204 + endloop + endfacet + facet normal -0.534055 0.00601387 0.845428 + outer loop + vertex -705.197 271.233 49.7797 + vertex -705.037 285.57 49.7786 + vertex -708.602 271.477 47.6266 + endloop + endfacet + facet normal -0.549777 0.0115483 0.835232 + outer loop + vertex -708.602 271.477 47.6266 + vertex -705.037 285.57 49.7786 + vertex -708.308 285.767 47.6224 + endloop + endfacet + facet normal 0.615665 -0.244078 0.749255 + outer loop + vertex -814.407 329.392 49.6031 + vertex -811.188 337.51 49.6026 + vertex -815.657 331.83 51.4246 + endloop + endfacet + facet normal 0.624286 -0.254259 0.738661 + outer loop + vertex -815.657 331.83 51.4246 + vertex -811.188 337.51 49.6026 + vertex -812.237 339.83 51.2874 + endloop + endfacet + facet normal 0.563167 -0.216043 0.797602 + outer loop + vertex -812.006 327.094 47.2848 + vertex -808.782 335.515 47.29 + vertex -814.407 329.392 49.6031 + endloop + endfacet + facet normal 0.570906 -0.226327 0.789203 + outer loop + vertex -814.407 329.392 49.6031 + vertex -808.782 335.515 47.29 + vertex -811.188 337.51 49.6026 + endloop + endfacet + facet normal 0.489386 -0.180276 0.85323 + outer loop + vertex -808.548 324.804 44.8179 + vertex -805.325 333.578 44.8232 + vertex -812.006 327.094 47.2848 + endloop + endfacet + facet normal 0.497092 -0.190784 0.846464 + outer loop + vertex -812.006 327.094 47.2848 + vertex -805.325 333.578 44.8232 + vertex -808.782 335.515 47.29 + endloop + endfacet + facet normal 0.395166 -0.140049 0.907871 + outer loop + vertex -804.359 322.378 42.6204 + vertex -801.131 331.515 42.6249 + vertex -808.548 324.804 44.8179 + endloop + endfacet + facet normal 0.401115 -0.147884 0.904012 + outer loop + vertex -808.548 324.804 44.8179 + vertex -801.131 331.515 42.6249 + vertex -805.325 333.578 44.8232 + endloop + endfacet + facet normal 0.29273 -0.0995983 0.950994 + outer loop + vertex -799.728 319.76 40.9206 + vertex -796.52 329.269 40.929 + vertex -804.359 322.378 42.6204 + endloop + endfacet + facet normal 0.297524 -0.105575 0.948859 + outer loop + vertex -804.359 322.378 42.6204 + vertex -796.52 329.269 40.929 + vertex -801.131 331.515 42.6249 + endloop + endfacet + facet normal -0.550101 0.00456915 0.835086 + outer loop + vertex -705.037 285.57 49.7786 + vertex -704.93 299.894 49.7709 + vertex -708.308 285.767 47.6224 + endloop + endfacet + facet normal -0.567919 0.0106665 0.823015 + outer loop + vertex -708.308 285.767 47.6224 + vertex -704.93 299.894 49.7709 + vertex -708.056 300.044 47.6117 + endloop + endfacet + facet normal 0.61998 -0.257915 0.741016 + outer loop + vertex -811.188 337.51 49.6026 + vertex -807.804 345.523 49.5599 + vertex -812.237 339.83 51.2874 + endloop + endfacet + facet normal 0.631985 -0.271908 0.725714 + outer loop + vertex -812.237 339.83 51.2874 + vertex -807.804 345.523 49.5599 + vertex -808.992 347.627 51.383 + endloop + endfacet + facet normal 0.569815 -0.228 0.789511 + outer loop + vertex -808.782 335.515 47.29 + vertex -805.447 343.762 47.264 + vertex -811.188 337.51 49.6026 + endloop + endfacet + facet normal 0.579081 -0.240438 0.779009 + outer loop + vertex -811.188 337.51 49.6026 + vertex -805.447 343.762 47.264 + vertex -807.804 345.523 49.5599 + endloop + endfacet + facet normal 0.496496 -0.191956 0.846549 + outer loop + vertex -805.325 333.578 44.8232 + vertex -801.987 342.169 44.8134 + vertex -808.782 335.515 47.29 + endloop + endfacet + facet normal 0.503015 -0.200818 0.840624 + outer loop + vertex -808.782 335.515 47.29 + vertex -801.987 342.169 44.8134 + vertex -805.447 343.762 47.264 + endloop + endfacet + facet normal 0.400527 -0.149136 0.904067 + outer loop + vertex -801.131 331.515 42.6249 + vertex -797.809 340.496 42.6343 + vertex -805.325 333.578 44.8232 + endloop + endfacet + facet normal 0.406542 -0.156943 0.900051 + outer loop + vertex -805.325 333.578 44.8232 + vertex -797.809 340.496 42.6343 + vertex -801.987 342.169 44.8134 + endloop + endfacet + facet normal 0.297627 -0.105357 0.948851 + outer loop + vertex -796.52 329.269 40.929 + vertex -793.23 338.64 40.9376 + vertex -801.131 331.515 42.6249 + endloop + endfacet + facet normal 0.304412 -0.113618 0.94574 + outer loop + vertex -801.131 331.515 42.6249 + vertex -793.23 338.64 40.9376 + vertex -797.809 340.496 42.6343 + endloop + endfacet + facet normal -0.56818 0.00352344 0.822897 + outer loop + vertex -704.93 299.894 49.7709 + vertex -704.851 314.2 49.764 + vertex -708.056 300.044 47.6117 + endloop + endfacet + facet normal -0.590542 0.0110136 0.806932 + outer loop + vertex -708.056 300.044 47.6117 + vertex -704.851 314.2 49.764 + vertex -707.794 314.302 47.609 + endloop + endfacet + facet normal 0.63114 -0.272749 0.726134 + outer loop + vertex -807.804 345.523 49.5599 + vertex -804.337 353.503 49.5441 + vertex -808.992 347.627 51.383 + endloop + endfacet + facet normal 0.644512 -0.289067 0.707845 + outer loop + vertex -808.992 347.627 51.383 + vertex -804.337 353.503 49.5441 + vertex -805.275 355.625 51.2642 + endloop + endfacet + facet normal 0.579365 -0.239969 0.778942 + outer loop + vertex -805.447 343.762 47.264 + vertex -802.001 351.932 47.2184 + vertex -807.804 345.523 49.5599 + endloop + endfacet + facet normal 0.590655 -0.255084 0.765545 + outer loop + vertex -807.804 345.523 49.5599 + vertex -802.001 351.932 47.2184 + vertex -804.337 353.503 49.5441 + endloop + endfacet + facet normal 0.504031 -0.198516 0.840562 + outer loop + vertex -801.987 342.169 44.8134 + vertex -798.575 350.637 44.7672 + vertex -805.447 343.762 47.264 + endloop + endfacet + facet normal 0.514258 -0.212223 0.830963 + outer loop + vertex -805.447 343.762 47.264 + vertex -798.575 350.637 44.7672 + vertex -802.001 351.932 47.2184 + endloop + endfacet + facet normal 0.408153 -0.152883 0.900021 + outer loop + vertex -797.809 340.496 42.6343 + vertex -794.415 349.353 42.6 + vertex -801.987 342.169 44.8134 + endloop + endfacet + facet normal 0.415937 -0.162723 0.894716 + outer loop + vertex -801.987 342.169 44.8134 + vertex -794.415 349.353 42.6 + vertex -798.575 350.637 44.7672 + endloop + endfacet + facet normal 0.305698 -0.110414 0.945705 + outer loop + vertex -793.23 338.64 40.9376 + vertex -789.863 347.915 40.9321 + vertex -797.809 340.496 42.6343 + endloop + endfacet + facet normal 0.309534 -0.114933 0.943917 + outer loop + vertex -797.809 340.496 42.6343 + vertex -789.863 347.915 40.9321 + vertex -794.415 349.353 42.6 + endloop + endfacet + facet normal -0.590775 0.00222057 0.806833 + outer loop + vertex -704.851 314.2 49.764 + vertex -704.784 328.521 49.7734 + vertex -707.794 314.302 47.609 + endloop + endfacet + facet normal -0.61295 0.00946646 0.790065 + outer loop + vertex -707.794 314.302 47.609 + vertex -704.784 328.521 49.7734 + vertex -707.554 328.57 47.6243 + endloop + endfacet + facet normal 0.6447 -0.2889 0.707742 + outer loop + vertex -804.337 353.503 49.5441 + vertex -800.882 361.48 49.6534 + vertex -805.275 355.625 51.2642 + endloop + endfacet + facet normal 0.661143 -0.307696 0.684261 + outer loop + vertex -805.275 355.625 51.2642 + vertex -800.882 361.48 49.6534 + vertex -801.964 363.31 51.5214 + endloop + endfacet + facet normal 0.591933 -0.252828 0.765306 + outer loop + vertex -802.001 351.932 47.2184 + vertex -798.541 360.13 47.2506 + vertex -804.337 353.503 49.5441 + endloop + endfacet + facet normal 0.607659 -0.273378 0.745664 + outer loop + vertex -804.337 353.503 49.5441 + vertex -798.541 360.13 47.2506 + vertex -800.882 361.48 49.6534 + endloop + endfacet + facet normal 0.516199 -0.207206 0.831026 + outer loop + vertex -798.575 350.637 44.7672 + vertex -795.124 359.084 44.7297 + vertex -802.001 351.932 47.2184 + endloop + endfacet + facet normal 0.531929 -0.2277 0.8156 + outer loop + vertex -802.001 351.932 47.2184 + vertex -795.124 359.084 44.7297 + vertex -798.541 360.13 47.2506 + endloop + endfacet + facet normal 0.417773 -0.157048 0.894875 + outer loop + vertex -794.415 349.353 42.6 + vertex -790.973 358.158 42.5383 + vertex -798.575 350.637 44.7672 + endloop + endfacet + facet normal 0.429747 -0.171638 0.886486 + outer loop + vertex -798.575 350.637 44.7672 + vertex -790.973 358.158 42.5383 + vertex -795.124 359.084 44.7297 + endloop + endfacet + facet normal 0.310898 -0.110684 0.943976 + outer loop + vertex -789.863 347.915 40.9321 + vertex -786.44 357.147 40.8873 + vertex -794.415 349.353 42.6 + endloop + endfacet + facet normal 0.316686 -0.117204 0.941262 + outer loop + vertex -794.415 349.353 42.6 + vertex -786.44 357.147 40.8873 + vertex -790.973 358.158 42.5383 + endloop + endfacet + facet normal -0.613071 0.000855756 0.790027 + outer loop + vertex -704.784 328.521 49.7734 + vertex -704.712 342.859 49.8138 + vertex -707.554 328.57 47.6243 + endloop + endfacet + facet normal -0.637967 0.00887347 0.770012 + outer loop + vertex -707.554 328.57 47.6243 + vertex -704.712 342.859 49.8138 + vertex -707.307 342.848 47.6637 + endloop + endfacet + facet normal 0.667938 -0.300295 0.680942 + outer loop + vertex -800.882 361.48 49.6534 + vertex -797.645 369.259 49.9086 + vertex -801.964 363.31 51.5214 + endloop + endfacet + facet normal 0.675682 -0.309082 0.66927 + outer loop + vertex -801.964 363.31 51.5214 + vertex -797.645 369.259 49.9086 + vertex -798.597 370.589 51.4835 + endloop + endfacet + facet normal 0.61138 -0.26616 0.745234 + outer loop + vertex -798.541 360.13 47.2506 + vertex -795.145 368.493 47.4511 + vertex -800.882 361.48 49.6534 + endloop + endfacet + facet normal 0.626278 -0.284432 0.725861 + outer loop + vertex -800.882 361.48 49.6534 + vertex -795.145 368.493 47.4511 + vertex -797.645 369.259 49.9086 + endloop + endfacet + facet normal 0.534292 -0.220817 0.815948 + outer loop + vertex -795.124 359.084 44.7297 + vertex -791.709 367.642 44.8098 + vertex -798.541 360.13 47.2506 + endloop + endfacet + facet normal 0.552511 -0.243497 0.797145 + outer loop + vertex -798.541 360.13 47.2506 + vertex -791.709 367.642 44.8098 + vertex -795.145 368.493 47.4511 + endloop + endfacet + facet normal 0.431629 -0.164318 0.886959 + outer loop + vertex -790.973 358.158 42.5383 + vertex -787.567 367.001 42.5188 + vertex -795.124 359.084 44.7297 + endloop + endfacet + facet normal 0.452728 -0.188794 0.871433 + outer loop + vertex -795.124 359.084 44.7297 + vertex -787.567 367.001 42.5188 + vertex -791.709 367.642 44.8098 + endloop + endfacet + facet normal 0.318446 -0.109803 0.94156 + outer loop + vertex -786.44 357.147 40.8873 + vertex -783.035 366.383 40.8126 + vertex -790.973 358.158 42.5383 + endloop + endfacet + facet normal 0.334319 -0.12673 0.933901 + outer loop + vertex -790.973 358.158 42.5383 + vertex -783.035 366.383 40.8126 + vertex -787.567 367.001 42.5188 + endloop + endfacet + facet normal -0.637968 -0.0011352 0.770062 + outer loop + vertex -704.712 342.859 49.8138 + vertex -704.682 357.213 49.8601 + vertex -707.307 342.848 47.6637 + endloop + endfacet + facet normal -0.664364 0.00715874 0.747375 + outer loop + vertex -707.307 342.848 47.6637 + vertex -704.682 357.213 49.8601 + vertex -707.104 357.182 47.707 + endloop + endfacet + facet normal 0.692215 -0.28822 0.66164 + outer loop + vertex -797.645 369.259 49.9086 + vertex -795.37 375.536 50.2622 + vertex -798.597 370.589 51.4835 + endloop + endfacet + facet normal 0.692892 -0.28891 0.66063 + outer loop + vertex -798.597 370.589 51.4835 + vertex -795.37 375.536 50.2622 + vertex -795.944 376.49 51.2815 + endloop + endfacet + facet normal 0.637106 -0.254507 0.727546 + outer loop + vertex -795.145 368.493 47.4511 + vertex -791.95 377.554 47.8233 + vertex -797.645 369.259 49.9086 + endloop + endfacet + facet normal 0.661297 -0.278965 0.696322 + outer loop + vertex -797.645 369.259 49.9086 + vertex -791.95 377.554 47.8233 + vertex -795.37 375.536 50.2622 + endloop + endfacet + facet normal 0.559445 -0.220907 0.798887 + outer loop + vertex -791.709 367.642 44.8098 + vertex -788.463 376.408 44.9607 + vertex -795.145 368.493 47.4511 + endloop + endfacet + facet normal 0.570032 -0.233335 0.787794 + outer loop + vertex -795.145 368.493 47.4511 + vertex -788.463 376.408 44.9607 + vertex -791.95 377.554 47.8233 + endloop + endfacet + facet normal 0.456252 -0.171923 0.873085 + outer loop + vertex -787.567 367.001 42.5188 + vertex -784.375 375.985 42.6198 + vertex -791.709 367.642 44.8098 + endloop + endfacet + facet normal 0.472944 -0.189934 0.860377 + outer loop + vertex -791.709 367.642 44.8098 + vertex -784.375 375.985 42.6198 + vertex -788.463 376.408 44.9607 + endloop + endfacet + facet normal 0.335679 -0.118419 0.934504 + outer loop + vertex -783.035 366.383 40.8126 + vertex -779.846 375.725 40.8511 + vertex -787.567 367.001 42.5188 + endloop + endfacet + facet normal 0.353647 -0.136053 0.925432 + outer loop + vertex -787.567 367.001 42.5188 + vertex -779.846 375.725 40.8511 + vertex -784.375 375.985 42.6198 + endloop + endfacet + facet normal -0.664204 -0.0115495 0.747462 + outer loop + vertex -704.682 357.213 49.8601 + vertex -704.821 371.73 49.9608 + vertex -707.104 357.182 47.707 + endloop + endfacet + facet normal -0.698926 -0.00110057 0.715193 + outer loop + vertex -707.104 357.182 47.707 + vertex -704.821 371.73 49.9608 + vertex -707.127 371.714 47.7068 + endloop + endfacet + facet normal 0.594667 -0.159095 0.788074 + outer loop + vertex -788.463 376.408 44.9607 + vertex -785.694 385.025 44.6108 + vertex -791.95 377.554 47.8233 + endloop + endfacet + facet normal 0.579759 -0.140362 0.802607 + outer loop + vertex -791.95 377.554 47.8233 + vertex -785.694 385.025 44.6108 + vertex -789.072 384.933 47.0349 + endloop + endfacet + facet normal 0.48213 -0.132424 0.866034 + outer loop + vertex -784.375 375.985 42.6198 + vertex -781.763 385.127 42.5637 + vertex -788.463 376.408 44.9607 + endloop + endfacet + facet normal 0.46121 -0.112472 0.880134 + outer loop + vertex -788.463 376.408 44.9607 + vertex -781.763 385.127 42.5637 + vertex -785.694 385.025 44.6108 + endloop + endfacet + facet normal 0.35674 -0.103 0.928508 + outer loop + vertex -779.846 375.725 40.8511 + vertex -777.328 385.236 40.9389 + vertex -784.375 375.985 42.6198 + endloop + endfacet + facet normal 0.344581 -0.0927119 0.934167 + outer loop + vertex -784.375 375.985 42.6198 + vertex -777.328 385.236 40.9389 + vertex -781.763 385.127 42.5637 + endloop + endfacet + facet normal -0.69847 -0.0315129 0.714945 + outer loop + vertex -704.821 371.73 49.9608 + vertex -705.335 386.645 50.1156 + vertex -707.127 371.714 47.7068 + endloop + endfacet + facet normal -0.748786 -0.0170287 0.662594 + outer loop + vertex -707.127 371.714 47.7068 + vertex -705.335 386.645 50.1156 + vertex -707.708 386.624 47.4344 + endloop + endfacet + facet normal -0.265067 -0.515596 0.814801 + outer loop + vertex -845.324 242.676 47.0767 + vertex -846.708 242.159 46.2995 + vertex -845.484 242.439 46.8749 + endloop + endfacet + facet normal -0.204311 -0.421815 0.883362 + outer loop + vertex -843.832 243.42 47.7771 + vertex -845.324 242.676 47.0767 + vertex -844.253 243.047 47.5018 + endloop + endfacet + facet normal -0.216596 -0.303254 0.927967 + outer loop + vertex -841.901 244.872 48.7024 + vertex -843.832 243.42 47.7771 + vertex -842.723 243.984 48.2202 + endloop + endfacet + facet normal -0.080268 -0.332329 0.939742 + outer loop + vertex -840.209 246.858 49.5491 + vertex -841.901 244.872 48.7024 + vertex -840.442 246.37 49.3567 + endloop + endfacet + facet normal 0.146503 -0.356592 0.922702 + outer loop + vertex -839.122 248.755 50.1097 + vertex -840.209 246.858 49.5491 + vertex -839.351 248.19 49.9277 + endloop + endfacet + facet normal -0.133436 -0.134605 0.981874 + outer loop + vertex -838.099 251.35 50.6045 + vertex -839.122 248.755 50.1097 + vertex -838.705 249.569 50.2779 + endloop + endfacet + facet normal 0.707607 -0.317532 0.631242 + outer loop + vertex -836.677 255.8 51.2491 + vertex -838.099 251.35 50.6045 + vertex -837.017 254.105 50.7774 + endloop + endfacet + facet normal 0.9567 -0.278443 0.0848194 + outer loop + vertex -835.769 259.047 51.6715 + vertex -836.677 255.8 51.2491 + vertex -835.489 259.975 51.554 + endloop + endfacet + facet normal 0.922931 -0.240951 0.300236 + outer loop + vertex -835.073 262.016 51.9129 + vertex -835.769 259.047 51.6715 + vertex -835.489 259.975 51.554 + endloop + endfacet + facet normal 0.666365 -0.163668 0.727441 + outer loop + vertex -834.299 265.79 52.0535 + vertex -835.073 262.016 51.9129 + vertex -834.708 263.517 51.9167 + endloop + endfacet + facet normal 0.818059 -0.173518 0.548335 + outer loop + vertex -833.326 270.215 52.0017 + vertex -834.299 265.79 52.0535 + vertex -834.062 265.482 51.602 + endloop + endfacet + facet normal 0.710914 -0.142109 0.688771 + outer loop + vertex -832.597 274.694 52.1734 + vertex -833.326 270.215 52.0017 + vertex -831.722 274.31 51.1907 + endloop + endfacet + facet normal 0.712539 -0.136833 0.688161 + outer loop + vertex -831.521 279.821 52.0783 + vertex -832.597 274.694 52.1734 + vertex -831.722 274.31 51.1907 + endloop + endfacet + facet normal 0.676867 -0.137201 0.723206 + outer loop + vertex -830.863 284.487 52.3478 + vertex -831.521 279.821 52.0783 + vertex -829.473 286.114 51.3554 + endloop + endfacet + facet normal 0.678799 -0.140325 0.720792 + outer loop + vertex -829.49 290.836 52.2909 + vertex -830.863 284.487 52.3478 + vertex -829.473 286.114 51.3554 + endloop + endfacet + facet normal 0.63264 -0.138137 0.762027 + outer loop + vertex -828.433 295.729 52.3003 + vertex -829.49 290.836 52.2909 + vertex -827.195 296.551 51.4218 + endloop + endfacet + facet normal 0.640819 -0.163107 0.750164 + outer loop + vertex -827.224 300.295 52.2601 + vertex -828.433 295.729 52.3003 + vertex -827.195 296.551 51.4218 + endloop + endfacet + facet normal 0.620158 -0.165669 0.766784 + outer loop + vertex -826.001 304.834 52.2519 + vertex -827.224 300.295 52.2601 + vertex -824.653 306.009 51.4156 + endloop + endfacet + facet normal 0.632184 -0.190708 0.750982 + outer loop + vertex -824.596 309.389 52.2258 + vertex -826.001 304.834 52.2519 + vertex -824.653 306.009 51.4156 + endloop + endfacet + facet normal 0.632297 -0.202718 0.747734 + outer loop + vertex -822.852 315.14 52.3101 + vertex -824.596 309.389 52.2258 + vertex -821.678 315.393 51.3862 + endloop + endfacet + facet normal 0.632247 -0.217334 0.74366 + outer loop + vertex -820.969 319.932 52.1102 + vertex -822.852 315.14 52.3101 + vertex -821.678 315.393 51.3862 + endloop + endfacet + facet normal 0.644916 -0.240857 0.725307 + outer loop + vertex -818.969 325.687 52.2429 + vertex -820.969 319.932 52.1102 + vertex -818.563 323.84 51.2687 + endloop + endfacet + facet normal 0.646047 -0.252334 0.720382 + outer loop + vertex -816.91 331.343 52.3771 + vertex -818.969 325.687 52.2429 + vertex -815.657 331.83 51.4246 + endloop + endfacet + facet normal 0.646635 -0.260762 0.716845 + outer loop + vertex -814.811 335.939 52.1562 + vertex -816.91 331.343 52.3771 + vertex -815.657 331.83 51.4246 + endloop + endfacet + facet normal 0.654756 -0.276139 0.703592 + outer loop + vertex -812.562 341.457 52.2286 + vertex -814.811 335.939 52.1562 + vertex -812.237 339.83 51.2874 + endloop + endfacet + facet normal 0.663824 -0.289596 0.689545 + outer loop + vertex -810.284 346.94 52.338 + vertex -812.562 341.457 52.2286 + vertex -808.992 347.627 51.383 + endloop + endfacet + facet normal 0.664698 -0.29651 0.685754 + outer loop + vertex -807.984 351.611 52.1292 + vertex -810.284 346.94 52.338 + vertex -808.992 347.627 51.383 + endloop + endfacet + facet normal 0.678503 -0.31513 0.663571 + outer loop + vertex -805.522 357.223 52.2764 + vertex -807.984 351.611 52.1292 + vertex -805.275 355.625 51.2642 + endloop + endfacet + facet normal 0.695998 -0.32759 0.638961 + outer loop + vertex -803.047 362.811 52.4446 + vertex -805.522 357.223 52.2764 + vertex -801.964 363.31 51.5214 + endloop + endfacet + facet normal 0.695953 -0.324389 0.640641 + outer loop + vertex -800.818 367.229 52.2612 + vertex -803.047 362.811 52.4446 + vertex -801.964 363.31 51.5214 + endloop + endfacet + facet normal 0.701741 -0.316211 0.638413 + outer loop + vertex -798.333 372.62 52.2001 + vertex -800.818 367.229 52.2612 + vertex -798.597 370.589 51.4835 + endloop + endfacet + facet normal 0.711763 -0.2874 0.640933 + outer loop + vertex -795.203 379.625 51.8645 + vertex -798.333 372.62 52.2001 + vertex -795.944 376.49 51.2815 + endloop + endfacet + facet normal 0.768622 -0.247539 0.589868 + outer loop + vertex -794.163 384.78 52.6728 + vertex -795.203 379.625 51.8645 + vertex -792.003 384.848 49.887 + endloop + endfacet + facet normal -0.449595 -0.487859 0.748237 + outer loop + vertex -698.863 144.783 43.2318 + vertex -696.119 143.781 44.2272 + vertex -697.271 144.655 44.1055 + endloop + endfacet + facet normal -0.383027 -0.381904 0.841094 + outer loop + vertex -704.198 146.947 41.6992 + vertex -701.52 145.855 42.4231 + vertex -703.23 147.009 42.1682 + endloop + endfacet + facet normal -0.316178 -0.291533 0.902796 + outer loop + vertex -711.953 150.747 40.1354 + vertex -708.028 148.706 40.8509 + vertex -709.531 150.631 40.9462 + endloop + endfacet + facet normal -0.283789 -0.259091 0.92322 + outer loop + vertex -716.679 152.924 39.2936 + vertex -711.953 150.747 40.1354 + vertex -713.57 152.963 40.2601 + endloop + endfacet + facet normal -0.0675689 -0.151679 0.986118 + outer loop + vertex -811.266 208 36.0405 + vertex -805.846 203.709 35.7517 + vertex -808.186 208.544 36.3351 + endloop + endfacet + facet normal -0.0788256 -0.189451 0.978721 + outer loop + vertex -815.309 211.298 36.3532 + vertex -811.266 208 36.0405 + vertex -813.327 210.661 36.3894 + endloop + endfacet + facet normal -0.0682285 -0.204726 0.976439 + outer loop + vertex -818.683 214.398 36.7674 + vertex -815.309 211.298 36.3532 + vertex -816.529 213.674 36.7661 + endloop + endfacet + facet normal -0.0445324 -0.216957 0.975165 + outer loop + vertex -823.198 218.891 37.5609 + vertex -818.683 214.398 36.7674 + vertex -819.915 216.965 37.2821 + endloop + endfacet + facet normal -0.0370209 -0.245495 0.968691 + outer loop + vertex -827.023 222.481 38.3245 + vertex -823.198 218.891 37.5609 + vertex -825.037 221.872 38.246 + endloop + endfacet + facet normal 0.00526421 -0.264912 0.964258 + outer loop + vertex -830.445 225.664 39.2175 + vertex -827.023 222.481 38.3245 + vertex -828.061 224.704 38.9409 + endloop + endfacet + facet normal 0.0333084 -0.280722 0.959211 + outer loop + vertex -834.007 229.467 40.4542 + vertex -830.445 225.664 39.2175 + vertex -830.918 227.562 39.7893 + endloop + endfacet + facet normal 0.0061931 -0.350572 0.936515 + outer loop + vertex -838.262 233.382 41.9478 + vertex -834.007 229.467 40.4542 + vertex -835.662 232.446 41.5802 + endloop + endfacet + facet normal -0.0340766 -0.425431 0.904349 + outer loop + vertex -841.883 236.959 43.4941 + vertex -838.262 233.382 41.9478 + vertex -839.248 235.871 43.0815 + endloop + endfacet + facet normal -0.15613 -0.566484 0.809147 + outer loop + vertex -844.46 239.613 44.8554 + vertex -841.883 236.959 43.4941 + vertex -843.5 239.016 44.6223 + endloop + endfacet + facet normal -0.207246 -0.61476 0.760999 + outer loop + vertex -846.708 242.159 46.2995 + vertex -844.46 239.613 44.8554 + vertex -845.174 240.98 45.7648 + endloop + endfacet + facet normal -0.910936 0.000144337 0.412547 + outer loop + vertex -702.631 198.288 52.3538 + vertex -702.595 205.36 52.4302 + vertex -702.724 196.696 52.1496 + endloop + endfacet + facet normal -0.997405 -0.0173623 -0.0698639 + outer loop + vertex -702.508 185.736 52.0082 + vertex -702.631 191.956 52.2097 + vertex -702.498 185.544 51.9098 + endloop + endfacet + facet normal 0.267831 -0.0397514 0.962645 + outer loop + vertex -702.251 179.717 51.6881 + vertex -702.508 185.736 52.0082 + vertex -702.349 181.092 51.7721 + endloop + endfacet + facet normal -0.988686 -0.0521463 -0.140644 + outer loop + vertex -702.01 175.869 51.424 + vertex -702.251 179.717 51.6881 + vertex -701.958 175.122 51.3322 + endloop + endfacet + facet normal -0.674836 -0.136544 0.725226 + outer loop + vertex -701.567 171.641 51.0406 + vertex -702.01 175.869 51.424 + vertex -701.958 175.122 51.3322 + endloop + endfacet + facet normal -0.951042 -0.151491 0.269385 + outer loop + vertex -700.844 166.047 50.4483 + vertex -701.567 171.641 51.0406 + vertex -701.106 167.933 50.5819 + endloop + endfacet + facet normal -0.837724 -0.081033 -0.540048 + outer loop + vertex -700.054 161.637 49.8844 + vertex -700.844 166.047 50.4483 + vertex -699.823 160.986 49.6246 + endloop + endfacet + facet normal -0.901335 -0.158144 -0.403218 + outer loop + vertex -698.914 157.213 49.0724 + vertex -700.054 161.637 49.8844 + vertex -699.823 160.986 49.6246 + endloop + endfacet + facet normal -0.588246 -0.349322 0.729343 + outer loop + vertex -697.161 151.798 47.8929 + vertex -698.914 157.213 49.0724 + vertex -698.11 154.478 48.4106 + endloop + endfacet + facet normal -0.174603 -0.307108 0.93552 + outer loop + vertex -695.36 147.413 46.7898 + vertex -697.161 151.798 47.8929 + vertex -695.903 148.345 46.9943 + endloop + endfacet + facet normal -0.290182 -0.379079 0.878688 + outer loop + vertex -693.155 142.971 45.6015 + vertex -695.36 147.413 46.7898 + vertex -694.674 145.582 46.226 + endloop + endfacet + facet normal 0.68716 -0.193175 0.700353 + outer loop + vertex -789.072 384.933 47.0349 + vertex -792.003 384.848 49.887 + vertex -791.95 377.554 47.8233 + endloop + endfacet + facet normal -0.251495 -0.651718 0.715552 + outer loop + vertex -845.174 240.98 45.7648 + vertex -845.808 241.951 46.4259 + vertex -846.708 242.159 46.2995 + endloop + endfacet + facet normal -0.143067 -0.61667 0.774113 + outer loop + vertex -845.808 241.951 46.4259 + vertex -845.28 242.3 46.8022 + vertex -845.484 242.439 46.8749 + endloop + endfacet + facet normal -0.101161 -0.548685 0.829886 + outer loop + vertex -841.161 237.171 43.7079 + vertex -841.836 237.347 43.7421 + vertex -839.248 235.871 43.0815 + endloop + endfacet + facet normal -0.084094 -0.529165 0.844342 + outer loop + vertex -841.836 237.347 43.7421 + vertex -843.5 239.016 44.6223 + vertex -841.883 236.959 43.4941 + endloop + endfacet + facet normal -0.194775 -0.611934 0.76655 + outer loop + vertex -843.5 239.016 44.6223 + vertex -845.174 240.98 45.7648 + vertex -844.46 239.613 44.8554 + endloop + endfacet + facet normal -0.382654 -0.383506 0.840535 + outer loop + vertex -703.23 147.009 42.1682 + vertex -706.317 148.362 41.3798 + vertex -704.198 146.947 41.6992 + endloop + endfacet + facet normal -0.0461397 -0.559453 0.827577 + outer loop + vertex -844.253 243.047 47.5018 + vertex -842.723 243.984 48.2202 + vertex -843.832 243.42 47.7771 + endloop + endfacet + facet normal -0.104704 -0.603082 0.790777 + outer loop + vertex -845.484 242.439 46.8749 + vertex -844.253 243.047 47.5018 + vertex -845.324 242.676 47.0767 + endloop + endfacet + facet normal -0.174445 -0.246522 0.953308 + outer loop + vertex -841.446 245.047 48.8309 + vertex -840.442 246.37 49.3567 + vertex -841.901 244.872 48.7024 + endloop + endfacet + facet normal -0.104289 -0.398224 0.911341 + outer loop + vertex -842.723 243.984 48.2202 + vertex -841.446 245.047 48.8309 + vertex -841.901 244.872 48.7024 + endloop + endfacet + facet normal -0.0238909 -0.42223 0.906174 + outer loop + vertex -835.662 232.446 41.5802 + vertex -839.248 235.871 43.0815 + vertex -838.262 233.382 41.9478 + endloop + endfacet + facet normal 0.00819953 -0.317577 0.948197 + outer loop + vertex -830.918 227.562 39.7893 + vertex -832.995 230.018 40.63 + vertex -834.007 229.467 40.4542 + endloop + endfacet + facet normal 0.0231575 -0.342209 0.939338 + outer loop + vertex -832.995 230.018 40.63 + vertex -835.662 232.446 41.5802 + vertex -834.007 229.467 40.4542 + endloop + endfacet + facet normal -0.0508001 -0.288801 0.956041 + outer loop + vertex -825.037 221.872 38.246 + vertex -828.061 224.704 38.9409 + vertex -827.023 222.481 38.3245 + endloop + endfacet + facet normal -0.00558038 -0.289783 0.957076 + outer loop + vertex -828.061 224.704 38.9409 + vertex -830.918 227.562 39.7893 + vertex -830.445 225.664 39.2175 + endloop + endfacet + facet normal -0.0588381 -0.240423 0.968883 + outer loop + vertex -819.915 216.965 37.2821 + vertex -822.409 219.637 37.7937 + vertex -823.198 218.891 37.5609 + endloop + endfacet + facet normal -0.0476389 -0.25158 0.966663 + outer loop + vertex -822.409 219.637 37.7937 + vertex -825.037 221.872 38.246 + vertex -823.198 218.891 37.5609 + endloop + endfacet + facet normal -0.0864624 -0.213508 0.973108 + outer loop + vertex -813.327 210.661 36.3894 + vertex -816.529 213.674 36.7661 + vertex -815.309 211.298 36.3532 + endloop + endfacet + facet normal -0.0772555 -0.231574 0.969745 + outer loop + vertex -816.529 213.674 36.7661 + vertex -819.915 216.965 37.2821 + vertex -818.683 214.398 36.7674 + endloop + endfacet + facet normal -0.0626563 -0.177371 0.982148 + outer loop + vertex -808.186 208.544 36.3351 + vertex -813.327 210.661 36.3894 + vertex -811.266 208 36.0405 + endloop + endfacet + facet normal -0.14023 -0.164451 0.976366 + outer loop + vertex -742.139 165.742 36.6014 + vertex -748.384 169.23 36.2919 + vertex -743.865 164.975 36.2243 + endloop + endfacet + facet normal -0.31667 -0.282097 0.905616 + outer loop + vertex -709.531 150.631 40.9462 + vertex -713.57 152.963 40.2601 + vertex -711.953 150.747 40.1354 + endloop + endfacet + facet normal -0.381285 -0.419022 0.82404 + outer loop + vertex -694.674 145.582 46.226 + vertex -693.959 144.012 45.7587 + vertex -693.155 142.971 45.6015 + endloop + endfacet + facet normal -0.358048 -0.394501 0.846269 + outer loop + vertex -695.903 148.345 46.9943 + vertex -694.674 145.582 46.226 + vertex -695.36 147.413 46.7898 + endloop + endfacet + facet normal -0.370986 -0.358157 0.856792 + outer loop + vertex -696.562 149.872 47.3473 + vertex -695.903 148.345 46.9943 + vertex -697.161 151.798 47.8929 + endloop + endfacet + facet normal -0.835835 -0.373825 0.402038 + outer loop + vertex -698.11 154.478 48.4106 + vertex -696.562 149.872 47.3473 + vertex -697.161 151.798 47.8929 + endloop + endfacet + facet normal 0.830307 -0.353163 0.431121 + outer loop + vertex -838.462 250.122 50.2989 + vertex -837.017 254.105 50.7774 + vertex -838.099 251.35 50.6045 + endloop + endfacet + facet normal 0.65316 -0.458644 0.602517 + outer loop + vertex -839.351 248.19 49.9277 + vertex -838.705 249.569 50.2779 + vertex -839.122 248.755 50.1097 + endloop + endfacet + facet normal 0.771965 -0.359128 0.524497 + outer loop + vertex -838.705 249.569 50.2779 + vertex -838.462 250.122 50.2989 + vertex -838.099 251.35 50.6045 + endloop + endfacet + facet normal 0.473087 -0.509152 0.718994 + outer loop + vertex -840.442 246.37 49.3567 + vertex -839.351 248.19 49.9277 + vertex -840.209 246.858 49.5491 + endloop + endfacet + facet normal -0.866399 -0.138526 -0.479753 + outer loop + vertex -699.823 160.986 49.6246 + vertex -698.11 154.478 48.4106 + vertex -698.914 157.213 49.0724 + endloop + endfacet + facet normal -0.824786 -0.0751061 -0.560435 + outer loop + vertex -701.106 167.933 50.5819 + vertex -699.823 160.986 49.6246 + vertex -700.844 166.047 50.4483 + endloop + endfacet + facet normal 0.949192 -0.231072 0.213635 + outer loop + vertex -835.489 259.975 51.554 + vertex -834.708 263.517 51.9167 + vertex -835.073 262.016 51.9129 + endloop + endfacet + facet normal 0.814945 -0.179765 0.550952 + outer loop + vertex -834.708 263.517 51.9167 + vertex -834.062 265.482 51.602 + vertex -834.299 265.79 52.0535 + endloop + endfacet + facet normal 0.888424 -0.27941 0.364187 + outer loop + vertex -837.017 254.105 50.7774 + vertex -835.489 259.975 51.554 + vertex -836.677 255.8 51.2491 + endloop + endfacet + facet normal -0.954825 -0.0833503 -0.285242 + outer loop + vertex -701.958 175.122 51.3322 + vertex -701.106 167.933 50.5819 + vertex -701.567 171.641 51.0406 + endloop + endfacet + facet normal -0.903279 -0.0900771 0.419491 + outer loop + vertex -702.349 181.092 51.7721 + vertex -701.958 175.122 51.3322 + vertex -702.251 179.717 51.6881 + endloop + endfacet + facet normal 0.755795 -0.170911 0.63211 + outer loop + vertex -834.062 265.482 51.602 + vertex -831.722 274.31 51.1907 + vertex -833.326 270.215 52.0017 + endloop + endfacet + facet normal -0.99964 -0.0198327 -0.0180476 + outer loop + vertex -702.724 196.696 52.1496 + vertex -702.498 185.544 51.9098 + vertex -702.631 191.956 52.2097 + endloop + endfacet + facet normal 0.683799 -0.140278 0.716059 + outer loop + vertex -831.722 274.31 51.1907 + vertex -829.473 286.114 51.3554 + vertex -831.521 279.821 52.0783 + endloop + endfacet + facet normal -0.847824 -0.00460196 0.530257 + outer loop + vertex -702.765 209.668 52.1965 + vertex -702.724 196.696 52.1496 + vertex -702.595 205.36 52.4302 + endloop + endfacet + facet normal 0.646908 -0.145926 0.748476 + outer loop + vertex -829.473 286.114 51.3554 + vertex -827.195 296.551 51.4218 + vertex -829.49 290.836 52.2909 + endloop + endfacet + facet normal 0.621792 -0.16663 0.765251 + outer loop + vertex -827.195 296.551 51.4218 + vertex -824.653 306.009 51.4156 + vertex -827.224 300.295 52.2601 + endloop + endfacet + facet normal 0.617169 -0.19327 0.762725 + outer loop + vertex -824.653 306.009 51.4156 + vertex -821.678 315.393 51.3862 + vertex -824.596 309.389 52.2258 + endloop + endfacet + facet normal 0.617038 -0.216996 0.756424 + outer loop + vertex -821.678 315.393 51.3862 + vertex -818.563 323.84 51.2687 + vertex -820.969 319.932 52.1102 + endloop + endfacet + facet normal 0.636489 -0.245755 0.731086 + outer loop + vertex -818.563 323.84 51.2687 + vertex -815.657 331.83 51.4246 + vertex -818.969 325.687 52.2429 + endloop + endfacet + facet normal 0.638043 -0.260381 0.72464 + outer loop + vertex -815.657 331.83 51.4246 + vertex -812.237 339.83 51.2874 + vertex -814.811 335.939 52.1562 + endloop + endfacet + facet normal 0.649814 -0.279098 0.706998 + outer loop + vertex -812.237 339.83 51.2874 + vertex -808.992 347.627 51.383 + vertex -812.562 341.457 52.2286 + endloop + endfacet + facet normal 0.659196 -0.296139 0.691204 + outer loop + vertex -808.992 347.627 51.383 + vertex -805.275 355.625 51.2642 + vertex -807.984 351.611 52.1292 + endloop + endfacet + facet normal 0.679137 -0.314739 0.663108 + outer loop + vertex -805.275 355.625 51.2642 + vertex -801.964 363.31 51.5214 + vertex -805.522 357.223 52.2764 + endloop + endfacet + facet normal 0.710638 -0.32549 0.623738 + outer loop + vertex -801.964 363.31 51.5214 + vertex -798.597 370.589 51.4835 + vertex -800.818 367.229 52.2612 + endloop + endfacet + facet normal 0.733056 -0.308838 0.60601 + outer loop + vertex -798.597 370.589 51.4835 + vertex -795.944 376.49 51.2815 + vertex -798.333 372.62 52.2001 + endloop + endfacet + facet normal 0.732972 -0.239333 0.636767 + outer loop + vertex -795.944 376.49 51.2815 + vertex -795.37 375.536 50.2622 + vertex -792.003 384.848 49.887 + endloop + endfacet + facet normal 0.645327 -0.203639 0.736264 + outer loop + vertex -795.37 375.536 50.2622 + vertex -791.95 377.554 47.8233 + vertex -792.003 384.848 49.887 + endloop + endfacet + facet normal -0.241692 -0.564834 0.789017 + outer loop + vertex -845.484 242.439 46.8749 + vertex -846.708 242.159 46.2995 + vertex -845.808 241.951 46.4259 + endloop + endfacet + facet normal 0.797064 -0.287157 0.531253 + outer loop + vertex -795.203 379.625 51.8645 + vertex -795.944 376.49 51.2815 + vertex -792.003 384.848 49.887 + endloop + endfacet + facet normal -0.08619 -0.528887 0.844304 + outer loop + vertex -841.883 236.959 43.4941 + vertex -839.248 235.871 43.0815 + vertex -841.836 237.347 43.7421 + endloop + endfacet + facet normal 0.634638 -0.450991 -0.627567 + outer loop + vertex 689.914 145.187 292.777 + vertex 690.058 143.531 294.113 + vertex 688.166 144.145 291.758 + endloop + endfacet + facet normal 0.553472 -0.468526 -0.688587 + outer loop + vertex 692.448 143.558 296.112 + vertex 691.363 143.311 295.408 + vertex 692.349 144.116 295.654 + endloop + endfacet + facet normal 0.707266 -0.441865 -0.551842 + outer loop + vertex 686.082 144.977 288.772 + vertex 684.176 145.557 285.865 + vertex 685.411 146.432 286.747 + endloop + endfacet + facet normal 0.674073 -0.440206 -0.593164 + outer loop + vertex 688.166 144.145 291.758 + vertex 686.082 144.977 288.772 + vertex 687.563 145.789 289.852 + endloop + endfacet + facet normal 0.758145 -0.464352 -0.457815 + outer loop + vertex 682.2 146.476 282.197 + vertex 680.526 147.52 278.366 + vertex 681.792 148.193 279.78 + endloop + endfacet + facet normal 0.732679 -0.452677 -0.508197 + outer loop + vertex 684.176 145.557 285.865 + vertex 682.2 146.476 282.197 + vertex 683.509 147.254 283.392 + endloop + endfacet + facet normal 0.789153 -0.483242 -0.379097 + outer loop + vertex 679.093 148.583 274.454 + vertex 678.118 149.625 271.097 + vertex 679.084 150.194 272.382 + endloop + endfacet + facet normal 0.778428 -0.472382 -0.413407 + outer loop + vertex 680.526 147.52 278.366 + vertex 679.093 148.583 274.454 + vertex 680.322 149.211 276.05 + endloop + endfacet + facet normal 0.757341 -0.50906 0.409015 + outer loop + vertex 679.149 148.323 68.2221 + vertex 680.506 147.248 64.371 + vertex 680.67 148.751 65.9388 + endloop + endfacet + facet normal 0.774863 -0.507033 0.377498 + outer loop + vertex 678.188 149.355 71.5805 + vertex 679.149 148.323 68.2221 + vertex 679.402 149.744 69.612 + endloop + endfacet + facet normal 0.717677 -0.488367 0.496424 + outer loop + vertex 682.133 146.289 60.6719 + vertex 683.771 145.628 57.6531 + vertex 683.668 146.953 59.1051 + endloop + endfacet + facet normal 0.739116 -0.497661 0.453917 + outer loop + vertex 680.506 147.248 64.371 + vertex 682.133 146.289 60.6719 + vertex 682.099 147.815 62.3988 + endloop + endfacet + facet normal 0.670767 -0.46345 0.579039 + outer loop + vertex 685.604 144.86 54.6185 + vertex 688.142 143.974 50.9683 + vertex 687.841 145.6 52.6193 + endloop + endfacet + facet normal 0.696393 -0.472421 0.540236 + outer loop + vertex 683.771 145.628 57.6531 + vertex 685.604 144.86 54.6185 + vertex 685.537 146.221 55.8952 + endloop + endfacet + facet normal 0.551398 -0.498997 0.668552 + outer loop + vertex 692.932 143.932 46.4628 + vertex 692.497 143.896 46.795 + vertex 692.121 143.156 46.5526 + endloop + endfacet + facet normal 0.562076 -0.491852 0.664945 + outer loop + vertex 692.118 144.16 47.3106 + vertex 691.077 143.215 47.4913 + vertex 692.497 143.896 46.795 + endloop + endfacet + facet normal 0.562807 -0.501129 0.657357 + outer loop + vertex 691.077 143.215 47.4913 + vertex 692.121 143.156 46.5526 + vertex 692.497 143.896 46.795 + endloop + endfacet + facet normal 0.563099 -0.515805 0.64565 + outer loop + vertex 691.705 142.658 46.5182 + vertex 692.121 143.156 46.5526 + vertex 690.725 142.663 47.376 + endloop + endfacet + facet normal 0.564378 -0.497363 0.658868 + outer loop + vertex 690.725 142.663 47.376 + vertex 692.121 143.156 46.5526 + vertex 691.077 143.215 47.4913 + endloop + endfacet + facet normal 0.583826 -0.504934 0.635759 + outer loop + vertex 690.725 142.663 47.376 + vertex 691.077 143.215 47.4913 + vertex 689.599 143.014 48.6894 + endloop + endfacet + facet normal 0.585742 -0.498276 0.63924 + outer loop + vertex 689.599 143.014 48.6894 + vertex 691.077 143.215 47.4913 + vertex 689.945 143.638 48.8585 + endloop + endfacet + facet normal 0.56757 -0.499968 0.654138 + outer loop + vertex 692.118 144.16 47.3106 + vertex 691.322 144.146 47.9913 + vertex 691.077 143.215 47.4913 + endloop + endfacet + facet normal 0.587302 -0.485681 0.647449 + outer loop + vertex 690.763 144.507 48.7688 + vertex 689.945 143.638 48.8585 + vertex 691.322 144.146 47.9913 + endloop + endfacet + facet normal 0.586493 -0.497071 0.639489 + outer loop + vertex 689.945 143.638 48.8585 + vertex 691.077 143.215 47.4913 + vertex 691.322 144.146 47.9913 + endloop + endfacet + facet normal 0.595722 -0.495157 0.632404 + outer loop + vertex 690.763 144.507 48.7688 + vertex 689.922 144.799 49.7897 + vertex 689.945 143.638 48.8585 + endloop + endfacet + facet normal 0.61476 -0.50527 0.605617 + outer loop + vertex 689.599 143.014 48.6894 + vertex 689.945 143.638 48.8585 + vertex 688.142 143.974 50.9683 + endloop + endfacet + facet normal 0.628325 -0.478964 0.613027 + outer loop + vertex 689.945 143.638 48.8585 + vertex 689.922 144.799 49.7897 + vertex 688.142 143.974 50.9683 + endloop + endfacet + facet normal 0.523427 -0.468397 0.711778 + outer loop + vertex 694.16 145.157 46.3666 + vertex 693.899 144.814 46.3329 + vertex 693.216 143.616 46.0472 + endloop + endfacet + facet normal 0.492638 -0.452036 0.74362 + outer loop + vertex 693.959 145.06 46.4427 + vertex 692.768 143.439 46.2465 + vertex 693.899 144.814 46.3329 + endloop + endfacet + facet normal 0.506716 -0.462605 0.727486 + outer loop + vertex 692.768 143.439 46.2465 + vertex 693.216 143.616 46.0472 + vertex 693.899 144.814 46.3329 + endloop + endfacet + facet normal -0.507401 0.444978 -0.737929 + outer loop + vertex 692.932 143.932 46.4628 + vertex 692.121 143.156 46.5526 + vertex 693.583 144.729 46.4963 + endloop + endfacet + facet normal 0.509803 -0.46245 0.725425 + outer loop + vertex 693.959 145.06 46.4427 + vertex 693.583 144.729 46.4963 + vertex 692.768 143.439 46.2465 + endloop + endfacet + facet normal 0.539394 -0.498264 0.678813 + outer loop + vertex 691.705 142.658 46.5182 + vertex 692.768 143.439 46.2465 + vertex 692.121 143.156 46.5526 + endloop + endfacet + facet normal 0.537615 -0.474516 0.696997 + outer loop + vertex 693.583 144.729 46.4963 + vertex 692.121 143.156 46.5526 + vertex 692.768 143.439 46.2465 + endloop + endfacet + facet normal 0.558079 -0.47438 0.680816 + outer loop + vertex 694.216 144.888 46.1404 + vertex 694.133 144.919 46.2299 + vertex 693.639 143.823 45.8714 + endloop + endfacet + facet normal 0.524292 -0.468747 0.710911 + outer loop + vertex 694.16 145.157 46.3666 + vertex 693.216 143.616 46.0472 + vertex 694.133 144.919 46.2299 + endloop + endfacet + facet normal 0.524804 -0.469029 0.710346 + outer loop + vertex 693.216 143.616 46.0472 + vertex 693.639 143.823 45.8714 + vertex 694.133 144.919 46.2299 + endloop + endfacet + facet normal 0.636008 -0.446686 -0.629258 + outer loop + vertex 694.687 147.065 295.734 + vertex 693.473 144.69 296.194 + vertex 693.898 145.873 295.783 + endloop + endfacet + facet normal 0.898865 -0.390763 -0.198357 + outer loop + vertex 679.341 166.821 247.805 + vertex 679.563 166.374 249.69 + vertex 677.627 162.171 249.197 + endloop + endfacet + facet normal 0.897909 -0.389547 -0.20497 + outer loop + vertex 677.627 162.171 249.197 + vertex 679.563 166.374 249.69 + vertex 677.863 161.701 251.126 + endloop + endfacet + facet normal 0.895591 -0.388036 -0.217587 + outer loop + vertex 678.082 161.072 253.148 + vertex 677.863 161.701 251.126 + vertex 679.801 165.863 251.68 + endloop + endfacet + facet normal 0.89708 -0.390057 -0.207614 + outer loop + vertex 679.801 165.863 251.68 + vertex 677.863 161.701 251.126 + vertex 679.563 166.374 249.69 + endloop + endfacet + facet normal 0.867837 -0.398396 -0.296882 + outer loop + vertex 678.069 159.824 255.187 + vertex 680.024 164.934 254.044 + vertex 679.248 161.532 256.34 + endloop + endfacet + facet normal 0.888807 -0.391782 -0.237759 + outer loop + vertex 679.801 165.863 251.68 + vertex 680.024 164.934 254.044 + vertex 678.082 161.072 253.148 + endloop + endfacet + facet normal 0.889209 -0.392684 -0.234746 + outer loop + vertex 678.082 161.072 253.148 + vertex 680.024 164.934 254.044 + vertex 678.069 159.824 255.187 + endloop + endfacet + facet normal 0.905357 -0.391334 -0.164884 + outer loop + vertex 678.679 168.686 240.346 + vertex 678.818 168.236 242.176 + vertex 676.916 164.064 241.631 + endloop + endfacet + facet normal 0.904916 -0.390594 -0.169009 + outer loop + vertex 676.916 164.064 241.631 + vertex 678.818 168.236 242.176 + vertex 677.064 163.601 243.494 + endloop + endfacet + facet normal 0.903089 -0.390481 -0.17876 + outer loop + vertex 677.225 163.107 245.39 + vertex 677.064 163.601 243.494 + vertex 678.974 167.765 244.046 + endloop + endfacet + facet normal 0.90368 -0.391435 -0.17361 + outer loop + vertex 678.974 167.765 244.046 + vertex 677.064 163.601 243.494 + vertex 678.818 168.236 242.176 + endloop + endfacet + facet normal 0.902606 -0.3908 -0.180495 + outer loop + vertex 678.974 167.765 244.046 + vertex 679.142 167.285 245.929 + vertex 677.225 163.107 245.39 + endloop + endfacet + facet normal 0.901811 -0.389604 -0.186938 + outer loop + vertex 677.225 163.107 245.39 + vertex 679.142 167.285 245.929 + vertex 677.411 162.623 247.294 + endloop + endfacet + facet normal 0.899977 -0.390065 -0.194655 + outer loop + vertex 677.627 162.171 249.197 + vertex 677.411 162.623 247.294 + vertex 679.341 166.821 247.805 + endloop + endfacet + facet normal 0.900331 -0.390547 -0.192034 + outer loop + vertex 679.341 166.821 247.805 + vertex 677.411 162.623 247.294 + vertex 679.142 167.285 245.929 + endloop + endfacet + facet normal 0.910255 -0.390839 -0.136674 + outer loop + vertex 678.248 170.379 233.187 + vertex 678.342 169.958 235.021 + vertex 676.465 165.772 234.487 + endloop + endfacet + facet normal 0.9099 -0.390128 -0.141001 + outer loop + vertex 676.465 165.772 234.487 + vertex 678.342 169.958 235.021 + vertex 676.564 165.353 236.287 + endloop + endfacet + facet normal 0.909231 -0.389561 -0.146772 + outer loop + vertex 676.671 164.938 238.05 + vertex 676.564 165.353 236.287 + vertex 678.444 169.548 236.801 + endloop + endfacet + facet normal 0.90965 -0.390325 -0.142068 + outer loop + vertex 678.444 169.548 236.801 + vertex 676.564 165.353 236.287 + vertex 678.342 169.958 235.021 + endloop + endfacet + facet normal 0.908235 -0.3903 -0.150911 + outer loop + vertex 678.444 169.548 236.801 + vertex 678.556 169.127 238.562 + vertex 676.671 164.938 238.05 + endloop + endfacet + facet normal 0.908066 -0.390009 -0.152672 + outer loop + vertex 676.671 164.938 238.05 + vertex 678.556 169.127 238.562 + vertex 676.791 164.524 239.821 + endloop + endfacet + facet normal 0.906152 -0.39078 -0.161802 + outer loop + vertex 676.916 164.064 241.631 + vertex 676.791 164.524 239.821 + vertex 678.679 168.686 240.346 + endloop + endfacet + facet normal 0.906402 -0.391201 -0.159366 + outer loop + vertex 678.679 168.686 240.346 + vertex 676.791 164.524 239.821 + vertex 678.556 169.127 238.562 + endloop + endfacet + facet normal 0.914506 -0.389185 -0.110521 + outer loop + vertex 677.938 172.052 225.51 + vertex 678.001 171.655 227.424 + vertex 676.142 167.456 226.825 + endloop + endfacet + facet normal 0.914234 -0.388336 -0.115635 + outer loop + vertex 676.142 167.456 226.825 + vertex 678.001 171.655 227.424 + vertex 676.208 167.035 228.763 + endloop + endfacet + facet normal 0.913135 -0.389623 -0.119913 + outer loop + vertex 676.288 166.625 230.708 + vertex 676.208 167.035 228.763 + vertex 678.078 171.234 229.361 + endloop + endfacet + facet normal 0.91307 -0.389439 -0.121 + outer loop + vertex 678.078 171.234 229.361 + vertex 676.208 167.035 228.763 + vertex 678.001 171.655 227.424 + endloop + endfacet + facet normal 0.912648 -0.390078 -0.122116 + outer loop + vertex 678.078 171.234 229.361 + vertex 678.158 170.815 231.293 + vertex 676.288 166.625 230.708 + endloop + endfacet + facet normal 0.912296 -0.389163 -0.127547 + outer loop + vertex 676.288 166.625 230.708 + vertex 678.158 170.815 231.293 + vertex 676.373 166.194 232.626 + endloop + endfacet + facet normal 0.910968 -0.390245 -0.133591 + outer loop + vertex 676.465 165.772 234.487 + vertex 676.373 166.194 232.626 + vertex 678.248 170.379 233.187 + endloop + endfacet + facet normal 0.910993 -0.390304 -0.133245 + outer loop + vertex 678.248 170.379 233.187 + vertex 676.373 166.194 232.626 + vertex 678.158 170.815 231.293 + endloop + endfacet + facet normal 0.916635 -0.38867 -0.0933583 + outer loop + vertex 677.715 173.5 217.867 + vertex 677.766 173.147 219.834 + vertex 675.903 168.9 219.224 + endloop + endfacet + facet normal 0.916568 -0.388368 -0.0952602 + outer loop + vertex 675.903 168.9 219.224 + vertex 677.766 173.147 219.834 + vertex 675.958 168.56 221.145 + endloop + endfacet + facet normal 0.916075 -0.388293 -0.100176 + outer loop + vertex 676.019 168.217 223.03 + vertex 675.958 168.56 221.145 + vertex 677.819 172.795 221.742 + endloop + endfacet + facet normal 0.916196 -0.388769 -0.0971777 + outer loop + vertex 677.819 172.795 221.742 + vertex 675.958 168.56 221.145 + vertex 677.766 173.147 219.834 + endloop + endfacet + facet normal 0.915149 -0.389243 -0.104845 + outer loop + vertex 677.819 172.795 221.742 + vertex 677.879 172.429 223.623 + vertex 676.019 168.217 223.03 + endloop + endfacet + facet normal 0.915095 -0.389055 -0.106009 + outer loop + vertex 676.019 168.217 223.03 + vertex 677.879 172.429 223.623 + vertex 676.078 167.842 224.915 + endloop + endfacet + facet normal 0.9148 -0.388894 -0.109102 + outer loop + vertex 676.142 167.456 226.825 + vertex 676.078 167.842 224.915 + vertex 677.938 172.052 225.51 + endloop + endfacet + facet normal 0.914905 -0.389245 -0.106948 + outer loop + vertex 677.938 172.052 225.51 + vertex 676.078 167.842 224.915 + vertex 677.879 172.429 223.623 + endloop + endfacet + facet normal 0.918628 -0.387815 -0.0756474 + outer loop + vertex 677.528 174.777 209.802 + vertex 677.569 174.493 211.755 + vertex 675.719 170.233 211.13 + endloop + endfacet + facet normal 0.918561 -0.387271 -0.0791619 + outer loop + vertex 675.719 170.233 211.13 + vertex 677.569 174.493 211.755 + vertex 675.759 169.916 213.142 + endloop + endfacet + facet normal 0.917869 -0.388375 -0.081745 + outer loop + vertex 675.809 169.603 215.199 + vertex 675.759 169.916 213.142 + vertex 677.618 174.176 213.782 + endloop + endfacet + facet normal 0.91784 -0.388165 -0.0830526 + outer loop + vertex 677.618 174.176 213.782 + vertex 675.759 169.916 213.142 + vertex 677.569 174.493 211.755 + endloop + endfacet + facet normal 0.917466 -0.388873 -0.0838665 + outer loop + vertex 677.618 174.176 213.782 + vertex 677.667 173.847 215.839 + vertex 675.809 169.603 215.199 + endloop + endfacet + facet normal 0.917396 -0.388415 -0.0867063 + outer loop + vertex 675.809 169.603 215.199 + vertex 677.667 173.847 215.839 + vertex 675.858 169.264 217.241 + endloop + endfacet + facet normal 0.916976 -0.388285 -0.0915978 + outer loop + vertex 675.903 168.9 219.224 + vertex 675.858 169.264 217.241 + vertex 677.715 173.5 217.867 + endloop + endfacet + facet normal 0.917072 -0.388801 -0.0883893 + outer loop + vertex 677.715 173.5 217.867 + vertex 675.858 169.264 217.241 + vertex 677.667 173.847 215.839 + endloop + endfacet + facet normal 0.920028 -0.387411 -0.0588346 + outer loop + vertex 677.393 175.735 202.375 + vertex 677.428 175.532 204.256 + vertex 675.586 171.251 203.64 + endloop + endfacet + facet normal 0.920002 -0.386673 -0.063876 + outer loop + vertex 675.586 171.251 203.64 + vertex 677.428 175.532 204.256 + vertex 675.611 171.003 205.498 + endloop + endfacet + facet normal 0.919475 -0.387715 -0.0651386 + outer loop + vertex 675.643 170.771 207.335 + vertex 675.611 171.003 205.498 + vertex 677.459 175.286 206.098 + endloop + endfacet + facet normal 0.919451 -0.387398 -0.0673278 + outer loop + vertex 677.459 175.286 206.098 + vertex 675.611 171.003 205.498 + vertex 677.428 175.532 204.256 + endloop + endfacet + facet normal 0.918962 -0.388383 -0.0683267 + outer loop + vertex 677.459 175.286 206.098 + vertex 677.49 175.037 207.929 + vertex 675.643 170.771 207.335 + endloop + endfacet + facet normal 0.918898 -0.387769 -0.0725416 + outer loop + vertex 675.643 170.771 207.335 + vertex 677.49 175.037 207.929 + vertex 675.677 170.503 209.196 + endloop + endfacet + facet normal 0.918912 -0.387455 -0.0740282 + outer loop + vertex 675.719 170.233 211.13 + vertex 675.677 170.503 209.196 + vertex 677.528 174.777 209.802 + endloop + endfacet + facet normal 0.918941 -0.387714 -0.0722859 + outer loop + vertex 677.528 174.777 209.802 + vertex 675.677 170.503 209.196 + vertex 677.49 175.037 207.929 + endloop + endfacet + facet normal 0.921725 -0.384123 -0.0535871 + outer loop + vertex 677.724 177.616 194.442 + vertex 677.395 176.568 196.297 + vertex 675.777 172.892 194.821 + endloop + endfacet + facet normal 0.921069 -0.386584 -0.0467414 + outer loop + vertex 675.777 172.892 194.821 + vertex 677.395 176.568 196.297 + vertex 675.51 171.923 197.569 + endloop + endfacet + facet normal 0.921031 -0.38617 -0.0507406 + outer loop + vertex 675.504 171.623 199.743 + vertex 675.51 171.923 197.569 + vertex 677.317 176.123 198.416 + endloop + endfacet + facet normal 0.920948 -0.386768 -0.0475963 + outer loop + vertex 677.317 176.123 198.416 + vertex 675.51 171.923 197.569 + vertex 677.395 176.568 196.297 + endloop + endfacet + facet normal 0.920652 -0.386742 -0.0531972 + outer loop + vertex 677.317 176.123 198.416 + vertex 677.347 175.917 200.436 + vertex 675.504 171.623 199.743 + endloop + endfacet + facet normal 0.920665 -0.386478 -0.0548684 + outer loop + vertex 675.504 171.623 199.743 + vertex 677.347 175.917 200.436 + vertex 675.546 171.44 201.733 + endloop + endfacet + facet normal 0.920178 -0.3872 -0.0578731 + outer loop + vertex 675.586 171.251 203.64 + vertex 675.546 171.44 201.733 + vertex 677.393 175.735 202.375 + endloop + endfacet + facet normal 0.920178 -0.387184 -0.0579823 + outer loop + vertex 677.393 175.735 202.375 + vertex 675.546 171.44 201.733 + vertex 677.347 175.917 200.436 + endloop + endfacet + facet normal 0.919774 -0.390516 -0.0389069 + outer loop + vertex 677.514 177.915 186.71 + vertex 677.297 177.201 188.753 + vertex 675.506 173.093 187.644 + endloop + endfacet + facet normal 0.921384 -0.38692 -0.0366643 + outer loop + vertex 677.617 177.787 190.601 + vertex 675.661 173.053 191.406 + vertex 677.297 177.201 188.753 + endloop + endfacet + facet normal 0.919957 -0.389763 -0.0419908 + outer loop + vertex 675.661 173.053 191.406 + vertex 675.506 173.093 187.644 + vertex 677.297 177.201 188.753 + endloop + endfacet + facet normal 0.920252 -0.388375 -0.0479744 + outer loop + vertex 677.617 177.787 190.601 + vertex 677.425 177.084 192.619 + vertex 675.661 173.053 191.406 + endloop + endfacet + facet normal 0.922761 -0.383386 -0.0390689 + outer loop + vertex 677.724 177.616 194.442 + vertex 675.777 172.892 194.821 + vertex 677.425 177.084 192.619 + endloop + endfacet + facet normal 0.92035 -0.387943 -0.04955 + outer loop + vertex 675.777 172.892 194.821 + vertex 675.661 173.053 191.406 + vertex 677.425 177.084 192.619 + endloop + endfacet + facet normal 0.919309 -0.393043 -0.0196884 + outer loop + vertex 677.442 178.178 179.212 + vertex 677.174 177.451 181.211 + vertex 675.347 173.239 179.998 + endloop + endfacet + facet normal 0.920519 -0.390354 -0.0163889 + outer loop + vertex 677.461 178.056 182.967 + vertex 675.394 173.146 183.815 + vertex 677.174 177.451 181.211 + endloop + endfacet + facet normal 0.919423 -0.392707 -0.021028 + outer loop + vertex 675.394 173.146 183.815 + vertex 675.347 173.239 179.998 + vertex 677.174 177.451 181.211 + endloop + endfacet + facet normal 0.919415 -0.392173 -0.0296203 + outer loop + vertex 677.461 178.056 182.967 + vertex 677.214 177.327 184.944 + vertex 675.394 173.146 183.815 + endloop + endfacet + facet normal 0.92097 -0.3887 -0.0269616 + outer loop + vertex 677.514 177.915 186.71 + vertex 675.506 173.093 187.644 + vertex 677.214 177.327 184.944 + endloop + endfacet + facet normal 0.919597 -0.391535 -0.0322754 + outer loop + vertex 675.506 173.093 187.644 + vertex 675.394 173.146 183.815 + vertex 677.214 177.327 184.944 + endloop + endfacet + facet normal 0.919251 -0.393578 -0.00860593 + outer loop + vertex 677.437 178.297 171.373 + vertex 677.159 177.602 173.464 + vertex 675.339 173.379 172.235 + endloop + endfacet + facet normal 0.92061 -0.390479 0.00187225 + outer loop + vertex 677.441 178.276 175.324 + vertex 675.363 173.38 176.134 + vertex 677.159 177.602 173.464 + endloop + endfacet + facet normal 0.918935 -0.394372 -0.00541065 + outer loop + vertex 675.363 173.38 176.134 + vertex 675.339 173.379 172.235 + vertex 677.159 177.602 173.464 + endloop + endfacet + facet normal 0.919801 -0.392236 -0.010818 + outer loop + vertex 677.441 178.276 175.324 + vertex 677.163 177.566 177.386 + vertex 675.363 173.38 176.134 + endloop + endfacet + facet normal 0.920048 -0.391696 -0.00925846 + outer loop + vertex 677.442 178.178 179.212 + vertex 675.347 173.239 179.998 + vertex 677.163 177.566 177.386 + endloop + endfacet + facet normal 0.919769 -0.392321 -0.0104881 + outer loop + vertex 675.347 173.239 179.998 + vertex 675.363 173.38 176.134 + vertex 677.163 177.566 177.386 + endloop + endfacet + facet normal 0.919937 -0.392002 0.00704958 + outer loop + vertex 677.463 178.171 163.482 + vertex 677.175 177.532 165.552 + vertex 675.393 173.328 164.336 + endloop + endfacet + facet normal 0.920304 -0.390811 0.0175169 + outer loop + vertex 677.445 178.252 167.406 + vertex 675.351 173.359 168.275 + vertex 677.175 177.532 165.552 + endloop + endfacet + facet normal 0.919277 -0.393402 0.012859 + outer loop + vertex 675.351 173.359 168.275 + vertex 675.393 173.328 164.336 + vertex 677.175 177.532 165.552 + endloop + endfacet + facet normal 0.919475 -0.393142 0.00240164 + outer loop + vertex 677.445 178.252 167.406 + vertex 677.161 177.601 169.503 + vertex 675.351 173.359 168.275 + endloop + endfacet + facet normal 0.920402 -0.390852 0.00974486 + outer loop + vertex 677.437 178.297 171.373 + vertex 675.339 173.379 172.235 + vertex 677.161 177.601 169.503 + endloop + endfacet + facet normal 0.919237 -0.393678 0.00460336 + outer loop + vertex 675.339 173.379 172.235 + vertex 675.351 173.359 168.275 + vertex 677.161 177.601 169.503 + endloop + endfacet + facet normal 0.918947 -0.393542 0.0257274 + outer loop + vertex 677.505 177.778 155.752 + vertex 677.211 177.227 157.799 + vertex 675.401 172.919 156.582 + endloop + endfacet + facet normal 0.920089 -0.390378 0.0322725 + outer loop + vertex 677.476 178.001 159.619 + vertex 675.376 173.12 160.461 + vertex 677.211 177.227 157.799 + endloop + endfacet + facet normal 0.91887 -0.393681 0.0263358 + outer loop + vertex 675.376 173.12 160.461 + vertex 675.401 172.919 156.582 + vertex 677.211 177.227 157.799 + endloop + endfacet + facet normal 0.919483 -0.392766 0.0169063 + outer loop + vertex 677.476 178.001 159.619 + vertex 677.192 177.424 161.66 + vertex 675.376 173.12 160.461 + endloop + endfacet + facet normal 0.920723 -0.389544 0.0229028 + outer loop + vertex 677.463 178.171 163.482 + vertex 675.393 173.328 164.336 + vertex 677.192 177.424 161.66 + endloop + endfacet + facet normal 0.919464 -0.392803 0.0170668 + outer loop + vertex 675.393 173.328 164.336 + vertex 675.376 173.12 160.461 + vertex 677.192 177.424 161.66 + endloop + endfacet + facet normal 0.918354 -0.393944 0.0378584 + outer loop + vertex 677.6 177.227 148.065 + vertex 677.293 176.705 150.084 + vertex 675.493 172.393 148.88 + endloop + endfacet + facet normal 0.919468 -0.390234 0.0479159 + outer loop + vertex 677.549 177.529 151.885 + vertex 675.472 172.741 152.735 + vertex 677.293 176.705 150.084 + endloop + endfacet + facet normal 0.917992 -0.394526 0.0404835 + outer loop + vertex 675.472 172.741 152.735 + vertex 675.493 172.393 148.88 + vertex 677.293 176.705 150.084 + endloop + endfacet + facet normal 0.91913 -0.392415 0.0347988 + outer loop + vertex 677.549 177.529 151.885 + vertex 677.247 177.003 153.927 + vertex 675.472 172.741 152.735 + endloop + endfacet + facet normal 0.919301 -0.391868 0.0364118 + outer loop + vertex 677.505 177.778 155.752 + vertex 675.401 172.919 156.582 + vertex 677.247 177.003 153.927 + endloop + endfacet + facet normal 0.919069 -0.392517 0.0352523 + outer loop + vertex 675.401 172.919 156.582 + vertex 675.472 172.741 152.735 + vertex 677.247 177.003 153.927 + endloop + endfacet + facet normal 0.91876 -0.390289 0.0596129 + outer loop + vertex 677.703 176.344 140.154 + vertex 677.381 175.904 142.239 + vertex 675.462 171.112 140.44 + endloop + endfacet + facet normal 0.918065 -0.391207 0.0641444 + outer loop + vertex 677.647 176.849 144.189 + vertex 675.501 171.911 144.792 + vertex 677.381 175.904 142.239 + endloop + endfacet + facet normal 0.91798 -0.391489 0.0636414 + outer loop + vertex 675.501 171.911 144.792 + vertex 675.462 171.112 140.44 + vertex 677.381 175.904 142.239 + endloop + endfacet + facet normal 0.91818 -0.393626 0.044766 + outer loop + vertex 677.647 176.849 144.189 + vertex 677.345 176.376 146.239 + vertex 675.501 171.911 144.792 + endloop + endfacet + facet normal 0.918654 -0.391362 0.0539493 + outer loop + vertex 677.6 177.227 148.065 + vertex 675.493 172.393 148.88 + vertex 677.345 176.376 146.239 + endloop + endfacet + facet normal 0.917596 -0.394558 0.0483868 + outer loop + vertex 675.493 172.393 148.88 + vertex 675.501 171.911 144.792 + vertex 677.345 176.376 146.239 + endloop + endfacet + facet normal 0.918713 -0.387493 0.0762553 + outer loop + vertex 677.553 174.388 132.005 + vertex 677.505 174.673 134.029 + vertex 675.679 170.203 133.315 + endloop + endfacet + facet normal 0.920113 -0.386244 0.0648633 + outer loop + vertex 675.679 170.203 133.315 + vertex 677.505 174.673 134.029 + vertex 675.749 170.737 135.496 + endloop + endfacet + facet normal 0.921223 -0.384543 0.0589488 + outer loop + vertex 676.011 171.675 137.527 + vertex 675.749 170.737 135.496 + vertex 677.516 175.065 136.119 + endloop + endfacet + facet normal 0.920294 -0.385379 0.0674001 + outer loop + vertex 677.516 175.065 136.119 + vertex 675.749 170.737 135.496 + vertex 677.505 174.673 134.029 + endloop + endfacet + facet normal 0.92271 -0.377748 0.0768902 + outer loop + vertex 677.516 175.065 136.119 + vertex 677.481 175.426 138.313 + vertex 676.011 171.675 137.527 + endloop + endfacet + facet normal 0.917684 -0.388553 0.0829616 + outer loop + vertex 677.703 176.344 140.154 + vertex 675.462 171.112 140.44 + vertex 677.481 175.426 138.313 + endloop + endfacet + facet normal 0.919168 -0.381092 0.0994977 + outer loop + vertex 675.462 171.112 140.44 + vertex 676.011 171.675 137.527 + vertex 677.481 175.426 138.313 + endloop + endfacet + facet normal 0.916359 -0.389155 0.0940489 + outer loop + vertex 677.766 173.127 124.192 + vertex 677.722 173.494 126.134 + vertex 675.894 169.009 125.391 + endloop + endfacet + facet normal 0.917103 -0.388608 0.0889113 + outer loop + vertex 675.894 169.009 125.391 + vertex 677.722 173.494 126.134 + vertex 675.858 169.373 127.346 + endloop + endfacet + facet normal 0.917273 -0.388683 0.0868044 + outer loop + vertex 675.804 169.678 129.293 + vertex 675.858 169.373 127.346 + vertex 677.679 173.835 128.092 + endloop + endfacet + facet normal 0.917085 -0.388828 0.0881336 + outer loop + vertex 677.679 173.835 128.092 + vertex 675.858 169.373 127.346 + vertex 677.722 173.494 126.134 + endloop + endfacet + facet normal 0.91728 -0.388603 0.0870909 + outer loop + vertex 677.679 173.835 128.092 + vertex 677.621 174.135 130.042 + vertex 675.804 169.678 129.293 + endloop + endfacet + facet normal 0.91778 -0.388207 0.0835222 + outer loop + vertex 675.804 169.678 129.293 + vertex 677.621 174.135 130.042 + vertex 675.735 169.938 131.257 + endloop + endfacet + facet normal 0.918659 -0.387875 0.074957 + outer loop + vertex 675.679 170.203 133.315 + vertex 675.735 169.938 131.257 + vertex 677.553 174.388 132.005 + endloop + endfacet + facet normal 0.917735 -0.388662 0.0818819 + outer loop + vertex 677.553 174.388 132.005 + vertex 675.735 169.938 131.257 + vertex 677.621 174.135 130.042 + endloop + endfacet + facet normal 0.914137 -0.390186 0.110034 + outer loop + vertex 677.994 171.677 116.695 + vertex 677.931 172.056 118.566 + vertex 676.113 167.588 117.822 + endloop + endfacet + facet normal 0.914709 -0.389829 0.106493 + outer loop + vertex 676.113 167.588 117.822 + vertex 677.931 172.056 118.566 + vertex 676.045 167.938 119.69 + endloop + endfacet + facet normal 0.915527 -0.388967 0.102544 + outer loop + vertex 675.99 168.302 121.56 + vertex 676.045 167.938 119.69 + vertex 677.869 172.424 120.423 + endloop + endfacet + facet normal 0.914708 -0.389486 0.107751 + outer loop + vertex 677.869 172.424 120.423 + vertex 676.045 167.938 119.69 + vertex 677.931 172.056 118.566 + endloop + endfacet + facet normal 0.915512 -0.389694 0.099882 + outer loop + vertex 677.869 172.424 120.423 + vertex 677.815 172.777 122.29 + vertex 675.99 168.302 121.56 + endloop + endfacet + facet normal 0.91571 -0.389562 0.0985761 + outer loop + vertex 675.99 168.302 121.56 + vertex 677.815 172.777 122.29 + vertex 675.941 168.666 123.457 + endloop + endfacet + facet normal 0.916309 -0.389893 0.0914383 + outer loop + vertex 675.894 169.009 125.391 + vertex 675.941 168.666 123.457 + vertex 677.766 173.127 124.192 + endloop + endfacet + facet normal 0.915675 -0.390345 0.0957596 + outer loop + vertex 677.766 173.127 124.192 + vertex 675.941 168.666 123.457 + vertex 677.815 172.777 122.29 + endloop + endfacet + facet normal 0.909628 -0.392544 0.135965 + outer loop + vertex 678.321 169.989 109.115 + vertex 678.225 170.427 111.018 + vertex 676.404 165.941 110.253 + endloop + endfacet + facet normal 0.910839 -0.391929 0.129477 + outer loop + vertex 676.404 165.941 110.253 + vertex 678.225 170.427 111.018 + vertex 676.319 166.371 112.152 + endloop + endfacet + facet normal 0.912061 -0.391459 0.12208 + outer loop + vertex 676.246 166.794 114.049 + vertex 676.319 166.371 112.152 + vertex 678.141 170.855 112.917 + endloop + endfacet + facet normal 0.910851 -0.392117 0.128822 + outer loop + vertex 678.141 170.855 112.917 + vertex 676.319 166.371 112.152 + vertex 678.225 170.427 111.018 + endloop + endfacet + facet normal 0.912049 -0.39117 0.123096 + outer loop + vertex 678.141 170.855 112.917 + vertex 678.066 171.276 114.811 + vertex 676.246 166.794 114.049 + endloop + endfacet + facet normal 0.913204 -0.390509 0.116449 + outer loop + vertex 676.246 166.794 114.049 + vertex 678.066 171.276 114.811 + vertex 676.176 167.193 115.941 + endloop + endfacet + facet normal 0.91413 -0.389586 0.1122 + outer loop + vertex 676.113 167.588 117.822 + vertex 676.176 167.193 115.941 + vertex 677.994 171.677 116.695 + endloop + endfacet + facet normal 0.913194 -0.390141 0.117759 + outer loop + vertex 677.994 171.677 116.695 + vertex 676.176 167.193 115.941 + vertex 678.066 171.276 114.811 + endloop + endfacet + facet normal 0.904047 -0.394442 0.164666 + outer loop + vertex 678.815 168.147 101.506 + vertex 678.673 168.609 103.394 + vertex 676.869 164.148 102.613 + endloop + endfacet + facet normal 0.905386 -0.393902 0.158484 + outer loop + vertex 676.869 164.148 102.613 + vertex 678.673 168.609 103.394 + vertex 676.738 164.615 104.521 + endloop + endfacet + facet normal 0.90743 -0.392231 0.150751 + outer loop + vertex 676.617 165.071 106.436 + vertex 676.738 164.615 104.521 + vertex 678.542 169.086 105.296 + endloop + endfacet + facet normal 0.905274 -0.393138 0.160999 + outer loop + vertex 678.542 169.086 105.296 + vertex 676.738 164.615 104.521 + vertex 678.673 168.609 103.394 + endloop + endfacet + facet normal 0.907445 -0.39236 0.150321 + outer loop + vertex 678.542 169.086 105.296 + vertex 678.426 169.549 107.206 + vertex 676.617 165.071 106.436 + endloop + endfacet + facet normal 0.908689 -0.3918 0.144145 + outer loop + vertex 676.617 165.071 106.436 + vertex 678.426 169.549 107.206 + vertex 676.508 165.523 108.349 + endloop + endfacet + facet normal 0.909625 -0.392514 0.136068 + outer loop + vertex 676.404 165.941 110.253 + vertex 676.508 165.523 108.349 + vertex 678.321 169.989 109.115 + endloop + endfacet + facet normal 0.908795 -0.392918 0.140386 + outer loop + vertex 678.321 169.989 109.115 + vertex 676.508 165.523 108.349 + vertex 678.426 169.549 107.206 + endloop + endfacet + facet normal 0.897273 -0.394574 0.198022 + outer loop + vertex 679.513 166.254 94.0939 + vertex 679.332 166.764 95.927 + vertex 677.523 162.263 95.1586 + endloop + endfacet + facet normal 0.899146 -0.394035 0.190453 + outer loop + vertex 677.523 162.263 95.1586 + vertex 679.332 166.764 95.927 + vertex 677.345 162.744 96.9906 + endloop + endfacet + facet normal 0.900278 -0.39501 0.182936 + outer loop + vertex 677.172 163.206 98.8446 + vertex 677.345 162.744 96.9906 + vertex 679.152 167.223 97.7721 + endloop + endfacet + facet normal 0.899461 -0.395276 0.186348 + outer loop + vertex 679.152 167.223 97.7721 + vertex 677.345 162.744 96.9906 + vertex 679.332 166.764 95.927 + endloop + endfacet + facet normal 0.900282 -0.395028 0.182878 + outer loop + vertex 679.152 167.223 97.7721 + vertex 678.975 167.68 99.6317 + vertex 677.172 163.206 98.8446 + endloop + endfacet + facet normal 0.901972 -0.394442 0.175676 + outer loop + vertex 677.172 163.206 98.8446 + vertex 678.975 167.68 99.6317 + vertex 677.013 163.68 100.72 + endloop + endfacet + facet normal 0.903954 -0.3939 0.166462 + outer loop + vertex 676.869 164.148 102.613 + vertex 677.013 163.68 100.72 + vertex 678.815 168.147 101.506 + endloop + endfacet + facet normal 0.90201 -0.394627 0.175063 + outer loop + vertex 678.815 168.147 101.506 + vertex 677.013 163.68 100.72 + vertex 678.975 167.68 99.6317 + endloop + endfacet + facet normal 0.876783 -0.380396 0.294195 + outer loop + vertex 680.618 165.486 88.4224 + vertex 678.427 161.012 89.1684 + vertex 679.948 162.949 87.1372 + endloop + endfacet + facet normal 0.894555 -0.366005 0.25654 + outer loop + vertex 681.329 166.142 86.8766 + vertex 680.618 165.486 88.4224 + vertex 679.948 162.949 87.1372 + endloop + endfacet + facet normal 0.872354 -0.415795 0.257123 + outer loop + vertex 678.223 159.311 87.107 + vertex 679.948 162.949 87.1372 + vertex 678.427 161.012 89.1684 + endloop + endfacet + facet normal 0.889459 -0.390884 0.236797 + outer loop + vertex 677.963 161.323 91.4227 + vertex 678.427 161.012 89.1684 + vertex 680.014 165.324 90.3228 + endloop + endfacet + facet normal 0.885712 -0.392485 0.24793 + outer loop + vertex 680.014 165.324 90.3228 + vertex 678.427 161.012 89.1684 + vertex 680.618 165.486 88.4224 + endloop + endfacet + facet normal 0.891018 -0.395527 0.222813 + outer loop + vertex 680.014 165.324 90.3228 + vertex 679.708 165.719 92.2475 + vertex 677.963 161.323 91.4227 + endloop + endfacet + facet normal 0.893995 -0.394699 0.212099 + outer loop + vertex 677.963 161.323 91.4227 + vertex 679.708 165.719 92.2475 + vertex 677.717 161.79 93.3308 + endloop + endfacet + facet normal 0.897332 -0.394788 0.197327 + outer loop + vertex 677.523 162.263 95.1586 + vertex 677.717 161.79 93.3308 + vertex 679.513 166.254 94.0939 + endloop + endfacet + facet normal 0.894254 -0.395599 0.209312 + outer loop + vertex 679.513 166.254 94.0939 + vertex 677.717 161.79 93.3308 + vertex 679.708 165.719 92.2475 + endloop + endfacet + facet normal 0.881849 -0.373201 0.288206 + outer loop + vertex 680.998 160.213 79.817 + vertex 682.387 163.652 80.0197 + vertex 680.592 160.675 81.6569 + endloop + endfacet + facet normal 0.881773 -0.372601 0.289214 + outer loop + vertex 680.592 160.675 81.6569 + vertex 682.387 163.652 80.0197 + vertex 681.972 164.101 81.8633 + endloop + endfacet + facet normal 0.855907 -0.426884 0.291877 + outer loop + vertex 679.489 157.048 79.6121 + vertex 680.998 160.213 79.817 + vertex 679.1 157.52 81.4435 + endloop + endfacet + facet normal 0.855796 -0.424682 0.295394 + outer loop + vertex 679.1 157.52 81.4435 + vertex 680.998 160.213 79.817 + vertex 680.592 160.675 81.6569 + endloop + endfacet + facet normal 0.860723 -0.425894 0.278874 + outer loop + vertex 679.1 157.52 81.4435 + vertex 680.592 160.675 81.6569 + vertex 678.719 157.967 83.3031 + endloop + endfacet + facet normal 0.860686 -0.424664 0.280855 + outer loop + vertex 678.719 157.967 83.3031 + vertex 680.592 160.675 81.6569 + vertex 680.208 161.135 83.5294 + endloop + endfacet + facet normal 0.886375 -0.373511 0.273551 + outer loop + vertex 680.592 160.675 81.6569 + vertex 681.972 164.101 81.8633 + vertex 680.208 161.135 83.5294 + endloop + endfacet + facet normal 0.886364 -0.373403 0.273732 + outer loop + vertex 680.208 161.135 83.5294 + vertex 681.972 164.101 81.8633 + vertex 681.601 164.579 83.7186 + endloop + endfacet + facet normal 0.890518 -0.374255 0.25867 + outer loop + vertex 680.208 161.135 83.5294 + vertex 681.601 164.579 83.7186 + vertex 679.935 161.775 85.3951 + endloop + endfacet + facet normal 0.890455 -0.373057 0.260611 + outer loop + vertex 679.935 161.775 85.3951 + vertex 681.601 164.579 83.7186 + vertex 681.361 165.241 85.4866 + endloop + endfacet + facet normal 0.864909 -0.425594 0.266085 + outer loop + vertex 678.719 157.967 83.3031 + vertex 680.208 161.135 83.5294 + vertex 678.387 158.474 85.193 + endloop + endfacet + facet normal 0.864892 -0.422268 0.271387 + outer loop + vertex 678.387 158.474 85.193 + vertex 680.208 161.135 83.5294 + vertex 679.935 161.775 85.3951 + endloop + endfacet + facet normal 0.86821 -0.423082 0.259256 + outer loop + vertex 678.387 158.474 85.193 + vertex 679.935 161.775 85.3951 + vertex 678.223 159.311 87.107 + endloop + endfacet + facet normal 0.868495 -0.414092 0.272479 + outer loop + vertex 678.223 159.311 87.107 + vertex 679.935 161.775 85.3951 + vertex 679.948 162.949 87.1372 + endloop + endfacet + facet normal 0.894271 -0.374225 0.245426 + outer loop + vertex 679.935 161.775 85.3951 + vertex 681.361 165.241 85.4866 + vertex 679.948 162.949 87.1372 + endloop + endfacet + facet normal 0.89443 -0.365903 0.257119 + outer loop + vertex 679.948 162.949 87.1372 + vertex 681.361 165.241 85.4866 + vertex 681.329 166.142 86.8766 + endloop + endfacet + facet normal 0.859338 -0.373198 0.34966 + outer loop + vertex 682.855 158.21 72.5525 + vertex 684.277 161.689 72.7703 + vertex 682.32 158.701 74.3918 + endloop + endfacet + facet normal 0.859131 -0.372225 0.351202 + outer loop + vertex 682.32 158.701 74.3918 + vertex 684.277 161.689 72.7703 + vertex 683.739 162.171 74.5972 + endloop + endfacet + facet normal 0.83178 -0.427568 0.354017 + outer loop + vertex 681.306 154.993 72.3075 + vertex 682.855 158.21 72.5525 + vertex 680.779 155.506 74.163 + endloop + endfacet + facet normal 0.831625 -0.426389 0.355798 + outer loop + vertex 680.779 155.506 74.163 + vertex 682.855 158.21 72.5525 + vertex 682.32 158.701 74.3918 + endloop + endfacet + facet normal 0.838577 -0.428365 0.336589 + outer loop + vertex 680.779 155.506 74.163 + vertex 682.32 158.701 74.3918 + vertex 680.307 156.016 75.9879 + endloop + endfacet + facet normal 0.838345 -0.42629 0.339786 + outer loop + vertex 680.307 156.016 75.9879 + vertex 682.32 158.701 74.3918 + vertex 681.841 159.204 76.2036 + endloop + endfacet + facet normal 0.865838 -0.373862 0.332494 + outer loop + vertex 682.32 158.701 74.3918 + vertex 683.739 162.171 74.5972 + vertex 681.841 159.204 76.2036 + endloop + endfacet + facet normal 0.865443 -0.371823 0.335791 + outer loop + vertex 681.841 159.204 76.2036 + vertex 683.739 162.171 74.5972 + vertex 683.253 162.671 76.4044 + endloop + endfacet + facet normal 0.872215 -0.373428 0.3159 + outer loop + vertex 681.841 159.204 76.2036 + vertex 683.253 162.671 76.4044 + vertex 681.408 159.716 78.0055 + endloop + endfacet + facet normal 0.871916 -0.371695 0.318755 + outer loop + vertex 681.408 159.716 78.0055 + vertex 683.253 162.671 76.4044 + vertex 682.809 163.174 78.2056 + endloop + endfacet + facet normal 0.844879 -0.428145 0.320737 + outer loop + vertex 680.307 156.016 75.9879 + vertex 681.841 159.204 76.2036 + vertex 679.884 156.537 77.7981 + endloop + endfacet + facet normal 0.844678 -0.425926 0.324202 + outer loop + vertex 679.884 156.537 77.7981 + vertex 681.841 159.204 76.2036 + vertex 681.408 159.716 78.0055 + endloop + endfacet + facet normal 0.850703 -0.427607 0.305706 + outer loop + vertex 679.884 156.537 77.7981 + vertex 681.408 159.716 78.0055 + vertex 679.489 157.048 79.6121 + endloop + endfacet + facet normal 0.850554 -0.425448 0.309113 + outer loop + vertex 679.489 157.048 79.6121 + vertex 681.408 159.716 78.0055 + vertex 680.998 160.213 79.817 + endloop + endfacet + facet normal 0.877693 -0.373001 0.300873 + outer loop + vertex 681.408 159.716 78.0055 + vertex 682.809 163.174 78.2056 + vertex 680.998 160.213 79.817 + endloop + endfacet + facet normal 0.877588 -0.372295 0.302051 + outer loop + vertex 680.998 160.213 79.817 + vertex 682.809 163.174 78.2056 + vertex 682.387 163.652 80.0197 + endloop + endfacet + facet normal 0.823315 -0.369533 0.430811 + outer loop + vertex 685.525 156.325 65.2062 + vertex 686.95 159.877 65.5304 + vertex 684.799 156.761 66.9692 + endloop + endfacet + facet normal 0.823413 -0.369789 0.430402 + outer loop + vertex 684.799 156.761 66.9692 + vertex 686.95 159.877 65.5304 + vertex 686.228 160.286 67.2635 + endloop + endfacet + facet normal 0.796651 -0.425252 0.429544 + outer loop + vertex 683.96 153.072 64.8902 + vertex 685.525 156.325 65.2062 + vertex 683.239 153.514 66.6637 + endloop + endfacet + facet normal 0.796044 -0.423059 0.432821 + outer loop + vertex 683.239 153.514 66.6637 + vertex 685.525 156.325 65.2062 + vertex 684.799 156.761 66.9692 + endloop + endfacet + facet normal 0.806594 -0.425963 0.409831 + outer loop + vertex 683.239 153.514 66.6637 + vertex 684.799 156.761 66.9692 + vertex 682.545 153.986 68.5208 + endloop + endfacet + facet normal 0.805972 -0.423164 0.413934 + outer loop + vertex 682.545 153.986 68.5208 + vertex 684.799 156.761 66.9692 + vertex 684.1 157.233 68.8105 + endloop + endfacet + facet normal 0.832449 -0.371819 0.410829 + outer loop + vertex 684.799 156.761 66.9692 + vertex 686.228 160.286 67.2635 + vertex 684.1 157.233 68.8105 + endloop + endfacet + facet normal 0.832183 -0.370977 0.412126 + outer loop + vertex 684.1 157.233 68.8105 + vertex 686.228 160.286 67.2635 + vertex 685.531 160.736 69.0749 + endloop + endfacet + facet normal 0.842331 -0.373353 0.388697 + outer loop + vertex 684.1 157.233 68.8105 + vertex 685.531 160.736 69.0749 + vertex 683.45 157.716 70.6854 + endloop + endfacet + facet normal 0.841656 -0.370829 0.392558 + outer loop + vertex 683.45 157.716 70.6854 + vertex 685.531 160.736 69.0749 + vertex 684.877 161.208 70.9227 + endloop + endfacet + facet normal 0.815719 -0.425832 0.391497 + outer loop + vertex 682.545 153.986 68.5208 + vertex 684.1 157.233 68.8105 + vertex 681.901 154.495 70.4161 + endloop + endfacet + facet normal 0.815567 -0.424987 0.392729 + outer loop + vertex 681.901 154.495 70.4161 + vertex 684.1 157.233 68.8105 + vertex 683.45 157.716 70.6854 + endloop + endfacet + facet normal 0.824062 -0.427331 0.3719 + outer loop + vertex 681.901 154.495 70.4161 + vertex 683.45 157.716 70.6854 + vertex 681.306 154.993 72.3075 + endloop + endfacet + facet normal 0.823752 -0.425293 0.37491 + outer loop + vertex 681.306 154.993 72.3075 + vertex 683.45 157.716 70.6854 + vertex 682.855 158.21 72.5525 + endloop + endfacet + facet normal 0.850938 -0.373074 0.369758 + outer loop + vertex 683.45 157.716 70.6854 + vertex 684.877 161.208 70.9227 + vertex 682.855 158.21 72.5525 + endloop + endfacet + facet normal 0.850451 -0.371022 0.372928 + outer loop + vertex 682.855 158.21 72.5525 + vertex 684.877 161.208 70.9227 + vertex 684.277 161.689 72.7703 + endloop + endfacet + facet normal 0.772962 -0.362999 0.520348 + outer loop + vertex 688.766 154.917 58.8523 + vertex 690.196 158.568 59.2749 + vertex 687.867 155.231 60.407 + endloop + endfacet + facet normal 0.772107 -0.361656 0.522548 + outer loop + vertex 687.867 155.231 60.407 + vertex 690.196 158.568 59.2749 + vertex 689.301 158.855 60.7966 + endloop + endfacet + facet normal 0.748701 -0.418434 0.51416 + outer loop + vertex 687.158 151.53 58.4376 + vertex 688.766 154.917 58.8523 + vertex 686.265 151.89 60.0311 + endloop + endfacet + facet normal 0.747872 -0.41675 0.516727 + outer loop + vertex 686.265 151.89 60.0311 + vertex 688.766 154.917 58.8523 + vertex 687.867 155.231 60.407 + endloop + endfacet + facet normal 0.762355 -0.420868 0.491615 + outer loop + vertex 686.265 151.89 60.0311 + vertex 687.867 155.231 60.407 + vertex 685.449 152.257 61.6101 + endloop + endfacet + facet normal 0.760948 -0.417791 0.496396 + outer loop + vertex 685.449 152.257 61.6101 + vertex 687.867 155.231 60.407 + vertex 687.044 155.574 61.9572 + endloop + endfacet + facet normal 0.786558 -0.364763 0.498272 + outer loop + vertex 687.867 155.231 60.407 + vertex 689.301 158.855 60.7966 + vertex 687.044 155.574 61.9572 + endloop + endfacet + facet normal 0.785966 -0.36377 0.499929 + outer loop + vertex 687.044 155.574 61.9572 + vertex 689.301 158.855 60.7966 + vertex 688.474 159.166 62.3228 + endloop + endfacet + facet normal 0.800591 -0.366925 0.473729 + outer loop + vertex 687.044 155.574 61.9572 + vertex 688.474 159.166 62.3228 + vertex 686.271 155.934 63.5424 + endloop + endfacet + facet normal 0.800392 -0.366553 0.474354 + outer loop + vertex 686.271 155.934 63.5424 + vertex 688.474 159.166 62.3228 + vertex 687.7 159.498 63.8865 + endloop + endfacet + facet normal 0.775405 -0.421957 0.469786 + outer loop + vertex 685.449 152.257 61.6101 + vertex 687.044 155.574 61.9572 + vertex 684.693 152.651 63.2126 + endloop + endfacet + facet normal 0.774557 -0.419878 0.473037 + outer loop + vertex 684.693 152.651 63.2126 + vertex 687.044 155.574 61.9572 + vertex 686.271 155.934 63.5424 + endloop + endfacet + facet normal 0.786344 -0.423234 0.45004 + outer loop + vertex 684.693 152.651 63.2126 + vertex 686.271 155.934 63.5424 + vertex 683.96 153.072 64.8902 + endloop + endfacet + facet normal 0.786013 -0.422267 0.451525 + outer loop + vertex 683.96 153.072 64.8902 + vertex 686.271 155.934 63.5424 + vertex 685.525 156.325 65.2062 + endloop + endfacet + facet normal 0.812608 -0.369191 0.450962 + outer loop + vertex 686.271 155.934 63.5424 + vertex 687.7 159.498 63.8865 + vertex 685.525 156.325 65.2062 + endloop + endfacet + facet normal 0.811594 -0.366999 0.454563 + outer loop + vertex 685.525 156.325 65.2062 + vertex 687.7 159.498 63.8865 + vertex 686.95 159.877 65.5304 + endloop + endfacet + facet normal 0.697804 -0.351167 0.6243 + outer loop + vertex 693.103 154.106 52.9247 + vertex 694.479 157.876 53.5071 + vertex 691.946 154.205 54.2733 + endloop + endfacet + facet normal 0.697701 -0.35106 0.624476 + outer loop + vertex 691.946 154.205 54.2733 + vertex 694.479 157.876 53.5071 + vertex 693.353 157.963 54.8144 + endloop + endfacet + facet normal 0.678692 -0.40162 0.614881 + outer loop + vertex 691.541 150.545 52.3232 + vertex 693.103 154.106 52.9247 + vertex 690.355 150.709 53.7383 + endloop + endfacet + facet normal 0.679829 -0.403069 0.612672 + outer loop + vertex 690.355 150.709 53.7383 + vertex 693.103 154.106 52.9247 + vertex 691.946 154.205 54.2733 + endloop + endfacet + facet normal 0.700888 -0.408383 0.58479 + outer loop + vertex 690.355 150.709 53.7383 + vertex 691.946 154.205 54.2733 + vertex 689.209 150.902 55.2473 + endloop + endfacet + facet normal 0.700542 -0.407868 0.585564 + outer loop + vertex 689.209 150.902 55.2473 + vertex 691.946 154.205 54.2733 + vertex 690.819 154.376 55.7415 + endloop + endfacet + facet normal 0.720825 -0.355473 0.595021 + outer loop + vertex 691.946 154.205 54.2733 + vertex 693.353 157.963 54.8144 + vertex 690.819 154.376 55.7415 + endloop + endfacet + facet normal 0.719889 -0.354346 0.596824 + outer loop + vertex 690.819 154.376 55.7415 + vertex 693.353 157.963 54.8144 + vertex 692.236 158.105 56.2455 + endloop + endfacet + facet normal 0.740862 -0.358426 0.568027 + outer loop + vertex 690.819 154.376 55.7415 + vertex 692.236 158.105 56.2455 + vertex 689.752 154.619 57.2853 + endloop + endfacet + facet normal 0.739543 -0.356641 0.570862 + outer loop + vertex 689.752 154.619 57.2853 + vertex 692.236 158.105 56.2455 + vertex 691.175 158.311 57.7489 + endloop + endfacet + facet normal 0.718617 -0.412577 0.559795 + outer loop + vertex 689.209 150.902 55.2473 + vertex 690.819 154.376 55.7415 + vertex 688.141 151.191 56.8306 + endloop + endfacet + facet normal 0.718224 -0.411906 0.560792 + outer loop + vertex 688.141 151.191 56.8306 + vertex 690.819 154.376 55.7415 + vertex 689.752 154.619 57.2853 + endloop + endfacet + facet normal 0.73394 -0.416113 0.536827 + outer loop + vertex 688.141 151.191 56.8306 + vertex 689.752 154.619 57.2853 + vertex 687.158 151.53 58.4376 + endloop + endfacet + facet normal 0.732855 -0.414061 0.539886 + outer loop + vertex 687.158 151.53 58.4376 + vertex 689.752 154.619 57.2853 + vertex 688.766 154.917 58.8523 + endloop + endfacet + facet normal 0.757165 -0.360179 0.544952 + outer loop + vertex 689.752 154.619 57.2853 + vertex 691.175 158.311 57.7489 + vertex 688.766 154.917 58.8523 + endloop + endfacet + facet normal 0.756783 -0.359614 0.545855 + outer loop + vertex 688.766 154.917 58.8523 + vertex 691.175 158.311 57.7489 + vertex 690.196 158.568 59.2749 + endloop + endfacet + facet normal 0.585639 -0.321222 0.744206 + outer loop + vertex 697.107 153.946 49.1704 + vertex 698.314 157.901 49.9276 + vertex 696.326 153.855 49.7456 + endloop + endfacet + facet normal 0.600753 -0.327967 0.729064 + outer loop + vertex 696.326 153.855 49.7456 + vertex 698.314 157.901 49.9276 + vertex 697.615 157.906 50.5063 + endloop + endfacet + facet normal 0.565317 -0.377404 0.733474 + outer loop + vertex 695.911 150.521 48.3301 + vertex 697.107 153.946 49.1704 + vertex 694.89 149.947 48.8217 + endloop + endfacet + facet normal 0.576445 -0.382577 0.722043 + outer loop + vertex 694.89 149.947 48.8217 + vertex 697.107 153.946 49.1704 + vertex 696.326 153.855 49.7456 + endloop + endfacet + facet normal 0.598787 -0.385991 0.701758 + outer loop + vertex 694.89 149.947 48.8217 + vertex 696.326 153.855 49.7456 + vertex 693.718 149.878 49.784 + endloop + endfacet + facet normal 0.600497 -0.387133 0.699665 + outer loop + vertex 693.718 149.878 49.784 + vertex 696.326 153.855 49.7456 + vertex 695.345 153.915 50.621 + endloop + endfacet + facet normal 0.616994 -0.330354 0.714272 + outer loop + vertex 696.326 153.855 49.7456 + vertex 697.615 157.906 50.5063 + vertex 695.345 153.915 50.621 + endloop + endfacet + facet normal 0.625483 -0.335464 0.70444 + outer loop + vertex 695.345 153.915 50.621 + vertex 697.615 157.906 50.5063 + vertex 696.672 157.882 51.3316 + endloop + endfacet + facet normal 0.572358 -0.463863 0.676193 + outer loop + vertex 693.671 145.247 46.7906 + vertex 694.777 147.621 47.4836 + vertex 693.322 145.43 47.2113 + endloop + endfacet + facet normal 0.569155 -0.462212 0.680016 + outer loop + vertex 693.322 145.43 47.2113 + vertex 694.777 147.621 47.4836 + vertex 694.208 147.537 47.9014 + endloop + endfacet + facet normal 0.556514 -0.481419 0.677147 + outer loop + vertex 692.932 143.932 46.4628 + vertex 693.671 145.247 46.7906 + vertex 692.497 143.896 46.795 + endloop + endfacet + facet normal 0.558933 -0.483533 0.67364 + outer loop + vertex 692.497 143.896 46.795 + vertex 693.671 145.247 46.7906 + vertex 693.322 145.43 47.2113 + endloop + endfacet + facet normal 0.566984 -0.485616 0.665362 + outer loop + vertex 692.497 143.896 46.795 + vertex 693.322 145.43 47.2113 + vertex 692.118 144.16 47.3106 + endloop + endfacet + facet normal 0.567598 -0.486277 0.664354 + outer loop + vertex 692.118 144.16 47.3106 + vertex 693.322 145.43 47.2113 + vertex 692.689 145.43 47.7522 + endloop + endfacet + facet normal 0.575745 -0.462986 0.673915 + outer loop + vertex 693.322 145.43 47.2113 + vertex 694.208 147.537 47.9014 + vertex 692.689 145.43 47.7522 + endloop + endfacet + facet normal 0.58439 -0.468422 0.662623 + outer loop + vertex 692.689 145.43 47.7522 + vertex 694.208 147.537 47.9014 + vertex 693.358 147.026 48.2909 + endloop + endfacet + facet normal 0.581574 -0.468142 0.665292 + outer loop + vertex 692.689 145.43 47.7522 + vertex 693.358 147.026 48.2909 + vertex 692.006 145.518 48.4109 + endloop + endfacet + facet normal 0.576045 -0.462496 0.673995 + outer loop + vertex 692.006 145.518 48.4109 + vertex 693.358 147.026 48.2909 + vertex 692.937 147.446 48.9382 + endloop + endfacet + facet normal 0.572279 -0.486837 0.659914 + outer loop + vertex 692.118 144.16 47.3106 + vertex 692.689 145.43 47.7522 + vertex 691.322 144.146 47.9913 + endloop + endfacet + facet normal 0.572834 -0.487627 0.658848 + outer loop + vertex 691.322 144.146 47.9913 + vertex 692.689 145.43 47.7522 + vertex 692.006 145.518 48.4109 + endloop + endfacet + facet normal 0.584255 -0.489747 0.647143 + outer loop + vertex 691.322 144.146 47.9913 + vertex 692.006 145.518 48.4109 + vertex 690.763 144.507 48.7688 + endloop + endfacet + facet normal 0.581743 -0.484455 0.653359 + outer loop + vertex 690.763 144.507 48.7688 + vertex 692.006 145.518 48.4109 + vertex 691.419 145.891 49.2106 + endloop + endfacet + facet normal 0.594975 -0.466339 0.654624 + outer loop + vertex 692.006 145.518 48.4109 + vertex 692.937 147.446 48.9382 + vertex 691.419 145.891 49.2106 + endloop + endfacet + facet normal 0.593594 -0.464549 0.657145 + outer loop + vertex 691.419 145.891 49.2106 + vertex 692.937 147.446 48.9382 + vertex 692.282 147.384 49.4857 + endloop + endfacet + facet normal 0.600506 -0.487193 0.634062 + outer loop + vertex 690.763 144.507 48.7688 + vertex 691.419 145.891 49.2106 + vertex 689.922 144.799 49.7897 + endloop + endfacet + facet normal 0.596948 -0.465769 0.653232 + outer loop + vertex 692.282 147.384 49.4857 + vertex 691.232 147.091 50.2364 + vertex 691.419 145.891 49.2106 + endloop + endfacet + facet normal 0.594071 -0.467438 0.654661 + outer loop + vertex 691.232 147.091 50.2364 + vertex 689.922 144.799 49.7897 + vertex 691.419 145.891 49.2106 + endloop + endfacet + facet normal 0.645549 -0.338616 0.684548 + outer loop + vertex 695.345 153.915 50.621 + vertex 696.672 157.882 51.3316 + vertex 694.258 154.029 51.7027 + endloop + endfacet + facet normal 0.648788 -0.341059 0.680259 + outer loop + vertex 694.258 154.029 51.7027 + vertex 696.672 157.882 51.3316 + vertex 695.595 157.853 52.3447 + endloop + endfacet + facet normal 0.630315 -0.392912 0.669569 + outer loop + vertex 693.718 149.878 49.784 + vertex 695.345 153.915 50.621 + vertex 692.706 150.344 51.0093 + endloop + endfacet + facet normal 0.628209 -0.391022 0.672648 + outer loop + vertex 692.706 150.344 51.0093 + vertex 695.345 153.915 50.621 + vertex 694.258 154.029 51.7027 + endloop + endfacet + facet normal 0.655484 -0.396839 0.642542 + outer loop + vertex 692.706 150.344 51.0093 + vertex 694.258 154.029 51.7027 + vertex 691.541 150.545 52.3232 + endloop + endfacet + facet normal 0.654697 -0.39599 0.643866 + outer loop + vertex 691.541 150.545 52.3232 + vertex 694.258 154.029 51.7027 + vertex 693.103 154.106 52.9247 + endloop + endfacet + facet normal 0.671184 -0.34485 0.656194 + outer loop + vertex 694.258 154.029 51.7027 + vertex 695.595 157.853 52.3447 + vertex 693.103 154.106 52.9247 + endloop + endfacet + facet normal 0.673182 -0.346643 0.653196 + outer loop + vertex 693.103 154.106 52.9247 + vertex 695.595 157.853 52.3447 + vertex 694.479 157.876 53.5071 + endloop + endfacet + facet normal 0.926864 -0.212923 -0.309172 + outer loop + vertex 697.676 153.998 48.6735 + vertex 698.863 158.027 49.458 + vertex 697.649 153.873 48.6813 + endloop + endfacet + facet normal 0.695231 -0.0692921 -0.715439 + outer loop + vertex 697.649 153.873 48.6813 + vertex 698.863 158.027 49.458 + vertex 698.844 157.846 49.4577 + endloop + endfacet + facet normal 0.938111 -0.345437 0.0249298 + outer loop + vertex 696.356 150.352 47.803 + vertex 697.676 153.998 48.6735 + vertex 696.318 150.248 47.8074 + endloop + endfacet + facet normal 0.866683 -0.209217 -0.452867 + outer loop + vertex 696.318 150.248 47.8074 + vertex 697.676 153.998 48.6735 + vertex 697.649 153.873 48.6813 + endloop + endfacet + facet normal 0.846345 -0.396631 0.355505 + outer loop + vertex 696.318 150.248 47.8074 + vertex 697.649 153.873 48.6813 + vertex 696.334 150.345 47.8768 + endloop + endfacet + facet normal 0.90093 -0.382615 0.204769 + outer loop + vertex 696.334 150.345 47.8768 + vertex 697.649 153.873 48.6813 + vertex 697.655 153.914 48.7313 + endloop + endfacet + facet normal 0.94005 -0.310375 0.141329 + outer loop + vertex 697.649 153.873 48.6813 + vertex 698.844 157.846 49.4577 + vertex 697.655 153.914 48.7313 + endloop + endfacet + facet normal 0.91091 -0.209817 -0.355274 + outer loop + vertex 697.655 153.914 48.7313 + vertex 698.844 157.846 49.4577 + vertex 698.846 157.813 49.4818 + endloop + endfacet + facet normal 0.464212 -0.429517 0.774611 + outer loop + vertex 694.16 145.157 46.3666 + vertex 695.071 147.203 46.9552 + vertex 693.899 144.814 46.3329 + endloop + endfacet + facet normal 0.670376 -0.476924 0.568453 + outer loop + vertex 693.899 144.814 46.3329 + vertex 695.071 147.203 46.9552 + vertex 695.013 147.133 46.9646 + endloop + endfacet + facet normal 0.528795 -0.450082 0.719585 + outer loop + vertex 693.899 144.814 46.3329 + vertex 695.013 147.133 46.9646 + vertex 693.959 145.06 46.4427 + endloop + endfacet + facet normal 0.564406 -0.459656 0.685684 + outer loop + vertex 693.959 145.06 46.4427 + vertex 695.013 147.133 46.9646 + vertex 694.989 147.193 47.0251 + endloop + endfacet + facet normal 0.49598 -0.443283 0.746662 + outer loop + vertex 693.959 145.06 46.4427 + vertex 694.989 147.193 47.0251 + vertex 693.583 144.729 46.4963 + endloop + endfacet + facet normal 0.543971 -0.460904 0.701187 + outer loop + vertex 693.583 144.729 46.4963 + vertex 694.989 147.193 47.0251 + vertex 694.953 147.392 47.1834 + endloop + endfacet + facet normal 0.563474 -0.462216 0.684729 + outer loop + vertex 694.777 147.621 47.4836 + vertex 693.671 145.247 46.7906 + vertex 694.953 147.392 47.1834 + endloop + endfacet + facet normal 0.554213 -0.480721 0.679526 + outer loop + vertex 692.932 143.932 46.4628 + vertex 693.583 144.729 46.4963 + vertex 693.671 145.247 46.7906 + endloop + endfacet + facet normal 0.590091 -0.472602 0.654553 + outer loop + vertex 693.583 144.729 46.4963 + vertex 694.953 147.392 47.1834 + vertex 693.671 145.247 46.7906 + endloop + endfacet + facet normal 0.628819 -0.327759 0.705096 + outer loop + vertex 697.655 153.914 48.7313 + vertex 698.846 157.813 49.4818 + vertex 697.543 153.992 48.8676 + endloop + endfacet + facet normal 0.575866 -0.317465 0.753389 + outer loop + vertex 697.543 153.992 48.8676 + vertex 698.846 157.813 49.4818 + vertex 698.712 157.867 49.6073 + endloop + endfacet + facet normal 0.647116 -0.395636 0.6517 + outer loop + vertex 696.334 150.345 47.8768 + vertex 697.655 153.914 48.7313 + vertex 696.276 150.513 48.0363 + endloop + endfacet + facet normal 0.592244 -0.384866 0.707902 + outer loop + vertex 696.276 150.513 48.0363 + vertex 697.655 153.914 48.7313 + vertex 697.543 153.992 48.8676 + endloop + endfacet + facet normal 0.574264 -0.382162 0.723998 + outer loop + vertex 696.276 150.513 48.0363 + vertex 697.543 153.992 48.8676 + vertex 695.911 150.521 48.3301 + endloop + endfacet + facet normal 0.555044 -0.375917 0.742033 + outer loop + vertex 695.911 150.521 48.3301 + vertex 697.543 153.992 48.8676 + vertex 697.107 153.946 49.1704 + endloop + endfacet + facet normal 0.563465 -0.315649 0.763462 + outer loop + vertex 697.543 153.992 48.8676 + vertex 698.712 157.867 49.6073 + vertex 697.107 153.946 49.1704 + endloop + endfacet + facet normal 0.577725 -0.320079 0.750855 + outer loop + vertex 697.107 153.946 49.1704 + vertex 698.712 157.867 49.6073 + vertex 698.314 157.901 49.9276 + endloop + endfacet + facet normal 0.782498 -0.404506 0.473363 + outer loop + vertex 696.206 149.509 47.3945 + vertex 697.796 153.834 48.4612 + vertex 696.496 150.453 47.7213 + endloop + endfacet + facet normal 0.593676 -0.383156 0.70763 + outer loop + vertex 696.496 150.453 47.7213 + vertex 697.796 153.834 48.4612 + vertex 697.897 154.356 48.6589 + endloop + endfacet + facet normal 0.761166 -0.353653 0.54365 + outer loop + vertex 697.796 153.834 48.4612 + vertex 699.121 158.05 49.3489 + vertex 697.897 154.356 48.6589 + endloop + endfacet + facet normal 0.483088 -0.312773 0.817801 + outer loop + vertex 697.897 154.356 48.6589 + vertex 699.121 158.05 49.3489 + vertex 699.063 158.157 49.424 + endloop + endfacet + facet normal 0.756651 -0.172234 -0.630726 + outer loop + vertex 693.881 144.2 45.9263 + vertex 694.675 145.917 46.4103 + vertex 694.216 144.888 46.1404 + endloop + endfacet + facet normal 0.794938 -0.458957 0.396776 + outer loop + vertex 694.216 144.888 46.1404 + vertex 694.675 145.917 46.4103 + vertex 695.121 147.004 46.7744 + endloop + endfacet + facet normal 0.572245 -0.45019 0.685466 + outer loop + vertex 694.216 144.888 46.1404 + vertex 695.121 147.004 46.7744 + vertex 694.133 144.919 46.2299 + endloop + endfacet + facet normal 0.576679 -0.451152 0.681104 + outer loop + vertex 694.133 144.919 46.2299 + vertex 695.121 147.004 46.7744 + vertex 695.163 147.289 46.9275 + endloop + endfacet + facet normal 0.58745 -0.452781 0.67074 + outer loop + vertex 694.133 144.919 46.2299 + vertex 695.163 147.289 46.9275 + vertex 694.16 145.157 46.3666 + endloop + endfacet + facet normal 0.621188 -0.459244 0.634996 + outer loop + vertex 694.16 145.157 46.3666 + vertex 695.163 147.289 46.9275 + vertex 695.071 147.203 46.9552 + endloop + endfacet + facet normal 0.518269 -0.318694 0.793619 + outer loop + vertex 697.897 154.356 48.6589 + vertex 699.063 158.157 49.424 + vertex 697.783 154.232 48.6835 + endloop + endfacet + facet normal 0.196638 -0.243289 0.949813 + outer loop + vertex 697.783 154.232 48.6835 + vertex 699.063 158.157 49.424 + vertex 698.951 158.171 49.4509 + endloop + endfacet + facet normal 0.650868 -0.390157 0.651266 + outer loop + vertex 696.496 150.453 47.7213 + vertex 697.897 154.356 48.6589 + vertex 696.458 150.535 47.8083 + endloop + endfacet + facet normal 0.568221 -0.376885 0.731493 + outer loop + vertex 696.458 150.535 47.8083 + vertex 697.897 154.356 48.6589 + vertex 697.783 154.232 48.6835 + endloop + endfacet + facet normal 0.666361 -0.389419 0.635858 + outer loop + vertex 696.458 150.535 47.8083 + vertex 697.783 154.232 48.6835 + vertex 696.356 150.352 47.803 + endloop + endfacet + facet normal 0.820492 -0.395477 0.412784 + outer loop + vertex 696.356 150.352 47.803 + vertex 697.783 154.232 48.6835 + vertex 697.676 153.998 48.6735 + endloop + endfacet + facet normal 0.642476 -0.325557 0.693712 + outer loop + vertex 697.783 154.232 48.6835 + vertex 698.951 158.171 49.4509 + vertex 697.676 153.998 48.6735 + endloop + endfacet + facet normal 0.580877 -0.317156 0.749662 + outer loop + vertex 697.676 153.998 48.6735 + vertex 698.951 158.171 49.4509 + vertex 698.863 158.027 49.458 + endloop + endfacet + facet normal 0.483643 -0.109913 -0.868337 + outer loop + vertex 700.867 167.237 293.119 + vertex 700.596 167.909 292.883 + vertex 701.601 176.092 292.407 + endloop + endfacet + facet normal 0.604229 -0.129479 -0.78622 + outer loop + vertex 700.052 166.354 292.721 + vertex 700.441 173.917 291.774 + vertex 700.596 167.909 292.883 + endloop + endfacet + facet normal 0.642802 -0.122924 -0.756106 + outer loop + vertex 700.441 173.917 291.774 + vertex 701.601 176.092 292.407 + vertex 700.596 167.909 292.883 + endloop + endfacet + facet normal 0.710445 -0.134927 -0.690698 + outer loop + vertex 698.647 166.035 291.431 + vertex 697.779 166.717 290.405 + vertex 698.849 173.176 290.244 + endloop + endfacet + facet normal 0.751259 -0.12014 -0.648981 + outer loop + vertex 697.957 175.69 288.747 + vertex 698.849 173.176 290.244 + vertex 697.502 171.417 289.011 + endloop + endfacet + facet normal 0.692881 -0.124522 -0.710219 + outer loop + vertex 700.052 166.354 292.721 + vertex 699.475 167.04 292.037 + vertex 700.441 173.917 291.774 + endloop + endfacet + facet normal 0.68871 -0.137823 -0.711817 + outer loop + vertex 698.647 166.035 291.431 + vertex 698.849 173.176 290.244 + vertex 699.475 167.04 292.037 + endloop + endfacet + facet normal 0.717509 -0.127011 -0.684872 + outer loop + vertex 698.849 173.176 290.244 + vertex 700.441 173.917 291.774 + vertex 699.475 167.04 292.037 + endloop + endfacet + facet normal 0.687163 -0.140554 0.712777 + outer loop + vertex 699.817 166.269 51.2663 + vertex 700.582 173.597 51.9736 + vertex 699.178 166.359 51.9002 + endloop + endfacet + facet normal 0.641064 -0.133204 0.75584 + outer loop + vertex 700.546 166.543 50.6551 + vertex 700.712 167.543 50.6908 + vertex 701.287 173.95 51.3325 + endloop + endfacet + facet normal 0.732405 -0.0307635 -0.680173 + outer loop + vertex 700.612 166.802 50.6164 + vertex 701.473 174.009 51.218 + vertex 700.712 167.543 50.6908 + endloop + endfacet + facet normal 0.548937 -0.131904 0.825391 + outer loop + vertex 701.473 174.009 51.218 + vertex 701.287 173.95 51.3325 + vertex 700.712 167.543 50.6908 + endloop + endfacet + facet normal 0.653214 -0.140032 0.744112 + outer loop + vertex 699.817 166.269 51.2663 + vertex 700.396 167.402 50.9713 + vertex 700.582 173.597 51.9736 + endloop + endfacet + facet normal 0.702521 -0.134141 0.698907 + outer loop + vertex 700.546 166.543 50.6551 + vertex 701.287 173.95 51.3325 + vertex 700.396 167.402 50.9713 + endloop + endfacet + facet normal 0.7028 -0.134163 0.698622 + outer loop + vertex 701.287 173.95 51.3325 + vertex 700.582 173.597 51.9736 + vertex 700.396 167.402 50.9713 + endloop + endfacet + facet normal 0.0122812 -0.084633 0.996337 + outer loop + vertex 700.612 166.802 50.6164 + vertex 700.824 168.088 50.723 + vertex 701.473 174.009 51.218 + endloop + endfacet + facet normal 0.150717 -0.106007 0.982877 + outer loop + vertex 700.886 167.314 50.63 + vertex 701.724 174.559 51.2829 + vertex 700.824 168.088 50.723 + endloop + endfacet + facet normal -0.0989228 -0.0721142 0.992479 + outer loop + vertex 701.724 174.559 51.2829 + vertex 701.473 174.009 51.218 + vertex 700.824 168.088 50.723 + endloop + endfacet + facet normal 0.58663 -0.0406951 -0.808832 + outer loop + vertex 701.328 184.616 291.383 + vertex 701.905 193.97 291.331 + vertex 702.282 186.028 292.004 + endloop + endfacet + facet normal 0.572477 -0.0422147 -0.818834 + outer loop + vertex 702.282 186.028 292.004 + vertex 701.905 193.97 291.331 + vertex 702.586 191.941 291.912 + endloop + endfacet + facet normal 0.586172 -0.0780745 -0.806416 + outer loop + vertex 700.441 173.917 291.774 + vertex 701.328 184.616 291.383 + vertex 701.601 176.092 292.407 + endloop + endfacet + facet normal 0.618715 -0.074114 -0.782112 + outer loop + vertex 701.601 176.092 292.407 + vertex 701.328 184.616 291.383 + vertex 702.282 186.028 292.004 + endloop + endfacet + facet normal 0.754499 -0.0507836 -0.654333 + outer loop + vertex 697.99 182.227 287.971 + vertex 698.648 192.755 287.914 + vertex 699.837 183.399 290.011 + endloop + endfacet + facet normal 0.760229 -0.0485985 -0.647835 + outer loop + vertex 699.837 183.399 290.011 + vertex 698.648 192.755 287.914 + vertex 700.503 194.324 289.972 + endloop + endfacet + facet normal 0.796325 -0.075088 -0.60019 + outer loop + vertex 697.957 175.69 288.747 + vertex 697.99 182.227 287.971 + vertex 698.849 173.176 290.244 + endloop + endfacet + facet normal 0.762946 -0.0883533 -0.640396 + outer loop + vertex 698.849 173.176 290.244 + vertex 697.99 182.227 287.971 + vertex 699.837 183.399 290.011 + endloop + endfacet + facet normal 0.710724 -0.0846261 -0.698363 + outer loop + vertex 698.849 173.176 290.244 + vertex 699.837 183.399 290.011 + vertex 700.441 173.917 291.774 + endloop + endfacet + facet normal 0.711302 -0.0844829 -0.697791 + outer loop + vertex 700.441 173.917 291.774 + vertex 699.837 183.399 290.011 + vertex 701.328 184.616 291.383 + endloop + endfacet + facet normal 0.6962 -0.0449431 -0.716439 + outer loop + vertex 699.837 183.399 290.011 + vertex 700.503 194.324 289.972 + vertex 701.328 184.616 291.383 + endloop + endfacet + facet normal 0.689028 -0.0465408 -0.723239 + outer loop + vertex 701.328 184.616 291.383 + vertex 700.503 194.324 289.972 + vertex 701.905 193.97 291.331 + endloop + endfacet + facet normal 0.901869 -0.055467 -0.428433 + outer loop + vertex 690.813 184.439 276.087 + vertex 691.475 194.187 276.219 + vertex 692.327 183.782 279.359 + endloop + endfacet + facet normal 0.899817 -0.0568754 -0.432544 + outer loop + vertex 692.327 183.782 279.359 + vertex 691.475 194.187 276.219 + vertex 692.996 193.518 279.47 + endloop + endfacet + facet normal 0.868713 -0.0540505 -0.492357 + outer loop + vertex 692.327 183.782 279.359 + vertex 692.996 193.518 279.47 + vertex 694.04 183.086 282.458 + endloop + endfacet + facet normal 0.862509 -0.057647 -0.502748 + outer loop + vertex 694.04 183.086 282.458 + vertex 692.996 193.518 279.47 + vertex 694.728 192.707 282.535 + endloop + endfacet + facet normal 0.76868 -0.0531398 0.637422 + outer loop + vertex 698.535 182.705 55.5273 + vertex 698.696 192.449 56.145 + vertex 696.498 182.6 57.9744 + endloop + endfacet + facet normal 0.782566 -0.0595278 0.619715 + outer loop + vertex 696.498 182.6 57.9744 + vertex 698.696 192.449 56.145 + vertex 696.756 192.448 58.5947 + endloop + endfacet + facet normal 0.814988 -0.0576615 0.576602 + outer loop + vertex 696.498 182.6 57.9744 + vertex 696.756 192.448 58.5947 + vertex 694.548 182.916 60.7619 + endloop + endfacet + facet normal 0.821373 -0.0613033 0.567087 + outer loop + vertex 694.548 182.916 60.7619 + vertex 696.756 192.448 58.5947 + vertex 694.863 192.711 61.3649 + endloop + endfacet + facet normal 0.750791 -0.0212186 -0.660199 + outer loop + vertex 698.648 192.755 287.914 + vertex 698.929 203.234 287.896 + vertex 700.503 194.324 289.972 + endloop + endfacet + facet normal 0.694376 -0.0110779 -0.719527 + outer loop + vertex 701.905 193.97 291.331 + vertex 700.503 194.324 289.972 + vertex 700.98 208.153 290.221 + endloop + endfacet + facet normal 0.752168 -0.00233799 -0.658967 + outer loop + vertex 698.61 212.334 287.5 + vertex 700.98 208.153 290.221 + vertex 698.929 203.234 287.896 + endloop + endfacet + facet normal 0.765051 -0.014878 -0.643798 + outer loop + vertex 700.503 194.324 289.972 + vertex 698.929 203.234 287.896 + vertex 700.98 208.153 290.221 + endloop + endfacet + facet normal 0.90517 -0.00195104 -0.425045 + outer loop + vertex 691.777 203.377 276.303 + vertex 691.805 211.973 276.323 + vertex 693.3 202.611 279.55 + endloop + endfacet + facet normal 0.903886 -0.00309267 -0.427762 + outer loop + vertex 693.3 202.611 279.55 + vertex 691.805 211.973 276.323 + vertex 693.326 211.221 279.543 + endloop + endfacet + facet normal 0.90348 -0.0257783 -0.427855 + outer loop + vertex 691.475 194.187 276.219 + vertex 691.777 203.377 276.303 + vertex 692.996 193.518 279.47 + endloop + endfacet + facet normal 0.902619 -0.0264541 -0.429628 + outer loop + vertex 692.996 193.518 279.47 + vertex 691.777 203.377 276.303 + vertex 693.3 202.611 279.55 + endloop + endfacet + facet normal 0.867489 -0.0246868 -0.496844 + outer loop + vertex 692.996 193.518 279.47 + vertex 693.3 202.611 279.55 + vertex 694.728 192.707 282.535 + endloop + endfacet + facet normal 0.864111 -0.0269032 -0.502582 + outer loop + vertex 694.728 192.707 282.535 + vertex 693.3 202.611 279.55 + vertex 695.043 201.838 282.588 + endloop + endfacet + facet normal 0.867058 -0.00304515 -0.498198 + outer loop + vertex 693.3 202.611 279.55 + vertex 693.326 211.221 279.543 + vertex 695.043 201.838 282.588 + endloop + endfacet + facet normal 0.865801 -0.00398099 -0.500373 + outer loop + vertex 695.043 201.838 282.588 + vertex 693.326 211.221 279.543 + vertex 695.065 210.646 282.556 + endloop + endfacet + facet normal 0.793974 -0.00321709 0.607944 + outer loop + vertex 698.606 201.816 56.6154 + vertex 698.232 208.882 57.1409 + vertex 696.781 201.525 58.9971 + endloop + endfacet + facet normal 0.798402 -0.00556506 0.602099 + outer loop + vertex 696.781 201.525 58.9971 + vertex 698.232 208.882 57.1409 + vertex 696.769 210.18 59.0929 + endloop + endfacet + facet normal 0.783733 -0.0236545 0.620648 + outer loop + vertex 698.696 192.449 56.145 + vertex 698.606 201.816 56.6154 + vertex 696.756 192.448 58.5947 + endloop + endfacet + facet normal 0.795164 -0.0290711 0.605697 + outer loop + vertex 696.756 192.448 58.5947 + vertex 698.606 201.816 56.6154 + vertex 696.781 201.525 58.9971 + endloop + endfacet + facet normal 0.824119 -0.0273811 0.565754 + outer loop + vertex 696.756 192.448 58.5947 + vertex 696.781 201.525 58.9971 + vertex 694.863 192.711 61.3649 + endloop + endfacet + facet normal 0.827978 -0.0297749 0.559969 + outer loop + vertex 694.863 192.711 61.3649 + vertex 696.781 201.525 58.9971 + vertex 694.968 202.005 61.7042 + endloop + endfacet + facet normal 0.830372 -0.00502408 0.557187 + outer loop + vertex 696.781 201.525 58.9971 + vertex 696.769 210.18 59.0929 + vertex 694.968 202.005 61.7042 + endloop + endfacet + facet normal 0.831396 -0.0057405 0.555651 + outer loop + vertex 694.968 202.005 61.7042 + vertex 696.769 210.18 59.0929 + vertex 694.966 210.894 61.7979 + endloop + endfacet + facet normal 0.751148 -0.0146929 0.659971 + outer loop + vertex 701.58 200.385 53.3107 + vertex 702.081 193.887 52.5951 + vertex 702.292 207.242 52.6526 + endloop + endfacet + facet normal 0.761244 0.00968775 -0.648393 + outer loop + vertex 698.61 212.334 287.5 + vertex 698.778 220.787 287.823 + vertex 700.98 208.153 290.221 + endloop + endfacet + facet normal 0.763413 0.0101219 -0.645831 + outer loop + vertex 698.35 230.15 287.464 + vertex 700.432 227.357 289.882 + vertex 698.778 220.787 287.823 + endloop + endfacet + facet normal 0.76299 0.010384 -0.646327 + outer loop + vertex 700.432 227.357 289.882 + vertex 700.98 208.153 290.221 + vertex 698.778 220.787 287.823 + endloop + endfacet + facet normal 0.903784 0.00575141 -0.427951 + outer loop + vertex 691.699 220.382 276.264 + vertex 691.612 229.058 276.197 + vertex 693.223 219.741 279.473 + endloop + endfacet + facet normal 0.905004 0.00687746 -0.425348 + outer loop + vertex 693.223 219.741 279.473 + vertex 691.612 229.058 276.197 + vertex 693.141 228.345 279.438 + endloop + endfacet + facet normal 0.904896 0.0084083 -0.42555 + outer loop + vertex 691.805 211.973 276.323 + vertex 691.699 220.382 276.264 + vertex 693.326 211.221 279.543 + endloop + endfacet + facet normal 0.903907 0.00747568 -0.427665 + outer loop + vertex 693.326 211.221 279.543 + vertex 691.699 220.382 276.264 + vertex 693.223 219.741 279.473 + endloop + endfacet + facet normal 0.866649 0.00644042 -0.498876 + outer loop + vertex 693.326 211.221 279.543 + vertex 693.223 219.741 279.473 + vertex 695.065 210.646 282.556 + endloop + endfacet + facet normal 0.866679 0.00646399 -0.498824 + outer loop + vertex 695.065 210.646 282.556 + vertex 693.223 219.741 279.473 + vertex 694.962 219.345 282.49 + endloop + endfacet + facet normal 0.866666 0.00621089 -0.49885 + outer loop + vertex 693.223 219.741 279.473 + vertex 693.141 228.345 279.438 + vertex 694.962 219.345 282.49 + endloop + endfacet + facet normal 0.868959 0.00804175 -0.494819 + outer loop + vertex 694.962 219.345 282.49 + vertex 693.141 228.345 279.438 + vertex 694.87 228.004 282.469 + endloop + endfacet + facet normal 0.797227 0.0111396 0.603577 + outer loop + vertex 698.485 217.617 56.7474 + vertex 698.258 225.81 56.8968 + vertex 696.746 218.855 59.022 + endloop + endfacet + facet normal 0.800061 0.00938346 0.599845 + outer loop + vertex 696.746 218.855 59.022 + vertex 698.258 225.81 56.8968 + vertex 696.7 227.617 58.9459 + endloop + endfacet + facet normal 0.801377 0.0037369 0.598148 + outer loop + vertex 698.232 208.882 57.1409 + vertex 698.485 217.617 56.7474 + vertex 696.769 210.18 59.0929 + endloop + endfacet + facet normal 0.796199 0.00709088 0.604994 + outer loop + vertex 696.769 210.18 59.0929 + vertex 698.485 217.617 56.7474 + vertex 696.746 218.855 59.022 + endloop + endfacet + facet normal 0.832915 0.00676774 0.55336 + outer loop + vertex 696.769 210.18 59.0929 + vertex 696.746 218.855 59.022 + vertex 694.966 210.894 61.7979 + endloop + endfacet + facet normal 0.832192 0.00730574 0.554439 + outer loop + vertex 694.966 210.894 61.7979 + vertex 696.746 218.855 59.022 + vertex 694.915 219.632 61.7596 + endloop + endfacet + facet normal 0.832421 0.00915476 0.554067 + outer loop + vertex 696.746 218.855 59.022 + vertex 696.7 227.617 58.9459 + vertex 694.915 219.632 61.7596 + endloop + endfacet + facet normal 0.833016 0.00870936 0.553181 + outer loop + vertex 694.915 219.632 61.7596 + vertex 696.7 227.617 58.9459 + vertex 694.855 228.301 61.714 + endloop + endfacet + facet normal 0.762473 0.00844014 -0.646965 + outer loop + vertex 698.35 230.15 287.464 + vertex 698.583 238.681 287.851 + vertex 700.432 227.357 289.882 + endloop + endfacet + facet normal 0.775445 0.00459989 -0.631398 + outer loop + vertex 698.295 247.839 287.563 + vertex 700.325 245.887 290.042 + vertex 698.583 238.681 287.851 + endloop + endfacet + facet normal 0.76658 0.00998842 -0.642071 + outer loop + vertex 700.325 245.887 290.042 + vertex 700.432 227.357 289.882 + vertex 698.583 238.681 287.851 + endloop + endfacet + facet normal 0.906684 -5.47916e-05 -0.42181 + outer loop + vertex 691.684 237.704 276.368 + vertex 691.941 244.42 276.919 + vertex 693.143 236.727 279.504 + endloop + endfacet + facet normal 0.900021 -0.0057993 -0.435808 + outer loop + vertex 693.143 236.727 279.504 + vertex 691.941 244.42 276.919 + vertex 693.153 245.166 279.413 + endloop + endfacet + facet normal 0.904518 0.00090142 -0.426434 + outer loop + vertex 691.612 229.058 276.197 + vertex 691.684 237.704 276.368 + vertex 693.141 228.345 279.438 + endloop + endfacet + facet normal 0.907053 0.00307639 -0.421005 + outer loop + vertex 693.141 228.345 279.438 + vertex 691.684 237.704 276.368 + vertex 693.143 236.727 279.504 + endloop + endfacet + facet normal 0.86877 0.00367483 -0.495202 + outer loop + vertex 693.141 228.345 279.438 + vertex 693.143 236.727 279.504 + vertex 694.87 228.004 282.469 + endloop + endfacet + facet normal 0.867761 0.00287309 -0.496973 + outer loop + vertex 694.87 228.004 282.469 + vertex 693.143 236.727 279.504 + vertex 694.835 236.683 282.459 + endloop + endfacet + facet normal 0.867687 -0.00642035 -0.497069 + outer loop + vertex 693.143 236.727 279.504 + vertex 693.153 245.166 279.413 + vertex 694.835 236.683 282.459 + endloop + endfacet + facet normal 0.873864 -0.00128293 -0.48617 + outer loop + vertex 694.835 236.683 282.459 + vertex 693.153 245.166 279.413 + vertex 694.842 245.366 282.448 + endloop + endfacet + facet normal 0.797522 0.00682536 0.603251 + outer loop + vertex 698.457 235.315 56.538 + vertex 698.15 243.919 56.8465 + vertex 696.655 236.413 58.9089 + endloop + endfacet + facet normal 0.806158 0.00192949 0.591697 + outer loop + vertex 696.655 236.413 58.9089 + vertex 698.15 243.919 56.8465 + vertex 696.644 245.114 58.8948 + endloop + endfacet + facet normal 0.798634 0.00595131 0.601787 + outer loop + vertex 698.258 225.81 56.8968 + vertex 698.457 235.315 56.538 + vertex 696.7 227.617 58.9459 + endloop + endfacet + facet normal 0.797491 0.0066833 0.603294 + outer loop + vertex 696.7 227.617 58.9459 + vertex 698.457 235.315 56.538 + vertex 696.655 236.413 58.9089 + endloop + endfacet + facet normal 0.832796 0.0066581 0.553541 + outer loop + vertex 696.7 227.617 58.9459 + vertex 696.655 236.413 58.9089 + vertex 694.855 228.301 61.714 + endloop + endfacet + facet normal 0.835982 0.00429124 0.54874 + outer loop + vertex 694.855 228.301 61.714 + vertex 696.655 236.413 58.9089 + vertex 694.827 236.901 61.6894 + endloop + endfacet + facet normal 0.835796 0.00189566 0.549037 + outer loop + vertex 696.655 236.413 58.9089 + vertex 696.644 245.114 58.8948 + vertex 694.827 236.901 61.6894 + endloop + endfacet + facet normal 0.839109 -0.000564043 0.543963 + outer loop + vertex 694.827 236.901 61.6894 + vertex 696.644 245.114 58.8948 + vertex 694.849 245.457 61.6648 + endloop + endfacet + facet normal 0.774067 0.00100094 -0.633103 + outer loop + vertex 698.295 247.839 287.563 + vertex 698.566 256.573 287.909 + vertex 700.325 245.887 290.042 + endloop + endfacet + facet normal 0.789941 -0.00241557 -0.613179 + outer loop + vertex 698.343 265.767 287.584 + vertex 700.114 264.926 289.87 + vertex 698.566 256.573 287.909 + endloop + endfacet + facet normal 0.778812 0.00295055 -0.62725 + outer loop + vertex 700.114 264.926 289.87 + vertex 700.325 245.887 290.042 + vertex 698.566 256.573 287.909 + endloop + endfacet + facet normal 0.916896 -0.0175882 -0.398738 + outer loop + vertex 691.743 253.322 275.952 + vertex 691.952 261.547 276.071 + vertex 693.191 253.865 279.259 + endloop + endfacet + facet normal 0.91888 -0.0153997 -0.394236 + outer loop + vertex 693.191 253.865 279.259 + vertex 691.952 261.547 276.071 + vertex 693.3 262.732 279.167 + endloop + endfacet + facet normal 0.902152 -0.0266958 -0.430591 + outer loop + vertex 691.941 244.42 276.919 + vertex 691.743 253.322 275.952 + vertex 693.153 245.166 279.413 + endloop + endfacet + facet normal 0.916591 -0.0110782 -0.399673 + outer loop + vertex 693.153 245.166 279.413 + vertex 691.743 253.322 275.952 + vertex 693.191 253.865 279.259 + endloop + endfacet + facet normal 0.874108 -0.0124123 -0.485573 + outer loop + vertex 693.153 245.166 279.413 + vertex 693.191 253.865 279.259 + vertex 694.842 245.366 282.448 + endloop + endfacet + facet normal 0.880624 -0.00671774 -0.473768 + outer loop + vertex 694.842 245.366 282.448 + vertex 693.191 253.865 279.259 + vertex 694.907 254.119 282.445 + endloop + endfacet + facet normal 0.880835 -0.0157504 -0.473161 + outer loop + vertex 693.191 253.865 279.259 + vertex 693.3 262.732 279.167 + vertex 694.907 254.119 282.445 + endloop + endfacet + facet normal 0.887663 -0.00961864 -0.460393 + outer loop + vertex 694.907 254.119 282.445 + vertex 693.3 262.732 279.167 + vertex 695.023 262.917 282.484 + endloop + endfacet + facet normal 0.808579 -0.000588342 0.588387 + outer loop + vertex 698.408 253.32 56.512 + vertex 698.193 261.466 56.8151 + vertex 696.677 253.739 58.8906 + endloop + endfacet + facet normal 0.817918 -0.00593471 0.575304 + outer loop + vertex 696.677 253.739 58.8906 + vertex 698.193 261.466 56.8151 + vertex 696.733 262.565 58.9026 + endloop + endfacet + facet normal 0.805352 -0.000968548 0.592796 + outer loop + vertex 698.15 243.919 56.8465 + vertex 698.408 253.32 56.512 + vertex 696.644 245.114 58.8948 + endloop + endfacet + facet normal 0.808388 -0.00282698 0.588643 + outer loop + vertex 696.644 245.114 58.8948 + vertex 698.408 253.32 56.512 + vertex 696.677 253.739 58.8906 + endloop + endfacet + facet normal 0.83897 -0.00296625 0.54417 + outer loop + vertex 696.644 245.114 58.8948 + vertex 696.677 253.739 58.8906 + vertex 694.849 245.457 61.6648 + endloop + endfacet + facet normal 0.842363 -0.00548716 0.538882 + outer loop + vertex 694.849 245.457 61.6648 + vertex 696.677 253.739 58.8906 + vertex 694.898 254.175 61.6757 + endloop + endfacet + facet normal 0.842321 -0.00603904 0.538942 + outer loop + vertex 696.677 253.739 58.8906 + vertex 696.733 262.565 58.9026 + vertex 694.898 254.175 61.6757 + endloop + endfacet + facet normal 0.851123 -0.0126336 0.524814 + outer loop + vertex 694.898 254.175 61.6757 + vertex 696.733 262.565 58.9026 + vertex 694.948 263.406 61.8183 + endloop + endfacet + facet normal 0.789326 -0.00579755 -0.613946 + outer loop + vertex 698.343 265.767 287.584 + vertex 698.655 274.545 287.903 + vertex 700.114 264.926 289.87 + endloop + endfacet + facet normal 0.803884 -0.00841468 -0.594726 + outer loop + vertex 698.496 283.616 287.56 + vertex 700.201 282.662 289.879 + vertex 698.655 274.545 287.903 + endloop + endfacet + facet normal 0.794571 -0.00361462 -0.607161 + outer loop + vertex 700.201 282.662 289.879 + vertex 700.114 264.926 289.87 + vertex 698.655 274.545 287.903 + endloop + endfacet + facet normal 0.929105 -0.0181005 -0.369372 + outer loop + vertex 691.925 271.221 275.306 + vertex 692.363 279.731 275.991 + vertex 693.48 271.641 279.198 + endloop + endfacet + facet normal 0.927549 -0.019823 -0.373175 + outer loop + vertex 693.48 271.641 279.198 + vertex 692.363 279.731 275.991 + vertex 693.689 280.433 279.25 + endloop + endfacet + facet normal 0.920388 -0.0282128 -0.389986 + outer loop + vertex 691.952 261.547 276.071 + vertex 691.925 271.221 275.306 + vertex 693.3 262.732 279.167 + endloop + endfacet + facet normal 0.929092 -0.0174567 -0.369436 + outer loop + vertex 693.3 262.732 279.167 + vertex 691.925 271.221 275.306 + vertex 693.48 271.641 279.198 + endloop + endfacet + facet normal 0.887738 -0.0163096 -0.46006 + outer loop + vertex 693.3 262.732 279.167 + vertex 693.48 271.641 279.198 + vertex 695.023 262.917 282.484 + endloop + endfacet + facet normal 0.892357 -0.0121424 -0.451166 + outer loop + vertex 695.023 262.917 282.484 + vertex 693.48 271.641 279.198 + vertex 695.175 271.702 282.549 + endloop + endfacet + facet normal 0.892317 -0.018522 -0.451029 + outer loop + vertex 693.48 271.641 279.198 + vertex 693.689 280.433 279.25 + vertex 695.175 271.702 282.549 + endloop + endfacet + facet normal 0.896031 -0.0151339 -0.443734 + outer loop + vertex 695.175 271.702 282.549 + vertex 693.689 280.433 279.25 + vertex 695.337 280.45 282.576 + endloop + endfacet + facet normal 0.82444 -0.0041867 0.565934 + outer loop + vertex 698.488 270.909 56.4983 + vertex 698.336 279.263 56.7823 + vertex 696.801 271.733 58.9626 + endloop + endfacet + facet normal 0.835162 -0.0110167 0.549894 + outer loop + vertex 696.801 271.733 58.9626 + vertex 698.336 279.263 56.7823 + vertex 696.93 280.957 58.9521 + endloop + endfacet + facet normal 0.817836 -0.0062618 0.575418 + outer loop + vertex 698.193 261.466 56.8151 + vertex 698.488 270.909 56.4983 + vertex 696.733 262.565 58.9026 + endloop + endfacet + facet normal 0.823525 -0.00982827 0.567195 + outer loop + vertex 696.733 262.565 58.9026 + vertex 698.488 270.909 56.4983 + vertex 696.801 271.733 58.9626 + endloop + endfacet + facet normal 0.851522 -0.00975522 0.524228 + outer loop + vertex 696.733 262.565 58.9026 + vertex 696.801 271.733 58.9626 + vertex 694.948 263.406 61.8183 + endloop + endfacet + facet normal 0.863768 -0.0195866 0.503509 + outer loop + vertex 694.948 263.406 61.8183 + vertex 696.801 271.733 58.9626 + vertex 695.018 273.376 62.0861 + endloop + endfacet + facet normal 0.865731 -0.0114987 0.500377 + outer loop + vertex 696.801 271.733 58.9626 + vertex 696.93 280.957 58.9521 + vertex 695.018 273.376 62.0861 + endloop + endfacet + facet normal 0.870522 -0.0162266 0.491863 + outer loop + vertex 695.018 273.376 62.0861 + vertex 696.93 280.957 58.9521 + vertex 695.41 282.562 61.694 + endloop + endfacet + facet normal 0.803512 -0.0102317 -0.5952 + outer loop + vertex 698.496 283.616 287.56 + vertex 698.838 292.365 287.871 + vertex 700.201 282.662 289.879 + endloop + endfacet + facet normal 0.817542 -0.0111028 -0.575761 + outer loop + vertex 698.718 301.298 287.529 + vertex 700.489 300.028 290.067 + vertex 698.838 292.365 287.871 + endloop + endfacet + facet normal 0.811024 -0.00705952 -0.58497 + outer loop + vertex 700.489 300.028 290.067 + vertex 700.201 282.662 289.879 + vertex 698.838 292.365 287.871 + endloop + endfacet + facet normal 0.936676 -0.0227884 -0.349456 + outer loop + vertex 692.419 289.12 275.302 + vertex 692.84 297.226 275.903 + vertex 693.892 289.106 279.251 + endloop + endfacet + facet normal 0.934265 -0.0256568 -0.355655 + outer loop + vertex 693.892 289.106 279.251 + vertex 692.84 297.226 275.903 + vertex 694.1 297.997 279.158 + endloop + endfacet + facet normal 0.928193 -0.0327241 -0.370658 + outer loop + vertex 692.363 279.731 275.991 + vertex 692.419 289.12 275.302 + vertex 693.689 280.433 279.25 + endloop + endfacet + facet normal 0.936697 -0.0218457 -0.34946 + outer loop + vertex 693.689 280.433 279.25 + vertex 692.419 289.12 275.302 + vertex 693.892 289.106 279.251 + endloop + endfacet + facet normal 0.895949 -0.0208827 -0.443665 + outer loop + vertex 693.689 280.433 279.25 + vertex 693.892 289.106 279.251 + vertex 695.337 280.45 282.576 + endloop + endfacet + facet normal 0.899516 -0.0175483 -0.436535 + outer loop + vertex 695.337 280.45 282.576 + vertex 693.892 289.106 279.251 + vertex 695.492 289.208 282.546 + endloop + endfacet + facet normal 0.899457 -0.025688 -0.436254 + outer loop + vertex 693.892 289.106 279.251 + vertex 694.1 297.997 279.158 + vertex 695.492 289.208 282.546 + endloop + endfacet + facet normal 0.905674 -0.0197918 -0.423513 + outer loop + vertex 695.492 289.208 282.546 + vertex 694.1 297.997 279.158 + vertex 695.671 298.113 282.512 + endloop + endfacet + facet normal 0.842367 -0.00756662 0.538852 + outer loop + vertex 698.655 288.7 56.4691 + vertex 698.514 296.982 56.8057 + vertex 697.031 289.921 59.026 + endloop + endfacet + facet normal 0.853106 -0.0152759 0.521514 + outer loop + vertex 697.031 289.921 59.026 + vertex 698.514 296.982 56.8057 + vertex 697.15 298.809 59.0916 + endloop + endfacet + facet normal 0.835522 -0.0100412 0.549366 + outer loop + vertex 698.336 279.263 56.7823 + vertex 698.655 288.7 56.4691 + vertex 696.93 280.957 58.9521 + endloop + endfacet + facet normal 0.840922 -0.013935 0.540977 + outer loop + vertex 696.93 280.957 58.9521 + vertex 698.655 288.7 56.4691 + vertex 697.031 289.921 59.026 + endloop + endfacet + facet normal 0.871147 -0.0138628 0.490826 + outer loop + vertex 696.93 280.957 58.9521 + vertex 697.031 289.921 59.026 + vertex 695.41 282.562 61.694 + endloop + endfacet + facet normal 0.883624 -0.0250565 0.467526 + outer loop + vertex 695.41 282.562 61.694 + vertex 697.031 289.921 59.026 + vertex 695.242 290.973 62.4636 + endloop + endfacet + facet normal 0.885035 -0.0152882 0.465273 + outer loop + vertex 697.031 289.921 59.026 + vertex 697.15 298.809 59.0916 + vertex 695.242 290.973 62.4636 + endloop + endfacet + facet normal 0.887354 -0.0178017 0.460745 + outer loop + vertex 695.242 290.973 62.4636 + vertex 697.15 298.809 59.0916 + vertex 695.693 300.565 61.9654 + endloop + endfacet + facet normal 0.817563 -0.0110184 -0.575734 + outer loop + vertex 698.718 301.298 287.529 + vertex 699.064 309.542 287.862 + vertex 700.489 300.028 290.067 + endloop + endfacet + facet normal 0.832109 -0.0119414 -0.554484 + outer loop + vertex 698.937 317.97 287.49 + vertex 700.646 316.432 290.087 + vertex 699.064 309.542 287.862 + endloop + endfacet + facet normal 0.825464 -0.00721068 -0.564408 + outer loop + vertex 700.646 316.432 290.087 + vertex 700.489 300.028 290.067 + vertex 699.064 309.542 287.862 + endloop + endfacet + facet normal 0.942978 -0.0385136 -0.33062 + outer loop + vertex 692.897 307.226 274.903 + vertex 693.449 319.462 275.055 + vertex 694.395 307.568 279.138 + endloop + endfacet + facet normal 0.943551 -0.0379281 -0.329047 + outer loop + vertex 694.395 307.568 279.138 + vertex 693.449 319.462 275.055 + vertex 695.06 316.768 279.983 + endloop + endfacet + facet normal 0.934968 -0.0405156 -0.352411 + outer loop + vertex 692.84 297.226 275.903 + vertex 692.897 307.226 274.903 + vertex 694.1 297.997 279.158 + endloop + endfacet + facet normal 0.943039 -0.0297543 -0.331348 + outer loop + vertex 694.1 297.997 279.158 + vertex 692.897 307.226 274.903 + vertex 694.395 307.568 279.138 + endloop + endfacet + facet normal 0.905595 -0.0287878 -0.423165 + outer loop + vertex 694.1 297.997 279.158 + vertex 694.395 307.568 279.138 + vertex 695.671 298.113 282.512 + endloop + endfacet + facet normal 0.912856 -0.0222813 -0.407674 + outer loop + vertex 695.671 298.113 282.512 + vertex 694.395 307.568 279.138 + vertex 695.965 306.74 282.698 + endloop + endfacet + facet normal 0.912188 -0.0283423 -0.40879 + outer loop + vertex 694.395 307.568 279.138 + vertex 695.06 316.768 279.983 + vertex 695.965 306.74 282.698 + endloop + endfacet + facet normal 0.915705 -0.0259195 -0.401014 + outer loop + vertex 695.965 306.74 282.698 + vertex 695.06 316.768 279.983 + vertex 696.386 313.362 283.232 + endloop + endfacet + facet normal 0.858762 -0.0108446 0.51226 + outer loop + vertex 698.847 306.116 56.5058 + vertex 698.762 314.122 56.8179 + vertex 697.3 307.5 59.1284 + endloop + endfacet + facet normal 0.868484 -0.0188883 0.495358 + outer loop + vertex 697.3 307.5 59.1284 + vertex 698.762 314.122 56.8179 + vertex 697.47 315.884 59.1491 + endloop + endfacet + facet normal 0.85359 -0.0139681 0.520758 + outer loop + vertex 698.514 296.982 56.8057 + vertex 698.847 306.116 56.5058 + vertex 697.15 298.809 59.0916 + endloop + endfacet + facet normal 0.857253 -0.0169931 0.514614 + outer loop + vertex 697.15 298.809 59.0916 + vertex 698.847 306.116 56.5058 + vertex 697.3 307.5 59.1284 + endloop + endfacet + facet normal 0.887492 -0.017286 0.460499 + outer loop + vertex 697.15 298.809 59.0916 + vertex 697.3 307.5 59.1284 + vertex 695.693 300.565 61.9654 + endloop + endfacet + facet normal 0.897474 -0.027911 0.440183 + outer loop + vertex 695.693 300.565 61.9654 + vertex 697.3 307.5 59.1284 + vertex 695.598 308.675 62.6727 + endloop + endfacet + facet normal 0.898779 -0.0193637 0.437975 + outer loop + vertex 697.3 307.5 59.1284 + vertex 697.47 315.884 59.1491 + vertex 695.598 308.675 62.6727 + endloop + endfacet + facet normal 0.900455 -0.0215379 0.434417 + outer loop + vertex 695.598 308.675 62.6727 + vertex 697.47 315.884 59.1491 + vertex 696.103 317.616 62.0701 + endloop + endfacet + facet normal 0.832543 -0.0104073 -0.553862 + outer loop + vertex 698.937 317.97 287.49 + vertex 699.299 325.989 287.883 + vertex 700.646 316.432 290.087 + endloop + endfacet + facet normal 0.844895 -0.0123346 -0.534789 + outer loop + vertex 699.271 334.921 287.633 + vertex 700.867 332.968 290.2 + vertex 699.299 325.989 287.883 + endloop + endfacet + facet normal 0.838445 -0.00751685 -0.544935 + outer loop + vertex 700.867 332.968 290.2 + vertex 700.646 316.432 290.087 + vertex 699.299 325.989 287.883 + endloop + endfacet + facet normal 0.91491 -0.0278337 -0.402696 + outer loop + vertex 696.386 313.362 283.232 + vertex 695.06 316.768 279.983 + vertex 696.236 321.678 282.315 + endloop + endfacet + facet normal 0.940342 -0.0302197 -0.338887 + outer loop + vertex 696.52 329.62 282.396 + vertex 696.236 321.678 282.315 + vertex 694.723 332.752 277.13 + endloop + endfacet + facet normal 0.943342 -0.0389366 -0.32953 + outer loop + vertex 693.449 319.462 275.055 + vertex 694.723 332.752 277.13 + vertex 695.06 316.768 279.983 + endloop + endfacet + facet normal 0.927877 -0.0464804 -0.369979 + outer loop + vertex 696.236 321.678 282.315 + vertex 695.06 316.768 279.983 + vertex 694.723 332.752 277.13 + endloop + endfacet + facet normal 0.873959 -0.0135738 0.48581 + outer loop + vertex 699.136 322.933 56.4742 + vertex 699.127 330.923 56.7136 + vertex 697.682 324.16 59.1256 + endloop + endfacet + facet normal 0.881447 -0.0201521 0.471852 + outer loop + vertex 697.682 324.16 59.1256 + vertex 699.127 330.923 56.7136 + vertex 697.929 332.826 59.0345 + endloop + endfacet + facet normal 0.868907 -0.0176569 0.494661 + outer loop + vertex 698.762 314.122 56.8179 + vertex 699.136 322.933 56.4742 + vertex 697.47 315.884 59.1491 + endloop + endfacet + facet normal 0.872404 -0.0208828 0.488339 + outer loop + vertex 697.47 315.884 59.1491 + vertex 699.136 322.933 56.4742 + vertex 697.682 324.16 59.1256 + endloop + endfacet + facet normal 0.900401 -0.0217502 0.434517 + outer loop + vertex 697.47 315.884 59.1491 + vertex 697.682 324.16 59.1256 + vertex 696.103 317.616 62.0701 + endloop + endfacet + facet normal 0.907244 -0.0301479 0.419524 + outer loop + vertex 696.103 317.616 62.0701 + vertex 697.682 324.16 59.1256 + vertex 696.084 325.504 62.6778 + endloop + endfacet + facet normal 0.908695 -0.0215056 0.416906 + outer loop + vertex 697.682 324.16 59.1256 + vertex 697.929 332.826 59.0345 + vertex 696.084 325.504 62.6778 + endloop + endfacet + facet normal 0.909579 -0.0227217 0.41491 + outer loop + vertex 696.084 325.504 62.6778 + vertex 697.929 332.826 59.0345 + vertex 696.634 334.747 61.9771 + endloop + endfacet + facet normal 0.844545 -0.0133187 -0.53532 + outer loop + vertex 699.271 334.921 287.633 + vertex 699.808 344.159 288.251 + vertex 700.867 332.968 290.2 + endloop + endfacet + facet normal 0.858408 -0.0195532 -0.512594 + outer loop + vertex 700.023 353.394 288.259 + vertex 701.261 351.358 290.41 + vertex 699.808 344.159 288.251 + endloop + endfacet + facet normal 0.847777 -0.0121236 -0.530214 + outer loop + vertex 701.261 351.358 290.41 + vertex 700.867 332.968 290.2 + vertex 699.808 344.159 288.251 + endloop + endfacet + facet normal 0.949661 -0.0370187 -0.311084 + outer loop + vertex 697.003 353.58 281.379 + vertex 696.478 339.844 281.411 + vertex 695.193 351.916 276.051 + endloop + endfacet + facet normal 0.940678 -0.0286831 -0.338087 + outer loop + vertex 696.52 329.62 282.396 + vertex 694.723 332.752 277.13 + vertex 696.478 339.844 281.411 + endloop + endfacet + facet normal 0.946597 -0.0412029 -0.319774 + outer loop + vertex 694.723 332.752 277.13 + vertex 695.193 351.916 276.051 + vertex 696.478 339.844 281.411 + endloop + endfacet + facet normal 0.885502 -0.0174214 0.46431 + outer loop + vertex 699.591 340.968 56.2409 + vertex 699.809 353.934 56.3104 + vertex 698.184 342.754 58.9907 + endloop + endfacet + facet normal 0.899121 -0.0259654 0.436929 + outer loop + vertex 698.184 342.754 58.9907 + vertex 699.809 353.934 56.3104 + vertex 698.243 353.505 59.5072 + endloop + endfacet + facet normal 0.882039 -0.0185108 0.470812 + outer loop + vertex 699.127 330.923 56.7136 + vertex 699.591 340.968 56.2409 + vertex 697.929 332.826 59.0345 + endloop + endfacet + facet normal 0.884566 -0.020693 0.465955 + outer loop + vertex 697.929 332.826 59.0345 + vertex 699.591 340.968 56.2409 + vertex 698.184 342.754 58.9907 + endloop + endfacet + facet normal 0.909887 -0.0215721 0.414295 + outer loop + vertex 697.929 332.826 59.0345 + vertex 698.184 342.754 58.9907 + vertex 696.634 334.747 61.9771 + endloop + endfacet + facet normal 0.91741 -0.0295364 0.396846 + outer loop + vertex 696.634 334.747 61.9771 + vertex 698.184 342.754 58.9907 + vertex 696.615 343.489 62.6732 + endloop + endfacet + facet normal 0.917939 -0.0241029 0.395988 + outer loop + vertex 698.184 342.754 58.9907 + vertex 698.243 353.505 59.5072 + vertex 696.615 343.489 62.6732 + endloop + endfacet + facet normal 0.923168 -0.0289622 0.383303 + outer loop + vertex 696.615 343.489 62.6732 + vertex 698.243 353.505 59.5072 + vertex 697.005 352.48 62.4122 + endloop + endfacet + facet normal 0.84695 -0.0446788 -0.529791 + outer loop + vertex 700.023 353.394 288.259 + vertex 700.024 366.703 287.137 + vertex 701.261 351.358 290.41 + endloop + endfacet + facet normal 0.904865 -0.0177303 -0.42533 + outer loop + vertex 701.261 351.358 290.41 + vertex 700.024 366.703 287.137 + vertex 701.712 368.854 290.638 + endloop + endfacet + facet normal 0.95044 -0.0530177 -0.306353 + outer loop + vertex 695.193 351.916 276.051 + vertex 696.17 368.893 276.147 + vertex 697.003 353.58 281.379 + endloop + endfacet + facet normal 0.952492 -0.0508346 -0.30029 + outer loop + vertex 697.003 353.58 281.379 + vertex 696.17 368.893 276.147 + vertex 698.001 368.853 281.959 + endloop + endfacet + facet normal 0.924863 -0.0482015 0.377234 + outer loop + vertex 697.005 352.48 62.4122 + vertex 698.243 353.505 59.5072 + vertex 698.069 365.616 61.4815 + endloop + endfacet + facet normal 0.899272 -0.0316086 0.436246 + outer loop + vertex 699.809 353.934 56.3104 + vertex 699.763 365.708 57.259 + vertex 698.243 353.505 59.5072 + endloop + endfacet + facet normal 0.927448 -0.0471431 0.37097 + outer loop + vertex 699.763 365.708 57.259 + vertex 698.069 365.616 61.4815 + vertex 698.243 353.505 59.5072 + endloop + endfacet + facet normal 0.951536 -0.0672217 -0.300102 + outer loop + vertex 696.17 368.893 276.147 + vertex 697.594 386.626 276.689 + vertex 698.001 368.853 281.959 + endloop + endfacet + facet normal 0.959034 -0.0601496 -0.27683 + outer loop + vertex 698.001 368.853 281.959 + vertex 697.594 386.626 276.689 + vertex 699.392 386.649 282.913 + endloop + endfacet + facet normal 0.926707 -0.0639551 0.370303 + outer loop + vertex 699.763 365.708 57.259 + vertex 701.478 386.658 56.5844 + vertex 698.069 365.616 61.4815 + endloop + endfacet + facet normal 0.928939 -0.065701 0.364355 + outer loop + vertex 698.069 365.616 61.4815 + vertex 701.478 386.658 56.5844 + vertex 699.309 386.648 62.1142 + endloop + endfacet + facet normal 0.645875 -0.434364 -0.627833 + outer loop + vertex 695.565 147.948 295.96 + vertex 693.645 143.512 297.054 + vertex 695.286 147.486 295.993 + endloop + endfacet + facet normal 0.896524 -0.392117 -0.20613 + outer loop + vertex 697.162 152.031 295.137 + vertex 695.565 147.948 295.96 + vertex 696.818 151.206 295.214 + endloop + endfacet + facet normal 0.915817 -0.240658 0.321502 + outer loop + vertex 698.862 157.326 294.256 + vertex 697.162 152.031 295.137 + vertex 698.289 155.434 294.472 + endloop + endfacet + facet normal 0.941883 -0.209109 0.262924 + outer loop + vertex 700.023 161.795 293.653 + vertex 698.862 157.326 294.256 + vertex 699.504 159.725 293.865 + endloop + endfacet + facet normal 0.71478 -0.0693545 0.695902 + outer loop + vertex 700.71 165.451 293.312 + vertex 700.023 161.795 293.653 + vertex 700.557 164.412 293.365 + endloop + endfacet + facet normal 0.453298 -0.134764 -0.881113 + outer loop + vertex 701.491 171.048 292.857 + vertex 700.71 165.451 293.312 + vertex 700.867 167.237 293.119 + endloop + endfacet + facet normal 0.290353 -0.0913529 -0.952549 + outer loop + vertex 702.085 176.437 292.521 + vertex 701.491 171.048 292.857 + vertex 701.601 176.092 292.407 + endloop + endfacet + facet normal 0.26746 -0.0561269 -0.961933 + outer loop + vertex 702.354 181.278 292.314 + vertex 702.085 176.437 292.521 + vertex 701.601 176.092 292.407 + endloop + endfacet + facet normal 0.535439 -0.0468141 -0.843275 + outer loop + vertex 702.646 187.288 292.165 + vertex 702.354 181.278 292.314 + vertex 702.282 186.028 292.004 + endloop + endfacet + facet normal 0.674601 -0.0314908 -0.73751 + outer loop + vertex 702.743 193.164 292.003 + vertex 702.646 187.288 292.165 + vertex 702.586 191.941 291.912 + endloop + endfacet + facet normal 0.605745 -0.0183474 -0.795447 + outer loop + vertex 702.403 197.882 291.635 + vertex 702.743 193.164 292.003 + vertex 702.586 191.941 291.912 + endloop + endfacet + facet normal 0.709025 0.00105197 -0.705182 + outer loop + vertex 702.346 203.86 291.587 + vertex 702.403 197.882 291.635 + vertex 700.98 208.153 290.221 + endloop + endfacet + facet normal 0.715079 0.00493704 -0.699026 + outer loop + vertex 702.146 209.56 291.423 + vertex 702.346 203.86 291.587 + vertex 700.98 208.153 290.221 + endloop + endfacet + facet normal 0.711212 0.0114382 -0.702884 + outer loop + vertex 701.906 216.962 291.301 + vertex 702.146 209.56 291.423 + vertex 700.98 208.153 290.221 + endloop + endfacet + facet normal 0.741944 0.013722 -0.670321 + outer loop + vertex 701.743 225.147 291.288 + vertex 701.906 216.962 291.301 + vertex 700.432 227.357 289.882 + endloop + endfacet + facet normal 0.74165 0.0133352 -0.670655 + outer loop + vertex 701.588 233.046 291.274 + vertex 701.743 225.147 291.288 + vertex 700.432 227.357 289.882 + endloop + endfacet + facet normal 0.764781 0.0134715 -0.64415 + outer loop + vertex 701.579 241.961 291.449 + vertex 701.588 233.046 291.274 + vertex 700.325 245.887 290.042 + endloop + endfacet + facet normal 0.765008 0.013642 -0.643877 + outer loop + vertex 701.352 247.846 291.304 + vertex 701.579 241.961 291.449 + vertex 700.325 245.887 290.042 + endloop + endfacet + facet normal 0.77148 0.00532499 -0.636231 + outer loop + vertex 701.251 255.431 291.245 + vertex 701.352 247.846 291.304 + vertex 700.325 245.887 290.042 + endloop + endfacet + facet normal 0.780401 0.00289225 -0.625272 + outer loop + vertex 701.324 265.8 291.385 + vertex 701.251 255.431 291.245 + vertex 700.114 264.926 289.87 + endloop + endfacet + facet normal 0.781192 9.63285e-05 -0.624291 + outer loop + vertex 701.101 274.048 291.106 + vertex 701.324 265.8 291.385 + vertex 700.114 264.926 289.87 + endloop + endfacet + facet normal 0.793317 -0.00391802 -0.608796 + outer loop + vertex 701.376 282.147 291.413 + vertex 701.101 274.048 291.106 + vertex 700.201 282.662 289.879 + endloop + endfacet + facet normal 0.793333 -0.00381929 -0.608776 + outer loop + vertex 701.238 290.426 291.181 + vertex 701.376 282.147 291.413 + vertex 700.201 282.662 289.879 + endloop + endfacet + facet normal 0.806454 -0.00562781 -0.59127 + outer loop + vertex 701.524 297.246 291.506 + vertex 701.238 290.426 291.181 + vertex 700.489 300.028 290.067 + endloop + endfacet + facet normal 0.808262 -0.00368308 -0.588812 + outer loop + vertex 701.466 302.283 291.394 + vertex 701.524 297.246 291.506 + vertex 700.489 300.028 290.067 + endloop + endfacet + facet normal 0.809584 -0.00533371 -0.58698 + outer loop + vertex 701.364 307.164 291.209 + vertex 701.466 302.283 291.394 + vertex 700.489 300.028 290.067 + endloop + endfacet + facet normal 0.819244 -0.00594706 -0.573414 + outer loop + vertex 701.601 312.357 291.495 + vertex 701.364 307.164 291.209 + vertex 700.646 316.432 290.087 + endloop + endfacet + facet normal 0.821848 -0.0040507 -0.569693 + outer loop + vertex 701.551 317.435 291.386 + vertex 701.601 312.357 291.495 + vertex 700.646 316.432 290.087 + endloop + endfacet + facet normal 0.82252 -0.00593671 -0.568705 + outer loop + vertex 701.547 323.811 291.314 + vertex 701.551 317.435 291.386 + vertex 700.646 316.432 290.087 + endloop + endfacet + facet normal 0.830941 -0.00598028 -0.556328 + outer loop + vertex 701.616 329.809 291.352 + vertex 701.547 323.811 291.314 + vertex 700.867 332.968 290.2 + endloop + endfacet + facet normal 0.830154 -0.00659232 -0.557495 + outer loop + vertex 701.647 332.857 291.362 + vertex 701.616 329.809 291.352 + vertex 700.867 332.968 290.2 + endloop + endfacet + facet normal 0.830037 -0.00891544 -0.557638 + outer loop + vertex 701.707 339.177 291.352 + vertex 701.647 332.857 291.362 + vertex 700.867 332.968 290.2 + endloop + endfacet + facet normal 0.850854 -0.00945182 -0.525318 + outer loop + vertex 701.829 345.872 291.427 + vertex 701.707 339.177 291.352 + vertex 701.261 351.358 290.41 + endloop + endfacet + facet normal 0.850172 -0.00972588 -0.526415 + outer loop + vertex 701.955 350.149 291.553 + vertex 701.829 345.872 291.427 + vertex 701.261 351.358 290.41 + endloop + endfacet + facet normal 0.851541 -0.00688437 -0.524242 + outer loop + vertex 701.951 354.374 291.491 + vertex 701.955 350.149 291.553 + vertex 701.261 351.358 290.41 + endloop + endfacet + facet normal 0.85493 -0.00966241 -0.518654 + outer loop + vertex 701.974 359.37 291.436 + vertex 701.951 354.374 291.491 + vertex 701.261 351.358 290.41 + endloop + endfacet + facet normal 0.891159 -0.0134468 -0.453491 + outer loop + vertex 702.232 365.181 291.77 + vertex 701.974 359.37 291.436 + vertex 701.712 368.854 290.638 + endloop + endfacet + facet normal 0.901516 -0.00557884 -0.432711 + outer loop + vertex 702.251 369.534 291.754 + vertex 702.232 365.181 291.77 + vertex 701.712 368.854 290.638 + endloop + endfacet + facet normal 0.901769 -0.00667004 -0.432167 + outer loop + vertex 702.213 372.174 291.634 + vertex 702.251 369.534 291.754 + vertex 701.712 368.854 290.638 + endloop + endfacet + facet normal 0.93643 -0.0368761 -0.348911 + outer loop + vertex 702.301 378.618 291.189 + vertex 702.213 372.174 291.634 + vertex 701.712 368.854 290.638 + endloop + endfacet + facet normal 0.878599 -0.0847119 -0.469987 + outer loop + vertex 703.566 386.655 292.105 + vertex 702.301 378.618 291.189 + vertex 701.505 386.658 288.252 + endloop + endfacet + facet normal 0.547728 -0.523244 0.652847 + outer loop + vertex 691.448 142.718 46.8104 + vertex 693.15 143.184 45.7555 + vertex 693.216 143.616 46.0472 + endloop + endfacet + facet normal -0.479904 0.686723 -0.545989 + outer loop + vertex 688.971 142.978 49.3145 + vertex 691.448 142.718 46.8104 + vertex 690.725 142.663 47.376 + endloop + endfacet + facet normal 0.666063 -0.442767 0.600265 + outer loop + vertex 686.204 143.836 53.0177 + vertex 688.971 142.978 49.3145 + vertex 688.142 143.974 50.9683 + endloop + endfacet + facet normal 0.702532 -0.450038 0.551285 + outer loop + vertex 683.417 144.915 57.4502 + vertex 686.204 143.836 53.0177 + vertex 685.604 144.86 54.6185 + endloop + endfacet + facet normal 0.708462 -0.501627 0.496439 + outer loop + vertex 681.001 146.019 62.0132 + vertex 683.417 144.915 57.4502 + vertex 682.133 146.289 60.6719 + endloop + endfacet + facet normal 0.729156 -0.532056 0.430405 + outer loop + vertex 679.331 147.185 66.2846 + vertex 681.001 146.019 62.0132 + vertex 680.506 147.248 64.371 + endloop + endfacet + facet normal 0.7676 -0.518607 0.376613 + outer loop + vertex 677.889 148.596 71.1656 + vertex 679.331 147.185 66.2846 + vertex 679.149 148.323 68.2221 + endloop + endfacet + facet normal 0.825466 -0.474668 0.305443 + outer loop + vertex 675.545 151.347 81.1226 + vertex 676.468 150.063 76.6316 + vertex 676.313 151.385 79.1047 + endloop + endfacet + facet normal 0.838974 -0.474932 0.265635 + outer loop + vertex 674.778 152.63 85.8377 + vertex 675.545 151.347 81.1226 + vertex 675.566 152.499 83.1148 + endloop + endfacet + facet normal 0.832344 -0.496693 0.245965 + outer loop + vertex 673.967 154.111 91.5737 + vertex 674.778 152.63 85.8377 + vertex 674.522 154.219 89.913 + endloop + endfacet + facet normal 0.817241 -0.52917 0.228246 + outer loop + vertex 673.52 155.277 95.8777 + vertex 673.967 154.111 91.5737 + vertex 674.031 155.26 94.0058 + endloop + endfacet + facet normal 0.826279 -0.517835 -0.221608 + outer loop + vertex 673.926 154.461 250.932 + vertex 673.481 155.525 246.787 + vertex 673.967 155.475 248.714 + endloop + endfacet + facet normal 0.832987 -0.497469 -0.242191 + outer loop + vertex 674.581 153.305 255.557 + vertex 673.926 154.461 250.932 + vertex 674.464 154.496 252.709 + endloop + endfacet + facet normal 0.852852 -0.451975 -0.261461 + outer loop + vertex 675.517 151.76 261.284 + vertex 674.581 153.305 255.557 + vertex 675.565 152.799 259.641 + endloop + endfacet + facet normal 0.854227 -0.426402 -0.297451 + outer loop + vertex 676.672 150.159 266.895 + vertex 675.517 151.76 261.284 + vertex 676.363 151.607 263.931 + endloop + endfacet + facet normal 0.809034 -0.44649 -0.382244 + outer loop + vertex 679.443 147.393 276.585 + vertex 677.912 148.868 271.622 + vertex 679.093 148.583 274.454 + endloop + endfacet + facet normal 0.762832 -0.483648 -0.429153 + outer loop + vertex 681.056 146.273 280.715 + vertex 679.443 147.393 276.585 + vertex 680.526 147.52 278.366 + endloop + endfacet + facet normal 0.719643 -0.494633 -0.487291 + outer loop + vertex 683.037 145.207 284.722 + vertex 681.056 146.273 280.715 + vertex 682.2 146.476 282.197 + endloop + endfacet + facet normal 0.693432 -0.468416 -0.547484 + outer loop + vertex 685.796 144.193 289.084 + vertex 683.037 145.207 284.722 + vertex 684.176 145.557 285.865 + endloop + endfacet + facet normal 0.657528 -0.46712 -0.591147 + outer loop + vertex 688.37 143.302 292.65 + vertex 685.796 144.193 289.084 + vertex 688.166 144.145 291.758 + endloop + endfacet + facet normal -0.276846 0.878381 0.389619 + outer loop + vertex 690.686 142.952 295.086 + vertex 688.37 143.302 292.65 + vertex 689.545 143.08 293.986 + endloop + endfacet + facet normal 0.565462 -0.00614903 0.824752 + outer loop + vertex 702.631 198.289 52.3535 + vertex 702.597 205.379 52.4295 + vertex 702.292 207.242 52.6526 + endloop + endfacet + facet normal -0.35468 -0.0349526 0.934334 + outer loop + vertex 702.249 179.684 51.6803 + vertex 702.51 185.737 52.006 + vertex 702.233 181.868 51.7558 + endloop + endfacet + facet normal -0.224093 -0.0524969 0.973153 + outer loop + vertex 702.02 175.886 51.4226 + vertex 702.249 179.684 51.6803 + vertex 701.724 174.559 51.2829 + endloop + endfacet + facet normal -0.121249 -0.0771671 0.989618 + outer loop + vertex 701.573 171.644 51.0371 + vertex 702.02 175.886 51.4226 + vertex 701.724 174.559 51.2829 + endloop + endfacet + facet normal 0.381089 -0.146313 0.912888 + outer loop + vertex 700.84 166.038 50.4445 + vertex 701.573 171.644 51.0371 + vertex 700.886 167.314 50.63 + endloop + endfacet + facet normal 0.969619 -0.149973 -0.193252 + outer loop + vertex 700.051 161.648 49.893 + vertex 700.84 166.038 50.4445 + vertex 700.482 163.961 50.2587 + endloop + endfacet + facet normal 0.968507 -0.24871 -0.011741 + outer loop + vertex 698.903 157.214 49.0828 + vertex 700.051 161.648 49.893 + vertex 699.121 158.05 49.3489 + endloop + endfacet + facet normal 0.932396 -0.331728 0.143511 + outer loop + vertex 697.154 151.78 47.8849 + vertex 698.903 157.214 49.0828 + vertex 697.796 153.834 48.4612 + endloop + endfacet + facet normal 0.853816 -0.42229 0.304415 + outer loop + vertex 695.4 147.438 46.7823 + vertex 697.154 151.78 47.8849 + vertex 696.206 149.509 47.3945 + endloop + endfacet + facet normal -0.0578342 0.263001 -0.96306 + outer loop + vertex 693.15 143.184 45.7555 + vertex 695.4 147.438 46.7823 + vertex 694.675 145.917 46.4103 + endloop + endfacet + facet normal 0.603879 -0.506159 -0.615738 + outer loop + vertex 688.166 144.145 291.758 + vertex 689.545 143.08 293.986 + vertex 688.37 143.302 292.65 + endloop + endfacet + facet normal 0.692175 -0.470151 -0.547587 + outer loop + vertex 684.176 145.557 285.865 + vertex 686.082 144.977 288.772 + vertex 685.796 144.193 289.084 + endloop + endfacet + facet normal 0.655086 -0.473111 -0.589091 + outer loop + vertex 686.082 144.977 288.772 + vertex 688.166 144.145 291.758 + vertex 685.796 144.193 289.084 + endloop + endfacet + facet normal 0.689824 -0.563209 -0.454905 + outer loop + vertex 680.526 147.52 278.366 + vertex 682.2 146.476 282.197 + vertex 681.056 146.273 280.715 + endloop + endfacet + facet normal 0.669675 -0.550295 -0.49871 + outer loop + vertex 682.2 146.476 282.197 + vertex 684.176 145.557 285.865 + vertex 683.037 145.207 284.722 + endloop + endfacet + facet normal 0.792398 -0.478358 -0.378522 + outer loop + vertex 678.118 149.625 271.097 + vertex 679.093 148.583 274.454 + vertex 677.912 148.868 271.622 + endloop + endfacet + facet normal 0.7439 -0.523996 -0.414778 + outer loop + vertex 679.093 148.583 274.454 + vertex 680.526 147.52 278.366 + vertex 679.443 147.393 276.585 + endloop + endfacet + facet normal 0.820789 -0.474796 -0.317607 + outer loop + vertex 676.363 151.607 263.931 + vertex 677.239 150.409 267.985 + vertex 676.672 150.159 266.895 + endloop + endfacet + facet normal 0.818647 -0.495656 -0.290074 + outer loop + vertex 675.565 152.799 259.641 + vertex 676.363 151.607 263.931 + vertex 675.517 151.76 261.284 + endloop + endfacet + facet normal 0.806755 -0.542841 -0.233387 + outer loop + vertex 673.967 155.475 248.714 + vertex 674.464 154.496 252.709 + vertex 673.926 154.461 250.932 + endloop + endfacet + facet normal 0.806985 -0.541989 0.234569 + outer loop + vertex 674.522 154.219 89.913 + vertex 674.031 155.26 94.0058 + vertex 673.967 154.111 91.5737 + endloop + endfacet + facet normal 0.799128 -0.524094 0.294482 + outer loop + vertex 676.313 151.385 79.1047 + vertex 675.566 152.499 83.1148 + vertex 675.545 151.347 81.1226 + endloop + endfacet + facet normal 0.798055 -0.509216 0.322191 + outer loop + vertex 677.219 150.205 74.9959 + vertex 676.313 151.385 79.1047 + vertex 676.468 150.063 76.6316 + endloop + endfacet + facet normal 0.698713 -0.586318 0.409915 + outer loop + vertex 680.506 147.248 64.371 + vertex 679.149 148.323 68.2221 + vertex 679.331 147.185 66.2846 + endloop + endfacet + facet normal 0.772274 -0.510685 0.37788 + outer loop + vertex 679.149 148.323 68.2221 + vertex 678.188 149.355 71.5805 + vertex 677.889 148.596 71.1656 + endloop + endfacet + facet normal 0.713612 -0.495035 0.495679 + outer loop + vertex 683.771 145.628 57.6531 + vertex 682.133 146.289 60.6719 + vertex 683.417 144.915 57.4502 + endloop + endfacet + facet normal 0.672231 -0.589219 0.448249 + outer loop + vertex 682.133 146.289 60.6719 + vertex 680.506 147.248 64.371 + vertex 681.001 146.019 62.0132 + endloop + endfacet + facet normal 0.639198 -0.516344 0.569926 + outer loop + vertex 688.142 143.974 50.9683 + vertex 685.604 144.86 54.6185 + vertex 686.204 143.836 53.0177 + endloop + endfacet + facet normal 0.684188 -0.492453 0.537937 + outer loop + vertex 685.604 144.86 54.6185 + vertex 683.771 145.628 57.6531 + vertex 683.417 144.915 57.4502 + endloop + endfacet + facet normal -0.496252 0.654826 -0.570032 + outer loop + vertex 691.705 142.658 46.5182 + vertex 690.725 142.663 47.376 + vertex 691.448 142.718 46.8104 + endloop + endfacet + facet normal 0.680443 -0.306588 0.665583 + outer loop + vertex 690.725 142.663 47.376 + vertex 689.599 143.014 48.6894 + vertex 688.971 142.978 49.3145 + endloop + endfacet + facet normal 0.631926 -0.482104 0.606832 + outer loop + vertex 689.599 143.014 48.6894 + vertex 688.142 143.974 50.9683 + vertex 688.971 142.978 49.3145 + endloop + endfacet + facet normal 0.43832 -0.103866 0.892798 + outer loop + vertex 693.216 143.616 46.0472 + vertex 692.768 143.439 46.2465 + vertex 691.448 142.718 46.8104 + endloop + endfacet + facet normal -0.564476 0.556499 -0.609651 + outer loop + vertex 692.768 143.439 46.2465 + vertex 691.705 142.658 46.5182 + vertex 691.448 142.718 46.8104 + endloop + endfacet + facet normal 0.635323 -0.494171 0.593431 + outer loop + vertex 694.216 144.888 46.1404 + vertex 693.639 143.823 45.8714 + vertex 693.881 144.2 45.9263 + endloop + endfacet + facet normal 0.533068 -0.527089 0.661828 + outer loop + vertex 693.639 143.823 45.8714 + vertex 693.216 143.616 46.0472 + vertex 693.15 143.184 45.7555 + endloop + endfacet + facet normal 0.541985 -0.380239 -0.749446 + outer loop + vertex 695.286 147.486 295.993 + vertex 696.818 151.206 295.214 + vertex 695.565 147.948 295.96 + endloop + endfacet + facet normal 0.625258 -0.431793 -0.650082 + outer loop + vertex 694.191 145.258 296.42 + vertex 695.286 147.486 295.993 + vertex 693.645 143.512 297.054 + endloop + endfacet + facet normal 0.77366 -0.298171 -0.559056 + outer loop + vertex 698.289 155.434 294.472 + vertex 699.504 159.725 293.865 + vertex 698.862 157.326 294.256 + endloop + endfacet + facet normal 0.72092 -0.355107 -0.595125 + outer loop + vertex 696.818 151.206 295.214 + vertex 698.289 155.434 294.472 + vertex 697.162 152.031 295.137 + endloop + endfacet + facet normal 0.486269 -0.373657 0.789888 + outer loop + vertex 697.796 153.834 48.4612 + vertex 696.206 149.509 47.3945 + vertex 697.154 151.78 47.8849 + endloop + endfacet + facet normal 0.838702 -0.351188 0.416229 + outer loop + vertex 699.121 158.05 49.3489 + vertex 697.796 153.834 48.4612 + vertex 698.903 157.214 49.0828 + endloop + endfacet + facet normal -0.371702 0.407238 -0.834263 + outer loop + vertex 694.675 145.917 46.4103 + vertex 693.881 144.2 45.9263 + vertex 693.15 143.184 45.7555 + endloop + endfacet + facet normal 0.461084 -0.411807 0.786013 + outer loop + vertex 696.206 149.509 47.3945 + vertex 694.675 145.917 46.4103 + vertex 695.4 147.438 46.7823 + endloop + endfacet + facet normal 0.142904 -0.0910912 -0.985536 + outer loop + vertex 700.867 167.237 293.119 + vertex 701.601 176.092 292.407 + vertex 701.491 171.048 292.857 + endloop + endfacet + facet normal -0.0899836 -0.0790541 0.992801 + outer loop + vertex 701.724 174.559 51.2829 + vertex 700.886 167.314 50.63 + vertex 701.573 171.644 51.0371 + endloop + endfacet + facet normal 0.516829 -0.0399224 -0.855157 + outer loop + vertex 702.282 186.028 292.004 + vertex 702.586 191.941 291.912 + vertex 702.646 187.288 292.165 + endloop + endfacet + facet normal 0.618026 -0.0175276 -0.785962 + outer loop + vertex 702.586 191.941 291.912 + vertex 701.905 193.97 291.331 + vertex 702.403 197.882 291.635 + endloop + endfacet + facet normal 0.281608 -0.0581076 -0.957768 + outer loop + vertex 701.601 176.092 292.407 + vertex 702.282 186.028 292.004 + vertex 702.354 181.278 292.314 + endloop + endfacet + facet normal -0.36379 -0.0348996 0.930827 + outer loop + vertex 702.233 181.868 51.7558 + vertex 701.724 174.559 51.2829 + vertex 702.249 179.684 51.6803 + endloop + endfacet + facet normal -0.520073 -0.017882 0.853934 + outer loop + vertex 702.558 189.909 52.1226 + vertex 702.233 181.868 51.7558 + vertex 702.51 185.737 52.006 + endloop + endfacet + facet normal 0.629771 -0.019755 -0.776529 + outer loop + vertex 701.905 193.97 291.331 + vertex 700.98 208.153 290.221 + vertex 702.403 197.882 291.635 + endloop + endfacet + facet normal 0.15372 -0.0271742 0.987741 + outer loop + vertex 702.292 207.242 52.6526 + vertex 702.458 193.507 52.2488 + vertex 702.631 198.289 52.3535 + endloop + endfacet + facet normal 0.723918 0.00850172 -0.689834 + outer loop + vertex 700.98 208.153 290.221 + vertex 700.432 227.357 289.882 + vertex 701.906 216.962 291.301 + endloop + endfacet + facet normal 0.748541 0.0100654 -0.663012 + outer loop + vertex 700.432 227.357 289.882 + vertex 700.325 245.887 290.042 + vertex 701.588 233.046 291.274 + endloop + endfacet + facet normal 0.780738 0.00299356 -0.624851 + outer loop + vertex 700.325 245.887 290.042 + vertex 700.114 264.926 289.87 + vertex 701.251 255.431 291.245 + endloop + endfacet + facet normal 0.794366 -0.00361348 -0.607429 + outer loop + vertex 700.114 264.926 289.87 + vertex 700.201 282.662 289.879 + vertex 701.101 274.048 291.106 + endloop + endfacet + facet normal 0.80161 -0.00676433 -0.597809 + outer loop + vertex 700.201 282.662 289.879 + vertex 700.489 300.028 290.067 + vertex 701.238 290.426 291.181 + endloop + endfacet + facet normal 0.814655 -0.00708833 -0.579902 + outer loop + vertex 700.489 300.028 290.067 + vertex 700.646 316.432 290.087 + vertex 701.364 307.164 291.209 + endloop + endfacet + facet normal 0.826046 -0.00722355 -0.563557 + outer loop + vertex 700.646 316.432 290.087 + vertex 700.867 332.968 290.2 + vertex 701.547 323.811 291.314 + endloop + endfacet + facet normal 0.836697 -0.0116886 -0.547542 + outer loop + vertex 700.867 332.968 290.2 + vertex 701.261 351.358 290.41 + vertex 701.707 339.177 291.352 + endloop + endfacet + facet normal 0.876084 -0.0162514 -0.481884 + outer loop + vertex 701.261 351.358 290.41 + vertex 701.712 368.854 290.638 + vertex 701.974 359.37 291.436 + endloop + endfacet + facet normal 0.910335 -0.0446041 -0.411461 + outer loop + vertex 701.712 368.854 290.638 + vertex 700.024 366.703 287.137 + vertex 701.505 386.658 288.252 + endloop + endfacet + facet normal 0.93479 -0.0365284 -0.353318 + outer loop + vertex 702.301 378.618 291.189 + vertex 701.712 368.854 290.638 + vertex 701.505 386.658 288.252 + endloop + endfacet + facet normal 0.281819 -0.0414518 -0.958572 + outer loop + vertex 693.881 144.2 45.9263 + vertex 693.639 143.823 45.8714 + vertex 693.15 143.184 45.7555 + endloop + endfacet + facet normal -0.640783 -0.448481 -0.623107 + outer loop + vertex -693.516 144.685 296.236 + vertex -694.724 147.089 295.748 + vertex -693.937 145.892 295.801 + endloop + endfacet + facet normal -0.603149 -0.129199 -0.787095 + outer loop + vertex -700.054 166.352 292.723 + vertex -700.596 167.911 292.883 + vertex -700.433 173.926 291.77 + endloop + endfacet + facet normal -0.486404 -0.11027 -0.866748 + outer loop + vertex -700.863 167.235 293.119 + vertex -701.607 176.092 292.41 + vertex -700.596 167.911 292.883 + endloop + endfacet + facet normal -0.639718 -0.122954 -0.758712 + outer loop + vertex -701.607 176.092 292.41 + vertex -700.433 173.926 291.77 + vertex -700.596 167.911 292.883 + endloop + endfacet + facet normal -0.5715 -0.0424653 -0.819503 + outer loop + vertex -702.587 191.946 291.912 + vertex -701.915 193.98 291.338 + vertex -702.272 186.025 291.999 + endloop + endfacet + facet normal -0.588209 -0.0407338 -0.807683 + outer loop + vertex -702.272 186.025 291.999 + vertex -701.915 193.98 291.338 + vertex -701.332 184.616 291.386 + endloop + endfacet + facet normal -0.620283 -0.0737878 -0.7809 + outer loop + vertex -702.272 186.025 291.999 + vertex -701.332 184.616 291.386 + vertex -701.607 176.092 292.41 + endloop + endfacet + facet normal -0.583995 -0.0782087 -0.807981 + outer loop + vertex -701.607 176.092 292.41 + vertex -701.332 184.616 291.386 + vertex -700.433 173.926 291.77 + endloop + endfacet + facet normal -0.637472 -0.447362 -0.627294 + outer loop + vertex -690.052 143.535 294.093 + vertex -689.926 145.188 292.786 + vertex -688.225 144.133 291.81 + endloop + endfacet + facet normal -0.557462 -0.470805 -0.683797 + outer loop + vertex -691.383 143.311 295.423 + vertex -692.476 143.536 296.159 + vertex -692.411 144.136 295.693 + endloop + endfacet + facet normal -0.749827 -0.11996 -0.650668 + outer loop + vertex -697.955 175.691 288.746 + vertex -697.502 171.419 289.012 + vertex -698.855 173.169 290.248 + endloop + endfacet + facet normal -0.711351 -0.135581 -0.689636 + outer loop + vertex -698.644 166.037 291.432 + vertex -698.855 173.169 290.248 + vertex -697.779 166.716 290.407 + endloop + endfacet + facet normal -0.686796 -0.138812 -0.713472 + outer loop + vertex -698.644 166.037 291.432 + vertex -699.478 167.035 292.041 + vertex -698.855 173.169 290.248 + endloop + endfacet + facet normal -0.693587 -0.123979 -0.709624 + outer loop + vertex -700.054 166.352 292.723 + vertex -700.433 173.926 291.77 + vertex -699.478 167.035 292.041 + endloop + endfacet + facet normal -0.719552 -0.126525 -0.682815 + outer loop + vertex -700.433 173.926 291.77 + vertex -698.855 173.169 290.248 + vertex -699.478 167.035 292.041 + endloop + endfacet + facet normal -0.761085 -0.0486552 -0.646825 + outer loop + vertex -700.498 194.325 289.969 + vertex -698.657 192.75 287.921 + vertex -699.833 183.401 290.009 + endloop + endfacet + facet normal -0.755103 -0.0509266 -0.653625 + outer loop + vertex -699.833 183.401 290.009 + vertex -698.657 192.75 287.921 + vertex -697.991 182.226 287.972 + endloop + endfacet + facet normal -0.688205 -0.0465338 -0.724022 + outer loop + vertex -701.915 193.98 291.338 + vertex -700.498 194.325 289.969 + vertex -701.332 184.616 291.386 + endloop + endfacet + facet normal -0.695402 -0.0449216 -0.717216 + outer loop + vertex -701.332 184.616 291.386 + vertex -700.498 194.325 289.969 + vertex -699.833 183.401 290.009 + endloop + endfacet + facet normal -0.710598 -0.0849241 -0.698454 + outer loop + vertex -701.332 184.616 291.386 + vertex -699.833 183.401 290.009 + vertex -700.433 173.926 291.77 + endloop + endfacet + facet normal -0.712572 -0.084436 -0.6965 + outer loop + vertex -700.433 173.926 291.77 + vertex -699.833 183.401 290.009 + vertex -698.855 173.169 290.248 + endloop + endfacet + facet normal -0.763468 -0.0879802 -0.639825 + outer loop + vertex -699.833 183.401 290.009 + vertex -697.991 182.226 287.972 + vertex -698.855 173.169 290.248 + endloop + endfacet + facet normal -0.794086 -0.0758216 -0.603058 + outer loop + vertex -698.855 173.169 290.248 + vertex -697.991 182.226 287.972 + vertex -697.955 175.691 288.746 + endloop + endfacet + facet normal -0.751461 -0.0210153 -0.659443 + outer loop + vertex -698.657 192.75 287.921 + vertex -700.498 194.325 289.969 + vertex -698.933 203.228 287.902 + endloop + endfacet + facet normal -0.752221 -0.00227238 -0.658907 + outer loop + vertex -698.61 212.331 287.502 + vertex -698.933 203.228 287.902 + vertex -700.981 208.156 290.223 + endloop + endfacet + facet normal -0.693421 -0.0109828 -0.720448 + outer loop + vertex -701.915 193.98 291.338 + vertex -700.981 208.156 290.223 + vertex -700.498 194.325 289.969 + endloop + endfacet + facet normal -0.76524 -0.0149085 -0.643573 + outer loop + vertex -698.933 203.228 287.902 + vertex -700.498 194.325 289.969 + vertex -700.981 208.156 290.223 + endloop + endfacet + facet normal -0.76333 0.0101633 -0.645929 + outer loop + vertex -698.35 230.147 287.467 + vertex -698.774 220.786 287.82 + vertex -700.432 227.36 289.883 + endloop + endfacet + facet normal -0.761216 0.00966859 -0.648426 + outer loop + vertex -698.61 212.331 287.502 + vertex -700.981 208.156 290.223 + vertex -698.774 220.786 287.82 + endloop + endfacet + facet normal -0.762986 0.0103764 -0.646332 + outer loop + vertex -700.981 208.156 290.223 + vertex -700.432 227.36 289.883 + vertex -698.774 220.786 287.82 + endloop + endfacet + facet normal -0.775268 0.00473905 -0.631615 + outer loop + vertex -698.296 247.828 287.568 + vertex -698.58 238.68 287.849 + vertex -700.325 245.887 290.045 + endloop + endfacet + facet normal -0.762374 0.00845055 -0.647081 + outer loop + vertex -698.35 230.147 287.467 + vertex -700.432 227.36 289.883 + vertex -698.58 238.68 287.849 + endloop + endfacet + facet normal -0.76657 0.0100351 -0.642082 + outer loop + vertex -700.432 227.36 289.883 + vertex -700.325 245.887 290.045 + vertex -698.58 238.68 287.849 + endloop + endfacet + facet normal -0.790003 -0.00252399 -0.613097 + outer loop + vertex -698.342 265.766 287.585 + vertex -698.566 256.567 287.912 + vertex -700.115 264.93 289.872 + endloop + endfacet + facet normal -0.77381 0.000915812 -0.633417 + outer loop + vertex -698.296 247.828 287.568 + vertex -700.325 245.887 290.045 + vertex -698.566 256.567 287.912 + endloop + endfacet + facet normal -0.778694 0.00292264 -0.627398 + outer loop + vertex -700.325 245.887 290.045 + vertex -700.115 264.93 289.872 + vertex -698.566 256.567 287.912 + endloop + endfacet + facet normal -0.80387 -0.00868318 -0.594741 + outer loop + vertex -698.494 283.62 287.557 + vertex -698.656 274.533 287.908 + vertex -700.2 282.663 289.877 + endloop + endfacet + facet normal -0.789446 -0.00561477 -0.613795 + outer loop + vertex -698.342 265.766 287.585 + vertex -700.115 264.93 289.872 + vertex -698.656 274.533 287.908 + endloop + endfacet + facet normal -0.794107 -0.00367365 -0.607767 + outer loop + vertex -700.115 264.93 289.872 + vertex -700.2 282.663 289.877 + vertex -698.656 274.533 287.908 + endloop + endfacet + facet normal -0.817254 -0.0112837 -0.576166 + outer loop + vertex -698.718 301.291 287.531 + vertex -698.841 292.345 287.88 + vertex -700.485 300.02 290.062 + endloop + endfacet + facet normal -0.803616 -0.00992282 -0.595066 + outer loop + vertex -698.494 283.62 287.557 + vertex -700.2 282.663 289.877 + vertex -698.841 292.345 287.88 + endloop + endfacet + facet normal -0.810401 -0.0070664 -0.585833 + outer loop + vertex -700.2 282.663 289.877 + vertex -700.485 300.02 290.062 + vertex -698.841 292.345 287.88 + endloop + endfacet + facet normal -0.831751 -0.0116142 -0.555027 + outer loop + vertex -698.937 317.962 287.495 + vertex -699.065 309.544 287.863 + vertex -700.646 316.43 290.088 + endloop + endfacet + facet normal -0.817283 -0.0111687 -0.576128 + outer loop + vertex -698.718 301.291 287.531 + vertex -700.485 300.02 290.062 + vertex -699.065 309.544 287.863 + endloop + endfacet + facet normal -0.825552 -0.00719968 -0.56428 + outer loop + vertex -700.485 300.02 290.062 + vertex -700.646 316.43 290.088 + vertex -699.065 309.544 287.863 + endloop + endfacet + facet normal -0.845039 -0.0125294 -0.534558 + outer loop + vertex -699.27 334.929 287.629 + vertex -699.297 325.988 287.882 + vertex -700.867 332.963 290.201 + endloop + endfacet + facet normal -0.832046 -0.0105711 -0.554605 + outer loop + vertex -698.937 317.962 287.495 + vertex -700.646 316.43 290.088 + vertex -699.297 325.988 287.882 + endloop + endfacet + facet normal -0.838315 -0.0075 -0.545134 + outer loop + vertex -700.646 316.43 290.088 + vertex -700.867 332.963 290.201 + vertex -699.297 325.988 287.882 + endloop + endfacet + facet normal -0.857641 -0.0192591 -0.513888 + outer loop + vertex -700.024 353.38 288.266 + vertex -699.808 344.158 288.251 + vertex -701.261 351.356 290.407 + endloop + endfacet + facet normal -0.84478 -0.0132534 -0.53495 + outer loop + vertex -699.27 334.929 287.629 + vertex -700.867 332.963 290.201 + vertex -699.808 344.158 288.251 + endloop + endfacet + facet normal -0.847555 -0.0122274 -0.530567 + outer loop + vertex -700.867 332.963 290.201 + vertex -701.261 351.356 290.407 + vertex -699.808 344.158 288.251 + endloop + endfacet + facet normal -0.903907 -0.0178801 -0.427356 + outer loop + vertex -701.717 368.858 290.637 + vertex -700.023 366.697 287.145 + vertex -701.261 351.356 290.407 + endloop + endfacet + facet normal -0.846082 -0.0446214 -0.531181 + outer loop + vertex -701.261 351.356 290.407 + vertex -700.023 366.697 287.145 + vertex -700.024 353.38 288.266 + endloop + endfacet + facet normal -0.708253 -0.43688 -0.55454 + outer loop + vertex -684.175 145.547 285.873 + vertex -686.109 145.004 288.773 + vertex -685.396 146.432 286.737 + endloop + endfacet + facet normal -0.67665 -0.433133 -0.595434 + outer loop + vertex -686.109 145.004 288.773 + vertex -688.225 144.133 291.81 + vertex -687.563 145.79 289.852 + endloop + endfacet + facet normal -0.757703 -0.465387 -0.457494 + outer loop + vertex -680.522 147.518 278.366 + vertex -682.193 146.48 282.19 + vertex -681.794 148.205 279.775 + endloop + endfacet + facet normal -0.732955 -0.451688 -0.50868 + outer loop + vertex -682.193 146.48 282.19 + vertex -684.175 145.547 285.873 + vertex -683.5 147.256 283.384 + endloop + endfacet + facet normal -0.899896 -0.0567724 -0.432393 + outer loop + vertex -692.995 193.516 279.469 + vertex -691.475 194.181 276.218 + vertex -692.327 183.782 279.358 + endloop + endfacet + facet normal -0.901843 -0.0554351 -0.428493 + outer loop + vertex -692.327 183.782 279.358 + vertex -691.475 194.181 276.218 + vertex -690.813 184.437 276.086 + endloop + endfacet + facet normal -0.862555 -0.0576142 -0.502672 + outer loop + vertex -694.729 192.712 282.538 + vertex -692.995 193.516 279.469 + vertex -694.039 183.085 282.457 + endloop + endfacet + facet normal -0.868855 -0.0539605 -0.492117 + outer loop + vertex -694.039 183.085 282.457 + vertex -692.995 193.516 279.469 + vertex -692.327 183.782 279.358 + endloop + endfacet + facet normal -0.904328 -0.00289404 -0.426828 + outer loop + vertex -693.326 211.224 279.546 + vertex -691.806 211.968 276.32 + vertex -693.3 202.611 279.548 + endloop + endfacet + facet normal -0.905055 -0.00224723 -0.425289 + outer loop + vertex -693.3 202.611 279.548 + vertex -691.806 211.968 276.32 + vertex -691.777 203.373 276.303 + endloop + endfacet + facet normal -0.865403 -0.00406478 -0.50106 + outer loop + vertex -695.064 210.655 282.552 + vertex -693.326 211.224 279.546 + vertex -695.04 201.843 282.583 + endloop + endfacet + facet normal -0.867107 -0.00279979 -0.498114 + outer loop + vertex -695.04 201.843 282.583 + vertex -693.326 211.224 279.546 + vertex -693.3 202.611 279.548 + endloop + endfacet + facet normal -0.864143 -0.0269569 -0.502523 + outer loop + vertex -695.04 201.843 282.583 + vertex -693.3 202.611 279.548 + vertex -694.729 192.712 282.538 + endloop + endfacet + facet normal -0.867486 -0.0247596 -0.496846 + outer loop + vertex -694.729 192.712 282.538 + vertex -693.3 202.611 279.548 + vertex -692.995 193.516 279.469 + endloop + endfacet + facet normal -0.902531 -0.0265155 -0.429807 + outer loop + vertex -693.3 202.611 279.548 + vertex -691.777 203.373 276.303 + vertex -692.995 193.516 279.469 + endloop + endfacet + facet normal -0.903532 -0.0257303 -0.427748 + outer loop + vertex -692.995 193.516 279.469 + vertex -691.777 203.373 276.303 + vertex -691.475 194.181 276.218 + endloop + endfacet + facet normal -0.905055 0.00706444 -0.425236 + outer loop + vertex -693.139 228.345 279.438 + vertex -691.611 229.059 276.199 + vertex -693.222 219.745 279.474 + endloop + endfacet + facet normal -0.904094 0.00617657 -0.427289 + outer loop + vertex -693.222 219.745 279.474 + vertex -691.611 229.059 276.199 + vertex -691.701 220.387 276.264 + endloop + endfacet + facet normal -0.868631 0.00779614 -0.495399 + outer loop + vertex -694.869 228.008 282.467 + vertex -693.139 228.345 279.438 + vertex -694.96 219.344 282.49 + endloop + endfacet + facet normal -0.866874 0.0063943 -0.498486 + outer loop + vertex -694.96 219.344 282.49 + vertex -693.139 228.345 279.438 + vertex -693.222 219.745 279.474 + endloop + endfacet + facet normal -0.866897 0.0068366 -0.49844 + outer loop + vertex -694.96 219.344 282.49 + vertex -693.222 219.745 279.474 + vertex -695.064 210.655 282.552 + endloop + endfacet + facet normal -0.866245 0.00631874 -0.499579 + outer loop + vertex -695.064 210.655 282.552 + vertex -693.222 219.745 279.474 + vertex -693.326 211.224 279.546 + endloop + endfacet + facet normal -0.904181 0.00739686 -0.427086 + outer loop + vertex -693.222 219.745 279.474 + vertex -691.701 220.387 276.264 + vertex -693.326 211.224 279.546 + endloop + endfacet + facet normal -0.905308 0.0084619 -0.42467 + outer loop + vertex -693.326 211.224 279.546 + vertex -691.701 220.387 276.264 + vertex -691.806 211.968 276.32 + endloop + endfacet + facet normal -0.900736 -0.00592342 -0.434327 + outer loop + vertex -693.152 245.171 279.411 + vertex -691.946 244.416 276.92 + vertex -693.141 236.729 279.503 + endloop + endfacet + facet normal -0.906327 -0.00110477 -0.422577 + outer loop + vertex -693.141 236.729 279.503 + vertex -691.946 244.416 276.92 + vertex -691.681 237.702 276.369 + endloop + endfacet + facet normal -0.873544 -0.00170899 -0.486743 + outer loop + vertex -694.841 245.38 282.441 + vertex -693.152 245.171 279.411 + vertex -694.833 236.686 282.458 + endloop + endfacet + facet normal -0.867701 -0.00656415 -0.497043 + outer loop + vertex -694.833 236.686 282.458 + vertex -693.152 245.171 279.411 + vertex -693.141 236.729 279.503 + endloop + endfacet + facet normal -0.867775 0.00304882 -0.496947 + outer loop + vertex -694.833 236.686 282.458 + vertex -693.141 236.729 279.503 + vertex -694.869 228.008 282.467 + endloop + endfacet + facet normal -0.86845 0.00358464 -0.495764 + outer loop + vertex -694.869 228.008 282.467 + vertex -693.141 236.729 279.503 + vertex -693.139 228.345 279.438 + endloop + endfacet + facet normal -0.90681 0.0029976 -0.421528 + outer loop + vertex -693.141 236.729 279.503 + vertex -691.681 237.702 276.369 + vertex -693.139 228.345 279.438 + endloop + endfacet + facet normal -0.904568 0.00107391 -0.426328 + outer loop + vertex -693.139 228.345 279.438 + vertex -691.681 237.702 276.369 + vertex -691.611 229.059 276.199 + endloop + endfacet + facet normal -0.919964 -0.0146954 -0.391728 + outer loop + vertex -693.295 262.74 279.168 + vertex -691.957 261.539 276.071 + vertex -693.191 253.869 279.257 + endloop + endfacet + facet normal -0.916452 -0.0185769 -0.399712 + outer loop + vertex -693.191 253.869 279.257 + vertex -691.957 261.539 276.071 + vertex -691.738 253.326 275.952 + endloop + endfacet + facet normal -0.886859 -0.0100518 -0.46193 + outer loop + vertex -695.023 262.923 282.481 + vertex -693.295 262.74 279.168 + vertex -694.904 254.124 282.444 + endloop + endfacet + facet normal -0.881289 -0.0150481 -0.472338 + outer loop + vertex -694.904 254.124 282.444 + vertex -693.295 262.74 279.168 + vertex -693.191 253.869 279.257 + endloop + endfacet + facet normal -0.881076 -0.00616074 -0.472934 + outer loop + vertex -694.904 254.124 282.444 + vertex -693.191 253.869 279.257 + vertex -694.841 245.38 282.441 + endloop + endfacet + facet normal -0.873793 -0.0125287 -0.486137 + outer loop + vertex -694.841 245.38 282.441 + vertex -693.191 253.869 279.257 + vertex -693.152 245.171 279.411 + endloop + endfacet + facet normal -0.916109 -0.0112024 -0.400773 + outer loop + vertex -693.191 253.869 279.257 + vertex -691.738 253.326 275.952 + vertex -693.152 245.171 279.411 + endloop + endfacet + facet normal -0.902779 -0.0256334 -0.42934 + outer loop + vertex -693.152 245.171 279.411 + vertex -691.738 253.326 275.952 + vertex -691.946 244.416 276.92 + endloop + endfacet + facet normal -0.928311 -0.019952 -0.37127 + outer loop + vertex -693.687 280.435 279.252 + vertex -692.367 279.722 275.988 + vertex -693.477 271.649 279.199 + endloop + endfacet + facet normal -0.929494 -0.0186342 -0.368366 + outer loop + vertex -693.477 271.649 279.199 + vertex -692.367 279.722 275.988 + vertex -691.926 271.219 275.306 + endloop + endfacet + facet normal -0.89529 -0.0154952 -0.445215 + outer loop + vertex -695.339 280.452 282.572 + vertex -693.687 280.435 279.252 + vertex -695.174 271.71 282.546 + endloop + endfacet + facet normal -0.89189 -0.0185875 -0.451871 + outer loop + vertex -695.174 271.71 282.546 + vertex -693.687 280.435 279.252 + vertex -693.477 271.649 279.199 + endloop + endfacet + facet normal -0.891931 -0.012057 -0.452011 + outer loop + vertex -695.174 271.71 282.546 + vertex -693.477 271.649 279.199 + vertex -695.023 262.923 282.481 + endloop + endfacet + facet normal -0.88693 -0.0165531 -0.461608 + outer loop + vertex -695.023 262.923 282.481 + vertex -693.477 271.649 279.199 + vertex -693.295 262.74 279.168 + endloop + endfacet + facet normal -0.929476 -0.0177385 -0.368457 + outer loop + vertex -693.477 271.649 279.199 + vertex -691.926 271.219 275.306 + vertex -693.295 262.74 279.168 + endloop + endfacet + facet normal -0.921508 -0.0276426 -0.387374 + outer loop + vertex -693.295 262.74 279.168 + vertex -691.926 271.219 275.306 + vertex -691.957 261.539 276.071 + endloop + endfacet + facet normal -0.934601 -0.0254984 -0.354782 + outer loop + vertex -694.099 297.998 279.159 + vertex -692.842 297.227 275.902 + vertex -693.892 289.107 279.251 + endloop + endfacet + facet normal -0.936572 -0.0231505 -0.349709 + outer loop + vertex -693.892 289.107 279.251 + vertex -692.842 297.227 275.902 + vertex -692.417 289.119 275.303 + endloop + endfacet + facet normal -0.905372 -0.0201856 -0.424139 + outer loop + vertex -695.672 298.117 282.511 + vertex -694.099 297.998 279.159 + vertex -695.491 289.207 282.548 + endloop + endfacet + facet normal -0.899742 -0.025525 -0.435676 + outer loop + vertex -695.491 289.207 282.548 + vertex -694.099 297.998 279.159 + vertex -693.892 289.107 279.251 + endloop + endfacet + facet normal -0.899804 -0.016835 -0.43597 + outer loop + vertex -695.491 289.207 282.548 + vertex -693.892 289.107 279.251 + vertex -695.339 280.452 282.572 + endloop + endfacet + facet normal -0.895208 -0.0211235 -0.445147 + outer loop + vertex -695.339 280.452 282.572 + vertex -693.892 289.107 279.251 + vertex -693.687 280.435 279.252 + endloop + endfacet + facet normal -0.936596 -0.0220895 -0.349714 + outer loop + vertex -693.892 289.107 279.251 + vertex -692.417 289.119 275.303 + vertex -693.687 280.435 279.252 + endloop + endfacet + facet normal -0.928922 -0.0319364 -0.368896 + outer loop + vertex -693.687 280.435 279.252 + vertex -692.417 289.119 275.303 + vertex -692.367 279.722 275.988 + endloop + endfacet + facet normal -0.943324 -0.0375674 -0.32974 + outer loop + vertex -695.059 316.768 279.983 + vertex -693.445 319.458 275.058 + vertex -694.398 307.572 279.137 + endloop + endfacet + facet normal -0.942707 -0.0381962 -0.331427 + outer loop + vertex -694.398 307.572 279.137 + vertex -693.445 319.458 275.058 + vertex -692.895 307.226 274.904 + endloop + endfacet + facet normal -0.915761 -0.0261239 -0.400874 + outer loop + vertex -696.385 313.361 283.233 + vertex -695.059 316.768 279.983 + vertex -695.963 306.736 282.7 + endloop + endfacet + facet normal -0.91274 -0.0282084 -0.407566 + outer loop + vertex -695.963 306.736 282.7 + vertex -695.059 316.768 279.983 + vertex -694.398 307.572 279.137 + endloop + endfacet + facet normal -0.913437 -0.0218983 -0.406392 + outer loop + vertex -695.963 306.736 282.7 + vertex -694.398 307.572 279.137 + vertex -695.672 298.117 282.511 + endloop + endfacet + facet normal -0.905293 -0.0292004 -0.423782 + outer loop + vertex -695.672 298.117 282.511 + vertex -694.398 307.572 279.137 + vertex -694.099 297.998 279.159 + endloop + endfacet + facet normal -0.94276 -0.0301565 -0.332105 + outer loop + vertex -694.398 307.572 279.137 + vertex -692.895 307.226 274.904 + vertex -694.099 297.998 279.159 + endloop + endfacet + facet normal -0.935294 -0.0401151 -0.35159 + outer loop + vertex -694.099 297.998 279.159 + vertex -692.895 307.226 274.904 + vertex -692.842 297.227 275.902 + endloop + endfacet + facet normal -0.914806 -0.0284207 -0.402892 + outer loop + vertex -696.385 313.361 283.233 + vertex -696.238 321.689 282.311 + vertex -695.059 316.768 279.983 + endloop + endfacet + facet normal -0.942992 -0.0391658 -0.330503 + outer loop + vertex -693.445 319.458 275.058 + vertex -695.059 316.768 279.983 + vertex -694.723 332.755 277.129 + endloop + endfacet + facet normal -0.940875 -0.0292713 -0.337487 + outer loop + vertex -696.516 329.611 282.399 + vertex -694.723 332.755 277.129 + vertex -696.238 321.689 282.311 + endloop + endfacet + facet normal -0.927552 -0.0466765 -0.370766 + outer loop + vertex -695.059 316.768 279.983 + vertex -696.238 321.689 282.311 + vertex -694.723 332.755 277.129 + endloop + endfacet + facet normal -0.940984 -0.0287697 -0.337225 + outer loop + vertex -696.516 329.611 282.399 + vertex -696.475 339.838 281.413 + vertex -694.723 332.755 277.129 + endloop + endfacet + facet normal -0.949733 -0.0372847 -0.310834 + outer loop + vertex -697.003 353.59 281.376 + vertex -695.194 351.924 276.049 + vertex -696.475 339.838 281.413 + endloop + endfacet + facet normal -0.946849 -0.0412263 -0.319026 + outer loop + vertex -695.194 351.924 276.049 + vertex -694.723 332.755 277.129 + vertex -696.475 339.838 281.413 + endloop + endfacet + facet normal -0.952374 -0.050957 -0.300646 + outer loop + vertex -698.002 368.869 281.952 + vertex -696.171 368.896 276.146 + vertex -697.003 353.59 281.376 + endloop + endfacet + facet normal -0.950496 -0.0529544 -0.306192 + outer loop + vertex -697.003 353.59 281.376 + vertex -696.171 368.896 276.146 + vertex -695.194 351.924 276.049 + endloop + endfacet + facet normal -0.959042 -0.0600195 -0.276833 + outer loop + vertex -699.392 386.649 282.913 + vertex -697.594 386.626 276.689 + vertex -698.002 368.869 281.952 + endloop + endfacet + facet normal -0.951436 -0.0671864 -0.300425 + outer loop + vertex -698.002 368.869 281.952 + vertex -697.594 386.626 276.689 + vertex -696.171 368.896 276.146 + endloop + endfacet + facet normal -0.788617 -0.483914 -0.379355 + outer loop + vertex -678.113 149.612 271.102 + vertex -679.094 148.581 274.456 + vertex -679.093 150.207 272.381 + endloop + endfacet + facet normal -0.778052 -0.473473 -0.412865 + outer loop + vertex -679.094 148.581 274.456 + vertex -680.522 147.518 278.366 + vertex -680.319 149.198 276.057 + endloop + endfacet + facet normal -0.895694 -0.389079 -0.215288 + outer loop + vertex -679.962 165.833 252.356 + vertex -679.639 166.18 250.389 + vertex -678.049 161.376 252.455 + endloop + endfacet + facet normal -0.895757 -0.389028 -0.21512 + outer loop + vertex -678.049 161.376 252.455 + vertex -679.639 166.18 250.389 + vertex -677.761 161.809 250.471 + endloop + endfacet + facet normal -0.898306 -0.389914 -0.202517 + outer loop + vertex -677.538 162.295 248.544 + vertex -677.761 161.809 250.471 + vertex -679.399 166.617 248.48 + endloop + endfacet + facet normal -0.898328 -0.389896 -0.202457 + outer loop + vertex -679.399 166.617 248.48 + vertex -677.761 161.809 250.471 + vertex -679.639 166.18 250.389 + endloop + endfacet + facet normal -0.87639 -0.385978 -0.288031 + outer loop + vertex -680.439 165.774 254.271 + vertex -678.404 160.833 254.7 + vertex -679.351 161.777 256.318 + endloop + endfacet + facet normal -0.891461 -0.387691 -0.234505 + outer loop + vertex -678.049 161.376 252.455 + vertex -678.404 160.833 254.7 + vertex -679.962 165.833 252.356 + endloop + endfacet + facet normal -0.891613 -0.387565 -0.234136 + outer loop + vertex -679.962 165.833 252.356 + vertex -678.404 160.833 254.7 + vertex -680.439 165.774 254.271 + endloop + endfacet + facet normal -0.904133 -0.390302 -0.173805 + outer loop + vertex -679.032 167.606 244.709 + vertex -678.874 168.076 242.836 + vertex -677.172 163.292 244.72 + endloop + endfacet + facet normal -0.903474 -0.39089 -0.175894 + outer loop + vertex -677.172 163.292 244.72 + vertex -678.874 168.076 242.836 + vertex -677.013 163.772 242.838 + endloop + endfacet + facet normal -0.905206 -0.390582 -0.167473 + outer loop + vertex -676.873 164.238 240.998 + vertex -677.013 163.772 242.838 + vertex -678.725 168.531 240.996 + endloop + endfacet + facet normal -0.904417 -0.391296 -0.170052 + outer loop + vertex -678.725 168.531 240.996 + vertex -677.013 163.772 242.838 + vertex -678.874 168.076 242.836 + endloop + endfacet + facet normal -0.900112 -0.39055 -0.193053 + outer loop + vertex -679.399 166.617 248.48 + vertex -679.208 167.11 246.591 + vertex -677.538 162.295 248.544 + endloop + endfacet + facet normal -0.900199 -0.390476 -0.192796 + outer loop + vertex -677.538 162.295 248.544 + vertex -679.208 167.11 246.591 + vertex -677.347 162.802 246.628 + endloop + endfacet + facet normal -0.902577 -0.389656 -0.183094 + outer loop + vertex -677.172 163.292 244.72 + vertex -677.347 162.802 246.628 + vertex -679.032 167.606 244.709 + endloop + endfacet + facet normal -0.90119 -0.390856 -0.187317 + outer loop + vertex -679.032 167.606 244.709 + vertex -677.347 162.802 246.628 + vertex -679.208 167.11 246.591 + endloop + endfacet + facet normal -0.909858 -0.38982 -0.142125 + outer loop + vertex -678.477 169.398 237.423 + vertex -678.377 169.811 235.646 + vertex -676.635 165.093 237.437 + endloop + endfacet + facet normal -0.909403 -0.390277 -0.143769 + outer loop + vertex -676.635 165.093 237.437 + vertex -678.377 169.811 235.646 + vertex -676.53 165.504 235.659 + endloop + endfacet + facet normal -0.910766 -0.389546 -0.136967 + outer loop + vertex -676.433 165.917 233.836 + vertex -676.53 165.504 235.659 + vertex -678.281 170.239 233.83 + endloop + endfacet + facet normal -0.909877 -0.390469 -0.140208 + outer loop + vertex -678.281 170.239 233.83 + vertex -676.53 165.504 235.659 + vertex -678.377 169.811 235.646 + endloop + endfacet + facet normal -0.906366 -0.39108 -0.159864 + outer loop + vertex -678.725 168.531 240.996 + vertex -678.595 168.965 239.195 + vertex -676.873 164.238 240.998 + endloop + endfacet + facet normal -0.90713 -0.390365 -0.15726 + outer loop + vertex -676.873 164.238 240.998 + vertex -678.595 168.965 239.195 + vertex -676.745 164.662 239.205 + endloop + endfacet + facet normal -0.908583 -0.389304 -0.151395 + outer loop + vertex -676.635 165.093 237.437 + vertex -676.745 164.662 239.205 + vertex -678.477 169.398 237.423 + endloop + endfacet + facet normal -0.907364 -0.390462 -0.155661 + outer loop + vertex -678.477 169.398 237.423 + vertex -676.745 164.662 239.205 + vertex -678.595 168.965 239.195 + endloop + endfacet + facet normal -0.912756 -0.389688 -0.122559 + outer loop + vertex -678.105 171.084 230.045 + vertex -678.025 171.505 228.114 + vertex -676.255 166.757 230.029 + endloop + endfacet + facet normal -0.913493 -0.388831 -0.119752 + outer loop + vertex -676.255 166.757 230.029 + vertex -678.025 171.505 228.114 + vertex -676.18 167.177 228.09 + endloop + endfacet + facet normal -0.91399 -0.389562 -0.113418 + outer loop + vertex -676.115 167.586 226.163 + vertex -676.18 167.177 228.09 + vertex -677.958 171.901 226.191 + endloop + endfacet + facet normal -0.914283 -0.389209 -0.112265 + outer loop + vertex -677.958 171.901 226.191 + vertex -676.18 167.177 228.09 + vertex -678.025 171.505 228.114 + endloop + endfacet + facet normal -0.911247 -0.389746 -0.133141 + outer loop + vertex -678.281 170.239 233.83 + vertex -678.188 170.662 231.961 + vertex -676.433 165.917 233.836 + endloop + endfacet + facet normal -0.911173 -0.389826 -0.133412 + outer loop + vertex -676.433 165.917 233.836 + vertex -678.188 170.662 231.961 + vertex -676.344 166.353 231.953 + endloop + endfacet + facet normal -0.91264 -0.389635 -0.123583 + outer loop + vertex -676.255 166.757 230.029 + vertex -676.344 166.353 231.953 + vertex -678.105 171.084 230.045 + endloop + endfacet + facet normal -0.912108 -0.390242 -0.12558 + outer loop + vertex -678.105 171.084 230.045 + vertex -676.344 166.353 231.953 + vertex -678.188 170.662 231.961 + endloop + endfacet + facet normal -0.91568 -0.389041 -0.100879 + outer loop + vertex -677.84 172.665 222.405 + vertex -677.783 173.024 220.503 + vertex -675.995 168.33 222.374 + endloop + endfacet + facet normal -0.916242 -0.388319 -0.0985306 + outer loop + vertex -675.995 168.33 222.374 + vertex -677.783 173.024 220.503 + vertex -675.938 168.678 220.472 + endloop + endfacet + facet normal -0.916907 -0.387795 -0.0943221 + outer loop + vertex -675.89 169.038 218.523 + vertex -675.938 168.678 220.472 + vertex -677.729 173.379 218.556 + endloop + endfacet + facet normal -0.916438 -0.388419 -0.0962906 + outer loop + vertex -677.729 173.379 218.556 + vertex -675.938 168.678 220.472 + vertex -677.783 173.024 220.503 + endloop + endfacet + facet normal -0.91417 -0.38965 -0.111652 + outer loop + vertex -677.958 171.901 226.191 + vertex -677.895 172.297 224.292 + vertex -676.115 167.586 226.163 + endloop + endfacet + facet normal -0.915132 -0.388478 -0.107788 + outer loop + vertex -676.115 167.586 226.163 + vertex -677.895 172.297 224.292 + vertex -676.054 167.97 224.262 + endloop + endfacet + facet normal -0.915474 -0.388938 -0.103127 + outer loop + vertex -675.995 168.33 222.374 + vertex -676.054 167.97 224.262 + vertex -677.84 172.665 222.405 + endloop + endfacet + facet normal -0.915638 -0.388732 -0.102448 + outer loop + vertex -677.84 172.665 222.405 + vertex -676.054 167.97 224.262 + vertex -677.895 172.297 224.292 + endloop + endfacet + facet normal -0.91841 -0.387657 -0.0790275 + outer loop + vertex -677.63 174.065 214.513 + vertex -677.587 174.378 212.476 + vertex -675.789 169.71 214.477 + endloop + endfacet + facet normal -0.917815 -0.388532 -0.0816021 + outer loop + vertex -675.789 169.71 214.477 + vertex -677.587 174.378 212.476 + vertex -675.745 170.035 212.441 + endloop + endfacet + facet normal -0.918813 -0.38724 -0.0763397 + outer loop + vertex -675.701 170.32 210.459 + vertex -675.745 170.035 212.441 + vertex -677.542 174.681 210.496 + endloop + endfacet + facet normal -0.917903 -0.388579 -0.0803807 + outer loop + vertex -677.542 174.681 210.496 + vertex -675.745 170.035 212.441 + vertex -677.587 174.378 212.476 + endloop + endfacet + facet normal -0.917439 -0.388071 -0.0877874 + outer loop + vertex -677.729 173.379 218.556 + vertex -677.682 173.722 216.552 + vertex -675.89 169.038 218.523 + endloop + endfacet + facet normal -0.916823 -0.38893 -0.0903882 + outer loop + vertex -675.89 169.038 218.523 + vertex -677.682 173.722 216.552 + vertex -675.838 169.384 216.519 + endloop + endfacet + facet normal -0.918025 -0.387451 -0.0843271 + outer loop + vertex -675.789 169.71 214.477 + vertex -675.838 169.384 216.519 + vertex -677.63 174.065 214.513 + endloop + endfacet + facet normal -0.916943 -0.388992 -0.08889 + outer loop + vertex -677.63 174.065 214.513 + vertex -675.838 169.384 216.519 + vertex -677.682 173.722 216.552 + endloop + endfacet + facet normal -0.919243 -0.388132 -0.0659258 + outer loop + vertex -677.464 175.191 206.738 + vertex -677.432 175.427 204.896 + vertex -675.628 170.851 206.696 + endloop + endfacet + facet normal -0.919699 -0.387427 -0.0636774 + outer loop + vertex -675.628 170.851 206.696 + vertex -677.432 175.427 204.896 + vertex -675.594 171.072 204.848 + endloop + endfacet + facet normal -0.920217 -0.386561 -0.0614063 + outer loop + vertex -675.57 171.315 202.966 + vertex -675.594 171.072 204.848 + vertex -677.401 175.665 203.022 + endloop + endfacet + facet normal -0.919676 -0.387413 -0.0640831 + outer loop + vertex -677.401 175.665 203.022 + vertex -675.594 171.072 204.848 + vertex -677.432 175.427 204.896 + endloop + endfacet + facet normal -0.918855 -0.387263 -0.0757159 + outer loop + vertex -677.542 174.681 210.496 + vertex -677.498 174.951 208.591 + vertex -675.701 170.32 210.459 + endloop + endfacet + facet normal -0.919197 -0.386757 -0.0741345 + outer loop + vertex -675.701 170.32 210.459 + vertex -677.498 174.951 208.591 + vertex -675.661 170.59 208.553 + endloop + endfacet + facet normal -0.918979 -0.387977 -0.0703748 + outer loop + vertex -675.628 170.851 206.696 + vertex -675.661 170.59 208.553 + vertex -677.464 175.191 206.738 + endloop + endfacet + facet normal -0.919625 -0.386997 -0.0672486 + outer loop + vertex -677.464 175.191 206.738 + vertex -675.661 170.59 208.553 + vertex -677.498 174.951 208.591 + endloop + endfacet + facet normal -0.921139 -0.386209 -0.048433 + outer loop + vertex -677.347 176.104 199.134 + vertex -677.303 176.252 197.101 + vertex -675.51 171.734 199.029 + endloop + endfacet + facet normal -0.920484 -0.387345 -0.0517041 + outer loop + vertex -675.51 171.734 199.029 + vertex -677.303 176.252 197.101 + vertex -675.446 171.868 196.897 + endloop + endfacet + facet normal -0.920063 -0.38817 -0.0529867 + outer loop + vertex -675.415 172.122 194.489 + vertex -675.446 171.868 196.897 + vertex -677.254 176.421 194.941 + endloop + endfacet + facet normal -0.920512 -0.3874 -0.0507802 + outer loop + vertex -677.254 176.421 194.941 + vertex -675.446 171.868 196.897 + vertex -677.303 176.252 197.101 + endloop + endfacet + facet normal -0.920366 -0.386661 -0.0584699 + outer loop + vertex -677.401 175.665 203.022 + vertex -677.377 175.897 201.101 + vertex -675.57 171.315 202.966 + endloop + endfacet + facet normal -0.920768 -0.386003 -0.0564636 + outer loop + vertex -675.57 171.315 202.966 + vertex -677.377 175.897 201.101 + vertex -675.548 171.545 201.034 + endloop + endfacet + facet normal -0.920923 -0.385983 -0.0540148 + outer loop + vertex -675.51 171.734 199.029 + vertex -675.548 171.545 201.034 + vertex -677.347 176.104 199.134 + endloop + endfacet + facet normal -0.920867 -0.386078 -0.0542938 + outer loop + vertex -677.347 176.104 199.134 + vertex -675.548 171.545 201.034 + vertex -677.377 175.897 201.101 + endloop + endfacet + facet normal -0.921052 -0.387764 -0.0360794 + outer loop + vertex -677.63 177.817 190.581 + vertex -677.32 177.251 188.751 + vertex -675.619 172.969 191.352 + endloop + endfacet + facet normal -0.919559 -0.390883 -0.0402679 + outer loop + vertex -677.528 177.95 186.724 + vertex -675.522 173.134 187.647 + vertex -677.32 177.251 188.751 + endloop + endfacet + facet normal -0.919637 -0.390559 -0.0416049 + outer loop + vertex -675.522 173.134 187.647 + vertex -675.619 172.969 191.352 + vertex -677.32 177.251 188.751 + endloop + endfacet + facet normal -0.920117 -0.388885 -0.0464038 + outer loop + vertex -677.254 176.421 194.941 + vertex -677.307 176.822 192.619 + vertex -675.415 172.122 194.489 + endloop + endfacet + facet normal -0.920324 -0.388694 -0.0438202 + outer loop + vertex -677.63 177.817 190.581 + vertex -675.619 172.969 191.352 + vertex -677.307 176.822 192.619 + endloop + endfacet + facet normal -0.920404 -0.388386 -0.0448611 + outer loop + vertex -675.619 172.969 191.352 + vertex -675.415 172.122 194.489 + vertex -677.307 176.822 192.619 + endloop + endfacet + facet normal -0.920626 -0.390201 -0.0138147 + outer loop + vertex -677.46 178.054 182.972 + vertex -677.171 177.434 181.214 + vertex -675.403 173.172 183.819 + endloop + endfacet + facet normal -0.919365 -0.392682 -0.0238396 + outer loop + vertex -677.44 178.187 179.21 + vertex -675.348 173.24 179.999 + vertex -677.171 177.434 181.214 + endloop + endfacet + facet normal -0.919073 -0.393561 -0.020364 + outer loop + vertex -675.348 173.24 179.999 + vertex -675.403 173.172 183.819 + vertex -677.171 177.434 181.214 + endloop + endfacet + facet normal -0.921104 -0.388535 -0.0246455 + outer loop + vertex -677.528 177.95 186.724 + vertex -677.217 177.323 184.955 + vertex -675.522 173.134 187.647 + endloop + endfacet + facet normal -0.919096 -0.392726 -0.0320818 + outer loop + vertex -677.46 178.054 182.972 + vertex -675.403 173.172 183.819 + vertex -677.217 177.323 184.955 + endloop + endfacet + facet normal -0.919113 -0.392666 -0.0323313 + outer loop + vertex -675.403 173.172 183.819 + vertex -675.522 173.134 187.647 + vertex -677.217 177.323 184.955 + endloop + endfacet + facet normal -0.920136 -0.391588 -0.0027728 + outer loop + vertex -677.443 178.269 175.324 + vertex -677.164 177.627 173.462 + vertex -675.365 173.382 176.134 + endloop + endfacet + facet normal -0.919421 -0.39326 -0.0032137 + outer loop + vertex -677.438 178.285 171.374 + vertex -675.34 173.373 172.237 + vertex -677.164 177.627 173.462 + endloop + endfacet + facet normal -0.919607 -0.392807 -0.00506517 + outer loop + vertex -675.34 173.373 172.237 + vertex -675.365 173.382 176.134 + vertex -677.164 177.627 173.462 + endloop + endfacet + facet normal -0.920585 -0.390483 -0.00683363 + outer loop + vertex -677.44 178.187 179.21 + vertex -677.165 177.569 177.385 + vertex -675.348 173.24 179.999 + endloop + endfacet + facet normal -0.919712 -0.392484 -0.00927202 + outer loop + vertex -677.443 178.269 175.324 + vertex -675.365 173.382 176.134 + vertex -677.165 177.569 177.385 + endloop + endfacet + facet normal -0.91981 -0.39223 -0.010264 + outer loop + vertex -675.365 173.382 176.134 + vertex -675.348 173.24 179.999 + vertex -677.165 177.569 177.385 + endloop + endfacet + facet normal -0.920063 -0.391494 0.0147175 + outer loop + vertex -677.446 178.245 167.407 + vertex -677.181 177.553 165.551 + vertex -675.356 173.368 168.275 + endloop + endfacet + facet normal -0.920134 -0.391491 0.00941264 + outer loop + vertex -677.465 178.172 163.483 + vertex -675.402 173.343 164.336 + vertex -677.181 177.553 165.551 + endloop + endfacet + facet normal -0.919709 -0.392381 0.0131178 + outer loop + vertex -675.402 173.343 164.336 + vertex -675.356 173.368 168.275 + vertex -677.181 177.553 165.551 + endloop + endfacet + facet normal -0.919958 -0.391981 0.00537573 + outer loop + vertex -677.438 178.285 171.374 + vertex -677.163 177.615 169.502 + vertex -675.34 173.373 172.237 + endloop + endfacet + facet normal -0.919564 -0.392899 0.00562314 + outer loop + vertex -677.446 178.245 167.407 + vertex -675.356 173.368 168.275 + vertex -677.163 177.615 169.502 + endloop + endfacet + facet normal -0.91971 -0.392575 0.00428882 + outer loop + vertex -675.356 173.368 168.275 + vertex -675.34 173.373 172.237 + vertex -677.163 177.615 169.502 + endloop + endfacet + facet normal -0.920032 -0.390565 0.0316237 + outer loop + vertex -677.48 178.005 159.622 + vertex -677.215 177.233 157.801 + vertex -675.382 173.129 160.462 + endloop + endfacet + facet normal -0.919134 -0.393196 0.024304 + outer loop + vertex -677.507 177.789 155.752 + vertex -675.402 172.917 156.579 + vertex -677.215 177.233 157.801 + endloop + endfacet + facet normal -0.918903 -0.393618 0.0261371 + outer loop + vertex -675.402 172.917 156.579 + vertex -675.382 173.129 160.462 + vertex -677.215 177.233 157.801 + endloop + endfacet + facet normal -0.920811 -0.389304 0.0234408 + outer loop + vertex -677.465 178.172 163.483 + vertex -677.197 177.428 161.662 + vertex -675.402 173.343 164.336 + endloop + endfacet + facet normal -0.91944 -0.392873 0.0167499 + outer loop + vertex -677.48 178.005 159.622 + vertex -675.382 173.129 160.462 + vertex -677.197 177.428 161.662 + endloop + endfacet + facet normal -0.919414 -0.392924 0.0169725 + outer loop + vertex -675.382 173.129 160.462 + vertex -675.402 173.343 164.336 + vertex -677.197 177.428 161.662 + endloop + endfacet + facet normal -0.919527 -0.390354 0.0457675 + outer loop + vertex -677.55 177.53 151.876 + vertex -677.293 176.712 150.068 + vertex -675.468 172.724 152.721 + endloop + endfacet + facet normal -0.918259 -0.393914 0.0403951 + outer loop + vertex -677.597 177.212 148.046 + vertex -675.491 172.39 148.884 + vertex -677.293 176.712 150.068 + endloop + endfacet + facet normal -0.918341 -0.393784 0.0397964 + outer loop + vertex -675.491 172.39 148.884 + vertex -675.468 172.724 152.721 + vertex -677.293 176.712 150.068 + endloop + endfacet + facet normal -0.919589 -0.391002 0.0384002 + outer loop + vertex -677.507 177.789 155.752 + vertex -677.249 177.002 153.923 + vertex -675.402 172.917 156.579 + endloop + endfacet + facet normal -0.919212 -0.392299 0.033935 + outer loop + vertex -677.55 177.53 151.876 + vertex -675.468 172.724 152.721 + vertex -677.249 177.002 153.923 + endloop + endfacet + facet normal -0.919006 -0.392644 0.0354685 + outer loop + vertex -675.468 172.724 152.721 + vertex -675.402 172.917 156.579 + vertex -677.249 177.002 153.923 + endloop + endfacet + facet normal -0.918005 -0.391926 0.0605055 + outer loop + vertex -677.636 176.804 144.201 + vertex -677.362 175.867 142.274 + vertex -675.514 171.944 144.904 + endloop + endfacet + facet normal -0.918392 -0.390815 0.0618055 + outer loop + vertex -677.69 176.307 140.185 + vertex -675.497 171.208 140.541 + vertex -677.362 175.867 142.274 + endloop + endfacet + facet normal -0.918315 -0.390933 0.062205 + outer loop + vertex -675.497 171.208 140.541 + vertex -675.514 171.944 144.904 + vertex -677.362 175.867 142.274 + endloop + endfacet + facet normal -0.918508 -0.391846 0.0529224 + outer loop + vertex -677.597 177.212 148.046 + vertex -677.341 176.368 146.236 + vertex -675.491 172.39 148.884 + endloop + endfacet + facet normal -0.917982 -0.393619 0.0487272 + outer loop + vertex -677.636 176.804 144.201 + vertex -675.514 171.944 144.904 + vertex -677.341 176.368 146.236 + endloop + endfacet + facet normal -0.917858 -0.393807 0.049522 + outer loop + vertex -675.514 171.944 144.904 + vertex -675.491 172.39 148.884 + vertex -677.341 176.368 146.236 + endloop + endfacet + facet normal -0.923838 -0.375677 0.0734184 + outer loop + vertex -677.999 176.27 136.343 + vertex -677.673 175.16 134.75 + vertex -676.387 172.439 137.019 + endloop + endfacet + facet normal -0.920265 -0.387001 0.0578169 + outer loop + vertex -676.387 172.439 137.019 + vertex -677.673 175.16 134.75 + vertex -675.82 170.766 134.845 + endloop + endfacet + facet normal -0.919441 -0.387874 0.0646739 + outer loop + vertex -675.684 170.074 132.63 + vertex -675.82 170.766 134.845 + vertex -677.53 174.471 132.744 + endloop + endfacet + facet normal -0.919795 -0.3866 0.0672082 + outer loop + vertex -677.53 174.471 132.744 + vertex -675.82 170.766 134.845 + vertex -677.673 175.16 134.75 + endloop + endfacet + facet normal -0.917617 -0.389152 0.0808683 + outer loop + vertex -677.69 176.307 140.185 + vertex -677.602 175.708 138.304 + vertex -675.497 171.208 140.541 + endloop + endfacet + facet normal -0.923783 -0.374617 0.0792918 + outer loop + vertex -677.999 176.27 136.343 + vertex -676.387 172.439 137.019 + vertex -677.602 175.708 138.304 + endloop + endfacet + facet normal -0.919313 -0.380804 0.0992585 + outer loop + vertex -676.387 172.439 137.019 + vertex -675.497 171.208 140.541 + vertex -677.602 175.708 138.304 + endloop + endfacet + facet normal -0.917307 -0.387345 0.0922603 + outer loop + vertex -677.637 173.904 128.743 + vertex -677.71 173.613 126.806 + vertex -675.817 169.557 128.59 + endloop + endfacet + facet normal -0.916969 -0.389207 0.0876686 + outer loop + vertex -675.817 169.557 128.59 + vertex -677.71 173.613 126.806 + vertex -675.878 169.263 126.652 + endloop + endfacet + facet normal -0.916953 -0.388352 0.0915406 + outer loop + vertex -675.913 168.889 124.717 + vertex -675.878 169.263 126.652 + vertex -677.754 173.275 124.879 + endloop + endfacet + facet normal -0.916799 -0.389199 0.0894598 + outer loop + vertex -677.754 173.275 124.879 + vertex -675.878 169.263 126.652 + vertex -677.71 173.613 126.806 + endloop + endfacet + facet normal -0.918611 -0.387814 0.0758508 + outer loop + vertex -677.53 174.471 132.744 + vertex -677.556 174.134 130.713 + vertex -675.684 170.074 132.63 + endloop + endfacet + facet normal -0.91866 -0.387601 0.0763489 + outer loop + vertex -675.684 170.074 132.63 + vertex -677.556 174.134 130.713 + vertex -675.739 169.795 130.555 + endloop + endfacet + facet normal -0.918109 -0.38738 0.083739 + outer loop + vertex -675.817 169.557 128.59 + vertex -675.739 169.795 130.555 + vertex -677.637 173.904 128.743 + endloop + endfacet + facet normal -0.918066 -0.387602 0.0831905 + outer loop + vertex -677.637 173.904 128.743 + vertex -675.739 169.795 130.555 + vertex -677.556 174.134 130.713 + endloop + endfacet + facet normal -0.915094 -0.390158 0.101882 + outer loop + vertex -677.848 172.535 121.085 + vertex -677.904 172.18 119.221 + vertex -676.007 168.172 120.91 + endloop + endfacet + facet normal -0.915215 -0.389299 0.104058 + outer loop + vertex -676.007 168.172 120.91 + vertex -677.904 172.18 119.221 + vertex -676.068 167.815 119.038 + endloop + endfacet + facet normal -0.914462 -0.389721 0.108981 + outer loop + vertex -676.134 167.445 117.164 + vertex -676.068 167.815 119.038 + vertex -677.97 171.806 117.356 + endloop + endfacet + facet normal -0.914519 -0.389262 0.110134 + outer loop + vertex -677.97 171.806 117.356 + vertex -676.068 167.815 119.038 + vertex -677.904 172.18 119.221 + endloop + endfacet + facet normal -0.916431 -0.388325 0.0967416 + outer loop + vertex -677.754 173.275 124.879 + vertex -677.798 172.902 122.968 + vertex -675.913 168.889 124.717 + endloop + endfacet + facet normal -0.916148 -0.39 0.0925941 + outer loop + vertex -675.913 168.889 124.717 + vertex -677.798 172.902 122.968 + vertex -675.958 168.54 122.799 + endloop + endfacet + facet normal -0.915296 -0.390169 0.10001 + outer loop + vertex -676.007 168.172 120.91 + vertex -675.958 168.54 122.799 + vertex -677.848 172.535 121.085 + endloop + endfacet + facet normal -0.915327 -0.389962 0.100527 + outer loop + vertex -677.848 172.535 121.085 + vertex -675.958 168.54 122.799 + vertex -677.798 172.902 122.968 + endloop + endfacet + facet normal -0.9116 -0.390771 0.127609 + outer loop + vertex -678.115 171.006 113.587 + vertex -678.196 170.576 111.689 + vertex -676.272 166.642 113.388 + endloop + endfacet + facet normal -0.911485 -0.391988 0.12466 + outer loop + vertex -676.272 166.642 113.388 + vertex -678.196 170.576 111.689 + vertex -676.351 166.223 111.49 + endloop + endfacet + facet normal -0.910457 -0.392191 0.131357 + outer loop + vertex -676.443 165.798 109.588 + vertex -676.351 166.223 111.49 + vertex -678.287 170.146 109.787 + endloop + endfacet + facet normal -0.910481 -0.391901 0.132055 + outer loop + vertex -678.287 170.146 109.787 + vertex -676.351 166.223 111.49 + vertex -678.196 170.576 111.689 + endloop + endfacet + facet normal -0.913856 -0.389688 0.114062 + outer loop + vertex -677.97 171.806 117.356 + vertex -678.038 171.416 115.477 + vertex -676.134 167.445 117.164 + endloop + endfacet + facet normal -0.913828 -0.389926 0.113471 + outer loop + vertex -676.134 167.445 117.164 + vertex -678.038 171.416 115.477 + vertex -676.201 167.054 115.28 + endloop + endfacet + facet normal -0.912689 -0.390853 0.119302 + outer loop + vertex -676.272 166.642 113.388 + vertex -676.201 167.054 115.28 + vertex -678.115 171.006 113.587 + endloop + endfacet + facet normal -0.912792 -0.389862 0.121729 + outer loop + vertex -678.115 171.006 113.587 + vertex -676.201 167.054 115.28 + vertex -678.038 171.416 115.477 + endloop + endfacet + facet normal -0.906464 -0.392121 0.156731 + outer loop + vertex -678.502 169.248 105.974 + vertex -678.628 168.779 104.069 + vertex -676.657 164.901 105.768 + endloop + endfacet + facet normal -0.90642 -0.393379 0.153807 + outer loop + vertex -676.657 164.901 105.768 + vertex -678.628 168.779 104.069 + vertex -676.783 164.443 103.856 + endloop + endfacet + facet normal -0.905068 -0.393386 0.161553 + outer loop + vertex -676.917 163.972 101.954 + vertex -676.783 164.443 103.856 + vertex -678.763 168.31 102.177 + endloop + endfacet + facet normal -0.905071 -0.393206 0.161971 + outer loop + vertex -678.763 168.31 102.177 + vertex -676.783 164.443 103.856 + vertex -678.628 168.779 104.069 + endloop + endfacet + facet normal -0.909374 -0.392081 0.138967 + outer loop + vertex -678.287 170.146 109.787 + vertex -678.387 169.704 107.882 + vertex -676.443 165.798 109.588 + endloop + endfacet + facet normal -0.909376 -0.392041 0.139062 + outer loop + vertex -676.443 165.798 109.588 + vertex -678.387 169.704 107.882 + vertex -676.544 165.356 107.681 + endloop + endfacet + facet normal -0.907988 -0.392314 0.14713 + outer loop + vertex -676.657 164.901 105.768 + vertex -676.544 165.356 107.681 + vertex -678.502 169.248 105.974 + endloop + endfacet + facet normal -0.908011 -0.391881 0.148142 + outer loop + vertex -678.502 169.248 105.974 + vertex -676.544 165.356 107.681 + vertex -678.387 169.704 107.882 + endloop + endfacet + facet normal -0.899685 -0.393323 0.189378 + outer loop + vertex -679.081 167.386 98.4336 + vertex -679.27 166.925 96.5769 + vertex -677.231 163.042 98.1994 + endloop + endfacet + facet normal -0.899781 -0.395369 0.184602 + outer loop + vertex -677.231 163.042 98.1994 + vertex -679.27 166.925 96.5769 + vertex -677.415 162.598 96.3498 + endloop + endfacet + facet normal -0.897927 -0.395697 0.192747 + outer loop + vertex -677.608 162.141 94.5134 + vertex -677.415 162.598 96.3498 + vertex -679.462 166.453 94.7318 + endloop + endfacet + facet normal -0.89789 -0.395063 0.194211 + outer loop + vertex -679.462 166.453 94.7318 + vertex -677.415 162.598 96.3498 + vertex -679.27 166.925 96.5769 + endloop + endfacet + facet normal -0.903332 -0.39316 0.171513 + outer loop + vertex -678.763 168.31 102.177 + vertex -678.915 167.84 100.298 + vertex -676.917 163.972 101.954 + endloop + endfacet + facet normal -0.903336 -0.394312 0.168827 + outer loop + vertex -676.917 163.972 101.954 + vertex -678.915 167.84 100.298 + vertex -677.067 163.506 100.067 + endloop + endfacet + facet normal -0.902026 -0.39366 0.177148 + outer loop + vertex -677.231 163.042 98.1994 + vertex -677.067 163.506 100.067 + vertex -679.081 167.386 98.4336 + endloop + endfacet + facet normal -0.902037 -0.394141 0.176019 + outer loop + vertex -679.081 167.386 98.4336 + vertex -677.067 163.506 100.067 + vertex -678.915 167.84 100.298 + endloop + endfacet + facet normal -0.872334 -0.391984 0.2922 + outer loop + vertex -678.082 160.112 88.8859 + vertex -680.16 164.68 88.8102 + vertex -679.842 162.717 87.128 + endloop + endfacet + facet normal -0.872372 -0.416636 0.255698 + outer loop + vertex -678.176 159.184 87.0532 + vertex -678.082 160.112 88.8859 + vertex -679.842 162.717 87.128 + endloop + endfacet + facet normal -0.8922 -0.368534 0.261078 + outer loop + vertex -681.263 166.009 86.9181 + vertex -679.842 162.717 87.128 + vertex -680.16 164.68 88.8102 + endloop + endfacet + facet normal -0.885654 -0.394726 0.244559 + outer loop + vertex -679.852 165.33 90.9768 + vertex -680.16 164.68 88.8102 + vertex -677.987 161.014 90.7626 + endloop + endfacet + facet normal -0.88586 -0.399057 0.236656 + outer loop + vertex -677.987 161.014 90.7626 + vertex -680.16 164.68 88.8102 + vertex -678.082 160.112 88.8859 + endloop + endfacet + facet normal -0.895384 -0.395231 0.205136 + outer loop + vertex -679.462 166.453 94.7318 + vertex -679.649 165.92 92.8862 + vertex -677.608 162.141 94.5134 + endloop + endfacet + facet normal -0.895459 -0.396345 0.202643 + outer loop + vertex -677.608 162.141 94.5134 + vertex -679.649 165.92 92.8862 + vertex -677.798 161.625 92.6663 + endloop + endfacet + facet normal -0.89238 -0.396216 0.216036 + outer loop + vertex -677.987 161.014 90.7626 + vertex -677.798 161.625 92.6663 + vertex -679.852 165.33 90.9768 + endloop + endfacet + facet normal -0.892347 -0.395741 0.217038 + outer loop + vertex -679.852 165.33 90.9768 + vertex -677.798 161.625 92.6663 + vertex -679.649 165.92 92.8862 + endloop + endfacet + facet normal -0.882025 -0.37262 0.288421 + outer loop + vertex -681.984 164.128 81.8648 + vertex -682.381 163.643 80.024 + vertex -680.596 160.684 81.6609 + endloop + endfacet + facet normal -0.88214 -0.373559 0.28685 + outer loop + vertex -680.596 160.684 81.6609 + vertex -682.381 163.643 80.024 + vertex -680.99 160.199 79.8195 + endloop + endfacet + facet normal -0.886484 -0.373616 0.273051 + outer loop + vertex -681.637 164.65 83.7054 + vertex -681.984 164.128 81.8648 + vertex -680.234 161.19 83.527 + endloop + endfacet + facet normal -0.886475 -0.373514 0.273222 + outer loop + vertex -680.234 161.19 83.527 + vertex -681.984 164.128 81.8648 + vertex -680.596 160.684 81.6609 + endloop + endfacet + facet normal -0.86049 -0.424327 0.281966 + outer loop + vertex -680.234 161.19 83.527 + vertex -680.596 160.684 81.6609 + vertex -678.732 157.997 83.3072 + endloop + endfacet + facet normal -0.86055 -0.426554 0.278398 + outer loop + vertex -678.732 157.997 83.3072 + vertex -680.596 160.684 81.6609 + vertex -679.097 157.519 81.445 + endloop + endfacet + facet normal -0.855658 -0.425358 0.294823 + outer loop + vertex -680.596 160.684 81.6609 + vertex -680.99 160.199 79.8195 + vertex -679.097 157.519 81.445 + endloop + endfacet + facet normal -0.855728 -0.426798 0.29253 + outer loop + vertex -679.097 157.519 81.445 + vertex -680.99 160.199 79.8195 + vertex -679.482 157.034 79.6115 + endloop + endfacet + facet normal -0.890336 -0.372108 0.262368 + outer loop + vertex -681.384 165.283 85.4627 + vertex -681.637 164.65 83.7054 + vertex -679.953 161.798 85.376 + endloop + endfacet + facet normal -0.890483 -0.374485 0.25846 + outer loop + vertex -679.953 161.798 85.376 + vertex -681.637 164.65 83.7054 + vertex -680.234 161.19 83.527 + endloop + endfacet + facet normal -0.892831 -0.368986 0.258267 + outer loop + vertex -681.263 166.009 86.9181 + vertex -681.384 165.283 85.4627 + vertex -679.842 162.717 87.128 + endloop + endfacet + facet normal -0.892909 -0.372914 0.252286 + outer loop + vertex -679.842 162.717 87.128 + vertex -681.384 165.283 85.4627 + vertex -679.953 161.798 85.376 + endloop + endfacet + facet normal -0.868008 -0.41494 0.272741 + outer loop + vertex -679.842 162.717 87.128 + vertex -679.953 161.798 85.376 + vertex -678.176 159.184 87.0532 + endloop + endfacet + facet normal -0.867969 -0.423855 0.2588 + outer loop + vertex -678.176 159.184 87.0532 + vertex -679.953 161.798 85.376 + vertex -678.409 158.521 85.1882 + endloop + endfacet + facet normal -0.864791 -0.423029 0.270525 + outer loop + vertex -679.953 161.798 85.376 + vertex -680.234 161.19 83.527 + vertex -678.409 158.521 85.1882 + endloop + endfacet + facet normal -0.864806 -0.425318 0.266863 + outer loop + vertex -678.409 158.521 85.1882 + vertex -680.234 161.19 83.527 + vertex -678.732 157.997 83.3072 + endloop + endfacet + facet normal -0.858202 -0.370938 0.354817 + outer loop + vertex -683.737 162.178 74.5974 + vertex -684.28 161.687 72.7703 + vertex -682.32 158.704 74.3925 + endloop + endfacet + facet normal -0.858872 -0.374062 0.349882 + outer loop + vertex -682.32 158.704 74.3925 + vertex -684.28 161.687 72.7703 + vertex -682.854 158.21 72.5535 + endloop + endfacet + facet normal -0.866001 -0.371162 0.335084 + outer loop + vertex -683.249 162.671 76.4049 + vertex -683.737 162.178 74.5974 + vertex -681.84 159.203 76.204 + endloop + endfacet + facet normal -0.866345 -0.372927 0.332222 + outer loop + vertex -681.84 159.203 76.204 + vertex -683.737 162.178 74.5974 + vertex -682.32 158.704 74.3925 + endloop + endfacet + facet normal -0.838473 -0.426235 0.339538 + outer loop + vertex -681.84 159.203 76.204 + vertex -682.32 158.704 74.3925 + vertex -680.306 156.015 75.99 + endloop + endfacet + facet normal -0.838714 -0.428388 0.336217 + outer loop + vertex -680.306 156.015 75.99 + vertex -682.32 158.704 74.3925 + vertex -680.779 155.508 74.1649 + endloop + endfacet + facet normal -0.831569 -0.42635 0.355977 + outer loop + vertex -682.32 158.704 74.3925 + vertex -682.854 158.21 72.5535 + vertex -680.779 155.508 74.1649 + endloop + endfacet + facet normal -0.8318 -0.428127 0.353293 + outer loop + vertex -680.779 155.508 74.1649 + vertex -682.854 158.21 72.5535 + vertex -681.31 155.005 72.3059 + endloop + endfacet + facet normal -0.872211 -0.371782 0.317846 + outer loop + vertex -682.801 163.162 78.2074 + vertex -683.249 162.671 76.4049 + vertex -681.402 159.707 78.0059 + endloop + endfacet + facet normal -0.872364 -0.372664 0.316391 + outer loop + vertex -681.402 159.707 78.0059 + vertex -683.249 162.671 76.4049 + vertex -681.84 159.203 76.204 + endloop + endfacet + facet normal -0.877641 -0.372611 0.30151 + outer loop + vertex -682.381 163.643 80.024 + vertex -682.801 163.162 78.2074 + vertex -680.99 160.199 79.8195 + endloop + endfacet + facet normal -0.877701 -0.373014 0.300836 + outer loop + vertex -680.99 160.199 79.8195 + vertex -682.801 163.162 78.2074 + vertex -681.402 159.707 78.0059 + endloop + endfacet + facet normal -0.850627 -0.425445 0.308919 + outer loop + vertex -680.99 160.199 79.8195 + vertex -681.402 159.707 78.0059 + vertex -679.482 157.034 79.6115 + endloop + endfacet + facet normal -0.850769 -0.427487 0.30569 + outer loop + vertex -679.482 157.034 79.6115 + vertex -681.402 159.707 78.0059 + vertex -679.88 156.529 77.7985 + endloop + endfacet + facet normal -0.84464 -0.425778 0.324493 + outer loop + vertex -681.402 159.707 78.0059 + vertex -681.84 159.203 76.204 + vertex -679.88 156.529 77.7985 + endloop + endfacet + facet normal -0.84485 -0.428055 0.320933 + outer loop + vertex -679.88 156.529 77.7985 + vertex -681.84 159.203 76.204 + vertex -680.306 156.015 75.99 + endloop + endfacet + facet normal -0.758146 -0.507453 0.40952 + outer loop + vertex -680.519 147.256 64.3659 + vertex -679.147 148.321 68.2255 + vertex -680.68 148.765 65.9386 + endloop + endfacet + facet normal -0.774838 -0.507072 0.377498 + outer loop + vertex -679.147 148.321 68.2255 + vertex -678.188 149.356 71.5836 + vertex -679.417 149.764 69.6097 + endloop + endfacet + facet normal -0.82223 -0.369831 0.432624 + outer loop + vertex -686.227 160.286 67.2635 + vertex -686.953 159.869 65.5274 + vertex -684.796 156.76 66.9699 + endloop + endfacet + facet normal -0.822602 -0.370805 0.43108 + outer loop + vertex -684.796 156.76 66.9699 + vertex -686.953 159.869 65.5274 + vertex -685.524 156.325 65.2066 + endloop + endfacet + facet normal -0.832333 -0.370487 0.412263 + outer loop + vertex -685.53 160.736 69.0749 + vertex -686.227 160.286 67.2635 + vertex -684.099 157.226 68.8107 + endloop + endfacet + facet normal -0.832885 -0.372236 0.409565 + outer loop + vertex -684.099 157.226 68.8107 + vertex -686.227 160.286 67.2635 + vertex -684.796 156.76 66.9699 + endloop + endfacet + facet normal -0.806116 -0.4242 0.412592 + outer loop + vertex -684.099 157.226 68.8107 + vertex -684.796 156.76 66.9699 + vertex -682.543 153.988 68.5215 + endloop + endfacet + facet normal -0.806458 -0.425748 0.410323 + outer loop + vertex -682.543 153.988 68.5215 + vertex -684.796 156.76 66.9699 + vertex -683.238 153.514 66.664 + endloop + endfacet + facet normal -0.796048 -0.422887 0.432983 + outer loop + vertex -684.796 156.76 66.9699 + vertex -685.524 156.325 65.2066 + vertex -683.238 153.514 66.664 + endloop + endfacet + facet normal -0.796626 -0.424973 0.429867 + outer loop + vertex -683.238 153.514 66.664 + vertex -685.524 156.325 65.2066 + vertex -683.956 153.067 64.8906 + endloop + endfacet + facet normal -0.841498 -0.370693 0.393024 + outer loop + vertex -684.876 161.21 70.9231 + vertex -685.53 160.736 69.0749 + vertex -683.447 157.715 70.6862 + endloop + endfacet + facet normal -0.842055 -0.372766 0.389858 + outer loop + vertex -683.447 157.715 70.6862 + vertex -685.53 160.736 69.0749 + vertex -684.099 157.226 68.8107 + endloop + endfacet + facet normal -0.850962 -0.372114 0.370667 + outer loop + vertex -684.28 161.687 72.7703 + vertex -684.876 161.21 70.9231 + vertex -682.854 158.21 72.5535 + endloop + endfacet + facet normal -0.85118 -0.373039 0.369235 + outer loop + vertex -682.854 158.21 72.5535 + vertex -684.876 161.21 70.9231 + vertex -683.447 157.715 70.6862 + endloop + endfacet + facet normal -0.823657 -0.425841 0.374499 + outer loop + vertex -682.854 158.21 72.5535 + vertex -683.447 157.715 70.6862 + vertex -681.31 155.005 72.3059 + endloop + endfacet + facet normal -0.82391 -0.427525 0.372015 + outer loop + vertex -681.31 155.005 72.3059 + vertex -683.447 157.715 70.6862 + vertex -681.898 154.495 70.4172 + endloop + endfacet + facet normal -0.814907 -0.425034 0.394046 + outer loop + vertex -683.447 157.715 70.6862 + vertex -684.099 157.226 68.8107 + vertex -681.898 154.495 70.4172 + endloop + endfacet + facet normal -0.815204 -0.426695 0.391629 + outer loop + vertex -681.898 154.495 70.4172 + vertex -684.099 157.226 68.8107 + vertex -682.543 153.988 68.5215 + endloop + endfacet + facet normal -0.718591 -0.485895 0.497526 + outer loop + vertex -683.801 145.641 57.6336 + vertex -682.132 146.275 60.664 + vertex -683.678 146.955 59.0953 + endloop + endfacet + facet normal -0.739813 -0.496554 0.453995 + outer loop + vertex -682.132 146.275 60.664 + vertex -680.519 147.256 64.3659 + vertex -682.105 147.818 62.3956 + endloop + endfacet + facet normal -0.770712 -0.360819 0.525178 + outer loop + vertex -689.298 158.86 60.7978 + vertex -690.197 158.565 59.2751 + vertex -687.865 155.233 60.4091 + endloop + endfacet + facet normal -0.772528 -0.363676 0.520518 + outer loop + vertex -687.865 155.233 60.4091 + vertex -690.197 158.565 59.2751 + vertex -688.762 154.916 58.8554 + endloop + endfacet + facet normal -0.787435 -0.365045 0.496677 + outer loop + vertex -688.476 159.161 62.3212 + vertex -689.298 158.86 60.7978 + vertex -687.042 155.573 61.9584 + endloop + endfacet + facet normal -0.78701 -0.364332 0.497872 + outer loop + vertex -687.042 155.573 61.9584 + vertex -689.298 158.86 60.7978 + vertex -687.865 155.233 60.4091 + endloop + endfacet + facet normal -0.760969 -0.418376 0.495871 + outer loop + vertex -687.042 155.573 61.9584 + vertex -687.865 155.233 60.4091 + vertex -685.451 152.27 61.6129 + endloop + endfacet + facet normal -0.762002 -0.420648 0.49235 + outer loop + vertex -685.451 152.27 61.6129 + vertex -687.865 155.233 60.4091 + vertex -686.259 151.887 60.035 + endloop + endfacet + facet normal -0.747759 -0.416574 0.517033 + outer loop + vertex -687.865 155.233 60.4091 + vertex -688.762 154.916 58.8554 + vertex -686.259 151.887 60.035 + endloop + endfacet + facet normal -0.748771 -0.418634 0.513894 + outer loop + vertex -686.259 151.887 60.035 + vertex -688.762 154.916 58.8554 + vertex -687.152 151.529 58.4413 + endloop + endfacet + facet normal -0.799385 -0.366495 0.476093 + outer loop + vertex -687.699 159.498 63.8864 + vertex -688.476 159.161 62.3212 + vertex -686.269 155.934 63.5433 + endloop + endfacet + facet normal -0.800084 -0.367801 0.473907 + outer loop + vertex -686.269 155.934 63.5433 + vertex -688.476 159.161 62.3212 + vertex -687.042 155.573 61.9584 + endloop + endfacet + facet normal -0.812229 -0.368532 0.452183 + outer loop + vertex -686.953 159.869 65.5274 + vertex -687.699 159.498 63.8864 + vertex -685.524 156.325 65.2066 + endloop + endfacet + facet normal -0.812613 -0.369367 0.450807 + outer loop + vertex -685.524 156.325 65.2066 + vertex -687.699 159.498 63.8864 + vertex -686.269 155.934 63.5433 + endloop + endfacet + facet normal -0.786221 -0.422051 0.451364 + outer loop + vertex -685.524 156.325 65.2066 + vertex -686.269 155.934 63.5433 + vertex -683.956 153.067 64.8906 + endloop + endfacet + facet normal -0.786802 -0.423745 0.448758 + outer loop + vertex -683.956 153.067 64.8906 + vertex -686.269 155.934 63.5433 + vertex -684.689 152.654 63.2155 + endloop + endfacet + facet normal -0.774273 -0.42016 0.473252 + outer loop + vertex -686.269 155.934 63.5433 + vertex -687.042 155.573 61.9584 + vertex -684.689 152.654 63.2155 + endloop + endfacet + facet normal -0.775221 -0.422493 0.469608 + outer loop + vertex -684.689 152.654 63.2155 + vertex -687.042 155.573 61.9584 + vertex -685.451 152.27 61.6129 + endloop + endfacet + facet normal -0.670049 -0.466716 0.577244 + outer loop + vertex -688.102 144.007 51.0275 + vertex -685.595 144.859 54.6271 + vertex -687.837 145.593 52.6172 + endloop + endfacet + facet normal -0.697148 -0.472952 0.538796 + outer loop + vertex -685.595 144.859 54.6271 + vertex -683.801 145.641 57.6336 + vertex -685.542 146.212 55.883 + endloop + endfacet + facet normal -0.697639 -0.350756 0.624716 + outer loop + vertex -693.348 157.968 54.8187 + vertex -694.474 157.88 53.5113 + vertex -691.943 154.207 54.2765 + endloop + endfacet + facet normal -0.697736 -0.350858 0.624551 + outer loop + vertex -691.943 154.207 54.2765 + vertex -694.474 157.88 53.5113 + vertex -693.1 154.106 52.9261 + endloop + endfacet + facet normal -0.721101 -0.354705 0.595145 + outer loop + vertex -692.236 158.104 56.2467 + vertex -693.348 157.968 54.8187 + vertex -690.817 154.374 55.7436 + endloop + endfacet + facet normal -0.721603 -0.355308 0.594176 + outer loop + vertex -690.817 154.374 55.7436 + vertex -693.348 157.968 54.8187 + vertex -691.943 154.207 54.2765 + endloop + endfacet + facet normal -0.701065 -0.408542 0.584466 + outer loop + vertex -690.817 154.374 55.7436 + vertex -691.943 154.207 54.2765 + vertex -689.207 150.902 55.2474 + endloop + endfacet + facet normal -0.7007 -0.408001 0.585282 + outer loop + vertex -689.207 150.902 55.2474 + vertex -691.943 154.207 54.2765 + vertex -690.354 150.701 53.7342 + endloop + endfacet + facet normal -0.679703 -0.402774 0.613006 + outer loop + vertex -691.943 154.207 54.2765 + vertex -693.1 154.106 52.9261 + vertex -690.354 150.701 53.7342 + endloop + endfacet + facet normal -0.678959 -0.401833 0.614447 + outer loop + vertex -690.354 150.701 53.7342 + vertex -693.1 154.106 52.9261 + vertex -691.545 150.553 52.3211 + endloop + endfacet + facet normal -0.739499 -0.357107 0.570627 + outer loop + vertex -691.176 158.309 57.7494 + vertex -692.236 158.104 56.2467 + vertex -689.749 154.618 57.2886 + endloop + endfacet + facet normal -0.740521 -0.358493 0.568429 + outer loop + vertex -689.749 154.618 57.2886 + vertex -692.236 158.104 56.2467 + vertex -690.817 154.374 55.7436 + endloop + endfacet + facet normal -0.756548 -0.360292 0.545733 + outer loop + vertex -690.197 158.565 59.2751 + vertex -691.176 158.309 57.7494 + vertex -688.762 154.916 58.8554 + endloop + endfacet + facet normal -0.756763 -0.36061 0.545225 + outer loop + vertex -688.762 154.916 58.8554 + vertex -691.176 158.309 57.7494 + vertex -689.749 154.618 57.2886 + endloop + endfacet + facet normal -0.732585 -0.414156 0.54018 + outer loop + vertex -688.762 154.916 58.8554 + vertex -689.749 154.618 57.2886 + vertex -687.152 151.529 58.4413 + endloop + endfacet + facet normal -0.733859 -0.416568 0.536583 + outer loop + vertex -687.152 151.529 58.4413 + vertex -689.749 154.618 57.2886 + vertex -688.138 151.194 56.8333 + endloop + endfacet + facet normal -0.717741 -0.412254 0.561155 + outer loop + vertex -689.749 154.618 57.2886 + vertex -690.817 154.374 55.7436 + vertex -688.138 151.194 56.8333 + endloop + endfacet + facet normal -0.718168 -0.412985 0.56007 + outer loop + vertex -688.138 151.194 56.8333 + vertex -690.817 154.374 55.7436 + vertex -689.207 150.902 55.2474 + endloop + endfacet + facet normal -0.782566 -0.059722 0.619696 + outer loop + vertex -696.762 192.451 58.5906 + vertex -698.698 192.447 56.1445 + vertex -696.498 182.597 57.9743 + endloop + endfacet + facet normal -0.768748 -0.0533603 0.637322 + outer loop + vertex -696.498 182.597 57.9743 + vertex -698.698 192.447 56.1445 + vertex -698.531 182.701 55.5298 + endloop + endfacet + facet normal -0.821066 -0.0612717 0.567536 + outer loop + vertex -694.865 192.713 61.3634 + vertex -696.762 192.451 58.5906 + vertex -694.549 182.915 60.7613 + endloop + endfacet + facet normal -0.815136 -0.0578848 0.57637 + outer loop + vertex -694.549 182.915 60.7613 + vertex -696.762 192.451 58.5906 + vertex -696.498 182.597 57.9743 + endloop + endfacet + facet normal -0.798615 -0.00570898 0.601815 + outer loop + vertex -696.77 210.176 59.0944 + vertex -698.238 208.888 57.1333 + vertex -696.782 201.524 58.9958 + endloop + endfacet + facet normal -0.793817 -0.00315845 0.608149 + outer loop + vertex -696.782 201.524 58.9958 + vertex -698.238 208.888 57.1333 + vertex -698.608 201.816 56.6139 + endloop + endfacet + facet normal -0.830979 -0.00559373 0.556276 + outer loop + vertex -694.968 210.9 61.7934 + vertex -696.77 210.176 59.0944 + vertex -694.968 202.005 61.7036 + endloop + endfacet + facet normal -0.830351 -0.00515443 0.557217 + outer loop + vertex -694.968 202.005 61.7036 + vertex -696.77 210.176 59.0944 + vertex -696.782 201.524 58.9958 + endloop + endfacet + facet normal -0.827968 -0.0297231 0.559987 + outer loop + vertex -694.968 202.005 61.7036 + vertex -696.782 201.524 58.9958 + vertex -694.865 192.713 61.3634 + endloop + endfacet + facet normal -0.823823 -0.0271525 0.566197 + outer loop + vertex -694.865 192.713 61.3634 + vertex -696.782 201.524 58.9958 + vertex -696.762 192.451 58.5906 + endloop + endfacet + facet normal -0.795007 -0.0288607 0.605913 + outer loop + vertex -696.782 201.524 58.9958 + vertex -698.608 201.816 56.6139 + vertex -696.762 192.451 58.5906 + endloop + endfacet + facet normal -0.783778 -0.0235478 0.620595 + outer loop + vertex -696.762 192.451 58.5906 + vertex -698.608 201.816 56.6139 + vertex -698.698 192.447 56.1445 + endloop + endfacet + facet normal -0.799228 0.00973233 0.600949 + outer loop + vertex -696.703 227.627 58.9376 + vertex -698.255 225.804 56.9026 + vertex -696.746 218.854 59.0222 + endloop + endfacet + facet normal -0.797161 0.0110101 0.603666 + outer loop + vertex -696.746 218.854 59.0222 + vertex -698.255 225.804 56.9026 + vertex -698.486 217.617 56.7472 + endloop + endfacet + facet normal -0.833299 0.00928224 0.552745 + outer loop + vertex -694.855 228.303 61.7124 + vertex -696.703 227.627 58.9376 + vertex -694.917 219.626 61.7645 + endloop + endfacet + facet normal -0.833092 0.00943726 0.553054 + outer loop + vertex -694.917 219.626 61.7645 + vertex -696.703 227.627 58.9376 + vertex -696.746 218.854 59.0222 + endloop + endfacet + facet normal -0.832752 0.00666493 0.553607 + outer loop + vertex -694.917 219.626 61.7645 + vertex -696.746 218.854 59.0222 + vertex -694.968 210.9 61.7934 + endloop + endfacet + facet normal -0.832513 0.0068423 0.553963 + outer loop + vertex -694.968 210.9 61.7934 + vertex -696.746 218.854 59.0222 + vertex -696.77 210.176 59.0944 + endloop + endfacet + facet normal -0.796186 0.00716989 0.605009 + outer loop + vertex -696.746 218.854 59.0222 + vertex -698.486 217.617 56.7472 + vertex -696.77 210.176 59.0944 + endloop + endfacet + facet normal -0.801581 0.00367488 0.597875 + outer loop + vertex -696.77 210.176 59.0944 + vertex -698.486 217.617 56.7472 + vertex -698.238 208.888 57.1333 + endloop + endfacet + facet normal -0.806689 0.00186998 0.590973 + outer loop + vertex -696.646 245.114 58.8969 + vertex -698.156 243.929 56.8386 + vertex -696.656 236.413 58.9102 + endloop + endfacet + facet normal -0.798 0.00681372 0.602618 + outer loop + vertex -696.656 236.413 58.9102 + vertex -698.156 243.929 56.8386 + vertex -698.462 235.325 56.5305 + endloop + endfacet + facet normal -0.838712 -0.00069675 0.544575 + outer loop + vertex -694.85 245.462 61.6628 + vertex -696.646 245.114 58.8969 + vertex -694.828 236.906 61.6851 + endloop + endfacet + facet normal -0.835286 0.00184083 0.549813 + outer loop + vertex -694.828 236.906 61.6851 + vertex -696.646 245.114 58.8969 + vertex -696.656 236.413 58.9102 + endloop + endfacet + facet normal -0.835483 0.00433301 0.549499 + outer loop + vertex -694.828 236.906 61.6851 + vertex -696.656 236.413 58.9102 + vertex -694.855 228.303 61.7124 + endloop + endfacet + facet normal -0.832972 0.00619712 0.55328 + outer loop + vertex -694.855 228.303 61.7124 + vertex -696.656 236.413 58.9102 + vertex -696.703 227.627 58.9376 + endloop + endfacet + facet normal -0.797861 0.00616292 0.60281 + outer loop + vertex -696.656 236.413 58.9102 + vertex -698.462 235.325 56.5305 + vertex -696.703 227.627 58.9376 + endloop + endfacet + facet normal -0.797751 0.0062336 0.602955 + outer loop + vertex -696.703 227.627 58.9376 + vertex -698.462 235.325 56.5305 + vertex -698.255 225.804 56.9026 + endloop + endfacet + facet normal -0.818809 -0.00613771 0.574033 + outer loop + vertex -696.731 262.565 58.9093 + vertex -698.2 261.474 56.8033 + vertex -696.678 253.741 58.8918 + endloop + endfacet + facet normal -0.808387 -0.000138506 0.588651 + outer loop + vertex -696.678 253.741 58.8918 + vertex -698.2 261.474 56.8033 + vertex -698.401 253.311 56.5245 + endloop + endfacet + facet normal -0.850223 -0.0116829 0.526293 + outer loop + vertex -694.946 263.399 61.8115 + vertex -696.731 262.565 58.9093 + vertex -694.901 254.182 61.6805 + endloop + endfacet + facet normal -0.842915 -0.00621309 0.538011 + outer loop + vertex -694.901 254.182 61.6805 + vertex -696.731 262.565 58.9093 + vertex -696.678 253.741 58.8918 + endloop + endfacet + facet normal -0.84293 -0.00601709 0.53799 + outer loop + vertex -694.901 254.182 61.6805 + vertex -696.678 253.741 58.8918 + vertex -694.85 245.462 61.6628 + endloop + endfacet + facet normal -0.838589 -0.00279335 0.544758 + outer loop + vertex -694.85 245.462 61.6628 + vertex -696.678 253.741 58.8918 + vertex -696.646 245.114 58.8969 + endloop + endfacet + facet normal -0.808167 -0.00265427 0.588947 + outer loop + vertex -696.678 253.741 58.8918 + vertex -698.401 253.311 56.5245 + vertex -696.646 245.114 58.8969 + endloop + endfacet + facet normal -0.805838 -0.00123272 0.592135 + outer loop + vertex -696.646 245.114 58.8969 + vertex -698.401 253.311 56.5245 + vertex -698.156 243.929 56.8386 + endloop + endfacet + facet normal -0.834893 -0.0110401 0.550301 + outer loop + vertex -696.933 280.954 58.9507 + vertex -698.333 279.259 56.7927 + vertex -696.804 271.732 58.9605 + endloop + endfacet + facet normal -0.824546 -0.00448164 0.565776 + outer loop + vertex -696.804 271.732 58.9605 + vertex -698.333 279.259 56.7927 + vertex -698.489 270.908 56.4991 + endloop + endfacet + facet normal -0.870581 -0.0168292 0.491738 + outer loop + vertex -695.414 282.561 61.6948 + vertex -696.933 280.954 58.9507 + vertex -695.018 273.375 62.0804 + endloop + endfacet + facet normal -0.86519 -0.0115142 0.501311 + outer loop + vertex -695.018 273.375 62.0804 + vertex -696.933 280.954 58.9507 + vertex -696.804 271.732 58.9605 + endloop + endfacet + facet normal -0.863169 -0.0198186 0.504526 + outer loop + vertex -695.018 273.375 62.0804 + vertex -696.804 271.732 58.9605 + vertex -694.946 263.399 61.8115 + endloop + endfacet + facet normal -0.850499 -0.0096849 0.525888 + outer loop + vertex -694.946 263.399 61.8115 + vertex -696.804 271.732 58.9605 + vertex -696.731 262.565 58.9093 + endloop + endfacet + facet normal -0.823699 -0.00970138 0.566945 + outer loop + vertex -696.804 271.732 58.9605 + vertex -698.489 270.908 56.4991 + vertex -696.731 262.565 58.9093 + endloop + endfacet + facet normal -0.818704 -0.00655957 0.574179 + outer loop + vertex -696.731 262.565 58.9093 + vertex -698.489 270.908 56.4991 + vertex -698.2 261.474 56.8033 + endloop + endfacet + facet normal -0.852541 -0.0146435 0.522454 + outer loop + vertex -697.156 298.824 59.0748 + vertex -698.513 296.981 56.8094 + vertex -697.035 289.919 59.023 + endloop + endfacet + facet normal -0.842566 -0.00751487 0.53854 + outer loop + vertex -697.035 289.919 59.023 + vertex -698.513 296.981 56.8094 + vertex -698.658 288.698 56.4676 + endloop + endfacet + facet normal -0.887367 -0.0177587 0.460722 + outer loop + vertex -695.698 300.585 61.9524 + vertex -697.156 298.824 59.0748 + vertex -695.244 290.981 62.4549 + endloop + endfacet + facet normal -0.884593 -0.0147521 0.46613 + outer loop + vertex -695.244 290.981 62.4549 + vertex -697.156 298.824 59.0748 + vertex -697.035 289.919 59.023 + endloop + endfacet + facet normal -0.883169 -0.0245263 0.468413 + outer loop + vertex -695.244 290.981 62.4549 + vertex -697.035 289.919 59.023 + vertex -695.414 282.561 61.6948 + endloop + endfacet + facet normal -0.871353 -0.013917 0.49046 + outer loop + vertex -695.414 282.561 61.6948 + vertex -697.035 289.919 59.023 + vertex -696.933 280.954 58.9507 + endloop + endfacet + facet normal -0.841102 -0.0139765 0.540696 + outer loop + vertex -697.035 289.919 59.023 + vertex -698.658 288.698 56.4676 + vertex -696.933 280.954 58.9507 + endloop + endfacet + facet normal -0.835344 -0.00982641 0.54964 + outer loop + vertex -696.933 280.954 58.9507 + vertex -698.658 288.698 56.4676 + vertex -698.333 279.259 56.7927 + endloop + endfacet + facet normal -0.868312 -0.0190383 0.495652 + outer loop + vertex -697.469 315.914 59.1503 + vertex -698.755 314.154 56.8297 + vertex -697.303 307.531 59.1188 + endloop + endfacet + facet normal -0.858522 -0.0110147 0.512659 + outer loop + vertex -697.303 307.531 59.1188 + vertex -698.755 314.154 56.8297 + vertex -698.848 306.138 56.5019 + endloop + endfacet + facet normal -0.899879 -0.0205731 0.435655 + outer loop + vertex -696.095 317.613 62.0685 + vertex -697.469 315.914 59.1503 + vertex -695.602 308.688 62.6646 + endloop + endfacet + facet normal -0.898989 -0.0194267 0.43754 + outer loop + vertex -695.602 308.688 62.6646 + vertex -697.469 315.914 59.1503 + vertex -697.303 307.531 59.1188 + endloop + endfacet + facet normal -0.89768 -0.0281187 0.43975 + outer loop + vertex -695.602 308.688 62.6646 + vertex -697.303 307.531 59.1188 + vertex -695.698 300.585 61.9524 + endloop + endfacet + facet normal -0.88749 -0.017297 0.460502 + outer loop + vertex -695.698 300.585 61.9524 + vertex -697.303 307.531 59.1188 + vertex -697.156 298.824 59.0748 + endloop + endfacet + facet normal -0.857025 -0.0170586 0.514993 + outer loop + vertex -697.303 307.531 59.1188 + vertex -698.848 306.138 56.5019 + vertex -697.156 298.824 59.0748 + endloop + endfacet + facet normal -0.852904 -0.0136798 0.521888 + outer loop + vertex -697.156 298.824 59.0748 + vertex -698.848 306.138 56.5019 + vertex -698.513 296.981 56.8094 + endloop + endfacet + facet normal -0.881601 -0.0213033 0.471514 + outer loop + vertex -697.904 332.761 59.0904 + vertex -699.108 330.883 56.7551 + vertex -697.666 324.141 59.1459 + endloop + endfacet + facet normal -0.873527 -0.0142386 0.486567 + outer loop + vertex -697.666 324.141 59.1459 + vertex -699.108 330.883 56.7551 + vertex -699.131 322.949 56.4825 + endloop + endfacet + facet normal -0.909005 -0.0224097 0.416182 + outer loop + vertex -696.607 334.634 62.0257 + vertex -697.904 332.761 59.0904 + vertex -696.066 325.434 62.7122 + endloop + endfacet + facet normal -0.90901 -0.0224163 0.416171 + outer loop + vertex -696.066 325.434 62.7122 + vertex -697.904 332.761 59.0904 + vertex -697.666 324.141 59.1459 + endloop + endfacet + facet normal -0.907609 -0.0310346 0.418667 + outer loop + vertex -696.066 325.434 62.7122 + vertex -697.666 324.141 59.1459 + vertex -696.095 317.613 62.0685 + endloop + endfacet + facet normal -0.899684 -0.0213579 0.43602 + outer loop + vertex -696.095 317.613 62.0685 + vertex -697.666 324.141 59.1459 + vertex -697.469 315.914 59.1503 + endloop + endfacet + facet normal -0.872198 -0.0206697 0.488715 + outer loop + vertex -697.666 324.141 59.1459 + vertex -699.131 322.949 56.4825 + vertex -697.469 315.914 59.1503 + endloop + endfacet + facet normal -0.868822 -0.0175596 0.494813 + outer loop + vertex -697.469 315.914 59.1503 + vertex -699.131 322.949 56.4825 + vertex -698.755 314.154 56.8297 + endloop + endfacet + facet normal -0.898236 -0.0264939 0.438715 + outer loop + vertex -698.344 354.108 59.3723 + vertex -699.932 354.095 56.12 + vertex -698.193 342.768 58.9974 + endloop + endfacet + facet normal -0.885272 -0.0178945 0.46473 + outer loop + vertex -698.193 342.768 58.9974 + vertex -699.932 354.095 56.12 + vertex -699.596 340.878 56.2519 + endloop + endfacet + facet normal -0.92152 -0.0291175 0.387237 + outer loop + vertex -697.026 352.647 62.3979 + vertex -698.344 354.108 59.3723 + vertex -696.611 343.488 62.6979 + endloop + endfacet + facet normal -0.917439 -0.0253734 0.397067 + outer loop + vertex -696.611 343.488 62.6979 + vertex -698.344 354.108 59.3723 + vertex -698.193 342.768 58.9974 + endloop + endfacet + facet normal -0.916927 -0.030657 0.397875 + outer loop + vertex -696.611 343.488 62.6979 + vertex -698.193 342.768 58.9974 + vertex -696.607 334.634 62.0257 + endloop + endfacet + facet normal -0.909029 -0.0223194 0.416135 + outer loop + vertex -696.607 334.634 62.0257 + vertex -698.193 342.768 58.9974 + vertex -697.904 332.761 59.0904 + endloop + endfacet + facet normal -0.884289 -0.0211393 0.466462 + outer loop + vertex -698.193 342.768 58.9974 + vertex -699.596 340.878 56.2519 + vertex -697.904 332.761 59.0904 + endloop + endfacet + facet normal -0.882286 -0.0193743 0.470315 + outer loop + vertex -697.904 332.761 59.0904 + vertex -699.596 340.878 56.2519 + vertex -699.108 330.883 56.7551 + endloop + endfacet + facet normal -0.898005 -0.0344732 0.438634 + outer loop + vertex -699.932 354.095 56.12 + vertex -698.344 354.108 59.3723 + vertex -700.342 368.985 56.4521 + endloop + endfacet + facet normal -0.923972 -0.0473055 0.379523 + outer loop + vertex -697.026 352.647 62.3979 + vertex -698.141 366.116 61.363 + vertex -698.344 354.108 59.3723 + endloop + endfacet + facet normal -0.921731 -0.0482216 0.384821 + outer loop + vertex -698.141 366.116 61.363 + vertex -700.342 368.985 56.4521 + vertex -698.344 354.108 59.3723 + endloop + endfacet + facet normal -0.928912 -0.0661488 0.364344 + outer loop + vertex -699.309 386.648 62.1142 + vertex -701.478 386.658 56.5844 + vertex -698.141 366.116 61.363 + endloop + endfacet + facet normal -0.923879 -0.0622507 0.377587 + outer loop + vertex -698.141 366.116 61.363 + vertex -701.478 386.658 56.5844 + vertex -700.342 368.985 56.4521 + endloop + endfacet + facet normal -0.559375 -0.494529 0.665237 + outer loop + vertex -692.094 144.153 47.3254 + vertex -692.457 143.896 46.829 + vertex -691.127 143.224 47.4478 + endloop + endfacet + facet normal -0.548697 -0.49787 0.671608 + outer loop + vertex -692.875 143.93 46.5123 + vertex -692.183 143.191 46.5295 + vertex -692.457 143.896 46.829 + endloop + endfacet + facet normal -0.559786 -0.498162 0.662174 + outer loop + vertex -692.183 143.191 46.5295 + vertex -691.127 143.224 47.4478 + vertex -692.457 143.896 46.829 + endloop + endfacet + facet normal -0.58606 -0.487601 0.647131 + outer loop + vertex -690.759 144.495 48.7634 + vertex -691.316 144.132 47.9859 + vertex -689.974 143.648 48.8366 + endloop + endfacet + facet normal -0.566852 -0.504111 0.651575 + outer loop + vertex -692.094 144.153 47.3254 + vertex -691.127 143.224 47.4478 + vertex -691.316 144.132 47.9859 + endloop + endfacet + facet normal -0.585059 -0.500116 0.638427 + outer loop + vertex -691.127 143.224 47.4478 + vertex -689.974 143.648 48.8366 + vertex -691.316 144.132 47.9859 + endloop + endfacet + facet normal -0.577575 -0.511977 0.635835 + outer loop + vertex -689.974 143.648 48.8366 + vertex -691.127 143.224 47.4478 + vertex -689.744 142.986 48.5123 + endloop + endfacet + facet normal -0.576175 -0.517238 0.632841 + outer loop + vertex -689.744 142.986 48.5123 + vertex -691.127 143.224 47.4478 + vertex -691.034 142.711 47.1131 + endloop + endfacet + facet normal -0.54918 -0.524141 0.650905 + outer loop + vertex -691.127 143.224 47.4478 + vertex -692.183 143.191 46.5295 + vertex -691.034 142.711 47.1131 + endloop + endfacet + facet normal -0.548812 -0.50138 0.668897 + outer loop + vertex -691.034 142.711 47.1131 + vertex -692.183 143.191 46.5295 + vertex -691.939 142.755 46.4032 + endloop + endfacet + facet normal -0.594423 -0.496625 0.632475 + outer loop + vertex -690.759 144.495 48.7634 + vertex -689.974 143.648 48.8366 + vertex -689.913 144.79 49.7904 + endloop + endfacet + facet normal -0.611508 -0.50902 0.60577 + outer loop + vertex -689.744 142.986 48.5123 + vertex -688.102 144.007 51.0275 + vertex -689.974 143.648 48.8366 + endloop + endfacet + facet normal -0.626872 -0.479536 0.614066 + outer loop + vertex -689.913 144.79 49.7904 + vertex -689.974 143.648 48.8366 + vertex -688.102 144.007 51.0275 + endloop + endfacet + facet normal -0.60095 -0.328751 0.728547 + outer loop + vertex -697.616 157.908 50.5079 + vertex -698.318 157.905 49.9276 + vertex -696.326 153.861 49.7455 + endloop + endfacet + facet normal -0.581766 -0.320165 0.747691 + outer loop + vertex -696.326 153.861 49.7455 + vertex -698.318 157.905 49.9276 + vertex -697.123 153.947 49.1626 + endloop + endfacet + facet normal -0.624898 -0.335121 0.705122 + outer loop + vertex -696.67 157.885 51.3348 + vertex -697.616 157.908 50.5079 + vertex -695.348 153.916 50.6201 + endloop + endfacet + facet normal -0.618601 -0.331339 0.712424 + outer loop + vertex -695.348 153.916 50.6201 + vertex -697.616 157.908 50.5079 + vertex -696.326 153.861 49.7455 + endloop + endfacet + facet normal -0.602425 -0.387442 0.697835 + outer loop + vertex -695.348 153.916 50.6201 + vertex -696.326 153.861 49.7455 + vertex -693.725 149.874 49.7776 + endloop + endfacet + facet normal -0.600086 -0.385893 0.700702 + outer loop + vertex -693.725 149.874 49.7776 + vertex -696.326 153.861 49.7455 + vertex -694.895 149.951 48.8176 + endloop + endfacet + facet normal -0.572366 -0.381692 0.725747 + outer loop + vertex -696.326 153.861 49.7455 + vertex -697.123 153.947 49.1626 + vertex -694.895 149.951 48.8176 + endloop + endfacet + facet normal -0.565769 -0.378599 0.732508 + outer loop + vertex -694.895 149.951 48.8176 + vertex -697.123 153.947 49.1626 + vertex -695.915 150.52 48.3243 + endloop + endfacet + facet normal -0.649748 -0.341383 0.67918 + outer loop + vertex -695.597 157.853 52.3458 + vertex -696.67 157.885 51.3348 + vertex -694.26 154.026 51.7014 + endloop + endfacet + facet normal -0.6457 -0.338345 0.684539 + outer loop + vertex -694.26 154.026 51.7014 + vertex -696.67 157.885 51.3348 + vertex -695.348 153.916 50.6201 + endloop + endfacet + facet normal -0.671721 -0.346106 0.654982 + outer loop + vertex -694.474 157.88 53.5113 + vertex -695.597 157.853 52.3458 + vertex -693.1 154.106 52.9261 + endloop + endfacet + facet normal -0.670322 -0.34485 0.657075 + outer loop + vertex -693.1 154.106 52.9261 + vertex -695.597 157.853 52.3458 + vertex -694.26 154.026 51.7014 + endloop + endfacet + facet normal -0.653808 -0.395986 0.644772 + outer loop + vertex -693.1 154.106 52.9261 + vertex -694.26 154.026 51.7014 + vertex -691.545 150.553 52.3211 + endloop + endfacet + facet normal -0.654931 -0.397202 0.642881 + outer loop + vertex -691.545 150.553 52.3211 + vertex -694.26 154.026 51.7014 + vertex -692.708 150.34 51.0049 + endloop + endfacet + facet normal -0.628215 -0.391523 0.672351 + outer loop + vertex -694.26 154.026 51.7014 + vertex -695.348 153.916 50.6201 + vertex -692.708 150.34 51.0049 + endloop + endfacet + facet normal -0.629422 -0.392605 0.670589 + outer loop + vertex -692.708 150.34 51.0049 + vertex -695.348 153.916 50.6201 + vertex -693.725 149.874 49.7776 + endloop + endfacet + facet normal -0.597199 -0.465303 0.653335 + outer loop + vertex -692.288 147.383 49.4808 + vertex -691.418 145.88 49.2054 + vertex -691.236 147.087 50.2311 + endloop + endfacet + facet normal -0.599806 -0.487696 0.634339 + outer loop + vertex -690.759 144.495 48.7634 + vertex -689.913 144.79 49.7904 + vertex -691.418 145.88 49.2054 + endloop + endfacet + facet normal -0.593334 -0.467527 0.655266 + outer loop + vertex -689.913 144.79 49.7904 + vertex -691.236 147.087 50.2311 + vertex -691.418 145.88 49.2054 + endloop + endfacet + facet normal -0.575761 -0.461874 0.674665 + outer loop + vertex -692.942 147.45 48.9359 + vertex -693.357 147.022 48.2894 + vertex -692.004 145.513 48.4113 + endloop + endfacet + facet normal -0.581974 -0.468236 0.664877 + outer loop + vertex -692.004 145.513 48.4113 + vertex -693.357 147.022 48.2894 + vertex -692.673 145.419 47.7593 + endloop + endfacet + facet normal -0.594117 -0.464179 0.656934 + outer loop + vertex -692.288 147.383 49.4808 + vertex -692.942 147.45 48.9359 + vertex -691.418 145.88 49.2054 + endloop + endfacet + facet normal -0.595502 -0.465957 0.654416 + outer loop + vertex -691.418 145.88 49.2054 + vertex -692.942 147.45 48.9359 + vertex -692.004 145.513 48.4113 + endloop + endfacet + facet normal -0.581659 -0.485021 0.653014 + outer loop + vertex -691.418 145.88 49.2054 + vertex -692.004 145.513 48.4113 + vertex -690.759 144.495 48.7634 + endloop + endfacet + facet normal -0.584139 -0.490149 0.646943 + outer loop + vertex -690.759 144.495 48.7634 + vertex -692.004 145.513 48.4113 + vertex -691.316 144.132 47.9859 + endloop + endfacet + facet normal -0.572902 -0.488095 0.658443 + outer loop + vertex -692.004 145.513 48.4113 + vertex -692.673 145.419 47.7593 + vertex -691.316 144.132 47.9859 + endloop + endfacet + facet normal -0.572652 -0.487747 0.658918 + outer loop + vertex -691.316 144.132 47.9859 + vertex -692.673 145.419 47.7593 + vertex -692.094 144.153 47.3254 + endloop + endfacet + facet normal -0.569676 -0.461842 0.679832 + outer loop + vertex -694.197 147.535 47.9074 + vertex -694.747 147.61 47.4968 + vertex -693.281 145.418 47.2368 + endloop + endfacet + facet normal -0.571965 -0.463048 0.677084 + outer loop + vertex -693.281 145.418 47.2368 + vertex -694.747 147.61 47.4968 + vertex -693.605 145.22 46.8271 + endloop + endfacet + facet normal -0.586712 -0.468756 0.660332 + outer loop + vertex -693.357 147.022 48.2894 + vertex -694.197 147.535 47.9074 + vertex -692.673 145.419 47.7593 + endloop + endfacet + facet normal -0.577358 -0.462879 0.672607 + outer loop + vertex -692.673 145.419 47.7593 + vertex -694.197 147.535 47.9074 + vertex -693.281 145.418 47.2368 + endloop + endfacet + facet normal -0.568758 -0.487245 0.662651 + outer loop + vertex -692.673 145.419 47.7593 + vertex -693.281 145.418 47.2368 + vertex -692.094 144.153 47.3254 + endloop + endfacet + facet normal -0.5668 -0.485185 0.665833 + outer loop + vertex -692.094 144.153 47.3254 + vertex -693.281 145.418 47.2368 + vertex -692.457 143.896 46.829 + endloop + endfacet + facet normal -0.557652 -0.482758 0.675254 + outer loop + vertex -693.281 145.418 47.2368 + vertex -693.605 145.22 46.8271 + vertex -692.457 143.896 46.829 + endloop + endfacet + facet normal -0.553979 -0.479565 0.680533 + outer loop + vertex -692.457 143.896 46.829 + vertex -693.605 145.22 46.8271 + vertex -692.875 143.93 46.5123 + endloop + endfacet + facet normal -0.682162 -0.139766 0.717719 + outer loop + vertex -699.82 166.271 51.2676 + vertex -699.168 166.362 51.9045 + vertex -700.574 173.597 51.9771 + endloop + endfacet + facet normal -0.471534 -0.453662 0.756205 + outer loop + vertex -693.937 145.052 46.4657 + vertex -693.908 144.824 46.3474 + vertex -693.032 143.505 46.102 + endloop + endfacet + facet normal -0.525346 -0.469178 0.709847 + outer loop + vertex -694.128 145.137 46.3905 + vertex -693.48 143.77 45.967 + vertex -693.908 144.824 46.3474 + endloop + endfacet + facet normal -0.496078 -0.465619 0.732875 + outer loop + vertex -693.48 143.77 45.967 + vertex -693.032 143.505 46.102 + vertex -693.908 144.824 46.3474 + endloop + endfacet + facet normal 0.396193 0.351044 -0.84841 + outer loop + vertex -692.875 143.93 46.5123 + vertex -693.554 144.721 46.5226 + vertex -692.183 143.191 46.5295 + endloop + endfacet + facet normal -0.530338 -0.496352 0.687296 + outer loop + vertex -691.939 142.755 46.4032 + vertex -692.183 143.191 46.5295 + vertex -693.032 143.505 46.102 + endloop + endfacet + facet normal -0.512728 -0.469048 0.7191 + outer loop + vertex -693.937 145.052 46.4657 + vertex -693.032 143.505 46.102 + vertex -693.554 144.721 46.5226 + endloop + endfacet + facet normal -0.529973 -0.471524 0.704836 + outer loop + vertex -692.183 143.191 46.5295 + vertex -693.554 144.721 46.5226 + vertex -693.032 143.505 46.102 + endloop + endfacet + facet normal -0.742874 -0.0943712 -0.662746 + outer loop + vertex -698.853 157.86 49.4509 + vertex -698.875 158.03 49.4516 + vertex -697.653 153.872 48.6738 + endloop + endfacet + facet normal -0.911285 -0.200568 -0.359628 + outer loop + vertex -697.653 153.872 48.6738 + vertex -698.875 158.03 49.4516 + vertex -697.677 153.999 48.6642 + endloop + endfacet + facet normal -0.873511 -0.179605 -0.452461 + outer loop + vertex -698.857 157.816 49.477 + vertex -698.853 157.86 49.4509 + vertex -697.664 153.911 48.7228 + endloop + endfacet + facet normal -0.956166 -0.291994 0.0220496 + outer loop + vertex -697.664 153.911 48.7228 + vertex -698.853 157.86 49.4509 + vertex -697.653 153.872 48.6738 + endloop + endfacet + facet normal -0.924542 -0.369925 0.091533 + outer loop + vertex -697.664 153.911 48.7228 + vertex -697.653 153.872 48.6738 + vertex -696.313 150.326 47.8782 + endloop + endfacet + facet normal -0.888514 -0.390008 0.241737 + outer loop + vertex -696.313 150.326 47.8782 + vertex -697.653 153.872 48.6738 + vertex -696.288 150.229 47.8139 + endloop + endfacet + facet normal -0.84358 -0.198309 -0.499046 + outer loop + vertex -697.653 153.872 48.6738 + vertex -697.677 153.999 48.6642 + vertex -696.288 150.229 47.8139 + endloop + endfacet + facet normal -0.932516 -0.356565 0.0572326 + outer loop + vertex -696.288 150.229 47.8139 + vertex -697.677 153.999 48.6642 + vertex -696.325 150.325 47.805 + endloop + endfacet + facet normal -0.573762 -0.317405 0.755017 + outer loop + vertex -698.72 157.871 49.6043 + vertex -698.857 157.816 49.477 + vertex -697.555 153.994 48.8593 + endloop + endfacet + facet normal -0.633101 -0.328844 0.700746 + outer loop + vertex -697.555 153.994 48.8593 + vertex -698.857 157.816 49.477 + vertex -697.664 153.911 48.7228 + endloop + endfacet + facet normal -0.5771 -0.319508 0.751579 + outer loop + vertex -698.318 157.905 49.9276 + vertex -698.72 157.871 49.6043 + vertex -697.123 153.947 49.1626 + endloop + endfacet + facet normal -0.567162 -0.316454 0.760384 + outer loop + vertex -697.123 153.947 49.1626 + vertex -698.72 157.871 49.6043 + vertex -697.555 153.994 48.8593 + endloop + endfacet + facet normal -0.558451 -0.377522 0.738654 + outer loop + vertex -697.123 153.947 49.1626 + vertex -697.555 153.994 48.8593 + vertex -695.915 150.52 48.3243 + endloop + endfacet + facet normal -0.581163 -0.384914 0.717001 + outer loop + vertex -695.915 150.52 48.3243 + vertex -697.555 153.994 48.8593 + vertex -696.265 150.51 48.0351 + endloop + endfacet + facet normal -0.594339 -0.386955 0.705001 + outer loop + vertex -697.555 153.994 48.8593 + vertex -697.664 153.911 48.7228 + vertex -696.265 150.51 48.0351 + endloop + endfacet + facet normal -0.639003 -0.396096 0.659381 + outer loop + vertex -696.265 150.51 48.0351 + vertex -697.664 153.911 48.7228 + vertex -696.313 150.326 47.8782 + endloop + endfacet + facet normal -0.545033 -0.476733 0.689684 + outer loop + vertex -692.875 143.93 46.5123 + vertex -693.605 145.22 46.8271 + vertex -693.554 144.721 46.5226 + endloop + endfacet + facet normal -0.566415 -0.461915 0.682502 + outer loop + vertex -694.747 147.61 47.4968 + vertex -694.906 147.38 47.2095 + vertex -693.605 145.22 46.8271 + endloop + endfacet + facet normal -0.579219 -0.467073 0.668093 + outer loop + vertex -694.906 147.38 47.2095 + vertex -693.554 144.721 46.5226 + vertex -693.605 145.22 46.8271 + endloop + endfacet + facet normal -0.540801 -0.457327 0.705965 + outer loop + vertex -694.906 147.38 47.2095 + vertex -694.93 147.167 47.0534 + vertex -693.554 144.721 46.5226 + endloop + endfacet + facet normal -0.492189 -0.439805 0.751213 + outer loop + vertex -693.554 144.721 46.5226 + vertex -694.93 147.167 47.0534 + vertex -693.937 145.052 46.4657 + endloop + endfacet + facet normal -0.559382 -0.455114 0.692794 + outer loop + vertex -694.93 147.167 47.0534 + vertex -694.956 147.106 46.9923 + vertex -693.937 145.052 46.4657 + endloop + endfacet + facet normal -0.521667 -0.445353 0.727684 + outer loop + vertex -693.937 145.052 46.4657 + vertex -694.956 147.106 46.9923 + vertex -693.908 144.824 46.3474 + endloop + endfacet + facet normal -0.682843 -0.471456 0.558081 + outer loop + vertex -694.956 147.106 46.9923 + vertex -695.018 147.182 46.9805 + vertex -693.908 144.824 46.3474 + endloop + endfacet + facet normal -0.439774 -0.420277 0.793704 + outer loop + vertex -693.908 144.824 46.3474 + vertex -695.018 147.182 46.9805 + vertex -694.128 145.137 46.3905 + endloop + endfacet + facet normal -0.752819 -0.0347803 -0.657308 + outer loop + vertex -700.612 166.803 50.6202 + vertex -700.711 167.546 50.6948 + vertex -701.471 174.014 51.2229 + endloop + endfacet + facet normal -0.635611 -0.132412 0.76057 + outer loop + vertex -700.546 166.546 50.6591 + vertex -701.278 173.95 51.3364 + vertex -700.711 167.546 50.6948 + endloop + endfacet + facet normal -0.533745 -0.130906 0.835452 + outer loop + vertex -701.278 173.95 51.3364 + vertex -701.471 174.014 51.2229 + vertex -700.711 167.546 50.6948 + endloop + endfacet + facet normal -0.710582 -0.133445 0.690844 + outer loop + vertex -700.546 166.546 50.6591 + vertex -700.402 167.401 50.9725 + vertex -701.278 173.95 51.3364 + endloop + endfacet + facet normal -0.649596 -0.139288 0.747411 + outer loop + vertex -699.82 166.271 51.2676 + vertex -700.574 173.597 51.9771 + vertex -700.402 167.401 50.9725 + endloop + endfacet + facet normal -0.703042 -0.132869 0.698626 + outer loop + vertex -700.574 173.597 51.9771 + vertex -701.278 173.95 51.3364 + vertex -700.402 167.401 50.9725 + endloop + endfacet + facet normal -0.746766 -0.014283 0.664933 + outer loop + vertex -702.093 193.908 52.591 + vertex -701.571 200.377 53.3158 + vertex -702.294 207.259 52.6513 + endloop + endfacet + facet normal -0.569127 -0.477428 0.669445 + outer loop + vertex -694.128 145.137 46.3905 + vertex -694.088 144.928 46.2753 + vertex -693.48 143.77 45.967 + endloop + endfacet + facet normal -0.60821 -0.479816 0.632342 + outer loop + vertex -694.114 144.861 46.2001 + vertex -693.586 143.781 45.8882 + vertex -694.088 144.928 46.2753 + endloop + endfacet + facet normal -0.555304 -0.473889 0.683422 + outer loop + vertex -693.586 143.781 45.8882 + vertex -693.48 143.77 45.967 + vertex -694.088 144.928 46.2753 + endloop + endfacet + facet normal -0.456715 -0.306883 0.835006 + outer loop + vertex -699.076 158.158 49.41 + vertex -699.139 158.057 49.3385 + vertex -697.912 154.359 48.6507 + endloop + endfacet + facet normal -0.756569 -0.353406 0.550188 + outer loop + vertex -697.912 154.359 48.6507 + vertex -699.139 158.057 49.3385 + vertex -697.812 153.854 48.4632 + endloop + endfacet + facet normal -0.575295 -0.381906 0.723314 + outer loop + vertex -697.912 154.359 48.6507 + vertex -697.812 153.854 48.4632 + vertex -696.47 150.441 47.7288 + endloop + endfacet + facet normal -0.769848 -0.408324 0.490515 + outer loop + vertex -696.47 150.441 47.7288 + vertex -697.812 153.854 48.4632 + vertex -696.175 149.508 47.415 + endloop + endfacet + facet normal -0.235002 -0.253134 0.938455 + outer loop + vertex -698.966 158.176 49.4425 + vertex -699.076 158.158 49.41 + vertex -697.789 154.224 48.6713 + endloop + endfacet + facet normal -0.477473 -0.310629 0.821906 + outer loop + vertex -697.789 154.224 48.6713 + vertex -699.076 158.158 49.41 + vertex -697.912 154.359 48.6507 + endloop + endfacet + facet normal -0.589072 -0.319981 0.742028 + outer loop + vertex -698.875 158.03 49.4516 + vertex -698.966 158.176 49.4425 + vertex -697.677 153.999 48.6642 + endloop + endfacet + facet normal -0.605355 -0.322347 0.727762 + outer loop + vertex -697.677 153.999 48.6642 + vertex -698.966 158.176 49.4425 + vertex -697.789 154.224 48.6713 + endloop + endfacet + facet normal -0.77717 -0.399694 0.486057 + outer loop + vertex -697.677 153.999 48.6642 + vertex -697.789 154.224 48.6713 + vertex -696.325 150.325 47.805 + endloop + endfacet + facet normal -0.669456 -0.391532 0.631294 + outer loop + vertex -696.325 150.325 47.805 + vertex -697.789 154.224 48.6713 + vertex -696.432 150.512 47.808 + endloop + endfacet + facet normal -0.533863 -0.371771 0.759458 + outer loop + vertex -697.789 154.224 48.6713 + vertex -697.912 154.359 48.6507 + vertex -696.432 150.512 47.808 + endloop + endfacet + facet normal -0.640677 -0.391226 0.660663 + outer loop + vertex -696.432 150.512 47.808 + vertex -697.912 154.359 48.6507 + vertex -696.47 150.441 47.7288 + endloop + endfacet + facet normal -0.618019 -0.453971 0.641844 + outer loop + vertex -695.018 147.182 46.9805 + vertex -695.104 147.265 46.9565 + vertex -694.128 145.137 46.3905 + endloop + endfacet + facet normal -0.648189 -0.458741 0.607789 + outer loop + vertex -694.128 145.137 46.3905 + vertex -695.104 147.265 46.9565 + vertex -694.088 144.928 46.2753 + endloop + endfacet + facet normal -0.610082 -0.45425 0.649197 + outer loop + vertex -695.104 147.265 46.9565 + vertex -695.051 146.995 46.8169 + vertex -694.088 144.928 46.2753 + endloop + endfacet + facet normal -0.634368 -0.458533 0.622354 + outer loop + vertex -694.088 144.928 46.2753 + vertex -695.051 146.995 46.8169 + vertex -694.114 144.861 46.2001 + endloop + endfacet + facet normal -0.736956 -0.465411 0.490192 + outer loop + vertex -695.051 146.995 46.8169 + vertex -694.6 145.883 46.4394 + vertex -694.114 144.861 46.2001 + endloop + endfacet + facet normal -0.870639 -0.456929 0.182217 + outer loop + vertex -694.114 144.861 46.2001 + vertex -694.6 145.883 46.4394 + vertex -693.784 144.133 45.9522 + endloop + endfacet + facet normal -0.153693 -0.106405 0.982373 + outer loop + vertex -700.883 167.307 50.6322 + vertex -700.822 168.086 50.7262 + vertex -701.719 174.553 51.2864 + endloop + endfacet + facet normal -0.0229334 -0.0859689 0.996034 + outer loop + vertex -700.612 166.803 50.6202 + vertex -701.471 174.014 51.2229 + vertex -700.822 168.086 50.7262 + endloop + endfacet + facet normal 0.0968227 -0.07257 0.992652 + outer loop + vertex -701.471 174.014 51.2229 + vertex -701.719 174.553 51.2864 + vertex -700.822 168.086 50.7262 + endloop + endfacet + facet normal -0.878583 -0.084932 -0.469978 + outer loop + vertex -702.303 378.625 291.194 + vertex -703.566 386.655 292.105 + vertex -701.505 386.658 288.252 + endloop + endfacet + facet normal -0.935079 -0.0359865 -0.352609 + outer loop + vertex -702.219 372.165 291.631 + vertex -702.303 378.625 291.194 + vertex -701.717 368.858 290.637 + endloop + endfacet + facet normal -0.904002 -0.0087695 -0.427438 + outer loop + vertex -702.253 369.542 291.758 + vertex -702.219 372.165 291.631 + vertex -701.717 368.858 290.637 + endloop + endfacet + facet normal -0.903261 -0.00553776 -0.429056 + outer loop + vertex -702.232 365.182 291.77 + vertex -702.253 369.542 291.758 + vertex -701.717 368.858 290.637 + endloop + endfacet + facet normal -0.892538 -0.0137342 -0.450763 + outer loop + vertex -701.976 359.375 291.44 + vertex -702.232 365.182 291.77 + vertex -701.717 368.858 290.637 + endloop + endfacet + facet normal -0.854875 -0.00934908 -0.51875 + outer loop + vertex -701.95 354.36 291.487 + vertex -701.976 359.375 291.44 + vertex -701.261 351.356 290.407 + endloop + endfacet + facet normal -0.852646 -0.00751191 -0.522436 + outer loop + vertex -701.956 350.156 291.557 + vertex -701.95 354.36 291.487 + vertex -701.261 351.356 290.407 + endloop + endfacet + facet normal -0.851546 -0.009828 -0.524188 + outer loop + vertex -701.83 345.874 291.433 + vertex -701.956 350.156 291.557 + vertex -701.261 351.356 290.407 + endloop + endfacet + facet normal -0.852994 -0.00923813 -0.521839 + outer loop + vertex -701.708 339.177 291.352 + vertex -701.83 345.874 291.433 + vertex -701.261 351.356 290.407 + endloop + endfacet + facet normal -0.829335 -0.00869456 -0.558685 + outer loop + vertex -701.643 332.854 291.355 + vertex -701.708 339.177 291.352 + vertex -700.867 332.963 290.201 + endloop + endfacet + facet normal -0.829398 -0.00743413 -0.558608 + outer loop + vertex -701.621 329.81 291.361 + vertex -701.643 332.854 291.355 + vertex -700.867 332.963 290.201 + endloop + endfacet + facet normal -0.83135 -0.00590411 -0.555718 + outer loop + vertex -701.55 323.81 291.319 + vertex -701.621 329.81 291.361 + vertex -700.867 332.963 290.201 + endloop + endfacet + facet normal -0.82265 -0.00590959 -0.568518 + outer loop + vertex -701.553 317.443 291.389 + vertex -701.55 323.81 291.319 + vertex -700.646 316.43 290.088 + endloop + endfacet + facet normal -0.821943 -0.00394419 -0.569556 + outer loop + vertex -701.602 312.357 291.496 + vertex -701.553 317.443 291.389 + vertex -700.646 316.43 290.088 + endloop + endfacet + facet normal -0.819216 -0.00593125 -0.573454 + outer loop + vertex -701.362 307.156 291.207 + vertex -701.602 312.357 291.496 + vertex -700.646 316.43 290.088 + endloop + endfacet + facet normal -0.810156 -0.00551464 -0.586189 + outer loop + vertex -701.465 302.291 291.394 + vertex -701.362 307.156 291.207 + vertex -700.485 300.02 290.062 + endloop + endfacet + facet normal -0.808592 -0.00356727 -0.588358 + outer loop + vertex -701.526 297.247 291.51 + vertex -701.465 302.291 291.394 + vertex -700.485 300.02 290.062 + endloop + endfacet + facet normal -0.806636 -0.00569188 -0.591021 + outer loop + vertex -701.243 290.426 291.188 + vertex -701.526 297.247 291.51 + vertex -700.485 300.02 290.062 + endloop + endfacet + facet normal -0.793564 -0.00379889 -0.608476 + outer loop + vertex -701.377 282.151 291.415 + vertex -701.243 290.426 291.188 + vertex -700.2 282.663 289.877 + endloop + endfacet + facet normal -0.793592 -0.00362437 -0.608439 + outer loop + vertex -701.095 274.035 291.095 + vertex -701.377 282.151 291.415 + vertex -700.2 282.663 289.877 + endloop + endfacet + facet normal -0.781702 -0.00039204 -0.623652 + outer loop + vertex -701.323 265.814 291.387 + vertex -701.095 274.035 291.095 + vertex -700.115 264.93 289.872 + endloop + endfacet + facet normal -0.780668 0.00322673 -0.624938 + outer loop + vertex -701.246 255.426 291.237 + vertex -701.323 265.814 291.387 + vertex -700.115 264.93 289.872 + endloop + endfacet + facet normal -0.772844 0.00466739 -0.634578 + outer loop + vertex -701.352 247.864 291.31 + vertex -701.246 255.426 291.237 + vertex -700.325 245.887 290.045 + endloop + endfacet + facet normal -0.765365 0.0142211 -0.643439 + outer loop + vertex -701.577 241.964 291.448 + vertex -701.352 247.864 291.31 + vertex -700.325 245.887 290.045 + endloop + endfacet + facet normal -0.764617 0.0136604 -0.64434 + outer loop + vertex -701.585 233.047 291.268 + vertex -701.577 241.964 291.448 + vertex -700.325 245.887 290.045 + endloop + endfacet + facet normal -0.741147 0.0131864 -0.671214 + outer loop + vertex -701.743 225.146 291.287 + vertex -701.585 233.047 291.268 + vertex -700.432 227.36 289.883 + endloop + endfacet + facet normal -0.741483 0.0136271 -0.670833 + outer loop + vertex -701.904 216.953 291.298 + vertex -701.743 225.146 291.287 + vertex -700.432 227.36 289.883 + endloop + endfacet + facet normal -0.710974 0.0113852 -0.703126 + outer loop + vertex -702.147 209.566 291.425 + vertex -701.904 216.953 291.298 + vertex -700.981 208.156 290.223 + endloop + endfacet + facet normal -0.714629 0.00526065 -0.699484 + outer loop + vertex -702.351 203.88 291.59 + vertex -702.147 209.566 291.425 + vertex -700.981 208.156 290.223 + endloop + endfacet + facet normal -0.706801 0.000218251 -0.707412 + outer loop + vertex -702.393 197.865 291.63 + vertex -702.351 203.88 291.59 + vertex -700.981 208.156 290.223 + endloop + endfacet + facet normal -0.60507 -0.018044 -0.795968 + outer loop + vertex -702.744 193.169 292.004 + vertex -702.393 197.865 291.63 + vertex -702.587 191.946 291.912 + endloop + endfacet + facet normal -0.675562 -0.0316053 -0.736626 + outer loop + vertex -702.643 187.289 292.164 + vertex -702.744 193.169 292.004 + vertex -702.587 191.946 291.912 + endloop + endfacet + facet normal -0.531727 -0.0462154 -0.845654 + outer loop + vertex -702.359 181.29 292.313 + vertex -702.643 187.289 292.164 + vertex -702.272 186.025 291.999 + endloop + endfacet + facet normal -0.270308 -0.0569926 -0.961085 + outer loop + vertex -702.079 176.432 292.522 + vertex -702.359 181.29 292.313 + vertex -701.607 176.092 292.41 + endloop + endfacet + facet normal -0.293288 -0.0920575 -0.951582 + outer loop + vertex -701.485 171.039 292.861 + vertex -702.079 176.432 292.522 + vertex -701.607 176.092 292.41 + endloop + endfacet + facet normal -0.474172 -0.136524 -0.869783 + outer loop + vertex -700.708 165.441 293.316 + vertex -701.485 171.039 292.861 + vertex -700.863 167.235 293.119 + endloop + endfacet + facet normal -0.773859 -0.0881412 0.627195 + outer loop + vertex -700.012 161.78 293.659 + vertex -700.708 165.441 293.316 + vertex -700.548 164.409 293.367 + endloop + endfacet + facet normal -0.946404 -0.212522 0.243216 + outer loop + vertex -698.851 157.302 294.264 + vertex -700.012 161.78 293.659 + vertex -699.498 159.726 293.865 + endloop + endfacet + facet normal -0.918861 -0.242859 0.310989 + outer loop + vertex -697.155 152.01 295.143 + vertex -698.851 157.302 294.264 + vertex -698.286 155.431 294.472 + endloop + endfacet + facet normal -0.904858 -0.388535 -0.173989 + outer loop + vertex -695.568 147.948 295.961 + vertex -697.155 152.01 295.143 + vertex -696.826 151.213 295.214 + endloop + endfacet + facet normal -0.67799 -0.444636 -0.585345 + outer loop + vertex -693.615 143.55 297.04 + vertex -695.568 147.948 295.961 + vertex -695.307 147.497 296.001 + endloop + endfacet + facet normal 0.479101 0.685287 0.548493 + outer loop + vertex -688.863 143.2 293.162 + vertex -691.353 142.932 295.671 + vertex -690.477 142.91 294.935 + endloop + endfacet + facet normal -0.679153 -0.413932 -0.606145 + outer loop + vertex -685.911 144.188 289.181 + vertex -688.863 143.2 293.162 + vertex -688.225 144.133 291.81 + endloop + endfacet + facet normal -0.699631 -0.452119 -0.553268 + outer loop + vertex -683.05 145.228 284.712 + vertex -685.911 144.188 289.181 + vertex -684.175 145.547 285.873 + endloop + endfacet + facet normal -0.718956 -0.493651 -0.489297 + outer loop + vertex -681.042 146.266 280.714 + vertex -683.05 145.228 284.712 + vertex -682.193 146.48 282.19 + endloop + endfacet + facet normal -0.760217 -0.488184 -0.428657 + outer loop + vertex -679.431 147.382 276.587 + vertex -681.042 146.266 280.714 + vertex -680.522 147.518 278.366 + endloop + endfacet + facet normal -0.805454 -0.452834 -0.382341 + outer loop + vertex -677.905 148.861 271.621 + vertex -679.431 147.382 276.587 + vertex -679.094 148.581 274.456 + endloop + endfacet + facet normal -0.849077 -0.43481 -0.300013 + outer loop + vertex -675.495 151.742 261.285 + vertex -676.657 150.152 266.879 + vertex -676.361 151.614 263.921 + endloop + endfacet + facet normal -0.846823 -0.462402 -0.262822 + outer loop + vertex -674.56 153.268 255.59 + vertex -675.495 151.742 261.285 + vertex -675.542 152.743 259.677 + endloop + endfacet + facet normal -0.825812 -0.508195 -0.244483 + outer loop + vertex -673.912 154.419 251.006 + vertex -674.56 153.268 255.59 + vertex -674.46 154.439 252.816 + endloop + endfacet + facet normal -0.823258 -0.522212 -0.222579 + outer loop + vertex -673.471 155.499 246.843 + vertex -673.912 154.419 251.006 + vertex -673.98 155.453 248.834 + endloop + endfacet + facet normal -0.818165 -0.528075 0.22747 + outer loop + vertex -673.952 154.11 91.6035 + vertex -673.494 155.271 95.9442 + vertex -674.039 155.32 94.0991 + endloop + endfacet + facet normal -0.831606 -0.497835 0.246155 + outer loop + vertex -674.764 152.62 85.8458 + vertex -673.952 154.11 91.6035 + vertex -674.524 154.262 89.9784 + endloop + endfacet + facet normal -0.836974 -0.477649 0.267068 + outer loop + vertex -675.539 151.325 81.1016 + vertex -674.764 152.62 85.8458 + vertex -675.56 152.488 83.1148 + endloop + endfacet + facet normal -0.824912 -0.475531 0.305599 + outer loop + vertex -676.466 150.049 76.6134 + vertex -675.539 151.325 81.1016 + vertex -676.306 151.371 79.1002 + endloop + endfacet + facet normal -0.76691 -0.518778 0.37778 + outer loop + vertex -679.336 147.186 66.283 + vertex -677.871 148.582 71.1746 + vertex -679.147 148.321 68.2255 + endloop + endfacet + facet normal -0.731041 -0.52836 0.431757 + outer loop + vertex -681.023 146.016 61.9945 + vertex -679.336 147.186 66.283 + vertex -680.519 147.256 64.3659 + endloop + endfacet + facet normal -0.711608 -0.497295 0.496298 + outer loop + vertex -683.43 144.917 57.443 + vertex -681.023 146.016 61.9945 + vertex -682.132 146.275 60.664 + endloop + endfacet + facet normal -0.69728 -0.464769 0.545702 + outer loop + vertex -686.108 143.887 53.1433 + vertex -683.43 144.917 57.443 + vertex -685.595 144.859 54.6271 + endloop + endfacet + facet normal -0.648825 -0.48797 0.583877 + outer loop + vertex -688.49 143.135 49.8675 + vertex -686.108 143.887 53.1433 + vertex -688.102 144.007 51.0275 + endloop + endfacet + facet normal -0.689729 -0.277924 0.668605 + outer loop + vertex -690.679 142.706 47.4309 + vertex -688.49 143.135 49.8675 + vertex -689.744 142.986 48.5123 + endloop + endfacet + facet normal 0.496086 0.648693 -0.577145 + outer loop + vertex -693.155 142.971 45.6015 + vertex -690.679 142.706 47.4309 + vertex -691.939 142.755 46.4032 + endloop + endfacet + facet normal -0.89597 -0.44411 -0.00213706 + outer loop + vertex -695.36 147.413 46.7898 + vertex -693.155 142.971 45.6015 + vertex -694.6 145.883 46.4394 + endloop + endfacet + facet normal -0.819559 -0.431529 0.376968 + outer loop + vertex -697.161 151.798 47.8929 + vertex -695.36 147.413 46.7898 + vertex -696.175 149.508 47.415 + endloop + endfacet + facet normal -0.938253 -0.327849 0.110436 + outer loop + vertex -698.914 157.213 49.0724 + vertex -697.161 151.798 47.8929 + vertex -697.812 153.854 48.4632 + endloop + endfacet + facet normal -0.969189 -0.237919 -0.0637721 + outer loop + vertex -700.054 161.637 49.8844 + vertex -698.914 157.213 49.0724 + vertex -699.139 158.057 49.3385 + endloop + endfacet + facet normal -0.965655 -0.145481 -0.215278 + outer loop + vertex -700.844 166.047 50.4483 + vertex -700.054 161.637 49.8844 + vertex -700.489 163.97 50.261 + endloop + endfacet + facet normal -0.37438 -0.145387 0.915807 + outer loop + vertex -701.567 171.641 51.0406 + vertex -700.844 166.047 50.4483 + vertex -700.883 167.307 50.6322 + endloop + endfacet + facet normal 0.118203 -0.0773731 0.98997 + outer loop + vertex -702.01 175.869 51.424 + vertex -701.567 171.641 51.0406 + vertex -701.719 174.553 51.2864 + endloop + endfacet + facet normal 0.220259 -0.0530636 0.973997 + outer loop + vertex -702.251 179.717 51.6881 + vertex -702.01 175.869 51.424 + vertex -701.719 174.553 51.2864 + endloop + endfacet + facet normal 0.362803 -0.0340202 0.931245 + outer loop + vertex -702.508 185.736 52.0082 + vertex -702.251 179.717 51.6881 + vertex -702.229 181.86 51.7577 + endloop + endfacet + facet normal -0.567441 -0.00602655 0.823392 + outer loop + vertex -702.595 205.36 52.4302 + vertex -702.631 198.288 52.3538 + vertex -702.294 207.259 52.6513 + endloop + endfacet + facet normal -0.795418 -0.298793 -0.527288 + outer loop + vertex -699.498 159.726 293.865 + vertex -698.286 155.431 294.472 + vertex -698.851 157.302 294.264 + endloop + endfacet + facet normal -0.744394 -0.35703 -0.564277 + outer loop + vertex -698.286 155.431 294.472 + vertex -696.826 151.213 295.214 + vertex -697.155 152.01 295.143 + endloop + endfacet + facet normal -0.541924 -0.380363 -0.749427 + outer loop + vertex -696.826 151.213 295.214 + vertex -695.307 147.497 296.001 + vertex -695.568 147.948 295.961 + endloop + endfacet + facet normal -0.652854 -0.441751 -0.615336 + outer loop + vertex -695.307 147.497 296.001 + vertex -694.2 145.253 296.438 + vertex -693.615 143.55 297.04 + endloop + endfacet + facet normal -0.151247 -0.0915375 -0.984249 + outer loop + vertex -701.607 176.092 292.41 + vertex -700.863 167.235 293.119 + vertex -701.485 171.039 292.861 + endloop + endfacet + facet normal -0.619086 -0.0170701 -0.785138 + outer loop + vertex -701.915 193.98 291.338 + vertex -702.587 191.946 291.912 + vertex -702.393 197.865 291.63 + endloop + endfacet + facet normal -0.515245 -0.0400181 -0.856108 + outer loop + vertex -702.587 191.946 291.912 + vertex -702.272 186.025 291.999 + vertex -702.643 187.289 292.164 + endloop + endfacet + facet normal -0.279786 -0.0583123 -0.95829 + outer loop + vertex -702.272 186.025 291.999 + vertex -701.607 176.092 292.41 + vertex -702.359 181.29 292.313 + endloop + endfacet + facet normal -0.658465 -0.437321 -0.612514 + outer loop + vertex -689.375 143.146 293.752 + vertex -688.225 144.133 291.81 + vertex -688.863 143.2 293.162 + endloop + endfacet + facet normal -0.707284 0.408506 -0.576951 + outer loop + vertex -690.477 142.91 294.935 + vertex -689.375 143.146 293.752 + vertex -688.863 143.2 293.162 + endloop + endfacet + facet normal -0.631556 -0.019358 -0.775089 + outer loop + vertex -700.981 208.156 290.223 + vertex -701.915 193.98 291.338 + vertex -702.393 197.865 291.63 + endloop + endfacet + facet normal -0.723618 0.00847355 -0.690149 + outer loop + vertex -700.432 227.36 289.883 + vertex -700.981 208.156 290.223 + vertex -701.904 216.953 291.298 + endloop + endfacet + facet normal -0.74764 0.0101188 -0.664027 + outer loop + vertex -700.325 245.887 290.045 + vertex -700.432 227.36 289.883 + vertex -701.585 233.047 291.268 + endloop + endfacet + facet normal -0.779726 0.0029457 -0.626114 + outer loop + vertex -700.115 264.93 289.872 + vertex -700.325 245.887 290.045 + vertex -701.246 255.426 291.237 + endloop + endfacet + facet normal -0.793433 -0.0036702 -0.608647 + outer loop + vertex -700.2 282.663 289.877 + vertex -700.115 264.93 289.872 + vertex -701.095 274.035 291.095 + endloop + endfacet + facet normal -0.801951 -0.00680458 -0.597351 + outer loop + vertex -700.485 300.02 290.062 + vertex -700.2 282.663 289.877 + vertex -701.243 290.426 291.188 + endloop + endfacet + facet normal -0.81463 -0.00706741 -0.579937 + outer loop + vertex -700.646 316.43 290.088 + vertex -700.485 300.02 290.062 + vertex -701.362 307.156 291.207 + endloop + endfacet + facet normal -0.826215 -0.00721485 -0.563309 + outer loop + vertex -700.867 332.963 290.201 + vertex -700.646 316.43 290.088 + vertex -701.55 323.81 291.319 + endloop + endfacet + facet normal -0.836826 -0.0118097 -0.547341 + outer loop + vertex -701.261 351.356 290.407 + vertex -700.867 332.963 290.201 + vertex -701.708 339.177 291.352 + endloop + endfacet + facet normal -0.909416 -0.0446079 -0.413488 + outer loop + vertex -700.023 366.697 287.145 + vertex -701.717 368.858 290.637 + vertex -701.505 386.658 288.252 + endloop + endfacet + facet normal -0.87772 -0.0165206 -0.47889 + outer loop + vertex -701.717 368.858 290.637 + vertex -701.261 351.356 290.407 + vertex -701.976 359.375 291.44 + endloop + endfacet + facet normal -0.703089 -0.447052 -0.553001 + outer loop + vertex -686.109 145.004 288.773 + vertex -684.175 145.547 285.873 + vertex -685.911 144.188 289.181 + endloop + endfacet + facet normal -0.662967 -0.457218 -0.592813 + outer loop + vertex -688.225 144.133 291.81 + vertex -686.109 145.004 288.773 + vertex -685.911 144.188 289.181 + endloop + endfacet + facet normal -0.687621 -0.566394 -0.454286 + outer loop + vertex -682.193 146.48 282.19 + vertex -680.522 147.518 278.366 + vertex -681.042 146.266 280.714 + endloop + endfacet + facet normal -0.671347 -0.54731 -0.499745 + outer loop + vertex -684.175 145.547 285.873 + vertex -682.193 146.48 282.19 + vertex -683.05 145.228 284.712 + endloop + endfacet + facet normal -0.790905 -0.480473 -0.378966 + outer loop + vertex -679.094 148.581 274.456 + vertex -678.113 149.612 271.102 + vertex -677.905 148.861 271.621 + endloop + endfacet + facet normal -0.741676 -0.527532 -0.414278 + outer loop + vertex -680.522 147.518 278.366 + vertex -679.094 148.581 274.456 + vertex -679.431 147.382 276.587 + endloop + endfacet + facet normal -0.817747 -0.479213 -0.318817 + outer loop + vertex -677.247 150.429 267.975 + vertex -676.361 151.614 263.921 + vertex -676.657 150.152 266.879 + endloop + endfacet + facet normal -0.811682 -0.506332 -0.291204 + outer loop + vertex -676.361 151.614 263.921 + vertex -675.542 152.743 259.677 + vertex -675.495 151.742 261.285 + endloop + endfacet + facet normal -0.800983 -0.549994 -0.236502 + outer loop + vertex -674.46 154.439 252.816 + vertex -673.98 155.453 248.834 + vertex -673.912 154.419 251.006 + endloop + endfacet + facet normal -0.808119 -0.540592 0.233889 + outer loop + vertex -674.039 155.32 94.0991 + vertex -674.524 154.262 89.9784 + vertex -673.952 154.11 91.6035 + endloop + endfacet + facet normal -0.798863 -0.524485 0.294505 + outer loop + vertex -675.56 152.488 83.1148 + vertex -676.306 151.371 79.1002 + vertex -675.539 151.325 81.1016 + endloop + endfacet + facet normal -0.796776 -0.51095 0.32261 + outer loop + vertex -676.306 151.371 79.1002 + vertex -677.232 150.219 74.9891 + vertex -676.466 150.049 76.6134 + endloop + endfacet + facet normal -0.699364 -0.585401 0.410118 + outer loop + vertex -679.147 148.321 68.2255 + vertex -680.519 147.256 64.3659 + vertex -679.336 147.186 66.283 + endloop + endfacet + facet normal -0.768963 -0.515306 0.37836 + outer loop + vertex -678.188 149.356 71.5836 + vertex -679.147 148.321 68.2255 + vertex -677.871 148.582 71.1746 + endloop + endfacet + facet normal -0.71216 -0.496583 0.49622 + outer loop + vertex -682.132 146.275 60.664 + vertex -683.801 145.641 57.6336 + vertex -683.43 144.917 57.443 + endloop + endfacet + facet normal -0.675604 -0.584517 0.449332 + outer loop + vertex -680.519 147.256 64.3659 + vertex -682.132 146.275 60.664 + vertex -681.023 146.016 61.9945 + endloop + endfacet + facet normal -0.631994 -0.529728 0.56566 + outer loop + vertex -685.595 144.859 54.6271 + vertex -688.102 144.007 51.0275 + vertex -686.108 143.887 53.1433 + endloop + endfacet + facet normal -0.684725 -0.493132 0.536631 + outer loop + vertex -683.801 145.641 57.6336 + vertex -685.595 144.859 54.6271 + vertex -683.43 144.917 57.443 + endloop + endfacet + facet normal -0.57386 -0.521403 0.631525 + outer loop + vertex -689.744 142.986 48.5123 + vertex -691.034 142.711 47.1131 + vertex -690.679 142.706 47.4309 + endloop + endfacet + facet normal 0.260966 0.925123 -0.275763 + outer loop + vertex -691.034 142.711 47.1131 + vertex -691.939 142.755 46.4032 + vertex -690.679 142.706 47.4309 + endloop + endfacet + facet normal -0.587219 -0.540373 0.602637 + outer loop + vertex -688.102 144.007 51.0275 + vertex -689.744 142.986 48.5123 + vertex -688.49 143.135 49.8675 + endloop + endfacet + facet normal -0.51343 -0.520866 0.681974 + outer loop + vertex -693.032 143.505 46.102 + vertex -693.48 143.77 45.967 + vertex -693.155 142.971 45.6015 + endloop + endfacet + facet normal -0.535245 -0.508691 0.674349 + outer loop + vertex -691.939 142.755 46.4032 + vertex -693.032 143.505 46.102 + vertex -693.155 142.971 45.6015 + endloop + endfacet + facet normal -0.156852 -0.0268633 0.987257 + outer loop + vertex -702.459 193.519 52.2513 + vertex -702.294 207.259 52.6513 + vertex -702.631 198.288 52.3538 + endloop + endfacet + facet normal -0.541738 -0.521852 0.658931 + outer loop + vertex -693.48 143.77 45.967 + vertex -693.586 143.781 45.8882 + vertex -693.155 142.971 45.6015 + endloop + endfacet + facet normal -0.72022 -0.492923 0.488171 + outer loop + vertex -693.586 143.781 45.8882 + vertex -694.114 144.861 46.2001 + vertex -693.784 144.133 45.9522 + endloop + endfacet + facet normal -0.850565 -0.350196 0.392303 + outer loop + vertex -697.812 153.854 48.4632 + vertex -699.139 158.057 49.3385 + vertex -698.914 157.213 49.0724 + endloop + endfacet + facet normal -0.479537 -0.372307 0.794627 + outer loop + vertex -696.175 149.508 47.415 + vertex -697.812 153.854 48.4632 + vertex -697.161 151.798 47.8929 + endloop + endfacet + facet normal -0.494485 -0.41968 0.761152 + outer loop + vertex -694.6 145.883 46.4394 + vertex -696.175 149.508 47.415 + vertex -695.36 147.413 46.7898 + endloop + endfacet + facet normal -0.297324 0.124796 -0.946586 + outer loop + vertex -693.784 144.133 45.9522 + vertex -694.6 145.883 46.4394 + vertex -693.155 142.971 45.6015 + endloop + endfacet + facet normal 0.0925324 -0.0789298 0.992576 + outer loop + vertex -700.883 167.307 50.6322 + vertex -701.719 174.553 51.2864 + vertex -701.567 171.641 51.0406 + endloop + endfacet + facet normal 0.518974 -0.0178008 0.854605 + outer loop + vertex -702.229 181.86 51.7577 + vertex -702.554 189.892 52.1229 + vertex -702.508 185.736 52.0082 + endloop + endfacet + facet normal 0.370599 -0.0340011 0.928171 + outer loop + vertex -701.719 174.553 51.2864 + vertex -702.229 181.86 51.7577 + vertex -702.251 179.717 51.6881 + endloop + endfacet + facet normal -0.935353 -0.0360449 -0.351874 + outer loop + vertex -702.303 378.625 291.194 + vertex -701.505 386.658 288.252 + vertex -701.717 368.858 290.637 + endloop + endfacet + facet normal -0.85198 -0.503969 0.141931 + outer loop + vertex -693.155 142.971 45.6015 + vertex -693.586 143.781 45.8882 + vertex -693.784 144.133 45.9522 + endloop + endfacet + facet normal 0.208469 -0.329045 0.921016 + outer loop + vertex 407.444 98.681 364.916 + vertex 409.225 101.525 365.529 + vertex 407.772 100.545 365.508 + endloop + endfacet + facet normal -0.209789 -0.329687 0.920486 + outer loop + vertex -409.226 101.53 365.53 + vertex -407.439 98.6828 364.918 + vertex -407.775 100.542 365.507 + endloop + endfacet + facet normal 0.372157 -0.155755 0.915008 + outer loop + vertex 414.02 126.138 370.07 + vertex 411.447 128.463 371.512 + vertex 412.855 125.53 370.44 + endloop + endfacet + facet normal 0.395425 -0.141834 0.907481 + outer loop + vertex 412.855 125.53 370.44 + vertex 411.447 128.463 371.512 + vertex 410.109 127.614 371.963 + endloop + endfacet + facet normal 0.406651 -0.16419 0.898708 + outer loop + vertex 411.447 128.463 371.512 + vertex 408.211 132.202 373.66 + vertex 410.109 127.614 371.963 + endloop + endfacet + facet normal 0.480926 -0.122178 0.868206 + outer loop + vertex 410.109 127.614 371.963 + vertex 408.211 132.202 373.66 + vertex 406.819 132.599 374.486 + endloop + endfacet + facet normal 0.409517 -0.213389 0.886996 + outer loop + vertex 407.824 127.635 372.959 + vertex 404.773 133.118 375.687 + vertex 406.101 125.522 373.247 + endloop + endfacet + facet normal 0.433983 -0.205925 0.877071 + outer loop + vertex 406.101 125.522 373.247 + vertex 404.773 133.118 375.687 + vertex 403.292 129.62 375.598 + endloop + endfacet + facet normal 0.466354 -0.172183 0.867679 + outer loop + vertex 408.211 132.202 373.66 + vertex 405.474 136.454 375.974 + vertex 406.819 132.599 374.486 + endloop + endfacet + facet normal 0.545031 -0.129564 0.828344 + outer loop + vertex 406.819 132.599 374.486 + vertex 405.474 136.454 375.974 + vertex 404.611 136.945 376.62 + endloop + endfacet + facet normal 0.474388 -0.222397 0.85176 + outer loop + vertex 404.773 133.118 375.687 + vertex 402.143 137.629 378.329 + vertex 403.292 129.62 375.598 + endloop + endfacet + facet normal 0.478627 -0.221095 0.849725 + outer loop + vertex 403.292 129.62 375.598 + vertex 402.143 137.629 378.329 + vertex 400.837 134.287 378.196 + endloop + endfacet + facet normal 0.51468 -0.19234 0.835529 + outer loop + vertex 405.474 136.454 375.974 + vertex 403.339 140.773 378.284 + vertex 404.611 136.945 376.62 + endloop + endfacet + facet normal 0.565888 -0.163409 0.808126 + outer loop + vertex 404.611 136.945 376.62 + vertex 403.339 140.773 378.284 + vertex 402.881 140.066 378.461 + endloop + endfacet + facet normal 0.520696 -0.236367 0.82037 + outer loop + vertex 402.143 137.629 378.329 + vertex 400.214 142.402 380.929 + vertex 400.837 134.287 378.196 + endloop + endfacet + facet normal 0.525097 -0.235197 0.817897 + outer loop + vertex 400.837 134.287 378.196 + vertex 400.214 142.402 380.929 + vertex 398.947 139.187 380.818 + endloop + endfacet + facet normal 0.591871 -0.186243 0.784221 + outer loop + vertex 403.339 140.773 378.284 + vertex 401.613 145.095 380.613 + vertex 402.881 140.066 378.461 + endloop + endfacet + facet normal 0.602486 -0.180655 0.777415 + outer loop + vertex 402.881 140.066 378.461 + vertex 401.613 145.095 380.613 + vertex 401.064 144.517 380.904 + endloop + endfacet + facet normal 0.562473 -0.248927 0.788454 + outer loop + vertex 400.214 142.402 380.929 + vertex 398.718 147.252 383.528 + vertex 398.947 139.187 380.818 + endloop + endfacet + facet normal 0.563302 -0.248725 0.787925 + outer loop + vertex 398.947 139.187 380.818 + vertex 398.718 147.252 383.528 + vertex 397.517 144.095 383.39 + endloop + endfacet + facet normal 0.618029 -0.204716 0.759033 + outer loop + vertex 401.613 145.095 380.613 + vertex 400.087 150.02 383.183 + vertex 401.064 144.517 380.904 + endloop + endfacet + facet normal 0.656857 -0.186091 0.730691 + outer loop + vertex 401.064 144.517 380.904 + vertex 400.087 150.02 383.183 + vertex 399.537 149.498 383.545 + endloop + endfacet + facet normal 0.593221 -0.258986 0.762243 + outer loop + vertex 398.718 147.252 383.528 + vertex 397.608 151.021 385.672 + vertex 397.517 144.095 383.39 + endloop + endfacet + facet normal 0.596088 -0.258356 0.760218 + outer loop + vertex 397.517 144.095 383.39 + vertex 397.608 151.021 385.672 + vertex 396.405 149.328 386.04 + endloop + endfacet + facet normal 0.667624 -0.208532 0.714698 + outer loop + vertex 400.087 150.02 383.183 + vertex 398.858 154.964 385.774 + vertex 399.537 149.498 383.545 + endloop + endfacet + facet normal 0.708486 -0.189263 0.679873 + outer loop + vertex 399.537 149.498 383.545 + vertex 398.858 154.964 385.774 + vertex 398.152 155.054 386.535 + endloop + endfacet + facet normal 0.607202 -0.26898 0.747633 + outer loop + vertex 397.608 151.021 385.672 + vertex 396.824 157.365 388.591 + vertex 396.405 149.328 386.04 + endloop + endfacet + facet normal 0.62025 -0.266518 0.737738 + outer loop + vertex 396.405 149.328 386.04 + vertex 396.824 157.365 388.591 + vertex 395.447 154.6 388.749 + endloop + endfacet + facet normal 0.702828 -0.216006 0.677772 + outer loop + vertex 398.858 154.964 385.774 + vertex 397.835 160.323 388.543 + vertex 398.152 155.054 386.535 + endloop + endfacet + facet normal 0.763736 -0.189249 0.617165 + outer loop + vertex 398.152 155.054 386.535 + vertex 397.835 160.323 388.543 + vertex 397.285 161.309 389.526 + endloop + endfacet + facet normal 0.640321 -0.27774 0.716135 + outer loop + vertex 396.824 157.365 388.591 + vertex 395.828 161.182 390.962 + vertex 395.447 154.6 388.749 + endloop + endfacet + facet normal 0.636499 -0.278556 0.719219 + outer loop + vertex 395.447 154.6 388.749 + vertex 395.828 161.182 390.962 + vertex 394.65 159.676 391.421 + endloop + endfacet + facet normal 0.737275 -0.224093 0.637345 + outer loop + vertex 397.835 160.323 388.543 + vertex 396.975 165.665 391.416 + vertex 397.285 161.309 389.526 + endloop + endfacet + facet normal 0.758013 -0.213486 0.616311 + outer loop + vertex 397.285 161.309 389.526 + vertex 396.975 165.665 391.416 + vertex 396.394 165.438 392.052 + endloop + endfacet + facet normal 0.646291 -0.290343 0.705697 + outer loop + vertex 395.828 161.182 390.962 + vertex 395.34 166.294 393.512 + vertex 394.65 159.676 391.421 + endloop + endfacet + facet normal 0.659592 -0.288101 0.694216 + outer loop + vertex 394.65 159.676 391.421 + vertex 395.34 166.294 393.512 + vertex 394.032 165 394.217 + endloop + endfacet + facet normal 0.757858 -0.238662 0.6072 + outer loop + vertex 396.975 165.665 391.416 + vertex 396.29 170.827 394.3 + vertex 396.394 165.438 392.052 + endloop + endfacet + facet normal 0.780033 -0.228019 0.582715 + outer loop + vertex 396.394 165.438 392.052 + vertex 396.29 170.827 394.3 + vertex 395.728 171.654 395.376 + endloop + endfacet + facet normal 0.667355 -0.303679 0.680012 + outer loop + vertex 395.34 166.294 393.512 + vertex 394.812 171.834 396.504 + vertex 394.032 165 394.217 + endloop + endfacet + facet normal 0.674848 -0.30226 0.673216 + outer loop + vertex 394.032 165 394.217 + vertex 394.812 171.834 396.504 + vertex 393.494 170.436 397.197 + endloop + endfacet + facet normal 0.756331 -0.264442 0.59836 + outer loop + vertex 396.29 170.827 394.3 + vertex 395.788 175.694 397.085 + vertex 395.728 171.654 395.376 + endloop + endfacet + facet normal 0.775337 -0.255854 0.5774 + outer loop + vertex 395.728 171.654 395.376 + vertex 395.788 175.694 397.085 + vertex 395.254 176.864 398.322 + endloop + endfacet + facet normal 0.682533 -0.316724 0.658662 + outer loop + vertex 394.812 171.834 396.504 + vertex 394.31 177.751 399.87 + vertex 393.494 170.436 397.197 + endloop + endfacet + facet normal 0.670328 -0.319431 0.669794 + outer loop + vertex 393.494 170.436 397.197 + vertex 394.31 177.751 399.87 + vertex 392.951 175.464 400.139 + endloop + endfacet + facet normal 0.750802 -0.286056 0.595372 + outer loop + vertex 395.788 175.694 397.085 + vertex 395.358 180.348 399.864 + vertex 395.254 176.864 398.322 + endloop + endfacet + facet normal 0.754515 -0.284429 0.591445 + outer loop + vertex 395.254 176.864 398.322 + vertex 395.358 180.348 399.864 + vertex 394.916 181.137 400.808 + endloop + endfacet + facet normal 0.683336 -0.329299 0.651624 + outer loop + vertex 394.31 177.751 399.87 + vertex 393.578 181.091 402.326 + vertex 392.951 175.464 400.139 + endloop + endfacet + facet normal 0.641764 -0.338803 0.688006 + outer loop + vertex 392.951 175.464 400.139 + vertex 393.578 181.091 402.326 + vertex 392.412 180.056 402.903 + endloop + endfacet + facet normal 0.745 -0.296846 0.597376 + outer loop + vertex 395.358 180.348 399.864 + vertex 394.844 184.37 402.504 + vertex 394.916 181.137 400.808 + endloop + endfacet + facet normal 0.732199 -0.303592 0.609686 + outer loop + vertex 394.916 181.137 400.808 + vertex 394.844 184.37 402.504 + vertex 394.276 183.993 402.998 + endloop + endfacet + facet normal 0.64376 -0.343354 0.683872 + outer loop + vertex 393.578 181.091 402.326 + vertex 393.264 185.45 404.81 + vertex 392.412 180.056 402.903 + endloop + endfacet + facet normal 0.61572 -0.347223 0.707337 + outer loop + vertex 392.412 180.056 402.903 + vertex 393.264 185.45 404.81 + vertex 391.857 184.12 405.381 + endloop + endfacet + facet normal 0.732394 -0.305337 0.608579 + outer loop + vertex 394.844 184.37 402.504 + vertex 394.362 186.888 404.347 + vertex 394.276 183.993 402.998 + endloop + endfacet + facet normal 0.715245 -0.312527 0.625102 + outer loop + vertex 394.276 183.993 402.998 + vertex 394.362 186.888 404.347 + vertex 393.928 187.469 405.134 + endloop + endfacet + facet normal 0.582122 -0.353913 0.732038 + outer loop + vertex 392.619 188.032 406.705 + vertex 392.228 189.172 407.568 + vertex 391.406 186.969 407.156 + endloop + endfacet + facet normal 0.550709 -0.347235 0.759044 + outer loop + vertex 391.406 186.969 407.156 + vertex 392.228 189.172 407.568 + vertex 390.884 188.076 408.04 + endloop + endfacet + facet normal 0.68355 -0.323776 0.654163 + outer loop + vertex 393.551 190.206 406.899 + vertex 393.373 190.389 407.176 + vertex 393.439 189.173 406.505 + endloop + endfacet + facet normal 0.648739 -0.340288 0.680693 + outer loop + vertex 393.439 189.173 406.505 + vertex 393.373 190.389 407.176 + vertex 393.046 189.929 407.257 + endloop + endfacet + facet normal 0.296327 -0.385505 0.873829 + outer loop + vertex 379.276 178.101 407.994 + vertex 379.669 176.424 407.121 + vertex 380.531 174.958 406.182 + endloop + endfacet + facet normal 0.278907 -0.194364 0.940443 + outer loop + vertex 414.112 113.742 367.718 + vertex 415.369 117.279 368.076 + vertex 413.394 117.131 368.631 + endloop + endfacet + facet normal 0.268677 -0.225893 0.936368 + outer loop + vertex 412.682 110.056 367.239 + vertex 414.112 113.742 367.718 + vertex 411.858 112.945 368.173 + endloop + endfacet + facet normal 0.199631 -0.333214 0.921475 + outer loop + vertex 382.349 182.943 409.413 + vertex 379.603 181.16 409.363 + vertex 381.344 181.86 409.239 + endloop + endfacet + facet normal 0.281567 -0.343786 0.895841 + outer loop + vertex 384.791 184.311 409.17 + vertex 382.349 182.943 409.413 + vertex 383.333 182.88 409.08 + endloop + endfacet + facet normal 0.331936 -0.338866 0.880334 + outer loop + vertex 387.537 185.981 408.778 + vertex 384.791 184.311 409.17 + vertex 385.644 183.982 408.722 + endloop + endfacet + facet normal 0.358784 -0.308484 0.880972 + outer loop + vertex 389.683 187.501 408.436 + vertex 387.537 185.981 408.778 + vertex 387.965 185.509 408.438 + endloop + endfacet + facet normal 0.375015 -0.154385 0.914073 + outer loop + vertex 391.647 189.103 407.901 + vertex 389.683 187.501 408.436 + vertex 390.884 188.076 408.04 + endloop + endfacet + facet normal 0.50582 -0.201151 0.838859 + outer loop + vertex 393.31 190.438 407.218 + vertex 391.647 189.103 407.901 + vertex 392.228 189.172 407.568 + endloop + endfacet + facet normal -0.535234 0.43792 -0.722323 + outer loop + vertex 393.936 188.976 405.868 + vertex 393.31 190.438 407.218 + vertex 393.551 190.206 406.899 + endloop + endfacet + facet normal 0.721459 -0.305458 0.621444 + outer loop + vertex 394.477 187.148 404.342 + vertex 393.936 188.976 405.868 + vertex 394.362 186.888 404.347 + endloop + endfacet + facet normal 0.726581 -0.309725 0.613311 + outer loop + vertex 394.85 185.361 402.997 + vertex 394.477 187.148 404.342 + vertex 394.844 184.37 402.504 + endloop + endfacet + facet normal 0.734816 -0.305836 0.605401 + outer loop + vertex 395.163 183.191 401.521 + vertex 394.85 185.361 402.997 + vertex 394.844 184.37 402.504 + endloop + endfacet + facet normal 0.760242 -0.287391 0.582614 + outer loop + vertex 395.437 181.217 400.189 + vertex 395.163 183.191 401.521 + vertex 395.358 180.348 399.864 + endloop + endfacet + facet normal 0.754669 -0.289239 0.58891 + outer loop + vertex 395.71 178.303 398.409 + vertex 395.437 181.217 400.189 + vertex 395.358 180.348 399.864 + endloop + endfacet + facet normal 0.808838 -0.246501 0.533871 + outer loop + vertex 395.89 176.087 397.113 + vertex 395.71 178.303 398.409 + vertex 395.788 175.694 397.085 + endloop + endfacet + facet normal 0.795854 -0.244583 0.553891 + outer loop + vertex 396.088 174.002 395.908 + vertex 395.89 176.087 397.113 + vertex 395.788 175.694 397.085 + endloop + endfacet + facet normal 0.879204 -0.169463 0.44529 + outer loop + vertex 396.266 172.133 394.844 + vertex 396.088 174.002 395.908 + vertex 396.29 170.827 394.3 + endloop + endfacet + facet normal 0.815781 -0.209619 0.539037 + outer loop + vertex 396.447 170.761 394.037 + vertex 396.266 172.133 394.844 + vertex 396.29 170.827 394.3 + endloop + endfacet + facet normal 0.81788 -0.202627 0.538529 + outer loop + vertex 396.655 168.813 392.988 + vertex 396.447 170.761 394.037 + vertex 396.29 170.827 394.3 + endloop + endfacet + facet normal 0.848182 -0.165082 0.503324 + outer loop + vertex 396.925 166.973 391.93 + vertex 396.655 168.813 392.988 + vertex 396.975 165.665 391.416 + endloop + endfacet + facet normal 0.837985 -0.171287 0.518114 + outer loop + vertex 397.105 165.489 391.147 + vertex 396.925 166.973 391.93 + vertex 396.975 165.665 391.416 + endloop + endfacet + facet normal 0.852697 -0.138434 0.503731 + outer loop + vertex 397.423 163.484 390.059 + vertex 397.105 165.489 391.147 + vertex 396.975 165.665 391.416 + endloop + endfacet + facet normal 0.904068 -0.0831316 0.419227 + outer loop + vertex 397.731 161.517 389.005 + vertex 397.423 163.484 390.059 + vertex 397.835 160.323 388.543 + endloop + endfacet + facet normal 0.826135 -0.138952 0.546071 + outer loop + vertex 398.019 160.067 388.199 + vertex 397.731 161.517 389.005 + vertex 397.835 160.323 388.543 + endloop + endfacet + facet normal 0.832102 -0.126522 0.539999 + outer loop + vertex 398.377 158.065 387.179 + vertex 398.019 160.067 388.199 + vertex 397.835 160.323 388.543 + endloop + endfacet + facet normal 0.794055 -0.144254 0.590481 + outer loop + vertex 398.85 155.936 386.023 + vertex 398.377 158.065 387.179 + vertex 398.858 154.964 385.774 + endloop + endfacet + facet normal 0.764941 -0.153486 0.625545 + outer loop + vertex 399.335 153.557 384.846 + vertex 398.85 155.936 386.023 + vertex 398.858 154.964 385.774 + endloop + endfacet + facet normal 0.800062 -0.107253 0.590253 + outer loop + vertex 399.798 151.815 383.902 + vertex 399.335 153.557 384.846 + vertex 400.087 150.02 383.183 + endloop + endfacet + facet normal 0.771293 -0.125409 0.624003 + outer loop + vertex 400.169 150.237 383.127 + vertex 399.798 151.815 383.902 + vertex 400.087 150.02 383.183 + endloop + endfacet + facet normal 0.75114 -0.110875 0.650765 + outer loop + vertex 400.799 148.227 382.057 + vertex 400.169 150.237 383.127 + vertex 400.087 150.02 383.183 + endloop + endfacet + facet normal 0.754528 -0.10265 0.64819 + outer loop + vertex 401.457 146.102 380.954 + vertex 400.799 148.227 382.057 + vertex 401.613 145.095 380.613 + endloop + endfacet + facet normal 0.670127 -0.142971 0.728347 + outer loop + vertex 402.216 144.013 379.846 + vertex 401.457 146.102 380.954 + vertex 401.613 145.095 380.613 + endloop + endfacet + facet normal 0.906209 0.118408 0.405912 + outer loop + vertex 402.9 142.13 378.868 + vertex 402.216 144.013 379.846 + vertex 403.339 140.773 378.284 + endloop + endfacet + facet normal 0.694908 -0.0826549 0.714332 + outer loop + vertex 403.501 140.775 378.126 + vertex 402.9 142.13 378.868 + vertex 403.339 140.773 378.284 + endloop + endfacet + facet normal 0.69573 -0.0640652 0.715441 + outer loop + vertex 404.302 138.928 377.182 + vertex 403.501 140.775 378.126 + vertex 403.339 140.773 378.284 + endloop + endfacet + facet normal 0.715674 -0.00184053 0.698432 + outer loop + vertex 405.311 137.108 376.144 + vertex 404.302 138.928 377.182 + vertex 405.474 136.454 375.974 + endloop + endfacet + facet normal 0.646871 -0.0355178 0.761772 + outer loop + vertex 406.464 135.08 375.07 + vertex 405.311 137.108 376.144 + vertex 405.474 136.454 375.974 + endloop + endfacet + facet normal 0.68282 0.0575783 0.728314 + outer loop + vertex 407.543 133.588 374.176 + vertex 406.464 135.08 375.07 + vertex 408.211 132.202 373.66 + endloop + endfacet + facet normal 0.601749 -0.00764604 0.798649 + outer loop + vertex 408.488 132.268 373.452 + vertex 407.543 133.588 374.176 + vertex 408.211 132.202 373.66 + endloop + endfacet + facet normal 0.589483 0.0646894 0.805186 + outer loop + vertex 409.934 130.705 372.518 + vertex 408.488 132.268 373.452 + vertex 408.211 132.202 373.66 + endloop + endfacet + facet normal 0.458975 -0.0870112 0.884178 + outer loop + vertex 411.463 129.122 371.569 + vertex 409.934 130.705 372.518 + vertex 411.447 128.463 371.512 + endloop + endfacet + facet normal 0.425292 -0.0875925 0.900808 + outer loop + vertex 412.808 127.919 370.817 + vertex 411.463 129.122 371.569 + vertex 411.447 128.463 371.512 + endloop + endfacet + facet normal 0.390888 -0.116836 0.912993 + outer loop + vertex 414.044 126.959 370.165 + vertex 412.808 127.919 370.817 + vertex 414.02 126.138 370.07 + endloop + endfacet + facet normal 0.260924 -0.199279 0.944567 + outer loop + vertex 413.394 117.131 368.631 + vertex 411.858 112.945 368.173 + vertex 414.112 113.742 367.718 + endloop + endfacet + facet normal 0.278546 -0.174577 0.944423 + outer loop + vertex 414.672 119.96 368.778 + vertex 413.394 117.131 368.631 + vertex 415.369 117.279 368.076 + endloop + endfacet + facet normal 0.372775 -0.120609 0.92005 + outer loop + vertex 414.02 126.138 370.07 + vertex 415.335 124.924 369.378 + vertex 414.946 126.712 369.77 + endloop + endfacet + facet normal 0.343239 -0.188967 0.920043 + outer loop + vertex 410.207 123.925 371.168 + vertex 412.663 121.987 369.854 + vertex 410.109 127.614 371.963 + endloop + endfacet + facet normal 0.42494 -0.0885624 0.900879 + outer loop + vertex 411.447 128.463 371.512 + vertex 414.02 126.138 370.07 + vertex 412.808 127.919 370.817 + endloop + endfacet + facet normal 0.375183 -0.171091 0.911025 + outer loop + vertex 412.855 125.53 370.44 + vertex 410.109 127.614 371.963 + vertex 412.663 121.987 369.854 + endloop + endfacet + facet normal 0.391527 -0.183723 0.901639 + outer loop + vertex 407.824 127.635 372.959 + vertex 410.207 123.925 371.168 + vertex 410.109 127.614 371.963 + endloop + endfacet + facet normal 0.550051 -0.00354591 0.835124 + outer loop + vertex 408.211 132.202 373.66 + vertex 411.447 128.463 371.512 + vertex 409.934 130.705 372.518 + endloop + endfacet + facet normal 0.390337 -0.197662 0.899203 + outer loop + vertex 410.109 127.614 371.963 + vertex 406.819 132.599 374.486 + vertex 407.824 127.635 372.959 + endloop + endfacet + facet normal 0.465373 -0.172893 0.868064 + outer loop + vertex 404.773 133.118 375.687 + vertex 407.824 127.635 372.959 + vertex 406.819 132.599 374.486 + endloop + endfacet + facet normal 0.8085 0.224095 0.54416 + outer loop + vertex 405.474 136.454 375.974 + vertex 408.211 132.202 373.66 + vertex 406.464 135.08 375.07 + endloop + endfacet + facet normal 0.459956 -0.191753 0.86699 + outer loop + vertex 406.819 132.599 374.486 + vertex 404.611 136.945 376.62 + vertex 404.773 133.118 375.687 + endloop + endfacet + facet normal 0.50433 -0.198302 0.840433 + outer loop + vertex 402.143 137.629 378.329 + vertex 404.773 133.118 375.687 + vertex 402.881 140.066 378.461 + endloop + endfacet + facet normal 0.890051 0.22946 0.393901 + outer loop + vertex 403.339 140.773 378.284 + vertex 405.474 136.454 375.974 + vertex 404.302 138.928 377.182 + endloop + endfacet + facet normal 0.552094 -0.175207 0.815165 + outer loop + vertex 404.611 136.945 376.62 + vertex 402.881 140.066 378.461 + vertex 404.773 133.118 375.687 + endloop + endfacet + facet normal 0.554976 -0.21359 0.803978 + outer loop + vertex 400.214 142.402 380.929 + vertex 402.143 137.629 378.329 + vertex 401.064 144.517 380.904 + endloop + endfacet + facet normal 0.730999 -0.073682 0.678388 + outer loop + vertex 401.613 145.095 380.613 + vertex 403.339 140.773 378.284 + vertex 402.216 144.013 379.846 + endloop + endfacet + facet normal 0.557927 -0.212474 0.80223 + outer loop + vertex 402.881 140.066 378.461 + vertex 401.064 144.517 380.904 + vertex 402.143 137.629 378.329 + endloop + endfacet + facet normal 0.601178 -0.225322 0.766691 + outer loop + vertex 398.718 147.252 383.528 + vertex 400.214 142.402 380.929 + vertex 399.537 149.498 383.545 + endloop + endfacet + facet normal 0.771109 -0.0900887 0.630297 + outer loop + vertex 400.087 150.02 383.183 + vertex 401.613 145.095 380.613 + vertex 400.799 148.227 382.057 + endloop + endfacet + facet normal 0.591559 -0.228629 0.773167 + outer loop + vertex 401.064 144.517 380.904 + vertex 399.537 149.498 383.545 + vertex 400.214 142.402 380.929 + endloop + endfacet + facet normal 0.617914 -0.243397 0.747623 + outer loop + vertex 397.608 151.021 385.672 + vertex 398.718 147.252 383.528 + vertex 398.152 155.054 386.535 + endloop + endfacet + facet normal 0.829892 -0.0828082 0.551745 + outer loop + vertex 398.858 154.964 385.774 + vertex 400.087 150.02 383.183 + vertex 399.335 153.557 384.846 + endloop + endfacet + facet normal 0.634917 -0.237378 0.735208 + outer loop + vertex 399.537 149.498 383.545 + vertex 398.152 155.054 386.535 + vertex 398.718 147.252 383.528 + endloop + endfacet + facet normal 0.669222 -0.240762 0.702976 + outer loop + vertex 396.824 157.365 388.591 + vertex 397.608 151.021 385.672 + vertex 398.152 155.054 386.535 + endloop + endfacet + facet normal 0.868924 -0.0859317 0.487429 + outer loop + vertex 397.835 160.323 388.543 + vertex 398.858 154.964 385.774 + vertex 398.377 158.065 387.179 + endloop + endfacet + facet normal 0.665348 -0.244965 0.705198 + outer loop + vertex 398.152 155.054 386.535 + vertex 397.285 161.309 389.526 + vertex 396.824 157.365 388.591 + endloop + endfacet + facet normal 0.654735 -0.268125 0.706704 + outer loop + vertex 395.828 161.182 390.962 + vertex 396.824 157.365 388.591 + vertex 396.394 165.438 392.052 + endloop + endfacet + facet normal 0.880555 -0.106608 0.461797 + outer loop + vertex 396.975 165.665 391.416 + vertex 397.835 160.323 388.543 + vertex 397.423 163.484 390.059 + endloop + endfacet + facet normal 0.726333 -0.237815 0.644891 + outer loop + vertex 397.285 161.309 389.526 + vertex 396.394 165.438 392.052 + vertex 396.824 157.365 388.591 + endloop + endfacet + facet normal 0.702483 -0.262857 0.66138 + outer loop + vertex 395.34 166.294 393.512 + vertex 395.828 161.182 390.962 + vertex 396.394 165.438 392.052 + endloop + endfacet + facet normal 0.877493 -0.139843 0.458749 + outer loop + vertex 396.29 170.827 394.3 + vertex 396.975 165.665 391.416 + vertex 396.655 168.813 392.988 + endloop + endfacet + facet normal 0.692142 -0.281263 0.664704 + outer loop + vertex 396.394 165.438 392.052 + vertex 395.728 171.654 395.376 + vertex 395.34 166.294 393.512 + endloop + endfacet + facet normal 0.72527 -0.272397 0.632284 + outer loop + vertex 394.812 171.834 396.504 + vertex 395.34 166.294 393.512 + vertex 395.728 171.654 395.376 + endloop + endfacet + facet normal 0.840884 -0.200903 0.502546 + outer loop + vertex 395.788 175.694 397.085 + vertex 396.29 170.827 394.3 + vertex 396.088 174.002 395.908 + endloop + endfacet + facet normal 0.719506 -0.291012 0.630573 + outer loop + vertex 395.728 171.654 395.376 + vertex 395.254 176.864 398.322 + vertex 394.812 171.834 396.504 + endloop + endfacet + facet normal 0.736491 -0.286133 0.612951 + outer loop + vertex 394.31 177.751 399.87 + vertex 394.812 171.834 396.504 + vertex 395.254 176.864 398.322 + endloop + endfacet + facet normal 0.793844 -0.255959 0.551631 + outer loop + vertex 395.358 180.348 399.864 + vertex 395.788 175.694 397.085 + vertex 395.71 178.303 398.409 + endloop + endfacet + facet normal 0.72787 -0.300913 0.616163 + outer loop + vertex 395.254 176.864 398.322 + vertex 394.916 181.137 400.808 + vertex 394.31 177.751 399.87 + endloop + endfacet + facet normal 0.700328 -0.316789 0.639676 + outer loop + vertex 393.578 181.091 402.326 + vertex 394.31 177.751 399.87 + vertex 394.276 183.993 402.998 + endloop + endfacet + facet normal 0.74346 -0.297942 0.598747 + outer loop + vertex 394.844 184.37 402.504 + vertex 395.358 180.348 399.864 + vertex 395.163 183.191 401.521 + endloop + endfacet + facet normal 0.736862 -0.299704 0.60598 + outer loop + vertex 394.916 181.137 400.808 + vertex 394.276 183.993 402.998 + vertex 394.31 177.751 399.87 + endloop + endfacet + facet normal 0.696364 -0.31683 0.643969 + outer loop + vertex 393.264 185.45 404.81 + vertex 393.578 181.091 402.326 + vertex 394.276 183.993 402.998 + endloop + endfacet + facet normal 0.6211 -0.357064 0.697668 + outer loop + vertex 391.857 184.12 405.381 + vertex 393.264 185.45 404.81 + vertex 392.619 188.032 406.705 + endloop + endfacet + facet normal 0.728173 -0.30863 0.611973 + outer loop + vertex 394.362 186.888 404.347 + vertex 394.844 184.37 402.504 + vertex 394.477 187.148 404.342 + endloop + endfacet + facet normal 0.685868 -0.329927 0.64864 + outer loop + vertex 394.276 183.993 402.998 + vertex 393.928 187.469 405.134 + vertex 393.264 185.45 404.81 + endloop + endfacet + facet normal 0.719007 -0.307348 0.623351 + outer loop + vertex 393.928 187.469 405.134 + vertex 394.362 186.888 404.347 + vertex 393.936 188.976 405.868 + endloop + endfacet + facet normal 0.272328 -0.393673 0.877986 + outer loop + vertex 381.344 181.86 409.239 + vertex 383.333 182.88 409.08 + vertex 382.349 182.943 409.413 + endloop + endfacet + facet normal 0.313751 -0.375086 0.872279 + outer loop + vertex 383.333 182.88 409.08 + vertex 385.644 183.982 408.722 + vertex 384.791 184.311 409.17 + endloop + endfacet + facet normal 0.329185 -0.336317 0.882342 + outer loop + vertex 385.644 183.982 408.722 + vertex 387.965 185.509 408.438 + vertex 387.537 185.981 408.778 + endloop + endfacet + facet normal 0.315227 -0.270909 0.909527 + outer loop + vertex 387.965 185.509 408.438 + vertex 389.577 186.828 408.272 + vertex 389.683 187.501 408.436 + endloop + endfacet + facet normal 0.417308 -0.276231 0.865766 + outer loop + vertex 389.577 186.828 408.272 + vertex 390.884 188.076 408.04 + vertex 389.683 187.501 408.436 + endloop + endfacet + facet normal 0.594422 -0.345305 0.726241 + outer loop + vertex 392.228 189.172 407.568 + vertex 392.619 188.032 406.705 + vertex 393.046 189.929 407.257 + endloop + endfacet + facet normal 0.585304 -0.359871 0.726575 + outer loop + vertex 392.619 188.032 406.705 + vertex 391.406 186.969 407.156 + vertex 391.857 184.12 405.381 + endloop + endfacet + facet normal 0.503965 -0.262492 0.822871 + outer loop + vertex 390.884 188.076 408.04 + vertex 392.228 189.172 407.568 + vertex 391.647 189.103 407.901 + endloop + endfacet + facet normal 0.501114 0.834812 -0.227979 + outer loop + vertex 393.373 190.389 407.176 + vertex 393.551 190.206 406.899 + vertex 393.31 190.438 407.218 + endloop + endfacet + facet normal 0.696125 -0.320642 0.642338 + outer loop + vertex 393.551 190.206 406.899 + vertex 393.439 189.173 406.505 + vertex 393.936 188.976 405.868 + endloop + endfacet + facet normal 0.645023 -0.343916 0.682398 + outer loop + vertex 393.439 189.173 406.505 + vertex 393.046 189.929 407.257 + vertex 392.619 188.032 406.705 + endloop + endfacet + facet normal 0.45886 -0.171221 0.871855 + outer loop + vertex 393.046 189.929 407.257 + vertex 393.373 190.389 407.176 + vertex 393.31 190.438 407.218 + endloop + endfacet + facet normal 0.499753 -0.194534 0.84404 + outer loop + vertex 393.31 190.438 407.218 + vertex 392.228 189.172 407.568 + vertex 393.046 189.929 407.257 + endloop + endfacet + facet normal 0.643242 -0.342193 0.684941 + outer loop + vertex 392.619 188.032 406.705 + vertex 393.264 185.45 404.81 + vertex 393.439 189.173 406.505 + endloop + endfacet + facet normal 0.682185 -0.32938 0.652789 + outer loop + vertex 393.264 185.45 404.81 + vertex 393.928 187.469 405.134 + vertex 393.439 189.173 406.505 + endloop + endfacet + facet normal 0.697893 -0.31655 0.642449 + outer loop + vertex 393.928 187.469 405.134 + vertex 393.936 188.976 405.868 + vertex 393.439 189.173 406.505 + endloop + endfacet + facet normal -0.430517 -0.205261 0.878933 + outer loop + vertex -403.36 129.016 375.403 + vertex -404.775 131.237 375.228 + vertex -406.02 125.464 373.271 + endloop + endfacet + facet normal -0.416444 -0.210192 0.88453 + outer loop + vertex -406.02 125.464 373.271 + vertex -404.775 131.237 375.228 + vertex -407.388 128.895 373.442 + endloop + endfacet + facet normal -0.481383 -0.216168 0.849436 + outer loop + vertex -400.97 133.964 378.016 + vertex -402.707 135.949 377.537 + vertex -403.36 129.016 375.403 + endloop + endfacet + facet normal -0.455453 -0.222481 0.862012 + outer loop + vertex -403.36 129.016 375.403 + vertex -402.707 135.949 377.537 + vertex -404.775 131.237 375.228 + endloop + endfacet + facet normal -0.52577 -0.232004 0.818376 + outer loop + vertex -398.993 139.165 380.761 + vertex -400.559 142.373 380.664 + vertex -400.97 133.964 378.016 + endloop + endfacet + facet normal -0.501057 -0.237556 0.832171 + outer loop + vertex -400.97 133.964 378.016 + vertex -400.559 142.373 380.664 + vertex -402.707 135.949 377.537 + endloop + endfacet + facet normal -0.562366 -0.248223 0.788752 + outer loop + vertex -397.492 144.058 383.371 + vertex -398.763 147.288 383.482 + vertex -398.993 139.165 380.761 + endloop + endfacet + facet normal -0.558966 -0.249041 0.790908 + outer loop + vertex -398.993 139.165 380.761 + vertex -398.763 147.288 383.482 + vertex -400.559 142.373 380.664 + endloop + endfacet + facet normal -0.596799 -0.258447 0.759629 + outer loop + vertex -396.377 149.324 386.039 + vertex -397.597 151.005 385.652 + vertex -397.492 144.058 383.371 + endloop + endfacet + facet normal -0.592832 -0.259309 0.762436 + outer loop + vertex -397.492 144.058 383.371 + vertex -397.597 151.005 385.652 + vertex -398.763 147.288 383.482 + endloop + endfacet + facet normal -0.625189 -0.266333 0.733625 + outer loop + vertex -395.423 154.919 388.883 + vertex -396.834 157.532 388.629 + vertex -396.377 149.324 386.039 + endloop + endfacet + facet normal -0.607986 -0.26953 0.746798 + outer loop + vertex -396.377 149.324 386.039 + vertex -396.834 157.532 388.629 + vertex -397.597 151.005 385.652 + endloop + endfacet + facet normal -0.63349 -0.282356 0.720393 + outer loop + vertex -394.588 160.032 391.621 + vertex -395.808 162.882 391.665 + vertex -395.423 154.919 388.883 + endloop + endfacet + facet normal -0.645549 -0.279556 0.710714 + outer loop + vertex -395.423 154.919 388.883 + vertex -395.808 162.882 391.665 + vertex -396.834 157.532 388.629 + endloop + endfacet + facet normal -0.650556 -0.293456 0.700472 + outer loop + vertex -393.974 165.02 394.282 + vertex -395.093 166.442 393.838 + vertex -394.588 160.032 391.621 + endloop + endfacet + facet normal -0.65708 -0.292058 0.694945 + outer loop + vertex -394.588 160.032 391.621 + vertex -395.093 166.442 393.838 + vertex -395.808 162.882 391.665 + endloop + endfacet + facet normal -0.667522 -0.304313 0.679565 + outer loop + vertex -393.486 170.23 397.094 + vertex -394.773 171.395 396.351 + vertex -393.974 165.02 394.282 + endloop + endfacet + facet normal -0.660209 -0.305527 0.686132 + outer loop + vertex -393.974 165.02 394.282 + vertex -394.773 171.395 396.351 + vertex -395.093 166.442 393.838 + endloop + endfacet + facet normal -0.666932 -0.319193 0.673288 + outer loop + vertex -392.974 175.338 400.022 + vertex -394.313 176.57 399.281 + vertex -393.486 170.23 397.094 + endloop + endfacet + facet normal -0.673097 -0.318058 0.667667 + outer loop + vertex -393.486 170.23 397.094 + vertex -394.313 176.57 399.281 + vertex -394.773 171.395 396.351 + endloop + endfacet + facet normal -0.648496 -0.334608 0.683733 + outer loop + vertex -392.347 179.973 402.885 + vertex -393.749 181.21 402.161 + vertex -392.974 175.338 400.022 + endloop + endfacet + facet normal -0.671547 -0.330216 0.663312 + outer loop + vertex -392.974 175.338 400.022 + vertex -393.749 181.21 402.161 + vertex -394.313 176.57 399.281 + endloop + endfacet + facet normal -0.60577 -0.351509 0.713782 + outer loop + vertex -391.502 183.426 405.303 + vertex -393.051 185.382 404.952 + vertex -392.347 179.973 402.885 + endloop + endfacet + facet normal -0.65206 -0.343125 0.67608 + outer loop + vertex -392.347 179.973 402.885 + vertex -393.051 185.382 404.952 + vertex -393.749 181.21 402.161 + endloop + endfacet + facet normal -0.56338 -0.351469 0.747712 + outer loop + vertex -391.035 187.987 407.89 + vertex -392.56 189.423 407.416 + vertex -392.013 187.251 406.807 + endloop + endfacet + facet normal -0.604619 -0.352482 0.714278 + outer loop + vertex -392.013 187.251 406.807 + vertex -392.56 189.423 407.416 + vertex -393.017 188.475 406.561 + endloop + endfacet + facet normal -0.413256 -0.137073 0.900239 + outer loop + vertex -409.642 128.76 372.38 + vertex -411.322 128.529 371.573 + vertex -412.741 124.714 370.341 + endloop + endfacet + facet normal -0.371362 -0.15744 0.915043 + outer loop + vertex -412.741 124.714 370.341 + vertex -411.322 128.529 371.573 + vertex -413.967 126.075 370.077 + endloop + endfacet + facet normal -0.487438 -0.118407 0.865092 + outer loop + vertex -407.099 132.658 374.346 + vertex -408.201 132.293 373.675 + vertex -409.642 128.76 372.38 + endloop + endfacet + facet normal -0.408699 -0.162611 0.898066 + outer loop + vertex -409.642 128.76 372.38 + vertex -408.201 132.293 373.675 + vertex -411.322 128.529 371.573 + endloop + endfacet + facet normal -0.51745 -0.141699 0.8439 + outer loop + vertex -404.698 135.646 376.32 + vertex -405.572 136.212 375.879 + vertex -407.099 132.658 374.346 + endloop + endfacet + facet normal -0.470252 -0.171395 0.865729 + outer loop + vertex -407.099 132.658 374.346 + vertex -405.572 136.212 375.879 + vertex -408.201 132.293 373.675 + endloop + endfacet + facet normal -0.589237 -0.150629 0.793795 + outer loop + vertex -402.238 141.501 379.257 + vertex -403.324 140.765 378.311 + vertex -404.698 135.646 376.32 + endloop + endfacet + facet normal -0.532914 -0.178695 0.827086 + outer loop + vertex -404.698 135.646 376.32 + vertex -403.324 140.765 378.311 + vertex -405.572 136.212 375.879 + endloop + endfacet + facet normal -0.623398 -0.177534 0.761484 + outer loop + vertex -400.777 146.348 381.583 + vertex -401.516 145.589 380.801 + vertex -402.238 141.501 379.257 + endloop + endfacet + facet normal -0.560594 -0.204126 0.802538 + outer loop + vertex -402.238 141.501 379.257 + vertex -401.516 145.589 380.801 + vertex -403.324 140.765 378.311 + endloop + endfacet + facet normal -0.66231 -0.188469 0.725137 + outer loop + vertex -399.543 149.816 383.611 + vertex -400.063 150.306 383.264 + vertex -400.777 146.348 381.583 + endloop + endfacet + facet normal -0.591574 -0.222406 0.774968 + outer loop + vertex -400.777 146.348 381.583 + vertex -400.063 150.306 383.264 + vertex -401.516 145.589 380.801 + endloop + endfacet + facet normal -0.703981 -0.192235 0.683708 + outer loop + vertex -398.15 155.049 386.517 + vertex -398.846 154.971 385.779 + vertex -399.543 149.816 383.611 + endloop + endfacet + facet normal -0.67152 -0.208161 0.711146 + outer loop + vertex -399.543 149.816 383.611 + vertex -398.846 154.971 385.779 + vertex -400.063 150.306 383.264 + endloop + endfacet + facet normal -0.757958 -0.193489 0.622946 + outer loop + vertex -397.315 161.175 389.436 + vertex -397.819 160.225 388.528 + vertex -398.15 155.049 386.517 + endloop + endfacet + facet normal -0.698259 -0.219951 0.681217 + outer loop + vertex -398.15 155.049 386.517 + vertex -397.819 160.225 388.528 + vertex -398.846 154.971 385.779 + endloop + endfacet + facet normal -0.763057 -0.211752 0.610659 + outer loop + vertex -396.571 165.197 391.76 + vertex -396.991 165.508 391.343 + vertex -397.315 161.175 389.436 + endloop + endfacet + facet normal -0.72955 -0.229103 0.644413 + outer loop + vertex -397.315 161.175 389.436 + vertex -396.991 165.508 391.343 + vertex -397.819 160.225 388.528 + endloop + endfacet + facet normal -0.768694 -0.230638 0.596587 + outer loop + vertex -395.752 170.309 394.791 + vertex -396.33 170.564 394.146 + vertex -396.571 165.197 391.76 + endloop + endfacet + facet normal -0.766415 -0.231835 0.599049 + outer loop + vertex -396.571 165.197 391.76 + vertex -396.33 170.564 394.146 + vertex -396.991 165.508 391.343 + endloop + endfacet + facet normal -0.776918 -0.251928 0.577002 + outer loop + vertex -395.242 176.443 398.157 + vertex -395.811 175.47 396.965 + vertex -395.752 170.309 394.791 + endloop + endfacet + facet normal -0.768519 -0.255816 0.586461 + outer loop + vertex -395.752 170.309 394.791 + vertex -395.811 175.47 396.965 + vertex -396.33 170.564 394.146 + endloop + endfacet + facet normal -0.748457 -0.285853 0.598415 + outer loop + vertex -394.74 181.248 401.079 + vertex -395.358 180.375 399.89 + vertex -395.242 176.443 398.157 + endloop + endfacet + facet normal -0.754684 -0.283143 0.591847 + outer loop + vertex -395.242 176.443 398.157 + vertex -395.358 180.375 399.89 + vertex -395.811 175.47 396.965 + endloop + endfacet + facet normal -0.717851 -0.310687 0.623028 + outer loop + vertex -394.182 185.13 403.659 + vertex -394.824 184.573 402.641 + vertex -394.74 181.248 401.079 + endloop + endfacet + facet normal -0.736835 -0.302513 0.604616 + outer loop + vertex -394.74 181.248 401.079 + vertex -394.824 184.573 402.641 + vertex -395.358 180.375 399.89 + endloop + endfacet + facet normal -0.698505 -0.322827 0.63865 + outer loop + vertex -393.71 187.972 405.611 + vertex -394.296 187.151 404.555 + vertex -394.182 185.13 403.659 + endloop + endfacet + facet normal -0.713951 -0.317288 0.624181 + outer loop + vertex -394.182 185.13 403.659 + vertex -394.296 187.151 404.555 + vertex -394.824 184.573 402.641 + endloop + endfacet + facet normal -0.653995 -0.332077 0.679717 + outer loop + vertex -393.173 190.34 407.336 + vertex -393.346 190.476 407.235 + vertex -393.352 189.787 406.893 + endloop + endfacet + facet normal -0.693752 -0.315688 0.647341 + outer loop + vertex -393.352 189.787 406.893 + vertex -393.346 190.476 407.235 + vertex -393.49 190.2 406.947 + endloop + endfacet + facet normal -0.255432 -0.399089 0.880615 + outer loop + vertex -379.966 174.862 406.307 + vertex -378.776 177.36 407.784 + vertex -380.575 174.86 406.129 + endloop + endfacet + facet normal -0.268825 -0.225564 0.936405 + outer loop + vertex -414.105 113.744 367.718 + vertex -412.68 110.05 367.237 + vertex -411.856 112.921 368.165 + endloop + endfacet + facet normal -0.281381 -0.193581 0.939868 + outer loop + vertex -415.325 117.444 368.115 + vertex -414.105 113.744 367.718 + vertex -413.36 117.016 368.615 + endloop + endfacet + facet normal -0.429256 -0.0838952 0.899278 + outer loop + vertex -411.405 129.137 371.59 + vertex -412.735 127.907 370.84 + vertex -411.322 128.529 371.573 + endloop + endfacet + facet normal -0.46253 -0.0879563 0.88223 + outer loop + vertex -409.914 130.744 372.532 + vertex -411.405 129.137 371.59 + vertex -411.322 128.529 371.573 + endloop + endfacet + facet normal -0.615074 0.103395 0.781661 + outer loop + vertex -408.487 132.274 373.452 + vertex -409.914 130.744 372.532 + vertex -408.201 132.293 373.675 + endloop + endfacet + facet normal -0.614285 0.00336533 0.789077 + outer loop + vertex -407.551 133.587 374.176 + vertex -408.487 132.274 373.452 + vertex -408.201 132.293 373.675 + endloop + endfacet + facet normal -0.677767 0.0569062 0.733071 + outer loop + vertex -406.497 135 375.04 + vertex -407.551 133.587 374.176 + vertex -408.201 132.293 373.675 + endloop + endfacet + facet normal -0.636111 -0.0474705 0.770136 + outer loop + vertex -405.352 137.019 376.11 + vertex -406.497 135 375.04 + vertex -405.572 136.212 375.879 + endloop + endfacet + facet normal -0.713649 -0.00634563 0.700474 + outer loop + vertex -404.361 138.829 377.136 + vertex -405.352 137.019 376.11 + vertex -405.572 136.212 375.879 + endloop + endfacet + facet normal -0.704789 -0.0517613 0.707526 + outer loop + vertex -403.537 140.707 378.095 + vertex -404.361 138.829 377.136 + vertex -403.324 140.765 378.311 + endloop + endfacet + facet normal -0.700055 -0.0775352 0.709868 + outer loop + vertex -402.948 142.061 378.823 + vertex -403.537 140.707 378.095 + vertex -403.324 140.765 378.311 + endloop + endfacet + facet normal -0.875702 0.0649262 0.478466 + outer loop + vertex -402.259 144.03 379.818 + vertex -402.948 142.061 378.823 + vertex -403.324 140.765 378.311 + endloop + endfacet + facet normal -0.671726 -0.138892 0.727663 + outer loop + vertex -401.495 146.172 380.932 + vertex -402.259 144.03 379.818 + vertex -401.516 145.589 380.801 + endloop + endfacet + facet normal -0.723046 -0.126086 0.679196 + outer loop + vertex -400.825 148.282 382.037 + vertex -401.495 146.172 380.932 + vertex -401.516 145.589 380.801 + endloop + endfacet + facet normal -0.760088 -0.10282 0.641634 + outer loop + vertex -400.207 150.236 383.082 + vertex -400.825 148.282 382.037 + vertex -400.063 150.306 383.264 + endloop + endfacet + facet normal -0.74945 -0.139618 0.647172 + outer loop + vertex -399.814 151.751 383.864 + vertex -400.207 150.236 383.082 + vertex -400.063 150.306 383.264 + endloop + endfacet + facet normal -0.794156 -0.111264 0.597442 + outer loop + vertex -399.334 153.501 384.827 + vertex -399.814 151.751 383.864 + vertex -400.063 150.306 383.264 + endloop + endfacet + facet normal -0.750531 -0.164796 0.639957 + outer loop + vertex -398.843 155.793 385.994 + vertex -399.334 153.501 384.827 + vertex -398.846 154.971 385.779 + endloop + endfacet + facet normal -0.778603 -0.156235 0.607756 + outer loop + vertex -398.357 157.937 387.167 + vertex -398.843 155.793 385.994 + vertex -398.846 154.971 385.779 + endloop + endfacet + facet normal -0.806336 -0.150416 0.572011 + outer loop + vertex -398.006 159.979 388.199 + vertex -398.357 157.937 387.167 + vertex -397.819 160.225 388.528 + endloop + endfacet + facet normal -0.801278 -0.160189 0.576449 + outer loop + vertex -397.712 161.47 389.023 + vertex -398.006 159.979 388.199 + vertex -397.819 160.225 388.528 + endloop + endfacet + facet normal -0.890056 -0.100228 0.444697 + outer loop + vertex -397.407 163.466 390.083 + vertex -397.712 161.47 389.023 + vertex -397.819 160.225 388.528 + endloop + endfacet + facet normal -0.847859 -0.142623 0.51068 + outer loop + vertex -397.085 165.476 391.179 + vertex -397.407 163.466 390.083 + vertex -396.991 165.508 391.343 + endloop + endfacet + facet normal -0.842038 -0.168284 0.512496 + outer loop + vertex -396.906 166.985 391.968 + vertex -397.085 165.476 391.179 + vertex -396.991 165.508 391.343 + endloop + endfacet + facet normal -0.848788 -0.163765 0.502733 + outer loop + vertex -396.654 168.746 392.967 + vertex -396.906 166.985 391.968 + vertex -396.991 165.508 391.343 + endloop + endfacet + facet normal -0.827964 -0.193613 0.526297 + outer loop + vertex -396.452 170.779 394.032 + vertex -396.654 168.746 392.967 + vertex -396.33 170.564 394.146 + endloop + endfacet + facet normal -0.82991 -0.197006 0.521956 + outer loop + vertex -396.284 172.14 394.813 + vertex -396.452 170.779 394.032 + vertex -396.33 170.564 394.146 + endloop + endfacet + facet normal -0.902398 -0.145569 0.40557 + outer loop + vertex -396.109 174.021 395.878 + vertex -396.284 172.14 394.813 + vertex -396.33 170.564 394.146 + endloop + endfacet + facet normal -0.818922 -0.22718 0.527026 + outer loop + vertex -395.91 176.127 397.095 + vertex -396.109 174.021 395.878 + vertex -395.811 175.47 396.965 + endloop + endfacet + facet normal -0.838065 -0.224177 0.497385 + outer loop + vertex -395.727 178.331 398.396 + vertex -395.91 176.127 397.095 + vertex -395.811 175.47 396.965 + endloop + endfacet + facet normal -0.771699 -0.278395 0.571819 + outer loop + vertex -395.465 181.239 400.166 + vertex -395.727 178.331 398.396 + vertex -395.358 180.375 399.89 + endloop + endfacet + facet normal -0.775946 -0.277255 0.566602 + outer loop + vertex -395.193 183.239 401.517 + vertex -395.465 181.239 400.166 + vertex -395.358 180.375 399.89 + endloop + endfacet + facet normal -0.733923 -0.307294 0.605745 + outer loop + vertex -394.877 185.344 402.968 + vertex -395.193 183.239 401.517 + vertex -394.824 184.573 402.641 + endloop + endfacet + facet normal -0.72598 -0.310162 0.613802 + outer loop + vertex -394.473 187.11 404.338 + vertex -394.877 185.344 402.968 + vertex -394.824 184.573 402.641 + endloop + endfacet + facet normal -0.705689 -0.315536 0.634382 + outer loop + vertex -393.876 188.997 405.941 + vertex -394.473 187.11 404.338 + vertex -394.296 187.151 404.555 + endloop + endfacet + facet normal 0.0355592 0.634263 -0.7723 + outer loop + vertex -393.313 190.556 407.248 + vertex -393.876 188.997 405.941 + vertex -393.49 190.2 406.947 + endloop + endfacet + facet normal -0.501642 -0.20826 0.839633 + outer loop + vertex -391.408 188.843 407.961 + vertex -393.313 190.556 407.248 + vertex -392.56 189.423 407.416 + endloop + endfacet + facet normal -0.441799 -0.263121 0.85766 + outer loop + vertex -389.471 187.345 408.499 + vertex -391.408 188.843 407.961 + vertex -391.035 187.987 407.89 + endloop + endfacet + facet normal -0.344642 -0.283392 0.894936 + outer loop + vertex -387.111 185.759 408.905 + vertex -389.471 187.345 408.499 + vertex -388.037 185.809 408.565 + endloop + endfacet + facet normal -0.341469 -0.363901 0.866588 + outer loop + vertex -384.984 184.375 409.163 + vertex -387.111 185.759 408.905 + vertex -385.892 184.181 408.723 + endloop + endfacet + facet normal -0.289387 -0.375469 0.880499 + outer loop + vertex -382.943 183.249 409.353 + vertex -384.984 184.375 409.163 + vertex -383.749 182.945 408.958 + endloop + endfacet + facet normal -0.188103 -0.300122 0.935171 + outer loop + vertex -379.621 181.232 409.374 + vertex -382.943 183.249 409.353 + vertex -381.751 182.027 409.201 + endloop + endfacet + facet normal -0.283845 -0.386368 0.877583 + outer loop + vertex -383.749 182.945 408.958 + vertex -381.751 182.027 409.201 + vertex -382.943 183.249 409.353 + endloop + endfacet + facet normal -0.326939 -0.404129 0.854278 + outer loop + vertex -385.892 184.181 408.723 + vertex -383.749 182.945 408.958 + vertex -384.984 184.375 409.163 + endloop + endfacet + facet normal -0.339129 -0.362277 0.868186 + outer loop + vertex -388.037 185.809 408.565 + vertex -385.892 184.181 408.723 + vertex -387.111 185.759 408.905 + endloop + endfacet + facet normal -0.380216 -0.317747 0.868604 + outer loop + vertex -389.617 186.795 408.234 + vertex -388.037 185.809 408.565 + vertex -389.471 187.345 408.499 + endloop + endfacet + facet normal -0.260905 -0.199516 0.944522 + outer loop + vertex -411.856 112.921 368.165 + vertex -413.36 117.016 368.615 + vertex -414.105 113.744 367.718 + endloop + endfacet + facet normal -0.447894 -0.288901 0.846125 + outer loop + vertex -391.035 187.987 407.89 + vertex -389.617 186.795 408.234 + vertex -389.471 187.345 408.499 + endloop + endfacet + facet normal -0.278741 -0.176677 0.943975 + outer loop + vertex -413.36 117.016 368.615 + vertex -414.421 120.659 368.984 + vertex -415.325 117.444 368.115 + endloop + endfacet + facet normal -0.360754 -0.176293 0.915848 + outer loop + vertex -412.666 120.773 369.612 + vertex -410.547 124.355 371.136 + vertex -412.741 124.714 370.341 + endloop + endfacet + facet normal -0.412004 -0.168167 0.895529 + outer loop + vertex -410.547 124.355 371.136 + vertex -407.388 128.895 373.442 + vertex -409.642 128.76 372.38 + endloop + endfacet + facet normal -0.415222 -0.211717 0.884741 + outer loop + vertex -407.388 128.895 373.442 + vertex -404.775 131.237 375.228 + vertex -404.698 135.646 376.32 + endloop + endfacet + facet normal -0.488529 -0.201563 0.848948 + outer loop + vertex -404.775 131.237 375.228 + vertex -402.707 135.949 377.537 + vertex -404.698 135.646 376.32 + endloop + endfacet + facet normal -0.566589 -0.199705 0.799434 + outer loop + vertex -402.707 135.949 377.537 + vertex -400.559 142.373 380.664 + vertex -402.238 141.501 379.257 + endloop + endfacet + facet normal -0.596685 -0.223662 0.770677 + outer loop + vertex -400.559 142.373 380.664 + vertex -398.763 147.288 383.482 + vertex -399.543 149.816 383.611 + endloop + endfacet + facet normal -0.615715 -0.244358 0.749122 + outer loop + vertex -398.763 147.288 383.482 + vertex -397.597 151.005 385.652 + vertex -398.15 155.049 386.517 + endloop + endfacet + facet normal -0.670255 -0.241672 0.701679 + outer loop + vertex -397.597 151.005 385.652 + vertex -396.834 157.532 388.629 + vertex -398.15 155.049 386.517 + endloop + endfacet + facet normal -0.687337 -0.254315 0.680361 + outer loop + vertex -396.834 157.532 388.629 + vertex -395.808 162.882 391.665 + vertex -396.571 165.197 391.76 + endloop + endfacet + facet normal -0.670946 -0.283349 0.685234 + outer loop + vertex -395.808 162.882 391.665 + vertex -395.093 166.442 393.838 + vertex -395.752 170.309 394.791 + endloop + endfacet + facet normal -0.713153 -0.280044 0.642642 + outer loop + vertex -395.093 166.442 393.838 + vertex -394.773 171.395 396.351 + vertex -395.752 170.309 394.791 + endloop + endfacet + facet normal -0.720624 -0.291874 0.628897 + outer loop + vertex -394.773 171.395 396.351 + vertex -394.313 176.57 399.281 + vertex -395.242 176.443 398.157 + endloop + endfacet + facet normal -0.706484 -0.309356 0.636537 + outer loop + vertex -394.313 176.57 399.281 + vertex -393.749 181.21 402.161 + vertex -394.74 181.248 401.079 + endloop + endfacet + facet normal -0.612754 -0.358769 0.704143 + outer loop + vertex -393.051 185.382 404.952 + vertex -391.502 183.426 405.303 + vertex -392.013 187.251 406.807 + endloop + endfacet + facet normal -0.679122 -0.326204 0.65756 + outer loop + vertex -393.749 181.21 402.161 + vertex -393.051 185.382 404.952 + vertex -394.182 185.13 403.659 + endloop + endfacet + facet normal -0.525579 -0.294727 0.798062 + outer loop + vertex -392.56 189.423 407.416 + vertex -391.035 187.987 407.89 + vertex -391.408 188.843 407.961 + endloop + endfacet + facet normal -0.611437 -0.360009 0.704655 + outer loop + vertex -392.013 187.251 406.807 + vertex -393.017 188.475 406.561 + vertex -393.051 185.382 404.952 + endloop + endfacet + facet normal -0.621827 -0.337397 0.70675 + outer loop + vertex -393.017 188.475 406.561 + vertex -392.56 189.423 407.416 + vertex -393.352 189.787 406.893 + endloop + endfacet + facet normal -0.367818 -0.122012 0.921858 + outer loop + vertex -415.343 124.982 369.384 + vertex -413.967 126.075 370.077 + vertex -414.905 126.579 369.77 + endloop + endfacet + facet normal -0.361363 -0.183818 0.914127 + outer loop + vertex -409.642 128.76 372.38 + vertex -412.741 124.714 370.341 + vertex -410.547 124.355 371.136 + endloop + endfacet + facet normal -0.428115 -0.0868062 0.899546 + outer loop + vertex -413.967 126.075 370.077 + vertex -411.322 128.529 371.573 + vertex -412.735 127.907 370.84 + endloop + endfacet + facet normal -0.410128 -0.183144 0.89345 + outer loop + vertex -407.099 132.658 374.346 + vertex -409.642 128.76 372.38 + vertex -407.388 128.895 373.442 + endloop + endfacet + facet normal -0.544009 -0.0173843 0.838899 + outer loop + vertex -411.322 128.529 371.573 + vertex -408.201 132.293 373.675 + vertex -409.914 130.744 372.532 + endloop + endfacet + facet normal -0.493654 -0.167129 0.853448 + outer loop + vertex -404.698 135.646 376.32 + vertex -407.099 132.658 374.346 + vertex -407.388 128.895 373.442 + endloop + endfacet + facet normal -0.794996 0.214101 0.567576 + outer loop + vertex -408.201 132.293 373.675 + vertex -405.572 136.212 375.879 + vertex -406.497 135 375.04 + endloop + endfacet + facet normal -0.484087 -0.221281 0.846578 + outer loop + vertex -402.238 141.501 379.257 + vertex -404.698 135.646 376.32 + vertex -402.707 135.949 377.537 + endloop + endfacet + facet normal -0.85514 0.158572 0.493549 + outer loop + vertex -405.572 136.212 375.879 + vertex -403.324 140.765 378.311 + vertex -404.361 138.829 377.136 + endloop + endfacet + facet normal -0.559225 -0.215598 0.80049 + outer loop + vertex -400.777 146.348 381.583 + vertex -402.238 141.501 379.257 + vertex -400.559 142.373 380.664 + endloop + endfacet + facet normal -0.7466 -0.062083 0.66237 + outer loop + vertex -403.324 140.765 378.311 + vertex -401.516 145.589 380.801 + vertex -402.259 144.03 379.818 + endloop + endfacet + facet normal -0.638763 -0.206265 0.74124 + outer loop + vertex -399.543 149.816 383.611 + vertex -400.777 146.348 381.583 + vertex -400.559 142.373 380.664 + endloop + endfacet + facet normal -0.772782 -0.0899332 0.628267 + outer loop + vertex -401.516 145.589 380.801 + vertex -400.063 150.306 383.264 + vertex -400.825 148.282 382.037 + endloop + endfacet + facet normal -0.640762 -0.235222 0.730818 + outer loop + vertex -398.15 155.049 386.517 + vertex -399.543 149.816 383.611 + vertex -398.763 147.288 383.482 + endloop + endfacet + facet normal -0.831983 -0.0790128 0.549146 + outer loop + vertex -400.063 150.306 383.264 + vertex -398.846 154.971 385.779 + vertex -399.334 153.501 384.827 + endloop + endfacet + facet normal -0.668149 -0.243854 0.702932 + outer loop + vertex -397.315 161.175 389.436 + vertex -398.15 155.049 386.517 + vertex -396.834 157.532 388.629 + endloop + endfacet + facet normal -0.870248 -0.0838698 0.485421 + outer loop + vertex -398.846 154.971 385.779 + vertex -397.819 160.225 388.528 + vertex -398.357 157.937 387.167 + endloop + endfacet + facet normal -0.725691 -0.238675 0.645296 + outer loop + vertex -396.571 165.197 391.76 + vertex -397.315 161.175 389.436 + vertex -396.834 157.532 388.629 + endloop + endfacet + facet normal -0.867504 -0.121199 0.48244 + outer loop + vertex -397.819 160.225 388.528 + vertex -396.991 165.508 391.343 + vertex -397.407 163.466 390.083 + endloop + endfacet + facet normal -0.721582 -0.263947 0.64004 + outer loop + vertex -395.752 170.309 394.791 + vertex -396.571 165.197 391.76 + vertex -395.808 162.882 391.665 + endloop + endfacet + facet normal -0.884777 -0.132024 0.446921 + outer loop + vertex -396.991 165.508 391.343 + vertex -396.33 170.564 394.146 + vertex -396.654 168.746 392.967 + endloop + endfacet + facet normal -0.702075 -0.296749 0.647326 + outer loop + vertex -395.242 176.443 398.157 + vertex -395.752 170.309 394.791 + vertex -394.773 171.395 396.351 + endloop + endfacet + facet normal -0.85392 -0.188506 0.485064 + outer loop + vertex -396.33 170.564 394.146 + vertex -395.811 175.47 396.965 + vertex -396.109 174.021 395.878 + endloop + endfacet + facet normal -0.716236 -0.306551 0.626923 + outer loop + vertex -394.74 181.248 401.079 + vertex -395.242 176.443 398.157 + vertex -394.313 176.57 399.281 + endloop + endfacet + facet normal -0.810995 -0.242503 0.532428 + outer loop + vertex -395.811 175.47 396.965 + vertex -395.358 180.375 399.89 + vertex -395.727 178.331 398.396 + endloop + endfacet + facet normal -0.704082 -0.319936 0.633963 + outer loop + vertex -394.182 185.13 403.659 + vertex -394.74 181.248 401.079 + vertex -393.749 181.21 402.161 + endloop + endfacet + facet normal -0.746424 -0.29574 0.596145 + outer loop + vertex -395.358 180.375 399.89 + vertex -394.824 184.573 402.641 + vertex -395.193 183.239 401.517 + endloop + endfacet + facet normal -0.701871 -0.318477 0.637141 + outer loop + vertex -394.296 187.151 404.555 + vertex -393.71 187.972 405.611 + vertex -393.876 188.997 405.941 + endloop + endfacet + facet normal -0.674517 -0.338712 0.655973 + outer loop + vertex -393.71 187.972 405.611 + vertex -394.182 185.13 403.659 + vertex -393.051 185.382 404.952 + endloop + endfacet + facet normal -0.701698 -0.326523 0.633247 + outer loop + vertex -394.824 184.573 402.641 + vertex -394.296 187.151 404.555 + vertex -394.473 187.11 404.338 + endloop + endfacet + facet normal -0.464639 0.0594375 0.883503 + outer loop + vertex -393.346 190.476 407.235 + vertex -393.173 190.34 407.336 + vertex -393.313 190.556 407.248 + endloop + endfacet + facet normal -0.623342 -0.355443 0.696495 + outer loop + vertex -393.173 190.34 407.336 + vertex -393.352 189.787 406.893 + vertex -392.56 189.423 407.416 + endloop + endfacet + facet normal -0.695679 -0.31604 0.645096 + outer loop + vertex -393.352 189.787 406.893 + vertex -393.49 190.2 406.947 + vertex -393.876 188.997 405.941 + endloop + endfacet + facet normal -0.922808 0.371021 0.103769 + outer loop + vertex -393.49 190.2 406.947 + vertex -393.346 190.476 407.235 + vertex -393.313 190.556 407.248 + endloop + endfacet + facet normal 0.828113 0.558019 0.0533268 + outer loop + vertex -392.56 189.423 407.416 + vertex -393.313 190.556 407.248 + vertex -393.173 190.34 407.336 + endloop + endfacet + facet normal -0.66568 -0.338743 0.664923 + outer loop + vertex -393.051 185.382 404.952 + vertex -393.017 188.475 406.561 + vertex -393.71 187.972 405.611 + endloop + endfacet + facet normal -0.666074 -0.338088 0.664863 + outer loop + vertex -393.017 188.475 406.561 + vertex -393.352 189.787 406.893 + vertex -393.71 187.972 405.611 + endloop + endfacet + facet normal -0.692462 -0.319995 0.646606 + outer loop + vertex -393.876 188.997 405.941 + vertex -393.71 187.972 405.611 + vertex -393.352 189.787 406.893 + endloop + endfacet + facet normal 0.575894 -0.133915 0.806482 + outer loop + vertex 392.855 202.202 410.38 + vertex 393.052 201.104 410.057 + vertex 393.751 202.702 409.823 + endloop + endfacet + facet normal 0.610256 -0.130924 0.78131 + outer loop + vertex 392.948 199.873 409.931 + vertex 393.789 200.246 409.337 + vertex 393.052 201.104 410.057 + endloop + endfacet + facet normal 0.598369 -0.146503 0.787713 + outer loop + vertex 393.789 200.246 409.337 + vertex 393.751 202.702 409.823 + vertex 393.052 201.104 410.057 + endloop + endfacet + facet normal 0.726379 -0.369992 0.579206 + outer loop + vertex 393.956 205.767 410.783 + vertex 393.044 203.671 410.588 + vertex 394.021 205.794 410.72 + endloop + endfacet + facet normal 0.591813 -0.187547 0.783954 + outer loop + vertex 392.855 202.202 410.38 + vertex 393.751 202.702 409.823 + vertex 393.044 203.671 410.588 + endloop + endfacet + facet normal 0.500942 -0.281149 0.818543 + outer loop + vertex 393.751 202.702 409.823 + vertex 394.021 205.794 410.72 + vertex 393.044 203.671 410.588 + endloop + endfacet + facet normal 0.32261 -0.237017 0.916377 + outer loop + vertex 381.303 195.638 414.188 + vertex 381.522 194.541 413.827 + vertex 385.388 197.529 413.239 + endloop + endfacet + facet normal 0.313233 -0.223586 0.922981 + outer loop + vertex 385.388 197.529 413.239 + vertex 381.522 194.541 413.827 + vertex 385.567 196.429 412.912 + endloop + endfacet + facet normal 0.333629 -0.243404 0.910739 + outer loop + vertex 381.149 196.806 414.556 + vertex 381.303 195.638 414.188 + vertex 385.195 198.675 413.574 + endloop + endfacet + facet normal 0.315091 -0.21699 0.923923 + outer loop + vertex 385.195 198.675 413.574 + vertex 381.303 195.638 414.188 + vertex 385.388 197.529 413.239 + endloop + endfacet + facet normal 0.397238 -0.195199 0.896716 + outer loop + vertex 385.195 198.675 413.574 + vertex 385.388 197.529 413.239 + vertex 388.697 200.443 412.407 + endloop + endfacet + facet normal 0.389593 -0.184946 0.902226 + outer loop + vertex 388.697 200.443 412.407 + vertex 385.388 197.529 413.239 + vertex 388.852 199.298 412.105 + endloop + endfacet + facet normal 0.39616 -0.202001 0.895686 + outer loop + vertex 385.388 197.529 413.239 + vertex 385.567 196.429 412.912 + vertex 388.852 199.298 412.105 + endloop + endfacet + facet normal 0.385428 -0.187518 0.903484 + outer loop + vertex 388.852 199.298 412.105 + vertex 385.567 196.429 412.912 + vertex 388.965 198.182 411.826 + endloop + endfacet + facet normal 0.373606 -0.341292 0.862519 + outer loop + vertex 381.107 198.043 415.064 + vertex 381.149 196.806 414.556 + vertex 385.135 199.924 414.063 + endloop + endfacet + facet normal 0.362373 -0.3252 0.873459 + outer loop + vertex 385.135 199.924 414.063 + vertex 381.149 196.806 414.556 + vertex 385.195 198.675 413.574 + endloop + endfacet + facet normal 0.412428 -0.540053 0.733653 + outer loop + vertex 380.841 199.141 416.022 + vertex 381.107 198.043 415.064 + vertex 385.38 201.286 415.049 + endloop + endfacet + facet normal 0.44023 -0.576904 0.688025 + outer loop + vertex 385.38 201.286 415.049 + vertex 381.107 198.043 415.064 + vertex 385.135 199.924 414.063 + endloop + endfacet + facet normal 0.506116 -0.563412 0.653003 + outer loop + vertex 385.38 201.286 415.049 + vertex 385.135 199.924 414.063 + vertex 389.037 203.203 413.869 + endloop + endfacet + facet normal 0.509321 -0.567588 0.646866 + outer loop + vertex 389.037 203.203 413.869 + vertex 385.135 199.924 414.063 + vertex 388.628 201.694 412.867 + endloop + endfacet + facet normal 0.444527 -0.308534 0.840953 + outer loop + vertex 385.135 199.924 414.063 + vertex 385.195 198.675 413.574 + vertex 388.628 201.694 412.867 + endloop + endfacet + facet normal 0.431003 -0.289979 0.854487 + outer loop + vertex 388.628 201.694 412.867 + vertex 385.195 198.675 413.574 + vertex 388.697 200.443 412.407 + endloop + endfacet + facet normal 0.516154 -0.270034 0.812814 + outer loop + vertex 388.628 201.694 412.867 + vertex 388.697 200.443 412.407 + vertex 391.364 203.078 411.589 + endloop + endfacet + facet normal 0.484321 -0.227913 0.844682 + outer loop + vertex 391.364 203.078 411.589 + vertex 388.697 200.443 412.407 + vertex 391.343 201.743 411.241 + endloop + endfacet + facet normal 0.595678 -0.55009 0.585294 + outer loop + vertex 389.037 203.203 413.869 + vertex 388.628 201.694 412.867 + vertex 391.847 204.734 412.448 + endloop + endfacet + facet normal 0.561429 -0.504061 0.656293 + outer loop + vertex 391.847 204.734 412.448 + vertex 388.628 201.694 412.867 + vertex 391.364 203.078 411.589 + endloop + endfacet + facet normal 0.675716 -0.484957 0.55518 + outer loop + vertex 391.847 204.734 412.448 + vertex 391.364 203.078 411.589 + vertex 393.956 205.767 410.783 + endloop + endfacet + facet normal 0.565505 -0.316977 0.7614 + outer loop + vertex 393.956 205.767 410.783 + vertex 391.364 203.078 411.589 + vertex 393.044 203.671 410.588 + endloop + endfacet + facet normal 0.555159 -0.218098 0.802641 + outer loop + vertex 391.364 203.078 411.589 + vertex 391.343 201.743 411.241 + vertex 393.044 203.671 410.588 + endloop + endfacet + facet normal 0.528354 -0.185694 0.828469 + outer loop + vertex 393.044 203.671 410.588 + vertex 391.343 201.743 411.241 + vertex 392.855 202.202 410.38 + endloop + endfacet + facet normal 0.463071 -0.171198 0.86963 + outer loop + vertex 388.852 199.298 412.105 + vertex 388.965 198.182 411.826 + vertex 391.449 200.583 410.976 + endloop + endfacet + facet normal 0.452601 -0.157504 0.877693 + outer loop + vertex 391.449 200.583 410.976 + vertex 388.965 198.182 411.826 + vertex 391.504 199.447 410.744 + endloop + endfacet + facet normal 0.46494 -0.166096 0.869622 + outer loop + vertex 388.697 200.443 412.407 + vertex 388.852 199.298 412.105 + vertex 391.343 201.743 411.241 + endloop + endfacet + facet normal 0.458625 -0.157949 0.87448 + outer loop + vertex 391.343 201.743 411.241 + vertex 388.852 199.298 412.105 + vertex 391.449 200.583 410.976 + endloop + endfacet + facet normal 0.522527 -0.144244 0.840332 + outer loop + vertex 391.343 201.743 411.241 + vertex 391.449 200.583 410.976 + vertex 392.855 202.202 410.38 + endloop + endfacet + facet normal 0.528278 -0.151001 0.835536 + outer loop + vertex 392.855 202.202 410.38 + vertex 391.449 200.583 410.976 + vertex 393.052 201.104 410.057 + endloop + endfacet + facet normal 0.527392 -0.145615 0.837051 + outer loop + vertex 391.449 200.583 410.976 + vertex 391.504 199.447 410.744 + vertex 393.052 201.104 410.057 + endloop + endfacet + facet normal 0.514889 -0.129654 0.847396 + outer loop + vertex 393.052 201.104 410.057 + vertex 391.504 199.447 410.744 + vertex 392.948 199.873 409.931 + endloop + endfacet + facet normal -0.251819 -0.297638 0.920869 + outer loop + vertex -380.105 196.068 414.708 + vertex -379.358 194.681 414.464 + vertex -373.535 194.176 415.893 + endloop + endfacet + facet normal -0.237931 -0.318322 0.917638 + outer loop + vertex -380.206 193.802 413.939 + vertex -373.812 192.009 414.975 + vertex -379.358 194.681 414.464 + endloop + endfacet + facet normal -0.251799 -0.350044 0.902256 + outer loop + vertex -373.812 192.009 414.975 + vertex -373.535 194.176 415.893 + vertex -379.358 194.681 414.464 + endloop + endfacet + facet normal -0.30281 -0.519159 0.799237 + outer loop + vertex -379.484 198.554 416.253 + vertex -379.015 196.931 415.376 + vertex -372.309 195.826 417.199 + endloop + endfacet + facet normal -0.264681 -0.358327 0.895291 + outer loop + vertex -380.105 196.068 414.708 + vertex -373.535 194.176 415.893 + vertex -379.015 196.931 415.376 + endloop + endfacet + facet normal -0.30243 -0.443066 0.843936 + outer loop + vertex -373.535 194.176 415.893 + vertex -372.309 195.826 417.199 + vertex -379.015 196.931 415.376 + endloop + endfacet + facet normal -0.607158 -0.076799 0.790861 + outer loop + vertex -393.406 201.051 409.766 + vertex -393.365 200.514 409.746 + vertex -392.641 200.584 410.309 + endloop + endfacet + facet normal -0.601959 -0.119661 0.789511 + outer loop + vertex -392.641 200.584 410.309 + vertex -393.365 200.514 409.746 + vertex -392.681 200.068 410.2 + endloop + endfacet + facet normal -0.615778 -0.116209 0.779302 + outer loop + vertex -393.367 201.683 409.891 + vertex -393.406 201.051 409.766 + vertex -392.6 201.148 410.417 + endloop + endfacet + facet normal -0.617196 -0.106325 0.779592 + outer loop + vertex -392.6 201.148 410.417 + vertex -393.406 201.051 409.766 + vertex -392.641 200.584 410.309 + endloop + endfacet + facet normal -0.524564 -0.125077 0.842133 + outer loop + vertex -392.6 201.148 410.417 + vertex -392.641 200.584 410.309 + vertex -391.381 200.395 411.065 + endloop + endfacet + facet normal -0.526343 -0.194489 0.82773 + outer loop + vertex -391.381 200.395 411.065 + vertex -392.641 200.584 410.309 + vertex -391.113 199.732 411.08 + endloop + endfacet + facet normal -0.507261 -0.139764 0.850384 + outer loop + vertex -392.641 200.584 410.309 + vertex -392.681 200.068 410.2 + vertex -391.113 199.732 411.08 + endloop + endfacet + facet normal -0.505061 -0.117218 0.855087 + outer loop + vertex -391.113 199.732 411.08 + vertex -392.681 200.068 410.2 + vertex -391.494 199.344 410.802 + endloop + endfacet + facet normal -0.613183 -0.0955795 0.784137 + outer loop + vertex -393.548 202.523 409.853 + vertex -393.367 201.683 409.891 + vertex -392.606 201.937 410.518 + endloop + endfacet + facet normal -0.610963 -0.10391 0.78481 + outer loop + vertex -392.606 201.937 410.518 + vertex -393.367 201.683 409.891 + vertex -392.6 201.148 410.417 + endloop + endfacet + facet normal -0.657928 -0.140167 0.739922 + outer loop + vertex -393.703 203.327 409.867 + vertex -393.548 202.523 409.853 + vertex -392.948 203.294 410.532 + endloop + endfacet + facet normal -0.636333 -0.168344 0.752822 + outer loop + vertex -392.948 203.294 410.532 + vertex -393.548 202.523 409.853 + vertex -392.606 201.937 410.518 + endloop + endfacet + facet normal -0.530877 -0.142654 0.835356 + outer loop + vertex -392.948 203.294 410.532 + vertex -392.606 201.937 410.518 + vertex -390.848 201.89 411.627 + endloop + endfacet + facet normal -0.530341 -0.151564 0.834127 + outer loop + vertex -390.848 201.89 411.627 + vertex -392.606 201.937 410.518 + vertex -390.894 200.857 411.41 + endloop + endfacet + facet normal -0.513767 -0.111655 0.850633 + outer loop + vertex -392.606 201.937 410.518 + vertex -392.6 201.148 410.417 + vertex -390.894 200.857 411.41 + endloop + endfacet + facet normal -0.512633 -0.0962225 0.853199 + outer loop + vertex -390.894 200.857 411.41 + vertex -392.6 201.148 410.417 + vertex -391.381 200.395 411.065 + endloop + endfacet + facet normal -0.446098 -0.16486 0.879669 + outer loop + vertex -390.848 201.89 411.627 + vertex -390.894 200.857 411.41 + vertex -387.938 200.17 412.78 + endloop + endfacet + facet normal -0.443145 -0.18687 0.876757 + outer loop + vertex -391.381 200.395 411.065 + vertex -388.509 199.235 412.27 + vertex -390.894 200.857 411.41 + endloop + endfacet + facet normal -0.449998 -0.200391 0.870256 + outer loop + vertex -388.509 199.235 412.27 + vertex -387.938 200.17 412.78 + vertex -390.894 200.857 411.41 + endloop + endfacet + facet normal -0.435002 -0.156333 0.886754 + outer loop + vertex -391.381 200.395 411.065 + vertex -391.113 199.732 411.08 + vertex -388.509 199.235 412.27 + endloop + endfacet + facet normal -0.436259 -0.200495 0.8772 + outer loop + vertex -391.494 199.344 410.802 + vertex -388.662 198.165 411.94 + vertex -391.113 199.732 411.08 + endloop + endfacet + facet normal -0.438939 -0.206141 0.87455 + outer loop + vertex -388.662 198.165 411.94 + vertex -388.509 199.235 412.27 + vertex -391.113 199.732 411.08 + endloop + endfacet + facet normal -0.585855 -0.536857 0.60709 + outer loop + vertex -391.684 204.647 412.55 + vertex -391.108 203.331 411.942 + vertex -388.601 202.967 414.04 + endloop + endfacet + facet normal -0.57782 -0.56034 0.593416 + outer loop + vertex -388.601 202.967 414.04 + vertex -391.108 203.331 411.942 + vertex -387.991 201.439 413.191 + endloop + endfacet + facet normal -0.494866 -0.269913 0.825987 + outer loop + vertex -391.108 203.331 411.942 + vertex -390.848 201.89 411.627 + vertex -387.991 201.439 413.191 + endloop + endfacet + facet normal -0.494528 -0.286375 0.820629 + outer loop + vertex -387.991 201.439 413.191 + vertex -390.848 201.89 411.627 + vertex -387.938 200.17 412.78 + endloop + endfacet + facet normal -0.41155 -0.296317 0.861872 + outer loop + vertex -387.991 201.439 413.191 + vertex -387.938 200.17 412.78 + vertex -383.942 199.313 414.393 + endloop + endfacet + facet normal -0.412047 -0.304384 0.858818 + outer loop + vertex -383.942 199.313 414.393 + vertex -387.938 200.17 412.78 + vertex -384.073 198.079 413.894 + endloop + endfacet + facet normal -0.491052 -0.564551 0.663438 + outer loop + vertex -388.601 202.967 414.04 + vertex -387.991 201.439 413.191 + vertex -384.543 200.87 415.259 + endloop + endfacet + facet normal -0.492104 -0.56011 0.666416 + outer loop + vertex -384.543 200.87 415.259 + vertex -387.991 201.439 413.191 + vertex -383.942 199.313 414.393 + endloop + endfacet + facet normal -0.398461 -0.558104 0.727838 + outer loop + vertex -384.543 200.87 415.259 + vertex -383.942 199.313 414.393 + vertex -379.484 198.554 416.253 + endloop + endfacet + facet normal -0.402386 -0.522304 0.751853 + outer loop + vertex -379.484 198.554 416.253 + vertex -383.942 199.313 414.393 + vertex -379.015 196.931 415.376 + endloop + endfacet + facet normal -0.333022 -0.323612 0.885647 + outer loop + vertex -383.942 199.313 414.393 + vertex -384.073 198.079 413.894 + vertex -379.015 196.931 415.376 + endloop + endfacet + facet normal -0.328312 -0.28266 0.901285 + outer loop + vertex -379.015 196.931 415.376 + vertex -384.073 198.079 413.894 + vertex -380.105 196.068 414.708 + endloop + endfacet + facet normal -0.375944 -0.222855 0.899445 + outer loop + vertex -388.509 199.235 412.27 + vertex -388.662 198.165 411.94 + vertex -384.22 196.961 413.499 + endloop + endfacet + facet normal -0.380669 -0.253426 0.889307 + outer loop + vertex -384.22 196.961 413.499 + vertex -388.662 198.165 411.94 + vertex -384.284 195.84 413.152 + endloop + endfacet + facet normal -0.389181 -0.246858 0.887468 + outer loop + vertex -387.938 200.17 412.78 + vertex -388.509 199.235 412.27 + vertex -384.073 198.079 413.894 + endloop + endfacet + facet normal -0.390963 -0.260147 0.882877 + outer loop + vertex -384.073 198.079 413.894 + vertex -388.509 199.235 412.27 + vertex -384.22 196.961 413.499 + endloop + endfacet + facet normal -0.325668 -0.276249 0.904227 + outer loop + vertex -384.073 198.079 413.894 + vertex -384.22 196.961 413.499 + vertex -380.105 196.068 414.708 + endloop + endfacet + facet normal -0.331737 -0.333887 0.88231 + outer loop + vertex -380.105 196.068 414.708 + vertex -384.22 196.961 413.499 + vertex -379.358 194.681 414.464 + endloop + endfacet + facet normal -0.305992 -0.265443 0.91428 + outer loop + vertex -384.22 196.961 413.499 + vertex -384.284 195.84 413.152 + vertex -379.358 194.681 414.464 + endloop + endfacet + facet normal -0.304376 -0.254427 0.917944 + outer loop + vertex -379.358 194.681 414.464 + vertex -384.284 195.84 413.152 + vertex -380.206 193.802 413.939 + endloop + endfacet + facet normal -0.233318 0.120792 -0.964869 + outer loop + vertex -393.891 200.757 409.169 + vertex -393.924 202.028 409.336 + vertex -393.864 200.345 409.111 + endloop + endfacet + facet normal 0.812443 0.151058 -0.563132 + outer loop + vertex -393.963 203.482 409.669 + vertex -393.891 203.048 409.657 + vertex -393.924 202.028 409.336 + endloop + endfacet + facet normal 0.93386 0.0797955 -0.348622 + outer loop + vertex -393.891 203.048 409.657 + vertex -393.864 200.345 409.111 + vertex -393.924 202.028 409.336 + endloop + endfacet + facet normal -0.732681 -0.275493 0.62232 + outer loop + vertex -394.021 205.794 410.72 + vertex -393.891 203.048 409.657 + vertex -393.988 205.781 410.752 + endloop + endfacet + facet normal 0.930858 0.16402 -0.326498 + outer loop + vertex -393.988 205.781 410.752 + vertex -393.891 203.048 409.657 + vertex -393.963 203.482 409.669 + endloop + endfacet + facet normal -0.594359 -0.263034 0.759968 + outer loop + vertex -393.703 203.327 409.867 + vertex -393.765 204.263 410.142 + vertex -393.902 203.267 409.69 + endloop + endfacet + facet normal -0.882684 -0.208167 0.42135 + outer loop + vertex -393.963 203.482 409.669 + vertex -393.902 203.267 409.69 + vertex -393.988 205.781 410.752 + endloop + endfacet + facet normal -0.727739 -0.345051 0.592735 + outer loop + vertex -393.956 205.767 410.783 + vertex -393.988 205.781 410.752 + vertex -393.765 204.263 410.142 + endloop + endfacet + facet normal -0.165892 -0.388442 0.906418 + outer loop + vertex -393.902 203.267 409.69 + vertex -393.765 204.263 410.142 + vertex -393.988 205.781 410.752 + endloop + endfacet + facet normal -0.800796 -0.0980968 0.590849 + outer loop + vertex -393.924 202.028 409.336 + vertex -393.891 200.757 409.169 + vertex -393.785 201.662 409.463 + endloop + endfacet + facet normal -0.841945 -0.0749228 0.534335 + outer loop + vertex -393.785 201.662 409.463 + vertex -393.891 200.757 409.169 + vertex -393.765 200.44 409.323 + endloop + endfacet + facet normal -0.77768 -0.160352 0.607866 + outer loop + vertex -393.963 203.482 409.669 + vertex -393.924 202.028 409.336 + vertex -393.902 203.267 409.69 + endloop + endfacet + facet normal -0.840068 -0.135678 0.525241 + outer loop + vertex -393.902 203.267 409.69 + vertex -393.924 202.028 409.336 + vertex -393.785 201.662 409.463 + endloop + endfacet + facet normal -0.707618 -0.119934 0.696343 + outer loop + vertex -393.367 201.683 409.891 + vertex -393.548 202.523 409.853 + vertex -393.785 201.662 409.463 + endloop + endfacet + facet normal -0.633829 -0.135877 0.761445 + outer loop + vertex -393.703 203.327 409.867 + vertex -393.902 203.267 409.69 + vertex -393.548 202.523 409.853 + endloop + endfacet + facet normal -0.657659 -0.152415 0.737736 + outer loop + vertex -393.902 203.267 409.69 + vertex -393.785 201.662 409.463 + vertex -393.548 202.523 409.853 + endloop + endfacet + facet normal -0.716694 -0.0814845 0.692611 + outer loop + vertex -393.365 200.514 409.746 + vertex -393.406 201.051 409.766 + vertex -393.765 200.44 409.323 + endloop + endfacet + facet normal -0.71026 -0.0942087 0.697607 + outer loop + vertex -393.367 201.683 409.891 + vertex -393.785 201.662 409.463 + vertex -393.406 201.051 409.766 + endloop + endfacet + facet normal -0.708249 -0.0917874 0.69997 + outer loop + vertex -393.785 201.662 409.463 + vertex -393.765 200.44 409.323 + vertex -393.406 201.051 409.766 + endloop + endfacet + facet normal 0.60401 -0.136901 0.785131 + outer loop + vertex 393.213 195.935 408.971 + vertex 393.8 196.487 408.616 + vertex 393.115 196.71 409.182 + endloop + endfacet + facet normal 0.605007 -0.15279 0.781423 + outer loop + vertex 392.921 197.568 409.5 + vertex 393.115 196.71 409.182 + vertex 393.812 197.875 408.87 + endloop + endfacet + facet normal 0.730729 -0.128967 0.670375 + outer loop + vertex 394.027 196.471 408.366 + vertex 393.812 197.875 408.87 + vertex 393.8 196.487 408.616 + endloop + endfacet + facet normal 0.600489 -0.148959 0.785636 + outer loop + vertex 393.115 196.71 409.182 + vertex 393.8 196.487 408.616 + vertex 393.812 197.875 408.87 + endloop + endfacet + facet normal 0.612897 -0.143787 0.77697 + outer loop + vertex 392.948 199.873 409.931 + vertex 393.073 198.772 409.629 + vertex 393.789 200.246 409.337 + endloop + endfacet + facet normal 0.605969 -0.160107 0.77921 + outer loop + vertex 392.921 197.568 409.5 + vertex 393.812 197.875 408.87 + vertex 393.073 198.772 409.629 + endloop + endfacet + facet normal 0.616742 -0.146353 0.77344 + outer loop + vertex 393.812 197.875 408.87 + vertex 393.789 200.246 409.337 + vertex 393.073 198.772 409.629 + endloop + endfacet + facet normal 0.326604 -0.30216 0.895561 + outer loop + vertex 382.021 191.394 412.724 + vertex 382.095 190.385 412.356 + vertex 385.892 193.227 411.93 + endloop + endfacet + facet normal 0.31253 -0.281608 0.907206 + outer loop + vertex 385.892 193.227 411.93 + vertex 382.095 190.385 412.356 + vertex 385.944 192.203 411.595 + endloop + endfacet + facet normal 0.32302 -0.279291 0.904243 + outer loop + vertex 381.896 192.428 413.088 + vertex 382.021 191.394 412.724 + vertex 385.822 194.281 412.257 + endloop + endfacet + facet normal 0.311556 -0.262754 0.913177 + outer loop + vertex 385.822 194.281 412.257 + vertex 382.021 191.394 412.724 + vertex 385.892 193.227 411.93 + endloop + endfacet + facet normal 0.395132 -0.248338 0.88442 + outer loop + vertex 385.822 194.281 412.257 + vertex 385.892 193.227 411.93 + vertex 389.108 195.989 411.269 + endloop + endfacet + facet normal 0.381623 -0.230016 0.895241 + outer loop + vertex 389.108 195.989 411.269 + vertex 385.892 193.227 411.93 + vertex 389.136 194.899 410.977 + endloop + endfacet + facet normal 0.396132 -0.267854 0.878256 + outer loop + vertex 385.892 193.227 411.93 + vertex 385.944 192.203 411.595 + vertex 389.136 194.899 410.977 + endloop + endfacet + facet normal 0.379482 -0.244951 0.892184 + outer loop + vertex 389.136 194.899 410.977 + vertex 385.944 192.203 411.595 + vertex 389.241 193.886 410.654 + endloop + endfacet + facet normal 0.327054 -0.273456 0.904576 + outer loop + vertex 381.737 193.475 413.462 + vertex 381.896 192.428 413.088 + vertex 385.724 195.351 412.587 + endloop + endfacet + facet normal 0.313128 -0.253377 0.915287 + outer loop + vertex 385.724 195.351 412.587 + vertex 381.896 192.428 413.088 + vertex 385.822 194.281 412.257 + endloop + endfacet + facet normal 0.322538 -0.248138 0.913453 + outer loop + vertex 381.522 194.541 413.827 + vertex 381.737 193.475 413.462 + vertex 385.567 196.429 412.912 + endloop + endfacet + facet normal 0.311298 -0.232056 0.921544 + outer loop + vertex 385.567 196.429 412.912 + vertex 381.737 193.475 413.462 + vertex 385.724 195.351 412.587 + endloop + endfacet + facet normal 0.39483 -0.21157 0.894062 + outer loop + vertex 385.567 196.429 412.912 + vertex 385.724 195.351 412.587 + vertex 388.965 198.182 411.826 + endloop + endfacet + facet normal 0.385459 -0.198973 0.901017 + outer loop + vertex 388.965 198.182 411.826 + vertex 385.724 195.351 412.587 + vertex 389.047 197.083 411.548 + endloop + endfacet + facet normal 0.400035 -0.236241 0.885529 + outer loop + vertex 385.724 195.351 412.587 + vertex 385.822 194.281 412.257 + vertex 389.047 197.083 411.548 + endloop + endfacet + facet normal 0.379638 -0.208773 0.901271 + outer loop + vertex 389.047 197.083 411.548 + vertex 385.822 194.281 412.257 + vertex 389.108 195.989 411.269 + endloop + endfacet + facet normal 0.459436 -0.195451 0.866439 + outer loop + vertex 389.047 197.083 411.548 + vertex 389.108 195.989 411.269 + vertex 391.529 198.312 410.51 + endloop + endfacet + facet normal 0.449559 -0.182559 0.874396 + outer loop + vertex 391.529 198.312 410.51 + vertex 389.108 195.989 411.269 + vertex 391.537 197.18 410.269 + endloop + endfacet + facet normal 0.461845 -0.184793 0.867497 + outer loop + vertex 388.965 198.182 411.826 + vertex 389.047 197.083 411.548 + vertex 391.504 199.447 410.744 + endloop + endfacet + facet normal 0.451227 -0.170903 0.875892 + outer loop + vertex 391.504 199.447 410.744 + vertex 389.047 197.083 411.548 + vertex 391.529 198.312 410.51 + endloop + endfacet + facet normal 0.519623 -0.161795 0.838937 + outer loop + vertex 391.504 199.447 410.744 + vertex 391.529 198.312 410.51 + vertex 392.948 199.873 409.931 + endloop + endfacet + facet normal 0.525658 -0.169227 0.833694 + outer loop + vertex 392.948 199.873 409.931 + vertex 391.529 198.312 410.51 + vertex 393.073 198.772 409.629 + endloop + endfacet + facet normal 0.526167 -0.17306 0.832585 + outer loop + vertex 391.529 198.312 410.51 + vertex 391.537 197.18 410.269 + vertex 393.073 198.772 409.629 + endloop + endfacet + facet normal 0.512712 -0.155343 0.84439 + outer loop + vertex 393.073 198.772 409.629 + vertex 391.537 197.18 410.269 + vertex 392.921 197.568 409.5 + endloop + endfacet + facet normal 0.455415 -0.227152 0.860813 + outer loop + vertex 389.136 194.899 410.977 + vertex 389.241 193.886 410.654 + vertex 391.581 196.104 410.001 + endloop + endfacet + facet normal 0.437833 -0.204266 0.875544 + outer loop + vertex 391.581 196.104 410.001 + vertex 389.241 193.886 410.654 + vertex 391.808 195.164 409.669 + endloop + endfacet + facet normal 0.461226 -0.2185 0.859958 + outer loop + vertex 389.108 195.989 411.269 + vertex 389.136 194.899 410.977 + vertex 391.537 197.18 410.269 + endloop + endfacet + facet normal 0.446075 -0.198592 0.872685 + outer loop + vertex 391.537 197.18 410.269 + vertex 389.136 194.899 410.977 + vertex 391.581 196.104 410.001 + endloop + endfacet + facet normal 0.516608 -0.186518 0.83566 + outer loop + vertex 391.537 197.18 410.269 + vertex 391.581 196.104 410.001 + vertex 392.921 197.568 409.5 + endloop + endfacet + facet normal 0.520156 -0.19086 0.832472 + outer loop + vertex 392.921 197.568 409.5 + vertex 391.581 196.104 410.001 + vertex 393.115 196.71 409.182 + endloop + endfacet + facet normal 0.516276 -0.172357 0.838899 + outer loop + vertex 391.581 196.104 410.001 + vertex 391.808 195.164 409.669 + vertex 393.115 196.71 409.182 + endloop + endfacet + facet normal 0.509609 -0.16498 0.844441 + outer loop + vertex 393.115 196.71 409.182 + vertex 391.808 195.164 409.669 + vertex 393.213 195.935 408.971 + endloop + endfacet + facet normal -0.218799 -0.299613 0.928633 + outer loop + vertex -380.407 191.645 413.178 + vertex -379.706 190.366 412.931 + vertex -373.879 189.843 414.135 + endloop + endfacet + facet normal -0.217117 -0.345074 0.913118 + outer loop + vertex -380.669 189.634 412.425 + vertex -374.028 187.791 413.308 + vertex -379.706 190.366 412.931 + endloop + endfacet + facet normal -0.219614 -0.350997 0.910259 + outer loop + vertex -374.028 187.791 413.308 + vertex -373.879 189.843 414.135 + vertex -379.706 190.366 412.931 + endloop + endfacet + facet normal -0.232605 -0.293844 0.92712 + outer loop + vertex -380.206 193.802 413.939 + vertex -379.475 192.46 413.697 + vertex -373.812 192.009 414.975 + endloop + endfacet + facet normal -0.224892 -0.327502 0.917696 + outer loop + vertex -380.407 191.645 413.178 + vertex -373.879 189.843 414.135 + vertex -379.475 192.46 413.697 + endloop + endfacet + facet normal -0.232651 -0.345535 0.909109 + outer loop + vertex -373.879 189.843 414.135 + vertex -373.812 192.009 414.975 + vertex -379.475 192.46 413.697 + endloop + endfacet + facet normal -0.606163 -0.157937 0.779501 + outer loop + vertex -393.556 196.783 408.934 + vertex -393.476 196.275 408.894 + vertex -392.845 196.315 409.393 + endloop + endfacet + facet normal -0.602823 -0.18086 0.777106 + outer loop + vertex -392.845 196.315 409.393 + vertex -393.476 196.275 408.894 + vertex -392.84 195.825 409.282 + endloop + endfacet + facet normal -0.607928 -0.184605 0.772233 + outer loop + vertex -393.505 197.295 409.097 + vertex -393.556 196.783 408.934 + vertex -392.84 196.823 409.507 + endloop + endfacet + facet normal -0.61015 -0.169427 0.773958 + outer loop + vertex -392.84 196.823 409.507 + vertex -393.556 196.783 408.934 + vertex -392.845 196.315 409.393 + endloop + endfacet + facet normal -0.515642 -0.184528 0.836698 + outer loop + vertex -392.84 196.823 409.507 + vertex -392.845 196.315 409.393 + vertex -391.702 196.1 410.049 + endloop + endfacet + facet normal -0.517333 -0.240487 0.821299 + outer loop + vertex -391.702 196.1 410.049 + vertex -392.845 196.315 409.393 + vertex -391.4 195.462 410.053 + endloop + endfacet + facet normal -0.500485 -0.194773 0.843551 + outer loop + vertex -392.845 196.315 409.393 + vertex -392.84 195.825 409.282 + vertex -391.4 195.462 410.053 + endloop + endfacet + facet normal -0.495334 -0.147969 0.856008 + outer loop + vertex -391.4 195.462 410.053 + vertex -392.84 195.825 409.282 + vertex -391.734 195.12 409.8 + endloop + endfacet + facet normal -0.600661 -0.139721 0.7872 + outer loop + vertex -393.567 197.826 409.144 + vertex -393.505 197.295 409.097 + vertex -392.827 197.344 409.622 + endloop + endfacet + facet normal -0.597995 -0.158984 0.785573 + outer loop + vertex -392.827 197.344 409.622 + vertex -393.505 197.295 409.097 + vertex -392.84 196.823 409.507 + endloop + endfacet + facet normal -0.606398 -0.165907 0.777661 + outer loop + vertex -393.494 198.361 409.314 + vertex -393.567 197.826 409.144 + vertex -392.824 197.886 409.736 + endloop + endfacet + facet normal -0.60745 -0.158987 0.778285 + outer loop + vertex -392.824 197.886 409.736 + vertex -393.567 197.826 409.144 + vertex -392.827 197.344 409.622 + endloop + endfacet + facet normal -0.515947 -0.172261 0.839121 + outer loop + vertex -392.824 197.886 409.736 + vertex -392.827 197.344 409.622 + vertex -391.659 197.149 410.301 + endloop + endfacet + facet normal -0.517002 -0.218624 0.827594 + outer loop + vertex -391.659 197.149 410.301 + vertex -392.827 197.344 409.622 + vertex -391.363 196.482 410.31 + endloop + endfacet + facet normal -0.500753 -0.174996 0.847717 + outer loop + vertex -392.827 197.344 409.622 + vertex -392.84 196.823 409.507 + vertex -391.363 196.482 410.31 + endloop + endfacet + facet normal -0.497452 -0.141551 0.855865 + outer loop + vertex -391.363 196.482 410.31 + vertex -392.84 196.823 409.507 + vertex -391.702 196.1 410.049 + endloop + endfacet + facet normal -0.410702 -0.17059 0.895669 + outer loop + vertex -391.659 197.149 410.301 + vertex -391.363 196.482 410.31 + vertex -388.861 195.976 411.361 + endloop + endfacet + facet normal -0.422415 -0.223675 0.878371 + outer loop + vertex -391.702 196.1 410.049 + vertex -388.967 194.933 411.067 + vertex -391.363 196.482 410.31 + endloop + endfacet + facet normal -0.41415 -0.206982 0.886362 + outer loop + vertex -388.967 194.933 411.067 + vertex -388.861 195.976 411.361 + vertex -391.363 196.482 410.31 + endloop + endfacet + facet normal -0.41288 -0.19065 0.890608 + outer loop + vertex -391.702 196.1 410.049 + vertex -391.4 195.462 410.053 + vertex -388.967 194.933 411.067 + endloop + endfacet + facet normal -0.42168 -0.234576 0.875877 + outer loop + vertex -391.734 195.12 409.8 + vertex -389.055 193.944 410.775 + vertex -391.4 195.462 410.053 + endloop + endfacet + facet normal -0.416163 -0.223412 0.881417 + outer loop + vertex -389.055 193.944 410.775 + vertex -388.967 194.933 411.067 + vertex -391.4 195.462 410.053 + endloop + endfacet + facet normal -0.59968 -0.118421 0.791429 + outer loop + vertex -393.537 198.907 409.364 + vertex -393.494 198.361 409.314 + vertex -392.8 198.431 409.851 + endloop + endfacet + facet normal -0.596467 -0.140798 0.790192 + outer loop + vertex -392.8 198.431 409.851 + vertex -393.494 198.361 409.314 + vertex -392.824 197.886 409.736 + endloop + endfacet + facet normal -0.600386 -0.146001 0.78627 + outer loop + vertex -393.443 199.457 409.537 + vertex -393.537 198.907 409.364 + vertex -392.762 198.984 409.969 + endloop + endfacet + facet normal -0.603066 -0.127802 0.787387 + outer loop + vertex -392.762 198.984 409.969 + vertex -393.537 198.907 409.364 + vertex -392.8 198.431 409.851 + endloop + endfacet + facet normal -0.511908 -0.146566 0.846445 + outer loop + vertex -392.762 198.984 409.969 + vertex -392.8 198.431 409.851 + vertex -391.588 198.242 410.551 + endloop + endfacet + facet normal -0.513366 -0.200763 0.834356 + outer loop + vertex -391.588 198.242 410.551 + vertex -392.8 198.431 409.851 + vertex -391.291 197.549 410.568 + endloop + endfacet + facet normal -0.497481 -0.158547 0.852863 + outer loop + vertex -392.8 198.431 409.851 + vertex -392.824 197.886 409.736 + vertex -391.291 197.549 410.568 + endloop + endfacet + facet normal -0.49361 -0.119831 0.861388 + outer loop + vertex -391.291 197.549 410.568 + vertex -392.824 197.886 409.736 + vertex -391.659 197.149 410.301 + endloop + endfacet + facet normal -0.597196 -0.0957167 0.796364 + outer loop + vertex -393.472 199.992 409.58 + vertex -393.443 199.457 409.537 + vertex -392.725 199.536 410.086 + endloop + endfacet + facet normal -0.592864 -0.126985 0.795228 + outer loop + vertex -392.725 199.536 410.086 + vertex -393.443 199.457 409.537 + vertex -392.762 198.984 409.969 + endloop + endfacet + facet normal -0.604204 -0.125847 0.786829 + outer loop + vertex -393.365 200.514 409.746 + vertex -393.472 199.992 409.58 + vertex -392.681 200.068 410.2 + endloop + endfacet + facet normal -0.605144 -0.118971 0.787177 + outer loop + vertex -392.681 200.068 410.2 + vertex -393.472 199.992 409.58 + vertex -392.725 199.536 410.086 + endloop + endfacet + facet normal -0.514069 -0.139194 0.84638 + outer loop + vertex -392.681 200.068 410.2 + vertex -392.725 199.536 410.086 + vertex -391.494 199.344 410.802 + endloop + endfacet + facet normal -0.515723 -0.192837 0.834771 + outer loop + vertex -391.494 199.344 410.802 + vertex -392.725 199.536 410.086 + vertex -391.205 198.655 410.821 + endloop + endfacet + facet normal -0.498198 -0.145997 0.854684 + outer loop + vertex -392.725 199.536 410.086 + vertex -392.762 198.984 409.969 + vertex -391.205 198.655 410.821 + endloop + endfacet + facet normal -0.494177 -0.105563 0.862928 + outer loop + vertex -391.205 198.655 410.821 + vertex -392.762 198.984 409.969 + vertex -391.588 198.242 410.551 + endloop + endfacet + facet normal -0.422647 -0.152122 0.893436 + outer loop + vertex -391.494 199.344 410.802 + vertex -391.205 198.655 410.821 + vertex -388.662 198.165 411.94 + endloop + endfacet + facet normal -0.422358 -0.187801 0.88676 + outer loop + vertex -391.588 198.242 410.551 + vertex -388.756 197.063 411.65 + vertex -391.205 198.655 410.821 + endloop + endfacet + facet normal -0.426532 -0.196211 0.882934 + outer loop + vertex -388.756 197.063 411.65 + vertex -388.662 198.165 411.94 + vertex -391.205 198.655 410.821 + endloop + endfacet + facet normal -0.413245 -0.156278 0.89711 + outer loop + vertex -391.588 198.242 410.551 + vertex -391.291 197.549 410.568 + vertex -388.756 197.063 411.65 + endloop + endfacet + facet normal -0.420036 -0.202916 0.884531 + outer loop + vertex -391.659 197.149 410.301 + vertex -388.861 195.976 411.361 + vertex -391.291 197.549 410.568 + endloop + endfacet + facet normal -0.416854 -0.196515 0.887477 + outer loop + vertex -388.861 195.976 411.361 + vertex -388.756 197.063 411.65 + vertex -391.291 197.549 410.568 + endloop + endfacet + facet normal -0.353441 -0.209094 0.911789 + outer loop + vertex -388.756 197.063 411.65 + vertex -388.861 195.976 411.361 + vertex -384.372 194.731 412.815 + endloop + endfacet + facet normal -0.359407 -0.243347 0.900893 + outer loop + vertex -384.372 194.731 412.815 + vertex -388.861 195.976 411.361 + vertex -384.503 193.659 412.473 + endloop + endfacet + facet normal -0.362108 -0.208435 0.908533 + outer loop + vertex -388.662 198.165 411.94 + vertex -388.756 197.063 411.65 + vertex -384.284 195.84 413.152 + endloop + endfacet + facet normal -0.367973 -0.243636 0.89735 + outer loop + vertex -384.284 195.84 413.152 + vertex -388.756 197.063 411.65 + vertex -384.372 194.731 412.815 + endloop + endfacet + facet normal -0.304572 -0.254893 0.91775 + outer loop + vertex -384.284 195.84 413.152 + vertex -384.372 194.731 412.815 + vertex -380.206 193.802 413.939 + endloop + endfacet + facet normal -0.314075 -0.331456 0.889659 + outer loop + vertex -380.206 193.802 413.939 + vertex -384.372 194.731 412.815 + vertex -379.475 192.46 413.697 + endloop + endfacet + facet normal -0.286422 -0.259138 0.922394 + outer loop + vertex -384.372 194.731 412.815 + vertex -384.503 193.659 412.473 + vertex -379.475 192.46 413.697 + endloop + endfacet + facet normal -0.286531 -0.259829 0.922165 + outer loop + vertex -379.475 192.46 413.697 + vertex -384.503 193.659 412.473 + vertex -380.407 191.645 413.178 + endloop + endfacet + facet normal -0.348259 -0.236994 0.906945 + outer loop + vertex -388.967 194.933 411.067 + vertex -389.055 193.944 410.775 + vertex -384.64 192.63 412.127 + endloop + endfacet + facet normal -0.354224 -0.268516 0.895782 + outer loop + vertex -384.64 192.63 412.127 + vertex -389.055 193.944 410.775 + vertex -384.767 191.649 411.783 + endloop + endfacet + facet normal -0.349677 -0.220393 0.910579 + outer loop + vertex -388.861 195.976 411.361 + vertex -388.967 194.933 411.067 + vertex -384.503 193.659 412.473 + endloop + endfacet + facet normal -0.355928 -0.255042 0.899038 + outer loop + vertex -384.503 193.659 412.473 + vertex -388.967 194.933 411.067 + vertex -384.64 192.63 412.127 + endloop + endfacet + facet normal -0.290817 -0.270044 0.917879 + outer loop + vertex -384.503 193.659 412.473 + vertex -384.64 192.63 412.127 + vertex -380.407 191.645 413.178 + endloop + endfacet + facet normal -0.300098 -0.337177 0.89233 + outer loop + vertex -380.407 191.645 413.178 + vertex -384.64 192.63 412.127 + vertex -379.706 190.366 412.931 + endloop + endfacet + facet normal -0.280245 -0.285303 0.91655 + outer loop + vertex -384.64 192.63 412.127 + vertex -384.767 191.649 411.783 + vertex -379.706 190.366 412.931 + endloop + endfacet + facet normal -0.277795 -0.27112 0.921588 + outer loop + vertex -379.706 190.366 412.931 + vertex -384.767 191.649 411.783 + vertex -380.669 189.634 412.425 + endloop + endfacet + facet normal 0.209018 0.182024 -0.960822 + outer loop + vertex -393.919 196.49 408.438 + vertex -393.935 197.441 408.615 + vertex -393.837 196.059 408.374 + endloop + endfacet + facet normal 0.163092 0.18214 -0.969653 + outer loop + vertex -393.941 198.545 408.821 + vertex -393.875 198.081 408.745 + vertex -393.935 197.441 408.615 + endloop + endfacet + facet normal 0.173904 0.18079 -0.968025 + outer loop + vertex -393.875 198.081 408.745 + vertex -393.837 196.059 408.374 + vertex -393.935 197.441 408.615 + endloop + endfacet + facet normal 0.0256415 0.165278 -0.985914 + outer loop + vertex -393.941 198.545 408.821 + vertex -393.905 199.557 408.992 + vertex -393.875 198.081 408.745 + endloop + endfacet + facet normal 0.0835711 0.14474 -0.985934 + outer loop + vertex -393.891 200.757 409.169 + vertex -393.864 200.345 409.111 + vertex -393.905 199.557 408.992 + endloop + endfacet + facet normal -0.208703 0.156997 -0.965295 + outer loop + vertex -393.864 200.345 409.111 + vertex -393.875 198.081 408.745 + vertex -393.905 199.557 408.992 + endloop + endfacet + facet normal -0.881482 -0.0483847 0.469732 + outer loop + vertex -393.905 199.557 408.992 + vertex -393.941 198.545 408.821 + vertex -393.817 199.363 409.137 + endloop + endfacet + facet normal -0.856694 -0.0681599 0.511302 + outer loop + vertex -393.817 199.363 409.137 + vertex -393.941 198.545 408.821 + vertex -393.857 198.296 408.927 + endloop + endfacet + facet normal -0.838017 -0.0700677 0.541127 + outer loop + vertex -393.891 200.757 409.169 + vertex -393.905 199.557 408.992 + vertex -393.765 200.44 409.323 + endloop + endfacet + facet normal -0.877361 -0.0402244 0.478142 + outer loop + vertex -393.765 200.44 409.323 + vertex -393.905 199.557 408.992 + vertex -393.817 199.363 409.137 + endloop + endfacet + facet normal -0.716525 -0.0937078 0.691239 + outer loop + vertex -393.443 199.457 409.537 + vertex -393.472 199.992 409.58 + vertex -393.817 199.363 409.137 + endloop + endfacet + facet normal -0.71799 -0.0724928 0.692268 + outer loop + vertex -393.365 200.514 409.746 + vertex -393.765 200.44 409.323 + vertex -393.472 199.992 409.58 + endloop + endfacet + facet normal -0.725704 -0.0828603 0.683 + outer loop + vertex -393.765 200.44 409.323 + vertex -393.817 199.363 409.137 + vertex -393.472 199.992 409.58 + endloop + endfacet + facet normal -0.714095 -0.118093 0.690016 + outer loop + vertex -393.494 198.361 409.314 + vertex -393.537 198.907 409.364 + vertex -393.857 198.296 408.927 + endloop + endfacet + facet normal -0.716008 -0.0964507 0.691397 + outer loop + vertex -393.443 199.457 409.537 + vertex -393.817 199.363 409.137 + vertex -393.537 198.907 409.364 + endloop + endfacet + facet normal -0.72423 -0.106539 0.681279 + outer loop + vertex -393.817 199.363 409.137 + vertex -393.857 198.296 408.927 + vertex -393.537 198.907 409.364 + endloop + endfacet + facet normal -0.869569 -0.10451 0.482625 + outer loop + vertex -393.935 197.441 408.615 + vertex -393.919 196.49 408.438 + vertex -393.849 197.244 408.727 + endloop + endfacet + facet normal -0.832376 -0.129483 0.538873 + outer loop + vertex -393.849 197.244 408.727 + vertex -393.919 196.49 408.438 + vertex -393.82 196.243 408.532 + endloop + endfacet + facet normal -0.877426 -0.0923737 0.470735 + outer loop + vertex -393.941 198.545 408.821 + vertex -393.935 197.441 408.615 + vertex -393.857 198.296 408.927 + endloop + endfacet + facet normal -0.866764 -0.0998808 0.488615 + outer loop + vertex -393.857 198.296 408.927 + vertex -393.935 197.441 408.615 + vertex -393.849 197.244 408.727 + endloop + endfacet + facet normal -0.7143 -0.143774 0.684912 + outer loop + vertex -393.505 197.295 409.097 + vertex -393.567 197.826 409.144 + vertex -393.849 197.244 408.727 + endloop + endfacet + facet normal -0.713148 -0.123525 0.690045 + outer loop + vertex -393.494 198.361 409.314 + vertex -393.857 198.296 408.927 + vertex -393.567 197.826 409.144 + endloop + endfacet + facet normal -0.722532 -0.134871 0.678054 + outer loop + vertex -393.857 198.296 408.927 + vertex -393.849 197.244 408.727 + vertex -393.567 197.826 409.144 + endloop + endfacet + facet normal -0.70688 -0.166593 0.687435 + outer loop + vertex -393.476 196.275 408.894 + vertex -393.556 196.783 408.934 + vertex -393.82 196.243 408.532 + endloop + endfacet + facet normal -0.713859 -0.146257 0.684846 + outer loop + vertex -393.505 197.295 409.097 + vertex -393.849 197.244 408.727 + vertex -393.556 196.783 408.934 + endloop + endfacet + facet normal -0.719416 -0.1531 0.677496 + outer loop + vertex -393.849 197.244 408.727 + vertex -393.82 196.243 408.532 + vertex -393.556 196.783 408.934 + endloop + endfacet + facet normal 0.680347 -0.209217 0.702393 + outer loop + vertex 393.306 193.441 408.265 + vertex 393.335 193.102 408.135 + vertex 393.655 193.747 408.018 + endloop + endfacet + facet normal 0.687013 -0.230364 0.689163 + outer loop + vertex 393.248 192.682 408.082 + vertex 393.563 192.975 407.866 + vertex 393.335 193.102 408.135 + endloop + endfacet + facet normal 0.692429 -0.217859 0.687808 + outer loop + vertex 393.563 192.975 407.866 + vertex 393.655 193.747 408.018 + vertex 393.335 193.102 408.135 + endloop + endfacet + facet normal 0.681167 -0.199116 0.704531 + outer loop + vertex 393.38 194.271 408.434 + vertex 393.396 193.889 408.31 + vertex 393.76 194.615 408.164 + endloop + endfacet + facet normal 0.679969 -0.20826 0.703043 + outer loop + vertex 393.306 193.441 408.265 + vertex 393.655 193.747 408.018 + vertex 393.396 193.889 408.31 + endloop + endfacet + facet normal 0.683172 -0.200595 0.702166 + outer loop + vertex 393.655 193.747 408.018 + vertex 393.76 194.615 408.164 + vertex 393.396 193.889 408.31 + endloop + endfacet + facet normal 0.81573 -0.190339 0.546219 + outer loop + vertex 393.76 194.615 408.164 + vertex 393.655 193.747 408.018 + vertex 393.811 194.331 407.988 + endloop + endfacet + facet normal 0.838242 -0.198299 0.507965 + outer loop + vertex 393.811 194.331 407.988 + vertex 393.655 193.747 408.018 + vertex 393.713 193.635 407.878 + endloop + endfacet + facet normal 0.837258 -0.199996 0.50892 + outer loop + vertex 393.655 193.747 408.018 + vertex 393.563 192.975 407.866 + vertex 393.713 193.635 407.878 + endloop + endfacet + facet normal 0.863044 -0.205017 0.461653 + outer loop + vertex 393.713 193.635 407.878 + vertex 393.563 192.975 407.866 + vertex 393.607 192.859 407.731 + endloop + endfacet + facet normal 0.677648 -0.185739 0.711544 + outer loop + vertex 393.496 195.516 408.662 + vertex 393.505 194.844 408.478 + vertex 393.894 195.613 408.308 + endloop + endfacet + facet normal 0.683073 -0.203709 0.701365 + outer loop + vertex 393.38 194.271 408.434 + vertex 393.76 194.615 408.164 + vertex 393.505 194.844 408.478 + endloop + endfacet + facet normal 0.688525 -0.194077 0.698762 + outer loop + vertex 393.76 194.615 408.164 + vertex 393.894 195.613 408.308 + vertex 393.505 194.844 408.478 + endloop + endfacet + facet normal 0.614547 -0.155704 0.773361 + outer loop + vertex 393.213 195.935 408.971 + vertex 393.496 195.516 408.662 + vertex 393.8 196.487 408.616 + endloop + endfacet + facet normal 0.677582 -0.178281 0.713512 + outer loop + vertex 393.8 196.487 408.616 + vertex 393.496 195.516 408.662 + vertex 393.894 195.613 408.308 + endloop + endfacet + facet normal 0.726861 -0.157104 0.668574 + outer loop + vertex 393.8 196.487 408.616 + vertex 393.894 195.613 408.308 + vertex 394.027 196.471 408.366 + endloop + endfacet + facet normal 0.861354 -0.165144 0.480412 + outer loop + vertex 394.027 196.471 408.366 + vertex 393.894 195.613 408.308 + vertex 393.938 195.352 408.14 + endloop + endfacet + facet normal 0.840103 -0.187171 0.509111 + outer loop + vertex 393.894 195.613 408.308 + vertex 393.76 194.615 408.164 + vertex 393.938 195.352 408.14 + endloop + endfacet + facet normal 0.824251 -0.182469 0.536018 + outer loop + vertex 393.938 195.352 408.14 + vertex 393.76 194.615 408.164 + vertex 393.811 194.331 407.988 + endloop + endfacet + facet normal 0.320442 -0.345141 0.882153 + outer loop + vertex 382.286 187.518 411.254 + vertex 382.352 186.574 410.861 + vertex 386.162 189.405 410.585 + endloop + endfacet + facet normal 0.309969 -0.330128 0.891591 + outer loop + vertex 386.162 189.405 410.585 + vertex 382.352 186.574 410.861 + vertex 386.211 188.514 410.238 + endloop + endfacet + facet normal 0.316634 -0.324729 0.891232 + outer loop + vertex 382.219 188.459 411.621 + vertex 382.286 187.518 411.254 + vertex 386.128 190.321 410.911 + endloop + endfacet + facet normal 0.306033 -0.309074 0.900454 + outer loop + vertex 386.128 190.321 410.911 + vertex 382.286 187.518 411.254 + vertex 386.162 189.405 410.585 + endloop + endfacet + facet normal 0.382067 -0.297249 0.875025 + outer loop + vertex 386.128 190.321 410.911 + vertex 386.162 189.405 410.585 + vertex 389.641 192.135 409.993 + endloop + endfacet + facet normal 0.37163 -0.281878 0.884554 + outer loop + vertex 389.641 192.135 409.993 + vertex 386.162 189.405 410.585 + vertex 389.639 191.265 409.717 + endloop + endfacet + facet normal 0.385585 -0.316267 0.866775 + outer loop + vertex 386.162 189.405 410.585 + vertex 386.211 188.514 410.238 + vertex 389.639 191.265 409.717 + endloop + endfacet + facet normal 0.372978 -0.298326 0.878572 + outer loop + vertex 389.639 191.265 409.717 + vertex 386.211 188.514 410.238 + vertex 389.669 190.452 409.428 + endloop + endfacet + facet normal 0.321653 -0.32399 0.889702 + outer loop + vertex 382.156 189.408 411.989 + vertex 382.219 188.459 411.621 + vertex 386.05 191.246 411.251 + endloop + endfacet + facet normal 0.309069 -0.305228 0.900729 + outer loop + vertex 386.05 191.246 411.251 + vertex 382.219 188.459 411.621 + vertex 386.128 190.321 410.911 + endloop + endfacet + facet normal 0.325045 -0.31455 0.891854 + outer loop + vertex 382.095 190.385 412.356 + vertex 382.156 189.408 411.989 + vertex 385.944 192.203 411.595 + endloop + endfacet + facet normal 0.309042 -0.290937 0.905455 + outer loop + vertex 385.944 192.203 411.595 + vertex 382.156 189.408 411.989 + vertex 386.05 191.246 411.251 + endloop + endfacet + facet normal 0.390016 -0.272666 0.879512 + outer loop + vertex 385.944 192.203 411.595 + vertex 386.05 191.246 411.251 + vertex 389.241 193.886 410.654 + endloop + endfacet + facet normal 0.373129 -0.24904 0.893731 + outer loop + vertex 389.241 193.886 410.654 + vertex 386.05 191.246 411.251 + vertex 389.617 193.082 410.273 + endloop + endfacet + facet normal 0.388543 -0.288992 0.874939 + outer loop + vertex 386.05 191.246 411.251 + vertex 386.128 190.321 410.911 + vertex 389.617 193.082 410.273 + endloop + endfacet + facet normal 0.365758 -0.255578 0.894931 + outer loop + vertex 389.617 193.082 410.273 + vertex 386.128 190.321 410.911 + vertex 389.641 192.135 409.993 + endloop + endfacet + facet normal 0.44647 -0.27142 0.852641 + outer loop + vertex 391.837 193.607 409.312 + vertex 391.546 193.893 409.555 + vertex 389.641 192.135 409.993 + endloop + endfacet + facet normal 0.422772 -0.229135 0.87679 + outer loop + vertex 391.616 194.404 409.655 + vertex 389.617 193.082 410.273 + vertex 391.546 193.893 409.555 + endloop + endfacet + facet normal 0.42749 -0.246603 0.869735 + outer loop + vertex 389.617 193.082 410.273 + vertex 389.641 192.135 409.993 + vertex 391.546 193.893 409.555 + endloop + endfacet + facet normal 0.439291 -0.208538 0.873805 + outer loop + vertex 389.241 193.886 410.654 + vertex 389.617 193.082 410.273 + vertex 391.808 195.164 409.669 + endloop + endfacet + facet normal 0.357861 -0.10721 0.9276 + outer loop + vertex 391.808 195.164 409.669 + vertex 389.617 193.082 410.273 + vertex 391.616 194.404 409.655 + endloop + endfacet + facet normal 0.484405 -0.138155 0.863866 + outer loop + vertex 391.616 194.404 409.655 + vertex 392.625 195.029 409.189 + vertex 391.808 195.164 409.669 + endloop + endfacet + facet normal 0.583395 -0.188914 0.789913 + outer loop + vertex 393.496 195.516 408.662 + vertex 393.213 195.935 408.971 + vertex 392.625 195.029 409.189 + endloop + endfacet + facet normal 0.489651 -0.110116 0.864938 + outer loop + vertex 393.213 195.935 408.971 + vertex 391.808 195.164 409.669 + vertex 392.625 195.029 409.189 + endloop + endfacet + facet normal 0.508086 -0.196743 0.838535 + outer loop + vertex 391.546 193.893 409.555 + vertex 391.837 193.607 409.312 + vertex 392.806 194.575 408.951 + endloop + endfacet + facet normal 0.525176 -0.219998 0.822065 + outer loop + vertex 392.806 194.575 408.951 + vertex 391.837 193.607 409.312 + vertex 392.799 194.061 408.819 + endloop + endfacet + facet normal 0.522411 -0.231731 0.820602 + outer loop + vertex 391.616 194.404 409.655 + vertex 391.546 193.893 409.555 + vertex 392.625 195.029 409.189 + endloop + endfacet + facet normal 0.51733 -0.225292 0.825599 + outer loop + vertex 392.625 195.029 409.189 + vertex 391.546 193.893 409.555 + vertex 392.806 194.575 408.951 + endloop + endfacet + facet normal 0.581562 -0.18256 0.792753 + outer loop + vertex 392.625 195.029 409.189 + vertex 392.806 194.575 408.951 + vertex 393.496 195.516 408.662 + endloop + endfacet + facet normal 0.601566 -0.203449 0.772481 + outer loop + vertex 393.496 195.516 408.662 + vertex 392.806 194.575 408.951 + vertex 393.505 194.844 408.478 + endloop + endfacet + facet normal 0.602171 -0.207966 0.770805 + outer loop + vertex 392.806 194.575 408.951 + vertex 392.799 194.061 408.819 + vertex 393.505 194.844 408.478 + endloop + endfacet + facet normal 0.589043 -0.189731 0.785513 + outer loop + vertex 393.505 194.844 408.478 + vertex 392.799 194.061 408.819 + vertex 393.38 194.271 408.434 + endloop + endfacet + facet normal 0.442378 -0.291527 0.848124 + outer loop + vertex 391.791 191.975 408.844 + vertex 391.535 192.177 409.047 + vertex 389.669 190.452 409.428 + endloop + endfacet + facet normal 0.426944 -0.250011 0.86903 + outer loop + vertex 391.796 192.746 409.083 + vertex 389.639 191.265 409.717 + vertex 391.535 192.177 409.047 + endloop + endfacet + facet normal 0.43841 -0.2864 0.851922 + outer loop + vertex 389.639 191.265 409.717 + vertex 389.669 190.452 409.428 + vertex 391.535 192.177 409.047 + endloop + endfacet + facet normal 0.438442 -0.272084 0.856586 + outer loop + vertex 391.796 192.746 409.083 + vertex 391.554 192.98 409.281 + vertex 389.639 191.265 409.717 + endloop + endfacet + facet normal 0.428732 -0.235979 0.872068 + outer loop + vertex 391.837 193.607 409.312 + vertex 389.641 192.135 409.993 + vertex 391.554 192.98 409.281 + endloop + endfacet + facet normal 0.439087 -0.272959 0.855977 + outer loop + vertex 389.641 192.135 409.993 + vertex 389.639 191.265 409.717 + vertex 391.554 192.98 409.281 + endloop + endfacet + facet normal 0.497363 -0.200497 0.844056 + outer loop + vertex 391.554 192.98 409.281 + vertex 391.796 192.746 409.083 + vertex 392.755 193.612 408.723 + endloop + endfacet + facet normal 0.516237 -0.229237 0.825197 + outer loop + vertex 392.755 193.612 408.723 + vertex 391.796 192.746 409.083 + vertex 392.736 193.216 408.626 + endloop + endfacet + facet normal 0.539686 -0.282165 0.793172 + outer loop + vertex 391.837 193.607 409.312 + vertex 391.554 192.98 409.281 + vertex 392.799 194.061 408.819 + endloop + endfacet + facet normal 0.505431 -0.225755 0.832811 + outer loop + vertex 392.799 194.061 408.819 + vertex 391.554 192.98 409.281 + vertex 392.755 193.612 408.723 + endloop + endfacet + facet normal 0.593038 -0.221656 0.774064 + outer loop + vertex 392.799 194.061 408.819 + vertex 392.755 193.612 408.723 + vertex 393.38 194.271 408.434 + endloop + endfacet + facet normal 0.594927 -0.224436 0.77181 + outer loop + vertex 393.38 194.271 408.434 + vertex 392.755 193.612 408.723 + vertex 393.396 193.889 408.31 + endloop + endfacet + facet normal 0.594259 -0.220369 0.773494 + outer loop + vertex 392.755 193.612 408.723 + vertex 392.736 193.216 408.626 + vertex 393.396 193.889 408.31 + endloop + endfacet + facet normal 0.578809 -0.196812 0.791357 + outer loop + vertex 393.396 193.889 408.31 + vertex 392.736 193.216 408.626 + vertex 393.306 193.441 408.265 + endloop + endfacet + facet normal 0.493778 -0.219728 0.84137 + outer loop + vertex 391.535 192.177 409.047 + vertex 391.791 191.975 408.844 + vertex 392.723 192.834 408.522 + endloop + endfacet + facet normal 0.51375 -0.24904 0.820999 + outer loop + vertex 392.723 192.834 408.522 + vertex 391.791 191.975 408.844 + vertex 392.709 192.456 408.416 + endloop + endfacet + facet normal 0.533111 -0.293974 0.79333 + outer loop + vertex 391.796 192.746 409.083 + vertex 391.535 192.177 409.047 + vertex 392.736 193.216 408.626 + endloop + endfacet + facet normal 0.501473 -0.242302 0.830551 + outer loop + vertex 392.736 193.216 408.626 + vertex 391.535 192.177 409.047 + vertex 392.723 192.834 408.522 + endloop + endfacet + facet normal 0.58397 -0.230904 0.778243 + outer loop + vertex 392.736 193.216 408.626 + vertex 392.723 192.834 408.522 + vertex 393.306 193.441 408.265 + endloop + endfacet + facet normal 0.591759 -0.242374 0.768815 + outer loop + vertex 393.306 193.441 408.265 + vertex 392.723 192.834 408.522 + vertex 393.335 193.102 408.135 + endloop + endfacet + facet normal 0.591008 -0.237756 0.770832 + outer loop + vertex 392.723 192.834 408.522 + vertex 392.709 192.456 408.416 + vertex 393.335 193.102 408.135 + endloop + endfacet + facet normal 0.579025 -0.219943 0.785083 + outer loop + vertex 393.335 193.102 408.135 + vertex 392.709 192.456 408.416 + vertex 393.248 192.682 408.082 + endloop + endfacet + facet normal -0.209929 -0.337389 0.917659 + outer loop + vertex -380.886 187.747 411.673 + vertex -380.15 186.537 411.397 + vertex -374.224 185.802 412.482 + endloop + endfacet + facet normal -0.22139 -0.39395 0.892071 + outer loop + vertex -381.094 185.898 410.881 + vertex -374.442 183.835 411.62 + vertex -380.15 186.537 411.397 + endloop + endfacet + facet normal -0.211701 -0.372531 0.90355 + outer loop + vertex -374.442 183.835 411.62 + vertex -374.224 185.802 412.482 + vertex -380.15 186.537 411.397 + endloop + endfacet + facet normal -0.212662 -0.32501 0.92149 + outer loop + vertex -380.669 189.634 412.425 + vertex -379.944 188.423 412.165 + vertex -374.028 187.791 413.308 + endloop + endfacet + facet normal -0.21538 -0.36022 0.907664 + outer loop + vertex -380.886 187.747 411.673 + vertex -374.224 185.802 412.482 + vertex -379.944 188.423 412.165 + endloop + endfacet + facet normal -0.213714 -0.356352 0.909582 + outer loop + vertex -374.224 185.802 412.482 + vertex -374.028 187.791 413.308 + vertex -379.944 188.423 412.165 + endloop + endfacet + facet normal -0.597744 -0.20736 0.774406 + outer loop + vertex -393.372 193.223 408.172 + vertex -393.295 192.823 408.124 + vertex -392.753 192.801 408.537 + endloop + endfacet + facet normal -0.593663 -0.243083 0.767121 + outer loop + vertex -392.753 192.801 408.537 + vertex -393.295 192.823 408.124 + vertex -392.72 192.403 408.437 + endloop + endfacet + facet normal -0.603064 -0.239209 0.760982 + outer loop + vertex -393.351 193.626 408.316 + vertex -393.372 193.223 408.172 + vertex -392.769 193.206 408.645 + endloop + endfacet + facet normal -0.604659 -0.22695 0.763467 + outer loop + vertex -392.769 193.206 408.645 + vertex -393.372 193.223 408.172 + vertex -392.753 192.801 408.537 + endloop + endfacet + facet normal -0.509708 -0.240002 0.826194 + outer loop + vertex -392.769 193.206 408.645 + vertex -392.753 192.801 408.537 + vertex -391.73 192.507 409.082 + endloop + endfacet + facet normal -0.514684 -0.299864 0.803232 + outer loop + vertex -391.73 192.507 409.082 + vertex -392.753 192.801 408.537 + vertex -391.431 191.954 409.067 + endloop + endfacet + facet normal -0.494914 -0.251054 0.831884 + outer loop + vertex -392.753 192.801 408.537 + vertex -392.72 192.403 408.437 + vertex -391.431 191.954 409.067 + endloop + endfacet + facet normal -0.489486 -0.218026 0.844315 + outer loop + vertex -391.431 191.954 409.067 + vertex -392.72 192.403 408.437 + vertex -391.704 191.709 408.846 + endloop + endfacet + facet normal -0.59884 -0.196741 0.776327 + outer loop + vertex -393.436 194.051 408.357 + vertex -393.351 193.626 408.316 + vertex -392.782 193.619 408.753 + endloop + endfacet + facet normal -0.595927 -0.220595 0.772145 + outer loop + vertex -392.782 193.619 408.753 + vertex -393.351 193.626 408.316 + vertex -392.769 193.206 408.645 + endloop + endfacet + facet normal -0.604779 -0.224214 0.76418 + outer loop + vertex -393.405 194.47 408.505 + vertex -393.436 194.051 408.357 + vertex -392.8 194.044 408.859 + endloop + endfacet + facet normal -0.605726 -0.217068 0.765492 + outer loop + vertex -392.8 194.044 408.859 + vertex -393.436 194.051 408.357 + vertex -392.782 193.619 408.753 + endloop + endfacet + facet normal -0.513032 -0.228542 0.827385 + outer loop + vertex -392.8 194.044 408.859 + vertex -392.782 193.619 408.753 + vertex -391.738 193.345 409.324 + endloop + endfacet + facet normal -0.516929 -0.286541 0.806647 + outer loop + vertex -391.738 193.345 409.324 + vertex -392.782 193.619 408.753 + vertex -391.437 192.774 409.315 + endloop + endfacet + facet normal -0.496306 -0.234187 0.835964 + outer loop + vertex -392.782 193.619 408.753 + vertex -392.769 193.206 408.645 + vertex -391.437 192.774 409.315 + endloop + endfacet + facet normal -0.490885 -0.198137 0.848395 + outer loop + vertex -391.437 192.774 409.315 + vertex -392.769 193.206 408.645 + vertex -391.73 192.507 409.082 + endloop + endfacet + facet normal -0.409077 -0.230723 0.882849 + outer loop + vertex -391.738 193.345 409.324 + vertex -391.437 192.774 409.315 + vertex -389.149 192.117 410.203 + endloop + endfacet + facet normal -0.422207 -0.284271 0.860774 + outer loop + vertex -391.73 192.507 409.082 + vertex -389.182 191.255 409.919 + vertex -391.437 192.774 409.315 + endloop + endfacet + facet normal -0.415004 -0.270433 0.868699 + outer loop + vertex -389.182 191.255 409.919 + vertex -389.149 192.117 410.203 + vertex -391.437 192.774 409.315 + endloop + endfacet + facet normal -0.408782 -0.244598 0.879244 + outer loop + vertex -391.73 192.507 409.082 + vertex -391.431 191.954 409.067 + vertex -389.182 191.255 409.919 + endloop + endfacet + facet normal -0.421871 -0.302554 0.854684 + outer loop + vertex -391.704 191.709 408.846 + vertex -389.198 190.427 409.629 + vertex -391.431 191.954 409.067 + endloop + endfacet + facet normal -0.416711 -0.29284 0.860579 + outer loop + vertex -389.198 190.427 409.629 + vertex -389.182 191.255 409.919 + vertex -391.431 191.954 409.067 + endloop + endfacet + facet normal -0.60132 -0.178536 0.778807 + outer loop + vertex -393.474 194.9 408.55 + vertex -393.405 194.47 408.505 + vertex -392.809 194.469 408.965 + endloop + endfacet + facet normal -0.598052 -0.206074 0.774511 + outer loop + vertex -392.809 194.469 408.965 + vertex -393.405 194.47 408.505 + vertex -392.8 194.044 408.859 + endloop + endfacet + facet normal -0.608107 -0.212093 0.764999 + outer loop + vertex -393.443 195.34 408.697 + vertex -393.474 194.9 408.55 + vertex -392.825 194.908 409.069 + endloop + endfacet + facet normal -0.609396 -0.202814 0.766488 + outer loop + vertex -392.825 194.908 409.069 + vertex -393.474 194.9 408.55 + vertex -392.809 194.469 408.965 + endloop + endfacet + facet normal -0.514712 -0.2144 0.830123 + outer loop + vertex -392.825 194.908 409.069 + vertex -392.809 194.469 408.965 + vertex -391.737 194.208 409.562 + endloop + endfacet + facet normal -0.517925 -0.269625 0.811823 + outer loop + vertex -391.737 194.208 409.562 + vertex -392.809 194.469 408.965 + vertex -391.439 193.631 409.56 + endloop + endfacet + facet normal -0.499008 -0.219949 0.83822 + outer loop + vertex -392.809 194.469 408.965 + vertex -392.8 194.044 408.859 + vertex -391.439 193.631 409.56 + endloop + endfacet + facet normal -0.49425 -0.185425 0.849314 + outer loop + vertex -391.439 193.631 409.56 + vertex -392.8 194.044 408.859 + vertex -391.738 193.345 409.324 + endloop + endfacet + facet normal -0.602914 -0.168893 0.779724 + outer loop + vertex -393.522 195.805 408.737 + vertex -393.443 195.34 408.697 + vertex -392.828 195.353 409.176 + endloop + endfacet + facet normal -0.600177 -0.190564 0.776835 + outer loop + vertex -392.828 195.353 409.176 + vertex -393.443 195.34 408.697 + vertex -392.825 194.908 409.069 + endloop + endfacet + facet normal -0.608921 -0.197004 0.768378 + outer loop + vertex -393.476 196.275 408.894 + vertex -393.522 195.805 408.737 + vertex -392.84 195.825 409.282 + endloop + endfacet + facet normal -0.609946 -0.189753 0.769389 + outer loop + vertex -392.84 195.825 409.282 + vertex -393.522 195.805 408.737 + vertex -392.828 195.353 409.176 + endloop + endfacet + facet normal -0.51787 -0.201412 0.831411 + outer loop + vertex -392.84 195.825 409.282 + vertex -392.828 195.353 409.176 + vertex -391.734 195.12 409.8 + endloop + endfacet + facet normal -0.520158 -0.260188 0.813473 + outer loop + vertex -391.734 195.12 409.8 + vertex -392.828 195.353 409.176 + vertex -391.426 194.516 409.804 + endloop + endfacet + facet normal -0.499914 -0.205388 0.841369 + outer loop + vertex -392.828 195.353 409.176 + vertex -392.825 194.908 409.069 + vertex -391.426 194.516 409.804 + endloop + endfacet + facet normal -0.495309 -0.16864 0.852191 + outer loop + vertex -391.426 194.516 409.804 + vertex -392.825 194.908 409.069 + vertex -391.737 194.208 409.562 + endloop + endfacet + facet normal -0.41294 -0.205154 0.887352 + outer loop + vertex -391.734 195.12 409.8 + vertex -391.426 194.516 409.804 + vertex -389.055 193.944 410.775 + endloop + endfacet + facet normal -0.423018 -0.25537 0.869392 + outer loop + vertex -391.737 194.208 409.562 + vertex -389.11 193.009 410.488 + vertex -391.426 194.516 409.804 + endloop + endfacet + facet normal -0.41739 -0.244019 0.875352 + outer loop + vertex -389.11 193.009 410.488 + vertex -389.055 193.944 410.775 + vertex -391.426 194.516 409.804 + endloop + endfacet + facet normal -0.410277 -0.214343 0.886414 + outer loop + vertex -391.737 194.208 409.562 + vertex -391.439 193.631 409.56 + vertex -389.11 193.009 410.488 + endloop + endfacet + facet normal -0.422675 -0.272672 0.864289 + outer loop + vertex -391.738 193.345 409.324 + vertex -389.149 192.117 410.203 + vertex -391.439 193.631 409.56 + endloop + endfacet + facet normal -0.416467 -0.260411 0.871058 + outer loop + vertex -389.149 192.117 410.203 + vertex -389.11 193.009 410.488 + vertex -391.439 193.631 409.56 + endloop + endfacet + facet normal -0.349788 -0.271502 0.896624 + outer loop + vertex -389.11 193.009 410.488 + vertex -389.149 192.117 410.203 + vertex -384.87 190.704 411.444 + endloop + endfacet + facet normal -0.354988 -0.295869 0.886817 + outer loop + vertex -384.87 190.704 411.444 + vertex -389.149 192.117 410.203 + vertex -384.95 189.79 411.107 + endloop + endfacet + facet normal -0.348904 -0.256069 0.901496 + outer loop + vertex -389.055 193.944 410.775 + vertex -389.11 193.009 410.488 + vertex -384.767 191.649 411.783 + endloop + endfacet + facet normal -0.35388 -0.280903 0.892111 + outer loop + vertex -384.767 191.649 411.783 + vertex -389.11 193.009 410.488 + vertex -384.87 190.704 411.444 + endloop + endfacet + facet normal -0.287873 -0.294954 0.911116 + outer loop + vertex -384.767 191.649 411.783 + vertex -384.87 190.704 411.444 + vertex -380.669 189.634 412.425 + endloop + endfacet + facet normal -0.299295 -0.368076 0.880308 + outer loop + vertex -380.669 189.634 412.425 + vertex -384.87 190.704 411.444 + vertex -379.944 188.423 412.165 + endloop + endfacet + facet normal -0.27707 -0.310937 0.909148 + outer loop + vertex -384.87 190.704 411.444 + vertex -384.95 189.79 411.107 + vertex -379.944 188.423 412.165 + endloop + endfacet + facet normal -0.272673 -0.287982 0.917995 + outer loop + vertex -379.944 188.423 412.165 + vertex -384.95 189.79 411.107 + vertex -380.886 187.747 411.673 + endloop + endfacet + facet normal -0.35173 -0.302867 0.885753 + outer loop + vertex -389.182 191.255 409.919 + vertex -389.198 190.427 409.629 + vertex -385.022 188.899 410.765 + endloop + endfacet + facet normal -0.3576 -0.327138 0.874701 + outer loop + vertex -385.022 188.899 410.765 + vertex -389.198 190.427 409.629 + vertex -385.093 188.026 410.41 + endloop + endfacet + facet normal -0.348495 -0.281317 0.894098 + outer loop + vertex -389.149 192.117 410.203 + vertex -389.182 191.255 409.919 + vertex -384.95 189.79 411.107 + endloop + endfacet + facet normal -0.355031 -0.31007 0.881935 + outer loop + vertex -384.95 189.79 411.107 + vertex -389.182 191.255 409.919 + vertex -385.022 188.899 410.765 + endloop + endfacet + facet normal -0.287969 -0.322961 0.901538 + outer loop + vertex -384.95 189.79 411.107 + vertex -385.022 188.899 410.765 + vertex -380.886 187.747 411.673 + endloop + endfacet + facet normal -0.298416 -0.381434 0.874903 + outer loop + vertex -380.886 187.747 411.673 + vertex -385.022 188.899 410.765 + vertex -380.15 186.537 411.397 + endloop + endfacet + facet normal -0.282122 -0.342117 0.896305 + outer loop + vertex -385.022 188.899 410.765 + vertex -385.093 188.026 410.41 + vertex -380.15 186.537 411.397 + endloop + endfacet + facet normal -0.277693 -0.321464 0.905289 + outer loop + vertex -380.15 186.537 411.397 + vertex -385.093 188.026 410.41 + vertex -381.094 185.898 410.881 + endloop + endfacet + facet normal -0.0116793 0.190922 -0.981536 + outer loop + vertex -393.651 193.04 407.767 + vertex -393.729 193.774 407.911 + vertex -393.597 192.884 407.736 + endloop + endfacet + facet normal 0.292526 0.212483 -0.932351 + outer loop + vertex -393.812 194.633 408.08 + vertex -393.724 194.241 408.018 + vertex -393.729 193.774 407.911 + endloop + endfacet + facet normal 0.209159 0.218127 -0.953244 + outer loop + vertex -393.724 194.241 408.018 + vertex -393.597 192.884 407.736 + vertex -393.729 193.774 407.911 + endloop + endfacet + facet normal 0.206364 0.197311 -0.958375 + outer loop + vertex -393.812 194.633 408.08 + vertex -393.863 195.479 408.244 + vertex -393.724 194.241 408.018 + endloop + endfacet + facet normal 0.307564 0.196291 -0.931061 + outer loop + vertex -393.919 196.49 408.438 + vertex -393.837 196.059 408.374 + vertex -393.863 195.479 408.244 + endloop + endfacet + facet normal 0.2637 0.201007 -0.943429 + outer loop + vertex -393.837 196.059 408.374 + vertex -393.724 194.241 408.018 + vertex -393.863 195.479 408.244 + endloop + endfacet + facet normal -0.85363 -0.147627 0.499521 + outer loop + vertex -393.863 195.479 408.244 + vertex -393.812 194.633 408.08 + vertex -393.77 195.305 408.35 + endloop + endfacet + facet normal -0.827971 -0.163974 0.536261 + outer loop + vertex -393.77 195.305 408.35 + vertex -393.812 194.633 408.08 + vertex -393.71 194.43 408.176 + endloop + endfacet + facet normal -0.846682 -0.145505 0.511818 + outer loop + vertex -393.919 196.49 408.438 + vertex -393.863 195.479 408.244 + vertex -393.82 196.243 408.532 + endloop + endfacet + facet normal -0.851093 -0.142766 0.505231 + outer loop + vertex -393.82 196.243 408.532 + vertex -393.863 195.479 408.244 + vertex -393.77 195.305 408.35 + endloop + endfacet + facet normal -0.706157 -0.178341 0.685228 + outer loop + vertex -393.443 195.34 408.697 + vertex -393.522 195.805 408.737 + vertex -393.77 195.305 408.35 + endloop + endfacet + facet normal -0.707893 -0.16049 0.687845 + outer loop + vertex -393.476 196.275 408.894 + vertex -393.82 196.243 408.532 + vertex -393.522 195.805 408.737 + endloop + endfacet + facet normal -0.714534 -0.169223 0.678827 + outer loop + vertex -393.82 196.243 408.532 + vertex -393.77 195.305 408.35 + vertex -393.522 195.805 408.737 + endloop + endfacet + facet normal -0.709491 -0.185512 0.679858 + outer loop + vertex -393.405 194.47 408.505 + vertex -393.474 194.9 408.55 + vertex -393.71 194.43 408.176 + endloop + endfacet + facet normal -0.706155 -0.178349 0.685227 + outer loop + vertex -393.443 195.34 408.697 + vertex -393.77 195.305 408.35 + vertex -393.474 194.9 408.55 + endloop + endfacet + facet normal -0.710436 -0.184475 0.679153 + outer loop + vertex -393.77 195.305 408.35 + vertex -393.71 194.43 408.176 + vertex -393.474 194.9 408.55 + endloop + endfacet + facet normal -0.863106 -0.183774 0.470399 + outer loop + vertex -393.729 193.774 407.911 + vertex -393.651 193.04 407.767 + vertex -393.641 193.599 408.004 + endloop + endfacet + facet normal -0.838258 -0.199831 0.507338 + outer loop + vertex -393.641 193.599 408.004 + vertex -393.651 193.04 407.767 + vertex -393.552 192.811 407.841 + endloop + endfacet + facet normal -0.840247 -0.182214 0.510669 + outer loop + vertex -393.812 194.633 408.08 + vertex -393.729 193.774 407.911 + vertex -393.71 194.43 408.176 + endloop + endfacet + facet normal -0.856624 -0.171972 0.486436 + outer loop + vertex -393.71 194.43 408.176 + vertex -393.729 193.774 407.911 + vertex -393.641 193.599 408.004 + endloop + endfacet + facet normal -0.706846 -0.208638 0.675898 + outer loop + vertex -393.351 193.626 408.316 + vertex -393.436 194.051 408.357 + vertex -393.641 193.599 408.004 + endloop + endfacet + facet normal -0.709251 -0.186718 0.679779 + outer loop + vertex -393.405 194.47 408.505 + vertex -393.71 194.43 408.176 + vertex -393.436 194.051 408.357 + endloop + endfacet + facet normal -0.717139 -0.197964 0.668223 + outer loop + vertex -393.71 194.43 408.176 + vertex -393.641 193.599 408.004 + vertex -393.436 194.051 408.357 + endloop + endfacet + facet normal -0.719126 -0.216914 0.660156 + outer loop + vertex -393.295 192.823 408.124 + vertex -393.372 193.223 408.172 + vertex -393.552 192.811 407.841 + endloop + endfacet + facet normal -0.707866 -0.203475 0.676405 + outer loop + vertex -393.351 193.626 408.316 + vertex -393.641 193.599 408.004 + vertex -393.372 193.223 408.172 + endloop + endfacet + facet normal -0.718222 -0.21785 0.660831 + outer loop + vertex -393.641 193.599 408.004 + vertex -393.552 192.811 407.841 + vertex -393.372 193.223 408.172 + endloop + endfacet + facet normal 0.821398 -0.56165 -0.0992717 + outer loop + vertex 393.212 190.817 407.478 + vertex 392.867 190.301 407.545 + vertex 393.414 191.126 407.399 + endloop + endfacet + facet normal 0.507514 -0.18697 0.841113 + outer loop + vertex 393.414 191.126 407.399 + vertex 392.867 190.301 407.545 + vertex 393.396 190.821 407.342 + endloop + endfacet + facet normal 0.675754 -0.239488 0.697139 + outer loop + vertex 393.184 191.322 407.681 + vertex 393.235 191.073 407.546 + vertex 393.45 191.622 407.526 + endloop + endfacet + facet normal 0.657001 -0.245795 0.712695 + outer loop + vertex 393.212 190.817 407.478 + vertex 393.414 191.126 407.399 + vertex 393.235 191.073 407.546 + endloop + endfacet + facet normal 0.656836 -0.231374 0.717658 + outer loop + vertex 393.414 191.126 407.399 + vertex 393.45 191.622 407.526 + vertex 393.235 191.073 407.546 + endloop + endfacet + facet normal 0.802792 -0.201794 0.561074 + outer loop + vertex 393.45 191.622 407.526 + vertex 393.414 191.126 407.399 + vertex 393.502 191.609 407.447 + endloop + endfacet + facet normal 0.668007 -0.192759 0.718756 + outer loop + vertex 393.502 191.609 407.447 + vertex 393.414 191.126 407.399 + vertex 393.486 191.219 407.357 + endloop + endfacet + facet normal 0.655167 -0.175561 0.734802 + outer loop + vertex 393.414 191.126 407.399 + vertex 393.396 190.821 407.342 + vertex 393.486 191.219 407.357 + endloop + endfacet + facet normal 0.589519 -0.162824 0.791174 + outer loop + vertex 393.486 191.219 407.357 + vertex 393.396 190.821 407.342 + vertex 393.494 190.898 407.285 + endloop + endfacet + facet normal 0.686266 -0.23462 0.688471 + outer loop + vertex 393.198 191.986 407.896 + vertex 393.229 191.693 407.766 + vertex 393.484 192.247 407.7 + endloop + endfacet + facet normal 0.677123 -0.241805 0.695007 + outer loop + vertex 393.184 191.322 407.681 + vertex 393.45 191.622 407.526 + vertex 393.229 191.693 407.766 + endloop + endfacet + facet normal 0.680669 -0.231251 0.695135 + outer loop + vertex 393.45 191.622 407.526 + vertex 393.484 192.247 407.7 + vertex 393.229 191.693 407.766 + endloop + endfacet + facet normal 0.686526 -0.229199 0.690036 + outer loop + vertex 393.248 192.682 408.082 + vertex 393.266 192.364 407.958 + vertex 393.563 192.975 407.866 + endloop + endfacet + facet normal 0.686476 -0.235143 0.688083 + outer loop + vertex 393.198 191.986 407.896 + vertex 393.484 192.247 407.7 + vertex 393.266 192.364 407.958 + endloop + endfacet + facet normal 0.688473 -0.230503 0.687657 + outer loop + vertex 393.484 192.247 407.7 + vertex 393.563 192.975 407.866 + vertex 393.266 192.364 407.958 + endloop + endfacet + facet normal 0.867656 -0.197176 0.456394 + outer loop + vertex 393.563 192.975 407.866 + vertex 393.484 192.247 407.7 + vertex 393.607 192.859 407.731 + endloop + endfacet + facet normal 0.832712 -0.19334 0.518854 + outer loop + vertex 393.607 192.859 407.731 + vertex 393.484 192.247 407.7 + vertex 393.527 192.051 407.559 + endloop + endfacet + facet normal 0.836112 -0.189611 0.514747 + outer loop + vertex 393.484 192.247 407.7 + vertex 393.45 191.622 407.526 + vertex 393.527 192.051 407.559 + endloop + endfacet + facet normal 0.806259 -0.18769 0.560998 + outer loop + vertex 393.527 192.051 407.559 + vertex 393.45 191.622 407.526 + vertex 393.502 191.609 407.447 + endloop + endfacet + facet normal 0.31581 -0.372179 0.872781 + outer loop + vertex 382.65 183.954 409.672 + vertex 382.722 183.379 409.401 + vertex 386.413 186.049 409.204 + endloop + endfacet + facet normal 0.300361 -0.349743 0.887391 + outer loop + vertex 386.413 186.049 409.204 + vertex 382.722 183.379 409.401 + vertex 386.432 185.498 408.98 + endloop + endfacet + facet normal 0.321341 -0.370222 0.871594 + outer loop + vertex 382.556 184.735 410.038 + vertex 382.65 183.954 409.672 + vertex 386.383 186.809 409.508 + endloop + endfacet + facet normal 0.302322 -0.344365 0.888828 + outer loop + vertex 386.383 186.809 409.508 + vertex 382.65 183.954 409.672 + vertex 386.413 186.049 409.204 + endloop + endfacet + facet normal 0.379174 -0.331411 0.863941 + outer loop + vertex 386.383 186.809 409.508 + vertex 386.413 186.049 409.204 + vertex 389.699 188.854 408.838 + endloop + endfacet + facet normal 0.346052 -0.288855 0.892642 + outer loop + vertex 389.699 188.854 408.838 + vertex 386.413 186.049 409.204 + vertex 389.35 187.903 408.665 + endloop + endfacet + facet normal 0.371892 -0.337967 0.864566 + outer loop + vertex 386.413 186.049 409.204 + vertex 386.432 185.498 408.98 + vertex 389.35 187.903 408.665 + endloop + endfacet + facet normal 0.36734 -0.331882 0.868859 + outer loop + vertex 389.35 187.903 408.665 + vertex 386.432 185.498 408.98 + vertex 389.372 187.451 408.483 + endloop + endfacet + facet normal 0.319126 -0.358301 0.877371 + outer loop + vertex 382.442 185.636 410.447 + vertex 382.556 184.735 410.038 + vertex 386.289 187.642 409.868 + endloop + endfacet + facet normal 0.310484 -0.346753 0.885077 + outer loop + vertex 386.289 187.642 409.868 + vertex 382.556 184.735 410.038 + vertex 386.383 186.809 409.508 + endloop + endfacet + facet normal 0.320717 -0.355964 0.877741 + outer loop + vertex 382.352 186.574 410.861 + vertex 382.442 185.636 410.447 + vertex 386.211 188.514 410.238 + endloop + endfacet + facet normal 0.314151 -0.346931 0.883713 + outer loop + vertex 386.211 188.514 410.238 + vertex 382.442 185.636 410.447 + vertex 386.289 187.642 409.868 + endloop + endfacet + facet normal 0.38693 -0.330661 0.860784 + outer loop + vertex 386.211 188.514 410.238 + vertex 386.289 187.642 409.868 + vertex 389.669 190.452 409.428 + endloop + endfacet + facet normal 0.375527 -0.315256 0.871546 + outer loop + vertex 389.669 190.452 409.428 + vertex 386.289 187.642 409.868 + vertex 389.709 189.658 409.123 + endloop + endfacet + facet normal 0.382083 -0.329374 0.863438 + outer loop + vertex 386.289 187.642 409.868 + vertex 386.383 186.809 409.508 + vertex 389.709 189.658 409.123 + endloop + endfacet + facet normal 0.371099 -0.315193 0.873463 + outer loop + vertex 389.709 189.658 409.123 + vertex 386.383 186.809 409.508 + vertex 389.699 188.854 408.838 + endloop + endfacet + facet normal 0.447672 -0.3186 0.835514 + outer loop + vertex 391.776 190.489 408.348 + vertex 391.551 190.681 408.542 + vertex 389.699 188.854 408.838 + endloop + endfacet + facet normal 0.423987 -0.27246 0.863714 + outer loop + vertex 391.787 191.228 408.598 + vertex 389.709 189.658 409.123 + vertex 391.551 190.681 408.542 + endloop + endfacet + facet normal 0.437039 -0.306168 0.845729 + outer loop + vertex 389.709 189.658 409.123 + vertex 389.699 188.854 408.838 + vertex 391.551 190.681 408.542 + endloop + endfacet + facet normal 0.445062 -0.30799 0.84087 + outer loop + vertex 391.787 191.228 408.598 + vertex 391.542 191.412 408.796 + vertex 389.709 189.658 409.123 + endloop + endfacet + facet normal 0.427129 -0.263895 0.864823 + outer loop + vertex 391.791 191.975 408.844 + vertex 389.669 190.452 409.428 + vertex 391.542 191.412 408.796 + endloop + endfacet + facet normal 0.440207 -0.302042 0.84557 + outer loop + vertex 389.669 190.452 409.428 + vertex 389.709 189.658 409.123 + vertex 391.542 191.412 408.796 + endloop + endfacet + facet normal 0.493475 -0.238762 0.836346 + outer loop + vertex 391.542 191.412 408.796 + vertex 391.787 191.228 408.598 + vertex 392.69 192.089 408.312 + endloop + endfacet + facet normal 0.512297 -0.264946 0.816918 + outer loop + vertex 392.69 192.089 408.312 + vertex 391.787 191.228 408.598 + vertex 392.674 191.738 408.208 + endloop + endfacet + facet normal 0.528805 -0.302759 0.792908 + outer loop + vertex 391.791 191.975 408.844 + vertex 391.542 191.412 408.796 + vertex 392.709 192.456 408.416 + endloop + endfacet + facet normal 0.501558 -0.260639 0.824928 + outer loop + vertex 392.709 192.456 408.416 + vertex 391.542 191.412 408.796 + vertex 392.69 192.089 408.312 + endloop + endfacet + facet normal 0.583787 -0.250078 0.772433 + outer loop + vertex 392.709 192.456 408.416 + vertex 392.69 192.089 408.312 + vertex 393.248 192.682 408.082 + endloop + endfacet + facet normal 0.592568 -0.26258 0.761521 + outer loop + vertex 393.248 192.682 408.082 + vertex 392.69 192.089 408.312 + vertex 393.266 192.364 407.958 + endloop + endfacet + facet normal 0.590876 -0.253332 0.765956 + outer loop + vertex 392.69 192.089 408.312 + vertex 392.674 191.738 408.208 + vertex 393.266 192.364 407.958 + endloop + endfacet + facet normal 0.575174 -0.230985 0.784742 + outer loop + vertex 393.266 192.364 407.958 + vertex 392.674 191.738 408.208 + vertex 393.198 191.986 407.896 + endloop + endfacet + facet normal 0.494816 -0.257821 0.829871 + outer loop + vertex 391.551 190.681 408.542 + vertex 391.776 190.489 408.348 + vertex 392.67 191.399 408.098 + endloop + endfacet + facet normal 0.514539 -0.282817 0.809484 + outer loop + vertex 392.67 191.399 408.098 + vertex 391.776 190.489 408.348 + vertex 392.656 191.032 407.978 + endloop + endfacet + facet normal 0.526804 -0.309466 0.791649 + outer loop + vertex 391.787 191.228 408.598 + vertex 391.551 190.681 408.542 + vertex 392.674 191.738 408.208 + endloop + endfacet + facet normal 0.500937 -0.272578 0.82144 + outer loop + vertex 392.674 191.738 408.208 + vertex 391.551 190.681 408.542 + vertex 392.67 191.399 408.098 + endloop + endfacet + facet normal 0.580456 -0.257607 0.772469 + outer loop + vertex 392.674 191.738 408.208 + vertex 392.67 191.399 408.098 + vertex 393.198 191.986 407.896 + endloop + endfacet + facet normal 0.593353 -0.274638 0.756642 + outer loop + vertex 393.198 191.986 407.896 + vertex 392.67 191.399 408.098 + vertex 393.229 191.693 407.766 + endloop + endfacet + facet normal 0.592241 -0.269439 0.759377 + outer loop + vertex 392.67 191.399 408.098 + vertex 392.656 191.032 407.978 + vertex 393.229 191.693 407.766 + endloop + endfacet + facet normal 0.575451 -0.248542 0.779155 + outer loop + vertex 393.229 191.693 407.766 + vertex 392.656 191.032 407.978 + vertex 393.184 191.322 407.681 + endloop + endfacet + facet normal 0.438795 -0.317167 0.840752 + outer loop + vertex 389.35 187.903 408.665 + vertex 389.372 187.451 408.483 + vertex 391.383 189.323 408.14 + endloop + endfacet + facet normal 0.451486 -0.33318 0.827739 + outer loop + vertex 391.383 189.323 408.14 + vertex 389.372 187.451 408.483 + vertex 391.497 189.069 407.975 + endloop + endfacet + facet normal 0.436986 -0.313759 0.84297 + outer loop + vertex 391.383 189.323 408.14 + vertex 391.449 189.834 408.296 + vertex 389.35 187.903 408.665 + endloop + endfacet + facet normal 0.423658 -0.280363 0.861342 + outer loop + vertex 391.776 190.489 408.348 + vertex 389.699 188.854 408.838 + vertex 391.449 189.834 408.296 + endloop + endfacet + facet normal 0.436474 -0.313106 0.843478 + outer loop + vertex 389.699 188.854 408.838 + vertex 389.35 187.903 408.665 + vertex 391.449 189.834 408.296 + endloop + endfacet + facet normal 0.51471 -0.310455 0.799182 + outer loop + vertex 391.449 189.834 408.296 + vertex 391.383 189.323 408.14 + vertex 392.613 190.622 407.852 + endloop + endfacet + facet normal 0.516681 -0.31281 0.796989 + outer loop + vertex 392.613 190.622 407.852 + vertex 391.383 189.323 408.14 + vertex 392.666 190.331 407.703 + endloop + endfacet + facet normal 0.530463 -0.327391 0.781936 + outer loop + vertex 391.776 190.489 408.348 + vertex 391.449 189.834 408.296 + vertex 392.656 191.032 407.978 + endloop + endfacet + facet normal 0.510904 -0.301543 0.805015 + outer loop + vertex 392.656 191.032 407.978 + vertex 391.449 189.834 408.296 + vertex 392.613 190.622 407.852 + endloop + endfacet + facet normal 0.586606 -0.293985 0.75463 + outer loop + vertex 392.656 191.032 407.978 + vertex 392.613 190.622 407.852 + vertex 393.184 191.322 407.681 + endloop + endfacet + facet normal 0.584298 -0.291426 0.757408 + outer loop + vertex 393.184 191.322 407.681 + vertex 392.613 190.622 407.852 + vertex 393.235 191.073 407.546 + endloop + endfacet + facet normal 0.581241 -0.283602 0.762711 + outer loop + vertex 392.613 190.622 407.852 + vertex 392.666 190.331 407.703 + vertex 393.235 191.073 407.546 + endloop + endfacet + facet normal 0.554718 -0.257195 0.791289 + outer loop + vertex 393.235 191.073 407.546 + vertex 392.666 190.331 407.703 + vertex 393.212 190.817 407.478 + endloop + endfacet + facet normal 0.566719 -0.277933 0.775618 + outer loop + vertex 393.212 190.817 407.478 + vertex 392.666 190.331 407.703 + vertex 392.867 190.301 407.545 + endloop + endfacet + facet normal 0.507578 -0.295918 0.809195 + outer loop + vertex 391.383 189.323 408.14 + vertex 391.497 189.069 407.975 + vertex 392.666 190.331 407.703 + endloop + endfacet + facet normal 0.547415 -0.342669 0.763489 + outer loop + vertex 391.497 189.069 407.975 + vertex 392.867 190.301 407.545 + vertex 392.666 190.331 407.703 + endloop + endfacet + facet normal -0.215009 -0.370461 0.90362 + outer loop + vertex -381.325 184.116 410.053 + vertex -380.554 183.08 409.812 + vertex -374.638 181.973 410.766 + endloop + endfacet + facet normal -0.22778 -0.417423 0.879702 + outer loop + vertex -381.422 182.836 409.472 + vertex -374.737 180.537 410.112 + vertex -380.554 183.08 409.812 + endloop + endfacet + facet normal -0.217503 -0.392267 0.893767 + outer loop + vertex -374.737 180.537 410.112 + vertex -374.638 181.973 410.766 + vertex -380.554 183.08 409.812 + endloop + endfacet + facet normal -0.214298 -0.366273 0.905494 + outer loop + vertex -381.094 185.898 410.881 + vertex -380.386 184.692 410.56 + vertex -374.442 183.835 411.62 + endloop + endfacet + facet normal -0.225536 -0.4099 0.883808 + outer loop + vertex -381.325 184.116 410.053 + vertex -374.638 181.973 410.766 + vertex -380.386 184.692 410.56 + endloop + endfacet + facet normal -0.215769 -0.388338 0.895901 + outer loop + vertex -374.638 181.973 410.766 + vertex -374.442 183.835 411.62 + vertex -380.386 184.692 410.56 + endloop + endfacet + facet normal -0.590604 -0.213172 0.778296 + outer loop + vertex -393.213 191.159 407.615 + vertex -393.242 190.82 407.5 + vertex -392.679 190.639 407.877 + endloop + endfacet + facet normal -0.595221 -0.279721 0.753305 + outer loop + vertex -392.679 190.639 407.877 + vertex -393.242 190.82 407.5 + vertex -392.46 190.019 407.82 + endloop + endfacet + facet normal -0.60596 -0.270943 0.747933 + outer loop + vertex -393.14 191.428 407.771 + vertex -393.213 191.159 407.615 + vertex -392.662 191.015 408.009 + endloop + endfacet + facet normal -0.605546 -0.238071 0.759365 + outer loop + vertex -392.662 191.015 408.009 + vertex -393.213 191.159 407.615 + vertex -392.679 190.639 407.877 + endloop + endfacet + facet normal -0.501074 -0.265391 0.823707 + outer loop + vertex -392.662 191.015 408.009 + vertex -392.679 190.639 407.877 + vertex -391.744 190.274 408.329 + endloop + endfacet + facet normal -0.506465 -0.296548 0.809662 + outer loop + vertex -391.744 190.274 408.329 + vertex -392.679 190.639 407.877 + vertex -391.446 189.678 408.297 + endloop + endfacet + facet normal -0.478799 -0.246716 0.842546 + outer loop + vertex -392.679 190.639 407.877 + vertex -392.46 190.019 407.82 + vertex -391.446 189.678 408.297 + endloop + endfacet + facet normal -0.476136 -0.230196 0.848708 + outer loop + vertex -391.446 189.678 408.297 + vertex -392.46 190.019 407.82 + vertex -391.399 189.305 408.222 + endloop + endfacet + facet normal -0.386738 -0.24096 0.890153 + outer loop + vertex -391.744 190.274 408.329 + vertex -391.446 189.678 408.297 + vertex -389.313 188.86 409.002 + endloop + endfacet + facet normal -0.354602 -0.226616 0.90714 + outer loop + vertex -391.399 189.305 408.222 + vertex -389.258 188.031 408.741 + vertex -391.446 189.678 408.297 + endloop + endfacet + facet normal -0.401127 -0.299624 0.865634 + outer loop + vertex -389.258 188.031 408.741 + vertex -389.313 188.86 409.002 + vertex -391.446 189.678 408.297 + endloop + endfacet + facet normal -0.387414 -0.295587 0.873235 + outer loop + vertex -391.399 189.305 408.222 + vertex -391.024 188.825 408.226 + vertex -389.258 188.031 408.741 + endloop + endfacet + facet normal -0.402934 -0.347276 0.846784 + outer loop + vertex -389.258 188.031 408.741 + vertex -391.024 188.825 408.226 + vertex -388.846 187.215 408.602 + endloop + endfacet + facet normal -0.596936 -0.2446 0.764093 + outer loop + vertex -393.193 191.745 407.832 + vertex -393.14 191.428 407.771 + vertex -392.634 191.332 408.136 + endloop + endfacet + facet normal -0.596707 -0.252244 0.761783 + outer loop + vertex -392.634 191.332 408.136 + vertex -393.14 191.428 407.771 + vertex -392.662 191.015 408.009 + endloop + endfacet + facet normal -0.605078 -0.29075 0.741178 + outer loop + vertex -393.199 192.074 407.955 + vertex -393.193 191.745 407.832 + vertex -392.653 191.67 408.243 + endloop + endfacet + facet normal -0.606935 -0.270591 0.747269 + outer loop + vertex -392.653 191.67 408.243 + vertex -393.193 191.745 407.832 + vertex -392.634 191.332 408.136 + endloop + endfacet + facet normal -0.509922 -0.285202 0.811566 + outer loop + vertex -392.653 191.67 408.243 + vertex -392.634 191.332 408.136 + vertex -391.677 190.974 408.612 + endloop + endfacet + facet normal -0.516377 -0.331719 0.789505 + outer loop + vertex -391.677 190.974 408.612 + vertex -392.634 191.332 408.136 + vertex -391.425 190.468 408.564 + endloop + endfacet + facet normal -0.494283 -0.285169 0.821196 + outer loop + vertex -392.634 191.332 408.136 + vertex -392.662 191.015 408.009 + vertex -391.425 190.468 408.564 + endloop + endfacet + facet normal -0.481478 -0.23183 0.845242 + outer loop + vertex -391.425 190.468 408.564 + vertex -392.662 191.015 408.009 + vertex -391.744 190.274 408.329 + endloop + endfacet + facet normal -0.595321 -0.230449 0.769731 + outer loop + vertex -393.287 192.442 407.998 + vertex -393.199 192.074 407.955 + vertex -392.683 192.023 408.34 + endloop + endfacet + facet normal -0.59282 -0.258968 0.762562 + outer loop + vertex -392.683 192.023 408.34 + vertex -393.199 192.074 407.955 + vertex -392.653 191.67 408.243 + endloop + endfacet + facet normal -0.601424 -0.263255 0.754312 + outer loop + vertex -393.295 192.823 408.124 + vertex -393.287 192.442 407.998 + vertex -392.72 192.403 408.437 + endloop + endfacet + facet normal -0.602842 -0.251543 0.757171 + outer loop + vertex -392.72 192.403 408.437 + vertex -393.287 192.442 407.998 + vertex -392.683 192.023 408.34 + endloop + endfacet + facet normal -0.508126 -0.258751 0.821496 + outer loop + vertex -392.72 192.403 408.437 + vertex -392.683 192.023 408.34 + vertex -391.704 191.709 408.846 + endloop + endfacet + facet normal -0.514218 -0.318128 0.796477 + outer loop + vertex -391.704 191.709 408.846 + vertex -392.683 192.023 408.34 + vertex -391.403 191.18 408.829 + endloop + endfacet + facet normal -0.493332 -0.268507 0.827362 + outer loop + vertex -392.683 192.023 408.34 + vertex -392.653 191.67 408.243 + vertex -391.403 191.18 408.829 + endloop + endfacet + facet normal -0.487511 -0.238757 0.839838 + outer loop + vertex -391.403 191.18 408.829 + vertex -392.653 191.67 408.243 + vertex -391.677 190.974 408.612 + endloop + endfacet + facet normal -0.406541 -0.259581 0.875981 + outer loop + vertex -391.704 191.709 408.846 + vertex -391.403 191.18 408.829 + vertex -389.198 190.427 409.629 + endloop + endfacet + facet normal -0.426314 -0.324726 0.84428 + outer loop + vertex -391.677 190.974 408.612 + vertex -389.241 189.638 409.328 + vertex -391.403 191.18 408.829 + endloop + endfacet + facet normal -0.415182 -0.304952 0.857104 + outer loop + vertex -389.241 189.638 409.328 + vertex -389.198 190.427 409.629 + vertex -391.403 191.18 408.829 + endloop + endfacet + facet normal -0.41163 -0.286813 0.865043 + outer loop + vertex -391.677 190.974 408.612 + vertex -391.425 190.468 408.564 + vertex -389.241 189.638 409.328 + endloop + endfacet + facet normal -0.423869 -0.326346 0.844886 + outer loop + vertex -391.744 190.274 408.329 + vertex -389.313 188.86 409.002 + vertex -391.425 190.468 408.564 + endloop + endfacet + facet normal -0.418343 -0.317418 0.85102 + outer loop + vertex -389.313 188.86 409.002 + vertex -389.241 189.638 409.328 + vertex -391.425 190.468 408.564 + endloop + endfacet + facet normal -0.355423 -0.332726 0.873481 + outer loop + vertex -389.241 189.638 409.328 + vertex -389.313 188.86 409.002 + vertex -385.201 187.165 410.03 + endloop + endfacet + facet normal -0.360113 -0.349202 0.865088 + outer loop + vertex -385.201 187.165 410.03 + vertex -389.313 188.86 409.002 + vertex -385.295 186.315 409.648 + endloop + endfacet + facet normal -0.35285 -0.317204 0.880272 + outer loop + vertex -389.198 190.427 409.629 + vertex -389.241 189.638 409.328 + vertex -385.093 188.026 410.41 + endloop + endfacet + facet normal -0.35855 -0.33887 0.869833 + outer loop + vertex -385.093 188.026 410.41 + vertex -389.241 189.638 409.328 + vertex -385.201 187.165 410.03 + endloop + endfacet + facet normal -0.293404 -0.35489 0.887675 + outer loop + vertex -385.093 188.026 410.41 + vertex -385.201 187.165 410.03 + vertex -381.094 185.898 410.881 + endloop + endfacet + facet normal -0.304069 -0.40719 0.861242 + outer loop + vertex -381.094 185.898 410.881 + vertex -385.201 187.165 410.03 + vertex -380.386 184.692 410.56 + endloop + endfacet + facet normal -0.285846 -0.366536 0.885406 + outer loop + vertex -385.201 187.165 410.03 + vertex -385.295 186.315 409.648 + vertex -380.386 184.692 410.56 + endloop + endfacet + facet normal -0.278663 -0.33699 0.899325 + outer loop + vertex -380.386 184.692 410.56 + vertex -385.295 186.315 409.648 + vertex -381.325 184.116 410.053 + endloop + endfacet + facet normal -0.335244 -0.319795 0.886195 + outer loop + vertex -389.258 188.031 408.741 + vertex -388.846 187.215 408.602 + vertex -385.311 185.511 409.325 + endloop + endfacet + facet normal -0.351668 -0.363936 0.862485 + outer loop + vertex -385.311 185.511 409.325 + vertex -388.846 187.215 408.602 + vertex -385.288 184.917 409.083 + endloop + endfacet + facet normal -0.335481 -0.303513 0.891814 + outer loop + vertex -389.313 188.86 409.002 + vertex -389.258 188.031 408.741 + vertex -385.295 186.315 409.648 + endloop + endfacet + facet normal -0.348288 -0.343474 0.872193 + outer loop + vertex -385.295 186.315 409.648 + vertex -389.258 188.031 408.741 + vertex -385.311 185.511 409.325 + endloop + endfacet + facet normal -0.286289 -0.352283 0.891031 + outer loop + vertex -385.295 186.315 409.648 + vertex -385.311 185.511 409.325 + vertex -381.325 184.116 410.053 + endloop + endfacet + facet normal -0.304768 -0.425363 0.852163 + outer loop + vertex -381.325 184.116 410.053 + vertex -385.311 185.511 409.325 + vertex -380.554 183.08 409.812 + endloop + endfacet + facet normal -0.280192 -0.370573 0.885533 + outer loop + vertex -385.311 185.511 409.325 + vertex -385.288 184.917 409.083 + vertex -380.554 183.08 409.812 + endloop + endfacet + facet normal -0.265429 -0.323501 0.908237 + outer loop + vertex -380.554 183.08 409.812 + vertex -385.288 184.917 409.083 + vertex -381.422 182.836 409.472 + endloop + endfacet + facet normal 0.251195 0.263389 -0.931411 + outer loop + vertex -393.449 190.901 407.256 + vertex -393.417 191.248 407.363 + vertex -393.402 190.998 407.296 + endloop + endfacet + facet normal -0.524105 0.200162 -0.827798 + outer loop + vertex -393.451 191.704 407.494 + vertex -393.443 191.702 407.489 + vertex -393.417 191.248 407.363 + endloop + endfacet + facet normal 0.981278 0.10223 -0.163227 + outer loop + vertex -393.443 191.702 407.489 + vertex -393.402 190.998 407.296 + vertex -393.417 191.248 407.363 + endloop + endfacet + facet normal -0.551872 0.0951899 -0.828478 + outer loop + vertex -393.451 191.704 407.494 + vertex -393.54 192.313 407.624 + vertex -393.443 191.702 407.489 + endloop + endfacet + facet normal -0.00785278 0.192209 -0.981323 + outer loop + vertex -393.651 193.04 407.767 + vertex -393.597 192.884 407.736 + vertex -393.54 192.313 407.624 + endloop + endfacet + facet normal -0.36958 0.143791 -0.918006 + outer loop + vertex -393.597 192.884 407.736 + vertex -393.443 191.702 407.489 + vertex -393.54 192.313 407.624 + endloop + endfacet + facet normal -0.857387 -0.223925 0.463406 + outer loop + vertex -393.54 192.313 407.624 + vertex -393.451 191.704 407.494 + vertex -393.446 192.09 407.69 + endloop + endfacet + facet normal -0.866489 -0.216841 0.44964 + outer loop + vertex -393.446 192.09 407.69 + vertex -393.451 191.704 407.494 + vertex -393.377 191.492 407.534 + endloop + endfacet + facet normal -0.857468 -0.22222 0.464077 + outer loop + vertex -393.651 193.04 407.767 + vertex -393.54 192.313 407.624 + vertex -393.552 192.811 407.841 + endloop + endfacet + facet normal -0.856457 -0.222874 0.465627 + outer loop + vertex -393.552 192.811 407.841 + vertex -393.54 192.313 407.624 + vertex -393.446 192.09 407.69 + endloop + endfacet + facet normal -0.717233 -0.24599 0.651971 + outer loop + vertex -393.199 192.074 407.955 + vertex -393.287 192.442 407.998 + vertex -393.446 192.09 407.69 + endloop + endfacet + facet normal -0.715854 -0.233854 0.657924 + outer loop + vertex -393.295 192.823 408.124 + vertex -393.552 192.811 407.841 + vertex -393.287 192.442 407.998 + endloop + endfacet + facet normal -0.721368 -0.241565 0.649057 + outer loop + vertex -393.552 192.811 407.841 + vertex -393.446 192.09 407.69 + vertex -393.287 192.442 407.998 + endloop + endfacet + facet normal -0.718038 -0.24323 0.65212 + outer loop + vertex -393.14 191.428 407.771 + vertex -393.193 191.745 407.832 + vertex -393.377 191.492 407.534 + endloop + endfacet + facet normal -0.715239 -0.258416 0.649349 + outer loop + vertex -393.199 192.074 407.955 + vertex -393.446 192.09 407.69 + vertex -393.193 191.745 407.832 + endloop + endfacet + facet normal -0.711209 -0.252749 0.655972 + outer loop + vertex -393.446 192.09 407.69 + vertex -393.377 191.492 407.534 + vertex -393.193 191.745 407.832 + endloop + endfacet + facet normal -0.943811 -0.0145736 0.330163 + outer loop + vertex -393.417 191.248 407.363 + vertex -393.449 190.901 407.256 + vertex -393.413 191.077 407.367 + endloop + endfacet + facet normal -0.902494 -0.0815505 0.422911 + outer loop + vertex -393.413 191.077 407.367 + vertex -393.449 190.901 407.256 + vertex -393.406 190.759 407.319 + endloop + endfacet + facet normal -0.849235 -0.203837 0.487083 + outer loop + vertex -393.451 191.704 407.494 + vertex -393.417 191.248 407.363 + vertex -393.377 191.492 407.534 + endloop + endfacet + facet normal -0.968357 -0.0171339 0.24898 + outer loop + vertex -393.377 191.492 407.534 + vertex -393.417 191.248 407.363 + vertex -393.413 191.077 407.367 + endloop + endfacet + facet normal -0.742926 -0.156562 0.650807 + outer loop + vertex -393.242 190.82 407.5 + vertex -393.213 191.159 407.615 + vertex -393.413 191.077 407.367 + endloop + endfacet + facet normal -0.719478 -0.193365 0.667054 + outer loop + vertex -393.14 191.428 407.771 + vertex -393.377 191.492 407.534 + vertex -393.213 191.159 407.615 + endloop + endfacet + facet normal -0.729006 -0.201173 0.654278 + outer loop + vertex -393.377 191.492 407.534 + vertex -393.413 191.077 407.367 + vertex -393.213 191.159 407.615 + endloop + endfacet + facet normal -0.714485 -0.117565 0.689702 + outer loop + vertex -393.413 191.077 407.367 + vertex -393.406 190.759 407.319 + vertex -393.242 190.82 407.5 + endloop + endfacet + facet normal -0.693061 -0.191495 0.694979 + outer loop + vertex -393.242 190.82 407.5 + vertex -393.406 190.759 407.319 + vertex -393.211 190.565 407.46 + endloop + endfacet + facet normal 0.554597 -0.254837 0.792136 + outer loop + vertex 392.781 189.884 407.511 + vertex 392.899 189.935 407.445 + vertex 393.353 190.553 407.326 + endloop + endfacet + facet normal 0.685783 -0.469593 0.556043 + outer loop + vertex 392.76 189.728 407.441 + vertex 393.303 190.362 407.308 + vertex 392.899 189.935 407.445 + endloop + endfacet + facet normal 0.511142 -0.215172 0.832127 + outer loop + vertex 393.303 190.362 407.308 + vertex 393.353 190.553 407.326 + vertex 392.899 189.935 407.445 + endloop + endfacet + facet normal 0.496262 -0.171659 0.851033 + outer loop + vertex 392.867 190.301 407.545 + vertex 392.866 190.086 407.503 + vertex 393.396 190.821 407.342 + endloop + endfacet + facet normal 0.579128 -0.14091 0.802967 + outer loop + vertex 393.494 190.898 407.285 + vertex 393.396 190.821 407.342 + vertex 393.353 190.553 407.326 + endloop + endfacet + facet normal 0.470319 -0.161991 0.867502 + outer loop + vertex 392.781 189.884 407.511 + vertex 393.353 190.553 407.326 + vertex 392.866 190.086 407.503 + endloop + endfacet + facet normal 0.441429 -0.123809 0.888713 + outer loop + vertex 393.396 190.821 407.342 + vertex 392.866 190.086 407.503 + vertex 393.353 190.553 407.326 + endloop + endfacet + facet normal -0.157629 0.0776797 -0.984438 + outer loop + vertex 382.516 182.877 409.201 + vertex 382.337 182.831 409.226 + vertex 386.377 185.026 408.753 + endloop + endfacet + facet normal 0.479663 -0.810341 0.336557 + outer loop + vertex 386.377 185.026 408.753 + vertex 382.337 182.831 409.226 + vertex 386.224 184.932 408.743 + endloop + endfacet + facet normal -0.031524 -0.134971 -0.990348 + outer loop + vertex 382.688 182.928 409.189 + vertex 382.516 182.877 409.201 + vertex 386.505 185.107 408.77 + endloop + endfacet + facet normal 0.493117 -0.835443 0.242633 + outer loop + vertex 386.505 185.107 408.77 + vertex 382.516 182.877 409.201 + vertex 386.377 185.026 408.753 + endloop + endfacet + facet normal 0.54237 -0.827179 -0.146999 + outer loop + vertex 386.505 185.107 408.77 + vertex 386.377 185.026 408.753 + vertex 389.519 187.17 408.282 + endloop + endfacet + facet normal 0.51693 -0.630409 0.579109 + outer loop + vertex 389.519 187.17 408.282 + vertex 386.377 185.026 408.753 + vertex 389.454 187.084 408.246 + endloop + endfacet + facet normal 0.524156 -0.830312 -0.189322 + outer loop + vertex 386.377 185.026 408.753 + vertex 386.224 184.932 408.743 + vertex 389.454 187.084 408.246 + endloop + endfacet + facet normal 0.519311 -0.651608 0.552922 + outer loop + vertex 389.454 187.084 408.246 + vertex 386.224 184.932 408.743 + vertex 389.361 186.981 408.213 + endloop + endfacet + facet normal 0.386903 -0.526598 0.756968 + outer loop + vertex 382.755 183.054 409.243 + vertex 382.688 182.928 409.189 + vertex 386.502 185.223 408.836 + endloop + endfacet + facet normal 0.34886 -0.453677 0.820045 + outer loop + vertex 386.502 185.223 408.836 + vertex 382.688 182.928 409.189 + vertex 386.505 185.107 408.77 + endloop + endfacet + facet normal 0.319655 -0.388105 0.864405 + outer loop + vertex 382.722 183.379 409.401 + vertex 382.755 183.054 409.243 + vertex 386.432 185.498 408.98 + endloop + endfacet + facet normal 0.312761 -0.37693 0.87184 + outer loop + vertex 386.432 185.498 408.98 + vertex 382.755 183.054 409.243 + vertex 386.502 185.223 408.836 + endloop + endfacet + facet normal 0.378495 -0.351917 0.856093 + outer loop + vertex 386.432 185.498 408.98 + vertex 386.502 185.223 408.836 + vertex 389.372 187.451 408.483 + endloop + endfacet + facet normal 0.389039 -0.367279 0.84484 + outer loop + vertex 389.372 187.451 408.483 + vertex 386.502 185.223 408.836 + vertex 389.472 187.254 408.352 + endloop + endfacet + facet normal 0.427321 -0.435811 0.792128 + outer loop + vertex 386.502 185.223 408.836 + vertex 386.505 185.107 408.77 + vertex 389.472 187.254 408.352 + endloop + endfacet + facet normal 0.421532 -0.426197 0.800417 + outer loop + vertex 389.472 187.254 408.352 + vertex 386.505 185.107 408.77 + vertex 389.519 187.17 408.282 + endloop + endfacet + facet normal 0.482691 -0.381999 0.78809 + outer loop + vertex 389.472 187.254 408.352 + vertex 389.519 187.17 408.282 + vertex 391.603 188.947 407.867 + endloop + endfacet + facet normal 0.424732 -0.298462 0.854707 + outer loop + vertex 391.603 188.947 407.867 + vertex 389.519 187.17 408.282 + vertex 391.637 188.857 407.818 + endloop + endfacet + facet normal 0.44845 -0.32803 0.831438 + outer loop + vertex 389.372 187.451 408.483 + vertex 389.472 187.254 408.352 + vertex 391.497 189.069 407.975 + endloop + endfacet + facet normal 0.455333 -0.337262 0.82397 + outer loop + vertex 391.497 189.069 407.975 + vertex 389.472 187.254 408.352 + vertex 391.603 188.947 407.867 + endloop + endfacet + facet normal 0.508468 -0.28184 0.81365 + outer loop + vertex 391.497 189.069 407.975 + vertex 391.603 188.947 407.867 + vertex 392.867 190.301 407.545 + endloop + endfacet + facet normal 0.417869 -0.178952 0.890708 + outer loop + vertex 392.867 190.301 407.545 + vertex 391.603 188.947 407.867 + vertex 392.866 190.086 407.503 + endloop + endfacet + facet normal 0.480991 -0.266598 0.835209 + outer loop + vertex 391.603 188.947 407.867 + vertex 391.637 188.857 407.818 + vertex 392.866 190.086 407.503 + endloop + endfacet + facet normal 0.346785 -0.107766 0.931733 + outer loop + vertex 392.866 190.086 407.503 + vertex 391.637 188.857 407.818 + vertex 392.781 189.884 407.511 + endloop + endfacet + facet normal 0.619095 -0.686708 0.38099 + outer loop + vertex 389.454 187.084 408.246 + vertex 389.361 186.981 408.213 + vertex 391.633 188.789 407.778 + endloop + endfacet + facet normal 0.564317 -0.564617 0.602291 + outer loop + vertex 391.633 188.789 407.778 + vertex 389.361 186.981 408.213 + vertex 391.575 188.688 407.738 + endloop + endfacet + facet normal 0.615239 -0.649899 0.44622 + outer loop + vertex 389.519 187.17 408.282 + vertex 389.454 187.084 408.246 + vertex 391.637 188.857 407.818 + endloop + endfacet + facet normal 0.513827 -0.457555 0.725689 + outer loop + vertex 391.637 188.857 407.818 + vertex 389.454 187.084 408.246 + vertex 391.633 188.789 407.778 + endloop + endfacet + facet normal 0.578796 -0.43926 0.687055 + outer loop + vertex 391.637 188.857 407.818 + vertex 391.633 188.789 407.778 + vertex 392.781 189.884 407.511 + endloop + endfacet + facet normal 0.577004 -0.436603 0.690249 + outer loop + vertex 392.781 189.884 407.511 + vertex 391.633 188.789 407.778 + vertex 392.899 189.935 407.445 + endloop + endfacet + facet normal 0.650144 -0.57278 0.499235 + outer loop + vertex 391.633 188.789 407.778 + vertex 391.575 188.688 407.738 + vertex 392.899 189.935 407.445 + endloop + endfacet + facet normal 0.508093 -0.355105 0.784692 + outer loop + vertex 392.899 189.935 407.445 + vertex 391.575 188.688 407.738 + vertex 392.76 189.728 407.441 + endloop + endfacet + facet normal -0.232681 -0.433704 0.870494 + outer loop + vertex -381.472 182.398 409.259 + vertex -380.675 182.02 409.284 + vertex -374.78 179.848 409.777 + endloop + endfacet + facet normal -0.223039 -0.690965 -0.68762 + outer loop + vertex -381.551 182.393 409.193 + vertex -374.813 179.736 409.677 + vertex -380.675 182.02 409.284 + endloop + endfacet + facet normal -0.281792 -0.59352 0.753875 + outer loop + vertex -374.813 179.736 409.677 + vertex -374.78 179.848 409.777 + vertex -380.675 182.02 409.284 + endloop + endfacet + facet normal -0.209777 -0.356531 0.910428 + outer loop + vertex -381.422 182.836 409.472 + vertex -380.61 182.21 409.414 + vertex -374.737 180.537 410.112 + endloop + endfacet + facet normal -0.25851 -0.511888 0.819234 + outer loop + vertex -381.472 182.398 409.259 + vertex -374.78 179.848 409.777 + vertex -380.61 182.21 409.414 + endloop + endfacet + facet normal -0.222893 -0.414238 0.882454 + outer loop + vertex -374.78 179.848 409.777 + vertex -374.737 180.537 410.112 + vertex -380.61 182.21 409.414 + endloop + endfacet + facet normal -0.466727 -0.414595 0.781202 + outer loop + vertex -391.397 188.698 407.891 + vertex -391.478 188.696 407.841 + vertex -388.932 186.794 408.353 + endloop + endfacet + facet normal -0.474927 -0.429022 0.768365 + outer loop + vertex -388.932 186.794 408.353 + vertex -391.478 188.696 407.841 + vertex -388.974 186.782 408.32 + endloop + endfacet + facet normal -0.451806 -0.390341 0.802188 + outer loop + vertex -391.478 188.696 407.841 + vertex -391.521 188.699 407.818 + vertex -388.974 186.782 408.32 + endloop + endfacet + facet normal -0.434684 -0.3617 0.824756 + outer loop + vertex -388.974 186.782 408.32 + vertex -391.521 188.699 407.818 + vertex -389.02 186.765 408.288 + endloop + endfacet + facet normal -0.488727 -0.492979 0.719804 + outer loop + vertex -391.024 188.825 408.226 + vertex -391.292 188.787 408.018 + vertex -388.846 187.215 408.602 + endloop + endfacet + facet normal -0.441595 -0.386287 0.8098 + outer loop + vertex -388.846 187.215 408.602 + vertex -391.292 188.787 408.018 + vertex -388.869 186.9 408.439 + endloop + endfacet + facet normal -0.492925 -0.469369 0.73261 + outer loop + vertex -391.292 188.787 408.018 + vertex -391.397 188.698 407.891 + vertex -388.869 186.9 408.439 + endloop + endfacet + facet normal -0.450957 -0.388785 0.80342 + outer loop + vertex -388.869 186.9 408.439 + vertex -391.397 188.698 407.891 + vertex -388.932 186.794 408.353 + endloop + endfacet + facet normal -0.392283 -0.431541 0.812334 + outer loop + vertex -388.869 186.9 408.439 + vertex -388.932 186.794 408.353 + vertex -385.316 184.593 408.929 + endloop + endfacet + facet normal -0.378415 -0.403312 0.833151 + outer loop + vertex -385.316 184.593 408.929 + vertex -388.932 186.794 408.353 + vertex -385.344 184.476 408.861 + endloop + endfacet + facet normal -0.37386 -0.404088 0.83483 + outer loop + vertex -388.846 187.215 408.602 + vertex -388.869 186.9 408.439 + vertex -385.288 184.917 409.083 + endloop + endfacet + facet normal -0.360699 -0.373952 0.854434 + outer loop + vertex -385.288 184.917 409.083 + vertex -388.869 186.9 408.439 + vertex -385.316 184.593 408.929 + endloop + endfacet + facet normal -0.296614 -0.388101 0.872581 + outer loop + vertex -385.288 184.917 409.083 + vertex -385.316 184.593 408.929 + vertex -381.422 182.836 409.472 + endloop + endfacet + facet normal -0.342474 -0.516955 0.784518 + outer loop + vertex -381.422 182.836 409.472 + vertex -385.316 184.593 408.929 + vertex -380.61 182.21 409.414 + endloop + endfacet + facet normal -0.305283 -0.430289 0.849502 + outer loop + vertex -385.316 184.593 408.929 + vertex -385.344 184.476 408.861 + vertex -380.61 182.21 409.414 + endloop + endfacet + facet normal -0.219245 -0.226285 0.949066 + outer loop + vertex -380.61 182.21 409.414 + vertex -385.344 184.476 408.861 + vertex -381.472 182.398 409.259 + endloop + endfacet + facet normal -0.397056 -0.4352 0.808052 + outer loop + vertex -388.974 186.782 408.32 + vertex -389.02 186.765 408.288 + vertex -385.388 184.442 408.822 + endloop + endfacet + facet normal -0.441324 -0.522421 0.729595 + outer loop + vertex -385.388 184.442 408.822 + vertex -389.02 186.765 408.288 + vertex -385.432 184.429 408.786 + endloop + endfacet + facet normal -0.432908 -0.50689 0.745421 + outer loop + vertex -388.932 186.794 408.353 + vertex -388.974 186.782 408.32 + vertex -385.344 184.476 408.861 + endloop + endfacet + facet normal -0.389609 -0.421462 0.818886 + outer loop + vertex -385.344 184.476 408.861 + vertex -388.974 186.782 408.32 + vertex -385.388 184.442 408.822 + endloop + endfacet + facet normal -0.339415 -0.476708 0.810893 + outer loop + vertex -385.344 184.476 408.861 + vertex -385.388 184.442 408.822 + vertex -381.472 182.398 409.259 + endloop + endfacet + facet normal -0.368619 -0.805742 -0.463574 + outer loop + vertex -381.472 182.398 409.259 + vertex -385.388 184.442 408.822 + vertex -380.675 182.02 409.284 + endloop + endfacet + facet normal -0.382882 -0.613177 0.690953 + outer loop + vertex -385.388 184.442 408.822 + vertex -385.432 184.429 408.786 + vertex -380.675 182.02 409.284 + endloop + endfacet + facet normal -0.0997141 0.00884787 0.994977 + outer loop + vertex -380.675 182.02 409.284 + vertex -385.432 184.429 408.786 + vertex -381.551 182.393 409.193 + endloop + endfacet + facet normal -0.342509 0.141269 0.928833 + outer loop + vertex -393.457 190.786 407.223 + vertex -393.53 190.734 407.205 + vertex -393.4 190.575 407.277 + endloop + endfacet + facet normal -0.360986 0.124105 0.924277 + outer loop + vertex -393.4 190.575 407.277 + vertex -393.53 190.734 407.205 + vertex -393.434 190.496 407.274 + endloop + endfacet + facet normal 0.295989 0.238875 -0.92484 + outer loop + vertex -393.402 190.998 407.296 + vertex -393.457 190.786 407.223 + vertex -393.449 190.901 407.256 + endloop + endfacet + facet normal -0.837908 -0.0916318 0.538065 + outer loop + vertex -393.449 190.901 407.256 + vertex -393.457 190.786 407.223 + vertex -393.4 190.575 407.277 + endloop + endfacet + facet normal -0.776301 -0.521489 0.354128 + outer loop + vertex -393.211 190.565 407.46 + vertex -393.406 190.759 407.319 + vertex -392.842 190.066 407.536 + endloop + endfacet + facet normal -0.61175 -0.297726 0.732885 + outer loop + vertex -392.735 189.82 407.525 + vertex -392.842 190.066 407.536 + vertex -393.4 190.575 407.277 + endloop + endfacet + facet normal -0.925249 -0.115819 0.361249 + outer loop + vertex -393.449 190.901 407.256 + vertex -393.4 190.575 407.277 + vertex -393.406 190.759 407.319 + endloop + endfacet + facet normal -0.560015 -0.205556 0.802577 + outer loop + vertex -392.842 190.066 407.536 + vertex -393.406 190.759 407.319 + vertex -393.4 190.575 407.277 + endloop + endfacet + facet normal -0.379965 -0.0499348 0.923652 + outer loop + vertex -392.815 189.803 407.491 + vertex -392.903 189.941 407.462 + vertex -393.434 190.496 407.274 + endloop + endfacet + facet normal -0.350151 -2.59657e-05 0.936693 + outer loop + vertex -392.735 189.82 407.525 + vertex -393.4 190.575 407.277 + vertex -392.903 189.941 407.462 + endloop + endfacet + facet normal -0.259646 0.0785565 0.962504 + outer loop + vertex -393.4 190.575 407.277 + vertex -393.434 190.496 407.274 + vertex -392.903 189.941 407.462 + endloop + endfacet + facet normal 0.705107 -0.658794 -0.262326 + outer loop + vertex 392.76 189.728 407.441 + vertex 392.819 189.802 407.413 + vertex 393.303 190.362 407.308 + endloop + endfacet + facet normal -0.505508 0.262507 -0.821919 + outer loop + vertex 392.707 189.772 407.472 + vertex 393.184 190.263 407.336 + vertex 392.819 189.802 407.413 + endloop + endfacet + facet normal -0.278347 0.0597172 -0.958622 + outer loop + vertex 393.184 190.263 407.336 + vertex 393.303 190.362 407.308 + vertex 392.819 189.802 407.413 + endloop + endfacet + facet normal -0.42522 0.593913 -0.682976 + outer loop + vertex 382.774 183.093 409.233 + vertex 383.188 183.438 409.275 + vertex 386.374 185.12 408.755 + endloop + endfacet + facet normal -0.377896 0.468478 -0.798575 + outer loop + vertex 386.374 185.12 408.755 + vertex 383.188 183.438 409.275 + vertex 386.929 185.644 408.799 + endloop + endfacet + facet normal -0.497186 0.581834 -0.643642 + outer loop + vertex 386.374 185.12 408.755 + vertex 386.929 185.644 408.799 + vertex 389.479 187.174 408.212 + endloop + endfacet + facet normal -0.446057 0.445885 -0.776029 + outer loop + vertex 389.479 187.174 408.212 + vertex 386.929 185.644 408.799 + vertex 389.969 187.744 408.258 + endloop + endfacet + facet normal -0.482651 0.820951 -0.305102 + outer loop + vertex 382.391 182.866 409.228 + vertex 382.774 183.093 409.233 + vertex 386.187 184.914 408.733 + endloop + endfacet + facet normal -0.334644 0.392015 -0.856935 + outer loop + vertex 386.187 184.914 408.733 + vertex 382.774 183.093 409.233 + vertex 386.374 185.12 408.755 + endloop + endfacet + facet normal -0.462879 0.746892 -0.477384 + outer loop + vertex 382.337 182.831 409.226 + vertex 382.391 182.866 409.228 + vertex 386.224 184.932 408.743 + endloop + endfacet + facet normal 0.459231 -0.880196 -0.119841 + outer loop + vertex 386.224 184.932 408.743 + vertex 382.391 182.866 409.228 + vertex 386.187 184.914 408.733 + endloop + endfacet + facet normal 0.482135 -0.818573 -0.312224 + outer loop + vertex 386.224 184.932 408.743 + vertex 386.187 184.914 408.733 + vertex 389.361 186.981 408.213 + endloop + endfacet + facet normal 0.549779 -0.834478 0.0372755 + outer loop + vertex 389.361 186.981 408.213 + vertex 386.187 184.914 408.733 + vertex 389.319 186.953 408.191 + endloop + endfacet + facet normal -0.44352 0.480174 -0.756785 + outer loop + vertex 386.187 184.914 408.733 + vertex 386.374 185.12 408.755 + vertex 389.319 186.953 408.191 + endloop + endfacet + facet normal -0.386803 0.360814 -0.848644 + outer loop + vertex 389.319 186.953 408.191 + vertex 386.374 185.12 408.755 + vertex 389.479 187.174 408.212 + endloop + endfacet + facet normal -0.487459 0.425712 -0.762334 + outer loop + vertex 389.319 186.953 408.191 + vertex 389.479 187.174 408.212 + vertex 391.551 188.658 407.717 + endloop + endfacet + facet normal -0.441592 0.33884 -0.830773 + outer loop + vertex 391.551 188.658 407.717 + vertex 389.479 187.174 408.212 + vertex 391.65 188.834 407.736 + endloop + endfacet + facet normal 0.594494 -0.798274 -0.096614 + outer loop + vertex 389.361 186.981 408.213 + vertex 389.319 186.953 408.191 + vertex 391.575 188.688 407.738 + endloop + endfacet + facet normal 0.618215 -0.723725 0.306648 + outer loop + vertex 391.575 188.688 407.738 + vertex 389.319 186.953 408.191 + vertex 391.551 188.658 407.717 + endloop + endfacet + facet normal 0.674064 -0.705459 0.219008 + outer loop + vertex 391.575 188.688 407.738 + vertex 391.551 188.658 407.717 + vertex 392.76 189.728 407.441 + endloop + endfacet + facet normal 0.290951 -0.533146 -0.79442 + outer loop + vertex 392.76 189.728 407.441 + vertex 391.551 188.658 407.717 + vertex 392.819 189.802 407.413 + endloop + endfacet + facet normal -0.523598 0.377843 -0.763597 + outer loop + vertex 391.551 188.658 407.717 + vertex 391.65 188.834 407.736 + vertex 392.819 189.802 407.413 + endloop + endfacet + facet normal -0.510009 0.354787 -0.783592 + outer loop + vertex 392.819 189.802 407.413 + vertex 391.65 188.834 407.736 + vertex 392.707 189.772 407.472 + endloop + endfacet + facet normal -0.542099 0.519103 -0.660803 + outer loop + vertex 389.479 187.174 408.212 + vertex 389.969 187.744 408.258 + vertex 391.65 188.834 407.736 + endloop + endfacet + facet normal -0.491377 0.382538 -0.782441 + outer loop + vertex 391.65 188.834 407.736 + vertex 389.969 187.744 408.258 + vertex 391.936 189.216 407.743 + endloop + endfacet + facet normal -0.559482 0.431884 -0.707429 + outer loop + vertex 391.65 188.834 407.736 + vertex 391.936 189.216 407.743 + vertex 392.707 189.772 407.472 + endloop + endfacet + facet normal -0.489077 0.275604 -0.827554 + outer loop + vertex 392.707 189.772 407.472 + vertex 391.936 189.216 407.743 + vertex 392.732 189.941 407.514 + endloop + endfacet + facet normal 0.247972 0.4749 -0.844381 + outer loop + vertex -381.551 182.393 409.193 + vertex -380.628 182.098 409.298 + vertex -374.813 179.736 409.677 + endloop + endfacet + facet normal 0.306838 0.631874 -0.711748 + outer loop + vertex -381.335 182.519 409.367 + vertex -374.452 179.494 409.648 + vertex -380.628 182.098 409.298 + endloop + endfacet + facet normal -0.244533 -0.465432 0.850633 + outer loop + vertex -374.452 179.494 409.648 + vertex -374.813 179.736 409.677 + vertex -380.628 182.098 409.298 + endloop + endfacet + facet normal 0.51958 0.53486 -0.666304 + outer loop + vertex -391.349 188.498 407.854 + vertex -390.864 188.249 408.031 + vertex -388.758 186.615 408.362 + endloop + endfacet + facet normal 0.470361 0.453 -0.757332 + outer loop + vertex -388.758 186.615 408.362 + vertex -390.864 188.249 408.031 + vertex -388.51 186.699 408.566 + endloop + endfacet + facet normal -0.353676 -0.237534 0.904705 + outer loop + vertex -391.521 188.699 407.818 + vertex -391.505 188.631 407.807 + vertex -389.02 186.765 408.288 + endloop + endfacet + facet normal -0.447696 -0.388379 0.805438 + outer loop + vertex -389.02 186.765 408.288 + vertex -391.505 188.631 407.807 + vertex -388.976 186.689 408.276 + endloop + endfacet + facet normal 0.465073 0.727568 0.504332 + outer loop + vertex -391.505 188.631 407.807 + vertex -391.349 188.498 407.854 + vertex -388.976 186.689 408.276 + endloop + endfacet + facet normal 0.451071 0.405945 -0.794823 + outer loop + vertex -388.976 186.689 408.276 + vertex -391.349 188.498 407.854 + vertex -388.758 186.615 408.362 + endloop + endfacet + facet normal 0.461477 0.580609 -0.67077 + outer loop + vertex -388.976 186.689 408.276 + vertex -388.758 186.615 408.362 + vertex -385.377 184.427 408.794 + endloop + endfacet + facet normal 0.389888 0.442982 -0.807313 + outer loop + vertex -385.377 184.427 408.794 + vertex -388.758 186.615 408.362 + vertex -385.175 184.481 408.921 + endloop + endfacet + facet normal -0.342078 -0.338716 0.876501 + outer loop + vertex -389.02 186.765 408.288 + vertex -388.976 186.689 408.276 + vertex -385.432 184.429 408.786 + endloop + endfacet + facet normal 0.154766 0.0199113 -0.98775 + outer loop + vertex -385.432 184.429 408.786 + vertex -388.976 186.689 408.276 + vertex -385.377 184.427 408.794 + endloop + endfacet + facet normal 0.156061 0.101065 -0.982563 + outer loop + vertex -385.432 184.429 408.786 + vertex -385.377 184.427 408.794 + vertex -381.551 182.393 409.193 + endloop + endfacet + facet normal 0.127805 0.046317 -0.990717 + outer loop + vertex -381.551 182.393 409.193 + vertex -385.377 184.427 408.794 + vertex -380.628 182.098 409.298 + endloop + endfacet + facet normal 0.343788 0.533976 -0.77245 + outer loop + vertex -385.377 184.427 408.794 + vertex -385.175 184.481 408.921 + vertex -380.628 182.098 409.298 + endloop + endfacet + facet normal 0.459645 0.825311 -0.328006 + outer loop + vertex -380.628 182.098 409.298 + vertex -385.175 184.481 408.921 + vertex -381.335 182.519 409.367 + endloop + endfacet + facet normal 0.427805 0.525509 -0.735407 + outer loop + vertex -388.758 186.615 408.362 + vertex -388.51 186.699 408.566 + vertex -385.175 184.481 408.921 + endloop + endfacet + facet normal 0.483099 0.628852 -0.609229 + outer loop + vertex -385.175 184.481 408.921 + vertex -388.51 186.699 408.566 + vertex -384.796 184.418 409.157 + endloop + endfacet + facet normal 0.438127 0.742636 -0.506495 + outer loop + vertex -385.175 184.481 408.921 + vertex -384.796 184.418 409.157 + vertex -381.335 182.519 409.367 + endloop + endfacet + facet normal 0.433797 0.829789 0.3511 + outer loop + vertex -381.335 182.519 409.367 + vertex -384.796 184.418 409.157 + vertex -382.313 183.012 409.413 + endloop + endfacet + facet normal 0.157624 0.33349 0.929483 + outer loop + vertex -393.53 190.734 407.205 + vertex -393.536 190.7 407.218 + vertex -393.434 190.496 407.274 + endloop + endfacet + facet normal 0.29569 -0.114357 -0.948414 + outer loop + vertex -393.434 190.496 407.274 + vertex -393.536 190.7 407.218 + vertex -393.335 190.43 407.313 + endloop + endfacet + facet normal 0.351214 0.0281142 -0.935873 + outer loop + vertex -392.49 189.623 407.606 + vertex -392.852 189.841 407.476 + vertex -393.335 190.43 407.313 + endloop + endfacet + facet normal -0.656824 -0.383118 0.649463 + outer loop + vertex -392.815 189.803 407.491 + vertex -393.434 190.496 407.274 + vertex -392.852 189.841 407.476 + endloop + endfacet + facet normal 0.412966 0.0868453 -0.906596 + outer loop + vertex -393.434 190.496 407.274 + vertex -393.335 190.43 407.313 + vertex -392.852 189.841 407.476 + endloop + endfacet + facet normal 0.249724 -0.488226 0.836226 + outer loop + vertex 374.142 177.503 408.859 + vertex 379.603 181.16 409.363 + vertex 377.225 180.248 409.541 + endloop + endfacet + facet normal 0.14352 -0.444328 0.884293 + outer loop + vertex 355.857 171.812 409.255 + vertex 365.276 174.667 409.161 + vertex 360.682 174.892 410.019 + endloop + endfacet + facet normal 0.112574 -0.442395 0.889727 + outer loop + vertex 344.24 169.802 409.725 + vertex 355.857 171.812 409.255 + vertex 352.663 172.84 410.17 + endloop + endfacet + facet normal 0.0899319 -0.403797 0.910418 + outer loop + vertex 335.397 167.706 409.669 + vertex 344.24 169.802 409.725 + vertex 335.317 169.217 410.347 + endloop + endfacet + facet normal 0.0775998 -0.404763 0.911123 + outer loop + vertex 327.643 165.536 409.366 + vertex 335.397 167.706 409.669 + vertex 335.317 169.217 410.347 + endloop + endfacet + facet normal 0.0745325 -0.419337 0.904766 + outer loop + vertex 306.802 161.852 409.404 + vertex 314.126 161.937 408.841 + vertex 318.239 165.585 410.192 + endloop + endfacet + facet normal -0.0743268 -0.417195 0.905773 + outer loop + vertex -312.883 161.342 408.673 + vertex -305.237 161.494 409.37 + vertex -314.271 164.927 410.21 + endloop + endfacet + facet normal -0.079306 -0.406777 0.910079 + outer loop + vertex -335.635 167.974 409.736 + vertex -327.247 165.354 409.295 + vertex -334.183 169.356 410.48 + endloop + endfacet + facet normal -0.088971 -0.398182 0.912982 + outer loop + vertex -344.306 169.962 409.757 + vertex -335.635 167.974 409.736 + vertex -334.183 169.356 410.48 + endloop + endfacet + facet normal -0.108225 -0.446094 0.888418 + outer loop + vertex -354.799 171.5 409.252 + vertex -344.306 169.962 409.757 + vertex -351.655 172.433 410.103 + endloop + endfacet + facet normal -0.133163 -0.43279 0.891605 + outer loop + vertex -363.823 174.234 409.231 + vertex -354.799 171.5 409.252 + vertex -357.246 173.976 410.088 + endloop + endfacet + facet normal -0.180229 -0.393706 0.901395 + outer loop + vertex -379.621 181.232 409.374 + vertex -372.482 176.987 408.947 + vertex -374.452 179.494 409.648 + endloop + endfacet + facet normal 0.450498 -0.781598 -0.431458 + outer loop + vertex 391.647 189.103 407.901 + vertex 393.31 190.438 407.218 + vertex 392.732 189.941 407.514 + endloop + endfacet + facet normal -0.61886 0.782391 0.0698345 + outer loop + vertex 389.683 187.501 408.436 + vertex 391.647 189.103 407.901 + vertex 389.969 187.744 408.258 + endloop + endfacet + facet normal -0.535468 0.809499 0.2408 + outer loop + vertex 387.537 185.981 408.778 + vertex 389.683 187.501 408.436 + vertex 389.969 187.744 408.258 + endloop + endfacet + facet normal -0.433387 0.80706 0.401036 + outer loop + vertex 384.791 184.311 409.17 + vertex 387.537 185.981 408.778 + vertex 386.929 185.644 408.799 + endloop + endfacet + facet normal -0.423234 0.822949 0.378983 + outer loop + vertex 382.349 182.943 409.413 + vertex 384.791 184.311 409.17 + vertex 383.188 183.438 409.275 + endloop + endfacet + facet normal -0.521718 0.810766 -0.265462 + outer loop + vertex 379.603 181.16 409.363 + vertex 382.349 182.943 409.413 + vertex 383.188 183.438 409.275 + endloop + endfacet + facet normal -0.217327 -0.3485 0.911766 + outer loop + vertex -382.943 183.249 409.353 + vertex -379.621 181.232 409.374 + vertex -382.313 183.012 409.413 + endloop + endfacet + facet normal -0.00503997 0.157937 0.987436 + outer loop + vertex -384.984 184.375 409.163 + vertex -382.943 183.249 409.353 + vertex -384.796 184.418 409.157 + endloop + endfacet + facet normal -0.00807703 0.17081 0.985271 + outer loop + vertex -387.111 185.759 408.905 + vertex -384.984 184.375 409.163 + vertex -384.796 184.418 409.157 + endloop + endfacet + facet normal 0.5576 0.830107 0.00217859 + outer loop + vertex -389.471 187.345 408.499 + vertex -387.111 185.759 408.905 + vertex -388.51 186.699 408.566 + endloop + endfacet + facet normal 0.497085 0.779627 0.380906 + outer loop + vertex -391.408 188.843 407.961 + vertex -389.471 187.345 408.499 + vertex -388.51 186.699 408.566 + endloop + endfacet + facet normal 0.136179 -0.247688 -0.959222 + outer loop + vertex -393.313 190.556 407.248 + vertex -391.408 188.843 407.961 + vertex -392.49 189.623 407.606 + endloop + endfacet + facet normal 0.73519 -0.283068 0.615928 + outer loop + vertex 393.977 203.644 409.783 + vertex 394.084 205.819 410.656 + vertex 394.021 205.794 410.72 + endloop + endfacet + facet normal 0.717852 -0.143921 0.681158 + outer loop + vertex 394.004 201.219 409.243 + vertex 393.977 203.644 409.783 + vertex 393.751 202.702 409.823 + endloop + endfacet + facet normal 0.770466 -0.109348 0.628033 + outer loop + vertex 394.004 198.812 408.823 + vertex 394.004 201.219 409.243 + vertex 393.789 200.246 409.337 + endloop + endfacet + facet normal 0.78297 -0.130383 0.608241 + outer loop + vertex 393.975 196.661 408.4 + vertex 394.004 198.812 408.823 + vertex 393.812 197.875 408.87 + endloop + endfacet + facet normal -0.406345 0.188807 -0.894 + outer loop + vertex 393.742 194.416 408.032 + vertex 393.975 196.661 408.4 + vertex 393.938 195.352 408.14 + endloop + endfacet + facet normal -0.383828 0.20673 -0.899966 + outer loop + vertex 393.488 192.121 407.613 + vertex 393.742 194.416 408.032 + vertex 393.607 192.859 407.731 + endloop + endfacet + facet normal -0.415815 0.24892 -0.874721 + outer loop + vertex 393.31 190.438 407.218 + vertex 393.488 192.121 407.613 + vertex 393.486 191.219 407.357 + endloop + endfacet + facet normal 0.845341 0.200712 -0.49509 + outer loop + vertex -393.52 192.733 407.777 + vertex -393.313 190.556 407.248 + vertex -393.443 191.702 407.489 + endloop + endfacet + facet normal 0.706584 0.204544 -0.677422 + outer loop + vertex -393.679 194.648 408.189 + vertex -393.52 192.733 407.777 + vertex -393.724 194.241 408.018 + endloop + endfacet + facet normal 0.694421 0.169879 -0.699228 + outer loop + vertex -393.768 196.566 408.566 + vertex -393.679 194.648 408.189 + vertex -393.837 196.059 408.374 + endloop + endfacet + facet normal 0.676843 0.133214 -0.723973 + outer loop + vertex -393.784 198.67 408.939 + vertex -393.768 196.566 408.566 + vertex -393.875 198.081 408.745 + endloop + endfacet + facet normal 0.726112 0.104626 -0.67957 + outer loop + vertex -393.762 201.01 409.322 + vertex -393.784 198.67 408.939 + vertex -393.864 200.345 409.111 + endloop + endfacet + facet normal 0.607756 0.165989 -0.776582 + outer loop + vertex -393.785 203.497 409.836 + vertex -393.762 201.01 409.322 + vertex -393.891 203.048 409.657 + endloop + endfacet + facet normal -0.734202 -0.308151 0.604971 + outer loop + vertex -394.084 205.819 410.656 + vertex -393.785 203.497 409.836 + vertex -394.021 205.794 410.72 + endloop + endfacet + facet normal -0.667347 -0.532499 0.520665 + outer loop + vertex -391.684 204.647 412.55 + vertex -393.956 205.767 410.783 + vertex -391.108 203.331 411.942 + endloop + endfacet + facet normal 0.775197 -0.110986 0.621893 + outer loop + vertex 393.751 202.702 409.823 + vertex 393.789 200.246 409.337 + vertex 394.004 201.219 409.243 + endloop + endfacet + facet normal 0.890481 -0.196656 0.410329 + outer loop + vertex 394.021 205.794 410.72 + vertex 393.751 202.702 409.823 + vertex 393.977 203.644 409.783 + endloop + endfacet + facet normal -0.645396 -0.254697 0.720134 + outer loop + vertex -393.703 203.327 409.867 + vertex -392.948 203.294 410.532 + vertex -393.765 204.263 410.142 + endloop + endfacet + facet normal -0.581791 -0.272561 0.766309 + outer loop + vertex -392.948 203.294 410.532 + vertex -390.848 201.89 411.627 + vertex -391.108 203.331 411.942 + endloop + endfacet + facet normal 0.56958 0.168169 -0.804548 + outer loop + vertex -393.864 200.345 409.111 + vertex -393.891 203.048 409.657 + vertex -393.762 201.01 409.322 + endloop + endfacet + facet normal 0.0379107 0.362356 -0.931268 + outer loop + vertex -393.891 203.048 409.657 + vertex -394.021 205.794 410.72 + vertex -393.785 203.497 409.836 + endloop + endfacet + facet normal -0.708145 -0.35104 0.612619 + outer loop + vertex -393.956 205.767 410.783 + vertex -393.765 204.263 410.142 + vertex -392.948 203.294 410.532 + endloop + endfacet + facet normal 0.793188 0.309896 -0.524231 + outer loop + vertex 393.812 197.875 408.87 + vertex 394.027 196.471 408.366 + vertex 393.975 196.661 408.4 + endloop + endfacet + facet normal 0.74866 -0.121136 0.651793 + outer loop + vertex 393.789 200.246 409.337 + vertex 393.812 197.875 408.87 + vertex 394.004 198.812 408.823 + endloop + endfacet + facet normal 0.776567 0.127578 -0.616982 + outer loop + vertex -393.837 196.059 408.374 + vertex -393.875 198.081 408.745 + vertex -393.768 196.566 408.566 + endloop + endfacet + facet normal 0.740455 0.103712 -0.664056 + outer loop + vertex -393.875 198.081 408.745 + vertex -393.864 200.345 409.111 + vertex -393.784 198.67 408.939 + endloop + endfacet + facet normal -0.342465 0.193541 -0.91938 + outer loop + vertex 393.811 194.331 407.988 + vertex 393.713 193.635 407.878 + vertex 393.742 194.416 408.032 + endloop + endfacet + facet normal -0.0771722 0.195103 -0.977742 + outer loop + vertex 393.713 193.635 407.878 + vertex 393.607 192.859 407.731 + vertex 393.742 194.416 408.032 + endloop + endfacet + facet normal 0.0638307 0.192404 -0.979238 + outer loop + vertex 394.027 196.471 408.366 + vertex 393.938 195.352 408.14 + vertex 393.975 196.661 408.4 + endloop + endfacet + facet normal -0.356287 0.180959 -0.916686 + outer loop + vertex 393.938 195.352 408.14 + vertex 393.811 194.331 407.988 + vertex 393.742 194.416 408.032 + endloop + endfacet + facet normal 0.737264 0.203395 -0.644261 + outer loop + vertex -393.597 192.884 407.736 + vertex -393.724 194.241 408.018 + vertex -393.52 192.733 407.777 + endloop + endfacet + facet normal 0.777385 0.16698 -0.606456 + outer loop + vertex -393.724 194.241 408.018 + vertex -393.837 196.059 408.374 + vertex -393.679 194.648 408.189 + endloop + endfacet + facet normal -0.79633 0.166269 -0.581561 + outer loop + vertex 393.502 191.609 407.447 + vertex 393.486 191.219 407.357 + vertex 393.488 192.121 407.613 + endloop + endfacet + facet normal -0.179533 0.210859 -0.960888 + outer loop + vertex 393.486 191.219 407.357 + vertex 393.494 190.898 407.285 + vertex 393.31 190.438 407.218 + endloop + endfacet + facet normal -0.630856 0.221556 -0.743595 + outer loop + vertex 393.607 192.859 407.731 + vertex 393.527 192.051 407.559 + vertex 393.488 192.121 407.613 + endloop + endfacet + facet normal -0.628484 0.223929 -0.744892 + outer loop + vertex 393.527 192.051 407.559 + vertex 393.502 191.609 407.447 + vertex 393.488 192.121 407.613 + endloop + endfacet + facet normal -0.534182 -0.192098 0.823255 + outer loop + vertex -392.46 190.019 407.82 + vertex -393.242 190.82 407.5 + vertex -393.211 190.565 407.46 + endloop + endfacet + facet normal -0.558255 -0.430612 0.709171 + outer loop + vertex -391.399 189.305 408.222 + vertex -392.46 190.019 407.82 + vertex -391.024 188.825 408.226 + endloop + endfacet + facet normal 0.73509 0.219013 -0.64162 + outer loop + vertex -393.402 190.998 407.296 + vertex -393.443 191.702 407.489 + vertex -393.313 190.556 407.248 + endloop + endfacet + facet normal 0.761694 0.22585 -0.607301 + outer loop + vertex -393.443 191.702 407.489 + vertex -393.597 192.884 407.736 + vertex -393.52 192.733 407.777 + endloop + endfacet + facet normal 0.962146 -0.240401 -0.128388 + outer loop + vertex 393.353 190.553 407.326 + vertex 393.303 190.362 407.308 + vertex 393.31 190.438 407.218 + endloop + endfacet + facet normal 0.926448 -0.375217 0.0301107 + outer loop + vertex 393.494 190.898 407.285 + vertex 393.353 190.553 407.326 + vertex 393.31 190.438 407.218 + endloop + endfacet + facet normal 0.089702 -0.397189 0.913342 + outer loop + vertex 348.112 172.284 410.424 + vertex 335.317 169.217 410.347 + vertex 344.24 169.802 409.725 + endloop + endfacet + facet normal 0.0779779 -0.40546 0.910781 + outer loop + vertex 335.317 169.217 410.347 + vertex 318.239 165.585 410.192 + vertex 327.643 165.536 409.366 + endloop + endfacet + facet normal 0.071991 -0.412277 0.90821 + outer loop + vertex 318.239 165.585 410.192 + vertex 301.166 163.012 410.378 + vertex 306.802 161.852 409.404 + endloop + endfacet + facet normal -0.0706098 -0.408459 0.910041 + outer loop + vertex -296.779 162.329 410.401 + vertex -314.271 164.927 410.21 + vertex -305.237 161.494 409.37 + endloop + endfacet + facet normal -0.0775327 -0.404102 0.911422 + outer loop + vertex -314.271 164.927 410.21 + vertex -334.183 169.356 410.48 + vertex -327.247 165.354 409.295 + endloop + endfacet + facet normal -0.0891264 -0.403685 0.910547 + outer loop + vertex -334.183 169.356 410.48 + vertex -348.712 172.379 410.398 + vertex -344.306 169.962 409.757 + endloop + endfacet + facet normal -0.488041 -0.317208 0.813139 + outer loop + vertex -391.478 188.696 407.841 + vertex -391.397 188.698 407.891 + vertex -392.735 189.82 407.525 + endloop + endfacet + facet normal -0.465541 -0.277132 0.840518 + outer loop + vertex -391.521 188.699 407.818 + vertex -391.478 188.696 407.841 + vertex -392.903 189.941 407.462 + endloop + endfacet + facet normal -0.531595 -0.382795 0.755562 + outer loop + vertex -391.292 188.787 408.018 + vertex -391.024 188.825 408.226 + vertex -392.46 190.019 407.82 + endloop + endfacet + facet normal -0.554602 -0.396033 0.731829 + outer loop + vertex -391.397 188.698 407.891 + vertex -391.292 188.787 408.018 + vertex -392.842 190.066 407.536 + endloop + endfacet + facet normal 0.22496 0.0390375 -0.973586 + outer loop + vertex -393.53 190.734 407.205 + vertex -393.457 190.786 407.223 + vertex -393.313 190.556 407.248 + endloop + endfacet + facet normal 0.440941 0.185303 -0.878199 + outer loop + vertex -393.457 190.786 407.223 + vertex -393.402 190.998 407.296 + vertex -393.313 190.556 407.248 + endloop + endfacet + facet normal -0.590616 -0.325893 0.738218 + outer loop + vertex -393.211 190.565 407.46 + vertex -392.842 190.066 407.536 + vertex -392.46 190.019 407.82 + endloop + endfacet + facet normal -0.426232 -0.222798 0.876748 + outer loop + vertex -392.842 190.066 407.536 + vertex -392.735 189.82 407.525 + vertex -391.397 188.698 407.891 + endloop + endfacet + facet normal -0.164316 0.098384 0.981489 + outer loop + vertex -392.903 189.941 407.462 + vertex -392.815 189.803 407.491 + vertex -391.521 188.699 407.818 + endloop + endfacet + facet normal -0.584517 -0.467223 0.663357 + outer loop + vertex -392.735 189.82 407.525 + vertex -392.903 189.941 407.462 + vertex -391.478 188.696 407.841 + endloop + endfacet + facet normal 0.447953 -0.6982 -0.55844 + outer loop + vertex 393.303 190.362 407.308 + vertex 393.184 190.263 407.336 + vertex 393.31 190.438 407.218 + endloop + endfacet + facet normal -0.515779 0.275442 -0.811236 + outer loop + vertex 393.184 190.263 407.336 + vertex 392.707 189.772 407.472 + vertex 392.732 189.941 407.514 + endloop + endfacet + facet normal -0.372503 0.749957 0.546631 + outer loop + vertex 386.929 185.644 408.799 + vertex 383.188 183.438 409.275 + vertex 384.791 184.311 409.17 + endloop + endfacet + facet normal -0.352438 0.676562 0.646569 + outer loop + vertex 389.969 187.744 408.258 + vertex 386.929 185.644 408.799 + vertex 387.537 185.981 408.778 + endloop + endfacet + facet normal -0.557853 0.518268 -0.648227 + outer loop + vertex 391.936 189.216 407.743 + vertex 389.969 187.744 408.258 + vertex 391.647 189.103 407.901 + endloop + endfacet + facet normal -0.553529 0.372423 -0.744921 + outer loop + vertex 392.732 189.941 407.514 + vertex 391.936 189.216 407.743 + vertex 391.647 189.103 407.901 + endloop + endfacet + facet normal 0.176264 -0.442126 0.879463 + outer loop + vertex 374.665 179.362 409.689 + vertex 368.705 177.217 409.805 + vertex 374.142 177.503 408.859 + endloop + endfacet + facet normal 0.214098 -0.383144 0.898534 + outer loop + vertex 380.132 181.795 409.508 + vertex 377.225 180.248 409.541 + vertex 379.603 181.16 409.363 + endloop + endfacet + facet normal 0.303219 -0.44472 0.842783 + outer loop + vertex 383.188 183.438 409.275 + vertex 380.132 181.795 409.508 + vertex 379.603 181.16 409.363 + endloop + endfacet + facet normal 0.1237 -0.417257 0.90033 + outer loop + vertex 360.682 174.892 410.019 + vertex 352.663 172.84 410.17 + vertex 355.857 171.812 409.255 + endloop + endfacet + facet normal -0.118613 -0.421003 0.899271 + outer loop + vertex -351.655 172.433 410.103 + vertex -357.246 173.976 410.088 + vertex -354.799 171.5 409.252 + endloop + endfacet + facet normal -0.091772 -0.116817 0.988904 + outer loop + vertex -374.452 179.494 409.648 + vertex -381.335 182.519 409.367 + vertex -379.621 181.232 409.374 + endloop + endfacet + facet normal -0.161026 -0.381133 0.910389 + outer loop + vertex -365.389 176.308 409.918 + vertex -374.452 179.494 409.648 + vertex -372.482 176.987 408.947 + endloop + endfacet + facet normal 0.450676 0.269759 -0.850953 + outer loop + vertex -390.864 188.249 408.031 + vertex -391.349 188.498 407.854 + vertex -392.49 189.623 407.606 + endloop + endfacet + facet normal 0.343989 0.206214 -0.91605 + outer loop + vertex -388.51 186.699 408.566 + vertex -390.864 188.249 408.031 + vertex -391.408 188.843 407.961 + endloop + endfacet + facet normal -0.431518 -0.248909 0.867085 + outer loop + vertex -391.505 188.631 407.807 + vertex -391.521 188.699 407.818 + vertex -392.815 189.803 407.491 + endloop + endfacet + facet normal 0.637013 0.566279 -0.523013 + outer loop + vertex -391.349 188.498 407.854 + vertex -391.505 188.631 407.807 + vertex -392.852 189.841 407.476 + endloop + endfacet + facet normal 0.381609 0.758157 0.528746 + outer loop + vertex -384.796 184.418 409.157 + vertex -388.51 186.699 408.566 + vertex -387.111 185.759 408.905 + endloop + endfacet + facet normal 0.144407 0.197471 0.969614 + outer loop + vertex -381.335 182.519 409.367 + vertex -382.313 183.012 409.413 + vertex -379.621 181.232 409.374 + endloop + endfacet + facet normal -0.0768149 0.0456017 0.996002 + outer loop + vertex -382.313 183.012 409.413 + vertex -384.796 184.418 409.157 + vertex -382.943 183.249 409.353 + endloop + endfacet + facet normal -0.0972109 -0.345615 -0.933327 + outer loop + vertex -393.536 190.7 407.218 + vertex -393.53 190.734 407.205 + vertex -393.313 190.556 407.248 + endloop + endfacet + facet normal -0.15791 -0.430275 -0.888779 + outer loop + vertex -393.335 190.43 407.313 + vertex -393.536 190.7 407.218 + vertex -393.313 190.556 407.248 + endloop + endfacet + facet normal 0.476739 0.301801 -0.825613 + outer loop + vertex -392.852 189.841 407.476 + vertex -392.49 189.623 407.606 + vertex -391.349 188.498 407.854 + endloop + endfacet + facet normal -0.111225 -0.439624 -0.891268 + outer loop + vertex -392.49 189.623 407.606 + vertex -393.335 190.43 407.313 + vertex -393.313 190.556 407.248 + endloop + endfacet + facet normal -0.450981 -0.664575 -0.595782 + outer loop + vertex -392.815 189.803 407.491 + vertex -392.852 189.841 407.476 + vertex -391.505 188.631 407.807 + endloop + endfacet + facet normal 0.133819 -0.61752 -0.775088 + outer loop + vertex 392.732 189.941 407.514 + vertex 393.31 190.438 407.218 + vertex 393.184 190.263 407.336 + endloop + endfacet + facet normal 0.53261 0.399117 -0.746346 + outer loop + vertex -392.49 189.623 407.606 + vertex -391.408 188.843 407.961 + vertex -390.864 188.249 408.031 + endloop + endfacet + facet normal -0.57416 -0.311075 0.757345 + outer loop + vertex -391.108 203.331 411.942 + vertex -393.956 205.767 410.783 + vertex -392.948 203.294 410.532 + endloop + endfacet + facet normal -0.572894 -0.431393 0.696916 + outer loop + vertex -391.292 188.787 408.018 + vertex -392.46 190.019 407.82 + vertex -392.842 190.066 407.536 + endloop + endfacet + facet normal 0.974769 0.175547 -0.137873 + outer loop + vertex 876.615 488.002 320.853 + vertex 877.972 478.892 318.85 + vertex 876.328 486.308 316.669 + endloop + endfacet + facet normal 0.973659 0.171741 -0.149977 + outer loop + vertex 876.328 486.308 316.669 + vertex 877.972 478.892 318.85 + vertex 877.631 477.31 314.821 + endloop + endfacet + facet normal 0.981655 0.169828 -0.0866756 + outer loop + vertex 876.812 489.078 325.191 + vertex 878.214 479.917 323.125 + vertex 876.615 488.002 320.853 + endloop + endfacet + facet normal 0.981268 0.167232 -0.0956424 + outer loop + vertex 876.615 488.002 320.853 + vertex 878.214 479.917 323.125 + vertex 877.972 478.892 318.85 + endloop + endfacet + facet normal 0.984902 0.164684 -0.0533565 + outer loop + vertex 876.946 489.668 329.496 + vertex 878.401 480.402 327.742 + vertex 876.812 489.078 325.191 + endloop + endfacet + facet normal 0.984878 0.16362 -0.0569601 + outer loop + vertex 876.812 489.078 325.191 + vertex 878.401 480.402 327.742 + vertex 878.214 479.917 323.125 + endloop + endfacet + facet normal 0.986693 0.160773 -0.0242847 + outer loop + vertex 877.034 489.872 334.414 + vertex 878.624 479.933 333.217 + vertex 876.946 489.668 329.496 + endloop + endfacet + facet normal 0.986774 0.159909 -0.0265818 + outer loop + vertex 876.946 489.668 329.496 + vertex 878.624 479.933 333.217 + vertex 878.401 480.402 327.742 + endloop + endfacet + facet normal 0.991362 0.13113 0.00247815 + outer loop + vertex 877.051 489.67 338.526 + vertex 878.012 482.421 337.449 + vertex 877.034 489.872 334.414 + endloop + endfacet + facet normal 0.987007 0.151429 0.0537285 + outer loop + vertex 877.034 489.872 334.414 + vertex 878.012 482.421 337.449 + vertex 878.624 479.933 333.217 + endloop + endfacet + facet normal 0.989175 0.143079 0.0325836 + outer loop + vertex 876.996 488.984 343.199 + vertex 878.263 480.421 342.321 + vertex 877.051 489.67 338.526 + endloop + endfacet + facet normal 0.991366 0.1311 0.00268881 + outer loop + vertex 877.051 489.67 338.526 + vertex 878.263 480.421 342.321 + vertex 878.012 482.421 337.449 + endloop + endfacet + facet normal 0.991392 0.115387 0.0618658 + outer loop + vertex 876.864 487.884 347.367 + vertex 877.645 481.686 346.408 + vertex 876.996 488.984 343.199 + endloop + endfacet + facet normal 0.969758 0.232314 0.0748289 + outer loop + vertex 878.997 475.852 347.002 + vertex 878.263 480.421 342.321 + vertex 877.645 481.686 346.408 + endloop + endfacet + facet normal 0.985045 0.134801 0.107308 + outer loop + vertex 878.263 480.421 342.321 + vertex 876.996 488.984 343.199 + vertex 877.645 481.686 346.408 + endloop + endfacet + facet normal 0.96008 0.236353 0.149613 + outer loop + vertex 877.076 481.197 351.507 + vertex 878.175 476.909 351.228 + vertex 877.284 481.781 349.252 + endloop + endfacet + facet normal 0.966906 0.225401 0.119532 + outer loop + vertex 877.284 481.781 349.252 + vertex 878.175 476.909 351.228 + vertex 878.294 477.571 349.022 + endloop + endfacet + facet normal 0.990089 0.0904797 0.107415 + outer loop + vertex 876.624 486.184 351.472 + vertex 877.076 481.197 351.507 + vertex 876.756 487.097 349.487 + endloop + endfacet + facet normal 0.988979 0.0930662 0.115146 + outer loop + vertex 876.756 487.097 349.487 + vertex 877.076 481.197 351.507 + vertex 877.284 481.781 349.252 + endloop + endfacet + facet normal 0.991838 0.0946633 0.0854215 + outer loop + vertex 876.756 487.097 349.487 + vertex 877.284 481.781 349.252 + vertex 876.864 487.884 347.367 + endloop + endfacet + facet normal 0.986929 0.105556 0.121777 + outer loop + vertex 876.864 487.884 347.367 + vertex 877.284 481.781 349.252 + vertex 877.645 481.686 346.408 + endloop + endfacet + facet normal 0.967345 0.22574 0.115257 + outer loop + vertex 877.284 481.781 349.252 + vertex 878.294 477.571 349.022 + vertex 877.645 481.686 346.408 + endloop + endfacet + facet normal 0.96239 0.236581 0.13355 + outer loop + vertex 877.645 481.686 346.408 + vertex 878.294 477.571 349.022 + vertex 878.997 475.852 347.002 + endloop + endfacet + facet normal 0.932902 0.253764 0.255534 + outer loop + vertex 876.687 479.374 355.186 + vertex 877.769 475.47 355.114 + vertex 876.886 480.379 353.461 + endloop + endfacet + facet normal 0.944665 0.243757 0.219522 + outer loop + vertex 876.886 480.379 353.461 + vertex 877.769 475.47 355.114 + vertex 877.984 476.252 353.317 + endloop + endfacet + facet normal 0.980279 0.0929693 0.174385 + outer loop + vertex 876.245 483.739 355.342 + vertex 876.687 479.374 355.186 + vertex 876.449 485.03 353.509 + endloop + endfacet + facet normal 0.981955 0.0905604 0.16602 + outer loop + vertex 876.449 485.03 353.509 + vertex 876.687 479.374 355.186 + vertex 876.886 480.379 353.461 + endloop + endfacet + facet normal 0.986402 0.0912777 0.136676 + outer loop + vertex 876.449 485.03 353.509 + vertex 876.886 480.379 353.461 + vertex 876.624 486.184 351.472 + endloop + endfacet + facet normal 0.986857 0.0903694 0.133965 + outer loop + vertex 876.624 486.184 351.472 + vertex 876.886 480.379 353.461 + vertex 877.076 481.197 351.507 + endloop + endfacet + facet normal 0.949406 0.245862 0.195397 + outer loop + vertex 876.886 480.379 353.461 + vertex 877.984 476.252 353.317 + vertex 877.076 481.197 351.507 + endloop + endfacet + facet normal 0.958428 0.235151 0.161617 + outer loop + vertex 877.076 481.197 351.507 + vertex 877.984 476.252 353.317 + vertex 878.175 476.909 351.228 + endloop + endfacet + facet normal 0.864582 0.265046 0.426907 + outer loop + vertex 876.221 476.68 358.147 + vertex 877.301 473.273 358.075 + vertex 876.468 478.142 356.74 + endloop + endfacet + facet normal 0.889381 0.256077 0.378716 + outer loop + vertex 876.468 478.142 356.74 + vertex 877.301 473.273 358.075 + vertex 877.547 474.492 356.674 + endloop + endfacet + facet normal 0.962054 0.0881969 0.258213 + outer loop + vertex 875.78 480.592 358.455 + vertex 876.221 476.68 358.147 + vertex 876.014 482.253 357.016 + endloop + endfacet + facet normal 0.961386 0.0886439 0.260537 + outer loop + vertex 876.014 482.253 357.016 + vertex 876.221 476.68 358.147 + vertex 876.468 478.142 356.74 + endloop + endfacet + facet normal 0.971824 0.0927301 0.2167 + outer loop + vertex 876.014 482.253 357.016 + vertex 876.468 478.142 356.74 + vertex 876.245 483.739 355.342 + endloop + endfacet + facet normal 0.973541 0.0910252 0.209601 + outer loop + vertex 876.245 483.739 355.342 + vertex 876.468 478.142 356.74 + vertex 876.687 479.374 355.186 + endloop + endfacet + facet normal 0.905175 0.26154 0.335045 + outer loop + vertex 876.468 478.142 356.74 + vertex 877.547 474.492 356.674 + vertex 876.687 479.374 355.186 + endloop + endfacet + facet normal 0.924044 0.250702 0.288602 + outer loop + vertex 876.687 479.374 355.186 + vertex 877.547 474.492 356.674 + vertex 877.769 475.47 355.114 + endloop + endfacet + facet normal 0.746753 0.237749 0.621157 + outer loop + vertex 875.646 473.683 360.251 + vertex 876.495 471.384 360.111 + vertex 875.936 475.162 359.336 + endloop + endfacet + facet normal 0.751299 0.237325 0.615814 + outer loop + vertex 875.936 475.162 359.336 + vertex 876.495 471.384 360.111 + vertex 876.974 471.963 359.303 + endloop + endfacet + facet normal 0.955447 0.0502219 0.290858 + outer loop + vertex 875.37 476.599 360.656 + vertex 875.646 473.683 360.251 + vertex 875.558 478.703 359.674 + endloop + endfacet + facet normal 0.91876 0.0610003 0.390075 + outer loop + vertex 875.558 478.703 359.674 + vertex 875.646 473.683 360.251 + vertex 875.936 475.162 359.336 + endloop + endfacet + facet normal 0.954385 0.0744278 0.289152 + outer loop + vertex 875.558 478.703 359.674 + vertex 875.936 475.162 359.336 + vertex 875.78 480.592 358.455 + endloop + endfacet + facet normal 0.941257 0.0803551 0.327991 + outer loop + vertex 875.78 480.592 358.455 + vertex 875.936 475.162 359.336 + vertex 876.221 476.68 358.147 + endloop + endfacet + facet normal 0.81193 0.257943 0.523675 + outer loop + vertex 875.936 475.162 359.336 + vertex 876.974 471.963 359.303 + vertex 876.221 476.68 358.147 + endloop + endfacet + facet normal 0.832667 0.253563 0.492312 + outer loop + vertex 876.221 476.68 358.147 + vertex 876.974 471.963 359.303 + vertex 877.301 473.273 358.075 + endloop + endfacet + facet normal 0.979734 0.00734263 0.200167 + outer loop + vertex 875.246 474.618 361.334 + vertex 875.36 472.722 360.844 + vertex 875.37 476.599 360.656 + endloop + endfacet + facet normal 0.887354 0.0202345 0.460645 + outer loop + vertex 875.37 476.599 360.656 + vertex 875.36 472.722 360.844 + vertex 875.646 473.683 360.251 + endloop + endfacet + facet normal 0.69692 0.214806 0.684222 + outer loop + vertex 875.36 472.722 360.844 + vertex 876.201 470.321 360.741 + vertex 875.646 473.683 360.251 + endloop + endfacet + facet normal 0.69528 0.21478 0.685898 + outer loop + vertex 875.646 473.683 360.251 + vertex 876.201 470.321 360.741 + vertex 876.495 471.384 360.111 + endloop + endfacet + facet normal 0.614627 0.195621 0.764177 + outer loop + vertex 876.612 468.292 361.058 + vertex 875.485 471.006 361.269 + vertex 875.988 469.004 361.378 + endloop + endfacet + facet normal 0.934326 0.0553375 0.352099 + outer loop + vertex 875.168 472.488 361.878 + vertex 875.166 472.362 361.905 + vertex 875.485 471.006 361.269 + endloop + endfacet + facet normal 0.969881 0.241959 -0.0280418 + outer loop + vertex 875.166 472.362 361.905 + vertex 875.988 469.004 361.378 + vertex 875.485 471.006 361.269 + endloop + endfacet + facet normal 0.926911 0.290406 0.237699 + outer loop + vertex 877.769 475.47 355.114 + vertex 878.871 472.305 354.683 + vertex 877.984 476.252 353.317 + endloop + endfacet + facet normal 0.939592 0.279423 0.197713 + outer loop + vertex 877.984 476.252 353.317 + vertex 878.871 472.305 354.683 + vertex 879.097 472.973 352.664 + endloop + endfacet + facet normal 0.942359 0.284736 0.175742 + outer loop + vertex 877.984 476.252 353.317 + vertex 879.097 472.973 352.664 + vertex 878.175 476.909 351.228 + endloop + endfacet + facet normal 0.950671 0.274957 0.143606 + outer loop + vertex 878.175 476.909 351.228 + vertex 879.097 472.973 352.664 + vertex 879.217 473.835 350.218 + endloop + endfacet + facet normal 0.860224 0.300325 0.412091 + outer loop + vertex 877.301 473.273 358.075 + vertex 878.384 470.498 357.837 + vertex 877.547 474.492 356.674 + endloop + endfacet + facet normal 0.890377 0.289055 0.351676 + outer loop + vertex 877.547 474.492 356.674 + vertex 878.384 470.498 357.837 + vertex 878.629 471.532 356.369 + endloop + endfacet + facet normal 0.90162 0.297006 0.314433 + outer loop + vertex 877.547 474.492 356.674 + vertex 878.629 471.532 356.369 + vertex 877.769 475.47 355.114 + endloop + endfacet + facet normal 0.921634 0.285081 0.263285 + outer loop + vertex 877.769 475.47 355.114 + vertex 878.629 471.532 356.369 + vertex 878.871 472.305 354.683 + endloop + endfacet + facet normal 0.727875 0.274351 0.628435 + outer loop + vertex 876.495 471.384 360.111 + vertex 877.582 467.87 360.386 + vertex 876.974 471.963 359.303 + endloop + endfacet + facet normal 0.745876 0.271663 0.608168 + outer loop + vertex 876.974 471.963 359.303 + vertex 877.582 467.87 360.386 + vertex 878.079 469.288 359.143 + endloop + endfacet + facet normal 0.795306 0.296838 0.52856 + outer loop + vertex 876.974 471.963 359.303 + vertex 878.079 469.288 359.143 + vertex 877.301 473.273 358.075 + endloop + endfacet + facet normal 0.838688 0.287596 0.462484 + outer loop + vertex 877.301 473.273 358.075 + vertex 878.079 469.288 359.143 + vertex 878.384 470.498 357.837 + endloop + endfacet + facet normal 0.949002 0.287418 -0.129561 + outer loop + vertex 879.684 473.403 321.379 + vertex 880.532 469.84 319.686 + vertex 879.418 472.396 317.198 + endloop + endfacet + facet normal 0.950372 0.277815 -0.140041 + outer loop + vertex 879.418 472.396 317.198 + vertex 880.532 469.84 319.686 + vertex 880.209 468.86 315.552 + endloop + endfacet + facet normal 0.958712 0.274735 -0.0734271 + outer loop + vertex 879.87 473.937 325.816 + vertex 880.732 470.482 324.137 + vertex 879.684 473.403 321.379 + endloop + endfacet + facet normal 0.960121 0.267356 -0.081779 + outer loop + vertex 879.684 473.403 321.379 + vertex 880.732 470.482 324.137 + vertex 880.532 469.84 319.686 + endloop + endfacet + facet normal 0.963016 0.267253 -0.0343027 + outer loop + vertex 880.042 473.913 330.459 + vertex 880.872 470.685 328.605 + vertex 879.87 473.937 325.816 + endloop + endfacet + facet normal 0.964429 0.260959 -0.042151 + outer loop + vertex 879.87 473.937 325.816 + vertex 880.872 470.685 328.605 + vertex 880.732 470.482 324.137 + endloop + endfacet + facet normal 0.963852 0.266346 -0.00707486 + outer loop + vertex 880.247 473.283 334.643 + vertex 880.949 470.703 333.071 + vertex 880.042 473.913 330.459 + endloop + endfacet + facet normal 0.965884 0.258379 -0.0175701 + outer loop + vertex 880.042 473.913 330.459 + vertex 880.949 470.703 333.071 + vertex 880.872 470.685 328.605 + endloop + endfacet + facet normal 0.962975 0.26926 0.0133748 + outer loop + vertex 879.66 475.172 338.878 + vertex 880.845 471 337.556 + vertex 880.247 473.283 334.643 + endloop + endfacet + facet normal 0.965747 0.259437 0.00510402 + outer loop + vertex 880.247 473.283 334.643 + vertex 880.845 471 337.556 + vertex 880.949 470.703 333.071 + endloop + endfacet + facet normal 0.958228 0.281334 0.0514847 + outer loop + vertex 879.881 473.401 344.441 + vertex 880.699 471.015 342.262 + vertex 879.66 475.172 338.878 + endloop + endfacet + facet normal 0.963934 0.264545 0.0291061 + outer loop + vertex 879.66 475.172 338.878 + vertex 880.699 471.015 342.262 + vertex 880.845 471 337.556 + endloop + endfacet + facet normal 0.953146 0.289155 0.0888988 + outer loop + vertex 879.978 471.769 348.71 + vertex 880.581 470.339 346.901 + vertex 879.881 473.401 344.441 + endloop + endfacet + facet normal 0.960519 0.270773 0.063913 + outer loop + vertex 879.881 473.401 344.441 + vertex 880.581 470.339 346.901 + vertex 880.699 471.015 342.262 + endloop + endfacet + facet normal 0.962663 0.247462 0.109734 + outer loop + vertex 879.826 471.113 351.521 + vertex 880.233 469.547 351.488 + vertex 879.978 471.769 348.71 + endloop + endfacet + facet normal 0.959504 0.256233 0.117036 + outer loop + vertex 879.978 471.769 348.71 + vertex 880.233 469.547 351.488 + vertex 880.581 470.339 346.901 + endloop + endfacet + facet normal 0.955677 0.244535 0.163963 + outer loop + vertex 879.826 471.113 351.521 + vertex 879.67 470.204 353.792 + vertex 880.233 469.547 351.488 + endloop + endfacet + facet normal 0.954591 0.219246 0.201712 + outer loop + vertex 879.362 469.753 355.736 + vertex 879.697 468.239 355.797 + vertex 879.67 470.204 353.792 + endloop + endfacet + facet normal 0.963863 0.196783 0.179566 + outer loop + vertex 879.697 468.239 355.797 + vertex 880.233 469.547 351.488 + vertex 879.67 470.204 353.792 + endloop + endfacet + facet normal 0.894008 0.260842 0.364295 + outer loop + vertex 878.897 467.622 358.72 + vertex 879.33 466.896 358.179 + vertex 879.184 468.703 357.244 + endloop + endfacet + facet normal 0.939611 0.218395 0.263504 + outer loop + vertex 879.362 469.753 355.736 + vertex 879.184 468.703 357.244 + vertex 879.697 468.239 355.797 + endloop + endfacet + facet normal 0.922757 0.256957 0.287217 + outer loop + vertex 879.419 466.855 357.927 + vertex 879.697 468.239 355.797 + vertex 879.33 466.896 358.179 + endloop + endfacet + facet normal 0.94025 0.213359 0.265346 + outer loop + vertex 879.184 468.703 357.244 + vertex 879.33 466.896 358.179 + vertex 879.697 468.239 355.797 + endloop + endfacet + facet normal 0.823877 0.265859 0.500544 + outer loop + vertex 878.833 465.519 360.014 + vertex 878.983 465.421 359.819 + vertex 879.051 466.003 359.398 + endloop + endfacet + facet normal 0.914562 0.16153 0.37079 + outer loop + vertex 879.051 466.003 359.398 + vertex 878.983 465.421 359.819 + vertex 879.147 465.944 359.186 + endloop + endfacet + facet normal 0.75164 0.282173 0.596167 + outer loop + vertex 878.477 465.78 360.34 + vertex 878.833 465.519 360.014 + vertex 878.599 466.636 359.78 + endloop + endfacet + facet normal 0.816491 0.276914 0.506617 + outer loop + vertex 878.599 466.636 359.78 + vertex 878.833 465.519 360.014 + vertex 879.051 466.003 359.398 + endloop + endfacet + facet normal 0.819866 0.285569 0.496256 + outer loop + vertex 878.599 466.636 359.78 + vertex 879.051 466.003 359.398 + vertex 878.897 467.622 358.72 + endloop + endfacet + facet normal 0.890671 0.244866 0.383073 + outer loop + vertex 878.897 467.622 358.72 + vertex 879.051 466.003 359.398 + vertex 879.33 466.896 358.179 + endloop + endfacet + facet normal 0.911381 0.203668 0.357636 + outer loop + vertex 879.051 466.003 359.398 + vertex 879.147 465.944 359.186 + vertex 879.33 466.896 358.179 + endloop + endfacet + facet normal 0.938907 0.148484 0.310493 + outer loop + vertex 879.33 466.896 358.179 + vertex 879.147 465.944 359.186 + vertex 879.419 466.855 357.927 + endloop + endfacet + facet normal 0.601361 0.277664 0.749178 + outer loop + vertex 878.148 464.7 361.061 + vertex 878.306 464.542 360.993 + vertex 878.241 465.197 360.803 + endloop + endfacet + facet normal 0.711566 0.260586 0.65251 + outer loop + vertex 878.241 465.197 360.803 + vertex 878.306 464.542 360.993 + vertex 878.409 464.679 360.826 + endloop + endfacet + facet normal 0.902972 0.313753 -0.293601 + outer loop + vertex 879.708 465.894 309.614 + vertex 879.118 464.911 306.747 + vertex 879.09 466.178 308.014 + endloop + endfacet + facet normal 0.919929 0.298989 -0.253647 + outer loop + vertex 880.104 466.59 311.868 + vertex 879.708 465.894 309.614 + vertex 879.81 467.412 311.77 + endloop + endfacet + facet normal 0.924913 0.303755 -0.228626 + outer loop + vertex 880.369 467.508 314.159 + vertex 880.104 466.59 311.868 + vertex 879.81 467.412 311.77 + endloop + endfacet + facet normal 0.945944 0.28016 -0.163403 + outer loop + vertex 880.61 468.402 317.088 + vertex 880.369 467.508 314.159 + vertex 880.209 468.86 315.552 + endloop + endfacet + facet normal 0.948604 0.288127 -0.130898 + outer loop + vertex 880.815 469.081 320.07 + vertex 880.61 468.402 317.088 + vertex 880.532 469.84 319.686 + endloop + endfacet + facet normal 0.947381 0.305499 -0.0955985 + outer loop + vertex 880.9 469.494 322.233 + vertex 880.815 469.081 320.07 + vertex 880.532 469.84 319.686 + endloop + endfacet + facet normal 0.956976 0.283362 -0.0624778 + outer loop + vertex 881.016 469.604 324.5 + vertex 880.9 469.494 322.233 + vertex 880.732 470.482 324.137 + endloop + endfacet + facet normal 0.955943 0.289978 -0.0456759 + outer loop + vertex 881.052 469.818 326.626 + vertex 881.016 469.604 324.5 + vertex 880.732 470.482 324.137 + endloop + endfacet + facet normal 0.940274 0.332106 0.0747719 + outer loop + vertex 880.82 469.609 347.134 + vertex 880.928 469.888 344.543 + vertex 880.581 470.339 346.901 + endloop + endfacet + facet normal 0.933822 0.340835 0.108661 + outer loop + vertex 880.623 469.489 349.202 + vertex 880.82 469.609 347.134 + vertex 880.581 470.339 346.901 + endloop + endfacet + facet normal 0.911776 0.383867 0.14598 + outer loop + vertex 880.446 469.14 351.225 + vertex 880.623 469.489 349.202 + vertex 880.233 469.547 351.488 + endloop + endfacet + facet normal 0.914956 0.350202 0.200535 + outer loop + vertex 880.08 468.478 354.054 + vertex 880.446 469.14 351.225 + vertex 880.233 469.547 351.488 + endloop + endfacet + facet normal 0.944794 0.224993 0.238205 + outer loop + vertex 879.597 467.458 356.932 + vertex 880.08 468.478 354.054 + vertex 879.697 468.239 355.797 + endloop + endfacet + facet normal -0.178455 -0.826892 -0.533295 + outer loop + vertex 879.199 466.354 358.779 + vertex 879.597 467.458 356.932 + vertex 879.419 466.855 357.927 + endloop + endfacet + facet normal -0.568203 -0.543679 -0.617704 + outer loop + vertex 878.729 465.236 360.194 + vertex 879.199 466.354 358.779 + vertex 879.147 465.944 359.186 + endloop + endfacet + facet normal 0.905925 -0.0430436 0.421245 + outer loop + vertex 878.302 464.302 361.019 + vertex 878.729 465.236 360.194 + vertex 878.409 464.679 360.826 + endloop + endfacet + facet normal 0.282993 0.00666434 0.959099 + outer loop + vertex 877.568 465.352 361.228 + vertex 878.302 464.302 361.019 + vertex 878.148 464.7 361.061 + endloop + endfacet + facet normal 0.422558 0.146124 0.894479 + outer loop + vertex 876.243 467.965 361.427 + vertex 877.568 465.352 361.228 + vertex 875.988 469.004 361.378 + endloop + endfacet + facet normal 0.620768 0.188533 0.760988 + outer loop + vertex 875.32 470.342 361.591 + vertex 876.243 467.965 361.427 + vertex 875.988 469.004 361.378 + endloop + endfacet + facet normal 0.966477 0.0343554 0.254444 + outer loop + vertex 875.163 472.235 361.932 + vertex 875.32 470.342 361.591 + vertex 875.166 472.362 361.905 + endloop + endfacet + facet normal 0.934539 0.0556346 0.351486 + outer loop + vertex 875.246 474.618 361.334 + vertex 875.168 472.488 361.878 + vertex 875.485 471.006 361.269 + endloop + endfacet + facet normal 0.949115 0.257357 -0.181514 + outer loop + vertex 877.631 477.31 314.821 + vertex 877.972 478.892 318.85 + vertex 879.418 472.396 317.198 + endloop + endfacet + facet normal 0.962169 0.247533 -0.113832 + outer loop + vertex 877.972 478.892 318.85 + vertex 878.214 479.917 323.125 + vertex 879.684 473.403 321.379 + endloop + endfacet + facet normal 0.968797 0.239382 -0.0642547 + outer loop + vertex 878.214 479.917 323.125 + vertex 878.401 480.402 327.742 + vertex 879.87 473.937 325.816 + endloop + endfacet + facet normal 0.971163 0.237634 -0.0192929 + outer loop + vertex 878.401 480.402 327.742 + vertex 878.624 479.933 333.217 + vertex 880.042 473.913 330.459 + endloop + endfacet + facet normal 0.97466 0.223485 0.00958134 + outer loop + vertex 878.624 479.933 333.217 + vertex 878.012 482.421 337.449 + vertex 879.66 475.172 338.878 + endloop + endfacet + facet normal 0.972246 0.229755 0.0441555 + outer loop + vertex 878.012 482.421 337.449 + vertex 878.263 480.421 342.321 + vertex 879.66 475.172 338.878 + endloop + endfacet + facet normal 0.963669 0.250269 0.0933104 + outer loop + vertex 878.263 480.421 342.321 + vertex 878.997 475.852 347.002 + vertex 879.881 473.401 344.441 + endloop + endfacet + facet normal 0.951091 0.278094 0.134495 + outer loop + vertex 878.294 477.571 349.022 + vertex 878.175 476.909 351.228 + vertex 879.217 473.835 350.218 + endloop + endfacet + facet normal 0.957344 0.269746 0.103581 + outer loop + vertex 878.997 475.852 347.002 + vertex 878.294 477.571 349.022 + vertex 879.217 473.835 350.218 + endloop + endfacet + facet normal 0.997476 0.0665155 -0.0248363 + outer loop + vertex 875.36 472.722 360.844 + vertex 875.246 474.618 361.334 + vertex 875.485 471.006 361.269 + endloop + endfacet + facet normal 0.705966 0.218423 0.673724 + outer loop + vertex 876.201 470.321 360.741 + vertex 875.36 472.722 360.844 + vertex 875.485 471.006 361.269 + endloop + endfacet + facet normal 0.638622 0.254391 0.726256 + outer loop + vertex 876.495 471.384 360.111 + vertex 876.201 470.321 360.741 + vertex 877.582 467.87 360.386 + endloop + endfacet + facet normal 0.717043 0.246859 0.651851 + outer loop + vertex 875.485 471.006 361.269 + vertex 876.612 468.292 361.058 + vertex 876.201 470.321 360.741 + endloop + endfacet + facet normal 0.654521 0.253978 0.712107 + outer loop + vertex 876.612 468.292 361.058 + vertex 875.988 469.004 361.378 + vertex 877.568 465.352 361.228 + endloop + endfacet + facet normal 0.00899701 -0.152934 0.988195 + outer loop + vertex 875.988 469.004 361.378 + vertex 875.166 472.362 361.905 + vertex 875.32 470.342 361.591 + endloop + endfacet + facet normal 0.941325 0.274548 0.196292 + outer loop + vertex 879.097 472.973 352.664 + vertex 878.871 472.305 354.683 + vertex 879.67 470.204 353.792 + endloop + endfacet + facet normal 0.948195 0.282146 0.146015 + outer loop + vertex 879.217 473.835 350.218 + vertex 879.097 472.973 352.664 + vertex 879.826 471.113 351.521 + endloop + endfacet + facet normal 0.893754 0.283024 0.347995 + outer loop + vertex 878.629 471.532 356.369 + vertex 878.384 470.498 357.837 + vertex 879.184 468.703 357.244 + endloop + endfacet + facet normal 0.921158 0.286205 0.263732 + outer loop + vertex 878.871 472.305 354.683 + vertex 878.629 471.532 356.369 + vertex 879.362 469.753 355.736 + endloop + endfacet + facet normal 0.725471 0.292005 0.623237 + outer loop + vertex 878.079 469.288 359.143 + vertex 877.582 467.87 360.386 + vertex 878.599 466.636 359.78 + endloop + endfacet + facet normal 0.835269 0.292087 0.465845 + outer loop + vertex 878.384 470.498 357.837 + vertex 878.079 469.288 359.143 + vertex 878.897 467.622 358.72 + endloop + endfacet + facet normal 0.894409 0.344887 -0.284754 + outer loop + vertex 879.09 466.178 308.014 + vertex 879.81 467.412 311.77 + vertex 879.708 465.894 309.614 + endloop + endfacet + facet normal 0.9119 0.341836 -0.227125 + outer loop + vertex 879.81 467.412 311.77 + vertex 880.209 468.86 315.552 + vertex 880.369 467.508 314.159 + endloop + endfacet + facet normal 0.962148 0.24464 -0.120095 + outer loop + vertex 879.684 473.403 321.379 + vertex 879.418 472.396 317.198 + vertex 877.972 478.892 318.85 + endloop + endfacet + facet normal 0.935683 0.3199 -0.148869 + outer loop + vertex 880.209 468.86 315.552 + vertex 880.532 469.84 319.686 + vertex 880.61 468.402 317.088 + endloop + endfacet + facet normal 0.968996 0.237151 -0.0693339 + outer loop + vertex 879.87 473.937 325.816 + vertex 879.684 473.403 321.379 + vertex 878.214 479.917 323.125 + endloop + endfacet + facet normal 0.938241 0.333962 -0.0904058 + outer loop + vertex 880.532 469.84 319.686 + vertex 880.732 470.482 324.137 + vertex 880.9 469.494 322.233 + endloop + endfacet + facet normal 0.972235 0.231399 -0.0348288 + outer loop + vertex 880.042 473.913 330.459 + vertex 879.87 473.937 325.816 + vertex 878.401 480.402 327.742 + endloop + endfacet + facet normal 0.953815 0.297233 -0.0434664 + outer loop + vertex 880.732 470.482 324.137 + vertex 880.872 470.685 328.605 + vertex 881.052 469.818 326.626 + endloop + endfacet + facet normal 0.972013 0.234608 -0.0122533 + outer loop + vertex 880.247 473.283 334.643 + vertex 880.042 473.913 330.459 + vertex 878.624 479.933 333.217 + endloop + endfacet + facet normal 0.958833 0.283427 -0.0175506 + outer loop + vertex 880.872 470.685 328.605 + vertex 880.949 470.703 333.071 + vertex 881.137 469.941 331.031 + endloop + endfacet + facet normal 0.969832 0.242349 0.0263293 + outer loop + vertex 879.66 475.172 338.878 + vertex 880.247 473.283 334.643 + vertex 878.624 479.933 333.217 + endloop + endfacet + facet normal 0.956626 0.291306 0.0027876 + outer loop + vertex 880.949 470.703 333.071 + vertex 880.845 471 337.556 + vertex 881.129 470.09 335.418 + endloop + endfacet + facet normal 0.971377 0.234778 0.0361429 + outer loop + vertex 879.881 473.401 344.441 + vertex 879.66 475.172 338.878 + vertex 878.263 480.421 342.321 + endloop + endfacet + facet normal 0.951241 0.307121 0.028578 + outer loop + vertex 880.845 471 337.556 + vertex 880.699 471.015 342.262 + vertex 881.05 470.115 340.257 + endloop + endfacet + facet normal 0.961222 0.26417 0.0791601 + outer loop + vertex 879.978 471.769 348.71 + vertex 879.881 473.401 344.441 + vertex 878.997 475.852 347.002 + endloop + endfacet + facet normal 0.93809 0.338566 0.0732135 + outer loop + vertex 880.699 471.015 342.262 + vertex 880.581 470.339 346.901 + vertex 880.928 469.888 344.543 + endloop + endfacet + facet normal 0.956371 0.268833 0.114379 + outer loop + vertex 879.826 471.113 351.521 + vertex 879.978 471.769 348.71 + vertex 879.217 473.835 350.218 + endloop + endfacet + facet normal 0.892662 0.427912 0.141585 + outer loop + vertex 880.581 470.339 346.901 + vertex 880.233 469.547 351.488 + vertex 880.623 469.489 349.202 + endloop + endfacet + facet normal 0.94843 0.266181 0.172132 + outer loop + vertex 879.67 470.204 353.792 + vertex 879.826 471.113 351.521 + vertex 879.097 472.973 352.664 + endloop + endfacet + facet normal 0.840332 0.480732 0.250477 + outer loop + vertex 880.233 469.547 351.488 + vertex 879.697 468.239 355.797 + vertex 880.08 468.478 354.054 + endloop + endfacet + facet normal 0.9401 0.267966 0.210725 + outer loop + vertex 879.362 469.753 355.736 + vertex 879.67 470.204 353.792 + vertex 878.871 472.305 354.683 + endloop + endfacet + facet normal 0.88753 0.272469 0.371554 + outer loop + vertex 878.897 467.622 358.72 + vertex 879.184 468.703 357.244 + vertex 878.384 470.498 357.837 + endloop + endfacet + facet normal 0.915187 0.271669 0.297705 + outer loop + vertex 879.184 468.703 357.244 + vertex 879.362 469.753 355.736 + vertex 878.629 471.532 356.369 + endloop + endfacet + facet normal 0.580193 0.646439 0.495472 + outer loop + vertex 879.697 468.239 355.797 + vertex 879.419 466.855 357.927 + vertex 879.597 467.458 356.932 + endloop + endfacet + facet normal 0.808408 0.0757261 0.583731 + outer loop + vertex 878.983 465.421 359.819 + vertex 878.833 465.519 360.014 + vertex 878.729 465.236 360.194 + endloop + endfacet + facet normal -0.486953 -0.606697 -0.628327 + outer loop + vertex 879.147 465.944 359.186 + vertex 878.983 465.421 359.819 + vertex 878.729 465.236 360.194 + endloop + endfacet + facet normal 0.72702 0.159003 0.667952 + outer loop + vertex 878.833 465.519 360.014 + vertex 878.477 465.78 360.34 + vertex 878.729 465.236 360.194 + endloop + endfacet + facet normal 0.728983 0.298428 0.616056 + outer loop + vertex 878.477 465.78 360.34 + vertex 878.599 466.636 359.78 + vertex 877.582 467.87 360.386 + endloop + endfacet + facet normal 0.824209 0.279949 0.492249 + outer loop + vertex 878.599 466.636 359.78 + vertex 878.897 467.622 358.72 + vertex 878.079 469.288 359.143 + endloop + endfacet + facet normal -0.876685 -0.27933 -0.39166 + outer loop + vertex 879.419 466.855 357.927 + vertex 879.147 465.944 359.186 + vertex 879.199 466.354 358.779 + endloop + endfacet + facet normal 0.46605 0.0854671 0.880621 + outer loop + vertex 878.306 464.542 360.993 + vertex 878.148 464.7 361.061 + vertex 878.302 464.302 361.019 + endloop + endfacet + facet normal 0.558035 0.29875 0.774174 + outer loop + vertex 878.148 464.7 361.061 + vertex 878.241 465.197 360.803 + vertex 877.568 465.352 361.228 + endloop + endfacet + facet normal 0.742699 0.268912 0.613258 + outer loop + vertex 878.241 465.197 360.803 + vertex 878.409 464.679 360.826 + vertex 878.729 465.236 360.194 + endloop + endfacet + facet normal 0.835018 0.0421632 0.548604 + outer loop + vertex 878.409 464.679 360.826 + vertex 878.306 464.542 360.993 + vertex 878.302 464.302 361.019 + endloop + endfacet + facet normal 0.955721 0.274307 0.106553 + outer loop + vertex 878.997 475.852 347.002 + vertex 879.217 473.835 350.218 + vertex 879.978 471.769 348.71 + endloop + endfacet + facet normal 0.621619 0.242097 0.744969 + outer loop + vertex 877.582 467.87 360.386 + vertex 876.201 470.321 360.741 + vertex 876.612 468.292 361.058 + endloop + endfacet + facet normal 0.622032 0.245225 0.7436 + outer loop + vertex 876.612 468.292 361.058 + vertex 877.568 465.352 361.228 + vertex 877.582 467.87 360.386 + endloop + endfacet + facet normal 0.760322 0.186742 0.622124 + outer loop + vertex 878.729 465.236 360.194 + vertex 878.477 465.78 360.34 + vertex 878.241 465.197 360.803 + endloop + endfacet + facet normal 0.673561 0.273156 0.686805 + outer loop + vertex 878.477 465.78 360.34 + vertex 877.582 467.87 360.386 + vertex 878.241 465.197 360.803 + endloop + endfacet + facet normal 0.557913 0.260427 0.787979 + outer loop + vertex 877.568 465.352 361.228 + vertex 878.241 465.197 360.803 + vertex 877.582 467.87 360.386 + endloop + endfacet + facet normal 0.322494 -0.878365 0.352806 + outer loop + vertex 677.654 123.718 317.174 + vertex 680.363 123.944 315.258 + vertex 686.392 126.834 316.942 + endloop + endfacet + facet normal 0.303012 -0.865086 0.399761 + outer loop + vertex 686.392 126.834 316.942 + vertex 680.363 123.944 315.258 + vertex 686.718 126.387 315.729 + endloop + endfacet + facet normal 0.314352 -0.88336 0.347647 + outer loop + vertex 667.384 119.934 316.845 + vertex 671.751 120.909 315.372 + vertex 677.654 123.718 317.174 + endloop + endfacet + facet normal 0.316215 -0.884428 0.343212 + outer loop + vertex 677.654 123.718 317.174 + vertex 671.751 120.909 315.372 + vertex 680.363 123.944 315.258 + endloop + endfacet + facet normal 0.299357 -0.904367 0.304147 + outer loop + vertex 658.715 116.644 315.992 + vertex 660.561 116.762 314.528 + vertex 661.551 117.512 315.784 + endloop + endfacet + facet normal 0.313364 -0.903445 0.292556 + outer loop + vertex 661.551 117.512 315.784 + vertex 660.561 116.762 314.528 + vertex 664.987 118.252 314.388 + endloop + endfacet + facet normal 0.355422 -0.910168 0.212765 + outer loop + vertex 687.206 126.303 314.84 + vertex 688.981 126.8 314 + vertex 691.957 128.121 314.68 + endloop + endfacet + facet normal 0.370817 -0.91554 0.155826 + outer loop + vertex 691.957 128.121 314.68 + vertex 688.981 126.8 314 + vertex 693.027 128.418 313.876 + endloop + endfacet + facet normal 0.358907 -0.890102 0.280898 + outer loop + vertex 686.718 126.387 315.729 + vertex 687.206 126.303 314.84 + vertex 691.022 128.163 315.859 + endloop + endfacet + facet normal 0.348954 -0.884867 0.308614 + outer loop + vertex 691.022 128.163 315.859 + vertex 687.206 126.303 314.84 + vertex 691.957 128.121 314.68 + endloop + endfacet + facet normal 0.341941 -0.922962 0.176687 + outer loop + vertex 688.981 126.8 314 + vertex 687.206 126.303 314.84 + vertex 681.807 124.052 313.53 + endloop + endfacet + facet normal 0.328749 -0.90622 0.265876 + outer loop + vertex 686.718 126.387 315.729 + vertex 680.363 123.944 315.258 + vertex 687.206 126.303 314.84 + endloop + endfacet + facet normal 0.330038 -0.918449 0.218007 + outer loop + vertex 680.363 123.944 315.258 + vertex 681.807 124.052 313.53 + vertex 687.206 126.303 314.84 + endloop + endfacet + facet normal 0.32518 -0.913581 0.244189 + outer loop + vertex 671.751 120.909 315.372 + vertex 671.345 120.209 313.294 + vertex 680.363 123.944 315.258 + endloop + endfacet + facet normal 0.332045 -0.917308 0.219756 + outer loop + vertex 680.363 123.944 315.258 + vertex 671.345 120.209 313.294 + vertex 681.807 124.052 313.53 + endloop + endfacet + facet normal 0.317215 -0.921169 0.225439 + outer loop + vertex 660.561 116.762 314.528 + vertex 662.69 117.081 312.834 + vertex 664.987 118.252 314.388 + endloop + endfacet + facet normal 0.322922 -0.921205 0.21703 + outer loop + vertex 664.987 118.252 314.388 + vertex 662.69 117.081 312.834 + vertex 665.209 117.878 312.469 + endloop + endfacet + facet normal 0.369396 -0.925997 -0.07795 + outer loop + vertex 693.755 128.69 312.341 + vertex 693.11 128.392 312.818 + vertex 688.808 126.737 312.104 + endloop + endfacet + facet normal 0.368221 -0.929488 -0.0215593 + outer loop + vertex 693.16 128.401 313.293 + vertex 688.902 126.719 313.108 + vertex 693.11 128.392 312.818 + endloop + endfacet + facet normal 0.3661 -0.929193 -0.050711 + outer loop + vertex 688.902 126.719 313.108 + vertex 688.808 126.737 312.104 + vertex 693.11 128.392 312.818 + endloop + endfacet + facet normal 0.372102 -0.926758 0.0515811 + outer loop + vertex 688.981 126.8 314 + vertex 688.902 126.719 313.108 + vertex 693.027 128.418 313.876 + endloop + endfacet + facet normal 0.361243 -0.926136 0.108515 + outer loop + vertex 693.027 128.418 313.876 + vertex 688.902 126.719 313.108 + vertex 693.16 128.401 313.293 + endloop + endfacet + facet normal 0.381373 -0.922498 -0.0596025 + outer loop + vertex 693.11 128.392 312.818 + vertex 693.755 128.69 312.341 + vertex 695.776 129.503 312.684 + endloop + endfacet + facet normal 0.386594 -0.916238 -0.105132 + outer loop + vertex 695.776 129.503 312.684 + vertex 693.755 128.69 312.341 + vertex 695.831 129.577 312.239 + endloop + endfacet + facet normal 0.399709 -0.916297 -0.0251562 + outer loop + vertex 693.16 128.401 313.293 + vertex 693.11 128.392 312.818 + vertex 695.449 129.398 313.352 + endloop + endfacet + facet normal 0.38613 -0.921394 0.0440046 + outer loop + vertex 695.449 129.398 313.352 + vertex 693.11 128.392 312.818 + vertex 695.776 129.503 312.684 + endloop + endfacet + facet normal 0.367525 -0.928624 -0.0508337 + outer loop + vertex 688.808 126.737 312.104 + vertex 688.902 126.719 313.108 + vertex 681.85 123.976 312.215 + endloop + endfacet + facet normal 0.354089 -0.933663 0.0537934 + outer loop + vertex 688.981 126.8 314 + vertex 681.807 124.052 313.53 + vertex 688.902 126.719 313.108 + endloop + endfacet + facet normal 0.354448 -0.932792 0.0653067 + outer loop + vertex 681.807 124.052 313.53 + vertex 681.85 123.976 312.215 + vertex 688.902 126.719 313.108 + endloop + endfacet + facet normal 0.337619 -0.929283 0.149823 + outer loop + vertex 669.762 119.393 311.803 + vertex 674.799 121.281 312.163 + vertex 671.345 120.209 313.294 + endloop + endfacet + facet normal 0.355883 -0.932245 0.065321 + outer loop + vertex 681.85 123.976 312.215 + vertex 681.807 124.052 313.53 + vertex 674.799 121.281 312.163 + endloop + endfacet + facet normal 0.337896 -0.929002 0.150935 + outer loop + vertex 681.807 124.052 313.53 + vertex 671.345 120.209 313.294 + vertex 674.799 121.281 312.163 + endloop + endfacet + facet normal 0.312259 -0.945743 0.0898026 + outer loop + vertex 662.69 117.081 312.834 + vertex 664.419 117.527 311.525 + vertex 665.209 117.878 312.469 + endloop + endfacet + facet normal 0.260496 -0.955734 0.136798 + outer loop + vertex 665.209 117.878 312.469 + vertex 664.419 117.527 311.525 + vertex 665.013 117.695 311.563 + endloop + endfacet + facet normal 0.371617 -0.900279 -0.226713 + outer loop + vertex 692.874 128.591 311.159 + vertex 692.98 128.473 311.8 + vertex 688.116 126.603 311.255 + endloop + endfacet + facet normal 0.369116 -0.914976 -0.163011 + outer loop + vertex 693.755 128.69 312.341 + vertex 688.808 126.737 312.104 + vertex 692.98 128.473 311.8 + endloop + endfacet + facet normal 0.369777 -0.915638 -0.157706 + outer loop + vertex 688.808 126.737 312.104 + vertex 688.116 126.603 311.255 + vertex 692.98 128.473 311.8 + endloop + endfacet + facet normal 0.378999 -0.897038 -0.227338 + outer loop + vertex 692.98 128.473 311.8 + vertex 692.874 128.591 311.159 + vertex 696.132 129.835 311.683 + endloop + endfacet + facet normal 0.380723 -0.886393 -0.263358 + outer loop + vertex 696.132 129.835 311.683 + vertex 692.874 128.591 311.159 + vertex 695.916 129.975 310.9 + endloop + endfacet + facet normal 0.379188 -0.907557 -0.180434 + outer loop + vertex 693.755 128.69 312.341 + vertex 692.98 128.473 311.8 + vertex 695.831 129.577 312.239 + endloop + endfacet + facet normal 0.381008 -0.900252 -0.210664 + outer loop + vertex 695.831 129.577 312.239 + vertex 692.98 128.473 311.8 + vertex 696.132 129.835 311.683 + endloop + endfacet + facet normal 0.34944 -0.936676 0.023013 + outer loop + vertex 669.762 119.393 311.803 + vertex 671.142 119.892 311.152 + vertex 674.799 121.281 312.163 + endloop + endfacet + facet normal 0.356187 -0.934404 -0.0045169 + outer loop + vertex 674.799 121.281 312.163 + vertex 671.142 119.892 311.152 + vertex 676.174 121.809 311.294 + endloop + endfacet + facet normal 0.357085 -0.934067 -0.00289071 + outer loop + vertex 674.799 121.281 312.163 + vertex 676.174 121.809 311.294 + vertex 681.85 123.976 312.215 + endloop + endfacet + facet normal 0.366779 -0.926906 -0.0794949 + outer loop + vertex 681.85 123.976 312.215 + vertex 676.174 121.809 311.294 + vertex 682.252 124.212 311.321 + endloop + endfacet + facet normal 0.341387 -0.939723 -0.0193698 + outer loop + vertex 665.013 117.695 311.563 + vertex 665.859 118.016 310.908 + vertex 666.881 118.37 311.755 + endloop + endfacet + facet normal 0.322683 -0.946488 0.00603072 + outer loop + vertex 666.881 118.37 311.755 + vertex 665.859 118.016 310.908 + vertex 667.788 118.674 311 + endloop + endfacet + facet normal 0.334455 -0.942157 0.0219006 + outer loop + vertex 666.881 118.37 311.755 + vertex 667.788 118.674 311 + vertex 669.762 119.393 311.803 + endloop + endfacet + facet normal 0.341272 -0.939959 0.00318845 + outer loop + vertex 669.762 119.393 311.803 + vertex 667.788 118.674 311 + vertex 671.142 119.892 311.152 + endloop + endfacet + facet normal 0.374618 -0.908119 -0.187031 + outer loop + vertex 688.599 126.95 310.664 + vertex 682.892 124.586 310.709 + vertex 683.628 124.957 310.381 + endloop + endfacet + facet normal 0.385484 -0.854229 0.348848 + outer loop + vertex 696.059 129.983 314.748 + vertex 693.621 130.227 318.04 + vertex 691.022 128.163 315.859 + endloop + endfacet + facet normal 0.472121 -0.867422 0.157101 + outer loop + vertex 697.525 130.378 312.526 + vertex 696.059 129.983 314.748 + vertex 695.449 129.398 313.352 + endloop + endfacet + facet normal 0.436033 -0.887658 -0.148119 + outer loop + vertex 697.764 130.708 311.254 + vertex 697.525 130.378 312.526 + vertex 696.132 129.835 311.683 + endloop + endfacet + facet normal 0.31202 -0.945928 -0.0886799 + outer loop + vertex 663.748 117.3 311.586 + vertex 666.065 118.181 310.343 + vertex 664.419 117.527 311.525 + endloop + endfacet + facet normal 0.367345 -0.917917 0.149955 + outer loop + vertex 662.147 116.804 312.468 + vertex 663.748 117.3 311.586 + vertex 662.69 117.081 312.834 + endloop + endfacet + facet normal 0.325685 -0.920932 0.214043 + outer loop + vertex 660.512 116.489 313.603 + vertex 662.147 116.804 312.468 + vertex 662.69 117.081 312.834 + endloop + endfacet + facet normal 0.287551 -0.922644 0.256986 + outer loop + vertex 658.632 116.314 315.078 + vertex 660.512 116.489 313.603 + vertex 660.561 116.762 314.528 + endloop + endfacet + facet normal 0.254193 -0.917025 0.307329 + outer loop + vertex 657.28 116.42 316.512 + vertex 658.632 116.314 315.078 + vertex 658.715 116.644 315.992 + endloop + endfacet + facet normal 0.382619 -0.916986 -0.112873 + outer loop + vertex 684.582 125.364 310.224 + vertex 687.17 126.44 310.253 + vertex 684.812 125.453 310.282 + endloop + endfacet + facet normal 0.382849 -0.916728 -0.114178 + outer loop + vertex 682.029 124.295 310.244 + vertex 684.582 125.364 310.224 + vertex 684.812 125.453 310.282 + endloop + endfacet + facet normal 0.355571 -0.869582 0.342633 + outer loop + vertex 680.115 123.511 310.239 + vertex 682.029 124.295 310.244 + vertex 680.169 123.545 310.269 + endloop + endfacet + facet normal 0.343178 -0.866939 0.36145 + outer loop + vertex 677.796 122.588 310.226 + vertex 680.115 123.511 310.239 + vertex 680.169 123.545 310.269 + endloop + endfacet + facet normal 0.315732 -0.790104 0.525404 + outer loop + vertex 675.453 121.653 310.229 + vertex 677.796 122.588 310.226 + vertex 675.79 121.8 310.247 + endloop + endfacet + facet normal 0.239112 -0.639215 0.73091 + outer loop + vertex 673.98 121.088 310.217 + vertex 675.453 121.653 310.229 + vertex 675.79 121.8 310.247 + endloop + endfacet + facet normal 0.338617 -0.849911 0.40372 + outer loop + vertex 686.392 126.834 316.942 + vertex 686.718 126.387 315.729 + vertex 691.022 128.163 315.859 + endloop + endfacet + facet normal 0.306777 -0.897961 0.315523 + outer loop + vertex 671.751 120.909 315.372 + vertex 667.384 119.934 316.845 + vertex 664.987 118.252 314.388 + endloop + endfacet + facet normal 0.296115 -0.906863 0.29986 + outer loop + vertex 660.561 116.762 314.528 + vertex 658.715 116.644 315.992 + vertex 658.632 116.314 315.078 + endloop + endfacet + facet normal 0.317297 -0.897873 0.305198 + outer loop + vertex 661.551 117.512 315.784 + vertex 664.987 118.252 314.388 + vertex 667.384 119.934 316.845 + endloop + endfacet + facet normal 0.40167 -0.892459 0.205375 + outer loop + vertex 691.957 128.121 314.68 + vertex 693.027 128.418 313.876 + vertex 696.059 129.983 314.748 + endloop + endfacet + facet normal 0.384646 -0.859716 0.336058 + outer loop + vertex 691.022 128.163 315.859 + vertex 691.957 128.121 314.68 + vertex 696.059 129.983 314.748 + endloop + endfacet + facet normal 0.323406 -0.914073 0.244702 + outer loop + vertex 671.345 120.209 313.294 + vertex 671.751 120.909 315.372 + vertex 664.987 118.252 314.388 + endloop + endfacet + facet normal 0.335051 -0.90835 0.25028 + outer loop + vertex 662.69 117.081 312.834 + vertex 660.561 116.762 314.528 + vertex 660.512 116.489 313.603 + endloop + endfacet + facet normal 0.321033 -0.921885 0.216945 + outer loop + vertex 664.987 118.252 314.388 + vertex 665.209 117.878 312.469 + vertex 671.345 120.209 313.294 + endloop + endfacet + facet normal 0.394102 -0.911769 0.115587 + outer loop + vertex 693.027 128.418 313.876 + vertex 693.16 128.401 313.293 + vertex 695.449 129.398 313.352 + endloop + endfacet + facet normal 0.438636 -0.893636 -0.0949355 + outer loop + vertex 695.776 129.503 312.684 + vertex 695.831 129.577 312.239 + vertex 697.525 130.378 312.526 + endloop + endfacet + facet normal 0.45191 -0.888339 0.0814342 + outer loop + vertex 695.449 129.398 313.352 + vertex 695.776 129.503 312.684 + vertex 697.525 130.378 312.526 + endloop + endfacet + facet normal 0.36643 -0.927027 -0.0796837 + outer loop + vertex 688.808 126.737 312.104 + vertex 681.85 123.976 312.215 + vertex 682.252 124.212 311.321 + endloop + endfacet + facet normal 0.328108 -0.930856 0.160785 + outer loop + vertex 669.762 119.393 311.803 + vertex 671.345 120.209 313.294 + vertex 666.881 118.37 311.755 + endloop + endfacet + facet normal 0.327716 -0.938013 0.112845 + outer loop + vertex 664.419 117.527 311.525 + vertex 662.69 117.081 312.834 + vertex 663.748 117.3 311.586 + endloop + endfacet + facet normal 0.326459 -0.937704 0.118889 + outer loop + vertex 665.209 117.878 312.469 + vertex 665.013 117.695 311.563 + vertex 666.881 118.37 311.755 + endloop + endfacet + facet normal 0.2762 -0.954671 -0.110982 + outer loop + vertex 665.013 117.695 311.563 + vertex 664.419 117.527 311.525 + vertex 665.859 118.016 310.908 + endloop + endfacet + facet normal 0.371209 -0.914835 -0.158998 + outer loop + vertex 688.116 126.603 311.255 + vertex 688.808 126.737 312.104 + vertex 682.252 124.212 311.321 + endloop + endfacet + facet normal 0.39918 -0.877191 -0.266815 + outer loop + vertex 696.132 129.835 311.683 + vertex 695.916 129.975 310.9 + vertex 697.764 130.708 311.254 + endloop + endfacet + facet normal 0.444454 -0.88012 -0.166881 + outer loop + vertex 695.831 129.577 312.239 + vertex 696.132 129.835 311.683 + vertex 697.525 130.378 312.526 + endloop + endfacet + facet normal 0.378616 -0.897616 -0.225689 + outer loop + vertex 692.667 128.728 310.387 + vertex 689.317 127.331 310.321 + vertex 691.998 128.467 310.3 + endloop + endfacet + facet normal 0.349412 -0.852777 0.388178 + outer loop + vertex 684.812 125.453 310.282 + vertex 680.169 123.545 310.269 + vertex 682.029 124.295 310.244 + endloop + endfacet + facet normal 0.384103 -0.919632 -0.0821071 + outer loop + vertex 689.317 127.331 310.321 + vertex 684.812 125.453 310.282 + vertex 687.17 126.44 310.253 + endloop + endfacet + facet normal 0.178157 -0.489325 0.85371 + outer loop + vertex 675.79 121.8 310.247 + vertex 672.428 120.508 310.208 + vertex 673.98 121.088 310.217 + endloop + endfacet + facet normal 0.347749 -0.87692 0.331786 + outer loop + vertex 680.169 123.545 310.269 + vertex 675.79 121.8 310.247 + vertex 677.796 122.588 310.226 + endloop + endfacet + facet normal 0.338444 -0.850909 0.401757 + outer loop + vertex 691.022 128.163 315.859 + vertex 693.621 130.227 318.04 + vertex 686.392 126.834 316.942 + endloop + endfacet + facet normal 0.404259 -0.893072 0.197479 + outer loop + vertex 695.449 129.398 313.352 + vertex 696.059 129.983 314.748 + vertex 693.027 128.418 313.876 + endloop + endfacet + facet normal 0.241072 -0.9516 -0.190636 + outer loop + vertex 664.419 117.527 311.525 + vertex 666.065 118.181 310.343 + vertex 665.859 118.016 310.908 + endloop + endfacet + facet normal 0.336704 -0.917751 -0.210627 + outer loop + vertex 667.999 118.855 310.253 + vertex 669.505 119.439 310.115 + vertex 670.639 119.819 310.273 + endloop + endfacet + facet normal 0.334695 -0.931498 0.142446 + outer loop + vertex 671.345 120.209 313.294 + vertex 665.209 117.878 312.469 + vertex 666.881 118.37 311.755 + endloop + endfacet + facet normal 0.33744 -0.919998 -0.199344 + outer loop + vertex 669.156 119.22 310.529 + vertex 667.999 118.855 310.253 + vertex 670.639 119.819 310.273 + endloop + endfacet + facet normal 0.404257 -0.574445 -0.71175 + outer loop + vertex 691.443 138.165 299.551 + vertex 687.323 135.989 298.967 + vertex 690.918 139.776 297.952 + endloop + endfacet + facet normal 0.472995 -0.617396 -0.628568 + outer loop + vertex 690.918 139.776 297.952 + vertex 687.323 135.989 298.967 + vertex 686.304 136.758 297.445 + endloop + endfacet + facet normal 0.377955 -0.60251 -0.702945 + outer loop + vertex 692.21 136.595 301.309 + vertex 688.245 134.738 300.769 + vertex 691.443 138.165 299.551 + endloop + endfacet + facet normal 0.424026 -0.62768 -0.652855 + outer loop + vertex 691.443 138.165 299.551 + vertex 688.245 134.738 300.769 + vertex 687.323 135.989 298.967 + endloop + endfacet + facet normal 0.353137 -0.625502 -0.695731 + outer loop + vertex 693.179 134.982 303.251 + vertex 689.248 133.336 302.736 + vertex 692.21 136.595 301.309 + endloop + endfacet + facet normal 0.391033 -0.643458 -0.658069 + outer loop + vertex 692.21 136.595 301.309 + vertex 689.248 133.336 302.736 + vertex 688.245 134.738 300.769 + endloop + endfacet + facet normal 0.335426 -0.653071 -0.678961 + outer loop + vertex 694.345 133.496 305.257 + vertex 690.422 132.008 304.749 + vertex 693.179 134.982 303.251 + endloop + endfacet + facet normal 0.364165 -0.665768 -0.651258 + outer loop + vertex 693.179 134.982 303.251 + vertex 690.422 132.008 304.749 + vertex 689.248 133.336 302.736 + endloop + endfacet + facet normal 0.330931 -0.690218 -0.643494 + outer loop + vertex 695.612 132.348 307.139 + vertex 691.919 131.035 306.649 + vertex 694.345 133.496 305.257 + endloop + endfacet + facet normal 0.345388 -0.696344 -0.629136 + outer loop + vertex 694.345 133.496 305.257 + vertex 691.919 131.035 306.649 + vertex 690.422 132.008 304.749 + endloop + endfacet + facet normal 0.338311 -0.731493 -0.592 + outer loop + vertex 696.426 131.537 308.607 + vertex 693.591 130.513 308.252 + vertex 695.612 132.348 307.139 + endloop + endfacet + facet normal 0.338779 -0.731694 -0.591483 + outer loop + vertex 695.612 132.348 307.139 + vertex 693.591 130.513 308.252 + vertex 691.919 131.035 306.649 + endloop + endfacet + facet normal 0.429069 -0.657453 -0.619399 + outer loop + vertex 687.323 135.989 298.967 + vertex 681.317 132.451 298.562 + vertex 686.304 136.758 297.445 + endloop + endfacet + facet normal 0.482332 -0.69631 -0.531514 + outer loop + vertex 686.304 136.758 297.445 + vertex 681.317 132.451 298.562 + vertex 679.818 132.687 296.892 + endloop + endfacet + facet normal 0.391776 -0.64959 -0.651571 + outer loop + vertex 688.245 134.738 300.769 + vertex 682.526 131.625 300.434 + vertex 687.323 135.989 298.967 + endloop + endfacet + facet normal 0.440553 -0.680865 -0.585094 + outer loop + vertex 687.323 135.989 298.967 + vertex 682.526 131.625 300.434 + vertex 681.317 132.451 298.562 + endloop + endfacet + facet normal 0.366101 -0.659341 -0.656688 + outer loop + vertex 689.248 133.336 302.736 + vertex 683.672 130.517 302.458 + vertex 688.245 134.738 300.769 + endloop + endfacet + facet normal 0.407658 -0.683773 -0.605202 + outer loop + vertex 688.245 134.738 300.769 + vertex 683.672 130.517 302.458 + vertex 682.526 131.625 300.434 + endloop + endfacet + facet normal 0.346908 -0.677293 -0.64879 + outer loop + vertex 690.422 132.008 304.749 + vertex 684.916 129.431 304.496 + vertex 689.248 133.336 302.736 + endloop + endfacet + facet normal 0.382951 -0.697729 -0.605411 + outer loop + vertex 689.248 133.336 302.736 + vertex 684.916 129.431 304.496 + vertex 683.672 130.517 302.458 + endloop + endfacet + facet normal 0.334343 -0.705357 -0.625049 + outer loop + vertex 691.919 131.035 306.649 + vertex 686.39 128.598 306.441 + vertex 690.422 132.008 304.749 + endloop + endfacet + facet normal 0.36539 -0.722901 -0.586433 + outer loop + vertex 690.422 132.008 304.749 + vertex 686.39 128.598 306.441 + vertex 684.916 129.431 304.496 + endloop + endfacet + facet normal 0.332901 -0.737724 -0.587315 + outer loop + vertex 693.591 130.513 308.252 + vertex 688.466 128.327 308.092 + vertex 691.919 131.035 306.649 + endloop + endfacet + facet normal 0.350772 -0.747878 -0.563594 + outer loop + vertex 691.919 131.035 306.649 + vertex 688.466 128.327 308.092 + vertex 686.39 128.598 306.441 + endloop + endfacet + facet normal 0.444069 -0.741149 -0.503489 + outer loop + vertex 681.317 132.451 298.562 + vertex 674.237 128.341 298.367 + vertex 679.818 132.687 296.892 + endloop + endfacet + facet normal 0.474685 -0.760158 -0.44366 + outer loop + vertex 679.818 132.687 296.892 + vertex 674.237 128.341 298.367 + vertex 672.387 128.159 296.7 + endloop + endfacet + facet normal 0.403617 -0.71176 -0.574884 + outer loop + vertex 682.526 131.625 300.434 + vertex 675.672 127.847 300.299 + vertex 681.317 132.451 298.562 + endloop + endfacet + facet normal 0.440762 -0.734884 -0.515435 + outer loop + vertex 681.317 132.451 298.562 + vertex 675.672 127.847 300.299 + vertex 674.237 128.341 298.367 + endloop + endfacet + facet normal 0.376146 -0.706317 -0.599692 + outer loop + vertex 683.672 130.517 302.458 + vertex 677.04 127.053 302.378 + vertex 682.526 131.625 300.434 + endloop + endfacet + facet normal 0.41175 -0.727442 -0.548898 + outer loop + vertex 682.526 131.625 300.434 + vertex 677.04 127.053 302.378 + vertex 675.672 127.847 300.299 + endloop + endfacet + facet normal 0.357969 -0.715669 -0.59973 + outer loop + vertex 684.916 129.431 304.496 + vertex 678.489 126.27 304.432 + vertex 683.672 130.517 302.458 + endloop + endfacet + facet normal 0.390295 -0.734434 -0.555227 + outer loop + vertex 683.672 130.517 302.458 + vertex 678.489 126.27 304.432 + vertex 677.04 127.053 302.378 + endloop + endfacet + facet normal 0.348558 -0.736627 -0.579559 + outer loop + vertex 686.39 128.598 306.441 + vertex 679.993 125.636 306.358 + vertex 684.916 129.431 304.496 + endloop + endfacet + facet normal 0.375573 -0.75265 -0.540799 + outer loop + vertex 684.916 129.431 304.496 + vertex 679.993 125.636 306.358 + vertex 678.489 126.27 304.432 + endloop + endfacet + facet normal 0.337978 -0.763657 -0.55009 + outer loop + vertex 688.466 128.327 308.092 + vertex 681.38 125.106 308.211 + vertex 686.39 128.598 306.441 + endloop + endfacet + facet normal 0.36906 -0.783126 -0.500508 + outer loop + vertex 686.39 128.598 306.441 + vertex 681.38 125.106 308.211 + vertex 679.993 125.636 306.358 + endloop + endfacet + facet normal 0.441218 -0.80236 -0.401927 + outer loop + vertex 674.237 128.341 298.367 + vertex 667.251 124.461 298.444 + vertex 672.387 128.159 296.7 + endloop + endfacet + facet normal 0.442492 -0.802929 -0.399382 + outer loop + vertex 672.387 128.159 296.7 + vertex 667.251 124.461 298.444 + vertex 665.459 124.286 296.809 + endloop + endfacet + facet normal 0.404318 -0.767926 -0.496806 + outer loop + vertex 675.672 127.847 300.299 + vertex 668.751 124.138 300.4 + vertex 674.237 128.341 298.367 + endloop + endfacet + facet normal 0.428007 -0.779653 -0.457111 + outer loop + vertex 674.237 128.341 298.367 + vertex 668.751 124.138 300.4 + vertex 667.251 124.461 298.444 + endloop + endfacet + facet normal 0.376573 -0.75529 -0.536404 + outer loop + vertex 677.04 127.053 302.378 + vertex 670.283 123.586 302.515 + vertex 675.672 127.847 300.299 + endloop + endfacet + facet normal 0.405109 -0.769324 -0.493991 + outer loop + vertex 675.672 127.847 300.299 + vertex 670.283 123.586 302.515 + vertex 668.751 124.138 300.4 + endloop + endfacet + facet normal 0.358901 -0.759451 -0.542609 + outer loop + vertex 678.489 126.27 304.432 + vertex 671.972 123.069 304.602 + vertex 677.04 127.053 302.378 + endloop + endfacet + facet normal 0.386072 -0.772528 -0.504132 + outer loop + vertex 677.04 127.053 302.378 + vertex 671.972 123.069 304.602 + vertex 670.283 123.586 302.515 + endloop + endfacet + facet normal 0.350864 -0.77319 -0.528272 + outer loop + vertex 679.993 125.636 306.358 + vertex 673.819 122.784 306.431 + vertex 678.489 126.27 304.432 + endloop + endfacet + facet normal 0.372034 -0.783776 -0.497279 + outer loop + vertex 678.489 126.27 304.432 + vertex 673.819 122.784 306.431 + vertex 671.972 123.069 304.602 + endloop + endfacet + facet normal 0.352685 -0.796003 -0.491928 + outer loop + vertex 681.38 125.106 308.211 + vertex 675.401 122.606 307.97 + vertex 679.993 125.636 306.358 + endloop + endfacet + facet normal 0.36565 -0.803693 -0.469444 + outer loop + vertex 679.993 125.636 306.358 + vertex 675.401 122.606 307.97 + vertex 673.819 122.784 306.431 + endloop + endfacet + facet normal 0.41895 -0.828852 -0.37079 + outer loop + vertex 667.251 124.461 298.444 + vertex 661.352 121.372 298.683 + vertex 665.459 124.286 296.809 + endloop + endfacet + facet normal 0.410786 -0.826468 -0.384974 + outer loop + vertex 665.459 124.286 296.809 + vertex 661.352 121.372 298.683 + vertex 659.505 121.159 297.171 + endloop + endfacet + facet normal 0.396008 -0.807501 -0.437173 + outer loop + vertex 668.751 124.138 300.4 + vertex 662.802 121.091 300.639 + vertex 667.251 124.461 298.444 + endloop + endfacet + facet normal 0.407764 -0.811235 -0.419077 + outer loop + vertex 667.251 124.461 298.444 + vertex 662.802 121.091 300.639 + vertex 661.352 121.372 298.683 + endloop + endfacet + facet normal 0.371472 -0.796681 -0.476769 + outer loop + vertex 670.283 123.586 302.515 + vertex 664.425 120.696 302.781 + vertex 668.751 124.138 300.4 + endloop + endfacet + facet normal 0.393616 -0.803562 -0.446491 + outer loop + vertex 668.751 124.138 300.4 + vertex 664.425 120.696 302.781 + vertex 662.802 121.091 300.639 + endloop + endfacet + facet normal 0.352816 -0.800674 -0.484193 + outer loop + vertex 671.972 123.069 304.602 + vertex 666.323 120.39 304.915 + vertex 670.283 123.586 302.515 + endloop + endfacet + facet normal 0.378124 -0.807887 -0.452041 + outer loop + vertex 670.283 123.586 302.515 + vertex 666.323 120.39 304.915 + vertex 664.425 120.696 302.781 + endloop + endfacet + facet normal 0.340262 -0.814456 -0.469981 + outer loop + vertex 673.819 122.784 306.431 + vertex 668.242 120.165 306.932 + vertex 671.972 123.069 304.602 + endloop + endfacet + facet normal 0.365057 -0.821168 -0.438654 + outer loop + vertex 671.972 123.069 304.602 + vertex 668.242 120.165 306.932 + vertex 666.323 120.39 304.915 + endloop + endfacet + facet normal 0.34341 -0.824888 -0.449032 + outer loop + vertex 675.401 122.606 307.97 + vertex 670.724 120.599 308.08 + vertex 673.819 122.784 306.431 + endloop + endfacet + facet normal 0.348526 -0.826658 -0.441776 + outer loop + vertex 668.242 120.165 306.932 + vertex 673.819 122.784 306.431 + vertex 670.724 120.599 308.08 + endloop + endfacet + facet normal 0.354328 -0.913697 -0.199022 + outer loop + vertex 675.374 121.664 310.094 + vertex 671.939 120.339 310.058 + vertex 673.289 120.925 309.773 + endloop + endfacet + facet normal 0.391362 -0.7598 -0.519172 + outer loop + vertex 697.556 132.513 308.03 + vertex 697.212 131.012 309.968 + vertex 696.426 131.537 308.607 + endloop + endfacet + facet normal 0.348423 -0.691938 -0.632316 + outer loop + vertex 696.825 133.892 306.118 + vertex 697.556 132.513 308.03 + vertex 695.612 132.348 307.139 + endloop + endfacet + facet normal 0.340443 -0.646641 -0.682609 + outer loop + vertex 695.457 135.352 304.053 + vertex 696.825 133.892 306.118 + vertex 694.345 133.496 305.257 + endloop + endfacet + facet normal 0.350189 -0.603143 -0.716649 + outer loop + vertex 694.688 137.195 302.126 + vertex 695.457 135.352 304.053 + vertex 693.179 134.982 303.251 + endloop + endfacet + facet normal 0.378284 -0.580113 -0.721367 + outer loop + vertex 693.724 138.801 300.329 + vertex 694.688 137.195 302.126 + vertex 692.21 136.595 301.309 + endloop + endfacet + facet normal 0.402549 -0.53589 -0.742143 + outer loop + vertex 693.508 140.577 298.93 + vertex 693.724 138.801 300.329 + vertex 691.443 138.165 299.551 + endloop + endfacet + facet normal 0.436636 -0.498774 -0.748714 + outer loop + vertex 693.645 143.512 297.054 + vertex 693.508 140.577 298.93 + vertex 690.918 139.776 297.952 + endloop + endfacet + facet normal 0.541106 -0.548355 -0.637583 + outer loop + vertex 691.69 141.52 297.108 + vertex 693.645 143.512 297.054 + vertex 690.918 139.776 297.952 + endloop + endfacet + facet normal 0.48469 -0.545654 -0.68362 + outer loop + vertex 689.447 139.619 297.035 + vertex 691.69 141.52 297.108 + vertex 690.918 139.776 297.952 + endloop + endfacet + facet normal 0.526197 -0.655685 -0.541474 + outer loop + vertex 687.292 138.085 296.799 + vertex 689.447 139.619 297.035 + vertex 686.304 136.758 297.445 + endloop + endfacet + facet normal 0.490036 -0.648644 -0.582346 + outer loop + vertex 684.343 136.105 296.522 + vertex 687.292 138.085 296.799 + vertex 686.304 136.758 297.445 + endloop + endfacet + facet normal 0.535682 -0.750984 -0.386094 + outer loop + vertex 681.623 134.299 296.262 + vertex 684.343 136.105 296.522 + vertex 679.818 132.687 296.892 + endloop + endfacet + facet normal 0.505497 -0.739816 -0.44401 + outer loop + vertex 679.381 132.885 296.065 + vertex 681.623 134.299 296.262 + vertex 679.818 132.687 296.892 + endloop + endfacet + facet normal 0.495197 -0.748704 -0.440706 + outer loop + vertex 676.476 130.919 296.141 + vertex 679.381 132.885 296.065 + vertex 679.818 132.687 296.892 + endloop + endfacet + facet normal 0.497962 -0.803707 -0.325712 + outer loop + vertex 673.588 129.226 295.904 + vertex 676.476 130.919 296.141 + vertex 672.387 128.159 296.7 + endloop + endfacet + facet normal 0.499682 -0.803694 -0.3231 + outer loop + vertex 671.666 128 295.979 + vertex 673.588 129.226 295.904 + vertex 672.387 128.159 296.7 + endloop + endfacet + facet normal 0.471243 -0.833651 -0.28802 + outer loop + vertex 669.551 126.763 296.102 + vertex 671.666 128 295.979 + vertex 672.387 128.159 296.7 + endloop + endfacet + facet normal 0.449387 -0.834111 -0.31986 + outer loop + vertex 667.043 125.463 295.966 + vertex 669.551 126.763 296.102 + vertex 665.459 124.286 296.809 + endloop + endfacet + facet normal 0.446541 -0.833762 -0.324718 + outer loop + vertex 664.81 124.214 296.103 + vertex 667.043 125.463 295.966 + vertex 665.459 124.286 296.809 + endloop + endfacet + facet normal 0.424022 -0.853822 -0.301982 + outer loop + vertex 661.876 122.7 296.263 + vertex 664.81 124.214 296.103 + vertex 665.459 124.286 296.809 + endloop + endfacet + facet normal 0.411753 -0.840563 -0.352014 + outer loop + vertex 659.104 121.281 296.412 + vertex 661.876 122.7 296.263 + vertex 659.505 121.159 297.171 + endloop + endfacet + facet normal 0.397576 -0.849822 -0.346029 + outer loop + vertex 657.314 120.364 296.605 + vertex 659.104 121.281 296.412 + vertex 659.505 121.159 297.171 + endloop + endfacet + facet normal 0.373162 -0.845188 -0.382633 + outer loop + vertex 654.963 119.339 296.576 + vertex 657.314 120.364 296.605 + vertex 655.568 119.244 297.376 + endloop + endfacet + facet normal 0.342477 -0.933111 -0.109609 + outer loop + vertex 672.372 120.484 310.18 + vertex 669.505 119.439 310.115 + vertex 671.939 120.339 310.058 + endloop + endfacet + facet normal 0.342521 -0.89302 -0.291881 + outer loop + vertex 673.98 121.088 310.217 + vertex 672.372 120.484 310.18 + vertex 675.374 121.664 310.094 + endloop + endfacet + facet normal 0.346691 -0.898365 -0.269713 + outer loop + vertex 675.453 121.653 310.229 + vertex 673.98 121.088 310.217 + vertex 675.374 121.664 310.094 + endloop + endfacet + facet normal 0.355728 -0.893335 -0.274609 + outer loop + vertex 677.796 122.588 310.226 + vertex 675.453 121.653 310.229 + vertex 675.374 121.664 310.094 + endloop + endfacet + facet normal 0.331873 -0.827286 -0.453275 + outer loop + vertex 680.115 123.511 310.239 + vertex 677.796 122.588 310.226 + vertex 681.33 124.09 310.071 + endloop + endfacet + facet normal 0.3483 -0.846838 -0.401936 + outer loop + vertex 682.029 124.295 310.244 + vertex 680.115 123.511 310.239 + vertex 681.33 124.09 310.071 + endloop + endfacet + facet normal 0.349193 -0.84194 -0.411342 + outer loop + vertex 684.582 125.364 310.224 + vertex 682.029 124.295 310.244 + vertex 681.33 124.09 310.071 + endloop + endfacet + facet normal 0.438294 -0.557048 -0.705405 + outer loop + vertex 691.443 138.165 299.551 + vertex 690.918 139.776 297.952 + vertex 693.508 140.577 298.93 + endloop + endfacet + facet normal 0.466842 -0.605268 -0.644755 + outer loop + vertex 690.918 139.776 297.952 + vertex 686.304 136.758 297.445 + vertex 689.447 139.619 297.035 + endloop + endfacet + facet normal 0.403119 -0.588163 -0.701113 + outer loop + vertex 692.21 136.595 301.309 + vertex 691.443 138.165 299.551 + vertex 693.724 138.801 300.329 + endloop + endfacet + facet normal 0.377356 -0.61108 -0.695833 + outer loop + vertex 693.179 134.982 303.251 + vertex 692.21 136.595 301.309 + vertex 694.688 137.195 302.126 + endloop + endfacet + facet normal 0.344451 -0.647318 -0.67995 + outer loop + vertex 694.345 133.496 305.257 + vertex 693.179 134.982 303.251 + vertex 695.457 135.352 304.053 + endloop + endfacet + facet normal 0.333734 -0.688234 -0.64417 + outer loop + vertex 695.612 132.348 307.139 + vertex 694.345 133.496 305.257 + vertex 696.825 133.892 306.118 + endloop + endfacet + facet normal 0.343893 -0.761993 -0.548729 + outer loop + vertex 693.591 130.513 308.252 + vertex 696.426 131.537 308.607 + vertex 695.209 130.383 309.447 + endloop + endfacet + facet normal 0.333084 -0.734766 -0.590909 + outer loop + vertex 696.426 131.537 308.607 + vertex 695.612 132.348 307.139 + vertex 697.556 132.513 308.03 + endloop + endfacet + facet normal 0.339319 -0.767989 -0.54319 + outer loop + vertex 695.209 130.383 309.447 + vertex 690.998 128.631 309.292 + vertex 693.591 130.513 308.252 + endloop + endfacet + facet normal 0.482171 -0.695973 -0.532102 + outer loop + vertex 686.304 136.758 297.445 + vertex 679.818 132.687 296.892 + vertex 684.343 136.105 296.522 + endloop + endfacet + facet normal 0.345708 -0.77165 -0.533893 + outer loop + vertex 688.466 128.327 308.092 + vertex 693.591 130.513 308.252 + vertex 690.998 128.631 309.292 + endloop + endfacet + facet normal 0.339379 -0.785881 -0.516926 + outer loop + vertex 690.998 128.631 309.292 + vertex 684.905 125.988 309.311 + vertex 688.466 128.327 308.092 + endloop + endfacet + facet normal 0.498292 -0.803965 -0.324569 + outer loop + vertex 679.818 132.687 296.892 + vertex 672.387 128.159 296.7 + vertex 676.476 130.919 296.141 + endloop + endfacet + facet normal 0.352994 -0.794624 -0.493931 + outer loop + vertex 681.38 125.106 308.211 + vertex 688.466 128.327 308.092 + vertex 684.905 125.988 309.311 + endloop + endfacet + facet normal 0.34104 -0.814062 -0.470101 + outer loop + vertex 681.33 124.09 310.071 + vertex 688.072 126.931 310.043 + vertex 684.582 125.364 310.224 + endloop + endfacet + facet normal 0.469585 -0.847144 -0.248671 + outer loop + vertex 672.387 128.159 296.7 + vertex 665.459 124.286 296.809 + vertex 669.551 126.763 296.102 + endloop + endfacet + facet normal 0.347589 -0.85677 -0.380955 + outer loop + vertex 675.374 121.664 310.094 + vertex 681.33 124.09 310.071 + vertex 677.796 122.588 310.226 + endloop + endfacet + facet normal 0.423782 -0.844536 -0.327366 + outer loop + vertex 665.459 124.286 296.809 + vertex 659.505 121.159 297.171 + vertex 661.876 122.7 296.263 + endloop + endfacet + facet normal 0.355789 -0.918144 -0.174431 + outer loop + vertex 671.939 120.339 310.058 + vertex 675.374 121.664 310.094 + vertex 672.372 120.484 310.18 + endloop + endfacet + facet normal 0.375856 -0.770764 -0.514446 + outer loop + vertex 696.426 131.537 308.607 + vertex 697.212 131.012 309.968 + vertex 695.209 130.383 309.447 + endloop + endfacet + facet normal 0.396962 -0.852678 -0.339648 + outer loop + vertex 657.314 120.364 296.605 + vertex 659.505 121.159 297.171 + vertex 655.568 119.244 297.376 + endloop + endfacet + facet normal 0.324133 -0.912223 -0.250573 + outer loop + vertex 664.957 118.002 309.389 + vertex 664.221 117.956 308.605 + vertex 665.597 118.162 309.636 + endloop + endfacet + facet normal 0.288733 -0.936613 -0.198468 + outer loop + vertex 665.432 118.216 309.138 + vertex 665.597 118.162 309.636 + vertex 664.221 117.956 308.605 + endloop + endfacet + facet normal 0.49798 -0.701232 0.510185 + outer loop + vertex 684.442 135.895 45.2665 + vertex 684.607 135.524 44.597 + vertex 689.505 139.369 45.0998 + endloop + endfacet + facet normal 0.520257 -0.790773 0.322507 + outer loop + vertex 676.639 130.711 45.1452 + vertex 677.499 130.991 44.4445 + vertex 684.442 135.895 45.2665 + endloop + endfacet + facet normal 0.453338 -0.728132 0.51411 + outer loop + vertex 684.442 135.895 45.2665 + vertex 677.499 130.991 44.4445 + vertex 684.607 135.524 44.597 + endloop + endfacet + facet normal 0.494098 -0.824071 0.277082 + outer loop + vertex 676.639 130.711 45.1452 + vertex 669.446 126.04 44.0778 + vertex 677.499 130.991 44.4445 + endloop + endfacet + facet normal 0.448929 -0.681649 0.57777 + outer loop + vertex 684.607 135.524 44.597 + vertex 685.204 135.019 43.5362 + vertex 689.245 138.444 44.4377 + endloop + endfacet + facet normal 0.425889 -0.664123 0.614458 + outer loop + vertex 689.245 138.444 44.4377 + vertex 685.204 135.019 43.5362 + vertex 690.416 138.141 43.2991 + endloop + endfacet + facet normal 0.463979 -0.743713 0.481263 + outer loop + vertex 677.499 130.991 44.4445 + vertex 678.178 130.763 43.4372 + vertex 684.607 135.524 44.597 + endloop + endfacet + facet normal 0.418994 -0.705097 0.572087 + outer loop + vertex 684.607 135.524 44.597 + vertex 678.178 130.763 43.4372 + vertex 685.204 135.019 43.5362 + endloop + endfacet + facet normal 0.467505 -0.789719 0.397219 + outer loop + vertex 669.446 126.04 44.0778 + vertex 670.125 125.955 43.1111 + vertex 677.499 130.991 44.4445 + endloop + endfacet + facet normal 0.43857 -0.766434 0.469292 + outer loop + vertex 677.499 130.991 44.4445 + vertex 670.125 125.955 43.1111 + vertex 678.178 130.763 43.4372 + endloop + endfacet + facet normal 0.433626 -0.678684 0.592753 + outer loop + vertex 685.204 135.019 43.5362 + vertex 686.106 134.049 41.7665 + vertex 690.416 138.141 43.2991 + endloop + endfacet + facet normal 0.432446 -0.726424 0.534134 + outer loop + vertex 678.178 130.763 43.4372 + vertex 679.171 130.119 41.7571 + vertex 685.204 135.019 43.5362 + endloop + endfacet + facet normal 0.398072 -0.7038 0.588391 + outer loop + vertex 685.204 135.019 43.5362 + vertex 679.171 130.119 41.7571 + vertex 686.106 134.049 41.7665 + endloop + endfacet + facet normal 0.437715 -0.765192 0.472108 + outer loop + vertex 670.125 125.955 43.1111 + vertex 671.043 125.445 41.4329 + vertex 678.178 130.763 43.4372 + endloop + endfacet + facet normal 0.402621 -0.682539 0.609948 + outer loop + vertex 686.106 134.049 41.7665 + vertex 687.087 132.544 39.435 + vertex 691.206 136.681 41.3446 + endloop + endfacet + facet normal 0.408668 -0.722422 0.557762 + outer loop + vertex 679.171 130.119 41.7571 + vertex 680.429 129.11 39.5294 + vertex 686.106 134.049 41.7665 + endloop + endfacet + facet normal 0.370461 -0.701584 0.608719 + outer loop + vertex 686.106 134.049 41.7665 + vertex 680.429 129.11 39.5294 + vertex 687.087 132.544 39.435 + endloop + endfacet + facet normal 0.367108 -0.692624 0.62089 + outer loop + vertex 687.087 132.544 39.435 + vertex 688.298 130.935 36.9236 + vertex 692.125 134.759 38.9268 + endloop + endfacet + facet normal 0.344243 -0.706275 0.618605 + outer loop + vertex 687.087 132.544 39.435 + vertex 681.837 127.912 37.0674 + vertex 688.298 130.935 36.9236 + endloop + endfacet + facet normal 0.337631 -0.707823 0.620477 + outer loop + vertex 688.298 130.935 36.9236 + vertex 689.666 129.498 34.5398 + vertex 693.326 132.827 36.3469 + endloop + endfacet + facet normal 0.325415 -0.715555 0.618131 + outer loop + vertex 688.298 130.935 36.9236 + vertex 683.323 126.773 34.7246 + vertex 689.666 129.498 34.5398 + endloop + endfacet + facet normal 0.410351 -0.832791 0.37158 + outer loop + vertex 657.592 119.634 44.1362 + vertex 654.659 118.333 44.4604 + vertex 654.164 117.688 43.5604 + endloop + endfacet + facet normal 0.431068 -0.826841 0.361266 + outer loop + vertex 664.846 123.715 44.9807 + vertex 661.761 122.158 45.0986 + vertex 662.023 121.951 44.3134 + endloop + endfacet + facet normal 0.460748 -0.828384 0.318577 + outer loop + vertex 667.671 125.476 45.4747 + vertex 664.846 123.715 44.9807 + vertex 668.365 125.57 44.7151 + endloop + endfacet + facet normal 0.446201 -0.841858 0.303612 + outer loop + vertex 669.417 126.355 45.3451 + vertex 667.671 125.476 45.4747 + vertex 668.365 125.57 44.7151 + endloop + endfacet + facet normal 0.495903 -0.840364 0.218789 + outer loop + vertex 670.594 127.065 45.4074 + vertex 669.417 126.355 45.3451 + vertex 668.365 125.57 44.7151 + endloop + endfacet + facet normal 0.539235 -0.838737 0.0757991 + outer loop + vertex 673.471 128.938 45.6623 + vertex 670.594 127.065 45.4074 + vertex 668.365 125.57 44.7151 + endloop + endfacet + facet normal 0.503308 -0.818871 0.275919 + outer loop + vertex 676.76 131.022 45.848 + vertex 673.471 128.938 45.6623 + vertex 676.639 130.711 45.1452 + endloop + endfacet + facet normal 0.548656 -0.795341 0.257701 + outer loop + vertex 679.19 132.786 46.1157 + vertex 676.76 131.022 45.848 + vertex 676.639 130.711 45.1452 + endloop + endfacet + facet normal 0.513988 -0.789291 0.33591 + outer loop + vertex 681.975 134.467 45.8068 + vertex 679.19 132.786 46.1157 + vertex 676.639 130.711 45.1452 + endloop + endfacet + facet normal 0.52169 -0.743876 0.417718 + outer loop + vertex 685.039 136.715 45.9815 + vertex 681.975 134.467 45.8068 + vertex 684.442 135.895 45.2665 + endloop + endfacet + facet normal 0.532749 -0.74221 0.406575 + outer loop + vertex 686.944 137.946 45.7323 + vertex 685.039 136.715 45.9815 + vertex 684.442 135.895 45.2665 + endloop + endfacet + facet normal 0.614554 -0.647212 -0.451044 + outer loop + vertex 689.02 139.796 45.9062 + vertex 686.944 137.946 45.7323 + vertex 684.442 135.895 45.2665 + endloop + endfacet + facet normal 0.278339 -0.8936 0.352145 + outer loop + vertex 662.478 115.959 32.6075 + vertex 664.875 116.122 31.1266 + vertex 663.885 116.082 31.8069 + endloop + endfacet + facet normal 0.336816 -0.842558 0.420299 + outer loop + vertex 660.139 115.954 34.4713 + vertex 662.478 115.959 32.6075 + vertex 661.814 116.246 33.7132 + endloop + endfacet + facet normal 0.351911 -0.842552 0.407755 + outer loop + vertex 657.903 116.058 36.6162 + vertex 660.139 115.954 34.4713 + vertex 659.43 116.371 35.9449 + endloop + endfacet + facet normal 0.459636 -0.640303 0.615424 + outer loop + vertex 684.442 135.895 45.2665 + vertex 689.505 139.369 45.0998 + vertex 689.02 139.796 45.9062 + endloop + endfacet + facet normal 0.525943 -0.798631 0.292527 + outer loop + vertex 676.639 130.711 45.1452 + vertex 684.442 135.895 45.2665 + vertex 681.975 134.467 45.8068 + endloop + endfacet + facet normal 0.503624 -0.83043 0.238221 + outer loop + vertex 668.365 125.57 44.7151 + vertex 676.639 130.711 45.1452 + vertex 673.471 128.938 45.6623 + endloop + endfacet + facet normal 0.465314 -0.844858 0.264003 + outer loop + vertex 662.023 121.951 44.3134 + vertex 668.365 125.57 44.7151 + vertex 664.846 123.715 44.9807 + endloop + endfacet + facet normal 0.129732 -0.982908 0.130616 + outer loop + vertex 664.875 116.122 31.1266 + vertex 665.624 116.162 30.6829 + vertex 663.885 116.082 31.8069 + endloop + endfacet + facet normal 0.432049 -0.834096 0.342955 + outer loop + vertex 661.62 121.496 43.5908 + vertex 657.592 119.634 44.1362 + vertex 655.879 118.322 43.1035 + endloop + endfacet + facet normal 0.336812 -0.820096 0.462602 + outer loop + vertex 665.385 116.281 31.0684 + vertex 663.885 116.082 31.8069 + vertex 665.624 116.162 30.6829 + endloop + endfacet + facet normal 0.259282 -0.643418 0.720268 + outer loop + vertex 657.26 108.727 25.7077 + vertex 661.994 110.088 25.219 + vertex 662.637 111.358 26.122 + endloop + endfacet + facet normal 0.306344 -0.686577 0.659367 + outer loop + vertex 658.755 110.243 26.591 + vertex 657.26 108.727 25.7077 + vertex 659.352 110.225 26.2955 + endloop + endfacet + facet normal 0.310209 -0.728872 0.610341 + outer loop + vertex 660.994 112.052 27.6136 + vertex 658.755 110.243 26.591 + vertex 661.078 111.533 26.9506 + endloop + endfacet + facet normal 0.334192 -0.76382 0.552173 + outer loop + vertex 664.073 114.405 29.0056 + vertex 660.994 112.052 27.6136 + vertex 663.057 113.219 27.9802 + endloop + endfacet + facet normal 0.294476 -0.721792 0.626339 + outer loop + vertex 694.339 127.359 29.7782 + vertex 691.335 126.339 30.0158 + vertex 687.698 124.44 29.5363 + endloop + endfacet + facet normal 0.260504 -0.645546 0.717919 + outer loop + vertex 662.637 111.358 26.122 + vertex 659.352 110.225 26.2955 + vertex 657.26 108.727 25.7077 + endloop + endfacet + facet normal 0.295486 -0.710305 0.63887 + outer loop + vertex 659.352 110.225 26.2955 + vertex 661.078 111.533 26.9506 + vertex 658.755 110.243 26.591 + endloop + endfacet + facet normal 0.304909 -0.73056 0.610994 + outer loop + vertex 661.078 111.533 26.9506 + vertex 663.057 113.219 27.9802 + vertex 660.994 112.052 27.6136 + endloop + endfacet + facet normal 0.26015 -0.643551 0.719836 + outer loop + vertex 661.994 110.088 25.219 + vertex 667.973 112.716 25.4079 + vertex 662.637 111.358 26.122 + endloop + endfacet + facet normal -0.479343 -0.614636 -0.626461 + outer loop + vertex -686.186 136.696 297.412 + vertex -687.048 135.83 298.922 + vertex -690.67 139.775 297.822 + endloop + endfacet + facet normal -0.414469 -0.57669 -0.70402 + outer loop + vertex -690.67 139.775 297.822 + vertex -687.048 135.83 298.922 + vertex -691.167 138.218 299.391 + endloop + endfacet + facet normal -0.480989 -0.694242 -0.535422 + outer loop + vertex -680.057 132.798 296.962 + vertex -681.334 132.417 298.603 + vertex -686.186 136.696 297.412 + endloop + endfacet + facet normal -0.427202 -0.657091 -0.621072 + outer loop + vertex -686.186 136.696 297.412 + vertex -681.334 132.417 298.603 + vertex -687.048 135.83 298.922 + endloop + endfacet + facet normal -0.474004 -0.758547 -0.447132 + outer loop + vertex -672.674 128.308 296.752 + vertex -674.344 128.406 298.355 + vertex -680.057 132.798 296.962 + endloop + endfacet + facet normal -0.440582 -0.736196 -0.513715 + outer loop + vertex -680.057 132.798 296.962 + vertex -674.344 128.406 298.355 + vertex -681.334 132.417 298.603 + endloop + endfacet + facet normal -0.445119 -0.802378 -0.397565 + outer loop + vertex -665.461 124.354 296.656 + vertex -667.213 124.582 298.157 + vertex -672.674 128.308 296.752 + endloop + endfacet + facet normal -0.440029 -0.799316 -0.409228 + outer loop + vertex -672.674 128.308 296.752 + vertex -667.213 124.582 298.157 + vertex -674.344 128.406 298.355 + endloop + endfacet + facet normal -0.432109 -0.616037 -0.65862 + outer loop + vertex -687.048 135.83 298.922 + vertex -687.951 134.496 300.762 + vertex -691.167 138.218 299.391 + endloop + endfacet + facet normal -0.376954 -0.589056 -0.714786 + outer loop + vertex -691.167 138.218 299.391 + vertex -687.951 134.496 300.762 + vertex -691.876 136.433 301.235 + endloop + endfacet + facet normal -0.438009 -0.678068 -0.590231 + outer loop + vertex -681.334 132.417 298.603 + vertex -682.513 131.532 300.494 + vertex -687.048 135.83 298.922 + endloop + endfacet + facet normal -0.385103 -0.647057 -0.658037 + outer loop + vertex -687.048 135.83 298.922 + vertex -682.513 131.532 300.494 + vertex -687.951 134.496 300.762 + endloop + endfacet + facet normal -0.439705 -0.734471 -0.516925 + outer loop + vertex -674.344 128.406 298.355 + vertex -675.726 127.864 300.301 + vertex -681.334 132.417 298.603 + endloop + endfacet + facet normal -0.399728 -0.70908 -0.580882 + outer loop + vertex -681.334 132.417 298.603 + vertex -675.726 127.864 300.301 + vertex -682.513 131.532 300.494 + endloop + endfacet + facet normal -0.431031 -0.780248 -0.453238 + outer loop + vertex -667.213 124.582 298.157 + vertex -668.565 124.198 300.103 + vertex -674.344 128.406 298.355 + endloop + endfacet + facet normal -0.405309 -0.764725 -0.500919 + outer loop + vertex -674.344 128.406 298.355 + vertex -668.565 124.198 300.103 + vertex -675.726 127.864 300.301 + endloop + endfacet + facet normal -0.394471 -0.637489 -0.661816 + outer loop + vertex -687.951 134.496 300.762 + vertex -688.969 133.034 302.776 + vertex -691.876 136.433 301.235 + endloop + endfacet + facet normal -0.351073 -0.618887 -0.702657 + outer loop + vertex -691.876 136.433 301.235 + vertex -688.969 133.034 302.776 + vertex -692.836 134.716 303.228 + endloop + endfacet + facet normal -0.402213 -0.682788 -0.609939 + outer loop + vertex -682.513 131.532 300.494 + vertex -683.751 130.433 302.541 + vertex -687.951 134.496 300.762 + endloop + endfacet + facet normal -0.358852 -0.659925 -0.660094 + outer loop + vertex -687.951 134.496 300.762 + vertex -683.751 130.433 302.541 + vertex -688.969 133.034 302.776 + endloop + endfacet + facet normal -0.409853 -0.729581 -0.547478 + outer loop + vertex -675.726 127.864 300.301 + vertex -677.164 127.082 302.419 + vertex -682.513 131.532 300.494 + endloop + endfacet + facet normal -0.370384 -0.70628 -0.603312 + outer loop + vertex -682.513 131.532 300.494 + vertex -677.164 127.082 302.419 + vertex -683.751 130.433 302.541 + endloop + endfacet + facet normal -0.408445 -0.771563 -0.487712 + outer loop + vertex -668.565 124.198 300.103 + vertex -670.063 123.616 302.279 + vertex -675.726 127.864 300.301 + endloop + endfacet + facet normal -0.378934 -0.754589 -0.535729 + outer loop + vertex -675.726 127.864 300.301 + vertex -670.063 123.616 302.279 + vertex -677.164 127.082 302.419 + endloop + endfacet + facet normal -0.36693 -0.67103 -0.644268 + outer loop + vertex -688.969 133.034 302.776 + vertex -689.971 131.65 304.789 + vertex -692.836 134.716 303.228 + endloop + endfacet + facet normal -0.332891 -0.656059 -0.677326 + outer loop + vertex -692.836 134.716 303.228 + vertex -689.971 131.65 304.789 + vertex -693.841 133.174 305.215 + endloop + endfacet + facet normal -0.378033 -0.703698 -0.601581 + outer loop + vertex -683.751 130.433 302.541 + vertex -684.925 129.327 304.572 + vertex -688.969 133.034 302.776 + endloop + endfacet + facet normal -0.343152 -0.685365 -0.642279 + outer loop + vertex -688.969 133.034 302.776 + vertex -684.925 129.327 304.572 + vertex -689.971 131.65 304.789 + endloop + endfacet + facet normal -0.385978 -0.738783 -0.552468 + outer loop + vertex -677.164 127.082 302.419 + vertex -678.678 126.32 304.496 + vertex -683.751 130.433 302.541 + endloop + endfacet + facet normal -0.35392 -0.720245 -0.596647 + outer loop + vertex -683.751 130.433 302.541 + vertex -678.678 126.32 304.496 + vertex -684.925 129.327 304.572 + endloop + endfacet + facet normal -0.389196 -0.777277 -0.494334 + outer loop + vertex -670.063 123.616 302.279 + vertex -671.809 123.083 304.491 + vertex -677.164 127.082 302.419 + endloop + endfacet + facet normal -0.358892 -0.760758 -0.540781 + outer loop + vertex -677.164 127.082 302.419 + vertex -671.809 123.083 304.491 + vertex -678.678 126.32 304.496 + endloop + endfacet + facet normal -0.347744 -0.712844 -0.609038 + outer loop + vertex -689.971 131.65 304.789 + vertex -690.816 130.458 306.667 + vertex -693.841 133.174 305.215 + endloop + endfacet + facet normal -0.331071 -0.704366 -0.627901 + outer loop + vertex -693.841 133.174 305.215 + vertex -690.816 130.458 306.667 + vertex -694.704 131.885 307.116 + endloop + endfacet + facet normal -0.363061 -0.735128 -0.572515 + outer loop + vertex -684.925 129.327 304.572 + vertex -685.845 128.32 306.449 + vertex -689.971 131.65 304.789 + endloop + endfacet + facet normal -0.336086 -0.719354 -0.607927 + outer loop + vertex -689.971 131.65 304.789 + vertex -685.845 128.32 306.449 + vertex -690.816 130.458 306.667 + endloop + endfacet + facet normal -0.371749 -0.758854 -0.534736 + outer loop + vertex -678.678 126.32 304.496 + vertex -680.029 125.661 306.372 + vertex -684.925 129.327 304.572 + endloop + endfacet + facet normal -0.347901 -0.744336 -0.570025 + outer loop + vertex -684.925 129.327 304.572 + vertex -680.029 125.661 306.372 + vertex -685.845 128.32 306.449 + endloop + endfacet + facet normal -0.350214 -0.775627 -0.525122 + outer loop + vertex -678.678 126.32 304.496 + vertex -673.793 122.808 306.426 + vertex -680.029 125.661 306.372 + endloop + endfacet + facet normal -0.341138 -0.751783 -0.564312 + outer loop + vertex -690.816 130.458 306.667 + vertex -691.514 129.563 308.281 + vertex -694.704 131.885 307.116 + endloop + endfacet + facet normal -0.338 -0.74976 -0.568873 + outer loop + vertex -694.704 131.885 307.116 + vertex -691.514 129.563 308.281 + vertex -695.257 130.857 308.8 + endloop + endfacet + facet normal -0.354214 -0.76931 -0.53169 + outer loop + vertex -685.845 128.32 306.449 + vertex -686.381 127.446 308.07 + vertex -690.816 130.458 306.667 + endloop + endfacet + facet normal -0.334663 -0.755315 -0.563471 + outer loop + vertex -690.816 130.458 306.667 + vertex -686.381 127.446 308.07 + vertex -691.514 129.563 308.281 + endloop + endfacet + facet normal -0.346093 -0.773347 -0.531182 + outer loop + vertex -685.845 128.32 306.449 + vertex -680.793 125.013 307.971 + vertex -686.381 127.446 308.07 + endloop + endfacet + facet normal -0.358376 -0.918841 -0.165224 + outer loop + vertex -670.667 119.856 310.052 + vertex -675.388 121.695 310.064 + vertex -673.161 120.882 309.759 + endloop + endfacet + facet normal -0.384946 -0.845002 -0.371198 + outer loop + vertex -657.638 120.577 296.478 + vertex -655.143 119.333 296.721 + vertex -656.384 119.549 297.516 + endloop + endfacet + facet normal -0.398849 -0.855321 -0.330675 + outer loop + vertex -660.046 121.79 296.245 + vertex -657.638 120.577 296.478 + vertex -660.311 121.729 296.722 + endloop + endfacet + facet normal -0.414652 -0.844836 -0.338107 + outer loop + vertex -662.101 122.804 296.23 + vertex -660.046 121.79 296.245 + vertex -660.311 121.729 296.722 + endloop + endfacet + facet normal -0.429945 -0.844422 -0.319528 + outer loop + vertex -664.209 123.947 296.046 + vertex -662.101 122.804 296.23 + vertex -665.461 124.354 296.656 + endloop + endfacet + facet normal -0.431884 -0.841043 -0.325764 + outer loop + vertex -666.442 125.085 296.068 + vertex -664.209 123.947 296.046 + vertex -665.461 124.354 296.656 + endloop + endfacet + facet normal -0.464358 -0.842442 -0.273247 + outer loop + vertex -669.283 126.645 296.087 + vertex -666.442 125.085 296.068 + vertex -665.461 124.354 296.656 + endloop + endfacet + facet normal -0.466611 -0.834657 -0.292611 + outer loop + vertex -672.217 128.282 296.095 + vertex -669.283 126.645 296.087 + vertex -672.674 128.308 296.752 + endloop + endfacet + facet normal -0.497125 -0.808548 -0.314827 + outer loop + vertex -674.329 129.597 296.053 + vertex -672.217 128.282 296.095 + vertex -672.674 128.308 296.752 + endloop + endfacet + facet normal -0.502761 -0.809497 -0.303227 + outer loop + vertex -677.023 131.186 296.279 + vertex -674.329 129.597 296.053 + vertex -672.674 128.308 296.752 + endloop + endfacet + facet normal -0.496493 -0.748575 -0.439467 + outer loop + vertex -679.864 133.13 296.178 + vertex -677.023 131.186 296.279 + vertex -680.057 132.798 296.962 + endloop + endfacet + facet normal -0.508594 -0.740632 -0.439086 + outer loop + vertex -681.944 134.466 296.333 + vertex -679.864 133.13 296.178 + vertex -680.057 132.798 296.962 + endloop + endfacet + facet normal -0.539079 -0.752322 -0.378689 + outer loop + vertex -684.472 136.177 296.533 + vertex -681.944 134.466 296.333 + vertex -680.057 132.798 296.962 + endloop + endfacet + facet normal -0.492343 -0.655918 -0.572162 + outer loop + vertex -687.249 138.068 296.754 + vertex -684.472 136.177 296.533 + vertex -686.186 136.696 297.412 + endloop + endfacet + facet normal -0.532739 -0.664267 -0.524346 + outer loop + vertex -689.318 139.552 296.976 + vertex -687.249 138.068 296.754 + vertex -686.186 136.696 297.412 + endloop + endfacet + facet normal -0.411935 -0.511431 -0.754153 + outer loop + vertex -694.412 139.658 300.186 + vertex -694.396 142.026 298.572 + vertex -691.167 138.218 299.391 + endloop + endfacet + facet normal -0.38179 -0.543382 -0.747645 + outer loop + vertex -695.219 137.722 302.006 + vertex -694.412 139.658 300.186 + vertex -691.876 136.433 301.235 + endloop + endfacet + facet normal -0.353226 -0.578758 -0.735031 + outer loop + vertex -696.199 135.873 303.933 + vertex -695.219 137.722 302.006 + vertex -692.836 134.716 303.228 + endloop + endfacet + facet normal -0.339547 -0.628932 -0.699394 + outer loop + vertex -697.199 134.236 305.89 + vertex -696.199 135.873 303.933 + vertex -693.841 133.174 305.215 + endloop + endfacet + facet normal -0.345144 -0.695086 -0.630659 + outer loop + vertex -697.96 132.78 307.911 + vertex -697.199 134.236 305.89 + vertex -694.704 131.885 307.116 + endloop + endfacet + facet normal -0.370489 -0.764377 -0.527699 + outer loop + vertex -697.477 131.04 310.093 + vertex -697.96 132.78 307.911 + vertex -695.257 130.857 308.8 + endloop + endfacet + facet normal -0.317019 -0.912229 -0.259493 + outer loop + vertex -663.734 117.815 308.587 + vertex -665.195 118.056 309.527 + vertex -664.801 117.996 309.254 + endloop + endfacet + facet normal -0.34355 -0.82221 -0.45381 + outer loop + vertex -681 123.872 310.262 + vertex -684.527 125.359 310.238 + vertex -681.697 124.289 310.035 + endloop + endfacet + facet normal -0.340734 -0.820414 -0.459153 + outer loop + vertex -679.593 123.292 310.254 + vertex -681 123.872 310.262 + vertex -681.697 124.289 310.035 + endloop + endfacet + facet normal -0.314703 -0.782645 -0.537056 + outer loop + vertex -677.609 122.502 310.242 + vertex -679.593 123.292 310.254 + vertex -681.697 124.289 310.035 + endloop + endfacet + facet normal -0.34217 -0.856765 -0.385841 + outer loop + vertex -675.45 121.639 310.246 + vertex -677.609 122.502 310.242 + vertex -675.388 121.695 310.064 + endloop + endfacet + facet normal -0.333168 -0.861085 -0.384098 + outer loop + vertex -674.008 121.089 310.228 + vertex -675.45 121.639 310.246 + vertex -675.388 121.695 310.064 + endloop + endfacet + facet normal -0.330223 -0.857316 -0.394921 + outer loop + vertex -672.113 120.376 310.19 + vertex -674.008 121.089 310.228 + vertex -675.388 121.695 310.064 + endloop + endfacet + facet normal -0.344777 -0.933894 -0.094711 + outer loop + vertex -669.575 119.439 310.195 + vertex -672.113 120.376 310.19 + vertex -670.667 119.856 310.052 + endloop + endfacet + facet normal -0.485427 -0.625593 -0.610733 + outer loop + vertex -686.186 136.696 297.412 + vertex -690.67 139.775 297.822 + vertex -689.318 139.552 296.976 + endloop + endfacet + facet normal -0.482867 -0.697951 -0.52887 + outer loop + vertex -680.057 132.798 296.962 + vertex -686.186 136.696 297.412 + vertex -684.472 136.177 296.533 + endloop + endfacet + facet normal -0.499541 -0.80669 -0.315769 + outer loop + vertex -672.674 128.308 296.752 + vertex -680.057 132.798 296.962 + vertex -677.023 131.186 296.279 + endloop + endfacet + facet normal -0.465955 -0.843558 -0.267013 + outer loop + vertex -665.461 124.354 296.656 + vertex -672.674 128.308 296.752 + vertex -669.283 126.645 296.087 + endloop + endfacet + facet normal -0.430706 -0.852436 -0.296388 + outer loop + vertex -660.311 121.729 296.722 + vertex -665.461 124.354 296.656 + vertex -662.101 122.804 296.23 + endloop + endfacet + facet normal -0.424088 -0.563946 -0.7086 + outer loop + vertex -691.167 138.218 299.391 + vertex -691.876 136.433 301.235 + vertex -694.412 139.658 300.186 + endloop + endfacet + facet normal -0.39125 -0.595374 -0.70175 + outer loop + vertex -691.876 136.433 301.235 + vertex -692.836 134.716 303.228 + vertex -695.219 137.722 302.006 + endloop + endfacet + facet normal -0.362121 -0.638858 -0.67877 + outer loop + vertex -692.836 134.716 303.228 + vertex -693.841 133.174 305.215 + vertex -696.199 135.873 303.933 + endloop + endfacet + facet normal -0.346561 -0.695783 -0.629112 + outer loop + vertex -693.841 133.174 305.215 + vertex -694.704 131.885 307.116 + vertex -697.199 134.236 305.89 + endloop + endfacet + facet normal -0.344308 -0.74672 -0.569088 + outer loop + vertex -694.704 131.885 307.116 + vertex -695.257 130.857 308.8 + vertex -697.96 132.78 307.911 + endloop + endfacet + facet normal -0.342077 -0.778895 -0.525648 + outer loop + vertex -695.257 130.857 308.8 + vertex -691.514 129.563 308.281 + vertex -692.345 129.143 309.444 + endloop + endfacet + facet normal -0.347839 -0.793702 -0.499045 + outer loop + vertex -691.514 129.563 308.281 + vertex -686.381 127.446 308.07 + vertex -687.066 126.987 309.278 + endloop + endfacet + facet normal 0.526224 0.456049 0.71771 + outer loop + vertex -664.801 117.996 309.254 + vertex -664.303 117.905 308.947 + vertex -663.734 117.815 308.587 + endloop + endfacet + facet normal -0.398831 -0.826921 -0.396403 + outer loop + vertex -665.659 118.157 309.782 + vertex -664.801 117.996 309.254 + vertex -665.195 118.056 309.527 + endloop + endfacet + facet normal -0.340227 -0.77716 -0.529403 + outer loop + vertex -692.345 129.143 309.444 + vertex -695.388 130.258 309.762 + vertex -695.257 130.857 308.8 + endloop + endfacet + facet normal -0.336331 -0.783125 -0.523065 + outer loop + vertex -687.066 126.987 309.278 + vertex -692.345 129.143 309.444 + vertex -691.514 129.563 308.281 + endloop + endfacet + facet normal -0.341166 -0.797948 -0.496875 + outer loop + vertex -680.46 124.151 309.296 + vertex -687.066 126.987 309.278 + vertex -686.381 127.446 308.07 + endloop + endfacet + facet normal -0.341489 -0.813558 -0.470647 + outer loop + vertex -688.807 127.274 310.034 + vertex -681.697 124.289 310.035 + vertex -684.527 125.359 310.238 + endloop + endfacet + facet normal -0.335301 -0.821055 -0.461997 + outer loop + vertex -681.697 124.289 310.035 + vertex -675.388 121.695 310.064 + vertex -677.609 122.502 310.242 + endloop + endfacet + facet normal -0.348162 -0.891779 -0.288985 + outer loop + vertex -675.388 121.695 310.064 + vertex -670.667 119.856 310.052 + vertex -672.113 120.376 310.19 + endloop + endfacet + facet normal -0.397029 -0.845489 -0.357094 + outer loop + vertex -657.638 120.577 296.478 + vertex -656.384 119.549 297.516 + vertex -660.311 121.729 296.722 + endloop + endfacet + facet normal -0.369775 -0.765695 -0.526286 + outer loop + vertex -697.477 131.04 310.093 + vertex -695.257 130.857 308.8 + vertex -695.388 130.258 309.762 + endloop + endfacet + facet normal -0.334082 -0.928678 -0.161077 + outer loop + vertex -669.575 119.439 310.195 + vertex -670.667 119.856 310.052 + vertex -667.813 118.826 310.073 + endloop + endfacet + facet normal -0.333599 -0.927498 -0.168697 + outer loop + vertex -668.372 119.084 309.759 + vertex -667.813 118.826 310.073 + vertex -670.667 119.856 310.052 + endloop + endfacet + facet normal -0.371362 -0.914358 0.161365 + outer loop + vertex -692.782 128.32 313.841 + vertex -688.863 126.762 314.033 + vertex -691.518 127.952 314.669 + endloop + endfacet + facet normal -0.356624 -0.909477 0.213706 + outer loop + vertex -691.518 127.952 314.669 + vertex -688.863 126.762 314.033 + vertex -686.898 126.193 314.892 + endloop + endfacet + facet normal -0.351976 -0.886149 0.301418 + outer loop + vertex -691.518 127.952 314.669 + vertex -686.898 126.193 314.892 + vertex -690.571 127.966 315.813 + endloop + endfacet + facet normal -0.356101 -0.888483 0.289466 + outer loop + vertex -690.571 127.966 315.813 + vertex -686.898 126.193 314.892 + vertex -686.195 126.203 315.786 + endloop + endfacet + facet normal -0.368413 -0.929159 -0.0305871 + outer loop + vertex -693.038 128.36 313.273 + vertex -693.318 128.486 312.826 + vertex -689.312 126.888 313.119 + endloop + endfacet + facet normal -0.371063 -0.924792 -0.084096 + outer loop + vertex -694.087 128.837 312.364 + vertex -690.378 127.356 312.274 + vertex -693.318 128.486 312.826 + endloop + endfacet + facet normal -0.366693 -0.928861 -0.0524727 + outer loop + vertex -690.378 127.356 312.274 + vertex -689.312 126.888 313.119 + vertex -693.318 128.486 312.826 + endloop + endfacet + facet normal -0.386964 -0.916156 -0.10448 + outer loop + vertex -695.765 129.559 312.247 + vertex -694.087 128.837 312.364 + vertex -695.627 129.452 312.673 + endloop + endfacet + facet normal -0.381398 -0.922131 -0.0648795 + outer loop + vertex -695.627 129.452 312.673 + vertex -694.087 128.837 312.364 + vertex -693.318 128.486 312.826 + endloop + endfacet + facet normal -0.38726 -0.921575 0.0270048 + outer loop + vertex -695.627 129.452 312.673 + vertex -693.318 128.486 312.826 + vertex -695.216 129.298 313.307 + endloop + endfacet + facet normal -0.39546 -0.918421 -0.0106635 + outer loop + vertex -695.216 129.298 313.307 + vertex -693.318 128.486 312.826 + vertex -693.038 128.36 313.273 + endloop + endfacet + facet normal -0.362292 -0.927004 0.0969974 + outer loop + vertex -693.038 128.36 313.273 + vertex -689.312 126.888 313.119 + vertex -692.782 128.32 313.841 + endloop + endfacet + facet normal -0.371155 -0.926979 0.0543545 + outer loop + vertex -692.782 128.32 313.841 + vertex -689.312 126.888 313.119 + vertex -688.863 126.762 314.033 + endloop + endfacet + facet normal -0.377981 -0.890774 -0.252294 + outer loop + vertex -695.661 129.854 310.934 + vertex -692.431 128.403 311.219 + vertex -695.932 129.747 311.72 + endloop + endfacet + facet normal -0.376829 -0.89972 -0.220236 + outer loop + vertex -695.932 129.747 311.72 + vertex -692.431 128.403 311.219 + vertex -693.171 128.554 311.869 + endloop + endfacet + facet normal -0.379285 -0.903061 -0.201554 + outer loop + vertex -695.932 129.747 311.72 + vertex -693.171 128.554 311.869 + vertex -695.765 129.559 312.247 + endloop + endfacet + facet normal -0.378142 -0.907923 -0.18079 + outer loop + vertex -695.765 129.559 312.247 + vertex -693.171 128.554 311.869 + vertex -694.087 128.837 312.364 + endloop + endfacet + facet normal -0.369182 -0.915509 -0.159837 + outer loop + vertex -694.087 128.837 312.364 + vertex -693.171 128.554 311.869 + vertex -690.378 127.356 312.274 + endloop + endfacet + facet normal -0.370358 -0.904426 -0.211775 + outer loop + vertex -692.431 128.403 311.219 + vertex -688.002 126.523 311.504 + vertex -693.171 128.554 311.869 + endloop + endfacet + facet normal -0.370757 -0.916315 -0.151349 + outer loop + vertex -688.002 126.523 311.504 + vertex -690.378 127.356 312.274 + vertex -693.171 128.554 311.869 + endloop + endfacet + facet normal -0.299874 -0.866962 0.398062 + outer loop + vertex -686.195 126.203 315.786 + vertex -680.197 123.872 315.228 + vertex -685.937 126.636 316.925 + endloop + endfacet + facet normal -0.320392 -0.880177 0.350197 + outer loop + vertex -685.937 126.636 316.925 + vertex -680.197 123.872 315.228 + vertex -677.399 123.608 317.125 + endloop + endfacet + facet normal -0.327389 -0.906356 0.267088 + outer loop + vertex -686.195 126.203 315.786 + vertex -686.898 126.193 314.892 + vertex -680.197 123.872 315.228 + endloop + endfacet + facet normal -0.341873 -0.924193 0.170265 + outer loop + vertex -688.863 126.762 314.033 + vertex -682.213 124.208 313.52 + vertex -686.898 126.193 314.892 + endloop + endfacet + facet normal -0.329496 -0.920984 0.207895 + outer loop + vertex -682.213 124.208 313.52 + vertex -680.197 123.872 315.228 + vertex -686.898 126.193 314.892 + endloop + endfacet + facet normal -0.355133 -0.933706 0.0455454 + outer loop + vertex -688.863 126.762 314.033 + vertex -689.312 126.888 313.119 + vertex -682.213 124.208 313.52 + endloop + endfacet + facet normal -0.36637 -0.928962 -0.052936 + outer loop + vertex -690.378 127.356 312.274 + vertex -683.076 124.487 312.09 + vertex -689.312 126.888 313.119 + endloop + endfacet + facet normal -0.354617 -0.934492 0.0311609 + outer loop + vertex -683.076 124.487 312.09 + vertex -682.213 124.208 313.52 + vertex -689.312 126.888 313.119 + endloop + endfacet + facet normal -0.374745 -0.921634 -0.100785 + outer loop + vertex -686.756 126.173 310.733 + vertex -681.118 123.922 310.357 + vertex -679.978 123.437 310.555 + endloop + endfacet + facet normal -0.312672 -0.887782 0.337757 + outer loop + vertex -680.197 123.872 315.228 + vertex -670.865 120.475 314.939 + vertex -677.399 123.608 317.125 + endloop + endfacet + facet normal -0.317174 -0.890022 0.327509 + outer loop + vertex -677.399 123.608 317.125 + vertex -670.865 120.475 314.939 + vertex -668.374 120.256 316.757 + endloop + endfacet + facet normal -0.334628 -0.917584 0.214627 + outer loop + vertex -682.213 124.208 313.52 + vertex -672.553 120.595 313.136 + vertex -680.197 123.872 315.228 + endloop + endfacet + facet normal -0.325035 -0.913762 0.243702 + outer loop + vertex -680.197 123.872 315.228 + vertex -672.553 120.595 313.136 + vertex -670.865 120.475 314.939 + endloop + endfacet + facet normal -0.362017 -0.931468 0.036212 + outer loop + vertex -683.076 124.487 312.09 + vertex -675.326 121.476 312.112 + vertex -682.213 124.208 313.52 + endloop + endfacet + facet normal -0.344006 -0.92973 0.131388 + outer loop + vertex -670.088 119.49 311.77 + vertex -672.553 120.595 313.136 + vertex -675.326 121.476 312.112 + endloop + endfacet + facet normal -0.342956 -0.93062 0.127781 + outer loop + vertex -672.553 120.595 313.136 + vertex -682.213 124.208 313.52 + vertex -675.326 121.476 312.112 + endloop + endfacet + facet normal -0.362338 -0.924054 -0.1218 + outer loop + vertex -675.759 121.741 310.619 + vertex -672.186 120.331 310.686 + vertex -676.014 121.761 311.227 + endloop + endfacet + facet normal -0.359286 -0.929201 -0.0865975 + outer loop + vertex -676.014 121.761 311.227 + vertex -672.186 120.331 310.686 + vertex -671.12 119.876 311.145 + endloop + endfacet + facet normal -0.367486 -0.919562 -0.139139 + outer loop + vertex -679.978 123.437 310.555 + vertex -675.759 121.741 310.619 + vertex -681.409 123.931 311.066 + endloop + endfacet + facet normal -0.367173 -0.921864 -0.123896 + outer loop + vertex -681.409 123.931 311.066 + vertex -675.759 121.741 310.619 + vertex -676.014 121.761 311.227 + endloop + endfacet + facet normal -0.368878 -0.924225 -0.0986797 + outer loop + vertex -681.409 123.931 311.066 + vertex -676.014 121.761 311.227 + vertex -683.076 124.487 312.09 + endloop + endfacet + facet normal -0.362056 -0.931976 -0.0183115 + outer loop + vertex -683.076 124.487 312.09 + vertex -676.014 121.761 311.227 + vertex -675.326 121.476 312.112 + endloop + endfacet + facet normal -0.35959 -0.932885 -0.0205214 + outer loop + vertex -676.014 121.761 311.227 + vertex -671.12 119.876 311.145 + vertex -675.326 121.476 312.112 + endloop + endfacet + facet normal -0.354217 -0.93514 0.00656526 + outer loop + vertex -675.326 121.476 312.112 + vertex -671.12 119.876 311.145 + vertex -670.088 119.49 311.77 + endloop + endfacet + facet normal -0.36694 -0.919563 -0.140564 + outer loop + vertex -681.118 123.922 310.357 + vertex -675.892 121.84 310.332 + vertex -679.978 123.437 310.555 + endloop + endfacet + facet normal -0.366897 -0.918426 -0.147917 + outer loop + vertex -679.978 123.437 310.555 + vertex -675.892 121.84 310.332 + vertex -675.759 121.741 310.619 + endloop + endfacet + facet normal -0.357023 -0.913987 -0.192778 + outer loop + vertex -672.186 120.331 310.686 + vertex -675.759 121.741 310.619 + vertex -671.502 120.139 310.329 + endloop + endfacet + facet normal -0.357118 -0.921368 -0.153452 + outer loop + vertex -671.502 120.139 310.329 + vertex -675.759 121.741 310.619 + vertex -675.892 121.84 310.332 + endloop + endfacet + facet normal -0.23752 -0.622067 0.746067 + outer loop + vertex -678.881 122.992 310.294 + vertex -676.215 121.949 310.273 + vertex -681.118 123.922 310.357 + endloop + endfacet + facet normal -0.352976 -0.889598 0.289866 + outer loop + vertex -681.118 123.922 310.357 + vertex -676.215 121.949 310.273 + vertex -675.892 121.84 310.332 + endloop + endfacet + facet normal -0.347039 -0.912997 0.214476 + outer loop + vertex -676.215 121.949 310.273 + vertex -672.836 120.655 310.232 + vertex -675.892 121.84 310.332 + endloop + endfacet + facet normal -0.361242 -0.932397 0.0118225 + outer loop + vertex -675.892 121.84 310.332 + vertex -672.836 120.655 310.232 + vertex -671.502 120.139 310.329 + endloop + endfacet + facet normal -0.337956 -0.933587 -0.119172 + outer loop + vertex -669.071 119.18 310.532 + vertex -666.815 118.377 310.42 + vertex -667.714 118.63 310.987 + endloop + endfacet + facet normal -0.326488 -0.940097 -0.0981017 + outer loop + vertex -667.714 118.63 310.987 + vertex -666.815 118.377 310.42 + vertex -665.733 117.951 310.901 + endloop + endfacet + facet normal -0.349411 -0.930402 -0.110739 + outer loop + vertex -672.186 120.331 310.686 + vertex -669.071 119.18 310.532 + vertex -671.12 119.876 311.145 + endloop + endfacet + facet normal -0.345856 -0.933423 -0.0954217 + outer loop + vertex -671.12 119.876 311.145 + vertex -669.071 119.18 310.532 + vertex -667.714 118.63 310.987 + endloop + endfacet + facet normal -0.344021 -0.938877 -0.0125846 + outer loop + vertex -671.12 119.876 311.145 + vertex -667.714 118.63 310.987 + vertex -670.088 119.49 311.77 + endloop + endfacet + facet normal -0.333911 -0.94235 0.0219149 + outer loop + vertex -670.088 119.49 311.77 + vertex -667.714 118.63 310.987 + vertex -667.167 118.455 311.788 + endloop + endfacet + facet normal -0.323664 -0.946067 0.0141075 + outer loop + vertex -667.714 118.63 310.987 + vertex -665.733 117.951 310.901 + vertex -667.167 118.455 311.788 + endloop + endfacet + facet normal -0.335697 -0.941938 -0.00771589 + outer loop + vertex -667.167 118.455 311.788 + vertex -665.733 117.951 310.901 + vertex -665.173 117.745 311.658 + endloop + endfacet + facet normal -0.309193 -0.898245 0.312339 + outer loop + vertex -664.349 118.119 314.655 + vertex -660.619 116.833 314.65 + vertex -661.982 117.87 316.283 + endloop + endfacet + facet normal -0.301658 -0.898534 0.318809 + outer loop + vertex -661.982 117.87 316.283 + vertex -660.619 116.833 314.65 + vertex -658.764 116.723 316.093 + endloop + endfacet + facet normal -0.318216 -0.917567 0.238347 + outer loop + vertex -666.006 118.224 312.848 + vertex -662.688 117.088 312.906 + vertex -664.349 118.119 314.655 + endloop + endfacet + facet normal -0.316015 -0.917753 0.240548 + outer loop + vertex -664.349 118.119 314.655 + vertex -662.688 117.088 312.906 + vertex -660.619 116.833 314.65 + endloop + endfacet + facet normal -0.259492 -0.945108 0.198581 + outer loop + vertex -665.173 117.745 311.658 + vertex -664.466 117.536 311.583 + vertex -666.006 118.224 312.848 + endloop + endfacet + facet normal -0.323423 -0.938946 0.117381 + outer loop + vertex -666.006 118.224 312.848 + vertex -664.466 117.536 311.583 + vertex -662.688 117.088 312.906 + endloop + endfacet + facet normal -0.334058 -0.919266 -0.208219 + outer loop + vertex -667.981 118.84 310.247 + vertex -666.537 118.319 310.233 + vertex -666.815 118.377 310.42 + endloop + endfacet + facet normal -0.325168 -0.925754 -0.19299 + outer loop + vertex -666.815 118.377 310.42 + vertex -666.537 118.319 310.233 + vertex -666.036 118.117 310.355 + endloop + endfacet + facet normal -0.403071 -0.90521 -0.134643 + outer loop + vertex -697.386 130.26 312.622 + vertex -697.93 130.681 311.418 + vertex -695.932 129.747 311.72 + endloop + endfacet + facet normal -0.439118 -0.88646 0.146165 + outer loop + vertex -696.214 129.992 314.516 + vertex -697.386 130.26 312.622 + vertex -695.216 129.298 313.307 + endloop + endfacet + facet normal -0.384849 -0.863897 0.324921 + outer loop + vertex -694.287 130.283 317.572 + vertex -696.214 129.992 314.516 + vertex -690.571 127.966 315.813 + endloop + endfacet + facet normal -0.266444 -0.908482 0.321975 + outer loop + vertex -658.725 116.347 315.066 + vertex -657.328 116.444 316.497 + vertex -658.764 116.723 316.093 + endloop + endfacet + facet normal -0.294968 -0.915758 0.27273 + outer loop + vertex -660.546 116.492 313.583 + vertex -658.725 116.347 315.066 + vertex -660.619 116.833 314.65 + endloop + endfacet + facet normal -0.325007 -0.920439 0.21717 + outer loop + vertex -662.096 116.768 312.433 + vertex -660.546 116.492 313.583 + vertex -662.688 117.088 312.906 + endloop + endfacet + facet normal -0.370439 -0.915484 0.157048 + outer loop + vertex -663.691 117.265 311.571 + vertex -662.096 116.768 312.433 + vertex -662.688 117.088 312.906 + endloop + endfacet + facet normal -0.329547 -0.942559 -0.0546049 + outer loop + vertex -666.04 118.158 310.344 + vertex -663.691 117.265 311.571 + vertex -664.466 117.536 311.583 + endloop + endfacet + facet normal 0.239479 0.569076 -0.78664 + outer loop + vertex -669.575 119.439 310.195 + vertex -666.04 118.158 310.344 + vertex -667.981 118.84 310.247 + endloop + endfacet + facet normal -0.336693 -0.910139 0.241423 + outer loop + vertex -672.113 120.376 310.19 + vertex -669.575 119.439 310.195 + vertex -672.836 120.655 310.232 + endloop + endfacet + facet normal -0.338154 -0.912334 0.230863 + outer loop + vertex -674.008 121.089 310.228 + vertex -672.113 120.376 310.19 + vertex -672.836 120.655 310.232 + endloop + endfacet + facet normal -0.241784 -0.657288 0.713802 + outer loop + vertex -675.45 121.639 310.246 + vertex -674.008 121.089 310.228 + vertex -676.215 121.949 310.273 + endloop + endfacet + facet normal -0.367759 -0.91828 0.146677 + outer loop + vertex -677.609 122.502 310.242 + vertex -675.45 121.639 310.246 + vertex -676.215 121.949 310.273 + endloop + endfacet + facet normal -0.351665 -0.878794 -0.322571 + outer loop + vertex -679.593 123.292 310.254 + vertex -677.609 122.502 310.242 + vertex -678.881 122.992 310.294 + endloop + endfacet + facet normal -0.378802 -0.916953 -0.125326 + outer loop + vertex -681 123.872 310.262 + vertex -679.593 123.292 310.254 + vertex -678.881 122.992 310.294 + endloop + endfacet + facet normal -0.388431 -0.921478 -0.00058436 + outer loop + vertex -684.527 125.359 310.238 + vertex -681 123.872 310.262 + vertex -681.118 123.922 310.357 + endloop + endfacet + facet normal -0.370611 -0.887755 -0.273018 + outer loop + vertex -688.06 126.829 310.254 + vertex -684.527 125.359 310.238 + vertex -686.945 126.328 310.371 + endloop + endfacet + facet normal -0.395342 -0.895004 0.206574 + outer loop + vertex -692.782 128.32 313.841 + vertex -691.518 127.952 314.669 + vertex -696.214 129.992 314.516 + endloop + endfacet + facet normal -0.385146 -0.862376 0.328589 + outer loop + vertex -691.518 127.952 314.669 + vertex -690.571 127.966 315.813 + vertex -696.214 129.992 314.516 + endloop + endfacet + facet normal -0.340149 -0.850589 0.400995 + outer loop + vertex -690.571 127.966 315.813 + vertex -686.195 126.203 315.786 + vertex -685.937 126.636 316.925 + endloop + endfacet + facet normal -0.413345 -0.90578 -0.0933156 + outer loop + vertex -695.765 129.559 312.247 + vertex -695.627 129.452 312.673 + vertex -697.386 130.26 312.622 + endloop + endfacet + facet normal -0.418053 -0.907016 0.0505278 + outer loop + vertex -695.627 129.452 312.673 + vertex -695.216 129.298 313.307 + vertex -697.386 130.26 312.622 + endloop + endfacet + facet normal -0.391425 -0.91348 0.111088 + outer loop + vertex -695.216 129.298 313.307 + vertex -693.038 128.36 313.273 + vertex -692.782 128.32 313.841 + endloop + endfacet + facet normal -0.37844 -0.890543 -0.252421 + outer loop + vertex -695.661 129.854 310.934 + vertex -695.932 129.747 311.72 + vertex -697.93 130.681 311.418 + endloop + endfacet + facet normal -0.425393 -0.886694 -0.181145 + outer loop + vertex -695.932 129.747 311.72 + vertex -695.765 129.559 312.247 + vertex -697.386 130.26 312.622 + endloop + endfacet + facet normal -0.365487 -0.921813 -0.129151 + outer loop + vertex -690.378 127.356 312.274 + vertex -688.002 126.523 311.504 + vertex -683.076 124.487 312.09 + endloop + endfacet + facet normal -0.365627 -0.856799 -0.36361 + outer loop + vertex -690.224 127.717 310.319 + vertex -692.786 128.794 310.358 + vertex -692.267 128.613 310.262 + endloop + endfacet + facet normal -0.373437 -0.903344 -0.210983 + outer loop + vertex -681.118 123.922 310.357 + vertex -686.945 126.328 310.371 + vertex -684.527 125.359 310.238 + endloop + endfacet + facet normal -0.373141 -0.913767 -0.160612 + outer loop + vertex -686.756 126.173 310.733 + vertex -679.978 123.437 310.555 + vertex -681.409 123.931 311.066 + endloop + endfacet + facet normal -0.310238 -0.896157 0.317262 + outer loop + vertex -668.374 120.256 316.757 + vertex -670.865 120.475 314.939 + vertex -664.349 118.119 314.655 + endloop + endfacet + facet normal -0.321171 -0.916124 0.239928 + outer loop + vertex -670.865 120.475 314.939 + vertex -672.553 120.595 313.136 + vertex -666.006 118.224 312.848 + endloop + endfacet + facet normal -0.330617 -0.930725 0.156345 + outer loop + vertex -672.553 120.595 313.136 + vertex -670.088 119.49 311.77 + vertex -667.167 118.455 311.788 + endloop + endfacet + facet normal -0.369705 -0.92372 -0.1003 + outer loop + vertex -681.409 123.931 311.066 + vertex -683.076 124.487 312.09 + vertex -688.002 126.523 311.504 + endloop + endfacet + facet normal -0.349014 -0.920859 -0.173805 + outer loop + vertex -672.186 120.331 310.686 + vertex -671.502 120.139 310.329 + vertex -669.071 119.18 310.532 + endloop + endfacet + facet normal -0.360199 -0.916992 -0.171415 + outer loop + vertex -676.215 121.949 310.273 + vertex -678.881 122.992 310.294 + vertex -677.609 122.502 310.242 + endloop + endfacet + facet normal -0.383548 -0.923498 0.00647529 + outer loop + vertex -678.881 122.992 310.294 + vertex -681.118 123.922 310.357 + vertex -681 123.872 310.262 + endloop + endfacet + facet normal -0.271954 -0.730123 0.626866 + outer loop + vertex -672.836 120.655 310.232 + vertex -676.215 121.949 310.273 + vertex -674.008 121.089 310.228 + endloop + endfacet + facet normal -0.346967 -0.925806 -0.14999 + outer loop + vertex -671.502 120.139 310.329 + vertex -672.836 120.655 310.232 + vertex -669.575 119.439 310.195 + endloop + endfacet + facet normal -0.337282 -0.921506 -0.192527 + outer loop + vertex -666.815 118.377 310.42 + vertex -669.071 119.18 310.532 + vertex -667.981 118.84 310.247 + endloop + endfacet + facet normal -0.322806 -0.940433 -0.106689 + outer loop + vertex -665.733 117.951 310.901 + vertex -666.815 118.377 310.42 + vertex -666.036 118.117 310.355 + endloop + endfacet + facet normal -0.322826 -0.934502 0.149963 + outer loop + vertex -667.167 118.455 311.788 + vertex -665.173 117.745 311.658 + vertex -666.006 118.224 312.848 + endloop + endfacet + facet normal -0.28879 -0.956272 -0.0463059 + outer loop + vertex -665.173 117.745 311.658 + vertex -665.733 117.951 310.901 + vertex -664.466 117.536 311.583 + endloop + endfacet + facet normal -0.311238 -0.896399 0.315594 + outer loop + vertex -664.349 118.119 314.655 + vertex -661.982 117.87 316.283 + vertex -668.374 120.256 316.757 + endloop + endfacet + facet normal -0.300576 -0.899412 0.317351 + outer loop + vertex -658.764 116.723 316.093 + vertex -660.619 116.833 314.65 + vertex -658.725 116.347 315.066 + endloop + endfacet + facet normal -0.320768 -0.916043 0.240776 + outer loop + vertex -666.006 118.224 312.848 + vertex -664.349 118.119 314.655 + vertex -670.865 120.475 314.939 + endloop + endfacet + facet normal -0.335765 -0.903591 0.266056 + outer loop + vertex -660.619 116.833 314.65 + vertex -662.688 117.088 312.906 + vertex -660.546 116.492 313.583 + endloop + endfacet + facet normal -0.325173 -0.938003 0.120052 + outer loop + vertex -662.688 117.088 312.906 + vertex -664.466 117.536 311.583 + vertex -663.691 117.265 311.571 + endloop + endfacet + facet normal 0.334637 0.930559 -0.148586 + outer loop + vertex -666.537 118.319 310.233 + vertex -667.981 118.84 310.247 + vertex -666.04 118.158 310.344 + endloop + endfacet + facet normal 0.137119 -0.240911 -0.960812 + outer loop + vertex -666.036 118.117 310.355 + vertex -666.537 118.319 310.233 + vertex -666.04 118.158 310.344 + endloop + endfacet + facet normal -0.400971 -0.89743 0.183962 + outer loop + vertex -696.214 129.992 314.516 + vertex -695.216 129.298 313.307 + vertex -692.782 128.32 313.841 + endloop + endfacet + facet normal -0.340192 -0.85036 0.401445 + outer loop + vertex -694.287 130.283 317.572 + vertex -690.571 127.966 315.813 + vertex -685.937 126.636 316.925 + endloop + endfacet + facet normal -0.173751 -0.950758 -0.256652 + outer loop + vertex -666.04 118.158 310.344 + vertex -664.466 117.536 311.583 + vertex -665.733 117.951 310.901 + endloop + endfacet + facet normal -0.346313 -0.931671 -0.109801 + outer loop + vertex -669.575 119.439 310.195 + vertex -667.981 118.84 310.247 + vertex -671.502 120.139 310.329 + endloop + endfacet + facet normal -0.329976 -0.930563 0.158649 + outer loop + vertex -666.006 118.224 312.848 + vertex -672.553 120.595 313.136 + vertex -667.167 118.455 311.788 + endloop + endfacet + facet normal -0.34212 -0.913349 -0.220789 + outer loop + vertex -669.071 119.18 310.532 + vertex -671.502 120.139 310.329 + vertex -667.981 118.84 310.247 + endloop + endfacet + facet normal 0.865822 -0.0537188 -0.49746 + outer loop + vertex -665.733 117.951 310.901 + vertex -666.036 118.117 310.355 + vertex -666.04 118.158 310.344 + endloop + endfacet + facet normal -0.25648 -0.637239 0.726736 + outer loop + vertex -661.677 109.992 25.254 + vertex -657.13 108.66 25.6911 + vertex -661.005 110.661 26.0777 + endloop + endfacet + facet normal -0.32553 -0.757131 0.566378 + outer loop + vertex -661.251 112.225 27.715 + vertex -664.199 114.469 29.0202 + vertex -663.008 113.116 27.8956 + endloop + endfacet + facet normal -0.317286 -0.735301 0.598884 + outer loop + vertex -658.785 110.265 26.6144 + vertex -661.251 112.225 27.715 + vertex -660.688 111.318 26.8986 + endloop + endfacet + facet normal -0.333168 -0.704284 0.626884 + outer loop + vertex -657.13 108.66 25.6911 + vertex -658.785 110.265 26.6144 + vertex -658.92 110.025 26.2728 + endloop + endfacet + facet normal -0.293738 -0.721235 0.627326 + outer loop + vertex -691.407 126.363 30.0089 + vertex -694.333 127.347 29.7703 + vertex -687.713 124.441 29.5288 + endloop + endfacet + facet normal -0.304074 -0.718584 0.62544 + outer loop + vertex -660.688 111.318 26.8986 + vertex -658.92 110.025 26.2728 + vertex -658.785 110.265 26.6144 + endloop + endfacet + facet normal -0.265125 -0.650997 0.711275 + outer loop + vertex -658.92 110.025 26.2728 + vertex -661.005 110.661 26.0777 + vertex -657.13 108.66 25.6911 + endloop + endfacet + facet normal -0.310451 -0.734813 0.603051 + outer loop + vertex -663.008 113.116 27.8956 + vertex -660.688 111.318 26.8986 + vertex -661.251 112.225 27.715 + endloop + endfacet + facet normal -0.254893 -0.638336 0.726331 + outer loop + vertex -661.677 109.992 25.254 + vertex -661.005 110.661 26.0777 + vertex -667.169 112.67 25.6802 + endloop + endfacet + facet normal -0.496017 -0.696378 0.518676 + outer loop + vertex -688.718 138.817 45.1181 + vertex -684.629 135.443 44.4983 + vertex -684.422 135.831 45.2181 + endloop + endfacet + facet normal -0.454645 -0.673069 0.583332 + outer loop + vertex -689.896 138.879 44.358 + vertex -685.396 135.007 43.3981 + vertex -684.629 135.443 44.4983 + endloop + endfacet + facet normal -0.426598 -0.682739 0.593196 + outer loop + vertex -690.619 137.92 42.9942 + vertex -686.215 133.991 41.6395 + vertex -685.396 135.007 43.3981 + endloop + endfacet + facet normal -0.398688 -0.686919 0.60761 + outer loop + vertex -691.253 136.497 41.167 + vertex -687.184 132.576 39.4039 + vertex -686.215 133.991 41.6395 + endloop + endfacet + facet normal -0.367509 -0.692202 0.621123 + outer loop + vertex -692.164 134.744 38.8738 + vertex -688.43 131.024 36.9366 + vertex -687.184 132.576 39.4039 + endloop + endfacet + facet normal -0.336829 -0.703122 0.626231 + outer loop + vertex -693.419 132.898 36.3583 + vertex -690.086 129.715 34.5763 + vertex -688.43 131.024 36.9366 + endloop + endfacet + facet normal -0.450018 -0.725262 0.521036 + outer loop + vertex -684.629 135.443 44.4983 + vertex -677.512 130.951 44.3933 + vertex -684.422 135.831 45.2181 + endloop + endfacet + facet normal -0.517273 -0.788614 0.332439 + outer loop + vertex -684.422 135.831 45.2181 + vertex -677.512 130.951 44.3933 + vertex -676.842 130.803 45.085 + endloop + endfacet + facet normal -0.419948 -0.704823 0.571724 + outer loop + vertex -685.396 135.007 43.3981 + vertex -678.216 130.749 43.422 + vertex -684.629 135.443 44.4983 + endloop + endfacet + facet normal -0.460551 -0.741189 0.488397 + outer loop + vertex -684.629 135.443 44.4983 + vertex -678.216 130.749 43.422 + vertex -677.512 130.951 44.3933 + endloop + endfacet + facet normal -0.396932 -0.702455 0.590764 + outer loop + vertex -686.215 133.991 41.6395 + vertex -679.189 130.128 41.7665 + vertex -685.396 135.007 43.3981 + endloop + endfacet + facet normal -0.434289 -0.729243 0.52877 + outer loop + vertex -685.396 135.007 43.3981 + vertex -679.189 130.128 41.7665 + vertex -678.216 130.749 43.422 + endloop + endfacet + facet normal -0.37012 -0.704047 0.606076 + outer loop + vertex -687.184 132.576 39.4039 + vertex -680.404 129.112 39.52 + vertex -686.215 133.991 41.6395 + endloop + endfacet + facet normal -0.409837 -0.727244 0.55059 + outer loop + vertex -686.215 133.991 41.6395 + vertex -680.404 129.112 39.52 + vertex -679.189 130.128 41.7665 + endloop + endfacet + facet normal -0.343625 -0.70686 0.61828 + outer loop + vertex -688.43 131.024 36.9366 + vertex -681.925 127.978 37.0696 + vertex -687.184 132.576 39.4039 + endloop + endfacet + facet normal -0.323479 -0.712851 0.622258 + outer loop + vertex -690.086 129.715 34.5763 + vertex -683.625 126.9 34.7103 + vertex -688.43 131.024 36.9366 + endloop + endfacet + facet normal -0.488067 -0.820624 0.297265 + outer loop + vertex -677.512 130.951 44.3933 + vertex -669.422 126.034 44.1002 + vertex -676.842 130.803 45.085 + endloop + endfacet + facet normal -0.436442 -0.763734 0.475634 + outer loop + vertex -678.216 130.749 43.422 + vertex -670.037 125.963 43.2424 + vertex -677.512 130.951 44.3933 + endloop + endfacet + facet normal -0.465705 -0.789898 0.398974 + outer loop + vertex -677.512 130.951 44.3933 + vertex -670.037 125.963 43.2424 + vertex -669.422 126.034 44.1002 + endloop + endfacet + facet normal -0.439025 -0.767809 0.466612 + outer loop + vertex -678.216 130.749 43.422 + vertex -670.941 125.528 41.677 + vertex -670.037 125.963 43.2424 + endloop + endfacet + facet normal -0.654408 -0.731154 -0.192782 + outer loop + vertex -686.944 137.951 45.7399 + vertex -688.941 139.7 45.8842 + vertex -684.422 135.831 45.2181 + endloop + endfacet + facet normal -0.531744 -0.735855 0.419244 + outer loop + vertex -685.177 136.806 45.9715 + vertex -686.944 137.951 45.7399 + vertex -684.422 135.831 45.2181 + endloop + endfacet + facet normal -0.51683 -0.736965 0.435624 + outer loop + vertex -682.19 134.59 45.7669 + vertex -685.177 136.806 45.9715 + vertex -684.422 135.831 45.2181 + endloop + endfacet + facet normal -0.510674 -0.784498 0.351817 + outer loop + vertex -679.56 133.02 46.0823 + vertex -682.19 134.59 45.7669 + vertex -676.842 130.803 45.085 + endloop + endfacet + facet normal -0.547035 -0.792335 0.270106 + outer loop + vertex -677.188 131.291 45.8155 + vertex -679.56 133.02 46.0823 + vertex -676.842 130.803 45.085 + endloop + endfacet + facet normal -0.496303 -0.811954 0.307268 + outer loop + vertex -673.971 129.277 45.689 + vertex -677.188 131.291 45.8155 + vertex -676.842 130.803 45.085 + endloop + endfacet + facet normal -0.52263 -0.834948 0.172393 + outer loop + vertex -670.995 127.374 45.4974 + vertex -673.971 129.277 45.689 + vertex -668.441 125.611 44.6955 + endloop + endfacet + facet normal -0.462741 -0.853259 0.240458 + outer loop + vertex -664.427 123.531 45.0436 + vertex -667.216 125.095 45.2232 + vertex -668.441 125.611 44.6955 + endloop + endfacet + facet normal -0.448984 -0.830736 0.329076 + outer loop + vertex -661.706 121.935 44.7245 + vertex -664.427 123.531 45.0436 + vertex -662.192 122.025 44.2905 + endloop + endfacet + facet normal -0.414006 -0.833008 0.36701 + outer loop + vertex -654.594 118.177 44.2052 + vertex -657.824 119.837 44.3296 + vertex -654.25 117.711 43.5362 + endloop + endfacet + facet normal -0.346915 -0.847244 0.402277 + outer loop + vertex -659.979 115.909 34.4929 + vertex -657.864 116.036 36.583 + vertex -659.212 116.198 35.763 + endloop + endfacet + facet normal -0.330252 -0.849025 0.41242 + outer loop + vertex -662.292 115.947 32.7172 + vertex -659.979 115.909 34.4929 + vertex -661.448 116.121 33.7524 + endloop + endfacet + facet normal -0.462174 -0.644655 0.608946 + outer loop + vertex -688.718 138.817 45.1181 + vertex -684.422 135.831 45.2181 + vertex -688.941 139.7 45.8842 + endloop + endfacet + facet normal -0.519291 -0.791395 0.322539 + outer loop + vertex -684.422 135.831 45.2181 + vertex -676.842 130.803 45.085 + vertex -682.19 134.59 45.7669 + endloop + endfacet + facet normal -0.495841 -0.822961 0.277266 + outer loop + vertex -676.842 130.803 45.085 + vertex -668.441 125.611 44.6955 + vertex -673.971 129.277 45.689 + endloop + endfacet + facet normal -0.458508 -0.833916 0.307173 + outer loop + vertex -668.441 125.611 44.6955 + vertex -662.192 122.025 44.2905 + vertex -664.427 123.531 45.0436 + endloop + endfacet + facet normal -0.432254 -0.829346 0.354037 + outer loop + vertex -657.824 119.837 44.3296 + vertex -662.363 122.003 43.8631 + vertex -656.826 118.798 43.1131 + endloop + endfacet + facet normal -0.33253 -0.825147 0.45668 + outer loop + vertex -665.501 116.366 31.1433 + vertex -665.591 116.189 30.7579 + vertex -663.839 116.154 31.9699 + endloop + endfacet + facet normal 0.378387 -0.12209 0.91756 + outer loop + vertex 414.271 157.851 373.32 + vertex 413.414 150.031 372.633 + vertex 417.043 155.4 371.851 + endloop + endfacet + facet normal 0.392492 -0.132706 0.910131 + outer loop + vertex 417.043 155.4 371.851 + vertex 413.414 150.031 372.633 + vertex 416.593 146.194 370.703 + endloop + endfacet + facet normal 0.433267 -0.124175 0.89267 + outer loop + vertex 411.593 160.797 375.03 + vertex 410.736 153.094 374.375 + vertex 414.271 157.851 373.32 + endloop + endfacet + facet normal 0.435389 -0.126039 0.891376 + outer loop + vertex 414.271 157.851 373.32 + vertex 410.736 153.094 374.375 + vertex 413.414 150.031 372.633 + endloop + endfacet + facet normal 0.488899 -0.126651 0.863098 + outer loop + vertex 409.432 163.697 376.68 + vertex 408.47 156.162 376.119 + vertex 411.593 160.797 375.03 + endloop + endfacet + facet normal 0.490432 -0.127934 0.862038 + outer loop + vertex 411.593 160.797 375.03 + vertex 408.47 156.162 376.119 + vertex 410.736 153.094 374.375 + endloop + endfacet + facet normal 0.544755 -0.127078 0.828911 + outer loop + vertex 407.511 166.775 378.414 + vertex 406.608 159.314 377.864 + vertex 409.432 163.697 376.68 + endloop + endfacet + facet normal 0.550019 -0.131602 0.824718 + outer loop + vertex 409.432 163.697 376.68 + vertex 406.608 159.314 377.864 + vertex 408.47 156.162 376.119 + endloop + endfacet + facet normal 0.601124 -0.126514 0.789078 + outer loop + vertex 405.873 169.881 380.16 + vertex 405.012 162.497 379.632 + vertex 407.511 166.775 378.414 + endloop + endfacet + facet normal 0.606774 -0.131272 0.78396 + outer loop + vertex 407.511 166.775 378.414 + vertex 405.012 162.497 379.632 + vertex 406.608 159.314 377.864 + endloop + endfacet + facet normal 0.658154 -0.124371 0.74254 + outer loop + vertex 404.42 173.129 381.992 + vertex 403.639 165.794 381.456 + vertex 405.873 169.881 380.16 + endloop + endfacet + facet normal 0.66468 -0.130102 0.735713 + outer loop + vertex 405.873 169.881 380.16 + vertex 403.639 165.794 381.456 + vertex 405.012 162.497 379.632 + endloop + endfacet + facet normal 0.712141 -0.123551 0.691079 + outer loop + vertex 403.175 176.412 383.862 + vertex 402.442 169.19 383.326 + vertex 404.42 173.129 381.992 + endloop + endfacet + facet normal 0.71529 -0.126412 0.687299 + outer loop + vertex 404.42 173.129 381.992 + vertex 402.442 169.19 383.326 + vertex 403.639 165.794 381.456 + endloop + endfacet + facet normal 0.763201 -0.122282 0.634485 + outer loop + vertex 402.123 179.697 385.76 + vertex 401.415 172.623 385.249 + vertex 403.175 176.412 383.862 + endloop + endfacet + facet normal 0.765503 -0.124529 0.631267 + outer loop + vertex 403.175 176.412 383.862 + vertex 401.415 172.623 385.249 + vertex 402.442 169.19 383.326 + endloop + endfacet + facet normal 0.807913 -0.122525 0.576424 + outer loop + vertex 401.197 183.134 387.789 + vertex 400.532 176.092 387.225 + vertex 402.123 179.697 385.76 + endloop + endfacet + facet normal 0.807948 -0.122564 0.576366 + outer loop + vertex 402.123 179.697 385.76 + vertex 400.532 176.092 387.225 + vertex 401.415 172.623 385.249 + endloop + endfacet + facet normal 0.844797 -0.122932 0.520774 + outer loop + vertex 400.504 186.16 389.627 + vertex 399.803 179.528 389.198 + vertex 401.197 183.134 387.789 + endloop + endfacet + facet normal 0.843622 -0.121614 0.522984 + outer loop + vertex 401.197 183.134 387.789 + vertex 399.803 179.528 389.198 + vertex 400.532 176.092 387.225 + endloop + endfacet + facet normal 0.873059 -0.125859 0.471092 + outer loop + vertex 399.871 189.396 391.665 + vertex 399.194 182.848 391.17 + vertex 400.504 186.16 389.627 + endloop + endfacet + facet normal 0.870906 -0.122785 0.475864 + outer loop + vertex 400.504 186.16 389.627 + vertex 399.194 182.848 391.17 + vertex 399.803 179.528 389.198 + endloop + endfacet + facet normal 0.897704 -0.12826 0.421517 + outer loop + vertex 399.348 192.508 393.725 + vertex 398.676 186.158 393.224 + vertex 399.871 189.396 391.665 + endloop + endfacet + facet normal 0.895601 -0.124854 0.426977 + outer loop + vertex 399.871 189.396 391.665 + vertex 398.676 186.158 393.224 + vertex 399.194 182.848 391.17 + endloop + endfacet + facet normal 0.916194 -0.132269 0.378277 + outer loop + vertex 398.898 195.572 395.888 + vertex 398.235 189.572 395.395 + vertex 399.348 192.508 393.725 + endloop + endfacet + facet normal 0.913818 -0.127139 0.38571 + outer loop + vertex 399.348 192.508 393.725 + vertex 398.235 189.572 395.395 + vertex 398.676 186.158 393.224 + endloop + endfacet + facet normal 0.930168 -0.136298 0.340897 + outer loop + vertex 398.497 198.523 398.16 + vertex 397.854 193.17 397.775 + vertex 398.898 195.572 395.888 + endloop + endfacet + facet normal 0.928747 -0.131067 0.34677 + outer loop + vertex 398.898 195.572 395.888 + vertex 397.854 193.17 397.775 + vertex 398.235 189.572 395.395 + endloop + endfacet + facet normal 0.933647 -0.151506 0.324575 + outer loop + vertex 398.089 201.383 400.669 + vertex 397.465 196.994 400.416 + vertex 398.497 198.523 398.16 + endloop + endfacet + facet normal 0.93252 -0.136119 0.334483 + outer loop + vertex 398.497 198.523 398.16 + vertex 397.465 196.994 400.416 + vertex 397.854 193.17 397.775 + endloop + endfacet + facet normal 0.905272 -0.216218 0.365694 + outer loop + vertex 397.627 203.747 403.211 + vertex 397.2 200.606 402.412 + vertex 398.089 201.383 400.669 + endloop + endfacet + facet normal 0.960815 -0.0766014 0.266395 + outer loop + vertex 396.989 198.284 402.504 + vertex 397.465 196.994 400.416 + vertex 397.2 200.606 402.412 + endloop + endfacet + facet normal 0.906118 -0.151652 0.394907 + outer loop + vertex 397.465 196.994 400.416 + vertex 398.089 201.383 400.669 + vertex 397.2 200.606 402.412 + endloop + endfacet + facet normal 0.917179 -0.0574654 0.39431 + outer loop + vertex 396.198 202.953 405.666 + vertex 396.261 201.718 405.342 + vertex 396.749 202.694 404.347 + endloop + endfacet + facet normal 0.942397 -0.0427254 0.331756 + outer loop + vertex 396.194 200.506 405.374 + vertex 396.637 200.218 404.08 + vertex 396.261 201.718 405.342 + endloop + endfacet + facet normal 0.924046 -0.0822918 0.37332 + outer loop + vertex 396.637 200.218 404.08 + vertex 396.749 202.694 404.347 + vertex 396.261 201.718 405.342 + endloop + endfacet + facet normal 0.801134 -0.389157 0.454688 + outer loop + vertex 396.781 205.67 406.299 + vertex 396.368 204.124 405.703 + vertex 397.249 204.894 404.81 + endloop + endfacet + facet normal 0.902845 -0.143675 0.405251 + outer loop + vertex 396.198 202.953 405.666 + vertex 396.749 202.694 404.347 + vertex 396.368 204.124 405.703 + endloop + endfacet + facet normal 0.794765 -0.292386 0.531845 + outer loop + vertex 396.749 202.694 404.347 + vertex 397.249 204.894 404.81 + vertex 396.368 204.124 405.703 + endloop + endfacet + facet normal 0.867925 -0.283016 0.408177 + outer loop + vertex 397.249 204.894 404.81 + vertex 396.749 202.694 404.347 + vertex 397.627 203.747 403.211 + endloop + endfacet + facet normal 0.861928 -0.231997 0.450842 + outer loop + vertex 397.627 203.747 403.211 + vertex 396.749 202.694 404.347 + vertex 397.2 200.606 402.412 + endloop + endfacet + facet normal 0.94999 -0.0758785 0.302921 + outer loop + vertex 396.749 202.694 404.347 + vertex 396.637 200.218 404.08 + vertex 397.2 200.606 402.412 + endloop + endfacet + facet normal 0.949998 -0.0741576 0.303324 + outer loop + vertex 397.2 200.606 402.412 + vertex 396.637 200.218 404.08 + vertex 396.989 198.284 402.504 + endloop + endfacet + facet normal 0.797332 -0.0520659 0.601291 + outer loop + vertex 394.121 202.378 409.045 + vertex 394.228 201.311 408.811 + vertex 394.596 202.335 408.412 + endloop + endfacet + facet normal 0.803641 -0.0578267 0.592299 + outer loop + vertex 394.596 202.335 408.412 + vertex 394.228 201.311 408.811 + vertex 394.649 201.219 408.231 + endloop + endfacet + facet normal 0.799503 -0.0727018 0.596247 + outer loop + vertex 394.11 203.598 409.208 + vertex 394.121 202.378 409.045 + vertex 394.534 203.482 408.626 + endloop + endfacet + facet normal 0.795927 -0.0694032 0.601401 + outer loop + vertex 394.534 203.482 408.626 + vertex 394.121 202.378 409.045 + vertex 394.596 202.335 408.412 + endloop + endfacet + facet normal 0.82317 -0.0610703 0.564502 + outer loop + vertex 394.534 203.482 408.626 + vertex 394.596 202.335 408.412 + vertex 395.154 203.514 407.725 + endloop + endfacet + facet normal 0.831133 -0.0725155 0.551325 + outer loop + vertex 395.154 203.514 407.725 + vertex 394.596 202.335 408.412 + vertex 395.192 202.351 407.515 + endloop + endfacet + facet normal 0.832109 -0.0499831 0.552355 + outer loop + vertex 394.596 202.335 408.412 + vertex 394.649 201.219 408.231 + vertex 395.192 202.351 407.515 + endloop + endfacet + facet normal 0.837299 -0.0579669 0.543664 + outer loop + vertex 395.192 202.351 407.515 + vertex 394.649 201.219 408.231 + vertex 395.222 201.203 407.347 + endloop + endfacet + facet normal 0.813665 -0.222742 0.53697 + outer loop + vertex 394.145 204.774 409.644 + vertex 394.11 203.598 409.208 + vertex 394.602 204.717 408.927 + endloop + endfacet + facet normal 0.775546 -0.189617 0.602141 + outer loop + vertex 394.602 204.717 408.927 + vertex 394.11 203.598 409.208 + vertex 394.534 203.482 408.626 + endloop + endfacet + facet normal 0.733502 -0.452458 0.507204 + outer loop + vertex 394.209 205.868 410.527 + vertex 394.145 204.774 409.644 + vertex 395.022 206.118 409.574 + endloop + endfacet + facet normal 0.734517 -0.453235 0.505038 + outer loop + vertex 395.022 206.118 409.574 + vertex 394.145 204.774 409.644 + vertex 394.602 204.717 408.927 + endloop + endfacet + facet normal 0.753122 -0.448054 0.48172 + outer loop + vertex 395.022 206.118 409.574 + vertex 394.602 204.717 408.927 + vertex 395.714 206.184 408.554 + endloop + endfacet + facet normal 0.746703 -0.438505 0.500147 + outer loop + vertex 395.714 206.184 408.554 + vertex 394.602 204.717 408.927 + vertex 395.22 204.742 408.027 + endloop + endfacet + facet normal 0.813475 -0.179712 0.553138 + outer loop + vertex 394.602 204.717 408.927 + vertex 394.534 203.482 408.626 + vertex 395.22 204.742 408.027 + endloop + endfacet + facet normal 0.813323 -0.179489 0.553434 + outer loop + vertex 395.22 204.742 408.027 + vertex 394.534 203.482 408.626 + vertex 395.154 203.514 407.725 + endloop + endfacet + facet normal 0.85024 -0.168046 0.498851 + outer loop + vertex 395.22 204.742 408.027 + vertex 395.154 203.514 407.725 + vertex 395.841 204.633 406.932 + endloop + endfacet + facet normal 0.849634 -0.166598 0.500368 + outer loop + vertex 395.841 204.633 406.932 + vertex 395.154 203.514 407.725 + vertex 395.757 203.39 406.66 + endloop + endfacet + facet normal 0.76987 -0.434487 0.467462 + outer loop + vertex 395.714 206.184 408.554 + vertex 395.22 204.742 408.027 + vertex 396.296 206.043 407.464 + endloop + endfacet + facet normal 0.7673 -0.427986 0.477576 + outer loop + vertex 396.296 206.043 407.464 + vertex 395.22 204.742 408.027 + vertex 395.841 204.633 406.932 + endloop + endfacet + facet normal 0.779152 -0.425344 0.460439 + outer loop + vertex 396.296 206.043 407.464 + vertex 395.841 204.633 406.932 + vertex 396.781 205.67 406.299 + endloop + endfacet + facet normal 0.772131 -0.397337 0.49592 + outer loop + vertex 396.781 205.67 406.299 + vertex 395.841 204.633 406.932 + vertex 396.368 204.124 405.703 + endloop + endfacet + facet normal 0.882499 -0.156367 0.443559 + outer loop + vertex 395.841 204.633 406.932 + vertex 395.757 203.39 406.66 + vertex 396.368 204.124 405.703 + endloop + endfacet + facet normal 0.880078 -0.141853 0.453145 + outer loop + vertex 396.368 204.124 405.703 + vertex 395.757 203.39 406.66 + vertex 396.198 202.953 405.666 + endloop + endfacet + facet normal 0.870505 -0.0491937 0.489695 + outer loop + vertex 395.192 202.351 407.515 + vertex 395.222 201.203 407.347 + vertex 395.769 202.2 406.474 + endloop + endfacet + facet normal 0.872571 -0.0540017 0.485493 + outer loop + vertex 395.769 202.2 406.474 + vertex 395.222 201.203 407.347 + vertex 395.781 201.003 406.319 + endloop + endfacet + facet normal 0.865507 -0.0615919 0.497096 + outer loop + vertex 395.154 203.514 407.725 + vertex 395.192 202.351 407.515 + vertex 395.757 203.39 406.66 + endloop + endfacet + facet normal 0.868376 -0.0679814 0.491225 + outer loop + vertex 395.757 203.39 406.66 + vertex 395.192 202.351 407.515 + vertex 395.769 202.2 406.474 + endloop + endfacet + facet normal 0.90284 -0.0574897 0.426115 + outer loop + vertex 395.757 203.39 406.66 + vertex 395.769 202.2 406.474 + vertex 396.198 202.953 405.666 + endloop + endfacet + facet normal 0.905033 -0.0649262 0.420357 + outer loop + vertex 396.198 202.953 405.666 + vertex 395.769 202.2 406.474 + vertex 396.261 201.718 405.342 + endloop + endfacet + facet normal 0.909433 -0.04431 0.413483 + outer loop + vertex 395.769 202.2 406.474 + vertex 395.781 201.003 406.319 + vertex 396.261 201.718 405.342 + endloop + endfacet + facet normal 0.908083 -0.0385843 0.417009 + outer loop + vertex 396.261 201.718 405.342 + vertex 395.781 201.003 406.319 + vertex 396.194 200.506 405.374 + endloop + endfacet + facet normal 0.991763 0.0216783 -0.126238 + outer loop + vertex 393.939 204.33 409.926 + vertex 393.919 202.093 409.384 + vertex 393.913 203.285 409.543 + endloop + endfacet + facet normal 0.959515 -0.0326782 0.279754 + outer loop + vertex 393.913 203.285 409.543 + vertex 393.919 202.093 409.384 + vertex 393.961 200.952 409.104 + endloop + endfacet + facet normal 0.735294 -0.354909 0.577393 + outer loop + vertex 394.147 205.844 410.591 + vertex 393.939 204.33 409.926 + vertex 394.178 205.856 410.559 + endloop + endfacet + facet normal -0.331125 -0.316918 0.888774 + outer loop + vertex 394.178 205.856 410.559 + vertex 393.939 204.33 409.926 + vertex 393.913 203.285 409.543 + endloop + endfacet + facet normal 0.90987 -0.167277 0.379678 + outer loop + vertex 394.11 203.598 409.208 + vertex 394.145 204.774 409.644 + vertex 393.913 203.285 409.543 + endloop + endfacet + facet normal 0.719384 -0.46136 0.519262 + outer loop + vertex 394.209 205.868 410.527 + vertex 394.178 205.856 410.559 + vertex 394.145 204.774 409.644 + endloop + endfacet + facet normal 0.974301 -0.162189 0.156311 + outer loop + vertex 394.178 205.856 410.559 + vertex 393.913 203.285 409.543 + vertex 394.145 204.774 409.644 + endloop + endfacet + facet normal 0.774579 -0.0605687 0.629571 + outer loop + vertex 394.228 201.311 408.811 + vertex 394.121 202.378 409.045 + vertex 393.961 200.952 409.104 + endloop + endfacet + facet normal 0.881855 -0.0548743 0.468317 + outer loop + vertex 394.11 203.598 409.208 + vertex 393.913 203.285 409.543 + vertex 394.121 202.378 409.045 + endloop + endfacet + facet normal 0.863333 -0.075921 0.49889 + outer loop + vertex 393.913 203.285 409.543 + vertex 393.961 200.952 409.104 + vertex 394.121 202.378 409.045 + endloop + endfacet + facet normal 0.441425 -0.0837246 0.893384 + outer loop + vertex 413.414 150.031 372.633 + vertex 412.887 142.635 372.201 + vertex 416.593 146.194 370.703 + endloop + endfacet + facet normal 0.430508 -0.0696146 0.899898 + outer loop + vertex 416.593 146.194 370.703 + vertex 412.887 142.635 372.201 + vertex 415.646 138.695 370.576 + endloop + endfacet + facet normal 0.473088 -0.084864 0.876919 + outer loop + vertex 410.736 153.094 374.375 + vertex 410.185 145.944 373.98 + vertex 413.414 150.031 372.633 + endloop + endfacet + facet normal 0.473245 -0.0850213 0.876818 + outer loop + vertex 413.414 150.031 372.633 + vertex 410.185 145.944 373.98 + vertex 412.887 142.635 372.201 + endloop + endfacet + facet normal 0.533058 -0.0849427 0.841804 + outer loop + vertex 408.47 156.162 376.119 + vertex 407.807 149.07 375.823 + vertex 410.736 153.094 374.375 + endloop + endfacet + facet normal 0.53578 -0.0876465 0.839796 + outer loop + vertex 410.736 153.094 374.375 + vertex 407.807 149.07 375.823 + vertex 410.185 145.944 373.98 + endloop + endfacet + facet normal 0.598601 -0.0871716 0.79629 + outer loop + vertex 406.608 159.314 377.864 + vertex 405.985 152.477 377.584 + vertex 408.47 156.162 376.119 + endloop + endfacet + facet normal 0.600675 -0.0892847 0.794492 + outer loop + vertex 408.47 156.162 376.119 + vertex 405.985 152.477 377.584 + vertex 407.807 149.07 375.823 + endloop + endfacet + facet normal 0.657344 -0.0863098 0.748632 + outer loop + vertex 405.012 162.497 379.632 + vertex 404.505 155.62 379.284 + vertex 406.608 159.314 377.864 + endloop + endfacet + facet normal 0.662067 -0.0908089 0.743923 + outer loop + vertex 406.608 159.314 377.864 + vertex 404.505 155.62 379.284 + vertex 405.985 152.477 377.584 + endloop + endfacet + facet normal 0.715869 -0.0851597 0.693022 + outer loop + vertex 403.639 165.794 381.456 + vertex 403.168 158.759 381.077 + vertex 405.012 162.497 379.632 + endloop + endfacet + facet normal 0.718743 -0.0878616 0.689702 + outer loop + vertex 405.012 162.497 379.632 + vertex 403.168 158.759 381.077 + vertex 404.505 155.62 379.284 + endloop + endfacet + facet normal 0.764033 -0.0830789 0.639805 + outer loop + vertex 402.442 169.19 383.326 + vertex 401.994 162.198 382.953 + vertex 403.639 165.794 381.456 + endloop + endfacet + facet normal 0.766433 -0.0855093 0.636607 + outer loop + vertex 403.639 165.794 381.456 + vertex 401.994 162.198 382.953 + vertex 403.168 158.759 381.077 + endloop + endfacet + facet normal 0.810314 -0.0824953 0.58016 + outer loop + vertex 401.415 172.623 385.249 + vertex 400.97 165.729 384.89 + vertex 402.442 169.19 383.326 + endloop + endfacet + facet normal 0.810641 -0.082865 0.57965 + outer loop + vertex 402.442 169.19 383.326 + vertex 400.97 165.729 384.89 + vertex 401.994 162.198 382.953 + endloop + endfacet + facet normal 0.849012 -0.0811951 0.522097 + outer loop + vertex 400.532 176.092 387.225 + vertex 400.063 169.332 386.936 + vertex 401.415 172.623 385.249 + endloop + endfacet + facet normal 0.849577 -0.0819593 0.521059 + outer loop + vertex 401.415 172.623 385.249 + vertex 400.063 169.332 386.936 + vertex 400.97 165.729 384.89 + endloop + endfacet + facet normal 0.882092 -0.0797415 0.464279 + outer loop + vertex 399.803 179.528 389.198 + vertex 399.316 173.104 389.021 + vertex 400.532 176.092 387.225 + endloop + endfacet + facet normal 0.88282 -0.0810023 0.462675 + outer loop + vertex 400.532 176.092 387.225 + vertex 399.316 173.104 389.021 + vertex 400.063 169.332 386.936 + endloop + endfacet + facet normal 0.907808 -0.0781192 0.412047 + outer loop + vertex 399.194 182.848 391.17 + vertex 398.753 176.815 390.997 + vertex 399.803 179.528 389.198 + endloop + endfacet + facet normal 0.908816 -0.0802622 0.409405 + outer loop + vertex 399.803 179.528 389.198 + vertex 398.753 176.815 390.997 + vertex 399.316 173.104 389.021 + endloop + endfacet + facet normal 0.927762 -0.0809257 0.364292 + outer loop + vertex 398.676 186.158 393.224 + vertex 398.246 180.151 392.987 + vertex 399.194 182.848 391.17 + endloop + endfacet + facet normal 0.926644 -0.0782289 0.367711 + outer loop + vertex 399.194 182.848 391.17 + vertex 398.246 180.151 392.987 + vertex 398.753 176.815 390.997 + endloop + endfacet + facet normal 0.942403 -0.0840371 0.323752 + outer loop + vertex 398.235 189.572 395.395 + vertex 397.811 183.615 395.082 + vertex 398.676 186.158 393.224 + endloop + endfacet + facet normal 0.941214 -0.0804629 0.32809 + outer loop + vertex 398.676 186.158 393.224 + vertex 397.811 183.615 395.082 + vertex 398.246 180.151 392.987 + endloop + endfacet + facet normal 0.954722 -0.087101 0.284462 + outer loop + vertex 397.854 193.17 397.775 + vertex 397.45 187.366 397.353 + vertex 398.235 189.572 395.395 + endloop + endfacet + facet normal 0.953811 -0.0830069 0.288711 + outer loop + vertex 398.235 189.572 395.395 + vertex 397.45 187.366 397.353 + vertex 397.811 183.615 395.082 + endloop + endfacet + facet normal 0.962472 -0.080961 0.259024 + outer loop + vertex 397.465 196.994 400.416 + vertex 397.103 191.447 400.028 + vertex 397.854 193.17 397.775 + endloop + endfacet + facet normal 0.962972 -0.0855788 0.255659 + outer loop + vertex 397.854 193.17 397.775 + vertex 397.103 191.447 400.028 + vertex 397.45 187.366 397.353 + endloop + endfacet + facet normal 0.965142 -0.0571985 0.255401 + outer loop + vertex 396.989 198.284 402.504 + vertex 396.939 195.432 402.054 + vertex 397.465 196.994 400.416 + endloop + endfacet + facet normal 0.971055 -0.0753135 0.226672 + outer loop + vertex 396.72 192.8 402.118 + vertex 397.103 191.447 400.028 + vertex 396.939 195.432 402.054 + endloop + endfacet + facet normal 0.968701 -0.0796928 0.235091 + outer loop + vertex 397.103 191.447 400.028 + vertex 397.465 196.994 400.416 + vertex 396.939 195.432 402.054 + endloop + endfacet + facet normal 0.942967 -0.0531603 0.328615 + outer loop + vertex 396.162 198.025 405.145 + vertex 396.182 196.792 404.887 + vertex 396.585 197.687 403.877 + endloop + endfacet + facet normal 0.938208 -0.079118 0.336908 + outer loop + vertex 396.061 195.673 404.963 + vertex 396.47 195.117 403.691 + vertex 396.182 196.792 404.887 + endloop + endfacet + facet normal 0.945506 -0.0651016 0.31903 + outer loop + vertex 396.47 195.117 403.691 + vertex 396.585 197.687 403.877 + vertex 396.182 196.792 404.887 + endloop + endfacet + facet normal 0.94309 -0.0362548 0.330555 + outer loop + vertex 396.194 200.506 405.374 + vertex 396.245 199.234 405.089 + vertex 396.637 200.218 404.08 + endloop + endfacet + facet normal 0.943401 -0.0498702 0.327883 + outer loop + vertex 396.162 198.025 405.145 + vertex 396.585 197.687 403.877 + vertex 396.245 199.234 405.089 + endloop + endfacet + facet normal 0.94544 -0.0453101 0.322631 + outer loop + vertex 396.585 197.687 403.877 + vertex 396.637 200.218 404.08 + vertex 396.245 199.234 405.089 + endloop + endfacet + facet normal 0.963177 -0.041112 0.265707 + outer loop + vertex 396.637 200.218 404.08 + vertex 396.585 197.687 403.877 + vertex 396.989 198.284 402.504 + endloop + endfacet + facet normal 0.964205 -0.0577182 0.258799 + outer loop + vertex 396.989 198.284 402.504 + vertex 396.585 197.687 403.877 + vertex 396.939 195.432 402.054 + endloop + endfacet + facet normal 0.962643 -0.0618551 0.263614 + outer loop + vertex 396.585 197.687 403.877 + vertex 396.47 195.117 403.691 + vertex 396.939 195.432 402.054 + endloop + endfacet + facet normal 0.962443 -0.0737637 0.261271 + outer loop + vertex 396.939 195.432 402.054 + vertex 396.47 195.117 403.691 + vertex 396.72 192.8 402.118 + endloop + endfacet + facet normal 0.794973 -0.105821 0.597344 + outer loop + vertex 394.246 197.936 408.348 + vertex 394.281 196.925 408.122 + vertex 394.683 197.866 407.754 + endloop + endfacet + facet normal 0.799616 -0.110583 0.590242 + outer loop + vertex 394.683 197.866 407.754 + vertex 394.281 196.925 408.122 + vertex 394.655 196.779 407.587 + endloop + endfacet + facet normal 0.802966 -0.0966083 0.588144 + outer loop + vertex 394.299 199.106 408.467 + vertex 394.246 197.936 408.348 + vertex 394.691 198.985 407.912 + endloop + endfacet + facet normal 0.797085 -0.0904015 0.597063 + outer loop + vertex 394.691 198.985 407.912 + vertex 394.246 197.936 408.348 + vertex 394.683 197.866 407.754 + endloop + endfacet + facet normal 0.837895 -0.0825466 0.539553 + outer loop + vertex 394.691 198.985 407.912 + vertex 394.683 197.866 407.754 + vertex 395.233 198.877 407.053 + endloop + endfacet + facet normal 0.83698 -0.0808939 0.541221 + outer loop + vertex 395.233 198.877 407.053 + vertex 394.683 197.866 407.754 + vertex 395.212 197.726 406.914 + endloop + endfacet + facet normal 0.833359 -0.104186 0.542823 + outer loop + vertex 394.683 197.866 407.754 + vertex 394.655 196.779 407.587 + vertex 395.212 197.726 406.914 + endloop + endfacet + facet normal 0.830179 -0.0980605 0.548805 + outer loop + vertex 395.212 197.726 406.914 + vertex 394.655 196.779 407.587 + vertex 395.17 196.626 406.781 + endloop + endfacet + facet normal 0.800961 -0.0681089 0.594829 + outer loop + vertex 394.226 200.143 408.684 + vertex 394.299 199.106 408.467 + vertex 394.679 200.105 408.07 + endloop + endfacet + facet normal 0.806932 -0.0738815 0.586005 + outer loop + vertex 394.679 200.105 408.07 + vertex 394.299 199.106 408.467 + vertex 394.691 198.985 407.912 + endloop + endfacet + facet normal 0.802648 -0.0656847 0.592826 + outer loop + vertex 394.228 201.311 408.811 + vertex 394.226 200.143 408.684 + vertex 394.649 201.219 408.231 + endloop + endfacet + facet normal 0.801277 -0.0643004 0.594828 + outer loop + vertex 394.649 201.219 408.231 + vertex 394.226 200.143 408.684 + vertex 394.679 200.105 408.07 + endloop + endfacet + facet normal 0.83741 -0.055979 0.543701 + outer loop + vertex 394.649 201.219 408.231 + vertex 394.679 200.105 408.07 + vertex 395.222 201.203 407.347 + endloop + endfacet + facet normal 0.840512 -0.0610457 0.538344 + outer loop + vertex 395.222 201.203 407.347 + vertex 394.679 200.105 408.07 + vertex 395.235 200.041 407.195 + endloop + endfacet + facet normal 0.84001 -0.0667999 0.538444 + outer loop + vertex 394.679 200.105 408.07 + vertex 394.691 198.985 407.912 + vertex 395.235 200.041 407.195 + endloop + endfacet + facet normal 0.839834 -0.0664992 0.538754 + outer loop + vertex 395.235 200.041 407.195 + vertex 394.691 198.985 407.912 + vertex 395.233 198.877 407.053 + endloop + endfacet + facet normal 0.871859 -0.0601258 0.486052 + outer loop + vertex 395.235 200.041 407.195 + vertex 395.233 198.877 407.053 + vertex 395.782 199.791 406.183 + endloop + endfacet + facet normal 0.871901 -0.0602365 0.485962 + outer loop + vertex 395.782 199.791 406.183 + vertex 395.233 198.877 407.053 + vertex 395.768 198.582 406.057 + endloop + endfacet + facet normal 0.872598 -0.0537937 0.485467 + outer loop + vertex 395.222 201.203 407.347 + vertex 395.235 200.041 407.195 + vertex 395.781 201.003 406.319 + endloop + endfacet + facet normal 0.87278 -0.0542384 0.485092 + outer loop + vertex 395.781 201.003 406.319 + vertex 395.235 200.041 407.195 + vertex 395.782 199.791 406.183 + endloop + endfacet + facet normal 0.906066 -0.0469513 0.420524 + outer loop + vertex 395.781 201.003 406.319 + vertex 395.782 199.791 406.183 + vertex 396.194 200.506 405.374 + endloop + endfacet + facet normal 0.9087 -0.0562602 0.41364 + outer loop + vertex 396.194 200.506 405.374 + vertex 395.782 199.791 406.183 + vertex 396.245 199.234 405.089 + endloop + endfacet + facet normal 0.909499 -0.0529885 0.412315 + outer loop + vertex 395.782 199.791 406.183 + vertex 395.768 198.582 406.057 + vertex 396.245 199.234 405.089 + endloop + endfacet + facet normal 0.907464 -0.0432136 0.417901 + outer loop + vertex 396.245 199.234 405.089 + vertex 395.768 198.582 406.057 + vertex 396.162 198.025 405.145 + endloop + endfacet + facet normal 0.862864 -0.0930106 0.496804 + outer loop + vertex 395.212 197.726 406.914 + vertex 395.17 196.626 406.781 + vertex 395.737 197.407 405.944 + endloop + endfacet + facet normal 0.860297 -0.0848503 0.502682 + outer loop + vertex 395.737 197.407 405.944 + vertex 395.17 196.626 406.781 + vertex 395.686 196.297 405.844 + endloop + endfacet + facet normal 0.86911 -0.0751357 0.488878 + outer loop + vertex 395.233 198.877 407.053 + vertex 395.212 197.726 406.914 + vertex 395.768 198.582 406.057 + endloop + endfacet + facet normal 0.867627 -0.070916 0.492132 + outer loop + vertex 395.768 198.582 406.057 + vertex 395.212 197.726 406.914 + vertex 395.737 197.407 405.944 + endloop + endfacet + facet normal 0.900988 -0.0657133 0.428839 + outer loop + vertex 395.768 198.582 406.057 + vertex 395.737 197.407 405.944 + vertex 396.162 198.025 405.145 + endloop + endfacet + facet normal 0.902832 -0.0737317 0.423624 + outer loop + vertex 396.162 198.025 405.145 + vertex 395.737 197.407 405.944 + vertex 396.182 196.792 404.887 + endloop + endfacet + facet normal 0.901005 -0.0798228 0.426401 + outer loop + vertex 395.737 197.407 405.944 + vertex 395.686 196.297 405.844 + vertex 396.182 196.792 404.887 + endloop + endfacet + facet normal 0.899512 -0.0684507 0.431501 + outer loop + vertex 396.182 196.792 404.887 + vertex 395.686 196.297 405.844 + vertex 396.061 195.673 404.963 + endloop + endfacet + facet normal 0.662364 -0.138394 0.736289 + outer loop + vertex 393.948 199.701 408.977 + vertex 393.888 197.021 408.528 + vertex 394.001 198.655 408.733 + endloop + endfacet + facet normal 0.61538 -0.140096 0.775681 + outer loop + vertex 394.001 198.655 408.733 + vertex 393.888 197.021 408.528 + vertex 393.948 196.464 408.379 + endloop + endfacet + facet normal 0.947715 -0.042093 0.316329 + outer loop + vertex 393.919 202.093 409.384 + vertex 393.948 199.701 408.977 + vertex 393.961 200.952 409.104 + endloop + endfacet + facet normal 0.906919 -0.0520249 0.418081 + outer loop + vertex 393.961 200.952 409.104 + vertex 393.948 199.701 408.977 + vertex 394.001 198.655 408.733 + endloop + endfacet + facet normal 0.734701 -0.0890684 0.672518 + outer loop + vertex 394.299 199.106 408.467 + vertex 394.226 200.143 408.684 + vertex 394.001 198.655 408.733 + endloop + endfacet + facet normal 0.778928 -0.0689286 0.623314 + outer loop + vertex 394.228 201.311 408.811 + vertex 393.961 200.952 409.104 + vertex 394.226 200.143 408.684 + endloop + endfacet + facet normal 0.752548 -0.0924441 0.652016 + outer loop + vertex 393.961 200.952 409.104 + vertex 394.001 198.655 408.733 + vertex 394.226 200.143 408.684 + endloop + endfacet + facet normal 0.712758 -0.129333 0.689383 + outer loop + vertex 394.281 196.925 408.122 + vertex 394.246 197.936 408.348 + vertex 393.948 196.464 408.379 + endloop + endfacet + facet normal 0.74322 -0.101317 0.661331 + outer loop + vertex 394.299 199.106 408.467 + vertex 394.001 198.655 408.733 + vertex 394.246 197.936 408.348 + endloop + endfacet + facet normal 0.710476 -0.128821 0.69183 + outer loop + vertex 394.001 198.655 408.733 + vertex 393.948 196.464 408.379 + vertex 394.246 197.936 408.348 + endloop + endfacet + facet normal 0.426594 -0.0730123 0.901491 + outer loop + vertex 412.887 142.635 372.201 + vertex 412.316 135.947 371.929 + vertex 415.646 138.695 370.576 + endloop + endfacet + facet normal 0.426634 -0.0730717 0.901468 + outer loop + vertex 415.646 138.695 370.576 + vertex 412.316 135.947 371.929 + vertex 415.374 132.883 370.234 + endloop + endfacet + facet normal 0.478318 -0.0796672 0.874566 + outer loop + vertex 410.185 145.944 373.98 + vertex 410.089 140.293 373.517 + vertex 412.887 142.635 372.201 + endloop + endfacet + facet normal 0.476133 -0.076214 0.876064 + outer loop + vertex 412.887 142.635 372.201 + vertex 410.089 140.293 373.517 + vertex 412.316 135.947 371.929 + endloop + endfacet + facet normal 0.54233 -0.0805983 0.836291 + outer loop + vertex 407.807 149.07 375.823 + vertex 407.355 142.325 375.466 + vertex 410.185 145.944 373.98 + endloop + endfacet + facet normal 0.5397 -0.0777322 0.838261 + outer loop + vertex 410.185 145.944 373.98 + vertex 407.355 142.325 375.466 + vertex 410.089 140.293 373.517 + endloop + endfacet + facet normal 0.612776 -0.0785993 0.786338 + outer loop + vertex 405.985 152.477 377.584 + vertex 405.363 146.707 377.491 + vertex 407.807 149.07 375.823 + endloop + endfacet + facet normal 0.615183 -0.0827176 0.784033 + outer loop + vertex 407.807 149.07 375.823 + vertex 405.363 146.707 377.491 + vertex 407.355 142.325 375.466 + endloop + endfacet + facet normal 0.670253 -0.0834391 0.737427 + outer loop + vertex 404.505 155.62 379.284 + vertex 404.244 150.343 378.924 + vertex 405.985 152.477 377.584 + endloop + endfacet + facet normal 0.670659 -0.0840458 0.736989 + outer loop + vertex 405.985 152.477 377.584 + vertex 404.244 150.343 378.924 + vertex 405.363 146.707 377.491 + endloop + endfacet + facet normal 0.722008 -0.0847437 0.686676 + outer loop + vertex 403.168 158.759 381.077 + vertex 402.938 152.55 380.553 + vertex 404.505 155.62 379.284 + endloop + endfacet + facet normal 0.719853 -0.0826029 0.689194 + outer loop + vertex 404.505 155.62 379.284 + vertex 402.938 152.55 380.553 + vertex 404.244 150.343 378.924 + endloop + endfacet + facet normal 0.766459 -0.0854853 0.636579 + outer loop + vertex 401.994 162.198 382.953 + vertex 401.687 155.876 382.474 + vertex 403.168 158.759 381.077 + endloop + endfacet + facet normal 0.763794 -0.0823703 0.640182 + outer loop + vertex 403.168 158.759 381.077 + vertex 401.687 155.876 382.474 + vertex 402.938 152.55 380.553 + endloop + endfacet + facet normal 0.806335 -0.087058 0.585018 + outer loop + vertex 400.97 165.729 384.89 + vertex 400.638 159.484 384.418 + vertex 401.994 162.198 382.953 + endloop + endfacet + facet normal 0.803828 -0.0836859 0.588946 + outer loop + vertex 401.994 162.198 382.953 + vertex 400.638 159.484 384.418 + vertex 401.687 155.876 382.474 + endloop + endfacet + facet normal 0.842727 -0.0892653 0.530889 + outer loop + vertex 400.063 169.332 386.936 + vertex 399.706 163.11 386.455 + vertex 400.97 165.729 384.89 + endloop + endfacet + facet normal 0.840102 -0.0851213 0.535707 + outer loop + vertex 400.97 165.729 384.89 + vertex 399.706 163.11 386.455 + vertex 400.638 159.484 384.418 + endloop + endfacet + facet normal 0.873434 -0.0914835 0.478272 + outer loop + vertex 399.316 173.104 389.021 + vertex 398.759 166.879 388.848 + vertex 400.063 169.332 386.936 + endloop + endfacet + facet normal 0.871543 -0.0871757 0.482508 + outer loop + vertex 400.063 169.332 386.936 + vertex 398.759 166.879 388.848 + vertex 399.706 163.11 386.455 + endloop + endfacet + facet normal 0.902324 -0.0879481 0.421991 + outer loop + vertex 398.753 176.815 390.997 + vertex 398.245 171.679 391.015 + vertex 399.316 173.104 389.021 + endloop + endfacet + facet normal 0.903172 -0.0924968 0.419195 + outer loop + vertex 399.316 173.104 389.021 + vertex 398.245 171.679 391.015 + vertex 398.759 166.879 388.848 + endloop + endfacet + facet normal 0.921214 -0.0860397 0.379423 + outer loop + vertex 398.246 180.151 392.987 + vertex 397.931 175.379 392.667 + vertex 398.753 176.815 390.997 + endloop + endfacet + facet normal 0.922074 -0.0900608 0.376389 + outer loop + vertex 398.753 176.815 390.997 + vertex 397.931 175.379 392.667 + vertex 398.245 171.679 391.015 + endloop + endfacet + facet normal 0.931829 -0.0950357 0.350233 + outer loop + vertex 397.811 183.615 395.082 + vertex 397.316 178.009 394.88 + vertex 398.246 180.151 392.987 + endloop + endfacet + facet normal 0.929069 -0.0852529 0.359949 + outer loop + vertex 398.246 180.151 392.987 + vertex 397.316 178.009 394.88 + vertex 397.931 175.379 392.667 + endloop + endfacet + facet normal 0.947061 -0.0946043 0.3068 + outer loop + vertex 397.45 187.366 397.353 + vertex 397.126 182.429 396.831 + vertex 397.811 183.615 395.082 + endloop + endfacet + facet normal 0.947083 -0.0948123 0.306668 + outer loop + vertex 397.811 183.615 395.082 + vertex 397.126 182.429 396.831 + vertex 397.316 178.009 394.88 + endloop + endfacet + facet normal 0.951875 -0.107159 0.287141 + outer loop + vertex 397.103 191.447 400.028 + vertex 396.661 185.533 399.286 + vertex 397.45 187.366 397.353 + endloop + endfacet + facet normal 0.949685 -0.0939303 0.29879 + outer loop + vertex 397.45 187.366 397.353 + vertex 396.661 185.533 399.286 + vertex 397.126 182.429 396.831 + endloop + endfacet + facet normal 0.961165 -0.115286 0.25074 + outer loop + vertex 396.72 192.8 402.118 + vertex 396.484 189.638 401.568 + vertex 397.103 191.447 400.028 + endloop + endfacet + facet normal 0.92463 -0.153858 0.348405 + outer loop + vertex 396.05 186.805 401.469 + vertex 396.661 185.533 399.286 + vertex 396.484 189.638 401.568 + endloop + endfacet + facet normal 0.959244 -0.104621 0.262498 + outer loop + vertex 396.661 185.533 399.286 + vertex 397.103 191.447 400.028 + vertex 396.484 189.638 401.568 + endloop + endfacet + facet normal 0.912013 -0.159281 0.377971 + outer loop + vertex 395.866 193.316 404.748 + vertex 395.744 191.905 404.447 + vertex 396.24 192.447 403.479 + endloop + endfacet + facet normal 0.880603 -0.199672 0.429732 + outer loop + vertex 395.491 190.835 404.468 + vertex 395.805 189.711 403.303 + vertex 395.744 191.905 404.447 + endloop + endfacet + facet normal 0.91242 -0.169059 0.372704 + outer loop + vertex 395.805 189.711 403.303 + vertex 396.24 192.447 403.479 + vertex 395.744 191.905 404.447 + endloop + endfacet + facet normal 0.935054 -0.0931854 0.342038 + outer loop + vertex 396.061 195.673 404.963 + vertex 396.032 194.435 404.703 + vertex 396.47 195.117 403.691 + endloop + endfacet + facet normal 0.925699 -0.123549 0.357514 + outer loop + vertex 395.866 193.316 404.748 + vertex 396.24 192.447 403.479 + vertex 396.032 194.435 404.703 + endloop + endfacet + facet normal 0.936729 -0.107408 0.33317 + outer loop + vertex 396.24 192.447 403.479 + vertex 396.47 195.117 403.691 + vertex 396.032 194.435 404.703 + endloop + endfacet + facet normal 0.946032 -0.106069 0.306223 + outer loop + vertex 396.47 195.117 403.691 + vertex 396.24 192.447 403.479 + vertex 396.72 192.8 402.118 + endloop + endfacet + facet normal 0.94546 -0.122963 0.301637 + outer loop + vertex 396.72 192.8 402.118 + vertex 396.24 192.447 403.479 + vertex 396.484 189.638 401.568 + endloop + endfacet + facet normal 0.915319 -0.169059 0.365528 + outer loop + vertex 396.24 192.447 403.479 + vertex 395.805 189.711 403.303 + vertex 396.484 189.638 401.568 + endloop + endfacet + facet normal 0.917923 -0.153436 0.365888 + outer loop + vertex 396.484 189.638 401.568 + vertex 395.805 189.711 403.303 + vertex 396.05 186.805 401.469 + endloop + endfacet + facet normal 0.760486 -0.188185 0.621489 + outer loop + vertex 394.053 194.009 407.667 + vertex 394.022 193.233 407.469 + vertex 394.459 193.907 407.139 + endloop + endfacet + facet normal 0.763425 -0.192518 0.616537 + outer loop + vertex 394.459 193.907 407.139 + vertex 394.022 193.233 407.469 + vertex 394.353 193.017 406.992 + endloop + endfacet + facet normal 0.772657 -0.180372 0.608661 + outer loop + vertex 394.181 194.934 407.778 + vertex 394.053 194.009 407.667 + vertex 394.54 194.805 407.284 + endloop + endfacet + facet normal 0.76497 -0.16957 0.621343 + outer loop + vertex 394.54 194.805 407.284 + vertex 394.053 194.009 407.667 + vertex 394.459 193.907 407.139 + endloop + endfacet + facet normal 0.802968 -0.165119 0.572693 + outer loop + vertex 394.54 194.805 407.284 + vertex 394.459 193.907 407.139 + vertex 395.039 194.632 406.535 + endloop + endfacet + facet normal 0.80114 -0.160428 0.576574 + outer loop + vertex 395.039 194.632 406.535 + vertex 394.459 193.907 407.139 + vertex 394.943 193.644 406.394 + endloop + endfacet + facet normal 0.791585 -0.189966 0.58078 + outer loop + vertex 394.459 193.907 407.139 + vertex 394.353 193.017 406.992 + vertex 394.943 193.644 406.394 + endloop + endfacet + facet normal 0.79242 -0.192696 0.57874 + outer loop + vertex 394.943 193.644 406.394 + vertex 394.353 193.017 406.992 + vertex 394.801 192.571 406.23 + endloop + endfacet + facet normal 0.781149 -0.147115 0.606764 + outer loop + vertex 394.186 195.839 407.991 + vertex 394.181 194.934 407.778 + vertex 394.607 195.753 407.429 + endloop + endfacet + facet normal 0.781393 -0.147405 0.60638 + outer loop + vertex 394.607 195.753 407.429 + vertex 394.181 194.934 407.778 + vertex 394.54 194.805 407.284 + endloop + endfacet + facet normal 0.792447 -0.140785 0.593471 + outer loop + vertex 394.281 196.925 408.122 + vertex 394.186 195.839 407.991 + vertex 394.655 196.779 407.587 + endloop + endfacet + facet normal 0.784165 -0.131037 0.60656 + outer loop + vertex 394.655 196.779 407.587 + vertex 394.186 195.839 407.991 + vertex 394.607 195.753 407.429 + endloop + endfacet + facet normal 0.825378 -0.12437 0.550712 + outer loop + vertex 394.655 196.779 407.587 + vertex 394.607 195.753 407.429 + vertex 395.17 196.626 406.781 + endloop + endfacet + facet normal 0.820564 -0.114379 0.559993 + outer loop + vertex 395.17 196.626 406.781 + vertex 394.607 195.753 407.429 + vertex 395.112 195.602 406.658 + endloop + endfacet + facet normal 0.814817 -0.142951 0.561817 + outer loop + vertex 394.607 195.753 407.429 + vertex 394.54 194.805 407.284 + vertex 395.112 195.602 406.658 + endloop + endfacet + facet normal 0.810535 -0.133174 0.570348 + outer loop + vertex 395.112 195.602 406.658 + vertex 394.54 194.805 407.284 + vertex 395.039 194.632 406.535 + endloop + endfacet + facet normal 0.844264 -0.129372 0.520079 + outer loop + vertex 395.112 195.602 406.658 + vertex 395.039 194.632 406.535 + vertex 395.618 195.233 405.744 + endloop + endfacet + facet normal 0.843771 -0.127116 0.521433 + outer loop + vertex 395.618 195.233 405.744 + vertex 395.039 194.632 406.535 + vertex 395.528 194.165 405.63 + endloop + endfacet + facet normal 0.85419 -0.110065 0.508178 + outer loop + vertex 395.17 196.626 406.781 + vertex 395.112 195.602 406.658 + vertex 395.686 196.297 405.844 + endloop + endfacet + facet normal 0.852044 -0.102178 0.513401 + outer loop + vertex 395.686 196.297 405.844 + vertex 395.112 195.602 406.658 + vertex 395.618 195.233 405.744 + endloop + endfacet + facet normal 0.888553 -0.0984292 0.448092 + outer loop + vertex 395.686 196.297 405.844 + vertex 395.618 195.233 405.744 + vertex 396.061 195.673 404.963 + endloop + endfacet + facet normal 0.890387 -0.112916 0.440978 + outer loop + vertex 396.061 195.673 404.963 + vertex 395.618 195.233 405.744 + vertex 396.032 194.435 404.703 + endloop + endfacet + facet normal 0.886198 -0.122654 0.446776 + outer loop + vertex 395.618 195.233 405.744 + vertex 395.528 194.165 405.63 + vertex 396.032 194.435 404.703 + endloop + endfacet + facet normal 0.886106 -0.114019 0.449239 + outer loop + vertex 396.032 194.435 404.703 + vertex 395.528 194.165 405.63 + vertex 395.866 193.316 404.748 + endloop + endfacet + facet normal 0.816681 -0.190712 0.544666 + outer loop + vertex 394.943 193.644 406.394 + vertex 394.801 192.571 406.23 + vertex 395.403 193.008 405.48 + endloop + endfacet + facet normal 0.817506 -0.199242 0.540358 + outer loop + vertex 395.403 193.008 405.48 + vertex 394.801 192.571 406.23 + vertex 395.214 191.693 405.281 + endloop + endfacet + facet normal 0.832782 -0.15697 0.530881 + outer loop + vertex 395.039 194.632 406.535 + vertex 394.943 193.644 406.394 + vertex 395.528 194.165 405.63 + endloop + endfacet + facet normal 0.832979 -0.158166 0.530216 + outer loop + vertex 395.528 194.165 405.63 + vertex 394.943 193.644 406.394 + vertex 395.403 193.008 405.48 + endloop + endfacet + facet normal 0.863477 -0.154981 0.479989 + outer loop + vertex 395.528 194.165 405.63 + vertex 395.403 193.008 405.48 + vertex 395.866 193.316 404.748 + endloop + endfacet + facet normal 0.864087 -0.175127 0.471893 + outer loop + vertex 395.866 193.316 404.748 + vertex 395.403 193.008 405.48 + vertex 395.744 191.905 404.447 + endloop + endfacet + facet normal 0.849608 -0.196165 0.489577 + outer loop + vertex 395.403 193.008 405.48 + vertex 395.214 191.693 405.281 + vertex 395.744 191.905 404.447 + endloop + endfacet + facet normal 0.849903 -0.191199 0.491028 + outer loop + vertex 395.744 191.905 404.447 + vertex 395.214 191.693 405.281 + vertex 395.491 190.835 404.468 + endloop + endfacet + facet normal 0.567858 -0.198113 0.798929 + outer loop + vertex 393.736 195.05 408.231 + vertex 393.588 193.435 407.936 + vertex 393.834 194.564 408.041 + endloop + endfacet + facet normal 0.595849 -0.202181 0.77723 + outer loop + vertex 393.834 194.564 408.041 + vertex 393.588 193.435 407.936 + vertex 393.678 192.991 407.751 + endloop + endfacet + facet normal 0.522862 -0.166257 0.836046 + outer loop + vertex 393.888 197.021 408.528 + vertex 393.736 195.05 408.231 + vertex 393.948 196.464 408.379 + endloop + endfacet + facet normal 0.621538 -0.173554 0.763917 + outer loop + vertex 393.948 196.464 408.379 + vertex 393.736 195.05 408.231 + vertex 393.834 194.564 408.041 + endloop + endfacet + facet normal 0.701822 -0.166794 0.69255 + outer loop + vertex 394.181 194.934 407.778 + vertex 394.186 195.839 407.991 + vertex 393.834 194.564 408.041 + endloop + endfacet + facet normal 0.723127 -0.144622 0.675405 + outer loop + vertex 394.281 196.925 408.122 + vertex 393.948 196.464 408.379 + vertex 394.186 195.839 407.991 + endloop + endfacet + facet normal 0.699365 -0.166009 0.695219 + outer loop + vertex 393.948 196.464 408.379 + vertex 393.834 194.564 408.041 + vertex 394.186 195.839 407.991 + endloop + endfacet + facet normal 0.701709 -0.201691 0.683319 + outer loop + vertex 394.022 193.233 407.469 + vertex 394.053 194.009 407.667 + vertex 393.678 192.991 407.751 + endloop + endfacet + facet normal 0.708477 -0.180316 0.68231 + outer loop + vertex 394.181 194.934 407.778 + vertex 393.834 194.564 408.041 + vertex 394.053 194.009 407.667 + endloop + endfacet + facet normal 0.690616 -0.196564 0.695998 + outer loop + vertex 393.834 194.564 408.041 + vertex 393.678 192.991 407.751 + vertex 394.053 194.009 407.667 + endloop + endfacet + facet normal 0.733423 -0.255571 0.6299 + outer loop + vertex 393.61 191.108 407.182 + vertex 393.564 190.498 406.988 + vertex 393.867 190.546 406.655 + endloop + endfacet + facet normal 0.732104 -0.265694 0.627241 + outer loop + vertex 393.867 190.546 406.655 + vertex 393.564 190.498 406.988 + vertex 393.808 189.868 406.436 + endloop + endfacet + facet normal 0.73901 -0.249075 0.62596 + outer loop + vertex 393.777 191.73 407.232 + vertex 393.61 191.108 407.182 + vertex 394.024 191.286 406.764 + endloop + endfacet + facet normal 0.739012 -0.249251 0.625887 + outer loop + vertex 394.024 191.286 406.764 + vertex 393.61 191.108 407.182 + vertex 393.867 190.546 406.655 + endloop + endfacet + facet normal 0.761815 -0.249906 0.59765 + outer loop + vertex 394.024 191.286 406.764 + vertex 393.867 190.546 406.655 + vertex 394.316 190.623 406.113 + endloop + endfacet + facet normal 0.76115 -0.254891 0.596391 + outer loop + vertex 394.316 190.623 406.113 + vertex 393.867 190.546 406.655 + vertex 394.221 189.805 405.885 + endloop + endfacet + facet normal 0.758069 -0.258721 0.598661 + outer loop + vertex 393.867 190.546 406.655 + vertex 393.808 189.868 406.436 + vertex 394.221 189.805 405.885 + endloop + endfacet + facet normal 0.760481 -0.249698 0.599432 + outer loop + vertex 394.221 189.805 405.885 + vertex 393.808 189.868 406.436 + vertex 394.076 189.297 405.858 + endloop + endfacet + facet normal 0.748279 -0.224416 0.624272 + outer loop + vertex 393.862 192.44 407.386 + vertex 393.777 191.73 407.232 + vertex 394.207 192.114 406.854 + endloop + endfacet + facet normal 0.750861 -0.233777 0.617702 + outer loop + vertex 394.207 192.114 406.854 + vertex 393.777 191.73 407.232 + vertex 394.024 191.286 406.764 + endloop + endfacet + facet normal 0.753042 -0.217896 0.620845 + outer loop + vertex 394.022 193.233 407.469 + vertex 393.862 192.44 407.386 + vertex 394.353 193.017 406.992 + endloop + endfacet + facet normal 0.752409 -0.2165 0.6221 + outer loop + vertex 394.353 193.017 406.992 + vertex 393.862 192.44 407.386 + vertex 394.207 192.114 406.854 + endloop + endfacet + facet normal 0.781342 -0.215638 0.585666 + outer loop + vertex 394.353 193.017 406.992 + vertex 394.207 192.114 406.854 + vertex 394.801 192.571 406.23 + endloop + endfacet + facet normal 0.782488 -0.223014 0.581358 + outer loop + vertex 394.801 192.571 406.23 + vertex 394.207 192.114 406.854 + vertex 394.592 191.424 406.071 + endloop + endfacet + facet normal 0.773691 -0.235608 0.588125 + outer loop + vertex 394.207 192.114 406.854 + vertex 394.024 191.286 406.764 + vertex 394.592 191.424 406.071 + endloop + endfacet + facet normal 0.773713 -0.235375 0.588189 + outer loop + vertex 394.592 191.424 406.071 + vertex 394.024 191.286 406.764 + vertex 394.316 190.623 406.113 + endloop + endfacet + facet normal 0.801375 -0.222794 0.555122 + outer loop + vertex 394.801 192.571 406.23 + vertex 394.592 191.424 406.071 + vertex 395.214 191.693 405.281 + endloop + endfacet + facet normal 0.815081 -0.237748 0.528317 + outer loop + vertex 395.491 190.835 404.468 + vertex 395.214 191.693 405.281 + vertex 394.947 189.94 404.904 + endloop + endfacet + facet normal 0.795981 -0.244884 0.553576 + outer loop + vertex 394.316 190.623 406.113 + vertex 394.947 189.94 404.904 + vertex 394.592 191.424 406.071 + endloop + endfacet + facet normal 0.800771 -0.239978 0.548795 + outer loop + vertex 395.214 191.693 405.281 + vertex 394.592 191.424 406.071 + vertex 394.947 189.94 404.904 + endloop + endfacet + facet normal 0.794876 -0.247029 0.55421 + outer loop + vertex 394.316 190.623 406.113 + vertex 394.221 189.805 405.885 + vertex 394.947 189.94 404.904 + endloop + endfacet + facet normal 0.783107 -0.2545 0.567426 + outer loop + vertex 394.076 189.297 405.858 + vertex 394.486 188.651 405.002 + vertex 394.221 189.805 405.885 + endloop + endfacet + facet normal 0.795522 -0.242394 0.555328 + outer loop + vertex 394.486 188.651 405.002 + vertex 394.947 189.94 404.904 + vertex 394.221 189.805 405.885 + endloop + endfacet + facet normal 0.600474 -0.239521 0.762929 + outer loop + vertex 393.451 192.22 407.713 + vertex 393.367 191.301 407.491 + vertex 393.509 191.75 407.521 + endloop + endfacet + facet normal 0.651546 -0.2525 0.715354 + outer loop + vertex 393.509 191.75 407.521 + vertex 393.367 191.301 407.491 + vertex 393.411 190.864 407.297 + endloop + endfacet + facet normal 0.580529 -0.209312 0.786877 + outer loop + vertex 393.588 193.435 407.936 + vertex 393.451 192.22 407.713 + vertex 393.678 192.991 407.751 + endloop + endfacet + facet normal 0.638575 -0.223926 0.73626 + outer loop + vertex 393.678 192.991 407.751 + vertex 393.451 192.22 407.713 + vertex 393.509 191.75 407.521 + endloop + endfacet + facet normal 0.70489 -0.229354 0.671213 + outer loop + vertex 393.777 191.73 407.232 + vertex 393.862 192.44 407.386 + vertex 393.509 191.75 407.521 + endloop + endfacet + facet normal 0.704708 -0.213939 0.676473 + outer loop + vertex 394.022 193.233 407.469 + vertex 393.678 192.991 407.751 + vertex 393.862 192.44 407.386 + endloop + endfacet + facet normal 0.695165 -0.221924 0.683736 + outer loop + vertex 393.678 192.991 407.751 + vertex 393.509 191.75 407.521 + vertex 393.862 192.44 407.386 + endloop + endfacet + facet normal 0.704095 -0.262818 0.65968 + outer loop + vertex 393.564 190.498 406.988 + vertex 393.61 191.108 407.182 + vertex 393.411 190.864 407.297 + endloop + endfacet + facet normal 0.702044 -0.242712 0.669496 + outer loop + vertex 393.777 191.73 407.232 + vertex 393.509 191.75 407.521 + vertex 393.61 191.108 407.182 + endloop + endfacet + facet normal 0.694383 -0.247244 0.675797 + outer loop + vertex 393.509 191.75 407.521 + vertex 393.411 190.864 407.297 + vertex 393.61 191.108 407.182 + endloop + endfacet + facet normal 0.41171 -0.117321 0.903732 + outer loop + vertex 410.871 132.713 372.316 + vertex 411.554 129.945 371.645 + vertex 413.575 130.291 370.769 + endloop + endfacet + facet normal 0.410902 -0.109049 0.905134 + outer loop + vertex 413.575 130.291 370.769 + vertex 411.554 129.945 371.645 + vertex 413.51 128.056 370.529 + endloop + endfacet + facet normal 0.451926 -0.121611 0.883727 + outer loop + vertex 408.686 136.558 373.962 + vertex 408.908 132.838 373.337 + vertex 410.871 132.713 372.316 + endloop + endfacet + facet normal 0.453892 -0.102412 0.885152 + outer loop + vertex 410.871 132.713 372.316 + vertex 408.908 132.838 373.337 + vertex 411.554 129.945 371.645 + endloop + endfacet + facet normal 0.514057 -0.134617 0.847126 + outer loop + vertex 406.154 138.807 375.856 + vertex 406.588 135.935 375.137 + vertex 408.686 136.558 373.962 + endloop + endfacet + facet normal 0.510555 -0.112842 0.852408 + outer loop + vertex 408.686 136.558 373.962 + vertex 406.588 135.935 375.137 + vertex 408.908 132.838 373.337 + endloop + endfacet + facet normal 0.575736 -0.130732 0.807117 + outer loop + vertex 404.751 142.328 377.427 + vertex 404.617 139.296 377.032 + vertex 406.154 138.807 375.856 + endloop + endfacet + facet normal 0.580319 -0.11439 0.806315 + outer loop + vertex 406.154 138.807 375.856 + vertex 404.617 139.296 377.032 + vertex 406.588 135.935 375.137 + endloop + endfacet + facet normal 0.629248 -0.131252 0.766042 + outer loop + vertex 403.209 146.967 379.489 + vertex 403.092 142.936 378.894 + vertex 404.751 142.328 377.427 + endloop + endfacet + facet normal 0.630292 -0.127756 0.765774 + outer loop + vertex 404.751 142.328 377.427 + vertex 403.092 142.936 378.894 + vertex 404.617 139.296 377.032 + endloop + endfacet + facet normal 0.686509 -0.13698 0.714102 + outer loop + vertex 401.595 150.753 381.767 + vertex 401.682 146.87 380.938 + vertex 403.209 146.967 379.489 + endloop + endfacet + facet normal 0.687176 -0.125474 0.715573 + outer loop + vertex 403.209 146.967 379.489 + vertex 401.682 146.87 380.938 + vertex 403.092 142.936 378.894 + endloop + endfacet + facet normal 0.722836 -0.142011 0.67627 + outer loop + vertex 400.44 154.459 383.779 + vertex 400.43 150.738 383.009 + vertex 401.595 150.753 381.767 + endloop + endfacet + facet normal 0.724114 -0.128348 0.677632 + outer loop + vertex 401.595 150.753 381.767 + vertex 400.43 150.738 383.009 + vertex 401.682 146.87 380.938 + endloop + endfacet + facet normal 0.758516 -0.146604 0.634949 + outer loop + vertex 399.493 158.16 385.765 + vertex 399.46 154.511 384.962 + vertex 400.44 154.459 383.779 + endloop + endfacet + facet normal 0.760201 -0.133727 0.635776 + outer loop + vertex 400.44 154.459 383.779 + vertex 399.46 154.511 384.962 + vertex 400.43 150.738 383.009 + endloop + endfacet + facet normal 0.788522 -0.153821 0.59546 + outer loop + vertex 398.659 161.69 387.781 + vertex 398.595 158.419 387.021 + vertex 399.493 158.16 385.765 + endloop + endfacet + facet normal 0.791999 -0.138064 0.594707 + outer loop + vertex 399.493 158.16 385.765 + vertex 398.595 158.419 387.021 + vertex 399.46 154.511 384.962 + endloop + endfacet + facet normal 0.807686 -0.167138 0.565428 + outer loop + vertex 397.982 164.346 389.533 + vertex 397.885 161.945 388.962 + vertex 398.659 161.69 387.781 + endloop + endfacet + facet normal 0.812439 -0.14703 0.564203 + outer loop + vertex 398.659 161.69 387.781 + vertex 397.885 161.945 388.962 + vertex 398.595 158.419 387.021 + endloop + endfacet + facet normal 0.820996 -0.167927 0.545679 + outer loop + vertex 397.672 167.906 391.096 + vertex 397.33 165.437 390.85 + vertex 397.982 164.346 389.533 + endloop + endfacet + facet normal 0.824124 -0.162383 0.542634 + outer loop + vertex 397.982 164.346 389.533 + vertex 397.33 165.437 390.85 + vertex 397.885 161.945 388.962 + endloop + endfacet + facet normal 0.841148 -0.170113 0.513354 + outer loop + vertex 397.242 172.456 393.308 + vertex 396.883 169.123 392.791 + vertex 397.672 167.906 391.096 + endloop + endfacet + facet normal 0.842425 -0.167542 0.512103 + outer loop + vertex 397.672 167.906 391.096 + vertex 396.883 169.123 392.791 + vertex 397.33 165.437 390.85 + endloop + endfacet + facet normal 0.858477 -0.185786 0.478018 + outer loop + vertex 396.642 175.446 395.548 + vertex 396.445 172.701 394.834 + vertex 397.242 172.456 393.308 + endloop + endfacet + facet normal 0.862792 -0.166848 0.477233 + outer loop + vertex 397.242 172.456 393.308 + vertex 396.445 172.701 394.834 + vertex 396.883 169.123 392.791 + endloop + endfacet + facet normal 0.867328 -0.180935 0.463686 + outer loop + vertex 396.456 179.785 397.588 + vertex 396.085 176.409 396.965 + vertex 396.642 175.446 395.548 + endloop + endfacet + facet normal 0.86641 -0.182874 0.464641 + outer loop + vertex 396.642 175.446 395.548 + vertex 396.085 176.409 396.965 + vertex 396.445 172.701 394.834 + endloop + endfacet + facet normal 0.882036 -0.186977 0.432496 + outer loop + vertex 395.884 183.589 400.4 + vertex 395.76 180.315 399.238 + vertex 396.456 179.785 397.588 + endloop + endfacet + facet normal 0.885106 -0.176769 0.430512 + outer loop + vertex 396.456 179.785 397.588 + vertex 395.76 180.315 399.238 + vertex 396.085 176.409 396.965 + endloop + endfacet + facet normal 0.855147 -0.212942 0.472631 + outer loop + vertex 395.276 186.993 403.034 + vertex 395.167 184.265 402.001 + vertex 395.884 183.589 400.4 + endloop + endfacet + facet normal 0.860367 -0.199166 0.46915 + outer loop + vertex 395.884 183.589 400.4 + vertex 395.167 184.265 402.001 + vertex 395.76 180.315 399.238 + endloop + endfacet + facet normal 0.816063 -0.237103 0.527089 + outer loop + vertex 394.486 188.651 405.002 + vertex 394.549 187.341 404.316 + vertex 395.276 186.993 403.034 + endloop + endfacet + facet normal 0.810134 -0.239724 0.534991 + outer loop + vertex 394.461 187.207 404.389 + vertex 395.167 184.265 402.001 + vertex 394.549 187.341 404.316 + endloop + endfacet + facet normal 0.817817 -0.231921 0.526676 + outer loop + vertex 395.167 184.265 402.001 + vertex 395.276 186.993 403.034 + vertex 394.549 187.341 404.316 + endloop + endfacet + facet normal 0.74861 -0.304762 0.588815 + outer loop + vertex 394.076 189.297 405.858 + vertex 393.978 189.021 405.84 + vertex 394.486 188.651 405.002 + endloop + endfacet + facet normal 0.766084 -0.26912 0.583686 + outer loop + vertex 394.486 188.651 405.002 + vertex 393.978 189.021 405.84 + vertex 394.549 187.341 404.316 + endloop + endfacet + facet normal 0.798302 -0.232625 0.555517 + outer loop + vertex 393.978 189.021 405.84 + vertex 394.08 188.466 405.461 + vertex 394.549 187.341 404.316 + endloop + endfacet + facet normal 0.803073 -0.226285 0.551242 + outer loop + vertex 394.549 187.341 404.316 + vertex 394.08 188.466 405.461 + vertex 394.461 187.207 404.389 + endloop + endfacet + facet normal 0.664035 -0.300592 0.684618 + outer loop + vertex 393.564 190.498 406.988 + vertex 393.411 190.864 407.297 + vertex 393.555 190.079 406.812 + endloop + endfacet + facet normal 0.46538 -0.449811 0.762294 + outer loop + vertex 393.666 189.652 406.493 + vertex 393.555 190.079 406.812 + vertex 393.401 190.511 407.161 + endloop + endfacet + facet normal 0.402576 -0.337614 0.850852 + outer loop + vertex 393.367 191.301 407.491 + vertex 393.401 190.511 407.161 + vertex 393.411 190.864 407.297 + endloop + endfacet + facet normal 0.714132 -0.268017 0.64667 + outer loop + vertex 393.555 190.079 406.812 + vertex 393.411 190.864 407.297 + vertex 393.401 190.511 407.161 + endloop + endfacet + facet normal -0.860126 0.153747 -0.486359 + outer loop + vertex 394.08 188.466 405.461 + vertex 393.937 189.014 405.887 + vertex 394.461 187.207 404.389 + endloop + endfacet + facet normal -0.652418 0.362432 -0.665577 + outer loop + vertex 394.461 187.207 404.389 + vertex 393.937 189.014 405.887 + vertex 394.211 188.333 405.247 + endloop + endfacet + facet normal 0.394833 -0.111089 0.912012 + outer loop + vertex 412.808 127.919 370.817 + vertex 414.044 126.959 370.165 + vertex 413.51 128.056 370.529 + endloop + endfacet + facet normal 0.394274 -0.128026 0.910031 + outer loop + vertex 411.463 129.122 371.569 + vertex 412.808 127.919 370.817 + vertex 411.554 129.945 371.645 + endloop + endfacet + facet normal 0.4225 -0.129925 0.897003 + outer loop + vertex 409.934 130.705 372.518 + vertex 411.463 129.122 371.569 + vertex 411.554 129.945 371.645 + endloop + endfacet + facet normal 0.42916 -0.136168 0.892905 + outer loop + vertex 408.488 132.268 373.452 + vertex 409.934 130.705 372.518 + vertex 408.908 132.838 373.337 + endloop + endfacet + facet normal 0.453236 -0.157038 0.877448 + outer loop + vertex 407.543 133.588 374.176 + vertex 408.488 132.268 373.452 + vertex 408.908 132.838 373.337 + endloop + endfacet + facet normal 0.50976 -0.13988 0.848869 + outer loop + vertex 406.464 135.08 375.07 + vertex 407.543 133.588 374.176 + vertex 406.588 135.935 375.137 + endloop + endfacet + facet normal 0.529519 -0.141767 0.836368 + outer loop + vertex 405.311 137.108 376.144 + vertex 406.464 135.08 375.07 + vertex 406.588 135.935 375.137 + endloop + endfacet + facet normal 0.56386 -0.150726 0.812 + outer loop + vertex 404.302 138.928 377.182 + vertex 405.311 137.108 376.144 + vertex 404.617 139.296 377.032 + endloop + endfacet + facet normal 0.573087 -0.162168 0.803289 + outer loop + vertex 403.501 140.775 378.126 + vertex 404.302 138.928 377.182 + vertex 404.617 139.296 377.032 + endloop + endfacet + facet normal 0.59409 -0.167075 0.786856 + outer loop + vertex 402.9 142.13 378.868 + vertex 403.501 140.775 378.126 + vertex 403.092 142.936 378.894 + endloop + endfacet + facet normal 0.619727 -0.172517 0.765621 + outer loop + vertex 402.216 144.013 379.846 + vertex 402.9 142.13 378.868 + vertex 403.092 142.936 378.894 + endloop + endfacet + facet normal 0.634132 -0.169842 0.754341 + outer loop + vertex 401.457 146.102 380.954 + vertex 402.216 144.013 379.846 + vertex 401.682 146.87 380.938 + endloop + endfacet + facet normal 0.656767 -0.176929 0.733043 + outer loop + vertex 400.799 148.227 382.057 + vertex 401.457 146.102 380.954 + vertex 401.682 146.87 380.938 + endloop + endfacet + facet normal 0.666306 -0.176714 0.724436 + outer loop + vertex 400.169 150.237 383.127 + vertex 400.799 148.227 382.057 + vertex 400.43 150.738 383.009 + endloop + endfacet + facet normal 0.680615 -0.188025 0.708103 + outer loop + vertex 399.798 151.815 383.902 + vertex 400.169 150.237 383.127 + vertex 400.43 150.738 383.009 + endloop + endfacet + facet normal 0.715832 -0.175942 0.675744 + outer loop + vertex 399.335 153.557 384.846 + vertex 399.798 151.815 383.902 + vertex 399.46 154.511 384.962 + endloop + endfacet + facet normal 0.73261 -0.175905 0.657526 + outer loop + vertex 398.85 155.936 386.023 + vertex 399.335 153.557 384.846 + vertex 399.46 154.511 384.962 + endloop + endfacet + facet normal 0.750652 -0.178662 0.636083 + outer loop + vertex 398.377 158.065 387.179 + vertex 398.85 155.936 386.023 + vertex 398.595 158.419 387.021 + endloop + endfacet + facet normal 0.755627 -0.185194 0.628277 + outer loop + vertex 398.019 160.067 388.199 + vertex 398.377 158.065 387.179 + vertex 398.595 158.419 387.021 + endloop + endfacet + facet normal 0.743975 -0.205147 0.635937 + outer loop + vertex 397.731 161.517 389.005 + vertex 398.019 160.067 388.199 + vertex 397.885 161.945 388.962 + endloop + endfacet + facet normal 0.757841 -0.212035 0.617023 + outer loop + vertex 397.423 163.484 390.059 + vertex 397.731 161.517 389.005 + vertex 397.885 161.945 388.962 + endloop + endfacet + facet normal 0.761387 -0.212044 0.61264 + outer loop + vertex 397.105 165.489 391.147 + vertex 397.423 163.484 390.059 + vertex 397.33 165.437 390.85 + endloop + endfacet + facet normal 0.756345 -0.230801 0.612106 + outer loop + vertex 396.925 166.973 391.93 + vertex 397.105 165.489 391.147 + vertex 397.33 165.437 390.85 + endloop + endfacet + facet normal 0.788893 -0.215315 0.575575 + outer loop + vertex 396.655 168.813 392.988 + vertex 396.925 166.973 391.93 + vertex 396.883 169.123 392.791 + endloop + endfacet + facet normal 0.791916 -0.221764 0.568938 + outer loop + vertex 396.447 170.761 394.037 + vertex 396.655 168.813 392.988 + vertex 396.883 169.123 392.791 + endloop + endfacet + facet normal 0.782157 -0.236147 0.576597 + outer loop + vertex 396.266 172.133 394.844 + vertex 396.447 170.761 394.037 + vertex 396.445 172.701 394.834 + endloop + endfacet + facet normal 0.795395 -0.240677 0.556256 + outer loop + vertex 396.088 174.002 395.908 + vertex 396.266 172.133 394.844 + vertex 396.445 172.701 394.834 + endloop + endfacet + facet normal 0.804635 -0.238022 0.543975 + outer loop + vertex 395.89 176.087 397.113 + vertex 396.088 174.002 395.908 + vertex 396.085 176.409 396.965 + endloop + endfacet + facet normal 0.80951 -0.245989 0.533088 + outer loop + vertex 395.71 178.303 398.409 + vertex 395.89 176.087 397.113 + vertex 396.085 176.409 396.965 + endloop + endfacet + facet normal 0.837453 -0.225759 0.4977 + outer loop + vertex 395.437 181.217 400.189 + vertex 395.71 178.303 398.409 + vertex 395.76 180.315 399.238 + endloop + endfacet + facet normal 0.823341 -0.234311 0.516922 + outer loop + vertex 395.163 183.191 401.521 + vertex 395.437 181.217 400.189 + vertex 395.167 184.265 402.001 + endloop + endfacet + facet normal 0.820095 -0.236211 0.5212 + outer loop + vertex 394.85 185.361 402.997 + vertex 395.163 183.191 401.521 + vertex 395.167 184.265 402.001 + endloop + endfacet + facet normal -0.580168 0.408821 -0.704464 + outer loop + vertex 394.477 187.148 404.342 + vertex 394.85 185.361 402.997 + vertex 394.461 187.207 404.389 + endloop + endfacet + facet normal 0.657257 -0.358932 0.662708 + outer loop + vertex 393.936 188.976 405.868 + vertex 394.477 187.148 404.342 + vertex 394.211 188.333 405.247 + endloop + endfacet + facet normal 0.652028 -0.344587 0.675366 + outer loop + vertex 393.31 190.438 407.218 + vertex 393.936 188.976 405.868 + vertex 393.937 189.014 405.887 + endloop + endfacet + facet normal -0.882753 0.193532 -0.428127 + outer loop + vertex 393.488 192.121 407.613 + vertex 393.31 190.438 407.218 + vertex 393.367 191.301 407.491 + endloop + endfacet + facet normal -0.862728 0.181742 -0.471879 + outer loop + vertex 393.742 194.416 408.032 + vertex 393.488 192.121 407.613 + vertex 393.588 193.435 407.936 + endloop + endfacet + facet normal -0.475698 0.190231 -0.858792 + outer loop + vertex 393.975 196.661 408.4 + vertex 393.742 194.416 408.032 + vertex 393.888 197.021 408.528 + endloop + endfacet + facet normal -0.519514 0.17183 -0.837006 + outer loop + vertex 394.004 198.812 408.823 + vertex 393.975 196.661 408.4 + vertex 393.888 197.021 408.528 + endloop + endfacet + facet normal 0.0214188 0.171824 -0.984895 + outer loop + vertex 394.004 201.219 409.243 + vertex 394.004 198.812 408.823 + vertex 393.948 199.701 408.977 + endloop + endfacet + facet normal 0.568777 0.184817 -0.801459 + outer loop + vertex 393.977 203.644 409.783 + vertex 394.004 201.219 409.243 + vertex 393.919 202.093 409.384 + endloop + endfacet + facet normal 0.869253 0.146628 -0.472122 + outer loop + vertex 394.084 205.819 410.656 + vertex 393.977 203.644 409.783 + vertex 393.939 204.33 409.926 + endloop + endfacet + facet normal 0.733586 -0.355475 0.579214 + outer loop + vertex 394.147 205.844 410.591 + vertex 394.084 205.819 410.656 + vertex 393.939 204.33 409.926 + endloop + endfacet + facet normal 0.460291 0.204948 -0.863787 + outer loop + vertex 393.919 202.093 409.384 + vertex 393.939 204.33 409.926 + vertex 393.977 203.644 409.783 + endloop + endfacet + facet normal -0.0633558 0.166332 -0.984032 + outer loop + vertex 393.888 197.021 408.528 + vertex 393.948 199.701 408.977 + vertex 394.004 198.812 408.823 + endloop + endfacet + facet normal 0.100388 0.168199 -0.980628 + outer loop + vertex 393.948 199.701 408.977 + vertex 393.919 202.093 409.384 + vertex 394.004 201.219 409.243 + endloop + endfacet + facet normal 0.407909 -0.0953837 0.908026 + outer loop + vertex 415.374 132.883 370.234 + vertex 412.316 135.947 371.929 + vertex 413.575 130.291 370.769 + endloop + endfacet + facet normal 0.47761 -0.0751957 0.875348 + outer loop + vertex 412.316 135.947 371.929 + vertex 410.089 140.293 373.517 + vertex 408.686 136.558 373.962 + endloop + endfacet + facet normal 0.528276 -0.0980306 0.843395 + outer loop + vertex 410.089 140.293 373.517 + vertex 407.355 142.325 375.466 + vertex 408.686 136.558 373.962 + endloop + endfacet + facet normal 0.598761 -0.0953575 0.795231 + outer loop + vertex 407.355 142.325 375.466 + vertex 405.363 146.707 377.491 + vertex 404.751 142.328 377.427 + endloop + endfacet + facet normal 0.672134 -0.0831038 0.735751 + outer loop + vertex 405.363 146.707 377.491 + vertex 404.244 150.343 378.924 + vertex 403.209 146.967 379.489 + endloop + endfacet + facet normal 0.706223 -0.0993699 0.700981 + outer loop + vertex 404.244 150.343 378.924 + vertex 402.938 152.55 380.553 + vertex 403.209 146.967 379.489 + endloop + endfacet + facet normal 0.740335 -0.104942 0.663997 + outer loop + vertex 402.938 152.55 380.553 + vertex 401.687 155.876 382.474 + vertex 401.595 150.753 381.767 + endloop + endfacet + facet normal 0.775525 -0.109581 0.621734 + outer loop + vertex 401.687 155.876 382.474 + vertex 400.638 159.484 384.418 + vertex 400.44 154.459 383.779 + endloop + endfacet + facet normal 0.809872 -0.115078 0.575208 + outer loop + vertex 400.638 159.484 384.418 + vertex 399.706 163.11 386.455 + vertex 399.493 158.16 385.765 + endloop + endfacet + facet normal 0.839318 -0.12486 0.529108 + outer loop + vertex 399.706 163.11 386.455 + vertex 398.759 166.879 388.848 + vertex 398.659 161.69 387.781 + endloop + endfacet + facet normal 0.870617 -0.12191 0.476617 + outer loop + vertex 398.759 166.879 388.848 + vertex 398.245 171.679 391.015 + vertex 397.672 167.906 391.096 + endloop + endfacet + facet normal 0.894901 -0.116639 0.430752 + outer loop + vertex 398.245 171.679 391.015 + vertex 397.931 175.379 392.667 + vertex 397.242 172.456 393.308 + endloop + endfacet + facet normal 0.906966 -0.125793 0.401981 + outer loop + vertex 397.931 175.379 392.667 + vertex 397.316 178.009 394.88 + vertex 397.242 172.456 393.308 + endloop + endfacet + facet normal 0.918861 -0.125746 0.374008 + outer loop + vertex 397.316 178.009 394.88 + vertex 397.126 182.429 396.831 + vertex 396.456 179.785 397.588 + endloop + endfacet + facet normal 0.927857 -0.135651 0.347391 + outer loop + vertex 397.126 182.429 396.831 + vertex 396.661 185.533 399.286 + vertex 396.456 179.785 397.588 + endloop + endfacet + facet normal 0.920596 -0.165169 0.353867 + outer loop + vertex 396.661 185.533 399.286 + vertex 396.05 186.805 401.469 + vertex 395.884 183.589 400.4 + endloop + endfacet + facet normal 0.83233 -0.269683 0.48425 + outer loop + vertex 395.805 189.711 403.303 + vertex 395.491 190.835 404.468 + vertex 394.947 189.94 404.904 + endloop + endfacet + facet normal 0.865239 -0.213309 0.453719 + outer loop + vertex 396.05 186.805 401.469 + vertex 395.805 189.711 403.303 + vertex 395.276 186.993 403.034 + endloop + endfacet + facet normal -0.778358 0.181133 -0.601123 + outer loop + vertex 393.588 193.435 407.936 + vertex 393.736 195.05 408.231 + vertex 393.742 194.416 408.032 + endloop + endfacet + facet normal -0.873881 0.137667 -0.46624 + outer loop + vertex 393.736 195.05 408.231 + vertex 393.888 197.021 408.528 + vertex 393.742 194.416 408.032 + endloop + endfacet + facet normal 0.715225 -0.282696 0.639169 + outer loop + vertex 393.808 189.868 406.436 + vertex 393.564 190.498 406.988 + vertex 393.555 190.079 406.812 + endloop + endfacet + facet normal 0.719762 -0.297103 0.627433 + outer loop + vertex 394.076 189.297 405.858 + vertex 393.808 189.868 406.436 + vertex 393.978 189.021 405.84 + endloop + endfacet + facet normal 0.808314 -0.248618 0.533683 + outer loop + vertex 394.947 189.94 404.904 + vertex 394.486 188.651 405.002 + vertex 395.276 186.993 403.034 + endloop + endfacet + facet normal -0.842162 0.198441 -0.501383 + outer loop + vertex 393.367 191.301 407.491 + vertex 393.451 192.22 407.713 + vertex 393.488 192.121 407.613 + endloop + endfacet + facet normal -0.850602 0.185734 -0.491913 + outer loop + vertex 393.451 192.22 407.713 + vertex 393.588 193.435 407.936 + vertex 393.488 192.121 407.613 + endloop + endfacet + facet normal 0.434632 -0.0870478 0.896391 + outer loop + vertex 410.871 132.713 372.316 + vertex 413.575 130.291 370.769 + vertex 412.316 135.947 371.929 + endloop + endfacet + facet normal 0.396656 -0.126232 0.909246 + outer loop + vertex 413.51 128.056 370.529 + vertex 411.554 129.945 371.645 + vertex 412.808 127.919 370.817 + endloop + endfacet + facet normal 0.472199 -0.106373 0.87505 + outer loop + vertex 408.686 136.558 373.962 + vertex 410.871 132.713 372.316 + vertex 412.316 135.947 371.929 + endloop + endfacet + facet normal 0.416176 -0.144276 0.897765 + outer loop + vertex 411.554 129.945 371.645 + vertex 408.908 132.838 373.337 + vertex 409.934 130.705 372.518 + endloop + endfacet + facet normal 0.542341 -0.0926049 0.835039 + outer loop + vertex 406.154 138.807 375.856 + vertex 408.686 136.558 373.962 + vertex 407.355 142.325 375.466 + endloop + endfacet + facet normal 0.44159 -0.179959 0.878984 + outer loop + vertex 408.908 132.838 373.337 + vertex 406.588 135.935 375.137 + vertex 407.543 133.588 374.176 + endloop + endfacet + facet normal 0.597425 -0.11601 0.793489 + outer loop + vertex 404.751 142.328 377.427 + vertex 406.154 138.807 375.856 + vertex 407.355 142.325 375.466 + endloop + endfacet + facet normal 0.497446 -0.186099 0.847298 + outer loop + vertex 406.588 135.935 375.137 + vertex 404.617 139.296 377.032 + vertex 405.311 137.108 376.144 + endloop + endfacet + facet normal 0.669386 -0.104352 0.735549 + outer loop + vertex 403.209 146.967 379.489 + vertex 404.751 142.328 377.427 + vertex 405.363 146.707 377.491 + endloop + endfacet + facet normal 0.553294 -0.183875 0.812438 + outer loop + vertex 404.617 139.296 377.032 + vertex 403.092 142.936 378.894 + vertex 403.501 140.775 378.126 + endloop + endfacet + facet normal 0.733057 -0.0928844 0.673795 + outer loop + vertex 401.595 150.753 381.767 + vertex 403.209 146.967 379.489 + vertex 402.938 152.55 380.553 + endloop + endfacet + facet normal 0.614843 -0.178715 0.768134 + outer loop + vertex 403.092 142.936 378.894 + vertex 401.682 146.87 380.938 + vertex 402.216 144.013 379.846 + endloop + endfacet + facet normal 0.771738 -0.100531 0.627944 + outer loop + vertex 400.44 154.459 383.779 + vertex 401.595 150.753 381.767 + vertex 401.687 155.876 382.474 + endloop + endfacet + facet normal 0.651021 -0.183547 0.736534 + outer loop + vertex 401.682 146.87 380.938 + vertex 400.43 150.738 383.009 + vertex 400.799 148.227 382.057 + endloop + endfacet + facet normal 0.806568 -0.105705 0.581613 + outer loop + vertex 399.493 158.16 385.765 + vertex 400.44 154.459 383.779 + vertex 400.638 159.484 384.418 + endloop + endfacet + facet normal 0.673827 -0.195666 0.712511 + outer loop + vertex 400.43 150.738 383.009 + vertex 399.46 154.511 384.962 + vertex 399.798 151.815 383.902 + endloop + endfacet + facet normal 0.83439 -0.111201 0.53984 + outer loop + vertex 398.659 161.69 387.781 + vertex 399.493 158.16 385.765 + vertex 399.706 163.11 386.455 + endloop + endfacet + facet normal 0.710473 -0.198503 0.675148 + outer loop + vertex 399.46 154.511 384.962 + vertex 398.595 158.419 387.021 + vertex 398.85 155.936 386.023 + endloop + endfacet + facet normal 0.849812 -0.121719 0.512839 + outer loop + vertex 397.982 164.346 389.533 + vertex 398.659 161.69 387.781 + vertex 398.759 166.879 388.848 + endloop + endfacet + facet normal 0.726122 -0.213571 0.653555 + outer loop + vertex 398.595 158.419 387.021 + vertex 397.885 161.945 388.962 + vertex 398.019 160.067 388.199 + endloop + endfacet + facet normal 0.866337 -0.135465 0.480738 + outer loop + vertex 397.672 167.906 391.096 + vertex 397.982 164.346 389.533 + vertex 398.759 166.879 388.848 + endloop + endfacet + facet normal 0.75415 -0.215504 0.620336 + outer loop + vertex 397.885 161.945 388.962 + vertex 397.33 165.437 390.85 + vertex 397.423 163.484 390.059 + endloop + endfacet + facet normal 0.892542 -0.126174 0.432953 + outer loop + vertex 397.242 172.456 393.308 + vertex 397.672 167.906 391.096 + vertex 398.245 171.679 391.015 + endloop + endfacet + facet normal 0.756777 -0.230414 0.611718 + outer loop + vertex 397.33 165.437 390.85 + vertex 396.883 169.123 392.791 + vertex 396.925 166.973 391.93 + endloop + endfacet + facet normal 0.90121 -0.129041 0.413726 + outer loop + vertex 396.642 175.446 395.548 + vertex 397.242 172.456 393.308 + vertex 397.316 178.009 394.88 + endloop + endfacet + facet normal 0.773191 -0.240369 0.586855 + outer loop + vertex 396.883 169.123 392.791 + vertex 396.445 172.701 394.834 + vertex 396.447 170.761 394.037 + endloop + endfacet + facet normal 0.913425 -0.140529 0.381977 + outer loop + vertex 396.456 179.785 397.588 + vertex 396.642 175.446 395.548 + vertex 397.316 178.009 394.88 + endloop + endfacet + facet normal 0.791128 -0.245225 0.56034 + outer loop + vertex 396.445 172.701 394.834 + vertex 396.085 176.409 396.965 + vertex 396.088 174.002 395.908 + endloop + endfacet + facet normal 0.912417 -0.14548 0.382532 + outer loop + vertex 395.884 183.589 400.4 + vertex 396.456 179.785 397.588 + vertex 396.661 185.533 399.286 + endloop + endfacet + facet normal 0.820071 -0.235214 0.521687 + outer loop + vertex 396.085 176.409 396.965 + vertex 395.76 180.315 399.238 + vertex 395.71 178.303 398.409 + endloop + endfacet + facet normal 0.869408 -0.195724 0.453675 + outer loop + vertex 395.276 186.993 403.034 + vertex 395.884 183.589 400.4 + vertex 396.05 186.805 401.469 + endloop + endfacet + facet normal 0.84296 -0.217726 0.491949 + outer loop + vertex 395.76 180.315 399.238 + vertex 395.167 184.265 402.001 + vertex 395.437 181.217 400.189 + endloop + endfacet + facet normal 0.880499 -0.152821 0.44874 + outer loop + vertex 395.167 184.265 402.001 + vertex 394.461 187.207 404.389 + vertex 394.85 185.361 402.997 + endloop + endfacet + facet normal 0.715363 -0.299541 0.631293 + outer loop + vertex 394.08 188.466 405.461 + vertex 393.978 189.021 405.84 + vertex 393.666 189.652 406.493 + endloop + endfacet + facet normal 0.746517 -0.263232 0.611082 + outer loop + vertex 393.555 190.079 406.812 + vertex 393.666 189.652 406.493 + vertex 393.978 189.021 405.84 + endloop + endfacet + facet normal 0.6722 -0.314404 0.670297 + outer loop + vertex 393.666 189.652 406.493 + vertex 393.401 190.511 407.161 + vertex 393.31 190.438 407.218 + endloop + endfacet + facet normal 0.656157 -0.266355 0.706055 + outer loop + vertex 393.401 190.511 407.161 + vertex 393.367 191.301 407.491 + vertex 393.31 190.438 407.218 + endloop + endfacet + facet normal -0.687369 0.325123 -0.649476 + outer loop + vertex 393.937 189.014 405.887 + vertex 394.08 188.466 405.461 + vertex 393.666 189.652 406.493 + endloop + endfacet + facet normal -0.590877 0.40193 -0.699512 + outer loop + vertex 394.461 187.207 404.389 + vertex 394.211 188.333 405.247 + vertex 394.477 187.148 404.342 + endloop + endfacet + facet normal 0.685081 -0.332793 0.648007 + outer loop + vertex 394.211 188.333 405.247 + vertex 393.937 189.014 405.887 + vertex 393.936 188.976 405.868 + endloop + endfacet + facet normal -0.516659 -0.69515 0.499829 + outer loop + vertex 393.31 190.438 407.218 + vertex 393.937 189.014 405.887 + vertex 393.666 189.652 406.493 + endloop + endfacet + facet normal 0.848319 -0.213092 0.484713 + outer loop + vertex 395.805 189.711 403.303 + vertex 394.947 189.94 404.904 + vertex 395.276 186.993 403.034 + endloop + endfacet + facet normal 0.697429 -0.313533 0.64443 + outer loop + vertex 393.808 189.868 406.436 + vertex 393.555 190.079 406.812 + vertex 393.978 189.021 405.84 + endloop + endfacet + facet normal -0.433934 -0.125865 0.892109 + outer loop + vertex -413.436 150.029 372.623 + vertex -410.746 153.044 374.357 + vertex -414.271 157.851 373.32 + endloop + endfacet + facet normal -0.4327 -0.124799 0.892858 + outer loop + vertex -414.271 157.851 373.32 + vertex -410.746 153.044 374.357 + vertex -411.593 160.797 375.03 + endloop + endfacet + facet normal -0.468422 -0.0852039 0.879387 + outer loop + vertex -413.004 142.73 372.146 + vertex -410.291 145.769 373.886 + vertex -413.436 150.029 372.623 + endloop + endfacet + facet normal -0.469605 -0.0862959 0.878649 + outer loop + vertex -413.436 150.029 372.623 + vertex -410.291 145.769 373.886 + vertex -410.746 153.044 374.357 + endloop + endfacet + facet normal -0.467131 -0.0746159 0.881034 + outer loop + vertex -412.843 137.261 371.768 + vertex -410.35 139.407 373.272 + vertex -413.004 142.73 372.146 + endloop + endfacet + facet normal -0.472744 -0.0802845 0.877535 + outer loop + vertex -413.004 142.73 372.146 + vertex -410.35 139.407 373.272 + vertex -410.291 145.769 373.886 + endloop + endfacet + facet normal -0.454436 -0.10403 0.884684 + outer loop + vertex -411.597 129.982 371.628 + vertex -408.9 133.016 373.37 + vertex -411.328 133.769 372.212 + endloop + endfacet + facet normal -0.458098 -0.122363 0.88044 + outer loop + vertex -411.328 133.769 372.212 + vertex -408.9 133.016 373.37 + vertex -408.211 136.924 374.272 + endloop + endfacet + facet normal -0.490151 -0.128413 0.862126 + outer loop + vertex -410.746 153.044 374.357 + vertex -408.479 156.123 376.104 + vertex -411.593 160.797 375.03 + endloop + endfacet + facet normal -0.488496 -0.127048 0.863267 + outer loop + vertex -411.593 160.797 375.03 + vertex -408.479 156.123 376.104 + vertex -409.432 163.697 376.68 + endloop + endfacet + facet normal -0.532606 -0.087849 0.841792 + outer loop + vertex -410.291 145.769 373.886 + vertex -407.884 148.838 375.729 + vertex -410.746 153.044 374.357 + endloop + endfacet + facet normal -0.531524 -0.0868566 0.842578 + outer loop + vertex -410.746 153.044 374.357 + vertex -407.884 148.838 375.729 + vertex -408.479 156.123 376.104 + endloop + endfacet + facet normal -0.528885 -0.076648 0.845225 + outer loop + vertex -410.35 139.407 373.272 + vertex -407.766 142.283 375.15 + vertex -410.291 145.769 373.886 + endloop + endfacet + facet normal -0.536214 -0.0838851 0.839903 + outer loop + vertex -410.291 145.769 373.886 + vertex -407.766 142.283 375.15 + vertex -407.884 148.838 375.729 + endloop + endfacet + facet normal -0.519905 -0.103948 0.847876 + outer loop + vertex -408.9 133.016 373.37 + vertex -406.51 136.104 375.214 + vertex -408.211 136.924 374.272 + endloop + endfacet + facet normal -0.527133 -0.127855 0.840109 + outer loop + vertex -408.211 136.924 374.272 + vertex -406.51 136.104 375.214 + vertex -405.882 139.914 376.188 + endloop + endfacet + facet normal -0.54711 -0.131641 0.826644 + outer loop + vertex -408.479 156.123 376.104 + vertex -406.612 159.314 377.848 + vertex -409.432 163.697 376.68 + endloop + endfacet + facet normal -0.543314 -0.128396 0.829653 + outer loop + vertex -409.432 163.697 376.68 + vertex -406.612 159.314 377.848 + vertex -407.511 166.775 378.414 + endloop + endfacet + facet normal -0.597868 -0.089904 0.796537 + outer loop + vertex -407.884 148.838 375.729 + vertex -406.009 152.264 377.523 + vertex -408.479 156.123 376.104 + endloop + endfacet + facet normal -0.595664 -0.0878008 0.798421 + outer loop + vertex -408.479 156.123 376.104 + vertex -406.009 152.264 377.523 + vertex -406.612 159.314 377.848 + endloop + endfacet + facet normal -0.60554 -0.0808741 0.791695 + outer loop + vertex -407.766 142.283 375.15 + vertex -405.4 145.556 377.293 + vertex -407.884 148.838 375.729 + endloop + endfacet + facet normal -0.606586 -0.0821088 0.790766 + outer loop + vertex -407.884 148.838 375.729 + vertex -405.4 145.556 377.293 + vertex -406.009 152.264 377.523 + endloop + endfacet + facet normal -0.589994 -0.107284 0.800248 + outer loop + vertex -406.51 136.104 375.214 + vertex -404.545 139.398 377.105 + vertex -405.882 139.914 376.188 + endloop + endfacet + facet normal -0.594431 -0.130892 0.793422 + outer loop + vertex -405.882 139.914 376.188 + vertex -404.545 139.398 377.105 + vertex -404.234 142.387 377.831 + endloop + endfacet + facet normal -0.607277 -0.132597 0.783347 + outer loop + vertex -406.612 159.314 377.848 + vertex -405.023 162.536 379.626 + vertex -407.511 166.775 378.414 + endloop + endfacet + facet normal -0.600615 -0.126959 0.789394 + outer loop + vertex -407.511 166.775 378.414 + vertex -405.023 162.536 379.626 + vertex -405.873 169.881 380.16 + endloop + endfacet + facet normal -0.660241 -0.0908779 0.745535 + outer loop + vertex -406.009 152.264 377.523 + vertex -404.516 155.59 379.25 + vertex -406.612 159.314 377.848 + endloop + endfacet + facet normal -0.657585 -0.0883885 0.748177 + outer loop + vertex -406.612 159.314 377.848 + vertex -404.516 155.59 379.25 + vertex -405.023 162.536 379.626 + endloop + endfacet + facet normal -0.67002 -0.0860358 0.737341 + outer loop + vertex -405.4 145.556 377.293 + vertex -404.266 150.08 378.852 + vertex -406.009 152.264 377.523 + endloop + endfacet + facet normal -0.668473 -0.0837908 0.739001 + outer loop + vertex -406.009 152.264 377.523 + vertex -404.266 150.08 378.852 + vertex -404.516 155.59 379.25 + endloop + endfacet + facet normal -0.645144 -0.116315 0.755156 + outer loop + vertex -404.545 139.398 377.105 + vertex -403.075 142.883 378.898 + vertex -404.234 142.387 377.831 + endloop + endfacet + facet normal -0.641188 -0.128529 0.756544 + outer loop + vertex -404.234 142.387 377.831 + vertex -403.075 142.883 378.898 + vertex -403.173 146.742 379.47 + endloop + endfacet + facet normal -0.664441 -0.13045 0.735867 + outer loop + vertex -405.023 162.536 379.626 + vertex -403.621 165.824 381.474 + vertex -405.873 169.881 380.16 + endloop + endfacet + facet normal -0.657895 -0.124595 0.742732 + outer loop + vertex -405.873 169.881 380.16 + vertex -403.621 165.824 381.474 + vertex -404.42 173.129 381.992 + endloop + endfacet + facet normal -0.719811 -0.0896957 0.68835 + outer loop + vertex -404.516 155.59 379.25 + vertex -403.159 158.788 381.086 + vertex -405.023 162.536 379.626 + endloop + endfacet + facet normal -0.715098 -0.0852246 0.693809 + outer loop + vertex -405.023 162.536 379.626 + vertex -403.159 158.788 381.086 + vertex -403.621 165.824 381.474 + endloop + endfacet + facet normal -0.720711 -0.082493 0.688309 + outer loop + vertex -404.266 150.08 378.852 + vertex -402.944 152.479 380.524 + vertex -404.516 155.59 379.25 + endloop + endfacet + facet normal -0.723974 -0.0857083 0.684483 + outer loop + vertex -404.516 155.59 379.25 + vertex -402.944 152.479 380.524 + vertex -403.159 158.788 381.086 + endloop + endfacet + facet normal -0.68941 -0.12342 0.713779 + outer loop + vertex -403.075 142.883 378.898 + vertex -401.727 146.79 380.875 + vertex -403.173 146.742 379.47 + endloop + endfacet + facet normal -0.687983 -0.136564 0.712762 + outer loop + vertex -403.173 146.742 379.47 + vertex -401.727 146.79 380.875 + vertex -401.599 150.614 381.731 + endloop + endfacet + facet normal -0.720083 -0.127093 0.682149 + outer loop + vertex -403.621 165.824 381.474 + vertex -402.42 169.271 383.384 + vertex -404.42 173.129 381.992 + endloop + endfacet + facet normal -0.714356 -0.121604 0.689135 + outer loop + vertex -404.42 173.129 381.992 + vertex -402.42 169.271 383.384 + vertex -403.175 176.412 383.862 + endloop + endfacet + facet normal -0.771682 -0.0854424 0.630243 + outer loop + vertex -403.159 158.788 381.086 + vertex -401.922 162.291 383.075 + vertex -403.621 165.824 381.474 + endloop + endfacet + facet normal -0.769369 -0.082897 0.633403 + outer loop + vertex -403.621 165.824 381.474 + vertex -401.922 162.291 383.075 + vertex -402.42 169.271 383.384 + endloop + endfacet + facet normal -0.767314 -0.0828557 0.635897 + outer loop + vertex -402.944 152.479 380.524 + vertex -401.634 155.886 382.548 + vertex -403.159 158.788 381.086 + endloop + endfacet + facet normal -0.770432 -0.0866568 0.631605 + outer loop + vertex -403.159 158.788 381.086 + vertex -401.634 155.886 382.548 + vertex -401.922 162.291 383.075 + endloop + endfacet + facet normal -0.72397 -0.127559 0.677935 + outer loop + vertex -401.727 146.79 380.875 + vertex -400.46 150.609 382.947 + vertex -401.599 150.614 381.731 + endloop + endfacet + facet normal -0.722119 -0.146281 0.676126 + outer loop + vertex -401.599 150.614 381.731 + vertex -400.46 150.609 382.947 + vertex -400.381 154.208 383.81 + endloop + endfacet + facet normal -0.767899 -0.123219 0.628608 + outer loop + vertex -402.42 169.271 383.384 + vertex -401.409 172.755 385.302 + vertex -403.175 176.412 383.862 + endloop + endfacet + facet normal -0.765221 -0.120432 0.632402 + outer loop + vertex -403.175 176.412 383.862 + vertex -401.409 172.755 385.302 + vertex -402.123 179.697 385.76 + endloop + endfacet + facet normal -0.815052 -0.0834981 0.573339 + outer loop + vertex -401.922 162.291 383.075 + vertex -400.928 166.08 385.04 + vertex -402.42 169.271 383.384 + endloop + endfacet + facet normal -0.81328 -0.0811959 0.576179 + outer loop + vertex -402.42 169.271 383.384 + vertex -400.928 166.08 385.04 + vertex -401.409 172.755 385.302 + endloop + endfacet + facet normal -0.810694 -0.0841733 0.579388 + outer loop + vertex -401.634 155.886 382.548 + vertex -400.36 159.755 384.893 + vertex -401.922 162.291 383.075 + endloop + endfacet + facet normal -0.811919 -0.0863952 0.577342 + outer loop + vertex -401.922 162.291 383.075 + vertex -400.36 159.755 384.893 + vertex -400.928 166.08 385.04 + endloop + endfacet + facet normal -0.755344 -0.137088 0.640829 + outer loop + vertex -400.46 150.609 382.947 + vertex -399.449 154.222 384.911 + vertex -400.381 154.208 383.81 + endloop + endfacet + facet normal -0.753125 -0.155718 0.639182 + outer loop + vertex -400.381 154.208 383.81 + vertex -399.449 154.222 384.911 + vertex -399.448 157.133 385.621 + endloop + endfacet + facet normal -0.808694 -0.121157 0.575616 + outer loop + vertex -401.409 172.755 385.302 + vertex -400.544 176.151 387.233 + vertex -402.123 179.697 385.76 + endloop + endfacet + facet normal -0.808982 -0.121481 0.575144 + outer loop + vertex -402.123 179.697 385.76 + vertex -400.544 176.151 387.233 + vertex -401.197 183.134 387.789 + endloop + endfacet + facet normal -0.852512 -0.0816724 0.516288 + outer loop + vertex -400.928 166.08 385.04 + vertex -400.13 169.658 386.925 + vertex -401.409 172.755 385.302 + endloop + endfacet + facet normal -0.850505 -0.0788882 0.520017 + outer loop + vertex -401.409 172.755 385.302 + vertex -400.13 169.658 386.925 + vertex -400.544 176.151 387.233 + endloop + endfacet + facet normal -0.851325 -0.0885428 0.517112 + outer loop + vertex -400.36 159.755 384.893 + vertex -399.832 164.431 386.562 + vertex -400.928 166.08 385.04 + endloop + endfacet + facet normal -0.849738 -0.0844557 0.520396 + outer loop + vertex -400.928 166.08 385.04 + vertex -399.832 164.431 386.562 + vertex -400.13 169.658 386.925 + endloop + endfacet + facet normal -0.780157 -0.148067 0.607808 + outer loop + vertex -399.449 154.222 384.911 + vertex -398.612 158.169 386.947 + vertex -399.448 157.133 385.621 + endloop + endfacet + facet normal -0.778346 -0.151436 0.609298 + outer loop + vertex -399.448 157.133 385.621 + vertex -398.612 158.169 386.947 + vertex -398.966 161.583 387.344 + endloop + endfacet + facet normal -0.841961 -0.120641 0.525878 + outer loop + vertex -400.544 176.151 387.233 + vertex -399.808 179.453 389.168 + vertex -401.197 183.134 387.789 + endloop + endfacet + facet normal -0.844443 -0.123307 0.521259 + outer loop + vertex -401.197 183.134 387.789 + vertex -399.808 179.453 389.168 + vertex -400.504 186.16 389.627 + endloop + endfacet + facet normal -0.879827 -0.0783275 0.468796 + outer loop + vertex -400.13 169.658 386.925 + vertex -399.396 172.956 388.852 + vertex -400.544 176.151 387.233 + endloop + endfacet + facet normal -0.879973 -0.0785373 0.468486 + outer loop + vertex -400.544 176.151 387.233 + vertex -399.396 172.956 388.852 + vertex -399.808 179.453 389.168 + endloop + endfacet + facet normal -0.870516 -0.0831893 0.485058 + outer loop + vertex -399.832 164.431 386.562 + vertex -399.08 167.04 388.359 + vertex -400.13 169.658 386.925 + endloop + endfacet + facet normal -0.872773 -0.0866615 0.480372 + outer loop + vertex -400.13 169.658 386.925 + vertex -399.08 167.04 388.359 + vertex -399.396 172.956 388.852 + endloop + endfacet + facet normal -0.810741 -0.14975 0.565928 + outer loop + vertex -398.612 158.169 386.947 + vertex -397.927 162.083 388.964 + vertex -398.966 161.583 387.344 + endloop + endfacet + facet normal -0.807213 -0.16225 0.567523 + outer loop + vertex -398.966 161.583 387.344 + vertex -397.927 162.083 388.964 + vertex -398.117 165.603 389.7 + endloop + endfacet + facet normal -0.869391 -0.122974 0.478578 + outer loop + vertex -399.808 179.453 389.168 + vertex -399.194 182.736 391.128 + vertex -400.504 186.16 389.627 + endloop + endfacet + facet normal -0.872248 -0.126802 0.472339 + outer loop + vertex -400.504 186.16 389.627 + vertex -399.194 182.736 391.128 + vertex -399.871 189.396 391.665 + endloop + endfacet + facet normal -0.902988 -0.0777656 0.422569 + outer loop + vertex -399.396 172.956 388.852 + vertex -398.765 176.318 390.82 + vertex -399.808 179.453 389.168 + endloop + endfacet + facet normal -0.904662 -0.0804883 0.41846 + outer loop + vertex -399.808 179.453 389.168 + vertex -398.765 176.318 390.82 + vertex -399.194 182.736 391.128 + endloop + endfacet + facet normal -0.893028 -0.0845479 0.441987 + outer loop + vertex -399.08 167.04 388.359 + vertex -398.406 170.476 390.379 + vertex -399.396 172.956 388.852 + endloop + endfacet + facet normal -0.894886 -0.088038 0.437524 + outer loop + vertex -399.396 172.956 388.852 + vertex -398.406 170.476 390.379 + vertex -398.765 176.318 390.82 + endloop + endfacet + facet normal -0.829929 -0.156756 0.535393 + outer loop + vertex -397.927 162.083 388.964 + vertex -397.311 165.819 391.012 + vertex -398.117 165.603 389.7 + endloop + endfacet + facet normal -0.827684 -0.167148 0.535725 + outer loop + vertex -398.117 165.603 389.7 + vertex -397.311 165.819 391.012 + vertex -397.519 169.258 391.765 + endloop + endfacet + facet normal -0.893539 -0.12564 0.431048 + outer loop + vertex -399.194 182.736 391.128 + vertex -398.672 186.084 393.186 + vertex -399.871 189.396 391.665 + endloop + endfacet + facet normal -0.896377 -0.129996 0.423804 + outer loop + vertex -399.871 189.396 391.665 + vertex -398.672 186.084 393.186 + vertex -399.348 192.508 393.725 + endloop + endfacet + facet normal -0.922898 -0.0797009 0.376705 + outer loop + vertex -398.765 176.318 390.82 + vertex -398.236 179.744 392.842 + vertex -399.194 182.736 391.128 + endloop + endfacet + facet normal -0.924925 -0.083724 0.370815 + outer loop + vertex -399.194 182.736 391.128 + vertex -398.236 179.744 392.842 + vertex -398.672 186.084 393.186 + endloop + endfacet + facet normal -0.912294 -0.0863044 0.400338 + outer loop + vertex -398.406 170.476 390.379 + vertex -397.852 173.975 392.396 + vertex -398.765 176.318 390.82 + endloop + endfacet + facet normal -0.91449 -0.091312 0.394169 + outer loop + vertex -398.765 176.318 390.82 + vertex -397.852 173.975 392.396 + vertex -398.236 179.744 392.842 + endloop + endfacet + facet normal -0.848039 -0.161588 0.504697 + outer loop + vertex -397.311 165.819 391.012 + vertex -396.827 169.422 392.98 + vertex -397.519 169.258 391.765 + endloop + endfacet + facet normal -0.845931 -0.171777 0.50487 + outer loop + vertex -397.519 169.258 391.765 + vertex -396.827 169.422 392.98 + vertex -397.037 172.817 393.783 + endloop + endfacet + facet normal -0.913749 -0.128604 0.385388 + outer loop + vertex -398.672 186.084 393.186 + vertex -398.233 189.567 395.387 + vertex -399.348 192.508 393.725 + endloop + endfacet + facet normal -0.915758 -0.132918 0.379105 + outer loop + vertex -399.348 192.508 393.725 + vertex -398.233 189.567 395.387 + vertex -398.898 195.572 395.888 + endloop + endfacet + facet normal -0.939727 -0.0826262 0.331792 + outer loop + vertex -398.236 179.744 392.842 + vertex -397.778 183.365 395.04 + vertex -398.672 186.084 393.186 + endloop + endfacet + facet normal -0.94144 -0.0873667 0.325665 + outer loop + vertex -398.672 186.084 393.186 + vertex -397.778 183.365 395.04 + vertex -398.233 189.567 395.387 + endloop + endfacet + facet normal -0.928235 -0.0896668 0.361025 + outer loop + vertex -397.852 173.975 392.396 + vertex -397.369 177.531 394.521 + vertex -398.236 179.744 392.842 + endloop + endfacet + facet normal -0.930607 -0.0966629 0.353026 + outer loop + vertex -398.236 179.744 392.842 + vertex -397.369 177.531 394.521 + vertex -397.778 183.365 395.04 + endloop + endfacet + facet normal -0.864415 -0.165781 0.474661 + outer loop + vertex -396.827 169.422 392.98 + vertex -396.42 172.94 394.95 + vertex -397.037 172.817 393.783 + endloop + endfacet + facet normal -0.861846 -0.178641 0.474667 + outer loop + vertex -397.037 172.817 393.783 + vertex -396.42 172.94 394.95 + vertex -396.613 176.318 395.87 + endloop + endfacet + facet normal -0.928571 -0.13166 0.347018 + outer loop + vertex -398.233 189.567 395.387 + vertex -397.857 193.217 397.778 + vertex -398.898 195.572 395.888 + endloop + endfacet + facet normal -0.929909 -0.13674 0.341426 + outer loop + vertex -398.898 195.572 395.888 + vertex -397.857 193.217 397.778 + vertex -398.497 198.523 398.16 + endloop + endfacet + facet normal -0.953782 -0.0861546 0.287884 + outer loop + vertex -397.778 183.365 395.04 + vertex -397.423 187.399 397.424 + vertex -398.233 189.567 395.387 + endloop + endfacet + facet normal -0.954293 -0.0886589 0.28542 + outer loop + vertex -398.233 189.567 395.387 + vertex -397.423 187.399 397.424 + vertex -397.857 193.217 397.778 + endloop + endfacet + facet normal -0.940379 -0.0949973 0.326591 + outer loop + vertex -397.369 177.531 394.521 + vertex -396.864 181.501 397.13 + vertex -397.778 183.365 395.04 + endloop + endfacet + facet normal -0.94214 -0.105157 0.318299 + outer loop + vertex -397.778 183.365 395.04 + vertex -396.864 181.501 397.13 + vertex -397.423 187.399 397.424 + endloop + endfacet + facet normal -0.879196 -0.171427 0.444552 + outer loop + vertex -396.42 172.94 394.95 + vertex -396.062 176.501 397.03 + vertex -396.613 176.318 395.87 + endloop + endfacet + facet normal -0.876064 -0.185156 0.44523 + outer loop + vertex -396.613 176.318 395.87 + vertex -396.062 176.501 397.03 + vertex -396.223 179.117 397.802 + endloop + endfacet + facet normal -0.932687 -0.13653 0.333849 + outer loop + vertex -397.857 193.217 397.778 + vertex -397.47 197.02 400.415 + vertex -398.497 198.523 398.16 + endloop + endfacet + facet normal -0.933719 -0.151371 0.324432 + outer loop + vertex -398.497 198.523 398.16 + vertex -397.47 197.02 400.415 + vertex -398.089 201.383 400.669 + endloop + endfacet + facet normal -0.964113 -0.0872771 0.250736 + outer loop + vertex -397.423 187.399 397.424 + vertex -397.121 191.641 400.062 + vertex -397.857 193.217 397.778 + endloop + endfacet + facet normal -0.963423 -0.0793994 0.255952 + outer loop + vertex -397.857 193.217 397.778 + vertex -397.121 191.641 400.062 + vertex -397.47 197.02 400.415 + endloop + endfacet + facet normal -0.954492 -0.104386 0.279373 + outer loop + vertex -396.864 181.501 397.13 + vertex -396.702 186.471 399.539 + vertex -397.423 187.399 397.424 + endloop + endfacet + facet normal -0.95451 -0.105476 0.278901 + outer loop + vertex -397.423 187.399 397.424 + vertex -396.702 186.471 399.539 + vertex -397.121 191.641 400.062 + endloop + endfacet + facet normal -0.880743 -0.182962 0.436827 + outer loop + vertex -396.062 176.501 397.03 + vertex -395.76 180.18 399.18 + vertex -396.223 179.117 397.802 + endloop + endfacet + facet normal -0.880904 -0.182642 0.436634 + outer loop + vertex -396.223 179.117 397.802 + vertex -395.76 180.18 399.18 + vertex -396.021 183.264 399.943 + endloop + endfacet + facet normal -0.960206 -0.0758301 0.268803 + outer loop + vertex -396.985 198.263 402.499 + vertex -397.194 200.594 402.408 + vertex -397.47 197.02 400.415 + endloop + endfacet + facet normal -0.90456 -0.217459 0.366719 + outer loop + vertex -397.627 203.747 403.211 + vertex -398.089 201.383 400.669 + vertex -397.194 200.594 402.408 + endloop + endfacet + facet normal -0.905238 -0.151558 0.396957 + outer loop + vertex -398.089 201.383 400.669 + vertex -397.47 197.02 400.415 + vertex -397.194 200.594 402.408 + endloop + endfacet + facet normal -0.971379 -0.0728646 0.226083 + outer loop + vertex -396.734 192.871 402.122 + vertex -396.944 195.454 402.051 + vertex -397.121 191.641 400.062 + endloop + endfacet + facet normal -0.964684 -0.0552192 0.257555 + outer loop + vertex -396.985 198.263 402.499 + vertex -397.47 197.02 400.415 + vertex -396.944 195.454 402.051 + endloop + endfacet + facet normal -0.968452 -0.0784512 0.236529 + outer loop + vertex -397.47 197.02 400.415 + vertex -397.121 191.641 400.062 + vertex -396.944 195.454 402.051 + endloop + endfacet + facet normal -0.928638 -0.153566 0.337712 + outer loop + vertex -396.107 186.99 401.413 + vertex -396.515 189.866 401.596 + vertex -396.702 186.471 399.539 + endloop + endfacet + facet normal -0.962 -0.11327 0.248449 + outer loop + vertex -396.734 192.871 402.122 + vertex -397.121 191.641 400.062 + vertex -396.515 189.866 401.596 + endloop + endfacet + facet normal -0.96037 -0.103902 0.258638 + outer loop + vertex -397.121 191.641 400.062 + vertex -396.702 186.471 399.539 + vertex -396.515 189.866 401.596 + endloop + endfacet + facet normal -0.873843 -0.185237 0.44954 + outer loop + vertex -395.76 180.18 399.18 + vertex -395.21 184.198 401.906 + vertex -396.021 183.264 399.943 + endloop + endfacet + facet normal -0.865878 -0.205721 0.455999 + outer loop + vertex -396.021 183.264 399.943 + vertex -395.21 184.198 401.906 + vertex -395.318 186.955 402.943 + endloop + endfacet + facet normal -0.942494 -0.0405939 0.331748 + outer loop + vertex -396.183 200.502 405.38 + vertex -396.246 201.71 405.349 + vertex -396.628 200.203 404.078 + endloop + endfacet + facet normal -0.915903 -0.0565376 0.397398 + outer loop + vertex -396.181 202.943 405.674 + vertex -396.738 202.68 404.353 + vertex -396.246 201.71 405.349 + endloop + endfacet + facet normal -0.92309 -0.0825322 0.375623 + outer loop + vertex -396.738 202.68 404.353 + vertex -396.628 200.203 404.078 + vertex -396.246 201.71 405.349 + endloop + endfacet + facet normal -0.949638 -0.0734863 0.304609 + outer loop + vertex -396.985 198.263 402.499 + vertex -396.628 200.203 404.078 + vertex -397.194 200.594 402.408 + endloop + endfacet + facet normal -0.949631 -0.0757675 0.304073 + outer loop + vertex -397.194 200.594 402.408 + vertex -396.628 200.203 404.078 + vertex -396.738 202.68 404.353 + endloop + endfacet + facet normal -0.860898 -0.233239 0.452167 + outer loop + vertex -397.194 200.594 402.408 + vertex -396.738 202.68 404.353 + vertex -397.627 203.747 403.211 + endloop + endfacet + facet normal -0.867024 -0.284521 0.409044 + outer loop + vertex -397.627 203.747 403.211 + vertex -396.738 202.68 404.353 + vertex -397.249 204.894 404.81 + endloop + endfacet + facet normal -0.901073 -0.144922 0.408736 + outer loop + vertex -396.181 202.943 405.674 + vertex -396.357 204.121 405.705 + vertex -396.738 202.68 404.353 + endloop + endfacet + facet normal -0.798248 -0.393486 0.456036 + outer loop + vertex -396.781 205.67 406.299 + vertex -397.249 204.894 404.81 + vertex -396.357 204.121 405.705 + endloop + endfacet + facet normal -0.791643 -0.293292 0.535986 + outer loop + vertex -397.249 204.894 404.81 + vertex -396.738 202.68 404.353 + vertex -396.357 204.121 405.705 + endloop + endfacet + facet normal -0.936991 -0.0792657 0.340243 + outer loop + vertex -396.052 195.648 404.963 + vertex -396.175 196.773 404.887 + vertex -396.469 195.102 403.689 + endloop + endfacet + facet normal -0.942784 -0.0527919 0.329199 + outer loop + vertex -396.153 198.015 405.148 + vertex -396.578 197.664 403.875 + vertex -396.175 196.773 404.887 + endloop + endfacet + facet normal -0.945096 -0.0636987 0.320524 + outer loop + vertex -396.578 197.664 403.875 + vertex -396.469 195.102 403.689 + vertex -396.175 196.773 404.887 + endloop + endfacet + facet normal -0.961998 -0.0710745 0.263645 + outer loop + vertex -396.734 192.871 402.122 + vertex -396.469 195.102 403.689 + vertex -396.944 195.454 402.051 + endloop + endfacet + facet normal -0.962088 -0.0604629 0.265952 + outer loop + vertex -396.944 195.454 402.051 + vertex -396.469 195.102 403.689 + vertex -396.578 197.664 403.875 + endloop + endfacet + facet normal -0.963865 -0.055678 0.260508 + outer loop + vertex -396.944 195.454 402.051 + vertex -396.578 197.664 403.875 + vertex -396.985 198.263 402.499 + endloop + endfacet + facet normal -0.962881 -0.0403564 0.266893 + outer loop + vertex -396.985 198.263 402.499 + vertex -396.578 197.664 403.875 + vertex -396.628 200.203 404.078 + endloop + endfacet + facet normal -0.943386 -0.0482948 0.328161 + outer loop + vertex -396.153 198.015 405.148 + vertex -396.234 199.223 405.093 + vertex -396.578 197.664 403.875 + endloop + endfacet + facet normal -0.942948 -0.0364089 0.330943 + outer loop + vertex -396.183 200.502 405.38 + vertex -396.628 200.203 404.078 + vertex -396.234 199.223 405.093 + endloop + endfacet + facet normal -0.945051 -0.044575 0.323871 + outer loop + vertex -396.628 200.203 404.078 + vertex -396.578 197.664 403.875 + vertex -396.234 199.223 405.093 + endloop + endfacet + facet normal -0.881221 -0.199811 0.428398 + outer loop + vertex -395.487 190.822 404.478 + vertex -395.74 191.886 404.454 + vertex -395.819 189.749 403.294 + endloop + endfacet + facet normal -0.911718 -0.155902 0.380084 + outer loop + vertex -395.855 193.281 404.75 + vertex -396.244 192.466 403.483 + vertex -395.74 191.886 404.454 + endloop + endfacet + facet normal -0.91243 -0.168524 0.372922 + outer loop + vertex -396.244 192.466 403.483 + vertex -395.819 189.749 403.294 + vertex -395.74 191.886 404.454 + endloop + endfacet + facet normal -0.917886 -0.153831 0.365816 + outer loop + vertex -396.107 186.99 401.413 + vertex -395.819 189.749 403.294 + vertex -396.515 189.866 401.596 + endloop + endfacet + facet normal -0.916021 -0.168468 0.364038 + outer loop + vertex -396.515 189.866 401.596 + vertex -395.819 189.749 403.294 + vertex -396.244 192.466 403.483 + endloop + endfacet + facet normal -0.944942 -0.121705 0.303763 + outer loop + vertex -396.515 189.866 401.596 + vertex -396.244 192.466 403.483 + vertex -396.734 192.871 402.122 + endloop + endfacet + facet normal -0.945293 -0.104854 0.308911 + outer loop + vertex -396.734 192.871 402.122 + vertex -396.244 192.466 403.483 + vertex -396.469 195.102 403.689 + endloop + endfacet + facet normal -0.923046 -0.125127 0.363772 + outer loop + vertex -395.855 193.281 404.75 + vertex -396.026 194.407 404.703 + vertex -396.244 192.466 403.483 + endloop + endfacet + facet normal -0.934154 -0.0920558 0.344792 + outer loop + vertex -396.052 195.648 404.963 + vertex -396.469 195.102 403.689 + vertex -396.026 194.407 404.703 + endloop + endfacet + facet normal -0.935899 -0.106162 0.335891 + outer loop + vertex -396.469 195.102 403.689 + vertex -396.244 192.466 403.483 + vertex -396.026 194.407 404.703 + endloop + endfacet + facet normal -0.79949 -0.251841 0.545337 + outer loop + vertex -394.459 187.131 404.361 + vertex -394.561 187.31 404.294 + vertex -395.21 184.198 401.906 + endloop + endfacet + facet normal -0.819103 -0.238109 0.521895 + outer loop + vertex -394.508 188.622 404.976 + vertex -395.318 186.955 402.943 + vertex -394.561 187.31 404.294 + endloop + endfacet + facet normal -0.822287 -0.228534 0.521167 + outer loop + vertex -395.318 186.955 402.943 + vertex -395.21 184.198 401.906 + vertex -394.561 187.31 404.294 + endloop + endfacet + facet normal -0.812693 -0.0590393 0.579693 + outer loop + vertex -394.685 201.24 408.207 + vertex -394.271 201.318 408.795 + vertex -394.64 202.367 408.385 + endloop + endfacet + facet normal -0.804034 -0.0510357 0.592389 + outer loop + vertex -394.64 202.367 408.385 + vertex -394.271 201.318 408.795 + vertex -394.158 202.384 409.041 + endloop + endfacet + facet normal -0.845115 -0.0574613 0.531487 + outer loop + vertex -395.23 201.219 407.338 + vertex -394.685 201.24 408.207 + vertex -395.204 202.374 407.504 + endloop + endfacet + facet normal -0.841142 -0.0513767 0.538368 + outer loop + vertex -395.204 202.374 407.504 + vertex -394.685 201.24 408.207 + vertex -394.64 202.367 408.385 + endloop + endfacet + facet normal -0.840113 -0.0724376 0.537552 + outer loop + vertex -395.204 202.374 407.504 + vertex -394.64 202.367 408.385 + vertex -395.175 203.54 407.708 + endloop + endfacet + facet normal -0.834834 -0.0647619 0.546679 + outer loop + vertex -395.175 203.54 407.708 + vertex -394.64 202.367 408.385 + vertex -394.59 203.522 408.598 + endloop + endfacet + facet normal -0.802563 -0.0744603 0.591902 + outer loop + vertex -394.64 202.367 408.385 + vertex -394.158 202.384 409.041 + vertex -394.59 203.522 408.598 + endloop + endfacet + facet normal -0.80626 -0.0780084 0.586396 + outer loop + vertex -394.59 203.522 408.598 + vertex -394.158 202.384 409.041 + vertex -394.16 203.622 409.202 + endloop + endfacet + facet normal -0.876302 -0.0527735 0.478862 + outer loop + vertex -395.772 201.007 406.324 + vertex -395.23 201.219 407.338 + vertex -395.76 202.209 406.478 + endloop + endfacet + facet normal -0.874946 -0.0496057 0.481673 + outer loop + vertex -395.76 202.209 406.478 + vertex -395.23 201.219 407.338 + vertex -395.204 202.374 407.504 + endloop + endfacet + facet normal -0.908685 -0.036668 0.415868 + outer loop + vertex -396.183 200.502 405.38 + vertex -395.772 201.007 406.324 + vertex -396.246 201.71 405.349 + endloop + endfacet + facet normal -0.910349 -0.0438224 0.411514 + outer loop + vertex -396.246 201.71 405.349 + vertex -395.772 201.007 406.324 + vertex -395.76 202.209 406.478 + endloop + endfacet + facet normal -0.906289 -0.0624753 0.418016 + outer loop + vertex -396.246 201.71 405.349 + vertex -395.76 202.209 406.478 + vertex -396.181 202.943 405.674 + endloop + endfacet + facet normal -0.904447 -0.0560931 0.422883 + outer loop + vertex -396.181 202.943 405.674 + vertex -395.76 202.209 406.478 + vertex -395.749 203.398 406.658 + endloop + endfacet + facet normal -0.873055 -0.0655268 0.483199 + outer loop + vertex -395.76 202.209 406.478 + vertex -395.204 202.374 407.504 + vertex -395.749 203.398 406.658 + endloop + endfacet + facet normal -0.871776 -0.0626261 0.485886 + outer loop + vertex -395.749 203.398 406.658 + vertex -395.204 202.374 407.504 + vertex -395.175 203.54 407.708 + endloop + endfacet + facet normal -0.854254 -0.170853 0.490977 + outer loop + vertex -395.749 203.398 406.658 + vertex -395.175 203.54 407.708 + vertex -395.845 204.641 406.925 + endloop + endfacet + facet normal -0.855618 -0.174225 0.487406 + outer loop + vertex -395.845 204.641 406.925 + vertex -395.175 203.54 407.708 + vertex -395.255 204.768 408.006 + endloop + endfacet + facet normal -0.880277 -0.142963 0.45241 + outer loop + vertex -396.181 202.943 405.674 + vertex -395.749 203.398 406.658 + vertex -396.357 204.121 405.705 + endloop + endfacet + facet normal -0.883328 -0.162096 0.439836 + outer loop + vertex -396.357 204.121 405.705 + vertex -395.749 203.398 406.658 + vertex -395.845 204.641 406.925 + endloop + endfacet + facet normal -0.77125 -0.400842 0.494469 + outer loop + vertex -396.357 204.121 405.705 + vertex -395.845 204.641 406.925 + vertex -396.781 205.67 406.299 + endloop + endfacet + facet normal -0.777898 -0.427465 0.460595 + outer loop + vertex -396.781 205.67 406.299 + vertex -395.845 204.641 406.925 + vertex -396.296 206.043 407.464 + endloop + endfacet + facet normal -0.770628 -0.429169 0.471112 + outer loop + vertex -395.845 204.641 406.925 + vertex -395.255 204.768 408.006 + vertex -396.296 206.043 407.464 + endloop + endfacet + facet normal -0.771453 -0.431214 0.467884 + outer loop + vertex -396.296 206.043 407.464 + vertex -395.255 204.768 408.006 + vertex -395.714 206.184 408.554 + endloop + endfacet + facet normal -0.785236 -0.188668 0.589753 + outer loop + vertex -394.59 203.522 408.598 + vertex -394.16 203.622 409.202 + vertex -394.652 204.749 408.909 + endloop + endfacet + facet normal -0.81294 -0.213214 0.541912 + outer loop + vertex -394.652 204.749 408.909 + vertex -394.16 203.622 409.202 + vertex -394.163 204.78 409.653 + endloop + endfacet + facet normal -0.823435 -0.184086 0.536718 + outer loop + vertex -395.175 203.54 407.708 + vertex -394.59 203.522 408.598 + vertex -395.255 204.768 408.006 + endloop + endfacet + facet normal -0.819879 -0.178775 0.543909 + outer loop + vertex -395.255 204.768 408.006 + vertex -394.59 203.522 408.598 + vertex -394.652 204.749 408.909 + endloop + endfacet + facet normal -0.752902 -0.435204 0.493696 + outer loop + vertex -395.255 204.768 408.006 + vertex -394.652 204.749 408.909 + vertex -395.714 206.184 408.554 + endloop + endfacet + facet normal -0.756208 -0.439961 0.484339 + outer loop + vertex -395.714 206.184 408.554 + vertex -394.652 204.749 408.909 + vertex -395.022 206.118 409.574 + endloop + endfacet + facet normal -0.740276 -0.445126 0.50384 + outer loop + vertex -394.652 204.749 408.909 + vertex -394.163 204.78 409.653 + vertex -395.022 206.118 409.574 + endloop + endfacet + facet normal -0.736287 -0.442065 0.512308 + outer loop + vertex -395.022 206.118 409.574 + vertex -394.163 204.78 409.653 + vertex -394.209 205.868 410.527 + endloop + endfacet + facet normal -0.811907 -0.111019 0.573133 + outer loop + vertex -394.671 196.767 407.567 + vertex -394.316 196.926 408.1 + vertex -394.703 197.857 407.732 + endloop + endfacet + facet normal -0.806779 -0.105639 0.581332 + outer loop + vertex -394.703 197.857 407.732 + vertex -394.316 196.926 408.1 + vertex -394.285 197.941 408.327 + endloop + endfacet + facet normal -0.834477 -0.0983574 0.542194 + outer loop + vertex -395.167 196.616 406.775 + vertex -394.671 196.767 407.567 + vertex -395.211 197.72 406.908 + endloop + endfacet + facet normal -0.838509 -0.105967 0.534485 + outer loop + vertex -395.211 197.72 406.908 + vertex -394.671 196.767 407.567 + vertex -394.703 197.857 407.732 + endloop + endfacet + facet normal -0.842367 -0.0812027 0.532751 + outer loop + vertex -395.211 197.72 406.908 + vertex -394.703 197.857 407.732 + vertex -395.236 198.878 407.045 + endloop + endfacet + facet normal -0.844221 -0.0844927 0.529294 + outer loop + vertex -395.236 198.878 407.045 + vertex -394.703 197.857 407.732 + vertex -394.717 198.985 407.89 + endloop + endfacet + facet normal -0.808905 -0.0913076 0.580805 + outer loop + vertex -394.703 197.857 407.732 + vertex -394.285 197.941 408.327 + vertex -394.717 198.985 407.89 + endloop + endfacet + facet normal -0.814345 -0.0971591 0.572191 + outer loop + vertex -394.717 198.985 407.89 + vertex -394.285 197.941 408.327 + vertex -394.337 199.102 408.451 + endloop + endfacet + facet normal -0.860637 -0.0851723 0.502046 + outer loop + vertex -395.677 196.284 405.845 + vertex -395.167 196.616 406.775 + vertex -395.728 197.402 405.947 + endloop + endfacet + facet normal -0.863432 -0.0939106 0.495648 + outer loop + vertex -395.728 197.402 405.947 + vertex -395.167 196.616 406.775 + vertex -395.211 197.72 406.908 + endloop + endfacet + facet normal -0.899008 -0.0688757 0.432483 + outer loop + vertex -396.052 195.648 404.963 + vertex -395.677 196.284 405.845 + vertex -396.175 196.773 404.887 + endloop + endfacet + facet normal -0.900464 -0.0801709 0.427478 + outer loop + vertex -396.175 196.773 404.887 + vertex -395.677 196.284 405.845 + vertex -395.728 197.402 405.947 + endloop + endfacet + facet normal -0.9025 -0.0734903 0.424373 + outer loop + vertex -396.175 196.773 404.887 + vertex -395.728 197.402 405.947 + vertex -396.153 198.015 405.148 + endloop + endfacet + facet normal -0.900882 -0.066384 0.428959 + outer loop + vertex -396.153 198.015 405.148 + vertex -395.728 197.402 405.947 + vertex -395.761 198.584 406.062 + endloop + endfacet + facet normal -0.868315 -0.0714568 0.490839 + outer loop + vertex -395.728 197.402 405.947 + vertex -395.211 197.72 406.908 + vertex -395.761 198.584 406.062 + endloop + endfacet + facet normal -0.870074 -0.0763696 0.48697 + outer loop + vertex -395.761 198.584 406.062 + vertex -395.211 197.72 406.908 + vertex -395.236 198.878 407.045 + endloop + endfacet + facet normal -0.873259 -0.0594647 0.483614 + outer loop + vertex -395.761 198.584 406.062 + vertex -395.236 198.878 407.045 + vertex -395.774 199.795 406.187 + endloop + endfacet + facet normal -0.874149 -0.0617645 0.481715 + outer loop + vertex -395.774 199.795 406.187 + vertex -395.236 198.878 407.045 + vertex -395.24 200.05 407.187 + endloop + endfacet + facet normal -0.908041 -0.041893 0.416781 + outer loop + vertex -396.153 198.015 405.148 + vertex -395.761 198.584 406.062 + vertex -396.234 199.223 405.093 + endloop + endfacet + facet normal -0.910168 -0.0523484 0.410918 + outer loop + vertex -396.234 199.223 405.093 + vertex -395.761 198.584 406.062 + vertex -395.774 199.795 406.187 + endloop + endfacet + facet normal -0.909244 -0.0560666 0.412471 + outer loop + vertex -396.234 199.223 405.093 + vertex -395.774 199.795 406.187 + vertex -396.183 200.502 405.38 + endloop + endfacet + facet normal -0.906418 -0.0459985 0.41987 + outer loop + vertex -396.183 200.502 405.38 + vertex -395.774 199.795 406.187 + vertex -395.772 201.007 406.324 + endloop + endfacet + facet normal -0.875566 -0.0528671 0.480196 + outer loop + vertex -395.774 199.795 406.187 + vertex -395.24 200.05 407.187 + vertex -395.772 201.007 406.324 + endloop + endfacet + facet normal -0.876109 -0.0541975 0.479057 + outer loop + vertex -395.772 201.007 406.324 + vertex -395.24 200.05 407.187 + vertex -395.23 201.219 407.338 + endloop + endfacet + facet normal -0.818388 -0.0734026 0.56996 + outer loop + vertex -394.717 198.985 407.89 + vertex -394.337 199.102 408.451 + vertex -394.711 200.115 408.044 + endloop + endfacet + facet normal -0.811031 -0.0661461 0.581252 + outer loop + vertex -394.711 200.115 408.044 + vertex -394.337 199.102 408.451 + vertex -394.262 200.138 408.674 + endloop + endfacet + facet normal -0.84632 -0.0673029 0.528406 + outer loop + vertex -395.236 198.878 407.045 + vertex -394.717 198.985 407.89 + vertex -395.24 200.05 407.187 + endloop + endfacet + facet normal -0.846476 -0.0675672 0.528122 + outer loop + vertex -395.24 200.05 407.187 + vertex -394.717 198.985 407.89 + vertex -394.711 200.115 408.044 + endloop + endfacet + facet normal -0.84708 -0.0607628 0.52798 + outer loop + vertex -395.24 200.05 407.187 + vertex -394.711 200.115 408.044 + vertex -395.23 201.219 407.338 + endloop + endfacet + facet normal -0.845108 -0.0575926 0.531485 + outer loop + vertex -395.23 201.219 407.338 + vertex -394.711 200.115 408.044 + vertex -394.685 201.24 408.207 + endloop + endfacet + facet normal -0.811068 -0.0656164 0.58126 + outer loop + vertex -394.711 200.115 408.044 + vertex -394.262 200.138 408.674 + vertex -394.685 201.24 408.207 + endloop + endfacet + facet normal -0.811848 -0.0664161 0.580079 + outer loop + vertex -394.685 201.24 408.207 + vertex -394.262 200.138 408.674 + vertex -394.271 201.318 408.795 + endloop + endfacet + facet normal -0.76928 -0.191757 0.609457 + outer loop + vertex -394.353 193.026 406.991 + vertex -394.039 193.255 407.461 + vertex -394.463 193.904 407.129 + endloop + endfacet + facet normal -0.768011 -0.189794 0.611668 + outer loop + vertex -394.463 193.904 407.129 + vertex -394.039 193.255 407.461 + vertex -394.081 194.033 407.648 + endloop + endfacet + facet normal -0.792999 -0.189982 0.578842 + outer loop + vertex -394.792 192.567 406.24 + vertex -394.353 193.026 406.991 + vertex -394.935 193.626 406.392 + endloop + endfacet + facet normal -0.792982 -0.189921 0.578887 + outer loop + vertex -394.935 193.626 406.392 + vertex -394.353 193.026 406.991 + vertex -394.463 193.904 407.129 + endloop + endfacet + facet normal -0.803209 -0.159444 0.573962 + outer loop + vertex -394.935 193.626 406.392 + vertex -394.463 193.904 407.129 + vertex -395.032 194.612 406.53 + endloop + endfacet + facet normal -0.805465 -0.165359 0.569106 + outer loop + vertex -395.032 194.612 406.53 + vertex -394.463 193.904 407.129 + vertex -394.547 194.794 407.269 + endloop + endfacet + facet normal -0.773685 -0.168928 0.610635 + outer loop + vertex -394.463 193.904 407.129 + vertex -394.081 194.033 407.648 + vertex -394.547 194.794 407.269 + endloop + endfacet + facet normal -0.781874 -0.180919 0.596608 + outer loop + vertex -394.547 194.794 407.269 + vertex -394.081 194.033 407.648 + vertex -394.21 194.945 407.757 + endloop + endfacet + facet normal -0.81692 -0.19697 0.542074 + outer loop + vertex -395.204 191.676 405.295 + vertex -394.792 192.567 406.24 + vertex -395.392 192.979 405.486 + endloop + endfacet + facet normal -0.816208 -0.188447 0.546162 + outer loop + vertex -395.392 192.979 405.486 + vertex -394.792 192.567 406.24 + vertex -394.935 193.626 406.392 + endloop + endfacet + facet normal -0.848791 -0.190624 0.493169 + outer loop + vertex -395.487 190.822 404.478 + vertex -395.204 191.676 405.295 + vertex -395.74 191.886 404.454 + endloop + endfacet + facet normal -0.848575 -0.194235 0.492131 + outer loop + vertex -395.74 191.886 404.454 + vertex -395.204 191.676 405.295 + vertex -395.392 192.979 405.486 + endloop + endfacet + facet normal -0.863875 -0.171787 0.473508 + outer loop + vertex -395.74 191.886 404.454 + vertex -395.392 192.979 405.486 + vertex -395.855 193.281 404.75 + endloop + endfacet + facet normal -0.863417 -0.155327 0.479983 + outer loop + vertex -395.855 193.281 404.75 + vertex -395.392 192.979 405.486 + vertex -395.52 194.14 405.63 + endloop + endfacet + facet normal -0.831572 -0.158312 0.532376 + outer loop + vertex -395.392 192.979 405.486 + vertex -394.935 193.626 406.392 + vertex -395.52 194.14 405.63 + endloop + endfacet + facet normal -0.831281 -0.156523 0.533359 + outer loop + vertex -395.52 194.14 405.63 + vertex -394.935 193.626 406.392 + vertex -395.032 194.612 406.53 + endloop + endfacet + facet normal -0.843285 -0.124213 0.522917 + outer loop + vertex -395.52 194.14 405.63 + vertex -395.032 194.612 406.53 + vertex -395.607 195.207 405.744 + endloop + endfacet + facet normal -0.844653 -0.130483 0.519168 + outer loop + vertex -395.607 195.207 405.744 + vertex -395.032 194.612 406.53 + vertex -395.106 195.588 406.654 + endloop + endfacet + facet normal -0.88559 -0.1158 0.449801 + outer loop + vertex -395.855 193.281 404.75 + vertex -395.52 194.14 405.63 + vertex -396.026 194.407 404.703 + endloop + endfacet + facet normal -0.88563 -0.119703 0.448699 + outer loop + vertex -396.026 194.407 404.703 + vertex -395.52 194.14 405.63 + vertex -395.607 195.207 405.744 + endloop + endfacet + facet normal -0.888954 -0.111974 0.444097 + outer loop + vertex -396.026 194.407 404.703 + vertex -395.607 195.207 405.744 + vertex -396.052 195.648 404.963 + endloop + endfacet + facet normal -0.887419 -0.0999595 0.449995 + outer loop + vertex -396.052 195.648 404.963 + vertex -395.607 195.207 405.744 + vertex -395.677 196.284 405.845 + endloop + endfacet + facet normal -0.852574 -0.103541 0.512246 + outer loop + vertex -395.607 195.207 405.744 + vertex -395.106 195.588 406.654 + vertex -395.677 196.284 405.845 + endloop + endfacet + facet normal -0.854451 -0.110403 0.507666 + outer loop + vertex -395.677 196.284 405.845 + vertex -395.106 195.588 406.654 + vertex -395.167 196.616 406.775 + endloop + endfacet + facet normal -0.791128 -0.149135 0.593191 + outer loop + vertex -394.547 194.794 407.269 + vertex -394.21 194.945 407.757 + vertex -394.616 195.741 407.415 + endloop + endfacet + facet normal -0.791317 -0.149364 0.592881 + outer loop + vertex -394.616 195.741 407.415 + vertex -394.21 194.945 407.757 + vertex -394.223 195.856 407.969 + endloop + endfacet + facet normal -0.813121 -0.134108 0.566436 + outer loop + vertex -395.032 194.612 406.53 + vertex -394.547 194.794 407.269 + vertex -395.106 195.588 406.654 + endloop + endfacet + facet normal -0.818115 -0.145436 0.556359 + outer loop + vertex -395.106 195.588 406.654 + vertex -394.547 194.794 407.269 + vertex -394.616 195.741 407.415 + endloop + endfacet + facet normal -0.824516 -0.114122 0.554211 + outer loop + vertex -395.106 195.588 406.654 + vertex -394.616 195.741 407.415 + vertex -395.167 196.616 406.775 + endloop + endfacet + facet normal -0.829656 -0.124692 0.544172 + outer loop + vertex -395.167 196.616 406.775 + vertex -394.616 195.741 407.415 + vertex -394.671 196.767 407.567 + endloop + endfacet + facet normal -0.795525 -0.12991 0.59183 + outer loop + vertex -394.616 195.741 407.415 + vertex -394.223 195.856 407.969 + vertex -394.671 196.767 407.567 + endloop + endfacet + facet normal -0.804464 -0.140834 0.577064 + outer loop + vertex -394.671 196.767 407.567 + vertex -394.223 195.856 407.969 + vertex -394.316 196.926 408.1 + endloop + endfacet + facet normal -0.731733 -0.261711 0.629345 + outer loop + vertex -393.834 189.835 406.402 + vertex -393.586 190.482 406.96 + vertex -393.871 190.579 406.669 + endloop + endfacet + facet normal -0.732011 -0.254089 0.632139 + outer loop + vertex -393.871 190.579 406.669 + vertex -393.586 190.482 406.96 + vertex -393.618 191.146 407.189 + endloop + endfacet + facet normal -0.760822 -0.245234 0.600841 + outer loop + vertex -394.099 189.27 405.836 + vertex -393.834 189.835 406.402 + vertex -394.227 189.814 405.897 + endloop + endfacet + facet normal -0.759204 -0.252507 0.599875 + outer loop + vertex -394.227 189.814 405.897 + vertex -393.834 189.835 406.402 + vertex -393.871 190.579 406.669 + endloop + endfacet + facet normal -0.762229 -0.248789 0.597588 + outer loop + vertex -394.227 189.814 405.897 + vertex -393.871 190.579 406.669 + vertex -394.31 190.65 406.138 + endloop + endfacet + facet normal -0.762696 -0.24526 0.59845 + outer loop + vertex -394.31 190.65 406.138 + vertex -393.871 190.579 406.669 + vertex -394.017 191.329 406.79 + endloop + endfacet + facet normal -0.739866 -0.24534 0.626423 + outer loop + vertex -393.871 190.579 406.669 + vertex -393.618 191.146 407.189 + vertex -394.017 191.329 406.79 + endloop + endfacet + facet normal -0.739898 -0.246365 0.625983 + outer loop + vertex -394.017 191.329 406.79 + vertex -393.618 191.146 407.189 + vertex -393.78 191.776 407.247 + endloop + endfacet + facet normal -0.789674 -0.247608 0.561343 + outer loop + vertex -394.099 189.27 405.836 + vertex -394.227 189.814 405.897 + vertex -394.508 188.622 404.976 + endloop + endfacet + facet normal -0.797749 -0.239552 0.553364 + outer loop + vertex -394.31 190.65 406.138 + vertex -394.95 189.937 404.908 + vertex -394.227 189.814 405.897 + endloop + endfacet + facet normal -0.79775 -0.239544 0.553366 + outer loop + vertex -394.95 189.937 404.908 + vertex -394.508 188.622 404.976 + vertex -394.227 189.814 405.897 + endloop + endfacet + facet normal -0.800101 -0.221216 0.557586 + outer loop + vertex -394.792 192.567 406.24 + vertex -395.204 191.676 405.295 + vertex -394.582 191.436 406.092 + endloop + endfacet + facet normal -0.796133 -0.242671 0.554331 + outer loop + vertex -394.31 190.65 406.138 + vertex -394.582 191.436 406.092 + vertex -394.95 189.937 404.908 + endloop + endfacet + facet normal -0.814387 -0.236967 0.529736 + outer loop + vertex -395.487 190.822 404.478 + vertex -394.95 189.937 404.908 + vertex -395.204 191.676 405.295 + endloop + endfacet + facet normal -0.799162 -0.239551 0.551322 + outer loop + vertex -394.582 191.436 406.092 + vertex -395.204 191.676 405.295 + vertex -394.95 189.937 404.908 + endloop + endfacet + facet normal -0.752731 -0.23017 0.616781 + outer loop + vertex -394.017 191.329 406.79 + vertex -393.78 191.776 407.247 + vertex -394.203 192.139 406.866 + endloop + endfacet + facet normal -0.751569 -0.225532 0.619902 + outer loop + vertex -394.203 192.139 406.866 + vertex -393.78 191.776 407.247 + vertex -393.873 192.474 407.388 + endloop + endfacet + facet normal -0.773186 -0.232605 0.589982 + outer loop + vertex -394.31 190.65 406.138 + vertex -394.017 191.329 406.79 + vertex -394.582 191.436 406.092 + endloop + endfacet + facet normal -0.773213 -0.23237 0.590039 + outer loop + vertex -394.582 191.436 406.092 + vertex -394.017 191.329 406.79 + vertex -394.203 192.139 406.866 + endloop + endfacet + facet normal -0.78121 -0.221159 0.583781 + outer loop + vertex -394.582 191.436 406.092 + vertex -394.203 192.139 406.866 + vertex -394.792 192.567 406.24 + endloop + endfacet + facet normal -0.780415 -0.215348 0.587007 + outer loop + vertex -394.792 192.567 406.24 + vertex -394.203 192.139 406.866 + vertex -394.353 193.026 406.991 + endloop + endfacet + facet normal -0.756941 -0.215578 0.616901 + outer loop + vertex -394.203 192.139 406.866 + vertex -393.873 192.474 407.388 + vertex -394.353 193.026 406.991 + endloop + endfacet + facet normal -0.757989 -0.218048 0.614742 + outer loop + vertex -394.353 193.026 406.991 + vertex -393.873 192.474 407.388 + vertex -394.039 193.255 407.461 + endloop + endfacet + facet normal -0.789248 -0.238269 0.565964 + outer loop + vertex -394.459 187.131 404.361 + vertex -393.982 188.655 405.668 + vertex -394.561 187.31 404.294 + endloop + endfacet + facet normal -0.722045 -0.317128 0.614883 + outer loop + vertex -394.561 187.31 404.294 + vertex -393.982 188.655 405.668 + vertex -394.042 188.897 405.722 + endloop + endfacet + facet normal -0.768752 -0.270168 0.579681 + outer loop + vertex -394.561 187.31 404.294 + vertex -394.042 188.897 405.722 + vertex -394.508 188.622 404.976 + endloop + endfacet + facet normal -0.757711 -0.295208 0.582001 + outer loop + vertex -394.508 188.622 404.976 + vertex -394.042 188.897 405.722 + vertex -394.099 189.27 405.836 + endloop + endfacet + facet normal 0.602195 0.398361 -0.69186 + outer loop + vertex -394.195 188.188 405.198 + vertex -393.895 188.969 405.911 + vertex -394.459 187.131 404.361 + endloop + endfacet + facet normal 0.92368 0.0378086 -0.381294 + outer loop + vertex -394.459 187.131 404.361 + vertex -393.895 188.969 405.911 + vertex -393.982 188.655 405.668 + endloop + endfacet + facet normal -0.649269 -0.123593 0.75045 + outer loop + vertex -393.927 200.881 409.152 + vertex -393.712 201.878 409.502 + vertex -393.86 203.216 409.594 + endloop + endfacet + facet normal -0.876381 -0.128963 0.464032 + outer loop + vertex -393.86 203.216 409.594 + vertex -393.712 201.878 409.502 + vertex -393.785 204.203 410.01 + endloop + endfacet + facet normal -0.826918 -0.0742597 0.557398 + outer loop + vertex -394.16 203.622 409.202 + vertex -394.158 202.384 409.041 + vertex -393.86 203.216 409.594 + endloop + endfacet + facet normal -0.758241 -0.0687832 0.648336 + outer loop + vertex -394.271 201.318 408.795 + vertex -393.927 200.881 409.152 + vertex -394.158 202.384 409.041 + endloop + endfacet + facet normal -0.818876 -0.084055 0.567782 + outer loop + vertex -393.927 200.881 409.152 + vertex -393.86 203.216 409.594 + vertex -394.158 202.384 409.041 + endloop + endfacet + facet normal -0.721518 -0.451551 0.524894 + outer loop + vertex -394.209 205.868 410.527 + vertex -394.163 204.78 409.653 + vertex -394.178 205.856 410.559 + endloop + endfacet + facet normal -0.863022 -0.185331 0.469942 + outer loop + vertex -394.16 203.622 409.202 + vertex -393.86 203.216 409.594 + vertex -394.163 204.78 409.653 + endloop + endfacet + facet normal -0.95711 -0.194024 0.215162 + outer loop + vertex -393.86 203.216 409.594 + vertex -394.178 205.856 410.559 + vertex -394.163 204.78 409.653 + endloop + endfacet + facet normal -0.254658 -0.358822 0.897996 + outer loop + vertex -393.86 203.216 409.594 + vertex -393.785 204.203 410.01 + vertex -394.178 205.856 410.559 + endloop + endfacet + facet normal -0.734176 -0.36481 0.572625 + outer loop + vertex -394.178 205.856 410.559 + vertex -393.785 204.203 410.01 + vertex -394.147 205.844 410.591 + endloop + endfacet + facet normal -0.694021 -0.130384 0.70805 + outer loop + vertex -393.977 196.564 408.411 + vertex -393.801 197.407 408.74 + vertex -393.992 198.663 408.783 + endloop + endfacet + facet normal -0.643798 -0.124369 0.755021 + outer loop + vertex -393.992 198.663 408.783 + vertex -393.801 197.407 408.74 + vertex -393.774 199.564 409.118 + endloop + endfacet + facet normal -0.755053 -0.102599 0.647586 + outer loop + vertex -394.337 199.102 408.451 + vertex -394.285 197.941 408.327 + vertex -393.992 198.663 408.783 + endloop + endfacet + facet normal -0.740554 -0.125242 0.660223 + outer loop + vertex -394.316 196.926 408.1 + vertex -393.977 196.564 408.411 + vertex -394.285 197.941 408.327 + endloop + endfacet + facet normal -0.73447 -0.123446 0.667319 + outer loop + vertex -393.977 196.564 408.411 + vertex -393.992 198.663 408.783 + vertex -394.285 197.941 408.327 + endloop + endfacet + facet normal -0.760303 -0.0727386 0.645484 + outer loop + vertex -394.271 201.318 408.795 + vertex -394.262 200.138 408.674 + vertex -393.927 200.881 409.152 + endloop + endfacet + facet normal -0.746937 -0.0875188 0.65911 + outer loop + vertex -394.337 199.102 408.451 + vertex -393.992 198.663 408.783 + vertex -394.262 200.138 408.674 + endloop + endfacet + facet normal -0.746937 -0.0875189 0.659109 + outer loop + vertex -393.992 198.663 408.783 + vertex -393.927 200.881 409.152 + vertex -394.262 200.138 408.674 + endloop + endfacet + facet normal -0.690792 -0.0986488 0.716292 + outer loop + vertex -393.992 198.663 408.783 + vertex -393.774 199.564 409.118 + vertex -393.927 200.881 409.152 + endloop + endfacet + facet normal -0.696879 -0.099201 0.710295 + outer loop + vertex -393.927 200.881 409.152 + vertex -393.774 199.564 409.118 + vertex -393.712 201.878 409.502 + endloop + endfacet + facet normal -0.66069 -0.203234 0.722624 + outer loop + vertex -393.712 193.04 407.747 + vertex -393.616 193.636 408.003 + vertex -393.876 194.661 408.053 + endloop + endfacet + facet normal -0.631406 -0.197127 0.749978 + outer loop + vertex -393.876 194.661 408.053 + vertex -393.616 193.636 408.003 + vertex -393.744 195.418 408.363 + endloop + endfacet + facet normal -0.73502 -0.18107 0.653421 + outer loop + vertex -394.21 194.945 407.757 + vertex -394.081 194.033 407.648 + vertex -393.876 194.661 408.053 + endloop + endfacet + facet normal -0.717669 -0.200384 0.666931 + outer loop + vertex -394.039 193.255 407.461 + vertex -393.712 193.04 407.747 + vertex -394.081 194.033 407.648 + endloop + endfacet + facet normal -0.714597 -0.19887 0.670673 + outer loop + vertex -393.712 193.04 407.747 + vertex -393.876 194.661 408.053 + vertex -394.081 194.033 407.648 + endloop + endfacet + facet normal -0.748843 -0.144529 0.646796 + outer loop + vertex -394.316 196.926 408.1 + vertex -394.223 195.856 407.969 + vertex -393.977 196.564 408.411 + endloop + endfacet + facet normal -0.730001 -0.164914 0.663251 + outer loop + vertex -394.21 194.945 407.757 + vertex -393.876 194.661 408.053 + vertex -394.223 195.856 407.969 + endloop + endfacet + facet normal -0.72756 -0.164002 0.666153 + outer loop + vertex -393.876 194.661 408.053 + vertex -393.977 196.564 408.411 + vertex -394.223 195.856 407.969 + endloop + endfacet + facet normal -0.687538 -0.169398 0.706113 + outer loop + vertex -393.876 194.661 408.053 + vertex -393.744 195.418 408.363 + vertex -393.977 196.564 408.411 + endloop + endfacet + facet normal -0.635655 -0.160901 0.755019 + outer loop + vertex -393.977 196.564 408.411 + vertex -393.744 195.418 408.363 + vertex -393.801 197.407 408.74 + endloop + endfacet + facet normal -0.693121 -0.251774 0.675421 + outer loop + vertex -393.42 190.825 407.276 + vertex -393.353 191.138 407.462 + vertex -393.521 191.753 407.519 + endloop + endfacet + facet normal -0.618435 -0.238283 0.748839 + outer loop + vertex -393.521 191.753 407.519 + vertex -393.353 191.138 407.462 + vertex -393.453 192.083 407.68 + endloop + endfacet + facet normal -0.712723 -0.242337 0.658254 + outer loop + vertex -393.78 191.776 407.247 + vertex -393.618 191.146 407.189 + vertex -393.521 191.753 407.519 + endloop + endfacet + facet normal -0.708697 -0.261014 0.655455 + outer loop + vertex -393.586 190.482 406.96 + vertex -393.42 190.825 407.276 + vertex -393.618 191.146 407.189 + endloop + endfacet + facet normal -0.698707 -0.250944 0.669952 + outer loop + vertex -393.42 190.825 407.276 + vertex -393.521 191.753 407.519 + vertex -393.618 191.146 407.189 + endloop + endfacet + facet normal -0.720389 -0.214199 0.659665 + outer loop + vertex -394.039 193.255 407.461 + vertex -393.873 192.474 407.388 + vertex -393.712 193.04 407.747 + endloop + endfacet + facet normal -0.714509 -0.228972 0.661096 + outer loop + vertex -393.78 191.776 407.247 + vertex -393.521 191.753 407.519 + vertex -393.873 192.474 407.388 + endloop + endfacet + facet normal -0.707894 -0.224163 0.669804 + outer loop + vertex -393.521 191.753 407.519 + vertex -393.712 193.04 407.747 + vertex -393.873 192.474 407.388 + endloop + endfacet + facet normal -0.642211 -0.225496 0.732609 + outer loop + vertex -393.521 191.753 407.519 + vertex -393.453 192.083 407.68 + vertex -393.712 193.04 407.747 + endloop + endfacet + facet normal -0.622588 -0.221444 0.750564 + outer loop + vertex -393.712 193.04 407.747 + vertex -393.453 192.083 407.68 + vertex -393.616 193.636 408.003 + endloop + endfacet + facet normal -0.662422 -0.308506 0.682658 + outer loop + vertex -393.586 190.482 406.96 + vertex -393.612 189.867 406.657 + vertex -393.42 190.825 407.276 + endloop + endfacet + facet normal -0.617453 -0.299006 0.727562 + outer loop + vertex -393.353 191.138 407.462 + vertex -393.42 190.825 407.276 + vertex -393.392 190.464 407.152 + endloop + endfacet + facet normal -0.614625 -0.356453 0.703688 + outer loop + vertex -393.592 189.75 406.615 + vertex -393.392 190.464 407.152 + vertex -393.612 189.867 406.657 + endloop + endfacet + facet normal -0.705479 -0.279625 0.651237 + outer loop + vertex -393.42 190.825 407.276 + vertex -393.612 189.867 406.657 + vertex -393.392 190.464 407.152 + endloop + endfacet + facet normal -0.604613 -0.37184 0.704399 + outer loop + vertex -393.876 188.997 405.941 + vertex -393.313 190.556 407.248 + vertex -393.895 188.969 405.911 + endloop + endfacet + facet normal -0.602047 -0.397613 0.692419 + outer loop + vertex -394.473 187.11 404.338 + vertex -393.876 188.997 405.941 + vertex -394.195 188.188 405.198 + endloop + endfacet + facet normal 0.485573 0.463816 -0.741009 + outer loop + vertex -394.877 185.344 402.968 + vertex -394.473 187.11 404.338 + vertex -394.459 187.131 404.361 + endloop + endfacet + facet normal -0.841196 -0.215485 0.49594 + outer loop + vertex -395.193 183.239 401.517 + vertex -394.877 185.344 402.968 + vertex -395.21 184.198 401.906 + endloop + endfacet + facet normal -0.850498 -0.210086 0.482201 + outer loop + vertex -395.465 181.239 400.166 + vertex -395.193 183.239 401.517 + vertex -395.21 184.198 401.906 + endloop + endfacet + facet normal -0.841616 -0.223351 0.491729 + outer loop + vertex -395.727 178.331 398.396 + vertex -395.465 181.239 400.166 + vertex -395.76 180.18 399.18 + endloop + endfacet + facet normal -0.817152 -0.241311 0.52348 + outer loop + vertex -395.91 176.127 397.095 + vertex -395.727 178.331 398.396 + vertex -396.062 176.501 397.03 + endloop + endfacet + facet normal -0.808742 -0.235135 0.539118 + outer loop + vertex -396.109 174.021 395.878 + vertex -395.91 176.127 397.095 + vertex -396.062 176.501 397.03 + endloop + endfacet + facet normal -0.810928 -0.229236 0.538373 + outer loop + vertex -396.284 172.14 394.813 + vertex -396.109 174.021 395.878 + vertex -396.42 172.94 394.95 + endloop + endfacet + facet normal -0.787156 -0.230945 0.571882 + outer loop + vertex -396.452 170.779 394.032 + vertex -396.284 172.14 394.813 + vertex -396.42 172.94 394.95 + endloop + endfacet + facet normal -0.79913 -0.214895 0.561437 + outer loop + vertex -396.654 168.746 392.967 + vertex -396.452 170.779 394.032 + vertex -396.827 169.422 392.98 + endloop + endfacet + facet normal -0.790278 -0.212898 0.574574 + outer loop + vertex -396.906 166.985 391.968 + vertex -396.654 168.746 392.967 + vertex -396.827 169.422 392.98 + endloop + endfacet + facet normal -0.772057 -0.220279 0.596158 + outer loop + vertex -397.085 165.476 391.179 + vertex -396.906 166.985 391.968 + vertex -397.311 165.819 391.012 + endloop + endfacet + facet normal -0.76508 -0.20948 0.608909 + outer loop + vertex -397.407 163.466 390.083 + vertex -397.085 165.476 391.179 + vertex -397.311 165.819 391.012 + endloop + endfacet + facet normal -0.762216 -0.208971 0.612665 + outer loop + vertex -397.712 161.47 389.023 + vertex -397.407 163.466 390.083 + vertex -397.927 162.083 388.964 + endloop + endfacet + facet normal -0.747568 -0.201881 0.632761 + outer loop + vertex -398.006 159.979 388.199 + vertex -397.712 161.47 389.023 + vertex -397.927 162.083 388.964 + endloop + endfacet + facet normal -0.738252 -0.1988 0.644564 + outer loop + vertex -398.357 157.937 387.167 + vertex -398.006 159.979 388.199 + vertex -398.612 158.169 386.947 + endloop + endfacet + facet normal -0.735224 -0.189577 0.650774 + outer loop + vertex -398.843 155.793 385.994 + vertex -398.357 157.937 387.167 + vertex -398.612 158.169 386.947 + endloop + endfacet + facet normal -0.711262 -0.191711 0.676279 + outer loop + vertex -399.334 153.501 384.827 + vertex -398.843 155.793 385.994 + vertex -399.449 154.222 384.911 + endloop + endfacet + facet normal -0.694997 -0.191098 0.693153 + outer loop + vertex -399.814 151.751 383.864 + vertex -399.334 153.501 384.827 + vertex -399.449 154.222 384.911 + endloop + endfacet + facet normal -0.670688 -0.195391 0.715542 + outer loop + vertex -400.207 150.236 383.082 + vertex -399.814 151.751 383.864 + vertex -400.46 150.609 382.947 + endloop + endfacet + facet normal -0.658768 -0.182091 0.729978 + outer loop + vertex -400.825 148.282 382.037 + vertex -400.207 150.236 383.082 + vertex -400.46 150.609 382.947 + endloop + endfacet + facet normal -0.653614 -0.177722 0.735666 + outer loop + vertex -401.495 146.172 380.932 + vertex -400.825 148.282 382.037 + vertex -401.727 146.79 380.875 + endloop + endfacet + facet normal -0.63235 -0.167811 0.756289 + outer loop + vertex -402.259 144.03 379.818 + vertex -401.495 146.172 380.932 + vertex -401.727 146.79 380.875 + endloop + endfacet + facet normal -0.626627 -0.165273 0.761592 + outer loop + vertex -402.948 142.061 378.823 + vertex -402.259 144.03 379.818 + vertex -403.075 142.883 378.898 + endloop + endfacet + facet normal -0.597232 -0.16288 0.785356 + outer loop + vertex -403.537 140.707 378.095 + vertex -402.948 142.061 378.823 + vertex -403.075 142.883 378.898 + endloop + endfacet + facet normal -0.589786 -0.146447 0.79417 + outer loop + vertex -404.361 138.829 377.136 + vertex -403.537 140.707 378.095 + vertex -404.545 139.398 377.105 + endloop + endfacet + facet normal -0.575748 -0.141287 0.805327 + outer loop + vertex -405.352 137.019 376.11 + vertex -404.361 138.829 377.136 + vertex -404.545 139.398 377.105 + endloop + endfacet + facet normal -0.53576 -0.137782 0.833053 + outer loop + vertex -406.497 135 375.04 + vertex -405.352 137.019 376.11 + vertex -406.51 136.104 375.214 + endloop + endfacet + facet normal -0.508999 -0.140031 0.8493 + outer loop + vertex -407.551 133.587 374.176 + vertex -406.497 135 375.04 + vertex -406.51 136.104 375.214 + endloop + endfacet + facet normal -0.456326 -0.156994 0.875853 + outer loop + vertex -408.487 132.274 373.452 + vertex -407.551 133.587 374.176 + vertex -408.9 133.016 373.37 + endloop + endfacet + facet normal -0.427246 -0.138877 0.893406 + outer loop + vertex -409.914 130.744 372.532 + vertex -408.487 132.274 373.452 + vertex -408.9 133.016 373.37 + endloop + endfacet + facet normal -0.420411 -0.135782 0.897116 + outer loop + vertex -411.405 129.137 371.59 + vertex -409.914 130.744 372.532 + vertex -411.597 129.982 371.628 + endloop + endfacet + facet normal -0.392793 -0.1301 0.910378 + outer loop + vertex -412.735 127.907 370.84 + vertex -411.405 129.137 371.59 + vertex -411.597 129.982 371.628 + endloop + endfacet + facet normal -0.624333 0.1874 -0.758346 + outer loop + vertex -393.785 203.497 409.836 + vertex -394.084 205.819 410.656 + vertex -393.785 204.203 410.01 + endloop + endfacet + facet normal 0.0100669 0.202367 -0.979258 + outer loop + vertex -393.762 201.01 409.322 + vertex -393.785 203.497 409.836 + vertex -393.712 201.878 409.502 + endloop + endfacet + facet normal 0.998769 -0.00114462 -0.049593 + outer loop + vertex -393.784 198.67 408.939 + vertex -393.762 201.01 409.322 + vertex -393.774 199.564 409.118 + endloop + endfacet + facet normal 0.683973 -0.12222 0.719196 + outer loop + vertex -393.768 196.566 408.566 + vertex -393.784 198.67 408.939 + vertex -393.801 197.407 408.74 + endloop + endfacet + facet normal 0.609061 -0.125716 0.783096 + outer loop + vertex -393.679 194.648 408.189 + vertex -393.768 196.566 408.566 + vertex -393.744 195.418 408.363 + endloop + endfacet + facet normal 0.837349 -0.047427 0.544608 + outer loop + vertex -393.52 192.733 407.777 + vertex -393.679 194.648 408.189 + vertex -393.616 193.636 408.003 + endloop + endfacet + facet normal 0.990641 0.112828 -0.0768063 + outer loop + vertex -393.313 190.556 407.248 + vertex -393.52 192.733 407.777 + vertex -393.453 192.083 407.68 + endloop + endfacet + facet normal -0.732551 -0.365118 0.574507 + outer loop + vertex -394.084 205.819 410.656 + vertex -394.147 205.844 410.591 + vertex -393.785 204.203 410.01 + endloop + endfacet + facet normal -0.388762 -0.13282 0.911714 + outer loop + vertex -411.597 129.982 371.628 + vertex -413.482 127.899 370.521 + vertex -412.735 127.907 370.84 + endloop + endfacet + facet normal -0.458727 -0.0866996 0.884338 + outer loop + vertex -410.35 139.407 373.272 + vertex -412.843 137.261 371.768 + vertex -411.328 133.769 372.212 + endloop + endfacet + facet normal -0.416341 -0.145262 0.897529 + outer loop + vertex -408.9 133.016 373.37 + vertex -411.597 129.982 371.628 + vertex -409.914 130.744 372.532 + endloop + endfacet + facet normal -0.494322 -0.0770461 0.865858 + outer loop + vertex -411.328 133.769 372.212 + vertex -408.211 136.924 374.272 + vertex -410.35 139.407 373.272 + endloop + endfacet + facet normal -0.511972 -0.0972371 0.853481 + outer loop + vertex -407.766 142.283 375.15 + vertex -410.35 139.407 373.272 + vertex -408.211 136.924 374.272 + endloop + endfacet + facet normal -0.448445 -0.176194 0.876272 + outer loop + vertex -406.51 136.104 375.214 + vertex -408.9 133.016 373.37 + vertex -407.551 133.587 374.176 + endloop + endfacet + facet normal -0.563351 -0.0877413 0.821546 + outer loop + vertex -408.211 136.924 374.272 + vertex -405.882 139.914 376.188 + vertex -407.766 142.283 375.15 + endloop + endfacet + facet normal -0.581043 -0.108356 0.806627 + outer loop + vertex -405.4 145.556 377.293 + vertex -407.766 142.283 375.15 + vertex -405.882 139.914 376.188 + endloop + endfacet + facet normal -0.509932 -0.178714 0.841446 + outer loop + vertex -404.545 139.398 377.105 + vertex -406.51 136.104 375.214 + vertex -405.352 137.019 376.11 + endloop + endfacet + facet normal -0.624576 -0.0983978 0.774741 + outer loop + vertex -405.882 139.914 376.188 + vertex -404.234 142.387 377.831 + vertex -405.4 145.556 377.293 + endloop + endfacet + facet normal -0.673139 -0.084341 0.734691 + outer loop + vertex -404.266 150.08 378.852 + vertex -405.4 145.556 377.293 + vertex -403.173 146.742 379.47 + endloop + endfacet + facet normal -0.561303 -0.178876 0.808048 + outer loop + vertex -403.075 142.883 378.898 + vertex -404.545 139.398 377.105 + vertex -403.537 140.707 378.095 + endloop + endfacet + facet normal -0.661342 -0.117695 0.740793 + outer loop + vertex -404.234 142.387 377.831 + vertex -403.173 146.742 379.47 + vertex -405.4 145.556 377.293 + endloop + endfacet + facet normal -0.704931 -0.100785 0.702078 + outer loop + vertex -402.944 152.479 380.524 + vertex -404.266 150.08 378.852 + vertex -403.173 146.742 379.47 + endloop + endfacet + facet normal -0.619104 -0.174 0.76579 + outer loop + vertex -401.727 146.79 380.875 + vertex -403.075 142.883 378.898 + vertex -402.259 144.03 379.818 + endloop + endfacet + facet normal -0.734241 -0.0941458 0.672329 + outer loop + vertex -403.173 146.742 379.47 + vertex -401.599 150.614 381.731 + vertex -402.944 152.479 380.524 + endloop + endfacet + facet normal -0.742543 -0.10738 0.661134 + outer loop + vertex -401.634 155.886 382.548 + vertex -402.944 152.479 380.524 + vertex -401.599 150.614 381.731 + endloop + endfacet + facet normal -0.642794 -0.189399 0.742256 + outer loop + vertex -400.46 150.609 382.947 + vertex -401.727 146.79 380.875 + vertex -400.825 148.282 382.037 + endloop + endfacet + facet normal -0.770607 -0.102585 0.629001 + outer loop + vertex -401.599 150.614 381.731 + vertex -400.381 154.208 383.81 + vertex -401.634 155.886 382.548 + endloop + endfacet + facet normal -0.778298 -0.11751 0.616801 + outer loop + vertex -400.36 159.755 384.893 + vertex -401.634 155.886 382.548 + vertex -400.381 154.208 383.81 + endloop + endfacet + facet normal -0.657277 -0.20969 0.72389 + outer loop + vertex -399.449 154.222 384.911 + vertex -400.46 150.609 382.947 + vertex -399.814 151.751 383.864 + endloop + endfacet + facet normal -0.797568 -0.112714 0.592605 + outer loop + vertex -400.381 154.208 383.81 + vertex -399.448 157.133 385.621 + vertex -400.36 159.755 384.893 + endloop + endfacet + facet normal -0.829999 -0.102098 0.54834 + outer loop + vertex -399.832 164.431 386.562 + vertex -400.36 159.755 384.893 + vertex -398.966 161.583 387.344 + endloop + endfacet + facet normal -0.690735 -0.210357 0.691835 + outer loop + vertex -398.612 158.169 386.947 + vertex -399.449 154.222 384.911 + vertex -398.843 155.793 385.994 + endloop + endfacet + facet normal -0.817749 -0.128483 0.561051 + outer loop + vertex -399.448 157.133 385.621 + vertex -398.966 161.583 387.344 + vertex -400.36 159.755 384.893 + endloop + endfacet + facet normal -0.846125 -0.114641 0.52051 + outer loop + vertex -399.08 167.04 388.359 + vertex -399.832 164.431 386.562 + vertex -398.966 161.583 387.344 + endloop + endfacet + facet normal -0.724761 -0.211127 0.655856 + outer loop + vertex -397.927 162.083 388.964 + vertex -398.612 158.169 386.947 + vertex -398.006 159.979 388.199 + endloop + endfacet + facet normal -0.859628 -0.110873 0.498745 + outer loop + vertex -398.966 161.583 387.344 + vertex -398.117 165.603 389.7 + vertex -399.08 167.04 388.359 + endloop + endfacet + facet normal -0.862617 -0.119621 0.491511 + outer loop + vertex -398.406 170.476 390.379 + vertex -399.08 167.04 388.359 + vertex -398.117 165.603 389.7 + endloop + endfacet + facet normal -0.759181 -0.212246 0.615301 + outer loop + vertex -397.311 165.819 391.012 + vertex -397.927 162.083 388.964 + vertex -397.407 163.466 390.083 + endloop + endfacet + facet normal -0.87977 -0.116375 0.460936 + outer loop + vertex -398.117 165.603 389.7 + vertex -397.519 169.258 391.765 + vertex -398.406 170.476 390.379 + endloop + endfacet + facet normal -0.881429 -0.123256 0.455951 + outer loop + vertex -397.852 173.975 392.396 + vertex -398.406 170.476 390.379 + vertex -397.519 169.258 391.765 + endloop + endfacet + facet normal -0.768817 -0.223765 0.59904 + outer loop + vertex -396.827 169.422 392.98 + vertex -397.311 165.819 391.012 + vertex -396.906 166.985 391.968 + endloop + endfacet + facet normal -0.896554 -0.120349 0.426271 + outer loop + vertex -397.519 169.258 391.765 + vertex -397.037 172.817 393.783 + vertex -397.852 173.975 392.396 + endloop + endfacet + facet normal -0.898283 -0.129002 0.420054 + outer loop + vertex -397.369 177.531 394.521 + vertex -397.852 173.975 392.396 + vertex -397.037 172.817 393.783 + endloop + endfacet + facet normal -0.780177 -0.234477 0.579953 + outer loop + vertex -396.42 172.94 394.95 + vertex -396.827 169.422 392.98 + vertex -396.452 170.779 394.032 + endloop + endfacet + facet normal -0.909498 -0.126047 0.396138 + outer loop + vertex -397.037 172.817 393.783 + vertex -396.613 176.318 395.87 + vertex -397.369 177.531 394.521 + endloop + endfacet + facet normal -0.911836 -0.138079 0.386638 + outer loop + vertex -396.864 181.501 397.13 + vertex -397.369 177.531 394.521 + vertex -396.613 176.318 395.87 + endloop + endfacet + facet normal -0.802587 -0.238758 0.54667 + outer loop + vertex -396.062 176.501 397.03 + vertex -396.42 172.94 394.95 + vertex -396.109 174.021 395.878 + endloop + endfacet + facet normal -0.913256 -0.137391 0.38352 + outer loop + vertex -396.613 176.318 395.87 + vertex -396.223 179.117 397.802 + vertex -396.864 181.501 397.13 + endloop + endfacet + facet normal -0.917921 -0.148504 0.367923 + outer loop + vertex -396.702 186.471 399.539 + vertex -396.864 181.501 397.13 + vertex -396.021 183.264 399.943 + endloop + endfacet + facet normal -0.825935 -0.232363 0.513652 + outer loop + vertex -395.76 180.18 399.18 + vertex -396.062 176.501 397.03 + vertex -395.727 178.331 398.396 + endloop + endfacet + facet normal -0.919525 -0.144118 0.365656 + outer loop + vertex -396.223 179.117 397.802 + vertex -396.021 183.264 399.943 + vertex -396.864 181.501 397.13 + endloop + endfacet + facet normal -0.928412 -0.15451 0.337902 + outer loop + vertex -396.107 186.99 401.413 + vertex -396.702 186.471 399.539 + vertex -396.021 183.264 399.943 + endloop + endfacet + facet normal -0.85337 -0.207503 0.478228 + outer loop + vertex -395.21 184.198 401.906 + vertex -395.76 180.18 399.18 + vertex -395.465 181.239 400.166 + endloop + endfacet + facet normal -0.873639 -0.195698 0.445485 + outer loop + vertex -396.021 183.264 399.943 + vertex -395.318 186.955 402.943 + vertex -396.107 186.99 401.413 + endloop + endfacet + facet normal -0.83351 -0.272371 0.480703 + outer loop + vertex -395.487 190.822 404.478 + vertex -395.819 189.749 403.294 + vertex -394.95 189.937 404.908 + endloop + endfacet + facet normal -0.870806 -0.211802 0.443662 + outer loop + vertex -395.819 189.749 403.294 + vertex -396.107 186.99 401.413 + vertex -395.318 186.955 402.943 + endloop + endfacet + facet normal -0.931932 -0.0607283 0.357513 + outer loop + vertex -394.459 187.131 404.361 + vertex -395.21 184.198 401.906 + vertex -394.877 185.344 402.968 + endloop + endfacet + facet normal -0.813729 -0.246309 0.526476 + outer loop + vertex -395.318 186.955 402.943 + vertex -394.508 188.622 404.976 + vertex -394.95 189.937 404.908 + endloop + endfacet + facet normal -0.702172 -0.290764 0.649931 + outer loop + vertex -393.586 190.482 406.96 + vertex -393.834 189.835 406.402 + vertex -393.612 189.867 406.657 + endloop + endfacet + facet normal -0.709534 -0.304168 0.635644 + outer loop + vertex -393.834 189.835 406.402 + vertex -394.099 189.27 405.836 + vertex -394.042 188.897 405.722 + endloop + endfacet + facet normal -0.692757 -0.317271 0.647632 + outer loop + vertex -394.042 188.897 405.722 + vertex -393.982 188.655 405.668 + vertex -393.612 189.867 406.657 + endloop + endfacet + facet normal -0.494132 -0.473742 0.728973 + outer loop + vertex -393.895 188.969 405.911 + vertex -394.195 188.188 405.198 + vertex -393.876 188.997 405.941 + endloop + endfacet + facet normal 0.479487 0.468674 -0.741915 + outer loop + vertex -394.195 188.188 405.198 + vertex -394.459 187.131 404.361 + vertex -394.473 187.11 404.338 + endloop + endfacet + facet normal 0.736555 0.273265 -0.618718 + outer loop + vertex -393.982 188.655 405.668 + vertex -393.895 188.969 405.911 + vertex -393.592 189.75 406.615 + endloop + endfacet + facet normal 0.653957 0.181082 -0.73454 + outer loop + vertex -393.785 204.203 410.01 + vertex -393.712 201.878 409.502 + vertex -393.785 203.497 409.836 + endloop + endfacet + facet normal 0.99864 -0.020663 0.0478598 + outer loop + vertex -393.774 199.564 409.118 + vertex -393.801 197.407 408.74 + vertex -393.784 198.67 408.939 + endloop + endfacet + facet normal 0.794075 0.0787153 -0.602701 + outer loop + vertex -393.712 201.878 409.502 + vertex -393.774 199.564 409.118 + vertex -393.762 201.01 409.322 + endloop + endfacet + facet normal 0.888853 -0.0281935 0.457324 + outer loop + vertex -393.744 195.418 408.363 + vertex -393.616 193.636 408.003 + vertex -393.679 194.648 408.189 + endloop + endfacet + facet normal 0.85862 -0.0718146 0.507558 + outer loop + vertex -393.801 197.407 408.74 + vertex -393.744 195.418 408.363 + vertex -393.768 196.566 408.566 + endloop + endfacet + facet normal 0.953884 0.159665 -0.254191 + outer loop + vertex -393.453 192.083 407.68 + vertex -393.353 191.138 407.462 + vertex -393.313 190.556 407.248 + endloop + endfacet + facet normal 0.994603 0.0958272 0.0397797 + outer loop + vertex -393.616 193.636 408.003 + vertex -393.453 192.083 407.68 + vertex -393.52 192.733 407.777 + endloop + endfacet + facet normal -0.554975 -0.320979 0.767448 + outer loop + vertex -393.353 191.138 407.462 + vertex -393.392 190.464 407.152 + vertex -393.313 190.556 407.248 + endloop + endfacet + facet normal -0.389805 -0.480891 0.785364 + outer loop + vertex -393.392 190.464 407.152 + vertex -393.592 189.75 406.615 + vertex -393.313 190.556 407.248 + endloop + endfacet + facet normal -0.650338 -0.351367 0.6735 + outer loop + vertex -393.592 189.75 406.615 + vertex -393.612 189.867 406.657 + vertex -393.982 188.655 405.668 + endloop + endfacet + facet normal 0.943025 -0.0720598 -0.324824 + outer loop + vertex -393.895 188.969 405.911 + vertex -393.313 190.556 407.248 + vertex -393.592 189.75 406.615 + endloop + endfacet + facet normal -0.849654 -0.212876 0.482465 + outer loop + vertex -394.95 189.937 404.908 + vertex -395.819 189.749 403.294 + vertex -395.318 186.955 402.943 + endloop + endfacet + facet normal -0.694701 -0.315319 0.646501 + outer loop + vertex -393.612 189.867 406.657 + vertex -393.834 189.835 406.402 + vertex -394.042 188.897 405.722 + endloop + endfacet + facet normal -0.966009 0.175055 -0.190216 + outer loop + vertex -877.294 475.934 312.412 + vertex -877.749 477.695 316.343 + vertex -875.88 484.06 312.71 + endloop + endfacet + facet normal -0.964663 0.166822 -0.203949 + outer loop + vertex -875.88 484.06 312.71 + vertex -877.749 477.695 316.343 + vertex -876.328 486.308 316.669 + endloop + endfacet + facet normal -0.91978 0.321317 -0.225301 + outer loop + vertex -879.767 467.293 311.532 + vertex -880.189 468.706 315.268 + vertex -878.845 470.351 312.128 + endloop + endfacet + facet normal -0.919893 0.320747 -0.225648 + outer loop + vertex -878.845 470.351 312.128 + vertex -880.189 468.706 315.268 + vertex -879.308 471.771 316.033 + endloop + endfacet + facet normal -0.977554 0.166135 -0.129564 + outer loop + vertex -877.749 477.695 316.343 + vertex -878.061 479.078 320.469 + vertex -876.328 486.308 316.669 + endloop + endfacet + facet normal -0.977385 0.164074 -0.133408 + outer loop + vertex -876.328 486.308 316.669 + vertex -878.061 479.078 320.469 + vertex -876.615 488.002 320.853 + endloop + endfacet + facet normal -0.938809 0.308235 -0.153719 + outer loop + vertex -880.189 468.706 315.268 + vertex -880.531 469.755 319.459 + vertex -879.308 471.771 316.033 + endloop + endfacet + facet normal -0.939333 0.305823 -0.155325 + outer loop + vertex -879.308 471.771 316.033 + vertex -880.531 469.755 319.459 + vertex -879.606 472.952 320.16 + endloop + endfacet + facet normal -0.983195 0.162829 -0.082554 + outer loop + vertex -878.061 479.078 320.469 + vertex -878.261 480.064 324.795 + vertex -876.615 488.002 320.853 + endloop + endfacet + facet normal -0.983188 0.161743 -0.0847394 + outer loop + vertex -876.615 488.002 320.853 + vertex -878.261 480.064 324.795 + vertex -876.812 489.078 325.191 + endloop + endfacet + facet normal -0.951453 0.294724 -0.088737 + outer loop + vertex -880.531 469.755 319.459 + vertex -880.725 470.455 323.873 + vertex -879.606 472.952 320.16 + endloop + endfacet + facet normal -0.953337 0.286665 -0.094723 + outer loop + vertex -879.606 472.952 320.16 + vertex -880.725 470.455 323.873 + vertex -879.796 473.743 324.469 + endloop + endfacet + facet normal -0.985907 0.160528 -0.0470914 + outer loop + vertex -878.261 480.064 324.795 + vertex -878.382 480.635 329.289 + vertex -876.812 489.078 325.191 + endloop + endfacet + facet normal -0.986043 0.158151 -0.0520413 + outer loop + vertex -876.812 489.078 325.191 + vertex -878.382 480.635 329.289 + vertex -876.95 489.681 329.642 + endloop + endfacet + facet normal -0.959199 0.279213 -0.0444719 + outer loop + vertex -880.725 470.455 323.873 + vertex -880.844 470.749 328.277 + vertex -879.796 473.743 324.469 + endloop + endfacet + facet normal -0.961253 0.270784 -0.0516647 + outer loop + vertex -879.796 473.743 324.469 + vertex -880.844 470.749 328.277 + vertex -879.912 474.18 328.928 + endloop + endfacet + facet normal -0.987409 0.15707 -0.0187795 + outer loop + vertex -878.382 480.635 329.289 + vertex -878.43 480.89 333.92 + vertex -876.95 489.681 329.642 + endloop + endfacet + facet normal -0.98767 0.154759 -0.0236184 + outer loop + vertex -876.95 489.681 329.642 + vertex -878.43 480.89 333.92 + vertex -877.034 489.872 334.414 + endloop + endfacet + facet normal -0.963987 0.265285 -0.018761 + outer loop + vertex -880.844 470.749 328.277 + vertex -880.887 470.91 332.754 + vertex -879.912 474.18 328.928 + endloop + endfacet + facet normal -0.964594 0.262907 -0.0209479 + outer loop + vertex -879.912 474.18 328.928 + vertex -880.887 470.91 332.754 + vertex -879.96 474.37 333.509 + endloop + endfacet + facet normal -0.988179 0.153072 0.00849259 + outer loop + vertex -878.43 480.89 333.92 + vertex -878.407 480.778 338.598 + vertex -877.034 489.872 334.414 + endloop + endfacet + facet normal -0.988474 0.151318 0.0045837 + outer loop + vertex -877.034 489.872 334.414 + vertex -878.407 480.778 338.598 + vertex -877.05 489.637 338.863 + endloop + endfacet + facet normal -0.966029 0.258431 0.00132733 + outer loop + vertex -880.887 470.91 332.754 + vertex -880.883 470.901 337.341 + vertex -879.96 474.37 333.509 + endloop + endfacet + facet normal -0.96482 0.26285 0.00561798 + outer loop + vertex -879.96 474.37 333.509 + vertex -880.883 470.901 337.341 + vertex -879.934 474.366 338.147 + endloop + endfacet + facet normal -0.987872 0.150184 0.0394166 + outer loop + vertex -878.407 480.778 338.598 + vertex -878.287 480.338 343.273 + vertex -877.05 489.637 338.863 + endloop + endfacet + facet normal -0.988426 0.147792 0.0342159 + outer loop + vertex -877.05 489.637 338.863 + vertex -878.287 480.338 343.273 + vertex -876.997 488.988 343.196 + endloop + endfacet + facet normal -0.965662 0.25861 0.0248506 + outer loop + vertex -880.883 470.901 337.341 + vertex -880.81 470.732 341.936 + vertex -879.934 474.366 338.147 + endloop + endfacet + facet normal -0.961868 0.270926 0.0375398 + outer loop + vertex -879.934 474.366 338.147 + vertex -880.81 470.732 341.936 + vertex -879.809 474.169 342.783 + endloop + endfacet + facet normal -0.986369 0.147823 0.0722883 + outer loop + vertex -878.287 480.338 343.273 + vertex -878.089 479.236 348.235 + vertex -876.997 488.988 343.196 + endloop + endfacet + facet normal -0.98682 0.146279 0.0692027 + outer loop + vertex -876.997 488.988 343.196 + vertex -878.089 479.236 348.235 + vertex -876.858 487.825 347.634 + endloop + endfacet + facet normal -0.96225 0.265009 0.0620109 + outer loop + vertex -880.81 470.732 341.936 + vertex -880.598 470.448 346.433 + vertex -879.809 474.169 342.783 + endloop + endfacet + facet normal -0.955624 0.283006 0.0817946 + outer loop + vertex -879.809 474.169 342.783 + vertex -880.598 470.448 346.433 + vertex -879.588 473.563 347.461 + endloop + endfacet + facet normal -0.961963 0.234172 0.140677 + outer loop + vertex -878.428 475.526 352.092 + vertex -877.35 480.524 351.14 + vertex -878.089 479.236 348.235 + endloop + endfacet + facet normal -0.987783 0.116399 0.103616 + outer loop + vertex -876.628 486.187 351.661 + vertex -876.858 487.825 347.634 + vertex -877.35 480.524 351.14 + endloop + endfacet + facet normal -0.971924 0.151872 0.179719 + outer loop + vertex -876.858 487.825 347.634 + vertex -878.089 479.236 348.235 + vertex -877.35 480.524 351.14 + endloop + endfacet + facet normal -0.955358 0.271331 0.116921 + outer loop + vertex -880.598 470.448 346.433 + vertex -880.231 469.789 350.968 + vertex -879.588 473.563 347.461 + endloop + endfacet + facet normal -0.948277 0.287179 0.135271 + outer loop + vertex -879.588 473.563 347.461 + vertex -880.231 469.789 350.968 + vertex -879.388 472.03 352.118 + endloop + endfacet + facet normal -0.949009 0.235073 0.210056 + outer loop + vertex -877.924 476.366 353.479 + vertex -877.796 475.28 355.275 + vertex -876.971 480.223 353.467 + endloop + endfacet + facet normal -0.936797 0.246877 0.247918 + outer loop + vertex -876.971 480.223 353.467 + vertex -877.796 475.28 355.275 + vertex -876.718 479.286 355.359 + endloop + endfacet + facet normal -0.949768 0.242446 0.197891 + outer loop + vertex -878.428 475.526 352.092 + vertex -877.924 476.366 353.479 + vertex -877.35 480.524 351.14 + endloop + endfacet + facet normal -0.953786 0.236183 0.18577 + outer loop + vertex -877.35 480.524 351.14 + vertex -877.924 476.366 353.479 + vertex -876.971 480.223 353.467 + endloop + endfacet + facet normal -0.978824 0.108838 0.173372 + outer loop + vertex -877.35 480.524 351.14 + vertex -876.971 480.223 353.467 + vertex -876.628 486.187 351.661 + endloop + endfacet + facet normal -0.985446 0.0986355 0.138444 + outer loop + vertex -876.628 486.187 351.661 + vertex -876.971 480.223 353.467 + vertex -876.459 485.068 353.663 + endloop + endfacet + facet normal -0.979128 0.0963289 0.178965 + outer loop + vertex -876.971 480.223 353.467 + vertex -876.718 479.286 355.359 + vertex -876.459 485.068 353.663 + endloop + endfacet + facet normal -0.979532 0.0957824 0.177041 + outer loop + vertex -876.459 485.068 353.663 + vertex -876.718 479.286 355.359 + vertex -876.26 483.805 355.45 + endloop + endfacet + facet normal -0.947238 0.260038 0.187403 + outer loop + vertex -880.231 469.789 350.968 + vertex -879.752 468.369 355.355 + vertex -879.388 472.03 352.118 + endloop + endfacet + facet normal -0.977209 0.186681 0.101055 + outer loop + vertex -879.388 472.03 352.118 + vertex -879.752 468.369 355.355 + vertex -879.534 469.783 354.854 + endloop + endfacet + facet normal -0.884151 0.248199 0.395822 + outer loop + vertex -877.528 474.289 356.964 + vertex -877.239 473.175 358.307 + vertex -876.469 478.086 356.949 + endloop + endfacet + facet normal -0.860156 0.256826 0.440649 + outer loop + vertex -876.469 478.086 356.949 + vertex -877.239 473.175 358.307 + vertex -876.218 476.67 358.264 + endloop + endfacet + facet normal -0.925828 0.243047 0.289431 + outer loop + vertex -877.796 475.28 355.275 + vertex -877.528 474.289 356.964 + vertex -876.718 479.286 355.359 + endloop + endfacet + facet normal -0.907489 0.254466 0.33423 + outer loop + vertex -876.718 479.286 355.359 + vertex -877.528 474.289 356.964 + vertex -876.469 478.086 356.949 + endloop + endfacet + facet normal -0.970285 0.0939287 0.222989 + outer loop + vertex -876.718 479.286 355.359 + vertex -876.469 478.086 356.949 + vertex -876.26 483.805 355.45 + endloop + endfacet + facet normal -0.970087 0.0941257 0.223768 + outer loop + vertex -876.26 483.805 355.45 + vertex -876.469 478.086 356.949 + vertex -876.025 482.303 357.098 + endloop + endfacet + facet normal -0.955744 0.0906393 0.279888 + outer loop + vertex -876.469 478.086 356.949 + vertex -876.218 476.67 358.264 + vertex -876.025 482.303 357.098 + endloop + endfacet + facet normal -0.959168 0.0884316 0.268657 + outer loop + vertex -876.025 482.303 357.098 + vertex -876.218 476.67 358.264 + vertex -875.787 480.622 358.503 + endloop + endfacet + facet normal -0.926937 0.271325 0.259174 + outer loop + vertex -878.875 472.202 354.637 + vertex -878.589 471.091 356.825 + vertex -877.796 475.28 355.275 + endloop + endfacet + facet normal -0.905777 0.286839 0.311916 + outer loop + vertex -877.796 475.28 355.275 + vertex -878.589 471.091 356.825 + vertex -877.528 474.289 356.964 + endloop + endfacet + facet normal -0.889257 0.279155 0.362347 + outer loop + vertex -878.589 471.091 356.825 + vertex -878.263 470.156 358.344 + vertex -877.528 474.289 356.964 + endloop + endfacet + facet normal -0.85425 0.294886 0.428134 + outer loop + vertex -877.528 474.289 356.964 + vertex -878.263 470.156 358.344 + vertex -877.239 473.175 358.307 + endloop + endfacet + facet normal -0.912006 0.260629 0.316729 + outer loop + vertex -879.011 467.981 358.241 + vertex -879.354 468.878 356.513 + vertex -879.409 466.961 357.932 + endloop + endfacet + facet normal -0.95673 0.182187 0.226881 + outer loop + vertex -879.462 466.744 357.883 + vertex -879.409 466.961 357.932 + vertex -879.752 468.369 355.355 + endloop + endfacet + facet normal -0.947438 0.22638 0.226081 + outer loop + vertex -879.534 469.783 354.854 + vertex -879.752 468.369 355.355 + vertex -879.354 468.878 356.513 + endloop + endfacet + facet normal -0.950012 0.202894 0.237299 + outer loop + vertex -879.409 466.961 357.932 + vertex -879.354 468.878 356.513 + vertex -879.752 468.369 355.355 + endloop + endfacet + facet normal -0.725966 0.230916 0.647805 + outer loop + vertex -876.909 471.992 359.376 + vertex -876.486 471.413 360.057 + vertex -875.941 475.156 359.334 + endloop + endfacet + facet normal -0.74026 0.229906 0.63179 + outer loop + vertex -875.941 475.156 359.334 + vertex -876.486 471.413 360.057 + vertex -875.695 473.561 360.203 + endloop + endfacet + facet normal -0.81621 0.244995 0.523238 + outer loop + vertex -877.239 473.175 358.307 + vertex -876.909 471.992 359.376 + vertex -876.218 476.67 358.264 + endloop + endfacet + facet normal -0.791099 0.249649 0.558424 + outer loop + vertex -876.218 476.67 358.264 + vertex -876.909 471.992 359.376 + vertex -875.941 475.156 359.334 + endloop + endfacet + facet normal -0.931477 0.0801962 0.35485 + outer loop + vertex -876.218 476.67 358.264 + vertex -875.941 475.156 359.334 + vertex -875.787 480.622 358.503 + endloop + endfacet + facet normal -0.95256 0.0718133 0.295758 + outer loop + vertex -875.787 480.622 358.503 + vertex -875.941 475.156 359.334 + vertex -875.561 478.715 359.694 + endloop + endfacet + facet normal -0.925353 0.0609781 0.37417 + outer loop + vertex -875.941 475.156 359.334 + vertex -875.695 473.561 360.203 + vertex -875.561 478.715 359.694 + endloop + endfacet + facet normal -0.950095 0.0549932 0.307076 + outer loop + vertex -875.561 478.715 359.694 + vertex -875.695 473.561 360.203 + vertex -875.37 476.602 360.661 + endloop + endfacet + facet normal -0.816758 0.283083 0.502763 + outer loop + vertex -878.263 470.156 358.344 + vertex -877.908 469.189 359.466 + vertex -877.239 473.175 358.307 + endloop + endfacet + facet normal -0.772574 0.293237 0.563153 + outer loop + vertex -877.239 473.175 358.307 + vertex -877.908 469.189 359.466 + vertex -876.909 471.992 359.376 + endloop + endfacet + facet normal -0.701494 0.27101 0.659136 + outer loop + vertex -877.908 469.189 359.466 + vertex -877.368 468.215 360.441 + vertex -876.909 471.992 359.376 + endloop + endfacet + facet normal -0.696347 0.271823 0.664239 + outer loop + vertex -876.909 471.992 359.376 + vertex -877.368 468.215 360.441 + vertex -876.486 471.413 360.057 + endloop + endfacet + facet normal -0.877119 0.197283 0.437883 + outer loop + vertex -879.237 466.054 359.013 + vertex -878.962 465.637 359.752 + vertex -879.069 466.247 359.262 + endloop + endfacet + facet normal -0.833516 0.249279 0.493064 + outer loop + vertex -879.069 466.247 359.262 + vertex -878.962 465.637 359.752 + vertex -878.762 465.812 360.002 + endloop + endfacet + facet normal -0.943168 0.164734 0.288612 + outer loop + vertex -879.462 466.744 357.883 + vertex -879.237 466.054 359.013 + vertex -879.409 466.961 357.932 + endloop + endfacet + facet normal -0.882569 0.281269 0.376775 + outer loop + vertex -879.409 466.961 357.932 + vertex -879.237 466.054 359.013 + vertex -879.069 466.247 359.262 + endloop + endfacet + facet normal -0.900512 0.242824 0.360714 + outer loop + vertex -879.409 466.961 357.932 + vertex -879.069 466.247 359.262 + vertex -879.011 467.981 358.241 + endloop + endfacet + facet normal -0.852729 0.286136 0.437011 + outer loop + vertex -879.011 467.981 358.241 + vertex -879.069 466.247 359.262 + vertex -878.65 467.266 359.413 + endloop + endfacet + facet normal -0.824896 0.265533 0.499038 + outer loop + vertex -879.069 466.247 359.262 + vertex -878.762 465.812 360.002 + vertex -878.65 467.266 359.413 + endloop + endfacet + facet normal -0.740047 0.300622 0.601629 + outer loop + vertex -878.65 467.266 359.413 + vertex -878.762 465.812 360.002 + vertex -878.32 466.441 360.231 + endloop + endfacet + facet normal -0.713229 0.217595 0.666301 + outer loop + vertex -876.486 471.413 360.057 + vertex -876.326 470.244 360.611 + vertex -875.695 473.561 360.203 + endloop + endfacet + facet normal -0.702901 0.216992 0.677381 + outer loop + vertex -875.695 473.561 360.203 + vertex -876.326 470.244 360.611 + vertex -875.472 471.891 360.969 + endloop + endfacet + facet normal -0.929558 0.0439167 0.36605 + outer loop + vertex -875.695 473.561 360.203 + vertex -875.472 471.891 360.969 + vertex -875.37 476.602 360.661 + endloop + endfacet + facet normal -0.955286 0.0396955 0.293005 + outer loop + vertex -875.37 476.602 360.661 + vertex -875.472 471.891 360.969 + vertex -875.246 474.619 361.335 + endloop + endfacet + facet normal -0.918043 0.0642229 0.391245 + outer loop + vertex -875.168 472.488 361.878 + vertex -875.534 470.305 361.378 + vertex -875.166 472.362 361.905 + endloop + endfacet + facet normal -0.716489 0.260286 0.647221 + outer loop + vertex -876.446 468.656 361.031 + vertex -876.401 467.966 361.359 + vertex -875.534 470.305 361.378 + endloop + endfacet + facet normal -0.758524 0.285985 -0.585538 + outer loop + vertex -876.401 467.966 361.359 + vertex -875.166 472.362 361.905 + vertex -875.534 470.305 361.378 + endloop + endfacet + facet normal 0.704857 -0.186227 -0.684468 + outer loop + vertex -878.332 464.023 361.053 + vertex -878.335 464.035 361.046 + vertex -878.352 464.337 360.947 + endloop + endfacet + facet normal -0.681237 0.228332 0.695543 + outer loop + vertex -878.299 464.039 361.081 + vertex -878.166 465.058 360.876 + vertex -878.335 464.035 361.046 + endloop + endfacet + facet normal -0.577302 0.225927 0.784653 + outer loop + vertex -878.166 465.058 360.876 + vertex -878.352 464.337 360.947 + vertex -878.335 464.035 361.046 + endloop + endfacet + facet normal -0.930651 0.354231 0.0917055 + outer loop + vertex -878.279 463.944 361.126 + vertex -878.171 464.224 361.147 + vertex -878.058 464.521 361.143 + endloop + endfacet + facet normal -0.732303 0.284797 0.618565 + outer loop + vertex -878.058 464.521 361.143 + vertex -878.171 464.224 361.147 + vertex -877.904 464.758 361.217 + endloop + endfacet + facet normal -0.801337 0.377125 0.464367 + outer loop + vertex -878.058 464.521 361.143 + vertex -877.904 464.758 361.217 + vertex -877.503 465.555 361.261 + endloop + endfacet + facet normal -0.825364 0.435495 -0.359331 + outer loop + vertex -877.503 465.555 361.261 + vertex -877.904 464.758 361.217 + vertex -877.524 465.528 361.276 + endloop + endfacet + facet normal -0.637628 0.262277 0.724321 + outer loop + vertex -877.424 466.241 361.083 + vertex -877.503 465.555 361.261 + vertex -876.401 467.966 361.359 + endloop + endfacet + facet normal -0.56995 0.228721 0.789204 + outer loop + vertex -876.401 467.966 361.359 + vertex -877.503 465.555 361.261 + vertex -877.139 466.251 361.323 + endloop + endfacet + facet normal 0.75271 -0.150378 -0.640947 + outer loop + vertex -878.332 464.023 361.053 + vertex -878.333 463.927 361.075 + vertex -878.335 464.035 361.046 + endloop + endfacet + facet normal -0.839485 0.11878 0.530241 + outer loop + vertex -878.335 464.035 361.046 + vertex -878.333 463.927 361.075 + vertex -878.323 463.896 361.097 + endloop + endfacet + facet normal -0.684156 0.196033 0.702496 + outer loop + vertex -878.335 464.035 361.046 + vertex -878.323 463.896 361.097 + vertex -878.299 464.039 361.081 + endloop + endfacet + facet normal -0.687511 0.196211 0.699164 + outer loop + vertex -878.299 464.039 361.081 + vertex -878.323 463.896 361.097 + vertex -878.279 463.944 361.126 + endloop + endfacet + facet normal -0.814451 0.105458 0.570569 + outer loop + vertex -878.617 464.889 360.467 + vertex -878.305 464.056 361.066 + vertex -878.352 464.337 360.947 + endloop + endfacet + facet normal -0.87628 -0.475956 -0.0748315 + outer loop + vertex -879.144 466.083 359.052 + vertex -878.617 464.889 360.467 + vertex -878.962 465.637 359.752 + endloop + endfacet + facet normal 0.158831 -0.839994 -0.518829 + outer loop + vertex -879.615 467.272 356.982 + vertex -879.144 466.083 359.052 + vertex -879.462 466.744 357.883 + endloop + endfacet + facet normal -0.930259 0.262865 0.25597 + outer loop + vertex -880.115 468.395 354.01 + vertex -879.615 467.272 356.982 + vertex -879.752 468.369 355.355 + endloop + endfacet + facet normal -0.906044 0.370654 0.204206 + outer loop + vertex -880.499 469.022 351.167 + vertex -880.115 468.395 354.01 + vertex -880.231 469.789 350.968 + endloop + endfacet + facet normal -0.922075 0.36008 0.141847 + outer loop + vertex -880.688 469.357 349.09 + vertex -880.499 469.022 351.167 + vertex -880.231 469.789 350.968 + endloop + endfacet + facet normal -0.939858 0.325953 0.102091 + outer loop + vertex -880.886 469.398 347.139 + vertex -880.688 469.357 349.09 + vertex -880.598 470.448 346.433 + endloop + endfacet + facet normal -0.94903 0.307198 0.0705112 + outer loop + vertex -880.995 469.651 344.569 + vertex -880.886 469.398 347.139 + vertex -880.598 470.448 346.433 + endloop + endfacet + facet normal -0.942765 0.330443 -0.04473 + outer loop + vertex -881.015 469.734 324.651 + vertex -881.045 469.926 326.706 + vertex -880.725 470.455 323.873 + endloop + endfacet + facet normal -0.94719 0.314853 -0.0608227 + outer loop + vertex -880.913 469.596 322.347 + vertex -881.015 469.734 324.651 + vertex -880.725 470.455 323.873 + endloop + endfacet + facet normal -0.931627 0.348163 -0.104182 + outer loop + vertex -880.835 469.159 320.193 + vertex -880.913 469.596 322.347 + vertex -880.531 469.755 319.459 + endloop + endfacet + facet normal -0.939552 0.314917 -0.134421 + outer loop + vertex -880.641 468.445 317.163 + vertex -880.835 469.159 320.193 + vertex -880.531 469.755 319.459 + endloop + endfacet + facet normal -0.928981 0.325048 -0.177024 + outer loop + vertex -880.394 467.558 314.237 + vertex -880.641 468.445 317.163 + vertex -880.189 468.706 315.268 + endloop + endfacet + facet normal -0.904103 0.350915 -0.243838 + outer loop + vertex -880.121 466.697 311.986 + vertex -880.394 467.558 314.237 + vertex -879.767 467.293 311.532 + endloop + endfacet + facet normal -0.904224 0.334396 -0.265627 + outer loop + vertex -879.713 465.967 309.678 + vertex -880.121 466.697 311.986 + vertex -879.767 467.293 311.532 + endloop + endfacet + facet normal -0.88884 0.344115 -0.302569 + outer loop + vertex -879.101 464.997 306.777 + vertex -879.713 465.967 309.678 + vertex -878.976 466.085 307.647 + endloop + endfacet + facet normal -0.908139 0.0694258 0.412872 + outer loop + vertex -875.496 469.941 361.584 + vertex -875.163 472.235 361.932 + vertex -875.166 472.362 361.905 + endloop + endfacet + facet normal -0.842508 0.338045 0.419412 + outer loop + vertex -876.829 466.909 361.351 + vertex -875.496 469.941 361.584 + vertex -876.401 467.966 361.359 + endloop + endfacet + facet normal 0.813569 -0.38595 -0.434912 + outer loop + vertex -877.821 464.966 361.221 + vertex -876.829 466.909 361.351 + vertex -877.524 465.528 361.276 + endloop + endfacet + facet normal 0.730395 -0.283112 -0.621587 + outer loop + vertex -878.305 464.056 361.066 + vertex -877.821 464.966 361.221 + vertex -878.171 464.224 361.147 + endloop + endfacet + facet normal -0.955328 0.0397177 0.292866 + outer loop + vertex -875.168 472.488 361.878 + vertex -875.246 474.619 361.335 + vertex -875.472 471.891 360.969 + endloop + endfacet + facet normal -0.876952 0.378389 -0.296272 + outer loop + vertex -879.767 467.293 311.532 + vertex -878.976 466.085 307.647 + vertex -879.713 465.967 309.678 + endloop + endfacet + facet normal -0.939385 0.258955 -0.224716 + outer loop + vertex -877.749 477.695 316.343 + vertex -877.294 475.934 312.412 + vertex -879.308 471.771 316.033 + endloop + endfacet + facet normal -0.892821 0.378641 -0.243931 + outer loop + vertex -880.189 468.706 315.268 + vertex -879.767 467.293 311.532 + vertex -880.394 467.558 314.237 + endloop + endfacet + facet normal -0.939203 0.271605 -0.21007 + outer loop + vertex -878.845 470.351 312.128 + vertex -879.308 471.771 316.033 + vertex -877.294 475.934 312.412 + endloop + endfacet + facet normal -0.955928 0.248923 -0.155691 + outer loop + vertex -878.061 479.078 320.469 + vertex -877.749 477.695 316.343 + vertex -879.606 472.952 320.16 + endloop + endfacet + facet normal -0.913775 0.370217 -0.167194 + outer loop + vertex -880.531 469.755 319.459 + vertex -880.189 468.706 315.268 + vertex -880.641 468.445 317.163 + endloop + endfacet + facet normal -0.955269 0.25885 -0.143033 + outer loop + vertex -879.308 471.771 316.033 + vertex -879.606 472.952 320.16 + vertex -877.749 477.695 316.343 + endloop + endfacet + facet normal -0.965764 0.239682 -0.0992562 + outer loop + vertex -878.261 480.064 324.795 + vertex -878.061 479.078 320.469 + vertex -879.796 473.743 324.469 + endloop + endfacet + facet normal -0.919544 0.379829 -0.10084 + outer loop + vertex -880.725 470.455 323.873 + vertex -880.531 469.755 319.459 + vertex -880.913 469.596 322.347 + endloop + endfacet + facet normal -0.964812 0.247749 -0.0880826 + outer loop + vertex -879.606 472.952 320.16 + vertex -879.796 473.743 324.469 + vertex -878.061 479.078 320.469 + endloop + endfacet + facet normal -0.970808 0.233248 -0.0559252 + outer loop + vertex -878.382 480.635 329.289 + vertex -878.261 480.064 324.795 + vertex -879.912 474.18 328.928 + endloop + endfacet + facet normal -0.945969 0.320848 -0.0468851 + outer loop + vertex -880.844 470.749 328.277 + vertex -880.725 470.455 323.873 + vertex -881.045 469.926 326.706 + endloop + endfacet + facet normal -0.970018 0.238105 -0.0486949 + outer loop + vertex -879.796 473.743 324.469 + vertex -879.912 474.18 328.928 + vertex -878.261 480.064 324.795 + endloop + endfacet + facet normal -0.972978 0.229784 -0.0226449 + outer loop + vertex -878.43 480.89 333.92 + vertex -878.382 480.635 329.289 + vertex -879.96 474.37 333.509 + endloop + endfacet + facet normal -0.957705 0.287092 -0.0194883 + outer loop + vertex -880.887 470.91 332.754 + vertex -880.844 470.749 328.277 + vertex -881.117 470.027 331.086 + endloop + endfacet + facet normal -0.972599 0.231651 -0.0197325 + outer loop + vertex -879.912 474.18 328.928 + vertex -879.96 474.37 333.509 + vertex -878.382 480.635 329.289 + endloop + endfacet + facet normal -0.972899 0.231002 0.0102933 + outer loop + vertex -878.407 480.778 338.598 + vertex -878.43 480.89 333.92 + vertex -879.934 474.366 338.147 + endloop + endfacet + facet normal -0.958894 0.283762 0.00137208 + outer loop + vertex -880.883 470.901 337.341 + vertex -880.887 470.91 332.754 + vertex -881.13 470.074 335.519 + endloop + endfacet + facet normal -0.97361 0.22815 0.00563792 + outer loop + vertex -879.96 474.37 333.509 + vertex -879.934 474.366 338.147 + vertex -878.43 480.89 333.92 + endloop + endfacet + facet normal -0.970695 0.235668 0.0470306 + outer loop + vertex -878.287 480.338 343.273 + vertex -878.407 480.778 338.598 + vertex -879.809 474.169 342.783 + endloop + endfacet + facet normal -0.956981 0.288998 0.0258334 + outer loop + vertex -880.81 470.732 341.936 + vertex -880.883 470.901 337.341 + vertex -881.097 469.918 340.387 + endloop + endfacet + facet normal -0.972724 0.229148 0.0360552 + outer loop + vertex -879.934 474.366 338.147 + vertex -879.809 474.169 342.783 + vertex -878.407 480.778 338.598 + endloop + endfacet + facet normal -0.965717 0.24256 0.0924967 + outer loop + vertex -878.089 479.236 348.235 + vertex -878.287 480.338 343.273 + vertex -879.588 473.563 347.461 + endloop + endfacet + facet normal -0.945493 0.319162 0.0646428 + outer loop + vertex -880.598 470.448 346.433 + vertex -880.81 470.732 341.936 + vertex -880.995 469.651 344.569 + endloop + endfacet + facet normal -0.969486 0.233073 0.0759799 + outer loop + vertex -879.809 474.169 342.783 + vertex -879.588 473.563 347.461 + vertex -878.287 480.338 343.273 + endloop + endfacet + facet normal -0.950185 0.262143 0.168613 + outer loop + vertex -878.428 475.526 352.092 + vertex -878.089 479.236 348.235 + vertex -879.388 472.03 352.118 + endloop + endfacet + facet normal -0.909724 0.393994 0.13104 + outer loop + vertex -880.231 469.789 350.968 + vertex -880.598 470.448 346.433 + vertex -880.688 469.357 349.09 + endloop + endfacet + facet normal -0.963765 0.238311 0.119856 + outer loop + vertex -879.588 473.563 347.461 + vertex -879.388 472.03 352.118 + vertex -878.089 479.236 348.235 + endloop + endfacet + facet normal -0.931463 0.277975 0.234747 + outer loop + vertex -877.796 475.28 355.275 + vertex -877.924 476.366 353.479 + vertex -878.875 472.202 354.637 + endloop + endfacet + facet normal -0.946439 0.266718 0.181976 + outer loop + vertex -877.924 476.366 353.479 + vertex -878.428 475.526 352.092 + vertex -878.875 472.202 354.637 + endloop + endfacet + facet normal -0.858405 0.453238 0.240242 + outer loop + vertex -879.752 468.369 355.355 + vertex -880.231 469.789 350.968 + vertex -880.115 468.395 354.01 + endloop + endfacet + facet normal -0.946107 0.273252 0.173824 + outer loop + vertex -879.388 472.03 352.118 + vertex -879.534 469.783 354.854 + vertex -878.875 472.202 354.637 + endloop + endfacet + facet normal -0.922399 0.281954 0.263975 + outer loop + vertex -878.589 471.091 356.825 + vertex -878.875 472.202 354.637 + vertex -879.354 468.878 356.513 + endloop + endfacet + facet normal -0.885215 0.286849 0.366214 + outer loop + vertex -878.263 470.156 358.344 + vertex -878.589 471.091 356.825 + vertex -879.011 467.981 358.241 + endloop + endfacet + facet normal -0.640342 0.610605 0.465966 + outer loop + vertex -879.462 466.744 357.883 + vertex -879.752 468.369 355.355 + vertex -879.615 467.272 356.982 + endloop + endfacet + facet normal -0.928115 0.275264 0.250662 + outer loop + vertex -879.534 469.783 354.854 + vertex -879.354 468.878 356.513 + vertex -878.875 472.202 354.637 + endloop + endfacet + facet normal -0.90826 0.269106 0.320384 + outer loop + vertex -879.354 468.878 356.513 + vertex -879.011 467.981 358.241 + vertex -878.589 471.091 356.825 + endloop + endfacet + facet normal -0.806289 0.297074 0.511513 + outer loop + vertex -877.908 469.189 359.466 + vertex -878.263 470.156 358.344 + vertex -878.65 467.266 359.413 + endloop + endfacet + facet normal -0.685649 0.288836 0.668176 + outer loop + vertex -877.368 468.215 360.441 + vertex -877.908 469.189 359.466 + vertex -878.32 466.441 360.231 + endloop + endfacet + facet normal -0.627601 0.26117 0.733422 + outer loop + vertex -876.486 471.413 360.057 + vertex -877.368 468.215 360.441 + vertex -876.326 470.244 360.611 + endloop + endfacet + facet normal 0.446468 -0.69792 -0.559976 + outer loop + vertex -878.962 465.637 359.752 + vertex -879.237 466.054 359.013 + vertex -879.144 466.083 359.052 + endloop + endfacet + facet normal -0.820295 0.149227 0.55213 + outer loop + vertex -878.762 465.812 360.002 + vertex -878.962 465.637 359.752 + vertex -878.617 464.889 360.467 + endloop + endfacet + facet normal 0.4418 -0.723754 -0.530089 + outer loop + vertex -879.237 466.054 359.013 + vertex -879.462 466.744 357.883 + vertex -879.144 466.083 359.052 + endloop + endfacet + facet normal -0.859016 0.274734 0.431986 + outer loop + vertex -879.011 467.981 358.241 + vertex -878.65 467.266 359.413 + vertex -878.263 470.156 358.344 + endloop + endfacet + facet normal -0.760841 0.277419 0.586651 + outer loop + vertex -878.65 467.266 359.413 + vertex -878.32 466.441 360.231 + vertex -877.908 469.189 359.466 + endloop + endfacet + facet normal -0.690491 0.235954 0.683775 + outer loop + vertex -878.32 466.441 360.231 + vertex -878.762 465.812 360.002 + vertex -878.617 464.889 360.467 + endloop + endfacet + facet normal -0.717521 0.228817 0.65788 + outer loop + vertex -875.472 471.891 360.969 + vertex -876.326 470.244 360.611 + vertex -876.446 468.656 361.031 + endloop + endfacet + facet normal -0.96186 0.103128 0.253358 + outer loop + vertex -875.534 470.305 361.378 + vertex -875.168 472.488 361.878 + vertex -875.472 471.891 360.969 + endloop + endfacet + facet normal 0.0564757 -0.138752 0.988716 + outer loop + vertex -875.166 472.362 361.905 + vertex -876.401 467.966 361.359 + vertex -875.496 469.941 361.584 + endloop + endfacet + facet normal -0.665289 0.28411 0.690414 + outer loop + vertex -876.401 467.966 361.359 + vertex -876.446 468.656 361.031 + vertex -877.424 466.241 361.083 + endloop + endfacet + facet normal -0.658042 0.212142 0.722479 + outer loop + vertex -876.446 468.656 361.031 + vertex -875.534 470.305 361.378 + vertex -875.472 471.891 360.969 + endloop + endfacet + facet normal 0.624206 -0.213679 -0.751471 + outer loop + vertex -878.332 464.023 361.053 + vertex -878.352 464.337 360.947 + vertex -878.305 464.056 361.066 + endloop + endfacet + facet normal -0.700584 0.246356 0.669695 + outer loop + vertex -878.352 464.337 360.947 + vertex -878.166 465.058 360.876 + vertex -878.617 464.889 360.467 + endloop + endfacet + facet normal -0.650033 0.230027 0.724254 + outer loop + vertex -878.166 465.058 360.876 + vertex -878.299 464.039 361.081 + vertex -878.058 464.521 361.143 + endloop + endfacet + facet normal 0.702014 -0.222643 -0.676466 + outer loop + vertex -878.171 464.224 361.147 + vertex -878.279 463.944 361.126 + vertex -878.323 463.896 361.097 + endloop + endfacet + facet normal -0.639688 0.223407 0.735451 + outer loop + vertex -878.279 463.944 361.126 + vertex -878.058 464.521 361.143 + vertex -878.299 464.039 361.081 + endloop + endfacet + facet normal 0.725696 -0.280218 -0.628366 + outer loop + vertex -877.904 464.758 361.217 + vertex -878.171 464.224 361.147 + vertex -877.821 464.966 361.221 + endloop + endfacet + facet normal -0.641213 0.261901 0.721286 + outer loop + vertex -878.058 464.521 361.143 + vertex -877.503 465.555 361.261 + vertex -877.424 466.241 361.083 + endloop + endfacet + facet normal -0.828691 0.461207 -0.31711 + outer loop + vertex -877.503 465.555 361.261 + vertex -877.524 465.528 361.276 + vertex -877.139 466.251 361.323 + endloop + endfacet + facet normal 0.529315 -0.197318 -0.825161 + outer loop + vertex -877.524 465.528 361.276 + vertex -877.904 464.758 361.217 + vertex -877.821 464.966 361.221 + endloop + endfacet + facet normal -0.471615 0.184862 0.86221 + outer loop + vertex -876.401 467.966 361.359 + vertex -877.139 466.251 361.323 + vertex -876.829 466.909 361.351 + endloop + endfacet + facet normal 0.599928 -0.181989 -0.77908 + outer loop + vertex -878.333 463.927 361.075 + vertex -878.332 464.023 361.053 + vertex -878.305 464.056 361.066 + endloop + endfacet + facet normal 0.760758 -0.205386 -0.615681 + outer loop + vertex -878.323 463.896 361.097 + vertex -878.333 463.927 361.075 + vertex -878.305 464.056 361.066 + endloop + endfacet + facet normal 0.315443 -0.107677 -0.942816 + outer loop + vertex -877.524 465.528 361.276 + vertex -876.829 466.909 361.351 + vertex -877.139 466.251 361.323 + endloop + endfacet + facet normal 0.68642 -0.212572 -0.695443 + outer loop + vertex -878.305 464.056 361.066 + vertex -878.171 464.224 361.147 + vertex -878.323 463.896 361.097 + endloop + endfacet + facet normal -0.949063 0.261885 0.175201 + outer loop + vertex -878.428 475.526 352.092 + vertex -879.388 472.03 352.118 + vertex -878.875 472.202 354.637 + endloop + endfacet + facet normal -0.646598 0.262208 0.71635 + outer loop + vertex -877.368 468.215 360.441 + vertex -878.32 466.441 360.231 + vertex -878.166 465.058 360.876 + endloop + endfacet + facet normal -0.603567 0.246742 0.758173 + outer loop + vertex -876.326 470.244 360.611 + vertex -877.368 468.215 360.441 + vertex -876.446 468.656 361.031 + endloop + endfacet + facet normal -0.700329 0.236287 0.673578 + outer loop + vertex -878.32 466.441 360.231 + vertex -878.617 464.889 360.467 + vertex -878.166 465.058 360.876 + endloop + endfacet + facet normal -0.606115 0.26144 0.751182 + outer loop + vertex -877.424 466.241 361.083 + vertex -876.446 468.656 361.031 + vertex -877.368 468.215 360.441 + endloop + endfacet + facet normal -0.610104 0.251495 0.751348 + outer loop + vertex -878.166 465.058 360.876 + vertex -878.058 464.521 361.143 + vertex -877.424 466.241 361.083 + endloop + endfacet + facet normal -0.618895 0.2587 0.741649 + outer loop + vertex -877.368 468.215 360.441 + vertex -878.166 465.058 360.876 + vertex -877.424 466.241 361.083 + endloop + endfacet + facet normal -0.880438 0.0257728 -0.47346 + outer loop + vertex -875.204 467.444 362.668 + vertex -875.092 464.787 362.315 + vertex -875.544 462.349 363.022 + endloop + endfacet + facet normal -0.982423 0.149575 -0.111679 + outer loop + vertex -875.544 462.349 363.022 + vertex -875.092 464.787 362.315 + vertex -875.757 460.532 362.465 + endloop + endfacet + facet normal -0.454761 0.102379 0.88471 + outer loop + vertex -875.092 464.787 362.315 + vertex -875.628 464.313 362.094 + vertex -875.757 460.532 362.465 + endloop + endfacet + facet normal -0.338827 0.103366 0.935153 + outer loop + vertex -875.757 460.532 362.465 + vertex -875.628 464.313 362.094 + vertex -876.435 460.391 362.235 + endloop + endfacet + facet normal -0.403315 0.105264 0.908987 + outer loop + vertex -875.834 466.425 361.823 + vertex -875.084 468.112 361.96 + vertex -875.841 468.227 361.611 + endloop + endfacet + facet normal -0.99981 -0.0190288 -0.00415074 + outer loop + vertex -875.158 471.98 361.985 + vertex -875.16 472.108 361.959 + vertex -875.084 468.112 361.96 + endloop + endfacet + facet normal -0.419891 -0.00769293 0.907542 + outer loop + vertex -875.16 472.108 361.959 + vertex -875.841 468.227 361.611 + vertex -875.084 468.112 361.96 + endloop + endfacet + facet normal -0.273409 0.0664936 0.959597 + outer loop + vertex -878.423 457.712 361.923 + vertex -879.334 451.413 362.1 + vertex -877.595 458.141 362.13 + endloop + endfacet + facet normal -0.228537 0.0819094 0.970083 + outer loop + vertex -875.628 464.313 362.094 + vertex -876.669 463.253 361.938 + vertex -876.435 460.391 362.235 + endloop + endfacet + facet normal -0.243718 0.0802974 0.966516 + outer loop + vertex -876.435 460.391 362.235 + vertex -876.669 463.253 361.938 + vertex -877.595 458.141 362.13 + endloop + endfacet + facet normal -0.238317 0.079373 0.967938 + outer loop + vertex -876.669 463.253 361.938 + vertex -877.654 461.059 361.876 + vertex -877.595 458.141 362.13 + endloop + endfacet + facet normal -0.278602 0.0776333 0.957264 + outer loop + vertex -877.595 458.141 362.13 + vertex -877.654 461.059 361.876 + vertex -878.423 457.712 361.923 + endloop + endfacet + facet normal -0.384949 0.142486 0.911873 + outer loop + vertex -877.315 463.999 361.642 + vertex -876.509 466.038 361.663 + vertex -877.033 466.172 361.421 + endloop + endfacet + facet normal -0.288001 0.11072 0.951208 + outer loop + vertex -875.834 466.425 361.823 + vertex -875.841 468.227 361.611 + vertex -876.509 466.038 361.663 + endloop + endfacet + facet normal -0.385745 0.139576 0.911986 + outer loop + vertex -875.841 468.227 361.611 + vertex -877.033 466.172 361.421 + vertex -876.509 466.038 361.663 + endloop + endfacet + facet normal -0.438111 0.180769 0.880557 + outer loop + vertex -877.355 466.082 361.279 + vertex -877.534 465.631 361.283 + vertex -877.033 466.172 361.421 + endloop + endfacet + facet normal -0.400296 0.139331 0.905732 + outer loop + vertex -877.033 466.172 361.421 + vertex -877.534 465.631 361.283 + vertex -877.728 464.417 361.384 + endloop + endfacet + facet normal -0.160805 -0.00357357 0.98698 + outer loop + vertex -893.242 383.188 361.852 + vertex -894.226 379.612 361.679 + vertex -893.091 375.481 361.849 + endloop + endfacet + facet normal -0.170169 -0.00621127 0.985395 + outer loop + vertex -893.091 375.481 361.849 + vertex -894.226 379.612 361.679 + vertex -894.053 371.797 361.66 + endloop + endfacet + facet normal -0.187327 0.00885147 0.982258 + outer loop + vertex -892.817 391.057 361.862 + vertex -893.984 387.704 361.67 + vertex -893.242 383.188 361.852 + endloop + endfacet + facet normal -0.198052 0.00700626 0.980167 + outer loop + vertex -893.242 383.188 361.852 + vertex -893.984 387.704 361.67 + vertex -894.226 379.612 361.679 + endloop + endfacet + facet normal -0.41711 0.101342 0.903188 + outer loop + vertex -879.543 456.649 361.575 + vertex -879.993 455.15 361.536 + vertex -880.275 452.15 361.742 + endloop + endfacet + facet normal -0.59361 0.142621 0.792014 + outer loop + vertex -880.096 454.879 361.508 + vertex -881.312 449.152 361.628 + vertex -879.993 455.15 361.536 + endloop + endfacet + facet normal -0.456726 0.123097 0.881049 + outer loop + vertex -878.875 459.833 361.477 + vertex -879.304 458.523 361.438 + vertex -879.543 456.649 361.575 + endloop + endfacet + facet normal -0.497179 0.126596 0.858363 + outer loop + vertex -879.543 456.649 361.575 + vertex -879.304 458.523 361.438 + vertex -879.993 455.15 361.536 + endloop + endfacet + facet normal -0.606042 0.146632 0.781801 + outer loop + vertex -879.304 458.523 361.438 + vertex -879.479 457.874 361.423 + vertex -879.993 455.15 361.536 + endloop + endfacet + facet normal -0.600333 0.145742 0.786359 + outer loop + vertex -879.993 455.15 361.536 + vertex -879.479 457.874 361.423 + vertex -880.096 454.879 361.508 + endloop + endfacet + facet normal -0.621992 0.168971 0.764575 + outer loop + vertex -878.368 463.588 361.121 + vertex -878.335 463.578 361.15 + vertex -878.26 464.121 361.091 + endloop + endfacet + facet normal -0.562321 0.158311 0.811624 + outer loop + vertex -878.272 463.054 361.296 + vertex -878.183 464.196 361.135 + vertex -878.335 463.578 361.15 + endloop + endfacet + facet normal -0.60591 0.168167 0.777556 + outer loop + vertex -878.183 464.196 361.135 + vertex -878.26 464.121 361.091 + vertex -878.335 463.578 361.15 + endloop + endfacet + facet normal 0.0961393 0.0831616 -0.991888 + outer loop + vertex -857.903 293.892 361.559 + vertex -856.093 292.377 361.607 + vertex -856.754 292.835 361.581 + endloop + endfacet + facet normal -0.133605 -0.0511969 0.989711 + outer loop + vertex -888.048 341.731 361.568 + vertex -887.016 339.215 361.577 + vertex -887.756 342.594 361.652 + endloop + endfacet + facet normal -0.142734 -0.0480094 0.988596 + outer loop + vertex -889.219 345.334 361.574 + vertex -888.048 341.731 361.568 + vertex -887.756 342.594 361.652 + endloop + endfacet + facet normal -0.191613 -0.0568504 0.979823 + outer loop + vertex -891.013 351.536 361.583 + vertex -889.219 345.334 361.574 + vertex -890 349.326 361.653 + endloop + endfacet + facet normal -0.181645 -0.0444177 0.982361 + outer loop + vertex -892.34 356.842 361.578 + vertex -891.013 351.536 361.583 + vertex -891.941 356.67 361.644 + endloop + endfacet + facet normal -0.177207 -0.0336757 0.983597 + outer loop + vertex -893.311 362.02 361.58 + vertex -892.34 356.842 361.578 + vertex -891.941 356.67 361.644 + endloop + endfacet + facet normal -0.191144 -0.0272934 0.981182 + outer loop + vertex -894.043 367.38 361.587 + vertex -893.311 362.02 361.58 + vertex -893.194 364.183 361.663 + endloop + endfacet + facet normal -0.198145 -0.0166718 0.980031 + outer loop + vertex -894.451 371.34 361.571 + vertex -894.043 367.38 361.587 + vertex -894.053 371.797 361.66 + endloop + endfacet + facet normal -0.206937 -0.0086921 0.978316 + outer loop + vertex -894.598 376.559 361.587 + vertex -894.451 371.34 361.571 + vertex -894.053 371.797 361.66 + endloop + endfacet + facet normal -0.258458 0.00226228 0.96602 + outer loop + vertex -894.523 382.935 361.592 + vertex -894.598 376.559 361.587 + vertex -894.226 379.612 361.679 + endloop + endfacet + facet normal -0.271735 0.0149232 0.962256 + outer loop + vertex -894.265 388.139 361.584 + vertex -894.523 382.935 361.592 + vertex -893.984 387.704 361.67 + endloop + endfacet + facet normal -0.25844 0.0241962 0.965724 + outer loop + vertex -893.77 393.074 361.593 + vertex -894.265 388.139 361.584 + vertex -893.984 387.704 361.67 + endloop + endfacet + facet normal -0.319455 0.0410146 0.946714 + outer loop + vertex -892.985 399.182 361.593 + vertex -893.77 393.074 361.593 + vertex -893.156 395.677 361.687 + endloop + endfacet + facet normal -0.344811 0.0547163 0.937076 + outer loop + vertex -892.208 404.206 361.586 + vertex -892.985 399.182 361.593 + vertex -892.07 403.681 361.667 + endloop + endfacet + facet normal -0.326373 0.0605354 0.943301 + outer loop + vertex -891.318 408.937 361.59 + vertex -892.208 404.206 361.586 + vertex -892.07 403.681 361.667 + endloop + endfacet + facet normal -0.400857 0.0839942 0.912282 + outer loop + vertex -890.081 414.915 361.583 + vertex -891.318 408.937 361.59 + vertex -890.653 411.22 361.672 + endloop + endfacet + facet normal -0.411124 0.105177 0.905492 + outer loop + vertex -886.943 427.951 361.577 + vertex -888.116 423.331 361.581 + vertex -887.287 425.917 361.658 + endloop + endfacet + facet normal -0.507954 0.130455 0.851448 + outer loop + vertex -881.615 448.257 361.584 + vertex -882.441 444.902 361.605 + vertex -881.312 449.152 361.628 + endloop + endfacet + facet normal -0.485022 0.121992 0.865951 + outer loop + vertex -880.675 452.234 361.55 + vertex -881.615 448.257 361.584 + vertex -881.312 449.152 361.628 + endloop + endfacet + facet normal 0.0217495 -0.0207926 -0.999547 + outer loop + vertex -880.017 455.179 361.503 + vertex -880.675 452.234 361.55 + vertex -880.096 454.879 361.508 + endloop + endfacet + facet normal 0.272339 -0.0862746 -0.958326 + outer loop + vertex -879.569 457.409 361.43 + vertex -880.017 455.179 361.503 + vertex -880.096 454.879 361.508 + endloop + endfacet + facet normal -0.981171 0.189271 -0.0384632 + outer loop + vertex -878.808 461.315 361.25 + vertex -879.569 457.409 361.43 + vertex -879.479 457.874 361.423 + endloop + endfacet + facet normal -0.709704 0.176189 0.682112 + outer loop + vertex -878.305 464.056 361.066 + vertex -878.808 461.315 361.25 + vertex -878.368 463.588 361.121 + endloop + endfacet + facet normal -0.671039 0.237823 0.702244 + outer loop + vertex -877.821 464.966 361.221 + vertex -878.305 464.056 361.066 + vertex -878.183 464.196 361.135 + endloop + endfacet + facet normal 0.153427 -0.0118808 -0.988089 + outer loop + vertex -876.829 466.909 361.351 + vertex -877.821 464.966 361.221 + vertex -877.355 466.082 361.279 + endloop + endfacet + facet normal -0.360063 0.086895 0.928872 + outer loop + vertex -875.496 469.941 361.584 + vertex -876.829 466.909 361.351 + vertex -875.841 468.227 361.611 + endloop + endfacet + facet normal -0.907347 0.0690372 0.414675 + outer loop + vertex -875.163 472.235 361.932 + vertex -875.496 469.941 361.584 + vertex -875.16 472.108 361.959 + endloop + endfacet + facet normal -0.982998 -0.0175557 -0.182775 + outer loop + vertex -875.204 467.444 362.668 + vertex -875.158 471.98 361.985 + vertex -875.084 468.112 361.96 + endloop + endfacet + facet normal -0.983064 -0.017205 -0.182455 + outer loop + vertex -875.092 464.787 362.315 + vertex -875.204 467.444 362.668 + vertex -875.084 468.112 361.96 + endloop + endfacet + facet normal -0.450152 0.0957269 0.887806 + outer loop + vertex -875.628 464.313 362.094 + vertex -875.092 464.787 362.315 + vertex -875.084 468.112 361.96 + endloop + endfacet + facet normal -0.359719 0.0842583 0.929249 + outer loop + vertex -875.084 468.112 361.96 + vertex -875.834 466.425 361.823 + vertex -875.628 464.313 362.094 + endloop + endfacet + facet normal -0.953905 0.188313 -0.233676 + outer loop + vertex -875.841 468.227 361.611 + vertex -875.16 472.108 361.959 + vertex -875.496 469.941 361.584 + endloop + endfacet + facet normal -0.245908 0.099847 0.964137 + outer loop + vertex -876.669 463.253 361.938 + vertex -875.628 464.313 362.094 + vertex -875.834 466.425 361.823 + endloop + endfacet + facet normal -0.306353 0.110537 0.945478 + outer loop + vertex -877.654 461.059 361.876 + vertex -876.669 463.253 361.938 + vertex -877.315 463.999 361.642 + endloop + endfacet + facet normal -0.305958 0.110912 0.945562 + outer loop + vertex -876.509 466.038 361.663 + vertex -877.315 463.999 361.642 + vertex -876.669 463.253 361.938 + endloop + endfacet + facet normal -0.414001 0.144905 0.898669 + outer loop + vertex -877.315 463.999 361.642 + vertex -877.033 466.172 361.421 + vertex -877.728 464.417 361.384 + endloop + endfacet + facet normal -0.512836 0.220892 0.829582 + outer loop + vertex -877.033 466.172 361.421 + vertex -875.841 468.227 361.611 + vertex -876.829 466.909 361.351 + endloop + endfacet + facet normal -0.287855 0.110432 0.951286 + outer loop + vertex -875.834 466.425 361.823 + vertex -876.509 466.038 361.663 + vertex -876.669 463.253 361.938 + endloop + endfacet + facet normal -0.389082 0.117547 0.913673 + outer loop + vertex -878.223 461.169 361.619 + vertex -877.654 461.059 361.876 + vertex -877.315 463.999 361.642 + endloop + endfacet + facet normal -0.422237 0.110188 0.899764 + outer loop + vertex -879.155 456.562 361.746 + vertex -878.223 461.169 361.619 + vertex -878.875 459.833 361.477 + endloop + endfacet + facet normal -0.888426 0.355141 0.290816 + outer loop + vertex -877.534 465.631 361.283 + vertex -877.355 466.082 361.279 + vertex -877.821 464.966 361.221 + endloop + endfacet + facet normal -0.441803 0.205333 0.873297 + outer loop + vertex -877.355 466.082 361.279 + vertex -877.033 466.172 361.421 + vertex -876.829 466.909 361.351 + endloop + endfacet + facet normal -0.54037 0.155135 0.827003 + outer loop + vertex -877.728 464.417 361.384 + vertex -877.534 465.631 361.283 + vertex -877.821 464.966 361.221 + endloop + endfacet + facet normal -0.141166 -0.0471649 0.988862 + outer loop + vertex -887.756 342.594 361.652 + vertex -890 349.326 361.653 + vertex -889.219 345.334 361.574 + endloop + endfacet + facet normal -0.154348 -0.0395369 0.987225 + outer loop + vertex -890 349.326 361.653 + vertex -891.941 356.67 361.644 + vertex -891.013 351.536 361.583 + endloop + endfacet + facet normal -0.159836 -0.0291925 0.986712 + outer loop + vertex -891.941 356.67 361.644 + vertex -893.194 364.183 361.663 + vertex -893.311 362.02 361.58 + endloop + endfacet + facet normal -0.151925 -0.0167064 0.988251 + outer loop + vertex -893.194 364.183 361.663 + vertex -894.053 371.797 361.66 + vertex -894.043 367.38 361.587 + endloop + endfacet + facet normal -0.189382 -0.00662842 0.981881 + outer loop + vertex -894.053 371.797 361.66 + vertex -894.226 379.612 361.679 + vertex -894.598 376.559 361.587 + endloop + endfacet + facet normal -0.206241 0.0072501 0.978474 + outer loop + vertex -894.226 379.612 361.679 + vertex -893.984 387.704 361.67 + vertex -894.523 382.935 361.592 + endloop + endfacet + facet normal -0.250154 0.0238982 0.967911 + outer loop + vertex -893.984 387.704 361.67 + vertex -893.156 395.677 361.687 + vertex -893.77 393.074 361.593 + endloop + endfacet + facet normal -0.269533 0.0389994 0.962201 + outer loop + vertex -893.156 395.677 361.687 + vertex -892.07 403.681 361.667 + vertex -892.985 399.182 361.593 + endloop + endfacet + facet normal -0.322535 0.0600057 0.944654 + outer loop + vertex -892.07 403.681 361.667 + vertex -890.653 411.22 361.672 + vertex -891.318 408.937 361.59 + endloop + endfacet + facet normal -0.334825 0.0744348 0.939336 + outer loop + vertex -890.653 411.22 361.672 + vertex -888.994 418.868 361.657 + vertex -890.081 414.915 361.583 + endloop + endfacet + facet normal -0.349976 0.0847489 0.932917 + outer loop + vertex -888.994 418.868 361.657 + vertex -887.287 425.917 361.658 + vertex -888.116 423.331 361.581 + endloop + endfacet + facet normal -0.4022 0.103835 0.909645 + outer loop + vertex -887.287 425.917 361.658 + vertex -885.502 432.895 361.65 + vertex -886.943 427.951 361.577 + endloop + endfacet + facet normal -0.481121 0.123241 0.867948 + outer loop + vertex -883.387 440.769 361.667 + vertex -881.312 449.152 361.628 + vertex -882.441 444.902 361.605 + endloop + endfacet + facet normal -0.382435 0.0962873 0.918952 + outer loop + vertex -879.543 456.649 361.575 + vertex -880.275 452.15 361.742 + vertex -879.155 456.562 361.746 + endloop + endfacet + facet normal -0.587929 0.141508 0.796439 + outer loop + vertex -881.312 449.152 361.628 + vertex -880.096 454.879 361.508 + vertex -880.675 452.234 361.55 + endloop + endfacet + facet normal -0.537773 0.15113 0.829434 + outer loop + vertex -879.304 458.523 361.438 + vertex -878.875 459.833 361.477 + vertex -878.808 461.315 361.25 + endloop + endfacet + facet normal -0.379724 0.108121 0.91876 + outer loop + vertex -878.875 459.833 361.477 + vertex -879.543 456.649 361.575 + vertex -879.155 456.562 361.746 + endloop + endfacet + facet normal -0.682475 0.168842 0.711141 + outer loop + vertex -879.479 457.874 361.423 + vertex -879.304 458.523 361.438 + vertex -878.808 461.315 361.25 + endloop + endfacet + facet normal -0.757083 0.137934 -0.638591 + outer loop + vertex -880.096 454.879 361.508 + vertex -879.479 457.874 361.423 + vertex -879.569 457.409 361.43 + endloop + endfacet + facet normal -0.623452 0.16415 0.764436 + outer loop + vertex -878.335 463.578 361.15 + vertex -878.368 463.588 361.121 + vertex -878.808 461.315 361.25 + endloop + endfacet + facet normal -0.66296 0.175233 0.727858 + outer loop + vertex -878.368 463.588 361.121 + vertex -878.26 464.121 361.091 + vertex -878.305 464.056 361.066 + endloop + endfacet + facet normal 0.505542 -0.015481 -0.862663 + outer loop + vertex -878.26 464.121 361.091 + vertex -878.183 464.196 361.135 + vertex -878.305 464.056 361.066 + endloop + endfacet + facet normal -0.533497 0.158754 0.830769 + outer loop + vertex -878.183 464.196 361.135 + vertex -878.272 463.054 361.296 + vertex -877.821 464.966 361.221 + endloop + endfacet + facet normal -0.572502 0.155272 0.805066 + outer loop + vertex -878.272 463.054 361.296 + vertex -878.335 463.578 361.15 + vertex -878.808 461.315 361.25 + endloop + endfacet + facet normal -0.426885 0.129837 0.894937 + outer loop + vertex -877.315 463.999 361.642 + vertex -877.728 464.417 361.384 + vertex -878.223 461.169 361.619 + endloop + endfacet + facet normal -0.471187 0.137115 0.871311 + outer loop + vertex -878.875 459.833 361.477 + vertex -878.223 461.169 361.619 + vertex -878.272 463.054 361.296 + endloop + endfacet + facet normal -0.531193 0.158272 0.832337 + outer loop + vertex -877.728 464.417 361.384 + vertex -877.821 464.966 361.221 + vertex -878.272 463.054 361.296 + endloop + endfacet + facet normal -0.556719 0.150087 0.81703 + outer loop + vertex -878.808 461.315 361.25 + vertex -878.875 459.833 361.477 + vertex -878.272 463.054 361.296 + endloop + endfacet + facet normal -0.480852 0.135988 0.866192 + outer loop + vertex -878.223 461.169 361.619 + vertex -877.728 464.417 361.384 + vertex -878.272 463.054 361.296 + endloop + endfacet + facet normal 0.16562 -0.0058825 0.986172 + outer loop + vertex 894.084 371.882 361.658 + vertex 894.268 379.902 361.675 + vertex 892.936 376.984 361.882 + endloop + endfacet + facet normal 0.159125 -0.00284147 0.987254 + outer loop + vertex 892.936 376.984 361.882 + vertex 894.268 379.902 361.675 + vertex 893.492 384.194 361.813 + endloop + endfacet + facet normal 0.220584 0.00864588 0.97533 + outer loop + vertex 894.268 379.902 361.675 + vertex 893.991 387.866 361.667 + vertex 893.492 384.194 361.813 + endloop + endfacet + facet normal 0.19393 0.0124873 0.980936 + outer loop + vertex 893.492 384.194 361.813 + vertex 893.991 387.866 361.667 + vertex 892.569 392.154 361.894 + endloop + endfacet + facet normal 0.262717 0.0623066 0.962859 + outer loop + vertex 878.394 457.545 361.971 + vertex 877.591 458.079 362.156 + vertex 878.911 452.535 362.154 + endloop + endfacet + facet normal 0.492807 0.123205 0.861372 + outer loop + vertex 880.155 454.673 361.503 + vertex 880.015 454.948 361.543 + vertex 881.445 448.643 361.627 + endloop + endfacet + facet normal 0.405047 0.096622 0.909176 + outer loop + vertex 879.363 457.134 361.601 + vertex 880.372 450.863 361.819 + vertex 880.015 454.948 361.543 + endloop + endfacet + facet normal 0.32922 0.101831 0.938746 + outer loop + vertex 876.545 460.284 362.221 + vertex 875.802 464.595 362.014 + vertex 875.838 460.581 362.437 + endloop + endfacet + facet normal 0.417083 0.0988961 0.903472 + outer loop + vertex 875.838 460.581 362.437 + vertex 875.802 464.595 362.014 + vertex 875.166 464.876 362.277 + endloop + endfacet + facet normal 0.987997 0.154467 -0.00130642 + outer loop + vertex 875.838 460.581 362.437 + vertex 875.166 464.876 362.277 + vertex 875.566 462.325 363.022 + endloop + endfacet + facet normal 0.931217 0.040221 -0.36224 + outer loop + vertex 875.566 462.325 363.022 + vertex 875.166 464.876 362.277 + vertex 875.207 467.441 362.668 + endloop + endfacet + facet normal 0.270893 0.0757212 0.959627 + outer loop + vertex 878.394 457.545 361.971 + vertex 877.751 460.604 361.911 + vertex 877.591 458.079 362.156 + endloop + endfacet + facet normal 0.239884 0.0784671 0.967625 + outer loop + vertex 877.591 458.079 362.156 + vertex 877.751 460.604 361.911 + vertex 876.893 462.435 361.975 + endloop + endfacet + facet normal 0.220741 0.0755983 0.972398 + outer loop + vertex 877.591 458.079 362.156 + vertex 876.893 462.435 361.975 + vertex 876.545 460.284 362.221 + endloop + endfacet + facet normal 0.194392 0.0804553 0.977619 + outer loop + vertex 876.545 460.284 362.221 + vertex 876.893 462.435 361.975 + vertex 875.802 464.595 362.014 + endloop + endfacet + facet normal 0.499402 0.127212 0.85698 + outer loop + vertex 880.155 454.673 361.503 + vertex 879.492 457.873 361.414 + vertex 880.015 454.948 361.543 + endloop + endfacet + facet normal 0.591324 0.140889 0.794032 + outer loop + vertex 880.015 454.948 361.543 + vertex 879.492 457.873 361.414 + vertex 879.263 458.769 361.426 + endloop + endfacet + facet normal 0.489157 0.122917 0.863491 + outer loop + vertex 880.015 454.948 361.543 + vertex 879.263 458.769 361.426 + vertex 879.363 457.134 361.601 + endloop + endfacet + facet normal 0.474631 0.122895 0.871563 + outer loop + vertex 879.363 457.134 361.601 + vertex 879.263 458.769 361.426 + vertex 878.819 460.465 361.428 + endloop + endfacet + facet normal 0.999743 -0.0146036 0.0173321 + outer loop + vertex 875.158 471.98 361.985 + vertex 875.105 468.303 361.931 + vertex 875.16 472.108 361.959 + endloop + endfacet + facet normal 0.427388 0.089288 0.899648 + outer loop + vertex 875.65 467.239 361.778 + vertex 875.68 468.558 361.633 + vertex 875.105 468.303 361.931 + endloop + endfacet + facet normal 0.465292 -0.0130632 0.885061 + outer loop + vertex 875.68 468.558 361.633 + vertex 875.16 472.108 361.959 + vertex 875.105 468.303 361.931 + endloop + endfacet + facet normal 0.242098 0.100672 0.965015 + outer loop + vertex 875.65 467.239 361.778 + vertex 876.35 465.843 361.748 + vertex 875.68 468.558 361.633 + endloop + endfacet + facet normal 0.357609 0.13532 0.924015 + outer loop + vertex 877.33 463.731 361.678 + vertex 876.692 466.47 361.524 + vertex 876.35 465.843 361.748 + endloop + endfacet + facet normal 0.366515 0.129519 0.921353 + outer loop + vertex 876.692 466.47 361.524 + vertex 875.68 468.558 361.633 + vertex 876.35 465.843 361.748 + endloop + endfacet + facet normal 0.497637 0.154891 0.853444 + outer loop + vertex 878.35 462.791 361.307 + vertex 878.363 463.44 361.182 + vertex 878.175 464.117 361.168 + endloop + endfacet + facet normal 0.638814 0.168063 0.75078 + outer loop + vertex 878.381 463.565 361.138 + vertex 878.279 464.036 361.119 + vertex 878.363 463.44 361.182 + endloop + endfacet + facet normal 0.518906 0.16052 0.839625 + outer loop + vertex 878.279 464.036 361.119 + vertex 878.175 464.117 361.168 + vertex 878.363 463.44 361.182 + endloop + endfacet + facet normal 0.774986 0.181617 0.605319 + outer loop + vertex 878.772 461.528 361.248 + vertex 878.302 464.302 361.019 + vertex 878.381 463.565 361.138 + endloop + endfacet + facet normal 0.750126 0.117996 -0.650682 + outer loop + vertex 879.564 457.463 361.424 + vertex 878.772 461.528 361.248 + vertex 879.492 457.873 361.414 + endloop + endfacet + facet normal -0.398544 -0.110166 -0.910509 + outer loop + vertex 880.045 455.099 361.499 + vertex 879.564 457.463 361.424 + vertex 880.155 454.673 361.503 + endloop + endfacet + facet normal -0.244171 -0.0708044 -0.967144 + outer loop + vertex 880.715 452.124 361.548 + vertex 880.045 455.099 361.499 + vertex 880.155 454.673 361.503 + endloop + endfacet + facet normal 0.445029 0.113541 0.888289 + outer loop + vertex 881.661 448.138 361.583 + vertex 880.715 452.124 361.548 + vertex 881.445 448.643 361.627 + endloop + endfacet + facet normal 0.45159 0.116674 0.884564 + outer loop + vertex 882.521 444.667 361.602 + vertex 881.661 448.138 361.583 + vertex 881.445 448.643 361.627 + endloop + endfacet + facet normal 0.386586 0.0985744 0.91697 + outer loop + vertex 888.172 423.032 361.59 + vertex 886.966 427.763 361.59 + vertex 887.452 425.21 361.66 + endloop + endfacet + facet normal 0.39281 0.0935302 0.914851 + outer loop + vertex 889.019 419.627 361.575 + vertex 888.172 423.032 361.59 + vertex 889.091 418.633 361.646 + endloop + endfacet + facet normal 0.417907 0.0945483 0.903556 + outer loop + vertex 890.108 414.707 361.586 + vertex 889.019 419.627 361.575 + vertex 889.091 418.633 361.646 + endloop + endfacet + facet normal 0.404804 0.0835039 0.910582 + outer loop + vertex 891.319 408.773 361.592 + vertex 890.108 414.707 361.586 + vertex 890.591 411.452 361.67 + endloop + endfacet + facet normal 0.356495 0.064782 0.932049 + outer loop + vertex 892.207 404.024 361.582 + vertex 891.319 408.773 361.592 + vertex 892.021 403.836 361.666 + endloop + endfacet + facet normal 0.362922 0.0575386 0.930041 + outer loop + vertex 892.982 399.065 361.587 + vertex 892.207 404.024 361.582 + vertex 892.021 403.836 361.666 + endloop + endfacet + facet normal 0.349814 0.0455511 0.935711 + outer loop + vertex 893.777 392.96 361.587 + vertex 892.982 399.065 361.587 + vertex 893.14 395.86 361.684 + endloop + endfacet + facet normal 0.275111 0.0267681 0.96104 + outer loop + vertex 894.265 388.047 361.584 + vertex 893.777 392.96 361.587 + vertex 893.991 387.866 361.667 + endloop + endfacet + facet normal 0.281642 0.0160943 0.959384 + outer loop + vertex 894.52 382.908 361.595 + vertex 894.265 388.047 361.584 + vertex 893.991 387.866 361.667 + endloop + endfacet + facet normal 0.274611 0.00259671 0.961552 + outer loop + vertex 894.598 376.495 361.59 + vertex 894.52 382.908 361.595 + vertex 894.268 379.902 361.675 + endloop + endfacet + facet normal 0.212854 -0.00929297 0.97704 + outer loop + vertex 894.444 371.166 361.573 + vertex 894.598 376.495 361.59 + vertex 894.084 371.882 361.658 + endloop + endfacet + facet normal 0.200622 -0.0157582 0.979542 + outer loop + vertex 894.093 367.242 361.582 + vertex 894.444 371.166 361.573 + vertex 894.084 371.882 361.658 + endloop + endfacet + facet normal 0.217723 -0.0307003 0.975528 + outer loop + vertex 893.366 361.968 361.578 + vertex 894.093 367.242 361.582 + vertex 893.358 364.248 361.652 + endloop + endfacet + facet normal 0.169585 -0.0329114 0.984966 + outer loop + vertex 892.382 356.807 361.575 + vertex 893.366 361.968 361.578 + vertex 891.913 356.788 361.655 + endloop + endfacet + facet normal 0.169895 -0.0423957 0.98455 + outer loop + vertex 890.992 351.404 361.582 + vertex 892.382 356.807 361.575 + vertex 891.913 356.788 361.655 + endloop + endfacet + facet normal 0.168312 -0.0517708 0.984373 + outer loop + vertex 889.106 345.123 361.575 + vertex 890.992 351.404 361.582 + vertex 889.684 348.895 361.674 + endloop + endfacet + facet normal 0.144803 -0.0499651 0.988198 + outer loop + vertex 887.931 341.493 361.563 + vertex 889.106 345.123 361.575 + vertex 887.522 341.792 361.638 + endloop + endfacet + facet normal 0.140208 -0.0563319 0.988518 + outer loop + vertex 886.872 338.958 361.569 + vertex 887.931 341.493 361.563 + vertex 887.522 341.792 361.638 + endloop + endfacet + facet normal 0.966441 0.0343268 0.254586 + outer loop + vertex 875.32 470.342 361.591 + vertex 875.163 472.235 361.932 + vertex 875.16 472.108 361.959 + endloop + endfacet + facet normal 0.441946 0.110152 0.890253 + outer loop + vertex 876.243 467.965 361.427 + vertex 875.32 470.342 361.591 + vertex 875.68 468.558 361.633 + endloop + endfacet + facet normal 0.550048 0.217471 0.806321 + outer loop + vertex 877.568 465.352 361.228 + vertex 876.243 467.965 361.427 + vertex 876.692 466.47 361.524 + endloop + endfacet + facet normal 0.570947 0.242629 0.784315 + outer loop + vertex 878.302 464.302 361.019 + vertex 877.568 465.352 361.228 + vertex 878.175 464.117 361.168 + endloop + endfacet + facet normal 0.98852 -0.0120009 -0.150615 + outer loop + vertex 875.158 471.98 361.985 + vertex 875.207 467.441 362.668 + vertex 875.105 468.303 361.931 + endloop + endfacet + facet normal 0.139646 -0.0474974 0.989062 + outer loop + vertex 889.684 348.895 361.674 + vertex 887.522 341.792 361.638 + vertex 889.106 345.123 361.575 + endloop + endfacet + facet normal 0.141476 -0.037603 0.989227 + outer loop + vertex 891.913 356.788 361.655 + vertex 889.684 348.895 361.674 + vertex 890.992 351.404 361.582 + endloop + endfacet + facet normal 0.1636 -0.0312169 0.986033 + outer loop + vertex 893.358 364.248 361.652 + vertex 891.913 356.788 361.655 + vertex 893.366 361.968 361.578 + endloop + endfacet + facet normal 0.158843 -0.01597 0.987175 + outer loop + vertex 894.084 371.882 361.658 + vertex 893.358 364.248 361.652 + vertex 894.093 367.242 361.582 + endloop + endfacet + facet normal 0.187365 -0.00637367 0.98227 + outer loop + vertex 894.268 379.902 361.675 + vertex 894.084 371.882 361.658 + vertex 894.598 376.495 361.59 + endloop + endfacet + facet normal 0.211399 0.00832836 0.977364 + outer loop + vertex 893.991 387.866 361.667 + vertex 894.268 379.902 361.675 + vertex 894.52 382.908 361.595 + endloop + endfacet + facet normal 0.267052 0.0264656 0.963319 + outer loop + vertex 893.14 395.86 361.684 + vertex 893.991 387.866 361.667 + vertex 893.777 392.96 361.587 + endloop + endfacet + facet normal 0.294692 0.043395 0.954606 + outer loop + vertex 892.021 403.836 361.666 + vertex 893.14 395.86 361.684 + vertex 892.982 399.065 361.587 + endloop + endfacet + facet normal 0.322684 0.0601648 0.944593 + outer loop + vertex 890.591 411.452 361.67 + vertex 892.021 403.836 361.666 + vertex 891.319 408.773 361.592 + endloop + endfacet + facet normal 0.345961 0.0754233 0.935212 + outer loop + vertex 889.091 418.633 361.646 + vertex 890.591 411.452 361.67 + vertex 890.108 414.707 361.586 + endloop + endfacet + facet normal 0.341879 0.0831636 0.936057 + outer loop + vertex 887.452 425.21 361.66 + vertex 889.091 418.633 361.646 + vertex 888.172 423.032 361.59 + endloop + endfacet + facet normal 0.370696 0.0957411 0.923806 + outer loop + vertex 885.609 432.341 361.661 + vertex 887.452 425.21 361.66 + vertex 886.966 427.763 361.59 + endloop + endfacet + facet normal 0.442538 0.114194 0.889449 + outer loop + vertex 881.445 448.643 361.627 + vertex 883.538 440.278 361.66 + vertex 882.521 444.667 361.602 + endloop + endfacet + facet normal 0.444998 0.113535 0.888306 + outer loop + vertex 880.155 454.673 361.503 + vertex 881.445 448.643 361.627 + vertex 880.715 452.124 361.548 + endloop + endfacet + facet normal 0.406942 0.0968964 0.9083 + outer loop + vertex 880.372 450.863 361.819 + vertex 879.363 457.134 361.601 + vertex 879.139 455.777 361.846 + endloop + endfacet + facet normal 0.416973 0.0985677 0.903558 + outer loop + vertex 875.166 464.876 362.277 + vertex 875.802 464.595 362.014 + vertex 875.105 468.303 361.931 + endloop + endfacet + facet normal 0.991243 0.0042295 -0.131986 + outer loop + vertex 875.207 467.441 362.668 + vertex 875.166 464.876 362.277 + vertex 875.105 468.303 361.931 + endloop + endfacet + facet normal 0.309617 0.111977 0.944245 + outer loop + vertex 876.893 462.435 361.975 + vertex 877.751 460.604 361.911 + vertex 877.33 463.731 361.678 + endloop + endfacet + facet normal 0.236872 0.102113 0.96616 + outer loop + vertex 875.802 464.595 362.014 + vertex 876.893 462.435 361.975 + vertex 876.35 465.843 361.748 + endloop + endfacet + facet normal 0.38387 0.102394 0.917692 + outer loop + vertex 878.382 460.566 361.629 + vertex 879.139 455.777 361.846 + vertex 879.363 457.134 361.601 + endloop + endfacet + facet normal 0.41116 0.122607 0.90328 + outer loop + vertex 877.751 460.604 361.911 + vertex 878.382 460.566 361.629 + vertex 877.33 463.731 361.678 + endloop + endfacet + facet normal 0.153407 0.00450484 -0.988153 + outer loop + vertex 879.492 457.873 361.414 + vertex 880.155 454.673 361.503 + vertex 879.564 457.463 361.424 + endloop + endfacet + facet normal 0.694629 0.168444 0.69937 + outer loop + vertex 879.263 458.769 361.426 + vertex 879.492 457.873 361.414 + vertex 878.772 461.528 361.248 + endloop + endfacet + facet normal 0.436997 0.117788 0.891717 + outer loop + vertex 879.363 457.134 361.601 + vertex 878.819 460.465 361.428 + vertex 878.382 460.566 361.629 + endloop + endfacet + facet normal 0.608751 0.158198 0.777429 + outer loop + vertex 878.819 460.465 361.428 + vertex 879.263 458.769 361.426 + vertex 878.772 461.528 361.248 + endloop + endfacet + facet normal 0.887987 0.169283 -0.427577 + outer loop + vertex 875.16 472.108 361.959 + vertex 875.68 468.558 361.633 + vertex 875.32 470.342 361.591 + endloop + endfacet + facet normal 0.454059 0.105115 0.884749 + outer loop + vertex 875.65 467.239 361.778 + vertex 875.105 468.303 361.931 + vertex 875.802 464.595 362.014 + endloop + endfacet + facet normal 0.241011 0.10012 0.965344 + outer loop + vertex 876.35 465.843 361.748 + vertex 875.65 467.239 361.778 + vertex 875.802 464.595 362.014 + endloop + endfacet + facet normal 0.524226 0.210942 0.82504 + outer loop + vertex 875.68 468.558 361.633 + vertex 876.692 466.47 361.524 + vertex 876.243 467.965 361.427 + endloop + endfacet + facet normal 0.496994 0.163744 0.852165 + outer loop + vertex 876.692 466.47 361.524 + vertex 877.33 463.731 361.678 + vertex 877.568 465.352 361.228 + endloop + endfacet + facet normal 0.309143 0.112167 0.944377 + outer loop + vertex 877.33 463.731 361.678 + vertex 876.35 465.843 361.748 + vertex 876.893 462.435 361.975 + endloop + endfacet + facet normal 0.554008 0.147247 0.819386 + outer loop + vertex 878.363 463.44 361.182 + vertex 878.35 462.791 361.307 + vertex 878.772 461.528 361.248 + endloop + endfacet + facet normal 0.386989 0.146196 0.910421 + outer loop + vertex 878.35 462.791 361.307 + vertex 878.175 464.117 361.168 + vertex 877.568 465.352 361.228 + endloop + endfacet + facet normal 0.563812 0.249845 0.787206 + outer loop + vertex 878.175 464.117 361.168 + vertex 878.279 464.036 361.119 + vertex 878.302 464.302 361.019 + endloop + endfacet + facet normal 0.733919 0.184957 0.653569 + outer loop + vertex 878.279 464.036 361.119 + vertex 878.381 463.565 361.138 + vertex 878.302 464.302 361.019 + endloop + endfacet + facet normal 0.647085 0.164597 0.744439 + outer loop + vertex 878.381 463.565 361.138 + vertex 878.363 463.44 361.182 + vertex 878.772 461.528 361.248 + endloop + endfacet + facet normal 0.515482 0.158248 0.842161 + outer loop + vertex 877.33 463.731 361.678 + vertex 878.382 460.566 361.629 + vertex 877.568 465.352 361.228 + endloop + endfacet + facet normal 0.43934 0.13493 0.88813 + outer loop + vertex 878.382 460.566 361.629 + vertex 878.819 460.465 361.428 + vertex 878.35 462.791 361.307 + endloop + endfacet + facet normal 0.588179 0.159907 0.792764 + outer loop + vertex 878.819 460.465 361.428 + vertex 878.772 461.528 361.248 + vertex 878.35 462.791 361.307 + endloop + endfacet + facet normal 0.361351 0.138724 0.922053 + outer loop + vertex 878.35 462.791 361.307 + vertex 877.568 465.352 361.228 + vertex 878.382 460.566 361.629 + endloop + endfacet +endsolid diff --git a/noether_examples/meshes/outputs/output_3.stl b/noether_examples/meshes/outputs/output_3.stl new file mode 100644 index 00000000..40ffe906 --- /dev/null +++ b/noether_examples/meshes/outputs/output_3.stl @@ -0,0 +1,6477 @@ +solid ascii + facet normal 0.164061 -0.319231 -0.933368 + outer loop + vertex -838.898 238.012 299.082 + vertex -834.993 238.137 299.725 + vertex -836.438 235.18 300.482 + endloop + endfacet + facet normal 0.145807 -0.311729 -0.938917 + outer loop + vertex -834.993 238.137 299.725 + vertex -832.826 235.594 300.906 + vertex -836.438 235.18 300.482 + endloop + endfacet + facet normal 0.14233 -0.266691 -0.953215 + outer loop + vertex -836.438 235.18 300.482 + vertex -832.826 235.594 300.906 + vertex -833.869 232.451 301.63 + endloop + endfacet + facet normal 0.129255 -0.263014 -0.956095 + outer loop + vertex -832.826 235.594 300.906 + vertex -830.44 232.999 301.943 + vertex -833.869 232.451 301.63 + endloop + endfacet + facet normal 0.123732 -0.222174 -0.967124 + outer loop + vertex -833.869 232.451 301.63 + vertex -830.44 232.999 301.943 + vertex -831.452 229.725 302.565 + endloop + endfacet + facet normal 0.105998 -0.217302 -0.970332 + outer loop + vertex -830.44 232.999 301.943 + vertex -827.9 230.015 302.888 + vertex -831.452 229.725 302.565 + endloop + endfacet + facet normal 0.104176 -0.18793 -0.976642 + outer loop + vertex -831.452 229.725 302.565 + vertex -827.9 230.015 302.888 + vertex -828.854 226.694 303.426 + endloop + endfacet + facet normal 0.0884235 -0.183788 -0.978981 + outer loop + vertex -827.9 230.015 302.888 + vertex -825.42 226.89 303.699 + vertex -828.854 226.694 303.426 + endloop + endfacet + facet normal 0.0874955 -0.162105 -0.982887 + outer loop + vertex -828.854 226.694 303.426 + vertex -825.42 226.89 303.699 + vertex -825.374 223.387 304.281 + endloop + endfacet + facet normal 0.101088 -0.16172 -0.981645 + outer loop + vertex -825.42 226.89 303.699 + vertex -820.246 225.284 304.496 + vertex -825.374 223.387 304.281 + endloop + endfacet + facet normal 0.0846508 -0.11638 -0.989591 + outer loop + vertex -820.246 225.284 304.496 + vertex -820.546 218.151 305.31 + vertex -825.374 223.387 304.281 + endloop + endfacet + facet normal 0.061983 -0.115627 -0.991357 + outer loop + vertex -820.246 225.284 304.496 + vertex -814.124 219.575 305.545 + vertex -820.546 218.151 305.31 + endloop + endfacet + facet normal 0.0545701 -0.0815601 -0.995173 + outer loop + vertex -820.546 218.151 305.31 + vertex -814.124 219.575 305.545 + vertex -813.698 212.836 306.121 + endloop + endfacet + facet normal 0.0372388 -0.082715 -0.995877 + outer loop + vertex -814.124 219.575 305.545 + vertex -808.139 214.299 306.207 + vertex -813.698 212.836 306.121 + endloop + endfacet + facet normal 0.0324665 -0.0644899 -0.99739 + outer loop + vertex -813.698 212.836 306.121 + vertex -808.139 214.299 306.207 + vertex -807.942 207.852 306.63 + endloop + endfacet + facet normal 0.0110099 -0.0651762 -0.997813 + outer loop + vertex -808.139 214.299 306.207 + vertex -802.24 209.41 306.591 + vertex -807.942 207.852 306.63 + endloop + endfacet + facet normal 0.00829439 -0.0552509 -0.998438 + outer loop + vertex -807.942 207.852 306.63 + vertex -802.24 209.41 306.591 + vertex -802.096 202.674 306.965 + endloop + endfacet + facet normal -0.00973426 -0.0556362 -0.998404 + outer loop + vertex -802.24 209.41 306.591 + vertex -796.117 204.82 306.788 + vertex -802.096 202.674 306.965 + endloop + endfacet + facet normal -0.012372 -0.0483149 -0.998756 + outer loop + vertex -802.096 202.674 306.965 + vertex -796.117 204.82 306.788 + vertex -795.736 198.415 307.093 + endloop + endfacet + facet normal -0.0200252 -0.0487626 -0.99861 + outer loop + vertex -796.117 204.82 306.788 + vertex -789.729 200.36 306.877 + vertex -795.736 198.415 307.093 + endloop + endfacet + facet normal -0.0206929 -0.0467103 -0.998694 + outer loop + vertex -795.736 198.415 307.093 + vertex -789.729 200.36 306.877 + vertex -789.373 193.577 307.187 + endloop + endfacet + facet normal -0.0333068 -0.0632745 -0.99744 + outer loop + vertex -795.736 198.415 307.093 + vertex -789.373 193.577 307.187 + vertex -794.539 194.743 307.286 + endloop + endfacet + facet normal -0.0279177 -0.0615319 -0.997715 + outer loop + vertex -794.539 194.743 307.286 + vertex -799.253 197.958 307.219 + vertex -795.736 198.415 307.093 + endloop + endfacet + facet normal -0.0268202 -0.0698386 -0.997198 + outer loop + vertex -802.096 202.674 306.965 + vertex -795.736 198.415 307.093 + vertex -799.253 197.958 307.219 + endloop + endfacet + facet normal -0.026176 -0.0694527 -0.997242 + outer loop + vertex -799.253 197.958 307.219 + vertex -803.077 200.583 307.137 + vertex -802.096 202.674 306.965 + endloop + endfacet + facet normal -0.0130059 -0.0756152 -0.997052 + outer loop + vertex -803.077 200.583 307.137 + vertex -806.511 203.529 306.958 + vertex -802.096 202.674 306.965 + endloop + endfacet + facet normal -0.0138915 -0.0801861 -0.996683 + outer loop + vertex -807.942 207.852 306.63 + vertex -802.096 202.674 306.965 + vertex -806.511 203.529 306.958 + endloop + endfacet + facet normal -0.0436932 -0.0846197 -0.995455 + outer loop + vertex -799.253 197.958 307.219 + vertex -794.539 194.743 307.286 + vertex -794.487 193.681 307.374 + endloop + endfacet + facet normal -0.0498843 -0.0848952 -0.99514 + outer loop + vertex -794.539 194.743 307.286 + vertex -790.787 191.625 307.364 + vertex -794.487 193.681 307.374 + endloop + endfacet + facet normal -0.0554511 -0.0949205 -0.993939 + outer loop + vertex -787.031 188.559 307.447 + vertex -794.487 193.681 307.374 + vertex -790.787 191.625 307.364 + endloop + endfacet + facet normal -0.117937 -0.185618 -0.975519 + outer loop + vertex -788.256 189.074 307.497 + vertex -794.487 193.681 307.374 + vertex -787.031 188.559 307.447 + endloop + endfacet + facet normal -0.120405 -0.191629 -0.974054 + outer loop + vertex -788.256 189.074 307.497 + vertex -787.031 188.559 307.447 + vertex -780.582 184.126 307.522 + endloop + endfacet + facet normal -0.0766338 -0.123827 -0.98934 + outer loop + vertex -780.89 183.509 307.623 + vertex -788.256 189.074 307.497 + vertex -780.582 184.126 307.522 + endloop + endfacet + facet normal -0.0771567 -0.123564 -0.989332 + outer loop + vertex -780.89 183.509 307.623 + vertex -780.582 184.126 307.522 + vertex -772.978 178.707 307.606 + endloop + endfacet + facet normal -0.0729764 -0.116672 -0.990486 + outer loop + vertex -772.943 177.046 307.799 + vertex -780.89 183.509 307.623 + vertex -772.978 178.707 307.606 + endloop + endfacet + facet normal -0.0747229 -0.116694 -0.990353 + outer loop + vertex -772.943 177.046 307.799 + vertex -772.978 178.707 307.606 + vertex -764.817 172.414 307.731 + endloop + endfacet + facet normal -0.0934268 -0.149589 -0.984324 + outer loop + vertex -764.844 170.207 308.069 + vertex -772.943 177.046 307.799 + vertex -764.817 172.414 307.731 + endloop + endfacet + facet normal -0.0955202 -0.149534 -0.984132 + outer loop + vertex -764.844 170.207 308.069 + vertex -764.817 172.414 307.731 + vertex -756.545 165.74 307.942 + endloop + endfacet + facet normal -0.104135 -0.160132 -0.981587 + outer loop + vertex -756.545 165.74 307.942 + vertex -764.817 172.414 307.731 + vertex -756.551 167.958 307.581 + endloop + endfacet + facet normal -0.108651 -0.160066 -0.981108 + outer loop + vertex -756.545 165.74 307.942 + vertex -756.551 167.958 307.581 + vertex -748.11 161.424 307.713 + endloop + endfacet + facet normal -0.122396 -0.177726 -0.976439 + outer loop + vertex -748.11 161.424 307.713 + vertex -756.551 167.958 307.581 + vertex -748.131 163.648 307.31 + endloop + endfacet + facet normal -0.127517 -0.17766 -0.975795 + outer loop + vertex -748.11 161.424 307.713 + vertex -748.131 163.648 307.31 + vertex -739.47 157.176 307.357 + endloop + endfacet + facet normal -0.147441 -0.204267 -0.967748 + outer loop + vertex -739.47 157.176 307.357 + vertex -748.131 163.648 307.31 + vertex -739.481 159.387 306.892 + endloop + endfacet + facet normal -0.151725 -0.204155 -0.967109 + outer loop + vertex -739.47 157.176 307.357 + vertex -739.481 159.387 306.892 + vertex -730.541 152.905 306.858 + endloop + endfacet + facet normal -0.181759 -0.245656 -0.952164 + outer loop + vertex -730.541 152.905 306.858 + vertex -739.481 159.387 306.892 + vertex -730.523 155.092 306.29 + endloop + endfacet + facet normal -0.184091 -0.245529 -0.951749 + outer loop + vertex -730.541 152.905 306.858 + vertex -730.523 155.092 306.29 + vertex -721.468 148.643 306.202 + endloop + endfacet + facet normal -0.0837997 -0.122152 -0.988967 + outer loop + vertex -764.817 172.414 307.731 + vertex -764.898 174.085 307.532 + vertex -756.551 167.958 307.581 + endloop + endfacet + facet normal -0.0908371 -0.131726 -0.987115 + outer loop + vertex -756.551 167.958 307.581 + vertex -764.898 174.085 307.532 + vertex -756.655 169.625 307.368 + endloop + endfacet + facet normal -0.0993781 -0.132148 -0.986236 + outer loop + vertex -756.551 167.958 307.581 + vertex -756.655 169.625 307.368 + vertex -748.131 163.648 307.31 + endloop + endfacet + facet normal -0.108625 -0.145363 -0.983397 + outer loop + vertex -748.131 163.648 307.31 + vertex -756.655 169.625 307.368 + vertex -748.24 165.313 307.076 + endloop + endfacet + facet normal -0.119367 -0.145875 -0.982075 + outer loop + vertex -748.131 163.648 307.31 + vertex -748.24 165.313 307.076 + vertex -739.481 159.387 306.892 + endloop + endfacet + facet normal -0.137082 -0.172264 -0.975466 + outer loop + vertex -739.481 159.387 306.892 + vertex -748.24 165.313 307.076 + vertex -739.58 161.051 306.612 + endloop + endfacet + facet normal -0.148206 -0.172639 -0.973771 + outer loop + vertex -739.481 159.387 306.892 + vertex -739.58 161.051 306.612 + vertex -730.523 155.092 306.29 + endloop + endfacet + facet normal -0.181592 -0.224262 -0.957461 + outer loop + vertex -730.523 155.092 306.29 + vertex -739.58 161.051 306.612 + vertex -730.601 156.769 305.912 + endloop + endfacet + facet normal -0.192794 -0.224287 -0.955262 + outer loop + vertex -730.523 155.092 306.29 + vertex -730.601 156.769 305.912 + vertex -721.362 150.795 305.45 + endloop + endfacet + facet normal -0.116268 -0.128949 -0.984812 + outer loop + vertex -748.24 165.313 307.076 + vertex -747.853 165.9 306.954 + vertex -739.58 161.051 306.612 + endloop + endfacet + facet normal -0.136945 -0.164799 -0.976774 + outer loop + vertex -739.58 161.051 306.612 + vertex -747.853 165.9 306.954 + vertex -739.213 161.71 306.449 + endloop + endfacet + facet normal -0.150887 -0.156853 -0.976028 + outer loop + vertex -739.58 161.051 306.612 + vertex -739.213 161.71 306.449 + vertex -730.601 156.769 305.912 + endloop + endfacet + facet normal -0.196416 -0.238922 -0.950966 + outer loop + vertex -730.601 156.769 305.912 + vertex -739.213 161.71 306.449 + vertex -730.177 157.464 305.65 + endloop + endfacet + facet normal -0.212247 -0.228902 -0.950029 + outer loop + vertex -730.601 156.769 305.912 + vertex -730.177 157.464 305.65 + vertex -721.298 152.46 304.872 + endloop + endfacet + facet normal -0.12747 -0.085189 -0.988177 + outer loop + vertex -739.213 161.71 306.449 + vertex -737.833 161.525 306.287 + vertex -730.177 157.464 305.65 + endloop + endfacet + facet normal -0.194678 -0.216875 -0.956591 + outer loop + vertex -730.177 157.464 305.65 + vertex -737.833 161.525 306.287 + vertex -728.585 157.163 305.394 + endloop + endfacet + facet normal -0.1786 -0.114387 -0.97725 + outer loop + vertex -730.177 157.464 305.65 + vertex -728.585 157.163 305.394 + vertex -720.711 153.219 304.417 + endloop + endfacet + facet normal -0.135379 -0.151942 -0.979074 + outer loop + vertex -739.213 161.71 306.449 + vertex -746.317 165.493 306.845 + vertex -737.833 161.525 306.287 + endloop + endfacet + facet normal -0.085981 -0.0575437 -0.994634 + outer loop + vertex -747.853 165.9 306.954 + vertex -746.317 165.493 306.845 + vertex -739.213 161.71 306.449 + endloop + endfacet + facet normal -0.105165 -0.132403 -0.985601 + outer loop + vertex -747.853 165.9 306.954 + vertex -754.763 169.733 307.176 + vertex -746.317 165.493 306.845 + endloop + endfacet + facet normal -0.0791978 -0.0851566 -0.993215 + outer loop + vertex -756.393 170.247 307.262 + vertex -754.763 169.733 307.176 + vertex -747.853 165.9 306.954 + endloop + endfacet + facet normal -0.0979929 -0.146236 -0.984384 + outer loop + vertex -756.393 170.247 307.262 + vertex -763.793 174.511 307.365 + vertex -754.763 169.733 307.176 + endloop + endfacet + facet normal -0.111149 -0.169194 -0.979295 + outer loop + vertex -764.671 174.714 307.43 + vertex -763.793 174.511 307.365 + vertex -756.393 170.247 307.262 + endloop + endfacet + facet normal -0.0905363 -0.130688 -0.987281 + outer loop + vertex -756.655 169.625 307.368 + vertex -764.671 174.714 307.43 + vertex -756.393 170.247 307.262 + endloop + endfacet + facet normal -0.114543 -0.184929 -0.976054 + outer loop + vertex -764.671 174.714 307.43 + vertex -771.413 178.812 307.445 + vertex -763.793 174.511 307.365 + endloop + endfacet + facet normal -0.067443 -0.101187 -0.992579 + outer loop + vertex -763.793 174.511 307.365 + vertex -771.413 178.812 307.445 + vertex -769.661 178.282 307.38 + endloop + endfacet + facet normal -0.0541479 -0.0804915 -0.995283 + outer loop + vertex -769.661 178.282 307.38 + vertex -765.642 176.514 307.304 + vertex -763.793 174.511 307.365 + endloop + endfacet + facet normal -0.0479521 -0.066347 -0.996644 + outer loop + vertex -765.642 176.514 307.304 + vertex -769.661 178.282 307.38 + vertex -769.368 180.958 307.187 + endloop + endfacet + facet normal -0.0496502 -0.0677665 -0.996465 + outer loop + vertex -769.368 180.958 307.187 + vertex -762.197 177.526 307.063 + vertex -765.642 176.514 307.304 + endloop + endfacet + facet normal -0.0503429 -0.065435 -0.996586 + outer loop + vertex -760.072 173.417 307.226 + vertex -765.642 176.514 307.304 + vertex -762.197 177.526 307.063 + endloop + endfacet + facet normal -0.0622831 -0.0715648 -0.995489 + outer loop + vertex -762.197 177.526 307.063 + vertex -755.694 174.134 306.9 + vertex -760.072 173.417 307.226 + endloop + endfacet + facet normal -0.0620954 -0.0726788 -0.99542 + outer loop + vertex -754.527 170.669 307.081 + vertex -760.072 173.417 307.226 + vertex -755.694 174.134 306.9 + endloop + endfacet + facet normal -0.0804918 -0.0787806 -0.993637 + outer loop + vertex -755.694 174.134 306.9 + vertex -748.66 170.169 306.645 + vertex -754.527 170.669 307.081 + endloop + endfacet + facet normal -0.08167 -0.0938188 -0.992234 + outer loop + vertex -750.354 168.068 306.983 + vertex -754.527 170.669 307.081 + vertex -748.66 170.169 306.645 + endloop + endfacet + facet normal -0.0916089 -0.0857842 -0.992093 + outer loop + vertex -744.4 165.535 306.652 + vertex -750.354 168.068 306.983 + vertex -748.66 170.169 306.645 + endloop + endfacet + facet normal -0.110588 -0.103226 -0.988491 + outer loop + vertex -748.66 170.169 306.645 + vertex -740.856 166.721 306.132 + vertex -744.4 165.535 306.652 + endloop + endfacet + facet normal -0.0702264 -0.0604386 -0.995698 + outer loop + vertex -755.694 174.134 306.9 + vertex -749.216 177.068 306.265 + vertex -748.66 170.169 306.645 + endloop + endfacet + facet normal -0.100549 -0.0627307 -0.992953 + outer loop + vertex -749.216 177.068 306.265 + vertex -741.856 173.432 305.75 + vertex -748.66 170.169 306.645 + endloop + endfacet + facet normal -0.0965999 -0.0709213 -0.992793 + outer loop + vertex -748.66 170.169 306.645 + vertex -741.856 173.432 305.75 + vertex -740.856 166.721 306.132 + endloop + endfacet + facet normal -0.132404 -0.076 -0.988278 + outer loop + vertex -741.856 173.432 305.75 + vertex -734.315 168.981 305.082 + vertex -740.856 166.721 306.132 + endloop + endfacet + facet normal -0.126114 -0.0938811 -0.987563 + outer loop + vertex -740.856 166.721 306.132 + vertex -734.315 168.981 305.082 + vertex -734.711 163.095 305.692 + endloop + endfacet + facet normal -0.160668 -0.0910639 -0.982799 + outer loop + vertex -734.711 163.095 305.692 + vertex -734.315 168.981 305.082 + vertex -729.945 163.803 304.847 + endloop + endfacet + facet normal -0.156483 -0.116772 -0.980753 + outer loop + vertex -729.376 159.849 305.227 + vertex -734.711 163.095 305.692 + vertex -729.945 163.803 304.847 + endloop + endfacet + facet normal -0.186186 -0.120505 -0.975097 + outer loop + vertex -729.945 163.803 304.847 + vertex -725.586 161.24 304.332 + vertex -729.376 159.849 305.227 + endloop + endfacet + facet normal -0.180946 -0.134253 -0.974287 + outer loop + vertex -729.376 159.849 305.227 + vertex -725.586 161.24 304.332 + vertex -724.544 157.56 304.645 + endloop + endfacet + facet normal -0.182216 -0.137094 -0.973654 + outer loop + vertex -729.376 159.849 305.227 + vertex -724.544 157.56 304.645 + vertex -726.637 156.878 305.133 + endloop + endfacet + facet normal -0.160048 -0.116449 -0.980216 + outer loop + vertex -726.637 156.878 305.133 + vertex -733.169 159.983 305.831 + vertex -729.376 159.849 305.227 + endloop + endfacet + facet normal -0.216508 -0.143584 -0.965665 + outer loop + vertex -725.586 161.24 304.332 + vertex -721.643 159.378 303.724 + vertex -724.544 157.56 304.645 + endloop + endfacet + facet normal -0.210529 -0.153057 -0.965532 + outer loop + vertex -724.544 157.56 304.645 + vertex -721.643 159.378 303.724 + vertex -721.026 156.322 304.074 + endloop + endfacet + facet normal -0.210519 -0.153025 -0.965539 + outer loop + vertex -724.544 157.56 304.645 + vertex -721.026 156.322 304.074 + vertex -721.425 154.915 304.384 + endloop + endfacet + facet normal -0.232435 -0.145941 -0.9616 + outer loop + vertex -721.026 156.322 304.074 + vertex -717.897 154.722 303.561 + vertex -721.425 154.915 304.384 + endloop + endfacet + facet normal -0.23251 -0.150153 -0.960933 + outer loop + vertex -716.102 152.467 303.479 + vertex -721.425 154.915 304.384 + vertex -717.897 154.722 303.561 + endloop + endfacet + facet normal -0.244677 -0.172262 -0.95418 + outer loop + vertex -721.026 156.322 304.074 + vertex -718.249 157.771 303.1 + vertex -717.897 154.722 303.561 + endloop + endfacet + facet normal -0.284009 -0.175064 -0.942704 + outer loop + vertex -718.249 157.771 303.1 + vertex -714.811 156.242 302.349 + vertex -717.897 154.722 303.561 + endloop + endfacet + facet normal -0.27295 -0.196712 -0.941702 + outer loop + vertex -717.897 154.722 303.561 + vertex -714.811 156.242 302.349 + vertex -713.704 152.987 302.708 + endloop + endfacet + facet normal -0.26614 -0.177419 -0.947466 + outer loop + vertex -717.897 154.722 303.561 + vertex -713.704 152.987 302.708 + vertex -716.102 152.467 303.479 + endloop + endfacet + facet normal -0.281095 -0.1674 -0.944967 + outer loop + vertex -718.249 157.771 303.1 + vertex -715.092 160.663 301.649 + vertex -714.811 156.242 302.349 + endloop + endfacet + facet normal -0.304689 -0.140199 -0.942077 + outer loop + vertex -718.282 162.653 302.385 + vertex -715.092 160.663 301.649 + vertex -718.249 157.771 303.1 + endloop + endfacet + facet normal -0.298601 -0.129136 -0.945601 + outer loop + vertex -715.092 160.663 301.649 + vertex -718.282 162.653 302.385 + vertex -715.095 166.473 300.857 + endloop + endfacet + facet normal -0.330145 -0.100021 -0.938616 + outer loop + vertex -718.282 162.653 302.385 + vertex -718.089 170.355 301.496 + vertex -715.095 166.473 300.857 + endloop + endfacet + facet normal -0.327173 -0.0975134 -0.939919 + outer loop + vertex -714.798 172.35 300.144 + vertex -715.095 166.473 300.857 + vertex -718.089 170.355 301.496 + endloop + endfacet + facet normal -0.344568 -0.0664392 -0.936407 + outer loop + vertex -718.089 170.355 301.496 + vertex -715.736 178.177 300.075 + vertex -714.798 172.35 300.144 + endloop + endfacet + facet normal -0.333206 -0.0705479 -0.940211 + outer loop + vertex -719.12 179.001 301.213 + vertex -715.736 178.177 300.075 + vertex -718.089 170.355 301.496 + endloop + endfacet + facet normal -0.328689 -0.0478166 -0.943227 + outer loop + vertex -719.12 179.001 301.213 + vertex -716.482 185.336 299.973 + vertex -715.736 178.177 300.075 + endloop + endfacet + facet normal -0.331973 -0.0462397 -0.942155 + outer loop + vertex -719.492 188.031 300.901 + vertex -716.482 185.336 299.973 + vertex -719.12 179.001 301.213 + endloop + endfacet + facet normal -0.329388 -0.042988 -0.943215 + outer loop + vertex -716.482 185.336 299.973 + vertex -719.492 188.031 300.901 + vertex -715.001 196.177 298.961 + endloop + endfacet + facet normal -0.383659 -0.033676 -0.92286 + outer loop + vertex -716.482 185.336 299.973 + vertex -715.001 196.177 298.961 + vertex -713.42 185.873 298.68 + endloop + endfacet + facet normal -0.380459 -0.0529312 -0.923282 + outer loop + vertex -716.482 185.336 299.973 + vertex -713.42 185.873 298.68 + vertex -715.736 178.177 300.075 + endloop + endfacet + facet normal -0.383434 -0.0518241 -0.922113 + outer loop + vertex -715.736 178.177 300.075 + vertex -713.42 185.873 298.68 + vertex -712.901 177.718 298.922 + endloop + endfacet + facet normal -0.385856 -0.0728831 -0.919676 + outer loop + vertex -715.736 178.177 300.075 + vertex -712.901 177.718 298.922 + vertex -714.798 172.35 300.144 + endloop + endfacet + facet normal -0.37776 -0.0764414 -0.922743 + outer loop + vertex -714.798 172.35 300.144 + vertex -712.901 177.718 298.922 + vertex -712.481 170.974 299.309 + endloop + endfacet + facet normal -0.422086 -0.0400433 -0.905671 + outer loop + vertex -715.001 196.177 298.961 + vertex -709.874 194.834 296.631 + vertex -713.42 185.873 298.68 + endloop + endfacet + facet normal -0.421944 -0.0401136 -0.905734 + outer loop + vertex -710.907 183.805 297.601 + vertex -713.42 185.873 298.68 + vertex -709.874 194.834 296.631 + endloop + endfacet + facet normal -0.431339 -0.0542296 -0.900559 + outer loop + vertex -713.42 185.873 298.68 + vertex -710.907 183.805 297.601 + vertex -712.901 177.718 298.922 + endloop + endfacet + facet normal -0.427827 -0.0557239 -0.902141 + outer loop + vertex -712.901 177.718 298.922 + vertex -710.907 183.805 297.601 + vertex -710.317 176.908 297.747 + endloop + endfacet + facet normal -0.433049 -0.078463 -0.897949 + outer loop + vertex -712.901 177.718 298.922 + vertex -710.317 176.908 297.747 + vertex -712.481 170.974 299.309 + endloop + endfacet + facet normal -0.417158 -0.0860508 -0.904751 + outer loop + vertex -712.481 170.974 299.309 + vertex -710.317 176.908 297.747 + vertex -709.809 169.926 298.177 + endloop + endfacet + facet normal -0.424228 -0.110518 -0.898786 + outer loop + vertex -712.481 170.974 299.309 + vertex -709.809 169.926 298.177 + vertex -712.22 164.731 299.954 + endloop + endfacet + facet normal -0.395254 -0.127684 -0.909654 + outer loop + vertex -712.22 164.731 299.954 + vertex -709.809 169.926 298.177 + vertex -709.228 163.584 298.814 + endloop + endfacet + facet normal -0.402232 -0.152788 -0.902699 + outer loop + vertex -712.22 164.731 299.954 + vertex -709.228 163.584 298.814 + vertex -711.82 159.246 300.704 + endloop + endfacet + facet normal -0.368773 -0.17705 -0.912502 + outer loop + vertex -711.82 159.246 300.704 + vertex -709.228 163.584 298.814 + vertex -708.394 157.93 299.575 + endloop + endfacet + facet normal -0.375559 -0.201462 -0.904637 + outer loop + vertex -711.82 159.246 300.704 + vertex -708.394 157.93 299.575 + vertex -711.036 154.757 301.378 + endloop + endfacet + facet normal -0.351417 -0.224048 -0.909015 + outer loop + vertex -711.036 154.757 301.378 + vertex -708.394 157.93 299.575 + vertex -707.171 153.034 300.308 + endloop + endfacet + facet normal -0.359503 -0.248033 -0.899576 + outer loop + vertex -711.036 154.757 301.378 + vertex -707.171 153.034 300.308 + vertex -709.58 151.375 301.728 + endloop + endfacet + facet normal -0.346007 -0.267409 -0.899318 + outer loop + vertex -709.58 151.375 301.728 + vertex -707.171 153.034 300.308 + vertex -706.63 150.137 300.962 + endloop + endfacet + facet normal -0.346552 -0.269161 -0.898585 + outer loop + vertex -709.58 151.375 301.728 + vertex -706.63 150.137 300.962 + vertex -706.924 148.936 301.435 + endloop + endfacet + facet normal -0.36188 -0.26366 -0.894162 + outer loop + vertex -706.63 150.137 300.962 + vertex -704.387 148.563 300.518 + vertex -706.924 148.936 301.435 + endloop + endfacet + facet normal -0.362529 -0.284443 -0.887505 + outer loop + vertex -706.924 148.936 301.435 + vertex -704.387 148.563 300.518 + vertex -703.44 147.131 300.59 + endloop + endfacet + facet normal -0.323692 -0.19113 -0.926657 + outer loop + vertex -706.924 148.936 301.435 + vertex -703.44 147.131 300.59 + vertex -705.532 147.698 301.204 + endloop + endfacet + facet normal -0.314986 -0.147043 -0.937637 + outer loop + vertex -701.203 145.87 300.036 + vertex -705.532 147.698 301.204 + vertex -703.44 147.131 300.59 + endloop + endfacet + facet normal -0.395008 -0.30488 -0.866612 + outer loop + vertex -704.387 148.563 300.518 + vertex -701.839 147.398 299.766 + vertex -703.44 147.131 300.59 + endloop + endfacet + facet normal -0.394351 -0.307208 -0.866089 + outer loop + vertex -700.063 145.853 299.506 + vertex -703.44 147.131 300.59 + vertex -701.839 147.398 299.766 + endloop + endfacet + facet normal -0.396994 -0.311282 -0.863423 + outer loop + vertex -704.387 148.563 300.518 + vertex -702.654 149.399 299.42 + vertex -701.839 147.398 299.766 + endloop + endfacet + facet normal -0.430924 -0.321582 -0.843143 + outer loop + vertex -702.654 149.399 299.42 + vertex -700.819 148.68 298.756 + vertex -701.839 147.398 299.766 + endloop + endfacet + facet normal -0.422158 -0.329611 -0.844476 + outer loop + vertex -701.839 147.398 299.766 + vertex -700.819 148.68 298.756 + vertex -700.007 146.92 299.037 + endloop + endfacet + facet normal -0.423507 -0.345565 -0.837393 + outer loop + vertex -700.007 146.92 299.037 + vertex -700.063 145.853 299.506 + vertex -701.839 147.398 299.766 + endloop + endfacet + facet normal -0.442039 -0.341166 -0.829583 + outer loop + vertex -700.007 146.92 299.037 + vertex -698.498 146.168 298.542 + vertex -700.063 145.853 299.506 + endloop + endfacet + facet normal -0.435361 -0.360324 -0.825001 + outer loop + vertex -697.182 144.719 298.481 + vertex -700.063 145.853 299.506 + vertex -698.498 146.168 298.542 + endloop + endfacet + facet normal -0.444882 -0.4109 -0.795765 + outer loop + vertex -700.063 145.853 299.506 + vertex -697.182 144.719 298.481 + vertex -698.453 144.787 299.156 + endloop + endfacet + facet normal -0.402588 -0.327706 -0.854712 + outer loop + vertex -698.453 144.787 299.156 + vertex -701.203 145.87 300.036 + vertex -700.063 145.853 299.506 + endloop + endfacet + facet normal -0.401211 -0.337756 -0.85144 + outer loop + vertex -703.44 147.131 300.59 + vertex -700.063 145.853 299.506 + vertex -701.203 145.87 300.036 + endloop + endfacet + facet normal -0.443874 -0.347137 -0.826119 + outer loop + vertex -700.007 146.92 299.037 + vertex -699.327 148.182 298.142 + vertex -698.498 146.168 298.542 + endloop + endfacet + facet normal -0.45308 -0.340569 -0.823851 + outer loop + vertex -700.819 148.68 298.756 + vertex -699.327 148.182 298.142 + vertex -700.007 146.92 299.037 + endloop + endfacet + facet normal -0.449575 -0.315455 -0.835686 + outer loop + vertex -700.819 148.68 298.756 + vertex -700.374 151.187 297.57 + vertex -699.327 148.182 298.142 + endloop + endfacet + facet normal -0.457717 -0.31245 -0.832388 + outer loop + vertex -701.674 151.07 298.329 + vertex -700.374 151.187 297.57 + vertex -700.819 148.68 298.756 + endloop + endfacet + facet normal -0.42729 -0.304921 -0.851144 + outer loop + vertex -702.654 149.399 299.42 + vertex -701.674 151.07 298.329 + vertex -700.819 148.68 298.756 + endloop + endfacet + facet normal -0.441905 -0.293984 -0.847522 + outer loop + vertex -703.344 152.25 298.79 + vertex -701.674 151.07 298.329 + vertex -702.654 149.399 299.42 + endloop + endfacet + facet normal -0.404828 -0.289397 -0.867389 + outer loop + vertex -704.751 150.648 299.982 + vertex -703.344 152.25 298.79 + vertex -702.654 149.399 299.42 + endloop + endfacet + facet normal -0.417825 -0.27652 -0.865424 + outer loop + vertex -704.921 152.698 299.409 + vertex -703.344 152.25 298.79 + vertex -704.751 150.648 299.982 + endloop + endfacet + facet normal -0.392087 -0.277637 -0.877032 + outer loop + vertex -704.921 152.698 299.409 + vertex -704.751 150.648 299.982 + vertex -707.171 153.034 300.308 + endloop + endfacet + facet normal -0.39154 -0.254876 -0.884158 + outer loop + vertex -707.171 153.034 300.308 + vertex -705.017 156.26 298.424 + vertex -704.921 152.698 299.409 + endloop + endfacet + facet normal -0.415609 -0.235515 -0.878523 + outer loop + vertex -708.394 157.93 299.575 + vertex -705.017 156.26 298.424 + vertex -707.171 153.034 300.308 + endloop + endfacet + facet normal -0.404185 -0.203265 -0.891806 + outer loop + vertex -708.394 157.93 299.575 + vertex -706.295 162.635 297.551 + vertex -705.017 156.26 298.424 + endloop + endfacet + facet normal -0.43836 -0.182936 -0.879986 + outer loop + vertex -709.228 163.584 298.814 + vertex -706.295 162.635 297.551 + vertex -708.394 157.93 299.575 + endloop + endfacet + facet normal -0.43103 -0.146459 -0.890373 + outer loop + vertex -709.228 163.584 298.814 + vertex -707.16 169.178 296.893 + vertex -706.295 162.635 297.551 + endloop + endfacet + facet normal -0.461928 -0.130537 -0.877259 + outer loop + vertex -709.809 169.926 298.177 + vertex -707.16 169.178 296.893 + vertex -709.228 163.584 298.814 + endloop + endfacet + facet normal -0.455864 -0.0960217 -0.884855 + outer loop + vertex -709.809 169.926 298.177 + vertex -707.806 176.244 296.459 + vertex -707.16 169.178 296.893 + endloop + endfacet + facet normal -0.472933 -0.08838 -0.876655 + outer loop + vertex -710.317 176.908 297.747 + vertex -707.806 176.244 296.459 + vertex -709.809 169.926 298.177 + endloop + endfacet + facet normal -0.467433 -0.0568211 -0.882201 + outer loop + vertex -710.317 176.908 297.747 + vertex -708.389 184.61 296.229 + vertex -707.806 176.244 296.459 + endloop + endfacet + facet normal -0.463026 -0.0583616 -0.884421 + outer loop + vertex -710.907 183.805 297.601 + vertex -708.389 184.61 296.229 + vertex -710.317 176.908 297.747 + endloop + endfacet + facet normal -0.469729 -0.0335653 -0.882172 + outer loop + vertex -710.907 183.805 297.601 + vertex -709.874 194.834 296.631 + vertex -708.389 184.61 296.229 + endloop + endfacet + facet normal -0.491152 -0.0371445 -0.870282 + outer loop + vertex -709.874 194.834 296.631 + vertex -705.959 194.055 294.455 + vertex -708.389 184.61 296.229 + endloop + endfacet + facet normal -0.497995 -0.0346708 -0.866487 + outer loop + vertex -706.282 182.773 295.092 + vertex -708.389 184.61 296.229 + vertex -705.959 194.055 294.455 + endloop + endfacet + facet normal -0.513772 -0.0593304 -0.855873 + outer loop + vertex -708.389 184.61 296.229 + vertex -706.282 182.773 295.092 + vertex -707.806 176.244 296.459 + endloop + endfacet + facet normal -0.50654 -0.0618801 -0.859993 + outer loop + vertex -707.806 176.244 296.459 + vertex -706.282 182.773 295.092 + vertex -705.59 175.821 295.185 + endloop + endfacet + facet normal -0.510344 -0.0991171 -0.854239 + outer loop + vertex -707.806 176.244 296.459 + vertex -705.59 175.821 295.185 + vertex -707.16 169.178 296.893 + endloop + endfacet + facet normal -0.495871 -0.104554 -0.862079 + outer loop + vertex -707.16 169.178 296.893 + vertex -705.59 175.821 295.185 + vertex -704.818 168.662 295.609 + endloop + endfacet + facet normal -0.500831 -0.151839 -0.852123 + outer loop + vertex -707.16 169.178 296.893 + vertex -704.818 168.662 295.609 + vertex -706.295 162.635 297.551 + endloop + endfacet + facet normal -0.469855 -0.164326 -0.867314 + outer loop + vertex -706.295 162.635 297.551 + vertex -704.818 168.662 295.609 + vertex -703.752 161.948 296.303 + endloop + endfacet + facet normal -0.476013 -0.212409 -0.853401 + outer loop + vertex -706.295 162.635 297.551 + vertex -703.752 161.948 296.303 + vertex -705.017 156.26 298.424 + endloop + endfacet + facet normal -0.447888 -0.223271 -0.865763 + outer loop + vertex -705.017 156.26 298.424 + vertex -703.752 161.948 296.303 + vertex -702.153 155.39 297.167 + endloop + endfacet + facet normal -0.487309 -0.00972656 -0.873175 + outer loop + vertex -709.874 194.834 296.631 + vertex -706.445 209.266 294.557 + vertex -705.959 194.055 294.455 + endloop + endfacet + facet normal -0.478167 -0.0126177 -0.878178 + outer loop + vertex -710.217 210.025 296.6 + vertex -706.445 209.266 294.557 + vertex -709.874 194.834 296.631 + endloop + endfacet + facet normal -0.475745 0.00318613 -0.879578 + outer loop + vertex -710.217 210.025 296.6 + vertex -706.34 223.634 294.552 + vertex -706.445 209.266 294.557 + endloop + endfacet + facet normal -0.482948 0.00583272 -0.87563 + outer loop + vertex -710.021 224.287 296.586 + vertex -706.34 223.634 294.552 + vertex -710.217 210.025 296.6 + endloop + endfacet + facet normal -0.48222 0.0110296 -0.875981 + outer loop + vertex -710.021 224.287 296.586 + vertex -705.998 237.276 294.535 + vertex -706.34 223.634 294.552 + endloop + endfacet + facet normal -0.493633 0.0155823 -0.869531 + outer loop + vertex -709.607 237.843 296.594 + vertex -705.998 237.276 294.535 + vertex -710.021 224.287 296.586 + endloop + endfacet + facet normal -0.49397 0.0128937 -0.869383 + outer loop + vertex -709.607 237.843 296.594 + vertex -705.636 250.643 294.528 + vertex -705.998 237.276 294.535 + endloop + endfacet + facet normal -0.504317 0.0170774 -0.863349 + outer loop + vertex -709.168 251.13 296.601 + vertex -705.636 250.643 294.528 + vertex -709.607 237.843 296.594 + endloop + endfacet + facet normal -0.505046 0.0104362 -0.863029 + outer loop + vertex -709.168 251.13 296.601 + vertex -705.382 264.088 294.542 + vertex -705.636 250.643 294.528 + endloop + endfacet + facet normal -0.515279 0.0144002 -0.856901 + outer loop + vertex -708.807 264.474 296.608 + vertex -705.382 264.088 294.542 + vertex -709.168 251.13 296.601 + endloop + endfacet + facet normal -0.515913 0.00722008 -0.856611 + outer loop + vertex -708.807 264.474 296.608 + vertex -705.222 277.714 294.56 + vertex -705.382 264.088 294.542 + endloop + endfacet + facet normal -0.530491 0.0125605 -0.847598 + outer loop + vertex -708.489 277.96 296.608 + vertex -705.222 277.714 294.56 + vertex -708.807 264.474 296.608 + endloop + endfacet + facet normal -0.530916 0.0053471 -0.847407 + outer loop + vertex -708.489 277.96 296.608 + vertex -705.096 291.353 294.567 + vertex -705.222 277.714 294.56 + endloop + endfacet + facet normal -0.546228 0.0107255 -0.837568 + outer loop + vertex -708.232 291.532 296.615 + vertex -705.096 291.353 294.567 + vertex -708.489 277.96 296.608 + endloop + endfacet + facet normal -0.546543 0.00355989 -0.837423 + outer loop + vertex -708.232 291.532 296.615 + vertex -704.989 304.881 294.555 + vertex -705.096 291.353 294.567 + endloop + endfacet + facet normal -0.566441 0.0104612 -0.824036 + outer loop + vertex -707.965 305.107 296.603 + vertex -704.989 304.881 294.555 + vertex -708.232 291.532 296.615 + endloop + endfacet + facet normal -0.5669 0.0021388 -0.823784 + outer loop + vertex -707.965 305.107 296.603 + vertex -704.89 318.331 294.522 + vertex -704.989 304.881 294.555 + endloop + endfacet + facet normal -0.586692 0.00894693 -0.809761 + outer loop + vertex -707.729 318.623 296.582 + vertex -704.89 318.331 294.522 + vertex -707.965 305.107 296.603 + endloop + endfacet + facet normal -0.587208 0.00164235 -0.809434 + outer loop + vertex -707.729 318.623 296.582 + vertex -704.801 331.776 294.484 + vertex -704.89 318.331 294.522 + endloop + endfacet + facet normal -0.608976 0.0090876 -0.793137 + outer loop + vertex -707.486 332.058 296.549 + vertex -704.801 331.776 294.484 + vertex -707.729 318.623 296.582 + endloop + endfacet + facet normal -0.609445 0.00232414 -0.792825 + outer loop + vertex -707.486 332.058 296.549 + vertex -704.783 345.232 294.51 + vertex -704.801 331.776 294.484 + endloop + endfacet + facet normal -0.629512 0.00890048 -0.77694 + outer loop + vertex -707.291 345.434 296.545 + vertex -704.783 345.232 294.51 + vertex -707.486 332.058 296.549 + endloop + endfacet + facet normal -0.629777 0.00386473 -0.776767 + outer loop + vertex -707.291 345.434 296.545 + vertex -704.796 358.789 294.588 + vertex -704.783 345.232 294.51 + endloop + endfacet + facet normal -0.648356 0.00960531 -0.761277 + outer loop + vertex -707.147 358.856 296.591 + vertex -704.796 358.789 294.588 + vertex -707.291 345.434 296.545 + endloop + endfacet + facet normal -0.64861 -0.00422149 -0.76111 + outer loop + vertex -707.147 358.856 296.591 + vertex -704.955 372.527 294.648 + vertex -704.796 358.789 294.588 + endloop + endfacet + facet normal -0.683464 0.00579288 -0.729961 + outer loop + vertex -707.187 372.517 296.737 + vertex -704.955 372.527 294.648 + vertex -707.147 358.856 296.591 + endloop + endfacet + facet normal -0.68331 -0.0176409 -0.729915 + outer loop + vertex -707.187 372.517 296.737 + vertex -705.335 386.645 294.662 + vertex -704.955 372.527 294.648 + endloop + endfacet + facet normal -0.748963 0.000847826 -0.662611 + outer loop + vertex -707.708 386.624 297.344 + vertex -705.335 386.645 294.662 + vertex -707.187 372.517 296.737 + endloop + endfacet + facet normal -0.386123 -0.270942 -0.881759 + outer loop + vertex -706.63 150.137 300.962 + vertex -707.171 153.034 300.308 + vertex -704.751 150.648 299.982 + endloop + endfacet + facet normal -0.414531 -0.252752 -0.874231 + outer loop + vertex -704.921 152.698 299.409 + vertex -705.017 156.26 298.424 + vertex -703.344 152.25 298.79 + endloop + endfacet + facet normal -0.433622 -0.278571 -0.856954 + outer loop + vertex -701.674 151.07 298.329 + vertex -703.344 152.25 298.79 + vertex -702.153 155.39 297.167 + endloop + endfacet + facet normal -0.465498 -0.277646 -0.840371 + outer loop + vertex -701.674 151.07 298.329 + vertex -702.153 155.39 297.167 + vertex -700.374 151.187 297.57 + endloop + endfacet + facet normal -0.454241 -0.2671 -0.849896 + outer loop + vertex -705.017 156.26 298.424 + vertex -702.153 155.39 297.167 + vertex -703.344 152.25 298.79 + endloop + endfacet + facet normal -0.406666 -0.293494 -0.865149 + outer loop + vertex -704.751 150.648 299.982 + vertex -702.654 149.399 299.42 + vertex -704.387 148.563 300.518 + endloop + endfacet + facet normal -0.378601 -0.29197 -0.878302 + outer loop + vertex -704.387 148.563 300.518 + vertex -706.63 150.137 300.962 + vertex -704.751 150.648 299.982 + endloop + endfacet + facet normal -0.416162 -0.0112811 -0.909221 + outer loop + vertex -715.001 196.177 298.961 + vertex -710.217 210.025 296.6 + vertex -709.874 194.834 296.631 + endloop + endfacet + facet normal -0.418783 -0.0101723 -0.908029 + outer loop + vertex -715.187 211.121 298.879 + vertex -710.217 210.025 296.6 + vertex -715.001 196.177 298.961 + endloop + endfacet + facet normal -0.416059 0.00487898 -0.909325 + outer loop + vertex -715.187 211.121 298.879 + vertex -710.021 224.287 296.586 + vertex -710.217 210.025 296.6 + endloop + endfacet + facet normal -0.426619 0.00988356 -0.904378 + outer loop + vertex -714.873 225.143 298.884 + vertex -710.021 224.287 296.586 + vertex -715.187 211.121 298.879 + endloop + endfacet + facet normal -0.426074 0.0135375 -0.904587 + outer loop + vertex -714.873 225.143 298.884 + vertex -709.607 237.843 296.594 + vertex -710.021 224.287 296.586 + endloop + endfacet + facet normal -0.436283 0.0186673 -0.899616 + outer loop + vertex -714.346 238.496 298.906 + vertex -709.607 237.843 296.594 + vertex -714.873 225.143 298.884 + endloop + endfacet + facet normal -0.436734 0.014867 -0.899468 + outer loop + vertex -714.346 238.496 298.906 + vertex -709.168 251.13 296.601 + vertex -709.607 237.843 296.594 + endloop + endfacet + facet normal -0.445817 0.0194202 -0.894914 + outer loop + vertex -713.783 251.668 298.911 + vertex -709.168 251.13 296.601 + vertex -714.346 238.496 298.906 + endloop + endfacet + facet normal -0.446505 0.0125551 -0.894693 + outer loop + vertex -713.783 251.668 298.911 + vertex -708.807 264.474 296.608 + vertex -709.168 251.13 296.601 + endloop + endfacet + facet normal -0.457191 0.0176968 -0.889193 + outer loop + vertex -713.263 264.943 298.908 + vertex -708.807 264.474 296.608 + vertex -713.783 251.668 298.911 + endloop + endfacet + facet normal -0.457805 0.0108488 -0.888987 + outer loop + vertex -713.263 264.943 298.908 + vertex -708.489 277.96 296.608 + vertex -708.807 264.474 296.608 + endloop + endfacet + facet normal -0.471429 0.0171264 -0.881738 + outer loop + vertex -712.781 278.376 298.911 + vertex -708.489 277.96 296.608 + vertex -713.263 264.943 298.908 + endloop + endfacet + facet normal -0.472063 0.00934654 -0.881515 + outer loop + vertex -712.781 278.376 298.911 + vertex -708.232 291.532 296.615 + vertex -708.489 277.96 296.608 + endloop + endfacet + facet normal -0.488204 0.0164876 -0.872574 + outer loop + vertex -712.329 291.926 298.915 + vertex -708.232 291.532 296.615 + vertex -712.781 278.376 298.911 + endloop + endfacet + facet normal -0.488807 0.00888855 -0.872347 + outer loop + vertex -712.329 291.926 298.915 + vertex -707.965 305.107 296.603 + vertex -708.232 291.532 296.615 + endloop + endfacet + facet normal -0.506401 0.0165049 -0.86214 + outer loop + vertex -711.883 305.473 298.912 + vertex -707.965 305.107 296.603 + vertex -712.329 291.926 298.915 + endloop + endfacet + facet normal -0.507084 0.00747656 -0.861864 + outer loop + vertex -711.883 305.473 298.912 + vertex -707.729 318.623 296.582 + vertex -707.965 305.107 296.603 + endloop + endfacet + facet normal -0.526967 0.0159054 -0.849737 + outer loop + vertex -711.445 318.927 298.892 + vertex -707.729 318.623 296.582 + vertex -711.883 305.473 298.912 + endloop + endfacet + facet normal -0.527515 0.0074767 -0.849513 + outer loop + vertex -711.445 318.927 298.892 + vertex -707.486 332.058 296.549 + vertex -707.729 318.623 296.582 + endloop + endfacet + facet normal -0.548292 0.01613 -0.836132 + outer loop + vertex -711.004 332.254 298.86 + vertex -707.486 332.058 296.549 + vertex -711.445 318.927 298.892 + endloop + endfacet + facet normal -0.548676 0.00770683 -0.836 + outer loop + vertex -711.004 332.254 298.86 + vertex -707.291 345.434 296.545 + vertex -707.486 332.058 296.549 + endloop + endfacet + facet normal -0.570459 0.0164486 -0.821161 + outer loop + vertex -710.582 345.525 298.833 + vertex -707.291 345.434 296.545 + vertex -711.004 332.254 298.86 + endloop + endfacet + facet normal -0.570653 0.00897257 -0.821142 + outer loop + vertex -710.582 345.525 298.833 + vertex -707.147 358.856 296.591 + vertex -707.291 345.434 296.545 + endloop + endfacet + facet normal -0.59117 0.0167432 -0.806373 + outer loop + vertex -710.212 358.893 298.839 + vertex -707.147 358.856 296.591 + vertex -710.582 345.525 298.833 + endloop + endfacet + facet normal -0.591316 0.00688385 -0.80641 + outer loop + vertex -710.212 358.893 298.839 + vertex -707.187 372.517 296.737 + vertex -707.147 358.856 296.591 + endloop + endfacet + facet normal -0.619809 0.0165778 -0.784577 + outer loop + vertex -710.062 372.536 299.008 + vertex -707.187 372.517 296.737 + vertex -710.212 358.893 298.839 + endloop + endfacet + facet normal -0.619882 0.0108534 -0.78462 + outer loop + vertex -710.062 372.536 299.008 + vertex -707.708 386.624 297.344 + vertex -707.187 372.517 296.737 + endloop + endfacet + facet normal -0.6503 0.0189116 -0.759442 + outer loop + vertex -710.506 386.592 299.74 + vertex -707.708 386.624 297.344 + vertex -710.062 372.536 299.008 + endloop + endfacet + facet normal -0.340106 -0.03624 -0.939688 + outer loop + vertex -721.089 197.966 301.095 + vertex -715.001 196.177 298.961 + vertex -719.492 188.031 300.901 + endloop + endfacet + facet normal -0.284103 -0.0268737 -0.958417 + outer loop + vertex -722.666 188.656 301.824 + vertex -721.089 197.966 301.095 + vertex -719.492 188.031 300.901 + endloop + endfacet + facet normal -0.285407 -0.0344175 -0.957788 + outer loop + vertex -722.666 188.656 301.824 + vertex -719.492 188.031 300.901 + vertex -723.08 181.377 302.209 + endloop + endfacet + facet normal -0.268651 -0.0443234 -0.962217 + outer loop + vertex -723.08 181.377 302.209 + vertex -719.492 188.031 300.901 + vertex -719.12 179.001 301.213 + endloop + endfacet + facet normal -0.275721 -0.057232 -0.959532 + outer loop + vertex -723.08 181.377 302.209 + vertex -719.12 179.001 301.213 + vertex -722.547 172.227 302.601 + endloop + endfacet + facet normal -0.2651 -0.0631408 -0.962151 + outer loop + vertex -722.547 172.227 302.601 + vertex -719.12 179.001 301.213 + vertex -718.089 170.355 301.496 + endloop + endfacet + facet normal -0.274595 -0.0885135 -0.957477 + outer loop + vertex -722.547 172.227 302.601 + vertex -718.089 170.355 301.496 + vertex -721.901 164.763 303.106 + endloop + endfacet + facet normal -0.252777 -0.104647 -0.961849 + outer loop + vertex -721.901 164.763 303.106 + vertex -718.089 170.355 301.496 + vertex -718.282 162.653 302.385 + endloop + endfacet + facet normal -0.262222 -0.122427 -0.95721 + outer loop + vertex -721.901 164.763 303.106 + vertex -718.282 162.653 302.385 + vertex -721.643 159.378 303.724 + endloop + endfacet + facet normal -0.243702 -0.142311 -0.959352 + outer loop + vertex -721.643 159.378 303.724 + vertex -718.282 162.653 302.385 + vertex -718.249 157.771 303.1 + endloop + endfacet + facet normal -0.333277 -0.00930385 -0.942783 + outer loop + vertex -721.089 197.966 301.095 + vertex -715.187 211.121 298.879 + vertex -715.001 196.177 298.961 + endloop + endfacet + facet normal -0.346312 -0.00266945 -0.938116 + outer loop + vertex -720.942 212.861 300.999 + vertex -715.187 211.121 298.879 + vertex -721.089 197.966 301.095 + endloop + endfacet + facet normal -0.343451 0.00803535 -0.939136 + outer loop + vertex -720.942 212.861 300.999 + vertex -714.873 225.143 298.884 + vertex -715.187 211.121 298.879 + endloop + endfacet + facet normal -0.354331 0.0141219 -0.935013 + outer loop + vertex -720.445 226.494 301.016 + vertex -714.873 225.143 298.884 + vertex -720.942 212.861 300.999 + endloop + endfacet + facet normal -0.354036 0.0154819 -0.935104 + outer loop + vertex -720.445 226.494 301.016 + vertex -714.346 238.496 298.906 + vertex -714.873 225.143 298.884 + endloop + endfacet + facet normal -0.361087 0.0195529 -0.932327 + outer loop + vertex -719.771 239.65 301.031 + vertex -714.346 238.496 298.906 + vertex -720.445 226.494 301.016 + endloop + endfacet + facet normal -0.361796 0.0158427 -0.932122 + outer loop + vertex -719.771 239.65 301.031 + vertex -713.783 251.668 298.911 + vertex -714.346 238.496 298.906 + endloop + endfacet + facet normal -0.368874 0.019873 -0.929267 + outer loop + vertex -719.061 252.746 301.03 + vertex -713.783 251.668 298.911 + vertex -719.771 239.65 301.031 + endloop + endfacet + facet normal -0.369898 0.0142673 -0.928963 + outer loop + vertex -719.061 252.746 301.03 + vertex -713.263 264.943 298.908 + vertex -713.783 251.668 298.911 + endloop + endfacet + facet normal -0.380665 0.0201638 -0.924493 + outer loop + vertex -718.366 265.956 301.032 + vertex -713.263 264.943 298.908 + vertex -719.061 252.746 301.03 + endloop + endfacet + facet normal -0.381765 0.0139153 -0.924155 + outer loop + vertex -718.366 265.956 301.032 + vertex -712.781 278.376 298.911 + vertex -713.263 264.943 298.908 + endloop + endfacet + facet normal -0.392656 0.0196118 -0.919476 + outer loop + vertex -717.698 279.322 301.031 + vertex -712.781 278.376 298.911 + vertex -718.366 265.956 301.032 + endloop + endfacet + facet normal -0.393713 0.0133547 -0.919136 + outer loop + vertex -717.698 279.322 301.031 + vertex -712.329 291.926 298.915 + vertex -712.781 278.376 298.911 + endloop + endfacet + facet normal -0.40829 0.0206584 -0.912618 + outer loop + vertex -717.032 292.761 301.038 + vertex -712.329 291.926 298.915 + vertex -717.698 279.322 301.031 + endloop + endfacet + facet normal -0.409429 0.0132944 -0.912245 + outer loop + vertex -717.032 292.761 301.038 + vertex -711.883 305.473 298.912 + vertex -712.329 291.926 298.915 + endloop + endfacet + facet normal -0.425413 0.0210216 -0.904755 + outer loop + vertex -716.367 306.174 301.037 + vertex -711.883 305.473 298.912 + vertex -717.032 292.761 301.038 + endloop + endfacet + facet normal -0.426554 0.0125652 -0.904375 + outer loop + vertex -716.367 306.174 301.037 + vertex -711.445 318.927 298.892 + vertex -711.883 305.473 298.912 + endloop + endfacet + facet normal -0.446281 0.0218171 -0.894627 + outer loop + vertex -715.697 319.472 301.026 + vertex -711.445 318.927 298.892 + vertex -716.367 306.174 301.037 + endloop + endfacet + facet normal -0.447293 0.0126398 -0.894298 + outer loop + vertex -715.697 319.472 301.026 + vertex -711.004 332.254 298.86 + vertex -711.445 318.927 298.892 + endloop + endfacet + facet normal -0.46649 0.021388 -0.884268 + outer loop + vertex -715.035 332.656 300.996 + vertex -711.004 332.254 298.86 + vertex -715.697 319.472 301.026 + endloop + endfacet + facet normal -0.467208 0.0130386 -0.884051 + outer loop + vertex -715.035 332.656 300.996 + vertex -710.582 345.525 298.833 + vertex -711.004 332.254 298.86 + endloop + endfacet + facet normal -0.4895 0.0228276 -0.871704 + outer loop + vertex -714.373 345.811 300.969 + vertex -710.582 345.525 298.833 + vertex -715.035 332.656 300.996 + endloop + endfacet + facet normal -0.490087 0.0139735 -0.871562 + outer loop + vertex -714.373 345.811 300.969 + vertex -710.212 358.893 298.839 + vertex -710.582 345.525 298.833 + endloop + endfacet + facet normal -0.512093 0.0230816 -0.85862 + outer loop + vertex -713.76 359.094 300.96 + vertex -710.212 358.893 298.839 + vertex -714.373 345.811 300.969 + endloop + endfacet + facet normal -0.512444 0.0163156 -0.858565 + outer loop + vertex -713.76 359.094 300.96 + vertex -710.062 372.536 299.008 + vertex -710.212 358.893 298.839 + endloop + endfacet + facet normal -0.534897 0.0245267 -0.844561 + outer loop + vertex -713.364 372.638 301.103 + vertex -710.062 372.536 299.008 + vertex -713.76 359.094 300.96 + endloop + endfacet + facet normal -0.534809 0.0269935 -0.844542 + outer loop + vertex -713.364 372.638 301.103 + vertex -710.506 386.592 299.74 + vertex -710.062 372.536 299.008 + endloop + endfacet + facet normal -0.537873 0.0278139 -0.842567 + outer loop + vertex -713.582 386.55 301.701 + vertex -710.506 386.592 299.74 + vertex -713.364 372.638 301.103 + endloop + endfacet + facet normal -0.385321 -0.0919455 -0.91819 + outer loop + vertex -714.798 172.35 300.144 + vertex -712.481 170.974 299.309 + vertex -715.095 166.473 300.857 + endloop + endfacet + facet normal -0.358294 -0.110674 -0.927026 + outer loop + vertex -715.095 166.473 300.857 + vertex -712.481 170.974 299.309 + vertex -712.22 164.731 299.954 + endloop + endfacet + facet normal -0.365989 -0.125948 -0.922057 + outer loop + vertex -715.095 166.473 300.857 + vertex -712.22 164.731 299.954 + vertex -715.092 160.663 301.649 + endloop + endfacet + facet normal -0.334441 -0.151593 -0.930145 + outer loop + vertex -715.092 160.663 301.649 + vertex -712.22 164.731 299.954 + vertex -711.82 159.246 300.704 + endloop + endfacet + facet normal -0.340142 -0.168035 -0.925239 + outer loop + vertex -715.092 160.663 301.649 + vertex -711.82 159.246 300.704 + vertex -714.811 156.242 302.349 + endloop + endfacet + facet normal -0.315434 -0.194586 -0.928783 + outer loop + vertex -714.811 156.242 302.349 + vertex -711.82 159.246 300.704 + vertex -711.036 154.757 301.378 + endloop + endfacet + facet normal -0.320475 -0.21086 -0.92349 + outer loop + vertex -714.811 156.242 302.349 + vertex -711.036 154.757 301.378 + vertex -713.704 152.987 302.708 + endloop + endfacet + facet normal -0.308624 -0.228592 -0.923308 + outer loop + vertex -713.704 152.987 302.708 + vertex -711.036 154.757 301.378 + vertex -709.58 151.375 301.728 + endloop + endfacet + facet normal -0.308036 -0.226682 -0.923975 + outer loop + vertex -713.704 152.987 302.708 + vertex -709.58 151.375 301.728 + vertex -710.716 150.329 302.364 + endloop + endfacet + facet normal -0.309171 -0.225408 -0.923907 + outer loop + vertex -706.924 148.936 301.435 + vertex -710.716 150.329 302.364 + vertex -709.58 151.375 301.728 + endloop + endfacet + facet normal -0.284986 -0.143704 -0.947698 + outer loop + vertex -705.532 147.698 301.204 + vertex -710.716 150.329 302.364 + vertex -706.924 148.936 301.435 + endloop + endfacet + facet normal -0.251215 -0.16002 -0.954612 + outer loop + vertex -721.643 159.378 303.724 + vertex -718.249 157.771 303.1 + vertex -721.026 156.322 304.074 + endloop + endfacet + facet normal -0.2068 -0.121339 -0.97083 + outer loop + vertex -725.586 161.24 304.332 + vertex -721.901 164.763 303.106 + vertex -721.643 159.378 303.724 + endloop + endfacet + facet normal -0.221177 -0.105829 -0.969475 + outer loop + vertex -726.099 166.604 303.863 + vertex -721.901 164.763 303.106 + vertex -725.586 161.24 304.332 + endloop + endfacet + facet normal -0.212433 -0.0842208 -0.973539 + outer loop + vertex -721.901 164.763 303.106 + vertex -726.099 166.604 303.863 + vertex -722.547 172.227 302.601 + endloop + endfacet + facet normal -0.219551 -0.079459 -0.97236 + outer loop + vertex -728.094 174.227 303.691 + vertex -722.547 172.227 302.601 + vertex -726.099 166.604 303.863 + endloop + endfacet + facet normal -0.211136 -0.0541703 -0.975955 + outer loop + vertex -722.547 172.227 302.601 + vertex -728.094 174.227 303.691 + vertex -723.08 181.377 302.209 + endloop + endfacet + facet normal -0.228857 -0.0410458 -0.972594 + outer loop + vertex -728.094 174.227 303.691 + vertex -727.306 187.51 302.945 + vertex -723.08 181.377 302.209 + endloop + endfacet + facet normal -0.225541 -0.0386563 -0.973466 + outer loop + vertex -722.666 188.656 301.824 + vertex -723.08 181.377 302.209 + vertex -727.306 187.51 302.945 + endloop + endfacet + facet normal -0.225715 -0.0379392 -0.973454 + outer loop + vertex -727.306 187.51 302.945 + vertex -721.089 197.966 301.095 + vertex -722.666 188.656 301.824 + endloop + endfacet + facet normal -0.258879 -0.0168584 -0.965763 + outer loop + vertex -727.458 201.423 302.742 + vertex -721.089 197.966 301.095 + vertex -727.306 187.51 302.945 + endloop + endfacet + facet normal -0.252273 -0.00378852 -0.967649 + outer loop + vertex -727.458 201.423 302.742 + vertex -720.942 212.861 300.999 + vertex -721.089 197.966 301.095 + endloop + endfacet + facet normal -0.266226 0.00473223 -0.963899 + outer loop + vertex -727.049 215.082 302.696 + vertex -720.942 212.861 300.999 + vertex -727.458 201.423 302.742 + endloop + endfacet + facet normal -0.264138 0.010872 -0.964423 + outer loop + vertex -727.049 215.082 302.696 + vertex -720.445 226.494 301.016 + vertex -720.942 212.861 300.999 + endloop + endfacet + facet normal -0.269565 0.0142403 -0.962877 + outer loop + vertex -726.346 228.317 302.695 + vertex -720.445 226.494 301.016 + vertex -727.049 215.082 302.696 + endloop + endfacet + facet normal -0.269377 0.0148882 -0.96292 + outer loop + vertex -726.346 228.317 302.695 + vertex -719.771 239.65 301.031 + vertex -720.445 226.494 301.016 + endloop + endfacet + facet normal -0.274351 0.0179881 -0.961461 + outer loop + vertex -725.516 241.342 302.702 + vertex -719.771 239.65 301.031 + vertex -726.346 228.317 302.695 + endloop + endfacet + facet normal -0.275234 0.0147957 -0.961263 + outer loop + vertex -725.516 241.342 302.702 + vertex -719.061 252.746 301.03 + vertex -719.771 239.65 301.031 + endloop + endfacet + facet normal -0.280825 0.018206 -0.959586 + outer loop + vertex -724.657 254.369 302.698 + vertex -719.061 252.746 301.03 + vertex -725.516 241.342 302.702 + endloop + endfacet + facet normal -0.281705 0.0149613 -0.959384 + outer loop + vertex -724.657 254.369 302.698 + vertex -718.366 265.956 301.032 + vertex -719.061 252.746 301.03 + endloop + endfacet + facet normal -0.288162 0.0187522 -0.957398 + outer loop + vertex -723.793 267.487 302.695 + vertex -718.366 265.956 301.032 + vertex -724.657 254.369 302.698 + endloop + endfacet + facet normal -0.289296 0.0144442 -0.957131 + outer loop + vertex -723.793 267.487 302.695 + vertex -717.698 279.322 301.031 + vertex -718.366 265.956 301.032 + endloop + endfacet + facet normal -0.300218 0.0205585 -0.953649 + outer loop + vertex -722.913 280.693 302.703 + vertex -717.698 279.322 301.031 + vertex -723.793 267.487 302.695 + endloop + endfacet + facet normal -0.301481 0.0153862 -0.953348 + outer loop + vertex -722.913 280.693 302.703 + vertex -717.032 292.761 301.038 + vertex -717.698 279.322 301.031 + endloop + endfacet + facet normal -0.313201 0.0216364 -0.94944 + outer loop + vertex -722.023 293.948 302.711 + vertex -717.032 292.761 301.038 + vertex -722.913 280.693 302.703 + endloop + endfacet + facet normal -0.314548 0.0155197 -0.949115 + outer loop + vertex -722.023 293.948 302.711 + vertex -716.367 306.174 301.037 + vertex -717.032 292.761 301.038 + endloop + endfacet + facet normal -0.327857 0.0223138 -0.944464 + outer loop + vertex -721.128 307.172 302.713 + vertex -716.367 306.174 301.037 + vertex -722.023 293.948 302.711 + endloop + endfacet + facet normal -0.329101 0.0158725 -0.944161 + outer loop + vertex -721.128 307.172 302.713 + vertex -715.697 319.472 301.026 + vertex -716.367 306.174 301.037 + endloop + endfacet + facet normal -0.344097 0.0232506 -0.938646 + outer loop + vertex -720.23 320.286 302.708 + vertex -715.697 319.472 301.026 + vertex -721.128 307.172 302.713 + endloop + endfacet + facet normal -0.345426 0.0151863 -0.938323 + outer loop + vertex -720.23 320.286 302.708 + vertex -715.035 332.656 300.996 + vertex -715.697 319.472 301.026 + endloop + endfacet + facet normal -0.364483 0.0242181 -0.930895 + outer loop + vertex -719.334 333.297 302.696 + vertex -715.035 332.656 300.996 + vertex -720.23 320.286 302.708 + endloop + endfacet + facet normal -0.36554 0.0164738 -0.93065 + outer loop + vertex -719.334 333.297 302.696 + vertex -714.373 345.811 300.969 + vertex -715.035 332.656 300.996 + endloop + endfacet + facet normal -0.386943 0.0261885 -0.921732 + outer loop + vertex -718.438 346.294 302.689 + vertex -714.373 345.811 300.969 + vertex -719.334 333.297 302.696 + endloop + endfacet + facet normal -0.387915 0.0173051 -0.921533 + outer loop + vertex -718.438 346.294 302.689 + vertex -713.76 359.094 300.96 + vertex -714.373 345.811 300.969 + endloop + endfacet + facet normal -0.411026 0.0271453 -0.911219 + outer loop + vertex -717.586 359.419 302.696 + vertex -713.76 359.094 300.96 + vertex -718.438 346.294 302.689 + endloop + endfacet + facet normal -0.411471 0.0216253 -0.911166 + outer loop + vertex -717.586 359.419 302.696 + vertex -713.364 372.638 301.103 + vertex -713.76 359.094 300.96 + endloop + endfacet + facet normal -0.430332 0.0287279 -0.902214 + outer loop + vertex -716.938 372.788 302.813 + vertex -713.364 372.638 301.103 + vertex -717.586 359.419 302.696 + endloop + endfacet + facet normal -0.430173 0.0320574 -0.902177 + outer loop + vertex -716.938 372.788 302.813 + vertex -713.582 386.55 301.701 + vertex -713.364 372.638 301.103 + endloop + endfacet + facet normal -0.425674 0.0307844 -0.904353 + outer loop + vertex -716.82 386.5 303.224 + vertex -713.582 386.55 301.701 + vertex -716.938 372.788 302.813 + endloop + endfacet + facet normal -0.175976 -0.102346 -0.97906 + outer loop + vertex -729.945 163.803 304.847 + vertex -726.099 166.604 303.863 + vertex -725.586 161.24 304.332 + endloop + endfacet + facet normal -0.185025 -0.0897686 -0.978625 + outer loop + vertex -729.497 167.623 304.412 + vertex -726.099 166.604 303.863 + vertex -729.945 163.803 304.847 + endloop + endfacet + facet normal -0.179277 -0.0691205 -0.981368 + outer loop + vertex -729.497 167.623 304.412 + vertex -728.094 174.227 303.691 + vertex -726.099 166.604 303.863 + endloop + endfacet + facet normal -0.157756 -0.074055 -0.984697 + outer loop + vertex -734.315 168.981 305.082 + vertex -728.094 174.227 303.691 + vertex -729.497 167.623 304.412 + endloop + endfacet + facet normal -0.171208 -0.0577978 -0.983538 + outer loop + vertex -734.69 179.157 304.549 + vertex -728.094 174.227 303.691 + vertex -734.315 168.981 305.082 + endloop + endfacet + facet normal -0.162455 -0.0457189 -0.985656 + outer loop + vertex -734.69 179.157 304.549 + vertex -727.306 187.51 302.945 + vertex -728.094 174.227 303.691 + endloop + endfacet + facet normal -0.181738 -0.0281524 -0.982944 + outer loop + vertex -734.473 191.296 304.161 + vertex -727.306 187.51 302.945 + vertex -734.69 179.157 304.549 + endloop + endfacet + facet normal -0.175667 -0.0162202 -0.984316 + outer loop + vertex -734.473 191.296 304.161 + vertex -727.458 201.423 302.742 + vertex -727.306 187.51 302.945 + endloop + endfacet + facet normal -0.188569 -0.00696422 -0.982035 + outer loop + vertex -734.023 204.278 303.983 + vertex -727.458 201.423 302.742 + vertex -734.473 191.296 304.161 + endloop + endfacet + facet normal -0.184714 0.00222539 -0.98279 + outer loop + vertex -734.023 204.278 303.983 + vertex -727.049 215.082 302.696 + vertex -727.458 201.423 302.742 + endloop + endfacet + facet normal -0.18959 0.00548536 -0.981848 + outer loop + vertex -733.289 217.428 303.914 + vertex -727.049 215.082 302.696 + vertex -734.023 204.278 303.983 + endloop + endfacet + facet normal -0.187982 0.00990684 -0.982123 + outer loop + vertex -733.289 217.428 303.914 + vertex -726.346 228.317 302.695 + vertex -727.049 215.082 302.696 + endloop + endfacet + facet normal -0.190069 0.0112842 -0.981706 + outer loop + vertex -732.401 230.476 303.893 + vertex -726.346 228.317 302.695 + vertex -733.289 217.428 303.914 + endloop + endfacet + facet normal -0.189615 0.0125981 -0.981778 + outer loop + vertex -732.401 230.476 303.893 + vertex -725.516 241.342 302.702 + vertex -726.346 228.317 302.695 + endloop + endfacet + facet normal -0.191297 0.0137017 -0.981437 + outer loop + vertex -731.444 243.424 303.887 + vertex -725.516 241.342 302.702 + vertex -732.401 230.476 303.893 + endloop + endfacet + facet normal -0.191765 0.012329 -0.981363 + outer loop + vertex -731.444 243.424 303.887 + vertex -724.657 254.369 302.698 + vertex -725.516 241.342 302.702 + endloop + endfacet + facet normal -0.197285 0.0158768 -0.980218 + outer loop + vertex -730.434 256.338 303.893 + vertex -724.657 254.369 302.698 + vertex -731.444 243.424 303.887 + endloop + endfacet + facet normal -0.198293 0.0128248 -0.980059 + outer loop + vertex -730.434 256.338 303.893 + vertex -723.793 267.487 302.695 + vertex -724.657 254.369 302.698 + endloop + endfacet + facet normal -0.204411 0.0166108 -0.978744 + outer loop + vertex -729.385 269.292 303.893 + vertex -723.793 267.487 302.695 + vertex -730.434 256.338 303.893 + endloop + endfacet + facet normal -0.205151 0.0142396 -0.978627 + outer loop + vertex -729.385 269.292 303.893 + vertex -722.913 280.693 302.703 + vertex -723.793 267.487 302.695 + endloop + endfacet + facet normal -0.211917 0.0182382 -0.977117 + outer loop + vertex -728.294 282.301 303.9 + vertex -722.913 280.693 302.703 + vertex -729.385 269.292 303.893 + endloop + endfacet + facet normal -0.212875 0.014918 -0.976965 + outer loop + vertex -728.294 282.301 303.9 + vertex -722.023 293.948 302.711 + vertex -722.913 280.693 302.703 + endloop + endfacet + facet normal -0.220229 0.0190515 -0.975262 + outer loop + vertex -727.183 295.352 303.904 + vertex -722.023 293.948 302.711 + vertex -728.294 282.301 303.9 + endloop + endfacet + facet normal -0.221264 0.0151059 -0.975097 + outer loop + vertex -727.183 295.352 303.904 + vertex -721.128 307.172 302.713 + vertex -722.023 293.948 302.711 + endloop + endfacet + facet normal -0.231022 0.0203424 -0.972736 + outer loop + vertex -726.058 308.369 303.909 + vertex -721.128 307.172 302.713 + vertex -727.183 295.352 303.904 + endloop + endfacet + facet normal -0.232137 0.0155718 -0.972558 + outer loop + vertex -726.058 308.369 303.909 + vertex -720.23 320.286 302.708 + vertex -721.128 307.172 302.713 + endloop + endfacet + facet normal -0.24389 0.0216211 -0.969562 + outer loop + vertex -724.928 321.281 303.912 + vertex -720.23 320.286 302.708 + vertex -726.058 308.369 303.909 + endloop + endfacet + facet normal -0.245044 0.0159524 -0.969381 + outer loop + vertex -724.928 321.281 303.912 + vertex -719.334 333.297 302.696 + vertex -720.23 320.286 302.708 + endloop + endfacet + facet normal -0.260191 0.0234207 -0.965273 + outer loop + vertex -723.799 334.09 303.919 + vertex -719.334 333.297 302.696 + vertex -724.928 321.281 303.912 + endloop + endfacet + facet normal -0.261201 0.0175051 -0.965126 + outer loop + vertex -723.799 334.09 303.919 + vertex -718.438 346.294 302.689 + vertex -719.334 333.297 302.696 + endloop + endfacet + facet normal -0.278113 0.0254284 -0.960212 + outer loop + vertex -722.68 346.888 303.934 + vertex -718.438 346.294 302.689 + vertex -723.799 334.09 303.919 + endloop + endfacet + facet normal -0.279038 0.0186007 -0.9601 + outer loop + vertex -722.68 346.888 303.934 + vertex -717.586 359.419 302.696 + vertex -718.438 346.294 302.689 + endloop + endfacet + facet normal -0.301472 0.0284152 -0.953052 + outer loop + vertex -721.588 359.799 303.973 + vertex -717.586 359.419 302.696 + vertex -722.68 346.888 303.934 + endloop + endfacet + facet normal -0.301986 0.0229465 -0.953036 + outer loop + vertex -721.588 359.799 303.973 + vertex -716.938 372.788 302.813 + vertex -717.586 359.419 302.696 + endloop + endfacet + facet normal -0.31801 0.0291656 -0.947639 + outer loop + vertex -720.673 372.96 304.071 + vertex -716.938 372.788 302.813 + vertex -721.588 359.799 303.973 + endloop + endfacet + facet normal -0.317909 0.0311516 -0.947609 + outer loop + vertex -720.673 372.96 304.071 + vertex -716.82 386.5 303.224 + vertex -716.938 372.788 302.813 + endloop + endfacet + facet normal -0.32541 0.033451 -0.944981 + outer loop + vertex -720.06 386.446 304.337 + vertex -716.82 386.5 303.224 + vertex -720.673 372.96 304.071 + endloop + endfacet + facet normal -0.162705 -0.0928056 -0.9823 + outer loop + vertex -729.497 167.623 304.412 + vertex -729.945 163.803 304.847 + vertex -734.315 168.981 305.082 + endloop + endfacet + facet normal -0.121047 -0.0563462 -0.991046 + outer loop + vertex -741.856 173.432 305.75 + vertex -734.69 179.157 304.549 + vertex -734.315 168.981 305.082 + endloop + endfacet + facet normal -0.131177 -0.0435317 -0.990403 + outer loop + vertex -741.896 182.94 305.337 + vertex -734.69 179.157 304.549 + vertex -741.856 173.432 305.75 + endloop + endfacet + facet normal -0.123953 -0.0294696 -0.99185 + outer loop + vertex -741.896 182.94 305.337 + vertex -734.473 191.296 304.161 + vertex -734.69 179.157 304.549 + endloop + endfacet + facet normal -0.133181 -0.0211332 -0.990866 + outer loop + vertex -741.376 194.422 305.022 + vertex -734.473 191.296 304.161 + vertex -741.896 182.94 305.337 + endloop + endfacet + facet normal -0.0896969 -0.023235 -0.995698 + outer loop + vertex -748.933 186.234 305.894 + vertex -741.376 194.422 305.022 + vertex -741.896 182.94 305.337 + endloop + endfacet + facet normal -0.0962016 -0.037309 -0.994662 + outer loop + vertex -748.933 186.234 305.894 + vertex -741.896 182.94 305.337 + vertex -749.216 177.068 306.265 + endloop + endfacet + facet normal -0.0652725 -0.0383652 -0.99713 + outer loop + vertex -756.185 180.489 306.59 + vertex -748.933 186.234 305.894 + vertex -749.216 177.068 306.265 + endloop + endfacet + facet normal -0.0679627 -0.0349623 -0.997075 + outer loop + vertex -755.787 189.495 306.247 + vertex -748.933 186.234 305.894 + vertex -756.185 180.489 306.59 + endloop + endfacet + facet normal -0.0462262 -0.0359702 -0.998283 + outer loop + vertex -763.024 183.997 306.78 + vertex -755.787 189.495 306.247 + vertex -756.185 180.489 306.59 + endloop + endfacet + facet normal -0.0536477 -0.0504926 -0.997283 + outer loop + vertex -763.024 183.997 306.78 + vertex -756.185 180.489 306.59 + vertex -762.197 177.526 307.063 + endloop + endfacet + facet normal -0.0525222 -0.0527665 -0.997225 + outer loop + vertex -762.197 177.526 307.063 + vertex -756.185 180.489 306.59 + vertex -755.694 174.134 306.9 + endloop + endfacet + facet normal -0.0479019 -0.0337642 -0.998281 + outer loop + vertex -762.574 192.992 306.454 + vertex -755.787 189.495 306.247 + vertex -763.024 183.997 306.78 + endloop + endfacet + facet normal -0.0331699 -0.0345218 -0.998853 + outer loop + vertex -769.846 187.807 306.875 + vertex -762.574 192.992 306.454 + vertex -763.024 183.997 306.78 + endloop + endfacet + facet normal -0.0408768 -0.0483413 -0.997994 + outer loop + vertex -769.846 187.807 306.875 + vertex -763.024 183.997 306.78 + vertex -769.368 180.958 307.187 + endloop + endfacet + facet normal -0.0315543 -0.047708 -0.998363 + outer loop + vertex -776.097 185.525 307.182 + vertex -769.846 187.807 306.875 + vertex -769.368 180.958 307.187 + endloop + endfacet + facet normal -0.0420359 -0.0631463 -0.997119 + outer loop + vertex -776.097 185.525 307.182 + vertex -769.368 180.958 307.187 + vertex -775.011 181.819 307.371 + endloop + endfacet + facet normal -0.0370137 -0.0616897 -0.997409 + outer loop + vertex -775.011 181.819 307.371 + vertex -780.313 185.387 307.347 + vertex -776.097 185.525 307.182 + endloop + endfacet + facet normal -0.0371058 -0.0590716 -0.997564 + outer loop + vertex -782.365 189.437 307.183 + vertex -776.097 185.525 307.182 + vertex -780.313 185.387 307.347 + endloop + endfacet + facet normal -0.0382073 -0.0596268 -0.997489 + outer loop + vertex -780.313 185.387 307.347 + vertex -785.505 188.443 307.363 + vertex -782.365 189.437 307.183 + endloop + endfacet + facet normal -0.0373527 -0.0623038 -0.997358 + outer loop + vertex -789.373 193.577 307.187 + vertex -782.365 189.437 307.183 + vertex -785.505 188.443 307.363 + endloop + endfacet + facet normal -0.037892 -0.0627086 -0.997312 + outer loop + vertex -785.505 188.443 307.363 + vertex -790.787 191.625 307.364 + vertex -789.373 193.577 307.187 + endloop + endfacet + facet normal -0.0623996 -0.103398 -0.992681 + outer loop + vertex -790.787 191.625 307.364 + vertex -785.505 188.443 307.363 + vertex -787.031 188.559 307.447 + endloop + endfacet + facet normal -0.0621287 -0.0995088 -0.993095 + outer loop + vertex -779.486 183.806 307.451 + vertex -787.031 188.559 307.447 + vertex -785.505 188.443 307.363 + endloop + endfacet + facet normal -0.0269448 -0.0446822 -0.998638 + outer loop + vertex -789.373 193.577 307.187 + vertex -783.138 195.969 306.912 + vertex -782.365 189.437 307.183 + endloop + endfacet + facet normal -0.028644 -0.0448809 -0.998582 + outer loop + vertex -783.138 195.969 306.912 + vertex -776.498 191.822 306.908 + vertex -782.365 189.437 307.183 + endloop + endfacet + facet normal -0.0209109 -0.0324978 -0.999253 + outer loop + vertex -783.138 195.969 306.912 + vertex -775.998 200.702 306.609 + vertex -776.498 191.822 306.908 + endloop + endfacet + facet normal -0.0258315 -0.0322174 -0.999147 + outer loop + vertex -775.998 200.702 306.609 + vertex -769.317 196.729 306.564 + vertex -776.498 191.822 306.908 + endloop + endfacet + facet normal -0.0250434 -0.0333694 -0.999129 + outer loop + vertex -776.498 191.822 306.908 + vertex -769.317 196.729 306.564 + vertex -769.846 187.807 306.875 + endloop + endfacet + facet normal -0.0193474 -0.0213068 -0.999586 + outer loop + vertex -775.998 200.702 306.609 + vertex -768.323 207.71 306.311 + vertex -769.317 196.729 306.564 + endloop + endfacet + facet normal -0.0295421 -0.0203791 -0.999356 + outer loop + vertex -768.323 207.71 306.311 + vertex -761.605 204.004 306.188 + vertex -769.317 196.729 306.564 + endloop + endfacet + facet normal -0.0282657 -0.0217326 -0.999364 + outer loop + vertex -769.317 196.729 306.564 + vertex -761.605 204.004 306.188 + vertex -762.574 192.992 306.454 + endloop + endfacet + facet normal -0.0438448 -0.0203482 -0.998831 + outer loop + vertex -761.605 204.004 306.188 + vertex -754.869 200.587 305.961 + vertex -762.574 192.992 306.454 + endloop + endfacet + facet normal -0.0391175 -0.0110061 -0.999174 + outer loop + vertex -761.605 204.004 306.188 + vertex -753.792 212.917 305.784 + vertex -754.869 200.587 305.961 + endloop + endfacet + facet normal -0.061267 -0.00905611 -0.99808 + outer loop + vertex -753.792 212.917 305.784 + vertex -747.141 209.824 305.403 + vertex -754.869 200.587 305.961 + endloop + endfacet + facet normal -0.0593929 -0.0106297 -0.998178 + outer loop + vertex -754.869 200.587 305.961 + vertex -747.141 209.824 305.403 + vertex -748.144 197.398 305.595 + endloop + endfacet + facet normal -0.0639967 -0.0203901 -0.997742 + outer loop + vertex -754.869 200.587 305.961 + vertex -748.144 197.398 305.595 + vertex -755.787 189.495 306.247 + endloop + endfacet + facet normal -0.089778 -0.0081445 -0.995929 + outer loop + vertex -747.141 209.824 305.403 + vertex -740.567 206.987 304.834 + vertex -748.144 197.398 305.595 + endloop + endfacet + facet normal -0.0883859 -0.0092536 -0.996043 + outer loop + vertex -748.144 197.398 305.595 + vertex -740.567 206.987 304.834 + vertex -741.376 194.422 305.022 + endloop + endfacet + facet normal -0.131572 -0.00640357 -0.991286 + outer loop + vertex -740.567 206.987 304.834 + vertex -734.023 204.278 303.983 + vertex -741.376 194.422 305.022 + endloop + endfacet + facet normal -0.128153 0.00200459 -0.991752 + outer loop + vertex -740.567 206.987 304.834 + vertex -733.289 217.428 303.914 + vertex -734.023 204.278 303.983 + endloop + endfacet + facet normal -0.12884 0.00249141 -0.991662 + outer loop + vertex -739.623 219.945 304.744 + vertex -733.289 217.428 303.914 + vertex -740.567 206.987 304.834 + endloop + endfacet + facet normal -0.127082 0.0069829 -0.991868 + outer loop + vertex -739.623 219.945 304.744 + vertex -732.401 230.476 303.893 + vertex -733.289 217.428 303.914 + endloop + endfacet + facet normal -0.12863 0.00806095 -0.99166 + outer loop + vertex -738.614 232.901 304.718 + vertex -732.401 230.476 303.893 + vertex -739.623 219.945 304.744 + endloop + endfacet + facet normal -0.0860992 0.00474012 -0.996275 + outer loop + vertex -746.093 222.699 305.316 + vertex -738.614 232.901 304.718 + vertex -739.623 219.945 304.744 + endloop + endfacet + facet normal -0.0879306 0.000406922 -0.996127 + outer loop + vertex -746.093 222.699 305.316 + vertex -739.623 219.945 304.744 + vertex -747.141 209.824 305.403 + endloop + endfacet + facet normal -0.0877686 0.00597284 -0.996123 + outer loop + vertex -744.999 235.56 305.297 + vertex -738.614 232.901 304.718 + vertex -746.093 222.699 305.316 + endloop + endfacet + facet normal -0.0579228 0.0034313 -0.998315 + outer loop + vertex -752.684 225.705 305.709 + vertex -744.999 235.56 305.297 + vertex -746.093 222.699 305.316 + endloop + endfacet + facet normal -0.0597791 -0.000653347 -0.998211 + outer loop + vertex -752.684 225.705 305.709 + vertex -746.093 222.699 305.316 + vertex -753.792 212.917 305.784 + endloop + endfacet + facet normal -0.0372266 -0.00261339 -0.999303 + outer loop + vertex -760.491 216.274 306.024 + vertex -752.684 225.705 305.709 + vertex -753.792 212.917 305.784 + endloop + endfacet + facet normal -0.0383244 -0.00170338 -0.999264 + outer loop + vertex -759.324 228.937 305.958 + vertex -752.684 225.705 305.709 + vertex -760.491 216.274 306.024 + endloop + endfacet + facet normal -0.0213607 -0.00326838 -0.999766 + outer loop + vertex -767.181 219.853 306.156 + vertex -759.324 228.937 305.958 + vertex -760.491 216.274 306.024 + endloop + endfacet + facet normal -0.0251718 -0.0103986 -0.999629 + outer loop + vertex -767.181 219.853 306.156 + vertex -760.491 216.274 306.024 + vertex -768.323 207.71 306.311 + endloop + endfacet + facet normal -0.0142173 -0.0114311 -0.999834 + outer loop + vertex -775.004 211.594 306.361 + vertex -767.181 219.853 306.156 + vertex -768.323 207.71 306.311 + endloop + endfacet + facet normal -0.0144022 -0.0112559 -0.999833 + outer loop + vertex -773.826 223.635 306.209 + vertex -767.181 219.853 306.156 + vertex -775.004 211.594 306.361 + endloop + endfacet + facet normal -0.00756467 -0.0119258 -0.9999 + outer loop + vertex -781.606 215.669 306.363 + vertex -773.826 223.635 306.209 + vertex -775.004 211.594 306.361 + endloop + endfacet + facet normal -0.0134892 -0.021524 -0.999677 + outer loop + vertex -781.606 215.669 306.363 + vertex -775.004 211.594 306.361 + vertex -782.64 204.838 306.61 + endloop + endfacet + facet normal -0.00849193 -0.022002 -0.999722 + outer loop + vertex -789.138 209.182 306.569 + vertex -781.606 215.669 306.363 + vertex -782.64 204.838 306.61 + endloop + endfacet + facet normal -0.0163729 -0.0337865 -0.999295 + outer loop + vertex -789.138 209.182 306.569 + vertex -782.64 204.838 306.61 + vertex -789.729 200.36 306.877 + endloop + endfacet + facet normal -0.0168047 -0.0331038 -0.999311 + outer loop + vertex -789.729 200.36 306.877 + vertex -782.64 204.838 306.61 + vertex -783.138 195.969 306.912 + endloop + endfacet + facet normal -0.00803398 -0.0225333 -0.999714 + outer loop + vertex -788.062 219.864 306.32 + vertex -781.606 215.669 306.363 + vertex -789.138 209.182 306.569 + endloop + endfacet + facet normal 0.000397076 -0.0233821 -0.999727 + outer loop + vertex -795.438 213.57 306.464 + vertex -788.062 219.864 306.32 + vertex -789.138 209.182 306.569 + endloop + endfacet + facet normal -0.00858525 -0.0362694 -0.999305 + outer loop + vertex -795.438 213.57 306.464 + vertex -789.138 209.182 306.569 + vertex -796.117 204.82 306.788 + endloop + endfacet + facet normal 0.00147022 -0.0246389 -0.999695 + outer loop + vertex -794.303 224.159 306.205 + vertex -788.062 219.864 306.32 + vertex -795.438 213.57 306.464 + endloop + endfacet + facet normal 0.0182066 -0.0264281 -0.999485 + outer loop + vertex -801.496 218.114 306.234 + vertex -794.303 224.159 306.205 + vertex -795.438 213.57 306.464 + endloop + endfacet + facet normal 0.0067709 -0.0416552 -0.999109 + outer loop + vertex -801.496 218.114 306.234 + vertex -795.438 213.57 306.464 + vertex -802.24 209.41 306.591 + endloop + endfacet + facet normal 0.0289994 -0.0435362 -0.998631 + outer loop + vertex -808.139 214.299 306.207 + vertex -801.496 218.114 306.234 + vertex -802.24 209.41 306.591 + endloop + endfacet + facet normal 0.0333486 -0.0511139 -0.998136 + outer loop + vertex -807.377 222.96 305.789 + vertex -801.496 218.114 306.234 + vertex -808.139 214.299 306.207 + endloop + endfacet + facet normal 0.0629468 -0.0536454 -0.996574 + outer loop + vertex -814.124 219.575 305.545 + vertex -807.377 222.96 305.789 + vertex -808.139 214.299 306.207 + endloop + endfacet + facet normal 0.0690231 -0.0658407 -0.99544 + outer loop + vertex -813.047 228.203 305.049 + vertex -807.377 222.96 305.789 + vertex -814.124 219.575 305.545 + endloop + endfacet + facet normal 0.104569 -0.070082 -0.992045 + outer loop + vertex -820.246 225.284 304.496 + vertex -813.047 228.203 305.049 + vertex -814.124 219.575 305.545 + endloop + endfacet + facet normal 0.110507 -0.0850708 -0.990228 + outer loop + vertex -817.992 233.503 304.042 + vertex -813.047 228.203 305.049 + vertex -820.246 225.284 304.496 + endloop + endfacet + facet normal 0.0911836 -0.0418055 -0.994956 + outer loop + vertex -813.047 228.203 305.049 + vertex -806.075 233.351 305.472 + vertex -807.377 222.96 305.789 + endloop + endfacet + facet normal 0.0524043 -0.037039 -0.997939 + outer loop + vertex -806.075 233.351 305.472 + vertex -800.304 228.628 305.95 + vertex -807.377 222.96 305.789 + endloop + endfacet + facet normal 0.0642115 -0.0225838 -0.997681 + outer loop + vertex -806.075 233.351 305.472 + vertex -798.925 240.135 305.778 + vertex -800.304 228.628 305.95 + endloop + endfacet + facet normal 0.0312086 -0.0186539 -0.999339 + outer loop + vertex -798.925 240.135 305.778 + vertex -792.972 235.831 306.045 + vertex -800.304 228.628 305.95 + endloop + endfacet + facet normal 0.0296935 -0.0171108 -0.999413 + outer loop + vertex -800.304 228.628 305.95 + vertex -792.972 235.831 306.045 + vertex -794.303 224.159 306.205 + endloop + endfacet + facet normal 0.00970786 -0.0148381 -0.999843 + outer loop + vertex -792.972 235.831 306.045 + vertex -786.789 231.651 306.167 + vertex -794.303 224.159 306.205 + endloop + endfacet + facet normal 0.0149234 -0.00712388 -0.999863 + outer loop + vertex -792.972 235.831 306.045 + vertex -785.371 243.714 306.102 + vertex -786.789 231.651 306.167 + endloop + endfacet + facet normal 0.00354486 -0.00578741 -0.999977 + outer loop + vertex -785.371 243.714 306.102 + vertex -779.026 239.792 306.147 + vertex -786.789 231.651 306.167 + endloop + endfacet + facet normal 0.00333079 -0.00558327 -0.999979 + outer loop + vertex -786.789 231.651 306.167 + vertex -779.026 239.792 306.147 + vertex -780.384 227.585 306.211 + endloop + endfacet + facet normal -0.00129009 -0.0128616 -0.999916 + outer loop + vertex -786.789 231.651 306.167 + vertex -780.384 227.585 306.211 + vertex -788.062 219.864 306.32 + endloop + endfacet + facet normal -0.00314928 -0.00486237 -0.999983 + outer loop + vertex -779.026 239.792 306.147 + vertex -772.531 235.993 306.145 + vertex -780.384 227.585 306.211 + endloop + endfacet + facet normal -0.00320178 -0.00481333 -0.999983 + outer loop + vertex -780.384 227.585 306.211 + vertex -772.531 235.993 306.145 + vertex -773.826 223.635 306.209 + endloop + endfacet + facet normal -0.0103623 -0.00406274 -0.999938 + outer loop + vertex -772.531 235.993 306.145 + vertex -765.95 232.367 306.092 + vertex -773.826 223.635 306.209 + endloop + endfacet + facet normal -0.00804335 0.000146106 -0.999968 + outer loop + vertex -772.531 235.993 306.145 + vertex -764.568 244.731 306.082 + vertex -765.95 232.367 306.092 + endloop + endfacet + facet normal -0.0197906 0.00145901 -0.999803 + outer loop + vertex -764.568 244.731 306.082 + vertex -758.04 241.484 305.948 + vertex -765.95 232.367 306.092 + endloop + endfacet + facet normal -0.0195247 0.00122819 -0.999809 + outer loop + vertex -765.95 232.367 306.092 + vertex -758.04 241.484 305.948 + vertex -759.324 228.937 305.958 + endloop + endfacet + facet normal -0.0370053 0.00301834 -0.999311 + outer loop + vertex -758.04 241.484 305.948 + vertex -751.501 238.427 305.697 + vertex -759.324 228.937 305.958 + endloop + endfacet + facet normal -0.0362736 0.00458495 -0.999331 + outer loop + vertex -758.04 241.484 305.948 + vertex -750.169 250.928 305.706 + vertex -751.501 238.427 305.697 + endloop + endfacet + facet normal -0.0600619 0.00711901 -0.998169 + outer loop + vertex -750.169 250.928 305.706 + vertex -743.802 248.25 305.304 + vertex -751.501 238.427 305.697 + endloop + endfacet + facet normal -0.058751 0.00608822 -0.998254 + outer loop + vertex -751.501 238.427 305.697 + vertex -743.802 248.25 305.304 + vertex -744.999 235.56 305.297 + endloop + endfacet + facet normal -0.0895277 0.0089908 -0.995944 + outer loop + vertex -743.802 248.25 305.304 + vertex -737.541 245.744 304.718 + vertex -744.999 235.56 305.297 + endloop + endfacet + facet normal -0.08959 0.00883405 -0.99594 + outer loop + vertex -743.802 248.25 305.304 + vertex -736.377 258.499 304.727 + vertex -737.541 245.744 304.718 + endloop + endfacet + facet normal -0.134349 0.0129144 -0.99085 + outer loop + vertex -736.377 258.499 304.727 + vertex -730.434 256.338 303.893 + vertex -737.541 245.744 304.718 + endloop + endfacet + facet normal -0.131115 0.0107091 -0.991309 + outer loop + vertex -737.541 245.744 304.718 + vertex -730.434 256.338 303.893 + vertex -731.444 243.424 303.887 + endloop + endfacet + facet normal -0.131024 0.010952 -0.991319 + outer loop + vertex -737.541 245.744 304.718 + vertex -731.444 243.424 303.887 + vertex -738.614 232.901 304.718 + endloop + endfacet + facet normal -0.135038 0.0109905 -0.990779 + outer loop + vertex -736.377 258.499 304.727 + vertex -729.385 269.292 303.893 + vertex -730.434 256.338 303.893 + endloop + endfacet + facet normal -0.139083 0.0136564 -0.990187 + outer loop + vertex -735.136 271.253 304.728 + vertex -729.385 269.292 303.893 + vertex -736.377 258.499 304.727 + endloop + endfacet + facet normal -0.139578 0.0121816 -0.990136 + outer loop + vertex -735.136 271.253 304.728 + vertex -728.294 282.301 303.9 + vertex -729.385 269.292 303.893 + endloop + endfacet + facet normal -0.143434 0.0146133 -0.989552 + outer loop + vertex -733.839 284.054 304.729 + vertex -728.294 282.301 303.9 + vertex -735.136 271.253 304.728 + endloop + endfacet + facet normal -0.14407 0.0125716 -0.989488 + outer loop + vertex -733.839 284.054 304.729 + vertex -727.183 295.352 303.904 + vertex -728.294 282.301 303.9 + endloop + endfacet + facet normal -0.149661 0.0159291 -0.988609 + outer loop + vertex -732.502 296.888 304.734 + vertex -727.183 295.352 303.904 + vertex -733.839 284.054 304.729 + endloop + endfacet + facet normal -0.150386 0.0133779 -0.988537 + outer loop + vertex -732.502 296.888 304.734 + vertex -726.058 308.369 303.909 + vertex -727.183 295.352 303.904 + endloop + endfacet + facet normal -0.156307 0.0167709 -0.987566 + outer loop + vertex -731.148 309.691 304.737 + vertex -726.058 308.369 303.909 + vertex -732.502 296.888 304.734 + endloop + endfacet + facet normal -0.15701 0.014023 -0.987497 + outer loop + vertex -731.148 309.691 304.737 + vertex -724.928 321.281 303.912 + vertex -726.058 308.369 303.909 + endloop + endfacet + facet normal -0.164306 0.0180278 -0.986245 + outer loop + vertex -729.785 322.384 304.742 + vertex -724.928 321.281 303.912 + vertex -731.148 309.691 304.737 + endloop + endfacet + facet normal -0.164975 0.0150371 -0.986183 + outer loop + vertex -729.785 322.384 304.742 + vertex -723.799 334.09 303.919 + vertex -724.928 321.281 303.912 + endloop + endfacet + facet normal -0.17481 0.0201928 -0.984395 + outer loop + vertex -728.42 334.965 304.757 + vertex -723.799 334.09 303.919 + vertex -729.785 322.384 304.742 + endloop + endfacet + facet normal -0.175504 0.0164824 -0.984341 + outer loop + vertex -728.42 334.965 304.757 + vertex -722.68 346.888 303.934 + vertex -723.799 334.09 303.919 + endloop + endfacet + facet normal -0.187079 0.0222109 -0.982094 + outer loop + vertex -727.072 347.537 304.785 + vertex -722.68 346.888 303.934 + vertex -728.42 334.965 304.757 + endloop + endfacet + facet normal -0.187567 0.0188748 -0.98207 + outer loop + vertex -727.072 347.537 304.785 + vertex -721.588 359.799 303.973 + vertex -722.68 346.888 303.934 + endloop + endfacet + facet normal -0.201781 0.0254285 -0.9791 + outer loop + vertex -725.745 360.216 304.841 + vertex -721.588 359.799 303.973 + vertex -727.072 347.537 304.785 + endloop + endfacet + facet normal -0.202192 0.0213512 -0.979113 + outer loop + vertex -725.745 360.216 304.841 + vertex -720.673 372.96 304.071 + vertex -721.588 359.799 303.973 + endloop + endfacet + facet normal -0.217164 0.027513 -0.975747 + outer loop + vertex -724.571 373.14 304.944 + vertex -720.673 372.96 304.071 + vertex -725.745 360.216 304.841 + endloop + endfacet + facet normal -0.217082 0.0291293 -0.975719 + outer loop + vertex -724.571 373.14 304.944 + vertex -720.06 386.446 304.337 + vertex -720.673 372.96 304.071 + endloop + endfacet + facet normal -0.236028 0.0357646 -0.971088 + outer loop + vertex -723.833 386.378 305.252 + vertex -720.06 386.446 304.337 + vertex -724.571 373.14 304.944 + endloop + endfacet + facet normal -0.0913491 0.0101181 -0.995768 + outer loop + vertex -742.477 260.814 305.31 + vertex -736.377 258.499 304.727 + vertex -743.802 248.25 305.304 + endloop + endfacet + facet normal -0.091751 0.00905242 -0.995741 + outer loop + vertex -742.477 260.814 305.31 + vertex -735.136 271.253 304.728 + vertex -736.377 258.499 304.727 + endloop + endfacet + facet normal -0.0947238 0.0111596 -0.995441 + outer loop + vertex -741.04 273.348 305.314 + vertex -735.136 271.253 304.728 + vertex -742.477 260.814 305.31 + endloop + endfacet + facet normal -0.0619438 0.00740333 -0.998052 + outer loop + vertex -748.674 263.278 305.713 + vertex -741.04 273.348 305.314 + vertex -742.477 260.814 305.31 + endloop + endfacet + facet normal -0.0617003 0.00801735 -0.998063 + outer loop + vertex -748.674 263.278 305.713 + vertex -742.477 260.814 305.31 + vertex -750.169 250.928 305.706 + endloop + endfacet + facet normal -0.0370208 0.00503215 -0.999302 + outer loop + vertex -756.573 253.783 305.958 + vertex -748.674 263.278 305.713 + vertex -750.169 250.928 305.706 + endloop + endfacet + facet normal -0.0377172 0.00561214 -0.999273 + outer loop + vertex -754.919 265.914 305.963 + vertex -748.674 263.278 305.713 + vertex -756.573 253.783 305.958 + endloop + endfacet + facet normal -0.0191788 0.00308626 -0.999811 + outer loop + vertex -762.976 256.827 306.09 + vertex -754.919 265.914 305.963 + vertex -756.573 253.783 305.958 + endloop + endfacet + facet normal -0.0191524 0.00314183 -0.999812 + outer loop + vertex -762.976 256.827 306.09 + vertex -756.573 253.783 305.958 + vertex -764.568 244.731 306.082 + endloop + endfacet + facet normal -0.0072735 0.00157815 -0.999972 + outer loop + vertex -771.062 248.177 306.135 + vertex -762.976 256.827 306.09 + vertex -764.568 244.731 306.082 + endloop + endfacet + facet normal -0.00737804 0.00167588 -0.999971 + outer loop + vertex -769.359 260.063 306.142 + vertex -762.976 256.827 306.09 + vertex -771.062 248.177 306.135 + endloop + endfacet + facet normal 8.08284e-05 0.000607211 -1 + outer loop + vertex -777.478 251.796 306.137 + vertex -769.359 260.063 306.142 + vertex -771.062 248.177 306.135 + endloop + endfacet + facet normal -0.000699684 -0.000776679 -0.999999 + outer loop + vertex -777.478 251.796 306.137 + vertex -771.062 248.177 306.135 + vertex -779.026 239.792 306.147 + endloop + endfacet + facet normal 0.000191402 0.000498634 -1 + outer loop + vertex -775.676 263.467 306.143 + vertex -769.359 260.063 306.142 + vertex -777.478 251.796 306.137 + endloop + endfacet + facet normal 0.0071558 -0.000576666 -0.999974 + outer loop + vertex -783.748 255.536 306.09 + vertex -775.676 263.467 306.143 + vertex -777.478 251.796 306.137 + endloop + endfacet + facet normal 0.00636129 -0.00190875 -0.999978 + outer loop + vertex -783.748 255.536 306.09 + vertex -777.478 251.796 306.137 + vertex -785.371 243.714 306.102 + endloop + endfacet + facet normal 0.0180888 -0.00351911 -0.99983 + outer loop + vertex -791.507 247.727 305.977 + vertex -783.748 255.536 306.09 + vertex -785.371 243.714 306.102 + endloop + endfacet + facet normal 0.0185675 -0.00399489 -0.99982 + outer loop + vertex -789.816 259.358 305.962 + vertex -783.748 255.536 306.09 + vertex -791.507 247.727 305.977 + endloop + endfacet + facet normal 0.0412114 -0.00728552 -0.999124 + outer loop + vertex -797.399 251.841 305.704 + vertex -789.816 259.358 305.962 + vertex -791.507 247.727 305.977 + endloop + endfacet + facet normal 0.0383606 -0.0113728 -0.999199 + outer loop + vertex -797.399 251.841 305.704 + vertex -791.507 247.727 305.977 + vertex -798.925 240.135 305.778 + endloop + endfacet + facet normal 0.0734866 -0.0159395 -0.997169 + outer loop + vertex -804.626 244.623 305.286 + vertex -797.399 251.841 305.704 + vertex -798.925 240.135 305.778 + endloop + endfacet + facet normal 0.0745263 -0.016986 -0.997074 + outer loop + vertex -803.058 256.073 305.209 + vertex -797.399 251.841 305.704 + vertex -804.626 244.623 305.286 + endloop + endfacet + facet normal 0.123288 -0.0236284 -0.99209 + outer loop + vertex -810.053 249.213 304.503 + vertex -803.058 256.073 305.209 + vertex -804.626 244.623 305.286 + endloop + endfacet + facet normal 0.11461 -0.0340147 -0.992828 + outer loop + vertex -810.053 249.213 304.503 + vertex -804.626 244.623 305.286 + vertex -811.514 238.281 304.709 + endloop + endfacet + facet normal 0.111566 -0.0306674 -0.993284 + outer loop + vertex -811.514 238.281 304.709 + vertex -804.626 244.623 305.286 + vertex -806.075 233.351 305.472 + endloop + endfacet + facet normal 0.1251 -0.0255049 -0.991816 + outer loop + vertex -808.452 260.41 304.417 + vertex -803.058 256.073 305.209 + vertex -810.053 249.213 304.503 + endloop + endfacet + facet normal 0.128413 -0.0213259 -0.991491 + outer loop + vertex -808.452 260.41 304.417 + vertex -801.254 267.256 305.202 + vertex -803.058 256.073 305.209 + endloop + endfacet + facet normal 0.0778157 -0.0131684 -0.996881 + outer loop + vertex -801.254 267.256 305.202 + vertex -795.655 263.257 305.692 + vertex -803.058 256.073 305.209 + endloop + endfacet + facet normal 0.077435 -0.0137043 -0.996903 + outer loop + vertex -801.254 267.256 305.202 + vertex -793.617 274.248 305.699 + vertex -795.655 263.257 305.692 + endloop + endfacet + facet normal 0.0419865 -0.00713148 -0.999093 + outer loop + vertex -793.617 274.248 305.699 + vertex -787.856 270.582 305.967 + vertex -795.655 263.257 305.692 + endloop + endfacet + facet normal 0.0416734 -0.00679754 -0.999108 + outer loop + vertex -795.655 263.257 305.692 + vertex -787.856 270.582 305.967 + vertex -789.816 259.358 305.962 + endloop + endfacet + facet normal 0.0195855 -0.00293951 -0.999804 + outer loop + vertex -787.856 270.582 305.967 + vertex -781.863 266.986 306.095 + vertex -789.816 259.358 305.962 + endloop + endfacet + facet normal 0.0193039 -0.00340884 -0.999808 + outer loop + vertex -787.856 270.582 305.967 + vertex -779.719 278.143 306.098 + vertex -781.863 266.986 306.095 + endloop + endfacet + facet normal 0.00739981 -0.00112115 -0.999972 + outer loop + vertex -779.719 278.143 306.098 + vertex -773.631 274.883 306.147 + vertex -781.863 266.986 306.095 + endloop + endfacet + facet normal 0.00720261 -0.000915584 -0.999974 + outer loop + vertex -781.863 266.986 306.095 + vertex -773.631 274.883 306.147 + vertex -775.676 263.467 306.143 + endloop + endfacet + facet normal 0.000260303 0.000327617 -1 + outer loop + vertex -773.631 274.883 306.147 + vertex -767.431 271.727 306.148 + vertex -775.676 263.467 306.143 + endloop + endfacet + facet normal 8.31092e-05 -2.04494e-05 -1 + outer loop + vertex -773.631 274.883 306.147 + vertex -765.318 283.298 306.148 + vertex -767.431 271.727 306.148 + endloop + endfacet + facet normal -0.00784203 0.00142655 -0.999968 + outer loop + vertex -765.318 283.298 306.148 + vertex -759.216 280.566 306.096 + vertex -767.431 271.727 306.148 + endloop + endfacet + facet normal -0.00782952 0.00141492 -0.999968 + outer loop + vertex -767.431 271.727 306.148 + vertex -759.216 280.566 306.096 + vertex -761.178 268.735 306.094 + endloop + endfacet + facet normal -0.0076799 0.00172757 -0.999969 + outer loop + vertex -767.431 271.727 306.148 + vertex -761.178 268.735 306.094 + vertex -769.359 260.063 306.142 + endloop + endfacet + facet normal -0.0203118 0.00348559 -0.999788 + outer loop + vertex -759.216 280.566 306.096 + vertex -753.122 277.999 305.963 + vertex -761.178 268.735 306.094 + endloop + endfacet + facet normal -0.0196439 0.00290462 -0.999803 + outer loop + vertex -761.178 268.735 306.094 + vertex -753.122 277.999 305.963 + vertex -754.919 265.914 305.963 + endloop + endfacet + facet normal -0.0388739 0.00576533 -0.999227 + outer loop + vertex -753.122 277.999 305.963 + vertex -747.054 275.595 305.713 + vertex -754.919 265.914 305.963 + endloop + endfacet + facet normal -0.0390252 0.00538299 -0.999224 + outer loop + vertex -753.122 277.999 305.963 + vertex -745.343 287.943 305.713 + vertex -747.054 275.595 305.713 + endloop + endfacet + facet normal -0.0656529 0.00907111 -0.997801 + outer loop + vertex -745.343 287.943 305.713 + vertex -739.535 285.931 305.312 + vertex -747.054 275.595 305.713 + endloop + endfacet + facet normal -0.0634955 0.0074958 -0.997954 + outer loop + vertex -747.054 275.595 305.713 + vertex -739.535 285.931 305.312 + vertex -741.04 273.348 305.314 + endloop + endfacet + facet normal -0.0980332 0.0116287 -0.995115 + outer loop + vertex -739.535 285.931 305.312 + vertex -733.839 284.054 304.729 + vertex -741.04 273.348 305.314 + endloop + endfacet + facet normal -0.0983736 0.0105894 -0.995093 + outer loop + vertex -739.535 285.931 305.312 + vertex -732.502 296.888 304.734 + vertex -733.839 284.054 304.729 + endloop + endfacet + facet normal -0.101549 0.0126454 -0.99475 + outer loop + vertex -737.978 298.542 305.314 + vertex -732.502 296.888 304.734 + vertex -739.535 285.931 305.312 + endloop + endfacet + facet normal -0.102032 0.0110334 -0.99472 + outer loop + vertex -737.978 298.542 305.314 + vertex -731.148 309.691 304.737 + vertex -732.502 296.888 304.734 + endloop + endfacet + facet normal -0.105694 0.0132984 -0.99431 + outer loop + vertex -736.395 311.113 305.314 + vertex -731.148 309.691 304.737 + vertex -737.978 298.542 305.314 + endloop + endfacet + facet normal -0.0679575 0.00854603 -0.997652 + outer loop + vertex -743.576 300.317 305.71 + vertex -736.395 311.113 305.314 + vertex -737.978 298.542 305.314 + endloop + endfacet + facet normal -0.0676687 0.00945939 -0.997663 + outer loop + vertex -743.576 300.317 305.71 + vertex -737.978 298.542 305.314 + vertex -745.343 287.943 305.713 + endloop + endfacet + facet normal -0.0403779 0.00556075 -0.999169 + outer loop + vertex -751.219 290.099 305.962 + vertex -743.576 300.317 305.71 + vertex -745.343 287.943 305.713 + endloop + endfacet + facet normal -0.041742 0.00658272 -0.999107 + outer loop + vertex -749.245 302.213 305.96 + vertex -743.576 300.317 305.71 + vertex -751.219 290.099 305.962 + endloop + endfacet + facet normal -0.0210094 0.00320428 -0.999774 + outer loop + vertex -757.134 292.404 306.094 + vertex -749.245 302.213 305.96 + vertex -751.219 290.099 305.962 + endloop + endfacet + facet normal -0.0208873 0.00351773 -0.999776 + outer loop + vertex -757.134 292.404 306.094 + vertex -751.219 290.099 305.962 + vertex -759.216 280.566 306.096 + endloop + endfacet + facet normal -0.0217561 0.00380504 -0.999756 + outer loop + vertex -754.969 304.239 306.092 + vertex -749.245 302.213 305.96 + vertex -757.134 292.404 306.094 + endloop + endfacet + facet normal -0.00816669 0.00131878 -0.999966 + outer loop + vertex -763.072 294.853 306.146 + vertex -754.969 304.239 306.092 + vertex -757.134 292.404 306.094 + endloop + endfacet + facet normal -0.00812566 0.00141829 -0.999966 + outer loop + vertex -763.072 294.853 306.146 + vertex -757.134 292.404 306.094 + vertex -765.318 283.298 306.148 + endloop + endfacet + facet normal 6.36546e-05 -0.000173476 -1 + outer loop + vertex -771.389 286.172 306.147 + vertex -763.072 294.853 306.146 + vertex -765.318 283.298 306.148 + endloop + endfacet + facet normal 0.000140068 -0.000246682 -1 + outer loop + vertex -768.999 297.426 306.144 + vertex -763.072 294.853 306.146 + vertex -771.389 286.172 306.147 + endloop + endfacet + facet normal 0.00767426 -0.00184681 -0.999969 + outer loop + vertex -777.361 289.147 306.095 + vertex -768.999 297.426 306.144 + vertex -771.389 286.172 306.147 + endloop + endfacet + facet normal 0.00764315 -0.00190927 -0.999969 + outer loop + vertex -777.361 289.147 306.095 + vertex -771.389 286.172 306.147 + vertex -779.719 278.143 306.098 + endloop + endfacet + facet normal 0.0194524 -0.0044393 -0.999801 + outer loop + vertex -785.621 281.48 305.969 + vertex -777.361 289.147 306.095 + vertex -779.719 278.143 306.098 + endloop + endfacet + facet normal 0.0197075 -0.00471413 -0.999795 + outer loop + vertex -783.172 292.189 305.966 + vertex -777.361 289.147 306.095 + vertex -785.621 281.48 305.969 + endloop + endfacet + facet normal 0.0406596 -0.00950473 -0.999128 + outer loop + vertex -791.306 284.882 305.705 + vertex -783.172 292.189 305.966 + vertex -785.621 281.48 305.969 + endloop + endfacet + facet normal 0.0413231 -0.00839443 -0.999111 + outer loop + vertex -791.306 284.882 305.705 + vertex -785.621 281.48 305.969 + vertex -793.617 274.248 305.699 + endloop + endfacet + facet normal 0.0759364 -0.0159194 -0.996986 + outer loop + vertex -799.146 278.008 305.218 + vertex -791.306 284.882 305.705 + vertex -793.617 274.248 305.699 + endloop + endfacet + facet normal 0.0758066 -0.0157705 -0.996998 + outer loop + vertex -796.765 288.371 305.235 + vertex -791.306 284.882 305.705 + vertex -799.146 278.008 305.218 + endloop + endfacet + facet normal 0.127192 -0.0275861 -0.991494 + outer loop + vertex -804.422 281.876 304.433 + vertex -796.765 288.371 305.235 + vertex -799.146 278.008 305.218 + endloop + endfacet + facet normal 0.129791 -0.0239912 -0.991251 + outer loop + vertex -804.422 281.876 304.433 + vertex -799.146 278.008 305.218 + vertex -806.576 271.365 304.405 + endloop + endfacet + facet normal 0.129777 -0.0239751 -0.991253 + outer loop + vertex -806.576 271.365 304.405 + vertex -799.146 278.008 305.218 + vertex -801.254 267.256 305.202 + endloop + endfacet + facet normal 0.127585 -0.0280567 -0.991431 + outer loop + vertex -801.989 291.961 304.461 + vertex -796.765 288.371 305.235 + vertex -804.422 281.876 304.433 + endloop + endfacet + facet normal 0.125488 -0.0311446 -0.991606 + outer loop + vertex -801.989 291.961 304.461 + vertex -794.166 298.477 305.246 + vertex -796.765 288.371 305.235 + endloop + endfacet + facet normal 0.0745894 -0.0180468 -0.997051 + outer loop + vertex -794.166 298.477 305.246 + vertex -788.777 295.293 305.707 + vertex -796.765 288.371 305.235 + endloop + endfacet + facet normal 0.0735509 -0.019811 -0.997095 + outer loop + vertex -794.166 298.477 305.246 + vertex -786.074 305.596 305.702 + vertex -788.777 295.293 305.707 + endloop + endfacet + facet normal 0.0411684 -0.011316 -0.999088 + outer loop + vertex -786.074 305.596 305.702 + vertex -780.555 302.816 305.961 + vertex -788.777 295.293 305.707 + endloop + endfacet + facet normal 0.0404314 -0.0105093 -0.999127 + outer loop + vertex -788.777 295.293 305.707 + vertex -780.555 302.816 305.961 + vertex -783.172 292.189 305.966 + endloop + endfacet + facet normal 0.0203231 -0.00555688 -0.999778 + outer loop + vertex -780.555 302.816 305.961 + vertex -774.849 300.089 306.092 + vertex -783.172 292.189 305.966 + endloop + endfacet + facet normal 0.0204923 -0.00520259 -0.999776 + outer loop + vertex -780.555 302.816 305.961 + vertex -772.22 310.989 306.089 + vertex -774.849 300.089 306.092 + endloop + endfacet + facet normal 0.0085355 -0.00231894 -0.999961 + outer loop + vertex -772.22 310.989 306.089 + vertex -766.503 308.648 306.143 + vertex -774.849 300.089 306.092 + endloop + endfacet + facet normal 0.00810677 -0.00190084 -0.999965 + outer loop + vertex -774.849 300.089 306.092 + vertex -766.503 308.648 306.143 + vertex -768.999 297.426 306.144 + endloop + endfacet + facet normal 0.000198237 -0.000141987 -1 + outer loop + vertex -766.503 308.648 306.143 + vertex -760.732 306.389 306.145 + vertex -768.999 297.426 306.144 + endloop + endfacet + facet normal 0.000202752 -0.000130451 -1 + outer loop + vertex -766.503 308.648 306.143 + vertex -758.328 317.845 306.144 + vertex -760.732 306.389 306.145 + endloop + endfacet + facet normal -0.00897664 0.00179571 -0.999958 + outer loop + vertex -758.328 317.845 306.144 + vertex -752.745 315.998 306.09 + vertex -760.732 306.389 306.145 + endloop + endfacet + facet normal -0.00859393 0.00147758 -0.999962 + outer loop + vertex -760.732 306.389 306.145 + vertex -752.745 315.998 306.09 + vertex -754.969 304.239 306.092 + endloop + endfacet + facet normal -0.0229762 0.00419796 -0.999727 + outer loop + vertex -752.745 315.998 306.09 + vertex -747.223 314.263 305.956 + vertex -754.969 304.239 306.092 + endloop + endfacet + facet normal -0.0231206 0.00373816 -0.999726 + outer loop + vertex -752.745 315.998 306.09 + vertex -745.171 326.18 305.953 + vertex -747.223 314.263 305.956 + endloop + endfacet + facet normal -0.0453075 0.00755891 -0.998944 + outer loop + vertex -745.171 326.18 305.953 + vertex -739.938 324.832 305.706 + vertex -747.223 314.263 305.956 + endloop + endfacet + facet normal -0.0434023 0.00624348 -0.999038 + outer loop + vertex -747.223 314.263 305.956 + vertex -739.938 324.832 305.706 + vertex -741.765 312.634 305.709 + endloop + endfacet + facet normal -0.0431931 0.00694505 -0.999043 + outer loop + vertex -747.223 314.263 305.956 + vertex -741.765 312.634 305.709 + vertex -749.245 302.213 305.96 + endloop + endfacet + facet normal -0.0729802 0.0106742 -0.997276 + outer loop + vertex -739.938 324.832 305.706 + vertex -734.797 323.566 305.316 + vertex -741.765 312.634 305.709 + endloop + endfacet + facet normal -0.0707573 0.0092511 -0.997451 + outer loop + vertex -741.765 312.634 305.709 + vertex -734.797 323.566 305.316 + vertex -736.395 311.113 305.314 + endloop + endfacet + facet normal -0.11042 0.0143402 -0.993782 + outer loop + vertex -734.797 323.566 305.316 + vertex -729.785 322.384 304.742 + vertex -736.395 311.113 305.314 + endloop + endfacet + facet normal -0.110677 0.0132448 -0.993768 + outer loop + vertex -734.797 323.566 305.316 + vertex -728.42 334.965 304.757 + vertex -729.785 322.384 304.742 + endloop + endfacet + facet normal -0.115674 0.0160705 -0.993157 + outer loop + vertex -733.194 335.902 305.329 + vertex -728.42 334.965 304.757 + vertex -734.797 323.566 305.316 + endloop + endfacet + facet normal -0.115959 0.0146108 -0.993146 + outer loop + vertex -733.194 335.902 305.329 + vertex -727.072 347.537 304.785 + vertex -728.42 334.965 304.757 + endloop + endfacet + facet normal -0.122207 0.0179359 -0.992342 + outer loop + vertex -731.607 348.227 305.356 + vertex -727.072 347.537 304.785 + vertex -733.194 335.902 305.329 + endloop + endfacet + facet normal -0.122324 0.0171718 -0.992342 + outer loop + vertex -731.607 348.227 305.356 + vertex -725.745 360.216 304.841 + vertex -727.072 347.537 304.785 + endloop + endfacet + facet normal -0.129029 0.0204889 -0.991429 + outer loop + vertex -730.037 360.66 305.409 + vertex -725.745 360.216 304.841 + vertex -731.607 348.227 305.356 + endloop + endfacet + facet normal -0.129117 0.0196407 -0.991435 + outer loop + vertex -730.037 360.66 305.409 + vertex -724.571 373.14 304.944 + vertex -725.745 360.216 304.841 + endloop + endfacet + facet normal -0.139996 0.0244641 -0.98985 + outer loop + vertex -728.634 373.332 305.523 + vertex -724.571 373.14 304.944 + vertex -730.037 360.66 305.409 + endloop + endfacet + facet normal -0.139676 0.0308237 -0.989717 + outer loop + vertex -728.634 373.332 305.523 + vertex -723.833 386.378 305.252 + vertex -724.571 373.14 304.944 + endloop + endfacet + facet normal -0.158934 0.0379764 -0.986558 + outer loop + vertex -727.734 386.305 305.878 + vertex -723.833 386.378 305.252 + vertex -728.634 373.332 305.523 + endloop + endfacet + facet normal -0.0730155 0.0105306 -0.997275 + outer loop + vertex -739.938 324.832 305.706 + vertex -733.194 335.902 305.329 + vertex -734.797 323.566 305.316 + endloop + endfacet + facet normal -0.0753343 0.0119497 -0.997087 + outer loop + vertex -738.101 336.908 305.711 + vertex -733.194 335.902 305.329 + vertex -739.938 324.832 305.706 + endloop + endfacet + facet normal -0.0753423 0.0119106 -0.997087 + outer loop + vertex -738.101 336.908 305.711 + vertex -731.607 348.227 305.356 + vertex -733.194 335.902 305.329 + endloop + endfacet + facet normal -0.0779638 0.0134216 -0.996866 + outer loop + vertex -736.266 348.964 305.73 + vertex -731.607 348.227 305.356 + vertex -738.101 336.908 305.711 + endloop + endfacet + facet normal -0.0463147 0.00860937 -0.99889 + outer loop + vertex -743.11 337.98 305.953 + vertex -736.266 348.964 305.73 + vertex -738.101 336.908 305.711 + endloop + endfacet + facet normal -0.0464245 0.00809662 -0.998889 + outer loop + vertex -743.11 337.98 305.953 + vertex -738.101 336.908 305.711 + vertex -745.171 326.18 305.953 + endloop + endfacet + facet normal -0.0240408 0.00418783 -0.999702 + outer loop + vertex -750.49 327.625 306.087 + vertex -743.11 337.98 305.953 + vertex -745.171 326.18 305.953 + endloop + endfacet + facet normal -0.0247869 0.00471986 -0.999682 + outer loop + vertex -748.223 339.132 306.085 + vertex -743.11 337.98 305.953 + vertex -750.49 327.625 306.087 + endloop + endfacet + facet normal -0.00986232 0.00177894 -0.99995 + outer loop + vertex -755.885 329.159 306.143 + vertex -748.223 339.132 306.085 + vertex -750.49 327.625 306.087 + endloop + endfacet + facet normal -0.00978299 0.00205805 -0.99995 + outer loop + vertex -755.885 329.159 306.143 + vertex -750.49 327.625 306.087 + vertex -758.328 317.845 306.144 + endloop + endfacet + facet normal 5.8609e-05 -6.66023e-05 -1 + outer loop + vertex -763.937 319.782 306.143 + vertex -755.885 329.159 306.143 + vertex -758.328 317.845 306.144 + endloop + endfacet + facet normal -0.000120046 8.6812e-05 -1 + outer loop + vertex -761.33 330.769 306.144 + vertex -755.885 329.159 306.143 + vertex -763.937 319.782 306.143 + endloop + endfacet + facet normal 0.00891998 -0.00205792 -0.999958 + outer loop + vertex -769.517 321.786 306.089 + vertex -761.33 330.769 306.144 + vertex -763.937 319.782 306.143 + endloop + endfacet + facet normal 0.00887229 -0.00219074 -0.999958 + outer loop + vertex -769.517 321.786 306.089 + vertex -763.937 319.782 306.143 + vertex -772.22 310.989 306.089 + endloop + endfacet + facet normal 0.0214099 -0.00533047 -0.999757 + outer loop + vertex -777.817 313.38 305.956 + vertex -769.517 321.786 306.089 + vertex -772.22 310.989 306.089 + endloop + endfacet + facet normal 0.0220872 -0.00599956 -0.999738 + outer loop + vertex -775 323.833 305.956 + vertex -769.517 321.786 306.089 + vertex -777.817 313.38 305.956 + endloop + endfacet + facet normal 0.0422239 -0.0114267 -0.999043 + outer loop + vertex -783.249 315.816 305.699 + vertex -775 323.833 305.956 + vertex -777.817 313.38 305.956 + endloop + endfacet + facet normal 0.042016 -0.0118906 -0.999046 + outer loop + vertex -783.249 315.816 305.699 + vertex -777.817 313.38 305.956 + vertex -786.074 305.596 305.702 + endloop + endfacet + facet normal 0.0742809 -0.020808 -0.99702 + outer loop + vertex -791.393 308.447 305.246 + vertex -783.249 315.816 305.699 + vertex -786.074 305.596 305.702 + endloop + endfacet + facet normal 0.0754983 -0.0221608 -0.9969 + outer loop + vertex -788.497 318.318 305.246 + vertex -783.249 315.816 305.699 + vertex -791.393 308.447 305.246 + endloop + endfacet + facet normal 0.124493 -0.0365359 -0.991548 + outer loop + vertex -796.51 311.38 304.495 + vertex -788.497 318.318 305.246 + vertex -791.393 308.447 305.246 + endloop + endfacet + facet normal 0.12525 -0.0352039 -0.991501 + outer loop + vertex -796.51 311.38 304.495 + vertex -791.393 308.447 305.246 + vertex -799.334 301.754 304.48 + endloop + endfacet + facet normal 0.124889 -0.0347686 -0.991561 + outer loop + vertex -799.334 301.754 304.48 + vertex -791.393 308.447 305.246 + vertex -794.166 298.477 305.246 + endloop + endfacet + facet normal 0.12703 -0.0395128 -0.991112 + outer loop + vertex -793.553 320.903 304.495 + vertex -788.497 318.318 305.246 + vertex -796.51 311.38 304.495 + endloop + endfacet + facet normal 0.127056 -0.0394612 -0.99111 + outer loop + vertex -793.553 320.903 304.495 + vertex -785.512 328.067 305.24 + vertex -788.497 318.318 305.246 + endloop + endfacet + facet normal 0.129649 -0.0424197 -0.990652 + outer loop + vertex -790.51 330.29 304.491 + vertex -785.512 328.067 305.24 + vertex -793.553 320.903 304.495 + endloop + endfacet + facet normal 0.130146 -0.0412981 -0.990634 + outer loop + vertex -790.51 330.29 304.491 + vertex -782.479 337.642 305.24 + vertex -785.512 328.067 305.24 + endloop + endfacet + facet normal 0.133021 -0.0444921 -0.990114 + outer loop + vertex -787.417 339.498 304.493 + vertex -782.479 337.642 305.24 + vertex -790.51 330.29 304.491 + endloop + endfacet + facet normal 0.13342 -0.0434281 -0.990108 + outer loop + vertex -787.417 339.498 304.493 + vertex -779.408 347.081 305.239 + vertex -782.479 337.642 305.24 + endloop + endfacet + facet normal 0.13659 -0.0468333 -0.98952 + outer loop + vertex -784.283 348.566 304.496 + vertex -779.408 347.081 305.239 + vertex -787.417 339.498 304.493 + endloop + endfacet + facet normal 0.137546 -0.0436991 -0.989531 + outer loop + vertex -784.283 348.566 304.496 + vertex -776.302 356.483 305.256 + vertex -779.408 347.081 305.239 + endloop + endfacet + facet normal 0.140286 -0.0465104 -0.989018 + outer loop + vertex -781.119 357.592 304.521 + vertex -776.302 356.483 305.256 + vertex -784.283 348.566 304.496 + endloop + endfacet + facet normal 0.141457 -0.0414605 -0.989076 + outer loop + vertex -781.119 357.592 304.521 + vertex -773.186 365.962 305.304 + vertex -776.302 356.483 305.256 + endloop + endfacet + facet normal 0.147144 -0.0469513 -0.988 + outer loop + vertex -777.962 366.688 304.558 + vertex -773.186 365.962 305.304 + vertex -781.119 357.592 304.521 + endloop + endfacet + facet normal 0.14918 -0.0337837 -0.988233 + outer loop + vertex -777.962 366.688 304.558 + vertex -770.248 375.612 305.418 + vertex -773.186 365.962 305.304 + endloop + endfacet + facet normal 0.158431 -0.0419482 -0.986479 + outer loop + vertex -775.001 375.936 304.641 + vertex -770.248 375.612 305.418 + vertex -777.962 366.688 304.558 + endloop + endfacet + facet normal 0.161185 -0.00258543 -0.986921 + outer loop + vertex -775.001 375.936 304.641 + vertex -768.045 385.454 305.752 + vertex -770.248 375.612 305.418 + endloop + endfacet + facet normal 0.159197 -0.00109482 -0.987246 + outer loop + vertex -772.465 385.352 305.039 + vertex -768.045 385.454 305.752 + vertex -775.001 375.936 304.641 + endloop + endfacet + facet normal 0.0755297 -0.0220947 -0.996899 + outer loop + vertex -788.497 318.318 305.246 + vertex -780.339 325.92 305.695 + vertex -783.249 315.816 305.699 + endloop + endfacet + facet normal 0.0775955 -0.024324 -0.996688 + outer loop + vertex -785.512 328.067 305.24 + vertex -780.339 325.92 305.695 + vertex -788.497 318.318 305.246 + endloop + endfacet + facet normal 0.0779661 -0.0234291 -0.996681 + outer loop + vertex -785.512 328.067 305.24 + vertex -777.38 335.861 305.693 + vertex -780.339 325.92 305.695 + endloop + endfacet + facet normal 0.0452019 -0.0136777 -0.998884 + outer loop + vertex -777.38 335.861 305.693 + vertex -772.134 334.132 305.954 + vertex -780.339 325.92 305.695 + endloop + endfacet + facet normal 0.0438895 -0.0123641 -0.99896 + outer loop + vertex -780.339 325.92 305.695 + vertex -772.134 334.132 305.954 + vertex -775 323.833 305.956 + endloop + endfacet + facet normal 0.0230254 -0.00655977 -0.999713 + outer loop + vertex -772.134 334.132 305.954 + vertex -766.769 332.436 306.089 + vertex -775 323.833 305.956 + endloop + endfacet + facet normal 0.0231633 -0.00612386 -0.999713 + outer loop + vertex -772.134 334.132 305.954 + vertex -763.996 342.948 306.089 + vertex -766.769 332.436 306.089 + endloop + endfacet + facet normal 0.00960516 -0.00254789 -0.999951 + outer loop + vertex -763.996 342.948 306.089 + vertex -758.703 341.63 306.143 + vertex -766.769 332.436 306.089 + endloop + endfacet + facet normal 0.00936641 -0.00233844 -0.999953 + outer loop + vertex -766.769 332.436 306.089 + vertex -758.703 341.63 306.143 + vertex -761.33 330.769 306.144 + endloop + endfacet + facet normal -0.000175144 -3.06926e-05 -1 + outer loop + vertex -758.703 341.63 306.143 + vertex -753.426 340.349 306.142 + vertex -761.33 330.769 306.144 + endloop + endfacet + facet normal -0.000137106 0.000126019 -1 + outer loop + vertex -758.703 341.63 306.143 + vertex -750.954 351.514 306.143 + vertex -753.426 340.349 306.142 + endloop + endfacet + facet normal -0.010362 0.0023895 -0.999943 + outer loop + vertex -750.954 351.514 306.143 + vertex -745.941 350.611 306.089 + vertex -753.426 340.349 306.142 + endloop + endfacet + facet normal -0.0103816 0.00240378 -0.999943 + outer loop + vertex -753.426 340.349 306.142 + vertex -745.941 350.611 306.089 + vertex -748.223 339.132 306.085 + endloop + endfacet + facet normal -0.0253427 0.00537739 -0.999664 + outer loop + vertex -745.941 350.611 306.089 + vertex -741.05 349.765 305.961 + vertex -748.223 339.132 306.085 + endloop + endfacet + facet normal -0.0251237 0.00664368 -0.999662 + outer loop + vertex -745.941 350.611 306.089 + vertex -739.003 361.655 305.988 + vertex -741.05 349.765 305.961 + endloop + endfacet + facet normal -0.0468671 0.0103865 -0.998847 + outer loop + vertex -739.003 361.655 305.988 + vertex -734.453 361.136 305.769 + vertex -741.05 349.765 305.961 + endloop + endfacet + facet normal -0.0463787 0.0101027 -0.998873 + outer loop + vertex -741.05 349.765 305.961 + vertex -734.453 361.136 305.769 + vertex -736.266 348.964 305.73 + endloop + endfacet + facet normal -0.0797617 0.0150692 -0.9967 + outer loop + vertex -734.453 361.136 305.769 + vertex -730.037 360.66 305.409 + vertex -736.266 348.964 305.73 + endloop + endfacet + facet normal -0.0794635 0.0178225 -0.996678 + outer loop + vertex -734.453 361.136 305.769 + vertex -728.634 373.332 305.523 + vertex -730.037 360.66 305.409 + endloop + endfacet + facet normal -0.08537 0.0206515 -0.996135 + outer loop + vertex -732.802 373.539 305.885 + vertex -728.634 373.332 305.523 + vertex -734.453 361.136 305.769 + endloop + endfacet + facet normal -0.0847292 0.0330829 -0.995855 + outer loop + vertex -732.802 373.539 305.885 + vertex -727.734 386.305 305.878 + vertex -728.634 373.332 305.523 + endloop + endfacet + facet normal -0.100383 0.0392985 -0.994172 + outer loop + vertex -731.559 386.23 306.261 + vertex -727.734 386.305 305.878 + vertex -732.802 373.539 305.885 + endloop + endfacet + facet normal -0.0482575 0.0343108 -0.998245 + outer loop + vertex -737.112 373.759 306.101 + vertex -731.559 386.23 306.261 + vertex -732.802 373.539 305.885 + endloop + endfacet + facet normal -0.0491618 0.0169771 -0.998647 + outer loop + vertex -737.112 373.759 306.101 + vertex -732.802 373.539 305.885 + vertex -739.003 361.655 305.988 + endloop + endfacet + facet normal -0.0240531 0.0130647 -0.999625 + outer loop + vertex -743.675 362.199 306.108 + vertex -737.112 373.759 306.101 + vertex -739.003 361.655 305.988 + endloop + endfacet + facet normal -0.0255521 0.0139158 -0.999577 + outer loop + vertex -741.578 373.998 306.218 + vertex -737.112 373.759 306.101 + vertex -743.675 362.199 306.108 + endloop + endfacet + facet normal -0.00935677 0.0110404 -0.999895 + outer loop + vertex -748.491 362.78 306.159 + vertex -741.578 373.998 306.218 + vertex -743.675 362.199 306.108 + endloop + endfacet + facet normal -0.010249 0.00365507 -0.999941 + outer loop + vertex -748.491 362.78 306.159 + vertex -743.675 362.199 306.108 + vertex -750.954 351.514 306.143 + endloop + endfacet + facet normal 0.000136159 0.00138424 -0.999999 + outer loop + vertex -756.06 352.457 306.144 + vertex -748.491 362.78 306.159 + vertex -750.954 351.514 306.143 + endloop + endfacet + facet normal 5.97229e-05 0.00144028 -0.999999 + outer loop + vertex -753.418 363.387 306.16 + vertex -748.491 362.78 306.159 + vertex -756.06 352.457 306.144 + endloop + endfacet + facet normal 0.0105092 -0.00108569 -0.999944 + outer loop + vertex -761.205 353.436 306.089 + vertex -753.418 363.387 306.16 + vertex -756.06 352.457 306.144 + endloop + endfacet + facet normal 0.010197 -0.00272814 -0.999944 + outer loop + vertex -761.205 353.436 306.089 + vertex -756.06 352.457 306.144 + vertex -763.996 342.948 306.089 + endloop + endfacet + facet normal 0.0241794 -0.00644911 -0.999687 + outer loop + vertex -769.242 344.293 305.953 + vertex -761.205 353.436 306.089 + vertex -763.996 342.948 306.089 + endloop + endfacet + facet normal 0.0246353 -0.00685015 -0.999673 + outer loop + vertex -766.323 354.419 305.956 + vertex -761.205 353.436 306.089 + vertex -769.242 344.293 305.953 + endloop + endfacet + facet normal 0.0469856 -0.0132947 -0.998807 + outer loop + vertex -774.39 345.661 305.693 + vertex -766.323 354.419 305.956 + vertex -769.242 344.293 305.953 + endloop + endfacet + facet normal 0.0467218 -0.0142874 -0.998806 + outer loop + vertex -774.39 345.661 305.693 + vertex -769.242 344.293 305.953 + vertex -777.38 335.861 305.693 + endloop + endfacet + facet normal 0.0801043 -0.0244733 -0.996486 + outer loop + vertex -782.479 337.642 305.24 + vertex -774.39 345.661 305.693 + vertex -777.38 335.861 305.693 + endloop + endfacet + facet normal 0.0824386 -0.0268424 -0.996235 + outer loop + vertex -779.408 347.081 305.239 + vertex -774.39 345.661 305.693 + vertex -782.479 337.642 305.24 + endloop + endfacet + facet normal 0.0829541 -0.0250224 -0.996239 + outer loop + vertex -779.408 347.081 305.239 + vertex -771.365 355.432 305.699 + vertex -774.39 345.661 305.693 + endloop + endfacet + facet normal 0.0839382 -0.0259762 -0.996132 + outer loop + vertex -776.302 356.483 305.256 + vertex -771.365 355.432 305.699 + vertex -779.408 347.081 305.239 + endloop + endfacet + facet normal 0.08477 -0.0220812 -0.996156 + outer loop + vertex -776.302 356.483 305.256 + vertex -768.325 365.281 305.74 + vertex -771.365 355.432 305.699 + endloop + endfacet + facet normal 0.0480477 -0.0107358 -0.998787 + outer loop + vertex -768.325 365.281 305.74 + vertex -763.392 364.639 305.984 + vertex -771.365 355.432 305.699 + endloop + endfacet + facet normal 0.0485571 -0.0111779 -0.998758 + outer loop + vertex -771.365 355.432 305.699 + vertex -763.392 364.639 305.984 + vertex -766.323 354.419 305.956 + endloop + endfacet + facet normal 0.0245209 -0.00428392 -0.99969 + outer loop + vertex -763.392 364.639 305.984 + vertex -758.403 364.006 306.109 + vertex -766.323 354.419 305.956 + endloop + endfacet + facet normal 0.0256464 0.00459271 -0.999661 + outer loop + vertex -763.392 364.639 305.984 + vertex -755.759 374.772 306.226 + vertex -758.403 364.006 306.109 + endloop + endfacet + facet normal 0.00940448 0.00858542 -0.999919 + outer loop + vertex -755.759 374.772 306.226 + vertex -750.915 374.509 306.27 + vertex -758.403 364.006 306.109 + endloop + endfacet + facet normal 0.0110892 0.00738413 -0.999911 + outer loop + vertex -758.403 364.006 306.109 + vertex -750.915 374.509 306.27 + vertex -753.418 363.387 306.16 + endloop + endfacet + facet normal 7.03238e-05 0.00986425 -0.999951 + outer loop + vertex -750.915 374.509 306.27 + vertex -746.176 374.25 306.267 + vertex -753.418 363.387 306.16 + endloop + endfacet + facet normal 0.00121908 0.0308268 -0.999524 + outer loop + vertex -750.915 374.509 306.27 + vertex -744.286 385.97 306.631 + vertex -746.176 374.25 306.267 + endloop + endfacet + facet normal -0.0077312 0.0322684 -0.999449 + outer loop + vertex -744.286 385.97 306.631 + vertex -739.917 386.061 306.6 + vertex -746.176 374.25 306.267 + endloop + endfacet + facet normal -0.00886649 0.0328693 -0.99942 + outer loop + vertex -746.176 374.25 306.267 + vertex -739.917 386.061 306.6 + vertex -741.578 373.998 306.218 + endloop + endfacet + facet normal -0.0257139 0.0351784 -0.99905 + outer loop + vertex -739.917 386.061 306.6 + vertex -735.788 386.146 306.497 + vertex -741.578 373.998 306.218 + endloop + endfacet + facet normal -0.000869505 0.0320337 -0.999486 + outer loop + vertex -748.869 385.873 306.632 + vertex -744.286 385.97 306.631 + vertex -750.915 374.509 306.27 + endloop + endfacet + facet normal 0.0105602 0.0299767 -0.999495 + outer loop + vertex -755.759 374.772 306.226 + vertex -748.869 385.873 306.632 + vertex -750.915 374.509 306.27 + endloop + endfacet + facet normal 0.00522286 0.0332868 -0.999432 + outer loop + vertex -753.737 385.769 306.603 + vertex -748.869 385.873 306.632 + vertex -755.759 374.772 306.226 + endloop + endfacet + facet normal 0.025275 0.0295941 -0.999242 + outer loop + vertex -760.636 375.036 306.111 + vertex -753.737 385.769 306.603 + vertex -755.759 374.772 306.226 + endloop + endfacet + facet normal 0.0233205 0.030851 -0.999252 + outer loop + vertex -758.566 385.664 306.487 + vertex -753.737 385.769 306.603 + vertex -760.636 375.036 306.111 + endloop + endfacet + facet normal 0.0513404 0.0253622 -0.998359 + outer loop + vertex -765.451 375.315 305.87 + vertex -758.566 385.664 306.487 + vertex -760.636 375.036 306.111 + endloop + endfacet + facet normal 0.0498144 -0.00127627 -0.998758 + outer loop + vertex -765.451 375.315 305.87 + vertex -760.636 375.036 306.111 + vertex -768.325 365.281 305.74 + endloop + endfacet + facet normal 0.0875369 -0.012118 -0.996088 + outer loop + vertex -773.186 365.962 305.304 + vertex -765.451 375.315 305.87 + vertex -768.325 365.281 305.74 + endloop + endfacet + facet normal 0.0928545 -0.0165488 -0.995542 + outer loop + vertex -770.248 375.612 305.418 + vertex -765.451 375.315 305.87 + vertex -773.186 365.962 305.304 + endloop + endfacet + facet normal 0.0947427 0.0141506 -0.995401 + outer loop + vertex -770.248 375.612 305.418 + vertex -762.992 385.567 306.25 + vertex -765.451 375.315 305.87 + endloop + endfacet + facet normal 0.0978378 0.0118722 -0.995132 + outer loop + vertex -768.045 385.454 305.752 + vertex -762.992 385.567 306.25 + vertex -770.248 375.612 305.418 + endloop + endfacet + facet normal 0.0529666 0.0242769 -0.998301 + outer loop + vertex -762.992 385.567 306.25 + vertex -758.566 385.664 306.487 + vertex -765.451 375.315 305.87 + endloop + endfacet + facet normal 0.0240009 0.0058332 -0.999695 + outer loop + vertex -760.636 375.036 306.111 + vertex -755.759 374.772 306.226 + vertex -763.392 364.639 305.984 + endloop + endfacet + facet normal 0.0493281 -0.000892013 -0.998782 + outer loop + vertex -768.325 365.281 305.74 + vertex -760.636 375.036 306.111 + vertex -763.392 364.639 305.984 + endloop + endfacet + facet normal 0.0859802 -0.0231855 -0.996027 + outer loop + vertex -773.186 365.962 305.304 + vertex -768.325 365.281 305.74 + vertex -776.302 356.483 305.256 + endloop + endfacet + facet normal 0.0479526 -0.0141871 -0.998749 + outer loop + vertex -771.365 355.432 305.699 + vertex -766.323 354.419 305.956 + vertex -774.39 345.661 305.693 + endloop + endfacet + facet normal 0.0250454 -0.00471747 -0.999675 + outer loop + vertex -766.323 354.419 305.956 + vertex -758.403 364.006 306.109 + vertex -761.205 353.436 306.089 + endloop + endfacet + facet normal 0.0100796 -0.000749454 -0.999949 + outer loop + vertex -758.403 364.006 306.109 + vertex -753.418 363.387 306.16 + vertex -761.205 353.436 306.089 + endloop + endfacet + facet normal 0.00101948 0.00923158 -0.999957 + outer loop + vertex -753.418 363.387 306.16 + vertex -746.176 374.25 306.267 + vertex -748.491 362.78 306.159 + endloop + endfacet + facet normal -0.0100435 0.0114635 -0.999884 + outer loop + vertex -746.176 374.25 306.267 + vertex -741.578 373.998 306.218 + vertex -748.491 362.78 306.159 + endloop + endfacet + facet normal -0.0244335 0.0345693 -0.999104 + outer loop + vertex -741.578 373.998 306.218 + vertex -735.788 386.146 306.497 + vertex -737.112 373.759 306.101 + endloop + endfacet + facet normal -0.0564339 0.0379446 -0.997685 + outer loop + vertex -735.788 386.146 306.497 + vertex -731.559 386.23 306.261 + vertex -737.112 373.759 306.101 + endloop + endfacet + facet normal -0.0462841 0.0154743 -0.998808 + outer loop + vertex -739.003 361.655 305.988 + vertex -732.802 373.539 305.885 + vertex -734.453 361.136 305.769 + endloop + endfacet + facet normal -0.0248229 0.00645466 -0.999671 + outer loop + vertex -743.675 362.199 306.108 + vertex -739.003 361.655 305.988 + vertex -745.941 350.611 306.089 + endloop + endfacet + facet normal -0.0101465 0.00358519 -0.999942 + outer loop + vertex -750.954 351.514 306.143 + vertex -743.675 362.199 306.108 + vertex -745.941 350.611 306.089 + endloop + endfacet + facet normal -0.000101442 9.80584e-05 -1 + outer loop + vertex -756.06 352.457 306.144 + vertex -750.954 351.514 306.143 + vertex -758.703 341.63 306.143 + endloop + endfacet + facet normal 0.00966982 -0.00228813 -0.999951 + outer loop + vertex -763.996 342.948 306.089 + vertex -756.06 352.457 306.144 + vertex -758.703 341.63 306.143 + endloop + endfacet + facet normal 0.0240522 -0.00694484 -0.999687 + outer loop + vertex -769.242 344.293 305.953 + vertex -763.996 342.948 306.089 + vertex -772.134 334.132 305.954 + endloop + endfacet + facet normal 0.0454167 -0.0130256 -0.998883 + outer loop + vertex -777.38 335.861 305.693 + vertex -769.242 344.293 305.953 + vertex -772.134 334.132 305.954 + endloop + endfacet + facet normal 0.0797978 -0.0253514 -0.996489 + outer loop + vertex -782.479 337.642 305.24 + vertex -777.38 335.861 305.693 + vertex -785.512 328.067 305.24 + endloop + endfacet + facet normal 0.0436723 -0.0129197 -0.998962 + outer loop + vertex -780.339 325.92 305.695 + vertex -775 323.833 305.956 + vertex -783.249 315.816 305.699 + endloop + endfacet + facet normal 0.0221801 -0.00575064 -0.999737 + outer loop + vertex -775 323.833 305.956 + vertex -766.769 332.436 306.089 + vertex -769.517 321.786 306.089 + endloop + endfacet + facet normal 0.00933616 -0.00243718 -0.999953 + outer loop + vertex -766.769 332.436 306.089 + vertex -761.33 330.769 306.144 + vertex -769.517 321.786 306.089 + endloop + endfacet + facet normal -0.000158787 -4.41887e-05 -1 + outer loop + vertex -761.33 330.769 306.144 + vertex -753.426 340.349 306.142 + vertex -755.885 329.159 306.143 + endloop + endfacet + facet normal -0.0104264 0.00221232 -0.999943 + outer loop + vertex -753.426 340.349 306.142 + vertex -748.223 339.132 306.085 + vertex -755.885 329.159 306.143 + endloop + endfacet + facet normal -0.0247317 0.00496504 -0.999682 + outer loop + vertex -748.223 339.132 306.085 + vertex -741.05 349.765 305.961 + vertex -743.11 337.98 305.953 + endloop + endfacet + facet normal -0.0465992 0.00878689 -0.998875 + outer loop + vertex -741.05 349.765 305.961 + vertex -736.266 348.964 305.73 + vertex -743.11 337.98 305.953 + endloop + endfacet + facet normal -0.0778637 0.0140538 -0.996865 + outer loop + vertex -736.266 348.964 305.73 + vertex -730.037 360.66 305.409 + vertex -731.607 348.227 305.356 + endloop + endfacet + facet normal -0.0453514 0.00738819 -0.998944 + outer loop + vertex -745.171 326.18 305.953 + vertex -738.101 336.908 305.711 + vertex -739.938 324.832 305.706 + endloop + endfacet + facet normal -0.0239877 0.0043834 -0.999703 + outer loop + vertex -750.49 327.625 306.087 + vertex -745.171 326.18 305.953 + vertex -752.745 315.998 306.09 + endloop + endfacet + facet normal -0.00907704 0.00149227 -0.999958 + outer loop + vertex -758.328 317.845 306.144 + vertex -750.49 327.625 306.087 + vertex -752.745 315.998 306.09 + endloop + endfacet + facet normal 7.55919e-05 -1.74213e-05 -1 + outer loop + vertex -763.937 319.782 306.143 + vertex -758.328 317.845 306.144 + vertex -766.503 308.648 306.143 + endloop + endfacet + facet normal 0.00866713 -0.00199747 -0.99996 + outer loop + vertex -772.22 310.989 306.089 + vertex -763.937 319.782 306.143 + vertex -766.503 308.648 306.143 + endloop + endfacet + facet normal 0.0211695 -0.00589336 -0.999759 + outer loop + vertex -777.817 313.38 305.956 + vertex -772.22 310.989 306.089 + vertex -780.555 302.816 305.961 + endloop + endfacet + facet normal 0.0412753 -0.0111036 -0.999086 + outer loop + vertex -786.074 305.596 305.702 + vertex -777.817 313.38 305.956 + vertex -780.555 302.816 305.961 + endloop + endfacet + facet normal 0.0743348 -0.020707 -0.997018 + outer loop + vertex -791.393 308.447 305.246 + vertex -786.074 305.596 305.702 + vertex -794.166 298.477 305.246 + endloop + endfacet + facet normal 0.126436 -0.0323018 -0.991449 + outer loop + vertex -799.334 301.754 304.48 + vertex -794.166 298.477 305.246 + vertex -801.989 291.961 304.461 + endloop + endfacet + facet normal 0.0744562 -0.0178922 -0.997064 + outer loop + vertex -796.765 288.371 305.235 + vertex -788.777 295.293 305.707 + vertex -791.306 284.882 305.705 + endloop + endfacet + facet normal 0.0408621 -0.00973063 -0.999117 + outer loop + vertex -788.777 295.293 305.707 + vertex -783.172 292.189 305.966 + vertex -791.306 284.882 305.705 + endloop + endfacet + facet normal 0.019642 -0.00483914 -0.999795 + outer loop + vertex -783.172 292.189 305.966 + vertex -774.849 300.089 306.092 + vertex -777.361 289.147 306.095 + endloop + endfacet + facet normal 0.00798736 -0.00216311 -0.999966 + outer loop + vertex -774.849 300.089 306.092 + vertex -768.999 297.426 306.144 + vertex -777.361 289.147 306.095 + endloop + endfacet + facet normal 0.000189158 -0.000133613 -1 + outer loop + vertex -768.999 297.426 306.144 + vertex -760.732 306.389 306.145 + vertex -763.072 294.853 306.146 + endloop + endfacet + facet normal -0.00853465 0.00163648 -0.999962 + outer loop + vertex -760.732 306.389 306.145 + vertex -754.969 304.239 306.092 + vertex -763.072 294.853 306.146 + endloop + endfacet + facet normal -0.021909 0.00337293 -0.999754 + outer loop + vertex -754.969 304.239 306.092 + vertex -747.223 314.263 305.956 + vertex -749.245 302.213 305.96 + endloop + endfacet + facet normal -0.0419254 0.00603371 -0.999103 + outer loop + vertex -749.245 302.213 305.96 + vertex -741.765 312.634 305.709 + vertex -743.576 300.317 305.71 + endloop + endfacet + facet normal -0.0704806 0.0102311 -0.997461 + outer loop + vertex -741.765 312.634 305.709 + vertex -736.395 311.113 305.314 + vertex -743.576 300.317 305.71 + endloop + endfacet + facet normal -0.106103 0.0117826 -0.994285 + outer loop + vertex -736.395 311.113 305.314 + vertex -729.785 322.384 304.742 + vertex -731.148 309.691 304.737 + endloop + endfacet + facet normal -0.0659362 0.0082508 -0.99779 + outer loop + vertex -745.343 287.943 305.713 + vertex -737.978 298.542 305.314 + vertex -739.535 285.931 305.312 + endloop + endfacet + facet normal -0.0401267 0.00624586 -0.999175 + outer loop + vertex -751.219 290.099 305.962 + vertex -745.343 287.943 305.713 + vertex -753.122 277.999 305.963 + endloop + endfacet + facet normal -0.020452 0.0031525 -0.999786 + outer loop + vertex -759.216 280.566 306.096 + vertex -751.219 290.099 305.962 + vertex -753.122 277.999 305.963 + endloop + endfacet + facet normal -0.00792605 0.00123888 -0.999968 + outer loop + vertex -765.318 283.298 306.148 + vertex -757.134 292.404 306.094 + vertex -759.216 280.566 306.096 + endloop + endfacet + facet normal 0.000119215 -5.61191e-05 -1 + outer loop + vertex -771.389 286.172 306.147 + vertex -765.318 283.298 306.148 + vertex -773.631 274.883 306.147 + endloop + endfacet + facet normal 0.00721546 -0.00146552 -0.999973 + outer loop + vertex -779.719 278.143 306.098 + vertex -771.389 286.172 306.147 + vertex -773.631 274.883 306.147 + endloop + endfacet + facet normal 0.0197584 -0.00389811 -0.999797 + outer loop + vertex -785.621 281.48 305.969 + vertex -779.719 278.143 306.098 + vertex -787.856 270.582 305.967 + endloop + endfacet + facet normal 0.0412416 -0.00830404 -0.999115 + outer loop + vertex -793.617 274.248 305.699 + vertex -785.621 281.48 305.969 + vertex -787.856 270.582 305.967 + endloop + endfacet + facet normal 0.0774354 -0.0137048 -0.996903 + outer loop + vertex -799.146 278.008 305.218 + vertex -793.617 274.248 305.699 + vertex -801.254 267.256 305.202 + endloop + endfacet + facet normal 0.130276 -0.0233185 -0.991203 + outer loop + vertex -806.576 271.365 304.405 + vertex -801.254 267.256 305.202 + vertex -808.452 260.41 304.417 + endloop + endfacet + facet normal 0.0775624 -0.0129059 -0.996904 + outer loop + vertex -803.058 256.073 305.209 + vertex -795.655 263.257 305.692 + vertex -797.399 251.841 305.704 + endloop + endfacet + facet normal 0.041293 -0.00736798 -0.99912 + outer loop + vertex -795.655 263.257 305.692 + vertex -789.816 259.358 305.962 + vertex -797.399 251.841 305.704 + endloop + endfacet + facet normal 0.0193722 -0.00271706 -0.999809 + outer loop + vertex -789.816 259.358 305.962 + vertex -781.863 266.986 306.095 + vertex -783.748 255.536 306.09 + endloop + endfacet + facet normal 0.00730753 -0.000731109 -0.999973 + outer loop + vertex -781.863 266.986 306.095 + vertex -775.676 263.467 306.143 + vertex -783.748 255.536 306.09 + endloop + endfacet + facet normal 0.000155573 0.000432147 -1 + outer loop + vertex -775.676 263.467 306.143 + vertex -767.431 271.727 306.148 + vertex -769.359 260.063 306.142 + endloop + endfacet + facet normal -0.00745797 0.00151818 -0.999971 + outer loop + vertex -769.359 260.063 306.142 + vertex -761.178 268.735 306.094 + vertex -762.976 256.827 306.09 + endloop + endfacet + facet normal -0.0194526 0.00332917 -0.999805 + outer loop + vertex -761.178 268.735 306.094 + vertex -754.919 265.914 305.963 + vertex -762.976 256.827 306.09 + endloop + endfacet + facet normal -0.0379645 0.00502551 -0.999266 + outer loop + vertex -754.919 265.914 305.963 + vertex -747.054 275.595 305.713 + vertex -748.674 263.278 305.713 + endloop + endfacet + facet normal -0.0631796 0.00834356 -0.997967 + outer loop + vertex -747.054 275.595 305.713 + vertex -741.04 273.348 305.314 + vertex -748.674 263.278 305.713 + endloop + endfacet + facet normal -0.0952292 0.00972631 -0.995408 + outer loop + vertex -741.04 273.348 305.314 + vertex -733.839 284.054 304.729 + vertex -735.136 271.253 304.728 + endloop + endfacet + facet normal -0.0601823 0.00683217 -0.998164 + outer loop + vertex -750.169 250.928 305.706 + vertex -742.477 260.814 305.31 + vertex -743.802 248.25 305.304 + endloop + endfacet + facet normal -0.0369636 0.00516069 -0.999303 + outer loop + vertex -756.573 253.783 305.958 + vertex -750.169 250.928 305.706 + vertex -758.04 241.484 305.948 + endloop + endfacet + facet normal -0.0190144 0.00301993 -0.999815 + outer loop + vertex -764.568 244.731 306.082 + vertex -756.573 253.783 305.958 + vertex -758.04 241.484 305.948 + endloop + endfacet + facet normal -0.00803661 0.000139954 -0.999968 + outer loop + vertex -771.062 248.177 306.135 + vertex -764.568 244.731 306.082 + vertex -772.531 235.993 306.145 + endloop + endfacet + facet normal -0.000738265 -0.000740041 -0.999999 + outer loop + vertex -779.026 239.792 306.147 + vertex -771.062 248.177 306.135 + vertex -772.531 235.993 306.145 + endloop + endfacet + facet normal 0.00610016 -0.00165367 -0.99998 + outer loop + vertex -785.371 243.714 306.102 + vertex -777.478 251.796 306.137 + vertex -779.026 239.792 306.147 + endloop + endfacet + facet normal 0.0154191 -0.00760198 -0.999852 + outer loop + vertex -791.507 247.727 305.977 + vertex -785.371 243.714 306.102 + vertex -792.972 235.831 306.045 + endloop + endfacet + facet normal 0.0372522 -0.0102883 -0.999253 + outer loop + vertex -798.925 240.135 305.778 + vertex -791.507 247.727 305.977 + vertex -792.972 235.831 306.045 + endloop + endfacet + facet normal 0.0664323 -0.0249334 -0.997479 + outer loop + vertex -804.626 244.623 305.286 + vertex -798.925 240.135 305.778 + vertex -806.075 233.351 305.472 + endloop + endfacet + facet normal 0.0958367 -0.0481666 -0.994231 + outer loop + vertex -811.514 238.281 304.709 + vertex -806.075 233.351 305.472 + vertex -813.047 228.203 305.049 + endloop + endfacet + facet normal 0.142305 -0.0550354 -0.988292 + outer loop + vertex -817.992 233.503 304.042 + vertex -811.514 238.281 304.709 + vertex -813.047 228.203 305.049 + endloop + endfacet + facet normal 0.148848 -0.0641168 -0.986779 + outer loop + vertex -816.573 243.072 303.634 + vertex -811.514 238.281 304.709 + vertex -817.992 233.503 304.042 + endloop + endfacet + facet normal 0.170018 -0.0412635 -0.984577 + outer loop + vertex -816.573 243.072 303.634 + vertex -810.053 249.213 304.503 + vertex -811.514 238.281 304.709 + endloop + endfacet + facet normal 0.175403 -0.0471512 -0.983367 + outer loop + vertex -815.179 253.78 303.369 + vertex -810.053 249.213 304.503 + vertex -816.573 243.072 303.634 + endloop + endfacet + facet normal 0.186588 -0.0342174 -0.981842 + outer loop + vertex -815.179 253.78 303.369 + vertex -808.452 260.41 304.417 + vertex -810.053 249.213 304.503 + endloop + endfacet + facet normal 0.190636 -0.0384713 -0.980907 + outer loop + vertex -813.479 264.805 303.267 + vertex -808.452 260.41 304.417 + vertex -815.179 253.78 303.369 + endloop + endfacet + facet normal 0.194199 -0.0342533 -0.980364 + outer loop + vertex -813.479 264.805 303.267 + vertex -806.576 271.365 304.405 + vertex -808.452 260.41 304.417 + endloop + endfacet + facet normal 0.197344 -0.0376936 -0.979609 + outer loop + vertex -811.594 275.524 303.235 + vertex -806.576 271.365 304.405 + vertex -813.479 264.805 303.267 + endloop + endfacet + facet normal 0.197226 -0.0378415 -0.979627 + outer loop + vertex -811.594 275.524 303.235 + vertex -804.422 281.876 304.433 + vertex -806.576 271.365 304.405 + endloop + endfacet + facet normal 0.201013 -0.0422967 -0.978675 + outer loop + vertex -809.413 285.791 303.239 + vertex -804.422 281.876 304.433 + vertex -811.594 275.524 303.235 + endloop + endfacet + facet normal 0.198764 -0.0452632 -0.979002 + outer loop + vertex -809.413 285.791 303.239 + vertex -801.989 291.961 304.461 + vertex -804.422 281.876 304.433 + endloop + endfacet + facet normal 0.200687 -0.0476781 -0.978494 + outer loop + vertex -806.955 295.598 303.265 + vertex -801.989 291.961 304.461 + vertex -809.413 285.791 303.239 + endloop + endfacet + facet normal 0.19784 -0.0516894 -0.97887 + outer loop + vertex -806.955 295.598 303.265 + vertex -799.334 301.754 304.48 + vertex -801.989 291.961 304.461 + endloop + endfacet + facet normal 0.198815 -0.0529484 -0.978606 + outer loop + vertex -804.273 305.07 303.298 + vertex -799.334 301.754 304.48 + vertex -806.955 295.598 303.265 + endloop + endfacet + facet normal 0.196701 -0.056185 -0.978852 + outer loop + vertex -804.273 305.07 303.298 + vertex -796.51 311.38 304.495 + vertex -799.334 301.754 304.48 + endloop + endfacet + facet normal 0.199803 -0.0601658 -0.977987 + outer loop + vertex -801.403 314.363 303.312 + vertex -796.51 311.38 304.495 + vertex -804.273 305.07 303.298 + endloop + endfacet + facet normal 0.198826 -0.0618065 -0.978084 + outer loop + vertex -801.403 314.363 303.312 + vertex -793.553 320.903 304.495 + vertex -796.51 311.38 304.495 + endloop + endfacet + facet normal 0.202085 -0.0658879 -0.977149 + outer loop + vertex -798.401 323.54 303.314 + vertex -793.553 320.903 304.495 + vertex -801.403 314.363 303.312 + endloop + endfacet + facet normal 0.202084 -0.0658892 -0.977149 + outer loop + vertex -798.401 323.54 303.314 + vertex -790.51 330.29 304.491 + vertex -793.553 320.903 304.495 + endloop + endfacet + facet normal 0.204979 -0.0694215 -0.976301 + outer loop + vertex -795.317 332.565 303.32 + vertex -790.51 330.29 304.491 + vertex -798.401 323.54 303.314 + endloop + endfacet + facet normal 0.205283 -0.0687716 -0.976283 + outer loop + vertex -795.317 332.565 303.32 + vertex -787.417 339.498 304.493 + vertex -790.51 330.29 304.491 + endloop + endfacet + facet normal 0.210563 -0.0750575 -0.974695 + outer loop + vertex -792.173 341.403 303.319 + vertex -787.417 339.498 304.493 + vertex -795.317 332.565 303.32 + endloop + endfacet + facet normal 0.211491 -0.0727271 -0.97467 + outer loop + vertex -792.173 341.403 303.319 + vertex -784.283 348.566 304.496 + vertex -787.417 339.498 304.493 + endloop + endfacet + facet normal 0.215993 -0.077915 -0.973281 + outer loop + vertex -788.996 350.089 303.328 + vertex -784.283 348.566 304.496 + vertex -792.173 341.403 303.319 + endloop + endfacet + facet normal 0.217398 -0.0735835 -0.973305 + outer loop + vertex -788.996 350.089 303.328 + vertex -781.119 357.592 304.521 + vertex -784.283 348.566 304.496 + endloop + endfacet + facet normal 0.224648 -0.0815573 -0.971021 + outer loop + vertex -785.802 358.728 303.342 + vertex -781.119 357.592 304.521 + vertex -788.996 350.089 303.328 + endloop + endfacet + facet normal 0.226393 -0.0745294 -0.97118 + outer loop + vertex -785.802 358.728 303.342 + vertex -777.962 366.688 304.558 + vertex -781.119 357.592 304.521 + endloop + endfacet + facet normal 0.236214 -0.0846895 -0.968003 + outer loop + vertex -782.634 367.418 303.354 + vertex -777.962 366.688 304.558 + vertex -785.802 358.728 303.342 + endloop + endfacet + facet normal 0.239003 -0.0679033 -0.968642 + outer loop + vertex -782.634 367.418 303.354 + vertex -775.001 375.936 304.641 + vertex -777.962 366.688 304.558 + endloop + endfacet + facet normal 0.249457 -0.0777832 -0.965257 + outer loop + vertex -779.641 376.241 303.417 + vertex -775.001 375.936 304.641 + vertex -782.634 367.418 303.354 + endloop + endfacet + facet normal 0.253238 -0.0272791 -0.967019 + outer loop + vertex -779.641 376.241 303.417 + vertex -772.465 385.352 305.039 + vertex -775.001 375.936 304.641 + endloop + endfacet + facet normal 0.2399 -0.0161236 -0.970664 + outer loop + vertex -777.328 385.236 303.839 + vertex -772.465 385.352 305.039 + vertex -779.641 376.241 303.417 + endloop + endfacet + facet normal 0.0487375 -0.0324541 -0.998284 + outer loop + vertex -807.377 222.96 305.789 + vertex -800.304 228.628 305.95 + vertex -801.496 218.114 306.234 + endloop + endfacet + facet normal 0.020616 -0.0292944 -0.999358 + outer loop + vertex -800.304 228.628 305.95 + vertex -794.303 224.159 306.205 + vertex -801.496 218.114 306.234 + endloop + endfacet + facet normal 0.00882624 -0.013954 -0.999864 + outer loop + vertex -794.303 224.159 306.205 + vertex -786.789 231.651 306.167 + vertex -788.062 219.864 306.32 + endloop + endfacet + facet normal -0.00156872 -0.0125846 -0.99992 + outer loop + vertex -788.062 219.864 306.32 + vertex -780.384 227.585 306.211 + vertex -781.606 215.669 306.363 + endloop + endfacet + facet normal -0.0135415 -0.0214649 -0.999678 + outer loop + vertex -782.64 204.838 306.61 + vertex -775.004 211.594 306.361 + vertex -775.998 200.702 306.609 + endloop + endfacet + facet normal -0.00751507 -0.0119742 -0.9999 + outer loop + vertex -780.384 227.585 306.211 + vertex -773.826 223.635 306.209 + vertex -781.606 215.669 306.363 + endloop + endfacet + facet normal -0.0103265 -0.00409502 -0.999938 + outer loop + vertex -773.826 223.635 306.209 + vertex -765.95 232.367 306.092 + vertex -767.181 219.853 306.156 + endloop + endfacet + facet normal -0.0216996 -0.00297506 -0.99976 + outer loop + vertex -765.95 232.367 306.092 + vertex -759.324 228.937 305.958 + vertex -767.181 219.853 306.156 + endloop + endfacet + facet normal -0.0363087 0.00244325 -0.999338 + outer loop + vertex -759.324 228.937 305.958 + vertex -751.501 238.427 305.697 + vertex -752.684 225.705 305.709 + endloop + endfacet + facet normal -0.0594082 0.00459348 -0.998223 + outer loop + vertex -751.501 238.427 305.697 + vertex -744.999 235.56 305.297 + vertex -752.684 225.705 305.709 + endloop + endfacet + facet normal -0.0872233 0.00729079 -0.996162 + outer loop + vertex -744.999 235.56 305.297 + vertex -737.541 245.744 304.718 + vertex -738.614 232.901 304.718 + endloop + endfacet + facet normal -0.128255 0.00903526 -0.9917 + outer loop + vertex -738.614 232.901 304.718 + vertex -731.444 243.424 303.887 + vertex -732.401 230.476 303.893 + endloop + endfacet + facet normal -0.086558 -0.000620588 -0.996247 + outer loop + vertex -747.141 209.824 305.403 + vertex -739.623 219.945 304.744 + vertex -740.567 206.987 304.834 + endloop + endfacet + facet normal -0.0580191 -0.0020435 -0.998313 + outer loop + vertex -753.792 212.917 305.784 + vertex -746.093 222.699 305.316 + vertex -747.141 209.824 305.403 + endloop + endfacet + facet normal -0.0407206 -0.00959882 -0.999124 + outer loop + vertex -760.491 216.274 306.024 + vertex -753.792 212.917 305.784 + vertex -761.605 204.004 306.188 + endloop + endfacet + facet normal -0.0244205 -0.0110861 -0.99964 + outer loop + vertex -768.323 207.71 306.311 + vertex -760.491 216.274 306.024 + vertex -761.605 204.004 306.188 + endloop + endfacet + facet normal -0.0197198 -0.0208991 -0.999587 + outer loop + vertex -775.004 211.594 306.361 + vertex -768.323 207.71 306.311 + vertex -775.998 200.702 306.609 + endloop + endfacet + facet normal -0.0206535 -0.0328855 -0.999246 + outer loop + vertex -782.64 204.838 306.61 + vertex -775.998 200.702 306.609 + vertex -783.138 195.969 306.912 + endloop + endfacet + facet normal -0.0602098 -0.0970253 -0.993459 + outer loop + vertex -785.505 188.443 307.363 + vertex -780.313 185.387 307.347 + vertex -779.486 183.806 307.451 + endloop + endfacet + facet normal -0.0284884 -0.0452622 -0.998569 + outer loop + vertex -782.365 189.437 307.183 + vertex -776.498 191.822 306.908 + vertex -776.097 185.525 307.182 + endloop + endfacet + facet normal -0.0611361 -0.0975026 -0.993356 + outer loop + vertex -780.313 185.387 307.347 + vertex -775.011 181.819 307.371 + vertex -779.486 183.806 307.451 + endloop + endfacet + facet normal -0.0611952 -0.0976364 -0.993339 + outer loop + vertex -771.413 178.812 307.445 + vertex -779.486 183.806 307.451 + vertex -775.011 181.819 307.371 + endloop + endfacet + facet normal -0.127414 -0.204717 -0.970493 + outer loop + vertex -772.71 179.339 307.504 + vertex -779.486 183.806 307.451 + vertex -771.413 178.812 307.445 + endloop + endfacet + facet normal -0.118808 -0.191707 -0.974235 + outer loop + vertex -780.582 184.126 307.522 + vertex -779.486 183.806 307.451 + vertex -772.71 179.339 307.504 + endloop + endfacet + facet normal -0.0323629 -0.0455032 -0.99844 + outer loop + vertex -776.498 191.822 306.908 + vertex -769.846 187.807 306.875 + vertex -776.097 185.525 307.182 + endloop + endfacet + facet normal -0.0343947 -0.0328054 -0.99887 + outer loop + vertex -769.317 196.729 306.564 + vertex -762.574 192.992 306.454 + vertex -769.846 187.807 306.875 + endloop + endfacet + facet normal -0.0419819 -0.0222408 -0.998871 + outer loop + vertex -762.574 192.992 306.454 + vertex -754.869 200.587 305.961 + vertex -755.787 189.495 306.247 + endloop + endfacet + facet normal -0.0619932 -0.0223345 -0.997827 + outer loop + vertex -755.787 189.495 306.247 + vertex -748.144 197.398 305.595 + vertex -748.933 186.234 305.894 + endloop + endfacet + facet normal -0.0930948 -0.0200731 -0.995455 + outer loop + vertex -748.144 197.398 305.595 + vertex -741.376 194.422 305.022 + vertex -748.933 186.234 305.894 + endloop + endfacet + facet normal -0.127887 -0.00920081 -0.991746 + outer loop + vertex -741.376 194.422 305.022 + vertex -734.023 204.278 303.983 + vertex -734.473 191.296 304.161 + endloop + endfacet + facet normal -0.0912141 -0.04356 -0.994878 + outer loop + vertex -749.216 177.068 306.265 + vertex -741.896 182.94 305.337 + vertex -741.856 173.432 305.75 + endloop + endfacet + facet normal -0.0730279 -0.0542851 -0.995851 + outer loop + vertex -756.185 180.489 306.59 + vertex -749.216 177.068 306.265 + vertex -755.694 174.134 306.9 + endloop + endfacet + facet normal -0.0678504 -0.0843618 -0.994122 + outer loop + vertex -760.072 173.417 307.226 + vertex -754.527 170.669 307.081 + vertex -754.763 169.733 307.176 + endloop + endfacet + facet normal -0.0634129 -0.0890007 -0.994011 + outer loop + vertex -765.642 176.514 307.304 + vertex -760.072 173.417 307.226 + vertex -763.793 174.511 307.365 + endloop + endfacet + facet normal -0.0406284 -0.0488578 -0.997979 + outer loop + vertex -769.368 180.958 307.187 + vertex -763.024 183.997 306.78 + vertex -762.197 177.526 307.063 + endloop + endfacet + facet normal -0.0426068 -0.0669454 -0.996847 + outer loop + vertex -769.661 178.282 307.38 + vertex -775.011 181.819 307.371 + vertex -769.368 180.958 307.187 + endloop + endfacet + facet normal -0.0692427 -0.10723 -0.99182 + outer loop + vertex -775.011 181.819 307.371 + vertex -769.661 178.282 307.38 + vertex -771.413 178.812 307.445 + endloop + endfacet + facet normal -0.128989 -0.208715 -0.969433 + outer loop + vertex -772.71 179.339 307.504 + vertex -771.413 178.812 307.445 + vertex -764.671 174.714 307.43 + endloop + endfacet + facet normal -0.0837915 -0.129862 -0.987985 + outer loop + vertex -764.898 174.085 307.532 + vertex -772.71 179.339 307.504 + vertex -764.671 174.714 307.43 + endloop + endfacet + facet normal -0.0806108 -0.125137 -0.988859 + outer loop + vertex -772.978 178.707 307.606 + vertex -772.71 179.339 307.504 + vertex -764.898 174.085 307.532 + endloop + endfacet + facet normal -0.105 -0.136419 -0.985071 + outer loop + vertex -748.24 165.313 307.076 + vertex -756.393 170.247 307.262 + vertex -747.853 165.9 306.954 + endloop + endfacet + facet normal -0.0993053 -0.126939 -0.986927 + outer loop + vertex -756.655 169.625 307.368 + vertex -756.393 170.247 307.262 + vertex -748.24 165.313 307.076 + endloop + endfacet + facet normal -0.0888406 -0.128011 -0.987786 + outer loop + vertex -764.898 174.085 307.532 + vertex -764.671 174.714 307.43 + vertex -756.655 169.625 307.368 + endloop + endfacet + facet normal -0.0885951 -0.143919 -0.985616 + outer loop + vertex -773 174.847 308.125 + vertex -772.943 177.046 307.799 + vertex -764.844 170.207 308.069 + endloop + endfacet + facet normal -0.0891078 -0.143899 -0.985572 + outer loop + vertex -773 174.847 308.125 + vertex -780.887 181.855 307.815 + vertex -772.943 177.046 307.799 + endloop + endfacet + facet normal -0.0880871 -0.142761 -0.98583 + outer loop + vertex -780.973 179.664 308.14 + vertex -780.887 181.855 307.815 + vertex -773 174.847 308.125 + endloop + endfacet + facet normal -0.0887501 -0.142727 -0.985775 + outer loop + vertex -780.973 179.664 308.14 + vertex -788.597 186.825 307.789 + vertex -780.887 181.855 307.815 + endloop + endfacet + facet normal -0.0715984 -0.116143 -0.990648 + outer loop + vertex -788.597 186.825 307.789 + vertex -788.59 188.485 307.594 + vertex -780.887 181.855 307.815 + endloop + endfacet + facet normal -0.0706728 -0.115074 -0.99084 + outer loop + vertex -780.887 181.855 307.815 + vertex -788.59 188.485 307.594 + vertex -780.89 183.509 307.623 + endloop + endfacet + facet normal -0.0683059 -0.116184 -0.990876 + outer loop + vertex -788.597 186.825 307.789 + vertex -796.016 193.593 307.507 + vertex -788.59 188.485 307.594 + endloop + endfacet + facet normal -0.0715139 -0.120834 -0.990093 + outer loop + vertex -796.016 193.593 307.507 + vertex -795.746 194.217 307.411 + vertex -788.59 188.485 307.594 + endloop + endfacet + facet normal -0.0726573 -0.122253 -0.989836 + outer loop + vertex -788.59 188.485 307.594 + vertex -795.746 194.217 307.411 + vertex -788.256 189.074 307.497 + endloop + endfacet + facet normal -0.0657392 -0.123353 -0.990183 + outer loop + vertex -796.016 193.593 307.507 + vertex -802.882 199.454 307.233 + vertex -795.746 194.217 307.411 + endloop + endfacet + facet normal -0.0684531 -0.127028 -0.989534 + outer loop + vertex -802.882 199.454 307.233 + vertex -802.048 199.151 307.214 + vertex -795.746 194.217 307.411 + endloop + endfacet + facet normal -0.10128 -0.168594 -0.980469 + outer loop + vertex -795.746 194.217 307.411 + vertex -802.048 199.151 307.214 + vertex -794.487 193.681 307.374 + endloop + endfacet + facet normal -0.0793117 -0.157197 -0.984377 + outer loop + vertex -802.882 199.454 307.233 + vertex -808.581 204.289 306.92 + vertex -802.048 199.151 307.214 + endloop + endfacet + facet normal -0.0527552 -0.126294 -0.990589 + outer loop + vertex -809.715 204.833 306.911 + vertex -808.581 204.289 306.92 + vertex -802.882 199.454 307.233 + endloop + endfacet + facet normal -0.0567236 -0.131284 -0.989721 + outer loop + vertex -803.15 198.828 307.331 + vertex -809.715 204.833 306.911 + vertex -802.882 199.454 307.233 + endloop + endfacet + facet normal -0.0704218 -0.146054 -0.986767 + outer loop + vertex -810.031 204.198 307.027 + vertex -809.715 204.833 306.911 + vertex -803.15 198.828 307.331 + endloop + endfacet + facet normal -0.060477 -0.133448 -0.989209 + outer loop + vertex -803.222 197.18 307.558 + vertex -810.031 204.198 307.027 + vertex -803.15 198.828 307.331 + endloop + endfacet + facet normal -0.0757252 -0.132656 -0.988265 + outer loop + vertex -803.222 197.18 307.558 + vertex -803.15 198.828 307.331 + vertex -796.039 191.936 307.712 + endloop + endfacet + facet normal -0.0882494 -0.149709 -0.984784 + outer loop + vertex -796.202 189.755 308.058 + vertex -803.222 197.18 307.558 + vertex -796.039 191.936 307.712 + endloop + endfacet + facet normal -0.0939725 -0.14921 -0.98433 + outer loop + vertex -796.202 189.755 308.058 + vertex -796.039 191.936 307.712 + vertex -788.713 184.635 308.119 + endloop + endfacet + facet normal -0.0883358 -0.143629 -0.985681 + outer loop + vertex -788.713 184.635 308.119 + vertex -796.039 191.936 307.712 + vertex -788.597 186.825 307.789 + endloop + endfacet + facet normal -0.0990012 -0.1597 -0.982189 + outer loop + vertex -803.445 195.007 307.934 + vertex -803.222 197.18 307.558 + vertex -796.202 189.755 308.058 + endloop + endfacet + facet normal -0.0864845 -0.161148 -0.983134 + outer loop + vertex -803.445 195.007 307.934 + vertex -810.174 202.547 307.29 + vertex -803.222 197.18 307.558 + endloop + endfacet + facet normal -0.105006 -0.177285 -0.978542 + outer loop + vertex -810.476 200.398 307.712 + vertex -810.174 202.547 307.29 + vertex -803.445 195.007 307.934 + endloop + endfacet + facet normal -0.135471 -0.216539 -0.966829 + outer loop + vertex -804.043 192.901 308.489 + vertex -810.476 200.398 307.712 + vertex -803.445 195.007 307.934 + endloop + endfacet + facet normal -0.142174 -0.214501 -0.966321 + outer loop + vertex -804.043 192.901 308.489 + vertex -803.445 195.007 307.934 + vertex -796.739 187.638 308.583 + endloop + endfacet + facet normal -0.133278 -0.206668 -0.969291 + outer loop + vertex -796.739 187.638 308.583 + vertex -803.445 195.007 307.934 + vertex -796.202 189.755 308.058 + endloop + endfacet + facet normal -0.13454 -0.206323 -0.96919 + outer loop + vertex -796.739 187.638 308.583 + vertex -796.202 189.755 308.058 + vertex -789.199 182.51 308.628 + endloop + endfacet + facet normal -0.130616 -0.202633 -0.970505 + outer loop + vertex -789.199 182.51 308.628 + vertex -796.202 189.755 308.058 + vertex -788.713 184.635 308.119 + endloop + endfacet + facet normal -0.128325 -0.2032 -0.970692 + outer loop + vertex -789.199 182.51 308.628 + vertex -788.713 184.635 308.119 + vertex -781.411 177.524 308.642 + endloop + endfacet + facet normal -0.127089 -0.201961 -0.971113 + outer loop + vertex -781.411 177.524 308.642 + vertex -788.713 184.635 308.119 + vertex -780.973 179.664 308.14 + endloop + endfacet + facet normal -0.123124 -0.202848 -0.971439 + outer loop + vertex -781.411 177.524 308.642 + vertex -780.973 179.664 308.14 + vertex -773.411 172.708 308.634 + endloop + endfacet + facet normal -0.126557 -0.206495 -0.970228 + outer loop + vertex -773.411 172.708 308.634 + vertex -780.973 179.664 308.14 + vertex -773 174.847 308.125 + endloop + endfacet + facet normal -0.122986 -0.207251 -0.970526 + outer loop + vertex -773.411 172.708 308.634 + vertex -773 174.847 308.125 + vertex -765.233 168.055 308.591 + endloop + endfacet + facet normal -0.127177 -0.211935 -0.968973 + outer loop + vertex -765.233 168.055 308.591 + vertex -773 174.847 308.125 + vertex -764.844 170.207 308.069 + endloop + endfacet + facet normal -0.12543 -0.212287 -0.969124 + outer loop + vertex -765.233 168.055 308.591 + vertex -764.844 170.207 308.069 + vertex -756.915 163.571 308.497 + endloop + endfacet + facet normal -0.135087 -0.223578 -0.965279 + outer loop + vertex -756.915 163.571 308.497 + vertex -764.844 170.207 308.069 + vertex -756.545 165.74 307.942 + endloop + endfacet + facet normal -0.134376 -0.223717 -0.965347 + outer loop + vertex -756.915 163.571 308.497 + vertex -756.545 165.74 307.942 + vertex -748.481 159.248 308.324 + endloop + endfacet + facet normal -0.150834 -0.243733 -0.958041 + outer loop + vertex -748.481 159.248 308.324 + vertex -756.545 165.74 307.942 + vertex -748.11 161.424 307.713 + endloop + endfacet + facet normal -0.151109 -0.243678 -0.958012 + outer loop + vertex -748.481 159.248 308.324 + vertex -748.11 161.424 307.713 + vertex -739.875 155.01 308.045 + endloop + endfacet + facet normal -0.171301 -0.269071 -0.947764 + outer loop + vertex -739.875 155.01 308.045 + vertex -748.11 161.424 307.713 + vertex -739.47 157.176 307.357 + endloop + endfacet + facet normal -0.169883 -0.269389 -0.947929 + outer loop + vertex -739.875 155.01 308.045 + vertex -739.47 157.176 307.357 + vertex -731.025 150.781 307.661 + endloop + endfacet + facet normal -0.19876 -0.306707 -0.93082 + outer loop + vertex -731.025 150.781 307.661 + vertex -739.47 157.176 307.357 + vertex -730.541 152.905 306.858 + endloop + endfacet + facet normal -0.194536 -0.307863 -0.93133 + outer loop + vertex -731.025 150.781 307.661 + vertex -730.541 152.905 306.858 + vertex -722.008 146.561 307.172 + endloop + endfacet + facet normal -0.149701 -0.228252 -0.962024 + outer loop + vertex -811.16 198.328 308.309 + vertex -810.476 200.398 307.712 + vertex -804.043 192.901 308.489 + endloop + endfacet + facet normal -0.13412 -0.233687 -0.963017 + outer loop + vertex -811.16 198.328 308.309 + vertex -817.364 205.974 307.318 + vertex -810.476 200.398 307.712 + endloop + endfacet + facet normal -0.107278 -0.201279 -0.973642 + outer loop + vertex -817.364 205.974 307.318 + vertex -816.952 208.07 306.839 + vertex -810.476 200.398 307.712 + endloop + endfacet + facet normal -0.0715075 -0.208707 -0.97536 + outer loop + vertex -817.364 205.974 307.318 + vertex -823.642 213.813 306.101 + vertex -816.952 208.07 306.839 + endloop + endfacet + facet normal -0.073894 -0.211391 -0.974604 + outer loop + vertex -823.642 213.813 306.101 + vertex -823.281 215.402 305.729 + vertex -816.952 208.07 306.839 + endloop + endfacet + facet normal -0.0232879 -0.2229 -0.974563 + outer loop + vertex -823.642 213.813 306.101 + vertex -829.783 221.338 304.526 + vertex -823.281 215.402 305.729 + endloop + endfacet + facet normal -0.0502196 -0.250817 -0.966731 + outer loop + vertex -829.783 221.338 304.526 + vertex -829.33 222.109 304.303 + vertex -823.281 215.402 305.729 + endloop + endfacet + facet normal -0.158653 -0.252492 -0.954504 + outer loop + vertex -818.177 203.985 307.979 + vertex -817.364 205.974 307.318 + vertex -811.16 198.328 308.309 + endloop + endfacet + facet normal -0.133835 -0.262963 -0.955478 + outer loop + vertex -818.177 203.985 307.979 + vertex -824.226 211.833 306.667 + vertex -817.364 205.974 307.318 + endloop + endfacet + facet normal -0.114759 -0.24152 -0.963586 + outer loop + vertex -824.226 211.833 306.667 + vertex -823.642 213.813 306.101 + vertex -817.364 205.974 307.318 + endloop + endfacet + facet normal -0.0703493 -0.254855 -0.964417 + outer loop + vertex -824.226 211.833 306.667 + vertex -830.331 219.835 304.997 + vertex -823.642 213.813 306.101 + endloop + endfacet + facet normal -0.0845773 -0.269704 -0.959222 + outer loop + vertex -830.331 219.835 304.997 + vertex -829.783 221.338 304.526 + vertex -823.642 213.813 306.101 + endloop + endfacet + facet normal -0.0821524 -0.180804 -0.980082 + outer loop + vertex -810.476 200.398 307.712 + vertex -816.952 208.07 306.839 + vertex -810.174 202.547 307.29 + endloop + endfacet + facet normal -0.0757353 -0.173085 -0.981991 + outer loop + vertex -816.952 208.07 306.839 + vertex -816.709 209.704 306.532 + vertex -810.174 202.547 307.29 + endloop + endfacet + facet normal -0.0523574 -0.152262 -0.986952 + outer loop + vertex -810.174 202.547 307.29 + vertex -816.709 209.704 306.532 + vertex -810.031 204.198 307.027 + endloop + endfacet + facet normal -0.0649492 -0.167248 -0.983773 + outer loop + vertex -816.709 209.704 306.532 + vertex -816.312 210.338 306.398 + vertex -810.031 204.198 307.027 + endloop + endfacet + facet normal -0.0384199 -0.183526 -0.982264 + outer loop + vertex -816.709 209.704 306.532 + vertex -822.763 216.016 305.59 + vertex -816.312 210.338 306.398 + endloop + endfacet + facet normal 0.0193489 -0.119381 -0.99266 + outer loop + vertex -822.763 216.016 305.59 + vertex -821.6 215.428 305.683 + vertex -816.312 210.338 306.398 + endloop + endfacet + facet normal -0.06742 -0.207175 -0.975978 + outer loop + vertex -816.312 210.338 306.398 + vertex -821.6 215.428 305.683 + vertex -815.476 210.131 306.385 + endloop + endfacet + facet normal -0.0554425 -0.158243 -0.985842 + outer loop + vertex -816.312 210.338 306.398 + vertex -815.476 210.131 306.385 + vertex -809.715 204.833 306.911 + endloop + endfacet + facet normal -0.0420768 -0.237323 -0.970519 + outer loop + vertex -822.763 216.016 305.59 + vertex -827.992 221.421 304.495 + vertex -821.6 215.428 305.683 + endloop + endfacet + facet normal -0.0418003 -0.186659 -0.981535 + outer loop + vertex -823.281 215.402 305.729 + vertex -822.763 216.016 305.59 + vertex -816.709 209.704 306.532 + endloop + endfacet + facet normal -0.00754398 -0.214448 -0.976706 + outer loop + vertex -823.281 215.402 305.729 + vertex -829.33 222.109 304.303 + vertex -822.763 216.016 305.59 + endloop + endfacet + facet normal 0.0776798 -0.125206 -0.989085 + outer loop + vertex -829.33 222.109 304.303 + vertex -827.992 221.421 304.495 + vertex -822.763 216.016 305.59 + endloop + endfacet + facet normal -0.0352341 -0.179315 -0.983161 + outer loop + vertex -816.952 208.07 306.839 + vertex -823.281 215.402 305.729 + vertex -816.709 209.704 306.532 + endloop + endfacet + facet normal -0.0645554 -0.121257 -0.99052 + outer loop + vertex -796.039 191.936 307.712 + vertex -803.15 198.828 307.331 + vertex -796.016 193.593 307.507 + endloop + endfacet + facet normal -0.0776818 -0.149872 -0.985649 + outer loop + vertex -810.174 202.547 307.29 + vertex -810.031 204.198 307.027 + vertex -803.222 197.18 307.558 + endloop + endfacet + facet normal -0.0525843 -0.154882 -0.986533 + outer loop + vertex -810.031 204.198 307.027 + vertex -816.312 210.338 306.398 + vertex -809.715 204.833 306.911 + endloop + endfacet + facet normal -0.0813706 -0.185779 -0.979217 + outer loop + vertex -809.715 204.833 306.911 + vertex -815.476 210.131 306.385 + vertex -808.581 204.289 306.92 + endloop + endfacet + facet normal -0.0682846 -0.126309 -0.989638 + outer loop + vertex -803.15 198.828 307.331 + vertex -802.882 199.454 307.233 + vertex -796.016 193.593 307.507 + endloop + endfacet + facet normal -0.0728009 -0.121073 -0.98997 + outer loop + vertex -796.039 191.936 307.712 + vertex -796.016 193.593 307.507 + vertex -788.597 186.825 307.789 + endloop + endfacet + facet normal -0.0895326 -0.143551 -0.985585 + outer loop + vertex -788.713 184.635 308.119 + vertex -788.597 186.825 307.789 + vertex -780.973 179.664 308.14 + endloop + endfacet + facet normal -0.0787999 -0.121962 -0.989402 + outer loop + vertex -764.817 172.414 307.731 + vertex -772.978 178.707 307.606 + vertex -764.898 174.085 307.532 + endloop + endfacet + facet normal -0.0716659 -0.115068 -0.990769 + outer loop + vertex -780.887 181.855 307.815 + vertex -780.89 183.509 307.623 + vertex -772.943 177.046 307.799 + endloop + endfacet + facet normal -0.0788263 -0.125901 -0.988906 + outer loop + vertex -772.978 178.707 307.606 + vertex -780.582 184.126 307.522 + vertex -772.71 179.339 307.504 + endloop + endfacet + facet normal -0.0746034 -0.12115 -0.989827 + outer loop + vertex -788.59 188.485 307.594 + vertex -788.256 189.074 307.497 + vertex -780.89 183.509 307.623 + endloop + endfacet + facet normal -0.117704 -0.187719 -0.975145 + outer loop + vertex -780.582 184.126 307.522 + vertex -787.031 188.559 307.447 + vertex -779.486 183.806 307.451 + endloop + endfacet + facet normal -0.0961336 -0.156328 -0.983016 + outer loop + vertex -795.746 194.217 307.411 + vertex -794.487 193.681 307.374 + vertex -788.256 189.074 307.497 + endloop + endfacet + facet normal -0.0338382 -0.0656413 -0.997269 + outer loop + vertex -790.787 191.625 307.364 + vertex -794.539 194.743 307.286 + vertex -789.373 193.577 307.187 + endloop + endfacet + facet normal -0.0260576 -0.0469854 -0.998556 + outer loop + vertex -789.729 200.36 306.877 + vertex -783.138 195.969 306.912 + vertex -789.373 193.577 307.187 + endloop + endfacet + facet normal -0.00986439 -0.0342256 -0.999365 + outer loop + vertex -796.117 204.82 306.788 + vertex -789.138 209.182 306.569 + vertex -789.729 200.36 306.877 + endloop + endfacet + facet normal 0.00407365 -0.0372508 -0.999298 + outer loop + vertex -802.24 209.41 306.591 + vertex -795.438 213.57 306.464 + vertex -796.117 204.82 306.788 + endloop + endfacet + facet normal 0.112307 -0.127484 -0.985462 + outer loop + vertex -825.42 226.89 303.699 + vertex -823.543 230.996 303.382 + vertex -820.246 225.284 304.496 + endloop + endfacet +endsolid diff --git a/noether_examples/meshes/outputs/output_4.stl b/noether_examples/meshes/outputs/output_4.stl new file mode 100644 index 00000000..af4cda40 --- /dev/null +++ b/noether_examples/meshes/outputs/output_4.stl @@ -0,0 +1,71458 @@ +solid ascii + facet normal 0.0702212 -0.820696 0.567034 + outer loop + vertex 495.752 66.9947 38.8697 + vertex 493.602 66.3397 38.1879 + vertex 497.079 67.3563 39.2288 + endloop + endfacet + facet normal 0.201936 -0.955269 0.216065 + outer loop + vertex 495.752 66.9947 38.8697 + vertex 497.079 67.3563 39.2288 + vertex 495.666 66.9795 38.883 + endloop + endfacet + facet normal 0.204192 -0.949833 0.236901 + outer loop + vertex 495.666 66.9795 38.883 + vertex 492.311 66.0124 37.8978 + vertex 495.752 66.9947 38.8697 + endloop + endfacet + facet normal 0.175379 -0.936396 0.30398 + outer loop + vertex 498.983 67.9652 40.0058 + vertex 495.666 66.9795 38.883 + vertex 497.079 67.3563 39.2288 + endloop + endfacet + facet normal 0.0335742 -0.824978 0.564167 + outer loop + vertex 497.079 67.3563 39.2288 + vertex 496.202 66.9098 38.6281 + vertex 498.983 67.9652 40.0058 + endloop + endfacet + facet normal 0.0324421 -0.823981 0.565688 + outer loop + vertex 495.261 65.9457 37.2777 + vertex 498.983 67.9652 40.0058 + vertex 496.202 66.9098 38.6281 + endloop + endfacet + facet normal 0.0892274 -0.83895 0.536844 + outer loop + vertex 493.162 65.8142 37.4211 + vertex 495.261 65.9457 37.2777 + vertex 496.202 66.9098 38.6281 + endloop + endfacet + facet normal 0.092384 -0.841938 0.531607 + outer loop + vertex 492.642 65.9224 37.6828 + vertex 493.162 65.8142 37.4211 + vertex 496.202 66.9098 38.6281 + endloop + endfacet + facet normal 0.0997812 -0.851882 0.51414 + outer loop + vertex 496.202 66.9098 38.6281 + vertex 493.602 66.3397 38.1879 + vertex 492.642 65.9224 37.6828 + endloop + endfacet + facet normal 0.117515 -0.863669 0.490169 + outer loop + vertex 493.602 66.3397 38.1879 + vertex 487.028 64.4231 36.3869 + vertex 492.642 65.9224 37.6828 + endloop + endfacet + facet normal 0.101012 -0.832446 0.544822 + outer loop + vertex 492.642 65.9224 37.6828 + vertex 487.422 64.2611 36.1122 + vertex 493.162 65.8142 37.4211 + endloop + endfacet + facet normal 0.090262 -0.811868 0.576821 + outer loop + vertex 493.162 65.8142 37.4211 + vertex 488.351 64.043 35.6811 + vertex 495.261 65.9457 37.2777 + endloop + endfacet + facet normal 0.101472 -0.860775 0.498769 + outer loop + vertex 499.375 65.9509 36.4498 + vertex 498.983 67.9652 40.0058 + vertex 495.261 65.9457 37.2777 + endloop + endfacet + facet normal 0.149458 -0.853172 0.499759 + outer loop + vertex 498.983 67.9652 40.0058 + vertex 499.375 65.9509 36.4498 + vertex 505.895 68.0592 38.0992 + endloop + endfacet + facet normal 0.14066 -0.873062 0.46688 + outer loop + vertex 505.895 68.0592 38.0992 + vertex 506.457 69.0406 39.7648 + vertex 498.983 67.9652 40.0058 + endloop + endfacet + facet normal 0.144385 -0.924562 0.352616 + outer loop + vertex 503.615 68.9543 40.7024 + vertex 498.983 67.9652 40.0058 + vertex 506.457 69.0406 39.7648 + endloop + endfacet + facet normal 0.166425 -0.873124 0.458211 + outer loop + vertex 505.895 68.0592 38.0992 + vertex 513.57 69.7847 38.5995 + vertex 506.457 69.0406 39.7648 + endloop + endfacet + facet normal 0.161221 -0.897245 0.411047 + outer loop + vertex 506.457 69.0406 39.7648 + vertex 513.57 69.7847 38.5995 + vertex 513.922 70.392 39.7872 + endloop + endfacet + facet normal 0.184394 -0.89615 0.403626 + outer loop + vertex 513.57 69.7847 38.5995 + vertex 523.628 71.8877 38.674 + vertex 513.922 70.392 39.7872 + endloop + endfacet + facet normal 0.182266 -0.915162 0.359523 + outer loop + vertex 513.922 70.392 39.7872 + vertex 523.628 71.8877 38.674 + vertex 524.54 72.4415 39.6209 + endloop + endfacet + facet normal 0.204433 -0.918004 0.339819 + outer loop + vertex 523.628 71.8877 38.674 + vertex 535.746 74.5107 38.4691 + vertex 524.54 72.4415 39.6209 + endloop + endfacet + facet normal 0.204624 -0.915756 0.345716 + outer loop + vertex 524.54 72.4415 39.6209 + vertex 535.746 74.5107 38.4691 + vertex 536.904 75.1334 39.4336 + endloop + endfacet + facet normal 0.225871 -0.919237 0.322469 + outer loop + vertex 535.746 74.5107 38.4691 + vertex 548.656 77.5497 38.0898 + vertex 536.904 75.1334 39.4336 + endloop + endfacet + facet normal 0.227132 -0.905843 0.357575 + outer loop + vertex 536.904 75.1334 39.4336 + vertex 548.656 77.5497 38.0898 + vertex 549.947 78.2557 39.0584 + endloop + endfacet + facet normal 0.248593 -0.909946 0.331963 + outer loop + vertex 548.656 77.5497 38.0898 + vertex 561.63 80.9088 37.5818 + vertex 549.947 78.2557 39.0584 + endloop + endfacet + facet normal 0.250146 -0.89204 0.376419 + outer loop + vertex 549.947 78.2557 39.0584 + vertex 561.63 80.9088 37.5818 + vertex 562.956 81.6895 38.5507 + endloop + endfacet + facet normal 0.26869 -0.895794 0.354059 + outer loop + vertex 561.63 80.9088 37.5818 + vertex 574.388 84.5149 37.0237 + vertex 562.956 81.6895 38.5507 + endloop + endfacet + facet normal 0.269607 -0.882133 0.386205 + outer loop + vertex 562.956 81.6895 38.5507 + vertex 574.388 84.5149 37.0237 + vertex 575.664 85.313 37.9558 + endloop + endfacet + facet normal 0.283955 -0.884989 0.369003 + outer loop + vertex 574.388 84.5149 37.0237 + vertex 586.282 88.1236 36.5254 + vertex 575.664 85.313 37.9558 + endloop + endfacet + facet normal 0.284223 -0.879292 0.382183 + outer loop + vertex 575.664 85.313 37.9558 + vertex 586.282 88.1236 36.5254 + vertex 587.426 88.8346 37.3104 + endloop + endfacet + facet normal 0.296742 -0.881908 0.366309 + outer loop + vertex 586.282 88.1236 36.5254 + vertex 596.043 91.2647 36.1808 + vertex 587.426 88.8346 37.3104 + endloop + endfacet + facet normal 0.296594 -0.88612 0.356123 + outer loop + vertex 587.426 88.8346 37.3104 + vertex 596.043 91.2647 36.1808 + vertex 595.798 91.4215 36.7747 + endloop + endfacet + facet normal 0.308241 -0.880764 0.359502 + outer loop + vertex 595.798 91.4215 36.7747 + vertex 596.043 91.2647 36.1808 + vertex 602.747 93.5799 36.1049 + endloop + endfacet + facet normal 0.309253 -0.903542 0.296606 + outer loop + vertex 602.747 93.5799 36.1049 + vertex 599.76 92.7284 36.6254 + vertex 595.798 91.4215 36.7747 + endloop + endfacet + facet normal 0.309479 -0.904635 0.293017 + outer loop + vertex 599.76 92.7284 36.6254 + vertex 595.822 91.5103 37.0237 + vertex 595.798 91.4215 36.7747 + endloop + endfacet + facet normal 0.308357 -0.87408 0.375366 + outer loop + vertex 595.822 91.5103 37.0237 + vertex 599.76 92.7284 36.6254 + vertex 599.113 92.7218 37.1412 + endloop + endfacet + facet normal 0.305441 -0.867773 0.392014 + outer loop + vertex 595.822 91.5103 37.0237 + vertex 599.113 92.7218 37.1412 + vertex 592.693 90.8922 38.0932 + endloop + endfacet + facet normal 0.3 -0.879563 0.369282 + outer loop + vertex 591.631 90.197 37.3007 + vertex 595.822 91.5103 37.0237 + vertex 592.693 90.8922 38.0932 + endloop + endfacet + facet normal 0.2949 -0.87871 0.375371 + outer loop + vertex 586.761 88.7837 37.8178 + vertex 591.631 90.197 37.3007 + vertex 592.693 90.8922 38.0932 + endloop + endfacet + facet normal 0.295738 -0.880447 0.370612 + outer loop + vertex 592.693 90.8922 38.0932 + vertex 583.628 88.2701 39.0982 + vertex 586.761 88.7837 37.8178 + endloop + endfacet + facet normal 0.28854 -0.891816 0.348437 + outer loop + vertex 579.711 86.6942 38.3082 + vertex 586.761 88.7837 37.8178 + vertex 583.628 88.2701 39.0982 + endloop + endfacet + facet normal 0.290445 -0.91216 0.289147 + outer loop + vertex 586.761 88.7837 37.8178 + vertex 579.711 86.6942 38.3082 + vertex 587.426 88.8346 37.3104 + endloop + endfacet + facet normal 0.29588 -0.892018 0.341699 + outer loop + vertex 592.693 90.8922 38.0932 + vertex 589.619 90.8935 40.759 + vertex 583.628 88.2701 39.0982 + endloop + endfacet + facet normal 0.296242 -0.892255 0.340767 + outer loop + vertex 583.628 88.2701 39.0982 + vertex 589.619 90.8935 40.759 + vertex 581.34 88.5769 41.8899 + endloop + endfacet + facet normal 0.286108 -0.898421 0.33314 + outer loop + vertex 583.628 88.2701 39.0982 + vertex 581.34 88.5769 41.8899 + vertex 573.689 85.4608 40.0577 + endloop + endfacet + facet normal 0.288089 -0.899902 0.327386 + outer loop + vertex 572.879 86.9314 44.8125 + vertex 573.689 85.4608 40.0577 + vertex 581.34 88.5769 41.8899 + endloop + endfacet + facet normal 0.285739 -0.903887 0.318341 + outer loop + vertex 581.672 89.7701 44.9806 + vertex 572.879 86.9314 44.8125 + vertex 581.34 88.5769 41.8899 + endloop + endfacet + facet normal 0.297131 -0.901026 0.316015 + outer loop + vertex 581.34 88.5769 41.8899 + vertex 587.924 91.7004 44.6059 + vertex 581.672 89.7701 44.9806 + endloop + endfacet + facet normal 0.29789 -0.907102 0.297367 + outer loop + vertex 581.672 89.7701 44.9806 + vertex 587.924 91.7004 44.6059 + vertex 584.613 92.5437 50.4945 + endloop + endfacet + facet normal 0.307314 -0.902418 0.301994 + outer loop + vertex 587.924 91.7004 44.6059 + vertex 593.644 94.9384 48.4606 + vertex 584.613 92.5437 50.4945 + endloop + endfacet + facet normal 0.30525 -0.908362 0.285834 + outer loop + vertex 592.868 95.9827 52.6077 + vertex 584.613 92.5437 50.4945 + vertex 593.644 94.9384 48.4606 + endloop + endfacet + facet normal 0.310637 -0.906374 0.286341 + outer loop + vertex 593.644 94.9384 48.4606 + vertex 597.6 97.7514 53.0733 + vertex 592.868 95.9827 52.6077 + endloop + endfacet + facet normal 0.31435 -0.911105 0.266592 + outer loop + vertex 592.868 95.9827 52.6077 + vertex 597.6 97.7514 53.0733 + vertex 592.471 97.6312 58.7101 + endloop + endfacet + facet normal 0.31668 -0.909665 0.268743 + outer loop + vertex 597.6 97.7514 53.0733 + vertex 600.009 100.32 58.9278 + vertex 592.471 97.6312 58.7101 + endloop + endfacet + facet normal 0.319193 -0.914948 0.246953 + outer loop + vertex 600.009 100.32 58.9278 + vertex 596.15 101.762 69.2582 + vertex 592.471 97.6312 58.7101 + endloop + endfacet + facet normal 0.307648 -0.917526 0.25199 + outer loop + vertex 588.948 98.54 66.3207 + vertex 592.471 97.6312 58.7101 + vertex 596.15 101.762 69.2582 + endloop + endfacet + facet normal 0.316843 -0.919708 0.231837 + outer loop + vertex 589.615 100.875 74.6721 + vertex 588.948 98.54 66.3207 + vertex 596.15 101.762 69.2582 + endloop + endfacet + facet normal 0.313193 -0.922153 0.227031 + outer loop + vertex 596.15 101.762 69.2582 + vertex 596.038 104.437 80.2793 + vertex 589.615 100.875 74.6721 + endloop + endfacet + facet normal 0.327793 -0.921185 0.209692 + outer loop + vertex 590.201 103.502 85.2953 + vertex 589.615 100.875 74.6721 + vertex 596.038 104.437 80.2793 + endloop + endfacet + facet normal 0.324804 -0.923107 0.205856 + outer loop + vertex 596.038 104.437 80.2793 + vertex 596.549 106.448 88.4932 + vertex 590.201 103.502 85.2953 + endloop + endfacet + facet normal 0.335325 -0.923663 0.185485 + outer loop + vertex 596.549 106.448 88.4932 + vertex 594.687 107.316 96.181 + vertex 590.201 103.502 85.2953 + endloop + endfacet + facet normal 0.324311 -0.926466 0.191006 + outer loop + vertex 587.667 104.217 93.069 + vertex 590.201 103.502 85.2953 + vertex 594.687 107.316 96.181 + endloop + endfacet + facet normal 0.33344 -0.927122 0.171064 + outer loop + vertex 589.511 106.663 102.731 + vertex 587.667 104.217 93.069 + vertex 594.687 107.316 96.181 + endloop + endfacet + facet normal 0.334437 -0.926607 0.171904 + outer loop + vertex 594.687 107.316 96.181 + vertex 595.884 109.458 105.397 + vertex 589.511 106.663 102.731 + endloop + endfacet + facet normal 0.34297 -0.926983 0.1519 + outer loop + vertex 595.884 109.458 105.397 + vertex 594.825 110.243 112.581 + vertex 589.511 106.663 102.731 + endloop + endfacet + facet normal 0.339548 -0.927884 0.154073 + outer loop + vertex 588.329 107.872 112.612 + vertex 589.511 106.663 102.731 + vertex 594.825 110.243 112.581 + endloop + endfacet + facet normal 0.340447 -0.9306 0.134463 + outer loop + vertex 594.825 110.243 112.581 + vertex 594.143 111.287 121.529 + vertex 588.329 107.872 112.612 + endloop + endfacet + facet normal 0.34062 -0.930555 0.134333 + outer loop + vertex 587.554 108.872 121.508 + vertex 588.329 107.872 112.612 + vertex 594.143 111.287 121.529 + endloop + endfacet + facet normal 0.341575 -0.932975 0.113512 + outer loop + vertex 594.143 111.287 121.529 + vertex 593.348 112.205 131.468 + vertex 587.554 108.872 121.508 + endloop + endfacet + facet normal 0.336651 -0.934353 0.116838 + outer loop + vertex 586.351 109.326 128.602 + vertex 587.554 108.872 121.508 + vertex 593.348 112.205 131.468 + endloop + endfacet + facet normal 0.345658 -0.933628 0.0941211 + outer loop + vertex 588.788 111.198 138.223 + vertex 586.351 109.326 128.602 + vertex 593.348 112.205 131.468 + endloop + endfacet + facet normal 0.346243 -0.933368 0.0945553 + outer loop + vertex 593.348 112.205 131.468 + vertex 595.176 113.848 140.985 + vertex 588.788 111.198 138.223 + endloop + endfacet + facet normal 0.356214 -0.931781 0.0699725 + outer loop + vertex 595.176 113.848 140.985 + vertex 594.384 114.089 148.23 + vertex 588.788 111.198 138.223 + endloop + endfacet + facet normal 0.350631 -0.933615 0.073625 + outer loop + vertex 588.031 111.704 148.242 + vertex 588.788 111.198 138.223 + vertex 594.384 114.089 148.23 + endloop + endfacet + facet normal 0.351095 -0.934975 0.050529 + outer loop + vertex 594.384 114.089 148.23 + vertex 593.988 114.422 157.153 + vertex 588.031 111.704 148.242 + endloop + endfacet + facet normal 0.351009 -0.935004 0.0505952 + outer loop + vertex 587.616 112.046 157.447 + vertex 588.031 111.704 148.242 + vertex 593.988 114.422 157.153 + endloop + endfacet + facet normal 0.350421 -0.936156 0.0285876 + outer loop + vertex 593.988 114.422 157.153 + vertex 593.639 114.571 166.304 + vertex 587.616 112.046 157.447 + endloop + endfacet + facet normal 0.349237 -0.936569 0.0295104 + outer loop + vertex 587.052 112.112 166.224 + vertex 587.616 112.046 157.447 + vertex 593.639 114.571 166.304 + endloop + endfacet + facet normal 0.349649 -0.936868 0.00482223 + outer loop + vertex 593.639 114.571 166.304 + vertex 592.78 114.301 176.156 + vertex 587.052 112.112 166.224 + endloop + endfacet + facet normal 0.339615 -0.940495 0.0114088 + outer loop + vertex 585.696 111.704 172.981 + vertex 587.052 112.112 166.224 + vertex 592.78 114.301 176.156 + endloop + endfacet + facet normal 0.348637 -0.937188 -0.0114285 + outer loop + vertex 587.44 112.252 181.24 + vertex 585.696 111.704 172.981 + vertex 592.78 114.301 176.156 + endloop + endfacet + facet normal 0.342783 -0.939234 -0.0184013 + outer loop + vertex 592.78 114.301 176.156 + vertex 594.155 114.59 187.038 + vertex 587.44 112.252 181.24 + endloop + endfacet + facet normal 0.356647 -0.933516 -0.0367651 + outer loop + vertex 588.994 112.416 192.16 + vertex 587.44 112.252 181.24 + vertex 594.155 114.59 187.038 + endloop + endfacet + facet normal 0.350927 -0.9354 -0.0433285 + outer loop + vertex 594.155 114.59 187.038 + vertex 595.396 114.676 195.229 + vertex 588.994 112.416 192.16 + endloop + endfacet + facet normal 0.360932 -0.930102 -0.0681007 + outer loop + vertex 595.396 114.676 195.229 + vertex 594.286 113.745 202.053 + vertex 588.994 112.416 192.16 + endloop + endfacet + facet normal 0.347787 -0.935631 -0.060326 + outer loop + vertex 587.533 111.255 201.742 + vertex 588.994 112.416 192.16 + vertex 594.286 113.745 202.053 + endloop + endfacet + facet normal 0.348209 -0.933152 -0.0893194 + outer loop + vertex 594.286 113.745 202.053 + vertex 593.056 112.386 211.462 + vertex 587.533 111.255 201.742 + endloop + endfacet + facet normal 0.335542 -0.938493 -0.0814999 + outer loop + vertex 585.903 110.073 208.65 + vertex 587.533 111.255 201.742 + vertex 593.056 112.386 211.462 + endloop + endfacet + facet normal 0.342883 -0.933579 -0.10422 + outer loop + vertex 587.635 109.796 216.828 + vertex 585.903 110.073 208.65 + vertex 593.056 112.386 211.462 + endloop + endfacet + facet normal 0.336449 -0.935084 -0.111447 + outer loop + vertex 593.056 112.386 211.462 + vertex 594.521 111.647 222.08 + vertex 587.635 109.796 216.828 + endloop + endfacet + facet normal 0.347017 -0.929167 -0.127389 + outer loop + vertex 589.483 109.003 227.647 + vertex 587.635 109.796 216.828 + vertex 594.521 111.647 222.08 + endloop + endfacet + facet normal 0.340759 -0.930591 -0.133729 + outer loop + vertex 594.521 111.647 222.08 + vertex 595.899 111.001 230.093 + vertex 589.483 109.003 227.647 + endloop + endfacet + facet normal 0.346378 -0.925611 -0.152537 + outer loop + vertex 595.899 111.001 230.093 + vertex 595.121 109.558 237.079 + vertex 589.483 109.003 227.647 + endloop + endfacet + facet normal 0.336588 -0.930199 -0.146415 + outer loop + vertex 588.703 107.161 237.555 + vertex 589.483 109.003 227.647 + vertex 595.121 109.558 237.079 + endloop + endfacet + facet normal 0.334512 -0.928069 -0.163677 + outer loop + vertex 595.121 109.558 237.079 + vertex 594.923 107.916 245.989 + vertex 588.703 107.161 237.555 + endloop + endfacet + facet normal 0.32997 -0.930311 -0.160126 + outer loop + vertex 588.383 105.514 246.463 + vertex 588.703 107.161 237.555 + vertex 594.923 107.916 245.989 + endloop + endfacet + facet normal 0.328615 -0.928813 -0.17123 + outer loop + vertex 594.923 107.916 245.989 + vertex 594.727 106.008 255.961 + vertex 588.383 105.514 246.463 + endloop + endfacet + facet normal 0.320979 -0.932435 -0.165942 + outer loop + vertex 587.457 103.929 253.578 + vertex 588.383 105.514 246.463 + vertex 594.727 106.008 255.961 + endloop + endfacet + facet normal 0.321665 -0.931709 -0.168668 + outer loop + vertex 590.178 103.184 262.883 + vertex 587.457 103.929 253.578 + vertex 594.727 106.008 255.961 + endloop + endfacet + facet normal 0.317147 -0.932645 -0.17202 + outer loop + vertex 594.727 106.008 255.961 + vertex 597.148 105.073 265.494 + vertex 590.178 103.184 262.883 + endloop + endfacet + facet normal 0.31577 -0.933952 -0.167398 + outer loop + vertex 597.148 105.073 265.494 + vertex 596.487 103.34 273.915 + vertex 590.178 103.184 262.883 + endloop + endfacet + facet normal 0.309605 -0.936645 -0.163834 + outer loop + vertex 588.676 101.286 270.899 + vertex 590.178 103.184 262.883 + vertex 596.487 103.34 273.915 + endloop + endfacet + facet normal 0.305316 -0.940328 -0.150216 + outer loop + vertex 591.82 100.797 280.344 + vertex 588.676 101.286 270.899 + vertex 596.487 103.34 273.915 + endloop + endfacet + facet normal 0.299969 -0.941354 -0.154503 + outer loop + vertex 596.487 103.34 273.915 + vertex 599.814 102.722 284.136 + vertex 591.82 100.797 280.344 + endloop + endfacet + facet normal 0.29187 -0.946941 -0.134593 + outer loop + vertex 591.82 100.797 280.344 + vertex 599.814 102.722 284.136 + vertex 598.841 101.717 289.098 + endloop + endfacet + facet normal 0.280876 -0.95153 -0.125294 + outer loop + vertex 592.047 99.7238 289.006 + vertex 591.82 100.797 280.344 + vertex 598.841 101.717 289.098 + endloop + endfacet + facet normal 0.281276 -0.953803 -0.105568 + outer loop + vertex 598.841 101.717 289.098 + vertex 599.658 101.321 294.859 + vertex 592.047 99.7238 289.006 + endloop + endfacet + facet normal 0.268193 -0.959427 -0.0870195 + outer loop + vertex 592.047 99.7238 289.006 + vertex 599.658 101.321 294.859 + vertex 594.407 99.7612 295.87 + endloop + endfacet + facet normal 0.271839 -0.958285 -0.0882798 + outer loop + vertex 592.047 99.7238 289.006 + vertex 594.407 99.7612 295.87 + vertex 582.823 96.9116 291.13 + endloop + endfacet + facet normal 0.27009 -0.958077 -0.0956019 + outer loop + vertex 581.419 97.4691 281.577 + vertex 592.047 99.7238 289.006 + vertex 582.823 96.9116 291.13 + endloop + endfacet + facet normal 0.276289 -0.956227 -0.0964048 + outer loop + vertex 581.419 97.4691 281.577 + vertex 582.823 96.9116 291.13 + vertex 569.453 93.9527 282.162 + endloop + endfacet + facet normal 0.274889 -0.954569 -0.115036 + outer loop + vertex 569.042 94.9239 273.121 + vertex 581.419 97.4691 281.577 + vertex 569.453 93.9527 282.162 + endloop + endfacet + facet normal 0.267925 -0.95656 -0.114934 + outer loop + vertex 569.042 94.9239 273.121 + vertex 569.453 93.9527 282.162 + vertex 556.31 91.3592 273.11 + endloop + endfacet + facet normal 0.267304 -0.954282 -0.133771 + outer loop + vertex 556.023 92.5299 264.185 + vertex 569.042 94.9239 273.121 + vertex 556.31 91.3592 273.11 + endloop + endfacet + facet normal 0.252636 -0.958262 -0.133822 + outer loop + vertex 556.023 92.5299 264.185 + vertex 556.31 91.3592 273.11 + vertex 543.026 89.1605 263.775 + endloop + endfacet + facet normal 0.25256 -0.956419 -0.146545 + outer loop + vertex 542.833 90.4591 254.967 + vertex 556.023 92.5299 264.185 + vertex 543.026 89.1605 263.775 + endloop + endfacet + facet normal 0.235063 -0.960829 -0.146812 + outer loop + vertex 542.833 90.4591 254.967 + vertex 543.026 89.1605 263.775 + vertex 530.253 87.4716 254.377 + endloop + endfacet + facet normal 0.23509 -0.9604 -0.149549 + outer loop + vertex 530.258 88.828 245.675 + vertex 542.833 90.4591 254.967 + vertex 530.253 87.4716 254.377 + endloop + endfacet + facet normal 0.218683 -0.964175 -0.150148 + outer loop + vertex 530.258 88.828 245.675 + vertex 530.253 87.4716 254.377 + vertex 519.025 86.3588 245.171 + endloop + endfacet + facet normal 0.218612 -0.965185 -0.143619 + outer loop + vertex 519.258 87.6989 236.518 + vertex 530.258 88.828 245.675 + vertex 519.025 86.3588 245.171 + endloop + endfacet + facet normal 0.204753 -0.968097 -0.144442 + outer loop + vertex 519.258 87.6989 236.518 + vertex 519.025 86.3588 245.171 + vertex 510.218 85.7916 236.488 + endloop + endfacet + facet normal 0.205077 -0.969832 -0.13179 + outer loop + vertex 510.592 87.0443 227.851 + vertex 519.258 87.6989 236.518 + vertex 510.218 85.7916 236.488 + endloop + endfacet + facet normal 0.19096 -0.972573 -0.132799 + outer loop + vertex 510.592 87.0443 227.851 + vertex 510.218 85.7916 236.488 + vertex 503.893 85.6112 228.713 + endloop + endfacet + facet normal 0.19329 -0.974111 -0.117245 + outer loop + vertex 504.825 86.7879 220.474 + vertex 510.592 87.0443 227.851 + vertex 503.893 85.6112 228.713 + endloop + endfacet + facet normal 0.179363 -0.976539 -0.119168 + outer loop + vertex 504.825 86.7879 220.474 + vertex 503.893 85.6112 228.713 + vertex 501.001 85.8404 222.482 + endloop + endfacet + facet normal 0.185592 -0.97674 -0.107399 + outer loop + vertex 501.001 85.8404 222.482 + vertex 501.711 86.6669 216.193 + vertex 504.825 86.7879 220.474 + endloop + endfacet + facet normal 0.175136 -0.979482 -0.0997161 + outer loop + vertex 504.737 87.6699 211.655 + vertex 504.825 86.7879 220.474 + vertex 501.711 86.6669 216.193 + endloop + endfacet + facet normal 0.183679 -0.9785 -0.0938037 + outer loop + vertex 501.711 86.6669 216.193 + vertex 501 86.9917 211.413 + vertex 504.737 87.6699 211.655 + endloop + endfacet + facet normal 0.183018 -0.979869 -0.0797574 + outer loop + vertex 501 86.9917 211.413 + vertex 501.895 87.6752 205.068 + vertex 504.737 87.6699 211.655 + endloop + endfacet + facet normal 0.182371 -0.980012 -0.0794782 + outer loop + vertex 505.689 88.5481 203.012 + vertex 504.737 87.6699 211.655 + vertex 501.895 87.6752 205.068 + endloop + endfacet + facet normal 0.1898 -0.979629 -0.0656005 + outer loop + vertex 501.895 87.6752 205.068 + vertex 502.721 88.2684 198.6 + vertex 505.689 88.5481 203.012 + endloop + endfacet + facet normal 0.177284 -0.982508 -0.0569963 + outer loop + vertex 505.672 89.0587 194.156 + vertex 505.689 88.5481 203.012 + vertex 502.721 88.2684 198.6 + endloop + endfacet + facet normal 0.186913 -0.981085 -0.0503472 + outer loop + vertex 502.721 88.2684 198.6 + vertex 502.062 88.392 193.744 + vertex 505.672 89.0587 194.156 + endloop + endfacet + facet normal 0.185454 -0.981989 -0.0361064 + outer loop + vertex 502.062 88.392 193.744 + vertex 502.935 88.7874 187.476 + vertex 505.672 89.0587 194.156 + endloop + endfacet + facet normal 0.18602 -0.981874 -0.0363432 + outer loop + vertex 506.574 89.548 185.554 + vertex 505.672 89.0587 194.156 + vertex 502.935 88.7874 187.476 + endloop + endfacet + facet normal 0.192822 -0.980962 -0.0231038 + outer loop + vertex 502.935 88.7874 187.476 + vertex 503.737 89.0964 181.052 + vertex 506.574 89.548 185.554 + endloop + endfacet + facet normal 0.181137 -0.983336 -0.0155025 + outer loop + vertex 506.609 89.6942 176.693 + vertex 506.574 89.548 185.554 + vertex 503.737 89.0964 181.052 + endloop + endfacet + facet normal 0.189616 -0.98181 -0.00970651 + outer loop + vertex 503.737 89.0964 181.052 + vertex 503.136 89.0285 176.17 + vertex 506.609 89.6942 176.693 + endloop + endfacet + facet normal 0.187821 -0.982199 0.00271819 + outer loop + vertex 503.136 89.0285 176.17 + vertex 503.986 89.1737 169.865 + vertex 506.609 89.6942 176.693 + endloop + endfacet + facet normal 0.186917 -0.982371 0.00307861 + outer loop + vertex 507.534 89.8432 168.079 + vertex 506.609 89.6942 176.693 + vertex 503.986 89.1737 169.865 + endloop + endfacet + facet normal 0.192843 -0.98111 0.0153266 + outer loop + vertex 503.986 89.1737 169.865 + vertex 504.779 89.2293 163.454 + vertex 507.534 89.8432 168.079 + endloop + endfacet + facet normal 0.180623 -0.983286 0.0228962 + outer loop + vertex 507.539 89.6353 159.117 + vertex 507.534 89.8432 168.079 + vertex 504.779 89.2293 163.454 + endloop + endfacet + facet normal 0.188235 -0.981728 0.0278872 + outer loop + vertex 504.779 89.2293 163.454 + vertex 504.176 88.9716 158.447 + vertex 507.539 89.6353 159.117 + endloop + endfacet + facet normal 0.185651 -0.981765 0.0408807 + outer loop + vertex 504.176 88.9716 158.447 + vertex 504.994 88.8632 152.129 + vertex 507.539 89.6353 159.117 + endloop + endfacet + facet normal 0.185882 -0.981725 0.040792 + outer loop + vertex 508.423 89.4437 150.478 + vertex 507.539 89.6353 159.117 + vertex 504.994 88.8632 152.129 + endloop + endfacet + facet normal 0.191025 -0.980207 0.0520031 + outer loop + vertex 504.994 88.8632 152.129 + vertex 505.729 88.6643 145.683 + vertex 508.423 89.4437 150.478 + endloop + endfacet + facet normal 0.179439 -0.98201 0.0588043 + outer loop + vertex 508.445 88.921 141.68 + vertex 508.423 89.4437 150.478 + vertex 505.729 88.6643 145.683 + endloop + endfacet + facet normal 0.186978 -0.980275 0.0640317 + outer loop + vertex 505.729 88.6643 145.683 + vertex 505.272 88.2503 140.677 + vertex 508.445 88.921 141.68 + endloop + endfacet + facet normal 0.183805 -0.980174 0.0739949 + outer loop + vertex 505.272 88.2503 140.677 + vertex 506.3 88.0736 135.784 + vertex 508.445 88.921 141.68 + endloop + endfacet + facet normal 0.179377 -0.980863 0.0757047 + outer loop + vertex 509.319 88.442 133.405 + vertex 508.445 88.921 141.68 + vertex 506.3 88.0736 135.784 + endloop + endfacet + facet normal 0.187193 -0.978553 0.0859829 + outer loop + vertex 506.3 88.0736 135.784 + vertex 506.277 87.5254 129.594 + vertex 509.319 88.442 133.405 + endloop + endfacet + facet normal 0.177912 -0.979581 0.0936363 + outer loop + vertex 509.36 87.5928 124.442 + vertex 509.319 88.442 133.405 + vertex 506.277 87.5254 129.594 + endloop + endfacet + facet normal 0.181596 -0.978691 0.0958521 + outer loop + vertex 506.277 87.5254 129.594 + vertex 506.229 86.8859 123.155 + vertex 509.36 87.5928 124.442 + endloop + endfacet + facet normal 0.176439 -0.978346 0.108208 + outer loop + vertex 506.229 86.8859 123.155 + vertex 507.316 86.5384 118.242 + vertex 509.36 87.5928 124.442 + endloop + endfacet + facet normal 0.17199 -0.978963 0.10978 + outer loop + vertex 510.215 86.7935 115.974 + vertex 509.36 87.5928 124.442 + vertex 507.316 86.5384 118.242 + endloop + endfacet + facet normal 0.179684 -0.976389 0.119906 + outer loop + vertex 507.316 86.5384 118.242 + vertex 507.257 85.764 112.024 + vertex 510.215 86.7935 115.974 + endloop + endfacet + facet normal 0.169731 -0.977199 0.127568 + outer loop + vertex 510.192 85.629 107.085 + vertex 510.215 86.7935 115.974 + vertex 507.257 85.764 112.024 + endloop + endfacet + facet normal 0.17258 -0.97648 0.129242 + outer loop + vertex 507.257 85.764 112.024 + vertex 507.117 84.8975 105.664 + vertex 510.192 85.629 107.085 + endloop + endfacet + facet normal 0.166965 -0.975821 0.141054 + outer loop + vertex 507.117 84.8975 105.664 + vertex 508.068 84.3726 100.907 + vertex 510.192 85.629 107.085 + endloop + endfacet + facet normal 0.161576 -0.97644 0.143033 + outer loop + vertex 510.852 84.5251 98.8036 + vertex 510.192 85.629 107.085 + vertex 508.068 84.3726 100.907 + endloop + endfacet + facet normal 0.16839 -0.973894 0.152233 + outer loop + vertex 508.068 84.3726 100.907 + vertex 507.818 83.3843 94.862 + vertex 510.852 84.5251 98.8036 + endloop + endfacet + facet normal 0.155756 -0.974403 0.162105 + outer loop + vertex 510.537 83.0314 90.1272 + vertex 510.852 84.5251 98.8036 + vertex 507.818 83.3843 94.862 + endloop + endfacet + facet normal 0.159203 -0.973526 0.16402 + outer loop + vertex 507.818 83.3843 94.862 + vertex 507.406 82.2671 88.6304 + vertex 510.537 83.0314 90.1272 + endloop + endfacet + facet normal 0.15139 -0.972021 0.179598 + outer loop + vertex 507.406 82.2671 88.6304 + vertex 508.155 81.532 84.0205 + vertex 510.537 83.0314 90.1272 + endloop + endfacet + facet normal 0.14639 -0.972407 0.181643 + outer loop + vertex 510.881 81.5435 81.8855 + vertex 510.537 83.0314 90.1272 + vertex 508.155 81.532 84.0205 + endloop + endfacet + facet normal 0.155576 -0.968708 0.193391 + outer loop + vertex 508.155 81.532 84.0205 + vertex 507.616 80.169 77.6267 + vertex 510.881 81.5435 81.8855 + endloop + endfacet + facet normal 0.154993 -0.968789 0.193457 + outer loop + vertex 507.616 80.169 77.6267 + vertex 508.155 81.532 84.0205 + vertex 505.577 81.0811 83.8276 + endloop + endfacet + facet normal 0.161708 -0.967291 0.195444 + outer loop + vertex 505.577 81.0811 83.8276 + vertex 505.134 78.8043 72.9259 + vertex 507.616 80.169 77.6267 + endloop + endfacet + facet normal 0.143749 -0.968113 0.205164 + outer loop + vertex 507.205 78.9834 72.32 + vertex 507.616 80.169 77.6267 + vertex 505.134 78.8043 72.9259 + endloop + endfacet + facet normal 0.148173 -0.963825 0.221552 + outer loop + vertex 506.725 77.6751 66.9493 + vertex 507.205 78.9834 72.32 + vertex 505.134 78.8043 72.9259 + endloop + endfacet + facet normal 0.154161 -0.962573 0.222909 + outer loop + vertex 505.134 78.8043 72.9259 + vertex 505.628 76.9903 64.7511 + vertex 506.725 77.6751 66.9493 + endloop + endfacet + facet normal 0.14029 -0.964788 0.222491 + outer loop + vertex 507.205 78.9834 72.32 + vertex 506.725 77.6751 66.9493 + vertex 509.915 79.4266 72.5334 + endloop + endfacet + facet normal 0.123417 -0.964821 0.232138 + outer loop + vertex 507.62 77.3049 64.9353 + vertex 509.915 79.4266 72.5334 + vertex 506.725 77.6751 66.9493 + endloop + endfacet + facet normal 0.12635 -0.964157 0.233319 + outer loop + vertex 506.554 76.8484 63.6263 + vertex 507.62 77.3049 64.9353 + vertex 506.725 77.6751 66.9493 + endloop + endfacet + facet normal 0.18357 -0.956113 0.228365 + outer loop + vertex 506.725 77.6751 66.9493 + vertex 506.154 76.4209 62.1577 + vertex 506.554 76.8484 63.6263 + endloop + endfacet + facet normal 0.0970594 -0.961708 0.256314 + outer loop + vertex 506.293 76.0917 60.8855 + vertex 507.62 77.3049 64.9353 + vertex 506.554 76.8484 63.6263 + endloop + endfacet + facet normal 0.081546 -0.962682 0.258058 + outer loop + vertex 506.293 76.0917 60.8855 + vertex 506.554 76.8484 63.6263 + vertex 506.154 76.4209 62.1577 + endloop + endfacet + facet normal 0.122216 -0.961052 0.247877 + outer loop + vertex 507.474 76.1554 60.5501 + vertex 507.62 77.3049 64.9353 + vertex 506.293 76.0917 60.8855 + endloop + endfacet + facet normal 0.127763 -0.954738 0.26861 + outer loop + vertex 505.621 74.8325 56.7294 + vertex 507.474 76.1554 60.5501 + vertex 506.293 76.0917 60.8855 + endloop + endfacet + facet normal 0.0729599 -0.957701 0.278364 + outer loop + vertex 505.621 74.8325 56.7294 + vertex 506.293 76.0917 60.8855 + vertex 505.491 75.2565 58.2223 + endloop + endfacet + facet normal 0.127686 -0.954738 0.268647 + outer loop + vertex 506.804 74.7374 55.8297 + vertex 507.474 76.1554 60.5501 + vertex 505.621 74.8325 56.7294 + endloop + endfacet + facet normal 0.141068 -0.947935 0.285515 + outer loop + vertex 504.576 73.3479 52.317 + vertex 506.804 74.7374 55.8297 + vertex 505.621 74.8325 56.7294 + endloop + endfacet + facet normal 0.127708 -0.947315 0.293743 + outer loop + vertex 505.773 73.2182 51.3781 + vertex 506.804 74.7374 55.8297 + vertex 504.576 73.3479 52.317 + endloop + endfacet + facet normal 0.140824 -0.940409 0.309515 + outer loop + vertex 503.318 71.8148 48.2311 + vertex 505.773 73.2182 51.3781 + vertex 504.576 73.3479 52.317 + endloop + endfacet + facet normal 0.122504 -0.938459 0.322936 + outer loop + vertex 504.585 71.7144 47.4589 + vertex 505.773 73.2182 51.3781 + vertex 503.318 71.8148 48.2311 + endloop + endfacet + facet normal 0.132402 -0.931682 0.338288 + outer loop + vertex 502.117 70.4207 44.8616 + vertex 504.585 71.7144 47.4589 + vertex 503.318 71.8148 48.2311 + endloop + endfacet + facet normal 0.0987595 -0.931458 0.350188 + outer loop + vertex 502.117 70.4207 44.8616 + vertex 503.318 71.8148 48.2311 + vertex 501.717 70.72 45.7706 + endloop + endfacet + facet normal 0.125309 -0.924644 0.359625 + outer loop + vertex 501.717 70.72 45.7706 + vertex 500.43 69.3872 42.7923 + vertex 502.117 70.4207 44.8616 + endloop + endfacet + facet normal 0.0297265 -0.917099 0.397549 + outer loop + vertex 500.43 69.3872 42.7923 + vertex 501.717 70.72 45.7706 + vertex 500.771 70.0121 44.2083 + endloop + endfacet + facet normal 0.0716285 -0.918784 0.388207 + outer loop + vertex 500.771 70.0121 44.2083 + vertex 499.999 69.316 42.7032 + vertex 500.43 69.3872 42.7923 + endloop + endfacet + facet normal 0.0630446 -0.905655 0.419301 + outer loop + vertex 499.999 69.316 42.7032 + vertex 499.314 68.7003 41.4763 + vertex 500.43 69.3872 42.7923 + endloop + endfacet + facet normal 0.0318551 -0.896862 0.441162 + outer loop + vertex 498.983 67.9652 40.0058 + vertex 500.43 69.3872 42.7923 + vertex 499.314 68.7003 41.4763 + endloop + endfacet + facet normal 0.0820243 -0.898725 0.430773 + outer loop + vertex 499.314 68.7003 41.4763 + vertex 498.625 68.3457 40.8678 + vertex 498.983 67.9652 40.0058 + endloop + endfacet + facet normal 0.10851 -0.892015 0.438787 + outer loop + vertex 498.625 68.3457 40.8678 + vertex 497.52 68.3475 41.1447 + vertex 498.983 67.9652 40.0058 + endloop + endfacet + facet normal 0.0840229 -0.907118 0.412405 + outer loop + vertex 495.34 68.2393 41.3508 + vertex 498.983 67.9652 40.0058 + vertex 497.52 68.3475 41.1447 + endloop + endfacet + facet normal 0.0819329 -0.919848 0.383624 + outer loop + vertex 497.52 68.3475 41.1447 + vertex 495.742 68.4387 41.7431 + vertex 495.34 68.2393 41.3508 + endloop + endfacet + facet normal 0.0686869 -0.916006 0.39524 + outer loop + vertex 495.742 68.4387 41.7431 + vertex 493.443 68.538 42.3728 + vertex 495.34 68.2393 41.3508 + endloop + endfacet + facet normal 0.0524125 -0.928126 0.368559 + outer loop + vertex 491.796 68.535 42.5996 + vertex 495.34 68.2393 41.3508 + vertex 493.443 68.538 42.3728 + endloop + endfacet + facet normal 0.0555047 -0.918655 0.391142 + outer loop + vertex 493.443 68.538 42.3728 + vertex 490.478 68.8359 43.4933 + vertex 491.796 68.535 42.5996 + endloop + endfacet + facet normal 0.0490953 -0.925335 0.375958 + outer loop + vertex 490.478 68.8359 43.4933 + vertex 493.443 68.538 42.3728 + vertex 492.068 68.8717 43.3738 + endloop + endfacet + facet normal 0.0490346 -0.925713 0.375036 + outer loop + vertex 490.681 69.0124 43.9023 + vertex 490.478 68.8359 43.4933 + vertex 492.068 68.8717 43.3738 + endloop + endfacet + facet normal 0.0512343 -0.923479 0.380213 + outer loop + vertex 492.068 68.8717 43.3738 + vertex 491.328 69.4301 44.8296 + vertex 490.681 69.0124 43.9023 + endloop + endfacet + facet normal 0.047798 -0.9228 0.382303 + outer loop + vertex 490.681 69.0124 43.9023 + vertex 491.328 69.4301 44.8296 + vertex 489.246 69.4582 45.1579 + endloop + endfacet + facet normal 0.0444917 -0.931101 0.362038 + outer loop + vertex 490.398 70.3556 47.3242 + vertex 489.246 69.4582 45.1579 + vertex 491.328 69.4301 44.8296 + endloop + endfacet + facet normal 0.0559615 -0.929099 0.365572 + outer loop + vertex 492.737 70.2616 46.7275 + vertex 490.398 70.3556 47.3242 + vertex 491.328 69.4301 44.8296 + endloop + endfacet + facet normal 0.0551978 -0.928948 0.366072 + outer loop + vertex 493.194 69.353 44.3527 + vertex 492.737 70.2616 46.7275 + vertex 491.328 69.4301 44.8296 + endloop + endfacet + facet normal 0.0680161 -0.927362 0.367931 + outer loop + vertex 494.73 70.1308 46.0293 + vertex 492.737 70.2616 46.7275 + vertex 493.194 69.353 44.3527 + endloop + endfacet + facet normal 0.0637709 -0.926308 0.371332 + outer loop + vertex 494.747 69.2579 43.8488 + vertex 494.73 70.1308 46.0293 + vertex 493.194 69.353 44.3527 + endloop + endfacet + facet normal 0.0693844 -0.919332 0.387316 + outer loop + vertex 494.747 69.2579 43.8488 + vertex 493.194 69.353 44.3527 + vertex 493.639 68.8273 43.0251 + endloop + endfacet + facet normal 0.0668654 -0.918312 0.390168 + outer loop + vertex 494.922 68.7226 42.5589 + vertex 494.747 69.2579 43.8488 + vertex 493.639 68.8273 43.0251 + endloop + endfacet + facet normal 0.0659544 -0.919341 0.387894 + outer loop + vertex 493.639 68.8273 43.0251 + vertex 493.443 68.538 42.3728 + vertex 494.922 68.7226 42.5589 + endloop + endfacet + facet normal 0.0765956 -0.917189 0.391022 + outer loop + vertex 496.03 69.2075 43.4792 + vertex 494.747 69.2579 43.8488 + vertex 494.922 68.7226 42.5589 + endloop + endfacet + facet normal 0.0752737 -0.916723 0.392369 + outer loop + vertex 496.142 68.7332 42.3497 + vertex 496.03 69.2075 43.4792 + vertex 494.922 68.7226 42.5589 + endloop + endfacet + facet normal 0.0756755 -0.91566 0.394767 + outer loop + vertex 496.142 68.7332 42.3497 + vertex 494.922 68.7226 42.5589 + vertex 495.742 68.4387 41.7431 + endloop + endfacet + facet normal 0.0833344 -0.916897 0.390327 + outer loop + vertex 496.142 68.7332 42.3497 + vertex 495.742 68.4387 41.7431 + vertex 497.087 68.6515 41.956 + endloop + endfacet + facet normal 0.084273 -0.915934 0.39238 + outer loop + vertex 497.087 68.6515 41.956 + vertex 497.152 69.1782 43.1714 + vertex 496.142 68.7332 42.3497 + endloop + endfacet + facet normal 0.0933208 -0.915371 0.391647 + outer loop + vertex 498.128 69.1499 42.8728 + vertex 497.152 69.1782 43.1714 + vertex 497.087 68.6515 41.956 + endloop + endfacet + facet normal 0.0945837 -0.915763 0.390426 + outer loop + vertex 498.029 68.6711 41.7736 + vertex 498.128 69.1499 42.8728 + vertex 497.087 68.6515 41.956 + endloop + endfacet + facet normal 0.0951483 -0.914392 0.393491 + outer loop + vertex 498.029 68.6711 41.7736 + vertex 497.087 68.6515 41.956 + vertex 497.52 68.3475 41.1447 + endloop + endfacet + facet normal 0.106484 -0.916572 0.385431 + outer loop + vertex 498.029 68.6711 41.7736 + vertex 497.52 68.3475 41.1447 + vertex 498.62 68.6161 41.4796 + endloop + endfacet + facet normal 0.10744 -0.915717 0.387193 + outer loop + vertex 498.62 68.6161 41.4796 + vertex 498.907 69.1276 42.6096 + vertex 498.029 68.6711 41.7736 + endloop + endfacet + facet normal 0.122452 -0.915482 0.383273 + outer loop + vertex 499.499 69.1464 42.4653 + vertex 498.907 69.1276 42.6096 + vertex 498.62 68.6161 41.4796 + endloop + endfacet + facet normal 0.112597 -0.913483 0.390988 + outer loop + vertex 499.314 68.7003 41.4763 + vertex 499.499 69.1464 42.4653 + vertex 498.62 68.6161 41.4796 + endloop + endfacet + facet normal 0.119402 -0.921331 0.369989 + outer loop + vertex 499.499 69.1464 42.4653 + vertex 499.821 69.7697 43.9136 + vertex 498.907 69.1276 42.6096 + endloop + endfacet + facet normal 0.11733 -0.921066 0.371311 + outer loop + vertex 499.821 69.7697 43.9136 + vertex 499.238 69.933 44.5029 + vertex 498.907 69.1276 42.6096 + endloop + endfacet + facet normal 0.100115 -0.921758 0.374618 + outer loop + vertex 498.907 69.1276 42.6096 + vertex 499.238 69.933 44.5029 + vertex 498.128 69.1499 42.8728 + endloop + endfacet + facet normal 0.0933021 -0.920769 0.378785 + outer loop + vertex 499.238 69.933 44.5029 + vertex 498.251 69.8101 44.4473 + vertex 498.128 69.1499 42.8728 + endloop + endfacet + facet normal 0.0959573 -0.930577 0.353296 + outer loop + vertex 498.251 69.8101 44.4473 + vertex 499.238 69.933 44.5029 + vertex 498.986 70.9977 47.3758 + endloop + endfacet + facet normal 0.0807432 -0.930565 0.357112 + outer loop + vertex 498.251 69.8101 44.4473 + vertex 498.986 70.9977 47.3758 + vertex 497.285 69.9872 45.1271 + endloop + endfacet + facet normal 0.0948783 -0.922157 0.375001 + outer loop + vertex 498.251 69.8101 44.4473 + vertex 497.285 69.9872 45.1271 + vertex 497.152 69.1782 43.1714 + endloop + endfacet + facet normal 0.0791653 -0.923054 0.376437 + outer loop + vertex 497.152 69.1782 43.1714 + vertex 497.285 69.9872 45.1271 + vertex 496.03 69.2075 43.4792 + endloop + endfacet + facet normal 0.077699 -0.922776 0.377422 + outer loop + vertex 497.285 69.9872 45.1271 + vertex 495.982 69.8742 45.1192 + vertex 496.03 69.2075 43.4792 + endloop + endfacet + facet normal 0.0787377 -0.932933 0.351335 + outer loop + vertex 495.982 69.8742 45.1192 + vertex 497.285 69.9872 45.1271 + vertex 496.794 71.0715 48.1165 + endloop + endfacet + facet normal 0.0665465 -0.932671 0.354536 + outer loop + vertex 495.982 69.8742 45.1192 + vertex 496.794 71.0715 48.1165 + vertex 494.73 70.1308 46.0293 + endloop + endfacet + facet normal 0.0760809 -0.935075 0.346189 + outer loop + vertex 496.794 71.0715 48.1165 + vertex 494.512 71.349 49.3676 + vertex 494.73 70.1308 46.0293 + endloop + endfacet + facet normal 0.0624056 -0.944245 0.323275 + outer loop + vertex 496.794 71.0715 48.1165 + vertex 496.247 72.6304 52.7753 + vertex 494.512 71.349 49.3676 + endloop + endfacet + facet normal 0.0706571 -0.944997 0.319356 + outer loop + vertex 496.247 72.6304 52.7753 + vertex 493.688 72.7013 53.5512 + vertex 494.512 71.349 49.3676 + endloop + endfacet + facet normal 0.0551702 -0.946851 0.316905 + outer loop + vertex 494.512 71.349 49.3676 + vertex 493.688 72.7013 53.5512 + vertex 492.044 71.459 50.126 + endloop + endfacet + facet normal 0.06367 -0.937118 0.343156 + outer loop + vertex 494.512 71.349 49.3676 + vertex 492.044 71.459 50.126 + vertex 492.737 70.2616 46.7275 + endloop + endfacet + facet normal 0.0563587 -0.946959 0.316374 + outer loop + vertex 493.688 72.7013 53.5512 + vertex 491.031 72.7812 54.2638 + vertex 492.044 71.459 50.126 + endloop + endfacet + facet normal 0.0406957 -0.948835 0.313138 + outer loop + vertex 492.044 71.459 50.126 + vertex 491.031 72.7812 54.2638 + vertex 489.409 71.5783 50.8298 + endloop + endfacet + facet normal 0.048635 -0.938749 0.341152 + outer loop + vertex 492.044 71.459 50.126 + vertex 489.409 71.5783 50.8298 + vertex 490.398 70.3556 47.3242 + endloop + endfacet + facet normal 0.0327867 -0.940792 0.337394 + outer loop + vertex 490.398 70.3556 47.3242 + vertex 489.409 71.5783 50.8298 + vertex 487.783 70.5322 48.0709 + endloop + endfacet + facet normal 0.0326333 -0.940769 0.337475 + outer loop + vertex 489.409 71.5783 50.8298 + vertex 486.701 71.7853 51.6687 + vertex 487.783 70.5322 48.0709 + endloop + endfacet + facet normal 0.0117098 -0.943195 0.332033 + outer loop + vertex 487.783 70.5322 48.0709 + vertex 486.701 71.7853 51.6687 + vertex 485.036 70.8489 49.0672 + endloop + endfacet + facet normal 0.0212377 -0.934431 0.35551 + outer loop + vertex 487.783 70.5322 48.0709 + vertex 485.036 70.8489 49.0672 + vertex 486.409 69.7774 46.169 + endloop + endfacet + facet normal 0.0215006 -0.934489 0.355343 + outer loop + vertex 489.246 69.4582 45.1579 + vertex 487.783 70.5322 48.0709 + vertex 486.409 69.7774 46.169 + endloop + endfacet + facet normal 0.0308162 -0.925086 0.378506 + outer loop + vertex 488.437 69.1708 44.5213 + vertex 489.246 69.4582 45.1579 + vertex 486.409 69.7774 46.169 + endloop + endfacet + facet normal 0.0212891 -0.929431 0.368381 + outer loop + vertex 486.409 69.7774 46.169 + vertex 488.004 69.0578 44.2613 + vertex 488.437 69.1708 44.5213 + endloop + endfacet + facet normal 0.0277846 -0.932898 0.359068 + outer loop + vertex 490.478 68.8359 43.4933 + vertex 488.437 69.1708 44.5213 + vertex 488.004 69.0578 44.2613 + endloop + endfacet + facet normal 0.025559 -0.935415 0.352626 + outer loop + vertex 488.004 69.0578 44.2613 + vertex 491.796 68.535 42.5996 + vertex 490.478 68.8359 43.4933 + endloop + endfacet + facet normal 0.00704606 -0.933667 0.358073 + outer loop + vertex 483.594 69.8188 46.3324 + vertex 488.004 69.0578 44.2613 + vertex 486.409 69.7774 46.169 + endloop + endfacet + facet normal 0.00693798 -0.934317 0.356375 + outer loop + vertex 486.409 69.7774 46.169 + vertex 483.571 70.3511 47.7282 + vertex 483.594 69.8188 46.3324 + endloop + endfacet + facet normal -0.00766924 -0.934391 0.356167 + outer loop + vertex 483.571 70.3511 47.7282 + vertex 481.089 70.6749 48.5243 + vertex 483.594 69.8188 46.3324 + endloop + endfacet + facet normal -0.0212564 -0.939261 0.342544 + outer loop + vertex 478.952 70.5579 48.071 + vertex 483.594 69.8188 46.3324 + vertex 481.089 70.6749 48.5243 + endloop + endfacet + facet normal -0.0230588 -0.936356 0.350295 + outer loop + vertex 481.089 70.6749 48.5243 + vertex 478.696 71.1728 49.6978 + vertex 478.952 70.5579 48.071 + endloop + endfacet + facet normal -0.0425113 -0.936756 0.347391 + outer loop + vertex 478.696 71.1728 49.6978 + vertex 476.425 71.533 50.3911 + vertex 478.952 70.5579 48.071 + endloop + endfacet + facet normal -0.0528823 -0.939873 0.337404 + outer loop + vertex 474.342 71.4265 49.768 + vertex 478.952 70.5579 48.071 + vertex 476.425 71.533 50.3911 + endloop + endfacet + facet normal -0.0562247 -0.93585 0.347885 + outer loop + vertex 476.425 71.533 50.3911 + vertex 474.107 72.1195 51.5941 + vertex 474.342 71.4265 49.768 + endloop + endfacet + facet normal -0.0797277 -0.935335 0.344661 + outer loop + vertex 474.107 72.1195 51.5941 + vertex 471.893 72.5517 52.2548 + vertex 474.342 71.4265 49.768 + endloop + endfacet + facet normal -0.089121 -0.937497 0.336387 + outer loop + vertex 470.242 72.3819 51.3443 + vertex 474.342 71.4265 49.768 + vertex 471.893 72.5517 52.2548 + endloop + endfacet + facet normal -0.0978206 -0.931252 0.351001 + outer loop + vertex 471.893 72.5517 52.2548 + vertex 469.123 73.3086 53.4912 + vertex 470.242 72.3819 51.3443 + endloop + endfacet + facet normal -0.11422 -0.940528 0.31994 + outer loop + vertex 471.893 72.5517 52.2548 + vertex 470.411 73.6515 54.9589 + vertex 469.123 73.3086 53.4912 + endloop + endfacet + facet normal -0.12015 -0.938191 0.324595 + outer loop + vertex 470.411 73.6515 54.9589 + vertex 468.05 74.3061 55.977 + vertex 469.123 73.3086 53.4912 + endloop + endfacet + facet normal -0.141214 -0.938339 0.315562 + outer loop + vertex 469.123 73.3086 53.4912 + vertex 468.05 74.3061 55.977 + vertex 466.962 74.0379 54.6928 + endloop + endfacet + facet normal -0.133175 -0.935204 0.328113 + outer loop + vertex 469.123 73.3086 53.4912 + vertex 466.962 74.0379 54.6928 + vertex 466.632 73.5973 53.3027 + endloop + endfacet + facet normal -0.133354 -0.933314 0.333378 + outer loop + vertex 466.632 73.5973 53.3027 + vertex 470.242 72.3819 51.3443 + vertex 469.123 73.3086 53.4912 + endloop + endfacet + facet normal -0.157527 -0.929946 0.332242 + outer loop + vertex 466.962 74.0379 54.6928 + vertex 464.847 74.6242 55.3309 + vertex 466.632 73.5973 53.3027 + endloop + endfacet + facet normal -0.166114 -0.936255 0.309568 + outer loop + vertex 466.962 74.0379 54.6928 + vertex 465.816 74.9515 56.8408 + vertex 464.847 74.6242 55.3309 + endloop + endfacet + facet normal -0.174312 -0.933226 0.314173 + outer loop + vertex 465.816 74.9515 56.8408 + vertex 463.576 75.6385 57.6385 + vertex 464.847 74.6242 55.3309 + endloop + endfacet + facet normal -0.192995 -0.932991 0.303778 + outer loop + vertex 464.847 74.6242 55.3309 + vertex 463.576 75.6385 57.6385 + vertex 462.713 75.3868 56.3172 + endloop + endfacet + facet normal -0.187442 -0.930723 0.31404 + outer loop + vertex 464.847 74.6242 55.3309 + vertex 462.713 75.3868 56.3172 + vertex 462.868 74.9382 55.0804 + endloop + endfacet + facet normal -0.186996 -0.932893 0.307803 + outer loop + vertex 462.868 74.9382 55.0804 + vertex 466.632 73.5973 53.3027 + vertex 464.847 74.6242 55.3309 + endloop + endfacet + facet normal -0.220811 -0.925433 0.307922 + outer loop + vertex 462.713 75.3868 56.3172 + vertex 460.792 76.0462 56.9218 + vertex 462.868 74.9382 55.0804 + endloop + endfacet + facet normal -0.236106 -0.926947 0.291588 + outer loop + vertex 459.271 76.3776 56.7436 + vertex 462.868 74.9382 55.0804 + vertex 460.792 76.0462 56.9218 + endloop + endfacet + facet normal -0.224211 -0.927439 0.29931 + outer loop + vertex 462.713 75.3868 56.3172 + vertex 461.134 76.4867 58.5427 + vertex 460.792 76.0462 56.9218 + endloop + endfacet + facet normal -0.255223 -0.918078 0.303305 + outer loop + vertex 460.792 76.0462 56.9218 + vertex 461.134 76.4867 58.5427 + vertex 457.449 77.9273 59.8025 + endloop + endfacet + facet normal -0.206739 -0.927419 0.311693 + outer loop + vertex 463.576 75.6385 57.6385 + vertex 461.134 76.4867 58.5427 + vertex 462.713 75.3868 56.3172 + endloop + endfacet + facet normal -0.221717 -0.934637 0.27802 + outer loop + vertex 463.576 75.6385 57.6385 + vertex 462.323 76.9083 60.9081 + vertex 461.134 76.4867 58.5427 + endloop + endfacet + facet normal -0.226972 -0.932689 0.280313 + outer loop + vertex 462.323 76.9083 60.9081 + vertex 459.848 77.825 61.9542 + vertex 461.134 76.4867 58.5427 + endloop + endfacet + facet normal -0.273039 -0.9261 0.260364 + outer loop + vertex 461.134 76.4867 58.5427 + vertex 459.848 77.825 61.9542 + vertex 457.449 77.9273 59.8025 + endloop + endfacet + facet normal -0.268372 -0.928945 0.255026 + outer loop + vertex 457.761 78.8157 63.3668 + vertex 457.449 77.9273 59.8025 + vertex 459.848 77.825 61.9542 + endloop + endfacet + facet normal -0.280241 -0.929914 0.238168 + outer loop + vertex 459.848 77.825 61.9542 + vertex 458.987 79.111 65.9629 + vertex 457.761 78.8157 63.3668 + endloop + endfacet + facet normal -0.286476 -0.927328 0.240819 + outer loop + vertex 458.987 79.111 65.9629 + vertex 456.794 79.9834 66.7134 + vertex 457.761 78.8157 63.3668 + endloop + endfacet + facet normal -0.317382 -0.920137 0.229384 + outer loop + vertex 457.761 78.8157 63.3668 + vertex 456.794 79.9834 66.7134 + vertex 455.466 79.7356 63.8819 + endloop + endfacet + facet normal -0.32205 -0.918011 0.231387 + outer loop + vertex 456.794 79.9834 66.7134 + vertex 454.592 80.9862 67.6271 + vertex 455.466 79.7356 63.8819 + endloop + endfacet + facet normal -0.360328 -0.906822 0.218718 + outer loop + vertex 455.466 79.7356 63.8819 + vertex 454.592 80.9862 67.6271 + vertex 453.237 80.9705 65.3292 + endloop + endfacet + facet normal -0.365597 -0.903958 0.221806 + outer loop + vertex 454.592 80.9862 67.6271 + vertex 452.344 82.1372 68.612 + vertex 453.237 80.9705 65.3292 + endloop + endfacet + facet normal -0.407677 -0.889746 0.205306 + outer loop + vertex 453.237 80.9705 65.3292 + vertex 452.344 82.1372 68.612 + vertex 450.896 82.1397 65.7473 + endloop + endfacet + facet normal -0.417572 -0.88397 0.210313 + outer loop + vertex 452.344 82.1372 68.612 + vertex 450.11 83.4089 69.5221 + vertex 450.896 82.1397 65.7473 + endloop + endfacet + facet normal -0.456451 -0.86772 0.196759 + outer loop + vertex 450.896 82.1397 65.7473 + vertex 450.11 83.4089 69.5221 + vertex 448.765 83.5585 67.0619 + endloop + endfacet + facet normal -0.471109 -0.857833 0.205374 + outer loop + vertex 450.11 83.4089 69.5221 + vertex 447.878 84.8629 70.4743 + vertex 448.765 83.5585 67.0619 + endloop + endfacet + facet normal -0.507782 -0.840454 0.189193 + outer loop + vertex 448.765 83.5585 67.0619 + vertex 447.878 84.8629 70.4743 + vertex 446.732 84.9076 67.5973 + endloop + endfacet + facet normal -0.52487 -0.828264 0.196189 + outer loop + vertex 447.878 84.8629 70.4743 + vertex 445.68 86.4578 71.3272 + vertex 446.732 84.9076 67.5973 + endloop + endfacet + facet normal -0.560522 -0.808776 0.178033 + outer loop + vertex 446.732 84.9076 67.5973 + vertex 445.68 86.4578 71.3272 + vertex 444.857 86.5037 68.9447 + endloop + endfacet + facet normal -0.545601 -0.812913 0.203695 + outer loop + vertex 444.857 86.5037 68.9447 + vertex 444.94 85.7889 66.3159 + vertex 446.732 84.9076 67.5973 + endloop + endfacet + facet normal -0.540777 -0.818738 0.192944 + outer loop + vertex 446.732 84.9076 67.5973 + vertex 444.94 85.7889 66.3159 + vertex 447.988 83.2061 63.8988 + endloop + endfacet + facet normal -0.51755 -0.824585 0.228479 + outer loop + vertex 444.167 85.7247 64.3316 + vertex 447.988 83.2061 63.8988 + vertex 444.94 85.7889 66.3159 + endloop + endfacet + facet normal -0.580043 -0.793283 0.185074 + outer loop + vertex 445.68 86.4578 71.3272 + vertex 443.585 88.1774 72.1338 + vertex 444.857 86.5037 68.9447 + endloop + endfacet + facet normal -0.596903 -0.783403 0.173167 + outer loop + vertex 444.857 86.5037 68.9447 + vertex 443.585 88.1774 72.1338 + vertex 443.106 87.8712 69.098 + endloop + endfacet + facet normal -0.638975 -0.74875 0.17631 + outer loop + vertex 443.585 88.1774 72.1338 + vertex 441.465 90.1562 72.8549 + vertex 443.106 87.8712 69.098 + endloop + endfacet + facet normal -0.650179 -0.741235 0.166846 + outer loop + vertex 443.106 87.8712 69.098 + vertex 441.465 90.1562 72.8549 + vertex 440.961 89.9024 69.7616 + endloop + endfacet + facet normal -0.246176 -0.937023 0.247762 + outer loop + vertex 461.243 78.2604 64.9874 + vertex 458.987 79.111 65.9629 + vertex 459.848 77.825 61.9542 + endloop + endfacet + facet normal -0.264676 -0.941452 0.208841 + outer loop + vertex 461.243 78.2604 64.9874 + vertex 460.076 79.6103 69.5941 + vertex 458.987 79.111 65.9629 + endloop + endfacet + facet normal -0.281334 -0.935663 0.213041 + outer loop + vertex 460.076 79.6103 69.5941 + vertex 457.704 80.4643 70.211 + vertex 458.987 79.111 65.9629 + endloop + endfacet + facet normal -0.300002 -0.93142 0.206048 + outer loop + vertex 458.987 79.111 65.9629 + vertex 457.704 80.4643 70.211 + vertex 456.794 79.9834 66.7134 + endloop + endfacet + facet normal -0.320396 -0.923649 0.210282 + outer loop + vertex 457.704 80.4643 70.211 + vertex 455.738 81.137 70.1708 + vertex 456.794 79.9834 66.7134 + endloop + endfacet + facet normal -0.33395 -0.920042 0.204938 + outer loop + vertex 456.794 79.9834 66.7134 + vertex 455.738 81.137 70.1708 + vertex 454.592 80.9862 67.6271 + endloop + endfacet + facet normal -0.334574 -0.919757 0.205202 + outer loop + vertex 455.738 81.137 70.1708 + vertex 453.52 82.3557 72.0173 + vertex 454.592 80.9862 67.6271 + endloop + endfacet + facet normal -0.380401 -0.905205 0.18947 + outer loop + vertex 454.592 80.9862 67.6271 + vertex 453.52 82.3557 72.0173 + vertex 452.344 82.1372 68.612 + endloop + endfacet + facet normal -0.390368 -0.900288 0.192597 + outer loop + vertex 453.52 82.3557 72.0173 + vertex 451.306 83.4295 72.5493 + vertex 452.344 82.1372 68.612 + endloop + endfacet + facet normal -0.431674 -0.884582 0.176556 + outer loop + vertex 452.344 82.1372 68.612 + vertex 451.306 83.4295 72.5493 + vertex 450.11 83.4089 69.5221 + endloop + endfacet + facet normal -0.446451 -0.876034 0.182335 + outer loop + vertex 451.306 83.4295 72.5493 + vertex 449.097 84.8758 74.0891 + vertex 450.11 83.4089 69.5221 + endloop + endfacet + facet normal -0.48696 -0.857249 0.167316 + outer loop + vertex 450.11 83.4089 69.5221 + vertex 449.097 84.8758 74.0891 + vertex 447.878 84.8629 70.4743 + endloop + endfacet + facet normal -0.50478 -0.845677 0.173286 + outer loop + vertex 449.097 84.8758 74.0891 + vertex 446.515 86.5672 74.8217 + vertex 447.878 84.8629 70.4743 + endloop + endfacet + facet normal -0.540097 -0.827211 0.154976 + outer loop + vertex 447.878 84.8629 70.4743 + vertex 446.515 86.5672 74.8217 + vertex 445.68 86.4578 71.3272 + endloop + endfacet + facet normal -0.564592 -0.809658 0.160281 + outer loop + vertex 446.515 86.5672 74.8217 + vertex 444.15 88.3606 75.5522 + vertex 445.68 86.4578 71.3272 + endloop + endfacet + facet normal -0.595285 -0.791081 0.140806 + outer loop + vertex 445.68 86.4578 71.3272 + vertex 444.15 88.3606 75.5522 + vertex 443.585 88.1774 72.1338 + endloop + endfacet + facet normal -0.359273 -0.916931 0.173669 + outer loop + vertex 455.738 81.137 70.1708 + vertex 455.43 82.0624 74.4204 + vertex 453.52 82.3557 72.0173 + endloop + endfacet + facet normal -0.356889 -0.918248 0.171613 + outer loop + vertex 453.52 82.3557 72.0173 + vertex 455.43 82.0624 74.4204 + vertex 451 84.6094 78.835 + endloop + endfacet + facet normal -0.398914 -0.908584 0.123862 + outer loop + vertex 455.301 82.9327 80.3888 + vertex 451 84.6094 78.835 + vertex 455.43 82.0624 74.4204 + endloop + endfacet + facet normal -0.333237 -0.933979 0.128984 + outer loop + vertex 458.301 81.0709 74.6564 + vertex 455.301 82.9327 80.3888 + vertex 455.43 82.0624 74.4204 + endloop + endfacet + facet normal -0.334235 -0.926782 0.171354 + outer loop + vertex 458.301 81.0709 74.6564 + vertex 455.43 82.0624 74.4204 + vertex 457.704 80.4643 70.211 + endloop + endfacet + facet normal -0.327714 -0.93546 0.132355 + outer loop + vertex 459.066 81.5033 79.6088 + vertex 455.301 82.9327 80.3888 + vertex 458.301 81.0709 74.6564 + endloop + endfacet + facet normal -0.294845 -0.946896 0.128272 + outer loop + vertex 461.012 80.0994 73.7181 + vertex 459.066 81.5033 79.6088 + vertex 458.301 81.0709 74.6564 + endloop + endfacet + facet normal -0.277816 -0.944549 0.175057 + outer loop + vertex 461.012 80.0994 73.7181 + vertex 458.301 81.0709 74.6564 + vertex 460.076 79.6103 69.5941 + endloop + endfacet + facet normal -0.256914 -0.951168 0.171099 + outer loop + vertex 462.385 78.8191 68.6622 + vertex 461.012 80.0994 73.7181 + vertex 460.076 79.6103 69.5941 + endloop + endfacet + facet normal -0.228126 -0.956785 0.180337 + outer loop + vertex 463.361 79.3481 72.7024 + vertex 461.012 80.0994 73.7181 + vertex 462.385 78.8191 68.6622 + endloop + endfacet + facet normal -0.219979 -0.959004 0.178661 + outer loop + vertex 464.591 78.1445 67.7572 + vertex 463.361 79.3481 72.7024 + vertex 462.385 78.8191 68.6622 + endloop + endfacet + facet normal -0.199803 -0.953882 0.224025 + outer loop + vertex 464.591 78.1445 67.7572 + vertex 462.385 78.8191 68.6622 + vertex 463.499 77.508 64.0733 + endloop + endfacet + facet normal -0.198802 -0.95415 0.223774 + outer loop + vertex 465.716 76.8485 63.2307 + vertex 464.591 78.1445 67.7572 + vertex 463.499 77.508 64.0733 + endloop + endfacet + facet normal -0.181432 -0.947279 0.264091 + outer loop + vertex 465.716 76.8485 63.2307 + vertex 463.499 77.508 64.0733 + vertex 464.616 76.1756 60.0612 + endloop + endfacet + facet normal -0.179028 -0.94793 0.263395 + outer loop + vertex 466.86 75.5219 59.234 + vertex 465.716 76.8485 63.2307 + vertex 464.616 76.1756 60.0612 + endloop + endfacet + facet normal -0.164875 -0.940798 0.296169 + outer loop + vertex 466.86 75.5219 59.234 + vertex 464.616 76.1756 60.0612 + vertex 465.816 74.9515 56.8408 + endloop + endfacet + facet normal -0.158686 -0.942575 0.293891 + outer loop + vertex 468.05 74.3061 55.977 + vertex 466.86 75.5219 59.234 + vertex 465.816 74.9515 56.8408 + endloop + endfacet + facet normal -0.140749 -0.943275 0.300703 + outer loop + vertex 469.16 74.9013 58.3636 + vertex 466.86 75.5219 59.234 + vertex 468.05 74.3061 55.977 + endloop + endfacet + facet normal -0.154957 -0.950736 0.268496 + outer loop + vertex 469.16 74.9013 58.3636 + vertex 467.969 76.2384 62.4115 + vertex 466.86 75.5219 59.234 + endloop + endfacet + facet normal -0.135461 -0.95196 0.274632 + outer loop + vertex 470.32 75.656 61.5517 + vertex 467.969 76.2384 62.4115 + vertex 469.16 74.9013 58.3636 + endloop + endfacet + facet normal -0.130084 -0.953188 0.272966 + outer loop + vertex 471.54 74.3085 57.4276 + vertex 470.32 75.656 61.5517 + vertex 469.16 74.9013 58.3636 + endloop + endfacet + facet normal -0.115744 -0.945445 0.304527 + outer loop + vertex 471.54 74.3085 57.4276 + vertex 469.16 74.9013 58.3636 + vertex 470.411 73.6515 54.9589 + endloop + endfacet + facet normal -0.109142 -0.94706 0.301937 + outer loop + vertex 472.804 73.0669 53.9902 + vertex 471.54 74.3085 57.4276 + vertex 470.411 73.6515 54.9589 + endloop + endfacet + facet normal -0.0913374 -0.946858 0.308411 + outer loop + vertex 473.976 73.7581 56.4593 + vertex 471.54 74.3085 57.4276 + vertex 472.804 73.0669 53.9902 + endloop + endfacet + facet normal -0.0861556 -0.948035 0.30628 + outer loop + vertex 475.152 72.5376 53.0124 + vertex 473.976 73.7581 56.4593 + vertex 472.804 73.0669 53.9902 + endloop + endfacet + facet normal -0.0738751 -0.94049 0.331695 + outer loop + vertex 475.152 72.5376 53.0124 + vertex 472.804 73.0669 53.9902 + vertex 474.107 72.1195 51.5941 + endloop + endfacet + facet normal -0.0682662 -0.947555 0.312217 + outer loop + vertex 476.452 73.2565 55.4785 + vertex 473.976 73.7581 56.4593 + vertex 475.152 72.5376 53.0124 + endloop + endfacet + facet normal -0.0651156 -0.948255 0.310761 + outer loop + vertex 477.525 72.0524 52.0289 + vertex 476.452 73.2565 55.4785 + vertex 475.152 72.5376 53.0124 + endloop + endfacet + facet normal -0.0537819 -0.940875 0.334457 + outer loop + vertex 477.525 72.0524 52.0289 + vertex 475.152 72.5376 53.0124 + vertex 476.425 71.533 50.3911 + endloop + endfacet + facet normal -0.0469151 -0.947541 0.316171 + outer loop + vertex 478.952 72.8109 54.5141 + vertex 476.452 73.2565 55.4785 + vertex 477.525 72.0524 52.0289 + endloop + endfacet + facet normal -0.0449741 -0.947964 0.315185 + outer loop + vertex 479.928 71.6155 51.058 + vertex 478.952 72.8109 54.5141 + vertex 477.525 72.0524 52.0289 + endloop + endfacet + facet normal -0.0346321 -0.940684 0.337511 + outer loop + vertex 479.928 71.6155 51.058 + vertex 477.525 72.0524 52.0289 + vertex 478.696 71.1728 49.6978 + endloop + endfacet + facet normal -0.0255939 -0.946966 0.320314 + outer loop + vertex 481.469 72.4158 53.5471 + vertex 478.952 72.8109 54.5141 + vertex 479.928 71.6155 51.058 + endloop + endfacet + facet normal -0.0254385 -0.946999 0.320228 + outer loop + vertex 482.413 71.2241 50.0978 + vertex 481.469 72.4158 53.5471 + vertex 479.928 71.6155 51.058 + endloop + endfacet + facet normal -0.016072 -0.939741 0.34151 + outer loop + vertex 482.413 71.2241 50.0978 + vertex 479.928 71.6155 51.058 + vertex 481.089 70.6749 48.5243 + endloop + endfacet + facet normal -0.00585561 -0.945654 0.325121 + outer loop + vertex 484.04 72.0724 52.5946 + vertex 481.469 72.4158 53.5471 + vertex 482.413 71.2241 50.0978 + endloop + endfacet + facet normal -0.0071881 -0.945378 0.325896 + outer loop + vertex 485.036 70.8489 49.0672 + vertex 484.04 72.0724 52.5946 + vertex 482.413 71.2241 50.0978 + endloop + endfacet + facet normal 0.00197919 -0.938027 0.346556 + outer loop + vertex 485.036 70.8489 49.0672 + vertex 482.413 71.2241 50.0978 + vertex 483.571 70.3511 47.7282 + endloop + endfacet + facet normal -0.0163468 -0.953873 0.299764 + outer loop + vertex 484.04 72.0724 52.5946 + vertex 483.065 73.4128 56.8068 + vertex 481.469 72.4158 53.5471 + endloop + endfacet + facet normal -0.0149576 -0.954089 0.299149 + outer loop + vertex 483.065 73.4128 56.8068 + vertex 480.483 73.7515 57.7579 + vertex 481.469 72.4158 53.5471 + endloop + endfacet + facet normal -0.0269018 -0.962558 0.269739 + outer loop + vertex 483.065 73.4128 56.8068 + vertex 481.847 74.7547 61.4736 + vertex 480.483 73.7515 57.7579 + endloop + endfacet + facet normal -0.0271588 -0.962526 0.269825 + outer loop + vertex 481.847 74.7547 61.4736 + vertex 479.238 75.0889 62.4034 + vertex 480.483 73.7515 57.7579 + endloop + endfacet + facet normal -0.0488036 -0.963226 0.264224 + outer loop + vertex 480.483 73.7515 57.7579 + vertex 479.238 75.0889 62.4034 + vertex 477.897 74.1487 58.728 + endloop + endfacet + facet normal -0.0363441 -0.955084 0.294099 + outer loop + vertex 480.483 73.7515 57.7579 + vertex 477.897 74.1487 58.728 + vertex 478.952 72.8109 54.5141 + endloop + endfacet + facet normal -0.0498812 -0.963073 0.264578 + outer loop + vertex 479.238 75.0889 62.4034 + vertex 476.632 75.483 63.3466 + vertex 477.897 74.1487 58.728 + endloop + endfacet + facet normal -0.0725189 -0.9633 0.258444 + outer loop + vertex 477.897 74.1487 58.728 + vertex 476.632 75.483 63.3466 + vertex 475.317 74.6017 59.6929 + endloop + endfacet + facet normal -0.0597551 -0.955491 0.288907 + outer loop + vertex 477.897 74.1487 58.728 + vertex 475.317 74.6017 59.6929 + vertex 476.452 73.2565 55.4785 + endloop + endfacet + facet normal -0.0723238 -0.963332 0.258381 + outer loop + vertex 476.632 75.483 63.3466 + vertex 474.041 75.9381 64.3181 + vertex 475.317 74.6017 59.6929 + endloop + endfacet + facet normal -0.097386 -0.96298 0.251366 + outer loop + vertex 475.317 74.6017 59.6929 + vertex 474.041 75.9381 64.3181 + vertex 472.777 75.1073 60.6453 + endloop + endfacet + facet normal -0.0836315 -0.955195 0.283917 + outer loop + vertex 475.317 74.6017 59.6929 + vertex 472.777 75.1073 60.6453 + vertex 473.976 73.7581 56.4593 + endloop + endfacet + facet normal -0.0979896 -0.962871 0.251549 + outer loop + vertex 474.041 75.9381 64.3181 + vertex 471.513 76.4415 65.2603 + vertex 472.777 75.1073 60.6453 + endloop + endfacet + facet normal -0.124801 -0.961742 0.243879 + outer loop + vertex 472.777 75.1073 60.6453 + vertex 471.513 76.4415 65.2603 + vertex 470.32 75.656 61.5517 + endloop + endfacet + facet normal -0.126515 -0.961397 0.244357 + outer loop + vertex 471.513 76.4415 65.2603 + vertex 469.092 76.9801 66.1259 + vertex 470.32 75.656 61.5517 + endloop + endfacet + facet normal -0.141784 -0.968244 0.205913 + outer loop + vertex 471.513 76.4415 65.2603 + vertex 470.221 77.6676 70.1357 + vertex 469.092 76.9801 66.1259 + endloop + endfacet + facet normal -0.138291 -0.968933 0.205048 + outer loop + vertex 470.221 77.6676 70.1357 + vertex 467.841 78.188 70.9901 + vertex 469.092 76.9801 66.1259 + endloop + endfacet + facet normal -0.168268 -0.965938 0.196596 + outer loop + vertex 469.092 76.9801 66.1259 + vertex 467.841 78.188 70.9901 + vertex 466.795 77.5448 66.9341 + endloop + endfacet + facet normal -0.152236 -0.959365 0.237576 + outer loop + vertex 469.092 76.9801 66.1259 + vertex 466.795 77.5448 66.9341 + vertex 467.969 76.2384 62.4115 + endloop + endfacet + facet normal -0.175146 -0.957069 0.230962 + outer loop + vertex 467.969 76.2384 62.4115 + vertex 466.795 77.5448 66.9341 + vertex 465.716 76.8485 63.2307 + endloop + endfacet + facet normal -0.162857 -0.96711 0.195386 + outer loop + vertex 467.841 78.188 70.9901 + vertex 465.571 78.7364 71.8124 + vertex 466.795 77.5448 66.9341 + endloop + endfacet + facet normal -0.192265 -0.963344 0.187091 + outer loop + vertex 466.795 77.5448 66.9341 + vertex 465.571 78.7364 71.8124 + vertex 464.591 78.1445 67.7572 + endloop + endfacet + facet normal -0.177514 -0.971387 0.157784 + outer loop + vertex 467.841 78.188 70.9901 + vertex 466.489 79.1897 75.6362 + vertex 465.571 78.7364 71.8124 + endloop + endfacet + facet normal -0.171795 -0.972613 0.156557 + outer loop + vertex 466.489 79.1897 75.6362 + vertex 464.102 79.8942 77.3927 + vertex 465.571 78.7364 71.8124 + endloop + endfacet + facet normal -0.20891 -0.967032 0.145624 + outer loop + vertex 465.571 78.7364 71.8124 + vertex 464.102 79.8942 77.3927 + vertex 463.361 79.3481 72.7024 + endloop + endfacet + facet normal -0.222071 -0.963835 0.147332 + outer loop + vertex 464.102 79.8942 77.3927 + vertex 461.854 80.4315 77.5188 + vertex 463.361 79.3481 72.7024 + endloop + endfacet + facet normal -0.224518 -0.967262 0.118306 + outer loop + vertex 461.854 80.4315 77.5188 + vertex 464.102 79.8942 77.3927 + vertex 460.787 81.5218 84.4083 + endloop + endfacet + facet normal -0.286421 -0.952185 0.106335 + outer loop + vertex 461.854 80.4315 77.5188 + vertex 460.787 81.5218 84.4083 + vertex 459.066 81.5033 79.6088 + endloop + endfacet + facet normal -0.291175 -0.95055 0.108033 + outer loop + vertex 460.787 81.5218 84.4083 + vertex 455.76 83.346 86.91 + vertex 459.066 81.5033 79.6088 + endloop + endfacet + facet normal -0.193945 -0.972818 0.126531 + outer loop + vertex 466.489 79.1897 75.6362 + vertex 465.75 80.2327 82.5216 + vertex 464.102 79.8942 77.3927 + endloop + endfacet + facet normal -0.202946 -0.970618 0.129278 + outer loop + vertex 465.75 80.2327 82.5216 + vertex 460.787 81.5218 84.4083 + vertex 464.102 79.8942 77.3927 + endloop + endfacet + facet normal -0.221875 -0.971766 0.080267 + outer loop + vertex 465.75 80.2327 82.5216 + vertex 461.253 82.0907 92.5848 + vertex 460.787 81.5218 84.4083 + endloop + endfacet + facet normal -0.264855 -0.960799 0.0819547 + outer loop + vertex 461.253 82.0907 92.5848 + vertex 456.06 83.6434 94.0073 + vertex 460.787 81.5218 84.4083 + endloop + endfacet + facet normal -0.317171 -0.94688 0.0531183 + outer loop + vertex 460.787 81.5218 84.4083 + vertex 456.06 83.6434 94.0073 + vertex 455.76 83.346 86.91 + endloop + endfacet + facet normal -0.175215 -0.979181 0.102487 + outer loop + vertex 466.406 81.0172 91.138 + vertex 461.253 82.0907 92.5848 + vertex 465.75 80.2327 82.5216 + endloop + endfacet + facet normal -0.143796 -0.984483 0.100578 + outer loop + vertex 471.231 79.2305 80.5474 + vertex 466.406 81.0172 91.138 + vertex 465.75 80.2327 82.5216 + endloop + endfacet + facet normal -0.127293 -0.981246 0.14475 + outer loop + vertex 471.231 79.2305 80.5474 + vertex 465.75 80.2327 82.5216 + vertex 468.862 78.8101 75.6142 + endloop + endfacet + facet normal -0.135552 -0.979567 0.148573 + outer loop + vertex 471.38 78.1792 73.7526 + vertex 471.231 79.2305 80.5474 + vertex 468.862 78.8101 75.6142 + endloop + endfacet + facet normal -0.115352 -0.977737 0.175281 + outer loop + vertex 471.38 78.1792 73.7526 + vertex 468.862 78.8101 75.6142 + vertex 470.221 77.6676 70.1357 + endloop + endfacet + facet normal -0.12598 -0.975856 0.178423 + outer loop + vertex 472.694 77.1646 69.1307 + vertex 471.38 78.1792 73.7526 + vertex 470.221 77.6676 70.1357 + endloop + endfacet + facet normal -0.0967801 -0.977562 0.187098 + outer loop + vertex 473.789 77.8156 73.0989 + vertex 471.38 78.1792 73.7526 + vertex 472.694 77.1646 69.1307 + endloop + endfacet + facet normal -0.0999995 -0.977083 0.187907 + outer loop + vertex 475.217 76.6986 68.0502 + vertex 473.789 77.8156 73.0989 + vertex 472.694 77.1646 69.1307 + endloop + endfacet + facet normal -0.0833684 -0.970991 0.224112 + outer loop + vertex 475.217 76.6986 68.0502 + vertex 472.694 77.1646 69.1307 + vertex 474.041 75.9381 64.3181 + endloop + endfacet + facet normal -0.058974 -0.978074 0.199731 + outer loop + vertex 476.228 77.2515 71.0564 + vertex 473.789 77.8156 73.0989 + vertex 475.217 76.6986 68.0502 + endloop + endfacet + facet normal -0.0726262 -0.976275 0.203991 + outer loop + vertex 477.734 76.3075 67.0747 + vertex 476.228 77.2515 71.0564 + vertex 475.217 76.6986 68.0502 + endloop + endfacet + facet normal -0.0606684 -0.970679 0.232597 + outer loop + vertex 477.734 76.3075 67.0747 + vertex 475.217 76.6986 68.0502 + vertex 476.632 75.483 63.3466 + endloop + endfacet + facet normal -0.0623707 -0.976171 0.207845 + outer loop + vertex 478.391 77.1215 71.0951 + vertex 476.228 77.2515 71.0564 + vertex 477.734 76.3075 67.0747 + endloop + endfacet + facet normal -0.0541112 -0.976918 0.206646 + outer loop + vertex 480.293 76.0058 66.3183 + vertex 478.391 77.1215 71.0951 + vertex 477.734 76.3075 67.0747 + endloop + endfacet + facet normal -0.0437478 -0.970043 0.238962 + outer loop + vertex 480.293 76.0058 66.3183 + vertex 477.734 76.3075 67.0747 + vertex 479.238 75.0889 62.4034 + endloop + endfacet + facet normal -0.0372801 -0.976297 0.2132 + outer loop + vertex 481.078 76.8898 70.5037 + vertex 478.391 77.1215 71.0951 + vertex 480.293 76.0058 66.3183 + endloop + endfacet + facet normal -0.0318981 -0.97669 0.212274 + outer loop + vertex 482.913 75.7319 65.452 + vertex 481.078 76.8898 70.5037 + vertex 480.293 76.0058 66.3183 + endloop + endfacet + facet normal -0.0207579 -0.96962 0.243735 + outer loop + vertex 482.913 75.7319 65.452 + vertex 480.293 76.0058 66.3183 + vertex 481.847 74.7547 61.4736 + endloop + endfacet + facet normal -0.0188437 -0.969778 0.243261 + outer loop + vertex 484.44 74.474 60.5555 + vertex 482.913 75.7319 65.452 + vertex 481.847 74.7547 61.4736 + endloop + endfacet + facet normal 0.000805557 -0.968488 0.249057 + outer loop + vertex 485.512 75.5079 64.5727 + vertex 482.913 75.7319 65.452 + vertex 484.44 74.474 60.5555 + endloop + endfacet + facet normal 0.00220064 -0.968576 0.248707 + outer loop + vertex 487.05 74.255 59.6796 + vertex 485.512 75.5079 64.5727 + vertex 484.44 74.474 60.5555 + endloop + endfacet + facet normal 0.013215 -0.96008 0.279413 + outer loop + vertex 487.05 74.255 59.6796 + vertex 484.44 74.474 60.5555 + vertex 485.672 73.133 55.8896 + endloop + endfacet + facet normal 0.0130086 -0.960063 0.279483 + outer loop + vertex 488.335 72.9197 55.0328 + vertex 487.05 74.255 59.6796 + vertex 485.672 73.133 55.8896 + endloop + endfacet + facet normal 0.023335 -0.950697 0.309241 + outer loop + vertex 488.335 72.9197 55.0328 + vertex 485.672 73.133 55.8896 + vertex 486.701 71.7853 51.6687 + endloop + endfacet + facet normal 0.00334587 -0.952377 0.304904 + outer loop + vertex 486.701 71.7853 51.6687 + vertex 485.672 73.133 55.8896 + vertex 484.04 72.0724 52.5946 + endloop + endfacet + facet normal 0.0300662 -0.958433 0.283729 + outer loop + vertex 489.695 74.1019 58.8823 + vertex 487.05 74.255 59.6796 + vertex 488.335 72.9197 55.0328 + endloop + endfacet + facet normal 0.0315434 -0.958531 0.283237 + outer loop + vertex 491.031 72.7812 54.2638 + vertex 489.695 74.1019 58.8823 + vertex 488.335 72.9197 55.0328 + endloop + endfacet + facet normal 0.047003 -0.95672 0.28719 + outer loop + vertex 492.369 74.0154 58.1564 + vertex 489.695 74.1019 58.8823 + vertex 491.031 72.7812 54.2638 + endloop + endfacet + facet normal 0.0385959 -0.965568 0.257271 + outer loop + vertex 492.369 74.0154 58.1564 + vertex 490.726 75.25 63.0363 + vertex 489.695 74.1019 58.8823 + endloop + endfacet + facet normal 0.0361044 -0.965504 0.257871 + outer loop + vertex 490.726 75.25 63.0363 + vertex 488.104 75.3473 63.7678 + vertex 489.695 74.1019 58.8823 + endloop + endfacet + facet normal 0.027636 -0.973145 0.228529 + outer loop + vertex 490.726 75.25 63.0363 + vertex 488.927 76.3908 68.1121 + vertex 488.104 75.3473 63.7678 + endloop + endfacet + facet normal 0.0251813 -0.973104 0.228985 + outer loop + vertex 488.927 76.3908 68.1121 + vertex 486.349 76.4925 68.8274 + vertex 488.104 75.3473 63.7678 + endloop + endfacet + facet normal 0.00906483 -0.974607 0.223737 + outer loop + vertex 488.104 75.3473 63.7678 + vertex 486.349 76.4925 68.8274 + vertex 485.512 75.5079 64.5727 + endloop + endfacet + facet normal 0.00681415 -0.974528 0.224162 + outer loop + vertex 486.349 76.4925 68.8274 + vertex 483.758 76.6607 69.6377 + vertex 485.512 75.5079 64.5727 + endloop + endfacet + facet normal -0.00202816 -0.980382 0.197098 + outer loop + vertex 486.349 76.4925 68.8274 + vertex 484.488 77.5471 74.0539 + vertex 483.758 76.6607 69.6377 + endloop + endfacet + facet normal -0.00236052 -0.98037 0.197151 + outer loop + vertex 484.488 77.5471 74.0539 + vertex 481.785 77.7339 74.9508 + vertex 483.758 76.6607 69.6377 + endloop + endfacet + facet normal -0.0225228 -0.981545 0.189902 + outer loop + vertex 483.758 76.6607 69.6377 + vertex 481.785 77.7339 74.9508 + vertex 481.078 76.8898 70.5037 + endloop + endfacet + facet normal -0.0249687 -0.981415 0.190266 + outer loop + vertex 481.785 77.7339 74.9508 + vertex 478.796 77.9869 75.8636 + vertex 481.078 76.8898 70.5037 + endloop + endfacet + facet normal -0.0341264 -0.986263 0.161622 + outer loop + vertex 481.785 77.7339 74.9508 + vertex 479.499 78.8292 81.1521 + vertex 478.796 77.9869 75.8636 + endloop + endfacet + facet normal -0.0353556 -0.986194 0.161775 + outer loop + vertex 479.499 78.8292 81.1521 + vertex 475.609 79.117 82.0559 + vertex 478.796 77.9869 75.8636 + endloop + endfacet + facet normal -0.0533924 -0.986843 0.152608 + outer loop + vertex 478.796 77.9869 75.8636 + vertex 475.609 79.117 82.0559 + vertex 475.76 78.1189 75.6547 + endloop + endfacet + facet normal -0.0552445 -0.981589 0.182839 + outer loop + vertex 478.796 77.9869 75.8636 + vertex 475.76 78.1189 75.6547 + vertex 478.391 77.1215 71.0951 + endloop + endfacet + facet normal -0.0778493 -0.985342 0.151794 + outer loop + vertex 475.609 79.117 82.0559 + vertex 471.231 79.2305 80.5474 + vertex 475.76 78.1189 75.6547 + endloop + endfacet + facet normal -0.0629506 -0.984227 0.165334 + outer loop + vertex 473.789 77.8156 73.0989 + vertex 475.76 78.1189 75.6547 + vertex 471.231 79.2305 80.5474 + endloop + endfacet + facet normal -0.0673619 -0.990366 0.120984 + outer loop + vertex 475.609 79.117 82.0559 + vertex 471.378 80.3927 90.1429 + vertex 471.231 79.2305 80.5474 + endloop + endfacet + facet normal -0.0475347 -0.990198 0.13133 + outer loop + vertex 476.116 80.0238 89.0767 + vertex 471.378 80.3927 90.1429 + vertex 475.609 79.117 82.0559 + endloop + endfacet + facet normal -0.0549277 -0.993508 0.0996199 + outer loop + vertex 476.116 80.0238 89.0767 + vertex 471.347 81.2117 98.2945 + vertex 471.378 80.3927 90.1429 + endloop + endfacet + facet normal -0.0760785 -0.992135 0.0994024 + outer loop + vertex 471.347 81.2117 98.2945 + vertex 466.319 81.73 99.6194 + vertex 471.378 80.3927 90.1429 + endloop + endfacet + facet normal -0.108006 -0.990749 0.0821641 + outer loop + vertex 471.378 80.3927 90.1429 + vertex 466.319 81.73 99.6194 + vertex 466.406 81.0172 91.138 + endloop + endfacet + facet normal -0.148783 -0.985521 0.0813078 + outer loop + vertex 466.319 81.73 99.6194 + vertex 461.146 82.6115 100.836 + vertex 466.406 81.0172 91.138 + endloop + endfacet + facet normal -0.158525 -0.986519 0.0406196 + outer loop + vertex 466.319 81.73 99.6194 + vertex 460.473 83.0564 109.019 + vertex 461.146 82.6115 100.836 + endloop + endfacet + facet normal -0.213551 -0.976285 0.0355399 + outer loop + vertex 460.473 83.0564 109.019 + vertex 455.047 84.2757 109.91 + vertex 461.146 82.6115 100.836 + endloop + endfacet + facet normal -0.246136 -0.969157 0.0123306 + outer loop + vertex 461.146 82.6115 100.836 + vertex 455.047 84.2757 109.91 + vertex 455.81 83.9798 101.866 + endloop + endfacet + facet normal -0.237431 -0.969665 0.0581105 + outer loop + vertex 461.146 82.6115 100.836 + vertex 455.81 83.9798 101.866 + vertex 461.253 82.0907 92.5848 + endloop + endfacet + facet normal -0.278236 -0.959973 0.0322062 + outer loop + vertex 461.253 82.0907 92.5848 + vertex 455.81 83.9798 101.866 + vertex 456.06 83.6434 94.0073 + endloop + endfacet + facet normal -0.220047 -0.975476 -0.00512491 + outer loop + vertex 460.473 83.0564 109.019 + vertex 453.904 84.4912 117.996 + vertex 455.047 84.2757 109.91 + endloop + endfacet + facet normal -0.19186 -0.981285 0.0164292 + outer loop + vertex 459.415 83.3999 117.176 + vertex 453.904 84.4912 117.996 + vertex 460.473 83.0564 109.019 + endloop + endfacet + facet normal -0.135586 -0.990472 0.0241161 + outer loop + vertex 465.728 82.3079 107.82 + vertex 459.415 83.3999 117.176 + vertex 460.473 83.0564 109.019 + endloop + endfacet + facet normal -0.107646 -0.993246 0.0432924 + outer loop + vertex 464.777 82.7703 116.064 + vertex 459.415 83.3999 117.176 + vertex 465.728 82.3079 107.82 + endloop + endfacet + facet normal -0.0644841 -0.996741 0.0484699 + outer loop + vertex 470.909 81.9068 106.465 + vertex 464.777 82.7703 116.064 + vertex 465.728 82.3079 107.82 + endloop + endfacet + facet normal -0.0556741 -0.995103 0.0816715 + outer loop + vertex 470.909 81.9068 106.465 + vertex 465.728 82.3079 107.82 + vertex 471.347 81.2117 98.2945 + endloop + endfacet + facet normal -0.0359093 -0.995919 0.082801 + outer loop + vertex 476.431 80.8975 96.7202 + vertex 470.909 81.9068 106.465 + vertex 471.347 81.2117 98.2945 + endloop + endfacet + facet normal -0.00473629 -0.994939 0.100365 + outer loop + vertex 476.163 81.7491 105.149 + vertex 470.909 81.9068 106.465 + vertex 476.431 80.8975 96.7202 + endloop + endfacet + facet normal 0.00336873 -0.994919 0.100621 + outer loop + vertex 481.701 80.7603 95.1864 + vertex 476.163 81.7491 105.149 + vertex 476.431 80.8975 96.7202 + endloop + endfacet + facet normal 0.0127653 -0.991092 0.132568 + outer loop + vertex 481.701 80.7603 95.1864 + vertex 476.431 80.8975 96.7202 + vertex 481.285 79.5788 86.3936 + endloop + endfacet + facet normal 0.015142 -0.991074 0.132453 + outer loop + vertex 486.592 79.4503 84.8254 + vertex 481.701 80.7603 95.1864 + vertex 481.285 79.5788 86.3936 + endloop + endfacet + facet normal 0.0243225 -0.986304 0.163134 + outer loop + vertex 486.592 79.4503 84.8254 + vertex 481.285 79.5788 86.3936 + vertex 485.049 78.4709 79.1342 + endloop + endfacet + facet normal 0.0189976 -0.986184 0.164558 + outer loop + vertex 487.782 78.2582 77.544 + vertex 486.592 79.4503 84.8254 + vertex 485.049 78.4709 79.1342 + endloop + endfacet + facet normal 0.0314271 -0.982164 0.185382 + outer loop + vertex 487.782 78.2582 77.544 + vertex 485.049 78.4709 79.1342 + vertex 487.076 77.4389 73.3231 + endloop + endfacet + facet normal 0.0283419 -0.98216 0.185898 + outer loop + vertex 489.656 77.3929 72.6864 + vertex 487.782 78.2582 77.544 + vertex 487.076 77.4389 73.3231 + endloop + endfacet + facet normal 0.0340467 -0.977392 0.208677 + outer loop + vertex 489.656 77.3929 72.6864 + vertex 487.076 77.4389 73.3231 + vertex 488.927 76.3908 68.1121 + endloop + endfacet + facet normal 0.035907 -0.977389 0.20838 + outer loop + vertex 491.532 76.3447 67.4469 + vertex 489.656 77.3929 72.6864 + vertex 488.927 76.3908 68.1121 + endloop + endfacet + facet normal 0.0518664 -0.975518 0.213717 + outer loop + vertex 492.279 77.3942 72.056 + vertex 489.656 77.3929 72.6864 + vertex 491.532 76.3447 67.4469 + endloop + endfacet + facet normal 0.0548817 -0.975463 0.213216 + outer loop + vertex 494.188 76.3474 66.7755 + vertex 492.279 77.3942 72.056 + vertex 491.532 76.3447 67.4469 + endloop + endfacet + facet normal 0.0611911 -0.969286 0.238204 + outer loop + vertex 494.188 76.3474 66.7755 + vertex 491.532 76.3447 67.4469 + vertex 493.376 75.2091 62.3522 + endloop + endfacet + facet normal 0.0644633 -0.969225 0.237587 + outer loop + vertex 496.053 75.2182 61.663 + vertex 494.188 76.3474 66.7755 + vertex 493.376 75.2091 62.3522 + endloop + endfacet + facet normal 0.0715933 -0.961479 0.265391 + outer loop + vertex 496.053 75.2182 61.663 + vertex 493.376 75.2091 62.3522 + vertex 495.04 73.9819 57.4573 + endloop + endfacet + facet normal 0.071522 -0.96148 0.265408 + outer loop + vertex 497.643 73.9814 56.7539 + vertex 496.053 75.2182 61.663 + vertex 495.04 73.9819 57.4573 + endloop + endfacet + facet normal 0.0796143 -0.952064 0.295358 + outer loop + vertex 497.643 73.9814 56.7539 + vertex 495.04 73.9819 57.4573 + vertex 496.247 72.6304 52.7753 + endloop + endfacet + facet normal 0.0762427 -0.951981 0.296513 + outer loop + vertex 498.66 72.5794 51.9911 + vertex 497.643 73.9814 56.7539 + vertex 496.247 72.6304 52.7753 + endloop + endfacet + facet normal 0.0938766 -0.949456 0.299534 + outer loop + vertex 500.085 74.0105 56.0808 + vertex 497.643 73.9814 56.7539 + vertex 498.66 72.5794 51.9911 + endloop + endfacet + facet normal 0.0901876 -0.949412 0.300804 + outer loop + vertex 500.744 72.5836 51.3796 + vertex 500.085 74.0105 56.0808 + vertex 498.66 72.5794 51.9911 + endloop + endfacet + facet normal 0.0983899 -0.939251 0.328827 + outer loop + vertex 500.744 72.5836 51.3796 + vertex 498.66 72.5794 51.9911 + vertex 498.986 70.9977 47.3758 + endloop + endfacet + facet normal 0.0956939 -0.939131 0.329963 + outer loop + vertex 500.642 71.0074 46.9233 + vertex 500.744 72.5836 51.3796 + vertex 498.986 70.9977 47.3758 + endloop + endfacet + facet normal 0.107737 -0.938056 0.329306 + outer loop + vertex 502.322 72.7038 51.2058 + vertex 500.744 72.5836 51.3796 + vertex 500.642 71.0074 46.9233 + endloop + endfacet + facet normal 0.12269 -0.938237 0.323509 + outer loop + vertex 501.806 71.3012 47.3338 + vertex 502.322 72.7038 51.2058 + vertex 500.642 71.0074 46.9233 + endloop + endfacet + facet normal 0.112069 -0.930686 0.348231 + outer loop + vertex 501.806 71.3012 47.3338 + vertex 500.642 71.0074 46.9233 + vertex 500.438 69.991 44.2722 + endloop + endfacet + facet normal 0.124816 -0.931109 0.342719 + outer loop + vertex 500.771 70.0121 44.2083 + vertex 501.806 71.3012 47.3338 + vertex 500.438 69.991 44.2722 + endloop + endfacet + facet normal 0.137885 -0.930882 0.338299 + outer loop + vertex 501.806 71.3012 47.3338 + vertex 500.771 70.0121 44.2083 + vertex 501.717 70.72 45.7706 + endloop + endfacet + facet normal 0.132025 -0.928893 0.346015 + outer loop + vertex 499.821 69.7697 43.9136 + vertex 500.438 69.991 44.2722 + vertex 500.642 71.0074 46.9233 + endloop + endfacet + facet normal 0.105403 -0.939394 0.326234 + outer loop + vertex 503.475 73.1016 51.9787 + vertex 502.322 72.7038 51.2058 + vertex 501.806 71.3012 47.3338 + endloop + endfacet + facet normal 0.155423 -0.938618 0.307961 + outer loop + vertex 503.475 73.1016 51.9787 + vertex 501.806 71.3012 47.3338 + vertex 503.102 72.2433 49.551 + endloop + endfacet + facet normal 0.128721 -0.946714 0.295235 + outer loop + vertex 503.475 73.1016 51.9787 + vertex 503.726 74.2809 55.6509 + vertex 502.322 72.7038 51.2058 + endloop + endfacet + facet normal 0.109682 -0.947166 0.301406 + outer loop + vertex 503.726 74.2809 55.6509 + vertex 502.163 74.0894 55.6182 + vertex 502.322 72.7038 51.2058 + endloop + endfacet + facet normal 0.111306 -0.955566 0.272954 + outer loop + vertex 503.726 74.2809 55.6509 + vertex 503.296 75.5254 60.1828 + vertex 502.163 74.0894 55.6182 + endloop + endfacet + facet normal 0.103683 -0.955855 0.274938 + outer loop + vertex 503.296 75.5254 60.1828 + vertex 501.204 75.3659 60.4172 + vertex 502.163 74.0894 55.6182 + endloop + endfacet + facet normal 0.0973676 -0.956808 0.27393 + outer loop + vertex 502.163 74.0894 55.6182 + vertex 501.204 75.3659 60.4172 + vertex 500.085 74.0105 56.0808 + endloop + endfacet + facet normal 0.0994461 -0.956753 0.273376 + outer loop + vertex 501.204 75.3659 60.4172 + vertex 498.705 75.2682 60.9847 + vertex 500.085 74.0105 56.0808 + endloop + endfacet + facet normal 0.093745 -0.964487 0.246936 + outer loop + vertex 501.204 75.3659 60.4172 + vertex 499.62 76.5106 65.4898 + vertex 498.705 75.2682 60.9847 + endloop + endfacet + facet normal 0.0948166 -0.964441 0.246705 + outer loop + vertex 499.62 76.5106 65.4898 + vertex 496.904 76.3985 66.0953 + vertex 498.705 75.2682 60.9847 + endloop + endfacet + facet normal 0.080157 -0.966936 0.242093 + outer loop + vertex 498.705 75.2682 60.9847 + vertex 496.904 76.3985 66.0953 + vertex 496.053 75.2182 61.663 + endloop + endfacet + facet normal 0.0898064 -0.970655 0.22308 + outer loop + vertex 499.62 76.5106 65.4898 + vertex 497.756 77.5465 70.7476 + vertex 496.904 76.3985 66.0953 + endloop + endfacet + facet normal 0.0886177 -0.970711 0.223311 + outer loop + vertex 497.756 77.5465 70.7476 + vertex 494.983 77.4415 71.3917 + vertex 496.904 76.3985 66.0953 + endloop + endfacet + facet normal 0.0729228 -0.973197 0.218106 + outer loop + vertex 496.904 76.3985 66.0953 + vertex 494.983 77.4415 71.3917 + vertex 494.188 76.3474 66.7755 + endloop + endfacet + facet normal 0.0834806 -0.976172 0.200296 + outer loop + vertex 497.756 77.5465 70.7476 + vertex 495.723 78.5695 76.5807 + vertex 494.983 77.4415 71.3917 + endloop + endfacet + facet normal 0.0775778 -0.976473 0.201204 + outer loop + vertex 495.723 78.5695 76.5807 + vertex 493.083 78.3038 76.3089 + vertex 494.983 77.4415 71.3917 + endloop + endfacet + facet normal 0.0654778 -0.978247 0.19684 + outer loop + vertex 494.983 77.4415 71.3917 + vertex 493.083 78.3038 76.3089 + vertex 492.279 77.3942 72.056 + endloop + endfacet + facet normal 0.0665918 -0.978215 0.196623 + outer loop + vertex 493.083 78.3038 76.3089 + vertex 490.282 78.423 77.8509 + vertex 492.279 77.3942 72.056 + endloop + endfacet + facet normal 0.0552884 -0.982757 0.176442 + outer loop + vertex 493.083 78.3038 76.3089 + vertex 491.998 79.5499 83.5893 + vertex 490.282 78.423 77.8509 + endloop + endfacet + facet normal 0.0582439 -0.982745 0.175556 + outer loop + vertex 491.998 79.5499 83.5893 + vertex 486.592 79.4503 84.8254 + vertex 490.282 78.423 77.8509 + endloop + endfacet + facet normal 0.0516448 -0.987894 0.146281 + outer loop + vertex 491.998 79.5499 83.5893 + vertex 487.153 80.8329 93.9648 + vertex 486.592 79.4503 84.8254 + endloop + endfacet + facet normal 0.0771088 -0.984464 0.157748 + outer loop + vertex 492.713 81.0828 92.8067 + vertex 487.153 80.8329 93.9648 + vertex 491.998 79.5499 83.5893 + endloop + endfacet + facet normal 0.0833871 -0.984041 0.157191 + outer loop + vertex 497.409 79.8244 82.4374 + vertex 492.713 81.0828 92.8067 + vertex 491.998 79.5499 83.5893 + endloop + endfacet + facet normal 0.0888638 -0.978873 0.184147 + outer loop + vertex 497.409 79.8244 82.4374 + vertex 491.998 79.5499 83.5893 + vertex 495.723 78.5695 76.5807 + endloop + endfacet + facet normal 0.0895167 -0.97885 0.183954 + outer loop + vertex 498.609 78.5532 75.0891 + vertex 497.409 79.8244 82.4374 + vertex 495.723 78.5695 76.5807 + endloop + endfacet + facet normal 0.108382 -0.976436 0.186618 + outer loop + vertex 498.609 78.5532 75.0891 + vertex 501.002 78.9412 75.7299 + vertex 497.409 79.8244 82.4374 + endloop + endfacet + facet normal 0.109211 -0.976263 0.187039 + outer loop + vertex 502.106 80.2122 81.7189 + vertex 497.409 79.8244 82.4374 + vertex 501.002 78.9412 75.7299 + endloop + endfacet + facet normal 0.108564 -0.97631 0.187168 + outer loop + vertex 503.059 79.0392 75.048 + vertex 502.106 80.2122 81.7189 + vertex 501.002 78.9412 75.7299 + endloop + endfacet + facet normal 0.115814 -0.970857 0.20982 + outer loop + vertex 503.059 79.0392 75.048 + vertex 501.002 78.9412 75.7299 + vertex 502.893 78.0532 70.577 + endloop + endfacet + facet normal 0.105167 -0.971931 0.210451 + outer loop + vertex 503.059 79.0392 75.048 + vertex 502.893 78.0532 70.577 + vertex 505.134 78.8043 72.9259 + endloop + endfacet + facet normal 0.0886111 -0.970164 0.225678 + outer loop + vertex 502.893 78.0532 70.577 + vertex 504.207 76.9746 65.4242 + vertex 505.134 78.8043 72.9259 + endloop + endfacet + facet normal 0.115806 -0.968183 0.221835 + outer loop + vertex 505.628 76.9903 64.7511 + vertex 505.134 78.8043 72.9259 + vertex 504.207 76.9746 65.4242 + endloop + endfacet + facet normal 0.127649 -0.960565 0.247024 + outer loop + vertex 505.628 76.9903 64.7511 + vertex 504.207 76.9746 65.4242 + vertex 504.793 75.7246 60.261 + endloop + endfacet + facet normal 0.145134 -0.959022 0.243336 + outer loop + vertex 505.656 75.9608 60.6772 + vertex 505.628 76.9903 64.7511 + vertex 504.793 75.7246 60.261 + endloop + endfacet + facet normal 0.131826 -0.954288 0.268247 + outer loop + vertex 505.656 75.9608 60.6772 + vertex 504.793 75.7246 60.261 + vertex 504.755 74.6555 56.476 + endloop + endfacet + facet normal 0.153861 -0.952461 0.262955 + outer loop + vertex 505.656 75.9608 60.6772 + vertex 504.755 74.6555 56.476 + vertex 505.491 75.2565 58.2223 + endloop + endfacet + facet normal 0.132244 -0.954236 0.268228 + outer loop + vertex 504.755 74.6555 56.476 + vertex 504.793 75.7246 60.261 + vertex 503.726 74.2809 55.6509 + endloop + endfacet + facet normal 0.176542 -0.954009 0.242282 + outer loop + vertex 506.147 76.7656 63.488 + vertex 505.628 76.9903 64.7511 + vertex 505.656 75.9608 60.6772 + endloop + endfacet + facet normal 0.144934 -0.957638 0.248843 + outer loop + vertex 506.147 76.7656 63.488 + vertex 505.656 75.9608 60.6772 + vertex 506.154 76.4209 62.1577 + endloop + endfacet + facet normal 0.141357 -0.963005 0.229433 + outer loop + vertex 505.628 76.9903 64.7511 + vertex 506.147 76.7656 63.488 + vertex 506.725 77.6751 66.9493 + endloop + endfacet + facet normal 0.0206425 -0.967805 0.250853 + outer loop + vertex 506.154 76.4209 62.1577 + vertex 506.725 77.6751 66.9493 + vertex 506.147 76.7656 63.488 + endloop + endfacet + facet normal 0.115273 -0.962376 0.246058 + outer loop + vertex 504.793 75.7246 60.261 + vertex 504.207 76.9746 65.4242 + vertex 503.296 75.5254 60.1828 + endloop + endfacet + facet normal 0.10108 -0.963273 0.248772 + outer loop + vertex 504.207 76.9746 65.4242 + vertex 502.128 76.7012 65.2106 + vertex 503.296 75.5254 60.1828 + endloop + endfacet + facet normal 0.103711 -0.967874 0.229048 + outer loop + vertex 502.128 76.7012 65.2106 + vertex 504.207 76.9746 65.4242 + vertex 502.893 78.0532 70.577 + endloop + endfacet + facet normal 0.104595 -0.967813 0.228907 + outer loop + vertex 502.893 78.0532 70.577 + vertex 500.47 77.7329 70.3298 + vertex 502.128 76.7012 65.2106 + endloop + endfacet + facet normal 0.0989379 -0.968792 0.227273 + outer loop + vertex 502.128 76.7012 65.2106 + vertex 500.47 77.7329 70.3298 + vertex 499.62 76.5106 65.4898 + endloop + endfacet + facet normal 0.107436 -0.972421 0.207015 + outer loop + vertex 502.893 78.0532 70.577 + vertex 501.002 78.9412 75.7299 + vertex 500.47 77.7329 70.3298 + endloop + endfacet + facet normal 0.0764129 -0.980094 0.183241 + outer loop + vertex 505.134 78.8043 72.9259 + vertex 502.106 80.2122 81.7189 + vertex 503.059 79.0392 75.048 + endloop + endfacet + facet normal 0.106297 -0.980424 0.165743 + outer loop + vertex 502.106 80.2122 81.7189 + vertex 497.991 81.4675 91.784 + vertex 497.409 79.8244 82.4374 + endloop + endfacet + facet normal 0.125338 -0.976899 0.173088 + outer loop + vertex 502.341 81.9959 91.6163 + vertex 497.991 81.4675 91.784 + vertex 502.106 80.2122 81.7189 + endloop + endfacet + facet normal 0.13935 -0.975114 0.172434 + outer loop + vertex 505.577 81.0811 83.8276 + vertex 502.341 81.9959 91.6163 + vertex 502.106 80.2122 81.7189 + endloop + endfacet + facet normal 0.140942 -0.974775 0.173055 + outer loop + vertex 505.395 82.6754 92.9565 + vertex 502.341 81.9959 91.6163 + vertex 505.577 81.0811 83.8276 + endloop + endfacet + facet normal 0.174882 -0.969311 0.172779 + outer loop + vertex 505.395 82.6754 92.9565 + vertex 505.577 81.0811 83.8276 + vertex 507.406 82.2671 88.6304 + endloop + endfacet + facet normal 0.150494 -0.976806 0.152319 + outer loop + vertex 505.395 82.6754 92.9565 + vertex 502.323 83.3849 100.541 + vertex 502.341 81.9959 91.6163 + endloop + endfacet + facet normal 0.135482 -0.978954 0.152623 + outer loop + vertex 502.323 83.3849 100.541 + vertex 498.095 82.846 100.838 + vertex 502.341 81.9959 91.6163 + endloop + endfacet + facet normal 0.1343 -0.982461 0.129359 + outer loop + vertex 502.323 83.3849 100.541 + vertex 497.812 83.9662 109.64 + vertex 498.095 82.846 100.838 + endloop + endfacet + facet normal 0.124951 -0.983712 0.129217 + outer loop + vertex 497.812 83.9662 109.64 + vertex 492.567 83.4265 110.602 + vertex 498.095 82.846 100.838 + endloop + endfacet + facet normal 0.111234 -0.986326 0.121607 + outer loop + vertex 498.095 82.846 100.838 + vertex 492.567 83.4265 110.602 + vertex 492.889 82.3772 101.798 + endloop + endfacet + facet normal 0.115765 -0.982158 0.148204 + outer loop + vertex 498.095 82.846 100.838 + vertex 492.889 82.3772 101.798 + vertex 497.991 81.4675 91.784 + endloop + endfacet + facet normal 0.0989171 -0.985213 0.139898 + outer loop + vertex 497.991 81.4675 91.784 + vertex 492.889 82.3772 101.798 + vertex 492.713 81.0828 92.8067 + endloop + endfacet + facet normal 0.0916281 -0.985883 0.140137 + outer loop + vertex 492.889 82.3772 101.798 + vertex 487.232 82.011 102.921 + vertex 492.713 81.0828 92.8067 + endloop + endfacet + facet normal 0.086221 -0.990011 0.11155 + outer loop + vertex 492.889 82.3772 101.798 + vertex 486.824 82.9644 111.697 + vertex 487.232 82.011 102.921 + endloop + endfacet + facet normal 0.0767266 -0.990832 0.111199 + outer loop + vertex 486.824 82.9644 111.697 + vertex 481.053 82.6326 112.722 + vertex 487.232 82.011 102.921 + endloop + endfacet + facet normal 0.0578997 -0.993352 0.0994909 + outer loop + vertex 487.232 82.011 102.921 + vertex 481.053 82.6326 112.722 + vertex 481.597 81.7905 103.998 + endloop + endfacet + facet normal 0.0635108 -0.989529 0.129613 + outer loop + vertex 487.232 82.011 102.921 + vertex 481.597 81.7905 103.998 + vertex 487.153 80.8329 93.9648 + endloop + endfacet + facet normal 0.0393285 -0.992412 0.116497 + outer loop + vertex 487.153 80.8329 93.9648 + vertex 481.597 81.7905 103.998 + vertex 481.701 80.7603 95.1864 + endloop + endfacet + facet normal 0.047553 -0.99396 0.0989044 + outer loop + vertex 481.053 82.6326 112.722 + vertex 475.473 82.4664 113.735 + vertex 481.597 81.7905 103.998 + endloop + endfacet + facet normal 0.025656 -0.996027 0.0852761 + outer loop + vertex 481.597 81.7905 103.998 + vertex 475.473 82.4664 113.735 + vertex 476.163 81.7491 105.149 + endloop + endfacet + facet normal 0.0124862 -0.996367 0.0842463 + outer loop + vertex 475.473 82.4664 113.735 + vertex 470.083 82.4935 114.854 + vertex 476.163 81.7491 105.149 + endloop + endfacet + facet normal 0.00638341 -0.998471 0.0549055 + outer loop + vertex 475.473 82.4664 113.735 + vertex 469.017 82.953 123.334 + vertex 470.083 82.4935 114.854 + endloop + endfacet + facet normal -0.0209132 -0.998455 0.0514723 + outer loop + vertex 469.017 82.953 123.334 + vertex 463.6 83.1223 124.417 + vertex 470.083 82.4935 114.854 + endloop + endfacet + facet normal -0.0439075 -0.998391 0.0358786 + outer loop + vertex 470.083 82.4935 114.854 + vertex 463.6 83.1223 124.417 + vertex 464.777 82.7703 116.064 + endloop + endfacet + facet normal -0.088233 -0.995662 0.0295185 + outer loop + vertex 463.6 83.1223 124.417 + vertex 458.139 83.6357 125.411 + vertex 464.777 82.7703 116.064 + endloop + endfacet + facet normal -0.0934169 -0.995627 0.00102461 + outer loop + vertex 463.6 83.1223 124.417 + vertex 456.725 83.7769 133.717 + vertex 458.139 83.6357 125.411 + endloop + endfacet + facet normal -0.15127 -0.988452 -0.00894562 + outer loop + vertex 456.725 83.7769 133.717 + vertex 451.003 84.6473 134.302 + vertex 458.139 83.6357 125.411 + endloop + endfacet + facet normal -0.174771 -0.984203 -0.0282915 + outer loop + vertex 458.139 83.6357 125.411 + vertex 451.003 84.6473 134.302 + vertex 452.531 84.611 126.123 + endloop + endfacet + facet normal -0.171145 -0.985244 0.00168683 + outer loop + vertex 458.139 83.6357 125.411 + vertex 452.531 84.611 126.123 + vertex 459.415 83.3999 117.176 + endloop + endfacet + facet normal -0.154023 -0.987354 -0.037527 + outer loop + vertex 456.725 83.7769 133.717 + vertex 449.359 84.59 142.554 + vertex 451.003 84.6473 134.302 + endloop + endfacet + facet normal -0.132471 -0.991 -0.0192271 + outer loop + vertex 455.219 83.816 142.077 + vertex 449.359 84.59 142.554 + vertex 456.725 83.7769 133.717 + endloop + endfacet + facet normal -0.075926 -0.997073 -0.00901443 + outer loop + vertex 462.306 83.3598 132.835 + vertex 455.219 83.816 142.077 + vertex 456.725 83.7769 133.717 + endloop + endfacet + facet normal -0.0557259 -0.998425 0.00654226 + outer loop + vertex 460.926 83.4922 141.281 + vertex 455.219 83.816 142.077 + vertex 462.306 83.3598 132.835 + endloop + endfacet + facet normal -0.0106625 -0.999846 0.0139286 + outer loop + vertex 467.827 83.287 131.834 + vertex 460.926 83.4922 141.281 + vertex 462.306 83.3598 132.835 + endloop + endfacet + facet normal -0.00621653 -0.999243 0.0383999 + outer loop + vertex 467.827 83.287 131.834 + vertex 462.306 83.3598 132.835 + vertex 469.017 82.953 123.334 + endloop + endfacet + facet normal 0.0220235 -0.998861 0.0423374 + outer loop + vertex 474.519 83.0311 122.314 + vertex 467.827 83.287 131.834 + vertex 469.017 82.953 123.334 + endloop + endfacet + facet normal 0.0392663 -0.997745 0.0544278 + outer loop + vertex 473.431 83.4558 130.885 + vertex 467.827 83.287 131.834 + vertex 474.519 83.0311 122.314 + endloop + endfacet + facet normal 0.0559648 -0.996833 0.0565015 + outer loop + vertex 480.214 83.2972 121.369 + vertex 473.431 83.4558 130.885 + vertex 474.519 83.0311 122.314 + endloop + endfacet + facet normal 0.0601506 -0.994791 0.0823023 + outer loop + vertex 480.214 83.2972 121.369 + vertex 474.519 83.0311 122.314 + vertex 481.053 82.6326 112.722 + endloop + endfacet + facet normal 0.0713614 -0.995167 0.0674482 + outer loop + vertex 479.238 83.8135 130.018 + vertex 473.431 83.4558 130.885 + vertex 480.214 83.2972 121.369 + endloop + endfacet + facet normal 0.0836604 -0.994118 0.0687735 + outer loop + vertex 486.103 83.7259 120.403 + vertex 479.238 83.8135 130.018 + vertex 480.214 83.2972 121.369 + endloop + endfacet + facet normal 0.0876274 -0.991707 0.0940126 + outer loop + vertex 486.103 83.7259 120.403 + vertex 480.214 83.2972 121.369 + vertex 486.824 82.9644 111.697 + endloop + endfacet + facet normal 0.0977684 -0.990687 0.0947642 + outer loop + vertex 492.567 83.4265 110.602 + vertex 486.103 83.7259 120.403 + vertex 486.824 82.9644 111.697 + endloop + endfacet + facet normal 0.11208 -0.988228 0.104129 + outer loop + vertex 491.956 84.2813 119.374 + vertex 486.103 83.7259 120.403 + vertex 492.567 83.4265 110.602 + endloop + endfacet + facet normal 0.108037 -0.99095 0.07966 + outer loop + vertex 491.956 84.2813 119.374 + vertex 485.246 84.3355 129.147 + vertex 486.103 83.7259 120.403 + endloop + endfacet + facet normal 0.120614 -0.988766 0.088282 + outer loop + vertex 491.213 84.98 128.213 + vertex 485.246 84.3355 129.147 + vertex 491.956 84.2813 119.374 + endloop + endfacet + facet normal 0.129073 -0.987642 0.0889038 + outer loop + vertex 497.268 84.8933 118.461 + vertex 491.213 84.98 128.213 + vertex 491.956 84.2813 119.374 + endloop + endfacet + facet normal 0.132669 -0.984846 0.111703 + outer loop + vertex 497.268 84.8933 118.461 + vertex 491.956 84.2813 119.374 + vertex 497.812 83.9662 109.64 + endloop + endfacet + facet normal 0.140974 -0.983648 0.112089 + outer loop + vertex 502.01 84.5283 109.293 + vertex 497.268 84.8933 118.461 + vertex 497.812 83.9662 109.64 + endloop + endfacet + facet normal 0.149979 -0.981781 0.116673 + outer loop + vertex 501.524 85.5027 118.117 + vertex 497.268 84.8933 118.461 + vertex 502.01 84.5283 109.293 + endloop + endfacet + facet normal 0.162484 -0.979734 0.117135 + outer loop + vertex 504.937 85.1291 110.258 + vertex 501.524 85.5027 118.117 + vertex 502.01 84.5283 109.293 + endloop + endfacet + facet normal 0.156659 -0.978514 0.134047 + outer loop + vertex 504.937 85.1291 110.258 + vertex 502.01 84.5283 109.293 + vertex 505.557 84.0222 101.453 + endloop + endfacet + facet normal 0.181459 -0.974056 0.135234 + outer loop + vertex 504.937 85.1291 110.258 + vertex 505.557 84.0222 101.453 + vertex 507.117 84.8975 105.664 + endloop + endfacet + facet normal 0.15528 -0.978816 0.133442 + outer loop + vertex 505.557 84.0222 101.453 + vertex 502.01 84.5283 109.293 + vertex 502.323 83.3849 100.541 + endloop + endfacet + facet normal 0.16437 -0.979323 0.117934 + outer loop + vertex 504.752 86.143 118.935 + vertex 501.524 85.5027 118.117 + vertex 504.937 85.1291 110.258 + endloop + endfacet + facet normal 0.177562 -0.977016 0.117945 + outer loop + vertex 504.752 86.143 118.935 + vertex 504.937 85.1291 110.258 + vertex 507.257 85.764 112.024 + endloop + endfacet + facet normal 0.168898 -0.98045 0.100947 + outer loop + vertex 504.752 86.143 118.935 + vertex 500.955 86.3223 127.029 + vertex 501.524 85.5027 118.117 + endloop + endfacet + facet normal 0.156515 -0.982564 0.10035 + outer loop + vertex 500.955 86.3223 127.029 + vertex 496.623 85.6662 127.362 + vertex 501.524 85.5027 118.117 + endloop + endfacet + facet normal 0.155282 -0.984602 0.0802867 + outer loop + vertex 500.955 86.3223 127.029 + vertex 495.955 86.2903 136.307 + vertex 496.623 85.6662 127.362 + endloop + endfacet + facet normal 0.146427 -0.986004 0.0797234 + outer loop + vertex 495.955 86.2903 136.307 + vertex 490.437 85.5355 137.108 + vertex 496.623 85.6662 127.362 + endloop + endfacet + facet normal 0.136894 -0.987844 0.0736474 + outer loop + vertex 496.623 85.6662 127.362 + vertex 490.437 85.5355 137.108 + vertex 491.213 84.98 128.213 + endloop + endfacet + facet normal 0.127837 -0.98911 0.0729359 + outer loop + vertex 490.437 85.5355 137.108 + vertex 484.357 84.8126 137.96 + vertex 491.213 84.98 128.213 + endloop + endfacet + facet normal 0.124926 -0.990872 0.0506636 + outer loop + vertex 490.437 85.5355 137.108 + vertex 483.438 85.149 146.805 + vertex 484.357 84.8126 137.96 + endloop + endfacet + facet normal 0.113553 -0.992296 0.0495364 + outer loop + vertex 483.438 85.149 146.805 + vertex 477.172 84.4659 147.485 + vertex 484.357 84.8126 137.96 + endloop + endfacet + facet normal 0.103848 -0.993699 0.0421648 + outer loop + vertex 484.357 84.8126 137.96 + vertex 477.172 84.4659 147.485 + vertex 478.219 84.2036 138.727 + endloop + endfacet + facet normal 0.106485 -0.992223 0.0644577 + outer loop + vertex 484.357 84.8126 137.96 + vertex 478.219 84.2036 138.727 + vertex 485.246 84.3355 129.147 + endloop + endfacet + facet normal 0.094429 -0.993978 0.055589 + outer loop + vertex 485.246 84.3355 129.147 + vertex 478.219 84.2036 138.727 + vertex 479.238 83.8135 130.018 + endloop + endfacet + facet normal 0.0814857 -0.995204 0.0541288 + outer loop + vertex 478.219 84.2036 138.727 + vertex 472.289 83.7599 139.494 + vertex 479.238 83.8135 130.018 + endloop + endfacet + facet normal 0.0787161 -0.996382 0.0320458 + outer loop + vertex 478.219 84.2036 138.727 + vertex 471.107 83.945 148.154 + vertex 472.289 83.7599 139.494 + endloop + endfacet + facet normal 0.060557 -0.997726 0.0295955 + outer loop + vertex 471.107 83.945 148.154 + vertex 465.248 83.6122 148.923 + vertex 472.289 83.7599 139.494 + endloop + endfacet + facet normal 0.0473167 -0.998686 0.0196939 + outer loop + vertex 472.289 83.7599 139.494 + vertex 465.248 83.6122 148.923 + vertex 466.568 83.5058 140.359 + endloop + endfacet + facet normal 0.050645 -0.997835 0.0419617 + outer loop + vertex 472.289 83.7599 139.494 + vertex 466.568 83.5058 140.359 + vertex 473.431 83.4558 130.885 + endloop + endfacet + facet normal 0.0183711 -0.999715 0.0152483 + outer loop + vertex 465.248 83.6122 148.923 + vertex 459.465 83.5186 149.754 + vertex 466.568 83.5058 140.359 + endloop + endfacet + facet normal 0.0030096 -0.999989 0.00363608 + outer loop + vertex 466.568 83.5058 140.359 + vertex 459.465 83.5186 149.754 + vertex 460.926 83.4922 141.281 + endloop + endfacet + facet normal -0.0421698 -0.999102 -0.00415736 + outer loop + vertex 459.465 83.5186 149.754 + vertex 453.604 83.7631 150.455 + vertex 460.926 83.4922 141.281 + endloop + endfacet + facet normal -0.0450299 -0.998585 -0.0282746 + outer loop + vertex 459.465 83.5186 149.754 + vertex 451.896 83.6023 158.854 + vertex 453.604 83.7631 150.455 + endloop + endfacet + facet normal -0.0997548 -0.994235 -0.0393226 + outer loop + vertex 451.896 83.6023 158.854 + vertex 445.702 84.2126 159.136 + vertex 453.604 83.7631 150.455 + endloop + endfacet + facet normal -0.116215 -0.991731 -0.0544351 + outer loop + vertex 453.604 83.7631 150.455 + vertex 445.702 84.2126 159.136 + vertex 447.591 84.4464 150.842 + endloop + endfacet + facet normal -0.114679 -0.992997 -0.0283774 + outer loop + vertex 453.604 83.7631 150.455 + vertex 447.591 84.4464 150.842 + vertex 455.219 83.816 142.077 + endloop + endfacet + facet normal -0.100718 -0.992893 -0.0633942 + outer loop + vertex 451.896 83.6023 158.854 + vertex 443.705 83.8874 167.403 + vertex 445.702 84.2126 159.136 + endloop + endfacet + facet normal -0.0866176 -0.994995 -0.0498148 + outer loop + vertex 450.09 83.34 167.233 + vertex 443.705 83.8874 167.403 + vertex 451.896 83.6023 158.854 + endloop + endfacet + facet normal -0.0316576 -0.998773 -0.0380882 + outer loop + vertex 457.921 83.4344 158.249 + vertex 450.09 83.34 167.233 + vertex 451.896 83.6023 158.854 + endloop + endfacet + facet normal -0.0182239 -0.999486 -0.0263849 + outer loop + vertex 456.286 83.2404 166.725 + vertex 450.09 83.34 167.233 + vertex 457.921 83.4344 158.249 + endloop + endfacet + facet normal 0.0260879 -0.9995 -0.017838 + outer loop + vertex 463.857 83.6025 157.512 + vertex 456.286 83.2404 166.725 + vertex 457.921 83.4344 158.249 + endloop + endfacet + facet normal 0.0287418 -0.999581 0.00351825 + outer loop + vertex 463.857 83.6025 157.512 + vertex 457.921 83.4344 158.249 + vertex 465.248 83.6122 148.923 + endloop + endfacet + facet normal 0.036315 -0.999296 -0.00942476 + outer loop + vertex 462.399 83.4686 166.09 + vertex 456.286 83.2404 166.725 + vertex 463.857 83.6025 157.512 + endloop + endfacet + facet normal 0.0662238 -0.997795 -0.00431631 + outer loop + vertex 469.87 84.0044 156.839 + vertex 462.399 83.4686 166.09 + vertex 463.857 83.6025 157.512 + endloop + endfacet + facet normal 0.0685462 -0.99751 0.0165897 + outer loop + vertex 469.87 84.0044 156.839 + vertex 463.857 83.6025 157.512 + vertex 471.107 83.945 148.154 + endloop + endfacet + facet normal 0.0876648 -0.995963 0.019303 + outer loop + vertex 477.172 84.4659 147.485 + vertex 469.87 84.0044 156.839 + vertex 471.107 83.945 148.154 + endloop + endfacet + facet normal 0.096708 -0.994962 0.0264121 + outer loop + vertex 476.082 84.5928 156.257 + vertex 469.87 84.0044 156.839 + vertex 477.172 84.4659 147.485 + endloop + endfacet + facet normal 0.0948306 -0.995476 0.00584257 + outer loop + vertex 476.082 84.5928 156.257 + vertex 468.572 83.9317 165.508 + vertex 469.87 84.0044 156.839 + endloop + endfacet + facet normal 0.10168 -0.994751 0.0114543 + outer loop + vertex 474.942 84.577 165.007 + vertex 468.572 83.9317 165.508 + vertex 476.082 84.5928 156.257 + endloop + endfacet + facet normal 0.117196 -0.993017 0.0134779 + outer loop + vertex 482.489 85.3407 155.653 + vertex 474.942 84.577 165.007 + vertex 476.082 84.5928 156.257 + endloop + endfacet + facet normal 0.119076 -0.992293 0.0342813 + outer loop + vertex 482.489 85.3407 155.653 + vertex 476.082 84.5928 156.257 + vertex 483.438 85.149 146.805 + endloop + endfacet + facet normal 0.131421 -0.990688 0.0355712 + outer loop + vertex 489.646 85.9445 146.025 + vertex 482.489 85.3407 155.653 + vertex 483.438 85.149 146.805 + endloop + endfacet + facet normal 0.138229 -0.989564 0.0407027 + outer loop + vertex 488.818 86.1956 154.942 + vertex 482.489 85.3407 155.653 + vertex 489.646 85.9445 146.025 + endloop + endfacet + facet normal 0.148276 -0.988071 0.041594 + outer loop + vertex 495.25 86.755 145.301 + vertex 488.818 86.1956 154.942 + vertex 489.646 85.9445 146.025 + endloop + endfacet + facet normal 0.150795 -0.986569 0.0627955 + outer loop + vertex 495.25 86.755 145.301 + vertex 489.646 85.9445 146.025 + vertex 495.955 86.2903 136.307 + endloop + endfacet + facet normal 0.160143 -0.985052 0.0634501 + outer loop + vertex 500.342 86.9852 136.023 + vertex 495.25 86.755 145.301 + vertex 495.955 86.2903 136.307 + endloop + endfacet + facet normal 0.164961 -0.984081 0.0661186 + outer loop + vertex 499.748 87.5005 145.174 + vertex 495.25 86.755 145.301 + vertex 500.342 86.9852 136.023 + endloop + endfacet + facet normal 0.178482 -0.981669 0.0668602 + outer loop + vertex 503.69 87.6457 136.784 + vertex 499.748 87.5005 145.174 + vertex 500.342 86.9852 136.023 + endloop + endfacet + facet normal 0.174454 -0.981071 0.084063 + outer loop + vertex 503.69 87.6457 136.784 + vertex 500.342 86.9852 136.023 + vertex 503.925 86.9323 127.97 + endloop + endfacet + facet normal 0.188547 -0.978446 0.0842269 + outer loop + vertex 503.69 87.6457 136.784 + vertex 503.925 86.9323 127.97 + vertex 506.277 87.5254 129.594 + endloop + endfacet + facet normal 0.174809 -0.980994 0.0842208 + outer loop + vertex 503.925 86.9323 127.97 + vertex 500.342 86.9852 136.023 + vertex 500.955 86.3223 127.029 + endloop + endfacet + facet normal 0.176832 -0.98202 0.0660792 + outer loop + vertex 503.092 88.2023 146.654 + vertex 499.748 87.5005 145.174 + vertex 503.69 87.6457 136.784 + endloop + endfacet + facet normal 0.206715 -0.976066 0.0675514 + outer loop + vertex 503.092 88.2023 146.654 + vertex 503.69 87.6457 136.784 + vertex 505.272 88.2503 140.677 + endloop + endfacet + facet normal 0.183998 -0.981668 0.0497235 + outer loop + vertex 503.092 88.2023 146.654 + vertex 499.08 87.8434 154.415 + vertex 499.748 87.5005 145.174 + endloop + endfacet + facet normal 0.168128 -0.984562 0.0486841 + outer loop + vertex 499.08 87.8434 154.415 + vertex 494.541 87.0639 154.326 + vertex 499.748 87.5005 145.174 + endloop + endfacet + facet normal 0.168621 -0.985241 0.0294525 + outer loop + vertex 499.08 87.8434 154.415 + vertex 493.831 87.211 163.313 + vertex 494.541 87.0639 154.326 + endloop + endfacet + facet normal 0.157525 -0.987101 0.0286065 + outer loop + vertex 493.831 87.211 163.313 + vertex 487.976 86.2919 163.843 + vertex 494.541 87.0639 154.326 + endloop + endfacet + facet normal 0.152587 -0.98797 0.0251295 + outer loop + vertex 494.541 87.0639 154.326 + vertex 487.976 86.2919 163.843 + vertex 488.818 86.1956 154.942 + endloop + endfacet + facet normal 0.141614 -0.989628 0.0241095 + outer loop + vertex 487.976 86.2919 163.843 + vertex 481.499 85.3805 164.475 + vertex 488.818 86.1956 154.942 + endloop + endfacet + facet normal 0.139692 -0.990188 0.00360464 + outer loop + vertex 487.976 86.2919 163.843 + vertex 480.483 85.2692 173.264 + vertex 481.499 85.3805 164.475 + endloop + endfacet + facet normal 0.125876 -0.992044 0.00198453 + outer loop + vertex 480.483 85.2692 173.264 + vertex 473.762 84.4173 173.716 + vertex 481.499 85.3805 164.475 + endloop + endfacet + facet normal 0.121489 -0.992591 -0.00174549 + outer loop + vertex 481.499 85.3805 164.475 + vertex 473.762 84.4173 173.716 + vertex 474.942 84.577 165.007 + endloop + endfacet + facet normal 0.105382 -0.994424 -0.00396219 + outer loop + vertex 473.762 84.4173 173.716 + vertex 467.225 83.7228 174.129 + vertex 474.942 84.577 165.007 + endloop + endfacet + facet normal 0.104136 -0.994287 -0.0234443 + outer loop + vertex 473.762 84.4173 173.716 + vertex 465.839 83.3759 182.69 + vertex 467.225 83.7228 174.129 + endloop + endfacet + facet normal 0.0831117 -0.996176 -0.0269237 + outer loop + vertex 465.839 83.3759 182.69 + vertex 459.312 82.8209 183.075 + vertex 467.225 83.7228 174.129 + endloop + endfacet + facet normal 0.0781911 -0.996447 -0.0313032 + outer loop + vertex 467.225 83.7228 174.129 + vertex 459.312 82.8209 183.075 + vertex 460.878 83.2095 174.617 + endloop + endfacet + facet normal 0.0797217 -0.996749 -0.0116861 + outer loop + vertex 467.225 83.7228 174.129 + vertex 460.878 83.2095 174.617 + vertex 468.572 83.9317 165.508 + endloop + endfacet + facet normal 0.0731855 -0.997169 -0.0172414 + outer loop + vertex 468.572 83.9317 165.508 + vertex 460.878 83.2095 174.617 + vertex 462.399 83.4686 166.09 + endloop + endfacet + facet normal 0.0430828 -0.998814 -0.0226629 + outer loop + vertex 460.878 83.2095 174.617 + vertex 454.59 82.9261 175.154 + vertex 462.399 83.4686 166.09 + endloop + endfacet + facet normal 0.0413057 -0.998215 -0.0431311 + outer loop + vertex 460.878 83.2095 174.617 + vertex 452.842 82.4928 183.508 + vertex 454.59 82.9261 175.154 + endloop + endfacet + facet normal -0.00293679 -0.998621 -0.0524132 + outer loop + vertex 452.842 82.4928 183.508 + vertex 446.255 82.4971 183.794 + vertex 454.59 82.9261 175.154 + endloop + endfacet + facet normal -0.0114452 -0.998097 -0.060595 + outer loop + vertex 454.59 82.9261 175.154 + vertex 446.255 82.4971 183.794 + vertex 448.199 82.9754 175.55 + endloop + endfacet + facet normal -0.0101361 -0.999176 -0.0393004 + outer loop + vertex 454.59 82.9261 175.154 + vertex 448.199 82.9754 175.55 + vertex 456.286 83.2404 166.725 + endloop + endfacet + facet normal -0.0651086 -0.995199 -0.0730759 + outer loop + vertex 446.255 82.4971 183.794 + vertex 439.468 82.9452 183.74 + vertex 448.199 82.9754 175.55 + endloop + endfacet + facet normal -0.0748697 -0.993693 -0.0834757 + outer loop + vertex 448.199 82.9754 175.55 + vertex 439.468 82.9452 183.74 + vertex 441.62 83.4656 175.614 + endloop + endfacet + facet normal -0.074771 -0.995355 -0.0606407 + outer loop + vertex 448.199 82.9754 175.55 + vertex 441.62 83.4656 175.614 + vertex 450.09 83.34 167.233 + endloop + endfacet + facet normal -0.0648204 -0.99342 -0.0944207 + outer loop + vertex 446.255 82.4971 183.794 + vertex 437.257 82.3262 191.77 + vertex 439.468 82.9452 183.74 + endloop + endfacet + facet normal -0.0570023 -0.994695 -0.0856272 + outer loop + vertex 444.259 81.9098 191.946 + vertex 437.257 82.3262 191.77 + vertex 446.255 82.4971 183.794 + endloop + endfacet + facet normal -0.0563516 -0.992694 -0.106694 + outer loop + vertex 444.259 81.9098 191.946 + vertex 434.999 81.6015 199.706 + vertex 437.257 82.3262 191.77 + endloop + endfacet + facet normal -0.0501767 -0.993785 -0.099369 + outer loop + vertex 442.222 81.2059 200.014 + vertex 434.999 81.6015 199.706 + vertex 444.259 81.9098 191.946 + endloop + endfacet + facet normal 0.0021192 -0.99626 -0.086384 + outer loop + vertex 451.047 81.9386 191.78 + vertex 442.222 81.2059 200.014 + vertex 444.259 81.9098 191.946 + endloop + endfacet + facet normal 0.00261691 -0.997798 -0.0662739 + outer loop + vertex 451.047 81.9386 191.78 + vertex 444.259 81.9098 191.946 + vertex 452.842 82.4928 183.508 + endloop + endfacet + facet normal 0.0467848 -0.997297 -0.0566573 + outer loop + vertex 459.312 82.8209 183.075 + vertex 451.047 81.9386 191.78 + vertex 452.842 82.4928 183.508 + endloop + endfacet + facet normal 0.0513911 -0.997309 -0.0522852 + outer loop + vertex 457.714 82.2987 191.466 + vertex 451.047 81.9386 191.78 + vertex 459.312 82.8209 183.075 + endloop + endfacet + facet normal 0.0504145 -0.996152 -0.0716857 + outer loop + vertex 457.714 82.2987 191.466 + vertex 449.221 81.2561 199.981 + vertex 451.047 81.9386 191.78 + endloop + endfacet + facet normal 0.0538454 -0.996213 -0.0682708 + outer loop + vertex 456.085 81.6402 199.79 + vertex 449.221 81.2561 199.981 + vertex 457.714 82.2987 191.466 + endloop + endfacet + facet normal 0.0846092 -0.994476 -0.0621129 + outer loop + vertex 464.425 82.8869 191.188 + vertex 456.085 81.6402 199.79 + vertex 457.714 82.2987 191.466 + endloop + endfacet + facet normal 0.0854814 -0.99541 -0.0430417 + outer loop + vertex 464.425 82.8869 191.188 + vertex 457.714 82.2987 191.466 + vertex 465.839 83.3759 182.69 + endloop + endfacet + facet normal 0.106795 -0.993501 -0.0393844 + outer loop + vertex 472.551 84.1101 182.369 + vertex 464.425 82.8869 191.188 + vertex 465.839 83.3759 182.69 + endloop + endfacet + facet normal 0.109147 -0.99333 -0.0371926 + outer loop + vertex 471.317 83.6522 190.976 + vertex 464.425 82.8869 191.188 + vertex 472.551 84.1101 182.369 + endloop + endfacet + facet normal 0.126444 -0.99137 -0.0346075 + outer loop + vertex 479.441 85.0014 182.01 + vertex 471.317 83.6522 190.976 + vertex 472.551 84.1101 182.369 + endloop + endfacet + facet normal 0.127505 -0.991722 -0.0151714 + outer loop + vertex 479.441 85.0014 182.01 + vertex 472.551 84.1101 182.369 + vertex 480.483 85.2692 173.264 + endloop + endfacet + facet normal 0.142045 -0.98977 -0.0133779 + outer loop + vertex 487.117 86.2287 172.709 + vertex 479.441 85.0014 182.01 + vertex 480.483 85.2692 173.264 + endloop + endfacet + facet normal 0.144605 -0.989426 -0.0112194 + outer loop + vertex 486.226 85.9984 181.545 + vertex 479.441 85.0014 182.01 + vertex 487.117 86.2287 172.709 + endloop + endfacet + facet normal 0.156938 -0.987559 -0.00992767 + outer loop + vertex 493.07 87.1792 172.258 + vertex 486.226 85.9984 181.545 + vertex 487.117 86.2287 172.709 + endloop + endfacet + facet normal 0.15841 -0.987323 0.0099804 + outer loop + vertex 493.07 87.1792 172.258 + vertex 487.117 86.2287 172.709 + vertex 493.831 87.211 163.313 + endloop + endfacet + facet normal 0.170732 -0.985256 0.011037 + outer loop + vertex 498.451 88.0132 163.45 + vertex 493.07 87.1792 172.258 + vertex 493.831 87.211 163.313 + endloop + endfacet + facet normal 0.171293 -0.985154 0.0113895 + outer loop + vertex 497.823 88.0073 172.394 + vertex 493.07 87.1792 172.258 + vertex 498.451 88.0132 163.45 + endloop + endfacet + facet normal 0.187095 -0.982262 0.0125019 + outer loop + vertex 501.961 88.6985 164.777 + vertex 497.823 88.0073 172.394 + vertex 498.451 88.0132 163.45 + endloop + endfacet + facet normal 0.181147 -0.983039 0.0286396 + outer loop + vertex 501.961 88.6985 164.777 + vertex 498.451 88.0132 163.45 + vertex 502.177 88.4846 156.069 + endloop + endfacet + facet normal 0.20374 -0.978593 0.0290908 + outer loop + vertex 501.961 88.6985 164.777 + vertex 502.177 88.4846 156.069 + vertex 504.176 88.9716 158.447 + endloop + endfacet + facet normal 0.18655 -0.981942 0.0314368 + outer loop + vertex 502.177 88.4846 156.069 + vertex 498.451 88.0132 163.45 + vertex 499.08 87.8434 154.415 + endloop + endfacet + facet normal 0.181337 -0.983377 0.00927264 + outer loop + vertex 501.067 88.6197 173.898 + vertex 497.823 88.0073 172.394 + vertex 501.961 88.6985 164.777 + endloop + endfacet + facet normal 0.201463 -0.979431 0.0112793 + outer loop + vertex 501.067 88.6197 173.898 + vertex 501.961 88.6985 164.777 + vertex 503.986 89.1737 169.865 + endloop + endfacet + facet normal 0.188294 -0.982093 -0.00626331 + outer loop + vertex 501.067 88.6197 173.898 + vertex 497.176 87.8264 181.306 + vertex 497.823 88.0073 172.394 + endloop + endfacet + facet normal 0.171384 -0.985175 -0.00755301 + outer loop + vertex 497.176 87.8264 181.306 + vertex 492.326 86.9839 181.158 + vertex 497.823 88.0073 172.394 + endloop + endfacet + facet normal 0.171893 -0.984758 -0.0265437 + outer loop + vertex 497.176 87.8264 181.306 + vertex 491.564 86.6111 190.051 + vertex 492.326 86.9839 181.158 + endloop + endfacet + facet normal 0.158582 -0.986955 -0.0277765 + outer loop + vertex 491.564 86.6111 190.051 + vertex 485.321 85.5993 190.363 + vertex 492.326 86.9839 181.158 + endloop + endfacet + facet normal 0.157665 -0.987081 -0.0284927 + outer loop + vertex 492.326 86.9839 181.158 + vertex 485.321 85.5993 190.363 + vertex 486.226 85.9984 181.545 + endloop + endfacet + facet normal 0.144589 -0.989039 -0.0299237 + outer loop + vertex 485.321 85.5993 190.363 + vertex 478.379 84.5735 190.722 + vertex 486.226 85.9984 181.545 + endloop + endfacet + facet normal 0.143457 -0.988396 -0.0499379 + outer loop + vertex 485.321 85.5993 190.363 + vertex 477.309 83.9791 199.412 + vertex 478.379 84.5735 190.722 + endloop + endfacet + facet normal 0.127899 -0.990423 -0.0519937 + outer loop + vertex 477.309 83.9791 199.412 + vertex 470.067 83.0371 199.541 + vertex 478.379 84.5735 190.722 + endloop + endfacet + facet normal 0.127325 -0.990468 -0.0525431 + outer loop + vertex 478.379 84.5735 190.722 + vertex 470.067 83.0371 199.541 + vertex 471.317 83.6522 190.976 + endloop + endfacet + facet normal 0.109485 -0.99245 -0.0552895 + outer loop + vertex 470.067 83.0371 199.541 + vertex 462.987 82.251 199.633 + vertex 471.317 83.6522 190.976 + endloop + endfacet + facet normal 0.109105 -0.991248 -0.0743202 + outer loop + vertex 470.067 83.0371 199.541 + vertex 461.535 81.4614 208.033 + vertex 462.987 82.251 199.633 + endloop + endfacet + facet normal 0.0869396 -0.993129 -0.078329 + outer loop + vertex 461.535 81.4614 208.033 + vertex 454.436 80.838 208.057 + vertex 462.987 82.251 199.633 + endloop + endfacet + facet normal 0.0860886 -0.993135 -0.0791938 + outer loop + vertex 462.987 82.251 199.633 + vertex 454.436 80.838 208.057 + vertex 456.085 81.6402 199.79 + endloop + endfacet + facet normal 0.0551853 -0.994807 -0.0855224 + outer loop + vertex 454.436 80.838 208.057 + vertex 447.367 80.4414 208.109 + vertex 456.085 81.6402 199.79 + endloop + endfacet + facet normal 0.0549483 -0.993024 -0.104327 + outer loop + vertex 454.436 80.838 208.057 + vertex 445.486 79.4918 216.157 + vertex 447.367 80.4414 208.109 + endloop + endfacet + facet normal 0.012283 -0.993366 -0.114335 + outer loop + vertex 445.486 79.4918 216.157 + vertex 438.054 79.4307 215.889 + vertex 447.367 80.4414 208.109 + endloop + endfacet + facet normal 0.0105213 -0.993145 -0.116415 + outer loop + vertex 447.367 80.4414 208.109 + vertex 438.054 79.4307 215.889 + vertex 440.158 80.3773 208.004 + endloop + endfacet + facet normal 0.0102636 -0.995191 -0.0974123 + outer loop + vertex 447.367 80.4414 208.109 + vertex 440.158 80.3773 208.004 + vertex 449.221 81.2561 199.981 + endloop + endfacet + facet normal 0.00664932 -0.994818 -0.101454 + outer loop + vertex 449.221 81.2561 199.981 + vertex 440.158 80.3773 208.004 + vertex 442.222 81.2059 200.014 + endloop + endfacet + facet normal -0.0446298 -0.992425 -0.114455 + outer loop + vertex 440.158 80.3773 208.004 + vertex 432.705 80.765 207.549 + vertex 442.222 81.2059 200.014 + endloop + endfacet + facet normal -0.043274 -0.989962 -0.134544 + outer loop + vertex 440.158 80.3773 208.004 + vertex 430.38 79.8155 215.283 + vertex 432.705 80.765 207.549 + endloop + endfacet + facet normal -0.0394459 -0.990799 -0.129466 + outer loop + vertex 438.054 79.4307 215.889 + vertex 430.38 79.8155 215.283 + vertex 440.158 80.3773 208.004 + endloop + endfacet + facet normal -0.0377437 -0.988074 -0.149279 + outer loop + vertex 438.054 79.4307 215.889 + vertex 428.015 78.7566 222.89 + vertex 430.38 79.8155 215.283 + endloop + endfacet + facet normal -0.0354944 -0.988632 -0.146107 + outer loop + vertex 435.926 78.3569 223.672 + vertex 428.015 78.7566 222.89 + vertex 438.054 79.4307 215.889 + endloop + endfacet + facet normal -0.0335353 -0.98581 -0.164482 + outer loop + vertex 435.926 78.3569 223.672 + vertex 425.611 77.5945 230.344 + vertex 428.015 78.7566 222.89 + endloop + endfacet + facet normal -0.0323924 -0.986135 -0.162753 + outer loop + vertex 433.779 77.1641 231.326 + vertex 425.611 77.5945 230.344 + vertex 435.926 78.3569 223.672 + endloop + endfacet + facet normal 0.0149972 -0.988596 -0.149842 + outer loop + vertex 443.593 78.4055 224.119 + vertex 433.779 77.1641 231.326 + vertex 435.926 78.3569 223.672 + endloop + endfacet + facet normal 0.0139675 -0.991163 -0.131914 + outer loop + vertex 443.593 78.4055 224.119 + vertex 435.926 78.3569 223.672 + vertex 445.486 79.4918 216.157 + endloop + endfacet + facet normal 0.055886 -0.990965 -0.12192 + outer loop + vertex 452.769 79.8898 216.26 + vertex 443.593 78.4055 224.119 + vertex 445.486 79.4918 216.157 + endloop + endfacet + facet normal 0.056335 -0.991003 -0.121403 + outer loop + vertex 451.091 78.7992 224.384 + vertex 443.593 78.4055 224.119 + vertex 452.769 79.8898 216.26 + endloop + endfacet + facet normal 0.086646 -0.989585 -0.114953 + outer loop + vertex 460.077 80.5148 216.389 + vertex 451.091 78.7992 224.384 + vertex 452.769 79.8898 216.26 + endloop + endfacet + facet normal 0.0864986 -0.991496 -0.0972291 + outer loop + vertex 460.077 80.5148 216.389 + vertex 452.769 79.8898 216.26 + vertex 461.535 81.4614 208.033 + endloop + endfacet + facet normal 0.10901 -0.989672 -0.0930944 + outer loop + vertex 468.81 82.2584 208.078 + vertex 460.077 80.5148 216.389 + vertex 461.535 81.4614 208.033 + endloop + endfacet + facet normal 0.108145 -0.989681 -0.0940054 + outer loop + vertex 467.555 81.3136 216.582 + vertex 460.077 80.5148 216.389 + vertex 468.81 82.2584 208.078 + endloop + endfacet + facet normal 0.126878 -0.987733 -0.0910239 + outer loop + vertex 476.244 83.2124 208.089 + vertex 467.555 81.3136 216.582 + vertex 468.81 82.2584 208.078 + endloop + endfacet + facet normal 0.127049 -0.989292 -0.07183 + outer loop + vertex 476.244 83.2124 208.089 + vertex 468.81 82.2584 208.078 + vertex 477.309 83.9791 199.412 + endloop + endfacet + facet normal 0.143022 -0.987263 -0.0696916 + outer loop + vertex 484.418 85.0261 199.17 + vertex 476.244 83.2124 208.089 + vertex 477.309 83.9791 199.412 + endloop + endfacet + facet normal 0.142607 -0.987295 -0.0700789 + outer loop + vertex 483.532 84.2736 207.968 + vertex 476.244 83.2124 208.089 + vertex 484.418 85.0261 199.17 + endloop + endfacet + facet normal 0.156735 -0.985264 -0.0684821 + outer loop + vertex 490.818 86.0605 198.935 + vertex 483.532 84.2736 207.968 + vertex 484.418 85.0261 199.17 + endloop + endfacet + facet normal 0.157664 -0.986331 -0.0478855 + outer loop + vertex 490.818 86.0605 198.935 + vertex 484.418 85.0261 199.17 + vertex 491.564 86.6111 190.051 + endloop + endfacet + facet normal 0.170953 -0.984175 -0.0466354 + outer loop + vertex 496.504 87.4608 190.229 + vertex 490.818 86.0605 198.935 + vertex 491.564 86.6111 190.051 + endloop + endfacet + facet normal 0.169323 -0.984404 -0.047737 + outer loop + vertex 495.866 86.9192 199.134 + vertex 490.818 86.0605 198.935 + vertex 496.504 87.4608 190.229 + endloop + endfacet + facet normal 0.188039 -0.981075 -0.0461932 + outer loop + vertex 499.904 88.0457 191.647 + vertex 495.866 86.9192 199.134 + vertex 496.504 87.4608 190.229 + endloop + endfacet + facet normal 0.181405 -0.982966 -0.0295036 + outer loop + vertex 499.904 88.0457 191.647 + vertex 496.504 87.4608 190.229 + vertex 500.815 88.4872 182.534 + endloop + endfacet + facet normal 0.202095 -0.978987 -0.0272432 + outer loop + vertex 499.904 88.0457 191.647 + vertex 500.815 88.4872 182.534 + vertex 502.935 88.7874 187.476 + endloop + endfacet + facet normal 0.187162 -0.981981 -0.0261476 + outer loop + vertex 500.815 88.4872 182.534 + vertex 496.504 87.4608 190.229 + vertex 497.176 87.8264 181.306 + endloop + endfacet + facet normal 0.181216 -0.98217 -0.0500381 + outer loop + vertex 499.686 87.568 200.232 + vertex 495.866 86.9192 199.134 + vertex 499.904 88.0457 191.647 + endloop + endfacet + facet normal 0.204737 -0.97758 -0.049185 + outer loop + vertex 499.686 87.568 200.232 + vertex 499.904 88.0457 191.647 + vertex 502.062 88.392 193.744 + endloop + endfacet + facet normal 0.185991 -0.980208 -0.0678164 + outer loop + vertex 499.686 87.568 200.232 + vertex 495.227 86.1822 208.035 + vertex 495.866 86.9192 199.134 + endloop + endfacet + facet normal 0.167684 -0.983395 -0.0693944 + outer loop + vertex 495.227 86.1822 208.035 + vertex 490.054 85.3152 207.819 + vertex 495.866 86.9192 199.134 + endloop + endfacet + facet normal 0.168216 -0.98174 -0.0888202 + outer loop + vertex 495.227 86.1822 208.035 + vertex 489.307 84.3864 216.672 + vertex 490.054 85.3152 207.819 + endloop + endfacet + facet normal 0.154027 -0.983937 -0.0902467 + outer loop + vertex 489.307 84.3864 216.672 + vertex 482.635 83.3366 216.73 + vertex 490.054 85.3152 207.819 + endloop + endfacet + facet normal 0.155093 -0.983852 -0.0893405 + outer loop + vertex 490.054 85.3152 207.819 + vertex 482.635 83.3366 216.73 + vertex 483.532 84.2736 207.968 + endloop + endfacet + facet normal 0.140994 -0.98582 -0.090994 + outer loop + vertex 482.635 83.3366 216.73 + vertex 475.182 82.2703 216.733 + vertex 483.532 84.2736 207.968 + endloop + endfacet + facet normal 0.140725 -0.983991 -0.109355 + outer loop + vertex 482.635 83.3366 216.73 + vertex 474.105 81.1648 225.295 + vertex 475.182 82.2703 216.733 + endloop + endfacet + facet normal 0.124459 -0.985923 -0.11165 + outer loop + vertex 474.105 81.1648 225.295 + vertex 466.293 80.2102 225.016 + vertex 475.182 82.2703 216.733 + endloop + endfacet + facet normal 0.125864 -0.985915 -0.11014 + outer loop + vertex 475.182 82.2703 216.733 + vertex 466.293 80.2102 225.016 + vertex 467.555 81.3136 216.582 + endloop + endfacet + facet normal 0.107078 -0.987786 -0.113196 + outer loop + vertex 466.293 80.2102 225.016 + vertex 458.613 79.417 224.674 + vertex 467.555 81.3136 216.582 + endloop + endfacet + facet normal 0.107583 -0.985757 -0.12926 + outer loop + vertex 466.293 80.2102 225.016 + vertex 457.115 78.1834 232.834 + vertex 458.613 79.417 224.674 + endloop + endfacet + facet normal 0.085264 -0.987361 -0.1336 + outer loop + vertex 457.115 78.1834 232.834 + vertex 449.392 77.5764 232.392 + vertex 458.613 79.417 224.674 + endloop + endfacet + facet normal 0.0861941 -0.987428 -0.132505 + outer loop + vertex 458.613 79.417 224.674 + vertex 449.392 77.5764 232.392 + vertex 451.091 78.7992 224.384 + endloop + endfacet + facet normal 0.0563357 -0.988684 -0.139031 + outer loop + vertex 449.392 77.5764 232.392 + vertex 441.673 77.1986 231.95 + vertex 451.091 78.7992 224.384 + endloop + endfacet + facet normal 0.0570954 -0.986373 -0.1543 + outer loop + vertex 449.392 77.5764 232.392 + vertex 439.68 75.8849 239.611 + vertex 441.673 77.1986 231.95 + endloop + endfacet + facet normal 0.0173813 -0.986206 -0.164606 + outer loop + vertex 439.68 75.8849 239.611 + vertex 431.57 75.8777 238.798 + vertex 441.673 77.1986 231.95 + endloop + endfacet + facet normal 0.0173195 -0.986193 -0.164694 + outer loop + vertex 441.673 77.1986 231.95 + vertex 431.57 75.8777 238.798 + vertex 433.779 77.1641 231.326 + endloop + endfacet + facet normal -0.0291458 -0.983601 -0.177988 + outer loop + vertex 431.57 75.8777 238.798 + vertex 423.168 76.3403 237.617 + vertex 433.779 77.1641 231.326 + endloop + endfacet + facet normal -0.0265854 -0.980449 -0.194968 + outer loop + vertex 431.57 75.8777 238.798 + vertex 420.639 75.0012 244.696 + vertex 423.168 76.3403 237.617 + endloop + endfacet + facet normal -0.0259923 -0.980676 -0.193903 + outer loop + vertex 429.222 74.5022 246.069 + vertex 420.639 75.0012 244.696 + vertex 431.57 75.8777 238.798 + endloop + endfacet + facet normal -0.0233393 -0.977562 -0.209352 + outer loop + vertex 429.222 74.5022 246.069 + vertex 417.906 73.5997 251.544 + vertex 420.639 75.0012 244.696 + endloop + endfacet + facet normal -0.0238958 -0.97731 -0.210461 + outer loop + vertex 426.597 73.0479 253.12 + vertex 417.906 73.5997 251.544 + vertex 429.222 74.5022 246.069 + endloop + endfacet + facet normal 0.0209343 -0.980685 -0.194473 + outer loop + vertex 437.486 74.4822 247.059 + vertex 426.597 73.0479 253.12 + vertex 429.222 74.5022 246.069 + endloop + endfacet + facet normal 0.0191423 -0.983557 -0.179582 + outer loop + vertex 437.486 74.4822 247.059 + vertex 429.222 74.5022 246.069 + vertex 439.68 75.8849 239.611 + endloop + endfacet + facet normal 0.0575388 -0.984044 -0.168365 + outer loop + vertex 447.594 76.2432 240.221 + vertex 437.486 74.4822 247.059 + vertex 439.68 75.8849 239.611 + endloop + endfacet + facet normal 0.0568988 -0.983924 -0.16928 + outer loop + vertex 445.583 74.81 247.875 + vertex 437.486 74.4822 247.059 + vertex 447.594 76.2432 240.221 + endloop + endfacet + facet normal 0.0857351 -0.983132 -0.161558 + outer loop + vertex 455.507 76.8341 240.825 + vertex 445.583 74.81 247.875 + vertex 447.594 76.2432 240.221 + endloop + endfacet + facet normal 0.0849469 -0.985142 -0.14926 + outer loop + vertex 455.507 76.8341 240.825 + vertex 447.594 76.2432 240.221 + vertex 457.115 78.1834 232.834 + endloop + endfacet + facet normal 0.106846 -0.983703 -0.14461 + outer loop + vertex 464.983 78.9678 233.311 + vertex 455.507 76.8341 240.825 + vertex 457.115 78.1834 232.834 + endloop + endfacet + facet normal 0.1055 -0.983602 -0.146279 + outer loop + vertex 463.574 77.6029 241.473 + vertex 455.507 76.8341 240.825 + vertex 464.983 78.9678 233.311 + endloop + endfacet + facet normal 0.123801 -0.981972 -0.142847 + outer loop + vertex 472.973 79.9149 233.726 + vertex 463.574 77.6029 241.473 + vertex 464.983 78.9678 233.311 + endloop + endfacet + facet normal 0.123328 -0.983905 -0.129312 + outer loop + vertex 472.973 79.9149 233.726 + vertex 464.983 78.9678 233.311 + vertex 474.105 81.1648 225.295 + endloop + endfacet + facet normal 0.139496 -0.982062 -0.126869 + outer loop + vertex 481.729 82.2324 225.414 + vertex 472.973 79.9149 233.726 + vertex 474.105 81.1648 225.295 + endloop + endfacet + facet normal 0.138134 -0.982068 -0.128306 + outer loop + vertex 480.753 80.974 233.995 + vertex 472.973 79.9149 233.726 + vertex 481.729 82.2324 225.414 + endloop + endfacet + facet normal 0.151975 -0.98026 -0.126466 + outer loop + vertex 488.538 83.2786 225.486 + vertex 480.753 80.974 233.995 + vertex 481.729 82.2324 225.414 + endloop + endfacet + facet normal 0.152102 -0.982206 -0.110162 + outer loop + vertex 488.538 83.2786 225.486 + vertex 481.729 82.2324 225.414 + vertex 489.307 84.3864 216.672 + endloop + endfacet + facet normal 0.166028 -0.980114 -0.108683 + outer loop + vertex 494.58 85.2478 216.958 + vertex 488.538 83.2786 225.486 + vertex 489.307 84.3864 216.672 + endloop + endfacet + facet normal 0.162792 -0.980392 -0.11104 + outer loop + vertex 493.944 84.1222 225.964 + vertex 488.538 83.2786 225.486 + vertex 494.58 85.2478 216.958 + endloop + endfacet + facet normal 0.180311 -0.977502 -0.109442 + outer loop + vertex 498.585 85.8625 218.067 + vertex 493.944 84.1222 225.964 + vertex 494.58 85.2478 216.958 + endloop + endfacet + facet normal 0.176265 -0.979892 -0.0935028 + outer loop + vertex 498.585 85.8625 218.067 + vertex 494.58 85.2478 216.958 + vertex 498.734 86.7137 209.428 + endloop + endfacet + facet normal 0.200791 -0.975246 -0.0926209 + outer loop + vertex 498.585 85.8625 218.067 + vertex 498.734 86.7137 209.428 + vertex 501 86.9917 211.413 + endloop + endfacet + facet normal 0.183781 -0.978915 -0.0891657 + outer loop + vertex 498.734 86.7137 209.428 + vertex 494.58 85.2478 216.958 + vertex 495.227 86.1822 208.035 + endloop + endfacet + facet normal 0.172396 -0.978375 -0.114285 + outer loop + vertex 497.977 84.6164 227.818 + vertex 493.944 84.1222 225.964 + vertex 498.585 85.8625 218.067 + endloop + endfacet + facet normal 0.196255 -0.974106 -0.112253 + outer loop + vertex 497.977 84.6164 227.818 + vertex 498.585 85.8625 218.067 + vertex 501.001 85.8404 222.482 + endloop + endfacet + facet normal 0.191004 -0.974784 -0.115384 + outer loop + vertex 501.001 85.8404 222.482 + vertex 500.561 85.1887 227.26 + vertex 497.977 84.6164 227.818 + endloop + endfacet + facet normal 0.187422 -0.973543 -0.130717 + outer loop + vertex 500.561 85.1887 227.26 + vertex 500.347 84.447 232.477 + vertex 497.977 84.6164 227.818 + endloop + endfacet + facet normal 0.186735 -0.973721 -0.130374 + outer loop + vertex 496.998 83.2083 236.931 + vertex 497.977 84.6164 227.818 + vertex 500.347 84.447 232.477 + endloop + endfacet + facet normal 0.174933 -0.974647 -0.139507 + outer loop + vertex 500.347 84.447 232.477 + vertex 499.878 83.3013 239.893 + vertex 496.998 83.2083 236.931 + endloop + endfacet + facet normal 0.179816 -0.973058 -0.144305 + outer loop + vertex 496.632 81.8783 245.444 + vertex 496.998 83.2083 236.931 + vertex 499.878 83.3013 239.893 + endloop + endfacet + facet normal 0.175651 -0.97344 -0.146839 + outer loop + vertex 499.878 83.3013 239.893 + vertex 499.479 82.5205 244.592 + vertex 496.632 81.8783 245.444 + endloop + endfacet + facet normal 0.173154 -0.972682 -0.154618 + outer loop + vertex 499.479 82.5205 244.592 + vertex 499.146 81.6559 249.658 + vertex 496.632 81.8783 245.444 + endloop + endfacet + facet normal 0.171984 -0.972998 -0.153936 + outer loop + vertex 495.455 80.2668 254.314 + vertex 496.632 81.8783 245.444 + vertex 499.146 81.6559 249.658 + endloop + endfacet + facet normal 0.167265 -0.973212 -0.15774 + outer loop + vertex 499.146 81.6559 249.658 + vertex 498.532 80.3508 257.06 + vertex 495.455 80.2668 254.314 + endloop + endfacet + facet normal 0.167217 -0.973228 -0.157686 + outer loop + vertex 494.983 78.7834 262.969 + vertex 495.455 80.2668 254.314 + vertex 498.532 80.3508 257.06 + endloop + endfacet + facet normal 0.162876 -0.973526 -0.160373 + outer loop + vertex 498.532 80.3508 257.06 + vertex 498.028 79.4889 261.779 + vertex 494.983 78.7834 262.969 + endloop + endfacet + facet normal 0.165301 -0.974068 -0.154489 + outer loop + vertex 498.028 79.4889 261.779 + vertex 497.653 78.5952 267.014 + vertex 494.983 78.7834 262.969 + endloop + endfacet + facet normal 0.165293 -0.97407 -0.154484 + outer loop + vertex 493.884 77.0333 272.829 + vertex 494.983 78.7834 262.969 + vertex 497.653 78.5952 267.014 + endloop + endfacet + facet normal 0.169685 -0.973775 -0.151558 + outer loop + vertex 497.653 78.5952 267.014 + vertex 497.208 77.5363 273.319 + vertex 493.884 77.0333 272.829 + endloop + endfacet + facet normal 0.169358 -0.974249 -0.148852 + outer loop + vertex 497.208 77.5363 273.319 + vertex 495.529 76.5824 277.652 + vertex 493.884 77.0333 272.829 + endloop + endfacet + facet normal 0.161585 -0.975945 -0.146359 + outer loop + vertex 492.698 75.5889 281.151 + vertex 493.884 77.0333 272.829 + vertex 495.529 76.5824 277.652 + endloop + endfacet + facet normal 0.176342 -0.97514 -0.134184 + outer loop + vertex 495.529 76.5824 277.652 + vertex 495.033 75.6797 283.56 + vertex 492.698 75.5889 281.151 + endloop + endfacet + facet normal 0.171295 -0.976707 -0.129232 + outer loop + vertex 492.208 74.6467 287.623 + vertex 492.698 75.5889 281.151 + vertex 495.033 75.6797 283.56 + endloop + endfacet + facet normal 0.192206 -0.974689 -0.114182 + outer loop + vertex 495.033 75.6797 283.56 + vertex 493.933 74.7059 290.02 + vertex 492.208 74.6467 287.623 + endloop + endfacet + facet normal 0.182437 -0.977369 -0.107087 + outer loop + vertex 491.084 73.75 293.892 + vertex 492.208 74.6467 287.623 + vertex 493.933 74.7059 290.02 + endloop + endfacet + facet normal 0.209623 -0.973971 -0.0862445 + outer loop + vertex 493.933 74.7059 290.02 + vertex 492.596 73.8866 296.023 + vertex 491.084 73.75 293.892 + endloop + endfacet + facet normal 0.201311 -0.976238 -0.0802039 + outer loop + vertex 492.596 73.8866 296.023 + vertex 490.545 73.2869 298.176 + vertex 491.084 73.75 293.892 + endloop + endfacet + facet normal 0.21984 -0.972455 -0.077465 + outer loop + vertex 490.545 73.2869 298.176 + vertex 489.573 73.0979 297.789 + vertex 491.084 73.75 293.892 + endloop + endfacet + facet normal 0.207452 -0.974747 -0.0826523 + outer loop + vertex 489.573 73.0979 297.789 + vertex 487.964 72.8223 297.001 + vertex 491.084 73.75 293.892 + endloop + endfacet + facet normal 0.193838 -0.97625 -0.0967597 + outer loop + vertex 491.084 73.75 293.892 + vertex 487.964 72.8223 297.001 + vertex 489.059 73.5306 292.048 + endloop + endfacet + facet normal 0.202306 -0.974736 -0.0946721 + outer loop + vertex 487.964 72.8223 297.001 + vertex 484.891 72.2632 296.191 + vertex 489.059 73.5306 292.048 + endloop + endfacet + facet normal 0.190399 -0.975859 -0.106992 + outer loop + vertex 489.059 73.5306 292.048 + vertex 484.891 72.2632 296.191 + vertex 485.901 72.9791 291.459 + endloop + endfacet + facet normal 0.192042 -0.974361 -0.117217 + outer loop + vertex 489.059 73.5306 292.048 + vertex 485.901 72.9791 291.459 + vertex 489.538 74.2835 286.575 + endloop + endfacet + facet normal 0.179401 -0.976597 -0.118631 + outer loop + vertex 492.208 74.6467 287.623 + vertex 489.059 73.5306 292.048 + vertex 489.538 74.2835 286.575 + endloop + endfacet + facet normal 0.184584 -0.975094 -0.122965 + outer loop + vertex 489.538 74.2835 286.575 + vertex 485.901 72.9791 291.459 + vertex 486.208 73.5668 287.259 + endloop + endfacet + facet normal 0.181271 -0.973748 -0.137677 + outer loop + vertex 486.208 73.5668 287.259 + vertex 487.94 74.8474 280.482 + vertex 489.538 74.2835 286.575 + endloop + endfacet + facet normal 0.171094 -0.975933 -0.13521 + outer loop + vertex 487.94 74.8474 280.482 + vertex 492.698 75.5889 281.151 + vertex 489.538 74.2835 286.575 + endloop + endfacet + facet normal 0.18259 -0.973555 -0.137303 + outer loop + vertex 486.208 73.5668 287.259 + vertex 482.737 73.006 286.619 + vertex 487.94 74.8474 280.482 + endloop + endfacet + facet normal 0.176517 -0.973919 -0.142561 + outer loop + vertex 482.737 73.006 286.619 + vertex 481.257 73.2535 283.096 + vertex 487.94 74.8474 280.482 + endloop + endfacet + facet normal 0.173287 -0.973312 -0.150453 + outer loop + vertex 483.464 74.6359 276.695 + vertex 487.94 74.8474 280.482 + vertex 481.257 73.2535 283.096 + endloop + endfacet + facet normal 0.169233 -0.973792 -0.151955 + outer loop + vertex 481.257 73.2535 283.096 + vertex 477.192 72.8398 281.221 + vertex 483.464 74.6359 276.695 + endloop + endfacet + facet normal 0.16529 -0.973612 -0.157348 + outer loop + vertex 483.464 74.6359 276.695 + vertex 477.192 72.8398 281.221 + vertex 478.061 73.8831 275.678 + endloop + endfacet + facet normal 0.165202 -0.973714 -0.156809 + outer loop + vertex 483.464 74.6359 276.695 + vertex 478.061 73.8831 275.678 + vertex 484.263 76.0084 269.015 + endloop + endfacet + facet normal 0.164843 -0.973767 -0.156856 + outer loop + vertex 489.616 76.7017 270.336 + vertex 483.464 74.6359 276.695 + vertex 484.263 76.0084 269.015 + endloop + endfacet + facet normal 0.164768 -0.973835 -0.156515 + outer loop + vertex 489.616 76.7017 270.336 + vertex 484.263 76.0084 269.015 + vertex 490.57 78.3087 261.341 + endloop + endfacet + facet normal 0.162641 -0.974147 -0.156797 + outer loop + vertex 494.983 78.7834 262.969 + vertex 489.616 76.7017 270.336 + vertex 490.57 78.3087 261.341 + endloop + endfacet + facet normal 0.16081 -0.973962 -0.159806 + outer loop + vertex 490.57 78.3087 261.341 + vertex 484.263 76.0084 269.015 + vertex 484.833 77.4748 260.65 + endloop + endfacet + facet normal 0.1606 -0.97436 -0.157577 + outer loop + vertex 490.57 78.3087 261.341 + vertex 484.833 77.4748 260.65 + vertex 491.469 79.8765 252.564 + endloop + endfacet + facet normal 0.164378 -0.973808 -0.157091 + outer loop + vertex 495.455 80.2668 254.314 + vertex 490.57 78.3087 261.341 + vertex 491.469 79.8765 252.564 + endloop + endfacet + facet normal 0.160137 -0.974374 -0.157961 + outer loop + vertex 491.469 79.8765 252.564 + vertex 484.833 77.4748 260.65 + vertex 485.783 79.0662 251.797 + endloop + endfacet + facet normal 0.159545 -0.975333 -0.15255 + outer loop + vertex 491.469 79.8765 252.564 + vertex 485.783 79.0662 251.797 + vertex 492.359 81.3904 243.815 + endloop + endfacet + facet normal 0.168903 -0.973942 -0.151357 + outer loop + vertex 496.632 81.8783 245.444 + vertex 491.469 79.8765 252.564 + vertex 492.359 81.3904 243.815 + endloop + endfacet + facet normal 0.160938 -0.975285 -0.151388 + outer loop + vertex 492.359 81.3904 243.815 + vertex 485.783 79.0662 251.797 + vertex 486.778 80.5956 243.002 + endloop + endfacet + facet normal 0.159869 -0.976787 -0.142577 + outer loop + vertex 492.359 81.3904 243.815 + vertex 486.778 80.5956 243.002 + vertex 493.189 82.8139 234.993 + endloop + endfacet + facet normal 0.172715 -0.97482 -0.141051 + outer loop + vertex 496.998 83.2083 236.931 + vertex 492.359 81.3904 243.815 + vertex 493.189 82.8139 234.993 + endloop + endfacet + facet normal 0.162415 -0.976668 -0.140506 + outer loop + vertex 493.189 82.8139 234.993 + vertex 486.778 80.5956 243.002 + vertex 487.689 82.0047 234.26 + endloop + endfacet + facet normal 0.161071 -0.978565 -0.128325 + outer loop + vertex 493.189 82.8139 234.993 + vertex 487.689 82.0047 234.26 + vertex 493.944 84.1222 225.964 + endloop + endfacet + facet normal 0.149913 -0.978435 -0.142093 + outer loop + vertex 486.778 80.5956 243.002 + vertex 479.707 79.5781 242.549 + vertex 487.689 82.0047 234.26 + endloop + endfacet + facet normal 0.150801 -0.978423 -0.141235 + outer loop + vertex 487.689 82.0047 234.26 + vertex 479.707 79.5781 242.549 + vertex 480.753 80.974 233.995 + endloop + endfacet + facet normal 0.137286 -0.980131 -0.143166 + outer loop + vertex 479.707 79.5781 242.549 + vertex 471.762 78.534 242.078 + vertex 480.753 80.974 233.995 + endloop + endfacet + facet normal 0.13772 -0.978365 -0.154386 + outer loop + vertex 479.707 79.5781 242.549 + vertex 470.508 77.0211 250.547 + vertex 471.762 78.534 242.078 + endloop + endfacet + facet normal 0.12212 -0.980021 -0.15699 + outer loop + vertex 470.508 77.0211 250.547 + vertex 462.076 76.1107 249.671 + vertex 471.762 78.534 242.078 + endloop + endfacet + facet normal 0.122964 -0.980084 -0.155934 + outer loop + vertex 471.762 78.534 242.078 + vertex 462.076 76.1107 249.671 + vertex 463.574 77.6029 241.473 + endloop + endfacet + facet normal 0.10489 -0.981608 -0.159514 + outer loop + vertex 462.076 76.1107 249.671 + vertex 453.729 75.3717 248.73 + vertex 463.574 77.6029 241.473 + endloop + endfacet + facet normal 0.105847 -0.97985 -0.169384 + outer loop + vertex 462.076 76.1107 249.671 + vertex 451.837 73.771 256.808 + vertex 453.729 75.3717 248.73 + endloop + endfacet + facet normal 0.0852792 -0.980971 -0.174422 + outer loop + vertex 451.837 73.771 256.808 + vertex 443.331 73.2665 255.486 + vertex 453.729 75.3717 248.73 + endloop + endfacet + facet normal 0.0858526 -0.981072 -0.173571 + outer loop + vertex 453.729 75.3717 248.73 + vertex 443.331 73.2665 255.486 + vertex 445.583 74.81 247.875 + endloop + endfacet + facet normal 0.0583157 -0.9816 -0.181827 + outer loop + vertex 443.331 73.2665 255.486 + vertex 434.994 72.9825 254.345 + vertex 445.583 74.81 247.875 + endloop + endfacet + facet normal 0.0599665 -0.979063 -0.194523 + outer loop + vertex 443.331 73.2665 255.486 + vertex 432.263 71.3868 261.535 + vertex 434.994 72.9825 254.345 + endloop + endfacet + facet normal 0.0232903 -0.977814 -0.208175 + outer loop + vertex 432.263 71.3868 261.535 + vertex 423.66 71.5158 259.966 + vertex 434.994 72.9825 254.345 + endloop + endfacet + facet normal 0.0228767 -0.977655 -0.208967 + outer loop + vertex 434.994 72.9825 254.345 + vertex 423.66 71.5158 259.966 + vertex 426.597 73.0479 253.12 + endloop + endfacet + facet normal -0.0215076 -0.973632 -0.227108 + outer loop + vertex 423.66 71.5158 259.966 + vertex 414.902 72.1325 258.152 + vertex 426.597 73.0479 253.12 + endloop + endfacet + facet normal -0.0178556 -0.969756 -0.243421 + outer loop + vertex 423.66 71.5158 259.966 + vertex 411.774 70.5914 264.521 + vertex 414.902 72.1325 258.152 + endloop + endfacet + facet normal -0.0173458 -0.970082 -0.242156 + outer loop + vertex 420.74 69.915 266.588 + vertex 411.774 70.5914 264.521 + vertex 423.66 71.5158 259.966 + endloop + endfacet + facet normal -0.012741 -0.965367 -0.260585 + outer loop + vertex 420.74 69.915 266.588 + vertex 409.164 68.9998 270.545 + vertex 411.774 70.5914 264.521 + endloop + endfacet + facet normal -0.00977338 -0.96757 -0.252413 + outer loop + vertex 418.559 68.357 272.645 + vertex 409.164 68.9998 270.545 + vertex 420.74 69.915 266.588 + endloop + endfacet + facet normal 0.0330356 -0.970749 -0.237814 + outer loop + vertex 429.661 69.7398 268.543 + vertex 418.559 68.357 272.645 + vertex 420.74 69.915 266.588 + endloop + endfacet + facet normal 0.028727 -0.975399 -0.218567 + outer loop + vertex 429.661 69.7398 268.543 + vertex 420.74 69.915 266.588 + vertex 432.263 71.3868 261.535 + endloop + endfacet + facet normal 0.0633959 -0.976506 -0.205953 + outer loop + vertex 441.022 71.6019 263.211 + vertex 429.661 69.7398 268.543 + vertex 432.263 71.3868 261.535 + endloop + endfacet + facet normal 0.0652781 -0.977172 -0.202174 + outer loop + vertex 439.179 69.8956 270.863 + vertex 429.661 69.7398 268.543 + vertex 441.022 71.6019 263.211 + endloop + endfacet + facet normal 0.0897132 -0.976465 -0.19613 + outer loop + vertex 449.929 71.9684 265.461 + vertex 439.179 69.8956 270.863 + vertex 441.022 71.6019 263.211 + endloop + endfacet + facet normal 0.0869425 -0.978931 -0.184757 + outer loop + vertex 449.929 71.9684 265.461 + vertex 441.022 71.6019 263.211 + vertex 451.837 73.771 256.808 + endloop + endfacet + facet normal 0.10683 -0.977823 -0.18014 + outer loop + vertex 460.595 74.4754 258.178 + vertex 449.929 71.9684 265.461 + vertex 451.837 73.771 256.808 + endloop + endfacet + facet normal 0.107896 -0.977982 -0.178634 + outer loop + vertex 459.383 72.7179 267.067 + vertex 449.929 71.9684 265.461 + vertex 460.595 74.4754 258.178 + endloop + endfacet + facet normal 0.124352 -0.976487 -0.176096 + outer loop + vertex 469.324 75.3757 259.349 + vertex 459.383 72.7179 267.067 + vertex 460.595 74.4754 258.178 + endloop + endfacet + facet normal 0.123229 -0.978345 -0.1663 + outer loop + vertex 469.324 75.3757 259.349 + vertex 460.595 74.4754 258.178 + vertex 470.508 77.0211 250.547 + endloop + endfacet + facet normal 0.138028 -0.976754 -0.16401 + outer loop + vertex 478.616 78.0505 251.24 + vertex 469.324 75.3757 259.349 + vertex 470.508 77.0211 250.547 + endloop + endfacet + facet normal 0.139555 -0.976826 -0.162284 + outer loop + vertex 477.544 76.4085 260.202 + vertex 469.324 75.3757 259.349 + vertex 478.616 78.0505 251.24 + endloop + endfacet + facet normal 0.150739 -0.975426 -0.16069 + outer loop + vertex 485.783 79.0662 251.797 + vertex 477.544 76.4085 260.202 + vertex 478.616 78.0505 251.24 + endloop + endfacet + facet normal 0.140233 -0.975297 -0.170674 + outer loop + vertex 477.544 76.4085 260.202 + vertex 468.252 73.6115 268.55 + vertex 469.324 75.3757 259.349 + endloop + endfacet + facet normal 0.14466 -0.97549 -0.165812 + outer loop + vertex 476.667 74.709 269.435 + vertex 468.252 73.6115 268.55 + vertex 477.544 76.4085 260.202 + endloop + endfacet + facet normal 0.152709 -0.974425 -0.164851 + outer loop + vertex 484.833 77.4748 260.65 + vertex 476.667 74.709 269.435 + vertex 477.544 76.4085 260.202 + endloop + endfacet + facet normal 0.145351 -0.973894 -0.174365 + outer loop + vertex 468.252 73.6115 268.55 + vertex 476.667 74.709 269.435 + vertex 469.071 72.6135 274.807 + endloop + endfacet + facet normal 0.141712 -0.974498 -0.173985 + outer loop + vertex 464.281 71.9096 274.848 + vertex 468.252 73.6115 268.55 + vertex 469.071 72.6135 274.807 + endloop + endfacet + facet normal 0.141717 -0.974522 -0.173846 + outer loop + vertex 469.071 72.6135 274.807 + vertex 463.639 71.1057 278.831 + vertex 464.281 71.9096 274.848 + endloop + endfacet + facet normal 0.135603 -0.975192 -0.174966 + outer loop + vertex 463.639 71.1057 278.831 + vertex 459.309 70.6678 277.916 + vertex 464.281 71.9096 274.848 + endloop + endfacet + facet normal 0.131884 -0.974643 -0.180771 + outer loop + vertex 464.281 71.9096 274.848 + vertex 459.309 70.6678 277.916 + vertex 460.401 71.6883 273.21 + endloop + endfacet + facet normal 0.125023 -0.975227 -0.18249 + outer loop + vertex 459.309 70.6678 277.916 + vertex 454.748 70.2795 276.866 + vertex 460.401 71.6883 273.21 + endloop + endfacet + facet normal 0.122484 -0.974835 -0.186265 + outer loop + vertex 460.401 71.6883 273.21 + vertex 454.748 70.2795 276.866 + vertex 455.289 71.0942 272.958 + endloop + endfacet + facet normal 0.122417 -0.975319 -0.183756 + outer loop + vertex 455.289 71.0942 272.958 + vertex 459.383 72.7179 267.067 + vertex 460.401 71.6883 273.21 + endloop + endfacet + facet normal 0.129036 -0.974291 -0.184681 + outer loop + vertex 459.383 72.7179 267.067 + vertex 468.252 73.6115 268.55 + vertex 460.401 71.6883 273.21 + endloop + endfacet + facet normal 0.11096 -0.975166 -0.191676 + outer loop + vertex 455.289 71.0942 272.958 + vertex 450.992 70.9672 271.117 + vertex 459.383 72.7179 267.067 + endloop + endfacet + facet normal 0.111101 -0.975084 -0.192009 + outer loop + vertex 455.289 71.0942 272.958 + vertex 449.93 69.9546 275.644 + vertex 450.992 70.9672 271.117 + endloop + endfacet + facet normal 0.100977 -0.975687 -0.19452 + outer loop + vertex 449.93 69.9546 275.644 + vertex 444.526 69.6865 274.184 + vertex 450.992 70.9672 271.117 + endloop + endfacet + facet normal 0.101408 -0.975813 -0.193664 + outer loop + vertex 450.992 70.9672 271.117 + vertex 444.526 69.6865 274.184 + vertex 446.182 70.5821 270.539 + endloop + endfacet + facet normal 0.101216 -0.976197 -0.191818 + outer loop + vertex 446.182 70.5821 270.539 + vertex 449.929 71.9684 265.461 + vertex 450.992 70.9672 271.117 + endloop + endfacet + facet normal 0.0863724 -0.975876 -0.200512 + outer loop + vertex 446.182 70.5821 270.539 + vertex 444.526 69.6865 274.184 + vertex 439.179 69.8956 270.863 + endloop + endfacet + facet normal 0.0892207 -0.974682 -0.205023 + outer loop + vertex 436.484 68.1913 277.793 + vertex 439.179 69.8956 270.863 + vertex 444.526 69.6865 274.184 + endloop + endfacet + facet normal 0.0909152 -0.975262 -0.201488 + outer loop + vertex 444.362 68.8981 277.926 + vertex 436.484 68.1913 277.793 + vertex 444.526 69.6865 274.184 + endloop + endfacet + facet normal 0.0908937 -0.973088 -0.211752 + outer loop + vertex 444.362 68.8981 277.926 + vertex 442.086 67.9952 281.098 + vertex 436.484 68.1913 277.793 + endloop + endfacet + facet normal 0.0930466 -0.972096 -0.215342 + outer loop + vertex 434.909 66.9574 282.682 + vertex 436.484 68.1913 277.793 + vertex 442.086 67.9952 281.098 + endloop + endfacet + facet normal 0.0930269 -0.97208 -0.215421 + outer loop + vertex 441.334 67.2936 283.94 + vertex 434.909 66.9574 282.682 + vertex 442.086 67.9952 281.098 + endloop + endfacet + facet normal 0.108 -0.971436 -0.211299 + outer loop + vertex 447.179 68.1989 282.765 + vertex 441.334 67.2936 283.94 + vertex 442.086 67.9952 281.098 + endloop + endfacet + facet normal 0.105341 -0.973512 -0.202922 + outer loop + vertex 447.179 68.1989 282.765 + vertex 442.086 67.9952 281.098 + vertex 448.763 69.0618 279.448 + endloop + endfacet + facet normal 0.118201 -0.973307 -0.196727 + outer loop + vertex 453.514 69.3815 280.721 + vertex 447.179 68.1989 282.765 + vertex 448.763 69.0618 279.448 + endloop + endfacet + facet normal 0.116464 -0.974881 -0.189852 + outer loop + vertex 453.514 69.3815 280.721 + vertex 448.763 69.0618 279.448 + vertex 454.748 70.2795 276.866 + endloop + endfacet + facet normal 0.114774 -0.974359 -0.193524 + outer loop + vertex 454.748 70.2795 276.866 + vertex 448.763 69.0618 279.448 + vertex 449.93 69.9546 275.644 + endloop + endfacet + facet normal 0.104313 -0.974868 -0.196852 + outer loop + vertex 448.763 69.0618 279.448 + vertex 444.362 68.8981 277.926 + vertex 449.93 69.9546 275.644 + endloop + endfacet + facet normal 0.119554 -0.973911 -0.192882 + outer loop + vertex 451.809 68.5137 284.045 + vertex 447.179 68.1989 282.765 + vertex 453.514 69.3815 280.721 + endloop + endfacet + facet normal 0.129985 -0.973634 -0.187459 + outer loop + vertex 458.014 69.7792 281.775 + vertex 451.809 68.5137 284.045 + vertex 453.514 69.3815 280.721 + endloop + endfacet + facet normal 0.128663 -0.974972 -0.181315 + outer loop + vertex 458.014 69.7792 281.775 + vertex 453.514 69.3815 280.721 + vertex 459.309 70.6678 277.916 + endloop + endfacet + facet normal 0.131782 -0.97426 -0.182895 + outer loop + vertex 456.306 68.9154 285.146 + vertex 451.809 68.5137 284.045 + vertex 458.014 69.7792 281.775 + endloop + endfacet + facet normal 0.140216 -0.973893 -0.178528 + outer loop + vertex 462.34 70.2236 282.748 + vertex 456.306 68.9154 285.146 + vertex 458.014 69.7792 281.775 + endloop + endfacet + facet normal 0.13917 -0.974971 -0.173386 + outer loop + vertex 462.34 70.2236 282.748 + vertex 458.014 69.7792 281.775 + vertex 463.639 71.1057 278.831 + endloop + endfacet + facet normal 0.145171 -0.974468 -0.171282 + outer loop + vertex 467.945 71.599 279.674 + vertex 462.34 70.2236 282.748 + vertex 463.639 71.1057 278.831 + endloop + endfacet + facet normal 0.148159 -0.974926 -0.166039 + outer loop + vertex 466.66 70.7239 283.666 + vertex 462.34 70.2236 282.748 + vertex 467.945 71.599 279.674 + endloop + endfacet + facet normal 0.153334 -0.974426 -0.164265 + outer loop + vertex 472.441 72.1824 280.41 + vertex 466.66 70.7239 283.666 + vertex 467.945 71.599 279.674 + endloop + endfacet + facet normal 0.153151 -0.974675 -0.162954 + outer loop + vertex 472.441 72.1824 280.41 + vertex 467.945 71.599 279.674 + vertex 472.946 72.9612 276.226 + endloop + endfacet + facet normal 0.158138 -0.973999 -0.162227 + outer loop + vertex 478.061 73.8831 275.678 + vertex 472.441 72.1824 280.41 + vertex 472.946 72.9612 276.226 + endloop + endfacet + facet normal 0.157892 -0.97373 -0.164074 + outer loop + vertex 472.946 72.9612 276.226 + vertex 476.667 74.709 269.435 + vertex 478.061 73.8831 275.678 + endloop + endfacet + facet normal 0.149185 -0.974334 -0.168573 + outer loop + vertex 472.946 72.9612 276.226 + vertex 467.945 71.599 279.674 + vertex 469.071 72.6135 274.807 + endloop + endfacet + facet normal 0.155975 -0.974761 -0.159726 + outer loop + vertex 471.109 71.2791 284.622 + vertex 466.66 70.7239 283.666 + vertex 472.441 72.1824 280.41 + endloop + endfacet + facet normal 0.161699 -0.974145 -0.157784 + outer loop + vertex 477.192 72.8398 281.221 + vertex 471.109 71.2791 284.622 + vertex 472.441 72.1824 280.41 + endloop + endfacet + facet normal 0.163972 -0.974396 -0.153834 + outer loop + vertex 475.347 71.8102 285.775 + vertex 471.109 71.2791 284.622 + vertex 477.192 72.8398 281.221 + endloop + endfacet + facet normal 0.164088 -0.974302 -0.154305 + outer loop + vertex 475.347 71.8102 285.775 + vertex 469.291 70.3928 288.285 + vertex 471.109 71.2791 284.622 + endloop + endfacet + facet normal 0.158866 -0.974737 -0.157001 + outer loop + vertex 469.291 70.3928 288.285 + vertex 464.958 69.8604 287.206 + vertex 471.109 71.2791 284.622 + endloop + endfacet + facet normal 0.159752 -0.973948 -0.160948 + outer loop + vertex 469.291 70.3928 288.285 + vertex 463.137 69.0522 290.289 + vertex 464.958 69.8604 287.206 + endloop + endfacet + facet normal 0.154342 -0.974273 -0.164228 + outer loop + vertex 463.137 69.0522 290.289 + vertex 458.837 68.56 289.168 + vertex 464.958 69.8604 287.206 + endloop + endfacet + facet normal 0.152248 -0.973561 -0.17029 + outer loop + vertex 464.958 69.8604 287.206 + vertex 458.837 68.56 289.168 + vertex 460.647 69.3658 286.179 + endloop + endfacet + facet normal 0.151127 -0.974635 -0.165069 + outer loop + vertex 464.958 69.8604 287.206 + vertex 460.647 69.3658 286.179 + vertex 466.66 70.7239 283.666 + endloop + endfacet + facet normal 0.145364 -0.973861 -0.174538 + outer loop + vertex 458.837 68.56 289.168 + vertex 454.496 68.1117 288.053 + vertex 460.647 69.3658 286.179 + endloop + endfacet + facet normal 0.143714 -0.973202 -0.179511 + outer loop + vertex 460.647 69.3658 286.179 + vertex 454.496 68.1117 288.053 + vertex 456.306 68.9154 285.146 + endloop + endfacet + facet normal 0.133991 -0.973441 -0.185633 + outer loop + vertex 454.496 68.1117 288.053 + vertex 449.926 67.7083 286.87 + vertex 456.306 68.9154 285.146 + endloop + endfacet + facet normal 0.135475 -0.972029 -0.191847 + outer loop + vertex 454.496 68.1117 288.053 + vertex 448.595 67.061 289.21 + vertex 449.926 67.7083 286.87 + endloop + endfacet + facet normal 0.121898 -0.972259 -0.199634 + outer loop + vertex 448.595 67.061 289.21 + vertex 443.4 66.7112 287.742 + vertex 449.926 67.7083 286.87 + endloop + endfacet + facet normal 0.121932 -0.972298 -0.199423 + outer loop + vertex 449.926 67.7083 286.87 + vertex 443.4 66.7112 287.742 + vertex 445.209 67.3984 285.498 + endloop + endfacet + facet normal 0.121159 -0.972966 -0.196617 + outer loop + vertex 449.926 67.7083 286.87 + vertex 445.209 67.3984 285.498 + vertex 451.809 68.5137 284.045 + endloop + endfacet + facet normal 0.106288 -0.971517 -0.211797 + outer loop + vertex 443.4 66.7112 287.742 + vertex 438.067 66.5657 285.733 + vertex 445.209 67.3984 285.498 + endloop + endfacet + facet normal 0.106933 -0.973847 -0.200467 + outer loop + vertex 445.209 67.3984 285.498 + vertex 438.067 66.5657 285.733 + vertex 441.334 67.2936 283.94 + endloop + endfacet + facet normal 0.10791 -0.970371 -0.216184 + outer loop + vertex 443.4 66.7112 287.742 + vertex 436.648 65.9879 287.618 + vertex 438.067 66.5657 285.733 + endloop + endfacet + facet normal 0.0896168 -0.969157 -0.229571 + outer loop + vertex 438.067 66.5657 285.733 + vertex 436.648 65.9879 287.618 + vertex 428.798 65.9451 284.735 + endloop + endfacet + facet normal 0.0884036 -0.972306 -0.216348 + outer loop + vertex 438.067 66.5657 285.733 + vertex 428.798 65.9451 284.735 + vertex 434.909 66.9574 282.682 + endloop + endfacet + facet normal 0.0773983 -0.966155 -0.246078 + outer loop + vertex 424.757 66.7148 280.441 + vertex 434.909 66.9574 282.682 + vertex 428.798 65.9451 284.735 + endloop + endfacet + facet normal 0.0672287 -0.96917 -0.237045 + outer loop + vertex 428.798 65.9451 284.735 + vertex 419.479 65.7753 282.786 + vertex 424.757 66.7148 280.441 + endloop + endfacet + facet normal 0.0420031 -0.956484 -0.288747 + outer loop + vertex 419.479 65.7753 282.786 + vertex 412.258 66.3289 279.901 + vertex 424.757 66.7148 280.441 + endloop + endfacet + facet normal 0.0396022 -0.974653 -0.22019 + outer loop + vertex 417.827 67.1697 277.181 + vertex 424.757 66.7148 280.441 + vertex 412.258 66.3289 279.901 + endloop + endfacet + facet normal 0.00863953 -0.960215 -0.279129 + outer loop + vertex 408.864 67.5224 275.691 + vertex 417.827 67.1697 277.181 + vertex 412.258 66.3289 279.901 + endloop + endfacet + facet normal -0.017063 -0.965483 -0.259905 + outer loop + vertex 412.258 66.3289 279.901 + vertex 400.965 67.1479 277.601 + vertex 408.864 67.5224 275.691 + endloop + endfacet + facet normal 0.00686974 -0.93095 -0.365081 + outer loop + vertex 412.258 66.3289 279.901 + vertex 404.26 66.1627 280.175 + vertex 400.965 67.1479 277.601 + endloop + endfacet + facet normal 0.00946573 -0.953074 -0.30259 + outer loop + vertex 413.161 65.5189 282.481 + vertex 404.26 66.1627 280.175 + vertex 412.258 66.3289 279.901 + endloop + endfacet + facet normal 0.00393975 -0.967561 -0.252606 + outer loop + vertex 417.827 67.1697 277.181 + vertex 408.864 67.5224 275.691 + vertex 418.559 68.357 272.645 + endloop + endfacet + facet normal 0.0421839 -0.968197 -0.246608 + outer loop + vertex 427.332 68.1517 274.952 + vertex 417.827 67.1697 277.181 + vertex 418.559 68.357 272.645 + endloop + endfacet + facet normal 0.0457543 -0.971443 -0.232819 + outer loop + vertex 424.757 66.7148 280.441 + vertex 417.827 67.1697 277.181 + vertex 427.332 68.1517 274.952 + endloop + endfacet + facet normal 0.0726532 -0.972672 -0.220523 + outer loop + vertex 436.484 68.1913 277.793 + vertex 424.757 66.7148 280.441 + vertex 427.332 68.1517 274.952 + endloop + endfacet + facet normal 0.0536902 -0.947166 -0.316217 + outer loop + vertex 419.479 65.7753 282.786 + vertex 413.161 65.5189 282.481 + vertex 412.258 66.3289 279.901 + endloop + endfacet + facet normal 0.052178 -0.960379 -0.273771 + outer loop + vertex 421.202 65.3377 284.649 + vertex 413.161 65.5189 282.481 + vertex 419.479 65.7753 282.786 + endloop + endfacet + facet normal 0.0794251 -0.9516 -0.296901 + outer loop + vertex 428.798 65.9451 284.735 + vertex 421.202 65.3377 284.649 + vertex 419.479 65.7753 282.786 + endloop + endfacet + facet normal 0.0799462 -0.964462 -0.251837 + outer loop + vertex 430.098 65.4861 286.905 + vertex 421.202 65.3377 284.649 + vertex 428.798 65.9451 284.735 + endloop + endfacet + facet normal 0.102227 -0.959078 -0.264046 + outer loop + vertex 436.648 65.9879 287.618 + vertex 430.098 65.4861 286.905 + vertex 428.798 65.9451 284.735 + endloop + endfacet + facet normal 0.0984602 -0.970132 -0.221697 + outer loop + vertex 438.661 65.7908 289.374 + vertex 430.098 65.4861 286.905 + vertex 436.648 65.9879 287.618 + endloop + endfacet + facet normal 0.118777 -0.962445 -0.244116 + outer loop + vertex 436.648 65.9879 287.618 + vertex 443.462 66.3113 289.658 + vertex 438.661 65.7908 289.374 + endloop + endfacet + facet normal 0.107958 -0.972496 -0.20639 + outer loop + vertex 443.462 66.3113 289.658 + vertex 436.648 65.9879 287.618 + vertex 443.4 66.7112 287.742 + endloop + endfacet + facet normal 0.123726 -0.970592 -0.206501 + outer loop + vertex 448.595 67.061 289.21 + vertex 443.462 66.3113 289.658 + vertex 443.4 66.7112 287.742 + endloop + endfacet + facet normal 0.12528 -0.973166 -0.19301 + outer loop + vertex 448.64 66.7329 290.894 + vertex 443.462 66.3113 289.658 + vertex 448.595 67.061 289.21 + endloop + endfacet + facet normal 0.138563 -0.971362 -0.193018 + outer loop + vertex 453.161 67.4672 290.444 + vertex 448.64 66.7329 290.894 + vertex 448.595 67.061 289.21 + endloop + endfacet + facet normal 0.14068 -0.974212 -0.176408 + outer loop + vertex 452.749 67.0778 292.266 + vertex 448.64 66.7329 290.894 + vertex 453.161 67.4672 290.444 + endloop + endfacet + facet normal 0.148895 -0.973358 -0.174367 + outer loop + vertex 457.476 67.9148 291.63 + vertex 452.749 67.0778 292.266 + vertex 453.161 67.4672 290.444 + endloop + endfacet + facet normal 0.148557 -0.973649 -0.173028 + outer loop + vertex 457.476 67.9148 291.63 + vertex 453.161 67.4672 290.444 + vertex 458.837 68.56 289.168 + endloop + endfacet + facet normal 0.150288 -0.974655 -0.165716 + outer loop + vertex 457.312 67.591 293.385 + vertex 452.749 67.0778 292.266 + vertex 457.476 67.9148 291.63 + endloop + endfacet + facet normal 0.158879 -0.973465 -0.164692 + outer loop + vertex 461.826 68.419 292.847 + vertex 457.312 67.591 293.385 + vertex 457.476 67.9148 291.63 + endloop + endfacet + facet normal 0.157778 -0.974363 -0.160384 + outer loop + vertex 461.826 68.419 292.847 + vertex 457.476 67.9148 291.63 + vertex 463.137 69.0522 290.289 + endloop + endfacet + facet normal 0.163449 -0.97392 -0.157367 + outer loop + vertex 467.514 69.5989 291.452 + vertex 461.826 68.419 292.847 + vertex 463.137 69.0522 290.289 + endloop + endfacet + facet normal 0.166371 -0.975124 -0.146472 + outer loop + vertex 466.304 68.9905 294.128 + vertex 461.826 68.419 292.847 + vertex 467.514 69.5989 291.452 + endloop + endfacet + facet normal 0.171921 -0.974554 -0.143833 + outer loop + vertex 472.001 70.2174 292.625 + vertex 466.304 68.9905 294.128 + vertex 467.514 69.5989 291.452 + endloop + endfacet + facet normal 0.171018 -0.975271 -0.139998 + outer loop + vertex 472.001 70.2174 292.625 + vertex 467.514 69.5989 291.452 + vertex 473.503 70.9433 289.402 + endloop + endfacet + facet normal 0.175097 -0.974832 -0.137999 + outer loop + vertex 477.778 71.5918 290.245 + vertex 472.001 70.2174 292.625 + vertex 473.503 70.9433 289.402 + endloop + endfacet + facet normal 0.17487 -0.975059 -0.136675 + outer loop + vertex 477.778 71.5918 290.245 + vertex 473.503 70.9433 289.402 + vertex 478.44 72.144 287.153 + endloop + endfacet + facet normal 0.17864 -0.974502 -0.135769 + outer loop + vertex 482.737 73.006 286.619 + vertex 477.778 71.5918 290.245 + vertex 478.44 72.144 287.153 + endloop + endfacet + facet normal 0.182976 -0.974506 -0.12984 + outer loop + vertex 482.042 72.3014 290.93 + vertex 477.778 71.5918 290.245 + vertex 482.737 73.006 286.619 + endloop + endfacet + facet normal 0.18243 -0.975141 -0.125774 + outer loop + vertex 482.042 72.3014 290.93 + vertex 476.541 70.8984 293.828 + vertex 477.778 71.5918 290.245 + endloop + endfacet + facet normal 0.187476 -0.97536 -0.116302 + outer loop + vertex 480.802 71.5444 295.279 + vertex 476.541 70.8984 293.828 + vertex 482.042 72.3014 290.93 + endloop + endfacet + facet normal 0.187279 -0.97539 -0.116363 + outer loop + vertex 485.901 72.9791 291.459 + vertex 480.802 71.5444 295.279 + vertex 482.042 72.3014 290.93 + endloop + endfacet + facet normal 0.187679 -0.975243 -0.11695 + outer loop + vertex 480.802 71.5444 295.279 + vertex 475.392 70.2793 297.146 + vertex 476.541 70.8984 293.828 + endloop + endfacet + facet normal 0.183917 -0.97579 -0.118354 + outer loop + vertex 475.392 70.2793 297.146 + vertex 470.866 69.6268 295.493 + vertex 476.541 70.8984 293.828 + endloop + endfacet + facet normal 0.180526 -0.97503 -0.129329 + outer loop + vertex 476.541 70.8984 293.828 + vertex 470.866 69.6268 295.493 + vertex 472.001 70.2174 292.625 + endloop + endfacet + facet normal 0.184454 -0.975495 -0.119941 + outer loop + vertex 475.392 70.2793 297.146 + vertex 470.19 69.2384 297.613 + vertex 470.866 69.6268 295.493 + endloop + endfacet + facet normal 0.17904 -0.976272 -0.12181 + outer loop + vertex 470.19 69.2384 297.613 + vertex 466.272 68.7111 296.079 + vertex 470.866 69.6268 295.493 + endloop + endfacet + facet normal 0.176835 -0.974707 -0.13666 + outer loop + vertex 470.866 69.6268 295.493 + vertex 466.272 68.7111 296.079 + vertex 466.304 68.9905 294.128 + endloop + endfacet + facet normal 0.168439 -0.976144 -0.137006 + outer loop + vertex 466.272 68.7111 296.079 + vertex 461.482 68.058 294.844 + vertex 466.304 68.9905 294.128 + endloop + endfacet + facet normal 0.166625 -0.977512 -0.129249 + outer loop + vertex 466.272 68.7111 296.079 + vertex 464.621 68.2979 297.076 + vertex 461.482 68.058 294.844 + endloop + endfacet + facet normal 0.176075 -0.977787 -0.113715 + outer loop + vertex 466.272 68.7111 296.079 + vertex 470.19 69.2384 297.613 + vertex 464.621 68.2979 297.076 + endloop + endfacet + facet normal 0.185245 -0.976208 -0.112708 + outer loop + vertex 474.014 69.8046 298.992 + vertex 470.19 69.2384 297.613 + vertex 475.392 70.2793 297.146 + endloop + endfacet + facet normal 0.19154 -0.975543 -0.107835 + outer loop + vertex 474.014 69.8046 298.992 + vertex 475.392 70.2793 297.146 + vertex 477.425 70.4694 299.037 + endloop + endfacet + facet normal 0.191632 -0.976902 -0.0945528 + outer loop + vertex 476.259 70.1208 300.276 + vertex 474.014 69.8046 298.992 + vertex 477.425 70.4694 299.037 + endloop + endfacet + facet normal 0.196616 -0.976367 -0.0897165 + outer loop + vertex 479.772 70.8442 300.101 + vertex 476.259 70.1208 300.276 + vertex 477.425 70.4694 299.037 + endloop + endfacet + facet normal 0.197292 -0.976083 -0.0913078 + outer loop + vertex 479.772 70.8442 300.101 + vertex 477.425 70.4694 299.037 + vertex 480.806 71.2332 298.178 + endloop + endfacet + facet normal 0.199469 -0.975756 -0.0900703 + outer loop + vertex 482.626 71.5159 299.146 + vertex 479.772 70.8442 300.101 + vertex 480.806 71.2332 298.178 + endloop + endfacet + facet normal 0.200797 -0.975235 -0.0927178 + outer loop + vertex 482.626 71.5159 299.146 + vertex 480.806 71.2332 298.178 + vertex 484.891 72.2632 296.191 + endloop + endfacet + facet normal 0.205918 -0.974548 -0.0886196 + outer loop + vertex 482.626 71.5159 299.146 + vertex 484.891 72.2632 296.191 + vertex 484.841 71.976 299.234 + endloop + endfacet + facet normal 0.205701 -0.975488 -0.0781719 + outer loop + vertex 484.841 71.976 299.234 + vertex 482.135 71.2808 300.786 + vertex 482.626 71.5159 299.146 + endloop + endfacet + facet normal 0.210117 -0.975144 -0.0703191 + outer loop + vertex 484.149 71.678 301.298 + vertex 482.135 71.2808 300.786 + vertex 484.841 71.976 299.234 + endloop + endfacet + facet normal 0.208164 -0.975512 -0.0710269 + outer loop + vertex 486.3 72.2339 299.967 + vertex 484.149 71.678 301.298 + vertex 484.841 71.976 299.234 + endloop + endfacet + facet normal 0.21024 -0.974736 -0.0754292 + outer loop + vertex 486.3 72.2339 299.967 + vertex 484.841 71.976 299.234 + vertex 487.964 72.8223 297.001 + endloop + endfacet + facet normal 0.214217 -0.97405 -0.0730618 + outer loop + vertex 486.3 72.2339 299.967 + vertex 487.964 72.8223 297.001 + vertex 487.874 72.5841 299.913 + endloop + endfacet + facet normal 0.214855 -0.974826 -0.0596013 + outer loop + vertex 487.874 72.5841 299.913 + vertex 485.868 72.031 301.73 + vertex 486.3 72.2339 299.967 + endloop + endfacet + facet normal 0.21928 -0.974138 -0.0545067 + outer loop + vertex 487.304 72.331 302.14 + vertex 485.868 72.031 301.73 + vertex 487.874 72.5841 299.913 + endloop + endfacet + facet normal 0.214799 -0.975065 -0.0557604 + outer loop + vertex 489.02 72.807 300.431 + vertex 487.304 72.331 302.14 + vertex 487.874 72.5841 299.913 + endloop + endfacet + facet normal 0.217351 -0.974135 -0.0618032 + outer loop + vertex 489.02 72.807 300.431 + vertex 487.874 72.5841 299.913 + vertex 489.573 73.0979 297.789 + endloop + endfacet + facet normal 0.221217 -0.973992 -0.0490129 + outer loop + vertex 488.172 72.4969 302.764 + vertex 487.304 72.331 302.14 + vertex 489.02 72.807 300.431 + endloop + endfacet + facet normal 0.220708 -0.974098 -0.049212 + outer loop + vertex 489.02 72.807 300.431 + vertex 489.447 72.8489 301.513 + vertex 488.172 72.4969 302.764 + endloop + endfacet + facet normal 0.22686 -0.972994 -0.0426367 + outer loop + vertex 489.447 72.8489 301.513 + vertex 488.32 72.5013 303.453 + vertex 488.172 72.4969 302.764 + endloop + endfacet + facet normal 0.224535 -0.973555 -0.0421322 + outer loop + vertex 487.556 72.3071 303.867 + vertex 488.172 72.4969 302.764 + vertex 488.32 72.5013 303.453 + endloop + endfacet + facet normal -0.197321 0.975881 0.0933831 + outer loop + vertex 487.556 72.3071 303.867 + vertex 488.32 72.5013 303.453 + vertex 486.781 72.1234 304.149 + endloop + endfacet + facet normal 0.217918 -0.975295 -0.0361994 + outer loop + vertex 487.556 72.3071 303.867 + vertex 486.781 72.1234 304.149 + vertex 486.643 72.1124 303.615 + endloop + endfacet + facet normal 0.216265 -0.975679 -0.0357641 + outer loop + vertex 486.781 72.1234 304.149 + vertex 484.165 71.5625 303.634 + vertex 486.643 72.1124 303.615 + endloop + endfacet + facet normal 0.216212 -0.975559 -0.039198 + outer loop + vertex 485.54 71.8905 303.052 + vertex 486.643 72.1124 303.615 + vertex 484.165 71.5625 303.634 + endloop + endfacet + facet normal 0.214247 -0.975789 -0.0439726 + outer loop + vertex 485.54 71.8905 303.052 + vertex 484.165 71.5625 303.634 + vertex 483.648 71.4938 302.637 + endloop + endfacet + facet normal 0.215454 -0.975233 -0.0500016 + outer loop + vertex 485.54 71.8905 303.052 + vertex 483.648 71.4938 302.637 + vertex 485.868 72.031 301.73 + endloop + endfacet + facet normal 0.213827 -0.975374 -0.0540691 + outer loop + vertex 485.868 72.031 301.73 + vertex 483.648 71.4938 302.637 + vertex 484.149 71.678 301.298 + endloop + endfacet + facet normal 0.212183 -0.975696 -0.0547296 + outer loop + vertex 483.648 71.4938 302.637 + vertex 481.905 71.1518 301.98 + vertex 484.149 71.678 301.298 + endloop + endfacet + facet normal 0.206739 -0.977606 -0.0393 + outer loop + vertex 481.905 71.1518 301.98 + vertex 483.648 71.4938 302.637 + vertex 480.451 70.8251 302.456 + endloop + endfacet + facet normal 0.201801 -0.977904 -0.0545906 + outer loop + vertex 481.905 71.1518 301.98 + vertex 480.451 70.8251 302.456 + vertex 479.348 70.6577 301.378 + endloop + endfacet + facet normal 0.204321 -0.976654 -0.0663324 + outer loop + vertex 481.905 71.1518 301.98 + vertex 479.348 70.6577 301.378 + vertex 482.135 71.2808 300.786 + endloop + endfacet + facet normal 0.202309 -0.976404 -0.0755326 + outer loop + vertex 482.135 71.2808 300.786 + vertex 479.348 70.6577 301.378 + vertex 479.772 70.8442 300.101 + endloop + endfacet + facet normal 0.193516 -0.980028 -0.0457817 + outer loop + vertex 480.451 70.8251 302.456 + vertex 475.931 70.0007 300.999 + vertex 479.348 70.6577 301.378 + endloop + endfacet + facet normal 0.20677 -0.977573 -0.0399681 + outer loop + vertex 484.165 71.5625 303.634 + vertex 480.451 70.8251 302.456 + vertex 483.648 71.4938 302.637 + endloop + endfacet + facet normal 0.207167 -0.977433 -0.0413065 + outer loop + vertex 484.165 71.5625 303.634 + vertex 481.485 71.0124 303.212 + vertex 480.451 70.8251 302.456 + endloop + endfacet + facet normal 0.189754 -0.981694 -0.0164392 + outer loop + vertex 481.485 71.0124 303.212 + vertex 477.004 70.1725 301.64 + vertex 480.451 70.8251 302.456 + endloop + endfacet + facet normal 0.203464 -0.975892 -0.0789765 + outer loop + vertex 480.451 70.8251 302.456 + vertex 477.004 70.1725 301.64 + vertex 475.931 70.0007 300.999 + endloop + endfacet + facet normal 0.17523 -0.984085 -0.0295185 + outer loop + vertex 477.004 70.1725 301.64 + vertex 471.404 69.2342 299.68 + vertex 475.931 70.0007 300.999 + endloop + endfacet + facet normal 0.196143 -0.974749 -0.106737 + outer loop + vertex 475.931 70.0007 300.999 + vertex 471.404 69.2342 299.68 + vertex 471.827 69.3571 299.334 + endloop + endfacet + facet normal 0.185492 -0.979493 -0.0786475 + outer loop + vertex 475.931 70.0007 300.999 + vertex 471.827 69.3571 299.334 + vertex 476.259 70.1208 300.276 + endloop + endfacet + facet normal 0.196173 -0.977809 -0.0735199 + outer loop + vertex 476.259 70.1208 300.276 + vertex 479.348 70.6577 301.378 + vertex 475.931 70.0007 300.999 + endloop + endfacet + facet normal 0.182221 -0.975412 -0.123962 + outer loop + vertex 471.404 69.2342 299.68 + vertex 464.621 68.2979 297.076 + vertex 471.827 69.3571 299.334 + endloop + endfacet + facet normal 0.288574 -0.865039 -0.410406 + outer loop + vertex 471.404 69.2342 299.68 + vertex 477.004 70.1725 301.64 + vertex 474.254 69.6807 300.743 + endloop + endfacet + facet normal 0.229973 -0.948414 -0.218228 + outer loop + vertex 474.254 69.6807 300.743 + vertex 470.393 69.0387 299.464 + vertex 471.404 69.2342 299.68 + endloop + endfacet + facet normal 0.184617 -0.980653 -0.0650877 + outer loop + vertex 470.393 69.0387 299.464 + vertex 474.254 69.6807 300.743 + vertex 473.789 69.5704 301.086 + endloop + endfacet + facet normal 0.201686 -0.978048 -0.0523868 + outer loop + vertex 477.004 70.1725 301.64 + vertex 481.485 71.0124 303.212 + vertex 478.587 70.4604 302.358 + endloop + endfacet + facet normal 0.1686 -0.985406 0.0234254 + outer loop + vertex 478.587 70.4604 302.358 + vertex 474.254 69.6807 300.743 + vertex 477.004 70.1725 301.64 + endloop + endfacet + facet normal 0.195101 -0.979482 -0.0505044 + outer loop + vertex 474.254 69.6807 300.743 + vertex 478.587 70.4604 302.358 + vertex 473.789 69.5704 301.086 + endloop + endfacet + facet normal 0.189478 -0.981489 -0.0278962 + outer loop + vertex 480.343 70.7609 303.716 + vertex 473.789 69.5704 301.086 + vertex 478.587 70.4604 302.358 + endloop + endfacet + facet normal 0.205133 -0.978357 -0.0271697 + outer loop + vertex 484.617 71.6423 304.176 + vertex 481.485 71.0124 303.212 + vertex 484.165 71.5625 303.634 + endloop + endfacet + facet normal 0.194494 -0.980862 0.00903769 + outer loop + vertex 481.485 71.0124 303.212 + vertex 484.617 71.6423 304.176 + vertex 483.752 71.4713 304.24 + endloop + endfacet + facet normal 0.165308 -0.98342 0.0745495 + outer loop + vertex 483.752 71.4713 304.24 + vertex 478.587 70.4604 302.358 + vertex 481.485 71.0124 303.212 + endloop + endfacet + facet normal 0.198697 -0.977105 0.076062 + outer loop + vertex 484.617 71.6423 304.176 + vertex 486.652 72.0891 304.601 + vertex 483.752 71.4713 304.24 + endloop + endfacet + facet normal 0.216932 -0.976111 -0.0121924 + outer loop + vertex 486.652 72.0891 304.601 + vertex 484.617 71.6423 304.176 + vertex 486.781 72.1234 304.149 + endloop + endfacet + facet normal 0.232857 -0.972483 -0.00738037 + outer loop + vertex 486.652 72.0891 304.601 + vertex 486.781 72.1234 304.149 + vertex 489.442 72.7649 303.576 + endloop + endfacet + facet normal 0.229824 -0.9731 -0.0160403 + outer loop + vertex 489.442 72.7649 303.576 + vertex 488.598 72.5247 306.068 + vertex 486.652 72.0891 304.601 + endloop + endfacet + facet normal 0.206364 -0.978333 0.0166617 + outer loop + vertex 488.598 72.5247 306.068 + vertex 483.752 71.4713 304.24 + vertex 486.652 72.0891 304.601 + endloop + endfacet + facet normal 0.226048 -0.973961 -0.0174017 + outer loop + vertex 488.598 72.5247 306.068 + vertex 489.442 72.7649 303.576 + vertex 493.312 73.6413 304.794 + endloop + endfacet + facet normal 0.229133 -0.97338 -0.00547679 + outer loop + vertex 495.6 74.1734 305.966 + vertex 488.598 72.5247 306.068 + vertex 493.312 73.6413 304.794 + endloop + endfacet + facet normal 0.233622 -0.972215 -0.0147704 + outer loop + vertex 493.312 73.6413 304.794 + vertex 502.286 75.7878 305.456 + vertex 495.6 74.1734 305.966 + endloop + endfacet + facet normal 0.235288 -0.971892 0.00809197 + outer loop + vertex 500.594 75.3845 306.222 + vertex 495.6 74.1734 305.966 + vertex 502.286 75.7878 305.456 + endloop + endfacet + facet normal 0.238373 -0.971052 0.0153565 + outer loop + vertex 505.472 76.5816 306.195 + vertex 500.594 75.3845 306.222 + vertex 502.286 75.7878 305.456 + endloop + endfacet + facet normal 0.239093 -0.970921 0.0121124 + outer loop + vertex 509.375 77.5417 306.124 + vertex 505.472 76.5816 306.195 + vertex 502.286 75.7878 305.456 + endloop + endfacet + facet normal 0.239044 -0.970926 0.0126423 + outer loop + vertex 502.286 75.7878 305.456 + vertex 515.64 79.0792 305.725 + vertex 509.375 77.5417 306.124 + endloop + endfacet + facet normal 0.241848 -0.96791 0.0682614 + outer loop + vertex 513.823 78.6557 306.158 + vertex 509.375 77.5417 306.124 + vertex 515.64 79.0792 305.725 + endloop + endfacet + facet normal 0.243062 -0.967179 0.0740662 + outer loop + vertex 516.426 79.3069 306.118 + vertex 513.823 78.6557 306.158 + vertex 515.64 79.0792 305.725 + endloop + endfacet + facet normal 0.246168 -0.966861 0.0676802 + outer loop + vertex 518.297 79.7808 306.086 + vertex 516.426 79.3069 306.118 + vertex 515.64 79.0792 305.725 + endloop + endfacet + facet normal 0.247215 -0.967076 0.0604053 + outer loop + vertex 522.915 80.9583 306.036 + vertex 518.297 79.7808 306.086 + vertex 515.64 79.0792 305.725 + endloop + endfacet + facet normal 0.244695 -0.964217 0.102033 + outer loop + vertex 515.64 79.0792 305.725 + vertex 529.574 82.6142 305.715 + vertex 522.915 80.9583 306.036 + endloop + endfacet + facet normal 0.245537 -0.953392 0.175369 + outer loop + vertex 529.984 82.7801 306.043 + vertex 522.915 80.9583 306.036 + vertex 529.574 82.6142 305.715 + endloop + endfacet + facet normal 0.245721 -0.953388 0.175137 + outer loop + vertex 538.208 84.9078 306.087 + vertex 529.984 82.7801 306.043 + vertex 529.574 82.6142 305.715 + endloop + endfacet + facet normal 0.2498 -0.960387 0.123521 + outer loop + vertex 529.574 82.6142 305.715 + vertex 543.099 86.1081 305.529 + vertex 538.208 84.9078 306.087 + endloop + endfacet + facet normal 0.249216 -0.961466 0.116077 + outer loop + vertex 545.121 86.7086 306.162 + vertex 538.208 84.9078 306.087 + vertex 543.099 86.1081 305.529 + endloop + endfacet + facet normal 0.251368 -0.961688 0.109412 + outer loop + vertex 550.359 88.0735 306.125 + vertex 545.121 86.7086 306.162 + vertex 543.099 86.1081 305.529 + endloop + endfacet + facet normal 0.253399 -0.963199 0.0896492 + outer loop + vertex 543.099 86.1081 305.529 + vertex 556.696 89.6758 305.427 + vertex 550.359 88.0735 306.125 + endloop + endfacet + facet normal 0.253854 -0.962536 0.0953061 + outer loop + vertex 557.474 89.9644 306.271 + vertex 550.359 88.0735 306.125 + vertex 556.696 89.6758 305.427 + endloop + endfacet + facet normal 0.25178 -0.962877 0.0973354 + outer loop + vertex 564.789 91.8775 306.273 + vertex 557.474 89.9644 306.271 + vertex 556.696 89.6758 305.427 + endloop + endfacet + facet normal 0.252659 -0.963347 0.0901403 + outer loop + vertex 556.696 89.6758 305.427 + vertex 570.266 93.2641 305.74 + vertex 564.789 91.8775 306.273 + endloop + endfacet + facet normal 0.252982 -0.962808 0.0948717 + outer loop + vertex 570.295 93.3395 306.428 + vertex 564.789 91.8775 306.273 + vertex 570.266 93.2641 305.74 + endloop + endfacet + facet normal 0.251344 -0.963226 0.0949861 + outer loop + vertex 577.732 95.2909 306.537 + vertex 570.295 93.3395 306.428 + vertex 570.266 93.2641 305.74 + endloop + endfacet + facet normal 0.250192 -0.962579 0.10414 + outer loop + vertex 570.266 93.2641 305.74 + vertex 582.649 96.5164 306.051 + vertex 577.732 95.2909 306.537 + endloop + endfacet + facet normal 0.250249 -0.962472 0.104987 + outer loop + vertex 588.676 98.1574 306.73 + vertex 577.732 95.2909 306.537 + vertex 582.649 96.5164 306.051 + endloop + endfacet + facet normal 0.249187 -0.961851 0.112912 + outer loop + vertex 582.649 96.5164 306.051 + vertex 594.898 99.7255 306.357 + vertex 588.676 98.1574 306.73 + endloop + endfacet + facet normal 0.248773 -0.963467 0.0992143 + outer loop + vertex 596.27 100.141 306.95 + vertex 588.676 98.1574 306.73 + vertex 594.898 99.7255 306.357 + endloop + endfacet + facet normal 0.242601 -0.963466 0.113485 + outer loop + vertex 601.473 101.463 307.048 + vertex 596.27 100.141 306.95 + vertex 594.898 99.7255 306.357 + endloop + endfacet + facet normal 0.247982 -0.966278 0.0693625 + outer loop + vertex 601.473 101.463 307.048 + vertex 594.898 99.7255 306.357 + vertex 603.98 102.059 306.394 + endloop + endfacet + facet normal 0.243071 -0.968809 0.0482217 + outer loop + vertex 606.888 102.83 307.217 + vertex 601.473 101.463 307.048 + vertex 603.98 102.059 306.394 + endloop + endfacet + facet normal 0.245463 -0.968598 0.0395708 + outer loop + vertex 603.98 102.059 306.394 + vertex 608.051 103.086 306.285 + vertex 606.888 102.83 307.217 + endloop + endfacet + facet normal 0.242461 -0.969509 0.0355738 + outer loop + vertex 610.266 103.666 307.004 + vertex 606.888 102.83 307.217 + vertex 608.051 103.086 306.285 + endloop + endfacet + facet normal 0.252811 -0.967514 0.00206918 + outer loop + vertex 610.266 103.666 307.004 + vertex 608.051 103.086 306.285 + vertex 608.772 103.272 304.89 + endloop + endfacet + facet normal 0.253618 -0.967301 0.00251497 + outer loop + vertex 608.408 103.176 304.833 + vertex 608.772 103.272 304.89 + vertex 608.051 103.086 306.285 + endloop + endfacet + facet normal 0.247275 -0.968945 0.000855728 + outer loop + vertex 608.408 103.176 304.833 + vertex 608.051 103.086 306.285 + vertex 606.987 102.814 305.155 + endloop + endfacet + facet normal 0.242496 -0.969918 -0.0213207 + outer loop + vertex 607.231 102.927 302.786 + vertex 608.408 103.176 304.833 + vertex 606.987 102.814 305.155 + endloop + endfacet + facet normal 0.260318 -0.965331 -0.0192668 + outer loop + vertex 607.231 102.927 302.786 + vertex 606.987 102.814 305.155 + vertex 605.118 102.354 302.911 + endloop + endfacet + facet normal 0.2588 -0.964961 -0.0432804 + outer loop + vertex 604.477 102.341 299.368 + vertex 607.231 102.927 302.786 + vertex 605.118 102.354 302.911 + endloop + endfacet + facet normal 0.26932 -0.96199 -0.0451938 + outer loop + vertex 604.477 102.341 299.368 + vertex 605.118 102.354 302.911 + vertex 601.063 101.371 299.674 + endloop + endfacet + facet normal 0.267088 -0.961283 -0.0678243 + outer loop + vertex 599.658 101.321 294.859 + vertex 604.477 102.341 299.368 + vertex 601.063 101.371 299.674 + endloop + endfacet + facet normal 0.277923 -0.95724 -0.0803186 + outer loop + vertex 603.409 102.412 294.828 + vertex 604.477 102.341 299.368 + vertex 599.658 101.321 294.859 + endloop + endfacet + facet normal 0.273222 -0.958682 -0.0792357 + outer loop + vertex 603.409 102.412 294.828 + vertex 606.289 102.875 299.157 + vertex 604.477 102.341 299.368 + endloop + endfacet + facet normal 0.291179 -0.952248 -0.0918663 + outer loop + vertex 605.004 102.925 294.57 + vertex 606.289 102.875 299.157 + vertex 603.409 102.412 294.828 + endloop + endfacet + facet normal 0.287932 -0.951304 -0.110076 + outer loop + vertex 602.668 102.691 290.48 + vertex 605.004 102.925 294.57 + vertex 603.409 102.412 294.828 + endloop + endfacet + facet normal 0.281965 -0.953192 -0.10918 + outer loop + vertex 602.668 102.691 290.48 + vertex 603.409 102.412 294.828 + vertex 598.841 101.717 289.098 + endloop + endfacet + facet normal 0.314369 -0.940932 -0.12577 + outer loop + vertex 603.468 103.155 289.007 + vertex 605.004 102.925 294.57 + vertex 602.668 102.691 290.48 + endloop + endfacet + facet normal 0.29532 -0.945446 -0.13754 + outer loop + vertex 602.668 102.691 290.48 + vertex 599.814 102.722 284.136 + vertex 603.468 103.155 289.007 + endloop + endfacet + facet normal 0.307561 -0.940073 -0.147202 + outer loop + vertex 599.814 102.722 284.136 + vertex 601.984 103.857 281.422 + vertex 603.468 103.155 289.007 + endloop + endfacet + facet normal 0.279326 -0.949556 -0.142553 + outer loop + vertex 603.972 103.288 289.109 + vertex 603.468 103.155 289.007 + vertex 601.984 103.857 281.422 + endloop + endfacet + facet normal 0.27516 -0.954414 -0.115678 + outer loop + vertex 603.972 103.288 289.109 + vertex 605.183 103.054 293.919 + vertex 603.468 103.155 289.007 + endloop + endfacet + facet normal -0.441013 0.884189 0.154008 + outer loop + vertex 603.972 103.288 289.109 + vertex 604.936 103.017 293.428 + vertex 605.183 103.054 293.919 + endloop + endfacet + facet normal -0.38662 0.913803 0.124458 + outer loop + vertex 604.936 103.017 293.428 + vertex 606.248 102.969 297.856 + vertex 605.183 103.054 293.919 + endloop + endfacet + facet normal -0.359703 0.925648 0.117429 + outer loop + vertex 605.183 103.054 293.919 + vertex 606.248 102.969 297.856 + vertex 606.651 103.021 298.682 + endloop + endfacet + facet normal 0.310813 -0.944929 -0.102491 + outer loop + vertex 605.183 103.054 293.919 + vertex 606.651 103.021 298.682 + vertex 605.004 102.925 294.57 + endloop + endfacet + facet normal -0.239796 0.969194 0.056229 + outer loop + vertex 606.248 102.969 297.856 + vertex 607.707 103.094 301.917 + vertex 606.651 103.021 298.682 + endloop + endfacet + facet normal -0.46286 0.876677 0.13114 + outer loop + vertex 606.651 103.021 298.682 + vertex 607.707 103.094 301.917 + vertex 607.948 103.129 302.533 + endloop + endfacet + facet normal 0.290175 -0.954349 -0.0708256 + outer loop + vertex 606.651 103.021 298.682 + vertex 607.948 103.129 302.533 + vertex 606.289 102.875 299.157 + endloop + endfacet + facet normal 0.254179 -0.965743 -0.0522802 + outer loop + vertex 606.289 102.875 299.157 + vertex 607.948 103.129 302.533 + vertex 607.231 102.927 302.786 + endloop + endfacet + facet normal 0.0984051 0.990665 -0.0943326 + outer loop + vertex 607.707 103.094 301.917 + vertex 608.772 103.272 304.89 + vertex 607.948 103.129 302.533 + endloop + endfacet + facet normal -0.879394 0.420773 0.222746 + outer loop + vertex 604.227 103.169 290.34 + vertex 604.936 103.017 293.428 + vertex 603.972 103.288 289.109 + endloop + endfacet + facet normal 0.203297 -0.969594 -0.136229 + outer loop + vertex 604.227 103.169 290.34 + vertex 603.972 103.288 289.109 + vertex 603.942 103.58 286.985 + endloop + endfacet + facet normal 0.37695 -0.914928 -0.144274 + outer loop + vertex 603.942 103.58 286.985 + vertex 604.873 103.093 292.51 + vertex 604.227 103.169 290.34 + endloop + endfacet + facet normal 0.282438 -0.950237 -0.131451 + outer loop + vertex 604.873 103.093 292.51 + vertex 603.942 103.58 286.985 + vertex 605.724 103.547 291.058 + endloop + endfacet + facet normal 0.287218 -0.949229 -0.128335 + outer loop + vertex 605.724 103.547 291.058 + vertex 605.522 103.127 293.707 + vertex 604.873 103.093 292.51 + endloop + endfacet + facet normal 0.19746 -0.977131 -0.0788975 + outer loop + vertex 605.522 103.127 293.707 + vertex 606.11 103.037 296.298 + vertex 604.873 103.093 292.51 + endloop + endfacet + facet normal 0.209996 -0.974178 -0.0829446 + outer loop + vertex 605.91 102.944 296.887 + vertex 604.873 103.093 292.51 + vertex 606.11 103.037 296.298 + endloop + endfacet + facet normal 0.248021 -0.96631 -0.0687764 + outer loop + vertex 606.11 103.037 296.298 + vertex 607.27 103.073 299.98 + vertex 605.91 102.944 296.887 + endloop + endfacet + facet normal 0.254002 -0.964618 -0.0706782 + outer loop + vertex 606.11 103.037 296.298 + vertex 608.014 103.312 299.383 + vertex 607.27 103.073 299.98 + endloop + endfacet + facet normal 0.262349 -0.963126 -0.0596802 + outer loop + vertex 608.014 103.312 299.383 + vertex 608.987 103.388 302.442 + vertex 607.27 103.073 299.98 + endloop + endfacet + facet normal 0.239355 -0.96999 -0.0427657 + outer loop + vertex 607.27 103.073 299.98 + vertex 608.987 103.388 302.442 + vertex 608.544 103.246 303.186 + endloop + endfacet + facet normal 0.257272 -0.965037 -0.0501544 + outer loop + vertex 607.27 103.073 299.98 + vertex 608.544 103.246 303.186 + vertex 607.285 103.027 300.933 + endloop + endfacet + facet normal 0.251111 -0.967316 -0.0352638 + outer loop + vertex 608.987 103.388 302.442 + vertex 609.929 103.552 304.639 + vertex 608.544 103.246 303.186 + endloop + endfacet + facet normal 0.241969 -0.969784 -0.0311584 + outer loop + vertex 608.987 103.388 302.442 + vertex 610.787 103.782 304.147 + vertex 609.929 103.552 304.639 + endloop + endfacet + facet normal 0.246929 -0.968783 -0.0220369 + outer loop + vertex 610.787 103.782 304.147 + vertex 611.357 103.899 305.405 + vertex 609.929 103.552 304.639 + endloop + endfacet + facet normal 0.243985 -0.969644 -0.0161672 + outer loop + vertex 609.929 103.552 304.639 + vertex 611.357 103.899 305.405 + vertex 610.512 103.682 305.663 + endloop + endfacet + facet normal 0.233747 -0.972246 -0.0100168 + outer loop + vertex 610.512 103.682 305.663 + vertex 609.764 103.505 305.393 + vertex 609.929 103.552 304.639 + endloop + endfacet + facet normal 0.227555 -0.973698 -0.0114606 + outer loop + vertex 609.764 103.505 305.393 + vertex 608.544 103.246 303.186 + vertex 609.929 103.552 304.639 + endloop + endfacet + facet normal 0.196371 -0.975835 0.0958343 + outer loop + vertex 609.764 103.505 305.393 + vertex 610.512 103.682 305.663 + vertex 611.247 103.873 306.107 + endloop + endfacet + facet normal 0.229167 -0.973033 0.0262573 + outer loop + vertex 610.266 103.666 307.004 + vertex 609.764 103.505 305.393 + vertex 611.247 103.873 306.107 + endloop + endfacet + facet normal 0.226196 -0.973814 0.0228243 + outer loop + vertex 611.247 103.873 306.107 + vertex 611.319 103.9 306.507 + vertex 610.266 103.666 307.004 + endloop + endfacet + facet normal 0.253114 -0.963727 0.0846381 + outer loop + vertex 611.802 104.022 306.46 + vertex 610.266 103.666 307.004 + vertex 611.319 103.9 306.507 + endloop + endfacet + facet normal 0.248151 -0.9685 0.0207205 + outer loop + vertex 611.319 103.9 306.507 + vertex 612.932 104.3 305.917 + vertex 611.802 104.022 306.46 + endloop + endfacet + facet normal 0.251916 -0.967309 0.0291659 + outer loop + vertex 613.451 104.434 305.883 + vertex 611.802 104.022 306.46 + vertex 612.932 104.3 305.917 + endloop + endfacet + facet normal 0.25137 -0.967696 0.0194285 + outer loop + vertex 615.05 104.837 305.232 + vertex 613.451 104.434 305.883 + vertex 612.932 104.3 305.917 + endloop + endfacet + facet normal 0.201657 -0.969973 -0.135966 + outer loop + vertex 612.932 104.3 305.917 + vertex 615.84 105.048 304.896 + vertex 615.05 104.837 305.232 + endloop + endfacet + facet normal 0.175122 -0.965002 -0.195203 + outer loop + vertex 615.84 105.048 304.896 + vertex 616.37 105.175 304.742 + vertex 615.05 104.837 305.232 + endloop + endfacet + facet normal 0.297959 -0.942568 0.150948 + outer loop + vertex 616.687 105.258 304.634 + vertex 615.05 104.837 305.232 + vertex 616.37 105.175 304.742 + endloop + endfacet + facet normal 0.254728 -0.966891 0.0153537 + outer loop + vertex 615.05 104.837 305.232 + vertex 616.687 105.258 304.634 + vertex 616.597 105.241 305.043 + endloop + endfacet + facet normal 0.264797 -0.964142 0.0176846 + outer loop + vertex 616.687 105.258 304.634 + vertex 618.221 105.67 304.118 + vertex 616.597 105.241 305.043 + endloop + endfacet + facet normal 0.275426 -0.96057 0.0380145 + outer loop + vertex 621.289 106.521 303.402 + vertex 616.597 105.241 305.043 + vertex 618.221 105.67 304.118 + endloop + endfacet + facet normal 0.0990176 -0.907189 -0.408905 + outer loop + vertex 615.84 105.048 304.896 + vertex 618.385 105.717 304.028 + vertex 616.37 105.175 304.742 + endloop + endfacet + facet normal 0.107149 -0.914065 -0.391156 + outer loop + vertex 616.37 105.175 304.742 + vertex 618.385 105.717 304.028 + vertex 616.687 105.258 304.634 + endloop + endfacet + facet normal 0.236296 -0.969084 -0.0710027 + outer loop + vertex 618.221 105.67 304.118 + vertex 616.687 105.258 304.634 + vertex 618.385 105.717 304.028 + endloop + endfacet + facet normal 0.22966 -0.969694 -0.083362 + outer loop + vertex 619.435 105.996 303.668 + vertex 618.221 105.67 304.118 + vertex 618.385 105.717 304.028 + endloop + endfacet + facet normal 0.280057 -0.958054 0.0608321 + outer loop + vertex 618.221 105.67 304.118 + vertex 619.435 105.996 303.668 + vertex 621.289 106.521 303.402 + endloop + endfacet + facet normal 0.274198 -0.961585 0.0129984 + outer loop + vertex 619.435 105.996 303.668 + vertex 620.631 106.332 303.299 + vertex 621.289 106.521 303.402 + endloop + endfacet + facet normal 0.277327 -0.960738 -0.00854372 + outer loop + vertex 620.631 106.332 303.299 + vertex 623.221 107.087 302.526 + vertex 621.289 106.521 303.402 + endloop + endfacet + facet normal 0.297642 -0.953808 0.0407408 + outer loop + vertex 626.591 108.109 301.837 + vertex 621.289 106.521 303.402 + vertex 623.221 107.087 302.526 + endloop + endfacet + facet normal 0.160421 -0.919178 -0.359691 + outer loop + vertex 623.221 107.087 302.526 + vertex 620.631 106.332 303.299 + vertex 621.479 106.587 303.027 + endloop + endfacet + facet normal -0.340349 0.140109 -0.929802 + outer loop + vertex 618.385 105.717 304.028 + vertex 621.479 106.587 303.027 + vertex 620.631 106.332 303.299 + endloop + endfacet + facet normal -0.35419 0.861751 -0.363229 + outer loop + vertex 620.631 106.332 303.299 + vertex 619.435 105.996 303.668 + vertex 618.385 105.717 304.028 + endloop + endfacet + facet normal 0.193066 -0.96498 -0.177593 + outer loop + vertex 618.928 105.898 303.636 + vertex 618.385 105.717 304.028 + vertex 615.84 105.048 304.896 + endloop + endfacet + facet normal 0.254471 -0.96667 -0.0281664 + outer loop + vertex 615.84 105.048 304.896 + vertex 615.906 105.076 304.525 + vertex 618.928 105.898 303.636 + endloop + endfacet + facet normal 0.249093 -0.967335 -0.0470773 + outer loop + vertex 617.14 105.453 303.315 + vertex 618.928 105.898 303.636 + vertex 615.906 105.076 304.525 + endloop + endfacet + facet normal 0.258466 -0.965316 -0.0368853 + outer loop + vertex 615.281 104.929 304.006 + vertex 617.14 105.453 303.315 + vertex 615.906 105.076 304.525 + endloop + endfacet + facet normal 0.250011 -0.967894 -0.025988 + outer loop + vertex 615.281 104.929 304.006 + vertex 615.906 105.076 304.525 + vertex 613.872 104.548 304.614 + endloop + endfacet + facet normal 0.247021 -0.968439 -0.0332558 + outer loop + vertex 613.545 104.504 303.477 + vertex 615.281 104.929 304.006 + vertex 613.872 104.548 304.614 + endloop + endfacet + facet normal 0.247297 -0.968366 -0.0333379 + outer loop + vertex 613.545 104.504 303.477 + vertex 613.872 104.548 304.614 + vertex 612.088 104.119 303.849 + endloop + endfacet + facet normal 0.244621 -0.968616 -0.0440913 + outer loop + vertex 611.669 104.083 302.318 + vertex 613.545 104.504 303.477 + vertex 612.088 104.119 303.849 + endloop + endfacet + facet normal 0.246432 -0.968133 -0.0445977 + outer loop + vertex 611.669 104.083 302.318 + vertex 612.088 104.119 303.849 + vertex 610.151 103.706 302.103 + endloop + endfacet + facet normal 0.248981 -0.96627 -0.0658116 + outer loop + vertex 611.669 104.083 302.318 + vertex 610.151 103.706 302.103 + vertex 609.943 103.836 299.412 + endloop + endfacet + facet normal 0.248321 -0.966467 -0.0654028 + outer loop + vertex 611.669 104.083 302.318 + vertex 609.943 103.836 299.412 + vertex 612.828 104.427 301.64 + endloop + endfacet + facet normal 0.262249 -0.961265 -0.0848189 + outer loop + vertex 609.943 103.836 299.412 + vertex 612.589 104.599 298.951 + vertex 612.828 104.427 301.64 + endloop + endfacet + facet normal 0.250913 -0.964357 -0.0840066 + outer loop + vertex 614.268 104.819 301.442 + vertex 612.828 104.427 301.64 + vertex 612.589 104.599 298.951 + endloop + endfacet + facet normal 0.260447 -0.961217 -0.0907132 + outer loop + vertex 612.589 104.599 298.951 + vertex 616.428 105.421 301.265 + vertex 614.268 104.819 301.442 + endloop + endfacet + facet normal 0.262336 -0.962331 -0.0714051 + outer loop + vertex 614.268 104.819 301.442 + vertex 616.428 105.421 301.265 + vertex 615.05 104.93 302.809 + endloop + endfacet + facet normal 0.258844 -0.963023 -0.074743 + outer loop + vertex 616.428 105.421 301.265 + vertex 617.14 105.453 303.315 + vertex 615.05 104.93 302.809 + endloop + endfacet + facet normal 0.254147 -0.9644 -0.0730909 + outer loop + vertex 616.428 105.421 301.265 + vertex 619.925 106.268 302.238 + vertex 617.14 105.453 303.315 + endloop + endfacet + facet normal 0.260565 -0.960289 -0.0997543 + outer loop + vertex 619.645 106.404 300.2 + vertex 619.925 106.268 302.238 + vertex 616.428 105.421 301.265 + endloop + endfacet + facet normal 0.260383 -0.960282 -0.100299 + outer loop + vertex 615.428 105.488 298.018 + vertex 619.645 106.404 300.2 + vertex 616.428 105.421 301.265 + endloop + endfacet + facet normal 0.272107 -0.954037 -0.125582 + outer loop + vertex 618.648 106.497 297.332 + vertex 619.645 106.404 300.2 + vertex 615.428 105.488 298.018 + endloop + endfacet + facet normal 0.271596 -0.953892 -0.127769 + outer loop + vertex 614.17 105.643 294.189 + vertex 618.648 106.497 297.332 + vertex 615.428 105.488 298.018 + endloop + endfacet + facet normal 0.281122 -0.95072 -0.13077 + outer loop + vertex 614.17 105.643 294.189 + vertex 615.428 105.488 298.018 + vertex 611.234 104.722 294.573 + endloop + endfacet + facet normal 0.279948 -0.95003 -0.138098 + outer loop + vertex 610.524 105.088 290.619 + vertex 614.17 105.643 294.189 + vertex 611.234 104.722 294.573 + endloop + endfacet + facet normal 0.289902 -0.946822 -0.13959 + outer loop + vertex 610.524 105.088 290.619 + vertex 611.234 104.722 294.573 + vertex 607.8 104.344 290.007 + endloop + endfacet + facet normal 0.292812 -0.943204 -0.156934 + outer loop + vertex 610.524 105.088 290.619 + vertex 607.8 104.344 290.007 + vertex 608.355 105.427 284.533 + endloop + endfacet + facet normal 0.296312 -0.941913 -0.158109 + outer loop + vertex 610.524 105.088 290.619 + vertex 608.355 105.427 284.533 + vertex 613.082 106.063 289.603 + endloop + endfacet + facet normal 0.312764 -0.933667 -0.174482 + outer loop + vertex 608.355 105.427 284.533 + vertex 613.601 107.297 283.929 + vertex 613.082 106.063 289.603 + endloop + endfacet + facet normal 0.300414 -0.937352 -0.176415 + outer loop + vertex 616.607 107.113 290.029 + vertex 613.082 106.063 289.603 + vertex 613.601 107.297 283.929 + endloop + endfacet + facet normal 0.308441 -0.934006 -0.18027 + outer loop + vertex 616.607 107.113 290.029 + vertex 613.601 107.297 283.929 + vertex 619.547 108.314 288.832 + endloop + endfacet + facet normal 0.305776 -0.933664 -0.186472 + outer loop + vertex 619.547 108.314 288.832 + vertex 620.759 107.831 293.24 + vertex 616.607 107.113 290.029 + endloop + endfacet + facet normal 0.293567 -0.940868 -0.169076 + outer loop + vertex 616.607 107.113 290.029 + vertex 620.759 107.831 293.24 + vertex 617.401 106.69 293.76 + endloop + endfacet + facet normal 0.293008 -0.940524 -0.171932 + outer loop + vertex 620.759 107.831 293.24 + vertex 621.985 107.585 296.674 + vertex 617.401 106.69 293.76 + endloop + endfacet + facet normal 0.279883 -0.948423 -0.148862 + outer loop + vertex 617.401 106.69 293.76 + vertex 621.985 107.585 296.674 + vertex 618.648 106.497 297.332 + endloop + endfacet + facet normal 0.27925 -0.948168 -0.15165 + outer loop + vertex 621.985 107.585 296.674 + vertex 622.962 107.444 299.355 + vertex 618.648 106.497 297.332 + endloop + endfacet + facet normal 0.276543 -0.94911 -0.150712 + outer loop + vertex 621.985 107.585 296.674 + vertex 626.282 108.539 298.55 + vertex 622.962 107.444 299.355 + endloop + endfacet + facet normal 0.274082 -0.948336 -0.159806 + outer loop + vertex 626.282 108.539 298.55 + vertex 626.546 108.316 300.33 + vertex 622.962 107.444 299.355 + endloop + endfacet + facet normal 0.267548 -0.95472 -0.130108 + outer loop + vertex 622.962 107.444 299.355 + vertex 626.546 108.316 300.33 + vertex 623.219 107.261 301.229 + endloop + endfacet + facet normal 0.266382 -0.955063 -0.129982 + outer loop + vertex 622.962 107.444 299.355 + vertex 623.219 107.261 301.229 + vertex 619.645 106.404 300.2 + endloop + endfacet + facet normal 0.260516 -0.953073 -0.15422 + outer loop + vertex 626.546 108.316 300.33 + vertex 625.893 107.959 301.434 + vertex 623.219 107.261 301.229 + endloop + endfacet + facet normal 0.258981 -0.959201 -0.113413 + outer loop + vertex 622.6 106.954 302.407 + vertex 623.219 107.261 301.229 + vertex 625.893 107.959 301.434 + endloop + endfacet + facet normal 0.229106 -0.951274 -0.206368 + outer loop + vertex 625.893 107.959 301.434 + vertex 624.864 107.588 302.001 + vertex 622.6 106.954 302.407 + endloop + endfacet + facet normal 0.246687 -0.961172 -0.123665 + outer loop + vertex 622.6 106.954 302.407 + vertex 624.864 107.588 302.001 + vertex 621.479 106.587 303.027 + endloop + endfacet + facet normal 0.217441 -0.960092 -0.175903 + outer loop + vertex 622.6 106.954 302.407 + vertex 621.479 106.587 303.027 + vertex 618.928 105.898 303.636 + endloop + endfacet + facet normal 0.252233 -0.964681 -0.0759524 + outer loop + vertex 622.6 106.954 302.407 + vertex 618.928 105.898 303.636 + vertex 619.925 106.268 302.238 + endloop + endfacet + facet normal 0.110405 -0.86857 -0.483111 + outer loop + vertex 621.479 106.587 303.027 + vertex 624.864 107.588 302.001 + vertex 623.221 107.087 302.526 + endloop + endfacet + facet normal 0.207838 -0.945339 -0.251273 + outer loop + vertex 625.423 107.748 301.862 + vertex 623.221 107.087 302.526 + vertex 624.864 107.588 302.001 + endloop + endfacet + facet normal -0.127367 -0.360903 -0.923865 + outer loop + vertex 627.698 108.476 301.263 + vertex 625.423 107.748 301.862 + vertex 624.864 107.588 302.001 + endloop + endfacet + facet normal 0.278839 -0.956857 -0.0816956 + outer loop + vertex 624.864 107.588 302.001 + vertex 627.69 108.479 301.201 + vertex 627.698 108.476 301.263 + endloop + endfacet + facet normal 0.297617 -0.951007 -0.083719 + outer loop + vertex 630.648 109.473 300.427 + vertex 627.698 108.476 301.263 + vertex 627.69 108.479 301.201 + endloop + endfacet + facet normal 0.26953 -0.945306 -0.18371 + outer loop + vertex 627.69 108.479 301.201 + vertex 629.277 109.066 300.51 + vertex 630.648 109.473 300.427 + endloop + endfacet + facet normal 0.240484 -0.939169 -0.245211 + outer loop + vertex 629.277 109.066 300.51 + vertex 627.69 108.479 301.201 + vertex 625.893 107.959 301.434 + endloop + endfacet + facet normal 0.303491 -0.950768 -0.0627206 + outer loop + vertex 627.698 108.476 301.263 + vertex 630.648 109.473 300.427 + vertex 631.973 109.896 300.439 + endloop + endfacet + facet normal 0.294631 -0.954656 -0.042707 + outer loop + vertex 625.423 107.748 301.862 + vertex 627.698 108.476 301.263 + vertex 626.591 108.109 301.837 + endloop + endfacet + facet normal 0.296162 -0.95459 0.0323351 + outer loop + vertex 623.221 107.087 302.526 + vertex 625.423 107.748 301.862 + vertex 626.591 108.109 301.837 + endloop + endfacet + facet normal 0.255763 -0.953501 -0.159441 + outer loop + vertex 625.893 107.959 301.434 + vertex 627.69 108.479 301.201 + vertex 624.864 107.588 302.001 + endloop + endfacet + facet normal 0.253657 -0.960255 -0.116484 + outer loop + vertex 619.925 106.268 302.238 + vertex 623.219 107.261 301.229 + vertex 622.6 106.954 302.407 + endloop + endfacet + facet normal 0.27115 -0.951196 -0.147323 + outer loop + vertex 629.277 109.066 300.51 + vertex 625.893 107.959 301.434 + vertex 626.546 108.316 300.33 + endloop + endfacet + facet normal 0.271724 -0.945128 -0.181379 + outer loop + vertex 626.546 108.316 300.33 + vertex 629.969 109.475 299.418 + vertex 629.277 109.066 300.51 + endloop + endfacet + facet normal 0.278033 -0.947112 -0.160239 + outer loop + vertex 626.282 108.539 298.55 + vertex 629.969 109.475 299.418 + vertex 626.546 108.316 300.33 + endloop + endfacet + facet normal 0.282154 -0.941624 -0.183668 + outer loop + vertex 629.523 109.656 297.803 + vertex 629.969 109.475 299.418 + vertex 626.282 108.539 298.55 + endloop + endfacet + facet normal 0.284377 -0.942535 -0.175378 + outer loop + vertex 625.335 108.728 296 + vertex 629.523 109.656 297.803 + vertex 626.282 108.539 298.55 + endloop + endfacet + facet normal 0.292631 -0.935462 -0.198185 + outer loop + vertex 628.676 109.91 295.356 + vertex 629.523 109.656 297.803 + vertex 625.335 108.728 296 + endloop + endfacet + facet normal 0.29468 -0.936594 -0.18962 + outer loop + vertex 624.175 109.037 292.669 + vertex 628.676 109.91 295.356 + vertex 625.335 108.728 296 + endloop + endfacet + facet normal 0.298399 -0.935179 -0.190784 + outer loop + vertex 624.175 109.037 292.669 + vertex 625.335 108.728 296 + vertex 620.759 107.831 293.24 + endloop + endfacet + facet normal 0.304978 -0.929073 -0.209312 + outer loop + vertex 627.566 110.277 292.109 + vertex 628.676 109.91 295.356 + vertex 624.175 109.037 292.669 + endloop + endfacet + facet normal 0.306909 -0.930378 -0.200509 + outer loop + vertex 623.405 109.553 289.097 + vertex 627.566 110.277 292.109 + vertex 624.175 109.037 292.669 + endloop + endfacet + facet normal 0.311988 -0.928508 -0.201334 + outer loop + vertex 623.405 109.553 289.097 + vertex 624.175 109.037 292.669 + vertex 619.547 108.314 288.832 + endloop + endfacet + facet normal 0.311989 -0.928981 -0.199142 + outer loop + vertex 623.405 109.553 289.097 + vertex 619.547 108.314 288.832 + vertex 620.005 109.669 283.229 + endloop + endfacet + facet normal 0.322241 -0.924197 -0.204988 + outer loop + vertex 623.405 109.553 289.097 + vertex 620.005 109.669 283.229 + vertex 626.37 110.849 287.915 + endloop + endfacet + facet normal 0.334676 -0.915293 -0.224121 + outer loop + vertex 620.005 109.669 283.229 + vertex 626.816 112.322 282.568 + vertex 626.37 110.849 287.915 + endloop + endfacet + facet normal 0.326844 -0.917791 -0.225463 + outer loop + vertex 630.147 112.126 288.191 + vertex 626.37 110.849 287.915 + vertex 626.816 112.322 282.568 + endloop + endfacet + facet normal 0.342179 -0.909961 -0.234274 + outer loop + vertex 630.147 112.126 288.191 + vertex 626.816 112.322 282.568 + vertex 633.091 113.503 287.146 + endloop + endfacet + facet normal 0.336344 -0.908341 -0.248573 + outer loop + vertex 633.091 113.503 287.146 + vertex 633.953 112.751 291.06 + vertex 630.147 112.126 288.191 + endloop + endfacet + facet normal 0.325485 -0.916548 -0.232378 + outer loop + vertex 630.147 112.126 288.191 + vertex 633.953 112.751 291.06 + vertex 630.844 111.516 291.573 + endloop + endfacet + facet normal 0.323146 -0.914795 -0.242335 + outer loop + vertex 633.953 112.751 291.06 + vertex 635.079 112.361 294.033 + vertex 630.844 111.516 291.573 + endloop + endfacet + facet normal 0.315236 -0.921618 -0.226376 + outer loop + vertex 630.844 111.516 291.573 + vertex 635.079 112.361 294.033 + vertex 631.975 111.131 294.716 + endloop + endfacet + facet normal 0.312195 -0.922883 -0.225436 + outer loop + vertex 630.844 111.516 291.573 + vertex 631.975 111.131 294.716 + vertex 627.566 110.277 292.109 + endloop + endfacet + facet normal 0.314354 -0.924444 -0.215833 + outer loop + vertex 626.37 110.849 287.915 + vertex 630.844 111.516 291.573 + vertex 627.566 110.277 292.109 + endloop + endfacet + facet normal 0.313428 -0.92063 -0.232816 + outer loop + vertex 635.079 112.361 294.033 + vertex 636.241 112.162 296.382 + vertex 631.975 111.131 294.716 + endloop + endfacet + facet normal 0.309484 -0.925119 -0.219941 + outer loop + vertex 631.975 111.131 294.716 + vertex 636.241 112.162 296.382 + vertex 632.779 110.831 297.113 + endloop + endfacet + facet normal 0.301561 -0.928266 -0.217678 + outer loop + vertex 631.975 111.131 294.716 + vertex 632.779 110.831 297.113 + vertex 628.676 109.91 295.356 + endloop + endfacet + facet normal 0.307147 -0.923797 -0.228604 + outer loop + vertex 636.241 112.162 296.382 + vertex 636.279 111.766 298.035 + vertex 632.779 110.831 297.113 + endloop + endfacet + facet normal 0.303482 -0.929702 -0.208696 + outer loop + vertex 632.779 110.831 297.113 + vertex 636.279 111.766 298.035 + vertex 632.742 110.487 298.587 + endloop + endfacet + facet normal 0.292096 -0.933099 -0.209774 + outer loop + vertex 632.779 110.831 297.113 + vertex 632.742 110.487 298.587 + vertex 629.523 109.656 297.803 + endloop + endfacet + facet normal 0.30304 -0.929377 -0.210773 + outer loop + vertex 632.742 110.487 298.587 + vertex 636.279 111.766 298.035 + vertex 634.129 110.774 299.317 + endloop + endfacet + facet normal 0.289288 -0.94009 -0.180399 + outer loop + vertex 632.742 110.487 298.587 + vertex 634.129 110.774 299.317 + vertex 629.969 109.475 299.418 + endloop + endfacet + facet normal 0.324585 -0.918059 -0.227625 + outer loop + vertex 636.241 112.162 296.382 + vertex 640.68 113.567 297.048 + vertex 636.279 111.766 298.035 + endloop + endfacet + facet normal 0.311129 -0.910209 -0.273348 + outer loop + vertex 640.68 113.567 297.048 + vertex 639.98 112.986 298.185 + vertex 636.279 111.766 298.035 + endloop + endfacet + facet normal 0.332936 -0.906905 -0.258219 + outer loop + vertex 640.68 113.567 297.048 + vertex 645.514 115.306 297.171 + vertex 639.98 112.986 298.185 + endloop + endfacet + facet normal 0.328735 -0.891439 -0.311879 + outer loop + vertex 645.4 115.853 295.489 + vertex 645.514 115.306 297.171 + vertex 640.68 113.567 297.048 + endloop + endfacet + facet normal 0.348723 -0.899507 -0.26321 + outer loop + vertex 640.68 113.567 297.048 + vertex 639.487 113.621 295.283 + vertex 645.4 115.853 295.489 + endloop + endfacet + facet normal 0.349105 -0.90106 -0.257328 + outer loop + vertex 641.179 114.833 293.333 + vertex 645.4 115.853 295.489 + vertex 639.487 113.621 295.283 + endloop + endfacet + facet normal 0.346211 -0.901395 -0.260049 + outer loop + vertex 637.44 113.426 293.234 + vertex 641.179 114.833 293.333 + vertex 639.487 113.621 295.283 + endloop + endfacet + facet normal 0.32952 -0.912521 -0.242328 + outer loop + vertex 637.44 113.426 293.234 + vertex 639.487 113.621 295.283 + vertex 635.079 112.361 294.033 + endloop + endfacet + facet normal 0.3462 -0.901355 -0.2602 + outer loop + vertex 637.262 114.087 290.705 + vertex 641.179 114.833 293.333 + vertex 637.44 113.426 293.234 + endloop + endfacet + facet normal 0.33746 -0.904597 -0.260431 + outer loop + vertex 637.262 114.087 290.705 + vertex 637.44 113.426 293.234 + vertex 633.953 112.751 291.06 + endloop + endfacet + facet normal 0.354913 -0.893403 -0.275442 + outer loop + vertex 641.071 115.732 290.277 + vertex 641.179 114.833 293.333 + vertex 637.262 114.087 290.705 + endloop + endfacet + facet normal 0.357269 -0.895895 -0.264065 + outer loop + vertex 637.022 114.943 287.479 + vertex 641.071 115.732 290.277 + vertex 637.262 114.087 290.705 + endloop + endfacet + facet normal 0.351376 -0.898174 -0.26423 + outer loop + vertex 637.022 114.943 287.479 + vertex 637.262 114.087 290.705 + vertex 633.091 113.503 287.146 + endloop + endfacet + facet normal 0.351566 -0.901113 -0.253766 + outer loop + vertex 637.022 114.943 287.479 + vertex 633.091 113.503 287.146 + vertex 633.82 115.24 281.987 + endloop + endfacet + facet normal 0.370484 -0.890465 -0.264222 + outer loop + vertex 637.022 114.943 287.479 + vertex 633.82 115.24 281.987 + vertex 640.197 116.611 286.307 + endloop + endfacet + facet normal 0.377836 -0.883361 -0.277332 + outer loop + vertex 633.82 115.24 281.987 + vertex 640.911 118.44 281.454 + vertex 640.197 116.611 286.307 + endloop + endfacet + facet normal 0.380316 -0.882511 -0.276647 + outer loop + vertex 643.564 118.1 286.186 + vertex 640.197 116.611 286.307 + vertex 640.911 118.44 281.454 + endloop + endfacet + facet normal 0.39381 -0.87434 -0.283626 + outer loop + vertex 640.911 118.44 281.454 + vertex 648.042 119.911 286.822 + vertex 643.564 118.1 286.186 + endloop + endfacet + facet normal 0.393871 -0.871551 -0.292002 + outer loop + vertex 643.564 118.1 286.186 + vertex 648.042 119.911 286.822 + vertex 644.794 117.626 289.262 + endloop + endfacet + facet normal 0.384518 -0.871487 -0.304395 + outer loop + vertex 648.042 119.911 286.822 + vertex 649.333 118.947 291.211 + vertex 644.794 117.626 289.262 + endloop + endfacet + facet normal 0.380871 -0.877331 -0.291938 + outer loop + vertex 645.844 116.94 292.693 + vertex 644.794 117.626 289.262 + vertex 649.333 118.947 291.211 + endloop + endfacet + facet normal 0.377858 -0.876588 -0.298022 + outer loop + vertex 645.844 116.94 292.693 + vertex 649.333 118.947 291.211 + vertex 652.229 119.204 294.127 + endloop + endfacet + facet normal 0.376466 -0.882119 -0.283088 + outer loop + vertex 652.229 119.204 294.127 + vertex 645.4 115.853 295.489 + vertex 645.844 116.94 292.693 + endloop + endfacet + facet normal 0.354667 -0.86595 -0.35262 + outer loop + vertex 652.229 119.204 294.127 + vertex 651.342 117.965 296.277 + vertex 645.4 115.853 295.489 + endloop + endfacet + facet normal 0.379222 -0.860775 -0.339495 + outer loop + vertex 652.229 119.204 294.127 + vertex 657.743 120.966 295.821 + vertex 651.342 117.965 296.277 + endloop + endfacet + facet normal 0.386583 -0.836196 -0.389011 + outer loop + vertex 659.538 122.723 293.828 + vertex 657.743 120.966 295.821 + vertex 652.229 119.204 294.127 + endloop + endfacet + facet normal 0.400575 -0.859236 -0.318201 + outer loop + vertex 659.538 122.723 293.828 + vertex 652.229 119.204 294.127 + vertex 654.397 121.404 290.917 + endloop + endfacet + facet normal 0.407257 -0.835217 -0.369533 + outer loop + vertex 659.538 122.723 293.828 + vertex 664.153 124.256 295.447 + vertex 657.743 120.966 295.821 + endloop + endfacet + facet normal 0.416349 -0.803523 -0.425447 + outer loop + vertex 665.849 126.126 293.576 + vertex 664.153 124.256 295.447 + vertex 659.538 122.723 293.828 + endloop + endfacet + facet normal 0.43278 -0.828769 -0.354743 + outer loop + vertex 665.849 126.126 293.576 + vertex 659.538 122.723 293.828 + vertex 660.608 124.675 290.572 + endloop + endfacet + facet normal 0.418584 -0.83295 -0.361913 + outer loop + vertex 654.397 121.404 290.917 + vertex 660.608 124.675 290.572 + vertex 659.538 122.723 293.828 + endloop + endfacet + facet normal 0.426381 -0.843928 -0.325555 + outer loop + vertex 654.405 123.269 286.093 + vertex 660.608 124.675 290.572 + vertex 654.397 121.404 290.917 + endloop + endfacet + facet normal 0.411223 -0.85044 -0.328098 + outer loop + vertex 654.405 123.269 286.093 + vertex 654.397 121.404 290.917 + vertex 648.042 119.911 286.822 + endloop + endfacet + facet normal 0.418616 -0.857905 -0.297924 + outer loop + vertex 647.369 121.834 280.339 + vertex 654.405 123.269 286.093 + vertex 648.042 119.911 286.822 + endloop + endfacet + facet normal 0.433949 -0.841944 -0.320652 + outer loop + vertex 653.595 125.228 279.853 + vertex 654.405 123.269 286.093 + vertex 647.369 121.834 280.339 + endloop + endfacet + facet normal 0.441201 -0.850384 -0.286687 + outer loop + vertex 646.309 123.706 273.153 + vertex 653.595 125.228 279.853 + vertex 647.369 121.834 280.339 + endloop + endfacet + facet normal 0.425759 -0.858292 -0.286468 + outer loop + vertex 646.309 123.706 273.153 + vertex 647.369 121.834 280.339 + vertex 639.867 120.364 273.592 + endloop + endfacet + facet normal 0.431449 -0.865195 -0.255518 + outer loop + vertex 638.886 122.108 266.032 + vertex 646.309 123.706 273.153 + vertex 639.867 120.364 273.592 + endloop + endfacet + facet normal 0.41749 -0.872082 -0.255295 + outer loop + vertex 638.886 122.108 266.032 + vertex 639.867 120.364 273.592 + vertex 632.219 118.838 266.297 + endloop + endfacet + facet normal 0.421326 -0.877709 -0.228277 + outer loop + vertex 631.452 120.444 258.709 + vertex 638.886 122.108 266.032 + vertex 632.219 118.838 266.297 + endloop + endfacet + facet normal 0.407528 -0.884206 -0.228257 + outer loop + vertex 631.452 120.444 258.709 + vertex 632.219 118.838 266.297 + vertex 624.595 117.258 258.808 + endloop + endfacet + facet normal 0.409878 -0.88857 -0.206017 + outer loop + vertex 624.005 118.759 251.162 + vertex 631.452 120.444 258.709 + vertex 624.595 117.258 258.808 + endloop + endfacet + facet normal 0.39656 -0.894559 -0.206165 + outer loop + vertex 624.005 118.759 251.162 + vertex 624.595 117.258 258.808 + vertex 617.151 115.725 251.14 + endloop + endfacet + facet normal 0.398059 -0.898082 -0.187075 + outer loop + vertex 616.707 117.146 243.372 + vertex 624.005 118.759 251.162 + vertex 617.151 115.725 251.14 + endloop + endfacet + facet normal 0.38612 -0.903226 -0.187333 + outer loop + vertex 616.707 117.146 243.372 + vertex 617.151 115.725 251.14 + vertex 610.356 114.416 243.445 + endloop + endfacet + facet normal 0.387558 -0.906099 -0.169654 + outer loop + vertex 610.047 115.764 235.544 + vertex 616.707 117.146 243.372 + vertex 610.356 114.416 243.445 + endloop + endfacet + facet normal 0.376148 -0.910828 -0.170015 + outer loop + vertex 610.047 115.764 235.544 + vertex 610.356 114.416 243.445 + vertex 604.801 113.507 236.026 + endloop + endfacet + facet normal 0.378545 -0.912814 -0.153214 + outer loop + vertex 604.631 114.776 228.043 + vertex 610.047 115.764 235.544 + vertex 604.801 113.507 236.026 + endloop + endfacet + facet normal 0.36445 -0.918433 -0.153807 + outer loop + vertex 604.631 114.776 228.043 + vertex 604.801 113.507 236.026 + vertex 600.746 113.071 229.019 + endloop + endfacet + facet normal 0.368931 -0.919245 -0.137399 + outer loop + vertex 600.851 114.266 221.309 + vertex 604.631 114.776 228.043 + vertex 600.746 113.071 229.019 + endloop + endfacet + facet normal 0.352355 -0.925546 -0.1386 + outer loop + vertex 600.851 114.266 221.309 + vertex 600.746 113.071 229.019 + vertex 599.279 113.336 223.52 + endloop + endfacet + facet normal 0.359207 -0.923736 -0.132971 + outer loop + vertex 599.279 113.336 223.52 + vertex 599.241 113.856 219.807 + vertex 600.851 114.266 221.309 + endloop + endfacet + facet normal 0.349784 -0.928924 -0.121457 + outer loop + vertex 599.241 113.856 219.807 + vertex 599.378 114.271 217.031 + vertex 600.851 114.266 221.309 + endloop + endfacet + facet normal 0.338206 -0.933711 -0.117476 + outer loop + vertex 600.545 115.185 213.121 + vertex 600.851 114.266 221.309 + vertex 599.378 114.271 217.031 + endloop + endfacet + facet normal 0.358734 -0.926963 -0.109769 + outer loop + vertex 599.378 114.271 217.031 + vertex 598.949 114.513 213.58 + vertex 600.545 115.185 213.121 + endloop + endfacet + facet normal 0.359656 -0.926978 -0.106582 + outer loop + vertex 598.949 114.513 213.58 + vertex 599.079 114.892 210.722 + vertex 600.545 115.185 213.121 + endloop + endfacet + facet normal 0.336916 -0.937083 -0.0914518 + outer loop + vertex 599.079 114.892 210.722 + vertex 599.07 115.249 207.035 + vertex 600.545 115.185 213.121 + endloop + endfacet + facet normal 0.350111 -0.93192 -0.0945957 + outer loop + vertex 600.349 116.005 204.323 + vertex 600.545 115.185 213.121 + vertex 599.07 115.249 207.035 + endloop + endfacet + facet normal 0.356328 -0.929909 -0.091104 + outer loop + vertex 599.07 115.249 207.035 + vertex 599.01 115.562 203.609 + vertex 600.349 116.005 204.323 + endloop + endfacet + facet normal 0.349997 -0.933585 -0.0769457 + outer loop + vertex 599.01 115.562 203.609 + vertex 598.963 115.686 201.882 + vertex 600.349 116.005 204.323 + endloop + endfacet + facet normal 0.333009 -0.940584 -0.0663831 + outer loop + vertex 598.963 115.686 201.882 + vertex 598.922 115.913 198.466 + vertex 600.349 116.005 204.323 + endloop + endfacet + facet normal 0.353511 -0.932693 -0.0715032 + outer loop + vertex 600.22 116.605 195.852 + vertex 600.349 116.005 204.323 + vertex 598.922 115.913 198.466 + endloop + endfacet + facet normal 0.36112 -0.930107 -0.0670367 + outer loop + vertex 598.922 115.913 198.466 + vertex 598.823 116.125 194.998 + vertex 600.22 116.605 195.852 + endloop + endfacet + facet normal 0.35454 -0.933458 -0.0543848 + outer loop + vertex 598.823 116.125 194.998 + vertex 598.806 116.219 193.273 + vertex 600.22 116.605 195.852 + endloop + endfacet + facet normal 0.335373 -0.941116 -0.0427266 + outer loop + vertex 598.806 116.219 193.273 + vertex 598.822 116.378 189.878 + vertex 600.22 116.605 195.852 + endloop + endfacet + facet normal 0.365203 -0.929576 -0.0501456 + outer loop + vertex 600.396 117.09 188.146 + vertex 600.22 116.605 195.852 + vertex 598.822 116.378 189.878 + endloop + endfacet + facet normal 0.372694 -0.926991 -0.0422717 + outer loop + vertex 598.822 116.378 189.878 + vertex 598.817 116.546 186.161 + vertex 600.396 117.09 188.146 + endloop + endfacet + facet normal 0.359789 -0.932536 -0.0304833 + outer loop + vertex 598.817 116.546 186.161 + vertex 598.994 116.703 183.45 + vertex 600.396 117.09 188.146 + endloop + endfacet + facet normal 0.354311 -0.934688 -0.02867 + outer loop + vertex 600.224 117.272 180.102 + vertex 600.396 117.09 188.146 + vertex 598.994 116.703 183.45 + endloop + endfacet + facet normal 0.37476 -0.92691 -0.0198364 + outer loop + vertex 598.994 116.703 183.45 + vertex 598.626 116.634 179.706 + vertex 600.224 117.272 180.102 + endloop + endfacet + facet normal 0.374358 -0.927112 -0.0178856 + outer loop + vertex 598.626 116.634 179.706 + vertex 598.812 116.757 177.209 + vertex 600.224 117.272 180.102 + endloop + endfacet + facet normal 0.355357 -0.934702 -0.00725884 + outer loop + vertex 598.812 116.757 177.209 + vertex 599 116.847 174.862 + vertex 600.224 117.272 180.102 + endloop + endfacet + facet normal 0.355223 -0.934754 -0.00722323 + outer loop + vertex 600.219 117.333 171.868 + vertex 600.224 117.272 180.102 + vertex 599 116.847 174.862 + endloop + endfacet + facet normal 0.37588 -0.926665 0.00250042 + outer loop + vertex 599 116.847 174.862 + vertex 598.651 116.695 171.021 + vertex 600.219 117.333 171.868 + endloop + endfacet + facet normal 0.374839 -0.927078 0.00473697 + outer loop + vertex 598.651 116.695 171.021 + vertex 598.823 116.753 168.666 + vertex 600.219 117.333 171.868 + endloop + endfacet + facet normal 0.354221 -0.935039 0.0151683 + outer loop + vertex 598.823 116.753 168.666 + vertex 599.018 116.79 166.446 + vertex 600.219 117.333 171.868 + endloop + endfacet + facet normal 0.36058 -0.93263 0.0135183 + outer loop + vertex 600.387 117.287 164.18 + vertex 600.219 117.333 171.868 + vertex 599.018 116.79 166.446 + endloop + endfacet + facet normal 0.377056 -0.925854 0.0249639 + outer loop + vertex 599.018 116.79 166.446 + vertex 598.683 116.541 162.251 + vertex 600.387 117.287 164.18 + endloop + endfacet + facet normal 0.37328 -0.92727 0.0288477 + outer loop + vertex 598.683 116.541 162.251 + vertex 598.977 116.556 158.95 + vertex 600.387 117.287 164.18 + endloop + endfacet + facet normal 0.35578 -0.933933 0.0344981 + outer loop + vertex 600.188 116.908 155.973 + vertex 600.387 117.287 164.18 + vertex 598.977 116.556 158.95 + endloop + endfacet + facet normal 0.364035 -0.9306 0.0382513 + outer loop + vertex 598.977 116.556 158.95 + vertex 598.776 116.362 156.127 + vertex 600.188 116.908 155.973 + endloop + endfacet + facet normal 0.365169 -0.92945 0.0526737 + outer loop + vertex 598.776 116.362 156.127 + vertex 598.669 116.157 153.262 + vertex 600.188 116.908 155.973 + endloop + endfacet + facet normal 0.365773 -0.929235 0.0522753 + outer loop + vertex 598.669 116.157 153.262 + vertex 599.039 116.137 150.301 + vertex 600.188 116.908 155.973 + endloop + endfacet + facet normal 0.353791 -0.933688 0.0553078 + outer loop + vertex 600.259 116.428 147.414 + vertex 600.188 116.908 155.973 + vertex 599.039 116.137 150.301 + endloop + endfacet + facet normal 0.362611 -0.930046 0.0594007 + outer loop + vertex 599.039 116.137 150.301 + vertex 598.905 115.9 147.413 + vertex 600.259 116.428 147.414 + endloop + endfacet + facet normal 0.362248 -0.929159 0.0737602 + outer loop + vertex 598.905 115.9 147.413 + vertex 598.789 115.624 144.503 + vertex 600.259 116.428 147.414 + endloop + endfacet + facet normal 0.362874 -0.928944 0.0733854 + outer loop + vertex 598.789 115.624 144.503 + vertex 599.143 115.529 141.559 + vertex 600.259 116.428 147.414 + endloop + endfacet + facet normal 0.35475 -0.931917 0.0753901 + outer loop + vertex 600.397 115.793 138.924 + vertex 600.259 116.428 147.414 + vertex 599.143 115.529 141.559 + endloop + endfacet + facet normal 0.363486 -0.928165 0.0799224 + outer loop + vertex 599.143 115.529 141.559 + vertex 599 115.222 138.639 + vertex 600.397 115.793 138.924 + endloop + endfacet + facet normal 0.360203 -0.927958 0.0956406 + outer loop + vertex 599 115.222 138.639 + vertex 598.856 114.864 135.708 + vertex 600.397 115.793 138.924 + endloop + endfacet + facet normal 0.363797 -0.926766 0.0935734 + outer loop + vertex 598.856 114.864 135.708 + vertex 599.262 114.748 132.984 + vertex 600.397 115.793 138.924 + endloop + endfacet + facet normal 0.359498 -0.928331 0.0946701 + outer loop + vertex 600.719 115.139 131.28 + vertex 600.397 115.793 138.924 + vertex 599.262 114.748 132.984 + endloop + endfacet + facet normal 0.366472 -0.924885 0.101422 + outer loop + vertex 599.262 114.748 132.984 + vertex 599.156 114.37 129.918 + vertex 600.719 115.139 131.28 + endloop + endfacet + facet normal 0.355624 -0.927486 0.115335 + outer loop + vertex 599.156 114.37 129.918 + vertex 599.2 113.915 126.122 + vertex 600.719 115.139 131.28 + endloop + endfacet + facet normal 0.358579 -0.926484 0.114227 + outer loop + vertex 600.622 114.1 123.16 + vertex 600.719 115.139 131.28 + vertex 599.2 113.915 126.122 + endloop + endfacet + facet normal 0.361657 -0.925092 0.115792 + outer loop + vertex 599.2 113.915 126.122 + vertex 599.228 113.489 122.634 + vertex 600.622 114.1 123.16 + endloop + endfacet + facet normal 0.357966 -0.925231 0.12573 + outer loop + vertex 599.228 113.489 122.634 + vertex 599.252 113.265 120.917 + vertex 600.622 114.1 123.16 + endloop + endfacet + facet normal 0.341577 -0.929752 0.137427 + outer loop + vertex 599.252 113.265 120.917 + vertex 599.336 112.796 117.531 + vertex 600.622 114.1 123.16 + endloop + endfacet + facet normal 0.354825 -0.925369 0.133384 + outer loop + vertex 600.748 112.96 114.913 + vertex 600.622 114.1 123.16 + vertex 599.336 112.796 117.531 + endloop + endfacet + facet normal 0.359115 -0.923357 0.135824 + outer loop + vertex 599.336 112.796 117.531 + vertex 599.369 112.308 114.129 + vertex 600.748 112.96 114.913 + endloop + endfacet + facet normal 0.353369 -0.923953 0.146428 + outer loop + vertex 599.369 112.308 114.129 + vertex 599.397 112.049 112.428 + vertex 600.748 112.96 114.913 + endloop + endfacet + facet normal 0.338071 -0.92806 0.156247 + outer loop + vertex 599.397 112.049 112.428 + vertex 599.512 111.526 109.072 + vertex 600.748 112.96 114.913 + endloop + endfacet + facet normal 0.356366 -0.922079 0.150908 + outer loop + vertex 601.119 111.858 107.308 + vertex 600.748 112.96 114.913 + vertex 599.512 111.526 109.072 + endloop + endfacet + facet normal 0.36109 -0.919439 0.15571 + outer loop + vertex 599.512 111.526 109.072 + vertex 599.595 110.94 105.42 + vertex 601.119 111.858 107.308 + endloop + endfacet + facet normal 0.349538 -0.922045 0.166301 + outer loop + vertex 599.595 110.94 105.42 + vertex 599.833 110.543 102.717 + vertex 601.119 111.858 107.308 + endloop + endfacet + facet normal 0.342438 -0.924231 0.168916 + outer loop + vertex 601.214 110.436 99.3313 + vertex 601.119 111.858 107.308 + vertex 599.833 110.543 102.717 + endloop + endfacet + facet normal 0.353959 -0.919037 0.17345 + outer loop + vertex 599.833 110.543 102.717 + vertex 599.624 109.778 99.0942 + vertex 601.214 110.436 99.3313 + endloop + endfacet + facet normal 0.353551 -0.918799 0.175527 + outer loop + vertex 599.624 109.778 99.0942 + vertex 599.888 109.408 96.6211 + vertex 601.214 110.436 99.3313 + endloop + endfacet + facet normal 0.338407 -0.922748 0.184438 + outer loop + vertex 599.888 109.408 96.6211 + vertex 600.2 109.044 94.2273 + vertex 601.214 110.436 99.3313 + endloop + endfacet + facet normal 0.335713 -0.923579 0.1852 + outer loop + vertex 601.614 108.916 91.0274 + vertex 601.214 110.436 99.3313 + vertex 600.2 109.044 94.2273 + endloop + endfacet + facet normal 0.348092 -0.917912 0.190444 + outer loop + vertex 600.2 109.044 94.2273 + vertex 600.092 108.246 90.579 + vertex 601.614 108.916 91.0274 + endloop + endfacet + facet normal 0.347563 -0.91778 0.19204 + outer loop + vertex 600.092 108.246 90.579 + vertex 600.388 107.852 88.1604 + vertex 601.614 108.916 91.0274 + endloop + endfacet + facet normal 0.331675 -0.921873 0.200353 + outer loop + vertex 600.388 107.852 88.1604 + vertex 600.686 107.45 85.8167 + vertex 601.614 108.916 91.0274 + endloop + endfacet + facet normal 0.330378 -0.922265 0.200694 + outer loop + vertex 602.073 107.29 82.8003 + vertex 601.614 108.916 91.0274 + vertex 600.686 107.45 85.8167 + endloop + endfacet + facet normal 0.343413 -0.916232 0.206367 + outer loop + vertex 600.686 107.45 85.8167 + vertex 600.538 106.555 82.0885 + vertex 602.073 107.29 82.8003 + endloop + endfacet + facet normal 0.342511 -0.916149 0.208226 + outer loop + vertex 600.538 106.555 82.0885 + vertex 600.799 106.106 79.6853 + vertex 602.073 107.29 82.8003 + endloop + endfacet + facet normal 0.323452 -0.920838 0.217801 + outer loop + vertex 600.799 106.106 79.6853 + vertex 601.174 105.706 77.4391 + vertex 602.073 107.29 82.8003 + endloop + endfacet + facet normal 0.32649 -0.919947 0.217028 + outer loop + vertex 602.875 105.778 75.1857 + vertex 602.073 107.29 82.8003 + vertex 601.174 105.706 77.4391 + endloop + endfacet + facet normal 0.339611 -0.912722 0.227161 + outer loop + vertex 601.174 105.706 77.4391 + vertex 601.227 104.663 73.1688 + vertex 602.875 105.778 75.1857 + endloop + endfacet + facet normal 0.33293 -0.913674 0.233148 + outer loop + vertex 601.227 104.663 73.1688 + vertex 602.067 103.986 69.3153 + vertex 602.875 105.778 75.1857 + endloop + endfacet + facet normal 0.326633 -0.915575 0.234594 + outer loop + vertex 604.057 104.31 67.8118 + vertex 602.875 105.778 75.1857 + vertex 602.067 103.986 69.3153 + endloop + endfacet + facet normal 0.33473 -0.909468 0.246625 + outer loop + vertex 602.067 103.986 69.3153 + vertex 602.81 102.647 63.3681 + vertex 604.057 104.31 67.8118 + endloop + endfacet + facet normal 0.316576 -0.914082 0.253444 + outer loop + vertex 605.09 102.158 58.7561 + vertex 604.057 104.31 67.8118 + vertex 602.81 102.647 63.3681 + endloop + endfacet + facet normal 0.317805 -0.913504 0.25399 + outer loop + vertex 602.81 102.647 63.3681 + vertex 603.494 101.556 58.5911 + vertex 605.09 102.158 58.7561 + endloop + endfacet + facet normal 0.31474 -0.909859 0.270363 + outer loop + vertex 603.494 101.556 58.5911 + vertex 604.291 100.336 53.5582 + vertex 605.09 102.158 58.7561 + endloop + endfacet + facet normal 0.29869 -0.914078 0.274311 + outer loop + vertex 605.266 100.024 51.4549 + vertex 605.09 102.158 58.7561 + vertex 604.291 100.336 53.5582 + endloop + endfacet + facet normal 0.307831 -0.909941 0.277935 + outer loop + vertex 604.773 99.5236 50.3623 + vertex 605.266 100.024 51.4549 + vertex 604.291 100.336 53.5582 + endloop + endfacet + facet normal -0.0851272 0.962481 -0.25765 + outer loop + vertex 604.291 100.336 53.5582 + vertex 605.166 99.1133 48.6998 + vertex 604.773 99.5236 50.3623 + endloop + endfacet + facet normal 0.295364 -0.908989 0.294108 + outer loop + vertex 605.75 98.9039 47.4661 + vertex 604.773 99.5236 50.3623 + vertex 605.166 99.1133 48.6998 + endloop + endfacet + facet normal 0.360219 -0.876519 0.319307 + outer loop + vertex 605.166 99.1133 48.6998 + vertex 606.588 98.1927 44.5686 + vertex 605.75 98.9039 47.4661 + endloop + endfacet + facet normal 0.28295 -0.913932 0.290978 + outer loop + vertex 605.75 98.9039 47.4661 + vertex 605.266 100.024 51.4549 + vertex 604.773 99.5236 50.3623 + endloop + endfacet + facet normal 0.310315 -0.904765 0.291727 + outer loop + vertex 606.952 99.149 46.9474 + vertex 605.266 100.024 51.4549 + vertex 605.75 98.9039 47.4661 + endloop + endfacet + facet normal 0.317458 -0.895195 0.312804 + outer loop + vertex 607.597 97.9861 42.965 + vertex 606.952 99.149 46.9474 + vertex 605.75 98.9039 47.4661 + endloop + endfacet + facet normal 0.30834 -0.899377 0.309916 + outer loop + vertex 607.597 97.9861 42.965 + vertex 605.75 98.9039 47.4661 + vertex 606.588 98.1927 44.5686 + endloop + endfacet + facet normal 0.32629 -0.891855 0.313258 + outer loop + vertex 608.986 98.2727 42.3345 + vertex 606.952 99.149 46.9474 + vertex 607.597 97.9861 42.965 + endloop + endfacet + facet normal 0.331927 -0.883975 0.329259 + outer loop + vertex 608.986 98.2727 42.3345 + vertex 607.597 97.9861 42.965 + vertex 609.035 97.4042 39.9537 + endloop + endfacet + facet normal 0.32192 -0.887295 0.330265 + outer loop + vertex 609.88 97.4782 39.3286 + vertex 608.986 98.2727 42.3345 + vertex 609.035 97.4042 39.9537 + endloop + endfacet + facet normal 0.334487 -0.875534 0.348653 + outer loop + vertex 610.098 97.0366 38.0103 + vertex 609.88 97.4782 39.3286 + vertex 609.035 97.4042 39.9537 + endloop + endfacet + facet normal 0.330211 -0.877905 0.346761 + outer loop + vertex 610.098 97.0366 38.0103 + vertex 609.035 97.4042 39.9537 + vertex 609.387 97.0078 38.6142 + endloop + endfacet + facet normal 0.344339 -0.865417 0.363983 + outer loop + vertex 610.337 96.7918 37.2026 + vertex 610.098 97.0366 38.0103 + vertex 609.387 97.0078 38.6142 + endloop + endfacet + facet normal 0.40476 -0.823195 0.398145 + outer loop + vertex 610.337 96.7918 37.2026 + vertex 609.387 97.0078 38.6142 + vertex 609.955 96.792 37.5907 + endloop + endfacet + facet normal 0.641532 0.43767 0.629986 + outer loop + vertex 611.015 96.7598 36.5343 + vertex 610.337 96.7918 37.2026 + vertex 609.955 96.792 37.5907 + endloop + endfacet + facet normal 0.370825 -0.839362 0.397442 + outer loop + vertex 609.955 96.792 37.5907 + vertex 611.235 96.4954 35.7707 + vertex 611.015 96.7598 36.5343 + endloop + endfacet + facet normal 0.324581 -0.860983 0.391606 + outer loop + vertex 612.287 97.2188 36.4888 + vertex 611.015 96.7598 36.5343 + vertex 611.235 96.4954 35.7707 + endloop + endfacet + facet normal 0.326887 -0.861435 0.388683 + outer loop + vertex 611.235 96.4954 35.7707 + vertex 614.542 98.094 36.5322 + vertex 612.287 97.2188 36.4888 + endloop + endfacet + facet normal 0.33024 -0.869066 0.368329 + outer loop + vertex 613.951 98.0227 36.8941 + vertex 612.287 97.2188 36.4888 + vertex 614.542 98.094 36.5322 + endloop + endfacet + facet normal 0.332984 -0.865829 0.373447 + outer loop + vertex 616.218 99.044 37.2407 + vertex 613.951 98.0227 36.8941 + vertex 614.542 98.094 36.5322 + endloop + endfacet + facet normal 0.336452 -0.867206 0.367089 + outer loop + vertex 614.542 98.094 36.5322 + vertex 618.058 99.7408 37.2 + vertex 616.218 99.044 37.2407 + endloop + endfacet + facet normal 0.336792 -0.868268 0.364256 + outer loop + vertex 619.07 100.415 37.8717 + vertex 616.218 99.044 37.2407 + vertex 618.058 99.7408 37.2 + endloop + endfacet + facet normal 0.341577 -0.869064 0.357844 + outer loop + vertex 618.058 99.7408 37.2 + vertex 620.693 101.051 37.8676 + vertex 619.07 100.415 37.8717 + endloop + endfacet + facet normal 0.342437 -0.871298 0.351534 + outer loop + vertex 621.565 101.641 38.4805 + vertex 619.07 100.415 37.8717 + vertex 620.693 101.051 37.8676 + endloop + endfacet + facet normal 0.34974 -0.872192 0.341998 + outer loop + vertex 620.693 101.051 37.8676 + vertex 623.04 102.239 38.4948 + vertex 621.565 101.641 38.4805 + endloop + endfacet + facet normal 0.349677 -0.872047 0.342432 + outer loop + vertex 623.04 102.239 38.4948 + vertex 624.859 103.481 39.8011 + vertex 621.565 101.641 38.4805 + endloop + endfacet + facet normal 0.345611 -0.870497 0.350411 + outer loop + vertex 621.059 101.789 39.3458 + vertex 621.565 101.641 38.4805 + vertex 624.859 103.481 39.8011 + endloop + endfacet + facet normal 0.350234 -0.875892 0.331887 + outer loop + vertex 624.859 103.481 39.8011 + vertex 623.485 103.708 41.8508 + vertex 621.059 101.789 39.3458 + endloop + endfacet + facet normal 0.345759 -0.875989 0.336295 + outer loop + vertex 621.059 101.789 39.3458 + vertex 623.485 103.708 41.8508 + vertex 620.443 102.364 41.4766 + endloop + endfacet + facet normal 0.342335 -0.87755 0.335727 + outer loop + vertex 621.059 101.789 39.3458 + vertex 620.443 102.364 41.4766 + vertex 618.915 100.949 39.336 + endloop + endfacet + facet normal 0.340776 -0.873705 0.347149 + outer loop + vertex 619.195 100.687 38.4022 + vertex 621.059 101.789 39.3458 + vertex 618.915 100.949 39.336 + endloop + endfacet + facet normal 0.342319 -0.872996 0.347413 + outer loop + vertex 619.195 100.687 38.4022 + vertex 618.915 100.949 39.336 + vertex 617.744 99.9894 38.079 + endloop + endfacet + facet normal 0.335952 -0.868103 0.365423 + outer loop + vertex 619.195 100.687 38.4022 + vertex 617.744 99.9894 38.079 + vertex 619.07 100.415 37.8717 + endloop + endfacet + facet normal 0.33889 -0.873043 0.350641 + outer loop + vertex 617.744 99.9894 38.079 + vertex 618.915 100.949 39.336 + vertex 616.957 100.096 39.1045 + endloop + endfacet + facet normal 0.33965 -0.872534 0.351172 + outer loop + vertex 617.744 99.9894 38.079 + vertex 616.957 100.096 39.1045 + vertex 616.195 99.334 37.9491 + endloop + endfacet + facet normal 0.336379 -0.867725 0.365928 + outer loop + vertex 616.195 99.334 37.9491 + vertex 616.218 99.044 37.2407 + vertex 617.744 99.9894 38.079 + endloop + endfacet + facet normal 0.335762 -0.867935 0.365995 + outer loop + vertex 616.195 99.334 37.9491 + vertex 614.831 98.6718 37.6303 + vertex 616.218 99.044 37.2407 + endloop + endfacet + facet normal 0.339758 -0.870911 0.355074 + outer loop + vertex 616.195 99.334 37.9491 + vertex 615.278 99.3247 38.8036 + vertex 614.831 98.6718 37.6303 + endloop + endfacet + facet normal 0.335806 -0.871658 0.356997 + outer loop + vertex 614.831 98.6718 37.6303 + vertex 615.278 99.3247 38.8036 + vertex 613.881 98.6953 38.5808 + endloop + endfacet + facet normal 0.336329 -0.871246 0.357509 + outer loop + vertex 614.831 98.6718 37.6303 + vertex 613.881 98.6953 38.5808 + vertex 613.59 98.1561 37.5408 + endloop + endfacet + facet normal 0.334587 -0.868488 0.365761 + outer loop + vertex 613.59 98.1561 37.5408 + vertex 613.951 98.0227 36.8941 + vertex 614.831 98.6718 37.6303 + endloop + endfacet + facet normal 0.331452 -0.870268 0.36438 + outer loop + vertex 613.59 98.1561 37.5408 + vertex 612.64 97.6557 37.2093 + vertex 613.951 98.0227 36.8941 + endloop + endfacet + facet normal 0.333808 -0.871438 0.359398 + outer loop + vertex 613.59 98.1561 37.5408 + vertex 612.696 98.1529 38.3632 + vertex 612.64 97.6557 37.2093 + endloop + endfacet + facet normal 0.328957 -0.872922 0.360271 + outer loop + vertex 612.64 97.6557 37.2093 + vertex 612.696 98.1529 38.3632 + vertex 611.684 97.6739 38.1269 + endloop + endfacet + facet normal 0.328228 -0.873504 0.359522 + outer loop + vertex 612.64 97.6557 37.2093 + vertex 611.684 97.6739 38.1269 + vertex 611.702 97.2524 37.0858 + endloop + endfacet + facet normal 0.325914 -0.870767 0.368165 + outer loop + vertex 611.702 97.2524 37.0858 + vertex 612.287 97.2188 36.4888 + vertex 612.64 97.6557 37.2093 + endloop + endfacet + facet normal 0.323355 -0.872728 0.36577 + outer loop + vertex 611.702 97.2524 37.0858 + vertex 611.063 96.9458 36.9198 + vertex 612.287 97.2188 36.4888 + endloop + endfacet + facet normal 0.325405 -0.874155 0.360505 + outer loop + vertex 611.702 97.2524 37.0858 + vertex 610.836 97.2814 37.9377 + vertex 611.063 96.9458 36.9198 + endloop + endfacet + facet normal 0.325253 -0.874217 0.360492 + outer loop + vertex 611.063 96.9458 36.9198 + vertex 610.836 97.2814 37.9377 + vertex 610.098 97.0366 38.0103 + endloop + endfacet + facet normal 0.324807 -0.874622 0.359913 + outer loop + vertex 611.702 97.2524 37.0858 + vertex 611.684 97.6739 38.1269 + vertex 610.836 97.2814 37.9377 + endloop + endfacet + facet normal 0.32924 -0.87808 0.347241 + outer loop + vertex 611.684 97.6739 38.1269 + vertex 610.617 97.9118 39.74 + vertex 610.836 97.2814 37.9377 + endloop + endfacet + facet normal 0.323871 -0.880059 0.34728 + outer loop + vertex 610.836 97.2814 37.9377 + vertex 610.617 97.9118 39.74 + vertex 609.88 97.4782 39.3286 + endloop + endfacet + facet normal 0.332964 -0.875828 0.349372 + outer loop + vertex 611.684 97.6739 38.1269 + vertex 611.694 98.2581 39.5821 + vertex 610.617 97.9118 39.74 + endloop + endfacet + facet normal 0.332616 -0.882803 0.331702 + outer loop + vertex 611.694 98.2581 39.5821 + vertex 610.952 99.0289 42.3773 + vertex 610.617 97.9118 39.74 + endloop + endfacet + facet normal 0.332375 -0.882871 0.331762 + outer loop + vertex 610.952 99.0289 42.3773 + vertex 608.986 98.2727 42.3345 + vertex 610.617 97.9118 39.74 + endloop + endfacet + facet normal 0.334839 -0.888293 0.314354 + outer loop + vertex 610.952 99.0289 42.3773 + vertex 608.84 99.7322 46.6139 + vertex 608.986 98.2727 42.3345 + endloop + endfacet + facet normal 0.335491 -0.887952 0.314622 + outer loop + vertex 610.952 99.0289 42.3773 + vertex 611.23 100.662 46.6895 + vertex 608.84 99.7322 46.6139 + endloop + endfacet + facet normal 0.338119 -0.893222 0.296361 + outer loop + vertex 611.23 100.662 46.6895 + vertex 609.426 101.297 50.6611 + vertex 608.84 99.7322 46.6139 + endloop + endfacet + facet normal 0.340543 -0.892509 0.295734 + outer loop + vertex 608.84 99.7322 46.6139 + vertex 609.426 101.297 50.6611 + vertex 607.102 100.796 51.8246 + endloop + endfacet + facet normal 0.329091 -0.8977 0.292974 + outer loop + vertex 608.84 99.7322 46.6139 + vertex 607.102 100.796 51.8246 + vertex 606.952 99.149 46.9474 + endloop + endfacet + facet normal 0.333546 -0.900747 0.278211 + outer loop + vertex 609.426 101.297 50.6611 + vertex 609.615 103.454 57.4202 + vertex 607.102 100.796 51.8246 + endloop + endfacet + facet normal 0.339082 -0.899609 0.275185 + outer loop + vertex 609.615 103.454 57.4202 + vertex 605.09 102.158 58.7561 + vertex 607.102 100.796 51.8246 + endloop + endfacet + facet normal 0.335858 -0.905821 0.258238 + outer loop + vertex 609.615 103.454 57.4202 + vertex 607.875 105.35 66.3323 + vertex 605.09 102.158 58.7561 + endloop + endfacet + facet normal 0.353409 -0.898575 0.260124 + outer loop + vertex 609.615 103.454 57.4202 + vertex 613.402 107.447 66.066 + vertex 607.875 105.35 66.3323 + endloop + endfacet + facet normal 0.354236 -0.902842 0.243708 + outer loop + vertex 613.402 107.447 66.066 + vertex 612.013 109.128 74.3131 + vertex 607.875 105.35 66.3323 + endloop + endfacet + facet normal 0.358906 -0.901781 0.240785 + outer loop + vertex 607.875 105.35 66.3323 + vertex 612.013 109.128 74.3131 + vertex 606.729 107.082 74.5261 + endloop + endfacet + facet normal 0.340424 -0.909189 0.239765 + outer loop + vertex 607.875 105.35 66.3323 + vertex 606.729 107.082 74.5261 + vertex 604.057 104.31 67.8118 + endloop + endfacet + facet normal 0.359716 -0.905508 0.225078 + outer loop + vertex 612.013 109.128 74.3131 + vertex 611.187 110.789 82.3163 + vertex 606.729 107.082 74.5261 + endloop + endfacet + facet normal 0.36496 -0.904291 0.221498 + outer loop + vertex 606.729 107.082 74.5261 + vertex 611.187 110.789 82.3163 + vertex 605.964 108.69 82.3513 + endloop + endfacet + facet normal 0.346195 -0.911715 0.221189 + outer loop + vertex 606.729 107.082 74.5261 + vertex 605.964 108.69 82.3513 + vertex 602.875 105.778 75.1857 + endloop + endfacet + facet normal 0.36603 -0.907187 0.207443 + outer loop + vertex 611.187 110.789 82.3163 + vertex 610.711 112.418 90.2792 + vertex 605.964 108.69 82.3513 + endloop + endfacet + facet normal 0.371299 -0.905898 0.203682 + outer loop + vertex 605.964 108.69 82.3513 + vertex 610.711 112.418 90.2792 + vertex 605.505 110.295 90.3258 + endloop + endfacet + facet normal 0.35212 -0.913431 0.204095 + outer loop + vertex 605.964 108.69 82.3513 + vertex 605.505 110.295 90.3258 + vertex 602.073 107.29 82.8003 + endloop + endfacet + facet normal 0.372151 -0.90826 0.191228 + outer loop + vertex 610.711 112.418 90.2792 + vertex 610.369 113.962 98.2784 + vertex 605.505 110.295 90.3258 + endloop + endfacet + facet normal 0.376733 -0.907069 0.187877 + outer loop + vertex 605.505 110.295 90.3258 + vertex 610.369 113.962 98.2784 + vertex 605.12 111.811 98.4207 + endloop + endfacet + facet normal 0.357989 -0.914525 0.188383 + outer loop + vertex 605.505 110.295 90.3258 + vertex 605.12 111.811 98.4207 + vertex 601.614 108.916 91.0274 + endloop + endfacet + facet normal 0.377345 -0.90943 0.174779 + outer loop + vertex 610.369 113.962 98.2784 + vertex 610.088 115.378 106.254 + vertex 605.12 111.811 98.4207 + endloop + endfacet + facet normal 0.381934 -0.908176 0.171297 + outer loop + vertex 605.12 111.811 98.4207 + vertex 610.088 115.378 106.254 + vertex 604.849 113.212 106.451 + endloop + endfacet + facet normal 0.362667 -0.915909 0.171996 + outer loop + vertex 605.12 111.811 98.4207 + vertex 604.849 113.212 106.451 + vertex 601.214 110.436 99.3313 + endloop + endfacet + facet normal 0.38239 -0.910596 0.156822 + outer loop + vertex 610.088 115.378 106.254 + vertex 609.853 116.644 114.174 + vertex 604.849 113.212 106.451 + endloop + endfacet + facet normal 0.387004 -0.909256 0.153238 + outer loop + vertex 604.849 113.212 106.451 + vertex 609.853 116.644 114.174 + vertex 604.648 114.459 114.359 + endloop + endfacet + facet normal 0.368142 -0.916932 0.153969 + outer loop + vertex 604.849 113.212 106.451 + vertex 604.648 114.459 114.359 + vertex 601.119 111.858 107.308 + endloop + endfacet + facet normal 0.38742 -0.911567 0.137661 + outer loop + vertex 609.853 116.644 114.174 + vertex 609.677 117.769 122.125 + vertex 604.648 114.459 114.359 + endloop + endfacet + facet normal 0.391246 -0.910378 0.134677 + outer loop + vertex 604.648 114.459 114.359 + vertex 609.677 117.769 122.125 + vertex 604.481 115.568 122.34 + endloop + endfacet + facet normal 0.372284 -0.918194 0.135367 + outer loop + vertex 604.648 114.459 114.359 + vertex 604.481 115.568 122.34 + vertex 600.748 112.96 114.913 + endloop + endfacet + facet normal 0.391488 -0.912547 0.118301 + outer loop + vertex 609.677 117.769 122.125 + vertex 609.551 118.759 130.174 + vertex 604.481 115.568 122.34 + endloop + endfacet + facet normal 0.394418 -0.911579 0.11601 + outer loop + vertex 604.481 115.568 122.34 + vertex 609.551 118.759 130.174 + vertex 604.362 116.545 130.419 + endloop + endfacet + facet normal 0.374707 -0.919768 0.116711 + outer loop + vertex 604.481 115.568 122.34 + vertex 604.362 116.545 130.419 + vertex 600.622 114.1 123.16 + endloop + endfacet + facet normal 0.394464 -0.913586 0.098787 + outer loop + vertex 609.551 118.759 130.174 + vertex 609.426 119.581 138.275 + vertex 604.362 116.545 130.419 + endloop + endfacet + facet normal 0.397211 -0.912624 0.0966443 + outer loop + vertex 604.362 116.545 130.419 + vertex 609.426 119.581 138.275 + vertex 604.246 117.345 138.457 + endloop + endfacet + facet normal 0.378278 -0.920579 0.0971624 + outer loop + vertex 604.362 116.545 130.419 + vertex 604.246 117.345 138.457 + vertex 600.719 115.139 131.28 + endloop + endfacet + facet normal 0.397305 -0.914311 0.0786424 + outer loop + vertex 609.426 119.581 138.275 + vertex 609.328 120.238 146.416 + vertex 604.246 117.345 138.457 + endloop + endfacet + facet normal 0.399736 -0.913411 0.0767635 + outer loop + vertex 604.246 117.345 138.457 + vertex 609.328 120.238 146.416 + vertex 604.114 117.973 146.612 + endloop + endfacet + facet normal 0.380874 -0.921409 0.077074 + outer loop + vertex 604.246 117.345 138.457 + vertex 604.114 117.973 146.612 + vertex 600.397 115.793 138.924 + endloop + endfacet + facet normal 0.399651 -0.91481 0.0583212 + outer loop + vertex 609.328 120.238 146.416 + vertex 609.243 120.723 154.596 + vertex 604.114 117.973 146.612 + endloop + endfacet + facet normal 0.401205 -0.914206 0.057115 + outer loop + vertex 604.114 117.973 146.612 + vertex 609.243 120.723 154.596 + vertex 604.019 118.451 154.929 + endloop + endfacet + facet normal 0.381713 -0.922499 0.0573687 + outer loop + vertex 604.114 117.973 146.612 + vertex 604.019 118.451 154.929 + vertex 600.259 116.428 147.414 + endloop + endfacet + facet normal 0.400534 -0.915506 0.0377063 + outer loop + vertex 609.243 120.723 154.596 + vertex 609.187 121.035 162.762 + vertex 604.019 118.451 154.929 + endloop + endfacet + facet normal 0.402151 -0.914849 0.0364227 + outer loop + vertex 604.019 118.451 154.929 + vertex 609.187 121.035 162.762 + vertex 604.012 118.776 163.165 + endloop + endfacet + facet normal 0.381967 -0.923445 0.0367458 + outer loop + vertex 604.019 118.451 154.929 + vertex 604.012 118.776 163.165 + vertex 600.188 116.908 155.973 + endloop + endfacet + facet normal 0.401046 -0.915913 0.0162741 + outer loop + vertex 609.187 121.035 162.762 + vertex 609.179 121.175 170.867 + vertex 604.012 118.776 163.165 + endloop + endfacet + facet normal 0.402022 -0.915499 0.0154904 + outer loop + vertex 604.012 118.776 163.165 + vertex 609.179 121.175 170.867 + vertex 604.002 118.908 171.207 + endloop + endfacet + facet normal 0.38363 -0.923355 0.0155961 + outer loop + vertex 604.012 118.776 163.165 + vertex 604.002 118.908 171.207 + vertex 600.387 117.287 164.18 + endloop + endfacet + facet normal 0.400917 -0.916099 -0.00535904 + outer loop + vertex 609.179 121.175 170.867 + vertex 609.187 121.131 178.946 + vertex 604.002 118.908 171.207 + endloop + endfacet + facet normal 0.401712 -0.915746 -0.00599325 + outer loop + vertex 604.002 118.908 171.207 + vertex 609.187 121.131 178.946 + vertex 604.024 118.864 179.256 + endloop + endfacet + facet normal 0.383278 -0.923614 -0.00598632 + outer loop + vertex 604.002 118.908 171.207 + vertex 604.024 118.864 179.256 + vertex 600.219 117.333 171.868 + endloop + endfacet + facet normal 0.400515 -0.915891 -0.0270407 + outer loop + vertex 609.187 121.131 178.946 + vertex 609.223 120.908 187.063 + vertex 604.024 118.864 179.256 + endloop + endfacet + facet normal 0.400161 -0.916054 -0.0267626 + outer loop + vertex 604.024 118.864 179.256 + vertex 609.223 120.908 187.063 + vertex 604.04 118.635 187.35 + endloop + endfacet + facet normal 0.38133 -0.924046 -0.0269522 + outer loop + vertex 604.024 118.864 179.256 + vertex 604.04 118.635 187.35 + vertex 600.224 117.272 180.102 + endloop + endfacet + facet normal 0.398797 -0.915736 -0.0488705 + outer loop + vertex 609.223 120.908 187.063 + vertex 609.277 120.496 195.203 + vertex 604.04 118.635 187.35 + endloop + endfacet + facet normal 0.398331 -0.915958 -0.0485076 + outer loop + vertex 604.04 118.635 187.35 + vertex 609.277 120.496 195.203 + vertex 604.073 118.223 195.41 + endloop + endfacet + facet normal 0.380805 -0.923366 -0.0488143 + outer loop + vertex 604.04 118.635 187.35 + vertex 604.073 118.223 195.41 + vertex 600.396 117.09 188.146 + endloop + endfacet + facet normal 0.397026 -0.915038 -0.0712425 + outer loop + vertex 609.277 120.496 195.203 + vertex 609.351 119.894 203.352 + vertex 604.073 118.223 195.41 + endloop + endfacet + facet normal 0.396255 -0.915418 -0.0706509 + outer loop + vertex 604.073 118.223 195.41 + vertex 609.351 119.894 203.352 + vertex 604.15 117.626 203.577 + endloop + endfacet + facet normal 0.379113 -0.922621 -0.0710156 + outer loop + vertex 604.073 118.223 195.41 + vertex 604.15 117.626 203.577 + vertex 600.22 116.605 195.852 + endloop + endfacet + facet normal 0.394639 -0.914021 -0.0939479 + outer loop + vertex 609.351 119.894 203.352 + vertex 609.483 119.112 211.513 + vertex 604.15 117.626 203.577 + endloop + endfacet + facet normal 0.392784 -0.914965 -0.0925243 + outer loop + vertex 604.15 117.626 203.577 + vertex 609.483 119.112 211.513 + vertex 604.292 116.846 211.886 + endloop + endfacet + facet normal 0.375055 -0.922335 -0.0929126 + outer loop + vertex 604.15 117.626 203.577 + vertex 604.292 116.846 211.886 + vertex 600.349 116.005 204.323 + endloop + endfacet + facet normal 0.390371 -0.913311 -0.116073 + outer loop + vertex 609.483 119.112 211.513 + vertex 609.637 118.149 219.611 + vertex 604.292 116.846 211.886 + endloop + endfacet + facet normal 0.388759 -0.914158 -0.114814 + outer loop + vertex 604.292 116.846 211.886 + vertex 609.637 118.149 219.611 + vertex 604.481 115.899 220.072 + endloop + endfacet + facet normal 0.370541 -0.921637 -0.115259 + outer loop + vertex 604.292 116.846 211.886 + vertex 604.481 115.899 220.072 + vertex 600.545 115.185 213.121 + endloop + endfacet + facet normal 0.385928 -0.912264 -0.13724 + outer loop + vertex 609.637 118.149 219.611 + vertex 609.815 117.022 227.604 + vertex 604.481 115.899 220.072 + endloop + endfacet + facet normal 0.384066 -0.913269 -0.135772 + outer loop + vertex 604.481 115.899 220.072 + vertex 609.815 117.022 227.604 + vertex 604.631 114.776 228.043 + endloop + endfacet + facet normal 0.399658 -0.906411 -0.136722 + outer loop + vertex 609.637 118.149 219.611 + vertex 616.158 119.816 227.618 + vertex 609.815 117.022 227.604 + endloop + endfacet + facet normal 0.398357 -0.903345 -0.158994 + outer loop + vertex 616.158 119.816 227.618 + vertex 616.381 118.523 235.525 + vertex 609.815 117.022 227.604 + endloop + endfacet + facet normal 0.394204 -0.905844 -0.155078 + outer loop + vertex 609.815 117.022 227.604 + vertex 616.381 118.523 235.525 + vertex 610.047 115.764 235.544 + endloop + endfacet + facet normal 0.412691 -0.896999 -0.15836 + outer loop + vertex 616.158 119.816 227.618 + vertex 623.249 121.659 235.659 + vertex 616.381 118.523 235.525 + endloop + endfacet + facet normal 0.411493 -0.893448 -0.18007 + outer loop + vertex 623.249 121.659 235.659 + vertex 623.561 120.232 243.455 + vertex 616.381 118.523 235.525 + endloop + endfacet + facet normal 0.405953 -0.897126 -0.174262 + outer loop + vertex 616.381 118.523 235.525 + vertex 623.561 120.232 243.455 + vertex 616.707 117.146 243.372 + endloop + endfacet + facet normal 0.42828 -0.885675 -0.179319 + outer loop + vertex 623.249 121.659 235.659 + vertex 630.386 123.526 243.486 + vertex 623.561 120.232 243.455 + endloop + endfacet + facet normal 0.426524 -0.881834 -0.201111 + outer loop + vertex 630.386 123.526 243.486 + vertex 630.828 121.995 251.137 + vertex 623.561 120.232 243.455 + endloop + endfacet + facet normal 0.419859 -0.88668 -0.193695 + outer loop + vertex 623.561 120.232 243.455 + vertex 630.828 121.995 251.137 + vertex 624.005 118.759 251.162 + endloop + endfacet + facet normal 0.445573 -0.872539 -0.200351 + outer loop + vertex 630.386 123.526 243.486 + vertex 637.345 125.347 251.029 + vertex 630.828 121.995 251.137 + endloop + endfacet + facet normal 0.442866 -0.868049 -0.224414 + outer loop + vertex 637.345 125.347 251.029 + vertex 638.008 123.742 258.548 + vertex 630.828 121.995 251.137 + endloop + endfacet + facet normal 0.434681 -0.874556 -0.21495 + outer loop + vertex 630.828 121.995 251.137 + vertex 638.008 123.742 258.548 + vertex 631.452 120.444 258.709 + endloop + endfacet + facet normal 0.463202 -0.85749 -0.223953 + outer loop + vertex 637.345 125.347 251.029 + vertex 644.192 127.123 258.393 + vertex 638.008 123.742 258.548 + endloop + endfacet + facet normal 0.459244 -0.851574 -0.252817 + outer loop + vertex 644.192 127.123 258.393 + vertex 645.165 125.448 265.803 + vertex 638.008 123.742 258.548 + endloop + endfacet + facet normal 0.448973 -0.86055 -0.240575 + outer loop + vertex 638.008 123.742 258.548 + vertex 645.165 125.448 265.803 + vertex 638.886 122.108 266.032 + endloop + endfacet + facet normal 0.481413 -0.839206 -0.252933 + outer loop + vertex 644.192 127.123 258.393 + vertex 651.052 128.87 265.654 + vertex 645.165 125.448 265.803 + endloop + endfacet + facet normal 0.475875 -0.831189 -0.287519 + outer loop + vertex 651.052 128.87 265.654 + vertex 652.337 127.102 272.892 + vertex 645.165 125.448 265.803 + endloop + endfacet + facet normal 0.463303 -0.843445 -0.271939 + outer loop + vertex 645.165 125.448 265.803 + vertex 652.337 127.102 272.892 + vertex 646.309 123.706 273.153 + endloop + endfacet + facet normal 0.501859 -0.815489 -0.288297 + outer loop + vertex 651.052 128.87 265.654 + vertex 657.924 130.618 272.674 + vertex 652.337 127.102 272.892 + endloop + endfacet + facet normal 0.494046 -0.805494 -0.327258 + outer loop + vertex 657.924 130.618 272.674 + vertex 659.394 128.734 279.529 + vertex 652.337 127.102 272.892 + endloop + endfacet + facet normal 0.479571 -0.821719 -0.307877 + outer loop + vertex 652.337 127.102 272.892 + vertex 659.394 128.734 279.529 + vertex 653.595 125.228 279.853 + endloop + endfacet + facet normal 0.471028 -0.811166 -0.346616 + outer loop + vertex 659.394 128.734 279.529 + vertex 660.453 126.712 285.7 + vertex 653.595 125.228 279.853 + endloop + endfacet + facet normal 0.495977 -0.796397 -0.346061 + outer loop + vertex 659.394 128.734 279.529 + vertex 666.228 130.463 285.345 + vertex 660.453 126.712 285.7 + endloop + endfacet + facet normal 0.512093 -0.774418 -0.371534 + outer loop + vertex 664.718 132.46 279.1 + vertex 666.228 130.463 285.345 + vertex 659.394 128.734 279.529 + endloop + endfacet + facet normal 0.541998 -0.753521 -0.372081 + outer loop + vertex 664.718 132.46 279.1 + vertex 671.764 134.714 284.8 + vertex 666.228 130.463 285.345 + endloop + endfacet + facet normal 0.552194 -0.736023 -0.391603 + outer loop + vertex 669.13 136.192 278.306 + vertex 671.764 134.714 284.8 + vertex 664.718 132.46 279.1 + endloop + endfacet + facet normal 0.523741 -0.786081 -0.328287 + outer loop + vertex 657.924 130.618 272.674 + vertex 664.718 132.46 279.1 + vertex 659.394 128.734 279.529 + endloop + endfacet + facet normal 0.534759 -0.7718 -0.34403 + outer loop + vertex 662.989 134.271 272.349 + vertex 664.718 132.46 279.1 + vertex 657.924 130.618 272.674 + endloop + endfacet + facet normal 0.544834 -0.782082 -0.302495 + outer loop + vertex 656.545 132.423 265.522 + vertex 662.989 134.271 272.349 + vertex 657.924 130.618 272.674 + endloop + endfacet + facet normal 0.554144 -0.770789 -0.314338 + outer loop + vertex 661.604 136.126 265.359 + vertex 662.989 134.271 272.349 + vertex 656.545 132.423 265.522 + endloop + endfacet + facet normal 0.562233 -0.78009 -0.274506 + outer loop + vertex 655.48 134.237 258.184 + vertex 661.604 136.126 265.359 + vertex 656.545 132.423 265.522 + endloop + endfacet + facet normal 0.528747 -0.802897 -0.275288 + outer loop + vertex 655.48 134.237 258.184 + vertex 656.545 132.423 265.522 + vertex 650.017 130.606 258.282 + endloop + endfacet + facet normal 0.534346 -0.810377 -0.240341 + outer loop + vertex 649.285 132.341 250.802 + vertex 655.48 134.237 258.184 + vertex 650.017 130.606 258.282 + endloop + endfacet + facet normal 0.504211 -0.82906 -0.241725 + outer loop + vertex 649.285 132.341 250.802 + vertex 650.017 130.606 258.282 + vertex 643.495 128.79 250.905 + endloop + endfacet + facet normal 0.508137 -0.834619 -0.21262 + outer loop + vertex 643.023 130.433 243.327 + vertex 649.285 132.341 250.802 + vertex 643.495 128.79 250.905 + endloop + endfacet + facet normal 0.481665 -0.849761 -0.214253 + outer loop + vertex 643.023 130.433 243.327 + vertex 643.495 128.79 250.905 + vertex 636.896 126.936 243.422 + endloop + endfacet + facet normal 0.484565 -0.854147 -0.188756 + outer loop + vertex 636.582 128.461 235.72 + vertex 643.023 130.433 243.327 + vertex 636.896 126.936 243.422 + endloop + endfacet + facet normal 0.460245 -0.867148 -0.19034 + outer loop + vertex 636.582 128.461 235.72 + vertex 636.896 126.936 243.422 + vertex 630.075 125.004 235.733 + endloop + endfacet + facet normal 0.462337 -0.870998 -0.166151 + outer loop + vertex 629.841 126.376 227.891 + vertex 636.582 128.461 235.72 + vertex 630.075 125.004 235.733 + endloop + endfacet + facet normal 0.440323 -0.882089 -0.167436 + outer loop + vertex 629.841 126.376 227.891 + vertex 630.075 125.004 235.733 + vertex 623.016 122.99 227.777 + endloop + endfacet + facet normal 0.441714 -0.885722 -0.142776 + outer loop + vertex 622.828 124.181 219.814 + vertex 629.841 126.376 227.891 + vertex 623.016 122.99 227.777 + endloop + endfacet + facet normal 0.422669 -0.894821 -0.143687 + outer loop + vertex 622.828 124.181 219.814 + vertex 623.016 122.99 227.777 + vertex 615.971 120.97 219.637 + endloop + endfacet + facet normal 0.423557 -0.898123 -0.118214 + outer loop + vertex 615.814 121.957 211.572 + vertex 622.828 124.181 219.814 + vertex 615.971 120.97 219.637 + endloop + endfacet + facet normal 0.40791 -0.905262 -0.118782 + outer loop + vertex 615.814 121.957 211.572 + vertex 615.971 120.97 219.637 + vertex 609.483 119.112 211.513 + endloop + endfacet + facet normal 0.427188 -0.895907 -0.121902 + outer loop + vertex 622.672 125.201 211.77 + vertex 622.828 124.181 219.814 + vertex 615.814 121.957 211.572 + endloop + endfacet + facet normal 0.427801 -0.898813 -0.095506 + outer loop + vertex 615.697 122.765 203.447 + vertex 622.672 125.201 211.77 + vertex 615.814 121.957 211.572 + endloop + endfacet + facet normal 0.411458 -0.906357 -0.0960208 + outer loop + vertex 615.697 122.765 203.447 + vertex 615.814 121.957 211.572 + vertex 609.351 119.894 203.352 + endloop + endfacet + facet normal 0.431115 -0.896865 -0.0988539 + outer loop + vertex 622.548 126.034 203.666 + vertex 622.672 125.201 211.77 + vertex 615.697 122.765 203.447 + endloop + endfacet + facet normal 0.431407 -0.899229 -0.0726347 + outer loop + vertex 615.604 123.379 195.294 + vertex 622.548 126.034 203.666 + vertex 615.697 122.765 203.447 + endloop + endfacet + facet normal 0.414339 -0.907187 -0.0730397 + outer loop + vertex 615.604 123.379 195.294 + vertex 615.697 122.765 203.447 + vertex 609.277 120.496 195.203 + endloop + endfacet + facet normal 0.434148 -0.897681 -0.0753984 + outer loop + vertex 622.454 126.672 195.534 + vertex 622.548 126.034 203.666 + vertex 615.604 123.379 195.294 + endloop + endfacet + facet normal 0.434115 -0.899472 -0.0499458 + outer loop + vertex 615.546 123.803 187.148 + vertex 622.454 126.672 195.534 + vertex 615.604 123.379 195.294 + endloop + endfacet + facet normal 0.416428 -0.907779 -0.0502531 + outer loop + vertex 615.546 123.803 187.148 + vertex 615.604 123.379 195.294 + vertex 609.223 120.908 187.063 + endloop + endfacet + facet normal 0.436507 -0.898176 -0.052359 + outer loop + vertex 622.389 127.113 187.415 + vertex 622.454 126.672 195.534 + vertex 615.546 123.803 187.148 + endloop + endfacet + facet normal 0.436163 -0.899434 -0.0279279 + outer loop + vertex 615.508 124.037 179.036 + vertex 622.389 127.113 187.415 + vertex 615.546 123.803 187.148 + endloop + endfacet + facet normal 0.417802 -0.908104 -0.0280906 + outer loop + vertex 615.508 124.037 179.036 + vertex 615.546 123.803 187.148 + vertex 609.187 121.131 178.946 + endloop + endfacet + facet normal 0.437918 -0.898524 -0.0297033 + outer loop + vertex 622.356 127.364 179.334 + vertex 622.389 127.113 187.415 + vertex 615.508 124.037 179.036 + endloop + endfacet + facet normal 0.437269 -0.899311 -0.00599781 + outer loop + vertex 615.5 124.087 170.959 + vertex 622.356 127.364 179.334 + vertex 615.508 124.037 179.036 + endloop + endfacet + facet normal 0.418442 -0.908224 -0.00603485 + outer loop + vertex 615.5 124.087 170.959 + vertex 615.508 124.037 179.036 + vertex 609.179 121.175 170.867 + endloop + endfacet + facet normal 0.438576 -0.898664 -0.00732083 + outer loop + vertex 622.348 127.426 171.283 + vertex 622.356 127.364 179.334 + vertex 615.5 124.087 170.959 + endloop + endfacet + facet normal 0.437645 -0.899008 0.0158832 + outer loop + vertex 615.53 123.959 162.881 + vertex 622.348 127.426 171.283 + vertex 615.5 124.087 170.959 + endloop + endfacet + facet normal 0.418346 -0.908148 0.0159564 + outer loop + vertex 615.53 123.959 162.881 + vertex 615.5 124.087 170.959 + vertex 609.187 121.035 162.762 + endloop + endfacet + facet normal 0.438551 -0.898582 0.014972 + outer loop + vertex 622.366 127.301 163.229 + vertex 622.348 127.426 171.283 + vertex 615.53 123.959 162.881 + endloop + endfacet + facet normal 0.437378 -0.898505 0.0372593 + outer loop + vertex 615.575 123.644 154.767 + vertex 622.366 127.301 163.229 + vertex 615.53 123.959 162.881 + endloop + endfacet + facet normal 0.417793 -0.907768 0.0375092 + outer loop + vertex 615.575 123.644 154.767 + vertex 615.53 123.959 162.881 + vertex 609.243 120.723 154.596 + endloop + endfacet + facet normal 0.437695 -0.898364 0.036944 + outer loop + vertex 622.408 126.989 155.141 + vertex 622.366 127.301 163.229 + vertex 615.575 123.644 154.767 + endloop + endfacet + facet normal 0.436309 -0.897912 0.0582146 + outer loop + vertex 615.65 123.153 146.627 + vertex 622.408 126.989 155.141 + vertex 615.575 123.644 154.767 + endloop + endfacet + facet normal 0.416313 -0.907331 0.0585981 + outer loop + vertex 615.65 123.153 146.627 + vertex 615.575 123.644 154.767 + vertex 609.328 120.238 146.416 + endloop + endfacet + facet normal 0.435917 -0.898077 0.0586004 + outer loop + vertex 622.477 126.492 147.015 + vertex 622.408 126.989 155.141 + vertex 615.65 123.153 146.627 + endloop + endfacet + facet normal 0.434371 -0.897272 0.0789008 + outer loop + vertex 615.744 122.482 138.483 + vertex 622.477 126.492 147.015 + vertex 615.65 123.153 146.627 + endloop + endfacet + facet normal 0.413845 -0.906873 0.0794559 + outer loop + vertex 615.744 122.482 138.483 + vertex 615.65 123.153 146.627 + vertex 609.426 119.581 138.275 + endloop + endfacet + facet normal 0.433428 -0.897646 0.079821 + outer loop + vertex 622.573 125.815 138.881 + vertex 622.477 126.492 147.015 + vertex 615.744 122.482 138.483 + endloop + endfacet + facet normal 0.431759 -0.896528 0.0991051 + outer loop + vertex 615.858 121.641 130.376 + vertex 622.573 125.815 138.881 + vertex 615.744 122.482 138.483 + endloop + endfacet + facet normal 0.410908 -0.906196 0.0998155 + outer loop + vertex 615.858 121.641 130.376 + vertex 615.744 122.482 138.483 + vertex 609.551 118.759 130.174 + endloop + endfacet + facet normal 0.430033 -0.89717 0.100783 + outer loop + vertex 622.695 124.965 130.798 + vertex 622.573 125.815 138.881 + vertex 615.858 121.641 130.376 + endloop + endfacet + facet normal 0.428232 -0.895787 0.119093 + outer loop + vertex 616.009 120.648 122.364 + vertex 622.695 124.965 130.798 + vertex 615.858 121.641 130.376 + endloop + endfacet + facet normal 0.407104 -0.905478 0.119897 + outer loop + vertex 616.009 120.648 122.364 + vertex 615.858 121.641 130.376 + vertex 609.677 117.769 122.125 + endloop + endfacet + facet normal 0.425777 -0.896637 0.121474 + outer loop + vertex 622.845 123.955 122.813 + vertex 622.695 124.965 130.798 + vertex 616.009 120.648 122.364 + endloop + endfacet + facet normal 0.423839 -0.895011 0.138981 + outer loop + vertex 616.197 119.507 114.444 + vertex 622.845 123.955 122.813 + vertex 616.009 120.648 122.364 + endloop + endfacet + facet normal 0.402426 -0.904705 0.139867 + outer loop + vertex 616.197 119.507 114.444 + vertex 616.009 120.648 122.364 + vertex 609.853 116.644 114.174 + endloop + endfacet + facet normal 0.420875 -0.895961 0.14184 + outer loop + vertex 623.039 122.797 114.922 + vertex 622.845 123.955 122.813 + vertex 616.197 119.507 114.444 + endloop + endfacet + facet normal 0.418846 -0.894143 0.158353 + outer loop + vertex 616.432 118.22 106.552 + vertex 623.039 122.797 114.922 + vertex 616.197 119.507 114.444 + endloop + endfacet + facet normal 0.397295 -0.903763 0.15928 + outer loop + vertex 616.432 118.22 106.552 + vertex 616.197 119.507 114.444 + vertex 610.088 115.378 106.254 + endloop + endfacet + facet normal 0.415185 -0.895227 0.161834 + outer loop + vertex 623.275 121.485 107.06 + vertex 623.039 122.797 114.922 + vertex 616.432 118.22 106.552 + endloop + endfacet + facet normal 0.413221 -0.89338 0.176408 + outer loop + vertex 616.707 116.781 98.6264 + vertex 623.275 121.485 107.06 + vertex 616.432 118.22 106.552 + endloop + endfacet + facet normal 0.39189 -0.902752 0.177371 + outer loop + vertex 616.707 116.781 98.6264 + vertex 616.432 118.22 106.552 + vertex 610.369 113.962 98.2784 + endloop + endfacet + facet normal 0.40935 -0.894442 0.180015 + outer loop + vertex 623.54 120.02 99.1774 + vertex 623.275 121.485 107.06 + vertex 616.707 116.781 98.6264 + endloop + endfacet + facet normal 0.407419 -0.892593 0.193101 + outer loop + vertex 617.03 115.208 90.6735 + vertex 623.54 120.02 99.1774 + vertex 616.707 116.781 98.6264 + endloop + endfacet + facet normal 0.386157 -0.90179 0.194056 + outer loop + vertex 617.03 115.208 90.6735 + vertex 616.707 116.781 98.6264 + vertex 610.711 112.418 90.2792 + endloop + endfacet + facet normal 0.40319 -0.893672 0.196949 + outer loop + vertex 623.848 118.418 91.2761 + vertex 623.54 120.02 99.1774 + vertex 617.03 115.208 90.6735 + endloop + endfacet + facet normal 0.401077 -0.89164 0.210036 + outer loop + vertex 617.5 113.546 82.7159 + vertex 623.848 118.418 91.2761 + vertex 617.03 115.208 90.6735 + endloop + endfacet + facet normal 0.379936 -0.900701 0.21068 + outer loop + vertex 617.5 113.546 82.7159 + vertex 617.03 115.208 90.6735 + vertex 611.187 110.789 82.3163 + endloop + endfacet + facet normal 0.396473 -0.892738 0.214075 + outer loop + vertex 624.312 116.728 83.3697 + vertex 623.848 118.418 91.2761 + vertex 617.5 113.546 82.7159 + endloop + endfacet + facet normal 0.393827 -0.890168 0.229131 + outer loop + vertex 618.383 111.877 74.717 + vertex 624.312 116.728 83.3697 + vertex 617.5 113.546 82.7159 + endloop + endfacet + facet normal 0.373508 -0.898986 0.228726 + outer loop + vertex 618.383 111.877 74.717 + vertex 617.5 113.546 82.7159 + vertex 612.013 109.128 74.3131 + endloop + endfacet + facet normal 0.389732 -0.891106 0.232463 + outer loop + vertex 625.192 115.038 75.4174 + vertex 624.312 116.728 83.3697 + vertex 618.383 111.877 74.717 + endloop + endfacet + facet normal 0.386567 -0.887979 0.249117 + outer loop + vertex 619.907 110.259 66.5854 + vertex 625.192 115.038 75.4174 + vertex 618.383 111.877 74.717 + endloop + endfacet + facet normal 0.367853 -0.896401 0.247286 + outer loop + vertex 619.907 110.259 66.5854 + vertex 618.383 111.877 74.717 + vertex 613.402 107.447 66.066 + endloop + endfacet + facet normal 0.365005 -0.892859 0.263769 + outer loop + vertex 615.511 105.801 57.5784 + vertex 619.907 110.259 66.5854 + vertex 613.402 107.447 66.066 + endloop + endfacet + facet normal 0.363096 -0.893297 0.264918 + outer loop + vertex 622.198 108.744 58.3344 + vertex 619.907 110.259 66.5854 + vertex 615.511 105.801 57.5784 + endloop + endfacet + facet normal 0.359467 -0.889478 0.282156 + outer loop + vertex 622.198 108.744 58.3344 + vertex 615.511 105.801 57.5784 + vertex 618.521 105.366 52.371 + endloop + endfacet + facet normal 0.356247 -0.89004 0.284459 + outer loop + vertex 621.909 106.612 52.0265 + vertex 622.198 108.744 58.3344 + vertex 618.521 105.366 52.371 + endloop + endfacet + facet normal 0.356079 -0.886661 0.295026 + outer loop + vertex 620.321 104.656 48.0636 + vertex 621.909 106.612 52.0265 + vertex 618.521 105.366 52.371 + endloop + endfacet + facet normal 0.350704 -0.889395 0.29323 + outer loop + vertex 620.321 104.656 48.0636 + vertex 618.521 105.366 52.371 + vertex 617.074 103.226 47.6121 + endloop + endfacet + facet normal 0.346903 -0.885644 0.308694 + outer loop + vertex 618.976 102.791 44.2239 + vertex 620.321 104.656 48.0636 + vertex 617.074 103.226 47.6121 + endloop + endfacet + facet normal 0.346296 -0.885986 0.308397 + outer loop + vertex 618.976 102.791 44.2239 + vertex 617.074 103.226 47.6121 + vertex 616.104 101.502 43.7461 + endloop + endfacet + facet normal 0.342281 -0.882393 0.32284 + outer loop + vertex 617.858 101.242 41.1768 + vertex 618.976 102.791 44.2239 + vertex 616.104 101.502 43.7461 + endloop + endfacet + facet normal 0.343665 -0.881541 0.323698 + outer loop + vertex 617.858 101.242 41.1768 + vertex 616.104 101.502 43.7461 + vertex 615.618 100.208 40.7384 + endloop + endfacet + facet normal 0.339145 -0.877868 0.338125 + outer loop + vertex 616.957 100.096 39.1045 + vertex 617.858 101.242 41.1768 + vertex 615.618 100.208 40.7384 + endloop + endfacet + facet normal 0.341466 -0.876275 0.339917 + outer loop + vertex 616.957 100.096 39.1045 + vertex 615.618 100.208 40.7384 + vertex 615.278 99.3247 38.8036 + endloop + endfacet + facet normal 0.334945 -0.878031 0.341866 + outer loop + vertex 615.278 99.3247 38.8036 + vertex 615.618 100.208 40.7384 + vertex 614.167 99.3782 40.029 + endloop + endfacet + facet normal 0.342239 -0.880026 0.329282 + outer loop + vertex 614.167 99.3782 40.029 + vertex 615.618 100.208 40.7384 + vertex 613.447 100.136 42.8017 + endloop + endfacet + facet normal 0.33827 -0.881766 0.328727 + outer loop + vertex 614.167 99.3782 40.029 + vertex 613.447 100.136 42.8017 + vertex 612.756 98.8746 40.1303 + endloop + endfacet + facet normal 0.337272 -0.875468 0.346126 + outer loop + vertex 613.881 98.6953 38.5808 + vertex 614.167 99.3782 40.029 + vertex 612.756 98.8746 40.1303 + endloop + endfacet + facet normal 0.337178 -0.875529 0.346064 + outer loop + vertex 613.881 98.6953 38.5808 + vertex 612.756 98.8746 40.1303 + vertex 612.696 98.1529 38.3632 + endloop + endfacet + facet normal 0.330062 -0.877777 0.347226 + outer loop + vertex 612.696 98.1529 38.3632 + vertex 612.756 98.8746 40.1303 + vertex 611.694 98.2581 39.5821 + endloop + endfacet + facet normal 0.335263 -0.882495 0.329849 + outer loop + vertex 613.447 100.136 42.8017 + vertex 610.952 99.0289 42.3773 + vertex 612.756 98.8746 40.1303 + endloop + endfacet + facet normal 0.338437 -0.883017 0.325178 + outer loop + vertex 616.104 101.502 43.7461 + vertex 613.447 100.136 42.8017 + vertex 615.618 100.208 40.7384 + endloop + endfacet + facet normal 0.344873 -0.885665 0.310903 + outer loop + vertex 616.104 101.502 43.7461 + vertex 614.028 101.877 47.1192 + vertex 613.447 100.136 42.8017 + endloop + endfacet + facet normal 0.337616 -0.88781 0.312745 + outer loop + vertex 613.447 100.136 42.8017 + vertex 614.028 101.877 47.1192 + vertex 611.23 100.662 46.6895 + endloop + endfacet + facet normal 0.342481 -0.892361 0.293937 + outer loop + vertex 614.028 101.877 47.1192 + vertex 612.168 102.648 51.6266 + vertex 611.23 100.662 46.6895 + endloop + endfacet + facet normal 0.346208 -0.890517 0.29516 + outer loop + vertex 614.028 101.877 47.1192 + vertex 615.214 103.673 51.1447 + vertex 612.168 102.648 51.6266 + endloop + endfacet + facet normal 0.345556 -0.895537 0.280364 + outer loop + vertex 615.214 103.673 51.1447 + vertex 615.511 105.801 57.5784 + vertex 612.168 102.648 51.6266 + endloop + endfacet + facet normal 0.348783 -0.894949 0.278239 + outer loop + vertex 615.511 105.801 57.5784 + vertex 609.615 103.454 57.4202 + vertex 612.168 102.648 51.6266 + endloop + endfacet + facet normal 0.34664 -0.890407 0.294983 + outer loop + vertex 617.074 103.226 47.6121 + vertex 615.214 103.673 51.1447 + vertex 614.028 101.877 47.1192 + endloop + endfacet + facet normal 0.345357 -0.88173 0.321373 + outer loop + vertex 620.443 102.364 41.4766 + vertex 618.976 102.791 44.2239 + vertex 617.858 101.242 41.1768 + endloop + endfacet + facet normal 0.346996 -0.880818 0.322107 + outer loop + vertex 620.443 102.364 41.4766 + vertex 622.077 104.155 44.615 + vertex 618.976 102.791 44.2239 + endloop + endfacet + facet normal 0.342712 -0.88692 0.309713 + outer loop + vertex 616.104 101.502 43.7461 + vertex 617.074 103.226 47.6121 + vertex 614.028 101.877 47.1192 + endloop + endfacet + facet normal 0.350647 -0.884773 0.306959 + outer loop + vertex 622.077 104.155 44.615 + vertex 620.321 104.656 48.0636 + vertex 618.976 102.791 44.2239 + endloop + endfacet + facet normal 0.353634 -0.883136 0.308243 + outer loop + vertex 622.077 104.155 44.615 + vertex 623.662 106.149 48.5078 + vertex 620.321 104.656 48.0636 + endloop + endfacet + facet normal 0.356224 -0.882564 0.306895 + outer loop + vertex 625.353 105.643 45.0902 + vertex 623.662 106.149 48.5078 + vertex 622.077 104.155 44.615 + endloop + endfacet + facet normal 0.352398 -0.878845 0.321632 + outer loop + vertex 623.485 103.708 41.8508 + vertex 625.353 105.643 45.0902 + vertex 622.077 104.155 44.615 + endloop + endfacet + facet normal 0.355819 -0.878304 0.319336 + outer loop + vertex 626.925 105.306 42.4128 + vertex 625.353 105.643 45.0902 + vertex 623.485 103.708 41.8508 + endloop + endfacet + facet normal 0.35903 -0.876395 0.320982 + outer loop + vertex 626.925 105.306 42.4128 + vertex 628.678 107.2 45.6234 + vertex 625.353 105.643 45.0902 + endloop + endfacet + facet normal 0.362827 -0.879773 0.307173 + outer loop + vertex 628.678 107.2 45.6234 + vertex 627.024 107.698 49.0039 + vertex 625.353 105.643 45.0902 + endloop + endfacet + facet normal 0.367922 -0.876927 0.309245 + outer loop + vertex 628.678 107.2 45.6234 + vertex 630.346 109.267 49.5013 + vertex 627.024 107.698 49.0039 + endloop + endfacet + facet normal 0.371143 -0.879832 0.296898 + outer loop + vertex 630.346 109.267 49.5013 + vertex 628.713 109.749 52.9709 + vertex 627.024 107.698 49.0039 + endloop + endfacet + facet normal 0.37082 -0.879909 0.297075 + outer loop + vertex 627.024 107.698 49.0039 + vertex 628.713 109.749 52.9709 + vertex 625.336 108.43 53.2772 + endloop + endfacet + facet normal 0.363768 -0.883571 0.294915 + outer loop + vertex 627.024 107.698 49.0039 + vertex 625.336 108.43 53.2772 + vertex 623.662 106.149 48.5078 + endloop + endfacet + facet normal 0.360892 -0.884296 0.296272 + outer loop + vertex 623.662 106.149 48.5078 + vertex 625.336 108.43 53.2772 + vertex 621.909 106.612 52.0265 + endloop + endfacet + facet normal 0.371091 -0.882472 0.289023 + outer loop + vertex 628.713 109.749 52.9709 + vertex 629.015 111.915 59.1951 + vertex 625.336 108.43 53.2772 + endloop + endfacet + facet normal 0.374046 -0.881928 0.286866 + outer loop + vertex 629.015 111.915 59.1951 + vertex 622.198 108.744 58.3344 + vertex 625.336 108.43 53.2772 + endloop + endfacet + facet normal 0.378037 -0.885749 0.269325 + outer loop + vertex 629.015 111.915 59.1951 + vertex 626.733 113.422 67.3549 + vertex 622.198 108.744 58.3344 + endloop + endfacet + facet normal 0.398422 -0.875585 0.273151 + outer loop + vertex 629.015 111.915 59.1951 + vertex 633.448 116.707 68.0915 + vertex 626.733 113.422 67.3549 + endloop + endfacet + facet normal 0.401931 -0.879018 0.256473 + outer loop + vertex 633.448 116.707 68.0915 + vertex 631.947 118.365 76.1232 + vertex 626.733 113.422 67.3549 + endloop + endfacet + facet normal 0.405908 -0.878037 0.253554 + outer loop + vertex 626.733 113.422 67.3549 + vertex 631.947 118.365 76.1232 + vertex 625.192 115.038 75.4174 + endloop + endfacet + facet normal 0.409153 -0.88113 0.237074 + outer loop + vertex 631.947 118.365 76.1232 + vertex 631.095 120.099 84.0414 + vertex 625.192 115.038 75.4174 + endloop + endfacet + facet normal 0.437877 -0.867203 0.237113 + outer loop + vertex 631.947 118.365 76.1232 + vertex 637.608 123.55 84.6323 + vertex 631.095 120.099 84.0414 + endloop + endfacet + facet normal 0.440568 -0.869752 0.222331 + outer loop + vertex 637.608 123.55 84.6323 + vertex 637.144 125.316 92.4612 + vertex 631.095 120.099 84.0414 + endloop + endfacet + facet normal 0.447183 -0.867867 0.216411 + outer loop + vertex 631.095 120.099 84.0414 + vertex 637.144 125.316 92.4612 + vertex 630.642 121.825 91.8994 + endloop + endfacet + facet normal 0.417052 -0.882386 0.217859 + outer loop + vertex 631.095 120.099 84.0414 + vertex 630.642 121.825 91.8994 + vertex 624.312 116.728 83.3697 + endloop + endfacet + facet normal 0.449337 -0.869832 0.20369 + outer loop + vertex 637.144 125.316 92.4612 + vertex 636.841 126.984 100.254 + vertex 630.642 121.825 91.8994 + endloop + endfacet + facet normal 0.455474 -0.867956 0.197977 + outer loop + vertex 630.642 121.825 91.8994 + vertex 636.841 126.984 100.254 + vertex 630.349 123.46 99.7429 + endloop + endfacet + facet normal 0.42459 -0.883027 0.199966 + outer loop + vertex 630.642 121.825 91.8994 + vertex 630.349 123.46 99.7429 + vertex 623.848 118.418 91.2761 + endloop + endfacet + facet normal 0.457389 -0.869687 0.185581 + outer loop + vertex 636.841 126.984 100.254 + vertex 636.576 128.506 108.037 + vertex 630.349 123.46 99.7429 + endloop + endfacet + facet normal 0.462385 -0.868044 0.18083 + outer loop + vertex 630.349 123.46 99.7429 + vertex 636.576 128.506 108.037 + vertex 630.088 124.954 107.577 + endloop + endfacet + facet normal 0.4313 -0.883507 0.182745 + outer loop + vertex 630.349 123.46 99.7429 + vertex 630.088 124.954 107.577 + vertex 623.54 120.02 99.1774 + endloop + endfacet + facet normal 0.464375 -0.869833 0.166571 + outer loop + vertex 636.576 128.506 108.037 + vertex 636.332 129.867 115.83 + vertex 630.088 124.954 107.577 + endloop + endfacet + facet normal 0.468471 -0.868385 0.162611 + outer loop + vertex 630.088 124.954 107.577 + vertex 636.332 129.867 115.83 + vertex 629.847 126.289 115.406 + endloop + endfacet + facet normal 0.437613 -0.884021 0.164325 + outer loop + vertex 630.088 124.954 107.577 + vertex 629.847 126.289 115.406 + vertex 623.275 121.485 107.06 + endloop + endfacet + facet normal 0.470546 -0.870194 0.146115 + outer loop + vertex 636.332 129.867 115.83 + vertex 636.124 131.071 123.671 + vertex 629.847 126.289 115.406 + endloop + endfacet + facet normal 0.47428 -0.868772 0.142457 + outer loop + vertex 629.847 126.289 115.406 + vertex 636.124 131.071 123.671 + vertex 629.648 127.471 123.274 + endloop + endfacet + facet normal 0.443597 -0.884574 0.144054 + outer loop + vertex 629.847 126.289 115.406 + vertex 629.648 127.471 123.274 + vertex 623.039 122.797 114.922 + endloop + endfacet + facet normal 0.476298 -0.870425 0.124503 + outer loop + vertex 636.124 131.071 123.671 + vertex 635.96 132.117 131.604 + vertex 629.648 127.471 123.274 + endloop + endfacet + facet normal 0.479285 -0.869201 0.121557 + outer loop + vertex 629.648 127.471 123.274 + vertex 635.96 132.117 131.604 + vertex 629.492 128.498 131.231 + endloop + endfacet + facet normal 0.449092 -0.884978 0.123003 + outer loop + vertex 629.648 127.471 123.274 + vertex 629.492 128.498 131.231 + vertex 622.845 123.955 122.813 + endloop + endfacet + facet normal 0.481179 -0.870618 0.102427 + outer loop + vertex 635.96 132.117 131.604 + vertex 635.841 132.996 139.633 + vertex 629.492 128.498 131.231 + endloop + endfacet + facet normal 0.483112 -0.86977 0.100513 + outer loop + vertex 629.492 128.498 131.231 + vertex 635.841 132.996 139.633 + vertex 629.369 129.36 139.287 + endloop + endfacet + facet normal 0.453655 -0.885352 0.10173 + outer loop + vertex 629.492 128.498 131.231 + vertex 629.369 129.36 139.287 + vertex 622.695 124.965 130.798 + endloop + endfacet + facet normal 0.484799 -0.870892 0.0807294 + outer loop + vertex 635.841 132.996 139.633 + vertex 635.743 133.691 147.719 + vertex 629.369 129.36 139.287 + endloop + endfacet + facet normal 0.48624 -0.87022 0.0792953 + outer loop + vertex 629.369 129.36 139.287 + vertex 635.743 133.691 147.719 + vertex 629.272 130.046 147.399 + endloop + endfacet + facet normal 0.457296 -0.885685 0.0802594 + outer loop + vertex 629.369 129.36 139.287 + vertex 629.272 130.046 147.399 + vertex 622.573 125.815 138.881 + endloop + endfacet + facet normal 0.487725 -0.871033 0.0585337 + outer loop + vertex 635.743 133.691 147.719 + vertex 635.673 134.194 155.803 + vertex 629.272 130.046 147.399 + endloop + endfacet + facet normal 0.488435 -0.870682 0.0578194 + outer loop + vertex 629.272 130.046 147.399 + vertex 635.673 134.194 155.803 + vertex 629.203 130.545 155.507 + endloop + endfacet + facet normal 0.46005 -0.885963 0.0585156 + outer loop + vertex 629.272 130.046 147.399 + vertex 629.203 130.545 155.507 + vertex 622.477 126.492 147.015 + endloop + endfacet + facet normal 0.489691 -0.871148 0.0361107 + outer loop + vertex 635.673 134.194 155.803 + vertex 635.627 134.502 163.851 + vertex 629.203 130.545 155.507 + endloop + endfacet + facet normal 0.489846 -0.871067 0.0359537 + outer loop + vertex 629.203 130.545 155.507 + vertex 635.627 134.502 163.851 + vertex 629.161 130.855 163.578 + endloop + endfacet + facet normal 0.461898 -0.886186 0.0363922 + outer loop + vertex 629.203 130.545 155.507 + vertex 629.161 130.855 163.578 + vertex 622.408 126.989 155.141 + endloop + endfacet + facet normal 0.49085 -0.871144 0.0132257 + outer loop + vertex 635.627 134.502 163.851 + vertex 635.614 134.616 171.867 + vertex 629.161 130.855 163.578 + endloop + endfacet + facet normal 0.490277 -0.871457 0.0138135 + outer loop + vertex 629.161 130.855 163.578 + vertex 635.614 134.616 171.867 + vertex 629.146 130.974 171.613 + endloop + endfacet + facet normal 0.462867 -0.886318 0.0139817 + outer loop + vertex 629.161 130.855 163.578 + vertex 629.146 130.974 171.613 + vertex 622.366 127.301 163.229 + endloop + endfacet + facet normal 0.491004 -0.871103 -0.0097674 + outer loop + vertex 635.614 134.616 171.867 + vertex 635.629 134.535 179.875 + vertex 629.146 130.974 171.613 + endloop + endfacet + facet normal 0.489769 -0.871811 -0.00849341 + outer loop + vertex 629.146 130.974 171.613 + vertex 635.629 134.535 179.875 + vertex 629.155 130.901 179.64 + endloop + endfacet + facet normal 0.462962 -0.886336 -0.00859717 + outer loop + vertex 629.146 130.974 171.613 + vertex 629.155 130.901 179.64 + vertex 622.348 127.426 171.283 + endloop + endfacet + facet normal 0.490193 -0.870996 -0.0328182 + outer loop + vertex 635.629 134.535 179.875 + vertex 635.669 134.255 187.9 + vertex 629.155 130.901 179.64 + endloop + endfacet + facet normal 0.488568 -0.87197 -0.031141 + outer loop + vertex 629.155 130.901 179.64 + vertex 635.669 134.255 187.9 + vertex 629.197 130.637 187.692 + endloop + endfacet + facet normal 0.462306 -0.886162 -0.0314684 + outer loop + vertex 629.155 130.901 179.64 + vertex 629.197 130.637 187.692 + vertex 622.356 127.364 179.334 + endloop + endfacet + facet normal 0.488647 -0.870668 -0.0562218 + outer loop + vertex 635.669 134.255 187.9 + vertex 635.743 133.777 195.951 + vertex 629.197 130.637 187.692 + endloop + endfacet + facet normal 0.486331 -0.872115 -0.0538367 + outer loop + vertex 629.197 130.637 187.692 + vertex 635.743 133.777 195.951 + vertex 629.264 130.175 195.774 + endloop + endfacet + facet normal 0.460672 -0.885901 -0.0544132 + outer loop + vertex 629.197 130.637 187.692 + vertex 629.264 130.175 195.774 + vertex 622.389 127.113 187.415 + endloop + endfacet + facet normal 0.486027 -0.870283 -0.0799103 + outer loop + vertex 635.743 133.777 195.951 + vertex 635.843 133.093 204.012 + vertex 629.264 130.175 195.774 + endloop + endfacet + facet normal 0.483223 -0.872102 -0.0770264 + outer loop + vertex 629.264 130.175 195.774 + vertex 635.843 133.093 204.012 + vertex 629.358 129.512 203.868 + endloop + endfacet + facet normal 0.458231 -0.885419 -0.0778253 + outer loop + vertex 629.264 130.175 195.774 + vertex 629.358 129.512 203.868 + vertex 622.454 126.672 195.534 + endloop + endfacet + facet normal 0.4825 -0.869711 -0.103907 + outer loop + vertex 635.843 133.093 204.012 + vertex 635.972 132.204 212.05 + vertex 629.358 129.512 203.868 + endloop + endfacet + facet normal 0.479294 -0.871869 -0.100604 + outer loop + vertex 629.358 129.512 203.868 + vertex 635.972 132.204 212.05 + vertex 629.489 128.653 211.943 + endloop + endfacet + facet normal 0.454877 -0.884742 -0.101578 + outer loop + vertex 629.358 129.512 203.868 + vertex 629.489 128.653 211.943 + vertex 622.548 126.034 203.666 + endloop + endfacet + facet normal 0.478148 -0.868963 -0.127584 + outer loop + vertex 635.972 132.204 212.05 + vertex 636.137 131.123 220.03 + vertex 629.489 128.653 211.943 + endloop + endfacet + facet normal 0.474477 -0.871521 -0.123786 + outer loop + vertex 629.489 128.653 211.943 + vertex 636.137 131.123 220.03 + vertex 629.646 127.6 219.956 + endloop + endfacet + facet normal 0.450742 -0.883867 -0.124942 + outer loop + vertex 629.489 128.653 211.943 + vertex 629.646 127.6 219.956 + vertex 622.672 125.201 211.77 + endloop + endfacet + facet normal 0.472971 -0.868196 -0.150114 + outer loop + vertex 636.137 131.123 220.03 + vertex 636.335 129.867 227.921 + vertex 629.646 127.6 219.956 + endloop + endfacet + facet normal 0.468936 -0.871099 -0.145899 + outer loop + vertex 629.646 127.6 219.956 + vertex 636.335 129.867 227.921 + vertex 629.841 126.376 227.891 + endloop + endfacet + facet normal 0.499264 -0.853637 -0.148458 + outer loop + vertex 636.137 131.123 220.03 + vertex 642.425 133.43 227.916 + vertex 636.335 129.867 227.921 + endloop + endfacet + facet normal 0.497126 -0.85002 -0.174161 + outer loop + vertex 642.425 133.43 227.916 + vertex 642.686 131.994 235.666 + vertex 636.335 129.867 227.921 + endloop + endfacet + facet normal 0.492631 -0.853572 -0.1695 + outer loop + vertex 636.335 129.867 227.921 + vertex 642.686 131.994 235.666 + vertex 636.582 128.461 235.72 + endloop + endfacet + facet normal 0.526949 -0.832334 -0.171887 + outer loop + vertex 642.425 133.43 227.916 + vertex 648.399 135.621 235.615 + vertex 642.686 131.994 235.666 + endloop + endfacet + facet normal 0.524102 -0.828225 -0.198396 + outer loop + vertex 648.399 135.621 235.615 + vertex 648.773 134.031 243.241 + vertex 642.686 131.994 235.666 + endloop + endfacet + facet normal 0.518448 -0.833154 -0.192527 + outer loop + vertex 642.686 131.994 235.666 + vertex 648.773 134.031 243.241 + vertex 643.023 130.433 243.327 + endloop + endfacet + facet normal 0.559379 -0.805551 -0.195401 + outer loop + vertex 648.399 135.621 235.615 + vertex 654.143 137.779 243.164 + vertex 648.773 134.031 243.241 + endloop + endfacet + facet normal 0.555367 -0.80042 -0.225598 + outer loop + vertex 654.143 137.779 243.164 + vertex 654.708 136.044 250.711 + vertex 648.773 134.031 243.241 + endloop + endfacet + facet normal 0.547828 -0.807791 -0.217621 + outer loop + vertex 648.773 134.031 243.241 + vertex 654.708 136.044 250.711 + vertex 649.285 132.341 250.802 + endloop + endfacet + facet normal 0.59424 -0.772984 -0.222202 + outer loop + vertex 654.143 137.779 243.164 + vertex 659.737 139.933 250.631 + vertex 654.708 136.044 250.711 + endloop + endfacet + facet normal 0.588448 -0.766228 -0.258116 + outer loop + vertex 659.737 139.933 250.631 + vertex 660.544 138.041 258.088 + vertex 654.708 136.044 250.711 + endloop + endfacet + facet normal 0.578855 -0.776919 -0.247635 + outer loop + vertex 654.708 136.044 250.711 + vertex 660.544 138.041 258.088 + vertex 655.48 134.237 258.184 + endloop + endfacet + facet normal 0.626093 -0.736954 -0.254767 + outer loop + vertex 659.737 139.933 250.631 + vertex 665.143 141.962 258.05 + vertex 660.544 138.041 258.088 + endloop + endfacet + facet normal 0.618209 -0.728117 -0.29608 + outer loop + vertex 665.143 141.962 258.05 + vertex 666.185 139.912 265.264 + vertex 660.544 138.041 258.088 + endloop + endfacet + facet normal 0.607342 -0.741973 -0.283922 + outer loop + vertex 660.544 138.041 258.088 + vertex 666.185 139.912 265.264 + vertex 661.604 136.126 265.359 + endloop + endfacet + facet normal 0.598208 -0.731989 -0.326097 + outer loop + vertex 666.185 139.912 265.264 + vertex 667.45 137.946 271.999 + vertex 661.604 136.126 265.359 + endloop + endfacet + facet normal 0.629424 -0.706108 -0.324401 + outer loop + vertex 666.185 139.912 265.264 + vertex 671.38 141.452 271.992 + vertex 667.45 137.946 271.999 + endloop + endfacet + facet normal 0.640467 -0.69032 -0.336541 + outer loop + vertex 670.237 143.598 265.415 + vertex 671.38 141.452 271.992 + vertex 666.185 139.912 265.264 + endloop + endfacet + facet normal 0.635807 -0.724876 -0.26515 + outer loop + vertex 664.293 143.939 250.605 + vertex 665.143 141.962 258.05 + vertex 659.737 139.933 250.631 + endloop + endfacet + facet normal 0.64256 -0.732293 -0.22553 + outer loop + vertex 659.129 141.715 243.114 + vertex 664.293 143.939 250.605 + vertex 659.737 139.933 250.631 + endloop + endfacet + facet normal 0.649439 -0.723914 -0.23276 + outer loop + vertex 663.65 145.765 243.131 + vertex 664.293 143.939 250.605 + vertex 659.129 141.715 243.114 + endloop + endfacet + facet normal 0.654547 -0.729764 -0.197518 + outer loop + vertex 658.688 143.363 235.561 + vertex 663.65 145.765 243.131 + vertex 659.129 141.715 243.114 + endloop + endfacet + facet normal 0.659385 -0.724017 -0.202513 + outer loop + vertex 663.188 147.445 235.62 + vertex 663.65 145.765 243.131 + vertex 658.688 143.363 235.561 + endloop + endfacet + facet normal 0.66305 -0.7285 -0.172201 + outer loop + vertex 658.372 144.882 227.92 + vertex 663.188 147.445 235.62 + vertex 658.688 143.363 235.561 + endloop + endfacet + facet normal 0.667042 -0.723875 -0.176238 + outer loop + vertex 662.866 149.002 228.008 + vertex 663.188 147.445 235.62 + vertex 658.372 144.882 227.92 + endloop + endfacet + facet normal 0.669823 -0.727494 -0.148626 + outer loop + vertex 658.142 146.255 220.162 + vertex 662.866 149.002 228.008 + vertex 658.372 144.882 227.92 + endloop + endfacet + facet normal 0.67335 -0.723499 -0.152148 + outer loop + vertex 662.624 150.403 220.271 + vertex 662.866 149.002 228.008 + vertex 658.142 146.255 220.162 + endloop + endfacet + facet normal 0.675527 -0.726546 -0.125672 + outer loop + vertex 657.965 147.45 212.303 + vertex 662.624 150.403 220.271 + vertex 658.142 146.255 220.162 + endloop + endfacet + facet normal 0.678516 -0.723233 -0.128647 + outer loop + vertex 662.445 151.629 212.441 + vertex 662.624 150.403 220.271 + vertex 657.965 147.45 212.303 + endloop + endfacet + facet normal 0.680158 -0.725856 -0.102557 + outer loop + vertex 657.822 148.436 204.38 + vertex 662.445 151.629 212.441 + vertex 657.965 147.45 212.303 + endloop + endfacet + facet normal 0.682613 -0.723194 -0.105019 + outer loop + vertex 662.305 152.642 204.55 + vertex 662.445 151.629 212.441 + vertex 657.822 148.436 204.38 + endloop + endfacet + facet normal 0.683727 -0.725426 -0.0792168 + outer loop + vertex 657.719 149.207 196.429 + vertex 662.305 152.642 204.55 + vertex 657.822 148.436 204.38 + endloop + endfacet + facet normal 0.686725 -0.722248 -0.0822543 + outer loop + vertex 662.204 153.448 196.63 + vertex 662.305 152.642 204.55 + vertex 657.719 149.207 196.429 + endloop + endfacet + facet normal 0.68734 -0.724086 -0.0571163 + outer loop + vertex 657.643 149.762 188.481 + vertex 662.204 153.448 196.63 + vertex 657.719 149.207 196.429 + endloop + endfacet + facet normal 0.689918 -0.721416 -0.0597672 + outer loop + vertex 662.133 154.037 188.706 + vertex 662.204 153.448 196.63 + vertex 657.643 149.762 188.481 + endloop + endfacet + facet normal 0.69008 -0.722884 -0.0350554 + outer loop + vertex 657.601 150.106 180.552 + vertex 662.133 154.037 188.706 + vertex 657.643 149.762 188.481 + endloop + endfacet + facet normal 0.692396 -0.720544 -0.0374711 + outer loop + vertex 662.092 154.409 180.799 + vertex 662.133 154.037 188.706 + vertex 657.601 150.106 180.552 + endloop + endfacet + facet normal 0.692124 -0.721661 -0.0130374 + outer loop + vertex 657.594 150.242 172.637 + vertex 662.092 154.409 180.799 + vertex 657.601 150.106 180.552 + endloop + endfacet + facet normal 0.694134 -0.719687 -0.0151529 + outer loop + vertex 662.091 154.574 172.907 + vertex 662.092 154.409 180.799 + vertex 657.594 150.242 172.637 + endloop + endfacet + facet normal 0.693454 -0.720451 0.00848543 + outer loop + vertex 657.612 150.166 164.711 + vertex 662.091 154.574 172.907 + vertex 657.594 150.242 172.637 + endloop + endfacet + facet normal 0.694353 -0.719595 0.00753415 + outer loop + vertex 662.12 154.519 164.998 + vertex 662.091 154.574 172.907 + vertex 657.612 150.166 164.711 + endloop + endfacet + facet normal 0.693254 -0.720017 0.0312113 + outer loop + vertex 657.67 149.877 156.748 + vertex 662.12 154.519 164.998 + vertex 657.612 150.166 164.711 + endloop + endfacet + facet normal 0.694239 -0.719112 0.0301705 + outer loop + vertex 662.177 154.24 157.049 + vertex 662.12 154.519 164.998 + vertex 657.67 149.877 156.748 + endloop + endfacet + facet normal 0.692795 -0.719189 0.0529327 + outer loop + vertex 657.747 149.363 148.752 + vertex 662.177 154.24 157.049 + vertex 657.67 149.877 156.748 + endloop + endfacet + facet normal 0.6924 -0.719539 0.0533493 + outer loop + vertex 662.244 153.713 149.07 + vertex 662.177 154.24 157.049 + vertex 657.747 149.363 148.752 + endloop + endfacet + facet normal 0.690627 -0.719297 0.0751399 + outer loop + vertex 657.847 148.624 140.763 + vertex 662.244 153.713 149.07 + vertex 657.747 149.363 148.752 + endloop + endfacet + facet normal 0.689 -0.720676 0.0768459 + outer loop + vertex 662.341 152.957 141.106 + vertex 662.244 153.713 149.07 + vertex 657.847 148.624 140.763 + endloop + endfacet + facet normal 0.686951 -0.720165 0.0972657 + outer loop + vertex 657.971 147.672 132.839 + vertex 662.341 152.957 141.106 + vertex 657.847 148.624 140.763 + endloop + endfacet + facet normal 0.684589 -0.722074 0.0997351 + outer loop + vertex 662.462 151.981 133.211 + vertex 662.341 152.957 141.106 + vertex 657.971 147.672 132.839 + endloop + endfacet + facet normal 0.682206 -0.721307 0.119629 + outer loop + vertex 658.128 146.525 125.023 + vertex 662.462 151.981 133.211 + vertex 657.971 147.672 132.839 + endloop + endfacet + facet normal 0.679223 -0.723597 0.122734 + outer loop + vertex 662.617 150.806 125.424 + vertex 662.462 151.981 133.211 + vertex 658.128 146.525 125.023 + endloop + endfacet + facet normal 0.676502 -0.722571 0.142251 + outer loop + vertex 658.338 145.203 117.316 + vertex 662.617 150.806 125.424 + vertex 658.128 146.525 125.023 + endloop + endfacet + facet normal 0.672893 -0.725195 0.145969 + outer loop + vertex 662.824 149.452 117.743 + vertex 662.617 150.806 125.424 + vertex 658.338 145.203 117.316 + endloop + endfacet + facet normal 0.66988 -0.723919 0.164932 + outer loop + vertex 658.616 143.718 109.667 + vertex 662.824 149.452 117.743 + vertex 658.338 145.203 117.316 + endloop + endfacet + facet normal 0.664935 -0.727316 0.16992 + outer loop + vertex 663.108 147.93 110.117 + vertex 662.824 149.452 117.743 + vertex 658.616 143.718 109.667 + endloop + endfacet + facet normal 0.661707 -0.725806 0.188015 + outer loop + vertex 658.989 142.075 102.013 + vertex 663.108 147.93 110.117 + vertex 658.616 143.718 109.667 + endloop + endfacet + facet normal 0.655965 -0.729533 0.193626 + outer loop + vertex 663.493 146.253 102.496 + vertex 663.108 147.93 110.117 + vertex 658.989 142.075 102.013 + endloop + endfacet + facet normal 0.652443 -0.727781 0.211311 + outer loop + vertex 659.482 140.285 94.3236 + vertex 663.493 146.253 102.496 + vertex 658.989 142.075 102.013 + endloop + endfacet + facet normal 0.645019 -0.732329 0.218276 + outer loop + vertex 664.013 144.436 94.8623 + vertex 663.493 146.253 102.496 + vertex 659.482 140.285 94.3236 + endloop + endfacet + facet normal 0.640878 -0.730211 0.236784 + outer loop + vertex 660.15 138.373 86.62 + vertex 664.013 144.436 94.8623 + vertex 659.482 140.285 94.3236 + endloop + endfacet + facet normal 0.630481 -0.736176 0.246044 + outer loop + vertex 664.74 142.5 87.207 + vertex 664.013 144.436 94.8623 + vertex 660.15 138.373 86.62 + endloop + endfacet + facet normal 0.625464 -0.733456 0.266153 + outer loop + vertex 661.08 136.379 78.9386 + vertex 664.74 142.5 87.207 + vertex 660.15 138.373 86.62 + endloop + endfacet + facet normal 0.611091 -0.741078 0.278158 + outer loop + vertex 665.798 140.472 79.4811 + vertex 664.74 142.5 87.207 + vertex 661.08 136.379 78.9386 + endloop + endfacet + facet normal 0.605857 -0.737671 0.297958 + outer loop + vertex 662.366 134.356 71.3171 + vertex 665.798 140.472 79.4811 + vertex 661.08 136.379 78.9386 + endloop + endfacet + facet normal 0.586038 -0.747207 0.313434 + outer loop + vertex 667.39 138.438 71.6545 + vertex 665.798 140.472 79.4811 + vertex 662.366 134.356 71.3171 + endloop + endfacet + facet normal 0.5816 -0.74318 0.330795 + outer loop + vertex 664.081 132.396 63.8969 + vertex 667.39 138.438 71.6545 + vertex 662.366 134.356 71.3171 + endloop + endfacet + facet normal 0.557079 -0.753449 0.349253 + outer loop + vertex 669.757 136.653 64.0274 + vertex 667.39 138.438 71.6545 + vertex 664.081 132.396 63.8969 + endloop + endfacet + facet normal 0.553276 -0.748855 0.364831 + outer loop + vertex 666.134 130.567 57.0293 + vertex 669.757 136.653 64.0274 + vertex 664.081 132.396 63.8969 + endloop + endfacet + facet normal 0.520337 -0.759236 0.390909 + outer loop + vertex 672.033 134.45 56.7194 + vertex 669.757 136.653 64.0274 + vertex 666.134 130.567 57.0293 + endloop + endfacet + facet normal 0.518019 -0.754796 0.402417 + outer loop + vertex 668.383 129.031 51.254 + vertex 672.033 134.45 56.7194 + vertex 666.134 130.567 57.0293 + endloop + endfacet + facet normal 0.487141 -0.760733 0.428927 + outer loop + vertex 673.962 132.44 50.9646 + vertex 672.033 134.45 56.7194 + vertex 668.383 129.031 51.254 + endloop + endfacet + facet normal 0.48505 -0.756483 0.438702 + outer loop + vertex 670.746 128.055 46.9579 + vertex 673.962 132.44 50.9646 + vertex 668.383 129.031 51.254 + endloop + endfacet + facet normal 0.470474 -0.757892 0.451945 + outer loop + vertex 676.674 131.994 47.3921 + vertex 673.962 132.44 50.9646 + vertex 670.746 128.055 46.9579 + endloop + endfacet + facet normal 0.601547 -0.765019 -0.229972 + outer loop + vertex 659.129 141.715 243.114 + vertex 659.737 139.933 250.631 + vertex 654.143 137.779 243.164 + endloop + endfacet + facet normal 0.606212 -0.770505 -0.197053 + outer loop + vertex 653.731 139.396 235.572 + vertex 659.129 141.715 243.114 + vertex 654.143 137.779 243.164 + endloop + endfacet + facet normal 0.611579 -0.76479 -0.202651 + outer loop + vertex 658.688 143.363 235.561 + vertex 659.129 141.715 243.114 + vertex 653.731 139.396 235.572 + endloop + endfacet + facet normal 0.615137 -0.769154 -0.173227 + outer loop + vertex 653.43 140.884 227.898 + vertex 658.688 143.363 235.561 + vertex 653.731 139.396 235.572 + endloop + endfacet + facet normal 0.572391 -0.80051 -0.177631 + outer loop + vertex 653.43 140.884 227.898 + vertex 653.731 139.396 235.572 + vertex 648.115 137.082 227.904 + endloop + endfacet + facet normal 0.57499 -0.804102 -0.151021 + outer loop + vertex 647.899 138.395 220.089 + vertex 653.43 140.884 227.898 + vertex 648.115 137.082 227.904 + endloop + endfacet + facet normal 0.537625 -0.82897 -0.154168 + outer loop + vertex 647.899 138.395 220.089 + vertex 648.115 137.082 227.904 + vertex 642.214 134.714 220.063 + endloop + endfacet + facet normal 0.539598 -0.832199 -0.127588 + outer loop + vertex 642.049 135.825 212.119 + vertex 647.899 138.395 220.089 + vertex 642.214 134.714 220.063 + endloop + endfacet + facet normal 0.508584 -0.851202 -0.129603 + outer loop + vertex 642.049 135.825 212.119 + vertex 642.214 134.714 220.063 + vertex 635.972 132.204 212.05 + endloop + endfacet + facet normal 0.5431 -0.829375 -0.131069 + outer loop + vertex 647.727 139.534 212.174 + vertex 647.899 138.395 220.089 + vertex 642.049 135.825 212.119 + endloop + endfacet + facet normal 0.544661 -0.832164 -0.10415 + outer loop + vertex 641.913 136.737 204.112 + vertex 647.727 139.534 212.174 + vertex 642.049 135.825 212.119 + endloop + endfacet + facet normal 0.513166 -0.851738 -0.105842 + outer loop + vertex 641.913 136.737 204.112 + vertex 642.049 135.825 212.119 + vertex 635.843 133.093 204.012 + endloop + endfacet + facet normal 0.547471 -0.829964 -0.106939 + outer loop + vertex 647.592 140.473 204.195 + vertex 647.727 139.534 212.174 + vertex 641.913 136.737 204.112 + endloop + endfacet + facet normal 0.548578 -0.83225 -0.0801416 + outer loop + vertex 641.81 137.443 196.081 + vertex 647.592 140.473 204.195 + vertex 641.913 136.737 204.112 + endloop + endfacet + facet normal 0.516716 -0.852269 -0.0814954 + outer loop + vertex 641.81 137.443 196.081 + vertex 641.913 136.737 204.112 + vertex 635.743 133.777 195.951 + endloop + endfacet + facet normal 0.550974 -0.830432 -0.0825269 + outer loop + vertex 647.487 141.199 196.19 + vertex 647.592 140.473 204.195 + vertex 641.81 137.443 196.081 + endloop + endfacet + facet normal 0.551625 -0.832174 -0.0565471 + outer loop + vertex 641.737 137.94 188.055 + vertex 647.487 141.199 196.19 + vertex 641.81 137.443 196.081 + endloop + endfacet + facet normal 0.51923 -0.852697 -0.0575195 + outer loop + vertex 641.737 137.94 188.055 + vertex 641.81 137.443 196.081 + vertex 635.669 134.255 187.9 + endloop + endfacet + facet normal 0.553721 -0.830635 -0.0586453 + outer loop + vertex 647.406 141.709 188.189 + vertex 647.487 141.199 196.19 + vertex 641.737 137.94 188.055 + endloop + endfacet + facet normal 0.553952 -0.831877 -0.0334483 + outer loop + vertex 641.69 138.23 180.053 + vertex 647.406 141.709 188.189 + vertex 641.737 137.94 188.055 + endloop + endfacet + facet normal 0.520969 -0.852897 -0.0340201 + outer loop + vertex 641.69 138.23 180.053 + vertex 641.737 137.94 188.055 + vertex 635.629 134.535 179.875 + endloop + endfacet + facet normal 0.555228 -0.830972 -0.0347319 + outer loop + vertex 647.36 142.013 180.211 + vertex 647.406 141.709 188.189 + vertex 641.69 138.23 180.053 + endloop + endfacet + facet normal 0.555065 -0.831742 -0.0104165 + outer loop + vertex 641.674 138.32 172.067 + vertex 647.36 142.013 180.211 + vertex 641.69 138.23 180.053 + endloop + endfacet + facet normal 0.521653 -0.853092 -0.0105902 + outer loop + vertex 641.674 138.32 172.067 + vertex 641.69 138.23 180.053 + vertex 635.614 134.616 171.867 + endloop + endfacet + facet normal 0.555944 -0.831143 -0.0113018 + outer loop + vertex 647.344 142.11 172.249 + vertex 647.36 142.013 180.211 + vertex 641.674 138.32 172.067 + endloop + endfacet + facet normal 0.555405 -0.831485 0.0125916 + outer loop + vertex 641.692 138.211 164.076 + vertex 647.344 142.11 172.249 + vertex 641.674 138.32 172.067 + endloop + endfacet + facet normal 0.521278 -0.853291 0.0128132 + outer loop + vertex 641.692 138.211 164.076 + vertex 641.674 138.32 172.067 + vertex 635.627 134.502 163.851 + endloop + endfacet + facet normal 0.555947 -0.831131 0.0120481 + outer loop + vertex 647.357 142.003 164.281 + vertex 647.344 142.11 172.249 + vertex 641.692 138.211 164.076 + endloop + endfacet + facet normal 0.555074 -0.831067 0.0349383 + outer loop + vertex 641.731 137.9 156.051 + vertex 647.357 142.003 164.281 + vertex 641.692 138.211 164.076 + endloop + endfacet + facet normal 0.520346 -0.853212 0.0356283 + outer loop + vertex 641.731 137.9 156.051 + vertex 641.692 138.211 164.076 + vertex 635.673 134.194 155.803 + endloop + endfacet + facet normal 0.554932 -0.831156 0.0350797 + outer loop + vertex 647.398 141.693 156.281 + vertex 647.357 142.003 164.281 + vertex 641.731 137.9 156.051 + endloop + endfacet + facet normal 0.553732 -0.830715 0.0573877 + outer loop + vertex 641.802 137.39 147.992 + vertex 647.398 141.693 156.281 + vertex 641.731 137.9 156.051 + endloop + endfacet + facet normal 0.51832 -0.853184 0.0584949 + outer loop + vertex 641.802 137.39 147.992 + vertex 641.731 137.9 156.051 + vertex 635.743 133.691 147.719 + endloop + endfacet + facet normal 0.552725 -0.831316 0.0583793 + outer loop + vertex 647.474 141.179 148.247 + vertex 647.398 141.693 156.281 + vertex 641.802 137.39 147.992 + endloop + endfacet + facet normal 0.551258 -0.83054 0.0794908 + outer loop + vertex 641.901 136.684 139.934 + vertex 647.474 141.179 148.247 + vertex 641.802 137.39 147.992 + endloop + endfacet + facet normal 0.515335 -0.853149 0.0810317 + outer loop + vertex 641.901 136.684 139.934 + vertex 641.802 137.39 147.992 + vertex 635.841 132.996 139.633 + endloop + endfacet + facet normal 0.550129 -0.831181 0.0805941 + outer loop + vertex 647.569 140.463 140.214 + vertex 647.474 141.179 148.247 + vertex 641.901 136.684 139.934 + endloop + endfacet + facet normal 0.548376 -0.83008 0.101242 + outer loop + vertex 642.028 135.792 131.93 + vertex 647.569 140.463 140.214 + vertex 641.901 136.684 139.934 + endloop + endfacet + facet normal 0.511265 -0.853201 0.103232 + outer loop + vertex 642.028 135.792 131.93 + vertex 641.901 136.684 139.934 + vertex 635.96 132.117 131.604 + endloop + endfacet + facet normal 0.545961 -0.831382 0.103591 + outer loop + vertex 647.701 139.556 132.235 + vertex 647.569 140.463 140.214 + vertex 642.028 135.792 131.93 + endloop + endfacet + facet normal 0.543988 -0.829998 0.123209 + outer loop + vertex 642.193 134.726 124.023 + vertex 647.701 139.556 132.235 + vertex 642.028 135.792 131.93 + endloop + endfacet + facet normal 0.50646 -0.853076 0.125537 + outer loop + vertex 642.193 134.726 124.023 + vertex 642.028 135.792 131.93 + vertex 636.124 131.071 123.671 + endloop + endfacet + facet normal 0.54085 -0.83159 0.12625 + outer loop + vertex 647.871 138.47 124.356 + vertex 647.701 139.556 132.235 + vertex 642.193 134.726 124.023 + endloop + endfacet + facet normal 0.538645 -0.829929 0.145189 + outer loop + vertex 642.407 133.499 116.212 + vertex 647.871 138.47 124.356 + vertex 642.193 134.726 124.023 + endloop + endfacet + facet normal 0.500597 -0.852976 0.147763 + outer loop + vertex 642.407 133.499 116.212 + vertex 642.193 134.726 124.023 + vertex 636.332 129.867 115.83 + endloop + endfacet + facet normal 0.534999 -0.831664 0.148694 + outer loop + vertex 648.087 137.218 116.579 + vertex 647.871 138.47 124.356 + vertex 642.407 133.499 116.212 + endloop + endfacet + facet normal 0.532694 -0.829857 0.166053 + outer loop + vertex 642.664 132.113 108.46 + vertex 648.087 137.218 116.579 + vertex 642.407 133.499 116.212 + endloop + endfacet + facet normal 0.493731 -0.853053 0.168911 + outer loop + vertex 642.664 132.113 108.46 + vertex 642.407 133.499 116.212 + vertex 636.576 128.506 108.037 + endloop + endfacet + facet normal 0.527889 -0.832001 0.17061 + outer loop + vertex 648.351 135.805 108.866 + vertex 648.087 137.218 116.579 + vertex 642.664 132.113 108.46 + endloop + endfacet + facet normal 0.525697 -0.830241 0.185317 + outer loop + vertex 642.945 130.564 100.722 + vertex 648.351 135.805 108.866 + vertex 642.664 132.113 108.46 + endloop + endfacet + facet normal 0.485997 -0.853388 0.188507 + outer loop + vertex 642.945 130.564 100.722 + vertex 642.664 132.113 108.46 + vertex 636.841 126.984 100.254 + endloop + endfacet + facet normal 0.519189 -0.832956 0.191384 + outer loop + vertex 648.661 134.228 101.161 + vertex 648.351 135.805 108.866 + vertex 642.945 130.564 100.722 + endloop + endfacet + facet normal 0.51709 -0.831218 0.204192 + outer loop + vertex 643.279 128.865 92.9595 + vertex 648.661 134.228 101.161 + vertex 642.945 130.564 100.722 + endloop + endfacet + facet normal 0.477139 -0.85399 0.207459 + outer loop + vertex 643.279 128.865 92.9595 + vertex 642.945 130.564 100.722 + vertex 637.144 125.316 92.4612 + endloop + endfacet + facet normal 0.508402 -0.834591 0.212099 + outer loop + vertex 649.052 132.498 93.4182 + vertex 648.661 134.228 101.161 + vertex 643.279 128.865 92.9595 + endloop + endfacet + facet normal 0.506084 -0.832563 0.225204 + outer loop + vertex 643.786 127.059 85.1466 + vertex 649.052 132.498 93.4182 + vertex 643.279 128.865 92.9595 + endloop + endfacet + facet normal 0.466586 -0.854652 0.227745 + outer loop + vertex 643.786 127.059 85.1466 + vertex 643.279 128.865 92.9595 + vertex 637.608 123.55 84.6323 + endloop + endfacet + facet normal 0.46394 -0.852114 0.242203 + outer loop + vertex 638.458 121.767 76.7317 + vertex 643.786 127.059 85.1466 + vertex 637.608 123.55 84.6323 + endloop + endfacet + facet normal 0.455671 -0.85461 0.249008 + outer loop + vertex 644.633 125.225 77.2995 + vertex 643.786 127.059 85.1466 + vertex 638.458 121.767 76.7317 + endloop + endfacet + facet normal 0.452481 -0.851522 0.2649 + outer loop + vertex 639.867 120.042 68.783 + vertex 644.633 125.225 77.2995 + vertex 638.458 121.767 76.7317 + endloop + endfacet + facet normal 0.422359 -0.867431 0.263014 + outer loop + vertex 639.867 120.042 68.783 + vertex 638.458 121.767 76.7317 + vertex 633.448 116.707 68.0915 + endloop + endfacet + facet normal 0.418861 -0.864057 0.279214 + outer loop + vertex 635.593 115.134 60.0056 + vertex 639.867 120.042 68.783 + vertex 633.448 116.707 68.0915 + endloop + endfacet + facet normal 0.413178 -0.86561 0.282849 + outer loop + vertex 641.868 118.422 60.9019 + vertex 639.867 120.042 68.783 + vertex 635.593 115.134 60.0056 + endloop + endfacet + facet normal 0.409012 -0.862102 0.29915 + outer loop + vertex 641.868 118.422 60.9019 + vertex 635.593 115.134 60.0056 + vertex 638.387 114.737 55.04 + endloop + endfacet + facet normal 0.40139 -0.863737 0.304703 + outer loop + vertex 641.491 116.051 54.676 + vertex 641.868 118.422 60.9019 + vertex 638.387 114.737 55.04 + endloop + endfacet + facet normal 0.401297 -0.862579 0.308088 + outer loop + vertex 639.786 113.892 50.8514 + vertex 641.491 116.051 54.676 + vertex 638.387 114.737 55.04 + endloop + endfacet + facet normal 0.3904 -0.868435 0.305629 + outer loop + vertex 639.786 113.892 50.8514 + vertex 638.387 114.737 55.04 + vertex 636.701 112.367 50.4592 + endloop + endfacet + facet normal 0.387819 -0.865879 0.315991 + outer loop + vertex 638.144 111.817 47.1822 + vertex 639.786 113.892 50.8514 + vertex 636.701 112.367 50.4592 + endloop + endfacet + facet normal 0.380362 -0.870111 0.313419 + outer loop + vertex 638.144 111.817 47.1822 + vertex 636.701 112.367 50.4592 + vertex 635.06 110.295 46.699 + endloop + endfacet + facet normal 0.377092 -0.867217 0.325172 + outer loop + vertex 636.494 109.972 44.1742 + vertex 638.144 111.817 47.1822 + vertex 635.06 110.295 46.699 + endloop + endfacet + facet normal 0.371905 -0.870399 0.322633 + outer loop + vertex 636.494 109.972 44.1742 + vertex 635.06 110.295 46.699 + vertex 633.406 108.452 43.6339 + endloop + endfacet + facet normal 0.368995 -0.867959 0.3324 + outer loop + vertex 634.854 108.454 42.0324 + vertex 636.494 109.972 44.1742 + vertex 633.406 108.452 43.6339 + endloop + endfacet + facet normal 0.366034 -0.870232 0.32972 + outer loop + vertex 634.854 108.454 42.0324 + vertex 633.406 108.452 43.6339 + vertex 631.876 106.989 41.4715 + endloop + endfacet + facet normal 0.366057 -0.870251 0.329644 + outer loop + vertex 634.854 108.454 42.0324 + vertex 631.876 106.989 41.4715 + vertex 633.248 107.298 40.7631 + endloop + endfacet + facet normal 0.369097 -0.870374 0.325909 + outer loop + vertex 633.248 107.298 40.7631 + vertex 636.322 108.778 41.2342 + vertex 634.854 108.454 42.0324 + endloop + endfacet + facet normal 0.37024 -0.868866 0.328623 + outer loop + vertex 637.945 109.975 42.5698 + vertex 634.854 108.454 42.0324 + vertex 636.322 108.778 41.2342 + endloop + endfacet + facet normal 0.367948 -0.868804 0.331353 + outer loop + vertex 636.322 108.778 41.2342 + vertex 639.29 110.276 41.8652 + vertex 637.945 109.975 42.5698 + endloop + endfacet + facet normal 0.372049 -0.863054 0.341639 + outer loop + vertex 641.06 111.468 42.9493 + vertex 637.945 109.975 42.5698 + vertex 639.29 110.276 41.8652 + endloop + endfacet + facet normal 0.369747 -0.862702 0.345011 + outer loop + vertex 639.29 110.276 41.8652 + vertex 640.775 110.968 42.0043 + vertex 641.06 111.468 42.9493 + endloop + endfacet + facet normal 0.381835 -0.859543 0.339688 + outer loop + vertex 640.775 110.968 42.0043 + vertex 642.28 111.78 42.3693 + vertex 641.06 111.468 42.9493 + endloop + endfacet + facet normal 0.38272 -0.858102 0.342325 + outer loop + vertex 644.292 113.148 43.5486 + vertex 641.06 111.468 42.9493 + vertex 642.28 111.78 42.3693 + endloop + endfacet + facet normal 0.393402 -0.859662 0.325908 + outer loop + vertex 642.28 111.78 42.3693 + vertex 644.546 112.867 42.4984 + vertex 644.292 113.148 43.5486 + endloop + endfacet + facet normal 0.393995 -0.859366 0.325972 + outer loop + vertex 647.863 114.916 43.8927 + vertex 644.292 113.148 43.5486 + vertex 644.546 112.867 42.4984 + endloop + endfacet + facet normal 0.38738 -0.857402 0.338818 + outer loop + vertex 644.546 112.867 42.4984 + vertex 648.386 114.745 42.861 + vertex 647.863 114.916 43.8927 + endloop + endfacet + facet normal 0.389595 -0.856042 0.339717 + outer loop + vertex 648.386 114.745 42.861 + vertex 650.709 116.178 43.8078 + vertex 647.863 114.916 43.8927 + endloop + endfacet + facet normal 0.385792 -0.845478 0.36923 + outer loop + vertex 651.766 117.545 45.8356 + vertex 647.863 114.916 43.8927 + vertex 650.709 116.178 43.8078 + endloop + endfacet + facet normal 0.385476 -0.845534 0.369433 + outer loop + vertex 650.709 116.178 43.8078 + vertex 652.998 116.986 43.2687 + vertex 651.766 117.545 45.8356 + endloop + endfacet + facet normal 0.405683 -0.83292 0.376384 + outer loop + vertex 652.998 116.986 43.2687 + vertex 654.659 118.333 44.4604 + vertex 651.766 117.545 45.8356 + endloop + endfacet + facet normal 0.408344 -0.833164 0.372951 + outer loop + vertex 654.659 118.333 44.4604 + vertex 652.998 116.986 43.2687 + vertex 654.164 117.688 43.5604 + endloop + endfacet + facet normal -0.372005 0.807827 -0.457196 + outer loop + vertex 653.166 117.115 43.3598 + vertex 654.164 117.688 43.5604 + vertex 652.998 116.986 43.2687 + endloop + endfacet + facet normal 0.404856 -0.817289 0.410036 + outer loop + vertex 653.597 117.217 43.1387 + vertex 653.166 117.115 43.3598 + vertex 652.998 116.986 43.2687 + endloop + endfacet + facet normal 0.40471 -0.820767 0.403176 + outer loop + vertex 654.549 117.22 42.1882 + vertex 653.597 117.217 43.1387 + vertex 652.998 116.986 43.2687 + endloop + endfacet + facet normal 0.400692 -0.82609 0.396259 + outer loop + vertex 652.998 116.986 43.2687 + vertex 654.358 116.606 41.1017 + vertex 654.549 117.22 42.1882 + endloop + endfacet + facet normal 0.389646 -0.829501 0.40013 + outer loop + vertex 655.662 116.854 40.3471 + vertex 654.549 117.22 42.1882 + vertex 654.358 116.606 41.1017 + endloop + endfacet + facet normal 0.389571 -0.829617 0.399962 + outer loop + vertex 654.358 116.606 41.1017 + vertex 655.902 116.263 38.8875 + vertex 655.662 116.854 40.3471 + endloop + endfacet + facet normal 0.368144 -0.839176 0.400317 + outer loop + vertex 657.152 116.481 38.1948 + vertex 655.662 116.854 40.3471 + vertex 655.902 116.263 38.8875 + endloop + endfacet + facet normal 0.368035 -0.839342 0.400069 + outer loop + vertex 655.902 116.263 38.8875 + vertex 657.903 116.058 36.6162 + vertex 657.152 116.481 38.1948 + endloop + endfacet + facet normal 0.347382 -0.851202 0.393422 + outer loop + vertex 659.43 116.371 35.9449 + vertex 657.152 116.481 38.1948 + vertex 657.903 116.058 36.6162 + endloop + endfacet + facet normal 0.388185 -0.813584 0.43289 + outer loop + vertex 657.152 116.481 38.1948 + vertex 659.43 116.371 35.9449 + vertex 659.957 117.8 38.1578 + endloop + endfacet + facet normal 0.389961 -0.817623 0.423583 + outer loop + vertex 657.708 117.629 39.8991 + vertex 657.152 116.481 38.1948 + vertex 659.957 117.8 38.1578 + endloop + endfacet + facet normal 0.404436 -0.799533 0.444047 + outer loop + vertex 657.708 117.629 39.8991 + vertex 659.957 117.8 38.1578 + vertex 662.829 120.822 40.9823 + endloop + endfacet + facet normal 0.416703 -0.80913 0.414329 + outer loop + vertex 657.967 118.797 41.9188 + vertex 657.708 117.629 39.8991 + vertex 662.829 120.822 40.9823 + endloop + endfacet + facet normal 0.416431 -0.802365 0.427546 + outer loop + vertex 662.829 120.822 40.9823 + vertex 663.718 122.297 42.8848 + vertex 657.967 118.797 41.9188 + endloop + endfacet + facet normal 0.437165 -0.820248 0.36889 + outer loop + vertex 663.718 122.297 42.8848 + vertex 661.62 121.496 43.5908 + vertex 657.967 118.797 41.9188 + endloop + endfacet + facet normal 0.415571 -0.813959 0.405921 + outer loop + vertex 655.879 118.322 43.1035 + vertex 657.967 118.797 41.9188 + vertex 661.62 121.496 43.5908 + endloop + endfacet + facet normal 0.41058 -0.822438 0.393725 + outer loop + vertex 655.879 118.322 43.1035 + vertex 654.549 117.22 42.1882 + vertex 657.967 118.797 41.9188 + endloop + endfacet + facet normal 0.441258 -0.802974 0.400654 + outer loop + vertex 661.62 121.496 43.5908 + vertex 663.718 122.297 42.8848 + vertex 669.446 126.04 44.0778 + endloop + endfacet + facet normal 0.483851 -0.853927 0.191567 + outer loop + vertex 668.365 125.57 44.7151 + vertex 661.62 121.496 43.5908 + vertex 669.446 126.04 44.0778 + endloop + endfacet + facet normal 0.50301 -0.829747 0.24187 + outer loop + vertex 668.365 125.57 44.7151 + vertex 669.446 126.04 44.0778 + vertex 676.639 130.711 45.1452 + endloop + endfacet + facet normal 0.463653 -0.842936 0.27292 + outer loop + vertex 662.023 121.951 44.3134 + vertex 661.62 121.496 43.5908 + vertex 668.365 125.57 44.7151 + endloop + endfacet + facet normal 0.433582 -0.851443 0.295046 + outer loop + vertex 661.62 121.496 43.5908 + vertex 662.023 121.951 44.3134 + vertex 657.592 119.634 44.1362 + endloop + endfacet + facet normal 0.431402 -0.848212 0.307294 + outer loop + vertex 659.621 120.854 44.6567 + vertex 657.592 119.634 44.1362 + vertex 662.023 121.951 44.3134 + endloop + endfacet + facet normal 0.400932 -0.830973 0.385665 + outer loop + vertex 657.592 119.634 44.1362 + vertex 659.621 120.854 44.6567 + vertex 658.298 120.97 46.2811 + endloop + endfacet + facet normal 0.409623 -0.828704 0.38139 + outer loop + vertex 654.659 118.333 44.4604 + vertex 657.592 119.634 44.1362 + vertex 658.298 120.97 46.2811 + endloop + endfacet + facet normal 0.408032 -0.828294 0.383977 + outer loop + vertex 658.298 120.97 46.2811 + vertex 651.766 117.545 45.8356 + vertex 654.659 118.333 44.4604 + endloop + endfacet + facet normal 0.41406 -0.836524 0.358861 + outer loop + vertex 658.298 120.97 46.2811 + vertex 655.503 121.461 50.6522 + vertex 651.766 117.545 45.8356 + endloop + endfacet + facet normal 0.429158 -0.834528 0.345524 + outer loop + vertex 651.766 117.545 45.8356 + vertex 655.503 121.461 50.6522 + vertex 651.534 118.613 48.701 + endloop + endfacet + facet normal 0.408529 -0.844048 0.3474 + outer loop + vertex 651.534 118.613 48.701 + vertex 648.573 116.977 48.2094 + vertex 651.766 117.545 45.8356 + endloop + endfacet + facet normal 0.401316 -0.852183 0.335751 + outer loop + vertex 648.573 116.977 48.2094 + vertex 646.626 114.987 45.4856 + vertex 651.766 117.545 45.8356 + endloop + endfacet + facet normal 0.399349 -0.852469 0.337366 + outer loop + vertex 644.738 115.068 47.9249 + vertex 646.626 114.987 45.4856 + vertex 648.573 116.977 48.2094 + endloop + endfacet + facet normal 0.401387 -0.855167 0.327991 + outer loop + vertex 648.573 116.977 48.2094 + vertex 646.783 117.468 51.681 + vertex 644.738 115.068 47.9249 + endloop + endfacet + facet normal 0.404128 -0.854588 0.32613 + outer loop + vertex 644.738 115.068 47.9249 + vertex 646.783 117.468 51.681 + vertex 643.044 115.533 51.2434 + endloop + endfacet + facet normal 0.393289 -0.861355 0.321546 + outer loop + vertex 644.738 115.068 47.9249 + vertex 643.044 115.533 51.2434 + vertex 641.291 113.364 47.5773 + endloop + endfacet + facet normal 0.390587 -0.858225 0.333005 + outer loop + vertex 642.89 113.13 45.0989 + vertex 644.738 115.068 47.9249 + vertex 641.291 113.364 47.5773 + endloop + endfacet + facet normal 0.383343 -0.863102 0.328792 + outer loop + vertex 642.89 113.13 45.0989 + vertex 641.291 113.364 47.5773 + vertex 639.614 111.51 44.6633 + endloop + endfacet + facet normal 0.379966 -0.859676 0.341441 + outer loop + vertex 641.06 111.468 42.9493 + vertex 642.89 113.13 45.0989 + vertex 639.614 111.51 44.6633 + endloop + endfacet + facet normal 0.383053 -0.863154 0.328992 + outer loop + vertex 639.614 111.51 44.6633 + vertex 641.291 113.364 47.5773 + vertex 638.144 111.817 47.1822 + endloop + endfacet + facet normal 0.39526 -0.860903 0.320336 + outer loop + vertex 641.291 113.364 47.5773 + vertex 643.044 115.533 51.2434 + vertex 639.786 113.892 50.8514 + endloop + endfacet + facet normal 0.406834 -0.857366 0.315294 + outer loop + vertex 646.783 117.468 51.681 + vertex 644.918 118.212 56.1104 + vertex 643.044 115.533 51.2434 + endloop + endfacet + facet normal 0.408898 -0.856792 0.314183 + outer loop + vertex 643.044 115.533 51.2434 + vertex 644.918 118.212 56.1104 + vertex 641.491 116.051 54.676 + endloop + endfacet + facet normal 0.424459 -0.846669 0.320916 + outer loop + vertex 646.783 117.468 51.681 + vertex 649.505 120.755 56.7514 + vertex 644.918 118.212 56.1104 + endloop + endfacet + facet normal 0.427469 -0.849294 0.309792 + outer loop + vertex 649.505 120.755 56.7514 + vertex 647.71 122.012 62.6743 + vertex 644.918 118.212 56.1104 + endloop + endfacet + facet normal 0.427846 -0.849185 0.309568 + outer loop + vertex 647.71 122.012 62.6743 + vertex 641.868 118.422 60.9019 + vertex 644.918 118.212 56.1104 + endloop + endfacet + facet normal 0.435473 -0.852099 0.29033 + outer loop + vertex 647.71 122.012 62.6743 + vertex 645.935 123.46 69.5871 + vertex 641.868 118.422 60.9019 + endloop + endfacet + facet normal 0.467496 -0.833446 0.294645 + outer loop + vertex 647.71 122.012 62.6743 + vertex 651.65 126.932 70.3399 + vertex 645.935 123.46 69.5871 + endloop + endfacet + facet normal 0.471472 -0.836593 0.278973 + outer loop + vertex 651.65 126.932 70.3399 + vertex 650.459 128.769 77.8606 + vertex 645.935 123.46 69.5871 + endloop + endfacet + facet normal 0.480899 -0.83356 0.271872 + outer loop + vertex 645.935 123.46 69.5871 + vertex 650.459 128.769 77.8606 + vertex 644.633 125.225 77.2995 + endloop + endfacet + facet normal 0.484226 -0.836563 0.256294 + outer loop + vertex 650.459 128.769 77.8606 + vertex 649.61 130.656 85.6254 + vertex 644.633 125.225 77.2995 + endloop + endfacet + facet normal 0.458629 -0.836125 0.300922 + outer loop + vertex 653.084 125.183 63.2952 + vertex 651.65 126.932 70.3399 + vertex 647.71 122.012 62.6743 + endloop + endfacet + facet normal 0.455156 -0.832941 0.314711 + outer loop + vertex 649.505 120.755 56.7514 + vertex 653.084 125.183 63.2952 + vertex 647.71 122.012 62.6743 + endloop + endfacet + facet normal 0.446907 -0.835121 0.320698 + outer loop + vertex 654.513 123.463 56.8237 + vertex 653.084 125.183 63.2952 + vertex 649.505 120.755 56.7514 + endloop + endfacet + facet normal 0.445445 -0.83264 0.329074 + outer loop + vertex 649.505 120.755 56.7514 + vertex 650.912 119.53 51.746 + vertex 654.513 123.463 56.8237 + endloop + endfacet + facet normal 0.432459 -0.835036 0.340138 + outer loop + vertex 655.503 121.461 50.6522 + vertex 654.513 123.463 56.8237 + vertex 650.912 119.53 51.746 + endloop + endfacet + facet normal 0.470411 -0.814499 0.339567 + outer loop + vertex 655.503 121.461 50.6522 + vertex 660.125 126.718 56.8572 + vertex 654.513 123.463 56.8237 + endloop + endfacet + facet normal 0.471073 -0.815603 0.335979 + outer loop + vertex 660.125 126.718 56.8572 + vertex 658.518 128.578 63.6245 + vertex 654.513 123.463 56.8237 + endloop + endfacet + facet normal 0.447037 -0.818656 0.360499 + outer loop + vertex 662.177 125.307 51.1086 + vertex 660.125 126.718 56.8572 + vertex 655.503 121.461 50.6522 + endloop + endfacet + facet normal 0.487166 -0.811282 0.32325 + outer loop + vertex 654.513 123.463 56.8237 + vertex 658.518 128.578 63.6245 + vertex 653.084 125.183 63.2952 + endloop + endfacet + facet normal 0.489465 -0.813958 0.312883 + outer loop + vertex 658.518 128.578 63.6245 + vertex 657.098 130.506 70.8646 + vertex 653.084 125.183 63.2952 + endloop + endfacet + facet normal 0.502167 -0.809853 0.303261 + outer loop + vertex 653.084 125.183 63.2952 + vertex 657.098 130.506 70.8646 + vertex 651.65 126.932 70.3399 + endloop + endfacet + facet normal 0.505658 -0.813025 0.288619 + outer loop + vertex 657.098 130.506 70.8646 + vertex 655.941 132.462 78.399 + vertex 651.65 126.932 70.3399 + endloop + endfacet + facet normal 0.51742 -0.808811 0.279465 + outer loop + vertex 651.65 126.932 70.3399 + vertex 655.941 132.462 78.399 + vertex 650.459 128.769 77.8606 + endloop + endfacet + facet normal 0.52109 -0.811894 0.263237 + outer loop + vertex 655.941 132.462 78.399 + vertex 655.077 134.405 86.1019 + vertex 650.459 128.769 77.8606 + endloop + endfacet + facet normal 0.531701 -0.807794 0.254487 + outer loop + vertex 650.459 128.769 77.8606 + vertex 655.077 134.405 86.1019 + vertex 649.61 130.656 85.6254 + endloop + endfacet + facet normal 0.534864 -0.810436 0.238985 + outer loop + vertex 655.077 134.405 86.1019 + vertex 654.46 136.284 93.8574 + vertex 649.61 130.656 85.6254 + endloop + endfacet + facet normal 0.545681 -0.805943 0.229541 + outer loop + vertex 649.61 130.656 85.6254 + vertex 654.46 136.284 93.8574 + vertex 649.052 132.498 93.4182 + endloop + endfacet + facet normal 0.548232 -0.807997 0.215832 + outer loop + vertex 654.46 136.284 93.8574 + vertex 654.013 138.045 101.582 + vertex 649.052 132.498 93.4182 + endloop + endfacet + facet normal 0.557126 -0.804026 0.20773 + outer loop + vertex 649.052 132.498 93.4182 + vertex 654.013 138.045 101.582 + vertex 648.661 134.228 101.161 + endloop + endfacet + facet normal 0.559519 -0.805843 0.193791 + outer loop + vertex 654.013 138.045 101.582 + vertex 653.67 139.653 109.261 + vertex 648.661 134.228 101.161 + endloop + endfacet + facet normal 0.566709 -0.802406 0.187044 + outer loop + vertex 648.661 134.228 101.161 + vertex 653.67 139.653 109.261 + vertex 648.351 135.805 108.866 + endloop + endfacet + facet normal 0.569081 -0.804123 0.171851 + outer loop + vertex 653.67 139.653 109.261 + vertex 653.396 141.1 116.939 + vertex 648.351 135.805 108.866 + endloop + endfacet + facet normal 0.574566 -0.801325 0.166589 + outer loop + vertex 648.351 135.805 108.866 + vertex 653.396 141.1 116.939 + vertex 648.087 137.218 116.579 + endloop + endfacet + facet normal 0.576986 -0.803017 0.149168 + outer loop + vertex 653.396 141.1 116.939 + vertex 653.18 142.383 124.682 + vertex 648.087 137.218 116.579 + endloop + endfacet + facet normal 0.581268 -0.80069 0.144994 + outer loop + vertex 648.087 137.218 116.579 + vertex 653.18 142.383 124.682 + vertex 647.871 138.47 124.356 + endloop + endfacet + facet normal 0.58362 -0.802263 0.125547 + outer loop + vertex 653.18 142.383 124.682 + vertex 653.018 143.493 132.529 + vertex 647.871 138.47 124.356 + endloop + endfacet + facet normal 0.586231 -0.800756 0.122977 + outer loop + vertex 647.871 138.47 124.356 + vertex 653.018 143.493 132.529 + vertex 647.701 139.556 132.235 + endloop + endfacet + facet normal 0.588291 -0.802054 0.103067 + outer loop + vertex 653.018 143.493 132.529 + vertex 652.887 144.419 140.482 + vertex 647.701 139.556 132.235 + endloop + endfacet + facet normal 0.418224 -0.848131 0.325211 + outer loop + vertex 650.912 119.53 51.746 + vertex 649.505 120.755 56.7514 + vertex 646.783 117.468 51.681 + endloop + endfacet + facet normal 0.416661 -0.845293 0.334473 + outer loop + vertex 648.573 116.977 48.2094 + vertex 650.912 119.53 51.746 + vertex 646.783 117.468 51.681 + endloop + endfacet + facet normal 0.392041 -0.857992 0.331894 + outer loop + vertex 646.626 114.987 45.4856 + vertex 644.738 115.068 47.9249 + vertex 642.89 113.13 45.0989 + endloop + endfacet + facet normal 0.389498 -0.855047 0.342324 + outer loop + vertex 644.292 113.148 43.5486 + vertex 646.626 114.987 45.4856 + vertex 642.89 113.13 45.0989 + endloop + endfacet + facet normal 0.411178 -0.846257 0.338795 + outer loop + vertex 651.534 118.613 48.701 + vertex 650.912 119.53 51.746 + vertex 648.573 116.977 48.2094 + endloop + endfacet + facet normal 0.432441 -0.835182 0.339802 + outer loop + vertex 651.534 118.613 48.701 + vertex 655.503 121.461 50.6522 + vertex 650.912 119.53 51.746 + endloop + endfacet + facet normal 0.443395 -0.814067 0.375094 + outer loop + vertex 658.298 120.97 46.2811 + vertex 662.177 125.307 51.1086 + vertex 655.503 121.461 50.6522 + endloop + endfacet + facet normal 0.428615 -0.815716 0.388453 + outer loop + vertex 664.823 124.709 46.9335 + vertex 662.177 125.307 51.1086 + vertex 658.298 120.97 46.2811 + endloop + endfacet + facet normal 0.46314 -0.787663 0.406311 + outer loop + vertex 664.823 124.709 46.9335 + vertex 668.383 129.031 51.254 + vertex 662.177 125.307 51.1086 + endloop + endfacet + facet normal 0.466489 -0.792702 0.392442 + outer loop + vertex 668.383 129.031 51.254 + vertex 666.134 130.567 57.0293 + vertex 662.177 125.307 51.1086 + endloop + endfacet + facet normal 0.493672 -0.787271 0.369449 + outer loop + vertex 662.177 125.307 51.1086 + vertex 666.134 130.567 57.0293 + vertex 660.125 126.718 56.8572 + endloop + endfacet + facet normal 0.496121 -0.790621 0.358861 + outer loop + vertex 666.134 130.567 57.0293 + vertex 664.081 132.396 63.8969 + vertex 660.125 126.718 56.8572 + endloop + endfacet + facet normal 0.521049 -0.78333 0.338971 + outer loop + vertex 660.125 126.718 56.8572 + vertex 664.081 132.396 63.8969 + vertex 658.518 128.578 63.6245 + endloop + endfacet + facet normal 0.523453 -0.786101 0.328697 + outer loop + vertex 664.081 132.396 63.8969 + vertex 662.366 134.356 71.3171 + vertex 658.518 128.578 63.6245 + endloop + endfacet + facet normal 0.542438 -0.779201 0.314018 + outer loop + vertex 658.518 128.578 63.6245 + vertex 662.366 134.356 71.3171 + vertex 657.098 130.506 70.8646 + endloop + endfacet + facet normal 0.545974 -0.782358 0.299714 + outer loop + vertex 662.366 134.356 71.3171 + vertex 661.08 136.379 78.9386 + vertex 657.098 130.506 70.8646 + endloop + endfacet + facet normal 0.561301 -0.776047 0.287563 + outer loop + vertex 657.098 130.506 70.8646 + vertex 661.08 136.379 78.9386 + vertex 655.941 132.462 78.399 + endloop + endfacet + facet normal 0.565406 -0.779114 0.270734 + outer loop + vertex 661.08 136.379 78.9386 + vertex 660.15 138.373 86.62 + vertex 655.941 132.462 78.399 + endloop + endfacet + facet normal 0.57834 -0.773282 0.259919 + outer loop + vertex 655.941 132.462 78.399 + vertex 660.15 138.373 86.62 + vertex 655.077 134.405 86.1019 + endloop + endfacet + facet normal 0.582131 -0.775924 0.243035 + outer loop + vertex 660.15 138.373 86.62 + vertex 659.482 140.285 94.3236 + vertex 655.077 134.405 86.1019 + endloop + endfacet + facet normal 0.592366 -0.770942 0.233989 + outer loop + vertex 655.077 134.405 86.1019 + vertex 659.482 140.285 94.3236 + vertex 654.46 136.284 93.8574 + endloop + endfacet + facet normal 0.595555 -0.773108 0.218214 + outer loop + vertex 659.482 140.285 94.3236 + vertex 658.989 142.075 102.013 + vertex 654.46 136.284 93.8574 + endloop + endfacet + facet normal 0.604339 -0.76853 0.210086 + outer loop + vertex 654.46 136.284 93.8574 + vertex 658.989 142.075 102.013 + vertex 654.013 138.045 101.582 + endloop + endfacet + facet normal 0.607117 -0.770336 0.194913 + outer loop + vertex 658.989 142.075 102.013 + vertex 658.616 143.718 109.667 + vertex 654.013 138.045 101.582 + endloop + endfacet + facet normal 0.614365 -0.766308 0.18796 + outer loop + vertex 654.013 138.045 101.582 + vertex 658.616 143.718 109.667 + vertex 653.67 139.653 109.261 + endloop + endfacet + facet normal 0.617078 -0.767971 0.171566 + outer loop + vertex 658.616 143.718 109.667 + vertex 658.338 145.203 117.316 + vertex 653.67 139.653 109.261 + endloop + endfacet + facet normal 0.62236 -0.764849 0.166354 + outer loop + vertex 653.67 139.653 109.261 + vertex 658.338 145.203 117.316 + vertex 653.396 141.1 116.939 + endloop + endfacet + facet normal 0.625009 -0.766389 0.148367 + outer loop + vertex 658.338 145.203 117.316 + vertex 658.128 146.525 125.023 + vertex 653.396 141.1 116.939 + endloop + endfacet + facet normal 0.62923 -0.76374 0.144118 + outer loop + vertex 653.396 141.1 116.939 + vertex 658.128 146.525 125.023 + vertex 653.18 142.383 124.682 + endloop + endfacet + facet normal 0.631672 -0.765085 0.125042 + outer loop + vertex 658.128 146.525 125.023 + vertex 657.971 147.672 132.839 + vertex 653.18 142.383 124.682 + endloop + endfacet + facet normal 0.635654 -0.762435 0.120985 + outer loop + vertex 653.18 142.383 124.682 + vertex 657.971 147.672 132.839 + vertex 653.018 143.493 132.529 + endloop + endfacet + facet normal 0.637756 -0.763495 0.101698 + outer loop + vertex 657.971 147.672 132.839 + vertex 657.847 148.624 140.763 + vertex 653.018 143.493 132.529 + endloop + endfacet + facet normal 0.640162 -0.761804 0.0992336 + outer loop + vertex 653.018 143.493 132.529 + vertex 657.847 148.624 140.763 + vertex 652.887 144.419 140.482 + endloop + endfacet + facet normal 0.642042 -0.762636 0.0785384 + outer loop + vertex 657.847 148.624 140.763 + vertex 657.747 149.363 148.752 + vertex 652.887 144.419 140.482 + endloop + endfacet + facet normal 0.64336 -0.761663 0.0771827 + outer loop + vertex 652.887 144.419 140.482 + vertex 657.747 149.363 148.752 + vertex 652.784 145.144 148.493 + endloop + endfacet + facet normal 0.644972 -0.762208 0.0552377 + outer loop + vertex 657.747 149.363 148.752 + vertex 657.67 149.877 156.748 + vertex 652.784 145.144 148.493 + endloop + endfacet + facet normal 0.645014 -0.762175 0.0551938 + outer loop + vertex 652.784 145.144 148.493 + vertex 657.67 149.877 156.748 + vertex 652.707 145.659 156.505 + endloop + endfacet + facet normal 0.646309 -0.762387 0.032409 + outer loop + vertex 657.67 149.877 156.748 + vertex 657.612 150.166 164.711 + vertex 652.707 145.659 156.505 + endloop + endfacet + facet normal 0.645955 -0.762672 0.0327772 + outer loop + vertex 652.707 145.659 156.505 + vertex 657.612 150.166 164.711 + vertex 652.661 145.963 164.484 + endloop + endfacet + facet normal 0.646916 -0.76251 0.00878514 + outer loop + vertex 657.612 150.166 164.711 + vertex 657.594 150.242 172.637 + vertex 652.661 145.963 164.484 + endloop + endfacet + facet normal 0.645174 -0.763962 0.010601 + outer loop + vertex 652.661 145.963 164.484 + vertex 657.594 150.242 172.637 + vertex 652.644 146.059 172.43 + endloop + endfacet + facet normal 0.645743 -0.763431 -0.0137147 + outer loop + vertex 657.594 150.242 172.637 + vertex 657.601 150.106 180.552 + vertex 652.644 146.059 172.43 + endloop + endfacet + facet normal 0.643984 -0.764947 -0.0118857 + outer loop + vertex 652.644 146.059 172.43 + vertex 657.601 150.106 180.552 + vertex 652.659 145.948 180.368 + endloop + endfacet + facet normal 0.644137 -0.764034 -0.0365996 + outer loop + vertex 657.601 150.106 180.552 + vertex 657.643 149.762 188.481 + vertex 652.659 145.948 180.368 + endloop + endfacet + facet normal 0.641941 -0.765985 -0.0343331 + outer loop + vertex 652.659 145.948 180.368 + vertex 657.643 149.762 188.481 + vertex 652.704 145.63 188.322 + endloop + endfacet + facet normal 0.596572 -0.801774 -0.0355047 + outer loop + vertex 652.659 145.948 180.368 + vertex 652.704 145.63 188.322 + vertex 647.36 142.013 180.211 + endloop + endfacet + facet normal 0.64166 -0.764677 -0.0595137 + outer loop + vertex 657.643 149.762 188.481 + vertex 657.719 149.207 196.429 + vertex 652.704 145.63 188.322 + endloop + endfacet + facet normal 0.639441 -0.766706 -0.0572463 + outer loop + vertex 652.704 145.63 188.322 + vertex 657.719 149.207 196.429 + vertex 652.784 145.101 196.297 + endloop + endfacet + facet normal 0.594687 -0.80178 -0.0591237 + outer loop + vertex 652.704 145.63 188.322 + vertex 652.784 145.101 196.297 + vertex 647.406 141.709 188.189 + endloop + endfacet + facet normal 0.638712 -0.765014 -0.0824717 + outer loop + vertex 657.719 149.207 196.429 + vertex 657.822 148.436 204.38 + vertex 652.784 145.101 196.297 + endloop + endfacet + facet normal 0.636648 -0.766954 -0.0803846 + outer loop + vertex 652.784 145.101 196.297 + vertex 657.822 148.436 204.38 + vertex 652.894 144.356 204.275 + endloop + endfacet + facet normal 0.592129 -0.801557 -0.0830024 + outer loop + vertex 652.784 145.101 196.297 + vertex 652.894 144.356 204.275 + vertex 647.487 141.199 196.19 + endloop + endfacet + facet normal 0.635407 -0.764785 -0.106593 + outer loop + vertex 657.822 148.436 204.38 + vertex 657.965 147.45 212.303 + vertex 652.894 144.356 204.275 + endloop + endfacet + facet normal 0.632642 -0.767454 -0.103818 + outer loop + vertex 652.894 144.356 204.275 + vertex 657.965 147.45 212.303 + vertex 653.031 143.393 212.227 + endloop + endfacet + facet normal 0.588498 -0.801365 -0.107164 + outer loop + vertex 652.894 144.356 204.275 + vertex 653.031 143.393 212.227 + vertex 647.592 140.473 204.195 + endloop + endfacet + facet normal 0.630887 -0.764824 -0.130483 + outer loop + vertex 657.965 147.45 212.303 + vertex 658.142 146.255 220.162 + vertex 653.031 143.393 212.227 + endloop + endfacet + facet normal 0.627831 -0.767848 -0.127423 + outer loop + vertex 653.031 143.393 212.227 + vertex 658.142 146.255 220.162 + vertex 653.205 142.226 220.113 + endloop + endfacet + facet normal 0.584099 -0.800982 -0.131363 + outer loop + vertex 653.031 143.393 212.227 + vertex 653.205 142.226 220.113 + vertex 647.727 139.534 212.174 + endloop + endfacet + facet normal 0.625608 -0.764802 -0.153923 + outer loop + vertex 658.142 146.255 220.162 + vertex 658.372 144.882 227.92 + vertex 653.205 142.226 220.113 + endloop + endfacet + facet normal 0.622177 -0.76828 -0.150469 + outer loop + vertex 653.205 142.226 220.113 + vertex 658.372 144.882 227.92 + vertex 653.43 140.884 227.898 + endloop + endfacet + facet normal 0.444171 -0.789423 0.423702 + outer loop + vertex 670.746 128.055 46.9579 + vertex 668.383 129.031 51.254 + vertex 664.823 124.709 46.9335 + endloop + endfacet + facet normal 0.416263 -0.817889 0.397219 + outer loop + vertex 659.621 120.854 44.6567 + vertex 661.761 122.158 45.0986 + vertex 658.298 120.97 46.2811 + endloop + endfacet + facet normal 0.419443 -0.805105 0.419373 + outer loop + vertex 664.823 124.709 46.9335 + vertex 658.298 120.97 46.2811 + vertex 661.761 122.158 45.0986 + endloop + endfacet + facet normal 0.422462 -0.805705 0.415169 + outer loop + vertex 661.761 122.158 45.0986 + vertex 664.846 123.715 44.9807 + vertex 664.823 124.709 46.9335 + endloop + endfacet + facet normal 0.428371 -0.803201 0.413964 + outer loop + vertex 664.846 123.715 44.9807 + vertex 667.671 125.476 45.4747 + vertex 664.823 124.709 46.9335 + endloop + endfacet + facet normal 0.429693 -0.827663 0.361024 + outer loop + vertex 661.761 122.158 45.0986 + vertex 659.621 120.854 44.6567 + vertex 662.023 121.951 44.3134 + endloop + endfacet + facet normal 0.447448 -0.807352 0.384673 + outer loop + vertex 669.446 126.04 44.0778 + vertex 663.718 122.297 42.8848 + vertex 670.125 125.955 43.1111 + endloop + endfacet + facet normal 0.440756 -0.797341 0.412287 + outer loop + vertex 663.718 122.297 42.8848 + vertex 662.829 120.822 40.9823 + vertex 670.125 125.955 43.1111 + endloop + endfacet + facet normal 0.414821 -0.782248 0.464771 + outer loop + vertex 670.125 125.955 43.1111 + vertex 662.829 120.822 40.9823 + vertex 671.043 125.445 41.4329 + endloop + endfacet + facet normal 0.412695 -0.779158 0.471801 + outer loop + vertex 662.829 120.822 40.9823 + vertex 665.495 120.887 38.7595 + vertex 671.043 125.445 41.4329 + endloop + endfacet + facet normal 0.393474 -0.771908 0.499335 + outer loop + vertex 671.043 125.445 41.4329 + vertex 665.495 120.887 38.7595 + vertex 672.783 124.963 39.3168 + endloop + endfacet + facet normal 0.413005 -0.753694 0.511246 + outer loop + vertex 671.043 125.445 41.4329 + vertex 672.783 124.963 39.3168 + vertex 679.171 130.119 41.7571 + endloop + endfacet + facet normal 0.407776 -0.74569 0.526939 + outer loop + vertex 678.178 130.763 43.4372 + vertex 671.043 125.445 41.4329 + vertex 679.171 130.119 41.7571 + endloop + endfacet + facet normal 0.394737 -0.773658 0.495616 + outer loop + vertex 665.495 120.887 38.7595 + vertex 668.167 121.05 36.8858 + vertex 672.783 124.963 39.3168 + endloop + endfacet + facet normal 0.378558 -0.767794 0.516901 + outer loop + vertex 672.783 124.963 39.3168 + vertex 668.167 121.05 36.8858 + vertex 674.41 124.14 36.9026 + endloop + endfacet + facet normal 0.394941 -0.754928 0.523552 + outer loop + vertex 672.783 124.963 39.3168 + vertex 674.41 124.14 36.9026 + vertex 680.429 129.11 39.5294 + endloop + endfacet + facet normal 0.385573 -0.73913 0.552287 + outer loop + vertex 679.171 130.119 41.7571 + vertex 672.783 124.963 39.3168 + vertex 680.429 129.11 39.5294 + endloop + endfacet + facet normal 0.386097 -0.782873 0.487892 + outer loop + vertex 668.167 121.05 36.8858 + vertex 668.528 119.435 34.0087 + vertex 674.41 124.14 36.9026 + endloop + endfacet + facet normal 0.355288 -0.770126 0.529789 + outer loop + vertex 674.41 124.14 36.9026 + vertex 668.528 119.435 34.0087 + vertex 676.243 123.376 34.5629 + endloop + endfacet + facet normal 0.372052 -0.75614 0.538358 + outer loop + vertex 674.41 124.14 36.9026 + vertex 676.243 123.376 34.5629 + vertex 681.837 127.912 37.0674 + endloop + endfacet + facet normal 0.3628 -0.739193 0.567424 + outer loop + vertex 680.429 129.11 39.5294 + vertex 674.41 124.14 36.9026 + vertex 681.837 127.912 37.0674 + endloop + endfacet + facet normal 0.382361 -0.725664 0.572024 + outer loop + vertex 680.429 129.11 39.5294 + vertex 681.837 127.912 37.0674 + vertex 687.087 132.544 39.435 + endloop + endfacet + facet normal 0.356265 -0.771636 0.526928 + outer loop + vertex 676.243 123.376 34.5629 + vertex 668.528 119.435 34.0087 + vertex 672.178 120.025 32.4034 + endloop + endfacet + facet normal 0.34006 -0.764933 0.547024 + outer loop + vertex 678.118 122.87 32.6902 + vertex 676.243 123.376 34.5629 + vertex 672.178 120.025 32.4034 + endloop + endfacet + facet normal 0.343112 -0.770338 0.537451 + outer loop + vertex 672.178 120.025 32.4034 + vertex 674.067 120.033 31.2094 + vertex 678.118 122.87 32.6902 + endloop + endfacet + facet normal 0.328235 -0.760799 0.559863 + outer loop + vertex 678.118 122.87 32.6902 + vertex 674.067 120.033 31.2094 + vertex 679.124 122.291 31.3135 + endloop + endfacet + facet normal 0.33437 -0.756225 0.562423 + outer loop + vertex 684.513 125.72 32.7202 + vertex 678.118 122.87 32.6902 + vertex 679.124 122.291 31.3135 + endloop + endfacet + facet normal 0.317597 -0.741563 0.590945 + outer loop + vertex 684.408 124.433 31.1608 + vertex 684.513 125.72 32.7202 + vertex 679.124 122.291 31.3135 + endloop + endfacet + facet normal 0.322713 -0.755689 0.569904 + outer loop + vertex 679.124 122.291 31.3135 + vertex 679.225 121.824 30.6358 + vertex 684.408 124.433 31.1608 + endloop + endfacet + facet normal 0.321954 -0.754567 0.571816 + outer loop + vertex 679.225 121.824 30.6358 + vertex 678.931 121.426 30.277 + vertex 684.408 124.433 31.1608 + endloop + endfacet + facet normal 0.304837 -0.733776 0.607163 + outer loop + vertex 684.408 124.433 31.1608 + vertex 678.931 121.426 30.277 + vertex 686.51 124.693 30.4193 + endloop + endfacet + facet normal 0.306047 -0.729023 0.612259 + outer loop + vertex 684.408 124.433 31.1608 + vertex 686.51 124.693 30.4193 + vertex 690.55 126.984 31.1282 + endloop + endfacet + facet normal 0.304503 -0.725238 0.617501 + outer loop + vertex 684.408 124.433 31.1608 + vertex 690.55 126.984 31.1282 + vertex 691.163 128.395 32.4829 + endloop + endfacet + facet normal 0.302036 -0.725281 0.618662 + outer loop + vertex 690.55 126.984 31.1282 + vertex 695.221 129.238 31.4909 + vertex 691.163 128.395 32.4829 + endloop + endfacet + facet normal 0.302717 -0.715007 0.630181 + outer loop + vertex 695.338 130.339 32.683 + vertex 691.163 128.395 32.4829 + vertex 695.221 129.238 31.4909 + endloop + endfacet + facet normal 0.315564 -0.712552 0.626648 + outer loop + vertex 695.221 129.238 31.4909 + vertex 697.478 131.413 32.8269 + vertex 695.338 130.339 32.683 + endloop + endfacet + facet normal 0.31041 -0.70392 0.63886 + outer loop + vertex 694.588 131.228 34.0268 + vertex 695.338 130.339 32.683 + vertex 697.478 131.413 32.8269 + endloop + endfacet + facet normal 0.318992 -0.676523 0.663747 + outer loop + vertex 697.478 131.413 32.8269 + vertex 697.293 133.642 35.1879 + vertex 694.588 131.228 34.0268 + endloop + endfacet + facet normal 0.330472 -0.68329 0.651078 + outer loop + vertex 693.326 132.827 36.3469 + vertex 694.588 131.228 34.0268 + vertex 697.293 133.642 35.1879 + endloop + endfacet + facet normal 0.33329 -0.645168 0.687514 + outer loop + vertex 697.293 133.642 35.1879 + vertex 696.14 135.99 37.9503 + vertex 693.326 132.827 36.3469 + endloop + endfacet + facet normal 0.362268 -0.657391 0.660756 + outer loop + vertex 692.125 134.759 38.9268 + vertex 693.326 132.827 36.3469 + vertex 696.14 135.99 37.9503 + endloop + endfacet + facet normal 0.359525 -0.617972 0.69918 + outer loop + vertex 696.14 135.99 37.9503 + vertex 695.172 138.262 40.4561 + vertex 692.125 134.759 38.9268 + endloop + endfacet + facet normal 0.401369 -0.636609 0.658507 + outer loop + vertex 691.206 136.681 41.3446 + vertex 692.125 134.759 38.9268 + vertex 695.172 138.262 40.4561 + endloop + endfacet + facet normal 0.395753 -0.603646 0.692092 + outer loop + vertex 695.172 138.262 40.4561 + vertex 694.4 140.172 42.5633 + vertex 691.206 136.681 41.3446 + endloop + endfacet + facet normal 0.438169 -0.626032 0.645052 + outer loop + vertex 690.416 138.141 43.2991 + vertex 691.206 136.681 41.3446 + vertex 694.4 140.172 42.5633 + endloop + endfacet + facet normal 0.425901 -0.585867 0.68947 + outer loop + vertex 694.4 140.172 42.5633 + vertex 693.443 141.438 44.2301 + vertex 690.416 138.141 43.2991 + endloop + endfacet + facet normal 0.46624 -0.609322 0.641364 + outer loop + vertex 689.245 138.444 44.4377 + vertex 690.416 138.141 43.2991 + vertex 693.443 141.438 44.2301 + endloop + endfacet + facet normal 0.459501 -0.598864 0.655912 + outer loop + vertex 689.505 139.369 45.0998 + vertex 689.245 138.444 44.4377 + vertex 693.443 141.438 44.2301 + endloop + endfacet + facet normal 0.443856 -0.546182 0.710406 + outer loop + vertex 693.443 141.438 44.2301 + vertex 693.15 143.184 45.7555 + vertex 689.505 139.369 45.0998 + endloop + endfacet + facet normal 0.510278 -0.594374 0.621558 + outer loop + vertex 693.15 143.184 45.7555 + vertex 689.02 139.796 45.9062 + vertex 689.505 139.369 45.0998 + endloop + endfacet + facet normal 0.462637 -0.538001 0.704643 + outer loop + vertex 693.15 143.184 45.7555 + vertex 693.443 141.438 44.2301 + vertex 695.412 143.344 44.3931 + endloop + endfacet + facet normal 0.466035 -0.52557 0.71175 + outer loop + vertex 696.23 143.898 44.2665 + vertex 693.15 143.184 45.7555 + vertex 695.412 143.344 44.3931 + endloop + endfacet + facet normal 0.453426 -0.52954 0.716933 + outer loop + vertex 696.683 143.587 43.769 + vertex 695.412 143.344 44.3931 + vertex 693.443 141.438 44.2301 + endloop + endfacet + facet normal 0.441432 -0.50635 0.740775 + outer loop + vertex 697.507 143.068 42.9228 + vertex 696.683 143.587 43.769 + vertex 693.443 141.438 44.2301 + endloop + endfacet + facet normal 0.436719 -0.512023 0.739668 + outer loop + vertex 696.683 143.587 43.769 + vertex 697.507 143.068 42.9228 + vertex 699.962 144.932 42.7637 + endloop + endfacet + facet normal 0.45642 -0.504921 0.732623 + outer loop + vertex 696.683 143.587 43.769 + vertex 697.919 144.402 43.5598 + vertex 695.412 143.344 44.3931 + endloop + endfacet + facet normal 0.404344 -0.604916 0.685991 + outer loop + vertex 689.505 139.369 45.0998 + vertex 684.607 135.524 44.597 + vertex 689.245 138.444 44.4377 + endloop + endfacet + facet normal 0.449614 -0.567897 0.689449 + outer loop + vertex 693.443 141.438 44.2301 + vertex 694.4 140.172 42.5633 + vertex 697.507 143.068 42.9228 + endloop + endfacet + facet normal 0.391149 -0.654333 0.647187 + outer loop + vertex 690.416 138.141 43.2991 + vertex 686.106 134.049 41.7665 + vertex 691.206 136.681 41.3446 + endloop + endfacet + facet normal 0.428842 -0.585618 0.687856 + outer loop + vertex 694.4 140.172 42.5633 + vertex 695.172 138.262 40.4561 + vertex 698.62 141.779 41.3008 + endloop + endfacet + facet normal 0.423936 -0.5446 0.723663 + outer loop + vertex 698.62 141.779 41.3008 + vertex 697.507 143.068 42.9228 + vertex 694.4 140.172 42.5633 + endloop + endfacet + facet normal 0.419635 -0.548121 0.723512 + outer loop + vertex 698.62 141.779 41.3008 + vertex 703.467 145.515 41.3193 + vertex 697.507 143.068 42.9228 + endloop + endfacet + facet normal 0.394339 -0.561339 0.727595 + outer loop + vertex 699.388 139.604 39.206 + vertex 698.62 141.779 41.3008 + vertex 695.172 138.262 40.4561 + endloop + endfacet + facet normal 0.399172 -0.558901 0.726837 + outer loop + vertex 699.388 139.604 39.206 + vertex 704.301 143.897 39.8099 + vertex 698.62 141.779 41.3008 + endloop + endfacet + facet normal 0.356969 -0.66045 0.66059 + outer loop + vertex 691.206 136.681 41.3446 + vertex 687.087 132.544 39.435 + vertex 692.125 134.759 38.9268 + endloop + endfacet + facet normal 0.396788 -0.598515 0.695945 + outer loop + vertex 695.172 138.262 40.4561 + vertex 696.14 135.99 37.9503 + vertex 699.388 139.604 39.206 + endloop + endfacet + facet normal 0.368825 -0.583081 0.723868 + outer loop + vertex 700.391 136.956 36.5628 + vertex 699.388 139.604 39.206 + vertex 696.14 135.99 37.9503 + endloop + endfacet + facet normal 0.376069 -0.579494 0.723021 + outer loop + vertex 700.391 136.956 36.5628 + vertex 704.996 141.585 37.8773 + vertex 699.388 139.604 39.206 + endloop + endfacet + facet normal 0.329951 -0.67558 0.659335 + outer loop + vertex 692.125 134.759 38.9268 + vertex 688.298 130.935 36.9236 + vertex 693.326 132.827 36.3469 + endloop + endfacet + facet normal 0.366808 -0.627682 0.686635 + outer loop + vertex 696.14 135.99 37.9503 + vertex 697.293 133.642 35.1879 + vertex 700.391 136.956 36.5628 + endloop + endfacet + facet normal 0.354097 -0.621031 0.699239 + outer loop + vertex 701.218 133.389 32.9757 + vertex 700.391 136.956 36.5628 + vertex 697.293 133.642 35.1879 + endloop + endfacet + facet normal 0.351783 -0.621935 0.699604 + outer loop + vertex 701.218 133.389 32.9757 + vertex 705.931 138.79 35.4073 + vertex 700.391 136.956 36.5628 + endloop + endfacet + facet normal 0.311631 -0.694472 0.648533 + outer loop + vertex 693.326 132.827 36.3469 + vertex 689.666 129.498 34.5398 + vertex 694.588 131.228 34.0268 + endloop + endfacet + facet normal 0.329556 -0.673469 0.661689 + outer loop + vertex 697.293 133.642 35.1879 + vertex 697.478 131.413 32.8269 + vertex 701.218 133.389 32.9757 + endloop + endfacet + facet normal 0.336859 -0.686025 0.644899 + outer loop + vertex 697.478 131.413 32.8269 + vertex 698.228 129.699 30.612 + vertex 701.218 133.389 32.9757 + endloop + endfacet + facet normal 0.287416 -0.670801 0.683679 + outer loop + vertex 700.712 130.026 29.8892 + vertex 701.218 133.389 32.9757 + vertex 698.228 129.699 30.612 + endloop + endfacet + facet normal 0.283568 -0.697049 0.658568 + outer loop + vertex 699.321 128.833 29.2249 + vertex 700.712 130.026 29.8892 + vertex 698.228 129.699 30.612 + endloop + endfacet + facet normal 0.273773 -0.704076 0.655229 + outer loop + vertex 698.228 129.699 30.612 + vertex 696.587 127.165 28.5752 + vertex 699.321 128.833 29.2249 + endloop + endfacet + facet normal 0.269197 -0.699293 0.66221 + outer loop + vertex 699.589 127.995 28.2314 + vertex 699.321 128.833 29.2249 + vertex 696.587 127.165 28.5752 + endloop + endfacet + facet normal 0.268346 -0.693609 0.668503 + outer loop + vertex 696.587 127.165 28.5752 + vertex 697.013 125.711 26.8957 + vertex 699.589 127.995 28.2314 + endloop + endfacet + facet normal 0.264499 -0.691462 0.67225 + outer loop + vertex 700.031 127.164 27.202 + vertex 699.589 127.995 28.2314 + vertex 697.013 125.711 26.8957 + endloop + endfacet + facet normal 0.2664 -0.690609 0.672377 + outer loop + vertex 700.031 127.164 27.202 + vertex 701.5 128.891 28.394 + vertex 699.589 127.995 28.2314 + endloop + endfacet + facet normal 0.268241 -0.693806 0.668341 + outer loop + vertex 701.5 128.891 28.394 + vertex 700.712 130.026 29.8892 + vertex 699.589 127.995 28.2314 + endloop + endfacet + facet normal 0.293961 -0.680165 0.671538 + outer loop + vertex 701.5 128.891 28.394 + vertex 703.45 131.691 30.377 + vertex 700.712 130.026 29.8892 + endloop + endfacet + facet normal 0.277177 -0.676259 0.682529 + outer loop + vertex 703.942 129.869 28.3709 + vertex 703.45 131.691 30.377 + vertex 701.5 128.891 28.394 + endloop + endfacet + facet normal 0.280569 -0.684973 0.672378 + outer loop + vertex 701.614 127.601 27.0328 + vertex 703.942 129.869 28.3709 + vertex 701.5 128.891 28.394 + endloop + endfacet + facet normal 0.27149 -0.680499 0.680598 + outer loop + vertex 703.857 128.316 26.8532 + vertex 703.942 129.869 28.3709 + vertex 701.614 127.601 27.0328 + endloop + endfacet + facet normal 0.284753 -0.678183 0.677483 + outer loop + vertex 703.857 128.316 26.8532 + vertex 707.392 130.914 27.9675 + vertex 703.942 129.869 28.3709 + endloop + endfacet + facet normal 0.280842 -0.656576 0.700025 + outer loop + vertex 707.392 130.914 27.9675 + vertex 707.945 133.479 30.1514 + vertex 703.942 129.869 28.3709 + endloop + endfacet + facet normal 0.29077 -0.655843 0.696651 + outer loop + vertex 707.945 133.479 30.1514 + vertex 707.392 130.914 27.9675 + vertex 714.445 135.377 29.2251 + endloop + endfacet + facet normal 0.280873 -0.64433 0.711301 + outer loop + vertex 707.392 130.914 27.9675 + vertex 710.095 131.062 27.0347 + vertex 714.445 135.377 29.2251 + endloop + endfacet + facet normal 0.258447 -0.631665 0.730893 + outer loop + vertex 714.047 132.812 27.1497 + vertex 714.445 135.377 29.2251 + vertex 710.095 131.062 27.0347 + endloop + endfacet + facet normal 0.268469 -0.652814 0.708349 + outer loop + vertex 712.232 130.794 25.9775 + vertex 714.047 132.812 27.1497 + vertex 710.095 131.062 27.0347 + endloop + endfacet + facet normal 0.26681 -0.65619 0.705852 + outer loop + vertex 712.232 130.794 25.9775 + vertex 710.095 131.062 27.0347 + vertex 707.928 128.841 25.7888 + endloop + endfacet + facet normal 0.267592 -0.656582 0.705191 + outer loop + vertex 707.928 128.841 25.7888 + vertex 710.095 131.062 27.0347 + vertex 706.325 129.042 26.5839 + endloop + endfacet + facet normal 0.266286 -0.65922 0.703222 + outer loop + vertex 707.928 128.841 25.7888 + vertex 706.325 129.042 26.5839 + vertex 704.046 127.268 25.7844 + endloop + endfacet + facet normal 0.270962 -0.662868 0.697987 + outer loop + vertex 704.046 127.268 25.7844 + vertex 706.325 129.042 26.5839 + vertex 703.857 128.316 26.8532 + endloop + endfacet + facet normal 0.262864 -0.665212 0.698853 + outer loop + vertex 704.046 127.268 25.7844 + vertex 703.857 128.316 26.8532 + vertex 701.687 126.635 26.0687 + endloop + endfacet + facet normal 0.269034 -0.66995 0.691945 + outer loop + vertex 701.687 126.635 26.0687 + vertex 703.857 128.316 26.8532 + vertex 701.614 127.601 27.0328 + endloop + endfacet + facet normal 0.260312 -0.671978 0.693313 + outer loop + vertex 701.687 126.635 26.0687 + vertex 701.614 127.601 27.0328 + vertex 699.542 125.933 26.1941 + endloop + endfacet + facet normal 0.259878 -0.671671 0.693773 + outer loop + vertex 699.542 125.933 26.1941 + vertex 701.614 127.601 27.0328 + vertex 700.031 127.164 27.202 + endloop + endfacet + facet normal 0.252272 -0.671266 0.696966 + outer loop + vertex 699.542 125.933 26.1941 + vertex 700.031 127.164 27.202 + vertex 697.013 125.711 26.8957 + endloop + endfacet + facet normal 0.254796 -0.655275 0.711121 + outer loop + vertex 697.013 125.711 26.8957 + vertex 695.738 123.893 25.677 + vertex 699.542 125.933 26.1941 + endloop + endfacet + facet normal 0.238219 -0.650433 0.721241 + outer loop + vertex 695.738 123.893 25.677 + vertex 697.013 125.711 26.8957 + vertex 693.24 123.5 26.1476 + endloop + endfacet + facet normal 0.238372 -0.629903 0.73919 + outer loop + vertex 693.24 123.5 26.1476 + vertex 691.994 122.484 25.6833 + vertex 695.738 123.893 25.677 + endloop + endfacet + facet normal 0.227094 -0.59982 0.767231 + outer loop + vertex 691.994 122.484 25.6833 + vertex 691.686 121.954 25.3601 + vertex 695.738 123.893 25.677 + endloop + endfacet + facet normal 0.23668 -0.602388 0.762307 + outer loop + vertex 691.994 122.484 25.6833 + vertex 687.172 120.456 25.5779 + vertex 691.686 121.954 25.3601 + endloop + endfacet + facet normal 0.237244 -0.604339 0.760585 + outer loop + vertex 691.686 121.954 25.3601 + vertex 687.172 120.456 25.5779 + vertex 687.854 120.191 25.1547 + endloop + endfacet + facet normal 0.237515 -0.603971 0.760792 + outer loop + vertex 687.854 120.191 25.1547 + vertex 687.172 120.456 25.5779 + vertex 679.014 116.793 25.217 + endloop + endfacet + facet normal 0.257401 -0.644261 0.720189 + outer loop + vertex 681.214 118.914 26.3279 + vertex 679.014 116.793 25.217 + vertex 687.172 120.456 25.5779 + endloop + endfacet + facet normal 0.256074 -0.634871 0.728948 + outer loop + vertex 688.954 121.64 25.9834 + vertex 681.214 118.914 26.3279 + vertex 687.172 120.456 25.5779 + endloop + endfacet + facet normal 0.261629 -0.652937 0.71079 + outer loop + vertex 688.954 121.64 25.9834 + vertex 688.554 122.064 26.5199 + vertex 681.214 118.914 26.3279 + endloop + endfacet + facet normal 0.275318 -0.682762 0.676784 + outer loop + vertex 682.436 120.464 27.3952 + vertex 681.214 118.914 26.3279 + vertex 688.554 122.064 26.5199 + endloop + endfacet + facet normal 0.274826 -0.678353 0.681402 + outer loop + vertex 689.712 123.089 27.0733 + vertex 682.436 120.464 27.3952 + vertex 688.554 122.064 26.5199 + endloop + endfacet + facet normal 0.266175 -0.673176 0.689917 + outer loop + vertex 693.063 124.04 26.7083 + vertex 689.712 123.089 27.0733 + vertex 688.554 122.064 26.5199 + endloop + endfacet + facet normal 0.257068 -0.654415 0.711095 + outer loop + vertex 693.063 124.04 26.7083 + vertex 688.554 122.064 26.5199 + vertex 693.24 123.5 26.1476 + endloop + endfacet + facet normal 0.268989 -0.689966 0.672005 + outer loop + vertex 693.582 124.95 27.4353 + vertex 689.712 123.089 27.0733 + vertex 693.063 124.04 26.7083 + endloop + endfacet + facet normal 0.259287 -0.688594 0.677206 + outer loop + vertex 693.582 124.95 27.4353 + vertex 693.063 124.04 26.7083 + vertex 697.013 125.711 26.8957 + endloop + endfacet + facet normal 0.279216 -0.706921 0.649847 + outer loop + vertex 693.582 124.95 27.4353 + vertex 688.431 123.243 27.7911 + vertex 689.712 123.089 27.0733 + endloop + endfacet + facet normal 0.27859 -0.704409 0.652837 + outer loop + vertex 692.46 125.22 28.2047 + vertex 688.431 123.243 27.7911 + vertex 693.582 124.95 27.4353 + endloop + endfacet + facet normal 0.275617 -0.708312 0.649869 + outer loop + vertex 692.46 125.22 28.2047 + vertex 693.582 124.95 27.4353 + vertex 696.587 127.165 28.5752 + endloop + endfacet + facet normal 0.283448 -0.721475 0.631769 + outer loop + vertex 692.505 125.855 28.9108 + vertex 692.46 125.22 28.2047 + vertex 696.587 127.165 28.5752 + endloop + endfacet + facet normal 0.28175 -0.713761 0.64122 + outer loop + vertex 696.587 127.165 28.5752 + vertex 694.339 127.359 29.7782 + vertex 692.505 125.855 28.9108 + endloop + endfacet + facet normal 0.29403 -0.720882 0.627596 + outer loop + vertex 694.339 127.359 29.7782 + vertex 687.698 124.44 29.5363 + vertex 692.505 125.855 28.9108 + endloop + endfacet + facet normal 0.29565 -0.732996 0.612624 + outer loop + vertex 687.935 123.793 28.6486 + vertex 692.505 125.855 28.9108 + vertex 687.698 124.44 29.5363 + endloop + endfacet + facet normal 0.29709 -0.732434 0.6126 + outer loop + vertex 687.935 123.793 28.6486 + vertex 687.698 124.44 29.5363 + vertex 682.193 121.913 29.1856 + endloop + endfacet + facet normal 0.297688 -0.735343 0.608813 + outer loop + vertex 682.076 121.218 28.403 + vertex 687.935 123.793 28.6486 + vertex 682.193 121.913 29.1856 + endloop + endfacet + facet normal 0.298273 -0.735248 0.608641 + outer loop + vertex 682.193 121.913 29.1856 + vertex 676.524 119.543 29.1006 + vertex 682.076 121.218 28.403 + endloop + endfacet + facet normal 0.299098 -0.741156 0.601022 + outer loop + vertex 682.076 121.218 28.403 + vertex 676.524 119.543 29.1006 + vertex 675.296 118.48 28.4012 + endloop + endfacet + facet normal 0.301421 -0.742215 0.598551 + outer loop + vertex 676.524 119.543 29.1006 + vertex 671.575 117.6 29.1828 + vertex 675.296 118.48 28.4012 + endloop + endfacet + facet normal 0.301174 -0.751881 0.586489 + outer loop + vertex 675.296 118.48 28.4012 + vertex 671.575 117.6 29.1828 + vertex 670.188 116.647 28.6743 + endloop + endfacet + facet normal 0.294083 -0.727064 0.620398 + outer loop + vertex 670.188 116.647 28.6743 + vertex 671.673 116.368 27.6435 + vertex 675.296 118.48 28.4012 + endloop + endfacet + facet normal 0.289166 -0.721688 0.628927 + outer loop + vertex 671.673 116.368 27.6435 + vertex 682.436 120.464 27.3952 + vertex 675.296 118.48 28.4012 + endloop + endfacet + facet normal 0.288384 -0.714648 0.63727 + outer loop + vertex 682.076 121.218 28.403 + vertex 675.296 118.48 28.4012 + vertex 682.436 120.464 27.3952 + endloop + endfacet + facet normal 0.288988 -0.714386 0.63729 + outer loop + vertex 682.076 121.218 28.403 + vertex 682.436 120.464 27.3952 + vertex 688.431 123.243 27.7911 + endloop + endfacet + facet normal 0.290169 -0.720266 0.630094 + outer loop + vertex 687.935 123.793 28.6486 + vertex 682.076 121.218 28.403 + vertex 688.431 123.243 27.7911 + endloop + endfacet + facet normal 0.291625 -0.730314 0.617736 + outer loop + vertex 671.673 116.368 27.6435 + vertex 670.188 116.647 28.6743 + vertex 667.134 115.445 28.6943 + endloop + endfacet + facet normal 0.29091 -0.740896 0.605347 + outer loop + vertex 671.673 116.368 27.6435 + vertex 667.134 115.445 28.6943 + vertex 665.474 114.397 28.2101 + endloop + endfacet + facet normal 0.287057 -0.721739 0.629835 + outer loop + vertex 665.474 114.397 28.2101 + vertex 665.054 113.347 27.1979 + vertex 671.673 116.368 27.6435 + endloop + endfacet + facet normal 0.274895 -0.699493 0.659654 + outer loop + vertex 670.681 114.708 26.2964 + vertex 671.673 116.368 27.6435 + vertex 665.054 113.347 27.1979 + endloop + endfacet + facet normal 0.2745 -0.693768 0.665835 + outer loop + vertex 665.054 113.347 27.1979 + vertex 662.637 111.358 26.122 + vertex 670.681 114.708 26.2964 + endloop + endfacet + facet normal 0.275539 -0.694427 0.664717 + outer loop + vertex 665.054 113.347 27.1979 + vertex 661.078 111.533 26.9506 + vertex 662.637 111.358 26.122 + endloop + endfacet + facet normal 0.274901 -0.695593 0.663762 + outer loop + vertex 662.637 111.358 26.122 + vertex 661.078 111.533 26.9506 + vertex 659.352 110.225 26.2955 + endloop + endfacet + facet normal 0.277468 -0.699849 0.658197 + outer loop + vertex 681.214 118.914 26.3279 + vertex 671.673 116.368 27.6435 + vertex 670.681 114.708 26.2964 + endloop + endfacet + facet normal 0.291903 -0.721638 0.62772 + outer loop + vertex 665.474 114.397 28.2101 + vertex 663.057 113.219 27.9802 + vertex 665.054 113.347 27.1979 + endloop + endfacet + facet normal 0.291266 -0.72358 0.625776 + outer loop + vertex 665.054 113.347 27.1979 + vertex 663.057 113.219 27.9802 + vertex 661.078 111.533 26.9506 + endloop + endfacet + facet normal 0.303254 -0.739673 0.600767 + outer loop + vertex 665.474 114.397 28.2101 + vertex 664.291 114.321 28.7129 + vertex 663.057 113.219 27.9802 + endloop + endfacet + facet normal 0.384452 -0.76988 0.509394 + outer loop + vertex 663.057 113.219 27.9802 + vertex 664.291 114.321 28.7129 + vertex 664.073 114.405 29.0056 + endloop + endfacet + facet normal 0.3531 -0.794991 0.493264 + outer loop + vertex 664.291 114.321 28.7129 + vertex 665.659 115.245 29.2234 + vertex 664.073 114.405 29.0056 + endloop + endfacet + facet normal 0.347139 -0.787771 0.508834 + outer loop + vertex 665.937 115.68 29.7079 + vertex 664.073 114.405 29.0056 + vertex 665.659 115.245 29.2234 + endloop + endfacet + facet normal 0.325588 -0.788463 0.521842 + outer loop + vertex 665.659 115.245 29.2234 + vertex 667.151 116.214 29.7562 + vertex 665.937 115.68 29.7079 + endloop + endfacet + facet normal 0.327 -0.791218 0.516764 + outer loop + vertex 667.151 116.214 29.7562 + vertex 666.871 116.245 29.9815 + vertex 665.937 115.68 29.7079 + endloop + endfacet + facet normal 0.337525 -0.799209 0.497334 + outer loop + vertex 665.937 115.68 29.7079 + vertex 666.871 116.245 29.9815 + vertex 666.552 116.196 30.1199 + endloop + endfacet + facet normal 0.331873 -0.812219 0.479751 + outer loop + vertex 666.871 116.245 29.9815 + vertex 668.484 116.911 29.9935 + vertex 666.552 116.196 30.1199 + endloop + endfacet + facet normal 0.332708 -0.815596 0.473401 + outer loop + vertex 669.642 117.413 30.0447 + vertex 666.552 116.196 30.1199 + vertex 668.484 116.911 29.9935 + endloop + endfacet + facet normal 0.331835 -0.813935 0.47686 + outer loop + vertex 669.642 117.413 30.0447 + vertex 668.484 116.911 29.9935 + vertex 672.859 118.647 29.9125 + endloop + endfacet + facet normal 0.330815 -0.810595 0.483215 + outer loop + vertex 671.964 118.342 30.0126 + vertex 669.642 117.413 30.0447 + vertex 672.859 118.647 29.9125 + endloop + endfacet + facet normal 0.328709 -0.796445 0.507568 + outer loop + vertex 675.448 119.789 30.0264 + vertex 671.964 118.342 30.0126 + vertex 672.859 118.647 29.9125 + endloop + endfacet + facet normal 0.322843 -0.785216 0.528403 + outer loop + vertex 672.859 118.647 29.9125 + vertex 680.8 121.921 29.9249 + vertex 675.448 119.789 30.0264 + endloop + endfacet + facet normal 0.312538 -0.757201 0.573556 + outer loop + vertex 678.869 121.223 30.0555 + vertex 675.448 119.789 30.0264 + vertex 680.8 121.921 29.9249 + endloop + endfacet + facet normal 0.310054 -0.747795 0.587086 + outer loop + vertex 681.83 122.508 30.1282 + vertex 678.869 121.223 30.0555 + vertex 680.8 121.921 29.9249 + endloop + endfacet + facet normal 0.308404 -0.745991 0.590241 + outer loop + vertex 684.982 123.826 30.1475 + vertex 681.83 122.508 30.1282 + vertex 680.8 121.921 29.9249 + endloop + endfacet + facet normal 0.304964 -0.73958 0.600015 + outer loop + vertex 680.8 121.921 29.9249 + vertex 687.904 124.962 30.0632 + vertex 684.982 123.826 30.1475 + endloop + endfacet + facet normal 0.301775 -0.730441 0.612689 + outer loop + vertex 687.528 124.936 30.2179 + vertex 684.982 123.826 30.1475 + vertex 687.904 124.962 30.0632 + endloop + endfacet + facet normal 0.302375 -0.728727 0.614431 + outer loop + vertex 689.587 125.831 30.2648 + vertex 687.528 124.936 30.2179 + vertex 687.904 124.962 30.0632 + endloop + endfacet + facet normal 0.299766 -0.724986 0.620109 + outer loop + vertex 690.975 126.355 30.207 + vertex 689.587 125.831 30.2648 + vertex 687.904 124.962 30.0632 + endloop + endfacet + facet normal 0.298912 -0.723344 0.622434 + outer loop + vertex 691.335 126.339 30.0158 + vertex 690.975 126.355 30.207 + vertex 687.904 124.962 30.0632 + endloop + endfacet + facet normal 0.302624 -0.73305 0.609144 + outer loop + vertex 687.904 124.962 30.0632 + vertex 687.698 124.44 29.5363 + vertex 691.335 126.339 30.0158 + endloop + endfacet + facet normal 0.301998 -0.73308 0.609418 + outer loop + vertex 687.904 124.962 30.0632 + vertex 680.8 121.921 29.9249 + vertex 687.698 124.44 29.5363 + endloop + endfacet + facet normal 0.309119 -0.757991 0.574365 + outer loop + vertex 687.698 124.44 29.5363 + vertex 680.8 121.921 29.9249 + vertex 681.92 122.146 29.6194 + endloop + endfacet + facet normal 0.304617 -0.746002 0.592191 + outer loop + vertex 687.698 124.44 29.5363 + vertex 681.92 122.146 29.6194 + vertex 682.193 121.913 29.1856 + endloop + endfacet + facet normal 0.304959 -0.745783 0.59229 + outer loop + vertex 681.92 122.146 29.6194 + vertex 677.505 120.337 29.6152 + vertex 682.193 121.913 29.1856 + endloop + endfacet + facet normal 0.309335 -0.756428 0.576306 + outer loop + vertex 681.92 122.146 29.6194 + vertex 680.8 121.921 29.9249 + vertex 677.505 120.337 29.6152 + endloop + endfacet + facet normal 0.297715 -0.718642 0.628426 + outer loop + vertex 689.587 125.831 30.2648 + vertex 690.975 126.355 30.207 + vertex 692.548 127.222 30.4532 + endloop + endfacet + facet normal 0.297035 -0.717427 0.630134 + outer loop + vertex 692.548 127.222 30.4532 + vertex 686.51 124.693 30.4193 + vertex 689.587 125.831 30.2648 + endloop + endfacet + facet normal 0.299917 -0.72143 0.624171 + outer loop + vertex 690.975 126.355 30.207 + vertex 691.335 126.339 30.0158 + vertex 692.548 127.222 30.4532 + endloop + endfacet + facet normal 0.293217 -0.716552 0.632912 + outer loop + vertex 691.335 126.339 30.0158 + vertex 694.339 127.359 29.7782 + vertex 692.548 127.222 30.4532 + endloop + endfacet + facet normal 0.29365 -0.715099 0.634353 + outer loop + vertex 695.975 128.708 30.5426 + vertex 692.548 127.222 30.4532 + vertex 694.339 127.359 29.7782 + endloop + endfacet + facet normal 0.295252 -0.716026 0.632561 + outer loop + vertex 694.339 127.359 29.7782 + vertex 698.228 129.699 30.612 + vertex 695.975 128.708 30.5426 + endloop + endfacet + facet normal 0.294804 -0.715094 0.633823 + outer loop + vertex 695.221 129.238 31.4909 + vertex 695.975 128.708 30.5426 + vertex 698.228 129.699 30.612 + endloop + endfacet + facet normal 0.293947 -0.715733 0.633499 + outer loop + vertex 695.221 129.238 31.4909 + vertex 692.548 127.222 30.4532 + vertex 695.975 128.708 30.5426 + endloop + endfacet + facet normal 0.296886 -0.716939 0.63076 + outer loop + vertex 687.528 124.936 30.2179 + vertex 689.587 125.831 30.2648 + vertex 686.51 124.693 30.4193 + endloop + endfacet + facet normal 0.296927 -0.720235 0.626974 + outer loop + vertex 684.982 123.826 30.1475 + vertex 687.528 124.936 30.2179 + vertex 686.51 124.693 30.4193 + endloop + endfacet + facet normal 0.297901 -0.721391 0.62518 + outer loop + vertex 681.83 122.508 30.1282 + vertex 684.982 123.826 30.1475 + vertex 686.51 124.693 30.4193 + endloop + endfacet + facet normal 0.307462 -0.74229 0.595376 + outer loop + vertex 678.869 121.223 30.0555 + vertex 681.83 122.508 30.1282 + vertex 678.931 121.426 30.277 + endloop + endfacet + facet normal 0.306158 -0.742432 0.595871 + outer loop + vertex 675.448 119.789 30.0264 + vertex 678.869 121.223 30.0555 + vertex 678.931 121.426 30.277 + endloop + endfacet + facet normal 0.314782 -0.75718 0.572355 + outer loop + vertex 678.931 121.426 30.277 + vertex 672.1 118.471 30.1245 + vertex 675.448 119.789 30.0264 + endloop + endfacet + facet normal 0.326588 -0.782305 0.530415 + outer loop + vertex 672.1 118.471 30.1245 + vertex 678.931 121.426 30.277 + vertex 675.462 120.127 30.4961 + endloop + endfacet + facet normal 0.335233 -0.79447 0.506395 + outer loop + vertex 671.693 118.514 30.4617 + vertex 672.1 118.471 30.1245 + vertex 675.462 120.127 30.4961 + endloop + endfacet + facet normal 0.327283 -0.776568 0.538357 + outer loop + vertex 674.067 120.033 31.2094 + vertex 671.693 118.514 30.4617 + vertex 675.462 120.127 30.4961 + endloop + endfacet + facet normal 0.333847 -0.781369 0.527266 + outer loop + vertex 670.02 118.177 31.0214 + vertex 671.693 118.514 30.4617 + vertex 674.067 120.033 31.2094 + endloop + endfacet + facet normal 0.32975 -0.797417 0.505363 + outer loop + vertex 670.02 118.177 31.0214 + vertex 668.974 117.317 30.3469 + vertex 671.693 118.514 30.4617 + endloop + endfacet + facet normal 0.333578 -0.79861 0.500947 + outer loop + vertex 667.222 116.945 30.9202 + vertex 668.974 117.317 30.3469 + vertex 670.02 118.177 31.0214 + endloop + endfacet + facet normal 0.335349 -0.802076 0.494181 + outer loop + vertex 668.315 117.986 31.8684 + vertex 667.222 116.945 30.9202 + vertex 670.02 118.177 31.0214 + endloop + endfacet + facet normal 0.343501 -0.785848 0.514248 + outer loop + vertex 668.315 117.986 31.8684 + vertex 670.02 118.177 31.0214 + vertex 672.178 120.025 32.4034 + endloop + endfacet + facet normal 0.340075 -0.802884 0.489619 + outer loop + vertex 665.894 116.984 31.9059 + vertex 667.222 116.945 30.9202 + vertex 668.315 117.986 31.8684 + endloop + endfacet + facet normal 0.336953 -0.794777 0.50477 + outer loop + vertex 668.315 117.986 31.8684 + vertex 668.528 119.435 34.0087 + vertex 665.894 116.984 31.9059 + endloop + endfacet + facet normal 0.357391 -0.798824 0.483893 + outer loop + vertex 668.528 119.435 34.0087 + vertex 664.077 116.799 32.9433 + vertex 665.894 116.984 31.9059 + endloop + endfacet + facet normal 0.346609 -0.81642 0.461867 + outer loop + vertex 664.077 116.799 32.9433 + vertex 664.434 116.268 31.7381 + vertex 665.894 116.984 31.9059 + endloop + endfacet + facet normal 0.343358 -0.812107 0.471792 + outer loop + vertex 664.434 116.268 31.7381 + vertex 665.385 116.281 31.0684 + vertex 665.894 116.984 31.9059 + endloop + endfacet + facet normal 0.33657 -0.82054 0.46199 + outer loop + vertex 664.434 116.268 31.7381 + vertex 663.885 116.082 31.8069 + vertex 665.385 116.281 31.0684 + endloop + endfacet + facet normal 0.336628 -0.821091 0.460967 + outer loop + vertex 664.077 116.799 32.9433 + vertex 663.885 116.082 31.8069 + vertex 664.434 116.268 31.7381 + endloop + endfacet + facet normal 0.354569 -0.816745 0.455201 + outer loop + vertex 661.814 116.246 33.7132 + vertex 663.885 116.082 31.8069 + vertex 664.077 116.799 32.9433 + endloop + endfacet + facet normal 0.354921 -0.815523 0.457113 + outer loop + vertex 663.114 117.888 35.6338 + vertex 661.814 116.246 33.7132 + vertex 664.077 116.799 32.9433 + endloop + endfacet + facet normal 0.372894 -0.81464 0.444198 + outer loop + vertex 659.43 116.371 35.9449 + vertex 661.814 116.246 33.7132 + vertex 663.114 117.888 35.6338 + endloop + endfacet + facet normal 0.330055 -0.854703 0.400682 + outer loop + vertex 661.814 116.246 33.7132 + vertex 659.43 116.371 35.9449 + vertex 660.139 115.954 34.4713 + endloop + endfacet + facet normal 0.306541 -0.86056 0.406779 + outer loop + vertex 663.885 116.082 31.8069 + vertex 661.814 116.246 33.7132 + vertex 662.478 115.959 32.6075 + endloop + endfacet + facet normal 0.368858 -0.808174 0.459128 + outer loop + vertex 663.114 117.888 35.6338 + vertex 664.077 116.799 32.9433 + vertex 668.528 119.435 34.0087 + endloop + endfacet + facet normal 0.331981 -0.81256 0.479097 + outer loop + vertex 665.894 116.984 31.9059 + vertex 665.385 116.281 31.0684 + vertex 667.222 116.945 30.9202 + endloop + endfacet + facet normal 0.332546 -0.815233 0.47414 + outer loop + vertex 665.385 116.281 31.0684 + vertex 666.81 116.485 30.419 + vertex 667.222 116.945 30.9202 + endloop + endfacet + facet normal 0.326988 -0.826385 0.458438 + outer loop + vertex 666.81 116.485 30.419 + vertex 665.385 116.281 31.0684 + vertex 665.624 116.162 30.6829 + endloop + endfacet + facet normal 0.327717 -0.819486 0.470153 + outer loop + vertex 665.624 116.162 30.6829 + vertex 666.686 116.335 30.2433 + vertex 666.81 116.485 30.419 + endloop + endfacet + facet normal 0.328475 -0.819488 0.46962 + outer loop + vertex 666.81 116.485 30.419 + vertex 666.686 116.335 30.2433 + vertex 668.201 116.875 30.1262 + endloop + endfacet + facet normal 0.328861 -0.814128 0.478588 + outer loop + vertex 668.974 117.317 30.3469 + vertex 666.81 116.485 30.419 + vertex 668.201 116.875 30.1262 + endloop + endfacet + facet normal 0.335464 -0.819076 0.465379 + outer loop + vertex 668.974 117.317 30.3469 + vertex 668.201 116.875 30.1262 + vertex 672.1 118.471 30.1245 + endloop + endfacet + facet normal 0.326707 -0.797637 0.506988 + outer loop + vertex 669.642 117.413 30.0447 + vertex 672.1 118.471 30.1245 + vertex 668.201 116.875 30.1262 + endloop + endfacet + facet normal 0.320715 -0.784455 0.530822 + outer loop + vertex 668.201 116.875 30.1262 + vertex 666.686 116.335 30.2433 + vertex 666.552 116.196 30.1199 + endloop + endfacet + facet normal 0.340411 -0.787863 0.513218 + outer loop + vertex 666.686 116.335 30.2433 + vertex 665.624 116.162 30.6829 + vertex 666.552 116.196 30.1199 + endloop + endfacet + facet normal 0.432495 -0.596046 0.676519 + outer loop + vertex 664.875 116.122 31.1266 + vertex 666.552 116.196 30.1199 + vertex 665.624 116.162 30.6829 + endloop + endfacet + facet normal -0.381593 0.717422 -0.582832 + outer loop + vertex 666.552 116.196 30.1199 + vertex 664.875 116.122 31.1266 + vertex 666.109 116.224 30.4434 + endloop + endfacet + facet normal 0.305288 -0.818305 0.487007 + outer loop + vertex 666.109 116.224 30.4434 + vertex 666.41 116.162 30.1516 + vertex 666.552 116.196 30.1199 + endloop + endfacet + facet normal 0.308855 -0.780507 0.543524 + outer loop + vertex 666.41 116.162 30.1516 + vertex 665.814 115.704 29.8326 + vertex 666.552 116.196 30.1199 + endloop + endfacet + facet normal 0.219567 -0.71608 0.662585 + outer loop + vertex 664.073 114.405 29.0056 + vertex 666.552 116.196 30.1199 + vertex 665.814 115.704 29.8326 + endloop + endfacet + facet normal 0.32032 -0.775583 0.543936 + outer loop + vertex 664.073 114.405 29.0056 + vertex 665.814 115.704 29.8326 + vertex 664.611 115.028 29.5759 + endloop + endfacet + facet normal 0.335394 -0.777574 0.531873 + outer loop + vertex 664.611 115.028 29.5759 + vertex 662.41 113.492 28.7187 + vertex 664.073 114.405 29.0056 + endloop + endfacet + facet normal 0.31532 -0.754691 0.575339 + outer loop + vertex 662.41 113.492 28.7187 + vertex 661.212 112.489 28.0597 + vertex 664.073 114.405 29.0056 + endloop + endfacet + facet normal 0.327966 -0.760235 0.560786 + outer loop + vertex 658.745 111.283 27.8673 + vertex 661.212 112.489 28.0597 + vertex 662.41 113.492 28.7187 + endloop + endfacet + facet normal 0.326711 -0.759051 0.563117 + outer loop + vertex 662.41 113.492 28.7187 + vertex 661.613 113.368 29.0142 + vertex 658.745 111.283 27.8673 + endloop + endfacet + facet normal 0.317249 -0.753229 0.576194 + outer loop + vertex 656.309 110.841 28.6312 + vertex 658.745 111.283 27.8673 + vertex 661.613 113.368 29.0142 + endloop + endfacet + facet normal 0.325384 -0.766828 0.553263 + outer loop + vertex 660.995 113.452 29.4943 + vertex 656.309 110.841 28.6312 + vertex 661.613 113.368 29.0142 + endloop + endfacet + facet normal 0.321848 -0.77105 0.549451 + outer loop + vertex 661.613 113.368 29.0142 + vertex 663.875 114.916 29.8612 + vertex 660.995 113.452 29.4943 + endloop + endfacet + facet normal 0.330542 -0.782645 0.527455 + outer loop + vertex 660.995 113.452 29.4943 + vertex 663.875 114.916 29.8612 + vertex 662.565 114.618 30.2404 + endloop + endfacet + facet normal 0.331246 -0.782986 0.526506 + outer loop + vertex 660.995 113.452 29.4943 + vertex 662.565 114.618 30.2404 + vertex 658.255 112.505 29.8093 + endloop + endfacet + facet normal 0.336034 -0.789969 0.512865 + outer loop + vertex 658.255 112.505 29.8093 + vertex 662.565 114.618 30.2404 + vertex 660.511 114.088 30.7699 + endloop + endfacet + facet normal 0.334959 -0.789396 0.514447 + outer loop + vertex 658.255 112.505 29.8093 + vertex 660.511 114.088 30.7699 + vertex 655.221 111.707 30.5612 + endloop + endfacet + facet normal 0.335183 -0.787148 0.517736 + outer loop + vertex 655.221 111.707 30.5612 + vertex 651.555 109.36 29.366 + vertex 658.255 112.505 29.8093 + endloop + endfacet + facet normal 0.324678 -0.769342 0.550179 + outer loop + vertex 651.555 109.36 29.366 + vertex 656.309 110.841 28.6312 + vertex 658.255 112.505 29.8093 + endloop + endfacet + facet normal 0.324427 -0.766496 0.554284 + outer loop + vertex 648.387 107.113 28.1121 + vertex 656.309 110.841 28.6312 + vertex 651.555 109.36 29.366 + endloop + endfacet + facet normal 0.32199 -0.765001 0.55776 + outer loop + vertex 648.387 107.113 28.1121 + vertex 651.555 109.36 29.366 + vertex 643.324 105.76 29.1797 + endloop + endfacet + facet normal 0.321905 -0.76893 0.55238 + outer loop + vertex 640.825 103.893 28.0376 + vertex 648.387 107.113 28.1121 + vertex 643.324 105.76 29.1797 + endloop + endfacet + facet normal 0.320816 -0.768351 0.553818 + outer loop + vertex 640.825 103.893 28.0376 + vertex 643.324 105.76 29.1797 + vertex 634.731 102.283 29.3334 + endloop + endfacet + facet normal 0.32047 -0.77892 0.539056 + outer loop + vertex 640.825 103.893 28.0376 + vertex 634.731 102.283 29.3334 + vertex 635.891 102.079 28.3493 + endloop + endfacet + facet normal 0.31702 -0.766093 0.559106 + outer loop + vertex 635.891 102.079 28.3493 + vertex 638.633 102.778 27.7527 + vertex 640.825 103.893 28.0376 + endloop + endfacet + facet normal 0.308959 -0.755128 0.578209 + outer loop + vertex 638.633 102.778 27.7527 + vertex 641.389 103.521 27.2507 + vertex 640.825 103.893 28.0376 + endloop + endfacet + facet normal 0.310375 -0.754131 0.578752 + outer loop + vertex 646.342 105.321 26.9389 + vertex 640.825 103.893 28.0376 + vertex 641.389 103.521 27.2507 + endloop + endfacet + facet normal 0.305706 -0.737141 0.602634 + outer loop + vertex 641.389 103.521 27.2507 + vertex 643.68 104.09 26.7838 + vertex 646.342 105.321 26.9389 + endloop + endfacet + facet normal 0.303844 -0.661475 0.68566 + outer loop + vertex 643.68 104.09 26.7838 + vertex 641.389 103.521 27.2507 + vertex 642.639 103.527 26.7015 + endloop + endfacet + facet normal 0.284093 -0.630349 0.722462 + outer loop + vertex 645.4 104.459 26.4295 + vertex 643.68 104.09 26.7838 + vertex 642.639 103.527 26.7015 + endloop + endfacet + facet normal 0.2851 -0.699249 0.655568 + outer loop + vertex 643.68 104.09 26.7838 + vertex 645.4 104.459 26.4295 + vertex 646.342 105.321 26.9389 + endloop + endfacet + facet normal 0.293281 -0.703403 0.647465 + outer loop + vertex 645.4 104.459 26.4295 + vertex 648.109 105.333 26.1522 + vertex 646.342 105.321 26.9389 + endloop + endfacet + facet normal 0.296165 -0.696055 0.65406 + outer loop + vertex 651.698 106.929 26.2248 + vertex 646.342 105.321 26.9389 + vertex 648.109 105.333 26.1522 + endloop + endfacet + facet normal 0.299666 -0.720425 0.62545 + outer loop + vertex 651.698 106.929 26.2248 + vertex 652.948 108.372 27.2884 + vertex 646.342 105.321 26.9389 + endloop + endfacet + facet normal 0.306232 -0.722224 0.620173 + outer loop + vertex 651.698 106.929 26.2248 + vertex 655.799 109.037 26.6548 + vertex 652.948 108.372 27.2884 + endloop + endfacet + facet normal 0.310329 -0.742686 0.593392 + outer loop + vertex 646.342 105.321 26.9389 + vertex 648.387 107.113 28.1121 + vertex 640.825 103.893 28.0376 + endloop + endfacet + facet normal 0.312104 -0.743463 0.591484 + outer loop + vertex 646.342 105.321 26.9389 + vertex 652.948 108.372 27.2884 + vertex 648.387 107.113 28.1121 + endloop + endfacet + facet normal 0.312187 -0.745336 0.589079 + outer loop + vertex 652.948 108.372 27.2884 + vertex 656.309 110.841 28.6312 + vertex 648.387 107.113 28.1121 + endloop + endfacet + facet normal 0.318057 -0.749036 0.581193 + outer loop + vertex 652.948 108.372 27.2884 + vertex 658.745 111.283 27.8673 + vertex 656.309 110.841 28.6312 + endloop + endfacet + facet normal 0.306922 -0.710005 0.633792 + outer loop + vertex 641.389 103.521 27.2507 + vertex 638.633 102.778 27.7527 + vertex 638.064 102.339 27.5361 + endloop + endfacet + facet normal 0.317834 -0.71734 0.620003 + outer loop + vertex 638.633 102.778 27.7527 + vertex 635.891 102.079 28.3493 + vertex 638.064 102.339 27.5361 + endloop + endfacet + facet normal 0.311763 -0.739399 0.596735 + outer loop + vertex 632.627 100.955 28.6616 + vertex 638.064 102.339 27.5361 + vertex 635.891 102.079 28.3493 + endloop + endfacet + facet normal 0.318372 -0.781166 0.537047 + outer loop + vertex 632.879 101.266 28.9522 + vertex 635.891 102.079 28.3493 + vertex 634.731 102.283 29.3334 + endloop + endfacet + facet normal 0.32227 -0.785176 0.528811 + outer loop + vertex 630.012 100.499 29.5606 + vertex 632.879 101.266 28.9522 + vertex 634.731 102.283 29.3334 + endloop + endfacet + facet normal 0.324838 -0.793845 0.514091 + outer loop + vertex 634.731 102.283 29.3334 + vertex 629.116 100.498 30.1254 + vertex 630.012 100.499 29.5606 + endloop + endfacet + facet normal 0.323618 -0.795594 0.512153 + outer loop + vertex 626.132 99.5005 30.4612 + vertex 630.012 100.499 29.5606 + vertex 629.116 100.498 30.1254 + endloop + endfacet + facet normal 0.325104 -0.80585 0.494888 + outer loop + vertex 629.116 100.498 30.1254 + vertex 626.353 99.8863 30.9441 + vertex 626.132 99.5005 30.4612 + endloop + endfacet + facet normal 0.324468 -0.805901 0.495221 + outer loop + vertex 623.601 98.948 31.2204 + vertex 626.132 99.5005 30.4612 + vertex 626.353 99.8863 30.9441 + endloop + endfacet + facet normal 0.326503 -0.818503 0.472703 + outer loop + vertex 626.353 99.8863 30.9441 + vertex 623.589 99.3064 31.8489 + vertex 623.601 98.948 31.2204 + endloop + endfacet + facet normal 0.326147 -0.818613 0.472759 + outer loop + vertex 621.223 98.4356 31.9734 + vertex 623.601 98.948 31.2204 + vertex 623.589 99.3064 31.8489 + endloop + endfacet + facet normal 0.329131 -0.829909 0.450471 + outer loop + vertex 623.589 99.3064 31.8489 + vertex 620.91 98.7687 32.8163 + vertex 621.223 98.4356 31.9734 + endloop + endfacet + facet normal 0.328219 -0.830358 0.45031 + outer loop + vertex 618.469 97.9065 33.0055 + vertex 621.223 98.4356 31.9734 + vertex 620.91 98.7687 32.8163 + endloop + endfacet + facet normal 0.330509 -0.842157 0.426069 + outer loop + vertex 620.91 98.7687 32.8163 + vertex 618.441 98.3429 33.8899 + vertex 618.469 97.9065 33.0055 + endloop + endfacet + facet normal 0.32796 -0.842987 0.426397 + outer loop + vertex 615.469 97.4219 34.3544 + vertex 618.469 97.9065 33.0055 + vertex 618.441 98.3429 33.8899 + endloop + endfacet + facet normal 0.327857 -0.854531 0.402849 + outer loop + vertex 618.441 98.3429 33.8899 + vertex 617.161 98.316 34.8741 + vertex 615.469 97.4219 34.3544 + endloop + endfacet + facet normal 0.328027 -0.854638 0.402482 + outer loop + vertex 617.161 98.316 34.8741 + vertex 615.963 98.2231 35.6537 + vertex 615.469 97.4219 34.3544 + endloop + endfacet + facet normal 0.322619 -0.855481 0.405055 + outer loop + vertex 611.235 96.4954 35.7707 + vertex 615.469 97.4219 34.3544 + vertex 615.963 98.2231 35.6537 + endloop + endfacet + facet normal 0.322215 -0.854167 0.408138 + outer loop + vertex 615.963 98.2231 35.6537 + vertex 616.693 98.9392 36.5755 + vertex 611.235 96.4954 35.7707 + endloop + endfacet + facet normal 0.33127 -0.85412 0.400923 + outer loop + vertex 615.963 98.2231 35.6537 + vertex 620 100.336 36.8196 + vertex 616.693 98.9392 36.5755 + endloop + endfacet + facet normal 0.331115 -0.853868 0.401587 + outer loop + vertex 623.269 102.152 37.986 + vertex 616.693 98.9392 36.5755 + vertex 620 100.336 36.8196 + endloop + endfacet + facet normal 0.354473 -0.865418 0.35412 + outer loop + vertex 624.393 102.5 37.7111 + vertex 623.269 102.152 37.986 + vertex 620 100.336 36.8196 + endloop + endfacet + facet normal 0.349276 -0.861149 0.369362 + outer loop + vertex 620 100.336 36.8196 + vertex 624.86 102.442 37.133 + vertex 624.393 102.5 37.7111 + endloop + endfacet + facet normal 0.353491 -0.858089 0.372461 + outer loop + vertex 624.393 102.5 37.7111 + vertex 624.86 102.442 37.133 + vertex 631.768 105.953 38.6667 + endloop + endfacet + facet normal 0.353494 -0.858092 0.372451 + outer loop + vertex 632.713 105.662 37.099 + vertex 631.768 105.953 38.6667 + vertex 624.86 102.442 37.133 + endloop + endfacet + facet normal 0.351742 -0.853697 0.384031 + outer loop + vertex 624.345 101.771 36.1141 + vertex 632.713 105.662 37.099 + vertex 624.86 102.442 37.133 + endloop + endfacet + facet normal 0.344966 -0.854633 0.388073 + outer loop + vertex 619.615 99.7668 35.904 + vertex 624.345 101.771 36.1141 + vertex 624.86 102.442 37.133 + endloop + endfacet + facet normal 0.342368 -0.849829 0.400718 + outer loop + vertex 620.724 99.7612 34.9446 + vertex 624.345 101.771 36.1141 + vertex 619.615 99.7668 35.904 + endloop + endfacet + facet normal 0.338377 -0.853572 0.396126 + outer loop + vertex 617.161 98.316 34.8741 + vertex 620.724 99.7612 34.9446 + vertex 619.615 99.7668 35.904 + endloop + endfacet + facet normal 0.345332 -0.851543 0.394487 + outer loop + vertex 620.724 99.7612 34.9446 + vertex 627.004 102.457 35.2661 + vertex 624.345 101.771 36.1141 + endloop + endfacet + facet normal 0.34035 -0.842651 0.417253 + outer loop + vertex 622.701 100.047 33.9094 + vertex 627.004 102.457 35.2661 + vertex 620.724 99.7612 34.9446 + endloop + endfacet + facet normal 0.337153 -0.847588 0.409784 + outer loop + vertex 618.441 98.3429 33.8899 + vertex 622.701 100.047 33.9094 + vertex 620.724 99.7612 34.9446 + endloop + endfacet + facet normal 0.342137 -0.843754 0.413547 + outer loop + vertex 622.701 100.047 33.9094 + vertex 628.175 102.358 34.0956 + vertex 627.004 102.457 35.2661 + endloop + endfacet + facet normal 0.34628 -0.840165 0.417389 + outer loop + vertex 628.175 102.358 34.0956 + vertex 636.121 106.207 35.2514 + vertex 627.004 102.457 35.2661 + endloop + endfacet + facet normal 0.350017 -0.849338 0.395112 + outer loop + vertex 636.121 106.207 35.2514 + vertex 632.713 105.662 37.099 + vertex 627.004 102.457 35.2661 + endloop + endfacet + facet normal 0.353107 -0.844735 0.402167 + outer loop + vertex 636.121 106.207 35.2514 + vertex 642.674 109.882 37.2173 + vertex 632.713 105.662 37.099 + endloop + endfacet + facet normal 0.356651 -0.852539 0.38207 + outer loop + vertex 632.713 105.662 37.099 + vertex 642.674 109.882 37.2173 + vertex 642.366 110.554 39.0043 + endloop + endfacet + facet normal 0.361668 -0.850396 0.38213 + outer loop + vertex 642.366 110.554 39.0043 + vertex 642.674 109.882 37.2173 + vertex 650.672 113.709 38.164 + endloop + endfacet + facet normal 0.361945 -0.852382 0.377412 + outer loop + vertex 650.672 113.709 38.164 + vertex 649.69 114.35 40.5532 + vertex 642.366 110.554 39.0043 + endloop + endfacet + facet normal 0.370625 -0.859127 0.352899 + outer loop + vertex 642.867 111.599 41.0209 + vertex 642.366 110.554 39.0043 + vertex 649.69 114.35 40.5532 + endloop + endfacet + facet normal 0.369259 -0.85305 0.36872 + outer loop + vertex 649.69 114.35 40.5532 + vertex 650.3 115.352 42.2612 + vertex 642.867 111.599 41.0209 + endloop + endfacet + facet normal 0.371782 -0.852485 0.367488 + outer loop + vertex 649.69 114.35 40.5532 + vertex 652.843 116.267 41.8096 + vertex 650.3 115.352 42.2612 + endloop + endfacet + facet normal 0.371928 -0.848833 0.375703 + outer loop + vertex 650.3 115.352 42.2612 + vertex 652.843 116.267 41.8096 + vertex 652.529 116.629 42.9396 + endloop + endfacet + facet normal 0.37961 -0.852969 0.358247 + outer loop + vertex 650.3 115.352 42.2612 + vertex 652.529 116.629 42.9396 + vertex 651.641 116.347 43.2091 + endloop + endfacet + facet normal 0.382115 -0.853221 0.354967 + outer loop + vertex 650.3 115.352 42.2612 + vertex 651.641 116.347 43.2091 + vertex 648.386 114.745 42.861 + endloop + endfacet + facet normal 0.381307 -0.847258 0.369809 + outer loop + vertex 651.641 116.347 43.2091 + vertex 652.529 116.629 42.9396 + vertex 652.691 116.856 43.2906 + endloop + endfacet + facet normal -0.387574 0.855836 -0.342537 + outer loop + vertex 651.641 116.347 43.2091 + vertex 652.691 116.856 43.2906 + vertex 652.998 116.986 43.2687 + endloop + endfacet + facet normal 0.385374 -0.846461 0.367412 + outer loop + vertex 652.691 116.856 43.2906 + vertex 652.529 116.629 42.9396 + vertex 652.998 116.986 43.2687 + endloop + endfacet + facet normal 0.37839 -0.845629 0.376475 + outer loop + vertex 652.529 116.629 42.9396 + vertex 652.843 116.267 41.8096 + vertex 652.998 116.986 43.2687 + endloop + endfacet + facet normal 0.366156 -0.85024 0.378183 + outer loop + vertex 649.69 114.35 40.5532 + vertex 653.939 115.836 39.7804 + vertex 652.843 116.267 41.8096 + endloop + endfacet + facet normal 0.367074 -0.849677 0.378559 + outer loop + vertex 652.843 116.267 41.8096 + vertex 653.939 115.836 39.7804 + vertex 654.358 116.606 41.1017 + endloop + endfacet + facet normal 0.362569 -0.861277 0.356014 + outer loop + vertex 631.768 105.953 38.6667 + vertex 642.366 110.554 39.0043 + vertex 642.867 111.599 41.0209 + endloop + endfacet + facet normal 0.37932 -0.87327 0.305804 + outer loop + vertex 631.768 105.953 38.6667 + vertex 642.867 111.599 41.0209 + vertex 632.531 106.734 39.949 + endloop + endfacet + facet normal 0.366338 -0.875568 0.314924 + outer loop + vertex 623.269 102.152 37.986 + vertex 631.768 105.953 38.6667 + vertex 632.531 106.734 39.949 + endloop + endfacet + facet normal 0.374767 -0.881175 0.288237 + outer loop + vertex 623.269 102.152 37.986 + vertex 632.531 106.734 39.949 + vertex 626.22 103.761 39.0655 + endloop + endfacet + facet normal 0.375933 -0.882229 0.283456 + outer loop + vertex 628.563 104.995 39.7986 + vertex 626.22 103.761 39.0655 + vertex 632.531 106.734 39.949 + endloop + endfacet + facet normal 0.377515 -0.884916 0.272774 + outer loop + vertex 630.935 106.173 40.3372 + vertex 628.563 104.995 39.7986 + vertex 632.531 106.734 39.949 + endloop + endfacet + facet normal 0.37821 -0.882753 0.278756 + outer loop + vertex 633.248 107.298 40.7631 + vertex 630.935 106.173 40.3372 + vertex 632.531 106.734 39.949 + endloop + endfacet + facet normal 0.360395 -0.874336 0.325041 + outer loop + vertex 628.563 104.995 39.7986 + vertex 630.935 106.173 40.3372 + vertex 628.847 105.509 40.8669 + endloop + endfacet + facet normal 0.357826 -0.875015 0.32605 + outer loop + vertex 628.847 105.509 40.8669 + vertex 624.859 103.481 39.8011 + vertex 628.563 104.995 39.7986 + endloop + endfacet + facet normal 0.357463 -0.874123 0.328831 + outer loop + vertex 626.22 103.761 39.0655 + vertex 628.563 104.995 39.7986 + vertex 624.859 103.481 39.8011 + endloop + endfacet + facet normal 0.356762 -0.874399 0.328858 + outer loop + vertex 628.847 105.509 40.8669 + vertex 626.925 105.306 42.4128 + vertex 624.859 103.481 39.8011 + endloop + endfacet + facet normal 0.358105 -0.873158 0.33069 + outer loop + vertex 628.847 105.509 40.8669 + vertex 630.273 106.921 43.0517 + vertex 626.925 105.306 42.4128 + endloop + endfacet + facet normal 0.360991 -0.872774 0.328558 + outer loop + vertex 631.876 106.989 41.4715 + vertex 630.273 106.921 43.0517 + vertex 628.847 105.509 40.8669 + endloop + endfacet + facet normal 0.360862 -0.872675 0.328963 + outer loop + vertex 631.876 106.989 41.4715 + vertex 628.847 105.509 40.8669 + vertex 630.935 106.173 40.3372 + endloop + endfacet + facet normal 0.389975 -0.884758 0.255194 + outer loop + vertex 632.531 106.734 39.949 + vertex 642.867 111.599 41.0209 + vertex 639.974 110.456 41.4797 + endloop + endfacet + facet normal 0.391282 -0.869506 0.301425 + outer loop + vertex 639.974 110.456 41.4797 + vertex 642.867 111.599 41.0209 + vertex 644.546 112.867 42.4984 + endloop + endfacet + facet normal 0.366164 -0.850082 0.378529 + outer loop + vertex 650.672 113.709 38.164 + vertex 653.939 115.836 39.7804 + vertex 649.69 114.35 40.5532 + endloop + endfacet + facet normal 0.362579 -0.849005 0.384353 + outer loop + vertex 650.672 113.709 38.164 + vertex 656.009 115.704 37.537 + vertex 653.939 115.836 39.7804 + endloop + endfacet + facet normal 0.358779 -0.852112 0.381029 + outer loop + vertex 653.939 115.836 39.7804 + vertex 656.009 115.704 37.537 + vertex 655.902 116.263 38.8875 + endloop + endfacet + facet normal 0.362209 -0.845507 0.392331 + outer loop + vertex 654.917 114.665 36.305 + vertex 656.009 115.704 37.537 + vertex 650.672 113.709 38.164 + endloop + endfacet + facet normal 0.362581 -0.844778 0.393554 + outer loop + vertex 654.917 114.665 36.305 + vertex 650.672 113.709 38.164 + vertex 648.302 111.497 35.5991 + endloop + endfacet + facet normal 0.356926 -0.837482 0.413797 + outer loop + vertex 656.027 114.237 34.4809 + vertex 654.917 114.665 36.305 + vertex 648.302 111.497 35.5991 + endloop + endfacet + facet normal 0.356586 -0.831768 0.42545 + outer loop + vertex 648.302 111.497 35.5991 + vertex 650.788 111.41 33.3453 + vertex 656.027 114.237 34.4809 + endloop + endfacet + facet normal 0.351784 -0.827641 0.437331 + outer loop + vertex 658.254 114.17 32.5623 + vertex 656.027 114.237 34.4809 + vertex 650.788 111.41 33.3453 + endloop + endfacet + facet normal 0.350492 -0.819674 0.453089 + outer loop + vertex 650.788 111.41 33.3453 + vertex 652.853 111.387 31.7072 + vertex 658.254 114.17 32.5623 + endloop + endfacet + facet normal 0.347776 -0.816685 0.460518 + outer loop + vertex 658.254 114.17 32.5623 + vertex 652.853 111.387 31.7072 + vertex 658.289 113.552 31.4408 + endloop + endfacet + facet normal 0.34748 -0.816786 0.460564 + outer loop + vertex 661.456 114.954 31.5371 + vertex 658.254 114.17 32.5623 + vertex 658.289 113.552 31.4408 + endloop + endfacet + facet normal 0.341008 -0.803989 0.487151 + outer loop + vertex 658.289 113.552 31.4408 + vertex 660.511 114.088 30.7699 + vertex 661.456 114.954 31.5371 + endloop + endfacet + facet normal 0.339401 -0.803679 0.488781 + outer loop + vertex 663.516 115.479 30.97 + vertex 661.456 114.954 31.5371 + vertex 660.511 114.088 30.7699 + endloop + endfacet + facet normal 0.337446 -0.814835 0.471355 + outer loop + vertex 661.456 114.954 31.5371 + vertex 663.516 115.479 30.97 + vertex 662.885 115.727 31.8501 + endloop + endfacet + facet normal 0.336409 -0.815572 0.47082 + outer loop + vertex 665.144 116.083 30.8541 + vertex 662.885 115.727 31.8501 + vertex 663.516 115.479 30.97 + endloop + endfacet + facet normal 0.333253 -0.802441 0.495006 + outer loop + vertex 664.715 115.663 30.4617 + vertex 665.144 116.083 30.8541 + vertex 663.516 115.479 30.97 + endloop + endfacet + facet normal 0.335584 -0.796745 0.502574 + outer loop + vertex 664.715 115.663 30.4617 + vertex 663.516 115.479 30.97 + vertex 662.565 114.618 30.2404 + endloop + endfacet + facet normal 0.326411 -0.801341 0.501307 + outer loop + vertex 664.715 115.663 30.4617 + vertex 665.565 115.874 30.245 + vertex 665.144 116.083 30.8541 + endloop + endfacet + facet normal 0.330207 -0.798706 0.503024 + outer loop + vertex 666.109 116.224 30.4434 + vertex 665.144 116.083 30.8541 + vertex 665.565 115.874 30.245 + endloop + endfacet + facet normal 0.326795 -0.796566 0.508613 + outer loop + vertex 666.106 115.997 30.0897 + vertex 666.109 116.224 30.4434 + vertex 665.565 115.874 30.245 + endloop + endfacet + facet normal 0.328814 -0.785322 0.524547 + outer loop + vertex 666.106 115.997 30.0897 + vertex 665.565 115.874 30.245 + vertex 664.611 115.028 29.5759 + endloop + endfacet + facet normal 0.32425 -0.783987 0.529364 + outer loop + vertex 663.875 114.916 29.8612 + vertex 664.611 115.028 29.5759 + vertex 665.565 115.874 30.245 + endloop + endfacet + facet normal 0.328152 -0.787684 0.521412 + outer loop + vertex 665.565 115.874 30.245 + vertex 664.715 115.663 30.4617 + vertex 663.875 114.916 29.8612 + endloop + endfacet + facet normal 0.32686 -0.835286 0.442107 + outer loop + vertex 662.885 115.727 31.8501 + vertex 665.144 116.083 30.8541 + vertex 664.875 116.122 31.1266 + endloop + endfacet + facet normal 0.345958 -0.822509 0.451433 + outer loop + vertex 661.456 114.954 31.5371 + vertex 662.885 115.727 31.8501 + vertex 658.254 114.17 32.5623 + endloop + endfacet + facet normal 0.345972 -0.822777 0.450934 + outer loop + vertex 658.254 114.17 32.5623 + vertex 662.885 115.727 31.8501 + vertex 660.324 115.552 33.4965 + endloop + endfacet + facet normal 0.338187 -0.833079 0.437731 + outer loop + vertex 660.324 115.552 33.4965 + vertex 662.885 115.727 31.8501 + vertex 662.478 115.959 32.6075 + endloop + endfacet + facet normal 0.343769 -0.80348 0.486048 + outer loop + vertex 652.853 111.387 31.7072 + vertex 655.221 111.707 30.5612 + vertex 658.289 113.552 31.4408 + endloop + endfacet + facet normal 0.34264 -0.805749 0.48308 + outer loop + vertex 647.679 108.439 30.4591 + vertex 655.221 111.707 30.5612 + vertex 652.853 111.387 31.7072 + endloop + endfacet + facet normal 0.342033 -0.805231 0.484372 + outer loop + vertex 647.679 108.439 30.4591 + vertex 652.853 111.387 31.7072 + vertex 644.526 107.96 31.8882 + endloop + endfacet + facet normal 0.340277 -0.80905 0.479218 + outer loop + vertex 639.065 104.828 30.4797 + vertex 647.679 108.439 30.4591 + vertex 644.526 107.96 31.8882 + endloop + endfacet + facet normal 0.337564 -0.806841 0.484828 + outer loop + vertex 639.065 104.828 30.4797 + vertex 644.526 107.96 31.8882 + vertex 635.653 104.251 31.8945 + endloop + endfacet + facet normal 0.33554 -0.811787 0.477928 + outer loop + vertex 635.653 104.251 31.8945 + vertex 631.459 101.797 30.67 + vertex 639.065 104.828 30.4797 + endloop + endfacet + facet normal 0.332151 -0.809277 0.484506 + outer loop + vertex 631.459 101.797 30.67 + vertex 635.653 104.251 31.8945 + vertex 628.341 101.209 31.8262 + endloop + endfacet + facet normal 0.330327 -0.814508 0.476929 + outer loop + vertex 626.353 99.8863 30.9441 + vertex 631.459 101.797 30.67 + vertex 628.341 101.209 31.8262 + endloop + endfacet + facet normal 0.339679 -0.826571 0.448774 + outer loop + vertex 628.341 101.209 31.8262 + vertex 635.653 104.251 31.8945 + vertex 632.082 103.513 33.2378 + endloop + endfacet + facet normal 0.334448 -0.823682 0.457922 + outer loop + vertex 628.341 101.209 31.8262 + vertex 632.082 103.513 33.2378 + vertex 625.295 100.556 32.877 + endloop + endfacet + facet normal 0.333335 -0.827074 0.452588 + outer loop + vertex 623.589 99.3064 31.8489 + vertex 628.341 101.209 31.8262 + vertex 625.295 100.556 32.877 + endloop + endfacet + facet normal 0.341399 -0.836147 0.429307 + outer loop + vertex 625.295 100.556 32.877 + vertex 632.082 103.513 33.2378 + vertex 628.175 102.358 34.0956 + endloop + endfacet + facet normal 0.34114 -0.822665 0.454803 + outer loop + vertex 635.653 104.251 31.8945 + vertex 641.34 107.54 33.5776 + vertex 632.082 103.513 33.2378 + endloop + endfacet + facet normal 0.345374 -0.825593 0.44622 + outer loop + vertex 635.653 104.251 31.8945 + vertex 644.526 107.96 31.8882 + vertex 641.34 107.54 33.5776 + endloop + endfacet + facet normal 0.347705 -0.821688 0.451587 + outer loop + vertex 644.526 107.96 31.8882 + vertex 650.788 111.41 33.3453 + vertex 641.34 107.54 33.5776 + endloop + endfacet + facet normal 0.348259 -0.822154 0.450309 + outer loop + vertex 644.526 107.96 31.8882 + vertex 652.853 111.387 31.7072 + vertex 650.788 111.41 33.3453 + endloop + endfacet + facet normal 0.353416 -0.825972 0.439167 + outer loop + vertex 658.254 114.17 32.5623 + vertex 660.324 115.552 33.4965 + vertex 656.027 114.237 34.4809 + endloop + endfacet + facet normal 0.35252 -0.833904 0.424657 + outer loop + vertex 656.027 114.237 34.4809 + vertex 660.324 115.552 33.4965 + vertex 658.28 115.668 35.421 + endloop + endfacet + facet normal 0.340929 -0.844521 0.41298 + outer loop + vertex 658.28 115.668 35.421 + vertex 660.324 115.552 33.4965 + vertex 660.139 115.954 34.4713 + endloop + endfacet + facet normal 0.352648 -0.835576 0.421252 + outer loop + vertex 641.34 107.54 33.5776 + vertex 650.788 111.41 33.3453 + vertex 648.302 111.497 35.5991 + endloop + endfacet + facet normal 0.349876 -0.833728 0.427181 + outer loop + vertex 641.34 107.54 33.5776 + vertex 648.302 111.497 35.5991 + vertex 636.121 106.207 35.2514 + endloop + endfacet + facet normal 0.348787 -0.837382 0.420879 + outer loop + vertex 641.34 107.54 33.5776 + vertex 636.121 106.207 35.2514 + vertex 632.082 103.513 33.2378 + endloop + endfacet + facet normal 0.358421 -0.836506 0.414478 + outer loop + vertex 656.027 114.237 34.4809 + vertex 658.28 115.668 35.421 + vertex 654.917 114.665 36.305 + endloop + endfacet + facet normal 0.356611 -0.845552 0.397329 + outer loop + vertex 654.917 114.665 36.305 + vertex 658.28 115.668 35.421 + vertex 656.009 115.704 37.537 + endloop + endfacet + facet normal 0.348113 -0.853234 0.388341 + outer loop + vertex 656.009 115.704 37.537 + vertex 658.28 115.668 35.421 + vertex 657.903 116.058 36.6162 + endloop + endfacet + facet normal 0.357007 -0.844748 0.39868 + outer loop + vertex 642.674 109.882 37.2173 + vertex 648.302 111.497 35.5991 + vertex 650.672 113.709 38.164 + endloop + endfacet + facet normal 0.356476 -0.846797 0.394791 + outer loop + vertex 636.121 106.207 35.2514 + vertex 648.302 111.497 35.5991 + vertex 642.674 109.882 37.2173 + endloop + endfacet + facet normal 0.341553 -0.834759 0.431879 + outer loop + vertex 628.175 102.358 34.0956 + vertex 632.082 103.513 33.2378 + vertex 636.121 106.207 35.2514 + endloop + endfacet + facet normal 0.337371 -0.834282 0.436067 + outer loop + vertex 625.295 100.556 32.877 + vertex 628.175 102.358 34.0956 + vertex 622.701 100.047 33.9094 + endloop + endfacet + facet normal 0.335697 -0.838111 0.429973 + outer loop + vertex 620.91 98.7687 32.8163 + vertex 625.295 100.556 32.877 + vertex 622.701 100.047 33.9094 + endloop + endfacet + facet normal 0.346697 -0.847418 0.402099 + outer loop + vertex 624.345 101.771 36.1141 + vertex 627.004 102.457 35.2661 + vertex 632.713 105.662 37.099 + endloop + endfacet + facet normal 0.359059 -0.854596 0.375156 + outer loop + vertex 632.713 105.662 37.099 + vertex 642.366 110.554 39.0043 + vertex 631.768 105.953 38.6667 + endloop + endfacet + facet normal 0.345527 -0.855065 0.38662 + outer loop + vertex 619.615 99.7668 35.904 + vertex 624.86 102.442 37.133 + vertex 620 100.336 36.8196 + endloop + endfacet + facet normal 0.355581 -0.860465 0.364913 + outer loop + vertex 624.393 102.5 37.7111 + vertex 631.768 105.953 38.6667 + vertex 623.269 102.152 37.986 + endloop + endfacet + facet normal 0.348605 -0.868291 0.352911 + outer loop + vertex 616.693 98.9392 36.5755 + vertex 623.269 102.152 37.986 + vertex 618.058 99.7408 37.2 + endloop + endfacet + facet normal 0.335213 -0.856724 0.39199 + outer loop + vertex 615.963 98.2231 35.6537 + vertex 619.615 99.7668 35.904 + vertex 620 100.336 36.8196 + endloop + endfacet + facet normal 0.317925 -0.867141 0.383393 + outer loop + vertex 615.469 97.4219 34.3544 + vertex 611.235 96.4954 35.7707 + vertex 613.292 96.7549 34.6517 + endloop + endfacet + facet normal 0.31786 -0.857436 0.404683 + outer loop + vertex 613.292 96.7549 34.6517 + vertex 615.377 97.2064 33.9708 + vertex 615.469 97.4219 34.3544 + endloop + endfacet + facet normal 0.318912 -0.857222 0.404308 + outer loop + vertex 615.377 97.2064 33.9708 + vertex 617.499 97.622 33.1782 + vertex 615.469 97.4219 34.3544 + endloop + endfacet + facet normal 0.325802 -0.841476 0.431012 + outer loop + vertex 615.377 97.2064 33.9708 + vertex 616.995 97.4103 33.1458 + vertex 617.499 97.622 33.1782 + endloop + endfacet + facet normal 0.323914 -0.838172 0.438803 + outer loop + vertex 616.995 97.4103 33.1458 + vertex 619.754 97.9672 32.1727 + vertex 617.499 97.622 33.1782 + endloop + endfacet + facet normal 0.327261 -0.831696 0.448533 + outer loop + vertex 617.499 97.622 33.1782 + vertex 619.754 97.9672 32.1727 + vertex 620.3 98.1564 32.1252 + endloop + endfacet + facet normal 0.323759 -0.840285 0.434858 + outer loop + vertex 617.499 97.622 33.1782 + vertex 620.3 98.1564 32.1252 + vertex 618.469 97.9065 33.0055 + endloop + endfacet + facet normal 0.324332 -0.815505 0.479334 + outer loop + vertex 619.754 97.9672 32.1727 + vertex 622.841 98.5774 31.1219 + vertex 620.3 98.1564 32.1252 + endloop + endfacet + facet normal 0.330669 -0.798948 0.502335 + outer loop + vertex 620.3 98.1564 32.1252 + vertex 622.841 98.5774 31.1219 + vertex 623.281 98.7764 31.1485 + endloop + endfacet + facet normal 0.32526 -0.818644 0.473317 + outer loop + vertex 620.3 98.1564 32.1252 + vertex 623.281 98.7764 31.1485 + vertex 621.223 98.4356 31.9734 + endloop + endfacet + facet normal 0.325424 -0.789708 0.520058 + outer loop + vertex 623.281 98.7764 31.1485 + vertex 622.841 98.5774 31.1219 + vertex 627.1 99.5452 29.9263 + endloop + endfacet + facet normal 0.327202 -0.778721 0.535288 + outer loop + vertex 622.841 98.5774 31.1219 + vertex 624.818 98.6023 29.9495 + vertex 627.1 99.5452 29.9263 + endloop + endfacet + facet normal 0.321195 -0.788197 0.524957 + outer loop + vertex 621.611 97.9 30.8574 + vertex 624.818 98.6023 29.9495 + vertex 622.841 98.5774 31.1219 + endloop + endfacet + facet normal 0.325511 -0.760897 0.561319 + outer loop + vertex 621.611 97.9 30.8574 + vertex 623.124 97.369 29.2604 + vertex 624.818 98.6023 29.9495 + endloop + endfacet + facet normal 0.31268 -0.75308 0.57888 + outer loop + vertex 623.124 97.369 29.2604 + vertex 626.001 98.13 28.6965 + vertex 624.818 98.6023 29.9495 + endloop + endfacet + facet normal 0.325704 -0.741374 0.586755 + outer loop + vertex 624.818 98.6023 29.9495 + vertex 626.001 98.13 28.6965 + vertex 627.473 99.1751 29.1997 + endloop + endfacet + facet normal 0.322318 -0.766401 0.555644 + outer loop + vertex 627.473 99.1751 29.1997 + vertex 627.1 99.5452 29.9263 + vertex 624.818 98.6023 29.9495 + endloop + endfacet + facet normal 0.32053 -0.767433 0.555254 + outer loop + vertex 627.473 99.1751 29.1997 + vertex 630.091 99.9274 28.7284 + vertex 627.1 99.5452 29.9263 + endloop + endfacet + facet normal 0.322898 -0.760485 0.563382 + outer loop + vertex 632.627 100.955 28.6616 + vertex 627.1 99.5452 29.9263 + vertex 630.091 99.9274 28.7284 + endloop + endfacet + facet normal 0.318193 -0.723 0.613208 + outer loop + vertex 627.473 99.1751 29.1997 + vertex 628.725 98.8627 28.1816 + vertex 630.091 99.9274 28.7284 + endloop + endfacet + facet normal 0.305141 -0.714611 0.62946 + outer loop + vertex 628.725 98.8627 28.1816 + vertex 631.462 99.6014 27.6934 + vertex 630.091 99.9274 28.7284 + endloop + endfacet + facet normal 0.317493 -0.698904 0.640883 + outer loop + vertex 630.091 99.9274 28.7284 + vertex 631.462 99.6014 27.6934 + vertex 632.839 100.598 28.0986 + endloop + endfacet + facet normal 0.31653 -0.743057 0.58964 + outer loop + vertex 632.839 100.598 28.0986 + vertex 632.627 100.955 28.6616 + vertex 630.091 99.9274 28.7284 + endloop + endfacet + facet normal 0.310227 -0.746076 0.589178 + outer loop + vertex 632.839 100.598 28.0986 + vertex 635.579 101.402 27.673 + vertex 632.627 100.955 28.6616 + endloop + endfacet + facet normal 0.311763 -0.739338 0.596811 + outer loop + vertex 638.064 102.339 27.5361 + vertex 632.627 100.955 28.6616 + vertex 635.579 101.402 27.673 + endloop + endfacet + facet normal 0.301305 -0.666506 0.681898 + outer loop + vertex 632.839 100.598 28.0986 + vertex 634.466 100.397 27.1824 + vertex 635.579 101.402 27.673 + endloop + endfacet + facet normal 0.283127 -0.655338 0.700265 + outer loop + vertex 634.466 100.397 27.1824 + vertex 637.808 101.368 26.7405 + vertex 635.579 101.402 27.673 + endloop + endfacet + facet normal 0.29413 -0.622347 0.725377 + outer loop + vertex 635.579 101.402 27.673 + vertex 637.808 101.368 26.7405 + vertex 638.121 102.041 27.1913 + endloop + endfacet + facet normal 0.298999 -0.697562 0.651158 + outer loop + vertex 638.121 102.041 27.1913 + vertex 638.064 102.339 27.5361 + vertex 635.579 101.402 27.673 + endloop + endfacet + facet normal 0.267973 -0.70715 0.654316 + outer loop + vertex 638.121 102.041 27.1913 + vertex 641.435 102.584 26.4207 + vertex 638.064 102.339 27.5361 + endloop + endfacet + facet normal 0.291134 -0.595307 0.748899 + outer loop + vertex 638.064 102.339 27.5361 + vertex 641.435 102.584 26.4207 + vertex 642.639 103.527 26.7015 + endloop + endfacet + facet normal 0.266438 -0.571792 0.775928 + outer loop + vertex 642.639 103.527 26.7015 + vertex 641.435 102.584 26.4207 + vertex 647.221 104.41 25.7789 + endloop + endfacet + facet normal 0.272641 -0.619534 0.736101 + outer loop + vertex 638.121 102.041 27.1913 + vertex 637.808 101.368 26.7405 + vertex 641.435 102.584 26.4207 + endloop + endfacet + facet normal 0.294209 -0.679453 0.672149 + outer loop + vertex 631.462 99.6014 27.6934 + vertex 634.466 100.397 27.1824 + vertex 632.839 100.598 28.0986 + endloop + endfacet + facet normal 0.311336 -0.73099 0.607226 + outer loop + vertex 626.001 98.13 28.6965 + vertex 628.725 98.8627 28.1816 + vertex 627.473 99.1751 29.1997 + endloop + endfacet + facet normal 0.30947 -0.775109 0.550849 + outer loop + vertex 620.372 96.6018 29.7268 + vertex 623.124 97.369 29.2604 + vertex 621.611 97.9 30.8574 + endloop + endfacet + facet normal 0.315365 -0.776319 0.545778 + outer loop + vertex 620.372 96.6018 29.7268 + vertex 621.611 97.9 30.8574 + vertex 619.49 97.2348 31.1371 + endloop + endfacet + facet normal 0.306332 -0.782068 0.542707 + outer loop + vertex 618.027 95.9351 30.0896 + vertex 620.372 96.6018 29.7268 + vertex 619.49 97.2348 31.1371 + endloop + endfacet + facet normal 0.320244 -0.78624 0.528461 + outer loop + vertex 617.674 96.7411 31.5029 + vertex 618.027 95.9351 30.0896 + vertex 619.49 97.2348 31.1371 + endloop + endfacet + facet normal 0.319356 -0.809508 0.492654 + outer loop + vertex 617.674 96.7411 31.5029 + vertex 619.49 97.2348 31.1371 + vertex 618.657 97.5441 32.1852 + endloop + endfacet + facet normal 0.329319 -0.812224 0.481498 + outer loop + vertex 617.172 97.1273 32.4974 + vertex 617.674 96.7411 31.5029 + vertex 618.657 97.5441 32.1852 + endloop + endfacet + facet normal 0.327973 -0.829548 0.451977 + outer loop + vertex 617.172 97.1273 32.4974 + vertex 618.657 97.5441 32.1852 + vertex 616.995 97.4103 33.1458 + endloop + endfacet + facet normal 0.329257 -0.828982 0.452083 + outer loop + vertex 617.172 97.1273 32.4974 + vertex 616.995 97.4103 33.1458 + vertex 615.752 96.8532 33.029 + endloop + endfacet + facet normal 0.332243 -0.821099 0.464124 + outer loop + vertex 615.752 96.8532 33.029 + vertex 616.119 96.3889 31.945 + vertex 617.172 97.1273 32.4974 + endloop + endfacet + facet normal 0.324083 -0.824973 0.463021 + outer loop + vertex 614.667 96.0499 32.3577 + vertex 616.119 96.3889 31.945 + vertex 615.752 96.8532 33.029 + endloop + endfacet + facet normal 0.327923 -0.826142 0.45821 + outer loop + vertex 614.348 96.4812 33.3635 + vertex 614.667 96.0499 32.3577 + vertex 615.752 96.8532 33.029 + endloop + endfacet + facet normal 0.327003 -0.832439 0.447342 + outer loop + vertex 614.348 96.4812 33.3635 + vertex 615.752 96.8532 33.029 + vertex 614.495 96.8713 33.9816 + endloop + endfacet + facet normal 0.320317 -0.833736 0.449757 + outer loop + vertex 614.348 96.4812 33.3635 + vertex 614.495 96.8713 33.9816 + vertex 613.074 96.2449 33.8325 + endloop + endfacet + facet normal 0.32224 -0.828783 0.457472 + outer loop + vertex 613.074 96.2449 33.8325 + vertex 613.229 95.7124 32.7584 + vertex 614.348 96.4812 33.3635 + endloop + endfacet + facet normal 0.313381 -0.831999 0.457789 + outer loop + vertex 611.853 95.3766 33.0903 + vertex 613.229 95.7124 32.7584 + vertex 613.074 96.2449 33.8325 + endloop + endfacet + facet normal 0.310924 -0.831202 0.460901 + outer loop + vertex 611.775 95.8335 33.9668 + vertex 611.853 95.3766 33.0903 + vertex 613.074 96.2449 33.8325 + endloop + endfacet + facet normal 0.311703 -0.837775 0.448301 + outer loop + vertex 611.775 95.8335 33.9668 + vertex 613.074 96.2449 33.8325 + vertex 612.476 96.3467 34.4384 + endloop + endfacet + facet normal 0.305409 -0.836054 0.455784 + outer loop + vertex 611.775 95.8335 33.9668 + vertex 612.476 96.3467 34.4384 + vertex 610.928 95.5395 33.9952 + endloop + endfacet + facet normal 0.304355 -0.832291 0.463315 + outer loop + vertex 611.775 95.8335 33.9668 + vertex 610.928 95.5395 33.9952 + vertex 610.651 94.9691 33.1526 + endloop + endfacet + facet normal 0.313144 -0.841919 0.439446 + outer loop + vertex 610.928 95.5395 33.9952 + vertex 612.476 96.3467 34.4384 + vertex 611.361 96.0112 34.5905 + endloop + endfacet + facet normal 0.317022 -0.84193 0.436635 + outer loop + vertex 610.15 95.0579 33.6314 + vertex 610.928 95.5395 33.9952 + vertex 611.361 96.0112 34.5905 + endloop + endfacet + facet normal 0.450023 -0.849282 0.276042 + outer loop + vertex 610.15 95.0579 33.6314 + vertex 611.361 96.0112 34.5905 + vertex 610.151 95.0884 33.724 + endloop + endfacet + facet normal 0.575189 -0.778367 0.251598 + outer loop + vertex 610.151 95.0884 33.724 + vertex 609.08 93.8024 32.1941 + vertex 610.15 95.0579 33.6314 + endloop + endfacet + facet normal 0.301879 -0.817963 0.4897 + outer loop + vertex 609.08 93.8024 32.1941 + vertex 609.595 94.1702 32.491 + vertex 610.15 95.0579 33.6314 + endloop + endfacet + facet normal -0.0461079 0.780339 -0.623655 + outer loop + vertex 608.91 93.493 31.8195 + vertex 609.08 93.8024 32.1941 + vertex 610.151 95.0884 33.724 + endloop + endfacet + facet normal 0.396308 -0.814343 0.424012 + outer loop + vertex 608.91 93.493 31.8195 + vertex 610.151 95.0884 33.724 + vertex 609.687 94.6868 33.3865 + endloop + endfacet + facet normal 0.368238 -0.845646 0.386373 + outer loop + vertex 611.235 96.4954 35.7707 + vertex 610.151 95.0884 33.724 + vertex 611.361 96.0112 34.5905 + endloop + endfacet + facet normal 0.270521 -0.819102 0.505855 + outer loop + vertex 610.15 95.0579 33.6314 + vertex 609.595 94.1702 32.491 + vertex 610.928 95.5395 33.9952 + endloop + endfacet + facet normal 0.313354 -0.848621 0.426206 + outer loop + vertex 613.292 96.7549 34.6517 + vertex 611.361 96.0112 34.5905 + vertex 612.476 96.3467 34.4384 + endloop + endfacet + facet normal 0.316073 -0.850755 0.419898 + outer loop + vertex 612.476 96.3467 34.4384 + vertex 614.495 96.8713 33.9816 + vertex 613.292 96.7549 34.6517 + endloop + endfacet + facet normal 0.306177 -0.832749 0.461285 + outer loop + vertex 610.651 94.9691 33.1526 + vertex 611.853 95.3766 33.0903 + vertex 611.775 95.8335 33.9668 + endloop + endfacet + facet normal 0.302234 -0.816408 0.49207 + outer loop + vertex 610.651 94.9691 33.1526 + vertex 610.687 94.2523 31.941 + vertex 611.853 95.3766 33.0903 + endloop + endfacet + facet normal 0.310982 -0.817683 0.484444 + outer loop + vertex 610.687 94.2523 31.941 + vertex 611.983 94.7119 31.8849 + vertex 611.853 95.3766 33.0903 + endloop + endfacet + facet normal 0.300917 -0.781769 0.546157 + outer loop + vertex 611.983 94.7119 31.8849 + vertex 610.687 94.2523 31.941 + vertex 611.49 93.2718 30.0952 + endloop + endfacet + facet normal 0.327287 -0.778188 0.53601 + outer loop + vertex 611.983 94.7119 31.8849 + vertex 611.49 93.2718 30.0952 + vertex 613.275 94.8829 31.3445 + endloop + endfacet + facet normal 0.312142 -0.81503 0.488153 + outer loop + vertex 611.983 94.7119 31.8849 + vertex 613.275 94.8829 31.3445 + vertex 613.229 95.7124 32.7584 + endloop + endfacet + facet normal 0.325964 -0.810819 0.486128 + outer loop + vertex 613.229 95.7124 32.7584 + vertex 613.275 94.8829 31.3445 + vertex 614.667 96.0499 32.3577 + endloop + endfacet + facet normal 0.325449 -0.81069 0.486686 + outer loop + vertex 613.275 94.8829 31.3445 + vertex 614.805 95.4132 31.2044 + vertex 614.667 96.0499 32.3577 + endloop + endfacet + facet normal 0.318239 -0.773742 0.547766 + outer loop + vertex 614.805 95.4132 31.2044 + vertex 613.275 94.8829 31.3445 + vertex 614.027 94.1136 29.8207 + endloop + endfacet + facet normal 0.321929 -0.773706 0.545657 + outer loop + vertex 614.805 95.4132 31.2044 + vertex 614.027 94.1136 29.8207 + vertex 616.079 95.4878 30.5587 + endloop + endfacet + facet normal 0.306756 -0.802058 0.512449 + outer loop + vertex 614.805 95.4132 31.2044 + vertex 616.079 95.4878 30.5587 + vertex 616.119 96.3889 31.945 + endloop + endfacet + facet normal 0.325233 -0.797139 0.508717 + outer loop + vertex 616.119 96.3889 31.945 + vertex 616.079 95.4878 30.5587 + vertex 617.674 96.7411 31.5029 + endloop + endfacet + facet normal 0.296565 -0.756104 0.583401 + outer loop + vertex 614.027 94.1136 29.8207 + vertex 616.25 94.1933 28.7943 + vertex 616.079 95.4878 30.5587 + endloop + endfacet + facet normal 0.312453 -0.75125 0.581375 + outer loop + vertex 618.027 95.9351 30.0896 + vertex 616.079 95.4878 30.5587 + vertex 616.25 94.1933 28.7943 + endloop + endfacet + facet normal 0.302872 -0.748156 0.590365 + outer loop + vertex 616.25 94.1933 28.7943 + vertex 618.73 95.0761 28.6407 + vertex 618.027 95.9351 30.0896 + endloop + endfacet + facet normal 0.303928 -0.747589 0.590541 + outer loop + vertex 618.027 95.9351 30.0896 + vertex 618.73 95.0761 28.6407 + vertex 620.372 96.6018 29.7268 + endloop + endfacet + facet normal 0.283471 -0.739671 0.610353 + outer loop + vertex 618.73 95.0761 28.6407 + vertex 621.417 95.6217 28.0538 + vertex 620.372 96.6018 29.7268 + endloop + endfacet + facet normal 0.306683 -0.725252 0.616405 + outer loop + vertex 620.372 96.6018 29.7268 + vertex 621.417 95.6217 28.0538 + vertex 623.124 97.369 29.2604 + endloop + endfacet + facet normal 0.30096 -0.723233 0.621577 + outer loop + vertex 621.417 95.6217 28.0538 + vertex 624.302 96.687 27.8966 + vertex 623.124 97.369 29.2604 + endloop + endfacet + facet normal 0.311771 -0.714369 0.626479 + outer loop + vertex 623.124 97.369 29.2604 + vertex 624.302 96.687 27.8966 + vertex 626.001 98.13 28.6965 + endloop + endfacet + facet normal 0.286405 -0.699914 0.654288 + outer loop + vertex 624.302 96.687 27.8966 + vertex 627.089 97.2468 27.2753 + vertex 626.001 98.13 28.6965 + endloop + endfacet + facet normal 0.308812 -0.683598 0.661308 + outer loop + vertex 626.001 98.13 28.6965 + vertex 627.089 97.2468 27.2753 + vertex 628.725 98.8627 28.1816 + endloop + endfacet + facet normal 0.293608 -0.676241 0.675642 + outer loop + vertex 627.089 97.2468 27.2753 + vertex 629.897 98.2534 27.0624 + vertex 628.725 98.8627 28.1816 + endloop + endfacet + facet normal 0.301665 -0.668446 0.679837 + outer loop + vertex 628.725 98.8627 28.1816 + vertex 629.897 98.2534 27.0624 + vertex 631.462 99.6014 27.6934 + endloop + endfacet + facet normal 0.271626 -0.648296 0.711289 + outer loop + vertex 629.897 98.2534 27.0624 + vertex 632.754 98.7522 26.426 + vertex 631.462 99.6014 27.6934 + endloop + endfacet + facet normal 0.289598 -0.632088 0.718747 + outer loop + vertex 631.462 99.6014 27.6934 + vertex 632.754 98.7522 26.426 + vertex 634.466 100.397 27.1824 + endloop + endfacet + facet normal 0.259732 -0.613444 0.745806 + outer loop + vertex 632.754 98.7522 26.426 + vertex 636.685 99.8059 25.9238 + vertex 634.466 100.397 27.1824 + endloop + endfacet + facet normal 0.272459 -0.592244 0.758296 + outer loop + vertex 634.466 100.397 27.1824 + vertex 636.685 99.8059 25.9238 + vertex 637.808 101.368 26.7405 + endloop + endfacet + facet normal 0.249512 -0.583396 0.772912 + outer loop + vertex 636.685 99.8059 25.9238 + vertex 641.019 101.135 25.5274 + vertex 637.808 101.368 26.7405 + endloop + endfacet + facet normal 0.257019 -0.559262 0.788141 + outer loop + vertex 641.019 101.135 25.5274 + vertex 641.435 102.584 26.4207 + vertex 637.808 101.368 26.7405 + endloop + endfacet + facet normal 0.242857 -0.558359 0.793256 + outer loop + vertex 641.019 101.135 25.5274 + vertex 645.973 102.679 25.0976 + vertex 641.435 102.584 26.4207 + endloop + endfacet + facet normal 0.251101 -0.505822 0.825283 + outer loop + vertex 641.435 102.584 26.4207 + vertex 645.973 102.679 25.0976 + vertex 647.221 104.41 25.7789 + endloop + endfacet + facet normal 0.22561 -0.493282 0.840103 + outer loop + vertex 645.973 102.679 25.0976 + vertex 651.414 104.385 24.6385 + vertex 647.221 104.41 25.7789 + endloop + endfacet + facet normal 0.22914 -0.469678 0.852583 + outer loop + vertex 647.221 104.41 25.7789 + vertex 651.414 104.385 24.6385 + vertex 653.384 106.34 25.1858 + endloop + endfacet + facet normal 0.233953 -0.488771 0.840457 + outer loop + vertex 647.221 104.41 25.7789 + vertex 653.384 106.34 25.1858 + vertex 650.615 105.947 25.7285 + endloop + endfacet + facet normal 0.234803 -0.531693 0.813739 + outer loop + vertex 653.437 107.095 25.6639 + vertex 650.615 105.947 25.7285 + vertex 653.384 106.34 25.1858 + endloop + endfacet + facet normal 0.218217 -0.532928 0.817539 + outer loop + vertex 657.26 108.727 25.7077 + vertex 653.437 107.095 25.6639 + vertex 653.384 106.34 25.1858 + endloop + endfacet + facet normal 0.259023 -0.626275 0.735315 + outer loop + vertex 653.437 107.095 25.6639 + vertex 657.26 108.727 25.7077 + vertex 655.119 108.099 25.9263 + endloop + endfacet + facet normal 0.193524 -0.338763 0.920754 + outer loop + vertex 656.258 108.49 25.831 + vertex 655.119 108.099 25.9263 + vertex 657.26 108.727 25.7077 + endloop + endfacet + facet normal 0.245659 -0.676793 0.693976 + outer loop + vertex 656.902 109.102 26.1994 + vertex 656.258 108.49 25.831 + vertex 657.26 108.727 25.7077 + endloop + endfacet + facet normal 0.262616 -0.666044 0.698153 + outer loop + vertex 657.26 108.727 25.7077 + vertex 658.755 110.243 26.591 + vertex 656.902 109.102 26.1994 + endloop + endfacet + facet normal 0.295483 -0.701718 0.648291 + outer loop + vertex 656.258 108.49 25.831 + vertex 656.902 109.102 26.1994 + vertex 655.119 108.099 25.9263 + endloop + endfacet + facet normal 0.303406 -0.711772 0.633502 + outer loop + vertex 655.119 108.099 25.9263 + vertex 656.902 109.102 26.1994 + vertex 655.799 109.037 26.6548 + endloop + endfacet + facet normal 0.298654 -0.710867 0.636768 + outer loop + vertex 655.119 108.099 25.9263 + vertex 655.799 109.037 26.6548 + vertex 651.698 106.929 26.2248 + endloop + endfacet + facet normal 0.286688 -0.66155 0.692936 + outer loop + vertex 655.119 108.099 25.9263 + vertex 651.698 106.929 26.2248 + vertex 653.437 107.095 25.6639 + endloop + endfacet + facet normal 0.286081 -0.664776 0.690095 + outer loop + vertex 650.615 105.947 25.7285 + vertex 653.437 107.095 25.6639 + vertex 651.698 106.929 26.2248 + endloop + endfacet + facet normal 0.279686 -0.660906 0.696404 + outer loop + vertex 648.109 105.333 26.1522 + vertex 650.615 105.947 25.7285 + vertex 651.698 106.929 26.2248 + endloop + endfacet + facet normal 0.271186 -0.573152 0.773276 + outer loop + vertex 650.615 105.947 25.7285 + vertex 648.109 105.333 26.1522 + vertex 647.221 104.41 25.7789 + endloop + endfacet + facet normal 0.263151 -0.568058 0.779783 + outer loop + vertex 648.109 105.333 26.1522 + vertex 645.4 104.459 26.4295 + vertex 647.221 104.41 25.7789 + endloop + endfacet + facet normal 0.20473 -0.449776 0.86936 + outer loop + vertex 651.414 104.385 24.6385 + vertex 656.734 106.115 24.2806 + vertex 653.384 106.34 25.1858 + endloop + endfacet + facet normal 0.205821 -0.444137 0.871998 + outer loop + vertex 653.384 106.34 25.1858 + vertex 656.734 106.115 24.2806 + vertex 658.665 108.039 24.8047 + endloop + endfacet + facet normal 0.237067 -0.558572 0.794856 + outer loop + vertex 653.384 106.34 25.1858 + vertex 658.665 108.039 24.8047 + vertex 657.26 108.727 25.7077 + endloop + endfacet + facet normal 0.187756 -0.42914 0.883508 + outer loop + vertex 656.734 106.115 24.2806 + vertex 661.787 107.844 24.0464 + vertex 658.665 108.039 24.8047 + endloop + endfacet + facet normal 0.189519 -0.418761 0.8881 + outer loop + vertex 658.665 108.039 24.8047 + vertex 661.787 107.844 24.0464 + vertex 663.455 109.634 24.5349 + endloop + endfacet + facet normal 0.221373 -0.525669 0.821381 + outer loop + vertex 658.665 108.039 24.8047 + vertex 663.455 109.634 24.5349 + vertex 661.994 110.088 25.219 + endloop + endfacet + facet normal 0.169709 -0.403336 0.899177 + outer loop + vertex 661.787 107.844 24.0464 + vertex 666.857 109.634 23.8928 + vertex 663.455 109.634 24.5349 + endloop + endfacet + facet normal 0.170133 -0.398118 0.90142 + outer loop + vertex 663.455 109.634 24.5349 + vertex 666.857 109.634 23.8928 + vertex 668.429 111.386 24.3697 + endloop + endfacet + facet normal 0.198471 -0.483187 0.852725 + outer loop + vertex 663.455 109.634 24.5349 + vertex 668.429 111.386 24.3697 + vertex 666.002 111.27 24.869 + endloop + endfacet + facet normal 0.197536 -0.496958 0.844992 + outer loop + vertex 671.38 113.289 24.7991 + vertex 666.002 111.27 24.869 + vertex 668.429 111.386 24.3697 + endloop + endfacet + facet normal 0.237544 -0.606512 0.75876 + outer loop + vertex 666.002 111.27 24.869 + vertex 671.38 113.289 24.7991 + vertex 667.973 112.716 25.4079 + endloop + endfacet + facet normal 0.246881 -0.615426 0.748532 + outer loop + vertex 661.994 110.088 25.219 + vertex 666.002 111.27 24.869 + vertex 667.973 112.716 25.4079 + endloop + endfacet + facet normal 0.225048 -0.518853 0.824709 + outer loop + vertex 666.002 111.27 24.869 + vertex 661.994 110.088 25.219 + vertex 663.455 109.634 24.5349 + endloop + endfacet + facet normal 0.237579 -0.60797 0.757581 + outer loop + vertex 679.014 116.793 25.217 + vertex 667.973 112.716 25.4079 + vertex 671.38 113.289 24.7991 + endloop + endfacet + facet normal 0.221755 -0.576899 0.786137 + outer loop + vertex 671.38 113.289 24.7991 + vertex 676.179 114.897 24.6255 + vertex 679.014 116.793 25.217 + endloop + endfacet + facet normal 0.219696 -0.57454 0.78844 + outer loop + vertex 676.179 114.897 24.6255 + vertex 679.837 116.263 24.6014 + vertex 679.014 116.793 25.217 + endloop + endfacet + facet normal 0.222859 -0.571316 0.789894 + outer loop + vertex 679.837 116.263 24.6014 + vertex 682.952 117.587 24.6802 + vertex 679.014 116.793 25.217 + endloop + endfacet + facet normal 0.222285 -0.565573 0.794176 + outer loop + vertex 682.952 117.587 24.6802 + vertex 686.909 119.305 24.7963 + vertex 679.014 116.793 25.217 + endloop + endfacet + facet normal 0.220375 -0.558666 0.799579 + outer loop + vertex 686.909 119.305 24.7963 + vertex 687.854 120.191 25.1547 + vertex 679.014 116.793 25.217 + endloop + endfacet + facet normal 0.215918 -0.555336 0.803107 + outer loop + vertex 693.145 121.939 24.9412 + vertex 687.854 120.191 25.1547 + vertex 686.909 119.305 24.7963 + endloop + endfacet + facet normal 0.221042 -0.572495 0.78955 + outer loop + vertex 691.686 121.954 25.3601 + vertex 687.854 120.191 25.1547 + vertex 693.145 121.939 24.9412 + endloop + endfacet + facet normal 0.218605 -0.584409 0.781459 + outer loop + vertex 691.686 121.954 25.3601 + vertex 693.145 121.939 24.9412 + vertex 695.738 123.893 25.677 + endloop + endfacet + facet normal 0.229227 -0.594472 0.770752 + outer loop + vertex 700.046 124.828 25.1167 + vertex 695.738 123.893 25.677 + vertex 693.145 121.939 24.9412 + endloop + endfacet + facet normal 0.23226 -0.622452 0.747401 + outer loop + vertex 695.738 123.893 25.677 + vertex 700.046 124.828 25.1167 + vertex 699.542 125.933 26.1941 + endloop + endfacet + facet normal 0.245467 -0.616847 0.747827 + outer loop + vertex 701.687 126.635 26.0687 + vertex 699.542 125.933 26.1941 + vertex 700.046 124.828 25.1167 + endloop + endfacet + facet normal 0.256261 -0.622327 0.739621 + outer loop + vertex 704.046 127.268 25.7844 + vertex 701.687 126.635 26.0687 + vertex 700.046 124.828 25.1167 + endloop + endfacet + facet normal 0.244387 -0.607329 0.755928 + outer loop + vertex 700.046 124.828 25.1167 + vertex 705.913 127.004 24.9681 + vertex 704.046 127.268 25.7844 + endloop + endfacet + facet normal 0.244808 -0.606354 0.756574 + outer loop + vertex 707.928 128.841 25.7888 + vertex 704.046 127.268 25.7844 + vertex 705.913 127.004 24.9681 + endloop + endfacet + facet normal 0.249828 -0.609862 0.7521 + outer loop + vertex 705.913 127.004 24.9681 + vertex 710.781 129.05 25.0104 + vertex 707.928 128.841 25.7888 + endloop + endfacet + facet normal 0.248487 -0.619553 0.744586 + outer loop + vertex 712.232 130.794 25.9775 + vertex 707.928 128.841 25.7888 + vertex 710.781 129.05 25.0104 + endloop + endfacet + facet normal 0.260401 -0.624765 0.736111 + outer loop + vertex 710.781 129.05 25.0104 + vertex 716.305 131.602 25.2218 + vertex 712.232 130.794 25.9775 + endloop + endfacet + facet normal 0.260783 -0.635378 0.726833 + outer loop + vertex 716.117 132.785 26.324 + vertex 712.232 130.794 25.9775 + vertex 716.305 131.602 25.2218 + endloop + endfacet + facet normal 0.274428 -0.631595 0.725104 + outer loop + vertex 720.739 134.643 26.1926 + vertex 716.117 132.785 26.324 + vertex 716.305 131.602 25.2218 + endloop + endfacet + facet normal 0.271054 -0.628057 0.729434 + outer loop + vertex 716.305 131.602 25.2218 + vertex 722.278 133.973 25.0438 + vertex 720.739 134.643 26.1926 + endloop + endfacet + facet normal 0.278844 -0.618743 0.73444 + outer loop + vertex 727.494 137.314 25.8787 + vertex 720.739 134.643 26.1926 + vertex 722.278 133.973 25.0438 + endloop + endfacet + facet normal 0.271742 -0.610111 0.744258 + outer loop + vertex 722.278 133.973 25.0438 + vertex 726.653 135.646 24.8187 + vertex 727.494 137.314 25.8787 + endloop + endfacet + facet normal 0.275611 -0.610799 0.742269 + outer loop + vertex 726.653 135.646 24.8187 + vertex 730.592 137.555 24.9267 + vertex 727.494 137.314 25.8787 + endloop + endfacet + facet normal 0.276683 -0.603893 0.747503 + outer loop + vertex 730.592 137.555 24.9267 + vertex 735.65 140.688 25.5857 + vertex 727.494 137.314 25.8787 + endloop + endfacet + facet normal 0.198947 -0.514524 0.834077 + outer loop + vertex 682.952 117.587 24.6802 + vertex 686.06 118.504 24.5046 + vertex 686.909 119.305 24.7963 + endloop + endfacet + facet normal 0.200039 -0.515391 0.833281 + outer loop + vertex 686.06 118.504 24.5046 + vertex 688.211 119.374 24.5265 + vertex 686.909 119.305 24.7963 + endloop + endfacet + facet normal 0.199887 -0.517509 0.832003 + outer loop + vertex 688.211 119.374 24.5265 + vertex 690.951 120.459 24.5433 + vertex 686.909 119.305 24.7963 + endloop + endfacet + facet normal 0.200656 -0.520675 0.82984 + outer loop + vertex 693.145 121.939 24.9412 + vertex 686.909 119.305 24.7963 + vertex 690.951 120.459 24.5433 + endloop + endfacet + facet normal 0.207572 -0.529042 0.822818 + outer loop + vertex 690.951 120.459 24.5433 + vertex 693.76 121.589 24.5607 + vertex 693.145 121.939 24.9412 + endloop + endfacet + facet normal 0.204765 -0.532384 0.821364 + outer loop + vertex 693.76 121.589 24.5607 + vertex 696.216 122.571 24.5854 + vertex 693.145 121.939 24.9412 + endloop + endfacet + facet normal 0.205909 -0.541458 0.815123 + outer loop + vertex 696.216 122.571 24.5854 + vertex 700.046 124.828 25.1167 + vertex 693.145 121.939 24.9412 + endloop + endfacet + facet normal 0.178472 -0.502189 0.846141 + outer loop + vertex 700.046 124.828 25.1167 + vertex 696.216 122.571 24.5854 + vertex 699.393 123.111 24.2355 + endloop + endfacet + facet normal 0.204834 -0.507503 0.836949 + outer loop + vertex 699.393 123.111 24.2355 + vertex 704.354 125.201 24.2889 + vertex 700.046 124.828 25.1167 + endloop + endfacet + facet normal 0.205153 -0.495521 0.844021 + outer loop + vertex 705.913 127.004 24.9681 + vertex 700.046 124.828 25.1167 + vertex 704.354 125.201 24.2889 + endloop + endfacet + facet normal 0.205585 -0.495794 0.843755 + outer loop + vertex 704.354 125.201 24.2889 + vertex 709.437 127.307 24.2875 + vertex 705.913 127.004 24.9681 + endloop + endfacet + facet normal 0.20531 -0.505737 0.837901 + outer loop + vertex 710.781 129.05 25.0104 + vertex 705.913 127.004 24.9681 + vertex 709.437 127.307 24.2875 + endloop + endfacet + facet normal 0.172736 -0.448435 0.876965 + outer loop + vertex 694.337 121.12 24.2133 + vertex 699.393 123.111 24.2355 + vertex 696.216 122.571 24.5854 + endloop + endfacet + facet normal 0.16889 -0.444199 0.879866 + outer loop + vertex 696.216 122.571 24.5854 + vertex 693.76 121.589 24.5607 + vertex 694.337 121.12 24.2133 + endloop + endfacet + facet normal 0.171898 -0.441187 0.880798 + outer loop + vertex 693.76 121.589 24.5607 + vertex 690.951 120.459 24.5433 + vertex 694.337 121.12 24.2133 + endloop + endfacet + facet normal 0.172653 -0.446459 0.877989 + outer loop + vertex 689.035 119.072 24.2143 + vertex 694.337 121.12 24.2133 + vertex 690.951 120.459 24.5433 + endloop + endfacet + facet normal 0.170382 -0.443755 0.879802 + outer loop + vertex 690.951 120.459 24.5433 + vertex 688.211 119.374 24.5265 + vertex 689.035 119.072 24.2143 + endloop + endfacet + facet normal 0.170492 -0.443543 0.879888 + outer loop + vertex 688.211 119.374 24.5265 + vertex 686.06 118.504 24.5046 + vertex 689.035 119.072 24.2143 + endloop + endfacet + facet normal 0.170654 -0.444711 0.879266 + outer loop + vertex 683.646 117.052 24.2389 + vertex 689.035 119.072 24.2143 + vertex 686.06 118.504 24.5046 + endloop + endfacet + facet normal 0.187234 -0.4693 0.862961 + outer loop + vertex 686.06 118.504 24.5046 + vertex 682.952 117.587 24.6802 + vertex 683.646 117.052 24.2389 + endloop + endfacet + facet normal 0.180581 -0.47606 0.860672 + outer loop + vertex 682.952 117.587 24.6802 + vertex 679.837 116.263 24.6014 + vertex 683.646 117.052 24.2389 + endloop + endfacet + facet normal 0.179501 -0.468966 0.864783 + outer loop + vertex 678.613 115.052 24.1989 + vertex 683.646 117.052 24.2389 + vertex 679.837 116.263 24.6014 + endloop + endfacet + facet normal 0.181314 -0.470412 0.863619 + outer loop + vertex 679.837 116.263 24.6014 + vertex 676.179 114.897 24.6255 + vertex 678.613 115.052 24.1989 + endloop + endfacet + facet normal 0.181368 -0.468643 0.864569 + outer loop + vertex 673.662 113.251 24.2611 + vertex 678.613 115.052 24.1989 + vertex 676.179 114.897 24.6255 + endloop + endfacet + facet normal 0.193097 -0.484111 0.853434 + outer loop + vertex 676.179 114.897 24.6255 + vertex 671.38 113.289 24.7991 + vertex 673.662 113.251 24.2611 + endloop + endfacet + facet normal 0.192255 -0.489963 0.850279 + outer loop + vertex 668.429 111.386 24.3697 + vertex 673.662 113.251 24.2611 + vertex 671.38 113.289 24.7991 + endloop + endfacet + facet normal 0.157679 -0.388672 0.907784 + outer loop + vertex 666.857 109.634 23.8928 + vertex 672.092 111.505 23.7847 + vertex 668.429 111.386 24.3697 + endloop + endfacet + facet normal 0.157649 -0.389528 0.907422 + outer loop + vertex 668.429 111.386 24.3697 + vertex 672.092 111.505 23.7847 + vertex 673.662 113.251 24.2611 + endloop + endfacet + facet normal 0.151215 -0.384609 0.91061 + outer loop + vertex 672.092 111.505 23.7847 + vertex 677.366 113.41 23.7131 + vertex 673.662 113.251 24.2611 + endloop + endfacet + facet normal 0.151223 -0.384198 0.910782 + outer loop + vertex 673.662 113.251 24.2611 + vertex 677.366 113.41 23.7131 + vertex 678.613 115.052 24.1989 + endloop + endfacet + facet normal 0.146753 -0.381372 0.912699 + outer loop + vertex 677.366 113.41 23.7131 + vertex 682.595 115.379 23.6954 + vertex 678.613 115.052 24.1989 + endloop + endfacet + facet normal 0.146938 -0.387932 0.9099 + outer loop + vertex 678.613 115.052 24.1989 + vertex 682.595 115.379 23.6954 + vertex 683.646 117.052 24.2389 + endloop + endfacet + facet normal 0.148877 -0.388913 0.909166 + outer loop + vertex 682.595 115.379 23.6954 + vertex 687.715 117.386 23.7154 + vertex 683.646 117.052 24.2389 + endloop + endfacet + facet normal 0.1488 -0.386008 0.910415 + outer loop + vertex 683.646 117.052 24.2389 + vertex 687.715 117.386 23.7154 + vertex 689.035 119.072 24.2143 + endloop + endfacet + facet normal 0.144775 -0.383377 0.912175 + outer loop + vertex 687.715 117.386 23.7154 + vertex 692.88 119.321 23.709 + vertex 689.035 119.072 24.2143 + endloop + endfacet + facet normal 0.144679 -0.374036 0.916059 + outer loop + vertex 689.035 119.072 24.2143 + vertex 692.88 119.321 23.709 + vertex 694.337 121.12 24.2133 + endloop + endfacet + facet normal 0.141301 -0.371714 0.917531 + outer loop + vertex 692.88 119.321 23.709 + vertex 698.112 121.274 23.6943 + vertex 694.337 121.12 24.2133 + endloop + endfacet + facet normal 0.141338 -0.369164 0.918554 + outer loop + vertex 694.337 121.12 24.2133 + vertex 698.112 121.274 23.6943 + vertex 699.393 123.111 24.2355 + endloop + endfacet + facet normal 0.145433 -0.371546 0.916953 + outer loop + vertex 698.112 121.274 23.6943 + vertex 703.314 123.305 23.6924 + vertex 699.393 123.111 24.2355 + endloop + endfacet + facet normal 0.145451 -0.368643 0.918121 + outer loop + vertex 699.393 123.111 24.2355 + vertex 703.314 123.305 23.6924 + vertex 704.354 125.201 24.2889 + endloop + endfacet + facet normal 0.151696 -0.371402 0.915996 + outer loop + vertex 703.314 123.305 23.6924 + vertex 708.477 125.439 23.7024 + vertex 704.354 125.201 24.2889 + endloop + endfacet + facet normal 0.151693 -0.365631 0.918315 + outer loop + vertex 704.354 125.201 24.2889 + vertex 708.477 125.439 23.7024 + vertex 709.437 127.307 24.2875 + endloop + endfacet + facet normal 0.151725 -0.365644 0.918305 + outer loop + vertex 708.477 125.439 23.7024 + vertex 713.614 127.619 23.7215 + vertex 709.437 127.307 24.2875 + endloop + endfacet + facet normal 0.151853 -0.372107 0.915684 + outer loop + vertex 709.437 127.307 24.2875 + vertex 713.614 127.619 23.7215 + vertex 714.531 129.5 24.3338 + endloop + endfacet + facet normal 0.158195 -0.374527 0.913621 + outer loop + vertex 713.614 127.619 23.7215 + vertex 718.742 129.844 23.7461 + vertex 714.531 129.5 24.3338 + endloop + endfacet + facet normal 0.158139 -0.372209 0.914578 + outer loop + vertex 714.531 129.5 24.3338 + vertex 718.742 129.844 23.7461 + vertex 719.817 131.78 24.348 + endloop + endfacet + facet normal 0.163986 -0.374804 0.912486 + outer loop + vertex 718.742 129.844 23.7461 + vertex 723.913 132.129 23.7553 + vertex 719.817 131.78 24.348 + endloop + endfacet + facet normal 0.163576 -0.359374 0.918745 + outer loop + vertex 719.817 131.78 24.348 + vertex 723.913 132.129 23.7553 + vertex 724.955 133.985 24.2955 + endloop + endfacet + facet normal 0.161482 -0.358415 0.91949 + outer loop + vertex 723.913 132.129 23.7553 + vertex 729.109 134.464 23.753 + vertex 724.955 133.985 24.2955 + endloop + endfacet + facet normal 0.16137 -0.356643 0.920199 + outer loop + vertex 724.955 133.985 24.2955 + vertex 729.109 134.464 23.753 + vertex 729.845 136.185 24.2905 + endloop + endfacet + facet normal 0.165196 -0.357914 0.919025 + outer loop + vertex 729.109 134.464 23.753 + vertex 734.358 136.889 23.7537 + vertex 729.845 136.185 24.2905 + endloop + endfacet + facet normal 0.168335 -0.38776 0.906259 + outer loop + vertex 729.845 136.185 24.2905 + vertex 734.358 136.889 23.7537 + vertex 734.914 138.662 24.4089 + endloop + endfacet + facet normal 0.185992 -0.391434 0.901214 + outer loop + vertex 734.358 136.889 23.7537 + vertex 739.699 139.401 23.7423 + vertex 734.914 138.662 24.4089 + endloop + endfacet + facet normal 0.187255 -0.405463 0.894726 + outer loop + vertex 734.914 138.662 24.4089 + vertex 739.699 139.401 23.7423 + vertex 740.409 141.325 24.4657 + endloop + endfacet + facet normal 0.202656 -0.409233 0.889639 + outer loop + vertex 739.699 139.401 23.7423 + vertex 744.997 141.934 23.7008 + vertex 740.409 141.325 24.4657 + endloop + endfacet + facet normal 0.202897 -0.413726 0.887504 + outer loop + vertex 740.409 141.325 24.4657 + vertex 744.997 141.934 23.7008 + vertex 745.876 143.972 24.4501 + endloop + endfacet + facet normal 0.212465 -0.416541 0.883941 + outer loop + vertex 744.997 141.934 23.7008 + vertex 750.124 144.454 23.656 + vertex 745.876 143.972 24.4501 + endloop + endfacet + facet normal 0.212571 -0.421032 0.881786 + outer loop + vertex 745.876 143.972 24.4501 + vertex 750.124 144.454 23.656 + vertex 751.131 146.637 24.4553 + endloop + endfacet + facet normal 0.223033 -0.424332 0.877609 + outer loop + vertex 750.124 144.454 23.656 + vertex 755.114 146.996 23.6171 + vertex 751.131 146.637 24.4553 + endloop + endfacet + facet normal 0.223103 -0.417307 0.880954 + outer loop + vertex 751.131 146.637 24.4553 + vertex 755.114 146.996 23.6171 + vertex 756.228 149.227 24.3917 + endloop + endfacet + facet normal 0.228265 -0.419126 0.878765 + outer loop + vertex 755.114 146.996 23.6171 + vertex 760.061 149.614 23.5805 + vertex 756.228 149.227 24.3917 + endloop + endfacet + facet normal 0.228264 -0.416074 0.880215 + outer loop + vertex 756.228 149.227 24.3917 + vertex 760.061 149.614 23.5805 + vertex 761.213 151.899 24.362 + endloop + endfacet + facet normal 0.234035 -0.418131 0.877721 + outer loop + vertex 760.061 149.614 23.5805 + vertex 765.098 152.366 23.5485 + vertex 761.213 151.899 24.362 + endloop + endfacet + facet normal 0.233927 -0.412696 0.880319 + outer loop + vertex 761.213 151.899 24.362 + vertex 765.098 152.366 23.5485 + vertex 766.488 154.789 24.315 + endloop + endfacet + facet normal 0.243136 -0.416605 0.875971 + outer loop + vertex 765.098 152.366 23.5485 + vertex 770.068 155.114 23.476 + vertex 766.488 154.789 24.315 + endloop + endfacet + facet normal 0.243493 -0.394549 0.886026 + outer loop + vertex 766.488 154.789 24.315 + vertex 770.068 155.114 23.476 + vertex 771.005 157.043 24.0774 + endloop + endfacet + facet normal 0.240033 -0.393331 0.88751 + outer loop + vertex 770.068 155.114 23.476 + vertex 774.775 157.822 23.4031 + vertex 771.005 157.043 24.0774 + endloop + endfacet + facet normal 0.241629 -0.406643 0.881054 + outer loop + vertex 771.005 157.043 24.0774 + vertex 774.775 157.822 23.4031 + vertex 774.842 159.498 24.1581 + endloop + endfacet + facet normal 0.25692 -0.405533 0.877232 + outer loop + vertex 774.775 157.822 23.4031 + vertex 779.422 160.628 23.3392 + vertex 774.842 159.498 24.1581 + endloop + endfacet + facet normal 0.257319 -0.408096 0.875925 + outer loop + vertex 774.842 159.498 24.1581 + vertex 779.422 160.628 23.3392 + vertex 779.519 162.333 24.1052 + endloop + endfacet + facet normal 0.271226 -0.407183 0.872146 + outer loop + vertex 779.422 160.628 23.3392 + vertex 784.121 163.533 23.234 + vertex 779.519 162.333 24.1052 + endloop + endfacet + facet normal 0.272123 -0.412723 0.869258 + outer loop + vertex 779.519 162.333 24.1052 + vertex 784.121 163.533 23.234 + vertex 784.217 165.219 24.0047 + endloop + endfacet + facet normal 0.28492 -0.41178 0.865597 + outer loop + vertex 784.121 163.533 23.234 + vertex 788.9 166.555 23.0987 + vertex 784.217 165.219 24.0047 + endloop + endfacet + facet normal 0.285864 -0.417001 0.862781 + outer loop + vertex 784.217 165.219 24.0047 + vertex 788.9 166.555 23.0987 + vertex 788.892 168.231 23.9115 + endloop + endfacet + facet normal 0.299913 -0.415072 0.858934 + outer loop + vertex 788.9 166.555 23.0987 + vertex 793.653 169.753 22.9846 + vertex 788.892 168.231 23.9115 + endloop + endfacet + facet normal 0.301947 -0.42477 0.853462 + outer loop + vertex 788.892 168.231 23.9115 + vertex 793.653 169.753 22.9846 + vertex 793.714 171.506 23.8353 + endloop + endfacet + facet normal 0.314205 -0.423385 0.849718 + outer loop + vertex 793.653 169.753 22.9846 + vertex 798.343 172.985 22.8605 + vertex 793.714 171.506 23.8353 + endloop + endfacet + facet normal 0.312637 -0.415553 0.854151 + outer loop + vertex 793.714 171.506 23.8353 + vertex 798.343 172.985 22.8605 + vertex 798.673 174.846 23.6455 + endloop + endfacet + facet normal 0.320098 -0.415681 0.85132 + outer loop + vertex 798.343 172.985 22.8605 + vertex 802.934 176.192 22.7003 + vertex 798.673 174.846 23.6455 + endloop + endfacet + facet normal 0.315931 -0.394297 0.86297 + outer loop + vertex 798.673 174.846 23.6455 + vertex 802.934 176.192 22.7003 + vertex 803.294 177.954 23.3737 + endloop + endfacet + facet normal 0.316279 -0.394316 0.862834 + outer loop + vertex 802.934 176.192 22.7003 + vertex 807.387 179.403 22.5354 + vertex 803.294 177.954 23.3737 + endloop + endfacet + facet normal 0.312697 -0.379657 0.870678 + outer loop + vertex 803.294 177.954 23.3737 + vertex 807.387 179.403 22.5354 + vertex 807.559 181.006 23.1726 + endloop + endfacet + facet normal 0.313712 -0.379626 0.870327 + outer loop + vertex 807.387 179.403 22.5354 + vertex 811.765 182.694 22.3931 + vertex 807.559 181.006 23.1726 + endloop + endfacet + facet normal 0.313106 -0.377611 0.871421 + outer loop + vertex 807.559 181.006 23.1726 + vertex 811.765 182.694 22.3931 + vertex 811.839 184.28 23.0539 + endloop + endfacet + facet normal 0.321414 -0.376868 0.868714 + outer loop + vertex 811.765 182.694 22.3931 + vertex 816.072 186.057 22.2586 + vertex 811.839 184.28 23.0539 + endloop + endfacet + facet normal 0.320867 -0.375141 0.869663 + outer loop + vertex 811.839 184.28 23.0539 + vertex 816.072 186.057 22.2586 + vertex 816.147 187.685 22.9328 + endloop + endfacet + facet normal 0.327882 -0.374497 0.867321 + outer loop + vertex 816.072 186.057 22.2586 + vertex 820.291 189.447 22.1271 + vertex 816.147 187.685 22.9328 + endloop + endfacet + facet normal 0.328423 -0.376202 0.866378 + outer loop + vertex 816.147 187.685 22.9328 + vertex 820.291 189.447 22.1271 + vertex 820.422 191.201 22.8391 + endloop + endfacet + facet normal 0.337982 -0.375536 0.862984 + outer loop + vertex 820.291 189.447 22.1271 + vertex 824.375 192.829 21.9996 + vertex 820.422 191.201 22.8391 + endloop + endfacet + facet normal 0.337054 -0.372395 0.864706 + outer loop + vertex 820.422 191.201 22.8391 + vertex 824.375 192.829 21.9996 + vertex 824.596 194.704 22.7208 + endloop + endfacet + facet normal 0.342755 -0.372232 0.862532 + outer loop + vertex 824.375 192.829 21.9996 + vertex 828.318 196.175 21.8767 + vertex 824.596 194.704 22.7208 + endloop + endfacet + facet normal 0.340943 -0.365613 0.866074 + outer loop + vertex 824.596 194.704 22.7208 + vertex 828.318 196.175 21.8767 + vertex 828.601 198.101 22.5785 + endloop + endfacet + facet normal 0.34333 -0.365619 0.865128 + outer loop + vertex 828.318 196.175 21.8767 + vertex 832.112 199.458 21.7581 + vertex 828.601 198.101 22.5785 + endloop + endfacet + facet normal 0.340977 -0.356727 0.869759 + outer loop + vertex 828.601 198.101 22.5785 + vertex 832.112 199.458 21.7581 + vertex 832.424 201.404 22.4343 + endloop + endfacet + facet normal 0.34119 -0.356732 0.869674 + outer loop + vertex 832.112 199.458 21.7581 + vertex 835.742 202.634 21.6367 + vertex 832.424 201.404 22.4343 + endloop + endfacet + facet normal 0.338134 -0.344536 0.875763 + outer loop + vertex 832.424 201.404 22.4343 + vertex 835.742 202.634 21.6367 + vertex 835.764 204.134 22.2183 + endloop + endfacet + facet normal 0.332659 -0.345171 0.877607 + outer loop + vertex 835.742 202.634 21.6367 + vertex 839.274 205.834 21.5566 + vertex 835.764 204.134 22.2183 + endloop + endfacet + facet normal 0.33983 -0.364035 0.867176 + outer loop + vertex 835.764 204.134 22.2183 + vertex 839.274 205.834 21.5566 + vertex 838.706 207.146 22.3301 + endloop + endfacet + facet normal 0.348545 -0.359371 0.865661 + outer loop + vertex 839.274 205.834 21.5566 + vertex 843.032 209.349 21.5027 + vertex 838.706 207.146 22.3301 + endloop + endfacet + facet normal 0.347548 -0.356875 0.867093 + outer loop + vertex 838.706 207.146 22.3301 + vertex 843.032 209.349 21.5027 + vertex 842.801 210.995 22.2729 + endloop + endfacet + facet normal 0.352001 -0.355644 0.865802 + outer loop + vertex 843.032 209.349 21.5027 + vertex 847.047 213.107 21.414 + vertex 842.801 210.995 22.2729 + endloop + endfacet + facet normal 0.346758 -0.342024 0.873372 + outer loop + vertex 842.801 210.995 22.2729 + vertex 847.047 213.107 21.414 + vertex 847.04 214.863 22.1048 + endloop + endfacet + facet normal 0.349325 -0.341667 0.872488 + outer loop + vertex 847.047 213.107 21.414 + vertex 850.758 216.684 21.329 + vertex 847.04 214.863 22.1048 + endloop + endfacet + facet normal 0.343784 -0.327038 0.880261 + outer loop + vertex 847.04 214.863 22.1048 + vertex 850.758 216.684 21.329 + vertex 850.628 218.19 21.9394 + endloop + endfacet + facet normal 0.339174 -0.328012 0.881685 + outer loop + vertex 850.758 216.684 21.329 + vertex 853.653 219.751 21.3563 + vertex 850.628 218.19 21.9394 + endloop + endfacet + facet normal 0.34804 -0.349621 0.869847 + outer loop + vertex 850.628 218.19 21.9394 + vertex 853.653 219.751 21.3563 + vertex 853.063 220.924 22.0639 + endloop + endfacet + facet normal 0.344768 -0.351579 0.870361 + outer loop + vertex 853.063 220.924 22.0639 + vertex 853.653 219.751 21.3563 + vertex 855.566 222.339 21.6441 + endloop + endfacet + facet normal 0.383078 -0.435938 0.814377 + outer loop + vertex 855.566 222.339 21.6441 + vertex 854.308 224.139 23.1992 + vertex 853.063 220.924 22.0639 + endloop + endfacet + facet normal 0.423226 -0.404653 0.810639 + outer loop + vertex 854.308 224.139 23.1992 + vertex 855.566 222.339 21.6441 + vertex 856.871 224.351 21.9673 + endloop + endfacet + facet normal 0.316306 -0.774823 0.547357 + outer loop + vertex 611.49 93.2718 30.0952 + vertex 614.027 94.1136 29.8207 + vertex 613.275 94.8829 31.3445 + endloop + endfacet + facet normal 0.295759 -0.784344 0.545282 + outer loop + vertex 609.585 93.0617 30.8265 + vertex 611.49 93.2718 30.0952 + vertex 610.687 94.2523 31.941 + endloop + endfacet + facet normal 0.30017 -0.785118 0.541745 + outer loop + vertex 609.866 94.1299 32.2185 + vertex 609.585 93.0617 30.8265 + vertex 610.687 94.2523 31.941 + endloop + endfacet + facet normal 0.39562 -0.765524 0.507403 + outer loop + vertex 609.595 94.1702 32.491 + vertex 609.585 93.0617 30.8265 + vertex 609.866 94.1299 32.2185 + endloop + endfacet + facet normal 0.336482 -0.823336 0.457053 + outer loop + vertex 609.866 94.1299 32.2185 + vertex 610.651 94.9691 33.1526 + vertex 609.595 94.1702 32.491 + endloop + endfacet + facet normal 0.332403 -0.785925 0.521374 + outer loop + vertex 608.448 92.1982 30.2492 + vertex 609.585 93.0617 30.8265 + vertex 609.595 94.1702 32.491 + endloop + endfacet + facet normal 0.230813 -0.78606 0.573442 + outer loop + vertex 609.08 93.8024 32.1941 + vertex 608.448 92.1982 30.2492 + vertex 609.595 94.1702 32.491 + endloop + endfacet + facet normal 0.218541 -0.786428 0.57773 + outer loop + vertex 608.05 92.1642 30.3539 + vertex 608.448 92.1982 30.2492 + vertex 609.08 93.8024 32.1941 + endloop + endfacet + facet normal -0.464246 0.774549 -0.429591 + outer loop + vertex 608.91 93.493 31.8195 + vertex 608.05 92.1642 30.3539 + vertex 609.08 93.8024 32.1941 + endloop + endfacet + facet normal 0.011362 0.73747 -0.675284 + outer loop + vertex 607.739 91.5975 29.7297 + vertex 608.05 92.1642 30.3539 + vertex 608.91 93.493 31.8195 + endloop + endfacet + facet normal 0.353699 -0.78289 0.511841 + outer loop + vertex 607.739 91.5975 29.7297 + vertex 608.91 93.493 31.8195 + vertex 608.22 92.6045 30.9375 + endloop + endfacet + facet normal 0.289186 -0.820059 0.493836 + outer loop + vertex 609.866 94.1299 32.2185 + vertex 610.687 94.2523 31.941 + vertex 610.651 94.9691 33.1526 + endloop + endfacet + facet normal 0.315826 -0.816048 0.484065 + outer loop + vertex 611.853 95.3766 33.0903 + vertex 611.983 94.7119 31.8849 + vertex 613.229 95.7124 32.7584 + endloop + endfacet + facet normal 0.318941 -0.831727 0.45443 + outer loop + vertex 614.495 96.8713 33.9816 + vertex 612.476 96.3467 34.4384 + vertex 613.074 96.2449 33.8325 + endloop + endfacet + facet normal 0.322203 -0.828769 0.457523 + outer loop + vertex 613.229 95.7124 32.7584 + vertex 614.667 96.0499 32.3577 + vertex 614.348 96.4812 33.3635 + endloop + endfacet + facet normal 0.327281 -0.810037 0.486546 + outer loop + vertex 614.667 96.0499 32.3577 + vertex 614.805 95.4132 31.2044 + vertex 616.119 96.3889 31.945 + endloop + endfacet + facet normal 0.329637 -0.82955 0.450762 + outer loop + vertex 616.995 97.4103 33.1458 + vertex 614.495 96.8713 33.9816 + vertex 615.752 96.8532 33.029 + endloop + endfacet + facet normal 0.321294 -0.816774 0.479219 + outer loop + vertex 616.119 96.3889 31.945 + vertex 617.674 96.7411 31.5029 + vertex 617.172 97.1273 32.4974 + endloop + endfacet + facet normal 0.330407 -0.80116 0.498973 + outer loop + vertex 618.657 97.5441 32.1852 + vertex 619.49 97.2348 31.1371 + vertex 620.034 97.8382 31.7458 + endloop + endfacet + facet normal 0.323767 -0.825882 0.461621 + outer loop + vertex 620.034 97.8382 31.7458 + vertex 619.754 97.9672 32.1727 + vertex 618.657 97.5441 32.1852 + endloop + endfacet + facet normal 0.282342 -0.851326 0.442184 + outer loop + vertex 620.034 97.8382 31.7458 + vertex 621.611 97.9 30.8574 + vertex 619.754 97.9672 32.1727 + endloop + endfacet + facet normal 0.30878 -0.790937 0.528274 + outer loop + vertex 616.079 95.4878 30.5587 + vertex 618.027 95.9351 30.0896 + vertex 617.674 96.7411 31.5029 + endloop + endfacet + facet normal 0.317916 -0.799948 0.508932 + outer loop + vertex 620.034 97.8382 31.7458 + vertex 619.49 97.2348 31.1371 + vertex 621.611 97.9 30.8574 + endloop + endfacet + facet normal 0.329845 -0.79668 0.506462 + outer loop + vertex 619.754 97.9672 32.1727 + vertex 621.611 97.9 30.8574 + vertex 622.841 98.5774 31.1219 + endloop + endfacet + facet normal 0.326081 -0.832271 0.448325 + outer loop + vertex 619.754 97.9672 32.1727 + vertex 616.995 97.4103 33.1458 + vertex 618.657 97.5441 32.1852 + endloop + endfacet + facet normal 0.325445 -0.842043 0.430172 + outer loop + vertex 614.495 96.8713 33.9816 + vertex 616.995 97.4103 33.1458 + vertex 615.377 97.2064 33.9708 + endloop + endfacet + facet normal 0.324375 -0.839013 0.43685 + outer loop + vertex 613.292 96.7549 34.6517 + vertex 614.495 96.8713 33.9816 + vertex 615.377 97.2064 33.9708 + endloop + endfacet + facet normal 0.320408 -0.863849 0.388722 + outer loop + vertex 611.361 96.0112 34.5905 + vertex 613.292 96.7549 34.6517 + vertex 611.235 96.4954 35.7707 + endloop + endfacet + facet normal 0.331483 -0.850542 0.408285 + outer loop + vertex 617.161 98.316 34.8741 + vertex 619.615 99.7668 35.904 + vertex 615.963 98.2231 35.6537 + endloop + endfacet + facet normal 0.335327 -0.846865 0.412767 + outer loop + vertex 618.441 98.3429 33.8899 + vertex 620.724 99.7612 34.9446 + vertex 617.161 98.316 34.8741 + endloop + endfacet + facet normal 0.323132 -0.851708 0.412528 + outer loop + vertex 618.469 97.9065 33.0055 + vertex 615.469 97.4219 34.3544 + vertex 617.499 97.622 33.1782 + endloop + endfacet + facet normal 0.332948 -0.837346 0.433586 + outer loop + vertex 620.91 98.7687 32.8163 + vertex 622.701 100.047 33.9094 + vertex 618.441 98.3429 33.8899 + endloop + endfacet + facet normal 0.325326 -0.837581 0.438887 + outer loop + vertex 621.223 98.4356 31.9734 + vertex 618.469 97.9065 33.0055 + vertex 620.3 98.1564 32.1252 + endloop + endfacet + facet normal 0.330478 -0.8262 0.456265 + outer loop + vertex 623.589 99.3064 31.8489 + vertex 625.295 100.556 32.877 + vertex 620.91 98.7687 32.8163 + endloop + endfacet + facet normal 0.327821 -0.812351 0.482307 + outer loop + vertex 623.601 98.948 31.2204 + vertex 621.223 98.4356 31.9734 + vertex 623.281 98.7764 31.1485 + endloop + endfacet + facet normal 0.327976 -0.813357 0.480501 + outer loop + vertex 626.353 99.8863 30.9441 + vertex 628.341 101.209 31.8262 + vertex 623.589 99.3064 31.8489 + endloop + endfacet + facet normal 0.323843 -0.808643 0.491143 + outer loop + vertex 626.132 99.5005 30.4612 + vertex 623.601 98.948 31.2204 + vertex 623.281 98.7764 31.1485 + endloop + endfacet + facet normal 0.326275 -0.786077 0.525003 + outer loop + vertex 623.281 98.7764 31.1485 + vertex 627.1 99.5452 29.9263 + vertex 626.132 99.5005 30.4612 + endloop + endfacet + facet normal 0.326342 -0.80006 0.503394 + outer loop + vertex 629.116 100.498 30.1254 + vertex 631.459 101.797 30.67 + vertex 626.353 99.8863 30.9441 + endloop + endfacet + facet normal 0.324122 -0.789757 0.520796 + outer loop + vertex 630.012 100.499 29.5606 + vertex 626.132 99.5005 30.4612 + vertex 627.1 99.5452 29.9263 + endloop + endfacet + facet normal 0.325309 -0.799108 0.50557 + outer loop + vertex 629.116 100.498 30.1254 + vertex 634.731 102.283 29.3334 + vertex 631.459 101.797 30.67 + endloop + endfacet + facet normal 0.328324 -0.791306 0.515789 + outer loop + vertex 634.731 102.283 29.3334 + vertex 639.065 104.828 30.4797 + vertex 631.459 101.797 30.67 + endloop + endfacet + facet normal 0.329904 -0.792625 0.512747 + outer loop + vertex 634.731 102.283 29.3334 + vertex 643.324 105.76 29.1797 + vertex 639.065 104.828 30.4797 + endloop + endfacet + facet normal 0.331091 -0.786897 0.520741 + outer loop + vertex 643.324 105.76 29.1797 + vertex 647.679 108.439 30.4591 + vertex 639.065 104.828 30.4797 + endloop + endfacet + facet normal 0.333196 -0.788508 0.516949 + outer loop + vertex 643.324 105.76 29.1797 + vertex 651.555 109.36 29.366 + vertex 647.679 108.439 30.4591 + endloop + endfacet + facet normal 0.318504 -0.771898 0.550207 + outer loop + vertex 635.891 102.079 28.3493 + vertex 632.879 101.266 28.9522 + vertex 632.627 100.955 28.6616 + endloop + endfacet + facet normal 0.333593 -0.786041 0.520437 + outer loop + vertex 651.555 109.36 29.366 + vertex 655.221 111.707 30.5612 + vertex 647.679 108.439 30.4591 + endloop + endfacet + facet normal 0.341474 -0.801771 0.490468 + outer loop + vertex 655.221 111.707 30.5612 + vertex 660.511 114.088 30.7699 + vertex 658.289 113.552 31.4408 + endloop + endfacet + facet normal 0.335208 -0.796658 0.502962 + outer loop + vertex 660.511 114.088 30.7699 + vertex 662.565 114.618 30.2404 + vertex 663.516 115.479 30.97 + endloop + endfacet + facet normal 0.32959 -0.788083 0.519899 + outer loop + vertex 662.565 114.618 30.2404 + vertex 663.875 114.916 29.8612 + vertex 664.715 115.663 30.4617 + endloop + endfacet + facet normal 0.327386 -0.774592 0.541133 + outer loop + vertex 661.613 113.368 29.0142 + vertex 664.611 115.028 29.5759 + vertex 663.875 114.916 29.8612 + endloop + endfacet + facet normal 0.329251 -0.771052 0.545043 + outer loop + vertex 660.995 113.452 29.4943 + vertex 658.255 112.505 29.8093 + vertex 656.309 110.841 28.6312 + endloop + endfacet + facet normal 0.31577 -0.740473 0.593286 + outer loop + vertex 658.806 110.697 27.1043 + vertex 661.212 112.489 28.0597 + vertex 658.745 111.283 27.8673 + endloop + endfacet + facet normal 0.323437 -0.770309 0.549557 + outer loop + vertex 662.41 113.492 28.7187 + vertex 664.611 115.028 29.5759 + vertex 661.613 113.368 29.0142 + endloop + endfacet + facet normal 0.332959 -0.788099 0.517723 + outer loop + vertex 665.814 115.704 29.8326 + vertex 666.106 115.997 30.0897 + vertex 664.611 115.028 29.5759 + endloop + endfacet + facet normal 0.320547 -0.785686 0.529101 + outer loop + vertex 665.814 115.704 29.8326 + vertex 666.41 116.162 30.1516 + vertex 666.106 115.997 30.0897 + endloop + endfacet + facet normal 0.330242 -0.79557 0.507945 + outer loop + vertex 666.106 115.997 30.0897 + vertex 666.41 116.162 30.1516 + vertex 666.109 116.224 30.4434 + endloop + endfacet + facet normal 0.303839 -0.854113 0.422105 + outer loop + vertex 665.144 116.083 30.8541 + vertex 666.109 116.224 30.4434 + vertex 664.875 116.122 31.1266 + endloop + endfacet + facet normal 0.329163 -0.81507 0.476773 + outer loop + vertex 667.222 116.945 30.9202 + vertex 666.81 116.485 30.419 + vertex 668.974 117.317 30.3469 + endloop + endfacet + facet normal 0.330764 -0.799361 0.501615 + outer loop + vertex 671.693 118.514 30.4617 + vertex 668.974 117.317 30.3469 + vertex 672.1 118.471 30.1245 + endloop + endfacet + facet normal 0.313805 -0.763429 0.564537 + outer loop + vertex 680.8 121.921 29.9249 + vertex 672.859 118.647 29.9125 + vertex 677.505 120.337 29.6152 + endloop + endfacet + facet normal 0.317372 -0.776882 0.54381 + outer loop + vertex 673.097 118.509 29.5757 + vertex 677.505 120.337 29.6152 + vertex 672.859 118.647 29.9125 + endloop + endfacet + facet normal 0.316643 -0.777392 0.543506 + outer loop + vertex 673.097 118.509 29.5757 + vertex 672.859 118.647 29.9125 + vertex 669.705 117.221 29.7101 + endloop + endfacet + facet normal 0.313144 -0.766358 0.560924 + outer loop + vertex 673.097 118.509 29.5757 + vertex 669.705 117.221 29.7101 + vertex 671.575 117.6 29.1828 + endloop + endfacet + facet normal 0.311849 -0.774329 0.550604 + outer loop + vertex 671.575 117.6 29.1828 + vertex 669.705 117.221 29.7101 + vertex 668.069 116.263 29.2888 + endloop + endfacet + facet normal 0.317108 -0.779031 0.540881 + outer loop + vertex 669.705 117.221 29.7101 + vertex 667.151 116.214 29.7562 + vertex 668.069 116.263 29.2888 + endloop + endfacet + facet normal 0.321608 -0.791399 0.519861 + outer loop + vertex 667.151 116.214 29.7562 + vertex 669.705 117.221 29.7101 + vertex 668.484 116.911 29.9935 + endloop + endfacet + facet normal 0.308091 -0.755256 0.578506 + outer loop + vertex 677.505 120.337 29.6152 + vertex 673.097 118.509 29.5757 + vertex 676.524 119.543 29.1006 + endloop + endfacet + facet normal 0.326809 -0.791947 0.515768 + outer loop + vertex 671.964 118.342 30.0126 + vertex 675.448 119.789 30.0264 + vertex 672.1 118.471 30.1245 + endloop + endfacet + facet normal 0.323563 -0.791229 0.518905 + outer loop + vertex 669.642 117.413 30.0447 + vertex 671.964 118.342 30.0126 + vertex 672.1 118.471 30.1245 + endloop + endfacet + facet normal 0.321995 -0.786819 0.526531 + outer loop + vertex 669.705 117.221 29.7101 + vertex 672.859 118.647 29.9125 + vertex 668.484 116.911 29.9935 + endloop + endfacet + facet normal 0.327613 -0.800944 0.501156 + outer loop + vertex 666.552 116.196 30.1199 + vertex 669.642 117.413 30.0447 + vertex 668.201 116.875 30.1262 + endloop + endfacet + facet normal 0.324227 -0.794321 0.513742 + outer loop + vertex 668.484 116.911 29.9935 + vertex 666.871 116.245 29.9815 + vertex 667.151 116.214 29.7562 + endloop + endfacet + facet normal 0.315632 -0.781837 0.537687 + outer loop + vertex 668.069 116.263 29.2888 + vertex 667.151 116.214 29.7562 + vertex 665.659 115.245 29.2234 + endloop + endfacet + facet normal 0.307118 -0.763621 0.567945 + outer loop + vertex 668.069 116.263 29.2888 + vertex 665.659 115.245 29.2234 + vertex 667.134 115.445 28.6943 + endloop + endfacet + facet normal 0.303356 -0.776209 0.552697 + outer loop + vertex 667.134 115.445 28.6943 + vertex 665.659 115.245 29.2234 + vertex 665.135 114.729 28.7862 + endloop + endfacet + facet normal 0.39365 -0.812424 0.430125 + outer loop + vertex 666.552 116.196 30.1199 + vertex 664.073 114.405 29.0056 + vertex 665.937 115.68 29.7079 + endloop + endfacet + facet normal 0.333138 -0.783079 0.525172 + outer loop + vertex 665.135 114.729 28.7862 + vertex 665.659 115.245 29.2234 + vertex 664.291 114.321 28.7129 + endloop + endfacet + facet normal 0.304176 -0.737221 0.603309 + outer loop + vertex 665.135 114.729 28.7862 + vertex 664.291 114.321 28.7129 + vertex 665.474 114.397 28.2101 + endloop + endfacet + facet normal 0.293831 -0.74343 0.600813 + outer loop + vertex 667.134 115.445 28.6943 + vertex 665.135 114.729 28.7862 + vertex 665.474 114.397 28.2101 + endloop + endfacet + facet normal 0.303962 -0.762417 0.571251 + outer loop + vertex 670.188 116.647 28.6743 + vertex 668.069 116.263 29.2888 + vertex 667.134 115.445 28.6943 + endloop + endfacet + facet normal 0.305294 -0.754756 0.580637 + outer loop + vertex 671.575 117.6 29.1828 + vertex 668.069 116.263 29.2888 + vertex 670.188 116.647 28.6743 + endloop + endfacet + facet normal 0.308889 -0.762504 0.568485 + outer loop + vertex 676.524 119.543 29.1006 + vertex 673.097 118.509 29.5757 + vertex 671.575 117.6 29.1828 + endloop + endfacet + facet normal 0.306808 -0.754636 0.579994 + outer loop + vertex 682.193 121.913 29.1856 + vertex 677.505 120.337 29.6152 + vertex 676.524 119.543 29.1006 + endloop + endfacet + facet normal 0.288952 -0.720424 0.630473 + outer loop + vertex 692.505 125.855 28.9108 + vertex 687.935 123.793 28.6486 + vertex 692.46 125.22 28.2047 + endloop + endfacet + facet normal 0.289048 -0.720918 0.629864 + outer loop + vertex 692.46 125.22 28.2047 + vertex 687.935 123.793 28.6486 + vertex 688.431 123.243 27.7911 + endloop + endfacet + facet normal 0.282124 -0.701949 0.653967 + outer loop + vertex 689.712 123.089 27.0733 + vertex 688.431 123.243 27.7911 + vertex 682.436 120.464 27.3952 + endloop + endfacet + facet normal 0.27547 -0.682807 0.676676 + outer loop + vertex 682.436 120.464 27.3952 + vertex 671.673 116.368 27.6435 + vertex 681.214 118.914 26.3279 + endloop + endfacet + facet normal 0.257361 -0.655707 0.709798 + outer loop + vertex 693.24 123.5 26.1476 + vertex 688.554 122.064 26.5199 + vertex 688.954 121.64 25.9834 + endloop + endfacet + facet normal 0.254379 -0.642506 0.722825 + outer loop + vertex 681.214 118.914 26.3279 + vertex 670.681 114.708 26.2964 + vertex 679.014 116.793 25.217 + endloop + endfacet + facet normal 0.256956 -0.663 0.703139 + outer loop + vertex 679.014 116.793 25.217 + vertex 670.681 114.708 26.2964 + vertex 667.973 112.716 25.4079 + endloop + endfacet + facet normal 0.263223 -0.668252 0.695811 + outer loop + vertex 667.973 112.716 25.4079 + vertex 670.681 114.708 26.2964 + vertex 662.637 111.358 26.122 + endloop + endfacet + facet normal 0.246474 -0.624573 0.741053 + outer loop + vertex 691.994 122.484 25.6833 + vertex 688.954 121.64 25.9834 + vertex 687.172 120.456 25.5779 + endloop + endfacet + facet normal 0.248995 -0.638088 0.728591 + outer loop + vertex 693.24 123.5 26.1476 + vertex 688.954 121.64 25.9834 + vertex 691.994 122.484 25.6833 + endloop + endfacet + facet normal 0.245009 -0.65869 0.711405 + outer loop + vertex 693.063 124.04 26.7083 + vertex 693.24 123.5 26.1476 + vertex 697.013 125.711 26.8957 + endloop + endfacet + facet normal 0.272586 -0.654627 0.705096 + outer loop + vertex 716.117 132.785 26.324 + vertex 714.047 132.812 27.1497 + vertex 712.232 130.794 25.9775 + endloop + endfacet + facet normal 0.276803 -0.641729 0.715237 + outer loop + vertex 716.117 132.785 26.324 + vertex 718.832 135.426 27.6422 + vertex 714.047 132.812 27.1497 + endloop + endfacet + facet normal 0.278587 -0.642756 0.71362 + outer loop + vertex 720.739 134.643 26.1926 + vertex 718.832 135.426 27.6422 + vertex 716.117 132.785 26.324 + endloop + endfacet + facet normal 0.285375 -0.634655 0.718174 + outer loop + vertex 720.739 134.643 26.1926 + vertex 725.714 138.593 27.7064 + vertex 718.832 135.426 27.6422 + endloop + endfacet + facet normal 0.272673 -0.60762 0.745954 + outer loop + vertex 725.714 138.593 27.7064 + vertex 723.713 140.133 29.6925 + vertex 718.832 135.426 27.6422 + endloop + endfacet + facet normal 0.275112 -0.609197 0.743769 + outer loop + vertex 723.713 140.133 29.6925 + vertex 714.445 135.377 29.2251 + vertex 718.832 135.426 27.6422 + endloop + endfacet + facet normal 0.283423 -0.598246 0.749516 + outer loop + vertex 725.714 138.593 27.7064 + vertex 731.948 144.007 29.6707 + vertex 723.713 140.133 29.6925 + endloop + endfacet + facet normal 0.280307 -0.595791 0.752636 + outer loop + vertex 733.591 142.064 27.5208 + vertex 731.948 144.007 29.6707 + vertex 725.714 138.593 27.7064 + endloop + endfacet + facet normal 0.292834 -0.625806 0.722921 + outer loop + vertex 725.714 138.593 27.7064 + vertex 727.494 137.314 25.8787 + vertex 733.591 142.064 27.5208 + endloop + endfacet + facet normal 0.281016 -0.615325 0.736482 + outer loop + vertex 727.494 137.314 25.8787 + vertex 735.65 140.688 25.5857 + vertex 733.591 142.064 27.5208 + endloop + endfacet + facet normal 0.292637 -0.604339 0.741039 + outer loop + vertex 742.376 145.813 27.1092 + vertex 733.591 142.064 27.5208 + vertex 735.65 140.688 25.5857 + endloop + endfacet + facet normal 0.282506 -0.59454 0.752803 + outer loop + vertex 735.65 140.688 25.5857 + vertex 742.109 143.458 25.3492 + vertex 742.376 145.813 27.1092 + endloop + endfacet + facet normal 0.292628 -0.593442 0.749797 + outer loop + vertex 742.109 143.458 25.3492 + vertex 747.389 146.392 25.6111 + vertex 742.376 145.813 27.1092 + endloop + endfacet + facet normal 0.293597 -0.584289 0.756576 + outer loop + vertex 750.968 150.349 27.2783 + vertex 742.376 145.813 27.1092 + vertex 747.389 146.392 25.6111 + endloop + endfacet + facet normal 0.302708 -0.589347 0.749025 + outer loop + vertex 747.389 146.392 25.6111 + vertex 753.459 149.472 25.5809 + vertex 750.968 150.349 27.2783 + endloop + endfacet + facet normal 0.309793 -0.579082 0.754117 + outer loop + vertex 758.952 154.274 27.0118 + vertex 750.968 150.349 27.2783 + vertex 753.459 149.472 25.5809 + endloop + endfacet + facet normal 0.309852 -0.579131 0.754055 + outer loop + vertex 753.459 149.472 25.5809 + vertex 758.228 151.64 25.2867 + vertex 758.952 154.274 27.0118 + endloop + endfacet + facet normal 0.320161 -0.579135 0.749733 + outer loop + vertex 758.228 151.64 25.2867 + vertex 763.293 154.717 25.5001 + vertex 758.952 154.274 27.0118 + endloop + endfacet + facet normal 0.321432 -0.570224 0.755994 + outer loop + vertex 767.354 159.183 27.1428 + vertex 758.952 154.274 27.0118 + vertex 763.293 154.717 25.5001 + endloop + endfacet + facet normal 0.330158 -0.575335 0.748322 + outer loop + vertex 763.293 154.717 25.5001 + vertex 770.23 158.363 25.2431 + vertex 767.354 159.183 27.1428 + endloop + endfacet + facet normal 0.338387 -0.56177 0.754923 + outer loop + vertex 775.729 163.697 26.7473 + vertex 767.354 159.183 27.1428 + vertex 770.23 158.363 25.2431 + endloop + endfacet + facet normal 0.337761 -0.561302 0.755551 + outer loop + vertex 770.23 158.363 25.2431 + vertex 775.732 161.402 25.0411 + vertex 775.729 163.697 26.7473 + endloop + endfacet + facet normal 0.348664 -0.558917 0.75236 + outer loop + vertex 775.732 161.402 25.0411 + vertex 780.372 164.481 25.1786 + vertex 775.729 163.697 26.7473 + endloop + endfacet + facet normal 0.349447 -0.547341 0.760464 + outer loop + vertex 784.388 168.997 26.5833 + vertex 775.729 163.697 26.7473 + vertex 780.372 164.481 25.1786 + endloop + endfacet + facet normal 0.358548 -0.552861 0.752189 + outer loop + vertex 780.372 164.481 25.1786 + vertex 785.063 167.125 24.8852 + vertex 784.388 168.997 26.5833 + endloop + endfacet + facet normal 0.370578 -0.547071 0.75059 + outer loop + vertex 785.063 167.125 24.8852 + vertex 789.454 170.364 25.0781 + vertex 784.388 168.997 26.5833 + endloop + endfacet + facet normal 0.370568 -0.546852 0.750754 + outer loop + vertex 791.798 174.144 26.6743 + vertex 784.388 168.997 26.5833 + vertex 789.454 170.364 25.0781 + endloop + endfacet + facet normal 0.390803 -0.55308 0.735782 + outer loop + vertex 789.454 170.364 25.0781 + vertex 795.128 174.217 24.9608 + vertex 791.798 174.144 26.6743 + endloop + endfacet + facet normal 0.39378 -0.542537 0.742018 + outer loop + vertex 798.696 178.807 26.4234 + vertex 791.798 174.144 26.6743 + vertex 795.128 174.217 24.9608 + endloop + endfacet + facet normal 0.405512 -0.548275 0.731406 + outer loop + vertex 795.128 174.217 24.9608 + vertex 800.483 177.605 24.5315 + vertex 798.696 178.807 26.4234 + endloop + endfacet + facet normal 0.415775 -0.537052 0.733966 + outer loop + vertex 800.483 177.605 24.5315 + vertex 804.566 181.823 25.305 + vertex 798.696 178.807 26.4234 + endloop + endfacet + facet normal 0.42195 -0.555561 0.716457 + outer loop + vertex 804.566 181.823 25.305 + vertex 803.505 183.217 27.0102 + vertex 798.696 178.807 26.4234 + endloop + endfacet + facet normal 0.416891 -0.550911 0.72298 + outer loop + vertex 798.696 178.807 26.4234 + vertex 803.505 183.217 27.0102 + vertex 801.088 183.192 28.3855 + endloop + endfacet + facet normal 0.406071 -0.548549 0.73089 + outer loop + vertex 795.696 179.291 28.4532 + vertex 798.696 178.807 26.4234 + vertex 801.088 183.192 28.3855 + endloop + endfacet + facet normal 0.420027 -0.540938 0.728672 + outer loop + vertex 805.523 186.681 28.4188 + vertex 801.088 183.192 28.3855 + vertex 803.505 183.217 27.0102 + endloop + endfacet + facet normal 0.430488 -0.543695 0.720469 + outer loop + vertex 803.505 183.217 27.0102 + vertex 808.082 186.558 26.7969 + vertex 805.523 186.681 28.4188 + endloop + endfacet + facet normal 0.431817 -0.540199 0.722301 + outer loop + vertex 805.523 186.681 28.4188 + vertex 808.082 186.558 26.7969 + vertex 809.259 189.899 28.5921 + endloop + endfacet + facet normal 0.436488 -0.540294 0.719416 + outer loop + vertex 809.259 189.899 28.5921 + vertex 808.082 186.558 26.7969 + vertex 811.95 190.85 27.6742 + endloop + endfacet + facet normal 0.435912 -0.533351 0.724926 + outer loop + vertex 812.043 192.673 28.9585 + vertex 809.259 189.899 28.5921 + vertex 811.95 190.85 27.6742 + endloop + endfacet + facet normal 0.44467 -0.531173 0.721196 + outer loop + vertex 811.95 190.85 27.6742 + vertex 814.71 194.538 28.688 + vertex 812.043 192.673 28.9585 + endloop + endfacet + facet normal 0.428125 -0.503251 0.750632 + outer loop + vertex 814.71 194.538 28.688 + vertex 813.896 195.785 29.9889 + vertex 812.043 192.673 28.9585 + endloop + endfacet + facet normal 0.410541 -0.497308 0.764291 + outer loop + vertex 812.043 192.673 28.9585 + vertex 813.896 195.785 29.9889 + vertex 810.8 193.207 29.9741 + endloop + endfacet + facet normal 0.380914 -0.461951 0.800941 + outer loop + vertex 813.896 195.785 29.9889 + vertex 813.002 197.275 31.2733 + vertex 810.8 193.207 29.9741 + endloop + endfacet + facet normal 0.382666 -0.462526 0.799773 + outer loop + vertex 810.8 193.207 29.9741 + vertex 813.002 197.275 31.2733 + vertex 809.596 194.075 31.0521 + endloop + endfacet + facet normal 0.377354 -0.468624 0.798746 + outer loop + vertex 810.8 193.207 29.9741 + vertex 809.596 194.075 31.0521 + vertex 807.512 190.432 29.8997 + endloop + endfacet + facet normal 0.411383 -0.50783 0.756884 + outer loop + vertex 809.259 189.899 28.5921 + vertex 810.8 193.207 29.9741 + vertex 807.512 190.432 29.8997 + endloop + endfacet + facet normal 0.407793 -0.514049 0.754625 + outer loop + vertex 809.259 189.899 28.5921 + vertex 807.512 190.432 29.8997 + vertex 805.523 186.681 28.4188 + endloop + endfacet + facet normal 0.40964 -0.514509 0.75331 + outer loop + vertex 805.523 186.681 28.4188 + vertex 807.512 190.432 29.8997 + vertex 803.754 187.465 29.916 + endloop + endfacet + facet normal 0.404648 -0.521602 0.751127 + outer loop + vertex 805.523 186.681 28.4188 + vertex 803.754 187.465 29.916 + vertex 801.088 183.192 28.3855 + endloop + endfacet + facet normal 0.399012 -0.519646 0.755485 + outer loop + vertex 801.088 183.192 28.3855 + vertex 803.754 187.465 29.916 + vertex 799.375 184.265 30.0278 + endloop + endfacet + facet normal 0.391642 -0.528215 0.753396 + outer loop + vertex 801.088 183.192 28.3855 + vertex 799.375 184.265 30.0278 + vertex 795.696 179.291 28.4532 + endloop + endfacet + facet normal 0.377438 -0.521463 0.765256 + outer loop + vertex 795.696 179.291 28.4532 + vertex 799.375 184.265 30.0278 + vertex 794.414 181.052 30.2857 + endloop + endfacet + facet normal 0.368334 -0.528023 0.765194 + outer loop + vertex 795.696 179.291 28.4532 + vertex 794.414 181.052 30.2857 + vertex 789.313 175.204 28.7054 + endloop + endfacet + facet normal 0.323873 -0.499581 0.803446 + outer loop + vertex 789.096 178.664 30.9447 + vertex 789.313 175.204 28.7054 + vertex 794.414 181.052 30.2857 + endloop + endfacet + facet normal 0.31575 -0.476832 0.820325 + outer loop + vertex 794.512 183.141 31.4622 + vertex 789.096 178.664 30.9447 + vertex 794.414 181.052 30.2857 + endloop + endfacet + facet normal 0.351221 -0.471928 0.808658 + outer loop + vertex 794.414 181.052 30.2857 + vertex 798.472 186.098 31.468 + vertex 794.512 183.141 31.4622 + endloop + endfacet + facet normal 0.345593 -0.468442 0.813097 + outer loop + vertex 799.375 184.265 30.0278 + vertex 798.472 186.098 31.468 + vertex 794.414 181.052 30.2857 + endloop + endfacet + facet normal 0.34912 -0.46643 0.812747 + outer loop + vertex 799.375 184.265 30.0278 + vertex 802.409 188.496 31.1532 + vertex 798.472 186.098 31.468 + endloop + endfacet + facet normal 0.368579 -0.476507 0.79818 + outer loop + vertex 803.754 187.465 29.916 + vertex 802.409 188.496 31.1532 + vertex 799.375 184.265 30.0278 + endloop + endfacet + facet normal 0.378053 -0.466163 0.799855 + outer loop + vertex 803.754 187.465 29.916 + vertex 806.297 191.849 31.2697 + vertex 802.409 188.496 31.1532 + endloop + endfacet + facet normal 0.369054 -0.462832 0.805969 + outer loop + vertex 807.512 190.432 29.8997 + vertex 806.297 191.849 31.2697 + vertex 803.754 187.465 29.916 + endloop + endfacet + facet normal 0.330524 -0.498032 0.801697 + outer loop + vertex 789.313 175.204 28.7054 + vertex 789.096 178.664 30.9447 + vertex 781.752 170.562 28.9391 + endloop + endfacet + facet normal 0.324384 -0.493741 0.806842 + outer loop + vertex 781.752 170.562 28.9391 + vertex 789.096 178.664 30.9447 + vertex 780.502 173.249 31.0857 + endloop + endfacet + facet normal 0.317246 -0.497491 0.807377 + outer loop + vertex 781.752 170.562 28.9391 + vertex 780.502 173.249 31.0857 + vertex 773.417 165.567 29.1365 + endloop + endfacet + facet normal 0.312191 -0.493887 0.81155 + outer loop + vertex 773.417 165.567 29.1365 + vertex 780.502 173.249 31.0857 + vertex 772.237 168.212 31.1999 + endloop + endfacet + facet normal 0.299582 -0.500201 0.812435 + outer loop + vertex 773.417 165.567 29.1365 + vertex 772.237 168.212 31.1999 + vertex 765.152 160.787 29.241 + endloop + endfacet + facet normal 0.29455 -0.496483 0.816545 + outer loop + vertex 765.152 160.787 29.241 + vertex 772.237 168.212 31.1999 + vertex 764.092 163.496 31.2709 + endloop + endfacet + facet normal 0.281513 -0.502345 0.817557 + outer loop + vertex 765.152 160.787 29.241 + vertex 764.092 163.496 31.2709 + vertex 757.002 156.305 29.2937 + endloop + endfacet + facet normal 0.280755 -0.501767 0.818172 + outer loop + vertex 757.002 156.305 29.2937 + vertex 764.092 163.496 31.2709 + vertex 755.904 159.025 31.3382 + endloop + endfacet + facet normal 0.269338 -0.50689 0.818853 + outer loop + vertex 757.002 156.305 29.2937 + vertex 755.904 159.025 31.3382 + vertex 748.752 152.023 29.3564 + endloop + endfacet + facet normal 0.275382 -0.511652 0.813865 + outer loop + vertex 748.752 152.023 29.3564 + vertex 755.904 159.025 31.3382 + vertex 747.584 154.73 31.4537 + endloop + endfacet + facet normal 0.26528 -0.516326 0.814269 + outer loop + vertex 748.752 152.023 29.3564 + vertex 747.584 154.73 31.4537 + vertex 740.294 147.878 29.4834 + endloop + endfacet + facet normal 0.274005 -0.523458 0.806792 + outer loop + vertex 740.294 147.878 29.4834 + vertex 747.584 154.73 31.4537 + vertex 739.198 150.615 31.6316 + endloop + endfacet + facet normal 0.2631 -0.528232 0.80731 + outer loop + vertex 740.294 147.878 29.4834 + vertex 739.198 150.615 31.6316 + vertex 731.948 144.007 29.6707 + endloop + endfacet + facet normal 0.2745 -0.537732 0.797179 + outer loop + vertex 731.948 144.007 29.6707 + vertex 739.198 150.615 31.6316 + vertex 730.762 146.593 31.8233 + endloop + endfacet + facet normal 0.258603 -0.545217 0.79741 + outer loop + vertex 731.948 144.007 29.6707 + vertex 730.762 146.593 31.8233 + vertex 723.713 140.133 29.6925 + endloop + endfacet + facet normal 0.275612 -0.558758 0.782194 + outer loop + vertex 723.713 140.133 29.6925 + vertex 730.762 146.593 31.8233 + vertex 722.14 142.514 31.9478 + endloop + endfacet + facet normal 0.253879 -0.571421 0.780399 + outer loop + vertex 723.713 140.133 29.6925 + vertex 722.14 142.514 31.9478 + vertex 714.445 135.377 29.2251 + endloop + endfacet + facet normal 0.29464 -0.601063 0.742907 + outer loop + vertex 714.445 135.377 29.2251 + vertex 722.14 142.514 31.9478 + vertex 713.956 138.888 32.26 + endloop + endfacet + facet normal 0.282623 -0.604417 0.744852 + outer loop + vertex 714.445 135.377 29.2251 + vertex 713.956 138.888 32.26 + vertex 707.945 133.479 30.1514 + endloop + endfacet + facet normal 0.3667 -0.464796 0.805913 + outer loop + vertex 807.512 190.432 29.8997 + vertex 809.596 194.075 31.0521 + vertex 806.297 191.849 31.2697 + endloop + endfacet + facet normal 0.377903 -0.463978 0.801195 + outer loop + vertex 813.896 195.785 29.9889 + vertex 816.158 199.5 31.0726 + vertex 813.002 197.275 31.2733 + endloop + endfacet + facet normal 0.401899 -0.473507 0.783753 + outer loop + vertex 817.157 198.426 29.9124 + vertex 816.158 199.5 31.0726 + vertex 813.896 195.785 29.9889 + endloop + endfacet + facet normal 0.39955 -0.475612 0.783679 + outer loop + vertex 817.157 198.426 29.9124 + vertex 819.692 202.865 31.3132 + vertex 816.158 199.5 31.0726 + endloop + endfacet + facet normal 0.412049 -0.479873 0.774557 + outer loop + vertex 820.575 201.264 29.8517 + vertex 819.692 202.865 31.3132 + vertex 817.157 198.426 29.9124 + endloop + endfacet + facet normal 0.436264 -0.509753 0.741502 + outer loop + vertex 818.072 197.174 28.5129 + vertex 820.575 201.264 29.8517 + vertex 817.157 198.426 29.9124 + endloop + endfacet + facet normal 0.437559 -0.508736 0.741438 + outer loop + vertex 818.072 197.174 28.5129 + vertex 817.157 198.426 29.9124 + vertex 814.71 194.538 28.688 + endloop + endfacet + facet normal 0.453149 -0.530268 0.716569 + outer loop + vertex 815.426 193.218 27.2588 + vertex 818.072 197.174 28.5129 + vertex 814.71 194.538 28.688 + endloop + endfacet + facet normal 0.457062 -0.531747 0.712979 + outer loop + vertex 818.998 196.045 27.0774 + vertex 818.072 197.174 28.5129 + vertex 815.426 193.218 27.2588 + endloop + endfacet + facet normal 0.460954 -0.537085 0.706443 + outer loop + vertex 816.514 192.302 25.8524 + vertex 818.998 196.045 27.0774 + vertex 815.426 193.218 27.2588 + endloop + endfacet + facet normal 0.455869 -0.542193 0.705841 + outer loop + vertex 816.514 192.302 25.8524 + vertex 815.426 193.218 27.2588 + vertex 812.586 189.363 26.1312 + endloop + endfacet + facet normal 0.451113 -0.535035 0.714307 + outer loop + vertex 814.306 188.996 24.7704 + vertex 816.514 192.302 25.8524 + vertex 812.586 189.363 26.1312 + endloop + endfacet + facet normal 0.446812 -0.542978 0.711009 + outer loop + vertex 814.306 188.996 24.7704 + vertex 812.586 189.363 26.1312 + vertex 809.881 185.69 25.0266 + endloop + endfacet + facet normal 0.442654 -0.54112 0.715015 + outer loop + vertex 809.881 185.69 25.0266 + vertex 812.586 189.363 26.1312 + vertex 808.082 186.558 26.7969 + endloop + endfacet + facet normal 0.436684 -0.548891 0.712759 + outer loop + vertex 809.881 185.69 25.0266 + vertex 808.082 186.558 26.7969 + vertex 804.566 181.823 25.305 + endloop + endfacet + facet normal 0.455751 -0.536744 0.710068 + outer loop + vertex 818.283 192.255 24.681 + vertex 816.514 192.302 25.8524 + vertex 814.306 188.996 24.7704 + endloop + endfacet + facet normal 0.458114 -0.530301 0.71338 + outer loop + vertex 818.283 192.255 24.681 + vertex 820.087 195.274 25.7676 + vertex 816.514 192.302 25.8524 + endloop + endfacet + facet normal 0.463584 -0.53187 0.708663 + outer loop + vertex 821.362 195.095 24.7984 + vertex 820.087 195.274 25.7676 + vertex 818.283 192.255 24.681 + endloop + endfacet + facet normal 0.465498 -0.527822 0.710433 + outer loop + vertex 821.362 195.095 24.7984 + vertex 823.361 198.054 25.6876 + vertex 820.087 195.274 25.7676 + endloop + endfacet + facet normal 0.471738 -0.535456 0.700535 + outer loop + vertex 823.361 198.054 25.6876 + vertex 822.431 198.936 26.9873 + vertex 820.087 195.274 25.7676 + endloop + endfacet + facet normal 0.468294 -0.53431 0.703714 + outer loop + vertex 820.087 195.274 25.7676 + vertex 822.431 198.936 26.9873 + vertex 818.998 196.045 27.0774 + endloop + endfacet + facet normal 0.46609 -0.531581 0.707235 + outer loop + vertex 822.431 198.936 26.9873 + vertex 821.518 200.033 28.4141 + vertex 818.998 196.045 27.0774 + endloop + endfacet + facet normal 0.467923 -0.530012 0.707202 + outer loop + vertex 822.431 198.936 26.9873 + vertex 824.859 202.902 28.3538 + vertex 821.518 200.033 28.4141 + endloop + endfacet + facet normal 0.458324 -0.518527 0.721851 + outer loop + vertex 824.859 202.902 28.3538 + vertex 823.943 204.143 29.8266 + vertex 821.518 200.033 28.4141 + endloop + endfacet + facet normal 0.445412 -0.514621 0.732648 + outer loop + vertex 821.518 200.033 28.4141 + vertex 823.943 204.143 29.8266 + vertex 820.575 201.264 29.8517 + endloop + endfacet + facet normal 0.428219 -0.494301 0.756502 + outer loop + vertex 823.943 204.143 29.8266 + vertex 822.94 205.238 31.1099 + vertex 820.575 201.264 29.8517 + endloop + endfacet + facet normal 0.422451 -0.499432 0.756375 + outer loop + vertex 823.943 204.143 29.8266 + vertex 826.423 208.741 31.4778 + vertex 822.94 205.238 31.1099 + endloop + endfacet + facet normal 0.442144 -0.504704 0.741473 + outer loop + vertex 827.273 207.103 29.8558 + vertex 826.423 208.741 31.4778 + vertex 823.943 204.143 29.8266 + endloop + endfacet + facet normal 0.431183 -0.511896 0.742996 + outer loop + vertex 827.273 207.103 29.8558 + vertex 829.721 211.401 31.396 + vertex 826.423 208.741 31.4778 + endloop + endfacet + facet normal 0.431417 -0.512198 0.742652 + outer loop + vertex 829.721 211.401 31.396 + vertex 830.865 215.791 33.7595 + vertex 826.423 208.741 31.4778 + endloop + endfacet + facet normal 0.381919 -0.493542 0.78138 + outer loop + vertex 830.865 215.791 33.7595 + vertex 824.16 209.508 33.0683 + vertex 826.423 208.741 31.4778 + endloop + endfacet + facet normal 0.393269 -0.473739 0.787979 + outer loop + vertex 822.94 205.238 31.1099 + vertex 826.423 208.741 31.4778 + vertex 824.16 209.508 33.0683 + endloop + endfacet + facet normal 0.395529 -0.473838 0.786787 + outer loop + vertex 822.94 205.238 31.1099 + vertex 824.16 209.508 33.0683 + vertex 819.692 202.865 31.3132 + endloop + endfacet + facet normal 0.352284 -0.453222 0.818832 + outer loop + vertex 824.16 209.508 33.0683 + vertex 817.458 203.682 32.7268 + vertex 819.692 202.865 31.3132 + endloop + endfacet + facet normal 0.360853 -0.43782 0.823468 + outer loop + vertex 816.158 199.5 31.0726 + vertex 819.692 202.865 31.3132 + vertex 817.458 203.682 32.7268 + endloop + endfacet + facet normal 0.360886 -0.437823 0.823451 + outer loop + vertex 816.158 199.5 31.0726 + vertex 817.458 203.682 32.7268 + vertex 813.002 197.275 31.2733 + endloop + endfacet + facet normal 0.32974 -0.421043 0.844982 + outer loop + vertex 817.458 203.682 32.7268 + vertex 810.78 198.13 32.5659 + vertex 813.002 197.275 31.2733 + endloop + endfacet + facet normal 0.333743 -0.413725 0.847023 + outer loop + vertex 809.596 194.075 31.0521 + vertex 813.002 197.275 31.2733 + vertex 810.78 198.13 32.5659 + endloop + endfacet + facet normal 0.335026 -0.413882 0.846439 + outer loop + vertex 809.596 194.075 31.0521 + vertex 810.78 198.13 32.5659 + vertex 806.297 191.849 31.2697 + endloop + endfacet + facet normal 0.314432 -0.401973 0.859971 + outer loop + vertex 810.78 198.13 32.5659 + vertex 803.744 192.602 32.5547 + vertex 806.297 191.849 31.2697 + endloop + endfacet + facet normal 0.31662 -0.397067 0.861446 + outer loop + vertex 802.409 188.496 31.1532 + vertex 806.297 191.849 31.2697 + vertex 803.744 192.602 32.5547 + endloop + endfacet + facet normal 0.310316 -0.39597 0.864241 + outer loop + vertex 802.409 188.496 31.1532 + vertex 803.744 192.602 32.5547 + vertex 798.472 186.098 31.468 + endloop + endfacet + facet normal 0.277836 -0.373141 0.885197 + outer loop + vertex 803.744 192.602 32.5547 + vertex 795.933 186.799 32.5606 + vertex 798.472 186.098 31.468 + endloop + endfacet + facet normal 0.277662 -0.373571 0.88507 + outer loop + vertex 794.512 183.141 31.4622 + vertex 798.472 186.098 31.468 + vertex 795.933 186.799 32.5606 + endloop + endfacet + facet normal 0.205131 -0.353671 0.912599 + outer loop + vertex 794.512 183.141 31.4622 + vertex 795.933 186.799 32.5606 + vertex 789.096 178.664 30.9447 + endloop + endfacet + facet normal 0.282495 -0.409705 0.867374 + outer loop + vertex 789.096 178.664 30.9447 + vertex 795.933 186.799 32.5606 + vertex 787.912 181.538 32.688 + endloop + endfacet + facet normal 0.274737 -0.413361 0.868131 + outer loop + vertex 789.096 178.664 30.9447 + vertex 787.912 181.538 32.688 + vertex 780.502 173.249 31.0857 + endloop + endfacet + facet normal 0.277541 -0.415498 0.866217 + outer loop + vertex 780.502 173.249 31.0857 + vertex 787.912 181.538 32.688 + vertex 779.803 176.317 32.7813 + endloop + endfacet + facet normal 0.267197 -0.418778 0.867889 + outer loop + vertex 780.502 173.249 31.0857 + vertex 779.803 176.317 32.7813 + vertex 772.237 168.212 31.1999 + endloop + endfacet + facet normal 0.262225 -0.414804 0.871307 + outer loop + vertex 772.237 168.212 31.1999 + vertex 779.803 176.317 32.7813 + vertex 771.751 171.386 32.8574 + endloop + endfacet + facet normal 0.249557 -0.41791 0.87354 + outer loop + vertex 772.237 168.212 31.1999 + vertex 771.751 171.386 32.8574 + vertex 764.092 163.496 31.2709 + endloop + endfacet + facet normal 0.248675 -0.417175 0.874143 + outer loop + vertex 764.092 163.496 31.2709 + vertex 771.751 171.386 32.8574 + vertex 763.646 166.714 32.9335 + endloop + endfacet + facet normal 0.236533 -0.419918 0.876197 + outer loop + vertex 764.092 163.496 31.2709 + vertex 763.646 166.714 32.9335 + vertex 755.904 159.025 31.3382 + endloop + endfacet + facet normal 0.241889 -0.424544 0.872498 + outer loop + vertex 755.904 159.025 31.3382 + vertex 763.646 166.714 32.9335 + vertex 755.409 162.238 33.0389 + endloop + endfacet + facet normal 0.232413 -0.426787 0.873978 + outer loop + vertex 755.904 159.025 31.3382 + vertex 755.409 162.238 33.0389 + vertex 747.584 154.73 31.4537 + endloop + endfacet + facet normal 0.243585 -0.436743 0.86598 + outer loop + vertex 747.584 154.73 31.4537 + vertex 755.409 162.238 33.0389 + vertex 747.06 157.932 33.2158 + endloop + endfacet + facet normal 0.233909 -0.439129 0.86744 + outer loop + vertex 747.584 154.73 31.4537 + vertex 747.06 157.932 33.2158 + vertex 739.198 150.615 31.6316 + endloop + endfacet + facet normal 0.250994 -0.454696 0.854549 + outer loop + vertex 739.198 150.615 31.6316 + vertex 747.06 157.932 33.2158 + vertex 738.625 153.771 33.4792 + endloop + endfacet + facet normal 0.237912 -0.458172 0.856432 + outer loop + vertex 739.198 150.615 31.6316 + vertex 738.625 153.771 33.4792 + vertex 730.762 146.593 31.8233 + endloop + endfacet + facet normal 0.259075 -0.477467 0.839587 + outer loop + vertex 730.762 146.593 31.8233 + vertex 738.625 153.771 33.4792 + vertex 730.037 149.655 33.7881 + endloop + endfacet + facet normal 0.240732 -0.483205 0.841761 + outer loop + vertex 730.762 146.593 31.8233 + vertex 730.037 149.655 33.7881 + vertex 722.14 142.514 31.9478 + endloop + endfacet + facet normal 0.432036 -0.512174 0.742309 + outer loop + vertex 829.721 211.401 31.396 + vertex 833.702 215.81 32.1216 + vertex 830.865 215.791 33.7595 + endloop + endfacet + facet normal 0.424645 -0.536559 0.729233 + outer loop + vertex 837.254 222.588 35.04 + vertex 830.865 215.791 33.7595 + vertex 833.702 215.81 32.1216 + endloop + endfacet + facet normal 0.41626 -0.530422 0.738498 + outer loop + vertex 837.254 222.588 35.04 + vertex 835.718 224.45 37.2432 + vertex 830.865 215.791 33.7595 + endloop + endfacet + facet normal 0.386862 -0.553532 0.737523 + outer loop + vertex 837.254 222.588 35.04 + vertex 841.179 229.975 38.5256 + vertex 835.718 224.45 37.2432 + endloop + endfacet + facet normal 0.392556 -0.557722 0.731332 + outer loop + vertex 841.179 229.975 38.5256 + vertex 840.144 231.907 40.5544 + vertex 835.718 224.45 37.2432 + endloop + endfacet + facet normal 0.460193 -0.520031 0.719577 + outer loop + vertex 830.839 210.46 30.0009 + vertex 829.721 211.401 31.396 + vertex 827.273 207.103 29.8558 + endloop + endfacet + facet normal 0.467387 -0.527244 0.709621 + outer loop + vertex 828.202 205.906 28.354 + vertex 830.839 210.46 30.0009 + vertex 827.273 207.103 29.8558 + endloop + endfacet + facet normal 0.470933 -0.524293 0.709464 + outer loop + vertex 828.202 205.906 28.354 + vertex 827.273 207.103 29.8558 + vertex 824.859 202.902 28.3538 + endloop + endfacet + facet normal 0.476803 -0.530827 0.70063 + outer loop + vertex 825.74 201.799 26.9177 + vertex 828.202 205.906 28.354 + vertex 824.859 202.902 28.3538 + endloop + endfacet + facet normal 0.485433 -0.533265 0.692808 + outer loop + vertex 829.117 204.838 26.8915 + vertex 828.202 205.906 28.354 + vertex 825.74 201.799 26.9177 + endloop + endfacet + facet normal 0.482488 -0.529954 0.697391 + outer loop + vertex 826.663 200.882 25.583 + vertex 829.117 204.838 26.8915 + vertex 825.74 201.799 26.9177 + endloop + endfacet + facet normal 0.478874 -0.533396 0.697258 + outer loop + vertex 826.663 200.882 25.583 + vertex 825.74 201.799 26.9177 + vertex 823.361 198.054 25.6876 + endloop + endfacet + facet normal 0.470931 -0.523651 0.709939 + outer loop + vertex 824.287 197.324 24.5348 + vertex 826.663 200.882 25.583 + vertex 823.361 198.054 25.6876 + endloop + endfacet + facet normal 0.473102 -0.524492 0.707872 + outer loop + vertex 827.914 200.404 24.3927 + vertex 826.663 200.882 25.583 + vertex 824.287 197.324 24.5348 + endloop + endfacet + facet normal 0.476491 -0.519364 0.709378 + outer loop + vertex 827.914 200.404 24.3927 + vertex 830.166 204.026 25.5314 + vertex 826.663 200.882 25.583 + endloop + endfacet + facet normal 0.47965 -0.520415 0.706473 + outer loop + vertex 831.734 203.825 24.3188 + vertex 830.166 204.026 25.5314 + vertex 827.914 200.404 24.3927 + endloop + endfacet + facet normal 0.48208 -0.515073 0.70873 + outer loop + vertex 831.734 203.825 24.3188 + vertex 833.795 207.376 25.4979 + vertex 830.166 204.026 25.5314 + endloop + endfacet + facet normal 0.494984 -0.529247 0.689121 + outer loop + vertex 833.795 207.376 25.4979 + vertex 832.686 208.121 26.867 + vertex 830.166 204.026 25.5314 + endloop + endfacet + facet normal 0.490298 -0.527811 0.693559 + outer loop + vertex 830.166 204.026 25.5314 + vertex 832.686 208.121 26.867 + vertex 829.117 204.838 26.8915 + endloop + endfacet + facet normal 0.497097 -0.535281 0.682912 + outer loop + vertex 832.686 208.121 26.867 + vertex 831.801 209.253 28.3981 + vertex 829.117 204.838 26.8915 + endloop + endfacet + facet normal 0.498097 -0.534423 0.682855 + outer loop + vertex 832.686 208.121 26.867 + vertex 835.696 212.753 28.2962 + vertex 831.801 209.253 28.3981 + endloop + endfacet + facet normal 0.503742 -0.540977 0.67349 + outer loop + vertex 835.696 212.753 28.2962 + vertex 835.017 214.453 30.1694 + vertex 831.801 209.253 28.3981 + endloop + endfacet + facet normal 0.483386 -0.535001 0.692901 + outer loop + vertex 831.801 209.253 28.3981 + vertex 835.017 214.453 30.1694 + vertex 830.839 210.46 30.0009 + endloop + endfacet + facet normal 0.481684 -0.533325 0.695374 + outer loop + vertex 835.017 214.453 30.1694 + vertex 833.702 215.81 32.1216 + vertex 830.839 210.46 30.0009 + endloop + endfacet + facet normal 0.47179 -0.54248 0.695075 + outer loop + vertex 835.017 214.453 30.1694 + vertex 838.867 220.792 32.5034 + vertex 833.702 215.81 32.1216 + endloop + endfacet + facet normal 0.47582 -0.546222 0.689375 + outer loop + vertex 838.867 220.792 32.5034 + vertex 837.254 222.588 35.04 + vertex 833.702 215.81 32.1216 + endloop + endfacet + facet normal 0.458591 -0.561194 0.689025 + outer loop + vertex 838.867 220.792 32.5034 + vertex 842.499 227.665 35.6849 + vertex 837.254 222.588 35.04 + endloop + endfacet + facet normal 0.466313 -0.567813 0.678337 + outer loop + vertex 842.499 227.665 35.6849 + vertex 841.179 229.975 38.5256 + vertex 837.254 222.588 35.04 + endloop + endfacet + facet normal 0.438268 -0.586875 0.680807 + outer loop + vertex 841.179 229.975 38.5256 + vertex 842.499 227.665 35.6849 + vertex 845.136 233.643 39.1403 + endloop + endfacet + facet normal 0.507346 -0.551849 0.661863 + outer loop + vertex 839.634 218.218 29.7695 + vertex 838.867 220.792 32.5034 + vertex 835.017 214.453 30.1694 + endloop + endfacet + facet normal 0.5013 -0.555393 0.663504 + outer loop + vertex 838.867 220.792 32.5034 + vertex 839.634 218.218 29.7695 + vertex 844.45 225.238 32.0072 + endloop + endfacet + facet normal 0.509998 -0.568302 0.645705 + outer loop + vertex 844.45 225.238 32.0072 + vertex 842.499 227.665 35.6849 + vertex 838.867 220.792 32.5034 + endloop + endfacet + facet normal 0.494397 -0.581467 0.646118 + outer loop + vertex 842.499 227.665 35.6849 + vertex 844.45 225.238 32.0072 + vertex 846.337 231.226 35.9525 + endloop + endfacet + facet normal 0.500992 -0.542757 0.674108 + outer loop + vertex 835.696 212.753 28.2962 + vertex 839.634 218.218 29.7695 + vertex 835.017 214.453 30.1694 + endloop + endfacet + facet normal 0.515414 -0.54884 0.658121 + outer loop + vertex 839.177 215.421 27.7949 + vertex 839.634 218.218 29.7695 + vertex 835.696 212.753 28.2962 + endloop + endfacet + facet normal 0.508262 -0.5366 0.673595 + outer loop + vertex 836.34 211.381 26.7171 + vertex 839.177 215.421 27.7949 + vertex 835.696 212.753 28.2962 + endloop + endfacet + facet normal 0.509412 -0.537075 0.672347 + outer loop + vertex 839.983 214.411 26.3775 + vertex 839.177 215.421 27.7949 + vertex 836.34 211.381 26.7171 + endloop + endfacet + facet normal 0.501818 -0.526373 0.686375 + outer loop + vertex 837.238 210.534 25.4108 + vertex 839.983 214.411 26.3775 + vertex 836.34 211.381 26.7171 + endloop + endfacet + facet normal 0.500916 -0.527275 0.686341 + outer loop + vertex 837.238 210.534 25.4108 + vertex 836.34 211.381 26.7171 + vertex 833.795 207.376 25.4979 + endloop + endfacet + facet normal 0.487608 -0.512193 0.707034 + outer loop + vertex 835.554 207.432 24.3258 + vertex 837.238 210.534 25.4108 + vertex 833.795 207.376 25.4979 + endloop + endfacet + facet normal 0.492689 -0.513407 0.702617 + outer loop + vertex 838.481 210.428 24.4615 + vertex 837.238 210.534 25.4108 + vertex 835.554 207.432 24.3258 + endloop + endfacet + facet normal 0.492951 -0.512782 0.70289 + outer loop + vertex 838.481 210.428 24.4615 + vertex 839.967 212.821 25.1657 + vertex 837.238 210.534 25.4108 + endloop + endfacet + facet normal 0.489212 -0.511501 0.706426 + outer loop + vertex 841.478 212.967 24.2254 + vertex 839.967 212.821 25.1657 + vertex 838.481 210.428 24.4615 + endloop + endfacet + facet normal 0.48855 -0.51417 0.704945 + outer loop + vertex 841.478 212.967 24.2254 + vertex 842.942 216.044 25.4546 + vertex 839.967 212.821 25.1657 + endloop + endfacet + facet normal 0.498635 -0.515688 0.696727 + outer loop + vertex 845.341 216.546 24.1093 + vertex 842.942 216.044 25.4546 + vertex 841.478 212.967 24.2254 + endloop + endfacet + facet normal 0.498868 -0.514097 0.697735 + outer loop + vertex 845.341 216.546 24.1093 + vertex 846.355 219.241 25.3696 + vertex 842.942 216.044 25.4546 + endloop + endfacet + facet normal 0.506887 -0.514323 0.691764 + outer loop + vertex 848.99 220.163 24.1251 + vertex 846.355 219.241 25.3696 + vertex 845.341 216.546 24.1093 + endloop + endfacet + facet normal 0.506848 -0.523281 0.685042 + outer loop + vertex 848.99 220.163 24.1251 + vertex 849.231 222.69 25.8762 + vertex 846.355 219.241 25.3696 + endloop + endfacet + facet normal 0.522405 -0.518928 0.676614 + outer loop + vertex 852 223.335 24.2333 + vertex 849.231 222.69 25.8762 + vertex 848.99 220.163 24.1251 + endloop + endfacet + facet normal 0.522039 -0.52132 0.675056 + outer loop + vertex 852 223.335 24.2333 + vertex 852.056 225.29 25.7001 + vertex 849.231 222.69 25.8762 + endloop + endfacet + facet normal 0.533932 -0.517098 0.668974 + outer loop + vertex 853.663 225.398 24.5007 + vertex 852.056 225.29 25.7001 + vertex 852 223.335 24.2333 + endloop + endfacet + facet normal 0.532298 -0.522173 0.666329 + outer loop + vertex 853.663 225.398 24.5007 + vertex 853.198 226.729 25.9162 + vertex 852.056 225.29 25.7001 + endloop + endfacet + facet normal 0.544796 -0.513895 0.662653 + outer loop + vertex 854.409 226.115 24.4436 + vertex 853.198 226.729 25.9162 + vertex 853.663 225.398 24.5007 + endloop + endfacet + facet normal 0.557726 -0.495739 0.665721 + outer loop + vertex 854.409 226.115 24.4436 + vertex 854.165 227.037 25.3348 + vertex 853.198 226.729 25.9162 + endloop + endfacet + facet normal 0.578933 -0.482196 0.657513 + outer loop + vertex 854.651 226.16 24.2633 + vertex 854.165 227.037 25.3348 + vertex 854.409 226.115 24.4436 + endloop + endfacet + facet normal 0.751704 -0.300454 0.587085 + outer loop + vertex 854.651 226.16 24.2633 + vertex 854.233 226.973 25.2152 + vertex 854.165 227.037 25.3348 + endloop + endfacet + facet normal -0.544184 0.504737 -0.670152 + outer loop + vertex 854.621 225.898 24.0908 + vertex 854.233 226.973 25.2152 + vertex 854.651 226.16 24.2633 + endloop + endfacet + facet normal 0.456714 -0.559121 0.691951 + outer loop + vertex 854.233 226.973 25.2152 + vertex 854.621 225.898 24.0908 + vertex 854.641 226.2 24.3212 + endloop + endfacet + facet normal 0.296787 -0.651168 0.698497 + outer loop + vertex 854.641 226.2 24.3212 + vertex 853.934 228.094 26.3871 + vertex 854.233 226.973 25.2152 + endloop + endfacet + facet normal 0.542204 -0.51873 0.66101 + outer loop + vertex 853.934 228.094 26.3871 + vertex 854.641 226.2 24.3212 + vertex 855.106 226.905 24.4933 + endloop + endfacet + facet normal 0.542649 -0.518277 0.661 + outer loop + vertex 855.106 226.905 24.4933 + vertex 855.661 228.508 25.2946 + vertex 853.934 228.094 26.3871 + endloop + endfacet + facet normal 0.480935 -0.519542 0.706242 + outer loop + vertex 855.106 226.905 24.4933 + vertex 856.833 227.158 23.5031 + vertex 855.661 228.508 25.2946 + endloop + endfacet + facet normal 0.505598 -0.496887 0.705318 + outer loop + vertex 856.833 227.158 23.5031 + vertex 858.454 229.25 23.8152 + vertex 855.661 228.508 25.2946 + endloop + endfacet + facet normal 0.504748 -0.507267 0.698505 + outer loop + vertex 855.661 228.508 25.2946 + vertex 858.454 229.25 23.8152 + vertex 857.499 230.942 25.7341 + endloop + endfacet + facet normal 0.516467 -0.498275 0.696408 + outer loop + vertex 858.454 229.25 23.8152 + vertex 860.887 231.862 23.8796 + vertex 857.499 230.942 25.7341 + endloop + endfacet + facet normal 0.517015 -0.491657 0.700692 + outer loop + vertex 857.499 230.942 25.7341 + vertex 860.887 231.862 23.8796 + vertex 860.211 233.38 25.4437 + endloop + endfacet + facet normal 0.51623 -0.492206 0.700885 + outer loop + vertex 860.887 231.862 23.8796 + vertex 863.729 234.844 23.8809 + vertex 860.211 233.38 25.4437 + endloop + endfacet + facet normal 0.516886 -0.500938 0.694183 + outer loop + vertex 860.211 233.38 25.4437 + vertex 863.729 234.844 23.8809 + vertex 862.807 236.525 25.7798 + endloop + endfacet + facet normal 0.528392 -0.492035 0.691884 + outer loop + vertex 863.729 234.844 23.8809 + vertex 866.724 238.047 23.8705 + vertex 862.807 236.525 25.7798 + endloop + endfacet + facet normal 0.527951 -0.479575 0.700911 + outer loop + vertex 862.807 236.525 25.7798 + vertex 866.724 238.047 23.8705 + vertex 866.183 239.643 25.3705 + endloop + endfacet + facet normal 0.531542 -0.477278 0.699763 + outer loop + vertex 866.724 238.047 23.8705 + vertex 869.696 241.291 23.8261 + vertex 866.183 239.643 25.3705 + endloop + endfacet + facet normal 0.531037 -0.473344 0.702813 + outer loop + vertex 866.183 239.643 25.3705 + vertex 869.696 241.291 23.8261 + vertex 868.898 242.771 25.4259 + endloop + endfacet + facet normal 0.539125 -0.466948 0.700931 + outer loop + vertex 869.696 241.291 23.8261 + vertex 872.58 244.55 23.7793 + vertex 868.898 242.771 25.4259 + endloop + endfacet + facet normal 0.536298 -0.447472 0.715649 + outer loop + vertex 868.898 242.771 25.4259 + vertex 872.58 244.55 23.7793 + vertex 872.089 245.816 24.9389 + endloop + endfacet + facet normal 0.533943 -0.449077 0.716404 + outer loop + vertex 872.58 244.55 23.7793 + vertex 875.302 247.813 23.7954 + vertex 872.089 245.816 24.9389 + endloop + endfacet + facet normal 0.538526 -0.463888 0.703418 + outer loop + vertex 872.089 245.816 24.9389 + vertex 875.302 247.813 23.7954 + vertex 874.15 248.703 25.2651 + endloop + endfacet + facet normal 0.550715 -0.448745 0.703805 + outer loop + vertex 875.302 247.813 23.7954 + vertex 877.896 251.2 23.9253 + vertex 874.15 248.703 25.2651 + endloop + endfacet + facet normal 0.553746 -0.457687 0.69562 + outer loop + vertex 874.15 248.703 25.2651 + vertex 877.896 251.2 23.9253 + vertex 876.908 252.291 25.43 + endloop + endfacet + facet normal 0.568392 -0.442069 0.693906 + outer loop + vertex 877.896 251.2 23.9253 + vertex 880.505 254.719 24.0299 + vertex 876.908 252.291 25.43 + endloop + endfacet + facet normal 0.569098 -0.444256 0.691928 + outer loop + vertex 876.908 252.291 25.43 + vertex 880.505 254.719 24.0299 + vertex 879.613 255.849 25.4895 + endloop + endfacet + facet normal 0.583261 -0.429701 0.689321 + outer loop + vertex 880.505 254.719 24.0299 + vertex 882.984 258.228 24.1197 + vertex 879.613 255.849 25.4895 + endloop + endfacet + facet normal 0.583732 -0.431102 0.688046 + outer loop + vertex 879.613 255.849 25.4895 + vertex 882.984 258.228 24.1197 + vertex 882.052 259.276 25.5672 + endloop + endfacet + facet normal 0.597908 -0.415191 0.685655 + outer loop + vertex 882.984 258.228 24.1197 + vertex 885.307 261.715 24.2061 + vertex 882.052 259.276 25.5672 + endloop + endfacet + facet normal 0.599239 -0.418869 0.682248 + outer loop + vertex 882.052 259.276 25.5672 + vertex 885.307 261.715 24.2061 + vertex 884.316 262.677 25.6667 + endloop + endfacet + facet normal 0.61347 -0.401158 0.68024 + outer loop + vertex 885.307 261.715 24.2061 + vertex 887.508 265.215 24.2845 + vertex 884.316 262.677 25.6667 + endloop + endfacet + facet normal 0.614883 -0.404813 0.676791 + outer loop + vertex 884.316 262.677 25.6667 + vertex 887.508 265.215 24.2845 + vertex 886.481 266.114 25.7557 + endloop + endfacet + facet normal 0.628441 -0.386484 0.675049 + outer loop + vertex 887.508 265.215 24.2845 + vertex 889.612 268.761 24.3565 + vertex 886.481 266.114 25.7557 + endloop + endfacet + facet normal 0.631662 -0.39429 0.667487 + outer loop + vertex 886.481 266.114 25.7557 + vertex 889.612 268.761 24.3565 + vertex 888.569 269.633 25.8586 + endloop + endfacet + facet normal 0.64697 -0.372385 0.665401 + outer loop + vertex 889.612 268.761 24.3565 + vertex 891.626 272.392 24.4301 + vertex 888.569 269.633 25.8586 + endloop + endfacet + facet normal 0.650021 -0.379366 0.658448 + outer loop + vertex 888.569 269.633 25.8586 + vertex 891.626 272.392 24.4301 + vertex 890.577 273.242 25.9555 + endloop + endfacet + facet normal 0.665196 -0.356417 0.656111 + outer loop + vertex 891.626 272.392 24.4301 + vertex 893.555 276.133 24.5072 + vertex 890.577 273.242 25.9555 + endloop + endfacet + facet normal 0.669043 -0.364624 0.647635 + outer loop + vertex 890.577 273.242 25.9555 + vertex 893.555 276.133 24.5072 + vertex 892.5 276.952 26.0581 + endloop + endfacet + facet normal 0.684751 -0.339323 0.644962 + outer loop + vertex 893.555 276.133 24.5072 + vertex 895.393 279.996 24.5873 + vertex 892.5 276.952 26.0581 + endloop + endfacet + facet normal 0.687476 -0.344706 0.639183 + outer loop + vertex 892.5 276.952 26.0581 + vertex 895.393 279.996 24.5873 + vertex 894.328 280.763 26.1469 + endloop + endfacet + facet normal 0.702288 -0.31876 0.636541 + outer loop + vertex 895.393 279.996 24.5873 + vertex 897.13 283.979 24.6656 + vertex 894.328 280.763 26.1469 + endloop + endfacet + facet normal 0.704991 -0.323638 0.631067 + outer loop + vertex 894.328 280.763 26.1469 + vertex 897.13 283.979 24.6656 + vertex 896.061 284.7 26.2297 + endloop + endfacet + facet normal 0.719647 -0.295724 0.628216 + outer loop + vertex 897.13 283.979 24.6656 + vertex 898.747 288.068 24.7383 + vertex 896.061 284.7 26.2297 + endloop + endfacet + facet normal 0.721528 -0.298837 0.624575 + outer loop + vertex 896.061 284.7 26.2297 + vertex 898.747 288.068 24.7383 + vertex 897.675 288.736 26.2967 + endloop + endfacet + facet normal 0.734384 -0.271933 0.621879 + outer loop + vertex 898.747 288.068 24.7383 + vertex 900.226 292.235 24.8143 + vertex 897.675 288.736 26.2967 + endloop + endfacet + facet normal 0.736067 -0.274481 0.618761 + outer loop + vertex 897.675 288.736 26.2967 + vertex 900.226 292.235 24.8143 + vertex 899.152 292.861 26.3692 + endloop + endfacet + facet normal 0.747987 -0.247143 0.615984 + outer loop + vertex 900.226 292.235 24.8143 + vertex 901.549 296.431 24.8909 + vertex 899.152 292.861 26.3692 + endloop + endfacet + facet normal 0.749352 -0.249071 0.613543 + outer loop + vertex 899.152 292.861 26.3692 + vertex 901.549 296.431 24.8909 + vertex 900.476 297.014 26.4378 + endloop + endfacet + facet normal 0.760175 -0.2217 0.610723 + outer loop + vertex 901.549 296.431 24.8909 + vertex 902.703 300.598 24.9669 + vertex 900.476 297.014 26.4378 + endloop + endfacet + facet normal 0.761363 -0.223283 0.608663 + outer loop + vertex 900.476 297.014 26.4378 + vertex 902.703 300.598 24.9669 + vertex 901.633 301.142 26.5052 + endloop + endfacet + facet normal 0.771726 -0.194184 0.605583 + outer loop + vertex 902.703 300.598 24.9669 + vertex 903.681 304.717 25.0416 + vertex 901.633 301.142 26.5052 + endloop + endfacet + facet normal 0.772549 -0.195222 0.604199 + outer loop + vertex 901.633 301.142 26.5052 + vertex 903.681 304.717 25.0416 + vertex 902.615 305.224 26.5692 + endloop + endfacet + facet normal 0.782588 -0.163509 0.600684 + outer loop + vertex 903.681 304.717 25.0416 + vertex 904.488 308.817 25.107 + vertex 902.615 305.224 26.5692 + endloop + endfacet + facet normal 0.783782 -0.164924 0.598737 + outer loop + vertex 902.615 305.224 26.5692 + vertex 904.488 308.817 25.107 + vertex 903.427 309.291 26.6261 + endloop + endfacet + facet normal 0.792602 -0.133245 0.595003 + outer loop + vertex 904.488 308.817 25.107 + vertex 905.134 312.95 25.1714 + vertex 903.427 309.291 26.6261 + endloop + endfacet + facet normal 0.794227 -0.135027 0.592429 + outer loop + vertex 903.427 309.291 26.6261 + vertex 905.134 312.95 25.1714 + vertex 904.081 313.409 26.6879 + endloop + endfacet + facet normal 0.801856 -0.104141 0.588373 + outer loop + vertex 905.134 312.95 25.1714 + vertex 905.635 317.158 25.2337 + vertex 904.081 313.409 26.6879 + endloop + endfacet + facet normal 0.802368 -0.104661 0.587581 + outer loop + vertex 904.081 313.409 26.6879 + vertex 905.635 317.158 25.2337 + vertex 904.589 317.611 26.7433 + endloop + endfacet + facet normal 0.808743 -0.0756503 0.583277 + outer loop + vertex 905.635 317.158 25.2337 + vertex 905.995 321.454 25.2909 + vertex 904.589 317.611 26.7433 + endloop + endfacet + facet normal 0.808428 -0.0753564 0.583751 + outer loop + vertex 904.589 317.611 26.7433 + vertex 905.995 321.454 25.2909 + vertex 904.952 321.907 26.7947 + endloop + endfacet + facet normal 0.8139 -0.0472475 0.579081 + outer loop + vertex 905.995 321.454 25.2909 + vertex 906.212 325.822 25.3426 + vertex 904.952 321.907 26.7947 + endloop + endfacet + facet normal 0.812719 -0.0462224 0.580819 + outer loop + vertex 904.952 321.907 26.7947 + vertex 906.212 325.822 25.3426 + vertex 905.168 326.27 26.8392 + endloop + endfacet + facet normal 0.817282 -0.019191 0.575918 + outer loop + vertex 906.212 325.822 25.3426 + vertex 906.282 330.233 25.39 + vertex 905.168 326.27 26.8392 + endloop + endfacet + facet normal 0.817002 -0.0189639 0.576323 + outer loop + vertex 905.168 326.27 26.8392 + vertex 906.282 330.233 25.39 + vertex 905.237 330.672 26.8868 + endloop + endfacet + facet normal 0.820681 0.00677447 0.571346 + outer loop + vertex 906.282 330.233 25.39 + vertex 906.214 334.648 25.436 + vertex 905.237 330.672 26.8868 + endloop + endfacet + facet normal 0.820963 0.00655861 0.570944 + outer loop + vertex 905.237 330.672 26.8868 + vertex 906.214 334.648 25.436 + vertex 905.168 335.072 26.9345 + endloop + endfacet + facet normal 0.823804 0.0308993 0.566032 + outer loop + vertex 906.214 334.648 25.436 + vertex 906.018 339.043 25.4805 + vertex 905.168 335.072 26.9345 + endloop + endfacet + facet normal 0.823739 0.0309472 0.566125 + outer loop + vertex 905.168 335.072 26.9345 + vertex 906.018 339.043 25.4805 + vertex 904.98 339.439 26.9704 + endloop + endfacet + facet normal 0.825699 0.0530187 0.561614 + outer loop + vertex 906.018 339.043 25.4805 + vertex 905.711 343.403 25.5215 + vertex 904.98 339.439 26.9704 + endloop + endfacet + facet normal 0.829199 0.0505633 0.556662 + outer loop + vertex 904.98 339.439 26.9704 + vertex 905.711 343.403 25.5215 + vertex 904.685 343.79 27.0147 + endloop + endfacet + facet normal 0.83067 0.0722711 0.552055 + outer loop + vertex 905.711 343.403 25.5215 + vertex 905.305 347.751 25.5631 + vertex 904.685 343.79 27.0147 + endloop + endfacet + facet normal 0.83456 0.0696265 0.546499 + outer loop + vertex 904.685 343.79 27.0147 + vertex 905.305 347.751 25.5631 + vertex 904.296 348.141 27.0543 + endloop + endfacet + facet normal 0.835591 0.0893851 0.542032 + outer loop + vertex 905.305 347.751 25.5631 + vertex 904.813 352.117 25.6017 + vertex 904.296 348.141 27.0543 + endloop + endfacet + facet normal 0.839099 0.0870769 0.536964 + outer loop + vertex 904.296 348.141 27.0543 + vertex 904.813 352.117 25.6017 + vertex 903.819 352.514 27.0895 + endloop + endfacet + facet normal 0.839766 0.103857 0.532924 + outer loop + vertex 904.813 352.117 25.6017 + vertex 904.245 356.512 25.6402 + vertex 903.819 352.514 27.0895 + endloop + endfacet + facet normal 0.840329 0.103499 0.532104 + outer loop + vertex 903.819 352.514 27.0895 + vertex 904.245 356.512 25.6402 + vertex 903.266 356.896 27.1113 + endloop + endfacet + facet normal 0.840677 0.118932 0.528316 + outer loop + vertex 904.245 356.512 25.6402 + vertex 903.605 360.922 25.665 + vertex 903.266 356.896 27.1113 + endloop + endfacet + facet normal 0.841485 0.118441 0.527138 + outer loop + vertex 903.266 356.896 27.1113 + vertex 903.605 360.922 25.665 + vertex 902.64 361.282 27.1246 + endloop + endfacet + facet normal 0.841528 0.134435 0.52322 + outer loop + vertex 903.605 360.922 25.665 + vertex 902.893 365.344 25.6742 + vertex 902.64 361.282 27.1246 + endloop + endfacet + facet normal 0.843696 0.133166 0.520043 + outer loop + vertex 902.64 361.282 27.1246 + vertex 902.893 365.344 25.6742 + vertex 901.93 365.714 27.1422 + endloop + endfacet + facet normal 0.843578 0.147428 0.516372 + outer loop + vertex 902.893 365.344 25.6742 + vertex 902.098 369.83 25.6923 + vertex 901.93 365.714 27.1422 + endloop + endfacet + facet normal 0.845709 0.14623 0.513218 + outer loop + vertex 901.93 365.714 27.1422 + vertex 902.098 369.83 25.6923 + vertex 901.108 370.281 27.1955 + endloop + endfacet + facet normal 0.84572 0.159091 0.509361 + outer loop + vertex 902.098 369.83 25.6923 + vertex 901.2 374.443 25.7417 + vertex 901.108 370.281 27.1955 + endloop + endfacet + facet normal 0.849718 0.156902 0.503349 + outer loop + vertex 901.108 370.281 27.1955 + vertex 901.2 374.443 25.7417 + vertex 900.15 375.062 27.3218 + endloop + endfacet + facet normal 0.850094 0.170586 0.498238 + outer loop + vertex 901.2 374.443 25.7417 + vertex 900.204 379.182 25.8189 + vertex 900.15 375.062 27.3218 + endloop + endfacet + facet normal 0.860069 0.164829 0.482818 + outer loop + vertex 900.15 375.062 27.3218 + vertex 900.204 379.182 25.8189 + vertex 899.064 380.087 27.5401 + endloop + endfacet + facet normal 0.861282 0.183214 0.473947 + outer loop + vertex 900.204 379.182 25.8189 + vertex 899.181 383.881 25.8616 + vertex 899.064 380.087 27.5401 + endloop + endfacet + facet normal 0.857413 0.185949 0.47986 + outer loop + vertex 899.064 380.087 27.5401 + vertex 899.181 383.881 25.8616 + vertex 898.178 384.65 27.3559 + endloop + endfacet + facet normal 0.857756 0.193104 0.476408 + outer loop + vertex 899.181 383.881 25.8616 + vertex 898.125 388.417 25.9238 + vertex 898.178 384.65 27.3559 + endloop + endfacet + facet normal 0.867944 0.187046 0.460095 + outer loop + vertex 898.178 384.65 27.3559 + vertex 898.125 388.417 25.9238 + vertex 897.037 388.901 27.7801 + endloop + endfacet + facet normal 0.86657 0.207071 0.454069 + outer loop + vertex 898.125 388.417 25.9238 + vertex 897.029 392.933 25.957 + vertex 897.037 388.901 27.7801 + endloop + endfacet + facet normal 0.86008 0.211636 0.46419 + outer loop + vertex 897.037 388.901 27.7801 + vertex 897.029 392.933 25.957 + vertex 896.012 393.742 27.472 + endloop + endfacet + facet normal 0.860133 0.213385 0.463291 + outer loop + vertex 897.029 392.933 25.957 + vertex 895.911 397.399 25.9748 + vertex 896.012 393.742 27.472 + endloop + endfacet + facet normal 0.868818 0.207922 0.44936 + outer loop + vertex 896.012 393.742 27.472 + vertex 895.911 397.399 25.9748 + vertex 894.821 397.928 27.8381 + endloop + endfacet + facet normal 0.867572 0.223706 0.444156 + outer loop + vertex 895.911 397.399 25.9748 + vertex 894.767 401.824 25.9817 + vertex 894.821 397.928 27.8381 + endloop + endfacet + facet normal 0.85825 0.23045 0.458584 + outer loop + vertex 894.821 397.928 27.8381 + vertex 894.767 401.824 25.9817 + vertex 893.748 402.613 27.4913 + endloop + endfacet + facet normal 0.858249 0.230265 0.45868 + outer loop + vertex 894.767 401.824 25.9817 + vertex 893.578 406.259 25.9793 + vertex 893.748 402.613 27.4913 + endloop + endfacet + facet normal 0.868649 0.223826 0.441985 + outer loop + vertex 893.748 402.613 27.4913 + vertex 893.578 406.259 25.9793 + vertex 892.497 406.765 27.8481 + endloop + endfacet + facet normal 0.867127 0.239036 0.436981 + outer loop + vertex 893.578 406.259 25.9793 + vertex 892.343 410.738 25.9806 + vertex 892.497 406.765 27.8481 + endloop + endfacet + facet normal 0.858915 0.244763 0.449841 + outer loop + vertex 892.497 406.765 27.8481 + vertex 892.343 410.738 25.9806 + vertex 891.337 411.482 27.4966 + endloop + endfacet + facet normal 0.858969 0.24195 0.451257 + outer loop + vertex 892.343 410.738 25.9806 + vertex 891.074 415.234 25.9855 + vertex 891.337 411.482 27.4966 + endloop + endfacet + facet normal 0.868452 0.236386 0.43579 + outer loop + vertex 891.337 411.482 27.4966 + vertex 891.074 415.234 25.9855 + vertex 890.029 415.63 27.8534 + endloop + endfacet + facet normal 0.866701 0.249273 0.43208 + outer loop + vertex 891.074 415.234 25.9855 + vertex 889.789 419.69 25.9916 + vertex 890.029 415.63 27.8534 + endloop + endfacet + facet normal 0.857713 0.255257 0.446287 + outer loop + vertex 890.029 415.63 27.8534 + vertex 889.789 419.69 25.9916 + vertex 888.819 420.307 27.5043 + endloop + endfacet + facet normal 0.857877 0.252639 0.44746 + outer loop + vertex 889.789 419.69 25.9916 + vertex 888.504 424.057 25.9901 + vertex 888.819 420.307 27.5043 + endloop + endfacet + facet normal 0.86777 0.246934 0.431276 + outer loop + vertex 888.819 420.307 27.5043 + vertex 888.504 424.057 25.9901 + vertex 887.505 424.312 27.8535 + endloop + endfacet + facet normal 0.865777 0.258232 0.428657 + outer loop + vertex 888.504 424.057 25.9901 + vertex 887.221 428.357 25.9917 + vertex 887.505 424.312 27.8535 + endloop + endfacet + facet normal 0.857638 0.263598 0.441557 + outer loop + vertex 887.505 424.312 27.8535 + vertex 887.221 428.357 25.9917 + vertex 886.28 428.887 27.5033 + endloop + endfacet + facet normal 0.858114 0.25851 0.443637 + outer loop + vertex 887.221 428.357 25.9917 + vertex 885.924 432.658 25.9935 + vertex 886.28 428.887 27.5033 + endloop + endfacet + facet normal 0.868775 0.252462 0.426019 + outer loop + vertex 886.28 428.887 27.5033 + vertex 885.924 432.658 25.9935 + vertex 884.948 432.87 27.857 + endloop + endfacet + facet normal 0.866671 0.263411 0.423671 + outer loop + vertex 885.924 432.658 25.9935 + vertex 884.598 437.021 25.9928 + vertex 884.948 432.87 27.857 + endloop + endfacet + facet normal 0.857873 0.269021 0.437814 + outer loop + vertex 884.948 432.87 27.857 + vertex 884.598 437.021 25.9928 + vertex 883.673 437.517 27.5004 + endloop + endfacet + facet normal 0.858631 0.261959 0.440602 + outer loop + vertex 884.598 437.021 25.9928 + vertex 883.248 441.45 25.9915 + vertex 883.673 437.517 27.5004 + endloop + endfacet + facet normal 0.871415 0.255064 0.419021 + outer loop + vertex 883.673 437.517 27.5004 + vertex 883.248 441.45 25.9915 + vertex 882.314 441.57 27.8607 + endloop + endfacet + facet normal 0.869217 0.26523 0.417271 + outer loop + vertex 883.248 441.45 25.9915 + vertex 881.887 445.906 25.9928 + vertex 882.314 441.57 27.8607 + endloop + endfacet + facet normal 0.861298 0.270093 0.430368 + outer loop + vertex 882.314 441.57 27.8607 + vertex 881.887 445.906 25.9928 + vertex 881.012 446.281 27.5088 + endloop + endfacet + facet normal 0.86233 0.262919 0.432736 + outer loop + vertex 881.887 445.906 25.9928 + vertex 880.544 450.31 25.9931 + vertex 881.012 446.281 27.5088 + endloop + endfacet + facet normal 0.873729 0.256846 0.41307 + outer loop + vertex 881.012 446.281 27.5088 + vertex 880.544 450.31 25.9931 + vertex 879.682 450.239 27.8624 + endloop + endfacet + facet normal 0.871702 0.264643 0.412431 + outer loop + vertex 880.544 450.31 25.9931 + vertex 879.232 454.632 25.9941 + vertex 879.682 450.239 27.8624 + endloop + endfacet + facet normal 0.863748 0.269513 0.425796 + outer loop + vertex 879.682 450.239 27.8624 + vertex 879.232 454.632 25.9941 + vertex 878.416 454.853 27.5095 + endloop + endfacet + facet normal 0.864816 0.263795 0.427206 + outer loop + vertex 879.232 454.632 25.9941 + vertex 877.936 458.89 25.9887 + vertex 878.416 454.853 27.5095 + endloop + endfacet + facet normal 0.875096 0.258263 0.409276 + outer loop + vertex 878.416 454.853 27.5095 + vertex 877.936 458.89 25.9887 + vertex 877.118 458.708 27.8532 + endloop + endfacet + facet normal 0.872951 0.265744 0.409067 + outer loop + vertex 877.936 458.89 25.9887 + vertex 876.626 463.165 26.0066 + vertex 877.118 458.708 27.8532 + endloop + endfacet + facet normal 0.866709 0.269483 0.419755 + outer loop + vertex 877.118 458.708 27.8532 + vertex 876.626 463.165 26.0066 + vertex 875.838 463.338 27.5218 + endloop + endfacet + facet normal 0.867342 0.266359 0.420441 + outer loop + vertex 876.626 463.165 26.0066 + vertex 875.255 467.55 26.0568 + vertex 875.838 463.338 27.5218 + endloop + endfacet + facet normal 0.878765 0.260739 0.399735 + outer loop + vertex 875.838 463.338 27.5218 + vertex 875.255 467.55 26.0568 + vertex 874.513 467.242 27.8898 + endloop + endfacet + facet normal 0.876489 0.267876 0.400012 + outer loop + vertex 875.255 467.55 26.0568 + vertex 873.778 472.146 26.2155 + vertex 874.513 467.242 27.8898 + endloop + endfacet + facet normal 0.880584 0.265855 0.392293 + outer loop + vertex 874.513 467.242 27.8898 + vertex 873.778 472.146 26.2155 + vertex 873.332 471.469 27.6754 + endloop + endfacet + facet normal 0.890889 0.242011 0.38438 + outer loop + vertex 873.332 471.469 27.6754 + vertex 873.778 472.146 26.2155 + vertex 871.973 477.701 26.9001 + endloop + endfacet + facet normal 0.882697 0.236688 0.405987 + outer loop + vertex 873.778 472.146 26.2155 + vertex 873.117 476.95 24.8508 + vertex 871.973 477.701 26.9001 + endloop + endfacet + facet normal 0.879527 0.26946 0.392204 + outer loop + vertex 871.808 481.56 24.6194 + vertex 871.973 477.701 26.9001 + vertex 873.117 476.95 24.8508 + endloop + endfacet + facet normal 0.933158 0.211672 0.290537 + outer loop + vertex 871.808 481.56 24.6194 + vertex 870.775 485.623 24.9776 + vertex 871.973 477.701 26.9001 + endloop + endfacet + facet normal 0.97497 0.179372 0.131377 + outer loop + vertex 870.02 488.074 27.2322 + vertex 871.973 477.701 26.9001 + vertex 870.775 485.623 24.9776 + endloop + endfacet + facet normal 0.965369 0.064792 0.252713 + outer loop + vertex 870.541 490.071 24.7314 + vertex 870.02 488.074 27.2322 + vertex 870.775 485.623 24.9776 + endloop + endfacet + facet normal 0.487958 -0.481088 0.728321 + outer loop + vertex 855.838 225.675 23.1908 + vertex 856.833 227.158 23.5031 + vertex 855.106 226.905 24.4933 + endloop + endfacet + facet normal 0.474703 -0.491141 0.730368 + outer loop + vertex 855.838 225.675 23.1908 + vertex 855.106 226.905 24.4933 + vertex 854.641 226.2 24.3212 + endloop + endfacet + facet normal 0.50325 -0.527004 0.68484 + outer loop + vertex 839.967 212.821 25.1657 + vertex 839.983 214.411 26.3775 + vertex 837.238 210.534 25.4108 + endloop + endfacet + facet normal 0.504118 -0.526703 0.684434 + outer loop + vertex 839.967 212.821 25.1657 + vertex 842.942 216.044 25.4546 + vertex 839.983 214.411 26.3775 + endloop + endfacet + facet normal 0.506913 -0.537906 0.673569 + outer loop + vertex 839.983 214.411 26.3775 + vertex 842.942 216.044 25.4546 + vertex 844.128 219.941 27.6744 + endloop + endfacet + facet normal 0.519296 -0.53678 0.66498 + outer loop + vertex 846.355 219.241 25.3696 + vertex 844.128 219.941 27.6744 + vertex 842.942 216.044 25.4546 + endloop + endfacet + facet normal 0.521738 -0.532925 0.666169 + outer loop + vertex 846.355 219.241 25.3696 + vertex 849.231 222.69 25.8762 + vertex 844.128 219.941 27.6744 + endloop + endfacet + facet normal 0.524967 -0.549539 0.649936 + outer loop + vertex 849.231 222.69 25.8762 + vertex 849.589 226.46 28.775 + vertex 844.128 219.941 27.6744 + endloop + endfacet + facet normal 0.533458 -0.554725 0.638517 + outer loop + vertex 844.45 225.238 32.0072 + vertex 844.128 219.941 27.6744 + vertex 849.589 226.46 28.775 + endloop + endfacet + facet normal 0.529265 -0.574481 0.62438 + outer loop + vertex 849.589 226.46 28.775 + vertex 848.067 229.75 33.0931 + vertex 844.45 225.238 32.0072 + endloop + endfacet + facet normal 0.532804 -0.576206 0.619763 + outer loop + vertex 848.067 229.75 33.0931 + vertex 846.337 231.226 35.9525 + vertex 844.45 225.238 32.0072 + endloop + endfacet + facet normal 0.520554 -0.588447 0.61867 + outer loop + vertex 848.067 229.75 33.0931 + vertex 848.454 232.762 35.6321 + vertex 846.337 231.226 35.9525 + endloop + endfacet + facet normal 0.524666 -0.596462 0.60742 + outer loop + vertex 848.454 232.762 35.6321 + vertex 847.591 235.172 38.744 + vertex 846.337 231.226 35.9525 + endloop + endfacet + facet normal 0.478688 -0.60336 0.63782 + outer loop + vertex 846.337 231.226 35.9525 + vertex 847.591 235.172 38.744 + vertex 845.136 233.643 39.1403 + endloop + endfacet + facet normal 0.501302 -0.588054 0.634735 + outer loop + vertex 846.337 231.226 35.9525 + vertex 845.136 233.643 39.1403 + vertex 842.499 227.665 35.6849 + endloop + endfacet + facet normal 0.483354 -0.614588 0.623418 + outer loop + vertex 847.591 235.172 38.744 + vertex 846.877 237.909 41.9951 + vertex 845.136 233.643 39.1403 + endloop + endfacet + facet normal 0.457922 -0.628053 0.629171 + outer loop + vertex 846.877 237.909 41.9951 + vertex 847.591 235.172 38.744 + vertex 848.713 238.142 40.8917 + endloop + endfacet + facet normal 0.451357 -0.647356 0.614171 + outer loop + vertex 848.713 238.142 40.8917 + vertex 848.136 240.643 43.9523 + vertex 846.877 237.909 41.9951 + endloop + endfacet + facet normal 0.5233 -0.597347 0.607728 + outer loop + vertex 847.591 235.172 38.744 + vertex 848.454 232.762 35.6321 + vertex 849.616 234.924 36.7561 + endloop + endfacet + facet normal 0.508031 -0.622504 0.59531 + outer loop + vertex 849.616 234.924 36.7561 + vertex 848.713 238.142 40.8917 + vertex 847.591 235.172 38.744 + endloop + endfacet + facet normal 0.530756 -0.60881 0.589617 + outer loop + vertex 848.713 238.142 40.8917 + vertex 849.616 234.924 36.7561 + vertex 851.251 238.508 38.9851 + endloop + endfacet + facet normal 0.518105 -0.640679 0.566655 + outer loop + vertex 851.251 238.508 38.9851 + vertex 850.618 241.113 42.5087 + vertex 848.713 238.142 40.8917 + endloop + endfacet + facet normal 0.550932 -0.620743 0.557811 + outer loop + vertex 851.251 238.508 38.9851 + vertex 854.625 242.565 40.1675 + vertex 850.618 241.113 42.5087 + endloop + endfacet + facet normal 0.52408 -0.597394 0.60701 + outer loop + vertex 848.454 232.762 35.6321 + vertex 850.196 230.943 32.3381 + vertex 849.616 234.924 36.7561 + endloop + endfacet + facet normal 0.579816 -0.566007 0.586045 + outer loop + vertex 851.113 232.884 33.3047 + vertex 849.616 234.924 36.7561 + vertex 850.196 230.943 32.3381 + endloop + endfacet + facet normal 0.562792 -0.566076 0.602348 + outer loop + vertex 852.315 230.479 29.922 + vertex 851.113 232.884 33.3047 + vertex 850.196 230.943 32.3381 + endloop + endfacet + facet normal 0.582714 -0.533009 0.613471 + outer loop + vertex 850.196 230.943 32.3381 + vertex 852.613 228.216 27.6718 + vertex 852.315 230.479 29.922 + endloop + endfacet + facet normal 0.55153 -0.563441 0.615101 + outer loop + vertex 852.613 228.216 27.6718 + vertex 850.196 230.943 32.3381 + vertex 849.589 226.46 28.775 + endloop + endfacet + facet normal 0.546982 -0.540329 0.639418 + outer loop + vertex 852.613 228.216 27.6718 + vertex 849.589 226.46 28.775 + vertex 853.198 226.729 25.9162 + endloop + endfacet + facet normal 0.553579 -0.535664 0.637663 + outer loop + vertex 854.165 227.037 25.3348 + vertex 852.613 228.216 27.6718 + vertex 853.198 226.729 25.9162 + endloop + endfacet + facet normal -0.296122 0.75931 -0.579448 + outer loop + vertex 854.165 227.037 25.3348 + vertex 854.233 226.973 25.2152 + vertex 852.613 228.216 27.6718 + endloop + endfacet + facet normal 0.572927 -0.514481 0.638016 + outer loop + vertex 853.934 228.094 26.3871 + vertex 852.613 228.216 27.6718 + vertex 854.233 226.973 25.2152 + endloop + endfacet + facet normal 0.549704 -0.532561 0.643587 + outer loop + vertex 852.056 225.29 25.7001 + vertex 853.198 226.729 25.9162 + vertex 849.589 226.46 28.775 + endloop + endfacet + facet normal 0.572943 -0.558061 0.600254 + outer loop + vertex 851.113 232.884 33.3047 + vertex 852.315 230.479 29.922 + vertex 853.565 233.187 31.2462 + endloop + endfacet + facet normal 0.563687 -0.582475 0.585645 + outer loop + vertex 853.565 233.187 31.2462 + vertex 852.324 235.821 35.0598 + vertex 851.113 232.884 33.3047 + endloop + endfacet + facet normal 0.576615 -0.572457 0.582931 + outer loop + vertex 853.565 233.187 31.2462 + vertex 856.893 237.409 32.1004 + vertex 852.324 235.821 35.0598 + endloop + endfacet + facet normal 0.572201 -0.595751 0.563619 + outer loop + vertex 852.324 235.821 35.0598 + vertex 856.893 237.409 32.1004 + vertex 855.558 240.055 36.252 + endloop + endfacet + facet normal 0.571844 -0.59562 0.56412 + outer loop + vertex 852.324 235.821 35.0598 + vertex 855.558 240.055 36.252 + vertex 851.251 238.508 38.9851 + endloop + endfacet + facet normal 0.556441 -0.60682 0.567576 + outer loop + vertex 852.324 235.821 35.0598 + vertex 851.251 238.508 38.9851 + vertex 849.616 234.924 36.7561 + endloop + endfacet + facet normal 0.592852 -0.579085 0.559632 + outer loop + vertex 856.893 237.409 32.1004 + vertex 861.729 242.985 32.7479 + vertex 855.558 240.055 36.252 + endloop + endfacet + facet normal 0.590338 -0.607547 0.531402 + outer loop + vertex 855.558 240.055 36.252 + vertex 861.729 242.985 32.7479 + vertex 860.453 245.387 36.9104 + endloop + endfacet + facet normal 0.590798 -0.607862 0.530529 + outer loop + vertex 855.558 240.055 36.252 + vertex 860.453 245.387 36.9104 + vertex 854.625 242.565 40.1675 + endloop + endfacet + facet normal 0.618118 -0.583918 0.526279 + outer loop + vertex 861.729 242.985 32.7479 + vertex 867.813 249.597 32.9375 + vertex 860.453 245.387 36.9104 + endloop + endfacet + facet normal 0.616778 -0.617128 0.488609 + outer loop + vertex 860.453 245.387 36.9104 + vertex 867.813 249.597 32.9375 + vertex 865.909 251.217 37.3872 + endloop + endfacet + facet normal 0.617391 -0.61759 0.487247 + outer loop + vertex 860.453 245.387 36.9104 + vertex 865.909 251.217 37.3872 + vertex 859.496 247.537 40.8491 + endloop + endfacet + facet normal 0.615026 -0.644519 0.454244 + outer loop + vertex 859.496 247.537 40.8491 + vertex 865.909 251.217 37.3872 + vertex 865.042 253.142 41.2922 + endloop + endfacet + facet normal 0.615942 -0.645245 0.451966 + outer loop + vertex 859.496 247.537 40.8491 + vertex 865.042 253.142 41.2922 + vertex 859.198 249.571 44.1585 + endloop + endfacet + facet normal 0.614233 -0.667955 0.420183 + outer loop + vertex 859.198 249.571 44.1585 + vertex 865.042 253.142 41.2922 + vertex 864.869 255.085 44.6341 + endloop + endfacet + facet normal 0.621769 -0.673887 0.399098 + outer loop + vertex 859.198 249.571 44.1585 + vertex 864.869 255.085 44.6341 + vertex 859.794 251.509 46.5029 + endloop + endfacet + facet normal 0.622284 -0.689724 0.370193 + outer loop + vertex 859.794 251.509 46.5029 + vertex 864.869 255.085 44.6341 + vertex 865.171 256.726 47.1826 + endloop + endfacet + facet normal 0.607769 -0.575009 0.547706 + outer loop + vertex 861.729 242.985 32.7479 + vertex 868.053 246.565 29.4874 + vertex 867.813 249.597 32.9375 + endloop + endfacet + facet normal 0.63491 -0.557842 0.534511 + outer loop + vertex 868.053 246.565 29.4874 + vertex 872.637 251.559 29.256 + vertex 867.813 249.597 32.9375 + endloop + endfacet + facet normal 0.636936 -0.547609 0.542621 + outer loop + vertex 872.637 251.559 29.256 + vertex 874.096 254.712 30.7249 + vertex 867.813 249.597 32.9375 + endloop + endfacet + facet normal 0.648155 -0.585467 0.486952 + outer loop + vertex 872.119 255.236 33.9853 + vertex 867.813 249.597 32.9375 + vertex 874.096 254.712 30.7249 + endloop + endfacet + facet normal 0.671701 -0.550611 0.495626 + outer loop + vertex 874.096 254.712 30.7249 + vertex 876.924 258.651 31.2682 + vertex 872.119 255.236 33.9853 + endloop + endfacet + facet normal 0.672304 -0.569629 0.472789 + outer loop + vertex 872.119 255.236 33.9853 + vertex 876.924 258.651 31.2682 + vertex 876.113 260.082 34.1458 + endloop + endfacet + facet normal 0.67907 -0.574672 0.456745 + outer loop + vertex 872.119 255.236 33.9853 + vertex 876.113 260.082 34.1458 + vertex 871.127 256.995 37.6741 + endloop + endfacet + facet normal 0.646211 -0.606577 0.463114 + outer loop + vertex 865.909 251.217 37.3872 + vertex 872.119 255.236 33.9853 + vertex 871.127 256.995 37.6741 + endloop + endfacet + facet normal 0.65292 -0.611811 0.446523 + outer loop + vertex 865.909 251.217 37.3872 + vertex 871.127 256.995 37.6741 + vertex 865.042 253.142 41.2922 + endloop + endfacet + facet normal 0.651681 -0.623325 0.432179 + outer loop + vertex 865.042 253.142 41.2922 + vertex 871.127 256.995 37.6741 + vertex 870.603 259.102 41.5033 + endloop + endfacet + facet normal 0.662378 -0.632234 0.401915 + outer loop + vertex 865.042 253.142 41.2922 + vertex 870.603 259.102 41.5033 + vertex 864.869 255.085 44.6341 + endloop + endfacet + facet normal 0.661741 -0.639231 0.391769 + outer loop + vertex 864.869 255.085 44.6341 + vertex 870.603 259.102 41.5033 + vertex 870.315 260.955 45.0128 + endloop + endfacet + facet normal 0.67869 -0.651547 0.338921 + outer loop + vertex 864.869 255.085 44.6341 + vertex 870.315 260.955 45.0128 + vertex 865.171 256.726 47.1826 + endloop + endfacet + facet normal 0.678695 -0.652914 0.336269 + outer loop + vertex 865.171 256.726 47.1826 + vertex 870.315 260.955 45.0128 + vertex 870.388 262.425 47.7207 + endloop + endfacet + facet normal 0.680003 -0.567277 0.464534 + outer loop + vertex 876.576 263.185 37.2579 + vertex 871.127 256.995 37.6741 + vertex 876.113 260.082 34.1458 + endloop + endfacet + facet normal 0.70796 -0.549956 0.443104 + outer loop + vertex 879.265 263.758 33.6713 + vertex 876.576 263.185 37.2579 + vertex 876.113 260.082 34.1458 + endloop + endfacet + facet normal 0.702256 -0.542797 0.460661 + outer loop + vertex 876.113 260.082 34.1458 + vertex 879.722 262.418 31.3951 + vertex 879.265 263.758 33.6713 + endloop + endfacet + facet normal 0.728714 -0.516025 0.450217 + outer loop + vertex 879.722 262.418 31.3951 + vertex 882.081 265.943 31.6168 + vertex 879.265 263.758 33.6713 + endloop + endfacet + facet normal 0.728665 -0.517705 0.448362 + outer loop + vertex 879.265 263.758 33.6713 + vertex 882.081 265.943 31.6168 + vertex 881.212 267.074 34.3363 + endloop + endfacet + facet normal 0.748179 -0.492817 0.444252 + outer loop + vertex 882.081 265.943 31.6168 + vertex 884.203 269.578 32.0763 + vertex 881.212 267.074 34.3363 + endloop + endfacet + facet normal 0.748132 -0.499992 0.436241 + outer loop + vertex 881.212 267.074 34.3363 + vertex 884.203 269.578 32.0763 + vertex 883.343 270.169 34.2284 + endloop + endfacet + facet normal 0.751913 -0.502945 0.426232 + outer loop + vertex 883.343 270.169 34.2284 + vertex 881.319 269.793 37.3558 + vertex 881.212 267.074 34.3363 + endloop + endfacet + facet normal 0.723184 -0.525789 0.44783 + outer loop + vertex 881.319 269.793 37.3558 + vertex 876.576 263.185 37.2579 + vertex 881.212 267.074 34.3363 + endloop + endfacet + facet normal 0.767418 -0.465622 0.440757 + outer loop + vertex 883.343 270.169 34.2284 + vertex 886.433 274.249 33.1584 + vertex 881.319 269.793 37.3558 + endloop + endfacet + facet normal 0.767143 -0.484898 0.419959 + outer loop + vertex 881.319 269.793 37.3558 + vertex 886.433 274.249 33.1584 + vertex 885.333 276.675 37.9695 + endloop + endfacet + facet normal 0.782894 -0.490739 0.382429 + outer loop + vertex 881.319 269.793 37.3558 + vertex 885.333 276.675 37.9695 + vertex 880.307 271.822 42.0319 + endloop + endfacet + facet normal 0.782727 -0.495946 0.376001 + outer loop + vertex 880.307 271.822 42.0319 + vertex 885.333 276.675 37.9695 + vertex 884.416 278.575 42.3849 + endloop + endfacet + facet normal 0.7963 -0.502179 0.337228 + outer loop + vertex 880.307 271.822 42.0319 + vertex 884.416 278.575 42.3849 + vertex 879.866 273.543 45.6361 + endloop + endfacet + facet normal 0.796314 -0.503162 0.335726 + outer loop + vertex 879.866 273.543 45.6361 + vertex 884.416 278.575 42.3849 + vertex 883.925 280.126 45.8729 + endloop + endfacet + facet normal 0.813716 -0.511733 0.275673 + outer loop + vertex 879.866 273.543 45.6361 + vertex 883.925 280.126 45.8729 + vertex 880.008 275.094 48.0942 + endloop + endfacet + facet normal 0.8133 -0.507388 0.284783 + outer loop + vertex 880.008 275.094 48.0942 + vertex 883.925 280.126 45.8729 + vertex 883.834 281.37 48.3492 + endloop + endfacet + facet normal 0.768837 -0.468018 0.435718 + outer loop + vertex 883.343 270.169 34.2284 + vertex 884.203 269.578 32.0763 + vertex 886.433 274.249 33.1584 + endloop + endfacet + facet normal 0.753962 -0.467005 0.462004 + outer loop + vertex 884.203 269.578 32.0763 + vertex 887.005 271.983 29.9342 + vertex 886.433 274.249 33.1584 + endloop + endfacet + facet normal 0.770591 -0.449009 0.452305 + outer loop + vertex 889.072 275.371 29.7765 + vertex 886.433 274.249 33.1584 + vertex 887.005 271.983 29.9342 + endloop + endfacet + facet normal 0.777758 -0.420216 0.467452 + outer loop + vertex 889.072 275.371 29.7765 + vertex 890.614 278.889 30.3734 + vertex 886.433 274.249 33.1584 + endloop + endfacet + facet normal 0.779219 -0.42639 0.459358 + outer loop + vertex 890.346 281.76 33.4928 + vertex 886.433 274.249 33.1584 + vertex 890.614 278.889 30.3734 + endloop + endfacet + facet normal 0.801328 -0.404295 0.44093 + outer loop + vertex 892.753 282.812 30.0828 + vertex 890.346 281.76 33.4928 + vertex 890.614 278.889 30.3734 + endloop + endfacet + facet normal 0.809289 -0.368201 0.457689 + outer loop + vertex 892.753 282.812 30.0828 + vertex 894.167 286.56 30.599 + vertex 890.346 281.76 33.4928 + endloop + endfacet + facet normal 0.811053 -0.374729 0.449189 + outer loop + vertex 893.778 289.435 33.7 + vertex 890.346 281.76 33.4928 + vertex 894.167 286.56 30.599 + endloop + endfacet + facet normal 0.835111 -0.347188 0.426673 + outer loop + vertex 896.06 290.673 30.2399 + vertex 893.778 289.435 33.7 + vertex 894.167 286.56 30.599 + endloop + endfacet + facet normal 0.840888 -0.309538 0.443952 + outer loop + vertex 896.06 290.673 30.2399 + vertex 897.228 294.55 30.7304 + vertex 893.778 289.435 33.7 + endloop + endfacet + facet normal 0.843309 -0.316931 0.434033 + outer loop + vertex 896.69 297.34 33.8137 + vertex 893.778 289.435 33.7 + vertex 897.228 294.55 30.7304 + endloop + endfacet + facet normal 0.864968 -0.287578 0.411254 + outer loop + vertex 898.813 298.78 30.3548 + vertex 896.69 297.34 33.8137 + vertex 897.228 294.55 30.7304 + endloop + endfacet + facet normal 0.868135 -0.249554 0.429028 + outer loop + vertex 898.813 298.78 30.3548 + vertex 899.688 302.643 30.8314 + vertex 896.69 297.34 33.8137 + endloop + endfacet + facet normal 0.870045 -0.254464 0.42222 + outer loop + vertex 898.999 305.375 33.8967 + vertex 896.69 297.34 33.8137 + vertex 899.688 302.643 30.8314 + endloop + endfacet + facet normal 0.889428 -0.223312 0.39881 + outer loop + vertex 900.919 306.867 30.4501 + vertex 898.999 305.375 33.8967 + vertex 899.688 302.643 30.8314 + endloop + endfacet + facet normal 0.89039 -0.181137 0.417606 + outer loop + vertex 900.919 306.867 30.4501 + vertex 901.489 310.759 30.924 + vertex 898.999 305.375 33.8967 + endloop + endfacet + facet normal 0.892904 -0.186642 0.40974 + outer loop + vertex 900.68 313.575 33.97 + vertex 898.999 305.375 33.8967 + vertex 901.489 310.759 30.924 + endloop + endfacet + facet normal 0.910899 -0.152846 0.383278 + outer loop + vertex 902.376 315.081 30.5392 + vertex 900.68 313.575 33.97 + vertex 901.489 310.759 30.924 + endloop + endfacet + facet normal 0.909416 -0.111652 0.400621 + outer loop + vertex 902.376 315.081 30.5392 + vertex 902.666 319.125 31.0073 + vertex 900.68 313.575 33.97 + endloop + endfacet + facet normal 0.912104 -0.116681 0.393003 + outer loop + vertex 901.732 322.024 34.0359 + vertex 900.68 313.575 33.97 + vertex 902.666 319.125 31.0073 + endloop + endfacet + facet normal 0.926865 -0.0836668 0.365952 + outer loop + vertex 903.224 323.613 30.6207 + vertex 901.732 322.024 34.0359 + vertex 902.666 319.125 31.0073 + endloop + endfacet + facet normal 0.923142 -0.0464574 0.381642 + outer loop + vertex 903.224 323.613 30.6207 + vertex 903.243 327.768 31.0815 + vertex 901.732 322.024 34.0359 + endloop + endfacet + facet normal 0.926712 -0.0522948 0.372117 + outer loop + vertex 902.195 330.663 34.0966 + vertex 901.732 322.024 34.0359 + vertex 903.243 327.768 31.0815 + endloop + endfacet + facet normal 0.937942 -0.0211766 0.346146 + outer loop + vertex 903.49 332.344 30.6921 + vertex 902.195 330.663 34.0966 + vertex 903.243 327.768 31.0815 + endloop + endfacet + facet normal 0.933005 0.0101138 0.359721 + outer loop + vertex 903.49 332.344 30.6921 + vertex 903.268 336.516 31.1511 + vertex 902.195 330.663 34.0966 + endloop + endfacet + facet normal 0.936643 0.00468319 0.350253 + outer loop + vertex 902.132 339.367 34.1506 + vertex 902.195 330.663 34.0966 + vertex 903.268 336.516 31.1511 + endloop + endfacet + facet normal 0.944398 0.0319775 0.327245 + outer loop + vertex 903.25 341.088 30.7548 + vertex 902.132 339.367 34.1506 + vertex 903.268 336.516 31.1511 + endloop + endfacet + facet normal 0.938945 0.0587489 0.339014 + outer loop + vertex 903.25 341.088 30.7548 + vertex 902.826 345.247 31.2087 + vertex 902.132 339.367 34.1506 + endloop + endfacet + facet normal 0.942568 0.0536503 0.329678 + outer loop + vertex 901.621 348.078 34.194 + vertex 902.132 339.367 34.1506 + vertex 902.826 345.247 31.2087 + endloop + endfacet + facet normal 0.947789 0.0772622 0.309398 + outer loop + vertex 902.582 349.824 30.8147 + vertex 901.621 348.078 34.194 + vertex 902.826 345.247 31.2087 + endloop + endfacet + facet normal 0.942288 0.0999276 0.319544 + outer loop + vertex 902.582 349.824 30.8147 + vertex 901.994 353.978 31.2497 + vertex 901.621 348.078 34.194 + endloop + endfacet + facet normal 0.944874 0.0964517 0.312906 + outer loop + vertex 900.719 356.809 34.2243 + vertex 901.621 348.078 34.194 + vertex 901.994 353.978 31.2497 + endloop + endfacet + facet normal 0.948153 0.115672 0.296018 + outer loop + vertex 901.563 358.558 30.8398 + vertex 900.719 356.809 34.2243 + vertex 901.994 353.978 31.2497 + endloop + endfacet + facet normal 0.942442 0.136375 0.305294 + outer loop + vertex 901.563 358.558 30.8398 + vertex 900.81 362.777 31.2803 + vertex 900.719 356.809 34.2243 + endloop + endfacet + facet normal 0.944646 0.133568 0.299672 + outer loop + vertex 899.448 365.708 34.2665 + vertex 900.719 356.809 34.2243 + vertex 900.81 362.777 31.2803 + endloop + endfacet + facet normal 0.946972 0.15099 0.28363 + outer loop + vertex 900.161 367.522 30.9176 + vertex 899.448 365.708 34.2665 + vertex 900.81 362.777 31.2803 + endloop + endfacet + facet normal 0.941767 0.167602 0.29152 + outer loop + vertex 900.161 367.522 30.9176 + vertex 899.215 371.919 31.4478 + vertex 899.448 365.708 34.2665 + endloop + endfacet + facet normal 0.944961 0.163926 0.283157 + outer loop + vertex 897.867 374.855 34.2455 + vertex 899.448 365.708 34.2665 + vertex 899.215 371.919 31.4478 + endloop + endfacet + facet normal 0.946471 0.177589 0.269546 + outer loop + vertex 898.455 376.269 31.2518 + vertex 897.867 374.855 34.2455 + vertex 899.215 371.919 31.4478 + endloop + endfacet + facet normal 0.94497 0.18246 0.271552 + outer loop + vertex 898.455 376.269 31.2518 + vertex 897.625 382.076 30.2371 + vertex 897.867 374.855 34.2455 + endloop + endfacet + facet normal 0.941519 0.18715 0.280209 + outer loop + vertex 897.867 374.855 34.2455 + vertex 897.625 382.076 30.2371 + vertex 895.959 383.885 34.6261 + endloop + endfacet + facet normal 0.952815 0.191417 0.235591 + outer loop + vertex 897.867 374.855 34.2455 + vertex 895.959 383.885 34.6261 + vertex 896.446 376.12 38.9658 + endloop + endfacet + facet normal 0.955653 0.165986 0.24326 + outer loop + vertex 898.011 367.233 38.8807 + vertex 897.867 374.855 34.2455 + vertex 896.446 376.12 38.9658 + endloop + endfacet + facet normal 0.961999 0.167367 0.215746 + outer loop + vertex 898.011 367.233 38.8807 + vertex 896.446 376.12 38.9658 + vertex 896.896 368.289 43.0356 + endloop + endfacet + facet normal 0.964876 0.136777 0.22429 + outer loop + vertex 898.131 359.588 43.0264 + vertex 898.011 367.233 38.8807 + vertex 896.896 368.289 43.0356 + endloop + endfacet + facet normal 0.970079 0.137542 0.200075 + outer loop + vertex 898.131 359.588 43.0264 + vertex 896.896 368.289 43.0356 + vertex 897.277 360.777 46.349 + endloop + endfacet + facet normal 0.971653 0.102618 0.212979 + outer loop + vertex 898.19 352.151 46.344 + vertex 898.131 359.588 43.0264 + vertex 897.277 360.777 46.349 + endloop + endfacet + facet normal 0.97964 0.103486 0.172036 + outer loop + vertex 898.19 352.151 46.344 + vertex 897.277 360.777 46.349 + vertex 897.614 353.744 48.6613 + endloop + endfacet + facet normal 0.978194 0.0674999 0.196419 + outer loop + vertex 898.203 345.237 48.6549 + vertex 898.19 352.151 46.344 + vertex 897.614 353.744 48.6613 + endloop + endfacet + facet normal 0.982809 0.0601953 0.174539 + outer loop + vertex 898.718 343.519 46.3429 + vertex 898.19 352.151 46.344 + vertex 898.203 345.237 48.6549 + endloop + endfacet + facet normal 0.97882 0.0196479 0.20378 + outer loop + vertex 898.361 336.207 48.7653 + vertex 898.718 343.519 46.3429 + vertex 898.203 345.237 48.6549 + endloop + endfacet + facet normal 0.983845 0.0110866 0.17868 + outer loop + vertex 898.82 334.915 46.3166 + vertex 898.718 343.519 46.3429 + vertex 898.361 336.207 48.7653 + endloop + endfacet + facet normal 0.972134 0.0107781 0.234178 + outer loop + vertex 898.82 334.915 46.3166 + vertex 899.541 342.35 42.9838 + vertex 898.718 343.519 46.3429 + endloop + endfacet + facet normal 0.973451 0.00821645 0.228748 + outer loop + vertex 899.62 333.8 42.9543 + vertex 899.541 342.35 42.9838 + vertex 898.82 334.915 46.3166 + endloop + endfacet + facet normal 0.965175 0.00802686 0.261483 + outer loop + vertex 899.62 333.8 42.9543 + vertex 900.684 341.072 38.8022 + vertex 899.541 342.35 42.9838 + endloop + endfacet + facet normal 0.965799 0.00663666 0.259208 + outer loop + vertex 900.754 332.449 38.7629 + vertex 900.684 341.072 38.8022 + vertex 899.62 333.8 42.9543 + endloop + endfacet + facet normal 0.955472 0.00638963 0.295011 + outer loop + vertex 900.754 332.449 38.7629 + vertex 902.132 339.367 34.1506 + vertex 900.684 341.072 38.8022 + endloop + endfacet + facet normal 0.955992 0.00517792 0.293349 + outer loop + vertex 902.195 330.663 34.0966 + vertex 902.132 339.367 34.1506 + vertex 900.754 332.449 38.7629 + endloop + endfacet + facet normal 0.973029 0.0595904 0.222853 + outer loop + vertex 898.718 343.519 46.3429 + vertex 899.028 350.948 43.0036 + vertex 898.19 352.151 46.344 + endloop + endfacet + facet normal 0.974161 0.0575423 0.218402 + outer loop + vertex 899.541 342.35 42.9838 + vertex 899.028 350.948 43.0036 + vertex 898.718 343.519 46.3429 + endloop + endfacet + facet normal 0.967114 0.0570544 0.247862 + outer loop + vertex 899.541 342.35 42.9838 + vertex 900.171 349.713 38.8283 + vertex 899.028 350.948 43.0036 + endloop + endfacet + facet normal 0.966826 0.099808 0.235129 + outer loop + vertex 900.171 349.713 38.8283 + vertex 899.267 358.41 38.8526 + vertex 899.028 350.948 43.0036 + endloop + endfacet + facet normal 0.966853 0.0997567 0.235039 + outer loop + vertex 899.028 350.948 43.0036 + vertex 899.267 358.41 38.8526 + vertex 898.131 359.588 43.0264 + endloop + endfacet + facet normal 0.958732 0.0988791 0.266561 + outer loop + vertex 900.171 349.713 38.8283 + vertex 900.719 356.809 34.2243 + vertex 899.267 358.41 38.8526 + endloop + endfacet + facet normal 0.957767 0.135662 0.25353 + outer loop + vertex 900.719 356.809 34.2243 + vertex 899.448 365.708 34.2665 + vertex 899.267 358.41 38.8526 + endloop + endfacet + facet normal 0.957819 0.13557 0.253386 + outer loop + vertex 899.267 358.41 38.8526 + vertex 899.448 365.708 34.2665 + vertex 898.011 367.233 38.8807 + endloop + endfacet + facet normal 0.959138 0.0980889 0.265392 + outer loop + vertex 901.621 348.078 34.194 + vertex 900.719 356.809 34.2243 + vertex 900.171 349.713 38.8283 + endloop + endfacet + facet normal 0.958368 0.056037 0.279983 + outer loop + vertex 900.684 341.072 38.8022 + vertex 901.621 348.078 34.194 + vertex 900.171 349.713 38.8283 + endloop + endfacet + facet normal 0.958922 0.0548655 0.278314 + outer loop + vertex 902.132 339.367 34.1506 + vertex 901.621 348.078 34.194 + vertex 900.684 341.072 38.8022 + endloop + endfacet + facet normal 0.967305 0.0566664 0.247203 + outer loop + vertex 900.684 341.072 38.8022 + vertex 900.171 349.713 38.8283 + vertex 899.541 342.35 42.9838 + endloop + endfacet + facet normal 0.976492 0.108089 0.186492 + outer loop + vertex 897.614 353.744 48.6613 + vertex 897.277 360.777 46.349 + vertex 896.628 362.477 48.7628 + endloop + endfacet + facet normal 0.976498 0.138976 0.164735 + outer loop + vertex 897.277 360.777 46.349 + vertex 896.045 369.442 46.3456 + vertex 896.628 362.477 48.7628 + endloop + endfacet + facet normal 0.972988 0.144104 0.180357 + outer loop + vertex 896.628 362.477 48.7628 + vertex 896.045 369.442 46.3456 + vertex 895.335 371.373 48.6326 + endloop + endfacet + facet normal 0.972657 0.169325 0.15896 + outer loop + vertex 896.045 369.442 46.3456 + vertex 894.563 377.964 46.3349 + vertex 895.335 371.373 48.6326 + endloop + endfacet + facet normal 0.969315 0.174038 0.173604 + outer loop + vertex 895.335 371.373 48.6326 + vertex 894.563 377.964 46.3349 + vertex 893.86 379.561 48.6614 + endloop + endfacet + facet normal 0.967779 0.196015 0.15806 + outer loop + vertex 894.563 377.964 46.3349 + vertex 892.868 386.322 46.3473 + vertex 893.86 379.561 48.6614 + endloop + endfacet + facet normal 0.964954 0.199751 0.170187 + outer loop + vertex 893.86 379.561 48.6614 + vertex 892.868 386.322 46.3473 + vertex 892.192 387.577 48.706 + endloop + endfacet + facet normal 0.962718 0.218379 0.15964 + outer loop + vertex 892.868 386.322 46.3473 + vertex 890.969 394.681 46.3677 + vertex 892.192 387.577 48.706 + endloop + endfacet + facet normal 0.961017 0.220463 0.166862 + outer loop + vertex 892.192 387.577 48.706 + vertex 890.969 394.681 46.3677 + vertex 890.328 395.609 48.8307 + endloop + endfacet + facet normal 0.958226 0.237183 0.159838 + outer loop + vertex 890.969 394.681 46.3677 + vertex 888.884 403.114 46.3488 + vertex 890.328 395.609 48.8307 + endloop + endfacet + facet normal 0.956732 0.238946 0.166038 + outer loop + vertex 890.328 395.609 48.8307 + vertex 888.884 403.114 46.3488 + vertex 888.181 404.324 48.659 + endloop + endfacet + facet normal 0.962999 0.239648 0.123297 + outer loop + vertex 890.328 395.609 48.8307 + vertex 888.181 404.324 48.659 + vertex 889.383 398.987 49.6457 + endloop + endfacet + facet normal 0.962009 0.236 0.13727 + outer loop + vertex 889.383 398.987 49.6457 + vertex 890.283 395.281 49.7133 + vertex 890.328 395.609 48.8307 + endloop + endfacet + facet normal 0.965988 0.222166 0.132325 + outer loop + vertex 890.283 395.281 49.7133 + vertex 890.972 392.231 49.8018 + vertex 890.328 395.609 48.8307 + endloop + endfacet + facet normal 0.965466 0.222832 0.134988 + outer loop + vertex 890.972 392.231 49.8018 + vertex 891.617 389.553 49.609 + vertex 890.328 395.609 48.8307 + endloop + endfacet + facet normal 0.966373 0.22229 0.129265 + outer loop + vertex 892.192 387.577 48.706 + vertex 890.328 395.609 48.8307 + vertex 891.617 389.553 49.609 + endloop + endfacet + facet normal 0.950926 0.221201 0.216357 + outer loop + vertex 890.972 392.231 49.8018 + vertex 890.283 395.281 49.7133 + vertex 890.412 394.182 50.2672 + endloop + endfacet + facet normal 0.954405 0.253436 0.15774 + outer loop + vertex 888.884 403.114 46.3488 + vertex 886.695 411.379 46.3202 + vertex 888.181 404.324 48.659 + endloop + endfacet + facet normal 0.952638 0.255465 0.164982 + outer loop + vertex 888.181 404.324 48.659 + vertex 886.695 411.379 46.3202 + vertex 886.076 412.177 48.6578 + endloop + endfacet + facet normal 0.95696 0.256619 0.13555 + outer loop + vertex 888.181 404.324 48.659 + vertex 886.076 412.177 48.6578 + vertex 887.416 406.675 49.6111 + endloop + endfacet + facet normal 0.956551 0.251962 0.146718 + outer loop + vertex 887.416 406.675 49.6111 + vertex 888.411 402.884 49.6334 + vertex 888.181 404.324 48.659 + endloop + endfacet + facet normal 0.962166 0.24038 0.128274 + outer loop + vertex 888.411 402.884 49.6334 + vertex 889.383 398.987 49.6457 + vertex 888.181 404.324 48.659 + endloop + endfacet + facet normal 0.949805 0.237536 0.203588 + outer loop + vertex 889.383 398.987 49.6457 + vertex 888.411 402.884 49.6334 + vertex 888.632 401.437 50.2899 + endloop + endfacet + facet normal 0.940873 0.248337 0.230407 + outer loop + vertex 888.411 402.884 49.6334 + vertex 887.416 406.675 49.6111 + vertex 888.632 401.437 50.2899 + endloop + endfacet + facet normal 0.944357 0.24738 0.216779 + outer loop + vertex 886.659 408.904 50.3644 + vertex 888.632 401.437 50.2899 + vertex 887.416 406.675 49.6111 + endloop + endfacet + facet normal 0.956956 0.256622 0.135571 + outer loop + vertex 886.414 410.399 49.6365 + vertex 887.416 406.675 49.6111 + vertex 886.076 412.177 48.6578 + endloop + endfacet + facet normal 0.951385 0.266209 0.154918 + outer loop + vertex 885.382 414.083 49.6422 + vertex 886.414 410.399 49.6365 + vertex 886.076 412.177 48.6578 + endloop + endfacet + facet normal 0.951482 0.270602 0.146479 + outer loop + vertex 886.076 412.177 48.6578 + vertex 883.823 420.013 48.8155 + vertex 885.382 414.083 49.6422 + endloop + endfacet + facet normal 0.953653 0.269432 0.133989 + outer loop + vertex 884.428 417.427 49.7075 + vertex 885.382 414.083 49.6422 + vertex 883.823 420.013 48.8155 + endloop + endfacet + facet normal 0.948015 0.276333 0.157821 + outer loop + vertex 883.661 420.013 49.7865 + vertex 884.428 417.427 49.7075 + vertex 883.823 420.013 48.8155 + endloop + endfacet + facet normal 0.947574 0.277882 0.157747 + outer loop + vertex 882.705 423.39 49.5844 + vertex 883.661 420.013 49.7865 + vertex 883.823 420.013 48.8155 + endloop + endfacet + facet normal 0.948458 0.280526 0.147422 + outer loop + vertex 883.823 420.013 48.8155 + vertex 881.458 428.071 48.6979 + vertex 882.705 423.39 49.5844 + endloop + endfacet + facet normal 0.946197 0.282045 0.158626 + outer loop + vertex 881.886 426.082 49.678 + vertex 882.705 423.39 49.5844 + vertex 881.458 428.071 48.6979 + endloop + endfacet + facet normal 0.943479 0.285906 0.167648 + outer loop + vertex 880.737 429.89 49.6543 + vertex 881.886 426.082 49.678 + vertex 881.458 428.071 48.6979 + endloop + endfacet + facet normal 0.943501 0.286681 0.166192 + outer loop + vertex 881.458 428.071 48.6979 + vertex 878.971 436.279 48.6601 + vertex 880.737 429.89 49.6543 + endloop + endfacet + facet normal 0.942627 0.287092 0.170387 + outer loop + vertex 879.19 434.923 49.7284 + vertex 880.737 429.89 49.6543 + vertex 878.971 436.279 48.6601 + endloop + endfacet + facet normal 0.941605 0.288925 0.172922 + outer loop + vertex 877.871 439.346 49.5216 + vertex 879.19 434.923 49.7284 + vertex 878.971 436.279 48.6601 + endloop + endfacet + facet normal 0.942078 0.290657 0.167356 + outer loop + vertex 878.971 436.279 48.6601 + vertex 876.436 444.494 48.657 + vertex 877.871 439.346 49.5216 + endloop + endfacet + facet normal 0.940634 0.291383 0.174076 + outer loop + vertex 876.688 443.056 49.7079 + vertex 877.871 439.346 49.5216 + vertex 876.436 444.494 48.657 + endloop + endfacet + facet normal 0.939768 0.292847 0.176286 + outer loop + vertex 875.411 447.255 49.5354 + vertex 876.688 443.056 49.7079 + vertex 876.436 444.494 48.657 + endloop + endfacet + facet normal 0.94028 0.295192 0.169512 + outer loop + vertex 876.436 444.494 48.657 + vertex 874.004 452.223 48.6899 + vertex 875.411 447.255 49.5354 + endloop + endfacet + facet normal 0.938549 0.296049 0.177428 + outer loop + vertex 874.276 450.729 49.7411 + vertex 875.411 447.255 49.5354 + vertex 874.004 452.223 48.6899 + endloop + endfacet + facet normal 0.936931 0.29866 0.181556 + outer loop + vertex 873.003 454.815 49.593 + vertex 874.276 450.729 49.7411 + vertex 874.004 452.223 48.6899 + endloop + endfacet + facet normal 0.937424 0.301309 0.174498 + outer loop + vertex 874.004 452.223 48.6899 + vertex 871.639 459.531 48.7734 + vertex 873.003 454.815 49.593 + endloop + endfacet + facet normal 0.933686 0.303054 0.190756 + outer loop + vertex 871.852 458.203 49.8444 + vertex 873.003 454.815 49.593 + vertex 871.639 459.531 48.7734 + endloop + endfacet + facet normal 0.931685 0.306344 0.195233 + outer loop + vertex 870.562 462.222 49.6925 + vertex 871.852 458.203 49.8444 + vertex 871.639 459.531 48.7734 + endloop + endfacet + facet normal 0.93051 0.301549 0.207894 + outer loop + vertex 871.639 459.531 48.7734 + vertex 869.562 466.01 48.6738 + vertex 870.562 462.222 49.6925 + endloop + endfacet + facet normal 0.925866 0.304558 0.223644 + outer loop + vertex 869.147 466.452 49.7882 + vertex 870.562 462.222 49.6925 + vertex 869.562 466.01 48.6738 + endloop + endfacet + facet normal 0.930897 0.279133 0.235616 + outer loop + vertex 869.562 466.01 48.6738 + vertex 868.043 471.031 48.729 + vertex 869.147 466.452 49.7882 + endloop + endfacet + facet normal 0.898322 0.292584 0.327739 + outer loop + vertex 868.038 469.943 49.7133 + vertex 869.147 466.452 49.7882 + vertex 868.043 471.031 48.729 + endloop + endfacet + facet normal 0.943697 0.219644 0.247372 + outer loop + vertex 867.25 473.767 49.3227 + vertex 868.038 469.943 49.7133 + vertex 868.043 471.031 48.729 + endloop + endfacet + facet normal 0.908738 0.181667 0.375756 + outer loop + vertex 867.25 473.767 49.3227 + vertex 868.043 471.031 48.729 + vertex 867.255 478.642 46.9553 + endloop + endfacet + facet normal 0.980954 0.0841343 0.175076 + outer loop + vertex 866.796 477.577 50.0365 + vertex 867.25 473.767 49.3227 + vertex 867.255 478.642 46.9553 + endloop + endfacet + facet normal 0.98089 0.0840527 0.17547 + outer loop + vertex 867.25 473.767 49.3227 + vertex 866.796 477.577 50.0365 + vertex 866.766 477.509 50.2382 + endloop + endfacet + facet normal 0.964391 0.150539 0.217459 + outer loop + vertex 868.043 471.031 48.729 + vertex 868.385 472.079 46.4847 + vertex 867.255 478.642 46.9553 + endloop + endfacet + facet normal 0.968405 0.152685 0.197177 + outer loop + vertex 867.823 480.089 43.0417 + vertex 867.255 478.642 46.9553 + vertex 868.385 472.079 46.4847 + endloop + endfacet + facet normal 0.965752 0.156653 0.206842 + outer loop + vertex 868.385 472.079 46.4847 + vertex 868.966 472.889 43.1603 + vertex 867.823 480.089 43.0417 + endloop + endfacet + facet normal 0.967196 0.156768 0.199889 + outer loop + vertex 868.966 472.889 43.1603 + vertex 868.411 481.779 38.8735 + vertex 867.823 480.089 43.0417 + endloop + endfacet + facet normal 0.96726 0.156662 0.199662 + outer loop + vertex 869.591 474.151 39.1431 + vertex 868.411 481.779 38.8735 + vertex 868.966 472.889 43.1603 + endloop + endfacet + facet normal 0.939267 0.257412 0.226972 + outer loop + vertex 870.916 465.762 43.1711 + vertex 869.591 474.151 39.1431 + vertex 868.966 472.889 43.1603 + endloop + endfacet + facet normal 0.941903 0.258115 0.214929 + outer loop + vertex 870.916 465.762 43.1711 + vertex 868.966 472.889 43.1603 + vertex 870.224 465.512 46.5038 + endloop + endfacet + facet normal 0.930867 0.295101 0.21541 + outer loop + vertex 872.461 458.515 46.4243 + vertex 870.916 465.762 43.1711 + vertex 870.224 465.512 46.5038 + endloop + endfacet + facet normal 0.934223 0.296365 0.198483 + outer loop + vertex 872.461 458.515 46.4243 + vertex 870.224 465.512 46.5038 + vertex 871.639 459.531 48.7734 + endloop + endfacet + facet normal 0.93546 0.290043 0.201964 + outer loop + vertex 873.189 458.493 43.0823 + vertex 870.916 465.762 43.1711 + vertex 872.461 458.515 46.4243 + endloop + endfacet + facet normal 0.933924 0.295202 0.201595 + outer loop + vertex 874.824 451.095 46.3426 + vertex 873.189 458.493 43.0823 + vertex 872.461 458.515 46.4243 + endloop + endfacet + facet normal 0.93701 0.296369 0.184873 + outer loop + vertex 874.824 451.095 46.3426 + vertex 872.461 458.515 46.4243 + vertex 874.004 452.223 48.6899 + endloop + endfacet + facet normal 0.937217 0.291475 0.191486 + outer loop + vertex 875.541 450.946 43.0593 + vertex 873.189 458.493 43.0823 + vertex 874.824 451.095 46.3426 + endloop + endfacet + facet normal 0.937238 0.291403 0.191494 + outer loop + vertex 877.246 443.311 46.3336 + vertex 875.541 450.946 43.0593 + vertex 874.824 451.095 46.3426 + endloop + endfacet + facet normal 0.939548 0.292137 0.178621 + outer loop + vertex 877.246 443.311 46.3336 + vertex 874.824 451.095 46.3426 + vertex 876.436 444.494 48.657 + endloop + endfacet + facet normal 0.939161 0.289188 0.185329 + outer loop + vertex 877.935 443.158 43.0786 + vertex 875.541 450.946 43.0593 + vertex 877.246 443.311 46.3336 + endloop + endfacet + facet normal 0.93948 0.288073 0.185449 + outer loop + vertex 879.694 435.316 46.3526 + vertex 877.935 443.158 43.0786 + vertex 877.246 443.311 46.3336 + endloop + endfacet + facet normal 0.941382 0.288629 0.174624 + outer loop + vertex 879.694 435.316 46.3526 + vertex 877.246 443.311 46.3336 + vertex 878.971 436.279 48.6601 + endloop + endfacet + facet normal 0.940663 0.286703 0.181534 + outer loop + vertex 880.351 435.225 43.0908 + vertex 877.935 443.158 43.0786 + vertex 879.694 435.316 46.3526 + endloop + endfacet + facet normal 0.941459 0.283925 0.181771 + outer loop + vertex 882.105 427.311 46.3692 + vertex 880.351 435.225 43.0908 + vertex 879.694 435.316 46.3526 + endloop + endfacet + facet normal 0.943601 0.284545 0.169268 + outer loop + vertex 882.105 427.311 46.3692 + vertex 879.694 435.316 46.3526 + vertex 881.458 428.071 48.6979 + endloop + endfacet + facet normal 0.942371 0.282852 0.178692 + outer loop + vertex 882.752 427.23 43.0856 + vertex 880.351 435.225 43.0908 + vertex 882.105 427.311 46.3692 + endloop + endfacet + facet normal 0.943988 0.277111 0.179153 + outer loop + vertex 884.441 419.365 46.3487 + vertex 882.752 427.23 43.0856 + vertex 882.105 427.311 46.3692 + endloop + endfacet + facet normal 0.946469 0.277879 0.164252 + outer loop + vertex 884.441 419.365 46.3487 + vertex 882.105 427.311 46.3692 + vertex 883.823 420.013 48.8155 + endloop + endfacet + facet normal 0.944746 0.276195 0.176552 + outer loop + vertex 885.113 419.169 43.0589 + vertex 882.752 427.23 43.0856 + vertex 884.441 419.365 46.3487 + endloop + endfacet + facet normal 0.947282 0.26665 0.177638 + outer loop + vertex 886.695 411.379 46.3202 + vertex 885.113 419.169 43.0589 + vertex 884.441 419.365 46.3487 + endloop + endfacet + facet normal 0.947889 0.265889 0.175525 + outer loop + vertex 887.415 410.961 43.0591 + vertex 885.113 419.169 43.0589 + vertex 886.695 411.379 46.3202 + endloop + endfacet + facet normal 0.944527 0.264946 0.194095 + outer loop + vertex 887.415 410.961 43.0591 + vertex 885.956 419.075 39.0879 + vertex 885.113 419.169 43.0589 + endloop + endfacet + facet normal 0.94186 0.27484 0.193295 + outer loop + vertex 885.956 419.075 39.0879 + vertex 883.549 427.319 39.0929 + vertex 885.113 419.169 43.0589 + endloop + endfacet + facet normal 0.9369 0.273377 0.217906 + outer loop + vertex 885.956 419.075 39.0879 + vertex 884.617 427.108 34.7646 + vertex 883.549 427.319 39.0929 + endloop + endfacet + facet normal 0.93528 0.27941 0.217212 + outer loop + vertex 884.617 427.108 34.7646 + vertex 882.123 435.452 34.7707 + vertex 883.549 427.319 39.0929 + endloop + endfacet + facet normal 0.934897 0.279889 0.218241 + outer loop + vertex 883.549 427.319 39.0929 + vertex 882.123 435.452 34.7707 + vertex 881.106 435.466 39.1082 + endloop + endfacet + facet normal 0.939787 0.281401 0.193945 + outer loop + vertex 883.549 427.319 39.0929 + vertex 881.106 435.466 39.1082 + vertex 882.752 427.23 43.0856 + endloop + endfacet + facet normal 0.934175 0.282427 0.218063 + outer loop + vertex 882.123 435.452 34.7707 + vertex 879.623 443.719 34.7721 + vertex 881.106 435.466 39.1082 + endloop + endfacet + facet normal 0.933499 0.283258 0.219876 + outer loop + vertex 881.106 435.466 39.1082 + vertex 879.623 443.719 34.7721 + vertex 878.667 443.513 39.0979 + endloop + endfacet + facet normal 0.93851 0.284745 0.195241 + outer loop + vertex 881.106 435.466 39.1082 + vertex 878.667 443.513 39.0979 + vertex 880.351 435.225 43.0908 + endloop + endfacet + facet normal 0.933327 0.28383 0.219865 + outer loop + vertex 879.623 443.719 34.7721 + vertex 877.146 451.887 34.7447 + vertex 878.667 443.513 39.0979 + endloop + endfacet + facet normal 0.932462 0.284873 0.222174 + outer loop + vertex 878.667 443.513 39.0979 + vertex 877.146 451.887 34.7447 + vertex 876.255 451.437 39.0621 + endloop + endfacet + facet normal 0.937496 0.286295 0.19783 + outer loop + vertex 878.667 443.513 39.0979 + vertex 876.255 451.437 39.0621 + vertex 877.935 443.158 43.0786 + endloop + endfacet + facet normal 0.932996 0.283173 0.222107 + outer loop + vertex 877.146 451.887 34.7447 + vertex 874.706 459.975 34.681 + vertex 876.255 451.437 39.0621 + endloop + endfacet + facet normal 0.930912 0.285631 0.227635 + outer loop + vertex 876.255 451.437 39.0621 + vertex 874.706 459.975 34.681 + vertex 873.883 459.187 39.0368 + endloop + endfacet + facet normal 0.936245 0.287181 0.202415 + outer loop + vertex 876.255 451.437 39.0621 + vertex 873.883 459.187 39.0368 + vertex 875.541 450.946 43.0593 + endloop + endfacet + facet normal 0.933129 0.278948 0.226846 + outer loop + vertex 874.706 459.975 34.681 + vertex 872.321 467.93 34.71 + vertex 873.883 459.187 39.0368 + endloop + endfacet + facet normal 0.930803 0.281598 0.23304 + outer loop + vertex 873.883 459.187 39.0368 + vertex 872.321 467.93 34.71 + vertex 871.59 466.725 39.0875 + endloop + endfacet + facet normal 0.935953 0.283326 0.209087 + outer loop + vertex 873.883 459.187 39.0368 + vertex 871.59 466.725 39.0875 + vertex 873.189 458.493 43.0823 + endloop + endfacet + facet normal 0.941862 0.24877 0.225852 + outer loop + vertex 872.321 467.93 34.71 + vertex 870.219 475.73 34.8844 + vertex 871.59 466.725 39.0875 + endloop + endfacet + facet normal 0.939743 0.25125 0.231855 + outer loop + vertex 871.59 466.725 39.0875 + vertex 870.219 475.73 34.8844 + vertex 869.591 474.151 39.1431 + endloop + endfacet + facet normal 0.967312 0.15539 0.200404 + outer loop + vertex 870.219 475.73 34.8844 + vertex 868.956 483.597 34.8806 + vertex 869.591 474.151 39.1431 + endloop + endfacet + facet normal 0.965093 0.155039 0.211088 + outer loop + vertex 870.219 475.73 34.8844 + vertex 869.457 485.556 31.1534 + vertex 868.956 483.597 34.8806 + endloop + endfacet + facet normal 0.95905 0.162504 0.231984 + outer loop + vertex 870.973 477.239 30.7123 + vertex 869.457 485.556 31.1534 + vertex 870.219 475.73 34.8844 + endloop + endfacet + facet normal 0.934364 0.246036 0.257741 + outer loop + vertex 872.321 467.93 34.71 + vertex 870.973 477.239 30.7123 + vertex 870.219 475.73 34.8844 + endloop + endfacet + facet normal 0.935775 0.244613 0.25395 + outer loop + vertex 873.281 468.847 30.2882 + vertex 870.973 477.239 30.7123 + vertex 872.321 467.93 34.71 + endloop + endfacet + facet normal 0.925607 0.276578 0.258372 + outer loop + vertex 874.706 459.975 34.681 + vertex 873.281 468.847 30.2882 + vertex 872.321 467.93 34.71 + endloop + endfacet + facet normal 0.926904 0.275202 0.255171 + outer loop + vertex 875.792 460.292 30.3959 + vertex 873.281 468.847 30.2882 + vertex 874.706 459.975 34.681 + endloop + endfacet + facet normal 0.925146 0.281065 0.25516 + outer loop + vertex 877.146 451.887 34.7447 + vertex 875.792 460.292 30.3959 + vertex 874.706 459.975 34.681 + endloop + endfacet + facet normal 0.925767 0.280385 0.253651 + outer loop + vertex 878.318 451.92 30.4316 + vertex 875.792 460.292 30.3959 + vertex 877.146 451.887 34.7447 + endloop + endfacet + facet normal 0.925436 0.281549 0.25357 + outer loop + vertex 879.623 443.719 34.7721 + vertex 878.318 451.92 30.4316 + vertex 877.146 451.887 34.7447 + endloop + endfacet + facet normal 0.926349 0.280526 0.251361 + outer loop + vertex 880.869 443.491 30.437 + vertex 878.318 451.92 30.4316 + vertex 879.623 443.719 34.7721 + endloop + endfacet + facet normal 0.926466 0.28009 0.251418 + outer loop + vertex 882.123 435.452 34.7707 + vertex 880.869 443.491 30.437 + vertex 879.623 443.719 34.7721 + endloop + endfacet + facet normal 0.926363 0.280208 0.251666 + outer loop + vertex 883.451 434.955 30.4345 + vertex 880.869 443.491 30.437 + vertex 882.123 435.452 34.7707 + endloop + endfacet + facet normal 0.92717 0.27696 0.252286 + outer loop + vertex 884.617 427.108 34.7646 + vertex 883.451 434.955 30.4345 + vertex 882.123 435.452 34.7707 + endloop + endfacet + facet normal 0.927173 0.276957 0.25228 + outer loop + vertex 885.998 426.436 30.4286 + vertex 883.451 434.955 30.4345 + vertex 884.617 427.108 34.7646 + endloop + endfacet + facet normal 0.928608 0.270792 0.253692 + outer loop + vertex 887.069 418.704 34.761 + vertex 885.998 426.436 30.4286 + vertex 884.617 427.108 34.7646 + endloop + endfacet + facet normal 0.928552 0.270859 0.253825 + outer loop + vertex 888.49 417.895 30.4269 + vertex 885.998 426.436 30.4286 + vertex 887.069 418.704 34.761 + endloop + endfacet + facet normal 0.930648 0.261137 0.256326 + outer loop + vertex 889.453 410.205 34.7636 + vertex 888.49 417.895 30.4269 + vertex 887.069 418.704 34.761 + endloop + endfacet + facet normal 0.939382 0.263576 0.219291 + outer loop + vertex 889.453 410.205 34.7636 + vertex 887.069 418.704 34.761 + vertex 888.301 410.712 39.0869 + endloop + endfacet + facet normal 0.942449 0.250313 0.221662 + outer loop + vertex 890.551 402.23 39.0985 + vertex 889.453 410.205 34.7636 + vertex 888.301 410.712 39.0869 + endloop + endfacet + facet normal 0.947683 0.251667 0.196371 + outer loop + vertex 890.551 402.23 39.0985 + vertex 888.301 410.712 39.0869 + vertex 889.637 402.573 43.07 + endloop + endfacet + facet normal 0.95147 0.235011 0.198681 + outer loop + vertex 891.731 394.088 43.0822 + vertex 890.551 402.23 39.0985 + vertex 889.637 402.573 43.07 + endloop + endfacet + facet normal 0.955157 0.235892 0.178971 + outer loop + vertex 891.731 394.088 43.0822 + vertex 889.637 402.573 43.07 + vertex 890.969 394.681 46.3677 + endloop + endfacet + facet normal 0.951341 0.23519 0.199086 + outer loop + vertex 892.673 393.647 39.1008 + vertex 890.551 402.23 39.0985 + vertex 891.731 394.088 43.0822 + endloop + endfacet + facet normal 0.955311 0.215632 0.202196 + outer loop + vertex 893.654 385.562 43.0853 + vertex 892.673 393.647 39.1008 + vertex 891.731 394.088 43.0822 + endloop + endfacet + facet normal 0.95938 0.216542 0.180832 + outer loop + vertex 893.654 385.562 43.0853 + vertex 891.731 394.088 43.0822 + vertex 892.868 386.322 46.3473 + endloop + endfacet + facet normal 0.955209 0.21578 0.20252 + outer loop + vertex 894.645 384.942 39.0728 + vertex 892.673 393.647 39.1008 + vertex 893.654 385.562 43.0853 + endloop + endfacet + facet normal 0.959113 0.193005 0.207004 + outer loop + vertex 895.386 376.968 43.0766 + vertex 894.645 384.942 39.0728 + vertex 893.654 385.562 43.0853 + endloop + endfacet + facet normal 0.963596 0.193931 0.184049 + outer loop + vertex 895.386 376.968 43.0766 + vertex 893.654 385.562 43.0853 + vertex 894.563 377.964 46.3349 + endloop + endfacet + facet normal 0.958969 0.193225 0.207469 + outer loop + vertex 896.446 376.12 38.9658 + vertex 894.645 384.942 39.0728 + vertex 895.386 376.968 43.0766 + endloop + endfacet + facet normal 0.94928 0.214348 0.230048 + outer loop + vertex 894.645 384.942 39.0728 + vertex 893.91 392.847 34.7422 + vertex 892.673 393.647 39.1008 + endloop + endfacet + facet normal 0.945756 0.233907 0.225461 + outer loop + vertex 893.91 392.847 34.7422 + vertex 891.741 401.595 34.7658 + vertex 892.673 393.647 39.1008 + endloop + endfacet + facet normal 0.935914 0.231358 0.26559 + outer loop + vertex 893.91 392.847 34.7422 + vertex 893.259 400.438 30.4219 + vertex 891.741 401.595 34.7658 + endloop + endfacet + facet normal 0.933157 0.248035 0.260187 + outer loop + vertex 893.259 400.438 30.4219 + vertex 890.925 409.214 30.4266 + vertex 891.741 401.595 34.7658 + endloop + endfacet + facet normal 0.933175 0.248013 0.260144 + outer loop + vertex 891.741 401.595 34.7658 + vertex 890.925 409.214 30.4266 + vertex 889.453 410.205 34.7636 + endloop + endfacet + facet normal 0.936201 0.23099 0.2649 + outer loop + vertex 895.478 391.501 30.3751 + vertex 893.259 400.438 30.4219 + vertex 893.91 392.847 34.7422 + endloop + endfacet + facet normal 0.938854 0.211156 0.271968 + outer loop + vertex 895.959 383.885 34.6261 + vertex 895.478 391.501 30.3751 + vertex 893.91 392.847 34.7422 + endloop + endfacet + facet normal 0.949436 0.214124 0.229614 + outer loop + vertex 895.959 383.885 34.6261 + vertex 893.91 392.847 34.7422 + vertex 894.645 384.942 39.0728 + endloop + endfacet + facet normal 0.945811 0.23383 0.225309 + outer loop + vertex 892.673 393.647 39.1008 + vertex 891.741 401.595 34.7658 + vertex 890.551 402.23 39.0985 + endloop + endfacet + facet normal 0.947916 0.251351 0.195649 + outer loop + vertex 889.637 402.573 43.07 + vertex 888.301 410.712 39.0869 + vertex 887.415 410.961 43.0591 + endloop + endfacet + facet normal 0.951361 0.25224 0.176882 + outer loop + vertex 889.637 402.573 43.07 + vertex 887.415 410.961 43.0591 + vertex 888.884 403.114 46.3488 + endloop + endfacet + facet normal 0.942353 0.250442 0.221923 + outer loop + vertex 891.741 401.595 34.7658 + vertex 889.453 410.205 34.7636 + vertex 890.551 402.23 39.0985 + endloop + endfacet + facet normal 0.939447 0.263491 0.219117 + outer loop + vertex 888.301 410.712 39.0869 + vertex 887.069 418.704 34.761 + vertex 885.956 419.075 39.0879 + endloop + endfacet + facet normal 0.930661 0.26112 0.256294 + outer loop + vertex 890.925 409.214 30.4266 + vertex 888.49 417.895 30.4269 + vertex 889.453 410.205 34.7636 + endloop + endfacet + facet normal 0.936996 0.273254 0.217649 + outer loop + vertex 887.069 418.704 34.761 + vertex 884.617 427.108 34.7646 + vertex 885.956 419.075 39.0879 + endloop + endfacet + facet normal 0.944543 0.264924 0.194044 + outer loop + vertex 888.301 410.712 39.0869 + vertex 885.956 419.075 39.0879 + vertex 887.415 410.961 43.0591 + endloop + endfacet + facet normal 0.941574 0.275208 0.194163 + outer loop + vertex 885.113 419.169 43.0589 + vertex 883.549 427.319 39.0929 + vertex 882.752 427.23 43.0856 + endloop + endfacet + facet normal 0.939359 0.281937 0.195232 + outer loop + vertex 882.752 427.23 43.0856 + vertex 881.106 435.466 39.1082 + vertex 880.351 435.225 43.0908 + endloop + endfacet + facet normal 0.937647 0.28581 0.197815 + outer loop + vertex 880.351 435.225 43.0908 + vertex 878.667 443.513 39.0979 + vertex 877.935 443.158 43.0786 + endloop + endfacet + facet normal 0.935908 0.288231 0.202484 + outer loop + vertex 877.935 443.158 43.0786 + vertex 876.255 451.437 39.0621 + vertex 875.541 450.946 43.0593 + endloop + endfacet + facet normal 0.933634 0.290302 0.209887 + outer loop + vertex 875.541 450.946 43.0593 + vertex 873.883 459.187 39.0368 + vertex 873.189 458.493 43.0823 + endloop + endfacet + facet normal 0.931455 0.28855 0.221654 + outer loop + vertex 873.189 458.493 43.0823 + vertex 871.59 466.725 39.0875 + vertex 870.916 465.762 43.1711 + endloop + endfacet + facet normal 0.943422 0.252366 0.215096 + outer loop + vertex 871.59 466.725 39.0875 + vertex 869.591 474.151 39.1431 + vertex 870.916 465.762 43.1711 + endloop + endfacet + facet normal 0.966485 0.156674 0.203371 + outer loop + vertex 869.591 474.151 39.1431 + vertex 868.956 483.597 34.8806 + vertex 868.411 481.779 38.8735 + endloop + endfacet + facet normal 0.937447 0.263209 0.227845 + outer loop + vertex 870.224 465.512 46.5038 + vertex 868.966 472.889 43.1603 + vertex 868.385 472.079 46.4847 + endloop + endfacet + facet normal 0.937913 0.263333 0.225775 + outer loop + vertex 870.224 465.512 46.5038 + vertex 868.385 472.079 46.4847 + vertex 869.562 466.01 48.6738 + endloop + endfacet + facet normal 0.956916 0.17331 -0.232969 + outer loop + vertex 868.038 469.943 49.7133 + vertex 867.25 473.767 49.3227 + vertex 868.466 468.5 50.3973 + endloop + endfacet + facet normal 0.959981 0.177319 -0.216782 + outer loop + vertex 866.766 477.509 50.2382 + vertex 868.466 468.5 50.3973 + vertex 867.25 473.767 49.3227 + endloop + endfacet + facet normal 0.951767 0.303503 0.0450037 + outer loop + vertex 869.147 466.452 49.7882 + vertex 868.038 469.943 49.7133 + vertex 868.466 468.5 50.3973 + endloop + endfacet + facet normal 0.922461 0.276204 0.269771 + outer loop + vertex 869.562 466.01 48.6738 + vertex 868.385 472.079 46.4847 + vertex 868.043 471.031 48.729 + endloop + endfacet + facet normal 0.929854 0.306342 0.203778 + outer loop + vertex 870.562 462.222 49.6925 + vertex 869.147 466.452 49.7882 + vertex 870.862 460.803 50.4578 + endloop + endfacet + facet normal 0.952474 0.297052 0.0674822 + outer loop + vertex 868.466 468.5 50.3973 + vertex 870.862 460.803 50.4578 + vertex 869.147 466.452 49.7882 + endloop + endfacet + facet normal 0.929138 0.301209 0.214418 + outer loop + vertex 871.639 459.531 48.7734 + vertex 870.224 465.512 46.5038 + vertex 869.562 466.01 48.6738 + endloop + endfacet + facet normal 0.930034 0.306118 0.203294 + outer loop + vertex 871.852 458.203 49.8444 + vertex 870.562 462.222 49.6925 + vertex 870.862 460.803 50.4578 + endloop + endfacet + facet normal 0.931324 0.301216 0.204708 + outer loop + vertex 873.003 454.815 49.593 + vertex 871.852 458.203 49.8444 + vertex 873.335 453.258 50.3725 + endloop + endfacet + facet normal 0.927982 0.301706 0.218686 + outer loop + vertex 870.862 460.803 50.4578 + vertex 873.335 453.258 50.3725 + vertex 871.852 458.203 49.8444 + endloop + endfacet + facet normal 0.933764 0.303937 0.188964 + outer loop + vertex 873.335 453.258 50.3725 + vertex 870.862 460.803 50.4578 + vertex 872.696 454.233 51.9605 + endloop + endfacet + facet normal 0.934723 0.298671 0.192584 + outer loop + vertex 875.062 446.884 51.8749 + vertex 873.335 453.258 50.3725 + vertex 872.696 454.233 51.9605 + endloop + endfacet + facet normal 0.937132 0.299606 0.178941 + outer loop + vertex 875.062 446.884 51.8749 + vertex 872.696 454.233 51.9605 + vertex 874.429 447.095 54.8401 + endloop + endfacet + facet normal 0.938591 0.294597 0.179609 + outer loop + vertex 874.429 447.095 54.8401 + vertex 876.778 439.679 54.7238 + vertex 875.062 446.884 51.8749 + endloop + endfacet + facet normal 0.93958 0.293491 0.176216 + outer loop + vertex 877.393 439.525 51.7034 + vertex 875.062 446.884 51.8749 + vertex 876.778 439.679 54.7238 + endloop + endfacet + facet normal 0.940901 0.288922 0.176718 + outer loop + vertex 876.778 439.679 54.7238 + vertex 879.395 431.4 54.3281 + vertex 877.393 439.525 51.7034 + endloop + endfacet + facet normal 0.940772 0.289046 0.177201 + outer loop + vertex 879.342 433.409 51.3325 + vertex 877.393 439.525 51.7034 + vertex 879.395 431.4 54.3281 + endloop + endfacet + facet normal 0.943085 0.283671 0.173553 + outer loop + vertex 881.554 425.604 52.0679 + vertex 879.342 433.409 51.3325 + vertex 879.395 431.4 54.3281 + endloop + endfacet + facet normal 0.943001 0.283098 0.174942 + outer loop + vertex 879.395 431.4 54.3281 + vertex 881.651 423.196 55.444 + vertex 881.554 425.604 52.0679 + endloop + endfacet + facet normal 0.946721 0.274385 0.16862 + outer loop + vertex 881.651 423.196 55.444 + vertex 883.774 416.414 54.5618 + vertex 881.554 425.604 52.0679 + endloop + endfacet + facet normal 0.943708 0.276973 0.180837 + outer loop + vertex 883.709 418.66 51.4576 + vertex 881.554 425.604 52.0679 + vertex 883.774 416.414 54.5618 + endloop + endfacet + facet normal 0.948479 0.265708 0.17259 + outer loop + vertex 885.787 410.72 52.2615 + vertex 883.709 418.66 51.4576 + vertex 883.774 416.414 54.5618 + endloop + endfacet + facet normal 0.94828 0.264392 0.175676 + outer loop + vertex 883.774 416.414 54.5618 + vertex 885.75 408.643 55.5908 + vertex 885.787 410.72 52.2615 + endloop + endfacet + facet normal 0.953727 0.250137 0.166844 + outer loop + vertex 885.75 408.643 55.5908 + vertex 887.392 402.777 54.995 + vertex 885.787 410.72 52.2615 + endloop + endfacet + facet normal 0.951786 0.252352 0.174421 + outer loop + vertex 888.015 402.544 51.9352 + vertex 885.787 410.72 52.2615 + vertex 887.392 402.777 54.995 + endloop + endfacet + facet normal 0.955855 0.234861 0.176582 + outer loop + vertex 887.392 402.777 54.995 + vertex 889.253 395.399 54.7396 + vertex 888.015 402.544 51.9352 + endloop + endfacet + facet normal 0.955016 0.235928 0.179671 + outer loop + vertex 889.893 395.108 51.7164 + vertex 888.015 402.544 51.9352 + vertex 889.253 395.399 54.7396 + endloop + endfacet + facet normal 0.959055 0.216687 0.182376 + outer loop + vertex 889.253 395.399 54.7396 + vertex 891.209 387.062 54.3543 + vertex 889.893 395.108 51.7164 + endloop + endfacet + facet normal 0.956503 0.219481 0.192171 + outer loop + vertex 891.384 388.914 51.3676 + vertex 889.893 395.108 51.7164 + vertex 891.209 387.062 54.3543 + endloop + endfacet + facet normal 0.963549 0.198375 0.1795 + outer loop + vertex 892.892 380.796 52.2459 + vertex 891.384 388.914 51.3676 + vertex 891.209 387.062 54.3543 + endloop + endfacet + facet normal 0.963123 0.196991 0.183272 + outer loop + vertex 891.209 387.062 54.3543 + vertex 892.607 379.118 55.5475 + vertex 892.892 380.796 52.2459 + endloop + endfacet + facet normal 0.970207 0.171634 0.170998 + outer loop + vertex 892.607 379.118 55.5475 + vertex 893.789 372.957 55.0272 + vertex 892.892 380.796 52.2459 + endloop + endfacet + facet normal 0.967287 0.175592 0.183095 + outer loop + vertex 894.54 372 51.974 + vertex 892.892 380.796 52.2459 + vertex 893.789 372.957 55.0272 + endloop + endfacet + facet normal 0.97017 0.147004 0.192768 + outer loop + vertex 893.789 372.957 55.0272 + vertex 894.972 365.4 54.8346 + vertex 894.54 372 51.974 + endloop + endfacet + facet normal 0.970585 0.146342 0.191179 + outer loop + vertex 895.747 364.125 51.8748 + vertex 894.54 372 51.974 + vertex 894.972 365.4 54.8346 + endloop + endfacet + facet normal 0.971902 0.11755 0.203933 + outer loop + vertex 894.972 365.4 54.8346 + vertex 895.914 357.687 54.7913 + vertex 895.747 364.125 51.8748 + endloop + endfacet + facet normal 0.973443 0.114904 0.198006 + outer loop + vertex 896.661 356.424 51.8528 + vertex 895.747 364.125 51.8748 + vertex 895.914 357.687 54.7913 + endloop + endfacet + facet normal 0.97378 0.0829122 0.211844 + outer loop + vertex 895.914 357.687 54.7913 + vertex 896.572 349.892 54.8166 + vertex 896.661 356.424 51.8528 + endloop + endfacet + facet normal 0.975687 0.0794456 0.204261 + outer loop + vertex 897.297 348.637 51.8444 + vertex 896.661 356.424 51.8528 + vertex 896.572 349.892 54.8166 + endloop + endfacet + facet normal 0.974649 0.0423044 0.219702 + outer loop + vertex 896.572 349.892 54.8166 + vertex 896.94 341.96 54.7116 + vertex 897.297 348.637 51.8444 + endloop + endfacet + facet normal 0.975293 0.0411329 0.217054 + outer loop + vertex 897.661 340.913 51.671 + vertex 897.297 348.637 51.8444 + vertex 896.94 341.96 54.7116 + endloop + endfacet + facet normal 0.972296 -0.00896466 0.233581 + outer loop + vertex 896.94 341.96 54.7116 + vertex 896.956 333.289 54.312 + vertex 897.661 340.913 51.671 + endloop + endfacet + facet normal 0.967763 -0.00221578 0.251854 + outer loop + vertex 897.745 334.6 51.2932 + vertex 897.661 340.913 51.671 + vertex 896.956 333.289 54.312 + endloop + endfacet + facet normal 0.960109 -0.00397763 0.279597 + outer loop + vertex 897.745 334.6 51.2932 + vertex 898.085 339.237 50.1926 + vertex 897.661 340.913 51.671 + endloop + endfacet + facet normal 0.970242 0.0337026 0.239781 + outer loop + vertex 898.085 339.237 50.1926 + vertex 897.801 346.851 50.2699 + vertex 897.661 340.913 51.671 + endloop + endfacet + facet normal 0.971215 -0.0147233 0.237751 + outer loop + vertex 897.973 332.126 50.2097 + vertex 898.085 339.237 50.1926 + vertex 897.745 334.6 51.2932 + endloop + endfacet + facet normal 0.979195 -0.00753252 0.202783 + outer loop + vertex 896.956 333.289 54.312 + vertex 896.94 341.96 54.7116 + vertex 895.933 335.155 59.3242 + endloop + endfacet + facet normal 0.977986 -0.00337971 0.208645 + outer loop + vertex 895.933 335.155 59.3242 + vertex 896.94 341.96 54.7116 + vertex 895.947 342.999 59.3854 + endloop + endfacet + facet normal 0.979642 -0.00332081 0.200723 + outer loop + vertex 895.933 335.155 59.3242 + vertex 895.947 342.999 59.3854 + vertex 894.704 336.232 65.3358 + endloop + endfacet + facet normal 0.979484 -0.002602 0.201507 + outer loop + vertex 894.704 336.232 65.3358 + vertex 895.947 342.999 59.3854 + vertex 894.724 343.766 65.3405 + endloop + endfacet + facet normal 0.98061 -0.00260136 0.195954 + outer loop + vertex 894.704 336.232 65.3358 + vertex 894.724 343.766 65.3405 + vertex 893.362 337.141 72.0647 + endloop + endfacet + facet normal 0.980673 -0.00294172 0.195631 + outer loop + vertex 893.362 337.141 72.0647 + vertex 894.724 343.766 65.3405 + vertex 893.386 344.549 72.058 + endloop + endfacet + facet normal 0.982259 -0.00295411 0.187505 + outer loop + vertex 893.362 337.141 72.0647 + vertex 893.386 344.549 72.058 + vertex 892.02 338.126 79.1135 + endloop + endfacet + facet normal 0.982269 -0.00301658 0.187451 + outer loop + vertex 892.02 338.126 79.1135 + vertex 893.386 344.549 72.058 + vertex 892.044 345.464 79.1065 + endloop + endfacet + facet normal 0.984081 -0.00303172 0.177693 + outer loop + vertex 892.02 338.126 79.1135 + vertex 892.044 345.464 79.1065 + vertex 890.723 339.186 86.3117 + endloop + endfacet + facet normal 0.983961 -0.00223137 0.178369 + outer loop + vertex 890.723 339.186 86.3117 + vertex 892.044 345.464 79.1065 + vertex 890.74 346.449 86.3103 + endloop + endfacet + facet normal 0.986322 -0.0022394 0.164812 + outer loop + vertex 890.723 339.186 86.3117 + vertex 890.74 346.449 86.3103 + vertex 889.5 340.217 93.6449 + endloop + endfacet + facet normal 0.986118 -0.000751301 0.166042 + outer loop + vertex 889.5 340.217 93.6449 + vertex 890.74 346.449 86.3103 + vertex 889.505 347.393 93.6462 + endloop + endfacet + facet normal 0.988323 -0.000750443 0.152372 + outer loop + vertex 889.5 340.217 93.6449 + vertex 889.505 347.393 93.6462 + vertex 888.346 341.163 101.138 + endloop + endfacet + facet normal 0.988145 0.00066711 0.153523 + outer loop + vertex 888.346 341.163 101.138 + vertex 889.505 347.393 93.6462 + vertex 888.341 348.254 101.138 + endloop + endfacet + facet normal 0.990257 0.000669808 0.139252 + outer loop + vertex 888.346 341.163 101.138 + vertex 888.341 348.254 101.138 + vertex 887.271 342.017 108.775 + endloop + endfacet + facet normal 0.990073 0.00227125 0.140534 + outer loop + vertex 887.271 342.017 108.775 + vertex 888.341 348.254 101.138 + vertex 887.255 349.032 108.775 + endloop + endfacet + facet normal 0.99217 0.00227734 0.124877 + outer loop + vertex 887.271 342.017 108.775 + vertex 887.255 349.032 108.775 + vertex 886.295 342.782 116.513 + endloop + endfacet + facet normal 0.990337 -0.049044 0.129719 + outer loop + vertex 885.954 335.882 116.513 + vertex 887.271 342.017 108.775 + vertex 886.295 342.782 116.513 + endloop + endfacet + facet normal 0.992403 -0.0491475 0.112785 + outer loop + vertex 885.954 335.882 116.513 + vertex 886.295 342.782 116.513 + vertex 885.103 336.612 124.321 + endloop + endfacet + facet normal 0.992342 -0.047657 0.113954 + outer loop + vertex 885.103 336.612 124.321 + vertex 886.295 342.782 116.513 + vertex 885.431 343.454 124.32 + endloop + endfacet + facet normal 0.994359 -0.0477559 0.0947111 + outer loop + vertex 885.103 336.612 124.321 + vertex 885.431 343.454 124.32 + vertex 884.384 337.237 132.177 + endloop + endfacet + facet normal 0.994309 -0.0460197 0.0960784 + outer loop + vertex 884.384 337.237 132.177 + vertex 885.431 343.454 124.32 + vertex 884.699 344.029 132.177 + endloop + endfacet + facet normal 0.995915 -0.0460949 0.0776378 + outer loop + vertex 884.384 337.237 132.177 + vertex 884.699 344.029 132.177 + vertex 883.793 337.75 140.066 + endloop + endfacet + facet normal 0.995896 -0.0449374 0.0785569 + outer loop + vertex 883.793 337.75 140.066 + vertex 884.699 344.029 132.177 + vertex 884.098 344.501 140.065 + endloop + endfacet + facet normal 0.997203 -0.0449979 0.0596842 + outer loop + vertex 883.793 337.75 140.066 + vertex 884.098 344.501 140.065 + vertex 883.339 338.149 147.952 + endloop + endfacet + facet normal 0.9972 -0.0444018 0.0601642 + outer loop + vertex 883.339 338.149 147.952 + vertex 884.098 344.501 140.065 + vertex 883.638 344.869 147.952 + endloop + endfacet + facet normal 0.998129 -0.0444448 0.0419797 + outer loop + vertex 883.339 338.149 147.952 + vertex 883.638 344.869 147.952 + vertex 883.021 338.435 155.805 + endloop + endfacet + facet normal 0.99813 -0.0443382 0.0420672 + outer loop + vertex 883.021 338.435 155.805 + vertex 883.638 344.869 147.952 + vertex 883.319 345.133 155.805 + endloop + endfacet + facet normal 0.998749 -0.0443668 0.0230458 + outer loop + vertex 883.021 338.435 155.805 + vertex 883.319 345.133 155.805 + vertex 882.849 338.609 163.626 + endloop + endfacet + facet normal 0.998769 -0.0435864 0.0236979 + outer loop + vertex 882.849 338.609 163.626 + vertex 883.319 345.133 155.805 + vertex 883.14 345.292 163.624 + endloop + endfacet + facet normal 0.999039 -0.043603 0.00447595 + outer loop + vertex 882.849 338.609 163.626 + vertex 883.14 345.292 163.624 + vertex 882.816 338.671 171.45 + endloop + endfacet + facet normal 0.999036 -0.0436666 0.00442199 + outer loop + vertex 882.816 338.671 171.45 + vertex 883.14 345.292 163.624 + vertex 883.108 345.349 171.449 + endloop + endfacet + facet normal 0.998944 -0.0436677 -0.0142767 + outer loop + vertex 882.816 338.671 171.45 + vertex 883.108 345.349 171.449 + vertex 882.927 338.62 179.327 + endloop + endfacet + facet normal 0.998901 -0.0444253 -0.0149247 + outer loop + vertex 882.927 338.62 179.327 + vertex 883.108 345.349 171.449 + vertex 883.224 345.302 179.325 + endloop + endfacet + facet normal 0.998436 -0.0444111 -0.0339722 + outer loop + vertex 882.927 338.62 179.327 + vertex 883.224 345.302 179.325 + vertex 883.19 338.458 187.272 + endloop + endfacet + facet normal 0.998361 -0.0454126 -0.0348349 + outer loop + vertex 883.19 338.458 187.272 + vertex 883.224 345.302 179.325 + vertex 883.494 345.152 187.269 + endloop + endfacet + facet normal 0.997549 -0.0453829 -0.0532587 + outer loop + vertex 883.19 338.458 187.272 + vertex 883.494 345.152 187.269 + vertex 883.604 338.18 195.26 + endloop + endfacet + facet normal 0.997405 -0.0469277 -0.0546046 + outer loop + vertex 883.604 338.18 195.26 + vertex 883.494 345.152 187.269 + vertex 883.919 344.895 195.257 + endloop + endfacet + facet normal 0.99615 -0.0468771 -0.0740836 + outer loop + vertex 883.604 338.18 195.26 + vertex 883.919 344.895 195.257 + vertex 884.179 337.788 203.238 + endloop + endfacet + facet normal 0.995912 -0.0489433 -0.075916 + outer loop + vertex 884.179 337.788 203.238 + vertex 883.919 344.895 195.257 + vertex 884.51 344.534 203.235 + endloop + endfacet + facet normal 0.994312 -0.0488732 -0.0946345 + outer loop + vertex 884.179 337.788 203.238 + vertex 884.51 344.534 203.235 + vertex 884.907 337.278 211.159 + endloop + endfacet + facet normal 0.993966 -0.0513755 -0.0969085 + outer loop + vertex 884.907 337.278 211.159 + vertex 884.51 344.534 203.235 + vertex 885.258 344.064 211.156 + endloop + endfacet + facet normal 0.991882 -0.0512774 -0.116363 + outer loop + vertex 884.907 337.278 211.159 + vertex 885.258 344.064 211.156 + vertex 885.796 336.656 219.004 + endloop + endfacet + facet normal 0.991327 -0.0546579 -0.119516 + outer loop + vertex 885.796 336.656 219.004 + vertex 885.258 344.064 211.156 + vertex 886.172 343.492 219.001 + endloop + endfacet + facet normal 0.988988 -0.0545352 -0.137582 + outer loop + vertex 885.796 336.656 219.004 + vertex 886.172 343.492 219.001 + vertex 886.836 335.925 226.772 + endloop + endfacet + facet normal 0.988467 -0.0572598 -0.140191 + outer loop + vertex 886.836 335.925 226.772 + vertex 886.172 343.492 219.001 + vertex 887.235 342.814 226.769 + endloop + endfacet + facet normal 0.985903 -0.0571197 -0.157263 + outer loop + vertex 886.836 335.925 226.772 + vertex 887.235 342.814 226.769 + vertex 888.016 335.09 234.471 + endloop + endfacet + facet normal 0.985083 -0.0608788 -0.16095 + outer loop + vertex 888.016 335.09 234.471 + vertex 887.235 342.814 226.769 + vertex 888.445 342.043 234.468 + endloop + endfacet + facet normal 0.982507 -0.0607254 -0.176044 + outer loop + vertex 888.016 335.09 234.471 + vertex 888.445 342.043 234.468 + vertex 889.324 334.169 242.092 + endloop + endfacet + facet normal 0.981447 -0.0650316 -0.180369 + outer loop + vertex 889.324 334.169 242.092 + vertex 888.445 342.043 234.468 + vertex 889.79 341.195 242.092 + endloop + endfacet + facet normal 0.978608 -0.0648448 -0.19525 + outer loop + vertex 889.324 334.169 242.092 + vertex 889.79 341.195 242.092 + vertex 890.761 333.19 249.621 + endloop + endfacet + facet normal 0.977631 -0.0683928 -0.198896 + outer loop + vertex 890.761 333.19 249.621 + vertex 889.79 341.195 242.092 + vertex 891.258 340.291 249.621 + endloop + endfacet + facet normal 0.974564 -0.0681779 -0.213489 + outer loop + vertex 890.761 333.19 249.621 + vertex 891.258 340.291 249.621 + vertex 892.313 332.16 257.035 + endloop + endfacet + facet normal 0.97374 -0.0708899 -0.216346 + outer loop + vertex 892.313 332.16 257.035 + vertex 891.258 340.291 249.621 + vertex 892.836 339.343 257.034 + endloop + endfacet + facet normal 0.970571 -0.0706612 -0.230214 + outer loop + vertex 892.313 332.16 257.035 + vertex 892.836 339.343 257.034 + vertex 893.958 331.062 264.304 + endloop + endfacet + facet normal 0.969698 -0.0732771 -0.233059 + outer loop + vertex 893.958 331.062 264.304 + vertex 892.836 339.343 257.034 + vertex 894.506 338.331 264.301 + endloop + endfacet + facet normal 0.966862 -0.0730673 -0.24462 + outer loop + vertex 893.958 331.062 264.304 + vertex 894.506 338.331 264.301 + vertex 895.647 329.864 271.338 + endloop + endfacet + facet normal 0.965882 -0.0757287 -0.247664 + outer loop + vertex 895.647 329.864 271.338 + vertex 894.506 338.331 264.301 + vertex 896.222 337.222 271.331 + endloop + endfacet + facet normal 0.963978 -0.0755867 -0.255015 + outer loop + vertex 895.647 329.864 271.338 + vertex 896.222 337.222 271.331 + vertex 897.277 328.582 277.882 + endloop + endfacet + facet normal 0.962402 -0.079385 -0.259771 + outer loop + vertex 897.277 328.582 277.882 + vertex 896.222 337.222 271.331 + vertex 897.894 336.026 277.89 + endloop + endfacet + facet normal 0.959856 -0.0791639 -0.269092 + outer loop + vertex 897.277 328.582 277.882 + vertex 897.894 336.026 277.89 + vertex 898.778 327.386 283.587 + endloop + endfacet + facet normal 0.959328 -0.0802451 -0.270649 + outer loop + vertex 898.778 327.386 283.587 + vertex 897.894 336.026 277.89 + vertex 899.405 334.914 283.578 + endloop + endfacet + facet normal 0.953982 -0.0798232 -0.289046 + outer loop + vertex 898.778 327.386 283.587 + vertex 899.405 334.914 283.578 + vertex 900.077 326.688 288.065 + endloop + endfacet + facet normal 0.954608 -0.0787955 -0.287255 + outer loop + vertex 900.077 326.688 288.065 + vertex 899.405 334.914 283.578 + vertex 900.706 334.249 288.082 + endloop + endfacet + facet normal 0.941646 -0.0776279 -0.327533 + outer loop + vertex 900.077 326.688 288.065 + vertex 900.706 334.249 288.082 + vertex 901.235 327.064 291.306 + endloop + endfacet + facet normal 0.948903 -0.0683623 -0.308074 + outer loop + vertex 901.235 327.064 291.306 + vertex 900.706 334.249 288.082 + vertex 901.787 334.617 291.329 + endloop + endfacet + facet normal 0.999867 0.00719113 -0.0146328 + outer loop + vertex 883.108 345.349 171.449 + vertex 883.06 352.068 171.448 + vertex 883.224 345.302 179.325 + endloop + endfacet + facet normal 0.999863 0.00655058 -0.015183 + outer loop + vertex 883.224 345.302 179.325 + vertex 883.06 352.068 171.448 + vertex 883.18 352.025 179.323 + endloop + endfacet + facet normal 0.999404 0.00654396 -0.0338897 + outer loop + vertex 883.224 345.302 179.325 + vertex 883.18 352.025 179.323 + vertex 883.494 345.152 187.269 + endloop + endfacet + facet normal 0.999393 0.00604611 -0.0343199 + outer loop + vertex 883.494 345.152 187.269 + vertex 883.18 352.025 179.323 + vertex 883.453 351.887 187.269 + endloop + endfacet + facet normal 0.998578 0.00603894 -0.0529662 + outer loop + vertex 883.494 345.152 187.269 + vertex 883.453 351.887 187.269 + vertex 883.919 344.895 195.257 + endloop + endfacet + facet normal 0.998509 0.00439492 -0.054401 + outer loop + vertex 883.919 344.895 195.257 + vertex 883.453 351.887 187.269 + vertex 883.89 351.654 195.255 + endloop + endfacet + facet normal 0.997278 0.00438424 -0.0736018 + outer loop + vertex 883.919 344.895 195.257 + vertex 883.89 351.654 195.255 + vertex 884.51 344.534 203.235 + endloop + endfacet + facet normal 0.997195 0.00304975 -0.074786 + outer loop + vertex 884.51 344.534 203.235 + vertex 883.89 351.654 195.255 + vertex 884.489 351.323 203.233 + endloop + endfacet + facet normal 0.995584 0.00303827 -0.0938304 + outer loop + vertex 884.51 344.534 203.235 + vertex 884.489 351.323 203.233 + vertex 885.258 344.064 211.156 + endloop + endfacet + facet normal 0.995356 0.0003619 -0.0962604 + outer loop + vertex 885.258 344.064 211.156 + vertex 884.489 351.323 203.233 + vertex 885.255 350.895 211.155 + endloop + endfacet + facet normal 0.993281 0.000358772 -0.11573 + outer loop + vertex 885.258 344.064 211.156 + vertex 885.255 350.895 211.155 + vertex 886.172 343.492 219.001 + endloop + endfacet + facet normal 0.993088 -0.00139225 -0.11736 + outer loop + vertex 886.172 343.492 219.001 + vertex 885.255 350.895 211.155 + vertex 886.181 350.37 218.999 + endloop + endfacet + facet normal 0.990758 -0.00139594 -0.135632 + outer loop + vertex 886.172 343.492 219.001 + vertex 886.181 350.37 218.999 + vertex 887.235 342.814 226.769 + endloop + endfacet + facet normal 0.99032 -0.00463727 -0.138724 + outer loop + vertex 887.235 342.814 226.769 + vertex 886.181 350.37 218.999 + vertex 887.267 349.752 226.768 + endloop + endfacet + facet normal 0.987787 -0.004629 -0.155745 + outer loop + vertex 887.235 342.814 226.769 + vertex 887.267 349.752 226.768 + vertex 888.445 342.043 234.468 + endloop + endfacet + facet normal 0.987285 -0.00772876 -0.158771 + outer loop + vertex 888.445 342.043 234.468 + vertex 887.267 349.752 226.768 + vertex 888.5 349.047 234.467 + endloop + endfacet + facet normal 0.984619 -0.00770993 -0.174548 + outer loop + vertex 888.445 342.043 234.468 + vertex 888.5 349.047 234.467 + vertex 889.79 341.195 242.092 + endloop + endfacet + facet normal 0.984101 -0.010469 -0.177302 + outer loop + vertex 889.79 341.195 242.092 + vertex 888.5 349.047 234.467 + vertex 889.865 348.271 242.09 + endloop + endfacet + facet normal 0.981214 -0.0104415 -0.192639 + outer loop + vertex 889.79 341.195 242.092 + vertex 889.865 348.271 242.09 + vertex 891.258 340.291 249.621 + endloop + endfacet + facet normal 0.980634 -0.0131562 -0.195408 + outer loop + vertex 891.258 340.291 249.621 + vertex 889.865 348.271 242.09 + vertex 891.354 347.445 249.619 + endloop + endfacet + facet normal 0.977659 -0.0131204 -0.209789 + outer loop + vertex 891.258 340.291 249.621 + vertex 891.354 347.445 249.619 + vertex 892.836 339.343 257.034 + endloop + endfacet + facet normal 0.976952 -0.0160537 -0.212854 + outer loop + vertex 892.836 339.343 257.034 + vertex 891.354 347.445 249.619 + vertex 892.955 346.581 257.033 + endloop + endfacet + facet normal 0.973979 -0.0160063 -0.226072 + outer loop + vertex 892.836 339.343 257.034 + vertex 892.955 346.581 257.033 + vertex 894.506 338.331 264.301 + endloop + endfacet + facet normal 0.973414 -0.0181069 -0.228335 + outer loop + vertex 894.506 338.331 264.301 + vertex 892.955 346.581 257.033 + vertex 894.642 345.657 264.299 + endloop + endfacet + facet normal 0.970671 -0.0180592 -0.239734 + outer loop + vertex 894.506 338.331 264.301 + vertex 894.642 345.657 264.299 + vertex 896.222 337.222 271.331 + endloop + endfacet + facet normal 0.969978 -0.0203617 -0.24234 + outer loop + vertex 896.222 337.222 271.331 + vertex 894.642 345.657 264.299 + vertex 896.378 344.643 271.331 + endloop + endfacet + facet normal 0.967927 -0.0203185 -0.25041 + outer loop + vertex 896.222 337.222 271.331 + vertex 896.378 344.643 271.331 + vertex 897.894 336.026 277.89 + endloop + endfacet + facet normal 0.96714 -0.0226084 -0.253237 + outer loop + vertex 897.894 336.026 277.89 + vertex 896.378 344.643 271.331 + vertex 898.07 343.546 277.89 + endloop + endfacet + facet normal 0.965101 -0.0225602 -0.260905 + outer loop + vertex 897.894 336.026 277.89 + vertex 898.07 343.546 277.89 + vertex 899.405 334.914 283.578 + endloop + endfacet + facet normal 0.964147 -0.0248787 -0.2642 + outer loop + vertex 899.405 334.914 283.578 + vertex 898.07 343.546 277.89 + vertex 899.608 342.497 283.603 + endloop + endfacet + facet normal 0.959484 -0.0246977 -0.28068 + outer loop + vertex 899.405 334.914 283.578 + vertex 899.608 342.497 283.603 + vertex 900.706 334.249 288.082 + endloop + endfacet + facet normal 0.960489 -0.0227751 -0.277386 + outer loop + vertex 900.706 334.249 288.082 + vertex 899.608 342.497 283.603 + vertex 900.888 341.824 288.09 + endloop + endfacet + facet normal 0.949348 -0.0224679 -0.313422 + outer loop + vertex 900.706 334.249 288.082 + vertex 900.888 341.824 288.09 + vertex 901.787 334.617 291.329 + endloop + endfacet + facet normal 0.95406 -0.0154949 -0.299214 + outer loop + vertex 901.787 334.617 291.329 + vertex 900.888 341.824 288.09 + vertex 901.903 341.898 291.323 + endloop + endfacet + facet normal 0.953658 0.0234977 -0.299974 + outer loop + vertex 900.888 341.824 288.09 + vertex 900.697 349.476 288.081 + vertex 901.903 341.898 291.323 + endloop + endfacet + facet normal 0.9565 0.0280545 -0.29038 + outer loop + vertex 901.903 341.898 291.323 + vertex 900.697 349.476 288.081 + vertex 901.682 349.513 291.332 + endloop + endfacet + facet normal 0.954945 0.0617372 -0.290291 + outer loop + vertex 900.697 349.476 288.081 + vertex 900.191 357.208 288.064 + vertex 901.682 349.513 291.332 + endloop + endfacet + facet normal 0.957024 0.065436 -0.282529 + outer loop + vertex 901.682 349.513 291.332 + vertex 900.191 357.208 288.064 + vertex 901.133 357.354 291.288 + endloop + endfacet + facet normal 0.954249 0.0962102 -0.283112 + outer loop + vertex 900.191 357.208 288.064 + vertex 899.415 364.88 288.055 + vertex 901.133 357.354 291.288 + endloop + endfacet + facet normal 0.956409 0.100542 -0.274178 + outer loop + vertex 901.133 357.354 291.288 + vertex 899.415 364.88 288.055 + vertex 900.326 365.053 291.296 + endloop + endfacet + facet normal 0.952973 0.128034 -0.27468 + outer loop + vertex 899.415 364.88 288.055 + vertex 898.397 372.469 288.059 + vertex 900.326 365.053 291.296 + endloop + endfacet + facet normal 0.955088 0.132867 -0.264866 + outer loop + vertex 900.326 365.053 291.296 + vertex 898.397 372.469 288.059 + vertex 899.254 372.789 291.309 + endloop + endfacet + facet normal 0.951283 0.155712 -0.266109 + outer loop + vertex 898.397 372.469 288.059 + vertex 897.162 380.014 288.06 + vertex 899.254 372.789 291.309 + endloop + endfacet + facet normal 0.952473 0.158831 -0.25994 + outer loop + vertex 899.254 372.789 291.309 + vertex 897.162 380.014 288.06 + vertex 897.989 380.364 291.303 + endloop + endfacet + facet normal 0.944946 0.157553 -0.2868 + outer loop + vertex 899.254 372.789 291.309 + vertex 897.989 380.364 291.303 + vertex 899.261 375.657 292.91 + endloop + endfacet + facet normal 0.94493 0.157526 -0.286867 + outer loop + vertex 898.641 379.288 292.862 + vertex 899.261 375.657 292.91 + vertex 897.989 380.364 291.303 + endloop + endfacet + facet normal 0.948464 0.179489 -0.261152 + outer loop + vertex 897.162 380.014 288.06 + vertex 895.736 387.555 288.064 + vertex 897.989 380.364 291.303 + endloop + endfacet + facet normal 0.949329 0.181973 -0.256241 + outer loop + vertex 897.989 380.364 291.303 + vertex 895.736 387.555 288.064 + vertex 896.573 388.033 291.504 + endloop + endfacet + facet normal 0.940772 0.181186 -0.286565 + outer loop + vertex 897.989 380.364 291.303 + vertex 896.573 388.033 291.504 + vertex 898.037 382.312 292.693 + endloop + endfacet + facet normal 0.942819 0.18343 -0.27829 + outer loop + vertex 897.592 385.291 293.15 + vertex 898.037 382.312 292.693 + vertex 896.573 388.033 291.504 + endloop + endfacet + facet normal 0.945127 0.20066 -0.257817 + outer loop + vertex 895.736 387.555 288.064 + vertex 894.111 395.179 288.042 + vertex 896.573 388.033 291.504 + endloop + endfacet + facet normal 0.946125 0.204138 -0.251348 + outer loop + vertex 896.573 388.033 291.504 + vertex 894.111 395.179 288.042 + vertex 894.716 396.405 291.313 + endloop + endfacet + facet normal 0.93854 0.201799 -0.280035 + outer loop + vertex 896.573 388.033 291.504 + vertex 894.716 396.405 291.313 + vertex 896.139 392.034 292.931 + endloop + endfacet + facet normal 0.939613 0.200867 -0.277093 + outer loop + vertex 896.139 392.034 292.931 + vertex 896.974 388.211 292.995 + vertex 896.573 388.033 291.504 + endloop + endfacet + facet normal 0.943174 0.184856 -0.276135 + outer loop + vertex 896.974 388.211 292.995 + vertex 897.592 385.291 293.15 + vertex 896.573 388.033 291.504 + endloop + endfacet + facet normal 0.953492 0.189248 -0.234603 + outer loop + vertex 897.592 385.291 293.15 + vertex 896.974 388.211 292.995 + vertex 897.136 389.121 294.384 + endloop + endfacet + facet normal 0.94841 0.203354 -0.243241 + outer loop + vertex 896.974 388.211 292.995 + vertex 896.139 392.034 292.931 + vertex 897.136 389.121 294.384 + endloop + endfacet + facet normal 0.949434 0.207506 -0.235619 + outer loop + vertex 895.455 396.828 294.397 + vertex 897.136 389.121 294.384 + vertex 896.139 392.034 292.931 + endloop + endfacet + facet normal 0.944096 0.206378 -0.257081 + outer loop + vertex 895.455 396.828 294.397 + vertex 896.439 395.656 297.072 + vertex 897.136 389.121 294.384 + endloop + endfacet + facet normal 0.947598 0.202607 -0.247001 + outer loop + vertex 897.136 389.121 294.384 + vertex 896.439 395.656 297.072 + vertex 898.175 387.526 297.065 + endloop + endfacet + facet normal 0.948353 0.184319 -0.258171 + outer loop + vertex 897.136 389.121 294.384 + vertex 898.175 387.526 297.065 + vertex 898.688 380.893 294.21 + endloop + endfacet + facet normal 0.951703 0.180389 -0.248437 + outer loop + vertex 898.688 380.893 294.21 + vertex 898.175 387.526 297.065 + vertex 899.772 379.152 297.1 + endloop + endfacet + facet normal 0.952031 0.159804 -0.260959 + outer loop + vertex 898.688 380.893 294.21 + vertex 899.772 379.152 297.1 + vertex 900.16 372.388 294.373 + endloop + endfacet + facet normal 0.955225 0.156111 -0.251346 + outer loop + vertex 900.16 372.388 294.373 + vertex 899.772 379.152 297.1 + vertex 901.141 370.815 297.125 + endloop + endfacet + facet normal 0.955161 0.132961 -0.264553 + outer loop + vertex 900.16 372.388 294.373 + vertex 901.141 370.815 297.125 + vertex 901.281 364.319 294.365 + endloop + endfacet + facet normal 0.959352 0.127599 -0.25172 + outer loop + vertex 901.281 364.319 294.365 + vertex 901.141 370.815 297.125 + vertex 902.228 362.636 297.123 + endloop + endfacet + facet normal 0.958181 0.100162 -0.26806 + outer loop + vertex 901.281 364.319 294.365 + vertex 902.228 362.636 297.123 + vertex 902.11 356.354 294.352 + endloop + endfacet + facet normal 0.962118 0.0946277 -0.255685 + outer loop + vertex 902.11 356.354 294.352 + vertex 902.228 362.636 297.123 + vertex 903.032 354.418 297.106 + endloop + endfacet + facet normal 0.958769 0.0623398 -0.277263 + outer loop + vertex 902.11 356.354 294.352 + vertex 903.032 354.418 297.106 + vertex 902.642 348.138 294.345 + endloop + endfacet + facet normal 0.963297 0.0556186 -0.262614 + outer loop + vertex 902.642 348.138 294.345 + vertex 903.032 354.418 297.106 + vertex 903.515 345.966 297.089 + endloop + endfacet + facet normal 0.957042 0.0194015 -0.289299 + outer loop + vertex 902.642 348.138 294.345 + vertex 903.515 345.966 297.089 + vertex 902.782 339.216 294.209 + endloop + endfacet + facet normal 0.962463 0.0110837 -0.271188 + outer loop + vertex 902.782 339.216 294.209 + vertex 903.515 345.966 297.089 + vertex 903.616 337.428 297.095 + endloop + endfacet + facet normal 0.951303 0.0109246 -0.308065 + outer loop + vertex 903.515 345.966 297.089 + vertex 904.77 344.494 300.912 + vertex 903.616 337.428 297.095 + endloop + endfacet + facet normal 0.951568 0.0104468 -0.30726 + outer loop + vertex 903.616 337.428 297.095 + vertex 904.77 344.494 300.912 + vertex 904.863 335.984 300.908 + endloop + endfacet + facet normal 0.948173 0.0104145 -0.317585 + outer loop + vertex 904.77 344.494 300.912 + vertex 906.387 342.97 305.689 + vertex 904.863 335.984 300.908 + endloop + endfacet + facet normal 0.946952 0.0130932 -0.321109 + outer loop + vertex 904.863 335.984 300.908 + vertex 906.387 342.97 305.689 + vertex 906.506 334.342 305.688 + endloop + endfacet + facet normal 0.945919 0.013079 -0.324138 + outer loop + vertex 906.506 334.342 305.688 + vertex 906.387 342.97 305.689 + vertex 907.571 340.361 309.038 + endloop + endfacet + facet normal 0.942847 0.0183968 -0.332718 + outer loop + vertex 907.826 336.227 309.532 + vertex 906.506 334.342 305.688 + vertex 907.571 340.361 309.038 + endloop + endfacet + facet normal 0.946379 -0.00381663 -0.323035 + outer loop + vertex 907.826 336.227 309.532 + vertex 907.639 331.653 309.038 + vertex 906.506 334.342 305.688 + endloop + endfacet + facet normal 0.936612 -0.0392377 -0.348163 + outer loop + vertex 906.148 325.808 305.686 + vertex 906.506 334.342 305.688 + vertex 907.639 331.653 309.038 + endloop + endfacet + facet normal 0.933369 -0.0331198 -0.357387 + outer loop + vertex 907.684 327.592 309.533 + vertex 906.148 325.808 305.686 + vertex 907.639 331.653 309.038 + endloop + endfacet + facet normal 0.936304 -0.0602403 -0.345984 + outer loop + vertex 907.684 327.592 309.533 + vertex 907.213 323.128 309.036 + vertex 906.148 325.808 305.686 + endloop + endfacet + facet normal 0.922389 -0.0997517 -0.373159 + outer loop + vertex 905.236 317.398 305.681 + vertex 906.148 325.808 305.686 + vertex 907.213 323.128 309.036 + endloop + endfacet + facet normal 0.918444 -0.0915719 -0.384804 + outer loop + vertex 907.022 319.143 309.527 + vertex 905.236 317.398 305.681 + vertex 907.213 323.128 309.036 + endloop + endfacet + facet normal 0.920414 -0.126144 -0.370034 + outer loop + vertex 907.022 319.143 309.527 + vertex 906.218 314.741 309.028 + vertex 905.236 317.398 305.681 + endloop + endfacet + facet normal 0.902227 -0.167385 -0.397453 + outer loop + vertex 903.69 309.026 305.696 + vertex 905.236 317.398 305.681 + vertex 906.218 314.741 309.028 + endloop + endfacet + facet normal 0.897651 -0.156999 -0.411794 + outer loop + vertex 905.746 310.771 309.514 + vertex 903.69 309.026 305.696 + vertex 906.218 314.741 309.028 + endloop + endfacet + facet normal 0.897936 -0.194714 -0.394711 + outer loop + vertex 905.746 310.771 309.514 + vertex 904.571 306.333 309.03 + vertex 903.69 309.026 305.696 + endloop + endfacet + facet normal 0.875069 -0.236413 -0.422331 + outer loop + vertex 901.441 300.561 305.775 + vertex 903.69 309.026 305.696 + vertex 904.571 306.333 309.03 + endloop + endfacet + facet normal 0.871846 -0.228543 -0.433188 + outer loop + vertex 903.771 302.324 309.535 + vertex 901.441 300.561 305.775 + vertex 904.571 306.333 309.03 + endloop + endfacet + facet normal 0.870472 -0.262298 -0.416508 + outer loop + vertex 903.771 302.324 309.535 + vertex 902.212 297.817 309.114 + vertex 901.441 300.561 305.775 + endloop + endfacet + facet normal 0.846458 -0.298631 -0.440827 + outer loop + vertex 898.432 291.819 305.919 + vertex 901.441 300.561 305.775 + vertex 902.212 297.817 309.114 + endloop + endfacet + facet normal 0.843931 -0.292217 -0.449878 + outer loop + vertex 901.158 293.872 309.699 + vertex 898.432 291.819 305.919 + vertex 902.212 297.817 309.114 + endloop + endfacet + facet normal 0.842329 -0.320262 -0.433491 + outer loop + vertex 901.158 293.872 309.699 + vertex 899.44 289.744 309.41 + vertex 898.432 291.819 305.919 + endloop + endfacet + facet normal 0.83088 -0.33896 -0.441299 + outer loop + vertex 899.44 289.744 309.41 + vertex 896.641 286.208 306.857 + vertex 898.432 291.819 305.919 + endloop + endfacet + facet normal 0.826919 -0.338933 -0.448698 + outer loop + vertex 895.583 286.665 304.562 + vertex 898.432 291.819 305.919 + vertex 896.641 286.208 306.857 + endloop + endfacet + facet normal 0.802569 -0.309305 -0.510112 + outer loop + vertex 893.438 286.042 301.565 + vertex 898.432 291.819 305.919 + vertex 895.583 286.665 304.562 + endloop + endfacet + facet normal 0.814384 -0.362325 -0.45332 + outer loop + vertex 896.857 294.221 301.17 + vertex 898.432 291.819 305.919 + vertex 893.438 286.042 301.565 + endloop + endfacet + facet normal 0.825898 -0.365957 -0.428915 + outer loop + vertex 892.217 288.149 297.417 + vertex 896.857 294.221 301.17 + vertex 893.438 286.042 301.565 + endloop + endfacet + facet normal 0.827303 -0.371923 -0.421002 + outer loop + vertex 895.688 296.108 297.205 + vertex 896.857 294.221 301.17 + vertex 892.217 288.149 297.417 + endloop + endfacet + facet normal 0.853045 -0.381424 -0.356133 + outer loop + vertex 891.687 289.87 294.302 + vertex 895.688 296.108 297.205 + vertex 892.217 288.149 297.417 + endloop + endfacet + facet normal 0.851103 -0.374858 -0.367566 + outer loop + vertex 895.27 298.078 294.228 + vertex 895.688 296.108 297.205 + vertex 891.687 289.87 294.302 + endloop + endfacet + facet normal 0.834661 -0.359007 -0.417678 + outer loop + vertex 897.634 285.242 309.672 + vertex 896.641 286.208 306.857 + vertex 899.44 289.744 309.41 + endloop + endfacet + facet normal 0.818318 -0.389721 -0.422461 + outer loop + vertex 896.641 286.208 306.857 + vertex 897.634 285.242 309.672 + vertex 894.739 281.808 307.233 + endloop + endfacet + facet normal 0.799702 -0.384948 -0.46075 + outer loop + vertex 893.609 282.878 304.377 + vertex 896.641 286.208 306.857 + vertex 894.739 281.808 307.233 + endloop + endfacet + facet normal 0.782264 -0.414584 -0.464956 + outer loop + vertex 893.609 282.878 304.377 + vertex 894.739 281.808 307.233 + vertex 891.92 278.987 305.005 + endloop + endfacet + facet normal 0.755751 -0.410398 -0.510308 + outer loop + vertex 891.92 278.987 305.005 + vertex 889.192 278.184 301.611 + vertex 893.609 282.878 304.377 + endloop + endfacet + facet normal 0.756057 -0.411458 -0.508998 + outer loop + vertex 889.192 278.184 301.611 + vertex 893.438 286.042 301.565 + vertex 893.609 282.878 304.377 + endloop + endfacet + facet normal 0.786201 -0.38621 -0.482421 + outer loop + vertex 895.583 286.665 304.562 + vertex 893.609 282.878 304.377 + vertex 893.438 286.042 301.565 + endloop + endfacet + facet normal 0.783621 -0.426024 -0.452152 + outer loop + vertex 888.178 280.551 297.623 + vertex 893.438 286.042 301.565 + vertex 889.192 278.184 301.611 + endloop + endfacet + facet normal 0.784048 -0.428977 -0.448607 + outer loop + vertex 892.217 288.149 297.417 + vertex 893.438 286.042 301.565 + vertex 888.178 280.551 297.623 + endloop + endfacet + facet normal 0.812663 -0.442309 -0.379397 + outer loop + vertex 887.903 282.67 294.564 + vertex 892.217 288.149 297.417 + vertex 888.178 280.551 297.623 + endloop + endfacet + facet normal 0.812329 -0.44071 -0.381963 + outer loop + vertex 891.687 289.87 294.302 + vertex 892.217 288.149 297.417 + vertex 887.903 282.67 294.564 + endloop + endfacet + facet normal 0.746396 -0.445347 -0.494529 + outer loop + vertex 891.92 278.987 305.005 + vertex 889.368 275.096 304.657 + vertex 889.192 278.184 301.611 + endloop + endfacet + facet normal 0.717139 -0.468314 -0.516134 + outer loop + vertex 884.554 270.886 301.788 + vertex 889.192 278.184 301.611 + vertex 889.368 275.096 304.657 + endloop + endfacet + facet normal 0.715157 -0.457901 -0.528088 + outer loop + vertex 887.453 271.54 305.147 + vertex 884.554 270.886 301.788 + vertex 889.368 275.096 304.657 + endloop + endfacet + facet normal 0.741173 -0.465753 -0.483464 + outer loop + vertex 889.368 275.096 304.657 + vertex 890.51 274.022 307.441 + vertex 887.453 271.54 305.147 + endloop + endfacet + facet normal 0.741232 -0.467234 -0.481941 + outer loop + vertex 887.453 271.54 305.147 + vertex 890.51 274.022 307.441 + vertex 888.248 270.423 307.451 + endloop + endfacet + facet normal 0.714983 -0.499935 -0.488738 + outer loop + vertex 887.453 271.54 305.147 + vertex 888.248 270.423 307.451 + vertex 884.679 267.963 304.748 + endloop + endfacet + facet normal 0.715444 -0.484288 -0.503592 + outer loop + vertex 884.679 267.963 304.748 + vertex 888.248 270.423 307.451 + vertex 885.876 266.905 307.466 + endloop + endfacet + facet normal 0.698376 -0.507203 -0.504992 + outer loop + vertex 884.679 267.963 304.748 + vertex 885.876 266.905 307.466 + vertex 882.578 264.581 305.239 + endloop + endfacet + facet normal 0.672374 -0.497329 -0.54825 + outer loop + vertex 882.578 264.581 305.239 + vertex 879.521 264.033 301.988 + vertex 884.679 267.963 304.748 + endloop + endfacet + facet normal 0.674506 -0.510847 -0.53299 + outer loop + vertex 879.521 264.033 301.988 + vertex 884.554 270.886 301.788 + vertex 884.679 267.963 304.748 + endloop + endfacet + facet normal 0.663346 -0.522716 -0.535481 + outer loop + vertex 882.578 264.581 305.239 + vertex 879.567 261.111 304.896 + vertex 879.521 264.033 301.988 + endloop + endfacet + facet normal 0.630436 -0.542681 -0.55502 + outer loop + vertex 874.139 257.445 302.316 + vertex 879.521 264.033 301.988 + vertex 879.567 261.111 304.896 + endloop + endfacet + facet normal 0.627839 -0.5251 -0.574533 + outer loop + vertex 877.283 257.79 305.435 + vertex 874.139 257.445 302.316 + vertex 879.567 261.111 304.896 + endloop + endfacet + facet normal 0.655313 -0.536975 -0.531246 + outer loop + vertex 879.567 261.111 304.896 + vertex 880.791 259.971 307.558 + vertex 877.283 257.79 305.435 + endloop + endfacet + facet normal 0.655272 -0.532267 -0.536014 + outer loop + vertex 877.283 257.79 305.435 + vertex 880.791 259.971 307.558 + vertex 878.12 256.597 307.643 + endloop + endfacet + facet normal 0.629157 -0.558692 -0.540393 + outer loop + vertex 877.283 257.79 305.435 + vertex 878.12 256.597 307.643 + vertex 874.095 254.431 305.197 + endloop + endfacet + facet normal 0.630019 -0.536563 -0.561405 + outer loop + vertex 874.095 254.431 305.197 + vertex 878.12 256.597 307.643 + vertex 875.41 253.287 307.766 + endloop + endfacet + facet normal 0.613255 -0.555711 -0.561342 + outer loop + vertex 874.095 254.431 305.197 + vertex 875.41 253.287 307.766 + vertex 871.761 251.23 305.816 + endloop + endfacet + facet normal 0.586046 -0.543528 -0.600939 + outer loop + vertex 871.761 251.23 305.816 + vertex 868.333 250.961 302.716 + vertex 874.095 254.431 305.197 + endloop + endfacet + facet normal 0.588761 -0.563044 -0.579949 + outer loop + vertex 868.333 250.961 302.716 + vertex 874.139 257.445 302.316 + vertex 874.095 254.431 305.197 + endloop + endfacet + facet normal 0.598519 -0.570687 -0.56222 + outer loop + vertex 867.771 254.029 299.003 + vertex 874.139 257.445 302.316 + vertex 868.333 250.961 302.716 + endloop + endfacet + facet normal 0.598347 -0.592161 -0.539746 + outer loop + vertex 873.146 259.982 298.431 + vertex 874.139 257.445 302.316 + vertex 867.771 254.029 299.003 + endloop + endfacet + facet normal 0.61539 -0.604313 -0.506064 + outer loop + vertex 866.983 255.937 295.767 + vertex 873.146 259.982 298.431 + vertex 867.771 254.029 299.003 + endloop + endfacet + facet normal 0.617128 -0.628137 -0.473917 + outer loop + vertex 872.84 262.149 295.161 + vertex 873.146 259.982 298.431 + vertex 866.983 255.937 295.767 + endloop + endfacet + facet normal 0.581108 -0.555869 -0.594409 + outer loop + vertex 871.761 251.23 305.816 + vertex 868.705 248.172 305.688 + vertex 868.333 250.961 302.716 + endloop + endfacet + facet normal 0.556333 -0.570037 -0.604608 + outer loop + vertex 868.705 248.172 305.688 + vertex 864.734 246.514 303.597 + vertex 868.333 250.961 302.716 + endloop + endfacet + facet normal 0.553899 -0.568749 -0.608047 + outer loop + vertex 864.042 247.82 301.745 + vertex 868.333 250.961 302.716 + vertex 864.734 246.514 303.597 + endloop + endfacet + facet normal 0.523441 -0.591853 -0.612959 + outer loop + vertex 864.042 247.82 301.745 + vertex 864.734 246.514 303.597 + vertex 861.262 245.49 301.621 + endloop + endfacet + facet normal 0.524713 -0.593514 -0.61026 + outer loop + vertex 864.042 247.82 301.745 + vertex 861.262 245.49 301.621 + vertex 862.663 248.799 299.607 + endloop + endfacet + facet normal 0.525776 -0.577609 -0.624441 + outer loop + vertex 861.262 245.49 301.621 + vertex 864.734 246.514 303.597 + vertex 861.545 243.178 303.997 + endloop + endfacet + facet normal 0.489413 -0.595258 -0.637294 + outer loop + vertex 861.262 245.49 301.621 + vertex 861.545 243.178 303.997 + vertex 857.922 242.513 301.837 + endloop + endfacet + facet normal 0.488514 -0.594361 -0.638818 + outer loop + vertex 857.922 242.513 301.837 + vertex 858.033 245.119 299.496 + vertex 861.262 245.49 301.621 + endloop + endfacet + facet normal 0.488257 -0.595139 -0.63829 + outer loop + vertex 862.663 248.799 299.607 + vertex 861.262 245.49 301.621 + vertex 858.033 245.119 299.496 + endloop + endfacet + facet normal 0.494845 -0.573059 -0.653247 + outer loop + vertex 857.922 242.513 301.837 + vertex 861.545 243.178 303.997 + vertex 858.488 240.214 304.282 + endloop + endfacet + facet normal 0.458981 -0.591849 -0.662609 + outer loop + vertex 857.922 242.513 301.837 + vertex 858.488 240.214 304.282 + vertex 855.074 240.012 302.097 + endloop + endfacet + facet normal 0.453742 -0.586724 -0.670726 + outer loop + vertex 857.922 242.513 301.837 + vertex 855.074 240.012 302.097 + vertex 854.818 242.468 299.776 + endloop + endfacet + facet normal 0.444877 -0.608749 -0.656894 + outer loop + vertex 854.818 242.468 299.776 + vertex 858.033 245.119 299.496 + vertex 857.922 242.513 301.837 + endloop + endfacet + facet normal 0.449502 -0.613548 -0.649235 + outer loop + vertex 854.908 244.624 297.801 + vertex 858.033 245.119 299.496 + vertex 854.818 242.468 299.776 + endloop + endfacet + facet normal 0.470408 -0.558057 -0.683585 + outer loop + vertex 855.074 240.012 302.097 + vertex 858.488 240.214 304.282 + vertex 855.851 237.735 304.492 + endloop + endfacet + facet normal 0.436076 -0.577068 -0.690528 + outer loop + vertex 855.074 240.012 302.097 + vertex 855.851 237.735 304.492 + vertex 852.824 237.92 302.425 + endloop + endfacet + facet normal 0.428828 -0.570795 -0.700214 + outer loop + vertex 852.824 237.92 302.425 + vertex 852.511 240.564 300.078 + vertex 855.074 240.012 302.097 + endloop + endfacet + facet normal 0.454305 -0.533617 -0.713344 + outer loop + vertex 852.824 237.92 302.425 + vertex 855.851 237.735 304.492 + vertex 854.119 235.758 304.867 + endloop + endfacet + facet normal 0.441919 -0.542367 -0.714524 + outer loop + vertex 852.824 237.92 302.425 + vertex 854.119 235.758 304.867 + vertex 852.545 235.797 303.864 + endloop + endfacet + facet normal 0.391721 -0.55093 -0.736906 + outer loop + vertex 852.824 237.92 302.425 + vertex 852.545 235.797 303.864 + vertex 850.852 236.849 302.177 + endloop + endfacet + facet normal 0.398758 -0.567779 -0.720152 + outer loop + vertex 851.063 239.414 300.272 + vertex 852.824 237.92 302.425 + vertex 850.852 236.849 302.177 + endloop + endfacet + facet normal 0.35341 -0.576402 -0.736792 + outer loop + vertex 850.852 236.849 302.177 + vertex 849.46 240.007 299.039 + vertex 851.063 239.414 300.272 + endloop + endfacet + facet normal 0.347701 -0.579332 -0.73721 + outer loop + vertex 849.46 240.007 299.039 + vertex 850.852 236.849 302.177 + vertex 847.756 236.464 301.02 + endloop + endfacet + facet normal 0.353377 -0.535625 -0.766962 + outer loop + vertex 849.67 234.386 303.353 + vertex 847.756 236.464 301.02 + vertex 850.852 236.849 302.177 + endloop + endfacet + facet normal 0.38847 -0.542062 -0.745158 + outer loop + vertex 851.499 234.669 304.101 + vertex 849.67 234.386 303.353 + vertex 850.852 236.849 302.177 + endloop + endfacet + facet normal 0.421699 -0.526238 -0.738406 + outer loop + vertex 850.852 236.849 302.177 + vertex 852.848 234.277 305.15 + vertex 851.499 234.669 304.101 + endloop + endfacet + facet normal 0.429008 -0.513589 -0.743087 + outer loop + vertex 852.497 233.414 305.545 + vertex 851.499 234.669 304.101 + vertex 852.848 234.277 305.15 + endloop + endfacet + facet normal 0.459336 -0.516552 -0.722624 + outer loop + vertex 853.694 232.427 307.011 + vertex 852.497 233.414 305.545 + vertex 852.848 234.277 305.15 + endloop + endfacet + facet normal 0.48745 -0.498146 -0.717108 + outer loop + vertex 852.848 234.277 305.15 + vertex 854.613 232.502 307.583 + vertex 853.694 232.427 307.011 + endloop + endfacet + facet normal 0.457455 -0.518516 -0.72241 + outer loop + vertex 853.694 232.427 307.011 + vertex 852.506 231.434 306.971 + vertex 852.497 233.414 305.545 + endloop + endfacet + facet normal 0.426565 -0.527508 -0.734695 + outer loop + vertex 852.497 233.414 305.545 + vertex 852.506 231.434 306.971 + vertex 851.169 232.766 305.239 + endloop + endfacet + facet normal 0.44222 -0.513055 -0.735674 + outer loop + vertex 852.506 231.434 306.971 + vertex 850.415 229.526 307.045 + vertex 851.169 232.766 305.239 + endloop + endfacet + facet normal 0.409985 -0.515072 -0.752737 + outer loop + vertex 851.169 232.766 305.239 + vertex 850.415 229.526 307.045 + vertex 848.879 230.946 305.236 + endloop + endfacet + facet normal 0.405163 -0.508995 -0.759452 + outer loop + vertex 851.169 232.766 305.239 + vertex 848.879 230.946 305.236 + vertex 849.67 234.386 303.353 + endloop + endfacet + facet normal 0.424079 -0.501529 -0.754073 + outer loop + vertex 850.415 229.526 307.045 + vertex 847.529 226.75 307.268 + vertex 848.879 230.946 305.236 + endloop + endfacet + facet normal 0.387778 -0.499753 -0.774516 + outer loop + vertex 848.879 230.946 305.236 + vertex 847.529 226.75 307.268 + vertex 845.947 228.091 305.611 + endloop + endfacet + facet normal 0.376566 -0.489787 -0.786325 + outer loop + vertex 848.879 230.946 305.236 + vertex 845.947 228.091 305.611 + vertex 846.91 232.227 303.496 + endloop + endfacet + facet normal 0.358868 -0.51041 -0.78147 + outer loop + vertex 849.67 234.386 303.353 + vertex 848.879 230.946 305.236 + vertex 846.91 232.227 303.496 + endloop + endfacet + facet normal 0.40042 -0.48695 -0.776237 + outer loop + vertex 847.529 226.75 307.268 + vertex 844.161 223.502 307.568 + vertex 845.947 228.091 305.611 + endloop + endfacet + facet normal 0.358703 -0.480879 -0.800054 + outer loop + vertex 845.947 228.091 305.611 + vertex 844.161 223.502 307.568 + vertex 842.66 224.887 306.063 + endloop + endfacet + facet normal 0.346737 -0.470229 -0.811577 + outer loop + vertex 845.947 228.091 305.611 + vertex 842.66 224.887 306.063 + vertex 844.241 229.016 304.346 + endloop + endfacet + facet normal 0.332218 -0.489608 -0.806173 + outer loop + vertex 846.91 232.227 303.496 + vertex 845.947 228.091 305.611 + vertex 844.241 229.016 304.346 + endloop + endfacet + facet normal 0.372909 -0.46722 -0.801651 + outer loop + vertex 844.161 223.502 307.568 + vertex 840.591 220.159 307.856 + vertex 842.66 224.887 306.063 + endloop + endfacet + facet normal 0.331601 -0.457931 -0.824827 + outer loop + vertex 842.66 224.887 306.063 + vertex 840.591 220.159 307.856 + vertex 839.166 221.593 306.487 + endloop + endfacet + facet normal 0.317047 -0.444185 -0.837962 + outer loop + vertex 842.66 224.887 306.063 + vertex 839.166 221.593 306.487 + vertex 841.021 226.317 304.685 + endloop + endfacet + facet normal 0.29921 -0.461776 -0.835007 + outer loop + vertex 844.241 229.016 304.346 + vertex 842.66 224.887 306.063 + vertex 841.021 226.317 304.685 + endloop + endfacet + facet normal 0.316626 -0.480402 -0.817901 + outer loop + vertex 844.241 229.016 304.346 + vertex 841.021 226.317 304.685 + vertex 843.722 231.956 302.419 + endloop + endfacet + facet normal 0.317226 -0.480216 -0.817778 + outer loop + vertex 844.241 229.016 304.346 + vertex 843.722 231.956 302.419 + vertex 846.91 232.227 303.496 + endloop + endfacet + facet normal 0.345974 -0.444848 -0.826082 + outer loop + vertex 840.591 220.159 307.856 + vertex 836.997 216.893 308.109 + vertex 839.166 221.593 306.487 + endloop + endfacet + facet normal 0.303693 -0.433119 -0.848633 + outer loop + vertex 839.166 221.593 306.487 + vertex 836.997 216.893 308.109 + vertex 835.656 218.373 306.874 + endloop + endfacet + facet normal 0.285497 -0.415111 -0.863814 + outer loop + vertex 839.166 221.593 306.487 + vertex 835.656 218.373 306.874 + vertex 837.682 222.683 305.473 + endloop + endfacet + facet normal 0.269142 -0.433742 -0.859902 + outer loop + vertex 841.021 226.317 304.685 + vertex 839.166 221.593 306.487 + vertex 837.682 222.683 305.473 + endloop + endfacet + facet normal 0.319049 -0.420005 -0.84959 + outer loop + vertex 836.997 216.893 308.109 + vertex 833.463 213.747 308.338 + vertex 835.656 218.373 306.874 + endloop + endfacet + facet normal 0.28086 -0.407952 -0.868731 + outer loop + vertex 835.656 218.373 306.874 + vertex 833.463 213.747 308.338 + vertex 832.185 215.255 307.216 + endloop + endfacet + facet normal 0.257962 -0.384396 -0.886395 + outer loop + vertex 835.656 218.373 306.874 + vertex 832.185 215.255 307.216 + vertex 834.315 220 305.779 + endloop + endfacet + facet normal 0.238205 -0.399811 -0.885104 + outer loop + vertex 837.682 222.683 305.473 + vertex 835.656 218.373 306.874 + vertex 834.315 220 305.779 + endloop + endfacet + facet normal 0.256262 -0.420769 -0.870221 + outer loop + vertex 837.682 222.683 305.473 + vertex 834.315 220 305.779 + vertex 837.962 226.227 303.841 + endloop + endfacet + facet normal 0.252537 -0.420937 -0.871227 + outer loop + vertex 837.682 222.683 305.473 + vertex 837.962 226.227 303.841 + vertex 841.021 226.317 304.685 + endloop + endfacet + facet normal 0.294967 -0.396472 -0.86937 + outer loop + vertex 833.463 213.747 308.338 + vertex 829.998 210.711 308.547 + vertex 832.185 215.255 307.216 + endloop + endfacet + facet normal 0.258745 -0.384008 -0.886334 + outer loop + vertex 832.185 215.255 307.216 + vertex 829.998 210.711 308.547 + vertex 828.78 212.244 307.527 + endloop + endfacet + facet normal 0.272724 -0.373188 -0.886765 + outer loop + vertex 829.998 210.711 308.547 + vertex 826.576 207.766 308.734 + vertex 828.78 212.244 307.527 + endloop + endfacet + facet normal 0.243806 -0.362408 -0.899566 + outer loop + vertex 828.78 212.244 307.527 + vertex 826.576 207.766 308.734 + vertex 825.413 209.327 307.789 + endloop + endfacet + facet normal 0.255653 -0.353689 -0.899747 + outer loop + vertex 826.576 207.766 308.734 + vertex 823.155 204.881 308.895 + vertex 825.413 209.327 307.789 + endloop + endfacet + facet normal 0.228532 -0.342761 -0.911202 + outer loop + vertex 825.413 209.327 307.789 + vertex 823.155 204.881 308.895 + vertex 822.041 206.466 308.02 + endloop + endfacet + facet normal 0.239059 -0.335385 -0.911245 + outer loop + vertex 823.155 204.881 308.895 + vertex 819.688 202.03 309.035 + vertex 822.041 206.466 308.02 + endloop + endfacet + facet normal 0.220481 -0.32727 -0.918848 + outer loop + vertex 822.041 206.466 308.02 + vertex 819.688 202.03 309.035 + vertex 818.626 203.628 308.211 + endloop + endfacet + facet normal 0.22802 -0.322229 -0.91879 + outer loop + vertex 819.688 202.03 309.035 + vertex 816.154 199.191 309.154 + vertex 818.626 203.628 308.211 + endloop + endfacet + facet normal 0.214476 -0.315847 -0.924252 + outer loop + vertex 818.626 203.628 308.211 + vertex 816.154 199.191 309.154 + vertex 815.152 200.805 308.37 + endloop + endfacet + facet normal 0.219525 -0.312663 -0.924148 + outer loop + vertex 816.154 199.191 309.154 + vertex 812.548 196.366 309.253 + vertex 815.152 200.805 308.37 + endloop + endfacet + facet normal 0.209535 -0.307601 -0.928158 + outer loop + vertex 815.152 200.805 308.37 + vertex 812.548 196.366 309.253 + vertex 811.603 197.999 308.499 + endloop + endfacet + facet normal 0.213839 -0.305047 -0.928019 + outer loop + vertex 812.548 196.366 309.253 + vertex 808.884 193.565 309.329 + vertex 811.603 197.999 308.499 + endloop + endfacet + facet normal 0.20394 -0.299715 -0.931976 + outer loop + vertex 811.603 197.999 308.499 + vertex 808.884 193.565 309.329 + vertex 807.998 195.221 308.603 + endloop + endfacet + facet normal 0.20715 -0.297937 -0.931838 + outer loop + vertex 808.884 193.565 309.329 + vertex 805.179 190.808 309.387 + vertex 807.998 195.221 308.603 + endloop + endfacet + facet normal 0.202223 -0.295139 -0.933809 + outer loop + vertex 807.998 195.221 308.603 + vertex 805.179 190.808 309.387 + vertex 804.349 192.479 308.68 + endloop + endfacet + facet normal 0.202663 -0.294911 -0.933786 + outer loop + vertex 805.179 190.808 309.387 + vertex 801.448 188.106 309.431 + vertex 804.349 192.479 308.68 + endloop + endfacet + facet normal 0.201683 -0.294329 -0.934181 + outer loop + vertex 804.349 192.479 308.68 + vertex 801.448 188.106 309.431 + vertex 800.677 189.795 308.732 + endloop + endfacet + facet normal 0.200557 -0.294872 -0.934252 + outer loop + vertex 801.448 188.106 309.431 + vertex 797.691 185.459 309.46 + vertex 800.677 189.795 308.732 + endloop + endfacet + facet normal 0.199873 -0.294448 -0.934533 + outer loop + vertex 800.677 189.795 308.732 + vertex 797.691 185.459 309.46 + vertex 796.961 187.159 308.768 + endloop + endfacet + facet normal 0.198831 -0.294925 -0.934604 + outer loop + vertex 797.691 185.459 309.46 + vertex 793.883 182.847 309.474 + vertex 796.961 187.159 308.768 + endloop + endfacet + facet normal 0.19584 -0.292993 -0.935843 + outer loop + vertex 796.961 187.159 308.768 + vertex 793.883 182.847 309.474 + vertex 793.173 184.55 308.792 + endloop + endfacet + facet normal 0.192845 -0.294323 -0.936047 + outer loop + vertex 793.883 182.847 309.474 + vertex 789.99 180.266 309.484 + vertex 793.173 184.55 308.792 + endloop + endfacet + facet normal 0.19378 -0.294954 -0.935655 + outer loop + vertex 793.173 184.55 308.792 + vertex 789.99 180.266 309.484 + vertex 789.298 181.968 308.804 + endloop + endfacet + facet normal 0.189385 -0.29686 -0.935953 + outer loop + vertex 789.99 180.266 309.484 + vertex 786.025 177.717 309.49 + vertex 789.298 181.968 308.804 + endloop + endfacet + facet normal 0.191908 -0.29863 -0.934875 + outer loop + vertex 789.298 181.968 308.804 + vertex 786.025 177.717 309.49 + vertex 785.362 179.421 308.809 + endloop + endfacet + facet normal 0.188881 -0.299893 -0.935087 + outer loop + vertex 786.025 177.717 309.49 + vertex 782.036 175.217 309.486 + vertex 785.362 179.421 308.809 + endloop + endfacet + facet normal 0.188206 -0.299406 -0.935379 + outer loop + vertex 785.362 179.421 308.809 + vertex 782.036 175.217 309.486 + vertex 781.406 176.939 308.808 + endloop + endfacet + facet normal 0.182926 -0.301488 -0.935758 + outer loop + vertex 782.036 175.217 309.486 + vertex 778.048 172.797 309.486 + vertex 781.406 176.939 308.808 + endloop + endfacet + facet normal 0.184049 -0.302318 -0.93527 + outer loop + vertex 781.406 176.939 308.808 + vertex 778.048 172.797 309.486 + vertex 777.45 174.533 308.807 + endloop + endfacet + facet normal 0.179765 -0.303917 -0.935585 + outer loop + vertex 778.048 172.797 309.486 + vertex 774.044 170.441 309.482 + vertex 777.45 174.533 308.807 + endloop + endfacet + facet normal 0.181323 -0.3051 -0.934899 + outer loop + vertex 777.45 174.533 308.807 + vertex 774.044 170.441 309.482 + vertex 773.46 172.181 308.801 + endloop + endfacet + facet normal 0.175699 -0.307147 -0.935303 + outer loop + vertex 774.044 170.441 309.482 + vertex 769.955 168.112 309.479 + vertex 773.46 172.181 308.801 + endloop + endfacet + facet normal 0.180423 -0.31086 -0.933174 + outer loop + vertex 773.46 172.181 308.801 + vertex 769.955 168.112 309.479 + vertex 769.371 169.843 308.789 + endloop + endfacet + facet normal 0.178028 -0.311736 -0.933342 + outer loop + vertex 769.955 168.112 309.479 + vertex 765.758 165.771 309.46 + vertex 769.371 169.843 308.789 + endloop + endfacet + facet normal 0.179058 -0.312572 -0.932865 + outer loop + vertex 769.371 169.843 308.789 + vertex 765.758 165.771 309.46 + vertex 765.163 167.503 308.765 + endloop + endfacet + facet normal 0.174882 -0.314115 -0.933139 + outer loop + vertex 765.758 165.771 309.46 + vertex 761.468 163.446 309.439 + vertex 765.163 167.503 308.765 + endloop + endfacet + facet normal 0.181047 -0.319244 -0.930218 + outer loop + vertex 765.163 167.503 308.765 + vertex 761.468 163.446 309.439 + vertex 760.885 165.177 308.731 + endloop + endfacet + facet normal 0.177189 -0.32065 -0.930477 + outer loop + vertex 761.468 163.446 309.439 + vertex 757.174 161.17 309.405 + vertex 760.885 165.177 308.731 + endloop + endfacet + facet normal 0.183533 -0.326003 -0.927382 + outer loop + vertex 760.885 165.177 308.731 + vertex 757.174 161.17 309.405 + vertex 756.606 162.905 308.683 + endloop + endfacet + facet normal 0.179843 -0.32732 -0.927641 + outer loop + vertex 757.174 161.17 309.405 + vertex 752.931 158.969 309.359 + vertex 756.606 162.905 308.683 + endloop + endfacet + facet normal 0.189071 -0.335137 -0.923003 + outer loop + vertex 756.606 162.905 308.683 + vertex 752.931 158.969 309.359 + vertex 752.376 160.709 308.614 + endloop + endfacet + facet normal 0.184132 -0.33687 -0.923371 + outer loop + vertex 752.931 158.969 309.359 + vertex 748.729 156.839 309.298 + vertex 752.376 160.709 308.614 + endloop + endfacet + facet normal 0.194943 -0.34606 -0.917736 + outer loop + vertex 752.376 160.709 308.614 + vertex 748.729 156.839 309.298 + vertex 748.176 158.582 308.524 + endloop + endfacet + facet normal 0.190434 -0.347645 -0.918084 + outer loop + vertex 748.729 156.839 309.298 + vertex 744.516 154.743 309.218 + vertex 748.176 158.582 308.524 + endloop + endfacet + facet normal 0.2024 -0.357875 -0.91157 + outer loop + vertex 748.176 158.582 308.524 + vertex 744.516 154.743 309.218 + vertex 743.952 156.48 308.411 + endloop + endfacet + facet normal 0.197109 -0.359781 -0.911979 + outer loop + vertex 744.516 154.743 309.218 + vertex 740.247 152.654 309.119 + vertex 743.952 156.48 308.411 + endloop + endfacet + facet normal 0.210229 -0.371101 -0.904482 + outer loop + vertex 743.952 156.48 308.411 + vertex 740.247 152.654 309.119 + vertex 739.677 154.393 308.274 + endloop + endfacet + facet normal 0.203439 -0.373585 -0.905012 + outer loop + vertex 740.247 152.654 309.119 + vertex 735.921 150.573 309.006 + vertex 739.677 154.393 308.274 + endloop + endfacet + facet normal 0.223528 -0.391006 -0.892832 + outer loop + vertex 739.677 154.393 308.274 + vertex 735.921 150.573 309.006 + vertex 735.35 152.31 308.103 + endloop + endfacet + facet normal 0.214539 -0.394346 -0.893568 + outer loop + vertex 735.921 150.573 309.006 + vertex 731.586 148.517 308.873 + vertex 735.35 152.31 308.103 + endloop + endfacet + facet normal 0.235377 -0.412294 -0.88012 + outer loop + vertex 735.35 152.31 308.103 + vertex 731.586 148.517 308.873 + vertex 730.994 150.251 307.902 + endloop + endfacet + facet normal 0.226142 -0.415862 -0.880862 + outer loop + vertex 731.586 148.517 308.873 + vertex 727.289 146.511 308.717 + vertex 730.994 150.251 307.902 + endloop + endfacet + facet normal 0.248992 -0.435101 -0.865269 + outer loop + vertex 730.994 150.251 307.902 + vertex 727.289 146.511 308.717 + vertex 726.626 148.23 307.662 + endloop + endfacet + facet normal 0.238106 -0.439741 -0.865987 + outer loop + vertex 727.289 146.511 308.717 + vertex 723.043 144.562 308.539 + vertex 726.626 148.23 307.662 + endloop + endfacet + facet normal 0.265848 -0.462083 -0.846052 + outer loop + vertex 726.626 148.23 307.662 + vertex 723.043 144.562 308.539 + vertex 722.287 146.232 307.389 + endloop + endfacet + facet normal 0.2517 -0.468887 -0.846636 + outer loop + vertex 723.043 144.562 308.539 + vertex 718.796 142.624 308.349 + vertex 722.287 146.232 307.389 + endloop + endfacet + facet normal 0.283261 -0.49303 -0.822609 + outer loop + vertex 722.287 146.232 307.389 + vertex 718.796 142.624 308.349 + vertex 717.956 144.205 307.113 + endloop + endfacet + facet normal 0.267478 -0.501531 -0.822753 + outer loop + vertex 718.796 142.624 308.349 + vertex 714.481 140.635 308.159 + vertex 717.956 144.205 307.113 + endloop + endfacet + facet normal 0.297345 -0.523488 -0.798465 + outer loop + vertex 717.956 144.205 307.113 + vertex 714.481 140.635 308.159 + vertex 713.594 142.144 306.84 + endloop + endfacet + facet normal 0.279468 -0.533713 -0.798153 + outer loop + vertex 714.481 140.635 308.159 + vertex 710.084 138.599 307.981 + vertex 713.594 142.144 306.84 + endloop + endfacet + facet normal 0.306808 -0.553174 -0.774511 + outer loop + vertex 713.594 142.144 306.84 + vertex 710.084 138.599 307.981 + vertex 709.205 140.152 306.524 + endloop + endfacet + facet normal 0.289266 -0.562875 -0.774272 + outer loop + vertex 710.084 138.599 307.981 + vertex 705.784 136.631 307.805 + vertex 709.205 140.152 306.524 + endloop + endfacet + facet normal 0.314283 -0.579155 -0.752201 + outer loop + vertex 709.205 140.152 306.524 + vertex 705.784 136.631 307.805 + vertex 704.824 138.348 306.082 + endloop + endfacet + facet normal 0.300634 -0.586595 -0.752015 + outer loop + vertex 705.784 136.631 307.805 + vertex 702.018 134.941 307.618 + vertex 704.824 138.348 306.082 + endloop + endfacet + facet normal 0.342364 -0.605736 -0.718241 + outer loop + vertex 704.824 138.348 306.082 + vertex 702.018 134.941 307.618 + vertex 700.846 136.609 305.653 + endloop + endfacet + facet normal 0.315941 -0.622089 -0.71637 + outer loop + vertex 702.018 134.941 307.618 + vertex 699.379 133.869 307.385 + vertex 700.846 136.609 305.653 + endloop + endfacet + facet normal 0.357585 -0.628302 -0.690919 + outer loop + vertex 700.846 136.609 305.653 + vertex 699.379 133.869 307.385 + vertex 698.254 135.611 305.219 + endloop + endfacet + facet normal 0.299966 -0.661291 -0.687542 + outer loop + vertex 699.379 133.869 307.385 + vertex 698.096 133.646 307.04 + vertex 698.254 135.611 305.219 + endloop + endfacet + facet normal 0.433595 -0.517768 -0.737504 + outer loop + vertex 847.529 226.75 307.268 + vertex 845.503 222.297 309.203 + vertex 844.161 223.502 307.568 + endloop + endfacet + facet normal 0.44034 -0.511122 -0.738143 + outer loop + vertex 845.503 222.297 309.203 + vertex 841.884 218.929 309.377 + vertex 844.161 223.502 307.568 + endloop + endfacet + facet normal 0.411708 -0.504965 -0.758622 + outer loop + vertex 844.161 223.502 307.568 + vertex 841.884 218.929 309.377 + vertex 840.591 220.159 307.856 + endloop + endfacet + facet normal 0.419153 -0.497881 -0.759227 + outer loop + vertex 841.884 218.929 309.377 + vertex 838.245 215.644 309.522 + vertex 840.591 220.159 307.856 + endloop + endfacet + facet normal 0.390689 -0.4904 -0.779019 + outer loop + vertex 840.591 220.159 307.856 + vertex 838.245 215.644 309.522 + vertex 836.997 216.893 308.109 + endloop + endfacet + facet normal 0.398498 -0.483206 -0.779558 + outer loop + vertex 838.245 215.644 309.522 + vertex 834.664 212.481 309.652 + vertex 836.997 216.893 308.109 + endloop + endfacet + facet normal 0.371621 -0.475273 -0.797504 + outer loop + vertex 836.997 216.893 308.109 + vertex 834.664 212.481 309.652 + vertex 833.463 213.747 308.338 + endloop + endfacet + facet normal 0.378408 -0.469231 -0.797891 + outer loop + vertex 834.664 212.481 309.652 + vertex 831.148 209.431 309.778 + vertex 833.463 213.747 308.338 + endloop + endfacet + facet normal 0.355762 -0.461939 -0.812432 + outer loop + vertex 833.463 213.747 308.338 + vertex 831.148 209.431 309.778 + vertex 829.998 210.711 308.547 + endloop + endfacet + facet normal 0.361946 -0.456639 -0.812696 + outer loop + vertex 831.148 209.431 309.778 + vertex 827.668 206.462 309.896 + vertex 829.998 210.711 308.547 + endloop + endfacet + facet normal 0.341865 -0.449604 -0.825218 + outer loop + vertex 829.998 210.711 308.547 + vertex 827.668 206.462 309.896 + vertex 826.576 207.766 308.734 + endloop + endfacet + facet normal 0.346679 -0.445681 -0.825337 + outer loop + vertex 827.668 206.462 309.896 + vertex 824.183 203.554 310.003 + vertex 826.576 207.766 308.734 + endloop + endfacet + facet normal 0.331298 -0.439782 -0.834765 + outer loop + vertex 826.576 207.766 308.734 + vertex 824.183 203.554 310.003 + vertex 823.155 204.881 308.895 + endloop + endfacet + facet normal 0.334987 -0.436942 -0.834785 + outer loop + vertex 824.183 203.554 310.003 + vertex 820.657 200.676 310.094 + vertex 823.155 204.881 308.895 + endloop + endfacet + facet normal 0.320184 -0.430715 -0.843781 + outer loop + vertex 823.155 204.881 308.895 + vertex 820.657 200.676 310.094 + vertex 819.688 202.03 309.035 + endloop + endfacet + facet normal 0.322239 -0.429226 -0.843758 + outer loop + vertex 820.657 200.676 310.094 + vertex 817.063 197.821 310.174 + vertex 819.688 202.03 309.035 + endloop + endfacet + facet normal 0.312885 -0.424928 -0.849434 + outer loop + vertex 819.688 202.03 309.035 + vertex 817.063 197.821 310.174 + vertex 816.154 199.191 309.154 + endloop + endfacet + facet normal 0.313867 -0.424257 -0.849408 + outer loop + vertex 817.063 197.821 310.174 + vertex 813.4 194.98 310.24 + vertex 816.154 199.191 309.154 + endloop + endfacet + facet normal 0.305646 -0.420172 -0.854421 + outer loop + vertex 816.154 199.191 309.154 + vertex 813.4 194.98 310.24 + vertex 812.548 196.366 309.253 + endloop + endfacet + facet normal 0.305272 -0.420413 -0.854437 + outer loop + vertex 813.4 194.98 310.24 + vertex 809.677 192.169 310.293 + vertex 812.548 196.366 309.253 + endloop + endfacet + facet normal 0.302299 -0.418833 -0.856267 + outer loop + vertex 812.548 196.366 309.253 + vertex 809.677 192.169 310.293 + vertex 808.884 193.565 309.329 + endloop + endfacet + facet normal 0.299488 -0.420536 -0.856421 + outer loop + vertex 809.677 192.169 310.293 + vertex 805.916 189.405 310.334 + vertex 808.884 193.565 309.329 + endloop + endfacet + facet normal 0.299628 -0.420614 -0.856333 + outer loop + vertex 808.884 193.565 309.329 + vertex 805.916 189.405 310.334 + vertex 805.179 190.808 309.387 + endloop + endfacet + facet normal 0.297566 -0.421792 -0.856473 + outer loop + vertex 805.916 189.405 310.334 + vertex 802.134 186.686 310.36 + vertex 805.179 190.808 309.387 + endloop + endfacet + facet normal 0.293857 -0.419606 -0.858824 + outer loop + vertex 805.179 190.808 309.387 + vertex 802.134 186.686 310.36 + vertex 801.448 188.106 309.431 + endloop + endfacet + facet normal 0.289451 -0.42196 -0.859167 + outer loop + vertex 802.134 186.686 310.36 + vertex 798.326 184.032 310.38 + vertex 801.448 188.106 309.431 + endloop + endfacet + facet normal 0.291619 -0.423297 -0.857775 + outer loop + vertex 801.448 188.106 309.431 + vertex 798.326 184.032 310.38 + vertex 797.691 185.459 309.46 + endloop + endfacet + facet normal 0.285548 -0.426343 -0.858309 + outer loop + vertex 798.326 184.032 310.38 + vertex 794.47 181.423 310.393 + vertex 797.691 185.459 309.46 + endloop + endfacet + facet normal 0.292225 -0.430651 -0.853899 + outer loop + vertex 797.691 185.459 309.46 + vertex 794.47 181.423 310.393 + vertex 793.883 182.847 309.474 + endloop + endfacet + facet normal 0.284427 -0.434355 -0.854656 + outer loop + vertex 794.47 181.423 310.393 + vertex 790.545 178.84 310.399 + vertex 793.883 182.847 309.474 + endloop + endfacet + facet normal 0.287108 -0.436168 -0.852834 + outer loop + vertex 793.883 182.847 309.474 + vertex 790.545 178.84 310.399 + vertex 789.99 180.266 309.484 + endloop + endfacet + facet normal 0.2804 -0.43921 -0.853505 + outer loop + vertex 790.545 178.84 310.399 + vertex 786.553 176.288 310.401 + vertex 789.99 180.266 309.484 + endloop + endfacet + facet normal 0.281483 -0.439973 -0.852755 + outer loop + vertex 789.99 180.266 309.484 + vertex 786.553 176.288 310.401 + vertex 786.025 177.717 309.49 + endloop + endfacet + facet normal 0.274824 -0.442867 -0.853429 + outer loop + vertex 786.553 176.288 310.401 + vertex 782.53 173.79 310.402 + vertex 786.025 177.717 309.49 + endloop + endfacet + facet normal 0.281429 -0.447659 -0.848763 + outer loop + vertex 786.025 177.717 309.49 + vertex 782.53 173.79 310.402 + vertex 782.036 175.217 309.486 + endloop + endfacet + facet normal 0.273151 -0.451093 -0.849649 + outer loop + vertex 782.53 173.79 310.402 + vertex 778.51 171.359 310.401 + vertex 782.036 175.217 309.486 + endloop + endfacet + facet normal 0.274149 -0.451835 -0.848933 + outer loop + vertex 782.036 175.217 309.486 + vertex 778.51 171.359 310.401 + vertex 778.048 172.797 309.486 + endloop + endfacet + facet normal 0.266634 -0.454776 -0.849756 + outer loop + vertex 778.51 171.359 310.401 + vertex 774.479 168.996 310.4 + vertex 778.048 172.797 309.486 + endloop + endfacet + facet normal 0.269988 -0.457338 -0.847318 + outer loop + vertex 778.048 172.797 309.486 + vertex 774.479 168.996 310.4 + vertex 774.044 170.441 309.482 + endloop + endfacet + facet normal 0.263484 -0.459763 -0.848053 + outer loop + vertex 774.479 168.996 310.4 + vertex 770.382 166.658 310.395 + vertex 774.044 170.441 309.482 + endloop + endfacet + facet normal 0.261791 -0.458425 -0.849301 + outer loop + vertex 774.044 170.441 309.482 + vertex 770.382 166.658 310.395 + vertex 769.955 168.112 309.479 + endloop + endfacet + facet normal 0.256928 -0.460188 -0.849832 + outer loop + vertex 770.382 166.658 310.395 + vertex 766.178 164.325 310.387 + vertex 769.955 168.112 309.479 + endloop + endfacet + facet normal 0.263312 -0.465402 -0.845025 + outer loop + vertex 769.955 168.112 309.479 + vertex 766.178 164.325 310.387 + vertex 765.758 165.771 309.46 + endloop + endfacet + facet normal 0.255913 -0.468064 -0.845828 + outer loop + vertex 766.178 164.325 310.387 + vertex 761.888 162.002 310.375 + vertex 765.758 165.771 309.46 + endloop + endfacet + facet normal 0.259568 -0.471132 -0.843006 + outer loop + vertex 765.758 165.771 309.46 + vertex 761.888 162.002 310.375 + vertex 761.468 163.446 309.439 + endloop + endfacet + facet normal 0.254851 -0.472825 -0.843497 + outer loop + vertex 761.888 162.002 310.375 + vertex 757.589 159.722 310.354 + vertex 761.468 163.446 309.439 + endloop + endfacet + facet normal 0.259 -0.476348 -0.840245 + outer loop + vertex 761.468 163.446 309.439 + vertex 757.589 159.722 310.354 + vertex 757.174 161.17 309.405 + endloop + endfacet + facet normal 0.253311 -0.478362 -0.840835 + outer loop + vertex 757.589 159.722 310.354 + vertex 753.337 157.519 310.326 + vertex 757.174 161.17 309.405 + endloop + endfacet + facet normal 0.260268 -0.48428 -0.835304 + outer loop + vertex 757.174 161.17 309.405 + vertex 753.337 157.519 310.326 + vertex 752.931 158.969 309.359 + endloop + endfacet + facet normal 0.254187 -0.486406 -0.835941 + outer loop + vertex 753.337 157.519 310.326 + vertex 749.132 155.385 310.289 + vertex 752.931 158.969 309.359 + endloop + endfacet + facet normal 0.26186 -0.492929 -0.829729 + outer loop + vertex 752.931 158.969 309.359 + vertex 749.132 155.385 310.289 + vertex 748.729 156.839 309.298 + endloop + endfacet + facet normal 0.255442 -0.495163 -0.830399 + outer loop + vertex 749.132 155.385 310.289 + vertex 744.922 153.294 310.241 + vertex 748.729 156.839 309.298 + endloop + endfacet + facet normal 0.266822 -0.504865 -0.820925 + outer loop + vertex 748.729 156.839 309.298 + vertex 744.922 153.294 310.241 + vertex 744.516 154.743 309.218 + endloop + endfacet + facet normal 0.258813 -0.507687 -0.821748 + outer loop + vertex 744.922 153.294 310.241 + vertex 740.655 151.215 310.182 + vertex 744.516 154.743 309.218 + endloop + endfacet + facet normal 0.273075 -0.519919 -0.809391 + outer loop + vertex 744.516 154.743 309.218 + vertex 740.655 151.215 310.182 + vertex 740.247 152.654 309.119 + endloop + endfacet + facet normal 0.265238 -0.522728 -0.810187 + outer loop + vertex 740.655 151.215 310.182 + vertex 736.332 149.135 310.109 + vertex 740.247 152.654 309.119 + endloop + endfacet + facet normal 0.277466 -0.533233 -0.799172 + outer loop + vertex 740.247 152.654 309.119 + vertex 736.332 149.135 310.109 + vertex 735.921 150.573 309.006 + endloop + endfacet + facet normal 0.269293 -0.536193 -0.799987 + outer loop + vertex 736.332 149.135 310.109 + vertex 731.996 147.079 310.027 + vertex 735.921 150.573 309.006 + endloop + endfacet + facet normal 0.284752 -0.549349 -0.785577 + outer loop + vertex 735.921 150.573 309.006 + vertex 731.996 147.079 310.027 + vertex 731.586 148.517 308.873 + endloop + endfacet + facet normal 0.27432 -0.553156 -0.786617 + outer loop + vertex 731.996 147.079 310.027 + vertex 727.708 145.079 309.938 + vertex 731.586 148.517 308.873 + endloop + endfacet + facet normal 0.293575 -0.569127 -0.768055 + outer loop + vertex 731.586 148.517 308.873 + vertex 727.708 145.079 309.938 + vertex 727.289 146.511 308.717 + endloop + endfacet + facet normal 0.281948 -0.573478 -0.769174 + outer loop + vertex 727.708 145.079 309.938 + vertex 723.491 143.142 309.836 + vertex 727.289 146.511 308.717 + endloop + endfacet + facet normal 0.301884 -0.589362 -0.749346 + outer loop + vertex 727.289 146.511 308.717 + vertex 723.491 143.142 309.836 + vertex 723.043 144.562 308.539 + endloop + endfacet + facet normal 0.289321 -0.594297 -0.750403 + outer loop + vertex 723.491 143.142 309.836 + vertex 719.296 141.246 309.721 + vertex 723.043 144.562 308.539 + endloop + endfacet + facet normal 0.311294 -0.611062 -0.727804 + outer loop + vertex 723.043 144.562 308.539 + vertex 719.296 141.246 309.721 + vertex 718.796 142.624 308.349 + endloop + endfacet + facet normal 0.297958 -0.616711 -0.728621 + outer loop + vertex 719.296 141.246 309.721 + vertex 715.032 139.329 309.599 + vertex 718.796 142.624 308.349 + endloop + endfacet + facet normal 0.32399 -0.635805 -0.700559 + outer loop + vertex 718.796 142.624 308.349 + vertex 715.032 139.329 309.599 + vertex 714.481 140.635 308.159 + endloop + endfacet + facet normal 0.306414 -0.643848 -0.701121 + outer loop + vertex 715.032 139.329 309.599 + vertex 710.688 137.374 309.496 + vertex 714.481 140.635 308.159 + endloop + endfacet + facet normal 0.334255 -0.663291 -0.669567 + outer loop + vertex 714.481 140.635 308.159 + vertex 710.688 137.374 309.496 + vertex 710.084 138.599 307.981 + endloop + endfacet + facet normal 0.31561 -0.672412 -0.669517 + outer loop + vertex 710.688 137.374 309.496 + vertex 706.47 135.455 309.435 + vertex 710.084 138.599 307.981 + endloop + endfacet + facet normal 0.341155 -0.688252 -0.640252 + outer loop + vertex 710.084 138.599 307.981 + vertex 706.47 135.455 309.435 + vertex 705.784 136.631 307.805 + endloop + endfacet + facet normal 0.32208 -0.698177 -0.639385 + outer loop + vertex 706.47 135.455 309.435 + vertex 702.822 133.792 309.414 + vertex 705.784 136.631 307.805 + endloop + endfacet + facet normal 0.349225 -0.710419 -0.611021 + outer loop + vertex 705.784 136.631 307.805 + vertex 702.822 133.792 309.414 + vertex 702.018 134.941 307.618 + endloop + endfacet + facet normal 0.327655 -0.722343 -0.608985 + outer loop + vertex 702.822 133.792 309.414 + vertex 700.232 132.643 309.383 + vertex 702.018 134.941 307.618 + endloop + endfacet + facet normal 0.347231 -0.725863 -0.593762 + outer loop + vertex 702.018 134.941 307.618 + vertex 700.232 132.643 309.383 + vertex 699.379 133.869 307.385 + endloop + endfacet + facet normal 0.297895 -0.751618 -0.588498 + outer loop + vertex 700.232 132.643 309.383 + vertex 698.947 132.224 309.268 + vertex 699.379 133.869 307.385 + endloop + endfacet + facet normal 0.289964 -0.75261 -0.591185 + outer loop + vertex 699.379 133.869 307.385 + vertex 698.947 132.224 309.268 + vertex 698.096 133.646 307.04 + endloop + endfacet + facet normal 0.225448 -0.779852 -0.583956 + outer loop + vertex 698.947 132.224 309.268 + vertex 698.585 132.25 309.093 + vertex 698.096 133.646 307.04 + endloop + endfacet + facet normal 0.356619 -0.730904 -0.581895 + outer loop + vertex 698.096 133.646 307.04 + vertex 698.585 132.25 309.093 + vertex 697.868 133.485 307.102 + endloop + endfacet + facet normal 0.492862 -0.648635 -0.579965 + outer loop + vertex 698.585 132.25 309.093 + vertex 698.327 132.318 308.798 + vertex 697.868 133.485 307.102 + endloop + endfacet + facet normal 0.953592 -0.0545446 -0.29612 + outer loop + vertex 697.868 133.485 307.102 + vertex 698.327 132.318 308.798 + vertex 697.971 133.11 307.504 + endloop + endfacet + facet normal 0.460132 -0.521586 -0.718489 + outer loop + vertex 848.897 225.562 309.007 + vertex 845.503 222.297 309.203 + vertex 847.529 226.75 307.268 + endloop + endfacet + facet normal 0.453037 -0.52872 -0.717783 + outer loop + vertex 850.415 229.526 307.045 + vertex 848.897 225.562 309.007 + vertex 847.529 226.75 307.268 + endloop + endfacet + facet normal 0.475232 -0.529685 -0.702559 + outer loop + vertex 851.761 228.367 308.829 + vertex 848.897 225.562 309.007 + vertex 850.415 229.526 307.045 + endloop + endfacet + facet normal 0.466578 -0.538427 -0.701713 + outer loop + vertex 852.506 231.434 306.971 + vertex 851.761 228.367 308.829 + vertex 850.415 229.526 307.045 + endloop + endfacet + facet normal 0.486548 -0.536089 -0.68984 + outer loop + vertex 853.824 230.343 308.749 + vertex 851.761 228.367 308.829 + vertex 852.506 231.434 306.971 + endloop + endfacet + facet normal 0.478194 -0.544702 -0.688934 + outer loop + vertex 853.694 232.427 307.011 + vertex 853.824 230.343 308.749 + vertex 852.506 231.434 306.971 + endloop + endfacet + facet normal 0.502275 -0.53512 -0.67924 + outer loop + vertex 855.138 231.302 308.965 + vertex 853.824 230.343 308.749 + vertex 853.694 232.427 307.011 + endloop + endfacet + facet normal 0.423786 -0.517816 -0.74315 + outer loop + vertex 852.497 233.414 305.545 + vertex 851.169 232.766 305.239 + vertex 851.499 234.669 304.101 + endloop + endfacet + facet normal 0.390779 -0.521332 -0.75862 + outer loop + vertex 851.499 234.669 304.101 + vertex 851.169 232.766 305.239 + vertex 849.67 234.386 303.353 + endloop + endfacet + facet normal 0.369174 -0.522715 -0.768426 + outer loop + vertex 849.67 234.386 303.353 + vertex 846.91 232.227 303.496 + vertex 847.756 236.464 301.02 + endloop + endfacet + facet normal 0.373316 -0.590758 -0.71529 + outer loop + vertex 851.063 239.414 300.272 + vertex 852.511 240.564 300.078 + vertex 852.824 237.92 302.425 + endloop + endfacet + facet normal 0.375474 -0.592974 -0.712321 + outer loop + vertex 850.908 241.116 298.774 + vertex 852.511 240.564 300.078 + vertex 851.063 239.414 300.272 + endloop + endfacet + facet normal 0.396242 -0.545845 -0.738272 + outer loop + vertex 852.848 234.277 305.15 + vertex 850.852 236.849 302.177 + vertex 852.545 235.797 303.864 + endloop + endfacet + facet normal 0.439272 -0.52773 -0.727008 + outer loop + vertex 852.545 235.797 303.864 + vertex 853.519 234.499 305.395 + vertex 852.848 234.277 305.15 + endloop + endfacet + facet normal 0.44008 -0.544788 -0.713818 + outer loop + vertex 853.519 234.499 305.395 + vertex 854.514 233.322 306.906 + vertex 852.848 234.277 305.15 + endloop + endfacet + facet normal 0.446701 -0.5368 -0.715754 + outer loop + vertex 854.613 232.502 307.583 + vertex 852.848 234.277 305.15 + vertex 854.514 233.322 306.906 + endloop + endfacet + facet normal 0.479513 -0.510961 -0.713433 + outer loop + vertex 853.519 234.499 305.395 + vertex 855.298 234.298 306.735 + vertex 854.514 233.322 306.906 + endloop + endfacet + facet normal 0.506266 -0.52705 -0.682578 + outer loop + vertex 855.298 234.298 306.735 + vertex 856.669 233.318 308.508 + vertex 854.514 233.322 306.906 + endloop + endfacet + facet normal 0.506554 -0.526274 -0.682963 + outer loop + vertex 854.514 233.322 306.906 + vertex 856.669 233.318 308.508 + vertex 855.985 232.248 308.826 + endloop + endfacet + facet normal 0.52747 -0.50199 -0.685405 + outer loop + vertex 854.514 233.322 306.906 + vertex 855.985 232.248 308.826 + vertex 854.613 232.502 307.583 + endloop + endfacet + facet normal 0.510185 -0.522549 -0.683121 + outer loop + vertex 855.298 234.298 306.735 + vertex 858.372 235.027 308.473 + vertex 856.669 233.318 308.508 + endloop + endfacet + facet normal 0.507641 -0.540103 -0.67126 + outer loop + vertex 857.014 236.054 306.62 + vertex 858.372 235.027 308.473 + vertex 855.298 234.298 306.735 + endloop + endfacet + facet normal 0.514982 -0.531992 -0.672144 + outer loop + vertex 857.014 236.054 306.62 + vertex 860.876 237.427 308.492 + vertex 858.372 235.027 308.473 + endloop + endfacet + facet normal 0.514128 -0.558695 -0.650794 + outer loop + vertex 859.53 238.475 306.528 + vertex 860.876 237.427 308.492 + vertex 857.014 236.054 306.62 + endloop + endfacet + facet normal 0.527701 -0.544088 -0.652303 + outer loop + vertex 859.53 238.475 306.528 + vertex 863.782 240.292 308.453 + vertex 860.876 237.427 308.492 + endloop + endfacet + facet normal 0.52836 -0.571773 -0.627623 + outer loop + vertex 862.467 241.368 306.365 + vertex 863.782 240.292 308.453 + vertex 859.53 238.475 306.528 + endloop + endfacet + facet normal 0.547914 -0.55115 -0.629304 + outer loop + vertex 862.467 241.368 306.365 + vertex 866.794 243.455 308.305 + vertex 863.782 240.292 308.453 + endloop + endfacet + facet normal 0.549117 -0.573749 -0.607686 + outer loop + vertex 865.561 244.656 306.057 + vertex 866.794 243.455 308.305 + vertex 862.467 241.368 306.365 + endloop + endfacet + facet normal 0.531814 -0.560044 -0.635236 + outer loop + vertex 861.545 243.178 303.997 + vertex 865.561 244.656 306.057 + vertex 862.467 241.368 306.365 + endloop + endfacet + facet normal 0.570195 -0.552546 -0.607923 + outer loop + vertex 865.561 244.656 306.057 + vertex 869.777 246.775 308.085 + vertex 866.794 243.455 308.305 + endloop + endfacet + facet normal 0.570876 -0.572268 -0.588735 + outer loop + vertex 868.705 248.172 305.688 + vertex 869.777 246.775 308.085 + vertex 865.561 244.656 306.057 + endloop + endfacet + facet normal 0.592776 -0.551814 -0.586615 + outer loop + vertex 868.705 248.172 305.688 + vertex 872.68 250.059 307.93 + vertex 869.777 246.775 308.085 + endloop + endfacet + facet normal 0.474294 -0.52285 -0.708289 + outer loop + vertex 854.119 235.758 304.867 + vertex 855.298 234.298 306.735 + vertex 853.519 234.499 305.395 + endloop + endfacet + facet normal 0.481329 -0.51679 -0.707991 + outer loop + vertex 854.119 235.758 304.867 + vertex 857.014 236.054 306.62 + vertex 855.298 234.298 306.735 + endloop + endfacet + facet normal 0.450177 -0.519049 -0.726588 + outer loop + vertex 852.545 235.797 303.864 + vertex 854.119 235.758 304.867 + vertex 853.519 234.499 305.395 + endloop + endfacet + facet normal 0.473824 -0.546408 -0.6906 + outer loop + vertex 855.851 237.735 304.492 + vertex 857.014 236.054 306.62 + vertex 854.119 235.758 304.867 + endloop + endfacet + facet normal 0.489199 -0.534247 -0.689394 + outer loop + vertex 855.851 237.735 304.492 + vertex 859.53 238.475 306.528 + vertex 857.014 236.054 306.62 + endloop + endfacet + facet normal 0.482851 -0.569725 -0.665033 + outer loop + vertex 858.488 240.214 304.282 + vertex 859.53 238.475 306.528 + vertex 855.851 237.735 304.492 + endloop + endfacet + facet normal 0.506792 -0.551843 -0.662292 + outer loop + vertex 858.488 240.214 304.282 + vertex 862.467 241.368 306.365 + vertex 859.53 238.475 306.528 + endloop + endfacet + facet normal 0.503414 -0.58061 -0.639896 + outer loop + vertex 861.545 243.178 303.997 + vertex 862.467 241.368 306.365 + vertex 858.488 240.214 304.282 + endloop + endfacet + facet normal 0.530355 -0.581125 -0.617266 + outer loop + vertex 864.734 246.514 303.597 + vertex 865.561 244.656 306.057 + vertex 861.545 243.178 303.997 + endloop + endfacet + facet normal 0.551856 -0.564035 -0.614264 + outer loop + vertex 862.663 248.799 299.607 + vertex 868.333 250.961 302.716 + vertex 864.042 247.82 301.745 + endloop + endfacet + facet normal 0.556726 -0.562027 -0.611704 + outer loop + vertex 865.561 244.656 306.057 + vertex 864.734 246.514 303.597 + vertex 868.705 248.172 305.688 + endloop + endfacet + facet normal 0.592067 -0.567763 -0.571928 + outer loop + vertex 871.761 251.23 305.816 + vertex 872.68 250.059 307.93 + vertex 868.705 248.172 305.688 + endloop + endfacet + facet normal 0.613028 -0.547345 -0.569746 + outer loop + vertex 871.761 251.23 305.816 + vertex 875.41 253.287 307.766 + vertex 872.68 250.059 307.93 + endloop + endfacet + facet normal 0.673697 -0.514803 -0.530198 + outer loop + vertex 879.567 261.111 304.896 + vertex 883.384 263.422 307.502 + vertex 880.791 259.971 307.558 + endloop + endfacet + facet normal 0.619003 -0.547441 -0.563155 + outer loop + vertex 877.283 257.79 305.435 + vertex 874.095 254.431 305.197 + vertex 874.139 257.445 302.316 + endloop + endfacet + facet normal 0.64536 -0.553455 -0.526496 + outer loop + vertex 873.146 259.982 298.431 + vertex 879.521 264.033 301.988 + vertex 874.139 257.445 302.316 + endloop + endfacet + facet normal 0.64563 -0.567386 -0.511112 + outer loop + vertex 878.533 266.451 298.055 + vertex 879.521 264.033 301.988 + vertex 873.146 259.982 298.431 + endloop + endfacet + facet normal 0.672595 -0.586373 -0.451422 + outer loop + vertex 872.84 262.149 295.161 + vertex 878.533 266.451 298.055 + vertex 873.146 259.982 298.431 + endloop + endfacet + facet normal 0.672797 -0.590352 -0.445902 + outer loop + vertex 878.434 268.772 294.832 + vertex 878.533 266.451 298.055 + vertex 872.84 262.149 295.161 + endloop + endfacet + facet normal 0.672906 -0.533266 -0.512664 + outer loop + vertex 882.578 264.581 305.239 + vertex 883.384 263.422 307.502 + vertex 879.567 261.111 304.896 + endloop + endfacet + facet normal 0.698342 -0.505 -0.507241 + outer loop + vertex 882.578 264.581 305.239 + vertex 885.876 266.905 307.466 + vertex 883.384 263.422 307.502 + endloop + endfacet + facet normal 0.738768 -0.499804 -0.452125 + outer loop + vertex 888.248 270.423 307.451 + vertex 889.334 269.816 309.898 + vertex 885.876 266.905 307.466 + endloop + endfacet + facet normal 0.738337 -0.488756 -0.464733 + outer loop + vertex 885.876 266.905 307.466 + vertex 889.334 269.816 309.898 + vertex 886.984 266.259 309.906 + endloop + endfacet + facet normal 0.71828 -0.518811 -0.463582 + outer loop + vertex 885.876 266.905 307.466 + vertex 886.984 266.259 309.906 + vertex 883.384 263.422 307.502 + endloop + endfacet + facet normal 0.717821 -0.504272 -0.480046 + outer loop + vertex 883.384 263.422 307.502 + vertex 886.984 266.259 309.906 + vertex 884.518 262.729 309.926 + endloop + endfacet + facet normal 0.69811 -0.532314 -0.478837 + outer loop + vertex 883.384 263.422 307.502 + vertex 884.518 262.729 309.926 + vertex 880.791 259.971 307.558 + endloop + endfacet + facet normal 0.697814 -0.521046 -0.491494 + outer loop + vertex 880.791 259.971 307.558 + vertex 884.518 262.729 309.926 + vertex 881.959 259.278 309.951 + endloop + endfacet + facet normal 0.677586 -0.548753 -0.489639 + outer loop + vertex 880.791 259.971 307.558 + vertex 881.959 259.278 309.951 + vertex 878.12 256.597 307.643 + endloop + endfacet + facet normal 0.677219 -0.533923 -0.506262 + outer loop + vertex 878.12 256.597 307.643 + vertex 881.959 259.278 309.951 + vertex 879.338 255.919 309.988 + endloop + endfacet + facet normal 0.659113 -0.558263 -0.503898 + outer loop + vertex 878.12 256.597 307.643 + vertex 879.338 255.919 309.988 + vertex 875.41 253.287 307.766 + endloop + endfacet + facet normal 0.65856 -0.542874 -0.521139 + outer loop + vertex 875.41 253.287 307.766 + vertex 879.338 255.919 309.988 + vertex 876.681 252.638 310.048 + endloop + endfacet + facet normal 0.640062 -0.56757 -0.517867 + outer loop + vertex 875.41 253.287 307.766 + vertex 876.681 252.638 310.048 + vertex 872.68 250.059 307.93 + endloop + endfacet + facet normal 0.639252 -0.55144 -0.535976 + outer loop + vertex 872.68 250.059 307.93 + vertex 876.681 252.638 310.048 + vertex 873.961 249.409 310.126 + endloop + endfacet + facet normal 0.621494 -0.574636 -0.532484 + outer loop + vertex 872.68 250.059 307.93 + vertex 873.961 249.409 310.126 + vertex 869.777 246.775 308.085 + endloop + endfacet + facet normal 0.620082 -0.556503 -0.552995 + outer loop + vertex 869.777 246.775 308.085 + vertex 873.961 249.409 310.126 + vertex 871.156 246.185 310.225 + endloop + endfacet + facet normal 0.603615 -0.57863 -0.548486 + outer loop + vertex 869.777 246.775 308.085 + vertex 871.156 246.185 310.225 + vertex 866.794 243.455 308.305 + endloop + endfacet + facet normal 0.601814 -0.563438 -0.566002 + outer loop + vertex 866.794 243.455 308.305 + vertex 871.156 246.185 310.225 + vertex 868.25 242.985 310.32 + endloop + endfacet + facet normal 0.58671 -0.584872 -0.560087 + outer loop + vertex 866.794 243.455 308.305 + vertex 868.25 242.985 310.32 + vertex 863.782 240.292 308.453 + endloop + endfacet + facet normal 0.58434 -0.566199 -0.581348 + outer loop + vertex 863.782 240.292 308.453 + vertex 868.25 242.985 310.32 + vertex 865.263 239.859 310.363 + endloop + endfacet + facet normal 0.570431 -0.586374 -0.57513 + outer loop + vertex 863.782 240.292 308.453 + vertex 865.263 239.859 310.363 + vertex 860.876 237.427 308.492 + endloop + endfacet + facet normal 0.568224 -0.563572 -0.59959 + outer loop + vertex 860.876 237.427 308.492 + vertex 865.263 239.859 310.363 + vertex 862.336 236.935 310.338 + endloop + endfacet + facet normal 0.558242 -0.577732 -0.595475 + outer loop + vertex 860.876 237.427 308.492 + vertex 862.336 236.935 310.338 + vertex 858.372 235.027 308.473 + endloop + endfacet + facet normal 0.557761 -0.559715 -0.61288 + outer loop + vertex 858.372 235.027 308.473 + vertex 862.336 236.935 310.338 + vertex 859.826 234.477 310.298 + endloop + endfacet + facet normal 0.554101 -0.56483 -0.611506 + outer loop + vertex 858.372 235.027 308.473 + vertex 859.826 234.477 310.298 + vertex 856.669 233.318 308.508 + endloop + endfacet + facet normal 0.55488 -0.556994 -0.617953 + outer loop + vertex 856.669 233.318 308.508 + vertex 859.826 234.477 310.298 + vertex 858.136 232.69 310.391 + endloop + endfacet + facet normal 0.563942 -0.544526 -0.620855 + outer loop + vertex 856.669 233.318 308.508 + vertex 858.136 232.69 310.391 + vertex 855.985 232.248 308.826 + endloop + endfacet + facet normal 0.546964 -0.602614 -0.581108 + outer loop + vertex 855.985 232.248 308.826 + vertex 858.136 232.69 310.391 + vertex 857.523 231.665 310.877 + endloop + endfacet + facet normal 0.758229 -0.468839 -0.453078 + outer loop + vertex 888.248 270.423 307.451 + vertex 891.561 273.411 309.906 + vertex 889.334 269.816 309.898 + endloop + endfacet + facet normal 0.758715 -0.478113 -0.442447 + outer loop + vertex 890.51 274.022 307.441 + vertex 891.561 273.411 309.906 + vertex 888.248 270.423 307.451 + endloop + endfacet + facet normal 0.778904 -0.444249 -0.442664 + outer loop + vertex 890.51 274.022 307.441 + vertex 893.68 277.124 309.906 + vertex 891.561 273.411 309.906 + endloop + endfacet + facet normal 0.779709 -0.455097 -0.430048 + outer loop + vertex 892.675 277.774 307.396 + vertex 893.68 277.124 309.906 + vertex 890.51 274.022 307.441 + endloop + endfacet + facet normal 0.799033 -0.421287 -0.429026 + outer loop + vertex 892.675 277.774 307.396 + vertex 895.71 281.032 309.851 + vertex 893.68 277.124 309.906 + endloop + endfacet + facet normal 0.799583 -0.426439 -0.422868 + outer loop + vertex 894.739 281.808 307.233 + vertex 895.71 281.032 309.851 + vertex 892.675 277.774 307.396 + endloop + endfacet + facet normal 0.756868 -0.442535 -0.480951 + outer loop + vertex 889.368 275.096 304.657 + vertex 892.675 277.774 307.396 + vertex 890.51 274.022 307.441 + endloop + endfacet + facet normal 0.705017 -0.489482 -0.513185 + outer loop + vertex 887.453 271.54 305.147 + vertex 884.679 267.963 304.748 + vertex 884.554 270.886 301.788 + endloop + endfacet + facet normal 0.738837 -0.481033 -0.471939 + outer loop + vertex 883.574 273.297 297.796 + vertex 889.192 278.184 301.611 + vertex 884.554 270.886 301.788 + endloop + endfacet + facet normal 0.738765 -0.480196 -0.472905 + outer loop + vertex 888.178 280.551 297.623 + vertex 889.192 278.184 301.611 + vertex 883.574 273.297 297.796 + endloop + endfacet + facet normal 0.77068 -0.498642 -0.396746 + outer loop + vertex 883.382 275.557 294.583 + vertex 888.178 280.551 297.623 + vertex 883.574 273.297 297.796 + endloop + endfacet + facet normal 0.769694 -0.490354 -0.408808 + outer loop + vertex 887.903 282.67 294.564 + vertex 888.178 280.551 297.623 + vertex 883.382 275.557 294.583 + endloop + endfacet + facet normal 0.757014 -0.454569 -0.469358 + outer loop + vertex 891.92 278.987 305.005 + vertex 892.675 277.774 307.396 + vertex 889.368 275.096 304.657 + endloop + endfacet + facet normal 0.782851 -0.419358 -0.459655 + outer loop + vertex 891.92 278.987 305.005 + vertex 894.739 281.808 307.233 + vertex 892.675 277.774 307.396 + endloop + endfacet + facet normal 0.801468 -0.395838 -0.448287 + outer loop + vertex 895.583 286.665 304.562 + vertex 896.641 286.208 306.857 + vertex 893.609 282.878 304.377 + endloop + endfacet + facet normal 0.818659 -0.391948 -0.419731 + outer loop + vertex 894.739 281.808 307.233 + vertex 897.634 285.242 309.672 + vertex 895.71 281.032 309.851 + endloop + endfacet + facet normal 0.849899 -0.299694 -0.433423 + outer loop + vertex 896.857 294.221 301.17 + vertex 901.441 300.561 305.775 + vertex 898.432 291.819 305.919 + endloop + endfacet + facet normal 0.851218 -0.305522 -0.426713 + outer loop + vertex 899.761 302.563 300.991 + vertex 901.441 300.561 305.775 + vertex 896.857 294.221 301.17 + endloop + endfacet + facet normal 0.862312 -0.308839 -0.401293 + outer loop + vertex 895.688 296.108 297.205 + vertex 899.761 302.563 300.991 + vertex 896.857 294.221 301.17 + endloop + endfacet + facet normal 0.862491 -0.309456 -0.400434 + outer loop + vertex 898.605 304.355 297.116 + vertex 899.761 302.563 300.991 + vertex 895.688 296.108 297.205 + endloop + endfacet + facet normal 0.887232 -0.317498 -0.334685 + outer loop + vertex 895.27 298.078 294.228 + vertex 898.605 304.355 297.116 + vertex 895.688 296.108 297.205 + endloop + endfacet + facet normal 0.882917 -0.304911 -0.357053 + outer loop + vertex 898.222 306.474 294.358 + vertex 898.605 304.355 297.116 + vertex 895.27 298.078 294.228 + endloop + endfacet + facet normal 0.881042 -0.237872 -0.408879 + outer loop + vertex 899.761 302.563 300.991 + vertex 903.69 309.026 305.696 + vertex 901.441 300.561 305.775 + endloop + endfacet + facet normal 0.881841 -0.240926 -0.405352 + outer loop + vertex 901.998 310.887 300.908 + vertex 903.69 309.026 305.696 + vertex 899.761 302.563 300.991 + endloop + endfacet + facet normal 0.892755 -0.243597 -0.379011 + outer loop + vertex 898.605 304.355 297.116 + vertex 901.998 310.887 300.908 + vertex 899.761 302.563 300.991 + endloop + endfacet + facet normal 0.892102 -0.241647 -0.381786 + outer loop + vertex 900.808 312.561 297.068 + vertex 901.998 310.887 300.908 + vertex 898.605 304.355 297.116 + endloop + endfacet + facet normal 0.915394 -0.247524 -0.317468 + outer loop + vertex 898.222 306.474 294.358 + vertex 900.808 312.561 297.068 + vertex 898.605 304.355 297.116 + endloop + endfacet + facet normal 0.911492 -0.237784 -0.335621 + outer loop + vertex 900.193 314.275 294.183 + vertex 900.808 312.561 297.068 + vertex 898.222 306.474 294.358 + endloop + endfacet + facet normal 0.907027 -0.168252 -0.385997 + outer loop + vertex 901.998 310.887 300.908 + vertex 905.236 317.398 305.681 + vertex 903.69 309.026 305.696 + endloop + endfacet + facet normal 0.907647 -0.17029 -0.383638 + outer loop + vertex 903.549 319.187 300.896 + vertex 905.236 317.398 305.681 + vertex 901.998 310.887 300.908 + endloop + endfacet + facet normal 0.917252 -0.172048 -0.359232 + outer loop + vertex 900.808 312.561 297.068 + vertex 903.549 319.187 300.896 + vertex 901.998 310.887 300.908 + endloop + endfacet + facet normal 0.916407 -0.169858 -0.362419 + outer loop + vertex 902.327 320.771 297.063 + vertex 903.549 319.187 300.896 + vertex 900.808 312.561 297.068 + endloop + endfacet + facet normal 0.937049 -0.173644 -0.302963 + outer loop + vertex 900.193 314.275 294.183 + vertex 902.327 320.771 297.063 + vertex 900.808 312.561 297.068 + endloop + endfacet + facet normal 0.931644 -0.161977 -0.325273 + outer loop + vertex 901.705 322.65 294.345 + vertex 902.327 320.771 297.063 + vertex 900.193 314.275 294.183 + endloop + endfacet + facet normal 0.926037 -0.100152 -0.363902 + outer loop + vertex 903.549 319.187 300.896 + vertex 906.148 325.808 305.686 + vertex 905.236 317.398 305.681 + endloop + endfacet + facet normal 0.926951 -0.102723 -0.360845 + outer loop + vertex 904.48 327.54 300.907 + vertex 906.148 325.808 305.686 + vertex 903.549 319.187 300.896 + endloop + endfacet + facet normal 0.934424 -0.103583 -0.340767 + outer loop + vertex 902.327 320.771 297.063 + vertex 904.48 327.54 300.907 + vertex 903.549 319.187 300.896 + endloop + endfacet + facet normal 0.93384 -0.102267 -0.342759 + outer loop + vertex 903.251 329.06 297.106 + vertex 904.48 327.54 300.907 + vertex 902.327 320.771 297.063 + endloop + endfacet + facet normal 0.951293 -0.104481 -0.290045 + outer loop + vertex 901.705 322.65 294.345 + vertex 903.251 329.06 297.106 + vertex 902.327 320.771 297.063 + endloop + endfacet + facet normal 0.946001 -0.0945837 -0.310057 + outer loop + vertex 902.527 330.741 294.385 + vertex 903.251 329.06 297.106 + vertex 901.705 322.65 294.345 + endloop + endfacet + facet normal 0.938869 -0.0393345 -0.342021 + outer loop + vertex 904.48 327.54 300.907 + vertex 906.506 334.342 305.688 + vertex 906.148 325.808 305.686 + endloop + endfacet + facet normal 0.940208 -0.0426118 -0.337926 + outer loop + vertex 904.863 335.984 300.908 + vertex 906.506 334.342 305.688 + vertex 904.48 327.54 300.907 + endloop + endfacet + facet normal 0.945503 -0.0428529 -0.322781 + outer loop + vertex 903.251 329.06 297.106 + vertex 904.863 335.984 300.908 + vertex 904.48 327.54 300.907 + endloop + endfacet + facet normal 0.944871 -0.0416037 -0.324788 + outer loop + vertex 903.616 337.428 297.095 + vertex 904.863 335.984 300.908 + vertex 903.251 329.06 297.106 + endloop + endfacet + facet normal 0.958762 -0.0421545 -0.281066 + outer loop + vertex 902.527 330.741 294.385 + vertex 903.616 337.428 297.095 + vertex 903.251 329.06 297.106 + endloop + endfacet + facet normal 0.954166 -0.0348506 -0.297242 + outer loop + vertex 902.782 339.216 294.209 + vertex 903.616 337.428 297.095 + vertex 902.527 330.741 294.385 + endloop + endfacet + facet normal 0.952124 0.0435501 -0.302594 + outer loop + vertex 907.516 344.989 309.533 + vertex 907.571 340.361 309.038 + vertex 906.387 342.97 305.689 + endloop + endfacet + facet normal 0.948481 0.0613055 -0.310847 + outer loop + vertex 907.516 344.989 309.533 + vertex 906.387 342.97 305.689 + vertex 907.09 349.066 309.037 + endloop + endfacet + facet normal 0.950869 0.0573946 -0.304227 + outer loop + vertex 906.387 342.97 305.689 + vertex 905.87 351.549 305.692 + vertex 907.09 349.066 309.037 + endloop + endfacet + facet normal 0.954455 0.0828926 -0.286609 + outer loop + vertex 906.845 353.602 309.531 + vertex 907.09 349.066 309.037 + vertex 905.87 351.549 305.692 + endloop + endfacet + facet normal 0.950181 0.100626 -0.295009 + outer loop + vertex 906.845 353.602 309.531 + vertex 905.87 351.549 305.692 + vertex 906.273 357.581 309.046 + endloop + endfacet + facet normal 0.95325 0.095752 -0.28661 + outer loop + vertex 905.87 351.549 305.692 + vertex 905.024 360.025 305.71 + vertex 906.273 357.581 309.046 + endloop + endfacet + facet normal 0.95526 0.117507 -0.271424 + outer loop + vertex 905.866 362.056 309.552 + vertex 906.273 357.581 309.046 + vertex 905.024 360.025 305.71 + endloop + endfacet + facet normal 0.951507 0.131605 -0.278055 + outer loop + vertex 905.866 362.056 309.552 + vertex 905.024 360.025 305.71 + vertex 905.179 366.024 309.077 + endloop + endfacet + facet normal 0.95416 0.127464 -0.270798 + outer loop + vertex 905.024 360.025 305.71 + vertex 903.904 368.452 305.728 + vertex 905.179 366.024 309.077 + endloop + endfacet + facet normal 0.955045 0.144076 -0.259095 + outer loop + vertex 904.644 370.462 309.573 + vertex 905.179 366.024 309.077 + vertex 903.904 368.452 305.728 + endloop + endfacet + facet normal 0.952044 0.154607 -0.264023 + outer loop + vertex 904.644 370.462 309.573 + vertex 903.904 368.452 305.728 + vertex 903.86 374.442 309.077 + endloop + endfacet + facet normal 0.953044 0.153087 -0.26129 + outer loop + vertex 903.904 368.452 305.728 + vertex 902.518 377.007 305.685 + vertex 903.86 374.442 309.077 + endloop + endfacet + facet normal 0.953527 0.168944 -0.24949 + outer loop + vertex 903.157 379.12 309.559 + vertex 903.86 374.442 309.077 + vertex 902.518 377.007 305.685 + endloop + endfacet + facet normal 0.949864 0.180592 -0.255235 + outer loop + vertex 903.157 379.12 309.559 + vertex 902.518 377.007 305.685 + vertex 902.156 383.486 308.921 + endloop + endfacet + facet normal 0.961528 0.191826 -0.196639 + outer loop + vertex 902.156 383.486 308.921 + vertex 902.88 383.096 312.084 + vertex 903.157 379.12 309.559 + endloop + endfacet + facet normal 0.962428 0.190128 -0.193868 + outer loop + vertex 903.157 379.12 309.559 + vertex 902.88 383.096 312.084 + vertex 903.841 378.109 311.963 + endloop + endfacet + facet normal 0.971686 0.190593 -0.139644 + outer loop + vertex 902.88 383.096 312.084 + vertex 903.5 381.937 314.815 + vertex 903.841 378.109 311.963 + endloop + endfacet + facet normal 0.968144 0.199234 -0.151664 + outer loop + vertex 903.841 378.109 311.963 + vertex 903.5 381.937 314.815 + vertex 904.353 377.142 313.959 + endloop + endfacet + facet normal 0.970883 0.174103 -0.164546 + outer loop + vertex 903.841 378.109 311.963 + vertex 904.353 377.142 313.959 + vertex 904.594 373.834 311.884 + endloop + endfacet + facet normal 0.961333 0.173333 -0.213996 + outer loop + vertex 903.86 374.442 309.077 + vertex 903.841 378.109 311.963 + vertex 904.594 373.834 311.884 + endloop + endfacet + facet normal 0.962613 0.162588 -0.216659 + outer loop + vertex 903.86 374.442 309.077 + vertex 904.594 373.834 311.884 + vertex 904.644 370.462 309.573 + endloop + endfacet + facet normal 0.965627 0.156421 -0.207598 + outer loop + vertex 904.644 370.462 309.573 + vertex 904.594 373.834 311.884 + vertex 905.265 369.772 311.945 + endloop + endfacet + facet normal 0.973888 0.167344 -0.15342 + outer loop + vertex 904.594 373.834 311.884 + vertex 904.353 377.142 313.959 + vertex 904.989 373.781 314.33 + endloop + endfacet + facet normal 0.975253 0.15881 -0.153824 + outer loop + vertex 904.594 373.834 311.884 + vertex 904.989 373.781 314.33 + vertex 905.265 369.772 311.945 + endloop + endfacet + facet normal 0.974616 0.16026 -0.156334 + outer loop + vertex 905.265 369.772 311.945 + vertex 904.989 373.781 314.33 + vertex 905.699 369.588 314.459 + endloop + endfacet + facet normal 0.976266 0.148694 -0.157467 + outer loop + vertex 905.265 369.772 311.945 + vertex 905.699 369.588 314.459 + vertex 905.905 365.577 311.952 + endloop + endfacet + facet normal 0.975592 0.150301 -0.160095 + outer loop + vertex 905.905 365.577 311.952 + vertex 905.699 369.588 314.459 + vertex 906.36 365.294 314.455 + endloop + endfacet + facet normal 0.977313 0.136472 -0.161969 + outer loop + vertex 905.905 365.577 311.952 + vertex 906.36 365.294 314.455 + vertex 906.492 361.357 311.938 + endloop + endfacet + facet normal 0.977217 0.136712 -0.162349 + outer loop + vertex 906.492 361.357 311.938 + vertex 906.36 365.294 314.455 + vertex 906.946 361.092 314.448 + endloop + endfacet + facet normal 0.978808 0.122444 -0.164142 + outer loop + vertex 906.492 361.357 311.938 + vertex 906.946 361.092 314.448 + vertex 907.017 357.156 311.934 + endloop + endfacet + facet normal 0.979178 0.121489 -0.162636 + outer loop + vertex 907.017 357.156 311.934 + vertex 906.946 361.092 314.448 + vertex 907.465 356.928 314.459 + endloop + endfacet + facet normal 0.980899 0.103743 -0.164545 + outer loop + vertex 907.017 357.156 311.934 + vertex 907.465 356.928 314.459 + vertex 907.464 352.938 311.936 + endloop + endfacet + facet normal 0.980225 0.105543 -0.167391 + outer loop + vertex 907.464 352.938 311.936 + vertex 907.465 356.928 314.459 + vertex 907.921 352.716 314.474 + endloop + endfacet + facet normal 0.981697 0.0873345 -0.169247 + outer loop + vertex 907.464 352.938 311.936 + vertex 907.921 352.716 314.474 + vertex 907.846 348.645 311.94 + endloop + endfacet + facet normal 0.981751 0.0871855 -0.169009 + outer loop + vertex 907.846 348.645 311.94 + vertex 907.921 352.716 314.474 + vertex 908.303 348.419 314.478 + endloop + endfacet + facet normal 0.982996 0.0667911 -0.171047 + outer loop + vertex 907.846 348.645 311.94 + vertex 908.303 348.419 314.478 + vertex 908.142 344.281 311.938 + endloop + endfacet + facet normal 0.982542 0.0680891 -0.173133 + outer loop + vertex 908.142 344.281 311.938 + vertex 908.303 348.419 314.478 + vertex 908.605 344.047 314.474 + endloop + endfacet + facet normal 0.983384 0.0476558 -0.175171 + outer loop + vertex 908.142 344.281 311.938 + vertex 908.605 344.047 314.474 + vertex 908.356 339.873 311.937 + endloop + endfacet + facet normal 0.98306 0.0486173 -0.176721 + outer loop + vertex 908.356 339.873 311.937 + vertex 908.605 344.047 314.474 + vertex 908.823 339.645 314.471 + endloop + endfacet + facet normal 0.98356 0.0228296 -0.179131 + outer loop + vertex 908.356 339.873 311.937 + vertex 908.823 339.645 314.471 + vertex 908.457 335.488 311.936 + endloop + endfacet + facet normal 0.982996 0.0246099 -0.181969 + outer loop + vertex 908.457 335.488 311.936 + vertex 908.823 339.645 314.471 + vertex 908.932 335.271 314.469 + endloop + endfacet + facet normal 0.982896 -0.00120796 -0.184157 + outer loop + vertex 908.457 335.488 311.936 + vertex 908.932 335.271 314.469 + vertex 908.452 331.144 311.937 + endloop + endfacet + facet normal 0.98251 9.70977e-05 -0.18621 + outer loop + vertex 908.452 331.144 311.937 + vertex 908.932 335.271 314.469 + vertex 908.932 330.942 314.47 + endloop + endfacet + facet normal 0.98161 -0.0303512 -0.188468 + outer loop + vertex 908.452 331.144 311.937 + vertex 908.932 330.942 314.47 + vertex 908.32 326.861 311.937 + endloop + endfacet + facet normal 0.980683 -0.0269416 -0.193738 + outer loop + vertex 908.32 326.861 311.937 + vertex 908.932 330.942 314.47 + vertex 908.815 326.665 314.472 + endloop + endfacet + facet normal 0.978875 -0.0587491 -0.195836 + outer loop + vertex 908.32 326.861 311.937 + vertex 908.815 326.665 314.472 + vertex 908.065 322.623 311.937 + endloop + endfacet + facet normal 0.978677 -0.057941 -0.197066 + outer loop + vertex 908.065 322.623 311.937 + vertex 908.815 326.665 314.472 + vertex 908.565 322.444 314.471 + endloop + endfacet + facet normal 0.975523 -0.0936427 -0.198964 + outer loop + vertex 908.065 322.623 311.937 + vertex 908.565 322.444 314.471 + vertex 907.662 318.428 311.932 + endloop + endfacet + facet normal 0.974834 -0.0904584 -0.203755 + outer loop + vertex 907.662 318.428 311.932 + vertex 908.565 322.444 314.471 + vertex 908.176 318.256 314.469 + endloop + endfacet + facet normal 0.970559 -0.125971 -0.205296 + outer loop + vertex 907.662 318.428 311.932 + vertex 908.176 318.256 314.469 + vertex 907.117 314.243 311.924 + endloop + endfacet + facet normal 0.969983 -0.122971 -0.209787 + outer loop + vertex 907.117 314.243 311.924 + vertex 908.176 318.256 314.469 + vertex 907.644 314.071 314.463 + endloop + endfacet + facet normal 0.963484 -0.164536 -0.211251 + outer loop + vertex 907.117 314.243 311.924 + vertex 907.644 314.071 314.463 + vertex 906.399 310.049 311.914 + endloop + endfacet + facet normal 0.962966 -0.161359 -0.21601 + outer loop + vertex 906.399 310.049 311.914 + vertex 907.644 314.071 314.463 + vertex 906.939 309.881 314.451 + endloop + endfacet + facet normal 0.955155 -0.201462 -0.217007 + outer loop + vertex 906.399 310.049 311.914 + vertex 906.939 309.881 314.451 + vertex 905.509 305.839 311.907 + endloop + endfacet + facet normal 0.954389 -0.196043 -0.225185 + outer loop + vertex 905.509 305.839 311.907 + vertex 906.939 309.881 314.451 + vertex 906.074 305.678 314.441 + endloop + endfacet + facet normal 0.944666 -0.238055 -0.225688 + outer loop + vertex 905.509 305.839 311.907 + vertex 906.074 305.678 314.441 + vertex 904.448 301.614 311.92 + endloop + endfacet + facet normal 0.944028 -0.232885 -0.233614 + outer loop + vertex 904.448 301.614 311.92 + vertex 906.074 305.678 314.441 + vertex 905.043 301.501 314.44 + endloop + endfacet + facet normal 0.933501 -0.272627 -0.232918 + outer loop + vertex 904.448 301.614 311.92 + vertex 905.043 301.501 314.44 + vertex 903.234 297.421 311.966 + endloop + endfacet + facet normal 0.932929 -0.267392 -0.241133 + outer loop + vertex 903.234 297.421 311.966 + vertex 905.043 301.501 314.44 + vertex 903.861 297.362 314.457 + endloop + endfacet + facet normal 0.920389 -0.309472 -0.238979 + outer loop + vertex 903.234 297.421 311.966 + vertex 903.861 297.362 314.457 + vertex 901.868 293.297 312.044 + endloop + endfacet + facet normal 0.919929 -0.304441 -0.247074 + outer loop + vertex 901.868 293.297 312.044 + vertex 903.861 297.362 314.457 + vertex 902.504 293.244 314.478 + endloop + endfacet + facet normal 0.906016 -0.345587 -0.244344 + outer loop + vertex 901.868 293.297 312.044 + vertex 902.504 293.244 314.478 + vertex 900.272 289.083 312.088 + endloop + endfacet + facet normal 0.905705 -0.341552 -0.251079 + outer loop + vertex 900.272 289.083 312.088 + vertex 902.504 293.244 314.478 + vertex 900.962 289.14 314.497 + endloop + endfacet + facet normal 0.892104 -0.378791 -0.246308 + outer loop + vertex 900.272 289.083 312.088 + vertex 900.962 289.14 314.497 + vertex 898.519 284.891 312.184 + endloop + endfacet + facet normal 0.891776 -0.374234 -0.25433 + outer loop + vertex 898.519 284.891 312.184 + vertex 900.962 289.14 314.497 + vertex 899.268 285.099 314.506 + endloop + endfacet + facet normal 0.877846 -0.410596 -0.24657 + outer loop + vertex 898.519 284.891 312.184 + vertex 899.268 285.099 314.506 + vertex 896.65 280.87 312.227 + endloop + endfacet + facet normal 0.877487 -0.403789 -0.258787 + outer loop + vertex 896.65 280.87 312.227 + vertex 899.268 285.099 314.506 + vertex 897.458 281.172 314.494 + endloop + endfacet + facet normal 0.861809 -0.442441 -0.248053 + outer loop + vertex 896.65 280.87 312.227 + vertex 897.458 281.172 314.494 + vertex 894.681 277.038 312.221 + endloop + endfacet + facet normal 0.861588 -0.433247 -0.264505 + outer loop + vertex 894.681 277.038 312.221 + vertex 897.458 281.172 314.494 + vertex 895.539 277.367 314.476 + endloop + endfacet + facet normal 0.843879 -0.473743 -0.251866 + outer loop + vertex 894.681 277.038 312.221 + vertex 895.539 277.367 314.476 + vertex 892.606 273.349 312.205 + endloop + endfacet + facet normal 0.843952 -0.464913 -0.267583 + outer loop + vertex 892.606 273.349 312.205 + vertex 895.539 277.367 314.476 + vertex 893.497 273.661 314.473 + endloop + endfacet + facet normal 0.827344 -0.49984 -0.256247 + outer loop + vertex 892.606 273.349 312.205 + vertex 893.497 273.661 314.473 + vertex 890.413 269.721 312.204 + endloop + endfacet + facet normal 0.827654 -0.486822 -0.279272 + outer loop + vertex 890.413 269.721 312.204 + vertex 893.497 273.661 314.473 + vertex 891.345 270.001 314.478 + endloop + endfacet + facet normal 0.809687 -0.522338 -0.267525 + outer loop + vertex 890.413 269.721 312.204 + vertex 891.345 270.001 314.478 + vertex 888.096 266.125 312.212 + endloop + endfacet + facet normal 0.809954 -0.516201 -0.278407 + outer loop + vertex 888.096 266.125 312.212 + vertex 891.345 270.001 314.478 + vertex 889.051 266.399 314.483 + endloop + endfacet + facet normal 0.793906 -0.545745 -0.268095 + outer loop + vertex 888.096 266.125 312.212 + vertex 889.051 266.399 314.483 + vertex 885.664 262.584 312.217 + endloop + endfacet + facet normal 0.794528 -0.535655 -0.286007 + outer loop + vertex 885.664 262.584 312.217 + vertex 889.051 266.399 314.483 + vertex 886.657 262.849 314.48 + endloop + endfacet + facet normal 0.777453 -0.56563 -0.27501 + outer loop + vertex 885.664 262.584 312.217 + vertex 886.657 262.849 314.48 + vertex 883.148 259.126 312.218 + endloop + endfacet + facet normal 0.777976 -0.559339 -0.286171 + outer loop + vertex 883.148 259.126 312.218 + vertex 886.657 262.849 314.48 + vertex 884.175 259.401 314.471 + endloop + endfacet + facet normal 0.761702 -0.586461 -0.275452 + outer loop + vertex 883.148 259.126 312.218 + vertex 884.175 259.401 314.471 + vertex 880.575 255.783 312.219 + endloop + endfacet + facet normal 0.762477 -0.57923 -0.288308 + outer loop + vertex 880.575 255.783 312.219 + vertex 884.175 259.401 314.471 + vertex 881.639 256.068 314.459 + endloop + endfacet + facet normal 0.749024 -0.600857 -0.279168 + outer loop + vertex 880.575 255.783 312.219 + vertex 881.639 256.068 314.459 + vertex 877.967 252.528 312.227 + endloop + endfacet + facet normal 0.749868 -0.593747 -0.291828 + outer loop + vertex 877.967 252.528 312.227 + vertex 881.639 256.068 314.459 + vertex 879.076 252.837 314.449 + endloop + endfacet + facet normal 0.734674 -0.617515 -0.280945 + outer loop + vertex 877.967 252.528 312.227 + vertex 879.076 252.837 314.449 + vertex 875.301 249.347 312.25 + endloop + endfacet + facet normal 0.735856 -0.608018 -0.298044 + outer loop + vertex 875.301 249.347 312.25 + vertex 879.076 252.837 314.449 + vertex 876.463 249.676 314.448 + endloop + endfacet + facet normal 0.721896 -0.629469 -0.287463 + outer loop + vertex 875.301 249.347 312.25 + vertex 876.463 249.676 314.448 + vertex 872.557 246.184 312.285 + endloop + endfacet + facet normal 0.722172 -0.62734 -0.291397 + outer loop + vertex 872.557 246.184 312.285 + vertex 876.463 249.676 314.448 + vertex 873.736 246.527 314.469 + endloop + endfacet + facet normal 0.710128 -0.645084 -0.282109 + outer loop + vertex 872.557 246.184 312.285 + vertex 873.736 246.527 314.469 + vertex 869.684 243.006 312.318 + endloop + endfacet + facet normal 0.710875 -0.639651 -0.292409 + outer loop + vertex 869.684 243.006 312.318 + vertex 873.736 246.527 314.469 + vertex 870.855 243.317 314.485 + endloop + endfacet + facet normal 0.695021 -0.661958 -0.280639 + outer loop + vertex 869.684 243.006 312.318 + vertex 870.855 243.317 314.485 + vertex 866.681 239.851 312.323 + endloop + endfacet + facet normal 0.696262 -0.654027 -0.29575 + outer loop + vertex 866.681 239.851 312.323 + vertex 870.855 243.317 314.485 + vertex 867.811 240.08 314.477 + endloop + endfacet + facet normal 0.684328 -0.669982 -0.287784 + outer loop + vertex 866.681 239.851 312.323 + vertex 867.811 240.08 314.477 + vertex 863.732 236.855 312.287 + endloop + endfacet + facet normal 0.685653 -0.662979 -0.300565 + outer loop + vertex 863.732 236.855 312.287 + vertex 867.811 240.08 314.477 + vertex 864.826 237.011 314.437 + endloop + endfacet + facet normal 0.679522 -0.670908 -0.296872 + outer loop + vertex 863.732 236.855 312.287 + vertex 864.826 237.011 314.437 + vertex 861.206 234.303 312.271 + endloop + endfacet + facet normal 0.680708 -0.666105 -0.304861 + outer loop + vertex 861.206 234.303 312.271 + vertex 864.826 237.011 314.437 + vertex 862.3 234.43 314.437 + endloop + endfacet + facet normal 0.682611 -0.663646 -0.305966 + outer loop + vertex 861.206 234.303 312.271 + vertex 862.3 234.43 314.437 + vertex 859.529 232.495 312.451 + endloop + endfacet + facet normal 0.678541 -0.675387 -0.288852 + outer loop + vertex 859.529 232.495 312.451 + vertex 862.3 234.43 314.437 + vertex 860.653 232.693 314.63 + endloop + endfacet + facet normal 0.693619 -0.655622 -0.298417 + outer loop + vertex 859.529 232.495 312.451 + vertex 860.653 232.693 314.63 + vertex 858.948 231.581 313.111 + endloop + endfacet + facet normal 0.667845 -0.707338 -0.231636 + outer loop + vertex 858.948 231.581 313.111 + vertex 860.653 232.693 314.63 + vertex 860.052 231.968 315.111 + endloop + endfacet + facet normal 0.98046 0.175777 -0.0883175 + outer loop + vertex 904.353 377.142 313.959 + vertex 904.253 378.959 316.471 + vertex 904.989 373.781 314.33 + endloop + endfacet + facet normal 0.979319 0.178488 -0.095266 + outer loop + vertex 904.989 373.781 314.33 + vertex 904.253 378.959 316.471 + vertex 905.139 374.357 316.954 + endloop + endfacet + facet normal 0.982226 0.163525 -0.0921493 + outer loop + vertex 904.989 373.781 314.33 + vertex 905.139 374.357 316.954 + vertex 905.699 369.588 314.459 + endloop + endfacet + facet normal 0.980593 0.167997 -0.101063 + outer loop + vertex 905.699 369.588 314.459 + vertex 905.139 374.357 316.954 + vertex 905.947 369.625 316.928 + endloop + endfacet + facet normal 0.983287 0.151427 -0.101081 + outer loop + vertex 905.699 369.588 314.459 + vertex 905.947 369.625 316.928 + vertex 906.36 365.294 314.455 + endloop + endfacet + facet normal 0.982741 0.153015 -0.103952 + outer loop + vertex 906.36 365.294 314.455 + vertex 905.947 369.625 316.928 + vertex 906.618 365.285 316.885 + endloop + endfacet + facet normal 0.984973 0.137697 -0.10425 + outer loop + vertex 906.36 365.294 314.455 + vertex 906.618 365.285 316.885 + vertex 906.946 361.092 314.448 + endloop + endfacet + facet normal 0.985104 0.137296 -0.103542 + outer loop + vertex 906.946 361.092 314.448 + vertex 906.618 365.285 316.885 + vertex 907.199 361.123 316.889 + endloop + endfacet + facet normal 0.987035 0.122633 -0.103555 + outer loop + vertex 906.946 361.092 314.448 + vertex 907.199 361.123 316.889 + vertex 907.465 356.928 314.459 + endloop + endfacet + facet normal 0.986923 0.122994 -0.10419 + outer loop + vertex 907.465 356.928 314.459 + vertex 907.199 361.123 316.889 + vertex 907.717 356.981 316.911 + endloop + endfacet + facet normal 0.988834 0.106698 -0.104036 + outer loop + vertex 907.465 356.928 314.459 + vertex 907.717 356.981 316.911 + vertex 907.921 352.716 314.474 + endloop + endfacet + facet normal 0.988921 0.106401 -0.103511 + outer loop + vertex 907.921 352.716 314.474 + vertex 907.717 356.981 316.911 + vertex 908.172 352.773 316.929 + endloop + endfacet + facet normal 0.990749 0.08804 -0.103274 + outer loop + vertex 907.921 352.716 314.474 + vertex 908.172 352.773 316.929 + vertex 908.303 348.419 314.478 + endloop + endfacet + facet normal 0.990438 0.0891586 -0.105278 + outer loop + vertex 908.303 348.419 314.478 + vertex 908.172 352.773 316.929 + vertex 908.559 348.477 316.934 + endloop + endfacet + facet normal 0.9921 0.0686939 -0.104967 + outer loop + vertex 908.303 348.419 314.478 + vertex 908.559 348.477 316.934 + vertex 908.605 344.047 314.474 + endloop + endfacet + facet normal 0.991654 0.0703843 -0.108019 + outer loop + vertex 908.605 344.047 314.474 + vertex 908.559 348.477 316.934 + vertex 908.868 344.115 316.931 + endloop + endfacet + facet normal 0.992986 0.0490595 -0.107576 + outer loop + vertex 908.605 344.047 314.474 + vertex 908.868 344.115 316.931 + vertex 908.823 339.645 314.471 + endloop + endfacet + facet normal 0.993075 0.0486952 -0.106916 + outer loop + vertex 908.823 339.645 314.471 + vertex 908.868 344.115 316.931 + vertex 909.082 339.745 316.928 + endloop + endfacet + facet normal 0.99405 0.0248502 -0.106051 + outer loop + vertex 908.823 339.645 314.471 + vertex 909.082 339.745 316.928 + vertex 908.932 335.271 314.469 + endloop + endfacet + facet normal 0.993857 0.0257281 -0.107636 + outer loop + vertex 908.932 335.271 314.469 + vertex 909.082 339.745 316.928 + vertex 909.195 335.397 316.926 + endloop + endfacet + facet normal 0.994326 0.000110414 -0.106377 + outer loop + vertex 908.932 335.271 314.469 + vertex 909.195 335.397 316.926 + vertex 908.932 330.942 314.47 + endloop + endfacet + facet normal 0.994034 0.0016078 -0.109062 + outer loop + vertex 908.932 330.942 314.47 + vertex 909.195 335.397 316.926 + vertex 909.202 331.093 316.926 + endloop + endfacet + facet normal 0.993856 -0.0272659 -0.107267 + outer loop + vertex 908.932 330.942 314.47 + vertex 909.202 331.093 316.926 + vertex 908.815 326.665 314.472 + endloop + endfacet + facet normal 0.993684 -0.0262341 -0.109102 + outer loop + vertex 908.815 326.665 314.472 + vertex 909.202 331.093 316.926 + vertex 909.089 326.838 316.927 + endloop + endfacet + facet normal 0.992554 -0.0587734 -0.106688 + outer loop + vertex 908.815 326.665 314.472 + vertex 909.089 326.838 316.927 + vertex 908.565 322.444 314.471 + endloop + endfacet + facet normal 0.992222 -0.0563135 -0.111017 + outer loop + vertex 908.565 322.444 314.471 + vertex 909.089 326.838 316.927 + vertex 908.851 322.63 316.929 + endloop + endfacet + facet normal 0.989887 -0.0919113 -0.108059 + outer loop + vertex 908.565 322.444 314.471 + vertex 908.851 322.63 316.929 + vertex 908.176 318.256 314.469 + endloop + endfacet + facet normal 0.989532 -0.088531 -0.113969 + outer loop + vertex 908.176 318.256 314.469 + vertex 908.851 322.63 316.929 + vertex 908.477 318.446 316.93 + endloop + endfacet + facet normal 0.985943 -0.125137 -0.11071 + outer loop + vertex 908.176 318.256 314.469 + vertex 908.477 318.446 316.93 + vertex 907.644 314.071 314.463 + endloop + endfacet + facet normal 0.985963 -0.125422 -0.110211 + outer loop + vertex 907.644 314.071 314.463 + vertex 908.477 318.446 316.93 + vertex 907.945 314.27 316.926 + endloop + endfacet + facet normal 0.9806 -0.164637 -0.106384 + outer loop + vertex 907.644 314.071 314.463 + vertex 907.945 314.27 316.926 + vertex 906.939 309.881 314.451 + endloop + endfacet + facet normal 0.980502 -0.16135 -0.112172 + outer loop + vertex 906.939 309.881 314.451 + vertex 907.945 314.27 316.926 + vertex 907.255 310.083 316.917 + endloop + endfacet + facet normal 0.973746 -0.200321 -0.10812 + outer loop + vertex 906.939 309.881 314.451 + vertex 907.255 310.083 316.917 + vertex 906.074 305.678 314.441 + endloop + endfacet + facet normal 0.97375 -0.197017 -0.113997 + outer loop + vertex 906.074 305.678 314.441 + vertex 907.255 310.083 316.917 + vertex 906.409 305.908 316.906 + endloop + endfacet + facet normal 0.965105 -0.238099 -0.108998 + outer loop + vertex 906.074 305.678 314.441 + vertex 906.409 305.908 316.906 + vertex 905.043 301.501 314.44 + endloop + endfacet + facet normal 0.965248 -0.233819 -0.116727 + outer loop + vertex 905.043 301.501 314.44 + vertex 906.409 305.908 316.906 + vertex 905.405 301.77 316.895 + endloop + endfacet + facet normal 0.955504 -0.273315 -0.110953 + outer loop + vertex 905.043 301.501 314.44 + vertex 905.405 301.77 316.895 + vertex 903.861 297.362 314.457 + endloop + endfacet + facet normal 0.955601 -0.271891 -0.11359 + outer loop + vertex 903.861 297.362 314.457 + vertex 905.405 301.77 316.895 + vertex 904.24 297.679 316.888 + endloop + endfacet + facet normal 0.944178 -0.31171 -0.106605 + outer loop + vertex 903.861 297.362 314.457 + vertex 904.24 297.679 316.888 + vertex 902.504 293.244 314.478 + endloop + endfacet + facet normal 0.944579 -0.307871 -0.11396 + outer loop + vertex 902.504 293.244 314.478 + vertex 904.24 297.679 316.888 + vertex 902.914 293.613 316.88 + endloop + endfacet + facet normal 0.930735 -0.350271 -0.105081 + outer loop + vertex 902.504 293.244 314.478 + vertex 902.914 293.613 316.88 + vertex 900.962 289.14 314.497 + endloop + endfacet + facet normal 0.931398 -0.345495 -0.11459 + outer loop + vertex 900.962 289.14 314.497 + vertex 902.914 293.613 316.88 + vertex 901.415 289.574 316.869 + endloop + endfacet + facet normal 0.917152 -0.384535 -0.104711 + outer loop + vertex 900.962 289.14 314.497 + vertex 901.415 289.574 316.869 + vertex 899.268 285.099 314.506 + endloop + endfacet + facet normal 0.917869 -0.380395 -0.113206 + outer loop + vertex 899.268 285.099 314.506 + vertex 901.415 289.574 316.869 + vertex 899.761 285.59 316.853 + endloop + endfacet + facet normal 0.903432 -0.416254 -0.102678 + outer loop + vertex 899.268 285.099 314.506 + vertex 899.761 285.59 316.853 + vertex 897.458 281.172 314.494 + endloop + endfacet + facet normal 0.904659 -0.410341 -0.114947 + outer loop + vertex 897.458 281.172 314.494 + vertex 899.761 285.59 316.853 + vertex 897.99 281.69 316.838 + endloop + endfacet + facet normal 0.888344 -0.447469 -0.103035 + outer loop + vertex 897.458 281.172 314.494 + vertex 897.99 281.69 316.838 + vertex 895.539 277.367 314.476 + endloop + endfacet + facet normal 0.889628 -0.442251 -0.113917 + outer loop + vertex 895.539 277.367 314.476 + vertex 897.99 281.69 316.838 + vertex 896.1 277.888 316.833 + endloop + endfacet + facet normal 0.871329 -0.480152 -0.101193 + outer loop + vertex 895.539 277.367 314.476 + vertex 896.1 277.888 316.833 + vertex 893.497 273.661 314.473 + endloop + endfacet + facet normal 0.873697 -0.47171 -0.118926 + outer loop + vertex 893.497 273.661 314.473 + vertex 896.1 277.888 316.833 + vertex 894.091 274.167 316.837 + endloop + endfacet + facet normal 0.857019 -0.503873 -0.107847 + outer loop + vertex 893.497 273.661 314.473 + vertex 894.091 274.167 316.837 + vertex 891.345 270.001 314.478 + endloop + endfacet + facet normal 0.857121 -0.503552 -0.108531 + outer loop + vertex 891.345 270.001 314.478 + vertex 894.091 274.167 316.837 + vertex 891.945 270.512 316.845 + endloop + endfacet + facet normal 0.839433 -0.534677 -0.0973327 + outer loop + vertex 891.345 270.001 314.478 + vertex 891.945 270.512 316.845 + vertex 889.051 266.399 314.483 + endloop + endfacet + facet normal 0.841664 -0.528509 -0.110813 + outer loop + vertex 889.051 266.399 314.483 + vertex 891.945 270.512 316.845 + vertex 889.682 266.908 316.847 + endloop + endfacet + facet normal 0.824898 -0.556302 -0.100355 + outer loop + vertex 889.051 266.399 314.483 + vertex 889.682 266.908 316.847 + vertex 886.657 262.849 314.48 + endloop + endfacet + facet normal 0.82568 -0.55433 -0.104737 + outer loop + vertex 886.657 262.849 314.48 + vertex 889.682 266.908 316.847 + vertex 887.308 263.373 316.844 + endloop + endfacet + facet normal 0.808083 -0.581543 -0.0938596 + outer loop + vertex 886.657 262.849 314.48 + vertex 887.308 263.373 316.844 + vertex 884.175 259.401 314.471 + endloop + endfacet + facet normal 0.810471 -0.576078 -0.106161 + outer loop + vertex 884.175 259.401 314.471 + vertex 887.308 263.373 316.844 + vertex 884.864 259.935 316.836 + endloop + endfacet + facet normal 0.792359 -0.602631 -0.0948854 + outer loop + vertex 884.175 259.401 314.471 + vertex 884.864 259.935 316.836 + vertex 881.639 256.068 314.459 + endloop + endfacet + facet normal 0.795289 -0.596329 -0.109117 + outer loop + vertex 881.639 256.068 314.459 + vertex 884.864 259.935 316.836 + vertex 882.371 256.612 316.825 + endloop + endfacet + facet normal 0.779783 -0.618124 -0.0993074 + outer loop + vertex 881.639 256.068 314.459 + vertex 882.371 256.612 316.825 + vertex 879.076 252.837 314.449 + endloop + endfacet + facet normal 0.780568 -0.616541 -0.102911 + outer loop + vertex 879.076 252.837 314.449 + vertex 882.371 256.612 316.825 + vertex 879.83 253.396 316.823 + endloop + endfacet + facet normal 0.76743 -0.634116 -0.0945912 + outer loop + vertex 879.076 252.837 314.449 + vertex 879.83 253.396 316.823 + vertex 876.463 249.676 314.448 + endloop + endfacet + facet normal 0.76714 -0.634652 -0.0933399 + outer loop + vertex 876.463 249.676 314.448 + vertex 879.83 253.396 316.823 + vertex 877.217 250.236 316.832 + endloop + endfacet + facet normal 0.752933 -0.652634 -0.0846221 + outer loop + vertex 876.463 249.676 314.448 + vertex 877.217 250.236 316.832 + vertex 873.736 246.527 314.469 + endloop + endfacet + facet normal 0.755565 -0.648046 -0.0957009 + outer loop + vertex 873.736 246.527 314.469 + vertex 877.217 250.236 316.832 + vertex 874.479 247.041 316.85 + endloop + endfacet + facet normal 0.74108 -0.665709 -0.0873626 + outer loop + vertex 873.736 246.527 314.469 + vertex 874.479 247.041 316.85 + vertex 870.855 243.317 314.485 + endloop + endfacet + facet normal 0.741305 -0.665334 -0.0882992 + outer loop + vertex 870.855 243.317 314.485 + vertex 874.479 247.041 316.85 + vertex 871.544 243.77 316.858 + endloop + endfacet + facet normal 0.726183 -0.682762 -0.0805791 + outer loop + vertex 870.855 243.317 314.485 + vertex 871.544 243.77 316.858 + vertex 867.811 240.08 314.477 + endloop + endfacet + facet normal 0.727735 -0.68035 -0.0867494 + outer loop + vertex 867.811 240.08 314.477 + vertex 871.544 243.77 316.858 + vertex 868.472 240.487 316.83 + endloop + endfacet + facet normal 0.715029 -0.694415 -0.0807487 + outer loop + vertex 867.811 240.08 314.477 + vertex 868.472 240.487 316.83 + vertex 864.826 237.011 314.437 + endloop + endfacet + facet normal 0.716894 -0.691658 -0.087595 + outer loop + vertex 864.826 237.011 314.437 + vertex 868.472 240.487 316.83 + vertex 865.516 237.429 316.78 + endloop + endfacet + facet normal 0.712153 -0.696826 -0.0852769 + outer loop + vertex 864.826 237.011 314.437 + vertex 865.516 237.429 316.78 + vertex 862.3 234.43 314.437 + endloop + endfacet + facet normal 0.711658 -0.697521 -0.0837076 + outer loop + vertex 862.3 234.43 314.437 + vertex 865.516 237.429 316.78 + vertex 863.098 234.962 316.785 + endloop + endfacet + facet normal 0.718067 -0.690453 -0.0874866 + outer loop + vertex 862.3 234.43 314.437 + vertex 863.098 234.962 316.785 + vertex 860.653 232.693 314.63 + endloop + endfacet + facet normal 0.709568 -0.701522 -0.0661818 + outer loop + vertex 860.653 232.693 314.63 + vertex 863.098 234.962 316.785 + vertex 861.51 233.346 316.891 + endloop + endfacet + facet normal 0.738024 -0.669232 -0.086309 + outer loop + vertex 860.653 232.693 314.63 + vertex 861.51 233.346 316.891 + vertex 860.052 231.968 315.111 + endloop + endfacet + facet normal 0.725689 -0.685044 -0.0639533 + outer loop + vertex 860.052 231.968 315.111 + vertex 861.51 233.346 316.891 + vertex 860.661 232.446 316.889 + endloop + endfacet + facet normal 0.587383 -0.809135 0.0167996 + outer loop + vertex 860.052 231.968 315.111 + vertex 860.661 232.446 316.889 + vertex 859.425 231.508 314.882 + endloop + endfacet + facet normal 0.989387 0.13795 -0.045637 + outer loop + vertex 906.618 365.285 316.885 + vertex 906.688 365.666 319.547 + vertex 907.199 361.123 316.889 + endloop + endfacet + facet normal 0.988454 0.142029 -0.0527879 + outer loop + vertex 907.199 361.123 316.889 + vertex 906.688 365.666 319.547 + vertex 907.318 361.113 319.107 + endloop + endfacet + facet normal 0.990895 0.123766 -0.053002 + outer loop + vertex 907.199 361.123 316.889 + vertex 907.318 361.113 319.107 + vertex 907.717 356.981 316.911 + endloop + endfacet + facet normal 0.992146 0.117909 -0.041752 + outer loop + vertex 907.717 356.981 316.911 + vertex 907.318 361.113 319.107 + vertex 907.781 357.387 319.573 + endloop + endfacet + facet normal 0.993431 0.107158 -0.0401414 + outer loop + vertex 907.717 356.981 316.911 + vertex 907.781 357.387 319.573 + vertex 908.172 352.773 316.929 + endloop + endfacet + facet normal 0.992547 0.111828 -0.0484225 + outer loop + vertex 908.172 352.773 316.929 + vertex 907.781 357.387 319.573 + vertex 908.282 352.753 319.148 + endloop + endfacet + facet normal 0.994783 0.0896162 -0.0487377 + outer loop + vertex 908.172 352.773 316.929 + vertex 908.282 352.753 319.148 + vertex 908.559 348.477 316.934 + endloop + endfacet + facet normal 0.995877 0.083187 -0.036183 + outer loop + vertex 908.559 348.477 316.934 + vertex 908.282 352.753 319.148 + vertex 908.62 348.899 319.595 + endloop + endfacet + facet normal 0.996909 0.0707131 -0.0342266 + outer loop + vertex 908.559 348.477 316.934 + vertex 908.62 348.899 319.595 + vertex 908.868 344.115 316.931 + endloop + endfacet + facet normal 0.996131 0.0760931 -0.0439624 + outer loop + vertex 908.868 344.115 316.931 + vertex 908.62 348.899 319.595 + vertex 908.965 344.133 319.152 + endloop + endfacet + facet normal 0.997844 0.0488744 -0.0438086 + outer loop + vertex 908.868 344.115 316.931 + vertex 908.965 344.133 319.152 + vertex 909.082 339.745 316.928 + endloop + endfacet + facet normal 0.99876 0.0410009 -0.0282232 + outer loop + vertex 909.082 339.745 316.928 + vertex 908.965 344.133 319.152 + vertex 909.136 340.26 319.593 + endloop + endfacet + facet normal 0.999346 0.0258347 -0.0253073 + outer loop + vertex 909.082 339.745 316.928 + vertex 909.136 340.26 319.593 + vertex 909.195 335.397 316.926 + endloop + endfacet + facet normal 0.998626 0.0338772 -0.0399853 + outer loop + vertex 909.195 335.397 316.926 + vertex 909.136 340.26 319.593 + vertex 909.28 335.489 319.147 + endloop + endfacet + facet normal 0.999251 0.00161574 -0.0386658 + outer loop + vertex 909.195 335.397 316.926 + vertex 909.28 335.489 319.147 + vertex 909.202 331.093 316.926 + endloop + endfacet + facet normal 0.999797 -0.0087758 -0.0181214 + outer loop + vertex 909.202 331.093 316.926 + vertex 909.28 335.489 319.147 + vertex 909.255 331.693 319.592 + endloop + endfacet + facet normal 0.999552 -0.0263588 -0.0141542 + outer loop + vertex 909.202 331.093 316.926 + vertex 909.255 331.693 319.592 + vertex 909.089 326.838 316.927 + endloop + endfacet + facet normal 0.999378 -0.0172276 -0.0307839 + outer loop + vertex 909.089 326.838 316.927 + vertex 909.255 331.693 319.592 + vertex 909.16 326.993 319.149 + endloop + endfacet + facet normal 0.998005 -0.056598 -0.0279938 + outer loop + vertex 909.089 326.838 316.927 + vertex 909.16 326.993 319.149 + vertex 908.851 322.63 316.929 + endloop + endfacet + facet normal 0.997637 -0.0685625 -0.00442252 + outer loop + vertex 908.851 322.63 316.929 + vertex 909.16 326.993 319.149 + vertex 908.907 323.279 319.596 + endloop + endfacet + facet normal 0.996023 -0.0890891 0.00061162 + outer loop + vertex 908.851 322.63 316.929 + vertex 908.907 323.279 319.596 + vertex 908.477 318.446 316.93 + endloop + endfacet + facet normal 0.996631 -0.0806816 -0.0147305 + outer loop + vertex 908.477 318.446 316.93 + vertex 908.907 323.279 319.596 + vertex 908.524 318.632 319.154 + endloop + endfacet + facet normal 0.991936 -0.126274 -0.0108198 + outer loop + vertex 908.477 318.446 316.93 + vertex 908.524 318.632 319.154 + vertex 907.945 314.27 316.926 + endloop + endfacet + facet normal 0.990497 -0.137113 0.0107795 + outer loop + vertex 907.945 314.27 316.926 + vertex 908.524 318.632 319.154 + vertex 908.008 314.935 319.598 + endloop + endfacet + facet normal 0.986538 -0.162622 0.0172279 + outer loop + vertex 907.945 314.27 316.926 + vertex 908.008 314.935 319.598 + vertex 907.255 310.083 316.917 + endloop + endfacet + facet normal 0.988386 -0.151944 -0.00262341 + outer loop + vertex 907.255 310.083 316.917 + vertex 908.008 314.935 319.598 + vertex 907.293 310.29 319.146 + endloop + endfacet + facet normal 0.980074 -0.198624 0.00186664 + outer loop + vertex 907.255 310.083 316.917 + vertex 907.293 310.29 319.146 + vertex 906.409 305.908 316.906 + endloop + endfacet + facet normal 0.97739 -0.209951 0.0250805 + outer loop + vertex 906.409 305.908 316.906 + vertex 907.293 310.29 319.146 + vertex 906.495 306.631 319.583 + endloop + endfacet + facet normal 0.971299 -0.235668 0.0322198 + outer loop + vertex 906.409 305.908 316.906 + vertex 906.495 306.631 319.583 + vertex 905.405 301.77 316.895 + endloop + endfacet + facet normal 0.975261 -0.221016 0.0041178 + outer loop + vertex 905.405 301.77 316.895 + vertex 906.495 306.631 319.583 + vertex 905.457 302.039 319.124 + endloop + endfacet + facet normal 0.961714 -0.273843 0.0108098 + outer loop + vertex 905.405 301.77 316.895 + vertex 905.457 302.039 319.124 + vertex 904.24 297.679 316.888 + endloop + endfacet + facet normal 0.956906 -0.287594 0.0402441 + outer loop + vertex 904.24 297.679 316.888 + vertex 905.457 302.039 319.124 + vertex 904.364 298.463 319.559 + endloop + endfacet + facet normal 0.949621 -0.309842 0.0471065 + outer loop + vertex 904.24 297.679 316.888 + vertex 904.364 298.463 319.559 + vertex 902.914 293.613 316.88 + endloop + endfacet + facet normal 0.954133 -0.298421 0.0239927 + outer loop + vertex 902.914 293.613 316.88 + vertex 904.364 298.463 319.559 + vertex 902.96 293.938 319.097 + endloop + endfacet + facet normal 0.936973 -0.347967 0.0316163 + outer loop + vertex 902.914 293.613 316.88 + vertex 902.96 293.938 319.097 + vertex 901.415 289.574 316.869 + endloop + endfacet + facet normal 0.93168 -0.358846 0.0565952 + outer loop + vertex 901.415 289.574 316.869 + vertex 902.96 293.938 319.097 + vertex 901.575 290.411 319.534 + endloop + endfacet + facet normal 0.921622 -0.382661 0.0646796 + outer loop + vertex 901.415 289.574 316.869 + vertex 901.575 290.411 319.534 + vertex 899.761 285.59 316.853 + endloop + endfacet + facet normal 0.930855 -0.364482 0.0257375 + outer loop + vertex 899.761 285.59 316.853 + vertex 901.575 290.411 319.534 + vertex 899.845 285.959 319.071 + endloop + endfacet + facet normal 0.909931 -0.413308 0.0346596 + outer loop + vertex 899.761 285.59 316.853 + vertex 899.845 285.959 319.071 + vertex 897.99 281.69 316.838 + endloop + endfacet + facet normal 0.901626 -0.427137 0.0679997 + outer loop + vertex 897.99 281.69 316.838 + vertex 899.845 285.959 319.071 + vertex 898.205 282.57 319.521 + endloop + endfacet + facet normal 0.892875 -0.444136 0.0742766 + outer loop + vertex 897.99 281.69 316.838 + vertex 898.205 282.57 319.521 + vertex 896.1 277.888 316.833 + endloop + endfacet + facet normal 0.903285 -0.427439 0.0370488 + outer loop + vertex 896.1 277.888 316.833 + vertex 898.205 282.57 319.521 + vertex 896.198 278.289 319.07 + endloop + endfacet + facet normal 0.879066 -0.474424 0.0465355 + outer loop + vertex 896.1 277.888 316.833 + vertex 896.198 278.289 319.07 + vertex 894.091 274.167 316.837 + endloop + endfacet + facet normal 0.868482 -0.488735 0.0829274 + outer loop + vertex 894.091 274.167 316.837 + vertex 896.198 278.289 319.07 + vertex 894.337 275.06 319.53 + endloop + endfacet + facet normal 0.858985 -0.504218 0.0889271 + outer loop + vertex 894.091 274.167 316.837 + vertex 894.337 275.06 319.53 + vertex 891.945 270.512 316.845 + endloop + endfacet + facet normal 0.869332 -0.490911 0.057172 + outer loop + vertex 891.945 270.512 316.845 + vertex 894.337 275.06 319.53 + vertex 892.039 270.94 319.081 + endloop + endfacet + facet normal 0.845097 -0.53055 0.065776 + outer loop + vertex 891.945 270.512 316.845 + vertex 892.039 270.94 319.081 + vertex 889.682 266.908 316.847 + endloop + endfacet + facet normal 0.835984 -0.540694 0.0937047 + outer loop + vertex 889.682 266.908 316.847 + vertex 892.039 270.94 319.081 + vertex 889.974 267.826 319.537 + endloop + endfacet + facet normal 0.826038 -0.554748 0.0995811 + outer loop + vertex 889.682 266.908 316.847 + vertex 889.974 267.826 319.537 + vertex 887.308 263.373 316.844 + endloop + endfacet + facet normal 0.837938 -0.541727 0.0662675 + outer loop + vertex 887.308 263.373 316.844 + vertex 889.974 267.826 319.537 + vertex 887.437 263.845 319.083 + endloop + endfacet + facet normal 0.812561 -0.577983 0.0753692 + outer loop + vertex 887.308 263.373 316.844 + vertex 887.437 263.845 319.083 + vertex 884.864 259.935 316.836 + endloop + endfacet + facet normal 0.800833 -0.589057 0.108063 + outer loop + vertex 884.864 259.935 316.836 + vertex 887.437 263.845 319.083 + vertex 885.219 260.913 319.536 + endloop + endfacet + facet normal 0.794736 -0.596607 0.111599 + outer loop + vertex 884.864 259.935 316.836 + vertex 885.219 260.913 319.536 + vertex 882.371 256.612 316.825 + endloop + endfacet + facet normal 0.808484 -0.583536 0.076411 + outer loop + vertex 882.371 256.612 316.825 + vertex 885.219 260.913 319.536 + vertex 882.536 257.137 319.081 + endloop + endfacet + facet normal 0.781728 -0.61762 0.0862947 + outer loop + vertex 882.371 256.612 316.825 + vertex 882.536 257.137 319.081 + vertex 879.83 253.396 316.823 + endloop + endfacet + facet normal 0.771028 -0.626536 0.113879 + outer loop + vertex 879.83 253.396 316.823 + vertex 882.536 257.137 319.081 + vertex 880.214 254.362 319.542 + endloop + endfacet + facet normal 0.765515 -0.632719 0.116851 + outer loop + vertex 879.83 253.396 316.823 + vertex 880.214 254.362 319.542 + vertex 877.217 250.236 316.832 + endloop + endfacet + facet normal 0.780778 -0.619654 0.0800918 + outer loop + vertex 877.217 250.236 316.832 + vertex 880.214 254.362 319.542 + vertex 877.36 250.709 319.1 + endloop + endfacet + facet normal 0.75666 -0.647926 0.0875073 + outer loop + vertex 877.217 250.236 316.832 + vertex 877.36 250.709 319.1 + vertex 874.479 247.041 316.85 + endloop + endfacet + facet normal 0.740259 -0.659992 0.128168 + outer loop + vertex 874.479 247.041 316.85 + vertex 877.36 250.709 319.1 + vertex 874.771 247.895 319.561 + endloop + endfacet + facet normal 0.738259 -0.66206 0.129035 + outer loop + vertex 874.479 247.041 316.85 + vertex 874.771 247.895 319.561 + vertex 871.544 243.77 316.858 + endloop + endfacet + facet normal 0.750485 -0.653149 0.100837 + outer loop + vertex 871.544 243.77 316.858 + vertex 874.771 247.895 319.561 + vertex 871.583 244.16 319.098 + endloop + endfacet + facet normal 0.72555 -0.679967 0.10593 + outer loop + vertex 871.544 243.77 316.858 + vertex 871.583 244.16 319.098 + vertex 868.472 240.487 316.83 + endloop + endfacet + facet normal 0.711228 -0.688878 0.140004 + outer loop + vertex 868.472 240.487 316.83 + vertex 871.583 244.16 319.098 + vertex 868.853 241.425 319.509 + endloop + endfacet + facet normal 0.710677 -0.689394 0.140263 + outer loop + vertex 868.472 240.487 316.83 + vertex 868.853 241.425 319.509 + vertex 865.516 237.429 316.78 + endloop + endfacet + facet normal 0.727883 -0.677992 0.102537 + outer loop + vertex 865.516 237.429 316.78 + vertex 868.853 241.425 319.509 + vertex 865.794 238.068 319.021 + endloop + endfacet + facet normal 0.710052 -0.695543 0.109754 + outer loop + vertex 865.516 237.429 316.78 + vertex 865.794 238.068 319.021 + vertex 863.098 234.962 316.785 + endloop + endfacet + facet normal 0.690476 -0.707607 0.15012 + outer loop + vertex 863.098 234.962 316.785 + vertex 865.794 238.068 319.021 + vertex 863.922 236.352 319.547 + endloop + endfacet + facet normal 0.711214 -0.689887 0.135017 + outer loop + vertex 863.098 234.962 316.785 + vertex 863.922 236.352 319.547 + vertex 861.51 233.346 316.891 + endloop + endfacet + facet normal 0.730509 -0.675381 0.101082 + outer loop + vertex 861.51 233.346 316.891 + vertex 863.922 236.352 319.547 + vertex 861.957 234.169 319.158 + endloop + endfacet + facet normal 0.72298 -0.682803 0.105259 + outer loop + vertex 861.51 233.346 316.891 + vertex 861.957 234.169 319.158 + vertex 860.661 232.446 316.889 + endloop + endfacet + facet normal 0.797396 -0.603452 0.0024736 + outer loop + vertex 860.661 232.446 316.889 + vertex 861.957 234.169 319.158 + vertex 861.074 232.999 318.459 + endloop + endfacet + facet normal 0.994246 0.106752 0.00891232 + outer loop + vertex 908.282 352.753 319.148 + vertex 907.781 357.387 319.573 + vertex 907.878 356.228 322.639 + endloop + endfacet + facet normal 0.995588 0.0903173 0.0254273 + outer loop + vertex 908.282 352.753 319.148 + vertex 907.878 356.228 322.639 + vertex 908.62 348.899 319.595 + endloop + endfacet + facet normal 0.995625 0.0887532 0.0292022 + outer loop + vertex 907.878 356.228 322.639 + vertex 908.631 347.769 322.656 + vertex 908.62 348.899 319.595 + endloop + endfacet + facet normal 0.997298 0.070011 0.0222705 + outer loop + vertex 908.965 344.133 319.152 + vertex 908.62 348.899 319.595 + vertex 908.631 347.769 322.656 + endloop + endfacet + facet normal 0.997823 0.049186 0.0439242 + outer loop + vertex 908.965 344.133 319.152 + vertex 908.631 347.769 322.656 + vertex 909.136 340.26 319.593 + endloop + endfacet + facet normal 0.997775 0.0484007 0.0458419 + outer loop + vertex 908.631 347.769 322.656 + vertex 909.044 339.264 322.657 + vertex 909.136 340.26 319.593 + endloop + endfacet + facet normal 0.998896 0.0265257 0.0387694 + outer loop + vertex 909.28 335.489 319.147 + vertex 909.136 340.26 319.593 + vertex 909.044 339.264 322.657 + endloop + endfacet + facet normal 0.997815 0.00108643 0.0660654 + outer loop + vertex 909.28 335.489 319.147 + vertex 909.044 339.264 322.657 + vertex 909.255 331.693 319.592 + endloop + endfacet + facet normal 0.997641 3.71297e-05 0.0686454 + outer loop + vertex 909.044 339.264 322.657 + vertex 909.044 330.835 322.656 + vertex 909.255 331.693 319.592 + endloop + endfacet + facet normal 0.997778 -0.0258768 0.0613971 + outer loop + vertex 909.16 326.993 319.149 + vertex 909.255 331.693 319.592 + vertex 909.044 330.835 322.656 + endloop + endfacet + facet normal 0.993909 -0.0563795 0.0946882 + outer loop + vertex 909.16 326.993 319.149 + vertex 909.044 330.835 322.656 + vertex 908.907 323.279 319.596 + endloop + endfacet + facet normal 0.993583 -0.0574766 0.0974118 + outer loop + vertex 909.044 330.835 322.656 + vertex 908.562 322.497 322.66 + vertex 908.907 323.279 319.596 + endloop + endfacet + facet normal 0.991955 -0.0901451 0.0888819 + outer loop + vertex 908.524 318.632 319.154 + vertex 908.907 323.279 319.596 + vertex 908.562 322.497 322.66 + endloop + endfacet + facet normal 0.984583 -0.122614 0.124749 + outer loop + vertex 908.524 318.632 319.154 + vertex 908.562 322.497 322.66 + vertex 908.008 314.935 319.598 + endloop + endfacet + facet normal 0.984025 -0.123846 0.127892 + outer loop + vertex 908.562 322.497 322.66 + vertex 907.519 314.212 322.66 + vertex 908.008 314.935 319.598 + endloop + endfacet + facet normal 0.979644 -0.162322 0.118105 + outer loop + vertex 907.293 310.29 319.146 + vertex 908.008 314.935 319.598 + vertex 907.519 314.212 322.66 + endloop + endfacet + facet normal 0.969222 -0.192926 0.152933 + outer loop + vertex 907.293 310.29 319.146 + vertex 907.519 314.212 322.66 + vertex 906.495 306.631 319.583 + endloop + endfacet + facet normal 0.968825 -0.193563 0.154633 + outer loop + vertex 907.519 314.212 322.66 + vertex 905.88 306.005 322.652 + vertex 906.495 306.631 319.583 + endloop + endfacet + facet normal 0.961771 -0.232087 0.145373 + outer loop + vertex 905.457 302.039 319.124 + vertex 906.495 306.631 319.583 + vertex 905.88 306.005 322.652 + endloop + endfacet + facet normal 0.945749 -0.266448 0.185914 + outer loop + vertex 905.457 302.039 319.124 + vertex 905.88 306.005 322.652 + vertex 904.364 298.463 319.559 + endloop + endfacet + facet normal 0.946542 -0.2655 0.183214 + outer loop + vertex 905.88 306.005 322.652 + vertex 903.612 297.909 322.641 + vertex 904.364 298.463 319.559 + endloop + endfacet + facet normal 0.935577 -0.307892 0.17291 + outer loop + vertex 902.96 293.938 319.097 + vertex 904.364 298.463 319.559 + vertex 903.612 297.909 322.641 + endloop + endfacet + facet normal 0.919159 -0.33532 0.206656 + outer loop + vertex 902.96 293.938 319.097 + vertex 903.612 297.909 322.641 + vertex 901.575 290.411 319.534 + endloop + endfacet + facet normal 0.920486 -0.334062 0.202751 + outer loop + vertex 903.612 297.909 322.641 + vertex 900.724 289.946 322.634 + vertex 901.575 290.411 319.534 + endloop + endfacet + facet normal 0.907518 -0.372853 0.193371 + outer loop + vertex 899.845 285.959 319.071 + vertex 901.575 290.411 319.534 + vertex 900.724 289.946 322.634 + endloop + endfacet + facet normal 0.888059 -0.399325 0.227793 + outer loop + vertex 899.845 285.959 319.071 + vertex 900.724 289.946 322.634 + vertex 898.205 282.57 319.521 + endloop + endfacet + facet normal 0.889835 -0.397981 0.22317 + outer loop + vertex 900.724 289.946 322.634 + vertex 897.275 282.236 322.636 + vertex 898.205 282.57 319.521 + endloop + endfacet + facet normal 0.875315 -0.433092 0.215072 + outer loop + vertex 896.198 278.289 319.07 + vertex 898.205 282.57 319.521 + vertex 897.275 282.236 322.636 + endloop + endfacet + facet normal 0.85421 -0.45701 0.247925 + outer loop + vertex 896.198 278.289 319.07 + vertex 897.275 282.236 322.636 + vertex 894.337 275.06 319.53 + endloop + endfacet + facet normal 0.856376 -0.455691 0.24283 + outer loop + vertex 897.275 282.236 322.636 + vertex 893.329 274.825 322.643 + vertex 894.337 275.06 319.53 + endloop + endfacet + facet normal 0.838073 -0.492776 0.234104 + outer loop + vertex 892.039 270.94 319.081 + vertex 894.337 275.06 319.53 + vertex 893.329 274.825 322.643 + endloop + endfacet + facet normal 0.82242 -0.507894 0.256258 + outer loop + vertex 892.039 270.94 319.081 + vertex 893.329 274.825 322.643 + vertex 889.974 267.826 319.537 + endloop + endfacet + facet normal 0.822166 -0.508022 0.256819 + outer loop + vertex 893.329 274.825 322.643 + vertex 888.932 267.714 322.651 + vertex 889.974 267.826 319.537 + endloop + endfacet + facet normal 0.803461 -0.540607 0.24939 + outer loop + vertex 887.437 263.845 319.083 + vertex 889.974 267.826 319.537 + vertex 888.932 267.714 322.651 + endloop + endfacet + facet normal 0.787443 -0.553871 0.270483 + outer loop + vertex 887.437 263.845 319.083 + vertex 888.932 267.714 322.651 + vertex 885.219 260.913 319.536 + endloop + endfacet + facet normal 0.787998 -0.553644 0.269327 + outer loop + vertex 888.932 267.714 322.651 + vertex 884.159 260.923 322.658 + vertex 885.219 260.913 319.536 + endloop + endfacet + facet normal 0.771119 -0.579524 0.263681 + outer loop + vertex 882.536 257.137 319.081 + vertex 885.219 260.913 319.536 + vertex 884.159 260.923 322.658 + endloop + endfacet + facet normal 0.758641 -0.588714 0.279068 + outer loop + vertex 882.536 257.137 319.081 + vertex 884.159 260.923 322.658 + vertex 880.214 254.362 319.542 + endloop + endfacet + facet normal 0.756076 -0.589584 0.284146 + outer loop + vertex 884.159 260.923 322.658 + vertex 879.016 254.332 322.666 + vertex 880.214 254.362 319.542 + endloop + endfacet + facet normal 0.740379 -0.61205 0.27791 + outer loop + vertex 877.36 250.709 319.1 + vertex 880.214 254.362 319.542 + vertex 879.016 254.332 322.666 + endloop + endfacet + facet normal 0.727095 -0.62086 0.293027 + outer loop + vertex 877.36 250.709 319.1 + vertex 879.016 254.332 322.666 + vertex 874.771 247.895 319.561 + endloop + endfacet + facet normal 0.724115 -0.621636 0.298709 + outer loop + vertex 879.016 254.332 322.666 + vertex 873.46 247.846 322.638 + vertex 874.771 247.895 319.561 + endloop + endfacet + facet normal 0.709225 -0.641647 0.292043 + outer loop + vertex 871.583 244.16 319.098 + vertex 874.771 247.895 319.561 + vertex 873.46 247.846 322.638 + endloop + endfacet + facet normal 0.696344 -0.648971 0.306499 + outer loop + vertex 871.583 244.16 319.098 + vertex 873.46 247.846 322.638 + vertex 868.853 241.425 319.509 + endloop + endfacet + facet normal 0.703297 -0.64755 0.293346 + outer loop + vertex 873.46 247.846 322.638 + vertex 868.093 242.021 322.647 + vertex 868.853 241.425 319.509 + endloop + endfacet + facet normal 0.685298 -0.66687 0.292662 + outer loop + vertex 865.794 238.068 319.021 + vertex 868.853 241.425 319.509 + vertex 868.093 242.021 322.647 + endloop + endfacet + facet normal 0.689701 -0.664612 0.287409 + outer loop + vertex 865.794 238.068 319.021 + vertex 868.093 242.021 322.647 + vertex 863.922 236.352 319.547 + endloop + endfacet + facet normal 0.687379 -0.665193 0.291597 + outer loop + vertex 868.093 242.021 322.647 + vertex 864.111 238.135 323.169 + vertex 863.922 236.352 319.547 + endloop + endfacet + facet normal 0.684139 -0.667873 0.293085 + outer loop + vertex 861.957 234.169 319.158 + vertex 863.922 236.352 319.547 + vertex 864.111 238.135 323.169 + endloop + endfacet + facet normal 0.993199 -0.0574525 0.101262 + outer loop + vertex 909.044 330.835 322.656 + vertex 908.653 332.218 327.274 + vertex 908.562 322.497 322.66 + endloop + endfacet + facet normal 0.991343 -0.0638323 0.114741 + outer loop + vertex 908.562 322.497 322.66 + vertex 908.653 332.218 327.274 + vertex 908.123 323.984 327.28 + endloop + endfacet + facet normal 0.98876 -0.0636512 0.135284 + outer loop + vertex 908.653 332.218 327.274 + vertex 908.185 334.06 331.568 + vertex 908.123 323.984 327.28 + endloop + endfacet + facet normal 0.986989 -0.0680611 0.145672 + outer loop + vertex 908.123 323.984 327.28 + vertex 908.185 334.06 331.568 + vertex 907.624 325.948 331.573 + endloop + endfacet + facet normal 0.980755 -0.0676044 0.183167 + outer loop + vertex 908.185 334.06 331.568 + vertex 907.607 336.375 335.514 + vertex 907.624 325.948 331.573 + endloop + endfacet + facet normal 0.978888 -0.0708426 0.191727 + outer loop + vertex 907.624 325.948 331.573 + vertex 907.607 336.375 335.514 + vertex 907.029 328.392 335.516 + endloop + endfacet + facet normal 0.970439 -0.0702217 0.230903 + outer loop + vertex 907.607 336.375 335.514 + vertex 906.921 339.007 339.2 + vertex 907.029 328.392 335.516 + endloop + endfacet + facet normal 0.968717 -0.072476 0.237349 + outer loop + vertex 907.029 328.392 335.516 + vertex 906.921 339.007 339.2 + vertex 906.333 331.152 339.199 + endloop + endfacet + facet normal 0.958871 -0.071743 0.274628 + outer loop + vertex 906.921 339.007 339.2 + vertex 906.123 341.787 342.711 + vertex 906.333 331.152 339.199 + endloop + endfacet + facet normal 0.957183 -0.073545 0.279984 + outer loop + vertex 906.333 331.152 339.199 + vertex 906.123 341.787 342.711 + vertex 905.53 334.065 342.709 + endloop + endfacet + facet normal 0.945587 -0.0726616 0.317151 + outer loop + vertex 906.123 341.787 342.711 + vertex 905.218 344.644 346.062 + vertex 905.53 334.065 342.709 + endloop + endfacet + facet normal 0.944198 -0.0739154 0.320977 + outer loop + vertex 905.53 334.065 342.709 + vertex 905.218 344.644 346.062 + vertex 904.625 337.064 346.063 + endloop + endfacet + facet normal 0.928884 -0.0727141 0.363162 + outer loop + vertex 905.218 344.644 346.062 + vertex 904.222 347.619 349.207 + vertex 904.625 337.064 346.063 + endloop + endfacet + facet normal 0.92467 -0.0758469 0.373139 + outer loop + vertex 904.625 337.064 346.063 + vertex 904.222 347.619 349.207 + vertex 903.614 340.192 349.205 + endloop + endfacet + facet normal 0.997388 3.67939e-05 0.072234 + outer loop + vertex 909.044 339.264 322.657 + vertex 908.709 340.498 327.277 + vertex 909.044 330.835 322.656 + endloop + endfacet + facet normal 0.996243 -0.00675003 0.0863431 + outer loop + vertex 909.044 330.835 322.656 + vertex 908.709 340.498 327.277 + vertex 908.653 332.218 327.274 + endloop + endfacet + facet normal 0.994523 -0.00674491 0.104296 + outer loop + vertex 908.709 340.498 327.277 + vertex 908.271 342.209 331.568 + vertex 908.653 332.218 327.274 + endloop + endfacet + facet normal 0.993539 -0.0105257 0.113005 + outer loop + vertex 908.653 332.218 327.274 + vertex 908.271 342.209 331.568 + vertex 908.185 334.06 331.568 + endloop + endfacet + facet normal 0.989159 -0.0104802 0.146471 + outer loop + vertex 908.271 342.209 331.568 + vertex 907.71 344.388 335.513 + vertex 908.185 334.06 331.568 + endloop + endfacet + facet normal 0.988294 -0.0126468 0.152039 + outer loop + vertex 908.185 334.06 331.568 + vertex 907.71 344.388 335.513 + vertex 907.607 336.375 335.514 + endloop + endfacet + facet normal 0.982004 -0.0125591 0.188441 + outer loop + vertex 907.71 344.388 335.513 + vertex 907.034 346.88 339.199 + vertex 907.607 336.375 335.514 + endloop + endfacet + facet normal 0.981125 -0.0141558 0.192857 + outer loop + vertex 907.607 336.375 335.514 + vertex 907.034 346.88 339.199 + vertex 906.921 339.007 339.2 + endloop + endfacet + facet normal 0.97348 -0.0140398 0.22834 + outer loop + vertex 907.034 346.88 339.199 + vertex 906.249 349.513 342.709 + vertex 906.921 339.007 339.2 + endloop + endfacet + facet normal 0.972262 -0.0157947 0.23336 + outer loop + vertex 906.921 339.007 339.2 + vertex 906.249 349.513 342.709 + vertex 906.123 341.787 342.711 + endloop + endfacet + facet normal 0.963846 -0.0156528 0.265999 + outer loop + vertex 906.249 349.513 342.709 + vertex 905.367 352.217 346.064 + vertex 906.123 341.787 342.711 + endloop + endfacet + facet normal 0.961105 -0.0189179 0.275536 + outer loop + vertex 906.123 341.787 342.711 + vertex 905.367 352.217 346.064 + vertex 905.218 344.644 346.062 + endloop + endfacet + facet normal 0.949112 -0.0186893 0.314385 + outer loop + vertex 905.367 352.217 346.064 + vertex 904.382 355.023 349.205 + vertex 905.218 344.644 346.062 + endloop + endfacet + facet normal 0.947365 -0.0203811 0.319507 + outer loop + vertex 905.218 344.644 346.062 + vertex 904.382 355.023 349.205 + vertex 904.222 347.619 349.207 + endloop + endfacet + facet normal 0.997585 0.048392 0.0498207 + outer loop + vertex 908.631 347.769 322.656 + vertex 908.349 348.826 327.277 + vertex 909.044 339.264 322.657 + endloop + endfacet + facet normal 0.997224 0.0430972 0.0607229 + outer loop + vertex 909.044 339.264 322.657 + vertex 908.349 348.826 327.277 + vertex 908.709 340.498 327.277 + endloop + endfacet + facet normal 0.996083 0.0430471 0.0772326 + outer loop + vertex 908.349 348.826 327.277 + vertex 907.949 350.381 331.571 + vertex 908.709 340.498 327.277 + endloop + endfacet + facet normal 0.995517 0.03915 0.0861002 + outer loop + vertex 908.709 340.498 327.277 + vertex 907.949 350.381 331.571 + vertex 908.271 342.209 331.568 + endloop + endfacet + facet normal 0.992679 0.0390266 0.114305 + outer loop + vertex 907.949 350.381 331.571 + vertex 907.415 352.411 335.517 + vertex 908.271 342.209 331.568 + endloop + endfacet + facet normal 0.991988 0.0363832 0.120984 + outer loop + vertex 908.271 342.209 331.568 + vertex 907.415 352.411 335.517 + vertex 907.71 344.388 335.513 + endloop + endfacet + facet normal 0.987281 0.0361926 0.154808 + outer loop + vertex 907.415 352.411 335.517 + vertex 906.752 354.752 339.198 + vertex 907.71 344.388 335.513 + endloop + endfacet + facet normal 0.986975 0.0354102 0.156929 + outer loop + vertex 907.71 344.388 335.513 + vertex 906.752 354.752 339.198 + vertex 907.034 346.88 339.199 + endloop + endfacet + facet normal 0.981626 0.0352203 0.187537 + outer loop + vertex 906.752 354.752 339.198 + vertex 905.992 357.231 342.71 + vertex 907.034 346.88 339.199 + endloop + endfacet + facet normal 0.980286 0.0325957 0.194876 + outer loop + vertex 907.034 346.88 339.199 + vertex 905.992 357.231 342.71 + vertex 906.249 349.513 342.709 + endloop + endfacet + facet normal 0.973498 0.0323677 0.226393 + outer loop + vertex 905.992 357.231 342.71 + vertex 905.128 359.768 346.062 + vertex 906.249 349.513 342.709 + endloop + endfacet + facet normal 0.972507 0.0308097 0.230827 + outer loop + vertex 906.249 349.513 342.709 + vertex 905.128 359.768 346.062 + vertex 905.367 352.217 346.064 + endloop + endfacet + facet normal 0.963139 0.0305201 0.267267 + outer loop + vertex 905.128 359.768 346.062 + vertex 904.172 362.396 349.207 + vertex 905.367 352.217 346.064 + endloop + endfacet + facet normal 0.960497 0.0272179 0.276955 + outer loop + vertex 905.367 352.217 346.064 + vertex 904.172 362.396 349.207 + vertex 904.382 355.023 349.205 + endloop + endfacet + facet normal 0.97773 0.0729161 0.196794 + outer loop + vertex 905.992 357.231 342.71 + vertex 904.568 367.281 346.061 + vertex 905.128 359.768 346.062 + endloop + endfacet + facet normal 0.970714 0.0724015 0.229069 + outer loop + vertex 904.568 367.281 346.061 + vertex 903.643 369.726 349.207 + vertex 905.128 359.768 346.062 + endloop + endfacet + facet normal 0.969189 0.0699274 0.236183 + outer loop + vertex 905.128 359.768 346.062 + vertex 903.643 369.726 349.207 + vertex 904.172 362.396 349.207 + endloop + endfacet + facet normal 0.973319 0.106895 0.203034 + outer loop + vertex 904.568 367.281 346.061 + vertex 902.844 377.005 349.205 + vertex 903.643 369.726 349.207 + endloop + endfacet + facet normal 0.973903 0.108123 0.199557 + outer loop + vertex 903.739 374.748 346.062 + vertex 902.844 377.005 349.205 + vertex 904.568 367.281 346.061 + endloop + endfacet + facet normal 0.980003 0.108807 0.166598 + outer loop + vertex 905.401 364.917 342.709 + vertex 903.739 374.748 346.062 + vertex 904.568 367.281 346.061 + endloop + endfacet + facet normal 0.980591 0.110485 0.16197 + outer loop + vertex 904.538 372.565 342.713 + vertex 903.739 374.748 346.062 + vertex 905.401 364.917 342.709 + endloop + endfacet + facet normal 0.984532 0.110945 0.135603 + outer loop + vertex 906.144 362.605 339.204 + vertex 904.538 372.565 342.713 + vertex 905.401 364.917 342.709 + endloop + endfacet + facet normal 0.984414 0.076132 0.158532 + outer loop + vertex 906.144 362.605 339.204 + vertex 905.401 364.917 342.709 + vertex 906.752 354.752 339.198 + endloop + endfacet + facet normal 0.98497 0.112664 0.130925 + outer loop + vertex 905.248 370.427 339.21 + vertex 904.538 372.565 342.713 + vertex 906.144 362.605 339.204 + endloop + endfacet + facet normal 0.988072 0.11304 0.104578 + outer loop + vertex 906.783 360.421 335.526 + vertex 905.248 370.427 339.21 + vertex 906.144 362.605 339.204 + endloop + endfacet + facet normal 0.989016 0.0779093 0.125607 + outer loop + vertex 906.783 360.421 335.526 + vertex 906.144 362.605 339.204 + vertex 907.415 352.411 335.517 + endloop + endfacet + facet normal 0.988421 0.115263 0.098686 + outer loop + vertex 905.852 368.412 335.521 + vertex 905.248 370.427 339.21 + vertex 906.783 360.421 335.526 + endloop + endfacet + facet normal 0.990794 0.115524 0.0705766 + outer loop + vertex 907.283 358.552 331.57 + vertex 905.852 368.412 335.521 + vertex 906.783 360.421 335.526 + endloop + endfacet + facet normal 0.992896 0.0810065 0.0871564 + outer loop + vertex 907.283 358.552 331.57 + vertex 906.783 360.421 335.526 + vertex 907.949 350.381 331.571 + endloop + endfacet + facet normal 0.990829 0.116123 0.0690955 + outer loop + vertex 906.33 366.689 331.558 + vertex 905.852 368.412 335.521 + vertex 907.283 358.552 331.57 + endloop + endfacet + facet normal 0.992166 0.116244 0.0457552 + outer loop + vertex 907.646 357.147 327.267 + vertex 906.33 366.689 331.558 + vertex 907.283 358.552 331.57 + endloop + endfacet + facet normal 0.994849 0.0841953 0.056445 + outer loop + vertex 907.646 357.147 327.267 + vertex 907.283 358.552 331.57 + vertex 908.349 348.826 327.277 + endloop + endfacet + facet normal 0.992095 0.119299 0.0389376 + outer loop + vertex 906.654 365.403 327.238 + vertex 906.33 366.689 331.558 + vertex 907.646 357.147 327.267 + endloop + endfacet + facet normal 0.992515 0.119305 0.0260957 + outer loop + vertex 907.878 356.228 322.639 + vertex 906.654 365.403 327.238 + vertex 907.646 357.147 327.267 + endloop + endfacet + facet normal 0.992253 0.122744 0.0191666 + outer loop + vertex 906.85 364.543 322.616 + vertex 906.654 365.403 327.238 + vertex 907.878 356.228 322.639 + endloop + endfacet + facet normal 0.988753 0.148885 0.0141567 + outer loop + vertex 906.85 364.543 322.616 + vertex 905.421 373.595 327.234 + vertex 906.654 365.403 327.238 + endloop + endfacet + facet normal 0.9885 0.148854 0.0266398 + outer loop + vertex 905.421 373.595 327.234 + vertex 905.126 374.785 331.526 + vertex 906.654 365.403 327.238 + endloop + endfacet + facet normal 0.984876 0.172111 0.0199416 + outer loop + vertex 905.421 373.595 327.234 + vertex 903.72 382.832 331.513 + vertex 905.126 374.785 331.526 + endloop + endfacet + facet normal 0.984293 0.17204 0.0396101 + outer loop + vertex 903.72 382.832 331.513 + vertex 903.306 384.285 335.488 + vertex 905.126 374.785 331.526 + endloop + endfacet + facet normal 0.98436 0.17113 0.0418217 + outer loop + vertex 905.126 374.785 331.526 + vertex 903.306 384.285 335.488 + vertex 904.681 376.368 335.508 + endloop + endfacet + facet normal 0.987764 0.147121 0.0517469 + outer loop + vertex 905.126 374.785 331.526 + vertex 904.681 376.368 335.508 + vertex 906.33 366.689 331.558 + endloop + endfacet + facet normal 0.983135 0.170978 0.0649021 + outer loop + vertex 903.306 384.285 335.488 + vertex 902.768 385.962 339.21 + vertex 904.681 376.368 335.508 + endloop + endfacet + facet normal 0.983135 0.170556 0.0659942 + outer loop + vertex 904.681 376.368 335.508 + vertex 902.768 385.962 339.21 + vertex 904.112 378.214 339.214 + endloop + endfacet + facet normal 0.986236 0.145195 0.0791009 + outer loop + vertex 904.681 376.368 335.508 + vertex 904.112 378.214 339.214 + vertex 905.852 368.412 335.521 + endloop + endfacet + facet normal 0.981129 0.170222 0.0917071 + outer loop + vertex 902.768 385.962 339.21 + vertex 902.133 387.73 342.728 + vertex 904.112 378.214 339.214 + endloop + endfacet + facet normal 0.981028 0.168968 0.0950482 + outer loop + vertex 904.112 378.214 339.214 + vertex 902.133 387.73 342.728 + vertex 903.436 380.17 342.72 + endloop + endfacet + facet normal 0.983553 0.143422 0.109792 + outer loop + vertex 904.112 378.214 339.214 + vertex 903.436 380.17 342.72 + vertex 905.248 370.427 339.21 + endloop + endfacet + facet normal 0.978423 0.168494 0.119573 + outer loop + vertex 902.133 387.73 342.728 + vertex 901.414 389.53 346.072 + vertex 903.436 380.17 342.72 + endloop + endfacet + facet normal 0.97823 0.1673 0.12279 + outer loop + vertex 903.436 380.17 342.72 + vertex 901.414 389.53 346.072 + vertex 902.675 382.165 346.065 + endloop + endfacet + facet normal 0.980159 0.141951 0.138342 + outer loop + vertex 903.436 380.17 342.72 + vertex 902.675 382.165 346.065 + vertex 904.538 372.565 342.713 + endloop + endfacet + facet normal 0.974051 0.166556 0.153246 + outer loop + vertex 901.414 389.53 346.072 + vertex 900.601 391.398 349.209 + vertex 902.675 382.165 346.065 + endloop + endfacet + facet normal 0.97368 0.165178 0.157049 + outer loop + vertex 902.675 382.165 346.065 + vertex 900.601 391.398 349.209 + vertex 901.818 384.229 349.205 + endloop + endfacet + facet normal 0.974765 0.139802 0.174034 + outer loop + vertex 902.675 382.165 346.065 + vertex 901.818 384.229 349.205 + vertex 903.739 374.748 346.062 + endloop + endfacet + facet normal 0.965409 0.163747 0.202911 + outer loop + vertex 900.601 391.398 349.209 + vertex 899.658 393.421 352.066 + vertex 901.818 384.229 349.205 + endloop + endfacet + facet normal 0.96547 0.163887 0.202507 + outer loop + vertex 901.818 384.229 349.205 + vertex 899.658 393.421 352.066 + vertex 900.84 386.453 352.069 + endloop + endfacet + facet normal 0.96509 0.137117 0.223161 + outer loop + vertex 901.818 384.229 349.205 + vertex 900.84 386.453 352.069 + vertex 902.844 377.005 349.205 + endloop + endfacet + facet normal 0.9646 0.136208 0.22582 + outer loop + vertex 902.844 377.005 349.205 + vertex 900.84 386.453 352.069 + vertex 901.833 379.421 352.069 + endloop + endfacet + facet normal 0.962266 0.105695 0.250746 + outer loop + vertex 902.844 377.005 349.205 + vertex 901.833 379.421 352.069 + vertex 903.643 369.726 349.207 + endloop + endfacet + facet normal 0.96144 0.104461 0.254404 + outer loop + vertex 903.643 369.726 349.207 + vertex 901.833 379.421 352.069 + vertex 902.603 372.336 352.069 + endloop + endfacet + facet normal 0.956094 0.0689828 0.284826 + outer loop + vertex 903.643 369.726 349.207 + vertex 902.603 372.336 352.069 + vertex 904.172 362.396 349.207 + endloop + endfacet + facet normal 0.955321 0.0680536 0.28763 + outer loop + vertex 904.172 362.396 349.207 + vertex 902.603 372.336 352.069 + vertex 903.11 365.206 352.07 + endloop + endfacet + facet normal 0.964577 0.186657 0.186413 + outer loop + vertex 900.601 391.398 349.209 + vertex 898.322 400.32 352.067 + vertex 899.658 393.421 352.066 + endloop + endfacet + facet normal 0.965018 0.187917 0.182832 + outer loop + vertex 899.217 398.504 349.21 + vertex 898.322 400.32 352.067 + vertex 900.601 391.398 349.209 + endloop + endfacet + facet normal 0.96329 0.208329 0.169325 + outer loop + vertex 899.217 398.504 349.21 + vertex 896.847 407.15 352.058 + vertex 898.322 400.32 352.067 + endloop + endfacet + facet normal 0.963164 0.207878 0.17059 + outer loop + vertex 897.696 405.551 349.21 + vertex 896.847 407.15 352.058 + vertex 899.217 398.504 349.21 + endloop + endfacet + facet normal 0.969573 0.209261 0.127034 + outer loop + vertex 899.986 396.842 346.08 + vertex 897.696 405.551 349.21 + vertex 899.217 398.504 349.21 + endloop + endfacet + facet normal 0.972089 0.189708 0.138035 + outer loop + vertex 899.986 396.842 346.08 + vertex 899.217 398.504 349.21 + vertex 901.414 389.53 346.072 + endloop + endfacet + facet normal 0.969672 0.210006 0.125033 + outer loop + vertex 898.415 404.096 346.082 + vertex 897.696 405.551 349.21 + vertex 899.986 396.842 346.08 + endloop + endfacet + facet normal 0.972871 0.210706 0.0955199 + outer loop + vertex 900.661 395.242 342.735 + vertex 898.415 404.096 346.082 + vertex 899.986 396.842 346.08 + endloop + endfacet + facet normal 0.975884 0.191101 0.105506 + outer loop + vertex 900.661 395.242 342.735 + vertex 899.986 396.842 346.08 + vertex 902.133 387.73 342.728 + endloop + endfacet + facet normal 0.972901 0.211483 0.0934835 + outer loop + vertex 899.04 402.701 342.732 + vertex 898.415 404.096 346.082 + vertex 900.661 395.242 342.735 + endloop + endfacet + facet normal 0.974884 0.211907 0.0685344 + outer loop + vertex 901.252 393.666 339.202 + vertex 899.04 402.701 342.732 + vertex 900.661 395.242 342.735 + endloop + endfacet + facet normal 0.978193 0.192622 0.0776899 + outer loop + vertex 901.252 393.666 339.202 + vertex 900.661 395.242 342.735 + vertex 902.768 385.962 339.21 + endloop + endfacet + facet normal 0.974866 0.212375 0.0673258 + outer loop + vertex 899.584 401.329 339.187 + vertex 899.04 402.701 342.732 + vertex 901.252 393.666 339.202 + endloop + endfacet + facet normal 0.976099 0.212601 0.0450746 + outer loop + vertex 901.752 392.163 335.466 + vertex 899.584 401.329 339.187 + vertex 901.252 393.666 339.202 + endloop + endfacet + facet normal 0.979675 0.193382 0.0532864 + outer loop + vertex 901.752 392.163 335.466 + vertex 901.252 393.666 339.202 + vertex 903.306 384.285 335.488 + endloop + endfacet + facet normal 0.976037 0.213203 0.0435556 + outer loop + vertex 900.04 400.004 335.443 + vertex 899.584 401.329 339.187 + vertex 901.752 392.163 335.466 + endloop + endfacet + facet normal 0.976727 0.213292 0.0226215 + outer loop + vertex 902.135 390.827 331.517 + vertex 900.04 400.004 335.443 + vertex 901.752 392.163 335.466 + endloop + endfacet + facet normal 0.980498 0.194317 0.0294081 + outer loop + vertex 902.135 390.827 331.517 + vertex 901.752 392.163 335.466 + vertex 903.72 382.832 331.513 + endloop + endfacet + facet normal 0.980845 0.194394 0.0124528 + outer loop + vertex 903.99 381.736 327.353 + vertex 902.135 390.827 331.517 + vertex 903.72 382.832 331.513 + endloop + endfacet + facet normal 0.980788 0.194726 0.0117024 + outer loop + vertex 902.404 389.715 327.459 + vertex 902.135 390.827 331.517 + vertex 903.99 381.736 327.353 + endloop + endfacet + facet normal 0.980818 0.194914 -0.00209732 + outer loop + vertex 904.083 381.223 323.406 + vertex 902.404 389.715 327.459 + vertex 903.99 381.736 327.353 + endloop + endfacet + facet normal 0.984532 0.175207 0.000553544 + outer loop + vertex 904.083 381.223 323.406 + vertex 903.99 381.736 327.353 + vertex 905.571 372.866 322.73 + endloop + endfacet + facet normal 0.984402 0.175795 -0.00700765 + outer loop + vertex 904.083 381.223 323.406 + vertex 905.571 372.866 322.73 + vertex 905.248 374.558 319.793 + endloop + endfacet + facet normal 0.982704 0.183828 -0.0223743 + outer loop + vertex 904.111 380.635 319.788 + vertex 904.083 381.223 323.406 + vertex 905.248 374.558 319.793 + endloop + endfacet + facet normal 0.981693 0.183613 -0.0506461 + outer loop + vertex 905.139 374.357 316.954 + vertex 904.111 380.635 319.788 + vertex 905.248 374.558 319.793 + endloop + endfacet + facet normal 0.97984 0.198246 -0.0247386 + outer loop + vertex 904.111 380.635 319.788 + vertex 902.577 388.662 323.364 + vertex 904.083 381.223 323.406 + endloop + endfacet + facet normal 0.97841 0.203362 -0.036835 + outer loop + vertex 902.732 387.102 318.873 + vertex 902.577 388.662 323.364 + vertex 904.111 380.635 319.788 + endloop + endfacet + facet normal 0.977985 0.200113 -0.0591625 + outer loop + vertex 904.111 380.635 319.788 + vertex 904.253 378.959 316.471 + vertex 902.732 387.102 318.873 + endloop + endfacet + facet normal 0.975895 0.204641 -0.0758357 + outer loop + vertex 904.253 378.959 316.471 + vertex 903.5 381.937 314.815 + vertex 902.732 387.102 318.873 + endloop + endfacet + facet normal 0.975565 0.20569 -0.0772334 + outer loop + vertex 902.158 388.479 315.288 + vertex 902.732 387.102 318.873 + vertex 903.5 381.937 314.815 + endloop + endfacet + facet normal 0.973644 0.216102 -0.0729259 + outer loop + vertex 902.158 388.479 315.288 + vertex 900.794 395.92 319.127 + vertex 902.732 387.102 318.873 + endloop + endfacet + facet normal 0.975497 0.215661 -0.0435357 + outer loop + vertex 900.794 395.92 319.127 + vertex 900.85 396.503 323.259 + vertex 902.732 387.102 318.873 + endloop + endfacet + facet normal 0.972472 0.228569 -0.0453169 + outer loop + vertex 900.794 395.92 319.127 + vertex 898.915 404.74 323.288 + vertex 900.85 396.503 323.259 + endloop + endfacet + facet normal 0.973321 0.228675 -0.0188135 + outer loop + vertex 898.915 404.74 323.288 + vertex 898.783 405.643 327.438 + vertex 900.85 396.503 323.259 + endloop + endfacet + facet normal 0.973212 0.229061 -0.0197112 + outer loop + vertex 900.85 396.503 323.259 + vertex 898.783 405.643 327.438 + vertex 900.673 397.612 327.444 + endloop + endfacet + facet normal 0.976503 0.21492 -0.0158251 + outer loop + vertex 900.85 396.503 323.259 + vertex 900.673 397.612 327.444 + vertex 902.577 388.662 323.364 + endloop + endfacet + facet normal 0.976723 0.214059 -0.0138336 + outer loop + vertex 902.577 388.662 323.364 + vertex 900.673 397.612 327.444 + vertex 902.404 389.715 327.459 + endloop + endfacet + facet normal 0.976802 0.214108 0.00404521 + outer loop + vertex 900.673 397.612 327.444 + vertex 900.403 398.768 331.514 + vertex 902.404 389.715 327.459 + endloop + endfacet + facet normal 0.973301 0.229533 -0.000568711 + outer loop + vertex 900.673 397.612 327.444 + vertex 898.533 406.697 331.503 + vertex 900.403 398.768 331.514 + endloop + endfacet + facet normal 0.973133 0.22952 0.0182307 + outer loop + vertex 898.533 406.697 331.503 + vertex 898.199 407.802 335.424 + vertex 900.403 398.768 331.514 + endloop + endfacet + facet normal 0.973085 0.229771 0.0176226 + outer loop + vertex 900.403 398.768 331.514 + vertex 898.199 407.802 335.424 + vertex 900.04 400.004 335.443 + endloop + endfacet + facet normal 0.972563 0.229695 0.0369093 + outer loop + vertex 898.199 407.802 335.424 + vertex 897.788 408.942 339.169 + vertex 900.04 400.004 335.443 + endloop + endfacet + facet normal 0.969311 0.24371 0.0322842 + outer loop + vertex 898.199 407.802 335.424 + vertex 895.893 416.482 339.158 + vertex 897.788 408.942 339.169 + endloop + endfacet + facet normal 0.968456 0.243526 0.0527994 + outer loop + vertex 895.893 416.482 339.158 + vertex 895.459 417.435 342.712 + vertex 897.788 408.942 339.169 + endloop + endfacet + facet normal 0.968515 0.243011 0.054072 + outer loop + vertex 897.788 408.942 339.169 + vertex 895.459 417.435 342.712 + vertex 897.297 410.106 342.722 + endloop + endfacet + facet normal 0.971563 0.22932 0.0589783 + outer loop + vertex 897.788 408.942 339.169 + vertex 897.297 410.106 342.722 + vertex 899.584 401.329 339.187 + endloop + endfacet + facet normal 0.966912 0.242645 0.07877 + outer loop + vertex 895.459 417.435 342.712 + vertex 894.945 418.399 346.057 + vertex 897.297 410.106 342.722 + endloop + endfacet + facet normal 0.96692 0.242475 0.0791971 + outer loop + vertex 897.297 410.106 342.722 + vertex 894.945 418.399 346.057 + vertex 896.726 411.289 346.074 + endloop + endfacet + facet normal 0.969889 0.228347 0.0846882 + outer loop + vertex 897.297 410.106 342.722 + vertex 896.726 411.289 346.074 + vertex 899.04 402.701 342.732 + endloop + endfacet + facet normal 0.964089 0.241839 0.109753 + outer loop + vertex 894.945 418.399 346.057 + vertex 894.334 419.419 349.169 + vertex 896.726 411.289 346.074 + endloop + endfacet + facet normal 0.96408 0.241632 0.110289 + outer loop + vertex 896.726 411.289 346.074 + vertex 894.334 419.419 349.169 + vertex 896.059 412.528 349.195 + endloop + endfacet + facet normal 0.966859 0.227105 0.116652 + outer loop + vertex 896.726 411.289 346.074 + vertex 896.059 412.528 349.195 + vertex 898.415 404.096 346.082 + endloop + endfacet + facet normal 0.958655 0.240431 0.152231 + outer loop + vertex 894.334 419.419 349.169 + vertex 893.593 420.578 352.006 + vertex 896.059 412.528 349.195 + endloop + endfacet + facet normal 0.958714 0.240763 0.151331 + outer loop + vertex 896.059 412.528 349.195 + vertex 893.593 420.578 352.006 + vertex 895.263 413.909 352.04 + endloop + endfacet + facet normal 0.961049 0.22593 0.159184 + outer loop + vertex 896.059 412.528 349.195 + vertex 895.263 413.909 352.04 + vertex 897.696 405.551 349.21 + endloop + endfacet + facet normal 0.956561 0.251715 0.147073 + outer loop + vertex 894.334 419.419 349.169 + vertex 891.864 427.17 351.973 + vertex 893.593 420.578 352.006 + endloop + endfacet + facet normal 0.956477 0.251136 0.148601 + outer loop + vertex 892.545 426.241 349.156 + vertex 891.864 427.17 351.973 + vertex 894.334 419.419 349.169 + endloop + endfacet + facet normal 0.955018 0.258157 0.145931 + outer loop + vertex 892.545 426.241 349.156 + vertex 890.076 433.783 351.977 + vertex 891.864 427.17 351.973 + endloop + endfacet + facet normal 0.955111 0.258939 0.143923 + outer loop + vertex 890.682 433.104 349.173 + vertex 890.076 433.783 351.977 + vertex 892.545 426.241 349.156 + endloop + endfacet + facet normal 0.959999 0.260373 0.102997 + outer loop + vertex 893.093 425.447 346.058 + vertex 890.682 433.104 349.173 + vertex 892.545 426.241 349.156 + endloop + endfacet + facet normal 0.961809 0.252657 0.105295 + outer loop + vertex 893.093 425.447 346.058 + vertex 892.545 426.241 349.156 + vertex 894.945 418.399 346.057 + endloop + endfacet + facet normal 0.959997 0.260543 0.102578 + outer loop + vertex 891.161 432.553 346.094 + vertex 890.682 433.104 349.173 + vertex 893.093 425.447 346.058 + endloop + endfacet + facet normal 0.962556 0.261395 0.0718193 + outer loop + vertex 893.544 424.704 342.721 + vertex 891.161 432.553 346.094 + vertex 893.093 425.447 346.058 + endloop + endfacet + facet normal 0.96439 0.254004 0.0737131 + outer loop + vertex 893.544 424.704 342.721 + vertex 893.093 425.447 346.058 + vertex 895.459 417.435 342.712 + endloop + endfacet + facet normal 0.962512 0.261859 0.0707089 + outer loop + vertex 891.544 432.044 342.763 + vertex 891.161 432.553 346.094 + vertex 893.544 424.704 342.721 + endloop + endfacet + facet normal 0.963819 0.262351 0.0471756 + outer loop + vertex 893.918 423.968 339.172 + vertex 891.544 432.044 342.763 + vertex 893.544 424.704 342.721 + endloop + endfacet + facet normal 0.965791 0.254652 0.048981 + outer loop + vertex 893.918 423.968 339.172 + vertex 893.544 424.704 342.721 + vertex 895.893 416.482 339.158 + endloop + endfacet + facet normal 0.966536 0.254885 0.0289979 + outer loop + vertex 896.254 415.537 335.417 + vertex 893.918 423.968 339.172 + vertex 895.893 416.482 339.158 + endloop + endfacet + facet normal 0.966531 0.254914 0.0289296 + outer loop + vertex 894.227 423.221 335.431 + vertex 893.918 423.968 339.172 + vertex 896.254 415.537 335.417 + endloop + endfacet + facet normal 0.966865 0.255035 0.0113237 + outer loop + vertex 896.546 414.605 331.504 + vertex 894.227 423.221 335.431 + vertex 896.254 415.537 335.417 + endloop + endfacet + facet normal 0.969735 0.243747 0.0142268 + outer loop + vertex 896.546 414.605 331.504 + vertex 896.254 415.537 335.417 + vertex 898.533 406.697 331.503 + endloop + endfacet + facet normal 0.969826 0.243773 -0.00361393 + outer loop + vertex 898.783 405.643 327.438 + vertex 896.546 414.605 331.504 + vertex 898.533 406.697 331.503 + endloop + endfacet + facet normal 0.970041 0.242935 -0.00165017 + outer loop + vertex 896.761 413.716 327.454 + vertex 896.546 414.605 331.504 + vertex 898.783 405.643 327.438 + endloop + endfacet + facet normal 0.966974 0.254836 -0.00442588 + outer loop + vertex 896.761 413.716 327.454 + vertex 894.474 422.466 331.52 + vertex 896.546 414.605 331.504 + endloop + endfacet + facet normal 0.967092 0.254404 -0.00342943 + outer loop + vertex 894.654 421.725 327.469 + vertex 894.474 422.466 331.52 + vertex 896.761 413.716 327.454 + endloop + endfacet + facet normal 0.966778 0.254362 -0.0253112 + outer loop + vertex 896.86 412.925 323.286 + vertex 894.654 421.725 327.469 + vertex 896.761 413.716 327.454 + endloop + endfacet + facet normal 0.969647 0.243408 -0.0231648 + outer loop + vertex 896.86 412.925 323.286 + vertex 896.761 413.716 327.454 + vertex 898.915 404.74 323.288 + endloop + endfacet + facet normal 0.968431 0.243093 -0.055198 + outer loop + vertex 898.844 404.059 319.048 + vertex 896.86 412.925 323.286 + vertex 898.915 404.74 323.288 + endloop + endfacet + facet normal 0.967953 0.244337 -0.058023 + outer loop + vertex 896.768 412.263 318.957 + vertex 896.86 412.925 323.286 + vertex 898.844 404.059 319.048 + endloop + endfacet + facet normal 0.964321 0.242894 -0.105295 + outer loop + vertex 898.518 403.397 314.536 + vertex 896.768 412.263 318.957 + vertex 898.844 404.059 319.048 + endloop + endfacet + facet normal 0.965961 0.236642 -0.104496 + outer loop + vertex 898.518 403.397 314.536 + vertex 898.844 404.059 319.048 + vertex 900.479 395.587 314.971 + endloop + endfacet + facet normal 0.968557 0.231143 -0.0920293 + outer loop + vertex 900.479 395.587 314.971 + vertex 898.844 404.059 319.048 + vertex 900.794 395.92 319.127 + endloop + endfacet + facet normal 0.96351 0.244524 -0.108886 + outer loop + vertex 896.376 411.775 314.395 + vertex 896.768 412.263 318.957 + vertex 898.518 403.397 314.536 + endloop + endfacet + facet normal 0.960912 0.254195 -0.109698 + outer loop + vertex 896.376 411.775 314.395 + vertex 894.596 420.466 318.943 + vertex 896.768 412.263 318.957 + endloop + endfacet + facet normal 0.964859 0.255322 -0.0621104 + outer loop + vertex 894.596 420.466 318.943 + vertex 894.723 421.043 323.288 + vertex 896.768 412.263 318.957 + endloop + endfacet + facet normal 0.962564 0.263599 -0.0631439 + outer loop + vertex 894.596 420.466 318.943 + vertex 892.503 429.155 323.311 + vertex 894.723 421.043 323.288 + endloop + endfacet + facet normal 0.964142 0.26393 -0.0277864 + outer loop + vertex 892.503 429.155 323.311 + vertex 892.463 429.742 327.485 + vertex 894.723 421.043 323.288 + endloop + endfacet + facet normal 0.96424 0.263637 -0.0271265 + outer loop + vertex 894.723 421.043 323.288 + vertex 892.463 429.742 327.485 + vertex 894.654 421.725 327.469 + endloop + endfacet + facet normal 0.964592 0.263692 -0.00540971 + outer loop + vertex 892.463 429.742 327.485 + vertex 892.319 430.353 331.536 + vertex 894.654 421.725 327.469 + endloop + endfacet + facet normal 0.963098 0.269079 -0.00627559 + outer loop + vertex 892.463 429.742 327.485 + vertex 890.061 438.436 331.561 + vertex 892.319 430.353 331.536 + endloop + endfacet + facet normal 0.963093 0.269031 0.00864423 + outer loop + vertex 890.061 438.436 331.561 + vertex 889.898 438.891 335.476 + vertex 892.319 430.353 331.536 + endloop + endfacet + facet normal 0.963198 0.268621 0.00959844 + outer loop + vertex 892.319 430.353 331.536 + vertex 889.898 438.891 335.476 + vertex 892.113 430.952 335.455 + endloop + endfacet + facet normal 0.964584 0.263569 0.0104425 + outer loop + vertex 892.319 430.353 331.536 + vertex 892.113 430.952 335.455 + vertex 894.474 422.466 331.52 + endloop + endfacet + facet normal 0.964538 0.263756 0.0100111 + outer loop + vertex 894.474 422.466 331.52 + vertex 892.113 430.952 335.455 + vertex 894.227 423.221 335.431 + endloop + endfacet + facet normal 0.964274 0.263636 0.0259208 + outer loop + vertex 892.113 430.952 335.455 + vertex 891.857 431.517 339.209 + vertex 894.227 423.221 335.431 + endloop + endfacet + facet normal 0.963092 0.26799 0.0251848 + outer loop + vertex 892.113 430.952 335.455 + vertex 889.692 439.295 339.231 + vertex 891.857 431.517 339.209 + endloop + endfacet + facet normal 0.962512 0.267776 0.0432072 + outer loop + vertex 889.692 439.295 339.231 + vertex 889.435 439.645 342.801 + vertex 891.857 431.517 339.209 + endloop + endfacet + facet normal 0.96266 0.266898 0.0452939 + outer loop + vertex 891.857 431.517 339.209 + vertex 889.435 439.645 342.801 + vertex 891.544 432.044 342.763 + endloop + endfacet + facet normal 0.961429 0.266444 0.0682852 + outer loop + vertex 889.435 439.645 342.801 + vertex 889.118 439.932 346.144 + vertex 891.544 432.044 342.763 + endloop + endfacet + facet normal 0.961247 0.267115 0.0682106 + outer loop + vertex 889.435 439.645 342.801 + vertex 886.979 447.638 346.105 + vertex 889.118 439.932 346.144 + endloop + endfacet + facet normal 0.958963 0.266622 0.0964544 + outer loop + vertex 886.979 447.638 346.105 + vertex 886.656 447.666 349.24 + vertex 889.118 439.932 346.144 + endloop + endfacet + facet normal 0.958986 0.265474 0.099341 + outer loop + vertex 889.118 439.932 346.144 + vertex 886.656 447.666 349.24 + vertex 888.722 440.207 349.231 + endloop + endfacet + facet normal 0.959143 0.264881 0.0994139 + outer loop + vertex 889.118 439.932 346.144 + vertex 888.722 440.207 349.231 + vertex 891.161 432.553 346.094 + endloop + endfacet + facet normal 0.954382 0.26415 0.139211 + outer loop + vertex 886.656 447.666 349.24 + vertex 886.235 447.706 352.052 + vertex 888.722 440.207 349.231 + endloop + endfacet + facet normal 0.954223 0.262615 0.14315 + outer loop + vertex 888.722 440.207 349.231 + vertex 886.235 447.706 352.052 + vertex 888.196 440.6 352.016 + endloop + endfacet + facet normal 0.954321 0.262216 0.143225 + outer loop + vertex 888.722 440.207 349.231 + vertex 888.196 440.6 352.016 + vertex 890.682 433.104 349.173 + endloop + endfacet + facet normal 0.954802 0.262584 0.139296 + outer loop + vertex 886.656 447.666 349.24 + vertex 884.28 454.861 351.964 + vertex 886.235 447.706 352.052 + endloop + endfacet + facet normal 0.955045 0.265349 0.132205 + outer loop + vertex 884.581 455.228 349.053 + vertex 884.28 454.861 351.964 + vertex 886.656 447.666 349.24 + endloop + endfacet + facet normal 0.95553 0.26368 0.132044 + outer loop + vertex 884.581 455.228 349.053 + vertex 882.325 462.03 351.793 + vertex 884.28 454.861 351.964 + endloop + endfacet + facet normal 0.955684 0.266742 0.124569 + outer loop + vertex 882.848 461.771 348.337 + vertex 882.325 462.03 351.793 + vertex 884.581 455.228 349.053 + endloop + endfacet + facet normal 0.960016 0.264344 0.0921478 + outer loop + vertex 884.91 455.171 345.786 + vertex 882.848 461.771 348.337 + vertex 884.581 455.228 349.053 + endloop + endfacet + facet normal 0.959199 0.26734 0.0920129 + outer loop + vertex 884.91 455.171 345.786 + vertex 884.581 455.228 349.053 + vertex 886.979 447.638 346.105 + endloop + endfacet + facet normal 0.961488 0.266859 0.0657809 + outer loop + vertex 887.252 447.482 342.741 + vertex 884.91 455.171 345.786 + vertex 886.979 447.638 346.105 + endloop + endfacet + facet normal 0.961285 0.268762 0.0608183 + outer loop + vertex 885.191 454.918 342.466 + vertex 884.91 455.171 345.786 + vertex 887.252 447.482 342.741 + endloop + endfacet + facet normal 0.962481 0.268335 0.0403203 + outer loop + vertex 887.465 447.252 339.203 + vertex 885.191 454.918 342.466 + vertex 887.252 447.482 342.741 + endloop + endfacet + facet normal 0.962164 0.269484 0.0402265 + outer loop + vertex 887.465 447.252 339.203 + vertex 887.252 447.482 342.741 + vertex 889.692 439.295 339.231 + endloop + endfacet + facet normal 0.962686 0.269571 0.0238098 + outer loop + vertex 889.898 438.891 335.476 + vertex 887.465 447.252 339.203 + vertex 889.692 439.295 339.231 + endloop + endfacet + facet normal 0.962459 0.270585 0.0213879 + outer loop + vertex 887.611 447.026 335.501 + vertex 887.465 447.252 339.203 + vertex 889.898 438.891 335.476 + endloop + endfacet + facet normal 0.96261 0.270044 0.0214269 + outer loop + vertex 887.611 447.026 335.501 + vertex 885.341 454.829 339.125 + vertex 887.465 447.252 339.203 + endloop + endfacet + facet normal 0.962332 0.271233 0.018693 + outer loop + vertex 885.368 454.978 335.574 + vertex 885.341 454.829 339.125 + vertex 887.611 447.026 335.501 + endloop + endfacet + facet normal 0.962448 0.271372 0.00708616 + outer loop + vertex 887.717 446.75 331.62 + vertex 885.368 454.978 335.574 + vertex 887.611 447.026 335.501 + endloop + endfacet + facet normal 0.962484 0.271245 0.00709619 + outer loop + vertex 887.717 446.75 331.62 + vertex 887.611 447.026 335.501 + vertex 890.061 438.436 331.561 + endloop + endfacet + facet normal 0.962461 0.271336 -0.00669865 + outer loop + vertex 890.172 437.94 327.522 + vertex 887.717 446.75 331.62 + vertex 890.061 438.436 331.561 + endloop + endfacet + facet normal 0.962231 0.272102 -0.00848169 + outer loop + vertex 887.787 446.377 327.575 + vertex 887.717 446.75 331.62 + vertex 890.172 437.94 327.522 + endloop + endfacet + facet normal 0.961799 0.272115 -0.0299249 + outer loop + vertex 890.189 437.422 323.361 + vertex 887.787 446.377 327.575 + vertex 890.172 437.94 327.522 + endloop + endfacet + facet normal 0.962517 0.269599 -0.0296085 + outer loop + vertex 890.189 437.422 323.361 + vertex 890.172 437.94 327.522 + vertex 892.503 429.155 323.311 + endloop + endfacet + facet normal 0.960851 0.269343 -0.0649623 + outer loop + vertex 892.361 428.62 318.983 + vertex 890.189 437.422 323.361 + vertex 892.503 429.155 323.311 + endloop + endfacet + facet normal 0.960332 0.270536 -0.0676165 + outer loop + vertex 890.03 436.909 319.046 + vertex 890.189 437.422 323.361 + vertex 892.361 428.62 318.983 + endloop + endfacet + facet normal 0.955955 0.269675 -0.115865 + outer loop + vertex 891.949 428.133 314.451 + vertex 890.03 436.909 319.046 + vertex 892.361 428.62 318.983 + endloop + endfacet + facet normal 0.957354 0.26484 -0.115473 + outer loop + vertex 891.949 428.133 314.451 + vertex 892.361 428.62 318.983 + vertex 894.191 420.001 314.391 + endloop + endfacet + facet normal 0.958183 0.263257 -0.11217 + outer loop + vertex 894.191 420.001 314.391 + vertex 892.361 428.62 318.983 + vertex 894.596 420.466 318.943 + endloop + endfacet + facet normal 0.954564 0.272208 -0.121283 + outer loop + vertex 889.598 436.411 314.526 + vertex 890.03 436.909 319.046 + vertex 891.949 428.133 314.451 + endloop + endfacet + facet normal 0.95403 0.274008 -0.121431 + outer loop + vertex 889.598 436.411 314.526 + vertex 887.597 445.381 319.052 + vertex 890.03 436.909 319.046 + endloop + endfacet + facet normal 0.958571 0.275279 -0.0732255 + outer loop + vertex 887.597 445.381 319.052 + vertex 887.781 445.896 323.384 + vertex 890.03 436.909 319.046 + endloop + endfacet + facet normal 0.958697 0.274853 -0.0731802 + outer loop + vertex 887.597 445.381 319.052 + vertex 885.418 454.092 323.215 + vertex 887.781 445.896 323.384 + endloop + endfacet + facet normal 0.960384 0.276061 -0.0381258 + outer loop + vertex 885.418 454.092 323.215 + vertex 885.413 454.708 327.54 + vertex 887.781 445.896 323.384 + endloop + endfacet + facet normal 0.961223 0.273807 -0.032866 + outer loop + vertex 887.781 445.896 323.384 + vertex 885.413 454.708 327.54 + vertex 887.787 446.377 327.575 + endloop + endfacet + facet normal 0.961651 0.274017 -0.0119431 + outer loop + vertex 885.413 454.708 327.54 + vertex 885.407 454.907 331.686 + vertex 887.787 446.377 327.575 + endloop + endfacet + facet normal 0.96183 0.273389 -0.0119127 + outer loop + vertex 885.413 454.708 327.54 + vertex 883.368 462.081 331.644 + vertex 885.407 454.907 331.686 + endloop + endfacet + facet normal 0.961877 0.273481 0.00131044 + outer loop + vertex 883.368 462.081 331.644 + vertex 883.408 461.92 335.62 + vertex 885.407 454.907 331.686 + endloop + endfacet + facet normal 0.962378 0.271673 0.00478668 + outer loop + vertex 885.407 454.907 331.686 + vertex 883.408 461.92 335.62 + vertex 885.368 454.978 335.574 + endloop + endfacet + facet normal 0.962274 0.271565 0.0167978 + outer loop + vertex 883.408 461.92 335.62 + vertex 883.45 461.546 339.263 + vertex 885.368 454.978 335.574 + endloop + endfacet + facet normal 0.962825 0.269615 0.0165913 + outer loop + vertex 883.45 461.546 339.263 + vertex 883.408 461.92 335.62 + vertex 882.037 466.594 339.206 + endloop + endfacet + facet normal 0.96232 0.26968 0.0348251 + outer loop + vertex 882.037 466.594 339.206 + vertex 882.146 465.706 343.07 + vertex 883.45 461.546 339.263 + endloop + endfacet + facet normal 0.961778 0.271934 0.0321761 + outer loop + vertex 883.682 460.409 341.953 + vertex 883.45 461.546 339.263 + vertex 882.146 465.706 343.07 + endloop + endfacet + facet normal 0.962065 0.267587 0.0531829 + outer loop + vertex 883.221 461.466 344.97 + vertex 883.682 460.409 341.953 + vertex 882.146 465.706 343.07 + endloop + endfacet + facet normal 0.960497 0.271242 0.0622313 + outer loop + vertex 882.146 465.706 343.07 + vertex 881.733 466.257 347.042 + vertex 883.221 461.466 344.97 + endloop + endfacet + facet normal 0.961339 0.262676 0.0826382 + outer loop + vertex 882.848 461.771 348.337 + vertex 883.221 461.466 344.97 + vertex 881.733 466.257 347.042 + endloop + endfacet + facet normal 0.958302 0.267262 0.101139 + outer loop + vertex 881.733 466.257 347.042 + vertex 881.353 466.387 350.303 + vertex 882.848 461.771 348.337 + endloop + endfacet + facet normal 0.961182 0.256408 0.101905 + outer loop + vertex 881.733 466.257 347.042 + vertex 880.85 468.781 349.022 + vertex 881.353 466.387 350.303 + endloop + endfacet + facet normal 0.953315 0.271242 0.132734 + outer loop + vertex 880.85 468.781 349.022 + vertex 880.538 468.416 352.013 + vertex 881.353 466.387 350.303 + endloop + endfacet + facet normal 0.954222 0.262235 0.143854 + outer loop + vertex 881.353 466.387 350.303 + vertex 880.538 468.416 352.013 + vertex 880.92 466.622 352.747 + endloop + endfacet + facet normal 0.954254 0.262108 0.143872 + outer loop + vertex 881.353 466.387 350.303 + vertex 880.92 466.622 352.747 + vertex 882.325 462.03 351.793 + endloop + endfacet + facet normal 0.959561 0.267847 0.0866068 + outer loop + vertex 881.162 468.762 345.621 + vertex 880.85 468.781 349.022 + vertex 881.733 466.257 347.042 + endloop + endfacet + facet normal 0.964376 0.256506 0.0646793 + outer loop + vertex 882.146 465.706 343.07 + vertex 881.162 468.762 345.621 + vertex 881.733 466.257 347.042 + endloop + endfacet + facet normal 0.962644 0.26548 0.0532616 + outer loop + vertex 881.255 469.125 342.14 + vertex 881.162 468.762 345.621 + vertex 882.146 465.706 343.07 + endloop + endfacet + facet normal 0.961637 0.269249 0.0525346 + outer loop + vertex 883.682 460.409 341.953 + vertex 883.221 461.466 344.97 + vertex 885.191 454.918 342.466 + endloop + endfacet + facet normal 0.962737 0.268018 0.0361098 + outer loop + vertex 885.341 454.829 339.125 + vertex 883.682 460.409 341.953 + vertex 885.191 454.918 342.466 + endloop + endfacet + facet normal 0.962276 0.270256 0.0314235 + outer loop + vertex 883.45 461.546 339.263 + vertex 883.682 460.409 341.953 + vertex 885.341 454.829 339.125 + endloop + endfacet + facet normal 0.964933 0.260461 0.032634 + outer loop + vertex 882.037 466.594 339.206 + vertex 881.255 469.125 342.14 + vertex 882.146 465.706 343.07 + endloop + endfacet + facet normal 0.963312 0.267074 0.0264954 + outer loop + vertex 881.317 469.267 338.47 + vertex 881.255 469.125 342.14 + vertex 882.037 466.594 339.206 + endloop + endfacet + facet normal 0.964492 0.263774 0.0133513 + outer loop + vertex 882.017 466.86 335.425 + vertex 881.317 469.267 338.47 + vertex 882.037 466.594 339.206 + endloop + endfacet + facet normal 0.962898 0.269738 0.00827103 + outer loop + vertex 881.304 469.422 334.855 + vertex 881.317 469.267 338.47 + vertex 882.017 466.86 335.425 + endloop + endfacet + facet normal 0.963605 0.267305 -0.00354087 + outer loop + vertex 881.944 467.071 331.53 + vertex 881.304 469.422 334.855 + vertex 882.017 466.86 335.425 + endloop + endfacet + facet normal 0.961649 0.274265 -0.00312798 + outer loop + vertex 881.944 467.071 331.53 + vertex 882.017 466.86 335.425 + vertex 883.368 462.081 331.644 + endloop + endfacet + facet normal 0.96157 0.273868 -0.0195 + outer loop + vertex 883.368 462.081 331.644 + vertex 883.185 462.399 327.084 + vertex 881.944 467.071 331.53 + endloop + endfacet + facet normal 0.961434 0.274307 -0.0199993 + outer loop + vertex 881.727 467.586 328.162 + vertex 881.944 467.071 331.53 + vertex 883.185 462.399 327.084 + endloop + endfacet + facet normal 0.959106 0.279185 -0.0466018 + outer loop + vertex 881.972 466.021 323.825 + vertex 881.727 467.586 328.162 + vertex 883.185 462.399 327.084 + endloop + endfacet + facet normal 0.959433 0.277768 -0.048299 + outer loop + vertex 883.185 462.399 327.084 + vertex 883.596 460.182 322.501 + vertex 881.972 466.021 323.825 + endloop + endfacet + facet normal 0.952419 0.287694 -0.10065 + outer loop + vertex 883.596 460.182 322.501 + vertex 882.807 461.429 318.603 + vertex 881.972 466.021 323.825 + endloop + endfacet + facet normal 0.959726 0.268516 -0.0826153 + outer loop + vertex 881.431 466.801 320.074 + vertex 881.972 466.021 323.825 + vertex 882.807 461.429 318.603 + endloop + endfacet + facet normal 0.961028 0.263424 -0.0838626 + outer loop + vertex 881.431 466.801 320.074 + vertex 881.082 468.812 322.393 + vertex 881.972 466.021 323.825 + endloop + endfacet + facet normal 0.959106 0.277672 -0.0549055 + outer loop + vertex 881.082 468.812 322.393 + vertex 881.221 469.164 326.609 + vertex 881.972 466.021 323.825 + endloop + endfacet + facet normal 0.952479 0.286028 -0.104746 + outer loop + vertex 880.856 468.125 318.462 + vertex 881.082 468.812 322.393 + vertex 881.431 466.801 320.074 + endloop + endfacet + facet normal 0.952971 0.285581 -0.101437 + outer loop + vertex 882.807 461.429 318.603 + vertex 883.596 460.182 322.501 + vertex 885.183 453.597 318.87 + endloop + endfacet + facet normal 0.948248 0.282674 -0.144639 + outer loop + vertex 884.631 453.074 314.233 + vertex 882.807 461.429 318.603 + vertex 885.183 453.597 318.87 + endloop + endfacet + facet normal 0.947739 0.284313 -0.144763 + outer loop + vertex 884.631 453.074 314.233 + vertex 885.183 453.597 318.87 + vertex 887.136 444.872 314.525 + endloop + endfacet + facet normal 0.95227 0.277054 -0.12815 + outer loop + vertex 887.136 444.872 314.525 + vertex 885.183 453.597 318.87 + vertex 887.597 445.381 319.052 + endloop + endfacet + facet normal 0.942523 0.291348 -0.163608 + outer loop + vertex 882.406 459.663 313.149 + vertex 882.807 461.429 318.603 + vertex 884.631 453.074 314.233 + endloop + endfacet + facet normal 0.949508 0.271275 -0.157623 + outer loop + vertex 882.807 461.429 318.603 + vertex 882.406 459.663 313.149 + vertex 881.301 465.268 316.137 + endloop + endfacet + facet normal 0.949062 0.281774 -0.14101 + outer loop + vertex 881.301 465.268 316.137 + vertex 881.431 466.801 320.074 + vertex 882.807 461.429 318.603 + endloop + endfacet + facet normal 0.957721 0.256012 -0.13126 + outer loop + vertex 881.301 465.268 316.137 + vertex 880.856 468.125 318.462 + vertex 881.431 466.801 320.074 + endloop + endfacet + facet normal 0.944893 0.282219 -0.165921 + outer loop + vertex 880.485 466.829 314.144 + vertex 880.856 468.125 318.462 + vertex 881.301 465.268 316.137 + endloop + endfacet + facet normal 0.957346 0.276662 -0.0833466 + outer loop + vertex 885.183 453.597 318.87 + vertex 883.596 460.182 322.501 + vertex 885.418 454.092 323.215 + endloop + endfacet + facet normal 0.958435 0.280913 -0.0499103 + outer loop + vertex 883.596 460.182 322.501 + vertex 883.185 462.399 327.084 + vertex 885.418 454.092 323.215 + endloop + endfacet + facet normal 0.962734 0.267158 -0.0420588 + outer loop + vertex 881.972 466.021 323.825 + vertex 881.221 469.164 326.609 + vertex 881.727 467.586 328.162 + endloop + endfacet + facet normal 0.959514 0.280301 -0.0276578 + outer loop + vertex 881.221 469.164 326.609 + vertex 881.267 469.423 330.801 + vertex 881.727 467.586 328.162 + endloop + endfacet + facet normal 0.971969 0.233784 -0.0249178 + outer loop + vertex 881.267 469.423 330.801 + vertex 881.221 469.164 326.609 + vertex 881.123 469.813 328.854 + endloop + endfacet + facet normal 0.967469 0.252123 -0.0209073 + outer loop + vertex 881.123 469.813 328.854 + vertex 881.137 469.941 331.031 + vertex 881.267 469.423 330.801 + endloop + endfacet + facet normal 0.96862 0.248276 -0.0116112 + outer loop + vertex 881.137 469.941 331.031 + vertex 881.169 469.915 333.208 + vertex 881.267 469.423 330.801 + endloop + endfacet + facet normal 0.963398 0.267837 -0.0113007 + outer loop + vertex 881.169 469.915 333.208 + vertex 881.137 469.941 331.031 + vertex 880.949 470.703 333.071 + endloop + endfacet + facet normal 0.963102 0.269115 -0.00350735 + outer loop + vertex 881.129 470.09 335.418 + vertex 881.169 469.915 333.208 + vertex 880.949 470.703 333.071 + endloop + endfacet + facet normal 0.966594 0.256301 -0.00242834 + outer loop + vertex 881.169 469.915 333.208 + vertex 881.129 470.09 335.418 + vertex 881.304 469.422 334.855 + endloop + endfacet + facet normal 0.968548 0.248723 0.00717649 + outer loop + vertex 881.129 470.09 335.418 + vertex 881.12 470.062 337.524 + vertex 881.304 469.422 334.855 + endloop + endfacet + facet normal 0.959668 0.281034 0.00756229 + outer loop + vertex 881.12 470.062 337.524 + vertex 881.129 470.09 335.418 + vertex 880.845 471 337.556 + endloop + endfacet + facet normal 0.959623 0.280628 0.019261 + outer loop + vertex 881.05 470.115 340.257 + vertex 881.12 470.062 337.524 + vertex 880.845 471 337.556 + endloop + endfacet + facet normal 0.964871 0.261981 0.0197506 + outer loop + vertex 881.12 470.062 337.524 + vertex 881.05 470.115 340.257 + vertex 881.317 469.267 338.47 + endloop + endfacet + facet normal 0.962498 0.270398 -0.0219469 + outer loop + vertex 881.137 469.941 331.031 + vertex 881.123 469.813 328.854 + vertex 880.872 470.685 328.605 + endloop + endfacet + facet normal 0.962892 0.268224 -0.0299322 + outer loop + vertex 881.123 469.813 328.854 + vertex 881.052 469.818 326.626 + vertex 880.872 470.685 328.605 + endloop + endfacet + facet normal 0.967498 0.25108 -0.0301168 + outer loop + vertex 881.052 469.818 326.626 + vertex 881.123 469.813 328.854 + vertex 881.221 469.164 326.609 + endloop + endfacet + facet normal 0.962396 0.270869 -0.020587 + outer loop + vertex 881.727 467.586 328.162 + vertex 881.267 469.423 330.801 + vertex 881.944 467.071 331.53 + endloop + endfacet + facet normal 0.96161 0.274277 -0.0088538 + outer loop + vertex 881.267 469.423 330.801 + vertex 881.304 469.422 334.855 + vertex 881.944 467.071 331.53 + endloop + endfacet + facet normal 0.971734 0.235907 -0.00895665 + outer loop + vertex 881.304 469.422 334.855 + vertex 881.267 469.423 330.801 + vertex 881.169 469.915 333.208 + endloop + endfacet + facet normal 0.968694 0.248151 0.00732373 + outer loop + vertex 881.317 469.267 338.47 + vertex 881.304 469.422 334.855 + vertex 881.12 470.062 337.524 + endloop + endfacet + facet normal 0.967911 0.249953 0.0259128 + outer loop + vertex 881.255 469.125 342.14 + vertex 881.317 469.267 338.47 + vertex 881.05 470.115 340.257 + endloop + endfacet + facet normal 0.966136 0.256346 0.0294657 + outer loop + vertex 881.05 470.115 340.257 + vertex 880.995 470.069 342.458 + vertex 881.255 469.125 342.14 + endloop + endfacet + facet normal 0.967127 0.248764 0.0527429 + outer loop + vertex 880.995 470.069 342.458 + vertex 880.928 469.888 344.543 + vertex 881.255 469.125 342.14 + endloop + endfacet + facet normal 0.949378 0.308848 0.0573941 + outer loop + vertex 880.928 469.888 344.543 + vertex 880.995 470.069 342.458 + vertex 880.699 471.015 342.262 + endloop + endfacet + facet normal 0.952173 0.304073 0.0301087 + outer loop + vertex 880.995 470.069 342.458 + vertex 881.05 470.115 340.257 + vertex 880.699 471.015 342.262 + endloop + endfacet + facet normal 0.96233 0.271528 0.0139093 + outer loop + vertex 882.017 466.86 335.425 + vertex 882.037 466.594 339.206 + vertex 883.408 461.92 335.62 + endloop + endfacet + facet normal 0.962553 0.271091 0.00120685 + outer loop + vertex 883.408 461.92 335.62 + vertex 883.368 462.081 331.644 + vertex 882.017 466.86 335.425 + endloop + endfacet + facet normal 0.960639 0.277134 -0.0192343 + outer loop + vertex 883.185 462.399 327.084 + vertex 883.368 462.081 331.644 + vertex 885.413 454.708 327.54 + endloop + endfacet + facet normal 0.960416 0.27595 -0.03811 + outer loop + vertex 885.418 454.092 323.215 + vertex 883.185 462.399 327.084 + vertex 885.413 454.708 327.54 + endloop + endfacet + facet normal 0.956557 0.2793 -0.0836047 + outer loop + vertex 885.183 453.597 318.87 + vertex 885.418 454.092 323.215 + vertex 887.597 445.381 319.052 + endloop + endfacet + facet normal 0.952284 0.277007 -0.128146 + outer loop + vertex 887.136 444.872 314.525 + vertex 887.597 445.381 319.052 + vertex 889.598 436.411 314.526 + endloop + endfacet + facet normal 0.959627 0.272963 -0.067879 + outer loop + vertex 890.03 436.909 319.046 + vertex 887.781 445.896 323.384 + vertex 890.189 437.422 323.361 + endloop + endfacet + facet normal 0.961353 0.273355 -0.0328143 + outer loop + vertex 887.781 445.896 323.384 + vertex 887.787 446.377 327.575 + vertex 890.189 437.422 323.361 + endloop + endfacet + facet normal 0.962119 0.272497 -0.0085201 + outer loop + vertex 887.787 446.377 327.575 + vertex 885.407 454.907 331.686 + vertex 887.717 446.75 331.62 + endloop + endfacet + facet normal 0.962171 0.272405 0.00477127 + outer loop + vertex 885.407 454.907 331.686 + vertex 885.368 454.978 335.574 + vertex 887.717 446.75 331.62 + endloop + endfacet + facet normal 0.962515 0.270585 0.0186673 + outer loop + vertex 885.368 454.978 335.574 + vertex 883.45 461.546 339.263 + vertex 885.341 454.829 339.125 + endloop + endfacet + facet normal 0.962167 0.270068 0.0360295 + outer loop + vertex 885.341 454.829 339.125 + vertex 885.191 454.918 342.466 + vertex 887.465 447.252 339.203 + endloop + endfacet + facet normal 0.96201 0.266093 0.0610826 + outer loop + vertex 885.191 454.918 342.466 + vertex 883.221 461.466 344.97 + vertex 884.91 455.171 345.786 + endloop + endfacet + facet normal 0.959862 0.268228 0.0819712 + outer loop + vertex 883.221 461.466 344.97 + vertex 882.848 461.771 348.337 + vertex 884.91 455.171 345.786 + endloop + endfacet + facet normal 0.958258 0.256786 0.125704 + outer loop + vertex 882.325 462.03 351.793 + vertex 882.848 461.771 348.337 + vertex 881.353 466.387 350.303 + endloop + endfacet + facet normal 0.959239 0.265613 0.0964918 + outer loop + vertex 886.979 447.638 346.105 + vertex 884.581 455.228 349.053 + vertex 886.656 447.666 349.24 + endloop + endfacet + facet normal 0.961142 0.268123 0.0656942 + outer loop + vertex 887.252 447.482 342.741 + vertex 886.979 447.638 346.105 + vertex 889.435 439.645 342.801 + endloop + endfacet + facet normal 0.96237 0.268294 0.0431461 + outer loop + vertex 889.692 439.295 339.231 + vertex 887.252 447.482 342.741 + vertex 889.435 439.645 342.801 + endloop + endfacet + facet normal 0.962976 0.268521 0.0239386 + outer loop + vertex 889.898 438.891 335.476 + vertex 889.692 439.295 339.231 + vertex 892.113 430.952 335.455 + endloop + endfacet + facet normal 0.962634 0.270674 0.00843424 + outer loop + vertex 890.061 438.436 331.561 + vertex 887.611 447.026 335.501 + vertex 889.898 438.891 335.476 + endloop + endfacet + facet normal 0.96308 0.269138 -0.00641189 + outer loop + vertex 890.172 437.94 327.522 + vertex 890.061 438.436 331.561 + vertex 892.463 429.742 327.485 + endloop + endfacet + facet normal 0.962682 0.269127 -0.0285323 + outer loop + vertex 892.503 429.155 323.311 + vertex 890.172 437.94 327.522 + vertex 892.463 429.742 327.485 + endloop + endfacet + facet normal 0.962329 0.264159 -0.0643709 + outer loop + vertex 892.361 428.62 318.983 + vertex 892.503 429.155 323.311 + vertex 894.596 420.466 318.943 + endloop + endfacet + facet normal 0.960469 0.255067 -0.111538 + outer loop + vertex 894.191 420.001 314.391 + vertex 894.596 420.466 318.943 + vertex 896.376 411.775 314.395 + endloop + endfacet + facet normal 0.965341 0.254128 -0.0594639 + outer loop + vertex 896.768 412.263 318.957 + vertex 894.723 421.043 323.288 + vertex 896.86 412.925 323.286 + endloop + endfacet + facet normal 0.966738 0.254486 -0.0255932 + outer loop + vertex 894.723 421.043 323.288 + vertex 894.654 421.725 327.469 + vertex 896.86 412.925 323.286 + endloop + endfacet + facet normal 0.964615 0.26361 -0.00522274 + outer loop + vertex 894.654 421.725 327.469 + vertex 892.319 430.353 331.536 + vertex 894.474 422.466 331.52 + endloop + endfacet + facet normal 0.966923 0.254791 0.0118933 + outer loop + vertex 894.474 422.466 331.52 + vertex 894.227 423.221 335.431 + vertex 896.546 414.605 331.504 + endloop + endfacet + facet normal 0.964381 0.263123 0.0271138 + outer loop + vertex 894.227 423.221 335.431 + vertex 891.857 431.517 339.209 + vertex 893.918 423.968 339.172 + endloop + endfacet + facet normal 0.963739 0.262855 0.0459881 + outer loop + vertex 891.857 431.517 339.209 + vertex 891.544 432.044 342.763 + vertex 893.918 423.968 339.172 + endloop + endfacet + facet normal 0.961502 0.265731 0.0700007 + outer loop + vertex 891.544 432.044 342.763 + vertex 889.118 439.932 346.144 + vertex 891.161 432.553 346.094 + endloop + endfacet + facet normal 0.959161 0.263888 0.10185 + outer loop + vertex 891.161 432.553 346.094 + vertex 888.722 440.207 349.231 + vertex 890.682 433.104 349.173 + endloop + endfacet + facet normal 0.954334 0.262331 0.142933 + outer loop + vertex 890.682 433.104 349.173 + vertex 888.196 440.6 352.016 + vertex 890.076 433.783 351.977 + endloop + endfacet + facet normal 0.961806 0.252446 0.105827 + outer loop + vertex 894.945 418.399 346.057 + vertex 892.545 426.241 349.156 + vertex 894.334 419.419 349.169 + endloop + endfacet + facet normal 0.964438 0.253353 0.0753063 + outer loop + vertex 895.459 417.435 342.712 + vertex 893.093 425.447 346.058 + vertex 894.945 418.399 346.057 + endloop + endfacet + facet normal 0.965825 0.254412 0.0495567 + outer loop + vertex 895.893 416.482 339.158 + vertex 893.544 424.704 342.721 + vertex 895.459 417.435 342.712 + endloop + endfacet + facet normal 0.969295 0.243801 0.0320632 + outer loop + vertex 896.254 415.537 335.417 + vertex 895.893 416.482 339.158 + vertex 898.199 407.802 335.424 + endloop + endfacet + facet normal 0.969704 0.243887 0.0138922 + outer loop + vertex 898.533 406.697 331.503 + vertex 896.254 415.537 335.417 + vertex 898.199 407.802 335.424 + endloop + endfacet + facet normal 0.973398 0.229121 0.000404955 + outer loop + vertex 898.783 405.643 327.438 + vertex 898.533 406.697 331.503 + vertex 900.673 397.612 327.444 + endloop + endfacet + facet normal 0.969797 0.242915 -0.0220254 + outer loop + vertex 898.915 404.74 323.288 + vertex 896.761 413.716 327.454 + vertex 898.783 405.643 327.438 + endloop + endfacet + facet normal 0.971207 0.232155 -0.0534888 + outer loop + vertex 898.844 404.059 319.048 + vertex 898.915 404.74 323.288 + vertex 900.794 395.92 319.127 + endloop + endfacet + facet normal 0.970015 0.225101 -0.0916563 + outer loop + vertex 900.479 395.587 314.971 + vertex 900.794 395.92 319.127 + vertex 902.158 388.479 315.288 + endloop + endfacet + facet normal 0.975883 0.21445 -0.0407757 + outer loop + vertex 902.732 387.102 318.873 + vertex 900.85 396.503 323.259 + vertex 902.577 388.662 323.364 + endloop + endfacet + facet normal 0.985972 0.166435 -0.0125717 + outer loop + vertex 906.095 369.491 319.144 + vertex 905.248 374.558 319.793 + vertex 905.571 372.866 322.73 + endloop + endfacet + facet normal 0.988193 0.153215 0.000195129 + outer loop + vertex 906.095 369.491 319.144 + vertex 905.571 372.866 322.73 + vertex 906.688 365.666 319.547 + endloop + endfacet + facet normal 0.988401 0.151829 0.00340332 + outer loop + vertex 905.571 372.866 322.73 + vertex 906.85 364.543 322.616 + vertex 906.688 365.666 319.547 + endloop + endfacet + facet normal 0.983628 0.171519 -0.0552953 + outer loop + vertex 905.947 369.625 316.928 + vertex 905.248 374.558 319.793 + vertex 906.095 369.491 319.144 + endloop + endfacet + facet normal 0.984904 0.173032 0.00485404 + outer loop + vertex 905.571 372.866 322.73 + vertex 903.99 381.736 327.353 + vertex 905.421 373.595 327.234 + endloop + endfacet + facet normal 0.980078 0.198378 -0.00966252 + outer loop + vertex 902.577 388.662 323.364 + vertex 902.404 389.715 327.459 + vertex 904.083 381.223 323.406 + endloop + endfacet + facet normal 0.977011 0.213091 0.0064194 + outer loop + vertex 902.404 389.715 327.459 + vertex 900.403 398.768 331.514 + vertex 902.135 390.827 331.517 + endloop + endfacet + facet normal 0.976767 0.213044 0.0232235 + outer loop + vertex 900.403 398.768 331.514 + vertex 900.04 400.004 335.443 + vertex 902.135 390.827 331.517 + endloop + endfacet + facet normal 0.972588 0.229512 0.0373636 + outer loop + vertex 900.04 400.004 335.443 + vertex 897.788 408.942 339.169 + vertex 899.584 401.329 339.187 + endloop + endfacet + facet normal 0.971611 0.22872 0.0605005 + outer loop + vertex 899.584 401.329 339.187 + vertex 897.297 410.106 342.722 + vertex 899.04 402.701 342.732 + endloop + endfacet + facet normal 0.969894 0.227786 0.0861319 + outer loop + vertex 899.04 402.701 342.732 + vertex 896.726 411.289 346.074 + vertex 898.415 404.096 346.082 + endloop + endfacet + facet normal 0.966867 0.227205 0.116388 + outer loop + vertex 898.415 404.096 346.082 + vertex 896.059 412.528 349.195 + vertex 897.696 405.551 349.21 + endloop + endfacet + facet normal 0.960986 0.225647 0.159967 + outer loop + vertex 897.696 405.551 349.21 + vertex 895.263 413.909 352.04 + vertex 896.847 407.15 352.058 + endloop + endfacet + facet normal 0.972007 0.189285 0.139188 + outer loop + vertex 901.414 389.53 346.072 + vertex 899.217 398.504 349.21 + vertex 900.601 391.398 349.209 + endloop + endfacet + facet normal 0.975824 0.190472 0.107178 + outer loop + vertex 902.133 387.73 342.728 + vertex 899.986 396.842 346.08 + vertex 901.414 389.53 346.072 + endloop + endfacet + facet normal 0.978176 0.191574 0.0804419 + outer loop + vertex 902.768 385.962 339.21 + vertex 900.661 395.242 342.735 + vertex 902.133 387.73 342.728 + endloop + endfacet + facet normal 0.979703 0.192893 0.0545371 + outer loop + vertex 903.306 384.285 335.488 + vertex 901.252 393.666 339.202 + vertex 902.768 385.962 339.21 + endloop + endfacet + facet normal 0.980598 0.193504 0.0313765 + outer loop + vertex 903.72 382.832 331.513 + vertex 901.752 392.163 335.466 + vertex 903.306 384.285 335.488 + endloop + endfacet + facet normal 0.984783 0.172812 0.0183919 + outer loop + vertex 903.99 381.736 327.353 + vertex 903.72 382.832 331.513 + vertex 905.421 373.595 327.234 + endloop + endfacet + facet normal 0.988382 0.151758 0.00841035 + outer loop + vertex 905.571 372.866 322.73 + vertex 905.421 373.595 327.234 + vertex 906.85 364.543 322.616 + endloop + endfacet + facet normal 0.988645 0.147169 0.0303806 + outer loop + vertex 906.654 365.403 327.238 + vertex 905.126 374.785 331.526 + vertex 906.33 366.689 331.558 + endloop + endfacet + facet normal 0.987788 0.145386 0.0560082 + outer loop + vertex 906.33 366.689 331.558 + vertex 904.681 376.368 335.508 + vertex 905.852 368.412 335.521 + endloop + endfacet + facet normal 0.986142 0.143816 0.0827159 + outer loop + vertex 905.852 368.412 335.521 + vertex 904.112 378.214 339.214 + vertex 905.248 370.427 339.21 + endloop + endfacet + facet normal 0.983397 0.142443 0.11243 + outer loop + vertex 905.248 370.427 339.21 + vertex 903.436 380.17 342.72 + vertex 904.538 372.565 342.713 + endloop + endfacet + facet normal 0.979811 0.140538 0.142197 + outer loop + vertex 904.538 372.565 342.713 + vertex 902.675 382.165 346.065 + vertex 903.739 374.748 346.062 + endloop + endfacet + facet normal 0.974263 0.138416 0.17791 + outer loop + vertex 903.739 374.748 346.062 + vertex 901.818 384.229 349.205 + vertex 902.844 377.005 349.205 + endloop + endfacet + facet normal 0.978905 0.0753799 0.189903 + outer loop + vertex 905.401 364.917 342.709 + vertex 904.568 367.281 346.061 + vertex 905.992 357.231 342.71 + endloop + endfacet + facet normal 0.984288 0.0757897 0.159475 + outer loop + vertex 906.752 354.752 339.198 + vertex 905.401 364.917 342.709 + vertex 905.992 357.231 342.71 + endloop + endfacet + facet normal 0.988635 0.0764794 0.129429 + outer loop + vertex 907.415 352.411 335.517 + vertex 906.144 362.605 339.204 + vertex 906.752 354.752 339.198 + endloop + endfacet + facet normal 0.992484 0.0782172 0.0941172 + outer loop + vertex 907.949 350.381 331.571 + vertex 906.783 360.421 335.526 + vertex 907.415 352.411 335.517 + endloop + endfacet + facet normal 0.994689 0.0811489 0.063307 + outer loop + vertex 908.349 348.826 327.277 + vertex 907.283 358.552 331.57 + vertex 907.949 350.381 331.571 + endloop + endfacet + facet normal 0.995581 0.0842389 0.0414965 + outer loop + vertex 908.631 347.769 322.656 + vertex 907.646 357.147 327.267 + vertex 908.349 348.826 327.277 + endloop + endfacet + facet normal 0.99553 0.0887506 0.0323101 + outer loop + vertex 907.878 356.228 322.639 + vertex 907.646 357.147 327.267 + vertex 908.631 347.769 322.656 + endloop + endfacet + facet normal 0.992325 0.122741 0.0150145 + outer loop + vertex 906.85 364.543 322.616 + vertex 907.878 356.228 322.639 + vertex 907.781 357.387 319.573 + endloop + endfacet + facet normal 0.992161 0.124492 0.0108462 + outer loop + vertex 907.318 361.113 319.107 + vertex 906.85 364.543 322.616 + vertex 907.781 357.387 319.573 + endloop + endfacet + facet normal 0.990514 0.137397 -0.00198696 + outer loop + vertex 907.318 361.113 319.107 + vertex 906.688 365.666 319.547 + vertex 906.85 364.543 322.616 + endloop + endfacet + facet normal 0.987841 0.148171 -0.0470606 + outer loop + vertex 906.618 365.285 316.885 + vertex 906.095 369.491 319.144 + vertex 906.688 365.666 319.547 + endloop + endfacet + facet normal 0.986582 0.153141 -0.0566079 + outer loop + vertex 905.947 369.625 316.928 + vertex 906.095 369.491 319.144 + vertex 906.618 365.285 316.885 + endloop + endfacet + facet normal 0.984471 0.168373 -0.0496742 + outer loop + vertex 905.139 374.357 316.954 + vertex 905.248 374.558 319.793 + vertex 905.947 369.625 316.928 + endloop + endfacet + facet normal 0.98169 0.183624 -0.0506716 + outer loop + vertex 904.253 378.959 316.471 + vertex 904.111 380.635 319.788 + vertex 905.139 374.357 316.954 + endloop + endfacet + facet normal 0.976416 0.191441 -0.0998104 + outer loop + vertex 904.353 377.142 313.959 + vertex 903.5 381.937 314.815 + vertex 904.253 378.959 316.471 + endloop + endfacet + facet normal 0.969176 0.208303 -0.131559 + outer loop + vertex 902.88 383.096 312.084 + vertex 902.158 388.479 315.288 + vertex 903.5 381.937 314.815 + endloop + endfacet + facet normal 0.968729 0.209276 -0.133295 + outer loop + vertex 901.647 388.579 311.73 + vertex 902.158 388.479 315.288 + vertex 902.88 383.096 312.084 + endloop + endfacet + facet normal 0.965927 0.222312 -0.132525 + outer loop + vertex 902.158 388.479 315.288 + vertex 901.647 388.579 311.73 + vertex 900.479 395.587 314.971 + endloop + endfacet + facet normal 0.958347 0.234896 -0.162466 + outer loop + vertex 900.023 394.046 310.058 + vertex 900.479 395.587 314.971 + vertex 901.647 388.579 311.73 + endloop + endfacet + facet normal 0.955763 0.226381 -0.1878 + outer loop + vertex 901.284 387.879 309.037 + vertex 900.023 394.046 310.058 + vertex 901.647 388.579 311.73 + endloop + endfacet + facet normal 0.963744 0.196052 -0.180998 + outer loop + vertex 901.284 387.879 309.037 + vertex 901.647 388.579 311.73 + vertex 902.156 383.486 308.921 + endloop + endfacet + facet normal 0.949229 0.194905 -0.246935 + outer loop + vertex 901.284 387.879 309.037 + vertex 902.156 383.486 308.921 + vertex 900.802 385.91 305.63 + endloop + endfacet + facet normal 0.934208 0.235276 -0.268145 + outer loop + vertex 900.802 385.91 305.63 + vertex 900.023 394.046 310.058 + vertex 901.284 387.879 309.037 + endloop + endfacet + facet normal 0.95335 0.209469 -0.217363 + outer loop + vertex 898.776 394.594 305.115 + vertex 900.023 394.046 310.058 + vertex 900.802 385.91 305.63 + endloop + endfacet + facet normal 0.946064 0.205824 -0.250199 + outer loop + vertex 899.36 386.643 300.783 + vertex 898.776 394.594 305.115 + vertex 900.802 385.91 305.63 + endloop + endfacet + facet normal 0.950031 0.179544 -0.255352 + outer loop + vertex 899.36 386.643 300.783 + vertex 900.802 385.91 305.63 + vertex 901.001 378.134 300.904 + endloop + endfacet + facet normal 0.949177 0.179332 -0.258657 + outer loop + vertex 899.772 379.152 297.1 + vertex 899.36 386.643 300.783 + vertex 901.001 378.134 300.904 + endloop + endfacet + facet normal 0.948896 0.181311 -0.258308 + outer loop + vertex 901.001 378.134 300.904 + vertex 900.802 385.91 305.63 + vertex 902.518 377.007 305.685 + endloop + endfacet + facet normal 0.951725 0.153661 -0.265722 + outer loop + vertex 901.001 378.134 300.904 + vertex 902.518 377.007 305.685 + vertex 902.371 369.705 300.935 + endloop + endfacet + facet normal 0.952576 0.153811 -0.262567 + outer loop + vertex 901.141 370.815 297.125 + vertex 901.001 378.134 300.904 + vertex 902.371 369.705 300.935 + endloop + endfacet + facet normal 0.948842 0.201955 -0.242721 + outer loop + vertex 897.538 395.039 300.646 + vertex 898.776 394.594 305.115 + vertex 899.36 386.643 300.783 + endloop + endfacet + facet normal 0.946132 0.201187 -0.25369 + outer loop + vertex 898.175 387.526 297.065 + vertex 897.538 395.039 300.646 + vertex 899.36 386.643 300.783 + endloop + endfacet + facet normal 0.945069 0.222288 -0.239651 + outer loop + vertex 897.538 395.039 300.646 + vertex 896.735 403.093 304.948 + vertex 898.776 394.594 305.115 + endloop + endfacet + facet normal 0.951936 0.224555 -0.208308 + outer loop + vertex 896.735 403.093 304.948 + vertex 897.792 403.046 309.73 + vertex 898.776 394.594 305.115 + endloop + endfacet + facet normal 0.948473 0.239553 -0.207396 + outer loop + vertex 896.735 403.093 304.948 + vertex 895.644 411.476 309.641 + vertex 897.792 403.046 309.73 + endloop + endfacet + facet normal 0.948189 0.239971 -0.208208 + outer loop + vertex 894.663 411.26 304.926 + vertex 895.644 411.476 309.641 + vertex 896.735 403.093 304.948 + endloop + endfacet + facet normal 0.941752 0.238262 -0.23735 + outer loop + vertex 895.617 403.193 300.615 + vertex 894.663 411.26 304.926 + vertex 896.735 403.093 304.948 + endloop + endfacet + facet normal 0.940713 0.239607 -0.240098 + outer loop + vertex 893.607 411.112 300.641 + vertex 894.663 411.26 304.926 + vertex 895.617 403.193 300.615 + endloop + endfacet + facet normal 0.937541 0.238845 -0.252923 + outer loop + vertex 894.585 403.522 297.099 + vertex 893.607 411.112 300.641 + vertex 895.617 403.193 300.615 + endloop + endfacet + facet normal 0.940848 0.222641 -0.255413 + outer loop + vertex 894.585 403.522 297.099 + vertex 895.617 403.193 300.615 + vertex 896.439 395.656 297.072 + endloop + endfacet + facet normal 0.942258 0.221006 -0.251609 + outer loop + vertex 896.439 395.656 297.072 + vertex 895.617 403.193 300.615 + vertex 897.538 395.039 300.646 + endloop + endfacet + facet normal 0.936641 0.23984 -0.255305 + outer loop + vertex 892.599 411.28 297.101 + vertex 893.607 411.112 300.641 + vertex 894.585 403.522 297.099 + endloop + endfacet + facet normal 0.937858 0.240151 -0.250499 + outer loop + vertex 893.629 404.456 294.416 + vertex 892.599 411.28 297.101 + vertex 894.585 403.522 297.099 + endloop + endfacet + facet normal 0.939911 0.225542 -0.256315 + outer loop + vertex 893.629 404.456 294.416 + vertex 894.585 403.522 297.099 + vertex 895.455 396.828 294.397 + endloop + endfacet + facet normal 0.935644 0.242249 -0.256682 + outer loop + vertex 891.56 412.279 294.254 + vertex 892.599 411.28 297.101 + vertex 893.629 404.456 294.416 + endloop + endfacet + facet normal 0.940751 0.24404 -0.235441 + outer loop + vertex 891.56 412.279 294.254 + vertex 893.629 404.456 294.416 + vertex 892.578 407.091 292.946 + endloop + endfacet + facet normal 0.942256 0.243059 -0.23038 + outer loop + vertex 892.578 407.091 292.946 + vertex 891.728 410.353 292.911 + vertex 891.56 412.279 294.254 + endloop + endfacet + facet normal 0.936029 0.252681 -0.244953 + outer loop + vertex 891.728 410.353 292.911 + vertex 890.957 413.005 292.701 + vertex 891.56 412.279 294.254 + endloop + endfacet + facet normal 0.935588 0.255925 -0.243265 + outer loop + vertex 890.957 413.005 292.701 + vertex 890.193 416.184 293.105 + vertex 891.56 412.279 294.254 + endloop + endfacet + facet normal 0.936477 0.257863 -0.237736 + outer loop + vertex 889.417 420.197 294.403 + vertex 891.56 412.279 294.254 + vertex 890.193 416.184 293.105 + endloop + endfacet + facet normal 0.931799 0.261488 -0.251742 + outer loop + vertex 890.193 416.184 293.105 + vertex 889.025 419.983 292.73 + vertex 889.417 420.197 294.403 + endloop + endfacet + facet normal 0.930538 0.26571 -0.251986 + outer loop + vertex 889.025 419.983 292.73 + vertex 888.231 423.16 293.15 + vertex 889.417 420.197 294.403 + endloop + endfacet + facet normal 0.931812 0.2704 -0.242094 + outer loop + vertex 887.359 427.326 294.445 + vertex 889.417 420.197 294.403 + vertex 888.231 423.16 293.15 + endloop + endfacet + facet normal 0.930232 0.271545 -0.246844 + outer loop + vertex 888.231 423.16 293.15 + vertex 887.434 425.717 292.957 + vertex 887.359 427.326 294.445 + endloop + endfacet + facet normal 0.92672 0.277447 -0.253402 + outer loop + vertex 887.434 425.717 292.957 + vertex 886.265 429.538 292.867 + vertex 887.359 427.326 294.445 + endloop + endfacet + facet normal 0.926957 0.281032 -0.248541 + outer loop + vertex 885.028 435.069 294.508 + vertex 887.359 427.326 294.445 + vertex 886.265 429.538 292.867 + endloop + endfacet + facet normal 0.927323 0.280789 -0.247445 + outer loop + vertex 886.265 429.538 292.867 + vertex 884.697 434.551 292.677 + vertex 885.028 435.069 294.508 + endloop + endfacet + facet normal 0.924882 0.287478 -0.248897 + outer loop + vertex 884.697 434.551 292.677 + vertex 883.594 438.602 293.26 + vertex 885.028 435.069 294.508 + endloop + endfacet + facet normal 0.92603 0.290909 -0.2405 + outer loop + vertex 882.735 442.567 294.745 + vertex 885.028 435.069 294.508 + vertex 883.594 438.602 293.26 + endloop + endfacet + facet normal 0.923056 0.293373 -0.248797 + outer loop + vertex 883.594 438.602 293.26 + vertex 881.916 443.655 292.993 + vertex 882.735 442.567 294.745 + endloop + endfacet + facet normal 0.921966 0.301197 -0.243431 + outer loop + vertex 880.566 448.769 294.206 + vertex 882.735 442.567 294.745 + vertex 881.916 443.655 292.993 + endloop + endfacet + facet normal 0.924342 0.300007 -0.235769 + outer loop + vertex 881.916 443.655 292.993 + vertex 880.674 447.367 292.844 + vertex 880.566 448.769 294.206 + endloop + endfacet + facet normal 0.917538 0.311074 -0.247701 + outer loop + vertex 880.674 447.367 292.844 + vertex 879.447 450.833 292.653 + vertex 880.566 448.769 294.206 + endloop + endfacet + facet normal 0.917557 0.312309 -0.246073 + outer loop + vertex 878.644 454.045 293.734 + vertex 880.566 448.769 294.206 + vertex 879.447 450.833 292.653 + endloop + endfacet + facet normal 0.912949 0.31546 -0.258861 + outer loop + vertex 879.447 450.833 292.653 + vertex 878.314 454.031 292.554 + vertex 878.644 454.045 293.734 + endloop + endfacet + facet normal 0.908112 0.330057 -0.257674 + outer loop + vertex 878.314 454.031 292.554 + vertex 877.291 457.049 292.815 + vertex 878.644 454.045 293.734 + endloop + endfacet + facet normal 0.90418 0.32085 -0.281982 + outer loop + vertex 877.291 457.049 292.815 + vertex 877.402 458.549 294.878 + vertex 878.644 454.045 293.734 + endloop + endfacet + facet normal 0.908159 0.319137 -0.270922 + outer loop + vertex 879.111 454.748 296.13 + vertex 878.644 454.045 293.734 + vertex 877.402 458.549 294.878 + endloop + endfacet + facet normal 0.905467 0.312613 -0.287057 + outer loop + vertex 877.402 458.549 294.878 + vertex 878.028 459.647 298.047 + vertex 879.111 454.748 296.13 + endloop + endfacet + facet normal 0.905228 0.312783 -0.287627 + outer loop + vertex 879.8 456.543 300.25 + vertex 879.111 454.748 296.13 + vertex 878.028 459.647 298.047 + endloop + endfacet + facet normal 0.9048 0.307889 -0.294179 + outer loop + vertex 878.028 459.647 298.047 + vertex 878.588 461.362 301.566 + vertex 879.8 456.543 300.25 + endloop + endfacet + facet normal 0.906763 0.306979 -0.28904 + outer loop + vertex 878.588 461.362 301.566 + vertex 879.885 461.284 305.552 + vertex 879.8 456.543 300.25 + endloop + endfacet + facet normal 0.9084 0.304328 -0.286696 + outer loop + vertex 881.138 455.906 303.814 + vertex 879.8 456.543 300.25 + vertex 879.885 461.284 305.552 + endloop + endfacet + facet normal 0.91629 0.299464 -0.265959 + outer loop + vertex 881.722 457.917 308.089 + vertex 881.138 455.906 303.814 + vertex 879.885 461.284 305.552 + endloop + endfacet + facet normal 0.916426 0.302534 -0.261984 + outer loop + vertex 879.885 461.284 305.552 + vertex 880.772 463.501 311.214 + vertex 881.722 457.917 308.089 + endloop + endfacet + facet normal 0.930795 0.266547 -0.250147 + outer loop + vertex 879.885 461.284 305.552 + vertex 879.777 465.069 309.181 + vertex 880.772 463.501 311.214 + endloop + endfacet + facet normal 0.910619 0.299316 -0.284926 + outer loop + vertex 878.721 463.642 304.308 + vertex 879.777 465.069 309.181 + vertex 879.885 461.284 305.552 + endloop + endfacet + facet normal 0.917187 0.297445 -0.265132 + outer loop + vertex 881.138 455.906 303.814 + vertex 881.722 457.917 308.089 + vertex 883.079 450.631 304.608 + endloop + endfacet + facet normal 0.915165 0.295315 -0.27434 + outer loop + vertex 882.116 449.784 300.484 + vertex 881.138 455.906 303.814 + vertex 883.079 450.631 304.608 + endloop + endfacet + facet normal 0.915864 0.293362 -0.274102 + outer loop + vertex 882.116 449.784 300.484 + vertex 883.079 450.631 304.608 + vertex 884.537 442.475 300.75 + endloop + endfacet + facet normal 0.915984 0.293418 -0.273639 + outer loop + vertex 883.611 442.09 297.238 + vertex 882.116 449.784 300.484 + vertex 884.537 442.475 300.75 + endloop + endfacet + facet normal 0.917965 0.287304 -0.273491 + outer loop + vertex 883.611 442.09 297.238 + vertex 884.537 442.475 300.75 + vertex 886.022 434.373 297.225 + endloop + endfacet + facet normal 0.920778 0.288164 -0.262927 + outer loop + vertex 885.028 435.069 294.508 + vertex 883.611 442.09 297.238 + vertex 886.022 434.373 297.225 + endloop + endfacet + facet normal 0.921178 0.284443 -0.265562 + outer loop + vertex 886.022 434.373 297.225 + vertex 884.537 442.475 300.75 + vertex 886.975 434.622 300.797 + endloop + endfacet + facet normal 0.92334 0.27727 -0.265639 + outer loop + vertex 886.022 434.373 297.225 + vertex 886.975 434.622 300.797 + vertex 888.313 426.692 297.169 + endloop + endfacet + facet normal 0.925045 0.277731 -0.259149 + outer loop + vertex 887.359 427.326 294.445 + vertex 886.022 434.373 297.225 + vertex 888.313 426.692 297.169 + endloop + endfacet + facet normal 0.926116 0.274562 -0.258697 + outer loop + vertex 888.313 426.692 297.169 + vertex 886.975 434.622 300.797 + vertex 889.299 426.731 300.74 + endloop + endfacet + facet normal 0.928429 0.266106 -0.259243 + outer loop + vertex 888.313 426.692 297.169 + vertex 889.299 426.731 300.74 + vertex 890.492 419.027 297.106 + endloop + endfacet + facet normal 0.929674 0.266421 -0.254414 + outer loop + vertex 889.417 420.197 294.403 + vertex 888.313 426.692 297.169 + vertex 890.492 419.027 297.106 + endloop + endfacet + facet normal 0.929868 0.264607 -0.255593 + outer loop + vertex 890.492 419.027 297.106 + vertex 889.299 426.731 300.74 + vertex 891.504 418.913 300.669 + endloop + endfacet + facet normal 0.932567 0.253817 -0.256702 + outer loop + vertex 890.492 419.027 297.106 + vertex 891.504 418.913 300.669 + vertex 892.599 411.28 297.101 + endloop + endfacet + facet normal 0.932562 0.26527 -0.244868 + outer loop + vertex 889.299 426.731 300.74 + vertex 890.311 427.146 305.047 + vertex 891.504 418.913 300.669 + endloop + endfacet + facet normal 0.934015 0.263524 -0.241187 + outer loop + vertex 891.504 418.913 300.669 + vertex 890.311 427.146 305.047 + vertex 892.53 419.214 304.973 + endloop + endfacet + facet normal 0.93681 0.253443 -0.24115 + outer loop + vertex 891.504 418.913 300.669 + vertex 892.53 419.214 304.973 + vertex 893.607 411.112 300.641 + endloop + endfacet + facet normal 0.940194 0.265001 -0.214032 + outer loop + vertex 890.311 427.146 305.047 + vertex 891.237 427.655 309.741 + vertex 892.53 419.214 304.973 + endloop + endfacet + facet normal 0.941146 0.26369 -0.211453 + outer loop + vertex 892.53 419.214 304.973 + vertex 891.237 427.655 309.741 + vertex 893.476 419.602 309.666 + endloop + endfacet + facet normal 0.943779 0.254306 -0.211208 + outer loop + vertex 892.53 419.214 304.973 + vertex 893.476 419.602 309.666 + vertex 894.663 411.26 304.926 + endloop + endfacet + facet normal 0.938443 0.270903 -0.214326 + outer loop + vertex 890.311 427.146 305.047 + vertex 888.887 435.861 309.825 + vertex 891.237 427.655 309.741 + endloop + endfacet + facet normal 0.935978 0.274115 -0.220919 + outer loop + vertex 887.965 435.222 305.125 + vertex 888.887 435.861 309.825 + vertex 890.311 427.146 305.047 + endloop + endfacet + facet normal 0.934839 0.27776 -0.221191 + outer loop + vertex 887.965 435.222 305.125 + vertex 886.403 444.181 309.774 + vertex 888.887 435.861 309.825 + endloop + endfacet + facet normal 0.931223 0.282093 -0.230756 + outer loop + vertex 885.501 443.287 305.044 + vertex 886.403 444.181 309.774 + vertex 887.965 435.222 305.125 + endloop + endfacet + facet normal 0.926539 0.280461 -0.250734 + outer loop + vertex 886.975 434.622 300.797 + vertex 885.501 443.287 305.044 + vertex 887.965 435.222 305.125 + endloop + endfacet + facet normal 0.930634 0.283851 -0.230976 + outer loop + vertex 885.501 443.287 305.044 + vertex 883.925 451.918 309.298 + vertex 886.403 444.181 309.774 + endloop + endfacet + facet normal 0.936363 0.287504 -0.201411 + outer loop + vertex 883.925 451.918 309.298 + vertex 884.631 453.074 314.233 + vertex 886.403 444.181 309.774 + endloop + endfacet + facet normal 0.941485 0.280923 -0.18625 + outer loop + vertex 886.403 444.181 309.774 + vertex 884.631 453.074 314.233 + vertex 887.136 444.872 314.525 + endloop + endfacet + facet normal 0.941763 0.280044 -0.186166 + outer loop + vertex 886.403 444.181 309.774 + vertex 887.136 444.872 314.525 + vertex 888.887 435.861 309.825 + endloop + endfacet + facet normal 0.945361 0.274991 -0.175138 + outer loop + vertex 888.887 435.861 309.825 + vertex 887.136 444.872 314.525 + vertex 889.598 436.411 314.526 + endloop + endfacet + facet normal 0.946059 0.272683 -0.174974 + outer loop + vertex 888.887 435.861 309.825 + vertex 889.598 436.411 314.526 + vertex 891.237 427.655 309.741 + endloop + endfacet + facet normal 0.947422 0.270626 -0.170743 + outer loop + vertex 891.237 427.655 309.741 + vertex 889.598 436.411 314.526 + vertex 891.949 428.133 314.451 + endloop + endfacet + facet normal 0.948932 0.265472 -0.170447 + outer loop + vertex 891.237 427.655 309.741 + vertex 891.949 428.133 314.451 + vertex 893.476 419.602 309.666 + endloop + endfacet + facet normal 0.950318 0.263272 -0.166083 + outer loop + vertex 893.476 419.602 309.666 + vertex 891.949 428.133 314.451 + vertex 894.191 420.001 314.391 + endloop + endfacet + facet normal 0.952724 0.254663 -0.16572 + outer loop + vertex 893.476 419.602 309.666 + vertex 894.191 420.001 314.391 + vertex 895.644 411.476 309.641 + endloop + endfacet + facet normal 0.9536 0.253221 -0.162865 + outer loop + vertex 895.644 411.476 309.641 + vertex 894.191 420.001 314.391 + vertex 896.376 411.775 314.395 + endloop + endfacet + facet normal 0.956532 0.242078 -0.162616 + outer loop + vertex 895.644 411.476 309.641 + vertex 896.376 411.775 314.395 + vertex 897.792 403.046 309.73 + endloop + endfacet + facet normal 0.956657 0.241871 -0.16219 + outer loop + vertex 897.792 403.046 309.73 + vertex 896.376 411.775 314.395 + vertex 898.518 403.397 314.536 + endloop + endfacet + facet normal 0.959181 0.2319 -0.161844 + outer loop + vertex 897.792 403.046 309.73 + vertex 898.518 403.397 314.536 + vertex 900.023 394.046 310.058 + endloop + endfacet + facet normal 0.9377 0.283621 -0.200692 + outer loop + vertex 883.925 451.918 309.298 + vertex 882.406 459.663 313.149 + vertex 884.631 453.074 314.233 + endloop + endfacet + facet normal 0.928093 0.294949 -0.227264 + outer loop + vertex 881.722 457.917 308.089 + vertex 882.406 459.663 313.149 + vertex 883.925 451.918 309.298 + endloop + endfacet + facet normal 0.932279 0.284002 -0.224052 + outer loop + vertex 882.406 459.663 313.149 + vertex 881.722 457.917 308.089 + vertex 880.772 463.501 311.214 + endloop + endfacet + facet normal 0.933481 0.293756 -0.205722 + outer loop + vertex 880.772 463.501 311.214 + vertex 881.301 465.268 316.137 + vertex 882.406 459.663 313.149 + endloop + endfacet + facet normal 0.948766 0.250953 -0.192003 + outer loop + vertex 880.772 463.501 311.214 + vertex 880.485 466.829 314.144 + vertex 881.301 465.268 316.137 + endloop + endfacet + facet normal 0.929104 0.286308 -0.234082 + outer loop + vertex 879.777 465.069 309.181 + vertex 880.485 466.829 314.144 + vertex 880.772 463.501 311.214 + endloop + endfacet + facet normal 0.924626 0.290386 -0.246461 + outer loop + vertex 883.079 450.631 304.608 + vertex 883.925 451.918 309.298 + vertex 885.501 443.287 305.044 + endloop + endfacet + facet normal 0.930359 0.272716 -0.245068 + outer loop + vertex 889.299 426.731 300.74 + vertex 887.965 435.222 305.125 + vertex 890.311 427.146 305.047 + endloop + endfacet + facet normal 0.928232 0.275125 -0.250381 + outer loop + vertex 886.975 434.622 300.797 + vertex 887.965 435.222 305.125 + vertex 889.299 426.731 300.74 + endloop + endfacet + facet normal 0.922332 0.284829 -0.261105 + outer loop + vertex 884.537 442.475 300.75 + vertex 885.501 443.287 305.044 + vertex 886.975 434.622 300.797 + endloop + endfacet + facet normal 0.913186 0.295733 -0.280418 + outer loop + vertex 881.235 449.189 296.987 + vertex 882.116 449.784 300.484 + vertex 883.611 442.09 297.238 + endloop + endfacet + facet normal 0.917073 0.297567 -0.265388 + outer loop + vertex 882.735 442.567 294.745 + vertex 881.235 449.189 296.987 + vertex 883.611 442.09 297.238 + endloop + endfacet + facet normal 0.910862 0.302317 -0.280954 + outer loop + vertex 881.235 449.189 296.987 + vertex 879.8 456.543 300.25 + vertex 882.116 449.784 300.484 + endloop + endfacet + facet normal 0.921129 0.288341 -0.261499 + outer loop + vertex 884.537 442.475 300.75 + vertex 883.079 450.631 304.608 + vertex 885.501 443.287 305.044 + endloop + endfacet + facet normal 0.924807 0.289894 -0.246358 + outer loop + vertex 883.079 450.631 304.608 + vertex 881.722 457.917 308.089 + vertex 883.925 451.918 309.298 + endloop + endfacet + facet normal 0.909102 0.301489 -0.287467 + outer loop + vertex 879.8 456.543 300.25 + vertex 881.138 455.906 303.814 + vertex 882.116 449.784 300.484 + endloop + endfacet + facet normal 0.909957 0.296158 -0.290292 + outer loop + vertex 878.588 461.362 301.566 + vertex 878.721 463.642 304.308 + vertex 879.885 461.284 305.552 + endloop + endfacet + facet normal 0.901062 0.311038 -0.302229 + outer loop + vertex 877.698 462.475 300.057 + vertex 878.721 463.642 304.308 + vertex 878.588 461.362 301.566 + endloop + endfacet + facet normal 0.897067 0.320769 -0.303937 + outer loop + vertex 878.721 463.642 304.308 + vertex 877.698 462.475 300.057 + vertex 878.015 463.649 302.232 + endloop + endfacet + facet normal 0.906175 0.290707 -0.307142 + outer loop + vertex 878.015 463.649 302.232 + vertex 878.59 464.222 304.469 + vertex 878.721 463.642 304.308 + endloop + endfacet + facet normal 0.90961 0.289069 -0.298412 + outer loop + vertex 878.59 464.222 304.469 + vertex 879.118 464.911 306.747 + vertex 878.721 463.642 304.308 + endloop + endfacet + facet normal 0.886202 0.344523 -0.309757 + outer loop + vertex 879.118 464.911 306.747 + vertex 878.59 464.222 304.469 + vertex 878.229 464.917 304.209 + endloop + endfacet + facet normal 0.890696 0.331232 -0.311362 + outer loop + vertex 878.229 464.917 304.209 + vertex 879.09 466.178 308.014 + vertex 879.118 464.911 306.747 + endloop + endfacet + facet normal 0.893985 0.323879 -0.309668 + outer loop + vertex 877.629 468.001 305.704 + vertex 879.09 466.178 308.014 + vertex 878.229 464.917 304.209 + endloop + endfacet + facet normal 0.885602 0.330374 -0.326439 + outer loop + vertex 877.629 468.001 305.704 + vertex 878.229 464.917 304.209 + vertex 876.649 466.643 301.671 + endloop + endfacet + facet normal 0.899586 0.298271 -0.319029 + outer loop + vertex 877.629 468.001 305.704 + vertex 876.649 466.643 301.671 + vertex 875.535 471.845 303.394 + endloop + endfacet + facet normal 0.897382 0.287774 -0.334502 + outer loop + vertex 875.535 471.845 303.394 + vertex 876.411 473.563 307.222 + vertex 877.629 468.001 305.704 + endloop + endfacet + facet normal 0.910396 0.281962 -0.302781 + outer loop + vertex 878.451 469.437 309.512 + vertex 877.629 468.001 305.704 + vertex 876.411 473.563 307.222 + endloop + endfacet + facet normal 0.909322 0.2773 -0.310223 + outer loop + vertex 876.411 473.563 307.222 + vertex 877.119 475.454 310.986 + vertex 878.451 469.437 309.512 + endloop + endfacet + facet normal 0.929401 0.267932 -0.253825 + outer loop + vertex 879.029 471.003 313.281 + vertex 878.451 469.437 309.512 + vertex 877.119 475.454 310.986 + endloop + endfacet + facet normal 0.929409 0.267974 -0.25375 + outer loop + vertex 877.119 475.454 310.986 + vertex 877.631 477.31 314.821 + vertex 879.029 471.003 313.281 + endloop + endfacet + facet normal 0.948911 0.25554 -0.185115 + outer loop + vertex 879.418 472.396 317.198 + vertex 879.029 471.003 313.281 + vertex 877.631 477.31 314.821 + endloop + endfacet + facet normal 0.932256 0.301599 -0.199839 + outer loop + vertex 879.418 472.396 317.198 + vertex 880.209 468.86 315.552 + vertex 879.029 471.003 313.281 + endloop + endfacet + facet normal 0.933274 0.291343 -0.210046 + outer loop + vertex 879.029 471.003 313.281 + vertex 880.209 468.86 315.552 + vertex 879.81 467.412 311.77 + endloop + endfacet + facet normal 0.959439 0.181343 -0.215853 + outer loop + vertex 875.88 484.06 312.71 + vertex 877.631 477.31 314.821 + vertex 877.119 475.454 310.986 + endloop + endfacet + facet normal 0.959983 0.182574 -0.212367 + outer loop + vertex 876.328 486.308 316.669 + vertex 877.631 477.31 314.821 + vertex 875.88 484.06 312.71 + endloop + endfacet + facet normal 0.91135 0.311452 -0.269145 + outer loop + vertex 879.029 471.003 313.281 + vertex 879.81 467.412 311.77 + vertex 878.451 469.437 309.512 + endloop + endfacet + facet normal 0.911727 0.305147 -0.275026 + outer loop + vertex 878.451 469.437 309.512 + vertex 879.81 467.412 311.77 + vertex 879.09 466.178 308.014 + endloop + endfacet + facet normal 0.941464 0.195072 -0.27494 + outer loop + vertex 875.245 481.598 308.928 + vertex 877.119 475.454 310.986 + vertex 876.411 473.563 307.222 + endloop + endfacet + facet normal 0.939783 0.191927 -0.282794 + outer loop + vertex 875.88 484.06 312.71 + vertex 877.119 475.454 310.986 + vertex 875.245 481.598 308.928 + endloop + endfacet + facet normal 0.928895 0.208448 -0.306111 + outer loop + vertex 874.472 479.27 305.223 + vertex 876.411 473.563 307.222 + vertex 875.535 471.845 303.394 + endloop + endfacet + facet normal 0.920736 0.212486 -0.327253 + outer loop + vertex 874.472 479.27 305.223 + vertex 875.535 471.845 303.394 + vertex 873.627 477.223 301.516 + endloop + endfacet + facet normal 0.925051 0.220223 -0.309489 + outer loop + vertex 873.627 477.223 301.516 + vertex 875.535 471.845 303.394 + vertex 874.592 470.251 299.44 + endloop + endfacet + facet normal 0.920588 0.22293 -0.320657 + outer loop + vertex 873.627 477.223 301.516 + vertex 874.592 470.251 299.44 + vertex 872.658 475.29 297.39 + endloop + endfacet + facet normal 0.922686 0.227571 -0.311226 + outer loop + vertex 872.658 475.29 297.39 + vertex 874.592 470.251 299.44 + vertex 873.828 468.543 295.926 + endloop + endfacet + facet normal 0.898507 0.236137 -0.370034 + outer loop + vertex 872.658 475.29 297.39 + vertex 873.828 468.543 295.926 + vertex 872.441 470.194 293.611 + endloop + endfacet + facet normal 0.940307 0.175976 -0.2913 + outer loop + vertex 872.441 470.194 293.611 + vertex 871.711 473.702 293.376 + vertex 872.658 475.29 297.39 + endloop + endfacet + facet normal 0.943245 0.177289 -0.280817 + outer loop + vertex 871.711 473.702 293.376 + vertex 872.441 470.194 293.611 + vertex 870.743 472.295 289.236 + endloop + endfacet + facet normal 0.927766 0.306604 -0.212708 + outer loop + vertex 872.441 470.194 293.611 + vertex 873.514 465.984 292.223 + vertex 870.743 472.295 289.236 + endloop + endfacet + facet normal 0.920262 0.312299 -0.235771 + outer loop + vertex 872.441 470.194 293.611 + vertex 873.528 467.255 293.961 + vertex 873.514 465.984 292.223 + endloop + endfacet + facet normal 0.897732 0.29288 -0.329088 + outer loop + vertex 873.528 467.255 293.961 + vertex 872.441 470.194 293.611 + vertex 873.828 468.543 295.926 + endloop + endfacet + facet normal 0.863218 0.351578 -0.362281 + outer loop + vertex 874.418 465.655 294.529 + vertex 873.528 467.255 293.961 + vertex 873.828 468.543 295.926 + endloop + endfacet + facet normal 0.880288 0.339921 -0.330977 + outer loop + vertex 874.418 465.655 294.529 + vertex 873.828 468.543 295.926 + vertex 875.689 465.019 297.256 + endloop + endfacet + facet normal 0.870444 0.375748 -0.318025 + outer loop + vertex 875.31 463.15 294.011 + vertex 874.418 465.655 294.529 + vertex 875.689 465.019 297.256 + endloop + endfacet + facet normal 0.875261 0.367834 -0.314032 + outer loop + vertex 876.314 462.296 295.81 + vertex 875.31 463.15 294.011 + vertex 875.689 465.019 297.256 + endloop + endfacet + facet normal 0.879579 0.364453 -0.305802 + outer loop + vertex 875.689 465.019 297.256 + vertex 876.599 463.183 297.688 + vertex 876.314 462.296 295.81 + endloop + endfacet + facet normal 0.880291 0.363155 -0.305297 + outer loop + vertex 877.007 462.652 298.232 + vertex 876.314 462.296 295.81 + vertex 876.599 463.183 297.688 + endloop + endfacet + facet normal 0.889027 0.34178 -0.304661 + outer loop + vertex 876.314 462.296 295.81 + vertex 877.007 462.652 298.232 + vertex 876.995 461.321 296.702 + endloop + endfacet + facet normal 0.888933 0.348426 -0.297318 + outer loop + vertex 876.995 461.321 296.702 + vertex 876.603 460.821 294.946 + vertex 876.314 462.296 295.81 + endloop + endfacet + facet normal 0.880991 0.355558 -0.312145 + outer loop + vertex 876.329 460.453 293.752 + vertex 876.314 462.296 295.81 + vertex 876.603 460.821 294.946 + endloop + endfacet + facet normal 0.895318 0.323955 -0.305709 + outer loop + vertex 876.603 460.821 294.946 + vertex 877.402 458.549 294.878 + vertex 876.329 460.453 293.752 + endloop + endfacet + facet normal 0.896748 0.333564 -0.290825 + outer loop + vertex 877.291 457.049 292.815 + vertex 876.329 460.453 293.752 + vertex 877.402 458.549 294.878 + endloop + endfacet + facet normal 0.882738 0.33908 -0.325267 + outer loop + vertex 876.329 460.453 293.752 + vertex 877.291 457.049 292.815 + vertex 875.482 460.583 291.59 + endloop + endfacet + facet normal 0.899222 0.324948 -0.292932 + outer loop + vertex 876.603 460.821 294.946 + vertex 876.995 461.321 296.702 + vertex 877.402 458.549 294.878 + endloop + endfacet + facet normal 0.878615 0.362898 -0.310387 + outer loop + vertex 875.689 465.019 297.256 + vertex 877.202 463.823 300.141 + vertex 876.599 463.183 297.688 + endloop + endfacet + facet normal 0.880531 0.358753 -0.309777 + outer loop + vertex 876.599 463.183 297.688 + vertex 877.202 463.823 300.141 + vertex 877.007 462.652 298.232 + endloop + endfacet + facet normal 0.883749 0.353361 -0.306797 + outer loop + vertex 877.473 463.101 300.091 + vertex 877.007 462.652 298.232 + vertex 877.202 463.823 300.141 + endloop + endfacet + facet normal 0.881535 0.352994 -0.313513 + outer loop + vertex 878.015 463.649 302.232 + vertex 877.473 463.101 300.091 + vertex 877.202 463.823 300.141 + endloop + endfacet + facet normal 0.884682 0.34317 -0.315551 + outer loop + vertex 877.202 463.823 300.141 + vertex 878.229 464.917 304.209 + vertex 878.015 463.649 302.232 + endloop + endfacet + facet normal 0.891023 0.336618 -0.304575 + outer loop + vertex 877.007 462.652 298.232 + vertex 877.473 463.101 300.091 + vertex 877.698 462.475 300.057 + endloop + endfacet + facet normal 0.882207 0.346129 -0.319225 + outer loop + vertex 876.649 466.643 301.671 + vertex 877.202 463.823 300.141 + vertex 875.689 465.019 297.256 + endloop + endfacet + facet normal 0.895453 0.317825 -0.31169 + outer loop + vertex 876.649 466.643 301.671 + vertex 875.689 465.019 297.256 + vertex 874.592 470.251 299.44 + endloop + endfacet + facet normal 0.876518 0.361678 -0.317656 + outer loop + vertex 876.314 462.296 295.81 + vertex 876.329 460.453 293.752 + vertex 875.31 463.15 294.011 + endloop + endfacet + facet normal 0.87534 0.361557 -0.321023 + outer loop + vertex 875.31 463.15 294.011 + vertex 876.329 460.453 293.752 + vertex 875.482 460.583 291.59 + endloop + endfacet + facet normal 0.876214 0.330207 -0.351017 + outer loop + vertex 873.828 468.543 295.926 + vertex 874.592 470.251 299.44 + vertex 875.689 465.019 297.256 + endloop + endfacet + facet normal 0.925488 0.202357 -0.320192 + outer loop + vertex 875.245 481.598 308.928 + vertex 876.411 473.563 307.222 + vertex 874.472 479.27 305.223 + endloop + endfacet + facet normal 0.892626 0.301975 -0.33471 + outer loop + vertex 874.592 470.251 299.44 + vertex 875.535 471.845 303.394 + vertex 876.649 466.643 301.671 + endloop + endfacet + facet normal 0.884038 0.344618 -0.315778 + outer loop + vertex 876.649 466.643 301.671 + vertex 878.229 464.917 304.209 + vertex 877.202 463.823 300.141 + endloop + endfacet + facet normal 0.894297 0.319383 -0.313412 + outer loop + vertex 878.451 469.437 309.512 + vertex 879.09 466.178 308.014 + vertex 877.629 468.001 305.704 + endloop + endfacet + facet normal 0.885305 0.342119 -0.314944 + outer loop + vertex 878.59 464.222 304.469 + vertex 878.015 463.649 302.232 + vertex 878.229 464.917 304.209 + endloop + endfacet + facet normal 0.888923 0.336216 -0.311086 + outer loop + vertex 877.473 463.101 300.091 + vertex 878.015 463.649 302.232 + vertex 877.698 462.475 300.057 + endloop + endfacet + facet normal 0.900578 0.316672 -0.297789 + outer loop + vertex 878.028 459.647 298.047 + vertex 877.698 462.475 300.057 + vertex 878.588 461.362 301.566 + endloop + endfacet + facet normal 0.900627 0.316616 -0.297702 + outer loop + vertex 876.995 461.321 296.702 + vertex 877.698 462.475 300.057 + vertex 878.028 459.647 298.047 + endloop + endfacet + facet normal 0.889774 0.340679 -0.30371 + outer loop + vertex 877.698 462.475 300.057 + vertex 876.995 461.321 296.702 + vertex 877.007 462.652 298.232 + endloop + endfacet + facet normal 0.909426 0.303518 -0.284292 + outer loop + vertex 879.111 454.748 296.13 + vertex 879.8 456.543 300.25 + vertex 881.235 449.189 296.987 + endloop + endfacet + facet normal 0.913463 0.307866 -0.266091 + outer loop + vertex 880.566 448.769 294.206 + vertex 879.111 454.748 296.13 + vertex 881.235 449.189 296.987 + endloop + endfacet + facet normal 0.90089 0.323132 -0.289799 + outer loop + vertex 877.402 458.549 294.878 + vertex 876.995 461.321 296.702 + vertex 878.028 459.647 298.047 + endloop + endfacet + facet normal 0.912519 0.308455 -0.268636 + outer loop + vertex 878.644 454.045 293.734 + vertex 879.111 454.748 296.13 + vertex 880.566 448.769 294.206 + endloop + endfacet + facet normal 0.895783 0.329396 -0.298449 + outer loop + vertex 877.291 457.049 292.815 + vertex 878.314 454.031 292.554 + vertex 877.694 454.418 291.121 + endloop + endfacet + facet normal 0.900372 0.309555 -0.305787 + outer loop + vertex 878.314 454.031 292.554 + vertex 879.447 450.833 292.653 + vertex 877.694 454.418 291.121 + endloop + endfacet + facet normal 0.902685 0.317029 -0.29095 + outer loop + vertex 880.164 447.462 291.204 + vertex 877.694 454.418 291.121 + vertex 879.447 450.833 292.653 + endloop + endfacet + facet normal 0.908238 0.319247 -0.270527 + outer loop + vertex 880.164 447.462 291.204 + vertex 877.398 452.614 287.999 + vertex 877.694 454.418 291.121 + endloop + endfacet + facet normal 0.89177 0.350028 -0.286753 + outer loop + vertex 877.398 452.614 287.999 + vertex 874.922 459.142 288.264 + vertex 877.694 454.418 291.121 + endloop + endfacet + facet normal 0.89087 0.342351 -0.298575 + outer loop + vertex 877.694 454.418 291.121 + vertex 874.922 459.142 288.264 + vertex 875.482 460.583 291.59 + endloop + endfacet + facet normal 0.894678 0.350722 -0.27667 + outer loop + vertex 877.398 452.614 287.999 + vertex 873.936 458.104 283.763 + vertex 874.922 459.142 288.264 + endloop + endfacet + facet normal 0.894594 0.362482 -0.261359 + outer loop + vertex 876.54 451.584 283.631 + vertex 873.936 458.104 283.763 + vertex 877.398 452.614 287.999 + endloop + endfacet + facet normal 0.910605 0.324753 -0.255606 + outer loop + vertex 879.897 445.627 288.022 + vertex 876.54 451.584 283.631 + vertex 877.398 452.614 287.999 + endloop + endfacet + facet normal 0.910669 0.329304 -0.249482 + outer loop + vertex 878.943 444.928 283.619 + vertex 876.54 451.584 283.631 + vertex 879.897 445.627 288.022 + endloop + endfacet + facet normal 0.921364 0.300011 -0.247148 + outer loop + vertex 882.204 438.532 288.009 + vertex 878.943 444.928 283.619 + vertex 879.897 445.627 288.022 + endloop + endfacet + facet normal 0.920516 0.299741 -0.250612 + outer loop + vertex 882.204 438.532 288.009 + vertex 879.897 445.627 288.022 + vertex 882.7 439.732 291.267 + endloop + endfacet + facet normal 0.925867 0.286368 -0.246503 + outer loop + vertex 884.803 432.692 290.99 + vertex 882.204 438.532 288.009 + vertex 882.7 439.732 291.267 + endloop + endfacet + facet normal 0.923197 0.285974 -0.256763 + outer loop + vertex 884.803 432.692 290.99 + vertex 882.7 439.732 291.267 + vertex 884.697 434.551 292.677 + endloop + endfacet + facet normal 0.925358 0.283503 -0.251672 + outer loop + vertex 884.396 431.386 288.02 + vertex 882.204 438.532 288.009 + vertex 884.803 432.692 290.99 + endloop + endfacet + facet normal 0.928207 0.276483 -0.248976 + outer loop + vertex 887.183 425.109 291.44 + vertex 884.396 431.386 288.02 + vertex 884.803 432.692 290.99 + endloop + endfacet + facet normal 0.92591 0.275181 -0.258778 + outer loop + vertex 887.183 425.109 291.44 + vertex 884.803 432.692 290.99 + vertex 886.265 429.538 292.867 + endloop + endfacet + facet normal 0.927836 0.27421 -0.252844 + outer loop + vertex 886.552 424.129 288.063 + vertex 884.396 431.386 288.02 + vertex 887.183 425.109 291.44 + endloop + endfacet + facet normal 0.930585 0.266395 -0.251088 + outer loop + vertex 889.28 417.648 291.298 + vertex 886.552 424.129 288.063 + vertex 887.183 425.109 291.44 + endloop + endfacet + facet normal 0.926201 0.265479 -0.267717 + outer loop + vertex 889.28 417.648 291.298 + vertex 887.183 425.109 291.44 + vertex 889.025 419.983 292.73 + endloop + endfacet + facet normal 0.930499 0.265983 -0.251841 + outer loop + vertex 888.6 416.963 288.06 + vertex 886.552 424.129 288.063 + vertex 889.28 417.648 291.298 + endloop + endfacet + facet normal 0.933779 0.255694 -0.250353 + outer loop + vertex 891.136 410.874 291.299 + vertex 888.6 416.963 288.06 + vertex 889.28 417.648 291.298 + endloop + endfacet + facet normal 0.929114 0.254414 -0.268366 + outer loop + vertex 891.136 410.874 291.299 + vertex 889.28 417.648 291.298 + vertex 890.957 413.005 292.701 + endloop + endfacet + facet normal 0.933494 0.254216 -0.252908 + outer loop + vertex 890.519 409.889 288.034 + vertex 888.6 416.963 288.06 + vertex 891.136 410.874 291.299 + endloop + endfacet + facet normal 0.937746 0.241302 -0.249812 + outer loop + vertex 892.94 403.887 291.324 + vertex 890.519 409.889 288.034 + vertex 891.136 410.874 291.299 + endloop + endfacet + facet normal 0.933598 0.240174 -0.265918 + outer loop + vertex 892.94 403.887 291.324 + vertex 891.136 410.874 291.299 + vertex 892.578 407.091 292.946 + endloop + endfacet + facet normal 0.935508 0.237972 -0.26114 + outer loop + vertex 892.578 407.091 292.946 + vertex 893.544 403.325 292.977 + vertex 892.94 403.887 291.324 + endloop + endfacet + facet normal 0.937255 0.225266 -0.2661 + outer loop + vertex 893.544 403.325 292.977 + vertex 894.404 399.705 292.94 + vertex 892.94 403.887 291.324 + endloop + endfacet + facet normal 0.936186 0.222593 -0.272046 + outer loop + vertex 894.716 396.405 291.313 + vertex 892.94 403.887 291.324 + vertex 894.404 399.705 292.94 + endloop + endfacet + facet normal 0.938346 0.220099 -0.266577 + outer loop + vertex 894.404 399.705 292.94 + vertex 895.305 395.842 292.923 + vertex 894.716 396.405 291.313 + endloop + endfacet + facet normal 0.940058 0.205105 -0.27244 + outer loop + vertex 895.305 395.842 292.923 + vertex 896.139 392.034 292.931 + vertex 894.716 396.405 291.313 + endloop + endfacet + facet normal 0.949684 0.207291 -0.234798 + outer loop + vertex 896.139 392.034 292.931 + vertex 895.305 395.842 292.923 + vertex 895.455 396.828 294.397 + endloop + endfacet + facet normal 0.944257 0.221375 -0.243664 + outer loop + vertex 895.305 395.842 292.923 + vertex 894.404 399.705 292.94 + vertex 895.455 396.828 294.397 + endloop + endfacet + facet normal 0.945461 0.226814 -0.233792 + outer loop + vertex 893.629 404.456 294.416 + vertex 895.455 396.828 294.397 + vertex 894.404 399.705 292.94 + endloop + endfacet + facet normal 0.942067 0.223954 -0.24971 + outer loop + vertex 894.716 396.405 291.313 + vertex 892.353 402.677 288.023 + vertex 892.94 403.887 291.324 + endloop + endfacet + facet normal 0.945388 0.226875 -0.234028 + outer loop + vertex 894.404 399.705 292.94 + vertex 893.544 403.325 292.977 + vertex 893.629 404.456 294.416 + endloop + endfacet + facet normal 0.93723 0.238668 -0.254239 + outer loop + vertex 892.353 402.677 288.023 + vertex 890.519 409.889 288.034 + vertex 892.94 403.887 291.324 + endloop + endfacet + facet normal 0.940459 0.239468 -0.24123 + outer loop + vertex 892.353 402.677 288.023 + vertex 889.44 409.62 283.559 + vertex 890.519 409.889 288.034 + endloop + endfacet + facet normal 0.936276 0.255383 -0.241177 + outer loop + vertex 889.44 409.62 283.559 + vertex 887.498 416.757 283.576 + vertex 890.519 409.889 288.034 + endloop + endfacet + facet normal 0.937864 0.255798 -0.234475 + outer loop + vertex 889.44 409.62 283.559 + vertex 886.068 416.784 277.89 + vertex 887.498 416.757 283.576 + endloop + endfacet + facet normal 0.934222 0.269651 -0.233492 + outer loop + vertex 886.068 416.784 277.89 + vertex 884.028 423.87 277.909 + vertex 887.498 416.757 283.576 + endloop + endfacet + facet normal 0.934186 0.268141 -0.235366 + outer loop + vertex 887.498 416.757 283.576 + vertex 884.028 423.87 277.909 + vertex 885.446 423.907 283.579 + endloop + endfacet + facet normal 0.932717 0.267722 -0.241588 + outer loop + vertex 887.498 416.757 283.576 + vertex 885.446 423.907 283.579 + vertex 888.6 416.963 288.06 + endloop + endfacet + facet normal 0.931128 0.27916 -0.234672 + outer loop + vertex 884.028 423.87 277.909 + vertex 881.91 430.943 277.919 + vertex 885.446 423.907 283.579 + endloop + endfacet + facet normal 0.931088 0.276469 -0.237992 + outer loop + vertex 885.446 423.907 283.579 + vertex 881.91 430.943 277.919 + vertex 883.333 431.047 283.605 + endloop + endfacet + facet normal 0.929875 0.276129 -0.243074 + outer loop + vertex 885.446 423.907 283.579 + vertex 883.333 431.047 283.605 + vertex 886.552 424.129 288.063 + endloop + endfacet + facet normal 0.927787 0.287863 -0.237374 + outer loop + vertex 881.91 430.943 277.919 + vertex 879.758 437.899 277.945 + vertex 883.333 431.047 283.605 + endloop + endfacet + facet normal 0.927779 0.285029 -0.2408 + outer loop + vertex 883.333 431.047 283.605 + vertex 879.758 437.899 277.945 + vertex 881.171 438.08 283.603 + endloop + endfacet + facet normal 0.926763 0.284715 -0.245047 + outer loop + vertex 883.333 431.047 283.605 + vertex 881.171 438.08 283.603 + vertex 884.396 431.386 288.02 + endloop + endfacet + facet normal 0.922027 0.303781 -0.239965 + outer loop + vertex 879.758 437.899 277.945 + vertex 877.551 444.598 277.945 + vertex 881.171 438.08 283.603 + endloop + endfacet + facet normal 0.922097 0.300592 -0.243682 + outer loop + vertex 881.171 438.08 283.603 + vertex 877.551 444.598 277.945 + vertex 878.943 444.928 283.619 + endloop + endfacet + facet normal 0.910794 0.333886 -0.242846 + outer loop + vertex 877.551 444.598 277.945 + vertex 875.218 450.972 277.956 + vertex 878.943 444.928 283.619 + endloop + endfacet + facet normal 0.91146 0.334124 -0.240004 + outer loop + vertex 877.551 444.598 277.945 + vertex 873.67 450.43 271.323 + vertex 875.218 450.972 277.956 + endloop + endfacet + facet normal 0.892979 0.381069 -0.239529 + outer loop + vertex 873.67 450.43 271.323 + vertex 871.205 456.225 271.353 + vertex 875.218 450.972 277.956 + endloop + endfacet + facet normal 0.894499 0.372422 -0.247331 + outer loop + vertex 875.218 450.972 277.956 + vertex 871.205 456.225 271.353 + vertex 872.697 457.069 278.018 + endloop + endfacet + facet normal 0.894226 0.372321 -0.248469 + outer loop + vertex 875.218 450.972 277.956 + vertex 872.697 457.069 278.018 + vertex 876.54 451.584 283.631 + endloop + endfacet + facet normal 0.89376 0.381383 -0.236091 + outer loop + vertex 873.67 450.43 271.323 + vertex 869.666 455.372 264.15 + vertex 871.205 456.225 271.353 + endloop + endfacet + facet normal 0.891938 0.389663 -0.229369 + outer loop + vertex 872.114 449.789 264.184 + vertex 869.666 455.372 264.15 + vertex 873.67 450.43 271.323 + endloop + endfacet + facet normal 0.912032 0.34003 -0.229298 + outer loop + vertex 875.985 444.236 271.348 + vertex 872.114 449.789 264.184 + vertex 873.67 450.43 271.323 + endloop + endfacet + facet normal 0.911341 0.344336 -0.225587 + outer loop + vertex 874.423 443.717 264.245 + vertex 872.114 449.789 264.184 + vertex 875.985 444.236 271.348 + endloop + endfacet + facet normal 0.924082 0.308393 -0.225758 + outer loop + vertex 878.193 437.627 271.358 + vertex 874.423 443.717 264.245 + vertex 875.985 444.236 271.348 + endloop + endfacet + facet normal 0.922703 0.307923 -0.231956 + outer loop + vertex 878.193 437.627 271.358 + vertex 875.985 444.236 271.348 + vertex 879.758 437.899 277.945 + endloop + endfacet + facet normal 0.923568 0.312885 -0.221641 + outer loop + vertex 876.633 437.224 264.288 + vertex 874.423 443.717 264.245 + vertex 878.193 437.627 271.358 + endloop + endfacet + facet normal 0.930185 0.292405 -0.221933 + outer loop + vertex 880.351 430.768 271.363 + vertex 876.633 437.224 264.288 + vertex 878.193 437.627 271.358 + endloop + endfacet + facet normal 0.928697 0.291932 -0.228687 + outer loop + vertex 880.351 430.768 271.363 + vertex 878.193 437.627 271.358 + vertex 881.91 430.943 277.919 + endloop + endfacet + facet normal 0.9299 0.295615 -0.218854 + outer loop + vertex 878.779 430.495 264.317 + vertex 876.633 437.224 264.288 + vertex 880.351 430.768 271.363 + endloop + endfacet + facet normal 0.933928 0.282335 -0.219238 + outer loop + vertex 882.454 423.807 271.358 + vertex 878.779 430.495 264.317 + vertex 880.351 430.768 271.363 + endloop + endfacet + facet normal 0.932284 0.281843 -0.226739 + outer loop + vertex 882.454 423.807 271.358 + vertex 880.351 430.768 271.363 + vertex 884.028 423.87 277.909 + endloop + endfacet + facet normal 0.933799 0.284126 -0.217469 + outer loop + vertex 880.857 423.674 264.329 + vertex 878.779 430.495 264.317 + vertex 882.454 423.807 271.358 + endloop + endfacet + facet normal 0.937324 0.271814 -0.218037 + outer loop + vertex 884.472 416.839 271.348 + vertex 880.857 423.674 264.329 + vertex 882.454 423.807 271.358 + endloop + endfacet + facet normal 0.935575 0.271319 -0.226022 + outer loop + vertex 884.472 416.839 271.348 + vertex 882.454 423.807 271.358 + vertex 886.068 416.784 277.89 + endloop + endfacet + facet normal 0.93933 0.257106 -0.227058 + outer loop + vertex 887.997 409.724 277.876 + vertex 884.472 416.839 271.348 + vertex 886.068 416.784 277.89 + endloop + endfacet + facet normal 0.939322 0.257885 -0.226205 + outer loop + vertex 886.375 409.897 271.337 + vertex 884.472 416.839 271.348 + vertex 887.997 409.724 277.876 + endloop + endfacet + facet normal 0.943479 0.240846 -0.227686 + outer loop + vertex 889.798 402.669 277.875 + vertex 886.375 409.897 271.337 + vertex 887.997 409.724 277.876 + endloop + endfacet + facet normal 0.942138 0.240505 -0.233522 + outer loop + vertex 889.798 402.669 277.875 + vertex 887.997 409.724 277.876 + vertex 891.263 402.438 283.547 + endloop + endfacet + facet normal 0.94637 0.221293 -0.235398 + outer loop + vertex 892.965 395.172 283.558 + vertex 889.798 402.669 277.875 + vertex 891.263 402.438 283.547 + endloop + endfacet + facet normal 0.944814 0.220919 -0.241912 + outer loop + vertex 892.965 395.172 283.558 + vertex 891.263 402.438 283.547 + vertex 894.111 395.179 288.042 + endloop + endfacet + facet normal 0.944826 0.220996 -0.241794 + outer loop + vertex 894.111 395.179 288.042 + vertex 891.263 402.438 283.547 + vertex 892.353 402.677 288.023 + endloop + endfacet + facet normal 0.946443 0.222189 -0.234258 + outer loop + vertex 891.463 395.578 277.875 + vertex 889.798 402.669 277.875 + vertex 892.965 395.172 283.558 + endloop + endfacet + facet normal 0.950408 0.201652 -0.236772 + outer loop + vertex 894.522 387.846 283.57 + vertex 891.463 395.578 277.875 + vertex 892.965 395.172 283.558 + endloop + endfacet + facet normal 0.94885 0.201311 -0.243225 + outer loop + vertex 894.522 387.846 283.57 + vertex 892.965 395.172 283.558 + vertex 895.736 387.555 288.064 + endloop + endfacet + facet normal 0.950553 0.202977 -0.235051 + outer loop + vertex 892.995 388.425 277.893 + vertex 891.463 395.578 277.875 + vertex 894.522 387.846 283.57 + endloop + endfacet + facet normal 0.95427 0.18044 -0.23835 + outer loop + vertex 895.915 380.483 283.571 + vertex 892.995 388.425 277.893 + vertex 894.522 387.846 283.57 + endloop + endfacet + facet normal 0.952442 0.180093 -0.245808 + outer loop + vertex 895.915 380.483 283.571 + vertex 894.522 387.846 283.57 + vertex 897.162 380.014 288.06 + endloop + endfacet + facet normal 0.954419 0.181504 -0.236939 + outer loop + vertex 894.37 381.191 277.892 + vertex 892.995 388.425 277.893 + vertex 895.915 380.483 283.571 + endloop + endfacet + facet normal 0.957806 0.156676 -0.240958 + outer loop + vertex 897.131 373.059 283.577 + vertex 894.37 381.191 277.892 + vertex 895.915 380.483 283.571 + endloop + endfacet + facet normal 0.955705 0.156325 -0.249379 + outer loop + vertex 897.131 373.059 283.577 + vertex 895.915 380.483 283.571 + vertex 898.397 372.469 288.059 + endloop + endfacet + facet normal 0.957963 0.157584 -0.239736 + outer loop + vertex 895.577 373.856 277.892 + vertex 894.37 381.191 277.892 + vertex 897.131 373.059 283.577 + endloop + endfacet + facet normal 0.961035 0.128742 -0.244618 + outer loop + vertex 898.139 365.533 283.578 + vertex 895.577 373.856 277.892 + vertex 897.131 373.059 283.577 + endloop + endfacet + facet normal 0.95852 0.128403 -0.254466 + outer loop + vertex 898.139 365.533 283.578 + vertex 897.131 373.059 283.577 + vertex 899.415 364.88 288.055 + endloop + endfacet + facet normal 0.961236 0.12969 -0.243322 + outer loop + vertex 896.583 366.385 277.885 + vertex 895.577 373.856 277.892 + vertex 898.139 365.533 283.578 + endloop + endfacet + facet normal 0.963641 0.0974232 -0.248807 + outer loop + vertex 898.914 357.887 283.586 + vertex 896.583 366.385 277.885 + vertex 898.139 365.533 283.578 + endloop + endfacet + facet normal 0.960893 0.0971335 -0.259324 + outer loop + vertex 898.914 357.887 283.586 + vertex 898.139 365.533 283.578 + vertex 900.191 357.208 288.064 + endloop + endfacet + facet normal 0.964044 0.0990084 -0.246609 + outer loop + vertex 897.364 358.796 277.891 + vertex 896.583 366.385 277.885 + vertex 898.914 357.887 283.586 + endloop + endfacet + facet normal 0.96548 0.0629814 -0.252748 + outer loop + vertex 899.421 350.174 283.6 + vertex 897.364 358.796 277.891 + vertex 898.914 357.887 283.586 + endloop + endfacet + facet normal 0.962437 0.0627605 -0.264152 + outer loop + vertex 899.421 350.174 283.6 + vertex 898.914 357.887 283.586 + vertex 900.697 349.476 288.081 + endloop + endfacet + facet normal 0.965911 0.0644215 -0.250729 + outer loop + vertex 897.874 351.151 277.892 + vertex 897.364 358.796 277.891 + vertex 899.421 350.174 283.6 + endloop + endfacet + facet normal 0.965928 0.0234105 -0.25775 + outer loop + vertex 899.608 342.497 283.603 + vertex 897.874 351.151 277.892 + vertex 899.421 350.174 283.6 + endloop + endfacet + facet normal 0.967717 0.0645428 -0.243636 + outer loop + vertex 897.874 351.151 277.892 + vertex 895.654 359.674 271.331 + vertex 897.364 358.796 277.891 + endloop + endfacet + facet normal 0.965958 0.100568 -0.238351 + outer loop + vertex 895.654 359.674 271.331 + vertex 894.874 367.165 271.331 + vertex 897.364 358.796 277.891 + endloop + endfacet + facet normal 0.967894 0.10077 -0.230276 + outer loop + vertex 895.654 359.674 271.331 + vertex 893.131 367.844 264.3 + vertex 894.874 367.165 271.331 + endloop + endfacet + facet normal 0.964972 0.132385 -0.226501 + outer loop + vertex 893.131 367.844 264.3 + vertex 892.132 375.118 264.297 + vertex 894.874 367.165 271.331 + endloop + endfacet + facet normal 0.964859 0.131426 -0.227541 + outer loop + vertex 894.874 367.165 271.331 + vertex 892.132 375.118 264.297 + vertex 893.868 374.548 271.331 + endloop + endfacet + facet normal 0.962981 0.13117 -0.235503 + outer loop + vertex 894.874 367.165 271.331 + vertex 893.868 374.548 271.331 + vertex 896.583 366.385 277.885 + endloop + endfacet + facet normal 0.961364 0.159429 -0.224412 + outer loop + vertex 892.132 375.118 264.297 + vertex 890.945 382.274 264.296 + vertex 893.868 374.548 271.331 + endloop + endfacet + facet normal 0.961302 0.158685 -0.225204 + outer loop + vertex 893.868 374.548 271.331 + vertex 890.945 382.274 264.296 + vertex 892.672 381.806 271.338 + endloop + endfacet + facet normal 0.959457 0.158389 -0.233141 + outer loop + vertex 893.868 374.548 271.331 + vertex 892.672 381.806 271.338 + vertex 895.577 373.856 277.892 + endloop + endfacet + facet normal 0.957498 0.183393 -0.222631 + outer loop + vertex 890.945 382.274 264.296 + vertex 889.596 389.322 264.298 + vertex 892.672 381.806 271.338 + endloop + endfacet + facet normal 0.957492 0.183275 -0.222754 + outer loop + vertex 892.672 381.806 271.338 + vertex 889.596 389.322 264.298 + vertex 891.305 388.939 271.33 + endloop + endfacet + facet normal 0.955724 0.182928 -0.230497 + outer loop + vertex 892.672 381.806 271.338 + vertex 891.305 388.939 271.33 + vertex 894.37 381.191 277.892 + endloop + endfacet + facet normal 0.953577 0.204982 -0.220621 + outer loop + vertex 889.596 389.322 264.298 + vertex 888.101 396.274 264.297 + vertex 891.305 388.939 271.33 + endloop + endfacet + facet normal 0.953557 0.204194 -0.221435 + outer loop + vertex 891.305 388.939 271.33 + vertex 888.101 396.274 264.297 + vertex 889.797 395.987 271.334 + endloop + endfacet + facet normal 0.951812 0.203824 -0.229151 + outer loop + vertex 891.305 388.939 271.33 + vertex 889.797 395.987 271.334 + vertex 892.995 388.425 277.893 + endloop + endfacet + facet normal 0.949427 0.224404 -0.219615 + outer loop + vertex 888.101 396.274 264.297 + vertex 886.475 403.16 264.305 + vertex 889.797 395.987 271.334 + endloop + endfacet + facet normal 0.949427 0.224008 -0.22002 + outer loop + vertex 889.797 395.987 271.334 + vertex 886.475 403.16 264.305 + vertex 888.151 402.959 271.33 + endloop + endfacet + facet normal 0.947758 0.22361 -0.227495 + outer loop + vertex 889.797 395.987 271.334 + vertex 888.151 402.959 271.33 + vertex 891.463 395.578 277.875 + endloop + endfacet + facet normal 0.945231 0.242487 -0.218492 + outer loop + vertex 886.475 403.16 264.305 + vertex 884.722 410.005 264.319 + vertex 888.151 402.959 271.33 + endloop + endfacet + facet normal 0.94524 0.242071 -0.218915 + outer loop + vertex 888.151 402.959 271.33 + vertex 884.722 410.005 264.319 + vertex 886.375 409.897 271.337 + endloop + endfacet + facet normal 0.941084 0.258797 -0.217679 + outer loop + vertex 884.722 410.005 264.319 + vertex 882.846 416.838 264.33 + vertex 886.375 409.897 271.337 + endloop + endfacet + facet normal 0.943295 0.259388 -0.207154 + outer loop + vertex 884.722 410.005 264.319 + vertex 881.264 416.788 257.062 + vertex 882.846 416.838 264.33 + endloop + endfacet + facet normal 0.939402 0.273717 -0.206405 + outer loop + vertex 881.264 416.788 257.062 + vertex 879.303 423.505 257.048 + vertex 882.846 416.838 264.33 + endloop + endfacet + facet normal 0.93944 0.273241 -0.20686 + outer loop + vertex 882.846 416.838 264.33 + vertex 879.303 423.505 257.048 + vertex 880.857 423.674 264.329 + endloop + endfacet + facet normal 0.935721 0.286077 -0.206364 + outer loop + vertex 879.303 423.505 257.048 + vertex 877.254 430.184 257.013 + vertex 880.857 423.674 264.329 + endloop + endfacet + facet normal 0.938037 0.28685 -0.19443 + outer loop + vertex 879.303 423.505 257.048 + vertex 875.797 429.892 249.553 + vertex 877.254 430.184 257.013 + endloop + endfacet + facet normal 0.933267 0.302224 -0.194099 + outer loop + vertex 875.797 429.892 249.553 + vertex 873.698 436.344 249.51 + vertex 877.254 430.184 257.013 + endloop + endfacet + facet normal 0.933607 0.299744 -0.196296 + outer loop + vertex 877.254 430.184 257.013 + vertex 873.698 436.344 249.51 + vertex 875.13 436.774 256.975 + endloop + endfacet + facet normal 0.93147 0.298993 -0.207283 + outer loop + vertex 877.254 430.184 257.013 + vertex 875.13 436.774 256.975 + vertex 878.779 430.495 264.317 + endloop + endfacet + facet normal 0.926135 0.322174 -0.196156 + outer loop + vertex 873.698 436.344 249.51 + vertex 871.521 442.605 249.513 + vertex 875.13 436.774 256.975 + endloop + endfacet + facet normal 0.926764 0.318297 -0.19949 + outer loop + vertex 875.13 436.774 256.975 + vertex 871.521 442.605 249.513 + vertex 872.937 443.139 256.942 + endloop + endfacet + facet normal 0.924772 0.317558 -0.209651 + outer loop + vertex 875.13 436.774 256.975 + vertex 872.937 443.139 256.942 + vertex 876.633 437.224 264.288 + endloop + endfacet + facet normal 0.913944 0.353384 -0.199566 + outer loop + vertex 871.521 442.605 249.513 + vertex 869.286 448.44 249.611 + vertex 872.937 443.139 256.942 + endloop + endfacet + facet normal 0.914765 0.349337 -0.202901 + outer loop + vertex 872.937 443.139 256.942 + vertex 869.286 448.44 249.611 + vertex 870.658 449.085 256.908 + endloop + endfacet + facet normal 0.912706 0.348488 -0.213362 + outer loop + vertex 872.937 443.139 256.942 + vertex 870.658 449.085 256.908 + vertex 874.423 443.717 264.245 + endloop + endfacet + facet normal 0.892987 0.401494 -0.203414 + outer loop + vertex 869.286 448.44 249.611 + vertex 867.014 453.577 249.777 + vertex 870.658 449.085 256.908 + endloop + endfacet + facet normal 0.89387 0.398241 -0.205914 + outer loop + vertex 870.658 449.085 256.908 + vertex 867.014 453.577 249.777 + vertex 868.256 454.454 256.865 + endloop + endfacet + facet normal 0.891751 0.397204 -0.216817 + outer loop + vertex 870.658 449.085 256.908 + vertex 868.256 454.454 256.865 + vertex 872.114 449.789 264.184 + endloop + endfacet + facet normal 0.895307 0.40214 -0.191597 + outer loop + vertex 869.286 448.44 249.611 + vertex 865.754 453.028 242.734 + vertex 867.014 453.577 249.777 + endloop + endfacet + facet normal 0.894436 0.405263 -0.189067 + outer loop + vertex 867.917 447.968 242.122 + vertex 865.754 453.028 242.734 + vertex 869.286 448.44 249.611 + endloop + endfacet + facet normal 0.896186 0.405045 -0.18108 + outer loop + vertex 867.917 447.968 242.122 + vertex 863.977 453.261 234.46 + vertex 865.754 453.028 242.734 + endloop + endfacet + facet normal 0.892674 0.416997 -0.171019 + outer loop + vertex 866.81 447.322 234.765 + vertex 863.977 453.261 234.46 + vertex 867.917 447.968 242.122 + endloop + endfacet + facet normal 0.896384 0.420316 -0.140821 + outer loop + vertex 866.81 447.322 234.765 + vertex 863.922 451.316 228.304 + vertex 863.977 453.261 234.46 + endloop + endfacet + facet normal 0.901559 0.404806 -0.152722 + outer loop + vertex 865.883 446.737 227.744 + vertex 863.922 451.316 228.304 + vertex 866.81 447.322 234.765 + endloop + endfacet + facet normal 0.903711 0.404285 -0.140929 + outer loop + vertex 863.922 451.316 228.304 + vertex 865.883 446.737 227.744 + vertex 863.251 450.828 222.604 + endloop + endfacet + facet normal 0.90239 0.408632 -0.136793 + outer loop + vertex 865.883 446.737 227.744 + vertex 864.547 447.124 220.091 + vertex 863.251 450.828 222.604 + endloop + endfacet + facet normal 0.902422 0.408588 -0.136712 + outer loop + vertex 862.349 451.3 218.064 + vertex 863.251 450.828 222.604 + vertex 864.547 447.124 220.091 + endloop + endfacet + facet normal 0.901345 0.416163 -0.119942 + outer loop + vertex 862.349 451.3 218.064 + vertex 864.547 447.124 220.091 + vertex 862.164 450.641 214.379 + endloop + endfacet + facet normal 0.900245 0.419195 -0.117616 + outer loop + vertex 864.547 447.124 220.091 + vertex 863.626 446.922 212.315 + vertex 862.164 450.641 214.379 + endloop + endfacet + facet normal 0.901829 0.417122 -0.11276 + outer loop + vertex 861.506 450.951 210.264 + vertex 862.164 450.641 214.379 + vertex 863.626 446.922 212.315 + endloop + endfacet + facet normal 0.900064 0.425312 -0.0948408 + outer loop + vertex 861.506 450.951 210.264 + vertex 863.626 446.922 212.315 + vertex 861.443 450.267 206.607 + endloop + endfacet + facet normal 0.900919 0.423136 -0.0964431 + outer loop + vertex 863.626 446.922 212.315 + vertex 862.935 446.606 204.471 + vertex 861.443 450.267 206.607 + endloop + endfacet + facet normal 0.902848 0.420362 -0.0903386 + outer loop + vertex 860.877 450.581 202.402 + vertex 861.443 450.267 206.607 + vertex 862.935 446.606 204.471 + endloop + endfacet + facet normal 0.900967 0.427348 -0.0750484 + outer loop + vertex 860.877 450.581 202.402 + vertex 862.935 446.606 204.471 + vertex 860.865 449.95 198.669 + endloop + endfacet + facet normal 0.901262 0.426634 -0.0755655 + outer loop + vertex 862.935 446.606 204.471 + vertex 862.383 446.361 196.515 + vertex 860.865 449.95 198.669 + endloop + endfacet + facet normal 0.902773 0.424285 -0.0705881 + outer loop + vertex 860.361 450.316 194.417 + vertex 860.865 449.95 198.669 + vertex 862.383 446.361 196.515 + endloop + endfacet + facet normal 0.900303 0.431926 -0.0538001 + outer loop + vertex 860.361 450.316 194.417 + vertex 862.383 446.361 196.515 + vertex 860.411 449.743 190.673 + endloop + endfacet + facet normal 0.901527 0.429103 -0.0558482 + outer loop + vertex 862.383 446.361 196.515 + vertex 861.964 446.2 188.514 + vertex 860.411 449.743 190.673 + endloop + endfacet + facet normal 0.903142 0.426392 -0.0502414 + outer loop + vertex 859.981 450.152 186.408 + vertex 860.411 449.743 190.673 + vertex 861.964 446.2 188.514 + endloop + endfacet + facet normal 0.900345 0.43388 -0.033559 + outer loop + vertex 859.981 450.152 186.408 + vertex 861.964 446.2 188.514 + vertex 860.097 449.621 182.655 + endloop + endfacet + facet normal 0.9021 0.42999 -0.0363889 + outer loop + vertex 861.964 446.2 188.514 + vertex 861.682 446.115 180.523 + vertex 860.097 449.621 182.655 + endloop + endfacet + facet normal 0.903733 0.427024 -0.0302975 + outer loop + vertex 859.741 450.073 178.398 + vertex 860.097 449.621 182.655 + vertex 861.682 446.115 180.523 + endloop + endfacet + facet normal 0.900777 0.434039 -0.014533 + outer loop + vertex 859.741 450.073 178.398 + vertex 861.682 446.115 180.523 + vertex 859.919 449.58 174.698 + endloop + endfacet + facet normal 0.903043 0.429168 -0.0181155 + outer loop + vertex 861.682 446.115 180.523 + vertex 861.533 446.096 172.635 + vertex 859.919 449.58 174.698 + endloop + endfacet + facet normal 0.904532 0.426238 -0.0119992 + outer loop + vertex 859.631 450.073 170.53 + vertex 859.919 449.58 174.698 + vertex 861.533 446.096 172.635 + endloop + endfacet + facet normal 0.901378 0.433017 0.00365642 + outer loop + vertex 859.631 450.073 170.53 + vertex 861.533 446.096 172.635 + vertex 859.866 449.614 166.925 + endloop + endfacet + facet normal 0.903601 0.428375 0.000147046 + outer loop + vertex 861.533 446.096 172.635 + vertex 861.509 446.15 164.867 + vertex 859.866 449.614 166.925 + endloop + endfacet + facet normal 0.90501 0.425342 0.00637948 + outer loop + vertex 859.642 450.153 162.835 + vertex 859.866 449.614 166.925 + vertex 861.509 446.15 164.867 + endloop + endfacet + facet normal 0.901854 0.431508 0.0214251 + outer loop + vertex 859.642 450.153 162.835 + vertex 861.509 446.15 164.867 + vertex 859.925 449.74 159.227 + endloop + endfacet + facet normal 0.90375 0.427663 0.0184448 + outer loop + vertex 861.509 446.15 164.867 + vertex 861.604 446.286 157.078 + vertex 859.925 449.74 159.227 + endloop + endfacet + facet normal 0.905337 0.423914 0.0257063 + outer loop + vertex 859.758 450.347 155.085 + vertex 859.925 449.74 159.227 + vertex 861.604 446.286 157.078 + endloop + endfacet + facet normal 0.901619 0.430442 0.0424552 + outer loop + vertex 859.758 450.347 155.085 + vertex 861.604 446.286 157.078 + vertex 860.11 449.98 151.338 + endloop + endfacet + facet normal 0.904052 0.425662 0.0387458 + outer loop + vertex 861.604 446.286 157.078 + vertex 861.842 446.507 149.08 + vertex 860.11 449.98 151.338 + endloop + endfacet + facet normal 0.905991 0.420557 0.0480835 + outer loop + vertex 860.048 450.608 147.018 + vertex 860.11 449.98 151.338 + vertex 861.842 446.507 149.08 + endloop + endfacet + facet normal 0.902736 0.425799 0.0613438 + outer loop + vertex 860.048 450.608 147.018 + vertex 861.842 446.507 149.08 + vertex 860.513 450.174 143.182 + endloop + endfacet + facet normal 0.907985 0.415537 0.0537794 + outer loop + vertex 861.842 446.507 149.08 + vertex 862.153 446.89 140.869 + vertex 860.513 450.174 143.182 + endloop + endfacet + facet normal 0.909571 0.410995 0.061355 + outer loop + vertex 860.571 450.625 139.315 + vertex 860.513 450.174 143.182 + vertex 862.153 446.89 140.869 + endloop + endfacet + facet normal 0.913173 0.405213 0.043795 + outer loop + vertex 862.153 446.89 140.869 + vertex 860.144 452.155 134.041 + vertex 860.571 450.625 139.315 + endloop + endfacet + facet normal 0.900241 0.430223 0.0668856 + outer loop + vertex 862.798 446.808 132.711 + vertex 860.144 452.155 134.041 + vertex 862.153 446.89 140.869 + endloop + endfacet + facet normal 0.924015 0.376023 0.0693067 + outer loop + vertex 864.651 440.885 140.15 + vertex 862.798 446.808 132.711 + vertex 862.153 446.89 140.869 + endloop + endfacet + facet normal 0.924248 0.377938 0.0541147 + outer loop + vertex 864.651 440.885 140.15 + vertex 862.153 446.89 140.869 + vertex 864.247 440.721 148.2 + endloop + endfacet + facet normal 0.937771 0.343016 0.0540832 + outer loop + vertex 866.43 434.81 147.836 + vertex 864.651 440.885 140.15 + vertex 864.247 440.721 148.2 + endloop + endfacet + facet normal 0.938173 0.344255 0.036333 + outer loop + vertex 866.43 434.81 147.836 + vertex 864.247 440.721 148.2 + vertex 866.171 434.68 155.731 + endloop + endfacet + facet normal 0.947365 0.318103 0.0362029 + outer loop + vertex 868.16 428.765 155.678 + vertex 866.43 434.81 147.836 + vertex 866.171 434.68 155.731 + endloop + endfacet + facet normal 0.947781 0.318404 0.0181531 + outer loop + vertex 868.16 428.765 155.678 + vertex 866.171 434.68 155.731 + vertex 868.032 428.699 163.486 + endloop + endfacet + facet normal 0.954046 0.299114 0.0180924 + outer loop + vertex 869.903 422.727 163.579 + vertex 868.16 428.765 155.678 + vertex 868.032 428.699 163.486 + endloop + endfacet + facet normal 0.954279 0.298915 0.000691041 + outer loop + vertex 869.903 422.727 163.579 + vertex 868.032 428.699 163.486 + vertex 869.903 422.708 171.388 + endloop + endfacet + facet normal 0.958909 0.283713 0.000652158 + outer loop + vertex 871.695 416.651 171.474 + vertex 869.903 422.727 163.579 + vertex 869.903 422.708 171.388 + endloop + endfacet + facet normal 0.958847 0.283453 -0.0163318 + outer loop + vertex 871.695 416.651 171.474 + vertex 869.903 422.708 171.388 + vertex 871.83 416.649 179.346 + endloop + endfacet + facet normal 0.962997 0.269013 -0.0164079 + outer loop + vertex 873.545 410.512 179.367 + vertex 871.695 416.651 171.474 + vertex 871.83 416.649 179.346 + endloop + endfacet + facet normal 0.962599 0.268844 -0.0335689 + outer loop + vertex 873.545 410.512 179.367 + vertex 871.83 416.649 179.346 + vertex 873.825 410.499 187.314 + endloop + endfacet + facet normal 0.966901 0.252911 -0.0337469 + outer loop + vertex 875.447 404.296 187.291 + vertex 873.545 410.512 179.367 + vertex 873.825 410.499 187.314 + endloop + endfacet + facet normal 0.966148 0.252781 -0.0515819 + outer loop + vertex 875.447 404.296 187.291 + vertex 873.825 410.499 187.314 + vertex 875.885 404.251 195.28 + endloop + endfacet + facet normal 0.970688 0.234664 -0.0519342 + outer loop + vertex 877.401 397.976 195.255 + vertex 875.447 404.296 187.291 + vertex 875.885 404.251 195.28 + endloop + endfacet + facet normal 0.969557 0.234465 -0.0706101 + outer loop + vertex 877.401 397.976 195.255 + vertex 875.885 404.251 195.28 + vertex 878.006 397.879 203.232 + endloop + endfacet + facet normal 0.97413 0.214477 -0.0711998 + outer loop + vertex 879.407 391.51 203.224 + vertex 877.401 397.976 195.255 + vertex 878.006 397.879 203.232 + endloop + endfacet + facet normal 0.972572 0.214161 -0.0907647 + outer loop + vertex 879.407 391.51 203.224 + vertex 878.006 397.879 203.232 + vertex 880.184 391.338 211.144 + endloop + endfacet + facet normal 0.977009 0.192482 -0.0916706 + outer loop + vertex 881.465 384.84 211.147 + vertex 879.407 391.51 203.224 + vertex 880.184 391.338 211.144 + endloop + endfacet + facet normal 0.975043 0.192085 -0.111332 + outer loop + vertex 881.465 384.84 211.147 + vertex 880.184 391.338 211.144 + vertex 882.412 384.576 218.991 + endloop + endfacet + facet normal 0.97935 0.167868 -0.112668 + outer loop + vertex 883.555 377.91 218.995 + vertex 881.465 384.84 211.147 + vertex 882.412 384.576 218.991 + endloop + endfacet + facet normal 0.97704 0.167461 -0.131722 + outer loop + vertex 883.555 377.91 218.995 + vertex 882.412 384.576 218.991 + vertex 884.666 377.539 226.764 + endloop + endfacet + facet normal 0.981085 0.140071 -0.133612 + outer loop + vertex 885.644 370.69 226.766 + vertex 883.555 377.91 218.995 + vertex 884.666 377.539 226.764 + endloop + endfacet + facet normal 0.978573 0.139707 -0.151253 + outer loop + vertex 885.644 370.69 226.766 + vertex 884.666 377.539 226.764 + vertex 886.905 370.194 234.465 + endloop + endfacet + facet normal 0.982082 0.108883 -0.153815 + outer loop + vertex 887.684 363.174 234.466 + vertex 885.644 370.69 226.766 + vertex 886.905 370.194 234.465 + endloop + endfacet + facet normal 0.97948 0.108592 -0.169782 + outer loop + vertex 887.684 363.174 234.466 + vertex 886.905 370.194 234.465 + vertex 889.075 362.547 242.089 + endloop + endfacet + facet normal 0.98214 0.0736587 -0.173137 + outer loop + vertex 889.611 355.402 242.09 + vertex 887.684 363.174 234.466 + vertex 889.075 362.547 242.089 + endloop + endfacet + facet normal 0.979326 0.073446 -0.188485 + outer loop + vertex 889.611 355.402 242.09 + vertex 889.075 362.547 242.089 + vertex 891.116 354.657 249.62 + endloop + endfacet + facet normal 0.980699 0.0324007 -0.192819 + outer loop + vertex 891.354 347.445 249.619 + vertex 889.611 355.402 242.09 + vertex 891.116 354.657 249.62 + endloop + endfacet + facet normal 0.979111 0.071688 -0.190269 + outer loop + vertex 891.116 354.657 249.62 + vertex 889.075 362.547 242.089 + vertex 890.586 361.885 249.618 + endloop + endfacet + facet normal 0.976262 0.0714763 -0.20446 + outer loop + vertex 891.116 354.657 249.62 + vertex 890.586 361.885 249.618 + vertex 892.725 353.877 257.031 + endloop + endfacet + facet normal 0.977432 0.0307542 -0.209 + outer loop + vertex 892.955 346.581 257.033 + vertex 891.116 354.657 249.62 + vertex 892.725 353.877 257.031 + endloop + endfacet + facet normal 0.975988 0.0696017 -0.206406 + outer loop + vertex 892.725 353.877 257.031 + vertex 890.586 361.885 249.618 + vertex 892.203 361.194 257.031 + endloop + endfacet + facet normal 0.972981 0.0693861 -0.220212 + outer loop + vertex 892.725 353.877 257.031 + vertex 892.203 361.194 257.031 + vertex 894.43 353.051 264.304 + endloop + endfacet + facet normal 0.973924 0.0281045 -0.225125 + outer loop + vertex 894.642 345.657 264.299 + vertex 892.725 353.877 257.031 + vertex 894.43 353.051 264.304 + endloop + endfacet + facet normal 0.972812 0.0684003 -0.221264 + outer loop + vertex 894.43 353.051 264.304 + vertex 892.203 361.194 257.031 + vertex 893.908 360.468 264.301 + endloop + endfacet + facet normal 0.970409 0.0682269 -0.231628 + outer loop + vertex 894.43 353.051 264.304 + vertex 893.908 360.468 264.301 + vertex 896.172 352.141 271.335 + endloop + endfacet + facet normal 0.971101 0.0267549 -0.237165 + outer loop + vertex 896.378 344.643 271.331 + vertex 894.43 353.051 264.304 + vertex 896.172 352.141 271.335 + endloop + endfacet + facet normal 0.970087 0.0666072 -0.233442 + outer loop + vertex 896.172 352.141 271.335 + vertex 893.908 360.468 264.301 + vertex 895.654 359.674 271.331 + endloop + endfacet + facet normal 0.970637 0.103216 -0.217278 + outer loop + vertex 892.203 361.194 257.031 + vertex 891.43 368.464 257.029 + vertex 893.908 360.468 264.301 + endloop + endfacet + facet normal 0.970508 0.102226 -0.218322 + outer loop + vertex 893.908 360.468 264.301 + vertex 891.43 368.464 257.029 + vertex 893.131 367.844 264.3 + endloop + endfacet + facet normal 0.967485 0.133276 -0.214965 + outer loop + vertex 891.43 368.464 257.029 + vertex 890.442 375.636 257.028 + vertex 893.131 367.844 264.3 + endloop + endfacet + facet normal 0.970287 0.133664 -0.201687 + outer loop + vertex 891.43 368.464 257.029 + vertex 888.831 376.141 249.615 + vertex 890.442 375.636 257.028 + endloop + endfacet + facet normal 0.966608 0.161466 -0.198992 + outer loop + vertex 888.831 376.141 249.615 + vertex 887.668 383.101 249.612 + vertex 890.442 375.636 257.028 + endloop + endfacet + facet normal 0.966589 0.160958 -0.199496 + outer loop + vertex 890.442 375.636 257.028 + vertex 887.668 383.101 249.612 + vertex 889.267 382.686 257.024 + endloop + endfacet + facet normal 0.963842 0.160492 -0.212721 + outer loop + vertex 890.442 375.636 257.028 + vertex 889.267 382.686 257.024 + vertex 892.132 375.118 264.297 + endloop + endfacet + facet normal 0.962646 0.185463 -0.197273 + outer loop + vertex 887.668 383.101 249.612 + vertex 886.347 389.954 249.61 + vertex 889.267 382.686 257.024 + endloop + endfacet + facet normal 0.962641 0.184887 -0.197837 + outer loop + vertex 889.267 382.686 257.024 + vertex 886.347 389.954 249.61 + vertex 887.932 389.634 257.022 + endloop + endfacet + facet normal 0.959921 0.184361 -0.211101 + outer loop + vertex 889.267 382.686 257.024 + vertex 887.932 389.634 257.022 + vertex 890.945 382.274 264.296 + endloop + endfacet + facet normal 0.958507 0.207003 -0.195997 + outer loop + vertex 886.347 389.954 249.61 + vertex 884.887 396.72 249.614 + vertex 887.932 389.634 257.022 + endloop + endfacet + facet normal 0.95852 0.206274 -0.196699 + outer loop + vertex 887.932 389.634 257.022 + vertex 884.887 396.72 249.614 + vertex 886.456 396.497 257.027 + endloop + endfacet + facet normal 0.955869 0.205714 -0.209752 + outer loop + vertex 887.932 389.634 257.022 + vertex 886.456 396.497 257.027 + vertex 889.596 389.322 264.298 + endloop + endfacet + facet normal 0.954255 0.226494 -0.195189 + outer loop + vertex 884.887 396.72 249.614 + vertex 883.298 403.428 249.63 + vertex 886.456 396.497 257.027 + endloop + endfacet + facet normal 0.954276 0.225967 -0.195692 + outer loop + vertex 886.456 396.497 257.027 + vertex 883.298 403.428 249.63 + vertex 884.849 403.295 257.039 + endloop + endfacet + facet normal 0.951713 0.225384 -0.208434 + outer loop + vertex 886.456 396.497 257.027 + vertex 884.849 403.295 257.039 + vertex 888.101 396.274 264.297 + endloop + endfacet + facet normal 0.949959 0.244468 -0.194456 + outer loop + vertex 883.298 403.428 249.63 + vertex 881.586 410.095 249.649 + vertex 884.849 403.295 257.039 + endloop + endfacet + facet normal 0.949987 0.244027 -0.194874 + outer loop + vertex 884.849 403.295 257.039 + vertex 881.586 410.095 249.649 + vertex 883.116 410.052 257.055 + endloop + endfacet + facet normal 0.947452 0.243407 -0.207573 + outer loop + vertex 884.849 403.295 257.039 + vertex 883.116 410.052 257.055 + vertex 886.475 403.16 264.305 + endloop + endfacet + facet normal 0.945755 0.26067 -0.193903 + outer loop + vertex 881.586 410.095 249.649 + vertex 879.756 416.734 249.647 + vertex 883.116 410.052 257.055 + endloop + endfacet + facet normal 0.945783 0.26033 -0.194223 + outer loop + vertex 883.116 410.052 257.055 + vertex 879.756 416.734 249.647 + vertex 881.264 416.788 257.062 + endloop + endfacet + facet normal 0.9418 0.274888 -0.193518 + outer loop + vertex 879.756 416.734 249.647 + vertex 877.819 423.342 249.61 + vertex 881.264 416.788 257.062 + endloop + endfacet + facet normal 0.944296 0.275695 -0.179713 + outer loop + vertex 879.756 416.734 249.647 + vertex 876.422 423.206 242.057 + vertex 877.819 423.342 249.61 + endloop + endfacet + facet normal 0.940123 0.289924 -0.179198 + outer loop + vertex 876.422 423.206 242.057 + vertex 874.421 429.645 241.979 + vertex 877.819 423.342 249.61 + endloop + endfacet + facet normal 0.940278 0.288802 -0.180194 + outer loop + vertex 877.819 423.342 249.61 + vertex 874.421 429.645 241.979 + vertex 875.797 429.892 249.553 + endloop + endfacet + facet normal 0.935124 0.305312 -0.179798 + outer loop + vertex 874.421 429.645 241.979 + vertex 872.353 435.962 241.949 + vertex 875.797 429.892 249.553 + endloop + endfacet + facet normal 0.937342 0.306103 -0.166405 + outer loop + vertex 874.421 429.645 241.979 + vertex 871.099 435.658 234.326 + vertex 872.353 435.962 241.949 + endloop + endfacet + facet normal 0.929379 0.329678 -0.166034 + outer loop + vertex 871.099 435.658 234.326 + vertex 869.012 441.637 234.518 + vertex 872.353 435.962 241.949 + endloop + endfacet + facet normal 0.929923 0.326954 -0.168359 + outer loop + vertex 872.353 435.962 241.949 + vertex 869.012 441.637 234.518 + vertex 870.204 442.101 242.003 + endloop + endfacet + facet normal 0.927671 0.32628 -0.18157 + outer loop + vertex 872.353 435.962 241.949 + vertex 870.204 442.101 242.003 + vertex 873.698 436.344 249.51 + endloop + endfacet + facet normal 0.916641 0.362485 -0.168448 + outer loop + vertex 869.012 441.637 234.518 + vertex 866.81 447.322 234.765 + vertex 870.204 442.101 242.003 + endloop + endfacet + facet normal 0.917018 0.360919 -0.169754 + outer loop + vertex 870.204 442.101 242.003 + vertex 866.81 447.322 234.765 + vertex 867.917 447.968 242.122 + endloop + endfacet + facet normal 0.91444 0.360215 -0.184512 + outer loop + vertex 870.204 442.101 242.003 + vertex 867.917 447.968 242.122 + vertex 871.521 442.605 249.513 + endloop + endfacet + facet normal 0.91944 0.362838 -0.151587 + outer loop + vertex 869.012 441.637 234.518 + vertex 865.883 446.737 227.744 + vertex 866.81 447.322 234.765 + endloop + endfacet + facet normal 0.919613 0.362148 -0.152186 + outer loop + vertex 867.859 441.394 226.969 + vertex 865.883 446.737 227.744 + vertex 869.012 441.637 234.518 + endloop + endfacet + facet normal 0.921448 0.361423 -0.142505 + outer loop + vertex 867.859 441.394 226.969 + vertex 864.547 447.124 220.091 + vertex 865.883 446.737 227.744 + endloop + endfacet + facet normal 0.919153 0.370454 -0.133875 + outer loop + vertex 866.804 441.234 219.283 + vertex 864.547 447.124 220.091 + vertex 867.859 441.394 226.969 + endloop + endfacet + facet normal 0.932718 0.334387 -0.134988 + outer loop + vertex 869.954 435.417 226.645 + vertex 866.804 441.234 219.283 + vertex 867.859 441.394 226.969 + endloop + endfacet + facet normal 0.93056 0.334395 -0.149126 + outer loop + vertex 869.954 435.417 226.645 + vertex 867.859 441.394 226.969 + vertex 871.099 435.658 234.326 + endloop + endfacet + facet normal 0.93913 0.309273 -0.149615 + outer loop + vertex 873.148 429.436 234.326 + vertex 869.954 435.417 226.645 + vertex 871.099 435.658 234.326 + endloop + endfacet + facet normal 0.938569 0.312148 -0.147143 + outer loop + vertex 872.002 429.245 226.61 + vertex 869.954 435.417 226.645 + vertex 873.148 429.436 234.326 + endloop + endfacet + facet normal 0.944661 0.292982 -0.147573 + outer loop + vertex 875.129 423.092 234.414 + vertex 872.002 429.245 226.61 + vertex 873.148 429.436 234.326 + endloop + endfacet + facet normal 0.942297 0.292021 -0.163706 + outer loop + vertex 875.129 423.092 234.414 + vertex 873.148 429.436 234.326 + vertex 876.422 423.206 242.057 + endloop + endfacet + facet normal 0.946723 0.277026 -0.164232 + outer loop + vertex 878.335 416.701 242.114 + vertex 875.129 423.092 234.414 + vertex 876.422 423.206 242.057 + endloop + endfacet + facet normal 0.946692 0.277247 -0.164035 + outer loop + vertex 877.018 416.688 234.489 + vertex 875.129 423.092 234.414 + vertex 878.335 416.701 242.114 + endloop + endfacet + facet normal 0.950786 0.262439 -0.164717 + outer loop + vertex 880.143 410.159 242.125 + vertex 877.018 416.688 234.489 + vertex 878.335 416.701 242.114 + endloop + endfacet + facet normal 0.948272 0.261718 -0.179678 + outer loop + vertex 880.143 410.159 242.125 + vertex 878.335 416.701 242.114 + vertex 881.586 410.095 249.649 + endloop + endfacet + facet normal 0.950742 0.262805 -0.164386 + outer loop + vertex 878.804 410.235 234.506 + vertex 877.018 416.688 234.489 + vertex 880.143 410.159 242.125 + endloop + endfacet + facet normal 0.954981 0.246352 -0.165296 + outer loop + vertex 881.836 403.583 242.107 + vertex 878.804 410.235 234.506 + vertex 880.143 410.159 242.125 + endloop + endfacet + facet normal 0.952471 0.245746 -0.18002 + outer loop + vertex 881.836 403.583 242.107 + vertex 880.143 410.159 242.125 + vertex 883.298 403.428 249.63 + endloop + endfacet + facet normal 0.954914 0.247016 -0.164688 + outer loop + vertex 880.481 403.741 234.487 + vertex 878.804 410.235 234.506 + vertex 881.836 403.583 242.107 + endloop + endfacet + facet normal 0.959335 0.228399 -0.165861 + outer loop + vertex 883.409 396.963 242.088 + vertex 880.481 403.741 234.487 + vertex 881.836 403.583 242.107 + endloop + endfacet + facet normal 0.956814 0.227843 -0.180538 + outer loop + vertex 883.409 396.963 242.088 + vertex 881.836 403.583 242.107 + vertex 884.887 396.72 249.614 + endloop + endfacet + facet normal 0.95927 0.229225 -0.165098 + outer loop + vertex 882.04 397.2 234.465 + vertex 880.481 403.741 234.487 + vertex 883.409 396.963 242.088 + endloop + endfacet + facet normal 0.963683 0.208769 -0.166527 + outer loop + vertex 884.855 390.281 242.081 + vertex 882.04 397.2 234.465 + vertex 883.409 396.963 242.088 + endloop + endfacet + facet normal 0.961109 0.208228 -0.181411 + outer loop + vertex 884.855 390.281 242.081 + vertex 883.409 396.963 242.088 + vertex 886.347 389.954 249.61 + endloop + endfacet + facet normal 0.963634 0.209623 -0.165733 + outer loop + vertex 883.475 390.597 234.457 + vertex 882.04 397.2 234.465 + vertex 884.855 390.281 242.081 + endloop + endfacet + facet normal 0.96793 0.187287 -0.167437 + outer loop + vertex 886.165 383.514 242.083 + vertex 883.475 390.597 234.457 + vertex 884.855 390.281 242.081 + endloop + endfacet + facet normal 0.965311 0.186775 -0.182453 + outer loop + vertex 886.165 383.514 242.083 + vertex 884.855 390.281 242.081 + vertex 887.668 383.101 249.612 + endloop + endfacet + facet normal 0.9679 0.188246 -0.166535 + outer loop + vertex 884.776 383.91 234.46 + vertex 883.475 390.597 234.457 + vertex 886.165 383.514 242.083 + endloop + endfacet + facet normal 0.972041 0.163456 -0.168577 + outer loop + vertex 887.321 376.641 242.087 + vertex 884.776 383.91 234.46 + vertex 886.165 383.514 242.083 + endloop + endfacet + facet normal 0.969394 0.163001 -0.18359 + outer loop + vertex 887.321 376.641 242.087 + vertex 886.165 383.514 242.083 + vertex 888.831 376.141 249.615 + endloop + endfacet + facet normal 0.973187 0.135034 -0.186209 + outer loop + vertex 889.813 369.063 249.617 + vertex 887.321 376.641 242.087 + vertex 888.831 376.141 249.615 + endloop + endfacet + facet normal 0.97325 0.136327 -0.184928 + outer loop + vertex 888.301 369.647 242.09 + vertex 887.321 376.641 242.087 + vertex 889.813 369.063 249.617 + endloop + endfacet + facet normal 0.976529 0.105095 -0.188008 + outer loop + vertex 890.586 361.885 249.618 + vertex 888.301 369.647 242.09 + vertex 889.813 369.063 249.617 + endloop + endfacet + facet normal 0.975911 0.136706 -0.170029 + outer loop + vertex 888.301 369.647 242.09 + vertex 885.927 377.112 234.463 + vertex 887.321 376.641 242.087 + endloop + endfacet + facet normal 0.975946 0.137967 -0.168805 + outer loop + vertex 886.905 370.194 234.465 + vertex 885.927 377.112 234.463 + vertex 888.301 369.647 242.09 + endloop + endfacet + facet normal 0.972037 0.164475 -0.167605 + outer loop + vertex 885.927 377.112 234.463 + vertex 884.776 383.91 234.46 + vertex 887.321 376.641 242.087 + endloop + endfacet + facet normal 0.974615 0.16492 -0.151419 + outer loop + vertex 885.927 377.112 234.463 + vertex 883.52 384.265 226.76 + vertex 884.776 383.91 234.46 + endloop + endfacet + facet normal 0.9704 0.189595 -0.149594 + outer loop + vertex 883.52 384.265 226.76 + vertex 882.227 390.883 226.758 + vertex 884.776 383.91 234.46 + endloop + endfacet + facet normal 0.972881 0.190085 -0.131794 + outer loop + vertex 883.52 384.265 226.76 + vertex 881.126 391.13 218.989 + vertex 882.227 390.883 226.758 + endloop + endfacet + facet normal 0.968493 0.21213 -0.130471 + outer loop + vertex 881.126 391.13 218.989 + vertex 879.71 397.597 218.997 + vertex 882.227 390.883 226.758 + endloop + endfacet + facet normal 0.968558 0.211462 -0.13107 + outer loop + vertex 882.227 390.883 226.758 + vertex 879.71 397.597 218.997 + vertex 880.802 397.414 226.766 + endloop + endfacet + facet normal 0.966098 0.210948 -0.148849 + outer loop + vertex 882.227 390.883 226.758 + vertex 880.802 397.414 226.766 + vertex 883.475 390.597 234.457 + endloop + endfacet + facet normal 0.964029 0.231862 -0.129952 + outer loop + vertex 879.71 397.597 218.997 + vertex 878.172 404.008 219.024 + vertex 880.802 397.414 226.766 + endloop + endfacet + facet normal 0.964119 0.231115 -0.130619 + outer loop + vertex 880.802 397.414 226.766 + vertex 878.172 404.008 219.024 + vertex 879.254 403.884 226.79 + endloop + endfacet + facet normal 0.961684 0.230598 -0.148288 + outer loop + vertex 880.802 397.414 226.766 + vertex 879.254 403.884 226.79 + vertex 882.04 397.2 234.465 + endloop + endfacet + facet normal 0.959658 0.249466 -0.129705 + outer loop + vertex 878.172 404.008 219.024 + vertex 876.522 410.367 219.044 + vertex 879.254 403.884 226.79 + endloop + endfacet + facet normal 0.959747 0.248826 -0.130272 + outer loop + vertex 879.254 403.884 226.79 + vertex 876.522 410.367 219.044 + vertex 877.591 410.307 226.81 + endloop + endfacet + facet normal 0.957324 0.248254 -0.147989 + outer loop + vertex 879.254 403.884 226.79 + vertex 877.591 410.307 226.81 + vertex 880.481 403.741 234.487 + endloop + endfacet + facet normal 0.955495 0.265033 -0.129561 + outer loop + vertex 876.522 410.367 219.044 + vertex 874.768 416.676 219.02 + vertex 877.591 410.307 226.81 + endloop + endfacet + facet normal 0.955574 0.264539 -0.129994 + outer loop + vertex 877.591 410.307 226.81 + vertex 874.768 416.676 219.02 + vertex 875.824 416.68 226.787 + endloop + endfacet + facet normal 0.953191 0.263812 -0.147753 + outer loop + vertex 877.591 410.307 226.81 + vertex 875.824 416.68 226.787 + vertex 878.804 410.235 234.506 + endloop + endfacet + facet normal 0.951527 0.278995 -0.12945 + outer loop + vertex 874.768 416.676 219.02 + vertex 872.928 422.909 218.925 + vertex 875.824 416.68 226.787 + endloop + endfacet + facet normal 0.951485 0.279236 -0.129244 + outer loop + vertex 875.824 416.68 226.787 + vertex 872.928 422.909 218.925 + vertex 873.959 422.995 226.703 + endloop + endfacet + facet normal 0.949121 0.278298 -0.147375 + outer loop + vertex 875.824 416.68 226.787 + vertex 873.959 422.995 226.703 + vertex 877.018 416.688 234.489 + endloop + endfacet + facet normal 0.946822 0.294856 -0.128798 + outer loop + vertex 872.928 422.909 218.925 + vertex 870.996 429.072 218.833 + vertex 873.959 422.995 226.703 + endloop + endfacet + facet normal 0.946861 0.294655 -0.128968 + outer loop + vertex 873.959 422.995 226.703 + vertex 870.996 429.072 218.833 + vertex 872.002 429.245 226.61 + endloop + endfacet + facet normal 0.940336 0.315018 -0.128579 + outer loop + vertex 870.996 429.072 218.833 + vertex 868.958 435.185 218.9 + vertex 872.002 429.245 226.61 + endloop + endfacet + facet normal 0.9425 0.315538 -0.110138 + outer loop + vertex 870.996 429.072 218.833 + vertex 868.116 434.963 211.065 + vertex 868.958 435.185 218.9 + endloop + endfacet + facet normal 0.932756 0.343356 -0.109877 + outer loop + vertex 868.116 434.963 211.065 + vertex 865.954 440.975 211.5 + vertex 868.958 435.185 218.9 + endloop + endfacet + facet normal 0.933721 0.339643 -0.113174 + outer loop + vertex 868.958 435.185 218.9 + vertex 865.954 440.975 211.5 + vertex 866.804 441.234 219.283 + endloop + endfacet + facet normal 0.919848 0.37569 -0.112859 + outer loop + vertex 865.954 440.975 211.5 + vertex 863.626 446.922 212.315 + vertex 866.804 441.234 219.283 + endloop + endfacet + facet normal 0.922259 0.374372 -0.0963581 + outer loop + vertex 865.954 440.975 211.5 + vertex 862.935 446.606 204.471 + vertex 863.626 446.922 212.315 + endloop + endfacet + facet normal 0.920842 0.378898 -0.0921237 + outer loop + vertex 865.267 440.727 203.611 + vertex 862.935 446.606 204.471 + vertex 865.954 440.975 211.5 + endloop + endfacet + facet normal 0.922993 0.377327 -0.0755575 + outer loop + vertex 865.267 440.727 203.611 + vertex 862.383 446.361 196.515 + vertex 862.935 446.606 204.471 + endloop + endfacet + facet normal 0.921855 0.380711 -0.072408 + outer loop + vertex 864.717 440.545 195.645 + vertex 862.383 446.361 196.515 + vertex 865.267 440.727 203.611 + endloop + endfacet + facet normal 0.93594 0.344604 -0.0725584 + outer loop + vertex 867.419 434.787 203.149 + vertex 864.717 440.545 195.645 + vertex 865.267 440.727 203.611 + endloop + endfacet + facet normal 0.934159 0.345317 -0.090021 + outer loop + vertex 867.419 434.787 203.149 + vertex 865.267 440.727 203.611 + vertex 868.116 434.963 211.065 + endloop + endfacet + facet normal 0.944142 0.316935 -0.090268 + outer loop + vertex 870.134 428.929 210.982 + vertex 867.419 434.787 203.149 + vertex 868.116 434.963 211.065 + endloop + endfacet + facet normal 0.943925 0.317779 -0.0895622 + outer loop + vertex 869.418 428.821 203.059 + vertex 867.419 434.787 203.149 + vertex 870.134 428.929 210.982 + endloop + endfacet + facet normal 0.950732 0.296695 -0.0898915 + outer loop + vertex 872.043 422.841 211.078 + vertex 869.418 428.821 203.059 + vertex 870.134 428.929 210.982 + endloop + endfacet + facet normal 0.948933 0.295822 -0.109613 + outer loop + vertex 872.043 422.841 211.078 + vertex 870.134 428.929 210.982 + vertex 872.928 422.909 218.925 + endloop + endfacet + facet normal 0.950719 0.296749 -0.0898471 + outer loop + vertex 871.31 422.79 203.157 + vertex 869.418 428.821 203.059 + vertex 872.043 422.841 211.078 + endloop + endfacet + facet normal 0.955494 0.280887 -0.0901864 + outer loop + vertex 873.866 416.669 211.175 + vertex 871.31 422.79 203.157 + vertex 872.043 422.841 211.078 + endloop + endfacet + facet normal 0.953675 0.280039 -0.109921 + outer loop + vertex 873.866 416.669 211.175 + vertex 872.043 422.841 211.078 + vertex 874.768 416.676 219.02 + endloop + endfacet + facet normal 0.955477 0.280966 -0.0901212 + outer loop + vertex 873.121 416.663 203.256 + vertex 871.31 422.79 203.157 + vertex 873.866 416.669 211.175 + endloop + endfacet + facet normal 0.95956 0.266564 -0.0904947 + outer loop + vertex 875.606 410.416 211.203 + vertex 873.121 416.663 203.256 + vertex 873.866 416.669 211.175 + endloop + endfacet + facet normal 0.95767 0.265951 -0.110174 + outer loop + vertex 875.606 410.416 211.203 + vertex 873.866 416.669 211.175 + vertex 876.522 410.367 219.044 + endloop + endfacet + facet normal 0.959467 0.267032 -0.0900972 + outer loop + vertex 874.852 410.451 203.281 + vertex 873.121 416.663 203.256 + vertex 875.606 410.416 211.203 + endloop + endfacet + facet normal 0.963724 0.251062 -0.0905741 + outer loop + vertex 877.247 404.107 211.18 + vertex 874.852 410.451 203.281 + vertex 875.606 410.416 211.203 + endloop + endfacet + facet normal 0.96179 0.25063 -0.110205 + outer loop + vertex 877.247 404.107 211.18 + vertex 875.606 410.416 211.203 + vertex 878.172 404.008 219.024 + endloop + endfacet + facet normal 0.96364 0.251528 -0.0901741 + outer loop + vertex 876.485 404.187 203.258 + vertex 874.852 410.451 203.281 + vertex 877.247 404.107 211.18 + endloop + endfacet + facet normal 0.968157 0.233301 -0.0907913 + outer loop + vertex 878.776 397.751 211.153 + vertex 876.485 404.187 203.258 + vertex 877.247 404.107 211.18 + endloop + endfacet + facet normal 0.966205 0.232914 -0.110451 + outer loop + vertex 878.776 397.751 211.153 + vertex 877.247 404.107 211.18 + vertex 879.71 397.597 218.997 + endloop + endfacet + facet normal 0.968097 0.233676 -0.090468 + outer loop + vertex 878.006 397.879 203.232 + vertex 876.485 404.187 203.258 + vertex 878.776 397.751 211.153 + endloop + endfacet + facet normal 0.965172 0.251855 -0.0707957 + outer loop + vertex 876.485 404.187 203.258 + vertex 874.26 410.479 195.303 + vertex 874.852 410.451 203.281 + endloop + endfacet + facet normal 0.9609 0.267791 -0.0704239 + outer loop + vertex 874.26 410.479 195.303 + vertex 872.537 416.656 195.278 + vertex 874.852 410.451 203.281 + endloop + endfacet + facet normal 0.961981 0.268168 -0.0517625 + outer loop + vertex 874.26 410.479 195.303 + vertex 872.108 416.65 187.29 + vertex 872.537 416.656 195.278 + endloop + endfacet + facet normal 0.95786 0.282573 -0.0515506 + outer loop + vertex 872.108 416.65 187.29 + vertex 870.312 422.723 187.194 + vertex 872.537 416.656 195.278 + endloop + endfacet + facet normal 0.957888 0.282459 -0.051644 + outer loop + vertex 872.537 416.656 195.278 + vertex 870.312 422.723 187.194 + vertex 870.734 422.751 195.181 + endloop + endfacet + facet normal 0.956873 0.281859 -0.0703591 + outer loop + vertex 872.537 416.656 195.278 + vertex 870.734 422.751 195.181 + vertex 873.121 416.663 203.256 + endloop + endfacet + facet normal 0.953062 0.298373 -0.0514436 + outer loop + vertex 870.312 422.723 187.194 + vertex 868.436 428.697 187.096 + vertex 870.734 422.751 195.181 + endloop + endfacet + facet normal 0.953056 0.298397 -0.0514247 + outer loop + vertex 870.734 422.751 195.181 + vertex 868.436 428.697 187.096 + vertex 868.851 428.749 195.081 + endloop + endfacet + facet normal 0.952052 0.29777 -0.0702133 + outer loop + vertex 870.734 422.751 195.181 + vertex 868.851 428.749 195.081 + vertex 871.31 422.79 203.157 + endloop + endfacet + facet normal 0.946176 0.319575 -0.0512052 + outer loop + vertex 868.436 428.697 187.096 + vertex 866.45 434.59 187.18 + vertex 868.851 428.749 195.081 + endloop + endfacet + facet normal 0.94639 0.318846 -0.0518091 + outer loop + vertex 868.851 428.749 195.081 + vertex 866.45 434.59 187.18 + vertex 866.862 434.666 195.171 + endloop + endfacet + facet normal 0.945244 0.318739 -0.0701359 + outer loop + vertex 868.851 428.749 195.081 + vertex 866.862 434.666 195.171 + vertex 869.418 428.821 203.059 + endloop + endfacet + facet normal 0.93619 0.347692 -0.0515591 + outer loop + vertex 866.45 434.59 187.18 + vertex 864.306 440.434 187.642 + vertex 866.862 434.666 195.171 + endloop + endfacet + facet normal 0.936698 0.346114 -0.0529409 + outer loop + vertex 866.862 434.666 195.171 + vertex 864.306 440.434 187.642 + vertex 864.717 440.545 195.645 + endloop + endfacet + facet normal 0.922439 0.382528 -0.052716 + outer loop + vertex 864.306 440.434 187.642 + vertex 861.964 446.2 188.514 + vertex 864.717 440.545 195.645 + endloop + endfacet + facet normal 0.923966 0.380717 -0.036633 + outer loop + vertex 864.306 440.434 187.642 + vertex 861.682 446.115 180.523 + vertex 861.964 446.2 188.514 + endloop + endfacet + facet normal 0.923117 0.382967 -0.0345249 + outer loop + vertex 864.032 440.376 179.686 + vertex 861.682 446.115 180.523 + vertex 864.306 440.434 187.642 + endloop + endfacet + facet normal 0.924343 0.381117 -0.0184021 + outer loop + vertex 864.032 440.376 179.686 + vertex 861.533 446.096 172.635 + vertex 861.682 446.115 180.523 + endloop + endfacet + facet normal 0.923583 0.38304 -0.0165728 + outer loop + vertex 863.893 440.369 171.815 + vertex 861.533 446.096 172.635 + vertex 864.032 440.376 179.686 + endloop + endfacet + facet normal 0.93766 0.347149 -0.0167918 + outer loop + vertex 866.181 434.55 179.239 + vertex 863.893 440.369 171.815 + vertex 864.032 440.376 179.686 + endloop + endfacet + facet normal 0.936845 0.348133 -0.0335498 + outer loop + vertex 866.181 434.55 179.239 + vertex 864.032 440.376 179.686 + vertex 866.45 434.59 187.18 + endloop + endfacet + facet normal 0.93732 0.348104 -0.0159384 + outer loop + vertex 866.048 434.547 171.372 + vertex 863.893 440.369 171.815 + vertex 866.181 434.55 179.239 + endloop + endfacet + facet normal 0.947284 0.319989 -0.0160987 + outer loop + vertex 868.166 428.669 179.155 + vertex 866.048 434.547 171.372 + vertex 866.181 434.55 179.239 + endloop + endfacet + facet normal 0.946806 0.320073 -0.033343 + outer loop + vertex 868.166 428.669 179.155 + vertex 866.181 434.55 179.239 + vertex 868.436 428.697 187.096 + endloop + endfacet + facet normal 0.947258 0.320071 -0.0160297 + outer loop + vertex 868.033 428.668 171.292 + vertex 866.048 434.547 171.372 + vertex 868.166 428.669 179.155 + endloop + endfacet + facet normal 0.954038 0.299249 -0.0161412 + outer loop + vertex 870.038 422.707 179.253 + vertex 868.033 428.668 171.292 + vertex 868.166 428.669 179.155 + endloop + endfacet + facet normal 0.953708 0.298861 -0.0335122 + outer loop + vertex 870.038 422.707 179.253 + vertex 868.166 428.669 179.155 + vertex 870.312 422.723 187.194 + endloop + endfacet + facet normal 0.95409 0.299078 -0.0162827 + outer loop + vertex 869.903 422.708 171.388 + vertex 868.033 428.668 171.292 + vertex 870.038 422.707 179.253 + endloop + endfacet + facet normal 0.94745 0.3199 0.00131191 + outer loop + vertex 868.033 428.668 171.292 + vertex 866.045 434.589 163.564 + vertex 866.048 434.547 171.372 + endloop + endfacet + facet normal 0.937555 0.347835 0.00146629 + outer loop + vertex 866.045 434.589 163.564 + vertex 863.881 440.42 164.019 + vertex 866.048 434.547 171.372 + endloop + endfacet + facet normal 0.937834 0.346543 0.0193687 + outer loop + vertex 866.045 434.589 163.564 + vertex 864 440.537 156.169 + vertex 863.881 440.42 164.019 + endloop + endfacet + facet normal 0.923949 0.382009 0.0196852 + outer loop + vertex 864 440.537 156.169 + vertex 861.604 446.286 157.078 + vertex 863.881 440.42 164.019 + endloop + endfacet + facet normal 0.924745 0.380168 0.0178694 + outer loop + vertex 863.881 440.42 164.019 + vertex 861.604 446.286 157.078 + vertex 861.509 446.15 164.867 + endloop + endfacet + facet normal 0.924012 0.382363 0.000991983 + outer loop + vertex 863.881 440.42 164.019 + vertex 861.509 446.15 164.867 + vertex 863.893 440.369 171.815 + endloop + endfacet + facet normal 0.92448 0.379323 0.0380767 + outer loop + vertex 864 440.537 156.169 + vertex 861.842 446.507 149.08 + vertex 861.604 446.286 157.078 + endloop + endfacet + facet normal 0.924797 0.378619 0.0373877 + outer loop + vertex 864.247 440.721 148.2 + vertex 861.842 446.507 149.08 + vertex 864 440.537 156.169 + endloop + endfacet + facet normal 0.937906 0.346357 0.0191994 + outer loop + vertex 866.171 434.68 155.731 + vertex 864 440.537 156.169 + vertex 866.045 434.589 163.564 + endloop + endfacet + facet normal 0.947514 0.319712 0.0011512 + outer loop + vertex 868.032 428.699 163.486 + vertex 866.045 434.589 163.564 + vertex 868.033 428.668 171.292 + endloop + endfacet + facet normal 0.937852 0.347034 0.000738749 + outer loop + vertex 866.048 434.547 171.372 + vertex 863.881 440.42 164.019 + vertex 863.893 440.369 171.815 + endloop + endfacet + facet normal 0.924537 0.381093 -0.000244636 + outer loop + vertex 863.893 440.369 171.815 + vertex 861.509 446.15 164.867 + vertex 861.533 446.096 172.635 + endloop + endfacet + facet normal 0.937305 0.346773 -0.0347487 + outer loop + vertex 866.45 434.59 187.18 + vertex 864.032 440.376 179.686 + vertex 864.306 440.434 187.642 + endloop + endfacet + facet normal 0.946956 0.319588 -0.033748 + outer loop + vertex 868.436 428.697 187.096 + vertex 866.181 434.55 179.239 + vertex 866.45 434.59 187.18 + endloop + endfacet + facet normal 0.953705 0.29887 -0.0335044 + outer loop + vertex 870.312 422.723 187.194 + vertex 868.166 428.669 179.155 + vertex 868.436 428.697 187.096 + endloop + endfacet + facet normal 0.958515 0.283051 -0.033646 + outer loop + vertex 872.108 416.65 187.29 + vertex 870.038 422.707 179.253 + vertex 870.312 422.723 187.194 + endloop + endfacet + facet normal 0.958516 0.283046 -0.0336496 + outer loop + vertex 871.83 416.649 179.346 + vertex 870.038 422.707 179.253 + vertex 872.108 416.65 187.29 + endloop + endfacet + facet normal 0.961948 0.268307 -0.0516462 + outer loop + vertex 873.825 410.499 187.314 + vertex 872.108 416.65 187.29 + vertex 874.26 410.479 195.303 + endloop + endfacet + facet normal 0.965113 0.252154 -0.0705425 + outer loop + vertex 875.885 404.251 195.28 + vertex 874.26 410.479 195.303 + vertex 876.485 404.187 203.258 + endloop + endfacet + facet normal 0.960957 0.267527 -0.0706453 + outer loop + vertex 874.852 410.451 203.281 + vertex 872.537 416.656 195.278 + vertex 873.121 416.663 203.256 + endloop + endfacet + facet normal 0.956908 0.281707 -0.0704843 + outer loop + vertex 873.121 416.663 203.256 + vertex 870.734 422.751 195.181 + vertex 871.31 422.79 203.157 + endloop + endfacet + facet normal 0.95212 0.297503 -0.0704308 + outer loop + vertex 871.31 422.79 203.157 + vertex 868.851 428.749 195.081 + vertex 869.418 428.821 203.059 + endloop + endfacet + facet normal 0.945446 0.318005 -0.0707455 + outer loop + vertex 869.418 428.821 203.059 + vertex 866.862 434.666 195.171 + vertex 867.419 434.787 203.149 + endloop + endfacet + facet normal 0.935219 0.346986 -0.0704711 + outer loop + vertex 866.862 434.666 195.171 + vertex 864.717 440.545 195.645 + vertex 867.419 434.787 203.149 + endloop + endfacet + facet normal 0.923701 0.378998 -0.0560028 + outer loop + vertex 864.717 440.545 195.645 + vertex 861.964 446.2 188.514 + vertex 862.383 446.361 196.515 + endloop + endfacet + facet normal 0.93486 0.342834 -0.0922084 + outer loop + vertex 868.116 434.963 211.065 + vertex 865.267 440.727 203.611 + vertex 865.954 440.975 211.5 + endloop + endfacet + facet normal 0.942256 0.316565 -0.109269 + outer loop + vertex 870.134 428.929 210.982 + vertex 868.116 434.963 211.065 + vertex 870.996 429.072 218.833 + endloop + endfacet + facet normal 0.948937 0.295806 -0.109625 + outer loop + vertex 872.928 422.909 218.925 + vertex 870.134 428.929 210.982 + vertex 870.996 429.072 218.833 + endloop + endfacet + facet normal 0.953696 0.27993 -0.110013 + outer loop + vertex 874.768 416.676 219.02 + vertex 872.043 422.841 211.078 + vertex 872.928 422.909 218.925 + endloop + endfacet + facet normal 0.957711 0.265722 -0.110371 + outer loop + vertex 876.522 410.367 219.044 + vertex 873.866 416.669 211.175 + vertex 874.768 416.676 219.02 + endloop + endfacet + facet normal 0.961893 0.249986 -0.110766 + outer loop + vertex 878.172 404.008 219.024 + vertex 875.606 410.416 211.203 + vertex 876.522 410.367 219.044 + endloop + endfacet + facet normal 0.966287 0.232325 -0.110967 + outer loop + vertex 879.71 397.597 218.997 + vertex 877.247 404.107 211.18 + vertex 878.172 404.008 219.024 + endloop + endfacet + facet normal 0.970769 0.212603 -0.111393 + outer loop + vertex 881.126 391.13 218.989 + vertex 878.776 397.751 211.153 + vertex 879.71 397.597 218.997 + endloop + endfacet + facet normal 0.970696 0.213217 -0.110852 + outer loop + vertex 880.184 391.338 211.144 + vertex 878.776 397.751 211.153 + vertex 881.126 391.13 218.989 + endloop + endfacet + facet normal 0.97282 0.190922 -0.131036 + outer loop + vertex 882.412 384.576 218.991 + vertex 881.126 391.13 218.989 + vertex 883.52 384.265 226.76 + endloop + endfacet + facet normal 0.974587 0.166045 -0.150366 + outer loop + vertex 884.666 377.539 226.764 + vertex 883.52 384.265 226.76 + vertex 885.927 377.112 234.463 + endloop + endfacet + facet normal 0.970444 0.188747 -0.150376 + outer loop + vertex 884.776 383.91 234.46 + vertex 882.227 390.883 226.758 + vertex 883.475 390.597 234.457 + endloop + endfacet + facet normal 0.966159 0.210152 -0.149576 + outer loop + vertex 883.475 390.597 234.457 + vertex 880.802 397.414 226.766 + vertex 882.04 397.2 234.465 + endloop + endfacet + facet normal 0.961766 0.229766 -0.149042 + outer loop + vertex 882.04 397.2 234.465 + vertex 879.254 403.884 226.79 + vertex 880.481 403.741 234.487 + endloop + endfacet + facet normal 0.957401 0.24761 -0.148569 + outer loop + vertex 880.481 403.741 234.487 + vertex 877.591 410.307 226.81 + vertex 878.804 410.235 234.506 + endloop + endfacet + facet normal 0.953228 0.263539 -0.147996 + outer loop + vertex 878.804 410.235 234.506 + vertex 875.824 416.68 226.787 + vertex 877.018 416.688 234.489 + endloop + endfacet + facet normal 0.949142 0.278163 -0.147493 + outer loop + vertex 877.018 416.688 234.489 + vertex 873.959 422.995 226.703 + vertex 875.129 423.092 234.414 + endloop + endfacet + facet normal 0.944541 0.29366 -0.146991 + outer loop + vertex 873.959 422.995 226.703 + vertex 872.002 429.245 226.61 + vertex 875.129 423.092 234.414 + endloop + endfacet + facet normal 0.940815 0.312798 -0.130478 + outer loop + vertex 872.002 429.245 226.61 + vertex 868.958 435.185 218.9 + vertex 869.954 435.417 226.645 + endloop + endfacet + facet normal 0.931424 0.339895 -0.130083 + outer loop + vertex 868.958 435.185 218.9 + vertex 866.804 441.234 219.283 + vertex 869.954 435.417 226.645 + endloop + endfacet + facet normal 0.921657 0.369351 -0.118858 + outer loop + vertex 866.804 441.234 219.283 + vertex 863.626 446.922 212.315 + vertex 864.547 447.124 220.091 + endloop + endfacet + facet normal 0.931505 0.33 -0.152968 + outer loop + vertex 871.099 435.658 234.326 + vertex 867.859 441.394 226.969 + vertex 869.012 441.637 234.518 + endloop + endfacet + facet normal 0.936913 0.308544 -0.1643 + outer loop + vertex 873.148 429.436 234.326 + vertex 871.099 435.658 234.326 + vertex 874.421 429.645 241.979 + endloop + endfacet + facet normal 0.942484 0.290831 -0.164744 + outer loop + vertex 876.422 423.206 242.057 + vertex 873.148 429.436 234.326 + vertex 874.421 429.645 241.979 + endloop + endfacet + facet normal 0.94424 0.276164 -0.179289 + outer loop + vertex 878.335 416.701 242.114 + vertex 876.422 423.206 242.057 + vertex 879.756 416.734 249.647 + endloop + endfacet + facet normal 0.948306 0.261378 -0.179991 + outer loop + vertex 881.586 410.095 249.649 + vertex 878.335 416.701 242.114 + vertex 879.756 416.734 249.647 + endloop + endfacet + facet normal 0.952525 0.245088 -0.180633 + outer loop + vertex 883.298 403.428 249.63 + vertex 880.143 410.159 242.125 + vertex 881.586 410.095 249.649 + endloop + endfacet + facet normal 0.95686 0.227077 -0.181257 + outer loop + vertex 884.887 396.72 249.614 + vertex 881.836 403.583 242.107 + vertex 883.298 403.428 249.63 + endloop + endfacet + facet normal 0.961134 0.207563 -0.18204 + outer loop + vertex 886.347 389.954 249.61 + vertex 883.409 396.963 242.088 + vertex 884.887 396.72 249.614 + endloop + endfacet + facet normal 0.965321 0.185983 -0.183212 + outer loop + vertex 887.668 383.101 249.612 + vertex 884.855 390.281 242.081 + vertex 886.347 389.954 249.61 + endloop + endfacet + facet normal 0.969376 0.161934 -0.184627 + outer loop + vertex 888.831 376.141 249.615 + vertex 886.165 383.514 242.083 + vertex 887.668 383.101 249.612 + endloop + endfacet + facet normal 0.970356 0.134636 -0.200704 + outer loop + vertex 889.813 369.063 249.617 + vertex 888.831 376.141 249.615 + vertex 891.43 368.464 257.029 + endloop + endfacet + facet normal 0.973502 0.103523 -0.203905 + outer loop + vertex 892.203 361.194 257.031 + vertex 889.813 369.063 249.617 + vertex 891.43 368.464 257.029 + endloop + endfacet + facet normal 0.973637 0.10478 -0.202614 + outer loop + vertex 890.586 361.885 249.618 + vertex 889.813 369.063 249.617 + vertex 892.203 361.194 257.031 + endloop + endfacet + facet normal 0.976637 0.106375 -0.186721 + outer loop + vertex 889.075 362.547 242.089 + vertex 888.301 369.647 242.09 + vertex 890.586 361.885 249.618 + endloop + endfacet + facet normal 0.982333 0.0756277 -0.171178 + outer loop + vertex 888.228 356.103 234.466 + vertex 887.684 363.174 234.466 + vertex 889.611 355.402 242.09 + endloop + endfacet + facet normal 0.98391 0.0350433 -0.175197 + outer loop + vertex 889.865 348.271 242.09 + vertex 888.228 356.103 234.466 + vertex 889.611 355.402 242.09 + endloop + endfacet + facet normal 0.98498 0.0758312 -0.155127 + outer loop + vertex 888.228 356.103 234.466 + vertex 886.428 363.742 226.767 + vertex 887.684 363.174 234.466 + endloop + endfacet + facet normal 0.985144 0.0780328 -0.152981 + outer loop + vertex 886.982 356.741 226.767 + vertex 886.428 363.742 226.767 + vertex 888.228 356.103 234.466 + endloop + endfacet + facet normal 0.986934 0.0379356 -0.156593 + outer loop + vertex 888.5 349.047 234.467 + vertex 886.982 356.741 226.767 + vertex 888.228 356.103 234.466 + endloop + endfacet + facet normal 0.987641 0.0782311 -0.135815 + outer loop + vertex 886.982 356.741 226.767 + vertex 885.32 364.238 218.998 + vertex 886.428 363.742 226.767 + endloop + endfacet + facet normal 0.984692 0.112412 -0.133213 + outer loop + vertex 885.32 364.238 218.998 + vertex 884.533 371.126 218.998 + vertex 886.428 363.742 226.767 + endloop + endfacet + facet normal 0.984669 0.110952 -0.134595 + outer loop + vertex 886.428 363.742 226.767 + vertex 884.533 371.126 218.998 + vertex 885.644 370.69 226.766 + endloop + endfacet + facet normal 0.987032 0.11268 -0.114331 + outer loop + vertex 885.32 364.238 218.998 + vertex 883.583 371.494 211.153 + vertex 884.533 371.126 218.998 + endloop + endfacet + facet normal 0.983334 0.142842 -0.11247 + outer loop + vertex 883.583 371.494 211.153 + vertex 882.605 378.225 211.15 + vertex 884.533 371.126 218.998 + endloop + endfacet + facet normal 0.983378 0.141744 -0.113474 + outer loop + vertex 884.533 371.126 218.998 + vertex 882.605 378.225 211.15 + vertex 883.555 377.91 218.995 + endloop + endfacet + facet normal 0.985338 0.143141 -0.0928404 + outer loop + vertex 883.583 371.494 211.153 + vertex 881.821 378.482 203.229 + vertex 882.605 378.225 211.15 + endloop + endfacet + facet normal 0.981213 0.169815 -0.0915681 + outer loop + vertex 881.821 378.482 203.229 + vertex 880.684 385.05 203.225 + vertex 882.605 378.225 211.15 + endloop + endfacet + facet normal 0.981279 0.169075 -0.0922208 + outer loop + vertex 882.605 378.225 211.15 + vertex 880.684 385.05 203.225 + vertex 881.465 384.84 211.147 + endloop + endfacet + facet normal 0.982792 0.1701 -0.0720186 + outer loop + vertex 881.821 378.482 203.229 + vertex 880.071 385.215 195.248 + vertex 880.684 385.05 203.225 + endloop + endfacet + facet normal 0.978446 0.19384 -0.0711924 + outer loop + vertex 880.071 385.215 195.248 + vertex 878.798 391.642 195.246 + vertex 880.684 385.05 203.225 + endloop + endfacet + facet normal 0.978508 0.193385 -0.0715831 + outer loop + vertex 880.684 385.05 203.225 + vertex 878.798 391.642 195.246 + vertex 879.407 391.51 203.224 + endloop + endfacet + facet normal 0.97959 0.194073 -0.0523361 + outer loop + vertex 880.071 385.215 195.248 + vertex 878.353 391.734 187.26 + vertex 878.798 391.642 195.246 + endloop + endfacet + facet normal 0.97514 0.21544 -0.0518416 + outer loop + vertex 878.353 391.734 187.26 + vertex 876.958 398.048 187.267 + vertex 878.798 391.642 195.246 + endloop + endfacet + facet normal 0.975206 0.215067 -0.0521563 + outer loop + vertex 878.798 391.642 195.246 + vertex 876.958 398.048 187.267 + vertex 877.401 397.976 195.255 + endloop + endfacet + facet normal 0.9759 0.215588 -0.0337865 + outer loop + vertex 878.353 391.734 187.26 + vertex 876.674 398.089 179.322 + vertex 876.958 398.048 187.267 + endloop + endfacet + facet normal 0.97135 0.235276 -0.0335207 + outer loop + vertex 876.674 398.089 179.322 + vertex 875.164 404.324 179.345 + vertex 876.958 398.048 187.267 + endloop + endfacet + facet normal 0.971403 0.235029 -0.0337287 + outer loop + vertex 876.958 398.048 187.267 + vertex 875.164 404.324 179.345 + vertex 875.447 404.296 187.291 + endloop + endfacet + facet normal 0.971784 0.235319 -0.01613 + outer loop + vertex 876.674 398.089 179.322 + vertex 875.031 404.335 171.466 + vertex 875.164 404.324 179.345 + endloop + endfacet + facet normal 0.967189 0.253551 -0.0160275 + outer loop + vertex 875.031 404.335 171.466 + vertex 873.41 410.518 171.49 + vertex 875.164 404.324 179.345 + endloop + endfacet + facet normal 0.967264 0.25325 -0.0162813 + outer loop + vertex 875.164 404.324 179.345 + vertex 873.41 410.518 171.49 + vertex 873.545 410.512 179.367 + endloop + endfacet + facet normal 0.967329 0.253522 0.000921285 + outer loop + vertex 875.031 404.335 171.466 + vertex 873.418 410.518 163.663 + vertex 873.41 410.518 171.49 + endloop + endfacet + facet normal 0.96293 0.269751 0.000917162 + outer loop + vertex 873.418 410.518 163.663 + vertex 871.697 416.661 163.656 + vertex 873.41 410.518 171.49 + endloop + endfacet + facet normal 0.963044 0.269342 0.000571624 + outer loop + vertex 873.41 410.518 171.49 + vertex 871.697 416.661 163.656 + vertex 871.695 416.651 171.474 + endloop + endfacet + facet normal 0.962781 0.269728 0.0173048 + outer loop + vertex 873.418 410.518 163.663 + vertex 871.833 416.678 155.842 + vertex 871.697 416.661 163.656 + endloop + endfacet + facet normal 0.958759 0.283695 0.0172645 + outer loop + vertex 871.833 416.678 155.842 + vertex 870.031 422.77 155.777 + vertex 871.697 416.661 163.656 + endloop + endfacet + facet normal 0.958729 0.283791 0.0173453 + outer loop + vertex 871.697 416.661 163.656 + vertex 870.031 422.77 155.777 + vertex 869.903 422.727 163.579 + endloop + endfacet + facet normal 0.958323 0.283739 0.0333056 + outer loop + vertex 871.833 416.678 155.842 + vertex 870.284 422.836 147.944 + vertex 870.031 422.77 155.777 + endloop + endfacet + facet normal 0.954289 0.297026 0.0332884 + outer loop + vertex 870.284 422.836 147.944 + vertex 868.41 428.867 147.839 + vertex 870.031 422.77 155.777 + endloop + endfacet + facet normal 0.953836 0.298351 0.034399 + outer loop + vertex 870.031 422.77 155.777 + vertex 868.41 428.867 147.839 + vertex 868.16 428.765 155.678 + endloop + endfacet + facet normal 0.953556 0.297086 0.0497102 + outer loop + vertex 870.284 422.836 147.944 + vertex 868.776 429.01 139.98 + vertex 868.41 428.867 147.839 + endloop + endfacet + facet normal 0.948481 0.312903 0.0497621 + outer loop + vertex 868.776 429.01 139.98 + vertex 866.811 434.975 139.915 + vertex 868.41 428.867 147.839 + endloop + endfacet + facet normal 0.947386 0.315805 0.0522201 + outer loop + vertex 868.41 428.867 147.839 + vertex 866.811 434.975 139.915 + vertex 866.43 434.81 147.836 + endloop + endfacet + facet normal 0.947455 0.312754 0.0671826 + outer loop + vertex 868.776 429.01 139.98 + vertex 867.296 435.2 132.027 + vertex 866.811 434.975 139.915 + endloop + endfacet + facet normal 0.939374 0.336215 0.0673533 + outer loop + vertex 867.296 435.2 132.027 + vertex 865.192 441.062 132.118 + vertex 866.811 434.975 139.915 + endloop + endfacet + facet normal 0.93777 0.339997 0.0706386 + outer loop + vertex 866.811 434.975 139.915 + vertex 865.192 441.062 132.118 + vertex 864.651 440.885 140.15 + endloop + endfacet + facet normal 0.938123 0.335477 0.0859103 + outer loop + vertex 867.296 435.2 132.027 + vertex 865.81 441.366 124.173 + vertex 865.192 441.062 132.118 + endloop + endfacet + facet normal 0.924724 0.370745 0.0862166 + outer loop + vertex 865.81 441.366 124.173 + vertex 863.509 447.035 124.48 + vertex 865.192 441.062 132.118 + endloop + endfacet + facet normal 0.922646 0.375 0.0900019 + outer loop + vertex 865.192 441.062 132.118 + vertex 863.509 447.035 124.48 + vertex 862.798 446.808 132.711 + endloop + endfacet + facet normal 0.902005 0.422341 0.0895259 + outer loop + vertex 863.509 447.035 124.48 + vertex 860.831 452.588 125.26 + vertex 862.798 446.808 132.711 + endloop + endfacet + facet normal 0.901042 0.418397 0.114309 + outer loop + vertex 863.509 447.035 124.48 + vertex 861.82 452.739 116.919 + vertex 860.831 452.588 125.26 + endloop + endfacet + facet normal 0.906178 0.409315 0.10631 + outer loop + vertex 864.274 447.426 116.456 + vertex 861.82 452.739 116.919 + vertex 863.509 447.035 124.48 + endloop + endfacet + facet normal 0.904515 0.406609 0.128533 + outer loop + vertex 864.274 447.426 116.456 + vertex 862.684 453.373 108.834 + vertex 861.82 452.739 116.919 + endloop + endfacet + facet normal 0.90979 0.397294 0.120164 + outer loop + vertex 865.05 448.005 108.662 + vertex 862.684 453.373 108.834 + vertex 864.274 447.426 116.456 + endloop + endfacet + facet normal 0.924886 0.36115 0.11898 + outer loop + vertex 866.489 441.778 116.377 + vertex 865.05 448.005 108.662 + vertex 864.274 447.426 116.456 + endloop + endfacet + facet normal 0.926755 0.362154 0.0998476 + outer loop + vertex 866.489 441.778 116.377 + vertex 864.274 447.426 116.456 + vertex 865.81 441.366 124.173 + endloop + endfacet + facet normal 0.938716 0.33011 0.0991957 + outer loop + vertex 867.872 435.493 124.211 + vertex 866.489 441.778 116.377 + vertex 865.81 441.366 124.173 + endloop + endfacet + facet normal 0.940668 0.325674 0.0952925 + outer loop + vertex 868.539 435.831 116.472 + vertex 866.489 441.778 116.377 + vertex 867.872 435.493 124.211 + endloop + endfacet + facet normal 0.946908 0.307143 0.0950202 + outer loop + vertex 869.836 429.405 124.319 + vertex 868.539 435.831 116.472 + vertex 867.872 435.493 124.211 + endloop + endfacet + facet normal 0.948293 0.307312 0.0793671 + outer loop + vertex 869.836 429.405 124.319 + vertex 867.872 435.493 124.211 + vertex 869.251 429.193 132.133 + endloop + endfacet + facet normal 0.952187 0.295039 0.0793253 + outer loop + vertex 871.154 423.03 132.209 + vertex 869.836 429.405 124.319 + vertex 869.251 429.193 132.133 + endloop + endfacet + facet normal 0.953293 0.295191 0.0639964 + outer loop + vertex 871.154 423.03 132.209 + vertex 869.251 429.193 132.133 + vertex 870.658 422.924 140.081 + endloop + endfacet + facet normal 0.956755 0.283755 0.0640608 + outer loop + vertex 872.493 416.732 140.106 + vertex 871.154 423.03 132.209 + vertex 870.658 422.924 140.081 + endloop + endfacet + facet normal 0.95759 0.283942 0.0489646 + outer loop + vertex 872.493 416.732 140.106 + vertex 870.658 422.924 140.081 + vertex 872.098 416.702 147.993 + endloop + endfacet + facet normal 0.96158 0.270095 0.0491114 + outer loop + vertex 873.841 410.502 147.98 + vertex 872.493 416.732 140.106 + vertex 872.098 416.702 147.993 + endloop + endfacet + facet normal 0.962185 0.270299 0.033731 + outer loop + vertex 873.841 410.502 147.98 + vertex 872.098 416.702 147.993 + vertex 873.562 410.513 155.84 + endloop + endfacet + facet normal 0.966658 0.253817 0.033913 + outer loop + vertex 875.193 404.306 155.814 + vertex 873.841 410.502 147.98 + vertex 873.562 410.513 155.84 + endloop + endfacet + facet normal 0.967042 0.253985 0.0179125 + outer loop + vertex 875.193 404.306 155.814 + vertex 873.562 410.513 155.84 + vertex 875.042 404.329 163.638 + endloop + endfacet + facet normal 0.971674 0.235637 0.0180549 + outer loop + vertex 876.554 398.094 163.621 + vertex 875.193 404.306 155.814 + vertex 875.042 404.329 163.638 + endloop + endfacet + facet normal 0.97182 0.235719 0.00131995 + outer loop + vertex 876.554 398.094 163.621 + vertex 875.042 404.329 163.638 + vertex 876.541 398.106 171.445 + endloop + endfacet + facet normal 0.976361 0.216144 0.00135596 + outer loop + vertex 877.934 391.813 171.441 + vertex 876.554 398.094 163.621 + vertex 876.541 398.106 171.445 + endloop + endfacet + facet normal 0.976236 0.216129 -0.0158601 + outer loop + vertex 877.934 391.813 171.441 + vertex 876.541 398.106 171.445 + vertex 878.066 391.792 179.315 + endloop + endfacet + facet normal 0.980661 0.195061 -0.0159891 + outer loop + vertex 879.337 385.406 179.318 + vertex 877.934 391.813 171.441 + vertex 878.066 391.792 179.315 + endloop + endfacet + facet normal 0.980233 0.194969 -0.0336106 + outer loop + vertex 879.337 385.406 179.318 + vertex 878.066 391.792 179.315 + vertex 879.623 385.335 187.262 + endloop + endfacet + facet normal 0.984578 0.171616 -0.0339767 + outer loop + vertex 880.758 378.824 187.265 + vertex 879.337 385.406 179.318 + vertex 879.623 385.335 187.262 + endloop + endfacet + facet normal 0.983808 0.171473 -0.0521382 + outer loop + vertex 880.758 378.824 187.265 + vertex 879.623 385.335 187.262 + vertex 881.206 378.682 195.252 + endloop + endfacet + facet normal 0.987986 0.145231 -0.0528394 + outer loop + vertex 882.185 372.026 195.254 + vertex 880.758 378.824 187.265 + vertex 881.206 378.682 195.252 + endloop + endfacet + facet normal 0.986816 0.145055 -0.0717814 + outer loop + vertex 882.185 372.026 195.254 + vertex 881.206 378.682 195.252 + vertex 882.799 371.794 203.231 + endloop + endfacet + facet normal 0.990604 0.11569 -0.07293 + outer loop + vertex 883.592 365.003 203.232 + vertex 882.185 372.026 195.254 + vertex 882.799 371.794 203.231 + endloop + endfacet + facet normal 0.989003 0.1155 -0.0923722 + outer loop + vertex 883.592 365.003 203.232 + vertex 882.799 371.794 203.231 + vertex 884.372 364.657 211.153 + endloop + endfacet + facet normal 0.99216 0.0822016 -0.0941361 + outer loop + vertex 884.943 357.772 211.154 + vertex 883.592 365.003 203.232 + vertex 884.372 364.657 211.153 + endloop + endfacet + facet normal 0.990131 0.082031 -0.11363 + outer loop + vertex 884.943 357.772 211.154 + vertex 884.372 364.657 211.153 + vertex 885.882 357.298 218.998 + endloop + endfacet + facet normal 0.992295 0.0428315 -0.116256 + outer loop + vertex 886.181 350.37 218.999 + vertex 884.943 357.772 211.154 + vertex 885.882 357.298 218.998 + endloop + endfacet + facet normal 0.990084 0.0802428 -0.115299 + outer loop + vertex 885.882 357.298 218.998 + vertex 884.372 364.657 211.153 + vertex 885.32 364.238 218.998 + endloop + endfacet + facet normal 0.992163 0.0835718 -0.0928859 + outer loop + vertex 884.169 358.159 203.233 + vertex 883.592 365.003 203.232 + vertex 884.943 357.772 211.154 + endloop + endfacet + facet normal 0.994454 0.0451587 -0.0949857 + outer loop + vertex 885.255 350.895 211.155 + vertex 884.169 358.159 203.233 + vertex 884.943 357.772 211.154 + endloop + endfacet + facet normal 0.993777 0.0837086 -0.0734886 + outer loop + vertex 884.169 358.159 203.233 + vertex 882.98 365.268 195.254 + vertex 883.592 365.003 203.232 + endloop + endfacet + facet normal 0.993757 0.0847571 -0.0725513 + outer loop + vertex 883.561 358.457 195.255 + vertex 882.98 365.268 195.254 + vertex 884.169 358.159 203.233 + endloop + endfacet + facet normal 0.996154 0.0466638 -0.0741568 + outer loop + vertex 884.489 351.323 203.233 + vertex 883.561 358.457 195.255 + vertex 884.169 358.159 203.233 + endloop + endfacet + facet normal 0.994957 0.0848605 -0.053473 + outer loop + vertex 883.561 358.457 195.255 + vertex 882.535 365.455 187.268 + vertex 882.98 365.268 195.254 + endloop + endfacet + facet normal 0.991697 0.117376 -0.0525302 + outer loop + vertex 882.535 365.455 187.268 + vertex 881.737 372.191 187.266 + vertex 882.98 365.268 195.254 + endloop + endfacet + facet normal 0.991745 0.11671 -0.0531155 + outer loop + vertex 882.98 365.268 195.254 + vertex 881.737 372.191 187.266 + vertex 882.185 372.026 195.254 + endloop + endfacet + facet normal 0.992488 0.117473 -0.0341605 + outer loop + vertex 882.535 365.455 187.268 + vertex 881.452 372.289 179.322 + vertex 881.737 372.191 187.266 + endloop + endfacet + facet normal 0.988643 0.146464 -0.0336685 + outer loop + vertex 881.452 372.289 179.322 + vertex 880.472 378.906 179.321 + vertex 881.737 372.191 187.266 + endloop + endfacet + facet normal 0.988701 0.145971 -0.0340943 + outer loop + vertex 881.737 372.191 187.266 + vertex 880.472 378.906 179.321 + vertex 880.758 378.824 187.265 + endloop + endfacet + facet normal 0.98908 0.146532 -0.0157854 + outer loop + vertex 881.452 372.289 179.322 + vertex 880.342 378.935 171.446 + vertex 880.472 378.906 179.321 + endloop + endfacet + facet normal 0.984897 0.172438 -0.0156218 + outer loop + vertex 880.342 378.935 171.446 + vertex 879.205 385.428 171.444 + vertex 880.472 378.906 179.321 + endloop + endfacet + facet normal 0.984958 0.172055 -0.0159483 + outer loop + vertex 880.472 378.906 179.321 + vertex 879.205 385.428 171.444 + vertex 879.337 385.406 179.318 + endloop + endfacet + facet normal 0.985014 0.172464 0.00179361 + outer loop + vertex 880.342 378.935 171.446 + vertex 879.223 385.408 163.621 + vertex 879.205 385.428 171.444 + endloop + endfacet + facet normal 0.980694 0.195543 0.00172457 + outer loop + vertex 879.223 385.408 163.621 + vertex 877.949 391.797 163.618 + vertex 879.205 385.428 171.444 + endloop + endfacet + facet normal 0.980742 0.195303 0.00152214 + outer loop + vertex 879.205 385.428 171.444 + vertex 877.949 391.797 163.618 + vertex 877.934 391.813 171.441 + endloop + endfacet + facet normal 0.980523 0.195516 0.0186557 + outer loop + vertex 879.223 385.408 163.621 + vertex 878.108 391.745 155.799 + vertex 877.949 391.797 163.618 + endloop + endfacet + facet normal 0.976142 0.216349 0.0184272 + outer loop + vertex 878.108 391.745 155.799 + vertex 876.709 398.058 155.8 + vertex 877.949 391.797 163.618 + endloop + endfacet + facet normal 0.976169 0.216237 0.0183329 + outer loop + vertex 877.949 391.797 163.618 + vertex 876.709 398.058 155.8 + vertex 876.554 398.094 163.621 + endloop + endfacet + facet normal 0.975719 0.216254 0.034734 + outer loop + vertex 878.108 391.745 155.799 + vertex 877.002 397.996 147.946 + vertex 876.709 398.058 155.8 + endloop + endfacet + facet normal 0.971218 0.235692 0.0344108 + outer loop + vertex 877.002 397.996 147.946 + vertex 875.48 404.268 147.956 + vertex 876.709 398.058 155.8 + endloop + endfacet + facet normal 0.971238 0.235619 0.03435 + outer loop + vertex 876.709 398.058 155.8 + vertex 875.48 404.268 147.956 + vertex 875.193 404.306 155.814 + endloop + endfacet + facet normal 0.970579 0.235514 0.0500909 + outer loop + vertex 877.002 397.996 147.946 + vertex 875.9 404.216 140.065 + vertex 875.48 404.268 147.956 + endloop + endfacet + facet normal 0.965946 0.25392 0.0497224 + outer loop + vertex 875.9 404.216 140.065 + vertex 874.25 410.486 140.084 + vertex 875.48 404.268 147.956 + endloop + endfacet + facet normal 0.965981 0.253808 0.0496281 + outer loop + vertex 875.48 404.268 147.956 + vertex 874.25 410.486 140.084 + vertex 873.841 410.502 147.98 + endloop + endfacet + facet normal 0.96511 0.253653 0.0649902 + outer loop + vertex 875.9 404.216 140.065 + vertex 874.787 410.467 132.186 + vertex 874.25 410.486 140.084 + endloop + endfacet + facet normal 0.960591 0.270346 0.0646424 + outer loop + vertex 874.787 410.467 132.186 + vertex 873.013 416.767 132.21 + vertex 874.25 410.486 140.084 + endloop + endfacet + facet normal 0.960671 0.270108 0.0644402 + outer loop + vertex 874.25 410.486 140.084 + vertex 873.013 416.767 132.21 + vertex 872.493 416.732 140.106 + endloop + endfacet + facet normal 0.959562 0.269999 0.0796276 + outer loop + vertex 874.787 410.467 132.186 + vertex 873.654 416.809 124.339 + vertex 873.013 416.767 132.21 + endloop + endfacet + facet normal 0.955588 0.283815 0.0793783 + outer loop + vertex 873.654 416.809 124.339 + vertex 871.769 423.149 124.356 + vertex 873.013 416.767 132.21 + endloop + endfacet + facet normal 0.955646 0.283658 0.0792415 + outer loop + vertex 873.013 416.767 132.21 + vertex 871.769 423.149 124.356 + vertex 871.154 423.03 132.209 + endloop + endfacet + facet normal 0.954399 0.283423 0.0937723 + outer loop + vertex 873.654 416.809 124.339 + vertex 872.498 423.283 116.541 + vertex 871.769 423.149 124.356 + endloop + endfacet + facet normal 0.951058 0.294479 0.0936494 + outer loop + vertex 872.498 423.283 116.541 + vertex 870.53 429.636 116.541 + vertex 871.769 423.149 124.356 + endloop + endfacet + facet normal 0.951034 0.29454 0.0937032 + outer loop + vertex 871.769 423.149 124.356 + vertex 870.53 429.636 116.541 + vertex 869.836 429.405 124.319 + endloop + endfacet + facet normal 0.949743 0.294072 0.107281 + outer loop + vertex 872.498 423.283 116.541 + vertex 871.328 429.882 108.811 + vertex 870.53 429.636 116.541 + endloop + endfacet + facet normal 0.946439 0.304542 0.107273 + outer loop + vertex 871.328 429.882 108.811 + vertex 869.299 436.192 108.795 + vertex 870.53 429.636 116.541 + endloop + endfacet + facet normal 0.946083 0.305377 0.108037 + outer loop + vertex 870.53 429.636 116.541 + vertex 869.299 436.192 108.795 + vertex 868.539 435.831 116.472 + endloop + endfacet + facet normal 0.940624 0.321724 0.108265 + outer loop + vertex 869.299 436.192 108.795 + vertex 867.232 442.262 108.713 + vertex 868.539 435.831 116.472 + endloop + endfacet + facet normal 0.93896 0.321353 0.122828 + outer loop + vertex 869.299 436.192 108.795 + vertex 868.046 442.77 101.166 + vertex 867.232 442.262 108.713 + endloop + endfacet + facet normal 0.929948 0.346315 0.123538 + outer loop + vertex 868.046 442.77 101.166 + vertex 865.859 448.669 101.092 + vertex 867.232 442.262 108.713 + endloop + endfacet + facet normal 0.926509 0.353141 0.129895 + outer loop + vertex 867.232 442.262 108.713 + vertex 865.859 448.669 101.092 + vertex 865.05 448.005 108.662 + endloop + endfacet + facet normal 0.913867 0.384208 0.131269 + outer loop + vertex 865.859 448.669 101.092 + vertex 863.53 454.206 101.094 + vertex 865.05 448.005 108.662 + endloop + endfacet + facet normal 0.910879 0.382944 0.153794 + outer loop + vertex 865.859 448.669 101.092 + vertex 864.406 455.13 93.6066 + vertex 863.53 454.206 101.094 + endloop + endfacet + facet normal 0.91516 0.372903 0.153055 + outer loop + vertex 864.406 455.13 93.6066 + vertex 862.151 460.651 93.6403 + vertex 863.53 454.206 101.094 + endloop + endfacet + facet normal 0.906029 0.388385 0.168132 + outer loop + vertex 863.53 454.206 101.094 + vertex 862.151 460.651 93.6403 + vertex 861.242 459.473 101.257 + endloop + endfacet + facet normal 0.909549 0.390741 0.141574 + outer loop + vertex 863.53 454.206 101.094 + vertex 861.242 459.473 101.257 + vertex 862.684 453.373 108.834 + endloop + endfacet + facet normal 0.900633 0.405836 0.155424 + outer loop + vertex 862.684 453.373 108.834 + vertex 861.242 459.473 101.257 + vertex 860.346 458.428 109.182 + endloop + endfacet + facet normal 0.903436 0.408979 0.128604 + outer loop + vertex 862.684 453.373 108.834 + vertex 860.346 458.428 109.182 + vertex 861.82 452.739 116.919 + endloop + endfacet + facet normal 0.892812 0.426865 0.143779 + outer loop + vertex 861.82 452.739 116.919 + vertex 860.346 458.428 109.182 + vertex 859.376 457.583 117.715 + endloop + endfacet + facet normal 0.894384 0.432587 0.113777 + outer loop + vertex 861.82 452.739 116.919 + vertex 859.376 457.583 117.715 + vertex 860.831 452.588 125.26 + endloop + endfacet + facet normal 0.861437 0.483917 0.154112 + outer loop + vertex 860.831 452.588 125.26 + vertex 859.376 457.583 117.715 + vertex 859.227 456.011 123.48 + endloop + endfacet + facet normal 0.876002 0.469037 0.112358 + outer loop + vertex 859.227 456.011 123.48 + vertex 858.941 455.55 127.636 + vertex 860.831 452.588 125.26 + endloop + endfacet + facet normal 0.871163 0.482302 0.0919749 + outer loop + vertex 860.144 452.155 134.041 + vertex 860.831 452.588 125.26 + vertex 858.941 455.55 127.636 + endloop + endfacet + facet normal 0.857463 0.503549 0.105815 + outer loop + vertex 858.268 455.864 131.595 + vertex 860.144 452.155 134.041 + vertex 858.941 455.55 127.636 + endloop + endfacet + facet normal 0.865525 0.493662 0.0846382 + outer loop + vertex 858.268 455.864 131.595 + vertex 858.164 455.356 135.626 + vertex 860.144 452.155 134.041 + endloop + endfacet + facet normal 0.861668 0.504049 0.0588432 + outer loop + vertex 858.164 455.356 135.626 + vertex 859.357 452.887 139.299 + vertex 860.144 452.155 134.041 + endloop + endfacet + facet normal 0.879141 0.47198 0.0659209 + outer loop + vertex 860.571 450.625 139.315 + vertex 860.144 452.155 134.041 + vertex 859.357 452.887 139.299 + endloop + endfacet + facet normal 0.879012 0.471925 0.067997 + outer loop + vertex 860.571 450.625 139.315 + vertex 859.357 452.887 139.299 + vertex 860.513 450.174 143.182 + endloop + endfacet + facet normal 0.879545 0.471044 0.0672225 + outer loop + vertex 860.513 450.174 143.182 + vertex 859.357 452.887 139.299 + vertex 858.984 452.974 143.574 + endloop + endfacet + facet normal 0.879472 0.472969 0.0531959 + outer loop + vertex 860.513 450.174 143.182 + vertex 858.984 452.974 143.574 + vertex 860.048 450.608 147.018 + endloop + endfacet + facet normal 0.873611 0.482699 0.0616908 + outer loop + vertex 860.048 450.608 147.018 + vertex 858.984 452.974 143.574 + vertex 858.749 452.871 147.707 + endloop + endfacet + facet normal 0.87331 0.483732 0.0577315 + outer loop + vertex 860.048 450.608 147.018 + vertex 858.749 452.871 147.707 + vertex 860.11 449.98 151.338 + endloop + endfacet + facet normal 0.87626 0.478937 0.0528069 + outer loop + vertex 860.11 449.98 151.338 + vertex 858.749 452.871 147.707 + vertex 858.596 452.705 151.751 + endloop + endfacet + facet normal 0.875812 0.481378 0.0350355 + outer loop + vertex 860.11 449.98 151.338 + vertex 858.596 452.705 151.751 + vertex 859.758 450.347 155.085 + endloop + endfacet + facet normal 0.871711 0.488274 0.0413403 + outer loop + vertex 859.758 450.347 155.085 + vertex 858.596 452.705 151.751 + vertex 858.496 452.549 155.709 + endloop + endfacet + facet normal 0.871308 0.489364 0.0366797 + outer loop + vertex 859.758 450.347 155.085 + vertex 858.496 452.549 155.709 + vertex 859.925 449.74 159.227 + endloop + endfacet + facet normal 0.874849 0.483435 0.0305057 + outer loop + vertex 859.925 449.74 159.227 + vertex 858.496 452.549 155.709 + vertex 858.428 452.426 159.594 + endloop + endfacet + facet normal 0.874173 0.485438 0.013077 + outer loop + vertex 859.925 449.74 159.227 + vertex 858.428 452.426 159.594 + vertex 859.642 450.153 162.835 + endloop + endfacet + facet normal 0.869815 0.492972 0.0199935 + outer loop + vertex 859.642 450.153 162.835 + vertex 858.428 452.426 159.594 + vertex 858.386 452.345 163.437 + endloop + endfacet + facet normal 0.869542 0.493556 0.0173 + outer loop + vertex 859.642 450.153 162.835 + vertex 858.386 452.345 163.437 + vertex 859.866 449.614 166.925 + endloop + endfacet + facet normal 0.873183 0.487273 0.0108359 + outer loop + vertex 859.866 449.614 166.925 + vertex 858.386 452.345 163.437 + vertex 858.369 452.29 167.27 + endloop + endfacet + facet normal 0.872333 0.488882 -0.00533111 + outer loop + vertex 859.866 449.614 166.925 + vertex 858.369 452.29 167.27 + vertex 859.631 450.073 170.53 + endloop + endfacet + facet normal 0.868168 0.496269 0.00130636 + outer loop + vertex 859.631 450.073 170.53 + vertex 858.369 452.29 167.27 + vertex 858.382 452.257 171.133 + endloop + endfacet + facet normal 0.867878 0.496776 -0.00113295 + outer loop + vertex 859.631 450.073 170.53 + vertex 858.382 452.257 171.133 + vertex 859.919 449.58 174.698 + endloop + endfacet + facet normal 0.87199 0.489452 -0.00840812 + outer loop + vertex 859.919 449.58 174.698 + vertex 858.382 452.257 171.133 + vertex 858.424 452.249 175.054 + endloop + endfacet + facet normal 0.870915 0.49087 -0.0235375 + outer loop + vertex 859.919 449.58 174.698 + vertex 858.424 452.249 175.054 + vertex 859.741 450.073 178.398 + endloop + endfacet + facet normal 0.867463 0.497174 -0.0180746 + outer loop + vertex 859.741 450.073 178.398 + vertex 858.424 452.249 175.054 + vertex 858.499 452.262 179.028 + endloop + endfacet + facet normal 0.867226 0.497523 -0.0197536 + outer loop + vertex 859.741 450.073 178.398 + vertex 858.499 452.262 179.028 + vertex 860.097 449.621 182.655 + endloop + endfacet + facet normal 0.871657 0.489335 -0.0276689 + outer loop + vertex 860.097 449.621 182.655 + vertex 858.499 452.262 179.028 + vertex 858.606 452.298 183.034 + endloop + endfacet + facet normal 0.870302 0.490679 -0.0425231 + outer loop + vertex 860.097 449.621 182.655 + vertex 858.606 452.298 183.034 + vertex 859.981 450.152 186.408 + endloop + endfacet + facet normal 0.867633 0.495734 -0.0382197 + outer loop + vertex 859.981 450.152 186.408 + vertex 858.606 452.298 183.034 + vertex 858.748 452.36 187.046 + endloop + endfacet + facet normal 0.867355 0.496082 -0.0399627 + outer loop + vertex 859.981 450.152 186.408 + vertex 858.748 452.36 187.046 + vertex 860.411 449.743 190.673 + endloop + endfacet + facet normal 0.871791 0.487502 -0.0481857 + outer loop + vertex 860.411 449.743 190.673 + vertex 858.748 452.36 187.046 + vertex 858.924 452.44 191.049 + endloop + endfacet + facet normal 0.8702 0.48867 -0.0628829 + outer loop + vertex 860.411 449.743 190.673 + vertex 858.924 452.44 191.049 + vertex 860.361 450.316 194.417 + endloop + endfacet + facet normal 0.867686 0.493638 -0.0586787 + outer loop + vertex 860.361 450.316 194.417 + vertex 858.924 452.44 191.049 + vertex 859.137 452.542 195.047 + endloop + endfacet + facet normal 0.867383 0.493961 -0.06041 + outer loop + vertex 860.361 450.316 194.417 + vertex 859.137 452.542 195.047 + vertex 860.865 449.95 198.669 + endloop + endfacet + facet normal 0.872259 0.484031 -0.0698403 + outer loop + vertex 860.865 449.95 198.669 + vertex 859.137 452.542 195.047 + vertex 859.383 452.674 199.046 + endloop + endfacet + facet normal 0.870371 0.485058 -0.0846952 + outer loop + vertex 860.865 449.95 198.669 + vertex 859.383 452.674 199.046 + vertex 860.877 450.581 202.402 + endloop + endfacet + facet normal 0.867888 0.490215 -0.0803742 + outer loop + vertex 860.877 450.581 202.402 + vertex 859.383 452.674 199.046 + vertex 859.66 452.838 203.031 + endloop + endfacet + facet normal 0.86788 0.490222 -0.0804155 + outer loop + vertex 860.877 450.581 202.402 + vertex 859.66 452.838 203.031 + vertex 861.443 450.267 206.607 + endloop + endfacet + facet normal 0.872683 0.479874 -0.0902501 + outer loop + vertex 861.443 450.267 206.607 + vertex 859.66 452.838 203.031 + vertex 859.961 453.032 206.974 + endloop + endfacet + facet normal 0.870621 0.480686 -0.104691 + outer loop + vertex 861.443 450.267 206.607 + vertex 859.961 453.032 206.974 + vertex 861.506 450.951 210.264 + endloop + endfacet + facet normal 0.868843 0.484597 -0.101383 + outer loop + vertex 861.506 450.951 210.264 + vertex 859.961 453.032 206.974 + vertex 860.296 453.245 210.858 + endloop + endfacet + facet normal 0.868645 0.484746 -0.102362 + outer loop + vertex 861.506 450.951 210.264 + vertex 860.296 453.245 210.858 + vertex 862.164 450.641 214.379 + endloop + endfacet + facet normal 0.873902 0.472496 -0.114207 + outer loop + vertex 862.164 450.641 214.379 + vertex 860.296 453.245 210.858 + vertex 860.687 453.457 214.734 + endloop + endfacet + facet normal 0.871575 0.473089 -0.128626 + outer loop + vertex 862.164 450.641 214.379 + vertex 860.687 453.457 214.734 + vertex 862.349 451.3 218.064 + endloop + endfacet + facet normal 0.870759 0.475039 -0.126956 + outer loop + vertex 862.349 451.3 218.064 + vertex 860.687 453.457 214.734 + vertex 861.168 453.654 218.766 + endloop + endfacet + facet normal 0.871537 0.474465 -0.12372 + outer loop + vertex 862.349 451.3 218.064 + vertex 861.168 453.654 218.766 + vertex 863.251 450.828 222.604 + endloop + endfacet + facet normal 0.876625 0.461561 -0.135981 + outer loop + vertex 863.251 450.828 222.604 + vertex 861.168 453.654 218.766 + vertex 861.699 453.949 223.189 + endloop + endfacet + facet normal 0.875285 0.462124 -0.142539 + outer loop + vertex 863.251 450.828 222.604 + vertex 861.699 453.949 223.189 + vertex 863.922 451.316 228.304 + endloop + endfacet + facet normal 0.873545 0.466283 -0.139641 + outer loop + vertex 863.922 451.316 228.304 + vertex 861.699 453.949 223.189 + vertex 861.89 454.877 227.488 + endloop + endfacet + facet normal 0.873035 0.462703 -0.154 + outer loop + vertex 863.922 451.316 228.304 + vertex 861.89 454.877 227.488 + vertex 863.977 453.261 234.46 + endloop + endfacet + facet normal 0.848651 0.511321 -0.135432 + outer loop + vertex 861.89 454.877 227.488 + vertex 861.175 456.656 229.722 + vertex 863.977 453.261 234.46 + endloop + endfacet + facet normal 0.858954 0.486683 -0.159179 + outer loop + vertex 861.631 456.983 233.183 + vertex 863.977 453.261 234.46 + vertex 861.175 456.656 229.722 + endloop + endfacet + facet normal 0.858908 0.480109 -0.178246 + outer loop + vertex 861.631 456.983 233.183 + vertex 862.761 456.6 237.596 + vertex 863.977 453.261 234.46 + endloop + endfacet + facet normal 0.862725 0.475554 -0.171913 + outer loop + vertex 865.754 453.028 242.734 + vertex 863.977 453.261 234.46 + vertex 862.761 456.6 237.596 + endloop + endfacet + facet normal 0.86774 0.46145 -0.184639 + outer loop + vertex 863.792 457.009 243.464 + vertex 865.754 453.028 242.734 + vertex 862.761 456.6 237.596 + endloop + endfacet + facet normal 0.866148 0.461839 -0.191032 + outer loop + vertex 865.754 453.028 242.734 + vertex 863.792 457.009 243.464 + vertex 867.014 453.577 249.777 + endloop + endfacet + facet normal 0.873913 0.439817 -0.206971 + outer loop + vertex 867.014 453.577 249.777 + vertex 863.792 457.009 243.464 + vertex 864.717 458.199 249.896 + endloop + endfacet + facet normal 0.8738 0.439775 -0.207536 + outer loop + vertex 867.014 453.577 249.777 + vertex 864.717 458.199 249.896 + vertex 868.256 454.454 256.865 + endloop + endfacet + facet normal 0.880707 0.418025 -0.222734 + outer loop + vertex 868.256 454.454 256.865 + vertex 864.717 458.199 249.896 + vertex 865.844 459.579 256.942 + endloop + endfacet + facet normal 0.880636 0.417997 -0.223068 + outer loop + vertex 868.256 454.454 256.865 + vertex 865.844 459.579 256.942 + vertex 869.666 455.372 264.15 + endloop + endfacet + facet normal 0.883992 0.405938 -0.231886 + outer loop + vertex 869.666 455.372 264.15 + vertex 865.844 459.579 256.942 + vertex 867.255 460.711 264.304 + endloop + endfacet + facet normal 0.882897 0.40558 -0.236637 + outer loop + vertex 869.666 455.372 264.15 + vertex 867.255 460.711 264.304 + vertex 871.205 456.225 271.353 + endloop + endfacet + facet normal 0.886256 0.391569 -0.247436 + outer loop + vertex 871.205 456.225 271.353 + vertex 867.255 460.711 264.304 + vertex 868.758 461.845 271.483 + endloop + endfacet + facet normal 0.886147 0.391533 -0.247881 + outer loop + vertex 871.205 456.225 271.353 + vertex 868.758 461.845 271.483 + vertex 872.697 457.069 278.018 + endloop + endfacet + facet normal 0.888792 0.377719 -0.259571 + outer loop + vertex 872.697 457.069 278.018 + vertex 868.758 461.845 271.483 + vertex 870.16 463.129 278.15 + endloop + endfacet + facet normal 0.888713 0.377693 -0.259878 + outer loop + vertex 872.697 457.069 278.018 + vertex 870.16 463.129 278.15 + vertex 873.936 458.104 283.763 + endloop + endfacet + facet normal 0.891186 0.356533 -0.280484 + outer loop + vertex 873.936 458.104 283.763 + vertex 870.16 463.129 278.15 + vertex 871.368 465.177 284.594 + endloop + endfacet + facet normal 0.892139 0.356523 -0.277451 + outer loop + vertex 873.936 458.104 283.763 + vertex 871.368 465.177 284.594 + vertex 874.922 459.142 288.264 + endloop + endfacet + facet normal 0.891733 0.35213 -0.284283 + outer loop + vertex 874.922 459.142 288.264 + vertex 871.368 465.177 284.594 + vertex 873.125 464.481 289.242 + endloop + endfacet + facet normal 0.885305 0.353278 -0.302372 + outer loop + vertex 874.922 459.142 288.264 + vertex 873.125 464.481 289.242 + vertex 875.482 460.583 291.59 + endloop + endfacet + facet normal 0.885811 0.357527 -0.295827 + outer loop + vertex 875.482 460.583 291.59 + vertex 873.125 464.481 289.242 + vertex 873.514 465.984 292.223 + endloop + endfacet + facet normal 0.836435 0.526687 -0.151585 + outer loop + vertex 860.3 456.985 226.038 + vertex 861.175 456.656 229.722 + vertex 861.89 454.877 227.488 + endloop + endfacet + facet normal 0.835744 0.528912 -0.147593 + outer loop + vertex 861.89 454.877 227.488 + vertex 860.165 456.359 223.032 + vertex 860.3 456.985 226.038 + endloop + endfacet + facet normal 0.838577 0.523595 -0.150459 + outer loop + vertex 861.699 453.949 223.189 + vertex 860.165 456.359 223.032 + vertex 861.89 454.877 227.488 + endloop + endfacet + facet normal 0.839422 0.524711 -0.141598 + outer loop + vertex 861.699 453.949 223.189 + vertex 859.785 455.902 219.082 + vertex 860.165 456.359 223.032 + endloop + endfacet + facet normal 0.835236 0.532867 -0.135769 + outer loop + vertex 861.168 453.654 218.766 + vertex 859.785 455.902 219.082 + vertex 861.699 453.949 223.189 + endloop + endfacet + facet normal 0.836217 0.532698 -0.13028 + outer loop + vertex 861.168 453.654 218.766 + vertex 859.337 455.619 215.053 + vertex 859.785 455.902 219.082 + endloop + endfacet + facet normal 0.833098 0.538683 -0.125572 + outer loop + vertex 860.687 453.457 214.734 + vertex 859.337 455.619 215.053 + vertex 861.168 453.654 218.766 + endloop + endfacet + facet normal 0.8342 0.538428 -0.119192 + outer loop + vertex 860.687 453.457 214.734 + vertex 858.929 455.386 211.138 + vertex 859.337 455.619 215.053 + endloop + endfacet + facet normal 0.830572 0.545159 -0.113805 + outer loop + vertex 860.296 453.245 210.858 + vertex 858.929 455.386 211.138 + vertex 860.687 453.457 214.734 + endloop + endfacet + facet normal 0.831963 0.544858 -0.104726 + outer loop + vertex 860.296 453.245 210.858 + vertex 858.588 455.158 207.251 + vertex 858.929 455.386 211.138 + endloop + endfacet + facet normal 0.829715 0.548875 -0.101531 + outer loop + vertex 859.961 453.032 206.974 + vertex 858.588 455.158 207.251 + vertex 860.296 453.245 210.858 + endloop + endfacet + facet normal 0.830851 0.548572 -0.0935681 + outer loop + vertex 859.961 453.032 206.974 + vertex 858.285 454.947 203.321 + vertex 858.588 455.158 207.251 + endloop + endfacet + facet normal 0.828584 0.552507 -0.0904646 + outer loop + vertex 859.66 452.838 203.031 + vertex 858.285 454.947 203.321 + vertex 859.961 453.032 206.974 + endloop + endfacet + facet normal 0.829572 0.55216 -0.0832452 + outer loop + vertex 859.66 452.838 203.031 + vertex 858.005 454.769 199.347 + vertex 858.285 454.947 203.321 + endloop + endfacet + facet normal 0.82734 0.555937 -0.0802615 + outer loop + vertex 859.383 452.674 199.046 + vertex 858.005 454.769 199.347 + vertex 859.66 452.838 203.031 + endloop + endfacet + facet normal 0.82851 0.555417 -0.0712932 + outer loop + vertex 859.383 452.674 199.046 + vertex 857.756 454.628 195.354 + vertex 858.005 454.769 199.347 + endloop + endfacet + facet normal 0.827139 0.557685 -0.0694891 + outer loop + vertex 859.137 452.542 195.047 + vertex 857.756 454.628 195.354 + vertex 859.383 452.674 199.046 + endloop + endfacet + facet normal 0.828157 0.557143 -0.0612245 + outer loop + vertex 859.137 452.542 195.047 + vertex 857.543 454.505 191.35 + vertex 857.756 454.628 195.354 + endloop + endfacet + facet normal 0.825791 0.560968 -0.0581728 + outer loop + vertex 858.924 452.44 191.049 + vertex 857.543 454.505 191.35 + vertex 859.137 452.542 195.047 + endloop + endfacet + facet normal 0.826783 0.560348 -0.0493958 + outer loop + vertex 858.924 452.44 191.049 + vertex 857.364 454.416 187.35 + vertex 857.543 454.505 191.35 + endloop + endfacet + facet normal 0.82539 0.56255 -0.0476313 + outer loop + vertex 858.748 452.36 187.046 + vertex 857.364 454.416 187.35 + vertex 858.924 452.44 191.049 + endloop + endfacet + facet normal 0.826307 0.561875 -0.0389072 + outer loop + vertex 858.748 452.36 187.046 + vertex 857.222 454.347 183.342 + vertex 857.364 454.416 187.35 + endloop + endfacet + facet normal 0.825398 0.563285 -0.0377763 + outer loop + vertex 858.606 452.298 183.034 + vertex 857.222 454.347 183.342 + vertex 858.748 452.36 187.046 + endloop + endfacet + facet normal 0.826494 0.562323 -0.0264656 + outer loop + vertex 858.606 452.298 183.034 + vertex 857.121 454.307 179.338 + vertex 857.222 454.347 183.342 + endloop + endfacet + facet normal 0.827023 0.561514 -0.0271182 + outer loop + vertex 858.499 452.262 179.028 + vertex 857.121 454.307 179.338 + vertex 858.606 452.298 183.034 + endloop + endfacet + facet normal 0.827718 0.560809 -0.0193731 + outer loop + vertex 858.499 452.262 179.028 + vertex 857.037 454.294 175.362 + vertex 857.121 454.307 179.338 + endloop + endfacet + facet normal 0.826208 0.563094 -0.0175046 + outer loop + vertex 858.424 452.249 175.054 + vertex 857.037 454.294 175.362 + vertex 858.499 452.262 179.028 + endloop + endfacet + facet normal 0.826995 0.562157 -0.00773534 + outer loop + vertex 858.424 452.249 175.054 + vertex 856.993 454.304 171.435 + vertex 857.037 454.294 175.362 + endloop + endfacet + facet normal 0.827031 0.562103 -0.00778033 + outer loop + vertex 858.382 452.257 171.133 + vertex 856.993 454.304 171.435 + vertex 858.424 452.249 175.054 + endloop + endfacet + facet normal 0.827773 0.561056 0.00272674 + outer loop + vertex 858.382 452.257 171.133 + vertex 856.978 454.345 167.568 + vertex 856.993 454.304 171.435 + endloop + endfacet + facet normal 0.828363 0.560189 0.00198721 + outer loop + vertex 858.369 452.29 167.27 + vertex 856.978 454.345 167.568 + vertex 858.382 452.257 171.133 + endloop + endfacet + facet normal 0.829 0.559111 0.0123908 + outer loop + vertex 858.369 452.29 167.27 + vertex 856.996 454.404 163.727 + vertex 856.978 454.345 167.568 + endloop + endfacet + facet normal 0.829592 0.558249 0.0116473 + outer loop + vertex 858.386 452.345 163.437 + vertex 856.996 454.404 163.727 + vertex 858.369 452.29 167.27 + endloop + endfacet + facet normal 0.830167 0.557041 0.0229902 + outer loop + vertex 858.386 452.345 163.437 + vertex 857.04 454.498 159.878 + vertex 856.996 454.404 163.727 + endloop + endfacet + facet normal 0.831853 0.554604 0.0208785 + outer loop + vertex 858.428 452.426 159.594 + vertex 857.04 454.498 159.878 + vertex 858.386 452.345 163.437 + endloop + endfacet + facet normal 0.832388 0.55314 0.0341567 + outer loop + vertex 858.428 452.426 159.594 + vertex 857.112 454.629 155.982 + vertex 857.04 454.498 159.878 + endloop + endfacet + facet normal 0.83419 0.550552 0.0319213 + outer loop + vertex 858.496 452.549 155.709 + vertex 857.112 454.629 155.982 + vertex 858.428 452.426 159.594 + endloop + endfacet + facet normal 0.8346 0.548845 0.0470372 + outer loop + vertex 858.496 452.549 155.709 + vertex 857.217 454.808 152.03 + vertex 857.112 454.629 155.982 + endloop + endfacet + facet normal 0.838158 0.543755 0.0426745 + outer loop + vertex 858.596 452.705 151.751 + vertex 857.217 454.808 152.03 + vertex 858.496 452.549 155.709 + endloop + endfacet + facet normal 0.838393 0.542327 0.0545752 + outer loop + vertex 858.596 452.705 151.751 + vertex 857.343 455.016 148.035 + vertex 857.217 454.808 152.03 + endloop + endfacet + facet normal 0.838885 0.541626 0.053973 + outer loop + vertex 858.749 452.871 147.707 + vertex 857.343 455.016 148.035 + vertex 858.596 452.705 151.751 + endloop + endfacet + facet normal 0.839095 0.540114 0.0647746 + outer loop + vertex 858.749 452.871 147.707 + vertex 857.536 455.201 143.993 + vertex 857.343 455.016 148.035 + endloop + endfacet + facet normal 0.84202 0.535962 0.0612147 + outer loop + vertex 858.984 452.974 143.574 + vertex 857.536 455.201 143.993 + vertex 858.749 452.871 147.707 + endloop + endfacet + facet normal 0.842307 0.534287 0.0711017 + outer loop + vertex 858.984 452.974 143.574 + vertex 857.807 455.319 139.894 + vertex 857.536 455.201 143.993 + endloop + endfacet + facet normal 0.848526 0.525341 0.0634101 + outer loop + vertex 859.357 452.887 139.299 + vertex 857.807 455.319 139.894 + vertex 858.984 452.974 143.574 + endloop + endfacet + facet normal 0.849126 0.522766 0.0755004 + outer loop + vertex 857.807 455.319 139.894 + vertex 859.357 452.887 139.299 + vertex 858.164 455.356 135.626 + endloop + endfacet + facet normal 0.910929 0.371007 0.180451 + outer loop + vertex 864.406 455.13 93.6066 + vertex 863.099 461.923 86.2404 + vertex 862.151 460.651 93.6403 + endloop + endfacet + facet normal 0.920535 0.354702 0.16371 + outer loop + vertex 865.331 456.113 86.2749 + vertex 863.099 461.923 86.2404 + vertex 864.406 455.13 93.6066 + endloop + endfacet + facet normal 0.914378 0.369736 0.164948 + outer loop + vertex 866.723 449.368 93.6788 + vertex 865.331 456.113 86.2749 + vertex 864.406 455.13 93.6066 + endloop + endfacet + facet normal 0.921328 0.357594 0.152581 + outer loop + vertex 867.65 450.1 86.3675 + vertex 865.331 456.113 86.2749 + vertex 866.723 449.368 93.6788 + endloop + endfacet + facet normal 0.9288 0.338161 0.151584 + outer loop + vertex 868.929 443.288 93.7279 + vertex 867.65 450.1 86.3675 + vertex 866.723 449.368 93.6788 + endloop + endfacet + facet normal 0.931211 0.338895 0.134154 + outer loop + vertex 868.929 443.288 93.7279 + vertex 866.723 449.368 93.6788 + vertex 868.046 442.77 101.166 + endloop + endfacet + facet normal 0.938639 0.317982 0.13358 + outer loop + vertex 870.144 436.564 101.194 + vertex 868.929 443.288 93.7279 + vertex 868.046 442.77 101.166 + endloop + endfacet + facet normal 0.939954 0.315212 0.130871 + outer loop + vertex 871.06 436.938 93.7108 + vertex 868.929 443.288 93.7279 + vertex 870.144 436.564 101.194 + endloop + endfacet + facet normal 0.944058 0.302753 0.130749 + outer loop + vertex 872.208 430.138 101.171 + vertex 871.06 436.938 93.7108 + vertex 870.144 436.564 101.194 + endloop + endfacet + facet normal 0.94544 0.30324 0.11912 + outer loop + vertex 872.208 430.138 101.171 + vertex 870.144 436.564 101.194 + vertex 871.328 429.882 108.811 + endloop + endfacet + facet normal 0.948555 0.293339 0.119148 + outer loop + vertex 873.325 423.431 108.788 + vertex 872.208 430.138 101.171 + vertex 871.328 429.882 108.811 + endloop + endfacet + facet normal 0.948765 0.292847 0.118684 + outer loop + vertex 874.235 423.584 101.141 + vertex 872.208 430.138 101.171 + vertex 873.325 423.431 108.788 + endloop + endfacet + facet normal 0.951963 0.282207 0.118851 + outer loop + vertex 875.257 416.923 108.771 + vertex 874.235 423.584 101.141 + vertex 873.325 423.431 108.788 + endloop + endfacet + facet normal 0.953261 0.282624 0.106853 + outer loop + vertex 875.257 416.923 108.771 + vertex 873.325 423.431 108.788 + vertex 874.406 416.862 116.519 + endloop + endfacet + facet normal 0.957168 0.268968 0.107175 + outer loop + vertex 876.215 410.428 116.509 + vertex 875.257 416.923 108.771 + vertex 874.406 416.862 116.519 + endloop + endfacet + facet normal 0.958458 0.269352 0.0938472 + outer loop + vertex 876.215 410.428 116.509 + vertex 874.406 416.862 116.519 + vertex 875.445 410.447 124.32 + endloop + endfacet + facet normal 0.962882 0.252904 0.0943224 + outer loop + vertex 877.12 404.073 124.316 + vertex 876.215 410.428 116.509 + vertex 875.445 410.447 124.32 + endloop + endfacet + facet normal 0.964098 0.253233 0.0799222 + outer loop + vertex 877.12 404.073 124.316 + vertex 875.445 410.447 124.32 + vertex 876.448 404.15 132.173 + endloop + endfacet + facet normal 0.968626 0.23513 0.0804858 + outer loop + vertex 877.991 397.796 132.173 + vertex 877.12 404.073 124.316 + vertex 876.448 404.15 132.173 + endloop + endfacet + facet normal 0.969692 0.235389 0.0654984 + outer loop + vertex 877.991 397.796 132.173 + vertex 876.448 404.15 132.173 + vertex 877.431 397.908 140.061 + endloop + endfacet + facet normal 0.974105 0.216222 0.0660833 + outer loop + vertex 878.846 391.534 140.063 + vertex 877.991 397.796 132.173 + vertex 877.431 397.908 140.061 + endloop + endfacet + facet normal 0.974984 0.216412 0.0507105 + outer loop + vertex 878.846 391.534 140.063 + vertex 877.431 397.908 140.061 + vertex 878.408 391.656 147.947 + endloop + endfacet + facet normal 0.979324 0.19569 0.0512742 + outer loop + vertex 879.693 385.225 147.95 + vertex 878.846 391.534 140.063 + vertex 878.408 391.656 147.947 + endloop + endfacet + facet normal 0.980002 0.19582 0.0353785 + outer loop + vertex 879.693 385.225 147.95 + vertex 878.408 391.656 147.947 + vertex 879.387 385.339 155.802 + endloop + endfacet + facet normal 0.9843 0.172816 0.0358806 + outer loop + vertex 880.531 378.823 155.804 + vertex 879.693 385.225 147.95 + vertex 879.387 385.339 155.802 + endloop + endfacet + facet normal 0.984751 0.172892 0.0193278 + outer loop + vertex 880.531 378.823 155.804 + vertex 879.387 385.339 155.802 + vertex 880.363 378.906 163.623 + endloop + endfacet + facet normal 0.988913 0.147182 0.0196911 + outer loop + vertex 881.348 372.286 163.624 + vertex 880.531 378.823 155.804 + vertex 880.363 378.906 163.623 + endloop + endfacet + facet normal 0.989103 0.147208 0.00234969 + outer loop + vertex 881.348 372.286 163.624 + vertex 880.363 378.906 163.623 + vertex 881.324 372.32 171.447 + endloop + endfacet + facet normal 0.992945 0.118548 0.00248675 + outer loop + vertex 882.126 365.602 171.448 + vertex 881.348 372.286 163.624 + vertex 881.324 372.32 171.447 + endloop + endfacet + facet normal 0.992831 0.118534 -0.015395 + outer loop + vertex 882.126 365.602 171.448 + vertex 881.324 372.32 171.447 + vertex 882.253 365.568 179.323 + endloop + endfacet + facet normal 0.996125 0.0865536 -0.0155876 + outer loop + vertex 882.841 358.793 179.323 + vertex 882.126 365.602 171.448 + vertex 882.253 365.568 179.323 + endloop + endfacet + facet normal 0.995681 0.0865144 -0.0336889 + outer loop + vertex 882.841 358.793 179.323 + vertex 882.253 365.568 179.323 + vertex 883.121 358.669 187.267 + endloop + endfacet + facet normal 0.998211 0.0489349 -0.0343659 + outer loop + vertex 883.453 351.887 187.269 + vertex 882.841 358.793 179.323 + vertex 883.121 358.669 187.267 + endloop + endfacet + facet normal 0.995709 0.0860244 -0.0341175 + outer loop + vertex 883.121 358.669 187.267 + vertex 882.253 365.568 179.323 + vertex 882.535 365.455 187.268 + endloop + endfacet + facet normal 0.996091 0.0870217 -0.0151797 + outer loop + vertex 882.718 358.832 171.448 + vertex 882.126 365.602 171.448 + vertex 882.841 358.793 179.323 + endloop + endfacet + facet normal 0.998634 0.0499376 -0.0154029 + outer loop + vertex 883.18 352.025 179.323 + vertex 882.718 358.832 171.448 + vertex 882.841 358.793 179.323 + endloop + endfacet + facet normal 0.996201 0.0870315 0.00301838 + outer loop + vertex 882.718 358.832 171.448 + vertex 882.154 365.564 163.624 + vertex 882.126 365.602 171.448 + endloop + endfacet + facet normal 0.996197 0.0870733 0.00305461 + outer loop + vertex 882.746 358.786 163.624 + vertex 882.154 365.564 163.624 + vertex 882.718 358.832 171.448 + endloop + endfacet + facet normal 0.998719 0.050495 0.00327894 + outer loop + vertex 883.06 352.068 171.448 + vertex 882.746 358.786 163.624 + vertex 882.718 358.832 171.448 + endloop + endfacet + facet normal 0.998697 0.0509075 0.00363402 + outer loop + vertex 883.091 352.017 163.624 + vertex 882.746 358.786 163.624 + vertex 883.06 352.068 171.448 + endloop + endfacet + facet normal 0.998466 0.050896 0.0218217 + outer loop + vertex 883.091 352.017 163.624 + vertex 882.923 358.657 155.804 + vertex 882.746 358.786 163.624 + endloop + endfacet + facet normal 0.995951 0.0873767 0.0211612 + outer loop + vertex 882.923 358.657 155.804 + vertex 882.328 365.448 155.804 + vertex 882.746 358.786 163.624 + endloop + endfacet + facet normal 0.995437 0.0873318 0.0384496 + outer loop + vertex 882.923 358.657 155.804 + vertex 882.648 365.257 147.951 + vertex 882.328 365.448 155.804 + endloop + endfacet + facet normal 0.992195 0.11891 0.0375503 + outer loop + vertex 882.648 365.257 147.951 + vertex 881.837 372.022 147.951 + vertex 882.328 365.448 155.804 + endloop + endfacet + facet normal 0.992182 0.118991 0.0376185 + outer loop + vertex 882.328 365.448 155.804 + vertex 881.837 372.022 147.951 + vertex 881.52 372.185 155.804 + endloop + endfacet + facet normal 0.99268 0.11905 0.020339 + outer loop + vertex 882.328 365.448 155.804 + vertex 881.52 372.185 155.804 + vertex 882.154 365.564 163.624 + endloop + endfacet + facet normal 0.992695 0.118942 0.0202467 + outer loop + vertex 882.154 365.564 163.624 + vertex 881.52 372.185 155.804 + vertex 881.348 372.286 163.624 + endloop + endfacet + facet normal 0.988388 0.147409 0.0368721 + outer loop + vertex 881.837 372.022 147.951 + vertex 880.843 378.684 147.951 + vertex 881.52 372.185 155.804 + endloop + endfacet + facet normal 0.988419 0.147239 0.0367289 + outer loop + vertex 881.52 372.185 155.804 + vertex 880.843 378.684 147.951 + vertex 880.531 378.823 155.804 + endloop + endfacet + facet normal 0.987662 0.147301 0.0531624 + outer loop + vertex 881.837 372.022 147.951 + vertex 881.297 378.488 140.065 + vertex 880.843 378.684 147.951 + endloop + endfacet + facet normal 0.983519 0.173083 0.0522816 + outer loop + vertex 881.297 378.488 140.065 + vertex 880.139 385.066 140.064 + vertex 880.843 378.684 147.951 + endloop + endfacet + facet normal 0.983544 0.172966 0.0521848 + outer loop + vertex 880.843 378.684 147.951 + vertex 880.139 385.066 140.064 + vertex 879.693 385.225 147.95 + endloop + endfacet + facet normal 0.982581 0.172919 0.0680634 + outer loop + vertex 881.297 378.488 140.065 + vertex 880.722 384.86 132.176 + vertex 880.139 385.066 140.064 + endloop + endfacet + facet normal 0.97831 0.195962 0.0671465 + outer loop + vertex 880.722 384.86 132.176 + vertex 879.417 391.374 132.175 + vertex 880.139 385.066 140.064 + endloop + endfacet + facet normal 0.978361 0.195762 0.0669823 + outer loop + vertex 880.139 385.066 140.064 + vertex 879.417 391.374 132.175 + vertex 878.846 391.534 140.063 + endloop + endfacet + facet normal 0.977184 0.195738 0.0824499 + outer loop + vertex 880.722 384.86 132.176 + vertex 880.119 391.182 124.319 + vertex 879.417 391.374 132.175 + endloop + endfacet + facet normal 0.972881 0.216452 0.0815588 + outer loop + vertex 880.119 391.182 124.319 + vertex 878.677 397.662 124.317 + vertex 879.417 391.374 132.175 + endloop + endfacet + facet normal 0.972957 0.216189 0.0813412 + outer loop + vertex 879.417 391.374 132.175 + vertex 878.677 397.662 124.317 + vertex 877.991 397.796 132.173 + endloop + endfacet + facet normal 0.971622 0.216176 0.0960118 + outer loop + vertex 880.119 391.182 124.319 + vertex 879.484 397.502 116.512 + vertex 878.677 397.662 124.317 + endloop + endfacet + facet normal 0.967275 0.235203 0.0951736 + outer loop + vertex 879.484 397.502 116.512 + vertex 877.908 403.984 116.509 + vertex 878.677 397.662 124.317 + endloop + endfacet + facet normal 0.967339 0.235007 0.0950082 + outer loop + vertex 878.677 397.662 124.317 + vertex 877.908 403.984 116.509 + vertex 877.12 404.073 124.316 + endloop + endfacet + facet normal 0.965966 0.23489 0.108331 + outer loop + vertex 879.484 397.502 116.512 + vertex 878.803 403.874 108.772 + vertex 877.908 403.984 116.509 + endloop + endfacet + facet normal 0.96156 0.252648 0.107571 + outer loop + vertex 878.803 403.874 108.772 + vertex 877.087 410.403 108.769 + vertex 877.908 403.984 116.509 + endloop + endfacet + facet normal 0.961578 0.252598 0.107528 + outer loop + vertex 877.908 403.984 116.509 + vertex 877.087 410.403 108.769 + vertex 876.215 410.428 116.509 + endloop + endfacet + facet normal 0.960268 0.252314 0.11926 + outer loop + vertex 878.803 403.874 108.772 + vertex 878.047 410.359 101.134 + vertex 877.087 410.403 108.769 + endloop + endfacet + facet normal 0.956032 0.268195 0.118636 + outer loop + vertex 878.047 410.359 101.134 + vertex 876.191 416.976 101.132 + vertex 877.087 410.403 108.769 + endloop + endfacet + facet normal 0.955956 0.268388 0.118811 + outer loop + vertex 877.087 410.403 108.769 + vertex 876.191 416.976 101.132 + vertex 875.257 416.923 108.771 + endloop + endfacet + facet normal 0.954758 0.26784 0.129222 + outer loop + vertex 878.047 410.359 101.134 + vertex 877.195 417.013 93.6424 + vertex 876.191 416.976 101.132 + endloop + endfacet + facet normal 0.951051 0.280919 0.128789 + outer loop + vertex 877.195 417.013 93.6424 + vertex 875.211 423.726 93.6463 + vertex 876.191 416.976 101.132 + endloop + endfacet + facet normal 0.95086 0.281368 0.129218 + outer loop + vertex 876.191 416.976 101.132 + vertex 875.211 423.726 93.6463 + vertex 874.235 423.584 101.141 + endloop + endfacet + facet normal 0.947759 0.291733 0.129011 + outer loop + vertex 875.211 423.726 93.6463 + vertex 873.156 430.392 93.6706 + vertex 874.235 423.584 101.141 + endloop + endfacet + facet normal 0.946418 0.291282 0.139459 + outer loop + vertex 875.211 423.726 93.6463 + vertex 874.16 430.641 86.3345 + vertex 873.156 430.392 93.6706 + endloop + endfacet + facet normal 0.94383 0.299594 0.139387 + outer loop + vertex 874.16 430.641 86.3345 + vertex 872.037 437.317 86.3667 + vertex 873.156 430.392 93.6706 + endloop + endfacet + facet normal 0.943143 0.301055 0.140878 + outer loop + vertex 873.156 430.392 93.6706 + vertex 872.037 437.317 86.3667 + vertex 871.06 436.938 93.7108 + endloop + endfacet + facet normal 0.93975 0.311449 0.140962 + outer loop + vertex 872.037 437.317 86.3667 + vertex 869.877 443.821 86.3932 + vertex 871.06 436.938 93.7108 + endloop + endfacet + facet normal 0.93789 0.310777 0.15421 + outer loop + vertex 872.037 437.317 86.3667 + vertex 870.879 444.39 79.1553 + vertex 869.877 443.821 86.3932 + endloop + endfacet + facet normal 0.933452 0.323671 0.154609 + outer loop + vertex 870.879 444.39 79.1553 + vertex 868.634 450.878 79.1256 + vertex 869.877 443.821 86.3932 + endloop + endfacet + facet normal 0.929831 0.330485 0.161843 + outer loop + vertex 869.877 443.821 86.3932 + vertex 868.634 450.878 79.1256 + vertex 867.65 450.1 86.3675 + endloop + endfacet + facet normal 0.924583 0.344521 0.162638 + outer loop + vertex 868.634 450.878 79.1256 + vertex 866.31 457.158 79.0361 + vertex 867.65 450.1 86.3675 + endloop + endfacet + facet normal 0.920936 0.343477 0.184119 + outer loop + vertex 868.634 450.878 79.1256 + vertex 867.315 458.266 71.9395 + vertex 866.31 457.158 79.0361 + endloop + endfacet + facet normal 0.929194 0.321736 0.181892 + outer loop + vertex 867.315 458.266 71.9395 + vertex 865.09 464.694 71.9355 + vertex 866.31 457.158 79.0361 + endloop + endfacet + facet normal 0.919974 0.33719 0.199878 + outer loop + vertex 866.31 457.158 79.0361 + vertex 865.09 464.694 71.9355 + vertex 864.079 463.273 78.9874 + endloop + endfacet + facet normal 0.924693 0.338704 0.173844 + outer loop + vertex 866.31 457.158 79.0361 + vertex 864.079 463.273 78.9874 + vertex 865.331 456.113 86.2749 + endloop + endfacet + facet normal 0.953973 0.236459 0.184451 + outer loop + vertex 865.09 464.694 71.9355 + vertex 863.449 471.136 72.1618 + vertex 864.079 463.273 78.9874 + endloop + endfacet + facet normal 0.948461 0.247594 0.197787 + outer loop + vertex 864.079 463.273 78.9874 + vertex 863.449 471.136 72.1618 + vertex 862.437 469.408 79.1796 + endloop + endfacet + facet normal 0.952445 0.24937 0.17511 + outer loop + vertex 864.079 463.273 78.9874 + vertex 862.437 469.408 79.1796 + vertex 863.099 461.923 86.2404 + endloop + endfacet + facet normal 0.945587 0.263559 0.190794 + outer loop + vertex 863.099 461.923 86.2404 + vertex 862.437 469.408 79.1796 + vertex 861.449 467.774 86.3325 + endloop + endfacet + facet normal 0.949623 0.265069 0.167197 + outer loop + vertex 863.099 461.923 86.2404 + vertex 861.449 467.774 86.3325 + vertex 862.151 460.651 93.6403 + endloop + endfacet + facet normal 0.942581 0.279849 0.18228 + outer loop + vertex 862.151 460.651 93.6403 + vertex 861.449 467.774 86.3325 + vertex 860.487 466.223 93.6877 + endloop + endfacet + facet normal 0.946777 0.281322 0.156433 + outer loop + vertex 862.151 460.651 93.6403 + vertex 860.487 466.223 93.6877 + vertex 861.242 459.473 101.257 + endloop + endfacet + facet normal 0.938777 0.298303 0.172375 + outer loop + vertex 861.242 459.473 101.257 + vertex 860.487 466.223 93.6877 + vertex 859.567 464.769 101.22 + endloop + endfacet + facet normal 0.942861 0.299411 0.14617 + outer loop + vertex 861.242 459.473 101.257 + vertex 859.567 464.769 101.22 + vertex 860.346 458.428 109.182 + endloop + endfacet + facet normal 0.934956 0.316396 0.16047 + outer loop + vertex 860.346 458.428 109.182 + vertex 859.567 464.769 101.22 + vertex 858.694 463.412 108.978 + endloop + endfacet + facet normal 0.938448 0.316637 0.138045 + outer loop + vertex 860.346 458.428 109.182 + vertex 858.694 463.412 108.978 + vertex 859.376 457.583 117.715 + endloop + endfacet + facet normal 0.933623 0.32735 0.14557 + outer loop + vertex 859.376 457.583 117.715 + vertex 858.694 463.412 108.978 + vertex 857.9 462.192 116.816 + endloop + endfacet + facet normal 0.928314 0.330481 0.170337 + outer loop + vertex 859.376 457.583 117.715 + vertex 857.9 462.192 116.816 + vertex 858.125 458.35 123.041 + endloop + endfacet + facet normal 0.884561 0.44372 0.143753 + outer loop + vertex 859.227 456.011 123.48 + vertex 859.376 457.583 117.715 + vertex 858.125 458.35 123.041 + endloop + endfacet + facet normal 0.89099 0.440441 0.110219 + outer loop + vertex 859.227 456.011 123.48 + vertex 858.125 458.35 123.041 + vertex 858.941 455.55 127.636 + endloop + endfacet + facet normal 0.876889 0.463651 0.126857 + outer loop + vertex 858.941 455.55 127.636 + vertex 858.125 458.35 123.041 + vertex 857.513 458.167 127.94 + endloop + endfacet + facet normal 0.877736 0.465809 0.112253 + outer loop + vertex 858.941 455.55 127.636 + vertex 857.513 458.167 127.94 + vertex 858.268 455.864 131.595 + endloop + endfacet + facet normal 0.879909 0.462326 0.109608 + outer loop + vertex 858.268 455.864 131.595 + vertex 857.513 458.167 127.94 + vertex 857.125 457.909 132.14 + endloop + endfacet + facet normal 0.879216 0.469327 0.0819217 + outer loop + vertex 858.268 455.864 131.595 + vertex 857.125 457.909 132.14 + vertex 858.164 455.356 135.626 + endloop + endfacet + facet normal 0.868993 0.485291 0.0966656 + outer loop + vertex 858.164 455.356 135.626 + vertex 857.125 457.909 132.14 + vertex 856.841 457.612 136.192 + endloop + endfacet + facet normal 0.868379 0.489914 0.0768302 + outer loop + vertex 858.164 455.356 135.626 + vertex 856.841 457.612 136.192 + vertex 857.807 455.319 139.894 + endloop + endfacet + facet normal 0.86297 0.498317 0.0834461 + outer loop + vertex 857.807 455.319 139.894 + vertex 856.841 457.612 136.192 + vertex 856.586 457.384 140.192 + endloop + endfacet + facet normal 0.863024 0.50008 0.071485 + outer loop + vertex 857.807 455.319 139.894 + vertex 856.586 457.384 140.192 + vertex 857.536 455.201 143.993 + endloop + endfacet + facet normal 0.857424 0.508691 0.0778306 + outer loop + vertex 857.536 455.201 143.993 + vertex 856.586 457.384 140.192 + vertex 856.368 457.144 144.156 + endloop + endfacet + facet normal 0.857753 0.510025 0.0642919 + outer loop + vertex 857.536 455.201 143.993 + vertex 856.368 457.144 144.156 + vertex 857.343 455.016 148.035 + endloop + endfacet + facet normal 0.854197 0.515462 0.0681673 + outer loop + vertex 857.343 455.016 148.035 + vertex 856.368 457.144 144.156 + vertex 856.2 456.898 148.125 + endloop + endfacet + facet normal 0.854647 0.516421 0.0537359 + outer loop + vertex 857.343 455.016 148.035 + vertex 856.2 456.898 148.125 + vertex 857.217 454.808 152.03 + endloop + endfacet + facet normal 0.85026 0.523107 0.0584557 + outer loop + vertex 857.217 454.808 152.03 + vertex 856.2 456.898 148.125 + vertex 856.067 456.669 152.104 + endloop + endfacet + facet normal 0.850585 0.523792 0.0463286 + outer loop + vertex 857.217 454.808 152.03 + vertex 856.067 456.669 152.104 + vertex 857.112 454.629 155.982 + endloop + endfacet + facet normal 0.849256 0.525818 0.0477526 + outer loop + vertex 857.112 454.629 155.982 + vertex 856.067 456.669 152.104 + vertex 855.962 456.479 156.065 + endloop + endfacet + facet normal 0.849461 0.526582 0.0335746 + outer loop + vertex 857.112 454.629 155.982 + vertex 855.962 456.479 156.065 + vertex 857.04 454.498 159.878 + endloop + endfacet + facet normal 0.846042 0.531813 0.0372592 + outer loop + vertex 857.04 454.498 159.878 + vertex 855.962 456.479 156.065 + vertex 855.881 456.334 159.974 + endloop + endfacet + facet normal 0.846069 0.532596 0.0225772 + outer loop + vertex 857.04 454.498 159.878 + vertex 855.881 456.334 159.974 + vertex 856.996 454.404 163.727 + endloop + endfacet + facet normal 0.845427 0.533584 0.0232761 + outer loop + vertex 856.996 454.404 163.727 + vertex 855.881 456.334 159.974 + vertex 855.841 456.23 163.836 + endloop + endfacet + facet normal 0.845293 0.534166 0.012081 + outer loop + vertex 856.996 454.404 163.727 + vertex 855.841 456.23 163.836 + vertex 856.978 454.345 167.568 + endloop + endfacet + facet normal 0.842555 0.5384 0.0150542 + outer loop + vertex 856.978 454.345 167.568 + vertex 855.841 456.23 163.836 + vertex 855.82 456.155 167.678 + endloop + endfacet + facet normal 0.842298 0.539007 0.00243987 + outer loop + vertex 856.978 454.345 167.568 + vertex 855.82 456.155 167.678 + vertex 856.993 454.304 171.435 + endloop + endfacet + facet normal 0.841263 0.540614 0.00355463 + outer loop + vertex 856.993 454.304 171.435 + vertex 855.82 456.155 167.678 + vertex 855.833 456.109 171.538 + endloop + endfacet + facet normal 0.840945 0.541063 -0.0079471 + outer loop + vertex 856.993 454.304 171.435 + vertex 855.833 456.109 171.538 + vertex 857.037 454.294 175.362 + endloop + endfacet + facet normal 0.84017 0.542277 -0.00712688 + outer loop + vertex 857.037 454.294 175.362 + vertex 855.833 456.109 171.538 + vertex 855.876 456.094 175.468 + endloop + endfacet + facet normal 0.839696 0.542704 -0.0195633 + outer loop + vertex 857.037 454.294 175.362 + vertex 855.876 456.094 175.468 + vertex 857.121 454.307 179.338 + endloop + endfacet + facet normal 0.837065 0.546845 -0.0168054 + outer loop + vertex 857.121 454.307 179.338 + vertex 855.876 456.094 175.468 + vertex 855.948 456.107 179.46 + endloop + endfacet + facet normal 0.836586 0.547191 -0.0265716 + outer loop + vertex 857.121 454.307 179.338 + vertex 855.948 456.107 179.46 + vertex 857.222 454.347 183.342 + endloop + endfacet + facet normal 0.839942 0.541841 -0.030098 + outer loop + vertex 857.222 454.347 183.342 + vertex 855.948 456.107 179.46 + vertex 856.062 456.152 183.462 + endloop + endfacet + facet normal 0.839411 0.542094 -0.0390287 + outer loop + vertex 857.222 454.347 183.342 + vertex 856.062 456.152 183.462 + vertex 857.364 454.416 187.35 + endloop + endfacet + facet normal 0.838553 0.543485 -0.0381206 + outer loop + vertex 857.364 454.416 187.35 + vertex 856.062 456.152 183.462 + vertex 856.197 456.224 187.461 + endloop + endfacet + facet normal 0.837814 0.543705 -0.0495191 + outer loop + vertex 857.364 454.416 187.35 + vertex 856.197 456.224 187.461 + vertex 857.543 454.505 191.35 + endloop + endfacet + facet normal 0.840063 0.539997 -0.0519351 + outer loop + vertex 857.543 454.505 191.35 + vertex 856.197 456.224 187.461 + vertex 856.378 456.328 191.463 + endloop + endfacet + facet normal 0.839353 0.54012 -0.0613014 + outer loop + vertex 857.543 454.505 191.35 + vertex 856.378 456.328 191.463 + vertex 857.756 454.628 195.354 + endloop + endfacet + facet normal 0.841137 0.53711 -0.0632486 + outer loop + vertex 857.756 454.628 195.354 + vertex 856.378 456.328 191.463 + vertex 856.594 456.461 195.466 + endloop + endfacet + facet normal 0.840448 0.53717 -0.0713888 + outer loop + vertex 857.756 454.628 195.354 + vertex 856.594 456.461 195.466 + vertex 858.005 454.769 199.347 + endloop + endfacet + facet normal 0.841627 0.535143 -0.0727011 + outer loop + vertex 858.005 454.769 199.347 + vertex 856.594 456.461 195.466 + vertex 856.836 456.622 199.457 + endloop + endfacet + facet normal 0.840645 0.535148 -0.0832625 + outer loop + vertex 858.005 454.769 199.347 + vertex 856.836 456.622 199.457 + vertex 858.285 454.947 203.321 + endloop + endfacet + facet normal 0.841303 0.533996 -0.0840084 + outer loop + vertex 858.285 454.947 203.321 + vertex 856.836 456.622 199.457 + vertex 857.108 456.819 203.426 + endloop + endfacet + facet normal 0.840344 0.533926 -0.0935148 + outer loop + vertex 858.285 454.947 203.321 + vertex 857.108 456.819 203.426 + vertex 858.588 455.158 207.251 + endloop + endfacet + facet normal 0.843649 0.527991 -0.0973703 + outer loop + vertex 858.588 455.158 207.251 + vertex 857.108 456.819 203.426 + vertex 857.422 457.042 207.358 + endloop + endfacet + facet normal 0.842829 0.527901 -0.104685 + outer loop + vertex 858.588 455.158 207.251 + vertex 857.422 457.042 207.358 + vertex 858.929 455.386 211.138 + endloop + endfacet + facet normal 0.847217 0.519731 -0.110015 + outer loop + vertex 858.929 455.386 211.138 + vertex 857.422 457.042 207.358 + vertex 857.779 457.29 211.28 + endloop + endfacet + facet normal 0.84599 0.519681 -0.119304 + outer loop + vertex 858.929 455.386 211.138 + vertex 857.779 457.29 211.28 + vertex 859.337 455.619 215.053 + endloop + endfacet + facet normal 0.847546 0.51668 -0.121275 + outer loop + vertex 859.337 455.619 215.053 + vertex 857.779 457.29 211.28 + vertex 858.178 457.563 215.235 + endloop + endfacet + facet normal 0.84619 0.516713 -0.130268 + outer loop + vertex 859.337 455.619 215.053 + vertex 858.178 457.563 215.235 + vertex 859.785 455.902 219.082 + endloop + endfacet + facet normal 0.848614 0.511931 -0.133346 + outer loop + vertex 859.785 455.902 219.082 + vertex 858.178 457.563 215.235 + vertex 858.601 457.893 219.194 + endloop + endfacet + facet normal 0.847529 0.511712 -0.140872 + outer loop + vertex 859.785 455.902 219.082 + vertex 858.601 457.893 219.194 + vertex 860.165 456.359 223.032 + endloop + endfacet + facet normal 0.850499 0.505749 -0.144466 + outer loop + vertex 860.165 456.359 223.032 + vertex 858.601 457.893 219.194 + vertex 859.004 458.291 222.956 + endloop + endfacet + facet normal 0.850606 0.505853 -0.143466 + outer loop + vertex 860.165 456.359 223.032 + vertex 859.004 458.291 222.956 + vertex 860.3 456.985 226.038 + endloop + endfacet + facet normal 0.858953 0.488204 -0.154458 + outer loop + vertex 860.3 456.985 226.038 + vertex 859.004 458.291 222.956 + vertex 859.49 458.582 226.58 + endloop + endfacet + facet normal 0.857365 0.489244 -0.159892 + outer loop + vertex 860.3 456.985 226.038 + vertex 859.49 458.582 226.58 + vertex 861.175 456.656 229.722 + endloop + endfacet + facet normal 0.858024 0.48765 -0.161222 + outer loop + vertex 861.175 456.656 229.722 + vertex 859.49 458.582 226.58 + vertex 860.035 458.823 230.213 + endloop + endfacet + facet normal 0.858516 0.48745 -0.159194 + outer loop + vertex 861.175 456.656 229.722 + vertex 860.035 458.823 230.213 + vertex 861.631 456.983 233.183 + endloop + endfacet + facet normal 0.86545 0.469881 -0.173805 + outer loop + vertex 861.631 456.983 233.183 + vertex 860.035 458.823 230.213 + vertex 860.663 459.078 234.026 + endloop + endfacet + facet normal 0.86331 0.471435 -0.180126 + outer loop + vertex 861.631 456.983 233.183 + vertex 860.663 459.078 234.026 + vertex 862.761 456.6 237.596 + endloop + endfacet + facet normal 0.864055 0.469337 -0.18202 + outer loop + vertex 862.761 456.6 237.596 + vertex 860.663 459.078 234.026 + vertex 861.392 459.449 238.442 + endloop + endfacet + facet normal 0.863338 0.469712 -0.184442 + outer loop + vertex 862.761 456.6 237.596 + vertex 861.392 459.449 238.442 + vertex 863.792 457.009 243.464 + endloop + endfacet + facet normal 0.873665 0.442292 -0.202698 + outer loop + vertex 863.792 457.009 243.464 + vertex 861.392 459.449 238.442 + vertex 862.089 460.453 243.639 + endloop + endfacet + facet normal 0.872725 0.442056 -0.207214 + outer loop + vertex 863.792 457.009 243.464 + vertex 862.089 460.453 243.639 + vertex 864.717 458.199 249.896 + endloop + endfacet + facet normal 0.902964 0.346314 -0.254407 + outer loop + vertex 862.627 463.772 250.067 + vertex 864.717 458.199 249.896 + vertex 862.089 460.453 243.639 + endloop + endfacet + facet normal 0.912448 0.348639 -0.21422 + outer loop + vertex 864.717 458.199 249.896 + vertex 862.627 463.772 250.067 + vertex 865.844 459.579 256.942 + endloop + endfacet + facet normal 0.914966 0.336413 -0.222854 + outer loop + vertex 865.844 459.579 256.942 + vertex 862.627 463.772 250.067 + vertex 863.98 464.98 257.446 + endloop + endfacet + facet normal 0.913949 0.336443 -0.226944 + outer loop + vertex 865.844 459.579 256.942 + vertex 863.98 464.98 257.446 + vertex 867.255 460.711 264.304 + endloop + endfacet + facet normal 0.916781 0.320626 -0.238142 + outer loop + vertex 867.255 460.711 264.304 + vertex 863.98 464.98 257.446 + vertex 865.46 466.368 265.011 + endloop + endfacet + facet normal 0.915608 0.320786 -0.242401 + outer loop + vertex 867.255 460.711 264.304 + vertex 865.46 466.368 265.011 + vertex 868.758 461.845 271.483 + endloop + endfacet + facet normal 0.9174 0.307559 -0.252558 + outer loop + vertex 868.758 461.845 271.483 + vertex 865.46 466.368 265.011 + vertex 866.839 467.74 271.692 + endloop + endfacet + facet normal 0.917517 0.307581 -0.252103 + outer loop + vertex 868.758 461.845 271.483 + vertex 866.839 467.74 271.692 + vertex 870.16 463.129 278.15 + endloop + endfacet + facet normal 0.919378 0.290461 -0.265284 + outer loop + vertex 870.16 463.129 278.15 + vertex 866.839 467.74 271.692 + vertex 868.257 469.254 278.262 + endloop + endfacet + facet normal 0.919507 0.290493 -0.264803 + outer loop + vertex 870.16 463.129 278.15 + vertex 868.257 469.254 278.262 + vertex 871.368 465.177 284.594 + endloop + endfacet + facet normal 0.921338 0.272466 -0.277307 + outer loop + vertex 871.368 465.177 284.594 + vertex 868.257 469.254 278.262 + vertex 869.607 470.827 284.293 + endloop + endfacet + facet normal 0.91757 0.270546 -0.291325 + outer loop + vertex 869.607 470.827 284.293 + vertex 870.743 472.295 289.236 + vertex 871.368 465.177 284.594 + endloop + endfacet + facet normal 0.911662 0.277627 -0.302979 + outer loop + vertex 873.125 464.481 289.242 + vertex 871.368 465.177 284.594 + vertex 870.743 472.295 289.236 + endloop + endfacet + facet normal 0.923148 0.281158 -0.262198 + outer loop + vertex 873.514 465.984 292.223 + vertex 873.125 464.481 289.242 + vertex 870.743 472.295 289.236 + endloop + endfacet + facet normal 0.950426 0.234877 0.20377 + outer loop + vertex 865.09 464.694 71.9355 + vertex 864.431 472.882 65.5703 + vertex 863.449 471.136 72.1618 + endloop + endfacet + facet normal 0.956879 0.222326 0.186958 + outer loop + vertex 866.06 466.123 65.2698 + vertex 864.431 472.882 65.5703 + vertex 865.09 464.694 71.9355 + endloop + endfacet + facet normal 0.953063 0.220493 0.207492 + outer loop + vertex 866.06 466.123 65.2698 + vertex 865.35 474.6 59.5221 + vertex 864.431 472.882 65.5703 + endloop + endfacet + facet normal 0.959193 0.209255 0.190161 + outer loop + vertex 866.932 467.487 59.3715 + vertex 865.35 474.6 59.5221 + vertex 866.06 466.123 65.2698 + endloop + endfacet + facet normal 0.928637 0.307033 0.208243 + outer loop + vertex 868.287 459.415 65.2333 + vertex 866.932 467.487 59.3715 + vertex 866.06 466.123 65.2698 + endloop + endfacet + facet normal 0.932501 0.308426 0.187924 + outer loop + vertex 868.287 459.415 65.2333 + vertex 866.06 466.123 65.2698 + vertex 867.315 458.266 71.9395 + endloop + endfacet + facet normal 0.924055 0.331338 0.190623 + outer loop + vertex 869.645 451.725 72.0136 + vertex 868.287 459.415 65.2333 + vertex 867.315 458.266 71.9395 + endloop + endfacet + facet normal 0.93009 0.321304 0.178035 + outer loop + vertex 870.612 452.657 65.2816 + vertex 868.287 459.415 65.2333 + vertex 869.645 451.725 72.0136 + endloop + endfacet + facet normal 0.932065 0.315797 0.177556 + outer loop + vertex 871.9 445.044 72.0609 + vertex 870.612 452.657 65.2816 + vertex 869.645 451.725 72.0136 + endloop + endfacet + facet normal 0.934374 0.316478 0.163666 + outer loop + vertex 871.9 445.044 72.0609 + vertex 869.645 451.725 72.0136 + vertex 870.879 444.39 79.1553 + endloop + endfacet + facet normal 0.937664 0.306816 0.163248 + outer loop + vertex 873.059 437.728 79.1502 + vertex 871.9 445.044 72.0609 + vertex 870.879 444.39 79.1553 + endloop + endfacet + facet normal 0.939392 0.303474 0.159516 + outer loop + vertex 874.093 438.242 72.0826 + vertex 871.9 445.044 72.0609 + vertex 873.059 437.728 79.1502 + endloop + endfacet + facet normal 0.941534 0.296853 0.159347 + outer loop + vertex 875.205 430.93 79.1368 + vertex 874.093 438.242 72.0826 + vertex 873.059 437.728 79.1502 + endloop + endfacet + facet normal 0.943097 0.297367 0.1488 + outer loop + vertex 875.205 430.93 79.1368 + vertex 873.059 437.728 79.1502 + vertex 874.16 430.641 86.3345 + endloop + endfacet + facet normal 0.945384 0.289995 0.148836 + outer loop + vertex 876.241 423.865 86.3197 + vertex 875.205 430.93 79.1368 + vertex 874.16 430.641 86.3345 + endloop + endfacet + facet normal 0.945827 0.289054 0.147847 + outer loop + vertex 877.307 424.056 79.1308 + vertex 875.205 430.93 79.1368 + vertex 876.241 423.865 86.3197 + endloop + endfacet + facet normal 0.948599 0.279738 0.148011 + outer loop + vertex 878.251 417.052 86.314 + vertex 877.307 424.056 79.1308 + vertex 876.241 423.865 86.3197 + endloop + endfacet + facet normal 0.949923 0.280136 0.138456 + outer loop + vertex 878.251 417.052 86.314 + vertex 876.241 423.865 86.3197 + vertex 877.195 417.013 93.6424 + endloop + endfacet + facet normal 0.953521 0.267399 0.138907 + outer loop + vertex 879.078 410.295 93.6437 + vertex 878.251 417.052 86.314 + vertex 877.195 417.013 93.6424 + endloop + endfacet + facet normal 0.953572 0.267278 0.13879 + outer loop + vertex 880.16 410.241 86.3131 + vertex 878.251 417.052 86.314 + vertex 879.078 410.295 93.6437 + endloop + endfacet + facet normal 0.957632 0.251953 0.139502 + outer loop + vertex 880.845 403.578 93.6466 + vertex 880.16 410.241 86.3131 + vertex 879.078 410.295 93.6437 + endloop + endfacet + facet normal 0.958884 0.252279 0.129989 + outer loop + vertex 880.845 403.578 93.6466 + vertex 879.078 410.295 93.6437 + vertex 879.788 403.737 101.138 + endloop + endfacet + facet normal 0.963169 0.234849 0.130963 + outer loop + vertex 881.409 397.087 101.14 + vertex 880.845 403.578 93.6466 + vertex 879.788 403.737 101.138 + endloop + endfacet + facet normal 0.964451 0.235158 0.120562 + outer loop + vertex 881.409 397.087 101.14 + vertex 879.788 403.737 101.138 + vertex 880.4 397.312 108.775 + endloop + endfacet + facet normal 0.968738 0.21619 0.121689 + outer loop + vertex 881.878 390.687 108.776 + vertex 881.409 397.087 101.14 + vertex 880.4 397.312 108.775 + endloop + endfacet + facet normal 0.970089 0.21649 0.109813 + outer loop + vertex 881.878 390.687 108.776 + vertex 880.4 397.312 108.775 + vertex 880.943 390.954 116.513 + endloop + endfacet + facet normal 0.974354 0.195709 0.111046 + outer loop + vertex 882.276 384.317 116.513 + vertex 881.878 390.687 108.776 + vertex 880.943 390.954 116.513 + endloop + endfacet + facet normal 0.975748 0.195989 0.097493 + outer loop + vertex 882.276 384.317 116.513 + vertex 880.943 390.954 116.513 + vertex 881.437 384.611 124.319 + endloop + endfacet + facet normal 0.979981 0.172835 0.0988208 + outer loop + vertex 882.615 377.931 124.319 + vertex 882.276 384.317 116.513 + vertex 881.437 384.611 124.319 + endloop + endfacet + facet normal 0.981323 0.173072 0.0839738 + outer loop + vertex 882.615 377.931 124.319 + vertex 881.437 384.611 124.319 + vertex 881.889 378.235 132.177 + endloop + endfacet + facet normal 0.985421 0.147172 0.085356 + outer loop + vertex 882.896 371.493 132.177 + vertex 882.615 377.931 124.319 + vertex 881.889 378.235 132.177 + endloop + endfacet + facet normal 0.986642 0.147354 0.0694638 + outer loop + vertex 882.896 371.493 132.177 + vertex 881.889 378.235 132.177 + vertex 882.296 371.789 140.065 + endloop + endfacet + facet normal 0.990382 0.118864 0.0708162 + outer loop + vertex 883.112 364.991 140.065 + vertex 882.896 371.493 132.177 + vertex 882.296 371.789 140.065 + endloop + endfacet + facet normal 0.991406 0.118987 0.0543653 + outer loop + vertex 883.112 364.991 140.065 + vertex 882.296 371.789 140.065 + vertex 882.648 365.257 147.951 + endloop + endfacet + facet normal 0.994642 0.0871401 0.0556295 + outer loop + vertex 883.245 358.441 147.951 + vertex 883.112 364.991 140.065 + vertex 882.648 365.257 147.951 + endloop + endfacet + facet normal 0.994661 0.0869986 0.0555116 + outer loop + vertex 883.711 358.14 140.065 + vertex 883.112 364.991 140.065 + vertex 883.245 358.441 147.951 + endloop + endfacet + facet normal 0.997089 0.0506007 0.0570436 + outer loop + vertex 883.59 351.632 147.951 + vertex 883.711 358.14 140.065 + vertex 883.245 358.441 147.951 + endloop + endfacet + facet normal 0.997939 0.0506435 0.0394063 + outer loop + vertex 883.59 351.632 147.951 + vertex 883.245 358.441 147.951 + vertex 883.268 351.872 155.804 + endloop + endfacet + facet normal 0.99914 0.00755014 0.040771 + outer loop + vertex 883.319 345.133 155.805 + vertex 883.59 351.632 147.951 + vertex 883.268 351.872 155.804 + endloop + endfacet + facet normal 0.997935 0.0506977 0.0394517 + outer loop + vertex 883.268 351.872 155.804 + vertex 883.245 358.441 147.951 + vertex 882.923 358.657 155.804 + endloop + endfacet + facet normal 0.997143 0.0500387 0.0565807 + outer loop + vertex 884.055 351.297 140.065 + vertex 883.711 358.14 140.065 + vertex 883.59 351.632 147.951 + endloop + endfacet + facet normal 0.998264 0.00707535 0.058472 + outer loop + vertex 883.638 344.869 147.952 + vertex 884.055 351.297 140.065 + vertex 883.59 351.632 147.951 + endloop + endfacet + facet normal 0.996007 0.0499819 0.0739752 + outer loop + vertex 884.055 351.297 140.065 + vertex 884.317 357.754 132.177 + vertex 883.711 358.14 140.065 + endloop + endfacet + facet normal 0.993642 0.0865527 0.0720015 + outer loop + vertex 884.317 357.754 132.177 + vertex 883.716 364.649 132.177 + vertex 883.711 358.14 140.065 + endloop + endfacet + facet normal 0.992291 0.0864356 0.0888061 + outer loop + vertex 884.317 357.754 132.177 + vertex 884.455 364.233 124.32 + vertex 883.716 364.649 132.177 + endloop + endfacet + facet normal 0.989183 0.118232 0.0868283 + outer loop + vertex 884.455 364.233 124.32 + vertex 883.631 371.133 124.319 + vertex 883.716 364.649 132.177 + endloop + endfacet + facet normal 0.989124 0.118533 0.0870779 + outer loop + vertex 883.716 364.649 132.177 + vertex 883.631 371.133 124.319 + vertex 882.896 371.493 132.177 + endloop + endfacet + facet normal 0.987693 0.118055 0.102598 + outer loop + vertex 884.455 364.233 124.32 + vertex 884.492 370.708 116.512 + vertex 883.631 371.133 124.319 + endloop + endfacet + facet normal 0.984002 0.147028 0.100613 + outer loop + vertex 884.492 370.708 116.512 + vertex 883.467 377.571 116.513 + vertex 883.631 371.133 124.319 + endloop + endfacet + facet normal 0.984001 0.147032 0.100617 + outer loop + vertex 883.631 371.133 124.319 + vertex 883.467 377.571 116.513 + vertex 882.615 377.931 124.319 + endloop + endfacet + facet normal 0.982479 0.1468 0.114826 + outer loop + vertex 884.492 370.708 116.512 + vertex 884.433 377.155 108.775 + vertex 883.467 377.571 116.513 + endloop + endfacet + facet normal 0.978455 0.172842 0.112923 + outer loop + vertex 884.433 377.155 108.775 + vertex 883.229 383.975 108.775 + vertex 883.467 377.571 116.513 + endloop + endfacet + facet normal 0.978477 0.172763 0.112857 + outer loop + vertex 883.467 377.571 116.513 + vertex 883.229 383.975 108.775 + vertex 882.276 384.317 116.513 + endloop + endfacet + facet normal 0.976987 0.172583 0.125344 + outer loop + vertex 884.433 377.155 108.775 + vertex 884.277 383.583 101.141 + vertex 883.229 383.975 108.775 + endloop + endfacet + facet normal 0.972791 0.195982 0.123565 + outer loop + vertex 884.277 383.583 101.141 + vertex 882.909 390.377 101.141 + vertex 883.229 383.975 108.775 + endloop + endfacet + facet normal 0.972865 0.195743 0.123362 + outer loop + vertex 883.229 383.975 108.775 + vertex 882.909 390.377 101.141 + vertex 881.878 390.687 108.776 + endloop + endfacet + facet normal 0.971427 0.195708 0.13427 + outer loop + vertex 884.277 383.583 101.141 + vertex 884.013 390.033 93.6516 + vertex 882.909 390.377 101.141 + endloop + endfacet + facet normal 0.967211 0.216554 0.132692 + outer loop + vertex 884.013 390.033 93.6516 + vertex 882.49 396.836 93.6497 + vertex 882.909 390.377 101.141 + endloop + endfacet + facet normal 0.967332 0.216204 0.132383 + outer loop + vertex 882.909 390.377 101.141 + vertex 882.49 396.836 93.6497 + vertex 881.409 397.087 101.14 + endloop + endfacet + facet normal 0.96591 0.216265 0.142295 + outer loop + vertex 884.013 390.033 93.6516 + vertex 883.628 396.583 86.3125 + vertex 882.49 396.836 93.6497 + endloop + endfacet + facet normal 0.961668 0.235198 0.140985 + outer loop + vertex 883.628 396.583 86.3125 + vertex 881.953 403.429 86.3129 + vertex 882.49 396.836 93.6497 + endloop + endfacet + facet normal 0.96184 0.234746 0.140566 + outer loop + vertex 882.49 396.836 93.6497 + vertex 881.953 403.429 86.3129 + vertex 880.845 403.578 93.6466 + endloop + endfacet + facet normal 0.960431 0.234895 0.149657 + outer loop + vertex 883.628 396.583 86.3125 + vertex 883.105 403.313 79.1035 + vertex 881.953 403.429 86.3129 + endloop + endfacet + facet normal 0.956223 0.252037 0.148708 + outer loop + vertex 883.105 403.313 79.1035 + vertex 881.278 410.239 79.1136 + vertex 881.953 403.429 86.3129 + endloop + endfacet + facet normal 0.956362 0.251704 0.14838 + outer loop + vertex 881.953 403.429 86.3129 + vertex 881.278 410.239 79.1136 + vertex 880.16 410.241 86.3131 + endloop + endfacet + facet normal 0.952363 0.266785 0.147755 + outer loop + vertex 881.278 410.239 79.1136 + vertex 879.341 417.15 79.1222 + vertex 880.16 410.241 86.3131 + endloop + endfacet + facet normal 0.951151 0.266435 0.155962 + outer loop + vertex 881.278 410.239 79.1136 + vertex 880.452 417.31 72.0699 + vertex 879.341 417.15 79.1222 + endloop + endfacet + facet normal 0.947772 0.278362 0.155702 + outer loop + vertex 880.452 417.31 72.0699 + vertex 878.385 424.343 72.0824 + vertex 879.341 417.15 79.1222 + endloop + endfacet + facet normal 0.947525 0.278885 0.156269 + outer loop + vertex 879.341 417.15 79.1222 + vertex 878.385 424.343 72.0824 + vertex 877.307 424.056 79.1308 + endloop + endfacet + facet normal 0.944916 0.287624 0.156227 + outer loop + vertex 878.385 424.343 72.0824 + vertex 876.255 431.334 72.0882 + vertex 877.307 424.056 79.1308 + endloop + endfacet + facet normal 0.943701 0.287248 0.164067 + outer loop + vertex 878.385 424.343 72.0824 + vertex 877.277 431.818 65.3648 + vertex 876.255 431.334 72.0882 + endloop + endfacet + facet normal 0.941918 0.292961 0.164207 + outer loop + vertex 877.277 431.818 65.3648 + vertex 875.078 438.891 65.3608 + vertex 876.255 431.334 72.0882 + endloop + endfacet + facet normal 0.941017 0.294677 0.166292 + outer loop + vertex 876.255 431.334 72.0882 + vertex 875.078 438.891 65.3608 + vertex 874.093 438.242 72.0826 + endloop + endfacet + facet normal 0.939298 0.299966 0.166551 + outer loop + vertex 875.078 438.891 65.3608 + vertex 872.869 445.822 65.3329 + vertex 874.093 438.242 72.0826 + endloop + endfacet + facet normal 0.937958 0.299572 0.174617 + outer loop + vertex 875.078 438.891 65.3608 + vertex 873.718 446.622 59.4013 + vertex 872.869 445.822 65.3329 + endloop + endfacet + facet normal 0.936012 0.305314 0.175113 + outer loop + vertex 873.718 446.622 59.4013 + vertex 871.449 453.596 59.3715 + vertex 872.869 445.822 65.3329 + endloop + endfacet + facet normal 0.933368 0.309683 0.18144 + outer loop + vertex 872.869 445.822 65.3329 + vertex 871.449 453.596 59.3715 + vertex 870.612 452.657 65.2816 + endloop + endfacet + facet normal 0.932316 0.312648 0.181762 + outer loop + vertex 871.449 453.596 59.3715 + vertex 869.129 460.519 59.3646 + vertex 870.612 452.657 65.2816 + endloop + endfacet + facet normal 0.930346 0.311998 0.192648 + outer loop + vertex 871.449 453.596 59.3715 + vertex 869.782 461.369 54.8325 + vertex 869.129 460.519 59.3646 + endloop + endfacet + facet normal 0.940146 0.283718 0.188757 + outer loop + vertex 869.782 461.369 54.8325 + vertex 867.618 468.608 54.7301 + vertex 869.129 460.519 59.3646 + endloop + endfacet + facet normal 0.932753 0.293854 0.208856 + outer loop + vertex 869.129 460.519 59.3646 + vertex 867.618 468.608 54.7301 + vertex 866.932 467.487 59.3715 + endloop + endfacet + facet normal 0.961901 0.196845 0.189733 + outer loop + vertex 867.618 468.608 54.7301 + vertex 866.166 476.225 54.1891 + vertex 866.932 467.487 59.3715 + endloop + endfacet + facet normal 0.957677 0.197441 0.209455 + outer loop + vertex 866.735 477.441 50.4409 + vertex 866.166 476.225 54.1891 + vertex 867.618 468.608 54.7301 + endloop + endfacet + facet normal 0.963973 0.187826 0.188357 + outer loop + vertex 868.078 469.134 51.8536 + vertex 866.735 477.441 50.4409 + vertex 867.618 468.608 54.7301 + endloop + endfacet + facet normal 0.959386 0.190444 0.208111 + outer loop + vertex 868.078 469.134 51.8536 + vertex 866.766 477.509 50.2382 + vertex 866.735 477.441 50.4409 + endloop + endfacet + facet normal 0.966618 0.185523 0.176725 + outer loop + vertex 868.466 468.5 50.3973 + vertex 866.766 477.509 50.2382 + vertex 868.078 469.134 51.8536 + endloop + endfacet + facet normal 0.950604 0.281586 0.130618 + outer loop + vertex 870.304 461.565 51.9703 + vertex 868.466 468.5 50.3973 + vertex 868.078 469.134 51.8536 + endloop + endfacet + facet normal 0.940975 0.27968 0.190643 + outer loop + vertex 870.304 461.565 51.9703 + vertex 868.078 469.134 51.8536 + vertex 869.782 461.369 54.8325 + endloop + endfacet + facet normal 0.93241 0.306844 0.190939 + outer loop + vertex 869.782 461.369 54.8325 + vertex 872.117 454.263 54.8484 + vertex 870.304 461.565 51.9703 + endloop + endfacet + facet normal 0.934483 0.304682 0.184148 + outer loop + vertex 872.696 454.233 51.9605 + vertex 870.304 461.565 51.9703 + vertex 872.117 454.263 54.8484 + endloop + endfacet + facet normal 0.93552 0.292797 0.197665 + outer loop + vertex 870.862 460.803 50.4578 + vertex 868.466 468.5 50.3973 + vertex 870.304 461.565 51.9703 + endloop + endfacet + facet normal 0.937647 0.283152 0.201599 + outer loop + vertex 867.618 468.608 54.7301 + vertex 869.782 461.369 54.8325 + vertex 868.078 469.134 51.8536 + endloop + endfacet + facet normal 0.933797 0.307283 0.183306 + outer loop + vertex 872.117 454.263 54.8484 + vertex 869.782 461.369 54.8325 + vertex 871.449 453.596 59.3715 + endloop + endfacet + facet normal 0.934624 0.304896 0.183077 + outer loop + vertex 873.718 446.622 59.4013 + vertex 872.117 454.263 54.8484 + vertex 871.449 453.596 59.3715 + endloop + endfacet + facet normal 0.936759 0.30182 0.177163 + outer loop + vertex 874.429 447.095 54.8401 + vertex 872.117 454.263 54.8484 + vertex 873.718 446.622 59.4013 + endloop + endfacet + facet normal 0.93842 0.296772 0.176899 + outer loop + vertex 875.97 439.493 59.4163 + vertex 874.429 447.095 54.8401 + vertex 873.718 446.622 59.4013 + endloop + endfacet + facet normal 0.93941 0.297073 0.171044 + outer loop + vertex 875.97 439.493 59.4163 + vertex 873.718 446.622 59.4013 + vertex 875.078 438.891 65.3608 + endloop + endfacet + facet normal 0.940846 0.292632 0.17081 + outer loop + vertex 877.277 431.818 65.3648 + vertex 875.97 439.493 59.4163 + vertex 875.078 438.891 65.3608 + endloop + endfacet + facet normal 0.941673 0.291168 0.168739 + outer loop + vertex 878.279 432.074 59.3352 + vertex 875.97 439.493 59.4163 + vertex 877.277 431.818 65.3648 + endloop + endfacet + facet normal 0.943276 0.285909 0.168782 + outer loop + vertex 879.462 424.611 65.3633 + vertex 878.279 432.074 59.3352 + vertex 877.277 431.818 65.3648 + endloop + endfacet + facet normal 0.943908 0.284741 0.167212 + outer loop + vertex 880.558 424.447 59.4553 + vertex 878.279 432.074 59.3352 + vertex 879.462 424.611 65.3633 + endloop + endfacet + facet normal 0.946041 0.277208 0.167817 + outer loop + vertex 881.583 417.376 65.3603 + vertex 880.558 424.447 59.4553 + vertex 879.462 424.611 65.3633 + endloop + endfacet + facet normal 0.946936 0.277473 0.162237 + outer loop + vertex 881.583 417.376 65.3603 + vertex 879.462 424.611 65.3633 + vertex 880.452 417.31 72.0699 + endloop + endfacet + facet normal 0.950125 0.266089 0.162664 + outer loop + vertex 882.428 410.265 72.0525 + vertex 881.583 417.376 65.3603 + vertex 880.452 417.31 72.0699 + endloop + endfacet + facet normal 0.950255 0.265812 0.162353 + outer loop + vertex 883.595 410.184 65.3551 + vertex 881.583 417.376 65.3603 + vertex 882.428 410.265 72.0525 + endloop + endfacet + facet normal 0.953953 0.251693 0.163168 + outer loop + vertex 884.291 403.211 72.0424 + vertex 883.595 410.184 65.3551 + vertex 882.428 410.265 72.0525 + endloop + endfacet + facet normal 0.954955 0.251967 0.156759 + outer loop + vertex 884.291 403.211 72.0424 + vertex 882.428 410.265 72.0525 + vertex 883.105 403.313 79.1035 + endloop + endfacet + facet normal 0.959132 0.234937 0.157706 + outer loop + vertex 884.81 396.351 79.1063 + vertex 884.291 403.211 72.0424 + vertex 883.105 403.313 79.1035 + endloop + endfacet + facet normal 0.958888 0.23553 0.1583 + outer loop + vertex 886.028 396.137 72.0474 + vertex 884.291 403.211 72.0424 + vertex 884.81 396.351 79.1063 + endloop + endfacet + facet normal 0.963054 0.216935 0.159582 + outer loop + vertex 886.39 389.333 79.1122 + vertex 886.028 396.137 72.0474 + vertex 884.81 396.351 79.1063 + endloop + endfacet + facet normal 0.964223 0.217192 0.151991 + outer loop + vertex 886.39 389.333 79.1122 + vertex 884.81 396.351 79.1063 + vertex 885.177 389.678 86.317 + endloop + endfacet + facet normal 0.968497 0.19591 0.153727 + outer loop + vertex 886.588 382.696 86.3226 + vertex 886.39 389.333 79.1122 + vertex 885.177 389.678 86.317 + endloop + endfacet + facet normal 0.969835 0.196173 0.144694 + outer loop + vertex 886.588 382.696 86.3226 + vertex 885.177 389.678 86.317 + vertex 885.403 383.149 93.6531 + endloop + endfacet + facet normal 0.974 0.172528 0.146829 + outer loop + vertex 886.64 376.165 93.6539 + vertex 886.588 382.696 86.3226 + vertex 885.403 383.149 93.6531 + endloop + endfacet + facet normal 0.975425 0.172779 0.136723 + outer loop + vertex 886.64 376.165 93.6539 + vertex 885.403 383.149 93.6531 + vertex 885.498 376.684 101.141 + endloop + endfacet + facet normal 0.979395 0.146358 0.139159 + outer loop + vertex 886.546 369.67 101.14 + vertex 886.64 376.165 93.6539 + vertex 885.498 376.684 101.141 + endloop + endfacet + facet normal 0.980921 0.146587 0.127698 + outer loop + vertex 886.546 369.67 101.14 + vertex 885.498 376.684 101.141 + vertex 885.47 370.22 108.774 + endloop + endfacet + facet normal 0.984487 0.117514 0.130294 + outer loop + vertex 886.31 363.185 108.774 + vertex 886.546 369.67 101.14 + vertex 885.47 370.22 108.774 + endloop + endfacet + facet normal 0.986139 0.117712 0.116935 + outer loop + vertex 886.31 363.185 108.774 + vertex 885.47 370.22 108.774 + vertex 885.326 363.745 116.512 + endloop + endfacet + facet normal 0.989141 0.0853334 0.11966 + outer loop + vertex 885.931 356.731 116.513 + vertex 886.31 363.185 108.774 + vertex 885.326 363.745 116.512 + endloop + endfacet + facet normal 0.990846 0.0854788 0.104488 + outer loop + vertex 885.931 356.731 116.513 + vertex 885.326 363.745 116.512 + vertex 885.06 357.283 124.319 + endloop + endfacet + facet normal 0.993031 0.0486579 0.107336 + outer loop + vertex 885.4 350.344 124.32 + vertex 885.931 356.731 116.513 + vertex 885.06 357.283 124.319 + endloop + endfacet + facet normal 0.994714 0.048739 0.0903842 + outer loop + vertex 885.4 350.344 124.32 + vertex 885.06 357.283 124.319 + vertex 884.66 350.867 132.177 + endloop + endfacet + facet normal 0.995618 0.005583 0.0933433 + outer loop + vertex 884.699 344.029 132.177 + vertex 885.4 350.344 124.32 + vertex 884.66 350.867 132.177 + endloop + endfacet + facet normal 0.994601 0.049648 0.0911207 + outer loop + vertex 884.66 350.867 132.177 + vertex 885.06 357.283 124.319 + vertex 884.317 357.754 132.177 + endloop + endfacet + facet normal 0.993093 0.048207 0.106972 + outer loop + vertex 886.271 349.73 116.513 + vertex 885.931 356.731 116.513 + vertex 885.4 350.344 124.32 + endloop + endfacet + facet normal 0.993867 0.00452946 0.110492 + outer loop + vertex 885.431 343.454 124.32 + vertex 886.271 349.73 116.513 + vertex 885.4 350.344 124.32 + endloop + endfacet + facet normal 0.991278 0.0481189 0.122691 + outer loop + vertex 886.271 349.73 116.513 + vertex 886.919 356.101 108.774 + vertex 885.931 356.731 116.513 + endloop + endfacet + facet normal 0.991426 0.0471189 0.12188 + outer loop + vertex 887.255 349.032 108.775 + vertex 886.919 356.101 108.774 + vertex 886.271 349.73 116.513 + endloop + endfacet + facet normal 0.989531 0.0470304 0.136442 + outer loop + vertex 887.255 349.032 108.775 + vertex 888.005 355.399 101.14 + vertex 886.919 356.101 108.774 + endloop + endfacet + facet normal 0.987557 0.0843491 0.132729 + outer loop + vertex 888.005 355.399 101.14 + vertex 887.394 362.559 101.14 + vertex 886.919 356.101 108.774 + endloop + endfacet + facet normal 0.987449 0.0848922 0.133181 + outer loop + vertex 886.919 356.101 108.774 + vertex 887.394 362.559 101.14 + vertex 886.31 363.185 108.774 + endloop + endfacet + facet normal 0.985794 0.0841988 0.145327 + outer loop + vertex 888.005 355.399 101.14 + vertex 888.556 361.874 93.6507 + vertex 887.394 362.559 101.14 + endloop + endfacet + facet normal 0.982957 0.11688 0.141898 + outer loop + vertex 888.556 361.874 93.6507 + vertex 887.7 369.069 93.6527 + vertex 887.394 362.559 101.14 + endloop + endfacet + facet normal 0.982903 0.117101 0.142088 + outer loop + vertex 887.394 362.559 101.14 + vertex 887.7 369.069 93.6527 + vertex 886.546 369.67 101.14 + endloop + endfacet + facet normal 0.981312 0.116681 0.153012 + outer loop + vertex 888.556 361.874 93.6507 + vertex 888.92 368.431 86.3206 + vertex 887.7 369.069 93.6527 + endloop + endfacet + facet normal 0.977818 0.146348 0.149848 + outer loop + vertex 888.92 368.431 86.3206 + vertex 887.843 375.62 86.3245 + vertex 887.7 369.069 93.6527 + endloop + endfacet + facet normal 0.977868 0.146172 0.149692 + outer loop + vertex 887.7 369.069 93.6527 + vertex 887.843 375.62 86.3245 + vertex 886.64 376.165 93.6539 + endloop + endfacet + facet normal 0.976271 0.146111 0.159832 + outer loop + vertex 888.92 368.431 86.3206 + vertex 889.106 375.067 79.1185 + vertex 887.843 375.62 86.3245 + endloop + endfacet + facet normal 0.972316 0.172997 0.157075 + outer loop + vertex 889.106 375.067 79.1185 + vertex 887.828 382.247 79.1184 + vertex 887.843 375.62 86.3245 + endloop + endfacet + facet normal 0.972467 0.172534 0.156649 + outer loop + vertex 887.843 375.62 86.3245 + vertex 887.828 382.247 79.1184 + vertex 886.588 382.696 86.3226 + endloop + endfacet + facet normal 0.97108 0.172777 0.16478 + outer loop + vertex 889.106 375.067 79.1185 + vertex 889.104 381.814 72.0505 + vertex 887.828 382.247 79.1184 + endloop + endfacet + facet normal 0.966817 0.197112 0.162518 + outer loop + vertex 889.104 381.814 72.0505 + vertex 887.636 389.016 72.0515 + vertex 887.828 382.247 79.1184 + endloop + endfacet + facet normal 0.967069 0.196423 0.161852 + outer loop + vertex 887.828 382.247 79.1184 + vertex 887.636 389.016 72.0515 + vertex 886.39 389.333 79.1122 + endloop + endfacet + facet normal 0.965812 0.196906 0.168627 + outer loop + vertex 889.104 381.814 72.0505 + vertex 888.877 388.705 65.3079 + vertex 887.636 389.016 72.0515 + endloop + endfacet + facet normal 0.961602 0.217879 0.166884 + outer loop + vertex 888.877 388.705 65.3079 + vertex 887.234 395.924 65.3457 + vertex 887.636 389.016 72.0515 + endloop + endfacet + facet normal 0.961839 0.217298 0.166272 + outer loop + vertex 887.636 389.016 72.0515 + vertex 887.234 395.924 65.3457 + vertex 886.028 396.137 72.0474 + endloop + endfacet + facet normal 0.957705 0.235788 0.164939 + outer loop + vertex 887.234 395.924 65.3457 + vertex 885.479 403.043 65.3636 + vertex 886.028 396.137 72.0474 + endloop + endfacet + facet normal 0.956872 0.23557 0.170011 + outer loop + vertex 887.234 395.924 65.3457 + vertex 886.584 402.751 59.5495 + vertex 885.479 403.043 65.3636 + endloop + endfacet + facet normal 0.95309 0.251453 0.168494 + outer loop + vertex 886.584 402.751 59.5495 + vertex 884.732 409.805 59.4961 + vertex 885.479 403.043 65.3636 + endloop + endfacet + facet normal 0.953032 0.251576 0.168642 + outer loop + vertex 885.479 403.043 65.3636 + vertex 884.732 409.805 59.4961 + vertex 883.595 410.184 65.3551 + endloop + endfacet + facet normal 0.949651 0.265017 0.167117 + outer loop + vertex 884.732 409.805 59.4961 + vertex 882.712 417.054 59.4795 + vertex 883.595 410.184 65.3551 + endloop + endfacet + facet normal 0.949102 0.264872 0.170437 + outer loop + vertex 884.732 409.805 59.4961 + vertex 883.774 416.414 54.5618 + vertex 882.712 417.054 59.4795 + endloop + endfacet + facet normal 0.95226 0.251272 0.173388 + outer loop + vertex 886.584 402.751 59.5495 + vertex 885.75 408.643 55.5908 + vertex 884.732 409.805 59.4961 + endloop + endfacet + facet normal 0.957046 0.235194 0.169549 + outer loop + vertex 888.337 395.725 59.3981 + vertex 886.584 402.751 59.5495 + vertex 887.234 395.924 65.3457 + endloop + endfacet + facet normal 0.956769 0.235089 0.171249 + outer loop + vertex 888.337 395.725 59.3981 + vertex 887.392 402.777 54.995 + vertex 886.584 402.751 59.5495 + endloop + endfacet + facet normal 0.960943 0.217708 0.170858 + outer loop + vertex 888.877 388.705 65.3079 + vertex 888.337 395.725 59.3981 + vertex 887.234 395.924 65.3457 + endloop + endfacet + facet normal 0.960935 0.217724 0.170878 + outer loop + vertex 890.048 388.238 59.3141 + vertex 888.337 395.725 59.3981 + vertex 888.877 388.705 65.3079 + endloop + endfacet + facet normal 0.964886 0.197447 0.173232 + outer loop + vertex 890.382 381.341 65.3174 + vertex 890.048 388.238 59.3141 + vertex 888.877 388.705 65.3079 + endloop + endfacet + facet normal 0.964573 0.198201 0.174115 + outer loop + vertex 891.593 380.609 59.4434 + vertex 890.048 388.238 59.3141 + vertex 890.382 381.341 65.3174 + endloop + endfacet + facet normal 0.968553 0.173873 0.17797 + outer loop + vertex 891.705 373.938 65.3495 + vertex 891.593 380.609 59.4434 + vertex 890.382 381.341 65.3174 + endloop + endfacet + facet normal 0.9695 0.174019 0.172589 + outer loop + vertex 891.705 373.938 65.3495 + vertex 890.382 381.341 65.3174 + vertex 890.409 374.514 72.052 + endloop + endfacet + facet normal 0.973488 0.146427 0.17573 + outer loop + vertex 891.523 367.111 72.0443 + vertex 891.705 373.938 65.3495 + vertex 890.409 374.514 72.052 + endloop + endfacet + facet normal 0.974674 0.146613 0.168862 + outer loop + vertex 891.523 367.111 72.0443 + vertex 890.409 374.514 72.052 + vertex 890.2 367.769 79.1123 + endloop + endfacet + facet normal 0.97815 0.116289 0.172335 + outer loop + vertex 891.082 360.36 79.103 + vertex 891.523 367.111 72.0443 + vertex 890.2 367.769 79.1123 + endloop + endfacet + facet normal 0.979679 0.116482 0.163284 + outer loop + vertex 891.082 360.36 79.103 + vertex 890.2 367.769 79.1123 + vertex 889.788 361.136 86.3141 + endloop + endfacet + facet normal 0.982387 0.0831048 0.167361 + outer loop + vertex 890.411 353.784 86.3103 + vertex 891.082 360.36 79.103 + vertex 889.788 361.136 86.3141 + endloop + endfacet + facet normal 0.984192 0.0832634 0.156309 + outer loop + vertex 890.411 353.784 86.3103 + vertex 889.788 361.136 86.3141 + vertex 889.174 354.627 93.6473 + endloop + endfacet + facet normal 0.985925 0.0451129 0.160984 + outer loop + vertex 889.505 347.393 93.6462 + vertex 890.411 353.784 86.3103 + vertex 889.174 354.627 93.6473 + endloop + endfacet + facet normal 0.984064 0.0838369 0.156807 + outer loop + vertex 889.174 354.627 93.6473 + vertex 889.788 361.136 86.3141 + vertex 888.556 361.874 93.6507 + endloop + endfacet + facet normal 0.982456 0.082811 0.1671 + outer loop + vertex 891.712 352.897 79.1014 + vertex 891.082 360.36 79.103 + vertex 890.411 353.784 86.3103 + endloop + endfacet + facet normal 0.984081 0.0441575 0.172147 + outer loop + vertex 890.74 346.449 86.3103 + vertex 891.712 352.897 79.1014 + vertex 890.411 353.784 86.3103 + endloop + endfacet + facet normal 0.980884 0.0826766 0.176158 + outer loop + vertex 891.712 352.897 79.1014 + vertex 892.414 359.611 72.0392 + vertex 891.082 360.36 79.103 + endloop + endfacet + facet normal 0.980776 0.0831078 0.176557 + outer loop + vertex 893.054 352.058 72.0394 + vertex 892.414 359.611 72.0392 + vertex 891.712 352.897 79.1014 + endloop + endfacet + facet normal 0.982404 0.0439928 0.181514 + outer loop + vertex 892.044 345.464 79.1065 + vertex 893.054 352.058 72.0394 + vertex 891.712 352.897 79.1014 + endloop + endfacet + facet normal 0.979443 0.082995 0.183857 + outer loop + vertex 893.054 352.058 72.0394 + vertex 893.731 358.975 65.3103 + vertex 892.414 359.611 72.0392 + endloop + endfacet + facet normal 0.976689 0.116754 0.180131 + outer loop + vertex 893.731 358.975 65.3103 + vertex 892.825 366.512 65.3393 + vertex 892.414 359.611 72.0392 + endloop + endfacet + facet normal 0.976951 0.115896 0.179264 + outer loop + vertex 892.414 359.611 72.0392 + vertex 892.825 366.512 65.3393 + vertex 891.523 367.111 72.0443 + endloop + endfacet + facet normal 0.975918 0.116645 0.184329 + outer loop + vertex 893.731 358.975 65.3103 + vertex 893.998 366.022 59.4384 + vertex 892.825 366.512 65.3393 + endloop + endfacet + facet normal 0.972569 0.145809 0.181243 + outer loop + vertex 893.998 366.022 59.4384 + vertex 892.886 373.301 59.5503 + vertex 892.825 366.512 65.3393 + endloop + endfacet + facet normal 0.972362 0.146371 0.1819 + outer loop + vertex 892.825 366.512 65.3393 + vertex 892.886 373.301 59.5503 + vertex 891.705 373.938 65.3495 + endloop + endfacet + facet normal 0.97225 0.145733 0.183009 + outer loop + vertex 893.998 366.022 59.4384 + vertex 893.789 372.957 55.0272 + vertex 892.886 373.301 59.5503 + endloop + endfacet + facet normal 0.975643 0.117446 0.185278 + outer loop + vertex 894.921 358.428 59.3912 + vertex 893.998 366.022 59.4384 + vertex 893.731 358.975 65.3103 + endloop + endfacet + facet normal 0.978442 0.0832379 0.189006 + outer loop + vertex 894.375 351.358 65.3302 + vertex 894.921 358.428 59.3912 + vertex 893.731 358.975 65.3103 + endloop + endfacet + facet normal 0.977939 0.0848511 0.19088 + outer loop + vertex 895.588 350.73 59.3939 + vertex 894.921 358.428 59.3912 + vertex 894.375 351.358 65.3302 + endloop + endfacet + facet normal 0.979675 0.0452139 0.19543 + outer loop + vertex 894.724 343.766 65.3405 + vertex 895.588 350.73 59.3939 + vertex 894.375 351.358 65.3302 + endloop + endfacet + facet normal 0.976696 0.0847456 0.197189 + outer loop + vertex 895.588 350.73 59.3939 + vertex 895.914 357.687 54.7913 + vertex 894.921 358.428 59.3912 + endloop + endfacet + facet normal 0.974675 0.117296 0.190394 + outer loop + vertex 894.921 358.428 59.3912 + vertex 894.972 365.4 54.8346 + vertex 893.998 366.022 59.4384 + endloop + endfacet + facet normal 0.979359 0.0833029 0.184165 + outer loop + vertex 894.375 351.358 65.3302 + vertex 893.731 358.975 65.3103 + vertex 893.054 352.058 72.0394 + endloop + endfacet + facet normal 0.981072 0.0438198 0.188621 + outer loop + vertex 893.386 344.549 72.058 + vertex 894.375 351.358 65.3302 + vertex 893.054 352.058 72.0394 + endloop + endfacet + facet normal 0.979672 0.116506 0.163306 + outer loop + vertex 889.788 361.136 86.3141 + vertex 890.2 367.769 79.1123 + vertex 888.92 368.431 86.3206 + endloop + endfacet + facet normal 0.978217 0.116052 0.172113 + outer loop + vertex 892.414 359.611 72.0392 + vertex 891.523 367.111 72.0443 + vertex 891.082 360.36 79.103 + endloop + endfacet + facet normal 0.974854 0.146039 0.168319 + outer loop + vertex 890.2 367.769 79.1123 + vertex 890.409 374.514 72.052 + vertex 889.106 375.067 79.1185 + endloop + endfacet + facet normal 0.973449 0.146544 0.175848 + outer loop + vertex 892.825 366.512 65.3393 + vertex 891.705 373.938 65.3495 + vertex 891.523 367.111 72.0443 + endloop + endfacet + facet normal 0.969769 0.173271 0.171829 + outer loop + vertex 890.409 374.514 72.052 + vertex 890.382 381.341 65.3174 + vertex 889.104 381.814 72.0505 + endloop + endfacet + facet normal 0.968513 0.173975 0.178086 + outer loop + vertex 892.886 373.301 59.5503 + vertex 891.593 380.609 59.4434 + vertex 891.705 373.938 65.3495 + endloop + endfacet + facet normal 0.967181 0.173845 0.185306 + outer loop + vertex 892.886 373.301 59.5503 + vertex 892.607 379.118 55.5475 + vertex 891.593 380.609 59.4434 + endloop + endfacet + facet normal 0.963767 0.198115 0.178616 + outer loop + vertex 891.593 380.609 59.4434 + vertex 891.209 387.062 54.3543 + vertex 890.048 388.238 59.3141 + endloop + endfacet + facet normal 0.960494 0.217594 0.173502 + outer loop + vertex 890.048 388.238 59.3141 + vertex 889.253 395.399 54.7396 + vertex 888.337 395.725 59.3981 + endloop + endfacet + facet normal 0.965553 0.197579 0.169323 + outer loop + vertex 890.382 381.341 65.3174 + vertex 888.877 388.705 65.3079 + vertex 889.104 381.814 72.0505 + endloop + endfacet + facet normal 0.970846 0.173462 0.165434 + outer loop + vertex 890.409 374.514 72.052 + vertex 889.104 381.814 72.0505 + vertex 889.106 375.067 79.1185 + endloop + endfacet + facet normal 0.976229 0.146253 0.159961 + outer loop + vertex 890.2 367.769 79.1123 + vertex 889.106 375.067 79.1185 + vertex 888.92 368.431 86.3206 + endloop + endfacet + facet normal 0.981304 0.11671 0.153037 + outer loop + vertex 889.788 361.136 86.3141 + vertex 888.92 368.431 86.3206 + vertex 888.556 361.874 93.6507 + endloop + endfacet + facet normal 0.985838 0.0839935 0.145152 + outer loop + vertex 889.174 354.627 93.6473 + vertex 888.556 361.874 93.6507 + vertex 888.005 355.399 101.14 + endloop + endfacet + facet normal 0.987701 0.0463542 0.149323 + outer loop + vertex 888.341 348.254 101.138 + vertex 889.174 354.627 93.6473 + vertex 888.005 355.399 101.14 + endloop + endfacet + facet normal 0.990724 0.0861797 0.105064 + outer loop + vertex 885.06 357.283 124.319 + vertex 885.326 363.745 116.512 + vertex 884.455 364.233 124.32 + endloop + endfacet + facet normal 0.989195 0.0850417 0.119419 + outer loop + vertex 886.919 356.101 108.774 + vertex 886.31 363.185 108.774 + vertex 885.931 356.731 116.513 + endloop + endfacet + facet normal 0.986073 0.118014 0.117186 + outer loop + vertex 885.326 363.745 116.512 + vertex 885.47 370.22 108.774 + vertex 884.492 370.708 116.512 + endloop + endfacet + facet normal 0.984537 0.117296 0.13011 + outer loop + vertex 887.394 362.559 101.14 + vertex 886.546 369.67 101.14 + vertex 886.31 363.185 108.774 + endloop + endfacet + facet normal 0.980901 0.146663 0.127762 + outer loop + vertex 885.47 370.22 108.774 + vertex 885.498 376.684 101.141 + vertex 884.433 377.155 108.775 + endloop + endfacet + facet normal 0.979383 0.1464 0.139195 + outer loop + vertex 887.7 369.069 93.6527 + vertex 886.64 376.165 93.6539 + vertex 886.546 369.67 101.14 + endloop + endfacet + facet normal 0.975474 0.172615 0.13658 + outer loop + vertex 885.498 376.684 101.141 + vertex 885.403 383.149 93.6531 + vertex 884.277 383.583 101.141 + endloop + endfacet + facet normal 0.973918 0.172789 0.147063 + outer loop + vertex 887.843 375.62 86.3245 + vertex 886.588 382.696 86.3226 + vertex 886.64 376.165 93.6539 + endloop + endfacet + facet normal 0.969957 0.19581 0.144367 + outer loop + vertex 885.403 383.149 93.6531 + vertex 885.177 389.678 86.317 + vertex 884.013 390.033 93.6516 + endloop + endfacet + facet normal 0.968236 0.196654 0.15442 + outer loop + vertex 887.828 382.247 79.1184 + vertex 886.39 389.333 79.1122 + vertex 886.588 382.696 86.3226 + endloop + endfacet + facet normal 0.964511 0.216422 0.151264 + outer loop + vertex 885.177 389.678 86.317 + vertex 884.81 396.351 79.1063 + vertex 883.628 396.583 86.3125 + endloop + endfacet + facet normal 0.962827 0.217518 0.160155 + outer loop + vertex 887.636 389.016 72.0515 + vertex 886.028 396.137 72.0474 + vertex 886.39 389.333 79.1122 + endloop + endfacet + facet normal 0.957916 0.235296 0.164414 + outer loop + vertex 886.028 396.137 72.0474 + vertex 885.479 403.043 65.3636 + vertex 884.291 403.211 72.0424 + endloop + endfacet + facet normal 0.953905 0.2518 0.163284 + outer loop + vertex 885.479 403.043 65.3636 + vertex 883.595 410.184 65.3551 + vertex 884.291 403.211 72.0424 + endloop + endfacet + facet normal 0.949379 0.265563 0.167796 + outer loop + vertex 883.595 410.184 65.3551 + vertex 882.712 417.054 59.4795 + vertex 881.583 417.376 65.3603 + endloop + endfacet + facet normal 0.946509 0.276308 0.166658 + outer loop + vertex 882.712 417.054 59.4795 + vertex 880.558 424.447 59.4553 + vertex 881.583 417.376 65.3603 + endloop + endfacet + facet normal 0.945697 0.276087 0.171558 + outer loop + vertex 882.712 417.054 59.4795 + vertex 881.651 423.196 55.444 + vertex 880.558 424.447 59.4553 + endloop + endfacet + facet normal 0.9431 0.284574 0.17199 + outer loop + vertex 880.558 424.447 59.4553 + vertex 879.395 431.4 54.3281 + vertex 878.279 432.074 59.3352 + endloop + endfacet + facet normal 0.940877 0.290867 0.173631 + outer loop + vertex 878.279 432.074 59.3352 + vertex 876.778 439.679 54.7238 + vertex 875.97 439.493 59.4163 + endloop + endfacet + facet normal 0.944235 0.286201 0.162814 + outer loop + vertex 879.462 424.611 65.3633 + vertex 877.277 431.818 65.3648 + vertex 878.385 424.343 72.0824 + endloop + endfacet + facet normal 0.946664 0.278024 0.162878 + outer loop + vertex 880.452 417.31 72.0699 + vertex 879.462 424.611 65.3633 + vertex 878.385 424.343 72.0824 + endloop + endfacet + facet normal 0.951168 0.266398 0.155923 + outer loop + vertex 882.428 410.265 72.0525 + vertex 880.452 417.31 72.0699 + vertex 881.278 410.239 79.1136 + endloop + endfacet + facet normal 0.955062 0.251719 0.156505 + outer loop + vertex 883.105 403.313 79.1035 + vertex 882.428 410.265 72.0525 + vertex 881.278 410.239 79.1136 + endloop + endfacet + facet normal 0.960302 0.23522 0.14997 + outer loop + vertex 884.81 396.351 79.1063 + vertex 883.105 403.313 79.1035 + vertex 883.628 396.583 86.3125 + endloop + endfacet + facet normal 0.965755 0.216696 0.142687 + outer loop + vertex 885.177 389.678 86.317 + vertex 883.628 396.583 86.3125 + vertex 884.013 390.033 93.6516 + endloop + endfacet + facet normal 0.971307 0.19608 0.134596 + outer loop + vertex 885.403 383.149 93.6531 + vertex 884.013 390.033 93.6516 + vertex 884.277 383.583 101.141 + endloop + endfacet + facet normal 0.976905 0.172869 0.125587 + outer loop + vertex 885.498 376.684 101.141 + vertex 884.277 383.583 101.141 + vertex 884.433 377.155 108.775 + endloop + endfacet + facet normal 0.982455 0.146897 0.114907 + outer loop + vertex 885.47 370.22 108.774 + vertex 884.433 377.155 108.775 + vertex 884.492 370.708 116.512 + endloop + endfacet + facet normal 0.987662 0.118205 0.102722 + outer loop + vertex 885.326 363.745 116.512 + vertex 884.492 370.708 116.512 + vertex 884.455 364.233 124.32 + endloop + endfacet + facet normal 0.99231 0.0863187 0.08871 + outer loop + vertex 885.06 357.283 124.319 + vertex 884.455 364.233 124.32 + vertex 884.317 357.754 132.177 + endloop + endfacet + facet normal 0.996036 0.0497198 0.0737617 + outer loop + vertex 884.66 350.867 132.177 + vertex 884.317 357.754 132.177 + vertex 884.055 351.297 140.065 + endloop + endfacet + facet normal 0.997072 0.00631476 0.0762068 + outer loop + vertex 884.098 344.501 140.065 + vertex 884.66 350.867 132.177 + vertex 884.055 351.297 140.065 + endloop + endfacet + facet normal 0.99359 0.086905 0.0722921 + outer loop + vertex 883.711 358.14 140.065 + vertex 883.716 364.649 132.177 + vertex 883.112 364.991 140.065 + endloop + endfacet + facet normal 0.990413 0.118688 0.0706707 + outer loop + vertex 883.716 364.649 132.177 + vertex 882.896 371.493 132.177 + vertex 883.112 364.991 140.065 + endloop + endfacet + facet normal 0.986682 0.147158 0.0693014 + outer loop + vertex 882.296 371.789 140.065 + vertex 881.889 378.235 132.177 + vertex 881.297 378.488 140.065 + endloop + endfacet + facet normal 0.985406 0.147242 0.0854142 + outer loop + vertex 883.631 371.133 124.319 + vertex 882.615 377.931 124.319 + vertex 882.896 371.493 132.177 + endloop + endfacet + facet normal 0.981381 0.172835 0.083778 + outer loop + vertex 881.889 378.235 132.177 + vertex 881.437 384.611 124.319 + vertex 880.722 384.86 132.176 + endloop + endfacet + facet normal 0.979933 0.173021 0.0989747 + outer loop + vertex 883.467 377.571 116.513 + vertex 882.276 384.317 116.513 + vertex 882.615 377.931 124.319 + endloop + endfacet + facet normal 0.975822 0.195728 0.0972765 + outer loop + vertex 881.437 384.611 124.319 + vertex 880.943 390.954 116.513 + vertex 880.119 391.182 124.319 + endloop + endfacet + facet normal 0.974261 0.196025 0.111311 + outer loop + vertex 883.229 383.975 108.775 + vertex 881.878 390.687 108.776 + vertex 882.276 384.317 116.513 + endloop + endfacet + facet normal 0.970204 0.21613 0.10951 + outer loop + vertex 880.943 390.954 116.513 + vertex 880.4 397.312 108.775 + vertex 879.484 397.502 116.512 + endloop + endfacet + facet normal 0.968637 0.216494 0.12195 + outer loop + vertex 882.909 390.377 101.141 + vertex 881.409 397.087 101.14 + vertex 881.878 390.687 108.776 + endloop + endfacet + facet normal 0.964573 0.234812 0.120261 + outer loop + vertex 880.4 397.312 108.775 + vertex 879.788 403.737 101.138 + vertex 878.803 403.874 108.772 + endloop + endfacet + facet normal 0.963096 0.235048 0.13114 + outer loop + vertex 882.49 396.836 93.6497 + vertex 880.845 403.578 93.6466 + vertex 881.409 397.087 101.14 + endloop + endfacet + facet normal 0.958944 0.252123 0.129847 + outer loop + vertex 879.788 403.737 101.138 + vertex 879.078 410.295 93.6437 + vertex 878.047 410.359 101.134 + endloop + endfacet + facet normal 0.957601 0.25203 0.139574 + outer loop + vertex 881.953 403.429 86.3129 + vertex 880.16 410.241 86.3131 + vertex 880.845 403.578 93.6466 + endloop + endfacet + facet normal 0.952303 0.266921 0.147892 + outer loop + vertex 880.16 410.241 86.3131 + vertex 879.341 417.15 79.1222 + vertex 878.251 417.052 86.314 + endloop + endfacet + facet normal 0.94881 0.279274 0.147531 + outer loop + vertex 879.341 417.15 79.1222 + vertex 877.307 424.056 79.1308 + vertex 878.251 417.052 86.314 + endloop + endfacet + facet normal 0.94443 0.288619 0.157327 + outer loop + vertex 877.307 424.056 79.1308 + vertex 876.255 431.334 72.0882 + vertex 875.205 430.93 79.1368 + endloop + endfacet + facet normal 0.942411 0.295106 0.157399 + outer loop + vertex 876.255 431.334 72.0882 + vertex 874.093 438.242 72.0826 + vertex 875.205 430.93 79.1368 + endloop + endfacet + facet normal 0.937683 0.302956 0.170202 + outer loop + vertex 874.093 438.242 72.0826 + vertex 872.869 445.822 65.3329 + vertex 871.9 445.044 72.0609 + endloop + endfacet + facet normal 0.935219 0.310213 0.170687 + outer loop + vertex 872.869 445.822 65.3329 + vertex 870.612 452.657 65.2816 + vertex 871.9 445.044 72.0609 + endloop + endfacet + facet normal 0.927311 0.320457 0.193394 + outer loop + vertex 870.612 452.657 65.2816 + vertex 869.129 460.519 59.3646 + vertex 868.287 459.415 65.2333 + endloop + endfacet + facet normal 0.936424 0.29503 0.189915 + outer loop + vertex 869.129 460.519 59.3646 + vertex 866.932 467.487 59.3715 + vertex 868.287 459.415 65.2333 + endloop + endfacet + facet normal 0.955425 0.208008 0.209512 + outer loop + vertex 866.932 467.487 59.3715 + vertex 866.166 476.225 54.1891 + vertex 865.35 474.6 59.5221 + endloop + endfacet + facet normal 0.925206 0.320369 0.203367 + outer loop + vertex 867.315 458.266 71.9395 + vertex 866.06 466.123 65.2698 + vertex 865.09 464.694 71.9355 + endloop + endfacet + facet normal 0.927447 0.332329 0.171461 + outer loop + vertex 869.645 451.725 72.0136 + vertex 867.315 458.266 71.9395 + vertex 868.634 450.878 79.1256 + endloop + endfacet + facet normal 0.930902 0.322863 0.170824 + outer loop + vertex 870.879 444.39 79.1553 + vertex 869.645 451.725 72.0136 + vertex 868.634 450.878 79.1256 + endloop + endfacet + facet normal 0.93956 0.307447 0.150675 + outer loop + vertex 873.059 437.728 79.1502 + vertex 870.879 444.39 79.1553 + vertex 872.037 437.317 86.3667 + endloop + endfacet + facet normal 0.942282 0.299048 0.150582 + outer loop + vertex 874.16 430.641 86.3345 + vertex 873.059 437.728 79.1502 + vertex 872.037 437.317 86.3667 + endloop + endfacet + facet normal 0.946796 0.290451 0.138619 + outer loop + vertex 876.241 423.865 86.3197 + vertex 874.16 430.641 86.3345 + vertex 875.211 423.726 93.6463 + endloop + endfacet + facet normal 0.94975 0.280529 0.138846 + outer loop + vertex 877.195 417.013 93.6424 + vertex 876.241 423.865 86.3197 + vertex 875.211 423.726 93.6463 + endloop + endfacet + facet normal 0.954793 0.267753 0.129141 + outer loop + vertex 879.078 410.295 93.6437 + vertex 877.195 417.013 93.6424 + vertex 878.047 410.359 101.134 + endloop + endfacet + facet normal 0.960217 0.252451 0.119381 + outer loop + vertex 879.788 403.737 101.138 + vertex 878.047 410.359 101.134 + vertex 878.803 403.874 108.772 + endloop + endfacet + facet normal 0.965887 0.235126 0.108532 + outer loop + vertex 880.4 397.312 108.775 + vertex 878.803 403.874 108.772 + vertex 879.484 397.502 116.512 + endloop + endfacet + facet normal 0.971546 0.216426 0.0962203 + outer loop + vertex 880.943 390.954 116.513 + vertex 879.484 397.502 116.512 + vertex 880.119 391.182 124.319 + endloop + endfacet + facet normal 0.977117 0.195987 0.082655 + outer loop + vertex 881.437 384.611 124.319 + vertex 880.119 391.182 124.319 + vertex 880.722 384.86 132.176 + endloop + endfacet + facet normal 0.982553 0.173041 0.0681638 + outer loop + vertex 881.889 378.235 132.177 + vertex 880.722 384.86 132.176 + vertex 881.297 378.488 140.065 + endloop + endfacet + facet normal 0.987662 0.147303 0.0531642 + outer loop + vertex 882.296 371.789 140.065 + vertex 881.297 378.488 140.065 + vertex 881.837 372.022 147.951 + endloop + endfacet + facet normal 0.991434 0.118819 0.054225 + outer loop + vertex 882.648 365.257 147.951 + vertex 882.296 371.789 140.065 + vertex 881.837 372.022 147.951 + endloop + endfacet + facet normal 0.995452 0.087211 0.0383476 + outer loop + vertex 883.245 358.441 147.951 + vertex 882.648 365.257 147.951 + vertex 882.923 358.657 155.804 + endloop + endfacet + facet normal 0.998477 0.0507249 0.0216761 + outer loop + vertex 883.268 351.872 155.804 + vertex 882.923 358.657 155.804 + vertex 883.091 352.017 163.624 + endloop + endfacet + facet normal 0.99972 0.00735113 0.0225089 + outer loop + vertex 883.14 345.292 163.624 + vertex 883.268 351.872 155.804 + vertex 883.091 352.017 163.624 + endloop + endfacet + facet normal 0.995985 0.0870552 0.0208855 + outer loop + vertex 882.746 358.786 163.624 + vertex 882.328 365.448 155.804 + vertex 882.154 365.564 163.624 + endloop + endfacet + facet normal 0.992862 0.118233 -0.0156571 + outer loop + vertex 882.253 365.568 179.323 + vertex 881.324 372.32 171.447 + vertex 881.452 372.289 179.322 + endloop + endfacet + facet normal 0.992894 0.118966 0.00284836 + outer loop + vertex 882.154 365.564 163.624 + vertex 881.348 372.286 163.624 + vertex 882.126 365.602 171.448 + endloop + endfacet + facet normal 0.989148 0.146906 0.00209027 + outer loop + vertex 881.324 372.32 171.447 + vertex 880.363 378.906 163.623 + vertex 880.342 378.935 171.446 + endloop + endfacet + facet normal 0.988892 0.147309 0.0197994 + outer loop + vertex 881.52 372.185 155.804 + vertex 880.531 378.823 155.804 + vertex 881.348 372.286 163.624 + endloop + endfacet + facet normal 0.984796 0.17266 0.0191321 + outer loop + vertex 880.363 378.906 163.623 + vertex 879.387 385.339 155.802 + vertex 879.223 385.408 163.621 + endloop + endfacet + facet normal 0.984245 0.173086 0.0361064 + outer loop + vertex 880.843 378.684 147.951 + vertex 879.693 385.225 147.95 + vertex 880.531 378.823 155.804 + endloop + endfacet + facet normal 0.980039 0.195655 0.035241 + outer loop + vertex 879.387 385.339 155.802 + vertex 878.408 391.656 147.947 + vertex 878.108 391.745 155.799 + endloop + endfacet + facet normal 0.979264 0.195939 0.0514792 + outer loop + vertex 880.139 385.066 140.064 + vertex 878.846 391.534 140.063 + vertex 879.693 385.225 147.95 + endloop + endfacet + facet normal 0.975029 0.216241 0.0505698 + outer loop + vertex 878.408 391.656 147.947 + vertex 877.431 397.908 140.061 + vertex 877.002 397.996 147.946 + endloop + endfacet + facet normal 0.974048 0.216427 0.0662526 + outer loop + vertex 879.417 391.374 132.175 + vertex 877.991 397.796 132.173 + vertex 878.846 391.534 140.063 + endloop + endfacet + facet normal 0.969712 0.235322 0.0654428 + outer loop + vertex 877.431 397.908 140.061 + vertex 876.448 404.15 132.173 + vertex 875.9 404.216 140.065 + endloop + endfacet + facet normal 0.968572 0.235303 0.0806301 + outer loop + vertex 878.677 397.662 124.317 + vertex 877.12 404.073 124.316 + vertex 877.991 397.796 132.173 + endloop + endfacet + facet normal 0.964068 0.253324 0.0799997 + outer loop + vertex 876.448 404.15 132.173 + vertex 875.445 410.447 124.32 + vertex 874.787 410.467 132.186 + endloop + endfacet + facet normal 0.962871 0.252937 0.0943505 + outer loop + vertex 877.908 403.984 116.509 + vertex 876.215 410.428 116.509 + vertex 877.12 404.073 124.316 + endloop + endfacet + facet normal 0.95838 0.269565 0.094033 + outer loop + vertex 875.445 410.447 124.32 + vertex 874.406 416.862 116.519 + vertex 873.654 416.809 124.339 + endloop + endfacet + facet normal 0.957248 0.268755 0.106987 + outer loop + vertex 877.087 410.403 108.769 + vertex 875.257 416.923 108.771 + vertex 876.215 410.428 116.509 + endloop + endfacet + facet normal 0.953125 0.282964 0.107161 + outer loop + vertex 874.406 416.862 116.519 + vertex 873.325 423.431 108.788 + vertex 872.498 423.283 116.541 + endloop + endfacet + facet normal 0.952146 0.281763 0.118439 + outer loop + vertex 876.191 416.976 101.132 + vertex 874.235 423.584 101.141 + vertex 875.257 416.923 108.771 + endloop + endfacet + facet normal 0.947467 0.292396 0.129657 + outer loop + vertex 874.235 423.584 101.141 + vertex 873.156 430.392 93.6706 + vertex 872.208 430.138 101.171 + endloop + endfacet + facet normal 0.944589 0.301587 0.129605 + outer loop + vertex 873.156 430.392 93.6706 + vertex 871.06 436.938 93.7108 + vertex 872.208 430.138 101.171 + endloop + endfacet + facet normal 0.938215 0.314592 0.144167 + outer loop + vertex 871.06 436.938 93.7108 + vertex 869.877 443.821 86.3932 + vertex 868.929 443.288 93.7279 + endloop + endfacet + facet normal 0.93237 0.331314 0.144628 + outer loop + vertex 869.877 443.821 86.3932 + vertex 867.65 450.1 86.3675 + vertex 868.929 443.288 93.7279 + endloop + endfacet + facet normal 0.917658 0.356532 0.175466 + outer loop + vertex 867.65 450.1 86.3675 + vertex 866.31 457.158 79.0361 + vertex 865.331 456.113 86.2749 + endloop + endfacet + facet normal 0.916159 0.353174 0.189527 + outer loop + vertex 865.331 456.113 86.2749 + vertex 864.079 463.273 78.9874 + vertex 863.099 461.923 86.2404 + endloop + endfacet + facet normal 0.917787 0.370819 0.141986 + outer loop + vertex 866.723 449.368 93.6788 + vertex 864.406 455.13 93.6066 + vertex 865.859 448.669 101.092 + endloop + endfacet + facet normal 0.927722 0.345708 0.140774 + outer loop + vertex 868.046 442.77 101.166 + vertex 866.723 449.368 93.6788 + vertex 865.859 448.669 101.092 + endloop + endfacet + facet normal 0.940287 0.318479 0.120132 + outer loop + vertex 870.144 436.564 101.194 + vertex 868.046 442.77 101.166 + vertex 869.299 436.192 108.795 + endloop + endfacet + facet normal 0.945048 0.304127 0.119959 + outer loop + vertex 871.328 429.882 108.811 + vertex 870.144 436.564 101.194 + vertex 869.299 436.192 108.795 + endloop + endfacet + facet normal 0.949862 0.293786 0.107019 + outer loop + vertex 873.325 423.431 108.788 + vertex 871.328 429.882 108.811 + vertex 872.498 423.283 116.541 + endloop + endfacet + facet normal 0.954411 0.283392 0.0937449 + outer loop + vertex 874.406 416.862 116.519 + vertex 872.498 423.283 116.541 + vertex 873.654 416.809 124.339 + endloop + endfacet + facet normal 0.959581 0.269947 0.0795828 + outer loop + vertex 875.445 410.447 124.32 + vertex 873.654 416.809 124.339 + vertex 874.787 410.467 132.186 + endloop + endfacet + facet normal 0.965117 0.253629 0.0649703 + outer loop + vertex 876.448 404.15 132.173 + vertex 874.787 410.467 132.186 + vertex 875.9 404.216 140.065 + endloop + endfacet + facet normal 0.970572 0.235541 0.0501135 + outer loop + vertex 877.431 397.908 140.061 + vertex 875.9 404.216 140.065 + vertex 877.002 397.996 147.946 + endloop + endfacet + facet normal 0.975686 0.216384 0.0348422 + outer loop + vertex 878.408 391.656 147.947 + vertex 877.002 397.996 147.946 + vertex 878.108 391.745 155.799 + endloop + endfacet + facet normal 0.980476 0.195735 0.0188398 + outer loop + vertex 879.387 385.339 155.802 + vertex 878.108 391.745 155.799 + vertex 879.223 385.408 163.621 + endloop + endfacet + facet normal 0.984975 0.172686 0.0019828 + outer loop + vertex 880.363 378.906 163.623 + vertex 879.223 385.408 163.621 + vertex 880.342 378.935 171.446 + endloop + endfacet + facet normal 0.989032 0.146886 -0.0154805 + outer loop + vertex 881.324 372.32 171.447 + vertex 880.342 378.935 171.446 + vertex 881.452 372.289 179.322 + endloop + endfacet + facet normal 0.992425 0.11818 -0.0335441 + outer loop + vertex 882.253 365.568 179.323 + vertex 881.452 372.289 179.322 + vertex 882.535 365.455 187.268 + endloop + endfacet + facet normal 0.994914 0.0859565 -0.0525072 + outer loop + vertex 883.121 358.669 187.267 + vertex 882.535 365.455 187.268 + vertex 883.561 358.457 195.255 + endloop + endfacet + facet normal 0.997396 0.0482014 -0.053647 + outer loop + vertex 883.89 351.654 195.255 + vertex 883.121 358.669 187.267 + vertex 883.561 358.457 195.255 + endloop + endfacet + facet normal 0.989043 0.114213 -0.0935389 + outer loop + vertex 884.372 364.657 211.153 + vertex 882.799 371.794 203.231 + vertex 883.583 371.494 211.153 + endloop + endfacet + facet normal 0.990559 0.116568 -0.0721487 + outer loop + vertex 882.98 365.268 195.254 + vertex 882.185 372.026 195.254 + vertex 883.592 365.003 203.232 + endloop + endfacet + facet normal 0.98688 0.144276 -0.0724663 + outer loop + vertex 882.799 371.794 203.231 + vertex 881.206 378.682 195.252 + vertex 881.821 378.482 203.229 + endloop + endfacet + facet normal 0.987923 0.145852 -0.0522993 + outer loop + vertex 881.737 372.191 187.266 + vertex 880.758 378.824 187.265 + vertex 882.185 372.026 195.254 + endloop + endfacet + facet normal 0.983878 0.170929 -0.0526057 + outer loop + vertex 881.206 378.682 195.252 + vertex 879.623 385.335 187.262 + vertex 880.071 385.215 195.248 + endloop + endfacet + facet normal 0.984526 0.171971 -0.0336736 + outer loop + vertex 880.472 378.906 179.321 + vertex 879.337 385.406 179.318 + vertex 880.758 378.824 187.265 + endloop + endfacet + facet normal 0.980294 0.194613 -0.0339115 + outer loop + vertex 879.623 385.335 187.262 + vertex 878.066 391.792 179.315 + vertex 878.353 391.734 187.26 + endloop + endfacet + facet normal 0.980622 0.195271 -0.0158109 + outer loop + vertex 879.205 385.428 171.444 + vertex 877.934 391.813 171.441 + vertex 879.337 385.406 179.318 + endloop + endfacet + facet normal 0.976286 0.21589 -0.0160616 + outer loop + vertex 878.066 391.792 179.315 + vertex 876.541 398.106 171.445 + vertex 876.674 398.089 179.322 + endloop + endfacet + facet normal 0.97633 0.21628 0.0014707 + outer loop + vertex 877.949 391.797 163.618 + vertex 876.554 398.094 163.621 + vertex 877.934 391.813 171.441 + endloop + endfacet + facet normal 0.97187 0.235516 0.00114865 + outer loop + vertex 876.541 398.106 171.445 + vertex 875.042 404.329 163.638 + vertex 875.031 404.335 171.466 + endloop + endfacet + facet normal 0.971643 0.235753 0.0181528 + outer loop + vertex 876.709 398.058 155.8 + vertex 875.193 404.306 155.814 + vertex 876.554 398.094 163.621 + endloop + endfacet + facet normal 0.967131 0.253665 0.017642 + outer loop + vertex 875.042 404.329 163.638 + vertex 873.562 410.513 155.84 + vertex 873.418 410.518 163.663 + endloop + endfacet + facet normal 0.966595 0.254029 0.0340916 + outer loop + vertex 875.48 404.268 147.956 + vertex 873.841 410.502 147.98 + vertex 875.193 404.306 155.814 + endloop + endfacet + facet normal 0.962309 0.269901 0.0333945 + outer loop + vertex 873.562 410.513 155.84 + vertex 872.098 416.702 147.993 + vertex 871.833 416.678 155.842 + endloop + endfacet + facet normal 0.961485 0.270389 0.0493605 + outer loop + vertex 874.25 410.486 140.084 + vertex 872.493 416.732 140.106 + vertex 873.841 410.502 147.98 + endloop + endfacet + facet normal 0.957683 0.283669 0.0487328 + outer loop + vertex 872.098 416.702 147.993 + vertex 870.658 422.924 140.081 + vertex 870.284 422.836 147.944 + endloop + endfacet + facet normal 0.956681 0.283963 0.0642388 + outer loop + vertex 873.013 416.767 132.21 + vertex 871.154 423.03 132.209 + vertex 872.493 416.732 140.106 + endloop + endfacet + facet normal 0.953049 0.295854 0.0645628 + outer loop + vertex 870.658 422.924 140.081 + vertex 869.251 429.193 132.133 + vertex 868.776 429.01 139.98 + endloop + endfacet + facet normal 0.952265 0.294833 0.0791461 + outer loop + vertex 871.769 423.149 124.356 + vertex 869.836 429.405 124.319 + vertex 871.154 423.03 132.209 + endloop + endfacet + facet normal 0.947371 0.309626 0.0813678 + outer loop + vertex 869.251 429.193 132.133 + vertex 867.872 435.493 124.211 + vertex 867.296 435.2 132.027 + endloop + endfacet + facet normal 0.947512 0.305677 0.09372 + outer loop + vertex 870.53 429.636 116.541 + vertex 868.539 435.831 116.472 + vertex 869.836 429.405 124.319 + endloop + endfacet + facet normal 0.938989 0.325356 0.111551 + outer loop + vertex 868.539 435.831 116.472 + vertex 867.232 442.262 108.713 + vertex 866.489 441.778 116.377 + endloop + endfacet + facet normal 0.928565 0.353764 0.112332 + outer loop + vertex 867.232 442.262 108.713 + vertex 865.05 448.005 108.662 + vertex 866.489 441.778 116.377 + endloop + endfacet + facet normal 0.907421 0.395554 0.14186 + outer loop + vertex 865.05 448.005 108.662 + vertex 863.53 454.206 101.094 + vertex 862.684 453.373 108.834 + endloop + endfacet + facet normal 0.923324 0.369105 0.105989 + outer loop + vertex 865.81 441.366 124.173 + vertex 864.274 447.426 116.456 + vertex 863.509 447.035 124.48 + endloop + endfacet + facet normal 0.940256 0.330537 0.081628 + outer loop + vertex 867.872 435.493 124.211 + vertex 865.81 441.366 124.173 + vertex 867.296 435.2 132.027 + endloop + endfacet + facet normal 0.948624 0.309737 0.0646175 + outer loop + vertex 869.251 429.193 132.133 + vertex 867.296 435.2 132.027 + vertex 868.776 429.01 139.98 + endloop + endfacet + facet normal 0.953983 0.295879 0.0486941 + outer loop + vertex 870.658 422.924 140.081 + vertex 868.776 429.01 139.98 + vertex 870.284 422.836 147.944 + endloop + endfacet + facet normal 0.958324 0.283735 0.0333026 + outer loop + vertex 872.098 416.702 147.993 + vertex 870.284 422.836 147.944 + vertex 871.833 416.678 155.842 + endloop + endfacet + facet normal 0.962696 0.270017 0.0175498 + outer loop + vertex 873.562 410.513 155.84 + vertex 871.833 416.678 155.842 + vertex 873.418 410.518 163.663 + endloop + endfacet + facet normal 0.967265 0.253768 0.00112924 + outer loop + vertex 875.042 404.329 163.638 + vertex 873.418 410.518 163.663 + vertex 875.031 404.335 171.466 + endloop + endfacet + facet normal 0.971734 0.235541 -0.0159434 + outer loop + vertex 876.541 398.106 171.445 + vertex 875.031 404.335 171.466 + vertex 876.674 398.089 179.322 + endloop + endfacet + facet normal 0.975856 0.215815 -0.0335955 + outer loop + vertex 878.066 391.792 179.315 + vertex 876.674 398.089 179.322 + vertex 878.353 391.734 187.26 + endloop + endfacet + facet normal 0.979531 0.194456 -0.0520104 + outer loop + vertex 879.623 385.335 187.262 + vertex 878.353 391.734 187.26 + vertex 880.071 385.215 195.248 + endloop + endfacet + facet normal 0.982724 0.170717 -0.0714826 + outer loop + vertex 881.206 378.682 195.252 + vertex 880.071 385.215 195.248 + vertex 881.821 378.482 203.229 + endloop + endfacet + facet normal 0.985283 0.144036 -0.0920386 + outer loop + vertex 882.799 371.794 203.231 + vertex 881.821 378.482 203.229 + vertex 883.583 371.494 211.153 + endloop + endfacet + facet normal 0.987021 0.11398 -0.113126 + outer loop + vertex 884.372 364.657 211.153 + vertex 883.583 371.494 211.153 + vertex 885.32 364.238 218.998 + endloop + endfacet + facet normal 0.987732 0.0800524 -0.134077 + outer loop + vertex 885.882 357.298 218.998 + vertex 885.32 364.238 218.998 + vertex 886.982 356.741 226.767 + endloop + endfacet + facet normal 0.989721 0.0403169 -0.137208 + outer loop + vertex 887.267 349.752 226.768 + vertex 885.882 357.298 218.998 + vertex 886.982 356.741 226.767 + endloop + endfacet + facet normal 0.979362 0.106671 -0.171675 + outer loop + vertex 889.075 362.547 242.089 + vertex 886.905 370.194 234.465 + vertex 888.301 369.647 242.09 + endloop + endfacet + facet normal 0.982151 0.110665 -0.152093 + outer loop + vertex 886.428 363.742 226.767 + vertex 885.644 370.69 226.766 + vertex 887.684 363.174 234.466 + endloop + endfacet + facet normal 0.978565 0.138343 -0.152552 + outer loop + vertex 886.905 370.194 234.465 + vertex 884.666 377.539 226.764 + vertex 885.927 377.112 234.463 + endloop + endfacet + facet normal 0.981063 0.141402 -0.132369 + outer loop + vertex 884.533 371.126 218.998 + vertex 883.555 377.91 218.995 + vertex 885.644 370.69 226.766 + endloop + endfacet + facet normal 0.977085 0.166482 -0.132622 + outer loop + vertex 884.666 377.539 226.764 + vertex 882.412 384.576 218.991 + vertex 883.52 384.265 226.76 + endloop + endfacet + facet normal 0.979291 0.168724 -0.111896 + outer loop + vertex 882.605 378.225 211.15 + vertex 881.465 384.84 211.147 + vertex 883.555 377.91 218.995 + endloop + endfacet + facet normal 0.97511 0.191378 -0.111961 + outer loop + vertex 882.412 384.576 218.991 + vertex 880.184 391.338 211.144 + vertex 881.126 391.13 218.989 + endloop + endfacet + facet normal 0.976941 0.193071 -0.0911574 + outer loop + vertex 880.684 385.05 203.225 + vertex 879.407 391.51 203.224 + vertex 881.465 384.84 211.147 + endloop + endfacet + facet normal 0.972648 0.213619 -0.091233 + outer loop + vertex 880.184 391.338 211.144 + vertex 878.006 397.879 203.232 + vertex 878.776 397.751 211.153 + endloop + endfacet + facet normal 0.974073 0.214842 -0.0708889 + outer loop + vertex 878.798 391.642 195.246 + vertex 877.401 397.976 195.255 + vertex 879.407 391.51 203.224 + endloop + endfacet + facet normal 0.969646 0.23397 -0.0710298 + outer loop + vertex 878.006 397.879 203.232 + vertex 875.885 404.251 195.28 + vertex 876.485 404.187 203.258 + endloop + endfacet + facet normal 0.970639 0.234913 -0.0517239 + outer loop + vertex 876.958 398.048 187.267 + vertex 875.447 404.296 187.291 + vertex 877.401 397.976 195.255 + endloop + endfacet + facet normal 0.966235 0.252378 -0.0519208 + outer loop + vertex 875.885 404.251 195.28 + vertex 873.825 410.499 187.314 + vertex 874.26 410.479 195.303 + endloop + endfacet + facet normal 0.966833 0.253201 -0.0335037 + outer loop + vertex 875.164 404.324 179.345 + vertex 873.545 410.512 179.367 + vertex 875.447 404.296 187.291 + endloop + endfacet + facet normal 0.962665 0.268577 -0.0337915 + outer loop + vertex 873.825 410.499 187.314 + vertex 871.83 416.649 179.346 + vertex 872.108 416.65 187.29 + endloop + endfacet + facet normal 0.96293 0.269266 -0.0161953 + outer loop + vertex 873.41 410.518 171.49 + vertex 871.695 416.651 171.474 + vertex 873.545 410.512 179.367 + endloop + endfacet + facet normal 0.958858 0.283413 -0.0163648 + outer loop + vertex 871.83 416.649 179.346 + vertex 869.903 422.708 171.388 + vertex 870.038 422.707 179.253 + endloop + endfacet + facet normal 0.958931 0.283638 0.000588597 + outer loop + vertex 871.697 416.661 163.656 + vertex 869.903 422.727 163.579 + vertex 871.695 416.651 171.474 + endloop + endfacet + facet normal 0.954136 0.29937 0.00107011 + outer loop + vertex 869.903 422.708 171.388 + vertex 868.032 428.699 163.486 + vertex 868.033 428.668 171.292 + endloop + endfacet + facet normal 0.954337 0.298228 0.017351 + outer loop + vertex 870.031 422.77 155.777 + vertex 868.16 428.765 155.678 + vertex 869.903 422.727 163.579 + endloop + endfacet + facet normal 0.947415 0.31944 0.0190401 + outer loop + vertex 868.032 428.699 163.486 + vertex 866.171 434.68 155.731 + vertex 866.045 434.589 163.564 + endloop + endfacet + facet normal 0.94812 0.316042 0.0344475 + outer loop + vertex 868.41 428.867 147.839 + vertex 866.43 434.81 147.836 + vertex 868.16 428.765 155.678 + endloop + endfacet + facet normal 0.937868 0.345011 0.0370171 + outer loop + vertex 866.171 434.68 155.731 + vertex 864.247 440.721 148.2 + vertex 864 440.537 156.169 + endloop + endfacet + facet normal 0.938595 0.341029 0.0523225 + outer loop + vertex 866.811 434.975 139.915 + vertex 864.651 440.885 140.15 + vertex 866.43 434.81 147.836 + endloop + endfacet + facet normal 0.924972 0.376379 0.0525964 + outer loop + vertex 864.247 440.721 148.2 + vertex 862.153 446.89 140.869 + vertex 861.842 446.507 149.08 + endloop + endfacet + facet normal 0.923394 0.377324 0.0704965 + outer loop + vertex 865.192 441.062 132.118 + vertex 862.798 446.808 132.711 + vertex 864.651 440.885 140.15 + endloop + endfacet + facet normal 0.90084 0.424413 0.0914405 + outer loop + vertex 862.798 446.808 132.711 + vertex 860.831 452.588 125.26 + vertex 860.144 452.155 134.041 + endloop + endfacet + facet normal 0.91582 0.353937 -0.189741 + outer loop + vertex 871.521 442.605 249.513 + vertex 867.917 447.968 242.122 + vertex 869.286 448.44 249.611 + endloop + endfacet + facet normal 0.928283 0.322916 -0.184435 + outer loop + vertex 873.698 436.344 249.51 + vertex 870.204 442.101 242.003 + vertex 871.521 442.605 249.513 + endloop + endfacet + facet normal 0.935483 0.303027 -0.181785 + outer loop + vertex 875.797 429.892 249.553 + vertex 872.353 435.962 241.949 + vertex 873.698 436.344 249.51 + endloop + endfacet + facet normal 0.937906 0.287953 -0.193429 + outer loop + vertex 877.819 423.342 249.61 + vertex 875.797 429.892 249.553 + vertex 879.303 423.505 257.048 + endloop + endfacet + facet normal 0.941844 0.274456 -0.193918 + outer loop + vertex 881.264 416.788 257.062 + vertex 877.819 423.342 249.61 + vertex 879.303 423.505 257.048 + endloop + endfacet + facet normal 0.943278 0.259654 -0.206897 + outer loop + vertex 883.116 410.052 257.055 + vertex 881.264 416.788 257.062 + vertex 884.722 410.005 264.319 + endloop + endfacet + facet normal 0.947469 0.243039 -0.207931 + outer loop + vertex 886.475 403.16 264.305 + vertex 883.116 410.052 257.055 + vertex 884.722 410.005 264.319 + endloop + endfacet + facet normal 0.951723 0.224935 -0.208873 + outer loop + vertex 888.101 396.274 264.297 + vertex 884.849 403.295 257.039 + vertex 886.475 403.16 264.305 + endloop + endfacet + facet normal 0.955869 0.205477 -0.209985 + outer loop + vertex 889.596 389.322 264.298 + vertex 886.456 396.497 257.027 + vertex 888.101 396.274 264.297 + endloop + endfacet + facet normal 0.959906 0.18385 -0.211611 + outer loop + vertex 890.945 382.274 264.296 + vertex 887.932 389.634 257.022 + vertex 889.596 389.322 264.298 + endloop + endfacet + facet normal 0.963804 0.159835 -0.213389 + outer loop + vertex 892.132 375.118 264.297 + vertex 889.267 382.686 257.024 + vertex 890.945 382.274 264.296 + endloop + endfacet + facet normal 0.967434 0.132727 -0.215534 + outer loop + vertex 893.131 367.844 264.3 + vertex 890.442 375.636 257.028 + vertex 892.132 375.118 264.297 + endloop + endfacet + facet normal 0.968082 0.101969 -0.228952 + outer loop + vertex 893.908 360.468 264.301 + vertex 893.131 367.844 264.3 + vertex 895.654 359.674 271.331 + endloop + endfacet + facet normal 0.968175 0.0664721 -0.241285 + outer loop + vertex 896.172 352.141 271.335 + vertex 895.654 359.674 271.331 + vertex 897.874 351.151 277.892 + endloop + endfacet + facet normal 0.968528 0.0249298 -0.247653 + outer loop + vertex 898.07 343.546 277.89 + vertex 896.172 352.141 271.335 + vertex 897.874 351.151 277.892 + endloop + endfacet + facet normal 0.965689 0.0991824 -0.240017 + outer loop + vertex 897.364 358.796 277.891 + vertex 894.874 367.165 271.331 + vertex 896.583 366.385 277.885 + endloop + endfacet + facet normal 0.962784 0.129892 -0.237013 + outer loop + vertex 896.583 366.385 277.885 + vertex 893.868 374.548 271.331 + vertex 895.577 373.856 277.892 + endloop + endfacet + facet normal 0.95939 0.157819 -0.233803 + outer loop + vertex 895.577 373.856 277.892 + vertex 892.672 381.806 271.338 + vertex 894.37 381.191 277.892 + endloop + endfacet + facet normal 0.955622 0.181731 -0.231863 + outer loop + vertex 894.37 381.191 277.892 + vertex 891.305 388.939 271.33 + vertex 892.995 388.425 277.893 + endloop + endfacet + facet normal 0.951779 0.203253 -0.229793 + outer loop + vertex 892.995 388.425 277.893 + vertex 889.797 395.987 271.334 + vertex 891.463 395.578 277.875 + endloop + endfacet + facet normal 0.947722 0.222489 -0.228741 + outer loop + vertex 891.463 395.578 277.875 + vertex 888.151 402.959 271.33 + vertex 889.798 402.669 277.875 + endloop + endfacet + facet normal 0.942085 0.239565 -0.234699 + outer loop + vertex 891.263 402.438 283.547 + vertex 887.997 409.724 277.876 + vertex 889.44 409.62 283.559 + endloop + endfacet + facet normal 0.943486 0.24163 -0.226824 + outer loop + vertex 888.151 402.959 271.33 + vertex 886.375 409.897 271.337 + vertex 889.798 402.669 277.875 + endloop + endfacet + facet normal 0.941102 0.25836 -0.218121 + outer loop + vertex 886.375 409.897 271.337 + vertex 882.846 416.838 264.33 + vertex 884.472 416.839 271.348 + endloop + endfacet + facet normal 0.937278 0.272612 -0.217237 + outer loop + vertex 882.846 416.838 264.33 + vertex 880.857 423.674 264.329 + vertex 884.472 416.839 271.348 + endloop + endfacet + facet normal 0.935849 0.284768 -0.207591 + outer loop + vertex 880.857 423.674 264.329 + vertex 877.254 430.184 257.013 + vertex 878.779 430.495 264.317 + endloop + endfacet + facet normal 0.931786 0.296254 -0.209783 + outer loop + vertex 878.779 430.495 264.317 + vertex 875.13 436.774 256.975 + vertex 876.633 437.224 264.288 + endloop + endfacet + facet normal 0.925338 0.313544 -0.213167 + outer loop + vertex 876.633 437.224 264.288 + vertex 872.937 443.139 256.942 + vertex 874.423 443.717 264.245 + endloop + endfacet + facet normal 0.913319 0.345184 -0.216094 + outer loop + vertex 874.423 443.717 264.245 + vertex 870.658 449.085 256.908 + vertex 872.114 449.789 264.184 + endloop + endfacet + facet normal 0.89347 0.390378 -0.222073 + outer loop + vertex 872.114 449.789 264.184 + vertex 868.256 454.454 256.865 + vertex 869.666 455.372 264.15 + endloop + endfacet + facet normal 0.9108 0.339547 -0.234842 + outer loop + vertex 875.985 444.236 271.348 + vertex 873.67 450.43 271.323 + vertex 877.551 444.598 277.945 + endloop + endfacet + facet normal 0.922997 0.3041 -0.235797 + outer loop + vertex 879.758 437.899 277.945 + vertex 875.985 444.236 271.348 + vertex 877.551 444.598 277.945 + endloop + endfacet + facet normal 0.928891 0.288187 -0.232613 + outer loop + vertex 881.91 430.943 277.919 + vertex 878.193 437.627 271.358 + vertex 879.758 437.899 277.945 + endloop + endfacet + facet normal 0.932373 0.279525 -0.229231 + outer loop + vertex 884.028 423.87 277.909 + vertex 880.351 430.768 271.363 + vertex 881.91 430.943 277.919 + endloop + endfacet + facet normal 0.935607 0.270033 -0.227423 + outer loop + vertex 886.068 416.784 277.89 + vertex 882.454 423.807 271.358 + vertex 884.028 423.87 277.909 + endloop + endfacet + facet normal 0.937898 0.256727 -0.233321 + outer loop + vertex 887.997 409.724 277.876 + vertex 886.068 416.784 277.89 + vertex 889.44 409.62 283.559 + endloop + endfacet + facet normal 0.94042 0.239153 -0.241694 + outer loop + vertex 891.263 402.438 283.547 + vertex 889.44 409.62 283.559 + vertex 892.353 402.677 288.023 + endloop + endfacet + facet normal 0.936227 0.254916 -0.241862 + outer loop + vertex 890.519 409.889 288.034 + vertex 887.498 416.757 283.576 + vertex 888.6 416.963 288.06 + endloop + endfacet + facet normal 0.932604 0.266581 -0.243276 + outer loop + vertex 888.6 416.963 288.06 + vertex 885.446 423.907 283.579 + vertex 886.552 424.129 288.063 + endloop + endfacet + facet normal 0.929754 0.274827 -0.245007 + outer loop + vertex 886.552 424.129 288.063 + vertex 883.333 431.047 283.605 + vertex 884.396 431.386 288.02 + endloop + endfacet + facet normal 0.9267 0.283922 -0.246203 + outer loop + vertex 884.396 431.386 288.02 + vertex 881.171 438.08 283.603 + vertex 882.204 438.532 288.009 + endloop + endfacet + facet normal 0.920541 0.299926 -0.250297 + outer loop + vertex 882.7 439.732 291.267 + vertex 879.897 445.627 288.022 + vertex 880.164 447.462 291.204 + endloop + endfacet + facet normal 0.917401 0.298794 -0.262865 + outer loop + vertex 882.7 439.732 291.267 + vertex 880.164 447.462 291.204 + vertex 881.916 443.655 292.993 + endloop + endfacet + facet normal 0.921383 0.300367 -0.246644 + outer loop + vertex 881.171 438.08 283.603 + vertex 878.943 444.928 283.619 + vertex 882.204 438.532 288.009 + endloop + endfacet + facet normal 0.911083 0.32945 -0.247771 + outer loop + vertex 878.943 444.928 283.619 + vertex 875.218 450.972 277.956 + vertex 876.54 451.584 283.631 + endloop + endfacet + facet normal 0.895304 0.362709 -0.258599 + outer loop + vertex 876.54 451.584 283.631 + vertex 872.697 457.069 278.018 + vertex 873.936 458.104 283.763 + endloop + endfacet + facet normal 0.90869 0.324043 -0.263209 + outer loop + vertex 879.897 445.627 288.022 + vertex 877.398 452.614 287.999 + vertex 880.164 447.462 291.204 + endloop + endfacet + facet normal 0.913261 0.308553 -0.265988 + outer loop + vertex 879.447 450.833 292.653 + vertex 880.674 447.367 292.844 + vertex 880.164 447.462 291.204 + endloop + endfacet + facet normal 0.916813 0.296204 -0.267802 + outer loop + vertex 880.674 447.367 292.844 + vertex 881.916 443.655 292.993 + vertex 880.164 447.462 291.204 + endloop + endfacet + facet normal 0.917067 0.297572 -0.265405 + outer loop + vertex 880.566 448.769 294.206 + vertex 881.235 449.189 296.987 + vertex 882.735 442.567 294.745 + endloop + endfacet + facet normal 0.923215 0.293463 -0.2481 + outer loop + vertex 881.916 443.655 292.993 + vertex 883.594 438.602 293.26 + vertex 882.7 439.732 291.267 + endloop + endfacet + facet normal 0.918981 0.289612 -0.267582 + outer loop + vertex 882.735 442.567 294.745 + vertex 883.611 442.09 297.238 + vertex 885.028 435.069 294.508 + endloop + endfacet + facet normal 0.924049 0.287663 -0.251762 + outer loop + vertex 883.594 438.602 293.26 + vertex 884.697 434.551 292.677 + vertex 882.7 439.732 291.267 + endloop + endfacet + facet normal 0.926614 0.280453 -0.250465 + outer loop + vertex 884.697 434.551 292.677 + vertex 886.265 429.538 292.867 + vertex 884.803 432.692 290.99 + endloop + endfacet + facet normal 0.922545 0.279843 -0.265705 + outer loop + vertex 885.028 435.069 294.508 + vertex 886.022 434.373 297.225 + vertex 887.359 427.326 294.445 + endloop + endfacet + facet normal 0.92414 0.276414 -0.263744 + outer loop + vertex 886.265 429.538 292.867 + vertex 887.434 425.717 292.957 + vertex 887.183 425.109 291.44 + endloop + endfacet + facet normal 0.926877 0.269402 -0.261384 + outer loop + vertex 887.434 425.717 292.957 + vertex 888.231 423.16 293.15 + vertex 887.183 425.109 291.44 + endloop + endfacet + facet normal 0.926853 0.269085 -0.261796 + outer loop + vertex 887.359 427.326 294.445 + vertex 888.313 426.692 297.169 + vertex 889.417 420.197 294.403 + endloop + endfacet + facet normal 0.926791 0.266452 -0.264694 + outer loop + vertex 888.231 423.16 293.15 + vertex 889.025 419.983 292.73 + vertex 887.183 425.109 291.44 + endloop + endfacet + facet normal 0.930242 0.260332 -0.258607 + outer loop + vertex 889.025 419.983 292.73 + vertex 890.193 416.184 293.105 + vertex 889.28 417.648 291.298 + endloop + endfacet + facet normal 0.931076 0.256803 -0.259134 + outer loop + vertex 889.417 420.197 294.403 + vertex 890.492 419.027 297.106 + vertex 891.56 412.279 294.254 + endloop + endfacet + facet normal 0.930393 0.25698 -0.2614 + outer loop + vertex 890.193 416.184 293.105 + vertex 890.957 413.005 292.701 + vertex 889.28 417.648 291.298 + endloop + endfacet + facet normal 0.932162 0.25024 -0.261635 + outer loop + vertex 890.957 413.005 292.701 + vertex 891.728 410.353 292.911 + vertex 891.136 410.874 291.299 + endloop + endfacet + facet normal 0.933684 0.240447 -0.265366 + outer loop + vertex 891.728 410.353 292.911 + vertex 892.578 407.091 292.946 + vertex 891.136 410.874 291.299 + endloop + endfacet + facet normal 0.939944 0.239256 -0.243438 + outer loop + vertex 893.544 403.325 292.977 + vertex 892.578 407.091 292.946 + vertex 893.629 404.456 294.416 + endloop + endfacet + facet normal 0.933803 0.25415 -0.251835 + outer loop + vertex 891.56 412.279 294.254 + vertex 890.492 419.027 297.106 + vertex 892.599 411.28 297.101 + endloop + endfacet + facet normal 0.933666 0.252641 -0.253851 + outer loop + vertex 892.599 411.28 297.101 + vertex 891.504 418.913 300.669 + vertex 893.607 411.112 300.641 + endloop + endfacet + facet normal 0.937362 0.252754 -0.239724 + outer loop + vertex 893.607 411.112 300.641 + vertex 892.53 419.214 304.973 + vertex 894.663 411.26 304.926 + endloop + endfacet + facet normal 0.944898 0.252703 -0.208107 + outer loop + vertex 894.663 411.26 304.926 + vertex 893.476 419.602 309.666 + vertex 895.644 411.476 309.641 + endloop + endfacet + facet normal 0.94543 0.221803 -0.238676 + outer loop + vertex 895.617 403.193 300.615 + vertex 896.735 403.093 304.948 + vertex 897.538 395.039 300.646 + endloop + endfacet + facet normal 0.949829 0.227667 -0.214457 + outer loop + vertex 898.776 394.594 305.115 + vertex 897.792 403.046 309.73 + vertex 900.023 394.046 310.058 + endloop + endfacet + facet normal 0.959255 0.231783 -0.161574 + outer loop + vertex 900.023 394.046 310.058 + vertex 898.518 403.397 314.536 + vertex 900.479 395.587 314.971 + endloop + endfacet + facet normal 0.95956 0.203235 -0.194781 + outer loop + vertex 902.156 383.486 308.921 + vertex 901.647 388.579 311.73 + vertex 902.88 383.096 312.084 + endloop + endfacet + facet normal 0.949263 0.18139 -0.256901 + outer loop + vertex 902.518 377.007 305.685 + vertex 900.802 385.91 305.63 + vertex 902.156 383.486 308.921 + endloop + endfacet + facet normal 0.964658 0.165992 -0.204648 + outer loop + vertex 903.157 379.12 309.559 + vertex 903.841 378.109 311.963 + vertex 903.86 374.442 309.077 + endloop + endfacet + facet normal 0.952154 0.152926 -0.264605 + outer loop + vertex 902.371 369.705 300.935 + vertex 902.518 377.007 305.685 + vertex 903.904 368.452 305.728 + endloop + endfacet + facet normal 0.953961 0.125791 -0.272277 + outer loop + vertex 902.371 369.705 300.935 + vertex 903.904 368.452 305.728 + vertex 903.466 361.371 300.923 + endloop + endfacet + facet normal 0.954856 0.125904 -0.26907 + outer loop + vertex 902.228 362.636 297.123 + vertex 902.371 369.705 300.935 + vertex 903.466 361.371 300.923 + endloop + endfacet + facet normal 0.967002 0.140329 -0.212637 + outer loop + vertex 904.644 370.462 309.573 + vertex 905.265 369.772 311.945 + vertex 905.179 366.024 309.077 + endloop + endfacet + facet normal 0.964189 0.146736 -0.220925 + outer loop + vertex 905.179 366.024 309.077 + vertex 905.265 369.772 311.945 + vertex 905.905 365.577 311.952 + endloop + endfacet + facet normal 0.964843 0.140623 -0.222042 + outer loop + vertex 905.179 366.024 309.077 + vertex 905.905 365.577 311.952 + vertex 905.866 362.056 309.552 + endloop + endfacet + facet normal 0.967371 0.135271 -0.214232 + outer loop + vertex 905.866 362.056 309.552 + vertex 905.905 365.577 311.952 + vertex 906.492 361.357 311.938 + endloop + endfacet + facet normal 0.96868 0.113033 -0.221096 + outer loop + vertex 905.866 362.056 309.552 + vertex 906.492 361.357 311.938 + vertex 906.273 357.581 309.046 + endloop + endfacet + facet normal 0.965413 0.120834 -0.231034 + outer loop + vertex 906.273 357.581 309.046 + vertex 906.492 361.357 311.938 + vertex 907.017 357.156 311.934 + endloop + endfacet + facet normal 0.966233 0.110519 -0.232763 + outer loop + vertex 906.273 357.581 309.046 + vertex 907.017 357.156 311.934 + vertex 906.845 353.602 309.531 + endloop + endfacet + facet normal 0.969822 0.102533 -0.221207 + outer loop + vertex 906.845 353.602 309.531 + vertex 907.017 357.156 311.934 + vertex 907.464 352.938 311.936 + endloop + endfacet + facet normal 0.970505 0.0774085 -0.228315 + outer loop + vertex 906.845 353.602 309.531 + vertex 907.464 352.938 311.936 + vertex 907.09 349.066 309.037 + endloop + endfacet + facet normal 0.967129 0.0859695 -0.239312 + outer loop + vertex 907.09 349.066 309.037 + vertex 907.464 352.938 311.936 + vertex 907.846 348.645 311.94 + endloop + endfacet + facet normal 0.967736 0.0717494 -0.241535 + outer loop + vertex 907.09 349.066 309.037 + vertex 907.846 348.645 311.94 + vertex 907.516 344.989 309.533 + endloop + endfacet + facet normal 0.970219 0.0659557 -0.233078 + outer loop + vertex 907.516 344.989 309.533 + vertex 907.846 348.645 311.94 + vertex 908.142 344.281 311.938 + endloop + endfacet + facet normal 0.969712 0.0372122 -0.241398 + outer loop + vertex 907.516 344.989 309.533 + vertex 908.142 344.281 311.938 + vertex 907.571 340.361 309.038 + endloop + endfacet + facet normal 0.966146 0.0468397 -0.253708 + outer loop + vertex 907.571 340.361 309.038 + vertex 908.142 344.281 311.938 + vertex 908.356 339.873 311.937 + endloop + endfacet + facet normal 0.966058 0.0289218 -0.2567 + outer loop + vertex 907.571 340.361 309.038 + vertex 908.356 339.873 311.937 + vertex 907.826 336.227 309.532 + endloop + endfacet + facet normal 0.968616 0.0225085 -0.247541 + outer loop + vertex 907.826 336.227 309.532 + vertex 908.356 339.873 311.937 + vertex 908.457 335.488 311.936 + endloop + endfacet + facet normal 0.966222 -0.0117093 -0.257443 + outer loop + vertex 907.826 336.227 309.532 + vertex 908.457 335.488 311.936 + vertex 907.639 331.653 309.038 + endloop + endfacet + facet normal 0.962757 -0.00120659 -0.270365 + outer loop + vertex 907.639 331.653 309.038 + vertex 908.457 335.488 311.936 + vertex 908.452 331.144 311.937 + endloop + endfacet + facet normal 0.961525 -0.0226272 -0.273784 + outer loop + vertex 907.639 331.653 309.038 + vertex 908.452 331.144 311.937 + vertex 907.684 327.592 309.533 + endloop + endfacet + facet normal 0.964068 -0.0298133 -0.263978 + outer loop + vertex 907.684 327.592 309.533 + vertex 908.452 331.144 311.937 + vertex 908.32 326.861 311.937 + endloop + endfacet + facet normal 0.958861 -0.0705228 -0.274978 + outer loop + vertex 907.684 327.592 309.533 + vertex 908.32 326.861 311.937 + vertex 907.213 323.128 309.036 + endloop + endfacet + facet normal 0.955141 -0.0573161 -0.290552 + outer loop + vertex 907.213 323.128 309.036 + vertex 908.32 326.861 311.937 + vertex 908.065 322.623 311.937 + endloop + endfacet + facet normal 0.952276 -0.082022 -0.294011 + outer loop + vertex 907.213 323.128 309.036 + vertex 908.065 322.623 311.937 + vertex 907.022 319.143 309.527 + endloop + endfacet + facet normal 0.955192 -0.0915872 -0.281461 + outer loop + vertex 907.022 319.143 309.527 + vertex 908.065 322.623 311.937 + vertex 907.662 318.428 311.932 + endloop + endfacet + facet normal 0.94582 -0.139493 -0.293198 + outer loop + vertex 907.022 319.143 309.527 + vertex 907.662 318.428 311.932 + vertex 906.218 314.741 309.028 + endloop + endfacet + facet normal 0.94176 -0.122024 -0.313365 + outer loop + vertex 906.218 314.741 309.028 + vertex 907.662 318.428 311.932 + vertex 907.117 314.243 311.924 + endloop + endfacet + facet normal 0.936637 -0.149962 -0.316579 + outer loop + vertex 906.218 314.741 309.028 + vertex 907.117 314.243 311.924 + vertex 905.746 310.771 309.514 + endloop + endfacet + facet normal 0.939312 -0.160188 -0.303368 + outer loop + vertex 905.746 310.771 309.514 + vertex 907.117 314.243 311.924 + vertex 906.399 310.049 311.914 + endloop + endfacet + facet normal 0.925472 -0.210724 -0.314796 + outer loop + vertex 905.746 310.771 309.514 + vertex 906.399 310.049 311.914 + vertex 904.571 306.333 309.03 + endloop + endfacet + facet normal 0.922343 -0.194316 -0.333952 + outer loop + vertex 904.571 306.333 309.03 + vertex 906.399 310.049 311.914 + vertex 905.509 305.839 311.907 + endloop + endfacet + facet normal 0.914402 -0.224862 -0.336609 + outer loop + vertex 904.571 306.333 309.03 + vertex 905.509 305.839 311.907 + vertex 903.771 302.324 309.535 + endloop + endfacet + facet normal 0.915838 -0.231143 -0.32835 + outer loop + vertex 903.771 302.324 309.535 + vertex 905.509 305.839 311.907 + vertex 904.448 301.614 311.92 + endloop + endfacet + facet normal 0.898754 -0.279431 -0.337876 + outer loop + vertex 903.771 302.324 309.535 + vertex 904.448 301.614 311.92 + vertex 902.212 297.817 309.114 + endloop + endfacet + facet normal 0.895987 -0.263134 -0.357725 + outer loop + vertex 902.212 297.817 309.114 + vertex 904.448 301.614 311.92 + vertex 903.234 297.421 311.966 + endloop + endfacet + facet normal 0.887314 -0.290241 -0.358378 + outer loop + vertex 902.212 297.817 309.114 + vertex 903.234 297.421 311.966 + vertex 901.158 293.872 309.699 + endloop + endfacet + facet normal 0.889623 -0.30126 -0.343241 + outer loop + vertex 901.158 293.872 309.699 + vertex 903.234 297.421 311.966 + vertex 901.868 293.297 312.044 + endloop + endfacet + facet normal 0.873955 -0.339422 -0.347844 + outer loop + vertex 901.158 293.872 309.699 + vertex 901.868 293.297 312.044 + vertex 899.44 289.744 309.41 + endloop + endfacet + facet normal 0.873378 -0.334365 -0.354134 + outer loop + vertex 899.44 289.744 309.41 + vertex 901.868 293.297 312.044 + vertex 900.272 289.083 312.088 + endloop + endfacet + facet normal 0.859449 -0.365453 -0.357481 + outer loop + vertex 899.44 289.744 309.41 + vertex 900.272 289.083 312.088 + vertex 897.634 285.242 309.672 + endloop + endfacet + facet normal 0.859814 -0.367742 -0.35424 + outer loop + vertex 897.634 285.242 309.672 + vertex 900.272 289.083 312.088 + vertex 898.519 284.891 312.184 + endloop + endfacet + facet normal 0.844972 -0.401162 -0.353683 + outer loop + vertex 897.634 285.242 309.672 + vertex 898.519 284.891 312.184 + vertex 895.71 281.032 309.851 + endloop + endfacet + facet normal 0.844223 -0.396198 -0.36099 + outer loop + vertex 895.71 281.032 309.851 + vertex 898.519 284.891 312.184 + vertex 896.65 280.87 312.227 + endloop + endfacet + facet normal 0.826878 -0.434726 -0.356771 + outer loop + vertex 895.71 281.032 309.851 + vertex 896.65 280.87 312.227 + vertex 893.68 277.124 309.906 + endloop + endfacet + facet normal 0.825503 -0.423598 -0.372973 + outer loop + vertex 893.68 277.124 309.906 + vertex 896.65 280.87 312.227 + vertex 894.681 277.038 312.221 + endloop + endfacet + facet normal 0.808088 -0.460911 -0.366817 + outer loop + vertex 893.68 277.124 309.906 + vertex 894.681 277.038 312.221 + vertex 891.561 273.411 309.906 + endloop + endfacet + facet normal 0.807282 -0.452618 -0.378725 + outer loop + vertex 891.561 273.411 309.906 + vertex 894.681 277.038 312.221 + vertex 892.606 273.349 312.205 + endloop + endfacet + facet normal 0.789528 -0.488406 -0.371624 + outer loop + vertex 891.561 273.411 309.906 + vertex 892.606 273.349 312.205 + vertex 889.334 269.816 309.898 + endloop + endfacet + facet normal 0.788625 -0.476383 -0.388754 + outer loop + vertex 889.334 269.816 309.898 + vertex 892.606 273.349 312.205 + vertex 890.413 269.721 312.204 + endloop + endfacet + facet normal 0.770797 -0.510001 -0.381801 + outer loop + vertex 889.334 269.816 309.898 + vertex 890.413 269.721 312.204 + vertex 886.984 266.259 309.906 + endloop + endfacet + facet normal 0.769977 -0.497039 -0.400111 + outer loop + vertex 886.984 266.259 309.906 + vertex 890.413 269.721 312.204 + vertex 888.096 266.125 312.212 + endloop + endfacet + facet normal 0.752547 -0.528042 -0.393504 + outer loop + vertex 886.984 266.259 309.906 + vertex 888.096 266.125 312.212 + vertex 884.518 262.729 309.926 + endloop + endfacet + facet normal 0.751967 -0.517153 -0.408778 + outer loop + vertex 884.518 262.729 309.926 + vertex 888.096 266.125 312.212 + vertex 885.664 262.584 312.217 + endloop + endfacet + facet normal 0.734148 -0.547362 -0.401773 + outer loop + vertex 884.518 262.729 309.926 + vertex 885.664 262.584 312.217 + vertex 881.959 259.278 309.951 + endloop + endfacet + facet normal 0.733572 -0.533727 -0.420723 + outer loop + vertex 881.959 259.278 309.951 + vertex 885.664 262.584 312.217 + vertex 883.148 259.126 312.218 + endloop + endfacet + facet normal 0.715735 -0.562929 -0.413322 + outer loop + vertex 881.959 259.278 309.951 + vertex 883.148 259.126 312.218 + vertex 879.338 255.919 309.988 + endloop + endfacet + facet normal 0.715315 -0.550821 -0.430025 + outer loop + vertex 879.338 255.919 309.988 + vertex 883.148 259.126 312.218 + vertex 880.575 255.783 312.219 + endloop + endfacet + facet normal 0.700294 -0.574912 -0.42316 + outer loop + vertex 879.338 255.919 309.988 + vertex 880.575 255.783 312.219 + vertex 876.681 252.638 310.048 + endloop + endfacet + facet normal 0.699781 -0.561777 -0.441263 + outer loop + vertex 876.681 252.638 310.048 + vertex 880.575 255.783 312.219 + vertex 877.967 252.528 312.227 + endloop + endfacet + facet normal 0.684118 -0.586731 -0.433278 + outer loop + vertex 876.681 252.638 310.048 + vertex 877.967 252.528 312.227 + vertex 873.961 249.409 310.126 + endloop + endfacet + facet normal 0.6836 -0.575932 -0.448323 + outer loop + vertex 873.961 249.409 310.126 + vertex 877.967 252.528 312.227 + vertex 875.301 249.347 312.25 + endloop + endfacet + facet normal 0.670466 -0.596911 -0.44065 + outer loop + vertex 873.961 249.409 310.126 + vertex 875.301 249.347 312.25 + vertex 871.156 246.185 310.225 + endloop + endfacet + facet normal 0.669726 -0.586088 -0.456036 + outer loop + vertex 871.156 246.185 310.225 + vertex 875.301 249.347 312.25 + vertex 872.557 246.184 312.285 + endloop + endfacet + facet normal 0.655716 -0.608819 -0.446516 + outer loop + vertex 871.156 246.185 310.225 + vertex 872.557 246.184 312.285 + vertex 868.25 242.985 310.32 + endloop + endfacet + facet normal 0.654718 -0.596885 -0.463759 + outer loop + vertex 868.25 242.985 310.32 + vertex 872.557 246.184 312.285 + vertex 869.684 243.006 312.318 + endloop + endfacet + facet normal 0.641205 -0.618781 -0.453835 + outer loop + vertex 868.25 242.985 310.32 + vertex 869.684 243.006 312.318 + vertex 865.263 239.859 310.363 + endloop + endfacet + facet normal 0.640583 -0.61045 -0.465837 + outer loop + vertex 865.263 239.859 310.363 + vertex 869.684 243.006 312.318 + vertex 866.681 239.851 312.323 + endloop + endfacet + facet normal 0.630149 -0.62675 -0.458363 + outer loop + vertex 865.263 239.859 310.363 + vertex 866.681 239.851 312.323 + vertex 862.336 236.935 310.338 + endloop + endfacet + facet normal 0.629633 -0.613841 -0.476196 + outer loop + vertex 862.336 236.935 310.338 + vertex 866.681 239.851 312.323 + vertex 863.732 236.855 312.287 + endloop + endfacet + facet normal 0.621079 -0.62674 -0.470593 + outer loop + vertex 862.336 236.935 310.338 + vertex 863.732 236.855 312.287 + vertex 859.826 234.477 310.298 + endloop + endfacet + facet normal 0.621504 -0.612291 -0.488705 + outer loop + vertex 859.826 234.477 310.298 + vertex 863.732 236.855 312.287 + vertex 861.206 234.303 312.271 + endloop + endfacet + facet normal 0.621095 -0.612892 -0.488472 + outer loop + vertex 859.826 234.477 310.298 + vertex 861.206 234.303 312.271 + vertex 858.136 232.69 310.391 + endloop + endfacet + facet normal 0.619716 -0.622453 -0.478021 + outer loop + vertex 858.136 232.69 310.391 + vertex 861.206 234.303 312.271 + vertex 859.529 232.495 312.451 + endloop + endfacet + facet normal 0.630756 -0.606554 -0.483984 + outer loop + vertex 858.136 232.69 310.391 + vertex 859.529 232.495 312.451 + vertex 857.523 231.665 310.877 + endloop + endfacet + facet normal 0.605116 -0.681316 -0.411878 + outer loop + vertex 857.523 231.665 310.877 + vertex 859.529 232.495 312.451 + vertex 858.948 231.581 313.111 + endloop + endfacet + facet normal 0.953126 0.127334 -0.274475 + outer loop + vertex 903.466 361.371 300.923 + vertex 903.904 368.452 305.728 + vertex 905.024 360.025 305.71 + endloop + endfacet + facet normal 0.954165 0.092946 -0.284483 + outer loop + vertex 903.466 361.371 300.923 + vertex 905.024 360.025 305.71 + vertex 904.282 352.985 300.92 + endloop + endfacet + facet normal 0.955974 0.09312 -0.278283 + outer loop + vertex 903.032 354.418 297.106 + vertex 903.466 361.371 300.923 + vertex 904.282 352.985 300.92 + endloop + endfacet + facet normal 0.95274 0.0957047 -0.288317 + outer loop + vertex 904.282 352.985 300.92 + vertex 905.024 360.025 305.71 + vertex 905.87 351.549 305.692 + endloop + endfacet + facet normal 0.952229 0.0550625 -0.300379 + outer loop + vertex 904.282 352.985 300.92 + vertex 905.87 351.549 305.692 + vertex 904.77 344.494 300.912 + endloop + endfacet + facet normal 0.951077 0.0574068 -0.303574 + outer loop + vertex 904.77 344.494 300.912 + vertex 905.87 351.549 305.692 + vertex 906.387 342.97 305.689 + endloop + endfacet + facet normal 0.954776 0.0552008 -0.292157 + outer loop + vertex 903.515 345.966 297.089 + vertex 904.282 352.985 300.92 + vertex 904.77 344.494 300.912 + endloop + endfacet + facet normal 0.954782 0.0551905 -0.29214 + outer loop + vertex 903.032 354.418 297.106 + vertex 904.282 352.985 300.92 + vertex 903.515 345.966 297.089 + endloop + endfacet + facet normal 0.955424 0.0940235 -0.279866 + outer loop + vertex 902.228 362.636 297.123 + vertex 903.466 361.371 300.923 + vertex 903.032 354.418 297.106 + endloop + endfacet + facet normal 0.954196 0.126919 -0.270927 + outer loop + vertex 901.141 370.815 297.125 + vertex 902.371 369.705 300.935 + vertex 902.228 362.636 297.123 + endloop + endfacet + facet normal 0.951421 0.155443 -0.265772 + outer loop + vertex 899.772 379.152 297.1 + vertex 901.001 378.134 300.904 + vertex 901.141 370.815 297.125 + endloop + endfacet + facet normal 0.948824 0.179792 -0.259631 + outer loop + vertex 898.175 387.526 297.065 + vertex 899.36 386.643 300.783 + vertex 899.772 379.152 297.1 + endloop + endfacet + facet normal 0.945356 0.202136 -0.255818 + outer loop + vertex 896.439 395.656 297.072 + vertex 897.538 395.039 300.646 + vertex 898.175 387.526 297.065 + endloop + endfacet + facet normal 0.942433 0.222993 -0.249188 + outer loop + vertex 895.455 396.828 294.397 + vertex 894.585 403.522 297.099 + vertex 896.439 395.656 297.072 + endloop + endfacet + facet normal 0.941173 0.220101 -0.256415 + outer loop + vertex 894.111 395.179 288.042 + vertex 892.353 402.677 288.023 + vertex 894.716 396.405 291.313 + endloop + endfacet + facet normal 0.948886 0.201503 -0.242922 + outer loop + vertex 895.736 387.555 288.064 + vertex 892.965 395.172 283.558 + vertex 894.111 395.179 288.042 + endloop + endfacet + facet normal 0.952475 0.180241 -0.245571 + outer loop + vertex 897.162 380.014 288.06 + vertex 894.522 387.846 283.57 + vertex 895.736 387.555 288.064 + endloop + endfacet + facet normal 0.955735 0.156438 -0.249194 + outer loop + vertex 898.397 372.469 288.059 + vertex 895.915 380.483 283.571 + vertex 897.162 380.014 288.06 + endloop + endfacet + facet normal 0.958636 0.128781 -0.253835 + outer loop + vertex 899.415 364.88 288.055 + vertex 897.131 373.059 283.577 + vertex 898.397 372.469 288.059 + endloop + endfacet + facet normal 0.960811 0.0969019 -0.259716 + outer loop + vertex 900.191 357.208 288.064 + vertex 898.139 365.533 283.578 + vertex 899.415 364.88 288.055 + endloop + endfacet + facet normal 0.962238 0.0622709 -0.26499 + outer loop + vertex 900.697 349.476 288.081 + vertex 898.914 357.887 283.586 + vertex 900.191 357.208 288.064 + endloop + endfacet + facet normal 0.962499 0.0237525 -0.270243 + outer loop + vertex 900.888 341.824 288.09 + vertex 899.421 350.174 283.6 + vertex 900.697 349.476 288.081 + endloop + endfacet + facet normal 0.9623 0.0233164 -0.27099 + outer loop + vertex 899.608 342.497 283.603 + vertex 899.421 350.174 283.6 + vertex 900.888 341.824 288.09 + endloop + endfacet + facet normal 0.966441 0.0248777 -0.255683 + outer loop + vertex 898.07 343.546 277.89 + vertex 897.874 351.151 277.892 + vertex 899.608 342.497 283.603 + endloop + endfacet + facet normal 0.969035 0.026702 -0.245476 + outer loop + vertex 896.378 344.643 271.331 + vertex 896.172 352.141 271.335 + vertex 898.07 343.546 277.89 + endloop + endfacet + facet normal 0.971417 0.0280392 -0.235716 + outer loop + vertex 894.642 345.657 264.299 + vertex 894.43 353.051 264.304 + vertex 896.378 344.643 271.331 + endloop + endfacet + facet normal 0.974477 0.0306577 -0.222383 + outer loop + vertex 892.955 346.581 257.033 + vertex 892.725 353.877 257.031 + vertex 894.642 345.657 264.299 + endloop + endfacet + facet normal 0.977726 0.0323039 -0.207385 + outer loop + vertex 891.354 347.445 249.619 + vertex 891.116 354.657 249.62 + vertex 892.955 346.581 257.033 + endloop + endfacet + facet normal 0.981118 0.0349435 -0.190229 + outer loop + vertex 889.865 348.271 242.09 + vertex 889.611 355.402 242.09 + vertex 891.354 347.445 249.619 + endloop + endfacet + facet normal 0.984298 0.037832 -0.172415 + outer loop + vertex 888.5 349.047 234.467 + vertex 888.228 356.103 234.466 + vertex 889.865 348.271 242.09 + endloop + endfacet + facet normal 0.987195 0.0402134 -0.154368 + outer loop + vertex 887.267 349.752 226.768 + vertex 886.982 356.741 226.767 + vertex 888.5 349.047 234.467 + endloop + endfacet + facet normal 0.989937 0.0427278 -0.134905 + outer loop + vertex 886.181 350.37 218.999 + vertex 885.882 357.298 218.998 + vertex 887.267 349.752 226.768 + endloop + endfacet + facet normal 0.992438 0.045064 -0.114172 + outer loop + vertex 885.255 350.895 211.155 + vertex 884.943 357.772 211.154 + vertex 886.181 350.37 218.999 + endloop + endfacet + facet normal 0.994511 0.0465859 -0.0936852 + outer loop + vertex 884.489 351.323 203.233 + vertex 884.169 358.159 203.233 + vertex 885.255 350.895 211.155 + endloop + endfacet + facet normal 0.996181 0.0481413 -0.0728388 + outer loop + vertex 883.89 351.654 195.255 + vertex 883.561 358.457 195.255 + vertex 884.489 351.323 203.233 + endloop + endfacet + facet normal 0.997395 0.0488912 -0.0530411 + outer loop + vertex 883.453 351.887 187.269 + vertex 883.121 358.669 187.267 + vertex 883.89 351.654 195.255 + endloop + endfacet + facet normal 0.998191 0.0499137 -0.0335136 + outer loop + vertex 883.18 352.025 179.323 + vertex 882.841 358.793 179.323 + vertex 883.453 351.887 187.269 + endloop + endfacet + facet normal 0.998613 0.0504893 -0.0149249 + outer loop + vertex 883.06 352.068 171.448 + vertex 882.718 358.832 171.448 + vertex 883.18 352.025 179.323 + endloop + endfacet + facet normal 0.999966 0.00719425 0.00392381 + outer loop + vertex 883.108 345.349 171.449 + vertex 883.091 352.017 163.624 + vertex 883.06 352.068 171.448 + endloop + endfacet + facet normal 0.999965 0.00735155 0.00405787 + outer loop + vertex 883.14 345.292 163.624 + vertex 883.091 352.017 163.624 + vertex 883.108 345.349 171.449 + endloop + endfacet + facet normal 0.999714 0.00755308 0.0226787 + outer loop + vertex 883.319 345.133 155.805 + vertex 883.268 351.872 155.804 + vertex 883.14 345.292 163.624 + endloop + endfacet + facet normal 0.999159 0.00708075 0.0403833 + outer loop + vertex 883.638 344.869 147.952 + vertex 883.59 351.632 147.951 + vertex 883.319 345.133 155.805 + endloop + endfacet + facet normal 0.998305 0.00632215 0.0578603 + outer loop + vertex 884.098 344.501 140.065 + vertex 884.055 351.297 140.065 + vertex 883.638 344.869 147.952 + endloop + endfacet + facet normal 0.997121 0.00559098 0.0756262 + outer loop + vertex 884.699 344.029 132.177 + vertex 884.66 350.867 132.177 + vertex 884.098 344.501 140.065 + endloop + endfacet + facet normal 0.995701 0.00453717 0.0925102 + outer loop + vertex 885.431 343.454 124.32 + vertex 885.4 350.344 124.32 + vertex 884.699 344.029 132.177 + endloop + endfacet + facet normal 0.993956 0.00355517 0.109718 + outer loop + vertex 886.295 342.782 116.513 + vertex 886.271 349.73 116.513 + vertex 885.431 343.454 124.32 + endloop + endfacet + facet normal 0.990423 -0.0506962 0.128424 + outer loop + vertex 886.915 335.052 108.774 + vertex 887.271 342.017 108.775 + vertex 885.954 335.882 116.513 + endloop + endfacet + facet normal 0.988184 -0.0505823 0.144687 + outer loop + vertex 886.915 335.052 108.774 + vertex 888.346 341.163 101.138 + vertex 887.271 342.017 108.775 + endloop + endfacet + facet normal 0.988317 -0.0527081 0.143011 + outer loop + vertex 887.97 334.125 101.137 + vertex 888.346 341.163 101.138 + vertex 886.915 335.052 108.774 + endloop + endfacet + facet normal 0.985949 -0.0525841 0.158554 + outer loop + vertex 887.97 334.125 101.137 + vertex 889.5 340.217 93.6449 + vertex 888.346 341.163 101.138 + endloop + endfacet + facet normal 0.986115 -0.0548541 0.156742 + outer loop + vertex 889.104 333.098 93.6439 + vertex 889.5 340.217 93.6449 + vertex 887.97 334.125 101.137 + endloop + endfacet + facet normal 0.983622 -0.0547176 0.171739 + outer loop + vertex 889.104 333.098 93.6439 + vertex 890.723 339.186 86.3117 + vertex 889.5 340.217 93.6449 + endloop + endfacet + facet normal 0.983783 -0.0566282 0.170188 + outer loop + vertex 890.309 331.994 86.3113 + vertex 890.723 339.186 86.3117 + vertex 889.104 333.098 93.6439 + endloop + endfacet + facet normal 0.981109 -0.0564752 0.185028 + outer loop + vertex 890.309 331.994 86.3113 + vertex 892.02 338.126 79.1135 + vertex 890.723 339.186 86.3117 + endloop + endfacet + facet normal 0.981369 -0.059167 0.182797 + outer loop + vertex 891.582 330.88 79.1157 + vertex 892.02 338.126 79.1135 + vertex 890.309 331.994 86.3113 + endloop + endfacet + facet normal 0.979078 -0.059025 0.194734 + outer loop + vertex 891.582 330.88 79.1157 + vertex 893.362 337.141 72.0647 + vertex 892.02 338.126 79.1135 + endloop + endfacet + facet normal 0.979063 -0.0588897 0.194851 + outer loop + vertex 892.923 329.814 72.0585 + vertex 893.362 337.141 72.0647 + vertex 891.582 330.88 79.1157 + endloop + endfacet + facet normal 0.97743 -0.0587986 0.202914 + outer loop + vertex 892.923 329.814 72.0585 + vertex 894.704 336.232 65.3358 + vertex 893.362 337.141 72.0647 + endloop + endfacet + facet normal 0.977393 -0.0585217 0.203169 + outer loop + vertex 894.257 328.731 65.3274 + vertex 894.704 336.232 65.3358 + vertex 892.923 329.814 72.0585 + endloop + endfacet + facet normal 0.975986 -0.0584451 0.209848 + outer loop + vertex 894.257 328.731 65.3274 + vertex 895.933 335.155 59.3242 + vertex 894.704 336.232 65.3358 + endloop + endfacet + facet normal 0.976123 -0.0593043 0.208967 + outer loop + vertex 895.439 327.329 59.4065 + vertex 895.933 335.155 59.3242 + vertex 894.257 328.731 65.3274 + endloop + endfacet + facet normal 0.973534 -0.0590169 0.220792 + outer loop + vertex 895.439 327.329 59.4065 + vertex 896.956 333.289 54.312 + vertex 895.933 335.155 59.3242 + endloop + endfacet + facet normal 0.975412 -0.0694303 0.209168 + outer loop + vertex 896.154 325.207 55.3718 + vertex 896.956 333.289 54.312 + vertex 895.439 327.329 59.4065 + endloop + endfacet + facet normal 0.968345 -0.0645381 0.241126 + outer loop + vertex 896.956 333.289 54.312 + vertex 896.154 325.207 55.3718 + vertex 897.106 326.917 52.0033 + endloop + endfacet + facet normal 0.971839 -0.059686 0.227962 + outer loop + vertex 897.106 326.917 52.0033 + vertex 897.745 334.6 51.2932 + vertex 896.956 333.289 54.312 + endloop + endfacet + facet normal 0.94838 -0.0498585 0.313193 + outer loop + vertex 897.106 326.917 52.0033 + vertex 897.973 332.126 50.2097 + vertex 897.745 334.6 51.2932 + endloop + endfacet + facet normal 0.961762 -0.0686286 0.26515 + outer loop + vertex 897.453 324.759 50.1889 + vertex 897.973 332.126 50.2097 + vertex 897.106 326.917 52.0033 + endloop + endfacet + facet normal 0.992038 0.0035486 0.125888 + outer loop + vertex 886.295 342.782 116.513 + vertex 887.255 349.032 108.775 + vertex 886.271 349.73 116.513 + endloop + endfacet + facet normal 0.989624 0.0464472 0.135965 + outer loop + vertex 888.341 348.254 101.138 + vertex 888.005 355.399 101.14 + vertex 887.255 349.032 108.775 + endloop + endfacet + facet normal 0.987899 0.0452051 0.148368 + outer loop + vertex 889.505 347.393 93.6462 + vertex 889.174 354.627 93.6473 + vertex 888.341 348.254 101.138 + endloop + endfacet + facet normal 0.986084 0.0442473 0.16025 + outer loop + vertex 890.74 346.449 86.3103 + vertex 890.411 353.784 86.3103 + vertex 889.505 347.393 93.6462 + endloop + endfacet + facet normal 0.9841 0.0440621 0.172064 + outer loop + vertex 892.044 345.464 79.1065 + vertex 891.712 352.897 79.1014 + vertex 890.74 346.449 86.3103 + endloop + endfacet + facet normal 0.982431 0.0438619 0.181396 + outer loop + vertex 893.386 344.549 72.058 + vertex 893.054 352.058 72.0394 + vertex 892.044 345.464 79.1065 + endloop + endfacet + facet normal 0.980736 0.0452553 0.190025 + outer loop + vertex 894.724 343.766 65.3405 + vertex 894.375 351.358 65.3302 + vertex 893.386 344.549 72.058 + endloop + endfacet + facet normal 0.979685 0.0451772 0.195389 + outer loop + vertex 895.947 342.999 59.3854 + vertex 895.588 350.73 59.3939 + vertex 894.724 343.766 65.3405 + endloop + endfacet + facet normal 0.978344 0.0451078 0.202012 + outer loop + vertex 895.947 342.999 59.3854 + vertex 896.572 349.892 54.8166 + vertex 895.588 350.73 59.3939 + endloop + endfacet + facet normal 0.963751 0.0395375 0.263859 + outer loop + vertex 897.661 340.913 51.671 + vertex 897.801 346.851 50.2699 + vertex 897.297 348.637 51.8444 + endloop + endfacet + facet normal 0.970982 0.073591 0.227548 + outer loop + vertex 897.801 346.851 50.2699 + vertex 897.2 354.712 50.2909 + vertex 897.297 348.637 51.8444 + endloop + endfacet + facet normal 0.979141 0.0427916 0.198626 + outer loop + vertex 896.94 341.96 54.7116 + vertex 896.572 349.892 54.8166 + vertex 895.947 342.999 59.3854 + endloop + endfacet + facet normal 0.96572 0.0785854 0.247405 + outer loop + vertex 897.297 348.637 51.8444 + vertex 897.2 354.712 50.2909 + vertex 896.661 356.424 51.8528 + endloop + endfacet + facet normal 0.970138 0.107162 0.217598 + outer loop + vertex 897.2 354.712 50.2909 + vertex 896.383 362.141 50.2748 + vertex 896.661 356.424 51.8528 + endloop + endfacet + facet normal 0.977306 0.0831549 0.194827 + outer loop + vertex 896.572 349.892 54.8166 + vertex 895.914 357.687 54.7913 + vertex 895.588 350.73 59.3939 + endloop + endfacet + facet normal 0.963577 0.113607 0.242102 + outer loop + vertex 896.661 356.424 51.8528 + vertex 896.383 362.141 50.2748 + vertex 895.747 364.125 51.8748 + endloop + endfacet + facet normal 0.96732 0.139064 0.212022 + outer loop + vertex 896.383 362.141 50.2748 + vertex 895.288 369.74 50.2859 + vertex 895.747 364.125 51.8748 + endloop + endfacet + facet normal 0.974411 0.117927 0.191355 + outer loop + vertex 895.914 357.687 54.7913 + vertex 894.972 365.4 54.8346 + vertex 894.921 358.428 59.3912 + endloop + endfacet + facet normal 0.961754 0.144466 0.232721 + outer loop + vertex 895.747 364.125 51.8748 + vertex 895.288 369.74 50.2859 + vertex 894.54 372 51.974 + endloop + endfacet + facet normal 0.964742 0.16789 0.202694 + outer loop + vertex 895.288 369.74 50.2859 + vertex 893.865 377.818 50.3685 + vertex 894.54 372 51.974 + endloop + endfacet + facet normal 0.971498 0.147393 0.185654 + outer loop + vertex 894.972 365.4 54.8346 + vertex 893.789 372.957 55.0272 + vertex 893.998 366.022 59.4384 + endloop + endfacet + facet normal 0.959363 0.172874 0.223018 + outer loop + vertex 894.54 372 51.974 + vertex 893.865 377.818 50.3685 + vertex 892.892 380.796 52.2459 + endloop + endfacet + facet normal 0.962209 0.193802 0.191297 + outer loop + vertex 893.865 377.818 50.3685 + vertex 892.12 386.565 50.2828 + vertex 892.892 380.796 52.2459 + endloop + endfacet + facet normal 0.968692 0.170549 0.180411 + outer loop + vertex 893.789 372.957 55.0272 + vertex 892.607 379.118 55.5475 + vertex 892.886 373.301 59.5503 + endloop + endfacet + facet normal 0.964627 0.196178 0.176095 + outer loop + vertex 892.607 379.118 55.5475 + vertex 891.209 387.062 54.3543 + vertex 891.593 380.609 59.4434 + endloop + endfacet + facet normal 0.955984 0.200706 0.214036 + outer loop + vertex 892.892 380.796 52.2459 + vertex 892.12 386.565 50.2828 + vertex 891.384 388.914 51.3676 + endloop + endfacet + facet normal 0.958993 0.215442 0.184166 + outer loop + vertex 892.12 386.565 50.2828 + vertex 890.412 394.182 50.2672 + vertex 891.384 388.914 51.3676 + endloop + endfacet + facet normal 0.954621 0.21845 0.20243 + outer loop + vertex 891.384 388.914 51.3676 + vertex 890.412 394.182 50.2672 + vertex 889.893 395.108 51.7164 + endloop + endfacet + facet normal 0.953181 0.23325 0.192458 + outer loop + vertex 890.412 394.182 50.2672 + vertex 888.632 401.437 50.2899 + vertex 889.893 395.108 51.7164 + endloop + endfacet + facet normal 0.960564 0.217461 0.173282 + outer loop + vertex 891.209 387.062 54.3543 + vertex 889.253 395.399 54.7396 + vertex 890.048 388.238 59.3141 + endloop + endfacet + facet normal 0.951474 0.234456 0.199317 + outer loop + vertex 889.893 395.108 51.7164 + vertex 888.632 401.437 50.2899 + vertex 888.015 402.544 51.9352 + endloop + endfacet + facet normal 0.949881 0.249119 0.188856 + outer loop + vertex 888.632 401.437 50.2899 + vertex 886.659 408.904 50.3644 + vertex 888.015 402.544 51.9352 + endloop + endfacet + facet normal 0.956682 0.235245 0.171518 + outer loop + vertex 889.253 395.399 54.7396 + vertex 887.392 402.777 54.995 + vertex 888.337 395.725 59.3981 + endloop + endfacet + facet normal 0.948085 0.250485 0.195937 + outer loop + vertex 888.015 402.544 51.9352 + vertex 886.659 408.904 50.3644 + vertex 885.787 410.72 52.2615 + endloop + endfacet + facet normal 0.947188 0.262866 0.183677 + outer loop + vertex 886.659 408.904 50.3644 + vertex 884.638 416.208 50.3329 + vertex 885.787 410.72 52.2615 + endloop + endfacet + facet normal 0.953187 0.249595 0.170696 + outer loop + vertex 887.392 402.777 54.995 + vertex 885.75 408.643 55.5908 + vertex 886.584 402.751 59.5495 + endloop + endfacet + facet normal 0.949649 0.263851 0.168963 + outer loop + vertex 885.75 408.643 55.5908 + vertex 883.774 416.414 54.5618 + vertex 884.732 409.805 59.4961 + endloop + endfacet + facet normal 0.943308 0.266864 0.197366 + outer loop + vertex 885.787 410.72 52.2615 + vertex 884.638 416.208 50.3329 + vertex 883.709 418.66 51.4576 + endloop + endfacet + facet normal 0.944316 0.274691 0.18114 + outer loop + vertex 884.638 416.208 50.3329 + vertex 882.442 423.815 50.2487 + vertex 883.709 418.66 51.4576 + endloop + endfacet + facet normal 0.935323 0.272585 0.225541 + outer loop + vertex 882.442 423.815 50.2487 + vertex 884.638 416.208 50.3329 + vertex 883.661 420.013 49.7865 + endloop + endfacet + facet normal 0.942535 0.275947 0.188365 + outer loop + vertex 883.709 418.66 51.4576 + vertex 882.442 423.815 50.2487 + vertex 881.554 425.604 52.0679 + endloop + endfacet + facet normal 0.941854 0.283126 0.18097 + outer loop + vertex 882.442 423.815 50.2487 + vertex 880.244 431.055 50.3617 + vertex 881.554 425.604 52.0679 + endloop + endfacet + facet normal 0.940248 0.282496 0.19008 + outer loop + vertex 880.244 431.055 50.3617 + vertex 882.442 423.815 50.2487 + vertex 880.737 429.89 49.6543 + endloop + endfacet + facet normal 0.946713 0.274374 0.168684 + outer loop + vertex 883.774 416.414 54.5618 + vertex 881.651 423.196 55.444 + vertex 882.712 417.054 59.4795 + endloop + endfacet + facet normal 0.944203 0.282635 0.169109 + outer loop + vertex 881.651 423.196 55.444 + vertex 879.395 431.4 54.3281 + vertex 880.558 424.447 59.4553 + endloop + endfacet + facet normal 0.940809 0.28409 0.184854 + outer loop + vertex 881.554 425.604 52.0679 + vertex 880.244 431.055 50.3617 + vertex 879.342 433.409 51.3325 + endloop + endfacet + facet normal 0.941289 0.287577 0.176844 + outer loop + vertex 880.244 431.055 50.3617 + vertex 878.06 438.283 50.2318 + vertex 879.342 433.409 51.3325 + endloop + endfacet + facet normal 0.938466 0.286998 0.192129 + outer loop + vertex 878.06 438.283 50.2318 + vertex 880.244 431.055 50.3617 + vertex 879.19 434.923 49.7284 + endloop + endfacet + facet normal 0.939961 0.288474 0.182364 + outer loop + vertex 879.342 433.409 51.3325 + vertex 878.06 438.283 50.2318 + vertex 877.393 439.525 51.7034 + endloop + endfacet + facet normal 0.939524 0.291721 0.179427 + outer loop + vertex 878.06 438.283 50.2318 + vertex 875.726 445.756 50.2994 + vertex 877.393 439.525 51.7034 + endloop + endfacet + facet normal 0.936764 0.29072 0.194821 + outer loop + vertex 875.726 445.756 50.2994 + vertex 878.06 438.283 50.2318 + vertex 876.688 443.056 49.7079 + endloop + endfacet + facet normal 0.941782 0.289472 0.171036 + outer loop + vertex 879.395 431.4 54.3281 + vertex 876.778 439.679 54.7238 + vertex 878.279 432.074 59.3352 + endloop + endfacet + facet normal 0.937951 0.29275 0.185861 + outer loop + vertex 877.393 439.525 51.7034 + vertex 875.726 445.756 50.2994 + vertex 875.062 446.884 51.8749 + endloop + endfacet + facet normal 0.939596 0.29501 0.173575 + outer loop + vertex 876.778 439.679 54.7238 + vertex 874.429 447.095 54.8401 + vertex 875.97 439.493 59.4163 + endloop + endfacet + facet normal 0.935498 0.301405 0.184385 + outer loop + vertex 872.117 454.263 54.8484 + vertex 874.429 447.095 54.8401 + vertex 872.696 454.233 51.9605 + endloop + endfacet + facet normal 0.93727 0.296993 0.182536 + outer loop + vertex 875.726 445.756 50.2994 + vertex 873.335 453.258 50.3725 + vertex 875.062 446.884 51.8749 + endloop + endfacet + facet normal 0.932503 0.295225 0.208039 + outer loop + vertex 873.335 453.258 50.3725 + vertex 875.726 445.756 50.2994 + vertex 874.276 450.729 49.7411 + endloop + endfacet + facet normal 0.933233 0.304265 0.191045 + outer loop + vertex 872.696 454.233 51.9605 + vertex 870.862 460.803 50.4578 + vertex 870.304 461.565 51.9703 + endloop + endfacet + facet normal 0.933498 0.299784 0.19675 + outer loop + vertex 874.004 452.223 48.6899 + vertex 872.461 458.515 46.4243 + vertex 871.639 459.531 48.7734 + endloop + endfacet + facet normal 0.933771 0.298262 0.197766 + outer loop + vertex 874.276 450.729 49.7411 + vertex 873.003 454.815 49.593 + vertex 873.335 453.258 50.3725 + endloop + endfacet + facet normal 0.936272 0.29447 0.191527 + outer loop + vertex 875.411 447.255 49.5354 + vertex 874.276 450.729 49.7411 + vertex 875.726 445.756 50.2994 + endloop + endfacet + facet normal 0.93745 0.294231 0.186054 + outer loop + vertex 876.436 444.494 48.657 + vertex 874.824 451.095 46.3426 + vertex 874.004 452.223 48.6899 + endloop + endfacet + facet normal 0.93767 0.292666 0.18741 + outer loop + vertex 876.688 443.056 49.7079 + vertex 875.411 447.255 49.5354 + vertex 875.726 445.756 50.2994 + endloop + endfacet + facet normal 0.938865 0.290262 0.185152 + outer loop + vertex 877.871 439.346 49.5216 + vertex 876.688 443.056 49.7079 + vertex 878.06 438.283 50.2318 + endloop + endfacet + facet normal 0.939972 0.290012 0.17985 + outer loop + vertex 878.971 436.279 48.6601 + vertex 877.246 443.311 46.3336 + vertex 876.436 444.494 48.657 + endloop + endfacet + facet normal 0.939768 0.288838 0.182779 + outer loop + vertex 879.19 434.923 49.7284 + vertex 877.871 439.346 49.5216 + vertex 878.06 438.283 50.2318 + endloop + endfacet + facet normal 0.94033 0.286185 0.184061 + outer loop + vertex 880.737 429.89 49.6543 + vertex 879.19 434.923 49.7284 + vertex 880.244 431.055 50.3617 + endloop + endfacet + facet normal 0.941896 0.286239 0.175783 + outer loop + vertex 881.458 428.071 48.6979 + vertex 879.694 435.316 46.3526 + vertex 878.971 436.279 48.6601 + endloop + endfacet + facet normal 0.934181 0.283404 0.216765 + outer loop + vertex 881.886 426.082 49.678 + vertex 880.737 429.89 49.6543 + vertex 882.442 423.815 50.2487 + endloop + endfacet + facet normal 0.940554 0.279117 0.193527 + outer loop + vertex 882.705 423.39 49.5844 + vertex 881.886 426.082 49.678 + vertex 882.442 423.815 50.2487 + endloop + endfacet + facet normal 0.944693 0.279767 0.171131 + outer loop + vertex 883.823 420.013 48.8155 + vertex 882.105 427.311 46.3692 + vertex 881.458 428.071 48.6979 + endloop + endfacet + facet normal 0.940705 0.27812 0.194225 + outer loop + vertex 883.661 420.013 49.7865 + vertex 882.705 423.39 49.5844 + vertex 882.442 423.815 50.2487 + endloop + endfacet + facet normal 0.938229 0.271709 0.214243 + outer loop + vertex 884.428 417.427 49.7075 + vertex 883.661 420.013 49.7865 + vertex 884.638 416.208 50.3329 + endloop + endfacet + facet normal 0.943264 0.265182 0.199829 + outer loop + vertex 885.382 414.083 49.6422 + vertex 884.428 417.427 49.7075 + vertex 884.638 416.208 50.3329 + endloop + endfacet + facet normal 0.948461 0.269321 0.167 + outer loop + vertex 886.076 412.177 48.6578 + vertex 884.441 419.365 46.3487 + vertex 883.823 420.013 48.8155 + endloop + endfacet + facet normal 0.938842 0.262591 0.222762 + outer loop + vertex 886.414 410.399 49.6365 + vertex 885.382 414.083 49.6422 + vertex 886.659 408.904 50.3644 + endloop + endfacet + facet normal 0.942128 0.261579 0.209692 + outer loop + vertex 884.638 416.208 50.3329 + vertex 886.659 408.904 50.3644 + vertex 885.382 414.083 49.6422 + endloop + endfacet + facet normal 0.946241 0.253291 0.201176 + outer loop + vertex 887.416 406.675 49.6111 + vertex 886.414 410.399 49.6365 + vertex 886.659 408.904 50.3644 + endloop + endfacet + facet normal 0.950141 0.267519 0.160203 + outer loop + vertex 886.695 411.379 46.3202 + vertex 884.441 419.365 46.3487 + vertex 886.076 412.177 48.6578 + endloop + endfacet + facet normal 0.951065 0.252621 0.177924 + outer loop + vertex 888.884 403.114 46.3488 + vertex 887.415 410.961 43.0591 + vertex 886.695 411.379 46.3202 + endloop + endfacet + facet normal 0.954789 0.236379 0.180286 + outer loop + vertex 890.969 394.681 46.3677 + vertex 889.637 402.573 43.07 + vertex 888.884 403.114 46.3488 + endloop + endfacet + facet normal 0.958744 0.217419 0.183138 + outer loop + vertex 892.868 386.322 46.3473 + vertex 891.731 394.088 43.0822 + vertex 890.969 394.681 46.3677 + endloop + endfacet + facet normal 0.962875 0.194978 0.186698 + outer loop + vertex 894.563 377.964 46.3349 + vertex 893.654 385.562 43.0853 + vertex 892.868 386.322 46.3473 + endloop + endfacet + facet normal 0.966718 0.168335 0.192666 + outer loop + vertex 896.045 369.442 46.3456 + vertex 895.386 376.968 43.0766 + vertex 894.563 377.964 46.3349 + endloop + endfacet + facet normal 0.967336 0.167392 0.190372 + outer loop + vertex 896.896 368.289 43.0356 + vertex 895.386 376.968 43.0766 + vertex 896.045 369.442 46.3456 + endloop + endfacet + facet normal 0.972932 0.100459 0.208116 + outer loop + vertex 899.028 350.948 43.0036 + vertex 898.131 359.588 43.0264 + vertex 898.19 352.151 46.344 + endloop + endfacet + facet normal 0.969771 0.138033 0.201223 + outer loop + vertex 897.277 360.777 46.349 + vertex 896.896 368.289 43.0356 + vertex 896.045 369.442 46.3456 + endloop + endfacet + facet normal 0.964934 0.136676 0.224102 + outer loop + vertex 899.267 358.41 38.8526 + vertex 898.011 367.233 38.8807 + vertex 898.131 359.588 43.0264 + endloop + endfacet + facet normal 0.962565 0.166451 0.213922 + outer loop + vertex 896.896 368.289 43.0356 + vertex 896.446 376.12 38.9658 + vertex 895.386 376.968 43.0766 + endloop + endfacet + facet normal 0.952694 0.191599 0.235931 + outer loop + vertex 896.446 376.12 38.9658 + vertex 895.959 383.885 34.6261 + vertex 894.645 384.942 39.0728 + endloop + endfacet + facet normal 0.939646 0.210122 0.270026 + outer loop + vertex 897.625 382.076 30.2371 + vertex 895.478 391.501 30.3751 + vertex 895.959 383.885 34.6261 + endloop + endfacet + facet normal 0.955818 0.16571 0.242801 + outer loop + vertex 899.448 365.708 34.2665 + vertex 897.867 374.855 34.2455 + vertex 898.011 367.233 38.8807 + endloop + endfacet + facet normal 0.803322 -0.367463 0.468662 + outer loop + vertex 892.753 282.812 30.0828 + vertex 895.14 285.568 28.1529 + vertex 894.167 286.56 30.599 + endloop + endfacet + facet normal 0.819896 -0.336932 0.462869 + outer loop + vertex 895.14 285.568 28.1529 + vertex 896.746 289.568 28.2202 + vertex 894.167 286.56 30.599 + endloop + endfacet + facet normal 0.819916 -0.337042 0.462752 + outer loop + vertex 894.167 286.56 30.599 + vertex 896.746 289.568 28.2202 + vertex 896.06 290.673 30.2399 + endloop + endfacet + facet normal 0.836349 -0.30885 0.452914 + outer loop + vertex 896.746 289.568 28.2202 + vertex 898.218 293.645 28.2815 + vertex 896.06 290.673 30.2399 + endloop + endfacet + facet normal 0.83647 -0.309276 0.452401 + outer loop + vertex 896.06 290.673 30.2399 + vertex 898.218 293.645 28.2815 + vertex 897.228 294.55 30.7304 + endloop + endfacet + facet normal 0.850007 -0.27914 0.446732 + outer loop + vertex 898.218 293.645 28.2815 + vertex 899.536 297.755 28.3412 + vertex 897.228 294.55 30.7304 + endloop + endfacet + facet normal 0.849909 -0.278747 0.447164 + outer loop + vertex 897.228 294.55 30.7304 + vertex 899.536 297.755 28.3412 + vertex 898.813 298.78 30.3548 + endloop + endfacet + facet normal 0.863664 -0.250225 0.437575 + outer loop + vertex 899.536 297.755 28.3412 + vertex 900.69 301.839 28.4003 + vertex 898.813 298.78 30.3548 + endloop + endfacet + facet normal 0.863466 -0.249641 0.438299 + outer loop + vertex 898.813 298.78 30.3548 + vertex 900.69 301.839 28.4003 + vertex 899.688 302.643 30.8314 + endloop + endfacet + facet normal 0.875113 -0.217283 0.432395 + outer loop + vertex 900.69 301.839 28.4003 + vertex 901.669 305.888 28.4532 + vertex 899.688 302.643 30.8314 + endloop + endfacet + facet normal 0.874673 -0.215832 0.434009 + outer loop + vertex 899.688 302.643 30.8314 + vertex 901.669 305.888 28.4532 + vertex 900.919 306.867 30.4501 + endloop + endfacet + facet normal 0.887219 -0.183943 0.423092 + outer loop + vertex 901.669 305.888 28.4532 + vertex 902.484 309.949 28.5085 + vertex 900.919 306.867 30.4501 + endloop + endfacet + facet normal 0.88627 -0.181568 0.426097 + outer loop + vertex 900.919 306.867 30.4501 + vertex 902.484 309.949 28.5085 + vertex 901.489 310.759 30.924 + endloop + endfacet + facet normal 0.895946 -0.147939 0.418802 + outer loop + vertex 902.484 309.949 28.5085 + vertex 903.141 314.066 28.5582 + vertex 901.489 310.759 30.924 + endloop + endfacet + facet normal 0.89535 -0.146328 0.420638 + outer loop + vertex 901.489 310.759 30.924 + vertex 903.141 314.066 28.5582 + vertex 902.376 315.081 30.5392 + endloop + endfacet + facet normal 0.905587 -0.114647 0.408372 + outer loop + vertex 903.141 314.066 28.5582 + vertex 903.652 318.276 28.6062 + vertex 902.376 315.081 30.5392 + endloop + endfacet + facet normal 0.904571 -0.112529 0.411203 + outer loop + vertex 902.376 315.081 30.5392 + vertex 903.652 318.276 28.6062 + vertex 902.666 319.125 31.0073 + endloop + endfacet + facet normal 0.911723 -0.0805429 0.402832 + outer loop + vertex 903.652 318.276 28.6062 + vertex 904.012 322.574 28.6518 + vertex 902.666 319.125 31.0073 + endloop + endfacet + facet normal 0.91069 -0.0782408 0.405613 + outer loop + vertex 902.666 319.125 31.0073 + vertex 904.012 322.574 28.6518 + vertex 903.224 323.613 30.6207 + endloop + endfacet + facet normal 0.918153 -0.0490266 0.39318 + outer loop + vertex 904.012 322.574 28.6518 + vertex 904.225 326.934 28.6969 + vertex 903.224 323.613 30.6207 + endloop + endfacet + facet normal 0.917515 -0.0478921 0.394806 + outer loop + vertex 903.224 323.613 30.6207 + vertex 904.225 326.934 28.6969 + vertex 903.243 327.768 31.0815 + endloop + endfacet + facet normal 0.922209 -0.0179678 0.386275 + outer loop + vertex 904.225 326.934 28.6969 + vertex 904.293 331.322 28.7384 + vertex 903.243 327.768 31.0815 + endloop + endfacet + facet normal 0.921572 -0.0167442 0.387845 + outer loop + vertex 903.243 327.768 31.0815 + vertex 904.293 331.322 28.7384 + vertex 903.49 332.344 30.6921 + endloop + endfacet + facet normal 0.92645 0.00916106 0.376306 + outer loop + vertex 904.293 331.322 28.7384 + vertex 904.234 335.705 28.7772 + vertex 903.49 332.344 30.6921 + endloop + endfacet + facet normal 0.927084 0.00814359 0.374766 + outer loop + vertex 903.49 332.344 30.6921 + vertex 904.234 335.705 28.7772 + vertex 903.268 336.516 31.1511 + endloop + endfacet + facet normal 0.9297 0.0350455 0.366646 + outer loop + vertex 904.234 335.705 28.7772 + vertex 904.057 340.068 28.8108 + vertex 903.268 336.516 31.1511 + endloop + endfacet + facet normal 0.929516 0.0353727 0.367081 + outer loop + vertex 903.268 336.516 31.1511 + vertex 904.057 340.068 28.8108 + vertex 903.25 341.088 30.7548 + endloop + endfacet + facet normal 0.932436 0.0573838 0.356749 + outer loop + vertex 904.057 340.068 28.8108 + vertex 903.775 344.427 28.8465 + vertex 903.25 341.088 30.7548 + endloop + endfacet + facet normal 0.933093 0.0563876 0.355186 + outer loop + vertex 903.25 341.088 30.7548 + vertex 903.775 344.427 28.8465 + vertex 902.826 345.247 31.2087 + endloop + endfacet + facet normal 0.934238 0.0790152 0.347786 + outer loop + vertex 903.775 344.427 28.8465 + vertex 903.394 348.79 28.8768 + vertex 902.826 345.247 31.2087 + endloop + endfacet + facet normal 0.933697 0.0799215 0.349031 + outer loop + vertex 902.826 345.247 31.2087 + vertex 903.394 348.79 28.8768 + vertex 902.582 349.824 30.8147 + endloop + endfacet + facet normal 0.935251 0.0975494 0.340279 + outer loop + vertex 903.394 348.79 28.8768 + vertex 902.928 353.164 28.9052 + vertex 902.582 349.824 30.8147 + endloop + endfacet + facet normal 0.935683 0.0969268 0.339269 + outer loop + vertex 902.582 349.824 30.8147 + vertex 902.928 353.164 28.9052 + vertex 901.994 353.978 31.2497 + endloop + endfacet + facet normal 0.935863 0.115583 0.332868 + outer loop + vertex 902.928 353.164 28.9052 + vertex 902.381 357.537 28.9238 + vertex 901.994 353.978 31.2497 + endloop + endfacet + facet normal 0.934345 0.117976 0.336277 + outer loop + vertex 901.994 353.978 31.2497 + vertex 902.381 357.537 28.9238 + vertex 901.563 358.558 30.8398 + endloop + endfacet + facet normal 0.935053 0.132704 0.328732 + outer loop + vertex 902.381 357.537 28.9238 + vertex 901.755 361.925 28.9338 + vertex 901.563 358.558 30.8398 + endloop + endfacet + facet normal 0.935107 0.132631 0.328608 + outer loop + vertex 901.563 358.558 30.8398 + vertex 901.755 361.925 28.9338 + vertex 900.81 362.777 31.2803 + endloop + endfacet + facet normal 0.934728 0.150019 0.322146 + outer loop + vertex 901.755 361.925 28.9338 + vertex 901.024 366.41 28.9672 + vertex 900.81 362.777 31.2803 + endloop + endfacet + facet normal 0.933159 0.152312 0.325601 + outer loop + vertex 900.81 362.777 31.2803 + vertex 901.024 366.41 28.9672 + vertex 900.161 367.522 30.9176 + endloop + endfacet + facet normal 0.933448 0.164597 0.318719 + outer loop + vertex 901.024 366.41 28.9672 + vertex 900.16 371.088 29.0813 + vertex 900.161 367.522 30.9176 + endloop + endfacet + facet normal 0.934669 0.163136 0.315881 + outer loop + vertex 900.161 367.522 30.9176 + vertex 900.16 371.088 29.0813 + vertex 899.215 371.919 31.4478 + endloop + endfacet + facet normal 0.93382 0.177967 0.310334 + outer loop + vertex 900.16 371.088 29.0813 + vertex 899.122 376.035 29.3668 + vertex 899.215 371.919 31.4478 + endloop + endfacet + facet normal 0.93443 0.177258 0.308903 + outer loop + vertex 899.215 371.919 31.4478 + vertex 899.122 376.035 29.3668 + vertex 898.455 376.269 31.2518 + endloop + endfacet + facet normal 0.933086 0.186995 0.30722 + outer loop + vertex 898.455 376.269 31.2518 + vertex 899.122 376.035 29.3668 + vertex 897.625 382.076 30.2371 + endloop + endfacet + facet normal 0.803108 -0.366483 0.469796 + outer loop + vertex 893.412 281.666 28.0633 + vertex 895.14 285.568 28.1529 + vertex 892.753 282.812 30.0828 + endloop + endfacet + facet normal 0.785193 -0.392689 0.478819 + outer loop + vertex 890.614 278.889 30.3734 + vertex 893.412 281.666 28.0633 + vertex 892.753 282.812 30.0828 + endloop + endfacet + facet normal 0.785094 -0.391956 0.479581 + outer loop + vertex 891.594 277.882 27.9468 + vertex 893.412 281.666 28.0633 + vertex 890.614 278.889 30.3734 + endloop + endfacet + facet normal 0.768308 -0.418879 0.483987 + outer loop + vertex 889.072 275.371 29.7765 + vertex 891.594 277.882 27.9468 + vertex 890.614 278.889 30.3734 + endloop + endfacet + facet normal 0.767715 -0.415465 0.487855 + outer loop + vertex 889.719 274.247 27.8003 + vertex 891.594 277.882 27.9468 + vertex 889.072 275.371 29.7765 + endloop + endfacet + facet normal 0.752144 -0.435801 0.494325 + outer loop + vertex 887.005 271.983 29.9342 + vertex 889.719 274.247 27.8003 + vertex 889.072 275.371 29.7765 + endloop + endfacet + facet normal 0.752278 -0.437935 0.492231 + outer loop + vertex 887.706 270.644 27.6723 + vertex 889.719 274.247 27.8003 + vertex 887.005 271.983 29.9342 + endloop + endfacet + facet normal 0.732974 -0.461219 0.500025 + outer loop + vertex 884.902 268.255 29.579 + vertex 887.706 270.644 27.6723 + vertex 887.005 271.983 29.9342 + endloop + endfacet + facet normal 0.732256 -0.455085 0.506655 + outer loop + vertex 885.625 267.091 27.4876 + vertex 887.706 270.644 27.6723 + vertex 884.902 268.255 29.579 + endloop + endfacet + facet normal 0.714565 -0.47632 0.512364 + outer loop + vertex 882.743 264.728 29.3104 + vertex 885.625 267.091 27.4876 + vertex 884.902 268.255 29.579 + endloop + endfacet + facet normal 0.737415 -0.486933 0.468098 + outer loop + vertex 882.743 264.728 29.3104 + vertex 884.902 268.255 29.579 + vertex 882.081 265.943 31.6168 + endloop + endfacet + facet normal 0.713639 -0.469108 0.520247 + outer loop + vertex 883.473 263.649 27.3369 + vertex 885.625 267.091 27.4876 + vertex 882.743 264.728 29.3104 + endloop + endfacet + facet normal 0.695147 -0.490786 0.525262 + outer loop + vertex 880.443 261.271 29.125 + vertex 883.473 263.649 27.3369 + vertex 882.743 264.728 29.3104 + endloop + endfacet + facet normal 0.71733 -0.503222 0.481877 + outer loop + vertex 880.443 261.271 29.125 + vertex 882.743 264.728 29.3104 + vertex 879.722 262.418 31.3951 + endloop + endfacet + facet normal 0.692637 -0.531052 0.488095 + outer loop + vertex 876.924 258.651 31.2682 + vertex 880.443 261.271 29.125 + vertex 879.722 262.418 31.3951 + endloop + endfacet + facet normal 0.691802 -0.515986 0.505141 + outer loop + vertex 878.078 257.87 28.8894 + vertex 880.443 261.271 29.125 + vertex 876.924 258.651 31.2682 + endloop + endfacet + facet normal 0.673613 -0.505685 0.539007 + outer loop + vertex 878.078 257.87 28.8894 + vertex 881.246 260.286 27.1974 + vertex 880.443 261.271 29.125 + endloop + endfacet + facet normal 0.671646 -0.493765 0.552347 + outer loop + vertex 878.952 257.006 27.0549 + vertex 881.246 260.286 27.1974 + vertex 878.078 257.87 28.8894 + endloop + endfacet + facet normal 0.652416 -0.516999 0.554135 + outer loop + vertex 876.126 255.011 28.5201 + vertex 878.952 257.006 27.0549 + vertex 878.078 257.87 28.8894 + endloop + endfacet + facet normal 0.661749 -0.521382 0.538747 + outer loop + vertex 876.126 255.011 28.5201 + vertex 878.078 257.87 28.8894 + vertex 874.096 254.712 30.7249 + endloop + endfacet + facet normal 0.651205 -0.508554 0.563298 + outer loop + vertex 876.271 253.602 27.0808 + vertex 878.952 257.006 27.0549 + vertex 876.126 255.011 28.5201 + endloop + endfacet + facet normal 0.634506 -0.51948 0.572313 + outer loop + vertex 872.637 251.559 29.256 + vertex 876.271 253.602 27.0808 + vertex 876.126 255.011 28.5201 + endloop + endfacet + facet normal 0.634541 -0.523343 0.568744 + outer loop + vertex 873.003 249.711 27.147 + vertex 876.271 253.602 27.0808 + vertex 872.637 251.559 29.256 + endloop + endfacet + facet normal 0.61467 -0.537278 0.577506 + outer loop + vertex 868.053 246.565 29.4874 + vertex 873.003 249.711 27.147 + vertex 872.637 251.559 29.256 + endloop + endfacet + facet normal 0.612772 -0.523551 0.591949 + outer loop + vertex 869.906 245.592 26.7095 + vertex 873.003 249.711 27.147 + vertex 868.053 246.565 29.4874 + endloop + endfacet + facet normal 0.597812 -0.543741 0.589038 + outer loop + vertex 868.053 246.565 29.4874 + vertex 863.762 240.484 28.2298 + vertex 869.906 245.592 26.7095 + endloop + endfacet + facet normal 0.6939 -0.481717 0.535212 + outer loop + vertex 881.246 260.286 27.1974 + vertex 883.473 263.649 27.3369 + vertex 880.443 261.271 29.125 + endloop + endfacet + facet normal 0.754043 -0.469254 0.459586 + outer loop + vertex 884.902 268.255 29.579 + vertex 887.005 271.983 29.9342 + vertex 884.203 269.578 32.0763 + endloop + endfacet + facet normal 0.737485 -0.489267 0.465546 + outer loop + vertex 882.081 265.943 31.6168 + vertex 884.902 268.255 29.579 + vertex 884.203 269.578 32.0763 + endloop + endfacet + facet normal 0.717442 -0.51001 0.474517 + outer loop + vertex 879.722 262.418 31.3951 + vertex 882.743 264.728 29.3104 + vertex 882.081 265.943 31.6168 + endloop + endfacet + facet normal 0.722646 -0.5164 0.459471 + outer loop + vertex 879.265 263.758 33.6713 + vertex 881.212 267.074 34.3363 + vertex 876.576 263.185 37.2579 + endloop + endfacet + facet normal 0.702811 -0.537853 0.465587 + outer loop + vertex 876.924 258.651 31.2682 + vertex 879.722 262.418 31.3951 + vertex 876.113 260.082 34.1458 + endloop + endfacet + facet normal 0.667223 -0.548538 0.503904 + outer loop + vertex 874.096 254.712 30.7249 + vertex 878.078 257.87 28.8894 + vertex 876.924 258.651 31.2682 + endloop + endfacet + facet normal 0.646683 -0.584844 0.489651 + outer loop + vertex 867.813 249.597 32.9375 + vertex 872.119 255.236 33.9853 + vertex 865.909 251.217 37.3872 + endloop + endfacet + facet normal 0.651583 -0.546627 0.525964 + outer loop + vertex 876.126 255.011 28.5201 + vertex 874.096 254.712 30.7249 + vertex 872.637 251.559 29.256 + endloop + endfacet + facet normal 0.606866 -0.547472 0.576184 + outer loop + vertex 863.762 240.484 28.2298 + vertex 868.053 246.565 29.4874 + vertex 861.729 242.985 32.7479 + endloop + endfacet + facet normal 0.581881 -0.571748 0.578376 + outer loop + vertex 856.893 237.409 32.1004 + vertex 863.762 240.484 28.2298 + vertex 861.729 242.985 32.7479 + endloop + endfacet + facet normal 0.582936 -0.554098 0.594274 + outer loop + vertex 857.952 234.252 28.1178 + vertex 863.762 240.484 28.2298 + vertex 856.893 237.409 32.1004 + endloop + endfacet + facet normal 0.5651 -0.566744 0.599552 + outer loop + vertex 853.565 233.187 31.2462 + vertex 857.952 234.252 28.1178 + vertex 856.893 237.409 32.1004 + endloop + endfacet + facet normal 0.568491 -0.553207 0.608917 + outer loop + vertex 854.641 230.563 27.857 + vertex 857.952 234.252 28.1178 + vertex 853.565 233.187 31.2462 + endloop + endfacet + facet normal 0.561951 -0.558036 0.610579 + outer loop + vertex 854.641 230.563 27.857 + vertex 853.565 233.187 31.2462 + vertex 852.315 230.479 29.922 + endloop + endfacet + facet normal 0.561146 -0.582731 0.587826 + outer loop + vertex 849.616 234.924 36.7561 + vertex 851.113 232.884 33.3047 + vertex 852.324 235.821 35.0598 + endloop + endfacet + facet normal 0.54124 -0.581551 0.607337 + outer loop + vertex 850.196 230.943 32.3381 + vertex 848.454 232.762 35.6321 + vertex 848.067 229.75 33.0931 + endloop + endfacet + facet normal 0.538806 -0.567605 0.622505 + outer loop + vertex 849.589 226.46 28.775 + vertex 850.196 230.943 32.3381 + vertex 848.067 229.75 33.0931 + endloop + endfacet + facet normal 0.516663 -0.560691 0.647059 + outer loop + vertex 844.128 219.941 27.6744 + vertex 844.45 225.238 32.0072 + vertex 839.634 218.218 29.7695 + endloop + endfacet + facet normal 0.541058 -0.544278 0.641107 + outer loop + vertex 849.231 222.69 25.8762 + vertex 852.056 225.29 25.7001 + vertex 849.589 226.46 28.775 + endloop + endfacet + facet normal 0.507912 -0.538388 0.672431 + outer loop + vertex 839.177 215.421 27.7949 + vertex 839.983 214.411 26.3775 + vertex 844.128 219.941 27.6744 + endloop + endfacet + facet normal 0.51678 -0.548504 0.657329 + outer loop + vertex 839.177 215.421 27.7949 + vertex 844.128 219.941 27.6744 + vertex 839.634 218.218 29.7695 + endloop + endfacet + facet normal 0.50704 -0.537452 0.673837 + outer loop + vertex 836.34 211.381 26.7171 + vertex 835.696 212.753 28.2962 + vertex 832.686 208.121 26.867 + endloop + endfacet + facet normal 0.49762 -0.526167 0.689582 + outer loop + vertex 833.795 207.376 25.4979 + vertex 836.34 211.381 26.7171 + vertex 832.686 208.121 26.867 + endloop + endfacet + facet normal 0.486337 -0.516283 0.704932 + outer loop + vertex 835.554 207.432 24.3258 + vertex 833.795 207.376 25.4979 + vertex 831.734 203.825 24.3188 + endloop + endfacet + facet normal 0.487021 -0.531364 0.693154 + outer loop + vertex 830.166 204.026 25.5314 + vertex 829.117 204.838 26.8915 + vertex 826.663 200.882 25.583 + endloop + endfacet + facet normal 0.486576 -0.532253 0.692784 + outer loop + vertex 829.117 204.838 26.8915 + vertex 831.801 209.253 28.3981 + vertex 828.202 205.906 28.354 + endloop + endfacet + facet normal 0.486589 -0.532267 0.692765 + outer loop + vertex 831.801 209.253 28.3981 + vertex 830.839 210.46 30.0009 + vertex 828.202 205.906 28.354 + endloop + endfacet + facet normal 0.453087 -0.527307 0.71879 + outer loop + vertex 830.839 210.46 30.0009 + vertex 833.702 215.81 32.1216 + vertex 829.721 211.401 31.396 + endloop + endfacet + facet normal 0.456154 -0.520272 0.72197 + outer loop + vertex 824.859 202.902 28.3538 + vertex 827.273 207.103 29.8558 + vertex 823.943 204.143 29.8266 + endloop + endfacet + facet normal 0.475174 -0.532206 0.70069 + outer loop + vertex 825.74 201.799 26.9177 + vertex 824.859 202.902 28.3538 + vertex 822.431 198.936 26.9873 + endloop + endfacet + facet normal 0.475142 -0.532168 0.70074 + outer loop + vertex 823.361 198.054 25.6876 + vertex 825.74 201.799 26.9177 + vertex 822.431 198.936 26.9873 + endloop + endfacet + facet normal 0.466609 -0.528256 0.709381 + outer loop + vertex 824.287 197.324 24.5348 + vertex 823.361 198.054 25.6876 + vertex 821.362 195.095 24.7984 + endloop + endfacet + facet normal 0.453133 -0.540966 0.708538 + outer loop + vertex 812.586 189.363 26.1312 + vertex 815.426 193.218 27.2588 + vertex 811.95 190.85 27.6742 + endloop + endfacet + facet normal 0.464603 -0.538395 0.703047 + outer loop + vertex 820.087 195.274 25.7676 + vertex 818.998 196.045 27.0774 + vertex 816.514 192.302 25.8524 + endloop + endfacet + facet normal 0.459751 -0.529485 0.712933 + outer loop + vertex 818.998 196.045 27.0774 + vertex 821.518 200.033 28.4141 + vertex 818.072 197.174 28.5129 + endloop + endfacet + facet normal 0.446948 -0.513373 0.732588 + outer loop + vertex 821.518 200.033 28.4141 + vertex 820.575 201.264 29.8517 + vertex 818.072 197.174 28.5129 + endloop + endfacet + facet normal 0.403395 -0.485564 0.775565 + outer loop + vertex 820.575 201.264 29.8517 + vertex 822.94 205.238 31.1099 + vertex 819.692 202.865 31.3132 + endloop + endfacet + facet normal 0.426298 -0.50459 0.750773 + outer loop + vertex 814.71 194.538 28.688 + vertex 817.157 198.426 29.9124 + vertex 813.896 195.785 29.9889 + endloop + endfacet + facet normal 0.448856 -0.533183 0.717108 + outer loop + vertex 815.426 193.218 27.2588 + vertex 814.71 194.538 28.688 + vertex 811.95 190.85 27.6742 + endloop + endfacet + facet normal 0.404347 -0.506501 0.761551 + outer loop + vertex 812.043 192.673 28.9585 + vertex 810.8 193.207 29.9741 + vertex 809.259 189.899 28.5921 + endloop + endfacet + facet normal 0.444904 -0.545939 0.709937 + outer loop + vertex 812.586 189.363 26.1312 + vertex 811.95 190.85 27.6742 + vertex 808.082 186.558 26.7969 + endloop + endfacet + facet normal 0.43285 -0.547191 0.716396 + outer loop + vertex 804.566 181.823 25.305 + vertex 808.082 186.558 26.7969 + vertex 803.505 183.217 27.0102 + endloop + endfacet + facet normal 0.402388 -0.556065 0.727238 + outer loop + vertex 798.696 178.807 26.4234 + vertex 795.696 179.291 28.4532 + vertex 791.798 174.144 26.6743 + endloop + endfacet + facet normal 0.378674 -0.54524 0.747877 + outer loop + vertex 791.798 174.144 26.6743 + vertex 795.696 179.291 28.4532 + vertex 789.313 175.204 28.7054 + endloop + endfacet + facet normal 0.373988 -0.551683 0.745506 + outer loop + vertex 791.798 174.144 26.6743 + vertex 789.313 175.204 28.7054 + vertex 784.388 168.997 26.5833 + endloop + endfacet + facet normal 0.356901 -0.543094 0.760046 + outer loop + vertex 784.388 168.997 26.5833 + vertex 789.313 175.204 28.7054 + vertex 781.752 170.562 28.9391 + endloop + endfacet + facet normal 0.350962 -0.549895 0.757919 + outer loop + vertex 784.388 168.997 26.5833 + vertex 781.752 170.562 28.9391 + vertex 775.729 163.697 26.7473 + endloop + endfacet + facet normal 0.345721 -0.546781 0.762566 + outer loop + vertex 775.729 163.697 26.7473 + vertex 781.752 170.562 28.9391 + vertex 773.417 165.567 29.1365 + endloop + endfacet + facet normal 0.335655 -0.556236 0.760222 + outer loop + vertex 775.729 163.697 26.7473 + vertex 773.417 165.567 29.1365 + vertex 767.354 159.183 27.1428 + endloop + endfacet + facet normal 0.328769 -0.551667 0.766534 + outer loop + vertex 767.354 159.183 27.1428 + vertex 773.417 165.567 29.1365 + vertex 765.152 160.787 29.241 + endloop + endfacet + facet normal 0.317162 -0.563107 0.763098 + outer loop + vertex 767.354 159.183 27.1428 + vertex 765.152 160.787 29.241 + vertex 758.952 154.274 27.0118 + endloop + endfacet + facet normal 0.313173 -0.560522 0.766641 + outer loop + vertex 758.952 154.274 27.0118 + vertex 765.152 160.787 29.241 + vertex 757.002 156.305 29.2937 + endloop + endfacet + facet normal 0.30438 -0.56732 0.76518 + outer loop + vertex 758.952 154.274 27.0118 + vertex 757.002 156.305 29.2937 + vertex 750.968 150.349 27.2783 + endloop + endfacet + facet normal 0.298011 -0.562829 0.770981 + outer loop + vertex 750.968 150.349 27.2783 + vertex 757.002 156.305 29.2937 + vertex 748.752 152.023 29.3564 + endloop + endfacet + facet normal 0.287333 -0.572838 0.767656 + outer loop + vertex 750.968 150.349 27.2783 + vertex 748.752 152.023 29.3564 + vertex 742.376 145.813 27.1092 + endloop + endfacet + facet normal 0.294698 -0.577983 0.760979 + outer loop + vertex 742.376 145.813 27.1092 + vertex 748.752 152.023 29.3564 + vertex 740.294 147.878 29.4834 + endloop + endfacet + facet normal 0.285315 -0.585208 0.759031 + outer loop + vertex 742.376 145.813 27.1092 + vertex 740.294 147.878 29.4834 + vertex 733.591 142.064 27.5208 + endloop + endfacet + facet normal 0.290153 -0.589136 0.754142 + outer loop + vertex 733.591 142.064 27.5208 + vertex 740.294 147.878 29.4834 + vertex 731.948 144.007 29.6707 + endloop + endfacet + facet normal 0.284004 -0.63352 0.719718 + outer loop + vertex 727.494 137.314 25.8787 + vertex 725.714 138.593 27.7064 + vertex 720.739 134.643 26.1926 + endloop + endfacet + facet normal 0.269539 -0.630766 0.727656 + outer loop + vertex 714.047 132.812 27.1497 + vertex 718.832 135.426 27.6422 + vertex 714.445 135.377 29.2251 + endloop + endfacet + facet normal 0.275313 -0.66792 0.691437 + outer loop + vertex 706.325 129.042 26.5839 + vertex 710.095 131.062 27.0347 + vertex 707.392 130.914 27.9675 + endloop + endfacet + facet normal 0.271776 -0.667346 0.693388 + outer loop + vertex 706.325 129.042 26.5839 + vertex 707.392 130.914 27.9675 + vertex 703.857 128.316 26.8532 + endloop + endfacet + facet normal 0.299907 -0.66824 0.680817 + outer loop + vertex 703.942 129.869 28.3709 + vertex 707.945 133.479 30.1514 + vertex 703.45 131.691 30.377 + endloop + endfacet + facet normal 0.286681 -0.62979 0.721927 + outer loop + vertex 707.945 133.479 30.1514 + vertex 707.138 136.052 32.7165 + vertex 703.45 131.691 30.377 + endloop + endfacet + facet normal 0.319952 -0.643622 0.695256 + outer loop + vertex 707.138 136.052 32.7165 + vertex 701.218 133.389 32.9757 + vertex 703.45 131.691 30.377 + endloop + endfacet + facet normal 0.306953 -0.621926 0.720408 + outer loop + vertex 707.945 133.479 30.1514 + vertex 713.956 138.888 32.26 + vertex 707.138 136.052 32.7165 + endloop + endfacet + facet normal 0.262773 -0.689378 0.675062 + outer loop + vertex 701.614 127.601 27.0328 + vertex 701.5 128.891 28.394 + vertex 700.031 127.164 27.202 + endloop + endfacet + facet normal 0.259737 -0.696539 0.668857 + outer loop + vertex 697.013 125.711 26.8957 + vertex 696.587 127.165 28.5752 + vertex 693.582 124.95 27.4353 + endloop + endfacet + facet normal 0.285966 -0.706046 0.64786 + outer loop + vertex 696.587 127.165 28.5752 + vertex 698.228 129.699 30.612 + vertex 694.339 127.359 29.7782 + endloop + endfacet + facet normal 0.280458 -0.695232 0.661813 + outer loop + vertex 699.589 127.995 28.2314 + vertex 700.712 130.026 29.8892 + vertex 699.321 128.833 29.2249 + endloop + endfacet + facet normal 0.286132 -0.67096 0.684063 + outer loop + vertex 700.712 130.026 29.8892 + vertex 703.45 131.691 30.377 + vertex 701.218 133.389 32.9757 + endloop + endfacet + facet normal 0.296456 -0.704131 0.645223 + outer loop + vertex 698.228 129.699 30.612 + vertex 697.478 131.413 32.8269 + vertex 695.221 129.238 31.4909 + endloop + endfacet + facet normal 0.300048 -0.709988 0.637094 + outer loop + vertex 694.588 131.228 34.0268 + vertex 691.163 128.395 32.4829 + vertex 695.338 130.339 32.683 + endloop + endfacet + facet normal 0.298009 -0.718511 0.628437 + outer loop + vertex 690.55 126.984 31.1282 + vertex 692.548 127.222 30.4532 + vertex 695.221 129.238 31.4909 + endloop + endfacet + facet normal 0.297829 -0.71929 0.627631 + outer loop + vertex 690.55 126.984 31.1282 + vertex 686.51 124.693 30.4193 + vertex 692.548 127.222 30.4532 + endloop + endfacet + facet normal 0.304991 -0.734111 0.606681 + outer loop + vertex 686.51 124.693 30.4193 + vertex 678.931 121.426 30.277 + vertex 681.83 122.508 30.1282 + endloop + endfacet + facet normal 0.318824 -0.75423 0.57401 + outer loop + vertex 679.225 121.824 30.6358 + vertex 675.462 120.127 30.4961 + vertex 678.931 121.426 30.277 + endloop + endfacet + facet normal 0.32005 -0.756632 0.570155 + outer loop + vertex 679.124 122.291 31.3135 + vertex 675.462 120.127 30.4961 + vertex 679.225 121.824 30.6358 + endloop + endfacet + facet normal 0.319147 -0.741212 0.590551 + outer loop + vertex 691.163 128.395 32.4829 + vertex 684.513 125.72 32.7202 + vertex 684.408 124.433 31.1608 + endloop + endfacet + facet normal 0.312834 -0.72329 0.615618 + outer loop + vertex 689.666 129.498 34.5398 + vertex 684.513 125.72 32.7202 + vertex 691.163 128.395 32.4829 + endloop + endfacet + facet normal 0.317339 -0.72002 0.617145 + outer loop + vertex 689.666 129.498 34.5398 + vertex 691.163 128.395 32.4829 + vertex 694.588 131.228 34.0268 + endloop + endfacet + facet normal 0.328007 -0.742179 0.58445 + outer loop + vertex 683.323 126.773 34.7246 + vertex 678.118 122.87 32.6902 + vertex 684.513 125.72 32.7202 + endloop + endfacet + facet normal 0.334194 -0.73817 0.58602 + outer loop + vertex 683.323 126.773 34.7246 + vertex 684.513 125.72 32.7202 + vertex 689.666 129.498 34.5398 + endloop + endfacet + facet normal 0.33165 -0.767898 0.548034 + outer loop + vertex 674.067 120.033 31.2094 + vertex 675.462 120.127 30.4961 + vertex 679.124 122.291 31.3135 + endloop + endfacet + facet normal 0.334767 -0.783062 0.524162 + outer loop + vertex 672.178 120.025 32.4034 + vertex 670.02 118.177 31.0214 + vertex 674.067 120.033 31.2094 + endloop + endfacet + facet normal 0.349749 -0.755379 0.554146 + outer loop + vertex 676.243 123.376 34.5629 + vertex 678.118 122.87 32.6902 + vertex 683.323 126.773 34.7246 + endloop + endfacet + facet normal 0.34239 -0.741151 0.577464 + outer loop + vertex 681.837 127.912 37.0674 + vertex 676.243 123.376 34.5629 + vertex 683.323 126.773 34.7246 + endloop + endfacet + facet normal 0.355436 -0.731973 0.581275 + outer loop + vertex 681.837 127.912 37.0674 + vertex 683.323 126.773 34.7246 + vertex 688.298 130.935 36.9236 + endloop + endfacet + facet normal 0.348401 -0.791822 0.501632 + outer loop + vertex 668.315 117.986 31.8684 + vertex 672.178 120.025 32.4034 + vertex 668.528 119.435 34.0087 + endloop + endfacet + facet normal 0.372338 -0.788592 0.489375 + outer loop + vertex 668.528 119.435 34.0087 + vertex 668.167 121.05 36.8858 + vertex 663.114 117.888 35.6338 + endloop + endfacet + facet normal 0.380226 -0.794745 0.473085 + outer loop + vertex 668.167 121.05 36.8858 + vertex 665.495 120.887 38.7595 + vertex 663.114 117.888 35.6338 + endloop + endfacet + facet normal 0.392576 -0.794449 0.463394 + outer loop + vertex 659.957 117.8 38.1578 + vertex 663.114 117.888 35.6338 + vertex 665.495 120.887 38.7595 + endloop + endfacet + facet normal 0.40046 -0.814608 0.419577 + outer loop + vertex 657.967 118.797 41.9188 + vertex 655.662 116.854 40.3471 + vertex 657.708 117.629 39.8991 + endloop + endfacet + facet normal 0.396482 -0.79919 0.451771 + outer loop + vertex 665.495 120.887 38.7595 + vertex 662.829 120.822 40.9823 + vertex 659.957 117.8 38.1578 + endloop + endfacet + facet normal 0.373525 -0.817288 0.438771 + outer loop + vertex 659.957 117.8 38.1578 + vertex 659.43 116.371 35.9449 + vertex 663.114 117.888 35.6338 + endloop + endfacet + facet normal 0.345756 -0.857032 0.382033 + outer loop + vertex 657.903 116.058 36.6162 + vertex 655.902 116.263 38.8875 + vertex 656.009 115.704 37.537 + endloop + endfacet + facet normal 0.400438 -0.815167 0.418511 + outer loop + vertex 655.662 116.854 40.3471 + vertex 657.152 116.481 38.1948 + vertex 657.708 117.629 39.8991 + endloop + endfacet + facet normal 0.359137 -0.851472 0.382122 + outer loop + vertex 655.902 116.263 38.8875 + vertex 654.358 116.606 41.1017 + vertex 653.939 115.836 39.7804 + endloop + endfacet + facet normal 0.408754 -0.815876 0.408982 + outer loop + vertex 654.549 117.22 42.1882 + vertex 655.662 116.854 40.3471 + vertex 657.967 118.797 41.9188 + endloop + endfacet + facet normal 0.367355 -0.849181 0.379397 + outer loop + vertex 654.358 116.606 41.1017 + vertex 652.998 116.986 43.2687 + vertex 652.843 116.267 41.8096 + endloop + endfacet + facet normal 0.403905 -0.82156 0.402368 + outer loop + vertex 653.597 117.217 43.1387 + vertex 654.549 117.22 42.1882 + vertex 655.879 118.322 43.1035 + endloop + endfacet + facet normal 0.408025 -0.830836 0.378454 + outer loop + vertex 654.164 117.688 43.5604 + vertex 653.597 117.217 43.1387 + vertex 655.879 118.322 43.1035 + endloop + endfacet + facet normal 0.408035 -0.830779 0.378568 + outer loop + vertex 654.164 117.688 43.5604 + vertex 655.879 118.322 43.1035 + vertex 657.592 119.634 44.1362 + endloop + endfacet + facet normal 0.398023 -0.829925 0.390899 + outer loop + vertex 653.166 117.115 43.3598 + vertex 653.597 117.217 43.1387 + vertex 654.164 117.688 43.5604 + endloop + endfacet + facet normal 0.384621 -0.850969 0.357658 + outer loop + vertex 652.998 116.986 43.2687 + vertex 650.709 116.178 43.8078 + vertex 651.641 116.347 43.2091 + endloop + endfacet + facet normal 0.398769 -0.84867 0.347481 + outer loop + vertex 647.863 114.916 43.8927 + vertex 651.766 117.545 45.8356 + vertex 646.626 114.987 45.4856 + endloop + endfacet + facet normal 0.390391 -0.855064 0.341263 + outer loop + vertex 647.863 114.916 43.8927 + vertex 646.626 114.987 45.4856 + vertex 644.292 113.148 43.5486 + endloop + endfacet + facet normal 0.406153 -0.877745 0.254171 + outer loop + vertex 644.546 112.867 42.4984 + vertex 642.28 111.78 42.3693 + vertex 639.974 110.456 41.4797 + endloop + endfacet + facet normal 0.384244 -0.859322 0.337524 + outer loop + vertex 644.292 113.148 43.5486 + vertex 642.89 113.13 45.0989 + vertex 641.06 111.468 42.9493 + endloop + endfacet + facet normal 0.424338 -0.880533 0.211185 + outer loop + vertex 642.28 111.78 42.3693 + vertex 640.775 110.968 42.0043 + vertex 639.974 110.456 41.4797 + endloop + endfacet + facet normal 0.385518 -0.881795 0.271688 + outer loop + vertex 640.775 110.968 42.0043 + vertex 639.29 110.276 41.8652 + vertex 639.974 110.456 41.4797 + endloop + endfacet + facet normal 0.373475 -0.864617 0.336086 + outer loop + vertex 641.06 111.468 42.9493 + vertex 639.614 111.51 44.6633 + vertex 637.945 109.975 42.5698 + endloop + endfacet + facet normal 0.373421 -0.864622 0.336133 + outer loop + vertex 637.945 109.975 42.5698 + vertex 639.614 111.51 44.6633 + vertex 636.494 109.972 44.1742 + endloop + endfacet + facet normal 0.38267 -0.882184 0.274437 + outer loop + vertex 636.322 108.778 41.2342 + vertex 633.248 107.298 40.7631 + vertex 632.531 106.734 39.949 + endloop + endfacet + facet normal 0.36451 -0.872375 0.325722 + outer loop + vertex 630.935 106.173 40.3372 + vertex 633.248 107.298 40.7631 + vertex 631.876 106.989 41.4715 + endloop + endfacet + facet normal 0.363788 -0.870501 0.331491 + outer loop + vertex 631.876 106.989 41.4715 + vertex 633.406 108.452 43.6339 + vertex 630.273 106.921 43.0517 + endloop + endfacet + facet normal 0.367171 -0.873218 0.32043 + outer loop + vertex 633.406 108.452 43.6339 + vertex 631.92 108.759 46.174 + vertex 630.273 106.921 43.0517 + endloop + endfacet + facet normal 0.36554 -0.873521 0.321468 + outer loop + vertex 630.273 106.921 43.0517 + vertex 631.92 108.759 46.174 + vertex 628.678 107.2 45.6234 + endloop + endfacet + facet normal 0.369152 -0.867943 0.332268 + outer loop + vertex 637.945 109.975 42.5698 + vertex 636.494 109.972 44.1742 + vertex 634.854 108.454 42.0324 + endloop + endfacet + facet normal 0.371719 -0.870434 0.322754 + outer loop + vertex 633.406 108.452 43.6339 + vertex 635.06 110.295 46.699 + vertex 631.92 108.759 46.174 + endloop + endfacet + facet normal 0.375251 -0.87342 0.310362 + outer loop + vertex 635.06 110.295 46.699 + vertex 633.574 110.831 50.0035 + vertex 631.92 108.759 46.174 + endloop + endfacet + facet normal 0.374732 -0.87354 0.310652 + outer loop + vertex 631.92 108.759 46.174 + vertex 633.574 110.831 50.0035 + vertex 630.346 109.267 49.5013 + endloop + endfacet + facet normal 0.377937 -0.876321 0.298705 + outer loop + vertex 633.574 110.831 50.0035 + vertex 632.042 111.602 54.2041 + vertex 630.346 109.267 49.5013 + endloop + endfacet + facet normal 0.386297 -0.871899 0.300943 + outer loop + vertex 633.574 110.831 50.0035 + vertex 635.24 112.904 53.8711 + vertex 632.042 111.602 54.2041 + endloop + endfacet + facet normal 0.38646 -0.873707 0.29544 + outer loop + vertex 635.24 112.904 53.8711 + vertex 635.593 115.134 60.0056 + vertex 632.042 111.602 54.2041 + endloop + endfacet + facet normal 0.391178 -0.87277 0.291982 + outer loop + vertex 635.593 115.134 60.0056 + vertex 629.015 111.915 59.1951 + vertex 632.042 111.602 54.2041 + endloop + endfacet + facet normal 0.384498 -0.872344 0.301956 + outer loop + vertex 636.701 112.367 50.4592 + vertex 635.24 112.904 53.8711 + vertex 633.574 110.831 50.0035 + endloop + endfacet + facet normal 0.376409 -0.867343 0.325624 + outer loop + vertex 639.614 111.51 44.6633 + vertex 638.144 111.817 47.1822 + vertex 636.494 109.972 44.1742 + endloop + endfacet + facet normal 0.381687 -0.8698 0.312669 + outer loop + vertex 635.06 110.295 46.699 + vertex 636.701 112.367 50.4592 + vertex 633.574 110.831 50.0035 + endloop + endfacet + facet normal 0.386097 -0.866283 0.316991 + outer loop + vertex 641.291 113.364 47.5773 + vertex 639.786 113.892 50.8514 + vertex 638.144 111.817 47.1822 + endloop + endfacet + facet normal 0.392369 -0.867899 0.304627 + outer loop + vertex 636.701 112.367 50.4592 + vertex 638.387 114.737 55.04 + vertex 635.24 112.904 53.8711 + endloop + endfacet + facet normal 0.397777 -0.863467 0.310158 + outer loop + vertex 643.044 115.533 51.2434 + vertex 641.491 116.051 54.676 + vertex 639.786 113.892 50.8514 + endloop + endfacet + facet normal 0.415026 -0.858293 0.301805 + outer loop + vertex 641.491 116.051 54.676 + vertex 644.918 118.212 56.1104 + vertex 641.868 118.422 60.9019 + endloop + endfacet + facet normal 0.397506 -0.869474 0.293265 + outer loop + vertex 635.24 112.904 53.8711 + vertex 638.387 114.737 55.04 + vertex 635.593 115.134 60.0056 + endloop + endfacet + facet normal 0.44099 -0.850457 0.286794 + outer loop + vertex 641.868 118.422 60.9019 + vertex 645.935 123.46 69.5871 + vertex 639.867 120.042 68.783 + endloop + endfacet + facet normal 0.444999 -0.853724 0.270428 + outer loop + vertex 645.935 123.46 69.5871 + vertex 644.633 125.225 77.2995 + vertex 639.867 120.042 68.783 + endloop + endfacet + facet normal 0.494165 -0.833198 0.248157 + outer loop + vertex 644.633 125.225 77.2995 + vertex 649.61 130.656 85.6254 + vertex 643.786 127.059 85.1466 + endloop + endfacet + facet normal 0.497029 -0.835833 0.233119 + outer loop + vertex 649.61 130.656 85.6254 + vertex 649.052 132.498 93.4182 + vertex 643.786 127.059 85.1466 + endloop + endfacet + facet normal 0.590546 -0.800679 0.100838 + outer loop + vertex 647.701 139.556 132.235 + vertex 652.887 144.419 140.482 + vertex 647.569 140.463 140.214 + endloop + endfacet + facet normal 0.592341 -0.801691 0.0801492 + outer loop + vertex 652.887 144.419 140.482 + vertex 652.784 145.144 148.493 + vertex 647.569 140.463 140.214 + endloop + endfacet + facet normal 0.594116 -0.800551 0.0783871 + outer loop + vertex 647.569 140.463 140.214 + vertex 652.784 145.144 148.493 + vertex 647.474 141.179 148.247 + endloop + endfacet + facet normal 0.595605 -0.801236 0.0572297 + outer loop + vertex 652.784 145.144 148.493 + vertex 652.707 145.659 156.505 + vertex 647.474 141.179 148.247 + endloop + endfacet + facet normal 0.595989 -0.800978 0.0568465 + outer loop + vertex 647.474 141.179 148.247 + vertex 652.707 145.659 156.505 + vertex 647.398 141.693 156.281 + endloop + endfacet + facet normal 0.597233 -0.801348 0.0339738 + outer loop + vertex 652.707 145.659 156.505 + vertex 652.661 145.963 164.484 + vertex 647.398 141.693 156.281 + endloop + endfacet + facet normal 0.597065 -0.801466 0.0341428 + outer loop + vertex 647.398 141.693 156.281 + vertex 652.661 145.963 164.484 + vertex 647.357 142.003 164.281 + endloop + endfacet + facet normal 0.597948 -0.80146 0.0109481 + outer loop + vertex 652.661 145.963 164.484 + vertex 652.644 146.059 172.43 + vertex 647.357 142.003 164.281 + endloop + endfacet + facet normal 0.59718 -0.802022 0.0117266 + outer loop + vertex 647.357 142.003 164.281 + vertex 652.644 146.059 172.43 + vertex 647.344 142.11 172.249 + endloop + endfacet + facet normal 0.597702 -0.801623 -0.012312 + outer loop + vertex 652.644 146.059 172.43 + vertex 652.659 145.948 180.368 + vertex 647.344 142.11 172.249 + endloop + endfacet + facet normal 0.596444 -0.802579 -0.0110363 + outer loop + vertex 647.344 142.11 172.249 + vertex 652.659 145.948 180.368 + vertex 647.36 142.013 180.211 + endloop + endfacet + facet normal 0.594978 -0.803027 -0.0338963 + outer loop + vertex 647.36 142.013 180.211 + vertex 652.704 145.63 188.322 + vertex 647.406 141.709 188.189 + endloop + endfacet + facet normal 0.592866 -0.80326 -0.0572962 + outer loop + vertex 647.406 141.709 188.189 + vertex 652.784 145.101 196.297 + vertex 647.487 141.199 196.19 + endloop + endfacet + facet normal 0.589717 -0.803577 -0.0806011 + outer loop + vertex 647.487 141.199 196.19 + vertex 652.894 144.356 204.275 + vertex 647.592 140.473 204.195 + endloop + endfacet + facet normal 0.585802 -0.80369 -0.104493 + outer loop + vertex 647.592 140.473 204.195 + vertex 653.031 143.393 212.227 + vertex 647.727 139.534 212.174 + endloop + endfacet + facet normal 0.580917 -0.803802 -0.128211 + outer loop + vertex 647.727 139.534 212.174 + vertex 653.205 142.226 220.113 + vertex 647.899 138.395 220.089 + endloop + endfacet + facet normal 0.533878 -0.832076 -0.15041 + outer loop + vertex 642.214 134.714 220.063 + vertex 648.115 137.082 227.904 + vertex 642.425 133.43 227.916 + endloop + endfacet + facet normal 0.578773 -0.800662 -0.154797 + outer loop + vertex 653.205 142.226 220.113 + vertex 653.43 140.884 227.898 + vertex 647.899 138.395 220.089 + endloop + endfacet + facet normal 0.568146 -0.804467 -0.173327 + outer loop + vertex 648.115 137.082 227.904 + vertex 653.731 139.396 235.572 + vertex 648.399 135.621 235.615 + endloop + endfacet + facet normal 0.619413 -0.764714 -0.177597 + outer loop + vertex 658.372 144.882 227.92 + vertex 658.688 143.363 235.561 + vertex 653.43 140.884 227.898 + endloop + endfacet + facet normal 0.564932 -0.800245 -0.201143 + outer loop + vertex 653.731 139.396 235.572 + vertex 654.143 137.779 243.164 + vertex 648.399 135.621 235.615 + endloop + endfacet + facet normal 0.531501 -0.82846 -0.176522 + outer loop + vertex 648.115 137.082 227.904 + vertex 648.399 135.621 235.615 + vertex 642.425 133.43 227.916 + endloop + endfacet + facet normal 0.50332 -0.850518 -0.152604 + outer loop + vertex 642.214 134.714 220.063 + vertex 642.425 133.43 227.916 + vertex 636.137 131.123 220.03 + endloop + endfacet + facet normal 0.50511 -0.853795 -0.126085 + outer loop + vertex 635.972 132.204 212.05 + vertex 642.214 134.714 220.063 + vertex 636.137 131.123 220.03 + endloop + endfacet + facet normal 0.509972 -0.854048 -0.102617 + outer loop + vertex 635.843 133.093 204.012 + vertex 642.049 135.825 212.119 + vertex 635.972 132.204 212.05 + endloop + endfacet + facet normal 0.514129 -0.854078 -0.0788834 + outer loop + vertex 635.743 133.777 195.951 + vertex 641.913 136.737 204.112 + vertex 635.843 133.093 204.012 + endloop + endfacet + facet normal 0.517234 -0.854043 -0.0554969 + outer loop + vertex 635.669 134.255 187.9 + vertex 641.81 137.443 196.081 + vertex 635.743 133.777 195.951 + endloop + endfacet + facet normal 0.519346 -0.853951 -0.0323699 + outer loop + vertex 635.629 134.535 179.875 + vertex 641.737 137.94 188.055 + vertex 635.669 134.255 187.9 + endloop + endfacet + facet normal 0.520725 -0.85367 -0.00964579 + outer loop + vertex 635.614 134.616 171.867 + vertex 641.69 138.23 180.053 + vertex 635.629 134.535 179.875 + endloop + endfacet + facet normal 0.52107 -0.853415 0.0130245 + outer loop + vertex 635.627 134.502 163.851 + vertex 641.674 138.32 172.067 + vertex 635.614 134.616 171.867 + endloop + endfacet + facet normal 0.520376 -0.853195 0.0355975 + outer loop + vertex 635.673 134.194 155.803 + vertex 641.692 138.211 164.076 + vertex 635.627 134.502 163.851 + endloop + endfacet + facet normal 0.519153 -0.852733 0.0576683 + outer loop + vertex 635.743 133.691 147.719 + vertex 641.731 137.9 156.051 + vertex 635.673 134.194 155.803 + endloop + endfacet + facet normal 0.516869 -0.852363 0.079525 + outer loop + vertex 635.841 132.996 139.633 + vertex 641.802 137.39 147.992 + vertex 635.743 133.691 147.719 + endloop + endfacet + facet normal 0.513673 -0.852035 0.100875 + outer loop + vertex 635.96 132.117 131.604 + vertex 641.901 136.684 139.934 + vertex 635.841 132.996 139.633 + endloop + endfacet + facet normal 0.509347 -0.851766 0.122724 + outer loop + vertex 636.124 131.071 123.671 + vertex 642.028 135.792 131.93 + vertex 635.96 132.117 131.604 + endloop + endfacet + facet normal 0.50436 -0.851381 0.144125 + outer loop + vertex 636.332 129.867 115.83 + vertex 642.193 134.726 124.023 + vertex 636.124 131.071 123.671 + endloop + endfacet + facet normal 0.498476 -0.851176 0.16438 + outer loop + vertex 636.576 128.506 108.037 + vertex 642.407 133.499 116.212 + vertex 636.332 129.867 115.83 + endloop + endfacet + facet normal 0.491695 -0.851288 0.183151 + outer loop + vertex 636.841 126.984 100.254 + vertex 642.664 132.113 108.46 + vertex 636.576 128.506 108.037 + endloop + endfacet + facet normal 0.484001 -0.851636 0.201145 + outer loop + vertex 637.144 125.316 92.4612 + vertex 642.945 130.564 100.722 + vertex 636.841 126.984 100.254 + endloop + endfacet + facet normal 0.474932 -0.851987 0.22036 + outer loop + vertex 637.608 123.55 84.6323 + vertex 643.279 128.865 92.9595 + vertex 637.144 125.316 92.4612 + endloop + endfacet + facet normal 0.431387 -0.868963 0.242503 + outer loop + vertex 638.458 121.767 76.7317 + vertex 637.608 123.55 84.6323 + vertex 631.947 118.365 76.1232 + endloop + endfacet + facet normal 0.428248 -0.865848 0.258672 + outer loop + vertex 633.448 116.707 68.0915 + vertex 638.458 121.767 76.7317 + vertex 631.947 118.365 76.1232 + endloop + endfacet + facet normal 0.395032 -0.876446 0.275303 + outer loop + vertex 635.593 115.134 60.0056 + vertex 633.448 116.707 68.0915 + vertex 629.015 111.915 59.1951 + endloop + endfacet + facet normal 0.382417 -0.878282 0.287014 + outer loop + vertex 628.713 109.749 52.9709 + vertex 632.042 111.602 54.2041 + vertex 629.015 111.915 59.1951 + endloop + endfacet + facet normal 0.376961 -0.876578 0.299185 + outer loop + vertex 630.346 109.267 49.5013 + vertex 632.042 111.602 54.2041 + vertex 628.713 109.749 52.9709 + endloop + endfacet + facet normal 0.369233 -0.87663 0.308522 + outer loop + vertex 631.92 108.759 46.174 + vertex 630.346 109.267 49.5013 + vertex 628.678 107.2 45.6234 + endloop + endfacet + facet normal 0.361623 -0.875943 0.3193 + outer loop + vertex 630.273 106.921 43.0517 + vertex 628.678 107.2 45.6234 + vertex 626.925 105.306 42.4128 + endloop + endfacet + facet normal 0.360265 -0.880339 0.308565 + outer loop + vertex 625.353 105.643 45.0902 + vertex 627.024 107.698 49.0039 + vertex 623.662 106.149 48.5078 + endloop + endfacet + facet normal 0.346578 -0.890441 0.294955 + outer loop + vertex 617.074 103.226 47.6121 + vertex 618.521 105.366 52.371 + vertex 615.214 103.673 51.1447 + endloop + endfacet + facet normal 0.356936 -0.886463 0.294585 + outer loop + vertex 623.662 106.149 48.5078 + vertex 621.909 106.612 52.0265 + vertex 620.321 104.656 48.0636 + endloop + endfacet + facet normal 0.366892 -0.886269 0.282697 + outer loop + vertex 621.909 106.612 52.0265 + vertex 625.336 108.43 53.2772 + vertex 622.198 108.744 58.3344 + endloop + endfacet + facet normal 0.353661 -0.892772 0.279076 + outer loop + vertex 615.214 103.673 51.1447 + vertex 618.521 105.366 52.371 + vertex 615.511 105.801 57.5784 + endloop + endfacet + facet normal 0.379951 -0.885294 0.268127 + outer loop + vertex 622.198 108.744 58.3344 + vertex 626.733 113.422 67.3549 + vertex 619.907 110.259 66.5854 + endloop + endfacet + facet normal 0.383417 -0.888703 0.251393 + outer loop + vertex 626.733 113.422 67.3549 + vertex 625.192 115.038 75.4174 + vertex 619.907 110.259 66.5854 + endloop + endfacet + facet normal 0.414317 -0.879858 0.232792 + outer loop + vertex 625.192 115.038 75.4174 + vertex 631.095 120.099 84.0414 + vertex 624.312 116.728 83.3697 + endloop + endfacet + facet normal 0.422378 -0.881016 0.213089 + outer loop + vertex 624.312 116.728 83.3697 + vertex 630.642 121.825 91.8994 + vertex 623.848 118.418 91.2761 + endloop + endfacet + facet normal 0.429334 -0.881722 0.195547 + outer loop + vertex 623.848 118.418 91.2761 + vertex 630.349 123.46 99.7429 + vertex 623.54 120.02 99.1774 + endloop + endfacet + facet normal 0.435616 -0.88223 0.178629 + outer loop + vertex 623.54 120.02 99.1774 + vertex 630.088 124.954 107.577 + vertex 623.275 121.485 107.06 + endloop + endfacet + facet normal 0.441503 -0.882779 0.160547 + outer loop + vertex 623.275 121.485 107.06 + vertex 629.847 126.289 115.406 + vertex 623.039 122.797 114.922 + endloop + endfacet + facet normal 0.447069 -0.883375 0.140635 + outer loop + vertex 623.039 122.797 114.922 + vertex 629.648 127.471 123.274 + vertex 622.845 123.955 122.813 + endloop + endfacet + facet normal 0.451756 -0.883985 0.120363 + outer loop + vertex 622.845 123.955 122.813 + vertex 629.492 128.498 131.231 + vertex 622.695 124.965 130.798 + endloop + endfacet + facet normal 0.455554 -0.884591 0.0998427 + outer loop + vertex 622.695 124.965 130.798 + vertex 629.369 129.36 139.287 + vertex 622.573 125.815 138.881 + endloop + endfacet + facet normal 0.458478 -0.885181 0.0790795 + outer loop + vertex 622.573 125.815 138.881 + vertex 629.272 130.046 147.399 + vertex 622.477 126.492 147.015 + endloop + endfacet + facet normal 0.460506 -0.885756 0.0580559 + outer loop + vertex 622.477 126.492 147.015 + vertex 629.203 130.545 155.507 + vertex 622.408 126.989 155.141 + endloop + endfacet + facet normal 0.461689 -0.886286 0.0366053 + outer loop + vertex 622.408 126.989 155.141 + vertex 629.161 130.855 163.578 + vertex 622.366 127.301 163.229 + endloop + endfacet + facet normal 0.462034 -0.886738 0.0148399 + outer loop + vertex 622.366 127.301 163.229 + vertex 629.146 130.974 171.613 + vertex 622.348 127.426 171.283 + endloop + endfacet + facet normal 0.461665 -0.887025 -0.00725393 + outer loop + vertex 622.348 127.426 171.283 + vertex 629.155 130.901 179.64 + vertex 622.356 127.364 179.334 + endloop + endfacet + facet normal 0.460355 -0.887247 -0.0294459 + outer loop + vertex 622.356 127.364 179.334 + vertex 629.197 130.637 187.692 + vertex 622.389 127.113 187.415 + endloop + endfacet + facet normal 0.458283 -0.887287 -0.0519403 + outer loop + vertex 622.389 127.113 187.415 + vertex 629.264 130.175 195.774 + vertex 622.454 126.672 195.534 + endloop + endfacet + facet normal 0.455325 -0.887176 -0.074819 + outer loop + vertex 622.454 126.672 195.534 + vertex 629.358 129.512 203.868 + vertex 622.548 126.034 203.666 + endloop + endfacet + facet normal 0.45156 -0.886827 -0.0981367 + outer loop + vertex 622.548 126.034 203.666 + vertex 629.489 128.653 211.943 + vertex 622.672 125.201 211.77 + endloop + endfacet + facet normal 0.447027 -0.88629 -0.121067 + outer loop + vertex 622.672 125.201 211.77 + vertex 629.646 127.6 219.956 + vertex 622.828 124.181 219.814 + endloop + endfacet + facet normal 0.418566 -0.89741 -0.139493 + outer loop + vertex 615.971 120.97 219.637 + vertex 623.016 122.99 227.777 + vertex 616.158 119.816 227.618 + endloop + endfacet + facet normal 0.445879 -0.882914 -0.147156 + outer loop + vertex 629.646 127.6 219.956 + vertex 629.841 126.376 227.891 + vertex 622.828 124.181 219.814 + endloop + endfacet + facet normal 0.435586 -0.885376 -0.162401 + outer loop + vertex 623.016 122.99 227.777 + vertex 630.075 125.004 235.733 + vertex 623.249 121.659 235.659 + endloop + endfacet + facet normal 0.467105 -0.86747 -0.171197 + outer loop + vertex 636.335 129.867 227.921 + vertex 636.582 128.461 235.72 + vertex 629.841 126.376 227.891 + endloop + endfacet + facet normal 0.454703 -0.871352 -0.184368 + outer loop + vertex 630.075 125.004 235.733 + vertex 636.896 126.936 243.422 + vertex 630.386 123.526 243.486 + endloop + endfacet + facet normal 0.490132 -0.849639 -0.194639 + outer loop + vertex 642.686 131.994 235.666 + vertex 643.023 130.433 243.327 + vertex 636.582 128.461 235.72 + endloop + endfacet + facet normal 0.474744 -0.855501 -0.206727 + outer loop + vertex 636.896 126.936 243.422 + vertex 643.495 128.79 250.905 + vertex 637.345 125.347 251.029 + endloop + endfacet + facet normal 0.515079 -0.828424 -0.220017 + outer loop + vertex 648.773 134.031 243.241 + vertex 649.285 132.341 250.802 + vertex 643.023 130.433 243.327 + endloop + endfacet + facet normal 0.495871 -0.836701 -0.232471 + outer loop + vertex 643.495 128.79 250.905 + vertex 650.017 130.606 258.282 + vertex 644.192 127.123 258.393 + endloop + endfacet + facet normal 0.543075 -0.801631 -0.249913 + outer loop + vertex 654.708 136.044 250.711 + vertex 655.48 134.237 258.184 + vertex 649.285 132.341 250.802 + endloop + endfacet + facet normal 0.519298 -0.812693 -0.264309 + outer loop + vertex 650.017 130.606 258.282 + vertex 656.545 132.423 265.522 + vertex 651.052 128.87 265.654 + endloop + endfacet + facet normal 0.57204 -0.768806 -0.285845 + outer loop + vertex 660.544 138.041 258.088 + vertex 661.604 136.126 265.359 + vertex 655.48 134.237 258.184 + endloop + endfacet + facet normal 0.588745 -0.744721 -0.314276 + outer loop + vertex 661.604 136.126 265.359 + vertex 667.45 137.946 271.999 + vertex 662.989 134.271 272.349 + endloop + endfacet + facet normal 0.568946 -0.746095 -0.345894 + outer loop + vertex 662.989 134.271 272.349 + vertex 669.13 136.192 278.306 + vertex 664.718 132.46 279.1 + endloop + endfacet + facet normal 0.5768 -0.73437 -0.357775 + outer loop + vertex 667.45 137.946 271.999 + vertex 669.13 136.192 278.306 + vertex 662.989 134.271 272.349 + endloop + endfacet + facet normal 0.610581 -0.705973 -0.358878 + outer loop + vertex 667.45 137.946 271.999 + vertex 672.648 139.582 277.623 + vertex 669.13 136.192 278.306 + endloop + endfacet + facet normal 0.618255 -0.693684 -0.369545 + outer loop + vertex 671.38 141.452 271.992 + vertex 672.648 139.582 277.623 + vertex 667.45 137.946 271.999 + endloop + endfacet + facet normal 0.641791 -0.672855 -0.367927 + outer loop + vertex 672.648 139.582 277.623 + vertex 671.38 141.452 271.992 + vertex 675.651 142.408 277.695 + endloop + endfacet + facet normal 0.62788 -0.656822 -0.417554 + outer loop + vertex 675.651 142.408 277.695 + vertex 676.951 140.914 281.999 + vertex 672.648 139.582 277.623 + endloop + endfacet + facet normal 0.619851 -0.672133 -0.404997 + outer loop + vertex 672.648 139.582 277.623 + vertex 676.951 140.914 281.999 + vertex 674.418 138.172 282.672 + endloop + endfacet + facet normal 0.593401 -0.696953 -0.402656 + outer loop + vertex 672.648 139.582 277.623 + vertex 674.418 138.172 282.672 + vertex 669.13 136.192 278.306 + endloop + endfacet + facet normal 0.591949 -0.699982 -0.399525 + outer loop + vertex 671.764 134.714 284.8 + vertex 669.13 136.192 278.306 + vertex 674.418 138.172 282.672 + endloop + endfacet + facet normal 0.56618 -0.701102 -0.43347 + outer loop + vertex 676.577 137.53 286.531 + vertex 671.764 134.714 284.8 + vertex 674.418 138.172 282.672 + endloop + endfacet + facet normal 0.565737 -0.680933 -0.46505 + outer loop + vertex 676.577 137.53 286.531 + vertex 677.147 136.019 289.437 + vertex 671.764 134.714 284.8 + endloop + endfacet + facet normal 0.543536 -0.722283 -0.427639 + outer loop + vertex 673.039 132.401 290.325 + vertex 671.764 134.714 284.8 + vertex 677.147 136.019 289.437 + endloop + endfacet + facet normal 0.523259 -0.736392 -0.428867 + outer loop + vertex 671.764 134.714 284.8 + vertex 673.039 132.401 290.325 + vertex 666.228 130.463 285.345 + endloop + endfacet + facet normal 0.503592 -0.771822 -0.388183 + outer loop + vertex 666.228 130.463 285.345 + vertex 673.039 132.401 290.325 + vertex 666.647 128.237 290.313 + endloop + endfacet + facet normal 0.4842 -0.782553 -0.391358 + outer loop + vertex 666.228 130.463 285.345 + vertex 666.647 128.237 290.313 + vertex 660.453 126.712 285.7 + endloop + endfacet + facet normal 0.463795 -0.812049 -0.354217 + outer loop + vertex 660.453 126.712 285.7 + vertex 666.647 128.237 290.313 + vertex 660.608 124.675 290.572 + endloop + endfacet + facet normal 0.451806 -0.79535 -0.404092 + outer loop + vertex 660.608 124.675 290.572 + vertex 666.647 128.237 290.313 + vertex 665.849 126.126 293.576 + endloop + endfacet + facet normal 0.467837 -0.789831 -0.396605 + outer loop + vertex 671.832 129.704 293.507 + vertex 665.849 126.126 293.576 + vertex 666.647 128.237 290.313 + endloop + endfacet + facet normal 0.447785 -0.757813 -0.474561 + outer loop + vertex 671.832 129.704 293.507 + vertex 670.231 127.595 295.365 + vertex 665.849 126.126 293.576 + endloop + endfacet + facet normal 0.468219 -0.756906 -0.455921 + outer loop + vertex 671.832 129.704 293.507 + vertex 676.062 131.201 295.366 + vertex 670.231 127.595 295.365 + endloop + endfacet + facet normal 0.478287 -0.710438 -0.516255 + outer loop + vertex 677.565 133.28 293.898 + vertex 676.062 131.201 295.366 + vertex 671.832 129.704 293.507 + endloop + endfacet + facet normal 0.495672 -0.746164 -0.444465 + outer loop + vertex 677.565 133.28 293.898 + vertex 671.832 129.704 293.507 + vertex 673.039 132.401 290.325 + endloop + endfacet + facet normal 0.491881 -0.710786 -0.502828 + outer loop + vertex 677.565 133.28 293.898 + vertex 681.573 134.811 295.655 + vertex 676.062 131.201 295.366 + endloop + endfacet + facet normal 0.488355 -0.74826 -0.449017 + outer loop + vertex 666.647 128.237 290.313 + vertex 673.039 132.401 290.325 + vertex 671.832 129.704 293.507 + endloop + endfacet + facet normal 0.562365 -0.683324 -0.465633 + outer loop + vertex 676.577 137.53 286.531 + vertex 680.26 138.749 289.19 + vertex 677.147 136.019 289.437 + endloop + endfacet + facet normal 0.569557 -0.664011 -0.484452 + outer loop + vertex 678.656 139.804 285.859 + vertex 680.26 138.749 289.19 + vertex 676.577 137.53 286.531 + endloop + endfacet + facet normal 0.592351 -0.6727 -0.44339 + outer loop + vertex 674.418 138.172 282.672 + vertex 678.656 139.804 285.859 + vertex 676.577 137.53 286.531 + endloop + endfacet + facet normal 0.581458 -0.65215 -0.486422 + outer loop + vertex 678.656 139.804 285.859 + vertex 682.415 140.935 288.835 + vertex 680.26 138.749 289.19 + endloop + endfacet + facet normal 0.590085 -0.629007 -0.506112 + outer loop + vertex 680.591 141.888 285.525 + vertex 682.415 140.935 288.835 + vertex 678.656 139.804 285.859 + endloop + endfacet + facet normal 0.602518 -0.614826 -0.508882 + outer loop + vertex 680.591 141.888 285.525 + vertex 683.951 142.529 288.728 + vertex 682.415 140.935 288.835 + endloop + endfacet + facet normal 0.61471 -0.586559 -0.527333 + outer loop + vertex 682.023 143.391 285.521 + vertex 683.951 142.529 288.728 + vertex 680.591 141.888 285.525 + endloop + endfacet + facet normal 0.628269 -0.568865 -0.530727 + outer loop + vertex 682.023 143.391 285.521 + vertex 684.898 143.508 288.801 + vertex 683.951 142.529 288.728 + endloop + endfacet + facet normal 0.637512 -0.550017 -0.5395 + outer loop + vertex 682.916 144.337 285.613 + vertex 684.898 143.508 288.801 + vertex 682.023 143.391 285.521 + endloop + endfacet + facet normal 0.661326 -0.515132 -0.54524 + outer loop + vertex 682.916 144.337 285.613 + vertex 685.303 144.015 288.811 + vertex 684.898 143.508 288.801 + endloop + endfacet + facet normal 0.66013 -0.517368 -0.544572 + outer loop + vertex 683.314 144.869 285.59 + vertex 685.303 144.015 288.811 + vertex 682.916 144.337 285.613 + endloop + endfacet + facet normal 0.685954 -0.534577 -0.493654 + outer loop + vertex 681.228 145.338 282.183 + vertex 683.314 144.869 285.59 + vertex 682.916 144.337 285.613 + endloop + endfacet + facet normal 0.663486 -0.564299 -0.491278 + outer loop + vertex 681.228 145.338 282.183 + vertex 682.916 144.337 285.613 + vertex 680.391 144.414 282.114 + endloop + endfacet + facet normal 0.683619 -0.5868 -0.433971 + outer loop + vertex 678.777 145.501 278.102 + vertex 681.228 145.338 282.183 + vertex 680.391 144.414 282.114 + endloop + endfacet + facet normal 0.663453 -0.610674 -0.432328 + outer loop + vertex 678.777 145.501 278.102 + vertex 680.391 144.414 282.114 + vertex 677.921 144.143 278.707 + endloop + endfacet + facet normal 0.665005 -0.608034 -0.433663 + outer loop + vertex 677.921 144.143 278.707 + vertex 680.391 144.414 282.114 + vertex 679.012 142.984 282.004 + endloop + endfacet + facet normal 0.661254 -0.612002 -0.433816 + outer loop + vertex 677.921 144.143 278.707 + vertex 679.012 142.984 282.004 + vertex 675.651 142.408 277.695 + endloop + endfacet + facet normal 0.662711 -0.64453 -0.381306 + outer loop + vertex 677.921 144.143 278.707 + vertex 675.651 142.408 277.695 + vertex 675.133 144.624 273.048 + endloop + endfacet + facet normal 0.689707 -0.609064 -0.391593 + outer loop + vertex 677.921 144.143 278.707 + vertex 675.133 144.624 273.048 + vertex 678.777 145.501 278.102 + endloop + endfacet + facet normal 0.685315 -0.61686 -0.387074 + outer loop + vertex 675.133 144.624 273.048 + vertex 677.315 147.064 273.022 + vertex 678.777 145.501 278.102 + endloop + endfacet + facet normal 0.695096 -0.60613 -0.386586 + outer loop + vertex 679.87 146.31 278.798 + vertex 678.777 145.501 278.102 + vertex 677.315 147.064 273.022 + endloop + endfacet + facet normal 0.725045 -0.564583 -0.394405 + outer loop + vertex 679.87 146.31 278.798 + vertex 677.315 147.064 273.022 + vertex 679.801 146.89 277.841 + endloop + endfacet + facet normal 0.706188 -0.593724 -0.385734 + outer loop + vertex 677.315 147.064 273.022 + vertex 677.81 148.456 271.786 + vertex 679.801 146.89 277.841 + endloop + endfacet + facet normal 0.728476 -0.566043 -0.385899 + outer loop + vertex 680.089 146.858 278.433 + vertex 679.801 146.89 277.841 + vertex 677.81 148.456 271.786 + endloop + endfacet + facet normal 0.647357 -0.586962 -0.486214 + outer loop + vertex 680.391 144.414 282.114 + vertex 682.023 143.391 285.521 + vertex 679.012 142.984 282.004 + endloop + endfacet + facet normal 0.636813 -0.607469 -0.474816 + outer loop + vertex 679.012 142.984 282.004 + vertex 682.023 143.391 285.521 + vertex 680.591 141.888 285.525 + endloop + endfacet + facet normal 0.624781 -0.620791 -0.473569 + outer loop + vertex 679.012 142.984 282.004 + vertex 680.591 141.888 285.525 + vertex 676.951 140.914 281.999 + endloop + endfacet + facet normal 0.614339 -0.643584 -0.456495 + outer loop + vertex 676.951 140.914 281.999 + vertex 680.591 141.888 285.525 + vertex 678.656 139.804 285.859 + endloop + endfacet + facet normal 0.698407 -0.562983 -0.441902 + outer loop + vertex 679.87 146.31 278.798 + vertex 681.228 145.338 282.183 + vertex 678.777 145.501 278.102 + endloop + endfacet + facet normal 0.698455 -0.562922 -0.441904 + outer loop + vertex 679.87 146.31 278.798 + vertex 681.586 145.853 282.093 + vertex 681.228 145.338 282.183 + endloop + endfacet + facet normal 0.65229 -0.626479 -0.426663 + outer loop + vertex 679.801 146.89 277.841 + vertex 681.586 145.853 282.093 + vertex 679.87 146.31 278.798 + endloop + endfacet + facet normal 0.779151 -0.449577 -0.436812 + outer loop + vertex 679.801 146.89 277.841 + vertex 681.542 146.012 281.85 + vertex 681.586 145.853 282.093 + endloop + endfacet + facet normal 0.679296 -0.550932 -0.4848 + outer loop + vertex 681.542 146.012 281.85 + vertex 683.209 145.114 285.206 + vertex 681.586 145.853 282.093 + endloop + endfacet + facet normal 0.741408 -0.454002 -0.494162 + outer loop + vertex 681.586 145.853 282.093 + vertex 683.209 145.114 285.206 + vertex 683.314 144.869 285.59 + endloop + endfacet + facet normal 0.638155 -0.556992 -0.531525 + outer loop + vertex 683.209 145.114 285.206 + vertex 685.173 144.248 288.473 + vertex 683.314 144.869 285.59 + endloop + endfacet + facet normal -0.697042 0.467913 0.543314 + outer loop + vertex 683.209 145.114 285.206 + vertex 684.479 144.482 287.38 + vertex 685.173 144.248 288.473 + endloop + endfacet + facet normal -0.868775 -0.0517826 0.492492 + outer loop + vertex 682.761 145.27 284.433 + vertex 684.479 144.482 287.38 + vertex 683.209 145.114 285.206 + endloop + endfacet + facet normal -0.558735 0.688863 0.461825 + outer loop + vertex 681.542 146.012 281.85 + vertex 682.761 145.27 284.433 + vertex 683.209 145.114 285.206 + endloop + endfacet + facet normal -0.690788 0.539635 0.481255 + outer loop + vertex 681.458 145.921 281.832 + vertex 682.761 145.27 284.433 + vertex 681.542 146.012 281.85 + endloop + endfacet + facet normal -0.703396 0.560126 0.437599 + outer loop + vertex 680.089 146.858 278.433 + vertex 681.458 145.921 281.832 + vertex 681.542 146.012 281.85 + endloop + endfacet + facet normal -0.398527 0.830419 0.389334 + outer loop + vertex 680.443 146.495 279.568 + vertex 681.458 145.921 281.832 + vertex 680.089 146.858 278.433 + endloop + endfacet + facet normal -0.559886 0.722789 0.405098 + outer loop + vertex 680.443 146.495 279.568 + vertex 680.089 146.858 278.433 + vertex 679.443 147.393 276.585 + endloop + endfacet + facet normal 0.857132 -0.278602 -0.433251 + outer loop + vertex 680.089 146.858 278.433 + vertex 681.542 146.012 281.85 + vertex 679.801 146.89 277.841 + endloop + endfacet + facet normal 0.657806 -0.574225 -0.487397 + outer loop + vertex 680.391 144.414 282.114 + vertex 682.916 144.337 285.613 + vertex 682.023 143.391 285.521 + endloop + endfacet + facet normal 0.673855 -0.553969 -0.488915 + outer loop + vertex 681.586 145.853 282.093 + vertex 683.314 144.869 285.59 + vertex 681.228 145.338 282.183 + endloop + endfacet + facet normal 0.726401 -0.404558 -0.555585 + outer loop + vertex 683.314 144.869 285.59 + vertex 685.173 144.248 288.473 + vertex 685.303 144.015 288.811 + endloop + endfacet + facet normal 0.596188 -0.662257 -0.453845 + outer loop + vertex 676.951 140.914 281.999 + vertex 678.656 139.804 285.859 + vertex 674.418 138.172 282.672 + endloop + endfacet + facet normal 0.644656 -0.640706 -0.41703 + outer loop + vertex 675.651 142.408 277.695 + vertex 679.012 142.984 282.004 + vertex 676.951 140.914 281.999 + endloop + endfacet + facet normal 0.656767 -0.649565 -0.383044 + outer loop + vertex 671.38 141.452 271.992 + vertex 675.133 144.624 273.048 + vertex 675.651 142.408 277.695 + endloop + endfacet + facet normal 0.512655 -0.803814 -0.301774 + outer loop + vertex 656.545 132.423 265.522 + vertex 657.924 130.618 272.674 + vertex 651.052 128.87 265.654 + endloop + endfacet + facet normal 0.491216 -0.829931 -0.264427 + outer loop + vertex 650.017 130.606 258.282 + vertex 651.052 128.87 265.654 + vertex 644.192 127.123 258.393 + endloop + endfacet + facet normal 0.471411 -0.850504 -0.23327 + outer loop + vertex 643.495 128.79 250.905 + vertex 644.192 127.123 258.393 + vertex 637.345 125.347 251.029 + endloop + endfacet + facet normal 0.452341 -0.867283 -0.207865 + outer loop + vertex 636.896 126.936 243.422 + vertex 637.345 125.347 251.029 + vertex 630.386 123.526 243.486 + endloop + endfacet + facet normal 0.433991 -0.881614 -0.185495 + outer loop + vertex 630.075 125.004 235.733 + vertex 630.386 123.526 243.486 + vertex 623.249 121.659 235.659 + endloop + endfacet + facet normal 0.417488 -0.893888 -0.163303 + outer loop + vertex 623.016 122.99 227.777 + vertex 623.249 121.659 235.659 + vertex 616.158 119.816 227.618 + endloop + endfacet + facet normal 0.403295 -0.904277 -0.140129 + outer loop + vertex 615.971 120.97 219.637 + vertex 616.158 119.816 227.618 + vertex 609.637 118.149 219.611 + endloop + endfacet + facet normal 0.404498 -0.907202 -0.115613 + outer loop + vertex 609.483 119.112 211.513 + vertex 615.971 120.97 219.637 + vertex 609.637 118.149 219.611 + endloop + endfacet + facet normal 0.408819 -0.907805 -0.0935821 + outer loop + vertex 609.351 119.894 203.352 + vertex 615.814 121.957 211.572 + vertex 609.483 119.112 211.513 + endloop + endfacet + facet normal 0.412013 -0.908416 -0.07089 + outer loop + vertex 609.277 120.496 195.203 + vertex 615.697 122.765 203.447 + vertex 609.351 119.894 203.352 + endloop + endfacet + facet normal 0.414666 -0.908674 -0.0486178 + outer loop + vertex 609.223 120.908 187.063 + vertex 615.604 123.379 195.294 + vertex 609.277 120.496 195.203 + endloop + endfacet + facet normal 0.416544 -0.908717 -0.0269152 + outer loop + vertex 609.187 121.131 178.946 + vertex 615.546 123.803 187.148 + vertex 609.223 120.908 187.063 + endloop + endfacet + facet normal 0.417694 -0.908572 -0.00533336 + outer loop + vertex 609.179 121.175 170.867 + vertex 615.508 124.037 179.036 + vertex 609.187 121.131 178.946 + endloop + endfacet + facet normal 0.41813 -0.908243 0.0161582 + outer loop + vertex 609.187 121.035 162.762 + vertex 615.5 124.087 170.959 + vertex 609.179 121.175 170.867 + endloop + endfacet + facet normal 0.417771 -0.907777 0.0375293 + outer loop + vertex 609.243 120.723 154.596 + vertex 615.53 123.959 162.881 + vertex 609.187 121.035 162.762 + endloop + endfacet + facet normal 0.416924 -0.907086 0.0580412 + outer loop + vertex 609.328 120.238 146.416 + vertex 615.575 123.644 154.767 + vertex 609.243 120.723 154.596 + endloop + endfacet + facet normal 0.41521 -0.906357 0.0782174 + outer loop + vertex 609.426 119.581 138.275 + vertex 615.65 123.153 146.627 + vertex 609.328 120.238 146.416 + endloop + endfacet + facet normal 0.412633 -0.905583 0.0982546 + outer loop + vertex 609.551 118.759 130.174 + vertex 615.744 122.482 138.483 + vertex 609.426 119.581 138.275 + endloop + endfacet + facet normal 0.409627 -0.90464 0.117614 + outer loop + vertex 609.677 117.769 122.125 + vertex 615.858 121.641 130.376 + vertex 609.551 118.759 130.174 + endloop + endfacet + facet normal 0.405656 -0.903708 0.136952 + outer loop + vertex 609.853 116.644 114.174 + vertex 616.009 120.648 122.364 + vertex 609.677 117.769 122.125 + endloop + endfacet + facet normal 0.400851 -0.902744 0.156114 + outer loop + vertex 610.088 115.378 106.254 + vertex 616.197 119.507 114.444 + vertex 609.853 116.644 114.174 + endloop + endfacet + facet normal 0.395694 -0.901737 0.17406 + outer loop + vertex 610.369 113.962 98.2784 + vertex 616.432 118.22 106.552 + vertex 610.088 115.378 106.254 + endloop + endfacet + facet normal 0.39028 -0.900761 0.190556 + outer loop + vertex 610.711 112.418 90.2792 + vertex 616.707 116.781 98.6264 + vertex 610.369 113.962 98.2784 + endloop + endfacet + facet normal 0.384407 -0.899657 0.207001 + outer loop + vertex 611.187 110.789 82.3163 + vertex 617.03 115.208 90.6735 + vertex 610.711 112.418 90.2792 + endloop + endfacet + facet normal 0.377834 -0.89802 0.225394 + outer loop + vertex 612.013 109.128 74.3131 + vertex 617.5 113.546 82.7159 + vertex 611.187 110.789 82.3163 + endloop + endfacet + facet normal 0.371048 -0.895689 0.245082 + outer loop + vertex 613.402 107.447 66.066 + vertex 618.383 111.877 74.717 + vertex 612.013 109.128 74.3131 + endloop + endfacet + facet normal 0.350909 -0.899159 0.261488 + outer loop + vertex 615.511 105.801 57.5784 + vertex 613.402 107.447 66.066 + vertex 609.615 103.454 57.4202 + endloop + endfacet + facet normal 0.34466 -0.897018 0.27671 + outer loop + vertex 609.426 101.297 50.6611 + vertex 612.168 102.648 51.6266 + vertex 609.615 103.454 57.4202 + endloop + endfacet + facet normal 0.336488 -0.89404 0.29575 + outer loop + vertex 611.23 100.662 46.6895 + vertex 612.168 102.648 51.6266 + vertex 609.426 101.297 50.6611 + endloop + endfacet + facet normal 0.339805 -0.886592 0.313828 + outer loop + vertex 613.447 100.136 42.8017 + vertex 611.23 100.662 46.6895 + vertex 610.952 99.0289 42.3773 + endloop + endfacet + facet normal 0.338919 -0.880056 0.332618 + outer loop + vertex 611.694 98.2581 39.5821 + vertex 612.756 98.8746 40.1303 + vertex 610.952 99.0289 42.3773 + endloop + endfacet + facet normal 0.332885 -0.875853 0.349382 + outer loop + vertex 612.696 98.1529 38.3632 + vertex 611.694 98.2581 39.5821 + vertex 611.684 97.6739 38.1269 + endloop + endfacet + facet normal 0.333207 -0.871939 0.358742 + outer loop + vertex 613.59 98.1561 37.5408 + vertex 613.881 98.6953 38.5808 + vertex 612.696 98.1529 38.3632 + endloop + endfacet + facet normal 0.339134 -0.874984 0.34553 + outer loop + vertex 615.278 99.3247 38.8036 + vertex 614.167 99.3782 40.029 + vertex 613.881 98.6953 38.5808 + endloop + endfacet + facet normal 0.337552 -0.872737 0.352688 + outer loop + vertex 616.195 99.334 37.9491 + vertex 616.957 100.096 39.1045 + vertex 615.278 99.3247 38.8036 + endloop + endfacet + facet normal 0.342419 -0.877271 0.336371 + outer loop + vertex 618.915 100.949 39.336 + vertex 617.858 101.242 41.1768 + vertex 616.957 100.096 39.1045 + endloop + endfacet + facet normal 0.327875 -0.869979 0.368285 + outer loop + vertex 619.07 100.415 37.8717 + vertex 621.059 101.789 39.3458 + vertex 619.195 100.687 38.4022 + endloop + endfacet + facet normal 0.341855 -0.877595 0.336099 + outer loop + vertex 617.858 101.242 41.1768 + vertex 618.915 100.949 39.336 + vertex 620.443 102.364 41.4766 + endloop + endfacet + facet normal 0.34964 -0.880369 0.320473 + outer loop + vertex 623.485 103.708 41.8508 + vertex 622.077 104.155 44.615 + vertex 620.443 102.364 41.4766 + endloop + endfacet + facet normal 0.35197 -0.8748 0.332929 + outer loop + vertex 624.859 103.481 39.8011 + vertex 626.925 105.306 42.4128 + vertex 623.485 103.708 41.8508 + endloop + endfacet + facet normal 0.358416 -0.872888 0.331065 + outer loop + vertex 623.04 102.239 38.4948 + vertex 626.22 103.761 39.0655 + vertex 624.859 103.481 39.8011 + endloop + endfacet + facet normal 0.364026 -0.87752 0.312161 + outer loop + vertex 626.22 103.761 39.0655 + vertex 623.04 102.239 38.4948 + vertex 623.269 102.152 37.986 + endloop + endfacet + facet normal 0.361379 -0.878948 0.311216 + outer loop + vertex 623.04 102.239 38.4948 + vertex 620.693 101.051 37.8676 + vertex 623.269 102.152 37.986 + endloop + endfacet + facet normal 0.343272 -0.871877 0.349278 + outer loop + vertex 621.565 101.641 38.4805 + vertex 621.059 101.789 39.3458 + vertex 619.07 100.415 37.8717 + endloop + endfacet + facet normal 0.363609 -0.88271 0.297677 + outer loop + vertex 620.693 101.051 37.8676 + vertex 618.058 99.7408 37.2 + vertex 623.269 102.152 37.986 + endloop + endfacet + facet normal 0.335973 -0.86762 0.366548 + outer loop + vertex 616.218 99.044 37.2407 + vertex 619.07 100.415 37.8717 + vertex 617.744 99.9894 38.079 + endloop + endfacet + facet normal 0.330953 -0.862161 0.383599 + outer loop + vertex 618.058 99.7408 37.2 + vertex 614.542 98.094 36.5322 + vertex 616.693 98.9392 36.5755 + endloop + endfacet + facet normal 0.335561 -0.868571 0.36467 + outer loop + vertex 613.951 98.0227 36.8941 + vertex 616.218 99.044 37.2407 + vertex 614.831 98.6718 37.6303 + endloop + endfacet + facet normal 0.331516 -0.870004 0.364953 + outer loop + vertex 612.287 97.2188 36.4888 + vertex 613.951 98.0227 36.8941 + vertex 612.64 97.6557 37.2093 + endloop + endfacet + facet normal 0.332695 -0.866061 0.373166 + outer loop + vertex 614.542 98.094 36.5322 + vertex 611.235 96.4954 35.7707 + vertex 616.693 98.9392 36.5755 + endloop + endfacet + facet normal 0.326132 -0.866684 0.377487 + outer loop + vertex 611.015 96.7598 36.5343 + vertex 612.287 97.2188 36.4888 + vertex 611.063 96.9458 36.9198 + endloop + endfacet + facet normal 0.319939 -0.87338 0.367215 + outer loop + vertex 611.235 96.4954 35.7707 + vertex 609.955 96.792 37.5907 + vertex 610.044 96.697 37.2871 + endloop + endfacet + facet normal 0.386041 -0.825028 0.412676 + outer loop + vertex 610.044 96.697 37.2871 + vertex 609.603 96.6963 37.6982 + vertex 611.235 96.4954 35.7707 + endloop + endfacet + facet normal 0.321016 -0.874815 0.362832 + outer loop + vertex 609.603 96.6963 37.6982 + vertex 608.686 96.3772 37.7405 + vertex 611.235 96.4954 35.7707 + endloop + endfacet + facet normal 0.314377 -0.880873 0.353878 + outer loop + vertex 607.859 95.6267 36.6067 + vertex 611.235 96.4954 35.7707 + vertex 608.686 96.3772 37.7405 + endloop + endfacet + facet normal 0.316747 -0.880749 0.352068 + outer loop + vertex 606.342 95.5926 37.8867 + vertex 607.859 95.6267 36.6067 + vertex 608.686 96.3772 37.7405 + endloop + endfacet + facet normal 0.317427 -0.88484 0.341026 + outer loop + vertex 608.686 96.3772 37.7405 + vertex 607.256 96.7761 40.1063 + vertex 606.342 95.5926 37.8867 + endloop + endfacet + facet normal 0.316119 -0.885056 0.34168 + outer loop + vertex 606.342 95.5926 37.8867 + vertex 607.256 96.7761 40.1063 + vertex 605.195 96.0608 40.16 + endloop + endfacet + facet normal 0.315111 -0.885571 0.341277 + outer loop + vertex 606.342 95.5926 37.8867 + vertex 605.195 96.0608 40.16 + vertex 602.86 94.3849 37.9676 + endloop + endfacet + facet normal 0.313463 -0.879733 0.357507 + outer loop + vertex 604.051 94.2915 36.6932 + vertex 606.342 95.5926 37.8867 + vertex 602.86 94.3849 37.9676 + endloop + endfacet + facet normal 0.312254 -0.880596 0.356439 + outer loop + vertex 604.051 94.2915 36.6932 + vertex 602.86 94.3849 37.9676 + vertex 599.113 92.7218 37.1412 + endloop + endfacet + facet normal 0.309681 -0.878476 0.363837 + outer loop + vertex 599.113 92.7218 37.1412 + vertex 602.86 94.3849 37.9676 + vertex 598.81 93.0826 38.2705 + endloop + endfacet + facet normal 0.310671 -0.886293 0.343464 + outer loop + vertex 602.86 94.3849 37.9676 + vertex 601.842 94.8665 40.1311 + vertex 598.81 93.0826 38.2705 + endloop + endfacet + facet normal 0.309279 -0.886006 0.345456 + outer loop + vertex 598.81 93.0826 38.2705 + vertex 601.842 94.8665 40.1311 + vertex 596.756 93.1332 40.2396 + endloop + endfacet + facet normal 0.307735 -0.887158 0.343875 + outer loop + vertex 598.81 93.0826 38.2705 + vertex 596.756 93.1332 40.2396 + vertex 592.693 90.8922 38.0932 + endloop + endfacet + facet normal 0.311199 -0.892894 0.325416 + outer loop + vertex 601.842 94.8665 40.1311 + vertex 600.727 95.6952 43.4713 + vertex 596.756 93.1332 40.2396 + endloop + endfacet + facet normal 0.310323 -0.892826 0.326439 + outer loop + vertex 596.756 93.1332 40.2396 + vertex 600.727 95.6952 43.4713 + vertex 595.199 93.8827 43.7695 + endloop + endfacet + facet normal 0.304644 -0.895485 0.324499 + outer loop + vertex 596.756 93.1332 40.2396 + vertex 595.199 93.8827 43.7695 + vertex 589.619 90.8935 40.759 + endloop + endfacet + facet normal 0.305797 -0.895764 0.322639 + outer loop + vertex 589.619 90.8935 40.759 + vertex 595.199 93.8827 43.7695 + vertex 587.924 91.7004 44.6059 + endloop + endfacet + facet normal 0.311429 -0.899473 0.306529 + outer loop + vertex 600.727 95.6952 43.4713 + vertex 599.511 96.7641 47.8438 + vertex 595.199 93.8827 43.7695 + endloop + endfacet + facet normal 0.312076 -0.899481 0.305849 + outer loop + vertex 595.199 93.8827 43.7695 + vertex 599.511 96.7641 47.8438 + vertex 593.644 94.9384 48.4606 + endloop + endfacet + facet normal 0.316961 -0.897202 0.307513 + outer loop + vertex 600.727 95.6952 43.4713 + vertex 603.212 98.0385 47.7474 + vertex 599.511 96.7641 47.8438 + endloop + endfacet + facet normal 0.318449 -0.902957 0.288546 + outer loop + vertex 603.212 98.0385 47.7474 + vertex 601.636 98.8654 52.0736 + vertex 599.511 96.7641 47.8438 + endloop + endfacet + facet normal 0.320315 -0.902645 0.287454 + outer loop + vertex 599.511 96.7641 47.8438 + vertex 601.636 98.8654 52.0736 + vertex 597.6 97.7514 53.0733 + endloop + endfacet + facet normal 0.321723 -0.901503 0.28946 + outer loop + vertex 603.212 98.0385 47.7474 + vertex 603.461 99.7599 52.8307 + vertex 601.636 98.8654 52.0736 + endloop + endfacet + facet normal 0.330906 -0.904098 0.270387 + outer loop + vertex 601.636 98.8654 52.0736 + vertex 603.461 99.7599 52.8307 + vertex 600.009 100.32 58.9278 + endloop + endfacet + facet normal 0.339948 -0.899318 0.275068 + outer loop + vertex 602.902 101.191 58.2022 + vertex 600.009 100.32 58.9278 + vertex 603.461 99.7599 52.8307 + endloop + endfacet + facet normal 0.342766 -0.898245 0.275076 + outer loop + vertex 604.584 99.8317 51.6663 + vertex 602.902 101.191 58.2022 + vertex 603.461 99.7599 52.8307 + endloop + endfacet + facet normal 0.36458 -0.88251 0.297083 + outer loop + vertex 605.046 98.6901 47.7084 + vertex 604.584 99.8317 51.6663 + vertex 603.461 99.7599 52.8307 + endloop + endfacet + facet normal 0.340939 -0.891923 0.297041 + outer loop + vertex 605.81 98.7485 47.0068 + vertex 604.584 99.8317 51.6663 + vertex 605.046 98.6901 47.7084 + endloop + endfacet + facet normal 0.356505 -0.879581 0.315026 + outer loop + vertex 606.132 97.6081 43.4578 + vertex 605.81 98.7485 47.0068 + vertex 605.046 98.6901 47.7084 + endloop + endfacet + facet normal 0.321074 -0.894924 0.309875 + outer loop + vertex 606.132 97.6081 43.4578 + vertex 605.046 98.6901 47.7084 + vertex 604.234 96.9439 43.507 + endloop + endfacet + facet normal 0.31961 -0.889502 0.32655 + outer loop + vertex 605.195 96.0608 40.16 + vertex 606.132 97.6081 43.4578 + vertex 604.234 96.9439 43.507 + endloop + endfacet + facet normal 0.314723 -0.891558 0.325689 + outer loop + vertex 605.195 96.0608 40.16 + vertex 604.234 96.9439 43.507 + vertex 601.842 94.8665 40.1311 + endloop + endfacet + facet normal 0.324173 -0.894128 0.308945 + outer loop + vertex 604.234 96.9439 43.507 + vertex 605.046 98.6901 47.7084 + vertex 603.212 98.0385 47.7474 + endloop + endfacet + facet normal 0.324612 -0.891512 0.315964 + outer loop + vertex 607.024 97.7719 43.0038 + vertex 605.81 98.7485 47.0068 + vertex 606.132 97.6081 43.4578 + endloop + endfacet + facet normal 0.330557 -0.884094 0.330318 + outer loop + vertex 607.256 96.7761 40.1063 + vertex 607.024 97.7719 43.0038 + vertex 606.132 97.6081 43.4578 + endloop + endfacet + facet normal 0.320656 -0.887582 0.330723 + outer loop + vertex 608.356 97.0361 39.7381 + vertex 607.024 97.7719 43.0038 + vertex 607.256 96.7761 40.1063 + endloop + endfacet + facet normal 0.372431 -0.861194 0.34589 + outer loop + vertex 608.356 97.0361 39.7381 + vertex 607.572 97.6206 42.037 + vertex 607.024 97.7719 43.0038 + endloop + endfacet + facet normal 0.320794 -0.890993 0.321282 + outer loop + vertex 607.572 97.6206 42.037 + vertex 606.131 98.5013 45.9188 + vertex 607.024 97.7719 43.0038 + endloop + endfacet + facet normal 0.321971 -0.885545 0.334882 + outer loop + vertex 609.037 96.9791 38.9326 + vertex 607.572 97.6206 42.037 + vertex 608.356 97.0361 39.7381 + endloop + endfacet + facet normal 0.353691 -0.863255 0.360129 + outer loop + vertex 609.603 96.6963 37.6982 + vertex 609.037 96.9791 38.9326 + vertex 608.356 97.0361 39.7381 + endloop + endfacet + facet normal 0.537993 -0.738501 0.406423 + outer loop + vertex 607.572 97.6206 42.037 + vertex 609.037 96.9791 38.9326 + vertex 608.34 97.3361 40.5032 + endloop + endfacet + facet normal 0.87887 0.45063 0.156588 + outer loop + vertex 607.024 97.7719 43.0038 + vertex 606.131 98.5013 45.9188 + vertex 605.81 98.7485 47.0068 + endloop + endfacet + facet normal 0.624773 -0.701217 0.343444 + outer loop + vertex 606.131 98.5013 45.9188 + vertex 605.098 99.3709 49.5735 + vertex 605.81 98.7485 47.0068 + endloop + endfacet + facet normal 0.568485 0.821648 -0.0414523 + outer loop + vertex 605.81 98.7485 47.0068 + vertex 605.098 99.3709 49.5735 + vertex 604.584 99.8317 51.6663 + endloop + endfacet + facet normal 0.438825 -0.848915 0.294578 + outer loop + vertex 604.584 99.8317 51.6663 + vertex 605.098 99.3709 49.5735 + vertex 604.291 100.336 53.5582 + endloop + endfacet + facet normal -0.373099 0.881574 -0.289178 + outer loop + vertex 605.166 99.1133 48.6998 + vertex 604.291 100.336 53.5582 + vertex 605.098 99.3709 49.5735 + endloop + endfacet + facet normal 0.336656 -0.907125 0.252561 + outer loop + vertex 602.902 101.191 58.2022 + vertex 600.884 102.934 67.1497 + vertex 600.009 100.32 58.9278 + endloop + endfacet + facet normal 0.325904 -0.900207 0.288816 + outer loop + vertex 605.046 98.6901 47.7084 + vertex 603.461 99.7599 52.8307 + vertex 603.212 98.0385 47.7474 + endloop + endfacet + facet normal 0.316394 -0.897275 0.307882 + outer loop + vertex 604.234 96.9439 43.507 + vertex 603.212 98.0385 47.7474 + vertex 600.727 95.6952 43.4713 + endloop + endfacet + facet normal 0.314188 -0.891599 0.326093 + outer loop + vertex 601.842 94.8665 40.1311 + vertex 604.234 96.9439 43.507 + vertex 600.727 95.6952 43.4713 + endloop + endfacet + facet normal 0.312388 -0.885449 0.344084 + outer loop + vertex 602.86 94.3849 37.9676 + vertex 605.195 96.0608 40.16 + vertex 601.842 94.8665 40.1311 + endloop + endfacet + facet normal 0.317453 -0.889969 0.327382 + outer loop + vertex 607.256 96.7761 40.1063 + vertex 606.132 97.6081 43.4578 + vertex 605.195 96.0608 40.16 + endloop + endfacet + facet normal 0.323696 -0.881324 0.344222 + outer loop + vertex 608.686 96.3772 37.7405 + vertex 608.356 97.0361 39.7381 + vertex 607.256 96.7761 40.1063 + endloop + endfacet + facet normal 0.316807 -0.880698 0.352141 + outer loop + vertex 607.859 95.6267 36.6067 + vertex 606.342 95.5926 37.8867 + vertex 604.051 94.2915 36.6932 + endloop + endfacet + facet normal 0.315962 -0.87777 0.360122 + outer loop + vertex 607.859 95.6267 36.6067 + vertex 604.051 94.2915 36.6932 + vertex 607.286 95.189 36.043 + endloop + endfacet + facet normal 0.316008 -0.877515 0.360702 + outer loop + vertex 602.747 93.5799 36.1049 + vertex 607.286 95.189 36.043 + vertex 604.051 94.2915 36.6932 + endloop + endfacet + facet normal 0.312373 -0.866129 0.390184 + outer loop + vertex 607.286 95.189 36.043 + vertex 602.747 93.5799 36.1049 + vertex 608.169 95.2632 35.501 + endloop + endfacet + facet normal 0.313239 -0.865116 0.391733 + outer loop + vertex 611.235 96.4954 35.7707 + vertex 607.286 95.189 36.043 + vertex 608.169 95.2632 35.501 + endloop + endfacet + facet normal 0.317263 -0.871324 0.374352 + outer loop + vertex 608.169 95.2632 35.501 + vertex 610.15 95.9257 35.3638 + vertex 611.235 96.4954 35.7707 + endloop + endfacet + facet normal 0.230106 -0.816368 0.529712 + outer loop + vertex 610.15 95.9257 35.3638 + vertex 609.22 95.2185 34.6778 + vertex 611.235 96.4954 35.7707 + endloop + endfacet + facet normal 0.311666 -0.840208 0.44375 + outer loop + vertex 608.169 95.2632 35.501 + vertex 609.22 95.2185 34.6778 + vertex 610.15 95.9257 35.3638 + endloop + endfacet + facet normal 0.309605 -0.842294 0.441232 + outer loop + vertex 604.251 93.4183 34.7277 + vertex 609.22 95.2185 34.6778 + vertex 608.169 95.2632 35.501 + endloop + endfacet + facet normal 0.303135 -0.823367 0.479767 + outer loop + vertex 604.251 93.4183 34.7277 + vertex 607.664 93.5097 32.7286 + vertex 609.22 95.2185 34.6778 + endloop + endfacet + facet normal 0.330572 -0.824653 0.458988 + outer loop + vertex 609.22 95.2185 34.6778 + vertex 607.664 93.5097 32.7286 + vertex 609.687 94.6868 33.3865 + endloop + endfacet + facet normal 0.289582 -0.843695 0.452019 + outer loop + vertex 609.687 94.6868 33.3865 + vertex 611.235 96.4954 35.7707 + vertex 609.22 95.2185 34.6778 + endloop + endfacet + facet normal 0.30623 -0.818997 0.48525 + outer loop + vertex 603.383 91.5683 32.1532 + vertex 607.664 93.5097 32.7286 + vertex 604.251 93.4183 34.7277 + endloop + endfacet + facet normal 0.29191 -0.820642 0.49126 + outer loop + vertex 603.383 91.5683 32.1532 + vertex 604.251 93.4183 34.7277 + vertex 596.141 90.3741 34.462 + endloop + endfacet + facet normal 0.294073 -0.813496 0.501742 + outer loop + vertex 596.141 90.3741 34.462 + vertex 596.406 88.3374 31.0043 + vertex 603.383 91.5683 32.1532 + endloop + endfacet + facet normal 0.281005 -0.796979 0.53466 + outer loop + vertex 603.773 89.7933 29.3028 + vertex 603.383 91.5683 32.1532 + vertex 596.406 88.3374 31.0043 + endloop + endfacet + facet normal 0.294088 -0.792796 0.533841 + outer loop + vertex 603.773 89.7933 29.3028 + vertex 606.531 91.0863 29.7032 + vertex 603.383 91.5683 32.1532 + endloop + endfacet + facet normal 0.290253 -0.796955 0.529732 + outer loop + vertex 603.383 91.5683 32.1532 + vertex 606.531 91.0863 29.7032 + vertex 607.664 93.5097 32.7286 + endloop + endfacet + facet normal 0.279849 -0.817662 0.503103 + outer loop + vertex 585.694 86.883 34.5991 + vertex 596.406 88.3374 31.0043 + vertex 596.141 90.3741 34.462 + endloop + endfacet + facet normal 0.277504 -0.824341 0.493411 + outer loop + vertex 584.323 84.6077 31.569 + vertex 596.406 88.3374 31.0043 + vertex 585.694 86.883 34.5991 + endloop + endfacet + facet normal 0.269182 -0.824683 0.497433 + outer loop + vertex 573.398 83.1895 35.1297 + vertex 584.323 84.6077 31.569 + vertex 585.694 86.883 34.5991 + endloop + endfacet + facet normal 0.266648 -0.831811 0.486816 + outer loop + vertex 571.923 80.9765 32.1562 + vertex 584.323 84.6077 31.569 + vertex 573.398 83.1895 35.1297 + endloop + endfacet + facet normal 0.253723 -0.831995 0.493364 + outer loop + vertex 560.668 79.646 35.7008 + vertex 571.923 80.9765 32.1562 + vertex 573.398 83.1895 35.1297 + endloop + endfacet + facet normal 0.251127 -0.839164 0.48243 + outer loop + vertex 559.509 77.5717 32.6957 + vertex 571.923 80.9765 32.1562 + vertex 560.668 79.646 35.7008 + endloop + endfacet + facet normal 0.233712 -0.839979 0.489708 + outer loop + vertex 547.817 76.3591 36.1959 + vertex 559.509 77.5717 32.6957 + vertex 560.668 79.646 35.7008 + endloop + endfacet + facet normal 0.232627 -0.842982 0.485042 + outer loop + vertex 546.945 74.3302 33.088 + vertex 559.509 77.5717 32.6957 + vertex 547.817 76.3591 36.1959 + endloop + endfacet + facet normal 0.212153 -0.844485 0.491768 + outer loop + vertex 535.052 73.3346 36.5087 + vertex 546.945 74.3302 33.088 + vertex 547.817 76.3591 36.1959 + endloop + endfacet + facet normal 0.216824 -0.869071 0.444637 + outer loop + vertex 535.052 73.3346 36.5087 + vertex 547.817 76.3591 36.1959 + vertex 535.746 74.5107 38.4691 + endloop + endfacet + facet normal 0.21332 -0.841263 0.496761 + outer loop + vertex 534.356 71.2697 33.311 + vertex 546.945 74.3302 33.088 + vertex 535.052 73.3346 36.5087 + endloop + endfacet + facet normal 0.19281 -0.842923 0.5023 + outer loop + vertex 523.195 70.6512 36.5572 + vertex 534.356 71.2697 33.311 + vertex 535.052 73.3346 36.5087 + endloop + endfacet + facet normal 0.197314 -0.863516 0.464121 + outer loop + vertex 523.195 70.6512 36.5572 + vertex 535.052 73.3346 36.5087 + vertex 523.628 71.8877 38.674 + endloop + endfacet + facet normal 0.19605 -0.834434 0.515058 + outer loop + vertex 522.487 68.4747 33.3006 + vertex 534.356 71.2697 33.311 + vertex 523.195 70.6512 36.5572 + endloop + endfacet + facet normal 0.176216 -0.835669 0.520197 + outer loop + vertex 513.347 68.3853 36.2533 + vertex 522.487 68.4747 33.3006 + vertex 523.195 70.6512 36.5572 + endloop + endfacet + facet normal 0.180905 -0.852142 0.491048 + outer loop + vertex 513.347 68.3853 36.2533 + vertex 523.195 70.6512 36.5572 + vertex 513.57 69.7847 38.5995 + endloop + endfacet + facet normal 0.181404 -0.824102 0.536609 + outer loop + vertex 512.623 66.0971 32.984 + vertex 522.487 68.4747 33.3006 + vertex 513.347 68.3853 36.2533 + endloop + endfacet + facet normal 0.160063 -0.825012 0.541973 + outer loop + vertex 506.082 66.3319 35.273 + vertex 512.623 66.0971 32.984 + vertex 513.347 68.3853 36.2533 + endloop + endfacet + facet normal 0.16597 -0.836491 0.522241 + outer loop + vertex 506.082 66.3319 35.273 + vertex 513.347 68.3853 36.2533 + vertex 505.895 68.0592 38.0992 + endloop + endfacet + facet normal 0.300383 -0.839807 0.452211 + outer loop + vertex 596.043 91.2647 36.1808 + vertex 596.141 90.3741 34.462 + vertex 604.251 93.4183 34.7277 + endloop + endfacet + facet normal 0.31068 -0.843383 0.438387 + outer loop + vertex 604.251 93.4183 34.7277 + vertex 608.169 95.2632 35.501 + vertex 602.747 93.5799 36.1049 + endloop + endfacet + facet normal 0.315282 -0.87774 0.36079 + outer loop + vertex 607.286 95.189 36.043 + vertex 611.235 96.4954 35.7707 + vertex 607.859 95.6267 36.6067 + endloop + endfacet + facet normal 0.322571 -0.881754 0.344177 + outer loop + vertex 609.603 96.6963 37.6982 + vertex 608.356 97.0361 39.7381 + vertex 608.686 96.3772 37.7405 + endloop + endfacet + facet normal 0.329541 -0.876076 0.351985 + outer loop + vertex 610.044 96.697 37.2871 + vertex 609.037 96.9791 38.9326 + vertex 609.603 96.6963 37.6982 + endloop + endfacet + facet normal 0.375947 -0.847177 0.375441 + outer loop + vertex 609.037 96.9791 38.9326 + vertex 610.044 96.697 37.2871 + vertex 609.955 96.792 37.5907 + endloop + endfacet + facet normal 0.321677 -0.882454 0.343218 + outer loop + vertex 609.955 96.792 37.5907 + vertex 608.34 97.3361 40.5032 + vertex 609.037 96.9791 38.9326 + endloop + endfacet + facet normal 0.330221 -0.865587 0.376449 + outer loop + vertex 610.337 96.7918 37.2026 + vertex 611.015 96.7598 36.5343 + vertex 611.063 96.9458 36.9198 + endloop + endfacet + facet normal 0.875416 0.0115304 0.483233 + outer loop + vertex 608.34 97.3361 40.5032 + vertex 609.955 96.792 37.5907 + vertex 609.387 97.0078 38.6142 + endloop + endfacet + facet normal 0.515686 -0.749004 0.416006 + outer loop + vertex 609.387 97.0078 38.6142 + vertex 608.541 97.3306 40.2442 + vertex 608.34 97.3361 40.5032 + endloop + endfacet + facet normal 0.427145 -0.834044 0.349168 + outer loop + vertex 608.541 97.3306 40.2442 + vertex 607.597 97.9861 42.965 + vertex 608.34 97.3361 40.5032 + endloop + endfacet + facet normal 0.325956 -0.873716 0.361072 + outer loop + vertex 611.063 96.9458 36.9198 + vertex 610.098 97.0366 38.0103 + vertex 610.337 96.7918 37.2026 + endloop + endfacet + facet normal 0.335314 -0.875695 0.347451 + outer loop + vertex 609.387 97.0078 38.6142 + vertex 609.035 97.4042 39.9537 + vertex 608.541 97.3306 40.2442 + endloop + endfacet + facet normal 0.325639 -0.878985 0.348344 + outer loop + vertex 610.836 97.2814 37.9377 + vertex 609.88 97.4782 39.3286 + vertex 610.098 97.0366 38.0103 + endloop + endfacet + facet normal 0.333473 -0.88223 0.332363 + outer loop + vertex 609.88 97.4782 39.3286 + vertex 610.617 97.9118 39.74 + vertex 608.986 98.2727 42.3345 + endloop + endfacet + facet normal 0.324793 -0.88762 0.326558 + outer loop + vertex 608.541 97.3306 40.2442 + vertex 609.035 97.4042 39.9537 + vertex 607.597 97.9861 42.965 + endloop + endfacet + facet normal 0.330489 -0.889792 0.314717 + outer loop + vertex 608.986 98.2727 42.3345 + vertex 608.84 99.7322 46.6139 + vertex 606.952 99.149 46.9474 + endloop + endfacet + facet normal 0.3193 -0.900791 0.294318 + outer loop + vertex 606.952 99.149 46.9474 + vertex 607.102 100.796 51.8246 + vertex 605.266 100.024 51.4549 + endloop + endfacet + facet normal 0.325643 -0.905397 0.272422 + outer loop + vertex 605.266 100.024 51.4549 + vertex 607.102 100.796 51.8246 + vertex 605.09 102.158 58.7561 + endloop + endfacet + facet normal 0.379217 -0.888859 0.257148 + outer loop + vertex 603.494 101.556 58.5911 + vertex 602.81 102.647 63.3681 + vertex 602.902 101.191 58.2022 + endloop + endfacet + facet normal 0.344516 -0.903718 0.25417 + outer loop + vertex 605.09 102.158 58.7561 + vertex 607.875 105.35 66.3323 + vertex 604.057 104.31 67.8118 + endloop + endfacet + facet normal 0.350862 -0.903202 0.247229 + outer loop + vertex 602.81 102.647 63.3681 + vertex 602.067 103.986 69.3153 + vertex 600.884 102.934 67.1497 + endloop + endfacet + facet normal 0.347348 -0.907475 0.236302 + outer loop + vertex 604.057 104.31 67.8118 + vertex 606.729 107.082 74.5261 + vertex 602.875 105.778 75.1857 + endloop + endfacet + facet normal 0.365278 -0.900012 0.237805 + outer loop + vertex 602.067 103.986 69.3153 + vertex 601.227 104.663 73.1688 + vertex 600.884 102.934 67.1497 + endloop + endfacet + facet normal 0.357838 -0.906081 0.225763 + outer loop + vertex 601.227 104.663 73.1688 + vertex 601.174 105.706 77.4391 + vertex 599.772 105.018 76.8984 + endloop + endfacet + facet normal 0.352507 -0.910107 0.217815 + outer loop + vertex 602.875 105.778 75.1857 + vertex 605.964 108.69 82.3513 + vertex 602.073 107.29 82.8003 + endloop + endfacet + facet normal 0.359734 -0.906433 0.221292 + outer loop + vertex 601.174 105.706 77.4391 + vertex 600.799 106.106 79.6853 + vertex 599.772 105.018 76.8984 + endloop + endfacet + facet normal 0.383937 -0.899262 0.209571 + outer loop + vertex 600.799 106.106 79.6853 + vertex 600.538 106.555 82.0885 + vertex 599.772 105.018 76.8984 + endloop + endfacet + facet normal 0.381978 -0.899979 0.210073 + outer loop + vertex 599.398 106.936 85.7976 + vertex 599.772 105.018 76.8984 + vertex 600.538 106.555 82.0885 + endloop + endfacet + facet normal 0.359777 -0.910393 0.204316 + outer loop + vertex 600.538 106.555 82.0885 + vertex 600.686 107.45 85.8167 + vertex 599.398 106.936 85.7976 + endloop + endfacet + facet normal 0.359077 -0.911586 0.200186 + outer loop + vertex 602.073 107.29 82.8003 + vertex 605.505 110.295 90.3258 + vertex 601.614 108.916 91.0274 + endloop + endfacet + facet normal 0.35998 -0.910816 0.202061 + outer loop + vertex 600.686 107.45 85.8167 + vertex 600.388 107.852 88.1604 + vertex 599.398 106.936 85.7976 + endloop + endfacet + facet normal 0.375879 -0.906216 0.193615 + outer loop + vertex 600.388 107.852 88.1604 + vertex 600.092 108.246 90.579 + vertex 599.398 106.936 85.7976 + endloop + endfacet + facet normal 0.379128 -0.905032 0.192819 + outer loop + vertex 598.882 108.517 94.2315 + vertex 599.398 106.936 85.7976 + vertex 600.092 108.246 90.579 + endloop + endfacet + facet normal 0.364894 -0.911747 0.188601 + outer loop + vertex 600.092 108.246 90.579 + vertex 600.2 109.044 94.2273 + vertex 598.882 108.517 94.2315 + endloop + endfacet + facet normal 0.364485 -0.912729 0.184599 + outer loop + vertex 601.614 108.916 91.0274 + vertex 605.12 111.811 98.4207 + vertex 601.214 110.436 99.3313 + endloop + endfacet + facet normal 0.36505 -0.912156 0.186304 + outer loop + vertex 600.2 109.044 94.2273 + vertex 599.888 109.408 96.6211 + vertex 598.882 108.517 94.2315 + endloop + endfacet + facet normal 0.382768 -0.906761 0.17684 + outer loop + vertex 599.888 109.408 96.6211 + vertex 599.624 109.778 99.0942 + vertex 598.882 108.517 94.2315 + endloop + endfacet + facet normal 0.392254 -0.903161 0.17446 + outer loop + vertex 598.52 110.052 102.99 + vertex 598.882 108.517 94.2315 + vertex 599.624 109.778 99.0942 + endloop + endfacet + facet normal 0.376105 -0.91077 0.170422 + outer loop + vertex 599.624 109.778 99.0942 + vertex 599.833 110.543 102.717 + vertex 598.52 110.052 102.99 + endloop + endfacet + facet normal 0.370085 -0.913794 0.167383 + outer loop + vertex 601.214 110.436 99.3313 + vertex 604.849 113.212 106.451 + vertex 601.119 111.858 107.308 + endloop + endfacet + facet normal 0.375701 -0.911558 0.167065 + outer loop + vertex 599.833 110.543 102.717 + vertex 599.595 110.94 105.42 + vertex 598.52 110.052 102.99 + endloop + endfacet + facet normal 0.398778 -0.904008 0.154095 + outer loop + vertex 599.595 110.94 105.42 + vertex 599.512 111.526 109.072 + vertex 598.52 110.052 102.99 + endloop + endfacet + facet normal 0.389673 -0.907569 0.156443 + outer loop + vertex 598.351 111.506 111.846 + vertex 598.52 110.052 102.99 + vertex 599.512 111.526 109.072 + endloop + endfacet + facet normal 0.373377 -0.915347 0.150764 + outer loop + vertex 601.119 111.858 107.308 + vertex 604.648 114.459 114.359 + vertex 600.748 112.96 114.913 + endloop + endfacet + facet normal 0.386191 -0.909307 0.154973 + outer loop + vertex 599.512 111.526 109.072 + vertex 599.397 112.049 112.428 + vertex 598.351 111.506 111.846 + endloop + endfacet + facet normal 0.391563 -0.908696 0.14474 + outer loop + vertex 599.397 112.049 112.428 + vertex 599.369 112.308 114.129 + vertex 598.351 111.506 111.846 + endloop + endfacet + facet normal 0.411786 -0.901494 0.133198 + outer loop + vertex 599.369 112.308 114.129 + vertex 599.336 112.796 117.531 + vertex 598.351 111.506 111.846 + endloop + endfacet + facet normal 0.394971 -0.908321 0.137659 + outer loop + vertex 598.036 112.665 120.402 + vertex 598.351 111.506 111.846 + vertex 599.336 112.796 117.531 + endloop + endfacet + facet normal 0.376909 -0.916721 0.132524 + outer loop + vertex 600.748 112.96 114.913 + vertex 604.481 115.568 122.34 + vertex 600.622 114.1 123.16 + endloop + endfacet + facet normal 0.391359 -0.910142 0.135942 + outer loop + vertex 599.336 112.796 117.531 + vertex 599.252 113.265 120.917 + vertex 598.036 112.665 120.402 + endloop + endfacet + facet normal 0.396122 -0.909754 0.124237 + outer loop + vertex 599.252 113.265 120.917 + vertex 599.228 113.489 122.634 + vertex 598.036 112.665 120.402 + endloop + endfacet + facet normal 0.412033 -0.904056 0.113629 + outer loop + vertex 599.228 113.489 122.634 + vertex 599.2 113.915 126.122 + vertex 598.036 112.665 120.402 + endloop + endfacet + facet normal 0.400257 -0.908893 0.117083 + outer loop + vertex 597.776 113.74 129.63 + vertex 598.036 112.665 120.402 + vertex 599.2 113.915 126.122 + endloop + endfacet + facet normal 0.380876 -0.917715 0.112841 + outer loop + vertex 600.622 114.1 123.16 + vertex 604.362 116.545 130.419 + vertex 600.719 115.139 131.28 + endloop + endfacet + facet normal 0.393017 -0.912441 0.113967 + outer loop + vertex 599.2 113.915 126.122 + vertex 599.156 114.37 129.918 + vertex 597.776 113.74 129.63 + endloop + endfacet + facet normal 0.396306 -0.912776 0.0988991 + outer loop + vertex 599.156 114.37 129.918 + vertex 599.262 114.748 132.984 + vertex 597.776 113.74 129.63 + endloop + endfacet + facet normal 0.382146 -0.919222 0.0948441 + outer loop + vertex 600.719 115.139 131.28 + vertex 604.246 117.345 138.457 + vertex 600.397 115.793 138.924 + endloop + endfacet + facet normal 0.39786 -0.912193 0.098035 + outer loop + vertex 599.262 114.748 132.984 + vertex 598.856 114.864 135.708 + vertex 597.776 113.74 129.63 + endloop + endfacet + facet normal 0.410313 -0.906997 0.0948626 + outer loop + vertex 597.795 114.704 138.77 + vertex 597.776 113.74 129.63 + vertex 598.856 114.864 135.708 + endloop + endfacet + facet normal 0.401453 -0.911291 0.0915677 + outer loop + vertex 598.856 114.864 135.708 + vertex 599 115.222 138.639 + vertex 597.795 114.704 138.77 + endloop + endfacet + facet normal 0.400588 -0.913057 0.0765227 + outer loop + vertex 599 115.222 138.639 + vertex 599.143 115.529 141.559 + vertex 597.795 114.704 138.77 + endloop + endfacet + facet normal 0.384422 -0.920107 0.0749892 + outer loop + vertex 600.397 115.793 138.924 + vertex 604.114 117.973 146.612 + vertex 600.259 116.428 147.414 + endloop + endfacet + facet normal 0.39934 -0.913541 0.0772688 + outer loop + vertex 599.143 115.529 141.559 + vertex 598.789 115.624 144.503 + vertex 597.795 114.704 138.77 + endloop + endfacet + facet normal 0.414751 -0.906958 0.0735394 + outer loop + vertex 597.823 115.427 147.527 + vertex 597.795 114.704 138.77 + vertex 598.789 115.624 144.503 + endloop + endfacet + facet normal 0.405651 -0.911317 0.0703473 + outer loop + vertex 598.789 115.624 144.503 + vertex 598.905 115.9 147.413 + vertex 597.823 115.427 147.527 + endloop + endfacet + facet normal 0.404751 -0.91271 0.0560098 + outer loop + vertex 598.905 115.9 147.413 + vertex 599.039 116.137 150.301 + vertex 597.823 115.427 147.527 + endloop + endfacet + facet normal 0.385883 -0.920915 0.054856 + outer loop + vertex 600.259 116.428 147.414 + vertex 604.019 118.451 154.929 + vertex 600.188 116.908 155.973 + endloop + endfacet + facet normal 0.403207 -0.913341 0.0568479 + outer loop + vertex 599.039 116.137 150.301 + vertex 598.669 116.157 153.262 + vertex 597.823 115.427 147.527 + endloop + endfacet + facet normal 0.419376 -0.906231 0.0535573 + outer loop + vertex 597.635 115.853 156.208 + vertex 597.823 115.427 147.527 + vertex 598.669 116.157 153.262 + endloop + endfacet + facet normal 0.409688 -0.910872 0.0496782 + outer loop + vertex 598.669 116.157 153.262 + vertex 598.776 116.362 156.127 + vertex 597.635 115.853 156.208 + endloop + endfacet + facet normal 0.409017 -0.911901 0.0337719 + outer loop + vertex 598.776 116.362 156.127 + vertex 598.977 116.556 158.95 + vertex 597.635 115.853 156.208 + endloop + endfacet + facet normal 0.38766 -0.921207 0.0331371 + outer loop + vertex 600.188 116.908 155.973 + vertex 604.012 118.776 163.165 + vertex 600.387 117.287 164.18 + endloop + endfacet + facet normal 0.411433 -0.910867 0.0323242 + outer loop + vertex 598.977 116.556 158.95 + vertex 598.683 116.541 162.251 + vertex 597.635 115.853 156.208 + endloop + endfacet + facet normal 0.416248 -0.908714 0.0312445 + outer loop + vertex 597.55 116.13 165.379 + vertex 597.635 115.853 156.208 + vertex 598.683 116.541 162.251 + endloop + endfacet + facet normal 0.396541 -0.917731 0.0229239 + outer loop + vertex 598.683 116.541 162.251 + vertex 599.018 116.79 166.446 + vertex 597.55 116.13 165.379 + endloop + endfacet + facet normal 0.386225 -0.922298 0.0140175 + outer loop + vertex 600.387 117.287 164.18 + vertex 604.002 118.908 171.207 + vertex 600.219 117.333 171.868 + endloop + endfacet + facet normal 0.398733 -0.916863 0.0193714 + outer loop + vertex 599.018 116.79 166.446 + vertex 598.823 116.753 168.666 + vertex 597.55 116.13 165.379 + endloop + endfacet + facet normal 0.421476 -0.906798 0.00865535 + outer loop + vertex 598.823 116.753 168.666 + vertex 598.651 116.695 171.021 + vertex 597.55 116.13 165.379 + endloop + endfacet + facet normal 0.417377 -0.908682 0.00964386 + outer loop + vertex 597.43 116.169 174.341 + vertex 597.55 116.13 165.379 + vertex 598.651 116.695 171.021 + endloop + endfacet + facet normal 0.396128 -0.918195 0.000323501 + outer loop + vertex 598.651 116.695 171.021 + vertex 599 116.847 174.862 + vertex 597.43 116.169 174.341 + endloop + endfacet + facet normal 0.385215 -0.922799 -0.00715286 + outer loop + vertex 600.219 117.333 171.868 + vertex 604.024 118.864 179.256 + vertex 600.224 117.272 180.102 + endloop + endfacet + facet normal 0.397128 -0.917757 -0.00326338 + outer loop + vertex 599 116.847 174.862 + vertex 598.812 116.757 177.209 + vertex 597.43 116.169 174.341 + endloop + endfacet + facet normal 0.4157 -0.909395 -0.0139313 + outer loop + vertex 598.812 116.757 177.209 + vertex 598.626 116.634 179.706 + vertex 597.43 116.169 174.341 + endloop + endfacet + facet normal 0.419656 -0.90756 -0.0149727 + outer loop + vertex 597.483 116.04 183.693 + vertex 597.43 116.169 174.341 + vertex 598.626 116.634 179.706 + endloop + endfacet + facet normal 0.398663 -0.916824 -0.0223712 + outer loop + vertex 598.626 116.634 179.706 + vertex 598.994 116.703 183.45 + vertex 597.483 116.04 183.693 + endloop + endfacet + facet normal 0.384778 -0.922552 -0.0290482 + outer loop + vertex 600.224 117.272 180.102 + vertex 604.04 118.635 187.35 + vertex 600.396 117.09 188.146 + endloop + endfacet + facet normal 0.397979 -0.916994 -0.0270902 + outer loop + vertex 598.994 116.703 183.45 + vertex 598.817 116.546 186.161 + vertex 597.483 116.04 183.693 + endloop + endfacet + facet normal 0.420447 -0.906371 -0.0414124 + outer loop + vertex 598.817 116.546 186.161 + vertex 598.822 116.378 189.878 + vertex 597.483 116.04 183.693 + endloop + endfacet + facet normal 0.411486 -0.910571 -0.0392417 + outer loop + vertex 597.807 115.787 192.953 + vertex 597.483 116.04 183.693 + vertex 598.822 116.378 189.878 + endloop + endfacet + facet normal 0.381738 -0.922952 -0.0493512 + outer loop + vertex 600.396 117.09 188.146 + vertex 604.073 118.223 195.41 + vertex 600.22 116.605 195.852 + endloop + endfacet + facet normal 0.407147 -0.91244 -0.0410341 + outer loop + vertex 598.822 116.378 189.878 + vertex 598.806 116.219 193.273 + vertex 597.807 115.787 192.953 + endloop + endfacet + facet normal 0.410295 -0.910372 -0.053679 + outer loop + vertex 598.806 116.219 193.273 + vertex 598.823 116.125 194.998 + vertex 597.807 115.787 192.953 + endloop + endfacet + facet normal 0.379388 -0.922496 -0.0711717 + outer loop + vertex 600.22 116.605 195.852 + vertex 604.15 117.626 203.577 + vertex 600.349 116.005 204.323 + endloop + endfacet + facet normal 0.399986 -0.914182 -0.0654388 + outer loop + vertex 598.922 115.913 198.466 + vertex 598.963 115.686 201.882 + vertex 597.919 115.269 201.335 + endloop + endfacet + facet normal 0.404764 -0.911188 -0.0768344 + outer loop + vertex 598.963 115.686 201.882 + vertex 599.01 115.562 203.609 + vertex 597.919 115.269 201.335 + endloop + endfacet + facet normal 0.377322 -0.921277 -0.0942127 + outer loop + vertex 600.349 116.005 204.323 + vertex 604.292 116.846 211.886 + vertex 600.545 115.185 213.121 + endloop + endfacet + facet normal 0.387712 -0.917408 -0.0896753 + outer loop + vertex 599.07 115.249 207.035 + vertex 599.079 114.892 210.722 + vertex 597.585 114.405 209.243 + endloop + endfacet + facet normal 0.398652 -0.911331 -0.102729 + outer loop + vertex 599.079 114.892 210.722 + vertex 598.949 114.513 213.58 + vertex 597.585 114.405 209.243 + endloop + endfacet + facet normal 0.373808 -0.920062 -0.117271 + outer loop + vertex 600.545 115.185 213.121 + vertex 604.481 115.899 220.072 + vertex 600.851 114.266 221.309 + endloop + endfacet + facet normal 0.387088 -0.914529 -0.11747 + outer loop + vertex 599.378 114.271 217.031 + vertex 599.241 113.856 219.807 + vertex 597.831 113.494 217.984 + endloop + endfacet + facet normal 0.402338 -0.906079 -0.13094 + outer loop + vertex 599.241 113.856 219.807 + vertex 599.279 113.336 223.52 + vertex 597.831 113.494 217.984 + endloop + endfacet + facet normal 0.336545 -0.931985 -0.134692 + outer loop + vertex 599.289 112.853 226.892 + vertex 599.279 113.336 223.52 + vertex 600.746 113.071 229.019 + endloop + endfacet + facet normal 0.348921 -0.926058 -0.143776 + outer loop + vertex 599.318 112.596 228.615 + vertex 599.289 112.853 226.892 + vertex 600.746 113.071 229.019 + endloop + endfacet + facet normal 0.350637 -0.924061 -0.152197 + outer loop + vertex 599.434 112.071 232.072 + vertex 599.318 112.596 228.615 + vertex 600.746 113.071 229.019 + endloop + endfacet + facet normal 0.346661 -0.925215 -0.154284 + outer loop + vertex 600.746 113.071 229.019 + vertex 600.966 111.77 237.318 + vertex 599.434 112.071 232.072 + endloop + endfacet + facet normal 0.338444 -0.928616 -0.15208 + outer loop + vertex 599.485 111.534 235.465 + vertex 599.434 112.071 232.072 + vertex 600.966 111.77 237.318 + endloop + endfacet + facet normal 0.346308 -0.92457 -0.158878 + outer loop + vertex 599.539 111.259 237.18 + vertex 599.485 111.534 235.465 + vertex 600.966 111.77 237.318 + endloop + endfacet + facet normal 0.346521 -0.923238 -0.165994 + outer loop + vertex 599.729 110.716 240.6 + vertex 599.539 111.259 237.18 + vertex 600.966 111.77 237.318 + endloop + endfacet + facet normal 0.345216 -0.923617 -0.166607 + outer loop + vertex 600.966 111.77 237.318 + vertex 601.539 110.545 245.296 + vertex 599.729 110.716 240.6 + endloop + endfacet + facet normal 0.343947 -0.924175 -0.166138 + outer loop + vertex 599.886 110.111 244.288 + vertex 599.729 110.716 240.6 + vertex 601.539 110.545 245.296 + endloop + endfacet + facet normal 0.347232 -0.921765 -0.172564 + outer loop + vertex 600.195 109.674 247.244 + vertex 599.886 110.111 244.288 + vertex 601.539 110.545 245.296 + endloop + endfacet + facet normal 0.343207 -0.922671 -0.175746 + outer loop + vertex 601.539 110.545 245.296 + vertex 601.779 109.208 252.785 + vertex 600.195 109.674 247.244 + endloop + endfacet + facet normal 0.344361 -0.922186 -0.176035 + outer loop + vertex 599.973 109.058 250.034 + vertex 600.195 109.674 247.244 + vertex 601.779 109.208 252.785 + endloop + endfacet + facet normal 0.342918 -0.922911 -0.175048 + outer loop + vertex 600.289 108.642 252.85 + vertex 599.973 109.058 250.034 + vertex 601.779 109.208 252.785 + endloop + endfacet + facet normal 0.342403 -0.92213 -0.180102 + outer loop + vertex 600.678 108.244 255.628 + vertex 600.289 108.642 252.85 + vertex 601.779 109.208 252.785 + endloop + endfacet + facet normal 0.339985 -0.922797 -0.181264 + outer loop + vertex 601.779 109.208 252.785 + vertex 602.355 107.819 260.933 + vertex 600.678 108.244 255.628 + endloop + endfacet + facet normal 0.341139 -0.922306 -0.181589 + outer loop + vertex 600.558 107.587 258.736 + vertex 600.678 108.244 255.628 + vertex 602.355 107.819 260.933 + endloop + endfacet + facet normal 0.340367 -0.922725 -0.180913 + outer loop + vertex 600.947 107.197 261.459 + vertex 600.558 107.587 258.736 + vertex 602.355 107.819 260.933 + endloop + endfacet + facet normal 0.33949 -0.922612 -0.183124 + outer loop + vertex 601.356 106.881 263.81 + vertex 600.947 107.197 261.459 + vertex 602.355 107.819 260.933 + endloop + endfacet + facet normal 0.340594 -0.922301 -0.18264 + outer loop + vertex 602.355 107.819 260.933 + vertex 603.093 106.531 268.815 + vertex 601.356 106.881 263.81 + endloop + endfacet + facet normal 0.343224 -0.921159 -0.183473 + outer loop + vertex 601.335 106.493 265.719 + vertex 601.356 106.881 263.81 + vertex 603.093 106.531 268.815 + endloop + endfacet + facet normal 0.336944 -0.924184 -0.179869 + outer loop + vertex 601.406 106.067 268.041 + vertex 601.335 106.493 265.719 + vertex 603.093 106.531 268.815 + endloop + endfacet + facet normal 0.336409 -0.92466 -0.178419 + outer loop + vertex 602.214 105.55 272.244 + vertex 601.406 106.067 268.041 + vertex 603.093 106.531 268.815 + endloop + endfacet + facet normal 0.340828 -0.923331 -0.176906 + outer loop + vertex 603.093 106.531 268.815 + vertex 604.219 105.285 277.489 + vertex 602.214 105.55 272.244 + endloop + endfacet + facet normal 0.326285 -0.929554 -0.171663 + outer loop + vertex 602.402 104.828 276.51 + vertex 602.214 105.55 272.244 + vertex 604.219 105.285 277.489 + endloop + endfacet + facet normal 0.323587 -0.931574 -0.165715 + outer loop + vertex 603.311 104.314 281.175 + vertex 602.402 104.828 276.51 + vertex 604.219 105.285 277.489 + endloop + endfacet + facet normal 0.329045 -0.929973 -0.163949 + outer loop + vertex 604.219 105.285 277.489 + vertex 605.133 104.293 284.949 + vertex 603.311 104.314 281.175 + endloop + endfacet + facet normal 0.303612 -0.940638 -0.151723 + outer loop + vertex 603.942 103.58 286.985 + vertex 603.311 104.314 281.175 + vertex 605.133 104.293 284.949 + endloop + endfacet + facet normal 0.296216 -0.943073 -0.151227 + outer loop + vertex 603.311 104.314 281.175 + vertex 603.942 103.58 286.985 + vertex 601.984 103.857 281.422 + endloop + endfacet + facet normal 0.308796 -0.937158 -0.162422 + outer loop + vertex 604.219 105.285 277.489 + vertex 608.355 105.427 284.533 + vertex 605.133 104.293 284.949 + endloop + endfacet + facet normal 0.326998 -0.929004 -0.173274 + outer loop + vertex 607.65 106.75 276.107 + vertex 608.355 105.427 284.533 + vertex 604.219 105.285 277.489 + endloop + endfacet + facet normal 0.294044 -0.942113 -0.161123 + outer loop + vertex 602.402 104.828 276.51 + vertex 603.311 104.314 281.175 + vertex 601.984 103.857 281.422 + endloop + endfacet + facet normal 0.286451 -0.944266 -0.162194 + outer loop + vertex 601.984 103.857 281.422 + vertex 600.555 105.145 271.402 + vertex 602.402 104.828 276.51 + endloop + endfacet + facet normal 0.313185 -0.935275 -0.16485 + outer loop + vertex 600.555 105.145 271.402 + vertex 601.984 103.857 281.422 + vertex 596.487 103.34 273.915 + endloop + endfacet + facet normal 0.314937 -0.93343 -0.17182 + outer loop + vertex 602.214 105.55 272.244 + vertex 602.402 104.828 276.51 + vertex 600.555 105.145 271.402 + endloop + endfacet + facet normal 0.325948 -0.928903 -0.175776 + outer loop + vertex 603.093 106.531 268.815 + vertex 607.65 106.75 276.107 + vertex 604.219 105.285 277.489 + endloop + endfacet + facet normal 0.337756 -0.923208 -0.183325 + outer loop + vertex 606.86 108.115 267.777 + vertex 607.65 106.75 276.107 + vertex 603.093 106.531 268.815 + endloop + endfacet + facet normal 0.331984 -0.925338 -0.183127 + outer loop + vertex 606.86 108.115 267.777 + vertex 612.807 108.751 275.348 + vertex 607.65 106.75 276.107 + endloop + endfacet + facet normal 0.33116 -0.924798 -0.187303 + outer loop + vertex 612.807 108.751 275.348 + vertex 613.601 107.297 283.929 + vertex 607.65 106.75 276.107 + endloop + endfacet + facet normal 0.32318 -0.927667 -0.187051 + outer loop + vertex 612.807 108.751 275.348 + vertex 620.005 109.669 283.229 + vertex 613.601 107.297 283.929 + endloop + endfacet + facet normal 0.341652 -0.917164 -0.205145 + outer loop + vertex 619.108 111.218 274.81 + vertex 620.005 109.669 283.229 + vertex 612.807 108.751 275.348 + endloop + endfacet + facet normal 0.343383 -0.919045 -0.193506 + outer loop + vertex 612.055 110.213 267.069 + vertex 619.108 111.218 274.81 + vertex 612.807 108.751 275.348 + endloop + endfacet + facet normal 0.357355 -0.910666 -0.207327 + outer loop + vertex 618.375 112.776 266.703 + vertex 619.108 111.218 274.81 + vertex 612.055 110.213 267.069 + endloop + endfacet + facet normal 0.359035 -0.912918 -0.194099 + outer loop + vertex 611.387 111.647 259.089 + vertex 618.375 112.776 266.703 + vertex 612.055 110.213 267.069 + endloop + endfacet + facet normal 0.354626 -0.914652 -0.194042 + outer loop + vertex 611.387 111.647 259.089 + vertex 612.055 110.213 267.069 + vertex 606.187 109.5 259.708 + endloop + endfacet + facet normal 0.356379 -0.916027 -0.184088 + outer loop + vertex 605.635 110.867 251.836 + vertex 611.387 111.647 259.089 + vertex 606.187 109.5 259.708 + endloop + endfacet + facet normal 0.349864 -0.918539 -0.184067 + outer loop + vertex 605.635 110.867 251.836 + vertex 606.187 109.5 259.708 + vertex 601.779 109.208 252.785 + endloop + endfacet + facet normal 0.362926 -0.912308 -0.189681 + outer loop + vertex 610.832 113.05 251.28 + vertex 611.387 111.647 259.089 + vertex 605.635 110.867 251.836 + endloop + endfacet + facet normal 0.364968 -0.913998 -0.177216 + outer loop + vertex 605.171 112.197 244.019 + vertex 610.832 113.05 251.28 + vertex 605.635 110.867 251.836 + endloop + endfacet + facet normal 0.355161 -0.91784 -0.177289 + outer loop + vertex 605.171 112.197 244.019 + vertex 605.635 110.867 251.836 + vertex 601.539 110.545 245.296 + endloop + endfacet + facet normal 0.369913 -0.911185 -0.181401 + outer loop + vertex 610.356 114.416 243.445 + vertex 610.832 113.05 251.28 + vertex 605.171 112.197 244.019 + endloop + endfacet + facet normal 0.370837 -0.909123 -0.189671 + outer loop + vertex 610.832 113.05 251.28 + vertex 617.728 114.279 258.872 + vertex 611.387 111.647 259.089 + endloop + endfacet + facet normal 0.378499 -0.904305 -0.197412 + outer loop + vertex 617.151 115.725 251.14 + vertex 617.728 114.279 258.872 + vertex 610.832 113.05 251.28 + endloop + endfacet + facet normal 0.345842 -0.919558 -0.186566 + outer loop + vertex 606.187 109.5 259.708 + vertex 612.055 110.213 267.069 + vertex 606.86 108.115 267.777 + endloop + endfacet + facet normal 0.343839 -0.920316 -0.186529 + outer loop + vertex 606.187 109.5 259.708 + vertex 606.86 108.115 267.777 + vertex 602.355 107.819 260.933 + endloop + endfacet + facet normal 0.369267 -0.906559 -0.204433 + outer loop + vertex 617.728 114.279 258.872 + vertex 618.375 112.776 266.703 + vertex 611.387 111.647 259.089 + endloop + endfacet + facet normal 0.376364 -0.90363 -0.204457 + outer loop + vertex 617.728 114.279 258.872 + vertex 625.276 115.694 266.509 + vertex 618.375 112.776 266.703 + endloop + endfacet + facet normal 0.374312 -0.900029 -0.223244 + outer loop + vertex 625.276 115.694 266.509 + vertex 625.988 114.03 274.413 + vertex 618.375 112.776 266.703 + endloop + endfacet + facet normal 0.380492 -0.897431 -0.223255 + outer loop + vertex 625.276 115.694 266.509 + vertex 633.029 117.105 274.054 + vertex 625.988 114.03 274.413 + endloop + endfacet + facet normal 0.377112 -0.892514 -0.247399 + outer loop + vertex 633.029 117.105 274.054 + vertex 633.82 115.24 281.987 + vertex 625.988 114.03 274.413 + endloop + endfacet + facet normal 0.358597 -0.905684 -0.226151 + outer loop + vertex 625.988 114.03 274.413 + vertex 633.82 115.24 281.987 + vertex 626.816 112.322 282.568 + endloop + endfacet + facet normal 0.357311 -0.906198 -0.226128 + outer loop + vertex 625.988 114.03 274.413 + vertex 626.816 112.322 282.568 + vertex 619.108 111.218 274.81 + endloop + endfacet + facet normal 0.394421 -0.887175 -0.239484 + outer loop + vertex 632.219 118.838 266.297 + vertex 633.029 117.105 274.054 + vertex 625.276 115.694 266.509 + endloop + endfacet + facet normal 0.386887 -0.896426 -0.216192 + outer loop + vertex 624.595 117.258 258.808 + vertex 625.276 115.694 266.509 + vertex 617.728 114.279 258.872 + endloop + endfacet + facet normal 0.359819 -0.909688 -0.207362 + outer loop + vertex 618.375 112.776 266.703 + vertex 625.988 114.03 274.413 + vertex 619.108 111.218 274.81 + endloop + endfacet + facet normal 0.344513 -0.918616 -0.193533 + outer loop + vertex 612.055 110.213 267.069 + vertex 612.807 108.751 275.348 + vertex 606.86 108.115 267.777 + endloop + endfacet + facet normal 0.316516 -0.932207 -0.17552 + outer loop + vertex 601.406 106.067 268.041 + vertex 602.214 105.55 272.244 + vertex 600.555 105.145 271.402 + endloop + endfacet + facet normal 0.314248 -0.932834 -0.176265 + outer loop + vertex 600.555 105.145 271.402 + vertex 599.93 106.587 262.657 + vertex 601.406 106.067 268.041 + endloop + endfacet + facet normal 0.325653 -0.928883 -0.176429 + outer loop + vertex 599.93 106.587 262.657 + vertex 600.555 105.145 271.402 + vertex 597.148 105.073 265.494 + endloop + endfacet + facet normal 0.33046 -0.926478 -0.180094 + outer loop + vertex 601.335 106.493 265.719 + vertex 601.406 106.067 268.041 + vertex 599.93 106.587 262.657 + endloop + endfacet + facet normal 0.338864 -0.922701 -0.183834 + outer loop + vertex 601.356 106.881 263.81 + vertex 601.335 106.493 265.719 + vertex 599.93 106.587 262.657 + endloop + endfacet + facet normal 0.337996 -0.923273 -0.182555 + outer loop + vertex 602.355 107.819 260.933 + vertex 606.86 108.115 267.777 + vertex 603.093 106.531 268.815 + endloop + endfacet + facet normal 0.33825 -0.923097 -0.182973 + outer loop + vertex 600.947 107.197 261.459 + vertex 601.356 106.881 263.81 + vertex 599.93 106.587 262.657 + endloop + endfacet + facet normal 0.340432 -0.922699 -0.180919 + outer loop + vertex 600.558 107.587 258.736 + vertex 600.947 107.197 261.459 + vertex 599.93 106.587 262.657 + endloop + endfacet + facet normal 0.34695 -0.920578 -0.179334 + outer loop + vertex 599.93 106.587 262.657 + vertex 599.007 108.062 253.3 + vertex 600.558 107.587 258.736 + endloop + endfacet + facet normal 0.33314 -0.925771 -0.178789 + outer loop + vertex 599.007 108.062 253.3 + vertex 599.93 106.587 262.657 + vertex 594.727 106.008 255.961 + endloop + endfacet + facet normal 0.351368 -0.918687 -0.18043 + outer loop + vertex 600.678 108.244 255.628 + vertex 600.558 107.587 258.736 + vertex 599.007 108.062 253.3 + endloop + endfacet + facet normal 0.345666 -0.920676 -0.181304 + outer loop + vertex 601.779 109.208 252.785 + vertex 606.187 109.5 259.708 + vertex 602.355 107.819 260.933 + endloop + endfacet + facet normal 0.351995 -0.918353 -0.180906 + outer loop + vertex 600.289 108.642 252.85 + vertex 600.678 108.244 255.628 + vertex 599.007 108.062 253.3 + endloop + endfacet + facet normal 0.353962 -0.918617 -0.175652 + outer loop + vertex 599.973 109.058 250.034 + vertex 600.289 108.642 252.85 + vertex 599.007 108.062 253.3 + endloop + endfacet + facet normal 0.361488 -0.916243 -0.172702 + outer loop + vertex 599.007 108.062 253.3 + vertex 598.674 109.626 244.305 + vertex 599.973 109.058 250.034 + endloop + endfacet + facet normal 0.343184 -0.923156 -0.173226 + outer loop + vertex 598.674 109.626 244.305 + vertex 599.007 108.062 253.3 + vertex 594.923 107.916 245.989 + endloop + endfacet + facet normal 0.363319 -0.915454 -0.173039 + outer loop + vertex 600.195 109.674 247.244 + vertex 599.973 109.058 250.034 + vertex 598.674 109.626 244.305 + endloop + endfacet + facet normal 0.352313 -0.919292 -0.175434 + outer loop + vertex 601.539 110.545 245.296 + vertex 605.635 110.867 251.836 + vertex 601.779 109.208 252.785 + endloop + endfacet + facet normal 0.36387 -0.915181 -0.173329 + outer loop + vertex 599.886 110.111 244.288 + vertex 600.195 109.674 247.244 + vertex 598.674 109.626 244.305 + endloop + endfacet + facet normal 0.364449 -0.916357 -0.165729 + outer loop + vertex 599.729 110.716 240.6 + vertex 599.886 110.111 244.288 + vertex 598.674 109.626 244.305 + endloop + endfacet + facet normal 0.372485 -0.913674 -0.16265 + outer loop + vertex 598.674 109.626 244.305 + vertex 598.491 111.113 235.532 + vertex 599.729 110.716 240.6 + endloop + endfacet + facet normal 0.350363 -0.922209 -0.163637 + outer loop + vertex 598.491 111.113 235.532 + vertex 598.674 109.626 244.305 + vertex 595.121 109.558 237.079 + endloop + endfacet + facet normal 0.359059 -0.918292 -0.166783 + outer loop + vertex 600.966 111.77 237.318 + vertex 605.171 112.197 244.019 + vertex 601.539 110.545 245.296 + endloop + endfacet + facet normal 0.359545 -0.918044 -0.167104 + outer loop + vertex 604.801 113.507 236.026 + vertex 605.171 112.197 244.019 + vertex 600.966 111.77 237.318 + endloop + endfacet + facet normal 0.386984 -0.90708 -0.165677 + outer loop + vertex 599.539 111.259 237.18 + vertex 599.729 110.716 240.6 + vertex 598.491 111.113 235.532 + endloop + endfacet + facet normal 0.375723 -0.913169 -0.157971 + outer loop + vertex 599.485 111.534 235.465 + vertex 599.539 111.259 237.18 + vertex 598.491 111.113 235.532 + endloop + endfacet + facet normal 0.376629 -0.914081 -0.150354 + outer loop + vertex 599.434 112.071 232.072 + vertex 599.485 111.534 235.465 + vertex 598.491 111.113 235.532 + endloop + endfacet + facet normal 0.383161 -0.911759 -0.147931 + outer loop + vertex 598.491 111.113 235.532 + vertex 598.245 112.38 227.086 + vertex 599.434 112.071 232.072 + endloop + endfacet + facet normal 0.352431 -0.923923 -0.14886 + outer loop + vertex 598.245 112.38 227.086 + vertex 598.491 111.113 235.532 + vertex 595.899 111.001 230.093 + endloop + endfacet + facet normal 0.397313 -0.905191 -0.1509 + outer loop + vertex 599.318 112.596 228.615 + vertex 599.434 112.071 232.072 + vertex 598.245 112.38 227.086 + endloop + endfacet + facet normal 0.386177 -0.911396 -0.14221 + outer loop + vertex 599.289 112.853 226.892 + vertex 599.318 112.596 228.615 + vertex 598.245 112.38 227.086 + endloop + endfacet + facet normal 0.388356 -0.912009 -0.131982 + outer loop + vertex 599.279 113.336 223.52 + vertex 599.289 112.853 226.892 + vertex 598.245 112.38 227.086 + endloop + endfacet + facet normal 0.395417 -0.909366 -0.129224 + outer loop + vertex 598.245 112.38 227.086 + vertex 597.831 113.494 217.984 + vertex 599.279 113.336 223.52 + endloop + endfacet + facet normal 0.367281 -0.920052 -0.136412 + outer loop + vertex 604.481 115.899 220.072 + vertex 604.631 114.776 228.043 + vertex 600.851 114.266 221.309 + endloop + endfacet + facet normal 0.364277 -0.91852 -0.153701 + outer loop + vertex 600.746 113.071 229.019 + vertex 604.801 113.507 236.026 + vertex 600.966 111.77 237.318 + endloop + endfacet + facet normal 0.38149 -0.911191 -0.155555 + outer loop + vertex 609.815 117.022 227.604 + vertex 610.047 115.764 235.544 + vertex 604.631 114.776 228.043 + endloop + endfacet + facet normal 0.372295 -0.912991 -0.166866 + outer loop + vertex 604.801 113.507 236.026 + vertex 610.356 114.416 243.445 + vertex 605.171 112.197 244.019 + endloop + endfacet + facet normal 0.392844 -0.902854 -0.174724 + outer loop + vertex 616.381 118.523 235.525 + vertex 616.707 117.146 243.372 + vertex 610.047 115.764 235.544 + endloop + endfacet + facet normal 0.380014 -0.90704 -0.181293 + outer loop + vertex 610.356 114.416 243.445 + vertex 617.151 115.725 251.14 + vertex 610.832 113.05 251.28 + endloop + endfacet + facet normal 0.404625 -0.893636 -0.194147 + outer loop + vertex 623.561 120.232 243.455 + vertex 624.005 118.759 251.162 + vertex 616.707 117.146 243.372 + endloop + endfacet + facet normal 0.388618 -0.900013 -0.197364 + outer loop + vertex 617.151 115.725 251.14 + vertex 624.595 117.258 258.808 + vertex 617.728 114.279 258.872 + endloop + endfacet + facet normal 0.417867 -0.882648 -0.215222 + outer loop + vertex 630.828 121.995 251.137 + vertex 631.452 120.444 258.709 + vertex 624.005 118.759 251.162 + endloop + endfacet + facet normal 0.39726 -0.891879 -0.216186 + outer loop + vertex 624.595 117.258 258.808 + vertex 632.219 118.838 266.297 + vertex 625.276 115.694 266.509 + endloop + endfacet + facet normal 0.431497 -0.869473 -0.240474 + outer loop + vertex 638.008 123.742 258.548 + vertex 638.886 122.108 266.032 + vertex 631.452 120.444 258.709 + endloop + endfacet + facet normal 0.404539 -0.882598 -0.239518 + outer loop + vertex 632.219 118.838 266.297 + vertex 639.867 120.364 273.592 + vertex 633.029 117.105 274.054 + endloop + endfacet + facet normal 0.39981 -0.876657 -0.267627 + outer loop + vertex 639.867 120.364 273.592 + vertex 640.911 118.44 281.454 + vertex 633.029 117.105 274.054 + endloop + endfacet + facet normal 0.444257 -0.853794 -0.271427 + outer loop + vertex 645.165 125.448 265.803 + vertex 646.309 123.706 273.153 + vertex 638.886 122.108 266.032 + endloop + endfacet + facet normal 0.411524 -0.871155 -0.267836 + outer loop + vertex 639.867 120.364 273.592 + vertex 647.369 121.834 280.339 + vertex 640.911 118.44 281.454 + endloop + endfacet + facet normal 0.456882 -0.834765 -0.307288 + outer loop + vertex 652.337 127.102 272.892 + vertex 653.595 125.228 279.853 + vertex 646.309 123.706 273.153 + endloop + endfacet + facet normal 0.452903 -0.83214 -0.320034 + outer loop + vertex 653.595 125.228 279.853 + vertex 660.453 126.712 285.7 + vertex 654.405 123.269 286.093 + endloop + endfacet + facet normal 0.444361 -0.821416 -0.357519 + outer loop + vertex 660.453 126.712 285.7 + vertex 660.608 124.675 290.572 + vertex 654.405 123.269 286.093 + endloop + endfacet + facet normal 0.435432 -0.802767 -0.407387 + outer loop + vertex 665.849 126.126 293.576 + vertex 670.231 127.595 295.365 + vertex 664.153 124.256 295.447 + endloop + endfacet + facet normal 0.398402 -0.859608 -0.319923 + outer loop + vertex 649.333 118.947 291.211 + vertex 654.397 121.404 290.917 + vertex 652.229 119.204 294.127 + endloop + endfacet + facet normal 0.369883 -0.88277 -0.289661 + outer loop + vertex 644.794 117.626 289.262 + vertex 645.844 116.94 292.693 + vertex 641.071 115.732 290.277 + endloop + endfacet + facet normal 0.374009 -0.884724 -0.278175 + outer loop + vertex 640.197 116.611 286.307 + vertex 644.794 117.626 289.262 + vertex 641.071 115.732 290.277 + endloop + endfacet + facet normal 0.400813 -0.863071 -0.307338 + outer loop + vertex 648.042 119.911 286.822 + vertex 654.397 121.404 290.917 + vertex 649.333 118.947 291.211 + endloop + endfacet + facet normal 0.403072 -0.865134 -0.298454 + outer loop + vertex 647.369 121.834 280.339 + vertex 648.042 119.911 286.822 + vertex 640.911 118.44 281.454 + endloop + endfacet + facet normal 0.378741 -0.879805 -0.287225 + outer loop + vertex 643.564 118.1 286.186 + vertex 644.794 117.626 289.262 + vertex 640.197 116.611 286.307 + endloop + endfacet + facet normal 0.383071 -0.889973 -0.247396 + outer loop + vertex 633.029 117.105 274.054 + vertex 640.911 118.44 281.454 + vertex 633.82 115.24 281.987 + endloop + endfacet + facet normal 0.364894 -0.888863 -0.277084 + outer loop + vertex 640.197 116.611 286.307 + vertex 641.071 115.732 290.277 + vertex 637.022 114.943 287.479 + endloop + endfacet + facet normal 0.364134 -0.889901 -0.27474 + outer loop + vertex 641.071 115.732 290.277 + vertex 645.844 116.94 292.693 + vertex 641.179 114.833 293.333 + endloop + endfacet + facet normal 0.361124 -0.887104 -0.287463 + outer loop + vertex 641.179 114.833 293.333 + vertex 645.844 116.94 292.693 + vertex 645.4 115.853 295.489 + endloop + endfacet + facet normal 0.354751 -0.881886 -0.310531 + outer loop + vertex 645.4 115.853 295.489 + vertex 651.342 117.965 296.277 + vertex 645.514 115.306 297.171 + endloop + endfacet + facet normal 0.325835 -0.912286 -0.248126 + outer loop + vertex 639.487 113.621 295.283 + vertex 640.68 113.567 297.048 + vertex 636.241 112.162 296.382 + endloop + endfacet + facet normal 0.329069 -0.913314 -0.239939 + outer loop + vertex 635.079 112.361 294.033 + vertex 639.487 113.621 295.283 + vertex 636.241 112.162 296.382 + endloop + endfacet + facet normal 0.328802 -0.912294 -0.244148 + outer loop + vertex 633.953 112.751 291.06 + vertex 637.44 113.426 293.234 + vertex 635.079 112.361 294.033 + endloop + endfacet + facet normal 0.339647 -0.906983 -0.249039 + outer loop + vertex 633.091 113.503 287.146 + vertex 637.262 114.087 290.705 + vertex 633.953 112.751 291.06 + endloop + endfacet + facet normal 0.354113 -0.900294 -0.253131 + outer loop + vertex 626.816 112.322 282.568 + vertex 633.82 115.24 281.987 + vertex 633.091 113.503 287.146 + endloop + endfacet + facet normal 0.326773 -0.916045 -0.232553 + outer loop + vertex 630.147 112.126 288.191 + vertex 630.844 111.516 291.573 + vertex 626.37 110.849 287.915 + endloop + endfacet + facet normal 0.337823 -0.918612 -0.205004 + outer loop + vertex 619.108 111.218 274.81 + vertex 626.816 112.322 282.568 + vertex 620.005 109.669 283.229 + endloop + endfacet + facet normal 0.317254 -0.923296 -0.216504 + outer loop + vertex 626.37 110.849 287.915 + vertex 627.566 110.277 292.109 + vertex 623.405 109.553 289.097 + endloop + endfacet + facet normal 0.303738 -0.929562 -0.208943 + outer loop + vertex 627.566 110.277 292.109 + vertex 631.975 111.131 294.716 + vertex 628.676 109.91 295.356 + endloop + endfacet + facet normal 0.29494 -0.934586 -0.198894 + outer loop + vertex 628.676 109.91 295.356 + vertex 632.779 110.831 297.113 + vertex 629.523 109.656 297.803 + endloop + endfacet + facet normal 0.287757 -0.939666 -0.184996 + outer loop + vertex 629.523 109.656 297.803 + vertex 632.742 110.487 298.587 + vertex 629.969 109.475 299.418 + endloop + endfacet + facet normal 0.28596 -0.941954 -0.175923 + outer loop + vertex 625.335 108.728 296 + vertex 626.282 108.539 298.55 + vertex 621.985 107.585 296.674 + endloop + endfacet + facet normal 0.28736 -0.942604 -0.170066 + outer loop + vertex 620.759 107.831 293.24 + vertex 625.335 108.728 296 + vertex 621.985 107.585 296.674 + endloop + endfacet + facet normal 0.29963 -0.935941 -0.185031 + outer loop + vertex 619.547 108.314 288.832 + vertex 624.175 109.037 292.669 + vertex 620.759 107.831 293.24 + endloop + endfacet + facet normal 0.321429 -0.926073 -0.197667 + outer loop + vertex 613.601 107.297 283.929 + vertex 620.005 109.669 283.229 + vertex 619.547 108.314 288.832 + endloop + endfacet + facet normal 0.300041 -0.93862 -0.170199 + outer loop + vertex 616.607 107.113 290.029 + vertex 617.401 106.69 293.76 + vertex 613.082 106.063 289.603 + endloop + endfacet + facet normal 0.285871 -0.945748 -0.154398 + outer loop + vertex 613.082 106.063 289.603 + vertex 617.401 106.69 293.76 + vertex 614.17 105.643 294.189 + endloop + endfacet + facet normal 0.313025 -0.93388 -0.17287 + outer loop + vertex 607.65 106.75 276.107 + vertex 613.601 107.297 283.929 + vertex 608.355 105.427 284.533 + endloop + endfacet + facet normal 0.31019 -0.938092 -0.154162 + outer loop + vertex 605.133 104.293 284.949 + vertex 608.355 105.427 284.533 + vertex 607.8 104.344 290.007 + endloop + endfacet + facet normal 0.290548 -0.946005 -0.143725 + outer loop + vertex 605.724 103.547 291.058 + vertex 605.133 104.293 284.949 + vertex 607.8 104.344 290.007 + endloop + endfacet + facet normal 0.296801 -0.945874 -0.131269 + outer loop + vertex 607.8 104.344 290.007 + vertex 608.7 103.941 294.943 + vertex 605.724 103.547 291.058 + endloop + endfacet + facet normal 0.277996 -0.953542 -0.116085 + outer loop + vertex 605.724 103.547 291.058 + vertex 608.7 103.941 294.943 + vertex 606.968 103.343 295.71 + endloop + endfacet + facet normal 0.284368 -0.953324 -0.10153 + outer loop + vertex 608.7 103.941 294.943 + vertex 609.943 103.836 299.412 + vertex 606.968 103.343 295.71 + endloop + endfacet + facet normal 0.2623 -0.961434 -0.0827212 + outer loop + vertex 606.968 103.343 295.71 + vertex 609.943 103.836 299.412 + vertex 608.014 103.312 299.383 + endloop + endfacet + facet normal 0.274986 -0.952907 -0.127868 + outer loop + vertex 607.8 104.344 290.007 + vertex 611.234 104.722 294.573 + vertex 608.7 103.941 294.943 + endloop + endfacet + facet normal 0.277542 -0.954067 -0.112817 + outer loop + vertex 611.234 104.722 294.573 + vertex 612.589 104.599 298.951 + vertex 608.7 103.941 294.943 + endloop + endfacet + facet normal 0.296904 -0.941967 -0.156671 + outer loop + vertex 613.082 106.063 289.603 + vertex 614.17 105.643 294.189 + vertex 610.524 105.088 290.619 + endloop + endfacet + facet normal 0.26453 -0.958208 -0.108909 + outer loop + vertex 611.234 104.722 294.573 + vertex 615.428 105.488 298.018 + vertex 612.589 104.599 298.951 + endloop + endfacet + facet normal 0.286439 -0.94612 -0.151025 + outer loop + vertex 617.401 106.69 293.76 + vertex 618.648 106.497 297.332 + vertex 614.17 105.643 294.189 + endloop + endfacet + facet normal 0.267962 -0.955392 -0.124184 + outer loop + vertex 618.648 106.497 297.332 + vertex 622.962 107.444 299.355 + vertex 619.645 106.404 300.2 + endloop + endfacet + facet normal 0.258985 -0.960736 -0.0995671 + outer loop + vertex 619.645 106.404 300.2 + vertex 623.219 107.261 301.229 + vertex 619.925 106.268 302.238 + endloop + endfacet + facet normal 0.266765 -0.958325 -0.102224 + outer loop + vertex 615.428 105.488 298.018 + vertex 616.428 105.421 301.265 + vertex 612.589 104.599 298.951 + endloop + endfacet + facet normal 0.253559 -0.965054 -0.0661647 + outer loop + vertex 614.268 104.819 301.442 + vertex 615.05 104.93 302.809 + vertex 612.828 104.427 301.64 + endloop + endfacet + facet normal 0.248849 -0.966898 -0.0564167 + outer loop + vertex 612.828 104.427 301.64 + vertex 615.05 104.93 302.809 + vertex 613.545 104.504 303.477 + endloop + endfacet + facet normal 0.260345 -0.960828 -0.0950252 + outer loop + vertex 608.7 103.941 294.943 + vertex 612.589 104.599 298.951 + vertex 609.943 103.836 299.412 + endloop + endfacet + facet normal 0.262391 -0.962655 -0.0666758 + outer loop + vertex 608.014 103.312 299.383 + vertex 609.943 103.836 299.412 + vertex 610.151 103.706 302.103 + endloop + endfacet + facet normal 0.242021 -0.969471 -0.039389 + outer loop + vertex 610.151 103.706 302.103 + vertex 612.088 104.119 303.849 + vertex 610.787 103.782 304.147 + endloop + endfacet + facet normal 0.244829 -0.969195 -0.0268471 + outer loop + vertex 612.088 104.119 303.849 + vertex 612.35 104.155 304.951 + vertex 610.787 103.782 304.147 + endloop + endfacet + facet normal 0.252529 -0.965856 -0.0578969 + outer loop + vertex 612.828 104.427 301.64 + vertex 613.545 104.504 303.477 + vertex 611.669 104.083 302.318 + endloop + endfacet + facet normal 0.244705 -0.969227 -0.0268168 + outer loop + vertex 612.088 104.119 303.849 + vertex 613.872 104.548 304.614 + vertex 612.35 104.155 304.951 + endloop + endfacet + facet normal 0.247886 -0.968717 -0.0118575 + outer loop + vertex 612.35 104.155 304.951 + vertex 613.872 104.548 304.614 + vertex 613.382 104.413 305.41 + endloop + endfacet + facet normal 0.246197 -0.969189 -0.0077898 + outer loop + vertex 612.35 104.155 304.951 + vertex 613.382 104.413 305.41 + vertex 611.357 103.899 305.405 + endloop + endfacet + facet normal 0.246179 -0.969218 0.00344998 + outer loop + vertex 613.382 104.413 305.41 + vertex 611.247 103.873 306.107 + vertex 611.357 103.899 305.405 + endloop + endfacet + facet normal 0.245731 -0.969336 0.00198753 + outer loop + vertex 613.382 104.413 305.41 + vertex 612.932 104.3 305.917 + vertex 611.247 103.873 306.107 + endloop + endfacet + facet normal 0.251631 -0.966535 -0.0499192 + outer loop + vertex 615.05 104.93 302.809 + vertex 615.281 104.929 304.006 + vertex 613.545 104.504 303.477 + endloop + endfacet + facet normal 0.250741 -0.968003 -0.0099784 + outer loop + vertex 615.906 105.076 304.525 + vertex 613.382 104.413 305.41 + vertex 613.872 104.548 304.614 + endloop + endfacet + facet normal 0.253666 -0.965983 -0.0503122 + outer loop + vertex 615.281 104.929 304.006 + vertex 615.05 104.93 302.809 + vertex 617.14 105.453 303.315 + endloop + endfacet + facet normal 0.2534 -0.964445 -0.0750586 + outer loop + vertex 619.925 106.268 302.238 + vertex 618.928 105.898 303.636 + vertex 617.14 105.453 303.315 + endloop + endfacet + facet normal 0.243982 -0.969308 -0.0302375 + outer loop + vertex 615.906 105.076 304.525 + vertex 615.84 105.048 304.896 + vertex 613.382 104.413 305.41 + endloop + endfacet + facet normal 0.230872 -0.964903 -0.125142 + outer loop + vertex 618.928 105.898 303.636 + vertex 621.479 106.587 303.027 + vertex 618.385 105.717 304.028 + endloop + endfacet + facet normal 0.25147 -0.967837 0.00740133 + outer loop + vertex 613.382 104.413 305.41 + vertex 615.84 105.048 304.896 + vertex 612.932 104.3 305.917 + endloop + endfacet + facet normal 0.256702 -0.965905 0.0336362 + outer loop + vertex 613.451 104.434 305.883 + vertex 615.05 104.837 305.232 + vertex 616.597 105.241 305.043 + endloop + endfacet + facet normal 0.246157 -0.969163 0.0113968 + outer loop + vertex 611.802 104.022 306.46 + vertex 613.451 104.434 305.883 + vertex 613.099 104.353 306.532 + endloop + endfacet + facet normal 0.252111 -0.967585 0.0148233 + outer loop + vertex 616.597 105.241 305.043 + vertex 613.099 104.353 306.532 + vertex 613.451 104.434 305.883 + endloop + endfacet + facet normal 0.239156 -0.970823 -0.0175524 + outer loop + vertex 616.597 105.241 305.043 + vertex 617.367 105.409 306.247 + vertex 613.099 104.353 306.532 + endloop + endfacet + facet normal 0.241108 -0.970408 0.013228 + outer loop + vertex 613.099 104.353 306.532 + vertex 617.367 105.409 306.247 + vertex 614.559 104.729 307.575 + endloop + endfacet + facet normal 0.239172 -0.970844 0.0160947 + outer loop + vertex 613.099 104.353 306.532 + vertex 614.559 104.729 307.575 + vertex 612.061 104.111 307.385 + endloop + endfacet + facet normal 0.237503 -0.971287 0.01394 + outer loop + vertex 613.099 104.353 306.532 + vertex 612.061 104.111 307.385 + vertex 610.266 103.666 307.004 + endloop + endfacet + facet normal 0.228153 -0.97186 0.0586095 + outer loop + vertex 612.061 104.111 307.385 + vertex 613.097 104.414 308.372 + vertex 610.266 103.666 307.004 + endloop + endfacet + facet normal 0.234553 -0.971065 0.0449274 + outer loop + vertex 611.706 104.076 308.327 + vertex 610.266 103.666 307.004 + vertex 613.097 104.414 308.372 + endloop + endfacet + facet normal 0.233167 -0.96946 0.0760339 + outer loop + vertex 613.484 104.572 309.205 + vertex 611.706 104.076 308.327 + vertex 613.097 104.414 308.372 + endloop + endfacet + facet normal 0.234165 -0.969258 0.0755329 + outer loop + vertex 613.097 104.414 308.372 + vertex 616.722 105.428 310.155 + vertex 613.484 104.572 309.205 + endloop + endfacet + facet normal 0.22498 -0.968556 0.106219 + outer loop + vertex 615.144 105.034 309.898 + vertex 613.484 104.572 309.205 + vertex 616.722 105.428 310.155 + endloop + endfacet + facet normal 0.221147 -0.966904 0.127241 + outer loop + vertex 616.72 105.479 310.541 + vertex 615.144 105.034 309.898 + vertex 616.722 105.428 310.155 + endloop + endfacet + facet normal 0.219626 -0.967246 0.127276 + outer loop + vertex 618.617 105.999 311.222 + vertex 616.72 105.479 310.541 + vertex 616.722 105.428 310.155 + endloop + endfacet + facet normal 0.224442 -0.967229 0.118717 + outer loop + vertex 616.722 105.428 310.155 + vertex 621.705 106.823 312.097 + vertex 618.617 105.999 311.222 + endloop + endfacet + facet normal 0.221575 -0.966666 0.128302 + outer loop + vertex 620.077 106.414 311.826 + vertex 618.617 105.999 311.222 + vertex 621.705 106.823 312.097 + endloop + endfacet + facet normal 0.216476 -0.963941 0.154777 + outer loop + vertex 621.514 106.826 312.383 + vertex 620.077 106.414 311.826 + vertex 621.705 106.823 312.097 + endloop + endfacet + facet normal 0.217113 -0.96373 0.155199 + outer loop + vertex 623.563 107.394 313.046 + vertex 621.514 106.826 312.383 + vertex 621.705 106.823 312.097 + endloop + endfacet + facet normal 0.23307 -0.964472 0.124383 + outer loop + vertex 621.705 106.823 312.097 + vertex 626.832 108.288 313.853 + vertex 623.563 107.394 313.046 + endloop + endfacet + facet normal 0.234536 -0.964817 0.118829 + outer loop + vertex 624.865 107.771 313.534 + vertex 623.563 107.394 313.046 + vertex 626.832 108.288 313.853 + endloop + endfacet + facet normal 0.226237 -0.960369 0.162813 + outer loop + vertex 625.834 108.064 313.915 + vertex 624.865 107.771 313.534 + vertex 626.832 108.288 313.853 + endloop + endfacet + facet normal 0.226715 -0.955947 0.186457 + outer loop + vertex 628.142 108.767 314.714 + vertex 625.834 108.064 313.915 + vertex 626.832 108.288 313.853 + endloop + endfacet + facet normal 0.207111 -0.949153 0.237093 + outer loop + vertex 625.834 108.064 313.915 + vertex 628.142 108.767 314.714 + vertex 626.151 108.218 314.254 + endloop + endfacet + facet normal 0.184169 -0.94837 0.258216 + outer loop + vertex 626.151 108.218 314.254 + vertex 623.668 107.491 313.356 + vertex 625.834 108.064 313.915 + endloop + endfacet + facet normal 0.159474 -0.935287 0.315922 + outer loop + vertex 626.151 108.218 314.254 + vertex 627.199 108.742 315.277 + vertex 623.668 107.491 313.356 + endloop + endfacet + facet normal 0.1846 -0.943523 0.275114 + outer loop + vertex 623.668 107.491 313.356 + vertex 627.199 108.742 315.277 + vertex 621.328 106.98 313.174 + endloop + endfacet + facet normal 0.191933 -0.956853 0.21816 + outer loop + vertex 623.668 107.491 313.356 + vertex 621.328 106.98 313.174 + vertex 619.26 106.228 311.696 + endloop + endfacet + facet normal 0.165341 -0.945593 0.280206 + outer loop + vertex 623.668 107.491 313.356 + vertex 619.26 106.228 311.696 + vertex 621.514 106.826 312.383 + endloop + endfacet + facet normal 0.189143 -0.953861 0.233184 + outer loop + vertex 621.514 106.826 312.383 + vertex 623.563 107.394 313.046 + vertex 623.668 107.491 313.356 + endloop + endfacet + facet normal 0.195056 -0.957171 0.213954 + outer loop + vertex 619.26 106.228 311.696 + vertex 621.328 106.98 313.174 + vertex 617.674 105.859 311.492 + endloop + endfacet + facet normal 0.200002 -0.962244 0.184624 + outer loop + vertex 619.26 106.228 311.696 + vertex 617.674 105.859 311.492 + vertex 615.315 105.12 310.196 + endloop + endfacet + facet normal 0.199749 -0.962178 0.185241 + outer loop + vertex 619.26 106.228 311.696 + vertex 615.315 105.12 310.196 + vertex 616.72 105.479 310.541 + endloop + endfacet + facet normal 0.188212 -0.95964 0.208968 + outer loop + vertex 616.72 105.479 310.541 + vertex 618.617 105.999 311.222 + vertex 619.26 106.228 311.696 + endloop + endfacet + facet normal 0.21574 -0.963769 0.156859 + outer loop + vertex 615.315 105.12 310.196 + vertex 617.674 105.859 311.492 + vertex 614.715 105.052 310.603 + endloop + endfacet + facet normal 0.211775 -0.96563 0.150701 + outer loop + vertex 615.315 105.12 310.196 + vertex 614.715 105.052 310.603 + vertex 611.878 104.19 309.065 + endloop + endfacet + facet normal 0.218337 -0.96693 0.131818 + outer loop + vertex 615.315 105.12 310.196 + vertex 611.878 104.19 309.065 + vertex 613.484 104.572 309.205 + endloop + endfacet + facet normal 0.232915 -0.966036 0.111919 + outer loop + vertex 611.878 104.19 309.065 + vertex 614.715 105.052 310.603 + vertex 612.181 104.378 310.058 + endloop + endfacet + facet normal 0.233099 -0.965998 0.111856 + outer loop + vertex 611.878 104.19 309.065 + vertex 612.181 104.378 310.058 + vertex 610.388 103.898 309.642 + endloop + endfacet + facet normal 0.222826 -0.97135 0.0826296 + outer loop + vertex 609.329 103.607 309.079 + vertex 611.878 104.19 309.065 + vertex 610.388 103.898 309.642 + endloop + endfacet + facet normal 0.205266 -0.971821 0.115891 + outer loop + vertex 610.388 103.898 309.642 + vertex 609.077 103.756 310.775 + vertex 609.329 103.607 309.079 + endloop + endfacet + facet normal 0.225757 -0.963987 0.140579 + outer loop + vertex 610.388 103.898 309.642 + vertex 611.062 104.249 310.968 + vertex 609.077 103.756 310.775 + endloop + endfacet + facet normal 0.222234 -0.960447 0.167791 + outer loop + vertex 611.062 104.249 310.968 + vertex 609.673 104.207 312.57 + vertex 609.077 103.756 310.775 + endloop + endfacet + facet normal 0.23052 -0.959031 0.164683 + outer loop + vertex 609.077 103.756 310.775 + vertex 609.673 104.207 312.57 + vertex 608.26 103.811 312.243 + endloop + endfacet + facet normal 0.146947 -0.981955 0.11904 + outer loop + vertex 609.077 103.756 310.775 + vertex 608.26 103.811 312.243 + vertex 607.874 103.745 312.174 + endloop + endfacet + facet normal 0.215887 -0.95157 0.218877 + outer loop + vertex 608.26 103.811 312.243 + vertex 609.673 104.207 312.57 + vertex 608.272 104.402 314.799 + endloop + endfacet + facet normal 0.12575 -0.966719 0.222804 + outer loop + vertex 608.272 104.402 314.799 + vertex 607.874 103.745 312.174 + vertex 608.26 103.811 312.243 + endloop + endfacet + facet normal 0.217051 -0.951145 0.219571 + outer loop + vertex 609.673 104.207 312.57 + vertex 611.124 105.183 315.362 + vertex 608.272 104.402 314.799 + endloop + endfacet + facet normal 0.217632 -0.951087 0.219249 + outer loop + vertex 612.791 105.072 313.228 + vertex 611.124 105.183 315.362 + vertex 609.673 104.207 312.57 + endloop + endfacet + facet normal 0.224298 -0.948352 0.224318 + outer loop + vertex 612.791 105.072 313.228 + vertex 615.12 106.314 316.147 + vertex 611.124 105.183 315.362 + endloop + endfacet + facet normal 0.212479 -0.948755 0.233918 + outer loop + vertex 616.953 106.24 314.185 + vertex 615.12 106.314 316.147 + vertex 612.791 105.072 313.228 + endloop + endfacet + facet normal 0.220514 -0.945068 0.241289 + outer loop + vertex 616.953 106.24 314.185 + vertex 619.748 107.645 317.132 + vertex 615.12 106.314 316.147 + endloop + endfacet + facet normal 0.203396 -0.944672 0.25734 + outer loop + vertex 622.084 107.641 315.272 + vertex 619.748 107.645 317.132 + vertex 616.953 106.24 314.185 + endloop + endfacet + facet normal 0.217068 -0.936767 0.274499 + outer loop + vertex 622.084 107.641 315.272 + vertex 624.481 109.066 318.239 + vertex 619.748 107.645 317.132 + endloop + endfacet + facet normal 0.191543 -0.936157 0.294825 + outer loop + vertex 626.763 109.153 317.032 + vertex 624.481 109.066 318.239 + vertex 622.084 107.641 315.272 + endloop + endfacet + facet normal 0.202277 -0.941194 0.270623 + outer loop + vertex 626.763 109.153 317.032 + vertex 622.084 107.641 315.272 + vertex 627.199 108.742 315.277 + endloop + endfacet + facet normal 0.219145 -0.936512 0.273716 + outer loop + vertex 626.763 109.153 317.032 + vertex 627.199 108.742 315.277 + vertex 631.114 110.365 317.694 + endloop + endfacet + facet normal 0.215554 -0.935774 0.279039 + outer loop + vertex 627.199 108.742 315.277 + vertex 635.139 111.158 317.246 + vertex 631.114 110.365 317.694 + endloop + endfacet + facet normal 0.212951 -0.91722 0.336689 + outer loop + vertex 626.763 109.153 317.032 + vertex 629.357 110.576 319.267 + vertex 624.481 109.066 318.239 + endloop + endfacet + facet normal 0.201919 -0.91537 0.348319 + outer loop + vertex 631.114 110.365 317.694 + vertex 629.357 110.576 319.267 + vertex 626.763 109.153 317.032 + endloop + endfacet + facet normal 0.220962 -0.903211 0.367948 + outer loop + vertex 631.114 110.365 317.694 + vertex 634.573 112.102 319.882 + vertex 629.357 110.576 319.267 + endloop + endfacet + facet normal 0.20065 -0.89659 0.394798 + outer loop + vertex 635.005 111.59 318.5 + vertex 634.573 112.102 319.882 + vertex 631.114 110.365 317.694 + endloop + endfacet + facet normal 0.21815 -0.915258 0.338695 + outer loop + vertex 635.005 111.59 318.5 + vertex 631.114 110.365 317.694 + vertex 635.139 111.158 317.246 + endloop + endfacet + facet normal 0.254407 -0.905648 0.339233 + outer loop + vertex 635.139 111.158 317.246 + vertex 640.395 113.67 320.011 + vertex 635.005 111.59 318.5 + endloop + endfacet + facet normal 0.204898 -0.88616 0.415617 + outer loop + vertex 643.33 113.717 318.664 + vertex 640.395 113.67 320.011 + vertex 635.139 111.158 317.246 + endloop + endfacet + facet normal 0.224205 -0.859891 0.458606 + outer loop + vertex 643.33 113.717 318.664 + vertex 649.073 116.512 321.096 + vertex 640.395 113.67 320.011 + endloop + endfacet + facet normal 0.213637 -0.853183 0.475855 + outer loop + vertex 651.356 116.326 319.738 + vertex 649.073 116.512 321.096 + vertex 643.33 113.717 318.664 + endloop + endfacet + facet normal 0.234009 -0.829652 0.50687 + outer loop + vertex 651.356 116.326 319.738 + vertex 657.305 119.339 321.924 + vertex 649.073 116.512 321.096 + endloop + endfacet + facet normal 0.236604 -0.831588 0.502474 + outer loop + vertex 659.118 119.002 320.512 + vertex 657.305 119.339 321.924 + vertex 651.356 116.326 319.738 + endloop + endfacet + facet normal 0.25601 -0.813008 0.52295 + outer loop + vertex 659.118 119.002 320.512 + vertex 665.406 122.247 322.478 + vertex 657.305 119.339 321.924 + endloop + endfacet + facet normal 0.253511 -0.8078 0.532157 + outer loop + vertex 665.406 122.247 322.478 + vertex 664.338 123.279 324.555 + vertex 657.305 119.339 321.924 + endloop + endfacet + facet normal 0.258915 -0.8117 0.523551 + outer loop + vertex 657.305 119.339 321.924 + vertex 664.338 123.279 324.555 + vertex 655.917 120.227 323.986 + endloop + endfacet + facet normal 0.23248 -0.826773 0.512249 + outer loop + vertex 657.305 119.339 321.924 + vertex 655.917 120.227 323.986 + vertex 649.073 116.512 321.096 + endloop + endfacet + facet normal 0.244176 -0.834321 0.494253 + outer loop + vertex 649.073 116.512 321.096 + vertex 655.917 120.227 323.986 + vertex 647.609 117.395 323.311 + endloop + endfacet + facet normal 0.217531 -0.848558 0.482317 + outer loop + vertex 649.073 116.512 321.096 + vertex 647.609 117.395 323.311 + vertex 640.395 113.67 320.011 + endloop + endfacet + facet normal 0.24048 -0.861646 0.446918 + outer loop + vertex 640.395 113.67 320.011 + vertex 647.609 117.395 323.311 + vertex 639.983 114.978 322.754 + endloop + endfacet + facet normal 0.223454 -0.866373 0.446615 + outer loop + vertex 640.395 113.67 320.011 + vertex 639.983 114.978 322.754 + vertex 634.573 112.102 319.882 + endloop + endfacet + facet normal 0.230383 -0.869572 0.43677 + outer loop + vertex 633.256 112.927 322.219 + vertex 634.573 112.102 319.882 + vertex 639.983 114.978 322.754 + endloop + endfacet + facet normal 0.207172 -0.880017 0.427375 + outer loop + vertex 634.573 112.102 319.882 + vertex 633.256 112.927 322.219 + vertex 629.357 110.576 319.267 + endloop + endfacet + facet normal 0.221313 -0.88397 0.411846 + outer loop + vertex 629.357 110.576 319.267 + vertex 633.256 112.927 322.219 + vertex 627.042 110.937 321.287 + endloop + endfacet + facet normal 0.197181 -0.900677 0.38717 + outer loop + vertex 629.357 110.576 319.267 + vertex 627.042 110.937 321.287 + vertex 624.481 109.066 318.239 + endloop + endfacet + facet normal 0.220636 -0.902923 0.368848 + outer loop + vertex 624.481 109.066 318.239 + vertex 627.042 110.937 321.287 + vertex 622.25 109.192 319.881 + endloop + endfacet + facet normal 0.197163 -0.920155 0.338292 + outer loop + vertex 624.481 109.066 318.239 + vertex 622.25 109.192 319.881 + vertex 619.748 107.645 317.132 + endloop + endfacet + facet normal 0.209211 -0.921242 0.327939 + outer loop + vertex 619.748 107.645 317.132 + vertex 622.25 109.192 319.881 + vertex 617.735 108.024 319.482 + endloop + endfacet + facet normal 0.198508 -0.926518 0.319623 + outer loop + vertex 619.748 107.645 317.132 + vertex 617.735 108.024 319.482 + vertex 615.12 106.314 316.147 + endloop + endfacet + facet normal 0.226845 -0.927285 0.297799 + outer loop + vertex 615.12 106.314 316.147 + vertex 617.735 108.024 319.482 + vertex 613.29 106.538 318.241 + endloop + endfacet + facet normal 0.209195 -0.935936 0.283303 + outer loop + vertex 615.12 106.314 316.147 + vertex 613.29 106.538 318.241 + vertex 611.124 105.183 315.362 + endloop + endfacet + facet normal 0.209055 -0.935936 0.283408 + outer loop + vertex 611.124 105.183 315.362 + vertex 613.29 106.538 318.241 + vertex 609.942 105.852 318.445 + endloop + endfacet + facet normal 0.201424 -0.938331 0.281004 + outer loop + vertex 611.124 105.183 315.362 + vertex 609.942 105.852 318.445 + vertex 608.272 104.402 314.799 + endloop + endfacet + facet normal 0.230214 -0.935845 0.266826 + outer loop + vertex 608.272 104.402 314.799 + vertex 609.942 105.852 318.445 + vertex 607.412 105.187 318.293 + endloop + endfacet + facet normal 0.237805 -0.933557 0.268179 + outer loop + vertex 608.272 104.402 314.799 + vertex 607.412 105.187 318.293 + vertex 606.667 104.374 316.126 + endloop + endfacet + facet normal 0.188296 -0.939145 0.287316 + outer loop + vertex 605.991 105.529 320.342 + vertex 606.667 104.374 316.126 + vertex 607.412 105.187 318.293 + endloop + endfacet + facet normal 0.197246 -0.883631 0.424607 + outer loop + vertex 622.25 109.192 319.881 + vertex 627.042 110.937 321.287 + vertex 622.826 111.027 323.432 + endloop + endfacet + facet normal 0.191003 -0.884338 0.425986 + outer loop + vertex 622.25 109.192 319.881 + vertex 622.826 111.027 323.432 + vertex 617.735 108.024 319.482 + endloop + endfacet + facet normal 0.218939 -0.891894 0.395716 + outer loop + vertex 622.826 111.027 323.432 + vertex 614.479 108.506 322.368 + vertex 617.735 108.024 319.482 + endloop + endfacet + facet normal 0.198189 -0.90575 0.374618 + outer loop + vertex 613.29 106.538 318.241 + vertex 617.735 108.024 319.482 + vertex 614.479 108.506 322.368 + endloop + endfacet + facet normal 0.208048 -0.904879 0.371362 + outer loop + vertex 613.29 106.538 318.241 + vertex 614.479 108.506 322.368 + vertex 609.942 105.852 318.445 + endloop + endfacet + facet normal 0.228694 -0.908445 0.349894 + outer loop + vertex 614.479 108.506 322.368 + vertex 608.376 107.048 322.572 + vertex 609.942 105.852 318.445 + endloop + endfacet + facet normal 0.219085 -0.91183 0.34723 + outer loop + vertex 607.412 105.187 318.293 + vertex 609.942 105.852 318.445 + vertex 608.376 107.048 322.572 + endloop + endfacet + facet normal 0.214849 -0.862427 0.458322 + outer loop + vertex 631.163 113.953 325.03 + vertex 622.826 111.027 323.432 + vertex 627.042 110.937 321.287 + endloop + endfacet + facet normal 0.205442 -0.860146 0.466842 + outer loop + vertex 633.256 112.927 322.219 + vertex 631.163 113.953 325.03 + vertex 627.042 110.937 321.287 + endloop + endfacet + facet normal 0.226555 -0.848469 0.478303 + outer loop + vertex 633.256 112.927 322.219 + vertex 638.822 116.419 325.777 + vertex 631.163 113.953 325.03 + endloop + endfacet + facet normal 0.219012 -0.845429 0.487118 + outer loop + vertex 639.983 114.978 322.754 + vertex 638.822 116.419 325.777 + vertex 633.256 112.927 322.219 + endloop + endfacet + facet normal 0.239235 -0.837581 0.491147 + outer loop + vertex 639.983 114.978 322.754 + vertex 646.641 118.943 326.273 + vertex 638.822 116.419 325.777 + endloop + endfacet + facet normal 0.226282 -0.830973 0.508213 + outer loop + vertex 647.609 117.395 323.311 + vertex 646.641 118.943 326.273 + vertex 639.983 114.978 322.754 + endloop + endfacet + facet normal 0.249424 -0.822411 0.5113 + outer loop + vertex 647.609 117.395 323.311 + vertex 654.858 121.735 326.755 + vertex 646.641 118.943 326.273 + endloop + endfacet + facet normal 0.233939 -0.813417 0.532566 + outer loop + vertex 655.917 120.227 323.986 + vertex 654.858 121.735 326.755 + vertex 647.609 117.395 323.311 + endloop + endfacet + facet normal 0.261336 -0.802144 0.536907 + outer loop + vertex 655.917 120.227 323.986 + vertex 663.387 124.828 327.225 + vertex 654.858 121.735 326.755 + endloop + endfacet + facet normal 0.250505 -0.778208 0.575881 + outer loop + vertex 663.387 124.828 327.225 + vertex 662.492 126.872 330.376 + vertex 654.858 121.735 326.755 + endloop + endfacet + facet normal 0.261082 -0.784492 0.562502 + outer loop + vertex 654.858 121.735 326.755 + vertex 662.492 126.872 330.376 + vertex 653.916 123.76 330.016 + endloop + endfacet + facet normal 0.236633 -0.793327 0.560926 + outer loop + vertex 654.858 121.735 326.755 + vertex 653.916 123.76 330.016 + vertex 646.641 118.943 326.273 + endloop + endfacet + facet normal 0.248911 -0.800103 0.545782 + outer loop + vertex 646.641 118.943 326.273 + vertex 653.916 123.76 330.016 + vertex 645.608 120.917 329.637 + endloop + endfacet + facet normal 0.226422 -0.808208 0.543629 + outer loop + vertex 646.641 118.943 326.273 + vertex 645.608 120.917 329.637 + vertex 638.822 116.419 325.777 + endloop + endfacet + facet normal 0.237011 -0.813462 0.531136 + outer loop + vertex 638.822 116.419 325.777 + vertex 645.608 120.917 329.637 + vertex 637.387 118.22 329.175 + endloop + endfacet + facet normal 0.21367 -0.822994 0.526333 + outer loop + vertex 638.822 116.419 325.777 + vertex 637.387 118.22 329.175 + vertex 631.163 113.953 325.03 + endloop + endfacet + facet normal 0.22667 -0.828343 0.512317 + outer loop + vertex 631.163 113.953 325.03 + vertex 637.387 118.22 329.175 + vertex 628.904 115.451 328.452 + endloop + endfacet + facet normal 0.199682 -0.842319 0.500625 + outer loop + vertex 631.163 113.953 325.03 + vertex 628.904 115.451 328.452 + vertex 622.826 111.027 323.432 + endloop + endfacet + facet normal 0.226909 -0.850365 0.474754 + outer loop + vertex 622.826 111.027 323.432 + vertex 628.904 115.451 328.452 + vertex 620.233 112.681 327.634 + endloop + endfacet + facet normal 0.201428 -0.862694 0.463881 + outer loop + vertex 622.826 111.027 323.432 + vertex 620.233 112.681 327.634 + vertex 614.479 108.506 322.368 + endloop + endfacet + facet normal 0.2334 -0.869846 0.434617 + outer loop + vertex 614.479 108.506 322.368 + vertex 620.233 112.681 327.634 + vertex 612.503 110.429 327.278 + endloop + endfacet + facet normal 0.223171 -0.873801 0.432049 + outer loop + vertex 614.479 108.506 322.368 + vertex 612.503 110.429 327.278 + vertex 608.376 107.048 322.572 + endloop + endfacet + facet normal 0.241299 -0.875957 0.417701 + outer loop + vertex 608.376 107.048 322.572 + vertex 612.503 110.429 327.278 + vertex 606.702 109.124 327.893 + endloop + endfacet + facet normal 0.24841 -0.754746 0.607166 + outer loop + vertex 662.492 126.872 330.376 + vertex 661.631 129.347 333.805 + vertex 653.916 123.76 330.016 + endloop + endfacet + facet normal 0.258227 -0.760544 0.595728 + outer loop + vertex 653.916 123.76 330.016 + vertex 661.631 129.347 333.805 + vertex 653.018 126.207 333.529 + endloop + endfacet + facet normal 0.235723 -0.768163 0.595282 + outer loop + vertex 653.916 123.76 330.016 + vertex 653.018 126.207 333.529 + vertex 645.608 120.917 329.637 + endloop + endfacet + facet normal 0.247141 -0.774553 0.582228 + outer loop + vertex 645.608 120.917 329.637 + vertex 653.018 126.207 333.529 + vertex 644.598 123.302 333.239 + endloop + endfacet + facet normal 0.224039 -0.782467 0.580991 + outer loop + vertex 645.608 120.917 329.637 + vertex 644.598 123.302 333.239 + vertex 637.387 118.22 329.175 + endloop + endfacet + facet normal 0.235532 -0.788502 0.568146 + outer loop + vertex 637.387 118.22 329.175 + vertex 644.598 123.302 333.239 + vertex 636.053 120.488 332.876 + endloop + endfacet + facet normal 0.212049 -0.797316 0.565086 + outer loop + vertex 637.387 118.22 329.175 + vertex 636.053 120.488 332.876 + vertex 628.904 115.451 328.452 + endloop + endfacet + facet normal 0.230038 -0.805804 0.545676 + outer loop + vertex 628.904 115.451 328.452 + vertex 636.053 120.488 332.876 + vertex 627.18 117.622 332.384 + endloop + endfacet + facet normal 0.209143 -0.814421 0.541274 + outer loop + vertex 628.904 115.451 328.452 + vertex 627.18 117.622 332.384 + vertex 620.233 112.681 327.634 + endloop + endfacet + facet normal 0.23236 -0.823798 0.517074 + outer loop + vertex 620.233 112.681 327.634 + vertex 627.18 117.622 332.384 + vertex 618.421 114.858 331.917 + endloop + endfacet + facet normal 0.218033 -0.829631 0.513979 + outer loop + vertex 620.233 112.681 327.634 + vertex 618.421 114.858 331.917 + vertex 612.503 110.429 327.278 + endloop + endfacet + facet normal 0.237363 -0.83575 0.495157 + outer loop + vertex 612.503 110.429 327.278 + vertex 618.421 114.858 331.917 + vertex 610.912 112.673 331.828 + endloop + endfacet + facet normal 0.240275 -0.834638 0.495627 + outer loop + vertex 612.503 110.429 327.278 + vertex 610.912 112.673 331.828 + vertex 606.702 109.124 327.893 + endloop + endfacet + facet normal 0.237137 -0.833922 0.498338 + outer loop + vertex 606.702 109.124 327.893 + vertex 610.912 112.673 331.828 + vertex 605.789 111.661 332.573 + endloop + endfacet + facet normal 0.272107 -0.822719 0.499091 + outer loop + vertex 606.702 109.124 327.893 + vertex 605.789 111.661 332.573 + vertex 603.518 109.634 330.471 + endloop + endfacet + facet normal 0.253299 -0.840287 0.47933 + outer loop + vertex 603.518 109.634 330.471 + vertex 603.987 108.07 327.48 + vertex 606.702 109.124 327.893 + endloop + endfacet + facet normal 0.235675 -0.845438 0.479262 + outer loop + vertex 603.987 108.07 327.48 + vertex 603.518 109.634 330.471 + vertex 600.982 108.361 329.471 + endloop + endfacet + facet normal 0.244858 -0.727814 0.64057 + outer loop + vertex 661.631 129.347 333.805 + vertex 660.838 132.202 337.352 + vertex 653.018 126.207 333.529 + endloop + endfacet + facet normal 0.253384 -0.733004 0.63127 + outer loop + vertex 653.018 126.207 333.529 + vertex 660.838 132.202 337.352 + vertex 652.234 129.05 337.146 + endloop + endfacet + facet normal 0.233241 -0.739217 0.631788 + outer loop + vertex 653.018 126.207 333.529 + vertex 652.234 129.05 337.146 + vertex 644.598 123.302 333.239 + endloop + endfacet + facet normal 0.243448 -0.745265 0.620736 + outer loop + vertex 644.598 123.302 333.239 + vertex 652.234 129.05 337.146 + vertex 643.757 126.119 336.951 + endloop + endfacet + facet normal 0.221283 -0.752045 0.620856 + outer loop + vertex 644.598 123.302 333.239 + vertex 643.757 126.119 336.951 + vertex 636.053 120.488 332.876 + endloop + endfacet + facet normal 0.233242 -0.759007 0.607871 + outer loop + vertex 636.053 120.488 332.876 + vertex 643.757 126.119 336.951 + vertex 635.038 123.246 336.709 + endloop + endfacet + facet normal 0.213553 -0.765317 0.607195 + outer loop + vertex 636.053 120.488 332.876 + vertex 635.038 123.246 336.709 + vertex 627.18 117.622 332.384 + endloop + endfacet + facet normal 0.22948 -0.774225 0.589843 + outer loop + vertex 627.18 117.622 332.384 + vertex 635.038 123.246 336.709 + vertex 625.979 120.307 336.376 + endloop + endfacet + facet normal 0.214499 -0.779325 0.588764 + outer loop + vertex 627.18 117.622 332.384 + vertex 625.979 120.307 336.376 + vertex 618.421 114.858 331.917 + endloop + endfacet + facet normal 0.230224 -0.787344 0.571914 + outer loop + vertex 618.421 114.858 331.917 + vertex 625.979 120.307 336.376 + vertex 617.17 117.5 336.057 + endloop + endfacet + facet normal 0.2231 -0.789812 0.571335 + outer loop + vertex 618.421 114.858 331.917 + vertex 617.17 117.5 336.057 + vertex 610.912 112.673 331.828 + endloop + endfacet + facet normal 0.232352 -0.793741 0.562128 + outer loop + vertex 610.912 112.673 331.828 + vertex 617.17 117.5 336.057 + vertex 609.807 115.324 336.029 + endloop + endfacet + facet normal 0.238139 -0.791809 0.56243 + outer loop + vertex 610.912 112.673 331.828 + vertex 609.807 115.324 336.029 + vertex 605.789 111.661 332.573 + endloop + endfacet + facet normal 0.233095 -0.790281 0.566676 + outer loop + vertex 605.789 111.661 332.573 + vertex 609.807 115.324 336.029 + vertex 604.811 114.211 336.531 + endloop + endfacet + facet normal 0.260756 -0.722741 0.640041 + outer loop + vertex 661.631 129.347 333.805 + vertex 669.69 135.51 337.481 + vertex 660.838 132.202 337.352 + endloop + endfacet + facet normal 0.247793 -0.68962 0.680457 + outer loop + vertex 669.69 135.51 337.481 + vertex 668.989 138.76 341.03 + vertex 660.838 132.202 337.352 + endloop + endfacet + facet normal 0.253464 -0.693355 0.674548 + outer loop + vertex 660.838 132.202 337.352 + vertex 668.989 138.76 341.03 + vertex 660.153 135.417 340.915 + endloop + endfacet + facet normal 0.239293 -0.697441 0.675511 + outer loop + vertex 660.838 132.202 337.352 + vertex 660.153 135.417 340.915 + vertex 652.234 129.05 337.146 + endloop + endfacet + facet normal 0.246834 -0.702242 0.667779 + outer loop + vertex 652.234 129.05 337.146 + vertex 660.153 135.417 340.915 + vertex 651.595 132.275 340.773 + endloop + endfacet + facet normal 0.229142 -0.707089 0.668969 + outer loop + vertex 652.234 129.05 337.146 + vertex 651.595 132.275 340.773 + vertex 643.757 126.119 336.951 + endloop + endfacet + facet normal 0.237044 -0.712106 0.660844 + outer loop + vertex 643.757 126.119 336.951 + vertex 651.595 132.275 340.773 + vertex 643.101 129.344 340.662 + endloop + endfacet + facet normal 0.217964 -0.7172 0.661903 + outer loop + vertex 643.757 126.119 336.951 + vertex 643.101 129.344 340.662 + vertex 635.038 123.246 336.709 + endloop + endfacet + facet normal 0.228781 -0.724161 0.650576 + outer loop + vertex 635.038 123.246 336.709 + vertex 643.101 129.344 340.662 + vertex 634.303 126.431 340.512 + endloop + endfacet + facet normal 0.212429 -0.728615 0.651148 + outer loop + vertex 635.038 123.246 336.709 + vertex 634.303 126.431 340.512 + vertex 625.979 120.307 336.376 + endloop + endfacet + facet normal 0.223921 -0.735971 0.63891 + outer loop + vertex 625.979 120.307 336.376 + vertex 634.303 126.431 340.512 + vertex 625.16 123.441 340.272 + endloop + endfacet + facet normal 0.212452 -0.7392 0.639099 + outer loop + vertex 625.979 120.307 336.376 + vertex 625.16 123.441 340.272 + vertex 617.17 117.5 336.057 + endloop + endfacet + facet normal 0.223409 -0.745785 0.627609 + outer loop + vertex 617.17 117.5 336.057 + vertex 625.16 123.441 340.272 + vertex 616.325 120.591 340.032 + endloop + endfacet + facet normal 0.218355 -0.747236 0.627662 + outer loop + vertex 617.17 117.5 336.057 + vertex 616.325 120.591 340.032 + vertex 609.807 115.324 336.029 + endloop + endfacet + facet normal 0.225192 -0.750696 0.621083 + outer loop + vertex 609.807 115.324 336.029 + vertex 616.325 120.591 340.032 + vertex 608.925 118.356 340.013 + endloop + endfacet + facet normal 0.229467 -0.74942 0.621059 + outer loop + vertex 609.807 115.324 336.029 + vertex 608.925 118.356 340.013 + vertex 604.811 114.211 336.531 + endloop + endfacet + facet normal 0.230087 -0.74963 0.620576 + outer loop + vertex 604.811 114.211 336.531 + vertex 608.925 118.356 340.013 + vertex 603.634 117.093 340.45 + endloop + endfacet + facet normal 0.250367 -0.742434 0.621375 + outer loop + vertex 604.811 114.211 336.531 + vertex 603.634 117.093 340.45 + vertex 601.849 113.974 337.442 + endloop + endfacet + facet normal 0.267016 -0.743727 0.61284 + outer loop + vertex 601.13 115.836 340.015 + vertex 601.849 113.974 337.442 + vertex 603.634 117.093 340.45 + endloop + endfacet + facet normal 0.228965 -0.757093 0.611871 + outer loop + vertex 601.849 113.974 337.442 + vertex 601.13 115.836 340.015 + vertex 599.106 114.495 339.113 + endloop + endfacet + facet normal 0.255874 -0.687242 0.679873 + outer loop + vertex 669.69 135.51 337.481 + vertex 677.825 141.897 340.876 + vertex 668.989 138.76 341.03 + endloop + endfacet + facet normal 0.245525 -0.65646 0.713286 + outer loop + vertex 677.825 141.897 340.876 + vertex 677.046 145.444 344.408 + vertex 668.989 138.76 341.03 + endloop + endfacet + facet normal 0.244908 -0.656025 0.713899 + outer loop + vertex 668.989 138.76 341.03 + vertex 677.046 145.444 344.408 + vertex 668.333 142.293 344.502 + endloop + endfacet + facet normal 0.239395 -0.657528 0.714386 + outer loop + vertex 668.989 138.76 341.03 + vertex 668.333 142.293 344.502 + vertex 660.153 135.417 340.915 + endloop + endfacet + facet normal 0.242817 -0.659867 0.711066 + outer loop + vertex 660.153 135.417 340.915 + vertex 668.333 142.293 344.502 + vertex 659.576 138.974 344.412 + endloop + endfacet + facet normal 0.231595 -0.662741 0.712137 + outer loop + vertex 660.153 135.417 340.915 + vertex 659.576 138.974 344.412 + vertex 651.595 132.275 340.773 + endloop + endfacet + facet normal 0.237524 -0.666716 0.706451 + outer loop + vertex 651.595 132.275 340.773 + vertex 659.576 138.974 344.412 + vertex 651.055 135.852 344.33 + endloop + endfacet + facet normal 0.222068 -0.670491 0.707903 + outer loop + vertex 651.595 132.275 340.773 + vertex 651.055 135.852 344.33 + vertex 643.101 129.344 340.662 + endloop + endfacet + facet normal 0.228351 -0.674748 0.701834 + outer loop + vertex 643.101 129.344 340.662 + vertex 651.055 135.852 344.33 + vertex 642.559 132.922 344.278 + endloop + endfacet + facet normal 0.212751 -0.678455 0.703161 + outer loop + vertex 643.101 129.344 340.662 + vertex 642.559 132.922 344.278 + vertex 634.303 126.431 340.512 + endloop + endfacet + facet normal 0.220594 -0.683927 0.695401 + outer loop + vertex 634.303 126.431 340.512 + vertex 642.559 132.922 344.278 + vertex 633.727 129.983 344.189 + endloop + endfacet + facet normal 0.206489 -0.687278 0.696428 + outer loop + vertex 634.303 126.431 340.512 + vertex 633.727 129.983 344.189 + vertex 625.16 123.441 340.272 + endloop + endfacet + facet normal 0.215475 -0.693617 0.687362 + outer loop + vertex 625.16 123.441 340.272 + vertex 633.727 129.983 344.189 + vertex 624.541 126.957 344.015 + endloop + endfacet + facet normal 0.205704 -0.695981 0.687966 + outer loop + vertex 625.16 123.441 340.272 + vertex 624.541 126.957 344.015 + vertex 616.325 120.591 340.032 + endloop + endfacet + facet normal 0.214577 -0.701923 0.679162 + outer loop + vertex 616.325 120.591 340.032 + vertex 624.541 126.957 344.015 + vertex 615.681 124.086 343.847 + endloop + endfacet + facet normal 0.210604 -0.702905 0.67939 + outer loop + vertex 616.325 120.591 340.032 + vertex 615.681 124.086 343.847 + vertex 608.925 118.356 340.013 + endloop + endfacet + facet normal 0.215799 -0.705871 0.674668 + outer loop + vertex 608.925 118.356 340.013 + vertex 615.681 124.086 343.847 + vertex 608.289 121.893 343.918 + endloop + endfacet + facet normal 0.223605 -0.703916 0.674168 + outer loop + vertex 608.925 118.356 340.013 + vertex 608.289 121.893 343.918 + vertex 603.634 117.093 340.45 + endloop + endfacet + facet normal 0.218532 -0.701791 0.678037 + outer loop + vertex 603.634 117.093 340.45 + vertex 608.289 121.893 343.918 + vertex 603.11 120.902 344.56 + endloop + endfacet + facet normal 0.24483 -0.656664 0.713337 + outer loop + vertex 677.825 141.897 340.876 + vertex 685.376 148.029 343.929 + vertex 677.046 145.444 344.408 + endloop + endfacet + facet normal 0.251188 -0.661263 0.70685 + outer loop + vertex 686.001 144.106 340.037 + vertex 685.376 148.029 343.929 + vertex 677.825 141.897 340.876 + endloop + endfacet + facet normal 0.255357 -0.686625 0.68069 + outer loop + vertex 678.258 138.454 337.24 + vertex 686.001 144.106 340.037 + vertex 677.825 141.897 340.876 + endloop + endfacet + facet normal 0.265531 -0.694586 0.668613 + outer loop + vertex 685.231 140.098 336.178 + vertex 686.001 144.106 340.037 + vertex 678.258 138.454 337.24 + endloop + endfacet + facet normal 0.266847 -0.713765 0.647558 + outer loop + vertex 678.47 135.395 333.781 + vertex 685.231 140.098 336.178 + vertex 678.258 138.454 337.24 + endloop + endfacet + facet normal 0.262925 -0.714693 0.648139 + outer loop + vertex 678.47 135.395 333.781 + vertex 678.258 138.454 337.24 + vertex 670.372 132.585 333.968 + endloop + endfacet + facet normal 0.27136 -0.741277 0.613899 + outer loop + vertex 671.109 130.083 330.621 + vertex 678.47 135.395 333.781 + vertex 670.372 132.585 333.968 + endloop + endfacet + facet normal 0.260189 -0.745002 0.614226 + outer loop + vertex 671.109 130.083 330.621 + vertex 670.372 132.585 333.968 + vertex 662.492 126.872 330.376 + endloop + endfacet + facet normal 0.271713 -0.741507 0.613465 + outer loop + vertex 679.083 132.986 330.598 + vertex 678.47 135.395 333.781 + vertex 671.109 130.083 330.621 + endloop + endfacet + facet normal 0.279132 -0.762112 0.584184 + outer loop + vertex 671.92 128.026 327.55 + vertex 679.083 132.986 330.598 + vertex 671.109 130.083 330.621 + endloop + endfacet + facet normal 0.265304 -0.767214 0.583949 + outer loop + vertex 671.92 128.026 327.55 + vertex 671.109 130.083 330.621 + vertex 663.387 124.828 327.225 + endloop + endfacet + facet normal 0.273689 -0.786502 0.553633 + outer loop + vertex 664.338 123.279 324.555 + vertex 671.92 128.026 327.55 + vertex 663.387 124.828 327.225 + endloop + endfacet + facet normal 0.269645 -0.783745 0.559496 + outer loop + vertex 672.704 126.407 324.903 + vertex 671.92 128.026 327.55 + vertex 664.338 123.279 324.555 + endloop + endfacet + facet normal 0.285335 -0.777551 0.560356 + outer loop + vertex 672.704 126.407 324.903 + vertex 679.938 130.977 327.561 + vertex 671.92 128.026 327.55 + endloop + endfacet + facet normal 0.283015 -0.775893 0.56382 + outer loop + vertex 680.465 129.224 324.885 + vertex 679.938 130.977 327.561 + vertex 672.704 126.407 324.903 + endloop + endfacet + facet normal 0.287393 -0.788081 0.544366 + outer loop + vertex 673.587 125.269 322.791 + vertex 680.465 129.224 324.885 + vertex 672.704 126.407 324.903 + endloop + endfacet + facet normal 0.272965 -0.79483 0.541973 + outer loop + vertex 673.587 125.269 322.791 + vertex 672.704 126.407 324.903 + vertex 665.406 122.247 322.478 + endloop + endfacet + facet normal 0.277086 -0.804298 0.52567 + outer loop + vertex 666.619 121.569 320.801 + vertex 673.587 125.269 322.791 + vertex 665.406 122.247 322.478 + endloop + endfacet + facet normal 0.278007 -0.805105 0.523945 + outer loop + vertex 675.112 124.732 321.156 + vertex 673.587 125.269 322.791 + vertex 666.619 121.569 320.801 + endloop + endfacet + facet normal 0.290144 -0.795421 0.532092 + outer loop + vertex 675.112 124.732 321.156 + vertex 681.316 128.143 322.871 + vertex 673.587 125.269 322.791 + endloop + endfacet + facet normal 0.296094 -0.800618 0.520903 + outer loop + vertex 683.477 127.879 321.238 + vertex 681.316 128.143 322.871 + vertex 675.112 124.732 321.156 + endloop + endfacet + facet normal 0.302535 -0.79336 0.528254 + outer loop + vertex 683.477 127.879 321.238 + vertex 687.111 130.348 322.865 + vertex 681.316 128.143 322.871 + endloop + endfacet + facet normal 0.299879 -0.786345 0.540124 + outer loop + vertex 687.111 130.348 322.865 + vertex 686.142 131.004 324.358 + vertex 681.316 128.143 322.871 + endloop + endfacet + facet normal 0.296363 -0.783531 0.54612 + outer loop + vertex 681.316 128.143 322.871 + vertex 686.142 131.004 324.358 + vertex 680.465 129.224 324.885 + endloop + endfacet + facet normal 0.294335 -0.771929 0.563464 + outer loop + vertex 686.142 131.004 324.358 + vertex 686.715 133.015 326.814 + vertex 680.465 129.224 324.885 + endloop + endfacet + facet normal 0.30998 -0.76975 0.55803 + outer loop + vertex 686.715 133.015 326.814 + vertex 686.142 131.004 324.358 + vertex 692.043 133.168 324.065 + endloop + endfacet + facet normal 0.311836 -0.766233 0.561823 + outer loop + vertex 692.043 133.168 324.065 + vertex 691.749 136.633 328.953 + vertex 686.715 133.015 326.814 + endloop + endfacet + facet normal 0.299037 -0.758548 0.578948 + outer loop + vertex 686.023 135.402 330.299 + vertex 686.715 133.015 326.814 + vertex 691.749 136.633 328.953 + endloop + endfacet + facet normal 0.300339 -0.741184 0.600369 + outer loop + vertex 691.749 136.633 328.953 + vertex 690.358 139.809 333.57 + vertex 686.023 135.402 330.299 + endloop + endfacet + facet normal 0.295793 -0.739719 0.604419 + outer loop + vertex 684.438 137.068 333.113 + vertex 686.023 135.402 330.299 + vertex 690.358 139.809 333.57 + endloop + endfacet + facet normal 0.283173 -0.717747 0.636123 + outer loop + vertex 685.231 140.098 336.178 + vertex 684.438 137.068 333.113 + vertex 690.358 139.809 333.57 + endloop + endfacet + facet normal 0.284433 -0.715287 0.638328 + outer loop + vertex 690.358 139.809 333.57 + vertex 690.647 143.731 337.836 + vertex 685.231 140.098 336.178 + endloop + endfacet + facet normal 0.285532 -0.7456 0.602123 + outer loop + vertex 686.023 135.402 330.299 + vertex 684.438 137.068 333.113 + vertex 679.083 132.986 330.598 + endloop + endfacet + facet normal 0.289321 -0.758784 0.583558 + outer loop + vertex 679.938 130.977 327.561 + vertex 686.023 135.402 330.299 + vertex 679.083 132.986 330.598 + endloop + endfacet + facet normal 0.292727 -0.76079 0.579231 + outer loop + vertex 686.715 133.015 326.814 + vertex 686.023 135.402 330.299 + vertex 679.938 130.977 327.561 + endloop + endfacet + facet normal 0.312434 -0.778247 0.544717 + outer loop + vertex 686.142 131.004 324.358 + vertex 687.111 130.348 322.865 + vertex 692.043 133.168 324.065 + endloop + endfacet + facet normal 0.316938 -0.782435 0.536047 + outer loop + vertex 687.111 130.348 322.865 + vertex 689.503 130.446 321.594 + vertex 692.043 133.168 324.065 + endloop + endfacet + facet normal 0.341182 -0.786191 0.515266 + outer loop + vertex 692.04 131.059 320.849 + vertex 692.043 133.168 324.065 + vertex 689.503 130.446 321.594 + endloop + endfacet + facet normal 0.339765 -0.794144 0.503881 + outer loop + vertex 690.019 130.069 320.651 + vertex 692.04 131.059 320.849 + vertex 689.503 130.446 321.594 + endloop + endfacet + facet normal 0.329345 -0.800504 0.500724 + outer loop + vertex 689.044 129.632 320.593 + vertex 690.019 130.069 320.651 + vertex 689.503 130.446 321.594 + endloop + endfacet + facet normal 0.315562 -0.801542 0.507889 + outer loop + vertex 687.277 128.967 320.643 + vertex 689.044 129.632 320.593 + vertex 689.503 130.446 321.594 + endloop + endfacet + facet normal 0.330408 -0.848022 0.414353 + outer loop + vertex 689.044 129.632 320.593 + vertex 687.277 128.967 320.643 + vertex 686.26 127.996 319.466 + endloop + endfacet + facet normal 0.342278 -0.848193 0.404245 + outer loop + vertex 687.277 128.967 320.643 + vertex 685.116 127.957 320.354 + vertex 686.26 127.996 319.466 + endloop + endfacet + facet normal 0.329347 -0.861249 0.387016 + outer loop + vertex 685.116 127.957 320.354 + vertex 681.649 126.521 320.108 + vertex 686.26 127.996 319.466 + endloop + endfacet + facet normal 0.329299 -0.873474 0.358616 + outer loop + vertex 674.767 123.521 319.119 + vertex 686.26 127.996 319.466 + vertex 681.649 126.521 320.108 + endloop + endfacet + facet normal 0.318415 -0.861022 0.396551 + outer loop + vertex 681.649 126.521 320.108 + vertex 677.742 125.193 320.361 + vertex 674.767 123.521 319.119 + endloop + endfacet + facet normal 0.323382 -0.863232 0.387627 + outer loop + vertex 677.742 125.193 320.361 + vertex 674.052 123.722 320.163 + vertex 674.767 123.521 319.119 + endloop + endfacet + facet normal 0.308379 -0.872452 0.379118 + outer loop + vertex 674.052 123.722 320.163 + vertex 669.78 122.124 319.961 + vertex 674.767 123.521 319.119 + endloop + endfacet + facet normal 0.308562 -0.870486 0.383463 + outer loop + vertex 665.765 120.156 318.724 + vertex 674.767 123.521 319.119 + vertex 669.78 122.124 319.961 + endloop + endfacet + facet normal 0.301393 -0.865843 0.399347 + outer loop + vertex 669.78 122.124 319.961 + vertex 665.137 120.385 319.695 + vertex 665.765 120.156 318.724 + endloop + endfacet + facet normal 0.282793 -0.876399 0.389812 + outer loop + vertex 665.137 120.385 319.695 + vertex 660.84 118.779 319.201 + vertex 665.765 120.156 318.724 + endloop + endfacet + facet normal 0.282177 -0.866851 0.41103 + outer loop + vertex 665.765 120.156 318.724 + vertex 660.84 118.779 319.201 + vertex 660.556 117.81 317.353 + endloop + endfacet + facet normal 0.301294 -0.881526 0.363503 + outer loop + vertex 667.384 119.934 316.845 + vertex 665.765 120.156 318.724 + vertex 660.556 117.81 317.353 + endloop + endfacet + facet normal 0.301517 -0.883363 0.358828 + outer loop + vertex 660.556 117.81 317.353 + vertex 661.551 117.512 315.784 + vertex 667.384 119.934 316.845 + endloop + endfacet + facet normal 0.297474 -0.885597 0.35669 + outer loop + vertex 660.556 117.81 317.353 + vertex 658.715 116.644 315.992 + vertex 661.551 117.512 315.784 + endloop + endfacet + facet normal 0.292956 -0.884873 0.362182 + outer loop + vertex 657.819 116.737 316.944 + vertex 658.715 116.644 315.992 + vertex 660.556 117.81 317.353 + endloop + endfacet + facet normal 0.275278 -0.863108 0.423399 + outer loop + vertex 657.819 116.737 316.944 + vertex 660.556 117.81 317.353 + vertex 657.153 116.999 317.911 + endloop + endfacet + facet normal 0.21362 -0.895791 0.389776 + outer loop + vertex 657.153 116.999 317.911 + vertex 657.28 116.42 316.512 + vertex 657.819 116.737 316.944 + endloop + endfacet + facet normal 0.262459 -0.90477 0.33542 + outer loop + vertex 658.715 116.644 315.992 + vertex 657.819 116.737 316.944 + vertex 657.28 116.42 316.512 + endloop + endfacet + facet normal 0.274802 -0.868315 0.412932 + outer loop + vertex 660.84 118.779 319.201 + vertex 657.153 116.999 317.911 + vertex 660.556 117.81 317.353 + endloop + endfacet + facet normal 0.261172 -0.859389 0.439591 + outer loop + vertex 660.84 118.779 319.201 + vertex 655.07 117.055 319.259 + vertex 657.153 116.999 317.911 + endloop + endfacet + facet normal 0.251633 -0.869388 0.42526 + outer loop + vertex 657.153 116.999 317.911 + vertex 655.07 117.055 319.259 + vertex 654.735 116.581 318.489 + endloop + endfacet + facet normal 0.26076 -0.868803 0.420934 + outer loop + vertex 654.064 116.689 319.127 + vertex 654.735 116.581 318.489 + vertex 655.07 117.055 319.259 + endloop + endfacet + facet normal 0.270167 -0.882059 0.385981 + outer loop + vertex 654.176 116.806 319.315 + vertex 654.064 116.689 319.127 + vertex 655.07 117.055 319.259 + endloop + endfacet + facet normal -0.274578 0.93115 -0.23993 + outer loop + vertex 652.993 116.424 319.187 + vertex 654.176 116.806 319.315 + vertex 655.07 117.055 319.259 + endloop + endfacet + facet normal 0.226432 -0.807255 0.545039 + outer loop + vertex 655.07 117.055 319.259 + vertex 651.76 116.118 319.246 + vertex 652.993 116.424 319.187 + endloop + endfacet + facet normal 0.22867 -0.814991 0.532447 + outer loop + vertex 651.76 116.118 319.246 + vertex 655.07 117.055 319.259 + vertex 651.356 116.326 319.738 + endloop + endfacet + facet normal 0.241161 -0.882565 0.403633 + outer loop + vertex 652.993 116.424 319.187 + vertex 654.064 116.689 319.127 + vertex 654.176 116.806 319.315 + endloop + endfacet + facet normal 0.241955 -0.889342 0.387981 + outer loop + vertex 652.473 116.083 318.731 + vertex 654.064 116.689 319.127 + vertex 652.993 116.424 319.187 + endloop + endfacet + facet normal 0.238867 -0.888808 0.391105 + outer loop + vertex 649.615 115.33 318.765 + vertex 652.473 116.083 318.731 + vertex 652.993 116.424 319.187 + endloop + endfacet + facet normal 0.241594 -0.90051 0.361545 + outer loop + vertex 649.01 114.892 318.078 + vertex 652.473 116.083 318.731 + vertex 649.615 115.33 318.765 + endloop + endfacet + facet normal 0.234041 -0.899955 0.367839 + outer loop + vertex 644.084 113.535 317.891 + vertex 649.01 114.892 318.078 + vertex 649.615 115.33 318.765 + endloop + endfacet + facet normal 0.240163 -0.915812 0.321884 + outer loop + vertex 644.103 113.292 317.187 + vertex 649.01 114.892 318.078 + vertex 644.084 113.535 317.891 + endloop + endfacet + facet normal 0.227982 -0.918686 0.322553 + outer loop + vertex 638.273 111.7 316.773 + vertex 644.103 113.292 317.187 + vertex 644.084 113.535 317.891 + endloop + endfacet + facet normal 0.234193 -0.930654 0.281136 + outer loop + vertex 638.531 111.559 316.092 + vertex 644.103 113.292 317.187 + vertex 638.273 111.7 316.773 + endloop + endfacet + facet normal 0.219887 -0.935456 0.276715 + outer loop + vertex 632.589 109.984 315.488 + vertex 638.531 111.559 316.092 + vertex 638.273 111.7 316.773 + endloop + endfacet + facet normal 0.226025 -0.944264 0.239327 + outer loop + vertex 632.744 109.824 314.712 + vertex 638.531 111.559 316.092 + vertex 632.589 109.984 315.488 + endloop + endfacet + facet normal 0.211812 -0.948073 0.237263 + outer loop + vertex 626.832 108.288 313.853 + vertex 632.744 109.824 314.712 + vertex 632.589 109.984 315.488 + endloop + endfacet + facet normal 0.221386 -0.957017 0.187366 + outer loop + vertex 627.125 108.191 313.011 + vertex 632.744 109.824 314.712 + vertex 626.832 108.288 313.853 + endloop + endfacet + facet normal 0.211291 -0.959913 0.184182 + outer loop + vertex 621.705 106.823 312.097 + vertex 627.125 108.191 313.011 + vertex 626.832 108.288 313.853 + endloop + endfacet + facet normal 0.21986 -0.965235 0.141358 + outer loop + vertex 621.849 106.708 311.087 + vertex 627.125 108.191 313.011 + vertex 621.705 106.823 312.097 + endloop + endfacet + facet normal 0.214231 -0.964241 0.156026 + outer loop + vertex 621.849 106.708 311.087 + vertex 628.336 108.275 311.862 + vertex 627.125 108.191 313.011 + endloop + endfacet + facet normal 0.219465 -0.962127 0.161698 + outer loop + vertex 628.336 108.275 311.862 + vertex 633.852 109.841 313.696 + vertex 627.125 108.191 313.011 + endloop + endfacet + facet normal 0.217962 -0.961753 0.165901 + outer loop + vertex 628.336 108.275 311.862 + vertex 635.931 110.076 312.328 + vertex 633.852 109.841 313.696 + endloop + endfacet + facet normal 0.224294 -0.958482 0.176082 + outer loop + vertex 635.931 110.076 312.328 + vertex 641.395 111.648 313.927 + vertex 633.852 109.841 313.696 + endloop + endfacet + facet normal 0.227973 -0.959645 0.164648 + outer loop + vertex 635.931 110.076 312.328 + vertex 643.898 111.984 312.416 + vertex 641.395 111.648 313.927 + endloop + endfacet + facet normal 0.234188 -0.95618 0.175714 + outer loop + vertex 643.898 111.984 312.416 + vertex 648.87 113.434 313.68 + vertex 641.395 111.648 313.927 + endloop + endfacet + facet normal 0.243784 -0.959421 0.141705 + outer loop + vertex 643.898 111.984 312.416 + vertex 651.36 113.847 312.19 + vertex 648.87 113.434 313.68 + endloop + endfacet + facet normal 0.246773 -0.957838 0.147138 + outer loop + vertex 651.36 113.847 312.19 + vertex 655.273 114.997 313.114 + vertex 648.87 113.434 313.68 + endloop + endfacet + facet normal 0.211834 -0.953284 0.215352 + outer loop + vertex 627.125 108.191 313.011 + vertex 633.852 109.841 313.696 + vertex 632.744 109.824 314.712 + endloop + endfacet + facet normal 0.221502 -0.948614 0.225982 + outer loop + vertex 633.852 109.841 313.696 + vertex 639.568 111.533 315.194 + vertex 632.744 109.824 314.712 + endloop + endfacet + facet normal 0.220084 -0.947849 0.230532 + outer loop + vertex 633.852 109.841 313.696 + vertex 641.395 111.648 313.927 + vertex 639.568 111.533 315.194 + endloop + endfacet + facet normal 0.228918 -0.942432 0.243758 + outer loop + vertex 641.395 111.648 313.927 + vertex 646.721 113.252 315.126 + vertex 639.568 111.533 315.194 + endloop + endfacet + facet normal 0.23331 -0.945281 0.228057 + outer loop + vertex 641.395 111.648 313.927 + vertex 648.87 113.434 313.68 + vertex 646.721 113.252 315.126 + endloop + endfacet + facet normal 0.238931 -0.941704 0.236864 + outer loop + vertex 648.87 113.434 313.68 + vertex 653.122 114.738 314.574 + vertex 646.721 113.252 315.126 + endloop + endfacet + facet normal 0.23977 -0.930707 0.276216 + outer loop + vertex 646.721 113.252 315.126 + vertex 653.122 114.738 314.574 + vertex 651.226 114.674 316.004 + endloop + endfacet + facet normal 0.233736 -0.925352 0.298482 + outer loop + vertex 646.721 113.252 315.126 + vertex 651.226 114.674 316.004 + vertex 645.085 113.227 316.329 + endloop + endfacet + facet normal 0.226438 -0.930334 0.288451 + outer loop + vertex 639.568 111.533 315.194 + vertex 646.721 113.252 315.126 + vertex 645.085 113.227 316.329 + endloop + endfacet + facet normal 0.226279 -0.930196 0.289022 + outer loop + vertex 639.568 111.533 315.194 + vertex 645.085 113.227 316.329 + vertex 638.531 111.559 316.092 + endloop + endfacet + facet normal 0.232873 -0.914322 0.331339 + outer loop + vertex 645.085 113.227 316.329 + vertex 651.226 114.674 316.004 + vertex 649.75 114.73 317.198 + endloop + endfacet + facet normal 0.231946 -0.913353 0.334644 + outer loop + vertex 645.085 113.227 316.329 + vertex 649.75 114.73 317.198 + vertex 644.103 113.292 317.187 + endloop + endfacet + facet normal 0.23668 -0.911668 0.335922 + outer loop + vertex 651.226 114.674 316.004 + vertex 654.21 115.7 316.687 + vertex 649.75 114.73 317.198 + endloop + endfacet + facet normal 0.237375 -0.902486 0.359404 + outer loop + vertex 649.75 114.73 317.198 + vertex 654.21 115.7 316.687 + vertex 652.996 115.86 317.892 + endloop + endfacet + facet normal 0.235863 -0.901012 0.36407 + outer loop + vertex 649.75 114.73 317.198 + vertex 652.996 115.86 317.892 + vertex 649.01 114.892 318.078 + endloop + endfacet + facet normal 0.234076 -0.904554 0.356357 + outer loop + vertex 654.21 115.7 316.687 + vertex 655.733 116.335 317.3 + vertex 652.996 115.86 317.892 + endloop + endfacet + facet normal 0.237927 -0.89209 0.384143 + outer loop + vertex 652.996 115.86 317.892 + vertex 655.733 116.335 317.3 + vertex 654.735 116.581 318.489 + endloop + endfacet + facet normal 0.237499 -0.891812 0.385054 + outer loop + vertex 652.996 115.86 317.892 + vertex 654.735 116.581 318.489 + vertex 652.473 116.083 318.731 + endloop + endfacet + facet normal 0.246323 -0.88718 0.390175 + outer loop + vertex 654.735 116.581 318.489 + vertex 655.733 116.335 317.3 + vertex 657.153 116.999 317.911 + endloop + endfacet + facet normal 0.243993 -0.917817 0.313176 + outer loop + vertex 651.226 114.674 316.004 + vertex 655.906 115.66 315.248 + vertex 654.21 115.7 316.687 + endloop + endfacet + facet normal 0.2326 -0.925163 0.299951 + outer loop + vertex 655.906 115.66 315.248 + vertex 657.019 116.141 315.868 + vertex 654.21 115.7 316.687 + endloop + endfacet + facet normal 0.241912 -0.908435 0.340916 + outer loop + vertex 654.21 115.7 316.687 + vertex 657.019 116.141 315.868 + vertex 655.733 116.335 317.3 + endloop + endfacet + facet normal 0.240822 -0.930011 0.277641 + outer loop + vertex 653.122 114.738 314.574 + vertex 655.906 115.66 315.248 + vertex 651.226 114.674 316.004 + endloop + endfacet + facet normal 0.248909 -0.947961 0.19853 + outer loop + vertex 648.87 113.434 313.68 + vertex 655.273 114.997 313.114 + vertex 653.122 114.738 314.574 + endloop + endfacet + facet normal 0.24738 -0.948863 0.196117 + outer loop + vertex 655.273 114.997 313.114 + vertex 657.853 115.806 313.774 + vertex 653.122 114.738 314.574 + endloop + endfacet + facet normal 0.252261 -0.937319 0.24041 + outer loop + vertex 653.122 114.738 314.574 + vertex 657.853 115.806 313.774 + vertex 655.906 115.66 315.248 + endloop + endfacet + facet normal 0.237482 -0.946148 0.220014 + outer loop + vertex 657.853 115.806 313.774 + vertex 658.773 116.174 314.366 + vertex 655.906 115.66 315.248 + endloop + endfacet + facet normal 0.250295 -0.929347 0.271415 + outer loop + vertex 655.906 115.66 315.248 + vertex 658.773 116.174 314.366 + vertex 657.019 116.141 315.868 + endloop + endfacet + facet normal 0.214985 -0.936756 0.276169 + outer loop + vertex 632.744 109.824 314.712 + vertex 639.568 111.533 315.194 + vertex 638.531 111.559 316.092 + endloop + endfacet + facet normal 0.222301 -0.919542 0.324076 + outer loop + vertex 638.531 111.559 316.092 + vertex 645.085 113.227 316.329 + vertex 644.103 113.292 317.187 + endloop + endfacet + facet normal 0.229634 -0.904462 0.359467 + outer loop + vertex 644.103 113.292 317.187 + vertex 649.75 114.73 317.198 + vertex 649.01 114.892 318.078 + endloop + endfacet + facet normal 0.234855 -0.893077 0.38374 + outer loop + vertex 649.01 114.892 318.078 + vertex 652.996 115.86 317.892 + vertex 652.473 116.083 318.731 + endloop + endfacet + facet normal 0.237632 -0.885446 0.399396 + outer loop + vertex 652.473 116.083 318.731 + vertex 654.735 116.581 318.489 + vertex 654.064 116.689 319.127 + endloop + endfacet + facet normal 0.255722 -0.839827 0.478849 + outer loop + vertex 655.07 117.055 319.259 + vertex 660.84 118.779 319.201 + vertex 659.118 119.002 320.512 + endloop + endfacet + facet normal 0.277579 -0.818196 0.503493 + outer loop + vertex 665.137 120.385 319.695 + vertex 669.78 122.124 319.961 + vertex 666.619 121.569 320.801 + endloop + endfacet + facet normal 0.31083 -0.875085 0.37096 + outer loop + vertex 665.765 120.156 318.724 + vertex 667.384 119.934 316.845 + vertex 674.767 123.521 319.119 + endloop + endfacet + facet normal 0.310438 -0.874845 0.371854 + outer loop + vertex 674.767 123.521 319.119 + vertex 667.384 119.934 316.845 + vertex 677.654 123.718 317.174 + endloop + endfacet + facet normal 0.276353 -0.805283 0.524546 + outer loop + vertex 669.78 122.124 319.961 + vertex 674.052 123.722 320.163 + vertex 675.112 124.732 321.156 + endloop + endfacet + facet normal 0.309692 -0.818939 0.483146 + outer loop + vertex 677.742 125.193 320.361 + vertex 681.649 126.521 320.108 + vertex 683.477 127.879 321.238 + endloop + endfacet + facet normal 0.323419 -0.861002 0.392526 + outer loop + vertex 674.767 123.521 319.119 + vertex 677.654 123.718 317.174 + vertex 686.26 127.996 319.466 + endloop + endfacet + facet normal 0.315838 -0.855397 0.410538 + outer loop + vertex 686.26 127.996 319.466 + vertex 677.654 123.718 317.174 + vertex 686.392 126.834 316.942 + endloop + endfacet + facet normal 0.336321 -0.848556 0.408461 + outer loop + vertex 686.26 127.996 319.466 + vertex 686.392 126.834 316.942 + vertex 693.621 130.227 318.04 + endloop + endfacet + facet normal 0.337369 -0.83386 0.436875 + outer loop + vertex 692.04 131.059 320.849 + vertex 686.26 127.996 319.466 + vertex 693.621 130.227 318.04 + endloop + endfacet + facet normal 0.337978 -0.833491 0.437108 + outer loop + vertex 695.719 132.51 320.77 + vertex 692.04 131.059 320.849 + vertex 693.621 130.227 318.04 + endloop + endfacet + facet normal 0.406402 -0.879168 0.248801 + outer loop + vertex 692.04 131.059 320.849 + vertex 690.019 130.069 320.651 + vertex 686.26 127.996 319.466 + endloop + endfacet + facet normal 0.303634 -0.816861 0.490453 + outer loop + vertex 681.649 126.521 320.108 + vertex 685.116 127.957 320.354 + vertex 683.477 127.879 321.238 + endloop + endfacet + facet normal 0.366709 -0.863269 0.346831 + outer loop + vertex 690.019 130.069 320.651 + vertex 689.044 129.632 320.593 + vertex 686.26 127.996 319.466 + endloop + endfacet + facet normal 0.323169 -0.791491 0.518752 + outer loop + vertex 695.719 132.51 320.77 + vertex 692.043 133.168 324.065 + vertex 692.04 131.059 320.849 + endloop + endfacet + facet normal 0.30874 -0.796734 0.519514 + outer loop + vertex 689.503 130.446 321.594 + vertex 687.111 130.348 322.865 + vertex 683.477 127.879 321.238 + endloop + endfacet + facet normal 0.309516 -0.798184 0.51682 + outer loop + vertex 689.503 130.446 321.594 + vertex 683.477 127.879 321.238 + vertex 687.277 128.967 320.643 + endloop + endfacet + facet normal 0.309834 -0.806955 0.502819 + outer loop + vertex 685.116 127.957 320.354 + vertex 687.277 128.967 320.643 + vertex 683.477 127.879 321.238 + endloop + endfacet + facet normal 0.287237 -0.787951 0.544635 + outer loop + vertex 681.316 128.143 322.871 + vertex 680.465 129.224 324.885 + vertex 673.587 125.269 322.791 + endloop + endfacet + facet normal 0.294339 -0.771933 0.563458 + outer loop + vertex 680.465 129.224 324.885 + vertex 686.715 133.015 326.814 + vertex 679.938 130.977 327.561 + endloop + endfacet + facet normal 0.279773 -0.762521 0.583343 + outer loop + vertex 679.938 130.977 327.561 + vertex 679.083 132.986 330.598 + vertex 671.92 128.026 327.55 + endloop + endfacet + facet normal 0.276108 -0.740077 0.613229 + outer loop + vertex 679.083 132.986 330.598 + vertex 684.438 137.068 333.113 + vertex 678.47 135.395 333.781 + endloop + endfacet + facet normal 0.264018 -0.715448 0.64686 + outer loop + vertex 670.372 132.585 333.968 + vertex 678.258 138.454 337.24 + vertex 669.69 135.51 337.481 + endloop + endfacet + facet normal 0.273035 -0.718598 0.639585 + outer loop + vertex 684.438 137.068 333.113 + vertex 685.231 140.098 336.178 + vertex 678.47 135.395 333.781 + endloop + endfacet + facet normal 0.261154 -0.694995 0.669911 + outer loop + vertex 686.001 144.106 340.037 + vertex 685.231 140.098 336.178 + vertex 690.647 143.731 337.836 + endloop + endfacet + facet normal 0.260181 -0.697005 0.668199 + outer loop + vertex 690.647 143.731 337.836 + vertex 690.698 146.033 340.218 + vertex 686.001 144.106 340.037 + endloop + endfacet + facet normal 0.246413 -0.666745 0.703372 + outer loop + vertex 690.698 146.033 340.218 + vertex 690.429 147.993 342.169 + vertex 686.001 144.106 340.037 + endloop + endfacet + facet normal 0.275551 -0.659123 0.699735 + outer loop + vertex 690.429 147.993 342.169 + vertex 690.698 146.033 340.218 + vertex 693.894 146.904 339.78 + endloop + endfacet + facet normal 0.272034 -0.663742 0.696738 + outer loop + vertex 693.894 146.904 339.78 + vertex 693.759 150.254 343.024 + vertex 690.429 147.993 342.169 + endloop + endfacet + facet normal 0.264638 -0.665331 0.69807 + outer loop + vertex 697.068 149.173 340.74 + vertex 693.759 150.254 343.024 + vertex 693.894 146.904 339.78 + endloop + endfacet + facet normal 0.286534 -0.684309 0.670537 + outer loop + vertex 697.068 149.173 340.74 + vertex 693.894 146.904 339.78 + vertex 698.809 146.554 337.322 + endloop + endfacet + facet normal 0.288112 -0.68348 0.670705 + outer loop + vertex 697.068 149.173 340.74 + vertex 698.809 146.554 337.322 + vertex 703.053 150.371 339.388 + endloop + endfacet + facet normal 0.288721 -0.646773 0.705921 + outer loop + vertex 697.516 152.237 343.363 + vertex 697.068 149.173 340.74 + vertex 703.053 150.371 339.388 + endloop + endfacet + facet normal 0.279505 -0.658615 0.698644 + outer loop + vertex 703.053 150.371 339.388 + vertex 703.33 154.593 343.258 + vertex 697.516 152.237 343.363 + endloop + endfacet + facet normal 0.280595 -0.658438 0.698374 + outer loop + vertex 711.397 154.18 339.628 + vertex 703.33 154.593 343.258 + vertex 703.053 150.371 339.388 + endloop + endfacet + facet normal 0.295452 -0.688701 0.662117 + outer loop + vertex 711.397 154.18 339.628 + vertex 703.053 150.371 339.388 + vertex 712.161 150.735 335.703 + endloop + endfacet + facet normal 0.301294 -0.686733 0.661528 + outer loop + vertex 721.118 154.879 335.926 + vertex 711.397 154.18 339.628 + vertex 712.161 150.735 335.703 + endloop + endfacet + facet normal 0.316908 -0.718213 0.619467 + outer loop + vertex 721.118 154.879 335.926 + vertex 712.161 150.735 335.703 + vertex 721.626 151.658 331.931 + endloop + endfacet + facet normal 0.324481 -0.715725 0.618425 + outer loop + vertex 730.985 155.949 331.987 + vertex 721.118 154.879 335.926 + vertex 721.626 151.658 331.931 + endloop + endfacet + facet normal 0.33785 -0.744338 0.576037 + outer loop + vertex 730.985 155.949 331.987 + vertex 721.626 151.658 331.931 + vertex 730.97 152.625 327.7 + endloop + endfacet + facet normal 0.347951 -0.741442 0.573754 + outer loop + vertex 740.142 156.909 327.674 + vertex 730.985 155.949 331.987 + vertex 730.97 152.625 327.7 + endloop + endfacet + facet normal 0.348261 -0.74065 0.574588 + outer loop + vertex 740.212 160.267 331.961 + vertex 730.985 155.949 331.987 + vertex 740.142 156.909 327.674 + endloop + endfacet + facet normal 0.360482 -0.737102 0.571606 + outer loop + vertex 748.971 161.203 327.644 + vertex 740.212 160.267 331.961 + vertex 740.142 156.909 327.674 + endloop + endfacet + facet normal 0.360887 -0.736096 0.572646 + outer loop + vertex 749.035 164.574 331.936 + vertex 740.212 160.267 331.961 + vertex 748.971 161.203 327.644 + endloop + endfacet + facet normal 0.373738 -0.732196 0.569393 + outer loop + vertex 757.57 165.583 327.632 + vertex 749.035 164.574 331.936 + vertex 748.971 161.203 327.644 + endloop + endfacet + facet normal 0.373943 -0.731681 0.56992 + outer loop + vertex 757.609 168.955 331.935 + vertex 749.035 164.574 331.936 + vertex 757.57 165.583 327.632 + endloop + endfacet + facet normal 0.38592 -0.727862 0.566818 + outer loop + vertex 766.098 170.109 327.638 + vertex 757.609 168.955 331.935 + vertex 757.57 165.583 327.632 + endloop + endfacet + facet normal 0.386621 -0.726022 0.568697 + outer loop + vertex 766.117 173.49 331.94 + vertex 757.609 168.955 331.935 + vertex 766.098 170.109 327.638 + endloop + endfacet + facet normal 0.398281 -0.722135 0.565591 + outer loop + vertex 774.604 174.804 327.643 + vertex 766.117 173.49 331.94 + vertex 766.098 170.109 327.638 + endloop + endfacet + facet normal 0.398204 -0.722348 0.565374 + outer loop + vertex 774.646 178.2 331.951 + vertex 766.117 173.49 331.94 + vertex 774.604 174.804 327.643 + endloop + endfacet + facet normal 0.411875 -0.717656 0.561541 + outer loop + vertex 783.087 179.674 327.644 + vertex 774.646 178.2 331.951 + vertex 774.604 174.804 327.643 + endloop + endfacet + facet normal 0.411857 -0.717708 0.561488 + outer loop + vertex 783.155 183.083 331.952 + vertex 774.646 178.2 331.951 + vertex 783.087 179.674 327.644 + endloop + endfacet + facet normal 0.426281 -0.712596 0.557217 + outer loop + vertex 791.513 184.714 327.643 + vertex 783.155 183.083 331.952 + vertex 783.087 179.674 327.644 + endloop + endfacet + facet normal 0.426482 -0.711993 0.557834 + outer loop + vertex 791.6 188.138 331.946 + vertex 783.155 183.083 331.952 + vertex 791.513 184.714 327.643 + endloop + endfacet + facet normal 0.442587 -0.706069 0.552796 + outer loop + vertex 799.843 189.932 327.639 + vertex 791.6 188.138 331.946 + vertex 791.513 184.714 327.643 + endloop + endfacet + facet normal 0.442253 -0.70712 0.551719 + outer loop + vertex 799.962 193.364 331.942 + vertex 791.6 188.138 331.946 + vertex 799.843 189.932 327.639 + endloop + endfacet + facet normal 0.460043 -0.700325 0.545806 + outer loop + vertex 808.058 195.324 327.633 + vertex 799.962 193.364 331.942 + vertex 799.843 189.932 327.639 + endloop + endfacet + facet normal 0.459382 -0.702488 0.54358 + outer loop + vertex 808.203 198.752 331.941 + vertex 799.962 193.364 331.942 + vertex 808.058 195.324 327.633 + endloop + endfacet + facet normal 0.477807 -0.695136 0.53711 + outer loop + vertex 816.124 200.869 327.634 + vertex 808.203 198.752 331.941 + vertex 808.058 195.324 327.633 + endloop + endfacet + facet normal 0.477686 -0.695548 0.536684 + outer loop + vertex 816.267 204.29 331.94 + vertex 808.203 198.752 331.941 + vertex 816.124 200.869 327.634 + endloop + endfacet + facet normal 0.496988 -0.687418 0.529583 + outer loop + vertex 824.008 206.572 327.638 + vertex 816.267 204.29 331.94 + vertex 816.124 200.869 327.634 + endloop + endfacet + facet normal 0.496332 -0.689744 0.527169 + outer loop + vertex 824.215 210.022 331.956 + vertex 816.267 204.29 331.94 + vertex 824.008 206.572 327.638 + endloop + endfacet + facet normal 0.517923 -0.680305 0.518596 + outer loop + vertex 831.809 212.518 327.646 + vertex 824.215 210.022 331.956 + vertex 824.008 206.572 327.638 + endloop + endfacet + facet normal 0.518257 -0.67904 0.519917 + outer loop + vertex 832.112 216.049 331.956 + vertex 824.215 210.022 331.956 + vertex 831.809 212.518 327.646 + endloop + endfacet + facet normal 0.53974 -0.669383 0.510497 + outer loop + vertex 839.59 218.778 327.629 + vertex 832.112 216.049 331.956 + vertex 831.809 212.518 327.646 + endloop + endfacet + facet normal 0.540001 -0.668311 0.511624 + outer loop + vertex 839.948 222.343 331.908 + vertex 832.112 216.049 331.956 + vertex 839.59 218.778 327.629 + endloop + endfacet + facet normal 0.560089 -0.658919 0.502121 + outer loop + vertex 847.09 225.116 327.58 + vertex 839.948 222.343 331.908 + vertex 839.59 218.778 327.629 + endloop + endfacet + facet normal 0.559925 -0.659592 0.50142 + outer loop + vertex 847.33 228.543 331.82 + vertex 839.948 222.343 331.908 + vertex 847.09 225.116 327.58 + endloop + endfacet + facet normal 0.575462 -0.651669 0.494137 + outer loop + vertex 853.535 230.85 327.637 + vertex 847.33 228.543 331.82 + vertex 847.09 225.116 327.58 + endloop + endfacet + facet normal 0.575074 -0.653003 0.492826 + outer loop + vertex 853.64 234.111 331.834 + vertex 847.33 228.543 331.82 + vertex 853.535 230.85 327.637 + endloop + endfacet + facet normal 0.581114 -0.649695 0.490105 + outer loop + vertex 858.335 235.559 328.187 + vertex 853.64 234.111 331.834 + vertex 853.535 230.85 327.637 + endloop + endfacet + facet normal 0.583585 -0.643024 0.495932 + outer loop + vertex 858.684 238.963 332.19 + vertex 853.64 234.111 331.834 + vertex 858.335 235.559 328.187 + endloop + endfacet + facet normal 0.581451 -0.644104 0.497036 + outer loop + vertex 858.684 238.963 332.19 + vertex 858.335 235.559 328.187 + vertex 861.599 239.415 329.365 + endloop + endfacet + facet normal 0.577471 -0.65173 0.491707 + outer loop + vertex 861.599 239.415 329.365 + vertex 861.539 241.023 331.568 + vertex 858.684 238.963 332.19 + endloop + endfacet + facet normal 0.39641 -0.6908 0.604694 + outer loop + vertex 783.155 183.083 331.952 + vertex 774.238 181.444 335.925 + vertex 774.646 178.2 331.951 + endloop + endfacet + facet normal 0.383765 -0.695615 0.607326 + outer loop + vertex 774.238 181.444 335.925 + vertex 765.701 176.729 335.918 + vertex 774.646 178.2 331.951 + endloop + endfacet + facet normal 0.367858 -0.666877 0.64804 + outer loop + vertex 774.238 181.444 335.925 + vertex 765.067 180 339.645 + vertex 765.701 176.729 335.918 + endloop + endfacet + facet normal 0.356129 -0.67135 0.64997 + outer loop + vertex 765.067 180 339.645 + vertex 756.539 175.467 339.636 + vertex 765.701 176.729 335.918 + endloop + endfacet + facet normal 0.356286 -0.670669 0.650587 + outer loop + vertex 765.701 176.729 335.918 + vertex 756.539 175.467 339.636 + vertex 757.178 172.19 335.907 + endloop + endfacet + facet normal 0.372136 -0.70033 0.609141 + outer loop + vertex 765.701 176.729 335.918 + vertex 757.178 172.19 335.907 + vertex 766.117 173.49 331.94 + endloop + endfacet + facet normal 0.345167 -0.674799 0.652308 + outer loop + vertex 756.539 175.467 339.636 + vertex 747.965 171.086 339.64 + vertex 757.178 172.19 335.907 + endloop + endfacet + facet normal 0.345119 -0.674991 0.652135 + outer loop + vertex 757.178 172.19 335.907 + vertex 747.965 171.086 339.64 + vertex 748.613 167.809 335.906 + endloop + endfacet + facet normal 0.359912 -0.703899 0.612364 + outer loop + vertex 757.178 172.19 335.907 + vertex 748.613 167.809 335.906 + vertex 757.609 168.955 331.935 + endloop + endfacet + facet normal 0.332435 -0.679576 0.653959 + outer loop + vertex 747.965 171.086 339.64 + vertex 739.159 166.795 339.657 + vertex 748.613 167.809 335.906 + endloop + endfacet + facet normal 0.332839 -0.67798 0.655409 + outer loop + vertex 748.613 167.809 335.906 + vertex 739.159 166.795 339.657 + vertex 739.811 163.506 335.924 + endloop + endfacet + facet normal 0.347602 -0.708353 0.614336 + outer loop + vertex 748.613 167.809 335.906 + vertex 739.811 163.506 335.924 + vertex 749.035 164.574 331.936 + endloop + endfacet + facet normal 0.320643 -0.682258 0.657048 + outer loop + vertex 739.159 166.795 339.657 + vertex 729.964 162.499 339.683 + vertex 739.811 163.506 335.924 + endloop + endfacet + facet normal 0.320716 -0.681962 0.657319 + outer loop + vertex 739.811 163.506 335.924 + vertex 729.964 162.499 339.683 + vertex 730.589 159.193 335.949 + endloop + endfacet + facet normal 0.334985 -0.712706 0.616308 + outer loop + vertex 739.811 163.506 335.924 + vertex 730.589 159.193 335.949 + vertex 740.212 160.267 331.961 + endloop + endfacet + facet normal 0.309971 -0.685573 0.658716 + outer loop + vertex 729.964 162.499 339.683 + vertex 720.513 158.232 339.69 + vertex 730.589 159.193 335.949 + endloop + endfacet + facet normal 0.310215 -0.684587 0.659627 + outer loop + vertex 730.589 159.193 335.949 + vertex 720.513 158.232 339.69 + vertex 721.118 154.879 335.926 + endloop + endfacet + facet normal 0.296105 -0.654806 0.695378 + outer loop + vertex 729.964 162.499 339.683 + vertex 719.964 161.761 343.247 + vertex 720.513 158.232 339.69 + endloop + endfacet + facet normal 0.28739 -0.65739 0.696595 + outer loop + vertex 719.964 161.761 343.247 + vertex 711.047 157.862 343.247 + vertex 720.513 158.232 339.69 + endloop + endfacet + facet normal 0.287405 -0.657338 0.696639 + outer loop + vertex 720.513 158.232 339.69 + vertex 711.047 157.862 343.247 + vertex 711.397 154.18 339.628 + endloop + endfacet + facet normal 0.296104 -0.654813 0.695373 + outer loop + vertex 729.329 165.997 343.248 + vertex 719.964 161.761 343.247 + vertex 729.964 162.499 339.683 + endloop + endfacet + facet normal 0.306394 -0.651536 0.693991 + outer loop + vertex 739.159 166.795 339.657 + vertex 729.329 165.997 343.248 + vertex 729.964 162.499 339.683 + endloop + endfacet + facet normal 0.306411 -0.65146 0.694055 + outer loop + vertex 738.514 170.289 343.221 + vertex 729.329 165.997 343.248 + vertex 739.159 166.795 339.657 + endloop + endfacet + facet normal 0.317093 -0.647946 0.692545 + outer loop + vertex 747.965 171.086 339.64 + vertex 738.514 170.289 343.221 + vertex 739.159 166.795 339.657 + endloop + endfacet + facet normal 0.316935 -0.648631 0.691975 + outer loop + vertex 747.331 174.571 343.197 + vertex 738.514 170.289 343.221 + vertex 747.965 171.086 339.64 + endloop + endfacet + facet normal 0.329627 -0.644349 0.690044 + outer loop + vertex 756.539 175.467 339.636 + vertex 747.331 174.571 343.197 + vertex 747.965 171.086 339.64 + endloop + endfacet + facet normal 0.329261 -0.645988 0.688685 + outer loop + vertex 755.91 178.935 343.188 + vertex 747.331 174.571 343.197 + vertex 756.539 175.467 339.636 + endloop + endfacet + facet normal 0.340533 -0.642075 0.68686 + outer loop + vertex 765.067 180 339.645 + vertex 755.91 178.935 343.188 + vertex 756.539 175.467 339.636 + endloop + endfacet + facet normal 0.340692 -0.641303 0.687503 + outer loop + vertex 764.435 183.467 343.192 + vertex 755.91 178.935 343.188 + vertex 765.067 180 339.645 + endloop + endfacet + facet normal 0.351811 -0.637327 0.685597 + outer loop + vertex 773.608 184.719 339.649 + vertex 764.435 183.467 343.192 + vertex 765.067 180 339.645 + endloop + endfacet + facet normal 0.351659 -0.638148 0.684912 + outer loop + vertex 772.975 188.179 343.198 + vertex 764.435 183.467 343.192 + vertex 773.608 184.719 339.649 + endloop + endfacet + facet normal 0.362857 -0.634028 0.682893 + outer loop + vertex 782.136 189.602 339.651 + vertex 772.975 188.179 343.198 + vertex 773.608 184.719 339.649 + endloop + endfacet + facet normal 0.379688 -0.663407 0.64477 + outer loop + vertex 782.136 189.602 339.651 + vertex 773.608 184.719 339.649 + vertex 782.757 186.334 335.923 + endloop + endfacet + facet normal 0.392824 -0.658115 0.642319 + outer loop + vertex 791.227 191.389 335.922 + vertex 782.136 189.602 339.651 + vertex 782.757 186.334 335.923 + endloop + endfacet + facet normal 0.409953 -0.686825 0.600175 + outer loop + vertex 791.227 191.389 335.922 + vertex 782.757 186.334 335.923 + vertex 791.6 188.138 331.946 + endloop + endfacet + facet normal 0.425632 -0.680489 0.596467 + outer loop + vertex 799.962 193.364 331.942 + vertex 791.227 191.389 335.922 + vertex 791.6 188.138 331.946 + endloop + endfacet + facet normal 0.425559 -0.680815 0.596146 + outer loop + vertex 799.597 196.614 335.914 + vertex 791.227 191.389 335.922 + vertex 799.962 193.364 331.942 + endloop + endfacet + facet normal 0.440989 -0.674346 0.592272 + outer loop + vertex 808.203 198.752 331.941 + vertex 799.597 196.614 335.914 + vertex 799.962 193.364 331.942 + endloop + endfacet + facet normal 0.440654 -0.675965 0.590674 + outer loop + vertex 807.841 201.989 335.915 + vertex 799.597 196.614 335.914 + vertex 808.203 198.752 331.941 + endloop + endfacet + facet normal 0.458796 -0.668032 0.585867 + outer loop + vertex 816.267 204.29 331.94 + vertex 807.841 201.989 335.915 + vertex 808.203 198.752 331.941 + endloop + endfacet + facet normal 0.458267 -0.670747 0.583173 + outer loop + vertex 815.924 207.521 335.925 + vertex 807.841 201.989 335.915 + vertex 816.267 204.29 331.94 + endloop + endfacet + facet normal 0.476531 -0.662438 0.578009 + outer loop + vertex 824.215 210.022 331.956 + vertex 815.924 207.521 335.925 + vertex 816.267 204.29 331.94 + endloop + endfacet + facet normal 0.476533 -0.662429 0.578017 + outer loop + vertex 823.904 213.278 335.945 + vertex 815.924 207.521 335.925 + vertex 824.215 210.022 331.956 + endloop + endfacet + facet normal 0.497887 -0.652347 0.571448 + outer loop + vertex 832.112 216.049 331.956 + vertex 823.904 213.278 335.945 + vertex 824.215 210.022 331.956 + endloop + endfacet + facet normal 0.497767 -0.653127 0.57066 + outer loop + vertex 831.88 219.355 335.943 + vertex 823.904 213.278 335.945 + vertex 832.112 216.049 331.956 + endloop + endfacet + facet normal 0.519615 -0.64254 0.563154 + outer loop + vertex 839.948 222.343 331.908 + vertex 831.88 219.355 335.943 + vertex 832.112 216.049 331.956 + endloop + endfacet + facet normal 0.519847 -0.640835 0.564881 + outer loop + vertex 839.738 225.66 335.865 + vertex 831.88 219.355 335.943 + vertex 839.948 222.343 331.908 + endloop + endfacet + facet normal 0.537413 -0.631974 0.558387 + outer loop + vertex 847.33 228.543 331.82 + vertex 839.738 225.66 335.865 + vertex 839.948 222.343 331.908 + endloop + endfacet + facet normal 0.537475 -0.63155 0.558807 + outer loop + vertex 847.095 231.818 335.748 + vertex 839.738 225.66 335.865 + vertex 847.33 228.543 331.82 + endloop + endfacet + facet normal 0.550112 -0.624874 0.553993 + outer loop + vertex 853.64 234.111 331.834 + vertex 847.095 231.818 335.748 + vertex 847.33 228.543 331.82 + endloop + endfacet + facet normal 0.550654 -0.622187 0.556474 + outer loop + vertex 853.385 237.388 335.751 + vertex 847.095 231.818 335.748 + vertex 853.64 234.111 331.834 + endloop + endfacet + facet normal 0.556418 -0.619055 0.55423 + outer loop + vertex 858.684 238.963 332.19 + vertex 853.385 237.388 335.751 + vertex 853.64 234.111 331.834 + endloop + endfacet + facet normal 0.558286 -0.612037 0.560114 + outer loop + vertex 858.317 242.324 336.228 + vertex 853.385 237.388 335.751 + vertex 858.684 238.963 332.19 + endloop + endfacet + facet normal 0.554932 -0.613924 0.56138 + outer loop + vertex 858.317 242.324 336.228 + vertex 858.684 238.963 332.19 + vertex 861.286 242.693 333.697 + endloop + endfacet + facet normal 0.556434 -0.610481 0.563644 + outer loop + vertex 861.286 242.693 333.697 + vertex 861.077 244.341 335.689 + vertex 858.317 242.324 336.228 + endloop + endfacet + facet normal 0.546776 -0.588809 0.595264 + outer loop + vertex 861.077 244.341 335.689 + vertex 860.857 246.312 337.84 + vertex 858.317 242.324 336.228 + endloop + endfacet + facet normal 0.585893 -0.566844 0.579152 + outer loop + vertex 860.857 246.312 337.84 + vertex 861.077 244.341 335.689 + vertex 863.409 247.071 336.001 + endloop + endfacet + facet normal 0.587338 -0.560623 0.583725 + outer loop + vertex 863.409 247.071 336.001 + vertex 863.287 250.791 339.697 + vertex 860.857 246.312 337.84 + endloop + endfacet + facet normal 0.594529 -0.556788 0.580105 + outer loop + vertex 863.409 247.071 336.001 + vertex 866.866 254.038 339.146 + vertex 863.287 250.791 339.697 + endloop + endfacet + facet normal 0.597879 -0.55686 0.576583 + outer loop + vertex 867.356 250.695 335.409 + vertex 866.866 254.038 339.146 + vertex 863.409 247.071 336.001 + endloop + endfacet + facet normal 0.607643 -0.550659 0.572315 + outer loop + vertex 867.356 250.695 335.409 + vertex 871.504 259.053 339.047 + vertex 866.866 254.038 339.146 + endloop + endfacet + facet normal 0.605871 -0.550615 0.574233 + outer loop + vertex 872.055 255.798 335.344 + vertex 871.504 259.053 339.047 + vertex 867.356 250.695 335.409 + endloop + endfacet + facet normal 0.624988 -0.537806 0.565823 + outer loop + vertex 872.055 255.798 335.344 + vertex 876.732 265.217 339.131 + vertex 871.504 259.053 339.047 + endloop + endfacet + facet normal 0.621314 -0.537658 0.569993 + outer loop + vertex 877.293 261.96 335.447 + vertex 876.732 265.217 339.131 + vertex 872.055 255.798 335.344 + endloop + endfacet + facet normal 0.649631 -0.517748 0.556702 + outer loop + vertex 877.293 261.96 335.447 + vertex 881.997 271.912 339.214 + vertex 876.732 265.217 339.131 + endloop + endfacet + facet normal 0.650064 -0.517758 0.556187 + outer loop + vertex 882.549 268.647 335.529 + vertex 881.997 271.912 339.214 + vertex 877.293 261.96 335.447 + endloop + endfacet + facet normal 0.687036 -0.489677 0.536841 + outer loop + vertex 882.549 268.647 335.529 + vertex 886.862 278.757 339.231 + vertex 881.997 271.912 339.214 + endloop + endfacet + facet normal 0.684284 -0.489759 0.54027 + outer loop + vertex 887.418 275.472 335.549 + vertex 886.862 278.757 339.231 + vertex 882.549 268.647 335.529 + endloop + endfacet + facet normal 0.606296 -0.580233 0.543815 + outer loop + vertex 861.077 244.341 335.689 + vertex 861.286 242.693 333.697 + vertex 863.409 247.071 336.001 + endloop + endfacet + facet normal 0.407403 -0.65166 0.639814 + outer loop + vertex 799.597 196.614 335.914 + vertex 790.608 194.658 339.645 + vertex 791.227 191.389 335.922 + endloop + endfacet + facet normal 0.407129 -0.653341 0.638272 + outer loop + vertex 798.986 199.872 339.639 + vertex 790.608 194.658 339.645 + vertex 799.597 196.614 335.914 + endloop + endfacet + facet normal 0.42179 -0.647039 0.635165 + outer loop + vertex 807.841 201.989 335.915 + vertex 798.986 199.872 339.639 + vertex 799.597 196.614 335.914 + endloop + endfacet + facet normal 0.421613 -0.64823 0.634066 + outer loop + vertex 807.224 205.233 339.642 + vertex 798.986 199.872 339.639 + vertex 807.841 201.989 335.915 + endloop + endfacet + facet normal 0.437832 -0.640978 0.630436 + outer loop + vertex 815.924 207.521 335.925 + vertex 807.224 205.233 339.642 + vertex 807.841 201.989 335.915 + endloop + endfacet + facet normal 0.437537 -0.643196 0.628379 + outer loop + vertex 815.312 210.755 339.662 + vertex 807.224 205.233 339.642 + vertex 815.924 207.521 335.925 + endloop + endfacet + facet normal 0.456261 -0.634483 0.623905 + outer loop + vertex 823.904 213.278 335.945 + vertex 815.312 210.755 339.662 + vertex 815.924 207.521 335.925 + endloop + endfacet + facet normal 0.456249 -0.634594 0.623801 + outer loop + vertex 823.316 216.531 339.684 + vertex 815.312 210.755 339.662 + vertex 823.904 213.278 335.945 + endloop + endfacet + facet normal 0.476294 -0.624931 0.618551 + outer loop + vertex 831.88 219.355 335.943 + vertex 823.316 216.531 339.684 + vertex 823.904 213.278 335.945 + endloop + endfacet + facet normal 0.476328 -0.624521 0.618938 + outer loop + vertex 831.322 222.629 339.676 + vertex 823.316 216.531 339.684 + vertex 831.88 219.355 335.943 + endloop + endfacet + facet normal 0.498384 -0.613499 0.612562 + outer loop + vertex 839.738 225.66 335.865 + vertex 831.322 222.629 339.676 + vertex 831.88 219.355 335.943 + endloop + endfacet + facet normal 0.498274 -0.6151 0.611044 + outer loop + vertex 839.23 228.956 339.596 + vertex 831.322 222.629 339.676 + vertex 839.738 225.66 335.865 + endloop + endfacet + facet normal 0.51657 -0.60569 0.605223 + outer loop + vertex 847.095 231.818 335.748 + vertex 839.23 228.956 339.596 + vertex 839.738 225.66 335.865 + endloop + endfacet + facet normal 0.516578 -0.605598 0.605309 + outer loop + vertex 846.612 235.149 339.492 + vertex 839.23 228.956 339.596 + vertex 847.095 231.818 335.748 + endloop + endfacet + facet normal 0.529773 -0.598632 0.600816 + outer loop + vertex 853.385 237.388 335.751 + vertex 846.612 235.149 339.492 + vertex 847.095 231.818 335.748 + endloop + endfacet + facet normal 0.530045 -0.596783 0.602414 + outer loop + vertex 852.851 240.795 339.596 + vertex 846.612 235.149 339.492 + vertex 853.385 237.388 335.751 + endloop + endfacet + facet normal 0.535912 -0.593576 0.600388 + outer loop + vertex 858.317 242.324 336.228 + vertex 852.851 240.795 339.596 + vertex 853.385 237.388 335.751 + endloop + endfacet + facet normal 0.536903 -0.588855 0.604139 + outer loop + vertex 857.7 245.973 340.334 + vertex 852.851 240.795 339.596 + vertex 858.317 242.324 336.228 + endloop + endfacet + facet normal 0.539507 -0.5874 0.603237 + outer loop + vertex 857.7 245.973 340.334 + vertex 858.317 242.324 336.228 + vertex 860.857 246.312 337.84 + endloop + endfacet + facet normal 0.402677 -0.619148 0.674171 + outer loop + vertex 807.224 205.233 339.642 + vertex 798.353 203.322 343.185 + vertex 798.986 199.872 339.639 + endloop + endfacet + facet normal 0.388544 -0.62485 0.677198 + outer loop + vertex 798.353 203.322 343.185 + vertex 789.978 198.119 343.189 + vertex 798.986 199.872 339.639 + endloop + endfacet + facet normal 0.402582 -0.619923 0.673516 + outer loop + vertex 806.584 208.673 343.19 + vertex 798.353 203.322 343.185 + vertex 807.224 205.233 339.642 + endloop + endfacet + facet normal 0.41733 -0.613745 0.670189 + outer loop + vertex 815.312 210.755 339.662 + vertex 806.584 208.673 343.19 + vertex 807.224 205.233 339.642 + endloop + endfacet + facet normal 0.417237 -0.614629 0.669436 + outer loop + vertex 814.665 214.185 343.215 + vertex 806.584 208.673 343.19 + vertex 815.312 210.755 339.662 + endloop + endfacet + facet normal 0.435855 -0.606497 0.664975 + outer loop + vertex 823.316 216.531 339.684 + vertex 814.665 214.185 343.215 + vertex 815.312 210.755 339.662 + endloop + endfacet + facet normal 0.435818 -0.606953 0.664583 + outer loop + vertex 822.677 219.965 343.24 + vertex 814.665 214.185 343.215 + vertex 823.316 216.531 339.684 + endloop + endfacet + facet normal 0.455998 -0.597773 0.659343 + outer loop + vertex 831.322 222.629 339.676 + vertex 822.677 219.965 343.24 + vertex 823.316 216.531 339.684 + endloop + endfacet + facet normal 0.455981 -0.598107 0.659052 + outer loop + vertex 830.702 226.073 343.23 + vertex 822.677 219.965 343.24 + vertex 831.322 222.629 339.676 + endloop + endfacet + facet normal 0.477108 -0.588115 0.653061 + outer loop + vertex 839.23 228.956 339.596 + vertex 830.702 226.073 343.23 + vertex 831.322 222.629 339.676 + endloop + endfacet + facet normal 0.477096 -0.588451 0.652767 + outer loop + vertex 838.631 232.421 343.157 + vertex 830.702 226.073 343.23 + vertex 839.23 228.956 339.596 + endloop + endfacet + facet normal 0.495304 -0.579538 0.647155 + outer loop + vertex 846.612 235.149 339.492 + vertex 838.631 232.421 343.157 + vertex 839.23 228.956 339.596 + endloop + endfacet + facet normal 0.495257 -0.580447 0.646376 + outer loop + vertex 846.018 238.653 343.094 + vertex 838.631 232.421 343.157 + vertex 846.612 235.149 339.492 + endloop + endfacet + facet normal 0.508534 -0.573742 0.642039 + outer loop + vertex 852.851 240.795 339.596 + vertex 846.018 238.653 343.094 + vertex 846.612 235.149 339.492 + endloop + endfacet + facet normal 0.508468 -0.574389 0.641512 + outer loop + vertex 852.226 244.342 343.267 + vertex 846.018 238.653 343.094 + vertex 852.851 240.795 339.596 + endloop + endfacet + facet normal 0.513316 -0.571868 0.639902 + outer loop + vertex 857.7 245.973 340.334 + vertex 852.226 244.342 343.267 + vertex 852.851 240.795 339.596 + endloop + endfacet + facet normal 0.514233 -0.564401 0.645768 + outer loop + vertex 856.647 249.159 343.957 + vertex 852.226 244.342 343.267 + vertex 857.7 245.973 340.334 + endloop + endfacet + facet normal 0.510487 -0.566714 0.646713 + outer loop + vertex 856.647 249.159 343.957 + vertex 857.7 245.973 340.334 + vertex 859.626 250.007 342.348 + endloop + endfacet + facet normal 0.513393 -0.542722 0.664741 + outer loop + vertex 859.626 250.007 342.348 + vertex 859.623 253.116 344.889 + vertex 856.647 249.159 343.957 + endloop + endfacet + facet normal 0.544427 -0.530463 0.649776 + outer loop + vertex 859.623 253.116 344.889 + vertex 859.626 250.007 342.348 + vertex 862.371 253.724 343.083 + endloop + endfacet + facet normal 0.547754 -0.513434 0.660568 + outer loop + vertex 862.371 253.724 343.083 + vertex 862.075 257.86 346.543 + vertex 859.623 253.116 344.889 + endloop + endfacet + facet normal 0.552367 -0.511284 0.658391 + outer loop + vertex 862.371 253.724 343.083 + vertex 865.613 261.056 346.056 + vertex 862.075 257.86 346.543 + endloop + endfacet + facet normal 0.556414 -0.511592 0.654735 + outer loop + vertex 866.276 257.468 342.69 + vertex 865.613 261.056 346.056 + vertex 862.371 253.724 343.083 + endloop + endfacet + facet normal 0.566425 -0.505857 0.650593 + outer loop + vertex 866.276 257.468 342.69 + vertex 870.187 266.088 345.986 + vertex 865.613 261.056 346.056 + endloop + endfacet + facet normal 0.562684 -0.505502 0.654106 + outer loop + vertex 870.877 262.482 342.606 + vertex 870.187 266.088 345.986 + vertex 866.276 257.468 342.69 + endloop + endfacet + facet normal 0.580852 -0.494781 0.646377 + outer loop + vertex 870.877 262.482 342.606 + vertex 875.379 272.26 346.046 + vertex 870.187 266.088 345.986 + endloop + endfacet + facet normal 0.577457 -0.49439 0.649709 + outer loop + vertex 876.102 268.669 342.67 + vertex 875.379 272.26 346.046 + vertex 870.877 262.482 342.606 + endloop + endfacet + facet normal 0.605405 -0.476972 0.637168 + outer loop + vertex 876.102 268.669 342.67 + vertex 880.617 278.977 346.097 + vertex 875.379 272.26 346.046 + endloop + endfacet + facet normal 0.599281 -0.476358 0.643386 + outer loop + vertex 881.361 275.373 342.736 + vertex 880.617 278.977 346.097 + vertex 876.102 268.669 342.67 + endloop + endfacet + facet normal 0.637619 -0.450922 0.624589 + outer loop + vertex 881.361 275.373 342.736 + vertex 885.442 285.805 346.101 + vertex 880.617 278.977 346.097 + endloop + endfacet + facet normal 0.634681 -0.45077 0.627683 + outer loop + vertex 886.212 282.218 342.747 + vertex 885.442 285.805 346.101 + vertex 881.361 275.373 342.736 + endloop + endfacet + facet normal 0.561274 -0.538667 0.628339 + outer loop + vertex 859.626 250.007 342.348 + vertex 860.83 249.058 340.46 + vertex 862.371 253.724 343.083 + endloop + endfacet + facet normal 0.571471 -0.537431 0.620152 + outer loop + vertex 863.287 250.791 339.697 + vertex 862.371 253.724 343.083 + vertex 860.83 249.058 340.46 + endloop + endfacet + facet normal 0.575148 -0.534892 0.618947 + outer loop + vertex 863.287 250.791 339.697 + vertex 866.276 257.468 342.69 + vertex 862.371 253.724 343.083 + endloop + endfacet + facet normal 0.580018 -0.53499 0.6143 + outer loop + vertex 866.866 254.038 339.146 + vertex 866.276 257.468 342.69 + vertex 863.287 250.791 339.697 + endloop + endfacet + facet normal 0.588437 -0.529856 0.610733 + outer loop + vertex 866.866 254.038 339.146 + vertex 870.877 262.482 342.606 + vertex 866.276 257.468 342.69 + endloop + endfacet + facet normal 0.585849 -0.5297 0.613351 + outer loop + vertex 871.504 259.053 339.047 + vertex 870.877 262.482 342.606 + vertex 866.866 254.038 339.146 + endloop + endfacet + facet normal 0.605264 -0.517411 0.60493 + outer loop + vertex 871.504 259.053 339.047 + vertex 876.102 268.669 342.67 + vertex 870.877 262.482 342.606 + endloop + endfacet + facet normal 0.599704 -0.51697 0.610817 + outer loop + vertex 876.732 265.217 339.131 + vertex 876.102 268.669 342.67 + vertex 871.504 259.053 339.047 + endloop + endfacet + facet normal 0.627953 -0.498396 0.597726 + outer loop + vertex 876.732 265.217 339.131 + vertex 881.361 275.373 342.736 + vertex 876.102 268.669 342.67 + endloop + endfacet + facet normal 0.623974 -0.498134 0.602096 + outer loop + vertex 881.997 271.912 339.214 + vertex 881.361 275.373 342.736 + vertex 876.732 265.217 339.131 + endloop + endfacet + facet normal 0.662926 -0.470721 0.582195 + outer loop + vertex 881.997 271.912 339.214 + vertex 886.212 282.218 342.747 + vertex 881.361 275.373 342.736 + endloop + endfacet + facet normal 0.660127 -0.470676 0.585403 + outer loop + vertex 886.862 278.757 339.231 + vertex 886.212 282.218 342.747 + vertex 881.997 271.912 339.214 + endloop + endfacet + facet normal 0.534552 -0.567837 0.625951 + outer loop + vertex 860.83 249.058 340.46 + vertex 859.626 250.007 342.348 + vertex 857.7 245.973 340.334 + endloop + endfacet + facet normal 0.388702 -0.623697 0.678169 + outer loop + vertex 798.986 199.872 339.639 + vertex 789.978 198.119 343.189 + vertex 790.608 194.658 339.645 + endloop + endfacet + facet normal 0.375436 -0.628869 0.680861 + outer loop + vertex 789.978 198.119 343.189 + vertex 781.504 193.067 343.196 + vertex 790.608 194.658 339.645 + endloop + endfacet + facet normal 0.375495 -0.628484 0.681184 + outer loop + vertex 790.608 194.658 339.645 + vertex 781.504 193.067 343.196 + vertex 782.136 189.602 339.651 + endloop + endfacet + facet normal 0.410377 -0.685034 0.60193 + outer loop + vertex 791.6 188.138 331.946 + vertex 782.757 186.334 335.923 + vertex 783.155 183.083 331.952 + endloop + endfacet + facet normal 0.392899 -0.657695 0.642703 + outer loop + vertex 790.608 194.658 339.645 + vertex 782.136 189.602 339.651 + vertex 791.227 191.389 335.922 + endloop + endfacet + facet normal 0.38001 -0.661755 0.646276 + outer loop + vertex 782.757 186.334 335.923 + vertex 773.608 184.719 339.649 + vertex 774.238 181.444 335.925 + endloop + endfacet + facet normal 0.362995 -0.633213 0.683576 + outer loop + vertex 781.504 193.067 343.196 + vertex 772.975 188.179 343.198 + vertex 782.136 189.602 339.651 + endloop + endfacet + facet normal 0.36794 -0.666486 0.648395 + outer loop + vertex 773.608 184.719 339.649 + vertex 765.067 180 339.645 + vertex 774.238 181.444 335.925 + endloop + endfacet + facet normal 0.396489 -0.690484 0.605002 + outer loop + vertex 782.757 186.334 335.923 + vertex 774.238 181.444 335.925 + vertex 783.155 183.083 331.952 + endloop + endfacet + facet normal 0.383642 -0.696074 0.606878 + outer loop + vertex 774.646 178.2 331.951 + vertex 765.701 176.729 335.918 + vertex 766.117 173.49 331.94 + endloop + endfacet + facet normal 0.372404 -0.699396 0.61005 + outer loop + vertex 766.117 173.49 331.94 + vertex 757.178 172.19 335.907 + vertex 757.609 168.955 331.935 + endloop + endfacet + facet normal 0.359852 -0.704098 0.61217 + outer loop + vertex 757.609 168.955 331.935 + vertex 748.613 167.809 335.906 + vertex 749.035 164.574 331.936 + endloop + endfacet + facet normal 0.347549 -0.708528 0.614165 + outer loop + vertex 749.035 164.574 331.936 + vertex 739.811 163.506 335.924 + vertex 740.212 160.267 331.961 + endloop + endfacet + facet normal 0.335109 -0.712294 0.616717 + outer loop + vertex 740.212 160.267 331.961 + vertex 730.589 159.193 335.949 + vertex 730.985 155.949 331.987 + endloop + endfacet + facet normal 0.338096 -0.743691 0.576728 + outer loop + vertex 730.97 152.625 327.7 + vertex 721.626 151.658 331.931 + vertex 721.78 148.428 327.677 + endloop + endfacet + facet normal 0.331893 -0.745557 0.57792 + outer loop + vertex 721.626 151.658 331.931 + vertex 713.135 147.669 331.662 + vertex 721.78 148.428 327.677 + endloop + endfacet + facet normal 0.331184 -0.74732 0.576047 + outer loop + vertex 721.78 148.428 327.677 + vertex 713.135 147.669 331.662 + vertex 713.348 144.635 327.603 + endloop + endfacet + facet normal 0.327366 -0.748485 0.576717 + outer loop + vertex 713.135 147.669 331.662 + vertex 707.149 144.598 331.074 + vertex 713.348 144.635 327.603 + endloop + endfacet + facet normal 0.323307 -0.755822 0.56939 + outer loop + vertex 713.348 144.635 327.603 + vertex 707.149 144.598 331.074 + vertex 706.104 141.632 327.73 + endloop + endfacet + facet normal 0.304434 -0.75783 0.577073 + outer loop + vertex 706.104 141.632 327.73 + vertex 707.149 144.598 331.074 + vertex 700.789 143.078 332.433 + endloop + endfacet + facet normal 0.312969 -0.748995 0.584001 + outer loop + vertex 700.789 143.078 332.433 + vertex 700.387 139.116 327.566 + vertex 706.104 141.632 327.73 + endloop + endfacet + facet normal 0.313864 -0.748801 0.583769 + outer loop + vertex 700.789 143.078 332.433 + vertex 695.863 139.937 331.052 + vertex 700.387 139.116 327.566 + endloop + endfacet + facet normal 0.308944 -0.754703 0.578772 + outer loop + vertex 700.387 139.116 327.566 + vertex 695.863 139.937 331.052 + vertex 696.325 136.606 326.463 + endloop + endfacet + facet normal 0.328383 -0.771368 0.54512 + outer loop + vertex 700.387 139.116 327.566 + vertex 696.325 136.606 326.463 + vertex 699.926 135.695 323.004 + endloop + endfacet + facet normal 0.326629 -0.771773 0.5456 + outer loop + vertex 700.387 139.116 327.566 + vertex 699.926 135.695 323.004 + vertex 705.269 138.089 323.191 + endloop + endfacet + facet normal 0.324919 -0.773546 0.544108 + outer loop + vertex 705.269 138.089 323.191 + vertex 706.104 141.632 327.73 + vertex 700.387 139.116 327.566 + endloop + endfacet + facet normal 0.33169 -0.772254 0.541854 + outer loop + vertex 712.849 141.323 323.16 + vertex 706.104 141.632 327.73 + vertex 705.269 138.089 323.191 + endloop + endfacet + facet normal 0.330369 -0.774097 0.540029 + outer loop + vertex 713.348 144.635 327.603 + vertex 706.104 141.632 327.73 + vertex 712.849 141.323 323.16 + endloop + endfacet + facet normal 0.339631 -0.771932 0.537375 + outer loop + vertex 721.522 145.102 323.107 + vertex 713.348 144.635 327.603 + vertex 712.849 141.323 323.16 + endloop + endfacet + facet normal 0.341233 -0.768972 0.540594 + outer loop + vertex 721.78 148.428 327.677 + vertex 713.348 144.635 327.603 + vertex 721.522 145.102 323.107 + endloop + endfacet + facet normal 0.348201 -0.767086 0.538828 + outer loop + vertex 730.624 149.212 323.077 + vertex 721.78 148.428 327.677 + vertex 721.522 145.102 323.107 + endloop + endfacet + facet normal 0.348548 -0.766374 0.539616 + outer loop + vertex 730.97 152.625 327.7 + vertex 721.78 148.428 327.677 + vertex 730.624 149.212 323.077 + endloop + endfacet + facet normal 0.358535 -0.763682 0.536882 + outer loop + vertex 739.65 153.425 323.042 + vertex 730.97 152.625 327.7 + vertex 730.624 149.212 323.077 + endloop + endfacet + facet normal 0.358381 -0.763995 0.53654 + outer loop + vertex 740.142 156.909 327.674 + vertex 730.97 152.625 327.7 + vertex 739.65 153.425 323.042 + endloop + endfacet + facet normal 0.370638 -0.760755 0.532803 + outer loop + vertex 748.383 157.66 323.014 + vertex 740.142 156.909 327.674 + vertex 739.65 153.425 323.042 + endloop + endfacet + facet normal 0.371264 -0.759536 0.534105 + outer loop + vertex 748.971 161.203 327.644 + vertex 740.142 156.909 327.674 + vertex 748.383 157.66 323.014 + endloop + endfacet + facet normal 0.383952 -0.75616 0.529909 + outer loop + vertex 756.99 162.023 323.004 + vertex 748.971 161.203 327.644 + vertex 748.383 157.66 323.014 + endloop + endfacet + facet normal 0.384921 -0.754253 0.53192 + outer loop + vertex 757.57 165.583 327.632 + vertex 748.971 161.203 327.644 + vertex 756.99 162.023 323.004 + endloop + endfacet + facet normal 0.396488 -0.75102 0.527983 + outer loop + vertex 765.576 166.556 323.004 + vertex 757.57 165.583 327.632 + vertex 756.99 162.023 323.004 + endloop + endfacet + facet normal 0.397325 -0.7493 0.529794 + outer loop + vertex 766.098 170.109 327.638 + vertex 757.57 165.583 327.632 + vertex 765.576 166.556 323.004 + endloop + endfacet + facet normal 0.410251 -0.745436 0.525376 + outer loop + vertex 774.067 171.229 323.004 + vertex 766.098 170.109 327.638 + vertex 765.576 166.556 323.004 + endloop + endfacet + facet normal 0.410671 -0.744542 0.526314 + outer loop + vertex 774.604 174.804 327.643 + vertex 766.098 170.109 327.638 + vertex 774.067 171.229 323.004 + endloop + endfacet + facet normal 0.423832 -0.740448 0.521635 + outer loop + vertex 782.516 176.068 323.007 + vertex 774.604 174.804 327.643 + vertex 774.067 171.229 323.004 + endloop + endfacet + facet normal 0.424331 -0.73935 0.522786 + outer loop + vertex 783.087 179.674 327.644 + vertex 774.604 174.804 327.643 + vertex 782.516 176.068 323.007 + endloop + endfacet + facet normal 0.439956 -0.734309 0.516941 + outer loop + vertex 790.903 181.091 323.004 + vertex 783.087 179.674 327.644 + vertex 782.516 176.068 323.007 + endloop + endfacet + facet normal 0.439665 -0.734972 0.516248 + outer loop + vertex 791.513 184.714 327.643 + vertex 783.087 179.674 327.644 + vertex 790.903 181.091 323.004 + endloop + endfacet + facet normal 0.457329 -0.729028 0.509282 + outer loop + vertex 799.18 186.281 323.001 + vertex 791.513 184.714 327.643 + vertex 790.903 181.091 323.004 + endloop + endfacet + facet normal 0.457172 -0.729392 0.508901 + outer loop + vertex 799.843 189.932 327.639 + vertex 791.513 184.714 327.643 + vertex 799.18 186.281 323.001 + endloop + endfacet + facet normal 0.475116 -0.723103 0.501385 + outer loop + vertex 807.363 191.658 323.001 + vertex 799.843 189.932 327.639 + vertex 799.18 186.281 323.001 + endloop + endfacet + facet normal 0.475057 -0.723245 0.501236 + outer loop + vertex 808.058 195.324 327.633 + vertex 799.843 189.932 327.639 + vertex 807.363 191.658 323.001 + endloop + endfacet + facet normal 0.495174 -0.715822 0.492343 + outer loop + vertex 815.405 197.218 322.997 + vertex 808.058 195.324 327.633 + vertex 807.363 191.658 323.001 + endloop + endfacet + facet normal 0.494008 -0.718693 0.489322 + outer loop + vertex 816.124 200.869 327.634 + vertex 808.058 195.324 327.633 + vertex 815.405 197.218 322.997 + endloop + endfacet + facet normal 0.514704 -0.710589 0.479732 + outer loop + vertex 823.257 202.907 322.999 + vertex 816.124 200.869 327.634 + vertex 815.405 197.218 322.997 + endloop + endfacet + facet normal 0.514373 -0.711417 0.478859 + outer loop + vertex 824.008 206.572 327.638 + vertex 816.124 200.869 327.634 + vertex 823.257 202.907 322.999 + endloop + endfacet + facet normal 0.536536 -0.702214 0.468001 + outer loop + vertex 830.911 208.755 323 + vertex 824.008 206.572 327.638 + vertex 823.257 202.907 322.999 + endloop + endfacet + facet normal 0.535904 -0.703825 0.466302 + outer loop + vertex 831.809 212.518 327.646 + vertex 824.008 206.572 327.638 + vertex 830.911 208.755 323 + endloop + endfacet + facet normal 0.558134 -0.694324 0.454313 + outer loop + vertex 838.545 214.896 323.006 + vertex 831.809 212.518 327.646 + vertex 830.911 208.755 323 + endloop + endfacet + facet normal 0.55863 -0.693013 0.455704 + outer loop + vertex 839.59 218.778 327.629 + vertex 831.809 212.518 327.646 + vertex 838.545 214.896 323.006 + endloop + endfacet + facet normal 0.580285 -0.683504 0.442823 + outer loop + vertex 846.199 221.386 322.994 + vertex 839.59 218.778 327.629 + vertex 838.545 214.896 323.006 + endloop + endfacet + facet normal 0.580343 -0.683343 0.442995 + outer loop + vertex 847.09 225.116 327.58 + vertex 839.59 218.778 327.629 + vertex 846.199 221.386 322.994 + endloop + endfacet + facet normal 0.601798 -0.67283 0.430276 + outer loop + vertex 853.177 227.63 322.997 + vertex 847.09 225.116 327.58 + vertex 846.199 221.386 322.994 + endloop + endfacet + facet normal 0.599745 -0.678271 0.424564 + outer loop + vertex 853.535 230.85 327.637 + vertex 847.09 225.116 327.58 + vertex 853.177 227.63 322.997 + endloop + endfacet + facet normal 0.612842 -0.670498 0.418159 + outer loop + vertex 858.317 232.568 323.383 + vertex 853.535 230.85 327.637 + vertex 853.177 227.63 322.997 + endloop + endfacet + facet normal 0.61192 -0.672479 0.416323 + outer loop + vertex 858.335 235.559 328.187 + vertex 853.535 230.85 327.637 + vertex 858.317 232.568 323.383 + endloop + endfacet + facet normal 0.611167 -0.672972 0.416633 + outer loop + vertex 858.335 235.559 328.187 + vertex 858.317 232.568 323.383 + vertex 861.529 236.695 325.338 + endloop + endfacet + facet normal 0.324864 -0.774797 0.542359 + outer loop + vertex 699.926 135.695 323.004 + vertex 696.325 136.606 326.463 + vertex 697.062 134.169 322.539 + endloop + endfacet + facet normal 0.319831 -0.776715 0.542606 + outer loop + vertex 697.062 134.169 322.539 + vertex 696.325 136.606 326.463 + vertex 692.043 133.168 324.065 + endloop + endfacet + facet normal 0.29295 -0.730544 0.616835 + outer loop + vertex 700.789 143.078 332.433 + vertex 695.105 143.475 335.602 + vertex 695.863 139.937 331.052 + endloop + endfacet + facet normal 0.30168 -0.715107 0.630564 + outer loop + vertex 698.809 146.554 337.322 + vertex 695.105 143.475 335.602 + vertex 700.789 143.078 332.433 + endloop + endfacet + facet normal 0.290252 -0.72051 0.629777 + outer loop + vertex 698.809 146.554 337.322 + vertex 700.789 143.078 332.433 + vertex 705.243 146.939 334.797 + endloop + endfacet + facet normal 0.305175 -0.728006 0.613902 + outer loop + vertex 707.149 144.598 331.074 + vertex 705.243 146.939 334.797 + vertex 700.789 143.078 332.433 + endloop + endfacet + facet normal 0.311342 -0.724554 0.614889 + outer loop + vertex 713.135 147.669 331.662 + vertex 705.243 146.939 334.797 + vertex 707.149 144.598 331.074 + endloop + endfacet + facet normal 0.313125 -0.718792 0.620718 + outer loop + vertex 712.161 150.735 335.703 + vertex 705.243 146.939 334.797 + vertex 713.135 147.669 331.662 + endloop + endfacet + facet normal 0.324488 -0.715703 0.618447 + outer loop + vertex 730.589 159.193 335.949 + vertex 721.118 154.879 335.926 + vertex 730.985 155.949 331.987 + endloop + endfacet + facet normal 0.317216 -0.717193 0.62049 + outer loop + vertex 721.626 151.658 331.931 + vertex 712.161 150.735 335.703 + vertex 713.135 147.669 331.662 + endloop + endfacet + facet normal 0.301071 -0.687541 0.66079 + outer loop + vertex 720.513 158.232 339.69 + vertex 711.397 154.18 339.628 + vertex 721.118 154.879 335.926 + endloop + endfacet + facet normal 0.294058 -0.692993 0.658248 + outer loop + vertex 712.161 150.735 335.703 + vertex 703.053 150.371 339.388 + vertex 705.243 146.939 334.797 + endloop + endfacet + facet normal 0.280303 -0.659162 0.697808 + outer loop + vertex 711.047 157.862 343.247 + vertex 703.33 154.593 343.258 + vertex 711.397 154.18 339.628 + endloop + endfacet + facet normal 0.299806 -0.690026 0.658772 + outer loop + vertex 705.243 146.939 334.797 + vertex 703.053 150.371 339.388 + vertex 698.809 146.554 337.322 + endloop + endfacet + facet normal 0.278223 -0.701293 0.656339 + outer loop + vertex 698.809 146.554 337.322 + vertex 693.894 146.904 339.78 + vertex 695.105 143.475 335.602 + endloop + endfacet + facet normal 0.277958 -0.64796 0.709146 + outer loop + vertex 697.516 152.237 343.363 + vertex 693.759 150.254 343.024 + vertex 697.068 149.173 340.74 + endloop + endfacet + facet normal 0.279968 -0.693225 0.664121 + outer loop + vertex 690.698 146.033 340.218 + vertex 690.647 143.731 337.836 + vertex 693.894 146.904 339.78 + endloop + endfacet + facet normal 0.241645 -0.66376 0.707835 + outer loop + vertex 685.376 148.029 343.929 + vertex 686.001 144.106 340.037 + vertex 690.429 147.993 342.169 + endloop + endfacet + facet normal 0.245766 -0.649691 0.719375 + outer loop + vertex 690.429 147.993 342.169 + vertex 690.575 150.743 344.604 + vertex 685.376 148.029 343.929 + endloop + endfacet + facet normal 0.234337 -0.632493 0.738268 + outer loop + vertex 690.575 150.743 344.604 + vertex 688.75 152.181 346.415 + vertex 685.376 148.029 343.929 + endloop + endfacet + facet normal 0.228095 -0.629907 0.742422 + outer loop + vertex 683.856 151.326 347.193 + vertex 685.376 148.029 343.929 + vertex 688.75 152.181 346.415 + endloop + endfacet + facet normal 0.226724 -0.598246 0.768569 + outer loop + vertex 688.75 152.181 346.415 + vertex 688.999 155.223 348.709 + vertex 683.856 151.326 347.193 + endloop + endfacet + facet normal 0.210524 -0.583117 0.784636 + outer loop + vertex 684.03 155.703 350.4 + vertex 683.856 151.326 347.193 + vertex 688.999 155.223 348.709 + endloop + endfacet + facet normal 0.214662 -0.570034 0.793084 + outer loop + vertex 688.999 155.223 348.709 + vertex 689.484 158.555 350.973 + vertex 684.03 155.703 350.4 + endloop + endfacet + facet normal 0.194767 -0.537488 0.820471 + outer loop + vertex 689.484 158.555 350.973 + vertex 687.748 160.281 352.516 + vertex 684.03 155.703 350.4 + endloop + endfacet + facet normal 0.179958 -0.529426 0.82905 + outer loop + vertex 682.945 159.573 353.106 + vertex 684.03 155.703 350.4 + vertex 687.748 160.281 352.516 + endloop + endfacet + facet normal 0.176254 -0.478253 0.860353 + outer loop + vertex 687.748 160.281 352.516 + vertex 688.22 163.729 354.336 + vertex 682.945 159.573 353.106 + endloop + endfacet + facet normal 0.20427 -0.478683 0.853895 + outer loop + vertex 688.22 163.729 354.336 + vertex 687.748 160.281 352.516 + vertex 692.153 162.075 352.468 + endloop + endfacet + facet normal 0.196092 -0.524524 0.828506 + outer loop + vertex 684.03 155.703 350.4 + vertex 682.945 159.573 353.106 + vertex 675.929 153.289 350.789 + endloop + endfacet + facet normal 0.179565 -0.51062 0.840847 + outer loop + vertex 675.929 153.289 350.789 + vertex 682.945 159.573 353.106 + vertex 675.6 157.7 353.537 + endloop + endfacet + facet normal 0.189759 -0.509055 0.839556 + outer loop + vertex 675.929 153.289 350.789 + vertex 675.6 157.7 353.537 + vertex 667.332 150.265 350.898 + endloop + endfacet + facet normal 0.186369 -0.506173 0.842054 + outer loop + vertex 667.332 150.265 350.898 + vertex 675.6 157.7 353.537 + vertex 666.969 154.746 353.672 + endloop + endfacet + facet normal 0.18694 -0.506082 0.841982 + outer loop + vertex 667.332 150.265 350.898 + vertex 666.969 154.746 353.672 + vertex 658.607 147.021 350.885 + endloop + endfacet + facet normal 0.189947 -0.508556 0.839816 + outer loop + vertex 658.607 147.021 350.885 + vertex 666.969 154.746 353.672 + vertex 658.202 151.492 353.685 + endloop + endfacet + facet normal 0.184683 -0.509435 0.840457 + outer loop + vertex 658.607 147.021 350.885 + vertex 658.202 151.492 353.685 + vertex 650.089 143.919 350.877 + endloop + endfacet + facet normal 0.184693 -0.509442 0.84045 + outer loop + vertex 650.089 143.919 350.877 + vertex 658.202 151.492 353.685 + vertex 649.68 148.392 353.678 + endloop + endfacet + facet normal 0.176521 -0.510781 0.841394 + outer loop + vertex 650.089 143.919 350.877 + vertex 649.68 148.392 353.678 + vertex 641.585 140.98 350.877 + endloop + endfacet + facet normal 0.177178 -0.511322 0.840927 + outer loop + vertex 641.585 140.98 350.877 + vertex 649.68 148.392 353.678 + vertex 641.157 145.446 353.682 + endloop + endfacet + facet normal 0.168323 -0.512762 0.841868 + outer loop + vertex 641.585 140.98 350.877 + vertex 641.157 145.446 353.682 + vertex 632.718 138.014 350.843 + endloop + endfacet + facet normal 0.169973 -0.514179 0.840672 + outer loop + vertex 632.718 138.014 350.843 + vertex 641.157 145.446 353.682 + vertex 632.287 142.473 353.658 + endloop + endfacet + facet normal 0.16311 -0.515276 0.841359 + outer loop + vertex 632.718 138.014 350.843 + vertex 632.287 142.473 353.658 + vertex 623.541 134.976 350.762 + endloop + endfacet + facet normal 0.165793 -0.517641 0.839381 + outer loop + vertex 623.541 134.976 350.762 + vertex 632.287 142.473 353.658 + vertex 623.212 139.468 353.597 + endloop + endfacet + facet normal 0.161786 -0.518208 0.839813 + outer loop + vertex 623.541 134.976 350.762 + vertex 623.212 139.468 353.597 + vertex 614.885 132.219 350.728 + endloop + endfacet + facet normal 0.163303 -0.519515 0.838711 + outer loop + vertex 614.885 132.219 350.728 + vertex 623.212 139.468 353.597 + vertex 614.772 136.795 353.584 + endloop + endfacet + facet normal 0.166032 -0.519224 0.838355 + outer loop + vertex 614.885 132.219 350.728 + vertex 614.772 136.795 353.584 + vertex 607.817 130.286 350.931 + endloop + endfacet + facet normal 0.162275 -0.516255 0.840921 + outer loop + vertex 607.817 130.286 350.931 + vertex 614.772 136.795 353.584 + vertex 607.724 134.863 353.758 + endloop + endfacet + facet normal 0.175523 -0.514868 0.839108 + outer loop + vertex 607.817 130.286 350.931 + vertex 607.724 134.863 353.758 + vertex 602.292 129.263 351.459 + endloop + endfacet + facet normal 0.158408 -0.502672 0.84984 + outer loop + vertex 602.292 129.263 351.459 + vertex 607.724 134.863 353.758 + vertex 601.978 133.784 354.191 + endloop + endfacet + facet normal 0.219909 -0.51781 0.826748 + outer loop + vertex 687.748 160.281 352.516 + vertex 689.484 158.555 350.973 + vertex 692.153 162.075 352.468 + endloop + endfacet + facet normal 0.233705 -0.569431 0.788118 + outer loop + vertex 689.484 158.555 350.973 + vertex 688.999 155.223 348.709 + vertex 693.092 157.881 349.416 + endloop + endfacet + facet normal 0.220109 -0.582114 0.782748 + outer loop + vertex 683.856 151.326 347.193 + vertex 684.03 155.703 350.4 + vertex 676.41 149.226 347.725 + endloop + endfacet + facet normal 0.208772 -0.572856 0.792623 + outer loop + vertex 676.41 149.226 347.725 + vertex 684.03 155.703 350.4 + vertex 675.929 153.289 350.789 + endloop + endfacet + facet normal 0.213948 -0.571785 0.792015 + outer loop + vertex 676.41 149.226 347.725 + vertex 675.929 153.289 350.789 + vertex 667.788 146.127 347.817 + endloop + endfacet + facet normal 0.210233 -0.568851 0.795117 + outer loop + vertex 667.788 146.127 347.817 + vertex 675.929 153.289 350.789 + vertex 667.332 150.265 350.898 + endloop + endfacet + facet normal 0.209445 -0.569008 0.795212 + outer loop + vertex 667.788 146.127 347.817 + vertex 667.332 150.265 350.898 + vertex 659.068 142.847 347.767 + endloop + endfacet + facet normal 0.210789 -0.570043 0.794115 + outer loop + vertex 659.068 142.847 347.767 + vertex 667.332 150.265 350.898 + vertex 658.607 147.021 350.885 + endloop + endfacet + facet normal 0.20546 -0.571105 0.794749 + outer loop + vertex 659.068 142.847 347.767 + vertex 658.607 147.021 350.885 + vertex 650.558 139.737 347.732 + endloop + endfacet + facet normal 0.20785 -0.572913 0.792824 + outer loop + vertex 650.558 139.737 347.732 + vertex 658.607 147.021 350.885 + vertex 650.089 143.919 350.877 + endloop + endfacet + facet normal 0.19665 -0.575117 0.794084 + outer loop + vertex 650.558 139.737 347.732 + vertex 650.089 143.919 350.877 + vertex 642.059 136.807 347.714 + endloop + endfacet + facet normal 0.199511 -0.577318 0.79177 + outer loop + vertex 642.059 136.807 347.714 + vertex 650.089 143.919 350.877 + vertex 641.585 140.98 350.877 + endloop + endfacet + facet normal 0.188862 -0.579369 0.792883 + outer loop + vertex 642.059 136.807 347.714 + vertex 641.585 140.98 350.877 + vertex 633.207 133.85 347.662 + endloop + endfacet + facet normal 0.191509 -0.581491 0.790691 + outer loop + vertex 633.207 133.85 347.662 + vertex 641.585 140.98 350.877 + vertex 632.718 138.014 350.843 + endloop + endfacet + facet normal 0.182113 -0.583282 0.791592 + outer loop + vertex 633.207 133.85 347.662 + vertex 632.718 138.014 350.843 + vertex 624.003 130.809 347.539 + endloop + endfacet + facet normal 0.187598 -0.587793 0.78696 + outer loop + vertex 624.003 130.809 347.539 + vertex 632.718 138.014 350.843 + vertex 623.541 134.976 350.762 + endloop + endfacet + facet normal 0.181849 -0.588858 0.787513 + outer loop + vertex 624.003 130.809 347.539 + vertex 623.541 134.976 350.762 + vertex 615.197 127.974 347.452 + endloop + endfacet + facet normal 0.185412 -0.591702 0.784545 + outer loop + vertex 615.197 127.974 347.452 + vertex 623.541 134.976 350.762 + vertex 614.885 132.219 350.728 + endloop + endfacet + facet normal 0.186128 -0.591586 0.784463 + outer loop + vertex 615.197 127.974 347.452 + vertex 614.885 132.219 350.728 + vertex 607.978 125.937 347.629 + endloop + endfacet + facet normal 0.183886 -0.589977 0.786202 + outer loop + vertex 607.978 125.937 347.629 + vertex 614.885 132.219 350.728 + vertex 607.817 130.286 350.931 + endloop + endfacet + facet normal 0.197262 -0.58809 0.784371 + outer loop + vertex 607.978 125.937 347.629 + vertex 607.817 130.286 350.931 + vertex 603.144 125.251 348.331 + endloop + endfacet + facet normal 0.183239 -0.579937 0.793786 + outer loop + vertex 603.144 125.251 348.331 + vertex 607.817 130.286 350.931 + vertex 602.292 129.263 351.459 + endloop + endfacet + facet normal 0.246144 -0.596401 0.764015 + outer loop + vertex 688.999 155.223 348.709 + vertex 688.75 152.181 346.415 + vertex 692.909 153.68 346.245 + endloop + endfacet + facet normal 0.250734 -0.59014 0.767377 + outer loop + vertex 692.909 153.68 346.245 + vertex 693.092 157.881 349.416 + vertex 688.999 155.223 348.709 + endloop + endfacet + facet normal 0.237049 -0.62615 0.742795 + outer loop + vertex 685.376 148.029 343.929 + vertex 683.856 151.326 347.193 + vertex 677.046 145.444 344.408 + endloop + endfacet + facet normal 0.22849 -0.619953 0.750634 + outer loop + vertex 677.046 145.444 344.408 + vertex 683.856 151.326 347.193 + vertex 676.41 149.226 347.725 + endloop + endfacet + facet normal 0.231941 -0.619077 0.750297 + outer loop + vertex 677.046 145.444 344.408 + vertex 676.41 149.226 347.725 + vertex 668.333 142.293 344.502 + endloop + endfacet + facet normal 0.230008 -0.617648 0.752069 + outer loop + vertex 668.333 142.293 344.502 + vertex 676.41 149.226 347.725 + vertex 667.788 146.127 347.817 + endloop + endfacet + facet normal 0.226691 -0.618433 0.75243 + outer loop + vertex 668.333 142.293 344.502 + vertex 667.788 146.127 347.817 + vertex 659.576 138.974 344.412 + endloop + endfacet + facet normal 0.228884 -0.620015 0.750462 + outer loop + vertex 659.576 138.974 344.412 + vertex 667.788 146.127 347.817 + vertex 659.068 142.847 347.767 + endloop + endfacet + facet normal 0.220665 -0.621884 0.751377 + outer loop + vertex 659.576 138.974 344.412 + vertex 659.068 142.847 347.767 + vertex 651.055 135.852 344.33 + endloop + endfacet + facet normal 0.225451 -0.625279 0.747126 + outer loop + vertex 651.055 135.852 344.33 + vertex 659.068 142.847 347.767 + vertex 650.558 139.737 347.732 + endloop + endfacet + facet normal 0.212031 -0.628251 0.748561 + outer loop + vertex 651.055 135.852 344.33 + vertex 650.558 139.737 347.732 + vertex 642.559 132.922 344.278 + endloop + endfacet + facet normal 0.216084 -0.631172 0.744936 + outer loop + vertex 642.559 132.922 344.278 + vertex 650.558 139.737 347.732 + vertex 642.059 136.807 347.714 + endloop + endfacet + facet normal 0.203434 -0.6339 0.74618 + outer loop + vertex 642.559 132.922 344.278 + vertex 642.059 136.807 347.714 + vertex 633.727 129.983 344.189 + endloop + endfacet + facet normal 0.208687 -0.637829 0.741366 + outer loop + vertex 633.727 129.983 344.189 + vertex 642.059 136.807 347.714 + vertex 633.207 133.85 347.662 + endloop + endfacet + facet normal 0.196888 -0.640357 0.742413 + outer loop + vertex 633.727 129.983 344.189 + vertex 633.207 133.85 347.662 + vertex 624.541 126.957 344.015 + endloop + endfacet + facet normal 0.203332 -0.645274 0.736395 + outer loop + vertex 624.541 126.957 344.015 + vertex 633.207 133.85 347.662 + vertex 624.003 130.809 347.539 + endloop + endfacet + facet normal 0.195658 -0.646923 0.737027 + outer loop + vertex 624.541 126.957 344.015 + vertex 624.003 130.809 347.539 + vertex 615.681 124.086 343.847 + endloop + endfacet + facet normal 0.202795 -0.652152 0.73046 + outer loop + vertex 615.681 124.086 343.847 + vertex 624.003 130.809 347.539 + vertex 615.197 127.974 347.452 + endloop + endfacet + facet normal 0.200534 -0.652622 0.730664 + outer loop + vertex 615.681 124.086 343.847 + vertex 615.197 127.974 347.452 + vertex 608.289 121.893 343.918 + endloop + endfacet + facet normal 0.202318 -0.653767 0.729148 + outer loop + vertex 608.289 121.893 343.918 + vertex 615.197 127.974 347.452 + vertex 607.978 125.937 347.629 + endloop + endfacet + facet normal 0.215039 -0.651394 0.727629 + outer loop + vertex 608.289 121.893 343.918 + vertex 607.978 125.937 347.629 + vertex 603.11 120.902 344.56 + endloop + endfacet + facet normal 0.198562 -0.642874 0.739788 + outer loop + vertex 603.11 120.902 344.56 + vertex 607.978 125.937 347.629 + vertex 603.144 125.251 348.331 + endloop + endfacet + facet normal 0.252909 -0.617331 0.744943 + outer loop + vertex 688.75 152.181 346.415 + vertex 690.575 150.743 344.604 + vertex 692.909 153.68 346.245 + endloop + endfacet + facet normal 0.256259 -0.648196 0.717059 + outer loop + vertex 690.575 150.743 344.604 + vertex 690.429 147.993 342.169 + vertex 693.759 150.254 343.024 + endloop + endfacet + facet normal 0.255088 -0.686693 0.680722 + outer loop + vertex 678.258 138.454 337.24 + vertex 677.825 141.897 340.876 + vertex 669.69 135.51 337.481 + endloop + endfacet + facet normal 0.254115 -0.718483 0.647463 + outer loop + vertex 670.372 132.585 333.968 + vertex 669.69 135.51 337.481 + vertex 661.631 129.347 333.805 + endloop + endfacet + facet normal 0.266047 -0.748674 0.607212 + outer loop + vertex 662.492 126.872 330.376 + vertex 670.372 132.585 333.968 + vertex 661.631 129.347 333.805 + endloop + endfacet + facet normal 0.270825 -0.770697 0.576784 + outer loop + vertex 663.387 124.828 327.225 + vertex 671.109 130.083 330.621 + vertex 662.492 126.872 330.376 + endloop + endfacet + facet normal 0.251283 -0.795758 0.551022 + outer loop + vertex 664.338 123.279 324.555 + vertex 663.387 124.828 327.225 + vertex 655.917 120.227 323.986 + endloop + endfacet + facet normal 0.275403 -0.796742 0.537917 + outer loop + vertex 665.406 122.247 322.478 + vertex 672.704 126.407 324.903 + vertex 664.338 123.279 324.555 + endloop + endfacet + facet normal 0.259142 -0.81564 0.517278 + outer loop + vertex 666.619 121.569 320.801 + vertex 665.406 122.247 322.478 + vertex 659.118 119.002 320.512 + endloop + endfacet + facet normal 0.265281 -0.830487 0.489814 + outer loop + vertex 666.619 121.569 320.801 + vertex 659.118 119.002 320.512 + vertex 660.84 118.779 319.201 + endloop + endfacet + facet normal 0.238881 -0.80573 0.541973 + outer loop + vertex 660.84 118.779 319.201 + vertex 665.137 120.385 319.695 + vertex 666.619 121.569 320.801 + endloop + endfacet + facet normal 0.230035 -0.886984 0.40043 + outer loop + vertex 635.005 111.59 318.5 + vertex 640.395 113.67 320.011 + vertex 634.573 112.102 319.882 + endloop + endfacet + facet normal 0.229075 -0.957769 0.173789 + outer loop + vertex 611.062 104.249 310.968 + vertex 612.791 105.072 313.228 + vertex 609.673 104.207 312.57 + endloop + endfacet + facet normal 0.222237 -0.958375 0.179242 + outer loop + vertex 614.144 105.094 311.669 + vertex 612.791 105.072 313.228 + vertex 611.062 104.249 310.968 + endloop + endfacet + facet normal 0.226441 -0.956696 0.182913 + outer loop + vertex 614.144 105.094 311.669 + vertex 616.953 106.24 314.185 + vertex 612.791 105.072 313.228 + endloop + endfacet + facet normal 0.212612 -0.956785 0.198388 + outer loop + vertex 617.854 106.105 312.568 + vertex 616.953 106.24 314.185 + vertex 614.144 105.094 311.669 + endloop + endfacet + facet normal 0.218071 -0.954951 0.201278 + outer loop + vertex 616.953 106.24 314.185 + vertex 617.854 106.105 312.568 + vertex 622.084 107.641 315.272 + endloop + endfacet + facet normal 0.200138 -0.952837 0.228137 + outer loop + vertex 621.328 106.98 313.174 + vertex 622.084 107.641 315.272 + vertex 617.854 106.105 312.568 + endloop + endfacet + facet normal 0.222947 -0.972117 0.0726789 + outer loop + vertex 609.329 103.607 309.079 + vertex 610.266 103.666 307.004 + vertex 611.878 104.19 309.065 + endloop + endfacet + facet normal 0.266056 -0.959509 0.092508 + outer loop + vertex 610.266 103.666 307.004 + vertex 609.329 103.607 309.079 + vertex 609.125 103.421 307.742 + endloop + endfacet + facet normal -0.175418 0.978444 -0.108981 + outer loop + vertex 609.318 103.499 308.133 + vertex 609.125 103.421 307.742 + vertex 609.329 103.607 309.079 + endloop + endfacet + facet normal 0.268114 -0.957583 0.105588 + outer loop + vertex 609.097 103.484 308.554 + vertex 609.318 103.499 308.133 + vertex 609.329 103.607 309.079 + endloop + endfacet + facet normal 0.248718 -0.961713 0.115101 + outer loop + vertex 608.688 103.46 309.237 + vertex 609.097 103.484 308.554 + vertex 609.329 103.607 309.079 + endloop + endfacet + facet normal 0.233726 -0.966512 0.105954 + outer loop + vertex 608.151 103.292 308.888 + vertex 609.097 103.484 308.554 + vertex 608.688 103.46 309.237 + endloop + endfacet + facet normal 0.230602 -0.966712 0.110862 + outer loop + vertex 608.151 103.292 308.888 + vertex 608.688 103.46 309.237 + vertex 607.479 103.252 309.939 + endloop + endfacet + facet normal 0.239418 -0.963889 0.116604 + outer loop + vertex 608.151 103.292 308.888 + vertex 607.479 103.252 309.939 + vertex 605.985 102.807 309.327 + endloop + endfacet + facet normal 0.236188 -0.966809 0.0974426 + outer loop + vertex 606.329 102.811 308.537 + vertex 608.151 103.292 308.888 + vertex 605.985 102.807 309.327 + endloop + endfacet + facet normal 0.241231 -0.965339 0.0996443 + outer loop + vertex 602.675 101.937 308.917 + vertex 606.329 102.811 308.537 + vertex 605.985 102.807 309.327 + endloop + endfacet + facet normal 0.240651 -0.965055 0.103714 + outer loop + vertex 602.675 101.937 308.917 + vertex 605.985 102.807 309.327 + vertex 602.557 101.985 309.633 + endloop + endfacet + facet normal 0.243767 -0.964223 0.10417 + outer loop + vertex 598.586 100.936 309.219 + vertex 602.675 101.937 308.917 + vertex 602.557 101.985 309.633 + endloop + endfacet + facet normal 0.242937 -0.963694 0.110795 + outer loop + vertex 598.586 100.936 309.219 + vertex 602.557 101.985 309.633 + vertex 597.23 100.667 309.846 + endloop + endfacet + facet normal 0.245235 -0.962463 0.116296 + outer loop + vertex 598.586 100.936 309.219 + vertex 597.23 100.667 309.846 + vertex 590.873 98.9622 309.147 + endloop + endfacet + facet normal 0.245788 -0.964058 0.1009 + outer loop + vertex 598.586 100.936 309.219 + vertex 590.873 98.9622 309.147 + vertex 597.031 100.468 308.533 + endloop + endfacet + facet normal 0.246248 -0.963218 0.107575 + outer loop + vertex 590.873 98.9622 309.147 + vertex 588.169 98.1478 308.044 + vertex 597.031 100.468 308.533 + endloop + endfacet + facet normal 0.247529 -0.964605 0.0909215 + outer loop + vertex 596.504 100.281 307.983 + vertex 597.031 100.468 308.533 + vertex 588.169 98.1478 308.044 + endloop + endfacet + facet normal 0.24762 -0.965131 0.0848867 + outer loop + vertex 588.169 98.1478 308.044 + vertex 596.057 100.128 307.55 + vertex 596.504 100.281 307.983 + endloop + endfacet + facet normal 0.24525 -0.965506 0.0874643 + outer loop + vertex 596.504 100.281 307.983 + vertex 596.057 100.128 307.55 + vertex 601.905 101.663 308.096 + endloop + endfacet + facet normal 0.245328 -0.96555 0.0867559 + outer loop + vertex 601.905 101.663 308.096 + vertex 596.057 100.128 307.55 + vertex 603.025 101.889 307.441 + endloop + endfacet + facet normal 0.241702 -0.967043 0.0800441 + outer loop + vertex 606.738 102.854 307.893 + vertex 601.905 101.663 308.096 + vertex 603.025 101.889 307.441 + endloop + endfacet + facet normal 0.241512 -0.966973 0.0814595 + outer loop + vertex 607.601 103.043 307.569 + vertex 606.738 102.854 307.893 + vertex 603.025 101.889 307.441 + endloop + endfacet + facet normal 0.242516 -0.968389 0.0583858 + outer loop + vertex 603.025 101.889 307.441 + vertex 607.137 102.919 307.454 + vertex 607.601 103.043 307.569 + endloop + endfacet + facet normal 0.233749 -0.967823 0.0931672 + outer loop + vertex 607.137 102.919 307.454 + vertex 608.318 103.21 307.513 + vertex 607.601 103.043 307.569 + endloop + endfacet + facet normal 0.233171 -0.968942 0.0823605 + outer loop + vertex 607.601 103.043 307.569 + vertex 608.318 103.21 307.513 + vertex 608.869 103.365 307.769 + endloop + endfacet + facet normal 0.224881 -0.9692 0.100404 + outer loop + vertex 608.318 103.21 307.513 + vertex 609.125 103.421 307.742 + vertex 608.869 103.365 307.769 + endloop + endfacet + facet normal -0.268866 0.961162 0.062277 + outer loop + vertex 609.125 103.421 307.742 + vertex 608.318 103.21 307.513 + vertex 606.888 102.83 307.217 + endloop + endfacet + facet normal 0.236305 -0.966362 0.101516 + outer loop + vertex 606.395 102.727 307.391 + vertex 606.888 102.83 307.217 + vertex 608.318 103.21 307.513 + endloop + endfacet + facet normal 0.239154 -0.964662 0.1106 + outer loop + vertex 606.395 102.727 307.391 + vertex 603.097 101.893 307.249 + vertex 606.888 102.83 307.217 + endloop + endfacet + facet normal 0.24182 -0.967939 0.0679442 + outer loop + vertex 603.097 101.893 307.249 + vertex 606.395 102.727 307.391 + vertex 603.025 101.889 307.441 + endloop + endfacet + facet normal 0.244626 -0.967158 0.0690221 + outer loop + vertex 596.962 100.327 307.05 + vertex 603.097 101.893 307.249 + vertex 603.025 101.889 307.441 + endloop + endfacet + facet normal 0.248608 -0.968521 0.0126625 + outer loop + vertex 596.962 100.327 307.05 + vertex 603.025 101.889 307.441 + vertex 594.474 99.6896 307.118 + endloop + endfacet + facet normal 0.249488 -0.965693 0.0720542 + outer loop + vertex 585.052 97.2375 306.878 + vertex 596.962 100.327 307.05 + vertex 594.474 99.6896 307.118 + endloop + endfacet + facet normal 0.248783 -0.964549 0.0880504 + outer loop + vertex 587.777 97.9737 307.243 + vertex 585.052 97.2375 306.878 + vertex 594.474 99.6896 307.118 + endloop + endfacet + facet normal 0.248822 -0.966098 0.0688654 + outer loop + vertex 596.057 100.128 307.55 + vertex 587.777 97.9737 307.243 + vertex 594.474 99.6896 307.118 + endloop + endfacet + facet normal 0.249942 -0.964936 0.0801782 + outer loop + vertex 571.551 93.7941 307.524 + vertex 585.052 97.2375 306.878 + vertex 587.777 97.9737 307.243 + endloop + endfacet + facet normal 0.249908 -0.964328 0.0872772 + outer loop + vertex 587.777 97.9737 307.243 + vertex 588.169 98.1478 308.044 + vertex 571.551 93.7941 307.524 + endloop + endfacet + facet normal 0.248183 -0.961454 0.118368 + outer loop + vertex 573.186 94.4458 309.388 + vertex 571.551 93.7941 307.524 + vertex 588.169 98.1478 308.044 + endloop + endfacet + facet normal 0.250064 -0.96118 0.116621 + outer loop + vertex 549.063 88.1086 308.883 + vertex 571.551 93.7941 307.524 + vertex 573.186 94.4458 309.388 + endloop + endfacet + facet normal 0.248686 -0.958015 0.142697 + outer loop + vertex 549.063 88.1086 308.883 + vertex 573.186 94.4458 309.388 + vertex 549.26 88.534 311.396 + endloop + endfacet + facet normal 0.251188 -0.957407 0.142397 + outer loop + vertex 525.807 82.3364 311.098 + vertex 549.063 88.1086 308.883 + vertex 549.26 88.534 311.396 + endloop + endfacet + facet normal 0.250095 -0.95429 0.163656 + outer loop + vertex 525.807 82.3364 311.098 + vertex 549.26 88.534 311.396 + vertex 526.088 82.95 314.247 + endloop + endfacet + facet normal 0.254149 -0.953313 0.163103 + outer loop + vertex 525.807 82.3364 311.098 + vertex 526.088 82.95 314.247 + vertex 512.237 79.1574 313.661 + endloop + endfacet + facet normal 0.252193 -0.956089 0.149305 + outer loop + vertex 509.943 78.312 312.122 + vertex 525.807 82.3364 311.098 + vertex 512.237 79.1574 313.661 + endloop + endfacet + facet normal 0.250572 -0.956131 0.151745 + outer loop + vertex 502.676 76.6652 313.746 + vertex 509.943 78.312 312.122 + vertex 512.237 79.1574 313.661 + endloop + endfacet + facet normal 0.250225 -0.954432 0.162626 + outer loop + vertex 502.676 76.6652 313.746 + vertex 512.237 79.1574 313.661 + vertex 503.381 77.1612 315.573 + endloop + endfacet + facet normal 0.245882 -0.955236 0.164519 + outer loop + vertex 498.346 75.8186 315.302 + vertex 502.676 76.6652 313.746 + vertex 503.381 77.1612 315.573 + endloop + endfacet + facet normal 0.243697 -0.951623 0.187152 + outer loop + vertex 498.346 75.8186 315.302 + vertex 503.381 77.1612 315.573 + vertex 498.639 76.2951 317.343 + endloop + endfacet + facet normal 0.227601 -0.954989 0.190246 + outer loop + vertex 498.346 75.8186 315.302 + vertex 498.639 76.2951 317.343 + vertex 495.296 75.1906 315.799 + endloop + endfacet + facet normal 0.224253 -0.960939 0.162193 + outer loop + vertex 496.957 75.1737 313.402 + vertex 498.346 75.8186 315.302 + vertex 495.296 75.1906 315.799 + endloop + endfacet + facet normal 0.214991 -0.964109 0.155795 + outer loop + vertex 495.296 75.1906 315.799 + vertex 493.428 74.0845 311.532 + vertex 496.957 75.1737 313.402 + endloop + endfacet + facet normal 0.224133 -0.964618 0.138843 + outer loop + vertex 496.695 74.8447 311.539 + vertex 496.957 75.1737 313.402 + vertex 493.428 74.0845 311.532 + endloop + endfacet + facet normal 0.225092 -0.968433 0.1071 + outer loop + vertex 496.221 74.5889 310.222 + vertex 496.695 74.8447 311.539 + vertex 493.428 74.0845 311.532 + endloop + endfacet + facet normal 0.219549 -0.971035 0.0942787 + outer loop + vertex 494.986 74.1797 308.884 + vertex 496.221 74.5889 310.222 + vertex 493.428 74.0845 311.532 + endloop + endfacet + facet normal 0.226457 -0.969037 0.0984155 + outer loop + vertex 493.428 74.0845 311.532 + vertex 491.407 73.2621 308.084 + vertex 494.986 74.1797 308.884 + endloop + endfacet + facet normal 0.231617 -0.969816 0.0762221 + outer loop + vertex 494.857 74.0457 307.569 + vertex 494.986 74.1797 308.884 + vertex 491.407 73.2621 308.084 + endloop + endfacet + facet normal 0.230452 -0.970778 0.0669513 + outer loop + vertex 494.237 73.8691 307.143 + vertex 494.857 74.0457 307.569 + vertex 491.407 73.2621 308.084 + endloop + endfacet + facet normal -0.367277 0.448673 -0.814739 + outer loop + vertex 495.868 74.2553 306.62 + vertex 494.237 73.8691 307.143 + vertex 491.407 73.2621 308.084 + endloop + endfacet + facet normal 0.228761 -0.972774 0.037136 + outer loop + vertex 491.407 73.2621 308.084 + vertex 488.598 72.5247 306.068 + vertex 495.868 74.2553 306.62 + endloop + endfacet + facet normal 0.246069 -0.969182 0.0117174 + outer loop + vertex 488.598 72.5247 306.068 + vertex 491.407 73.2621 308.084 + vertex 488.031 72.3989 307.576 + endloop + endfacet + facet normal 0.234128 -0.972181 0.00697737 + outer loop + vertex 488.031 72.3989 307.576 + vertex 485.201 71.7205 308.013 + vertex 488.598 72.5247 306.068 + endloop + endfacet + facet normal 0.241703 -0.970122 0.0210549 + outer loop + vertex 485.097 71.6852 307.583 + vertex 488.598 72.5247 306.068 + vertex 485.201 71.7205 308.013 + endloop + endfacet + facet normal 0.23239 -0.972339 0.0234954 + outer loop + vertex 480.098 70.544 309.803 + vertex 485.097 71.6852 307.583 + vertex 485.201 71.7205 308.013 + endloop + endfacet + facet normal 0.238853 -0.970085 0.0434091 + outer loop + vertex 480.098 70.544 309.803 + vertex 485.201 71.7205 308.013 + vertex 481.302 70.8519 310.06 + endloop + endfacet + facet normal 0.237703 -0.97011 0.0488285 + outer loop + vertex 481.302 70.8519 310.06 + vertex 475.576 69.5476 312.02 + vertex 480.098 70.544 309.803 + endloop + endfacet + facet normal 0.241396 -0.968753 0.0569707 + outer loop + vertex 475.576 69.5476 312.02 + vertex 472.238 68.7626 312.815 + vertex 480.098 70.544 309.803 + endloop + endfacet + facet normal 0.266557 -0.9549 0.130816 + outer loop + vertex 476.346 69.6819 311.155 + vertex 480.098 70.544 309.803 + vertex 472.238 68.7626 312.815 + endloop + endfacet + facet normal 0.252625 -0.963206 0.09173 + outer loop + vertex 473.458 69.0208 312.166 + vertex 476.346 69.6819 311.155 + vertex 472.238 68.7626 312.815 + endloop + endfacet + facet normal 0.249829 -0.964466 0.0859701 + outer loop + vertex 469.132 68.0389 313.72 + vertex 473.458 69.0208 312.166 + vertex 472.238 68.7626 312.815 + endloop + endfacet + facet normal 0.264168 -0.953703 0.143759 + outer loop + vertex 472.238 68.7626 312.815 + vertex 462.59 66.5732 316.018 + vertex 469.132 68.0389 313.72 + endloop + endfacet + facet normal 0.273083 -0.946128 0.173975 + outer loop + vertex 466.531 67.4454 314.576 + vertex 469.132 68.0389 313.72 + vertex 462.59 66.5732 316.018 + endloop + endfacet + facet normal 0.254942 -0.959969 0.116033 + outer loop + vertex 464.042 66.8783 315.353 + vertex 466.531 67.4454 314.576 + vertex 462.59 66.5732 316.018 + endloop + endfacet + facet normal 0.253992 -0.960498 0.113715 + outer loop + vertex 460.998 66.1905 316.343 + vertex 464.042 66.8783 315.353 + vertex 462.59 66.5732 316.018 + endloop + endfacet + facet normal 0.259752 -0.954024 0.149555 + outer loop + vertex 457.582 65.42 317.36 + vertex 460.998 66.1905 316.343 + vertex 462.59 66.5732 316.018 + endloop + endfacet + facet normal 0.266866 -0.946239 0.182798 + outer loop + vertex 462.59 66.5732 316.018 + vertex 451.406 64.046 319.264 + vertex 457.582 65.42 317.36 + endloop + endfacet + facet normal 0.247822 -0.962631 0.109209 + outer loop + vertex 453.168 64.4177 318.542 + vertex 457.582 65.42 317.36 + vertex 451.406 64.046 319.264 + endloop + endfacet + facet normal 0.243509 -0.964988 0.0974715 + outer loop + vertex 447.603 63.1663 320.055 + vertex 453.168 64.4177 318.542 + vertex 451.406 64.046 319.264 + endloop + endfacet + facet normal 0.253351 -0.954663 0.156309 + outer loop + vertex 451.406 64.046 319.264 + vertex 440.966 61.6958 321.831 + vertex 447.603 63.1663 320.055 + endloop + endfacet + facet normal 0.24764 -0.960017 0.130543 + outer loop + vertex 442.886 62.1009 321.17 + vertex 447.603 63.1663 320.055 + vertex 440.966 61.6958 321.831 + endloop + endfacet + facet normal 0.241363 -0.964207 0.109764 + outer loop + vertex 437.227 60.8374 322.513 + vertex 442.886 62.1009 321.17 + vertex 440.966 61.6958 321.831 + endloop + endfacet + facet normal 0.258702 -0.935367 0.241169 + outer loop + vertex 440.966 61.6958 321.831 + vertex 430.426 59.3507 324.043 + vertex 437.227 60.8374 322.513 + endloop + endfacet + facet normal 0.2541 -0.94347 0.212834 + outer loop + vertex 432.321 59.7399 323.505 + vertex 437.227 60.8374 322.513 + vertex 430.426 59.3507 324.043 + endloop + endfacet + facet normal 0.244445 -0.954495 0.17084 + outer loop + vertex 426.42 58.4393 324.683 + vertex 432.321 59.7399 323.505 + vertex 430.426 59.3507 324.043 + endloop + endfacet + facet normal 0.264209 -0.872169 0.411722 + outer loop + vertex 430.426 59.3507 324.043 + vertex 419.528 56.9644 325.981 + vertex 426.42 58.4393 324.683 + endloop + endfacet + facet normal 0.251721 -0.924647 0.285769 + outer loop + vertex 421.102 57.2668 325.573 + vertex 426.42 58.4393 324.683 + vertex 419.528 56.9644 325.981 + endloop + endfacet + facet normal 0.226184 -0.971451 0.0715751 + outer loop + vertex 426.42 58.4393 324.683 + vertex 421.102 57.2668 325.573 + vertex 427.991 58.7592 324.06 + endloop + endfacet + facet normal 0.225572 -0.971821 0.0684219 + outer loop + vertex 416.645 56.263 326.01 + vertex 427.991 58.7592 324.06 + vertex 421.102 57.2668 325.573 + endloop + endfacet + facet normal 0.229658 -0.965154 0.125443 + outer loop + vertex 421.102 57.2668 325.573 + vertex 414.846 55.9121 326.603 + vertex 416.645 56.263 326.01 + endloop + endfacet + facet normal 0.226273 -0.967388 0.113849 + outer loop + vertex 414.846 55.9121 326.603 + vertex 408.391 54.5069 327.493 + vertex 416.645 56.263 326.01 + endloop + endfacet + facet normal 0.229857 -0.963297 0.138651 + outer loop + vertex 407.225 54.1988 327.284 + vertex 416.645 56.263 326.01 + vertex 408.391 54.5069 327.493 + endloop + endfacet + facet normal 0.225108 -0.969901 0.0928334 + outer loop + vertex 407.225 54.1988 327.284 + vertex 414.046 55.614 325.532 + vertex 416.645 56.263 326.01 + endloop + endfacet + facet normal 0.227804 -0.970499 0.0789727 + outer loop + vertex 414.046 55.614 325.532 + vertex 424.671 57.964 323.762 + vertex 416.645 56.263 326.01 + endloop + endfacet + facet normal 0.220599 -0.974907 0.0298677 + outer loop + vertex 414.046 55.614 325.532 + vertex 421.645 57.2458 322.669 + vertex 424.671 57.964 323.762 + endloop + endfacet + facet normal 0.222992 -0.974549 0.0230074 + outer loop + vertex 421.645 57.2458 322.669 + vertex 432.545 59.6863 320.4 + vertex 424.671 57.964 323.762 + endloop + endfacet + facet normal 0.22133 -0.975016 0.0188759 + outer loop + vertex 424.671 57.964 323.762 + vertex 432.545 59.6863 320.4 + vertex 435.795 60.4447 321.459 + endloop + endfacet + facet normal 0.227998 -0.972153 0.0541713 + outer loop + vertex 424.671 57.964 323.762 + vertex 435.795 60.4447 321.459 + vertex 427.991 58.7592 324.06 + endloop + endfacet + facet normal 0.227773 -0.972247 0.0534339 + outer loop + vertex 427.991 58.7592 324.06 + vertex 435.795 60.4447 321.459 + vertex 438.946 61.199 321.754 + endloop + endfacet + facet normal 0.226028 -0.973117 0.0442239 + outer loop + vertex 427.991 58.7592 324.06 + vertex 438.946 61.199 321.754 + vertex 432.321 59.7399 323.505 + endloop + endfacet + facet normal 0.22881 -0.97252 0.0430318 + outer loop + vertex 435.795 60.4447 321.459 + vertex 446.802 62.9188 318.851 + vertex 438.946 61.199 321.754 + endloop + endfacet + facet normal 0.229433 -0.97229 0.0448541 + outer loop + vertex 438.946 61.199 321.754 + vertex 446.802 62.9188 318.851 + vertex 449.47 63.5649 319.204 + endloop + endfacet + facet normal 0.22898 -0.97249 0.0428002 + outer loop + vertex 438.946 61.199 321.754 + vertex 449.47 63.5649 319.204 + vertex 442.886 62.1009 321.17 + endloop + endfacet + facet normal 0.230094 -0.972347 0.0399654 + outer loop + vertex 446.802 62.9188 318.851 + vertex 457.031 65.2328 316.258 + vertex 449.47 63.5649 319.204 + endloop + endfacet + facet normal 0.232867 -0.971341 0.0476507 + outer loop + vertex 449.47 63.5649 319.204 + vertex 457.031 65.2328 316.258 + vertex 459.841 65.9122 316.374 + endloop + endfacet + facet normal 0.232052 -0.971691 0.0443733 + outer loop + vertex 449.47 63.5649 319.204 + vertex 459.841 65.9122 316.374 + vertex 453.168 64.4177 318.542 + endloop + endfacet + facet normal 0.233242 -0.971595 0.0400189 + outer loop + vertex 457.031 65.2328 316.258 + vertex 466.048 67.2888 313.619 + vertex 459.841 65.9122 316.374 + endloop + endfacet + facet normal 0.235183 -0.970921 0.0447282 + outer loop + vertex 459.841 65.9122 316.374 + vertex 466.048 67.2888 313.619 + vertex 470.051 68.233 313.065 + endloop + endfacet + facet normal 0.231391 -0.972333 0.0320372 + outer loop + vertex 459.841 65.9122 316.374 + vertex 470.051 68.233 313.065 + vertex 464.042 66.8783 315.353 + endloop + endfacet + facet normal 0.232961 -0.972122 0.0266124 + outer loop + vertex 466.048 67.2888 313.619 + vertex 473.492 68.9982 310.899 + vertex 470.051 68.233 313.065 + endloop + endfacet + facet normal 0.231933 -0.972414 0.0248766 + outer loop + vertex 473.492 68.9982 310.899 + vertex 477.707 69.977 309.859 + vertex 470.051 68.233 313.065 + endloop + endfacet + facet normal 0.22521 -0.974302 0.00402406 + outer loop + vertex 466.048 67.2888 313.619 + vertex 470.549 68.3172 310.703 + vertex 473.492 68.9982 310.899 + endloop + endfacet + facet normal 0.225864 -0.974138 -0.00636571 + outer loop + vertex 470.549 68.3172 310.703 + vertex 475.884 69.5686 308.471 + vertex 473.492 68.9982 310.899 + endloop + endfacet + facet normal 0.22085 -0.975239 -0.0115623 + outer loop + vertex 473.492 68.9982 310.899 + vertex 475.884 69.5686 308.471 + vertex 478.138 70.0752 308.797 + endloop + endfacet + facet normal 0.226597 -0.973987 0.00178125 + outer loop + vertex 478.138 70.0752 308.797 + vertex 477.707 69.977 309.859 + vertex 473.492 68.9982 310.899 + endloop + endfacet + facet normal 0.228479 -0.973545 0.00258521 + outer loop + vertex 478.138 70.0752 308.797 + vertex 481.261 70.8051 307.654 + vertex 477.707 69.977 309.859 + endloop + endfacet + facet normal 0.222615 -0.974879 -0.00736512 + outer loop + vertex 477.707 69.977 309.859 + vertex 481.261 70.8051 307.654 + vertex 482.16 71.0065 308.174 + endloop + endfacet + facet normal 0.230631 -0.972926 0.0150111 + outer loop + vertex 477.707 69.977 309.859 + vertex 482.16 71.0065 308.174 + vertex 478.072 70.0698 310.276 + endloop + endfacet + facet normal 0.228743 -0.973343 0.0167531 + outer loop + vertex 478.072 70.0698 310.276 + vertex 470.051 68.233 313.065 + vertex 477.707 69.977 309.859 + endloop + endfacet + facet normal 0.231736 -0.972432 0.0259601 + outer loop + vertex 470.051 68.233 313.065 + vertex 478.072 70.0698 310.276 + vertex 473.458 69.0208 312.166 + endloop + endfacet + facet normal 0.22415 -0.974553 0.00168009 + outer loop + vertex 478.072 70.0698 310.276 + vertex 482.16 71.0065 308.174 + vertex 483.349 71.2798 308.11 + endloop + endfacet + facet normal 0.23356 -0.971994 0.0260368 + outer loop + vertex 478.072 70.0698 310.276 + vertex 483.349 71.2798 308.11 + vertex 480.098 70.544 309.803 + endloop + endfacet + facet normal 0.223778 -0.974624 -0.00552992 + outer loop + vertex 482.16 71.0065 308.174 + vertex 485.07 71.6825 306.804 + vertex 483.349 71.2798 308.11 + endloop + endfacet + facet normal 0.221797 -0.975058 -0.00827521 + outer loop + vertex 483.349 71.2798 308.11 + vertex 485.07 71.6825 306.804 + vertex 486.185 71.9359 306.822 + endloop + endfacet + facet normal 0.226846 -0.973925 0.00342658 + outer loop + vertex 483.349 71.2798 308.11 + vertex 486.185 71.9359 306.822 + vertex 485.097 71.6852 307.583 + endloop + endfacet + facet normal 0.221894 -0.974947 -0.0155684 + outer loop + vertex 486.185 71.9359 306.822 + vertex 485.07 71.6825 306.804 + vertex 486.604 72.0415 306.186 + endloop + endfacet + facet normal 0.235117 -0.971946 -0.00635354 + outer loop + vertex 486.185 71.9359 306.822 + vertex 486.604 72.0415 306.186 + vertex 488.598 72.5247 306.068 + endloop + endfacet + facet normal 0.231042 -0.970486 -0.0691134 + outer loop + vertex 486.604 72.0415 306.186 + vertex 484.782 71.6547 305.526 + vertex 488.598 72.5247 306.068 + endloop + endfacet + facet normal 0.227953 -0.972685 -0.0438319 + outer loop + vertex 483.752 71.4713 304.24 + vertex 488.598 72.5247 306.068 + vertex 484.782 71.6547 305.526 + endloop + endfacet + facet normal 0.217173 -0.975738 -0.0277558 + outer loop + vertex 484.782 71.6547 305.526 + vertex 486.604 72.0415 306.186 + vertex 485.07 71.6825 306.804 + endloop + endfacet + facet normal 0.221131 -0.974823 -0.0286692 + outer loop + vertex 483.774 71.3919 306.685 + vertex 484.782 71.6547 305.526 + vertex 485.07 71.6825 306.804 + endloop + endfacet + facet normal 0.219486 -0.975149 -0.030174 + outer loop + vertex 483.774 71.3919 306.685 + vertex 482.204 71.0673 305.754 + vertex 484.782 71.6547 305.526 + endloop + endfacet + facet normal 0.217533 -0.975688 -0.0266928 + outer loop + vertex 481.261 70.8051 307.654 + vertex 482.204 71.0673 305.754 + vertex 483.774 71.3919 306.685 + endloop + endfacet + facet normal 0.222589 -0.974616 -0.0240354 + outer loop + vertex 479.667 70.4614 306.83 + vertex 482.204 71.0673 305.754 + vertex 481.261 70.8051 307.654 + endloop + endfacet + facet normal 0.216989 -0.975445 -0.0377105 + outer loop + vertex 479.667 70.4614 306.83 + vertex 479.757 70.5556 304.912 + vertex 482.204 71.0673 305.754 + endloop + endfacet + facet normal 0.223312 -0.973047 -0.0575413 + outer loop + vertex 479.757 70.5556 304.912 + vertex 480.343 70.7609 303.716 + vertex 482.204 71.0673 305.754 + endloop + endfacet + facet normal 0.214009 -0.974836 -0.0624085 + outer loop + vertex 479.757 70.5556 304.912 + vertex 476.76 69.993 303.422 + vertex 480.343 70.7609 303.716 + endloop + endfacet + facet normal 0.211036 -0.975871 -0.056035 + outer loop + vertex 477.066 69.9228 305.8 + vertex 476.76 69.993 303.422 + vertex 479.757 70.5556 304.912 + endloop + endfacet + facet normal 0.214208 -0.975157 -0.0564229 + outer loop + vertex 473.946 69.3142 304.472 + vertex 476.76 69.993 303.422 + vertex 477.066 69.9228 305.8 + endloop + endfacet + facet normal 0.2117 -0.976049 -0.0501232 + outer loop + vertex 473.212 68.9975 307.541 + vertex 473.946 69.3142 304.472 + vertex 477.066 69.9228 305.8 + endloop + endfacet + facet normal 0.219642 -0.975055 -0.032018 + outer loop + vertex 473.212 68.9975 307.541 + vertex 477.066 69.9228 305.8 + vertex 475.884 69.5686 308.471 + endloop + endfacet + facet normal 0.215578 -0.975897 -0.0339297 + outer loop + vertex 475.884 69.5686 308.471 + vertex 477.066 69.9228 305.8 + vertex 479.667 70.4614 306.83 + endloop + endfacet + facet normal 0.215176 -0.975334 -0.0492192 + outer loop + vertex 470.308 68.4236 306.216 + vertex 473.946 69.3142 304.472 + vertex 473.212 68.9975 307.541 + endloop + endfacet + facet normal 0.213659 -0.97584 -0.045677 + outer loop + vertex 468.32 67.8259 309.684 + vertex 470.308 68.4236 306.216 + vertex 473.212 68.9975 307.541 + endloop + endfacet + facet normal 0.224203 -0.974321 -0.020766 + outer loop + vertex 468.32 67.8259 309.684 + vertex 473.212 68.9975 307.541 + vertex 470.549 68.3172 310.703 + endloop + endfacet + facet normal 0.221454 -0.975064 -0.0143974 + outer loop + vertex 463.78 66.7458 313.011 + vertex 468.32 67.8259 309.684 + vertex 470.549 68.3172 310.703 + endloop + endfacet + facet normal 0.226009 -0.974094 -0.00786919 + outer loop + vertex 463.144 66.6105 311.498 + vertex 468.32 67.8259 309.684 + vertex 463.78 66.7458 313.011 + endloop + endfacet + facet normal 0.220483 -0.975376 -0.00543158 + outer loop + vertex 463.144 66.6105 311.498 + vertex 463.78 66.7458 313.011 + vertex 455.446 64.8527 314.667 + endloop + endfacet + facet normal 0.212799 -0.976779 -0.0248803 + outer loop + vertex 463.144 66.6105 311.498 + vertex 455.446 64.8527 314.667 + vertex 460.021 65.9517 310.651 + endloop + endfacet + facet normal 0.21597 -0.975682 -0.0374236 + outer loop + vertex 460.021 65.9517 310.651 + vertex 465.849 67.3298 308.352 + vertex 463.144 66.6105 311.498 + endloop + endfacet + facet normal 0.20811 -0.976398 -0.0577754 + outer loop + vertex 460.021 65.9517 310.651 + vertex 462.985 66.8045 306.913 + vertex 465.849 67.3298 308.352 + endloop + endfacet + facet normal 0.21152 -0.97521 -0.064996 + outer loop + vertex 462.985 66.8045 306.913 + vertex 467.145 67.8509 304.752 + vertex 465.849 67.3298 308.352 + endloop + endfacet + facet normal 0.207514 -0.975966 -0.066548 + outer loop + vertex 465.849 67.3298 308.352 + vertex 467.145 67.8509 304.752 + vertex 470.308 68.4236 306.216 + endloop + endfacet + facet normal 0.208783 -0.975491 -0.0694771 + outer loop + vertex 467.145 67.8509 304.752 + vertex 470.494 68.6916 303.012 + vertex 470.308 68.4236 306.216 + endloop + endfacet + facet normal 0.197321 -0.976031 -0.0918061 + outer loop + vertex 467.145 67.8509 304.752 + vertex 466.802 68.0824 301.554 + vertex 470.494 68.6916 303.012 + endloop + endfacet + facet normal 0.199453 -0.975033 -0.0976211 + outer loop + vertex 466.802 68.0824 301.554 + vertex 469.439 68.7182 300.59 + vertex 470.494 68.6916 303.012 + endloop + endfacet + facet normal 0.198629 -0.975236 -0.0972643 + outer loop + vertex 470.494 68.6916 303.012 + vertex 469.439 68.7182 300.59 + vertex 473.176 69.3197 302.19 + endloop + endfacet + facet normal 0.206481 -0.975791 -0.0720877 + outer loop + vertex 470.494 68.6916 303.012 + vertex 473.176 69.3197 302.19 + vertex 473.946 69.3142 304.472 + endloop + endfacet + facet normal 0.202952 -0.9732 -0.108128 + outer loop + vertex 473.176 69.3197 302.19 + vertex 469.439 68.7182 300.59 + vertex 473.789 69.5704 301.086 + endloop + endfacet + facet normal 0.216782 -0.971088 -0.0999638 + outer loop + vertex 473.176 69.3197 302.19 + vertex 473.789 69.5704 301.086 + vertex 476.76 69.993 303.422 + endloop + endfacet + facet normal 0.191923 -0.97432 -0.117755 + outer loop + vertex 466.802 68.0824 301.554 + vertex 465.39 68.0724 299.336 + vertex 469.439 68.7182 300.59 + endloop + endfacet + facet normal 0.200452 -0.968412 -0.148313 + outer loop + vertex 465.39 68.0724 299.336 + vertex 465.943 68.3293 298.405 + vertex 469.439 68.7182 300.59 + endloop + endfacet + facet normal 0.182213 -0.970212 -0.159647 + outer loop + vertex 465.39 68.0724 299.336 + vertex 461.095 67.5225 297.775 + vertex 465.943 68.3293 298.405 + endloop + endfacet + facet normal 0.176529 -0.973896 -0.142705 + outer loop + vertex 462.886 67.502 300.131 + vertex 461.095 67.5225 297.775 + vertex 465.39 68.0724 299.336 + endloop + endfacet + facet normal 0.175372 -0.974233 -0.141829 + outer loop + vertex 458.474 66.9061 298.769 + vertex 461.095 67.5225 297.775 + vertex 462.886 67.502 300.131 + endloop + endfacet + facet normal 0.174987 -0.9745 -0.140464 + outer loop + vertex 460.027 66.7353 301.888 + vertex 458.474 66.9061 298.769 + vertex 462.886 67.502 300.131 + endloop + endfacet + facet normal 0.190092 -0.974884 -0.116045 + outer loop + vertex 460.027 66.7353 301.888 + vertex 462.886 67.502 300.131 + vertex 463.688 67.2812 303.299 + endloop + endfacet + facet normal 0.189259 -0.97532 -0.113716 + outer loop + vertex 459.804 66.2743 305.47 + vertex 460.027 66.7353 301.888 + vertex 463.688 67.2812 303.299 + endloop + endfacet + facet normal 0.202952 -0.975124 -0.0891287 + outer loop + vertex 459.804 66.2743 305.47 + vertex 463.688 67.2812 303.299 + vertex 462.985 66.8045 306.913 + endloop + endfacet + facet normal 0.200532 -0.976129 -0.0834246 + outer loop + vertex 458.268 65.6728 308.817 + vertex 459.804 66.2743 305.47 + vertex 462.985 66.8045 306.913 + endloop + endfacet + facet normal 0.199197 -0.976346 -0.0840759 + outer loop + vertex 454.489 64.9817 307.889 + vertex 459.804 66.2743 305.47 + vertex 458.268 65.6728 308.817 + endloop + endfacet + facet normal 0.195843 -0.978202 -0.0690334 + outer loop + vertex 458.268 65.6728 308.817 + vertex 451.529 64.0681 312.436 + vertex 454.489 64.9817 307.889 + endloop + endfacet + facet normal 0.197034 -0.97802 -0.0682214 + outer loop + vertex 451.529 64.0681 312.436 + vertex 446.296 63.1948 309.843 + vertex 454.489 64.9817 307.889 + endloop + endfacet + facet normal 0.190185 -0.97704 -0.0960384 + outer loop + vertex 452.049 64.6917 306.008 + vertex 454.489 64.9817 307.889 + vertex 446.296 63.1948 309.843 + endloop + endfacet + facet normal 0.178191 -0.977352 -0.114152 + outer loop + vertex 452.049 64.6917 306.008 + vertex 446.296 63.1948 309.843 + vertex 448.087 64.0712 305.136 + endloop + endfacet + facet normal 0.18092 -0.975115 -0.128137 + outer loop + vertex 448.087 64.0712 305.136 + vertex 452.969 65.2798 302.831 + vertex 452.049 64.6917 306.008 + endloop + endfacet + facet normal 0.182934 -0.974822 -0.1275 + outer loop + vertex 452.049 64.6917 306.008 + vertex 452.969 65.2798 302.831 + vertex 456.385 65.7567 304.085 + endloop + endfacet + facet normal 0.185825 -0.973123 -0.136017 + outer loop + vertex 452.969 65.2798 302.831 + vertex 456.186 66.1913 300.705 + vertex 456.385 65.7567 304.085 + endloop + endfacet + facet normal 0.179815 -0.97428 -0.135813 + outer loop + vertex 456.385 65.7567 304.085 + vertex 456.186 66.1913 300.705 + vertex 460.027 66.7353 301.888 + endloop + endfacet + facet normal 0.174047 -0.972676 -0.153654 + outer loop + vertex 452.969 65.2798 302.831 + vertex 452.846 65.6984 300.042 + vertex 456.186 66.1913 300.705 + endloop + endfacet + facet normal 0.17735 -0.968789 -0.173191 + outer loop + vertex 452.846 65.6984 300.042 + vertex 453.602 66.2252 297.869 + vertex 456.186 66.1913 300.705 + endloop + endfacet + facet normal 0.165984 -0.972584 -0.16288 + outer loop + vertex 456.186 66.1913 300.705 + vertex 453.602 66.2252 297.869 + vertex 458.474 66.9061 298.769 + endloop + endfacet + facet normal 0.167256 -0.970974 -0.170983 + outer loop + vertex 453.602 66.2252 297.869 + vertex 454.885 66.7528 296.129 + vertex 458.474 66.9061 298.769 + endloop + endfacet + facet normal 0.150923 -0.971427 -0.183173 + outer loop + vertex 454.885 66.7528 296.129 + vertex 453.602 66.2252 297.869 + vertex 447.211 65.7735 294.999 + endloop + endfacet + facet normal 0.14954 -0.973718 -0.171791 + outer loop + vertex 447.211 65.7735 294.999 + vertex 449.609 66.4101 293.478 + vertex 454.885 66.7528 296.129 + endloop + endfacet + facet normal 0.156949 -0.969731 -0.187054 + outer loop + vertex 454.885 66.7528 296.129 + vertex 449.609 66.4101 293.478 + vertex 458.064 67.3114 295.9 + endloop + endfacet + facet normal 0.160653 -0.975573 -0.149829 + outer loop + vertex 454.885 66.7528 296.129 + vertex 458.064 67.3114 295.9 + vertex 461.095 67.5225 297.775 + endloop + endfacet + facet normal 0.13377 -0.971493 -0.19572 + outer loop + vertex 447.211 65.7735 294.999 + vertex 441.436 65.7369 291.233 + vertex 449.609 66.4101 293.478 + endloop + endfacet + facet normal 0.130047 -0.973134 -0.189994 + outer loop + vertex 438.474 65.113 292.401 + vertex 441.436 65.7369 291.233 + vertex 447.211 65.7735 294.999 + endloop + endfacet + facet normal 0.143628 -0.960356 -0.238929 + outer loop + vertex 438.474 65.113 292.401 + vertex 447.211 65.7735 294.999 + vertex 442.084 64.8221 295.741 + endloop + endfacet + facet normal 0.143962 -0.960219 -0.239279 + outer loop + vertex 442.084 64.8221 295.741 + vertex 438.088 64.4433 294.857 + vertex 438.474 65.113 292.401 + endloop + endfacet + facet normal 0.127661 -0.961774 -0.242265 + outer loop + vertex 438.088 64.4433 294.857 + vertex 434.366 64.3325 293.335 + vertex 438.474 65.113 292.401 + endloop + endfacet + facet normal 0.121 -0.956116 -0.266836 + outer loop + vertex 430.398 64.7519 290.033 + vertex 438.474 65.113 292.401 + vertex 434.366 64.3325 293.335 + endloop + endfacet + facet normal 0.119453 -0.956803 -0.265065 + outer loop + vertex 434.366 64.3325 293.335 + vertex 430.436 64.0746 292.495 + vertex 430.398 64.7519 290.033 + endloop + endfacet + facet normal 0.100594 -0.958889 -0.265353 + outer loop + vertex 430.436 64.0746 292.495 + vertex 426.188 64.063 290.926 + vertex 430.398 64.7519 290.033 + endloop + endfacet + facet normal 0.095319 -0.953466 -0.286036 + outer loop + vertex 421.721 64.6099 287.615 + vertex 430.398 64.7519 290.033 + vertex 426.188 64.063 290.926 + endloop + endfacet + facet normal 0.0907255 -0.955645 -0.2802 + outer loop + vertex 426.188 64.063 290.926 + vertex 421.421 63.8705 290.04 + vertex 421.721 64.6099 287.615 + endloop + endfacet + facet normal 0.0709316 -0.956519 -0.282913 + outer loop + vertex 421.421 63.8705 290.04 + vertex 415.968 63.9361 288.451 + vertex 421.721 64.6099 287.615 + endloop + endfacet + facet normal 0.067915 -0.951609 -0.299713 + outer loop + vertex 413.1 64.7997 285.059 + vertex 421.721 64.6099 287.615 + vertex 415.968 63.9361 288.451 + endloop + endfacet + facet normal 0.0414115 -0.95932 -0.279269 + outer loop + vertex 415.968 63.9361 288.451 + vertex 408.166 64.124 286.648 + vertex 413.1 64.7997 285.059 + endloop + endfacet + facet normal 0.0281441 -0.948405 -0.31581 + outer loop + vertex 404.837 65.2503 282.969 + vertex 413.1 64.7997 285.059 + vertex 408.166 64.124 286.648 + endloop + endfacet + facet normal -0.00321919 -0.957002 -0.290062 + outer loop + vertex 408.166 64.124 286.648 + vertex 399.4 64.8116 284.477 + vertex 404.837 65.2503 282.969 + endloop + endfacet + facet normal -0.0189916 -0.939558 -0.341863 + outer loop + vertex 396.249 66.2204 280.78 + vertex 404.837 65.2503 282.969 + vertex 399.4 64.8116 284.477 + endloop + endfacet + facet normal -0.0433309 -0.965235 -0.257767 + outer loop + vertex 396.249 66.2204 280.78 + vertex 401.085 66.0571 280.579 + vertex 404.837 65.2503 282.969 + endloop + endfacet + facet normal -0.00470247 -0.949693 -0.313146 + outer loop + vertex 404.837 65.2503 282.969 + vertex 401.085 66.0571 280.579 + vertex 408.976 65.3948 282.469 + endloop + endfacet + facet normal 0.0122314 -0.938 -0.346419 + outer loop + vertex 402.55 63.0182 289.444 + vertex 399.4 64.8116 284.477 + vertex 408.166 64.124 286.648 + endloop + endfacet + facet normal 0.0367142 -0.952315 -0.302899 + outer loop + vertex 402.55 63.0182 289.444 + vertex 408.166 64.124 286.648 + vertex 411.31 62.6651 291.616 + endloop + endfacet + facet normal 0.0459422 -0.939983 -0.338114 + outer loop + vertex 404.575 61.0769 295.116 + vertex 402.55 63.0182 289.444 + vertex 411.31 62.6651 291.616 + endloop + endfacet + facet normal 0.0686742 -0.951578 -0.299639 + outer loop + vertex 404.575 61.0769 295.116 + vertex 411.31 62.6651 291.616 + vertex 412.694 61.0083 297.195 + endloop + endfacet + facet normal 0.0766373 -0.940729 -0.330387 + outer loop + vertex 404.982 59.0312 301.036 + vertex 404.575 61.0769 295.116 + vertex 412.694 61.0083 297.195 + endloop + endfacet + facet normal 0.096022 -0.950238 -0.296358 + outer loop + vertex 404.982 59.0312 301.036 + vertex 412.694 61.0083 297.195 + vertex 411.791 58.9716 303.433 + endloop + endfacet + facet normal 0.105269 -0.940736 -0.322387 + outer loop + vertex 403.787 56.9582 306.694 + vertex 404.982 59.0312 301.036 + vertex 411.791 58.9716 303.433 + endloop + endfacet + facet normal 0.122471 -0.950339 -0.286105 + outer loop + vertex 403.787 56.9582 306.694 + vertex 411.791 58.9716 303.433 + vertex 409.569 56.9945 309.049 + endloop + endfacet + facet normal 0.130565 -0.943004 -0.306097 + outer loop + vertex 401.159 54.9651 311.714 + vertex 403.787 56.9582 306.694 + vertex 409.569 56.9945 309.049 + endloop + endfacet + facet normal 0.126216 -0.942872 -0.308322 + outer loop + vertex 396.067 55.0301 309.43 + vertex 403.787 56.9582 306.694 + vertex 401.159 54.9651 311.714 + endloop + endfacet + facet normal 0.133856 -0.936136 -0.325165 + outer loop + vertex 393.096 53.0921 313.787 + vertex 396.067 55.0301 309.43 + vertex 401.159 54.9651 311.714 + endloop + endfacet + facet normal 0.127973 -0.935635 -0.328954 + outer loop + vertex 388.498 53.2487 311.552 + vertex 396.067 55.0301 309.43 + vertex 393.096 53.0921 313.787 + endloop + endfacet + facet normal 0.135117 -0.929484 -0.343225 + outer loop + vertex 385.325 51.4488 315.178 + vertex 388.498 53.2487 311.552 + vertex 393.096 53.0921 313.787 + endloop + endfacet + facet normal 0.127026 -0.928219 -0.349678 + outer loop + vertex 381.033 51.69 312.978 + vertex 388.498 53.2487 311.552 + vertex 385.325 51.4488 315.178 + endloop + endfacet + facet normal 0.135167 -0.921222 -0.3648 + outer loop + vertex 381.033 51.69 312.978 + vertex 385.325 51.4488 315.178 + vertex 377.298 50.0413 315.758 + endloop + endfacet + facet normal 0.12687 -0.91856 -0.374368 + outer loop + vertex 377.298 50.0413 315.758 + vertex 374.525 50.4749 313.754 + vertex 381.033 51.69 312.978 + endloop + endfacet + facet normal 0.13372 -0.914071 -0.382875 + outer loop + vertex 374.525 50.4749 313.754 + vertex 377.298 50.0413 315.758 + vertex 367.085 48.7569 315.257 + endloop + endfacet + facet normal 0.109442 -0.931277 -0.347486 + outer loop + vertex 396.067 55.0301 309.43 + vertex 397.808 57.1302 304.35 + vertex 403.787 56.9582 306.694 + endloop + endfacet + facet normal 0.103492 -0.931205 -0.349495 + outer loop + vertex 390.725 55.2976 307.136 + vertex 397.808 57.1302 304.35 + vertex 396.067 55.0301 309.43 + endloop + endfacet + facet normal 0.113044 -0.92187 -0.370644 + outer loop + vertex 388.498 53.2487 311.552 + vertex 390.725 55.2976 307.136 + vertex 396.067 55.0301 309.43 + endloop + endfacet + facet normal 0.105488 -0.921327 -0.374203 + outer loop + vertex 383.48 53.5848 309.31 + vertex 390.725 55.2976 307.136 + vertex 388.498 53.2487 311.552 + endloop + endfacet + facet normal 0.11508 -0.911774 -0.39424 + outer loop + vertex 381.033 51.69 312.978 + vertex 383.48 53.5848 309.31 + vertex 388.498 53.2487 311.552 + endloop + endfacet + facet normal 0.104717 -0.910333 -0.400409 + outer loop + vertex 375.464 51.9582 310.912 + vertex 383.48 53.5848 309.31 + vertex 381.033 51.69 312.978 + endloop + endfacet + facet normal 0.11608 -0.895747 -0.429141 + outer loop + vertex 375.464 51.9582 310.912 + vertex 381.033 51.69 312.978 + vertex 374.525 50.4749 313.754 + endloop + endfacet + facet normal 0.113007 -0.895672 -0.430117 + outer loop + vertex 374.525 50.4749 313.754 + vertex 369.657 50.2976 312.845 + vertex 375.464 51.9582 310.912 + endloop + endfacet + facet normal 0.115392 -0.88842 -0.444292 + outer loop + vertex 369.657 50.2976 312.845 + vertex 374.525 50.4749 313.754 + vertex 367.085 48.7569 315.257 + endloop + endfacet + facet normal 0.0836444 -0.916801 -0.390487 + outer loop + vertex 390.725 55.2976 307.136 + vertex 391.617 57.5562 302.024 + vertex 397.808 57.1302 304.35 + endloop + endfacet + facet normal 0.0716619 -0.929816 -0.360981 + outer loop + vertex 391.617 57.5562 302.024 + vertex 398.016 59.3296 298.727 + vertex 397.808 57.1302 304.35 + endloop + endfacet + facet normal 0.0796944 -0.929348 -0.3605 + outer loop + vertex 397.808 57.1302 304.35 + vertex 398.016 59.3296 298.727 + vertex 404.982 59.0312 301.036 + endloop + endfacet + facet normal 0.0448394 -0.913535 -0.404281 + outer loop + vertex 391.617 57.5562 302.024 + vertex 390.854 59.9645 296.497 + vertex 398.016 59.3296 298.727 + endloop + endfacet + facet normal 0.0320686 -0.929368 -0.36776 + outer loop + vertex 390.854 59.9645 296.497 + vertex 396.606 61.579 292.919 + vertex 398.016 59.3296 298.727 + endloop + endfacet + facet normal 0.0435579 -0.928001 -0.370022 + outer loop + vertex 398.016 59.3296 298.727 + vertex 396.606 61.579 292.919 + vertex 404.575 61.0769 295.116 + endloop + endfacet + facet normal -0.000130198 -0.911445 -0.411423 + outer loop + vertex 390.854 59.9645 296.497 + vertex 388.372 62.5106 290.858 + vertex 396.606 61.579 292.919 + endloop + endfacet + facet normal -0.0122077 -0.928583 -0.370924 + outer loop + vertex 388.372 62.5106 290.858 + vertex 393.649 63.8789 287.259 + vertex 396.606 61.579 292.919 + endloop + endfacet + facet normal 0.00326372 -0.925844 -0.377892 + outer loop + vertex 396.606 61.579 292.919 + vertex 393.649 63.8789 287.259 + vertex 402.55 63.0182 289.444 + endloop + endfacet + facet normal -0.0123856 -0.913386 -0.406906 + outer loop + vertex 383.259 60.9958 294.414 + vertex 388.372 62.5106 290.858 + vertex 390.854 59.9645 296.497 + endloop + endfacet + facet normal 0.00213742 -0.893119 -0.449815 + outer loop + vertex 385.061 58.3023 299.77 + vertex 383.259 60.9958 294.414 + vertex 390.854 59.9645 296.497 + endloop + endfacet + facet normal -0.00925221 -0.894618 -0.446736 + outer loop + vertex 377.932 59.4501 297.619 + vertex 383.259 60.9958 294.414 + vertex 385.061 58.3023 299.77 + endloop + endfacet + facet normal 0.0345589 -0.914435 -0.403254 + outer loop + vertex 385.061 58.3023 299.77 + vertex 390.854 59.9645 296.497 + vertex 391.617 57.5562 302.024 + endloop + endfacet + facet normal 0.0493001 -0.896541 -0.440209 + outer loop + vertex 385.067 55.8245 304.817 + vertex 385.061 58.3023 299.77 + vertex 391.617 57.5562 302.024 + endloop + endfacet + facet normal 0.038363 -0.896976 -0.440411 + outer loop + vertex 378.986 56.6844 302.536 + vertex 385.061 58.3023 299.77 + vertex 385.067 55.8245 304.817 + endloop + endfacet + facet normal 0.0544425 -0.877744 -0.476026 + outer loop + vertex 378.224 54.2321 306.971 + vertex 378.986 56.6844 302.536 + vertex 385.067 55.8245 304.817 + endloop + endfacet + facet normal 0.0399558 -0.877303 -0.478271 + outer loop + vertex 372.738 55.2474 304.65 + vertex 378.986 56.6844 302.536 + vertex 378.224 54.2321 306.971 + endloop + endfacet + facet normal 0.0584588 -0.856456 -0.512899 + outer loop + vertex 371.323 53.0182 308.211 + vertex 372.738 55.2474 304.65 + vertex 378.224 54.2321 306.971 + endloop + endfacet + facet normal 0.0386946 -0.853832 -0.519109 + outer loop + vertex 366.596 54.1102 306.063 + vertex 372.738 55.2474 304.65 + vertex 371.323 53.0182 308.211 + endloop + endfacet + facet normal 0.0601503 -0.830156 -0.554278 + outer loop + vertex 366.596 54.1102 306.063 + vertex 371.323 53.0182 308.211 + vertex 365.174 52.3067 308.61 + endloop + endfacet + facet normal 0.0657578 -0.855682 -0.513308 + outer loop + vertex 367.35 51.1962 310.74 + vertex 365.174 52.3067 308.61 + vertex 371.323 53.0182 308.211 + endloop + endfacet + facet normal 0.0768393 -0.849758 -0.521542 + outer loop + vertex 365.174 52.3067 308.61 + vertex 367.35 51.1962 310.74 + vertex 357.858 50.8127 309.966 + endloop + endfacet + facet normal 0.0519227 -0.798618 -0.599594 + outer loop + vertex 360.135 53.1643 307.031 + vertex 365.174 52.3067 308.61 + vertex 357.858 50.8127 309.966 + endloop + endfacet + facet normal 0.0362685 -0.825003 -0.563963 + outer loop + vertex 365.174 52.3067 308.61 + vertex 360.135 53.1643 307.031 + vertex 366.596 54.1102 306.063 + endloop + endfacet + facet normal 0.0231392 -0.787922 -0.61534 + outer loop + vertex 360.994 55.5106 304.059 + vertex 366.596 54.1102 306.063 + vertex 360.135 53.1643 307.031 + endloop + endfacet + facet normal 0.00365198 -0.7854 -0.618978 + outer loop + vertex 360.135 53.1643 307.031 + vertex 355.03 54.7669 304.967 + vertex 360.994 55.5106 304.059 + endloop + endfacet + facet normal -0.00858292 -0.745402 -0.666561 + outer loop + vertex 355.169 57.251 302.188 + vertex 360.994 55.5106 304.059 + vertex 355.03 54.7669 304.967 + endloop + endfacet + facet normal -0.0227347 -0.744884 -0.666806 + outer loop + vertex 355.03 54.7669 304.967 + vertex 351.483 56.3364 303.335 + vertex 355.169 57.251 302.188 + endloop + endfacet + facet normal 0.075241 -0.916887 -0.391992 + outer loop + vertex 385.067 55.8245 304.817 + vertex 391.617 57.5562 302.024 + vertex 390.725 55.2976 307.136 + endloop + endfacet + facet normal 0.0877173 -0.90355 -0.419408 + outer loop + vertex 383.48 53.5848 309.31 + vertex 385.067 55.8245 304.817 + vertex 390.725 55.2976 307.136 + endloop + endfacet + facet normal 0.0770317 -0.902913 -0.422865 + outer loop + vertex 378.224 54.2321 306.971 + vertex 385.067 55.8245 304.817 + vertex 383.48 53.5848 309.31 + endloop + endfacet + facet normal 0.0905618 -0.888759 -0.44934 + outer loop + vertex 375.464 51.9582 310.912 + vertex 378.224 54.2321 306.971 + vertex 383.48 53.5848 309.31 + endloop + endfacet + facet normal 0.0731074 -0.885166 -0.459495 + outer loop + vertex 371.323 53.0182 308.211 + vertex 378.224 54.2321 306.971 + vertex 375.464 51.9582 310.912 + endloop + endfacet + facet normal 0.0920492 -0.870821 -0.482906 + outer loop + vertex 371.323 53.0182 308.211 + vertex 375.464 51.9582 310.912 + vertex 367.35 51.1962 310.74 + endloop + endfacet + facet normal 0.092292 -0.875242 -0.474798 + outer loop + vertex 369.657 50.2976 312.845 + vertex 367.35 51.1962 310.74 + vertex 375.464 51.9582 310.912 + endloop + endfacet + facet normal 0.126944 -0.950289 -0.284318 + outer loop + vertex 409.569 56.9945 309.049 + vertex 411.791 58.9716 303.433 + vertex 418.269 59.1069 305.873 + endloop + endfacet + facet normal 0.145467 -0.959832 -0.239922 + outer loop + vertex 409.569 56.9945 309.049 + vertex 418.269 59.1069 305.873 + vertex 415.058 57.2361 311.41 + endloop + endfacet + facet normal 0.151908 -0.954825 -0.255406 + outer loop + vertex 405.985 55.0999 314 + vertex 409.569 56.9945 309.049 + vertex 415.058 57.2361 311.41 + endloop + endfacet + facet normal 0.148741 -0.954719 -0.257657 + outer loop + vertex 401.159 54.9651 311.714 + vertex 409.569 56.9945 309.049 + vertex 405.985 55.0999 314 + endloop + endfacet + facet normal 0.1546 -0.950287 -0.270283 + outer loop + vertex 397.351 53.1242 316.008 + vertex 401.159 54.9651 311.714 + vertex 405.985 55.0999 314 + endloop + endfacet + facet normal 0.150207 -0.949921 -0.274021 + outer loop + vertex 393.096 53.0921 313.787 + vertex 401.159 54.9651 311.714 + vertex 397.351 53.1242 316.008 + endloop + endfacet + facet normal 0.155756 -0.945876 -0.284709 + outer loop + vertex 389.412 51.4104 317.358 + vertex 393.096 53.0921 313.787 + vertex 397.351 53.1242 316.008 + endloop + endfacet + facet normal 0.147364 -0.94474 -0.292832 + outer loop + vertex 385.325 51.4488 315.178 + vertex 393.096 53.0921 313.787 + vertex 389.412 51.4104 317.358 + endloop + endfacet + facet normal 0.150785 -0.942201 -0.2992 + outer loop + vertex 385.325 51.4488 315.178 + vertex 389.412 51.4104 317.358 + vertex 381.569 49.9086 318.135 + endloop + endfacet + facet normal 0.142588 -0.940417 -0.308683 + outer loop + vertex 381.569 49.9086 318.135 + vertex 377.298 50.0413 315.758 + vertex 385.325 51.4488 315.178 + endloop + endfacet + facet normal 0.149083 -0.959801 -0.237815 + outer loop + vertex 415.058 57.2361 311.41 + vertex 418.269 59.1069 305.873 + vertex 424.357 59.4547 308.286 + endloop + endfacet + facet normal 0.142355 -0.965038 -0.220083 + outer loop + vertex 418.269 59.1069 305.873 + vertex 427.287 61.2707 302.218 + vertex 424.357 59.4547 308.286 + endloop + endfacet + facet normal 0.147362 -0.964848 -0.217608 + outer loop + vertex 424.357 59.4547 308.286 + vertex 427.287 61.2707 302.218 + vertex 433.876 61.7351 304.621 + endloop + endfacet + facet normal 0.166283 -0.970919 -0.172242 + outer loop + vertex 424.357 59.4547 308.286 + vertex 433.876 61.7351 304.621 + vertex 430.075 59.9952 310.759 + endloop + endfacet + facet normal 0.170744 -0.968141 -0.183165 + outer loop + vertex 420.192 57.673 313.82 + vertex 424.357 59.4547 308.286 + vertex 430.075 59.9952 310.759 + endloop + endfacet + facet normal 0.168999 -0.968195 -0.184495 + outer loop + vertex 415.058 57.2361 311.41 + vertex 424.357 59.4547 308.286 + vertex 420.192 57.673 313.82 + endloop + endfacet + facet normal 0.17311 -0.965665 -0.19371 + outer loop + vertex 410.531 55.4379 316.329 + vertex 415.058 57.2361 311.41 + vertex 420.192 57.673 313.82 + endloop + endfacet + facet normal 0.171706 -0.965657 -0.194998 + outer loop + vertex 405.985 55.0999 314 + vertex 415.058 57.2361 311.41 + vertex 410.531 55.4379 316.329 + endloop + endfacet + facet normal 0.175433 -0.963419 -0.202599 + outer loop + vertex 401.318 53.3525 318.268 + vertex 405.985 55.0999 314 + vertex 410.531 55.4379 316.329 + endloop + endfacet + facet normal 0.172608 -0.963287 -0.205635 + outer loop + vertex 397.351 53.1242 316.008 + vertex 405.985 55.0999 314 + vertex 401.318 53.3525 318.268 + endloop + endfacet + facet normal 0.176338 -0.961141 -0.2124 + outer loop + vertex 392.971 51.5359 319.559 + vertex 397.351 53.1242 316.008 + vertex 401.318 53.3525 318.268 + endloop + endfacet + facet normal 0.169917 -0.960572 -0.220068 + outer loop + vertex 389.412 51.4104 317.358 + vertex 397.351 53.1242 316.008 + vertex 392.971 51.5359 319.559 + endloop + endfacet + facet normal 0.173172 -0.958743 -0.225439 + outer loop + vertex 389.412 51.4104 317.358 + vertex 392.971 51.5359 319.559 + vertex 386.026 50.1817 319.983 + endloop + endfacet + facet normal 0.159219 -0.956971 -0.242601 + outer loop + vertex 386.026 50.1817 319.983 + vertex 381.569 49.9086 318.135 + vertex 389.412 51.4104 317.358 + endloop + endfacet + facet normal 0.15853 -0.957526 -0.240857 + outer loop + vertex 381.569 49.9086 318.135 + vertex 386.026 50.1817 319.983 + vertex 377.951 48.5076 321.324 + endloop + endfacet + facet normal 0.167665 -0.970836 -0.171363 + outer loop + vertex 430.075 59.9952 310.759 + vertex 433.876 61.7351 304.621 + vertex 440.284 62.3921 307.168 + endloop + endfacet + facet normal 0.162766 -0.973891 -0.158252 + outer loop + vertex 440.284 62.3921 307.168 + vertex 433.876 61.7351 304.621 + vertex 441.229 63.3153 302.459 + endloop + endfacet + facet normal 0.160325 -0.974206 -0.158803 + outer loop + vertex 445.299 63.8526 303.271 + vertex 440.284 62.3921 307.168 + vertex 441.229 63.3153 302.459 + endloop + endfacet + facet normal 0.162388 -0.97185 -0.170696 + outer loop + vertex 441.229 63.3153 302.459 + vertex 445.946 64.5058 300.168 + vertex 445.299 63.8526 303.271 + endloop + endfacet + facet normal 0.163835 -0.971667 -0.170355 + outer loop + vertex 445.299 63.8526 303.271 + vertex 445.946 64.5058 300.168 + vertex 449.525 64.8729 301.517 + endloop + endfacet + facet normal 0.174252 -0.973747 -0.146471 + outer loop + vertex 445.299 63.8526 303.271 + vertex 449.525 64.8729 301.517 + vertex 448.087 64.0712 305.136 + endloop + endfacet + facet normal 0.165728 -0.970389 -0.175728 + outer loop + vertex 445.946 64.5058 300.168 + vertex 449.567 65.4449 298.397 + vertex 449.525 64.8729 301.517 + endloop + endfacet + facet normal 0.163231 -0.970792 -0.175835 + outer loop + vertex 449.525 64.8729 301.517 + vertex 449.567 65.4449 298.397 + vertex 452.846 65.6984 300.042 + endloop + endfacet + facet normal 0.158002 -0.968848 -0.190709 + outer loop + vertex 445.946 64.5058 300.168 + vertex 445.796 65.034 297.36 + vertex 449.567 65.4449 298.397 + endloop + endfacet + facet normal 0.161642 -0.965243 -0.205375 + outer loop + vertex 449.567 65.4449 298.397 + vertex 445.796 65.034 297.36 + vertex 447.211 65.7735 294.999 + endloop + endfacet + facet normal 0.155255 -0.969304 -0.190647 + outer loop + vertex 442.275 64.1737 298.867 + vertex 445.796 65.034 297.36 + vertex 445.946 64.5058 300.168 + endloop + endfacet + facet normal 0.146587 -0.966769 -0.20945 + outer loop + vertex 442.275 64.1737 298.867 + vertex 442.084 64.8221 295.741 + vertex 445.796 65.034 297.36 + endloop + endfacet + facet normal 0.147624 -0.966605 -0.209479 + outer loop + vertex 438.621 63.8804 297.646 + vertex 442.084 64.8221 295.741 + vertex 442.275 64.1737 298.867 + endloop + endfacet + facet normal 0.146352 -0.96767 -0.205419 + outer loop + vertex 438.269 63.1777 300.705 + vertex 438.621 63.8804 297.646 + vertex 442.275 64.1737 298.867 + endloop + endfacet + facet normal 0.155613 -0.970048 -0.186523 + outer loop + vertex 438.269 63.1777 300.705 + vertex 442.275 64.1737 298.867 + vertex 441.229 63.3153 302.459 + endloop + endfacet + facet normal 0.142518 -0.968126 -0.205964 + outer loop + vertex 434.281 62.7346 300.029 + vertex 438.621 63.8804 297.646 + vertex 438.269 63.1777 300.705 + endloop + endfacet + facet normal 0.141455 -0.96982 -0.198592 + outer loop + vertex 438.269 63.1777 300.705 + vertex 433.876 61.7351 304.621 + vertex 434.281 62.7346 300.029 + endloop + endfacet + facet normal 0.135109 -0.966409 -0.21863 + outer loop + vertex 434.281 62.7346 300.029 + vertex 435.008 63.6392 296.479 + vertex 438.621 63.8804 297.646 + endloop + endfacet + facet normal 0.135795 -0.9658 -0.220882 + outer loop + vertex 435.008 63.6392 296.479 + vertex 438.088 64.4433 294.857 + vertex 438.621 63.8804 297.646 + endloop + endfacet + facet normal 0.133053 -0.966589 -0.219096 + outer loop + vertex 431.295 62.6991 298.371 + vertex 435.008 63.6392 296.479 + vertex 434.281 62.7346 300.029 + endloop + endfacet + facet normal 0.133451 -0.96637 -0.219819 + outer loop + vertex 431.295 62.6991 298.371 + vertex 434.281 62.7346 300.029 + vertex 427.287 61.2707 302.218 + endloop + endfacet + facet normal 0.118022 -0.964734 -0.235286 + outer loop + vertex 431.295 62.6991 298.371 + vertex 427.287 61.2707 302.218 + vertex 427.204 62.3695 297.671 + endloop + endfacet + facet normal 0.118129 -0.964547 -0.235997 + outer loop + vertex 427.204 62.3695 297.671 + vertex 431.356 63.455 295.313 + vertex 431.295 62.6991 298.371 + endloop + endfacet + facet normal 0.109804 -0.96212 -0.249536 + outer loop + vertex 427.204 62.3695 297.671 + vertex 427.428 63.3202 294.104 + vertex 431.356 63.455 295.313 + endloop + endfacet + facet normal 0.109156 -0.962755 -0.24736 + outer loop + vertex 427.428 63.3202 294.104 + vertex 430.436 64.0746 292.495 + vertex 431.356 63.455 295.313 + endloop + endfacet + facet normal 0.106771 -0.962393 -0.249799 + outer loop + vertex 423.759 62.433 295.954 + vertex 427.428 63.3202 294.104 + vertex 427.204 62.3695 297.671 + endloop + endfacet + facet normal 0.109212 -0.96085 -0.254639 + outer loop + vertex 423.759 62.433 295.954 + vertex 427.204 62.3695 297.671 + vertex 420.238 61.0208 299.773 + endloop + endfacet + facet normal 0.0944506 -0.958909 -0.26753 + outer loop + vertex 423.759 62.433 295.954 + vertex 420.238 61.0208 299.773 + vertex 419.146 62.1755 295.248 + endloop + endfacet + facet normal 0.0940464 -0.959768 -0.264575 + outer loop + vertex 419.146 62.1755 295.248 + vertex 423.066 63.2119 292.882 + vertex 423.759 62.433 295.954 + endloop + endfacet + facet normal 0.0850124 -0.956748 -0.278219 + outer loop + vertex 419.146 62.1755 295.248 + vertex 418.063 63.0713 291.837 + vertex 423.066 63.2119 292.882 + endloop + endfacet + facet normal 0.0834748 -0.959082 -0.270545 + outer loop + vertex 418.063 63.0713 291.837 + vertex 421.421 63.8705 290.04 + vertex 423.066 63.2119 292.882 + endloop + endfacet + facet normal 0.0849129 -0.956765 -0.278191 + outer loop + vertex 415.527 62.2464 293.9 + vertex 418.063 63.0713 291.837 + vertex 419.146 62.1755 295.248 + endloop + endfacet + facet normal 0.0870797 -0.954889 -0.283908 + outer loop + vertex 415.527 62.2464 293.9 + vertex 419.146 62.1755 295.248 + vertex 412.694 61.0083 297.195 + endloop + endfacet + facet normal 0.0670136 -0.952106 -0.298336 + outer loop + vertex 415.527 62.2464 293.9 + vertex 411.31 62.6651 291.616 + vertex 418.063 63.0713 291.837 + endloop + endfacet + facet normal 0.0668313 -0.956039 -0.285523 + outer loop + vertex 411.31 62.6651 291.616 + vertex 415.968 63.9361 288.451 + vertex 418.063 63.0713 291.837 + endloop + endfacet + facet normal 0.0928886 -0.95915 -0.267214 + outer loop + vertex 420.238 61.0208 299.773 + vertex 412.694 61.0083 297.195 + vertex 419.146 62.1755 295.248 + endloop + endfacet + facet normal 0.0981491 -0.959145 -0.265343 + outer loop + vertex 423.759 62.433 295.954 + vertex 423.066 63.2119 292.882 + vertex 427.428 63.3202 294.104 + endloop + endfacet + facet normal 0.097355 -0.960027 -0.26243 + outer loop + vertex 423.066 63.2119 292.882 + vertex 426.188 64.063 290.926 + vertex 427.428 63.3202 294.104 + endloop + endfacet + facet normal 0.115845 -0.964992 -0.235309 + outer loop + vertex 427.287 61.2707 302.218 + vertex 420.238 61.0208 299.773 + vertex 427.204 62.3695 297.671 + endloop + endfacet + facet normal 0.123898 -0.963891 -0.235718 + outer loop + vertex 431.295 62.6991 298.371 + vertex 431.356 63.455 295.313 + vertex 435.008 63.6392 296.479 + endloop + endfacet + facet normal 0.124555 -0.963277 -0.237872 + outer loop + vertex 431.356 63.455 295.313 + vertex 434.366 64.3325 293.335 + vertex 435.008 63.6392 296.479 + endloop + endfacet + facet normal 0.15405 -0.970203 -0.187016 + outer loop + vertex 441.229 63.3153 302.459 + vertex 442.275 64.1737 298.867 + vertex 445.946 64.5058 300.168 + endloop + endfacet + facet normal 0.172321 -0.974533 -0.143492 + outer loop + vertex 445.299 63.8526 303.271 + vertex 448.087 64.0712 305.136 + vertex 440.284 62.3921 307.168 + endloop + endfacet + facet normal 0.154381 -0.970652 -0.184396 + outer loop + vertex 438.269 63.1777 300.705 + vertex 441.229 63.3153 302.459 + vertex 433.876 61.7351 304.621 + endloop + endfacet + facet normal 0.14081 -0.969899 -0.198667 + outer loop + vertex 433.876 61.7351 304.621 + vertex 427.287 61.2707 302.218 + vertex 434.281 62.7346 300.029 + endloop + endfacet + facet normal 0.124248 -0.957502 -0.260294 + outer loop + vertex 418.269 59.1069 305.873 + vertex 420.238 61.0208 299.773 + vertex 427.287 61.2707 302.218 + endloop + endfacet + facet normal 0.118742 -0.957698 -0.262134 + outer loop + vertex 411.791 58.9716 303.433 + vertex 420.238 61.0208 299.773 + vertex 418.269 59.1069 305.873 + endloop + endfacet + facet normal 0.0998025 -0.940913 -0.323607 + outer loop + vertex 397.808 57.1302 304.35 + vertex 404.982 59.0312 301.036 + vertex 403.787 56.9582 306.694 + endloop + endfacet + facet normal 0.102473 -0.94989 -0.29531 + outer loop + vertex 411.791 58.9716 303.433 + vertex 412.694 61.0083 297.195 + vertex 420.238 61.0208 299.773 + endloop + endfacet + facet normal 0.0691023 -0.941412 -0.330105 + outer loop + vertex 398.016 59.3296 298.727 + vertex 404.575 61.0769 295.116 + vertex 404.982 59.0312 301.036 + endloop + endfacet + facet normal 0.0676417 -0.951719 -0.299425 + outer loop + vertex 412.694 61.0083 297.195 + vertex 411.31 62.6651 291.616 + vertex 415.527 62.2464 293.9 + endloop + endfacet + facet normal 0.0327703 -0.941971 -0.334092 + outer loop + vertex 396.606 61.579 292.919 + vertex 402.55 63.0182 289.444 + vertex 404.575 61.0769 295.116 + endloop + endfacet + facet normal -0.00897679 -0.94234 -0.334537 + outer loop + vertex 393.649 63.8789 287.259 + vertex 399.4 64.8116 284.477 + vertex 402.55 63.0182 289.444 + endloop + endfacet + facet normal -0.0345248 -0.923862 -0.381166 + outer loop + vertex 393.649 63.8789 287.259 + vertex 389.114 66.3852 281.595 + vertex 399.4 64.8116 284.477 + endloop + endfacet + facet normal -0.0575482 -0.948237 -0.312307 + outer loop + vertex 399.4 64.8116 284.477 + vertex 389.114 66.3852 281.595 + vertex 396.249 66.2204 280.78 + endloop + endfacet + facet normal -0.0622107 -0.932271 -0.35637 + outer loop + vertex 388.809 67.6083 278.448 + vertex 396.249 66.2204 280.78 + vertex 389.114 66.3852 281.595 + endloop + endfacet + facet normal -0.0777679 -0.945944 -0.314869 + outer loop + vertex 388.809 67.6083 278.448 + vertex 392.199 67.3937 278.256 + vertex 396.249 66.2204 280.78 + endloop + endfacet + facet normal -0.0464248 -0.93226 -0.358799 + outer loop + vertex 396.249 66.2204 280.78 + vertex 392.199 67.3937 278.256 + vertex 401.085 66.0571 280.579 + endloop + endfacet + facet normal -0.0562166 -0.928904 -0.366029 + outer loop + vertex 384.324 65.219 285.29 + vertex 389.114 66.3852 281.595 + vertex 393.649 63.8789 287.259 + endloop + endfacet + facet normal -0.04412 -0.910622 -0.410879 + outer loop + vertex 388.372 62.5106 290.858 + vertex 384.324 65.219 285.29 + vertex 393.649 63.8789 287.259 + endloop + endfacet + facet normal -0.0591946 -0.913931 -0.401529 + outer loop + vertex 379.825 63.8794 289.002 + vertex 384.324 65.219 285.29 + vertex 388.372 62.5106 290.858 + endloop + endfacet + facet normal -0.0460716 -0.893422 -0.446849 + outer loop + vertex 383.259 60.9958 294.414 + vertex 379.825 63.8794 289.002 + vertex 388.372 62.5106 290.858 + endloop + endfacet + facet normal -0.0579698 -0.895837 -0.440586 + outer loop + vertex 375.237 62.4749 292.462 + vertex 379.825 63.8794 289.002 + vertex 383.259 60.9958 294.414 + endloop + endfacet + facet normal 0.00582073 -0.972524 -0.232731 + outer loop + vertex 404.837 65.2503 282.969 + vertex 408.976 65.3948 282.469 + vertex 413.1 64.7997 285.059 + endloop + endfacet + facet normal 0.0386282 -0.958695 -0.2818 + outer loop + vertex 413.1 64.7997 285.059 + vertex 408.976 65.3948 282.469 + vertex 417.277 65.1147 284.56 + endloop + endfacet + facet normal 0.0486684 -0.949599 -0.309667 + outer loop + vertex 411.31 62.6651 291.616 + vertex 408.166 64.124 286.648 + vertex 415.968 63.9361 288.451 + endloop + endfacet + facet normal 0.0461301 -0.972615 -0.227799 + outer loop + vertex 413.1 64.7997 285.059 + vertex 417.277 65.1147 284.56 + vertex 421.721 64.6099 287.615 + endloop + endfacet + facet normal 0.0710232 -0.962365 -0.262317 + outer loop + vertex 421.721 64.6099 287.615 + vertex 417.277 65.1147 284.56 + vertex 425.583 65.111 286.822 + endloop + endfacet + facet normal 0.072662 -0.954636 -0.288773 + outer loop + vertex 421.421 63.8705 290.04 + vertex 418.063 63.0713 291.837 + vertex 415.968 63.9361 288.451 + endloop + endfacet + facet normal 0.0896061 -0.957617 -0.273754 + outer loop + vertex 423.066 63.2119 292.882 + vertex 421.421 63.8705 290.04 + vertex 426.188 64.063 290.926 + endloop + endfacet + facet normal 0.0792559 -0.970572 -0.227397 + outer loop + vertex 421.721 64.6099 287.615 + vertex 425.583 65.111 286.822 + vertex 430.398 64.7519 290.033 + endloop + endfacet + facet normal 0.0931884 -0.964371 -0.247597 + outer loop + vertex 430.398 64.7519 290.033 + vertex 425.583 65.111 286.822 + vertex 433.739 65.33 289.039 + endloop + endfacet + facet normal 0.0998313 -0.959539 -0.263283 + outer loop + vertex 427.428 63.3202 294.104 + vertex 426.188 64.063 290.926 + vertex 430.436 64.0746 292.495 + endloop + endfacet + facet normal 0.116408 -0.961372 -0.249425 + outer loop + vertex 431.356 63.455 295.313 + vertex 430.436 64.0746 292.495 + vertex 434.366 64.3325 293.335 + endloop + endfacet + facet normal 0.105344 -0.971781 -0.211057 + outer loop + vertex 430.398 64.7519 290.033 + vertex 433.739 65.33 289.039 + vertex 438.474 65.113 292.401 + endloop + endfacet + facet normal 0.126001 -0.96303 -0.238112 + outer loop + vertex 435.008 63.6392 296.479 + vertex 434.366 64.3325 293.335 + vertex 438.088 64.4433 294.857 + endloop + endfacet + facet normal 0.140504 -0.96496 -0.221612 + outer loop + vertex 438.621 63.8804 297.646 + vertex 438.088 64.4433 294.857 + vertex 442.084 64.8221 295.741 + endloop + endfacet + facet normal 0.148287 -0.965624 -0.213496 + outer loop + vertex 445.796 65.034 297.36 + vertex 442.084 64.8221 295.741 + vertex 447.211 65.7735 294.999 + endloop + endfacet + facet normal 0.115204 -0.9676 -0.224674 + outer loop + vertex 438.474 65.113 292.401 + vertex 433.739 65.33 289.039 + vertex 441.436 65.7369 291.233 + endloop + endfacet + facet normal 0.160005 -0.965746 -0.204289 + outer loop + vertex 449.567 65.4449 298.397 + vertex 447.211 65.7735 294.999 + vertex 453.602 66.2252 297.869 + endloop + endfacet + facet normal 0.164305 -0.970204 -0.178067 + outer loop + vertex 452.846 65.6984 300.042 + vertex 449.567 65.4449 298.397 + vertex 453.602 66.2252 297.869 + endloop + endfacet + facet normal 0.173573 -0.972762 -0.153646 + outer loop + vertex 449.525 64.8729 301.517 + vertex 452.846 65.6984 300.042 + vertex 452.969 65.2798 302.831 + endloop + endfacet + facet normal 0.171442 -0.974066 -0.147659 + outer loop + vertex 448.087 64.0712 305.136 + vertex 449.525 64.8729 301.517 + vertex 452.969 65.2798 302.831 + endloop + endfacet + facet normal 0.180769 -0.977 -0.113106 + outer loop + vertex 446.296 63.1948 309.843 + vertex 440.284 62.3921 307.168 + vertex 448.087 64.0712 305.136 + endloop + endfacet + facet normal 0.184861 -0.975051 -0.122888 + outer loop + vertex 435.341 60.6833 313.29 + vertex 440.284 62.3921 307.168 + vertex 446.296 63.1948 309.843 + endloop + endfacet + facet normal 0.186014 -0.974952 -0.121929 + outer loop + vertex 430.075 59.9952 310.759 + vertex 440.284 62.3921 307.168 + vertex 435.341 60.6833 313.29 + endloop + endfacet + facet normal 0.188573 -0.973737 -0.127582 + outer loop + vertex 424.863 58.265 316.26 + vertex 430.075 59.9952 310.759 + vertex 435.341 60.6833 313.29 + endloop + endfacet + facet normal 0.189559 -0.97367 -0.126628 + outer loop + vertex 420.192 57.673 313.82 + vertex 430.075 59.9952 310.759 + vertex 424.863 58.265 316.26 + endloop + endfacet + facet normal 0.191159 -0.972929 -0.129872 + outer loop + vertex 414.738 55.9538 318.671 + vertex 420.192 57.673 313.82 + vertex 424.863 58.265 316.26 + endloop + endfacet + facet normal 0.191454 -0.972916 -0.129535 + outer loop + vertex 410.531 55.4379 316.329 + vertex 420.192 57.673 313.82 + vertex 414.738 55.9538 318.671 + endloop + endfacet + facet normal 0.192795 -0.972309 -0.132078 + outer loop + vertex 405.115 53.7922 320.538 + vertex 410.531 55.4379 316.329 + vertex 414.738 55.9538 318.671 + endloop + endfacet + facet normal 0.192099 -0.972324 -0.13298 + outer loop + vertex 401.318 53.3525 318.268 + vertex 410.531 55.4379 316.329 + vertex 405.115 53.7922 320.538 + endloop + endfacet + facet normal 0.193712 -0.971612 -0.135814 + outer loop + vertex 396.394 51.8763 321.806 + vertex 401.318 53.3525 318.268 + vertex 405.115 53.7922 320.538 + endloop + endfacet + facet normal 0.189566 -0.971607 -0.141583 + outer loop + vertex 392.971 51.5359 319.559 + vertex 401.318 53.3525 318.268 + vertex 396.394 51.8763 321.806 + endloop + endfacet + facet normal 0.190434 -0.971235 -0.142961 + outer loop + vertex 392.971 51.5359 319.559 + vertex 396.394 51.8763 321.806 + vertex 388.263 50.1793 322.503 + endloop + endfacet + facet normal 0.179479 -0.970631 -0.160197 + outer loop + vertex 388.263 50.1793 322.503 + vertex 386.026 50.1817 319.983 + vertex 392.971 51.5359 319.559 + endloop + endfacet + facet normal 0.175494 -0.971935 -0.156663 + outer loop + vertex 386.026 50.1817 319.983 + vertex 388.263 50.1793 322.503 + vertex 377.951 48.5076 321.324 + endloop + endfacet + facet normal 0.194499 -0.9756 -0.101855 + outer loop + vertex 452.049 64.6917 306.008 + vertex 456.385 65.7567 304.085 + vertex 454.489 64.9817 307.889 + endloop + endfacet + facet normal 0.200062 -0.976932 -0.0746997 + outer loop + vertex 439.981 61.4539 315.698 + vertex 446.296 63.1948 309.843 + vertex 451.529 64.0681 312.436 + endloop + endfacet + facet normal 0.200641 -0.976862 -0.0740544 + outer loop + vertex 435.341 60.6833 313.29 + vertex 446.296 63.1948 309.843 + vertex 439.981 61.4539 315.698 + endloop + endfacet + facet normal 0.202003 -0.976366 -0.0768392 + outer loop + vertex 428.974 58.9512 318.562 + vertex 435.341 60.6833 313.29 + vertex 439.981 61.4539 315.698 + endloop + endfacet + facet normal 0.204317 -0.976107 -0.0739597 + outer loop + vertex 424.863 58.265 316.26 + vertex 435.341 60.6833 313.29 + vertex 428.974 58.9512 318.562 + endloop + endfacet + facet normal 0.204205 -0.976146 -0.0737483 + outer loop + vertex 418.442 56.5716 320.896 + vertex 424.863 58.265 316.26 + vertex 428.974 58.9512 318.562 + endloop + endfacet + facet normal 0.205747 -0.975986 -0.0715549 + outer loop + vertex 414.738 55.9538 318.671 + vertex 424.863 58.265 316.26 + vertex 418.442 56.5716 320.896 + endloop + endfacet + facet normal 0.205144 -0.97619 -0.0704957 + outer loop + vertex 408.707 54.4025 322.604 + vertex 414.738 55.9538 318.671 + vertex 418.442 56.5716 320.896 + endloop + endfacet + facet normal 0.2058 -0.976125 -0.0694646 + outer loop + vertex 405.115 53.7922 320.538 + vertex 414.738 55.9538 318.671 + vertex 408.707 54.4025 322.604 + endloop + endfacet + facet normal 0.204416 -0.976594 -0.0669195 + outer loop + vertex 400.058 52.5051 323.873 + vertex 405.115 53.7922 320.538 + vertex 408.707 54.4025 322.604 + endloop + endfacet + facet normal 0.204921 -0.976542 -0.0661342 + outer loop + vertex 396.394 51.8763 321.806 + vertex 405.115 53.7922 320.538 + vertex 400.058 52.5051 323.873 + endloop + endfacet + facet normal 0.207263 -0.97574 -0.0705289 + outer loop + vertex 396.394 51.8763 321.806 + vertex 400.058 52.5051 323.873 + vertex 392.736 50.905 324.494 + endloop + endfacet + facet normal 0.196517 -0.976764 -0.0855212 + outer loop + vertex 392.736 50.905 324.494 + vertex 388.263 50.1793 322.503 + vertex 396.394 51.8763 321.806 + endloop + endfacet + facet normal 0.206485 -0.977233 -0.048783 + outer loop + vertex 458.268 65.6728 308.817 + vertex 460.021 65.9517 310.651 + vertex 451.529 64.0681 312.436 + endloop + endfacet + facet normal 0.189996 -0.976237 -0.104228 + outer loop + vertex 454.489 64.9817 307.889 + vertex 456.385 65.7567 304.085 + vertex 459.804 66.2743 305.47 + endloop + endfacet + facet normal 0.193436 -0.974542 -0.113356 + outer loop + vertex 456.385 65.7567 304.085 + vertex 460.027 66.7353 301.888 + vertex 459.804 66.2743 305.47 + endloop + endfacet + facet normal 0.186477 -0.975683 -0.115186 + outer loop + vertex 463.688 67.2812 303.299 + vertex 462.886 67.502 300.131 + vertex 466.802 68.0824 301.554 + endloop + endfacet + facet normal 0.18208 -0.972697 -0.143897 + outer loop + vertex 456.186 66.1913 300.705 + vertex 458.474 66.9061 298.769 + vertex 460.027 66.7353 301.888 + endloop + endfacet + facet normal 0.164971 -0.971916 -0.167822 + outer loop + vertex 458.474 66.9061 298.769 + vertex 454.885 66.7528 296.129 + vertex 461.095 67.5225 297.775 + endloop + endfacet + facet normal 0.18609 -0.975893 -0.114035 + outer loop + vertex 462.886 67.502 300.131 + vertex 465.39 68.0724 299.336 + vertex 466.802 68.0824 301.554 + endloop + endfacet + facet normal 0.199439 -0.975582 -0.0920005 + outer loop + vertex 463.688 67.2812 303.299 + vertex 466.802 68.0824 301.554 + vertex 467.145 67.8509 304.752 + endloop + endfacet + facet normal 0.19868 -0.975917 -0.0900648 + outer loop + vertex 462.985 66.8045 306.913 + vertex 463.688 67.2812 303.299 + vertex 467.145 67.8509 304.752 + endloop + endfacet + facet normal 0.212145 -0.975722 -0.0544226 + outer loop + vertex 458.268 65.6728 308.817 + vertex 462.985 66.8045 306.913 + vertex 460.021 65.9517 310.651 + endloop + endfacet + facet normal 0.211041 -0.977105 -0.0269721 + outer loop + vertex 455.446 64.8527 314.667 + vertex 451.529 64.0681 312.436 + vertex 460.021 65.9517 310.651 + endloop + endfacet + facet normal 0.212709 -0.976653 -0.0300606 + outer loop + vertex 443.826 62.2302 317.647 + vertex 451.529 64.0681 312.436 + vertex 455.446 64.8527 314.667 + endloop + endfacet + facet normal 0.212542 -0.976681 -0.0303172 + outer loop + vertex 439.981 61.4539 315.698 + vertex 451.529 64.0681 312.436 + vertex 443.826 62.2302 317.647 + endloop + endfacet + facet normal 0.212728 -0.976629 -0.0307045 + outer loop + vertex 432.545 59.6863 320.4 + vertex 439.981 61.4539 315.698 + vertex 443.826 62.2302 317.647 + endloop + endfacet + facet normal 0.214921 -0.976255 -0.0270956 + outer loop + vertex 428.974 58.9512 318.562 + vertex 439.981 61.4539 315.698 + vertex 432.545 59.6863 320.4 + endloop + endfacet + facet normal 0.213591 -0.976619 -0.0243661 + outer loop + vertex 421.645 57.2458 322.669 + vertex 428.974 58.9512 318.562 + vertex 432.545 59.6863 320.4 + endloop + endfacet + facet normal 0.216241 -0.976146 -0.0194419 + outer loop + vertex 418.442 56.5716 320.896 + vertex 428.974 58.9512 318.562 + vertex 421.645 57.2458 322.669 + endloop + endfacet + facet normal 0.214374 -0.976622 -0.0158902 + outer loop + vertex 411.588 55.0111 324.336 + vertex 418.442 56.5716 320.896 + vertex 421.645 57.2458 322.669 + endloop + endfacet + facet normal 0.215038 -0.976498 -0.0145107 + outer loop + vertex 408.707 54.4025 322.604 + vertex 418.442 56.5716 320.896 + vertex 411.588 55.0111 324.336 + endloop + endfacet + facet normal 0.213873 -0.976782 -0.012472 + outer loop + vertex 403.775 53.2891 325.22 + vertex 408.707 54.4025 322.604 + vertex 411.588 55.0111 324.336 + endloop + endfacet + facet normal 0.211974 -0.977141 -0.0162045 + outer loop + vertex 400.058 52.5051 323.873 + vertex 408.707 54.4025 322.604 + vertex 403.775 53.2891 325.22 + endloop + endfacet + facet normal 0.20573 -0.978607 0.00188154 + outer loop + vertex 400.058 52.5051 323.873 + vertex 403.775 53.2891 325.22 + vertex 396.581 51.7796 326.692 + endloop + endfacet + facet normal 0.214562 -0.97662 0.0132873 + outer loop + vertex 396.581 51.7796 326.692 + vertex 392.736 50.905 324.494 + vertex 400.058 52.5051 323.873 + endloop + endfacet + facet normal 0.223455 -0.974659 0.010349 + outer loop + vertex 457.031 65.2328 316.258 + vertex 455.446 64.8527 314.667 + vertex 463.78 66.7458 313.011 + endloop + endfacet + facet normal 0.216038 -0.97567 -0.0373624 + outer loop + vertex 463.144 66.6105 311.498 + vertex 465.849 67.3298 308.352 + vertex 468.32 67.8259 309.684 + endloop + endfacet + facet normal 0.218707 -0.97486 -0.042614 + outer loop + vertex 465.849 67.3298 308.352 + vertex 470.308 68.4236 306.216 + vertex 468.32 67.8259 309.684 + endloop + endfacet + facet normal 0.205547 -0.97616 -0.0697211 + outer loop + vertex 470.308 68.4236 306.216 + vertex 470.494 68.6916 303.012 + vertex 473.946 69.3142 304.472 + endloop + endfacet + facet normal 0.208204 -0.975382 -0.0726684 + outer loop + vertex 473.946 69.3142 304.472 + vertex 473.176 69.3197 302.19 + vertex 476.76 69.993 303.422 + endloop + endfacet + facet normal 0.216982 -0.975447 -0.0377109 + outer loop + vertex 477.066 69.9228 305.8 + vertex 479.757 70.5556 304.912 + vertex 479.667 70.4614 306.83 + endloop + endfacet + facet normal 0.21993 -0.975414 -0.0140914 + outer loop + vertex 482.16 71.0065 308.174 + vertex 483.774 71.3919 306.685 + vertex 485.07 71.6825 306.804 + endloop + endfacet + facet normal 0.223853 -0.974575 -0.00962274 + outer loop + vertex 481.261 70.8051 307.654 + vertex 483.774 71.3919 306.685 + vertex 482.16 71.0065 308.174 + endloop + endfacet + facet normal 0.2206 -0.97516 -0.0199612 + outer loop + vertex 478.138 70.0752 308.797 + vertex 479.667 70.4614 306.83 + vertex 481.261 70.8051 307.654 + endloop + endfacet + facet normal 0.221843 -0.974898 -0.0189437 + outer loop + vertex 475.884 69.5686 308.471 + vertex 479.667 70.4614 306.83 + vertex 478.138 70.0752 308.797 + endloop + endfacet + facet normal 0.21782 -0.975631 -0.0264253 + outer loop + vertex 470.549 68.3172 310.703 + vertex 473.212 68.9975 307.541 + vertex 475.884 69.5686 308.471 + endloop + endfacet + facet normal 0.229896 -0.973145 0.0116665 + outer loop + vertex 463.78 66.7458 313.011 + vertex 470.549 68.3172 310.703 + vertex 466.048 67.2888 313.619 + endloop + endfacet + facet normal 0.227783 -0.973509 0.0198803 + outer loop + vertex 466.048 67.2888 313.619 + vertex 457.031 65.2328 316.258 + vertex 463.78 66.7458 313.011 + endloop + endfacet + facet normal 0.223194 -0.974716 0.0106227 + outer loop + vertex 446.802 62.9188 318.851 + vertex 455.446 64.8527 314.667 + vertex 457.031 65.2328 316.258 + endloop + endfacet + facet normal 0.222211 -0.974962 0.00847803 + outer loop + vertex 443.826 62.2302 317.647 + vertex 455.446 64.8527 314.667 + vertex 446.802 62.9188 318.851 + endloop + endfacet + facet normal 0.221583 -0.975089 0.0101023 + outer loop + vertex 435.795 60.4447 321.459 + vertex 443.826 62.2302 317.647 + vertex 446.802 62.9188 318.851 + endloop + endfacet + facet normal 0.223053 -0.974715 0.0133737 + outer loop + vertex 432.545 59.6863 320.4 + vertex 443.826 62.2302 317.647 + vertex 435.795 60.4447 321.459 + endloop + endfacet + facet normal 0.222225 -0.974386 0.0344799 + outer loop + vertex 411.588 55.0111 324.336 + vertex 421.645 57.2458 322.669 + vertex 414.046 55.614 325.532 + endloop + endfacet + facet normal 0.219061 -0.974841 0.041209 + outer loop + vertex 404.859 53.5943 326.587 + vertex 411.588 55.0111 324.336 + vertex 414.046 55.614 325.532 + endloop + endfacet + facet normal 0.219698 -0.974608 0.0432585 + outer loop + vertex 403.775 53.2891 325.22 + vertex 411.588 55.0111 324.336 + vertex 404.859 53.5943 326.587 + endloop + endfacet + facet normal 0.214453 -0.975572 0.0476341 + outer loop + vertex 403.775 53.2891 325.22 + vertex 404.859 53.5943 326.587 + vertex 396.581 51.7796 326.692 + endloop + endfacet + facet normal 0.21439 -0.973297 0.0820399 + outer loop + vertex 400.172 52.6921 328.132 + vertex 396.581 51.7796 326.692 + vertex 404.859 53.5943 326.587 + endloop + endfacet + facet normal 0.219143 -0.970764 0.0979424 + outer loop + vertex 404.859 53.5943 326.587 + vertex 407.225 54.1988 327.284 + vertex 400.172 52.6921 328.132 + endloop + endfacet + facet normal 0.219218 -0.970667 0.0987391 + outer loop + vertex 403.562 53.451 328.067 + vertex 400.172 52.6921 328.132 + vertex 407.225 54.1988 327.284 + endloop + endfacet + facet normal 0.227997 -0.962392 0.147714 + outer loop + vertex 408.391 54.5069 327.493 + vertex 403.562 53.451 328.067 + vertex 407.225 54.1988 327.284 + endloop + endfacet + facet normal 0.235178 -0.938932 0.251193 + outer loop + vertex 403.562 53.451 328.067 + vertex 408.391 54.5069 327.493 + vertex 402.11 53.187 328.44 + endloop + endfacet + facet normal 0.236824 -0.933292 0.269964 + outer loop + vertex 409.583 54.8162 327.516 + vertex 402.11 53.187 328.44 + vertex 408.391 54.5069 327.493 + endloop + endfacet + facet normal 0.233752 -0.946772 0.221322 + outer loop + vertex 402.11 53.187 328.44 + vertex 409.583 54.8162 327.516 + vertex 403.513 53.6097 328.766 + endloop + endfacet + facet normal 0.231122 -0.945203 0.230595 + outer loop + vertex 398.479 52.4796 329.179 + vertex 402.11 53.187 328.44 + vertex 403.513 53.6097 328.766 + endloop + endfacet + facet normal 0.231267 -0.943731 0.236403 + outer loop + vertex 398.479 52.4796 329.179 + vertex 403.513 53.6097 328.766 + vertex 398.864 52.7738 329.977 + endloop + endfacet + facet normal 0.209273 -0.945936 0.247809 + outer loop + vertex 398.479 52.4796 329.179 + vertex 398.864 52.7738 329.977 + vertex 395.63 51.8401 329.144 + endloop + endfacet + facet normal 0.209247 -0.945844 0.248184 + outer loop + vertex 397.932 52.2887 328.913 + vertex 398.479 52.4796 329.179 + vertex 395.63 51.8401 329.144 + endloop + endfacet + facet normal 0.196614 -0.978735 0.0584848 + outer loop + vertex 395.63 51.8401 329.144 + vertex 400.172 52.6921 328.132 + vertex 397.932 52.2887 328.913 + endloop + endfacet + facet normal 0.216271 -0.950003 0.225212 + outer loop + vertex 395.955 52.36 331.025 + vertex 395.63 51.8401 329.144 + vertex 398.864 52.7738 329.977 + endloop + endfacet + facet normal 0.231569 -0.943289 0.237867 + outer loop + vertex 398.864 52.7738 329.977 + vertex 403.513 53.6097 328.766 + vertex 405.186 54.2288 329.592 + endloop + endfacet + facet normal 0.234867 -0.944004 0.231719 + outer loop + vertex 403.513 53.6097 328.766 + vertex 411.994 55.4491 327.664 + vertex 405.186 54.2288 329.592 + endloop + endfacet + facet normal 0.232993 -0.946431 0.223568 + outer loop + vertex 405.186 54.2288 329.592 + vertex 411.994 55.4491 327.664 + vertex 414.029 56.1412 328.472 + endloop + endfacet + facet normal 0.237669 -0.947728 0.212897 + outer loop + vertex 411.994 55.4491 327.664 + vertex 422.256 57.6636 326.065 + vertex 414.029 56.1412 328.472 + endloop + endfacet + facet normal 0.235164 -0.950627 0.2025 + outer loop + vertex 414.029 56.1412 328.472 + vertex 422.256 57.6636 326.065 + vertex 424.288 58.3461 326.909 + endloop + endfacet + facet normal 0.241689 -0.95199 0.187889 + outer loop + vertex 422.256 57.6636 326.065 + vertex 432.89 59.9877 324.162 + vertex 424.288 58.3461 326.909 + endloop + endfacet + facet normal 0.238885 -0.954688 0.177494 + outer loop + vertex 424.288 58.3461 326.909 + vertex 432.89 59.9877 324.162 + vertex 434.854 60.6486 325.073 + endloop + endfacet + facet normal 0.246508 -0.955558 0.161685 + outer loop + vertex 432.89 59.9877 324.162 + vertex 443.423 62.334 321.97 + vertex 434.854 60.6486 325.073 + endloop + endfacet + facet normal 0.245034 -0.956721 0.156984 + outer loop + vertex 434.854 60.6486 325.073 + vertex 443.423 62.334 321.97 + vertex 445.56 63.037 322.919 + endloop + endfacet + facet normal 0.251617 -0.957269 0.142565 + outer loop + vertex 443.423 62.334 321.97 + vertex 454.406 64.8177 319.262 + vertex 445.56 63.037 322.919 + endloop + endfacet + facet normal 0.249789 -0.95848 0.137553 + outer loop + vertex 445.56 63.037 322.919 + vertex 454.406 64.8177 319.262 + vertex 457.002 65.6303 320.21 + endloop + endfacet + facet normal 0.254152 -0.958923 0.125989 + outer loop + vertex 454.406 64.8177 319.262 + vertex 466.805 67.6243 315.612 + vertex 457.002 65.6303 320.21 + endloop + endfacet + facet normal 0.247538 -0.962579 0.110303 + outer loop + vertex 457.002 65.6303 320.21 + vertex 466.805 67.6243 315.612 + vertex 469.661 68.4976 316.825 + endloop + endfacet + facet normal 0.250211 -0.962588 0.104017 + outer loop + vertex 469.661 68.4976 316.825 + vertex 466.805 67.6243 315.612 + vertex 475.978 69.7112 312.86 + endloop + endfacet + facet normal 0.240272 -0.966809 0.0868887 + outer loop + vertex 478.42 70.3527 313.244 + vertex 469.661 68.4976 316.825 + vertex 475.978 69.7112 312.86 + endloop + endfacet + facet normal 0.242674 -0.967391 0.0725559 + outer loop + vertex 475.978 69.7112 312.86 + vertex 482.537 71.2001 310.771 + vertex 478.42 70.3527 313.244 + endloop + endfacet + facet normal 0.241819 -0.967719 0.071019 + outer loop + vertex 478.42 70.3527 313.244 + vertex 482.537 71.2001 310.771 + vertex 483.711 71.5821 311.979 + endloop + endfacet + facet normal 0.246834 -0.964364 0.0952585 + outer loop + vertex 478.42 70.3527 313.244 + vertex 483.711 71.5821 311.979 + vertex 478.542 70.5553 314.978 + endloop + endfacet + facet normal 0.243094 -0.965979 0.0882603 + outer loop + vertex 478.542 70.5553 314.978 + vertex 483.711 71.5821 311.979 + vertex 484.99 72.0415 313.486 + endloop + endfacet + facet normal 0.247442 -0.962591 0.110416 + outer loop + vertex 478.542 70.5553 314.978 + vertex 484.99 72.0415 313.486 + vertex 480.863 71.281 316.105 + endloop + endfacet + facet normal 0.240962 -0.962609 0.123776 + outer loop + vertex 480.863 71.281 316.105 + vertex 471.763 69.4208 319.354 + vertex 478.542 70.5553 314.978 + endloop + endfacet + facet normal 0.251149 -0.957646 0.140847 + outer loop + vertex 471.763 69.4208 319.354 + vertex 469.661 68.4976 316.825 + vertex 478.542 70.5553 314.978 + endloop + endfacet + facet normal 0.24984 -0.957819 0.141998 + outer loop + vertex 459.169 66.5508 322.153 + vertex 469.661 68.4976 316.825 + vertex 471.763 69.4208 319.354 + endloop + endfacet + facet normal 0.259058 -0.952141 0.162224 + outer loop + vertex 457.002 65.6303 320.21 + vertex 469.661 68.4976 316.825 + vertex 459.169 66.5508 322.153 + endloop + endfacet + facet normal 0.252859 -0.952569 0.169338 + outer loop + vertex 447.509 63.9023 324.665 + vertex 457.002 65.6303 320.21 + vertex 459.169 66.5508 322.153 + endloop + endfacet + facet normal 0.258122 -0.948813 0.18201 + outer loop + vertex 445.56 63.037 322.919 + vertex 457.002 65.6303 320.21 + vertex 447.509 63.9023 324.665 + endloop + endfacet + facet normal 0.248035 -0.949234 0.193479 + outer loop + vertex 436.583 61.469 326.734 + vertex 445.56 63.037 322.919 + vertex 447.509 63.9023 324.665 + endloop + endfacet + facet normal 0.252191 -0.945784 0.204676 + outer loop + vertex 434.854 60.6486 325.073 + vertex 445.56 63.037 322.919 + vertex 436.583 61.469 326.734 + endloop + endfacet + facet normal 0.240966 -0.946077 0.216503 + outer loop + vertex 425.94 59.1589 328.485 + vertex 434.854 60.6486 325.073 + vertex 436.583 61.469 326.734 + endloop + endfacet + facet normal 0.245087 -0.942062 0.229023 + outer loop + vertex 424.288 58.3461 326.909 + vertex 434.854 60.6486 325.073 + vertex 425.94 59.1589 328.485 + endloop + endfacet + facet normal 0.235629 -0.942019 0.23891 + outer loop + vertex 415.736 56.984 329.974 + vertex 424.288 58.3461 326.909 + vertex 425.94 59.1589 328.485 + endloop + endfacet + facet normal 0.240004 -0.937148 0.253283 + outer loop + vertex 414.029 56.1412 328.472 + vertex 424.288 58.3461 326.909 + vertex 415.736 56.984 329.974 + endloop + endfacet + facet normal 0.233853 -0.936837 0.260096 + outer loop + vertex 406.851 55.0655 331.051 + vertex 414.029 56.1412 328.472 + vertex 415.736 56.984 329.974 + endloop + endfacet + facet normal 0.23587 -0.934472 0.266697 + outer loop + vertex 405.186 54.2288 329.592 + vertex 414.029 56.1412 328.472 + vertex 406.851 55.0655 331.051 + endloop + endfacet + facet normal 0.233204 -0.934297 0.269639 + outer loop + vertex 400.273 53.5417 331.46 + vertex 405.186 54.2288 329.592 + vertex 406.851 55.0655 331.051 + endloop + endfacet + facet normal 0.231554 -0.93614 0.264621 + outer loop + vertex 398.864 52.7738 329.977 + vertex 405.186 54.2288 329.592 + vertex 400.273 53.5417 331.46 + endloop + endfacet + facet normal 0.22926 -0.936093 0.266777 + outer loop + vertex 398.864 52.7738 329.977 + vertex 400.273 53.5417 331.46 + vertex 395.955 52.36 331.025 + endloop + endfacet + facet normal 0.251698 -0.954766 0.158336 + outer loop + vertex 480.863 71.281 316.105 + vertex 480.649 71.6134 318.448 + vertex 471.763 69.4208 319.354 + endloop + endfacet + facet normal 0.253983 -0.945753 0.202594 + outer loop + vertex 472.319 70.2872 322.7 + vertex 471.763 69.4208 319.354 + vertex 480.649 71.6134 318.448 + endloop + endfacet + facet normal 0.25846 -0.942379 0.212416 + outer loop + vertex 482.46 72.6967 321.052 + vertex 472.319 70.2872 322.7 + vertex 480.649 71.6134 318.448 + endloop + endfacet + facet normal 0.259437 -0.942273 0.211692 + outer loop + vertex 480.649 71.6134 318.448 + vertex 487.764 73.3364 317.398 + vertex 482.46 72.6967 321.052 + endloop + endfacet + facet normal 0.257207 -0.943659 0.208211 + outer loop + vertex 482.46 72.6967 321.052 + vertex 487.764 73.3364 317.398 + vertex 490.016 74.4285 319.566 + endloop + endfacet + facet normal 0.264733 -0.943307 0.20022 + outer loop + vertex 487.764 73.3364 317.398 + vertex 492.18 74.4718 316.908 + vertex 490.016 74.4285 319.566 + endloop + endfacet + facet normal 0.253333 -0.948366 0.190853 + outer loop + vertex 490.016 74.4285 319.566 + vertex 492.18 74.4718 316.908 + vertex 493.339 75.1428 318.704 + endloop + endfacet + facet normal 0.264783 -0.931645 0.248852 + outer loop + vertex 490.016 74.4285 319.566 + vertex 493.339 75.1428 318.704 + vertex 492.99 75.6997 321.161 + endloop + endfacet + facet normal 0.256339 -0.930031 0.263311 + outer loop + vertex 486.057 74.5959 324.012 + vertex 490.016 74.4285 319.566 + vertex 492.99 75.6997 321.161 + endloop + endfacet + facet normal 0.265356 -0.925234 0.271161 + outer loop + vertex 486.057 74.5959 324.012 + vertex 482.46 72.6967 321.052 + vertex 490.016 74.4285 319.566 + endloop + endfacet + facet normal 0.26335 -0.925112 0.273521 + outer loop + vertex 474.587 71.8048 325.616 + vertex 482.46 72.6967 321.052 + vertex 486.057 74.5959 324.012 + endloop + endfacet + facet normal 0.264404 -0.92422 0.275514 + outer loop + vertex 472.319 70.2872 322.7 + vertex 482.46 72.6967 321.052 + vertex 474.587 71.8048 325.616 + endloop + endfacet + facet normal 0.261734 -0.92434 0.277652 + outer loop + vertex 462.972 69.0873 327.517 + vertex 472.319 70.2872 322.7 + vertex 474.587 71.8048 325.616 + endloop + endfacet + facet normal 0.265898 -0.920375 0.286719 + outer loop + vertex 461.014 67.6546 324.734 + vertex 472.319 70.2872 322.7 + vertex 462.972 69.0873 327.517 + endloop + endfacet + facet normal 0.259838 -0.920713 0.291157 + outer loop + vertex 451.511 66.4797 329.5 + vertex 461.014 67.6546 324.734 + vertex 462.972 69.0873 327.517 + endloop + endfacet + facet normal 0.266333 -0.914107 0.305738 + outer loop + vertex 449.471 65.0338 326.953 + vertex 461.014 67.6546 324.734 + vertex 451.511 66.4797 329.5 + endloop + endfacet + facet normal 0.252916 -0.914233 0.316561 + outer loop + vertex 440.305 64.0126 331.328 + vertex 449.471 65.0338 326.953 + vertex 451.511 66.4797 329.5 + endloop + endfacet + facet normal 0.25956 -0.906784 0.332222 + outer loop + vertex 438.37 62.5709 328.904 + vertex 449.471 65.0338 326.953 + vertex 440.305 64.0126 331.328 + endloop + endfacet + facet normal 0.242903 -0.906494 0.345349 + outer loop + vertex 429.281 61.6613 332.909 + vertex 438.37 62.5709 328.904 + vertex 440.305 64.0126 331.328 + endloop + endfacet + facet normal 0.24936 -0.898257 0.361875 + outer loop + vertex 427.545 60.2369 330.57 + vertex 438.37 62.5709 328.904 + vertex 429.281 61.6613 332.909 + endloop + endfacet + facet normal 0.235732 -0.897896 0.371771 + outer loop + vertex 418.796 59.4553 334.23 + vertex 427.545 60.2369 330.57 + vertex 429.281 61.6613 332.909 + endloop + endfacet + facet normal 0.240955 -0.890551 0.385824 + outer loop + vertex 417.251 58.0591 331.972 + vertex 427.545 60.2369 330.57 + vertex 418.796 59.4553 334.23 + endloop + endfacet + facet normal 0.233143 -0.89035 0.39105 + outer loop + vertex 409.838 57.5197 335.164 + vertex 417.251 58.0591 331.972 + vertex 418.796 59.4553 334.23 + endloop + endfacet + facet normal 0.236454 -0.885702 0.399527 + outer loop + vertex 408.393 56.1497 332.982 + vertex 417.251 58.0591 331.972 + vertex 409.838 57.5197 335.164 + endloop + endfacet + facet normal 0.233872 -0.885634 0.401194 + outer loop + vertex 403.392 55.9553 335.468 + vertex 408.393 56.1497 332.982 + vertex 409.838 57.5197 335.164 + endloop + endfacet + facet normal 0.232374 -0.88745 0.398039 + outer loop + vertex 401.853 54.6059 333.358 + vertex 408.393 56.1497 332.982 + vertex 403.392 55.9553 335.468 + endloop + endfacet + facet normal 0.234851 -0.887571 0.396311 + outer loop + vertex 401.853 54.6059 333.358 + vertex 403.392 55.9553 335.468 + vertex 399.214 54.6471 335.014 + endloop + endfacet + facet normal 0.32992 -0.909451 0.253085 + outer loop + vertex 493.339 75.1428 318.704 + vertex 494.565 75.4919 318.361 + vertex 492.99 75.6997 321.161 + endloop + endfacet + facet normal 0.289081 -0.928878 0.231557 + outer loop + vertex 492.99 75.6997 321.161 + vertex 494.565 75.4919 318.361 + vertex 495.981 76.98 322.563 + endloop + endfacet + facet normal 0.234538 -0.938513 0.253347 + outer loop + vertex 495.981 76.98 322.563 + vertex 494.565 75.4919 318.361 + vertex 497.401 76.6868 320.162 + endloop + endfacet + facet normal 0.309669 -0.938789 0.150929 + outer loop + vertex 493.339 75.1428 318.704 + vertex 492.18 74.4718 316.908 + vertex 494.565 75.4919 318.361 + endloop + endfacet + facet normal 0.26234 -0.951788 0.158988 + outer loop + vertex 487.764 73.3364 317.398 + vertex 490.311 73.6428 315.031 + vertex 492.18 74.4718 316.908 + endloop + endfacet + facet normal 0.28839 -0.948431 0.131564 + outer loop + vertex 490.311 73.6428 315.031 + vertex 492.381 74.1628 314.242 + vertex 492.18 74.4718 316.908 + endloop + endfacet + facet normal 0.278364 -0.955171 0.100806 + outer loop + vertex 490.311 73.6428 315.031 + vertex 489.233 73.1144 312.999 + vertex 492.381 74.1628 314.242 + endloop + endfacet + facet normal 0.25781 -0.959582 0.112855 + outer loop + vertex 486.326 72.6002 315.268 + vertex 489.233 73.1144 312.999 + vertex 490.311 73.6428 315.031 + endloop + endfacet + facet normal 0.255452 -0.960589 0.109604 + outer loop + vertex 484.99 72.0415 313.486 + vertex 489.233 73.1144 312.999 + vertex 486.326 72.6002 315.268 + endloop + endfacet + facet normal 0.254073 -0.962714 0.0928884 + outer loop + vertex 484.99 72.0415 313.486 + vertex 487.587 72.5283 311.427 + vertex 489.233 73.1144 312.999 + endloop + endfacet + facet normal 0.261332 -0.961513 0.0848443 + outer loop + vertex 487.587 72.5283 311.427 + vertex 490.09 73.1393 310.642 + vertex 489.233 73.1144 312.999 + endloop + endfacet + facet normal 0.256063 -0.96442 0.0657724 + outer loop + vertex 487.587 72.5283 311.427 + vertex 486.928 72.251 309.926 + vertex 490.09 73.1393 310.642 + endloop + endfacet + facet normal 0.254574 -0.96435 0.0722595 + outer loop + vertex 488.63 72.6014 308.608 + vertex 490.09 73.1393 310.642 + vertex 486.928 72.251 309.926 + endloop + endfacet + facet normal 0.24442 -0.967921 0.0582006 + outer loop + vertex 485.873 71.9133 308.742 + vertex 488.63 72.6014 308.608 + vertex 486.928 72.251 309.926 + endloop + endfacet + facet normal 0.243154 -0.968167 0.0593992 + outer loop + vertex 482.537 71.2001 310.771 + vertex 485.873 71.9133 308.742 + vertex 486.928 72.251 309.926 + endloop + endfacet + facet normal 0.240976 -0.96894 0.0555479 + outer loop + vertex 481.302 70.8519 310.06 + vertex 485.873 71.9133 308.742 + vertex 482.537 71.2001 310.771 + endloop + endfacet + facet normal 0.244099 -0.968541 0.0484222 + outer loop + vertex 485.873 71.9133 308.742 + vertex 488.031 72.3989 307.576 + vertex 488.63 72.6014 308.608 + endloop + endfacet + facet normal 0.244921 -0.966262 0.0796946 + outer loop + vertex 490.09 73.1393 310.642 + vertex 488.63 72.6014 308.608 + vertex 491.407 73.2621 308.084 + endloop + endfacet + facet normal 0.246055 -0.966682 0.0705832 + outer loop + vertex 483.711 71.5821 311.979 + vertex 486.928 72.251 309.926 + vertex 487.587 72.5283 311.427 + endloop + endfacet + facet normal 0.258713 -0.953458 0.15487 + outer loop + vertex 486.326 72.6002 315.268 + vertex 490.311 73.6428 315.031 + vertex 487.764 73.3364 317.398 + endloop + endfacet + facet normal 0.25438 -0.954107 0.15802 + outer loop + vertex 480.649 71.6134 318.448 + vertex 486.326 72.6002 315.268 + vertex 487.764 73.3364 317.398 + endloop + endfacet + facet normal 0.256447 -0.945206 0.202042 + outer loop + vertex 461.014 67.6546 324.734 + vertex 471.763 69.4208 319.354 + vertex 472.319 70.2872 322.7 + endloop + endfacet + facet normal 0.262167 -0.940786 0.214919 + outer loop + vertex 459.169 66.5508 322.153 + vertex 471.763 69.4208 319.354 + vertex 461.014 67.6546 324.734 + endloop + endfacet + facet normal 0.255972 -0.941408 0.219614 + outer loop + vertex 449.471 65.0338 326.953 + vertex 459.169 66.5508 322.153 + vertex 461.014 67.6546 324.734 + endloop + endfacet + facet normal 0.263406 -0.935224 0.236587 + outer loop + vertex 447.509 63.9023 324.665 + vertex 459.169 66.5508 322.153 + vertex 449.471 65.0338 326.953 + endloop + endfacet + facet normal 0.251095 -0.935806 0.247425 + outer loop + vertex 438.37 62.5709 328.904 + vertex 447.509 63.9023 324.665 + vertex 449.471 65.0338 326.953 + endloop + endfacet + facet normal 0.256686 -0.930551 0.261127 + outer loop + vertex 436.583 61.469 326.734 + vertex 447.509 63.9023 324.665 + vertex 438.37 62.5709 328.904 + endloop + endfacet + facet normal 0.242708 -0.930943 0.272834 + outer loop + vertex 427.545 60.2369 330.57 + vertex 436.583 61.469 326.734 + vertex 438.37 62.5709 328.904 + endloop + endfacet + facet normal 0.248079 -0.925141 0.287352 + outer loop + vertex 425.94 59.1589 328.485 + vertex 436.583 61.469 326.734 + vertex 427.545 60.2369 330.57 + endloop + endfacet + facet normal 0.236161 -0.925333 0.296627 + outer loop + vertex 417.251 58.0591 331.972 + vertex 425.94 59.1589 328.485 + vertex 427.545 60.2369 330.57 + endloop + endfacet + facet normal 0.241327 -0.919104 0.311463 + outer loop + vertex 415.736 56.984 329.974 + vertex 425.94 59.1589 328.485 + vertex 417.251 58.0591 331.972 + endloop + endfacet + facet normal 0.234233 -0.919102 0.316839 + outer loop + vertex 408.393 56.1497 332.982 + vertex 415.736 56.984 329.974 + vertex 417.251 58.0591 331.972 + endloop + endfacet + facet normal 0.237113 -0.91556 0.32485 + outer loop + vertex 406.851 55.0655 331.051 + vertex 415.736 56.984 329.974 + vertex 408.393 56.1497 332.982 + endloop + endfacet + facet normal 0.234891 -0.915511 0.326597 + outer loop + vertex 401.853 54.6059 333.358 + vertex 406.851 55.0655 331.051 + vertex 408.393 56.1497 332.982 + endloop + endfacet + facet normal 0.232634 -0.917989 0.321212 + outer loop + vertex 400.273 53.5417 331.46 + vertex 406.851 55.0655 331.051 + vertex 401.853 54.6059 333.358 + endloop + endfacet + facet normal 0.233883 -0.918028 0.320194 + outer loop + vertex 400.273 53.5417 331.46 + vertex 401.853 54.6059 333.358 + vertex 397.561 53.3663 332.939 + endloop + endfacet + facet normal 0.254618 -0.953966 0.158488 + outer loop + vertex 480.863 71.281 316.105 + vertex 486.326 72.6002 315.268 + vertex 480.649 71.6134 318.448 + endloop + endfacet + facet normal 0.249679 -0.961567 0.114237 + outer loop + vertex 480.863 71.281 316.105 + vertex 484.99 72.0415 313.486 + vertex 486.326 72.6002 315.268 + endloop + endfacet + facet normal 0.247628 -0.965192 0.0841734 + outer loop + vertex 483.711 71.5821 311.979 + vertex 487.587 72.5283 311.427 + vertex 484.99 72.0415 313.486 + endloop + endfacet + facet normal 0.244612 -0.967223 0.0681469 + outer loop + vertex 482.537 71.2001 310.771 + vertex 486.928 72.251 309.926 + vertex 483.711 71.5821 311.979 + endloop + endfacet + facet normal 0.238881 -0.969235 0.0593312 + outer loop + vertex 475.978 69.7112 312.86 + vertex 481.302 70.8519 310.06 + vertex 482.537 71.2001 310.771 + endloop + endfacet + facet normal 0.243485 -0.965183 0.0955898 + outer loop + vertex 478.42 70.3527 313.244 + vertex 478.542 70.5553 314.978 + vertex 469.661 68.4976 316.825 + endloop + endfacet + facet normal 0.241937 -0.967568 0.072656 + outer loop + vertex 475.576 69.5476 312.02 + vertex 475.978 69.7112 312.86 + vertex 466.805 67.6243 315.612 + endloop + endfacet + facet normal 0.250588 -0.961615 0.111812 + outer loop + vertex 454.406 64.8177 319.262 + vertex 462.59 66.5732 316.018 + vertex 466.805 67.6243 315.612 + endloop + endfacet + facet normal 0.247338 -0.961277 0.121531 + outer loop + vertex 443.423 62.334 321.97 + vertex 451.406 64.046 319.264 + vertex 454.406 64.8177 319.262 + endloop + endfacet + facet normal 0.242045 -0.960892 0.134538 + outer loop + vertex 432.89 59.9877 324.162 + vertex 440.966 61.6958 321.831 + vertex 443.423 62.334 321.97 + endloop + endfacet + facet normal 0.239091 -0.956344 0.168052 + outer loop + vertex 422.256 57.6636 326.065 + vertex 430.426 59.3507 324.043 + vertex 432.89 59.9877 324.162 + endloop + endfacet + facet normal 0.236988 -0.949366 0.206256 + outer loop + vertex 411.994 55.4491 327.664 + vertex 419.528 56.9644 325.981 + vertex 422.256 57.6636 326.065 + endloop + endfacet + facet normal 0.236785 -0.949673 0.205071 + outer loop + vertex 409.583 54.8162 327.516 + vertex 419.528 56.9644 325.981 + vertex 411.994 55.4491 327.664 + endloop + endfacet + facet normal 0.250018 -0.897061 0.36438 + outer loop + vertex 419.528 56.9644 325.981 + vertex 409.583 54.8162 327.516 + vertex 414.846 55.9121 326.603 + endloop + endfacet + facet normal 0.228325 -0.950206 0.212077 + outer loop + vertex 397.932 52.2887 328.913 + vertex 402.11 53.187 328.44 + vertex 398.479 52.4796 329.179 + endloop + endfacet + facet normal 0.234433 -0.945542 0.225814 + outer loop + vertex 403.513 53.6097 328.766 + vertex 409.583 54.8162 327.516 + vertex 411.994 55.4491 327.664 + endloop + endfacet + facet normal 0.218393 -0.960901 0.170216 + outer loop + vertex 400.172 52.6921 328.132 + vertex 403.562 53.451 328.067 + vertex 402.11 53.187 328.44 + endloop + endfacet + facet normal 0.205644 -0.973113 0.103735 + outer loop + vertex 395.63 51.8401 329.144 + vertex 396.581 51.7796 326.692 + vertex 400.172 52.6921 328.132 + endloop + endfacet + facet normal 0.223205 -0.971107 0.0844505 + outer loop + vertex 404.859 53.5943 326.587 + vertex 414.046 55.614 325.532 + vertex 407.225 54.1988 327.284 + endloop + endfacet + facet normal 0.238638 -0.938664 0.248922 + outer loop + vertex 408.391 54.5069 327.493 + vertex 414.846 55.9121 326.603 + vertex 409.583 54.8162 327.516 + endloop + endfacet + facet normal 0.243282 -0.939175 0.242413 + outer loop + vertex 414.846 55.9121 326.603 + vertex 421.102 57.2668 325.573 + vertex 419.528 56.9644 325.981 + endloop + endfacet + facet normal 0.226174 -0.971387 0.0724788 + outer loop + vertex 416.645 56.263 326.01 + vertex 424.671 57.964 323.762 + vertex 427.991 58.7592 324.06 + endloop + endfacet + facet normal 0.23969 -0.955664 0.17104 + outer loop + vertex 419.528 56.9644 325.981 + vertex 430.426 59.3507 324.043 + vertex 422.256 57.6636 326.065 + endloop + endfacet + facet normal 0.230149 -0.969652 0.0824966 + outer loop + vertex 432.321 59.7399 323.505 + vertex 426.42 58.4393 324.683 + vertex 427.991 58.7592 324.06 + endloop + endfacet + facet normal 0.228412 -0.972059 0.0541256 + outer loop + vertex 437.227 60.8374 322.513 + vertex 432.321 59.7399 323.505 + vertex 438.946 61.199 321.754 + endloop + endfacet + facet normal 0.241933 -0.960984 0.134083 + outer loop + vertex 430.426 59.3507 324.043 + vertex 440.966 61.6958 321.831 + vertex 432.89 59.9877 324.162 + endloop + endfacet + facet normal 0.231376 -0.970927 0.061373 + outer loop + vertex 442.886 62.1009 321.17 + vertex 437.227 60.8374 322.513 + vertex 438.946 61.199 321.754 + endloop + endfacet + facet normal 0.232188 -0.97114 0.0545489 + outer loop + vertex 447.603 63.1663 320.055 + vertex 442.886 62.1009 321.17 + vertex 449.47 63.5649 319.204 + endloop + endfacet + facet normal 0.244061 -0.963445 0.110488 + outer loop + vertex 440.966 61.6958 321.831 + vertex 451.406 64.046 319.264 + vertex 443.423 62.334 321.97 + endloop + endfacet + facet normal 0.23454 -0.970245 0.060131 + outer loop + vertex 453.168 64.4177 318.542 + vertex 447.603 63.1663 320.055 + vertex 449.47 63.5649 319.204 + endloop + endfacet + facet normal 0.234463 -0.970708 0.0524718 + outer loop + vertex 457.582 65.42 317.36 + vertex 453.168 64.4177 318.542 + vertex 459.841 65.9122 316.374 + endloop + endfacet + facet normal 0.247821 -0.963211 0.103968 + outer loop + vertex 451.406 64.046 319.264 + vertex 462.59 66.5732 316.018 + vertex 454.406 64.8177 319.262 + endloop + endfacet + facet normal 0.234898 -0.970544 0.0535501 + outer loop + vertex 460.998 66.1905 316.343 + vertex 457.582 65.42 317.36 + vertex 459.841 65.9122 316.374 + endloop + endfacet + facet normal 0.234817 -0.970878 0.0475172 + outer loop + vertex 464.042 66.8783 315.353 + vertex 460.998 66.1905 316.343 + vertex 459.841 65.9122 316.374 + endloop + endfacet + facet normal 0.23205 -0.972113 0.0338962 + outer loop + vertex 466.531 67.4454 314.576 + vertex 464.042 66.8783 315.353 + vertex 470.051 68.233 313.065 + endloop + endfacet + facet normal 0.235583 -0.970913 0.042755 + outer loop + vertex 469.132 68.0389 313.72 + vertex 466.531 67.4454 314.576 + vertex 470.051 68.233 313.065 + endloop + endfacet + facet normal 0.249274 -0.964071 0.0918103 + outer loop + vertex 462.59 66.5732 316.018 + vertex 472.238 68.7626 312.815 + vertex 466.805 67.6243 315.612 + endloop + endfacet + facet normal 0.235928 -0.970807 0.0432699 + outer loop + vertex 473.458 69.0208 312.166 + vertex 469.132 68.0389 313.72 + vertex 470.051 68.233 313.065 + endloop + endfacet + facet normal 0.231595 -0.972476 0.0255918 + outer loop + vertex 476.346 69.6819 311.155 + vertex 473.458 69.0208 312.166 + vertex 478.072 70.0698 310.276 + endloop + endfacet + facet normal 0.234988 -0.971448 0.0327015 + outer loop + vertex 480.098 70.544 309.803 + vertex 476.346 69.6819 311.155 + vertex 478.072 70.0698 310.276 + endloop + endfacet + facet normal 0.248141 -0.96459 0.0893986 + outer loop + vertex 466.805 67.6243 315.612 + vertex 472.238 68.7626 312.815 + vertex 475.576 69.5476 312.02 + endloop + endfacet + facet normal 0.244664 -0.966987 0.0712399 + outer loop + vertex 475.576 69.5476 312.02 + vertex 481.302 70.8519 310.06 + vertex 475.978 69.7112 312.86 + endloop + endfacet + facet normal 0.236574 -0.970841 0.0387451 + outer loop + vertex 485.873 71.9133 308.742 + vertex 481.302 70.8519 310.06 + vertex 485.201 71.7205 308.013 + endloop + endfacet + facet normal 0.232794 -0.972218 0.0244685 + outer loop + vertex 485.097 71.6852 307.583 + vertex 480.098 70.544 309.803 + vertex 483.349 71.2798 308.11 + endloop + endfacet + facet normal 0.246823 -0.968471 0.033804 + outer loop + vertex 488.598 72.5247 306.068 + vertex 485.097 71.6852 307.583 + vertex 486.185 71.9359 306.822 + endloop + endfacet + facet normal 0.238361 -0.970472 0.0369996 + outer loop + vertex 485.201 71.7205 308.013 + vertex 488.031 72.3989 307.576 + vertex 485.873 71.9133 308.742 + endloop + endfacet + facet normal 0.240224 -0.969386 0.0508345 + outer loop + vertex 488.63 72.6014 308.608 + vertex 488.031 72.3989 307.576 + vertex 491.407 73.2621 308.084 + endloop + endfacet + facet normal 0.238092 -0.970911 0.0253762 + outer loop + vertex 494.237 73.8691 307.143 + vertex 495.868 74.2553 306.62 + vertex 499.329 75.1106 306.873 + endloop + endfacet + facet normal 0.239239 -0.969477 0.0536482 + outer loop + vertex 494.237 73.8691 307.143 + vertex 499.329 75.1106 306.873 + vertex 494.857 74.0457 307.569 + endloop + endfacet + facet normal 0.240682 -0.968461 0.0644664 + outer loop + vertex 494.857 74.0457 307.569 + vertex 499.329 75.1106 306.873 + vertex 500.831 75.535 307.639 + endloop + endfacet + facet normal 0.243759 -0.968087 0.0582198 + outer loop + vertex 499.329 75.1106 306.873 + vertex 510.366 77.8828 306.758 + vertex 500.831 75.535 307.639 + endloop + endfacet + facet normal 0.24485 -0.966767 0.0735539 + outer loop + vertex 500.831 75.535 307.639 + vertex 510.366 77.8828 306.758 + vertex 511.722 78.3008 307.739 + endloop + endfacet + facet normal 0.245053 -0.967283 0.0656704 + outer loop + vertex 500.831 75.535 307.639 + vertex 511.722 78.3008 307.739 + vertex 501.086 75.6841 308.885 + endloop + endfacet + facet normal 0.238891 -0.968725 0.0671015 + outer loop + vertex 494.986 74.1797 308.884 + vertex 500.831 75.535 307.639 + vertex 501.086 75.6841 308.885 + endloop + endfacet + facet normal 0.245758 -0.966503 0.0739964 + outer loop + vertex 501.086 75.6841 308.885 + vertex 511.722 78.3008 307.739 + vertex 509.37 77.8022 309.037 + endloop + endfacet + facet normal 0.245364 -0.965728 0.0846513 + outer loop + vertex 501.086 75.6841 308.885 + vertex 509.37 77.8022 309.037 + vertex 501.504 75.9167 310.328 + endloop + endfacet + facet normal 0.241247 -0.966647 0.085992 + outer loop + vertex 496.221 74.5889 310.222 + vertex 501.086 75.6841 308.885 + vertex 501.504 75.9167 310.328 + endloop + endfacet + facet normal 0.247994 -0.963108 0.104512 + outer loop + vertex 501.504 75.9167 310.328 + vertex 509.37 77.8022 309.037 + vertex 511.546 78.5108 310.405 + endloop + endfacet + facet normal 0.247714 -0.962265 0.112621 + outer loop + vertex 501.504 75.9167 310.328 + vertex 511.546 78.5108 310.405 + vertex 502.028 76.243 311.963 + endloop + endfacet + facet normal 0.243473 -0.963166 0.114161 + outer loop + vertex 496.695 74.8447 311.539 + vertex 501.504 75.9167 310.328 + vertex 502.028 76.243 311.963 + endloop + endfacet + facet normal 0.248755 -0.961001 0.120822 + outer loop + vertex 502.028 76.243 311.963 + vertex 511.546 78.5108 310.405 + vertex 509.943 78.312 312.122 + endloop + endfacet + facet normal 0.249682 -0.962967 0.101753 + outer loop + vertex 509.37 77.8022 309.037 + vertex 525.835 82.0135 308.489 + vertex 511.546 78.5108 310.405 + endloop + endfacet + facet normal 0.251652 -0.960147 0.121611 + outer loop + vertex 525.835 82.0135 308.489 + vertex 525.807 82.3364 311.098 + vertex 511.546 78.5108 310.405 + endloop + endfacet + facet normal 0.24951 -0.964946 0.0813894 + outer loop + vertex 509.37 77.8022 309.037 + vertex 511.722 78.3008 307.739 + vertex 525.835 82.0135 308.489 + endloop + endfacet + facet normal 0.248419 -0.963841 0.0964314 + outer loop + vertex 527.67 82.3146 306.773 + vertex 525.835 82.0135 308.489 + vertex 511.722 78.3008 307.739 + endloop + endfacet + facet normal 0.249791 -0.963329 0.0979865 + outer loop + vertex 527.67 82.3146 306.773 + vertex 548.05 87.6428 307.201 + vertex 525.835 82.0135 308.489 + endloop + endfacet + facet normal 0.250282 -0.96126 0.115495 + outer loop + vertex 525.835 82.0135 308.489 + vertex 548.05 87.6428 307.201 + vertex 549.063 88.1086 308.883 + endloop + endfacet + facet normal 0.247943 -0.959268 0.135382 + outer loop + vertex 527.67 82.3146 306.773 + vertex 546.178 87.0422 306.375 + vertex 548.05 87.6428 307.201 + endloop + endfacet + facet normal 0.250206 -0.95938 0.130336 + outer loop + vertex 546.178 87.0422 306.375 + vertex 565.79 92.1924 306.636 + vertex 548.05 87.6428 307.201 + endloop + endfacet + facet normal 0.250213 -0.961758 0.111425 + outer loop + vertex 548.05 87.6428 307.201 + vertex 565.79 92.1924 306.636 + vertex 571.551 93.7941 307.524 + endloop + endfacet + facet normal 0.248419 -0.95437 0.165727 + outer loop + vertex 565.79 92.1924 306.636 + vertex 546.178 87.0422 306.375 + vertex 557.474 89.9644 306.271 + endloop + endfacet + facet normal 0.247892 -0.958762 0.139012 + outer loop + vertex 531.561 83.2307 306.153 + vertex 546.178 87.0422 306.375 + vertex 527.67 82.3146 306.773 + endloop + endfacet + facet normal 0.245985 -0.961425 0.123099 + outer loop + vertex 531.561 83.2307 306.153 + vertex 527.67 82.3146 306.773 + vertex 519.715 80.2082 306.217 + endloop + endfacet + facet normal 0.241479 -0.941379 0.235571 + outer loop + vertex 519.715 80.2082 306.217 + vertex 524.663 81.4337 306.042 + vertex 531.561 83.2307 306.153 + endloop + endfacet + facet normal 0.223214 -0.882281 0.414435 + outer loop + vertex 531.561 83.2307 306.153 + vertex 524.663 81.4337 306.042 + vertex 529.984 82.7801 306.043 + endloop + endfacet + facet normal 0.239337 -0.923623 0.299397 + outer loop + vertex 516.817 79.4307 306.135 + vertex 524.663 81.4337 306.042 + vertex 519.715 80.2082 306.217 + endloop + endfacet + facet normal 0.232826 -0.90525 0.355408 + outer loop + vertex 506.823 76.9471 306.357 + vertex 516.817 79.4307 306.135 + vertex 519.715 80.2082 306.217 + endloop + endfacet + facet normal 0.245183 -0.9656 0.0866141 + outer loop + vertex 506.823 76.9471 306.357 + vertex 519.715 80.2082 306.217 + vertex 510.366 77.8828 306.758 + endloop + endfacet + facet normal 0.22073 -0.844814 0.48741 + outer loop + vertex 510.312 77.7897 306.237 + vertex 516.817 79.4307 306.135 + vertex 506.823 76.9471 306.357 + endloop + endfacet + facet normal 0.236742 -0.954644 0.180576 + outer loop + vertex 510.312 77.7897 306.237 + vertex 506.823 76.9471 306.357 + vertex 505.472 76.5816 306.195 + endloop + endfacet + facet normal 0.200098 -0.754482 0.625075 + outer loop + vertex 516.817 79.4307 306.135 + vertex 510.312 77.7897 306.237 + vertex 513.823 78.6557 306.158 + endloop + endfacet + facet normal 0.179356 -0.669096 0.721209 + outer loop + vertex 524.663 81.4337 306.042 + vertex 516.817 79.4307 306.135 + vertex 522.915 80.9583 306.036 + endloop + endfacet + facet normal 0.235466 -0.921053 0.310188 + outer loop + vertex 546.178 87.0422 306.375 + vertex 531.561 83.2307 306.153 + vertex 538.208 84.9078 306.087 + endloop + endfacet + facet normal 0.247446 -0.966384 0.069802 + outer loop + vertex 510.366 77.8828 306.758 + vertex 527.67 82.3146 306.773 + vertex 511.722 78.3008 307.739 + endloop + endfacet + facet normal 0.243349 -0.964698 0.100692 + outer loop + vertex 510.366 77.8828 306.758 + vertex 499.329 75.1106 306.873 + vertex 506.823 76.9471 306.357 + endloop + endfacet + facet normal 0.240384 -0.967764 0.0751558 + outer loop + vertex 494.857 74.0457 307.569 + vertex 500.831 75.535 307.639 + vertex 494.986 74.1797 308.884 + endloop + endfacet + facet normal 0.238743 -0.96813 0.0756674 + outer loop + vertex 494.986 74.1797 308.884 + vertex 501.086 75.6841 308.885 + vertex 496.221 74.5889 310.222 + endloop + endfacet + facet normal 0.240624 -0.965358 0.100913 + outer loop + vertex 496.221 74.5889 310.222 + vertex 501.504 75.9167 310.328 + vertex 496.695 74.8447 311.539 + endloop + endfacet + facet normal 0.24117 -0.960935 0.135797 + outer loop + vertex 496.695 74.8447 311.539 + vertex 502.028 76.243 311.963 + vertex 496.957 75.1737 313.402 + endloop + endfacet + facet normal 0.242024 -0.960213 0.139341 + outer loop + vertex 496.957 75.1737 313.402 + vertex 502.028 76.243 311.963 + vertex 502.676 76.6652 313.746 + endloop + endfacet + facet normal 0.244937 -0.950538 0.191006 + outer loop + vertex 498.639 76.2951 317.343 + vertex 503.381 77.1612 315.573 + vertex 503.87 77.6451 317.354 + endloop + endfacet + facet normal 0.2443 -0.948165 0.203225 + outer loop + vertex 498.639 76.2951 317.343 + vertex 503.87 77.6451 317.354 + vertex 499.814 76.9583 319.025 + endloop + endfacet + facet normal 0.213324 -0.95053 0.2258 + outer loop + vertex 498.639 76.2951 317.343 + vertex 499.814 76.9583 319.025 + vertex 497.401 76.6868 320.162 + endloop + endfacet + facet normal 0.210511 -0.95142 0.224688 + outer loop + vertex 497.401 76.6868 320.162 + vertex 495.296 75.1906 315.799 + vertex 498.639 76.2951 317.343 + endloop + endfacet + facet normal 0.225768 -0.94031 0.254649 + outer loop + vertex 499.814 76.9583 319.025 + vertex 500.344 77.4839 320.497 + vertex 497.401 76.6868 320.162 + endloop + endfacet + facet normal 0.217735 -0.929154 0.298773 + outer loop + vertex 500.344 77.4839 320.497 + vertex 500.857 78.2723 322.574 + vertex 497.401 76.6868 320.162 + endloop + endfacet + facet normal 0.224849 -0.930422 0.28941 + outer loop + vertex 498.671 78.2961 324.349 + vertex 497.401 76.6868 320.162 + vertex 500.857 78.2723 322.574 + endloop + endfacet + facet normal 0.247594 -0.924555 0.289646 + outer loop + vertex 500.344 77.4839 320.497 + vertex 505.017 78.8753 320.943 + vertex 500.857 78.2723 322.574 + endloop + endfacet + facet normal 0.250763 -0.920662 0.299165 + outer loop + vertex 500.857 78.2723 322.574 + vertex 505.017 78.8753 320.943 + vertex 506.995 80.103 323.063 + endloop + endfacet + facet normal 0.253158 -0.920719 0.296964 + outer loop + vertex 505.017 78.8753 320.943 + vertex 513.964 81.296 320.821 + vertex 506.995 80.103 323.063 + endloop + endfacet + facet normal 0.25239 -0.921896 0.293951 + outer loop + vertex 506.995 80.103 323.063 + vertex 513.964 81.296 320.821 + vertex 513.937 81.8809 322.679 + endloop + endfacet + facet normal 0.250983 -0.906642 0.339127 + outer loop + vertex 513.937 81.8809 322.679 + vertex 513.145 82.6015 325.192 + vertex 506.995 80.103 323.063 + endloop + endfacet + facet normal 0.252547 -0.90751 0.335628 + outer loop + vertex 513.145 82.6015 325.192 + vertex 503.134 79.9308 325.503 + vertex 506.995 80.103 323.063 + endloop + endfacet + facet normal 0.246354 -0.912904 0.325446 + outer loop + vertex 500.857 78.2723 322.574 + vertex 506.995 80.103 323.063 + vertex 503.134 79.9308 325.503 + endloop + endfacet + facet normal 0.251228 -0.912916 0.321664 + outer loop + vertex 500.857 78.2723 322.574 + vertex 503.134 79.9308 325.503 + vertex 498.671 78.2961 324.349 + endloop + endfacet + facet normal 0.252725 -0.90602 0.339497 + outer loop + vertex 513.937 81.8809 322.679 + vertex 526.991 85.0822 321.505 + vertex 513.145 82.6015 325.192 + endloop + endfacet + facet normal 0.250472 -0.910973 0.327706 + outer loop + vertex 513.145 82.6015 325.192 + vertex 526.991 85.0822 321.505 + vertex 529.667 87.1294 325.15 + endloop + endfacet + facet normal 0.244391 -0.911002 0.332187 + outer loop + vertex 526.991 85.0822 321.505 + vertex 548.938 90.9795 321.531 + vertex 529.667 87.1294 325.15 + endloop + endfacet + facet normal 0.245099 -0.908403 0.33872 + outer loop + vertex 529.667 87.1294 325.15 + vertex 548.938 90.9795 321.531 + vertex 548.892 92.2871 325.071 + endloop + endfacet + facet normal 0.240091 -0.909599 0.339096 + outer loop + vertex 548.938 90.9795 321.531 + vertex 568.414 96.2788 321.957 + vertex 548.892 92.2871 325.071 + endloop + endfacet + facet normal 0.241441 -0.902495 0.356664 + outer loop + vertex 548.892 92.2871 325.071 + vertex 568.414 96.2788 321.957 + vertex 567.844 97.3932 325.162 + endloop + endfacet + facet normal 0.23655 -0.903934 0.356296 + outer loop + vertex 568.414 96.2788 321.957 + vertex 583.964 100.597 322.588 + vertex 567.844 97.3932 325.162 + endloop + endfacet + facet normal 0.238238 -0.894228 0.378945 + outer loop + vertex 567.844 97.3932 325.162 + vertex 583.964 100.597 322.588 + vertex 583.938 101.761 325.35 + endloop + endfacet + facet normal 0.234417 -0.881484 0.40992 + outer loop + vertex 567.844 97.3932 325.162 + vertex 583.938 101.761 325.35 + vertex 567.922 98.9527 328.471 + endloop + endfacet + facet normal 0.238559 -0.880609 0.40941 + outer loop + vertex 549.018 93.8747 328.564 + vertex 567.844 97.3932 325.162 + vertex 567.922 98.9527 328.471 + endloop + endfacet + facet normal 0.237236 -0.88757 0.394891 + outer loop + vertex 548.892 92.2871 325.071 + vertex 567.844 97.3932 325.162 + vertex 549.018 93.8747 328.564 + endloop + endfacet + facet normal 0.241569 -0.886655 0.39432 + outer loop + vertex 530.506 88.9281 328.782 + vertex 548.892 92.2871 325.071 + vertex 549.018 93.8747 328.564 + endloop + endfacet + facet normal 0.240558 -0.890756 0.385598 + outer loop + vertex 529.667 87.1294 325.15 + vertex 548.892 92.2871 325.071 + vertex 530.506 88.9281 328.782 + endloop + endfacet + facet normal 0.245495 -0.890052 0.384109 + outer loop + vertex 515.367 84.816 328.929 + vertex 529.667 87.1294 325.15 + vertex 530.506 88.9281 328.782 + endloop + endfacet + facet normal 0.245133 -0.890988 0.382164 + outer loop + vertex 513.145 82.6015 325.192 + vertex 529.667 87.1294 325.15 + vertex 515.367 84.816 328.929 + endloop + endfacet + facet normal 0.251068 -0.890872 0.378565 + outer loop + vertex 505.449 81.9564 328.777 + vertex 513.145 82.6015 325.192 + vertex 515.367 84.816 328.929 + endloop + endfacet + facet normal 0.249788 -0.892518 0.375523 + outer loop + vertex 503.134 79.9308 325.503 + vertex 513.145 82.6015 325.192 + vertex 505.449 81.9564 328.777 + endloop + endfacet + facet normal 0.257905 -0.892588 0.369827 + outer loop + vertex 503.134 79.9308 325.503 + vertex 505.449 81.9564 328.777 + vertex 500.235 80.1291 328.003 + endloop + endfacet + facet normal 0.236043 -0.873781 0.425195 + outer loop + vertex 567.922 98.9527 328.471 + vertex 583.938 101.761 325.35 + vertex 584.191 103.359 328.494 + endloop + endfacet + facet normal 0.231408 -0.856859 0.460698 + outer loop + vertex 567.922 98.9527 328.471 + vertex 584.191 103.359 328.494 + vertex 567.975 100.807 331.894 + endloop + endfacet + facet normal 0.23438 -0.856253 0.460323 + outer loop + vertex 549.12 95.7294 332.048 + vertex 567.922 98.9527 328.471 + vertex 567.975 100.807 331.894 + endloop + endfacet + facet normal 0.233543 -0.861163 0.451504 + outer loop + vertex 549.018 93.8747 328.564 + vertex 567.922 98.9527 328.471 + vertex 549.12 95.7294 332.048 + endloop + endfacet + facet normal 0.236849 -0.860497 0.451052 + outer loop + vertex 530.753 90.8114 332.311 + vertex 549.018 93.8747 328.564 + vertex 549.12 95.7294 332.048 + endloop + endfacet + facet normal 0.236121 -0.864049 0.444597 + outer loop + vertex 530.506 88.9281 328.782 + vertex 549.018 93.8747 328.564 + vertex 530.753 90.8114 332.311 + endloop + endfacet + facet normal 0.240436 -0.863237 0.443861 + outer loop + vertex 515.97 86.7855 332.489 + vertex 530.506 88.9281 328.782 + vertex 530.753 90.8114 332.311 + endloop + endfacet + facet normal 0.239533 -0.866154 0.438635 + outer loop + vertex 515.367 84.816 328.929 + vertex 530.506 88.9281 328.782 + vertex 515.97 86.7855 332.489 + endloop + endfacet + facet normal 0.245612 -0.86523 0.437095 + outer loop + vertex 506.455 83.9925 332.307 + vertex 515.367 84.816 328.929 + vertex 515.97 86.7855 332.489 + endloop + endfacet + facet normal 0.243814 -0.868516 0.431549 + outer loop + vertex 505.449 81.9564 328.777 + vertex 515.367 84.816 328.929 + vertex 506.455 83.9925 332.307 + endloop + endfacet + facet normal 0.25432 -0.867325 0.427866 + outer loop + vertex 505.449 81.9564 328.777 + vertex 506.455 83.9925 332.307 + vertex 501.375 82.1547 331.601 + endloop + endfacet + facet normal 0.23265 -0.850814 0.471158 + outer loop + vertex 567.975 100.807 331.894 + vertex 584.191 103.359 328.494 + vertex 583.915 105.179 331.917 + endloop + endfacet + facet normal 0.226165 -0.827394 0.51407 + outer loop + vertex 567.975 100.807 331.894 + vertex 583.915 105.179 331.917 + vertex 567.734 102.857 335.299 + endloop + endfacet + facet normal 0.228226 -0.826916 0.513929 + outer loop + vertex 549.068 97.8193 335.482 + vertex 567.975 100.807 331.894 + vertex 567.734 102.857 335.299 + endloop + endfacet + facet normal 0.227769 -0.83023 0.508762 + outer loop + vertex 549.12 95.7294 332.048 + vertex 567.975 100.807 331.894 + vertex 549.068 97.8193 335.482 + endloop + endfacet + facet normal 0.230062 -0.829754 0.508507 + outer loop + vertex 530.823 92.9186 335.74 + vertex 549.12 95.7294 332.048 + vertex 549.068 97.8193 335.482 + endloop + endfacet + facet normal 0.229814 -0.831284 0.506114 + outer loop + vertex 530.753 90.8114 332.311 + vertex 549.12 95.7294 332.048 + vertex 530.823 92.9186 335.74 + endloop + endfacet + facet normal 0.233561 -0.830558 0.505592 + outer loop + vertex 516.109 88.8751 335.895 + vertex 530.753 90.8114 332.311 + vertex 530.823 92.9186 335.74 + endloop + endfacet + facet normal 0.232933 -0.833129 0.501635 + outer loop + vertex 515.97 86.7855 332.489 + vertex 530.753 90.8114 332.311 + vertex 516.109 88.8751 335.895 + endloop + endfacet + facet normal 0.238652 -0.83205 0.500738 + outer loop + vertex 506.779 86.0921 335.717 + vertex 515.97 86.7855 332.489 + vertex 516.109 88.8751 335.895 + endloop + endfacet + facet normal 0.23634 -0.837296 0.49303 + outer loop + vertex 506.455 83.9925 332.307 + vertex 515.97 86.7855 332.489 + vertex 506.779 86.0921 335.717 + endloop + endfacet + facet normal 0.24687 -0.835495 0.490921 + outer loop + vertex 506.455 83.9925 332.307 + vertex 506.779 86.0921 335.717 + vertex 501.958 84.319 335.124 + endloop + endfacet + facet normal 0.227162 -0.821639 0.522788 + outer loop + vertex 567.734 102.857 335.299 + vertex 583.915 105.179 331.917 + vertex 583.525 107.194 335.253 + endloop + endfacet + facet normal 0.219583 -0.793565 0.567484 + outer loop + vertex 567.734 102.857 335.299 + vertex 583.525 107.194 335.253 + vertex 567.441 105.114 338.568 + endloop + endfacet + facet normal 0.220663 -0.793318 0.567411 + outer loop + vertex 548.886 100.111 338.789 + vertex 567.734 102.857 335.299 + vertex 567.441 105.114 338.568 + endloop + endfacet + facet normal 0.220374 -0.796017 0.563731 + outer loop + vertex 549.068 97.8193 335.482 + vertex 567.734 102.857 335.299 + vertex 548.886 100.111 338.789 + endloop + endfacet + facet normal 0.221562 -0.795764 0.563622 + outer loop + vertex 530.743 95.2495 339.058 + vertex 549.068 97.8193 335.482 + vertex 548.886 100.111 338.789 + endloop + endfacet + facet normal 0.221612 -0.795363 0.564168 + outer loop + vertex 530.823 92.9186 335.74 + vertex 549.068 97.8193 335.482 + vertex 530.743 95.2495 339.058 + endloop + endfacet + facet normal 0.224312 -0.794827 0.563857 + outer loop + vertex 516.061 91.2138 339.21 + vertex 530.823 92.9186 335.74 + vertex 530.743 95.2495 339.058 + endloop + endfacet + facet normal 0.224329 -0.794737 0.563977 + outer loop + vertex 516.109 88.8751 335.895 + vertex 530.823 92.9186 335.74 + vertex 516.061 91.2138 339.21 + endloop + endfacet + facet normal 0.230947 -0.793426 0.56315 + outer loop + vertex 506.823 88.3227 338.925 + vertex 516.109 88.8751 335.895 + vertex 516.061 91.2138 339.21 + endloop + endfacet + facet normal 0.228315 -0.800774 0.553745 + outer loop + vertex 506.779 86.0921 335.717 + vertex 516.109 88.8751 335.895 + vertex 506.823 88.3227 338.925 + endloop + endfacet + facet normal 0.238996 -0.798736 0.55218 + outer loop + vertex 506.779 86.0921 335.717 + vertex 506.823 88.3227 338.925 + vertex 502.369 86.6226 338.393 + endloop + endfacet + facet normal 0.220669 -0.785999 0.577503 + outer loop + vertex 567.441 105.114 338.568 + vertex 583.525 107.194 335.253 + vertex 583.057 109.429 338.474 + endloop + endfacet + facet normal 0.21854 -0.786543 0.577572 + outer loop + vertex 583.057 109.429 338.474 + vertex 583.525 107.194 335.253 + vertex 594.124 110.258 335.416 + endloop + endfacet + facet normal 0.22063 -0.77876 0.587244 + outer loop + vertex 594.124 110.258 335.416 + vertex 593.735 112.539 338.586 + vertex 583.057 109.429 338.474 + endloop + endfacet + facet normal 0.210552 -0.745771 0.632055 + outer loop + vertex 582.921 112.066 341.631 + vertex 583.057 109.429 338.474 + vertex 593.735 112.539 338.586 + endloop + endfacet + facet normal 0.21183 -0.740882 0.637356 + outer loop + vertex 593.735 112.539 338.586 + vertex 593.624 115.146 341.654 + vertex 582.921 112.066 341.631 + endloop + endfacet + facet normal 0.207584 -0.741652 0.637856 + outer loop + vertex 593.735 112.539 338.586 + vertex 599.106 114.495 339.113 + vertex 593.624 115.146 341.654 + endloop + endfacet + facet normal 0.211521 -0.734705 0.644567 + outer loop + vertex 593.624 115.146 341.654 + vertex 599.106 114.495 339.113 + vertex 599.12 117.154 342.139 + endloop + endfacet + facet normal 0.200004 -0.736498 0.646196 + outer loop + vertex 599.12 117.154 342.139 + vertex 599.106 114.495 339.113 + vertex 601.13 115.836 340.015 + endloop + endfacet + facet normal 0.212409 -0.745423 0.631845 + outer loop + vertex 567.16 107.635 341.701 + vertex 583.057 109.429 338.474 + vertex 582.921 112.066 341.631 + endloop + endfacet + facet normal 0.211595 -0.752154 0.624092 + outer loop + vertex 567.441 105.114 338.568 + vertex 583.057 109.429 338.474 + vertex 567.16 107.635 341.701 + endloop + endfacet + facet normal 0.211289 -0.75222 0.624117 + outer loop + vertex 548.66 102.627 341.928 + vertex 567.441 105.114 338.568 + vertex 567.16 107.635 341.701 + endloop + endfacet + facet normal 0.211045 -0.755293 0.620478 + outer loop + vertex 548.886 100.111 338.789 + vertex 567.441 105.114 338.568 + vertex 548.66 102.627 341.928 + endloop + endfacet + facet normal 0.211362 -0.755228 0.620449 + outer loop + vertex 530.653 97.8156 342.206 + vertex 548.886 100.111 338.789 + vertex 548.66 102.627 341.928 + endloop + endfacet + facet normal 0.211411 -0.754712 0.621059 + outer loop + vertex 530.743 95.2495 339.058 + vertex 548.886 100.111 338.789 + vertex 530.653 97.8156 342.206 + endloop + endfacet + facet normal 0.21325 -0.754377 0.620838 + outer loop + vertex 516.134 93.8578 342.385 + vertex 530.743 95.2495 339.058 + vertex 530.653 97.8156 342.206 + endloop + endfacet + facet normal 0.213457 -0.753139 0.622268 + outer loop + vertex 516.061 91.2138 339.21 + vertex 530.743 95.2495 339.058 + vertex 516.134 93.8578 342.385 + endloop + endfacet + facet normal 0.218768 -0.752295 0.621444 + outer loop + vertex 506.252 90.914 342.3 + vertex 516.061 91.2138 339.21 + vertex 516.134 93.8578 342.385 + endloop + endfacet + facet normal 0.217576 -0.756046 0.617297 + outer loop + vertex 506.823 88.3227 338.925 + vertex 516.061 91.2138 339.21 + vertex 506.252 90.914 342.3 + endloop + endfacet + facet normal 0.241026 -0.749665 0.616367 + outer loop + vertex 506.823 88.3227 338.925 + vertex 506.252 90.914 342.3 + vertex 502.722 88.6288 340.9 + endloop + endfacet + facet normal 0.222477 -0.735475 0.639984 + outer loop + vertex 501.961 90.1975 342.968 + vertex 502.722 88.6288 340.9 + vertex 506.252 90.914 342.3 + endloop + endfacet + facet normal 0.209927 -0.740109 0.638881 + outer loop + vertex 502.722 88.6288 340.9 + vertex 501.961 90.1975 342.968 + vertex 500.543 88.2545 341.183 + endloop + endfacet + facet normal 0.215922 -0.779897 0.587484 + outer loop + vertex 594.124 110.258 335.416 + vertex 599.601 112.22 336.008 + vertex 593.735 112.539 338.586 + endloop + endfacet + facet normal 0.221539 -0.769508 0.59898 + outer loop + vertex 593.735 112.539 338.586 + vertex 599.601 112.22 336.008 + vertex 599.106 114.495 339.113 + endloop + endfacet + facet normal 0.226631 -0.812386 0.537278 + outer loop + vertex 594.67 108.254 332.156 + vertex 594.124 110.258 335.416 + vertex 583.525 107.194 335.253 + endloop + endfacet + facet normal 0.219484 -0.814342 0.537283 + outer loop + vertex 594.67 108.254 332.156 + vertex 600.25 110.138 332.731 + vertex 594.124 110.258 335.416 + endloop + endfacet + facet normal 0.227078 -0.800937 0.554017 + outer loop + vertex 594.124 110.258 335.416 + vertex 600.25 110.138 332.731 + vertex 599.601 112.22 336.008 + endloop + endfacet + facet normal 0.223605 -0.822534 0.522913 + outer loop + vertex 583.525 107.194 335.253 + vertex 583.915 105.179 331.917 + vertex 594.67 108.254 332.156 + endloop + endfacet + facet normal 0.2305 -0.843685 0.484835 + outer loop + vertex 595.331 106.499 328.787 + vertex 594.67 108.254 332.156 + vertex 583.915 105.179 331.917 + endloop + endfacet + facet normal 0.220302 -0.846663 0.484384 + outer loop + vertex 595.331 106.499 328.787 + vertex 600.982 108.361 329.471 + vertex 594.67 108.254 332.156 + endloop + endfacet + facet normal 0.228842 -0.832209 0.505034 + outer loop + vertex 594.67 108.254 332.156 + vertex 600.982 108.361 329.471 + vertex 600.25 110.138 332.731 + endloop + endfacet + facet normal 0.227779 -0.851999 0.471396 + outer loop + vertex 583.915 105.179 331.917 + vertex 584.191 103.359 328.494 + vertex 595.331 106.499 328.787 + endloop + endfacet + facet normal 0.233949 -0.870335 0.433342 + outer loop + vertex 596.316 104.955 325.153 + vertex 595.331 106.499 328.787 + vertex 584.191 103.359 328.494 + endloop + endfacet + facet normal 0.22399 -0.8736 0.432032 + outer loop + vertex 596.316 104.955 325.153 + vertex 601.869 106.878 326.163 + vertex 595.331 106.499 328.787 + endloop + endfacet + facet normal 0.230144 -0.863478 0.44882 + outer loop + vertex 595.331 106.499 328.787 + vertex 601.869 106.878 326.163 + vertex 600.982 108.361 329.471 + endloop + endfacet + facet normal 0.232418 -0.874446 0.425825 + outer loop + vertex 584.191 103.359 328.494 + vertex 583.938 101.761 325.35 + vertex 596.316 104.955 325.153 + endloop + endfacet + facet normal 0.235486 -0.888272 0.39436 + outer loop + vertex 596.316 104.955 325.153 + vertex 583.938 101.761 325.35 + vertex 593.822 103.406 323.155 + endloop + endfacet + facet normal 0.234519 -0.888063 0.395406 + outer loop + vertex 600.103 104.732 322.407 + vertex 596.316 104.955 325.153 + vertex 593.822 103.406 323.155 + endloop + endfacet + facet normal 0.237177 -0.885797 0.398888 + outer loop + vertex 600.103 104.732 322.407 + vertex 603.354 105.64 322.491 + vertex 596.316 104.955 325.153 + endloop + endfacet + facet normal 0.235794 -0.888062 0.394648 + outer loop + vertex 596.316 104.955 325.153 + vertex 603.354 105.64 322.491 + vertex 601.869 106.878 326.163 + endloop + endfacet + facet normal 0.242044 -0.899909 0.362737 + outer loop + vertex 600.103 104.732 322.407 + vertex 602.495 104.712 320.761 + vertex 603.354 105.64 322.491 + endloop + endfacet + facet normal 0.234598 -0.906125 0.351995 + outer loop + vertex 602.495 104.712 320.761 + vertex 600.103 104.732 322.407 + vertex 596.211 103.145 320.915 + endloop + endfacet + facet normal 0.236384 -0.916046 0.324011 + outer loop + vertex 601.523 103.96 319.344 + vertex 602.495 104.712 320.761 + vertex 596.211 103.145 320.915 + endloop + endfacet + facet normal 0.234081 -0.920065 0.314143 + outer loop + vertex 596.211 103.145 320.915 + vertex 596.074 102.365 318.733 + vertex 601.523 103.96 319.344 + endloop + endfacet + facet normal 0.240072 -0.928597 0.282973 + outer loop + vertex 601.958 103.511 317.5 + vertex 601.523 103.96 319.344 + vertex 596.074 102.365 318.733 + endloop + endfacet + facet normal 0.238173 -0.932987 0.26983 + outer loop + vertex 596.074 102.365 318.733 + vertex 595.99 101.797 316.844 + vertex 601.958 103.511 317.5 + endloop + endfacet + facet normal 0.241135 -0.936902 0.253117 + outer loop + vertex 601.912 102.96 315.508 + vertex 601.958 103.511 317.5 + vertex 595.99 101.797 316.844 + endloop + endfacet + facet normal 0.23835 -0.941978 0.23636 + outer loop + vertex 595.99 101.797 316.844 + vertex 595.439 101.212 315.068 + vertex 601.912 102.96 315.508 + endloop + endfacet + facet normal 0.240393 -0.945422 0.219975 + outer loop + vertex 601.912 102.96 315.508 + vertex 595.439 101.212 315.068 + vertex 601.572 102.432 313.609 + endloop + endfacet + facet normal 0.23432 -0.946614 0.221395 + outer loop + vertex 605.124 103.467 314.275 + vertex 601.912 102.96 315.508 + vertex 601.572 102.432 313.609 + endloop + endfacet + facet normal 0.235251 -0.947291 0.21748 + outer loop + vertex 601.572 102.432 313.609 + vertex 605.648 103.395 313.392 + vertex 605.124 103.467 314.275 + endloop + endfacet + facet normal 0.247554 -0.942531 0.224393 + outer loop + vertex 605.648 103.395 313.392 + vertex 606.851 103.672 313.232 + vertex 605.124 103.467 314.275 + endloop + endfacet + facet normal 0.244651 -0.951333 0.18738 + outer loop + vertex 605.648 103.395 313.392 + vertex 605.503 103.18 312.492 + vertex 606.851 103.672 313.232 + endloop + endfacet + facet normal 0.245893 -0.951442 0.185188 + outer loop + vertex 607.185 103.404 311.408 + vertex 606.851 103.672 313.232 + vertex 605.503 103.18 312.492 + endloop + endfacet + facet normal 0.241419 -0.954009 0.177719 + outer loop + vertex 605.198 102.915 311.482 + vertex 607.185 103.404 311.408 + vertex 605.503 103.18 312.492 + endloop + endfacet + facet normal 0.238136 -0.954619 0.17887 + outer loop + vertex 601.849 102.18 312.017 + vertex 605.198 102.915 311.482 + vertex 605.503 103.18 312.492 + endloop + endfacet + facet normal 0.235847 -0.952592 0.192209 + outer loop + vertex 601.849 102.18 312.017 + vertex 605.503 103.18 312.492 + vertex 601.572 102.432 313.609 + endloop + endfacet + facet normal 0.240102 -0.951416 0.192765 + outer loop + vertex 595.38 100.644 312.496 + vertex 601.849 102.18 312.017 + vertex 601.572 102.432 313.609 + endloop + endfacet + facet normal 0.240082 -0.951403 0.192854 + outer loop + vertex 593.984 100.539 313.714 + vertex 595.38 100.644 312.496 + vertex 601.572 102.432 313.609 + endloop + endfacet + facet normal 0.242482 -0.950211 0.195708 + outer loop + vertex 585.591 98.2756 313.125 + vertex 595.38 100.644 312.496 + vertex 593.984 100.539 313.714 + endloop + endfacet + facet normal 0.241658 -0.948964 0.202655 + outer loop + vertex 585.591 98.2756 313.125 + vertex 593.984 100.539 313.714 + vertex 587.435 99.0517 314.561 + endloop + endfacet + facet normal 0.243469 -0.948992 0.200344 + outer loop + vertex 587.435 99.0517 314.561 + vertex 572.066 95.2203 315.089 + vertex 585.591 98.2756 313.125 + endloop + endfacet + facet normal 0.243167 -0.949752 0.197079 + outer loop + vertex 572.066 95.2203 315.089 + vertex 572.576 94.7102 312.002 + vertex 585.591 98.2756 313.125 + endloop + endfacet + facet normal 0.244569 -0.951532 0.186476 + outer loop + vertex 588.196 98.6699 311.721 + vertex 585.591 98.2756 313.125 + vertex 572.576 94.7102 312.002 + endloop + endfacet + facet normal 0.245252 -0.95606 0.160628 + outer loop + vertex 588.196 98.6699 311.721 + vertex 572.576 94.7102 312.002 + vertex 588.448 98.5161 310.421 + endloop + endfacet + facet normal 0.242593 -0.956809 0.160201 + outer loop + vertex 588.196 98.6699 311.721 + vertex 588.448 98.5161 310.421 + vertex 596.265 100.642 311.281 + endloop + endfacet + facet normal 0.242784 -0.953544 0.17835 + outer loop + vertex 595.38 100.644 312.496 + vertex 588.196 98.6699 311.721 + vertex 596.265 100.642 311.281 + endloop + endfacet + facet normal 0.242564 -0.956784 0.160398 + outer loop + vertex 597.82 100.909 310.519 + vertex 596.265 100.642 311.281 + vertex 588.448 98.5161 310.421 + endloop + endfacet + facet normal 0.243894 -0.960824 0.131659 + outer loop + vertex 597.82 100.909 310.519 + vertex 588.448 98.5161 310.421 + vertex 597.23 100.667 309.846 + endloop + endfacet + facet normal 0.24152 -0.961121 0.133847 + outer loop + vertex 597.23 100.667 309.846 + vertex 602.364 102.018 310.283 + vertex 597.82 100.909 310.519 + endloop + endfacet + facet normal 0.241708 -0.959295 0.146048 + outer loop + vertex 597.82 100.909 310.519 + vertex 602.364 102.018 310.283 + vertex 602.2 102.087 311.008 + endloop + endfacet + facet normal 0.239298 -0.959972 0.145567 + outer loop + vertex 602.364 102.018 310.283 + vertex 605.584 102.878 310.665 + vertex 602.2 102.087 311.008 + endloop + endfacet + facet normal 0.239945 -0.958136 0.156212 + outer loop + vertex 602.2 102.087 311.008 + vertex 605.584 102.878 310.665 + vertex 605.198 102.915 311.482 + endloop + endfacet + facet normal 0.241112 -0.961301 0.133287 + outer loop + vertex 602.364 102.018 310.283 + vertex 605.342 102.723 309.987 + vertex 605.584 102.878 310.665 + endloop + endfacet + facet normal 0.240785 -0.961365 0.133418 + outer loop + vertex 605.342 102.723 309.987 + vertex 607.479 103.252 309.939 + vertex 605.584 102.878 310.665 + endloop + endfacet + facet normal 0.245742 -0.957955 0.1481 + outer loop + vertex 607.479 103.252 309.939 + vertex 607.185 103.404 311.408 + vertex 605.584 102.878 310.665 + endloop + endfacet + facet normal 0.241228 -0.95922 0.147327 + outer loop + vertex 607.479 103.252 309.939 + vertex 608.188 103.515 310.49 + vertex 607.185 103.404 311.408 + endloop + endfacet + facet normal 0.256341 -0.952457 0.164666 + outer loop + vertex 607.185 103.404 311.408 + vertex 608.188 103.515 310.49 + vertex 607.648 103.643 312.069 + endloop + endfacet + facet normal 0.332351 -0.924145 0.188411 + outer loop + vertex 607.648 103.643 312.069 + vertex 608.188 103.515 310.49 + vertex 607.874 103.745 312.174 + endloop + endfacet + facet normal 0.240234 -0.963314 0.119644 + outer loop + vertex 602.557 101.985 309.633 + vertex 605.342 102.723 309.987 + vertex 602.364 102.018 310.283 + endloop + endfacet + facet normal 0.240358 -0.958163 0.155412 + outer loop + vertex 597.82 100.909 310.519 + vertex 602.2 102.087 311.008 + vertex 596.265 100.642 311.281 + endloop + endfacet + facet normal 0.240425 -0.955383 0.171578 + outer loop + vertex 596.265 100.642 311.281 + vertex 602.2 102.087 311.008 + vertex 601.849 102.18 312.017 + endloop + endfacet + facet normal 0.244876 -0.957246 0.154001 + outer loop + vertex 572.576 94.7102 312.002 + vertex 573.186 94.4458 309.388 + vertex 588.448 98.5161 310.421 + endloop + endfacet + facet normal 0.246909 -0.959751 0.133843 + outer loop + vertex 590.873 98.9622 309.147 + vertex 588.448 98.5161 310.421 + vertex 573.186 94.4458 309.388 + endloop + endfacet + facet normal 0.248127 -0.948347 0.197665 + outer loop + vertex 549.117 89.09 314.486 + vertex 572.576 94.7102 312.002 + vertex 572.066 95.2203 315.089 + endloop + endfacet + facet normal 0.24551 -0.941726 0.22995 + outer loop + vertex 549.117 89.09 314.486 + vertex 572.066 95.2203 315.089 + vertex 549.041 89.9161 317.95 + endloop + endfacet + facet normal 0.250899 -0.940356 0.229741 + outer loop + vertex 526.344 83.8082 317.737 + vertex 549.117 89.09 314.486 + vertex 549.041 89.9161 317.95 + endloop + endfacet + facet normal 0.24769 -0.929899 0.271913 + outer loop + vertex 526.344 83.8082 317.737 + vertex 549.041 89.9161 317.95 + vertex 526.991 85.0822 321.505 + endloop + endfacet + facet normal 0.255639 -0.928302 0.270008 + outer loop + vertex 526.344 83.8082 317.737 + vertex 526.991 85.0822 321.505 + vertex 513.964 81.296 320.821 + endloop + endfacet + facet normal 0.25504 -0.929426 0.266687 + outer loop + vertex 511.452 80.1155 319.109 + vertex 526.344 83.8082 317.737 + vertex 513.964 81.296 320.821 + endloop + endfacet + facet normal 0.254142 -0.939403 0.230073 + outer loop + vertex 511.452 80.1155 319.109 + vertex 512.898 80.0189 317.118 + vertex 526.344 83.8082 317.737 + endloop + endfacet + facet normal 0.255918 -0.942926 0.213066 + outer loop + vertex 526.088 82.95 314.247 + vertex 526.344 83.8082 317.737 + vertex 512.898 80.0189 317.118 + endloop + endfacet + facet normal 0.254358 -0.945508 0.203263 + outer loop + vertex 510.808 79.1203 315.553 + vertex 526.088 82.95 314.247 + vertex 512.898 80.0189 317.118 + endloop + endfacet + facet normal 0.253944 -0.945501 0.203813 + outer loop + vertex 503.87 77.6451 317.354 + vertex 510.808 79.1203 315.553 + vertex 512.898 80.0189 317.118 + endloop + endfacet + facet normal 0.25345 -0.942025 0.21989 + outer loop + vertex 503.87 77.6451 317.354 + vertex 512.898 80.0189 317.118 + vertex 504.387 78.1855 319.073 + endloop + endfacet + facet normal 0.255302 -0.938888 0.230891 + outer loop + vertex 504.387 78.1855 319.073 + vertex 512.898 80.0189 317.118 + vertex 511.452 80.1155 319.109 + endloop + endfacet + facet normal 0.253334 -0.932194 0.258526 + outer loop + vertex 504.387 78.1855 319.073 + vertex 511.452 80.1155 319.109 + vertex 505.017 78.8753 320.943 + endloop + endfacet + facet normal 0.248628 -0.926551 0.28229 + outer loop + vertex 526.991 85.0822 321.505 + vertex 549.041 89.9161 317.95 + vertex 548.938 90.9795 321.531 + endloop + endfacet + facet normal 0.242747 -0.928027 0.28256 + outer loop + vertex 549.041 89.9161 317.95 + vertex 571.685 96.0096 318.509 + vertex 548.938 90.9795 321.531 + endloop + endfacet + facet normal 0.249583 -0.944433 0.213901 + outer loop + vertex 526.088 82.95 314.247 + vertex 549.117 89.09 314.486 + vertex 526.344 83.8082 317.737 + endloop + endfacet + facet normal 0.246381 -0.937983 0.243896 + outer loop + vertex 549.041 89.9161 317.95 + vertex 572.066 95.2203 315.089 + vertex 571.685 96.0096 318.509 + endloop + endfacet + facet normal 0.24043 -0.9396 0.243607 + outer loop + vertex 571.685 96.0096 318.509 + vertex 572.066 95.2203 315.089 + vertex 585.972 99.0826 316.262 + endloop + endfacet + facet normal 0.241042 -0.937758 0.250018 + outer loop + vertex 588.027 100.072 317.99 + vertex 571.685 96.0096 318.509 + vertex 585.972 99.0826 316.262 + endloop + endfacet + facet normal 0.239444 -0.937671 0.251871 + outer loop + vertex 585.972 99.0826 316.262 + vertex 595.99 101.797 316.844 + vertex 588.027 100.072 317.99 + endloop + endfacet + facet normal 0.239437 -0.92591 0.292166 + outer loop + vertex 588.027 100.072 317.99 + vertex 585.239 99.9793 319.982 + vertex 571.685 96.0096 318.509 + endloop + endfacet + facet normal 0.238279 -0.924241 0.29833 + outer loop + vertex 568.414 96.2788 321.957 + vertex 571.685 96.0096 318.509 + vertex 585.239 99.9793 319.982 + endloop + endfacet + facet normal 0.237537 -0.927253 0.289444 + outer loop + vertex 588.027 100.072 317.99 + vertex 596.074 102.365 318.733 + vertex 585.239 99.9793 319.982 + endloop + endfacet + facet normal 0.247311 -0.951557 0.18269 + outer loop + vertex 549.26 88.534 311.396 + vertex 572.576 94.7102 312.002 + vertex 549.117 89.09 314.486 + endloop + endfacet + facet normal 0.242942 -0.943325 0.226092 + outer loop + vertex 587.435 99.0517 314.561 + vertex 585.972 99.0826 316.262 + vertex 572.066 95.2203 315.089 + endloop + endfacet + facet normal 0.240695 -0.944357 0.224177 + outer loop + vertex 587.435 99.0517 314.561 + vertex 595.439 101.212 315.068 + vertex 585.972 99.0826 316.262 + endloop + endfacet + facet normal 0.242269 -0.947038 0.21077 + outer loop + vertex 587.435 99.0517 314.561 + vertex 593.984 100.539 313.714 + vertex 595.439 101.212 315.068 + endloop + endfacet + facet normal 0.24227 -0.953025 0.181791 + outer loop + vertex 588.196 98.6699 311.721 + vertex 595.38 100.644 312.496 + vertex 585.591 98.2756 313.125 + endloop + endfacet + facet normal 0.239659 -0.954756 0.176079 + outer loop + vertex 596.265 100.642 311.281 + vertex 601.849 102.18 312.017 + vertex 595.38 100.644 312.496 + endloop + endfacet + facet normal 0.237192 -0.956376 0.170545 + outer loop + vertex 602.2 102.087 311.008 + vertex 605.198 102.915 311.482 + vertex 601.849 102.18 312.017 + endloop + endfacet + facet normal 0.241534 -0.957618 0.156939 + outer loop + vertex 605.198 102.915 311.482 + vertex 605.584 102.878 310.665 + vertex 607.185 103.404 311.408 + endloop + endfacet + facet normal 0.231476 -0.955447 0.183138 + outer loop + vertex 607.185 103.404 311.408 + vertex 607.648 103.643 312.069 + vertex 606.851 103.672 313.232 + endloop + endfacet + facet normal 0.279264 -0.935753 0.215356 + outer loop + vertex 606.851 103.672 313.232 + vertex 607.648 103.643 312.069 + vertex 607.09 103.858 313.728 + endloop + endfacet + facet normal 0.246227 -0.940754 0.23314 + outer loop + vertex 607.09 103.858 313.728 + vertex 605.515 103.906 315.586 + vertex 606.851 103.672 313.232 + endloop + endfacet + facet normal 0.263189 -0.932507 0.247311 + outer loop + vertex 605.515 103.906 315.586 + vertex 607.09 103.858 313.728 + vertex 606.667 104.374 316.126 + endloop + endfacet + facet normal 0.386022 -0.885421 0.258875 + outer loop + vertex 607.874 103.745 312.174 + vertex 606.667 104.374 316.126 + vertex 607.09 103.858 313.728 + endloop + endfacet + facet normal 0.314292 -0.922189 0.225362 + outer loop + vertex 607.09 103.858 313.728 + vertex 607.648 103.643 312.069 + vertex 607.874 103.745 312.174 + endloop + endfacet + facet normal 0.235182 -0.953323 0.189379 + outer loop + vertex 601.572 102.432 313.609 + vertex 605.503 103.18 312.492 + vertex 605.648 103.395 313.392 + endloop + endfacet + facet normal 0.241367 -0.939612 0.242634 + outer loop + vertex 601.912 102.96 315.508 + vertex 605.124 103.467 314.275 + vertex 605.515 103.906 315.586 + endloop + endfacet + facet normal 0.239296 -0.947074 0.213983 + outer loop + vertex 595.439 101.212 315.068 + vertex 593.984 100.539 313.714 + vertex 601.572 102.432 313.609 + endloop + endfacet + facet normal 0.241441 -0.941473 0.235235 + outer loop + vertex 585.972 99.0826 316.262 + vertex 595.439 101.212 315.068 + vertex 595.99 101.797 316.844 + endloop + endfacet + facet normal 0.240468 -0.937058 0.253176 + outer loop + vertex 601.912 102.96 315.508 + vertex 605.515 103.906 315.586 + vertex 601.958 103.511 317.5 + endloop + endfacet + facet normal 0.24084 -0.932389 0.269532 + outer loop + vertex 588.027 100.072 317.99 + vertex 595.99 101.797 316.844 + vertex 596.074 102.365 318.733 + endloop + endfacet + facet normal 0.24731 -0.926341 0.284131 + outer loop + vertex 601.523 103.96 319.344 + vertex 601.958 103.511 317.5 + vertex 604.698 104.655 318.848 + endloop + endfacet + facet normal 0.238526 -0.919133 0.31353 + outer loop + vertex 585.239 99.9793 319.982 + vertex 596.074 102.365 318.733 + vertex 596.211 103.145 320.915 + endloop + endfacet + facet normal 0.235364 -0.913539 0.331737 + outer loop + vertex 585.239 99.9793 319.982 + vertex 596.211 103.145 320.915 + vertex 583.964 100.597 322.588 + endloop + endfacet + facet normal 0.236799 -0.903186 0.358023 + outer loop + vertex 583.964 100.597 322.588 + vertex 596.211 103.145 320.915 + vertex 593.822 103.406 323.155 + endloop + endfacet + facet normal 0.249762 -0.915749 0.314677 + outer loop + vertex 601.523 103.96 319.344 + vertex 604.698 104.655 318.848 + vertex 602.495 104.712 320.761 + endloop + endfacet + facet normal 0.233327 -0.905444 0.354583 + outer loop + vertex 593.822 103.406 323.155 + vertex 596.211 103.145 320.915 + vertex 600.103 104.732 322.407 + endloop + endfacet + facet normal 0.233334 -0.895341 0.379368 + outer loop + vertex 583.938 101.761 325.35 + vertex 583.964 100.597 322.588 + vertex 593.822 103.406 323.155 + endloop + endfacet + facet normal 0.239662 -0.911804 0.33343 + outer loop + vertex 583.964 100.597 322.588 + vertex 568.414 96.2788 321.957 + vertex 585.239 99.9793 319.982 + endloop + endfacet + facet normal 0.243989 -0.921063 0.303502 + outer loop + vertex 548.938 90.9795 321.531 + vertex 571.685 96.0096 318.509 + vertex 568.414 96.2788 321.957 + endloop + endfacet + facet normal 0.252512 -0.921865 0.293943 + outer loop + vertex 513.937 81.8809 322.679 + vertex 513.964 81.296 320.821 + vertex 526.991 85.0822 321.505 + endloop + endfacet + facet normal 0.255103 -0.929433 0.266601 + outer loop + vertex 505.017 78.8753 320.943 + vertex 511.452 80.1155 319.109 + vertex 513.964 81.296 320.821 + endloop + endfacet + facet normal 0.252845 -0.932273 0.25872 + outer loop + vertex 500.344 77.4839 320.497 + vertex 504.387 78.1855 319.073 + vertex 505.017 78.8753 320.943 + endloop + endfacet + facet normal 0.248886 -0.936995 0.245146 + outer loop + vertex 499.814 76.9583 319.025 + vertex 504.387 78.1855 319.073 + vertex 500.344 77.4839 320.497 + endloop + endfacet + facet normal 0.250631 -0.942543 0.2209 + outer loop + vertex 499.814 76.9583 319.025 + vertex 503.87 77.6451 317.354 + vertex 504.387 78.1855 319.073 + endloop + endfacet + facet normal 0.250931 -0.949367 0.189041 + outer loop + vertex 503.381 77.1612 315.573 + vertex 510.808 79.1203 315.553 + vertex 503.87 77.6451 317.354 + endloop + endfacet + facet normal 0.241106 -0.958963 0.149193 + outer loop + vertex 496.957 75.1737 313.402 + vertex 502.676 76.6652 313.746 + vertex 498.346 75.8186 315.302 + endloop + endfacet + facet normal 0.251705 -0.952486 0.17151 + outer loop + vertex 503.381 77.1612 315.573 + vertex 512.237 79.1574 313.661 + vertex 510.808 79.1203 315.553 + endloop + endfacet + facet normal 0.247922 -0.959055 0.136924 + outer loop + vertex 502.028 76.243 311.963 + vertex 509.943 78.312 312.122 + vertex 502.676 76.6652 313.746 + endloop + endfacet + facet normal 0.251505 -0.959943 0.123511 + outer loop + vertex 509.943 78.312 312.122 + vertex 511.546 78.5108 310.405 + vertex 525.807 82.3364 311.098 + endloop + endfacet + facet normal 0.253335 -0.951828 0.172755 + outer loop + vertex 510.808 79.1203 315.553 + vertex 512.237 79.1574 313.661 + vertex 526.088 82.95 314.247 + endloop + endfacet + facet normal 0.251513 -0.950456 0.182687 + outer loop + vertex 526.088 82.95 314.247 + vertex 549.26 88.534 311.396 + vertex 549.117 89.09 314.486 + endloop + endfacet + facet normal 0.249998 -0.960575 0.121646 + outer loop + vertex 525.835 82.0135 308.489 + vertex 549.063 88.1086 308.883 + vertex 525.807 82.3364 311.098 + endloop + endfacet + facet normal 0.249207 -0.955985 0.154885 + outer loop + vertex 549.26 88.534 311.396 + vertex 573.186 94.4458 309.388 + vertex 572.576 94.7102 312.002 + endloop + endfacet + facet normal 0.250037 -0.961304 0.115655 + outer loop + vertex 548.05 87.6428 307.201 + vertex 571.551 93.7941 307.524 + vertex 549.063 88.1086 308.883 + endloop + endfacet + facet normal 0.250566 -0.961899 0.109395 + outer loop + vertex 565.79 92.1924 306.636 + vertex 585.052 97.2375 306.878 + vertex 571.551 93.7941 307.524 + endloop + endfacet + facet normal 0.250382 -0.961417 0.113956 + outer loop + vertex 585.052 97.2375 306.878 + vertex 565.79 92.1924 306.636 + vertex 577.732 95.2909 306.537 + endloop + endfacet + facet normal 0.251482 -0.966653 -0.0483676 + outer loop + vertex 592.308 99.1246 306.889 + vertex 596.962 100.327 307.05 + vertex 585.052 97.2375 306.878 + endloop + endfacet + facet normal 0.248958 -0.958103 0.141627 + outer loop + vertex 592.308 99.1246 306.889 + vertex 585.052 97.2375 306.878 + vertex 588.676 98.1574 306.73 + endloop + endfacet + facet normal 0.24585 -0.964394 0.0974747 + outer loop + vertex 596.962 100.327 307.05 + vertex 592.308 99.1246 306.889 + vertex 596.27 100.141 306.95 + endloop + endfacet + facet normal 0.245588 -0.964296 0.0990976 + outer loop + vertex 600.024 101.114 307.12 + vertex 596.962 100.327 307.05 + vertex 596.27 100.141 306.95 + endloop + endfacet + facet normal 0.238256 -0.95214 0.191477 + outer loop + vertex 596.27 100.141 306.95 + vertex 601.473 101.463 307.048 + vertex 600.024 101.114 307.12 + endloop + endfacet + facet normal 0.24885 -0.953146 -0.172007 + outer loop + vertex 600.024 101.114 307.12 + vertex 603.097 101.893 307.249 + vertex 596.962 100.327 307.05 + endloop + endfacet + facet normal 0.237851 -0.961343 0.138732 + outer loop + vertex 603.097 101.893 307.249 + vertex 600.024 101.114 307.12 + vertex 601.473 101.463 307.048 + endloop + endfacet + facet normal 0.209978 -0.919843 0.331357 + outer loop + vertex 607.137 102.919 307.454 + vertex 606.395 102.727 307.391 + vertex 608.318 103.21 307.513 + endloop + endfacet + facet normal 0.241632 -0.96538 0.098264 + outer loop + vertex 603.025 101.889 307.441 + vertex 606.395 102.727 307.391 + vertex 607.137 102.919 307.454 + endloop + endfacet + facet normal 0.236013 -0.969553 0.0653024 + outer loop + vertex 607.601 103.043 307.569 + vertex 608.869 103.365 307.769 + vertex 606.738 102.854 307.893 + endloop + endfacet + facet normal 0.236614 -0.96821 0.0811348 + outer loop + vertex 606.738 102.854 307.893 + vertex 608.869 103.365 307.769 + vertex 608.589 103.333 308.208 + endloop + endfacet + facet normal 0.23588 -0.968041 0.0851963 + outer loop + vertex 606.738 102.854 307.893 + vertex 608.589 103.333 308.208 + vertex 606.329 102.811 308.537 + endloop + endfacet + facet normal 0.229277 -0.970366 0.0762975 + outer loop + vertex 609.318 103.499 308.133 + vertex 608.589 103.333 308.208 + vertex 608.869 103.365 307.769 + endloop + endfacet + facet normal 0.241877 -0.966205 0.0891283 + outer loop + vertex 606.329 102.811 308.537 + vertex 601.905 101.663 308.096 + vertex 606.738 102.854 307.893 + endloop + endfacet + facet normal 0.24536 -0.966004 0.0814572 + outer loop + vertex 596.057 100.128 307.55 + vertex 594.474 99.6896 307.118 + vertex 603.025 101.889 307.441 + endloop + endfacet + facet normal 0.247753 -0.964779 0.0884291 + outer loop + vertex 587.777 97.9737 307.243 + vertex 596.057 100.128 307.55 + vertex 588.169 98.1478 308.044 + endloop + endfacet + facet normal 0.244996 -0.965006 0.0934874 + outer loop + vertex 596.504 100.281 307.983 + vertex 601.905 101.663 308.096 + vertex 597.031 100.468 308.533 + endloop + endfacet + facet normal 0.244947 -0.965095 0.0926968 + outer loop + vertex 597.031 100.468 308.533 + vertex 601.905 101.663 308.096 + vertex 602.675 101.937 308.917 + endloop + endfacet + facet normal 0.247401 -0.963233 0.104757 + outer loop + vertex 590.873 98.9622 309.147 + vertex 573.186 94.4458 309.388 + vertex 588.169 98.1478 308.044 + endloop + endfacet + facet normal 0.243758 -0.961451 0.127254 + outer loop + vertex 588.448 98.5161 310.421 + vertex 590.873 98.9622 309.147 + vertex 597.23 100.667 309.846 + endloop + endfacet + facet normal 0.24303 -0.962514 0.120433 + outer loop + vertex 597.23 100.667 309.846 + vertex 602.557 101.985 309.633 + vertex 602.364 102.018 310.283 + endloop + endfacet + facet normal 0.243821 -0.964079 0.105368 + outer loop + vertex 597.031 100.468 308.533 + vertex 602.675 101.937 308.917 + vertex 598.586 100.936 309.219 + endloop + endfacet + facet normal 0.241205 -0.963857 0.113141 + outer loop + vertex 602.557 101.985 309.633 + vertex 605.985 102.807 309.327 + vertex 605.342 102.723 309.987 + endloop + endfacet + facet normal 0.241002 -0.965705 0.0966 + outer loop + vertex 601.905 101.663 308.096 + vertex 606.329 102.811 308.537 + vertex 602.675 101.937 308.917 + endloop + endfacet + facet normal 0.236908 -0.96698 0.0939418 + outer loop + vertex 606.329 102.811 308.537 + vertex 608.589 103.333 308.208 + vertex 608.151 103.292 308.888 + endloop + endfacet + facet normal 0.240957 -0.963948 0.112887 + outer loop + vertex 605.342 102.723 309.987 + vertex 605.985 102.807 309.327 + vertex 607.479 103.252 309.939 + endloop + endfacet + facet normal 0.246446 -0.958922 0.140475 + outer loop + vertex 607.479 103.252 309.939 + vertex 608.688 103.46 309.237 + vertex 608.188 103.515 310.49 + endloop + endfacet + facet normal 0.228045 -0.96966 0.088065 + outer loop + vertex 608.589 103.333 308.208 + vertex 609.097 103.484 308.554 + vertex 608.151 103.292 308.888 + endloop + endfacet + facet normal 0.229981 -0.969464 0.0851379 + outer loop + vertex 609.097 103.484 308.554 + vertex 608.589 103.333 308.208 + vertex 609.318 103.499 308.133 + endloop + endfacet + facet normal 0.223526 -0.971101 0.083663 + outer loop + vertex 608.869 103.365 307.769 + vertex 609.125 103.421 307.742 + vertex 609.318 103.499 308.133 + endloop + endfacet + facet normal 0.22592 -0.963962 0.140489 + outer loop + vertex 612.181 104.378 310.058 + vertex 611.062 104.249 310.968 + vertex 610.388 103.898 309.642 + endloop + endfacet + facet normal 0.230639 -0.961936 0.146579 + outer loop + vertex 612.181 104.378 310.058 + vertex 614.144 105.094 311.669 + vertex 611.062 104.249 310.968 + endloop + endfacet + facet normal 0.222224 -0.962275 0.156984 + outer loop + vertex 614.715 105.052 310.603 + vertex 614.144 105.094 311.669 + vertex 612.181 104.378 310.058 + endloop + endfacet + facet normal 0.223808 -0.961772 0.157812 + outer loop + vertex 614.715 105.052 310.603 + vertex 617.854 106.105 312.568 + vertex 614.144 105.094 311.669 + endloop + endfacet + facet normal 0.206486 -0.960808 0.184962 + outer loop + vertex 617.674 105.859 311.492 + vertex 617.854 106.105 312.568 + vertex 614.715 105.052 310.603 + endloop + endfacet + facet normal 0.209649 -0.96025 0.184304 + outer loop + vertex 617.674 105.859 311.492 + vertex 621.328 106.98 313.174 + vertex 617.854 106.105 312.568 + endloop + endfacet + facet normal 0.204714 -0.952299 0.226317 + outer loop + vertex 627.199 108.742 315.277 + vertex 622.084 107.641 315.272 + vertex 621.328 106.98 313.174 + endloop + endfacet + facet normal 0.193835 -0.939373 0.282852 + outer loop + vertex 627.199 108.742 315.277 + vertex 626.151 108.218 314.254 + vertex 628.142 108.767 314.714 + endloop + endfacet + facet normal 0.197911 -0.936399 0.289808 + outer loop + vertex 628.142 108.767 314.714 + vertex 631.24 109.737 315.733 + vertex 627.199 108.742 315.277 + endloop + endfacet + facet normal 0.216787 -0.945891 0.24144 + outer loop + vertex 631.24 109.737 315.733 + vertex 628.142 108.767 314.714 + vertex 632.589 109.984 315.488 + endloop + endfacet + facet normal 0.218142 -0.942819 0.252003 + outer loop + vertex 634.425 110.639 316.35 + vertex 631.24 109.737 315.733 + vertex 632.589 109.984 315.488 + endloop + endfacet + facet normal 0.182103 -0.946959 0.264778 + outer loop + vertex 624.865 107.771 313.534 + vertex 625.834 108.064 313.915 + vertex 623.668 107.491 313.356 + endloop + endfacet + facet normal 0.18839 -0.953941 0.233463 + outer loop + vertex 623.563 107.394 313.046 + vertex 624.865 107.771 313.534 + vertex 623.668 107.491 313.356 + endloop + endfacet + facet normal 0.176654 -0.952283 0.2489 + outer loop + vertex 620.077 106.414 311.826 + vertex 621.514 106.826 312.383 + vertex 619.26 106.228 311.696 + endloop + endfacet + facet normal 0.183615 -0.9592 0.214991 + outer loop + vertex 618.617 105.999 311.222 + vertex 620.077 106.414 311.826 + vertex 619.26 106.228 311.696 + endloop + endfacet + facet normal 0.215544 -0.966281 0.140861 + outer loop + vertex 616.722 105.428 310.155 + vertex 621.849 106.708 311.087 + vertex 621.705 106.823 312.097 + endloop + endfacet + facet normal 0.225211 -0.969893 0.0926742 + outer loop + vertex 617.411 105.493 309.151 + vertex 621.849 106.708 311.087 + vertex 616.722 105.428 310.155 + endloop + endfacet + facet normal 0.222547 -0.969904 0.0987876 + outer loop + vertex 617.411 105.493 309.151 + vertex 623.421 106.94 309.821 + vertex 621.849 106.708 311.087 + endloop + endfacet + facet normal 0.222459 -0.969936 0.0986727 + outer loop + vertex 623.421 106.94 309.821 + vertex 628.336 108.275 311.862 + vertex 621.849 106.708 311.087 + endloop + endfacet + facet normal 0.221877 -0.969926 0.100068 + outer loop + vertex 623.421 106.94 309.821 + vertex 630.821 108.689 310.368 + vertex 628.336 108.275 311.862 + endloop + endfacet + facet normal 0.223583 -0.969216 0.103102 + outer loop + vertex 630.821 108.689 310.368 + vertex 635.931 110.076 312.328 + vertex 628.336 108.275 311.862 + endloop + endfacet + facet normal 0.227512 -0.96933 0.0929394 + outer loop + vertex 630.821 108.689 310.368 + vertex 638.939 110.628 310.721 + vertex 635.931 110.076 312.328 + endloop + endfacet + facet normal 0.230678 -0.967946 0.0993413 + outer loop + vertex 638.939 110.628 310.721 + vertex 643.898 111.984 312.416 + vertex 635.931 110.076 312.328 + endloop + endfacet + facet normal 0.239531 -0.968098 0.0735549 + outer loop + vertex 638.939 110.628 310.721 + vertex 646.937 112.619 310.874 + vertex 643.898 111.984 312.416 + endloop + endfacet + facet normal 0.243721 -0.966327 0.082541 + outer loop + vertex 646.937 112.619 310.874 + vertex 651.36 113.847 312.19 + vertex 643.898 111.984 312.416 + endloop + endfacet + facet normal 0.256666 -0.965733 0.0384975 + outer loop + vertex 646.937 112.619 310.874 + vertex 654.131 114.53 310.864 + vertex 651.36 113.847 312.19 + endloop + endfacet + facet normal 0.258949 -0.964902 0.0436964 + outer loop + vertex 654.131 114.53 310.864 + vertex 657.526 115.484 311.803 + vertex 651.36 113.847 312.19 + endloop + endfacet + facet normal 0.26091 -0.961042 0.0912405 + outer loop + vertex 651.36 113.847 312.19 + vertex 657.526 115.484 311.803 + vertex 655.273 114.997 313.114 + endloop + endfacet + facet normal 0.257748 -0.962441 0.0852873 + outer loop + vertex 657.526 115.484 311.803 + vertex 659.876 116.171 312.456 + vertex 655.273 114.997 313.114 + endloop + endfacet + facet normal 0.263523 -0.954452 0.139916 + outer loop + vertex 655.273 114.997 313.114 + vertex 659.876 116.171 312.456 + vertex 657.853 115.806 313.774 + endloop + endfacet + facet normal 0.24615 -0.962862 0.110935 + outer loop + vertex 659.876 116.171 312.456 + vertex 660.689 116.442 313.003 + vertex 657.853 115.806 313.774 + endloop + endfacet + facet normal 0.26218 -0.947605 0.182502 + outer loop + vertex 657.853 115.806 313.774 + vertex 660.689 116.442 313.003 + vertex 658.773 116.174 314.366 + endloop + endfacet + facet normal 0.205773 -0.964845 0.163499 + outer loop + vertex 615.144 105.034 309.898 + vertex 616.72 105.479 310.541 + vertex 615.315 105.12 310.196 + endloop + endfacet + facet normal 0.198391 -0.965624 0.167964 + outer loop + vertex 613.484 104.572 309.205 + vertex 615.144 105.034 309.898 + vertex 615.315 105.12 310.196 + endloop + endfacet + facet normal 0.2257 -0.969746 0.0930197 + outer loop + vertex 613.097 104.414 308.372 + vertex 617.411 105.493 309.151 + vertex 616.722 105.428 310.155 + endloop + endfacet + facet normal 0.234598 -0.971024 0.0455616 + outer loop + vertex 614.559 104.729 307.575 + vertex 617.411 105.493 309.151 + vertex 613.097 104.414 308.372 + endloop + endfacet + facet normal 0.232895 -0.971278 0.0487654 + outer loop + vertex 614.559 104.729 307.575 + vertex 619.633 105.96 307.859 + vertex 617.411 105.493 309.151 + endloop + endfacet + facet normal 0.229432 -0.972401 0.0424071 + outer loop + vertex 619.633 105.96 307.859 + vertex 623.421 106.94 309.821 + vertex 617.411 105.493 309.151 + endloop + endfacet + facet normal 0.229846 -0.972339 0.0415768 + outer loop + vertex 619.633 105.96 307.859 + vertex 626.494 107.598 308.237 + vertex 623.421 106.94 309.821 + endloop + endfacet + facet normal 0.227343 -0.973135 0.0363907 + outer loop + vertex 626.494 107.598 308.237 + vertex 630.821 108.689 310.368 + vertex 623.421 106.94 309.821 + endloop + endfacet + facet normal 0.231226 -0.972492 0.028177 + outer loop + vertex 626.494 107.598 308.237 + vertex 634.417 109.495 308.682 + vertex 630.821 108.689 310.368 + endloop + endfacet + facet normal 0.231102 -0.972529 0.0278959 + outer loop + vertex 634.417 109.495 308.682 + vertex 638.939 110.628 310.721 + vertex 630.821 108.689 310.368 + endloop + endfacet + facet normal 0.240015 -0.970743 0.0071413 + outer loop + vertex 634.417 109.495 308.682 + vertex 642.611 111.524 309.13 + vertex 638.939 110.628 310.721 + endloop + endfacet + facet normal 0.241308 -0.970394 0.010323 + outer loop + vertex 642.611 111.524 309.13 + vertex 646.937 112.619 310.874 + vertex 638.939 110.628 310.721 + endloop + endfacet + facet normal 0.255115 -0.966552 -0.0263482 + outer loop + vertex 642.611 111.524 309.13 + vertex 650.341 113.554 309.517 + vertex 646.937 112.619 310.874 + endloop + endfacet + facet normal 0.256722 -0.966233 -0.0220964 + outer loop + vertex 650.341 113.554 309.517 + vertex 654.131 114.53 310.864 + vertex 646.937 112.619 310.874 + endloop + endfacet + facet normal 0.221918 -0.970014 0.0991245 + outer loop + vertex 611.706 104.076 308.327 + vertex 613.484 104.572 309.205 + vertex 611.878 104.19 309.065 + endloop + endfacet + facet normal 0.175786 -0.978142 0.111078 + outer loop + vertex 610.266 103.666 307.004 + vertex 611.706 104.076 308.327 + vertex 611.878 104.19 309.065 + endloop + endfacet + facet normal 0.236526 -0.970371 0.0493582 + outer loop + vertex 612.061 104.111 307.385 + vertex 614.559 104.729 307.575 + vertex 613.097 104.414 308.372 + endloop + endfacet + facet normal 0.235695 -0.971827 0.00106147 + outer loop + vertex 617.367 105.409 306.247 + vertex 619.633 105.96 307.859 + vertex 614.559 104.729 307.575 + endloop + endfacet + facet normal 0.237926 -0.971281 -0.00226219 + outer loop + vertex 617.367 105.409 306.247 + vertex 623.314 106.866 306.227 + vertex 619.633 105.96 307.859 + endloop + endfacet + facet normal 0.232934 -0.97239 -0.0141378 + outer loop + vertex 623.314 106.866 306.227 + vertex 626.494 107.598 308.237 + vertex 619.633 105.96 307.859 + endloop + endfacet + facet normal 0.238763 -0.970783 -0.023942 + outer loop + vertex 623.314 106.866 306.227 + vertex 630.701 108.676 306.507 + vertex 626.494 107.598 308.237 + endloop + endfacet + facet normal 0.234514 -0.971493 -0.0347147 + outer loop + vertex 630.701 108.676 306.507 + vertex 634.417 109.495 308.682 + vertex 626.494 107.598 308.237 + endloop + endfacet + facet normal 0.245076 -0.967995 -0.0540775 + outer loop + vertex 630.701 108.676 306.507 + vertex 638.739 110.681 307.049 + vertex 634.417 109.495 308.682 + endloop + endfacet + facet normal 0.243035 -0.968184 -0.0596165 + outer loop + vertex 638.739 110.681 307.049 + vertex 642.611 111.524 309.13 + vertex 634.417 109.495 308.682 + endloop + endfacet + facet normal 0.257886 -0.961997 -0.0897556 + outer loop + vertex 638.739 110.681 307.049 + vertex 646.678 112.744 307.745 + vertex 642.611 111.524 309.13 + endloop + endfacet + facet normal 0.257196 -0.961991 -0.0917759 + outer loop + vertex 646.678 112.744 307.745 + vertex 650.341 113.554 309.517 + vertex 642.611 111.524 309.13 + endloop + endfacet + facet normal 0.273187 -0.953299 -0.128802 + outer loop + vertex 646.678 112.744 307.745 + vertex 653.844 114.703 308.443 + vertex 650.341 113.554 309.517 + endloop + endfacet + facet normal 0.273517 -0.953343 -0.127773 + outer loop + vertex 653.844 114.703 308.443 + vertex 656.991 115.424 309.803 + vertex 650.341 113.554 309.517 + endloop + endfacet + facet normal 0.24743 -0.968629 -0.0231489 + outer loop + vertex 616.597 105.241 305.043 + vertex 621.65 106.543 304.589 + vertex 617.367 105.409 306.247 + endloop + endfacet + facet normal 0.23748 -0.970111 -0.0498801 + outer loop + vertex 621.65 106.543 304.589 + vertex 623.314 106.866 306.227 + vertex 617.367 105.409 306.247 + endloop + endfacet + facet normal 0.246903 -0.967179 -0.060036 + outer loop + vertex 621.65 106.543 304.589 + vertex 628.066 108.186 304.493 + vertex 623.314 106.866 306.227 + endloop + endfacet + facet normal 0.240057 -0.967534 -0.0790678 + outer loop + vertex 628.066 108.186 304.493 + vertex 630.701 108.676 306.507 + vertex 623.314 106.866 306.227 + endloop + endfacet + facet normal 0.252633 -0.962718 -0.0966969 + outer loop + vertex 628.066 108.186 304.493 + vertex 635.552 110.114 304.864 + vertex 630.701 108.676 306.507 + endloop + endfacet + facet normal 0.247562 -0.962443 -0.111431 + outer loop + vertex 635.552 110.114 304.864 + vertex 638.739 110.681 307.049 + vertex 630.701 108.676 306.507 + endloop + endfacet + facet normal 0.264052 -0.954657 -0.137503 + outer loop + vertex 635.552 110.114 304.864 + vertex 643.4 112.17 305.656 + vertex 638.739 110.681 307.049 + endloop + endfacet + facet normal 0.260879 -0.954043 -0.147459 + outer loop + vertex 643.4 112.17 305.656 + vertex 646.678 112.744 307.745 + vertex 638.739 110.681 307.049 + endloop + endfacet + facet normal 0.277372 -0.944516 -0.17594 + outer loop + vertex 643.4 112.17 305.656 + vertex 650.798 114.155 306.667 + vertex 646.678 112.744 307.745 + endloop + endfacet + facet normal 0.275754 -0.943958 -0.181392 + outer loop + vertex 650.798 114.155 306.667 + vertex 653.844 114.703 308.443 + vertex 646.678 112.744 307.745 + endloop + endfacet + facet normal 0.289322 -0.93445 -0.207594 + outer loop + vertex 650.798 114.155 306.667 + vertex 657 115.854 307.662 + vertex 653.844 114.703 308.443 + endloop + endfacet + facet normal 0.288775 -0.934206 -0.209447 + outer loop + vertex 657 115.854 307.662 + vertex 659.597 116.351 309.025 + vertex 653.844 114.703 308.443 + endloop + endfacet + facet normal 0.286916 -0.943844 -0.163819 + outer loop + vertex 653.844 114.703 308.443 + vertex 659.597 116.351 309.025 + vertex 656.991 115.424 309.803 + endloop + endfacet + facet normal 0.287258 -0.943923 -0.162766 + outer loop + vertex 659.597 116.351 309.025 + vertex 661.974 116.91 309.98 + vertex 656.991 115.424 309.803 + endloop + endfacet + facet normal 0.287614 -0.950305 -0.11916 + outer loop + vertex 656.991 115.424 309.803 + vertex 661.974 116.91 309.98 + vertex 659.854 116.172 310.75 + endloop + endfacet + facet normal 0.287315 -0.950293 -0.119972 + outer loop + vertex 661.974 116.91 309.98 + vertex 663.661 117.343 310.59 + vertex 659.854 116.172 310.75 + endloop + endfacet + facet normal 0.289744 -0.953359 -0.0845899 + outer loop + vertex 659.854 116.172 310.75 + vertex 663.661 117.343 310.59 + vertex 661.849 116.722 311.383 + endloop + endfacet + facet normal 0.289275 -0.953403 -0.0856957 + outer loop + vertex 663.661 117.343 310.59 + vertex 664.324 117.508 310.987 + vertex 661.849 116.722 311.383 + endloop + endfacet + facet normal 0.294485 -0.954098 -0.0545504 + outer loop + vertex 661.849 116.722 311.383 + vertex 664.324 117.508 310.987 + vertex 662.523 116.9 311.901 + endloop + endfacet + facet normal 0.296862 -0.935496 -0.191625 + outer loop + vertex 659.597 116.351 309.025 + vertex 663.438 117.483 309.45 + vertex 661.974 116.91 309.98 + endloop + endfacet + facet normal 0.297842 -0.935693 -0.189127 + outer loop + vertex 663.438 117.483 309.45 + vertex 664.908 117.824 310.078 + vertex 661.974 116.91 309.98 + endloop + endfacet + facet normal 0.298538 -0.941333 -0.157375 + outer loop + vertex 661.974 116.91 309.98 + vertex 664.908 117.824 310.078 + vertex 663.661 117.343 310.59 + endloop + endfacet + facet normal 0.299837 -0.941429 -0.154303 + outer loop + vertex 664.908 117.824 310.078 + vertex 665.48 117.951 310.415 + vertex 663.661 117.343 310.59 + endloop + endfacet + facet normal 0.304929 -0.945389 -0.115145 + outer loop + vertex 663.661 117.343 310.59 + vertex 665.48 117.951 310.415 + vertex 664.324 117.508 310.987 + endloop + endfacet + facet normal 0.3692 -0.928943 0.0274858 + outer loop + vertex 664.324 117.508 310.987 + vertex 665.48 117.951 310.415 + vertex 666.065 118.181 310.343 + endloop + endfacet + facet normal 0.308437 -0.935739 -0.171054 + outer loop + vertex 664.908 117.824 310.078 + vertex 665.924 118.144 310.156 + vertex 665.48 117.951 310.415 + endloop + endfacet + facet normal 0.356031 -0.930545 -0.0856078 + outer loop + vertex 665.48 117.951 310.415 + vertex 665.924 118.144 310.156 + vertex 666.065 118.181 310.343 + endloop + endfacet + facet normal -0.122835 0.987405 -0.0997117 + outer loop + vertex 665.924 118.144 310.156 + vertex 665.342 118.034 309.781 + vertex 666.065 118.181 310.343 + endloop + endfacet + facet normal 0.466504 -0.792468 -0.392897 + outer loop + vertex 664.957 118.002 309.389 + vertex 666.065 118.181 310.343 + vertex 665.342 118.034 309.781 + endloop + endfacet + facet normal 0.306988 -0.92469 -0.225182 + outer loop + vertex 665.342 118.034 309.781 + vertex 663.893 117.74 309.014 + vertex 664.957 118.002 309.389 + endloop + endfacet + facet normal 0.307052 -0.924634 -0.225325 + outer loop + vertex 663.893 117.74 309.014 + vertex 665.342 118.034 309.781 + vertex 663.438 117.483 309.45 + endloop + endfacet + facet normal 0.301012 -0.925008 -0.231842 + outer loop + vertex 661.413 117.071 308.465 + vertex 663.893 117.74 309.014 + vertex 663.438 117.483 309.45 + endloop + endfacet + facet normal 0.303893 -0.918579 -0.252708 + outer loop + vertex 662.072 117.421 307.983 + vertex 663.893 117.74 309.014 + vertex 661.413 117.071 308.465 + endloop + endfacet + facet normal 0.299389 -0.918384 -0.258721 + outer loop + vertex 659.19 116.73 307.103 + vertex 662.072 117.421 307.983 + vertex 661.413 117.071 308.465 + endloop + endfacet + facet normal 0.300426 -0.917504 -0.260636 + outer loop + vertex 659.19 116.73 307.103 + vertex 661.413 117.071 308.465 + vertex 657 115.854 307.662 + endloop + endfacet + facet normal 0.300364 -0.917469 -0.260829 + outer loop + vertex 654.417 115.51 305.897 + vertex 659.19 116.73 307.103 + vertex 657 115.854 307.662 + endloop + endfacet + facet normal 0.304793 -0.90779 -0.28813 + outer loop + vertex 656.911 116.519 305.355 + vertex 659.19 116.73 307.103 + vertex 654.417 115.51 305.897 + endloop + endfacet + facet normal 0.305866 -0.908543 -0.284598 + outer loop + vertex 652.003 115.341 303.843 + vertex 656.911 116.519 305.355 + vertex 654.417 115.51 305.897 + endloop + endfacet + facet normal 0.298653 -0.913673 -0.275698 + outer loop + vertex 652.003 115.341 303.843 + vertex 654.417 115.51 305.897 + vertex 648.021 113.814 304.588 + endloop + endfacet + facet normal 0.301029 -0.91553 -0.266808 + outer loop + vertex 645.643 113.654 302.454 + vertex 652.003 115.341 303.843 + vertex 648.021 113.814 304.588 + endloop + endfacet + facet normal 0.287125 -0.92452 -0.250642 + outer loop + vertex 645.643 113.654 302.454 + vertex 648.021 113.814 304.588 + vertex 640.667 111.829 303.488 + endloop + endfacet + facet normal 0.291318 -0.927244 -0.235272 + outer loop + vertex 638.675 111.688 301.575 + vertex 645.643 113.654 302.454 + vertex 640.667 111.829 303.488 + endloop + endfacet + facet normal 0.272805 -0.937687 -0.215224 + outer loop + vertex 638.675 111.688 301.575 + vertex 640.667 111.829 303.488 + vertex 633.287 109.819 302.889 + endloop + endfacet + facet normal 0.28067 -0.941216 -0.187981 + outer loop + vertex 632.114 109.766 301.403 + vertex 638.675 111.688 301.575 + vertex 633.287 109.819 302.889 + endloop + endfacet + facet normal 0.25979 -0.950373 -0.171172 + outer loop + vertex 632.114 109.766 301.403 + vertex 633.287 109.819 302.889 + vertex 626.717 108.02 302.905 + endloop + endfacet + facet normal 0.277386 -0.954164 -0.112373 + outer loop + vertex 626.591 108.109 301.837 + vertex 632.114 109.766 301.403 + vertex 626.717 108.02 302.905 + endloop + endfacet + facet normal 0.255115 -0.960601 -0.11028 + outer loop + vertex 626.591 108.109 301.837 + vertex 626.717 108.02 302.905 + vertex 621.289 106.521 303.402 + endloop + endfacet + facet normal 0.260346 -0.963526 -0.0619455 + outer loop + vertex 621.289 106.521 303.402 + vertex 626.717 108.02 302.905 + vertex 621.65 106.543 304.589 + endloop + endfacet + facet normal 0.271199 -0.947904 -0.16712 + outer loop + vertex 631.973 109.896 300.439 + vertex 632.114 109.766 301.403 + vertex 626.591 108.109 301.837 + endloop + endfacet + facet normal 0.295246 -0.940248 -0.1696 + outer loop + vertex 631.973 109.896 300.439 + vertex 637.591 111.712 300.148 + vertex 632.114 109.766 301.403 + endloop + endfacet + facet normal 0.290767 -0.933118 -0.211531 + outer loop + vertex 637.449 111.874 299.239 + vertex 637.591 111.712 300.148 + vertex 631.973 109.896 300.439 + endloop + endfacet + facet normal 0.314395 -0.924913 -0.213758 + outer loop + vertex 637.449 111.874 299.239 + vertex 642.931 113.758 299.15 + vertex 637.591 111.712 300.148 + endloop + endfacet + facet normal 0.298859 -0.913973 -0.274475 + outer loop + vertex 642.931 113.758 299.15 + vertex 643.864 113.639 300.563 + vertex 637.591 111.712 300.148 + endloop + endfacet + facet normal 0.299442 -0.922643 -0.243031 + outer loop + vertex 637.591 111.712 300.148 + vertex 643.864 113.639 300.563 + vertex 638.675 111.688 301.575 + endloop + endfacet + facet normal 0.315441 -0.905236 -0.284683 + outer loop + vertex 642.931 113.758 299.15 + vertex 648.294 115.423 299.797 + vertex 643.864 113.639 300.563 + endloop + endfacet + facet normal 0.309902 -0.900379 -0.305415 + outer loop + vertex 648.294 115.423 299.797 + vertex 649.878 115.318 301.714 + vertex 643.864 113.639 300.563 + endloop + endfacet + facet normal 0.307756 -0.908689 -0.282082 + outer loop + vertex 643.864 113.639 300.563 + vertex 649.878 115.318 301.714 + vertex 645.643 113.654 302.454 + endloop + endfacet + facet normal 0.320441 -0.893794 -0.313768 + outer loop + vertex 648.294 115.423 299.797 + vertex 652.733 116.554 301.109 + vertex 649.878 115.318 301.714 + endloop + endfacet + facet normal 0.317458 -0.891505 -0.32317 + outer loop + vertex 652.733 116.554 301.109 + vertex 654.699 116.462 303.296 + vertex 649.878 115.318 301.714 + endloop + endfacet + facet normal 0.312848 -0.900239 -0.302812 + outer loop + vertex 649.878 115.318 301.714 + vertex 654.699 116.462 303.296 + vertex 652.003 115.341 303.843 + endloop + endfacet + facet normal 0.319652 -0.890026 -0.32508 + outer loop + vertex 652.733 116.554 301.109 + vertex 655.79 117.064 302.718 + vertex 654.699 116.462 303.296 + endloop + endfacet + facet normal 0.317567 -0.88952 -0.328488 + outer loop + vertex 655.79 117.064 302.718 + vertex 657.888 117.026 304.85 + vertex 654.699 116.462 303.296 + endloop + endfacet + facet normal 0.308743 -0.900436 -0.30642 + outer loop + vertex 654.699 116.462 303.296 + vertex 657.888 117.026 304.85 + vertex 656.911 116.519 305.355 + endloop + endfacet + facet normal 0.308961 -0.900487 -0.306049 + outer loop + vertex 657.888 117.026 304.85 + vertex 660.039 117.162 306.621 + vertex 656.911 116.519 305.355 + endloop + endfacet + facet normal 0.282737 -0.919612 -0.272714 + outer loop + vertex 660.039 117.162 306.621 + vertex 657.888 117.026 304.85 + vertex 659.885 117.293 306.02 + endloop + endfacet + facet normal 0.292871 -0.915901 -0.274502 + outer loop + vertex 659.885 117.293 306.02 + vertex 661.688 117.456 307.401 + vertex 660.039 117.162 306.621 + endloop + endfacet + facet normal 0.311173 -0.901734 -0.300078 + outer loop + vertex 661.688 117.456 307.401 + vertex 659.885 117.293 306.02 + vertex 661.977 117.69 306.996 + endloop + endfacet + facet normal 0.319103 -0.900973 -0.293975 + outer loop + vertex 663.334 117.715 308.392 + vertex 661.688 117.456 307.401 + vertex 661.977 117.69 306.996 + endloop + endfacet + facet normal 0.314579 -0.904 -0.289523 + outer loop + vertex 661.977 117.69 306.996 + vertex 664.221 117.956 308.605 + vertex 663.334 117.715 308.392 + endloop + endfacet + facet normal 0.332606 -0.888087 -0.317292 + outer loop + vertex 664.328 118.5 307.195 + vertex 664.221 117.956 308.605 + vertex 661.977 117.69 306.996 + endloop + endfacet + facet normal 0.3306 -0.870786 -0.363917 + outer loop + vertex 664.328 118.5 307.195 + vertex 661.977 117.69 306.996 + vertex 662.192 118.566 305.096 + endloop + endfacet + facet normal 0.357484 -0.848331 -0.390563 + outer loop + vertex 664.328 118.5 307.195 + vertex 662.192 118.566 305.096 + vertex 666.323 120.39 304.915 + endloop + endfacet + facet normal 0.333391 -0.848223 -0.411544 + outer loop + vertex 666.323 120.39 304.915 + vertex 668.242 120.165 306.932 + vertex 664.328 118.5 307.195 + endloop + endfacet + facet normal 0.343584 -0.864944 -0.365817 + outer loop + vertex 664.328 118.5 307.195 + vertex 668.242 120.165 306.932 + vertex 665.877 118.627 308.348 + endloop + endfacet + facet normal 0.319021 -0.859012 -0.400406 + outer loop + vertex 668.242 120.165 306.932 + vertex 667.786 119.291 308.445 + vertex 665.877 118.627 308.348 + endloop + endfacet + facet normal 0.332123 -0.856533 -0.395026 + outer loop + vertex 667.786 119.291 308.445 + vertex 668.242 120.165 306.932 + vertex 670.724 120.599 308.08 + endloop + endfacet + facet normal 0.347161 -0.874551 -0.338586 + outer loop + vertex 670.724 120.599 308.08 + vertex 669.07 119.527 309.151 + vertex 667.786 119.291 308.445 + endloop + endfacet + facet normal 0.327634 -0.897431 -0.295423 + outer loop + vertex 669.07 119.527 309.151 + vertex 666.891 118.713 309.209 + vertex 667.786 119.291 308.445 + endloop + endfacet + facet normal 0.327063 -0.897421 -0.296084 + outer loop + vertex 667.786 119.291 308.445 + vertex 666.891 118.713 309.209 + vertex 665.877 118.627 308.348 + endloop + endfacet + facet normal 0.321074 -0.90202 -0.288568 + outer loop + vertex 666.891 118.713 309.209 + vertex 665.432 118.216 309.138 + vertex 665.877 118.627 308.348 + endloop + endfacet + facet normal 0.335666 -0.899678 -0.27912 + outer loop + vertex 665.877 118.627 308.348 + vertex 665.432 118.216 309.138 + vertex 664.661 118.137 308.467 + endloop + endfacet + facet normal 0.323709 -0.884108 -0.336996 + outer loop + vertex 665.877 118.627 308.348 + vertex 664.661 118.137 308.467 + vertex 664.328 118.5 307.195 + endloop + endfacet + facet normal 0.303796 -0.922064 -0.239805 + outer loop + vertex 664.661 118.137 308.467 + vertex 665.432 118.216 309.138 + vertex 664.221 117.956 308.605 + endloop + endfacet + facet normal 0.334886 -0.872592 -0.355575 + outer loop + vertex 672.173 120.746 309.084 + vertex 669.07 119.527 309.151 + vertex 670.724 120.599 308.08 + endloop + endfacet + facet normal 0.355587 -0.849949 -0.388774 + outer loop + vertex 675.401 122.606 307.97 + vertex 672.173 120.746 309.084 + vertex 670.724 120.599 308.08 + endloop + endfacet + facet normal 0.344662 -0.844122 -0.410691 + outer loop + vertex 675.896 122.22 309.177 + vertex 672.173 120.746 309.084 + vertex 675.401 122.606 307.97 + endloop + endfacet + facet normal 0.365108 -0.833076 -0.415549 + outer loop + vertex 675.401 122.606 307.97 + vertex 681.38 125.106 308.211 + vertex 675.896 122.22 309.177 + endloop + endfacet + facet normal 0.354827 -0.822951 -0.443677 + outer loop + vertex 681.38 125.106 308.211 + vertex 678.915 123.316 309.558 + vertex 675.896 122.22 309.177 + endloop + endfacet + facet normal 0.347103 -0.820389 -0.454402 + outer loop + vertex 684.905 125.988 309.311 + vertex 678.915 123.316 309.558 + vertex 681.38 125.106 308.211 + endloop + endfacet + facet normal 0.348931 -0.832849 -0.429661 + outer loop + vertex 664.425 120.696 302.781 + vertex 666.323 120.39 304.915 + vertex 662.192 118.566 305.096 + endloop + endfacet + facet normal 0.368059 -0.833591 -0.411896 + outer loop + vertex 662.192 118.566 305.096 + vertex 660.166 118.738 302.938 + vertex 664.425 120.696 302.781 + endloop + endfacet + facet normal 0.364323 -0.826799 -0.42857 + outer loop + vertex 662.802 121.091 300.639 + vertex 664.425 120.696 302.781 + vertex 660.166 118.738 302.938 + endloop + endfacet + facet normal 0.380994 -0.828238 -0.410932 + outer loop + vertex 660.166 118.738 302.938 + vertex 658.555 119.064 300.787 + vertex 662.802 121.091 300.639 + endloop + endfacet + facet normal 0.382668 -0.83119 -0.403348 + outer loop + vertex 661.352 121.372 298.683 + vertex 662.802 121.091 300.639 + vertex 658.555 119.064 300.787 + endloop + endfacet + facet normal 0.391373 -0.832165 -0.392846 + outer loop + vertex 658.555 119.064 300.787 + vertex 657.172 119.334 298.836 + vertex 661.352 121.372 298.683 + endloop + endfacet + facet normal 0.397001 -0.841696 -0.365975 + outer loop + vertex 659.505 121.159 297.171 + vertex 661.352 121.372 298.683 + vertex 657.172 119.334 298.836 + endloop + endfacet + facet normal 0.389365 -0.84092 -0.37583 + outer loop + vertex 657.172 119.334 298.836 + vertex 655.568 119.244 297.376 + vertex 659.505 121.159 297.171 + endloop + endfacet + facet normal 0.380189 -0.849754 -0.365206 + outer loop + vertex 657.172 119.334 298.836 + vertex 654.698 118.288 298.694 + vertex 655.568 119.244 297.376 + endloop + endfacet + facet normal 0.379814 -0.8498 -0.365487 + outer loop + vertex 655.568 119.244 297.376 + vertex 654.698 118.288 298.694 + vertex 653.928 118.439 297.543 + endloop + endfacet + facet normal 0.371042 -0.838779 -0.398469 + outer loop + vertex 655.568 119.244 297.376 + vertex 653.928 118.439 297.543 + vertex 652.787 118.223 296.936 + endloop + endfacet + facet normal 0.371214 -0.846634 -0.381328 + outer loop + vertex 652.787 118.223 296.936 + vertex 654.963 119.339 296.576 + vertex 655.568 119.244 297.376 + endloop + endfacet + facet normal 0.349608 -0.824805 -0.444377 + outer loop + vertex 654.963 119.339 296.576 + vertex 652.787 118.223 296.936 + vertex 651.342 117.965 296.277 + endloop + endfacet + facet normal 0.339357 -0.844576 -0.41416 + outer loop + vertex 652.787 118.223 296.936 + vertex 649.509 116.904 296.94 + vertex 651.342 117.965 296.277 + endloop + endfacet + facet normal 0.313403 -0.780475 -0.54096 + outer loop + vertex 649.509 116.904 296.94 + vertex 652.787 118.223 296.936 + vertex 651.115 117.487 297.029 + endloop + endfacet + facet normal 0.302007 -0.759108 -0.576669 + outer loop + vertex 652.455 118.019 297.03 + vertex 651.115 117.487 297.029 + vertex 652.787 118.223 296.936 + endloop + endfacet + facet normal 0.395962 -0.82859 -0.395793 + outer loop + vertex 652.787 118.223 296.936 + vertex 653.263 118.089 297.693 + vertex 652.455 118.019 297.03 + endloop + endfacet + facet normal 0.355836 -0.869487 -0.342597 + outer loop + vertex 652.242 117.808 297.345 + vertex 652.455 118.019 297.03 + vertex 653.263 118.089 297.693 + endloop + endfacet + facet normal 0.356011 -0.869087 -0.343431 + outer loop + vertex 652.794 117.623 298.386 + vertex 652.242 117.808 297.345 + vertex 653.263 118.089 297.693 + endloop + endfacet + facet normal 0.349829 -0.869752 -0.348066 + outer loop + vertex 653.263 118.089 297.693 + vertex 653.931 117.832 299.005 + vertex 652.794 117.623 298.386 + endloop + endfacet + facet normal 0.351124 -0.868043 -0.351018 + outer loop + vertex 654.076 117.347 300.351 + vertex 652.794 117.623 298.386 + vertex 653.931 117.832 299.005 + endloop + endfacet + facet normal 0.344712 -0.870527 -0.35122 + outer loop + vertex 653.931 117.832 299.005 + vertex 654.785 117.699 300.174 + vertex 654.076 117.347 300.351 + endloop + endfacet + facet normal 0.341856 -0.868573 -0.35877 + outer loop + vertex 654.785 117.699 300.174 + vertex 655.886 117.41 301.924 + vertex 654.076 117.347 300.351 + endloop + endfacet + facet normal 0.328441 -0.88009 -0.342882 + outer loop + vertex 655.79 117.064 302.718 + vertex 654.076 117.347 300.351 + vertex 655.886 117.41 301.924 + endloop + endfacet + facet normal 0.321331 -0.882045 -0.34459 + outer loop + vertex 655.886 117.41 301.924 + vertex 657.709 117.234 304.074 + vertex 655.79 117.064 302.718 + endloop + endfacet + facet normal 0.342556 -0.867217 -0.361372 + outer loop + vertex 657.709 117.234 304.074 + vertex 655.886 117.41 301.924 + vertex 657.507 117.718 302.72 + endloop + endfacet + facet normal 0.33234 -0.871222 -0.361277 + outer loop + vertex 657.507 117.718 302.72 + vertex 659.53 117.604 304.856 + vertex 657.709 117.234 304.074 + endloop + endfacet + facet normal 0.323871 -0.884741 -0.335173 + outer loop + vertex 659.885 117.293 306.02 + vertex 657.709 117.234 304.074 + vertex 659.53 117.604 304.856 + endloop + endfacet + facet normal 0.357798 -0.851048 -0.384316 + outer loop + vertex 660.166 118.738 302.938 + vertex 659.53 117.604 304.856 + vertex 657.507 117.718 302.72 + endloop + endfacet + facet normal 0.34648 -0.861297 -0.371645 + outer loop + vertex 656.011 118.026 300.611 + vertex 657.507 117.718 302.72 + vertex 655.886 117.41 301.924 + endloop + endfacet + facet normal 0.371043 -0.844325 -0.386578 + outer loop + vertex 658.555 119.064 300.787 + vertex 657.507 117.718 302.72 + vertex 656.011 118.026 300.611 + endloop + endfacet + facet normal 0.36013 -0.857093 -0.368371 + outer loop + vertex 655.886 117.41 301.924 + vertex 654.785 117.699 300.174 + vertex 656.011 118.026 300.611 + endloop + endfacet + facet normal 0.359059 -0.859631 -0.363471 + outer loop + vertex 654.698 118.288 298.694 + vertex 656.011 118.026 300.611 + vertex 654.785 117.699 300.174 + endloop + endfacet + facet normal 0.362912 -0.858164 -0.363112 + outer loop + vertex 654.785 117.699 300.174 + vertex 653.931 117.832 299.005 + vertex 654.698 118.288 298.694 + endloop + endfacet + facet normal 0.334425 -0.878347 -0.341564 + outer loop + vertex 652.794 117.623 298.386 + vertex 654.076 117.347 300.351 + vertex 651.333 116.779 299.126 + endloop + endfacet + facet normal 0.340623 -0.879945 -0.33117 + outer loop + vertex 650.747 117.085 297.712 + vertex 652.794 117.623 298.386 + vertex 651.333 116.779 299.126 + endloop + endfacet + facet normal 0.329812 -0.885291 -0.327848 + outer loop + vertex 650.747 117.085 297.712 + vertex 651.333 116.779 299.126 + vertex 647.554 115.658 298.351 + endloop + endfacet + facet normal 0.339809 -0.892997 -0.295103 + outer loop + vertex 647.978 116.13 297.411 + vertex 650.747 117.085 297.712 + vertex 647.554 115.658 298.351 + endloop + endfacet + facet normal 0.327114 -0.895417 -0.302033 + outer loop + vertex 647.978 116.13 297.411 + vertex 647.554 115.658 298.351 + vertex 643.012 114.052 298.194 + endloop + endfacet + facet normal 0.330413 -0.909678 -0.25162 + outer loop + vertex 643.012 114.052 298.194 + vertex 647.554 115.658 298.351 + vertex 642.931 113.758 299.15 + endloop + endfacet + facet normal 0.339309 -0.878788 -0.33556 + outer loop + vertex 651.115 117.487 297.029 + vertex 650.747 117.085 297.712 + vertex 647.978 116.13 297.411 + endloop + endfacet + facet normal 0.343535 -0.878153 -0.332913 + outer loop + vertex 651.115 117.487 297.029 + vertex 652.242 117.808 297.345 + vertex 650.747 117.085 297.712 + endloop + endfacet + facet normal 0.32848 -0.891209 -0.312805 + outer loop + vertex 647.554 115.658 298.351 + vertex 651.333 116.779 299.126 + vertex 648.294 115.423 299.797 + endloop + endfacet + facet normal 0.331969 -0.882051 -0.33434 + outer loop + vertex 651.333 116.779 299.126 + vertex 654.076 117.347 300.351 + vertex 652.733 116.554 301.109 + endloop + endfacet + facet normal 0.367178 -0.859766 -0.354941 + outer loop + vertex 653.931 117.832 299.005 + vertex 653.263 118.089 297.693 + vertex 654.698 118.288 298.694 + endloop + endfacet + facet normal 0.341916 -0.877077 -0.337386 + outer loop + vertex 652.242 117.808 297.345 + vertex 652.794 117.623 298.386 + vertex 650.747 117.085 297.712 + endloop + endfacet + facet normal 0.346105 -0.870519 -0.34987 + outer loop + vertex 652.455 118.019 297.03 + vertex 652.242 117.808 297.345 + vertex 651.115 117.487 297.029 + endloop + endfacet + facet normal 0.363079 -0.851148 -0.379105 + outer loop + vertex 653.263 118.089 297.693 + vertex 652.787 118.223 296.936 + vertex 653.928 118.439 297.543 + endloop + endfacet + facet normal 0.370175 -0.856411 -0.359905 + outer loop + vertex 653.928 118.439 297.543 + vertex 654.698 118.288 298.694 + vertex 653.263 118.089 297.693 + endloop + endfacet + facet normal 0.379105 -0.845824 -0.375314 + outer loop + vertex 657.172 119.334 298.836 + vertex 656.011 118.026 300.611 + vertex 654.698 118.288 298.694 + endloop + endfacet + facet normal 0.371608 -0.846679 -0.380844 + outer loop + vertex 658.555 119.064 300.787 + vertex 656.011 118.026 300.611 + vertex 657.172 119.334 298.836 + endloop + endfacet + facet normal 0.356879 -0.846249 -0.395602 + outer loop + vertex 660.166 118.738 302.938 + vertex 657.507 117.718 302.72 + vertex 658.555 119.064 300.787 + endloop + endfacet + facet normal 0.343738 -0.853937 -0.390687 + outer loop + vertex 662.192 118.566 305.096 + vertex 659.53 117.604 304.856 + vertex 660.166 118.738 302.938 + endloop + endfacet + facet normal 0.345534 -0.866501 -0.360253 + outer loop + vertex 662.192 118.566 305.096 + vertex 661.977 117.69 306.996 + vertex 659.53 117.604 304.856 + endloop + endfacet + facet normal 0.269131 -0.905249 -0.328773 + outer loop + vertex 664.661 118.137 308.467 + vertex 664.221 117.956 308.605 + vertex 664.328 118.5 307.195 + endloop + endfacet + facet normal 0.295845 -0.921983 -0.249847 + outer loop + vertex 661.688 117.456 307.401 + vertex 663.334 117.715 308.392 + vertex 662.072 117.421 307.983 + endloop + endfacet + facet normal 0.278618 -0.930192 -0.238986 + outer loop + vertex 662.072 117.421 307.983 + vertex 660.039 117.162 306.621 + vertex 661.688 117.456 307.401 + endloop + endfacet + facet normal 0.32432 -0.884545 -0.335258 + outer loop + vertex 659.53 117.604 304.856 + vertex 661.977 117.69 306.996 + vertex 659.885 117.293 306.02 + endloop + endfacet + facet normal 0.302627 -0.900967 -0.310927 + outer loop + vertex 657.709 117.234 304.074 + vertex 659.885 117.293 306.02 + vertex 657.888 117.026 304.85 + endloop + endfacet + facet normal 0.299004 -0.902337 -0.310459 + outer loop + vertex 657.888 117.026 304.85 + vertex 655.79 117.064 302.718 + vertex 657.709 117.234 304.074 + endloop + endfacet + facet normal 0.327027 -0.880974 -0.341964 + outer loop + vertex 654.076 117.347 300.351 + vertex 655.79 117.064 302.718 + vertex 652.733 116.554 301.109 + endloop + endfacet + facet normal 0.323239 -0.887367 -0.32878 + outer loop + vertex 651.333 116.779 299.126 + vertex 652.733 116.554 301.109 + vertex 648.294 115.423 299.797 + endloop + endfacet + facet normal 0.315825 -0.897647 -0.307383 + outer loop + vertex 647.554 115.658 298.351 + vertex 648.294 115.423 299.797 + vertex 642.931 113.758 299.15 + endloop + endfacet + facet normal 0.310554 -0.915675 -0.255139 + outer loop + vertex 643.012 114.052 298.194 + vertex 642.931 113.758 299.15 + vertex 637.449 111.874 299.239 + endloop + endfacet + facet normal 0.261827 -0.957363 -0.122074 + outer loop + vertex 626.717 108.02 302.905 + vertex 633.287 109.819 302.889 + vertex 628.066 108.186 304.493 + endloop + endfacet + facet normal 0.253438 -0.955969 -0.147962 + outer loop + vertex 633.287 109.819 302.889 + vertex 635.552 110.114 304.864 + vertex 628.066 108.186 304.493 + endloop + endfacet + facet normal 0.27925 -0.93279 -0.227864 + outer loop + vertex 637.591 111.712 300.148 + vertex 638.675 111.688 301.575 + vertex 632.114 109.766 301.403 + endloop + endfacet + facet normal 0.271742 -0.947189 -0.170263 + outer loop + vertex 633.287 109.819 302.889 + vertex 640.667 111.829 303.488 + vertex 635.552 110.114 304.864 + endloop + endfacet + facet normal 0.292792 -0.917872 -0.267927 + outer loop + vertex 643.864 113.639 300.563 + vertex 645.643 113.654 302.454 + vertex 638.675 111.688 301.575 + endloop + endfacet + facet normal 0.284071 -0.93538 -0.210636 + outer loop + vertex 640.667 111.829 303.488 + vertex 648.021 113.814 304.588 + vertex 643.4 112.17 305.656 + endloop + endfacet + facet normal 0.304496 -0.905871 -0.294414 + outer loop + vertex 649.878 115.318 301.714 + vertex 652.003 115.341 303.843 + vertex 645.643 113.654 302.454 + endloop + endfacet + facet normal 0.294654 -0.924384 -0.242266 + outer loop + vertex 648.021 113.814 304.588 + vertex 654.417 115.51 305.897 + vertex 650.798 114.155 306.667 + endloop + endfacet + facet normal 0.311015 -0.898802 -0.308907 + outer loop + vertex 654.699 116.462 303.296 + vertex 656.911 116.519 305.355 + vertex 652.003 115.341 303.843 + endloop + endfacet + facet normal 0.302122 -0.909856 -0.2844 + outer loop + vertex 656.911 116.519 305.355 + vertex 660.039 117.162 306.621 + vertex 659.19 116.73 307.103 + endloop + endfacet + facet normal 0.30423 -0.910208 -0.281007 + outer loop + vertex 660.039 117.162 306.621 + vertex 662.072 117.421 307.983 + vertex 659.19 116.73 307.103 + endloop + endfacet + facet normal 0.289239 -0.930918 -0.223008 + outer loop + vertex 663.893 117.74 309.014 + vertex 662.072 117.421 307.983 + vertex 663.334 117.715 308.392 + endloop + endfacet + facet normal 0.312021 -0.918217 -0.243968 + outer loop + vertex 663.334 117.715 308.392 + vertex 664.957 118.002 309.389 + vertex 663.893 117.74 309.014 + endloop + endfacet + facet normal 0.306182 -0.922994 -0.233097 + outer loop + vertex 664.957 118.002 309.389 + vertex 663.334 117.715 308.392 + vertex 664.221 117.956 308.605 + endloop + endfacet + facet normal 0.300641 -0.937912 -0.173023 + outer loop + vertex 666.065 118.181 310.343 + vertex 664.957 118.002 309.389 + vertex 665.597 118.162 309.636 + endloop + endfacet + facet normal 0.312633 -0.93245 -0.181098 + outer loop + vertex 665.597 118.162 309.636 + vertex 666.363 118.346 310.008 + vertex 666.065 118.181 310.343 + endloop + endfacet + facet normal 0.324575 -0.930548 -0.169506 + outer loop + vertex 666.363 118.346 310.008 + vertex 667.25 118.648 310.051 + vertex 666.065 118.181 310.343 + endloop + endfacet + facet normal 0.331409 -0.932338 -0.144617 + outer loop + vertex 669.505 119.439 310.115 + vertex 666.065 118.181 310.343 + vertex 667.25 118.648 310.051 + endloop + endfacet + facet normal 0.330335 -0.926323 -0.181118 + outer loop + vertex 669.505 119.439 310.115 + vertex 667.25 118.648 310.051 + vertex 668.104 119.01 309.754 + endloop + endfacet + facet normal 0.333102 -0.922109 -0.196872 + outer loop + vertex 668.104 119.01 309.754 + vertex 670.421 119.848 309.749 + vertex 669.505 119.439 310.115 + endloop + endfacet + facet normal 0.336739 -0.922579 -0.188295 + outer loop + vertex 670.421 119.848 309.749 + vertex 671.939 120.339 310.058 + vertex 669.505 119.439 310.115 + endloop + endfacet + facet normal 0.342798 -0.907842 -0.241478 + outer loop + vertex 670.421 119.848 309.749 + vertex 673.289 120.925 309.773 + vertex 671.939 120.339 310.058 + endloop + endfacet + facet normal 0.328501 -0.909751 -0.25385 + outer loop + vertex 670.421 119.848 309.749 + vertex 668.104 119.01 309.754 + vertex 669.07 119.527 309.151 + endloop + endfacet + facet normal 0.34332 -0.890859 -0.297491 + outer loop + vertex 672.173 120.746 309.084 + vertex 670.421 119.848 309.749 + vertex 669.07 119.527 309.151 + endloop + endfacet + facet normal 0.336031 -0.888257 -0.313181 + outer loop + vertex 673.289 120.925 309.773 + vertex 670.421 119.848 309.749 + vertex 672.173 120.746 309.084 + endloop + endfacet + facet normal 0.353057 -0.869403 -0.345671 + outer loop + vertex 675.896 122.22 309.177 + vertex 673.289 120.925 309.773 + vertex 672.173 120.746 309.084 + endloop + endfacet + facet normal 0.339309 -0.859041 -0.383298 + outer loop + vertex 675.621 121.845 309.774 + vertex 673.289 120.925 309.773 + vertex 675.896 122.22 309.177 + endloop + endfacet + facet normal 0.3579 -0.856078 -0.372877 + outer loop + vertex 678.915 123.316 309.558 + vertex 675.621 121.845 309.774 + vertex 675.896 122.22 309.177 + endloop + endfacet + facet normal 0.386952 -0.897497 -0.211583 + outer loop + vertex 678.915 123.316 309.558 + vertex 675.374 121.664 310.094 + vertex 675.621 121.845 309.774 + endloop + endfacet + facet normal 0.3523 -0.868037 -0.349853 + outer loop + vertex 681.33 124.09 310.071 + vertex 675.374 121.664 310.094 + vertex 678.915 123.316 309.558 + endloop + endfacet + facet normal 0.356229 -0.8372 -0.414967 + outer loop + vertex 684.905 125.988 309.311 + vertex 681.33 124.09 310.071 + vertex 678.915 123.316 309.558 + endloop + endfacet + facet normal 0.347859 -0.829914 -0.436161 + outer loop + vertex 688.072 126.931 310.043 + vertex 681.33 124.09 310.071 + vertex 684.905 125.988 309.311 + endloop + endfacet + facet normal 0.349908 -0.809828 -0.470895 + outer loop + vertex 690.998 128.631 309.292 + vertex 688.072 126.931 310.043 + vertex 684.905 125.988 309.311 + endloop + endfacet + facet normal 0.343527 -0.804709 -0.484181 + outer loop + vertex 693.757 129.355 310.048 + vertex 688.072 126.931 310.043 + vertex 690.998 128.631 309.292 + endloop + endfacet + facet normal 0.346116 -0.787228 -0.510368 + outer loop + vertex 695.209 130.383 309.447 + vertex 693.757 129.355 310.048 + vertex 690.998 128.631 309.292 + endloop + endfacet + facet normal 0.343077 -0.785595 -0.514917 + outer loop + vertex 696.125 130.407 310.02 + vertex 693.757 129.355 310.048 + vertex 695.209 130.383 309.447 + endloop + endfacet + facet normal 0.37748 -0.728027 -0.572263 + outer loop + vertex 696.125 130.407 310.02 + vertex 695.209 130.383 309.447 + vertex 697.212 131.012 309.968 + endloop + endfacet + facet normal 0.412557 -0.782072 -0.467076 + outer loop + vertex 697.212 131.012 309.968 + vertex 696.119 130.279 310.229 + vertex 696.125 130.407 310.02 + endloop + endfacet + facet normal 0.503424 -0.833014 -0.229459 + outer loop + vertex 696.119 130.279 310.229 + vertex 697.212 131.012 309.968 + vertex 696.02 130.19 310.337 + endloop + endfacet + facet normal 0.382429 -0.852306 -0.356824 + outer loop + vertex 694.876 129.679 310.33 + vertex 696.119 130.279 310.229 + vertex 696.02 130.19 310.337 + endloop + endfacet + facet normal 0.399991 -0.893756 -0.202997 + outer loop + vertex 696.02 130.19 310.337 + vertex 694.476 129.485 310.399 + vertex 694.876 129.679 310.33 + endloop + endfacet + facet normal 0.371235 -0.873868 -0.31391 + outer loop + vertex 691.998 128.467 310.3 + vertex 694.876 129.679 310.33 + vertex 694.476 129.485 310.399 + endloop + endfacet + facet normal 0.378268 -0.900673 -0.21378 + outer loop + vertex 694.476 129.485 310.399 + vertex 692.667 128.728 310.387 + vertex 691.998 128.467 310.3 + endloop + endfacet + facet normal 0.379445 -0.9095 0.169795 + outer loop + vertex 692.667 128.728 310.387 + vertex 694.476 129.485 310.399 + vertex 694.827 129.643 310.463 + endloop + endfacet + facet normal 0.391334 -0.91737 -0.0727362 + outer loop + vertex 691.252 128.119 310.452 + vertex 692.667 128.728 310.387 + vertex 694.827 129.643 310.463 + endloop + endfacet + facet normal 0.374218 -0.875621 -0.305367 + outer loop + vertex 693.094 128.816 310.71 + vertex 691.252 128.119 310.452 + vertex 694.827 129.643 310.463 + endloop + endfacet + facet normal 0.380771 -0.881526 -0.27915 + outer loop + vertex 695.916 129.975 310.9 + vertex 693.094 128.816 310.71 + vertex 694.827 129.643 310.463 + endloop + endfacet + facet normal 0.403529 -0.836938 -0.36973 + outer loop + vertex 697.212 131.012 309.968 + vertex 695.916 129.975 310.9 + vertex 694.827 129.643 310.463 + endloop + endfacet + facet normal 0.403003 -0.836891 -0.370409 + outer loop + vertex 697.212 131.012 309.968 + vertex 697.764 130.708 311.254 + vertex 695.916 129.975 310.9 + endloop + endfacet + facet normal 0.38183 -0.887692 -0.257311 + outer loop + vertex 692.874 128.591 311.159 + vertex 693.094 128.816 310.71 + vertex 695.916 129.975 310.9 + endloop + endfacet + facet normal 0.372265 -0.890032 -0.263177 + outer loop + vertex 692.874 128.591 311.159 + vertex 688.599 126.95 310.664 + vertex 693.094 128.816 310.71 + endloop + endfacet + facet normal 0.371884 -0.900797 -0.224202 + outer loop + vertex 688.116 126.603 311.255 + vertex 688.599 126.95 310.664 + vertex 692.874 128.591 311.159 + endloop + endfacet + facet normal 0.371332 -0.900898 -0.224713 + outer loop + vertex 688.599 126.95 310.664 + vertex 688.116 126.603 311.255 + vertex 682.892 124.586 310.709 + endloop + endfacet + facet normal 0.373287 -0.892759 -0.252265 + outer loop + vertex 693.094 128.816 310.71 + vertex 688.599 126.95 310.664 + vertex 691.252 128.119 310.452 + endloop + endfacet + facet normal 0.375788 -0.895756 -0.237498 + outer loop + vertex 688.599 126.95 310.664 + vertex 687.548 126.587 310.37 + vertex 691.252 128.119 310.452 + endloop + endfacet + facet normal 0.381407 -0.91508 -0.130983 + outer loop + vertex 687.548 126.587 310.37 + vertex 689.317 127.331 310.321 + vertex 691.252 128.119 310.452 + endloop + endfacet + facet normal 0.38368 -0.918294 -0.0976005 + outer loop + vertex 687.548 126.587 310.37 + vertex 684.812 125.453 310.282 + vertex 689.317 127.331 310.321 + endloop + endfacet + facet normal 0.383535 -0.922921 -0.0334478 + outer loop + vertex 683.628 124.957 310.381 + vertex 684.812 125.453 310.282 + vertex 687.548 126.587 310.37 + endloop + endfacet + facet normal 0.379029 -0.921778 -0.0816255 + outer loop + vertex 683.628 124.957 310.381 + vertex 680.169 123.545 310.269 + vertex 684.812 125.453 310.282 + endloop + endfacet + facet normal 0.37696 -0.925675 0.0320521 + outer loop + vertex 678.677 122.941 310.37 + vertex 680.169 123.545 310.269 + vertex 683.628 124.957 310.381 + endloop + endfacet + facet normal 0.370211 -0.907894 -0.196655 + outer loop + vertex 678.677 122.941 310.37 + vertex 683.628 124.957 310.381 + vertex 682.892 124.586 310.709 + endloop + endfacet + facet normal 0.370034 -0.915872 -0.155733 + outer loop + vertex 682.892 124.586 310.709 + vertex 677.358 122.353 310.691 + vertex 678.677 122.941 310.37 + endloop + endfacet + facet normal 0.362757 -0.913921 -0.182088 + outer loop + vertex 678.677 122.941 310.37 + vertex 677.358 122.353 310.691 + vertex 674.198 121.17 310.333 + endloop + endfacet + facet normal 0.367604 -0.929978 -0.00299933 + outer loop + vertex 674.198 121.17 310.333 + vertex 675.79 121.8 310.247 + vertex 678.677 122.941 310.37 + endloop + endfacet + facet normal 0.355822 -0.921146 -0.157734 + outer loop + vertex 674.198 121.17 310.333 + vertex 672.428 120.508 310.208 + vertex 675.79 121.8 310.247 + endloop + endfacet + facet normal 0.354761 -0.930163 -0.0945558 + outer loop + vertex 670.639 119.819 310.273 + vertex 672.428 120.508 310.208 + vertex 674.198 121.17 310.333 + endloop + endfacet + facet normal 0.351778 -0.918497 -0.180599 + outer loop + vertex 670.639 119.819 310.273 + vertex 674.198 121.17 310.333 + vertex 672.643 120.517 310.626 + endloop + endfacet + facet normal 0.348511 -0.925527 -0.148124 + outer loop + vertex 672.643 120.517 310.626 + vertex 669.156 119.22 310.529 + vertex 670.639 119.819 310.273 + endloop + endfacet + facet normal 0.349324 -0.93062 -0.109171 + outer loop + vertex 671.142 119.892 311.152 + vertex 669.156 119.22 310.529 + vertex 672.643 120.517 310.626 + endloop + endfacet + facet normal 0.356875 -0.930091 -0.0870166 + outer loop + vertex 671.142 119.892 311.152 + vertex 672.643 120.517 310.626 + vertex 676.174 121.809 311.294 + endloop + endfacet + facet normal 0.36158 -0.924146 -0.123343 + outer loop + vertex 676.174 121.809 311.294 + vertex 672.643 120.517 310.626 + vertex 677.358 122.353 310.691 + endloop + endfacet + facet normal 0.36564 -0.923635 -0.114917 + outer loop + vertex 676.174 121.809 311.294 + vertex 677.358 122.353 310.691 + vertex 682.252 124.212 311.321 + endloop + endfacet + facet normal 0.369075 -0.913363 -0.171904 + outer loop + vertex 682.252 124.212 311.321 + vertex 677.358 122.353 310.691 + vertex 682.892 124.586 310.709 + endloop + endfacet + facet normal 0.37038 -0.913119 -0.170388 + outer loop + vertex 682.252 124.212 311.321 + vertex 682.892 124.586 310.709 + vertex 688.116 126.603 311.255 + endloop + endfacet + facet normal 0.343585 -0.935179 -0.0859642 + outer loop + vertex 667.788 118.674 311 + vertex 669.156 119.22 310.529 + vertex 671.142 119.892 311.152 + endloop + endfacet + facet normal 0.335745 -0.9356 -0.109217 + outer loop + vertex 667.788 118.674 311 + vertex 667.019 118.463 310.444 + vertex 669.156 119.22 310.529 + endloop + endfacet + facet normal 0.334727 -0.924592 -0.181899 + outer loop + vertex 669.156 119.22 310.529 + vertex 667.019 118.463 310.444 + vertex 667.999 118.855 310.253 + endloop + endfacet + facet normal 0.329629 -0.922061 -0.202851 + outer loop + vertex 667.019 118.463 310.444 + vertex 666.736 118.401 310.265 + vertex 667.999 118.855 310.253 + endloop + endfacet + facet normal -0.328275 0.906082 -0.26693 + outer loop + vertex 667.999 118.855 310.253 + vertex 666.736 118.401 310.265 + vertex 666.065 118.181 310.343 + endloop + endfacet + facet normal 0.224874 -0.73151 -0.643681 + outer loop + vertex 666.065 118.181 310.343 + vertex 669.505 119.439 310.115 + vertex 667.999 118.855 310.253 + endloop + endfacet + facet normal 0.249161 -0.893518 -0.373557 + outer loop + vertex 666.736 118.401 310.265 + vertex 666.281 118.219 310.396 + vertex 666.065 118.181 310.343 + endloop + endfacet + facet normal 0.217694 -0.955266 -0.200192 + outer loop + vertex 666.281 118.219 310.396 + vertex 665.859 118.016 310.908 + vertex 666.065 118.181 310.343 + endloop + endfacet + facet normal 0.318013 -0.941433 -0.112121 + outer loop + vertex 667.019 118.463 310.444 + vertex 665.859 118.016 310.908 + vertex 666.281 118.219 310.396 + endloop + endfacet + facet normal 0.318819 -0.929973 -0.183045 + outer loop + vertex 666.281 118.219 310.396 + vertex 666.736 118.401 310.265 + vertex 667.019 118.463 310.444 + endloop + endfacet + facet normal 0.325489 -0.940961 -0.0929966 + outer loop + vertex 665.859 118.016 310.908 + vertex 667.019 118.463 310.444 + vertex 667.788 118.674 311 + endloop + endfacet + facet normal 0.33896 -0.904486 -0.258866 + outer loop + vertex 672.428 120.508 310.208 + vertex 670.639 119.819 310.273 + vertex 669.505 119.439 310.115 + endloop + endfacet + facet normal 0.33678 -0.932468 0.130699 + outer loop + vertex 669.505 119.439 310.115 + vertex 672.372 120.484 310.18 + vertex 672.428 120.508 310.208 + endloop + endfacet + facet normal 0.347786 -0.931369 0.10769 + outer loop + vertex 672.372 120.484 310.18 + vertex 673.98 121.088 310.217 + vertex 672.428 120.508 310.208 + endloop + endfacet + facet normal 0.360991 -0.922054 -0.139645 + outer loop + vertex 672.643 120.517 310.626 + vertex 674.198 121.17 310.333 + vertex 677.358 122.353 310.691 + endloop + endfacet + facet normal 0.369272 -0.925698 -0.0819859 + outer loop + vertex 678.677 122.941 310.37 + vertex 675.79 121.8 310.247 + vertex 680.169 123.545 310.269 + endloop + endfacet + facet normal 0.373537 -0.900154 -0.22404 + outer loop + vertex 687.548 126.587 310.37 + vertex 688.599 126.95 310.664 + vertex 683.628 124.957 310.381 + endloop + endfacet + facet normal 0.381294 -0.90601 -0.18374 + outer loop + vertex 691.252 128.119 310.452 + vertex 689.317 127.331 310.321 + vertex 692.667 128.728 310.387 + endloop + endfacet + facet normal 0.351181 -0.823019 -0.446443 + outer loop + vertex 694.876 129.679 310.33 + vertex 691.998 128.467 310.3 + vertex 693.757 129.355 310.048 + endloop + endfacet + facet normal 0.414589 -0.909764 -0.0211047 + outer loop + vertex 694.827 129.643 310.463 + vertex 694.476 129.485 310.399 + vertex 696.02 130.19 310.337 + endloop + endfacet + facet normal 0.35293 -0.809931 -0.468458 + outer loop + vertex 696.119 130.279 310.229 + vertex 694.876 129.679 310.33 + vertex 693.757 129.355 310.048 + endloop + endfacet + facet normal -0.217863 0.644607 0.732815 + outer loop + vertex 694.827 129.643 310.463 + vertex 696.02 130.19 310.337 + vertex 697.212 131.012 309.968 + endloop + endfacet + facet normal 0.351229 -0.80305 -0.481402 + outer loop + vertex 693.757 129.355 310.048 + vertex 696.125 130.407 310.02 + vertex 696.119 130.279 310.229 + endloop + endfacet + facet normal 0.351412 -0.823285 -0.44577 + outer loop + vertex 688.072 126.931 310.043 + vertex 693.757 129.355 310.048 + vertex 691.998 128.467 310.3 + endloop + endfacet + facet normal 0.351218 -0.822529 -0.447316 + outer loop + vertex 691.998 128.467 310.3 + vertex 689.202 127.293 310.265 + vertex 688.072 126.931 310.043 + endloop + endfacet + facet normal 0.383964 -0.909065 -0.161782 + outer loop + vertex 689.202 127.293 310.265 + vertex 691.998 128.467 310.3 + vertex 689.317 127.331 310.321 + endloop + endfacet + facet normal 0.382623 -0.910252 -0.158243 + outer loop + vertex 687.17 126.44 310.253 + vertex 689.202 127.293 310.265 + vertex 689.317 127.331 310.321 + endloop + endfacet + facet normal 0.35087 -0.830723 -0.432192 + outer loop + vertex 689.202 127.293 310.265 + vertex 687.17 126.44 310.253 + vertex 688.072 126.931 310.043 + endloop + endfacet + facet normal 0.350115 -0.830105 -0.433988 + outer loop + vertex 687.17 126.44 310.253 + vertex 684.582 125.364 310.224 + vertex 688.072 126.931 310.043 + endloop + endfacet + facet normal 0.356697 -0.903331 -0.238246 + outer loop + vertex 675.621 121.845 309.774 + vertex 675.374 121.664 310.094 + vertex 673.289 120.925 309.773 + endloop + endfacet + facet normal 0.333659 -0.910068 -0.245862 + outer loop + vertex 669.07 119.527 309.151 + vertex 668.104 119.01 309.754 + vertex 666.891 118.713 309.209 + endloop + endfacet + facet normal 0.32441 -0.920003 -0.219893 + outer loop + vertex 668.104 119.01 309.754 + vertex 666.509 118.451 309.741 + vertex 666.891 118.713 309.209 + endloop + endfacet + facet normal 0.3239 -0.920085 -0.220299 + outer loop + vertex 666.891 118.713 309.209 + vertex 666.509 118.451 309.741 + vertex 665.432 118.216 309.138 + endloop + endfacet + facet normal 0.31751 -0.92543 -0.206799 + outer loop + vertex 665.432 118.216 309.138 + vertex 666.509 118.451 309.741 + vertex 665.597 118.162 309.636 + endloop + endfacet + facet normal 0.32612 -0.92556 -0.192311 + outer loop + vertex 666.509 118.451 309.741 + vertex 668.104 119.01 309.754 + vertex 667.25 118.648 310.051 + endloop + endfacet + facet normal 0.324311 -0.927305 -0.18689 + outer loop + vertex 667.25 118.648 310.051 + vertex 666.363 118.346 310.008 + vertex 666.509 118.451 309.741 + endloop + endfacet + facet normal 0.316874 -0.928917 -0.19158 + outer loop + vertex 666.509 118.451 309.741 + vertex 666.363 118.346 310.008 + vertex 665.597 118.162 309.636 + endloop + endfacet + facet normal 0.308847 -0.928312 -0.207002 + outer loop + vertex 665.342 118.034 309.781 + vertex 665.924 118.144 310.156 + vertex 664.908 117.824 310.078 + endloop + endfacet + facet normal 0.305723 -0.928314 -0.21158 + outer loop + vertex 663.438 117.483 309.45 + vertex 665.342 118.034 309.781 + vertex 664.908 117.824 310.078 + endloop + endfacet + facet normal 0.298221 -0.927595 -0.225017 + outer loop + vertex 661.413 117.071 308.465 + vertex 663.438 117.483 309.45 + vertex 659.597 116.351 309.025 + endloop + endfacet + facet normal 0.29716 -0.927214 -0.227968 + outer loop + vertex 657 115.854 307.662 + vertex 661.413 117.071 308.465 + vertex 659.597 116.351 309.025 + endloop + endfacet + facet normal 0.292853 -0.923242 -0.24872 + outer loop + vertex 654.417 115.51 305.897 + vertex 657 115.854 307.662 + vertex 650.798 114.155 306.667 + endloop + endfacet + facet normal 0.280793 -0.933688 -0.22222 + outer loop + vertex 648.021 113.814 304.588 + vertex 650.798 114.155 306.667 + vertex 643.4 112.17 305.656 + endloop + endfacet + facet normal 0.266643 -0.945466 -0.187071 + outer loop + vertex 640.667 111.829 303.488 + vertex 643.4 112.17 305.656 + vertex 635.552 110.114 304.864 + endloop + endfacet + facet normal 0.245248 -0.963499 -0.107347 + outer loop + vertex 626.717 108.02 302.905 + vertex 628.066 108.186 304.493 + vertex 621.65 106.543 304.589 + endloop + endfacet + facet normal 0.244242 -0.96804 -0.0569632 + outer loop + vertex 621.289 106.521 303.402 + vertex 621.65 106.543 304.589 + vertex 616.597 105.241 305.043 + endloop + endfacet + facet normal 0.243572 -0.968342 0.0546397 + outer loop + vertex 610.266 103.666 307.004 + vertex 611.802 104.022 306.46 + vertex 613.099 104.353 306.532 + endloop + endfacet + facet normal 0.247455 -0.96872 0.0186653 + outer loop + vertex 611.247 103.873 306.107 + vertex 612.932 104.3 305.917 + vertex 611.319 103.9 306.507 + endloop + endfacet + facet normal 0.175422 -0.983507 0.0440475 + outer loop + vertex 610.266 103.666 307.004 + vertex 608.682 103.259 304.215 + vertex 609.764 103.505 305.393 + endloop + endfacet + facet normal 0.249801 -0.968289 0.00404867 + outer loop + vertex 610.512 103.682 305.663 + vertex 611.357 103.899 305.405 + vertex 611.247 103.873 306.107 + endloop + endfacet + facet normal 0.241209 -0.970281 -0.0193046 + outer loop + vertex 610.787 103.782 304.147 + vertex 612.35 104.155 304.951 + vertex 611.357 103.899 305.405 + endloop + endfacet + facet normal 0.252194 -0.966736 -0.0426508 + outer loop + vertex 610.151 103.706 302.103 + vertex 610.787 103.782 304.147 + vertex 608.987 103.388 302.442 + endloop + endfacet + facet normal 0.248614 -0.967028 -0.0552118 + outer loop + vertex 608.987 103.388 302.442 + vertex 608.014 103.312 299.383 + vertex 610.151 103.706 302.103 + endloop + endfacet + facet normal 0.280599 -0.955794 -0.0878801 + outer loop + vertex 606.968 103.343 295.71 + vertex 608.014 103.312 299.383 + vertex 606.11 103.037 296.298 + endloop + endfacet + facet normal 0.275402 -0.956539 -0.0958482 + outer loop + vertex 605.522 103.127 293.707 + vertex 606.968 103.343 295.71 + vertex 606.11 103.037 296.298 + endloop + endfacet + facet normal 0.313594 -0.941284 -0.125072 + outer loop + vertex 605.724 103.547 291.058 + vertex 606.968 103.343 295.71 + vertex 605.522 103.127 293.707 + endloop + endfacet + facet normal 0.313695 -0.938382 -0.145031 + outer loop + vertex 605.133 104.293 284.949 + vertex 605.724 103.547 291.058 + vertex 603.942 103.58 286.985 + endloop + endfacet + facet normal 0.27294 -0.955142 -0.114919 + outer loop + vertex 603.468 103.155 289.007 + vertex 605.183 103.054 293.919 + vertex 605.004 102.925 294.57 + endloop + endfacet + facet normal 0.271465 -0.958561 -0.086416 + outer loop + vertex 605.004 102.925 294.57 + vertex 606.651 103.021 298.682 + vertex 606.289 102.875 299.157 + endloop + endfacet + facet normal 0.257835 -0.965733 -0.0296716 + outer loop + vertex 601.063 101.371 299.674 + vertex 605.118 102.354 302.911 + vertex 601.425 101.365 303.026 + endloop + endfacet + facet normal 0.26579 -0.963548 -0.0305262 + outer loop + vertex 601.063 101.371 299.674 + vertex 601.425 101.365 303.026 + vertex 597.287 100.308 300.352 + endloop + endfacet + facet normal 0.262182 -0.963678 -0.0508413 + outer loop + vertex 594.407 99.7612 295.87 + vertex 601.063 101.371 299.674 + vertex 597.287 100.308 300.352 + endloop + endfacet + facet normal 0.261047 -0.964027 -0.0500693 + outer loop + vertex 597.287 100.308 300.352 + vertex 590.375 98.5179 298.786 + vertex 594.407 99.7612 295.87 + endloop + endfacet + facet normal 0.253985 -0.967085 -0.0154008 + outer loop + vertex 597.287 100.308 300.352 + vertex 595.897 99.9036 302.835 + vertex 590.375 98.5179 298.786 + endloop + endfacet + facet normal 0.255276 -0.966714 -0.0172883 + outer loop + vertex 590.375 98.5179 298.786 + vertex 595.897 99.9036 302.835 + vertex 588.557 97.9711 302.519 + endloop + endfacet + facet normal 0.256772 -0.966331 -0.0165038 + outer loop + vertex 590.375 98.5179 298.786 + vertex 588.557 97.9711 302.519 + vertex 580.223 95.8358 297.88 + endloop + endfacet + facet normal 0.25954 -0.964237 -0.0537284 + outer loop + vertex 580.223 95.8358 297.88 + vertex 582.823 96.9116 291.13 + vertex 590.375 98.5179 298.786 + endloop + endfacet + facet normal 0.264636 -0.962969 -0.0515641 + outer loop + vertex 582.823 96.9116 291.13 + vertex 580.223 95.8358 297.88 + vertex 568.978 93.1265 290.763 + endloop + endfacet + facet normal 0.255989 -0.965981 -0.0367552 + outer loop + vertex 568.978 93.1265 290.763 + vertex 580.223 95.8358 297.88 + vertex 567.855 92.5298 298.625 + endloop + endfacet + facet normal 0.257205 -0.965665 -0.0365575 + outer loop + vertex 568.978 93.1265 290.763 + vertex 567.855 92.5298 298.625 + vertex 555.115 89.4398 290.613 + endloop + endfacet + facet normal 0.257086 -0.963874 -0.0696653 + outer loop + vertex 556.239 90.358 282.056 + vertex 568.978 93.1265 290.763 + vertex 555.115 89.4398 290.613 + endloop + endfacet + facet normal 0.247117 -0.966363 -0.0712414 + outer loop + vertex 556.239 90.358 282.056 + vertex 555.115 89.4398 290.613 + vertex 542.684 86.9153 281.738 + endloop + endfacet + facet normal 0.247137 -0.963635 -0.101638 + outer loop + vertex 543.174 87.9936 272.707 + vertex 556.239 90.358 282.056 + vertex 542.684 86.9153 281.738 + endloop + endfacet + facet normal 0.232821 -0.967069 -0.102825 + outer loop + vertex 543.174 87.9936 272.707 + vertex 542.684 86.9153 281.738 + vertex 530.225 84.9361 272.141 + endloop + endfacet + facet normal 0.233202 -0.963827 -0.129054 + outer loop + vertex 530.352 86.1734 263.13 + vertex 543.174 87.9936 272.707 + vertex 530.225 84.9361 272.141 + endloop + endfacet + facet normal 0.218403 -0.967198 -0.129725 + outer loop + vertex 530.352 86.1734 263.13 + vertex 530.225 84.9361 272.141 + vertex 518.774 83.6439 262.497 + endloop + endfacet + facet normal 0.218769 -0.964782 -0.146071 + outer loop + vertex 518.895 84.9934 253.765 + vertex 530.352 86.1734 263.13 + vertex 518.774 83.6439 262.497 + endloop + endfacet + facet normal 0.204942 -0.967715 -0.146717 + outer loop + vertex 518.895 84.9934 253.765 + vertex 518.774 83.6439 262.497 + vertex 509.593 83.0522 253.576 + endloop + endfacet + facet normal 0.204894 -0.967074 -0.150951 + outer loop + vertex 509.887 84.4457 245.047 + vertex 518.895 84.9934 253.765 + vertex 509.593 83.0522 253.576 + endloop + endfacet + facet normal 0.19054 -0.969856 -0.1519 + outer loop + vertex 509.887 84.4457 245.047 + vertex 509.593 83.0522 253.576 + vertex 502.985 82.9591 245.881 + endloop + endfacet + facet normal 0.191472 -0.97064 -0.145588 + outer loop + vertex 503.901 84.3856 237.575 + vertex 509.887 84.4457 245.047 + vertex 502.985 82.9591 245.881 + endloop + endfacet + facet normal 0.177226 -0.973044 -0.147571 + outer loop + vertex 503.901 84.3856 237.575 + vertex 502.985 82.9591 245.881 + vertex 499.878 83.3013 239.893 + endloop + endfacet + facet normal 0.191058 -0.970772 -0.145255 + outer loop + vertex 510.218 85.7916 236.488 + vertex 509.887 84.4457 245.047 + vertex 503.901 84.3856 237.575 + endloop + endfacet + facet normal 0.192763 -0.969114 -0.153817 + outer loop + vertex 502.985 82.9591 245.881 + vertex 509.593 83.0522 253.576 + vertex 502.926 81.5597 254.625 + endloop + endfacet + facet normal 0.178034 -0.971843 -0.154353 + outer loop + vertex 502.985 82.9591 245.881 + vertex 502.926 81.5597 254.625 + vertex 499.146 81.6559 249.658 + endloop + endfacet + facet normal 0.193555 -0.96963 -0.149514 + outer loop + vertex 509.593 83.0522 253.576 + vertex 509.16 81.618 262.316 + vertex 502.926 81.5597 254.625 + endloop + endfacet + facet normal 0.195987 -0.968834 -0.151492 + outer loop + vertex 502.926 81.5597 254.625 + vertex 509.16 81.618 262.316 + vertex 501.729 79.9927 263.097 + endloop + endfacet + facet normal 0.181891 -0.971197 -0.153921 + outer loop + vertex 502.926 81.5597 254.625 + vertex 501.729 79.9927 263.097 + vertex 498.532 80.3508 257.06 + endloop + endfacet + facet normal 0.197566 -0.970306 -0.139547 + outer loop + vertex 509.16 81.618 262.316 + vertex 508.178 80.0954 271.514 + vertex 501.729 79.9927 263.097 + endloop + endfacet + facet normal 0.205535 -0.967745 -0.145685 + outer loop + vertex 501.729 79.9927 263.097 + vertex 508.178 80.0954 271.514 + vertex 501.074 78.5018 272.076 + endloop + endfacet + facet normal 0.191318 -0.970432 -0.147168 + outer loop + vertex 501.729 79.9927 263.097 + vertex 501.074 78.5018 272.076 + vertex 497.653 78.5952 267.014 + endloop + endfacet + facet normal 0.207425 -0.969865 -0.127813 + outer loop + vertex 508.178 80.0954 271.514 + vertex 505.944 78.3315 281.271 + vertex 501.074 78.5018 272.076 + endloop + endfacet + facet normal 0.215134 -0.967642 -0.131854 + outer loop + vertex 501.074 78.5018 272.076 + vertex 505.944 78.3315 281.271 + vertex 498.708 76.9154 279.859 + endloop + endfacet + facet normal 0.198158 -0.970465 -0.137589 + outer loop + vertex 501.074 78.5018 272.076 + vertex 498.708 76.9154 279.859 + vertex 497.208 77.5363 273.319 + endloop + endfacet + facet normal 0.213735 -0.969087 -0.12324 + outer loop + vertex 498.708 76.9154 279.859 + vertex 505.944 78.3315 281.271 + vertex 501.517 76.6625 286.718 + endloop + endfacet + facet normal 0.20618 -0.971101 -0.120221 + outer loop + vertex 497.107 75.6406 287.409 + vertex 498.708 76.9154 279.859 + vertex 501.517 76.6625 286.718 + endloop + endfacet + facet normal 0.210734 -0.973013 -0.0940068 + outer loop + vertex 501.517 76.6625 286.718 + vertex 499.783 75.7282 292.503 + vertex 497.107 75.6406 287.409 + endloop + endfacet + facet normal 0.209392 -0.973371 -0.0932952 + outer loop + vertex 497.107 75.6406 287.409 + vertex 499.783 75.7282 292.503 + vertex 495.762 74.7701 293.474 + endloop + endfacet + facet normal 0.209986 -0.973257 -0.093147 + outer loop + vertex 497.107 75.6406 287.409 + vertex 495.762 74.7701 293.474 + vertex 493.933 74.7059 290.02 + endloop + endfacet + facet normal 0.215954 -0.974112 -0.066852 + outer loop + vertex 499.783 75.7282 292.503 + vertex 498.478 75.0932 297.538 + vertex 495.762 74.7701 293.474 + endloop + endfacet + facet normal 0.217275 -0.973755 -0.067763 + outer loop + vertex 495.762 74.7701 293.474 + vertex 498.478 75.0932 297.538 + vertex 494.6 74.179 298.241 + endloop + endfacet + facet normal 0.217117 -0.973788 -0.0678055 + outer loop + vertex 495.762 74.7701 293.474 + vertex 494.6 74.179 298.241 + vertex 492.596 73.8866 296.023 + endloop + endfacet + facet normal 0.213318 -0.974869 -0.0642292 + outer loop + vertex 494.6 74.179 298.241 + vertex 492.249 73.5763 299.581 + vertex 492.596 73.8866 296.023 + endloop + endfacet + facet normal 0.210858 -0.975385 -0.0645142 + outer loop + vertex 490.794 73.2254 300.13 + vertex 492.596 73.8866 296.023 + vertex 492.249 73.5763 299.581 + endloop + endfacet + facet normal 0.223587 -0.973614 -0.0456517 + outer loop + vertex 494.6 74.179 298.241 + vertex 493.573 73.788 301.553 + vertex 492.249 73.5763 299.581 + endloop + endfacet + facet normal 0.222259 -0.973961 -0.0447221 + outer loop + vertex 492.249 73.5763 299.581 + vertex 493.573 73.788 301.553 + vertex 491.263 73.2343 302.13 + endloop + endfacet + facet normal 0.217472 -0.974949 -0.0467052 + outer loop + vertex 492.249 73.5763 299.581 + vertex 491.263 73.2343 302.13 + vertex 490.794 73.2254 300.13 + endloop + endfacet + facet normal 0.214808 -0.975569 -0.0460775 + outer loop + vertex 489.442 72.7649 303.576 + vertex 490.794 73.2254 300.13 + vertex 491.263 73.2343 302.13 + endloop + endfacet + facet normal 0.224013 -0.973994 -0.0339696 + outer loop + vertex 491.263 73.2343 302.13 + vertex 491.241 73.1737 303.723 + vertex 489.442 72.7649 303.576 + endloop + endfacet + facet normal 0.225228 -0.973715 -0.0339422 + outer loop + vertex 491.263 73.2343 302.13 + vertex 492.608 73.4996 303.443 + vertex 491.241 73.1737 303.723 + endloop + endfacet + facet normal 0.228625 -0.973367 -0.0169463 + outer loop + vertex 491.241 73.1737 303.723 + vertex 492.608 73.4996 303.443 + vertex 493.312 73.6413 304.794 + endloop + endfacet + facet normal 0.22864 -0.973364 -0.0169543 + outer loop + vertex 492.608 73.4996 303.443 + vertex 496.169 74.332 303.677 + vertex 493.312 73.6413 304.794 + endloop + endfacet + facet normal 0.229453 -0.972818 -0.0312421 + outer loop + vertex 493.573 73.788 301.553 + vertex 496.169 74.332 303.677 + vertex 492.608 73.4996 303.443 + endloop + endfacet + facet normal 0.225072 -0.974006 -0.0255862 + outer loop + vertex 497.24 74.643 301.261 + vertex 496.169 74.332 303.677 + vertex 493.573 73.788 301.553 + endloop + endfacet + facet normal 0.227333 -0.973508 -0.02452 + outer loop + vertex 497.24 74.643 301.261 + vertex 500.648 75.3796 303.61 + vertex 496.169 74.332 303.677 + endloop + endfacet + facet normal 0.227915 -0.973593 0.0130591 + outer loop + vertex 500.648 75.3796 303.61 + vertex 502.286 75.7878 305.456 + vertex 496.169 74.332 303.677 + endloop + endfacet + facet normal 0.232983 -0.972467 -0.00528713 + outer loop + vertex 502.286 75.7878 305.456 + vertex 493.312 73.6413 304.794 + vertex 496.169 74.332 303.677 + endloop + endfacet + facet normal 0.231223 -0.97285 0.00995913 + outer loop + vertex 500.648 75.3796 303.61 + vertex 506.987 76.8915 304.128 + vertex 502.286 75.7878 305.456 + endloop + endfacet + facet normal 0.23307 -0.972358 -0.0140993 + outer loop + vertex 502.262 75.799 301.371 + vertex 506.987 76.8915 304.128 + vertex 500.648 75.3796 303.61 + endloop + endfacet + facet normal 0.227501 -0.97377 -0.00399566 + outer loop + vertex 508.463 77.2464 301.668 + vertex 506.987 76.8915 304.128 + vertex 502.262 75.799 301.371 + endloop + endfacet + facet normal 0.23336 -0.97239 -0.000281143 + outer loop + vertex 508.463 77.2464 301.668 + vertex 513.616 78.4824 304.148 + vertex 506.987 76.8915 304.128 + endloop + endfacet + facet normal 0.232608 -0.97015 0.0685749 + outer loop + vertex 513.616 78.4824 304.148 + vertex 515.64 79.0792 305.725 + vertex 506.987 76.8915 304.128 + endloop + endfacet + facet normal 0.238426 -0.970438 0.0374472 + outer loop + vertex 515.64 79.0792 305.725 + vertex 502.286 75.7878 305.456 + vertex 506.987 76.8915 304.128 + endloop + endfacet + facet normal 0.240057 -0.96899 0.05857 + outer loop + vertex 513.616 78.4824 304.148 + vertex 521.83 80.5369 304.472 + vertex 515.64 79.0792 305.725 + endloop + endfacet + facet normal 0.245034 -0.965594 0.0871041 + outer loop + vertex 529.574 82.6142 305.715 + vertex 515.64 79.0792 305.725 + vertex 521.83 80.5369 304.472 + endloop + endfacet + facet normal 0.247846 -0.966221 0.0706344 + outer loop + vertex 532.789 83.3183 304.067 + vertex 529.574 82.6142 305.715 + vertex 521.83 80.5369 304.472 + endloop + endfacet + facet normal 0.246737 -0.968814 0.0228026 + outer loop + vertex 523.74 80.9625 301.885 + vertex 532.789 83.3183 304.067 + vertex 521.83 80.5369 304.472 + endloop + endfacet + facet normal 0.239888 -0.970644 0.0174447 + outer loop + vertex 523.74 80.9625 301.885 + vertex 521.83 80.5369 304.472 + vertex 515.578 78.9478 302.025 + endloop + endfacet + facet normal 0.239106 -0.970601 -0.0276091 + outer loop + vertex 517.061 79.4114 298.571 + vertex 523.74 80.9625 301.885 + vertex 515.578 78.9478 302.025 + endloop + endfacet + facet normal 0.231305 -0.972381 -0.0311979 + outer loop + vertex 517.061 79.4114 298.571 + vertex 515.578 78.9478 302.025 + vertex 510.197 77.8077 297.662 + endloop + endfacet + facet normal 0.235483 -0.969507 -0.0678484 + outer loop + vertex 517.061 79.4114 298.571 + vertex 510.197 77.8077 297.662 + vertex 513.586 79.0816 291.223 + endloop + endfacet + facet normal 0.231805 -0.970516 -0.0660636 + outer loop + vertex 517.061 79.4114 298.571 + vertex 513.586 79.0816 291.223 + vertex 523.868 81.1149 297.428 + endloop + endfacet + facet normal 0.232467 -0.970277 -0.0672394 + outer loop + vertex 513.586 79.0816 291.223 + vertex 527.463 82.3999 291.314 + vertex 523.868 81.1149 297.428 + endloop + endfacet + facet normal 0.23547 -0.969682 -0.0653488 + outer loop + vertex 530.401 82.7092 297.313 + vertex 523.868 81.1149 297.428 + vertex 527.463 82.3999 291.314 + endloop + endfacet + facet normal 0.250575 -0.965343 -0.072971 + outer loop + vertex 527.463 82.3999 291.314 + vertex 538.196 84.7341 297.292 + vertex 530.401 82.7092 297.313 + endloop + endfacet + facet normal 0.240816 -0.969068 -0.0539941 + outer loop + vertex 540.976 85.8072 290.429 + vertex 538.196 84.7341 297.292 + vertex 527.463 82.3999 291.314 + endloop + endfacet + facet normal 0.253835 -0.966043 -0.0482475 + outer loop + vertex 540.976 85.8072 290.429 + vertex 551.823 88.2972 297.644 + vertex 538.196 84.7341 297.292 + endloop + endfacet + facet normal 0.249125 -0.967619 -0.040621 + outer loop + vertex 555.115 89.4398 290.613 + vertex 551.823 88.2972 297.644 + vertex 540.976 85.8072 290.429 + endloop + endfacet + facet normal 0.235363 -0.969532 -0.0679165 + outer loop + vertex 510.197 77.8077 297.662 + vertex 505.226 76.9698 292.397 + vertex 513.586 79.0816 291.223 + endloop + endfacet + facet normal 0.232908 -0.968849 -0.0841727 + outer loop + vertex 505.912 77.5271 287.881 + vertex 513.586 79.0816 291.223 + vertex 505.226 76.9698 292.397 + endloop + endfacet + facet normal 0.214491 -0.972802 -0.087459 + outer loop + vertex 505.912 77.5271 287.881 + vertex 505.226 76.9698 292.397 + vertex 501.517 76.6625 286.718 + endloop + endfacet + facet normal 0.245457 -0.962446 -0.115967 + outer loop + vertex 505.944 78.3315 281.271 + vertex 513.586 79.0816 291.223 + vertex 505.912 77.5271 287.881 + endloop + endfacet + facet normal 0.221979 -0.970179 -0.0973529 + outer loop + vertex 516.693 80.7833 281.348 + vertex 513.586 79.0816 291.223 + vertex 505.944 78.3315 281.271 + endloop + endfacet + facet normal 0.232132 -0.96815 -0.093809 + outer loop + vertex 516.693 80.7833 281.348 + vertex 527.463 82.3999 291.314 + vertex 513.586 79.0816 291.223 + endloop + endfacet + facet normal 0.224997 -0.970583 -0.0857038 + outer loop + vertex 529.301 83.6907 281.521 + vertex 527.463 82.3999 291.314 + vertex 516.693 80.7833 281.348 + endloop + endfacet + facet normal 0.224743 -0.967869 -0.112784 + outer loop + vertex 518.229 82.271 271.641 + vertex 529.301 83.6907 281.521 + vertex 516.693 80.7833 281.348 + endloop + endfacet + facet normal 0.211561 -0.970542 -0.11528 + outer loop + vertex 518.229 82.271 271.641 + vertex 516.693 80.7833 281.348 + vertex 508.178 80.0954 271.514 + endloop + endfacet + facet normal 0.219883 -0.969631 -0.107085 + outer loop + vertex 530.225 84.9361 272.141 + vertex 529.301 83.6907 281.521 + vertex 518.229 82.271 271.641 + endloop + endfacet + facet normal 0.238562 -0.967594 -0.0827632 + outer loop + vertex 529.301 83.6907 281.521 + vertex 540.976 85.8072 290.429 + vertex 527.463 82.3999 291.314 + endloop + endfacet + facet normal 0.234721 -0.968976 -0.0774016 + outer loop + vertex 542.684 86.9153 281.738 + vertex 540.976 85.8072 290.429 + vertex 529.301 83.6907 281.521 + endloop + endfacet + facet normal 0.228941 -0.971493 -0.0615418 + outer loop + vertex 503.665 76.2791 297.493 + vertex 505.226 76.9698 292.397 + vertex 510.197 77.8077 297.662 + endloop + endfacet + facet normal 0.228619 -0.9728 -0.0373334 + outer loop + vertex 510.197 77.8077 297.662 + vertex 508.463 77.2464 301.668 + vertex 503.665 76.2791 297.493 + endloop + endfacet + facet normal 0.22887 -0.972729 -0.0376387 + outer loop + vertex 503.665 76.2791 297.493 + vertex 508.463 77.2464 301.668 + vertex 502.262 75.799 301.371 + endloop + endfacet + facet normal 0.222361 -0.974137 -0.0401673 + outer loop + vertex 503.665 76.2791 297.493 + vertex 502.262 75.799 301.371 + vertex 498.478 75.0932 297.538 + endloop + endfacet + facet normal 0.225009 -0.973411 -0.0429158 + outer loop + vertex 498.478 75.0932 297.538 + vertex 502.262 75.799 301.371 + vertex 497.24 74.643 301.261 + endloop + endfacet + facet normal 0.220761 -0.973207 -0.0642796 + outer loop + vertex 505.226 76.9698 292.397 + vertex 503.665 76.2791 297.493 + vertex 499.783 75.7282 292.503 + endloop + endfacet + facet normal 0.234065 -0.971598 -0.0348072 + outer loop + vertex 510.197 77.8077 297.662 + vertex 515.578 78.9478 302.025 + vertex 508.463 77.2464 301.668 + endloop + endfacet + facet normal 0.238532 -0.970777 -0.0263689 + outer loop + vertex 523.868 81.1149 297.428 + vertex 523.74 80.9625 301.885 + vertex 517.061 79.4114 298.571 + endloop + endfacet + facet normal 0.241693 -0.969998 -0.0262519 + outer loop + vertex 523.868 81.1149 297.428 + vertex 532.374 83.1439 300.766 + vertex 523.74 80.9625 301.885 + endloop + endfacet + facet normal 0.23683 -0.971465 -0.0129662 + outer loop + vertex 530.401 82.7092 297.313 + vertex 532.374 83.1439 300.766 + vertex 523.868 81.1149 297.428 + endloop + endfacet + facet normal 0.251319 -0.967661 -0.0217223 + outer loop + vertex 530.401 82.7092 297.313 + vertex 538.196 84.7341 297.292 + vertex 532.374 83.1439 300.766 + endloop + endfacet + facet normal 0.256723 -0.966409 -0.0120942 + outer loop + vertex 532.374 83.1439 300.766 + vertex 538.196 84.7341 297.292 + vertex 545.46 86.598 302.545 + endloop + endfacet + facet normal 0.252701 -0.967352 0.0193179 + outer loop + vertex 532.789 83.3183 304.067 + vertex 532.374 83.1439 300.766 + vertex 545.46 86.598 302.545 + endloop + endfacet + facet normal 0.255215 -0.965912 0.0433538 + outer loop + vertex 545.46 86.598 302.545 + vertex 543.099 86.1081 305.529 + vertex 532.789 83.3183 304.067 + endloop + endfacet + facet normal 0.253121 -0.967411 -0.00675861 + outer loop + vertex 538.196 84.7341 297.292 + vertex 551.823 88.2972 297.644 + vertex 545.46 86.598 302.545 + endloop + endfacet + facet normal 0.255661 -0.966761 -0.0032347 + outer loop + vertex 561.5 90.8384 302.934 + vertex 545.46 86.598 302.545 + vertex 551.823 88.2972 297.644 + endloop + endfacet + facet normal 0.255427 -0.966824 -0.00277508 + outer loop + vertex 551.823 88.2972 297.644 + vertex 567.855 92.5298 298.625 + vertex 561.5 90.8384 302.934 + endloop + endfacet + facet normal 0.256898 -0.966438 -0.000453438 + outer loop + vertex 574.453 94.2811 304.092 + vertex 561.5 90.8384 302.934 + vertex 567.855 92.5298 298.625 + endloop + endfacet + facet normal 0.251747 -0.967773 0.00619115 + outer loop + vertex 567.855 92.5298 298.625 + vertex 580.422 95.8255 302.783 + vertex 574.453 94.2811 304.092 + endloop + endfacet + facet normal 0.254255 -0.966958 0.0185953 + outer loop + vertex 580.422 95.8255 302.783 + vertex 581.641 96.1898 305.063 + vertex 574.453 94.2811 304.092 + endloop + endfacet + facet normal 0.247657 -0.966552 0.0666615 + outer loop + vertex 581.641 96.1898 305.063 + vertex 582.649 96.5164 306.051 + vertex 574.453 94.2811 304.092 + endloop + endfacet + facet normal 0.253989 -0.965356 0.0598068 + outer loop + vertex 581.641 96.1898 305.063 + vertex 587.488 97.7304 305.098 + vertex 582.649 96.5164 306.051 + endloop + endfacet + facet normal 0.254633 -0.966863 0.0183778 + outer loop + vertex 580.422 95.8255 302.783 + vertex 587.488 97.7304 305.098 + vertex 581.641 96.1898 305.063 + endloop + endfacet + facet normal 0.255465 -0.966691 0.0156958 + outer loop + vertex 588.557 97.9711 302.519 + vertex 587.488 97.7304 305.098 + vertex 580.422 95.8255 302.783 + endloop + endfacet + facet normal 0.252766 -0.967419 0.0145085 + outer loop + vertex 588.557 97.9711 302.519 + vertex 593.978 99.4225 304.85 + vertex 587.488 97.7304 305.098 + endloop + endfacet + facet normal 0.253491 -0.966523 0.0396954 + outer loop + vertex 593.978 99.4225 304.85 + vertex 594.898 99.7255 306.357 + vertex 587.488 97.7304 305.098 + endloop + endfacet + facet normal 0.251786 -0.966922 0.0408172 + outer loop + vertex 593.978 99.4225 304.85 + vertex 599.871 100.969 305.144 + vertex 594.898 99.7255 306.357 + endloop + endfacet + facet normal 0.248658 -0.968225 0.0266509 + outer loop + vertex 599.871 100.969 305.144 + vertex 603.98 102.059 306.394 + vertex 594.898 99.7255 306.357 + endloop + endfacet + facet normal 0.251591 -0.967692 0.0165409 + outer loop + vertex 599.871 100.969 305.144 + vertex 604.379 102.138 304.961 + vertex 603.98 102.059 306.394 + endloop + endfacet + facet normal 0.249577 -0.968224 0.015951 + outer loop + vertex 604.379 102.138 304.961 + vertex 606.987 102.814 305.155 + vertex 603.98 102.059 306.394 + endloop + endfacet + facet normal 0.251126 -0.967948 0.00345409 + outer loop + vertex 601.425 101.365 303.026 + vertex 604.379 102.138 304.961 + vertex 599.871 100.969 305.144 + endloop + endfacet + facet normal 0.255343 -0.966827 0.00675815 + outer loop + vertex 601.425 101.365 303.026 + vertex 599.871 100.969 305.144 + vertex 595.897 99.9036 302.835 + endloop + endfacet + facet normal 0.253408 -0.967305 0.0103083 + outer loop + vertex 595.897 99.9036 302.835 + vertex 599.871 100.969 305.144 + vertex 593.978 99.4225 304.85 + endloop + endfacet + facet normal 0.252767 -0.966445 0.045754 + outer loop + vertex 574.453 94.2811 304.092 + vertex 570.266 93.2641 305.74 + vertex 561.5 90.8384 302.934 + endloop + endfacet + facet normal 0.254489 -0.96626 0.03972 + outer loop + vertex 561.5 90.8384 302.934 + vertex 556.696 89.6758 305.427 + vertex 545.46 86.598 302.545 + endloop + endfacet + facet normal 0.247371 -0.968713 0.0200602 + outer loop + vertex 532.374 83.1439 300.766 + vertex 532.789 83.3183 304.067 + vertex 523.74 80.9625 301.885 + endloop + endfacet + facet normal 0.242215 -0.970158 0.0111867 + outer loop + vertex 515.578 78.9478 302.025 + vertex 521.83 80.5369 304.472 + vertex 513.616 78.4824 304.148 + endloop + endfacet + facet normal 0.232478 -0.9726 0.00165605 + outer loop + vertex 515.578 78.9478 302.025 + vertex 513.616 78.4824 304.148 + vertex 508.463 77.2464 301.668 + endloop + endfacet + facet normal 0.224701 -0.974213 -0.0204817 + outer loop + vertex 502.262 75.799 301.371 + vertex 500.648 75.3796 303.61 + vertex 497.24 74.643 301.261 + endloop + endfacet + facet normal 0.224979 -0.973781 -0.0336739 + outer loop + vertex 493.573 73.788 301.553 + vertex 492.608 73.4996 303.443 + vertex 491.263 73.2343 302.13 + endloop + endfacet + facet normal 0.223388 -0.973657 -0.0457184 + outer loop + vertex 494.6 74.179 298.241 + vertex 497.24 74.643 301.261 + vertex 493.573 73.788 301.553 + endloop + endfacet + facet normal 0.221644 -0.974129 -0.0441215 + outer loop + vertex 498.478 75.0932 297.538 + vertex 497.24 74.643 301.261 + vertex 494.6 74.179 298.241 + endloop + endfacet + facet normal 0.221859 -0.972899 -0.065168 + outer loop + vertex 499.783 75.7282 292.503 + vertex 503.665 76.2791 297.493 + vertex 498.478 75.0932 297.538 + endloop + endfacet + facet normal 0.219804 -0.97129 -0.0910108 + outer loop + vertex 501.517 76.6625 286.718 + vertex 505.226 76.9698 292.397 + vertex 499.783 75.7282 292.503 + endloop + endfacet + facet normal 0.205267 -0.971267 -0.120442 + outer loop + vertex 498.708 76.9154 279.859 + vertex 497.107 75.6406 287.409 + vertex 495.033 75.6797 283.56 + endloop + endfacet + facet normal 0.221341 -0.968179 -0.116779 + outer loop + vertex 505.912 77.5271 287.881 + vertex 501.517 76.6625 286.718 + vertex 505.944 78.3315 281.271 + endloop + endfacet + facet normal 0.221496 -0.967231 -0.124114 + outer loop + vertex 508.178 80.0954 271.514 + vertex 516.693 80.7833 281.348 + vertex 505.944 78.3315 281.271 + endloop + endfacet + facet normal 0.211229 -0.967695 -0.137657 + outer loop + vertex 509.16 81.618 262.316 + vertex 518.229 82.271 271.641 + vertex 508.178 80.0954 271.514 + endloop + endfacet + facet normal 0.206761 -0.969282 -0.133201 + outer loop + vertex 518.774 83.6439 262.497 + vertex 518.229 82.271 271.641 + vertex 509.16 81.618 262.316 + endloop + endfacet + facet normal 0.204522 -0.967214 -0.150557 + outer loop + vertex 519.025 86.3588 245.171 + vertex 518.895 84.9934 253.765 + vertex 509.887 84.4457 245.047 + endloop + endfacet + facet normal 0.206589 -0.9671 -0.148453 + outer loop + vertex 509.593 83.0522 253.576 + vertex 518.774 83.6439 262.497 + vertex 509.16 81.618 262.316 + endloop + endfacet + facet normal 0.218387 -0.964942 -0.145584 + outer loop + vertex 530.253 87.4716 254.377 + vertex 530.352 86.1734 263.13 + vertex 518.895 84.9934 253.765 + endloop + endfacet + facet normal 0.22022 -0.966481 -0.131978 + outer loop + vertex 518.774 83.6439 262.497 + vertex 530.225 84.9361 272.141 + vertex 518.229 82.271 271.641 + endloop + endfacet + facet normal 0.233712 -0.963606 -0.129778 + outer loop + vertex 543.026 89.1605 263.775 + vertex 543.174 87.9936 272.707 + vertex 530.352 86.1734 263.13 + endloop + endfacet + facet normal 0.234551 -0.966394 -0.10521 + outer loop + vertex 530.225 84.9361 272.141 + vertex 542.684 86.9153 281.738 + vertex 529.301 83.6907 281.521 + endloop + endfacet + facet normal 0.249849 -0.962496 -0.105717 + outer loop + vertex 556.31 91.3592 273.11 + vertex 556.239 90.358 282.056 + vertex 543.174 87.9936 272.707 + endloop + endfacet + facet normal 0.249055 -0.965646 -0.074159 + outer loop + vertex 542.684 86.9153 281.738 + vertex 555.115 89.4398 290.613 + vertex 540.976 85.8072 290.429 + endloop + endfacet + facet normal 0.262277 -0.961843 -0.0779061 + outer loop + vertex 569.453 93.9527 282.162 + vertex 568.978 93.1265 290.763 + vertex 556.239 90.358 282.056 + endloop + endfacet + facet normal 0.257188 -0.965671 -0.0365287 + outer loop + vertex 555.115 89.4398 290.613 + vertex 567.855 92.5298 298.625 + vertex 551.823 88.2972 297.644 + endloop + endfacet + facet normal 0.257509 -0.966196 -0.012472 + outer loop + vertex 567.855 92.5298 298.625 + vertex 580.223 95.8358 297.88 + vertex 580.422 95.8255 302.783 + endloop + endfacet + facet normal 0.254625 -0.966961 -0.0123568 + outer loop + vertex 580.223 95.8358 297.88 + vertex 588.557 97.9711 302.519 + vertex 580.422 95.8255 302.783 + endloop + endfacet + facet normal 0.254158 -0.967099 0.0110717 + outer loop + vertex 595.897 99.9036 302.835 + vertex 593.978 99.4225 304.85 + vertex 588.557 97.9711 302.519 + endloop + endfacet + facet normal 0.256002 -0.966572 -0.0141881 + outer loop + vertex 597.287 100.308 300.352 + vertex 601.425 101.365 303.026 + vertex 595.897 99.9036 302.835 + endloop + endfacet + facet normal 0.25855 -0.965959 -0.00867298 + outer loop + vertex 605.118 102.354 302.911 + vertex 604.379 102.138 304.961 + vertex 601.425 101.365 303.026 + endloop + endfacet + facet normal 0.275912 -0.959431 -0.0580129 + outer loop + vertex 606.289 102.875 299.157 + vertex 607.231 102.927 302.786 + vertex 604.477 102.341 299.368 + endloop + endfacet + facet normal 0.251493 -0.967792 -0.0114092 + outer loop + vertex 605.118 102.354 302.911 + vertex 606.987 102.814 305.155 + vertex 604.379 102.138 304.961 + endloop + endfacet + facet normal 0.260908 -0.964815 -0.0325301 + outer loop + vertex 607.948 103.129 302.533 + vertex 608.408 103.176 304.833 + vertex 607.231 102.927 302.786 + endloop + endfacet + facet normal 0.258598 -0.965453 -0.0320549 + outer loop + vertex 607.948 103.129 302.533 + vertex 608.772 103.272 304.89 + vertex 608.408 103.176 304.833 + endloop + endfacet + facet normal 0.24338 -0.968399 0.0544877 + outer loop + vertex 606.888 102.83 307.217 + vertex 610.266 103.666 307.004 + vertex 609.125 103.421 307.742 + endloop + endfacet + facet normal 0.244743 -0.969582 0.00339295 + outer loop + vertex 608.051 103.086 306.285 + vertex 603.98 102.059 306.394 + vertex 606.987 102.814 305.155 + endloop + endfacet + facet normal 0.231117 -0.919987 0.316557 + outer loop + vertex 588.676 98.1574 306.73 + vertex 596.27 100.141 306.95 + vertex 592.308 99.1246 306.889 + endloop + endfacet + facet normal 0.25202 -0.966514 0.0483416 + outer loop + vertex 594.898 99.7255 306.357 + vertex 582.649 96.5164 306.051 + vertex 587.488 97.7304 305.098 + endloop + endfacet + facet normal 0.248923 -0.959312 0.133257 + outer loop + vertex 577.732 95.2909 306.537 + vertex 588.676 98.1574 306.73 + vertex 585.052 97.2375 306.878 + endloop + endfacet + facet normal 0.252687 -0.966476 0.0455299 + outer loop + vertex 574.453 94.2811 304.092 + vertex 582.649 96.5164 306.051 + vertex 570.266 93.2641 305.74 + endloop + endfacet + facet normal 0.250181 -0.960354 0.123001 + outer loop + vertex 570.295 93.3395 306.428 + vertex 577.732 95.2909 306.537 + vertex 565.79 92.1924 306.636 + endloop + endfacet + facet normal 0.250367 -0.95785 0.140857 + outer loop + vertex 564.789 91.8775 306.273 + vertex 570.295 93.3395 306.428 + vertex 565.79 92.1924 306.636 + endloop + endfacet + facet normal 0.254579 -0.966228 0.0399082 + outer loop + vertex 561.5 90.8384 302.934 + vertex 570.266 93.2641 305.74 + vertex 556.696 89.6758 305.427 + endloop + endfacet + facet normal 0.250457 -0.957861 0.140619 + outer loop + vertex 557.474 89.9644 306.271 + vertex 564.789 91.8775 306.273 + vertex 565.79 92.1924 306.636 + endloop + endfacet + facet normal 0.24601 -0.942979 0.224207 + outer loop + vertex 550.359 88.0735 306.125 + vertex 557.474 89.9644 306.271 + vertex 546.178 87.0422 306.375 + endloop + endfacet + facet normal 0.253864 -0.966318 0.0422183 + outer loop + vertex 545.46 86.598 302.545 + vertex 556.696 89.6758 305.427 + vertex 543.099 86.1081 305.529 + endloop + endfacet + facet normal 0.245966 -0.937219 0.247228 + outer loop + vertex 545.121 86.7086 306.162 + vertex 550.359 88.0735 306.125 + vertex 546.178 87.0422 306.375 + endloop + endfacet + facet normal 0.240034 -0.932615 0.269469 + outer loop + vertex 538.208 84.9078 306.087 + vertex 545.121 86.7086 306.162 + vertex 546.178 87.0422 306.375 + endloop + endfacet + facet normal 0.250378 -0.965159 0.0760249 + outer loop + vertex 532.789 83.3183 304.067 + vertex 543.099 86.1081 305.529 + vertex 529.574 82.6142 305.715 + endloop + endfacet + facet normal 0.230132 -0.897271 0.376754 + outer loop + vertex 529.984 82.7801 306.043 + vertex 538.208 84.9078 306.087 + vertex 531.561 83.2307 306.153 + endloop + endfacet + facet normal 0.0465058 -0.184104 0.981806 + outer loop + vertex 522.915 80.9583 306.036 + vertex 529.984 82.7801 306.043 + vertex 524.663 81.4337 306.042 + endloop + endfacet + facet normal 0.199581 -0.756204 0.623156 + outer loop + vertex 518.297 79.7808 306.086 + vertex 522.915 80.9583 306.036 + vertex 516.817 79.4307 306.135 + endloop + endfacet + facet normal 0.184305 -0.679468 0.71018 + outer loop + vertex 516.426 79.3069 306.118 + vertex 518.297 79.7808 306.086 + vertex 516.817 79.4307 306.135 + endloop + endfacet + facet normal 0.174554 -0.652471 0.737436 + outer loop + vertex 513.823 78.6557 306.158 + vertex 516.426 79.3069 306.118 + vertex 516.817 79.4307 306.135 + endloop + endfacet + facet normal 0.240247 -0.963145 0.120965 + outer loop + vertex 509.375 77.5417 306.124 + vertex 513.823 78.6557 306.158 + vertex 510.312 77.7897 306.237 + endloop + endfacet + facet normal 0.239135 -0.962432 0.128602 + outer loop + vertex 505.472 76.5816 306.195 + vertex 509.375 77.5417 306.124 + vertex 510.312 77.7897 306.237 + endloop + endfacet + facet normal 0.234858 -0.95283 0.192239 + outer loop + vertex 500.594 75.3845 306.222 + vertex 505.472 76.5816 306.195 + vertex 506.823 76.9471 306.357 + endloop + endfacet + facet normal 0.239672 -0.96478 0.108432 + outer loop + vertex 506.823 76.9471 306.357 + vertex 495.868 74.2553 306.62 + vertex 500.594 75.3845 306.222 + endloop + endfacet + facet normal 0.234369 -0.971809 0.0256525 + outer loop + vertex 495.6 74.1734 305.966 + vertex 500.594 75.3845 306.222 + vertex 495.868 74.2553 306.62 + endloop + endfacet + facet normal 0.229504 -0.972911 0.0277824 + outer loop + vertex 488.598 72.5247 306.068 + vertex 495.6 74.1734 305.966 + vertex 495.868 74.2553 306.62 + endloop + endfacet + facet normal 0.221736 -0.975103 -0.00287465 + outer loop + vertex 493.312 73.6413 304.794 + vertex 489.442 72.7649 303.576 + vertex 491.241 73.1737 303.723 + endloop + endfacet + facet normal 0.219532 -0.974515 -0.0461183 + outer loop + vertex 486.643 72.1124 303.615 + vertex 485.54 71.8905 303.052 + vertex 487.304 72.331 302.14 + endloop + endfacet + facet normal 0.216497 -0.97558 -0.0370532 + outer loop + vertex 486.781 72.1234 304.149 + vertex 484.617 71.6423 304.176 + vertex 484.165 71.5625 303.634 + endloop + endfacet + facet normal 0.230682 -0.972864 -0.0179229 + outer loop + vertex 486.781 72.1234 304.149 + vertex 488.32 72.5013 303.453 + vertex 489.442 72.7649 303.576 + endloop + endfacet + facet normal 0.220104 -0.974449 -0.0447598 + outer loop + vertex 487.556 72.3071 303.867 + vertex 486.643 72.1124 303.615 + vertex 488.172 72.4969 302.764 + endloop + endfacet + facet normal 0.232745 -0.971756 -0.038999 + outer loop + vertex 488.32 72.5013 303.453 + vertex 489.447 72.8489 301.513 + vertex 489.442 72.7649 303.576 + endloop + endfacet + facet normal 0.23161 -0.972026 -0.0390127 + outer loop + vertex 490.794 73.2254 300.13 + vertex 489.442 72.7649 303.576 + vertex 489.447 72.8489 301.513 + endloop + endfacet + facet normal 0.228512 -0.972132 -0.0523631 + outer loop + vertex 489.447 72.8489 301.513 + vertex 489.02 72.807 300.431 + vertex 490.545 73.2869 298.176 + endloop + endfacet + facet normal 0.213226 -0.975291 -0.0578116 + outer loop + vertex 489.447 72.8489 301.513 + vertex 490.545 73.2869 298.176 + vertex 490.794 73.2254 300.13 + endloop + endfacet + facet normal 0.222706 -0.973102 -0.0589471 + outer loop + vertex 492.596 73.8866 296.023 + vertex 490.794 73.2254 300.13 + vertex 490.545 73.2869 298.176 + endloop + endfacet + facet normal 0.219319 -0.974558 -0.0462203 + outer loop + vertex 488.172 72.4969 302.764 + vertex 486.643 72.1124 303.615 + vertex 487.304 72.331 302.14 + endloop + endfacet + facet normal 0.217921 -0.974719 -0.0493335 + outer loop + vertex 487.304 72.331 302.14 + vertex 485.54 71.8905 303.052 + vertex 485.868 72.031 301.73 + endloop + endfacet + facet normal 0.215079 -0.97478 -0.0595412 + outer loop + vertex 485.868 72.031 301.73 + vertex 484.149 71.678 301.298 + vertex 486.3 72.2339 299.967 + endloop + endfacet + facet normal 0.208969 -0.975737 -0.0653392 + outer loop + vertex 484.149 71.678 301.298 + vertex 481.905 71.1518 301.98 + vertex 482.135 71.2808 300.786 + endloop + endfacet + facet normal 0.19485 -0.975204 -0.104926 + outer loop + vertex 480.802 71.5444 295.279 + vertex 484.891 72.2632 296.191 + vertex 480.806 71.2332 298.178 + endloop + endfacet + facet normal 0.196807 -0.974816 -0.104887 + outer loop + vertex 478.64 70.8482 297.693 + vertex 480.802 71.5444 295.279 + vertex 480.806 71.2332 298.178 + endloop + endfacet + facet normal 0.203223 -0.975942 -0.0789802 + outer loop + vertex 482.135 71.2808 300.786 + vertex 479.772 70.8442 300.101 + vertex 482.626 71.5159 299.146 + endloop + endfacet + facet normal 0.195477 -0.975781 -0.0981884 + outer loop + vertex 480.806 71.2332 298.178 + vertex 477.425 70.4694 299.037 + vertex 478.64 70.8482 297.693 + endloop + endfacet + facet normal 0.19742 -0.977268 -0.0772786 + outer loop + vertex 479.348 70.6577 301.378 + vertex 476.259 70.1208 300.276 + vertex 479.772 70.8442 300.101 + endloop + endfacet + facet normal 0.186861 -0.978634 -0.0857826 + outer loop + vertex 476.259 70.1208 300.276 + vertex 471.827 69.3571 299.334 + vertex 474.014 69.8046 298.992 + endloop + endfacet + facet normal 0.18861 -0.976466 -0.104592 + outer loop + vertex 478.64 70.8482 297.693 + vertex 477.425 70.4694 299.037 + vertex 475.392 70.2793 297.146 + endloop + endfacet + facet normal 0.183285 -0.977235 -0.106856 + outer loop + vertex 474.014 69.8046 298.992 + vertex 471.827 69.3571 299.334 + vertex 470.19 69.2384 297.613 + endloop + endfacet + facet normal 0.18961 -0.975504 -0.111533 + outer loop + vertex 478.64 70.8482 297.693 + vertex 475.392 70.2793 297.146 + vertex 480.802 71.5444 295.279 + endloop + endfacet + facet normal 0.170338 -0.974463 -0.146309 + outer loop + vertex 478.44 72.144 287.153 + vertex 473.503 70.9433 289.402 + vertex 475.347 71.8102 285.775 + endloop + endfacet + facet normal 0.170935 -0.974145 -0.147727 + outer loop + vertex 478.44 72.144 287.153 + vertex 475.347 71.8102 285.775 + vertex 481.257 73.2535 283.096 + endloop + endfacet + facet normal 0.179902 -0.975489 -0.126715 + outer loop + vertex 476.541 70.8984 293.828 + vertex 472.001 70.2174 292.625 + vertex 477.778 71.5918 290.245 + endloop + endfacet + facet normal 0.167249 -0.974373 -0.150418 + outer loop + vertex 473.503 70.9433 289.402 + vertex 467.514 69.5989 291.452 + vertex 469.291 70.3928 288.285 + endloop + endfacet + facet normal 0.175421 -0.975674 -0.131482 + outer loop + vertex 470.866 69.6268 295.493 + vertex 466.304 68.9905 294.128 + vertex 472.001 70.2174 292.625 + endloop + endfacet + facet normal 0.166643 -0.974921 -0.147512 + outer loop + vertex 466.304 68.9905 294.128 + vertex 461.482 68.058 294.844 + vertex 461.826 68.419 292.847 + endloop + endfacet + facet normal 0.161204 -0.975672 -0.148586 + outer loop + vertex 461.482 68.058 294.844 + vertex 457.312 67.591 293.385 + vertex 461.826 68.419 292.847 + endloop + endfacet + facet normal 0.157136 -0.978145 -0.136162 + outer loop + vertex 457.312 67.591 293.385 + vertex 461.482 68.058 294.844 + vertex 455.419 67.1748 294.191 + endloop + endfacet + facet normal 0.148192 -0.976527 -0.156315 + outer loop + vertex 457.312 67.591 293.385 + vertex 455.419 67.1748 294.191 + vertex 452.749 67.0778 292.266 + endloop + endfacet + facet normal 0.137561 -0.976396 -0.166515 + outer loop + vertex 448.64 66.7329 290.894 + vertex 452.749 67.0778 292.266 + vertex 447.183 66.3833 291.74 + endloop + endfacet + facet normal 0.12428 -0.974183 -0.188472 + outer loop + vertex 448.64 66.7329 290.894 + vertex 447.183 66.3833 291.74 + vertex 443.462 66.3113 289.658 + endloop + endfacet + facet normal 0.1368 -0.972988 -0.185958 + outer loop + vertex 453.161 67.4672 290.444 + vertex 448.595 67.061 289.21 + vertex 454.496 68.1117 288.053 + endloop + endfacet + facet normal 0.146718 -0.972604 -0.180317 + outer loop + vertex 458.837 68.56 289.168 + vertex 453.161 67.4672 290.444 + vertex 454.496 68.1117 288.053 + endloop + endfacet + facet normal 0.155493 -0.973258 -0.16909 + outer loop + vertex 463.137 69.0522 290.289 + vertex 457.476 67.9148 291.63 + vertex 458.837 68.56 289.168 + endloop + endfacet + facet normal 0.162448 -0.97475 -0.153207 + outer loop + vertex 467.514 69.5989 291.452 + vertex 463.137 69.0522 290.289 + vertex 469.291 70.3928 288.285 + endloop + endfacet + facet normal 0.166724 -0.974799 -0.148226 + outer loop + vertex 473.503 70.9433 289.402 + vertex 469.291 70.3928 288.285 + vertex 475.347 71.8102 285.775 + endloop + endfacet + facet normal 0.156484 -0.974238 -0.162397 + outer loop + vertex 471.109 71.2791 284.622 + vertex 464.958 69.8604 287.206 + vertex 466.66 70.7239 283.666 + endloop + endfacet + facet normal 0.148921 -0.974115 -0.170067 + outer loop + vertex 466.66 70.7239 283.666 + vertex 460.647 69.3658 286.179 + vertex 462.34 70.2236 282.748 + endloop + endfacet + facet normal 0.142392 -0.974506 -0.173387 + outer loop + vertex 460.647 69.3658 286.179 + vertex 456.306 68.9154 285.146 + vertex 462.34 70.2236 282.748 + endloop + endfacet + facet normal 0.133082 -0.972981 -0.188673 + outer loop + vertex 456.306 68.9154 285.146 + vertex 449.926 67.7083 286.87 + vertex 451.809 68.5137 284.045 + endloop + endfacet + facet normal 0.12085 -0.972753 -0.197854 + outer loop + vertex 451.809 68.5137 284.045 + vertex 445.209 67.3984 285.498 + vertex 447.179 68.1989 282.765 + endloop + endfacet + facet normal 0.109183 -0.972407 -0.206162 + outer loop + vertex 445.209 67.3984 285.498 + vertex 441.334 67.2936 283.94 + vertex 447.179 68.1989 282.765 + endloop + endfacet + facet normal 0.0942628 -0.97044 -0.222173 + outer loop + vertex 441.334 67.2936 283.94 + vertex 438.067 66.5657 285.733 + vertex 434.909 66.9574 282.682 + endloop + endfacet + facet normal 0.0722548 -0.972342 -0.222103 + outer loop + vertex 434.909 66.9574 282.682 + vertex 424.757 66.7148 280.441 + vertex 436.484 68.1913 277.793 + endloop + endfacet + facet normal 0.105798 -0.973807 -0.201263 + outer loop + vertex 448.763 69.0618 279.448 + vertex 442.086 67.9952 281.098 + vertex 444.362 68.8981 277.926 + endloop + endfacet + facet normal 0.07015 -0.974655 -0.212431 + outer loop + vertex 436.484 68.1913 277.793 + vertex 427.332 68.1517 274.952 + vertex 439.179 69.8956 270.863 + endloop + endfacet + facet normal 0.102593 -0.974253 -0.200764 + outer loop + vertex 449.93 69.9546 275.644 + vertex 444.362 68.8981 277.926 + vertex 444.526 69.6865 274.184 + endloop + endfacet + facet normal 0.113384 -0.975661 -0.187697 + outer loop + vertex 454.748 70.2795 276.866 + vertex 449.93 69.9546 275.644 + vertex 455.289 71.0942 272.958 + endloop + endfacet + facet normal 0.125914 -0.974315 -0.186695 + outer loop + vertex 459.309 70.6678 277.916 + vertex 453.514 69.3815 280.721 + vertex 454.748 70.2795 276.866 + endloop + endfacet + facet normal 0.136299 -0.97443 -0.178628 + outer loop + vertex 463.639 71.1057 278.831 + vertex 458.014 69.7792 281.775 + vertex 459.309 70.6678 277.916 + endloop + endfacet + facet normal 0.144891 -0.974793 -0.169662 + outer loop + vertex 467.945 71.599 279.674 + vertex 463.639 71.1057 278.831 + vertex 469.071 72.6135 274.807 + endloop + endfacet + facet normal 0.131714 -0.974743 -0.180355 + outer loop + vertex 464.281 71.9096 274.848 + vertex 460.401 71.6883 273.21 + vertex 468.252 73.6115 268.55 + endloop + endfacet + facet normal 0.149304 -0.974256 -0.168917 + outer loop + vertex 472.946 72.9612 276.226 + vertex 469.071 72.6135 274.807 + vertex 476.667 74.709 269.435 + endloop + endfacet + facet normal 0.127243 -0.976762 -0.172468 + outer loop + vertex 468.252 73.6115 268.55 + vertex 459.383 72.7179 267.067 + vertex 469.324 75.3757 259.349 + endloop + endfacet + facet normal 0.110143 -0.974943 -0.193273 + outer loop + vertex 449.929 71.9684 265.461 + vertex 459.383 72.7179 267.067 + vertex 450.992 70.9672 271.117 + endloop + endfacet + facet normal 0.0862301 -0.975443 -0.202669 + outer loop + vertex 446.182 70.5821 270.539 + vertex 439.179 69.8956 270.863 + vertex 449.929 71.9684 265.461 + endloop + endfacet + facet normal 0.068682 -0.973895 -0.216361 + outer loop + vertex 439.179 69.8956 270.863 + vertex 427.332 68.1517 274.952 + vertex 429.661 69.7398 268.543 + endloop + endfacet + facet normal 0.0370825 -0.97304 -0.227634 + outer loop + vertex 427.332 68.1517 274.952 + vertex 418.559 68.357 272.645 + vertex 429.661 69.7398 268.543 + endloop + endfacet + facet normal -0.00401928 -0.9611 -0.276171 + outer loop + vertex 418.559 68.357 272.645 + vertex 408.864 67.5224 275.691 + vertex 409.164 68.9998 270.545 + endloop + endfacet + facet normal 0.0262198 -0.974248 -0.223949 + outer loop + vertex 432.263 71.3868 261.535 + vertex 420.74 69.915 266.588 + vertex 423.66 71.5158 259.966 + endloop + endfacet + facet normal 0.0609502 -0.979341 -0.19281 + outer loop + vertex 441.022 71.6019 263.211 + vertex 432.263 71.3868 261.535 + vertex 443.331 73.2665 255.486 + endloop + endfacet + facet normal 0.0867985 -0.9789 -0.184989 + outer loop + vertex 451.837 73.771 256.808 + vertex 441.022 71.6019 263.211 + vertex 443.331 73.2665 255.486 + endloop + endfacet + facet normal 0.105403 -0.979791 -0.170001 + outer loop + vertex 460.595 74.4754 258.178 + vertex 451.837 73.771 256.808 + vertex 462.076 76.1107 249.671 + endloop + endfacet + facet normal 0.122942 -0.978319 -0.166664 + outer loop + vertex 470.508 77.0211 250.547 + vertex 460.595 74.4754 258.178 + vertex 462.076 76.1107 249.671 + endloop + endfacet + facet normal 0.137436 -0.978354 -0.154708 + outer loop + vertex 478.616 78.0505 251.24 + vertex 470.508 77.0211 250.547 + vertex 479.707 79.5781 242.549 + endloop + endfacet + facet normal 0.150357 -0.976751 -0.152805 + outer loop + vertex 486.778 80.5956 243.002 + vertex 478.616 78.0505 251.24 + vertex 479.707 79.5781 242.549 + endloop + endfacet + facet normal 0.150317 -0.976751 -0.152845 + outer loop + vertex 485.783 79.0662 251.797 + vertex 478.616 78.0505 251.24 + vertex 486.778 80.5956 243.002 + endloop + endfacet + facet normal 0.152495 -0.975435 -0.158972 + outer loop + vertex 484.833 77.4748 260.65 + vertex 477.544 76.4085 260.202 + vertex 485.783 79.0662 251.797 + endloop + endfacet + facet normal 0.157828 -0.974404 -0.160086 + outer loop + vertex 484.263 76.0084 269.015 + vertex 476.667 74.709 269.435 + vertex 484.833 77.4748 260.65 + endloop + endfacet + facet normal 0.157509 -0.973805 -0.163999 + outer loop + vertex 476.667 74.709 269.435 + vertex 484.263 76.0084 269.015 + vertex 478.061 73.8831 275.678 + endloop + endfacet + facet normal 0.161731 -0.974105 -0.157998 + outer loop + vertex 477.192 72.8398 281.221 + vertex 472.441 72.1824 280.41 + vertex 478.061 73.8831 275.678 + endloop + endfacet + facet normal 0.169094 -0.973865 -0.151638 + outer loop + vertex 481.257 73.2535 283.096 + vertex 475.347 71.8102 285.775 + vertex 477.192 72.8398 281.221 + endloop + endfacet + facet normal 0.172451 -0.973615 -0.149448 + outer loop + vertex 487.94 74.8474 280.482 + vertex 483.464 74.6359 276.695 + vertex 489.616 76.7017 270.336 + endloop + endfacet + facet normal 0.163976 -0.974828 -0.151069 + outer loop + vertex 493.884 77.0333 272.829 + vertex 487.94 74.8474 280.482 + vertex 489.616 76.7017 270.336 + endloop + endfacet + facet normal 0.177575 -0.973664 -0.142987 + outer loop + vertex 478.44 72.144 287.153 + vertex 481.257 73.2535 283.096 + vertex 482.737 73.006 286.619 + endloop + endfacet + facet normal 0.18146 -0.974751 -0.130124 + outer loop + vertex 486.208 73.5668 287.259 + vertex 482.042 72.3014 290.93 + vertex 482.737 73.006 286.619 + endloop + endfacet + facet normal 0.187981 -0.974487 -0.122632 + outer loop + vertex 485.901 72.9791 291.459 + vertex 482.042 72.3014 290.93 + vertex 486.208 73.5668 287.259 + endloop + endfacet + facet normal 0.195039 -0.975064 -0.105881 + outer loop + vertex 484.891 72.2632 296.191 + vertex 480.802 71.5444 295.279 + vertex 485.901 72.9791 291.459 + endloop + endfacet + facet normal 0.20091 -0.975577 -0.0887991 + outer loop + vertex 484.891 72.2632 296.191 + vertex 487.964 72.8223 297.001 + vertex 484.841 71.976 299.234 + endloop + endfacet + facet normal 0.203287 -0.97635 -0.0735877 + outer loop + vertex 487.964 72.8223 297.001 + vertex 489.573 73.0979 297.789 + vertex 487.874 72.5841 299.913 + endloop + endfacet + facet normal 0.214343 -0.974757 -0.0625006 + outer loop + vertex 490.545 73.2869 298.176 + vertex 489.02 72.807 300.431 + vertex 489.573 73.0979 297.789 + endloop + endfacet + facet normal 0.201055 -0.975586 -0.0883732 + outer loop + vertex 492.596 73.8866 296.023 + vertex 493.933 74.7059 290.02 + vertex 495.762 74.7701 293.474 + endloop + endfacet + facet normal 0.199807 -0.974349 -0.10354 + outer loop + vertex 491.084 73.75 293.892 + vertex 489.059 73.5306 292.048 + vertex 492.208 74.6467 287.623 + endloop + endfacet + facet normal 0.193217 -0.974513 -0.113983 + outer loop + vertex 493.933 74.7059 290.02 + vertex 495.033 75.6797 283.56 + vertex 497.107 75.6406 287.409 + endloop + endfacet + facet normal 0.182859 -0.974761 -0.128074 + outer loop + vertex 492.208 74.6467 287.623 + vertex 489.538 74.2835 286.575 + vertex 492.698 75.5889 281.151 + endloop + endfacet + facet normal 0.193646 -0.972115 -0.132267 + outer loop + vertex 495.033 75.6797 283.56 + vertex 495.529 76.5824 277.652 + vertex 498.708 76.9154 279.859 + endloop + endfacet + facet normal 0.172172 -0.974399 -0.14458 + outer loop + vertex 492.698 75.5889 281.151 + vertex 487.94 74.8474 280.482 + vertex 493.884 77.0333 272.829 + endloop + endfacet + facet normal 0.197033 -0.970727 -0.137356 + outer loop + vertex 495.529 76.5824 277.652 + vertex 497.208 77.5363 273.319 + vertex 498.708 76.9154 279.859 + endloop + endfacet + facet normal 0.194226 -0.969557 -0.149116 + outer loop + vertex 497.208 77.5363 273.319 + vertex 497.653 78.5952 267.014 + vertex 501.074 78.5018 272.076 + endloop + endfacet + facet normal 0.16586 -0.973986 -0.154406 + outer loop + vertex 493.884 77.0333 272.829 + vertex 489.616 76.7017 270.336 + vertex 494.983 78.7834 262.969 + endloop + endfacet + facet normal 0.186356 -0.970592 -0.152389 + outer loop + vertex 497.653 78.5952 267.014 + vertex 498.028 79.4889 261.779 + vertex 501.729 79.9927 263.097 + endloop + endfacet + facet normal 0.187852 -0.969571 -0.156981 + outer loop + vertex 498.028 79.4889 261.779 + vertex 498.532 80.3508 257.06 + vertex 501.729 79.9927 263.097 + endloop + endfacet + facet normal 0.163064 -0.973878 -0.158024 + outer loop + vertex 494.983 78.7834 262.969 + vertex 490.57 78.3087 261.341 + vertex 495.455 80.2668 254.314 + endloop + endfacet + facet normal 0.18056 -0.971072 -0.156261 + outer loop + vertex 498.532 80.3508 257.06 + vertex 499.146 81.6559 249.658 + vertex 502.926 81.5597 254.625 + endloop + endfacet + facet normal 0.163619 -0.974228 -0.155269 + outer loop + vertex 495.455 80.2668 254.314 + vertex 491.469 79.8765 252.564 + vertex 496.632 81.8783 245.444 + endloop + endfacet + facet normal 0.178243 -0.971839 -0.154139 + outer loop + vertex 499.146 81.6559 249.658 + vertex 499.479 82.5205 244.592 + vertex 502.985 82.9591 245.881 + endloop + endfacet + facet normal 0.175753 -0.973423 -0.146828 + outer loop + vertex 499.479 82.5205 244.592 + vertex 499.878 83.3013 239.893 + vertex 502.985 82.9591 245.881 + endloop + endfacet + facet normal 0.16671 -0.975254 -0.145212 + outer loop + vertex 496.632 81.8783 245.444 + vertex 492.359 81.3904 243.815 + vertex 496.998 83.2083 236.931 + endloop + endfacet + facet normal 0.182347 -0.973382 -0.138842 + outer loop + vertex 499.878 83.3013 239.893 + vertex 500.347 84.447 232.477 + vertex 503.901 84.3856 237.575 + endloop + endfacet + facet normal 0.176805 -0.974944 -0.134997 + outer loop + vertex 503.893 85.6112 228.713 + vertex 503.901 84.3856 237.575 + vertex 500.347 84.447 232.477 + endloop + endfacet + facet normal 0.168694 -0.976685 -0.132771 + outer loop + vertex 496.998 83.2083 236.931 + vertex 493.189 82.8139 234.993 + vertex 497.977 84.6164 227.818 + endloop + endfacet + facet normal 0.180813 -0.974733 -0.131157 + outer loop + vertex 500.347 84.447 232.477 + vertex 500.561 85.1887 227.26 + vertex 503.893 85.6112 228.713 + endloop + endfacet + facet normal 0.177728 -0.975909 -0.126547 + outer loop + vertex 497.977 84.6164 227.818 + vertex 493.189 82.8139 234.993 + vertex 493.944 84.1222 225.964 + endloop + endfacet + facet normal 0.16382 -0.978384 -0.126206 + outer loop + vertex 493.944 84.1222 225.964 + vertex 487.689 82.0047 234.26 + vertex 488.538 83.2786 225.486 + endloop + endfacet + facet normal 0.150567 -0.980309 -0.127768 + outer loop + vertex 487.689 82.0047 234.26 + vertex 480.753 80.974 233.995 + vertex 488.538 83.2786 225.486 + endloop + endfacet + facet normal 0.138346 -0.980152 -0.141993 + outer loop + vertex 480.753 80.974 233.995 + vertex 471.762 78.534 242.078 + vertex 472.973 79.9149 233.726 + endloop + endfacet + facet normal 0.122334 -0.981898 -0.144605 + outer loop + vertex 471.762 78.534 242.078 + vertex 463.574 77.6029 241.473 + vertex 472.973 79.9149 233.726 + endloop + endfacet + facet normal 0.106245 -0.981752 -0.157721 + outer loop + vertex 463.574 77.6029 241.473 + vertex 453.729 75.3717 248.73 + vertex 455.507 76.8341 240.825 + endloop + endfacet + facet normal 0.0848525 -0.983009 -0.162765 + outer loop + vertex 453.729 75.3717 248.73 + vertex 445.583 74.81 247.875 + vertex 455.507 76.8341 240.825 + endloop + endfacet + facet normal 0.058101 -0.98155 -0.182164 + outer loop + vertex 445.583 74.81 247.875 + vertex 434.994 72.9825 254.345 + vertex 437.486 74.4822 247.059 + endloop + endfacet + facet normal 0.020778 -0.980634 -0.194742 + outer loop + vertex 434.994 72.9825 254.345 + vertex 426.597 73.0479 253.12 + vertex 437.486 74.4822 247.059 + endloop + endfacet + facet normal -0.0209071 -0.973956 -0.225771 + outer loop + vertex 426.597 73.0479 253.12 + vertex 414.902 72.1325 258.152 + vertex 417.906 73.5997 251.544 + endloop + endfacet + facet normal 0.0189158 -0.983497 -0.179936 + outer loop + vertex 439.68 75.8849 239.611 + vertex 429.222 74.5022 246.069 + vertex 431.57 75.8777 238.798 + endloop + endfacet + facet normal 0.0566059 -0.986301 -0.154942 + outer loop + vertex 447.594 76.2432 240.221 + vertex 439.68 75.8849 239.611 + vertex 449.392 77.5764 232.392 + endloop + endfacet + facet normal 0.0859237 -0.985244 -0.148028 + outer loop + vertex 457.115 78.1834 232.834 + vertex 447.594 76.2432 240.221 + vertex 449.392 77.5764 232.392 + endloop + endfacet + facet normal 0.10621 -0.985696 -0.130856 + outer loop + vertex 464.983 78.9678 233.311 + vertex 457.115 78.1834 232.834 + vertex 466.293 80.2102 225.016 + endloop + endfacet + facet normal 0.124788 -0.983937 -0.127659 + outer loop + vertex 474.105 81.1648 225.295 + vertex 464.983 78.9678 233.311 + vertex 466.293 80.2102 225.016 + endloop + endfacet + facet normal 0.139516 -0.984027 -0.110569 + outer loop + vertex 481.729 82.2324 225.414 + vertex 474.105 81.1648 225.295 + vertex 482.635 83.3366 216.73 + endloop + endfacet + facet normal 0.153581 -0.982121 -0.108859 + outer loop + vertex 489.307 84.3864 216.672 + vertex 481.729 82.2324 225.414 + vertex 482.635 83.3366 216.73 + endloop + endfacet + facet normal 0.165376 -0.982039 -0.0908288 + outer loop + vertex 494.58 85.2478 216.958 + vertex 489.307 84.3864 216.672 + vertex 495.227 86.1822 208.035 + endloop + endfacet + facet normal 0.177653 -0.981397 -0.0727916 + outer loop + vertex 498.734 86.7137 209.428 + vertex 495.227 86.1822 208.035 + vertex 499.686 87.568 200.232 + endloop + endfacet + facet normal 0.200706 -0.977147 -0.0700113 + outer loop + vertex 498.734 86.7137 209.428 + vertex 499.686 87.568 200.232 + vertex 501.895 87.6752 205.068 + endloop + endfacet + facet normal 0.169899 -0.983122 -0.0678612 + outer loop + vertex 495.866 86.9192 199.134 + vertex 490.054 85.3152 207.819 + vertex 490.818 86.0605 198.935 + endloop + endfacet + facet normal 0.155792 -0.985359 -0.0692618 + outer loop + vertex 490.054 85.3152 207.819 + vertex 483.532 84.2736 207.968 + vertex 490.818 86.0605 198.935 + endloop + endfacet + facet normal 0.142053 -0.985762 -0.0899713 + outer loop + vertex 483.532 84.2736 207.968 + vertex 475.182 82.2703 216.733 + vertex 476.244 83.2124 208.089 + endloop + endfacet + facet normal 0.125741 -0.98777 -0.0921954 + outer loop + vertex 475.182 82.2703 216.733 + vertex 467.555 81.3136 216.582 + vertex 476.244 83.2124 208.089 + endloop + endfacet + facet normal 0.108403 -0.987808 -0.111737 + outer loop + vertex 467.555 81.3136 216.582 + vertex 458.613 79.417 224.674 + vertex 460.077 80.5148 216.389 + endloop + endfacet + facet normal 0.0857319 -0.989546 -0.115972 + outer loop + vertex 458.613 79.417 224.674 + vertex 451.091 78.7992 224.384 + vertex 460.077 80.5148 216.389 + endloop + endfacet + facet normal 0.0568193 -0.988739 -0.138441 + outer loop + vertex 451.091 78.7992 224.384 + vertex 441.673 77.1986 231.95 + vertex 443.593 78.4055 224.119 + endloop + endfacet + facet normal 0.0160465 -0.98879 -0.148447 + outer loop + vertex 441.673 77.1986 231.95 + vertex 433.779 77.1641 231.326 + vertex 443.593 78.4055 224.119 + endloop + endfacet + facet normal -0.0302002 -0.983254 -0.179722 + outer loop + vertex 433.779 77.1641 231.326 + vertex 423.168 76.3403 237.617 + vertex 425.611 77.5945 230.344 + endloop + endfacet + facet normal 0.0129437 -0.991006 -0.133193 + outer loop + vertex 445.486 79.4918 216.157 + vertex 435.926 78.3569 223.672 + vertex 438.054 79.4307 215.889 + endloop + endfacet + facet normal 0.0557394 -0.99307 -0.103461 + outer loop + vertex 452.769 79.8898 216.26 + vertex 445.486 79.4918 216.157 + vertex 454.436 80.838 208.057 + endloop + endfacet + facet normal 0.0867324 -0.9915 -0.0969808 + outer loop + vertex 461.535 81.4614 208.033 + vertex 452.769 79.8898 216.26 + vertex 454.436 80.838 208.057 + endloop + endfacet + facet normal 0.109066 -0.991249 -0.0743591 + outer loop + vertex 468.81 82.2584 208.078 + vertex 461.535 81.4614 208.033 + vertex 470.067 83.0371 199.541 + endloop + endfacet + facet normal 0.127402 -0.989272 -0.07148 + outer loop + vertex 477.309 83.9791 199.412 + vertex 468.81 82.2584 208.078 + vertex 470.067 83.0371 199.541 + endloop + endfacet + facet normal 0.143869 -0.988355 -0.0495661 + outer loop + vertex 484.418 85.0261 199.17 + vertex 477.309 83.9791 199.412 + vertex 485.321 85.5993 190.363 + endloop + endfacet + facet normal 0.15747 -0.986354 -0.0480409 + outer loop + vertex 491.564 86.6111 190.051 + vertex 484.418 85.0261 199.17 + vertex 485.321 85.5993 190.363 + endloop + endfacet + facet normal 0.170402 -0.98499 -0.0275328 + outer loop + vertex 496.504 87.4608 190.229 + vertex 491.564 86.6111 190.051 + vertex 497.176 87.8264 181.306 + endloop + endfacet + facet normal 0.181869 -0.983274 -0.00976422 + outer loop + vertex 500.815 88.4872 182.534 + vertex 497.176 87.8264 181.306 + vertex 501.067 88.6197 173.898 + endloop + endfacet + facet normal 0.203448 -0.979044 -0.00906881 + outer loop + vertex 500.815 88.4872 182.534 + vertex 501.067 88.6197 173.898 + vertex 503.136 89.0285 176.17 + endloop + endfacet + facet normal 0.171818 -0.985102 -0.00727198 + outer loop + vertex 497.823 88.0073 172.394 + vertex 492.326 86.9839 181.158 + vertex 493.07 87.1792 172.258 + endloop + endfacet + facet normal 0.158967 -0.987248 -0.00839277 + outer loop + vertex 492.326 86.9839 181.158 + vertex 486.226 85.9984 181.545 + vertex 493.07 87.1792 172.258 + endloop + endfacet + facet normal 0.143209 -0.989203 -0.0311288 + outer loop + vertex 486.226 85.9984 181.545 + vertex 478.379 84.5735 190.722 + vertex 479.441 85.0014 182.01 + endloop + endfacet + facet normal 0.12812 -0.991207 -0.0330653 + outer loop + vertex 478.379 84.5735 190.722 + vertex 471.317 83.6522 190.976 + vertex 479.441 85.0014 182.01 + endloop + endfacet + facet normal 0.108467 -0.992506 -0.056278 + outer loop + vertex 471.317 83.6522 190.976 + vertex 462.987 82.251 199.633 + vertex 464.425 82.8869 191.188 + endloop + endfacet + facet normal 0.0866377 -0.994423 -0.0601386 + outer loop + vertex 462.987 82.251 199.633 + vertex 456.085 81.6402 199.79 + vertex 464.425 82.8869 191.188 + endloop + endfacet + facet normal 0.0532275 -0.994736 -0.0875642 + outer loop + vertex 456.085 81.6402 199.79 + vertex 447.367 80.4414 208.109 + vertex 449.221 81.2561 199.981 + endloop + endfacet + facet normal 0.00675832 -0.996655 -0.081447 + outer loop + vertex 449.221 81.2561 199.981 + vertex 442.222 81.2059 200.014 + vertex 451.047 81.9386 191.78 + endloop + endfacet + facet normal -0.049166 -0.99154 -0.120133 + outer loop + vertex 442.222 81.2059 200.014 + vertex 432.705 80.765 207.549 + vertex 434.999 81.6015 199.706 + endloop + endfacet + facet normal -0.00382046 -0.99734 -0.0727905 + outer loop + vertex 452.842 82.4928 183.508 + vertex 444.259 81.9098 191.946 + vertex 446.255 82.4971 183.794 + endloop + endfacet + facet normal 0.0481481 -0.998157 -0.0369426 + outer loop + vertex 459.312 82.8209 183.075 + vertex 452.842 82.4928 183.508 + vertex 460.878 83.2095 174.617 + endloop + endfacet + facet normal 0.0819111 -0.995561 -0.0463654 + outer loop + vertex 465.839 83.3759 182.69 + vertex 457.714 82.2987 191.466 + vertex 459.312 82.8209 183.075 + endloop + endfacet + facet normal 0.107762 -0.993971 -0.0202063 + outer loop + vertex 472.551 84.1101 182.369 + vertex 465.839 83.3759 182.69 + vertex 473.762 84.4173 173.716 + endloop + endfacet + facet normal 0.124548 -0.992054 -0.0177896 + outer loop + vertex 480.483 85.2692 173.264 + vertex 472.551 84.1101 182.369 + vertex 473.762 84.4173 173.716 + endloop + endfacet + facet normal 0.143712 -0.989596 0.00686595 + outer loop + vertex 487.117 86.2287 172.709 + vertex 480.483 85.2692 173.264 + vertex 487.976 86.2919 163.843 + endloop + endfacet + facet normal 0.155768 -0.987761 0.0080469 + outer loop + vertex 493.831 87.211 163.313 + vertex 487.117 86.2287 172.709 + vertex 487.976 86.2919 163.843 + endloop + endfacet + facet normal 0.170106 -0.984958 0.0303488 + outer loop + vertex 498.451 88.0132 163.45 + vertex 493.831 87.211 163.313 + vertex 499.08 87.8434 154.415 + endloop + endfacet + facet normal 0.178507 -0.982824 0.046831 + outer loop + vertex 502.177 88.4846 156.069 + vertex 499.08 87.8434 154.415 + vertex 503.092 88.2023 146.654 + endloop + endfacet + facet normal 0.199695 -0.978644 0.048766 + outer loop + vertex 502.177 88.4846 156.069 + vertex 503.092 88.2023 146.654 + vertex 504.994 88.8632 152.129 + endloop + endfacet + facet normal 0.164606 -0.985256 0.0466472 + outer loop + vertex 499.748 87.5005 145.174 + vertex 494.541 87.0639 154.326 + vertex 495.25 86.755 145.301 + endloop + endfacet + facet normal 0.154661 -0.9869 0.0459226 + outer loop + vertex 494.541 87.0639 154.326 + vertex 488.818 86.1956 154.942 + vertex 495.25 86.755 145.301 + endloop + endfacet + facet normal 0.136001 -0.990512 0.0197243 + outer loop + vertex 488.818 86.1956 154.942 + vertex 481.499 85.3805 164.475 + vertex 482.489 85.3407 155.653 + endloop + endfacet + facet normal 0.123071 -0.992229 0.0182816 + outer loop + vertex 481.499 85.3805 164.475 + vertex 474.942 84.577 165.007 + vertex 482.489 85.3407 155.653 + endloop + endfacet + facet normal 0.100133 -0.994938 -0.00845106 + outer loop + vertex 474.942 84.577 165.007 + vertex 467.225 83.7228 174.129 + vertex 468.572 83.9317 165.508 + endloop + endfacet + facet normal 0.0750814 -0.997173 0.00287284 + outer loop + vertex 468.572 83.9317 165.508 + vertex 462.399 83.4686 166.09 + vertex 469.87 84.0044 156.839 + endloop + endfacet + facet normal 0.034126 -0.998955 -0.0303875 + outer loop + vertex 462.399 83.4686 166.09 + vertex 454.59 82.9261 175.154 + vertex 456.286 83.2404 166.725 + endloop + endfacet + facet normal -0.0200104 -0.998631 -0.0483331 + outer loop + vertex 456.286 83.2404 166.725 + vertex 448.199 82.9754 175.55 + vertex 450.09 83.34 167.233 + endloop + endfacet + facet normal -0.0871118 -0.99351 -0.0731397 + outer loop + vertex 450.09 83.34 167.233 + vertex 441.62 83.4656 175.614 + vertex 443.705 83.8874 167.403 + endloop + endfacet + facet normal -0.0293865 -0.999452 -0.0152538 + outer loop + vertex 457.921 83.4344 158.249 + vertex 451.896 83.6023 158.854 + vertex 459.465 83.5186 149.754 + endloop + endfacet + facet normal 0.015154 -0.99986 -0.00716282 + outer loop + vertex 465.248 83.6122 148.923 + vertex 457.921 83.4344 158.249 + vertex 459.465 83.5186 149.754 + endloop + endfacet + facet normal 0.0577836 -0.998295 0.00822307 + outer loop + vertex 471.107 83.945 148.154 + vertex 463.857 83.6025 157.512 + vertex 465.248 83.6122 148.923 + endloop + endfacet + facet normal 0.089938 -0.995122 0.0405454 + outer loop + vertex 477.172 84.4659 147.485 + vertex 471.107 83.945 148.154 + vertex 478.219 84.2036 138.727 + endloop + endfacet + facet normal 0.111358 -0.99338 0.028211 + outer loop + vertex 483.438 85.149 146.805 + vertex 476.082 84.5928 156.257 + vertex 477.172 84.4659 147.485 + endloop + endfacet + facet normal 0.133973 -0.98933 0.0572545 + outer loop + vertex 489.646 85.9445 146.025 + vertex 483.438 85.149 146.805 + vertex 490.437 85.5355 137.108 + endloop + endfacet + facet normal 0.143545 -0.98794 0.0580392 + outer loop + vertex 495.955 86.2903 136.307 + vertex 489.646 85.9445 146.025 + vertex 490.437 85.5355 137.108 + endloop + endfacet + facet normal 0.161177 -0.98339 0.083468 + outer loop + vertex 500.342 86.9852 136.023 + vertex 495.955 86.2903 136.307 + vertex 500.955 86.3223 127.029 + endloop + endfacet + facet normal 0.16932 -0.980358 0.101142 + outer loop + vertex 503.925 86.9323 127.97 + vertex 500.955 86.3223 127.029 + vertex 504.752 86.143 118.935 + endloop + endfacet + facet normal 0.19581 -0.975205 0.103118 + outer loop + vertex 503.925 86.9323 127.97 + vertex 504.752 86.143 118.935 + vertex 506.229 86.8859 123.155 + endloop + endfacet + facet normal 0.148671 -0.984194 0.0962203 + outer loop + vertex 501.524 85.5027 118.117 + vertex 496.623 85.6662 127.362 + vertex 497.268 84.8933 118.461 + endloop + endfacet + facet normal 0.140069 -0.985505 0.0957112 + outer loop + vertex 496.623 85.6662 127.362 + vertex 491.213 84.98 128.213 + vertex 497.268 84.8933 118.461 + endloop + endfacet + facet normal 0.117279 -0.990938 0.0654775 + outer loop + vertex 491.213 84.98 128.213 + vertex 484.357 84.8126 137.96 + vertex 485.246 84.3355 129.147 + endloop + endfacet + facet normal 0.0976192 -0.992106 0.0787202 + outer loop + vertex 485.246 84.3355 129.147 + vertex 479.238 83.8135 130.018 + vertex 486.103 83.7259 120.403 + endloop + endfacet + facet normal 0.0679878 -0.996706 0.0442219 + outer loop + vertex 479.238 83.8135 130.018 + vertex 472.289 83.7599 139.494 + vertex 473.431 83.4558 130.885 + endloop + endfacet + facet normal 0.0353111 -0.9989 0.0308575 + outer loop + vertex 473.431 83.4558 130.885 + vertex 466.568 83.5058 140.359 + vertex 467.827 83.287 131.834 + endloop + endfacet + facet normal 0.00677133 -0.999622 0.0266593 + outer loop + vertex 466.568 83.5058 140.359 + vertex 460.926 83.4922 141.281 + vertex 467.827 83.287 131.834 + endloop + endfacet + facet normal -0.0590899 -0.998096 -0.017692 + outer loop + vertex 460.926 83.4922 141.281 + vertex 453.604 83.7631 150.455 + vertex 455.219 83.816 142.077 + endloop + endfacet + facet normal -0.134484 -0.989855 -0.0458392 + outer loop + vertex 455.219 83.816 142.077 + vertex 447.591 84.4464 150.842 + vertex 449.359 84.59 142.554 + endloop + endfacet + facet normal -0.0718123 -0.997271 0.0171103 + outer loop + vertex 462.306 83.3598 132.835 + vertex 456.725 83.7769 133.717 + vertex 463.6 83.1223 124.417 + endloop + endfacet + facet normal -0.0264058 -0.99936 0.0241463 + outer loop + vertex 469.017 82.953 123.334 + vertex 462.306 83.3598 132.835 + vertex 463.6 83.1223 124.417 + endloop + endfacet + facet normal 0.0268722 -0.99728 0.068627 + outer loop + vertex 474.519 83.0311 122.314 + vertex 469.017 82.953 123.334 + vertex 475.473 82.4664 113.735 + endloop + endfacet + facet normal 0.0424446 -0.996621 0.0703161 + outer loop + vertex 481.053 82.6326 112.722 + vertex 474.519 83.0311 122.314 + vertex 475.473 82.4664 113.735 + endloop + endfacet + facet normal 0.0719588 -0.993916 0.0833807 + outer loop + vertex 486.824 82.9644 111.697 + vertex 480.214 83.2972 121.369 + vertex 481.053 82.6326 112.722 + endloop + endfacet + facet normal 0.102571 -0.987289 0.121405 + outer loop + vertex 492.567 83.4265 110.602 + vertex 486.824 82.9644 111.697 + vertex 492.889 82.3772 101.798 + endloop + endfacet + facet normal 0.120791 -0.987148 0.104631 + outer loop + vertex 497.812 83.9662 109.64 + vertex 491.956 84.2813 119.374 + vertex 492.567 83.4265 110.602 + endloop + endfacet + facet normal 0.142339 -0.980809 0.13324 + outer loop + vertex 502.01 84.5283 109.293 + vertex 497.812 83.9662 109.64 + vertex 502.323 83.3849 100.541 + endloop + endfacet + facet normal 0.149684 -0.976979 0.152007 + outer loop + vertex 505.557 84.0222 101.453 + vertex 502.323 83.3849 100.541 + vertex 505.395 82.6754 92.9565 + endloop + endfacet + facet normal 0.166143 -0.974427 0.151288 + outer loop + vertex 505.557 84.0222 101.453 + vertex 505.395 82.6754 92.9565 + vertex 507.818 83.3843 94.862 + endloop + endfacet + facet normal 0.124876 -0.981081 0.147936 + outer loop + vertex 502.341 81.9959 91.6163 + vertex 498.095 82.846 100.838 + vertex 497.991 81.4675 91.784 + endloop + endfacet + facet normal 0.102175 -0.972857 0.20763 + outer loop + vertex 501.002 78.9412 75.7299 + vertex 498.609 78.5532 75.0891 + vertex 500.47 77.7329 70.3298 + endloop + endfacet + facet normal 0.0986011 -0.973499 0.206344 + outer loop + vertex 500.47 77.7329 70.3298 + vertex 498.609 78.5532 75.0891 + vertex 497.756 77.5465 70.7476 + endloop + endfacet + facet normal 0.103634 -0.980673 0.165952 + outer loop + vertex 497.991 81.4675 91.784 + vertex 492.713 81.0828 92.8067 + vertex 497.409 79.8244 82.4374 + endloop + endfacet + facet normal 0.071423 -0.989007 0.129475 + outer loop + vertex 492.713 81.0828 92.8067 + vertex 487.232 82.011 102.921 + vertex 487.153 80.8329 93.9648 + endloop + endfacet + facet normal 0.0801858 -0.980438 0.179755 + outer loop + vertex 493.083 78.3038 76.3089 + vertex 495.723 78.5695 76.5807 + vertex 491.998 79.5499 83.5893 + endloop + endfacet + facet normal 0.100871 -0.973367 0.205867 + outer loop + vertex 498.609 78.5532 75.0891 + vertex 495.723 78.5695 76.5807 + vertex 497.756 77.5465 70.7476 + endloop + endfacet + facet normal 0.101417 -0.968646 0.226801 + outer loop + vertex 500.47 77.7329 70.3298 + vertex 497.756 77.5465 70.7476 + vertex 499.62 76.5106 65.4898 + endloop + endfacet + facet normal 0.100926 -0.963256 0.2489 + outer loop + vertex 502.128 76.7012 65.2106 + vertex 499.62 76.5106 65.4898 + vertex 501.204 75.3659 60.4172 + endloop + endfacet + facet normal 0.10132 -0.963236 0.248819 + outer loop + vertex 503.296 75.5254 60.1828 + vertex 502.128 76.7012 65.2106 + vertex 501.204 75.3659 60.4172 + endloop + endfacet + facet normal 0.112928 -0.955349 0.273048 + outer loop + vertex 504.793 75.7246 60.261 + vertex 503.296 75.5254 60.1828 + vertex 503.726 74.2809 55.6509 + endloop + endfacet + facet normal 0.106885 -0.948756 0.297383 + outer loop + vertex 504.755 74.6555 56.476 + vertex 503.726 74.2809 55.6509 + vertex 503.475 73.1016 51.9787 + endloop + endfacet + facet normal 0.150557 -0.946844 0.284288 + outer loop + vertex 504.755 74.6555 56.476 + vertex 503.475 73.1016 51.9787 + vertex 504.457 73.8285 53.8797 + endloop + endfacet + facet normal 0.105395 -0.947654 0.301404 + outer loop + vertex 502.322 72.7038 51.2058 + vertex 502.163 74.0894 55.6182 + vertex 500.744 72.5836 51.3796 + endloop + endfacet + facet normal 0.0792035 -0.941292 0.328172 + outer loop + vertex 498.986 70.9977 47.3758 + vertex 498.66 72.5794 51.9911 + vertex 496.794 71.0715 48.1165 + endloop + endfacet + facet normal 0.103294 -0.94766 0.302109 + outer loop + vertex 502.163 74.0894 55.6182 + vertex 500.085 74.0105 56.0808 + vertex 500.744 72.5836 51.3796 + endloop + endfacet + facet normal 0.0858839 -0.958985 0.270132 + outer loop + vertex 500.085 74.0105 56.0808 + vertex 498.705 75.2682 60.9847 + vertex 497.643 73.9814 56.7539 + endloop + endfacet + facet normal 0.0871002 -0.958963 0.26982 + outer loop + vertex 498.705 75.2682 60.9847 + vertex 496.053 75.2182 61.663 + vertex 497.643 73.9814 56.7539 + endloop + endfacet + facet normal 0.0561565 -0.96378 0.26072 + outer loop + vertex 495.04 73.9819 57.4573 + vertex 493.376 75.2091 62.3522 + vertex 492.369 74.0154 58.1564 + endloop + endfacet + facet normal 0.0641443 -0.954635 0.290789 + outer loop + vertex 495.04 73.9819 57.4573 + vertex 492.369 74.0154 58.1564 + vertex 493.688 72.7013 53.5512 + endloop + endfacet + facet normal 0.0788765 -0.966977 0.242349 + outer loop + vertex 496.904 76.3985 66.0953 + vertex 494.188 76.3474 66.7755 + vertex 496.053 75.2182 61.663 + endloop + endfacet + facet normal 0.0451452 -0.971457 0.232879 + outer loop + vertex 493.376 75.2091 62.3522 + vertex 491.532 76.3447 67.4469 + vertex 490.726 75.25 63.0363 + endloop + endfacet + facet normal 0.0707146 -0.973271 0.218504 + outer loop + vertex 494.983 77.4415 71.3917 + vertex 492.279 77.3942 72.056 + vertex 494.188 76.3474 66.7755 + endloop + endfacet + facet normal 0.0461754 -0.980693 0.190026 + outer loop + vertex 492.279 77.3942 72.056 + vertex 490.282 78.423 77.8509 + vertex 489.656 77.3929 72.6864 + endloop + endfacet + facet normal 0.0412658 -0.980792 0.190641 + outer loop + vertex 490.282 78.423 77.8509 + vertex 487.782 78.2582 77.544 + vertex 489.656 77.3929 72.6864 + endloop + endfacet + facet normal 0.00912555 -0.984001 0.17793 + outer loop + vertex 487.076 77.4389 73.3231 + vertex 485.049 78.4709 79.1342 + vertex 484.488 77.5471 74.0539 + endloop + endfacet + facet normal 0.00423958 -0.983938 0.178459 + outer loop + vertex 485.049 78.4709 79.1342 + vertex 482.534 78.4428 79.039 + vertex 484.488 77.5471 74.0539 + endloop + endfacet + facet normal 0.0442494 -0.984718 0.168443 + outer loop + vertex 487.782 78.2582 77.544 + vertex 490.282 78.423 77.8509 + vertex 486.592 79.4503 84.8254 + endloop + endfacet + facet normal 0.00523096 -0.988133 0.153514 + outer loop + vertex 482.534 78.4428 79.039 + vertex 485.049 78.4709 79.1342 + vertex 481.285 79.5788 86.3936 + endloop + endfacet + facet normal -0.0221928 -0.988599 0.148928 + outer loop + vertex 482.534 78.4428 79.039 + vertex 481.285 79.5788 86.3936 + vertex 479.499 78.8292 81.1521 + endloop + endfacet + facet normal -0.0099778 -0.989399 0.144882 + outer loop + vertex 481.285 79.5788 86.3936 + vertex 476.116 80.0238 89.0767 + vertex 479.499 78.8292 81.1521 + endloop + endfacet + facet normal 0.04603 -0.988116 0.146659 + outer loop + vertex 487.153 80.8329 93.9648 + vertex 481.701 80.7603 95.1864 + vertex 486.592 79.4503 84.8254 + endloop + endfacet + facet normal -0.0260177 -0.993072 0.114592 + outer loop + vertex 481.285 79.5788 86.3936 + vertex 476.431 80.8975 96.7202 + vertex 476.116 80.0238 89.0767 + endloop + endfacet + facet normal 0.0322315 -0.992674 0.116443 + outer loop + vertex 481.597 81.7905 103.998 + vertex 476.163 81.7491 105.149 + vertex 481.701 80.7603 95.1864 + endloop + endfacet + facet normal -0.0127945 -0.997569 0.0685004 + outer loop + vertex 476.163 81.7491 105.149 + vertex 470.083 82.4935 114.854 + vertex 470.909 81.9068 106.465 + endloop + endfacet + facet normal -0.0369552 -0.997129 0.0660913 + outer loop + vertex 470.083 82.4935 114.854 + vertex 464.777 82.7703 116.064 + vertex 470.909 81.9068 106.465 + endloop + endfacet + facet normal -0.114422 -0.993375 0.0107092 + outer loop + vertex 464.777 82.7703 116.064 + vertex 458.139 83.6357 125.411 + vertex 459.415 83.3999 117.176 + endloop + endfacet + facet normal -0.196898 -0.980244 -0.0188037 + outer loop + vertex 459.415 83.3999 117.176 + vertex 452.531 84.611 126.123 + vertex 453.904 84.4912 117.996 + endloop + endfacet + facet normal -0.127201 -0.990024 0.0605965 + outer loop + vertex 465.728 82.3079 107.82 + vertex 460.473 83.0564 109.019 + vertex 466.319 81.73 99.6194 + endloop + endfacet + facet normal -0.0856569 -0.994274 0.0638897 + outer loop + vertex 471.347 81.2117 98.2945 + vertex 465.728 82.3079 107.82 + vertex 466.319 81.73 99.6194 + endloop + endfacet + facet normal -0.0258908 -0.993076 0.114587 + outer loop + vertex 476.431 80.8975 96.7202 + vertex 471.347 81.2117 98.2945 + vertex 476.116 80.0238 89.0767 + endloop + endfacet + facet normal -0.0428149 -0.990455 0.131022 + outer loop + vertex 475.609 79.117 82.0559 + vertex 479.499 78.8292 81.1521 + vertex 476.116 80.0238 89.0767 + endloop + endfacet + facet normal -0.00577461 -0.985103 0.171868 + outer loop + vertex 482.534 78.4428 79.039 + vertex 479.499 78.8292 81.1521 + vertex 481.785 77.7339 74.9508 + endloop + endfacet + facet normal -0.0107719 -0.984907 0.172749 + outer loop + vertex 484.488 77.5471 74.0539 + vertex 482.534 78.4428 79.039 + vertex 481.785 77.7339 74.9508 + endloop + endfacet + facet normal 0.0165364 -0.978952 0.203422 + outer loop + vertex 487.076 77.4389 73.3231 + vertex 484.488 77.5471 74.0539 + vertex 486.349 76.4925 68.8274 + endloop + endfacet + facet normal 0.0178006 -0.978971 0.203222 + outer loop + vertex 488.927 76.3908 68.1121 + vertex 487.076 77.4389 73.3231 + vertex 486.349 76.4925 68.8274 + endloop + endfacet + facet normal 0.0423977 -0.97146 0.233382 + outer loop + vertex 491.532 76.3447 67.4469 + vertex 488.927 76.3908 68.1121 + vertex 490.726 75.25 63.0363 + endloop + endfacet + facet normal 0.052666 -0.963752 0.26155 + outer loop + vertex 493.376 75.2091 62.3522 + vertex 490.726 75.25 63.0363 + vertex 492.369 74.0154 58.1564 + endloop + endfacet + facet normal 0.0203456 -0.967207 0.253172 + outer loop + vertex 489.695 74.1019 58.8823 + vertex 488.104 75.3473 63.7678 + vertex 487.05 74.255 59.6796 + endloop + endfacet + facet normal -0.00659196 -0.961536 0.274599 + outer loop + vertex 485.672 73.133 55.8896 + vertex 484.44 74.474 60.5555 + vertex 483.065 73.4128 56.8068 + endloop + endfacet + facet normal 0.018788 -0.967139 0.253555 + outer loop + vertex 488.104 75.3473 63.7678 + vertex 485.512 75.5079 64.5727 + vertex 487.05 74.255 59.6796 + endloop + endfacet + facet normal -0.0101361 -0.975768 0.218574 + outer loop + vertex 485.512 75.5079 64.5727 + vertex 483.758 76.6607 69.6377 + vertex 482.913 75.7319 65.452 + endloop + endfacet + facet normal -0.012602 -0.975634 0.219042 + outer loop + vertex 483.758 76.6607 69.6377 + vertex 481.078 76.8898 70.5037 + vertex 482.913 75.7319 65.452 + endloop + endfacet + facet normal -0.0446495 -0.982273 0.182064 + outer loop + vertex 481.078 76.8898 70.5037 + vertex 478.796 77.9869 75.8636 + vertex 478.391 77.1215 71.0951 + endloop + endfacet + facet normal -0.0621966 -0.9819 0.178896 + outer loop + vertex 478.391 77.1215 71.0951 + vertex 475.76 78.1189 75.6547 + vertex 476.228 77.2515 71.0564 + endloop + endfacet + facet normal -0.0786462 -0.981052 0.177064 + outer loop + vertex 476.228 77.2515 71.0564 + vertex 475.76 78.1189 75.6547 + vertex 473.789 77.8156 73.0989 + endloop + endfacet + facet normal -0.10773 -0.982846 0.149692 + outer loop + vertex 471.38 78.1792 73.7526 + vertex 473.789 77.8156 73.0989 + vertex 471.231 79.2305 80.5474 + endloop + endfacet + facet normal -0.099809 -0.987604 0.121145 + outer loop + vertex 471.378 80.3927 90.1429 + vertex 466.406 81.0172 91.138 + vertex 471.231 79.2305 80.5474 + endloop + endfacet + facet normal -0.187567 -0.980452 0.0594396 + outer loop + vertex 466.406 81.0172 91.138 + vertex 461.146 82.6115 100.836 + vertex 461.253 82.0907 92.5848 + endloop + endfacet + facet normal -0.15546 -0.979036 0.131606 + outer loop + vertex 466.489 79.1897 75.6362 + vertex 468.862 78.8101 75.6142 + vertex 465.75 80.2327 82.5216 + endloop + endfacet + facet normal -0.154363 -0.974121 0.16511 + outer loop + vertex 468.862 78.8101 75.6142 + vertex 466.489 79.1897 75.6362 + vertex 467.841 78.188 70.9901 + endloop + endfacet + facet normal -0.153827 -0.974223 0.165005 + outer loop + vertex 470.221 77.6676 70.1357 + vertex 468.862 78.8101 75.6142 + vertex 467.841 78.188 70.9901 + endloop + endfacet + facet normal -0.110067 -0.970421 0.214868 + outer loop + vertex 472.694 77.1646 69.1307 + vertex 470.221 77.6676 70.1357 + vertex 471.513 76.4415 65.2603 + endloop + endfacet + facet normal -0.112791 -0.969944 0.21561 + outer loop + vertex 474.041 75.9381 64.3181 + vertex 472.694 77.1646 69.1307 + vertex 471.513 76.4415 65.2603 + endloop + endfacet + facet normal -0.0861474 -0.970566 0.224901 + outer loop + vertex 476.632 75.483 63.3466 + vertex 475.217 76.6986 68.0502 + vertex 474.041 75.9381 64.3181 + endloop + endfacet + facet normal -0.062409 -0.970457 0.233062 + outer loop + vertex 479.238 75.0889 62.4034 + vertex 477.734 76.3075 67.0747 + vertex 476.632 75.483 63.3466 + endloop + endfacet + facet normal -0.0395422 -0.970477 0.23793 + outer loop + vertex 481.847 74.7547 61.4736 + vertex 480.293 76.0058 66.3183 + vertex 479.238 75.0889 62.4034 + endloop + endfacet + facet normal -0.00682506 -0.961512 0.274678 + outer loop + vertex 484.44 74.474 60.5555 + vertex 481.847 74.7547 61.4736 + vertex 483.065 73.4128 56.8068 + endloop + endfacet + facet normal 0.00479919 -0.95258 0.304249 + outer loop + vertex 485.672 73.133 55.8896 + vertex 483.065 73.4128 56.8068 + vertex 484.04 72.0724 52.5946 + endloop + endfacet + facet normal -0.0368435 -0.954999 0.29431 + outer loop + vertex 481.469 72.4158 53.5471 + vertex 480.483 73.7515 57.7579 + vertex 478.952 72.8109 54.5141 + endloop + endfacet + facet normal -0.0589905 -0.955629 0.288605 + outer loop + vertex 478.952 72.8109 54.5141 + vertex 477.897 74.1487 58.728 + vertex 476.452 73.2565 55.4785 + endloop + endfacet + facet normal -0.0814277 -0.955623 0.283115 + outer loop + vertex 476.452 73.2565 55.4785 + vertex 475.317 74.6017 59.6929 + vertex 473.976 73.7581 56.4593 + endloop + endfacet + facet normal -0.105407 -0.9549 0.277587 + outer loop + vertex 473.976 73.7581 56.4593 + vertex 472.777 75.1073 60.6453 + vertex 471.54 74.3085 57.4276 + endloop + endfacet + facet normal -0.110053 -0.953925 0.279132 + outer loop + vertex 472.777 75.1073 60.6453 + vertex 470.32 75.656 61.5517 + vertex 471.54 74.3085 57.4276 + endloop + endfacet + facet normal -0.151033 -0.959632 0.237266 + outer loop + vertex 470.32 75.656 61.5517 + vertex 469.092 76.9801 66.1259 + vertex 467.969 76.2384 62.4115 + endloop + endfacet + facet normal -0.159073 -0.949714 0.269702 + outer loop + vertex 467.969 76.2384 62.4115 + vertex 465.716 76.8485 63.2307 + vertex 466.86 75.5219 59.234 + endloop + endfacet + facet normal -0.207185 -0.944236 0.255915 + outer loop + vertex 464.616 76.1756 60.0612 + vertex 463.499 77.508 64.0733 + vertex 462.323 76.9083 60.9081 + endloop + endfacet + facet normal -0.21046 -0.943232 0.256943 + outer loop + vertex 463.499 77.508 64.0733 + vertex 461.243 78.2604 64.9874 + vertex 462.323 76.9083 60.9081 + endloop + endfacet + facet normal -0.174303 -0.957272 0.230755 + outer loop + vertex 466.795 77.5448 66.9341 + vertex 464.591 78.1445 67.7572 + vertex 465.716 76.8485 63.2307 + endloop + endfacet + facet normal -0.229227 -0.949208 0.215545 + outer loop + vertex 463.499 77.508 64.0733 + vertex 462.385 78.8191 68.6622 + vertex 461.243 78.2604 64.9874 + endloop + endfacet + facet normal -0.191337 -0.963566 0.186899 + outer loop + vertex 465.571 78.7364 71.8124 + vertex 463.361 79.3481 72.7024 + vertex 464.591 78.1445 67.7572 + endloop + endfacet + facet normal -0.246969 -0.959079 0.138472 + outer loop + vertex 463.361 79.3481 72.7024 + vertex 461.854 80.4315 77.5188 + vertex 461.012 80.0994 73.7181 + endloop + endfacet + facet normal -0.261261 -0.954875 0.141268 + outer loop + vertex 461.854 80.4315 77.5188 + vertex 459.066 81.5033 79.6088 + vertex 461.012 80.0994 73.7181 + endloop + endfacet + facet normal -0.321829 -0.929692 0.17916 + outer loop + vertex 457.704 80.4643 70.211 + vertex 455.43 82.0624 74.4204 + vertex 455.738 81.137 70.1708 + endloop + endfacet + facet normal -0.294854 -0.940665 0.16796 + outer loop + vertex 460.076 79.6103 69.5941 + vertex 458.301 81.0709 74.6564 + vertex 457.704 80.4643 70.211 + endloop + endfacet + facet normal -0.236717 -0.946915 0.217523 + outer loop + vertex 462.385 78.8191 68.6622 + vertex 460.076 79.6103 69.5941 + vertex 461.243 78.2604 64.9874 + endloop + endfacet + facet normal -0.309826 -0.915852 0.255388 + outer loop + vertex 457.761 78.8157 63.3668 + vertex 455.466 79.7356 63.8819 + vertex 457.449 77.9273 59.8025 + endloop + endfacet + facet normal -0.243243 -0.938103 0.246569 + outer loop + vertex 462.323 76.9083 60.9081 + vertex 461.243 78.2604 64.9874 + vertex 459.848 77.825 61.9542 + endloop + endfacet + facet normal -0.192273 -0.937397 0.290376 + outer loop + vertex 464.616 76.1756 60.0612 + vertex 462.323 76.9083 60.9081 + vertex 463.576 75.6385 57.6385 + endloop + endfacet + facet normal -0.185567 -0.939491 0.287961 + outer loop + vertex 465.816 74.9515 56.8408 + vertex 464.616 76.1756 60.0612 + vertex 463.576 75.6385 57.6385 + endloop + endfacet + facet normal -0.146783 -0.936047 0.319799 + outer loop + vertex 468.05 74.3061 55.977 + vertex 465.816 74.9515 56.8408 + vertex 466.962 74.0379 54.6928 + endloop + endfacet + facet normal -0.133621 -0.945208 0.297871 + outer loop + vertex 470.411 73.6515 54.9589 + vertex 469.16 74.9013 58.3636 + vertex 468.05 74.3061 55.977 + endloop + endfacet + facet normal -0.0961514 -0.939301 0.329345 + outer loop + vertex 472.804 73.0669 53.9902 + vertex 470.411 73.6515 54.9589 + vertex 471.893 72.5517 52.2548 + endloop + endfacet + facet normal -0.0867912 -0.941675 0.325138 + outer loop + vertex 474.107 72.1195 51.5941 + vertex 472.804 73.0669 53.9902 + vertex 471.893 72.5517 52.2548 + endloop + endfacet + facet normal -0.0681613 -0.942218 0.327993 + outer loop + vertex 476.425 71.533 50.3911 + vertex 475.152 72.5376 53.0124 + vertex 474.107 72.1195 51.5941 + endloop + endfacet + facet normal -0.0483194 -0.942308 0.331243 + outer loop + vertex 478.696 71.1728 49.6978 + vertex 477.525 72.0524 52.0289 + vertex 476.425 71.533 50.3911 + endloop + endfacet + facet normal -0.0316155 -0.941654 0.335095 + outer loop + vertex 481.089 70.6749 48.5243 + vertex 479.928 71.6155 51.058 + vertex 478.696 71.1728 49.6978 + endloop + endfacet + facet normal -0.0137163 -0.940411 0.339762 + outer loop + vertex 483.571 70.3511 47.7282 + vertex 482.413 71.2241 50.0978 + vertex 481.089 70.6749 48.5243 + endloop + endfacet + facet normal 0.0357987 -0.927105 0.373088 + outer loop + vertex 490.478 68.8359 43.4933 + vertex 489.246 69.4582 45.1579 + vertex 488.437 69.1708 44.5213 + endloop + endfacet + facet normal 0.00123832 -0.937765 0.347269 + outer loop + vertex 486.409 69.7774 46.169 + vertex 485.036 70.8489 49.0672 + vertex 483.571 70.3511 47.7282 + endloop + endfacet + facet normal 0.0134049 -0.943514 0.331063 + outer loop + vertex 486.701 71.7853 51.6687 + vertex 484.04 72.0724 52.5946 + vertex 485.036 70.8489 49.0672 + endloop + endfacet + facet normal 0.023153 -0.950676 0.309322 + outer loop + vertex 489.409 71.5783 50.8298 + vertex 488.335 72.9197 55.0328 + vertex 486.701 71.7853 51.6687 + endloop + endfacet + facet normal 0.0405862 -0.948824 0.313186 + outer loop + vertex 491.031 72.7812 54.2638 + vertex 488.335 72.9197 55.0328 + vertex 489.409 71.5783 50.8298 + endloop + endfacet + facet normal 0.0481392 -0.956775 0.286816 + outer loop + vertex 493.688 72.7013 53.5512 + vertex 492.369 74.0154 58.1564 + vertex 491.031 72.7812 54.2638 + endloop + endfacet + facet normal 0.0619533 -0.954556 0.291521 + outer loop + vertex 496.247 72.6304 52.7753 + vertex 495.04 73.9819 57.4573 + vertex 493.688 72.7013 53.5512 + endloop + endfacet + facet normal 0.085779 -0.941752 0.325185 + outer loop + vertex 498.66 72.5794 51.9911 + vertex 496.247 72.6304 52.7753 + vertex 496.794 71.0715 48.1165 + endloop + endfacet + facet normal 0.0877048 -0.931741 0.352374 + outer loop + vertex 498.986 70.9977 47.3758 + vertex 496.794 71.0715 48.1165 + vertex 497.285 69.9872 45.1271 + endloop + endfacet + facet normal 0.102088 -0.929826 0.353556 + outer loop + vertex 500.642 71.0074 46.9233 + vertex 498.986 70.9977 47.3758 + vertex 499.238 69.933 44.5029 + endloop + endfacet + facet normal 0.0987993 -0.929508 0.355322 + outer loop + vertex 499.821 69.7697 43.9136 + vertex 500.642 71.0074 46.9233 + vertex 499.238 69.933 44.5029 + endloop + endfacet + facet normal 0.114802 -0.921479 0.371076 + outer loop + vertex 500.438 69.991 44.2722 + vertex 499.821 69.7697 43.9136 + vertex 499.499 69.1464 42.4653 + endloop + endfacet + facet normal 0.143309 -0.923048 0.356994 + outer loop + vertex 499.999 69.316 42.7032 + vertex 500.438 69.991 44.2722 + vertex 499.499 69.1464 42.4653 + endloop + endfacet + facet normal 0.105227 -0.915126 0.389194 + outer loop + vertex 498.907 69.1276 42.6096 + vertex 498.128 69.1499 42.8728 + vertex 498.029 68.6711 41.7736 + endloop + endfacet + facet normal 0.0893443 -0.920996 0.379189 + outer loop + vertex 498.128 69.1499 42.8728 + vertex 498.251 69.8101 44.4473 + vertex 497.152 69.1782 43.1714 + endloop + endfacet + facet normal 0.08385 -0.915785 0.39282 + outer loop + vertex 497.152 69.1782 43.1714 + vertex 496.03 69.2075 43.4792 + vertex 496.142 68.7332 42.3497 + endloop + endfacet + facet normal 0.0724493 -0.923197 0.377437 + outer loop + vertex 496.03 69.2075 43.4792 + vertex 495.982 69.8742 45.1192 + vertex 494.747 69.2579 43.8488 + endloop + endfacet + facet normal 0.0593125 -0.921153 0.384654 + outer loop + vertex 493.639 68.8273 43.0251 + vertex 493.194 69.353 44.3527 + vertex 492.068 68.8717 43.3738 + endloop + endfacet + facet normal 0.0800558 -0.925175 0.371002 + outer loop + vertex 495.982 69.8742 45.1192 + vertex 494.73 70.1308 46.0293 + vertex 494.747 69.2579 43.8488 + endloop + endfacet + facet normal 0.0596049 -0.936478 0.345626 + outer loop + vertex 492.737 70.2616 46.7275 + vertex 494.73 70.1308 46.0293 + vertex 494.512 71.349 49.3676 + endloop + endfacet + facet normal 0.0492553 -0.938837 0.340822 + outer loop + vertex 492.737 70.2616 46.7275 + vertex 492.044 71.459 50.126 + vertex 490.398 70.3556 47.3242 + endloop + endfacet + facet normal 0.040985 -0.930614 0.363701 + outer loop + vertex 490.398 70.3556 47.3242 + vertex 487.783 70.5322 48.0709 + vertex 489.246 69.4582 45.1579 + endloop + endfacet + facet normal 0.0600701 -0.921414 0.383911 + outer loop + vertex 493.194 69.353 44.3527 + vertex 491.328 69.4301 44.8296 + vertex 492.068 68.8717 43.3738 + endloop + endfacet + facet normal 0.0430791 -0.924939 0.377667 + outer loop + vertex 490.681 69.0124 43.9023 + vertex 489.246 69.4582 45.1579 + vertex 490.478 68.8359 43.4933 + endloop + endfacet + facet normal 0.0604335 -0.919068 0.389439 + outer loop + vertex 493.639 68.8273 43.0251 + vertex 492.068 68.8717 43.3738 + vertex 493.443 68.538 42.3728 + endloop + endfacet + facet normal 0.0853424 -0.88769 0.452464 + outer loop + vertex 495.34 68.2393 41.3508 + vertex 491.796 68.535 42.5996 + vertex 492.979 68.1325 41.5867 + endloop + endfacet + facet normal 0.0858595 -0.884151 0.459245 + outer loop + vertex 492.979 68.1325 41.5867 + vertex 495.401 67.7703 40.4366 + vertex 495.34 68.2393 41.3508 + endloop + endfacet + facet normal 0.0911646 -0.878649 0.468684 + outer loop + vertex 495.401 67.7703 40.4366 + vertex 492.979 68.1325 41.5867 + vertex 493.466 67.5693 40.4361 + endloop + endfacet + facet normal 0.0903184 -0.870538 0.483742 + outer loop + vertex 494.088 67.2048 39.6639 + vertex 495.401 67.7703 40.4366 + vertex 493.466 67.5693 40.4361 + endloop + endfacet + facet normal 0.0851008 -0.872797 0.480607 + outer loop + vertex 493.466 67.5693 40.4361 + vertex 491.774 66.7765 39.2961 + vertex 494.088 67.2048 39.6639 + endloop + endfacet + facet normal 0.0736933 -0.866721 0.493319 + outer loop + vertex 493.466 67.5693 40.4361 + vertex 490.726 67.0822 39.9897 + vertex 491.774 66.7765 39.2961 + endloop + endfacet + facet normal 0.0754771 -0.865369 0.495418 + outer loop + vertex 490.726 67.0822 39.9897 + vertex 488.414 66.2001 38.801 + vertex 491.774 66.7765 39.2961 + endloop + endfacet + facet normal 0.0677509 -0.847289 0.526794 + outer loop + vertex 491.774 66.7765 39.2961 + vertex 488.414 66.2001 38.801 + vertex 488.352 65.6949 37.9964 + endloop + endfacet + facet normal 0.0791243 -0.858693 0.506345 + outer loop + vertex 491.774 66.7765 39.2961 + vertex 488.352 65.6949 37.9964 + vertex 491.848 66.3503 38.5616 + endloop + endfacet + facet normal 0.0784192 -0.858773 0.50632 + outer loop + vertex 494.088 67.2048 39.6639 + vertex 491.774 66.7765 39.2961 + vertex 491.848 66.3503 38.5616 + endloop + endfacet + facet normal 0.0946275 -0.870701 0.482624 + outer loop + vertex 494.088 67.2048 39.6639 + vertex 491.848 66.3503 38.5616 + vertex 494.476 66.9642 39.1538 + endloop + endfacet + facet normal 0.0708928 -0.840867 0.536578 + outer loop + vertex 491.848 66.3503 38.5616 + vertex 488.352 65.6949 37.9964 + vertex 488.935 65.486 37.5921 + endloop + endfacet + facet normal 0.0629106 -0.831391 0.552115 + outer loop + vertex 488.935 65.486 37.5921 + vertex 489.544 65.4607 37.4846 + vertex 491.848 66.3503 38.5616 + endloop + endfacet + facet normal 0.0666883 -0.818589 0.570495 + outer loop + vertex 488.935 65.486 37.5921 + vertex 483.621 64.2591 36.4528 + vertex 489.544 65.4607 37.4846 + endloop + endfacet + facet normal 0.0767571 -0.836399 0.54272 + outer loop + vertex 488.935 65.486 37.5921 + vertex 488.352 65.6949 37.9964 + vertex 483.621 64.2591 36.4528 + endloop + endfacet + facet normal 0.067761 -0.847289 0.526793 + outer loop + vertex 488.414 66.2001 38.801 + vertex 482.415 64.8749 37.4414 + vertex 488.352 65.6949 37.9964 + endloop + endfacet + facet normal 0.0687565 -0.848935 0.524005 + outer loop + vertex 488.414 66.2001 38.801 + vertex 486.391 66.3358 39.2864 + vertex 482.415 64.8749 37.4414 + endloop + endfacet + facet normal 0.0648767 -0.857577 0.510247 + outer loop + vertex 490.726 67.0822 39.9897 + vertex 486.391 66.3358 39.2864 + vertex 488.414 66.2001 38.801 + endloop + endfacet + facet normal 0.0720775 -0.873046 0.482282 + outer loop + vertex 489.154 67.3384 40.6884 + vertex 486.391 66.3358 39.2864 + vertex 490.726 67.0822 39.9897 + endloop + endfacet + facet normal 0.0702716 -0.875027 0.478946 + outer loop + vertex 491.906 67.7383 41.0151 + vertex 489.154 67.3384 40.6884 + vertex 490.726 67.0822 39.9897 + endloop + endfacet + facet normal 0.0738306 -0.884533 0.460598 + outer loop + vertex 490.324 68.0172 41.8045 + vertex 489.154 67.3384 40.6884 + vertex 491.906 67.7383 41.0151 + endloop + endfacet + facet normal 0.0764199 -0.882053 0.464912 + outer loop + vertex 491.906 67.7383 41.0151 + vertex 492.979 68.1325 41.5867 + vertex 490.324 68.0172 41.8045 + endloop + endfacet + facet normal 0.0758141 -0.887418 0.454688 + outer loop + vertex 492.979 68.1325 41.5867 + vertex 489.406 68.5579 43.0128 + vertex 490.324 68.0172 41.8045 + endloop + endfacet + facet normal 0.065866 -0.891193 0.448818 + outer loop + vertex 488.312 68.2052 42.4729 + vertex 490.324 68.0172 41.8045 + vertex 489.406 68.5579 43.0128 + endloop + endfacet + facet normal 0.0622581 -0.888603 0.454432 + outer loop + vertex 488.312 68.2052 42.4729 + vertex 489.406 68.5579 43.0128 + vertex 486.598 68.5418 43.366 + endloop + endfacet + facet normal 0.0569059 -0.893265 0.445914 + outer loop + vertex 486.598 68.5418 43.366 + vertex 485.626 67.8973 42.1988 + vertex 488.312 68.2052 42.4729 + endloop + endfacet + facet normal 0.0547345 -0.886462 0.459553 + outer loop + vertex 488.312 68.2052 42.4729 + vertex 485.626 67.8973 42.1988 + vertex 487.404 67.6011 41.4157 + endloop + endfacet + facet normal 0.0567752 -0.884338 0.463383 + outer loop + vertex 485.626 67.8973 42.1988 + vertex 483.203 66.9598 40.7066 + vertex 487.404 67.6011 41.4157 + endloop + endfacet + facet normal 0.0500872 -0.870173 0.490195 + outer loop + vertex 487.404 67.6011 41.4157 + vertex 483.203 66.9598 40.7066 + vertex 485.51 66.7875 40.165 + endloop + endfacet + facet normal 0.0648507 -0.878528 0.473269 + outer loop + vertex 487.404 67.6011 41.4157 + vertex 485.51 66.7875 40.165 + vertex 489.154 67.3384 40.6884 + endloop + endfacet + facet normal 0.054771 -0.860215 0.506981 + outer loop + vertex 485.51 66.7875 40.165 + vertex 483.203 66.9598 40.7066 + vertex 479.917 65.5624 38.6907 + endloop + endfacet + facet normal 0.0570449 -0.863512 0.501093 + outer loop + vertex 485.51 66.7875 40.165 + vertex 479.917 65.5624 38.6907 + vertex 486.391 66.3358 39.2864 + endloop + endfacet + facet normal 0.0288368 -0.842917 0.53727 + outer loop + vertex 476.862 66.3276 40.0551 + vertex 479.917 65.5624 38.6907 + vertex 483.203 66.9598 40.7066 + endloop + endfacet + facet normal 0.0347328 -0.836497 0.54687 + outer loop + vertex 476.862 66.3276 40.0551 + vertex 470.657 64.3899 37.4853 + vertex 479.917 65.5624 38.6907 + endloop + endfacet + facet normal 0.0387215 -0.873249 0.485733 + outer loop + vertex 485.626 67.8973 42.1988 + vertex 482.132 67.4581 41.6878 + vertex 483.203 66.9598 40.7066 + endloop + endfacet + facet normal 0.0373425 -0.873948 0.484582 + outer loop + vertex 482.132 67.4581 41.6878 + vertex 476.862 66.3276 40.0551 + vertex 483.203 66.9598 40.7066 + endloop + endfacet + facet normal 0.0305084 -0.865165 0.500559 + outer loop + vertex 482.132 67.4581 41.6878 + vertex 479.425 67.6962 42.2644 + vertex 476.862 66.3276 40.0551 + endloop + endfacet + facet normal 0.00103845 -0.850638 0.52575 + outer loop + vertex 473.04 67.0119 41.1699 + vertex 476.862 66.3276 40.0551 + vertex 479.425 67.6962 42.2644 + endloop + endfacet + facet normal 0.0103831 -0.835921 0.548751 + outer loop + vertex 473.04 67.0119 41.1699 + vertex 467.975 65.3755 38.773 + vertex 476.862 66.3276 40.0551 + endloop + endfacet + facet normal 0.0244912 -0.878188 0.477688 + outer loop + vertex 483.737 68.2382 43.0398 + vertex 479.425 67.6962 42.2644 + vertex 482.132 67.4581 41.6878 + endloop + endfacet + facet normal 0.0295027 -0.888841 0.457265 + outer loop + vertex 481.48 68.6393 43.965 + vertex 479.425 67.6962 42.2644 + vertex 483.737 68.2382 43.0398 + endloop + endfacet + facet normal 0.0254923 -0.893021 0.449292 + outer loop + vertex 484.431 68.817 44.1507 + vertex 481.48 68.6393 43.965 + vertex 483.737 68.2382 43.0398 + endloop + endfacet + facet normal 0.0451237 -0.897241 0.43923 + outer loop + vertex 484.431 68.817 44.1507 + vertex 483.737 68.2382 43.0398 + vertex 486.598 68.5418 43.366 + endloop + endfacet + facet normal 0.0470808 -0.894884 0.443808 + outer loop + vertex 484.431 68.817 44.1507 + vertex 486.598 68.5418 43.366 + vertex 485.456 69.1228 44.6588 + endloop + endfacet + facet normal 0.0388907 -0.888789 0.456663 + outer loop + vertex 484.431 68.817 44.1507 + vertex 485.456 69.1228 44.6588 + vertex 482.533 69.2288 45.1139 + endloop + endfacet + facet normal 0.0391619 -0.887978 0.458215 + outer loop + vertex 485.456 69.1228 44.6588 + vertex 481.522 69.7293 46.1702 + vertex 482.533 69.2288 45.1139 + endloop + endfacet + facet normal 0.0266361 -0.899102 0.436928 + outer loop + vertex 482.533 69.2288 45.1139 + vertex 481.48 68.6393 43.965 + vertex 484.431 68.817 44.1507 + endloop + endfacet + facet normal 0.00783679 -0.89258 0.450822 + outer loop + vertex 482.533 69.2288 45.1139 + vertex 479.082 69.2132 45.1429 + vertex 481.48 68.6393 43.965 + endloop + endfacet + facet normal 0.00771367 -0.892682 0.450621 + outer loop + vertex 479.082 69.2132 45.1429 + vertex 476.629 68.3077 43.3913 + vertex 481.48 68.6393 43.965 + endloop + endfacet + facet normal -0.0175533 -0.877969 0.478396 + outer loop + vertex 476.629 68.3077 43.3913 + vertex 479.082 69.2132 45.1429 + vertex 473.767 69.1665 44.8622 + endloop + endfacet + facet normal -0.0147879 -0.875774 0.482496 + outer loop + vertex 473.767 69.1665 44.8622 + vertex 470.082 67.9599 42.5593 + vertex 476.629 68.3077 43.3913 + endloop + endfacet + facet normal 0.00769044 -0.904151 0.427144 + outer loop + vertex 480.37 69.5956 45.9291 + vertex 479.082 69.2132 45.1429 + vertex 482.533 69.2288 45.1139 + endloop + endfacet + facet normal 0.0126961 -0.898864 0.438044 + outer loop + vertex 480.37 69.5956 45.9291 + vertex 482.533 69.2288 45.1139 + vertex 481.522 69.7293 46.1702 + endloop + endfacet + facet normal 0.00273784 -0.879919 0.475115 + outer loop + vertex 480.37 69.5956 45.9291 + vertex 481.522 69.7293 46.1702 + vertex 476.552 70.136 46.9521 + endloop + endfacet + facet normal -0.0155536 -0.924105 0.381822 + outer loop + vertex 478.952 70.5579 48.071 + vertex 476.552 70.136 46.9521 + vertex 481.522 69.7293 46.1702 + endloop + endfacet + facet normal -0.0253954 -0.916186 0.399947 + outer loop + vertex 478.952 70.5579 48.071 + vertex 474.342 71.4265 49.768 + vertex 476.552 70.136 46.9521 + endloop + endfacet + facet normal -0.0611024 -0.924676 0.375819 + outer loop + vertex 471.15 71.3367 49.0281 + vertex 476.552 70.136 46.9521 + vertex 474.342 71.4265 49.768 + endloop + endfacet + facet normal -0.0644063 -0.918829 0.389365 + outer loop + vertex 474.342 71.4265 49.768 + vertex 470.242 72.3819 51.3443 + vertex 471.15 71.3367 49.0281 + endloop + endfacet + facet normal -0.104736 -0.921237 0.374637 + outer loop + vertex 466.71 72.7038 51.1486 + vertex 471.15 71.3367 49.0281 + vertex 470.242 72.3819 51.3443 + endloop + endfacet + facet normal -0.104792 -0.919962 0.377742 + outer loop + vertex 470.242 72.3819 51.3443 + vertex 466.632 73.5973 53.3027 + vertex 466.71 72.7038 51.1486 + endloop + endfacet + facet normal -0.0817689 -0.906848 0.413449 + outer loop + vertex 466.71 72.7038 51.1486 + vertex 466.236 71.5197 48.4575 + vertex 471.15 71.3367 49.0281 + endloop + endfacet + facet normal -0.0399145 -0.906454 0.420413 + outer loop + vertex 471.15 71.3367 49.0281 + vertex 470.199 70.2506 46.596 + vertex 476.552 70.136 46.9521 + endloop + endfacet + facet normal -0.0420637 -0.883757 0.466052 + outer loop + vertex 476.552 70.136 46.9521 + vertex 470.199 70.2506 46.596 + vertex 473.767 69.1665 44.8622 + endloop + endfacet + facet normal -0.0152016 -0.899141 0.437395 + outer loop + vertex 476.552 70.136 46.9521 + vertex 473.767 69.1665 44.8622 + vertex 479.082 69.2132 45.1429 + endloop + endfacet + facet normal -0.0409064 -0.882851 0.467868 + outer loop + vertex 470.199 70.2506 46.596 + vertex 467.03 69.0924 44.1334 + vertex 473.767 69.1665 44.8622 + endloop + endfacet + facet normal -0.00698941 -0.8947 0.446612 + outer loop + vertex 480.37 69.5956 45.9291 + vertex 476.552 70.136 46.9521 + vertex 479.082 69.2132 45.1429 + endloop + endfacet + facet normal 0.00281554 -0.875964 0.482369 + outer loop + vertex 481.48 68.6393 43.965 + vertex 476.629 68.3077 43.3913 + vertex 479.425 67.6962 42.2644 + endloop + endfacet + facet normal 0.00862899 -0.869749 0.493419 + outer loop + vertex 476.629 68.3077 43.3913 + vertex 473.04 67.0119 41.1699 + vertex 479.425 67.6962 42.2644 + endloop + endfacet + facet normal 0.0443353 -0.887171 0.459307 + outer loop + vertex 483.737 68.2382 43.0398 + vertex 482.132 67.4581 41.6878 + vertex 485.626 67.8973 42.1988 + endloop + endfacet + facet normal 0.0423828 -0.889119 0.45571 + outer loop + vertex 486.598 68.5418 43.366 + vertex 483.737 68.2382 43.0398 + vertex 485.626 67.8973 42.1988 + endloop + endfacet + facet normal 0.0622536 -0.888622 0.454396 + outer loop + vertex 489.406 68.5579 43.0128 + vertex 485.456 69.1228 44.6588 + vertex 486.598 68.5418 43.366 + endloop + endfacet + facet normal 0.066774 -0.889924 0.451194 + outer loop + vertex 488.312 68.2052 42.4729 + vertex 487.404 67.6011 41.4157 + vertex 490.324 68.0172 41.8045 + endloop + endfacet + facet normal 0.0630014 -0.880637 0.469583 + outer loop + vertex 490.324 68.0172 41.8045 + vertex 487.404 67.6011 41.4157 + vertex 489.154 67.3384 40.6884 + endloop + endfacet + facet normal 0.0583459 -0.862861 0.502062 + outer loop + vertex 489.154 67.3384 40.6884 + vertex 485.51 66.7875 40.165 + vertex 486.391 66.3358 39.2864 + endloop + endfacet + facet normal 0.0795147 -0.87872 0.470667 + outer loop + vertex 491.906 67.7383 41.0151 + vertex 490.726 67.0822 39.9897 + vertex 493.466 67.5693 40.4361 + endloop + endfacet + facet normal 0.0922593 -0.871693 0.48129 + outer loop + vertex 495.401 67.7703 40.4366 + vertex 494.088 67.2048 39.6639 + vertex 494.476 66.9642 39.1538 + endloop + endfacet + facet normal 0.10458 -0.874274 0.474033 + outer loop + vertex 494.476 66.9642 39.1538 + vertex 498.983 67.9652 40.0058 + vertex 495.401 67.7703 40.4366 + endloop + endfacet + facet normal 0.103084 -0.871751 0.478982 + outer loop + vertex 493.585 66.4385 38.389 + vertex 498.983 67.9652 40.0058 + vertex 494.476 66.9642 39.1538 + endloop + endfacet + facet normal 0.104029 -0.872109 0.478126 + outer loop + vertex 494.476 66.9642 39.1538 + vertex 489.544 65.4607 37.4846 + vertex 493.585 66.4385 38.389 + endloop + endfacet + facet normal 0.0767941 -0.8823 0.46438 + outer loop + vertex 491.906 67.7383 41.0151 + vertex 493.466 67.5693 40.4361 + vertex 492.979 68.1325 41.5867 + endloop + endfacet + facet normal 0.0665412 -0.898137 0.434653 + outer loop + vertex 489.406 68.5579 43.0128 + vertex 492.979 68.1325 41.5867 + vertex 491.796 68.535 42.5996 + endloop + endfacet + facet normal 0.0661723 -0.919845 0.386662 + outer loop + vertex 493.443 68.538 42.3728 + vertex 495.742 68.4387 41.7431 + vertex 494.922 68.7226 42.5589 + endloop + endfacet + facet normal 0.0837205 -0.917599 0.388591 + outer loop + vertex 495.742 68.4387 41.7431 + vertex 497.52 68.3475 41.1447 + vertex 497.087 68.6515 41.956 + endloop + endfacet + facet normal 0.103251 -0.88221 0.459396 + outer loop + vertex 498.983 67.9652 40.0058 + vertex 495.34 68.2393 41.3508 + vertex 495.401 67.7703 40.4366 + endloop + endfacet + facet normal 0.0995026 -0.909801 0.402941 + outer loop + vertex 497.52 68.3475 41.1447 + vertex 498.625 68.3457 40.8678 + vertex 498.62 68.6161 41.4796 + endloop + endfacet + facet normal 0.112053 -0.90854 0.402491 + outer loop + vertex 499.314 68.7003 41.4763 + vertex 498.62 68.6161 41.4796 + vertex 498.625 68.3457 40.8678 + endloop + endfacet + facet normal 0.124908 -0.912964 0.388452 + outer loop + vertex 499.999 69.316 42.7032 + vertex 499.499 69.1464 42.4653 + vertex 499.314 68.7003 41.4763 + endloop + endfacet + facet normal 0.127943 -0.923547 0.361512 + outer loop + vertex 500.771 70.0121 44.2083 + vertex 500.438 69.991 44.2722 + vertex 499.999 69.316 42.7032 + endloop + endfacet + facet normal 0.117717 -0.928985 0.350897 + outer loop + vertex 503.455 70.3755 44.2932 + vertex 504.585 71.7144 47.4589 + vertex 502.117 70.4207 44.8616 + endloop + endfacet + facet normal 0.124801 -0.921811 0.367 + outer loop + vertex 501.237 69.376 42.537 + vertex 503.455 70.3755 44.2932 + vertex 502.117 70.4207 44.8616 + endloop + endfacet + facet normal 0.118505 -0.919886 0.373854 + outer loop + vertex 502.668 69.3276 41.9642 + vertex 503.455 70.3755 44.2932 + vertex 501.237 69.376 42.537 + endloop + endfacet + facet normal 0.126986 -0.910198 0.394227 + outer loop + vertex 502.668 69.3276 41.9642 + vertex 501.237 69.376 42.537 + vertex 498.983 67.9652 40.0058 + endloop + endfacet + facet normal 0.139175 -0.9163 0.375532 + outer loop + vertex 498.983 67.9652 40.0058 + vertex 503.615 68.9543 40.7024 + vertex 502.668 69.3276 41.9642 + endloop + endfacet + facet normal 0.13368 -0.918528 0.372069 + outer loop + vertex 505.77 69.6915 41.7481 + vertex 502.668 69.3276 41.9642 + vertex 503.615 68.9543 40.7024 + endloop + endfacet + facet normal 0.14487 -0.924309 0.353081 + outer loop + vertex 503.615 68.9543 40.7024 + vertex 507.534 69.4992 40.521 + vertex 505.77 69.6915 41.7481 + endloop + endfacet + facet normal 0.147103 -0.922813 0.356056 + outer loop + vertex 510.05 70.2909 41.5334 + vertex 505.77 69.6915 41.7481 + vertex 507.534 69.4992 40.521 + endloop + endfacet + facet normal 0.153093 -0.926411 0.343985 + outer loop + vertex 507.534 69.4992 40.521 + vertex 511.702 70.152 40.4241 + vertex 510.05 70.2909 41.5334 + endloop + endfacet + facet normal 0.16434 -0.918465 0.359742 + outer loop + vertex 515.731 71.1975 41.253 + vertex 510.05 70.2909 41.5334 + vertex 511.702 70.152 40.4241 + endloop + endfacet + facet normal 0.172057 -0.927066 0.333083 + outer loop + vertex 511.702 70.152 40.4241 + vertex 517.287 71.0875 40.1429 + vertex 515.731 71.1975 41.253 + endloop + endfacet + facet normal 0.181481 -0.920644 0.345657 + outer loop + vertex 522.456 72.3517 40.7959 + vertex 515.731 71.1975 41.253 + vertex 517.287 71.0875 40.1429 + endloop + endfacet + facet normal 0.179352 -0.917185 0.355815 + outer loop + vertex 517.287 71.0875 40.1429 + vertex 522.129 71.9823 40.0087 + vertex 522.456 72.3517 40.7959 + endloop + endfacet + facet normal 0.19714 -0.916493 0.348104 + outer loop + vertex 522.129 71.9823 40.0087 + vertex 528.157 73.3329 40.1507 + vertex 522.456 72.3517 40.7959 + endloop + endfacet + facet normal 0.211319 -0.961595 0.175155 + outer loop + vertex 528.157 73.3329 40.1507 + vertex 522.129 71.9823 40.0087 + vertex 524.54 72.4415 39.6209 + endloop + endfacet + facet normal 0.181488 -0.919821 0.347838 + outer loop + vertex 522.456 72.3517 40.7959 + vertex 523.238 73.4501 43.293 + vertex 515.731 71.1975 41.253 + endloop + endfacet + facet normal 0.180674 -0.919133 0.350074 + outer loop + vertex 515.731 71.1975 41.253 + vertex 523.238 73.4501 43.293 + vertex 515.399 72.0532 43.6707 + endloop + endfacet + facet normal 0.181086 -0.928256 0.324884 + outer loop + vertex 523.238 73.4501 43.293 + vertex 523.033 74.9946 47.8199 + vertex 515.399 72.0532 43.6707 + endloop + endfacet + facet normal 0.173988 -0.925625 0.336076 + outer loop + vertex 515.399 72.0532 43.6707 + vertex 523.033 74.9946 47.8199 + vertex 514.659 73.1866 47.1754 + endloop + endfacet + facet normal 0.161072 -0.928597 0.33431 + outer loop + vertex 515.399 72.0532 43.6707 + vertex 514.659 73.1866 47.1754 + vertex 509.595 71.03 43.6249 + endloop + endfacet + facet normal 0.159259 -0.919443 0.359528 + outer loop + vertex 510.05 70.2909 41.5334 + vertex 515.399 72.0532 43.6707 + vertex 509.595 71.03 43.6249 + endloop + endfacet + facet normal 0.148145 -0.924795 0.350438 + outer loop + vertex 509.595 71.03 43.6249 + vertex 514.659 73.1866 47.1754 + vertex 509.437 71.8881 45.9564 + endloop + endfacet + facet normal 0.142262 -0.925739 0.350385 + outer loop + vertex 509.595 71.03 43.6249 + vertex 509.437 71.8881 45.9564 + vertex 505.817 70.5121 43.7907 + endloop + endfacet + facet normal 0.142117 -0.919622 0.366195 + outer loop + vertex 505.77 69.6915 41.7481 + vertex 509.595 71.03 43.6249 + vertex 505.817 70.5121 43.7907 + endloop + endfacet + facet normal 0.133563 -0.920659 0.366809 + outer loop + vertex 505.77 69.6915 41.7481 + vertex 505.817 70.5121 43.7907 + vertex 502.668 69.3276 41.9642 + endloop + endfacet + facet normal 0.143553 -0.926235 0.348542 + outer loop + vertex 505.817 70.5121 43.7907 + vertex 509.437 71.8881 45.9564 + vertex 506.89 71.7946 46.7572 + endloop + endfacet + facet normal 0.128872 -0.926361 0.353904 + outer loop + vertex 505.817 70.5121 43.7907 + vertex 506.89 71.7946 46.7572 + vertex 503.455 70.3755 44.2932 + endloop + endfacet + facet normal 0.140214 -0.930867 0.337381 + outer loop + vertex 509.437 71.8881 45.9564 + vertex 511.85 73.557 49.5582 + vertex 506.89 71.7946 46.7572 + endloop + endfacet + facet normal 0.149543 -0.934467 0.323123 + outer loop + vertex 506.89 71.7946 46.7572 + vertex 511.85 73.557 49.5582 + vertex 508.219 73.3056 50.5116 + endloop + endfacet + facet normal 0.132778 -0.93487 0.329223 + outer loop + vertex 506.89 71.7946 46.7572 + vertex 508.219 73.3056 50.5116 + vertex 504.585 71.7144 47.4589 + endloop + endfacet + facet normal 0.146402 -0.939448 0.309846 + outer loop + vertex 511.85 73.557 49.5582 + vertex 512.736 74.9838 53.4655 + vertex 508.219 73.3056 50.5116 + endloop + endfacet + facet normal 0.158183 -0.942721 0.293692 + outer loop + vertex 508.219 73.3056 50.5116 + vertex 512.736 74.9838 53.4655 + vertex 509.414 74.8664 54.8781 + endloop + endfacet + facet normal 0.139726 -0.943915 0.299169 + outer loop + vertex 508.219 73.3056 50.5116 + vertex 509.414 74.8664 54.8781 + vertex 505.773 73.2182 51.3781 + endloop + endfacet + facet normal 0.15264 -0.947715 0.280244 + outer loop + vertex 512.736 74.9838 53.4655 + vertex 515.023 76.8079 58.3887 + vertex 509.414 74.8664 54.8781 + endloop + endfacet + facet normal 0.1627 -0.950261 0.26558 + outer loop + vertex 509.414 74.8664 54.8781 + vertex 515.023 76.8079 58.3887 + vertex 510.406 76.463 59.983 + endloop + endfacet + facet normal 0.145284 -0.951978 0.269501 + outer loop + vertex 509.414 74.8664 54.8781 + vertex 510.406 76.463 59.983 + vertex 506.804 74.7374 55.8297 + endloop + endfacet + facet normal 0.15852 -0.954509 0.252556 + outer loop + vertex 515.023 76.8079 58.3887 + vertex 516.03 78.7214 64.9884 + vertex 510.406 76.463 59.983 + endloop + endfacet + facet normal 0.1676 -0.95549 0.242797 + outer loop + vertex 510.406 76.463 59.983 + vertex 516.03 78.7214 64.9884 + vertex 510.705 77.9767 65.7335 + endloop + endfacet + facet normal 0.147857 -0.958294 0.244563 + outer loop + vertex 510.406 76.463 59.983 + vertex 510.705 77.9767 65.7335 + vertex 507.474 76.1554 60.5501 + endloop + endfacet + facet normal 0.165883 -0.959863 0.226157 + outer loop + vertex 516.03 78.7214 64.9884 + vertex 516.133 80.4238 72.1382 + vertex 510.705 77.9767 65.7335 + endloop + endfacet + facet normal 0.168184 -0.959915 0.224227 + outer loop + vertex 516.133 80.4238 72.1382 + vertex 509.915 79.4266 72.5334 + vertex 510.705 77.9767 65.7335 + endloop + endfacet + facet normal 0.167669 -0.964257 0.205173 + outer loop + vertex 516.133 80.4238 72.1382 + vertex 516.097 82.1214 80.1464 + vertex 509.915 79.4266 72.5334 + endloop + endfacet + facet normal 0.173621 -0.964222 0.200327 + outer loop + vertex 509.915 79.4266 72.5334 + vertex 516.097 82.1214 80.1464 + vertex 510.881 81.5435 81.8855 + endloop + endfacet + facet normal 0.16955 -0.96762 0.186989 + outer loop + vertex 516.097 82.1214 80.1464 + vertex 516.101 83.7625 88.6348 + vertex 510.881 81.5435 81.8855 + endloop + endfacet + facet normal 0.192731 -0.963429 0.186168 + outer loop + vertex 516.097 82.1214 80.1464 + vertex 523.806 85.1181 87.6734 + vertex 516.101 83.7625 88.6348 + endloop + endfacet + facet normal 0.191525 -0.96619 0.172612 + outer loop + vertex 523.806 85.1181 87.6734 + vertex 523.671 86.6344 96.3107 + vertex 516.101 83.7625 88.6348 + endloop + endfacet + facet normal 0.196544 -0.966062 0.167614 + outer loop + vertex 516.101 83.7625 88.6348 + vertex 523.671 86.6344 96.3107 + vertex 515.995 85.2187 97.1515 + endloop + endfacet + facet normal 0.172632 -0.970539 0.168084 + outer loop + vertex 516.101 83.7625 88.6348 + vertex 515.995 85.2187 97.1515 + vertex 510.537 83.0314 90.1272 + endloop + endfacet + facet normal 0.195567 -0.968402 0.154758 + outer loop + vertex 523.671 86.6344 96.3107 + vertex 523.453 87.9762 104.982 + vertex 515.995 85.2187 97.1515 + endloop + endfacet + facet normal 0.200642 -0.968139 0.149832 + outer loop + vertex 515.995 85.2187 97.1515 + vertex 523.453 87.9762 104.982 + vertex 515.798 86.5024 105.71 + endloop + endfacet + facet normal 0.179287 -0.9723 0.149963 + outer loop + vertex 515.995 85.2187 97.1515 + vertex 515.798 86.5024 105.71 + vertex 510.852 84.5251 98.8036 + endloop + endfacet + facet normal 0.199844 -0.970147 0.137395 + outer loop + vertex 523.453 87.9762 104.982 + vertex 523.221 89.1567 113.656 + vertex 515.798 86.5024 105.71 + endloop + endfacet + facet normal 0.204481 -0.9698 0.132947 + outer loop + vertex 515.798 86.5024 105.71 + vertex 523.221 89.1567 113.656 + vertex 515.484 87.6159 114.316 + endloop + endfacet + facet normal 0.184277 -0.97387 0.132736 + outer loop + vertex 515.798 86.5024 105.71 + vertex 515.484 87.6159 114.316 + vertex 510.192 85.629 107.085 + endloop + endfacet + facet normal 0.203735 -0.971662 0.119857 + outer loop + vertex 523.221 89.1567 113.656 + vertex 522.92 90.1637 122.331 + vertex 515.484 87.6159 114.316 + endloop + endfacet + facet normal 0.20751 -0.971302 0.116242 + outer loop + vertex 515.484 87.6159 114.316 + vertex 522.92 90.1637 122.331 + vertex 515.126 88.5771 122.987 + endloop + endfacet + facet normal 0.188697 -0.975173 0.115893 + outer loop + vertex 515.484 87.6159 114.316 + vertex 515.126 88.5771 122.987 + vertex 510.215 86.7935 115.974 + endloop + endfacet + facet normal 0.206686 -0.973053 0.102216 + outer loop + vertex 522.92 90.1637 122.331 + vertex 522.606 91.0131 131.052 + vertex 515.126 88.5771 122.987 + endloop + endfacet + facet normal 0.210114 -0.97266 0.0989181 + outer loop + vertex 515.126 88.5771 122.987 + vertex 522.606 91.0131 131.052 + vertex 514.726 89.3767 131.699 + endloop + endfacet + facet normal 0.191547 -0.976536 0.0984211 + outer loop + vertex 515.126 88.5771 122.987 + vertex 514.726 89.3767 131.699 + vertex 509.36 87.5928 124.442 + endloop + endfacet + facet normal 0.209221 -0.974252 0.0840252 + outer loop + vertex 522.606 91.0131 131.052 + vertex 522.273 91.6997 139.842 + vertex 514.726 89.3767 131.699 + endloop + endfacet + facet normal 0.211896 -0.973893 0.0814434 + outer loop + vertex 514.726 89.3767 131.699 + vertex 522.273 91.6997 139.842 + vertex 514.307 90.0156 140.428 + endloop + endfacet + facet normal 0.194495 -0.977563 0.0808785 + outer loop + vertex 514.726 89.3767 131.699 + vertex 514.307 90.0156 140.428 + vertex 509.319 88.442 133.405 + endloop + endfacet + facet normal 0.211029 -0.97527 0.065685 + outer loop + vertex 522.273 91.6997 139.842 + vertex 521.945 92.2247 148.69 + vertex 514.307 90.0156 140.428 + endloop + endfacet + facet normal 0.213431 -0.974901 0.0633658 + outer loop + vertex 514.307 90.0156 140.428 + vertex 521.945 92.2247 148.69 + vertex 513.916 90.4989 149.18 + endloop + endfacet + facet normal 0.196137 -0.978564 0.0627953 + outer loop + vertex 514.307 90.0156 140.428 + vertex 513.916 90.4989 149.18 + vertex 508.445 88.921 141.68 + endloop + endfacet + facet normal 0.212672 -0.97599 0.0470646 + outer loop + vertex 521.945 92.2247 148.69 + vertex 521.638 92.5852 157.554 + vertex 513.916 90.4989 149.18 + endloop + endfacet + facet normal 0.214393 -0.975692 0.0454036 + outer loop + vertex 513.916 90.4989 149.18 + vertex 521.638 92.5852 157.554 + vertex 513.525 90.822 157.973 + endloop + endfacet + facet normal 0.198633 -0.979048 0.0448255 + outer loop + vertex 513.916 90.4989 149.18 + vertex 513.525 90.822 157.973 + vertex 508.423 89.4437 150.478 + endloop + endfacet + facet normal 0.21367 -0.976506 0.027961 + outer loop + vertex 521.638 92.5852 157.554 + vertex 521.304 92.7652 166.388 + vertex 513.525 90.822 157.973 + endloop + endfacet + facet normal 0.214939 -0.976262 0.0267321 + outer loop + vertex 513.525 90.822 157.973 + vertex 521.304 92.7652 166.388 + vertex 513.152 90.9808 166.771 + endloop + endfacet + facet normal 0.199193 -0.979612 0.0261247 + outer loop + vertex 513.525 90.822 157.973 + vertex 513.152 90.9808 166.771 + vertex 507.539 89.6353 159.117 + endloop + endfacet + facet normal 0.214181 -0.976759 0.00827987 + outer loop + vertex 521.304 92.7652 166.388 + vertex 521.035 92.7807 175.185 + vertex 513.152 90.9808 166.771 + endloop + endfacet + facet normal 0.214853 -0.976617 0.00761986 + outer loop + vertex 513.152 90.9808 166.771 + vertex 521.035 92.7807 175.185 + vertex 512.758 90.9626 175.528 + endloop + endfacet + facet normal 0.20003 -0.979765 0.00694755 + outer loop + vertex 513.152 90.9808 166.771 + vertex 512.758 90.9626 175.528 + vertex 507.534 89.8432 168.079 + endloop + endfacet + facet normal 0.214072 -0.976745 -0.0119477 + outer loop + vertex 521.035 92.7807 175.185 + vertex 520.741 92.6093 183.937 + vertex 512.758 90.9626 175.528 + endloop + endfacet + facet normal 0.214399 -0.976669 -0.0122735 + outer loop + vertex 512.758 90.9626 175.528 + vertex 520.741 92.6093 183.937 + vertex 512.396 90.7734 184.254 + endloop + endfacet + facet normal 0.199648 -0.979782 -0.0129538 + outer loop + vertex 512.758 90.9626 175.528 + vertex 512.396 90.7734 184.254 + vertex 506.609 89.6942 176.693 + endloop + endfacet + facet normal 0.213553 -0.976379 -0.0328433 + outer loop + vertex 520.741 92.6093 183.937 + vertex 520.483 92.259 192.672 + vertex 512.396 90.7734 184.254 + endloop + endfacet + facet normal 0.213028 -0.976511 -0.032316 + outer loop + vertex 512.396 90.7734 184.254 + vertex 520.483 92.259 192.672 + vertex 511.999 90.399 192.948 + endloop + endfacet + facet normal 0.198766 -0.979488 -0.0330958 + outer loop + vertex 512.396 90.7734 184.254 + vertex 511.999 90.399 192.948 + vertex 506.574 89.548 185.554 + endloop + endfacet + facet normal 0.212135 -0.975721 -0.0544727 + outer loop + vertex 520.483 92.259 192.672 + vertex 520.228 91.716 201.405 + vertex 511.999 90.399 192.948 + endloop + endfacet + facet normal 0.211443 -0.97591 -0.0537705 + outer loop + vertex 511.999 90.399 192.948 + vertex 520.228 91.716 201.405 + vertex 511.645 89.8428 201.652 + endloop + endfacet + facet normal 0.196954 -0.978894 -0.05455 + outer loop + vertex 511.999 90.399 192.948 + vertex 511.645 89.8428 201.652 + vertex 505.672 89.0587 194.156 + endloop + endfacet + facet normal 0.210507 -0.974605 -0.0763637 + outer loop + vertex 520.228 91.716 201.405 + vertex 519.994 90.9789 210.167 + vertex 511.645 89.8428 201.652 + endloop + endfacet + facet normal 0.209519 -0.974897 -0.0753559 + outer loop + vertex 511.645 89.8428 201.652 + vertex 519.994 90.9789 210.167 + vertex 511.292 89.091 210.397 + endloop + endfacet + facet normal 0.195162 -0.977807 -0.0761852 + outer loop + vertex 511.645 89.8428 201.652 + vertex 511.292 89.091 210.397 + vertex 505.689 88.5481 203.012 + endloop + endfacet + facet normal 0.208561 -0.973156 -0.0973122 + outer loop + vertex 519.994 90.9789 210.167 + vertex 519.763 90.0494 218.968 + vertex 511.292 89.091 210.397 + endloop + endfacet + facet normal 0.207652 -0.973443 -0.0963817 + outer loop + vertex 511.292 89.091 210.397 + vertex 519.763 90.0494 218.968 + vertex 510.949 88.1498 219.163 + endloop + endfacet + facet normal 0.19299 -0.976367 -0.09727 + outer loop + vertex 511.292 89.091 210.397 + vertex 510.949 88.1498 219.163 + vertex 504.737 87.6699 211.655 + endloop + endfacet + facet normal 0.206793 -0.971478 -0.116047 + outer loop + vertex 519.763 90.0494 218.968 + vertex 519.511 88.9447 227.767 + vertex 510.949 88.1498 219.163 + endloop + endfacet + facet normal 0.205962 -0.971756 -0.115194 + outer loop + vertex 510.949 88.1498 219.163 + vertex 519.511 88.9447 227.767 + vertex 510.592 87.0443 227.851 + endloop + endfacet + facet normal 0.22062 -0.968523 -0.115281 + outer loop + vertex 519.763 90.0494 218.968 + vertex 530.512 91.4162 228.055 + vertex 519.511 88.9447 227.767 + endloop + endfacet + facet normal 0.220577 -0.96629 -0.132775 + outer loop + vertex 530.512 91.4162 228.055 + vertex 530.382 90.171 236.902 + vertex 519.511 88.9447 227.767 + endloop + endfacet + facet normal 0.219362 -0.966773 -0.131265 + outer loop + vertex 519.511 88.9447 227.767 + vertex 530.382 90.171 236.902 + vertex 519.258 87.6989 236.518 + endloop + endfacet + facet normal 0.237205 -0.962451 -0.13199 + outer loop + vertex 530.512 91.4162 228.055 + vertex 542.747 93.1662 237.282 + vertex 530.382 90.171 236.902 + endloop + endfacet + facet normal 0.237153 -0.960545 -0.145297 + outer loop + vertex 542.747 93.1662 237.282 + vertex 542.766 91.8289 246.155 + vertex 530.382 90.171 236.902 + endloop + endfacet + facet normal 0.236086 -0.961036 -0.143781 + outer loop + vertex 530.382 90.171 236.902 + vertex 542.766 91.8289 246.155 + vertex 530.258 88.828 245.675 + endloop + endfacet + facet normal 0.25679 -0.95559 -0.144593 + outer loop + vertex 542.747 93.1662 237.282 + vertex 555.653 95.2476 246.448 + vertex 542.766 91.8289 246.155 + endloop + endfacet + facet normal 0.256651 -0.954377 -0.152628 + outer loop + vertex 555.653 95.2476 246.448 + vertex 555.799 93.8679 255.32 + vertex 542.766 91.8289 246.155 + endloop + endfacet + facet normal 0.255195 -0.955122 -0.150391 + outer loop + vertex 542.766 91.8289 246.155 + vertex 555.799 93.8679 255.32 + vertex 542.833 90.4591 254.967 + endloop + endfacet + facet normal 0.275851 -0.949087 -0.152119 + outer loop + vertex 555.653 95.2476 246.448 + vertex 568.413 97.5293 255.351 + vertex 555.799 93.8679 255.32 + endloop + endfacet + facet normal 0.275723 -0.948618 -0.155242 + outer loop + vertex 568.413 97.5293 255.351 + vertex 568.667 96.1549 264.2 + vertex 555.799 93.8679 255.32 + endloop + endfacet + facet normal 0.272633 -0.950301 -0.150331 + outer loop + vertex 555.799 93.8679 255.32 + vertex 568.667 96.1549 264.2 + vertex 556.023 92.5299 264.185 + endloop + endfacet + facet normal 0.290474 -0.944248 -0.154986 + outer loop + vertex 568.413 97.5293 255.351 + vertex 580.068 99.7454 263.693 + vertex 568.667 96.1549 264.2 + endloop + endfacet + facet normal 0.290623 -0.944479 -0.153287 + outer loop + vertex 580.068 99.7454 263.693 + vertex 580.531 98.4562 272.514 + vertex 568.667 96.1549 264.2 + endloop + endfacet + facet normal 0.283961 -0.948148 -0.142765 + outer loop + vertex 568.667 96.1549 264.2 + vertex 580.531 98.4562 272.514 + vertex 569.042 94.9239 273.121 + endloop + endfacet + facet normal 0.296991 -0.942489 -0.153331 + outer loop + vertex 580.068 99.7454 263.693 + vertex 588.676 101.286 270.899 + vertex 580.531 98.4562 272.514 + endloop + endfacet + facet normal 0.294616 -0.941887 -0.1614 + outer loop + vertex 579.676 101.122 254.945 + vertex 580.068 99.7454 263.693 + vertex 568.413 97.5293 255.351 + endloop + endfacet + facet normal 0.295033 -0.942617 -0.156298 + outer loop + vertex 568.147 98.9098 246.523 + vertex 579.676 101.122 254.945 + vertex 568.413 97.5293 255.351 + endloop + endfacet + facet normal 0.29831 -0.940745 -0.161275 + outer loop + vertex 579.226 102.451 246.363 + vertex 579.676 101.122 254.945 + vertex 568.147 98.9098 246.523 + endloop + endfacet + facet normal 0.298914 -0.942191 -0.151415 + outer loop + vertex 567.904 100.249 237.707 + vertex 579.226 102.451 246.363 + vertex 568.147 98.9098 246.523 + endloop + endfacet + facet normal 0.281802 -0.947399 -0.151735 + outer loop + vertex 567.904 100.249 237.707 + vertex 568.147 98.9098 246.523 + vertex 555.489 96.5832 237.541 + endloop + endfacet + facet normal 0.282237 -0.949551 -0.136728 + outer loop + vertex 555.335 97.8216 228.623 + vertex 567.904 100.249 237.707 + vertex 555.489 96.5832 237.541 + endloop + endfacet + facet normal 0.261412 -0.955429 -0.137186 + outer loop + vertex 555.335 97.8216 228.623 + vertex 555.489 96.5832 237.541 + vertex 542.712 94.4042 228.37 + endloop + endfacet + facet normal 0.261686 -0.957792 -0.118976 + outer loop + vertex 542.669 95.4993 219.459 + vertex 555.335 97.8216 228.623 + vertex 542.712 94.4042 228.37 + endloop + endfacet + facet normal 0.24103 -0.963129 -0.119532 + outer loop + vertex 542.669 95.4993 219.459 + vertex 542.712 94.4042 228.37 + vertex 530.608 92.5149 219.186 + endloop + endfacet + facet normal 0.241137 -0.965506 -0.0982421 + outer loop + vertex 530.697 93.4373 210.34 + vertex 542.669 95.4993 219.459 + vertex 530.608 92.5149 219.186 + endloop + endfacet + facet normal 0.224272 -0.969502 -0.0988287 + outer loop + vertex 530.697 93.4373 210.34 + vertex 530.608 92.5149 219.186 + vertex 519.994 90.9789 210.167 + endloop + endfacet + facet normal 0.243032 -0.964756 -0.100899 + outer loop + vertex 542.676 96.4303 210.574 + vertex 542.669 95.4993 219.459 + vertex 530.697 93.4373 210.34 + endloop + endfacet + facet normal 0.243109 -0.966927 -0.0771424 + outer loop + vertex 530.827 94.1727 201.531 + vertex 542.676 96.4303 210.574 + vertex 530.697 93.4373 210.34 + endloop + endfacet + facet normal 0.225991 -0.971023 -0.0777371 + outer loop + vertex 530.827 94.1727 201.531 + vertex 530.697 93.4373 210.34 + vertex 520.228 91.716 201.405 + endloop + endfacet + facet normal 0.244655 -0.966361 -0.0793089 + outer loop + vertex 542.718 97.168 201.716 + vertex 542.676 96.4303 210.574 + vertex 530.827 94.1727 201.531 + endloop + endfacet + facet normal 0.244699 -0.968041 -0.0549435 + outer loop + vertex 530.984 94.7111 192.742 + vertex 542.718 97.168 201.716 + vertex 530.827 94.1727 201.531 + endloop + endfacet + facet normal 0.227402 -0.972218 -0.0555069 + outer loop + vertex 530.984 94.7111 192.742 + vertex 530.827 94.1727 201.531 + vertex 520.483 92.259 192.672 + endloop + endfacet + facet normal 0.245911 -0.967636 -0.0566389 + outer loop + vertex 542.777 97.7006 192.873 + vertex 542.718 97.168 201.716 + vertex 530.984 94.7111 192.742 + endloop + endfacet + facet normal 0.245925 -0.968732 -0.0328377 + outer loop + vertex 531.156 95.0529 183.953 + vertex 542.777 97.7006 192.873 + vertex 530.984 94.7111 192.742 + endloop + endfacet + facet normal 0.228335 -0.973011 -0.03335 + outer loop + vertex 531.156 95.0529 183.953 + vertex 530.984 94.7111 192.742 + vertex 520.741 92.6093 183.937 + endloop + endfacet + facet normal 0.247217 -0.968341 -0.0346368 + outer loop + vertex 542.868 98.04 184.028 + vertex 542.777 97.7006 192.873 + vertex 531.156 95.0529 183.953 + endloop + endfacet + facet normal 0.24721 -0.968892 -0.011675 + outer loop + vertex 531.327 95.2024 175.142 + vertex 542.868 98.04 184.028 + vertex 531.156 95.0529 183.953 + endloop + endfacet + facet normal 0.228989 -0.973354 -0.0121023 + outer loop + vertex 531.327 95.2024 175.142 + vertex 531.156 95.0529 183.953 + vertex 521.035 92.7807 175.185 + endloop + endfacet + facet normal 0.247949 -0.96869 -0.0126998 + outer loop + vertex 542.966 98.1815 175.161 + vertex 542.868 98.04 184.028 + vertex 531.327 95.2024 175.142 + endloop + endfacet + facet normal 0.247924 -0.968737 0.00911495 + outer loop + vertex 531.523 95.1694 166.293 + vertex 542.966 98.1815 175.161 + vertex 531.327 95.2024 175.142 + endloop + endfacet + facet normal 0.229094 -0.973365 0.00871478 + outer loop + vertex 531.523 95.1694 166.293 + vertex 531.327 95.2024 175.142 + vertex 521.304 92.7652 166.388 + endloop + endfacet + facet normal 0.248324 -0.968639 0.00856596 + outer loop + vertex 543.095 98.1359 166.253 + vertex 542.966 98.1815 175.161 + vertex 531.523 95.1694 166.293 + endloop + endfacet + facet normal 0.248294 -0.968242 0.0292672 + outer loop + vertex 531.771 94.9641 157.397 + vertex 543.095 98.1359 166.253 + vertex 531.523 95.1694 166.293 + endloop + endfacet + facet normal 0.22888 -0.973027 0.028836 + outer loop + vertex 531.771 94.9641 157.397 + vertex 531.523 95.1694 166.293 + vertex 521.638 92.5852 157.554 + endloop + endfacet + facet normal 0.248046 -0.968296 0.0296044 + outer loop + vertex 543.243 97.8998 157.295 + vertex 543.095 98.1359 166.253 + vertex 531.771 94.9641 157.397 + endloop + endfacet + facet normal 0.248018 -0.96752 0.0489097 + outer loop + vertex 532.005 94.5728 148.467 + vertex 543.243 97.8998 157.295 + vertex 531.771 94.9641 157.397 + endloop + endfacet + facet normal 0.228044 -0.972437 0.0486007 + outer loop + vertex 532.005 94.5728 148.467 + vertex 531.771 94.9641 157.397 + vertex 521.945 92.2247 148.69 + endloop + endfacet + facet normal 0.247445 -0.967627 0.0496798 + outer loop + vertex 543.403 97.4793 148.31 + vertex 543.243 97.8998 157.295 + vertex 532.005 94.5728 148.467 + endloop + endfacet + facet normal 0.247416 -0.966521 0.0679835 + outer loop + vertex 532.245 94.0078 139.561 + vertex 543.403 97.4793 148.31 + vertex 532.005 94.5728 148.467 + endloop + endfacet + facet normal 0.226776 -0.971588 0.067749 + outer loop + vertex 532.245 94.0078 139.561 + vertex 532.005 94.5728 148.467 + vertex 522.273 91.6997 139.842 + endloop + endfacet + facet normal 0.246448 -0.966677 0.0692792 + outer loop + vertex 543.563 96.8786 139.356 + vertex 543.403 97.4793 148.31 + vertex 532.245 94.0078 139.561 + endloop + endfacet + facet normal 0.24641 -0.965266 0.0868511 + outer loop + vertex 532.473 93.2714 130.73 + vertex 543.563 96.8786 139.356 + vertex 532.245 94.0078 139.561 + endloop + endfacet + facet normal 0.224941 -0.970504 0.0867335 + outer loop + vertex 532.473 93.2714 130.73 + vertex 532.245 94.0078 139.561 + vertex 522.606 91.0131 131.052 + endloop + endfacet + facet normal 0.245068 -0.965444 0.088651 + outer loop + vertex 543.746 96.1104 130.484 + vertex 543.563 96.8786 139.356 + vertex 532.473 93.2714 130.73 + endloop + endfacet + facet normal 0.245014 -0.963792 0.105229 + outer loop + vertex 532.745 92.3852 121.98 + vertex 543.746 96.1104 130.484 + vertex 532.473 93.2714 130.73 + endloop + endfacet + facet normal 0.222877 -0.969166 0.105086 + outer loop + vertex 532.745 92.3852 121.98 + vertex 532.473 93.2714 130.73 + vertex 522.92 90.1637 122.331 + endloop + endfacet + facet normal 0.243034 -0.964 0.107881 + outer loop + vertex 543.946 95.1758 121.683 + vertex 543.746 96.1104 130.484 + vertex 532.745 92.3852 121.98 + endloop + endfacet + facet normal 0.242985 -0.962133 0.123527 + outer loop + vertex 532.973 91.3214 113.246 + vertex 543.946 95.1758 121.683 + vertex 532.745 92.3852 121.98 + endloop + endfacet + facet normal 0.219979 -0.967643 0.123596 + outer loop + vertex 532.973 91.3214 113.246 + vertex 532.745 92.3852 121.98 + vertex 523.221 89.1567 113.656 + endloop + endfacet + facet normal 0.240754 -0.962306 0.126507 + outer loop + vertex 544.161 94.0737 112.89 + vertex 543.946 95.1758 121.683 + vertex 532.973 91.3214 113.246 + endloop + endfacet + facet normal 0.240721 -0.9603 0.140986 + outer loop + vertex 533.209 90.0934 104.479 + vertex 544.161 94.0737 112.89 + vertex 532.973 91.3214 113.246 + endloop + endfacet + facet normal 0.216906 -0.965936 0.141137 + outer loop + vertex 533.209 90.0934 104.479 + vertex 532.973 91.3214 113.246 + vertex 523.453 87.9762 104.982 + endloop + endfacet + facet normal 0.238303 -0.960427 0.144196 + outer loop + vertex 544.36 92.7971 104.059 + vertex 544.161 94.0737 112.89 + vertex 533.209 90.0934 104.479 + endloop + endfacet + facet normal 0.238296 -0.958183 0.158432 + outer loop + vertex 533.379 88.6814 95.6833 + vertex 544.36 92.7971 104.059 + vertex 533.209 90.0934 104.479 + endloop + endfacet + facet normal 0.213512 -0.963936 0.158874 + outer loop + vertex 533.379 88.6814 95.6833 + vertex 533.209 90.0934 104.479 + vertex 523.671 86.6344 96.3107 + endloop + endfacet + facet normal 0.235614 -0.958253 0.161982 + outer loop + vertex 544.541 91.346 95.2105 + vertex 544.36 92.7971 104.059 + vertex 533.379 88.6814 95.6833 + endloop + endfacet + facet normal 0.235617 -0.955849 0.175603 + outer loop + vertex 533.564 87.1241 86.959 + vertex 544.541 91.346 95.2105 + vertex 533.379 88.6814 95.6833 + endloop + endfacet + facet normal 0.210573 -0.961586 0.176099 + outer loop + vertex 533.564 87.1241 86.959 + vertex 533.379 88.6814 95.6833 + vertex 523.806 85.1181 87.6734 + endloop + endfacet + facet normal 0.211019 -0.958883 0.189775 + outer loop + vertex 523.94 83.4785 79.2396 + vertex 533.564 87.1241 86.959 + vertex 523.806 85.1181 87.6734 + endloop + endfacet + facet normal 0.20785 -0.958794 0.193683 + outer loop + vertex 533.769 85.4468 78.4355 + vertex 533.564 87.1241 86.959 + vertex 523.94 83.4785 79.2396 + endloop + endfacet + facet normal 0.208418 -0.955537 0.208592 + outer loop + vertex 523.983 81.7277 71.1765 + vertex 533.769 85.4468 78.4355 + vertex 523.94 83.4785 79.2396 + endloop + endfacet + facet normal 0.185143 -0.960128 0.209464 + outer loop + vertex 523.983 81.7277 71.1765 + vertex 523.94 83.4785 79.2396 + vertex 516.133 80.4238 72.1382 + endloop + endfacet + facet normal 0.204134 -0.95522 0.214204 + outer loop + vertex 533.795 83.5819 70.0943 + vertex 533.769 85.4468 78.4355 + vertex 523.983 81.7277 71.1765 + endloop + endfacet + facet normal 0.205245 -0.95089 0.231695 + outer loop + vertex 523.416 79.6762 63.2596 + vertex 533.795 83.5819 70.0943 + vertex 523.983 81.7277 71.1765 + endloop + endfacet + facet normal 0.178491 -0.955513 0.234811 + outer loop + vertex 523.416 79.6762 63.2596 + vertex 523.983 81.7277 71.1765 + vertex 516.03 78.7214 64.9884 + endloop + endfacet + facet normal 0.199493 -0.950065 0.239958 + outer loop + vertex 533.309 81.3656 61.7238 + vertex 533.795 83.5819 70.0943 + vertex 523.416 79.6762 63.2596 + endloop + endfacet + facet normal 0.201586 -0.944433 0.259632 + outer loop + vertex 520.636 76.5929 54.2018 + vertex 533.309 81.3656 61.7238 + vertex 523.416 79.6762 63.2596 + endloop + endfacet + facet normal 0.166305 -0.94792 0.271644 + outer loop + vertex 520.636 76.5929 54.2018 + vertex 523.416 79.6762 63.2596 + vertex 515.023 76.8079 58.3887 + endloop + endfacet + facet normal 0.195402 -0.94306 0.269177 + outer loop + vertex 533.154 79.0874 53.8545 + vertex 533.309 81.3656 61.7238 + vertex 520.636 76.5929 54.2018 + endloop + endfacet + facet normal 0.19421 -0.931906 0.306323 + outer loop + vertex 523.033 74.9946 47.8199 + vertex 533.154 79.0874 53.8545 + vertex 520.636 76.5929 54.2018 + endloop + endfacet + facet normal 0.200267 -0.933551 0.297281 + outer loop + vertex 533.464 77.0691 47.3072 + vertex 533.154 79.0874 53.8545 + vertex 523.033 74.9946 47.8199 + endloop + endfacet + facet normal 0.222577 -0.928631 0.296822 + outer loop + vertex 533.464 77.0691 47.3072 + vertex 545.026 81.7601 53.3134 + vertex 533.154 79.0874 53.8545 + endloop + endfacet + facet normal 0.223189 -0.93713 0.268279 + outer loop + vertex 545.026 81.7601 53.3134 + vertex 545.026 83.9748 61.0505 + vertex 533.154 79.0874 53.8545 + endloop + endfacet + facet normal 0.250112 -0.930824 0.266477 + outer loop + vertex 545.026 81.7601 53.3134 + vertex 557.264 87.166 60.7101 + vertex 545.026 83.9748 61.0505 + endloop + endfacet + facet normal 0.251066 -0.937 0.24289 + outer loop + vertex 557.264 87.166 60.7101 + vertex 557.196 89.3124 69.0611 + vertex 545.026 83.9748 61.0505 + endloop + endfacet + facet normal 0.25284 -0.937186 0.24032 + outer loop + vertex 545.026 83.9748 61.0505 + vertex 557.196 89.3124 69.0611 + vertex 545.1 86.1268 69.3642 + endloop + endfacet + facet normal 0.224133 -0.94395 0.242328 + outer loop + vertex 545.026 83.9748 61.0505 + vertex 545.1 86.1268 69.3642 + vertex 533.309 81.3656 61.7238 + endloop + endfacet + facet normal 0.253613 -0.942126 0.219267 + outer loop + vertex 557.196 89.3124 69.0611 + vertex 557.016 91.2449 77.573 + vertex 545.1 86.1268 69.3642 + endloop + endfacet + facet normal 0.255842 -0.942253 0.216112 + outer loop + vertex 545.1 86.1268 69.3642 + vertex 557.016 91.2449 77.573 + vertex 545.005 88.0462 77.8453 + endloop + endfacet + facet normal 0.227707 -0.94916 0.21736 + outer loop + vertex 545.1 86.1268 69.3642 + vertex 545.005 88.0462 77.8453 + vertex 533.795 83.5819 70.0943 + endloop + endfacet + facet normal 0.256431 -0.945967 0.19847 + outer loop + vertex 557.016 91.2449 77.573 + vertex 556.731 92.9762 86.1922 + vertex 545.005 88.0462 77.8453 + endloop + endfacet + facet normal 0.258269 -0.946001 0.195907 + outer loop + vertex 545.005 88.0462 77.8453 + vertex 556.731 92.9762 86.1922 + vertex 544.766 89.7626 86.4487 + endloop + endfacet + facet normal 0.230784 -0.952951 0.19653 + outer loop + vertex 545.005 88.0462 77.8453 + vertex 544.766 89.7626 86.4487 + vertex 533.769 85.4468 78.4355 + endloop + endfacet + facet normal 0.258718 -0.948871 0.180855 + outer loop + vertex 556.731 92.9762 86.1922 + vertex 556.467 94.5749 94.9579 + vertex 544.766 89.7626 86.4487 + endloop + endfacet + facet normal 0.260672 -0.948847 0.178155 + outer loop + vertex 544.766 89.7626 86.4487 + vertex 556.467 94.5749 94.9579 + vertex 544.541 91.346 95.2105 + endloop + endfacet + facet normal 0.261037 -0.951309 0.163925 + outer loop + vertex 556.467 94.5749 94.9579 + vertex 556.25 96.0401 103.807 + vertex 544.541 91.346 95.2105 + endloop + endfacet + facet normal 0.287489 -0.943756 0.163323 + outer loop + vertex 556.467 94.5749 94.9579 + vertex 568.245 99.6838 103.749 + vertex 556.25 96.0401 103.807 + endloop + endfacet + facet normal 0.288105 -0.946023 0.148447 + outer loop + vertex 568.245 99.6838 103.749 + vertex 567.969 100.984 112.569 + vertex 556.25 96.0401 103.807 + endloop + endfacet + facet normal 0.289624 -0.945887 0.146339 + outer loop + vertex 556.25 96.0401 103.807 + vertex 567.969 100.984 112.569 + vertex 556.057 97.3478 112.642 + endloop + endfacet + facet normal 0.263179 -0.953499 0.146887 + outer loop + vertex 556.25 96.0401 103.807 + vertex 556.057 97.3478 112.642 + vertex 544.36 92.7971 104.059 + endloop + endfacet + facet normal 0.29017 -0.947986 0.130859 + outer loop + vertex 567.969 100.984 112.569 + vertex 567.784 102.134 121.313 + vertex 556.057 97.3478 112.642 + endloop + endfacet + facet normal 0.291919 -0.947787 0.128383 + outer loop + vertex 556.057 97.3478 112.642 + vertex 567.784 102.134 121.313 + vertex 555.883 98.4879 121.455 + endloop + endfacet + facet normal 0.265657 -0.955418 0.128852 + outer loop + vertex 556.057 97.3478 112.642 + vertex 555.883 98.4879 121.455 + vertex 544.161 94.0737 112.89 + endloop + endfacet + facet normal 0.292323 -0.949747 0.11193 + outer loop + vertex 567.784 102.134 121.313 + vertex 567.736 103.164 130.178 + vertex 555.883 98.4879 121.455 + endloop + endfacet + facet normal 0.293901 -0.949524 0.109667 + outer loop + vertex 555.883 98.4879 121.455 + vertex 567.736 103.164 130.178 + vertex 555.723 99.4605 130.303 + endloop + endfacet + facet normal 0.267706 -0.957197 0.110038 + outer loop + vertex 555.883 98.4879 121.455 + vertex 555.723 99.4605 130.303 + vertex 543.946 95.1758 121.683 + endloop + endfacet + facet normal 0.294269 -0.951332 0.0915059 + outer loop + vertex 567.736 103.164 130.178 + vertex 567.658 104.008 139.199 + vertex 555.723 99.4605 130.303 + endloop + endfacet + facet normal 0.295443 -0.951128 0.0898267 + outer loop + vertex 555.723 99.4605 130.303 + vertex 567.658 104.008 139.199 + vertex 555.59 100.262 139.228 + endloop + endfacet + facet normal 0.269547 -0.95876 0.0901265 + outer loop + vertex 555.723 99.4605 130.303 + vertex 555.59 100.262 139.228 + vertex 543.746 96.1104 130.484 + endloop + endfacet + facet normal 0.295862 -0.952629 0.0704449 + outer loop + vertex 567.658 104.008 139.199 + vertex 567.538 104.64 148.251 + vertex 555.59 100.262 139.228 + endloop + endfacet + facet normal 0.296243 -0.952551 0.0699037 + outer loop + vertex 555.59 100.262 139.228 + vertex 567.538 104.64 148.251 + vertex 555.472 100.885 148.218 + endloop + endfacet + facet normal 0.270846 -0.960068 0.0700905 + outer loop + vertex 555.59 100.262 139.228 + vertex 555.472 100.885 148.218 + vertex 543.563 96.8786 139.356 + endloop + endfacet + facet normal 0.296647 -0.953675 0.0500485 + outer loop + vertex 567.538 104.64 148.251 + vertex 567.391 105.065 157.209 + vertex 555.472 100.885 148.218 + endloop + endfacet + facet normal 0.296558 -0.953696 0.0501758 + outer loop + vertex 555.472 100.885 148.218 + vertex 567.391 105.065 157.209 + vertex 555.358 101.323 157.219 + endloop + endfacet + facet normal 0.271592 -0.961101 0.050221 + outer loop + vertex 555.472 100.885 148.218 + vertex 555.358 101.323 157.219 + vertex 543.403 97.4793 148.31 + endloop + endfacet + facet normal 0.296784 -0.954472 0.0300529 + outer loop + vertex 567.391 105.065 157.209 + vertex 567.297 105.314 166.06 + vertex 555.358 101.323 157.219 + endloop + endfacet + facet normal 0.296911 -0.954438 0.0298663 + outer loop + vertex 555.358 101.323 157.219 + vertex 567.297 105.314 166.06 + vertex 555.274 101.578 166.199 + endloop + endfacet + facet normal 0.271981 -0.96184 0.0298442 + outer loop + vertex 555.358 101.323 157.219 + vertex 555.274 101.578 166.199 + vertex 543.243 97.8998 157.295 + endloop + endfacet + facet normal 0.296809 -0.954896 0.00878211 + outer loop + vertex 567.297 105.314 166.06 + vertex 567.376 105.421 174.989 + vertex 555.274 101.578 166.199 + endloop + endfacet + facet normal 0.296888 -0.954873 0.00866359 + outer loop + vertex 555.274 101.578 166.199 + vertex 567.376 105.421 174.989 + vertex 555.221 101.643 175.163 + endloop + endfacet + facet normal 0.272016 -0.962255 0.00856925 + outer loop + vertex 555.274 101.578 166.199 + vertex 555.221 101.643 175.163 + vertex 543.095 98.1359 166.253 + endloop + endfacet + facet normal 0.296572 -0.954905 -0.0141907 + outer loop + vertex 567.376 105.421 174.989 + vertex 567.442 105.306 184.052 + vertex 555.221 101.643 175.163 + endloop + endfacet + facet normal 0.29619 -0.955032 -0.0136129 + outer loop + vertex 555.221 101.643 175.163 + vertex 567.442 105.306 184.052 + vertex 555.167 101.499 184.102 + endloop + endfacet + facet normal 0.271795 -0.962255 -0.013878 + outer loop + vertex 555.221 101.643 175.163 + vertex 555.167 101.499 184.102 + vertex 542.966 98.1815 175.161 + endloop + endfacet + facet normal 0.295916 -0.954465 -0.037811 + outer loop + vertex 567.442 105.306 184.052 + vertex 567.321 104.913 193.03 + vertex 555.167 101.499 184.102 + endloop + endfacet + facet normal 0.294508 -0.954982 -0.0356966 + outer loop + vertex 555.167 101.499 184.102 + vertex 567.321 104.913 193.03 + vertex 555.114 101.15 192.99 + endloop + endfacet + facet normal 0.270736 -0.961976 -0.0361129 + outer loop + vertex 555.167 101.499 184.102 + vertex 555.114 101.15 192.99 + vertex 542.868 98.04 184.028 + endloop + endfacet + facet normal 0.294234 -0.953837 -0.0601845 + outer loop + vertex 567.321 104.913 193.03 + vertex 567.248 104.334 201.847 + vertex 555.114 101.15 192.99 + endloop + endfacet + facet normal 0.292744 -0.954434 -0.0579286 + outer loop + vertex 555.114 101.15 192.99 + vertex 567.248 104.334 201.847 + vertex 555.104 100.609 201.857 + endloop + endfacet + facet normal 0.269345 -0.961273 -0.0583704 + outer loop + vertex 555.114 101.15 192.99 + vertex 555.104 100.609 201.857 + vertex 542.777 97.7006 192.873 + endloop + endfacet + facet normal 0.292222 -0.952802 -0.0823032 + outer loop + vertex 567.248 104.334 201.847 + vertex 567.397 103.614 210.719 + vertex 555.104 100.609 201.857 + endloop + endfacet + facet normal 0.291011 -0.953332 -0.0804435 + outer loop + vertex 555.104 100.609 201.857 + vertex 567.397 103.614 210.719 + vertex 555.151 99.8725 210.756 + endloop + endfacet + facet normal 0.267659 -0.960113 -0.0808813 + outer loop + vertex 555.104 100.609 201.857 + vertex 555.151 99.8725 210.756 + vertex 542.718 97.168 201.716 + endloop + endfacet + facet normal 0.290285 -0.951196 -0.104697 + outer loop + vertex 567.397 103.614 210.719 + vertex 567.623 102.687 219.761 + vertex 555.151 99.8725 210.756 + endloop + endfacet + facet normal 0.288829 -0.951882 -0.102466 + outer loop + vertex 555.151 99.8725 210.756 + vertex 567.623 102.687 219.761 + vertex 555.229 98.9342 219.691 + endloop + endfacet + facet normal 0.265964 -0.958469 -0.10296 + outer loop + vertex 555.151 99.8725 210.756 + vertex 555.229 98.9342 219.691 + vertex 542.676 96.4303 210.574 + endloop + endfacet + facet normal 0.28818 -0.949306 -0.125582 + outer loop + vertex 567.623 102.687 219.761 + vertex 567.779 101.538 228.81 + vertex 555.229 98.9342 219.691 + endloop + endfacet + facet normal 0.285694 -0.950548 -0.121807 + outer loop + vertex 555.229 98.9342 219.691 + vertex 567.779 101.538 228.81 + vertex 555.335 97.8216 228.623 + endloop + endfacet + facet normal 0.307786 -0.94319 -0.125142 + outer loop + vertex 567.623 102.687 219.761 + vertex 579.328 105.323 228.684 + vertex 567.779 101.538 228.81 + endloop + endfacet + facet normal 0.306707 -0.940586 -0.1457 + outer loop + vertex 579.328 105.323 228.684 + vertex 579.245 103.886 237.787 + vertex 567.779 101.538 228.81 + endloop + endfacet + facet normal 0.303204 -0.942477 -0.140731 + outer loop + vertex 567.779 101.538 228.81 + vertex 579.245 103.886 237.787 + vertex 567.904 100.249 237.707 + endloop + endfacet + facet normal 0.32058 -0.936079 -0.144862 + outer loop + vertex 579.328 105.323 228.684 + vertex 588.703 107.161 237.555 + vertex 579.245 103.886 237.787 + endloop + endfacet + facet normal 0.309179 -0.942461 -0.127185 + outer loop + vertex 578.995 106.493 219.206 + vertex 579.328 105.323 228.684 + vertex 567.623 102.687 219.761 + endloop + endfacet + facet normal 0.326413 -0.936647 -0.127074 + outer loop + vertex 578.995 106.493 219.206 + vertex 589.483 109.003 227.647 + vertex 579.328 105.323 228.684 + endloop + endfacet + facet normal 0.311012 -0.944639 -0.104543 + outer loop + vertex 567.397 103.614 210.719 + vertex 578.995 106.493 219.206 + vertex 567.623 102.687 219.761 + endloop + endfacet + facet normal 0.311214 -0.944538 -0.104853 + outer loop + vertex 578.286 107.273 210.072 + vertex 578.995 106.493 219.206 + vertex 567.397 103.614 210.719 + endloop + endfacet + facet normal 0.329552 -0.938198 -0.105734 + outer loop + vertex 578.286 107.273 210.072 + vertex 587.635 109.796 216.828 + vertex 578.995 106.493 219.206 + endloop + endfacet + facet normal 0.31311 -0.94616 -0.0821158 + outer loop + vertex 567.248 104.334 201.847 + vertex 578.286 107.273 210.072 + vertex 567.397 103.614 210.719 + endloop + endfacet + facet normal 0.313661 -0.945905 -0.082946 + outer loop + vertex 578.24 108 201.612 + vertex 578.286 107.273 210.072 + vertex 567.248 104.334 201.847 + endloop + endfacet + facet normal 0.330164 -0.940306 -0.0825561 + outer loop + vertex 578.24 108 201.612 + vertex 585.903 110.073 208.65 + vertex 578.286 107.273 210.072 + endloop + endfacet + facet normal 0.314638 -0.947339 -0.059588 + outer loop + vertex 567.321 104.913 193.03 + vertex 578.24 108 201.612 + vertex 567.248 104.334 201.847 + endloop + endfacet + facet normal 0.316101 -0.946719 -0.0616717 + outer loop + vertex 578.782 108.749 192.885 + vertex 578.24 108 201.612 + vertex 567.321 104.913 193.03 + endloop + endfacet + facet normal 0.330759 -0.941784 -0.0603371 + outer loop + vertex 578.782 108.749 192.885 + vertex 587.533 111.255 201.742 + vertex 578.24 108 201.612 + endloop + endfacet + facet normal 0.316762 -0.947774 -0.0372374 + outer loop + vertex 567.442 105.306 184.052 + vertex 578.782 108.749 192.885 + vertex 567.321 104.913 193.03 + endloop + endfacet + facet normal 0.3172 -0.947602 -0.037866 + outer loop + vertex 578.776 109.124 183.466 + vertex 578.782 108.749 192.885 + vertex 567.442 105.306 184.052 + endloop + endfacet + facet normal 0.33534 -0.941345 -0.0376292 + outer loop + vertex 578.776 109.124 183.466 + vertex 588.994 112.416 192.16 + vertex 578.782 108.749 192.885 + endloop + endfacet + facet normal 0.318493 -0.947818 -0.0142612 + outer loop + vertex 567.376 105.421 174.989 + vertex 578.776 109.124 183.466 + vertex 567.442 105.306 184.052 + endloop + endfacet + facet normal 0.317518 -0.948166 -0.0127981 + outer loop + vertex 578.202 109.055 174.297 + vertex 578.776 109.124 183.466 + vertex 567.376 105.421 174.989 + endloop + endfacet + facet normal 0.336437 -0.941601 -0.01403 + outer loop + vertex 578.202 109.055 174.297 + vertex 587.44 112.252 181.24 + vertex 578.776 109.124 183.466 + endloop + endfacet + facet normal 0.318757 -0.947798 0.00850237 + outer loop + vertex 567.297 105.314 166.06 + vertex 578.202 109.055 174.297 + vertex 567.376 105.421 174.989 + endloop + endfacet + facet normal 0.317929 -0.948065 0.00972033 + outer loop + vertex 578.12 108.941 165.861 + vertex 578.202 109.055 174.297 + vertex 567.297 105.314 166.06 + endloop + endfacet + facet normal 0.334767 -0.942253 0.00947656 + outer loop + vertex 578.12 108.941 165.861 + vertex 585.696 111.704 172.981 + vertex 578.202 109.055 174.297 + endloop + endfacet + facet normal 0.318137 -0.947567 0.0300865 + outer loop + vertex 567.391 105.065 157.209 + vertex 578.12 108.941 165.861 + vertex 567.297 105.314 166.06 + endloop + endfacet + facet normal 0.318333 -0.94751 0.0298179 + outer loop + vertex 578.484 108.796 157.345 + vertex 578.12 108.941 165.861 + vertex 567.391 105.065 157.209 + endloop + endfacet + facet normal 0.333301 -0.942331 0.0303706 + outer loop + vertex 578.484 108.796 157.345 + vertex 587.052 112.112 166.224 + vertex 578.12 108.941 165.861 + endloop + endfacet + facet normal 0.317851 -0.946818 0.0500704 + outer loop + vertex 567.538 104.64 148.251 + vertex 578.484 108.796 157.345 + vertex 567.391 105.065 157.209 + endloop + endfacet + facet normal 0.317999 -0.946778 0.049875 + outer loop + vertex 578.736 108.406 148.338 + vertex 578.484 108.796 157.345 + vertex 567.538 104.64 148.251 + endloop + endfacet + facet normal 0.334411 -0.941095 0.0500871 + outer loop + vertex 578.736 108.406 148.338 + vertex 587.616 112.046 157.447 + vertex 578.484 108.796 157.345 + endloop + endfacet + facet normal 0.317466 -0.945664 0.0702462 + outer loop + vertex 567.658 104.008 139.199 + vertex 578.736 108.406 148.338 + vertex 567.538 104.64 148.251 + endloop + endfacet + facet normal 0.316941 -0.945788 0.0709414 + outer loop + vertex 578.954 107.784 139.073 + vertex 578.736 108.406 148.338 + vertex 567.658 104.008 139.199 + endloop + endfacet + facet normal 0.33419 -0.939831 0.0709487 + outer loop + vertex 578.954 107.784 139.073 + vertex 588.031 111.704 148.242 + vertex 578.736 108.406 148.338 + endloop + endfacet + facet normal 0.316626 -0.944172 0.0910295 + outer loop + vertex 567.736 103.164 130.178 + vertex 578.954 107.784 139.073 + vertex 567.658 104.008 139.199 + endloop + endfacet + facet normal 0.31472 -0.944555 0.0936326 + outer loop + vertex 578.7 106.784 129.839 + vertex 578.954 107.784 139.073 + vertex 567.736 103.164 130.178 + endloop + endfacet + facet normal 0.333679 -0.938146 0.0924164 + outer loop + vertex 578.7 106.784 129.839 + vertex 588.788 111.198 138.223 + vertex 578.954 107.784 139.073 + endloop + endfacet + facet normal 0.314642 -0.942671 0.111228 + outer loop + vertex 567.784 102.134 121.313 + vertex 578.7 106.784 129.839 + vertex 567.736 103.164 130.178 + endloop + endfacet + facet normal 0.312476 -0.943036 0.114201 + outer loop + vertex 578.601 105.702 121.179 + vertex 578.7 106.784 129.839 + vertex 567.784 102.134 121.313 + endloop + endfacet + facet normal 0.329697 -0.937265 0.113284 + outer loop + vertex 578.601 105.702 121.179 + vertex 586.351 109.326 128.602 + vertex 578.7 106.784 129.839 + endloop + endfacet + facet normal 0.312031 -0.941079 0.130413 + outer loop + vertex 567.969 100.984 112.569 + vertex 578.601 105.702 121.179 + vertex 567.784 102.134 121.313 + endloop + endfacet + facet normal 0.310591 -0.941291 0.132307 + outer loop + vertex 579.045 104.65 112.647 + vertex 578.601 105.702 121.179 + vertex 567.969 100.984 112.569 + endloop + endfacet + facet normal 0.326472 -0.935879 0.132465 + outer loop + vertex 579.045 104.65 112.647 + vertex 587.554 108.872 121.508 + vertex 578.601 105.702 121.179 + endloop + endfacet + facet normal 0.309787 -0.939198 0.148118 + outer loop + vertex 568.245 99.6838 103.749 + vertex 579.045 104.65 112.647 + vertex 567.969 100.984 112.569 + endloop + endfacet + facet normal 0.308092 -0.93941 0.150293 + outer loop + vertex 579.531 103.365 103.618 + vertex 579.045 104.65 112.647 + vertex 568.245 99.6838 103.749 + endloop + endfacet + facet normal 0.307503 -0.937065 0.165379 + outer loop + vertex 568.494 98.1941 94.8442 + vertex 579.531 103.365 103.618 + vertex 568.245 99.6838 103.749 + endloop + endfacet + facet normal 0.304848 -0.937311 0.168864 + outer loop + vertex 579.641 101.751 94.4627 + vertex 579.531 103.365 103.618 + vertex 568.494 98.1941 94.8442 + endloop + endfacet + facet normal 0.304537 -0.934899 0.182264 + outer loop + vertex 568.793 96.5803 86.0663 + vertex 579.641 101.751 94.4627 + vertex 568.494 98.1941 94.8442 + endloop + endfacet + facet normal 0.283229 -0.94148 0.182747 + outer loop + vertex 568.793 96.5803 86.0663 + vertex 568.494 98.1941 94.8442 + vertex 556.731 92.9762 86.1922 + endloop + endfacet + facet normal 0.302038 -0.935056 0.185589 + outer loop + vertex 579.992 100.128 85.7125 + vertex 579.641 101.751 94.4627 + vertex 568.793 96.5803 86.0663 + endloop + endfacet + facet normal 0.30159 -0.932184 0.200191 + outer loop + vertex 569.142 94.8389 77.4321 + vertex 579.992 100.128 85.7125 + vertex 568.793 96.5803 86.0663 + endloop + endfacet + facet normal 0.280531 -0.93864 0.200642 + outer loop + vertex 569.142 94.8389 77.4321 + vertex 568.793 96.5803 86.0663 + vertex 557.016 91.2449 77.573 + endloop + endfacet + facet normal 0.298361 -0.93229 0.204489 + outer loop + vertex 580.503 98.3588 76.9023 + vertex 579.992 100.128 85.7125 + vertex 569.142 94.8389 77.4321 + endloop + endfacet + facet normal 0.298002 -0.928677 0.2208 + outer loop + vertex 569.373 92.8642 68.8141 + vertex 580.503 98.3588 76.9023 + vertex 569.142 94.8389 77.4321 + endloop + endfacet + facet normal 0.277181 -0.934898 0.221666 + outer loop + vertex 569.373 92.8642 68.8141 + vertex 569.142 94.8389 77.4321 + vertex 557.196 89.3124 69.0611 + endloop + endfacet + facet normal 0.293731 -0.92863 0.226646 + outer loop + vertex 580.59 96.2091 67.9831 + vertex 580.503 98.3588 76.9023 + vertex 569.373 92.8642 68.8141 + endloop + endfacet + facet normal 0.293704 -0.92418 0.244192 + outer loop + vertex 569.715 90.7181 60.2812 + vertex 580.59 96.2091 67.9831 + vertex 569.373 92.8642 68.8141 + endloop + endfacet + facet normal 0.273794 -0.930091 0.244882 + outer loop + vertex 569.715 90.7181 60.2812 + vertex 569.373 92.8642 68.8141 + vertex 557.264 87.166 60.7101 + endloop + endfacet + facet normal 0.272916 -0.924413 0.266416 + outer loop + vertex 557.598 84.9995 52.8511 + vertex 569.715 90.7181 60.2812 + vertex 557.264 87.166 60.7101 + endloop + endfacet + facet normal 0.27166 -0.924231 0.268324 + outer loop + vertex 570.839 88.669 52.0849 + vertex 569.715 90.7181 60.2812 + vertex 557.598 84.9995 52.8511 + endloop + endfacet + facet normal 0.271019 -0.916525 0.294161 + outer loop + vertex 558.878 83.2109 46.0993 + vertex 570.839 88.669 52.0849 + vertex 557.598 84.9995 52.8511 + endloop + endfacet + facet normal 0.249267 -0.923408 0.291862 + outer loop + vertex 558.878 83.2109 46.0993 + vertex 557.598 84.9995 52.8511 + vertex 545.571 79.8127 46.7126 + endloop + endfacet + facet normal 0.247989 -0.912227 0.326103 + outer loop + vertex 548.189 78.7672 41.7969 + vertex 558.878 83.2109 46.0993 + vertex 545.571 79.8127 46.7126 + endloop + endfacet + facet normal 0.226428 -0.921165 0.31652 + outer loop + vertex 548.189 78.7672 41.7969 + vertex 545.571 79.8127 46.7126 + vertex 533.777 75.3237 42.085 + endloop + endfacet + facet normal 0.224288 -0.920144 0.320982 + outer loop + vertex 533.777 75.3237 42.085 + vertex 545.571 79.8127 46.7126 + vertex 533.464 77.0691 47.3072 + endloop + endfacet + facet normal 0.201315 -0.925319 0.321335 + outer loop + vertex 533.777 75.3237 42.085 + vertex 533.464 77.0691 47.3072 + vertex 523.238 73.4501 43.293 + endloop + endfacet + facet normal 0.251706 -0.913871 0.318565 + outer loop + vertex 561.55 82.2262 41.1631 + vertex 558.878 83.2109 46.0993 + vertex 548.189 78.7672 41.7969 + endloop + endfacet + facet normal 0.270647 -0.905394 0.327128 + outer loop + vertex 561.55 82.2262 41.1631 + vertex 572.879 86.9314 44.8125 + vertex 558.878 83.2109 46.0993 + endloop + endfacet + facet normal 0.248668 -0.923243 0.292894 + outer loop + vertex 545.571 79.8127 46.7126 + vertex 557.598 84.9995 52.8511 + vertex 545.026 81.7601 53.3134 + endloop + endfacet + facet normal 0.270612 -0.916416 0.294876 + outer loop + vertex 572.879 86.9314 44.8125 + vertex 570.839 88.669 52.0849 + vertex 558.878 83.2109 46.0993 + endloop + endfacet + facet normal 0.290229 -0.909163 0.298647 + outer loop + vertex 572.879 86.9314 44.8125 + vertex 584.613 92.5437 50.4945 + vertex 570.839 88.669 52.0849 + endloop + endfacet + facet normal 0.289512 -0.918137 0.27057 + outer loop + vertex 584.613 92.5437 50.4945 + vertex 581.703 94.2527 59.4083 + vertex 570.839 88.669 52.0849 + endloop + endfacet + facet normal 0.30402 -0.912352 0.274198 + outer loop + vertex 584.613 92.5437 50.4945 + vertex 592.471 97.6312 58.7101 + vertex 581.703 94.2527 59.4083 + endloop + endfacet + facet normal 0.290352 -0.918219 0.269386 + outer loop + vertex 570.839 88.669 52.0849 + vertex 581.703 94.2527 59.4083 + vertex 569.715 90.7181 60.2812 + endloop + endfacet + facet normal 0.290545 -0.92402 0.248538 + outer loop + vertex 581.703 94.2527 59.4083 + vertex 580.59 96.2091 67.9831 + vertex 569.715 90.7181 60.2812 + endloop + endfacet + facet normal 0.305837 -0.918853 0.249344 + outer loop + vertex 581.703 94.2527 59.4083 + vertex 588.948 98.54 66.3207 + vertex 580.59 96.2091 67.9831 + endloop + endfacet + facet normal 0.310255 -0.923504 0.22557 + outer loop + vertex 580.59 96.2091 67.9831 + vertex 589.615 100.875 74.6721 + vertex 580.503 98.3588 76.9023 + endloop + endfacet + facet normal 0.314719 -0.926924 0.204361 + outer loop + vertex 580.503 98.3588 76.9023 + vertex 590.201 103.502 85.2953 + vertex 579.992 100.128 85.7125 + endloop + endfacet + facet normal 0.31793 -0.929839 0.185258 + outer loop + vertex 579.992 100.128 85.7125 + vertex 587.667 104.217 93.069 + vertex 579.641 101.751 94.4627 + endloop + endfacet + facet normal 0.322818 -0.931424 0.168042 + outer loop + vertex 579.641 101.751 94.4627 + vertex 589.511 106.663 102.731 + vertex 579.531 103.365 103.618 + endloop + endfacet + facet normal 0.324639 -0.933806 0.150386 + outer loop + vertex 579.531 103.365 103.618 + vertex 588.329 107.872 112.612 + vertex 579.045 104.65 112.647 + endloop + endfacet + facet normal 0.285613 -0.943875 0.165906 + outer loop + vertex 568.494 98.1941 94.8442 + vertex 568.245 99.6838 103.749 + vertex 556.467 94.5749 94.9579 + endloop + endfacet + facet normal 0.285009 -0.941417 0.180288 + outer loop + vertex 556.731 92.9762 86.1922 + vertex 568.494 98.1941 94.8442 + vertex 556.467 94.5749 94.9579 + endloop + endfacet + facet normal 0.282535 -0.93863 0.197858 + outer loop + vertex 557.016 91.2449 77.573 + vertex 568.793 96.5803 86.0663 + vertex 556.731 92.9762 86.1922 + endloop + endfacet + facet normal 0.27965 -0.934979 0.218197 + outer loop + vertex 557.196 89.3124 69.0611 + vertex 569.142 94.8389 77.4321 + vertex 557.016 91.2449 77.573 + endloop + endfacet + facet normal 0.276236 -0.930287 0.241371 + outer loop + vertex 557.264 87.166 60.7101 + vertex 569.373 92.8642 68.8141 + vertex 557.196 89.3124 69.0611 + endloop + endfacet + facet normal 0.249656 -0.930747 0.267175 + outer loop + vertex 557.598 84.9995 52.8511 + vertex 557.264 87.166 60.7101 + vertex 545.026 81.7601 53.3134 + endloop + endfacet + facet normal 0.224987 -0.929346 0.292741 + outer loop + vertex 545.571 79.8127 46.7126 + vertex 545.026 81.7601 53.3134 + vertex 533.464 77.0691 47.3072 + endloop + endfacet + facet normal 0.224068 -0.937301 0.266946 + outer loop + vertex 533.154 79.0874 53.8545 + vertex 545.026 83.9748 61.0505 + vertex 533.309 81.3656 61.7238 + endloop + endfacet + facet normal 0.227903 -0.944445 0.23682 + outer loop + vertex 533.309 81.3656 61.7238 + vertex 545.1 86.1268 69.3642 + vertex 533.795 83.5819 70.0943 + endloop + endfacet + facet normal 0.230826 -0.949398 0.212986 + outer loop + vertex 533.795 83.5819 70.0943 + vertex 545.005 88.0462 77.8453 + vertex 533.769 85.4468 78.4355 + endloop + endfacet + facet normal 0.233271 -0.953034 0.193162 + outer loop + vertex 533.769 85.4468 78.4355 + vertex 544.766 89.7626 86.4487 + vertex 533.564 87.1241 86.959 + endloop + endfacet + facet normal 0.233275 -0.955847 0.178717 + outer loop + vertex 544.766 89.7626 86.4487 + vertex 544.541 91.346 95.2105 + vertex 533.564 87.1241 86.959 + endloop + endfacet + facet normal 0.26287 -0.951238 0.16139 + outer loop + vertex 544.541 91.346 95.2105 + vertex 556.25 96.0401 103.807 + vertex 544.36 92.7971 104.059 + endloop + endfacet + facet normal 0.2654 -0.953357 0.143784 + outer loop + vertex 544.36 92.7971 104.059 + vertex 556.057 97.3478 112.642 + vertex 544.161 94.0737 112.89 + endloop + endfacet + facet normal 0.267477 -0.955254 0.126277 + outer loop + vertex 544.161 94.0737 112.89 + vertex 555.883 98.4879 121.455 + vertex 543.946 95.1758 121.683 + endloop + endfacet + facet normal 0.269322 -0.957005 0.107735 + outer loop + vertex 543.946 95.1758 121.683 + vertex 555.723 99.4605 130.303 + vertex 543.746 96.1104 130.484 + endloop + endfacet + facet normal 0.270629 -0.958599 0.0885855 + outer loop + vertex 543.746 96.1104 130.484 + vertex 555.59 100.262 139.228 + vertex 543.563 96.8786 139.356 + endloop + endfacet + facet normal 0.271417 -0.959965 0.0692768 + outer loop + vertex 543.563 96.8786 139.356 + vertex 555.472 100.885 148.218 + vertex 543.403 97.4793 148.31 + endloop + endfacet + facet normal 0.271882 -0.961041 0.0498061 + outer loop + vertex 543.403 97.4793 148.31 + vertex 555.358 101.323 157.219 + vertex 543.243 97.8998 157.295 + endloop + endfacet + facet normal 0.271992 -0.961837 0.0298289 + outer loop + vertex 543.243 97.8998 157.295 + vertex 555.274 101.578 166.199 + vertex 543.095 98.1359 166.253 + endloop + endfacet + facet normal 0.271808 -0.962311 0.00887381 + outer loop + vertex 543.095 98.1359 166.253 + vertex 555.221 101.643 175.163 + vertex 542.966 98.1815 175.161 + endloop + endfacet + facet normal 0.270759 -0.962568 -0.0123484 + outer loop + vertex 542.966 98.1815 175.161 + vertex 555.167 101.499 184.102 + vertex 542.868 98.04 184.028 + endloop + endfacet + facet normal 0.269433 -0.962412 -0.0341819 + outer loop + vertex 542.868 98.04 184.028 + vertex 555.114 101.15 192.99 + vertex 542.777 97.7006 192.873 + endloop + endfacet + facet normal 0.267851 -0.961823 -0.056143 + outer loop + vertex 542.777 97.7006 192.873 + vertex 555.104 100.609 201.857 + vertex 542.718 97.168 201.716 + endloop + endfacet + facet normal 0.266223 -0.960691 -0.0787337 + outer loop + vertex 542.718 97.168 201.716 + vertex 555.151 99.8725 210.756 + vertex 542.676 96.4303 210.574 + endloop + endfacet + facet normal 0.264189 -0.959241 -0.100304 + outer loop + vertex 542.676 96.4303 210.574 + vertex 555.229 98.9342 219.691 + vertex 542.669 95.4993 219.459 + endloop + endfacet + facet normal 0.239096 -0.963944 -0.116815 + outer loop + vertex 530.608 92.5149 219.186 + vertex 542.712 94.4042 228.37 + vertex 530.512 91.4162 228.055 + endloop + endfacet + facet normal 0.263916 -0.956758 -0.12232 + outer loop + vertex 555.229 98.9342 219.691 + vertex 555.335 97.8216 228.623 + vertex 542.669 95.4993 219.459 + endloop + endfacet + facet normal 0.259216 -0.956496 -0.133873 + outer loop + vertex 542.712 94.4042 228.37 + vertex 555.489 96.5832 237.541 + vertex 542.747 93.1662 237.282 + endloop + endfacet + facet normal 0.285223 -0.947992 -0.141276 + outer loop + vertex 567.779 101.538 228.81 + vertex 567.904 100.249 237.707 + vertex 555.335 97.8216 228.623 + endloop + endfacet + facet normal 0.279027 -0.948898 -0.147435 + outer loop + vertex 555.489 96.5832 237.541 + vertex 568.147 98.9098 246.523 + vertex 555.653 95.2476 246.448 + endloop + endfacet + facet normal 0.302571 -0.940154 -0.156717 + outer loop + vertex 579.245 103.886 237.787 + vertex 579.226 102.451 246.363 + vertex 567.904 100.249 237.707 + endloop + endfacet + facet normal 0.314952 -0.936195 -0.156027 + outer loop + vertex 579.245 103.886 237.787 + vertex 588.383 105.514 246.463 + vertex 579.226 102.451 246.363 + endloop + endfacet + facet normal 0.309755 -0.937035 -0.161301 + outer loop + vertex 579.226 102.451 246.363 + vertex 587.457 103.929 253.578 + vertex 579.676 101.122 254.945 + endloop + endfacet + facet normal 0.30619 -0.938199 -0.161338 + outer loop + vertex 579.676 101.122 254.945 + vertex 590.178 103.184 262.883 + vertex 580.068 99.7454 263.693 + endloop + endfacet + facet normal 0.278681 -0.947534 -0.156574 + outer loop + vertex 568.147 98.9098 246.523 + vertex 568.413 97.5293 255.351 + vertex 555.653 95.2476 246.448 + endloop + endfacet + facet normal 0.258965 -0.954496 -0.147904 + outer loop + vertex 555.489 96.5832 237.541 + vertex 555.653 95.2476 246.448 + vertex 542.747 93.1662 237.282 + endloop + endfacet + facet normal 0.238992 -0.96166 -0.134511 + outer loop + vertex 542.712 94.4042 228.37 + vertex 542.747 93.1662 237.282 + vertex 530.512 91.4162 228.055 + endloop + endfacet + facet normal 0.222395 -0.967853 -0.117481 + outer loop + vertex 530.608 92.5149 219.186 + vertex 530.512 91.4162 228.055 + vertex 519.763 90.0494 218.968 + endloop + endfacet + facet normal 0.222493 -0.970134 -0.096628 + outer loop + vertex 519.994 90.9789 210.167 + vertex 530.608 92.5149 219.186 + vertex 519.763 90.0494 218.968 + endloop + endfacet + facet normal 0.224371 -0.971556 -0.0757369 + outer loop + vertex 520.228 91.716 201.405 + vertex 530.697 93.4373 210.34 + vertex 519.994 90.9789 210.167 + endloop + endfacet + facet normal 0.226076 -0.972619 -0.0538725 + outer loop + vertex 520.483 92.259 192.672 + vertex 530.827 94.1727 201.531 + vertex 520.228 91.716 201.405 + endloop + endfacet + facet normal 0.227486 -0.973245 -0.0323058 + outer loop + vertex 520.741 92.6093 183.937 + vertex 530.984 94.7111 192.742 + vertex 520.483 92.259 192.672 + endloop + endfacet + facet normal 0.228415 -0.973497 -0.0114028 + outer loop + vertex 521.035 92.7807 175.185 + vertex 531.156 95.0529 183.953 + vertex 520.741 92.6093 183.937 + endloop + endfacet + facet normal 0.229081 -0.973368 0.00873053 + outer loop + vertex 521.304 92.7652 166.388 + vertex 531.327 95.2024 175.142 + vertex 521.035 92.7807 175.185 + endloop + endfacet + facet normal 0.229184 -0.972967 0.0284739 + outer loop + vertex 521.638 92.5852 157.554 + vertex 531.523 95.1694 166.293 + vertex 521.304 92.7652 166.388 + endloop + endfacet + facet normal 0.228992 -0.97227 0.0474788 + outer loop + vertex 521.945 92.2247 148.69 + vertex 531.771 94.9641 157.397 + vertex 521.638 92.5852 157.554 + endloop + endfacet + facet normal 0.228183 -0.971372 0.0660896 + outer loop + vertex 522.273 91.6997 139.842 + vertex 532.005 94.5728 148.467 + vertex 521.945 92.2247 148.69 + endloop + endfacet + facet normal 0.226935 -0.970247 0.0843843 + outer loop + vertex 522.606 91.0131 131.052 + vertex 532.245 94.0078 139.561 + vertex 522.273 91.6997 139.842 + endloop + endfacet + facet normal 0.225094 -0.968933 0.102477 + outer loop + vertex 522.92 90.1637 122.331 + vertex 532.473 93.2714 130.73 + vertex 522.606 91.0131 131.052 + endloop + endfacet + facet normal 0.223011 -0.967398 0.120032 + outer loop + vertex 523.221 89.1567 113.656 + vertex 532.745 92.3852 121.98 + vertex 522.92 90.1637 122.331 + endloop + endfacet + facet normal 0.220137 -0.965752 0.137341 + outer loop + vertex 523.453 87.9762 104.982 + vertex 532.973 91.3214 113.246 + vertex 523.221 89.1567 113.656 + endloop + endfacet + facet normal 0.21714 -0.963822 0.15459 + outer loop + vertex 523.671 86.6344 96.3107 + vertex 533.209 90.0934 104.479 + vertex 523.453 87.9762 104.982 + endloop + endfacet + facet normal 0.213872 -0.961573 0.172151 + outer loop + vertex 523.806 85.1181 87.6734 + vertex 533.379 88.6814 95.6833 + vertex 523.671 86.6344 96.3107 + endloop + endfacet + facet normal 0.188692 -0.963421 0.190301 + outer loop + vertex 523.94 83.4785 79.2396 + vertex 523.806 85.1181 87.6734 + vertex 516.097 82.1214 80.1464 + endloop + endfacet + facet normal 0.189787 -0.960306 0.204436 + outer loop + vertex 516.133 80.4238 72.1382 + vertex 523.94 83.4785 79.2396 + vertex 516.097 82.1214 80.1464 + endloop + endfacet + facet normal 0.186423 -0.956353 0.225025 + outer loop + vertex 516.03 78.7214 64.9884 + vertex 523.983 81.7277 71.1765 + vertex 516.133 80.4238 72.1382 + endloop + endfacet + facet normal 0.181135 -0.951607 0.248263 + outer loop + vertex 516.03 78.7214 64.9884 + vertex 515.023 76.8079 58.3887 + vertex 523.416 79.6762 63.2596 + endloop + endfacet + facet normal 0.16748 -0.94727 0.273186 + outer loop + vertex 512.736 74.9838 53.4655 + vertex 520.636 76.5929 54.2018 + vertex 515.023 76.8079 58.3887 + endloop + endfacet + facet normal 0.162591 -0.938143 0.3057 + outer loop + vertex 512.736 74.9838 53.4655 + vertex 511.85 73.557 49.5582 + vertex 520.636 76.5929 54.2018 + endloop + endfacet + facet normal 0.15154 -0.933899 0.323833 + outer loop + vertex 511.85 73.557 49.5582 + vertex 514.659 73.1866 47.1754 + vertex 520.636 76.5929 54.2018 + endloop + endfacet + facet normal 0.155191 -0.931905 0.327826 + outer loop + vertex 509.437 71.8881 45.9564 + vertex 514.659 73.1866 47.1754 + vertex 511.85 73.557 49.5582 + endloop + endfacet + facet normal 0.178968 -0.936443 0.301736 + outer loop + vertex 523.033 74.9946 47.8199 + vertex 520.636 76.5929 54.2018 + vertex 514.659 73.1866 47.1754 + endloop + endfacet + facet normal 0.199814 -0.924551 0.324468 + outer loop + vertex 523.033 74.9946 47.8199 + vertex 523.238 73.4501 43.293 + vertex 533.464 77.0691 47.3072 + endloop + endfacet + facet normal 0.202258 -0.918189 0.340619 + outer loop + vertex 522.456 72.3517 40.7959 + vertex 533.777 75.3237 42.085 + vertex 523.238 73.4501 43.293 + endloop + endfacet + facet normal 0.172114 -0.95546 0.239734 + outer loop + vertex 517.287 71.0875 40.1429 + vertex 511.702 70.152 40.4241 + vertex 513.922 70.392 39.7872 + endloop + endfacet + facet normal 0.164466 -0.922554 0.349063 + outer loop + vertex 515.731 71.1975 41.253 + vertex 515.399 72.0532 43.6707 + vertex 510.05 70.2909 41.5334 + endloop + endfacet + facet normal 0.156299 -0.971429 0.178597 + outer loop + vertex 511.702 70.152 40.4241 + vertex 507.534 69.4992 40.521 + vertex 513.922 70.392 39.7872 + endloop + endfacet + facet normal 0.147096 -0.922127 0.357834 + outer loop + vertex 510.05 70.2909 41.5334 + vertex 509.595 71.03 43.6249 + vertex 505.77 69.6915 41.7481 + endloop + endfacet + facet normal 0.115057 -0.907728 0.403476 + outer loop + vertex 500.43 69.3872 42.7923 + vertex 498.983 67.9652 40.0058 + vertex 501.237 69.376 42.537 + endloop + endfacet + facet normal 0.131788 -0.91989 0.36937 + outer loop + vertex 502.668 69.3276 41.9642 + vertex 505.817 70.5121 43.7907 + vertex 503.455 70.3755 44.2932 + endloop + endfacet + facet normal 0.13706 -0.928925 0.343966 + outer loop + vertex 503.455 70.3755 44.2932 + vertex 506.89 71.7946 46.7572 + vertex 504.585 71.7144 47.4589 + endloop + endfacet + facet normal 0.145358 -0.937659 0.3157 + outer loop + vertex 504.585 71.7144 47.4589 + vertex 508.219 73.3056 50.5116 + vertex 505.773 73.2182 51.3781 + endloop + endfacet + facet normal 0.151589 -0.945662 0.287652 + outer loop + vertex 505.773 73.2182 51.3781 + vertex 509.414 74.8664 54.8781 + vertex 506.804 74.7374 55.8297 + endloop + endfacet + facet normal 0.151124 -0.952436 0.264626 + outer loop + vertex 506.804 74.7374 55.8297 + vertex 510.406 76.463 59.983 + vertex 507.474 76.1554 60.5501 + endloop + endfacet + facet normal 0.144902 -0.958275 0.246398 + outer loop + vertex 507.474 76.1554 60.5501 + vertex 510.705 77.9767 65.7335 + vertex 507.62 77.3049 64.9353 + endloop + endfacet + facet normal 0.151968 -0.962905 0.222979 + outer loop + vertex 507.62 77.3049 64.9353 + vertex 510.705 77.9767 65.7335 + vertex 509.915 79.4266 72.5334 + endloop + endfacet + facet normal 0.142216 -0.968306 0.205326 + outer loop + vertex 507.616 80.169 77.6267 + vertex 507.205 78.9834 72.32 + vertex 509.915 79.4266 72.5334 + endloop + endfacet + facet normal 0.140769 -0.968645 0.204722 + outer loop + vertex 509.915 79.4266 72.5334 + vertex 510.881 81.5435 81.8855 + vertex 507.616 80.169 77.6267 + endloop + endfacet + facet normal 0.123092 -0.972425 0.198087 + outer loop + vertex 505.577 81.0811 83.8276 + vertex 502.106 80.2122 81.7189 + vertex 505.134 78.8043 72.9259 + endloop + endfacet + facet normal 0.175951 -0.967433 0.181977 + outer loop + vertex 510.881 81.5435 81.8855 + vertex 516.101 83.7625 88.6348 + vertex 510.537 83.0314 90.1272 + endloop + endfacet + facet normal 0.156386 -0.971107 0.180264 + outer loop + vertex 508.155 81.532 84.0205 + vertex 507.406 82.2671 88.6304 + vertex 505.577 81.0811 83.8276 + endloop + endfacet + facet normal 0.155763 -0.974028 0.164337 + outer loop + vertex 507.406 82.2671 88.6304 + vertex 507.818 83.3843 94.862 + vertex 505.395 82.6754 92.9565 + endloop + endfacet + facet normal 0.182337 -0.970065 0.160396 + outer loop + vertex 510.537 83.0314 90.1272 + vertex 515.995 85.2187 97.1515 + vertex 510.852 84.5251 98.8036 + endloop + endfacet + facet normal 0.168962 -0.973801 0.152195 + outer loop + vertex 507.818 83.3843 94.862 + vertex 508.068 84.3726 100.907 + vertex 505.557 84.0222 101.453 + endloop + endfacet + facet normal 0.186806 -0.971724 0.144414 + outer loop + vertex 510.852 84.5251 98.8036 + vertex 515.798 86.5024 105.71 + vertex 510.192 85.629 107.085 + endloop + endfacet + facet normal 0.16682 -0.975849 0.141028 + outer loop + vertex 508.068 84.3726 100.907 + vertex 507.117 84.8975 105.664 + vertex 505.557 84.0222 101.453 + endloop + endfacet + facet normal 0.168862 -0.977107 0.129409 + outer loop + vertex 507.117 84.8975 105.664 + vertex 507.257 85.764 112.024 + vertex 504.937 85.1291 110.258 + endloop + endfacet + facet normal 0.191874 -0.97317 0.126983 + outer loop + vertex 510.192 85.629 107.085 + vertex 515.484 87.6159 114.316 + vertex 510.215 86.7935 115.974 + endloop + endfacet + facet normal 0.182871 -0.97581 0.119803 + outer loop + vertex 507.257 85.764 112.024 + vertex 507.316 86.5384 118.242 + vertex 504.752 86.143 118.935 + endloop + endfacet + facet normal 0.194538 -0.974521 0.111637 + outer loop + vertex 510.215 86.7935 115.974 + vertex 515.126 88.5771 122.987 + vertex 509.36 87.5928 124.442 + endloop + endfacet + facet normal 0.180221 -0.977569 0.10899 + outer loop + vertex 507.316 86.5384 118.242 + vertex 506.229 86.8859 123.155 + vertex 504.752 86.143 118.935 + endloop + endfacet + facet normal 0.180608 -0.978871 0.0958774 + outer loop + vertex 506.229 86.8859 123.155 + vertex 506.277 87.5254 129.594 + vertex 503.925 86.9323 127.97 + endloop + endfacet + facet normal 0.198116 -0.975722 0.0933643 + outer loop + vertex 509.36 87.5928 124.442 + vertex 514.726 89.3767 131.699 + vertex 509.319 88.442 133.405 + endloop + endfacet + facet normal 0.193132 -0.977409 0.0858598 + outer loop + vertex 506.277 87.5254 129.594 + vertex 506.3 88.0736 135.784 + vertex 503.69 87.6457 136.784 + endloop + endfacet + facet normal 0.198984 -0.97693 0.0775471 + outer loop + vertex 509.319 88.442 133.405 + vertex 514.307 90.0156 140.428 + vertex 508.445 88.921 141.68 + endloop + endfacet + facet normal 0.189278 -0.979047 0.0751036 + outer loop + vertex 506.3 88.0736 135.784 + vertex 505.272 88.2503 140.677 + vertex 503.69 87.6457 136.784 + endloop + endfacet + facet normal 0.194827 -0.9788 0.063194 + outer loop + vertex 505.272 88.2503 140.677 + vertex 505.729 88.6643 145.683 + vertex 503.092 88.2023 146.654 + endloop + endfacet + facet normal 0.201632 -0.977706 0.0586052 + outer loop + vertex 508.445 88.921 141.68 + vertex 513.916 90.4989 149.18 + vertex 508.423 89.4437 150.478 + endloop + endfacet + facet normal 0.190949 -0.980222 0.0519949 + outer loop + vertex 505.729 88.6643 145.683 + vertex 504.994 88.8632 152.129 + vertex 503.092 88.2023 146.654 + endloop + endfacet + facet normal 0.202071 -0.978454 0.0423758 + outer loop + vertex 508.423 89.4437 150.478 + vertex 513.525 90.822 157.973 + vertex 507.539 89.6353 159.117 + endloop + endfacet + facet normal 0.189694 -0.980971 0.0413905 + outer loop + vertex 504.994 88.8632 152.129 + vertex 504.176 88.9716 158.447 + vertex 502.177 88.4846 156.069 + endloop + endfacet + facet normal 0.197157 -0.980008 0.0267258 + outer loop + vertex 504.176 88.9716 158.447 + vertex 504.779 89.2293 163.454 + vertex 501.961 88.6985 164.777 + endloop + endfacet + facet normal 0.203529 -0.978803 0.0228028 + outer loop + vertex 507.539 89.6353 159.117 + vertex 513.152 90.9808 166.771 + vertex 507.534 89.8432 168.079 + endloop + endfacet + facet normal 0.191995 -0.981278 0.0152203 + outer loop + vertex 504.779 89.2293 163.454 + vertex 503.986 89.1737 169.865 + vertex 501.961 88.6985 164.777 + endloop + endfacet + facet normal 0.202897 -0.979188 0.00485043 + outer loop + vertex 507.534 89.8432 168.079 + vertex 512.758 90.9626 175.528 + vertex 506.609 89.6942 176.693 + endloop + endfacet + facet normal 0.190594 -0.981664 0.00310452 + outer loop + vertex 503.986 89.1737 169.865 + vertex 503.136 89.0285 176.17 + vertex 501.067 88.6197 173.898 + endloop + endfacet + facet normal 0.198762 -0.979988 -0.0108582 + outer loop + vertex 503.136 89.0285 176.17 + vertex 503.737 89.0964 181.052 + vertex 500.815 88.4872 182.534 + endloop + endfacet + facet normal 0.202655 -0.97913 -0.0153483 + outer loop + vertex 506.609 89.6942 176.693 + vertex 512.396 90.7734 184.254 + vertex 506.574 89.548 185.554 + endloop + endfacet + facet normal 0.192751 -0.980975 -0.0231133 + outer loop + vertex 503.737 89.0964 181.052 + vertex 502.935 88.7874 187.476 + vertex 500.815 88.4872 182.534 + endloop + endfacet + facet normal 0.200787 -0.979023 -0.0346324 + outer loop + vertex 506.574 89.548 185.554 + vertex 511.999 90.399 192.948 + vertex 505.672 89.0587 194.156 + endloop + endfacet + facet normal 0.191639 -0.980835 -0.0351715 + outer loop + vertex 502.935 88.7874 187.476 + vertex 502.062 88.392 193.744 + vertex 499.904 88.0457 191.647 + endloop + endfacet + facet normal 0.198032 -0.978826 -0.0517986 + outer loop + vertex 502.062 88.392 193.744 + vertex 502.721 88.2684 198.6 + vertex 499.686 87.568 200.232 + endloop + endfacet + facet normal 0.199679 -0.978214 -0.0567924 + outer loop + vertex 505.672 89.0587 194.156 + vertex 511.645 89.8428 201.652 + vertex 505.689 88.5481 203.012 + endloop + endfacet + facet normal 0.190832 -0.979438 -0.0654511 + outer loop + vertex 502.721 88.2684 198.6 + vertex 501.895 87.6752 205.068 + vertex 499.686 87.568 200.232 + endloop + endfacet + facet normal 0.196976 -0.977333 -0.0775963 + outer loop + vertex 505.689 88.5481 203.012 + vertex 511.292 89.091 210.397 + vertex 504.737 87.6699 211.655 + endloop + endfacet + facet normal 0.189103 -0.978792 -0.0787837 + outer loop + vertex 501.895 87.6752 205.068 + vertex 501 86.9917 211.413 + vertex 498.734 86.7137 209.428 + endloop + endfacet + facet normal 0.194155 -0.976339 -0.0952154 + outer loop + vertex 501 86.9917 211.413 + vertex 501.711 86.6669 216.193 + vertex 498.585 85.8625 218.067 + endloop + endfacet + facet normal 0.195667 -0.975606 -0.0995336 + outer loop + vertex 504.737 87.6699 211.655 + vertex 510.949 88.1498 219.163 + vertex 504.825 86.7879 220.474 + endloop + endfacet + facet normal 0.187009 -0.976491 -0.107206 + outer loop + vertex 501.711 86.6669 216.193 + vertex 501.001 85.8404 222.482 + vertex 498.585 85.8625 218.067 + endloop + endfacet + facet normal 0.175094 -0.977548 -0.117223 + outer loop + vertex 500.561 85.1887 227.26 + vertex 501.001 85.8404 222.482 + vertex 503.893 85.6112 228.713 + endloop + endfacet + facet normal 0.191875 -0.974525 -0.116125 + outer loop + vertex 510.949 88.1498 219.163 + vertex 510.592 87.0443 227.851 + vertex 504.825 86.7879 220.474 + endloop + endfacet + facet normal 0.193143 -0.971895 -0.134591 + outer loop + vertex 503.893 85.6112 228.713 + vertex 510.218 85.7916 236.488 + vertex 503.901 84.3856 237.575 + endloop + endfacet + facet normal 0.205371 -0.969729 -0.132092 + outer loop + vertex 519.511 88.9447 227.767 + vertex 519.258 87.6989 236.518 + vertex 510.592 87.0443 227.851 + endloop + endfacet + facet normal 0.204632 -0.968142 -0.144316 + outer loop + vertex 510.218 85.7916 236.488 + vertex 519.025 86.3588 245.171 + vertex 509.887 84.4457 245.047 + endloop + endfacet + facet normal 0.219397 -0.96486 -0.144601 + outer loop + vertex 530.382 90.171 236.902 + vertex 530.258 88.828 245.675 + vertex 519.258 87.6989 236.518 + endloop + endfacet + facet normal 0.218471 -0.964265 -0.149878 + outer loop + vertex 519.025 86.3588 245.171 + vertex 530.253 87.4716 254.377 + vertex 518.895 84.9934 253.765 + endloop + endfacet + facet normal 0.236096 -0.959927 -0.150994 + outer loop + vertex 542.766 91.8289 246.155 + vertex 542.833 90.4591 254.967 + vertex 530.258 88.828 245.675 + endloop + endfacet + facet normal 0.233963 -0.961338 -0.145225 + outer loop + vertex 530.253 87.4716 254.377 + vertex 543.026 89.1605 263.775 + vertex 530.352 86.1734 263.13 + endloop + endfacet + facet normal 0.255192 -0.955088 -0.150611 + outer loop + vertex 555.799 93.8679 255.32 + vertex 556.023 92.5299 264.185 + vertex 542.833 90.4591 254.967 + endloop + endfacet + facet normal 0.249833 -0.959587 -0.129522 + outer loop + vertex 543.026 89.1605 263.775 + vertex 556.31 91.3592 273.11 + vertex 543.174 87.9936 272.707 + endloop + endfacet + facet normal 0.272934 -0.951383 -0.142748 + outer loop + vertex 568.667 96.1549 264.2 + vertex 569.042 94.9239 273.121 + vertex 556.023 92.5299 264.185 + endloop + endfacet + facet normal 0.261821 -0.959358 -0.105271 + outer loop + vertex 556.31 91.3592 273.11 + vertex 569.453 93.9527 282.162 + vertex 556.239 90.358 282.056 + endloop + endfacet + facet normal 0.284979 -0.949494 -0.131334 + outer loop + vertex 580.531 98.4562 272.514 + vertex 581.419 97.4691 281.577 + vertex 569.042 94.9239 273.121 + endloop + endfacet + facet normal 0.287958 -0.948568 -0.131525 + outer loop + vertex 580.531 98.4562 272.514 + vertex 591.82 100.797 280.344 + vertex 581.419 97.4691 281.577 + endloop + endfacet + facet normal 0.264834 -0.961159 -0.0776991 + outer loop + vertex 569.453 93.9527 282.162 + vertex 582.823 96.9116 291.13 + vertex 568.978 93.1265 290.763 + endloop + endfacet + facet normal 0.258963 -0.964425 -0.0531198 + outer loop + vertex 594.407 99.7612 295.87 + vertex 590.375 98.5179 298.786 + vertex 582.823 96.9116 291.13 + endloop + endfacet + facet normal 0.271756 -0.959875 -0.0692008 + outer loop + vertex 599.658 101.321 294.859 + vertex 601.063 101.371 299.674 + vertex 594.407 99.7612 295.87 + endloop + endfacet + facet normal 0.277088 -0.955083 -0.105062 + outer loop + vertex 598.841 101.717 289.098 + vertex 603.409 102.412 294.828 + vertex 599.658 101.321 294.859 + endloop + endfacet + facet normal 0.288889 -0.94914 -0.125207 + outer loop + vertex 591.82 100.797 280.344 + vertex 592.047 99.7238 289.006 + vertex 581.419 97.4691 281.577 + endloop + endfacet + facet normal 0.289866 -0.947485 -0.135096 + outer loop + vertex 599.814 102.722 284.136 + vertex 602.668 102.691 290.48 + vertex 598.841 101.717 289.098 + endloop + endfacet + facet normal 0.299416 -0.941558 -0.154335 + outer loop + vertex 596.487 103.34 273.915 + vertex 601.984 103.857 281.422 + vertex 599.814 102.722 284.136 + endloop + endfacet + facet normal 0.298213 -0.942957 -0.147988 + outer loop + vertex 588.676 101.286 270.899 + vertex 591.82 100.797 280.344 + vertex 580.531 98.4562 272.514 + endloop + endfacet + facet normal 0.305755 -0.937737 -0.164814 + outer loop + vertex 590.178 103.184 262.883 + vertex 588.676 101.286 270.899 + vertex 580.068 99.7454 263.693 + endloop + endfacet + facet normal 0.311249 -0.935354 -0.168041 + outer loop + vertex 597.148 105.073 265.494 + vertex 600.555 105.145 271.402 + vertex 596.487 103.34 273.915 + endloop + endfacet + facet normal 0.327665 -0.928578 -0.174292 + outer loop + vertex 594.727 106.008 255.961 + vertex 599.93 106.587 262.657 + vertex 597.148 105.073 265.494 + endloop + endfacet + facet normal 0.308896 -0.936616 -0.165329 + outer loop + vertex 587.457 103.929 253.578 + vertex 590.178 103.184 262.883 + vertex 579.676 101.122 254.945 + endloop + endfacet + facet normal 0.31448 -0.934418 -0.167228 + outer loop + vertex 588.383 105.514 246.463 + vertex 587.457 103.929 253.578 + vertex 579.226 102.451 246.363 + endloop + endfacet + facet normal 0.338224 -0.925508 -0.170409 + outer loop + vertex 594.923 107.916 245.989 + vertex 599.007 108.062 253.3 + vertex 594.727 106.008 255.961 + endloop + endfacet + facet normal 0.319397 -0.933817 -0.161154 + outer loop + vertex 588.703 107.161 237.555 + vertex 588.383 105.514 246.463 + vertex 579.245 103.886 237.787 + endloop + endfacet + facet normal 0.348059 -0.923282 -0.162494 + outer loop + vertex 595.121 109.558 237.079 + vertex 598.674 109.626 244.305 + vertex 594.923 107.916 245.989 + endloop + endfacet + facet normal 0.323489 -0.934545 -0.148255 + outer loop + vertex 589.483 109.003 227.647 + vertex 588.703 107.161 237.555 + vertex 579.328 105.323 228.684 + endloop + endfacet + facet normal 0.356262 -0.92215 -0.150722 + outer loop + vertex 595.899 111.001 230.093 + vertex 598.491 111.113 235.532 + vertex 595.121 109.558 237.079 + endloop + endfacet + facet normal 0.365483 -0.920654 -0.137179 + outer loop + vertex 594.521 111.647 222.08 + vertex 598.245 112.38 227.086 + vertex 595.899 111.001 230.093 + endloop + endfacet + facet normal 0.355986 -0.925488 -0.129406 + outer loop + vertex 597.831 113.494 217.984 + vertex 598.245 112.38 227.086 + vertex 594.521 111.647 222.08 + endloop + endfacet + facet normal 0.324321 -0.937766 -0.124141 + outer loop + vertex 587.635 109.796 216.828 + vertex 589.483 109.003 227.647 + vertex 578.995 106.493 219.206 + endloop + endfacet + facet normal 0.371173 -0.92138 -0.115283 + outer loop + vertex 593.056 112.386 211.462 + vertex 597.831 113.494 217.984 + vertex 594.521 111.647 222.08 + endloop + endfacet + facet normal 0.360807 -0.926503 -0.106823 + outer loop + vertex 597.585 114.405 209.243 + vertex 597.831 113.494 217.984 + vertex 593.056 112.386 211.462 + endloop + endfacet + facet normal 0.326533 -0.939777 -0.100967 + outer loop + vertex 585.903 110.073 208.65 + vertex 587.635 109.796 216.828 + vertex 578.286 107.273 210.072 + endloop + endfacet + facet normal 0.330504 -0.94015 -0.0829722 + outer loop + vertex 587.533 111.255 201.742 + vertex 585.903 110.073 208.65 + vertex 578.24 108 201.612 + endloop + endfacet + facet normal 0.370676 -0.924848 -0.0851839 + outer loop + vertex 594.286 113.745 202.053 + vertex 597.585 114.405 209.243 + vertex 593.056 112.386 211.462 + endloop + endfacet + facet normal 0.370865 -0.924763 -0.0852786 + outer loop + vertex 597.919 115.269 201.335 + vertex 597.585 114.405 209.243 + vertex 594.286 113.745 202.053 + endloop + endfacet + facet normal 0.333297 -0.940705 -0.0631495 + outer loop + vertex 588.994 112.416 192.16 + vertex 587.533 111.255 201.742 + vertex 578.782 108.749 192.885 + endloop + endfacet + facet normal 0.374863 -0.924791 -0.0651103 + outer loop + vertex 595.396 114.676 195.229 + vertex 597.919 115.269 201.335 + vertex 594.286 113.745 202.053 + endloop + endfacet + facet normal 0.36865 -0.927479 -0.0622824 + outer loop + vertex 597.807 115.787 192.953 + vertex 597.919 115.269 201.335 + vertex 595.396 114.676 195.229 + endloop + endfacet + facet normal 0.380408 -0.923576 -0.04792 + outer loop + vertex 594.155 114.59 187.038 + vertex 597.807 115.787 192.953 + vertex 595.396 114.676 195.229 + endloop + endfacet + facet normal 0.366621 -0.929586 -0.0381929 + outer loop + vertex 597.483 116.04 183.693 + vertex 597.807 115.787 192.953 + vertex 594.155 114.59 187.038 + endloop + endfacet + facet normal 0.331938 -0.94272 -0.0331108 + outer loop + vertex 587.44 112.252 181.24 + vertex 588.994 112.416 192.16 + vertex 578.776 109.124 183.466 + endloop + endfacet + facet normal 0.37944 -0.92492 -0.0234121 + outer loop + vertex 592.78 114.301 176.156 + vertex 597.483 116.04 183.693 + vertex 594.155 114.59 187.038 + endloop + endfacet + facet normal 0.367738 -0.929809 -0.0149833 + outer loop + vertex 597.43 116.169 174.341 + vertex 597.483 116.04 183.693 + vertex 592.78 114.301 176.156 + endloop + endfacet + facet normal 0.332116 -0.943208 -0.00754067 + outer loop + vertex 585.696 111.704 172.981 + vertex 587.44 112.252 181.24 + vertex 578.202 109.055 174.297 + endloop + endfacet + facet normal 0.334166 -0.942459 0.0101966 + outer loop + vertex 587.052 112.112 166.224 + vertex 585.696 111.704 172.981 + vertex 578.12 108.941 165.861 + endloop + endfacet + facet normal 0.375271 -0.926886 0.00733085 + outer loop + vertex 593.639 114.571 166.304 + vertex 597.43 116.169 174.341 + vertex 592.78 114.301 176.156 + endloop + endfacet + facet normal 0.372023 -0.928179 0.00911959 + outer loop + vertex 597.55 116.13 165.379 + vertex 597.43 116.169 174.341 + vertex 593.639 114.571 166.304 + endloop + endfacet + facet normal 0.334907 -0.941816 0.0286284 + outer loop + vertex 587.616 112.046 157.447 + vertex 587.052 112.112 166.224 + vertex 578.484 108.796 157.345 + endloop + endfacet + facet normal 0.376011 -0.926148 0.0294002 + outer loop + vertex 593.988 114.422 157.153 + vertex 597.55 116.13 165.379 + vertex 593.639 114.571 166.304 + endloop + endfacet + facet normal 0.372102 -0.92766 0.0314068 + outer loop + vertex 597.635 115.853 156.208 + vertex 597.55 116.13 165.379 + vertex 593.988 114.422 157.153 + endloop + endfacet + facet normal 0.334422 -0.941092 0.0500746 + outer loop + vertex 588.031 111.704 148.242 + vertex 587.616 112.046 157.447 + vertex 578.736 108.406 148.338 + endloop + endfacet + facet normal 0.376241 -0.925102 0.0512751 + outer loop + vertex 594.384 114.089 148.23 + vertex 597.635 115.853 156.208 + vertex 593.988 114.422 157.153 + endloop + endfacet + facet normal 0.371635 -0.926834 0.0535351 + outer loop + vertex 597.823 115.427 147.527 + vertex 597.635 115.853 156.208 + vertex 594.384 114.089 148.23 + endloop + endfacet + facet normal 0.332693 -0.940236 0.0726032 + outer loop + vertex 588.788 111.198 138.223 + vertex 588.031 111.704 148.242 + vertex 578.954 107.784 139.073 + endloop + endfacet + facet normal 0.374434 -0.924476 0.071722 + outer loop + vertex 595.176 113.848 140.985 + vertex 597.823 115.427 147.527 + vertex 594.384 114.089 148.23 + endloop + endfacet + facet normal 0.367034 -0.92715 0.0753616 + outer loop + vertex 597.795 114.704 138.77 + vertex 597.823 115.427 147.527 + vertex 595.176 113.848 140.985 + endloop + endfacet + facet normal 0.375513 -0.922716 0.0870944 + outer loop + vertex 593.348 112.205 131.468 + vertex 597.795 114.704 138.77 + vertex 595.176 113.848 140.985 + endloop + endfacet + facet normal 0.361635 -0.92725 0.0970975 + outer loop + vertex 597.776 113.74 129.63 + vertex 597.795 114.704 138.77 + vertex 593.348 112.205 131.468 + endloop + endfacet + facet normal 0.328184 -0.939342 0.0996589 + outer loop + vertex 586.351 109.326 128.602 + vertex 588.788 111.198 138.223 + vertex 578.7 106.784 129.839 + endloop + endfacet + facet normal 0.327731 -0.93768 0.115539 + outer loop + vertex 587.554 108.872 121.508 + vertex 586.351 109.326 128.602 + vertex 578.601 105.702 121.179 + endloop + endfacet + facet normal 0.367432 -0.922956 0.114655 + outer loop + vertex 594.143 111.287 121.529 + vertex 597.776 113.74 129.63 + vertex 593.348 112.205 131.468 + endloop + endfacet + facet normal 0.361585 -0.924861 0.117854 + outer loop + vertex 598.036 112.665 120.402 + vertex 597.776 113.74 129.63 + vertex 594.143 111.287 121.529 + endloop + endfacet + facet normal 0.32537 -0.936097 0.133628 + outer loop + vertex 588.329 107.872 112.612 + vertex 587.554 108.872 121.508 + vertex 579.045 104.65 112.647 + endloop + endfacet + facet normal 0.36526 -0.92103 0.135237 + outer loop + vertex 594.825 110.243 112.581 + vertex 598.036 112.665 120.402 + vertex 594.143 111.287 121.529 + endloop + endfacet + facet normal 0.359195 -0.922955 0.138323 + outer loop + vertex 598.351 111.506 111.846 + vertex 598.036 112.665 120.402 + vertex 594.825 110.243 112.581 + endloop + endfacet + facet normal 0.322381 -0.934198 0.152791 + outer loop + vertex 589.511 106.663 102.731 + vertex 588.329 107.872 112.612 + vertex 579.531 103.365 103.618 + endloop + endfacet + facet normal 0.361253 -0.919696 0.1538 + outer loop + vertex 595.884 109.458 105.397 + vertex 598.351 111.506 111.846 + vertex 594.825 110.243 112.581 + endloop + endfacet + facet normal 0.352133 -0.922487 0.158175 + outer loop + vertex 598.52 110.052 102.99 + vertex 598.351 111.506 111.846 + vertex 595.884 109.458 105.397 + endloop + endfacet + facet normal 0.359043 -0.9183 0.166776 + outer loop + vertex 594.687 107.316 96.181 + vertex 598.52 110.052 102.99 + vertex 595.884 109.458 105.397 + endloop + endfacet + facet normal 0.345519 -0.921798 0.175795 + outer loop + vertex 598.882 108.517 94.2315 + vertex 598.52 110.052 102.99 + vertex 594.687 107.316 96.181 + endloop + endfacet + facet normal 0.316919 -0.932079 0.175472 + outer loop + vertex 587.667 104.217 93.069 + vertex 589.511 106.663 102.731 + vertex 579.641 101.751 94.4627 + endloop + endfacet + facet normal 0.315136 -0.930167 0.188355 + outer loop + vertex 590.201 103.502 85.2953 + vertex 587.667 104.217 93.069 + vertex 579.992 100.128 85.7125 + endloop + endfacet + facet normal 0.350154 -0.917552 0.188387 + outer loop + vertex 596.549 106.448 88.4932 + vertex 598.882 108.517 94.2315 + vertex 594.687 107.316 96.181 + endloop + endfacet + facet normal 0.340423 -0.92019 0.193295 + outer loop + vertex 599.398 106.936 85.7976 + vertex 598.882 108.517 94.2315 + vertex 596.549 106.448 88.4932 + endloop + endfacet + facet normal 0.348269 -0.915266 0.202478 + outer loop + vertex 596.038 104.437 80.2793 + vertex 599.398 106.936 85.7976 + vertex 596.549 106.448 88.4932 + endloop + endfacet + facet normal 0.334766 -0.918144 0.212001 + outer loop + vertex 599.772 105.018 76.8984 + vertex 599.398 106.936 85.7976 + vertex 596.038 104.437 80.2793 + endloop + endfacet + facet normal 0.308076 -0.927369 0.212309 + outer loop + vertex 589.615 100.875 74.6721 + vertex 590.201 103.502 85.2953 + vertex 580.503 98.3588 76.9023 + endloop + endfacet + facet normal 0.345194 -0.911235 0.224705 + outer loop + vertex 596.15 101.762 69.2582 + vertex 599.772 105.018 76.8984 + vertex 596.038 104.437 80.2793 + endloop + endfacet + facet normal 0.33028 -0.914617 0.233217 + outer loop + vertex 600.884 102.934 67.1497 + vertex 599.772 105.018 76.8984 + vertex 596.15 101.762 69.2582 + endloop + endfacet + facet normal 0.304061 -0.923488 0.233916 + outer loop + vertex 588.948 98.54 66.3207 + vertex 589.615 100.875 74.6721 + vertex 580.59 96.2091 67.9831 + endloop + endfacet + facet normal 0.304554 -0.918905 0.250722 + outer loop + vertex 592.471 97.6312 58.7101 + vertex 588.948 98.54 66.3207 + vertex 581.703 94.2527 59.4083 + endloop + endfacet + facet normal 0.336985 -0.907022 0.252493 + outer loop + vertex 600.009 100.32 58.9278 + vertex 600.884 102.934 67.1497 + vertex 596.15 101.762 69.2582 + endloop + endfacet + facet normal 0.317476 -0.909505 0.268345 + outer loop + vertex 597.6 97.7514 53.0733 + vertex 601.636 98.8654 52.0736 + vertex 600.009 100.32 58.9278 + endloop + endfacet + facet normal 0.312014 -0.906289 0.285109 + outer loop + vertex 599.511 96.7641 47.8438 + vertex 597.6 97.7514 53.0733 + vertex 593.644 94.9384 48.4606 + endloop + endfacet + facet normal 0.311675 -0.912004 0.266661 + outer loop + vertex 592.868 95.9827 52.6077 + vertex 592.471 97.6312 58.7101 + vertex 584.613 92.5437 50.4945 + endloop + endfacet + facet normal 0.305625 -0.902208 0.304325 + outer loop + vertex 595.199 93.8827 43.7695 + vertex 593.644 94.9384 48.4606 + vertex 587.924 91.7004 44.6059 + endloop + endfacet + facet normal 0.28748 -0.908404 0.303576 + outer loop + vertex 581.672 89.7701 44.9806 + vertex 584.613 92.5437 50.4945 + vertex 572.879 86.9314 44.8125 + endloop + endfacet + facet normal 0.271018 -0.905602 0.326243 + outer loop + vertex 573.689 85.4608 40.0577 + vertex 572.879 86.9314 44.8125 + vertex 561.55 82.2262 41.1631 + endloop + endfacet + facet normal 0.295576 -0.900444 0.319116 + outer loop + vertex 589.619 90.8935 40.759 + vertex 587.924 91.7004 44.6059 + vertex 581.34 88.5769 41.8899 + endloop + endfacet + facet normal 0.303559 -0.885983 0.350552 + outer loop + vertex 592.693 90.8922 38.0932 + vertex 596.756 93.1332 40.2396 + vertex 589.619 90.8935 40.759 + endloop + endfacet + facet normal 0.295101 -0.908587 0.295609 + outer loop + vertex 591.631 90.197 37.3007 + vertex 586.761 88.7837 37.8178 + vertex 587.426 88.8346 37.3104 + endloop + endfacet + facet normal 0.304781 -0.880468 0.363159 + outer loop + vertex 599.113 92.7218 37.1412 + vertex 598.81 93.0826 38.2705 + vertex 592.693 90.8922 38.0932 + endloop + endfacet + facet normal 0.31138 -0.871354 0.379191 + outer loop + vertex 604.051 94.2915 36.6932 + vertex 599.113 92.7218 37.1412 + vertex 599.76 92.7284 36.6254 + endloop + endfacet + facet normal 0.313508 -0.876585 0.365119 + outer loop + vertex 599.76 92.7284 36.6254 + vertex 602.747 93.5799 36.1049 + vertex 604.051 94.2915 36.6932 + endloop + endfacet + facet normal 0.299453 -0.853097 0.427262 + outer loop + vertex 602.747 93.5799 36.1049 + vertex 596.043 91.2647 36.1808 + vertex 604.251 93.4183 34.7277 + endloop + endfacet + facet normal 0.287501 -0.843632 0.453462 + outer loop + vertex 586.282 88.1236 36.5254 + vertex 596.141 90.3741 34.462 + vertex 596.043 91.2647 36.1808 + endloop + endfacet + facet normal 0.287618 -0.842803 0.454928 + outer loop + vertex 585.694 86.883 34.5991 + vertex 596.141 90.3741 34.462 + vertex 586.282 88.1236 36.5254 + endloop + endfacet + facet normal 0.275415 -0.844323 0.459636 + outer loop + vertex 574.388 84.5149 37.0237 + vertex 585.694 86.883 34.5991 + vertex 586.282 88.1236 36.5254 + endloop + endfacet + facet normal 0.274575 -0.84933 0.45083 + outer loop + vertex 573.398 83.1895 35.1297 + vertex 585.694 86.883 34.5991 + vertex 574.388 84.5149 37.0237 + endloop + endfacet + facet normal 0.260232 -0.849695 0.458581 + outer loop + vertex 561.63 80.9088 37.5818 + vertex 573.398 83.1895 35.1297 + vertex 574.388 84.5149 37.0237 + endloop + endfacet + facet normal 0.25874 -0.858028 0.443669 + outer loop + vertex 560.668 79.646 35.7008 + vertex 573.398 83.1895 35.1297 + vertex 561.63 80.9088 37.5818 + endloop + endfacet + facet normal 0.239993 -0.858349 0.453475 + outer loop + vertex 548.656 77.5497 38.0898 + vertex 560.668 79.646 35.7008 + vertex 561.63 80.9088 37.5818 + endloop + endfacet + facet normal 0.238486 -0.866292 0.438933 + outer loop + vertex 547.817 76.3591 36.1959 + vertex 560.668 79.646 35.7008 + vertex 548.656 77.5497 38.0898 + endloop + endfacet + facet normal 0.217253 -0.866871 0.448705 + outer loop + vertex 535.746 74.5107 38.4691 + vertex 547.817 76.3591 36.1959 + vertex 548.656 77.5497 38.0898 + endloop + endfacet + facet normal 0.195936 -0.869944 0.452556 + outer loop + vertex 523.628 71.8877 38.674 + vertex 535.052 73.3346 36.5087 + vertex 535.746 74.5107 38.4691 + endloop + endfacet + facet normal 0.177422 -0.865127 0.469124 + outer loop + vertex 513.57 69.7847 38.5995 + vertex 523.195 70.6512 36.5572 + vertex 523.628 71.8877 38.674 + endloop + endfacet + facet normal 0.159858 -0.854408 0.494402 + outer loop + vertex 505.895 68.0592 38.0992 + vertex 513.347 68.3853 36.2533 + vertex 513.57 69.7847 38.5995 + endloop + endfacet + facet normal 0.139541 -0.840768 0.523104 + outer loop + vertex 506.082 66.3319 35.273 + vertex 505.895 68.0592 38.0992 + vertex 499.375 65.9509 36.4498 + endloop + endfacet + facet normal 0.159834 -0.926347 0.341078 + outer loop + vertex 498.983 67.9652 40.0058 + vertex 493.585 66.4385 38.389 + vertex 495.666 66.9795 38.883 + endloop + endfacet + facet normal 0.107614 -0.866701 0.487082 + outer loop + vertex 497.079 67.3563 39.2288 + vertex 493.602 66.3397 38.1879 + vertex 496.202 66.9098 38.6281 + endloop + endfacet + facet normal 0.111928 -0.869025 0.481942 + outer loop + vertex 495.752 66.9947 38.8697 + vertex 492.311 66.0124 37.8978 + vertex 493.602 66.3397 38.1879 + endloop + endfacet +endsolid diff --git a/noether_examples/meshes/outputs/output_5.stl b/noether_examples/meshes/outputs/output_5.stl new file mode 100644 index 00000000..6904d2fa --- /dev/null +++ b/noether_examples/meshes/outputs/output_5.stl @@ -0,0 +1,69183 @@ +solid ascii + facet normal -0.153327 -0.91606 0.370574 + outer loop + vertex -495.868 67.088 39.0706 + vertex -495.612 66.9797 38.9089 + vertex -493.304 66.3152 38.2216 + endloop + endfacet + facet normal -0.134982 -0.901003 0.412279 + outer loop + vertex -495.868 67.088 39.0706 + vertex -493.304 66.3152 38.2216 + vertex -492.742 66.1796 38.1092 + endloop + endfacet + facet normal -0.151808 -0.915492 0.372597 + outer loop + vertex -495.612 66.9797 38.9089 + vertex -495.868 67.088 39.0706 + vertex -497.802 67.6441 39.6493 + endloop + endfacet + facet normal -0.129888 -0.897557 0.421332 + outer loop + vertex -497.802 67.6441 39.6493 + vertex -497.219 67.3483 39.1987 + vertex -495.612 66.9797 38.9089 + endloop + endfacet + facet normal -0.131017 -0.899287 0.417273 + outer loop + vertex -495.612 66.9797 38.9089 + vertex -497.219 67.3483 39.1987 + vertex -495.078 66.7816 38.6497 + endloop + endfacet + facet normal -0.146936 -0.9084 0.391433 + outer loop + vertex -490.68 65.5499 37.4423 + vertex -495.612 66.9797 38.9089 + vertex -495.078 66.7816 38.6497 + endloop + endfacet + facet normal -0.112254 -0.870531 0.47914 + outer loop + vertex -495.078 66.7816 38.6497 + vertex -493.338 66.1627 37.9329 + vertex -490.68 65.5499 37.4423 + endloop + endfacet + facet normal -0.098425 -0.85887 0.502648 + outer loop + vertex -495.078 66.7816 38.6497 + vertex -497.219 67.3483 39.1987 + vertex -493.338 66.1627 37.9329 + endloop + endfacet + facet normal -0.108535 -0.869593 0.481693 + outer loop + vertex -493.338 66.1627 37.9329 + vertex -497.219 67.3483 39.1987 + vertex -498.006 67.0539 38.4901 + endloop + endfacet + facet normal -0.10528 -0.861711 0.496356 + outer loop + vertex -493.409 65.8495 37.3743 + vertex -493.338 66.1627 37.9329 + vertex -498.006 67.0539 38.4901 + endloop + endfacet + facet normal -0.0937959 -0.845313 0.525974 + outer loop + vertex -493.409 65.8495 37.3743 + vertex -498.006 67.0539 38.4901 + vertex -495.01 65.5909 36.6731 + endloop + endfacet + facet normal -0.101709 -0.835275 0.540344 + outer loop + vertex -493.409 65.8495 37.3743 + vertex -495.01 65.5909 36.6731 + vertex -487.815 64.0779 35.6886 + endloop + endfacet + facet normal -0.101638 -0.850028 0.516839 + outer loop + vertex -498.006 67.0539 38.4901 + vertex -499.669 66.038 36.4921 + vertex -495.01 65.5909 36.6731 + endloop + endfacet + facet normal -0.114507 -0.84376 0.524364 + outer loop + vertex -499.669 66.038 36.4921 + vertex -498.006 67.0539 38.4901 + vertex -501.789 67.029 37.6239 + endloop + endfacet + facet normal -0.0992495 -0.882953 0.45885 + outer loop + vertex -498.556 67.9088 40.0162 + vertex -501.789 67.029 37.6239 + vertex -498.006 67.0539 38.4901 + endloop + endfacet + facet normal 0.397444 0.854199 -0.335234 + outer loop + vertex -498.006 67.0539 38.4901 + vertex -498.514 67.7604 39.6878 + vertex -498.556 67.9088 40.0162 + endloop + endfacet + facet normal 0.464068 0.827957 -0.314847 + outer loop + vertex -498.514 67.7604 39.6878 + vertex -498.575 67.8909 39.9414 + vertex -498.556 67.9088 40.0162 + endloop + endfacet + facet normal -0.196789 -0.941185 0.274671 + outer loop + vertex -498.575 67.8909 39.9414 + vertex -497.802 67.6441 39.6493 + vertex -498.556 67.9088 40.0162 + endloop + endfacet + facet normal -0.122728 -0.894066 0.430795 + outer loop + vertex -498.575 67.8909 39.9414 + vertex -498.514 67.7604 39.6878 + vertex -497.802 67.6441 39.6493 + endloop + endfacet + facet normal -0.145216 -0.848785 0.508406 + outer loop + vertex -501.789 67.029 37.6239 + vertex -498.556 67.9088 40.0162 + vertex -505.101 68.193 38.621 + endloop + endfacet + facet normal -0.140681 -0.843886 0.51775 + outer loop + vertex -505.101 68.193 38.621 + vertex -506.338 66.629 35.7359 + vertex -501.789 67.029 37.6239 + endloop + endfacet + facet normal -0.168703 -0.834439 0.524644 + outer loop + vertex -505.101 68.193 38.621 + vertex -512.935 68.3803 36.4002 + vertex -506.338 66.629 35.7359 + endloop + endfacet + facet normal -0.165234 -0.826495 0.538148 + outer loop + vertex -512.935 68.3803 36.4002 + vertex -512.328 66.0567 33.0176 + vertex -506.338 66.629 35.7359 + endloop + endfacet + facet normal -0.1818 -0.825422 0.534441 + outer loop + vertex -512.935 68.3803 36.4002 + vertex -522.352 68.4303 33.2739 + vertex -512.328 66.0567 33.0176 + endloop + endfacet + facet normal -0.176407 -0.836985 0.518012 + outer loop + vertex -523.143 70.6383 36.5723 + vertex -522.352 68.4303 33.2739 + vertex -512.935 68.3803 36.4002 + endloop + endfacet + facet normal -0.180394 -0.852872 0.489967 + outer loop + vertex -513.175 69.7578 38.7095 + vertex -523.143 70.6383 36.5723 + vertex -512.935 68.3803 36.4002 + endloop + endfacet + facet normal -0.160308 -0.85496 0.493301 + outer loop + vertex -513.175 69.7578 38.7095 + vertex -512.935 68.3803 36.4002 + vertex -505.101 68.193 38.621 + endloop + endfacet + facet normal -0.176828 -0.865865 0.467985 + outer loop + vertex -523.698 71.9055 38.7071 + vertex -523.143 70.6383 36.5723 + vertex -513.175 69.7578 38.7095 + endloop + endfacet + facet normal -0.182761 -0.894998 0.406911 + outer loop + vertex -513.308 70.2585 39.7509 + vertex -523.698 71.9055 38.7071 + vertex -513.175 69.7578 38.7095 + endloop + endfacet + facet normal -0.161925 -0.897286 0.410679 + outer loop + vertex -513.308 70.2585 39.7509 + vertex -513.175 69.7578 38.7095 + vertex -505.927 68.9316 39.762 + endloop + endfacet + facet normal -0.168092 -0.932354 0.320094 + outer loop + vertex -505.846 69.034 40.1029 + vertex -513.308 70.2585 39.7509 + vertex -505.927 68.9316 39.762 + endloop + endfacet + facet normal -0.146994 -0.937133 0.316505 + outer loop + vertex -505.846 69.034 40.1029 + vertex -505.927 68.9316 39.762 + vertex -502.226 68.4673 40.1063 + endloop + endfacet + facet normal -0.150201 -0.90886 0.389117 + outer loop + vertex -502.226 68.4673 40.1063 + vertex -505.927 68.9316 39.762 + vertex -502.075 68.3202 39.8206 + endloop + endfacet + facet normal -0.128292 -0.907518 0.399941 + outer loop + vertex -502.226 68.4673 40.1063 + vertex -502.075 68.3202 39.8206 + vertex -498.556 67.9088 40.0162 + endloop + endfacet + facet normal -0.129649 -0.913954 0.38455 + outer loop + vertex -498.556 67.9088 40.0162 + vertex -502.937 68.7502 40.5391 + vertex -502.226 68.4673 40.1063 + endloop + endfacet + facet normal -0.128819 -0.912273 0.388798 + outer loop + vertex -502.937 68.7502 40.5391 + vertex -498.556 67.9088 40.0162 + vertex -502.449 69.2333 41.834 + endloop + endfacet + facet normal -0.134475 -0.910784 0.390371 + outer loop + vertex -502.449 69.2333 41.834 + vertex -505.826 69.6407 41.6213 + vertex -502.937 68.7502 40.5391 + endloop + endfacet + facet normal -0.127471 -0.911476 0.391105 + outer loop + vertex -500.818 69.2014 42.2912 + vertex -502.449 69.2333 41.834 + vertex -498.556 67.9088 40.0162 + endloop + endfacet + facet normal -0.103538 -0.905506 0.411507 + outer loop + vertex -498.556 67.9088 40.0162 + vertex -499.755 69.0167 42.1523 + vertex -500.818 69.2014 42.2912 + endloop + endfacet + facet normal -0.111035 -0.920648 0.374271 + outer loop + vertex -501.806 70.2419 44.5576 + vertex -500.818 69.2014 42.2912 + vertex -499.755 69.0167 42.1523 + endloop + endfacet + facet normal -0.119283 -0.922143 0.368001 + outer loop + vertex -499.755 69.0167 42.1523 + vertex -501.349 70.4326 45.1838 + vertex -501.806 70.2419 44.5576 + endloop + endfacet + facet normal -0.129488 -0.921344 0.366548 + outer loop + vertex -501.806 70.2419 44.5576 + vertex -503.325 70.3043 44.1779 + vertex -500.818 69.2014 42.2912 + endloop + endfacet + facet normal -0.125316 -0.928849 0.348619 + outer loop + vertex -501.806 70.2419 44.5576 + vertex -504.502 71.6734 47.4024 + vertex -503.325 70.3043 44.1779 + endloop + endfacet + facet normal -0.14067 -0.928752 0.342974 + outer loop + vertex -504.502 71.6734 47.4024 + vertex -506.935 71.8107 46.7763 + vertex -503.325 70.3043 44.1779 + endloop + endfacet + facet normal -0.13387 -0.926674 0.351218 + outer loop + vertex -503.325 70.3043 44.1779 + vertex -506.935 71.8107 46.7763 + vertex -505.956 70.5204 43.7453 + endloop + endfacet + facet normal -0.136219 -0.919325 0.369169 + outer loop + vertex -503.325 70.3043 44.1779 + vertex -505.956 70.5204 43.7453 + vertex -502.449 69.2333 41.834 + endloop + endfacet + facet normal -0.134248 -0.918406 0.372166 + outer loop + vertex -502.449 69.2333 41.834 + vertex -505.956 70.5204 43.7453 + vertex -505.826 69.6407 41.6213 + endloop + endfacet + facet normal -0.143993 -0.917348 0.371132 + outer loop + vertex -505.956 70.5204 43.7453 + vertex -509.983 71.0927 43.5973 + vertex -505.826 69.6407 41.6213 + endloop + endfacet + facet normal -0.147687 -0.919301 0.364795 + outer loop + vertex -505.826 69.6407 41.6213 + vertex -509.983 71.0927 43.5973 + vertex -510.29 70.2775 41.4188 + endloop + endfacet + facet normal -0.147391 -0.910014 0.387492 + outer loop + vertex -505.826 69.6407 41.6213 + vertex -510.29 70.2775 41.4188 + vertex -506.857 69.3045 40.4395 + endloop + endfacet + facet normal -0.138896 -0.913994 0.381212 + outer loop + vertex -506.857 69.3045 40.4395 + vertex -502.937 68.7502 40.5391 + vertex -505.826 69.6407 41.6213 + endloop + endfacet + facet normal -0.153383 -0.915498 0.371936 + outer loop + vertex -511.019 69.9557 40.326 + vertex -506.857 69.3045 40.4395 + vertex -510.29 70.2775 41.4188 + endloop + endfacet + facet normal -0.16494 -0.910878 0.37828 + outer loop + vertex -510.29 70.2775 41.4188 + vertex -515.914 71.1974 41.1817 + vertex -511.019 69.9557 40.326 + endloop + endfacet + facet normal -0.175799 -0.925049 0.336718 + outer loop + vertex -516.301 70.8757 40.0959 + vertex -511.019 69.9557 40.326 + vertex -515.914 71.1974 41.1817 + endloop + endfacet + facet normal -0.182269 -0.923158 0.338462 + outer loop + vertex -515.914 71.1974 41.1817 + vertex -522.638 72.3789 40.7834 + vertex -516.301 70.8757 40.0959 + endloop + endfacet + facet normal -0.179225 -0.917693 0.354566 + outer loop + vertex -522.28 72.0156 40.024 + vertex -516.301 70.8757 40.0959 + vertex -522.638 72.3789 40.7834 + endloop + endfacet + facet normal -0.197065 -0.917311 0.345985 + outer loop + vertex -528.458 73.3982 40.171 + vertex -522.28 72.0156 40.024 + vertex -522.638 72.3789 40.7834 + endloop + endfacet + facet normal -0.210816 -0.960995 0.179012 + outer loop + vertex -522.28 72.0156 40.024 + vertex -528.458 73.3982 40.171 + vertex -524.665 72.4667 39.6363 + endloop + endfacet + facet normal -0.182201 -0.919029 0.349555 + outer loop + vertex -515.914 71.1974 41.1817 + vertex -523.558 73.5149 43.2906 + vertex -522.638 72.3789 40.7834 + endloop + endfacet + facet normal -0.202517 -0.91779 0.341538 + outer loop + vertex -522.638 72.3789 40.7834 + vertex -523.558 73.5149 43.2906 + vertex -533.934 75.3626 42.1029 + endloop + endfacet + facet normal -0.201555 -0.925143 0.321692 + outer loop + vertex -533.511 77.0793 47.3054 + vertex -533.934 75.3626 42.1029 + vertex -523.558 73.5149 43.2906 + endloop + endfacet + facet normal -0.199601 -0.924173 0.325673 + outer loop + vertex -523.207 75.0335 47.8145 + vertex -533.511 77.0793 47.3054 + vertex -523.558 73.5149 43.2906 + endloop + endfacet + facet normal -0.181462 -0.927953 0.325537 + outer loop + vertex -515.833 72.1301 43.6494 + vertex -523.207 75.0335 47.8145 + vertex -523.558 73.5149 43.2906 + endloop + endfacet + facet normal -0.173871 -0.925271 0.337108 + outer loop + vertex -514.898 73.248 47.1998 + vertex -523.207 75.0335 47.8145 + vertex -515.833 72.1301 43.6494 + endloop + endfacet + facet normal -0.161664 -0.928301 0.334847 + outer loop + vertex -509.983 71.0927 43.5973 + vertex -514.898 73.248 47.1998 + vertex -515.833 72.1301 43.6494 + endloop + endfacet + facet normal -0.148649 -0.924709 0.350452 + outer loop + vertex -509.628 71.9383 45.9794 + vertex -514.898 73.248 47.1998 + vertex -509.983 71.0927 43.5973 + endloop + endfacet + facet normal -0.156026 -0.932188 0.326623 + outer loop + vertex -509.628 71.9383 45.9794 + vertex -511.897 73.5888 49.6057 + vertex -514.898 73.248 47.1998 + endloop + endfacet + facet normal -0.152432 -0.934239 0.322431 + outer loop + vertex -514.898 73.248 47.1998 + vertex -511.897 73.5888 49.6057 + vertex -520.637 76.6014 54.2029 + endloop + endfacet + facet normal -0.163147 -0.938353 0.304757 + outer loop + vertex -512.703 74.9968 53.5096 + vertex -520.637 76.6014 54.2029 + vertex -511.897 73.5888 49.6057 + endloop + endfacet + facet normal -0.147945 -0.939689 0.308377 + outer loop + vertex -508.194 73.3172 50.5549 + vertex -512.703 74.9968 53.5096 + vertex -511.897 73.5888 49.6057 + endloop + endfacet + facet normal -0.151123 -0.934511 0.32226 + outer loop + vertex -508.194 73.3172 50.5549 + vertex -511.897 73.5888 49.6057 + vertex -506.935 71.8107 46.7763 + endloop + endfacet + facet normal -0.15912 -0.942758 0.293068 + outer loop + vertex -509.403 74.8796 54.9243 + vertex -512.703 74.9968 53.5096 + vertex -508.194 73.3172 50.5549 + endloop + endfacet + facet normal -0.141512 -0.943907 0.298352 + outer loop + vertex -505.744 73.213 51.387 + vertex -509.403 74.8796 54.9243 + vertex -508.194 73.3172 50.5549 + endloop + endfacet + facet normal -0.147292 -0.937186 0.316208 + outer loop + vertex -505.744 73.213 51.387 + vertex -508.194 73.3172 50.5549 + vertex -504.502 71.6734 47.4024 + endloop + endfacet + facet normal -0.1272 -0.937899 0.322748 + outer loop + vertex -503.211 71.7301 48.0765 + vertex -505.744 73.213 51.387 + vertex -504.502 71.6734 47.4024 + endloop + endfacet + facet normal -0.14229 -0.939408 0.311874 + outer loop + vertex -504.566 73.3393 52.3054 + vertex -505.744 73.213 51.387 + vertex -503.211 71.7301 48.0765 + endloop + endfacet + facet normal -0.127967 -0.947033 0.294539 + outer loop + vertex -504.566 73.3393 52.3054 + vertex -506.804 74.7503 55.8697 + vertex -505.744 73.213 51.387 + endloop + endfacet + facet normal -0.140384 -0.947599 0.286965 + outer loop + vertex -505.623 74.8421 56.7508 + vertex -506.804 74.7503 55.8697 + vertex -504.566 73.3393 52.3054 + endloop + endfacet + facet normal -0.126213 -0.954912 0.268724 + outer loop + vertex -505.623 74.8421 56.7508 + vertex -507.492 76.1663 60.578 + vertex -506.804 74.7503 55.8697 + endloop + endfacet + facet normal -0.151481 -0.952471 0.264296 + outer loop + vertex -507.492 76.1663 60.578 + vertex -510.39 76.4681 60.0046 + vertex -506.804 74.7503 55.8697 + endloop + endfacet + facet normal -0.14534 -0.951991 0.269423 + outer loop + vertex -506.804 74.7503 55.8697 + vertex -510.39 76.4681 60.0046 + vertex -509.403 74.8796 54.9243 + endloop + endfacet + facet normal -0.163077 -0.950239 0.265428 + outer loop + vertex -510.39 76.4681 60.0046 + vertex -514.988 76.8094 58.4018 + vertex -509.403 74.8796 54.9243 + endloop + endfacet + facet normal -0.158778 -0.954566 0.252175 + outer loop + vertex -510.39 76.4681 60.0046 + vertex -516.014 78.7157 64.9719 + vertex -514.988 76.8094 58.4018 + endloop + endfacet + facet normal -0.181527 -0.951658 0.247779 + outer loop + vertex -516.014 78.7157 64.9719 + vertex -523.393 79.6705 63.233 + vertex -514.988 76.8094 58.4018 + endloop + endfacet + facet normal -0.166745 -0.947942 0.271296 + outer loop + vertex -523.393 79.6705 63.233 + vertex -520.637 76.6014 54.2029 + vertex -514.988 76.8094 58.4018 + endloop + endfacet + facet normal -0.201501 -0.944484 0.259512 + outer loop + vertex -523.393 79.6705 63.233 + vertex -533.26 81.3509 61.6877 + vertex -520.637 76.6014 54.2029 + endloop + endfacet + facet normal -0.195037 -0.943043 0.269499 + outer loop + vertex -520.637 76.6014 54.2029 + vertex -533.26 81.3509 61.6877 + vertex -533.111 79.0739 53.8271 + endloop + endfacet + facet normal -0.193936 -0.931828 0.306734 + outer loop + vertex -520.637 76.6014 54.2029 + vertex -533.111 79.0739 53.8271 + vertex -523.207 75.0335 47.8145 + endloop + endfacet + facet normal -0.223595 -0.937313 0.2673 + outer loop + vertex -533.26 81.3509 61.6877 + vertex -544.935 83.9563 61.0574 + vertex -533.111 79.0739 53.8271 + endloop + endfacet + facet normal -0.222793 -0.937159 0.268508 + outer loop + vertex -533.111 79.0739 53.8271 + vertex -544.935 83.9563 61.0574 + vertex -544.912 81.7361 53.3273 + endloop + endfacet + facet normal -0.222073 -0.928513 0.297569 + outer loop + vertex -533.111 79.0739 53.8271 + vertex -544.912 81.7361 53.3273 + vertex -533.511 77.0793 47.3054 + endloop + endfacet + facet normal -0.224635 -0.929257 0.293294 + outer loop + vertex -533.511 77.0793 47.3054 + vertex -544.912 81.7361 53.3273 + vertex -545.462 79.7832 46.7191 + endloop + endfacet + facet normal -0.248152 -0.923202 0.293461 + outer loop + vertex -544.912 81.7361 53.3273 + vertex -557.445 84.9653 52.8883 + vertex -545.462 79.7832 46.7191 + endloop + endfacet + facet normal -0.249271 -0.923507 0.291546 + outer loop + vertex -545.462 79.7832 46.7191 + vertex -557.445 84.9653 52.8883 + vertex -558.742 83.1847 46.1387 + endloop + endfacet + facet normal -0.247927 -0.912471 0.325467 + outer loop + vertex -545.462 79.7832 46.7191 + vertex -558.742 83.1847 46.1387 + vertex -548.126 78.7619 41.8258 + endloop + endfacet + facet normal -0.226838 -0.921302 0.315827 + outer loop + vertex -533.934 75.3626 42.1029 + vertex -545.462 79.7832 46.7191 + vertex -548.126 78.7619 41.8258 + endloop + endfacet + facet normal -0.251736 -0.914132 0.317793 + outer loop + vertex -548.126 78.7619 41.8258 + vertex -558.742 83.1847 46.1387 + vertex -561.474 82.2221 41.2058 + endloop + endfacet + facet normal -0.270666 -0.905576 0.326606 + outer loop + vertex -558.742 83.1847 46.1387 + vertex -572.861 86.943 44.8584 + vertex -561.474 82.2221 41.2058 + endloop + endfacet + facet normal -0.270912 -0.905715 0.326017 + outer loop + vertex -561.474 82.2221 41.2058 + vertex -572.861 86.943 44.8584 + vertex -573.735 85.501 40.1263 + endloop + endfacet + facet normal -0.287131 -0.900225 0.327338 + outer loop + vertex -573.735 85.501 40.1263 + vertex -572.861 86.943 44.8584 + vertex -581.367 88.6279 42.0315 + endloop + endfacet + facet normal -0.285664 -0.899173 0.331488 + outer loop + vertex -583.572 88.2894 39.2125 + vertex -573.735 85.501 40.1263 + vertex -581.367 88.6279 42.0315 + endloop + endfacet + facet normal -0.295863 -0.89315 0.338745 + outer loop + vertex -581.367 88.6279 42.0315 + vertex -589.524 90.9176 40.9441 + vertex -583.572 88.2894 39.2125 + endloop + endfacet + facet normal -0.295623 -0.893002 0.339345 + outer loop + vertex -583.572 88.2894 39.2125 + vertex -589.524 90.9176 40.9441 + vertex -591.768 90.6619 38.316 + endloop + endfacet + facet normal -0.295547 -0.88534 0.358923 + outer loop + vertex -583.572 88.2894 39.2125 + vertex -591.768 90.6619 38.316 + vertex -586.75 88.7858 37.8205 + endloop + endfacet + facet normal -0.289022 -0.89464 0.340713 + outer loop + vertex -586.75 88.7858 37.8205 + vertex -579.818 86.7187 38.2727 + vertex -583.572 88.2894 39.2125 + endloop + endfacet + facet normal -0.290497 -0.908222 0.301238 + outer loop + vertex -579.818 86.7187 38.2727 + vertex -586.75 88.7858 37.8205 + vertex -587.729 88.8735 37.1406 + endloop + endfacet + facet normal -0.295881 -0.903667 0.309581 + outer loop + vertex -586.75 88.7858 37.8205 + vertex -591.631 90.1917 37.259 + vertex -587.729 88.8735 37.1406 + endloop + endfacet + facet normal -0.296217 -0.886335 0.355903 + outer loop + vertex -591.631 90.1917 37.259 + vertex -586.75 88.7858 37.8205 + vertex -591.768 90.6619 38.316 + endloop + endfacet + facet normal -0.301988 -0.884935 0.354533 + outer loop + vertex -595.666 91.5508 37.215 + vertex -591.631 90.1917 37.259 + vertex -591.768 90.6619 38.316 + endloop + endfacet + facet normal -0.304035 -0.87947 0.36619 + outer loop + vertex -591.768 90.6619 38.316 + vertex -598.493 92.8845 38.071 + vertex -595.666 91.5508 37.215 + endloop + endfacet + facet normal -0.309806 -0.882994 0.35262 + outer loop + vertex -599.729 92.8712 36.9516 + vertex -595.666 91.5508 37.215 + vertex -598.493 92.8845 38.071 + endloop + endfacet + facet normal -0.312697 -0.880703 0.355786 + outer loop + vertex -598.493 92.8845 38.071 + vertex -603.742 94.5844 37.6647 + vertex -599.729 92.8712 36.9516 + endloop + endfacet + facet normal -0.311594 -0.879624 0.359402 + outer loop + vertex -603.111 93.7737 36.228 + vertex -599.729 92.8712 36.9516 + vertex -603.742 94.5844 37.6647 + endloop + endfacet + facet normal -0.317902 -0.878705 0.356112 + outer loop + vertex -607.163 95.36 36.5254 + vertex -603.111 93.7737 36.228 + vertex -603.742 94.5844 37.6647 + endloop + endfacet + facet normal -0.316309 -0.882127 0.348999 + outer loop + vertex -603.742 94.5844 37.6647 + vertex -607.555 96.0062 37.8028 + vertex -607.163 95.36 36.5254 + endloop + endfacet + facet normal -0.316015 -0.882185 0.349118 + outer loop + vertex -611.172 96.652 36.1614 + vertex -607.163 95.36 36.5254 + vertex -607.555 96.0062 37.8028 + endloop + endfacet + facet normal -0.316319 -0.881742 0.349963 + outer loop + vertex -607.555 96.0062 37.8028 + vertex -608.837 96.5634 38.0487 + vertex -611.172 96.652 36.1614 + endloop + endfacet + facet normal -0.325815 -0.87334 0.362108 + outer loop + vertex -608.837 96.5634 38.0487 + vertex -609.355 96.6784 37.8598 + vertex -611.172 96.652 36.1614 + endloop + endfacet + facet normal -0.505055 -0.664623 0.550632 + outer loop + vertex -609.355 96.6784 37.8598 + vertex -609.689 96.6854 37.5618 + vertex -611.172 96.652 36.1614 + endloop + endfacet + facet normal -0.306355 -0.886998 0.345516 + outer loop + vertex -609.392 96.8695 38.2974 + vertex -611.172 96.652 36.1614 + vertex -609.689 96.6854 37.5618 + endloop + endfacet + facet normal -0.329901 -0.877028 0.349265 + outer loop + vertex -609.355 96.6784 37.8598 + vertex -608.692 96.9442 39.1531 + vertex -609.689 96.6854 37.5618 + endloop + endfacet + facet normal -0.357096 -0.861873 0.360079 + outer loop + vertex -608.182 96.9931 39.7762 + vertex -608.692 96.9442 39.1531 + vertex -609.355 96.6784 37.8598 + endloop + endfacet + facet normal -0.323914 -0.884901 0.334708 + outer loop + vertex -608.182 96.9931 39.7762 + vertex -607.421 97.5895 42.0893 + vertex -608.692 96.9442 39.1531 + endloop + endfacet + facet normal -0.423335 -0.828992 0.365459 + outer loop + vertex -608.692 96.9442 39.1531 + vertex -607.421 97.5895 42.0893 + vertex -607.931 97.4043 41.0782 + endloop + endfacet + facet normal -0.317852 -0.886074 0.337405 + outer loop + vertex -607.931 97.4043 41.0782 + vertex -609.392 96.8695 38.2974 + vertex -608.692 96.9442 39.1531 + endloop + endfacet + facet normal -0.385947 -0.846957 0.365661 + outer loop + vertex -609.392 96.8695 38.2974 + vertex -607.931 97.4043 41.0782 + vertex -608.546 97.2787 40.1385 + endloop + endfacet + facet normal -0.383764 -0.855801 0.346887 + outer loop + vertex -606.996 97.7246 42.8932 + vertex -607.421 97.5895 42.0893 + vertex -608.182 96.9931 39.7762 + endloop + endfacet + facet normal -0.320503 -0.887788 0.330319 + outer loop + vertex -607.426 96.826 40.0603 + vertex -606.996 97.7246 42.8932 + vertex -608.182 96.9931 39.7762 + endloop + endfacet + facet normal -0.323685 -0.882156 0.342096 + outer loop + vertex -607.426 96.826 40.0603 + vertex -608.182 96.9931 39.7762 + vertex -608.837 96.5634 38.0487 + endloop + endfacet + facet normal -0.336499 -0.881666 0.330808 + outer loop + vertex -606.205 97.6047 43.378 + vertex -606.996 97.7246 42.8932 + vertex -607.426 96.826 40.0603 + endloop + endfacet + facet normal -0.320538 -0.88912 0.326682 + outer loop + vertex -605.582 96.1742 40.0961 + vertex -606.205 97.6047 43.378 + vertex -607.426 96.826 40.0603 + endloop + endfacet + facet normal -0.319244 -0.884749 0.339562 + outer loop + vertex -605.582 96.1742 40.0961 + vertex -607.426 96.826 40.0603 + vertex -607.555 96.0062 37.8028 + endloop + endfacet + facet normal -0.323308 -0.888421 0.325852 + outer loop + vertex -604.33 96.9869 43.554 + vertex -606.205 97.6047 43.378 + vertex -605.582 96.1742 40.0961 + endloop + endfacet + facet normal -0.317219 -0.891181 0.324296 + outer loop + vertex -602.056 94.9267 40.117 + vertex -604.33 96.9869 43.554 + vertex -605.582 96.1742 40.0961 + endloop + endfacet + facet normal -0.31539 -0.885736 0.340589 + outer loop + vertex -602.056 94.9267 40.117 + vertex -605.582 96.1742 40.0961 + vertex -603.742 94.5844 37.6647 + endloop + endfacet + facet normal -0.315578 -0.891335 0.325474 + outer loop + vertex -600.704 95.7191 43.5979 + vertex -604.33 96.9869 43.554 + vertex -602.056 94.9267 40.117 + endloop + endfacet + facet normal -0.31179 -0.893059 0.324396 + outer loop + vertex -596.645 93.1248 40.3565 + vertex -600.704 95.7191 43.5979 + vertex -602.056 94.9267 40.117 + endloop + endfacet + facet normal -0.310368 -0.88618 0.344031 + outer loop + vertex -596.645 93.1248 40.3565 + vertex -602.056 94.9267 40.117 + vertex -598.493 92.8845 38.071 + endloop + endfacet + facet normal -0.309629 -0.892877 0.326957 + outer loop + vertex -595.151 93.8819 43.8388 + vertex -600.704 95.7191 43.5979 + vertex -596.645 93.1248 40.3565 + endloop + endfacet + facet normal -0.304331 -0.89533 0.325218 + outer loop + vertex -589.524 90.9176 40.9441 + vertex -595.151 93.8819 43.8388 + vertex -596.645 93.1248 40.3565 + endloop + endfacet + facet normal -0.305123 -0.895541 0.323893 + outer loop + vertex -587.937 91.7174 44.6502 + vertex -595.151 93.8819 43.8388 + vertex -589.524 90.9176 40.9441 + endloop + endfacet + facet normal -0.305029 -0.900938 0.308656 + outer loop + vertex -595.151 93.8819 43.8388 + vertex -587.937 91.7174 44.6502 + vertex -593.444 94.7443 48.0433 + endloop + endfacet + facet normal -0.308837 -0.899228 0.309852 + outer loop + vertex -593.444 94.7443 48.0433 + vertex -599.052 96.5955 47.826 + vertex -595.151 93.8819 43.8388 + endloop + endfacet + facet normal -0.30998 -0.904781 0.292034 + outer loop + vertex -593.444 94.7443 48.0433 + vertex -596.724 96.9444 51.3782 + vertex -599.052 96.5955 47.826 + endloop + endfacet + facet normal -0.306362 -0.906713 0.289852 + outer loop + vertex -596.724 96.9444 51.3782 + vertex -600.048 98.6269 53.1281 + vertex -599.052 96.5955 47.826 + endloop + endfacet + facet normal -0.316599 -0.90412 0.286936 + outer loop + vertex -599.052 96.5955 47.826 + vertex -600.048 98.6269 53.1281 + vertex -602.844 98.0095 48.0975 + endloop + endfacet + facet normal -0.312896 -0.898316 0.308423 + outer loop + vertex -599.052 96.5955 47.826 + vertex -602.844 98.0095 48.0975 + vertex -600.704 95.7191 43.5979 + endloop + endfacet + facet normal -0.320148 -0.902311 0.288687 + outer loop + vertex -600.048 98.6269 53.1281 + vertex -603.155 99.8535 53.5159 + vertex -602.844 98.0095 48.0975 + endloop + endfacet + facet normal -0.326919 -0.900231 0.28759 + outer loop + vertex -602.844 98.0095 48.0975 + vertex -603.155 99.8535 53.5159 + vertex -605.046 98.716 47.8056 + endloop + endfacet + facet normal -0.327396 -0.893245 0.3081 + outer loop + vertex -602.844 98.0095 48.0975 + vertex -605.046 98.716 47.8056 + vertex -604.33 96.9869 43.554 + endloop + endfacet + facet normal -0.366593 -0.881691 0.297036 + outer loop + vertex -603.155 99.8535 53.5159 + vertex -604.662 99.8747 51.7188 + vertex -605.046 98.716 47.8056 + endloop + endfacet + facet normal -0.345139 -0.890173 0.297442 + outer loop + vertex -605.046 98.716 47.8056 + vertex -604.662 99.8747 51.7188 + vertex -605.912 98.7405 46.8743 + endloop + endfacet + facet normal -0.363855 -0.876504 0.315201 + outer loop + vertex -605.046 98.716 47.8056 + vertex -605.912 98.7405 46.8743 + vertex -606.205 97.6047 43.378 + endloop + endfacet + facet normal -0.948786 -0.147589 0.279324 + outer loop + vertex -604.662 99.8747 51.7188 + vertex -605.268 99.3765 49.3992 + vertex -605.912 98.7405 46.8743 + endloop + endfacet + facet normal -0.641357 -0.689139 0.337266 + outer loop + vertex -605.912 98.7405 46.8743 + vertex -605.268 99.3765 49.3992 + vertex -606.214 98.4897 45.7872 + endloop + endfacet + facet normal -0.925347 -0.22083 0.308166 + outer loop + vertex -605.912 98.7405 46.8743 + vertex -606.214 98.4897 45.7872 + vertex -606.996 97.7246 42.8932 + endloop + endfacet + facet normal -0.714891 0.698277 0.0366066 + outer loop + vertex -605.268 99.3765 49.3992 + vertex -604.662 99.8747 51.7188 + vertex -604.199 100.26 53.4201 + endloop + endfacet + facet normal 0.34526 0.893253 -0.287912 + outer loop + vertex -604.199 100.26 53.4201 + vertex -605.3 99.1155 48.5514 + vertex -605.268 99.3765 49.3992 + endloop + endfacet + facet normal -0.340265 -0.899296 0.274749 + outer loop + vertex -604.662 99.8747 51.7188 + vertex -603.155 99.8535 53.5159 + vertex -602.866 101.301 58.6114 + endloop + endfacet + facet normal -0.34642 -0.897032 0.274456 + outer loop + vertex -599.436 100.783 61.2497 + vertex -602.866 101.301 58.6114 + vertex -603.155 99.8535 53.5159 + endloop + endfacet + facet normal -0.330863 -0.909467 0.251791 + outer loop + vertex -599.436 100.783 61.2497 + vertex -601.131 103.175 67.6616 + vertex -602.866 101.301 58.6114 + endloop + endfacet + facet normal -0.345236 -0.905557 0.246533 + outer loop + vertex -598.324 102.899 70.5773 + vertex -601.131 103.175 67.6616 + vertex -599.436 100.783 61.2497 + endloop + endfacet + facet normal -0.317866 -0.915778 0.245586 + outer loop + vertex -598.324 102.899 70.5773 + vertex -599.436 100.783 61.2497 + vertex -591.908 99.8156 67.385 + endloop + endfacet + facet normal -0.328853 -0.917213 0.22489 + outer loop + vertex -595.449 103.821 78.5444 + vertex -598.324 102.899 70.5773 + vertex -591.908 99.8156 67.385 + endloop + endfacet + facet normal -0.312271 -0.921323 0.231627 + outer loop + vertex -591.908 99.8156 67.385 + vertex -588.279 100.556 75.2232 + vertex -595.449 103.821 78.5444 + endloop + endfacet + facet normal -0.322476 -0.922759 0.21101 + outer loop + vertex -588.279 100.556 75.2232 + vertex -588.935 102.609 83.1977 + vertex -595.449 103.821 78.5444 + endloop + endfacet + facet normal -0.319317 -0.924985 0.206009 + outer loop + vertex -595.445 106.139 88.9564 + vertex -595.449 103.821 78.5444 + vertex -588.935 102.609 83.1977 + endloop + endfacet + facet normal -0.330842 -0.923884 0.192305 + outer loop + vertex -588.935 102.609 83.1977 + vertex -589.172 104.615 92.4261 + vertex -595.445 106.139 88.9564 + endloop + endfacet + facet normal -0.327758 -0.926342 0.18565 + outer loop + vertex -595.511 108.007 98.1599 + vertex -595.445 106.139 88.9564 + vertex -589.172 104.615 92.4261 + endloop + endfacet + facet normal -0.338677 -0.924912 0.172732 + outer loop + vertex -589.172 104.615 92.4261 + vertex -589.558 106.705 102.86 + vertex -595.511 108.007 98.1599 + endloop + endfacet + facet normal -0.33585 -0.926692 0.168659 + outer loop + vertex -596.017 109.637 106.112 + vertex -595.511 108.007 98.1599 + vertex -589.558 106.705 102.86 + endloop + endfacet + facet normal -0.345215 -0.926481 0.149866 + outer loop + vertex -593.912 110.086 113.734 + vertex -596.017 109.637 106.112 + vertex -589.558 106.705 102.86 + endloop + endfacet + facet normal -0.331215 -0.930451 0.156706 + outer loop + vertex -589.558 106.705 102.86 + vertex -586.727 106.951 110.304 + vertex -593.912 110.086 113.734 + endloop + endfacet + facet normal -0.340018 -0.930229 0.138062 + outer loop + vertex -586.727 106.951 110.304 + vertex -587.946 108.631 118.627 + vertex -593.912 110.086 113.734 + endloop + endfacet + facet normal -0.336626 -0.932148 0.133354 + outer loop + vertex -594.673 111.873 124.307 + vertex -593.912 110.086 113.734 + vertex -587.946 108.631 118.627 + endloop + endfacet + facet normal -0.349916 -0.929554 0.116134 + outer loop + vertex -587.946 108.631 118.627 + vertex -589.28 110.49 129.48 + vertex -594.673 111.873 124.307 + endloop + endfacet + facet normal -0.346705 -0.931222 0.112341 + outer loop + vertex -595.736 113.256 132.483 + vertex -594.673 111.873 124.307 + vertex -589.28 110.49 129.48 + endloop + endfacet + facet normal -0.357149 -0.929834 0.0886165 + outer loop + vertex -594.516 113.463 139.572 + vertex -595.736 113.256 132.483 + vertex -589.28 110.49 129.48 + endloop + endfacet + facet normal -0.347995 -0.932749 0.094224 + outer loop + vertex -589.28 110.49 129.48 + vertex -587.758 110.905 139.216 + vertex -594.516 113.463 139.572 + endloop + endfacet + facet normal -0.349857 -0.934226 0.0694344 + outer loop + vertex -593.43 113.79 149.447 + vertex -594.516 113.463 139.572 + vertex -587.758 110.905 139.216 + endloop + endfacet + facet normal -0.34245 -0.936601 0.0742101 + outer loop + vertex -587.758 110.905 139.216 + vertex -586.22 110.925 146.559 + vertex -593.43 113.79 149.447 + endloop + endfacet + facet normal -0.350824 -0.935012 0.0517251 + outer loop + vertex -586.22 110.925 146.559 + vertex -588.25 112.218 156.157 + vertex -593.43 113.79 149.447 + endloop + endfacet + facet normal -0.34934 -0.935638 0.0504327 + outer loop + vertex -595.025 114.915 159.263 + vertex -593.43 113.79 149.447 + vertex -588.25 112.218 156.157 + endloop + endfacet + facet normal -0.359569 -0.932767 0.0256236 + outer loop + vertex -593.246 114.451 167.352 + vertex -595.025 114.915 159.263 + vertex -588.25 112.218 156.157 + endloop + endfacet + facet normal -0.341162 -0.939347 0.0351506 + outer loop + vertex -588.25 112.218 156.157 + vertex -586.01 111.693 163.88 + vertex -593.246 114.451 167.352 + endloop + endfacet + facet normal -0.350129 -0.936593 0.0142721 + outer loop + vertex -586.01 111.693 163.88 + vertex -587.237 112.276 172.024 + vertex -593.246 114.451 167.352 + endloop + endfacet + facet normal -0.343303 -0.939215 0.00427253 + outer loop + vertex -593.886 114.733 177.953 + vertex -593.246 114.451 167.352 + vertex -587.237 112.276 172.024 + endloop + endfacet + facet normal -0.353673 -0.935326 -0.00896782 + outer loop + vertex -587.237 112.276 172.024 + vertex -587.867 112.424 181.419 + vertex -593.886 114.733 177.953 + endloop + endfacet + facet normal -0.346744 -0.937688 -0.0225738 + outer loop + vertex -594.458 114.718 187.353 + vertex -593.886 114.733 177.953 + vertex -587.867 112.424 181.419 + endloop + endfacet + facet normal -0.358204 -0.932904 -0.0371532 + outer loop + vertex -587.867 112.424 181.419 + vertex -589.146 112.488 192.146 + vertex -594.458 114.718 187.353 + endloop + endfacet + facet normal -0.351995 -0.934921 -0.0449749 + outer loop + vertex -595.589 114.767 195.187 + vertex -594.458 114.718 187.353 + vertex -589.146 112.488 192.146 + endloop + endfacet + facet normal -0.361436 -0.929857 -0.0687747 + outer loop + vertex -594.593 113.891 201.793 + vertex -595.589 114.767 195.187 + vertex -589.146 112.488 192.146 + endloop + endfacet + facet normal -0.350566 -0.934486 -0.061964 + outer loop + vertex -589.146 112.488 192.146 + vertex -587.96 111.401 201.825 + vertex -594.593 113.891 201.793 + endloop + endfacet + facet normal -0.34975 -0.932655 -0.0884838 + outer loop + vertex -594.099 112.888 210.419 + vertex -594.593 113.891 201.793 + vertex -587.96 111.401 201.825 + endloop + endfacet + facet normal -0.346098 -0.934286 -0.0855938 + outer loop + vertex -587.96 111.401 201.825 + vertex -587.393 110.375 210.733 + vertex -594.099 112.888 210.419 + endloop + endfacet + facet normal -0.344152 -0.932301 -0.111241 + outer loop + vertex -593.657 111.539 220.354 + vertex -594.099 112.888 210.419 + vertex -587.393 110.375 210.733 + endloop + endfacet + facet normal -0.33581 -0.936019 -0.105359 + outer loop + vertex -587.393 110.375 210.733 + vertex -586.375 109.195 217.97 + vertex -593.657 111.539 220.354 + endloop + endfacet + facet normal -0.341809 -0.930914 -0.128704 + outer loop + vertex -586.375 109.195 217.97 + vertex -589.207 108.915 227.514 + vertex -593.657 111.539 220.354 + endloop + endfacet + facet normal -0.339856 -0.931434 -0.130108 + outer loop + vertex -595.899 111.052 229.697 + vertex -593.657 111.539 220.354 + vertex -589.207 108.915 227.514 + endloop + endfacet + facet normal -0.34507 -0.926339 -0.151073 + outer loop + vertex -595.298 109.634 237.022 + vertex -595.899 111.052 229.697 + vertex -589.207 108.915 227.514 + endloop + endfacet + facet normal -0.33689 -0.930228 -0.145538 + outer loop + vertex -589.207 108.915 227.514 + vertex -588.716 107.171 237.528 + vertex -595.298 109.634 237.022 + endloop + endfacet + facet normal -0.334732 -0.92808 -0.163164 + outer loop + vertex -595.113 107.99 245.991 + vertex -595.298 109.634 237.022 + vertex -588.716 107.171 237.528 + endloop + endfacet + facet normal -0.330355 -0.930258 -0.159645 + outer loop + vertex -588.716 107.171 237.528 + vertex -588.421 105.535 246.449 + vertex -595.113 107.99 245.991 + endloop + endfacet + facet normal -0.328948 -0.928641 -0.171523 + outer loop + vertex -594.955 106.099 255.928 + vertex -595.113 107.99 245.991 + vertex -588.421 105.535 246.449 + endloop + endfacet + facet normal -0.321413 -0.932255 -0.166113 + outer loop + vertex -588.421 105.535 246.449 + vertex -587.509 103.956 253.546 + vertex -594.955 106.099 255.928 + endloop + endfacet + facet normal -0.322219 -0.931382 -0.169419 + outer loop + vertex -587.509 103.956 253.546 + vertex -590.655 103.334 262.952 + vertex -594.955 106.099 255.928 + endloop + endfacet + facet normal -0.317288 -0.932443 -0.172855 + outer loop + vertex -597.641 105.289 265.23 + vertex -594.955 106.099 255.928 + vertex -590.655 103.334 262.952 + endloop + endfacet + facet normal -0.316671 -0.933106 -0.170391 + outer loop + vertex -597.53 103.878 272.745 + vertex -597.641 105.289 265.23 + vertex -590.655 103.334 262.952 + endloop + endfacet + facet normal -0.307796 -0.937224 -0.163932 + outer loop + vertex -590.655 103.334 262.952 + vertex -590.548 101.551 272.941 + vertex -597.53 103.878 272.745 + endloop + endfacet + facet normal -0.308264 -0.938116 -0.157836 + outer loop + vertex -598.574 102.593 282.424 + vertex -597.53 103.878 272.745 + vertex -590.548 101.551 272.941 + endloop + endfacet + facet normal -0.297551 -0.94313 -0.148218 + outer loop + vertex -590.548 101.551 272.941 + vertex -590.815 100.282 281.55 + vertex -598.574 102.593 282.424 + endloop + endfacet + facet normal -0.29678 -0.945243 -0.135787 + outer loop + vertex -598.574 102.593 282.424 + vertex -590.815 100.282 281.55 + vertex -598.325 101.569 289.005 + endloop + endfacet + facet normal -0.291094 -0.94694 -0.136266 + outer loop + vertex -598.325 101.569 289.005 + vertex -602.368 102.654 290.107 + vertex -598.574 102.593 282.424 + endloop + endfacet + facet normal -0.294099 -0.945795 -0.137759 + outer loop + vertex -602.368 102.654 290.107 + vertex -603.381 103.181 288.651 + vertex -598.574 102.593 282.424 + endloop + endfacet + facet normal -0.305702 -0.94068 -0.147199 + outer loop + vertex -602.014 103.927 281.041 + vertex -598.574 102.593 282.424 + vertex -603.381 103.181 288.651 + endloop + endfacet + facet normal -0.277083 -0.950147 -0.142987 + outer loop + vertex -604.152 103.345 289.052 + vertex -602.014 103.927 281.041 + vertex -603.381 103.181 288.651 + endloop + endfacet + facet normal -0.262444 -0.958495 -0.111399 + outer loop + vertex -603.381 103.181 288.651 + vertex -605.372 103.109 293.963 + vertex -604.152 103.345 289.052 + endloop + endfacet + facet normal 0.622527 0.758873 0.191237 + outer loop + vertex -605.372 103.109 293.963 + vertex -605.204 103.083 293.519 + vertex -604.152 103.345 289.052 + endloop + endfacet + facet normal 0.785036 0.57946 0.218963 + outer loop + vertex -604.152 103.345 289.052 + vertex -605.204 103.083 293.519 + vertex -604.425 103.213 290.384 + endloop + endfacet + facet normal 0.889272 -0.435699 0.139144 + outer loop + vertex -604.152 103.345 289.052 + vertex -604.425 103.213 290.384 + vertex -603.751 103.506 286.992 + endloop + endfacet + facet normal -0.953226 -0.218815 -0.208519 + outer loop + vertex -604.877 103.076 292.589 + vertex -603.751 103.506 286.992 + vertex -604.425 103.213 290.384 + endloop + endfacet + facet normal -0.212018 -0.970219 -0.117147 + outer loop + vertex -603.751 103.506 286.992 + vertex -604.877 103.076 292.589 + vertex -604.67 103.206 291.145 + endloop + endfacet + facet normal -0.387458 -0.909342 -0.151569 + outer loop + vertex -604.67 103.206 291.145 + vertex -603.701 103.802 285.088 + vertex -603.751 103.506 286.992 + endloop + endfacet + facet normal -0.296026 -0.946691 -0.12706 + outer loop + vertex -605.139 102.999 293.779 + vertex -604.67 103.206 291.145 + vertex -604.877 103.076 292.589 + endloop + endfacet + facet normal 0.600583 0.778284 0.183232 + outer loop + vertex -605.918 102.972 296.444 + vertex -605.139 102.999 293.779 + vertex -604.877 103.076 292.589 + endloop + endfacet + facet normal 0.842302 0.482341 0.240569 + outer loop + vertex -604.877 103.076 292.589 + vertex -606.116 102.99 297.103 + vertex -605.918 102.972 296.444 + endloop + endfacet + facet normal -0.281364 -0.955215 -0.0916481 + outer loop + vertex -605.918 102.972 296.444 + vertex -605.868 103.023 295.765 + vertex -605.139 102.999 293.779 + endloop + endfacet + facet normal -0.319481 -0.942961 -0.0935816 + outer loop + vertex -605.918 102.972 296.444 + vertex -607.166 103.08 299.618 + vertex -605.868 103.023 295.765 + endloop + endfacet + facet normal -0.246582 -0.966687 -0.0686604 + outer loop + vertex -607.166 103.08 299.618 + vertex -607.355 103.161 299.158 + vertex -605.868 103.023 295.765 + endloop + endfacet + facet normal -0.323298 -0.940637 -0.103352 + outer loop + vertex -605.868 103.023 295.765 + vertex -607.355 103.161 299.158 + vertex -606.047 103.162 295.062 + endloop + endfacet + facet normal -0.291762 -0.949768 -0.113208 + outer loop + vertex -605.868 103.023 295.765 + vertex -606.047 103.162 295.062 + vertex -604.67 103.206 291.145 + endloop + endfacet + facet normal -0.340196 -0.931321 -0.130031 + outer loop + vertex -604.67 103.206 291.145 + vertex -606.047 103.162 295.062 + vertex -605.015 103.453 290.276 + endloop + endfacet + facet normal -0.313675 -0.938752 -0.142659 + outer loop + vertex -604.67 103.206 291.145 + vertex -605.015 103.453 290.276 + vertex -603.701 103.802 285.088 + endloop + endfacet + facet normal -0.325147 -0.934438 -0.145273 + outer loop + vertex -604.871 104.242 284.878 + vertex -603.701 103.802 285.088 + vertex -605.015 103.453 290.276 + endloop + endfacet + facet normal -0.3019 -0.942128 -0.145779 + outer loop + vertex -606.162 103.686 291.141 + vertex -604.871 104.242 284.878 + vertex -605.015 103.453 290.276 + endloop + endfacet + facet normal -0.284115 -0.951287 -0.119718 + outer loop + vertex -605.015 103.453 290.276 + vertex -606.925 103.412 295.136 + vertex -606.162 103.686 291.141 + endloop + endfacet + facet normal -0.274752 -0.954231 -0.118131 + outer loop + vertex -606.925 103.412 295.136 + vertex -608.577 103.879 295.201 + vertex -606.162 103.686 291.141 + endloop + endfacet + facet normal -0.293957 -0.94695 -0.129903 + outer loop + vertex -606.162 103.686 291.141 + vertex -608.577 103.879 295.201 + vertex -607.598 104.25 290.284 + endloop + endfacet + facet normal -0.272069 -0.953983 -0.126077 + outer loop + vertex -608.577 103.879 295.201 + vertex -610.876 104.573 294.91 + vertex -607.598 104.25 290.284 + endloop + endfacet + facet normal -0.286439 -0.948302 -0.136657 + outer loop + vertex -607.598 104.25 290.284 + vertex -610.876 104.573 294.91 + vertex -610.097 104.919 290.88 + endloop + endfacet + facet normal -0.289848 -0.94438 -0.155351 + outer loop + vertex -610.097 104.919 290.88 + vertex -607.931 105.303 284.502 + vertex -607.598 104.25 290.284 + endloop + endfacet + facet normal -0.306915 -0.939286 -0.153442 + outer loop + vertex -607.931 105.303 284.502 + vertex -604.871 104.242 284.878 + vertex -607.598 104.25 290.284 + endloop + endfacet + facet normal -0.305327 -0.93816 -0.163191 + outer loop + vertex -604.871 104.242 284.878 + vertex -607.931 105.303 284.502 + vertex -604.146 105.484 276.381 + endloop + endfacet + facet normal -0.334618 -0.927939 -0.164195 + outer loop + vertex -602.816 104.781 277.641 + vertex -604.871 104.242 284.878 + vertex -604.146 105.484 276.381 + endloop + endfacet + facet normal -0.326388 -0.929164 -0.173566 + outer loop + vertex -602.816 104.781 277.641 + vertex -604.146 105.484 276.381 + vertex -601.848 106.068 268.933 + endloop + endfacet + facet normal -0.381148 -0.907518 -0.176455 + outer loop + vertex -602.816 104.781 277.641 + vertex -601.848 106.068 268.933 + vertex -601.818 105.404 272.283 + endloop + endfacet + facet normal -0.354464 -0.918961 -0.172815 + outer loop + vertex -601.818 105.404 272.283 + vertex -602.178 104.752 276.488 + vertex -602.816 104.781 277.641 + endloop + endfacet + facet normal -0.34523 -0.923432 -0.167598 + outer loop + vertex -602.178 104.752 276.488 + vertex -602.854 104.151 281.196 + vertex -602.816 104.781 277.641 + endloop + endfacet + facet normal -0.386078 -0.907549 -0.165224 + outer loop + vertex -603.701 103.802 285.088 + vertex -602.816 104.781 277.641 + vertex -602.854 104.151 281.196 + endloop + endfacet + facet normal -0.28104 -0.946049 -0.16127 + outer loop + vertex -602.854 104.151 281.196 + vertex -602.178 104.752 276.488 + vertex -602.014 103.927 281.041 + endloop + endfacet + facet normal -0.279397 -0.948592 -0.148696 + outer loop + vertex -603.751 103.506 286.992 + vertex -602.854 104.151 281.196 + vertex -602.014 103.927 281.041 + endloop + endfacet + facet normal -0.322141 -0.934131 -0.1537 + outer loop + vertex -602.854 104.151 281.196 + vertex -603.751 103.506 286.992 + vertex -603.701 103.802 285.088 + endloop + endfacet + facet normal -0.27007 -0.949078 -0.162215 + outer loop + vertex -600.795 105.265 271.186 + vertex -602.014 103.927 281.041 + vertex -602.178 104.752 276.488 + endloop + endfacet + facet normal -0.317245 -0.933708 -0.165965 + outer loop + vertex -597.53 103.878 272.745 + vertex -602.014 103.927 281.041 + vertex -600.795 105.265 271.186 + endloop + endfacet + facet normal -0.311161 -0.934746 -0.171551 + outer loop + vertex -602.178 104.752 276.488 + vertex -601.818 105.404 272.283 + vertex -600.795 105.265 271.186 + endloop + endfacet + facet normal -0.315979 -0.932231 -0.176362 + outer loop + vertex -601.818 105.404 272.283 + vertex -601.262 106.012 268.072 + vertex -600.795 105.265 271.186 + endloop + endfacet + facet normal -0.312677 -0.933205 -0.177091 + outer loop + vertex -600.052 106.638 262.639 + vertex -600.795 105.265 271.186 + vertex -601.262 106.012 268.072 + endloop + endfacet + facet normal -0.334205 -0.92497 -0.180935 + outer loop + vertex -601.262 106.012 268.072 + vertex -601.076 106.393 265.783 + vertex -600.052 106.638 262.639 + endloop + endfacet + facet normal -0.343119 -0.921185 -0.183542 + outer loop + vertex -601.076 106.393 265.783 + vertex -600.934 106.722 263.867 + vertex -600.052 106.638 262.639 + endloop + endfacet + facet normal -0.3417 -0.921924 -0.182474 + outer loop + vertex -600.934 106.722 263.867 + vertex -600.677 107.098 261.485 + vertex -600.052 106.638 262.639 + endloop + endfacet + facet normal -0.343827 -0.921402 -0.181113 + outer loop + vertex -600.677 107.098 261.485 + vertex -600.394 107.529 258.755 + vertex -600.052 106.638 262.639 + endloop + endfacet + facet normal -0.351124 -0.918885 -0.179894 + outer loop + vertex -599.141 108.116 253.312 + vertex -600.052 106.638 262.639 + vertex -600.394 107.529 258.755 + endloop + endfacet + facet normal -0.356146 -0.916768 -0.180821 + outer loop + vertex -600.394 107.529 258.755 + vertex -600.283 108.101 255.638 + vertex -599.141 108.116 253.312 + endloop + endfacet + facet normal -0.354913 -0.917365 -0.18022 + outer loop + vertex -600.283 108.101 255.638 + vertex -600.052 108.558 252.858 + vertex -599.141 108.116 253.312 + endloop + endfacet + facet normal -0.357263 -0.917368 -0.175499 + outer loop + vertex -600.052 108.558 252.858 + vertex -599.827 109.008 250.046 + vertex -599.141 108.116 253.312 + endloop + endfacet + facet normal -0.366732 -0.914168 -0.172638 + outer loop + vertex -598.784 109.67 244.322 + vertex -599.141 108.116 253.312 + vertex -599.827 109.008 250.046 + endloop + endfacet + facet normal -0.374793 -0.91069 -0.173704 + outer loop + vertex -599.827 109.008 250.046 + vertex -599.784 109.522 247.259 + vertex -598.784 109.67 244.322 + endloop + endfacet + facet normal -0.372048 -0.91198 -0.172835 + outer loop + vertex -599.784 109.522 247.259 + vertex -599.597 110.004 244.313 + vertex -598.784 109.67 244.322 + endloop + endfacet + facet normal -0.372616 -0.913171 -0.165156 + outer loop + vertex -599.597 110.004 244.313 + vertex -599.466 110.614 240.642 + vertex -598.784 109.67 244.322 + endloop + endfacet + facet normal -0.385331 -0.908517 -0.161607 + outer loop + vertex -598.642 111.177 235.515 + vertex -598.784 109.67 244.322 + vertex -599.466 110.614 240.642 + endloop + endfacet + facet normal -0.402303 -0.900791 -0.163486 + outer loop + vertex -599.466 110.614 240.642 + vertex -599.396 111.199 237.247 + vertex -598.642 111.177 235.515 + endloop + endfacet + facet normal -0.388406 -0.907957 -0.157341 + outer loop + vertex -599.396 111.199 237.247 + vertex -599.354 111.477 235.54 + vertex -598.642 111.177 235.515 + endloop + endfacet + facet normal -0.388625 -0.909054 -0.150304 + outer loop + vertex -599.354 111.477 235.54 + vertex -599.24 111.993 232.124 + vertex -598.642 111.177 235.515 + endloop + endfacet + facet normal -0.399272 -0.904901 -0.147427 + outer loop + vertex -598.278 112.427 226.857 + vertex -598.642 111.177 235.515 + vertex -599.24 111.993 232.124 + endloop + endfacet + facet normal -0.414466 -0.897683 -0.149608 + outer loop + vertex -599.24 111.993 232.124 + vertex -599.159 112.531 228.671 + vertex -598.278 112.427 226.857 + endloop + endfacet + facet normal -0.400669 -0.905076 -0.142484 + outer loop + vertex -599.159 112.531 228.671 + vertex -599.114 112.783 226.942 + vertex -598.278 112.427 226.857 + endloop + endfacet + facet normal -0.400344 -0.906792 -0.132112 + outer loop + vertex -599.114 112.783 226.942 + vertex -598.985 113.222 223.54 + vertex -598.278 112.427 226.857 + endloop + endfacet + facet normal -0.412338 -0.901939 -0.128391 + outer loop + vertex -597.907 113.57 217.637 + vertex -598.278 112.427 226.857 + vertex -598.985 113.222 223.54 + endloop + endfacet + facet normal -0.302246 -0.942085 -0.145339 + outer loop + vertex -599.114 112.783 226.942 + vertex -599.159 112.531 228.671 + vertex -599.572 112.595 229.116 + endloop + endfacet + facet normal -0.235537 -0.96271 -0.133086 + outer loop + vertex -598.985 113.222 223.54 + vertex -599.114 112.783 226.942 + vertex -599.572 112.595 229.116 + endloop + endfacet + facet normal -0.317881 -0.937893 -0.138953 + outer loop + vertex -599.572 112.595 229.116 + vertex -599.441 113.694 221.4 + vertex -598.985 113.222 223.54 + endloop + endfacet + facet normal -0.333335 -0.933149 -0.134614 + outer loop + vertex -598.923 113.736 219.823 + vertex -598.985 113.222 223.54 + vertex -599.441 113.694 221.4 + endloop + endfacet + facet normal -0.296168 -0.947214 -0.122758 + outer loop + vertex -598.949 114.102 217.067 + vertex -598.923 113.736 219.823 + vertex -599.441 113.694 221.4 + endloop + endfacet + facet normal -0.400138 -0.908997 -0.116676 + outer loop + vertex -598.923 113.736 219.823 + vertex -598.949 114.102 217.067 + vertex -597.907 113.57 217.637 + endloop + endfacet + facet normal -0.428182 -0.894173 -0.130828 + outer loop + vertex -598.985 113.222 223.54 + vertex -598.923 113.736 219.823 + vertex -597.907 113.57 217.637 + endloop + endfacet + facet normal -0.353326 -0.925302 -0.137758 + outer loop + vertex -599.572 112.595 229.116 + vertex -601.055 113.313 228.096 + vertex -599.441 113.694 221.4 + endloop + endfacet + facet normal -0.342428 -0.929739 -0.135383 + outer loop + vertex -599.441 113.694 221.4 + vertex -601.055 113.313 228.096 + vertex -600.915 114.423 220.122 + endloop + endfacet + facet normal -0.356883 -0.92679 -0.117029 + outer loop + vertex -599.441 113.694 221.4 + vertex -600.915 114.423 220.122 + vertex -599.305 114.677 213.198 + endloop + endfacet + facet normal -0.344563 -0.931773 -0.114346 + outer loop + vertex -599.305 114.677 213.198 + vertex -600.915 114.423 220.122 + vertex -600.77 115.377 211.907 + endloop + endfacet + facet normal -0.360847 -0.927899 -0.0937713 + outer loop + vertex -599.305 114.677 213.198 + vertex -600.77 115.377 211.907 + vertex -599.126 115.501 204.352 + endloop + endfacet + facet normal -0.352291 -0.931361 -0.0919659 + outer loop + vertex -599.126 115.501 204.352 + vertex -600.77 115.377 211.907 + vertex -600.621 116.146 203.546 + endloop + endfacet + facet normal -0.362693 -0.929204 -0.0709496 + outer loop + vertex -599.126 115.501 204.352 + vertex -600.621 116.146 203.546 + vertex -598.967 116.093 195.793 + endloop + endfacet + facet normal -0.358329 -0.930967 -0.0700064 + outer loop + vertex -598.967 116.093 195.793 + vertex -600.621 116.146 203.546 + vertex -600.52 116.726 195.327 + endloop + endfacet + facet normal -0.364253 -0.930012 -0.0489563 + outer loop + vertex -598.967 116.093 195.793 + vertex -600.52 116.726 195.327 + vertex -598.971 116.503 188.033 + endloop + endfacet + facet normal -0.359492 -0.931919 -0.0478866 + outer loop + vertex -598.971 116.503 188.033 + vertex -600.52 116.726 195.327 + vertex -600.484 117.128 187.224 + endloop + endfacet + facet normal -0.36857 -0.929155 -0.0287658 + outer loop + vertex -598.971 116.503 188.033 + vertex -600.484 117.128 187.224 + vertex -598.96 116.749 179.938 + endloop + endfacet + facet normal -0.357877 -0.933398 -0.0263081 + outer loop + vertex -598.96 116.749 179.938 + vertex -600.484 117.128 187.224 + vertex -600.464 117.35 179.084 + endloop + endfacet + facet normal -0.367624 -0.92995 -0.00673304 + outer loop + vertex -598.96 116.749 179.938 + vertex -600.464 117.35 179.084 + vertex -598.999 116.824 171.692 + endloop + endfacet + facet normal -0.361243 -0.932457 -0.00529082 + outer loop + vertex -598.999 116.824 171.692 + vertex -600.464 117.35 179.084 + vertex -600.453 117.391 171.038 + endloop + endfacet + facet normal -0.368798 -0.929402 0.0141154 + outer loop + vertex -598.999 116.824 171.692 + vertex -600.453 117.391 171.038 + vertex -599.024 116.718 164.026 + endloop + endfacet + facet normal -0.361497 -0.932238 0.0158749 + outer loop + vertex -599.024 116.718 164.026 + vertex -600.453 117.391 171.038 + vertex -600.467 117.26 163.019 + endloop + endfacet + facet normal -0.372118 -0.927577 0.0336025 + outer loop + vertex -599.024 116.718 164.026 + vertex -600.467 117.26 163.019 + vertex -599.012 116.417 155.861 + endloop + endfacet + facet normal -0.357776 -0.933067 0.0371648 + outer loop + vertex -599.012 116.417 155.861 + vertex -600.467 117.26 163.019 + vertex -600.511 116.95 154.817 + endloop + endfacet + facet normal -0.368647 -0.927917 0.0553966 + outer loop + vertex -599.012 116.417 155.861 + vertex -600.511 116.95 154.817 + vertex -599.041 115.918 147.3 + endloop + endfacet + facet normal -0.358981 -0.931554 0.0577857 + outer loop + vertex -599.041 115.918 147.3 + vertex -600.511 116.95 154.817 + vertex -600.568 116.456 146.499 + endloop + endfacet + facet normal -0.366772 -0.927239 0.0755423 + outer loop + vertex -599.041 115.918 147.3 + vertex -600.568 116.456 146.499 + vertex -599.104 115.249 138.794 + endloop + endfacet + facet normal -0.359587 -0.929902 0.0773245 + outer loop + vertex -599.104 115.249 138.794 + vertex -600.568 116.456 146.499 + vertex -600.653 115.808 138.311 + endloop + endfacet + facet normal -0.363935 -0.926549 0.0951733 + outer loop + vertex -599.104 115.249 138.794 + vertex -600.653 115.808 138.311 + vertex -599.244 114.515 131.113 + endloop + endfacet + facet normal -0.287775 -0.952844 0.0962969 + outer loop + vertex -599.104 115.249 138.794 + vertex -599.244 114.515 131.113 + vertex -598.813 114.568 132.92 + endloop + endfacet + facet normal -0.305661 -0.947411 0.0947795 + outer loop + vertex -598.813 114.568 132.92 + vertex -598.71 114.808 135.651 + vertex -599.104 115.249 138.794 + endloop + endfacet + facet normal -0.288399 -0.952517 0.0976603 + outer loop + vertex -598.71 114.808 135.651 + vertex -598.746 115.111 138.506 + vertex -599.104 115.249 138.794 + endloop + endfacet + facet normal -0.300545 -0.95028 0.0814902 + outer loop + vertex -598.746 115.111 138.506 + vertex -598.754 115.364 141.424 + vertex -599.104 115.249 138.794 + endloop + endfacet + facet normal -0.266647 -0.960679 0.0774313 + outer loop + vertex -599.041 115.918 147.3 + vertex -599.104 115.249 138.794 + vertex -598.754 115.364 141.424 + endloop + endfacet + facet normal -0.312208 -0.947133 0.0739271 + outer loop + vertex -598.754 115.364 141.424 + vertex -598.632 115.555 144.38 + vertex -599.041 115.918 147.3 + endloop + endfacet + facet normal -0.304739 -0.949458 0.0752633 + outer loop + vertex -598.632 115.555 144.38 + vertex -598.644 115.79 147.302 + vertex -599.041 115.918 147.3 + endloop + endfacet + facet normal -0.304948 -0.950422 0.060868 + outer loop + vertex -598.644 115.79 147.302 + vertex -598.669 115.984 150.199 + vertex -599.041 115.918 147.3 + endloop + endfacet + facet normal -0.272797 -0.960384 0.0569651 + outer loop + vertex -599.012 116.417 155.861 + vertex -599.041 115.918 147.3 + vertex -598.669 115.984 150.199 + endloop + endfacet + facet normal -0.323524 -0.944752 0.0526929 + outer loop + vertex -598.669 115.984 150.199 + vertex -598.568 116.119 153.244 + vertex -599.012 116.417 155.861 + endloop + endfacet + facet normal -0.309003 -0.949429 0.0556872 + outer loop + vertex -598.568 116.119 153.244 + vertex -598.631 116.309 156.127 + vertex -599.012 116.417 155.861 + endloop + endfacet + facet normal -0.298153 -0.953745 0.0384041 + outer loop + vertex -598.631 116.309 156.127 + vertex -598.646 116.426 158.914 + vertex -599.012 116.417 155.861 + endloop + endfacet + facet normal -0.269835 -0.962269 0.0350339 + outer loop + vertex -599.024 116.718 164.026 + vertex -599.012 116.417 155.861 + vertex -598.646 116.426 158.914 + endloop + endfacet + facet normal -0.420386 -0.90664 0.0357724 + outer loop + vertex -598.646 116.426 158.914 + vertex -598.631 116.309 156.127 + vertex -597.782 115.934 156.61 + endloop + endfacet + facet normal -0.431262 -0.901706 0.030642 + outer loop + vertex -598.55 116.494 162.279 + vertex -598.646 116.426 158.914 + vertex -597.782 115.934 156.61 + endloop + endfacet + facet normal -0.433089 -0.900841 0.0303093 + outer loop + vertex -597.782 115.934 156.61 + vertex -597.745 116.225 165.793 + vertex -598.55 116.494 162.279 + endloop + endfacet + facet normal -0.407402 -0.912946 0.023503 + outer loop + vertex -598.655 116.646 166.367 + vertex -598.55 116.494 162.279 + vertex -597.745 116.225 165.793 + endloop + endfacet + facet normal -0.411093 -0.911443 0.0165539 + outer loop + vertex -598.634 116.677 168.616 + vertex -598.655 116.646 166.367 + vertex -597.745 116.225 165.793 + endloop + endfacet + facet normal -0.434124 -0.900821 0.00760567 + outer loop + vertex -598.555 116.659 171.02 + vertex -598.634 116.677 168.616 + vertex -597.745 116.225 165.793 + endloop + endfacet + facet normal -0.426727 -0.904335 0.00904276 + outer loop + vertex -597.745 116.225 165.793 + vertex -597.586 116.239 174.694 + vertex -598.555 116.659 171.02 + endloop + endfacet + facet normal -0.341806 -0.939761 0.00427653 + outer loop + vertex -598.634 116.677 168.616 + vertex -598.555 116.659 171.02 + vertex -598.999 116.824 171.692 + endloop + endfacet + facet normal -0.343238 -0.939243 0.00320173 + outer loop + vertex -598.555 116.659 171.02 + vertex -598.632 116.701 174.765 + vertex -598.999 116.824 171.692 + endloop + endfacet + facet normal -0.261876 -0.965072 -0.0075629 + outer loop + vertex -598.96 116.749 179.938 + vertex -598.999 116.824 171.692 + vertex -598.632 116.701 174.765 + endloop + endfacet + facet normal -0.27646 -0.960988 -0.00852452 + outer loop + vertex -598.632 116.701 174.765 + vertex -598.565 116.66 177.153 + vertex -598.96 116.749 179.938 + endloop + endfacet + facet normal -0.343053 -0.939131 -0.0186583 + outer loop + vertex -598.565 116.66 177.153 + vertex -598.462 116.572 179.691 + vertex -598.96 116.749 179.938 + endloop + endfacet + facet normal -0.343406 -0.938985 -0.0194723 + outer loop + vertex -598.462 116.572 179.691 + vertex -598.541 116.525 183.359 + vertex -598.96 116.749 179.938 + endloop + endfacet + facet normal -0.27267 -0.961651 -0.0296242 + outer loop + vertex -598.971 116.503 188.033 + vertex -598.96 116.749 179.938 + vertex -598.541 116.525 183.359 + endloop + endfacet + facet normal -0.409459 -0.912097 -0.0205334 + outer loop + vertex -598.541 116.525 183.359 + vertex -598.462 116.572 179.691 + vertex -597.653 116.113 183.922 + endloop + endfacet + facet normal -0.405658 -0.913607 -0.0276335 + outer loop + vertex -598.469 116.41 186.11 + vertex -598.541 116.525 183.359 + vertex -597.653 116.113 183.922 + endloop + endfacet + facet normal -0.299419 -0.953583 -0.0320481 + outer loop + vertex -598.541 116.525 183.359 + vertex -598.469 116.41 186.11 + vertex -598.971 116.503 188.033 + endloop + endfacet + facet normal -0.337982 -0.940181 -0.042747 + outer loop + vertex -598.469 116.41 186.11 + vertex -598.477 116.243 189.833 + vertex -598.971 116.503 188.033 + endloop + endfacet + facet normal -0.436328 -0.898849 -0.041083 + outer loop + vertex -598.477 116.243 189.833 + vertex -598.469 116.41 186.11 + vertex -597.653 116.113 183.922 + endloop + endfacet + facet normal -0.426167 -0.903779 -0.0395588 + outer loop + vertex -597.653 116.113 183.922 + vertex -597.859 115.815 192.955 + vertex -598.477 116.243 189.833 + endloop + endfacet + facet normal -0.424782 -0.905185 -0.0141767 + outer loop + vertex -598.462 116.572 179.691 + vertex -598.565 116.66 177.153 + vertex -597.586 116.239 174.694 + endloop + endfacet + facet normal -0.430726 -0.902351 -0.0154079 + outer loop + vertex -597.586 116.239 174.694 + vertex -597.653 116.113 183.922 + vertex -598.462 116.572 179.691 + endloop + endfacet + facet normal -0.40378 -0.914847 -0.00416227 + outer loop + vertex -598.565 116.66 177.153 + vertex -598.632 116.701 174.765 + vertex -597.586 116.239 174.694 + endloop + endfacet + facet normal -0.403452 -0.914999 0.0016882 + outer loop + vertex -598.632 116.701 174.765 + vertex -598.555 116.659 171.02 + vertex -597.586 116.239 174.694 + endloop + endfacet + facet normal -0.255275 -0.966738 0.0158513 + outer loop + vertex -598.655 116.646 166.367 + vertex -598.634 116.677 168.616 + vertex -598.999 116.824 171.692 + endloop + endfacet + facet normal -0.276919 -0.960787 0.0142523 + outer loop + vertex -598.999 116.824 171.692 + vertex -599.024 116.718 164.026 + vertex -598.655 116.646 166.367 + endloop + endfacet + facet normal -0.346767 -0.937591 0.0259847 + outer loop + vertex -598.55 116.494 162.279 + vertex -598.655 116.646 166.367 + vertex -599.024 116.718 164.026 + endloop + endfacet + facet normal -0.338039 -0.940693 0.0287552 + outer loop + vertex -598.646 116.426 158.914 + vertex -598.55 116.494 162.279 + vertex -599.024 116.718 164.026 + endloop + endfacet + facet normal -0.426877 -0.902923 0.0500594 + outer loop + vertex -598.631 116.309 156.127 + vertex -598.568 116.119 153.244 + vertex -597.782 115.934 156.61 + endloop + endfacet + facet normal -0.421594 -0.905165 0.0541656 + outer loop + vertex -598.568 116.119 153.244 + vertex -598.669 115.984 150.199 + vertex -597.776 115.404 147.465 + endloop + endfacet + facet normal -0.433648 -0.899591 0.0518234 + outer loop + vertex -597.776 115.404 147.465 + vertex -597.782 115.934 156.61 + vertex -598.568 116.119 153.244 + endloop + endfacet + facet normal -0.414511 -0.908249 0.0571322 + outer loop + vertex -598.669 115.984 150.199 + vertex -598.644 115.79 147.302 + vertex -597.776 115.404 147.465 + endloop + endfacet + facet normal -0.416345 -0.906406 0.0713109 + outer loop + vertex -598.644 115.79 147.302 + vertex -598.632 115.555 144.38 + vertex -597.776 115.404 147.465 + endloop + endfacet + facet normal -0.416456 -0.905861 0.0773358 + outer loop + vertex -598.754 115.364 141.424 + vertex -598.746 115.111 138.506 + vertex -598.053 114.806 138.657 + endloop + endfacet + facet normal -0.421453 -0.903691 0.0756327 + outer loop + vertex -598.632 115.555 144.38 + vertex -598.754 115.364 141.424 + vertex -598.053 114.806 138.657 + endloop + endfacet + facet normal -0.427472 -0.90094 0.0746643 + outer loop + vertex -598.053 114.806 138.657 + vertex -597.776 115.404 147.465 + vertex -598.632 115.555 144.38 + endloop + endfacet + facet normal -0.418438 -0.903693 0.0908274 + outer loop + vertex -598.746 115.111 138.506 + vertex -598.71 114.808 135.651 + vertex -598.053 114.806 138.657 + endloop + endfacet + facet normal -0.431792 -0.897088 0.0937506 + outer loop + vertex -598.124 113.939 130.037 + vertex -598.053 114.806 138.657 + vertex -598.71 114.808 135.651 + endloop + endfacet + facet normal -0.424011 -0.900649 0.095114 + outer loop + vertex -598.71 114.808 135.651 + vertex -598.813 114.568 132.92 + vertex -598.124 113.939 130.037 + endloop + endfacet + facet normal -0.40922 -0.906937 0.100019 + outer loop + vertex -598.813 114.568 132.92 + vertex -598.816 114.234 129.883 + vertex -598.124 113.939 130.037 + endloop + endfacet + facet normal -0.411135 -0.904511 0.113259 + outer loop + vertex -598.816 114.234 129.883 + vertex -598.862 113.781 126.097 + vertex -598.124 113.939 130.037 + endloop + endfacet + facet normal -0.416544 -0.901918 0.114168 + outer loop + vertex -598.054 112.743 120.843 + vertex -598.124 113.939 130.037 + vertex -598.862 113.781 126.097 + endloop + endfacet + facet normal -0.416515 -0.901931 0.114175 + outer loop + vertex -598.862 113.781 126.097 + vertex -598.955 113.377 122.565 + vertex -598.054 112.743 120.843 + endloop + endfacet + facet normal -0.397945 -0.908663 0.126379 + outer loop + vertex -598.955 113.377 122.565 + vertex -598.997 113.156 120.841 + vertex -598.054 112.743 120.843 + endloop + endfacet + facet normal -0.397464 -0.907534 0.135665 + outer loop + vertex -598.997 113.156 120.841 + vertex -599.055 112.672 117.439 + vertex -598.054 112.743 120.843 + endloop + endfacet + facet normal -0.402649 -0.905023 0.137138 + outer loop + vertex -598.367 111.547 112.032 + vertex -598.054 112.743 120.843 + vertex -599.055 112.672 117.439 + endloop + endfacet + facet normal -0.414061 -0.900229 0.134688 + outer loop + vertex -599.055 112.672 117.439 + vertex -599.174 112.209 113.976 + vertex -598.367 111.547 112.032 + endloop + endfacet + facet normal -0.396137 -0.906772 0.144361 + outer loop + vertex -599.174 112.209 113.976 + vertex -599.214 111.955 112.27 + vertex -598.367 111.547 112.032 + endloop + endfacet + facet normal -0.393235 -0.906431 0.154107 + outer loop + vertex -599.214 111.955 112.27 + vertex -599.256 111.411 108.965 + vertex -598.367 111.547 112.032 + endloop + endfacet + facet normal -0.401693 -0.902324 0.156379 + outer loop + vertex -598.738 110.197 103.289 + vertex -598.367 111.547 112.032 + vertex -599.256 111.411 108.965 + endloop + endfacet + facet normal -0.41954 -0.894729 0.153124 + outer loop + vertex -599.256 111.411 108.965 + vertex -599.36 110.836 105.322 + vertex -598.738 110.197 103.289 + endloop + endfacet + facet normal -0.389626 -0.905927 0.165794 + outer loop + vertex -599.36 110.836 105.322 + vertex -599.498 110.402 102.625 + vertex -598.738 110.197 103.289 + endloop + endfacet + facet normal -0.393311 -0.903403 0.170795 + outer loop + vertex -599.498 110.402 102.625 + vertex -599.544 109.76 99.1211 + vertex -598.738 110.197 103.289 + endloop + endfacet + facet normal -0.40678 -0.897047 0.172734 + outer loop + vertex -598.963 108.616 94.5472 + vertex -598.738 110.197 103.289 + vertex -599.544 109.76 99.1211 + endloop + endfacet + facet normal -0.39618 -0.901313 0.175147 + outer loop + vertex -599.544 109.76 99.1211 + vertex -599.722 109.355 96.6317 + vertex -598.963 108.616 94.5472 + endloop + endfacet + facet normal -0.373375 -0.90882 0.18611 + outer loop + vertex -599.722 109.355 96.6317 + vertex -599.883 108.931 94.2398 + vertex -598.963 108.616 94.5472 + endloop + endfacet + facet normal -0.374019 -0.90798 0.188898 + outer loop + vertex -599.883 108.931 94.2398 + vertex -599.955 108.204 90.6051 + vertex -598.963 108.616 94.5472 + endloop + endfacet + facet normal -0.388432 -0.90129 0.191825 + outer loop + vertex -599.322 106.885 85.6879 + vertex -598.963 108.616 94.5472 + vertex -599.955 108.204 90.6051 + endloop + endfacet + facet normal -0.382085 -0.903688 0.193285 + outer loop + vertex -599.955 108.204 90.6051 + vertex -600.149 107.759 88.1419 + vertex -599.322 106.885 85.6879 + endloop + endfacet + facet normal -0.362642 -0.909771 0.202008 + outer loop + vertex -600.149 107.759 88.1419 + vertex -600.318 107.302 85.7785 + vertex -599.322 106.885 85.6879 + endloop + endfacet + facet normal -0.362192 -0.909314 0.204852 + outer loop + vertex -600.318 107.302 85.7785 + vertex -600.429 106.503 82.0344 + vertex -599.322 106.885 85.6879 + endloop + endfacet + facet normal -0.387547 -0.897312 0.211279 + outer loop + vertex -600.064 105.127 76.8628 + vertex -599.322 106.885 85.6879 + vertex -600.429 106.503 82.0344 + endloop + endfacet + facet normal -0.398572 -0.892927 0.209335 + outer loop + vertex -600.429 106.503 82.0344 + vertex -600.646 106.034 79.6239 + vertex -600.064 105.127 76.8628 + endloop + endfacet + facet normal -0.370539 -0.902757 0.218472 + outer loop + vertex -600.646 106.034 79.6239 + vertex -600.81 105.55 77.3454 + vertex -600.064 105.127 76.8628 + endloop + endfacet + facet normal -0.366124 -0.902859 0.225386 + outer loop + vertex -600.81 105.55 77.3454 + vertex -601.059 104.608 73.1646 + vertex -600.064 105.127 76.8628 + endloop + endfacet + facet normal -0.30581 -0.924706 0.226714 + outer loop + vertex -601.059 104.608 73.1646 + vertex -600.81 105.55 77.3454 + vertex -601.396 105.177 75.0302 + endloop + endfacet + facet normal -0.284531 -0.930121 0.232202 + outer loop + vertex -601.545 103.786 69.2792 + vertex -601.059 104.608 73.1646 + vertex -601.396 105.177 75.0302 + endloop + endfacet + facet normal -0.389101 -0.89023 0.236834 + outer loop + vertex -601.059 104.608 73.1646 + vertex -601.545 103.786 69.2792 + vertex -601.131 103.175 67.6616 + endloop + endfacet + facet normal -0.36085 -0.899198 0.247447 + outer loop + vertex -601.545 103.786 69.2792 + vertex -602.343 102.475 63.3493 + vertex -601.131 103.175 67.6616 + endloop + endfacet + facet normal -0.307348 -0.919582 0.244759 + outer loop + vertex -602.343 102.475 63.3493 + vertex -601.545 103.786 69.2792 + vertex -602.264 103.579 67.5961 + endloop + endfacet + facet normal -0.256623 -0.941828 0.217035 + outer loop + vertex -600.87 106.802 82.7067 + vertex -601.396 105.177 75.0302 + vertex -600.81 105.55 77.3454 + endloop + endfacet + facet normal -0.338165 -0.915705 0.217093 + outer loop + vertex -600.87 106.802 82.7067 + vertex -602.414 107.24 82.1454 + vertex -601.396 105.177 75.0302 + endloop + endfacet + facet normal -0.327921 -0.918858 0.219473 + outer loop + vertex -601.396 105.177 75.0302 + vertex -602.414 107.24 82.1454 + vertex -603.07 105.59 74.2596 + endloop + endfacet + facet normal -0.333669 -0.912887 0.235166 + outer loop + vertex -601.396 105.177 75.0302 + vertex -603.07 105.59 74.2596 + vertex -602.264 103.579 67.5961 + endloop + endfacet + facet normal -0.275095 -0.932851 0.232617 + outer loop + vertex -601.396 105.177 75.0302 + vertex -602.264 103.579 67.5961 + vertex -601.545 103.786 69.2792 + endloop + endfacet + facet normal -0.32166 -0.916529 0.237719 + outer loop + vertex -602.264 103.579 67.5961 + vertex -603.07 105.59 74.2596 + vertex -604.121 103.822 66.0222 + endloop + endfacet + facet normal -0.333998 -0.90781 0.253629 + outer loop + vertex -602.264 103.579 67.5961 + vertex -604.121 103.822 66.0222 + vertex -603.565 101.523 58.525 + endloop + endfacet + facet normal -0.249977 -0.935964 0.247956 + outer loop + vertex -602.264 103.579 67.5961 + vertex -603.565 101.523 58.525 + vertex -602.343 102.475 63.3493 + endloop + endfacet + facet normal -0.243669 -0.937945 0.246749 + outer loop + vertex -603.168 101.418 58.517 + vertex -602.343 102.475 63.3493 + vertex -603.565 101.523 58.525 + endloop + endfacet + facet normal -0.24241 -0.934298 0.261388 + outer loop + vertex -604.199 100.26 53.4201 + vertex -603.168 101.418 58.517 + vertex -603.565 101.523 58.525 + endloop + endfacet + facet normal -0.422373 -0.861664 0.281311 + outer loop + vertex -603.168 101.418 58.517 + vertex -604.199 100.26 53.4201 + vertex -602.866 101.301 58.6114 + endloop + endfacet + facet normal -0.851896 0.510625 0.116342 + outer loop + vertex -604.662 99.8747 51.7188 + vertex -602.866 101.301 58.6114 + vertex -604.199 100.26 53.4201 + endloop + endfacet + facet normal -0.419221 -0.869343 0.261718 + outer loop + vertex -602.343 102.475 63.3493 + vertex -603.168 101.418 58.517 + vertex -602.866 101.301 58.6114 + endloop + endfacet + facet normal -0.319684 -0.91227 0.256058 + outer loop + vertex -603.565 101.523 58.525 + vertex -604.121 103.822 66.0222 + vertex -605.569 101.822 57.0888 + endloop + endfacet + facet normal -0.331131 -0.902936 0.27397 + outer loop + vertex -603.565 101.523 58.525 + vertex -605.569 101.822 57.0888 + vertex -604.983 99.9432 51.604 + endloop + endfacet + facet normal -0.289175 -0.918711 0.268974 + outer loop + vertex -604.59 99.7241 51.2787 + vertex -603.565 101.523 58.525 + vertex -604.983 99.9432 51.604 + endloop + endfacet + facet normal -0.274679 -0.918003 0.286046 + outer loop + vertex -604.59 99.7241 51.2787 + vertex -604.983 99.9432 51.604 + vertex -605.841 98.76 46.9834 + endloop + endfacet + facet normal -0.216317 -0.93727 0.273371 + outer loop + vertex -605.527 98.828 47.465 + vertex -604.59 99.7241 51.2787 + vertex -605.841 98.76 46.9834 + endloop + endfacet + facet normal -0.252569 -0.921579 0.294789 + outer loop + vertex -605.527 98.828 47.465 + vertex -605.841 98.76 46.9834 + vertex -606.946 97.9889 43.626 + endloop + endfacet + facet normal -0.234867 -0.927877 0.289622 + outer loop + vertex -605.527 98.828 47.465 + vertex -606.946 97.9889 43.626 + vertex -606.497 98.2048 44.6816 + endloop + endfacet + facet normal -0.296781 -0.904767 0.305478 + outer loop + vertex -606.946 97.9889 43.626 + vertex -605.841 98.76 46.9834 + vertex -607.499 97.8953 42.8108 + endloop + endfacet + facet normal -0.351671 -0.872562 0.339063 + outer loop + vertex -606.946 97.9889 43.626 + vertex -607.499 97.8953 42.8108 + vertex -608.546 97.2787 40.1385 + endloop + endfacet + facet normal -0.318821 -0.889462 0.327431 + outer loop + vertex -606.946 97.9889 43.626 + vertex -608.546 97.2787 40.1385 + vertex -607.931 97.4043 41.0782 + endloop + endfacet + facet normal -0.327676 -0.884388 0.332394 + outer loop + vertex -608.546 97.2787 40.1385 + vertex -607.499 97.8953 42.8108 + vertex -609.168 97.2123 39.3484 + endloop + endfacet + facet normal -0.37956 -0.847878 0.370185 + outer loop + vertex -608.546 97.2787 40.1385 + vertex -609.168 97.2123 39.3484 + vertex -609.983 96.8257 37.6276 + endloop + endfacet + facet normal -0.326896 -0.87954 0.345757 + outer loop + vertex -608.546 97.2787 40.1385 + vertex -609.983 96.8257 37.6276 + vertex -609.392 96.8695 38.2974 + endloop + endfacet + facet normal -0.350153 -0.864731 0.360047 + outer loop + vertex -609.983 96.8257 37.6276 + vertex -609.168 97.2123 39.3484 + vertex -610.235 96.8215 37.3726 + endloop + endfacet + facet normal -0.391314 -0.828749 0.40006 + outer loop + vertex -609.983 96.8257 37.6276 + vertex -610.235 96.8215 37.3726 + vertex -610.771 96.6806 36.5555 + endloop + endfacet + facet normal 0.210996 0.935942 -0.281946 + outer loop + vertex -611.172 96.652 36.1614 + vertex -609.983 96.8257 37.6276 + vertex -610.771 96.6806 36.5555 + endloop + endfacet + facet normal -0.33591 -0.851488 0.402657 + outer loop + vertex -610.771 96.6806 36.5555 + vertex -611.268 96.7574 36.3035 + vertex -611.172 96.652 36.1614 + endloop + endfacet + facet normal -0.307829 -0.852484 0.422508 + outer loop + vertex -611.268 96.7574 36.3035 + vertex -612.226 97.192 36.4829 + vertex -611.172 96.652 36.1614 + endloop + endfacet + facet normal -0.331252 -0.867542 0.371003 + outer loop + vertex -614.379 98.0274 36.5141 + vertex -611.172 96.652 36.1614 + vertex -612.226 97.192 36.4829 + endloop + endfacet + facet normal -0.331957 -0.869192 0.366483 + outer loop + vertex -612.226 97.192 36.4829 + vertex -613.722 97.9053 36.8194 + vertex -614.379 98.0274 36.5141 + endloop + endfacet + facet normal -0.333617 -0.866598 0.371091 + outer loop + vertex -613.722 97.9053 36.8194 + vertex -615.919 98.8879 37.1386 + vertex -614.379 98.0274 36.5141 + endloop + endfacet + facet normal -0.337071 -0.868036 0.36455 + outer loop + vertex -617.898 99.6488 37.1208 + vertex -614.379 98.0274 36.5141 + vertex -615.919 98.8879 37.1386 + endloop + endfacet + facet normal -0.337405 -0.868962 0.362026 + outer loop + vertex -615.919 98.8879 37.1386 + vertex -618.698 100.228 37.7654 + vertex -617.898 99.6488 37.1208 + endloop + endfacet + facet normal -0.341544 -0.869334 0.357221 + outer loop + vertex -620.44 100.911 37.7628 + vertex -617.898 99.6488 37.1208 + vertex -618.698 100.228 37.7654 + endloop + endfacet + facet normal -0.342383 -0.871496 0.351097 + outer loop + vertex -618.698 100.228 37.7654 + vertex -621.035 101.385 38.3593 + vertex -620.44 100.911 37.7628 + endloop + endfacet + facet normal -0.34874 -0.871503 0.344764 + outer loop + vertex -622.704 102.085 38.4398 + vertex -620.44 100.911 37.7628 + vertex -621.035 101.385 38.3593 + endloop + endfacet + facet normal -0.349309 -0.872501 0.34165 + outer loop + vertex -622.704 102.085 38.4398 + vertex -621.035 101.385 38.3593 + vertex -623.608 102.943 39.7055 + endloop + endfacet + facet normal -0.355573 -0.871875 0.336753 + outer loop + vertex -626.323 103.881 39.2673 + vertex -622.704 102.085 38.4398 + vertex -623.608 102.943 39.7055 + endloop + endfacet + facet normal -0.355352 -0.875175 0.328318 + outer loop + vertex -623.608 102.943 39.7055 + vertex -627.239 104.747 40.5857 + vertex -626.323 103.881 39.2673 + endloop + endfacet + facet normal -0.358395 -0.874813 0.325967 + outer loop + vertex -629.523 105.483 40.0496 + vertex -626.323 103.881 39.2673 + vertex -627.239 104.747 40.5857 + endloop + endfacet + facet normal -0.358519 -0.874304 0.327194 + outer loop + vertex -627.239 104.747 40.5857 + vertex -630.259 106.204 41.1679 + vertex -629.523 105.483 40.0496 + endloop + endfacet + facet normal -0.36052 -0.874037 0.325706 + outer loop + vertex -631.714 106.528 40.429 + vertex -629.523 105.483 40.0496 + vertex -630.259 106.204 41.1679 + endloop + endfacet + facet normal -0.362351 -0.871506 0.330422 + outer loop + vertex -630.259 106.204 41.1679 + vertex -633.31 107.612 41.5373 + vertex -631.714 106.528 40.429 + endloop + endfacet + facet normal -0.364271 -0.871684 0.327831 + outer loop + vertex -633.275 107.223 40.5416 + vertex -631.714 106.528 40.429 + vertex -633.31 107.612 41.5373 + endloop + endfacet + facet normal -0.369101 -0.869966 0.326992 + outer loop + vertex -635.667 108.436 41.0682 + vertex -633.275 107.223 40.5416 + vertex -633.31 107.612 41.5373 + endloop + endfacet + facet normal -0.369059 -0.870254 0.326273 + outer loop + vertex -633.31 107.612 41.5373 + vertex -636.469 109.242 42.3114 + vertex -635.667 108.436 41.0682 + endloop + endfacet + facet normal -0.369145 -0.870241 0.326209 + outer loop + vertex -638.446 109.871 41.7524 + vertex -635.667 108.436 41.0682 + vertex -636.469 109.242 42.3114 + endloop + endfacet + facet normal -0.370591 -0.865741 0.336386 + outer loop + vertex -636.469 109.242 42.3114 + vertex -639.336 110.677 42.8474 + vertex -638.446 109.871 41.7524 + endloop + endfacet + facet normal -0.373846 -0.865448 0.333525 + outer loop + vertex -640.609 110.956 42.1423 + vertex -638.446 109.871 41.7524 + vertex -639.336 110.677 42.8474 + endloop + endfacet + facet normal -0.377097 -0.861063 0.341128 + outer loop + vertex -639.336 110.677 42.8474 + vertex -642.208 112.082 43.2188 + vertex -640.609 110.956 42.1423 + endloop + endfacet + facet normal -0.38231 -0.861586 0.333929 + outer loop + vertex -642.63 111.939 42.3652 + vertex -640.609 110.956 42.1423 + vertex -642.208 112.082 43.2188 + endloop + endfacet + facet normal -0.387438 -0.858507 0.335944 + outer loop + vertex -642.208 112.082 43.2188 + vertex -645.319 113.572 43.4374 + vertex -642.63 111.939 42.3652 + endloop + endfacet + facet normal -0.394784 -0.860845 0.321079 + outer loop + vertex -644.075 112.55 42.2262 + vertex -642.63 111.939 42.3652 + vertex -645.319 113.572 43.4374 + endloop + endfacet + facet normal -0.391319 -0.861032 0.324798 + outer loop + vertex -648.123 114.705 43.0637 + vertex -644.075 112.55 42.2262 + vertex -645.319 113.572 43.4374 + endloop + endfacet + facet normal -0.390851 -0.852592 0.346875 + outer loop + vertex -645.319 113.572 43.4374 + vertex -649.291 116.228 45.4901 + vertex -648.123 114.705 43.0637 + endloop + endfacet + facet normal -0.382202 -0.854353 0.35214 + outer loop + vertex -650.779 116.188 43.7773 + vertex -648.123 114.705 43.0637 + vertex -649.291 116.228 45.4901 + endloop + endfacet + facet normal -0.38628 -0.851077 0.355607 + outer loop + vertex -652.961 117.015 43.3864 + vertex -650.779 116.188 43.7773 + vertex -649.291 116.228 45.4901 + endloop + endfacet + facet normal -0.397798 -0.834147 0.382041 + outer loop + vertex -649.291 116.228 45.4901 + vertex -654.991 119.25 46.1533 + vertex -652.961 117.015 43.3864 + endloop + endfacet + facet normal -0.404409 -0.833435 0.376616 + outer loop + vertex -654.594 118.177 44.2052 + vertex -652.961 117.015 43.3864 + vertex -654.991 119.25 46.1533 + endloop + endfacet + facet normal -0.412626 -0.830809 0.373492 + outer loop + vertex -657.824 119.837 44.3296 + vertex -654.594 118.177 44.2052 + vertex -654.991 119.25 46.1533 + endloop + endfacet + facet normal -0.416914 -0.824728 0.382108 + outer loop + vertex -654.991 119.25 46.1533 + vertex -660.922 122.345 46.3625 + vertex -657.824 119.837 44.3296 + endloop + endfacet + facet normal -0.396985 -0.821751 0.408813 + outer loop + vertex -660.311 121.176 44.6059 + vertex -657.824 119.837 44.3296 + vertex -660.922 122.345 46.3625 + endloop + endfacet + facet normal -0.410944 -0.818383 0.401714 + outer loop + vertex -661.706 121.935 44.7245 + vertex -660.311 121.176 44.6059 + vertex -660.922 122.345 46.3625 + endloop + endfacet + facet normal -0.426521 -0.807952 0.406563 + outer loop + vertex -664.427 123.531 45.0436 + vertex -661.706 121.935 44.7245 + vertex -660.922 122.345 46.3625 + endloop + endfacet + facet normal -0.428518 -0.800936 0.41818 + outer loop + vertex -660.922 122.345 46.3625 + vertex -666.877 125.882 47.035 + vertex -664.427 123.531 45.0436 + endloop + endfacet + facet normal -0.421128 -0.800396 0.426635 + outer loop + vertex -667.216 125.095 45.2232 + vertex -664.427 123.531 45.0436 + vertex -666.877 125.882 47.035 + endloop + endfacet + facet normal -0.437818 -0.791736 0.425993 + outer loop + vertex -669.168 126.371 45.5893 + vertex -667.216 125.095 45.2232 + vertex -666.877 125.882 47.035 + endloop + endfacet + facet normal -0.479068 -0.821398 0.309515 + outer loop + vertex -667.216 125.095 45.2232 + vertex -669.168 126.371 45.5893 + vertex -668.441 125.611 44.6955 + endloop + endfacet + facet normal -0.468381 -0.823533 0.320018 + outer loop + vertex -669.168 126.371 45.5893 + vertex -670.995 127.374 45.4974 + vertex -668.441 125.611 44.6955 + endloop + endfacet + facet normal -0.446971 -0.772547 0.450985 + outer loop + vertex -670.995 127.374 45.4974 + vertex -669.168 126.371 45.5893 + vertex -672.025 129.02 47.2957 + endloop + endfacet + facet normal -0.463771 -0.76969 0.43874 + outer loop + vertex -673.971 129.277 45.689 + vertex -670.995 127.374 45.4974 + vertex -672.025 129.02 47.2957 + endloop + endfacet + facet normal -0.448368 -0.772838 0.449098 + outer loop + vertex -666.877 125.882 47.035 + vertex -672.025 129.02 47.2957 + vertex -669.168 126.371 45.5893 + endloop + endfacet + facet normal -0.433972 -0.846253 0.309071 + outer loop + vertex -660.311 121.176 44.6059 + vertex -661.706 121.935 44.7245 + vertex -662.192 122.025 44.2905 + endloop + endfacet + facet normal -0.419071 -0.828187 0.372136 + outer loop + vertex -654.991 119.25 46.1533 + vertex -658.482 123.126 50.8488 + vertex -660.922 122.345 46.3625 + endloop + endfacet + facet normal -0.450002 -0.805752 0.385048 + outer loop + vertex -658.482 123.126 50.8488 + vertex -664.354 126.582 51.2165 + vertex -660.922 122.345 46.3625 + endloop + endfacet + facet normal -0.434994 -0.807918 0.397552 + outer loop + vertex -660.922 122.345 46.3625 + vertex -664.354 126.582 51.2165 + vertex -666.877 125.882 47.035 + endloop + endfacet + facet normal -0.471217 -0.778555 0.414495 + outer loop + vertex -664.354 126.582 51.2165 + vertex -669.922 130.043 51.3876 + vertex -666.877 125.882 47.035 + endloop + endfacet + facet normal -0.454351 -0.780949 0.428583 + outer loop + vertex -666.877 125.882 47.035 + vertex -669.922 130.043 51.3876 + vertex -672.025 129.02 47.2957 + endloop + endfacet + facet normal -0.475234 -0.784245 0.398889 + outer loop + vertex -664.354 126.582 51.2165 + vertex -667.704 131.62 57.1312 + vertex -669.922 130.043 51.3876 + endloop + endfacet + facet normal -0.500903 -0.778067 0.379089 + outer loop + vertex -662.202 127.968 56.9066 + vertex -667.704 131.62 57.1312 + vertex -664.354 126.582 51.2165 + endloop + endfacet + facet normal -0.504337 -0.782399 0.365372 + outer loop + vertex -662.202 127.968 56.9066 + vertex -665.578 133.464 64.0159 + vertex -667.704 131.62 57.1312 + endloop + endfacet + facet normal -0.52845 -0.774458 0.347785 + outer loop + vertex -660.391 129.759 63.647 + vertex -665.578 133.464 64.0159 + vertex -662.202 127.968 56.9066 + endloop + endfacet + facet normal -0.532192 -0.778255 0.333301 + outer loop + vertex -660.391 129.759 63.647 + vertex -663.788 135.426 71.4538 + vertex -665.578 133.464 64.0159 + endloop + endfacet + facet normal -0.551749 -0.770519 0.319175 + outer loop + vertex -658.91 131.733 70.9735 + vertex -663.788 135.426 71.4538 + vertex -660.391 129.759 63.647 + endloop + endfacet + facet normal -0.555858 -0.773905 0.303467 + outer loop + vertex -658.91 131.733 70.9735 + vertex -662.448 137.461 79.0999 + vertex -663.788 135.426 71.4538 + endloop + endfacet + facet normal -0.572676 -0.766439 0.290883 + outer loop + vertex -657.735 133.737 78.5643 + vertex -662.448 137.461 79.0999 + vertex -658.91 131.733 70.9735 + endloop + endfacet + facet normal -0.577184 -0.769588 0.273116 + outer loop + vertex -657.735 133.737 78.5643 + vertex -661.475 139.457 86.7799 + vertex -662.448 137.461 79.0999 + endloop + endfacet + facet normal -0.590021 -0.763372 0.262944 + outer loop + vertex -656.839 135.701 86.2767 + vertex -661.475 139.457 86.7799 + vertex -657.735 133.737 78.5643 + endloop + endfacet + facet normal -0.594245 -0.766145 0.244733 + outer loop + vertex -656.839 135.701 86.2767 + vertex -660.766 141.364 94.4685 + vertex -661.475 139.457 86.7799 + endloop + endfacet + facet normal -0.604462 -0.760826 0.236158 + outer loop + vertex -656.179 137.582 94.0249 + vertex -660.766 141.364 94.4685 + vertex -656.839 135.701 86.2767 + endloop + endfacet + facet normal -0.60808 -0.763164 0.218678 + outer loop + vertex -656.179 137.582 94.0249 + vertex -660.25 143.152 102.146 + vertex -660.766 141.364 94.4685 + endloop + endfacet + facet normal -0.615917 -0.758815 0.211768 + outer loop + vertex -655.696 139.344 101.745 + vertex -660.25 143.152 102.146 + vertex -656.179 137.582 94.0249 + endloop + endfacet + facet normal -0.619003 -0.760757 0.195153 + outer loop + vertex -655.696 139.344 101.745 + vertex -659.867 144.801 109.791 + vertex -660.25 143.152 102.146 + endloop + endfacet + facet normal -0.626117 -0.75657 0.188625 + outer loop + vertex -655.337 140.959 109.417 + vertex -659.867 144.801 109.791 + vertex -655.696 139.344 101.745 + endloop + endfacet + facet normal -0.629024 -0.758301 0.171196 + outer loop + vertex -655.337 140.959 109.417 + vertex -659.589 146.296 117.43 + vertex -659.867 144.801 109.791 + endloop + endfacet + facet normal -0.634663 -0.75478 0.165858 + outer loop + vertex -655.064 142.414 117.083 + vertex -659.589 146.296 117.43 + vertex -655.337 140.959 109.417 + endloop + endfacet + facet normal -0.63737 -0.756299 0.147552 + outer loop + vertex -655.064 142.414 117.083 + vertex -659.384 147.625 125.126 + vertex -659.589 146.296 117.43 + endloop + endfacet + facet normal -0.641344 -0.753673 0.143717 + outer loop + vertex -654.849 143.706 124.811 + vertex -659.384 147.625 125.126 + vertex -655.064 142.414 117.083 + endloop + endfacet + facet normal -0.643844 -0.755001 0.12425 + outer loop + vertex -654.849 143.706 124.811 + vertex -659.228 148.776 132.933 + vertex -659.384 147.625 125.126 + endloop + endfacet + facet normal -0.647318 -0.752577 0.120863 + outer loop + vertex -654.685 144.823 132.649 + vertex -659.228 148.776 132.933 + vertex -654.849 143.706 124.811 + endloop + endfacet + facet normal -0.649463 -0.753629 0.101197 + outer loop + vertex -654.685 144.823 132.649 + vertex -659.102 149.731 140.851 + vertex -659.228 148.776 132.933 + endloop + endfacet + facet normal -0.652199 -0.751619 0.0985208 + outer loop + vertex -654.557 145.753 140.593 + vertex -659.102 149.731 140.851 + vertex -654.685 144.823 132.649 + endloop + endfacet + facet normal -0.654069 -0.752417 0.0778617 + outer loop + vertex -654.557 145.753 140.593 + vertex -659.004 150.472 148.834 + vertex -659.102 149.731 140.851 + endloop + endfacet + facet normal -0.65503 -0.751677 0.0769192 + outer loop + vertex -654.452 146.481 148.597 + vertex -659.004 150.472 148.834 + vertex -654.557 145.753 140.593 + endloop + endfacet + facet normal -0.656624 -0.752201 0.0551186 + outer loop + vertex -654.452 146.481 148.597 + vertex -658.923 150.986 156.824 + vertex -659.004 150.472 148.834 + endloop + endfacet + facet normal -0.657024 -0.75188 0.0547258 + outer loop + vertex -654.377 146.998 156.602 + vertex -658.923 150.986 156.824 + vertex -654.452 146.481 148.597 + endloop + endfacet + facet normal -0.658321 -0.752072 0.0316466 + outer loop + vertex -654.377 146.998 156.602 + vertex -658.873 151.278 164.782 + vertex -658.923 150.986 156.824 + endloop + endfacet + facet normal -0.65722 -0.752987 0.0327306 + outer loop + vertex -654.328 147.301 164.574 + vertex -658.873 151.278 164.782 + vertex -654.377 146.998 156.602 + endloop + endfacet + facet normal -0.658158 -0.752824 0.00916936 + outer loop + vertex -654.328 147.301 164.574 + vertex -658.846 151.351 172.705 + vertex -658.873 151.278 164.782 + endloop + endfacet + facet normal -0.657233 -0.75362 0.0100794 + outer loop + vertex -654.314 147.395 172.513 + vertex -658.846 151.351 172.705 + vertex -654.328 147.301 164.574 + endloop + endfacet + facet normal -0.657781 -0.753077 -0.0140968 + outer loop + vertex -654.314 147.395 172.513 + vertex -658.857 151.212 180.615 + vertex -658.846 151.351 172.705 + endloop + endfacet + facet normal -0.655896 -0.754752 -0.0122508 + outer loop + vertex -654.33 147.281 180.444 + vertex -658.857 151.212 180.615 + vertex -654.314 147.395 172.513 + endloop + endfacet + facet normal -0.656031 -0.753851 -0.0365035 + outer loop + vertex -654.33 147.281 180.444 + vertex -658.896 150.862 188.539 + vertex -658.857 151.212 180.615 + endloop + endfacet + facet normal -0.654065 -0.755646 -0.0346008 + outer loop + vertex -654.378 146.959 188.39 + vertex -658.896 150.862 188.539 + vertex -654.33 147.281 180.444 + endloop + endfacet + facet normal -0.610501 -0.791206 -0.035782 + outer loop + vertex -649.461 143.531 180.287 + vertex -654.378 146.959 188.39 + vertex -654.33 147.281 180.444 + endloop + endfacet + facet normal -0.610362 -0.792039 -0.0115018 + outer loop + vertex -649.461 143.531 180.287 + vertex -654.33 147.281 180.444 + vertex -649.442 143.632 172.335 + endloop + endfacet + facet normal -0.572104 -0.820097 -0.011764 + outer loop + vertex -644.26 140.02 172.138 + vertex -649.461 143.531 180.287 + vertex -649.442 143.632 172.335 + endloop + endfacet + facet normal -0.571488 -0.82052 0.0121896 + outer loop + vertex -644.26 140.02 172.138 + vertex -649.442 143.632 172.335 + vertex -644.277 139.913 164.157 + endloop + endfacet + facet normal -0.539016 -0.842204 0.0124142 + outer loop + vertex -638.801 136.405 163.925 + vertex -644.26 140.02 172.138 + vertex -644.277 139.913 164.157 + endloop + endfacet + facet normal -0.538028 -0.842184 0.0353839 + outer loop + vertex -638.801 136.405 163.925 + vertex -644.277 139.913 164.157 + vertex -638.847 136.097 155.889 + endloop + endfacet + facet normal -0.508477 -0.860327 0.0359105 + outer loop + vertex -633.09 132.684 155.646 + vertex -638.801 136.405 163.925 + vertex -638.847 136.097 155.889 + endloop + endfacet + facet normal -0.507264 -0.859846 0.0578547 + outer loop + vertex -633.09 132.684 155.646 + vertex -638.847 136.097 155.889 + vertex -633.164 132.183 147.552 + endloop + endfacet + facet normal -0.477947 -0.876431 0.0586132 + outer loop + vertex -627.1 128.859 147.299 + vertex -633.09 132.684 155.646 + vertex -633.164 132.183 147.552 + endloop + endfacet + facet normal -0.476597 -0.875542 0.0792519 + outer loop + vertex -627.1 128.859 147.299 + vertex -633.164 132.183 147.552 + vertex -627.198 128.178 139.181 + endloop + endfacet + facet normal -0.448975 -0.889945 0.0801279 + outer loop + vertex -620.864 124.956 138.888 + vertex -627.1 128.859 147.299 + vertex -627.198 128.178 139.181 + endloop + endfacet + facet normal -0.447473 -0.88875 0.0994524 + outer loop + vertex -620.864 124.956 138.888 + vertex -627.198 128.178 139.181 + vertex -620.981 124.11 130.801 + endloop + endfacet + facet normal -0.42385 -0.900161 0.100304 + outer loop + vertex -614.591 121.061 130.448 + vertex -620.864 124.956 138.888 + vertex -620.981 124.11 130.801 + endloop + endfacet + facet normal -0.422155 -0.898728 0.118626 + outer loop + vertex -614.591 121.061 130.448 + vertex -620.981 124.11 130.801 + vertex -614.727 120.068 122.433 + endloop + endfacet + facet normal -0.403762 -0.907046 0.119343 + outer loop + vertex -608.793 117.379 122.076 + vertex -614.591 121.061 130.448 + vertex -614.727 120.068 122.433 + endloop + endfacet + facet normal -0.40195 -0.905374 0.136871 + outer loop + vertex -608.793 117.379 122.076 + vertex -614.727 120.068 122.433 + vertex -608.96 116.252 114.126 + endloop + endfacet + facet normal -0.387644 -0.911506 0.137438 + outer loop + vertex -604.182 114.19 113.935 + vertex -608.793 117.379 122.076 + vertex -608.96 116.252 114.126 + endloop + endfacet + facet normal -0.386102 -0.90948 0.154181 + outer loop + vertex -604.182 114.19 113.935 + vertex -608.96 116.252 114.126 + vertex -604.405 112.94 106.001 + endloop + endfacet + facet normal -0.371501 -0.915452 0.154712 + outer loop + vertex -601.283 111.714 106.242 + vertex -604.182 114.19 113.935 + vertex -604.405 112.94 106.001 + endloop + endfacet + facet normal -0.371596 -0.912632 0.170348 + outer loop + vertex -601.283 111.714 106.242 + vertex -604.405 112.94 106.001 + vertex -601.611 110.356 98.2512 + endloop + endfacet + facet normal -0.342696 -0.923744 0.171047 + outer loop + vertex -600.02 109.944 99.2124 + vertex -601.283 111.714 106.242 + vertex -601.611 110.356 98.2512 + endloop + endfacet + facet normal -0.34956 -0.918539 0.184644 + outer loop + vertex -600.02 109.944 99.2124 + vertex -601.611 110.356 98.2512 + vertex -600.422 108.437 90.9559 + endloop + endfacet + facet normal -0.26384 -0.946547 0.185575 + outer loop + vertex -600.02 109.944 99.2124 + vertex -600.422 108.437 90.9559 + vertex -599.883 108.931 94.2398 + endloop + endfacet + facet normal -0.338688 -0.922059 0.187341 + outer loop + vertex -600.422 108.437 90.9559 + vertex -601.611 110.356 98.2512 + vertex -601.986 108.849 90.155 + endloop + endfacet + facet normal -0.344151 -0.917262 0.200473 + outer loop + vertex -600.422 108.437 90.9559 + vertex -601.986 108.849 90.155 + vertex -600.87 106.802 82.7067 + endloop + endfacet + facet normal -0.366901 -0.911342 0.186652 + outer loop + vertex -601.611 110.356 98.2512 + vertex -604.726 111.563 98.022 + vertex -601.986 108.849 90.155 + endloop + endfacet + facet normal -0.362527 -0.912683 0.188638 + outer loop + vertex -601.986 108.849 90.155 + vertex -604.726 111.563 98.022 + vertex -605.075 110.043 89.9973 + endloop + endfacet + facet normal -0.362153 -0.909924 0.202195 + outer loop + vertex -601.986 108.849 90.155 + vertex -605.075 110.043 89.9973 + vertex -602.414 107.24 82.1454 + endloop + endfacet + facet normal -0.356626 -0.911557 0.204651 + outer loop + vertex -602.414 107.24 82.1454 + vertex -605.075 110.043 89.9973 + vertex -605.549 108.431 81.99 + endloop + endfacet + facet normal -0.371156 -0.905805 0.204352 + outer loop + vertex -605.075 110.043 89.9973 + vertex -609.843 112.056 90.2599 + vertex -605.549 108.431 81.99 + endloop + endfacet + facet normal -0.366881 -0.90693 0.207065 + outer loop + vertex -605.549 108.431 81.99 + vertex -609.843 112.056 90.2599 + vertex -610.343 110.432 82.2576 + endloop + endfacet + facet normal -0.364836 -0.904094 0.222505 + outer loop + vertex -605.549 108.431 81.99 + vertex -610.343 110.432 82.2576 + vertex -606.33 106.764 73.9353 + endloop + endfacet + facet normal -0.349816 -0.910065 0.222284 + outer loop + vertex -603.07 105.59 74.2596 + vertex -605.549 108.431 81.99 + vertex -606.33 106.764 73.9353 + endloop + endfacet + facet normal -0.360723 -0.905139 0.224949 + outer loop + vertex -606.33 106.764 73.9353 + vertex -610.343 110.432 82.2576 + vertex -611.185 108.764 74.1987 + endloop + endfacet + facet normal -0.358386 -0.901695 0.241878 + outer loop + vertex -606.33 106.764 73.9353 + vertex -611.185 108.764 74.1987 + vertex -607.569 105.032 65.642 + endloop + endfacet + facet normal -0.344773 -0.907222 0.240998 + outer loop + vertex -604.121 103.822 66.0222 + vertex -606.33 106.764 73.9353 + vertex -607.569 105.032 65.642 + endloop + endfacet + facet normal -0.355026 -0.902542 0.243667 + outer loop + vertex -607.569 105.032 65.642 + vertex -611.185 108.764 74.1987 + vertex -612.589 107.099 65.9861 + endloop + endfacet + facet normal -0.352459 -0.899012 0.259903 + outer loop + vertex -607.569 105.032 65.642 + vertex -612.589 107.099 65.9861 + vertex -609.256 103.22 57.088 + endloop + endfacet + facet normal -0.342467 -0.903178 0.258815 + outer loop + vertex -605.569 101.822 57.0888 + vertex -607.569 105.032 65.642 + vertex -609.256 103.22 57.088 + endloop + endfacet + facet normal -0.340856 -0.898921 0.275242 + outer loop + vertex -605.569 101.822 57.0888 + vertex -609.256 103.22 57.088 + vertex -607.191 100.649 51.2473 + endloop + endfacet + facet normal -0.340618 -0.899025 0.275197 + outer loop + vertex -605.904 99.8941 50.3749 + vertex -605.569 101.822 57.0888 + vertex -607.191 100.649 51.2473 + endloop + endfacet + facet normal -0.325979 -0.897904 0.295816 + outer loop + vertex -605.904 99.8941 50.3749 + vertex -607.191 100.649 51.2473 + vertex -607.299 99.0699 46.3366 + endloop + endfacet + facet normal -0.330223 -0.895995 0.296892 + outer loop + vertex -606.417 98.787 46.4631 + vertex -605.904 99.8941 50.3749 + vertex -607.299 99.0699 46.3366 + endloop + endfacet + facet normal -0.330808 -0.889018 0.316565 + outer loop + vertex -606.417 98.787 46.4631 + vertex -607.299 99.0699 46.3366 + vertex -608.229 97.9134 42.1164 + endloop + endfacet + facet normal -0.320123 -0.894128 0.313139 + outer loop + vertex -607.499 97.8953 42.8108 + vertex -606.417 98.787 46.4631 + vertex -608.229 97.9134 42.1164 + endloop + endfacet + facet normal -0.331806 -0.888607 0.316673 + outer loop + vertex -608.229 97.9134 42.1164 + vertex -607.299 99.0699 46.3366 + vertex -609.095 98.278 42.2321 + endloop + endfacet + facet normal -0.328139 -0.88458 0.331426 + outer loop + vertex -608.229 97.9134 42.1164 + vertex -609.095 98.278 42.2321 + vertex -609.444 97.4592 39.7009 + endloop + endfacet + facet normal -0.323495 -0.886991 0.329542 + outer loop + vertex -609.227 97.331 39.5691 + vertex -608.229 97.9134 42.1164 + vertex -609.444 97.4592 39.7009 + endloop + endfacet + facet normal -0.313307 -0.884998 0.34441 + outer loop + vertex -609.227 97.331 39.5691 + vertex -609.444 97.4592 39.7009 + vertex -609.933 97.045 38.1917 + endloop + endfacet + facet normal -0.363062 -0.857623 0.364239 + outer loop + vertex -609.227 97.331 39.5691 + vertex -609.933 97.045 38.1917 + vertex -609.168 97.2123 39.3484 + endloop + endfacet + facet normal -0.313406 -0.884955 0.34443 + outer loop + vertex -609.933 97.045 38.1917 + vertex -609.444 97.4592 39.7009 + vertex -610.365 97.1108 37.9678 + endloop + endfacet + facet normal -0.318946 -0.877886 0.357197 + outer loop + vertex -609.933 97.045 38.1917 + vertex -610.365 97.1108 37.9678 + vertex -610.718 96.7999 36.8887 + endloop + endfacet + facet normal -0.317709 -0.878583 0.356584 + outer loop + vertex -610.718 96.7999 36.8887 + vertex -610.235 96.8215 37.3726 + vertex -609.933 97.045 38.1917 + endloop + endfacet + facet normal -0.319559 -0.877613 0.357319 + outer loop + vertex -610.718 96.7999 36.8887 + vertex -610.365 97.1108 37.9678 + vertex -611.194 96.9729 36.8883 + endloop + endfacet + facet normal -0.318767 -0.87542 0.363357 + outer loop + vertex -610.718 96.7999 36.8887 + vertex -611.194 96.9729 36.8883 + vertex -611.268 96.7574 36.3035 + endloop + endfacet + facet normal -0.321879 -0.876116 0.358907 + outer loop + vertex -610.365 97.1108 37.9678 + vertex -610.827 97.3265 38.0802 + vertex -611.194 96.9729 36.8883 + endloop + endfacet + facet normal -0.329414 -0.872765 0.360231 + outer loop + vertex -611.194 96.9729 36.8883 + vertex -610.827 97.3265 38.0802 + vertex -611.626 97.2473 37.1579 + endloop + endfacet + facet normal -0.32766 -0.872411 0.362683 + outer loop + vertex -611.626 97.2473 37.1579 + vertex -612.226 97.192 36.4829 + vertex -611.194 96.9729 36.8883 + endloop + endfacet + facet normal -0.331139 -0.869889 0.365568 + outer loop + vertex -611.626 97.2473 37.1579 + vertex -612.445 97.5788 37.2045 + vertex -612.226 97.192 36.4829 + endloop + endfacet + facet normal -0.332207 -0.87176 0.360102 + outer loop + vertex -611.626 97.2473 37.1579 + vertex -611.496 97.644 38.2381 + vertex -612.445 97.5788 37.2045 + endloop + endfacet + facet normal -0.332219 -0.871751 0.360112 + outer loop + vertex -611.496 97.644 38.2381 + vertex -612.405 98.0465 38.3741 + vertex -612.445 97.5788 37.2045 + endloop + endfacet + facet normal -0.335734 -0.870552 0.359754 + outer loop + vertex -612.445 97.5788 37.2045 + vertex -612.405 98.0465 38.3741 + vertex -613.304 98.0183 37.4662 + endloop + endfacet + facet normal -0.33277 -0.868832 0.3666 + outer loop + vertex -613.304 98.0183 37.4662 + vertex -613.722 97.9053 36.8194 + vertex -612.445 97.5788 37.2045 + endloop + endfacet + facet normal -0.334125 -0.868003 0.367329 + outer loop + vertex -613.304 98.0183 37.4662 + vertex -614.491 98.4974 37.5192 + vertex -613.722 97.9053 36.8194 + endloop + endfacet + facet normal -0.335879 -0.871293 0.357819 + outer loop + vertex -613.304 98.0183 37.4662 + vertex -613.517 98.528 38.508 + vertex -614.491 98.4974 37.5192 + endloop + endfacet + facet normal -0.335592 -0.871516 0.357543 + outer loop + vertex -613.517 98.528 38.508 + vertex -614.848 99.1147 38.6883 + vertex -614.491 98.4974 37.5192 + endloop + endfacet + facet normal -0.339119 -0.870757 0.356064 + outer loop + vertex -614.491 98.4974 37.5192 + vertex -614.848 99.1147 38.6883 + vertex -615.792 99.1249 37.8149 + endloop + endfacet + facet normal -0.335054 -0.867642 0.367336 + outer loop + vertex -615.792 99.1249 37.8149 + vertex -615.919 98.8879 37.1386 + vertex -614.491 98.4974 37.5192 + endloop + endfacet + facet normal -0.335477 -0.867471 0.367355 + outer loop + vertex -615.792 99.1249 37.8149 + vertex -617.314 99.7716 37.952 + vertex -615.919 98.8879 37.1386 + endloop + endfacet + facet normal -0.338964 -0.87244 0.352068 + outer loop + vertex -615.792 99.1249 37.8149 + vertex -616.467 99.8581 38.9816 + vertex -617.314 99.7716 37.952 + endloop + endfacet + facet normal -0.338316 -0.872891 0.351572 + outer loop + vertex -616.467 99.8581 38.9816 + vertex -618.355 100.677 39.1983 + vertex -617.314 99.7716 37.952 + endloop + endfacet + facet normal -0.341284 -0.872767 0.349003 + outer loop + vertex -617.314 99.7716 37.952 + vertex -618.355 100.677 39.1983 + vertex -618.7 100.446 38.2839 + endloop + endfacet + facet normal -0.335499 -0.868592 0.364677 + outer loop + vertex -618.7 100.446 38.2839 + vertex -618.698 100.228 37.7654 + vertex -617.314 99.7716 37.952 + endloop + endfacet + facet normal -0.328739 -0.870777 0.365619 + outer loop + vertex -618.7 100.446 38.2839 + vertex -620.381 101.465 39.1986 + vertex -618.698 100.228 37.7654 + endloop + endfacet + facet normal -0.339685 -0.873552 0.348597 + outer loop + vertex -618.7 100.446 38.2839 + vertex -618.355 100.677 39.1983 + vertex -620.381 101.465 39.1986 + endloop + endfacet + facet normal -0.341298 -0.877693 0.336409 + outer loop + vertex -619.698 102.012 41.3182 + vertex -620.381 101.465 39.1986 + vertex -618.355 100.677 39.1983 + endloop + endfacet + facet normal -0.34112 -0.877714 0.336535 + outer loop + vertex -617.252 100.958 41.0491 + vertex -619.698 102.012 41.3182 + vertex -618.355 100.677 39.1983 + endloop + endfacet + facet normal -0.344493 -0.881834 0.322013 + outer loop + vertex -617.252 100.958 41.0491 + vertex -618.212 102.436 44.0691 + vertex -619.698 102.012 41.3182 + endloop + endfacet + facet normal -0.345473 -0.881288 0.322458 + outer loop + vertex -618.212 102.436 44.0691 + vertex -621.104 103.7 44.4261 + vertex -619.698 102.012 41.3182 + endloop + endfacet + facet normal -0.348312 -0.880747 0.32088 + outer loop + vertex -619.698 102.012 41.3182 + vertex -621.104 103.7 44.4261 + vertex -622.467 103.231 41.658 + endloop + endfacet + facet normal -0.350519 -0.879548 0.321763 + outer loop + vertex -621.104 103.7 44.4261 + vertex -624.099 105.053 44.8598 + vertex -622.467 103.231 41.658 + endloop + endfacet + facet normal -0.353944 -0.878939 0.31967 + outer loop + vertex -622.467 103.231 41.658 + vertex -624.099 105.053 44.8598 + vertex -625.549 104.667 42.1943 + endloop + endfacet + facet normal -0.34985 -0.875374 0.333655 + outer loop + vertex -622.467 103.231 41.658 + vertex -625.549 104.667 42.1943 + vertex -623.608 102.943 39.7055 + endloop + endfacet + facet normal -0.348761 -0.876015 0.333112 + outer loop + vertex -620.381 101.465 39.1986 + vertex -622.467 103.231 41.658 + vertex -623.608 102.943 39.7055 + endloop + endfacet + facet normal -0.356374 -0.877548 0.320791 + outer loop + vertex -624.099 105.053 44.8598 + vertex -627.127 106.467 45.3663 + vertex -625.549 104.667 42.1943 + endloop + endfacet + facet normal -0.358922 -0.87707 0.319253 + outer loop + vertex -625.549 104.667 42.1943 + vertex -627.127 106.467 45.3663 + vertex -628.635 106.143 42.7802 + endloop + endfacet + facet normal -0.355611 -0.874425 0.330032 + outer loop + vertex -625.549 104.667 42.1943 + vertex -628.635 106.143 42.7802 + vertex -627.239 104.747 40.5857 + endloop + endfacet + facet normal -0.362134 -0.875152 0.320886 + outer loop + vertex -627.127 106.467 45.3663 + vertex -630.12 107.897 45.888 + vertex -628.635 106.143 42.7802 + endloop + endfacet + facet normal -0.363653 -0.87485 0.31999 + outer loop + vertex -628.635 106.143 42.7802 + vertex -630.12 107.897 45.888 + vertex -631.628 107.577 43.2989 + endloop + endfacet + facet normal -0.360552 -0.872201 0.330558 + outer loop + vertex -628.635 106.143 42.7802 + vertex -631.628 107.577 43.2989 + vertex -630.259 106.204 41.1679 + endloop + endfacet + facet normal -0.367759 -0.872365 0.322075 + outer loop + vertex -630.12 107.897 45.888 + vertex -633.063 109.319 46.3777 + vertex -631.628 107.577 43.2989 + endloop + endfacet + facet normal -0.368577 -0.872196 0.321598 + outer loop + vertex -631.628 107.577 43.2989 + vertex -633.063 109.319 46.3777 + vertex -634.622 109.043 43.8451 + endloop + endfacet + facet normal -0.36551 -0.869699 0.331701 + outer loop + vertex -631.628 107.577 43.2989 + vertex -634.622 109.043 43.8451 + vertex -633.31 107.612 41.5373 + endloop + endfacet + facet normal -0.372591 -0.869674 0.323795 + outer loop + vertex -633.063 109.319 46.3777 + vertex -635.965 110.734 46.8394 + vertex -634.622 109.043 43.8451 + endloop + endfacet + facet normal -0.373232 -0.869535 0.323429 + outer loop + vertex -634.622 109.043 43.8451 + vertex -635.965 110.734 46.8394 + vertex -637.595 110.51 44.3565 + endloop + endfacet + facet normal -0.370188 -0.866948 0.33371 + outer loop + vertex -634.622 109.043 43.8451 + vertex -637.595 110.51 44.3565 + vertex -636.469 109.242 42.3114 + endloop + endfacet + facet normal -0.378109 -0.866334 0.326342 + outer loop + vertex -635.965 110.734 46.8394 + vertex -638.926 112.169 47.22 + vertex -637.595 110.51 44.3565 + endloop + endfacet + facet normal -0.379092 -0.866123 0.325762 + outer loop + vertex -637.595 110.51 44.3565 + vertex -638.926 112.169 47.22 + vertex -640.668 112.005 44.757 + endloop + endfacet + facet normal -0.375915 -0.862848 0.337907 + outer loop + vertex -637.595 110.51 44.3565 + vertex -640.668 112.005 44.757 + vertex -639.336 110.677 42.8474 + endloop + endfacet + facet normal -0.38546 -0.861707 0.329972 + outer loop + vertex -638.926 112.169 47.22 + vertex -642.196 113.749 47.5262 + vertex -640.668 112.005 44.757 + endloop + endfacet + facet normal -0.387203 -0.861373 0.3288 + outer loop + vertex -640.668 112.005 44.757 + vertex -642.196 113.749 47.5262 + vertex -644.228 113.735 45.0958 + endloop + endfacet + facet normal -0.384162 -0.857662 0.341811 + outer loop + vertex -640.668 112.005 44.757 + vertex -644.228 113.735 45.0958 + vertex -642.208 112.082 43.2188 + endloop + endfacet + facet normal -0.393814 -0.856244 0.334299 + outer loop + vertex -642.196 113.749 47.5262 + vertex -645.911 115.575 47.8251 + vertex -644.228 113.735 45.0958 + endloop + endfacet + facet normal -0.395472 -0.855955 0.333081 + outer loop + vertex -644.228 113.735 45.0958 + vertex -645.911 115.575 47.8251 + vertex -649.291 116.228 45.4901 + endloop + endfacet + facet normal -0.401339 -0.849082 0.343493 + outer loop + vertex -648.745 117.132 48.3641 + vertex -649.291 116.228 45.4901 + vertex -645.911 115.575 47.8251 + endloop + endfacet + facet normal -0.404831 -0.851707 0.332727 + outer loop + vertex -645.911 115.575 47.8251 + vertex -647.95 117.929 51.3699 + vertex -648.745 117.132 48.3641 + endloop + endfacet + facet normal -0.420565 -0.843286 0.334653 + outer loop + vertex -648.745 117.132 48.3641 + vertex -647.95 117.929 51.3699 + vertex -652.359 119.722 50.3493 + endloop + endfacet + facet normal -0.420447 -0.84414 0.332643 + outer loop + vertex -651.287 121.591 56.4451 + vertex -652.359 119.722 50.3493 + vertex -647.95 117.929 51.3699 + endloop + endfacet + facet normal -0.432292 -0.841827 0.323187 + outer loop + vertex -646.485 119.101 56.3823 + vertex -651.287 121.591 56.4451 + vertex -647.95 117.929 51.3699 + endloop + endfacet + facet normal -0.410776 -0.853843 0.31971 + outer loop + vertex -643.984 115.992 51.2938 + vertex -646.485 119.101 56.3823 + vertex -647.95 117.929 51.3699 + endloop + endfacet + facet normal -0.416693 -0.852389 0.315912 + outer loop + vertex -642.102 116.72 55.7398 + vertex -646.485 119.101 56.3823 + vertex -643.984 115.992 51.2938 + endloop + endfacet + facet normal -0.400987 -0.86175 0.310799 + outer loop + vertex -640.426 114.182 50.8664 + vertex -642.102 116.72 55.7398 + vertex -643.984 115.992 51.2938 + endloop + endfacet + facet normal -0.398124 -0.858841 0.322319 + outer loop + vertex -640.426 114.182 50.8664 + vertex -643.984 115.992 51.2938 + vertex -642.196 113.749 47.5262 + endloop + endfacet + facet normal -0.402091 -0.861432 0.310254 + outer loop + vertex -638.887 114.711 54.327 + vertex -642.102 116.72 55.7398 + vertex -640.426 114.182 50.8664 + endloop + endfacet + facet normal -0.39184 -0.867438 0.306613 + outer loop + vertex -637.37 112.674 50.5027 + vertex -638.887 114.711 54.327 + vertex -640.426 114.182 50.8664 + endloop + endfacet + facet normal -0.389249 -0.864763 0.317284 + outer loop + vertex -637.37 112.674 50.5027 + vertex -640.426 114.182 50.8664 + vertex -638.926 112.169 47.22 + endloop + endfacet + facet normal -0.394914 -0.866626 0.304961 + outer loop + vertex -635.98 113.519 54.7066 + vertex -638.887 114.711 54.327 + vertex -637.37 112.674 50.5027 + endloop + endfacet + facet normal -0.384729 -0.871994 0.302671 + outer loop + vertex -634.494 111.276 50.1339 + vertex -635.98 113.519 54.7066 + vertex -637.37 112.674 50.5027 + endloop + endfacet + facet normal -0.381983 -0.869271 0.313779 + outer loop + vertex -634.494 111.276 50.1339 + vertex -637.37 112.674 50.5027 + vertex -635.965 110.734 46.8394 + endloop + endfacet + facet normal -0.385801 -0.871693 0.302175 + outer loop + vertex -633.06 111.828 53.5556 + vertex -635.98 113.519 54.7066 + vertex -634.494 111.276 50.1339 + endloop + endfacet + facet normal -0.379484 -0.875178 0.300091 + outer loop + vertex -631.581 109.865 49.6999 + vertex -633.06 111.828 53.5556 + vertex -634.494 111.276 50.1339 + endloop + endfacet + facet normal -0.376512 -0.872515 0.311378 + outer loop + vertex -631.581 109.865 49.6999 + vertex -634.494 111.276 50.1339 + vertex -633.063 109.319 46.3777 + endloop + endfacet + facet normal -0.381646 -0.874619 0.298977 + outer loop + vertex -630.078 110.652 53.9211 + vertex -633.06 111.828 53.5556 + vertex -631.581 109.865 49.6999 + endloop + endfacet + facet normal -0.374015 -0.878581 0.297 + outer loop + vertex -628.591 108.432 49.2263 + vertex -630.078 110.652 53.9211 + vertex -631.581 109.865 49.6999 + endloop + endfacet + facet normal -0.370532 -0.875586 0.309927 + outer loop + vertex -628.591 108.432 49.2263 + vertex -631.581 109.865 49.6999 + vertex -630.12 107.897 45.888 + endloop + endfacet + facet normal -0.372222 -0.879071 0.297799 + outer loop + vertex -627.007 108.941 52.7088 + vertex -630.078 110.652 53.9211 + vertex -628.591 108.432 49.2263 + endloop + endfacet + facet normal -0.367796 -0.881492 0.29614 + outer loop + vertex -625.54 106.997 48.7466 + vertex -627.007 108.941 52.7088 + vertex -628.591 108.432 49.2263 + endloop + endfacet + facet normal -0.364399 -0.878525 0.30888 + outer loop + vertex -625.54 106.997 48.7466 + vertex -628.591 108.432 49.2263 + vertex -627.127 106.467 45.3663 + endloop + endfacet + facet normal -0.368122 -0.88141 0.295979 + outer loop + vertex -623.877 107.754 53.0677 + vertex -627.007 108.941 52.7088 + vertex -625.54 106.997 48.7466 + endloop + endfacet + facet normal -0.361485 -0.884805 0.294021 + outer loop + vertex -622.451 105.586 48.2964 + vertex -623.877 107.754 53.0677 + vertex -625.54 106.997 48.7466 + endloop + endfacet + facet normal -0.357827 -0.881389 0.308406 + outer loop + vertex -622.451 105.586 48.2964 + vertex -625.54 106.997 48.7466 + vertex -624.099 105.053 44.8598 + endloop + endfacet + facet normal -0.35804 -0.885724 0.295468 + outer loop + vertex -620.72 106.078 51.8693 + vertex -623.877 107.754 53.0677 + vertex -622.451 105.586 48.2964 + endloop + endfacet + facet normal -0.355008 -0.887357 0.294223 + outer loop + vertex -619.353 104.217 47.9067 + vertex -620.72 106.078 51.8693 + vertex -622.451 105.586 48.2964 + endloop + endfacet + facet normal -0.351717 -0.883901 0.308242 + outer loop + vertex -619.353 104.217 47.9067 + vertex -622.451 105.586 48.2964 + vertex -621.104 103.7 44.4261 + endloop + endfacet + facet normal -0.354533 -0.887474 0.294442 + outer loop + vertex -617.545 104.958 52.3161 + vertex -620.72 106.078 51.8693 + vertex -619.353 104.217 47.9067 + endloop + endfacet + facet normal -0.349548 -0.889985 0.29282 + outer loop + vertex -616.302 102.908 47.5684 + vertex -617.545 104.958 52.3161 + vertex -619.353 104.217 47.9067 + endloop + endfacet + facet normal -0.346136 -0.886054 0.308379 + outer loop + vertex -616.302 102.908 47.5684 + vertex -619.353 104.217 47.9067 + vertex -618.212 102.436 44.0691 + endloop + endfacet + facet normal -0.345821 -0.886229 0.308231 + outer loop + vertex -615.484 101.24 43.6915 + vertex -616.302 102.908 47.5684 + vertex -618.212 102.436 44.0691 + endloop + endfacet + facet normal -0.341402 -0.887435 0.309683 + outer loop + vertex -613.406 101.661 47.1872 + vertex -616.302 102.908 47.5684 + vertex -615.484 101.24 43.6915 + endloop + endfacet + facet normal -0.34405 -0.885925 0.311074 + outer loop + vertex -612.962 99.9643 42.8472 + vertex -613.406 101.661 47.1872 + vertex -615.484 101.24 43.6915 + endloop + endfacet + facet normal -0.338032 -0.883241 0.324991 + outer loop + vertex -612.962 99.9643 42.8472 + vertex -615.484 101.24 43.6915 + vertex -615.105 99.975 40.647 + endloop + endfacet + facet normal -0.342122 -0.880181 0.328989 + outer loop + vertex -613.727 99.1877 39.9744 + vertex -612.962 99.9643 42.8472 + vertex -615.105 99.975 40.647 + endloop + endfacet + facet normal -0.334731 -0.878153 0.341763 + outer loop + vertex -613.727 99.1877 39.9744 + vertex -615.105 99.975 40.647 + vertex -614.848 99.1147 38.6883 + endloop + endfacet + facet normal -0.340881 -0.876399 0.340185 + outer loop + vertex -614.848 99.1147 38.6883 + vertex -615.105 99.975 40.647 + vertex -616.467 99.8581 38.9816 + endloop + endfacet + facet normal -0.338679 -0.877907 0.33849 + outer loop + vertex -615.105 99.975 40.647 + vertex -617.252 100.958 41.0491 + vertex -616.467 99.8581 38.9816 + endloop + endfacet + facet normal -0.337606 -0.88217 0.328326 + outer loop + vertex -613.727 99.1877 39.9744 + vertex -612.381 98.7448 40.1677 + vertex -612.962 99.9643 42.8472 + endloop + endfacet + facet normal -0.333874 -0.883126 0.32957 + outer loop + vertex -610.653 98.9607 42.4967 + vertex -612.962 99.9643 42.8472 + vertex -612.381 98.7448 40.1677 + endloop + endfacet + facet normal -0.338307 -0.8803 0.332597 + outer loop + vertex -611.407 98.1945 39.702 + vertex -610.653 98.9607 42.4967 + vertex -612.381 98.7448 40.1677 + endloop + endfacet + facet normal -0.330552 -0.878026 0.34613 + outer loop + vertex -611.407 98.1945 39.702 + vertex -612.381 98.7448 40.1677 + vertex -612.405 98.0465 38.3741 + endloop + endfacet + facet normal -0.337568 -0.875677 0.345307 + outer loop + vertex -612.405 98.0465 38.3741 + vertex -612.381 98.7448 40.1677 + vertex -613.517 98.528 38.508 + endloop + endfacet + facet normal -0.332527 -0.882825 0.33173 + outer loop + vertex -611.407 98.1945 39.702 + vertex -610.473 97.9165 39.8986 + vertex -610.653 98.9607 42.4967 + endloop + endfacet + facet normal -0.330621 -0.883404 0.332095 + outer loop + vertex -609.095 98.278 42.2321 + vertex -610.653 98.9607 42.4967 + vertex -610.473 97.9165 39.8986 + endloop + endfacet + facet normal -0.33589 -0.880412 0.334743 + outer loop + vertex -609.973 97.5453 39.4242 + vertex -609.095 98.278 42.2321 + vertex -610.473 97.9165 39.8986 + endloop + endfacet + facet normal -0.322714 -0.880057 0.348362 + outer loop + vertex -609.973 97.5453 39.4242 + vertex -610.473 97.9165 39.8986 + vertex -610.827 97.3265 38.0802 + endloop + endfacet + facet normal -0.333343 -0.875812 0.349051 + outer loop + vertex -610.827 97.3265 38.0802 + vertex -610.473 97.9165 39.8986 + vertex -611.496 97.644 38.2381 + endloop + endfacet + facet normal -0.335188 -0.887584 0.315981 + outer loop + vertex -609.095 98.278 42.2321 + vertex -608.694 99.6614 46.5435 + vertex -610.653 98.9607 42.4967 + endloop + endfacet + facet normal -0.331937 -0.88926 0.314697 + outer loop + vertex -608.694 99.6614 46.5435 + vertex -610.789 100.544 46.8271 + vertex -610.653 98.9607 42.4967 + endloop + endfacet + facet normal -0.33612 -0.893632 0.297397 + outer loop + vertex -608.694 99.6614 46.5435 + vertex -609.077 101.166 50.6323 + vertex -610.789 100.544 46.8271 + endloop + endfacet + facet normal -0.332934 -0.895214 0.296223 + outer loop + vertex -609.077 101.166 50.6323 + vertex -611.585 102.455 51.7091 + vertex -610.789 100.544 46.8271 + endloop + endfacet + facet normal -0.340633 -0.893012 0.294105 + outer loop + vertex -610.789 100.544 46.8271 + vertex -611.585 102.455 51.7091 + vertex -613.406 101.661 47.1872 + endloop + endfacet + facet normal -0.343934 -0.891401 0.295151 + outer loop + vertex -611.585 102.455 51.7091 + vertex -614.458 103.395 51.2003 + vertex -613.406 101.661 47.1872 + endloop + endfacet + facet normal -0.342957 -0.896691 0.279866 + outer loop + vertex -614.458 103.395 51.2003 + vertex -611.585 102.455 51.7091 + vertex -614.637 105.457 57.5857 + endloop + endfacet + facet normal -0.351688 -0.893683 0.278651 + outer loop + vertex -614.458 103.395 51.2003 + vertex -614.637 105.457 57.5857 + vertex -617.545 104.958 52.3161 + endloop + endfacet + facet normal -0.356784 -0.890861 0.281197 + outer loop + vertex -614.637 105.457 57.5857 + vertex -620.847 108.148 58.2324 + vertex -617.545 104.958 52.3161 + endloop + endfacet + facet normal -0.360241 -0.894714 0.264032 + outer loop + vertex -614.637 105.457 57.5857 + vertex -618.601 109.706 66.5772 + vertex -620.847 108.148 58.2324 + endloop + endfacet + facet normal -0.375487 -0.887595 0.266806 + outer loop + vertex -618.601 109.706 66.5772 + vertex -624.934 112.576 67.2131 + vertex -620.847 108.148 58.2324 + endloop + endfacet + facet normal -0.374122 -0.887934 0.267594 + outer loop + vertex -620.847 108.148 58.2324 + vertex -624.934 112.576 67.2131 + vertex -627.18 111.037 58.9657 + endloop + endfacet + facet normal -0.370412 -0.884151 0.284729 + outer loop + vertex -620.847 108.148 58.2324 + vertex -627.18 111.037 58.9657 + vertex -623.877 107.754 53.0677 + endloop + endfacet + facet normal -0.392482 -0.878954 0.27092 + outer loop + vertex -624.934 112.576 67.2131 + vertex -631.198 115.565 67.836 + vertex -627.18 111.037 58.9657 + endloop + endfacet + facet normal -0.38965 -0.8797 0.272583 + outer loop + vertex -627.18 111.037 58.9657 + vertex -631.198 115.565 67.836 + vertex -633.301 113.978 59.7072 + endloop + endfacet + facet normal -0.386001 -0.876165 0.288685 + outer loop + vertex -627.18 111.037 58.9657 + vertex -633.301 113.978 59.7072 + vertex -630.078 110.652 53.9211 + endloop + endfacet + facet normal -0.411612 -0.868535 0.276084 + outer loop + vertex -631.198 115.565 67.836 + vertex -637.223 118.624 68.4764 + vertex -633.301 113.978 59.7072 + endloop + endfacet + facet normal -0.40645 -0.869982 0.279159 + outer loop + vertex -633.301 113.978 59.7072 + vertex -637.223 118.624 68.4764 + vertex -639.174 116.997 60.5648 + endloop + endfacet + facet normal -0.402393 -0.866609 0.295074 + outer loop + vertex -633.301 113.978 59.7072 + vertex -639.174 116.997 60.5648 + vertex -635.98 113.519 54.7066 + endloop + endfacet + facet normal -0.432202 -0.856319 0.2827 + outer loop + vertex -637.223 118.624 68.4764 + vertex -642.984 121.792 69.2637 + vertex -639.174 116.997 60.5648 + endloop + endfacet + facet normal -0.427294 -0.857797 0.285664 + outer loop + vertex -639.174 116.997 60.5648 + vertex -642.984 121.792 69.2637 + vertex -644.706 120.333 62.3074 + endloop + endfacet + facet normal -0.419934 -0.855143 0.30395 + outer loop + vertex -639.174 116.997 60.5648 + vertex -644.706 120.333 62.3074 + vertex -642.102 116.72 55.7398 + endloop + endfacet + facet normal -0.454103 -0.842726 0.289142 + outer loop + vertex -642.984 121.792 69.2637 + vertex -648.482 125.004 69.9903 + vertex -644.706 120.333 62.3074 + endloop + endfacet + facet normal -0.445908 -0.845186 0.294665 + outer loop + vertex -644.706 120.333 62.3074 + vertex -648.482 125.004 69.9903 + vertex -649.884 123.278 62.9186 + endloop + endfacet + facet normal -0.4426 -0.842147 0.308048 + outer loop + vertex -644.706 120.333 62.3074 + vertex -649.884 123.278 62.9186 + vertex -646.485 119.101 56.3823 + endloop + endfacet + facet normal -0.480307 -0.825408 0.296659 + outer loop + vertex -648.482 125.004 69.9903 + vertex -653.786 128.272 70.4956 + vertex -649.884 123.278 62.9186 + endloop + endfacet + facet normal -0.4683 -0.829146 0.305307 + outer loop + vertex -649.884 123.278 62.9186 + vertex -653.786 128.272 70.4956 + vertex -655.118 126.361 63.262 + endloop + endfacet + facet normal -0.465922 -0.826338 0.316357 + outer loop + vertex -649.884 123.278 62.9186 + vertex -655.118 126.361 63.262 + vertex -651.287 121.591 56.4451 + endloop + endfacet + facet normal -0.452474 -0.829896 0.326404 + outer loop + vertex -651.287 121.591 56.4451 + vertex -655.118 126.361 63.262 + vertex -656.6 124.531 56.5547 + endloop + endfacet + facet normal -0.483514 -0.828446 0.28265 + outer loop + vertex -648.482 125.004 69.9903 + vertex -652.67 130.204 78.0665 + vertex -653.786 128.272 70.4956 + endloop + endfacet + facet normal -0.494589 -0.824653 0.274463 + outer loop + vertex -647.316 126.823 77.5556 + vertex -652.67 130.204 78.0665 + vertex -648.482 125.004 69.9903 + endloop + endfacet + facet normal -0.497908 -0.827597 0.259174 + outer loop + vertex -647.316 126.823 77.5556 + vertex -651.822 132.12 85.8158 + vertex -652.67 130.204 78.0665 + endloop + endfacet + facet normal -0.508362 -0.82375 0.251005 + outer loop + vertex -646.484 128.684 85.3492 + vertex -651.822 132.12 85.8158 + vertex -647.316 126.823 77.5556 + endloop + endfacet + facet normal -0.469952 -0.845897 0.252196 + outer loop + vertex -641.7 123.537 76.9997 + vertex -646.484 128.684 85.3492 + vertex -647.316 126.823 77.5556 + endloop + endfacet + facet normal -0.466712 -0.842961 0.267577 + outer loop + vertex -641.7 123.537 76.9997 + vertex -647.316 126.823 77.5556 + vertex -642.984 121.792 69.2637 + endloop + endfacet + facet normal -0.478959 -0.8429 0.245188 + outer loop + vertex -640.87 125.352 84.8612 + vertex -646.484 128.684 85.3492 + vertex -641.7 123.537 76.9997 + endloop + endfacet + facet normal -0.445811 -0.860717 0.245801 + outer loop + vertex -635.833 120.34 76.4486 + vertex -640.87 125.352 84.8612 + vertex -641.7 123.537 76.9997 + endloop + endfacet + facet normal -0.442631 -0.857637 0.261795 + outer loop + vertex -635.833 120.34 76.4486 + vertex -641.7 123.537 76.9997 + vertex -637.223 118.624 68.4764 + endloop + endfacet + facet normal -0.453225 -0.858473 0.240025 + outer loop + vertex -635.003 122.115 84.3626 + vertex -640.87 125.352 84.8612 + vertex -635.833 120.34 76.4486 + endloop + endfacet + facet normal -0.423214 -0.87359 0.24027 + outer loop + vertex -629.735 117.237 75.9059 + vertex -635.003 122.115 84.3626 + vertex -635.833 120.34 76.4486 + endloop + endfacet + facet normal -0.420171 -0.870446 0.256474 + outer loop + vertex -629.735 117.237 75.9059 + vertex -635.833 120.34 76.4486 + vertex -631.198 115.565 67.836 + endloop + endfacet + facet normal -0.429512 -0.871855 0.235345 + outer loop + vertex -628.89 118.968 83.8607 + vertex -635.003 122.115 84.3626 + vertex -629.735 117.237 75.9059 + endloop + endfacet + facet normal -0.402513 -0.884665 0.235267 + outer loop + vertex -623.43 114.219 75.3438 + vertex -628.89 118.968 83.8607 + vertex -629.735 117.237 75.9059 + endloop + endfacet + facet normal -0.399482 -0.881439 0.251952 + outer loop + vertex -623.43 114.219 75.3438 + vertex -629.735 117.237 75.9059 + vertex -624.934 112.576 67.2131 + endloop + endfacet + facet normal -0.407158 -0.883497 0.231638 + outer loop + vertex -622.577 115.92 83.3308 + vertex -628.89 118.968 83.8607 + vertex -623.43 114.219 75.3438 + endloop + endfacet + facet normal -0.384589 -0.893618 0.231381 + outer loop + vertex -617.105 111.343 74.7489 + vertex -622.577 115.92 83.3308 + vertex -623.43 114.219 75.3438 + endloop + endfacet + facet normal -0.38155 -0.890409 0.248175 + outer loop + vertex -617.105 111.343 74.7489 + vertex -623.43 114.219 75.3438 + vertex -618.601 109.706 66.5772 + endloop + endfacet + facet normal -0.365028 -0.897738 0.246619 + outer loop + vertex -612.589 107.099 65.9861 + vertex -617.105 111.343 74.7489 + vertex -618.601 109.706 66.5772 + endloop + endfacet + facet normal -0.388645 -0.89266 0.228284 + outer loop + vertex -616.24 113.017 82.7706 + vertex -622.577 115.92 83.3308 + vertex -617.105 111.343 74.7489 + endloop + endfacet + facet normal -0.370931 -0.900248 0.227956 + outer loop + vertex -611.185 108.764 74.1987 + vertex -616.24 113.017 82.7706 + vertex -617.105 111.343 74.7489 + endloop + endfacet + facet normal -0.39123 -0.895331 0.21289 + outer loop + vertex -616.24 113.017 82.7706 + vertex -622.116 117.601 91.2476 + vertex -622.577 115.92 83.3308 + endloop + endfacet + facet normal -0.414868 -0.884831 0.212036 + outer loop + vertex -622.116 117.601 91.2476 + vertex -628.449 120.687 91.7341 + vertex -622.577 115.92 83.3308 + endloop + endfacet + facet normal -0.416921 -0.886949 0.198744 + outer loop + vertex -622.116 117.601 91.2476 + vertex -628.16 122.31 99.583 + vertex -628.449 120.687 91.7341 + endloop + endfacet + facet normal -0.446172 -0.873009 0.196939 + outer loop + vertex -628.16 122.31 99.583 + vertex -634.252 125.519 100.011 + vertex -628.449 120.687 91.7341 + endloop + endfacet + facet normal -0.440469 -0.874757 0.201958 + outer loop + vertex -628.449 120.687 91.7341 + vertex -634.252 125.519 100.011 + vertex -634.546 123.866 92.206 + endloop + endfacet + facet normal -0.438376 -0.872686 0.215047 + outer loop + vertex -628.449 120.687 91.7341 + vertex -634.546 123.866 92.206 + vertex -628.89 118.968 83.8607 + endloop + endfacet + facet normal -0.472832 -0.85823 0.199677 + outer loop + vertex -634.252 125.519 100.011 + vertex -640.05 128.818 100.458 + vertex -634.546 123.866 92.206 + endloop + endfacet + facet normal -0.466024 -0.86055 0.205611 + outer loop + vertex -634.546 123.866 92.206 + vertex -640.05 128.818 100.458 + vertex -640.376 127.137 92.6835 + endloop + endfacet + facet normal -0.46382 -0.858525 0.218646 + outer loop + vertex -634.546 123.866 92.206 + vertex -640.376 127.137 92.6835 + vertex -635.003 122.115 84.3626 + endloop + endfacet + facet normal -0.500922 -0.841366 0.202929 + outer loop + vertex -640.05 128.818 100.458 + vertex -645.563 132.21 100.913 + vertex -640.376 127.137 92.6835 + endloop + endfacet + facet normal -0.492844 -0.84442 0.209903 + outer loop + vertex -640.376 127.137 92.6835 + vertex -645.563 132.21 100.913 + vertex -645.94 130.502 93.1571 + endloop + endfacet + facet normal -0.490479 -0.842383 0.223207 + outer loop + vertex -640.376 127.137 92.6835 + vertex -645.94 130.502 93.1571 + vertex -640.87 125.352 84.8612 + endloop + endfacet + facet normal -0.532087 -0.821078 0.206673 + outer loop + vertex -645.563 132.21 100.913 + vertex -650.791 135.707 101.347 + vertex -645.94 130.502 93.1571 + endloop + endfacet + facet normal -0.523959 -0.824508 0.213666 + outer loop + vertex -645.94 130.502 93.1571 + vertex -650.791 135.707 101.347 + vertex -651.218 133.972 93.6023 + endloop + endfacet + facet normal -0.521355 -0.822364 0.227829 + outer loop + vertex -645.94 130.502 93.1571 + vertex -651.218 133.972 93.6023 + vertex -646.484 128.684 85.3492 + endloop + endfacet + facet normal -0.53449 -0.822929 0.192634 + outer loop + vertex -645.563 132.21 100.913 + vertex -650.457 137.291 109.041 + vertex -650.791 135.707 101.347 + endloop + endfacet + facet normal -0.541501 -0.819768 0.186436 + outer loop + vertex -645.264 133.768 108.634 + vertex -650.457 137.291 109.041 + vertex -645.563 132.21 100.913 + endloop + endfacet + facet normal -0.543946 -0.821562 0.170757 + outer loop + vertex -645.264 133.768 108.634 + vertex -650.191 138.715 116.738 + vertex -650.457 137.291 109.041 + endloop + endfacet + facet normal -0.548349 -0.819448 0.16679 + outer loop + vertex -645.001 135.166 116.366 + vertex -650.191 138.715 116.738 + vertex -645.264 133.768 108.634 + endloop + endfacet + facet normal -0.511106 -0.842597 0.169709 + outer loop + vertex -639.771 130.351 108.211 + vertex -645.001 135.166 116.366 + vertex -645.264 133.768 108.634 + endloop + endfacet + facet normal -0.508857 -0.840826 0.184597 + outer loop + vertex -639.771 130.351 108.211 + vertex -645.264 133.768 108.634 + vertex -640.05 128.818 100.458 + endloop + endfacet + facet normal -0.515882 -0.840535 0.165428 + outer loop + vertex -639.521 131.727 115.98 + vertex -645.001 135.166 116.366 + vertex -639.771 130.351 108.211 + endloop + endfacet + facet normal -0.482405 -0.859736 0.167751 + outer loop + vertex -633.991 127.029 107.805 + vertex -639.521 131.727 115.98 + vertex -639.771 130.351 108.211 + endloop + endfacet + facet normal -0.480355 -0.857937 0.182216 + outer loop + vertex -633.991 127.029 107.805 + vertex -639.771 130.351 108.211 + vertex -634.252 125.519 100.011 + endloop + endfacet + facet normal -0.486817 -0.858013 0.163776 + outer loop + vertex -633.748 128.381 115.612 + vertex -639.521 131.727 115.98 + vertex -633.991 127.029 107.805 + endloop + endfacet + facet normal -0.454878 -0.874998 0.165726 + outer loop + vertex -627.904 123.792 107.422 + vertex -633.748 128.381 115.612 + vertex -633.991 127.029 107.805 + endloop + endfacet + facet normal -0.453011 -0.873164 0.179903 + outer loop + vertex -627.904 123.792 107.422 + vertex -633.991 127.029 107.805 + vertex -628.16 122.31 99.583 + endloop + endfacet + facet normal -0.423586 -0.887457 0.181642 + outer loop + vertex -621.807 119.188 99.1476 + vertex -627.904 123.792 107.422 + vertex -628.16 122.31 99.583 + endloop + endfacet + facet normal -0.428016 -0.88614 0.177646 + outer loop + vertex -621.546 120.642 107.031 + vertex -627.904 123.792 107.422 + vertex -621.807 119.188 99.1476 + endloop + endfacet + facet normal -0.403546 -0.8973 0.178894 + outer loop + vertex -615.408 116.218 98.682 + vertex -621.546 120.642 107.031 + vertex -621.807 119.188 99.1476 + endloop + endfacet + facet normal -0.401687 -0.895382 0.192196 + outer loop + vertex -615.408 116.218 98.682 + vertex -621.807 119.188 99.1476 + vertex -615.75 114.665 90.7334 + endloop + endfacet + facet normal -0.383395 -0.903207 0.192937 + outer loop + vertex -609.843 112.056 90.2599 + vertex -615.408 116.218 98.682 + vertex -615.75 114.665 90.7334 + endloop + endfacet + facet normal -0.386942 -0.902288 0.190139 + outer loop + vertex -609.474 113.581 98.2471 + vertex -615.408 116.218 98.682 + vertex -609.843 112.056 90.2599 + endloop + endfacet + facet normal -0.388839 -0.904278 0.17631 + outer loop + vertex -609.474 113.581 98.2471 + vertex -615.143 117.648 106.605 + vertex -615.408 116.218 98.682 + endloop + endfacet + facet normal -0.392271 -0.903334 0.173524 + outer loop + vertex -609.202 114.991 106.205 + vertex -615.143 117.648 106.605 + vertex -609.474 113.581 98.2471 + endloop + endfacet + facet normal -0.378163 -0.909224 0.174084 + outer loop + vertex -604.726 111.563 98.022 + vertex -609.202 114.991 106.205 + vertex -609.474 113.581 98.2471 + endloop + endfacet + facet normal -0.38113 -0.908362 0.1721 + outer loop + vertex -604.405 112.94 106.001 + vertex -609.202 114.991 106.205 + vertex -604.726 111.563 98.022 + endloop + endfacet + facet normal -0.394154 -0.905279 0.158468 + outer loop + vertex -609.202 114.991 106.205 + vertex -614.911 118.93 114.505 + vertex -615.143 117.648 106.605 + endloop + endfacet + facet normal -0.41284 -0.897051 0.15768 + outer loop + vertex -614.911 118.93 114.505 + vertex -621.316 121.948 114.903 + vertex -615.143 117.648 106.605 + endloop + endfacet + facet normal -0.409271 -0.898116 0.160887 + outer loop + vertex -615.143 117.648 106.605 + vertex -621.316 121.948 114.903 + vertex -621.546 120.642 107.031 + endloop + endfacet + facet normal -0.433714 -0.886781 0.159721 + outer loop + vertex -621.316 121.948 114.903 + vertex -627.67 125.121 115.264 + vertex -621.546 120.642 107.031 + endloop + endfacet + facet normal -0.435565 -0.888643 0.143515 + outer loop + vertex -621.316 121.948 114.903 + vertex -627.472 126.297 123.147 + vertex -627.67 125.121 115.264 + endloop + endfacet + facet normal -0.464929 -0.873878 0.14205 + outer loop + vertex -627.472 126.297 123.147 + vertex -633.541 129.578 123.47 + vertex -627.67 125.121 115.264 + endloop + endfacet + facet normal -0.461226 -0.875278 0.145459 + outer loop + vertex -627.67 125.121 115.264 + vertex -633.541 129.578 123.47 + vertex -633.748 128.381 115.612 + endloop + endfacet + facet normal -0.492563 -0.85833 0.143704 + outer loop + vertex -633.541 129.578 123.47 + vertex -639.31 132.945 123.808 + vertex -633.748 128.381 115.612 + endloop + endfacet + facet normal -0.49465 -0.860041 0.125106 + outer loop + vertex -633.541 129.578 123.47 + vertex -639.146 134.003 131.73 + vertex -639.31 132.945 123.808 + endloop + endfacet + facet normal -0.526867 -0.840967 0.123227 + outer loop + vertex -639.146 134.003 131.73 + vertex -644.618 137.479 132.057 + vertex -639.31 132.945 123.808 + endloop + endfacet + facet normal -0.524105 -0.842319 0.125748 + outer loop + vertex -639.31 132.945 123.808 + vertex -644.618 137.479 132.057 + vertex -644.784 136.404 124.162 + endloop + endfacet + facet normal -0.521817 -0.840661 0.144903 + outer loop + vertex -639.31 132.945 123.808 + vertex -644.784 136.404 124.162 + vertex -639.521 131.727 115.98 + endloop + endfacet + facet normal -0.559702 -0.819457 0.123384 + outer loop + vertex -644.618 137.479 132.057 + vertex -649.805 141.069 132.368 + vertex -644.784 136.404 124.162 + endloop + endfacet + facet normal -0.557 -0.820919 0.125868 + outer loop + vertex -644.784 136.404 124.162 + vertex -649.805 141.069 132.368 + vertex -649.971 139.975 124.501 + endloop + endfacet + facet normal -0.554598 -0.819295 0.145523 + outer loop + vertex -644.784 136.404 124.162 + vertex -649.971 139.975 124.501 + vertex -645.001 135.166 116.366 + endloop + endfacet + facet normal -0.60069 -0.790042 0.122499 + outer loop + vertex -649.805 141.069 132.368 + vertex -654.685 144.823 132.649 + vertex -649.971 139.975 124.501 + endloop + endfacet + facet normal -0.597574 -0.791942 0.125432 + outer loop + vertex -649.971 139.975 124.501 + vertex -654.685 144.823 132.649 + vertex -654.849 143.706 124.811 + endloop + endfacet + facet normal -0.595134 -0.790399 0.145204 + outer loop + vertex -649.971 139.975 124.501 + vertex -654.849 143.706 124.811 + vertex -650.191 138.715 116.738 + endloop + endfacet + facet normal -0.591241 -0.792642 0.148837 + outer loop + vertex -650.191 138.715 116.738 + vertex -654.849 143.706 124.811 + vertex -655.064 142.414 117.083 + endloop + endfacet + facet normal -0.588715 -0.790975 0.166653 + outer loop + vertex -650.191 138.715 116.738 + vertex -655.064 142.414 117.083 + vertex -650.457 137.291 109.041 + endloop + endfacet + facet normal -0.583501 -0.793809 0.171446 + outer loop + vertex -650.457 137.291 109.041 + vertex -655.064 142.414 117.083 + vertex -655.337 140.959 109.417 + endloop + endfacet + facet normal -0.580817 -0.791965 0.188263 + outer loop + vertex -650.457 137.291 109.041 + vertex -655.337 140.959 109.417 + vertex -650.791 135.707 101.347 + endloop + endfacet + facet normal -0.574 -0.795452 0.194372 + outer loop + vertex -650.791 135.707 101.347 + vertex -655.337 140.959 109.417 + vertex -655.696 139.344 101.745 + endloop + endfacet + facet normal -0.571369 -0.793543 0.209348 + outer loop + vertex -650.791 135.707 101.347 + vertex -655.696 139.344 101.745 + vertex -651.218 133.972 93.6023 + endloop + endfacet + facet normal -0.562146 -0.797969 0.217339 + outer loop + vertex -651.218 133.972 93.6023 + vertex -655.696 139.344 101.745 + vertex -656.179 137.582 94.0249 + endloop + endfacet + facet normal -0.559221 -0.795732 0.232556 + outer loop + vertex -651.218 133.972 93.6023 + vertex -656.179 137.582 94.0249 + vertex -651.822 132.12 85.8158 + endloop + endfacet + facet normal -0.549013 -0.800309 0.241021 + outer loop + vertex -651.822 132.12 85.8158 + vertex -656.179 137.582 94.0249 + vertex -656.839 135.701 86.2767 + endloop + endfacet + facet normal -0.545641 -0.79764 0.256993 + outer loop + vertex -651.822 132.12 85.8158 + vertex -656.839 135.701 86.2767 + vertex -652.67 130.204 78.0665 + endloop + endfacet + facet normal -0.533692 -0.802624 0.266397 + outer loop + vertex -652.67 130.204 78.0665 + vertex -656.839 135.701 86.2767 + vertex -657.735 133.737 78.5643 + endloop + endfacet + facet normal -0.53006 -0.799638 0.282161 + outer loop + vertex -652.67 130.204 78.0665 + vertex -657.735 133.737 78.5643 + vertex -653.786 128.272 70.4956 + endloop + endfacet + facet normal -0.516498 -0.804845 0.292325 + outer loop + vertex -653.786 128.272 70.4956 + vertex -657.735 133.737 78.5643 + vertex -658.91 131.733 70.9735 + endloop + endfacet + facet normal -0.513126 -0.801788 0.306329 + outer loop + vertex -653.786 128.272 70.4956 + vertex -658.91 131.733 70.9735 + vertex -655.118 126.361 63.262 + endloop + endfacet + facet normal -0.497115 -0.807296 0.31804 + outer loop + vertex -655.118 126.361 63.262 + vertex -658.91 131.733 70.9735 + vertex -660.391 129.759 63.647 + endloop + endfacet + facet normal -0.494561 -0.804552 0.328793 + outer loop + vertex -655.118 126.361 63.262 + vertex -660.391 129.759 63.647 + vertex -656.6 124.531 56.5547 + endloop + endfacet + facet normal -0.475533 -0.810063 0.343025 + outer loop + vertex -656.6 124.531 56.5547 + vertex -660.391 129.759 63.647 + vertex -662.202 127.968 56.9066 + endloop + endfacet + facet normal -0.472768 -0.806732 0.354506 + outer loop + vertex -656.6 124.531 56.5547 + vertex -662.202 127.968 56.9066 + vertex -658.482 123.126 50.8488 + endloop + endfacet + facet normal -0.433716 -0.831275 0.347667 + outer loop + vertex -652.359 119.722 50.3493 + vertex -656.6 124.531 56.5547 + vertex -658.482 123.126 50.8488 + endloop + endfacet + facet normal -0.602811 -0.79129 0.102368 + outer loop + vertex -649.805 141.069 132.368 + vertex -654.557 145.753 140.593 + vertex -654.685 144.823 132.649 + endloop + endfacet + facet normal -0.60449 -0.790212 0.100784 + outer loop + vertex -649.671 141.982 140.337 + vertex -654.557 145.753 140.593 + vertex -649.805 141.069 132.368 + endloop + endfacet + facet normal -0.606339 -0.791185 0.0798762 + outer loop + vertex -649.671 141.982 140.337 + vertex -654.452 146.481 148.597 + vertex -654.557 145.753 140.593 + endloop + endfacet + facet normal -0.607983 -0.790077 0.0783211 + outer loop + vertex -649.572 142.702 148.361 + vertex -654.452 146.481 148.597 + vertex -649.671 141.982 140.337 + endloop + endfacet + facet normal -0.56609 -0.820401 0.0805233 + outer loop + vertex -644.49 138.38 140.05 + vertex -649.572 142.702 148.361 + vertex -649.671 141.982 140.337 + endloop + endfacet + facet normal -0.564226 -0.819378 0.101329 + outer loop + vertex -644.49 138.38 140.05 + vertex -649.671 141.982 140.337 + vertex -644.618 137.479 132.057 + endloop + endfacet + facet normal -0.567285 -0.819683 0.0794201 + outer loop + vertex -644.39 139.09 148.097 + vertex -649.572 142.702 148.361 + vertex -644.49 138.38 140.05 + endloop + endfacet + facet normal -0.532832 -0.842336 0.0809907 + outer loop + vertex -639.018 134.889 139.747 + vertex -644.39 139.09 148.097 + vertex -644.49 138.38 140.05 + endloop + endfacet + facet normal -0.53102 -0.841266 0.101441 + outer loop + vertex -639.018 134.889 139.747 + vertex -644.49 138.38 140.05 + vertex -639.146 134.003 131.73 + endloop + endfacet + facet normal -0.499715 -0.860042 0.103017 + outer loop + vertex -633.387 130.619 131.415 + vertex -639.018 134.889 139.747 + vertex -639.146 134.003 131.73 + endloop + endfacet + facet normal -0.501839 -0.859036 0.101066 + outer loop + vertex -633.259 131.49 139.457 + vertex -639.018 134.889 139.747 + vertex -633.387 130.619 131.415 + endloop + endfacet + facet normal -0.471358 -0.875975 0.102416 + outer loop + vertex -627.318 127.319 131.117 + vertex -633.259 131.49 139.457 + vertex -633.387 130.619 131.415 + endloop + endfacet + facet normal -0.469632 -0.8745 0.121229 + outer loop + vertex -627.318 127.319 131.117 + vertex -633.387 130.619 131.415 + vertex -627.472 126.297 123.147 + endloop + endfacet + facet normal -0.440943 -0.889129 0.122552 + outer loop + vertex -621.128 123.104 122.809 + vertex -627.318 127.319 131.117 + vertex -627.472 126.297 123.147 + endloop + endfacet + facet normal -0.443747 -0.88809 0.119936 + outer loop + vertex -620.981 124.11 130.801 + vertex -627.318 127.319 131.117 + vertex -621.128 123.104 122.809 + endloop + endfacet + facet normal -0.473704 -0.874961 0.100238 + outer loop + vertex -627.198 128.178 139.181 + vertex -633.259 131.49 139.457 + vertex -627.318 127.319 131.117 + endloop + endfacet + facet normal -0.503534 -0.860183 0.080859 + outer loop + vertex -633.259 131.49 139.457 + vertex -638.919 135.59 147.819 + vertex -639.018 134.889 139.747 + endloop + endfacet + facet normal -0.505096 -0.859401 0.0794185 + outer loop + vertex -633.164 132.183 147.552 + vertex -638.919 135.59 147.819 + vertex -633.259 131.49 139.457 + endloop + endfacet + facet normal -0.53433 -0.841518 0.0796149 + outer loop + vertex -638.919 135.59 147.819 + vertex -644.39 139.09 148.097 + vertex -639.018 134.889 139.747 + endloop + endfacet + facet normal -0.535887 -0.842266 0.0584239 + outer loop + vertex -638.919 135.59 147.819 + vertex -644.317 139.602 156.144 + vertex -644.39 139.09 148.097 + endloop + endfacet + facet normal -0.569506 -0.819987 0.0573143 + outer loop + vertex -644.317 139.602 156.144 + vertex -649.499 143.218 156.385 + vertex -644.39 139.09 148.097 + endloop + endfacet + facet normal -0.570805 -0.820347 0.0348267 + outer loop + vertex -644.317 139.602 156.144 + vertex -649.458 143.528 164.376 + vertex -649.499 143.218 156.385 + endloop + endfacet + facet normal -0.611236 -0.790723 0.0338846 + outer loop + vertex -649.458 143.528 164.376 + vertex -654.328 147.301 164.574 + vertex -649.499 143.218 156.385 + endloop + endfacet + facet normal -0.611235 -0.790724 0.0338857 + outer loop + vertex -649.499 143.218 156.385 + vertex -654.328 147.301 164.574 + vertex -654.377 146.998 156.602 + endloop + endfacet + facet normal -0.609988 -0.790405 0.0563501 + outer loop + vertex -649.499 143.218 156.385 + vertex -654.377 146.998 156.602 + vertex -649.572 142.702 148.361 + endloop + endfacet + facet normal -0.612149 -0.790674 0.0104387 + outer loop + vertex -649.458 143.528 164.376 + vertex -654.314 147.395 172.513 + vertex -654.328 147.301 164.574 + endloop + endfacet + facet normal -0.611049 -0.791509 0.011492 + outer loop + vertex -649.442 143.632 172.335 + vertex -654.314 147.395 172.513 + vertex -649.458 143.528 164.376 + endloop + endfacet + facet normal -0.570957 -0.820247 0.0346844 + outer loop + vertex -644.277 139.913 164.157 + vertex -649.458 143.528 164.376 + vertex -644.317 139.602 156.144 + endloop + endfacet + facet normal -0.536746 -0.841773 0.057629 + outer loop + vertex -638.847 136.097 155.889 + vertex -644.317 139.602 156.144 + vertex -638.919 135.59 147.819 + endloop + endfacet + facet normal -0.568868 -0.820387 0.057907 + outer loop + vertex -644.39 139.09 148.097 + vertex -649.499 143.218 156.385 + vertex -649.572 142.702 148.361 + endloop + endfacet + facet normal -0.609529 -0.790727 0.0567852 + outer loop + vertex -649.572 142.702 148.361 + vertex -654.377 146.998 156.602 + vertex -654.452 146.481 148.597 + endloop + endfacet + facet normal -0.561797 -0.820766 0.103567 + outer loop + vertex -644.618 137.479 132.057 + vertex -649.671 141.982 140.337 + vertex -649.805 141.069 132.368 + endloop + endfacet + facet normal -0.528933 -0.842347 0.103351 + outer loop + vertex -639.146 134.003 131.73 + vertex -644.49 138.38 140.05 + vertex -644.618 137.479 132.057 + endloop + endfacet + facet normal -0.497834 -0.858622 0.122186 + outer loop + vertex -633.387 130.619 131.415 + vertex -639.146 134.003 131.73 + vertex -633.541 129.578 123.47 + endloop + endfacet + facet normal -0.466845 -0.875629 0.123814 + outer loop + vertex -627.472 126.297 123.147 + vertex -633.387 130.619 131.415 + vertex -633.541 129.578 123.47 + endloop + endfacet + facet normal -0.439139 -0.887413 0.140198 + outer loop + vertex -621.128 123.104 122.809 + vertex -627.472 126.297 123.147 + vertex -621.316 121.948 114.903 + endloop + endfacet + facet normal -0.414731 -0.898906 0.141299 + outer loop + vertex -614.911 118.93 114.505 + vertex -621.128 123.104 122.809 + vertex -621.316 121.948 114.903 + endloop + endfacet + facet normal -0.417796 -0.897921 0.138509 + outer loop + vertex -614.727 120.068 122.433 + vertex -621.128 123.104 122.809 + vertex -614.911 118.93 114.505 + endloop + endfacet + facet normal -0.397173 -0.904393 0.155971 + outer loop + vertex -608.96 116.252 114.126 + vertex -614.911 118.93 114.505 + vertex -609.202 114.991 106.205 + endloop + endfacet + facet normal -0.397634 -0.896435 0.19568 + outer loop + vertex -615.75 114.665 90.7334 + vertex -621.807 119.188 99.1476 + vertex -622.116 117.601 91.2476 + endloop + endfacet + facet normal -0.407416 -0.896225 0.175479 + outer loop + vertex -615.143 117.648 106.605 + vertex -621.546 120.642 107.031 + vertex -615.408 116.218 98.682 + endloop + endfacet + facet normal -0.429833 -0.888022 0.163282 + outer loop + vertex -621.546 120.642 107.031 + vertex -627.67 125.121 115.264 + vertex -627.904 123.792 107.422 + endloop + endfacet + facet normal -0.45931 -0.873436 0.161688 + outer loop + vertex -627.67 125.121 115.264 + vertex -633.748 128.381 115.612 + vertex -627.904 123.792 107.422 + endloop + endfacet + facet normal -0.488945 -0.859839 0.147 + outer loop + vertex -633.748 128.381 115.612 + vertex -639.31 132.945 123.808 + vertex -639.521 131.727 115.98 + endloop + endfacet + facet normal -0.518214 -0.842318 0.148168 + outer loop + vertex -639.521 131.727 115.98 + vertex -644.784 136.404 124.162 + vertex -645.001 135.166 116.366 + endloop + endfacet + facet normal -0.550836 -0.821214 0.148956 + outer loop + vertex -645.001 135.166 116.366 + vertex -649.971 139.975 124.501 + vertex -650.191 138.715 116.738 + endloop + endfacet + facet normal -0.503114 -0.84315 0.189667 + outer loop + vertex -640.05 128.818 100.458 + vertex -645.264 133.768 108.634 + vertex -645.563 132.21 100.913 + endloop + endfacet + facet normal -0.474787 -0.85997 0.187162 + outer loop + vertex -634.252 125.519 100.011 + vertex -639.771 130.351 108.211 + vertex -640.05 128.818 100.458 + endloop + endfacet + facet normal -0.448001 -0.874809 0.1844 + outer loop + vertex -628.16 122.31 99.583 + vertex -633.991 127.029 107.805 + vertex -634.252 125.519 100.011 + endloop + endfacet + facet normal -0.421794 -0.885596 0.194446 + outer loop + vertex -621.807 119.188 99.1476 + vertex -628.16 122.31 99.583 + vertex -622.116 117.601 91.2476 + endloop + endfacet + facet normal -0.395535 -0.894277 0.209335 + outer loop + vertex -615.75 114.665 90.7334 + vertex -622.116 117.601 91.2476 + vertex -616.24 113.017 82.7706 + endloop + endfacet + facet normal -0.377315 -0.902004 0.209815 + outer loop + vertex -610.343 110.432 82.2576 + vertex -615.75 114.665 90.7334 + vertex -616.24 113.017 82.7706 + endloop + endfacet + facet normal -0.409729 -0.886171 0.216387 + outer loop + vertex -622.577 115.92 83.3308 + vertex -628.449 120.687 91.7341 + vertex -628.89 118.968 83.8607 + endloop + endfacet + facet normal -0.432099 -0.87449 0.220359 + outer loop + vertex -628.89 118.968 83.8607 + vertex -634.546 123.866 92.206 + vertex -635.003 122.115 84.3626 + endloop + endfacet + facet normal -0.455899 -0.861048 0.225283 + outer loop + vertex -635.003 122.115 84.3626 + vertex -640.376 127.137 92.6835 + vertex -640.87 125.352 84.8612 + endloop + endfacet + facet normal -0.481759 -0.84546 0.230448 + outer loop + vertex -640.87 125.352 84.8612 + vertex -645.94 130.502 93.1571 + vertex -646.484 128.684 85.3492 + endloop + endfacet + facet normal -0.511317 -0.826319 0.23612 + outer loop + vertex -646.484 128.684 85.3492 + vertex -651.218 133.972 93.6023 + vertex -651.822 132.12 85.8158 + endloop + endfacet + facet normal -0.457895 -0.845765 0.273886 + outer loop + vertex -642.984 121.792 69.2637 + vertex -647.316 126.823 77.5556 + vertex -648.482 125.004 69.9903 + endloop + endfacet + facet normal -0.436222 -0.859544 0.26626 + outer loop + vertex -637.223 118.624 68.4764 + vertex -641.7 123.537 76.9997 + vertex -642.984 121.792 69.2637 + endloop + endfacet + facet normal -0.415008 -0.871865 0.260039 + outer loop + vertex -631.198 115.565 67.836 + vertex -635.833 120.34 76.4486 + vertex -637.223 118.624 68.4764 + endloop + endfacet + facet normal -0.39575 -0.882384 0.25452 + outer loop + vertex -624.934 112.576 67.2131 + vertex -629.735 117.237 75.9059 + vertex -631.198 115.565 67.836 + endloop + endfacet + facet normal -0.378746 -0.891078 0.250064 + outer loop + vertex -618.601 109.706 66.5772 + vertex -623.43 114.219 75.3438 + vertex -624.934 112.576 67.2131 + endloop + endfacet + facet normal -0.361922 -0.89431 0.2631 + outer loop + vertex -612.589 107.099 65.9861 + vertex -618.601 109.706 66.5772 + vertex -614.637 105.457 57.5857 + endloop + endfacet + facet normal -0.346735 -0.895963 0.277533 + outer loop + vertex -609.256 103.22 57.088 + vertex -614.637 105.457 57.5857 + vertex -611.585 102.455 51.7091 + endloop + endfacet + facet normal -0.342913 -0.89786 0.276148 + outer loop + vertex -609.077 101.166 50.6323 + vertex -609.256 103.22 57.088 + vertex -611.585 102.455 51.7091 + endloop + endfacet + facet normal -0.341376 -0.892001 0.296304 + outer loop + vertex -607.191 100.649 51.2473 + vertex -609.077 101.166 50.6323 + vertex -608.694 99.6614 46.5435 + endloop + endfacet + facet normal -0.334039 -0.875402 0.349413 + outer loop + vertex -610.473 97.9165 39.8986 + vertex -611.407 98.1945 39.702 + vertex -611.496 97.644 38.2381 + endloop + endfacet + facet normal -0.338073 -0.887271 0.313778 + outer loop + vertex -610.653 98.9607 42.4967 + vertex -610.789 100.544 46.8271 + vertex -612.962 99.9643 42.8472 + endloop + endfacet + facet normal -0.337873 -0.875488 0.34549 + outer loop + vertex -612.381 98.7448 40.1677 + vertex -613.727 99.1877 39.9744 + vertex -613.517 98.528 38.508 + endloop + endfacet + facet normal -0.343191 -0.881718 0.323717 + outer loop + vertex -617.252 100.958 41.0491 + vertex -615.105 99.975 40.647 + vertex -615.484 101.24 43.6915 + endloop + endfacet + facet normal -0.33607 -0.888361 0.312843 + outer loop + vertex -610.789 100.544 46.8271 + vertex -613.406 101.661 47.1872 + vertex -612.962 99.9643 42.8472 + endloop + endfacet + facet normal -0.344958 -0.891132 0.294767 + outer loop + vertex -613.406 101.661 47.1872 + vertex -614.458 103.395 51.2003 + vertex -616.302 102.908 47.5684 + endloop + endfacet + facet normal -0.344688 -0.891276 0.294649 + outer loop + vertex -614.458 103.395 51.2003 + vertex -617.545 104.958 52.3161 + vertex -616.302 102.908 47.5684 + endloop + endfacet + facet normal -0.354267 -0.891339 0.282859 + outer loop + vertex -620.72 106.078 51.8693 + vertex -617.545 104.958 52.3161 + vertex -620.847 108.148 58.2324 + endloop + endfacet + facet normal -0.364395 -0.887689 0.281469 + outer loop + vertex -620.72 106.078 51.8693 + vertex -620.847 108.148 58.2324 + vertex -623.877 107.754 53.0677 + endloop + endfacet + facet normal -0.368209 -0.884594 0.28621 + outer loop + vertex -627.007 108.941 52.7088 + vertex -623.877 107.754 53.0677 + vertex -627.18 111.037 58.9657 + endloop + endfacet + facet normal -0.378372 -0.880798 0.284656 + outer loop + vertex -627.007 108.941 52.7088 + vertex -627.18 111.037 58.9657 + vertex -630.078 110.652 53.9211 + endloop + endfacet + facet normal -0.381711 -0.877078 0.291599 + outer loop + vertex -633.06 111.828 53.5556 + vertex -630.078 110.652 53.9211 + vertex -633.301 113.978 59.7072 + endloop + endfacet + facet normal -0.39157 -0.873291 0.289889 + outer loop + vertex -633.06 111.828 53.5556 + vertex -633.301 113.978 59.7072 + vertex -635.98 113.519 54.7066 + endloop + endfacet + facet normal -0.394965 -0.868291 0.300123 + outer loop + vertex -638.887 114.711 54.327 + vertex -635.98 113.519 54.7066 + vertex -639.174 116.997 60.5648 + endloop + endfacet + facet normal -0.408589 -0.862869 0.297509 + outer loop + vertex -638.887 114.711 54.327 + vertex -639.174 116.997 60.5648 + vertex -642.102 116.72 55.7398 + endloop + endfacet + facet normal -0.419942 -0.855141 0.303945 + outer loop + vertex -646.485 119.101 56.3823 + vertex -642.102 116.72 55.7398 + vertex -644.706 120.333 62.3074 + endloop + endfacet + facet normal -0.433789 -0.844485 0.314123 + outer loop + vertex -646.485 119.101 56.3823 + vertex -649.884 123.278 62.9186 + vertex -651.287 121.591 56.4451 + endloop + endfacet + facet normal -0.451238 -0.827912 0.333084 + outer loop + vertex -651.287 121.591 56.4451 + vertex -656.6 124.531 56.5547 + vertex -652.359 119.722 50.3493 + endloop + endfacet + facet normal -0.409119 -0.850841 0.329685 + outer loop + vertex -643.984 115.992 51.2938 + vertex -647.95 117.929 51.3699 + vertex -645.911 115.575 47.8251 + endloop + endfacet + facet normal -0.414819 -0.842392 0.343948 + outer loop + vertex -648.745 117.132 48.3641 + vertex -652.359 119.722 50.3493 + vertex -649.291 116.228 45.4901 + endloop + endfacet + facet normal -0.39618 -0.859292 0.32351 + outer loop + vertex -642.196 113.749 47.5262 + vertex -643.984 115.992 51.2938 + vertex -645.911 115.575 47.8251 + endloop + endfacet + facet normal -0.388198 -0.865024 0.317861 + outer loop + vertex -638.926 112.169 47.22 + vertex -640.426 114.182 50.8664 + vertex -642.196 113.749 47.5262 + endloop + endfacet + facet normal -0.381191 -0.86947 0.314189 + outer loop + vertex -635.965 110.734 46.8394 + vertex -637.37 112.674 50.5027 + vertex -638.926 112.169 47.22 + endloop + endfacet + facet normal -0.375974 -0.872649 0.311653 + outer loop + vertex -633.063 109.319 46.3777 + vertex -634.494 111.276 50.1339 + vertex -635.965 110.734 46.8394 + endloop + endfacet + facet normal -0.37131 -0.875397 0.309531 + outer loop + vertex -630.12 107.897 45.888 + vertex -631.581 109.865 49.6999 + vertex -633.063 109.319 46.3777 + endloop + endfacet + facet normal -0.3658 -0.87819 0.308177 + outer loop + vertex -627.127 106.467 45.3663 + vertex -628.591 108.432 49.2263 + vertex -630.12 107.897 45.888 + endloop + endfacet + facet normal -0.360173 -0.880834 0.307258 + outer loop + vertex -624.099 105.053 44.8598 + vertex -625.54 106.997 48.7466 + vertex -627.127 106.467 45.3663 + endloop + endfacet + facet normal -0.354337 -0.883278 0.307026 + outer loop + vertex -621.104 103.7 44.4261 + vertex -622.451 105.586 48.2964 + vertex -624.099 105.053 44.8598 + endloop + endfacet + facet normal -0.349122 -0.885311 0.307146 + outer loop + vertex -618.212 102.436 44.0691 + vertex -619.353 104.217 47.9067 + vertex -621.104 103.7 44.4261 + endloop + endfacet + facet normal -0.342088 -0.882391 0.32305 + outer loop + vertex -615.484 101.24 43.6915 + vertex -618.212 102.436 44.0691 + vertex -617.252 100.958 41.0491 + endloop + endfacet + facet normal -0.344356 -0.876261 0.337025 + outer loop + vertex -619.698 102.012 41.3182 + vertex -622.467 103.231 41.658 + vertex -620.381 101.465 39.1986 + endloop + endfacet + facet normal -0.341893 -0.877263 0.336927 + outer loop + vertex -616.467 99.8581 38.9816 + vertex -617.252 100.958 41.0491 + vertex -618.355 100.677 39.1983 + endloop + endfacet + facet normal -0.336771 -0.872708 0.353505 + outer loop + vertex -614.848 99.1147 38.6883 + vertex -616.467 99.8581 38.9816 + vertex -615.792 99.1249 37.8149 + endloop + endfacet + facet normal -0.338885 -0.875204 0.345218 + outer loop + vertex -613.517 98.528 38.508 + vertex -613.727 99.1877 39.9744 + vertex -614.848 99.1147 38.6883 + endloop + endfacet + facet normal -0.334274 -0.871695 0.358343 + outer loop + vertex -612.405 98.0465 38.3741 + vertex -613.517 98.528 38.508 + vertex -613.304 98.0183 37.4662 + endloop + endfacet + facet normal -0.335259 -0.874971 0.349324 + outer loop + vertex -611.496 97.644 38.2381 + vertex -611.407 98.1945 39.702 + vertex -612.405 98.0465 38.3741 + endloop + endfacet + facet normal -0.329312 -0.872838 0.360149 + outer loop + vertex -610.827 97.3265 38.0802 + vertex -611.496 97.644 38.2381 + vertex -611.626 97.2473 37.1579 + endloop + endfacet + facet normal -0.325261 -0.878572 0.349738 + outer loop + vertex -610.365 97.1108 37.9678 + vertex -609.973 97.5453 39.4242 + vertex -610.827 97.3265 38.0802 + endloop + endfacet + facet normal -0.326222 -0.878161 0.349874 + outer loop + vertex -609.444 97.4592 39.7009 + vertex -609.973 97.5453 39.4242 + vertex -610.365 97.1108 37.9678 + endloop + endfacet + facet normal -0.397937 -0.848101 0.349814 + outer loop + vertex -609.168 97.2123 39.3484 + vertex -608.229 97.9134 42.1164 + vertex -609.227 97.331 39.5691 + endloop + endfacet + facet normal -0.318117 -0.888301 0.331246 + outer loop + vertex -609.973 97.5453 39.4242 + vertex -609.444 97.4592 39.7009 + vertex -609.095 98.278 42.2321 + endloop + endfacet + facet normal -0.330143 -0.889429 0.316104 + outer loop + vertex -607.299 99.0699 46.3366 + vertex -608.694 99.6614 46.5435 + vertex -609.095 98.278 42.2321 + endloop + endfacet + facet normal -0.349356 -0.888574 0.2973 + outer loop + vertex -604.983 99.9432 51.604 + vertex -605.904 99.8941 50.3749 + vertex -606.417 98.787 46.4631 + endloop + endfacet + facet normal -0.335494 -0.894666 0.294984 + outer loop + vertex -607.299 99.0699 46.3366 + vertex -607.191 100.649 51.2473 + vertex -608.694 99.6614 46.5435 + endloop + endfacet + facet normal -0.337193 -0.899787 0.276919 + outer loop + vertex -609.077 101.166 50.6323 + vertex -607.191 100.649 51.2473 + vertex -609.256 103.22 57.088 + endloop + endfacet + facet normal -0.349792 -0.89968 0.261193 + outer loop + vertex -609.256 103.22 57.088 + vertex -612.589 107.099 65.9861 + vertex -614.637 105.457 57.5857 + endloop + endfacet + facet normal -0.367973 -0.897043 0.244764 + outer loop + vertex -611.185 108.764 74.1987 + vertex -617.105 111.343 74.7489 + vertex -612.589 107.099 65.9861 + endloop + endfacet + facet normal -0.374803 -0.899333 0.22522 + outer loop + vertex -610.343 110.432 82.2576 + vertex -616.24 113.017 82.7706 + vertex -611.185 108.764 74.1987 + endloop + endfacet + facet normal -0.381321 -0.901022 0.206768 + outer loop + vertex -609.843 112.056 90.2599 + vertex -615.75 114.665 90.7334 + vertex -610.343 110.432 82.2576 + endloop + endfacet + facet normal -0.372879 -0.908093 0.190599 + outer loop + vertex -605.075 110.043 89.9973 + vertex -609.474 113.581 98.2471 + vertex -609.843 112.056 90.2599 + endloop + endfacet + facet normal -0.376579 -0.907069 0.188187 + outer loop + vertex -604.726 111.563 98.022 + vertex -609.474 113.581 98.2471 + vertex -605.075 110.043 89.9973 + endloop + endfacet + facet normal -0.35696 -0.919017 0.167295 + outer loop + vertex -599.763 111.282 107.112 + vertex -601.283 111.714 106.242 + vertex -600.02 109.944 99.2124 + endloop + endfacet + facet normal -0.275264 -0.946351 0.169263 + outer loop + vertex -599.763 111.282 107.112 + vertex -600.02 109.944 99.2124 + vertex -599.498 110.402 102.625 + endloop + endfacet + facet normal -0.350316 -0.924016 0.153212 + outer loop + vertex -599.763 111.282 107.112 + vertex -601.084 112.946 114.129 + vertex -601.283 111.714 106.242 + endloop + endfacet + facet normal -0.359314 -0.920954 0.150791 + outer loop + vertex -599.563 112.445 114.692 + vertex -601.084 112.946 114.129 + vertex -599.763 111.282 107.112 + endloop + endfacet + facet normal -0.316755 -0.936247 0.152014 + outer loop + vertex -599.563 112.445 114.692 + vertex -599.763 111.282 107.112 + vertex -599.256 111.411 108.965 + endloop + endfacet + facet normal -0.354824 -0.925148 0.13491 + outer loop + vertex -599.563 112.445 114.692 + vertex -600.941 114.056 122.114 + vertex -601.084 112.946 114.129 + endloop + endfacet + facet normal -0.380685 -0.91495 0.133959 + outer loop + vertex -600.941 114.056 122.114 + vertex -604.026 115.308 121.901 + vertex -601.084 112.946 114.129 + endloop + endfacet + facet normal -0.376559 -0.916363 0.13595 + outer loop + vertex -601.084 112.946 114.129 + vertex -604.026 115.308 121.901 + vertex -604.182 114.19 113.935 + endloop + endfacet + facet normal -0.38049 -0.917352 0.117015 + outer loop + vertex -600.941 114.056 122.114 + vertex -603.896 116.283 129.965 + vertex -604.026 115.308 121.901 + endloop + endfacet + facet normal -0.394146 -0.911628 0.116544 + outer loop + vertex -603.896 116.283 129.965 + vertex -608.661 118.362 130.114 + vertex -604.026 115.308 121.901 + endloop + endfacet + facet normal -0.391994 -0.912364 0.118032 + outer loop + vertex -604.026 115.308 121.901 + vertex -608.661 118.362 130.114 + vertex -608.793 117.379 122.076 + endloop + endfacet + facet normal -0.395405 -0.913213 0.0984679 + outer loop + vertex -603.896 116.283 129.965 + vertex -608.551 119.191 138.239 + vertex -608.661 118.362 130.114 + endloop + endfacet + facet normal -0.409142 -0.907188 0.0980395 + outer loop + vertex -608.551 119.191 138.239 + vertex -614.474 121.896 138.556 + vertex -608.661 118.362 130.114 + endloop + endfacet + facet normal -0.407604 -0.90774 0.0993297 + outer loop + vertex -608.661 118.362 130.114 + vertex -614.474 121.896 138.556 + vertex -614.591 121.061 130.448 + endloop + endfacet + facet normal -0.41069 -0.908347 0.0789898 + outer loop + vertex -608.551 119.191 138.239 + vertex -614.382 122.564 146.712 + vertex -614.474 121.896 138.556 + endloop + endfacet + facet normal -0.428223 -0.900255 0.0785252 + outer loop + vertex -614.382 122.564 146.712 + vertex -620.769 125.63 147.028 + vertex -614.474 121.896 138.556 + endloop + endfacet + facet normal -0.427113 -0.900693 0.079543 + outer loop + vertex -614.474 121.896 138.556 + vertex -620.769 125.63 147.028 + vertex -620.864 124.956 138.888 + endloop + endfacet + facet normal -0.429632 -0.901116 0.0583629 + outer loop + vertex -614.382 122.564 146.712 + vertex -620.699 126.123 155.162 + vertex -620.769 125.63 147.028 + endloop + endfacet + facet normal -0.452244 -0.890014 0.0578847 + outer loop + vertex -620.699 126.123 155.162 + vertex -627.031 129.357 155.415 + vertex -620.769 125.63 147.028 + endloop + endfacet + facet normal -0.451646 -0.890281 0.0584503 + outer loop + vertex -620.769 125.63 147.028 + vertex -627.031 129.357 155.415 + vertex -627.1 128.859 147.299 + endloop + endfacet + facet normal -0.45338 -0.890567 0.0365599 + outer loop + vertex -620.699 126.123 155.162 + vertex -626.985 129.665 163.495 + vertex -627.031 129.357 155.415 + endloop + endfacet + facet normal -0.479985 -0.87653 0.0361785 + outer loop + vertex -626.985 129.665 163.495 + vertex -633.045 132.992 163.704 + vertex -627.031 129.357 155.415 + endloop + endfacet + facet normal -0.479929 -0.876559 0.0362318 + outer loop + vertex -627.031 129.357 155.415 + vertex -633.045 132.992 163.704 + vertex -633.09 132.684 155.646 + endloop + endfacet + facet normal -0.480856 -0.876694 0.013614 + outer loop + vertex -626.985 129.665 163.495 + vertex -633.027 133.107 171.73 + vertex -633.045 132.992 163.704 + endloop + endfacet + facet normal -0.508997 -0.860663 0.0134459 + outer loop + vertex -633.027 133.107 171.73 + vertex -638.788 136.517 171.928 + vertex -633.045 132.992 163.704 + endloop + endfacet + facet normal -0.509561 -0.860338 0.0129133 + outer loop + vertex -633.045 132.992 163.704 + vertex -638.788 136.517 171.928 + vertex -638.801 136.405 163.925 + endloop + endfacet + facet normal -0.509618 -0.860341 -0.0101175 + outer loop + vertex -633.027 133.107 171.73 + vertex -638.8 136.431 179.925 + vertex -638.788 136.517 171.928 + endloop + endfacet + facet normal -0.538292 -0.842699 -0.00997069 + outer loop + vertex -638.8 136.431 179.925 + vertex -644.277 139.927 180.112 + vertex -638.788 136.517 171.928 + endloop + endfacet + facet normal -0.539356 -0.842006 -0.0109731 + outer loop + vertex -638.788 136.517 171.928 + vertex -644.277 139.927 180.112 + vertex -644.26 140.02 172.138 + endloop + endfacet + facet normal -0.538592 -0.841865 -0.0343827 + outer loop + vertex -638.8 136.431 179.925 + vertex -644.324 139.63 188.103 + vertex -644.277 139.927 180.112 + endloop + endfacet + facet normal -0.570074 -0.820898 -0.0337894 + outer loop + vertex -644.324 139.63 188.103 + vertex -649.506 143.223 188.256 + vertex -644.277 139.927 180.112 + endloop + endfacet + facet normal -0.571309 -0.81999 -0.0349501 + outer loop + vertex -644.277 139.927 180.112 + vertex -649.506 143.223 188.256 + vertex -649.461 143.531 180.287 + endloop + endfacet + facet normal -0.569907 -0.819588 -0.0590015 + outer loop + vertex -644.324 139.63 188.103 + vertex -649.589 142.705 196.247 + vertex -649.506 143.223 188.256 + endloop + endfacet + facet normal -0.606798 -0.792763 -0.0576465 + outer loop + vertex -649.589 142.705 196.247 + vertex -654.457 146.423 196.357 + vertex -649.506 143.223 188.256 + endloop + endfacet + facet normal -0.608452 -0.791379 -0.0592047 + outer loop + vertex -649.506 143.223 188.256 + vertex -654.457 146.423 196.357 + vertex -654.378 146.959 188.39 + endloop + endfacet + facet normal -0.651402 -0.756567 -0.0572936 + outer loop + vertex -654.457 146.423 196.357 + vertex -658.976 150.304 196.482 + vertex -654.378 146.959 188.39 + endloop + endfacet + facet normal -0.650653 -0.754887 -0.082445 + outer loop + vertex -654.457 146.423 196.357 + vertex -659.08 149.527 204.425 + vertex -658.976 150.304 196.482 + endloop + endfacet + facet normal -0.648334 -0.757114 -0.0802598 + outer loop + vertex -654.564 145.67 204.327 + vertex -659.08 149.527 204.425 + vertex -654.457 146.423 196.357 + endloop + endfacet + facet normal -0.647083 -0.754986 -0.106202 + outer loop + vertex -654.564 145.67 204.327 + vertex -659.22 148.533 212.341 + vertex -659.08 149.527 204.425 + endloop + endfacet + facet normal -0.64473 -0.757302 -0.104008 + outer loop + vertex -654.706 144.7 212.27 + vertex -659.22 148.533 212.341 + vertex -654.564 145.67 204.327 + endloop + endfacet + facet normal -0.602614 -0.79078 -0.107348 + outer loop + vertex -649.693 141.97 204.242 + vertex -654.706 144.7 212.27 + vertex -654.564 145.67 204.327 + endloop + endfacet + facet normal -0.603837 -0.793001 -0.0808153 + outer loop + vertex -649.693 141.97 204.242 + vertex -654.564 145.67 204.327 + vertex -649.589 142.705 196.247 + endloop + endfacet + facet normal -0.567095 -0.819483 -0.0827695 + outer loop + vertex -644.397 139.125 196.118 + vertex -649.693 141.97 204.242 + vertex -649.589 142.705 196.247 + endloop + endfacet + facet normal -0.564827 -0.821257 -0.0806693 + outer loop + vertex -644.505 138.412 204.139 + vertex -649.693 141.97 204.242 + vertex -644.397 139.125 196.118 + endloop + endfacet + facet normal -0.534377 -0.841256 -0.0820356 + outer loop + vertex -638.916 135.657 195.978 + vertex -644.505 138.412 204.139 + vertex -644.397 139.125 196.118 + endloop + endfacet + facet normal -0.534868 -0.84308 -0.055972 + outer loop + vertex -638.916 135.657 195.978 + vertex -644.397 139.125 196.118 + vertex -638.846 136.146 187.94 + endloop + endfacet + facet normal -0.507108 -0.860012 -0.0567626 + outer loop + vertex -633.079 132.756 187.787 + vertex -638.916 135.657 195.978 + vertex -638.846 136.146 187.94 + endloop + endfacet + facet normal -0.507178 -0.861256 -0.031769 + outer loop + vertex -633.079 132.756 187.787 + vertex -638.846 136.146 187.94 + vertex -633.041 133.03 179.749 + endloop + endfacet + facet normal -0.480123 -0.876611 -0.0321647 + outer loop + vertex -626.978 129.715 179.581 + vertex -633.079 132.756 187.787 + vertex -633.041 133.03 179.749 + endloop + endfacet + facet normal -0.479843 -0.877316 -0.0081631 + outer loop + vertex -626.978 129.715 179.581 + vertex -633.041 133.03 179.749 + vertex -626.969 129.786 171.542 + endloop + endfacet + facet normal -0.454392 -0.890764 -0.00825311 + outer loop + vertex -620.636 126.557 171.324 + vertex -626.978 129.715 179.581 + vertex -626.969 129.786 171.542 + endloop + endfacet + facet normal -0.453728 -0.891017 0.0148063 + outer loop + vertex -620.636 126.557 171.324 + vertex -626.969 129.786 171.542 + vertex -620.655 126.432 163.26 + endloop + endfacet + facet normal -0.432204 -0.901652 0.0149211 + outer loop + vertex -614.265 123.365 162.972 + vertex -620.636 126.557 171.324 + vertex -620.655 126.432 163.26 + endloop + endfacet + facet normal -0.431148 -0.901522 0.0369925 + outer loop + vertex -614.265 123.365 162.972 + vertex -620.655 126.432 163.26 + vertex -614.313 123.055 154.86 + endloop + endfacet + facet normal -0.414413 -0.909329 0.0371932 + outer loop + vertex -608.371 120.335 154.565 + vertex -614.265 123.365 162.972 + vertex -614.313 123.055 154.86 + endloop + endfacet + facet normal -0.413143 -0.908816 0.0580177 + outer loop + vertex -608.371 120.335 154.565 + vertex -614.313 123.055 154.86 + vertex -608.441 119.845 146.402 + endloop + endfacet + facet normal -0.400488 -0.914449 0.0582475 + outer loop + vertex -603.685 117.754 146.268 + vertex -608.371 120.335 154.565 + vertex -608.441 119.845 146.402 + endloop + endfacet + facet normal -0.399495 -0.913439 0.0776704 + outer loop + vertex -603.685 117.754 146.268 + vertex -608.441 119.845 146.402 + vertex -603.772 117.097 138.096 + endloop + endfacet + facet normal -0.385369 -0.91946 0.0780038 + outer loop + vertex -600.653 115.808 138.311 + vertex -603.685 117.754 146.268 + vertex -603.772 117.097 138.096 + endloop + endfacet + facet normal -0.385838 -0.917507 0.0964896 + outer loop + vertex -600.653 115.808 138.311 + vertex -603.772 117.097 138.096 + vertex -600.798 115.019 130.233 + endloop + endfacet + facet normal -0.383034 -0.91854 0.0978232 + outer loop + vertex -600.798 115.019 130.233 + vertex -603.772 117.097 138.096 + vertex -603.896 116.283 129.965 + endloop + endfacet + facet normal -0.398025 -0.913994 0.0786807 + outer loop + vertex -603.772 117.097 138.096 + vertex -608.441 119.845 146.402 + vertex -608.551 119.191 138.239 + endloop + endfacet + facet normal -0.400628 -0.914394 0.058151 + outer loop + vertex -603.586 118.232 154.461 + vertex -608.371 120.335 154.565 + vertex -603.685 117.754 146.268 + endloop + endfacet + facet normal -0.387411 -0.920061 0.0583227 + outer loop + vertex -600.568 116.456 146.499 + vertex -603.586 118.232 154.461 + vertex -603.685 117.754 146.268 + endloop + endfacet + facet normal -0.4014 -0.915132 0.0375731 + outer loop + vertex -603.586 118.232 154.461 + vertex -608.327 120.649 162.696 + vertex -608.371 120.335 154.565 + endloop + endfacet + facet normal -0.401406 -0.915129 0.0375687 + outer loop + vertex -603.547 118.55 162.629 + vertex -608.327 120.649 162.696 + vertex -603.586 118.232 154.461 + endloop + endfacet + facet normal -0.388118 -0.920837 0.037726 + outer loop + vertex -600.511 116.95 154.817 + vertex -603.547 118.55 162.629 + vertex -603.586 118.232 154.461 + endloop + endfacet + facet normal -0.401886 -0.915542 0.0164464 + outer loop + vertex -603.547 118.55 162.629 + vertex -608.302 120.784 170.791 + vertex -608.327 120.649 162.696 + endloop + endfacet + facet normal -0.414431 -0.909933 0.0163911 + outer loop + vertex -608.302 120.784 170.791 + vertex -614.242 123.494 171.051 + vertex -608.327 120.649 162.696 + endloop + endfacet + facet normal -0.415218 -0.909586 0.0157154 + outer loop + vertex -608.327 120.649 162.696 + vertex -614.242 123.494 171.051 + vertex -614.265 123.365 162.972 + endloop + endfacet + facet normal -0.415292 -0.909668 -0.00604909 + outer loop + vertex -608.302 120.784 170.791 + vertex -614.244 123.441 179.129 + vertex -614.242 123.494 171.051 + endloop + endfacet + facet normal -0.430982 -0.90234 -0.00600597 + outer loop + vertex -614.244 123.441 179.129 + vertex -620.644 126.496 179.383 + vertex -614.242 123.494 171.051 + endloop + endfacet + facet normal -0.432272 -0.901714 -0.0072227 + outer loop + vertex -614.242 123.494 171.051 + vertex -620.644 126.496 179.383 + vertex -620.636 126.557 171.324 + endloop + endfacet + facet normal -0.431561 -0.9016 -0.0295488 + outer loop + vertex -614.244 123.441 179.129 + vertex -620.678 126.248 187.466 + vertex -620.644 126.496 179.383 + endloop + endfacet + facet normal -0.451988 -0.891542 -0.029327 + outer loop + vertex -620.678 126.248 187.466 + vertex -627.018 129.456 187.642 + vertex -620.644 126.496 179.383 + endloop + endfacet + facet normal -0.453652 -0.890642 -0.0309338 + outer loop + vertex -620.644 126.496 179.383 + vertex -627.018 129.456 187.642 + vertex -626.978 129.715 179.581 + endloop + endfacet + facet normal -0.452068 -0.890356 -0.0538603 + outer loop + vertex -620.678 126.248 187.466 + vertex -627.081 128.999 195.728 + vertex -627.018 129.456 187.642 + endloop + endfacet + facet normal -0.47629 -0.87767 -0.0533305 + outer loop + vertex -627.081 128.999 195.728 + vertex -633.152 132.286 195.85 + vertex -627.018 129.456 187.642 + endloop + endfacet + facet normal -0.478476 -0.87635 -0.0554194 + outer loop + vertex -627.018 129.456 187.642 + vertex -633.152 132.286 195.85 + vertex -633.079 132.756 187.787 + endloop + endfacet + facet normal -0.475877 -0.875958 -0.0789868 + outer loop + vertex -627.081 128.999 195.728 + vertex -633.249 131.611 203.921 + vertex -633.152 132.286 195.85 + endloop + endfacet + facet normal -0.501866 -0.861414 -0.0780836 + outer loop + vertex -633.249 131.611 203.921 + vertex -639.016 134.961 204.024 + vertex -633.152 132.286 195.85 + endloop + endfacet + facet normal -0.504554 -0.85961 -0.0806023 + outer loop + vertex -633.152 132.286 195.85 + vertex -639.016 134.961 204.024 + vertex -638.916 135.657 195.978 + endloop + endfacet + facet normal -0.500994 -0.859097 -0.104674 + outer loop + vertex -633.249 131.611 203.921 + vertex -639.149 134.061 212.047 + vertex -639.016 134.961 204.024 + endloop + endfacet + facet normal -0.527636 -0.843163 -0.103326 + outer loop + vertex -639.149 134.061 212.047 + vertex -644.637 137.485 212.134 + vertex -639.016 134.961 204.024 + endloop + endfacet + facet normal -0.530747 -0.84085 -0.106202 + outer loop + vertex -639.016 134.961 204.024 + vertex -644.637 137.485 212.134 + vertex -644.505 138.412 204.139 + endloop + endfacet + facet normal -0.560727 -0.821388 -0.10444 + outer loop + vertex -644.637 137.485 212.134 + vertex -649.832 141.021 212.211 + vertex -644.505 138.412 204.139 + endloop + endfacet + facet normal -0.5592 -0.818562 -0.131343 + outer loop + vertex -644.637 137.485 212.134 + vertex -650.004 139.871 220.116 + vertex -649.832 141.021 212.211 + endloop + endfacet + facet normal -0.595133 -0.793295 -0.128451 + outer loop + vertex -650.004 139.871 220.116 + vertex -654.879 143.523 220.147 + vertex -649.832 141.021 212.211 + endloop + endfacet + facet normal -0.598169 -0.790549 -0.131248 + outer loop + vertex -649.832 141.021 212.211 + vertex -654.879 143.523 220.147 + vertex -654.706 144.7 212.27 + endloop + endfacet + facet normal -0.639729 -0.757986 -0.127295 + outer loop + vertex -654.879 143.523 220.147 + vertex -659.402 147.333 220.193 + vertex -654.706 144.7 212.27 + endloop + endfacet + facet normal -0.63748 -0.754998 -0.153611 + outer loop + vertex -654.879 143.523 220.147 + vertex -659.632 145.95 227.943 + vertex -659.402 147.333 220.193 + endloop + endfacet + facet normal -0.634216 -0.758351 -0.150577 + outer loop + vertex -655.106 142.169 227.923 + vertex -659.632 145.95 227.943 + vertex -654.879 143.523 220.147 + endloop + endfacet + facet normal -0.631409 -0.754853 -0.17754 + outer loop + vertex -655.106 142.169 227.923 + vertex -659.951 144.422 235.576 + vertex -659.632 145.95 227.943 + endloop + endfacet + facet normal -0.627227 -0.759243 -0.1736 + outer loop + vertex -655.411 140.668 235.587 + vertex -659.951 144.422 235.576 + vertex -655.106 142.169 227.923 + endloop + endfacet + facet normal -0.586558 -0.7901 -0.178022 + outer loop + vertex -650.223 138.544 227.921 + vertex -655.411 140.668 235.587 + vertex -655.106 142.169 227.923 + endloop + endfacet + facet normal -0.589197 -0.793673 -0.151425 + outer loop + vertex -650.223 138.544 227.921 + vertex -655.106 142.169 227.923 + vertex -650.004 139.871 220.116 + endloop + endfacet + facet normal -0.55369 -0.818244 -0.154608 + outer loop + vertex -644.803 136.361 220.066 + vertex -650.223 138.544 227.921 + vertex -650.004 139.871 220.116 + endloop + endfacet + facet normal -0.54986 -0.821482 -0.151065 + outer loop + vertex -645.016 135.062 227.902 + vertex -650.223 138.544 227.921 + vertex -644.803 136.361 220.066 + endloop + endfacet + facet normal -0.52099 -0.839684 -0.153298 + outer loop + vertex -639.314 132.966 220.009 + vertex -645.016 135.062 227.902 + vertex -644.803 136.361 220.066 + endloop + endfacet + facet normal -0.522763 -0.842985 -0.126866 + outer loop + vertex -639.314 132.966 220.009 + vertex -644.803 136.361 220.066 + vertex -639.149 134.061 212.047 + endloop + endfacet + facet normal -0.496546 -0.858454 -0.128449 + outer loop + vertex -633.376 130.734 211.971 + vertex -639.314 132.966 220.009 + vertex -639.149 134.061 212.047 + endloop + endfacet + facet normal -0.492949 -0.86102 -0.12508 + outer loop + vertex -633.54 129.666 219.966 + vertex -639.314 132.966 220.009 + vertex -633.376 130.734 211.971 + endloop + endfacet + facet normal -0.468148 -0.874566 -0.126378 + outer loop + vertex -627.304 127.493 211.905 + vertex -633.54 129.666 219.966 + vertex -633.376 130.734 211.971 + endloop + endfacet + facet normal -0.469346 -0.877345 -0.0999027 + outer loop + vertex -627.304 127.493 211.905 + vertex -633.376 130.734 211.971 + vertex -627.179 128.346 203.827 + endloop + endfacet + facet normal -0.446272 -0.889202 -0.100799 + outer loop + vertex -620.835 125.175 203.709 + vertex -627.304 127.493 211.905 + vertex -627.179 128.346 203.827 + endloop + endfacet + facet normal -0.446914 -0.891457 -0.0746405 + outer loop + vertex -620.835 125.175 203.709 + vertex -627.179 128.346 203.827 + vertex -620.742 125.809 195.582 + endloop + endfacet + facet normal -0.427934 -0.900681 -0.0751442 + outer loop + vertex -614.348 122.788 195.385 + vertex -620.835 125.175 203.709 + vertex -620.742 125.809 195.582 + endloop + endfacet + facet normal -0.427976 -0.902403 -0.0500504 + outer loop + vertex -614.348 122.788 195.385 + vertex -620.742 125.809 195.582 + vertex -614.283 123.209 187.24 + endloop + endfacet + facet normal -0.413275 -0.909217 -0.0502851 + outer loop + vertex -608.34 120.52 187.016 + vertex -614.348 122.788 195.385 + vertex -614.283 123.209 187.24 + endloop + endfacet + facet normal -0.412908 -0.910389 -0.0264341 + outer loop + vertex -608.34 120.52 187.016 + vertex -614.283 123.209 187.24 + vertex -608.313 120.743 178.886 + endloop + endfacet + facet normal -0.401324 -0.915552 -0.0265364 + outer loop + vertex -603.529 118.649 178.807 + vertex -608.34 120.52 187.016 + vertex -608.313 120.743 178.886 + endloop + endfacet + facet normal -0.40116 -0.915997 -0.00453739 + outer loop + vertex -603.529 118.649 178.807 + vertex -608.313 120.743 178.886 + vertex -603.529 118.689 170.725 + endloop + endfacet + facet normal -0.388257 -0.92154 -0.00456543 + outer loop + vertex -600.453 117.391 171.038 + vertex -603.529 118.649 178.807 + vertex -603.529 118.689 170.725 + endloop + endfacet + facet normal -0.401989 -0.91563 -0.00511564 + outer loop + vertex -603.529 118.689 170.725 + vertex -608.313 120.743 178.886 + vertex -608.302 120.784 170.791 + endloop + endfacet + facet normal -0.400351 -0.915997 -0.0258642 + outer loop + vertex -603.579 118.441 186.946 + vertex -608.34 120.52 187.016 + vertex -603.529 118.649 178.807 + endloop + endfacet + facet normal -0.38807 -0.921265 -0.0259232 + outer loop + vertex -600.464 117.35 179.084 + vertex -603.579 118.441 186.946 + vertex -603.529 118.649 178.807 + endloop + endfacet + facet normal -0.400295 -0.915102 -0.048501 + outer loop + vertex -603.579 118.441 186.946 + vertex -608.412 120.118 195.184 + vertex -608.34 120.52 187.016 + endloop + endfacet + facet normal -0.398205 -0.916088 -0.0470742 + outer loop + vertex -603.623 118.04 195.108 + vertex -608.412 120.118 195.184 + vertex -603.579 118.441 186.946 + endloop + endfacet + facet normal -0.386427 -0.921109 -0.0472578 + outer loop + vertex -600.484 117.128 187.224 + vertex -603.623 118.04 195.108 + vertex -603.579 118.441 186.946 + endloop + endfacet + facet normal -0.397965 -0.914671 -0.0707145 + outer loop + vertex -603.623 118.04 195.108 + vertex -608.491 119.521 203.35 + vertex -608.412 120.118 195.184 + endloop + endfacet + facet normal -0.408365 -0.910094 -0.0704798 + outer loop + vertex -608.491 119.521 203.35 + vertex -614.436 122.174 203.539 + vertex -608.412 120.118 195.184 + endloop + endfacet + facet normal -0.411099 -0.908679 -0.0727983 + outer loop + vertex -608.412 120.118 195.184 + vertex -614.436 122.174 203.539 + vertex -614.348 122.788 195.385 + endloop + endfacet + facet normal -0.408173 -0.907845 -0.095981 + outer loop + vertex -608.491 119.521 203.35 + vertex -614.555 121.369 211.665 + vertex -614.436 122.174 203.539 + endloop + endfacet + facet normal -0.421572 -0.901744 -0.0955728 + outer loop + vertex -614.555 121.369 211.665 + vertex -620.958 124.346 211.815 + vertex -614.436 122.174 203.539 + endloop + endfacet + facet normal -0.424691 -0.899964 -0.0984983 + outer loop + vertex -614.436 122.174 203.539 + vertex -620.958 124.346 211.815 + vertex -620.835 125.175 203.709 + endloop + endfacet + facet normal -0.420882 -0.898952 -0.12142 + outer loop + vertex -614.555 121.369 211.665 + vertex -621.112 123.33 219.87 + vertex -620.958 124.346 211.815 + endloop + endfacet + facet normal -0.438756 -0.890465 -0.12069 + outer loop + vertex -621.112 123.33 219.87 + vertex -627.461 126.45 219.931 + vertex -620.958 124.346 211.815 + endloop + endfacet + facet normal -0.442223 -0.888287 -0.124033 + outer loop + vertex -620.958 124.346 211.815 + vertex -627.461 126.45 219.931 + vertex -627.304 127.493 211.905 + endloop + endfacet + facet normal -0.43745 -0.887304 -0.146046 + outer loop + vertex -621.112 123.33 219.87 + vertex -627.661 125.24 227.886 + vertex -627.461 126.45 219.931 + endloop + endfacet + facet normal -0.459025 -0.87652 -0.144946 + outer loop + vertex -627.661 125.24 227.886 + vertex -633.74 128.425 227.876 + vertex -627.461 126.45 219.931 + endloop + endfacet + facet normal -0.46306 -0.873743 -0.148826 + outer loop + vertex -627.461 126.45 219.931 + vertex -633.74 128.425 227.876 + vertex -633.54 129.666 219.966 + endloop + endfacet + facet normal -0.487212 -0.860755 -0.147398 + outer loop + vertex -633.74 128.425 227.876 + vertex -639.519 131.695 227.88 + vertex -633.54 129.666 219.966 + endloop + endfacet + facet normal -0.485205 -0.857177 -0.172696 + outer loop + vertex -633.74 128.425 227.876 + vertex -639.78 130.277 235.65 + vertex -639.519 131.695 227.88 + endloop + endfacet + facet normal -0.510003 -0.843015 -0.170944 + outer loop + vertex -639.78 130.277 235.65 + vertex -645.293 133.616 235.634 + vertex -639.519 131.695 227.88 + endloop + endfacet + facet normal -0.514762 -0.839192 -0.175435 + outer loop + vertex -639.519 131.695 227.88 + vertex -645.293 133.616 235.634 + vertex -645.016 135.062 227.902 + endloop + endfacet + facet normal -0.543112 -0.82161 -0.173162 + outer loop + vertex -645.293 133.616 235.634 + vertex -650.513 137.07 235.616 + vertex -645.016 135.062 227.902 + endloop + endfacet + facet normal -0.540264 -0.817442 -0.199759 + outer loop + vertex -645.293 133.616 235.634 + vertex -650.906 135.471 243.222 + vertex -650.513 137.07 235.616 + endloop + endfacet + facet normal -0.57354 -0.795187 -0.196801 + outer loop + vertex -650.906 135.471 243.222 + vertex -655.837 139.042 243.166 + vertex -650.513 137.07 235.616 + endloop + endfacet + facet normal -0.579038 -0.789863 -0.202068 + outer loop + vertex -650.513 137.07 235.616 + vertex -655.837 139.042 243.166 + vertex -655.411 140.668 235.587 + endloop + endfacet + facet normal -0.618377 -0.760534 -0.197985 + outer loop + vertex -655.837 139.042 243.166 + vertex -660.401 142.764 243.121 + vertex -655.411 140.668 235.587 + endloop + endfacet + facet normal -0.613611 -0.755094 -0.230898 + outer loop + vertex -655.837 139.042 243.166 + vertex -661.027 140.979 250.626 + vertex -660.401 142.764 243.121 + endloop + endfacet + facet normal -0.652312 -0.723296 -0.226566 + outer loop + vertex -661.027 140.979 250.626 + vertex -665.173 144.723 250.606 + vertex -660.401 142.764 243.121 + endloop + endfacet + facet normal -0.659104 -0.715028 -0.233059 + outer loop + vertex -660.401 142.764 243.121 + vertex -665.173 144.723 250.606 + vertex -664.518 146.553 243.139 + endloop + endfacet + facet normal -0.664274 -0.72081 -0.197924 + outer loop + vertex -660.401 142.764 243.121 + vertex -664.518 146.553 243.139 + vertex -659.951 144.422 235.576 + endloop + endfacet + facet normal -0.668959 -0.715233 -0.202325 + outer loop + vertex -659.951 144.422 235.576 + vertex -664.518 146.553 243.139 + vertex -664.055 148.244 235.634 + endloop + endfacet + facet normal -0.672645 -0.719645 -0.172219 + outer loop + vertex -659.951 144.422 235.576 + vertex -664.055 148.244 235.634 + vertex -659.632 145.95 227.943 + endloop + endfacet + facet normal -0.676452 -0.715214 -0.175731 + outer loop + vertex -659.632 145.95 227.943 + vertex -664.055 148.244 235.634 + vertex -663.721 149.798 228.025 + endloop + endfacet + facet normal -0.67924 -0.71876 -0.148382 + outer loop + vertex -659.632 145.95 227.943 + vertex -663.721 149.798 228.025 + vertex -659.402 147.333 220.193 + endloop + endfacet + facet normal -0.682797 -0.714703 -0.151621 + outer loop + vertex -659.402 147.333 220.193 + vertex -663.721 149.798 228.025 + vertex -663.486 151.212 220.296 + endloop + endfacet + facet normal -0.68496 -0.717672 -0.125602 + outer loop + vertex -659.402 147.333 220.193 + vertex -663.486 151.212 220.296 + vertex -659.22 148.533 212.341 + endloop + endfacet + facet normal -0.687543 -0.71478 -0.127961 + outer loop + vertex -659.22 148.533 212.341 + vertex -663.486 151.212 220.296 + vertex -663.308 152.442 212.471 + endloop + endfacet + facet normal -0.689179 -0.717346 -0.102215 + outer loop + vertex -659.22 148.533 212.341 + vertex -663.308 152.442 212.471 + vertex -659.08 149.527 204.425 + endloop + endfacet + facet normal -0.692113 -0.714122 -0.104925 + outer loop + vertex -659.08 149.527 204.425 + vertex -663.308 152.442 212.471 + vertex -663.162 153.459 204.585 + endloop + endfacet + facet normal -0.693243 -0.716335 -0.0792342 + outer loop + vertex -659.08 149.527 204.425 + vertex -663.162 153.459 204.585 + vertex -658.976 150.304 196.482 + endloop + endfacet + facet normal -0.695861 -0.713516 -0.0816847 + outer loop + vertex -658.976 150.304 196.482 + vertex -663.162 153.459 204.585 + vertex -663.064 154.27 196.668 + endloop + endfacet + facet normal -0.696474 -0.715295 -0.0572445 + outer loop + vertex -658.976 150.304 196.482 + vertex -663.064 154.27 196.668 + vertex -658.896 150.862 188.539 + endloop + endfacet + facet normal -0.699028 -0.7126 -0.0596838 + outer loop + vertex -658.896 150.862 188.539 + vertex -663.064 154.27 196.668 + vertex -662.99 154.861 188.747 + endloop + endfacet + facet normal -0.699205 -0.714066 -0.0349522 + outer loop + vertex -658.896 150.862 188.539 + vertex -662.99 154.861 188.747 + vertex -658.857 151.212 180.615 + endloop + endfacet + facet normal -0.701774 -0.711415 -0.0374469 + outer loop + vertex -658.857 151.212 180.615 + vertex -662.99 154.861 188.747 + vertex -662.949 155.236 180.844 + endloop + endfacet + facet normal -0.70152 -0.712523 -0.01345 + outer loop + vertex -658.857 151.212 180.615 + vertex -662.949 155.236 180.844 + vertex -658.846 151.351 172.705 + endloop + endfacet + facet normal -0.7031 -0.710932 -0.0150056 + outer loop + vertex -658.846 151.351 172.705 + vertex -662.949 155.236 180.844 + vertex -662.948 155.402 172.954 + endloop + endfacet + facet normal -0.702415 -0.711711 0.00894048 + outer loop + vertex -658.846 151.351 172.705 + vertex -662.948 155.402 172.954 + vertex -658.873 151.278 164.782 + endloop + endfacet + facet normal -0.704102 -0.710062 0.007267 + outer loop + vertex -658.873 151.278 164.782 + vertex -662.948 155.402 172.954 + vertex -662.968 155.341 165.047 + endloop + endfacet + facet normal -0.70304 -0.7105 0.0304018 + outer loop + vertex -658.873 151.278 164.782 + vertex -662.968 155.341 165.047 + vertex -658.923 150.986 156.824 + endloop + endfacet + facet normal -0.703496 -0.710068 0.0299486 + outer loop + vertex -658.923 150.986 156.824 + vertex -662.968 155.341 165.047 + vertex -663.032 155.069 157.102 + endloop + endfacet + facet normal -0.702046 -0.710165 0.052877 + outer loop + vertex -658.923 150.986 156.824 + vertex -663.032 155.069 157.102 + vertex -659.004 150.472 148.834 + endloop + endfacet + facet normal -0.701956 -0.710248 0.0529672 + outer loop + vertex -659.004 150.472 148.834 + vertex -663.032 155.069 157.102 + vertex -663.102 154.544 149.127 + endloop + endfacet + facet normal -0.700208 -0.710041 0.0744962 + outer loop + vertex -659.004 150.472 148.834 + vertex -663.102 154.544 149.127 + vertex -659.102 149.731 140.851 + endloop + endfacet + facet normal -0.698421 -0.711612 0.0762732 + outer loop + vertex -659.102 149.731 140.851 + vertex -663.102 154.544 149.127 + vertex -663.199 153.785 141.168 + endloop + endfacet + facet normal -0.696359 -0.711133 0.0968167 + outer loop + vertex -659.102 149.731 140.851 + vertex -663.199 153.785 141.168 + vertex -659.228 148.776 132.933 + endloop + endfacet + facet normal -0.69406 -0.713064 0.0991004 + outer loop + vertex -659.228 148.776 132.933 + vertex -663.199 153.785 141.168 + vertex -663.316 152.803 133.279 + endloop + endfacet + facet normal -0.69168 -0.712347 0.118917 + outer loop + vertex -659.228 148.776 132.933 + vertex -663.316 152.803 133.279 + vertex -659.384 147.625 125.126 + endloop + endfacet + facet normal -0.688858 -0.714606 0.121713 + outer loop + vertex -659.384 147.625 125.126 + vertex -663.316 152.803 133.279 + vertex -663.47 151.627 125.499 + endloop + endfacet + facet normal -0.686094 -0.713624 0.14148 + outer loop + vertex -659.384 147.625 125.126 + vertex -663.47 151.627 125.499 + vertex -659.589 146.296 117.43 + endloop + endfacet + facet normal -0.68251 -0.716348 0.145004 + outer loop + vertex -659.589 146.296 117.43 + vertex -663.47 151.627 125.499 + vertex -663.672 150.265 117.824 + endloop + endfacet + facet normal -0.67939 -0.715084 0.164573 + outer loop + vertex -659.589 146.296 117.43 + vertex -663.672 150.265 117.824 + vertex -659.867 144.801 109.791 + endloop + endfacet + facet normal -0.674795 -0.718394 0.169001 + outer loop + vertex -659.867 144.801 109.791 + vertex -663.672 150.265 117.824 + vertex -663.953 148.737 110.204 + endloop + endfacet + facet normal -0.671339 -0.716832 0.188299 + outer loop + vertex -659.867 144.801 109.791 + vertex -663.953 148.737 110.204 + vertex -660.25 143.152 102.146 + endloop + endfacet + facet normal -0.666058 -0.720438 0.193225 + outer loop + vertex -660.25 143.152 102.146 + vertex -663.953 148.737 110.204 + vertex -664.345 147.058 102.593 + endloop + endfacet + facet normal -0.662298 -0.718636 0.211953 + outer loop + vertex -660.25 143.152 102.146 + vertex -664.345 147.058 102.593 + vertex -660.766 141.364 94.4685 + endloop + endfacet + facet normal -0.655367 -0.723121 0.21815 + outer loop + vertex -660.766 141.364 94.4685 + vertex -664.345 147.058 102.593 + vertex -664.875 145.24 94.9743 + endloop + endfacet + facet normal -0.650691 -0.720847 0.238705 + outer loop + vertex -660.766 141.364 94.4685 + vertex -664.875 145.24 94.9743 + vertex -661.475 139.457 86.7799 + endloop + endfacet + facet normal -0.641199 -0.72663 0.246724 + outer loop + vertex -661.475 139.457 86.7799 + vertex -664.875 145.24 94.9743 + vertex -665.629 143.313 87.3382 + endloop + endfacet + facet normal -0.635609 -0.723775 0.268609 + outer loop + vertex -661.475 139.457 86.7799 + vertex -665.629 143.313 87.3382 + vertex -662.448 137.461 79.0999 + endloop + endfacet + facet normal -0.621242 -0.731911 0.279937 + outer loop + vertex -662.448 137.461 79.0999 + vertex -665.629 143.313 87.3382 + vertex -666.72 141.286 79.6196 + endloop + endfacet + facet normal -0.615311 -0.728249 0.301737 + outer loop + vertex -662.448 137.461 79.0999 + vertex -666.72 141.286 79.6196 + vertex -663.788 135.426 71.4538 + endloop + endfacet + facet normal -0.595953 -0.738279 0.315886 + outer loop + vertex -663.788 135.426 71.4538 + vertex -666.72 141.286 79.6196 + vertex -668.346 139.246 71.7835 + endloop + endfacet + facet normal -0.590726 -0.733748 0.335645 + outer loop + vertex -663.788 135.426 71.4538 + vertex -668.346 139.246 71.7835 + vertex -665.578 133.464 64.0159 + endloop + endfacet + facet normal -0.567022 -0.744616 0.352183 + outer loop + vertex -665.578 133.464 64.0159 + vertex -668.346 139.246 71.7835 + vertex -670.717 137.433 64.1325 + endloop + endfacet + facet normal -0.562144 -0.73887 0.371571 + outer loop + vertex -665.578 133.464 64.0159 + vertex -670.717 137.433 64.1325 + vertex -667.704 131.62 57.1312 + endloop + endfacet + facet normal -0.529934 -0.750419 0.39502 + outer loop + vertex -667.704 131.62 57.1312 + vertex -670.717 137.433 64.1325 + vertex -673.041 135.218 56.8061 + endloop + endfacet + facet normal -0.527235 -0.74522 0.408252 + outer loop + vertex -667.704 131.62 57.1312 + vertex -673.041 135.218 56.8061 + vertex -669.922 130.043 51.3876 + endloop + endfacet + facet normal -0.494604 -0.752828 0.434301 + outer loop + vertex -669.922 130.043 51.3876 + vertex -673.041 135.218 56.8061 + vertex -674.939 133.148 51.0584 + endloop + endfacet + facet normal -0.493237 -0.74993 0.440819 + outer loop + vertex -669.922 130.043 51.3876 + vertex -674.939 133.148 51.0584 + vertex -672.025 129.02 47.2957 + endloop + endfacet + facet normal -0.474793 -0.751952 0.457319 + outer loop + vertex -672.025 129.02 47.2957 + vertex -674.939 133.148 51.0584 + vertex -677.326 132.449 47.4302 + endloop + endfacet + facet normal -0.645515 -0.715973 -0.265882 + outer loop + vertex -661.027 140.979 250.626 + vertex -666.043 142.748 258.039 + vertex -665.173 144.723 250.606 + endloop + endfacet + facet normal -0.635593 -0.728262 -0.256236 + outer loop + vertex -661.855 139.084 258.064 + vertex -666.043 142.748 258.039 + vertex -661.027 140.979 250.626 + endloop + endfacet + facet normal -0.600304 -0.7565 -0.259505 + outer loop + vertex -656.422 137.301 250.693 + vertex -661.855 139.084 258.064 + vertex -661.027 140.979 250.626 + endloop + endfacet + facet normal -0.590678 -0.767265 -0.249807 + outer loop + vertex -657.202 135.474 258.15 + vertex -661.855 139.084 258.064 + vertex -656.422 137.301 250.693 + endloop + endfacet + facet normal -0.557106 -0.79123 -0.252165 + outer loop + vertex -651.435 133.768 250.76 + vertex -657.202 135.474 258.15 + vertex -656.422 137.301 250.693 + endloop + endfacet + facet normal -0.56197 -0.79747 -0.219616 + outer loop + vertex -651.435 133.768 250.76 + vertex -656.422 137.301 250.693 + vertex -650.906 135.471 243.222 + endloop + endfacet + facet normal -0.531133 -0.817684 -0.222017 + outer loop + vertex -645.649 132.045 243.266 + vertex -651.435 133.768 250.76 + vertex -650.906 135.471 243.222 + endloop + endfacet + facet normal -0.523805 -0.824302 -0.214837 + outer loop + vertex -646.128 130.38 250.82 + vertex -651.435 133.768 250.76 + vertex -645.649 132.045 243.266 + endloop + endfacet + facet normal -0.498773 -0.839246 -0.216543 + outer loop + vertex -640.111 128.739 243.321 + vertex -646.128 130.38 250.82 + vertex -645.649 132.045 243.266 + endloop + endfacet + facet normal -0.501703 -0.843727 -0.190838 + outer loop + vertex -640.111 128.739 243.321 + vertex -645.649 132.045 243.266 + vertex -639.78 130.277 235.65 + endloop + endfacet + facet normal -0.478098 -0.856958 -0.19247 + outer loop + vertex -633.99 127.038 235.692 + vertex -640.111 128.739 243.321 + vertex -639.78 130.277 235.65 + endloop + endfacet + facet normal -0.472294 -0.861416 -0.186818 + outer loop + vertex -634.307 125.538 243.41 + vertex -640.111 128.739 243.321 + vertex -633.99 127.038 235.692 + endloop + endfacet + facet normal -0.450455 -0.872754 -0.188122 + outer loop + vertex -627.904 123.884 235.75 + vertex -634.307 125.538 243.41 + vertex -633.99 127.038 235.692 + endloop + endfacet + facet normal -0.452534 -0.876342 -0.165037 + outer loop + vertex -627.904 123.884 235.75 + vertex -633.99 127.038 235.692 + vertex -627.661 125.24 227.886 + endloop + endfacet + facet normal -0.43201 -0.886434 -0.166142 + outer loop + vertex -621.302 122.146 227.854 + vertex -627.904 123.884 235.75 + vertex -627.661 125.24 227.886 + endloop + endfacet + facet normal -0.427366 -0.889523 -0.161578 + outer loop + vertex -621.543 120.825 235.765 + vertex -627.904 123.884 235.75 + vertex -621.302 122.146 227.854 + endloop + endfacet + facet normal -0.411304 -0.896928 -0.162327 + outer loop + vertex -614.883 119.223 227.74 + vertex -621.543 120.825 235.765 + vertex -621.302 122.146 227.854 + endloop + endfacet + facet normal -0.412425 -0.900292 -0.139209 + outer loop + vertex -614.883 119.223 227.74 + vertex -621.302 122.146 227.854 + vertex -614.704 120.379 219.735 + endloop + endfacet + facet normal -0.400231 -0.905701 -0.139717 + outer loop + vertex -608.744 117.771 219.571 + vertex -614.883 119.223 227.74 + vertex -614.704 120.379 219.735 + endloop + endfacet + facet normal -0.400922 -0.908809 -0.115443 + outer loop + vertex -608.744 117.771 219.571 + vertex -614.704 120.379 219.735 + vertex -608.612 118.739 211.489 + endloop + endfacet + facet normal -0.391577 -0.912833 -0.115772 + outer loop + vertex -603.819 116.687 211.462 + vertex -608.744 117.771 219.571 + vertex -608.612 118.739 211.489 + endloop + endfacet + facet normal -0.392456 -0.915206 -0.0915165 + outer loop + vertex -603.819 116.687 211.462 + vertex -608.612 118.739 211.489 + vertex -603.719 117.461 203.284 + endloop + endfacet + facet normal -0.382533 -0.919371 -0.0917888 + outer loop + vertex -600.621 116.146 203.546 + vertex -603.819 116.687 211.462 + vertex -603.719 117.461 203.284 + endloop + endfacet + facet normal -0.395633 -0.913621 -0.093658 + outer loop + vertex -603.719 117.461 203.284 + vertex -608.612 118.739 211.489 + vertex -608.491 119.521 203.35 + endloop + endfacet + facet normal -0.388518 -0.914399 -0.113705 + outer loop + vertex -603.973 115.742 219.587 + vertex -608.744 117.771 219.571 + vertex -603.819 116.687 211.462 + endloop + endfacet + facet normal -0.377975 -0.918769 -0.114014 + outer loop + vertex -600.77 115.377 211.907 + vertex -603.973 115.742 219.587 + vertex -603.819 116.687 211.462 + endloop + endfacet + facet normal -0.387314 -0.911754 -0.136722 + outer loop + vertex -603.973 115.742 219.587 + vertex -608.924 116.646 227.583 + vertex -608.744 117.771 219.571 + endloop + endfacet + facet normal -0.383693 -0.913648 -0.134265 + outer loop + vertex -604.139 114.634 227.603 + vertex -608.924 116.646 227.583 + vertex -603.973 115.742 219.587 + endloop + endfacet + facet normal -0.372534 -0.918196 -0.134662 + outer loop + vertex -600.915 114.423 220.122 + vertex -604.139 114.634 227.603 + vertex -603.973 115.742 219.587 + endloop + endfacet + facet normal -0.38246 -0.91092 -0.154756 + outer loop + vertex -604.139 114.634 227.603 + vertex -609.149 115.39 235.531 + vertex -608.924 116.646 227.583 + endloop + endfacet + facet normal -0.390798 -0.907428 -0.154441 + outer loop + vertex -609.149 115.39 235.531 + vertex -615.124 117.939 235.674 + vertex -608.924 116.646 227.583 + endloop + endfacet + facet normal -0.395507 -0.904685 -0.158488 + outer loop + vertex -608.924 116.646 227.583 + vertex -615.124 117.939 235.674 + vertex -614.883 119.223 227.74 + endloop + endfacet + facet normal -0.389919 -0.90428 -0.173901 + outer loop + vertex -609.149 115.39 235.531 + vertex -615.446 116.565 243.54 + vertex -615.124 117.939 235.674 + endloop + endfacet + facet normal -0.400134 -0.899874 -0.17355 + outer loop + vertex -615.446 116.565 243.54 + vertex -621.867 119.412 243.586 + vertex -615.124 117.939 235.674 + endloop + endfacet + facet normal -0.40559 -0.896387 -0.17885 + outer loop + vertex -615.124 117.939 235.674 + vertex -621.867 119.412 243.586 + vertex -621.543 120.825 235.765 + endloop + endfacet + facet normal -0.420308 -0.889701 -0.178252 + outer loop + vertex -621.867 119.412 243.586 + vertex -628.222 122.427 243.522 + vertex -621.543 120.825 235.765 + endloop + endfacet + facet normal -0.418457 -0.886232 -0.198712 + outer loop + vertex -621.867 119.412 243.586 + vertex -628.661 120.913 251.196 + vertex -628.222 122.427 243.522 + endloop + endfacet + facet normal -0.435968 -0.877895 -0.19807 + outer loop + vertex -628.661 120.913 251.196 + vertex -634.747 123.972 251.034 + vertex -628.222 122.427 243.522 + endloop + endfacet + facet normal -0.442611 -0.873002 -0.204847 + outer loop + vertex -628.222 122.427 243.522 + vertex -634.747 123.972 251.034 + vertex -634.307 125.538 243.41 + endloop + endfacet + facet normal -0.462793 -0.8627 -0.203893 + outer loop + vertex -634.747 123.972 251.034 + vertex -640.558 127.121 250.902 + vertex -634.307 125.538 243.41 + endloop + endfacet + facet normal -0.45974 -0.858101 -0.228697 + outer loop + vertex -634.747 123.972 251.034 + vertex -641.198 125.465 258.402 + vertex -640.558 127.121 250.902 + endloop + endfacet + facet normal -0.4796 -0.847344 -0.228017 + outer loop + vertex -641.198 125.465 258.402 + vertex -646.799 128.662 258.3 + vertex -640.558 127.121 250.902 + endloop + endfacet + facet normal -0.488153 -0.840032 -0.236755 + outer loop + vertex -640.558 127.121 250.902 + vertex -646.799 128.662 258.3 + vertex -646.128 130.38 250.82 + endloop + endfacet + facet normal -0.511121 -0.826554 -0.23572 + outer loop + vertex -646.799 128.662 258.3 + vertex -652.156 131.995 258.23 + vertex -646.128 130.38 250.82 + endloop + endfacet + facet normal -0.506311 -0.819502 -0.268452 + outer loop + vertex -646.799 128.662 258.3 + vertex -653.147 130.189 265.61 + vertex -652.156 131.995 258.23 + endloop + endfacet + facet normal -0.532654 -0.802811 -0.267908 + outer loop + vertex -653.147 130.189 265.61 + vertex -658.24 133.609 265.49 + vertex -652.156 131.995 258.23 + endloop + endfacet + facet normal -0.542232 -0.792854 -0.278149 + outer loop + vertex -652.156 131.995 258.23 + vertex -658.24 133.609 265.49 + vertex -657.202 135.474 258.15 + endloop + endfacet + facet normal -0.57362 -0.770863 -0.277002 + outer loop + vertex -658.24 133.609 265.49 + vertex -662.914 137.145 265.326 + vertex -657.202 135.474 258.15 + endloop + endfacet + facet normal -0.565124 -0.761502 -0.31741 + outer loop + vertex -658.24 133.609 265.49 + vertex -664.292 135.249 272.329 + vertex -662.914 137.145 265.326 + endloop + endfacet + facet normal -0.598072 -0.73608 -0.317012 + outer loop + vertex -664.292 135.249 272.329 + vertex -668.377 138.721 271.974 + vertex -662.914 137.145 265.326 + endloop + endfacet + facet normal -0.607386 -0.723715 -0.327597 + outer loop + vertex -662.914 137.145 265.326 + vertex -668.377 138.721 271.974 + vertex -667.101 140.7 265.237 + endloop + endfacet + facet normal -0.616644 -0.733565 -0.285716 + outer loop + vertex -662.914 137.145 265.326 + vertex -667.101 140.7 265.237 + vertex -661.855 139.084 258.064 + endloop + endfacet + facet normal -0.636812 -0.698782 -0.325844 + outer loop + vertex -668.377 138.721 271.974 + vertex -671.941 141.969 271.974 + vertex -667.101 140.7 265.237 + endloop + endfacet + facet normal -0.647939 -0.683199 -0.336771 + outer loop + vertex -667.101 140.7 265.237 + vertex -671.941 141.969 271.974 + vertex -670.782 144.107 265.407 + endloop + endfacet + facet normal -0.555848 -0.772712 -0.306513 + outer loop + vertex -659.601 131.742 272.664 + vertex -664.292 135.249 272.329 + vertex -658.24 133.609 265.49 + endloop + endfacet + facet normal -0.544952 -0.762232 -0.349327 + outer loop + vertex -659.601 131.742 272.664 + vertex -666.109 133.429 279.135 + vertex -664.292 135.249 272.329 + endloop + endfacet + facet normal -0.57808 -0.736492 -0.351288 + outer loop + vertex -666.109 133.429 279.135 + vertex -670.113 136.964 278.313 + vertex -664.292 135.249 272.329 + endloop + endfacet + facet normal -0.585393 -0.725698 -0.361493 + outer loop + vertex -664.292 135.249 272.329 + vertex -670.113 136.964 278.313 + vertex -668.377 138.721 271.974 + endloop + endfacet + facet normal -0.619237 -0.696442 -0.362648 + outer loop + vertex -670.113 136.964 278.313 + vertex -673.23 140.104 277.604 + vertex -668.377 138.721 271.974 + endloop + endfacet + facet normal -0.62561 -0.686497 -0.370586 + outer loop + vertex -668.377 138.721 271.974 + vertex -673.23 140.104 277.604 + vertex -671.941 141.969 271.974 + endloop + endfacet + facet normal -0.648446 -0.665862 -0.368979 + outer loop + vertex -673.23 140.104 277.604 + vertex -675.933 142.691 277.687 + vertex -671.941 141.969 271.974 + endloop + endfacet + facet normal -0.662617 -0.644464 -0.381582 + outer loop + vertex -675.364 144.853 273.047 + vertex -671.941 141.969 271.974 + vertex -675.933 142.691 277.687 + endloop + endfacet + facet normal -0.666571 -0.641035 -0.380469 + outer loop + vertex -678.017 144.253 278.706 + vertex -675.364 144.853 273.047 + vertex -675.933 142.691 277.687 + endloop + endfacet + facet normal -0.666581 -0.606839 -0.432916 + outer loop + vertex -675.933 142.691 277.687 + vertex -679.104 143.1 281.996 + vertex -678.017 144.253 278.706 + endloop + endfacet + facet normal -0.667264 -0.60611 -0.432886 + outer loop + vertex -679.104 143.1 281.996 + vertex -680.383 144.43 282.105 + vertex -678.017 144.253 278.706 + endloop + endfacet + facet normal -0.664456 -0.61074 -0.430691 + outer loop + vertex -678.017 144.253 278.706 + vertex -680.383 144.43 282.105 + vertex -678.801 145.532 278.102 + endloop + endfacet + facet normal -0.685367 -0.586092 -0.432168 + outer loop + vertex -680.383 144.43 282.105 + vertex -681.189 145.322 282.175 + vertex -678.801 145.532 278.102 + endloop + endfacet + facet normal -0.701433 -0.560494 -0.440271 + outer loop + vertex -678.801 145.532 278.102 + vertex -681.189 145.322 282.175 + vertex -679.842 146.29 278.796 + endloop + endfacet + facet normal -0.697571 -0.565398 -0.440136 + outer loop + vertex -681.189 145.322 282.175 + vertex -681.542 145.832 282.078 + vertex -679.842 146.29 278.796 + endloop + endfacet + facet normal -0.655169 -0.623708 -0.426312 + outer loop + vertex -679.842 146.29 278.796 + vertex -681.542 145.832 282.078 + vertex -679.774 146.871 277.84 + endloop + endfacet + facet normal -0.769367 -0.467255 -0.4356 + outer loop + vertex -681.542 145.832 282.078 + vertex -681.507 146.001 281.835 + vertex -679.774 146.871 277.84 + endloop + endfacet + facet normal -0.846064 -0.308973 -0.43441 + outer loop + vertex -679.774 146.871 277.84 + vertex -681.507 146.001 281.835 + vertex -680.065 146.842 278.428 + endloop + endfacet + facet normal 0.735508 0.516227 0.438791 + outer loop + vertex -681.507 146.001 281.835 + vertex -681.438 145.924 281.81 + vertex -680.065 146.842 278.428 + endloop + endfacet + facet normal 0.37565 0.844477 0.381766 + outer loop + vertex -680.065 146.842 278.428 + vertex -681.438 145.924 281.81 + vertex -680.429 146.494 279.557 + endloop + endfacet + facet normal 0.535974 0.742371 0.402017 + outer loop + vertex -680.065 146.842 278.428 + vertex -680.429 146.494 279.557 + vertex -679.431 147.382 276.587 + endloop + endfacet + facet normal 0.723706 0.491383 0.484553 + outer loop + vertex -681.507 146.001 281.835 + vertex -682.745 145.274 284.421 + vertex -681.438 145.924 281.81 + endloop + endfacet + facet normal 0.531871 0.713997 0.455325 + outer loop + vertex -683.188 145.117 285.185 + vertex -682.745 145.274 284.421 + vertex -681.507 146.001 281.835 + endloop + endfacet + facet normal 0.857441 -0.26069 0.443661 + outer loop + vertex -683.188 145.117 285.185 + vertex -684.524 144.494 287.402 + vertex -682.745 145.274 284.421 + endloop + endfacet + facet normal 0.743661 0.374882 0.553562 + outer loop + vertex -685.213 144.254 288.49 + vertex -684.524 144.494 287.402 + vertex -683.188 145.117 285.185 + endloop + endfacet + facet normal -0.635193 -0.557283 -0.534757 + outer loop + vertex -683.278 144.857 285.563 + vertex -685.213 144.254 288.49 + vertex -683.188 145.117 285.185 + endloop + endfacet + facet normal -0.732595 -0.46664 -0.495532 + outer loop + vertex -683.278 144.857 285.563 + vertex -683.188 145.117 285.185 + vertex -681.542 145.832 282.078 + endloop + endfacet + facet normal -0.687552 -0.472005 -0.5518 + outer loop + vertex -685.303 144.006 288.814 + vertex -685.213 144.254 288.49 + vertex -683.278 144.857 285.563 + endloop + endfacet + facet normal -0.651946 -0.527955 -0.54427 + outer loop + vertex -682.875 144.325 285.596 + vertex -685.303 144.006 288.814 + vertex -683.278 144.857 285.563 + endloop + endfacet + facet normal -0.678389 -0.544798 -0.492934 + outer loop + vertex -682.875 144.325 285.596 + vertex -683.278 144.857 285.563 + vertex -681.189 145.322 282.175 + endloop + endfacet + facet normal -0.65237 -0.527181 -0.544513 + outer loop + vertex -684.865 143.49 288.789 + vertex -685.303 144.006 288.814 + vertex -682.875 144.325 285.596 + endloop + endfacet + facet normal -0.637036 -0.549345 -0.540745 + outer loop + vertex -682.011 143.412 285.506 + vertex -684.865 143.49 288.789 + vertex -682.875 144.325 285.596 + endloop + endfacet + facet normal -0.62671 -0.570078 -0.531268 + outer loop + vertex -683.961 142.557 288.724 + vertex -684.865 143.49 288.789 + vertex -682.011 143.412 285.506 + endloop + endfacet + facet normal -0.617255 -0.582515 -0.528841 + outer loop + vertex -680.702 142.015 285.516 + vertex -683.961 142.557 288.724 + vertex -682.011 143.412 285.506 + endloop + endfacet + facet normal -0.605143 -0.609677 -0.511953 + outer loop + vertex -682.593 141.102 288.839 + vertex -683.961 142.557 288.724 + vertex -680.702 142.015 285.516 + endloop + endfacet + facet normal -0.594116 -0.622654 -0.509242 + outer loop + vertex -679.024 140.134 285.859 + vertex -682.593 141.102 288.839 + vertex -680.702 142.015 285.516 + endloop + endfacet + facet normal -0.619562 -0.636314 -0.459617 + outer loop + vertex -679.024 140.134 285.859 + vertex -680.702 142.015 285.516 + vertex -677.251 141.206 281.984 + endloop + endfacet + facet normal -0.602539 -0.654406 -0.456835 + outer loop + vertex -675.076 138.717 282.683 + vertex -679.024 140.134 285.859 + vertex -677.251 141.206 281.984 + endloop + endfacet + facet normal -0.627302 -0.662643 -0.40914 + outer loop + vertex -675.076 138.717 282.683 + vertex -677.251 141.206 281.984 + vertex -673.23 140.104 277.604 + endloop + endfacet + facet normal -0.600934 -0.688192 -0.406535 + outer loop + vertex -673.23 140.104 277.604 + vertex -670.113 136.964 278.313 + vertex -675.076 138.717 282.683 + endloop + endfacet + facet normal -0.602028 -0.685966 -0.408672 + outer loop + vertex -670.113 136.964 278.313 + vertex -672.992 135.566 284.9 + vertex -675.076 138.717 282.683 + endloop + endfacet + facet normal -0.574532 -0.689995 -0.440249 + outer loop + vertex -677.305 138.105 286.55 + vertex -675.076 138.717 282.683 + vertex -672.992 135.566 284.9 + endloop + endfacet + facet normal -0.574208 -0.667172 -0.474517 + outer loop + vertex -677.305 138.105 286.55 + vertex -672.992 135.566 284.9 + vertex -678.203 136.809 289.459 + endloop + endfacet + facet normal -0.568505 -0.671819 -0.474827 + outer loop + vertex -678.203 136.809 289.459 + vertex -680.74 139.153 289.181 + vertex -677.305 138.105 286.55 + endloop + endfacet + facet normal -0.575309 -0.654445 -0.490634 + outer loop + vertex -677.305 138.105 286.55 + vertex -680.74 139.153 289.181 + vertex -679.024 140.134 285.859 + endloop + endfacet + facet normal -0.554118 -0.706059 -0.440947 + outer loop + vertex -672.992 135.566 284.9 + vertex -675.312 133.668 290.855 + vertex -678.203 136.809 289.459 + endloop + endfacet + facet normal -0.530124 -0.72605 -0.437973 + outer loop + vertex -667.899 131.526 285.433 + vertex -675.312 133.668 290.855 + vertex -672.992 135.566 284.9 + endloop + endfacet + facet normal -0.510492 -0.762991 -0.396539 + outer loop + vertex -668.262 129.274 290.234 + vertex -675.312 133.668 290.855 + vertex -667.899 131.526 285.433 + endloop + endfacet + facet normal -0.498025 -0.769981 -0.398875 + outer loop + vertex -662.462 127.967 285.514 + vertex -668.262 129.274 290.234 + vertex -667.899 131.526 285.433 + endloop + endfacet + facet normal -0.478848 -0.79714 -0.367793 + outer loop + vertex -662.932 126.358 289.615 + vertex -668.262 129.274 290.234 + vertex -662.462 127.967 285.514 + endloop + endfacet + facet normal -0.461771 -0.80639 -0.369463 + outer loop + vertex -657.276 124.89 285.749 + vertex -662.932 126.358 289.615 + vertex -662.462 127.967 285.514 + endloop + endfacet + facet normal -0.448484 -0.825445 -0.342786 + outer loop + vertex -658.852 123.729 290.609 + vertex -662.932 126.358 289.615 + vertex -657.276 124.89 285.749 + endloop + endfacet + facet normal -0.427571 -0.838008 -0.339006 + outer loop + vertex -651.7 121.812 286.325 + vertex -658.852 123.729 290.609 + vertex -657.276 124.89 285.749 + endloop + endfacet + facet normal -0.434807 -0.845621 -0.309626 + outer loop + vertex -651.7 121.812 286.325 + vertex -657.276 124.89 285.749 + vertex -650.341 123.435 279.984 + endloop + endfacet + facet normal -0.419608 -0.853696 -0.308435 + outer loop + vertex -644.38 120.321 280.493 + vertex -651.7 121.812 286.325 + vertex -650.341 123.435 279.984 + endloop + endfacet + facet normal -0.425965 -0.860919 -0.278158 + outer loop + vertex -644.38 120.321 280.493 + vertex -650.341 123.435 279.984 + vertex -643.196 122.079 273.239 + endloop + endfacet + facet normal -0.414499 -0.866652 -0.277677 + outer loop + vertex -637.136 119.032 273.704 + vertex -644.38 120.321 280.493 + vertex -643.196 122.079 273.239 + endloop + endfacet + facet normal -0.41973 -0.872734 -0.249322 + outer loop + vertex -637.136 119.032 273.704 + vertex -643.196 122.079 273.239 + vertex -636.18 120.746 266.094 + endloop + endfacet + facet normal -0.408277 -0.878209 -0.249115 + outer loop + vertex -629.986 117.773 266.424 + vertex -637.136 119.032 273.704 + vertex -636.18 120.746 266.094 + endloop + endfacet + facet normal -0.411968 -0.883148 -0.224348 + outer loop + vertex -629.986 117.773 266.424 + vertex -636.18 120.746 266.094 + vertex -629.257 119.37 258.798 + endloop + endfacet + facet normal -0.399869 -0.888691 -0.224353 + outer loop + vertex -622.883 116.453 258.991 + vertex -629.986 117.773 266.424 + vertex -629.257 119.37 258.798 + endloop + endfacet + facet normal -0.402246 -0.892533 -0.203922 + outer loop + vertex -622.883 116.453 258.991 + vertex -629.257 119.37 258.798 + vertex -622.31 117.949 251.316 + endloop + endfacet + facet normal -0.391086 -0.89745 -0.204048 + outer loop + vertex -615.894 115.151 251.326 + vertex -622.883 116.453 258.991 + vertex -622.31 117.949 251.316 + endloop + endfacet + facet normal -0.392526 -0.900688 -0.186239 + outer loop + vertex -615.894 115.151 251.326 + vertex -622.31 117.949 251.316 + vertex -615.446 116.565 243.54 + endloop + endfacet + facet normal -0.383657 -0.904465 -0.186415 + outer loop + vertex -609.478 114.056 243.431 + vertex -615.894 115.151 251.326 + vertex -615.446 116.565 243.54 + endloop + endfacet + facet normal -0.377304 -0.908285 -0.180723 + outer loop + vertex -609.924 112.682 251.269 + vertex -615.894 115.151 251.326 + vertex -609.478 114.056 243.431 + endloop + endfacet + facet normal -0.371027 -0.910848 -0.180815 + outer loop + vertex -604.668 112.085 243.49 + vertex -609.924 112.682 251.269 + vertex -609.478 114.056 243.431 + endloop + endfacet + facet normal -0.372182 -0.91322 -0.165863 + outer loop + vertex -604.668 112.085 243.49 + vertex -609.478 114.056 243.431 + vertex -604.371 113.404 235.562 + endloop + endfacet + facet normal -0.363821 -0.916539 -0.166102 + outer loop + vertex -601.278 112.082 236.079 + vertex -604.668 112.085 243.49 + vertex -604.371 113.404 235.562 + endloop + endfacet + facet normal -0.36678 -0.917851 -0.151728 + outer loop + vertex -601.278 112.082 236.079 + vertex -604.371 113.404 235.562 + vertex -601.055 113.313 228.096 + endloop + endfacet + facet normal -0.368317 -0.917121 -0.152419 + outer loop + vertex -601.055 113.313 228.096 + vertex -604.371 113.404 235.562 + vertex -604.139 114.634 227.603 + endloop + endfacet + facet normal -0.360603 -0.918075 -0.16463 + outer loop + vertex -601.573 110.769 244.051 + vertex -604.668 112.085 243.49 + vertex -601.278 112.082 236.079 + endloop + endfacet + facet normal -0.340164 -0.925753 -0.165137 + outer loop + vertex -599.788 111.302 237.385 + vertex -601.573 110.769 244.051 + vertex -601.278 112.082 236.079 + endloop + endfacet + facet normal -0.349466 -0.924266 -0.153641 + outer loop + vertex -599.788 111.302 237.385 + vertex -601.278 112.082 236.079 + vertex -599.572 112.595 229.116 + endloop + endfacet + facet normal -0.301523 -0.940781 -0.154966 + outer loop + vertex -599.788 111.302 237.385 + vertex -599.572 112.595 229.116 + vertex -599.24 111.993 232.124 + endloop + endfacet + facet normal -0.265356 -0.951987 -0.152668 + outer loop + vertex -599.24 111.993 232.124 + vertex -599.354 111.477 235.54 + vertex -599.788 111.302 237.385 + endloop + endfacet + facet normal -0.345269 -0.923646 -0.166335 + outer loop + vertex -600.13 110.001 245.322 + vertex -601.573 110.769 244.051 + vertex -599.788 111.302 237.385 + endloop + endfacet + facet normal -0.311242 -0.935574 -0.166826 + outer loop + vertex -600.13 110.001 245.322 + vertex -599.788 111.302 237.385 + vertex -599.466 110.614 240.642 + endloop + endfacet + facet normal -0.338583 -0.924612 -0.174512 + outer loop + vertex -600.13 110.001 245.322 + vertex -602.034 109.459 251.883 + vertex -601.573 110.769 244.051 + endloop + endfacet + facet normal -0.353568 -0.918997 -0.174454 + outer loop + vertex -602.034 109.459 251.883 + vertex -605.109 110.742 251.36 + vertex -601.573 110.769 244.051 + endloop + endfacet + facet normal -0.351627 -0.917997 -0.183415 + outer loop + vertex -602.034 109.459 251.883 + vertex -605.693 109.39 259.245 + vertex -605.109 110.742 251.36 + endloop + endfacet + facet normal -0.356347 -0.916167 -0.183451 + outer loop + vertex -605.693 109.39 259.245 + vertex -610.479 111.282 259.091 + vertex -605.109 110.742 251.36 + endloop + endfacet + facet normal -0.363916 -0.912056 -0.188996 + outer loop + vertex -605.109 110.742 251.36 + vertex -610.479 111.282 259.091 + vertex -609.924 112.682 251.269 + endloop + endfacet + facet normal -0.368471 -0.910226 -0.188992 + outer loop + vertex -610.479 111.282 259.091 + vertex -616.451 113.703 259.075 + vertex -609.924 112.682 251.269 + endloop + endfacet + facet normal -0.367409 -0.907693 -0.20274 + outer loop + vertex -610.479 111.282 259.091 + vertex -617.104 112.217 266.911 + vertex -616.451 113.703 259.075 + endloop + endfacet + facet normal -0.37142 -0.906054 -0.202763 + outer loop + vertex -617.104 112.217 266.911 + vertex -623.548 114.902 266.72 + vertex -616.451 113.703 259.075 + endloop + endfacet + facet normal -0.38172 -0.899309 -0.213383 + outer loop + vertex -616.451 113.703 259.075 + vertex -623.548 114.902 266.72 + vertex -622.883 116.453 258.991 + endloop + endfacet + facet normal -0.369623 -0.902924 -0.219332 + outer loop + vertex -617.104 112.217 266.911 + vertex -624.275 113.274 274.645 + vertex -623.548 114.902 266.72 + endloop + endfacet + facet normal -0.373026 -0.901518 -0.219355 + outer loop + vertex -624.275 113.274 274.645 + vertex -630.79 116.072 274.226 + vertex -623.548 114.902 266.72 + endloop + endfacet + facet normal -0.386958 -0.891832 -0.234307 + outer loop + vertex -623.548 114.902 266.72 + vertex -630.79 116.072 274.226 + vertex -629.986 117.773 266.424 + endloop + endfacet + facet normal -0.369936 -0.897452 -0.240266 + outer loop + vertex -624.275 113.274 274.645 + vertex -631.621 114.279 282.201 + vertex -630.79 116.072 274.226 + endloop + endfacet + facet normal -0.373213 -0.896085 -0.240301 + outer loop + vertex -631.621 114.279 282.201 + vertex -638.218 117.181 281.626 + vertex -630.79 116.072 274.226 + endloop + endfacet + facet normal -0.390578 -0.883189 -0.259664 + outer loop + vertex -630.79 116.072 274.226 + vertex -638.218 117.181 281.626 + vertex -637.136 119.032 273.704 + endloop + endfacet + facet normal -0.368462 -0.890534 -0.266804 + outer loop + vertex -638.218 117.181 281.626 + vertex -631.621 114.279 282.201 + vertex -637.584 115.452 286.521 + endloop + endfacet + facet normal -0.369185 -0.890289 -0.266624 + outer loop + vertex -640.771 116.808 286.408 + vertex -638.218 117.181 281.626 + vertex -637.584 115.452 286.521 + endloop + endfacet + facet normal -0.3679 -0.888029 -0.27578 + outer loop + vertex -637.584 115.452 286.521 + vertex -642.025 116.36 289.522 + vertex -640.771 116.808 286.408 + endloop + endfacet + facet normal -0.382913 -0.88011 -0.280685 + outer loop + vertex -640.771 116.808 286.408 + vertex -642.025 116.36 289.522 + vertex -645.321 118.56 287.121 + endloop + endfacet + facet normal -0.374018 -0.879992 -0.292787 + outer loop + vertex -646.677 117.643 291.608 + vertex -645.321 118.56 287.121 + vertex -642.025 116.36 289.522 + endloop + endfacet + facet normal -0.369982 -0.885766 -0.280236 + outer loop + vertex -643.128 115.714 293.02 + vertex -646.677 117.643 291.608 + vertex -642.025 116.36 289.522 + endloop + endfacet + facet normal -0.358331 -0.891369 -0.277598 + outer loop + vertex -638.514 114.633 290.536 + vertex -643.128 115.714 293.02 + vertex -642.025 116.36 289.522 + endloop + endfacet + facet normal -0.35175 -0.898617 -0.262219 + outer loop + vertex -638.739 113.813 293.648 + vertex -643.128 115.714 293.02 + vertex -638.514 114.633 290.536 + endloop + endfacet + facet normal -0.343902 -0.901588 -0.262433 + outer loop + vertex -635.006 113.163 290.989 + vertex -638.739 113.813 293.648 + vertex -638.514 114.633 290.536 + endloop + endfacet + facet normal -0.346054 -0.903629 -0.252389 + outer loop + vertex -635.006 113.163 290.989 + vertex -638.514 114.633 290.536 + vertex -634.685 113.955 287.714 + endloop + endfacet + facet normal -0.342581 -0.904958 -0.252369 + outer loop + vertex -631.055 112.666 287.408 + vertex -635.006 113.163 290.989 + vertex -634.685 113.955 287.714 + endloop + endfacet + facet normal -0.342678 -0.90725 -0.243864 + outer loop + vertex -634.685 113.955 287.714 + vertex -631.621 114.279 282.201 + vertex -631.055 112.666 287.408 + endloop + endfacet + facet normal -0.347496 -0.905686 -0.242855 + outer loop + vertex -631.621 114.279 282.201 + vertex -625.144 111.63 282.813 + vertex -631.055 112.666 287.408 + endloop + endfacet + facet normal -0.335432 -0.914727 -0.225298 + outer loop + vertex -628.339 111.407 288.475 + vertex -631.055 112.666 287.408 + vertex -625.144 111.63 282.813 + endloop + endfacet + facet normal -0.322273 -0.921174 -0.218126 + outer loop + vertex -628.339 111.407 288.475 + vertex -625.144 111.63 282.813 + vertex -624.806 110.241 288.179 + endloop + endfacet + facet normal -0.322295 -0.919751 -0.224016 + outer loop + vertex -624.806 110.241 288.179 + vertex -629.068 110.839 291.856 + vertex -628.339 111.407 288.475 + endloop + endfacet + facet normal -0.319404 -0.920865 -0.22358 + outer loop + vertex -629.068 110.839 291.856 + vertex -631.953 111.961 291.356 + vertex -628.339 111.407 288.475 + endloop + endfacet + facet normal -0.317181 -0.919315 -0.232931 + outer loop + vertex -629.068 110.839 291.856 + vertex -633.096 111.591 294.375 + vertex -631.953 111.961 291.356 + endloop + endfacet + facet normal -0.32071 -0.917797 -0.234081 + outer loop + vertex -633.096 111.591 294.375 + vertex -635.258 112.556 293.551 + vertex -631.953 111.961 291.356 + endloop + endfacet + facet normal -0.32885 -0.911202 -0.248131 + outer loop + vertex -631.953 111.961 291.356 + vertex -635.258 112.556 293.551 + vertex -635.006 113.163 290.989 + endloop + endfacet + facet normal -0.320734 -0.917803 -0.234027 + outer loop + vertex -633.096 111.591 294.375 + vertex -637.254 112.722 295.635 + vertex -635.258 112.556 293.551 + endloop + endfacet + facet normal -0.335026 -0.908869 -0.248426 + outer loop + vertex -635.258 112.556 293.551 + vertex -637.254 112.722 295.635 + vertex -638.739 113.813 293.648 + endloop + endfacet + facet normal -0.337357 -0.908531 -0.246497 + outer loop + vertex -637.254 112.722 295.635 + vertex -642.836 114.738 295.844 + vertex -638.739 113.813 293.648 + endloop + endfacet + facet normal -0.337067 -0.907175 -0.25183 + outer loop + vertex -637.254 112.722 295.635 + vertex -638.485 112.679 297.437 + vertex -642.836 114.738 295.844 + endloop + endfacet + facet normal -0.320187 -0.901634 -0.290751 + outer loop + vertex -638.485 112.679 297.437 + vertex -643.144 114.296 297.554 + vertex -642.836 114.738 295.844 + endloop + endfacet + facet normal -0.343487 -0.892425 -0.292566 + outer loop + vertex -643.144 114.296 297.554 + vertex -648.587 116.707 296.591 + vertex -642.836 114.738 295.844 + endloop + endfacet + facet normal -0.343812 -0.877639 -0.333982 + outer loop + vertex -642.836 114.738 295.844 + vertex -648.587 116.707 296.591 + vertex -649.343 117.758 294.607 + endloop + endfacet + facet normal -0.362433 -0.891838 -0.270678 + outer loop + vertex -642.836 114.738 295.844 + vertex -649.343 117.758 294.607 + vertex -643.128 115.714 293.02 + endloop + endfacet + facet normal -0.364998 -0.873012 -0.32346 + outer loop + vertex -648.587 116.707 296.591 + vertex -654.279 119.263 296.116 + vertex -649.343 117.758 294.607 + endloop + endfacet + facet normal -0.372844 -0.85005 -0.372026 + outer loop + vertex -649.343 117.758 294.607 + vertex -654.279 119.263 296.116 + vertex -655.636 120.438 294.791 + endloop + endfacet + facet normal -0.378814 -0.867488 -0.322435 + outer loop + vertex -649.343 117.758 294.607 + vertex -655.636 120.438 294.791 + vertex -652.805 120.338 291.735 + endloop + endfacet + facet normal -0.387843 -0.867479 -0.311543 + outer loop + vertex -652.805 120.338 291.735 + vertex -646.677 117.643 291.608 + vertex -649.343 117.758 294.607 + endloop + endfacet + facet normal -0.406599 -0.844353 -0.348922 + outer loop + vertex -655.636 120.438 294.791 + vertex -660.26 122.986 294.013 + vertex -652.805 120.338 291.735 + endloop + endfacet + facet normal -0.407025 -0.842832 -0.352086 + outer loop + vertex -658.852 123.729 290.609 + vertex -652.805 120.338 291.735 + vertex -660.26 122.986 294.013 + endloop + endfacet + facet normal -0.440154 -0.822047 -0.361253 + outer loop + vertex -660.26 122.986 294.013 + vertex -666.157 126.512 293.174 + vertex -658.852 123.729 290.609 + endloop + endfacet + facet normal -0.440495 -0.820874 -0.363497 + outer loop + vertex -662.932 126.358 289.615 + vertex -658.852 123.729 290.609 + vertex -666.157 126.512 293.174 + endloop + endfacet + facet normal -0.418421 -0.801424 -0.427367 + outer loop + vertex -660.26 122.986 294.013 + vertex -665.775 125.11 295.429 + vertex -666.157 126.512 293.174 + endloop + endfacet + facet normal -0.443715 -0.792843 -0.417753 + outer loop + vertex -665.775 125.11 295.429 + vertex -671.433 128.31 295.367 + vertex -666.157 126.512 293.174 + endloop + endfacet + facet normal -0.455409 -0.748205 -0.482485 + outer loop + vertex -666.157 126.512 293.174 + vertex -671.433 128.31 295.367 + vertex -673.007 130.38 293.642 + endloop + endfacet + facet normal -0.471055 -0.785783 -0.400815 + outer loop + vertex -666.157 126.512 293.174 + vertex -673.007 130.38 293.642 + vertex -668.262 129.274 290.234 + endloop + endfacet + facet normal -0.468829 -0.74792 -0.469909 + outer loop + vertex -671.433 128.31 295.367 + vertex -676.837 131.593 295.532 + vertex -673.007 130.38 293.642 + endloop + endfacet + facet normal -0.480028 -0.707709 -0.518384 + outer loop + vertex -673.007 130.38 293.642 + vertex -676.837 131.593 295.532 + vertex -678.194 133.424 294.289 + endloop + endfacet + facet normal -0.490685 -0.737407 -0.464176 + outer loop + vertex -673.007 130.38 293.642 + vertex -678.194 133.424 294.289 + vertex -675.312 133.668 290.855 + endloop + endfacet + facet normal -0.521249 -0.700648 -0.487229 + outer loop + vertex -678.194 133.424 294.289 + vertex -682.345 136.684 294.042 + vertex -675.312 133.668 290.855 + endloop + endfacet + facet normal -0.4921 -0.708315 -0.50609 + outer loop + vertex -676.837 131.593 295.532 + vertex -681.876 134.966 295.712 + vertex -678.194 133.424 294.289 + endloop + endfacet + facet normal -0.416221 -0.823172 -0.386197 + outer loop + vertex -660.173 122.111 295.784 + vertex -665.775 125.11 295.429 + vertex -660.26 122.986 294.013 + endloop + endfacet + facet normal -0.392623 -0.832087 -0.391764 + outer loop + vertex -655.636 120.438 294.791 + vertex -660.173 122.111 295.784 + vertex -660.26 122.986 294.013 + endloop + endfacet + facet normal -0.390812 -0.849892 -0.353483 + outer loop + vertex -654.279 119.263 296.116 + vertex -660.173 122.111 295.784 + vertex -655.636 120.438 294.791 + endloop + endfacet + facet normal -0.323428 -0.914364 -0.243585 + outer loop + vertex -637.89 112.163 298.588 + vertex -643.144 114.296 297.554 + vertex -638.485 112.679 297.437 + endloop + endfacet + facet normal -0.304048 -0.917849 -0.255163 + outer loop + vertex -638.485 112.679 297.437 + vertex -634.448 111.068 298.423 + vertex -637.89 112.163 298.588 + endloop + endfacet + facet normal -0.314989 -0.923385 -0.219415 + outer loop + vertex -634.448 111.068 298.423 + vertex -638.485 112.679 297.437 + vertex -634.295 111.415 296.745 + endloop + endfacet + facet normal -0.300378 -0.928314 -0.219105 + outer loop + vertex -631.149 110.225 297.472 + vertex -634.448 111.068 298.423 + vertex -634.295 111.415 296.745 + endloop + endfacet + facet normal -0.302665 -0.929437 -0.211047 + outer loop + vertex -631.149 110.225 297.472 + vertex -634.295 111.415 296.745 + vertex -630.247 110.482 295.049 + endloop + endfacet + facet normal -0.296903 -0.931723 -0.209145 + outer loop + vertex -627.227 109.383 295.654 + vertex -631.149 110.225 297.472 + vertex -630.247 110.482 295.049 + endloop + endfacet + facet normal -0.298891 -0.932828 -0.201238 + outer loop + vertex -627.227 109.383 295.654 + vertex -630.247 110.482 295.049 + vertex -626.03 109.705 292.383 + endloop + endfacet + facet normal -0.301913 -0.93164 -0.202227 + outer loop + vertex -622.907 108.58 292.905 + vertex -627.227 109.383 295.654 + vertex -626.03 109.705 292.383 + endloop + endfacet + facet normal -0.303603 -0.932738 -0.194487 + outer loop + vertex -622.907 108.58 292.905 + vertex -626.03 109.705 292.383 + vertex -622.069 109.054 289.324 + endloop + endfacet + facet normal -0.309815 -0.930452 -0.195638 + outer loop + vertex -618.477 107.922 289.019 + vertex -622.907 108.58 292.905 + vertex -622.069 109.054 289.324 + endloop + endfacet + facet normal -0.309789 -0.930768 -0.19417 + outer loop + vertex -622.069 109.054 289.324 + vertex -618.784 109.191 283.426 + vertex -618.477 107.922 289.019 + endloop + endfacet + facet normal -0.319532 -0.927724 -0.192944 + outer loop + vertex -618.784 109.191 283.426 + vertex -612.829 107.019 284.009 + vertex -618.477 107.922 289.019 + endloop + endfacet + facet normal -0.306553 -0.935261 -0.176952 + outer loop + vertex -615.767 106.812 290.193 + vertex -618.477 107.922 289.019 + vertex -612.829 107.019 284.009 + endloop + endfacet + facet normal -0.298627 -0.938504 -0.173295 + outer loop + vertex -615.767 106.812 290.193 + vertex -612.829 107.019 284.009 + vertex -612.451 105.833 289.777 + endloop + endfacet + facet normal -0.298171 -0.939901 -0.166377 + outer loop + vertex -612.451 105.833 289.777 + vertex -616.651 106.429 293.94 + vertex -615.767 106.812 290.193 + endloop + endfacet + facet normal -0.291731 -0.942146 -0.165085 + outer loop + vertex -616.651 106.429 293.94 + vertex -619.764 107.481 293.434 + vertex -615.767 106.812 290.193 + endloop + endfacet + facet normal -0.291294 -0.941898 -0.167262 + outer loop + vertex -616.651 106.429 293.94 + vertex -621.098 107.283 296.873 + vertex -619.764 107.481 293.434 + endloop + endfacet + facet normal -0.284772 -0.944311 -0.164872 + outer loop + vertex -621.098 107.283 296.873 + vertex -624.178 108.321 296.252 + vertex -619.764 107.481 293.434 + endloop + endfacet + facet normal -0.296337 -0.93696 -0.185179 + outer loop + vertex -619.764 107.481 293.434 + vertex -624.178 108.321 296.252 + vertex -622.907 108.58 292.905 + endloop + endfacet + facet normal -0.283716 -0.943841 -0.169322 + outer loop + vertex -621.098 107.283 296.873 + vertex -625.191 108.172 298.778 + vertex -624.178 108.321 296.252 + endloop + endfacet + facet normal -0.280643 -0.944967 -0.168156 + outer loop + vertex -625.191 108.172 298.778 + vertex -628.167 109.173 298.117 + vertex -624.178 108.321 296.252 + endloop + endfacet + facet normal -0.289591 -0.938005 -0.190483 + outer loop + vertex -624.178 108.321 296.252 + vertex -628.167 109.173 298.117 + vertex -627.227 109.383 295.654 + endloop + endfacet + facet normal -0.279637 -0.944562 -0.172065 + outer loop + vertex -625.191 108.172 298.778 + vertex -628.485 108.97 299.751 + vertex -628.167 109.173 298.117 + endloop + endfacet + facet normal -0.281227 -0.944045 -0.172311 + outer loop + vertex -628.485 108.97 299.751 + vertex -631.208 109.924 298.967 + vertex -628.167 109.173 298.117 + endloop + endfacet + facet normal -0.287146 -0.936798 -0.19989 + outer loop + vertex -628.167 109.173 298.117 + vertex -631.208 109.924 298.967 + vertex -631.149 110.225 297.472 + endloop + endfacet + facet normal -0.283235 -0.944577 -0.165989 + outer loop + vertex -631.208 109.924 298.967 + vertex -628.485 108.97 299.751 + vertex -632.473 110.179 299.677 + endloop + endfacet + facet normal -0.297337 -0.934725 -0.19463 + outer loop + vertex -631.208 109.924 298.967 + vertex -632.473 110.179 299.677 + vertex -634.448 111.068 298.423 + endloop + endfacet + facet normal -0.274154 -0.950077 -0.148978 + outer loop + vertex -625.35 107.97 300.36 + vertex -628.485 108.97 299.751 + vertex -625.191 108.172 298.778 + endloop + endfacet + facet normal -0.271982 -0.950722 -0.148841 + outer loop + vertex -622.117 107.182 299.486 + vertex -625.35 107.97 300.36 + vertex -625.191 108.172 298.778 + endloop + endfacet + facet normal -0.265173 -0.956947 -0.11805 + outer loop + vertex -622.431 107.042 301.321 + vertex -625.35 107.97 300.36 + vertex -622.117 107.182 299.486 + endloop + endfacet + facet normal -0.266793 -0.956467 -0.118291 + outer loop + vertex -618.975 106.205 300.299 + vertex -622.431 107.042 301.321 + vertex -622.117 107.182 299.486 + endloop + endfacet + facet normal -0.266532 -0.956421 -0.119248 + outer loop + vertex -618.975 106.205 300.299 + vertex -622.117 107.182 299.486 + vertex -617.965 106.272 297.501 + endloop + endfacet + facet normal -0.270952 -0.954982 -0.12081 + outer loop + vertex -614.907 105.31 298.247 + vertex -618.975 106.205 300.299 + vertex -617.965 106.272 297.501 + endloop + endfacet + facet normal -0.270115 -0.954808 -0.124018 + outer loop + vertex -614.907 105.31 298.247 + vertex -617.965 106.272 297.501 + vertex -613.617 105.441 294.43 + endloop + endfacet + facet normal -0.27907 -0.951843 -0.126944 + outer loop + vertex -610.876 104.573 294.91 + vertex -614.907 105.31 298.247 + vertex -613.617 105.441 294.43 + endloop + endfacet + facet normal -0.262735 -0.959071 -0.105612 + outer loop + vertex -612.213 104.463 299.236 + vertex -614.907 105.31 298.247 + vertex -610.876 104.573 294.91 + endloop + endfacet + facet normal -0.265472 -0.959106 -0.0981869 + outer loop + vertex -612.213 104.463 299.236 + vertex -615.93 105.273 301.38 + vertex -614.907 105.31 298.247 + endloop + endfacet + facet normal -0.259499 -0.961835 -0.0867974 + outer loop + vertex -613.817 104.679 301.646 + vertex -615.93 105.273 301.38 + vertex -612.213 104.463 299.236 + endloop + endfacet + facet normal -0.250304 -0.964822 -0.0804087 + outer loop + vertex -613.817 104.679 301.646 + vertex -612.213 104.463 299.236 + vertex -612.444 104.302 301.889 + endloop + endfacet + facet normal -0.254 -0.965322 -0.0603049 + outer loop + vertex -612.444 104.302 301.889 + vertex -614.629 104.813 302.905 + vertex -613.817 104.679 301.646 + endloop + endfacet + facet normal -0.250412 -0.966749 -0.0518711 + outer loop + vertex -613.167 104.394 303.659 + vertex -614.629 104.813 302.905 + vertex -612.444 104.302 301.889 + endloop + endfacet + facet normal -0.25394 -0.965747 -0.0533637 + outer loop + vertex -611.382 103.984 302.587 + vertex -613.167 104.394 303.659 + vertex -612.444 104.302 301.889 + endloop + endfacet + facet normal -0.247009 -0.966869 -0.0644286 + outer loop + vertex -611.382 103.984 302.587 + vertex -612.444 104.302 301.889 + vertex -609.754 103.768 299.592 + endloop + endfacet + facet normal -0.247569 -0.966705 -0.0647449 + outer loop + vertex -611.382 103.984 302.587 + vertex -609.754 103.768 299.592 + vertex -610.057 103.667 302.263 + endloop + endfacet + facet normal -0.241732 -0.969599 -0.0380017 + outer loop + vertex -610.057 103.667 302.263 + vertex -611.851 104.043 304.081 + vertex -611.382 103.984 302.587 + endloop + endfacet + facet normal -0.238915 -0.970407 -0.0350565 + outer loop + vertex -610.77 103.769 304.291 + vertex -611.851 104.043 304.081 + vertex -610.057 103.667 302.263 + endloop + endfacet + facet normal -0.24137 -0.969767 -0.0359507 + outer loop + vertex -609.095 103.427 302.257 + vertex -610.77 103.769 304.291 + vertex -610.057 103.667 302.263 + endloop + endfacet + facet normal -0.241261 -0.968863 -0.0556634 + outer loop + vertex -609.095 103.427 302.257 + vertex -610.057 103.667 302.263 + vertex -608.017 103.341 299.096 + endloop + endfacet + facet normal -0.255877 -0.964798 -0.0607594 + outer loop + vertex -607.355 103.161 299.158 + vertex -609.095 103.427 302.257 + vertex -608.017 103.341 299.096 + endloop + endfacet + facet normal -0.227945 -0.972661 -0.0444031 + outer loop + vertex -608.639 103.309 302.52 + vertex -609.095 103.427 302.257 + vertex -607.355 103.161 299.158 + endloop + endfacet + facet normal -0.236064 -0.971283 -0.0297069 + outer loop + vertex -609.095 103.427 302.257 + vertex -608.639 103.309 302.52 + vertex -610.079 103.596 304.574 + endloop + endfacet + facet normal -0.232229 -0.972258 -0.0280064 + outer loop + vertex -610.079 103.596 304.574 + vertex -610.77 103.769 304.291 + vertex -609.095 103.427 302.257 + endloop + endfacet + facet normal -0.238128 -0.971148 -0.0129097 + outer loop + vertex -610.079 103.596 304.574 + vertex -611.374 103.9 305.556 + vertex -610.77 103.769 304.291 + endloop + endfacet + facet normal -0.239529 -0.970794 -0.0136164 + outer loop + vertex -611.374 103.9 305.556 + vertex -612.178 104.104 305.15 + vertex -610.77 103.769 304.291 + endloop + endfacet + facet normal -0.248374 -0.968651 0.00499287 + outer loop + vertex -612.178 104.104 305.15 + vertex -611.374 103.9 305.556 + vertex -613.145 104.354 305.559 + endloop + endfacet + facet normal -0.251855 -0.967758 -0.00378191 + outer loop + vertex -612.178 104.104 305.15 + vertex -613.145 104.354 305.559 + vertex -613.583 104.471 304.762 + endloop + endfacet + facet normal -0.247638 -0.968648 -0.01992 + outer loop + vertex -612.178 104.104 305.15 + vertex -613.583 104.471 304.762 + vertex -611.851 104.043 304.081 + endloop + endfacet + facet normal -0.250113 -0.967848 -0.0267171 + outer loop + vertex -611.851 104.043 304.081 + vertex -613.583 104.471 304.762 + vertex -613.167 104.394 303.659 + endloop + endfacet + facet normal -0.250333 -0.967789 -0.0268045 + outer loop + vertex -613.583 104.471 304.762 + vertex -614.951 104.845 304.057 + vertex -613.167 104.394 303.659 + endloop + endfacet + facet normal -0.254867 -0.966818 -0.0175024 + outer loop + vertex -614.951 104.845 304.057 + vertex -613.583 104.471 304.762 + vertex -615.811 105.064 304.481 + endloop + endfacet + facet normal -0.260641 -0.964964 -0.0301759 + outer loop + vertex -614.951 104.845 304.057 + vertex -615.811 105.064 304.481 + vertex -616.977 105.418 303.232 + endloop + endfacet + facet normal -0.25487 -0.965927 -0.0450223 + outer loop + vertex -614.951 104.845 304.057 + vertex -616.977 105.418 303.232 + vertex -614.629 104.813 302.905 + endloop + endfacet + facet normal -0.257791 -0.963649 -0.0701723 + outer loop + vertex -616.977 105.418 303.232 + vertex -615.93 105.273 301.38 + vertex -614.629 104.813 302.905 + endloop + endfacet + facet normal -0.254939 -0.964528 -0.068492 + outer loop + vertex -616.977 105.418 303.232 + vertex -619.185 106.081 302.116 + vertex -615.93 105.273 301.38 + endloop + endfacet + facet normal -0.260166 -0.960811 -0.0956849 + outer loop + vertex -615.93 105.273 301.38 + vertex -619.185 106.081 302.116 + vertex -618.975 106.205 300.299 + endloop + endfacet + facet normal -0.254068 -0.96463 -0.0702746 + outer loop + vertex -619.185 106.081 302.116 + vertex -616.977 105.418 303.232 + vertex -620.377 106.324 303.09 + endloop + endfacet + facet normal -0.264194 -0.960839 -0.0836039 + outer loop + vertex -619.185 106.081 302.116 + vertex -620.377 106.324 303.09 + vertex -622.431 107.042 301.321 + endloop + endfacet + facet normal -0.256875 -0.966444 -0.00082796 + outer loop + vertex -613.145 104.354 305.559 + vertex -615.811 105.064 304.481 + vertex -613.583 104.471 304.762 + endloop + endfacet + facet normal -0.245388 -0.968933 -0.030877 + outer loop + vertex -613.145 104.354 305.559 + vertex -615.382 104.938 305.033 + vertex -615.811 105.064 304.481 + endloop + endfacet + facet normal -0.260838 -0.965215 -0.0179909 + outer loop + vertex -615.382 104.938 305.033 + vertex -620.377 106.324 303.09 + vertex -615.811 105.064 304.481 + endloop + endfacet + facet normal -0.2558 -0.966598 0.0159606 + outer loop + vertex -612.479 104.188 306.16 + vertex -615.382 104.938 305.033 + vertex -613.145 104.354 305.559 + endloop + endfacet + facet normal -0.248541 -0.968593 0.00736572 + outer loop + vertex -611.222 103.865 306.129 + vertex -612.479 104.188 306.16 + vertex -613.145 104.354 305.559 + endloop + endfacet + facet normal -0.248412 -0.968575 0.0124059 + outer loop + vertex -611.158 103.854 306.566 + vertex -612.479 104.188 306.16 + vertex -611.222 103.865 306.129 + endloop + endfacet + facet normal -0.236014 -0.971693 0.0105113 + outer loop + vertex -611.158 103.854 306.566 + vertex -611.222 103.865 306.129 + vertex -610.052 103.583 306.265 + endloop + endfacet + facet normal -0.193471 -0.967472 0.162994 + outer loop + vertex -611.158 103.854 306.566 + vertex -610.052 103.583 306.265 + vertex -611.449 103.942 306.743 + endloop + endfacet + facet normal -0.233744 -0.971108 0.0480938 + outer loop + vertex -609.406 103.505 307.843 + vertex -611.449 103.942 306.743 + vertex -610.052 103.583 306.265 + endloop + endfacet + facet normal -0.196968 -0.979867 0.0326096 + outer loop + vertex -608.898 103.311 305.076 + vertex -609.406 103.505 307.843 + vertex -610.052 103.583 306.265 + endloop + endfacet + facet normal 0.241396 -0.868679 0.432579 + outer loop + vertex -608.898 103.311 305.076 + vertex -610.052 103.583 306.265 + vertex -609.252 103.376 305.404 + endloop + endfacet + facet normal -0.175092 -0.984532 0.00625924 + outer loop + vertex -609.252 103.376 305.404 + vertex -608.489 103.229 303.709 + vertex -608.898 103.311 305.076 + endloop + endfacet + facet normal -0.231361 -0.97266 -0.0201134 + outer loop + vertex -609.252 103.376 305.404 + vertex -609.259 103.385 305.048 + vertex -608.489 103.229 303.709 + endloop + endfacet + facet normal -0.254486 -0.966474 -0.0341333 + outer loop + vertex -608.489 103.229 303.709 + vertex -609.259 103.385 305.048 + vertex -608.442 103.243 302.984 + endloop + endfacet + facet normal -0.218932 -0.975215 -0.0319988 + outer loop + vertex -608.489 103.229 303.709 + vertex -608.442 103.243 302.984 + vertex -607.229 103.057 300.352 + endloop + endfacet + facet normal -0.263295 -0.963242 -0.0532887 + outer loop + vertex -607.229 103.057 300.352 + vertex -608.442 103.243 302.984 + vertex -607.166 103.08 299.618 + endloop + endfacet + facet normal -0.229876 -0.97239 -0.040179 + outer loop + vertex -608.442 103.243 302.984 + vertex -608.639 103.309 302.52 + vertex -607.166 103.08 299.618 + endloop + endfacet + facet normal -0.248569 -0.968099 -0.0316009 + outer loop + vertex -608.442 103.243 302.984 + vertex -609.798 103.523 305.076 + vertex -608.639 103.309 302.52 + endloop + endfacet + facet normal -0.248861 -0.968017 -0.0318008 + outer loop + vertex -609.259 103.385 305.048 + vertex -609.798 103.523 305.076 + vertex -608.442 103.243 302.984 + endloop + endfacet + facet normal -0.247592 -0.968856 -0.00414266 + outer loop + vertex -609.259 103.385 305.048 + vertex -610.052 103.583 306.265 + vertex -609.798 103.523 305.076 + endloop + endfacet + facet normal -0.269194 -0.962895 -0.0191896 + outer loop + vertex -609.259 103.385 305.048 + vertex -609.252 103.376 305.404 + vertex -610.052 103.583 306.265 + endloop + endfacet + facet normal -0.321143 -0.947001 0.00751575 + outer loop + vertex -609.406 103.505 307.843 + vertex -608.898 103.311 305.076 + vertex -608.586 103.213 306.117 + endloop + endfacet + facet normal -0.245332 -0.968291 0.0471622 + outer loop + vertex -608.586 103.213 306.117 + vertex -605.737 102.509 306.479 + vertex -609.406 103.505 307.843 + endloop + endfacet + facet normal -0.244848 -0.968347 0.0485045 + outer loop + vertex -604.09 102.134 307.297 + vertex -609.406 103.505 307.843 + vertex -605.737 102.509 306.479 + endloop + endfacet + facet normal -0.245092 -0.968259 0.0490361 + outer loop + vertex -599.077 100.833 306.667 + vertex -604.09 102.134 307.297 + vertex -605.737 102.509 306.479 + endloop + endfacet + facet normal -0.244847 -0.968962 0.0340878 + outer loop + vertex -599.077 100.833 306.667 + vertex -605.737 102.509 306.479 + vertex -601.379 101.364 305.236 + endloop + endfacet + facet normal -0.251207 -0.966883 0.045089 + outer loop + vertex -601.379 101.364 305.236 + vertex -595.086 99.729 305.231 + vertex -599.077 100.833 306.667 + endloop + endfacet + facet normal -0.250801 -0.966933 0.0462563 + outer loop + vertex -595.086 99.729 305.231 + vertex -592.034 98.9948 306.43 + vertex -599.077 100.833 306.667 + endloop + endfacet + facet normal -0.246038 -0.959985 0.133769 + outer loop + vertex -594.35 99.6505 306.877 + vertex -599.077 100.833 306.667 + vertex -592.034 98.9948 306.43 + endloop + endfacet + facet normal -0.249285 -0.961135 0.118642 + outer loop + vertex -588.403 98.0947 306.768 + vertex -594.35 99.6505 306.877 + vertex -592.034 98.9948 306.43 + endloop + endfacet + facet normal -0.249144 -0.961463 0.116261 + outer loop + vertex -592.034 98.9948 306.43 + vertex -581.994 96.3356 305.955 + vertex -588.403 98.0947 306.768 + endloop + endfacet + facet normal -0.250786 -0.962313 0.105162 + outer loop + vertex -578.032 95.3694 306.561 + vertex -588.403 98.0947 306.768 + vertex -581.994 96.3356 305.955 + endloop + endfacet + facet normal -0.250817 -0.962277 0.105424 + outer loop + vertex -581.994 96.3356 305.955 + vertex -569.853 93.1518 305.779 + vertex -578.032 95.3694 306.561 + endloop + endfacet + facet normal -0.250766 -0.962242 0.105862 + outer loop + vertex -570.579 93.4135 306.438 + vertex -578.032 95.3694 306.561 + vertex -569.853 93.1518 305.779 + endloop + endfacet + facet normal -0.252249 -0.962041 0.104149 + outer loop + vertex -564.896 91.9065 306.283 + vertex -570.579 93.4135 306.438 + vertex -569.853 93.1518 305.779 + endloop + endfacet + facet normal -0.252133 -0.962249 0.102496 + outer loop + vertex -569.853 93.1518 305.779 + vertex -556.496 89.6297 305.57 + vertex -564.896 91.9065 306.283 + endloop + endfacet + facet normal -0.250728 -0.961141 0.115511 + outer loop + vertex -557.515 89.9781 306.257 + vertex -564.896 91.9065 306.283 + vertex -556.496 89.6297 305.57 + endloop + endfacet + facet normal -0.25277 -0.960976 0.112399 + outer loop + vertex -550.232 88.0437 306.097 + vertex -557.515 89.9781 306.257 + vertex -556.496 89.6297 305.57 + endloop + endfacet + facet normal -0.252207 -0.962317 0.101673 + outer loop + vertex -556.496 89.6297 305.57 + vertex -542.94 86.071 305.516 + vertex -550.232 88.0437 306.097 + endloop + endfacet + facet normal -0.251119 -0.961422 0.112281 + outer loop + vertex -544.966 86.6698 306.11 + vertex -550.232 88.0437 306.097 + vertex -542.94 86.071 305.516 + endloop + endfacet + facet normal -0.249529 -0.961213 0.117493 + outer loop + vertex -538.051 84.8664 306.042 + vertex -544.966 86.6698 306.11 + vertex -542.94 86.071 305.516 + endloop + endfacet + facet normal -0.250129 -0.959999 0.125843 + outer loop + vertex -542.94 86.071 305.516 + vertex -529.511 82.5958 305.695 + vertex -538.051 84.8664 306.042 + endloop + endfacet + facet normal -0.246395 -0.953362 0.17433 + outer loop + vertex -529.936 82.764 306.015 + vertex -538.051 84.8664 306.042 + vertex -529.511 82.5958 305.695 + endloop + endfacet + facet normal -0.246155 -0.953365 0.174651 + outer loop + vertex -523.038 80.985 306.026 + vertex -529.936 82.764 306.015 + vertex -529.511 82.5958 305.695 + endloop + endfacet + facet normal -0.244975 -0.964751 0.0961436 + outer loop + vertex -529.511 82.5958 305.695 + vertex -515.667 79.0842 305.734 + vertex -523.038 80.985 306.026 + endloop + endfacet + facet normal -0.247391 -0.967471 0.052891 + outer loop + vertex -518.503 79.8289 306.089 + vertex -523.038 80.985 306.026 + vertex -515.667 79.0842 305.734 + endloop + endfacet + facet normal -0.245559 -0.967084 0.0666986 + outer loop + vertex -516.507 79.3244 306.124 + vertex -518.503 79.8289 306.089 + vertex -515.667 79.0842 305.734 + endloop + endfacet + facet normal -0.242517 -0.967366 0.0734078 + outer loop + vertex -513.231 78.5087 306.196 + vertex -516.507 79.3244 306.124 + vertex -515.667 79.0842 305.734 + endloop + endfacet + facet normal -0.241419 -0.968128 0.0666704 + outer loop + vertex -508.334 77.2862 306.178 + vertex -513.231 78.5087 306.196 + vertex -515.667 79.0842 305.734 + endloop + endfacet + facet normal -0.23884 -0.970977 0.0125749 + outer loop + vertex -515.667 79.0842 305.734 + vertex -502.779 75.91 305.41 + vertex -508.334 77.2862 306.178 + endloop + endfacet + facet normal -0.239024 -0.970949 0.011195 + outer loop + vertex -502.725 75.9064 306.261 + vertex -508.334 77.2862 306.178 + vertex -502.779 75.91 305.41 + endloop + endfacet + facet normal -0.237123 -0.971417 0.0110716 + outer loop + vertex -498.071 74.7683 306.082 + vertex -502.725 75.9064 306.261 + vertex -502.779 75.91 305.41 + endloop + endfacet + facet normal -0.233816 -0.972188 -0.0134005 + outer loop + vertex -502.779 75.91 305.41 + vertex -494.527 73.9291 305.125 + vertex -498.071 74.7683 306.082 + endloop + endfacet + facet normal -0.23351 -0.972278 -0.0121884 + outer loop + vertex -494.273 73.8559 306.11 + vertex -498.071 74.7683 306.082 + vertex -494.527 73.9291 305.125 + endloop + endfacet + facet normal -0.226879 -0.973822 -0.0140088 + outer loop + vertex -489.091 72.6494 306.048 + vertex -494.273 73.8559 306.11 + vertex -494.527 73.9291 305.125 + endloop + endfacet + facet normal -0.227204 -0.973773 -0.0120296 + outer loop + vertex -489.091 72.6494 306.048 + vertex -494.527 73.9291 305.125 + vertex -491.184 73.165 303.83 + endloop + endfacet + facet normal -0.218993 -0.975518 -0.0201788 + outer loop + vertex -489.894 72.8995 302.674 + vertex -489.091 72.6494 306.048 + vertex -491.184 73.165 303.83 + endloop + endfacet + facet normal -0.226909 -0.97347 -0.0294867 + outer loop + vertex -491.184 73.165 303.83 + vertex -491.45 73.2958 301.564 + vertex -489.894 72.8995 302.674 + endloop + endfacet + facet normal -0.224202 -0.974086 -0.0298407 + outer loop + vertex -491.184 73.165 303.83 + vertex -492.983 73.5964 303.27 + vertex -491.45 73.2958 301.564 + endloop + endfacet + facet normal -0.225195 -0.973827 -0.0307784 + outer loop + vertex -491.45 73.2958 301.564 + vertex -492.983 73.5964 303.27 + vertex -493.828 73.8543 301.292 + endloop + endfacet + facet normal -0.223306 -0.97362 -0.0468825 + outer loop + vertex -491.45 73.2958 301.564 + vertex -493.828 73.8543 301.292 + vertex -492.668 73.7248 298.456 + endloop + endfacet + facet normal -0.224247 -0.973423 -0.0464866 + outer loop + vertex -491.45 73.2958 301.564 + vertex -492.668 73.7248 298.456 + vertex -490.841 73.2468 299.65 + endloop + endfacet + facet normal -0.216912 -0.975194 -0.0441052 + outer loop + vertex -490.841 73.2468 299.65 + vertex -489.894 72.8995 302.674 + vertex -491.45 73.2958 301.564 + endloop + endfacet + facet normal -0.23478 -0.971303 -0.0380662 + outer loop + vertex -489.894 72.8995 302.674 + vertex -490.841 73.2468 299.65 + vertex -489.521 72.8639 301.278 + endloop + endfacet + facet normal -0.227335 -0.97315 -0.036027 + outer loop + vertex -489.521 72.8639 301.278 + vertex -488.488 72.5374 303.579 + vertex -489.894 72.8995 302.674 + endloop + endfacet + facet normal -0.230379 -0.972487 -0.0345663 + outer loop + vertex -488.488 72.5374 303.579 + vertex -489.521 72.8639 301.278 + vertex -488.203 72.5048 302.597 + endloop + endfacet + facet normal -0.233041 -0.971824 -0.0353613 + outer loop + vertex -487.559 72.308 303.761 + vertex -488.488 72.5374 303.579 + vertex -488.203 72.5048 302.597 + endloop + endfacet + facet normal -0.219331 -0.974683 -0.0434343 + outer loop + vertex -488.203 72.5048 302.597 + vertex -486.626 72.1097 303.5 + vertex -487.559 72.308 303.761 + endloop + endfacet + facet normal -0.21579 -0.975986 -0.0297782 + outer loop + vertex -487.559 72.308 303.761 + vertex -486.626 72.1097 303.5 + vertex -486.652 72.0886 304.383 + endloop + endfacet + facet normal -0.216006 -0.975938 -0.0297835 + outer loop + vertex -484.14 71.5573 303.573 + vertex -486.652 72.0886 304.383 + vertex -486.626 72.1097 303.5 + endloop + endfacet + facet normal -0.215602 -0.975615 -0.0411182 + outer loop + vertex -485.539 71.8907 302.998 + vertex -484.14 71.5573 303.573 + vertex -486.626 72.1097 303.5 + endloop + endfacet + facet normal -0.21835 -0.974716 -0.0474609 + outer loop + vertex -487.315 72.3351 302.042 + vertex -485.539 71.8907 302.998 + vertex -486.626 72.1097 303.5 + endloop + endfacet + facet normal -0.21589 -0.975023 -0.0521745 + outer loop + vertex -485.874 72.0326 301.73 + vertex -485.539 71.8907 302.998 + vertex -487.315 72.3351 302.042 + endloop + endfacet + facet normal -0.216798 -0.974561 -0.056821 + outer loop + vertex -487.95 72.6055 299.827 + vertex -485.874 72.0326 301.73 + vertex -487.315 72.3351 302.042 + endloop + endfacet + facet normal -0.209212 -0.976078 -0.0591812 + outer loop + vertex -487.95 72.6055 299.827 + vertex -487.315 72.3351 302.042 + vertex -489.069 72.8137 300.349 + endloop + endfacet + facet normal -0.211711 -0.975175 -0.0649005 + outer loop + vertex -489.069 72.8137 300.349 + vertex -489.987 73.2125 297.351 + vertex -487.95 72.6055 299.827 + endloop + endfacet + facet normal -0.199808 -0.976951 -0.0751235 + outer loop + vertex -489.987 73.2125 297.351 + vertex -488.036 72.8506 296.868 + vertex -487.95 72.6055 299.827 + endloop + endfacet + facet normal -0.211098 -0.974614 -0.0746032 + outer loop + vertex -486.309 72.2371 299.997 + vertex -487.95 72.6055 299.827 + vertex -488.036 72.8506 296.868 + endloop + endfacet + facet normal -0.210325 -0.974746 -0.0750554 + outer loop + vertex -486.309 72.2371 299.997 + vertex -488.036 72.8506 296.868 + vertex -484.838 71.9737 299.294 + endloop + endfacet + facet normal -0.208515 -0.975438 -0.0710072 + outer loop + vertex -484.838 71.9737 299.294 + vertex -484.142 71.6742 301.365 + vertex -486.309 72.2371 299.997 + endloop + endfacet + facet normal -0.214623 -0.974786 -0.0610595 + outer loop + vertex -486.309 72.2371 299.997 + vertex -484.142 71.6742 301.365 + vertex -485.874 72.0326 301.73 + endloop + endfacet + facet normal -0.213613 -0.975327 -0.055743 + outer loop + vertex -484.142 71.6742 301.365 + vertex -483.648 71.4932 302.638 + vertex -485.874 72.0326 301.73 + endloop + endfacet + facet normal -0.212293 -0.975583 -0.0562919 + outer loop + vertex -484.142 71.6742 301.365 + vertex -481.905 71.1496 302.021 + vertex -483.648 71.4932 302.638 + endloop + endfacet + facet normal -0.206576 -0.977653 -0.039009 + outer loop + vertex -481.905 71.1496 302.021 + vertex -480.464 70.8291 302.423 + vertex -483.648 71.4932 302.638 + endloop + endfacet + facet normal -0.206738 -0.9775 -0.0418788 + outer loop + vertex -480.464 70.8291 302.423 + vertex -484.14 71.5573 303.573 + vertex -483.648 71.4932 302.638 + endloop + endfacet + facet normal -0.207773 -0.977122 -0.0454247 + outer loop + vertex -480.464 70.8291 302.423 + vertex -481.478 71.0111 303.145 + vertex -484.14 71.5573 303.573 + endloop + endfacet + facet normal -0.205601 -0.978157 -0.0305997 + outer loop + vertex -484.14 71.5573 303.573 + vertex -481.478 71.0111 303.145 + vertex -484.475 71.6096 304.151 + endloop + endfacet + facet normal -0.189595 -0.981675 0.0191685 + outer loop + vertex -484.475 71.6096 304.151 + vertex -481.478 71.0111 303.145 + vertex -483.723 71.4656 304.21 + endloop + endfacet + facet normal -0.191586 -0.980305 0.0479281 + outer loop + vertex -486.029 71.9439 304.778 + vertex -484.475 71.6096 304.151 + vertex -483.723 71.4656 304.21 + endloop + endfacet + facet normal -0.216445 -0.976166 -0.015878 + outer loop + vertex -486.652 72.0886 304.383 + vertex -484.475 71.6096 304.151 + vertex -486.029 71.9439 304.778 + endloop + endfacet + facet normal -0.225093 -0.974336 -0.00155249 + outer loop + vertex -486.652 72.0886 304.383 + vertex -486.029 71.9439 304.778 + vertex -489.091 72.6494 306.048 + endloop + endfacet + facet normal -0.232261 -0.972571 -0.0126474 + outer loop + vertex -489.091 72.6494 306.048 + vertex -488.488 72.5374 303.579 + vertex -486.652 72.0886 304.383 + endloop + endfacet + facet normal -0.169924 -0.97649 0.132637 + outer loop + vertex -483.723 71.4656 304.21 + vertex -489.091 72.6494 306.048 + vertex -486.029 71.9439 304.778 + endloop + endfacet + facet normal -0.167307 -0.983627 0.0669781 + outer loop + vertex -478.6 70.4651 302.314 + vertex -483.723 71.4656 304.21 + vertex -481.478 71.0111 303.145 + endloop + endfacet + facet normal -0.190463 -0.98149 -0.0200208 + outer loop + vertex -480.464 70.8291 302.423 + vertex -477.027 70.1789 301.602 + vertex -481.478 71.0111 303.145 + endloop + endfacet + facet normal -0.199302 -0.978811 -0.0469762 + outer loop + vertex -481.478 71.0111 303.145 + vertex -477.027 70.1789 301.602 + vertex -478.6 70.4651 302.314 + endloop + endfacet + facet normal -0.170466 -0.985173 0.0193634 + outer loop + vertex -474.277 69.6857 300.719 + vertex -478.6 70.4651 302.314 + vertex -477.027 70.1789 301.602 + endloop + endfacet + facet normal -0.194276 -0.97978 -0.0478343 + outer loop + vertex -478.6 70.4651 302.314 + vertex -474.277 69.6857 300.719 + vertex -473.8 69.5734 301.083 + endloop + endfacet + facet normal -0.189746 -0.981405 -0.0289814 + outer loop + vertex -473.8 69.5734 301.083 + vertex -480.356 70.7639 303.688 + vertex -478.6 70.4651 302.314 + endloop + endfacet + facet normal -0.204397 -0.975338 -0.0832906 + outer loop + vertex -475.949 70.0056 300.985 + vertex -477.027 70.1789 301.602 + vertex -480.464 70.8291 302.423 + endloop + endfacet + facet normal -0.175806 -0.983939 -0.0309175 + outer loop + vertex -475.949 70.0056 300.985 + vertex -471.411 69.2361 299.673 + vertex -477.027 70.1789 301.602 + endloop + endfacet + facet normal -0.292233 -0.852133 -0.434129 + outer loop + vertex -477.027 70.1789 301.602 + vertex -471.411 69.2361 299.673 + vertex -474.277 69.6857 300.719 + endloop + endfacet + facet normal -0.226022 -0.951149 -0.21031 + outer loop + vertex -470.401 69.0413 299.468 + vertex -474.277 69.6857 300.719 + vertex -471.411 69.2361 299.673 + endloop + endfacet + facet normal -0.183306 -0.981062 -0.0625845 + outer loop + vertex -474.277 69.6857 300.719 + vertex -470.401 69.0413 299.468 + vertex -473.8 69.5734 301.083 + endloop + endfacet + facet normal -0.196333 -0.974647 -0.107317 + outer loop + vertex -471.833 69.3593 299.326 + vertex -471.411 69.2361 299.673 + vertex -475.949 70.0056 300.985 + endloop + endfacet + facet normal -0.185686 -0.979424 -0.0790513 + outer loop + vertex -476.265 70.1237 300.265 + vertex -471.833 69.3593 299.326 + vertex -475.949 70.0056 300.985 + endloop + endfacet + facet normal -0.196404 -0.977722 -0.0740671 + outer loop + vertex -476.265 70.1237 300.265 + vertex -475.949 70.0056 300.985 + vertex -479.355 70.6594 301.388 + endloop + endfacet + facet normal -0.197366 -0.977308 -0.0769117 + outer loop + vertex -479.76 70.8401 300.131 + vertex -476.265 70.1237 300.265 + vertex -479.355 70.6594 301.388 + endloop + endfacet + facet normal -0.202771 -0.976347 -0.0750308 + outer loop + vertex -479.76 70.8401 300.131 + vertex -479.355 70.6594 301.388 + vertex -482.123 71.2758 300.847 + endloop + endfacet + facet normal -0.2038 -0.975841 -0.0787342 + outer loop + vertex -482.605 71.5095 299.198 + vertex -479.76 70.8401 300.131 + vertex -482.123 71.2758 300.847 + endloop + endfacet + facet normal -0.206155 -0.975407 -0.0779845 + outer loop + vertex -482.605 71.5095 299.198 + vertex -482.123 71.2758 300.847 + vertex -484.838 71.9737 299.294 + endloop + endfacet + facet normal -0.2064 -0.974496 -0.0880733 + outer loop + vertex -482.605 71.5095 299.198 + vertex -484.838 71.9737 299.294 + vertex -484.89 72.2623 296.224 + endloop + endfacet + facet normal -0.201514 -0.975156 -0.0919949 + outer loop + vertex -482.605 71.5095 299.198 + vertex -484.89 72.2623 296.224 + vertex -480.789 71.2274 298.21 + endloop + endfacet + facet normal -0.195363 -0.975128 -0.104682 + outer loop + vertex -484.89 72.2623 296.224 + vertex -480.788 71.5387 295.309 + vertex -480.789 71.2274 298.21 + endloop + endfacet + facet normal -0.197738 -0.974655 -0.104632 + outer loop + vertex -478.629 70.8419 297.719 + vertex -480.789 71.2274 298.21 + vertex -480.788 71.5387 295.309 + endloop + endfacet + facet normal -0.189512 -0.975443 -0.112229 + outer loop + vertex -480.788 71.5387 295.309 + vertex -475.383 70.2789 297.132 + vertex -478.629 70.8419 297.719 + endloop + endfacet + facet normal -0.188325 -0.976516 -0.104644 + outer loop + vertex -478.629 70.8419 297.719 + vertex -475.383 70.2789 297.132 + vertex -477.412 70.4639 299.056 + endloop + endfacet + facet normal -0.191335 -0.975575 -0.107909 + outer loop + vertex -475.383 70.2789 297.132 + vertex -474.016 69.807 298.973 + vertex -477.412 70.4639 299.056 + endloop + endfacet + facet normal -0.191273 -0.977073 -0.0935075 + outer loop + vertex -476.265 70.1237 300.265 + vertex -477.412 70.4639 299.056 + vertex -474.016 69.807 298.973 + endloop + endfacet + facet normal -0.185373 -0.976208 -0.112497 + outer loop + vertex -475.383 70.2789 297.132 + vertex -470.179 69.2359 297.607 + vertex -474.016 69.807 298.973 + endloop + endfacet + facet normal -0.183312 -0.977296 -0.106251 + outer loop + vertex -474.016 69.807 298.973 + vertex -470.179 69.2359 297.607 + vertex -471.833 69.3593 299.326 + endloop + endfacet + facet normal -0.184553 -0.975483 -0.119885 + outer loop + vertex -470.858 69.6256 295.481 + vertex -470.179 69.2359 297.607 + vertex -475.383 70.2789 297.132 + endloop + endfacet + facet normal -0.183917 -0.975833 -0.118003 + outer loop + vertex -476.535 70.8939 293.842 + vertex -470.858 69.6256 295.481 + vertex -475.383 70.2789 297.132 + endloop + endfacet + facet normal -0.180425 -0.97503 -0.129474 + outer loop + vertex -472 70.2186 292.607 + vertex -470.858 69.6256 295.481 + vertex -476.535 70.8939 293.842 + endloop + endfacet + facet normal -0.179797 -0.975481 -0.126924 + outer loop + vertex -477.776 71.5907 290.244 + vertex -472 70.2186 292.607 + vertex -476.535 70.8939 293.842 + endloop + endfacet + facet normal -0.182844 -0.975061 -0.125792 + outer loop + vertex -477.776 71.5907 290.244 + vertex -476.535 70.8939 293.842 + vertex -482.026 72.2958 290.956 + endloop + endfacet + facet normal -0.183386 -0.974457 -0.129625 + outer loop + vertex -482.721 73.0015 286.634 + vertex -477.776 71.5907 290.244 + vertex -482.026 72.2958 290.956 + endloop + endfacet + facet normal -0.18201 -0.974681 -0.129883 + outer loop + vertex -482.721 73.0015 286.634 + vertex -482.026 72.2958 290.956 + vertex -486.195 73.5608 287.306 + endloop + endfacet + facet normal -0.183185 -0.973493 -0.136949 + outer loop + vertex -486.195 73.5608 287.306 + vertex -487.945 74.8468 280.505 + vertex -482.721 73.0015 286.634 + endloop + endfacet + facet normal -0.176985 -0.973865 -0.142346 + outer loop + vertex -481.254 73.252 283.096 + vertex -482.721 73.0015 286.634 + vertex -487.945 74.8468 280.505 + endloop + endfacet + facet normal -0.173737 -0.973247 -0.150355 + outer loop + vertex -483.449 74.6332 276.693 + vertex -481.254 73.252 283.096 + vertex -487.945 74.8468 280.505 + endloop + endfacet + facet normal -0.172767 -0.973598 -0.149191 + outer loop + vertex -489.61 76.6996 270.341 + vertex -483.449 74.6332 276.693 + vertex -487.945 74.8468 280.505 + endloop + endfacet + facet normal -0.16449 -0.974789 -0.150763 + outer loop + vertex -489.61 76.6996 270.341 + vertex -487.945 74.8468 280.505 + vertex -493.901 77.0372 272.84 + endloop + endfacet + facet normal -0.166362 -0.973951 -0.15409 + outer loop + vertex -494.994 78.7877 262.956 + vertex -489.61 76.6996 270.341 + vertex -493.901 77.0372 272.84 + endloop + endfacet + facet normal -0.165839 -0.974029 -0.154162 + outer loop + vertex -494.994 78.7877 262.956 + vertex -493.901 77.0372 272.84 + vertex -497.682 78.6011 267.026 + endloop + endfacet + facet normal -0.165873 -0.974019 -0.154184 + outer loop + vertex -497.682 78.6011 267.026 + vertex -498.045 79.4941 261.776 + vertex -494.994 78.7877 262.956 + endloop + endfacet + facet normal -0.163393 -0.973458 -0.160255 + outer loop + vertex -498.045 79.4941 261.776 + vertex -498.545 80.3551 257.056 + vertex -494.994 78.7877 262.956 + endloop + endfacet + facet normal -0.167601 -0.973169 -0.157645 + outer loop + vertex -495.458 80.269 254.306 + vertex -494.994 78.7877 262.956 + vertex -498.545 80.3551 257.056 + endloop + endfacet + facet normal -0.167714 -0.973129 -0.157774 + outer loop + vertex -498.545 80.3551 257.056 + vertex -499.167 81.6611 249.661 + vertex -495.458 80.269 254.306 + endloop + endfacet + facet normal -0.172642 -0.972907 -0.153772 + outer loop + vertex -496.622 81.8746 245.454 + vertex -495.458 80.269 254.306 + vertex -499.167 81.6611 249.661 + endloop + endfacet + facet normal -0.173779 -0.972599 -0.154444 + outer loop + vertex -499.167 81.6611 249.661 + vertex -499.496 82.5237 244.601 + vertex -496.622 81.8746 245.454 + endloop + endfacet + facet normal -0.176282 -0.973362 -0.146597 + outer loop + vertex -499.496 82.5237 244.601 + vertex -499.886 83.3022 239.899 + vertex -496.622 81.8746 245.454 + endloop + endfacet + facet normal -0.180097 -0.973012 -0.144266 + outer loop + vertex -497.006 83.211 236.919 + vertex -496.622 81.8746 245.454 + vertex -499.886 83.3022 239.899 + endloop + endfacet + facet normal -0.175136 -0.974622 -0.139422 + outer loop + vertex -499.886 83.3022 239.899 + vertex -500.349 84.4475 232.475 + vertex -497.006 83.211 236.919 + endloop + endfacet + facet normal -0.18689 -0.973698 -0.130324 + outer loop + vertex -497.976 84.6158 227.814 + vertex -497.006 83.211 236.919 + vertex -500.349 84.4475 232.475 + endloop + endfacet + facet normal -0.187466 -0.973549 -0.130612 + outer loop + vertex -500.349 84.4475 232.475 + vertex -500.566 85.1885 227.264 + vertex -497.976 84.6158 227.814 + endloop + endfacet + facet normal -0.190965 -0.974786 -0.115432 + outer loop + vertex -500.566 85.1885 227.264 + vertex -500.998 85.8392 222.483 + vertex -497.976 84.6158 227.814 + endloop + endfacet + facet normal -0.196287 -0.974099 -0.112258 + outer loop + vertex -498.581 85.8609 218.068 + vertex -497.976 84.6158 227.814 + vertex -500.998 85.8392 222.483 + endloop + endfacet + facet normal -0.187296 -0.97642 -0.107346 + outer loop + vertex -500.998 85.8392 222.483 + vertex -501.699 86.6677 216.171 + vertex -498.581 85.8609 218.068 + endloop + endfacet + facet normal -0.194769 -0.976239 -0.0949854 + outer loop + vertex -501.699 86.6677 216.171 + vertex -501 86.9908 211.416 + vertex -498.581 85.8609 218.068 + endloop + endfacet + facet normal -0.20058 -0.975281 -0.0927091 + outer loop + vertex -498.734 86.7144 209.42 + vertex -498.581 85.8609 218.068 + vertex -501 86.9908 211.416 + endloop + endfacet + facet normal -0.188804 -0.978844 -0.078848 + outer loop + vertex -501 86.9908 211.416 + vertex -501.889 87.6731 205.076 + vertex -498.734 86.7144 209.42 + endloop + endfacet + facet normal -0.200467 -0.977196 -0.0700141 + outer loop + vertex -499.671 87.5652 200.229 + vertex -498.734 86.7144 209.42 + vertex -501.889 87.6731 205.076 + endloop + endfacet + facet normal -0.191083 -0.979375 -0.0656706 + outer loop + vertex -501.889 87.6731 205.076 + vertex -502.704 88.268 198.573 + vertex -499.671 87.5652 200.229 + endloop + endfacet + facet normal -0.198784 -0.978701 -0.0512843 + outer loop + vertex -502.704 88.268 198.573 + vertex -502.069 88.3906 193.772 + vertex -499.671 87.5652 200.229 + endloop + endfacet + facet normal -0.203979 -0.977736 -0.0492318 + outer loop + vertex -499.897 88.0447 191.641 + vertex -499.671 87.5652 200.229 + vertex -502.069 88.3906 193.772 + endloop + endfacet + facet normal -0.191113 -0.980922 -0.0355977 + outer loop + vertex -502.069 88.3906 193.772 + vertex -502.934 88.788 187.47 + vertex -499.897 88.0447 191.641 + endloop + endfacet + facet normal -0.202093 -0.978987 -0.0272566 + outer loop + vertex -500.809 88.487 182.524 + vertex -499.897 88.0447 191.641 + vertex -502.934 88.788 187.47 + endloop + endfacet + facet normal -0.192461 -0.981035 -0.0229935 + outer loop + vertex -502.934 88.788 187.47 + vertex -503.734 89.0949 181.065 + vertex -500.809 88.487 182.524 + endloop + endfacet + facet normal -0.198143 -0.980109 -0.0112184 + outer loop + vertex -503.734 89.0949 181.065 + vertex -503.121 89.0273 176.139 + vertex -500.809 88.487 182.524 + endloop + endfacet + facet normal -0.204305 -0.978867 -0.00888277 + outer loop + vertex -501.052 88.6157 173.918 + vertex -500.809 88.487 182.524 + vertex -503.121 89.0273 176.139 + endloop + endfacet + facet normal -0.191367 -0.981512 0.00365697 + outer loop + vertex -503.121 89.0273 176.139 + vertex -503.991 89.1737 169.891 + vertex -501.052 88.6157 173.918 + endloop + endfacet + facet normal -0.201021 -0.979525 0.0109769 + outer loop + vertex -501.959 88.6992 164.755 + vertex -501.052 88.6157 173.918 + vertex -503.991 89.1737 169.891 + endloop + endfacet + facet normal -0.19147 -0.981385 0.014927 + outer loop + vertex -503.991 89.1737 169.891 + vertex -504.771 89.228 163.456 + vertex -501.959 88.6992 164.755 + endloop + endfacet + facet normal -0.196782 -0.980077 0.0269561 + outer loop + vertex -504.771 89.228 163.456 + vertex -504.174 88.971 158.467 + vertex -501.959 88.6992 164.755 + endloop + endfacet + facet normal -0.202657 -0.978818 0.0290802 + outer loop + vertex -502.182 88.4863 156.037 + vertex -501.959 88.6992 164.755 + vertex -504.174 88.971 158.467 + endloop + endfacet + facet normal -0.188514 -0.981208 0.0411568 + outer loop + vertex -504.174 88.971 158.467 + vertex -504.987 88.8621 152.146 + vertex -502.182 88.4863 156.037 + endloop + endfacet + facet normal -0.199084 -0.978756 0.0490149 + outer loop + vertex -503.077 88.1995 146.674 + vertex -502.182 88.4863 156.037 + vertex -504.987 88.8621 152.146 + endloop + endfacet + facet normal -0.191183 -0.980179 0.0519445 + outer loop + vertex -504.987 88.8621 152.146 + vertex -505.729 88.665 145.695 + vertex -503.077 88.1995 146.674 + endloop + endfacet + facet normal -0.194955 -0.978798 0.0628266 + outer loop + vertex -505.729 88.665 145.695 + vertex -505.258 88.2467 140.642 + vertex -503.077 88.1995 146.674 + endloop + endfacet + facet normal -0.207962 -0.975801 0.0675523 + outer loop + vertex -503.683 87.6443 136.789 + vertex -503.077 88.1995 146.674 + vertex -505.258 88.2467 140.642 + endloop + endfacet + facet normal -0.189492 -0.978968 0.0755986 + outer loop + vertex -505.258 88.2467 140.642 + vertex -506.3 88.0739 135.793 + vertex -503.683 87.6443 136.789 + endloop + endfacet + facet normal -0.193122 -0.977416 0.085805 + outer loop + vertex -506.3 88.0739 135.793 + vertex -506.272 87.5241 129.593 + vertex -503.683 87.6443 136.789 + endloop + endfacet + facet normal -0.188961 -0.978357 0.0843239 + outer loop + vertex -503.909 86.9303 127.998 + vertex -503.683 87.6443 136.789 + vertex -506.272 87.5241 129.593 + endloop + endfacet + facet normal -0.18118 -0.978753 0.0959985 + outer loop + vertex -506.272 87.5241 129.593 + vertex -506.225 86.8864 123.179 + vertex -503.909 86.9303 127.998 + endloop + endfacet + facet normal -0.195484 -0.9753 0.102842 + outer loop + vertex -504.755 86.1433 118.926 + vertex -503.909 86.9303 127.998 + vertex -506.225 86.8864 123.179 + endloop + endfacet + facet normal -0.179789 -0.977683 0.108683 + outer loop + vertex -506.225 86.8864 123.179 + vertex -507.307 86.5367 118.243 + vertex -504.755 86.1433 118.926 + endloop + endfacet + facet normal -0.182484 -0.975883 0.119798 + outer loop + vertex -507.307 86.5367 118.243 + vertex -507.249 85.7626 112.025 + vertex -504.755 86.1433 118.926 + endloop + endfacet + facet normal -0.177499 -0.977014 0.118059 + outer loop + vertex -504.932 85.129 110.267 + vertex -504.755 86.1433 118.926 + vertex -507.249 85.7626 112.025 + endloop + endfacet + facet normal -0.168909 -0.977099 0.129409 + outer loop + vertex -507.249 85.7626 112.025 + vertex -507.114 84.8977 105.672 + vertex -504.932 85.129 110.267 + endloop + endfacet + facet normal -0.181414 -0.974069 0.135197 + outer loop + vertex -505.558 84.0231 101.458 + vertex -504.932 85.129 110.267 + vertex -507.114 84.8977 105.672 + endloop + endfacet + facet normal -0.166719 -0.975871 0.140998 + outer loop + vertex -507.114 84.8977 105.672 + vertex -508.073 84.3751 100.921 + vertex -505.558 84.0231 101.458 + endloop + endfacet + facet normal -0.168815 -0.973835 0.152144 + outer loop + vertex -508.073 84.3751 100.921 + vertex -507.814 83.3843 94.8667 + vertex -505.558 84.0231 101.458 + endloop + endfacet + facet normal -0.166015 -0.974456 0.151246 + outer loop + vertex -505.398 82.6759 92.954 + vertex -505.558 84.0231 101.458 + vertex -507.814 83.3843 94.8667 + endloop + endfacet + facet normal -0.155347 -0.974055 0.164571 + outer loop + vertex -507.814 83.3843 94.8667 + vertex -507.406 82.2698 88.6552 + vertex -505.398 82.6759 92.954 + endloop + endfacet + facet normal -0.174085 -0.969435 0.172886 + outer loop + vertex -505.576 81.0804 83.8284 + vertex -505.398 82.6759 92.954 + vertex -507.406 82.2698 88.6552 + endloop + endfacet + facet normal -0.156835 -0.971113 0.179841 + outer loop + vertex -507.406 82.2698 88.6552 + vertex -508.153 81.5303 84.0107 + vertex -505.576 81.0804 83.8284 + endloop + endfacet + facet normal -0.155405 -0.96863 0.193922 + outer loop + vertex -508.153 81.5303 84.0107 + vertex -507.614 80.1678 77.6372 + vertex -505.576 81.0804 83.8284 + endloop + endfacet + facet normal -0.160675 -0.967455 0.195484 + outer loop + vertex -505.132 78.8015 72.9148 + vertex -505.576 81.0804 83.8284 + vertex -507.614 80.1678 77.6372 + endloop + endfacet + facet normal -0.143128 -0.968254 0.204936 + outer loop + vertex -507.614 80.1678 77.6372 + vertex -507.189 78.9769 72.3069 + vertex -505.132 78.8015 72.9148 + endloop + endfacet + facet normal -0.147758 -0.963812 0.221886 + outer loop + vertex -507.189 78.9769 72.3069 + vertex -506.718 77.6718 66.9519 + vertex -505.132 78.8015 72.9148 + endloop + endfacet + facet normal -0.152386 -0.962849 0.222935 + outer loop + vertex -505.613 76.9884 64.7553 + vertex -505.132 78.8015 72.9148 + vertex -506.718 77.6718 66.9519 + endloop + endfacet + facet normal -0.140039 -0.964755 0.222795 + outer loop + vertex -506.718 77.6718 66.9519 + vertex -507.189 78.9769 72.3069 + vertex -509.923 79.4253 72.5304 + endloop + endfacet + facet normal -0.124981 -0.964784 0.231455 + outer loop + vertex -509.923 79.4253 72.5304 + vertex -507.595 77.3004 64.9301 + vertex -506.718 77.6718 66.9519 + endloop + endfacet + facet normal -0.127506 -0.964215 0.232446 + outer loop + vertex -507.595 77.3004 64.9301 + vertex -506.548 76.8468 63.6229 + vertex -506.718 77.6718 66.9519 + endloop + endfacet + facet normal -0.186542 -0.955783 0.227335 + outer loop + vertex -506.148 76.4215 62.163 + vertex -506.718 77.6718 66.9519 + vertex -506.548 76.8468 63.6229 + endloop + endfacet + facet normal -0.0970041 -0.961786 0.256043 + outer loop + vertex -506.548 76.8468 63.6229 + vertex -507.595 77.3004 64.9301 + vertex -506.301 76.0989 60.9069 + endloop + endfacet + facet normal -0.0836826 -0.962651 0.25749 + outer loop + vertex -506.548 76.8468 63.6229 + vertex -506.301 76.0989 60.9069 + vertex -506.148 76.4215 62.163 + endloop + endfacet + facet normal -0.122755 -0.961068 0.247547 + outer loop + vertex -506.301 76.0989 60.9069 + vertex -507.595 77.3004 64.9301 + vertex -507.492 76.1663 60.578 + endloop + endfacet + facet normal -0.144713 -0.958326 0.246314 + outer loop + vertex -507.595 77.3004 64.9301 + vertex -510.684 77.9723 65.7293 + vertex -507.492 76.1663 60.578 + endloop + endfacet + facet normal -0.151827 -0.962985 0.22273 + outer loop + vertex -507.595 77.3004 64.9301 + vertex -509.923 79.4253 72.5304 + vertex -510.684 77.9723 65.7293 + endloop + endfacet + facet normal -0.168518 -0.959922 0.223945 + outer loop + vertex -509.923 79.4253 72.5304 + vertex -516.123 80.4152 72.1074 + vertex -510.684 77.9723 65.7293 + endloop + endfacet + facet normal -0.166015 -0.959863 0.226056 + outer loop + vertex -516.014 78.7157 64.9719 + vertex -510.684 77.9723 65.7293 + vertex -516.123 80.4152 72.1074 + endloop + endfacet + facet normal -0.186756 -0.956319 0.224893 + outer loop + vertex -516.123 80.4152 72.1074 + vertex -523.982 81.7206 71.1331 + vertex -516.014 78.7157 64.9719 + endloop + endfacet + facet normal -0.185469 -0.960056 0.209506 + outer loop + vertex -516.123 80.4152 72.1074 + vertex -523.953 83.4757 79.2008 + vertex -523.982 81.7206 71.1331 + endloop + endfacet + facet normal -0.208626 -0.955491 0.208595 + outer loop + vertex -523.953 83.4757 79.2008 + vertex -533.8 85.4559 78.4229 + vertex -523.982 81.7206 71.1331 + endloop + endfacet + facet normal -0.204362 -0.955178 0.214177 + outer loop + vertex -523.982 81.7206 71.1331 + vertex -533.8 85.4559 78.4229 + vertex -533.792 83.5798 70.0637 + endloop + endfacet + facet normal -0.205436 -0.950907 0.231456 + outer loop + vertex -523.982 81.7206 71.1331 + vertex -533.792 83.5798 70.0637 + vertex -523.393 79.6705 63.233 + endloop + endfacet + facet normal -0.230661 -0.949464 0.21287 + outer loop + vertex -533.8 85.4559 78.4229 + vertex -545.042 88.0683 77.8938 + vertex -533.792 83.5798 70.0637 + endloop + endfacet + facet normal -0.227404 -0.949221 0.21741 + outer loop + vertex -533.792 83.5798 70.0637 + vertex -545.042 88.0683 77.8938 + vertex -545.077 86.1257 69.3752 + endloop + endfacet + facet normal -0.227531 -0.944521 0.236875 + outer loop + vertex -533.792 83.5798 70.0637 + vertex -545.077 86.1257 69.3752 + vertex -533.26 81.3509 61.6877 + endloop + endfacet + facet normal -0.255517 -0.942375 0.215966 + outer loop + vertex -545.042 88.0683 77.8938 + vertex -557.031 91.2685 77.6734 + vertex -545.077 86.1257 69.3752 + endloop + endfacet + facet normal -0.253066 -0.94224 0.219413 + outer loop + vertex -545.077 86.1257 69.3752 + vertex -557.031 91.2685 77.6734 + vertex -557.104 89.2975 69.1251 + endloop + endfacet + facet normal -0.252219 -0.937393 0.240166 + outer loop + vertex -545.077 86.1257 69.3752 + vertex -557.104 89.2975 69.1251 + vertex -544.935 83.9563 61.0574 + endloop + endfacet + facet normal -0.250462 -0.937212 0.242697 + outer loop + vertex -544.935 83.9563 61.0574 + vertex -557.104 89.2975 69.1251 + vertex -557.118 87.1367 60.7663 + endloop + endfacet + facet normal -0.275793 -0.930512 0.241009 + outer loop + vertex -557.104 89.2975 69.1251 + vertex -569.207 92.8279 68.9059 + vertex -557.118 87.1367 60.7663 + endloop + endfacet + facet normal -0.27375 -0.930354 0.243931 + outer loop + vertex -557.118 87.1367 60.7663 + vertex -569.207 92.8279 68.9059 + vertex -569.704 90.7331 60.3582 + endloop + endfacet + facet normal -0.272805 -0.924523 0.266147 + outer loop + vertex -557.118 87.1367 60.7663 + vertex -569.704 90.7331 60.3582 + vertex -557.445 84.9653 52.8883 + endloop + endfacet + facet normal -0.271925 -0.924395 0.267491 + outer loop + vertex -557.445 84.9653 52.8883 + vertex -569.704 90.7331 60.3582 + vertex -570.848 88.6706 52.0682 + endloop + endfacet + facet normal -0.291367 -0.918125 0.268612 + outer loop + vertex -569.704 90.7331 60.3582 + vertex -582.328 94.411 59.2359 + vertex -570.848 88.6706 52.0682 + endloop + endfacet + facet normal -0.289833 -0.917933 0.270915 + outer loop + vertex -570.848 88.6706 52.0682 + vertex -582.328 94.411 59.2359 + vertex -584.755 92.4797 50.0953 + endloop + endfacet + facet normal -0.291295 -0.908671 0.299105 + outer loop + vertex -570.848 88.6706 52.0682 + vertex -584.755 92.4797 50.0953 + vertex -572.861 86.943 44.8584 + endloop + endfacet + facet normal -0.286876 -0.907233 0.307622 + outer loop + vertex -572.861 86.943 44.8584 + vertex -584.755 92.4797 50.0953 + vertex -581.719 89.8065 45.0436 + endloop + endfacet + facet normal -0.297464 -0.906148 0.300683 + outer loop + vertex -581.719 89.8065 45.0436 + vertex -584.755 92.4797 50.0953 + vertex -587.937 91.7174 44.6502 + endloop + endfacet + facet normal -0.296816 -0.900535 0.317706 + outer loop + vertex -581.719 89.8065 45.0436 + vertex -587.937 91.7174 44.6502 + vertex -581.367 88.6279 42.0315 + endloop + endfacet + facet normal -0.30796 -0.91101 0.274266 + outer loop + vertex -582.328 94.411 59.2359 + vertex -593.361 97.2936 56.4219 + vertex -584.755 92.4797 50.0953 + endloop + endfacet + facet normal -0.310709 -0.91116 0.270642 + outer loop + vertex -584.755 92.4797 50.0953 + vertex -593.361 97.2936 56.4219 + vertex -592.885 95.6637 51.4819 + endloop + endfacet + facet normal -0.305206 -0.906413 0.292 + outer loop + vertex -592.885 95.6637 51.4819 + vertex -593.444 94.7443 48.0433 + vertex -584.755 92.4797 50.0953 + endloop + endfacet + facet normal -0.311206 -0.911019 0.270547 + outer loop + vertex -592.885 95.6637 51.4819 + vertex -593.361 97.2936 56.4219 + vertex -596.724 96.9444 51.3782 + endloop + endfacet + facet normal -0.304225 -0.918746 0.251699 + outer loop + vertex -582.328 94.411 59.2359 + vertex -591.908 99.8156 67.385 + vertex -593.361 97.2936 56.4219 + endloop + endfacet + facet normal -0.306681 -0.918721 0.248795 + outer loop + vertex -580.771 96.3347 68.2588 + vertex -591.908 99.8156 67.385 + vertex -582.328 94.411 59.2359 + endloop + endfacet + facet normal -0.291224 -0.924142 0.247284 + outer loop + vertex -569.704 90.7331 60.3582 + vertex -580.771 96.3347 68.2588 + vertex -582.328 94.411 59.2359 + endloop + endfacet + facet normal -0.293908 -0.924268 0.243613 + outer loop + vertex -569.207 92.8279 68.9059 + vertex -580.771 96.3347 68.2588 + vertex -569.704 90.7331 60.3582 + endloop + endfacet + facet normal -0.294254 -0.928772 0.225382 + outer loop + vertex -569.207 92.8279 68.9059 + vertex -580.018 98.1504 76.7241 + vertex -580.771 96.3347 68.2588 + endloop + endfacet + facet normal -0.309982 -0.923573 0.225665 + outer loop + vertex -580.018 98.1504 76.7241 + vertex -588.279 100.556 75.2232 + vertex -580.771 96.3347 68.2588 + endloop + endfacet + facet normal -0.297843 -0.928813 0.220446 + outer loop + vertex -569.029 94.8014 77.4609 + vertex -580.018 98.1504 76.7241 + vertex -569.207 92.8279 68.9059 + endloop + endfacet + facet normal -0.297879 -0.932224 0.205492 + outer loop + vertex -569.029 94.8014 77.4609 + vertex -579.975 100.033 85.3263 + vertex -580.018 98.1504 76.7241 + endloop + endfacet + facet normal -0.315043 -0.926807 0.204392 + outer loop + vertex -579.975 100.033 85.3263 + vertex -588.935 102.609 83.1977 + vertex -580.018 98.1504 76.7241 + endloop + endfacet + facet normal -0.301797 -0.932159 0.199997 + outer loop + vertex -568.848 96.6062 86.1458 + vertex -579.975 100.033 85.3263 + vertex -569.029 94.8014 77.4609 + endloop + endfacet + facet normal -0.279975 -0.938748 0.200912 + outer loop + vertex -557.031 91.2685 77.6734 + vertex -568.848 96.6062 86.1458 + vertex -569.029 94.8014 77.4609 + endloop + endfacet + facet normal -0.282368 -0.938741 0.197569 + outer loop + vertex -556.78 93.018 86.3447 + vertex -568.848 96.6062 86.1458 + vertex -557.031 91.2685 77.6734 + endloop + endfacet + facet normal -0.282975 -0.941625 0.182392 + outer loop + vertex -556.78 93.018 86.3447 + vertex -568.478 98.1996 94.9453 + vertex -568.848 96.6062 86.1458 + endloop + endfacet + facet normal -0.305019 -0.934779 0.182078 + outer loop + vertex -568.478 98.1996 94.9453 + vertex -579.876 101.812 94.3954 + vertex -568.848 96.6062 86.1458 + endloop + endfacet + facet normal -0.305154 -0.937247 0.168667 + outer loop + vertex -568.478 98.1996 94.9453 + vertex -579.183 103.176 103.23 + vertex -579.876 101.812 94.3954 + endloop + endfacet + facet normal -0.322793 -0.931237 0.169122 + outer loop + vertex -579.183 103.176 103.23 + vertex -589.558 106.705 102.86 + vertex -579.876 101.812 94.3954 + endloop + endfacet + facet normal -0.307552 -0.937038 0.165443 + outer loop + vertex -568.081 99.6183 103.719 + vertex -579.183 103.176 103.23 + vertex -568.478 98.1996 94.9453 + endloop + endfacet + facet normal -0.285526 -0.943961 0.165565 + outer loop + vertex -556.447 94.5901 95.1158 + vertex -568.081 99.6183 103.719 + vertex -568.478 98.1996 94.9453 + endloop + endfacet + facet normal -0.287046 -0.943868 0.163455 + outer loop + vertex -556.185 96.0368 103.93 + vertex -568.081 99.6183 103.719 + vertex -556.447 94.5901 95.1158 + endloop + endfacet + facet normal -0.260704 -0.951403 0.163909 + outer loop + vertex -544.539 91.3584 95.2971 + vertex -556.185 96.0368 103.93 + vertex -556.447 94.5901 95.1158 + endloop + endfacet + facet normal -0.26027 -0.949024 0.1778 + outer loop + vertex -544.539 91.3584 95.2971 + vertex -556.447 94.5901 95.1158 + vertex -544.804 89.7889 86.5318 + endloop + endfacet + facet normal -0.233235 -0.955949 0.178222 + outer loop + vertex -533.596 87.1344 86.9608 + vertex -544.539 91.3584 95.2971 + vertex -544.804 89.7889 86.5318 + endloop + endfacet + facet normal -0.233127 -0.953113 0.192945 + outer loop + vertex -533.596 87.1344 86.9608 + vertex -544.804 89.7889 86.5318 + vertex -533.8 85.4559 78.4229 + endloop + endfacet + facet normal -0.23525 -0.955945 0.175574 + outer loop + vertex -533.395 88.6869 95.6828 + vertex -544.539 91.3584 95.2971 + vertex -533.596 87.1344 86.9608 + endloop + endfacet + facet normal -0.210692 -0.961576 0.176011 + outer loop + vertex -523.823 85.1177 87.6417 + vertex -533.395 88.6869 95.6828 + vertex -533.596 87.1344 86.9608 + endloop + endfacet + facet normal -0.211092 -0.958867 0.189773 + outer loop + vertex -523.823 85.1177 87.6417 + vertex -533.596 87.1344 86.9608 + vertex -523.953 83.4757 79.2008 + endloop + endfacet + facet normal -0.188948 -0.96337 0.190308 + outer loop + vertex -516.11 82.1197 80.1235 + vertex -523.823 85.1177 87.6417 + vertex -523.953 83.4757 79.2008 + endloop + endfacet + facet normal -0.192898 -0.963378 0.18626 + outer loop + vertex -516.107 83.7611 88.6166 + vertex -523.823 85.1177 87.6417 + vertex -516.11 82.1197 80.1235 + endloop + endfacet + facet normal -0.169696 -0.96758 0.187063 + outer loop + vertex -510.857 81.536 81.8695 + vertex -516.107 83.7611 88.6166 + vertex -516.11 82.1197 80.1235 + endloop + endfacet + facet normal -0.173787 -0.964153 0.200515 + outer loop + vertex -510.857 81.536 81.8695 + vertex -516.11 82.1197 80.1235 + vertex -509.923 79.4253 72.5304 + endloop + endfacet + facet normal -0.17625 -0.967392 0.181902 + outer loop + vertex -510.552 83.0358 90.142 + vertex -516.107 83.7611 88.6166 + vertex -510.857 81.536 81.8695 + endloop + endfacet + facet normal -0.145903 -0.972469 0.181702 + outer loop + vertex -510.552 83.0358 90.142 + vertex -510.857 81.536 81.8695 + vertex -508.153 81.5303 84.0107 + endloop + endfacet + facet normal -0.172877 -0.970485 0.168145 + outer loop + vertex -510.552 83.0358 90.142 + vertex -516.017 85.2225 97.1443 + vertex -516.107 83.7611 88.6166 + endloop + endfacet + facet normal -0.19666 -0.966035 0.167635 + outer loop + vertex -516.017 85.2225 97.1443 + vertex -523.663 86.6284 96.276 + vertex -516.107 83.7611 88.6166 + endloop + endfacet + facet normal -0.195652 -0.968344 0.155017 + outer loop + vertex -516.017 85.2225 97.1443 + vertex -523.476 87.979 104.948 + vertex -523.663 86.6284 96.276 + endloop + endfacet + facet normal -0.21709 -0.963804 0.154771 + outer loop + vertex -523.476 87.979 104.948 + vertex -533.202 90.091 104.459 + vertex -523.663 86.6284 96.276 + endloop + endfacet + facet normal -0.213559 -0.963915 0.158934 + outer loop + vertex -523.663 86.6284 96.276 + vertex -533.202 90.091 104.459 + vertex -533.395 88.6869 95.6828 + endloop + endfacet + facet normal -0.237974 -0.958241 0.158564 + outer loop + vertex -533.202 90.091 104.459 + vertex -544.339 92.8008 104.12 + vertex -533.395 88.6869 95.6828 + endloop + endfacet + facet normal -0.23808 -0.960429 0.144549 + outer loop + vertex -533.202 90.091 104.459 + vertex -544.151 94.0782 112.916 + vertex -544.339 92.8008 104.12 + endloop + endfacet + facet normal -0.265117 -0.953387 0.144102 + outer loop + vertex -544.151 94.0782 112.916 + vertex -556.018 97.3517 112.742 + vertex -544.339 92.8008 104.12 + endloop + endfacet + facet normal -0.262851 -0.953534 0.147248 + outer loop + vertex -544.339 92.8008 104.12 + vertex -556.018 97.3517 112.742 + vertex -556.185 96.0368 103.93 + endloop + endfacet + facet normal -0.289565 -0.945863 0.146609 + outer loop + vertex -556.018 97.3517 112.742 + vertex -567.907 100.956 112.515 + vertex -556.185 96.0368 103.93 + endloop + endfacet + facet normal -0.289922 -0.948006 0.131267 + outer loop + vertex -556.018 97.3517 112.742 + vertex -567.843 102.169 121.417 + vertex -567.907 100.956 112.515 + endloop + endfacet + facet normal -0.313065 -0.940731 0.130442 + outer loop + vertex -567.843 102.169 121.417 + vertex -579.066 105.824 120.837 + vertex -567.907 100.956 112.515 + endloop + endfacet + facet normal -0.309677 -0.941174 0.135244 + outer loop + vertex -567.907 100.956 112.515 + vertex -579.066 105.824 120.837 + vertex -578.761 104.42 111.77 + endloop + endfacet + facet normal -0.309931 -0.939016 0.14897 + outer loop + vertex -567.907 100.956 112.515 + vertex -578.761 104.42 111.77 + vertex -568.081 99.6183 103.719 + endloop + endfacet + facet normal -0.328863 -0.934876 0.133624 + outer loop + vertex -579.066 105.824 120.837 + vertex -587.946 108.631 118.627 + vertex -578.761 104.42 111.77 + endloop + endfacet + facet normal -0.312919 -0.942989 0.113375 + outer loop + vertex -567.843 102.169 121.417 + vertex -578.972 106.915 130.172 + vertex -579.066 105.824 120.837 + endloop + endfacet + facet normal -0.332313 -0.936399 0.1128 + outer loop + vertex -578.972 106.915 130.172 + vertex -589.28 110.49 129.48 + vertex -579.066 105.824 120.837 + endloop + endfacet + facet normal -0.315143 -0.942608 0.110341 + outer loop + vertex -567.67 103.155 130.326 + vertex -578.972 106.915 130.172 + vertex -567.843 102.169 121.417 + endloop + endfacet + facet normal -0.292585 -0.94981 0.110702 + outer loop + vertex -555.868 98.4959 121.549 + vertex -567.67 103.155 130.326 + vertex -567.843 102.169 121.417 + endloop + endfacet + facet normal -0.293779 -0.949638 0.109005 + outer loop + vertex -555.725 99.4675 130.4 + vertex -567.67 103.155 130.326 + vertex -555.868 98.4959 121.549 + endloop + endfacet + facet normal -0.267504 -0.957323 0.109424 + outer loop + vertex -543.964 95.1859 121.694 + vertex -555.725 99.4675 130.4 + vertex -555.868 98.4959 121.549 + endloop + endfacet + facet normal -0.267159 -0.955343 0.12628 + outer loop + vertex -543.964 95.1859 121.694 + vertex -555.868 98.4959 121.549 + vertex -544.151 94.0782 112.916 + endloop + endfacet + facet normal -0.240629 -0.962326 0.126593 + outer loop + vertex -532.996 91.3273 113.208 + vertex -543.964 95.1859 121.694 + vertex -544.151 94.0782 112.916 + endloop + endfacet + facet normal -0.242787 -0.962157 0.123727 + outer loop + vertex -532.767 92.3927 121.942 + vertex -543.964 95.1859 121.694 + vertex -532.996 91.3273 113.208 + endloop + endfacet + facet normal -0.220173 -0.967573 0.123795 + outer loop + vertex -523.225 89.1556 113.613 + vertex -532.767 92.3927 121.942 + vertex -532.996 91.3273 113.208 + endloop + endfacet + facet normal -0.220322 -0.965685 0.137517 + outer loop + vertex -523.225 89.1556 113.613 + vertex -532.996 91.3273 113.208 + vertex -523.476 87.979 104.948 + endloop + endfacet + facet normal -0.20009 -0.970078 0.137526 + outer loop + vertex -515.791 86.4997 105.695 + vertex -523.225 89.1556 113.613 + vertex -523.476 87.979 104.948 + endloop + endfacet + facet normal -0.204765 -0.96973 0.133021 + outer loop + vertex -515.491 87.6173 114.305 + vertex -523.225 89.1556 113.613 + vertex -515.791 86.4997 105.695 + endloop + endfacet + facet normal -0.184379 -0.973836 0.132844 + outer loop + vertex -510.169 85.6233 107.073 + vertex -515.491 87.6173 114.305 + vertex -515.791 86.4997 105.695 + endloop + endfacet + facet normal -0.18689 -0.971704 0.144442 + outer loop + vertex -510.169 85.6233 107.073 + vertex -515.791 86.4997 105.695 + vertex -510.84 84.5224 98.7995 + endloop + endfacet + facet normal -0.161655 -0.976428 0.143025 + outer loop + vertex -510.169 85.6233 107.073 + vertex -510.84 84.5224 98.7995 + vertex -508.073 84.3751 100.921 + endloop + endfacet + facet normal -0.179434 -0.972274 0.149958 + outer loop + vertex -510.84 84.5224 98.7995 + vertex -515.791 86.4997 105.695 + vertex -516.017 85.2225 97.1443 + endloop + endfacet + facet normal -0.192326 -0.973105 0.126794 + outer loop + vertex -510.237 86.8006 116.005 + vertex -515.491 87.6173 114.305 + vertex -510.169 85.6233 107.073 + endloop + endfacet + facet normal -0.169656 -0.97722 0.12751 + outer loop + vertex -510.237 86.8006 116.005 + vertex -510.169 85.6233 107.073 + vertex -507.249 85.7626 112.025 + endloop + endfacet + facet normal -0.189134 -0.975078 0.115984 + outer loop + vertex -510.237 86.8006 116.005 + vertex -515.134 88.5789 122.971 + vertex -515.491 87.6173 114.305 + endloop + endfacet + facet normal -0.207907 -0.971207 0.116328 + outer loop + vertex -515.134 88.5789 122.971 + vertex -522.938 90.1683 122.291 + vertex -515.491 87.6173 114.305 + endloop + endfacet + facet normal -0.207042 -0.972973 0.102263 + outer loop + vertex -515.134 88.5789 122.971 + vertex -522.605 91.0141 131.013 + vertex -522.938 90.1683 122.291 + endloop + endfacet + facet normal -0.225328 -0.968869 0.102563 + outer loop + vertex -522.605 91.0141 131.013 + vertex -532.523 93.289 130.714 + vertex -522.938 90.1683 122.291 + endloop + endfacet + facet normal -0.223055 -0.969108 0.105239 + outer loop + vertex -522.938 90.1683 122.291 + vertex -532.523 93.289 130.714 + vertex -532.767 92.3927 121.942 + endloop + endfacet + facet normal -0.244683 -0.963868 0.105306 + outer loop + vertex -532.523 93.289 130.714 + vertex -543.781 96.1254 130.518 + vertex -532.767 92.3927 121.942 + endloop + endfacet + facet normal -0.244808 -0.96553 0.0884356 + outer loop + vertex -532.523 93.289 130.714 + vertex -543.622 96.9021 139.436 + vertex -543.781 96.1254 130.518 + endloop + endfacet + facet normal -0.270018 -0.958798 0.0882971 + outer loop + vertex -543.622 96.9021 139.436 + vertex -555.613 100.271 139.354 + vertex -543.781 96.1254 130.518 + endloop + endfacet + facet normal -0.269201 -0.958921 0.0894493 + outer loop + vertex -543.781 96.1254 130.518 + vertex -555.613 100.271 139.354 + vertex -555.725 99.4675 130.4 + endloop + endfacet + facet normal -0.294989 -0.951338 0.0890907 + outer loop + vertex -555.613 100.271 139.354 + vertex -567.54 103.96 139.254 + vertex -555.725 99.4675 130.4 + endloop + endfacet + facet normal -0.295284 -0.952793 0.0706557 + outer loop + vertex -555.613 100.271 139.354 + vertex -567.478 104.609 148.269 + vertex -567.54 103.96 139.254 + endloop + endfacet + facet normal -0.317523 -0.945642 0.0702941 + outer loop + vertex -567.478 104.609 148.269 + vertex -578.437 108.26 147.87 + vertex -567.54 103.96 139.254 + endloop + endfacet + facet normal -0.316504 -0.945878 0.071701 + outer loop + vertex -567.54 103.96 139.254 + vertex -578.437 108.26 147.87 + vertex -578.443 107.591 139.029 + endloop + endfacet + facet normal -0.316377 -0.944368 0.0898557 + outer loop + vertex -567.54 103.96 139.254 + vertex -578.443 107.591 139.029 + vertex -567.67 103.155 130.326 + endloop + endfacet + facet normal -0.333863 -0.939924 0.0712628 + outer loop + vertex -578.437 108.26 147.87 + vertex -586.22 110.925 146.559 + vertex -578.443 107.591 139.029 + endloop + endfacet + facet normal -0.317285 -0.946879 0.0524471 + outer loop + vertex -567.478 104.609 148.269 + vertex -578.353 108.724 156.756 + vertex -578.437 108.26 147.87 + endloop + endfacet + facet normal -0.335236 -0.940682 0.052292 + outer loop + vertex -578.353 108.724 156.756 + vertex -588.25 112.218 156.157 + vertex -578.437 108.26 147.87 + endloop + endfacet + facet normal -0.318504 -0.946563 0.0507322 + outer loop + vertex -567.354 105.049 157.247 + vertex -578.353 108.724 156.756 + vertex -567.478 104.609 148.269 + endloop + endfacet + facet normal -0.296123 -0.953799 0.0507795 + outer loop + vertex -555.497 100.896 148.387 + vertex -567.354 105.049 157.247 + vertex -567.478 104.609 148.269 + endloop + endfacet + facet normal -0.296639 -0.953678 0.0500328 + outer loop + vertex -555.345 101.321 157.388 + vertex -567.354 105.049 157.247 + vertex -555.497 100.896 148.387 + endloop + endfacet + facet normal -0.271256 -0.96121 0.0499586 + outer loop + vertex -543.442 97.4956 148.415 + vertex -555.345 101.321 157.388 + vertex -555.497 100.896 148.387 + endloop + endfacet + facet normal -0.270989 -0.960112 0.0689174 + outer loop + vertex -543.442 97.4956 148.415 + vertex -555.497 100.896 148.387 + vertex -543.622 96.9021 139.436 + endloop + endfacet + facet normal -0.246336 -0.966735 0.06886 + outer loop + vertex -532.28 94.0211 139.564 + vertex -543.442 97.4956 148.415 + vertex -543.622 96.9021 139.436 + endloop + endfacet + facet normal -0.247205 -0.966595 0.0677084 + outer loop + vertex -532.02 94.5788 148.476 + vertex -543.442 97.4956 148.415 + vertex -532.28 94.0211 139.564 + endloop + endfacet + facet normal -0.226857 -0.971591 0.067426 + outer loop + vertex -522.289 91.7054 139.812 + vertex -532.02 94.5788 148.476 + vertex -532.28 94.0211 139.564 + endloop + endfacet + facet normal -0.226964 -0.97024 0.0843932 + outer loop + vertex -522.289 91.7054 139.812 + vertex -532.28 94.0211 139.564 + vertex -522.605 91.0141 131.013 + endloop + endfacet + facet normal -0.209441 -0.9742 0.0840751 + outer loop + vertex -514.715 89.3745 131.671 + vertex -522.289 91.7054 139.812 + vertex -522.605 91.0141 131.013 + endloop + endfacet + facet normal -0.212125 -0.97384 0.081475 + outer loop + vertex -514.31 90.0171 140.405 + vertex -522.289 91.7054 139.812 + vertex -514.715 89.3745 131.671 + endloop + endfacet + facet normal -0.194752 -0.977507 0.0809406 + outer loop + vertex -509.309 88.4402 133.394 + vertex -514.31 90.0171 140.405 + vertex -514.715 89.3745 131.671 + endloop + endfacet + facet normal -0.198415 -0.975654 0.0934379 + outer loop + vertex -509.309 88.4402 133.394 + vertex -514.715 89.3745 131.671 + vertex -509.345 87.5893 124.434 + endloop + endfacet + facet normal -0.178139 -0.979531 0.0937261 + outer loop + vertex -509.309 88.4402 133.394 + vertex -509.345 87.5893 124.434 + vertex -506.272 87.5241 129.593 + endloop + endfacet + facet normal -0.191823 -0.976471 0.0985308 + outer loop + vertex -509.345 87.5893 124.434 + vertex -514.715 89.3745 131.671 + vertex -515.134 88.5789 122.971 + endloop + endfacet + facet normal -0.199378 -0.976854 0.0774933 + outer loop + vertex -508.461 88.9252 141.69 + vertex -514.31 90.0171 140.405 + vertex -509.309 88.4402 133.394 + endloop + endfacet + facet normal -0.179729 -0.980798 0.0757153 + outer loop + vertex -508.461 88.9252 141.69 + vertex -509.309 88.4402 133.394 + vertex -506.3 88.0739 135.793 + endloop + endfacet + facet normal -0.196463 -0.978496 0.0628285 + outer loop + vertex -508.461 88.9252 141.69 + vertex -513.936 90.5043 149.164 + vertex -514.31 90.0171 140.405 + endloop + endfacet + facet normal -0.213607 -0.974863 0.0633598 + outer loop + vertex -513.936 90.5043 149.164 + vertex -521.942 92.2259 148.661 + vertex -514.31 90.0171 140.405 + endloop + endfacet + facet normal -0.212813 -0.975964 0.0469553 + outer loop + vertex -513.936 90.5043 149.164 + vertex -521.648 92.589 157.542 + vertex -521.942 92.2259 148.661 + endloop + endfacet + facet normal -0.228795 -0.972323 0.047336 + outer loop + vertex -521.648 92.589 157.542 + vertex -531.78 94.9664 157.403 + vertex -521.942 92.2259 148.661 + endloop + endfacet + facet normal -0.227929 -0.972476 0.0483593 + outer loop + vertex -521.942 92.2259 148.661 + vertex -531.78 94.9664 157.403 + vertex -532.02 94.5788 148.476 + endloop + endfacet + facet normal -0.247787 -0.967591 0.0486813 + outer loop + vertex -531.78 94.9664 157.403 + vertex -543.251 97.903 157.382 + vertex -532.02 94.5788 148.476 + endloop + endfacet + facet normal -0.247942 -0.968336 0.0291674 + outer loop + vertex -531.78 94.9664 157.403 + vertex -543.071 98.1252 166.289 + vertex -543.251 97.903 157.382 + endloop + endfacet + facet normal -0.271757 -0.961914 0.0294886 + outer loop + vertex -543.071 98.1252 166.289 + vertex -555.206 101.554 166.311 + vertex -543.251 97.903 157.382 + endloop + endfacet + facet normal -0.271845 -0.961893 0.0293618 + outer loop + vertex -543.251 97.903 157.382 + vertex -555.206 101.554 166.311 + vertex -555.345 101.321 157.388 + endloop + endfacet + facet normal -0.297081 -0.954395 0.0295603 + outer loop + vertex -555.206 101.554 166.311 + vertex -567.257 105.3 166.133 + vertex -555.345 101.321 157.388 + endloop + endfacet + facet normal -0.29692 -0.954862 0.00880671 + outer loop + vertex -555.206 101.554 166.311 + vertex -567.251 105.38 175.026 + vertex -567.257 105.3 166.133 + endloop + endfacet + facet normal -0.319596 -0.947514 0.00875453 + outer loop + vertex -567.251 105.38 175.026 + vertex -578.363 109.12 174.173 + vertex -567.257 105.3 166.133 + endloop + endfacet + facet normal -0.318095 -0.947994 0.0110557 + outer loop + vertex -567.257 105.3 166.133 + vertex -578.363 109.12 174.173 + vertex -578.152 108.947 165.371 + endloop + endfacet + facet normal -0.319174 -0.947214 0.0302231 + outer loop + vertex -567.257 105.3 166.133 + vertex -578.152 108.947 165.371 + vertex -567.354 105.049 157.247 + endloop + endfacet + facet normal -0.337269 -0.94135 0.0104641 + outer loop + vertex -578.363 109.12 174.173 + vertex -587.237 112.276 172.024 + vertex -578.152 108.947 165.371 + endloop + endfacet + facet normal -0.318084 -0.947974 -0.0129487 + outer loop + vertex -567.251 105.38 175.026 + vertex -578.713 109.111 183.454 + vertex -578.363 109.12 174.173 + endloop + endfacet + facet normal -0.337593 -0.941193 -0.0136777 + outer loop + vertex -578.713 109.111 183.454 + vertex -587.867 112.424 181.419 + vertex -578.363 109.12 174.173 + endloop + endfacet + facet normal -0.318888 -0.947687 -0.0141693 + outer loop + vertex -567.272 105.253 183.99 + vertex -578.713 109.111 183.454 + vertex -567.251 105.38 175.026 + endloop + endfacet + facet normal -0.29663 -0.954887 -0.0142191 + outer loop + vertex -555.111 101.607 175.168 + vertex -567.272 105.253 183.99 + vertex -567.251 105.38 175.026 + endloop + endfacet + facet normal -0.295954 -0.955111 -0.0131935 + outer loop + vertex -555.071 101.472 184.015 + vertex -567.272 105.253 183.99 + vertex -555.111 101.607 175.168 + endloop + endfacet + facet normal -0.271506 -0.962343 -0.0134151 + outer loop + vertex -542.938 98.1726 175.14 + vertex -555.071 101.472 184.015 + vertex -555.111 101.607 175.168 + endloop + endfacet + facet normal -0.271471 -0.962402 0.00924806 + outer loop + vertex -542.938 98.1726 175.14 + vertex -555.111 101.607 175.168 + vertex -543.071 98.1252 166.289 + endloop + endfacet + facet normal -0.247973 -0.968726 0.00892735 + outer loop + vertex -531.557 95.1779 166.294 + vertex -542.938 98.1726 175.14 + vertex -543.071 98.1252 166.289 + endloop + endfacet + facet normal -0.247692 -0.968794 0.00931186 + outer loop + vertex -531.363 95.2133 175.137 + vertex -542.938 98.1726 175.14 + vertex -531.557 95.1779 166.294 + endloop + endfacet + facet normal -0.229058 -0.973372 0.00892143 + outer loop + vertex -521.348 92.7765 166.395 + vertex -531.363 95.2133 175.137 + vertex -531.557 95.1779 166.294 + endloop + endfacet + facet normal -0.229157 -0.972976 0.0283517 + outer loop + vertex -521.348 92.7765 166.395 + vertex -531.557 95.1779 166.294 + vertex -521.648 92.589 157.542 + endloop + endfacet + facet normal -0.213774 -0.976484 0.0279059 + outer loop + vertex -513.543 90.8272 157.975 + vertex -521.348 92.7765 166.395 + vertex -521.648 92.589 157.542 + endloop + endfacet + facet normal -0.214991 -0.97625 0.0267232 + outer loop + vertex -513.148 90.9811 166.777 + vertex -521.348 92.7765 166.395 + vertex -513.543 90.8272 157.975 + endloop + endfacet + facet normal -0.199243 -0.979603 0.0260745 + outer loop + vertex -507.524 89.6331 159.109 + vertex -513.148 90.9811 166.777 + vertex -513.543 90.8272 157.975 + endloop + endfacet + facet normal -0.202099 -0.978444 0.0424559 + outer loop + vertex -507.524 89.6331 159.109 + vertex -513.543 90.8272 157.975 + vertex -508.432 89.4465 150.484 + endloop + endfacet + facet normal -0.186224 -0.981658 0.0408541 + outer loop + vertex -507.524 89.6331 159.109 + vertex -508.432 89.4465 150.484 + vertex -504.987 88.8621 152.146 + endloop + endfacet + facet normal -0.198913 -0.978996 0.0447312 + outer loop + vertex -508.432 89.4465 150.484 + vertex -513.543 90.8272 157.975 + vertex -513.936 90.5043 149.164 + endloop + endfacet + facet normal -0.203708 -0.97877 0.0226532 + outer loop + vertex -507.54 89.8443 168.091 + vertex -513.148 90.9811 166.777 + vertex -507.524 89.6331 159.109 + endloop + endfacet + facet normal -0.180666 -0.98328 0.0227991 + outer loop + vertex -507.54 89.8443 168.091 + vertex -507.524 89.6331 159.109 + vertex -504.771 89.228 163.456 + endloop + endfacet + facet normal -0.200195 -0.979732 0.00682991 + outer loop + vertex -507.54 89.8443 168.091 + vertex -512.773 90.9655 175.546 + vertex -513.148 90.9811 166.777 + endloop + endfacet + facet normal -0.21501 -0.976583 0.00746933 + outer loop + vertex -512.773 90.9655 175.546 + vertex -521.063 92.7881 175.201 + vertex -513.148 90.9811 166.777 + endloop + endfacet + facet normal -0.214229 -0.97671 -0.0119943 + outer loop + vertex -512.773 90.9655 175.546 + vertex -520.765 92.6152 183.958 + vertex -521.063 92.7881 175.201 + endloop + endfacet + facet normal -0.22877 -0.973413 -0.0114343 + outer loop + vertex -520.765 92.6152 183.958 + vertex -531.189 95.0651 183.944 + vertex -521.063 92.7881 175.201 + endloop + endfacet + facet normal -0.229105 -0.97333 -0.0118447 + outer loop + vertex -521.063 92.7881 175.201 + vertex -531.189 95.0651 183.944 + vertex -531.363 95.2133 175.137 + endloop + endfacet + facet normal -0.247169 -0.968905 -0.0114136 + outer loop + vertex -531.189 95.0651 183.944 + vertex -542.857 98.0415 183.967 + vertex -531.363 95.2133 175.137 + endloop + endfacet + facet normal -0.247084 -0.968395 -0.0340588 + outer loop + vertex -531.189 95.0651 183.944 + vertex -542.786 97.7126 192.8 + vertex -542.857 98.0415 183.967 + endloop + endfacet + facet normal -0.269241 -0.962484 -0.0336594 + outer loop + vertex -542.786 97.7126 192.8 + vertex -555.063 101.144 192.869 + vertex -542.857 98.0415 183.967 + endloop + endfacet + facet normal -0.270376 -0.962106 -0.0353475 + outer loop + vertex -542.857 98.0415 183.967 + vertex -555.063 101.144 192.869 + vertex -555.071 101.472 184.015 + endloop + endfacet + facet normal -0.294025 -0.955154 -0.035069 + outer loop + vertex -555.063 101.144 192.869 + vertex -567.235 104.888 192.95 + vertex -555.071 101.472 184.015 + endloop + endfacet + facet normal -0.293824 -0.953954 -0.0603334 + outer loop + vertex -555.063 101.144 192.869 + vertex -567.219 104.321 201.836 + vertex -567.235 104.888 192.95 + endloop + endfacet + facet normal -0.31397 -0.947542 -0.0598878 + outer loop + vertex -567.219 104.321 201.836 + vertex -578.444 108.035 201.921 + vertex -567.235 104.888 192.95 + endloop + endfacet + facet normal -0.31619 -0.946602 -0.0629922 + outer loop + vertex -567.235 104.888 192.95 + vertex -578.444 108.035 201.921 + vertex -578.746 108.741 192.844 + endloop + endfacet + facet normal -0.316812 -0.947756 -0.0372552 + outer loop + vertex -567.235 104.888 192.95 + vertex -578.746 108.741 192.844 + vertex -567.272 105.253 183.99 + endloop + endfacet + facet normal -0.332224 -0.941158 -0.062035 + outer loop + vertex -578.444 108.035 201.921 + vertex -587.96 111.401 201.825 + vertex -578.746 108.741 192.844 + endloop + endfacet + facet normal -0.313575 -0.94578 -0.084679 + outer loop + vertex -567.219 104.321 201.836 + vertex -578.252 107.196 210.582 + vertex -578.444 108.035 201.921 + endloop + endfacet + facet normal -0.328499 -0.940774 -0.0838636 + outer loop + vertex -578.252 107.196 210.582 + vertex -587.393 110.375 210.733 + vertex -578.444 108.035 201.921 + endloop + endfacet + facet normal -0.311868 -0.946557 -0.0822713 + outer loop + vertex -567.331 103.586 210.719 + vertex -578.252 107.196 210.582 + vertex -567.219 104.321 201.836 + endloop + endfacet + facet normal -0.291731 -0.952932 -0.082544 + outer loop + vertex -555.091 100.616 201.747 + vertex -567.331 103.586 210.719 + vertex -567.219 104.321 201.836 + endloop + endfacet + facet normal -0.290254 -0.953573 -0.0803165 + outer loop + vertex -555.16 99.885 210.68 + vertex -567.331 103.586 210.719 + vertex -555.091 100.616 201.747 + endloop + endfacet + facet normal -0.26743 -0.960194 -0.0806808 + outer loop + vertex -542.744 97.1849 201.659 + vertex -555.16 99.885 210.68 + vertex -555.091 100.616 201.747 + endloop + endfacet + facet normal -0.26772 -0.961866 -0.0560302 + outer loop + vertex -542.744 97.1849 201.659 + vertex -555.091 100.616 201.747 + vertex -542.786 97.7126 192.8 + endloop + endfacet + facet normal -0.246067 -0.967606 -0.0564743 + outer loop + vertex -531.008 94.7211 192.736 + vertex -542.744 97.1849 201.659 + vertex -542.786 97.7126 192.8 + endloop + endfacet + facet normal -0.244938 -0.967984 -0.0548853 + outer loop + vertex -530.851 94.1825 201.534 + vertex -542.744 97.1849 201.659 + vertex -531.008 94.7211 192.736 + endloop + endfacet + facet normal -0.227614 -0.972171 -0.0554513 + outer loop + vertex -520.478 92.2586 192.689 + vertex -530.851 94.1825 201.534 + vertex -531.008 94.7211 192.736 + endloop + endfacet + facet normal -0.227746 -0.973186 -0.0322708 + outer loop + vertex -520.478 92.2586 192.689 + vertex -531.008 94.7211 192.736 + vertex -520.765 92.6152 183.958 + endloop + endfacet + facet normal -0.213593 -0.97637 -0.0328663 + outer loop + vertex -512.365 90.7676 184.257 + vertex -520.478 92.2586 192.689 + vertex -520.765 92.6152 183.958 + endloop + endfacet + facet normal -0.213189 -0.976472 -0.0324592 + outer loop + vertex -511.999 90.3985 192.957 + vertex -520.478 92.2586 192.689 + vertex -512.365 90.7676 184.257 + endloop + endfacet + facet normal -0.199031 -0.979431 -0.03318 + outer loop + vertex -506.602 89.5517 185.576 + vertex -511.999 90.3985 192.957 + vertex -512.365 90.7676 184.257 + endloop + endfacet + facet normal -0.202983 -0.979058 -0.0155753 + outer loop + vertex -506.602 89.5517 185.576 + vertex -512.365 90.7676 184.257 + vertex -506.595 89.6916 176.688 + endloop + endfacet + facet normal -0.181194 -0.983323 -0.015625 + outer loop + vertex -506.602 89.5517 185.576 + vertex -506.595 89.6916 176.688 + vertex -503.734 89.0949 181.065 + endloop + endfacet + facet normal -0.199637 -0.979785 -0.0129209 + outer loop + vertex -506.595 89.6916 176.688 + vertex -512.365 90.7676 184.257 + vertex -512.773 90.9655 175.546 + endloop + endfacet + facet normal -0.200772 -0.97903 -0.0344988 + outer loop + vertex -505.666 89.0576 194.152 + vertex -511.999 90.3985 192.957 + vertex -506.602 89.5517 185.576 + endloop + endfacet + facet normal -0.18574 -0.981928 -0.036306 + outer loop + vertex -505.666 89.0576 194.152 + vertex -506.602 89.5517 185.576 + vertex -502.934 88.788 187.47 + endloop + endfacet + facet normal -0.196943 -0.978892 -0.0546301 + outer loop + vertex -505.666 89.0576 194.152 + vertex -511.651 89.8423 201.666 + vertex -511.999 90.3985 192.957 + endloop + endfacet + facet normal -0.21166 -0.975859 -0.0538467 + outer loop + vertex -511.651 89.8423 201.666 + vertex -520.24 91.7186 201.423 + vertex -511.999 90.3985 192.957 + endloop + endfacet + facet normal -0.210734 -0.974549 -0.0764536 + outer loop + vertex -511.651 89.8423 201.666 + vertex -520.002 90.9798 210.187 + vertex -520.24 91.7186 201.423 + endloop + endfacet + facet normal -0.224641 -0.971487 -0.0758191 + outer loop + vertex -520.002 90.9798 210.187 + vertex -530.714 93.4434 210.356 + vertex -520.24 91.7186 201.423 + endloop + endfacet + facet normal -0.226269 -0.97095 -0.0778324 + outer loop + vertex -520.24 91.7186 201.423 + vertex -530.714 93.4434 210.356 + vertex -530.851 94.1825 201.534 + endloop + endfacet + facet normal -0.243277 -0.966878 -0.0772274 + outer loop + vertex -530.714 93.4434 210.356 + vertex -542.712 96.4467 210.553 + vertex -530.851 94.1825 201.534 + endloop + endfacet + facet normal -0.243127 -0.964719 -0.10103 + outer loop + vertex -530.714 93.4434 210.356 + vertex -542.701 95.5098 219.472 + vertex -542.712 96.4467 210.553 + endloop + endfacet + facet normal -0.264113 -0.959249 -0.10043 + outer loop + vertex -542.701 95.5098 219.472 + vertex -555.248 98.9446 219.66 + vertex -542.712 96.4467 210.553 + endloop + endfacet + facet normal -0.265813 -0.958509 -0.102973 + outer loop + vertex -542.712 96.4467 210.553 + vertex -555.248 98.9446 219.66 + vertex -555.16 99.885 210.68 + endloop + endfacet + facet normal -0.288273 -0.952045 -0.102514 + outer loop + vertex -555.248 98.9446 219.66 + vertex -567.566 102.667 219.73 + vertex -555.16 99.885 210.68 + endloop + endfacet + facet normal -0.287644 -0.949543 -0.125012 + outer loop + vertex -555.248 98.9446 219.66 + vertex -567.735 101.526 228.783 + vertex -567.566 102.667 219.73 + endloop + endfacet + facet normal -0.307315 -0.943414 -0.124607 + outer loop + vertex -567.735 101.526 228.783 + vertex -579.236 105.288 228.665 + vertex -567.566 102.667 219.73 + endloop + endfacet + facet normal -0.308614 -0.942738 -0.126503 + outer loop + vertex -567.566 102.667 219.73 + vertex -579.236 105.288 228.665 + vertex -578.698 106.357 219.388 + endloop + endfacet + facet normal -0.310029 -0.944966 -0.104503 + outer loop + vertex -567.566 102.667 219.73 + vertex -578.698 106.357 219.388 + vertex -567.331 103.586 210.719 + endloop + endfacet + facet normal -0.326127 -0.936779 -0.126831 + outer loop + vertex -579.236 105.288 228.665 + vertex -589.207 108.915 227.514 + vertex -578.698 106.357 219.388 + endloop + endfacet + facet normal -0.306263 -0.940841 -0.144987 + outer loop + vertex -567.735 101.526 228.783 + vertex -579.216 103.878 237.776 + vertex -579.236 105.288 228.665 + endloop + endfacet + facet normal -0.320735 -0.936124 -0.144225 + outer loop + vertex -579.216 103.878 237.776 + vertex -588.716 107.171 237.528 + vertex -579.236 105.288 228.665 + endloop + endfacet + facet normal -0.303321 -0.942426 -0.140816 + outer loop + vertex -567.839 100.23 237.683 + vertex -579.216 103.878 237.776 + vertex -567.735 101.526 228.783 + endloop + endfacet + facet normal -0.285133 -0.947998 -0.141415 + outer loop + vertex -555.335 97.8204 228.623 + vertex -567.839 100.23 237.683 + vertex -567.735 101.526 228.783 + endloop + endfacet + facet normal -0.282178 -0.94954 -0.136927 + outer loop + vertex -555.449 96.5714 237.52 + vertex -567.839 100.23 237.683 + vertex -555.335 97.8204 228.623 + endloop + endfacet + facet normal -0.261146 -0.955458 -0.137488 + outer loop + vertex -542.726 94.4081 228.388 + vertex -555.449 96.5714 237.52 + vertex -555.335 97.8204 228.623 + endloop + endfacet + facet normal -0.261448 -0.957843 -0.119087 + outer loop + vertex -542.726 94.4081 228.388 + vertex -555.335 97.8204 228.623 + vertex -542.701 95.5098 219.472 + endloop + endfacet + facet normal -0.241141 -0.963083 -0.119677 + outer loop + vertex -530.629 92.5192 219.214 + vertex -542.726 94.4081 228.388 + vertex -542.701 95.5098 219.472 + endloop + endfacet + facet normal -0.239158 -0.963919 -0.11689 + outer loop + vertex -530.536 91.421 228.08 + vertex -542.726 94.4081 228.388 + vertex -530.629 92.5192 219.214 + endloop + endfacet + facet normal -0.222572 -0.967804 -0.117546 + outer loop + vertex -519.777 90.0508 218.989 + vertex -530.536 91.421 228.08 + vertex -530.629 92.5192 219.214 + endloop + endfacet + facet normal -0.222658 -0.970091 -0.0966823 + outer loop + vertex -519.777 90.0508 218.989 + vertex -530.629 92.5192 219.214 + vertex -520.002 90.9798 210.187 + endloop + endfacet + facet normal -0.208757 -0.97311 -0.0973568 + outer loop + vertex -511.306 89.0913 210.415 + vertex -519.777 90.0508 218.989 + vertex -520.002 90.9798 210.187 + endloop + endfacet + facet normal -0.207788 -0.973416 -0.0963655 + outer loop + vertex -510.97 88.1521 219.179 + vertex -519.777 90.0508 218.989 + vertex -511.306 89.0913 210.415 + endloop + endfacet + facet normal -0.192891 -0.976389 -0.0972542 + outer loop + vertex -504.719 87.6677 211.643 + vertex -510.97 88.1521 219.179 + vertex -511.306 89.0913 210.415 + endloop + endfacet + facet normal -0.196777 -0.977376 -0.0775528 + outer loop + vertex -504.719 87.6677 211.643 + vertex -511.306 89.0913 210.415 + vertex -505.672 88.5449 203.008 + endloop + endfacet + facet normal -0.182449 -0.980004 -0.0794023 + outer loop + vertex -504.719 87.6677 211.643 + vertex -505.672 88.5449 203.008 + vertex -501.889 87.6731 205.076 + endloop + endfacet + facet normal -0.195095 -0.977816 -0.0762415 + outer loop + vertex -505.672 88.5449 203.008 + vertex -511.306 89.0913 210.415 + vertex -511.651 89.8423 201.666 + endloop + endfacet + facet normal -0.195555 -0.975631 -0.0995128 + outer loop + vertex -504.811 86.7864 220.465 + vertex -510.97 88.1521 219.179 + vertex -504.719 87.6677 211.643 + endloop + endfacet + facet normal -0.17493 -0.979522 -0.099685 + outer loop + vertex -504.811 86.7864 220.465 + vertex -504.719 87.6677 211.643 + vertex -501.699 86.6677 216.171 + endloop + endfacet + facet normal -0.191862 -0.974539 -0.116029 + outer loop + vertex -504.811 86.7864 220.465 + vertex -510.598 87.0451 227.86 + vertex -510.97 88.1521 219.179 + endloop + endfacet + facet normal -0.206008 -0.971761 -0.115068 + outer loop + vertex -510.598 87.0451 227.86 + vertex -519.546 88.9502 227.791 + vertex -510.97 88.1521 219.179 + endloop + endfacet + facet normal -0.205445 -0.969734 -0.131937 + outer loop + vertex -510.598 87.0451 227.86 + vertex -519.301 87.7083 236.539 + vertex -519.546 88.9502 227.791 + endloop + endfacet + facet normal -0.219428 -0.966777 -0.131126 + outer loop + vertex -519.301 87.7083 236.539 + vertex -530.429 90.1832 236.913 + vertex -519.546 88.9502 227.791 + endloop + endfacet + facet normal -0.220712 -0.966266 -0.132728 + outer loop + vertex -519.546 88.9502 227.791 + vertex -530.429 90.1832 236.913 + vertex -530.536 91.421 228.08 + endloop + endfacet + facet normal -0.236959 -0.96251 -0.132005 + outer loop + vertex -530.429 90.1832 236.913 + vertex -542.74 93.1644 237.275 + vertex -530.536 91.421 228.08 + endloop + endfacet + facet normal -0.236889 -0.960596 -0.145394 + outer loop + vertex -530.429 90.1832 236.913 + vertex -542.764 91.8328 246.111 + vertex -542.74 93.1644 237.275 + endloop + endfacet + facet normal -0.256721 -0.955593 -0.144693 + outer loop + vertex -542.764 91.8328 246.111 + vertex -555.595 95.2402 246.374 + vertex -542.74 93.1644 237.275 + endloop + endfacet + facet normal -0.258754 -0.954569 -0.147798 + outer loop + vertex -542.74 93.1644 237.275 + vertex -555.595 95.2402 246.374 + vertex -555.449 96.5714 237.52 + endloop + endfacet + facet normal -0.278923 -0.948951 -0.147287 + outer loop + vertex -555.595 95.2402 246.374 + vertex -568.042 98.8863 246.454 + vertex -555.449 96.5714 237.52 + endloop + endfacet + facet normal -0.278582 -0.947585 -0.156446 + outer loop + vertex -555.595 95.2402 246.374 + vertex -568.369 97.5229 255.294 + vertex -568.042 98.8863 246.454 + endloop + endfacet + facet normal -0.295097 -0.942598 -0.156287 + outer loop + vertex -568.369 97.5229 255.294 + vertex -579.723 101.137 254.932 + vertex -568.042 98.8863 246.454 + endloop + endfacet + facet normal -0.298423 -0.940692 -0.161375 + outer loop + vertex -568.042 98.8863 246.454 + vertex -579.723 101.137 254.932 + vertex -579.136 102.429 246.32 + endloop + endfacet + facet normal -0.299021 -0.942182 -0.151261 + outer loop + vertex -568.042 98.8863 246.454 + vertex -579.136 102.429 246.32 + vertex -567.839 100.23 237.683 + endloop + endfacet + facet normal -0.310358 -0.936783 -0.161602 + outer loop + vertex -579.723 101.137 254.932 + vertex -587.509 103.956 253.546 + vertex -579.136 102.429 246.32 + endloop + endfacet + facet normal -0.294744 -0.941943 -0.160838 + outer loop + vertex -568.369 97.5229 255.294 + vertex -580.396 99.7942 264.032 + vertex -579.723 101.137 254.932 + endloop + endfacet + facet normal -0.306665 -0.938077 -0.161149 + outer loop + vertex -580.396 99.7942 264.032 + vertex -590.655 103.334 262.952 + vertex -579.723 101.137 254.932 + endloop + endfacet + facet normal -0.29063 -0.944268 -0.154572 + outer loop + vertex -568.624 96.1422 264.209 + vertex -580.396 99.7942 264.032 + vertex -568.369 97.5229 255.294 + endloop + endfacet + facet normal -0.275761 -0.948675 -0.154828 + outer loop + vertex -555.749 93.8668 255.219 + vertex -568.624 96.1422 264.209 + vertex -568.369 97.5229 255.294 + endloop + endfacet + facet normal -0.272493 -0.95044 -0.149702 + outer loop + vertex -555.933 92.5235 264.083 + vertex -568.624 96.1422 264.209 + vertex -555.749 93.8668 255.219 + endloop + endfacet + facet normal -0.254898 -0.955252 -0.150066 + outer loop + vertex -542.818 90.4658 254.903 + vertex -555.933 92.5235 264.083 + vertex -555.749 93.8668 255.219 + endloop + endfacet + facet normal -0.254898 -0.955249 -0.150089 + outer loop + vertex -542.818 90.4658 254.903 + vertex -555.749 93.8668 255.219 + vertex -542.764 91.8328 246.111 + endloop + endfacet + facet normal -0.235806 -0.960042 -0.150716 + outer loop + vertex -530.288 88.8372 245.673 + vertex -542.818 90.4658 254.903 + vertex -542.764 91.8328 246.111 + endloop + endfacet + facet normal -0.234912 -0.960462 -0.149427 + outer loop + vertex -530.264 87.4777 254.375 + vertex -542.818 90.4658 254.903 + vertex -530.288 88.8372 245.673 + endloop + endfacet + facet normal -0.218571 -0.964214 -0.150057 + outer loop + vertex -519.083 86.3718 245.195 + vertex -530.264 87.4777 254.375 + vertex -530.288 88.8372 245.673 + endloop + endfacet + facet normal -0.218514 -0.96522 -0.143532 + outer loop + vertex -519.083 86.3718 245.195 + vertex -530.288 88.8372 245.673 + vertex -519.301 87.7083 236.539 + endloop + endfacet + facet normal -0.204876 -0.96809 -0.144318 + outer loop + vertex -510.259 85.7993 236.508 + vertex -519.083 86.3718 245.195 + vertex -519.301 87.7083 236.539 + endloop + endfacet + facet normal -0.204818 -0.968111 -0.144257 + outer loop + vertex -509.934 84.4545 245.072 + vertex -519.083 86.3718 245.195 + vertex -510.259 85.7993 236.508 + endloop + endfacet + facet normal -0.191301 -0.970735 -0.145182 + outer loop + vertex -503.934 84.3901 237.596 + vertex -509.934 84.4545 245.072 + vertex -510.259 85.7993 236.508 + endloop + endfacet + facet normal -0.193372 -0.971851 -0.134582 + outer loop + vertex -503.934 84.3901 237.596 + vertex -510.259 85.7993 236.508 + vertex -503.873 85.6102 228.698 + endloop + endfacet + facet normal -0.177075 -0.97491 -0.134889 + outer loop + vertex -503.934 84.3901 237.596 + vertex -503.873 85.6102 228.698 + vertex -500.349 84.4475 232.475 + endloop + endfacet + facet normal -0.191016 -0.972584 -0.132637 + outer loop + vertex -503.873 85.6102 228.698 + vertex -510.259 85.7993 236.508 + vertex -510.598 87.0451 227.86 + endloop + endfacet + facet normal -0.191699 -0.970608 -0.145502 + outer loop + vertex -502.977 82.9633 245.852 + vertex -509.934 84.4545 245.072 + vertex -503.934 84.3901 237.596 + endloop + endfacet + facet normal -0.177526 -0.972991 -0.147557 + outer loop + vertex -502.977 82.9633 245.852 + vertex -503.934 84.3901 237.596 + vertex -499.886 83.3022 239.899 + endloop + endfacet + facet normal -0.190782 -0.969779 -0.152086 + outer loop + vertex -502.977 82.9633 245.852 + vertex -509.622 83.055 253.604 + vertex -509.934 84.4545 245.072 + endloop + endfacet + facet normal -0.204892 -0.967048 -0.151121 + outer loop + vertex -509.622 83.055 253.604 + vertex -518.901 84.9923 253.788 + vertex -509.934 84.4545 245.072 + endloop + endfacet + facet normal -0.204941 -0.967672 -0.147005 + outer loop + vertex -509.622 83.055 253.604 + vertex -518.72 83.6278 262.517 + vertex -518.901 84.9923 253.788 + endloop + endfacet + facet normal -0.218414 -0.96483 -0.146281 + outer loop + vertex -518.72 83.6278 262.517 + vertex -530.257 86.1471 263.127 + vertex -518.901 84.9923 253.788 + endloop + endfacet + facet normal -0.218584 -0.964759 -0.146497 + outer loop + vertex -518.901 84.9923 253.788 + vertex -530.257 86.1471 263.127 + vertex -530.264 87.4777 254.375 + endloop + endfacet + facet normal -0.234274 -0.961155 -0.145936 + outer loop + vertex -530.257 86.1471 263.127 + vertex -542.947 89.1504 263.719 + vertex -530.264 87.4777 254.375 + endloop + endfacet + facet normal -0.234083 -0.96349 -0.129974 + outer loop + vertex -530.257 86.1471 263.127 + vertex -543.037 87.9649 272.667 + vertex -542.947 89.1504 263.719 + endloop + endfacet + facet normal -0.249774 -0.95959 -0.129614 + outer loop + vertex -543.037 87.9649 272.667 + vertex -556.174 91.3369 273.019 + vertex -542.947 89.1504 263.719 + endloop + endfacet + facet normal -0.252659 -0.958226 -0.134038 + outer loop + vertex -542.947 89.1504 263.719 + vertex -556.174 91.3369 273.019 + vertex -555.933 92.5235 264.083 + endloop + endfacet + facet normal -0.267035 -0.954338 -0.133908 + outer loop + vertex -556.174 91.3369 273.019 + vertex -568.898 94.8822 273.127 + vertex -555.933 92.5235 264.083 + endloop + endfacet + facet normal -0.267518 -0.956648 -0.115151 + outer loop + vertex -556.174 91.3369 273.019 + vertex -569.335 93.9258 282.087 + vertex -568.898 94.8822 273.127 + endloop + endfacet + facet normal -0.27376 -0.954866 -0.115265 + outer loop + vertex -569.335 93.9258 282.087 + vertex -581.096 97.3307 281.814 + vertex -568.898 94.8822 273.127 + endloop + endfacet + facet normal -0.283743 -0.949956 -0.130668 + outer loop + vertex -568.898 94.8822 273.127 + vertex -581.096 97.3307 281.814 + vertex -580.616 98.3916 273.059 + endloop + endfacet + facet normal -0.283203 -0.948386 -0.14269 + outer loop + vertex -568.898 94.8822 273.127 + vertex -580.616 98.3916 273.059 + vertex -568.624 96.1422 264.209 + endloop + endfacet + facet normal -0.284867 -0.949616 -0.130688 + outer loop + vertex -581.096 97.3307 281.814 + vertex -590.815 100.282 281.55 + vertex -580.616 98.3916 273.059 + endloop + endfacet + facet normal -0.285573 -0.950913 -0.119215 + outer loop + vertex -581.096 97.3307 281.814 + vertex -591.615 99.5638 289.198 + vertex -590.815 100.282 281.55 + endloop + endfacet + facet normal -0.269582 -0.95836 -0.0941849 + outer loop + vertex -582.756 96.8856 291.095 + vertex -591.615 99.5638 289.198 + vertex -581.096 97.3307 281.814 + endloop + endfacet + facet normal -0.271654 -0.958642 -0.0849126 + outer loop + vertex -591.615 99.5638 289.198 + vertex -582.756 96.8856 291.095 + vertex -594.215 99.7085 295.883 + endloop + endfacet + facet normal -0.268722 -0.95957 -0.0837522 + outer loop + vertex -594.215 99.7085 295.883 + vertex -599.349 101.234 294.883 + vertex -591.615 99.5638 289.198 + endloop + endfacet + facet normal -0.282093 -0.953772 -0.103643 + outer loop + vertex -591.615 99.5638 289.198 + vertex -599.349 101.234 294.883 + vertex -598.325 101.569 289.005 + endloop + endfacet + facet normal -0.277241 -0.955276 -0.102884 + outer loop + vertex -599.349 101.234 294.883 + vertex -603.212 102.362 294.816 + vertex -598.325 101.569 289.005 + endloop + endfacet + facet normal -0.278208 -0.957201 -0.0797942 + outer loop + vertex -599.349 101.234 294.883 + vertex -604.25 102.281 299.402 + vertex -603.212 102.362 294.816 + endloop + endfacet + facet normal -0.272413 -0.958972 -0.0785135 + outer loop + vertex -604.25 102.281 299.402 + vertex -606.205 102.848 299.258 + vertex -603.212 102.362 294.816 + endloop + endfacet + facet normal -0.289763 -0.952774 -0.0908822 + outer loop + vertex -603.212 102.362 294.816 + vertex -606.205 102.848 299.258 + vertex -605.012 102.934 294.562 + endloop + endfacet + facet normal -0.286661 -0.951655 -0.110352 + outer loop + vertex -603.212 102.362 294.816 + vertex -605.012 102.934 294.562 + vertex -602.368 102.654 290.107 + endloop + endfacet + facet normal -0.275547 -0.95731 -0.0873549 + outer loop + vertex -606.205 102.848 299.258 + vertex -606.754 103.045 298.836 + vertex -605.012 102.934 294.562 + endloop + endfacet + facet normal -0.299415 -0.94915 -0.0972907 + outer loop + vertex -605.012 102.934 294.562 + vertex -606.754 103.045 298.836 + vertex -605.372 103.109 293.963 + endloop + endfacet + facet normal 0.703692 0.679261 0.208381 + outer loop + vertex -606.754 103.045 298.836 + vertex -606.52 103.039 298.067 + vertex -605.372 103.109 293.963 + endloop + endfacet + facet normal -0.487547 -0.861599 -0.141229 + outer loop + vertex -606.754 103.045 298.836 + vertex -607.909 103.142 302.232 + vertex -606.52 103.039 298.067 + endloop + endfacet + facet normal -0.293274 -0.953273 -0.0725358 + outer loop + vertex -607.94 103.12 302.652 + vertex -607.909 103.142 302.232 + vertex -606.754 103.045 298.836 + endloop + endfacet + facet normal -0.358906 -0.930255 -0.0762366 + outer loop + vertex -607.94 103.12 302.652 + vertex -608.711 103.249 304.703 + vertex -607.909 103.142 302.232 + endloop + endfacet + facet normal -0.563811 -0.81256 -0.147861 + outer loop + vertex -607.909 103.142 302.232 + vertex -608.711 103.249 304.703 + vertex -608.898 103.311 305.076 + endloop + endfacet + facet normal -0.254998 -0.966311 -0.0349139 + outer loop + vertex -608.478 103.183 304.836 + vertex -608.711 103.249 304.703 + vertex -607.94 103.12 302.652 + endloop + endfacet + facet normal -0.261393 -0.964541 -0.0365387 + outer loop + vertex -607.152 102.898 302.854 + vertex -608.478 103.183 304.836 + vertex -607.94 103.12 302.652 + endloop + endfacet + facet normal -0.256941 -0.964901 -0.054286 + outer loop + vertex -607.152 102.898 302.854 + vertex -607.94 103.12 302.652 + vertex -606.205 102.848 299.258 + endloop + endfacet + facet normal -0.239531 -0.970661 -0.0210382 + outer loop + vertex -607.393 102.908 305.167 + vertex -608.478 103.183 304.836 + vertex -607.152 102.898 302.854 + endloop + endfacet + facet normal -0.258711 -0.96568 -0.0230561 + outer loop + vertex -605.108 102.349 302.91 + vertex -607.393 102.908 305.167 + vertex -607.152 102.898 302.854 + endloop + endfacet + facet normal -0.25798 -0.965131 -0.0443712 + outer loop + vertex -605.108 102.349 302.91 + vertex -607.152 102.898 302.854 + vertex -604.25 102.281 299.402 + endloop + endfacet + facet normal -0.269094 -0.961959 -0.04715 + outer loop + vertex -600.916 101.335 299.688 + vertex -605.108 102.349 302.91 + vertex -604.25 102.281 299.402 + endloop + endfacet + facet normal -0.256985 -0.965945 -0.0301403 + outer loop + vertex -601.725 101.446 303.015 + vertex -605.108 102.349 302.91 + vertex -600.916 101.335 299.688 + endloop + endfacet + facet normal -0.265319 -0.963621 -0.0322465 + outer loop + vertex -597.324 100.323 300.352 + vertex -601.725 101.446 303.015 + vertex -600.916 101.335 299.688 + endloop + endfacet + facet normal -0.262121 -0.963752 -0.0497534 + outer loop + vertex -597.324 100.323 300.352 + vertex -600.916 101.335 299.688 + vertex -594.215 99.7085 295.883 + endloop + endfacet + facet normal -0.261333 -0.963995 -0.0491718 + outer loop + vertex -597.324 100.323 300.352 + vertex -594.215 99.7085 295.883 + vertex -590.509 98.5582 298.739 + endloop + endfacet + facet normal -0.254117 -0.967052 -0.0153428 + outer loop + vertex -590.509 98.5582 298.739 + vertex -596.489 100.064 302.897 + vertex -597.324 100.323 300.352 + endloop + endfacet + facet normal -0.256272 -0.966424 -0.0186679 + outer loop + vertex -589.01 98.0878 302.523 + vertex -596.489 100.064 302.897 + vertex -590.509 98.5582 298.739 + endloop + endfacet + facet normal -0.257878 -0.96601 -0.0179802 + outer loop + vertex -580.569 95.9255 297.628 + vertex -589.01 98.0878 302.523 + vertex -590.509 98.5582 298.739 + endloop + endfacet + facet normal -0.261316 -0.963733 -0.0541486 + outer loop + vertex -580.569 95.9255 297.628 + vertex -590.509 98.5582 298.739 + vertex -582.756 96.8856 291.095 + endloop + endfacet + facet normal -0.26464 -0.962895 -0.0529125 + outer loop + vertex -569.281 93.2132 290.526 + vertex -580.569 95.9255 297.628 + vertex -582.756 96.8856 291.095 + endloop + endfacet + facet normal -0.265219 -0.960911 -0.0794335 + outer loop + vertex -569.281 93.2132 290.526 + vertex -582.756 96.8856 291.095 + vertex -569.335 93.9258 282.087 + endloop + endfacet + facet normal -0.261718 -0.961862 -0.0795362 + outer loop + vertex -556.251 90.3759 281.963 + vertex -569.281 93.2132 290.526 + vertex -569.335 93.9258 282.087 + endloop + endfacet + facet normal -0.256061 -0.96411 -0.0701824 + outer loop + vertex -555.875 89.6473 290.602 + vertex -569.281 93.2132 290.526 + vertex -556.251 90.3759 281.963 + endloop + endfacet + facet normal -0.247474 -0.966309 -0.0707412 + outer loop + vertex -542.711 86.9241 281.749 + vertex -555.875 89.6473 290.602 + vertex -556.251 90.3759 281.963 + endloop + endfacet + facet normal -0.247274 -0.963606 -0.101577 + outer loop + vertex -542.711 86.9241 281.749 + vertex -556.251 90.3759 281.963 + vertex -543.037 87.9649 272.667 + endloop + endfacet + facet normal -0.233118 -0.967034 -0.102477 + outer loop + vertex -530.072 84.8951 272.144 + vertex -542.711 86.9241 281.749 + vertex -543.037 87.9649 272.667 + endloop + endfacet + facet normal -0.234841 -0.966358 -0.104887 + outer loop + vertex -529.189 83.6616 281.532 + vertex -542.711 86.9241 281.749 + vertex -530.072 84.8951 272.144 + endloop + endfacet + facet normal -0.219964 -0.969653 -0.10672 + outer loop + vertex -518.106 82.2363 271.638 + vertex -529.189 83.6616 281.532 + vertex -530.072 84.8951 272.144 + endloop + endfacet + facet normal -0.220328 -0.96637 -0.132603 + outer loop + vertex -518.106 82.2363 271.638 + vertex -530.072 84.8951 272.144 + vertex -518.72 83.6278 262.517 + endloop + endfacet + facet normal -0.206874 -0.969157 -0.133933 + outer loop + vertex -509.142 81.6099 262.325 + vertex -518.106 82.2363 271.638 + vertex -518.72 83.6278 262.517 + endloop + endfacet + facet normal -0.211245 -0.967607 -0.138245 + outer loop + vertex -508.127 80.0803 271.479 + vertex -518.106 82.2363 271.638 + vertex -509.142 81.6099 262.325 + endloop + endfacet + facet normal -0.197164 -0.970286 -0.140255 + outer loop + vertex -501.739 79.9958 263.085 + vertex -508.127 80.0803 271.479 + vertex -509.142 81.6099 262.325 + endloop + endfacet + facet normal -0.195687 -0.968871 -0.151646 + outer loop + vertex -501.739 79.9958 263.085 + vertex -509.142 81.6099 262.325 + vertex -502.931 81.5621 254.616 + endloop + endfacet + facet normal -0.181556 -0.971236 -0.154073 + outer loop + vertex -501.739 79.9958 263.085 + vertex -502.931 81.5621 254.616 + vertex -498.545 80.3551 257.056 + endloop + endfacet + facet normal -0.193652 -0.969535 -0.150003 + outer loop + vertex -502.931 81.5621 254.616 + vertex -509.142 81.6099 262.325 + vertex -509.622 83.055 253.604 + endloop + endfacet + facet normal -0.204142 -0.968055 -0.145587 + outer loop + vertex -501.131 78.5153 272.075 + vertex -508.127 80.0803 271.479 + vertex -501.739 79.9958 263.085 + endloop + endfacet + facet normal -0.1909 -0.970556 -0.146895 + outer loop + vertex -501.131 78.5153 272.075 + vertex -501.739 79.9958 263.085 + vertex -497.682 78.6011 267.026 + endloop + endfacet + facet normal -0.194292 -0.969531 -0.149195 + outer loop + vertex -497.682 78.6011 267.026 + vertex -497.262 77.5507 273.305 + vertex -501.131 78.5153 272.075 + endloop + endfacet + facet normal -0.198175 -0.970446 -0.137703 + outer loop + vertex -498.748 76.9248 279.855 + vertex -501.131 78.5153 272.075 + vertex -497.262 77.5507 273.305 + endloop + endfacet + facet normal -0.194991 -0.971183 -0.137051 + outer loop + vertex -497.262 77.5507 273.305 + vertex -495.59 76.5948 277.7 + vertex -498.748 76.9248 279.855 + endloop + endfacet + facet normal -0.19192 -0.972444 -0.132357 + outer loop + vertex -495.59 76.5948 277.7 + vertex -495.076 75.6904 283.6 + vertex -498.748 76.9248 279.855 + endloop + endfacet + facet normal -0.204517 -0.971516 -0.119702 + outer loop + vertex -497.013 75.6095 287.566 + vertex -498.748 76.9248 279.855 + vertex -495.076 75.6904 283.6 + endloop + endfacet + facet normal -0.194327 -0.974199 -0.114779 + outer loop + vertex -495.076 75.6904 283.6 + vertex -493.801 74.6804 290.015 + vertex -497.013 75.6095 287.566 + endloop + endfacet + facet normal -0.211977 -0.973012 -0.0911762 + outer loop + vertex -495.186 74.582 294.285 + vertex -497.013 75.6095 287.566 + vertex -493.801 74.6804 290.015 + endloop + endfacet + facet normal -0.207866 -0.974021 -0.0898657 + outer loop + vertex -493.801 74.6804 290.015 + vertex -491.986 73.7641 295.748 + vertex -495.186 74.582 294.285 + endloop + endfacet + facet normal -0.217371 -0.973657 -0.0688642 + outer loop + vertex -491.986 73.7641 295.748 + vertex -492.668 73.7248 298.456 + vertex -495.186 74.582 294.285 + endloop + endfacet + facet normal -0.220308 -0.973128 -0.0669822 + outer loop + vertex -492.668 73.7248 298.456 + vertex -495.003 74.2372 298.69 + vertex -495.186 74.582 294.285 + endloop + endfacet + facet normal -0.218176 -0.973599 -0.067108 + outer loop + vertex -495.003 74.2372 298.69 + vertex -498.43 75.0659 297.811 + vertex -495.186 74.582 294.285 + endloop + endfacet + facet normal -0.217623 -0.97376 -0.0665768 + outer loop + vertex -495.186 74.582 294.285 + vertex -498.43 75.0659 297.811 + vertex -499.686 75.6964 292.694 + endloop + endfacet + facet normal -0.221816 -0.97289 -0.06544 + outer loop + vertex -498.43 75.0659 297.811 + vertex -503.668 76.2775 297.552 + vertex -499.686 75.6964 292.694 + endloop + endfacet + facet normal -0.219994 -0.973407 -0.0638846 + outer loop + vertex -499.686 75.6964 292.694 + vertex -503.668 76.2775 297.552 + vertex -505.209 76.9655 292.375 + endloop + endfacet + facet normal -0.218079 -0.971739 -0.0903611 + outer loop + vertex -499.686 75.6964 292.694 + vertex -505.209 76.9655 292.375 + vertex -501.524 76.6638 286.728 + endloop + endfacet + facet normal -0.210133 -0.973235 -0.093051 + outer loop + vertex -497.013 75.6095 287.566 + vertex -499.686 75.6964 292.694 + vertex -501.524 76.6638 286.728 + endloop + endfacet + facet normal -0.2137 -0.972978 -0.0874381 + outer loop + vertex -501.524 76.6638 286.728 + vertex -505.209 76.9655 292.375 + vertex -505.921 77.5318 287.815 + endloop + endfacet + facet normal -0.220049 -0.968484 -0.116695 + outer loop + vertex -505.921 77.5318 287.815 + vertex -505.933 78.3292 281.219 + vertex -501.524 76.6638 286.728 + endloop + endfacet + facet normal -0.212772 -0.969357 -0.122783 + outer loop + vertex -505.933 78.3292 281.219 + vertex -498.748 76.9248 279.855 + vertex -501.524 76.6638 286.728 + endloop + endfacet + facet normal -0.245054 -0.962553 -0.115934 + outer loop + vertex -505.921 77.5318 287.815 + vertex -513.499 79.0608 291.137 + vertex -505.933 78.3292 281.219 + endloop + endfacet + facet normal -0.221468 -0.970294 -0.0973713 + outer loop + vertex -505.933 78.3292 281.219 + vertex -513.499 79.0608 291.137 + vertex -516.553 80.745 281.301 + endloop + endfacet + facet normal -0.221005 -0.96734 -0.124141 + outer loop + vertex -505.933 78.3292 281.219 + vertex -516.553 80.745 281.301 + vertex -508.127 80.0803 271.479 + endloop + endfacet + facet normal -0.232615 -0.968061 -0.0935271 + outer loop + vertex -513.499 79.0608 291.137 + vertex -527.375 82.3786 291.306 + vertex -516.553 80.745 281.301 + endloop + endfacet + facet normal -0.225558 -0.97047 -0.085501 + outer loop + vertex -516.553 80.745 281.301 + vertex -527.375 82.3786 291.306 + vertex -529.189 83.6616 281.532 + endloop + endfacet + facet normal -0.240722 -0.967103 -0.0822443 + outer loop + vertex -527.375 82.3786 291.306 + vertex -541.502 85.9554 290.596 + vertex -529.189 83.6616 281.532 + endloop + endfacet + facet normal -0.232366 -0.968992 -0.0840266 + outer loop + vertex -505.921 77.5318 287.815 + vertex -505.209 76.9655 292.375 + vertex -513.499 79.0608 291.137 + endloop + endfacet + facet normal -0.234925 -0.969634 -0.0679784 + outer loop + vertex -505.209 76.9655 292.375 + vertex -510.182 77.8031 297.615 + vertex -513.499 79.0608 291.137 + endloop + endfacet + facet normal -0.234506 -0.969719 -0.0682091 + outer loop + vertex -516.934 79.3731 298.508 + vertex -513.499 79.0608 291.137 + vertex -510.182 77.8031 297.615 + endloop + endfacet + facet normal -0.230026 -0.972752 -0.0290006 + outer loop + vertex -510.182 77.8031 297.615 + vertex -515.594 78.954 301.938 + vertex -516.934 79.3731 298.508 + endloop + endfacet + facet normal -0.238772 -0.970745 -0.0253392 + outer loop + vertex -515.594 78.954 301.938 + vertex -523.611 80.9293 301.806 + vertex -516.934 79.3731 298.508 + endloop + endfacet + facet normal -0.239009 -0.970673 -0.0258531 + outer loop + vertex -516.934 79.3731 298.508 + vertex -523.611 80.9293 301.806 + vertex -523.664 81.0609 297.353 + endloop + endfacet + facet normal -0.242484 -0.969813 -0.0257863 + outer loop + vertex -523.611 80.9293 301.806 + vertex -532.265 83.1207 300.768 + vertex -523.664 81.0609 297.353 + endloop + endfacet + facet normal -0.237387 -0.971341 -0.0120285 + outer loop + vertex -523.664 81.0609 297.353 + vertex -532.265 83.1207 300.768 + vertex -530.261 82.6738 297.312 + endloop + endfacet + facet normal -0.252771 -0.967288 -0.0214742 + outer loop + vertex -530.261 82.6738 297.312 + vertex -532.265 83.1207 300.768 + vertex -538.624 84.8552 297.491 + endloop + endfacet + facet normal -0.257266 -0.966263 -0.012211 + outer loop + vertex -532.265 83.1207 300.768 + vertex -545.628 86.6525 302.834 + vertex -538.624 84.8552 297.491 + endloop + endfacet + facet normal -0.253514 -0.967307 -0.00694234 + outer loop + vertex -554.901 89.113 298.618 + vertex -538.624 84.8552 297.491 + vertex -545.628 86.6525 302.834 + endloop + endfacet + facet normal -0.256025 -0.96667 -0.00104703 + outer loop + vertex -545.628 86.6525 302.834 + vertex -560.16 90.5002 303.794 + vertex -554.901 89.113 298.618 + endloop + endfacet + facet normal -0.253992 -0.967206 0.00116313 + outer loop + vertex -560.16 90.5002 303.794 + vertex -571.617 93.5083 303.337 + vertex -554.901 89.113 298.618 + endloop + endfacet + facet normal -0.254781 -0.966997 -0.00182603 + outer loop + vertex -569.157 92.8708 297.762 + vertex -554.901 89.113 298.618 + vertex -571.617 93.5083 303.337 + endloop + endfacet + facet normal -0.25265 -0.967557 -0.00082169 + outer loop + vertex -569.157 92.8708 297.762 + vertex -571.617 93.5083 303.337 + vertex -580.349 95.7892 302.475 + endloop + endfacet + facet normal -0.25837 -0.965923 -0.0154176 + outer loop + vertex -580.569 95.9255 297.628 + vertex -569.157 92.8708 297.762 + vertex -580.349 95.7892 302.475 + endloop + endfacet + facet normal -0.254157 -0.967033 0.0158426 + outer loop + vertex -571.617 93.5083 303.337 + vertex -581.006 96.0003 304.819 + vertex -580.349 95.7892 302.475 + endloop + endfacet + facet normal -0.256543 -0.966415 0.0151176 + outer loop + vertex -581.006 96.0003 304.819 + vertex -587.35 97.6887 305.105 + vertex -580.349 95.7892 302.475 + endloop + endfacet + facet normal -0.256391 -0.966448 0.0155454 + outer loop + vertex -580.349 95.7892 302.475 + vertex -587.35 97.6887 305.105 + vertex -589.01 98.0878 302.523 + endloop + endfacet + facet normal -0.254755 -0.966898 0.0144239 + outer loop + vertex -587.35 97.6887 305.105 + vertex -595.086 99.729 305.231 + vertex -589.01 98.0878 302.523 + endloop + endfacet + facet normal -0.253987 -0.965087 0.0640085 + outer loop + vertex -581.006 96.0003 304.819 + vertex -581.994 96.3356 305.955 + vertex -587.35 97.6887 305.105 + endloop + endfacet + facet normal -0.2452 -0.966784 0.0721508 + outer loop + vertex -571.617 93.5083 303.337 + vertex -581.994 96.3356 305.955 + vertex -581.006 96.0003 304.819 + endloop + endfacet + facet normal -0.255328 -0.96588 0.0434039 + outer loop + vertex -560.16 90.5002 303.794 + vertex -569.853 93.1518 305.779 + vertex -571.617 93.5083 303.337 + endloop + endfacet + facet normal -0.252727 -0.966362 0.0476771 + outer loop + vertex -545.628 86.6525 302.834 + vertex -556.496 89.6297 305.57 + vertex -560.16 90.5002 303.794 + endloop + endfacet + facet normal -0.252839 -0.967336 0.0182524 + outer loop + vertex -532.265 83.1207 300.768 + vertex -532.684 83.2926 304.072 + vertex -545.628 86.6525 302.834 + endloop + endfacet + facet normal -0.255128 -0.965795 0.0463708 + outer loop + vertex -532.684 83.2926 304.072 + vertex -542.94 86.071 305.516 + vertex -545.628 86.6525 302.834 + endloop + endfacet + facet normal -0.24757 -0.968684 0.0189907 + outer loop + vertex -523.611 80.9293 301.806 + vertex -532.684 83.2926 304.072 + vertex -532.265 83.1207 300.768 + endloop + endfacet + facet normal -0.246974 -0.968784 0.0214786 + outer loop + vertex -521.808 80.5282 304.444 + vertex -532.684 83.2926 304.072 + vertex -523.611 80.9293 301.806 + endloop + endfacet + facet normal -0.247985 -0.966235 0.0699579 + outer loop + vertex -532.684 83.2926 304.072 + vertex -521.808 80.5282 304.444 + vertex -529.511 82.5958 305.695 + endloop + endfacet + facet normal -0.245171 -0.965632 0.086292 + outer loop + vertex -515.667 79.0842 305.734 + vertex -529.511 82.5958 305.695 + vertex -521.808 80.5282 304.444 + endloop + endfacet + facet normal -0.239507 -0.969325 0.055186 + outer loop + vertex -513.741 78.5151 304.099 + vertex -515.667 79.0842 305.734 + vertex -521.808 80.5282 304.444 + endloop + endfacet + facet normal -0.241674 -0.970303 0.0102564 + outer loop + vertex -513.741 78.5151 304.099 + vertex -521.808 80.5282 304.444 + vertex -515.594 78.954 301.938 + endloop + endfacet + facet normal -0.232269 -0.97265 0.00170974 + outer loop + vertex -508.578 77.278 301.645 + vertex -513.741 78.5151 304.099 + vertex -515.594 78.954 301.938 + endloop + endfacet + facet normal -0.233228 -0.972422 -0.000422889 + outer loop + vertex -507.242 76.9565 304.128 + vertex -513.741 78.5151 304.099 + vertex -508.578 77.278 301.645 + endloop + endfacet + facet normal -0.22751 -0.973769 -0.00367363 + outer loop + vertex -502.409 75.8375 301.402 + vertex -507.242 76.9565 304.128 + vertex -508.578 77.278 301.645 + endloop + endfacet + facet normal -0.232971 -0.972384 -0.0139242 + outer loop + vertex -500.968 75.4607 303.61 + vertex -507.242 76.9565 304.128 + vertex -502.409 75.8375 301.402 + endloop + endfacet + facet normal -0.226273 -0.973887 -0.0185513 + outer loop + vertex -497.405 74.676 301.351 + vertex -500.968 75.4607 303.61 + vertex -502.409 75.8375 301.402 + endloop + endfacet + facet normal -0.227628 -0.973526 -0.0208135 + outer loop + vertex -496.601 74.4389 303.645 + vertex -500.968 75.4607 303.61 + vertex -497.405 74.676 301.351 + endloop + endfacet + facet normal -0.224175 -0.974298 -0.0221039 + outer loop + vertex -493.828 73.8543 301.292 + vertex -496.601 74.4389 303.645 + vertex -497.405 74.676 301.351 + endloop + endfacet + facet normal -0.227916 -0.973586 0.0136093 + outer loop + vertex -500.968 75.4607 303.61 + vertex -496.601 74.4389 303.645 + vertex -502.779 75.91 305.41 + endloop + endfacet + facet normal -0.233638 -0.972295 -0.00749363 + outer loop + vertex -494.527 73.9291 305.125 + vertex -502.779 75.91 305.41 + vertex -496.601 74.4389 303.645 + endloop + endfacet + facet normal -0.231095 -0.972877 0.010233 + outer loop + vertex -500.968 75.4607 303.61 + vertex -502.779 75.91 305.41 + vertex -507.242 76.9565 304.128 + endloop + endfacet + facet normal -0.233032 -0.970413 0.0631953 + outer loop + vertex -513.741 78.5151 304.099 + vertex -507.242 76.9565 304.128 + vertex -515.667 79.0842 305.734 + endloop + endfacet + facet normal -0.238129 -0.970543 0.0366231 + outer loop + vertex -502.779 75.91 305.41 + vertex -515.667 79.0842 305.734 + vertex -507.242 76.9565 304.128 + endloop + endfacet + facet normal -0.239461 -0.970774 0.0160414 + outer loop + vertex -515.594 78.954 301.938 + vertex -521.808 80.5282 304.444 + vertex -523.611 80.9293 301.806 + endloop + endfacet + facet normal -0.233537 -0.971765 -0.0336587 + outer loop + vertex -508.578 77.278 301.645 + vertex -515.594 78.954 301.938 + vertex -510.182 77.8031 297.615 + endloop + endfacet + facet normal -0.22821 -0.972949 -0.0359337 + outer loop + vertex -503.668 76.2775 297.552 + vertex -508.578 77.278 301.645 + vertex -510.182 77.8031 297.615 + endloop + endfacet + facet normal -0.228582 -0.972844 -0.0364056 + outer loop + vertex -502.409 75.8375 301.402 + vertex -508.578 77.278 301.645 + vertex -503.668 76.2775 297.552 + endloop + endfacet + facet normal -0.231895 -0.970433 -0.066962 + outer loop + vertex -516.934 79.3731 298.508 + vertex -523.664 81.0609 297.353 + vertex -513.499 79.0608 291.137 + endloop + endfacet + facet normal -0.232799 -0.970106 -0.0685451 + outer loop + vertex -527.375 82.3786 291.306 + vertex -513.499 79.0608 291.137 + vertex -523.664 81.0609 297.353 + endloop + endfacet + facet normal -0.236572 -0.969365 -0.0660683 + outer loop + vertex -530.261 82.6738 297.312 + vertex -527.375 82.3786 291.306 + vertex -523.664 81.0609 297.353 + endloop + endfacet + facet normal -0.253185 -0.964561 -0.0742887 + outer loop + vertex -530.261 82.6738 297.312 + vertex -538.624 84.8552 297.491 + vertex -527.375 82.3786 291.306 + endloop + endfacet + facet normal -0.242571 -0.968666 -0.0533375 + outer loop + vertex -527.375 82.3786 291.306 + vertex -538.624 84.8552 297.491 + vertex -541.502 85.9554 290.596 + endloop + endfacet + facet normal -0.255853 -0.965558 -0.0472984 + outer loop + vertex -538.624 84.8552 297.491 + vertex -554.901 89.113 298.618 + vertex -541.502 85.9554 290.596 + endloop + endfacet + facet normal -0.248643 -0.967988 -0.0342987 + outer loop + vertex -541.502 85.9554 290.596 + vertex -554.901 89.113 298.618 + vertex -555.875 89.6473 290.602 + endloop + endfacet + facet normal -0.252844 -0.966919 -0.0337167 + outer loop + vertex -554.901 89.113 298.618 + vertex -569.157 92.8708 297.762 + vertex -555.875 89.6473 290.602 + endloop + endfacet + facet normal -0.228159 -0.971697 -0.0612272 + outer loop + vertex -503.668 76.2775 297.552 + vertex -510.182 77.8031 297.615 + vertex -505.209 76.9655 292.375 + endloop + endfacet + facet normal -0.223409 -0.973975 -0.038227 + outer loop + vertex -498.43 75.0659 297.811 + vertex -502.409 75.8375 301.402 + vertex -503.668 76.2775 297.552 + endloop + endfacet + facet normal -0.226337 -0.973158 -0.041646 + outer loop + vertex -497.405 74.676 301.351 + vertex -502.409 75.8375 301.402 + vertex -498.43 75.0659 297.811 + endloop + endfacet + facet normal -0.224553 -0.973547 -0.0422052 + outer loop + vertex -495.003 74.2372 298.69 + vertex -497.405 74.676 301.351 + vertex -498.43 75.0659 297.811 + endloop + endfacet + facet normal -0.224346 -0.973604 -0.0420087 + outer loop + vertex -493.828 73.8543 301.292 + vertex -497.405 74.676 301.351 + vertex -495.003 74.2372 298.69 + endloop + endfacet + facet normal -0.211095 -0.975146 -0.0673052 + outer loop + vertex -491.986 73.7641 295.748 + vertex -490.841 73.2468 299.65 + vertex -492.668 73.7248 298.456 + endloop + endfacet + facet normal -0.207283 -0.974126 -0.0900669 + outer loop + vertex -491.986 73.7641 295.748 + vertex -493.801 74.6804 290.015 + vertex -491.142 73.8311 293.081 + endloop + endfacet + facet normal -0.199105 -0.976061 -0.0875279 + outer loop + vertex -491.142 73.8311 293.081 + vertex -489.987 73.2125 297.351 + vertex -491.986 73.7641 295.748 + endloop + endfacet + facet normal -0.210708 -0.974847 -0.0726352 + outer loop + vertex -489.987 73.2125 297.351 + vertex -490.378 73.1923 298.757 + vertex -491.986 73.7641 295.748 + endloop + endfacet + facet normal -0.231588 -0.970917 -0.0607295 + outer loop + vertex -490.841 73.2468 299.65 + vertex -491.986 73.7641 295.748 + vertex -490.378 73.1923 298.757 + endloop + endfacet + facet normal -0.185248 -0.976533 -0.109845 + outer loop + vertex -492.268 74.67 287.52 + vertex -491.142 73.8311 293.081 + vertex -493.801 74.6804 290.015 + endloop + endfacet + facet normal -0.193566 -0.97513 -0.107949 + outer loop + vertex -492.268 74.67 287.52 + vertex -489.084 73.5482 291.946 + vertex -491.142 73.8311 293.081 + endloop + endfacet + facet normal -0.188538 -0.977131 -0.0983289 + outer loop + vertex -489.084 73.5482 291.946 + vertex -488.036 72.8506 296.868 + vertex -491.142 73.8311 293.081 + endloop + endfacet + facet normal -0.201789 -0.974794 -0.0951749 + outer loop + vertex -489.084 73.5482 291.946 + vertex -484.89 72.2623 296.224 + vertex -488.036 72.8506 296.868 + endloop + endfacet + facet normal -0.190271 -0.975905 -0.106801 + outer loop + vertex -485.906 72.9774 291.499 + vertex -484.89 72.2623 296.224 + vertex -489.084 73.5482 291.946 + endloop + endfacet + facet normal -0.191533 -0.974404 -0.117691 + outer loop + vertex -489.574 74.2903 286.6 + vertex -485.906 72.9774 291.499 + vertex -489.084 73.5482 291.946 + endloop + endfacet + facet normal -0.184827 -0.975058 -0.122887 + outer loop + vertex -486.195 73.5608 287.306 + vertex -485.906 72.9774 291.499 + vertex -489.574 74.2903 286.6 + endloop + endfacet + facet normal -0.178467 -0.976698 -0.119207 + outer loop + vertex -489.574 74.2903 286.6 + vertex -489.084 73.5482 291.946 + vertex -492.268 74.67 287.52 + endloop + endfacet + facet normal -0.181607 -0.974853 -0.129151 + outer loop + vertex -492.268 74.67 287.52 + vertex -492.735 75.5977 281.175 + vertex -489.574 74.2903 286.6 + endloop + endfacet + facet normal -0.171884 -0.975816 -0.135049 + outer loop + vertex -492.735 75.5977 281.175 + vertex -487.945 74.8468 280.505 + vertex -489.574 74.2903 286.6 + endloop + endfacet + facet normal -0.173287 -0.976258 -0.129969 + outer loop + vertex -492.735 75.5977 281.175 + vertex -492.268 74.67 287.52 + vertex -495.076 75.6904 283.6 + endloop + endfacet + facet normal -0.208535 -0.973658 -0.0922107 + outer loop + vertex -495.186 74.582 294.285 + vertex -499.686 75.6964 292.694 + vertex -497.013 75.6095 287.566 + endloop + endfacet + facet normal -0.193546 -0.974333 -0.114955 + outer loop + vertex -493.801 74.6804 290.015 + vertex -495.076 75.6904 283.6 + vertex -492.268 74.67 287.52 + endloop + endfacet + facet normal -0.20478 -0.971469 -0.119635 + outer loop + vertex -497.013 75.6095 287.566 + vertex -501.524 76.6638 286.728 + vertex -498.748 76.9248 279.855 + endloop + endfacet + facet normal -0.177419 -0.974969 -0.134006 + outer loop + vertex -495.076 75.6904 283.6 + vertex -495.59 76.5948 277.7 + vertex -492.735 75.5977 281.175 + endloop + endfacet + facet normal -0.163519 -0.975731 -0.145642 + outer loop + vertex -493.901 77.0372 272.84 + vertex -492.735 75.5977 281.175 + vertex -495.59 76.5948 277.7 + endloop + endfacet + facet normal -0.169307 -0.974458 -0.147537 + outer loop + vertex -495.59 76.5948 277.7 + vertex -497.262 77.5507 273.305 + vertex -493.901 77.0372 272.84 + endloop + endfacet + facet normal -0.214258 -0.967785 -0.132232 + outer loop + vertex -498.748 76.9248 279.855 + vertex -505.933 78.3292 281.219 + vertex -501.131 78.5153 272.075 + endloop + endfacet + facet normal -0.206104 -0.970123 -0.127997 + outer loop + vertex -501.131 78.5153 272.075 + vertex -505.933 78.3292 281.219 + vertex -508.127 80.0803 271.479 + endloop + endfacet + facet normal -0.21151 -0.970494 -0.115782 + outer loop + vertex -508.127 80.0803 271.479 + vertex -516.553 80.745 281.301 + vertex -518.106 82.2363 271.638 + endloop + endfacet + facet normal -0.225416 -0.967674 -0.113112 + outer loop + vertex -516.553 80.745 281.301 + vertex -529.189 83.6616 281.532 + vertex -518.106 82.2363 271.638 + endloop + endfacet + facet normal -0.235023 -0.96917 -0.0739797 + outer loop + vertex -529.189 83.6616 281.532 + vertex -541.502 85.9554 290.596 + vertex -542.711 86.9241 281.749 + endloop + endfacet + facet normal -0.248161 -0.966051 -0.071842 + outer loop + vertex -541.502 85.9554 290.596 + vertex -555.875 89.6473 290.602 + vertex -542.711 86.9241 281.749 + endloop + endfacet + facet normal -0.256628 -0.965627 -0.0413185 + outer loop + vertex -555.875 89.6473 290.602 + vertex -569.157 92.8708 297.762 + vertex -569.281 93.2132 290.526 + endloop + endfacet + facet normal -0.257897 -0.96529 -0.0412809 + outer loop + vertex -569.157 92.8708 297.762 + vertex -580.569 95.9255 297.628 + vertex -569.281 93.2132 290.526 + endloop + endfacet + facet normal -0.25655 -0.966406 -0.015514 + outer loop + vertex -580.349 95.7892 302.475 + vertex -589.01 98.0878 302.523 + vertex -580.569 95.9255 297.628 + endloop + endfacet + facet normal -0.254739 -0.966902 0.0144624 + outer loop + vertex -589.01 98.0878 302.523 + vertex -595.086 99.729 305.231 + vertex -596.489 100.064 302.897 + endloop + endfacet + facet normal -0.255561 -0.966679 -0.0148311 + outer loop + vertex -596.489 100.064 302.897 + vertex -601.725 101.446 303.015 + vertex -597.324 100.323 300.352 + endloop + endfacet + facet normal -0.255189 -0.966883 0.00408944 + outer loop + vertex -596.489 100.064 302.897 + vertex -601.379 101.364 305.236 + vertex -601.725 101.446 303.015 + endloop + endfacet + facet normal -0.249059 -0.968483 0.00307301 + outer loop + vertex -601.379 101.364 305.236 + vertex -605.04 102.305 304.946 + vertex -601.725 101.446 303.015 + endloop + endfacet + facet normal -0.25759 -0.966172 -0.0125974 + outer loop + vertex -601.725 101.446 303.015 + vertex -605.04 102.305 304.946 + vertex -605.108 102.349 302.91 + endloop + endfacet + facet normal -0.249342 -0.968329 -0.0129162 + outer loop + vertex -605.04 102.305 304.946 + vertex -607.393 102.908 305.167 + vertex -605.108 102.349 302.91 + endloop + endfacet + facet normal -0.246685 -0.968946 0.0170324 + outer loop + vertex -605.04 102.305 304.946 + vertex -605.737 102.509 306.479 + vertex -607.393 102.908 305.167 + endloop + endfacet + facet normal -0.246343 -0.969179 0.00249824 + outer loop + vertex -608.478 103.183 304.836 + vertex -607.393 102.908 305.167 + vertex -608.586 103.213 306.117 + endloop + endfacet + facet normal -0.273726 -0.961808 1.22289e-05 + outer loop + vertex -608.478 103.183 304.836 + vertex -608.586 103.213 306.117 + vertex -608.711 103.249 304.703 + endloop + endfacet + facet normal -0.287563 -0.955147 -0.0707234 + outer loop + vertex -606.205 102.848 299.258 + vertex -607.94 103.12 302.652 + vertex -606.754 103.045 298.836 + endloop + endfacet + facet normal -0.274125 -0.95989 -0.0588808 + outer loop + vertex -604.25 102.281 299.402 + vertex -607.152 102.898 302.854 + vertex -606.205 102.848 299.258 + endloop + endfacet + facet normal -0.267214 -0.961311 -0.0669183 + outer loop + vertex -600.916 101.335 299.688 + vertex -604.25 102.281 299.402 + vertex -599.349 101.234 294.883 + endloop + endfacet + facet normal -0.271804 -0.959916 -0.0684443 + outer loop + vertex -594.215 99.7085 295.883 + vertex -600.916 101.335 299.688 + vertex -599.349 101.234 294.883 + endloop + endfacet + facet normal -0.259305 -0.964396 -0.0519644 + outer loop + vertex -590.509 98.5582 298.739 + vertex -594.215 99.7085 295.883 + vertex -582.756 96.8856 291.095 + endloop + endfacet + facet normal -0.274788 -0.956796 -0.0950409 + outer loop + vertex -569.335 93.9258 282.087 + vertex -582.756 96.8856 291.095 + vertex -581.096 97.3307 281.814 + endloop + endfacet + facet normal -0.261317 -0.959488 -0.10534 + outer loop + vertex -556.251 90.3759 281.963 + vertex -569.335 93.9258 282.087 + vertex -556.174 91.3369 273.019 + endloop + endfacet + facet normal -0.249879 -0.962505 -0.105565 + outer loop + vertex -543.037 87.9649 272.667 + vertex -556.251 90.3759 281.963 + vertex -556.174 91.3369 273.019 + endloop + endfacet + facet normal -0.233419 -0.963777 -0.12903 + outer loop + vertex -530.072 84.8951 272.144 + vertex -543.037 87.9649 272.667 + vertex -530.257 86.1471 263.127 + endloop + endfacet + facet normal -0.218074 -0.967258 -0.129828 + outer loop + vertex -518.72 83.6278 262.517 + vertex -530.072 84.8951 272.144 + vertex -530.257 86.1471 263.127 + endloop + endfacet + facet normal -0.206721 -0.967009 -0.148865 + outer loop + vertex -509.142 81.6099 262.325 + vertex -518.72 83.6278 262.517 + vertex -509.622 83.055 253.604 + endloop + endfacet + facet normal -0.192948 -0.969056 -0.153951 + outer loop + vertex -502.931 81.5621 254.616 + vertex -509.622 83.055 253.604 + vertex -502.977 82.9633 245.852 + endloop + endfacet + facet normal -0.177748 -0.971875 -0.15448 + outer loop + vertex -502.931 81.5621 254.616 + vertex -502.977 82.9633 245.852 + vertex -499.167 81.6611 249.661 + endloop + endfacet + facet normal -0.2047 -0.96712 -0.150919 + outer loop + vertex -509.934 84.4545 245.072 + vertex -518.901 84.9923 253.788 + vertex -519.083 86.3718 245.195 + endloop + endfacet + facet normal -0.218647 -0.964183 -0.150152 + outer loop + vertex -518.901 84.9923 253.788 + vertex -530.264 87.4777 254.375 + vertex -519.083 86.3718 245.195 + endloop + endfacet + facet normal -0.234898 -0.960865 -0.146835 + outer loop + vertex -530.264 87.4777 254.375 + vertex -542.947 89.1504 263.719 + vertex -542.818 90.4658 254.903 + endloop + endfacet + facet normal -0.252543 -0.956441 -0.146434 + outer loop + vertex -542.947 89.1504 263.719 + vertex -555.933 92.5235 264.083 + vertex -542.818 90.4658 254.903 + endloop + endfacet + facet normal -0.27271 -0.95144 -0.142799 + outer loop + vertex -555.933 92.5235 264.083 + vertex -568.898 94.8822 273.127 + vertex -568.624 96.1422 264.209 + endloop + endfacet + facet normal -0.290674 -0.944375 -0.153834 + outer loop + vertex -568.624 96.1422 264.209 + vertex -580.616 98.3916 273.059 + vertex -580.396 99.7942 264.032 + endloop + endfacet + facet normal -0.297901 -0.942148 -0.153664 + outer loop + vertex -580.616 98.3916 273.059 + vertex -590.548 101.551 272.941 + vertex -580.396 99.7942 264.032 + endloop + endfacet + facet normal -0.275861 -0.949076 -0.152168 + outer loop + vertex -555.749 93.8668 255.219 + vertex -568.369 97.5229 255.294 + vertex -555.595 95.2402 246.374 + endloop + endfacet + facet normal -0.256566 -0.954395 -0.152658 + outer loop + vertex -542.764 91.8328 246.111 + vertex -555.749 93.8668 255.219 + vertex -555.595 95.2402 246.374 + endloop + endfacet + facet normal -0.235817 -0.961089 -0.143868 + outer loop + vertex -530.288 88.8372 245.673 + vertex -542.764 91.8328 246.111 + vertex -530.429 90.1832 236.913 + endloop + endfacet + facet normal -0.219452 -0.964832 -0.144708 + outer loop + vertex -519.301 87.7083 236.539 + vertex -530.288 88.8372 245.673 + vertex -530.429 90.1832 236.913 + endloop + endfacet + facet normal -0.2052 -0.969821 -0.131684 + outer loop + vertex -510.259 85.7993 236.508 + vertex -519.301 87.7083 236.539 + vertex -510.598 87.0451 227.86 + endloop + endfacet + facet normal -0.193273 -0.974126 -0.117148 + outer loop + vertex -503.873 85.6102 228.698 + vertex -510.598 87.0451 227.86 + vertex -504.811 86.7864 220.465 + endloop + endfacet + facet normal -0.179567 -0.976515 -0.119051 + outer loop + vertex -503.873 85.6102 228.698 + vertex -504.811 86.7864 220.465 + vertex -500.998 85.8392 222.483 + endloop + endfacet + facet normal -0.20694 -0.971449 -0.116025 + outer loop + vertex -510.97 88.1521 219.179 + vertex -519.546 88.9502 227.791 + vertex -519.777 90.0508 218.989 + endloop + endfacet + facet normal -0.220754 -0.968491 -0.115292 + outer loop + vertex -519.546 88.9502 227.791 + vertex -530.536 91.421 228.08 + vertex -519.777 90.0508 218.989 + endloop + endfacet + facet normal -0.239043 -0.961586 -0.134946 + outer loop + vertex -530.536 91.421 228.08 + vertex -542.74 93.1644 237.275 + vertex -542.726 94.4081 228.388 + endloop + endfacet + facet normal -0.25901 -0.956497 -0.134265 + outer loop + vertex -542.74 93.1644 237.275 + vertex -555.449 96.5714 237.52 + vertex -542.726 94.4081 228.388 + endloop + endfacet + facet normal -0.281748 -0.947426 -0.151664 + outer loop + vertex -555.449 96.5714 237.52 + vertex -568.042 98.8863 246.454 + vertex -567.839 100.23 237.683 + endloop + endfacet + facet normal -0.302711 -0.940127 -0.156612 + outer loop + vertex -567.839 100.23 237.683 + vertex -579.136 102.429 246.32 + vertex -579.216 103.878 237.776 + endloop + endfacet + facet normal -0.315351 -0.936097 -0.15581 + outer loop + vertex -579.136 102.429 246.32 + vertex -588.421 105.535 246.449 + vertex -579.216 103.878 237.776 + endloop + endfacet + facet normal -0.285642 -0.950541 -0.121989 + outer loop + vertex -555.335 97.8204 228.623 + vertex -567.735 101.526 228.783 + vertex -555.248 98.9446 219.66 + endloop + endfacet + facet normal -0.263767 -0.956769 -0.122558 + outer loop + vertex -542.701 95.5098 219.472 + vertex -555.335 97.8204 228.623 + vertex -555.248 98.9446 219.66 + endloop + endfacet + facet normal -0.241275 -0.965452 -0.098429 + outer loop + vertex -530.629 92.5192 219.214 + vertex -542.701 95.5098 219.472 + vertex -530.714 93.4434 210.356 + endloop + endfacet + facet normal -0.224533 -0.969424 -0.0990029 + outer loop + vertex -520.002 90.9798 210.187 + vertex -530.629 92.5192 219.214 + vertex -530.714 93.4434 210.356 + endloop + endfacet + facet normal -0.209711 -0.974851 -0.0754109 + outer loop + vertex -511.306 89.0913 210.415 + vertex -520.002 90.9798 210.187 + vertex -511.651 89.8423 201.666 + endloop + endfacet + facet normal -0.199555 -0.97824 -0.0567778 + outer loop + vertex -505.672 88.5449 203.008 + vertex -511.651 89.8423 201.666 + vertex -505.666 89.0576 194.152 + endloop + endfacet + facet normal -0.176828 -0.982589 -0.0570134 + outer loop + vertex -505.672 88.5449 203.008 + vertex -505.666 89.0576 194.152 + vertex -502.704 88.268 198.573 + endloop + endfacet + facet normal -0.212316 -0.975679 -0.0545134 + outer loop + vertex -511.999 90.3985 192.957 + vertex -520.24 91.7186 201.423 + vertex -520.478 92.2586 192.689 + endloop + endfacet + facet normal -0.22639 -0.972542 -0.0539348 + outer loop + vertex -520.24 91.7186 201.423 + vertex -530.851 94.1825 201.534 + vertex -520.478 92.2586 192.689 + endloop + endfacet + facet normal -0.244778 -0.966328 -0.0793395 + outer loop + vertex -530.851 94.1825 201.534 + vertex -542.712 96.4467 210.553 + vertex -542.744 97.1849 201.659 + endloop + endfacet + facet normal -0.266171 -0.9607 -0.0787957 + outer loop + vertex -542.712 96.4467 210.553 + vertex -555.16 99.885 210.68 + vertex -542.744 97.1849 201.659 + endloop + endfacet + facet normal -0.289668 -0.951391 -0.104627 + outer loop + vertex -555.16 99.885 210.68 + vertex -567.566 102.667 219.73 + vertex -567.331 103.586 210.719 + endloop + endfacet + facet normal -0.310905 -0.944535 -0.105789 + outer loop + vertex -567.331 103.586 210.719 + vertex -578.698 106.357 219.388 + vertex -578.252 107.196 210.582 + endloop + endfacet + facet normal -0.327492 -0.938879 -0.10609 + outer loop + vertex -578.698 106.357 219.388 + vertex -586.375 109.195 217.97 + vertex -578.252 107.196 210.582 + endloop + endfacet + facet normal -0.292075 -0.954652 -0.0577156 + outer loop + vertex -555.091 100.616 201.747 + vertex -567.219 104.321 201.836 + vertex -555.063 101.144 192.869 + endloop + endfacet + facet normal -0.269066 -0.961371 -0.0580424 + outer loop + vertex -542.786 97.7126 192.8 + vertex -555.091 100.616 201.747 + vertex -555.063 101.144 192.869 + endloop + endfacet + facet normal -0.246207 -0.968661 -0.0328299 + outer loop + vertex -531.008 94.7211 192.736 + vertex -542.786 97.7126 192.8 + vertex -531.189 95.0651 183.944 + endloop + endfacet + facet normal -0.228629 -0.972942 -0.0333592 + outer loop + vertex -520.765 92.6152 183.958 + vertex -531.008 94.7211 192.736 + vertex -531.189 95.0651 183.944 + endloop + endfacet + facet normal -0.214395 -0.976671 -0.0121594 + outer loop + vertex -512.365 90.7676 184.257 + vertex -520.765 92.6152 183.958 + vertex -512.773 90.9655 175.546 + endloop + endfacet + facet normal -0.202816 -0.979205 0.00491107 + outer loop + vertex -506.595 89.6916 176.688 + vertex -512.773 90.9655 175.546 + vertex -507.54 89.8443 168.091 + endloop + endfacet + facet normal -0.187189 -0.982319 0.00313815 + outer loop + vertex -506.595 89.6916 176.688 + vertex -507.54 89.8443 168.091 + vertex -503.991 89.1737 169.891 + endloop + endfacet + facet normal -0.21424 -0.976746 0.00822708 + outer loop + vertex -513.148 90.9811 166.777 + vertex -521.063 92.7881 175.201 + vertex -521.348 92.7765 166.395 + endloop + endfacet + facet normal -0.229234 -0.973332 0.00870791 + outer loop + vertex -521.063 92.7881 175.201 + vertex -531.363 95.2133 175.137 + vertex -521.348 92.7765 166.395 + endloop + endfacet + facet normal -0.24769 -0.968763 -0.0121359 + outer loop + vertex -531.363 95.2133 175.137 + vertex -542.857 98.0415 183.967 + vertex -542.938 98.1726 175.14 + endloop + endfacet + facet normal -0.27044 -0.962664 -0.0118386 + outer loop + vertex -542.857 98.0415 183.967 + vertex -555.071 101.472 184.015 + vertex -542.938 98.1726 175.14 + endloop + endfacet + facet normal -0.295724 -0.954532 -0.03762 + outer loop + vertex -555.071 101.472 184.015 + vertex -567.235 104.888 192.95 + vertex -567.272 105.253 183.99 + endloop + endfacet + facet normal -0.31766 -0.947424 -0.0384841 + outer loop + vertex -567.272 105.253 183.99 + vertex -578.746 108.741 192.844 + vertex -578.713 109.111 183.454 + endloop + endfacet + facet normal -0.336454 -0.940921 -0.0382938 + outer loop + vertex -578.746 108.741 192.844 + vertex -589.146 112.488 192.146 + vertex -578.713 109.111 183.454 + endloop + endfacet + facet normal -0.296895 -0.954869 0.00884434 + outer loop + vertex -555.111 101.607 175.168 + vertex -567.251 105.38 175.026 + vertex -555.206 101.554 166.311 + endloop + endfacet + facet normal -0.271899 -0.962287 0.00862125 + outer loop + vertex -543.071 98.1252 166.289 + vertex -555.111 101.607 175.168 + vertex -555.206 101.554 166.311 + endloop + endfacet + facet normal -0.247885 -0.968348 0.0292452 + outer loop + vertex -531.557 95.1779 166.294 + vertex -543.071 98.1252 166.289 + vertex -531.78 94.9664 157.403 + endloop + endfacet + facet normal -0.228716 -0.973065 0.0288769 + outer loop + vertex -521.648 92.589 157.542 + vertex -531.557 95.1779 166.294 + vertex -531.78 94.9664 157.403 + endloop + endfacet + facet normal -0.214526 -0.975667 0.0453044 + outer loop + vertex -513.543 90.8272 157.975 + vertex -521.648 92.589 157.542 + vertex -513.936 90.5043 149.164 + endloop + endfacet + facet normal -0.20198 -0.977635 0.0586052 + outer loop + vertex -508.432 89.4465 150.484 + vertex -513.936 90.5043 149.164 + vertex -508.461 88.9252 141.69 + endloop + endfacet + facet normal -0.179748 -0.981954 0.0587885 + outer loop + vertex -508.432 89.4465 150.484 + vertex -508.461 88.9252 141.69 + vertex -505.729 88.665 145.695 + endloop + endfacet + facet normal -0.211241 -0.975227 0.0656444 + outer loop + vertex -514.31 90.0171 140.405 + vertex -521.942 92.2259 148.661 + vertex -522.289 91.7054 139.812 + endloop + endfacet + facet normal -0.228005 -0.971415 0.0660779 + outer loop + vertex -521.942 92.2259 148.661 + vertex -532.02 94.5788 148.476 + vertex -522.289 91.7054 139.812 + endloop + endfacet + facet normal -0.247379 -0.967668 0.0492245 + outer loop + vertex -532.02 94.5788 148.476 + vertex -543.251 97.903 157.382 + vertex -543.442 97.4956 148.415 + endloop + endfacet + facet normal -0.27162 -0.961134 0.0494432 + outer loop + vertex -543.251 97.903 157.382 + vertex -555.345 101.321 157.388 + vertex -543.442 97.4956 148.415 + endloop + endfacet + facet normal -0.296662 -0.954506 0.0301819 + outer loop + vertex -555.345 101.321 157.388 + vertex -567.257 105.3 166.133 + vertex -567.354 105.049 157.247 + endloop + endfacet + facet normal -0.317996 -0.947554 0.0319519 + outer loop + vertex -567.354 105.049 157.247 + vertex -578.152 108.947 165.371 + vertex -578.353 108.724 156.756 + endloop + endfacet + facet normal -0.335175 -0.941605 0.0322003 + outer loop + vertex -578.152 108.947 165.371 + vertex -586.01 111.693 163.88 + vertex -578.353 108.724 156.756 + endloop + endfacet + facet normal -0.295955 -0.952656 0.0696961 + outer loop + vertex -555.497 100.896 148.387 + vertex -567.478 104.609 148.269 + vertex -555.613 100.271 139.354 + endloop + endfacet + facet normal -0.270297 -0.960237 0.0698919 + outer loop + vertex -543.622 96.9021 139.436 + vertex -555.497 100.896 148.387 + vertex -555.613 100.271 139.354 + endloop + endfacet + facet normal -0.246183 -0.965346 0.08661 + outer loop + vertex -532.28 94.0211 139.564 + vertex -543.622 96.9021 139.436 + vertex -532.523 93.289 130.714 + endloop + endfacet + facet normal -0.225209 -0.970467 0.0864587 + outer loop + vertex -522.605 91.0141 131.013 + vertex -532.28 94.0211 139.564 + vertex -532.523 93.289 130.714 + endloop + endfacet + facet normal -0.210357 -0.972592 0.0990681 + outer loop + vertex -514.715 89.3745 131.671 + vertex -522.605 91.0141 131.013 + vertex -515.134 88.5789 122.971 + endloop + endfacet + facet normal -0.194834 -0.974442 0.111815 + outer loop + vertex -509.345 87.5893 124.434 + vertex -515.134 88.5789 122.971 + vertex -510.237 86.8006 116.005 + endloop + endfacet + facet normal -0.17206 -0.978945 0.109824 + outer loop + vertex -509.345 87.5893 124.434 + vertex -510.237 86.8006 116.005 + vertex -507.307 86.5367 118.243 + endloop + endfacet + facet normal -0.203978 -0.971579 0.120112 + outer loop + vertex -515.491 87.6173 114.305 + vertex -522.938 90.1683 122.291 + vertex -523.225 89.1556 113.613 + endloop + endfacet + facet normal -0.223185 -0.96733 0.12025 + outer loop + vertex -522.938 90.1683 122.291 + vertex -532.767 92.3927 121.942 + vertex -523.225 89.1556 113.613 + endloop + endfacet + facet normal -0.242905 -0.964056 0.107671 + outer loop + vertex -532.767 92.3927 121.942 + vertex -543.781 96.1254 130.518 + vertex -543.964 95.1859 121.694 + endloop + endfacet + facet normal -0.268886 -0.957157 0.107475 + outer loop + vertex -543.781 96.1254 130.518 + vertex -555.725 99.4675 130.4 + vertex -543.964 95.1859 121.694 + endloop + endfacet + facet normal -0.294229 -0.951472 0.0901726 + outer loop + vertex -555.725 99.4675 130.4 + vertex -567.54 103.96 139.254 + vertex -567.67 103.155 130.326 + endloop + endfacet + facet normal -0.315523 -0.944544 0.0910032 + outer loop + vertex -567.67 103.155 130.326 + vertex -578.443 107.591 139.029 + vertex -578.972 106.915 130.172 + endloop + endfacet + facet normal -0.332134 -0.938778 0.0915543 + outer loop + vertex -578.443 107.591 139.029 + vertex -587.758 110.905 139.216 + vertex -578.972 106.915 130.172 + endloop + endfacet + facet normal -0.292147 -0.947756 0.128095 + outer loop + vertex -555.868 98.4959 121.549 + vertex -567.843 102.169 121.417 + vertex -556.018 97.3517 112.742 + endloop + endfacet + facet normal -0.265473 -0.955497 0.128648 + outer loop + vertex -544.151 94.0782 112.916 + vertex -555.868 98.4959 121.549 + vertex -556.018 97.3517 112.742 + endloop + endfacet + facet normal -0.240515 -0.9603 0.141335 + outer loop + vertex -532.996 91.3273 113.208 + vertex -544.151 94.0782 112.916 + vertex -533.202 90.091 104.459 + endloop + endfacet + facet normal -0.216876 -0.96588 0.141567 + outer loop + vertex -523.476 87.979 104.948 + vertex -532.996 91.3273 113.208 + vertex -533.202 90.091 104.459 + endloop + endfacet + facet normal -0.200907 -0.968074 0.149898 + outer loop + vertex -515.791 86.4997 105.695 + vertex -523.476 87.979 104.948 + vertex -516.017 85.2225 97.1443 + endloop + endfacet + facet normal -0.182497 -0.970019 0.160492 + outer loop + vertex -510.84 84.5224 98.7995 + vertex -516.017 85.2225 97.1443 + vertex -510.552 83.0358 90.142 + endloop + endfacet + facet normal -0.155765 -0.974397 0.162133 + outer loop + vertex -510.84 84.5224 98.7995 + vertex -510.552 83.0358 90.142 + vertex -507.814 83.3843 94.8667 + endloop + endfacet + facet normal -0.191663 -0.966163 0.172612 + outer loop + vertex -516.107 83.7611 88.6166 + vertex -523.663 86.6284 96.276 + vertex -523.823 85.1177 87.6417 + endloop + endfacet + facet normal -0.213871 -0.961561 0.17222 + outer loop + vertex -523.663 86.6284 96.276 + vertex -533.395 88.6869 95.6828 + vertex -523.823 85.1177 87.6417 + endloop + endfacet + facet normal -0.235348 -0.958314 0.162004 + outer loop + vertex -533.395 88.6869 95.6828 + vertex -544.339 92.8008 104.12 + vertex -544.539 91.3584 95.2971 + endloop + endfacet + facet normal -0.258706 -0.949049 0.179935 + outer loop + vertex -544.804 89.7889 86.5318 + vertex -556.447 94.5901 95.1158 + vertex -556.78 93.018 86.3447 + endloop + endfacet + facet normal -0.258156 -0.946103 0.195563 + outer loop + vertex -544.804 89.7889 86.5318 + vertex -556.78 93.018 86.3447 + vertex -545.042 88.0683 77.8938 + endloop + endfacet + facet normal -0.262477 -0.951331 0.161478 + outer loop + vertex -544.339 92.8008 104.12 + vertex -556.185 96.0368 103.93 + vertex -544.539 91.3584 95.2971 + endloop + endfacet + facet normal -0.287455 -0.94604 0.149592 + outer loop + vertex -556.185 96.0368 103.93 + vertex -567.907 100.956 112.515 + vertex -568.081 99.6183 103.719 + endloop + endfacet + facet normal -0.307674 -0.939255 0.152106 + outer loop + vertex -568.081 99.6183 103.719 + vertex -578.761 104.42 111.77 + vertex -579.183 103.176 103.23 + endloop + endfacet + facet normal -0.324525 -0.933566 0.15211 + outer loop + vertex -578.761 104.42 111.77 + vertex -586.727 106.951 110.304 + vertex -579.183 103.176 103.23 + endloop + endfacet + facet normal -0.285002 -0.941552 0.179591 + outer loop + vertex -556.447 94.5901 95.1158 + vertex -568.478 98.1996 94.9453 + vertex -556.78 93.018 86.3447 + endloop + endfacet + facet normal -0.301677 -0.934959 0.186659 + outer loop + vertex -568.848 96.6062 86.1458 + vertex -579.876 101.812 94.3954 + vertex -579.975 100.033 85.3263 + endloop + endfacet + facet normal -0.319558 -0.929188 0.185723 + outer loop + vertex -579.876 101.812 94.3954 + vertex -589.172 104.615 92.4261 + vertex -579.975 100.033 85.3263 + endloop + endfacet + facet normal -0.276768 -0.935071 0.221453 + outer loop + vertex -557.104 89.2975 69.1251 + vertex -569.029 94.8014 77.4609 + vertex -569.207 92.8279 68.9059 + endloop + endfacet + facet normal -0.279219 -0.935154 0.218001 + outer loop + vertex -557.031 91.2685 77.6734 + vertex -569.029 94.8014 77.4609 + vertex -557.104 89.2975 69.1251 + endloop + endfacet + facet normal -0.256179 -0.946073 0.19829 + outer loop + vertex -545.042 88.0683 77.8938 + vertex -556.78 93.018 86.3447 + vertex -557.031 91.2685 77.6734 + endloop + endfacet + facet normal -0.230707 -0.953039 0.196189 + outer loop + vertex -533.8 85.4559 78.4229 + vertex -544.804 89.7889 86.5318 + vertex -545.042 88.0683 77.8938 + endloop + endfacet + facet normal -0.208093 -0.958786 0.193462 + outer loop + vertex -523.953 83.4757 79.2008 + vertex -533.596 87.1344 86.9608 + vertex -533.8 85.4559 78.4229 + endloop + endfacet + facet normal -0.190076 -0.960235 0.204499 + outer loop + vertex -516.11 82.1197 80.1235 + vertex -523.953 83.4757 79.2008 + vertex -516.123 80.4152 72.1074 + endloop + endfacet + facet normal -0.167926 -0.964185 0.205302 + outer loop + vertex -509.923 79.4253 72.5304 + vertex -516.11 82.1197 80.1235 + vertex -516.123 80.4152 72.1074 + endloop + endfacet + facet normal -0.142085 -0.968384 0.205048 + outer loop + vertex -507.189 78.9769 72.3069 + vertex -507.614 80.1678 77.6372 + vertex -509.923 79.4253 72.5304 + endloop + endfacet + facet normal -0.141376 -0.96855 0.204752 + outer loop + vertex -510.857 81.536 81.8695 + vertex -509.923 79.4253 72.5304 + vertex -507.614 80.1678 77.6372 + endloop + endfacet + facet normal -0.122817 -0.972463 0.198069 + outer loop + vertex -505.132 78.8015 72.9148 + vertex -502.112 80.2118 81.7123 + vertex -505.576 81.0804 83.8284 + endloop + endfacet + facet normal -0.139304 -0.975165 0.172185 + outer loop + vertex -502.112 80.2118 81.7123 + vertex -502.324 81.9943 91.6355 + vertex -505.576 81.0804 83.8284 + endloop + endfacet + facet normal -0.12469 -0.977027 0.172832 + outer loop + vertex -502.112 80.2118 81.7123 + vertex -497.993 81.4674 91.7814 + vertex -502.324 81.9943 91.6355 + endloop + endfacet + facet normal -0.124354 -0.981139 0.147994 + outer loop + vertex -497.993 81.4674 91.7814 + vertex -498.1 82.8468 100.837 + vertex -502.324 81.9943 91.6355 + endloop + endfacet + facet normal -0.13551 -0.978905 0.15291 + outer loop + vertex -502.324 81.9943 91.6355 + vertex -498.1 82.8468 100.837 + vertex -502.328 83.3858 100.54 + endloop + endfacet + facet normal -0.151106 -0.976675 0.152554 + outer loop + vertex -502.324 81.9943 91.6355 + vertex -502.328 83.3858 100.54 + vertex -505.398 82.6759 92.954 + endloop + endfacet + facet normal -0.134308 -0.982474 0.129254 + outer loop + vertex -498.1 82.8468 100.837 + vertex -497.805 83.9648 109.641 + vertex -502.328 83.3858 100.54 + endloop + endfacet + facet normal -0.142699 -0.980747 0.133315 + outer loop + vertex -502.328 83.3858 100.54 + vertex -497.805 83.9648 109.641 + vertex -502.018 84.5292 109.283 + endloop + endfacet + facet normal -0.155163 -0.978826 0.133506 + outer loop + vertex -502.328 83.3858 100.54 + vertex -502.018 84.5292 109.283 + vertex -505.558 84.0231 101.458 + endloop + endfacet + facet normal -0.141284 -0.983598 0.112131 + outer loop + vertex -497.805 83.9648 109.641 + vertex -497.265 84.8927 118.461 + vertex -502.018 84.5292 109.283 + endloop + endfacet + facet normal -0.150092 -0.98177 0.11662 + outer loop + vertex -502.018 84.5292 109.283 + vertex -497.265 84.8927 118.461 + vertex -501.525 85.5033 118.118 + endloop + endfacet + facet normal -0.162177 -0.979792 0.117076 + outer loop + vertex -502.018 84.5292 109.283 + vertex -501.525 85.5033 118.118 + vertex -504.932 85.129 110.267 + endloop + endfacet + facet normal -0.148804 -0.984165 0.0963133 + outer loop + vertex -497.265 84.8927 118.461 + vertex -496.628 85.6674 127.361 + vertex -501.525 85.5033 118.118 + endloop + endfacet + facet normal -0.156342 -0.982599 0.100279 + outer loop + vertex -501.525 85.5033 118.118 + vertex -496.628 85.6674 127.361 + vertex -500.95 86.3219 127.036 + endloop + endfacet + facet normal -0.169016 -0.980435 0.100898 + outer loop + vertex -501.525 85.5033 118.118 + vertex -500.95 86.3219 127.036 + vertex -504.755 86.1433 118.926 + endloop + endfacet + facet normal -0.155143 -0.984629 0.0802237 + outer loop + vertex -496.628 85.6674 127.361 + vertex -495.954 86.2898 136.304 + vertex -500.95 86.3219 127.036 + endloop + endfacet + facet normal -0.161242 -0.983375 0.083516 + outer loop + vertex -500.95 86.3219 127.036 + vertex -495.954 86.2898 136.304 + vertex -500.34 86.9843 136.013 + endloop + endfacet + facet normal -0.174321 -0.981079 0.0842349 + outer loop + vertex -500.95 86.3219 127.036 + vertex -500.34 86.9843 136.013 + vertex -503.909 86.9303 127.998 + endloop + endfacet + facet normal -0.160179 -0.985042 0.0635159 + outer loop + vertex -495.954 86.2898 136.304 + vertex -495.255 86.7561 145.297 + vertex -500.34 86.9843 136.013 + endloop + endfacet + facet normal -0.165009 -0.984069 0.0661853 + outer loop + vertex -500.34 86.9843 136.013 + vertex -495.255 86.7561 145.297 + vertex -499.75 87.5007 145.16 + endloop + endfacet + facet normal -0.178289 -0.981701 0.0669076 + outer loop + vertex -500.34 86.9843 136.013 + vertex -499.75 87.5007 145.16 + vertex -503.683 87.6443 136.789 + endloop + endfacet + facet normal -0.164611 -0.985258 0.0465819 + outer loop + vertex -495.255 86.7561 145.297 + vertex -494.539 87.0632 154.325 + vertex -499.75 87.5007 145.16 + endloop + endfacet + facet normal -0.168332 -0.984525 0.0487331 + outer loop + vertex -499.75 87.5007 145.16 + vertex -494.539 87.0632 154.325 + vertex -499.086 87.8446 154.405 + endloop + endfacet + facet normal -0.18361 -0.981741 0.0497278 + outer loop + vertex -499.75 87.5007 145.16 + vertex -499.086 87.8446 154.405 + vertex -503.077 88.1995 146.674 + endloop + endfacet + facet normal -0.168794 -0.985214 0.0293518 + outer loop + vertex -494.539 87.0632 154.325 + vertex -493.815 87.2074 163.324 + vertex -499.086 87.8446 154.405 + endloop + endfacet + facet normal -0.170529 -0.984884 0.0304007 + outer loop + vertex -499.086 87.8446 154.405 + vertex -493.815 87.2074 163.324 + vertex -498.459 88.0152 163.447 + endloop + endfacet + facet normal -0.186903 -0.981874 0.0314788 + outer loop + vertex -499.086 87.8446 154.405 + vertex -498.459 88.0152 163.447 + vertex -502.182 88.4863 156.037 + endloop + endfacet + facet normal -0.17109 -0.985191 0.0112254 + outer loop + vertex -493.815 87.2074 163.324 + vertex -493.075 87.1805 172.259 + vertex -498.459 88.0152 163.447 + endloop + endfacet + facet normal -0.171297 -0.985154 0.0113555 + outer loop + vertex -498.459 88.0152 163.447 + vertex -493.075 87.1805 172.259 + vertex -497.823 88.0078 172.394 + endloop + endfacet + facet normal -0.187279 -0.982227 0.0124939 + outer loop + vertex -498.459 88.0152 163.447 + vertex -497.823 88.0078 172.394 + vertex -501.959 88.6992 164.755 + endloop + endfacet + facet normal -0.171816 -0.985102 -0.00727171 + outer loop + vertex -493.075 87.1805 172.259 + vertex -492.331 86.9853 181.156 + vertex -497.823 88.0078 172.394 + endloop + endfacet + facet normal -0.171326 -0.985185 -0.00758849 + outer loop + vertex -497.823 88.0078 172.394 + vertex -492.331 86.9853 181.156 + vertex -497.173 87.826 181.303 + endloop + endfacet + facet normal -0.187911 -0.982166 -0.00631599 + outer loop + vertex -497.823 88.0078 172.394 + vertex -497.173 87.826 181.303 + vertex -501.052 88.6157 173.918 + endloop + endfacet + facet normal -0.171833 -0.984766 -0.0266461 + outer loop + vertex -492.331 86.9853 181.156 + vertex -491.558 86.6096 190.05 + vertex -497.173 87.826 181.303 + endloop + endfacet + facet normal -0.170803 -0.984926 -0.0273292 + outer loop + vertex -497.173 87.826 181.303 + vertex -491.558 86.6096 190.05 + vertex -496.518 87.4652 190.215 + endloop + endfacet + facet normal -0.187202 -0.981977 -0.0260048 + outer loop + vertex -497.173 87.826 181.303 + vertex -496.518 87.4652 190.215 + vertex -500.809 88.487 182.524 + endloop + endfacet + facet normal -0.171301 -0.984118 -0.0465553 + outer loop + vertex -491.558 86.6096 190.05 + vertex -490.82 86.061 198.933 + vertex -496.518 87.4652 190.215 + endloop + endfacet + facet normal -0.169396 -0.984386 -0.0478435 + outer loop + vertex -496.518 87.4652 190.215 + vertex -490.82 86.061 198.933 + vertex -495.864 86.9195 199.126 + endloop + endfacet + facet normal -0.187826 -0.981111 -0.0462897 + outer loop + vertex -496.518 87.4652 190.215 + vertex -495.864 86.9195 199.126 + vertex -499.897 88.0447 191.641 + endloop + endfacet + facet normal -0.169945 -0.983117 -0.0678244 + outer loop + vertex -490.82 86.061 198.933 + vertex -490.069 85.3184 207.814 + vertex -495.864 86.9195 199.126 + endloop + endfacet + facet normal -0.16751 -0.983417 -0.0695037 + outer loop + vertex -495.864 86.9195 199.126 + vertex -490.069 85.3184 207.814 + vertex -495.219 86.1803 208.031 + endloop + endfacet + facet normal -0.185917 -0.980216 -0.0679045 + outer loop + vertex -495.864 86.9195 199.126 + vertex -495.219 86.1803 208.031 + vertex -499.671 87.5652 200.229 + endloop + endfacet + facet normal -0.168053 -0.981754 -0.0889788 + outer loop + vertex -490.069 85.3184 207.814 + vertex -489.308 84.3856 216.67 + vertex -495.219 86.1803 208.031 + endloop + endfacet + facet normal -0.165461 -0.982027 -0.090808 + outer loop + vertex -495.219 86.1803 208.031 + vertex -489.308 84.3856 216.67 + vertex -494.58 85.2474 216.956 + endloop + endfacet + facet normal -0.183988 -0.978877 -0.0891534 + outer loop + vertex -495.219 86.1803 208.031 + vertex -494.58 85.2474 216.956 + vertex -498.734 86.7144 209.42 + endloop + endfacet + facet normal -0.166113 -0.980099 -0.108682 + outer loop + vertex -489.308 84.3856 216.67 + vertex -488.531 83.2765 225.484 + vertex -494.58 85.2474 216.956 + endloop + endfacet + facet normal -0.162909 -0.980375 -0.111019 + outer loop + vertex -494.58 85.2474 216.956 + vertex -488.531 83.2765 225.484 + vertex -493.95 84.1232 225.959 + endloop + endfacet + facet normal -0.180328 -0.977499 -0.109441 + outer loop + vertex -494.58 85.2474 216.956 + vertex -493.95 84.1232 225.959 + vertex -498.581 85.8609 218.068 + endloop + endfacet + facet normal -0.16392 -0.978381 -0.126098 + outer loop + vertex -488.531 83.2765 225.484 + vertex -487.687 82.0046 234.255 + vertex -493.95 84.1232 225.959 + endloop + endfacet + facet normal -0.160935 -0.978577 -0.128402 + outer loop + vertex -493.95 84.1232 225.959 + vertex -487.687 82.0046 234.255 + vertex -493.183 82.8118 234.992 + endloop + endfacet + facet normal -0.177763 -0.975898 -0.126584 + outer loop + vertex -493.95 84.1232 225.959 + vertex -493.183 82.8118 234.992 + vertex -497.976 84.6158 227.814 + endloop + endfacet + facet normal -0.162281 -0.976689 -0.140512 + outer loop + vertex -487.687 82.0046 234.255 + vertex -486.765 80.5934 243 + vertex -493.183 82.8118 234.992 + endloop + endfacet + facet normal -0.159767 -0.976807 -0.142559 + outer loop + vertex -493.183 82.8118 234.992 + vertex -486.765 80.5934 243 + vertex -492.361 81.3908 243.808 + endloop + endfacet + facet normal -0.172889 -0.974795 -0.141012 + outer loop + vertex -493.183 82.8118 234.992 + vertex -492.361 81.3908 243.808 + vertex -497.006 83.211 236.919 + endloop + endfacet + facet normal -0.16083 -0.975298 -0.151416 + outer loop + vertex -486.765 80.5934 243 + vertex -485.784 79.0667 251.791 + vertex -492.361 81.3908 243.808 + endloop + endfacet + facet normal -0.159422 -0.975346 -0.15259 + outer loop + vertex -492.361 81.3908 243.808 + vertex -485.784 79.0667 251.791 + vertex -491.452 79.8723 252.564 + endloop + endfacet + facet normal -0.169055 -0.973918 -0.151342 + outer loop + vertex -492.361 81.3908 243.808 + vertex -491.452 79.8723 252.564 + vertex -496.622 81.8746 245.454 + endloop + endfacet + facet normal -0.160031 -0.974374 -0.158065 + outer loop + vertex -485.784 79.0667 251.791 + vertex -484.83 77.4732 260.648 + vertex -491.452 79.8723 252.564 + endloop + endfacet + facet normal -0.160645 -0.974356 -0.157556 + outer loop + vertex -491.452 79.8723 252.564 + vertex -484.83 77.4732 260.648 + vertex -490.564 78.3073 261.337 + endloop + endfacet + facet normal -0.1647 -0.973762 -0.15704 + outer loop + vertex -491.452 79.8723 252.564 + vertex -490.564 78.3073 261.337 + vertex -495.458 80.269 254.306 + endloop + endfacet + facet normal -0.160862 -0.973945 -0.159856 + outer loop + vertex -484.83 77.4732 260.648 + vertex -484.27 76.0081 269.011 + vertex -490.564 78.3073 261.337 + endloop + endfacet + facet normal -0.165063 -0.973808 -0.156369 + outer loop + vertex -490.564 78.3073 261.337 + vertex -484.27 76.0081 269.011 + vertex -489.61 76.6996 270.341 + endloop + endfacet + facet normal -0.157622 -0.974426 -0.160157 + outer loop + vertex -484.83 77.4732 260.648 + vertex -476.655 74.7071 269.432 + vertex -484.27 76.0081 269.011 + endloop + endfacet + facet normal -0.157294 -0.973809 -0.164176 + outer loop + vertex -484.27 76.0081 269.011 + vertex -476.655 74.7071 269.432 + vertex -478.067 73.8834 275.671 + endloop + endfacet + facet normal -0.165377 -0.973715 -0.156617 + outer loop + vertex -483.449 74.6332 276.693 + vertex -484.27 76.0081 269.011 + vertex -478.067 73.8834 275.671 + endloop + endfacet + facet normal -0.165488 -0.973587 -0.157294 + outer loop + vertex -478.067 73.8834 275.671 + vertex -477.195 72.8398 281.213 + vertex -483.449 74.6332 276.693 + endloop + endfacet + facet normal -0.161818 -0.974095 -0.157967 + outer loop + vertex -478.067 73.8834 275.671 + vertex -472.453 72.1819 280.412 + vertex -477.195 72.8398 281.213 + endloop + endfacet + facet normal -0.161747 -0.974187 -0.157474 + outer loop + vertex -472.453 72.1819 280.412 + vertex -471.105 71.2801 284.606 + vertex -477.195 72.8398 281.213 + endloop + endfacet + facet normal -0.163732 -0.974408 -0.154014 + outer loop + vertex -477.195 72.8398 281.213 + vertex -471.105 71.2801 284.606 + vertex -475.352 71.8101 285.768 + endloop + endfacet + facet normal -0.169262 -0.973834 -0.151648 + outer loop + vertex -477.195 72.8398 281.213 + vertex -475.352 71.8101 285.768 + vertex -481.254 73.252 283.096 + endloop + endfacet + facet normal -0.171047 -0.974106 -0.147853 + outer loop + vertex -481.254 73.252 283.096 + vertex -475.352 71.8101 285.768 + vertex -478.451 72.1442 287.151 + endloop + endfacet + facet normal -0.170353 -0.974476 -0.14621 + outer loop + vertex -475.352 71.8101 285.768 + vertex -473.501 70.9431 289.39 + vertex -478.451 72.1442 287.151 + endloop + endfacet + facet normal -0.174948 -0.975087 -0.136375 + outer loop + vertex -478.451 72.1442 287.151 + vertex -473.501 70.9431 289.39 + vertex -477.776 71.5907 290.244 + endloop + endfacet + facet normal -0.166609 -0.974821 -0.148207 + outer loop + vertex -475.352 71.8101 285.768 + vertex -469.29 70.3931 288.274 + vertex -473.501 70.9431 289.39 + endloop + endfacet + facet normal -0.167141 -0.97439 -0.150428 + outer loop + vertex -469.29 70.3931 288.274 + vertex -467.52 69.6014 291.435 + vertex -473.501 70.9431 289.39 + endloop + endfacet + facet normal -0.170952 -0.975299 -0.139883 + outer loop + vertex -473.501 70.9431 289.39 + vertex -467.52 69.6014 291.435 + vertex -472 70.2186 292.607 + endloop + endfacet + facet normal -0.171886 -0.974558 -0.143844 + outer loop + vertex -467.52 69.6014 291.435 + vertex -466.317 68.9945 294.109 + vertex -472 70.2186 292.607 + endloop + endfacet + facet normal -0.166466 -0.975117 -0.146409 + outer loop + vertex -467.52 69.6014 291.435 + vertex -461.83 68.418 292.848 + vertex -466.317 68.9945 294.109 + endloop + endfacet + facet normal -0.166687 -0.97495 -0.14727 + outer loop + vertex -461.83 68.418 292.848 + vertex -461.492 68.0592 294.84 + vertex -466.317 68.9945 294.109 + endloop + endfacet + facet normal -0.168521 -0.976169 -0.136728 + outer loop + vertex -466.317 68.9945 294.109 + vertex -461.492 68.0592 294.84 + vertex -466.285 68.7157 296.061 + endloop + endfacet + facet normal -0.176676 -0.974773 -0.136394 + outer loop + vertex -466.317 68.9945 294.109 + vertex -466.285 68.7157 296.061 + vertex -470.858 69.6256 295.481 + endloop + endfacet + facet normal -0.166677 -0.977572 -0.12873 + outer loop + vertex -466.285 68.7157 296.061 + vertex -461.492 68.0592 294.84 + vertex -464.625 68.2993 297.074 + endloop + endfacet + facet normal -0.175833 -0.977816 -0.113838 + outer loop + vertex -466.285 68.7157 296.061 + vertex -464.625 68.2993 297.074 + vertex -470.179 69.2359 297.607 + endloop + endfacet + facet normal -0.161341 -0.975691 -0.148312 + outer loop + vertex -461.83 68.418 292.848 + vertex -457.298 67.584 293.403 + vertex -461.492 68.0592 294.84 + endloop + endfacet + facet normal -0.157117 -0.978293 -0.135121 + outer loop + vertex -457.298 67.584 293.403 + vertex -455.414 67.1713 294.202 + vertex -461.492 68.0592 294.84 + endloop + endfacet + facet normal -0.147695 -0.976577 -0.156472 + outer loop + vertex -457.298 67.584 293.403 + vertex -452.731 67.074 292.277 + vertex -455.414 67.1713 294.202 + endloop + endfacet + facet normal -0.149908 -0.974608 -0.166333 + outer loop + vertex -457.458 67.9084 291.647 + vertex -452.731 67.074 292.277 + vertex -457.298 67.584 293.403 + endloop + endfacet + facet normal -0.148495 -0.973273 -0.17518 + outer loop + vertex -453.13 67.4635 290.45 + vertex -452.731 67.074 292.277 + vertex -457.458 67.9084 291.647 + endloop + endfacet + facet normal -0.148125 -0.973591 -0.173724 + outer loop + vertex -458.808 68.554 289.181 + vertex -453.13 67.4635 290.45 + vertex -457.458 67.9084 291.647 + endloop + endfacet + facet normal -0.155267 -0.973186 -0.169708 + outer loop + vertex -458.808 68.554 289.181 + vertex -457.458 67.9084 291.647 + vertex -463.134 69.0506 290.29 + endloop + endfacet + facet normal -0.154052 -0.974276 -0.164484 + outer loop + vertex -464.947 69.8572 287.211 + vertex -458.808 68.554 289.181 + vertex -463.134 69.0506 290.29 + endloop + endfacet + facet normal -0.159616 -0.973942 -0.161121 + outer loop + vertex -464.947 69.8572 287.211 + vertex -463.134 69.0506 290.29 + vertex -469.29 70.3931 288.274 + endloop + endfacet + facet normal -0.158749 -0.974726 -0.157185 + outer loop + vertex -471.105 71.2801 284.606 + vertex -464.947 69.8572 287.211 + vertex -469.29 70.3931 288.274 + endloop + endfacet + facet normal -0.156464 -0.974253 -0.162328 + outer loop + vertex -466.655 70.7207 283.675 + vertex -464.947 69.8572 287.211 + vertex -471.105 71.2801 284.606 + endloop + endfacet + facet normal -0.150763 -0.974671 -0.165185 + outer loop + vertex -466.655 70.7207 283.675 + vertex -460.614 69.3602 286.189 + vertex -464.947 69.8572 287.211 + endloop + endfacet + facet normal -0.148422 -0.974113 -0.170511 + outer loop + vertex -462.307 70.2221 282.739 + vertex -460.614 69.3602 286.189 + vertex -466.655 70.7207 283.675 + endloop + endfacet + facet normal -0.147586 -0.974991 -0.166166 + outer loop + vertex -467.946 71.5967 279.681 + vertex -462.307 70.2221 282.739 + vertex -466.655 70.7207 283.675 + endloop + endfacet + facet normal -0.153162 -0.974456 -0.164247 + outer loop + vertex -467.946 71.5967 279.681 + vertex -466.655 70.7207 283.675 + vertex -472.453 72.1819 280.412 + endloop + endfacet + facet normal -0.153009 -0.974667 -0.163134 + outer loop + vertex -472.95 72.9614 276.221 + vertex -467.946 71.5967 279.681 + vertex -472.453 72.1819 280.412 + endloop + endfacet + facet normal -0.148912 -0.974316 -0.16892 + outer loop + vertex -469.067 72.6135 274.804 + vertex -467.946 71.5967 279.681 + vertex -472.95 72.9614 276.221 + endloop + endfacet + facet normal -0.149009 -0.974252 -0.1692 + outer loop + vertex -472.95 72.9614 276.221 + vertex -476.655 74.7071 269.432 + vertex -469.067 72.6135 274.804 + endloop + endfacet + facet normal -0.145045 -0.973888 -0.174656 + outer loop + vertex -476.655 74.7071 269.432 + vertex -468.243 73.6113 268.557 + vertex -469.067 72.6135 274.804 + endloop + endfacet + facet normal -0.141302 -0.974508 -0.174262 + outer loop + vertex -464.27 71.9092 274.853 + vertex -469.067 72.6135 274.804 + vertex -468.243 73.6113 268.557 + endloop + endfacet + facet normal -0.131031 -0.974751 -0.180809 + outer loop + vertex -464.27 71.9092 274.853 + vertex -468.243 73.6113 268.557 + vertex -460.375 71.6905 273.21 + endloop + endfacet + facet normal -0.131216 -0.974641 -0.181263 + outer loop + vertex -460.375 71.6905 273.21 + vertex -459.281 70.6679 277.916 + vertex -464.27 71.9092 274.853 + endloop + endfacet + facet normal -0.135017 -0.975212 -0.175306 + outer loop + vertex -464.27 71.9092 274.853 + vertex -459.281 70.6679 277.916 + vertex -463.623 71.1046 278.831 + endloop + endfacet + facet normal -0.13573 -0.97443 -0.179064 + outer loop + vertex -459.281 70.6679 277.916 + vertex -457.981 69.7784 281.771 + vertex -463.623 71.1046 278.831 + endloop + endfacet + facet normal -0.138778 -0.975011 -0.173477 + outer loop + vertex -463.623 71.1046 278.831 + vertex -457.981 69.7784 281.771 + vertex -462.307 70.2221 282.739 + endloop + endfacet + facet normal -0.139857 -0.973892 -0.178816 + outer loop + vertex -457.981 69.7784 281.771 + vertex -456.273 68.9149 285.139 + vertex -462.307 70.2221 282.739 + endloop + endfacet + facet normal -0.131888 -0.974236 -0.182946 + outer loop + vertex -457.981 69.7784 281.771 + vertex -451.828 68.5198 284.038 + vertex -456.273 68.9149 285.139 + endloop + endfacet + facet normal -0.133296 -0.972864 -0.189125 + outer loop + vertex -451.828 68.5198 284.038 + vertex -449.977 67.7197 286.849 + vertex -456.273 68.9149 285.139 + endloop + endfacet + facet normal -0.134397 -0.973418 -0.185461 + outer loop + vertex -456.273 68.9149 285.139 + vertex -449.977 67.7197 286.849 + vertex -454.463 68.1101 288.05 + endloop + endfacet + facet normal -0.143336 -0.973197 -0.17984 + outer loop + vertex -456.273 68.9149 285.139 + vertex -454.463 68.1101 288.05 + vertex -460.614 69.3602 286.189 + endloop + endfacet + facet normal -0.144957 -0.973852 -0.174926 + outer loop + vertex -460.614 69.3602 286.189 + vertex -454.463 68.1101 288.05 + vertex -458.808 68.554 289.181 + endloop + endfacet + facet normal -0.135665 -0.972253 -0.190574 + outer loop + vertex -449.977 67.7197 286.849 + vertex -448.596 67.0727 289.167 + vertex -454.463 68.1101 288.05 + endloop + endfacet + facet normal -0.1366 -0.97295 -0.186305 + outer loop + vertex -454.463 68.1101 288.05 + vertex -448.596 67.0727 289.167 + vertex -453.13 67.4635 290.45 + endloop + endfacet + facet normal -0.138503 -0.971267 -0.193539 + outer loop + vertex -448.596 67.0727 289.167 + vertex -448.582 66.7276 290.888 + vertex -453.13 67.4635 290.45 + endloop + endfacet + facet normal -0.124488 -0.973069 -0.194011 + outer loop + vertex -448.596 67.0727 289.167 + vertex -443.405 66.3373 289.524 + vertex -448.582 66.7276 290.888 + endloop + endfacet + facet normal -0.123132 -0.974322 -0.188507 + outer loop + vertex -448.582 66.7276 290.888 + vertex -443.405 66.3373 289.524 + vertex -447.172 66.3869 291.729 + endloop + endfacet + facet normal -0.137059 -0.976546 -0.166052 + outer loop + vertex -448.582 66.7276 290.888 + vertex -447.172 66.3869 291.729 + vertex -452.731 67.074 292.277 + endloop + endfacet + facet normal -0.123757 -0.971614 -0.201618 + outer loop + vertex -443.644 66.7602 287.633 + vertex -443.405 66.3373 289.524 + vertex -448.596 67.0727 289.167 + endloop + endfacet + facet normal -0.106202 -0.973155 -0.20418 + outer loop + vertex -443.644 66.7602 287.633 + vertex -436.239 66.0764 287.041 + vertex -443.405 66.3373 289.524 + endloop + endfacet + facet normal -0.118661 -0.963201 -0.241171 + outer loop + vertex -436.239 66.0764 287.041 + vertex -438.575 65.8001 289.294 + vertex -443.405 66.3373 289.524 + endloop + endfacet + facet normal -0.0983677 -0.970301 -0.220996 + outer loop + vertex -436.239 66.0764 287.041 + vertex -429.885 65.4735 286.859 + vertex -438.575 65.8001 289.294 + endloop + endfacet + facet normal -0.0985777 -0.958256 -0.268381 + outer loop + vertex -427.781 65.7544 285.084 + vertex -429.885 65.4735 286.859 + vertex -436.239 66.0764 287.041 + endloop + endfacet + facet normal -0.0886605 -0.970668 -0.223479 + outer loop + vertex -427.781 65.7544 285.084 + vertex -436.239 66.0764 287.041 + vertex -433.467 66.6995 283.234 + endloop + endfacet + facet normal -0.0729096 -0.960951 -0.266939 + outer loop + vertex -420.702 65.9842 282.323 + vertex -427.781 65.7544 285.084 + vertex -433.467 66.6995 283.234 + endloop + endfacet + facet normal -0.0701519 -0.973285 -0.218622 + outer loop + vertex -433.467 66.6995 283.234 + vertex -426.349 66.9864 279.673 + vertex -420.702 65.9842 282.323 + endloop + endfacet + facet normal -0.0453692 -0.962528 -0.267362 + outer loop + vertex -426.349 66.9864 279.673 + vertex -415.69 66.913 278.129 + vertex -420.702 65.9842 282.323 + endloop + endfacet + facet normal -0.0380715 -0.965072 -0.259205 + outer loop + vertex -411.018 66.0432 280.681 + vertex -420.702 65.9842 282.323 + vertex -415.69 66.913 278.129 + endloop + endfacet + facet normal -1.68696e-05 -0.946547 -0.322567 + outer loop + vertex -403.761 66.8167 278.411 + vertex -411.018 66.0432 280.681 + vertex -415.69 66.913 278.129 + endloop + endfacet + facet normal -0.000978729 -0.958259 -0.285899 + outer loop + vertex -415.69 66.913 278.129 + vertex -405.772 67.7907 275.153 + vertex -403.761 66.8167 278.411 + endloop + endfacet + facet normal 0.00744742 -0.965586 -0.259976 + outer loop + vertex -417.804 68.3652 272.675 + vertex -405.772 67.7907 275.153 + vertex -415.69 66.913 278.129 + endloop + endfacet + facet normal -0.0373029 -0.969162 -0.243583 + outer loop + vertex -417.804 68.3652 272.675 + vertex -415.69 66.913 278.129 + vertex -427.339 68.1612 274.946 + endloop + endfacet + facet normal -0.0331621 -0.973426 -0.226586 + outer loop + vertex -429.76 69.7326 268.55 + vertex -417.804 68.3652 272.675 + vertex -427.339 68.1612 274.946 + endloop + endfacet + facet normal -0.067808 -0.974532 -0.213749 + outer loop + vertex -429.76 69.7326 268.55 + vertex -427.339 68.1612 274.946 + vertex -439.341 69.8962 270.843 + endloop + endfacet + facet normal -0.0651101 -0.977159 -0.20229 + outer loop + vertex -441.172 71.5978 263.213 + vertex -429.76 69.7326 268.55 + vertex -439.341 69.8962 270.843 + endloop + endfacet + facet normal -0.0907401 -0.976402 -0.195972 + outer loop + vertex -441.172 71.5978 263.213 + vertex -439.341 69.8962 270.843 + vertex -450.003 71.9666 265.465 + endloop + endfacet + facet normal -0.0880009 -0.978822 -0.184831 + outer loop + vertex -451.871 73.7679 256.815 + vertex -441.172 71.5978 263.213 + vertex -450.003 71.9666 265.465 + endloop + endfacet + facet normal -0.107715 -0.977689 -0.180337 + outer loop + vertex -451.871 73.7679 256.815 + vertex -450.003 71.9666 265.465 + vertex -460.584 74.4756 258.182 + endloop + endfacet + facet normal -0.106266 -0.979685 -0.170075 + outer loop + vertex -462.047 76.1118 249.671 + vertex -451.871 73.7679 256.815 + vertex -460.584 74.4756 258.182 + endloop + endfacet + facet normal -0.122861 -0.97828 -0.166952 + outer loop + vertex -462.047 76.1118 249.671 + vertex -460.584 74.4756 258.182 + vertex -470.485 77.0217 250.549 + endloop + endfacet + facet normal -0.122014 -0.980034 -0.156987 + outer loop + vertex -471.74 78.5352 242.077 + vertex -462.047 76.1118 249.671 + vertex -470.485 77.0217 250.549 + endloop + endfacet + facet normal -0.137462 -0.978398 -0.154405 + outer loop + vertex -471.74 78.5352 242.077 + vertex -470.485 77.0217 250.549 + vertex -479.71 79.5808 242.546 + endloop + endfacet + facet normal -0.137029 -0.98018 -0.143076 + outer loop + vertex -480.755 80.9757 233.991 + vertex -471.74 78.5352 242.077 + vertex -479.71 79.5808 242.546 + endloop + endfacet + facet normal -0.15061 -0.978467 -0.141137 + outer loop + vertex -480.755 80.9757 233.991 + vertex -479.71 79.5808 242.546 + vertex -487.687 82.0046 234.255 + endloop + endfacet + facet normal -0.138154 -0.980203 -0.141828 + outer loop + vertex -472.966 79.9164 233.725 + vertex -471.74 78.5352 242.077 + vertex -480.755 80.9757 233.991 + endloop + endfacet + facet normal -0.137947 -0.982109 -0.128186 + outer loop + vertex -481.735 82.2331 225.412 + vertex -472.966 79.9164 233.725 + vertex -480.755 80.9757 233.991 + endloop + endfacet + facet normal -0.151842 -0.980298 -0.126334 + outer loop + vertex -481.735 82.2331 225.412 + vertex -480.755 80.9757 233.991 + vertex -488.531 83.2765 225.484 + endloop + endfacet + facet normal -0.139411 -0.982103 -0.12664 + outer loop + vertex -474.105 81.1653 225.294 + vertex -472.966 79.9164 233.725 + vertex -481.735 82.2331 225.412 + endloop + endfacet + facet normal -0.139433 -0.984035 -0.110603 + outer loop + vertex -482.651 83.3387 216.73 + vertex -474.105 81.1653 225.294 + vertex -481.735 82.2331 225.412 + endloop + endfacet + facet normal -0.15346 -0.982138 -0.108881 + outer loop + vertex -482.651 83.3387 216.73 + vertex -481.735 82.2331 225.412 + vertex -489.308 84.3856 216.67 + endloop + endfacet + facet normal -0.140821 -0.983993 -0.109208 + outer loop + vertex -475.187 82.2703 216.732 + vertex -474.105 81.1653 225.294 + vertex -482.651 83.3387 216.73 + endloop + endfacet + facet normal -0.141087 -0.985816 -0.0908922 + outer loop + vertex -483.534 84.2731 207.967 + vertex -475.187 82.2703 216.732 + vertex -482.651 83.3387 216.73 + endloop + endfacet + facet normal -0.15529 -0.983829 -0.0892486 + outer loop + vertex -483.534 84.2731 207.967 + vertex -482.651 83.3387 216.73 + vertex -490.069 85.3184 207.814 + endloop + endfacet + facet normal -0.142061 -0.985762 -0.0899521 + outer loop + vertex -476.248 83.2119 208.089 + vertex -475.187 82.2703 216.732 + vertex -483.534 84.2731 207.967 + endloop + endfacet + facet normal -0.142613 -0.987289 -0.0701582 + outer loop + vertex -484.423 85.0266 199.169 + vertex -476.248 83.2119 208.089 + vertex -483.534 84.2731 207.967 + endloop + endfacet + facet normal -0.15677 -0.985253 -0.0685544 + outer loop + vertex -484.423 85.0266 199.169 + vertex -483.534 84.2731 207.967 + vertex -490.82 86.061 198.933 + endloop + endfacet + facet normal -0.142935 -0.987264 -0.0698584 + outer loop + vertex -477.317 83.9805 199.415 + vertex -476.248 83.2119 208.089 + vertex -484.423 85.0266 199.169 + endloop + endfacet + facet normal -0.143795 -0.988362 -0.0496436 + outer loop + vertex -485.328 85.6007 190.361 + vertex -477.317 83.9805 199.415 + vertex -484.423 85.0266 199.169 + endloop + endfacet + facet normal -0.157332 -0.986373 -0.0481228 + outer loop + vertex -485.328 85.6007 190.361 + vertex -484.423 85.0266 199.169 + vertex -491.558 86.6096 190.05 + endloop + endfacet + facet normal -0.143579 -0.988383 -0.0498379 + outer loop + vertex -478.38 84.5732 190.721 + vertex -477.317 83.9805 199.415 + vertex -485.328 85.6007 190.361 + endloop + endfacet + facet normal -0.14471 -0.989025 -0.029809 + outer loop + vertex -486.221 85.9971 181.547 + vertex -478.38 84.5732 190.721 + vertex -485.328 85.6007 190.361 + endloop + endfacet + facet normal -0.157816 -0.98706 -0.028392 + outer loop + vertex -486.221 85.9971 181.547 + vertex -485.328 85.6007 190.361 + vertex -492.331 86.9853 181.156 + endloop + endfacet + facet normal -0.143176 -0.989207 -0.0311483 + outer loop + vertex -479.44 85.001 182.009 + vertex -478.38 84.5732 190.721 + vertex -486.221 85.9971 181.547 + endloop + endfacet + facet normal -0.144573 -0.989431 -0.0111521 + outer loop + vertex -487.106 86.226 172.711 + vertex -479.44 85.001 182.009 + vertex -486.221 85.9971 181.547 + endloop + endfacet + facet normal -0.157194 -0.987519 -0.00983866 + outer loop + vertex -487.106 86.226 172.711 + vertex -486.221 85.9971 181.547 + vertex -493.075 87.1805 172.259 + endloop + endfacet + facet normal -0.141866 -0.989795 -0.0134322 + outer loop + vertex -480.485 85.2695 173.263 + vertex -479.44 85.001 182.009 + vertex -487.106 86.226 172.711 + endloop + endfacet + facet normal -0.143523 -0.989624 0.00673465 + outer loop + vertex -487.975 86.2916 163.843 + vertex -480.485 85.2695 173.263 + vertex -487.106 86.226 172.711 + endloop + endfacet + facet normal -0.155585 -0.987791 0.00792951 + outer loop + vertex -487.975 86.2916 163.843 + vertex -487.106 86.226 172.711 + vertex -493.815 87.2074 163.324 + endloop + endfacet + facet normal -0.139639 -0.990196 0.00358444 + outer loop + vertex -481.501 85.381 164.475 + vertex -480.485 85.2695 173.263 + vertex -487.975 86.2916 163.843 + endloop + endfacet + facet normal -0.141554 -0.989639 0.0240143 + outer loop + vertex -488.826 86.1972 154.938 + vertex -481.501 85.381 164.475 + vertex -487.975 86.2916 163.843 + endloop + endfacet + facet normal -0.15245 -0.987994 0.0250384 + outer loop + vertex -488.826 86.1972 154.938 + vertex -487.975 86.2916 163.843 + vertex -494.539 87.0632 154.325 + endloop + endfacet + facet normal -0.136004 -0.990513 0.0196773 + outer loop + vertex -482.495 85.3421 155.652 + vertex -481.501 85.381 164.475 + vertex -488.826 86.1972 154.938 + endloop + endfacet + facet normal -0.13826 -0.989553 0.040843 + outer loop + vertex -489.644 85.9436 146.022 + vertex -482.495 85.3421 155.652 + vertex -488.826 86.1972 154.938 + endloop + endfacet + facet normal -0.14847 -0.988036 0.0417371 + outer loop + vertex -489.644 85.9436 146.022 + vertex -488.826 86.1972 154.938 + vertex -495.255 86.7561 145.297 + endloop + endfacet + facet normal -0.13124 -0.990713 0.035559 + outer loop + vertex -483.443 85.1502 146.806 + vertex -482.495 85.3421 155.652 + vertex -489.644 85.9436 146.022 + endloop + endfacet + facet normal -0.133781 -0.989369 0.0570222 + outer loop + vertex -490.448 85.5384 137.107 + vertex -483.443 85.1502 146.806 + vertex -489.644 85.9436 146.022 + endloop + endfacet + facet normal -0.143264 -0.987994 0.0578145 + outer loop + vertex -490.448 85.5384 137.107 + vertex -489.644 85.9436 146.022 + vertex -495.954 86.2898 136.304 + endloop + endfacet + facet normal -0.125205 -0.990831 0.0507699 + outer loop + vertex -484.357 84.8125 137.959 + vertex -483.443 85.1502 146.806 + vertex -490.448 85.5384 137.107 + endloop + endfacet + facet normal -0.128133 -0.989052 0.0732029 + outer loop + vertex -491.211 84.9789 128.212 + vertex -484.357 84.8125 137.959 + vertex -490.448 85.5384 137.107 + endloop + endfacet + facet normal -0.137149 -0.98779 0.0738965 + outer loop + vertex -491.211 84.9789 128.212 + vertex -490.448 85.5384 137.107 + vertex -496.628 85.6674 127.361 + endloop + endfacet + facet normal -0.117049 -0.990972 0.0653776 + outer loop + vertex -485.25 84.3365 129.148 + vertex -484.357 84.8125 137.959 + vertex -491.211 84.9789 128.212 + endloop + endfacet + facet normal -0.120395 -0.988802 0.0881836 + outer loop + vertex -491.957 84.2813 119.371 + vertex -485.25 84.3365 129.148 + vertex -491.211 84.9789 128.212 + endloop + endfacet + facet normal -0.128995 -0.98766 0.0888197 + outer loop + vertex -491.957 84.2813 119.371 + vertex -491.211 84.9789 128.212 + vertex -497.265 84.8927 118.461 + endloop + endfacet + facet normal -0.108035 -0.990946 0.0797152 + outer loop + vertex -486.104 83.7261 120.402 + vertex -485.25 84.3365 129.148 + vertex -491.957 84.2813 119.371 + endloop + endfacet + facet normal -0.112068 -0.988235 0.104074 + outer loop + vertex -492.574 83.4274 110.599 + vertex -486.104 83.7261 120.402 + vertex -491.957 84.2813 119.371 + endloop + endfacet + facet normal -0.120558 -0.987183 0.104569 + outer loop + vertex -492.574 83.4274 110.599 + vertex -491.957 84.2813 119.371 + vertex -497.805 83.9648 109.641 + endloop + endfacet + facet normal -0.0977827 -0.99069 0.0947217 + outer loop + vertex -486.828 82.9652 111.696 + vertex -486.104 83.7261 120.402 + vertex -492.574 83.4274 110.599 + endloop + endfacet + facet normal -0.102632 -0.987264 0.121554 + outer loop + vertex -492.885 82.3759 101.795 + vertex -486.828 82.9652 111.696 + vertex -492.574 83.4274 110.599 + endloop + endfacet + facet normal -0.111453 -0.986284 0.121749 + outer loop + vertex -492.885 82.3759 101.795 + vertex -492.574 83.4274 110.599 + vertex -498.1 82.8468 100.837 + endloop + endfacet + facet normal -0.0860538 -0.990023 0.111576 + outer loop + vertex -487.234 82.0115 102.92 + vertex -486.828 82.9652 111.696 + vertex -492.885 82.3759 101.795 + endloop + endfacet + facet normal -0.0914567 -0.985911 0.140054 + outer loop + vertex -492.715 81.0831 92.8057 + vertex -487.234 82.0115 102.92 + vertex -492.885 82.3759 101.795 + endloop + endfacet + facet normal -0.0988746 -0.985229 0.139815 + outer loop + vertex -492.715 81.0831 92.8057 + vertex -492.885 82.3759 101.795 + vertex -497.993 81.4674 91.7814 + endloop + endfacet + facet normal -0.103611 -0.98068 0.165929 + outer loop + vertex -497.414 79.8249 82.4353 + vertex -492.715 81.0831 92.8057 + vertex -497.993 81.4674 91.7814 + endloop + endfacet + facet normal -0.083572 -0.984016 0.157254 + outer loop + vertex -491.998 79.5492 83.5887 + vertex -492.715 81.0831 92.8057 + vertex -497.414 79.8249 82.4353 + endloop + endfacet + facet normal -0.0890874 -0.978806 0.184399 + outer loop + vertex -491.998 79.5492 83.5887 + vertex -497.414 79.8249 82.4353 + vertex -495.719 78.5676 76.5804 + endloop + endfacet + facet normal -0.079478 -0.980535 0.179538 + outer loop + vertex -493.084 78.3043 76.3087 + vertex -491.998 79.5492 83.5887 + vertex -495.719 78.5676 76.5804 + endloop + endfacet + facet normal -0.0768614 -0.976559 0.201062 + outer loop + vertex -494.978 77.4404 71.3887 + vertex -493.084 78.3043 76.3087 + vertex -495.719 78.5676 76.5804 + endloop + endfacet + facet normal -0.0832764 -0.976235 0.200076 + outer loop + vertex -494.978 77.4404 71.3887 + vertex -495.719 78.5676 76.5804 + vertex -497.752 77.545 70.7442 + endloop + endfacet + facet normal -0.0884999 -0.970687 0.22346 + outer loop + vertex -496.892 76.3955 66.0916 + vertex -494.978 77.4404 71.3887 + vertex -497.752 77.545 70.7442 + endloop + endfacet + facet normal -0.0896304 -0.970635 0.223238 + outer loop + vertex -496.892 76.3955 66.0916 + vertex -497.752 77.545 70.7442 + vertex -499.606 76.5076 65.4895 + endloop + endfacet + facet normal -0.0945339 -0.964527 0.246476 + outer loop + vertex -498.685 75.2651 60.9806 + vertex -496.892 76.3955 66.0916 + vertex -499.606 76.5076 65.4895 + endloop + endfacet + facet normal -0.0934207 -0.964574 0.246717 + outer loop + vertex -498.685 75.2651 60.9806 + vertex -499.606 76.5076 65.4895 + vertex -501.181 75.3643 60.4235 + endloop + endfacet + facet normal -0.0989583 -0.956945 0.272882 + outer loop + vertex -500.074 74.0114 56.0803 + vertex -498.685 75.2651 60.9806 + vertex -501.181 75.3643 60.4235 + endloop + endfacet + facet normal -0.0973623 -0.956988 0.273302 + outer loop + vertex -500.074 74.0114 56.0803 + vertex -501.181 75.3643 60.4235 + vertex -502.159 74.0931 55.6237 + endloop + endfacet + facet normal -0.103315 -0.947646 0.302147 + outer loop + vertex -500.753 72.5903 51.3909 + vertex -500.074 74.0114 56.0803 + vertex -502.159 74.0931 55.6237 + endloop + endfacet + facet normal -0.104829 -0.947641 0.301642 + outer loop + vertex -500.753 72.5903 51.3909 + vertex -502.159 74.0931 55.6237 + vertex -502.344 72.7078 51.2072 + endloop + endfacet + facet normal -0.107298 -0.938187 0.329078 + outer loop + vertex -500.71 71.0128 46.9078 + vertex -500.753 72.5903 51.3909 + vertex -502.344 72.7078 51.2072 + endloop + endfacet + facet normal -0.115973 -0.938291 0.325821 + outer loop + vertex -500.71 71.0128 46.9078 + vertex -502.344 72.7078 51.2072 + vertex -501.827 71.2832 47.2889 + endloop + endfacet + facet normal -0.106252 -0.931023 0.349151 + outer loop + vertex -500.71 71.0128 46.9078 + vertex -501.827 71.2832 47.2889 + vertex -500.525 70.0145 44.3021 + endloop + endfacet + facet normal -0.131502 -0.928786 0.346502 + outer loop + vertex -499.885 69.7552 43.85 + vertex -500.71 71.0128 46.9078 + vertex -500.525 70.0145 44.3021 + endloop + endfacet + facet normal -0.108068 -0.920687 0.375042 + outer loop + vertex -499.453 69.1168 42.4071 + vertex -499.885 69.7552 43.85 + vertex -500.525 70.0145 44.3021 + endloop + endfacet + facet normal -0.121714 -0.921871 0.367885 + outer loop + vertex -499.453 69.1168 42.4071 + vertex -500.525 70.0145 44.3021 + vertex -500.066 69.4144 42.9501 + endloop + endfacet + facet normal -0.0835699 -0.910601 0.404749 + outer loop + vertex -499.065 68.7085 41.5687 + vertex -499.453 69.1168 42.4071 + vertex -500.066 69.4144 42.9501 + endloop + endfacet + facet normal -0.0335299 -0.899622 0.43538 + outer loop + vertex -499.065 68.7085 41.5687 + vertex -500.066 69.4144 42.9501 + vertex -499.755 69.0167 42.1523 + endloop + endfacet + facet normal 0.24954 -0.702906 0.666073 + outer loop + vertex -498.424 68.3441 40.9439 + vertex -499.065 68.7085 41.5687 + vertex -499.755 69.0167 42.1523 + endloop + endfacet + facet normal -0.101914 -0.901264 0.421113 + outer loop + vertex -499.065 68.7085 41.5687 + vertex -498.424 68.3441 40.9439 + vertex -498.4 68.5361 41.3606 + endloop + endfacet + facet normal -0.0990517 -0.901591 0.421098 + outer loop + vertex -498.424 68.3441 40.9439 + vertex -497.194 68.2493 41.0302 + vertex -498.4 68.5361 41.3606 + endloop + endfacet + facet normal -0.108702 -0.912192 0.395081 + outer loop + vertex -497.887 68.6086 41.6692 + vertex -498.4 68.5361 41.3606 + vertex -497.194 68.2493 41.0302 + endloop + endfacet + facet normal -0.0980138 -0.909084 0.40492 + outer loop + vertex -497.887 68.6086 41.6692 + vertex -497.194 68.2493 41.0302 + vertex -496.967 68.608 41.8906 + endloop + endfacet + facet normal -0.0953895 -0.91415 0.393994 + outer loop + vertex -496.967 68.608 41.8906 + vertex -498.133 69.1387 42.8395 + vertex -497.887 68.6086 41.6692 + endloop + endfacet + facet normal -0.106632 -0.91396 0.391545 + outer loop + vertex -497.887 68.6086 41.6692 + vertex -498.133 69.1387 42.8395 + vertex -498.881 69.0872 42.5156 + endloop + endfacet + facet normal -0.0994075 -0.921267 0.376013 + outer loop + vertex -498.133 69.1387 42.8395 + vertex -499.3 69.9346 44.4812 + vertex -498.881 69.0872 42.5156 + endloop + endfacet + facet normal -0.118686 -0.920743 0.371681 + outer loop + vertex -498.881 69.0872 42.5156 + vertex -499.3 69.9346 44.4812 + vertex -499.885 69.7552 43.85 + endloop + endfacet + facet normal -0.0935537 -0.920354 0.379732 + outer loop + vertex -498.133 69.1387 42.8395 + vertex -498.312 69.8274 44.4646 + vertex -499.3 69.9346 44.4812 + endloop + endfacet + facet normal -0.0951053 -0.930588 0.353499 + outer loop + vertex -498.312 69.8274 44.4646 + vertex -499.036 71.0116 47.3874 + vertex -499.3 69.9346 44.4812 + endloop + endfacet + facet normal -0.102032 -0.929735 0.353812 + outer loop + vertex -499.036 71.0116 47.3874 + vertex -500.71 71.0128 46.9078 + vertex -499.3 69.9346 44.4812 + endloop + endfacet + facet normal -0.0808307 -0.930587 0.357035 + outer loop + vertex -498.312 69.8274 44.4646 + vertex -497.34 70.0092 45.1588 + vertex -499.036 71.0116 47.3874 + endloop + endfacet + facet normal -0.0891684 -0.931998 0.351324 + outer loop + vertex -496.813 71.0839 48.1433 + vertex -499.036 71.0116 47.3874 + vertex -497.34 70.0092 45.1588 + endloop + endfacet + facet normal -0.0798309 -0.933289 0.350141 + outer loop + vertex -496.028 69.8963 45.1567 + vertex -496.813 71.0839 48.1433 + vertex -497.34 70.0092 45.1588 + endloop + endfacet + facet normal -0.0788834 -0.922786 0.377151 + outer loop + vertex -496.057 69.2254 43.5093 + vertex -496.028 69.8963 45.1567 + vertex -497.34 70.0092 45.1588 + endloop + endfacet + facet normal -0.0791295 -0.922834 0.376982 + outer loop + vertex -496.057 69.2254 43.5093 + vertex -497.34 70.0092 45.1588 + vertex -497.176 69.1902 43.1882 + endloop + endfacet + facet normal -0.0845631 -0.914767 0.395031 + outer loop + vertex -496.086 68.7213 42.3357 + vertex -496.057 69.2254 43.5093 + vertex -497.176 69.1902 43.1882 + endloop + endfacet + facet normal -0.082911 -0.914151 0.396805 + outer loop + vertex -496.086 68.7213 42.3357 + vertex -497.176 69.1902 43.1882 + vertex -496.967 68.608 41.8906 + endloop + endfacet + facet normal -0.0847626 -0.912559 0.400064 + outer loop + vertex -496.086 68.7213 42.3357 + vertex -496.967 68.608 41.8906 + vertex -495.546 68.3852 41.6835 + endloop + endfacet + facet normal -0.0777076 -0.910971 0.405085 + outer loop + vertex -496.086 68.7213 42.3357 + vertex -495.546 68.3852 41.6835 + vertex -494.85 68.7091 42.5452 + endloop + endfacet + facet normal -0.0680254 -0.914586 0.398629 + outer loop + vertex -495.546 68.3852 41.6835 + vertex -493.289 68.5018 42.3361 + vertex -494.85 68.7091 42.5452 + endloop + endfacet + facet normal -0.0683523 -0.91531 0.396907 + outer loop + vertex -493.585 68.8203 43.0197 + vertex -494.85 68.7091 42.5452 + vertex -493.289 68.5018 42.3361 + endloop + endfacet + facet normal -0.0628192 -0.914774 0.399051 + outer loop + vertex -493.585 68.8203 43.0197 + vertex -493.289 68.5018 42.3361 + vertex -491.981 68.862 43.3678 + endloop + endfacet + facet normal -0.0600844 -0.920084 0.387086 + outer loop + vertex -491.981 68.862 43.3678 + vertex -493.204 69.3646 44.3726 + vertex -493.585 68.8203 43.0197 + endloop + endfacet + facet normal -0.0705566 -0.918385 0.389348 + outer loop + vertex -493.585 68.8203 43.0197 + vertex -493.204 69.3646 44.3726 + vertex -494.769 69.2692 43.8639 + endloop + endfacet + facet normal -0.0641121 -0.926403 0.371035 + outer loop + vertex -493.204 69.3646 44.3726 + vertex -494.772 70.1479 46.0575 + vertex -494.769 69.2692 43.8639 + endloop + endfacet + facet normal -0.0803431 -0.92532 0.370579 + outer loop + vertex -494.769 69.2692 43.8639 + vertex -494.772 70.1479 46.0575 + vertex -496.028 69.8963 45.1567 + endloop + endfacet + facet normal -0.0681167 -0.927415 0.36778 + outer loop + vertex -493.204 69.3646 44.3726 + vertex -492.77 70.2727 46.7428 + vertex -494.772 70.1479 46.0575 + endloop + endfacet + facet normal -0.0597477 -0.936689 0.345028 + outer loop + vertex -492.77 70.2727 46.7428 + vertex -494.537 71.3543 49.3733 + vertex -494.772 70.1479 46.0575 + endloop + endfacet + facet normal -0.0756557 -0.935308 0.345653 + outer loop + vertex -494.537 71.3543 49.3733 + vertex -496.813 71.0839 48.1433 + vertex -494.772 70.1479 46.0575 + endloop + endfacet + facet normal -0.062214 -0.944428 0.322778 + outer loop + vertex -494.537 71.3543 49.3733 + vertex -496.239 72.6296 52.7766 + vertex -496.813 71.0839 48.1433 + endloop + endfacet + facet normal -0.0854365 -0.94191 0.324817 + outer loop + vertex -496.813 71.0839 48.1433 + vertex -496.239 72.6296 52.7766 + vertex -498.643 72.5818 52.0055 + endloop + endfacet + facet normal -0.0761314 -0.952015 0.29643 + outer loop + vertex -496.239 72.6296 52.7766 + vertex -497.619 73.9779 56.7523 + vertex -498.643 72.5818 52.0055 + endloop + endfacet + facet normal -0.0949813 -0.949294 0.299698 + outer loop + vertex -498.643 72.5818 52.0055 + vertex -497.619 73.9779 56.7523 + vertex -500.074 74.0114 56.0803 + endloop + endfacet + facet normal -0.0795954 -0.952097 0.295256 + outer loop + vertex -496.239 72.6296 52.7766 + vertex -495.021 73.9773 57.4508 + vertex -497.619 73.9779 56.7523 + endloop + endfacet + facet normal -0.071525 -0.961527 0.265237 + outer loop + vertex -495.021 73.9773 57.4508 + vertex -496.031 75.2134 61.6595 + vertex -497.619 73.9779 56.7523 + endloop + endfacet + facet normal -0.0876994 -0.958912 0.26981 + outer loop + vertex -497.619 73.9779 56.7523 + vertex -496.031 75.2134 61.6595 + vertex -498.685 75.2651 60.9806 + endloop + endfacet + facet normal -0.0709358 -0.961531 0.265379 + outer loop + vertex -495.021 73.9773 57.4508 + vertex -493.36 75.2054 62.3446 + vertex -496.031 75.2134 61.6595 + endloop + endfacet + facet normal -0.0637922 -0.969308 0.237429 + outer loop + vertex -493.36 75.2054 62.3446 + vertex -494.176 76.344 66.7734 + vertex -496.031 75.2134 61.6595 + endloop + endfacet + facet normal -0.0792008 -0.966916 0.24249 + outer loop + vertex -496.031 75.2134 61.6595 + vertex -494.176 76.344 66.7734 + vertex -496.892 76.3955 66.0916 + endloop + endfacet + facet normal -0.0605271 -0.969366 0.238046 + outer loop + vertex -493.36 75.2054 62.3446 + vertex -491.519 76.3425 67.443 + vertex -494.176 76.344 66.7734 + endloop + endfacet + facet normal -0.054304 -0.975467 0.213342 + outer loop + vertex -491.519 76.3425 67.443 + vertex -492.274 77.393 72.0543 + vertex -494.176 76.344 66.7734 + endloop + endfacet + facet normal -0.0709051 -0.973175 0.218867 + outer loop + vertex -494.176 76.344 66.7734 + vertex -492.274 77.393 72.0543 + vertex -494.978 77.4404 71.3887 + endloop + endfacet + facet normal -0.0520745 -0.975507 0.213716 + outer loop + vertex -491.519 76.3425 67.443 + vertex -489.648 77.3914 72.6863 + vertex -492.274 77.393 72.0543 + endloop + endfacet + facet normal -0.0464125 -0.980651 0.190183 + outer loop + vertex -489.648 77.3914 72.6863 + vertex -490.28 78.4229 77.8512 + vertex -492.274 77.393 72.0543 + endloop + endfacet + facet normal -0.0668655 -0.978166 0.196775 + outer loop + vertex -492.274 77.393 72.0543 + vertex -490.28 78.4229 77.8512 + vertex -493.084 78.3043 76.3087 + endloop + endfacet + facet normal -0.0407884 -0.980763 0.190894 + outer loop + vertex -489.648 77.3914 72.6863 + vertex -487.781 78.259 77.543 + vertex -490.28 78.4229 77.8512 + endloop + endfacet + facet normal -0.0438679 -0.984798 0.168071 + outer loop + vertex -487.781 78.259 77.543 + vertex -486.585 79.4486 84.8257 + vertex -490.28 78.4229 77.8512 + endloop + endfacet + facet normal -0.0583602 -0.982757 0.175449 + outer loop + vertex -486.585 79.4486 84.8257 + vertex -491.998 79.5492 83.5887 + vertex -490.28 78.4229 77.8512 + endloop + endfacet + facet normal -0.0518495 -0.987844 0.146549 + outer loop + vertex -486.585 79.4486 84.8257 + vertex -487.16 80.835 93.9671 + vertex -491.998 79.5492 83.5887 + endloop + endfacet + facet normal -0.0463248 -0.988062 0.146929 + outer loop + vertex -486.585 79.4486 84.8257 + vertex -481.701 80.7605 95.1874 + vertex -487.16 80.835 93.9671 + endloop + endfacet + facet normal -0.0395846 -0.9924 0.116511 + outer loop + vertex -481.701 80.7605 95.1874 + vertex -481.598 81.7908 103.999 + vertex -487.16 80.835 93.9671 + endloop + endfacet + facet normal -0.0635185 -0.989542 0.129509 + outer loop + vertex -487.16 80.835 93.9671 + vertex -481.598 81.7908 103.999 + vertex -487.234 82.0115 102.92 + endloop + endfacet + facet normal -0.0579301 -0.993347 0.0995241 + outer loop + vertex -481.598 81.7908 103.999 + vertex -481.054 82.6331 112.723 + vertex -487.234 82.0115 102.92 + endloop + endfacet + facet normal -0.0475919 -0.993955 0.0989379 + outer loop + vertex -481.598 81.7908 103.999 + vertex -475.473 82.4667 113.735 + vertex -481.054 82.6331 112.723 + endloop + endfacet + facet normal -0.0424625 -0.996627 0.0702182 + outer loop + vertex -475.473 82.4667 113.735 + vertex -474.517 83.0304 122.313 + vertex -481.054 82.6331 112.723 + endloop + endfacet + facet normal -0.0601809 -0.994796 0.0822183 + outer loop + vertex -481.054 82.6331 112.723 + vertex -474.517 83.0304 122.313 + vertex -480.214 83.2969 121.368 + endloop + endfacet + facet normal -0.0719669 -0.993923 0.0832964 + outer loop + vertex -481.054 82.6331 112.723 + vertex -480.214 83.2969 121.368 + vertex -486.828 82.9652 111.696 + endloop + endfacet + facet normal -0.0560284 -0.996823 0.0566138 + outer loop + vertex -474.517 83.0304 122.313 + vertex -473.43 83.4561 130.885 + vertex -480.214 83.2969 121.368 + endloop + endfacet + facet normal -0.0713221 -0.995168 0.0674871 + outer loop + vertex -480.214 83.2969 121.368 + vertex -473.43 83.4561 130.885 + vertex -479.238 83.8136 130.019 + endloop + endfacet + facet normal -0.0837361 -0.994108 0.0688234 + outer loop + vertex -480.214 83.2969 121.368 + vertex -479.238 83.8136 130.019 + vertex -486.104 83.7261 120.402 + endloop + endfacet + facet normal -0.0679401 -0.996711 0.0441847 + outer loop + vertex -473.43 83.4561 130.885 + vertex -472.289 83.76 139.494 + vertex -479.238 83.8136 130.019 + endloop + endfacet + facet normal -0.0814469 -0.995208 0.0540986 + outer loop + vertex -479.238 83.8136 130.019 + vertex -472.289 83.76 139.494 + vertex -478.22 84.2036 138.727 + endloop + endfacet + facet normal -0.094518 -0.993971 0.0555724 + outer loop + vertex -479.238 83.8136 130.019 + vertex -478.22 84.2036 138.727 + vertex -485.25 84.3365 129.148 + endloop + endfacet + facet normal -0.0786805 -0.996385 0.032051 + outer loop + vertex -472.289 83.76 139.494 + vertex -471.107 83.9452 148.155 + vertex -478.22 84.2036 138.727 + endloop + endfacet + facet normal -0.0899895 -0.995114 0.0406175 + outer loop + vertex -478.22 84.2036 138.727 + vertex -471.107 83.9452 148.155 + vertex -477.174 84.4665 147.486 + endloop + endfacet + facet normal -0.103857 -0.993695 0.042231 + outer loop + vertex -478.22 84.2036 138.727 + vertex -477.174 84.4665 147.486 + vertex -484.357 84.8125 137.959 + endloop + endfacet + facet normal -0.0877124 -0.995959 0.0193002 + outer loop + vertex -471.107 83.9452 148.155 + vertex -469.87 84.0046 156.839 + vertex -477.174 84.4665 147.486 + endloop + endfacet + facet normal -0.0966854 -0.994966 0.0263559 + outer loop + vertex -477.174 84.4665 147.486 + vertex -469.87 84.0046 156.839 + vertex -476.083 84.5929 156.257 + endloop + endfacet + facet normal -0.111385 -0.993378 0.0281611 + outer loop + vertex -477.174 84.4665 147.486 + vertex -476.083 84.5929 156.257 + vertex -483.443 85.1502 146.806 + endloop + endfacet + facet normal -0.0948092 -0.995479 0.00580576 + outer loop + vertex -469.87 84.0046 156.839 + vertex -468.573 83.9316 165.508 + vertex -476.083 84.5929 156.257 + endloop + endfacet + facet normal -0.101784 -0.99474 0.011521 + outer loop + vertex -476.083 84.5929 156.257 + vertex -468.573 83.9316 165.508 + vertex -474.944 84.5777 165.009 + endloop + endfacet + facet normal -0.117311 -0.993003 0.0135448 + outer loop + vertex -476.083 84.5929 156.257 + vertex -474.944 84.5777 165.009 + vertex -482.495 85.3421 155.652 + endloop + endfacet + facet normal -0.100243 -0.994928 -0.00839722 + outer loop + vertex -468.573 83.9316 165.508 + vertex -467.225 83.723 174.131 + vertex -474.944 84.5777 165.009 + endloop + endfacet + facet normal -0.105331 -0.994429 -0.00404539 + outer loop + vertex -474.944 84.5777 165.009 + vertex -467.225 83.723 174.131 + vertex -473.763 84.4172 173.715 + endloop + endfacet + facet normal -0.121444 -0.992597 -0.00182532 + outer loop + vertex -474.944 84.5777 165.009 + vertex -473.763 84.4172 173.715 + vertex -481.501 85.381 164.475 + endloop + endfacet + facet normal -0.10408 -0.994292 -0.0234791 + outer loop + vertex -467.225 83.723 174.131 + vertex -465.839 83.3759 182.69 + vertex -473.763 84.4172 173.715 + endloop + endfacet + facet normal -0.107837 -0.993965 -0.0201242 + outer loop + vertex -473.763 84.4172 173.715 + vertex -465.839 83.3759 182.69 + vertex -472.552 84.1106 182.372 + endloop + endfacet + facet normal -0.124589 -0.99205 -0.0177149 + outer loop + vertex -473.763 84.4172 173.715 + vertex -472.552 84.1106 182.372 + vertex -480.485 85.2695 173.263 + endloop + endfacet + facet normal -0.106876 -0.993493 -0.0393486 + outer loop + vertex -465.839 83.3759 182.69 + vertex -464.425 82.8871 191.19 + vertex -472.552 84.1106 182.372 + endloop + endfacet + facet normal -0.109121 -0.99333 -0.037256 + outer loop + vertex -472.552 84.1106 182.372 + vertex -464.425 82.8871 191.19 + vertex -471.319 83.6524 190.976 + endloop + endfacet + facet normal -0.126338 -0.991381 -0.0346834 + outer loop + vertex -472.552 84.1106 182.372 + vertex -471.319 83.6524 190.976 + vertex -479.44 85.001 182.009 + endloop + endfacet + facet normal -0.108438 -0.992505 -0.0563527 + outer loop + vertex -464.425 82.8871 191.19 + vertex -462.989 82.2507 199.634 + vertex -471.319 83.6524 190.976 + endloop + endfacet + facet normal -0.109504 -0.992446 -0.0553174 + outer loop + vertex -471.319 83.6524 190.976 + vertex -462.989 82.2507 199.634 + vertex -470.069 83.0371 199.541 + endloop + endfacet + facet normal -0.127274 -0.990473 -0.0525835 + outer loop + vertex -471.319 83.6524 190.976 + vertex -470.069 83.0371 199.541 + vertex -478.38 84.5732 190.721 + endloop + endfacet + facet normal -0.109124 -0.991248 -0.0742987 + outer loop + vertex -462.989 82.2507 199.634 + vertex -461.538 81.4614 208.032 + vertex -470.069 83.0371 199.541 + endloop + endfacet + facet normal -0.109023 -0.991251 -0.0744009 + outer loop + vertex -470.069 83.0371 199.541 + vertex -461.538 81.4614 208.032 + vertex -468.815 82.2583 208.079 + endloop + endfacet + facet normal -0.127517 -0.989256 -0.0715013 + outer loop + vertex -470.069 83.0371 199.541 + vertex -468.815 82.2583 208.079 + vertex -477.317 83.9805 199.415 + endloop + endfacet + facet normal -0.108969 -0.989675 -0.0931064 + outer loop + vertex -461.538 81.4614 208.032 + vertex -460.08 80.5148 216.388 + vertex -468.815 82.2583 208.079 + endloop + endfacet + facet normal -0.108127 -0.989684 -0.0939936 + outer loop + vertex -468.815 82.2583 208.079 + vertex -460.08 80.5148 216.388 + vertex -467.56 81.3134 216.584 + endloop + endfacet + facet normal -0.126842 -0.987738 -0.0910176 + outer loop + vertex -468.815 82.2583 208.079 + vertex -467.56 81.3134 216.584 + vertex -476.248 83.2119 208.089 + endloop + endfacet + facet normal -0.10839 -0.987824 -0.111604 + outer loop + vertex -460.08 80.5148 216.388 + vertex -458.609 79.4172 224.674 + vertex -467.56 81.3134 216.584 + endloop + endfacet + facet normal -0.107071 -0.987802 -0.113058 + outer loop + vertex -467.56 81.3134 216.584 + vertex -458.609 79.4172 224.674 + vertex -466.289 80.211 225.013 + endloop + endfacet + facet normal -0.125828 -0.985936 -0.109984 + outer loop + vertex -467.56 81.3134 216.584 + vertex -466.289 80.211 225.013 + vertex -475.187 82.2703 216.732 + endloop + endfacet + facet normal -0.107562 -0.98581 -0.128879 + outer loop + vertex -458.609 79.4172 224.674 + vertex -457.092 78.1854 232.831 + vertex -466.289 80.211 225.013 + endloop + endfacet + facet normal -0.10612 -0.985745 -0.130559 + outer loop + vertex -466.289 80.211 225.013 + vertex -457.092 78.1854 232.831 + vertex -464.963 78.9697 233.307 + endloop + endfacet + facet normal -0.124716 -0.983989 -0.127325 + outer loop + vertex -466.289 80.211 225.013 + vertex -464.963 78.9697 233.307 + vertex -474.105 81.1653 225.294 + endloop + endfacet + facet normal -0.106762 -0.983734 -0.144465 + outer loop + vertex -457.092 78.1854 232.831 + vertex -455.473 76.8361 240.822 + vertex -464.963 78.9697 233.307 + endloop + endfacet + facet normal -0.105399 -0.983631 -0.146157 + outer loop + vertex -464.963 78.9697 233.307 + vertex -455.473 76.8361 240.822 + vertex -463.543 77.6043 241.472 + endloop + endfacet + facet normal -0.123621 -0.982013 -0.142716 + outer loop + vertex -464.963 78.9697 233.307 + vertex -463.543 77.6043 241.472 + vertex -472.966 79.9164 233.725 + endloop + endfacet + facet normal -0.106187 -0.98167 -0.158265 + outer loop + vertex -455.473 76.8361 240.822 + vertex -453.717 75.3705 248.734 + vertex -463.543 77.6043 241.472 + endloop + endfacet + facet normal -0.105282 -0.981574 -0.15946 + outer loop + vertex -463.543 77.6043 241.472 + vertex -453.717 75.3705 248.734 + vertex -462.047 76.1118 249.671 + endloop + endfacet + facet normal -0.0850692 -0.982921 -0.163184 + outer loop + vertex -455.473 76.8361 240.822 + vertex -445.583 74.8083 247.881 + vertex -453.717 75.3705 248.734 + endloop + endfacet + facet normal -0.0861476 -0.98082 -0.174847 + outer loop + vertex -445.583 74.8083 247.881 + vertex -443.411 73.2596 255.498 + vertex -453.717 75.3705 248.734 + endloop + endfacet + facet normal -0.0861436 -0.980819 -0.174853 + outer loop + vertex -453.717 75.3705 248.734 + vertex -443.411 73.2596 255.498 + vertex -451.871 73.7679 256.815 + endloop + endfacet + facet normal -0.0589499 -0.981396 -0.182722 + outer loop + vertex -445.583 74.8083 247.881 + vertex -435.092 72.9703 254.368 + vertex -443.411 73.2596 255.498 + endloop + endfacet + facet normal -0.0605568 -0.978894 -0.19519 + outer loop + vertex -435.092 72.9703 254.368 + vertex -432.442 71.3738 261.552 + vertex -443.411 73.2596 255.498 + endloop + endfacet + facet normal -0.0618379 -0.979252 -0.192981 + outer loop + vertex -443.411 73.2596 255.498 + vertex -432.442 71.3738 261.552 + vertex -441.172 71.5978 263.213 + endloop + endfacet + facet normal -0.0234531 -0.977717 -0.208614 + outer loop + vertex -435.092 72.9703 254.368 + vertex -423.824 71.5001 259.992 + vertex -432.442 71.3738 261.552 + endloop + endfacet + facet normal -0.0259178 -0.974707 -0.221981 + outer loop + vertex -423.824 71.5001 259.992 + vertex -420.754 69.9211 266.566 + vertex -432.442 71.3738 261.552 + endloop + endfacet + facet normal -0.0276365 -0.975511 -0.218207 + outer loop + vertex -432.442 71.3738 261.552 + vertex -420.754 69.9211 266.566 + vertex -429.76 69.7326 268.55 + endloop + endfacet + facet normal 0.0175237 -0.970315 -0.24121 + outer loop + vertex -423.824 71.5001 259.992 + vertex -411.833 70.5975 264.494 + vertex -420.754 69.9211 266.566 + endloop + endfacet + facet normal 0.0138546 -0.96663 -0.2558 + outer loop + vertex -411.833 70.5975 264.494 + vertex -408.581 69.1096 270.292 + vertex -420.754 69.9211 266.566 + endloop + endfacet + facet normal 0.012832 -0.967474 -0.252643 + outer loop + vertex -420.754 69.9211 266.566 + vertex -408.581 69.1096 270.292 + vertex -417.804 68.3652 272.675 + endloop + endfacet + facet normal 0.0180418 -0.969978 -0.242523 + outer loop + vertex -415.015 72.1161 258.183 + vertex -411.833 70.5975 264.494 + vertex -423.824 71.5001 259.992 + endloop + endfacet + facet normal 0.0212666 -0.973431 -0.227992 + outer loop + vertex -426.658 73.0454 253.129 + vertex -415.015 72.1161 258.183 + vertex -423.824 71.5001 259.992 + endloop + endfacet + facet normal 0.0202589 -0.97397 -0.22577 + outer loop + vertex -417.938 73.5891 251.567 + vertex -415.015 72.1161 258.183 + vertex -426.658 73.0454 253.129 + endloop + endfacet + facet normal 0.0233022 -0.977426 -0.20999 + outer loop + vertex -429.215 74.4998 246.076 + vertex -417.938 73.5891 251.567 + vertex -426.658 73.0454 253.129 + endloop + endfacet + facet normal -0.0209471 -0.980656 -0.194614 + outer loop + vertex -429.215 74.4998 246.076 + vertex -426.658 73.0454 253.129 + vertex -437.487 74.48 247.066 + endloop + endfacet + facet normal -0.0191998 -0.983467 -0.180069 + outer loop + vertex -439.648 75.8883 239.605 + vertex -429.215 74.4998 246.076 + vertex -437.487 74.48 247.066 + endloop + endfacet + facet normal -0.0575399 -0.983926 -0.169051 + outer loop + vertex -439.648 75.8883 239.605 + vertex -437.487 74.48 247.066 + vertex -447.56 76.2459 240.217 + endloop + endfacet + facet normal -0.0565468 -0.986326 -0.154802 + outer loop + vertex -449.37 77.5784 232.388 + vertex -439.648 75.8883 239.605 + vertex -447.56 76.2459 240.217 + endloop + endfacet + facet normal -0.0859308 -0.985273 -0.147829 + outer loop + vertex -449.37 77.5784 232.388 + vertex -447.56 76.2459 240.217 + vertex -457.092 78.1854 232.831 + endloop + endfacet + facet normal -0.0571228 -0.986411 -0.154046 + outer loop + vertex -441.655 77.2006 231.946 + vertex -439.648 75.8883 239.605 + vertex -449.37 77.5784 232.388 + endloop + endfacet + facet normal -0.0563558 -0.988735 -0.138661 + outer loop + vertex -451.089 78.7987 224.385 + vertex -441.655 77.2006 231.946 + vertex -449.37 77.5784 232.388 + endloop + endfacet + facet normal -0.0863083 -0.98748 -0.132035 + outer loop + vertex -451.089 78.7987 224.385 + vertex -449.37 77.5784 232.388 + vertex -458.609 79.4172 224.674 + endloop + endfacet + facet normal -0.0565971 -0.988763 -0.138366 + outer loop + vertex -443.589 78.4072 224.115 + vertex -441.655 77.2006 231.946 + vertex -451.089 78.7987 224.385 + endloop + endfacet + facet normal -0.0561043 -0.99101 -0.121457 + outer loop + vertex -452.772 79.8896 216.261 + vertex -443.589 78.4072 224.115 + vertex -451.089 78.7987 224.385 + endloop + endfacet + facet normal -0.0866596 -0.989586 -0.114937 + outer loop + vertex -452.772 79.8896 216.261 + vertex -451.089 78.7987 224.385 + vertex -460.08 80.5148 216.388 + endloop + endfacet + facet normal -0.0558553 -0.990989 -0.121744 + outer loop + vertex -445.49 79.492 216.157 + vertex -443.589 78.4072 224.115 + vertex -452.772 79.8896 216.261 + endloop + endfacet + facet normal -0.0557078 -0.993063 -0.10355 + outer loop + vertex -454.437 80.8386 208.055 + vertex -445.49 79.492 216.157 + vertex -452.772 79.8896 216.261 + endloop + endfacet + facet normal -0.0866425 -0.991497 -0.0970939 + outer loop + vertex -454.437 80.8386 208.055 + vertex -452.772 79.8896 216.261 + vertex -461.538 81.4614 208.032 + endloop + endfacet + facet normal -0.0550654 -0.993025 -0.104253 + outer loop + vertex -447.37 80.4411 208.109 + vertex -445.49 79.492 216.157 + vertex -454.437 80.8386 208.055 + endloop + endfacet + facet normal -0.0553091 -0.994804 -0.0854721 + outer loop + vertex -456.086 81.6405 199.79 + vertex -447.37 80.4411 208.109 + vertex -454.437 80.8386 208.055 + endloop + endfacet + facet normal -0.0859997 -0.993143 -0.0791874 + outer loop + vertex -456.086 81.6405 199.79 + vertex -454.437 80.8386 208.055 + vertex -462.989 82.2507 199.634 + endloop + endfacet + facet normal -0.0533484 -0.994734 -0.0875161 + outer loop + vertex -449.224 81.2555 199.982 + vertex -447.37 80.4411 208.109 + vertex -456.086 81.6405 199.79 + endloop + endfacet + facet normal -0.0539709 -0.996208 -0.0682422 + outer loop + vertex -457.714 82.2989 191.466 + vertex -449.224 81.2555 199.982 + vertex -456.086 81.6405 199.79 + endloop + endfacet + facet normal -0.0845966 -0.994477 -0.0621154 + outer loop + vertex -457.714 82.2989 191.466 + vertex -456.086 81.6405 199.79 + vertex -464.425 82.8871 191.19 + endloop + endfacet + facet normal -0.0501636 -0.99614 -0.0720296 + outer loop + vertex -451.044 81.9405 191.777 + vertex -449.224 81.2555 199.982 + vertex -457.714 82.2989 191.466 + endloop + endfacet + facet normal -0.0511498 -0.997324 -0.0522403 + outer loop + vertex -459.313 82.8204 183.077 + vertex -451.044 81.9405 191.777 + vertex -457.714 82.2989 191.466 + endloop + endfacet + facet normal -0.0819977 -0.995559 -0.0462493 + outer loop + vertex -459.313 82.8204 183.077 + vertex -457.714 82.2989 191.466 + vertex -465.839 83.3759 182.69 + endloop + endfacet + facet normal -0.0463436 -0.997309 -0.0568071 + outer loop + vertex -452.837 82.4951 183.504 + vertex -451.044 81.9405 191.777 + vertex -459.313 82.8204 183.077 + endloop + endfacet + facet normal -0.0476909 -0.998175 -0.0370477 + outer loop + vertex -460.878 83.2091 174.617 + vertex -452.837 82.4951 183.504 + vertex -459.313 82.8204 183.077 + endloop + endfacet + facet normal -0.0782818 -0.99644 -0.0313082 + outer loop + vertex -460.878 83.2091 174.617 + vertex -459.313 82.8204 183.077 + vertex -467.225 83.723 174.131 + endloop + endfacet + facet normal -0.0410772 -0.998229 -0.0430367 + outer loop + vertex -454.589 82.9272 175.152 + vertex -452.837 82.4951 183.504 + vertex -460.878 83.2091 174.617 + endloop + endfacet + facet normal -0.0428209 -0.998822 -0.0228378 + outer loop + vertex -462.397 83.4692 166.089 + vertex -454.589 82.9272 175.152 + vertex -460.878 83.2091 174.617 + endloop + endfacet + facet normal -0.0730185 -0.997179 -0.0174095 + outer loop + vertex -462.397 83.4692 166.089 + vertex -460.878 83.2091 174.617 + vertex -468.573 83.9316 165.508 + endloop + endfacet + facet normal -0.0345393 -0.998954 -0.0299811 + outer loop + vertex -456.29 83.2389 166.728 + vertex -454.589 82.9272 175.152 + vertex -462.397 83.4692 166.089 + endloop + endfacet + facet normal -0.0367188 -0.999283 -0.00925599 + outer loop + vertex -463.858 83.6023 157.513 + vertex -456.29 83.2389 166.728 + vertex -462.397 83.4692 166.089 + endloop + endfacet + facet normal -0.0662859 -0.997792 -0.00419725 + outer loop + vertex -463.858 83.6023 157.513 + vertex -462.397 83.4692 166.089 + vertex -469.87 84.0046 156.839 + endloop + endfacet + facet normal -0.0259093 -0.9995 -0.0181426 + outer loop + vertex -457.92 83.435 158.249 + vertex -456.29 83.2389 166.728 + vertex -463.858 83.6023 157.513 + endloop + endfacet + facet normal -0.0285893 -0.999585 0.00346508 + outer loop + vertex -465.248 83.6123 148.923 + vertex -457.92 83.435 158.249 + vertex -463.858 83.6023 157.513 + endloop + endfacet + facet normal -0.0577959 -0.998295 0.00819376 + outer loop + vertex -465.248 83.6123 148.923 + vertex -463.858 83.6023 157.513 + vertex -471.107 83.9452 148.155 + endloop + endfacet + facet normal -0.0152757 -0.999859 -0.00700292 + outer loop + vertex -459.466 83.5182 149.755 + vertex -457.92 83.435 158.249 + vertex -465.248 83.6123 148.923 + endloop + endfacet + facet normal -0.0184753 -0.999713 0.0152572 + outer loop + vertex -466.567 83.506 140.359 + vertex -459.466 83.5182 149.755 + vertex -465.248 83.6123 148.923 + endloop + endfacet + facet normal -0.0473045 -0.998687 0.0196839 + outer loop + vertex -466.567 83.506 140.359 + vertex -465.248 83.6123 148.923 + vertex -472.289 83.76 139.494 + endloop + endfacet + facet normal -0.00283243 -0.99999 0.00343629 + outer loop + vertex -460.925 83.4932 141.279 + vertex -459.466 83.5182 149.755 + vertex -466.567 83.506 140.359 + endloop + endfacet + facet normal -0.00661665 -0.999623 0.0266286 + outer loop + vertex -467.826 83.2872 131.834 + vertex -460.925 83.4932 141.279 + vertex -466.567 83.506 140.359 + endloop + endfacet + facet normal -0.0353261 -0.9989 0.0308508 + outer loop + vertex -467.826 83.2872 131.834 + vertex -466.567 83.506 140.359 + vertex -473.43 83.4561 130.885 + endloop + endfacet + facet normal 0.010722 -0.999845 0.0139649 + outer loop + vertex -462.305 83.3604 132.835 + vertex -460.925 83.4932 141.279 + vertex -467.826 83.2872 131.834 + endloop + endfacet + facet normal 0.00629144 -0.999244 0.0383569 + outer loop + vertex -469.016 82.9534 123.333 + vertex -462.305 83.3604 132.835 + vertex -467.826 83.2872 131.834 + endloop + endfacet + facet normal -0.0218034 -0.998868 0.0422726 + outer loop + vertex -469.016 82.9534 123.333 + vertex -467.826 83.2872 131.834 + vertex -474.517 83.0304 122.313 + endloop + endfacet + facet normal 0.0260457 -0.999363 0.0244109 + outer loop + vertex -463.603 83.121 124.418 + vertex -462.305 83.3604 132.835 + vertex -469.016 82.9534 123.333 + endloop + endfacet + facet normal 0.020593 -0.998462 0.0514664 + outer loop + vertex -470.081 82.4944 114.853 + vertex -463.603 83.121 124.418 + vertex -469.016 82.9534 123.333 + endloop + endfacet + facet normal -0.00624913 -0.998476 0.0548385 + outer loop + vertex -470.081 82.4944 114.853 + vertex -469.016 82.9534 123.333 + vertex -475.473 82.4667 113.735 + endloop + endfacet + facet normal -0.012363 -0.996367 0.0842629 + outer loop + vertex -476.163 81.7492 105.149 + vertex -470.081 82.4944 114.853 + vertex -475.473 82.4667 113.735 + endloop + endfacet + facet normal 0.0127554 -0.997562 0.0686116 + outer loop + vertex -470.908 81.9068 106.465 + vertex -470.081 82.4944 114.853 + vertex -476.163 81.7492 105.149 + endloop + endfacet + facet normal 0.0047226 -0.994937 0.100385 + outer loop + vertex -476.43 80.8974 96.7196 + vertex -470.908 81.9068 106.465 + vertex -476.163 81.7492 105.149 + endloop + endfacet + facet normal -0.00341106 -0.994917 0.100641 + outer loop + vertex -476.43 80.8974 96.7196 + vertex -476.163 81.7492 105.149 + vertex -481.701 80.7605 95.1874 + endloop + endfacet + facet normal -0.0127758 -0.991099 0.132515 + outer loop + vertex -481.286 79.5791 86.3921 + vertex -476.43 80.8974 96.7196 + vertex -481.701 80.7605 95.1874 + endloop + endfacet + facet normal 0.0257299 -0.993071 0.114663 + outer loop + vertex -476.11 80.023 89.0746 + vertex -476.43 80.8974 96.7196 + vertex -481.286 79.5791 86.3921 + endloop + endfacet + facet normal 0.00961996 -0.989366 0.145132 + outer loop + vertex -476.11 80.023 89.0746 + vertex -481.286 79.5791 86.3921 + vertex -479.488 78.8275 81.1491 + endloop + endfacet + facet normal 0.04337 -0.990445 0.13091 + outer loop + vertex -475.602 79.1167 82.0493 + vertex -476.11 80.023 89.0746 + vertex -479.488 78.8275 81.1491 + endloop + endfacet + facet normal 0.0358592 -0.986146 0.161955 + outer loop + vertex -478.776 77.9844 75.8577 + vertex -475.602 79.1167 82.0493 + vertex -479.488 78.8275 81.1491 + endloop + endfacet + facet normal 0.0336451 -0.98627 0.161677 + outer loop + vertex -478.776 77.9844 75.8577 + vertex -479.488 78.8275 81.1491 + vertex -481.774 77.7324 74.9442 + endloop + endfacet + facet normal 0.0244664 -0.981391 0.190453 + outer loop + vertex -481.057 76.8882 70.502 + vertex -478.776 77.9844 75.8577 + vertex -481.774 77.7324 74.9442 + endloop + endfacet + facet normal 0.0225918 -0.981491 0.190169 + outer loop + vertex -481.057 76.8882 70.502 + vertex -481.774 77.7324 74.9442 + vertex -483.741 76.6589 69.6376 + endloop + endfacet + facet normal 0.0130795 -0.975818 0.218195 + outer loop + vertex -482.907 75.7346 65.4538 + vertex -481.057 76.8882 70.502 + vertex -483.741 76.6589 69.6376 + endloop + endfacet + facet normal 0.0106999 -0.975946 0.217749 + outer loop + vertex -482.907 75.7346 65.4538 + vertex -483.741 76.6589 69.6376 + vertex -485.507 75.5088 64.5697 + endloop + endfacet + facet normal -0.00035358 -0.968659 0.248394 + outer loop + vertex -484.457 74.4812 60.5639 + vertex -482.907 75.7346 65.4538 + vertex -485.507 75.5088 64.5697 + endloop + endfacet + facet normal -0.00125325 -0.968715 0.248172 + outer loop + vertex -484.457 74.4812 60.5639 + vertex -485.507 75.5088 64.5697 + vertex -487.061 74.2587 59.6819 + endloop + endfacet + facet normal -0.0124403 -0.960195 0.279055 + outer loop + vertex -485.704 73.1421 55.9005 + vertex -484.457 74.4812 60.5639 + vertex -487.061 74.2587 59.6819 + endloop + endfacet + facet normal -0.0120069 -0.960158 0.2792 + outer loop + vertex -485.704 73.1421 55.9005 + vertex -487.061 74.2587 59.6819 + vertex -488.357 72.9263 55.0442 + endloop + endfacet + facet normal -0.0224929 -0.950696 0.309308 + outer loop + vertex -486.711 71.7905 51.6729 + vertex -485.704 73.1421 55.9005 + vertex -488.357 72.9263 55.0442 + endloop + endfacet + facet normal -0.0227138 -0.950723 0.309209 + outer loop + vertex -486.711 71.7905 51.6729 + vertex -488.357 72.9263 55.0442 + vertex -489.427 71.5864 50.8459 + endloop + endfacet + facet normal -0.0322781 -0.940553 0.338111 + outer loop + vertex -487.728 70.5277 48.063 + vertex -486.711 71.7905 51.6729 + vertex -489.427 71.5864 50.8459 + endloop + endfacet + facet normal -0.0334704 -0.940746 0.337457 + outer loop + vertex -487.728 70.5277 48.063 + vertex -489.427 71.5864 50.8459 + vertex -490.395 70.3616 47.3355 + endloop + endfacet + facet normal -0.0416613 -0.93006 0.365038 + outer loop + vertex -489.132 69.4512 45.1601 + vertex -487.728 70.5277 48.063 + vertex -490.395 70.3616 47.3355 + endloop + endfacet + facet normal -0.0464172 -0.930794 0.362584 + outer loop + vertex -489.132 69.4512 45.1601 + vertex -490.395 70.3616 47.3355 + vertex -491.3 69.4321 44.8336 + endloop + endfacet + facet normal -0.049735 -0.921952 0.384097 + outer loop + vertex -490.577 69.0032 43.8976 + vertex -489.132 69.4512 45.1601 + vertex -491.3 69.4321 44.8336 + endloop + endfacet + facet normal -0.0516948 -0.92239 0.382784 + outer loop + vertex -490.577 69.0032 43.8976 + vertex -491.3 69.4321 44.8336 + vertex -491.981 68.862 43.3678 + endloop + endfacet + facet normal -0.0519083 -0.922168 0.383291 + outer loop + vertex -490.577 69.0032 43.8976 + vertex -491.981 68.862 43.3678 + vertex -490.33 68.8051 43.4544 + endloop + endfacet + facet normal -0.0499126 -0.92187 0.384271 + outer loop + vertex -490.33 68.8051 43.4544 + vertex -489.132 69.4512 45.1601 + vertex -490.577 69.0032 43.8976 + endloop + endfacet + facet normal -0.0366597 -0.925723 0.37642 + outer loop + vertex -488.265 69.142 44.4841 + vertex -489.132 69.4512 45.1601 + vertex -490.33 68.8051 43.4544 + endloop + endfacet + facet normal -0.0192332 -0.938199 0.345563 + outer loop + vertex -488.265 69.142 44.4841 + vertex -490.33 68.8051 43.4544 + vertex -488.074 69.029 44.1878 + endloop + endfacet + facet normal -0.00565982 -0.935492 0.353303 + outer loop + vertex -488.074 69.029 44.1878 + vertex -486.258 69.7546 46.1382 + vertex -488.265 69.142 44.4841 + endloop + endfacet + facet normal -0.0054595 -0.935555 0.353139 + outer loop + vertex -488.074 69.029 44.1878 + vertex -483.565 69.7951 46.2872 + vertex -486.258 69.7546 46.1382 + endloop + endfacet + facet normal -0.00549785 -0.935317 0.353768 + outer loop + vertex -483.4 70.3211 47.6804 + vertex -486.258 69.7546 46.1382 + vertex -483.565 69.7951 46.2872 + endloop + endfacet + facet normal 0.00906692 -0.935861 0.352253 + outer loop + vertex -480.916 70.6453 48.4778 + vertex -483.4 70.3211 47.6804 + vertex -483.565 69.7951 46.2872 + endloop + endfacet + facet normal 0.0261379 -0.942187 0.334066 + outer loop + vertex -483.565 69.7951 46.2872 + vertex -478.931 70.6015 48.1991 + vertex -480.916 70.6453 48.4778 + endloop + endfacet + facet normal 0.0274548 -0.938957 0.342937 + outer loop + vertex -478.522 71.134 49.6242 + vertex -480.916 70.6453 48.4778 + vertex -478.931 70.6015 48.1991 + endloop + endfacet + facet normal 0.0480548 -0.940113 0.33746 + outer loop + vertex -476.257 71.5134 50.3586 + vertex -478.522 71.134 49.6242 + vertex -478.931 70.6015 48.1991 + endloop + endfacet + facet normal 0.0678413 -0.946454 0.315631 + outer loop + vertex -478.931 70.6015 48.1991 + vertex -474.412 71.5484 50.067 + vertex -476.257 71.5134 50.3586 + endloop + endfacet + facet normal 0.069701 -0.942132 0.327915 + outer loop + vertex -473.907 72.0947 51.5294 + vertex -476.257 71.5134 50.3586 + vertex -474.412 71.5484 50.067 + endloop + endfacet + facet normal 0.0949717 -0.942831 0.319451 + outer loop + vertex -471.608 72.5811 52.2813 + vertex -473.907 72.0947 51.5294 + vertex -474.412 71.5484 50.067 + endloop + endfacet + facet normal 0.115128 -0.948105 0.296383 + outer loop + vertex -474.412 71.5484 50.067 + vertex -470.074 72.615 51.794 + vertex -471.608 72.5811 52.2813 + endloop + endfacet + facet normal 0.120259 -0.942125 0.31295 + outer loop + vertex -468.724 73.3624 53.5249 + vertex -471.608 72.5811 52.2813 + vertex -470.074 72.615 51.794 + endloop + endfacet + facet normal 0.117984 -0.940903 0.317459 + outer loop + vertex -468.724 73.3624 53.5249 + vertex -470.262 73.6327 54.8981 + vertex -471.608 72.5811 52.2813 + endloop + endfacet + facet normal 0.0978902 -0.939817 0.327356 + outer loop + vertex -471.608 72.5811 52.2813 + vertex -470.262 73.6327 54.8981 + vertex -472.69 73.0317 53.8984 + endloop + endfacet + facet normal 0.108041 -0.945785 0.306296 + outer loop + vertex -470.262 73.6327 54.8981 + vertex -471.57 74.2881 57.3832 + vertex -472.69 73.0317 53.8984 + endloop + endfacet + facet normal 0.0882761 -0.945762 0.312636 + outer loop + vertex -472.69 73.0317 53.8984 + vertex -471.57 74.2881 57.3832 + vertex -474.007 73.7393 56.4109 + endloop + endfacet + facet normal 0.0844337 -0.94669 0.310883 + outer loop + vertex -472.69 73.0317 53.8984 + vertex -474.007 73.7393 56.4109 + vertex -475.067 72.4941 52.907 + endloop + endfacet + facet normal 0.0731944 -0.93971 0.334047 + outer loop + vertex -473.907 72.0947 51.5294 + vertex -472.69 73.0317 53.8984 + vertex -475.067 72.4941 52.907 + endloop + endfacet + facet normal 0.0656995 -0.946339 0.316427 + outer loop + vertex -475.067 72.4941 52.907 + vertex -474.007 73.7393 56.4109 + vertex -476.484 73.247 55.4529 + endloop + endfacet + facet normal 0.0628631 -0.946994 0.315042 + outer loop + vertex -475.067 72.4941 52.907 + vertex -476.484 73.247 55.4529 + vertex -477.449 72.0174 51.9492 + endloop + endfacet + facet normal 0.052548 -0.939967 0.337195 + outer loop + vertex -476.257 71.5134 50.3586 + vertex -475.067 72.4941 52.907 + vertex -477.449 72.0174 51.9492 + endloop + endfacet + facet normal 0.0438502 -0.946381 0.320062 + outer loop + vertex -477.449 72.0174 51.9492 + vertex -476.484 73.247 55.4529 + vertex -478.977 72.8043 54.4854 + endloop + endfacet + facet normal 0.0427061 -0.94664 0.319452 + outer loop + vertex -477.449 72.0174 51.9492 + vertex -478.977 72.8043 54.4854 + vertex -479.847 71.5882 50.9979 + endloop + endfacet + facet normal 0.0324901 -0.939195 0.341845 + outer loop + vertex -478.522 71.134 49.6242 + vertex -477.449 72.0174 51.9492 + vertex -479.847 71.5882 50.9979 + endloop + endfacet + facet normal 0.0240516 -0.945815 0.323815 + outer loop + vertex -479.847 71.5882 50.9979 + vertex -478.977 72.8043 54.4854 + vertex -481.485 72.4163 53.5383 + endloop + endfacet + facet normal 0.023681 -0.945897 0.323602 + outer loop + vertex -479.847 71.5882 50.9979 + vertex -481.485 72.4163 53.5383 + vertex -482.324 71.2051 50.0594 + endloop + endfacet + facet normal 0.0144276 -0.93849 0.345005 + outer loop + vertex -480.916 70.6453 48.4778 + vertex -479.847 71.5882 50.9979 + vertex -482.324 71.2051 50.0594 + endloop + endfacet + facet normal 0.00504221 -0.944766 0.327706 + outer loop + vertex -482.324 71.2051 50.0594 + vertex -481.485 72.4163 53.5383 + vertex -484.047 72.0773 52.6006 + endloop + endfacet + facet normal 0.00574482 -0.944615 0.32813 + outer loop + vertex -482.324 71.2051 50.0594 + vertex -484.047 72.0773 52.6006 + vertex -484.954 70.8387 49.0509 + endloop + endfacet + facet normal -0.00362583 -0.936837 0.349746 + outer loop + vertex -483.4 70.3211 47.6804 + vertex -482.324 71.2051 50.0594 + vertex -484.954 70.8387 49.0509 + endloop + endfacet + facet normal -0.014324 -0.942934 0.332672 + outer loop + vertex -484.954 70.8387 49.0509 + vertex -484.047 72.0773 52.6006 + vertex -486.711 71.7905 51.6729 + endloop + endfacet + facet normal 0.0161858 -0.953656 0.300463 + outer loop + vertex -481.485 72.4163 53.5383 + vertex -483.101 73.4251 56.8276 + vertex -484.047 72.0773 52.6006 + endloop + endfacet + facet normal -0.00499281 -0.952402 0.304805 + outer loop + vertex -484.047 72.0773 52.6006 + vertex -483.101 73.4251 56.8276 + vertex -485.704 73.1421 55.9005 + endloop + endfacet + facet normal 0.0152107 -0.953808 0.30003 + outer loop + vertex -481.485 72.4163 53.5383 + vertex -480.529 73.7643 57.7754 + vertex -483.101 73.4251 56.8276 + endloop + endfacet + facet normal 0.0276346 -0.962613 0.269468 + outer loop + vertex -480.529 73.7643 57.7754 + vertex -481.868 74.7649 61.487 + vertex -483.101 73.4251 56.8276 + endloop + endfacet + facet normal 0.00747136 -0.961558 0.2745 + outer loop + vertex -483.101 73.4251 56.8276 + vertex -481.868 74.7649 61.487 + vertex -484.457 74.4812 60.5639 + endloop + endfacet + facet normal 0.0276296 -0.962613 0.269467 + outer loop + vertex -480.529 73.7643 57.7754 + vertex -479.26 75.1018 62.4231 + vertex -481.868 74.7649 61.487 + endloop + endfacet + facet normal 0.0404282 -0.970735 0.236728 + outer loop + vertex -479.26 75.1018 62.4231 + vertex -480.284 76.0103 66.3234 + vertex -481.868 74.7649 61.487 + endloop + endfacet + facet normal 0.0214638 -0.969861 0.242712 + outer loop + vertex -481.868 74.7649 61.487 + vertex -480.284 76.0103 66.3234 + vertex -482.907 75.7346 65.4538 + endloop + endfacet + facet normal 0.045054 -0.970261 0.237833 + outer loop + vertex -479.26 75.1018 62.4231 + vertex -477.726 76.3154 67.0837 + vertex -480.284 76.0103 66.3234 + endloop + endfacet + facet normal 0.0554678 -0.977079 0.205523 + outer loop + vertex -477.726 76.3154 67.0837 + vertex -478.37 77.1216 71.0905 + vertex -480.284 76.0103 66.3234 + endloop + endfacet + facet normal 0.0383618 -0.976463 0.212247 + outer loop + vertex -480.284 76.0103 66.3234 + vertex -478.37 77.1216 71.0905 + vertex -481.057 76.8882 70.502 + endloop + endfacet + facet normal 0.06306 -0.97639 0.206606 + outer loop + vertex -477.726 76.3154 67.0837 + vertex -476.203 77.2543 71.056 + vertex -478.37 77.1216 71.0905 + endloop + endfacet + facet normal 0.0629504 -0.981923 0.178507 + outer loop + vertex -476.203 77.2543 71.056 + vertex -475.738 78.1191 75.649 + vertex -478.37 77.1216 71.0905 + endloop + endfacet + facet normal 0.0560565 -0.981621 0.182422 + outer loop + vertex -478.37 77.1216 71.0905 + vertex -475.738 78.1191 75.649 + vertex -478.776 77.9844 75.8577 + endloop + endfacet + facet normal 0.0790419 -0.981082 0.17672 + outer loop + vertex -476.203 77.2543 71.056 + vertex -473.76 77.8191 73.0988 + vertex -475.738 78.1191 75.649 + endloop + endfacet + facet normal 0.0635816 -0.984226 0.165094 + outer loop + vertex -475.738 78.1191 75.649 + vertex -473.76 77.8191 73.0988 + vertex -471.201 79.233 80.5422 + endloop + endfacet + facet normal 0.0780659 -0.985307 0.151908 + outer loop + vertex -475.602 79.1167 82.0493 + vertex -475.738 78.1191 75.649 + vertex -471.201 79.233 80.5422 + endloop + endfacet + facet normal 0.0675494 -0.990375 0.120807 + outer loop + vertex -471.201 79.233 80.5422 + vertex -471.366 80.3925 90.1399 + vertex -475.602 79.1167 82.0493 + endloop + endfacet + facet normal 0.100184 -0.98758 0.121033 + outer loop + vertex -471.201 79.233 80.5422 + vertex -466.391 81.0192 91.1356 + vertex -471.366 80.3925 90.1399 + endloop + endfacet + facet normal 0.108372 -0.990715 0.0820984 + outer loop + vertex -466.391 81.0192 91.1356 + vertex -466.311 81.7307 99.6165 + vertex -471.366 80.3925 90.1399 + endloop + endfacet + facet normal 0.0761958 -0.99212 0.0994596 + outer loop + vertex -471.366 80.3925 90.1399 + vertex -466.311 81.7307 99.6165 + vertex -471.344 81.2115 98.2932 + endloop + endfacet + facet normal 0.0550033 -0.993501 0.0996558 + outer loop + vertex -471.366 80.3925 90.1399 + vertex -471.344 81.2115 98.2932 + vertex -476.11 80.023 89.0746 + endloop + endfacet + facet normal 0.0857795 -0.994266 0.0638529 + outer loop + vertex -466.311 81.7307 99.6165 + vertex -465.727 82.3079 107.819 + vertex -471.344 81.2115 98.2932 + endloop + endfacet + facet normal 0.0556699 -0.995101 0.0817038 + outer loop + vertex -471.344 81.2115 98.2932 + vertex -465.727 82.3079 107.819 + vertex -470.908 81.9068 106.465 + endloop + endfacet + facet normal 0.0644816 -0.99674 0.0484852 + outer loop + vertex -465.727 82.3079 107.819 + vertex -464.777 82.7704 116.063 + vertex -470.908 81.9068 106.465 + endloop + endfacet + facet normal 0.107517 -0.993258 0.0433339 + outer loop + vertex -465.727 82.3079 107.819 + vertex -459.415 83.3994 117.177 + vertex -464.777 82.7704 116.063 + endloop + endfacet + facet normal 0.11426 -0.993391 0.0109322 + outer loop + vertex -459.415 83.3994 117.177 + vertex -458.136 83.6371 125.409 + vertex -464.777 82.7704 116.063 + endloop + endfacet + facet normal 0.0886707 -0.995629 0.0293235 + outer loop + vertex -464.777 82.7704 116.063 + vertex -458.136 83.6371 125.409 + vertex -463.603 83.121 124.418 + endloop + endfacet + facet normal 0.0938284 -0.995588 0.000850445 + outer loop + vertex -458.136 83.6371 125.409 + vertex -456.725 83.7772 133.717 + vertex -463.603 83.121 124.418 + endloop + endfacet + facet normal 0.150803 -0.988523 -0.008946 + outer loop + vertex -458.136 83.6371 125.409 + vertex -451.007 84.6442 134.306 + vertex -456.725 83.7772 133.717 + endloop + endfacet + facet normal 0.153522 -0.987455 -0.0369169 + outer loop + vertex -451.007 84.6442 134.306 + vertex -449.358 84.5923 142.552 + vertex -456.725 83.7772 133.717 + endloop + endfacet + facet normal 0.132715 -0.990967 -0.0192411 + outer loop + vertex -456.725 83.7772 133.717 + vertex -449.358 84.5923 142.552 + vertex -455.219 83.8166 142.077 + endloop + endfacet + facet normal 0.0758869 -0.997076 -0.00897099 + outer loop + vertex -456.725 83.7772 133.717 + vertex -455.219 83.8166 142.077 + vertex -462.305 83.3604 132.835 + endloop + endfacet + facet normal 0.13474 -0.989808 -0.0460899 + outer loop + vertex -449.358 84.5923 142.552 + vertex -447.591 84.4468 150.842 + vertex -455.219 83.8166 142.077 + endloop + endfacet + facet normal 0.114996 -0.992952 -0.0286824 + outer loop + vertex -455.219 83.8166 142.077 + vertex -447.591 84.4468 150.842 + vertex -453.607 83.7612 150.458 + endloop + endfacet + facet normal 0.0590859 -0.998091 -0.0179653 + outer loop + vertex -455.219 83.8166 142.077 + vertex -453.607 83.7612 150.458 + vertex -460.925 83.4932 141.279 + endloop + endfacet + facet normal 0.116486 -0.99171 -0.054233 + outer loop + vertex -447.591 84.4468 150.842 + vertex -445.699 84.2157 159.132 + vertex -453.607 83.7612 150.458 + endloop + endfacet + facet normal 0.0999948 -0.994221 -0.0390652 + outer loop + vertex -453.607 83.7612 150.458 + vertex -445.699 84.2157 159.132 + vertex -451.894 83.6036 158.852 + endloop + endfacet + facet normal 0.0447587 -0.998609 -0.0278758 + outer loop + vertex -453.607 83.7612 150.458 + vertex -451.894 83.6036 158.852 + vertex -459.466 83.5182 149.755 + endloop + endfacet + facet normal 0.100987 -0.992817 -0.0641488 + outer loop + vertex -445.699 84.2157 159.132 + vertex -443.71 83.8832 167.409 + vertex -451.894 83.6036 158.852 + endloop + endfacet + facet normal 0.0857895 -0.995081 -0.0495388 + outer loop + vertex -451.894 83.6036 158.852 + vertex -443.71 83.8832 167.409 + vertex -450.086 83.3425 167.229 + endloop + endfacet + facet normal 0.0317446 -0.998774 -0.0379873 + outer loop + vertex -451.894 83.6036 158.852 + vertex -450.086 83.3425 167.229 + vertex -457.92 83.435 158.249 + endloop + endfacet + facet normal 0.0863199 -0.99361 -0.0727126 + outer loop + vertex -443.71 83.8832 167.409 + vertex -441.622 83.4641 175.615 + vertex -450.086 83.3425 167.229 + endloop + endfacet + facet normal 0.0747486 -0.995334 -0.0610091 + outer loop + vertex -450.086 83.3425 167.229 + vertex -441.622 83.4641 175.615 + vertex -448.202 82.9738 175.553 + endloop + endfacet + facet normal 0.0206275 -0.99859 -0.0489036 + outer loop + vertex -450.086 83.3425 167.229 + vertex -448.202 82.9738 175.553 + vertex -456.29 83.2389 166.728 + endloop + endfacet + facet normal 0.0748398 -0.993701 -0.0834141 + outer loop + vertex -441.622 83.4641 175.615 + vertex -439.47 82.9439 183.742 + vertex -448.202 82.9738 175.553 + endloop + endfacet + facet normal 0.0647654 -0.99525 -0.0726779 + outer loop + vertex -448.202 82.9738 175.553 + vertex -439.47 82.9439 183.742 + vertex -446.253 82.4989 183.791 + endloop + endfacet + facet normal 0.011044 -0.998129 -0.0601385 + outer loop + vertex -448.202 82.9738 175.553 + vertex -446.253 82.4989 183.791 + vertex -454.589 82.9272 175.152 + endloop + endfacet + facet normal 0.0644904 -0.993447 -0.0943634 + outer loop + vertex -439.47 82.9439 183.742 + vertex -437.259 82.3249 191.771 + vertex -446.253 82.4989 183.791 + endloop + endfacet + facet normal 0.056879 -0.994687 -0.0858111 + outer loop + vertex -446.253 82.4989 183.791 + vertex -437.259 82.3249 191.771 + vertex -444.26 81.9093 191.947 + endloop + endfacet + facet normal 0.00377046 -0.997323 -0.0730191 + outer loop + vertex -446.253 82.4989 183.791 + vertex -444.26 81.9093 191.947 + vertex -452.837 82.4951 183.504 + endloop + endfacet + facet normal 0.0562329 -0.99269 -0.106792 + outer loop + vertex -437.259 82.3249 191.771 + vertex -435.003 81.5985 199.711 + vertex -444.26 81.9093 191.947 + endloop + endfacet + facet normal 0.0498327 -0.993818 -0.0992064 + outer loop + vertex -444.26 81.9093 191.947 + vertex -435.003 81.5985 199.711 + vertex -442.223 81.2062 200.014 + endloop + endfacet + facet normal -0.00241486 -0.996273 -0.0862278 + outer loop + vertex -444.26 81.9093 191.947 + vertex -442.223 81.2062 200.014 + vertex -451.044 81.9405 191.777 + endloop + endfacet + facet normal 0.04885 -0.991606 -0.119709 + outer loop + vertex -435.003 81.5985 199.711 + vertex -432.707 80.7653 207.55 + vertex -442.223 81.2062 200.014 + endloop + endfacet + facet normal 0.044449 -0.992463 -0.114202 + outer loop + vertex -442.223 81.2062 200.014 + vertex -432.707 80.7653 207.55 + vertex -440.156 80.3799 208 + endloop + endfacet + facet normal -0.00654854 -0.99484 -0.101248 + outer loop + vertex -442.223 81.2062 200.014 + vertex -440.156 80.3799 208 + vertex -449.224 81.2555 199.982 + endloop + endfacet + facet normal 0.0431012 -0.989991 -0.134389 + outer loop + vertex -432.707 80.7653 207.55 + vertex -430.38 79.8172 215.28 + vertex -440.156 80.3799 208 + endloop + endfacet + facet normal 0.0397467 -0.990725 -0.129942 + outer loop + vertex -440.156 80.3799 208 + vertex -430.38 79.8172 215.28 + vertex -438.06 79.4288 215.893 + endloop + endfacet + facet normal -0.0102043 -0.993084 -0.116959 + outer loop + vertex -440.156 80.3799 208 + vertex -438.06 79.4288 215.893 + vertex -447.37 80.4411 208.109 + endloop + endfacet + facet normal 0.0380871 -0.988091 -0.149082 + outer loop + vertex -430.38 79.8172 215.28 + vertex -428.011 78.7617 222.881 + vertex -438.06 79.4288 215.893 + endloop + endfacet + facet normal 0.0360275 -0.988603 -0.146169 + outer loop + vertex -438.06 79.4288 215.893 + vertex -428.011 78.7617 222.881 + vertex -435.929 78.356 223.673 + endloop + endfacet + facet normal -0.0131604 -0.991024 -0.133036 + outer loop + vertex -438.06 79.4288 215.893 + vertex -435.929 78.356 223.673 + vertex -445.49 79.492 216.157 + endloop + endfacet + facet normal 0.0339556 -0.985646 -0.165374 + outer loop + vertex -428.011 78.7617 222.881 + vertex -425.614 77.5911 230.35 + vertex -435.929 78.356 223.673 + endloop + endfacet + facet normal 0.0318031 -0.986259 -0.162119 + outer loop + vertex -435.929 78.356 223.673 + vertex -425.614 77.5911 230.35 + vertex -433.764 77.1695 231.316 + endloop + endfacet + facet normal -0.0152109 -0.988694 -0.149175 + outer loop + vertex -435.929 78.356 223.673 + vertex -433.764 77.1695 231.316 + vertex -443.589 78.4072 224.115 + endloop + endfacet + facet normal 0.0296121 -0.983343 -0.179331 + outer loop + vertex -425.614 77.5911 230.35 + vertex -423.156 76.3399 237.617 + vertex -433.764 77.1695 231.316 + endloop + endfacet + facet normal 0.0291528 -0.983494 -0.178578 + outer loop + vertex -433.764 77.1695 231.316 + vertex -423.156 76.3399 237.617 + vertex -431.552 75.8759 238.801 + endloop + endfacet + facet normal -0.0170867 -0.986085 -0.165361 + outer loop + vertex -433.764 77.1695 231.316 + vertex -431.552 75.8759 238.801 + vertex -441.655 77.2006 231.946 + endloop + endfacet + facet normal 0.0267439 -0.98054 -0.194491 + outer loop + vertex -423.156 76.3399 237.617 + vertex -420.618 75.0061 244.69 + vertex -431.552 75.8759 238.801 + endloop + endfacet + facet normal 0.0264768 -0.980642 -0.194011 + outer loop + vertex -431.552 75.8759 238.801 + vertex -420.618 75.0061 244.69 + vertex -429.215 74.4998 246.076 + endloop + endfacet + facet normal 0.175266 -0.984092 -0.0290507 + outer loop + vertex -452.526 84.6154 126.118 + vertex -451.007 84.6442 134.306 + vertex -458.136 83.6371 125.409 + endloop + endfacet + facet normal 0.171556 -0.985173 0.00179468 + outer loop + vertex -459.415 83.3994 117.177 + vertex -452.526 84.6154 126.118 + vertex -458.136 83.6371 125.409 + endloop + endfacet + facet normal 0.196834 -0.980265 -0.0183488 + outer loop + vertex -453.905 84.4903 117.998 + vertex -452.526 84.6154 126.118 + vertex -459.415 83.3994 117.177 + endloop + endfacet + facet normal 0.191868 -0.981285 0.0163084 + outer loop + vertex -460.469 83.0577 109.017 + vertex -453.905 84.4903 117.998 + vertex -459.415 83.3994 117.177 + endloop + endfacet + facet normal 0.219824 -0.975526 -0.00503972 + outer loop + vertex -455.05 84.2743 109.912 + vertex -453.905 84.4903 117.998 + vertex -460.469 83.0577 109.017 + endloop + endfacet + facet normal 0.213288 -0.97634 0.0356076 + outer loop + vertex -461.135 82.6138 100.833 + vertex -455.05 84.2743 109.912 + vertex -460.469 83.0577 109.017 + endloop + endfacet + facet normal 0.158749 -0.986484 0.0405967 + outer loop + vertex -461.135 82.6138 100.833 + vertex -460.469 83.0577 109.017 + vertex -466.311 81.7307 99.6165 + endloop + endfacet + facet normal 0.246475 -0.969075 0.0120346 + outer loop + vertex -455.796 83.9845 101.863 + vertex -455.05 84.2743 109.912 + vertex -461.135 82.6138 100.833 + endloop + endfacet + facet normal 0.237722 -0.969593 0.058118 + outer loop + vertex -461.232 82.0953 92.5824 + vertex -455.796 83.9845 101.863 + vertex -461.135 82.6138 100.833 + endloop + endfacet + facet normal 0.187863 -0.980398 0.0593854 + outer loop + vertex -461.232 82.0953 92.5824 + vertex -461.135 82.6138 100.833 + vertex -466.391 81.0192 91.1356 + endloop + endfacet + facet normal 0.175538 -0.979134 0.10239 + outer loop + vertex -465.716 80.239 82.5184 + vertex -461.232 82.0953 92.5824 + vertex -466.391 81.0192 91.1356 + endloop + endfacet + facet normal 0.22215 -0.971704 0.0802519 + outer loop + vertex -460.746 81.5309 84.401 + vertex -461.232 82.0953 92.5824 + vertex -465.716 80.239 82.5184 + endloop + endfacet + facet normal 0.203304 -0.970551 0.129222 + outer loop + vertex -460.746 81.5309 84.401 + vertex -465.716 80.239 82.5184 + vertex -464.056 79.9036 77.3869 + endloop + endfacet + facet normal 0.19401 -0.972827 0.126363 + outer loop + vertex -466.444 79.1997 75.6346 + vertex -464.056 79.9036 77.3869 + vertex -465.716 80.239 82.5184 + endloop + endfacet + facet normal 0.155719 -0.97903 0.131348 + outer loop + vertex -466.444 79.1997 75.6346 + vertex -465.716 80.239 82.5184 + vertex -468.823 78.8187 75.6153 + endloop + endfacet + facet normal 0.154682 -0.974223 0.164202 + outer loop + vertex -467.823 78.199 70.9965 + vertex -466.444 79.1997 75.6346 + vertex -468.823 78.8187 75.6153 + endloop + endfacet + facet normal 0.154188 -0.974318 0.164107 + outer loop + vertex -467.823 78.199 70.9965 + vertex -468.823 78.8187 75.6153 + vertex -470.203 77.6795 70.1484 + endloop + endfacet + facet normal 0.138861 -0.969089 0.203921 + outer loop + vertex -469.133 76.9895 66.1401 + vertex -467.823 78.199 70.9965 + vertex -470.203 77.6795 70.1484 + endloop + endfacet + facet normal 0.14184 -0.968511 0.204618 + outer loop + vertex -469.133 76.9895 66.1401 + vertex -470.203 77.6795 70.1484 + vertex -471.545 76.4543 65.2789 + endloop + endfacet + facet normal 0.125851 -0.961336 0.244938 + outer loop + vertex -470.402 75.6542 61.5515 + vertex -469.133 76.9895 66.1401 + vertex -471.545 76.4543 65.2789 + endloop + endfacet + facet normal 0.123357 -0.961827 0.244279 + outer loop + vertex -470.402 75.6542 61.5515 + vertex -471.545 76.4543 65.2789 + vertex -472.844 75.1096 60.6403 + endloop + endfacet + facet normal 0.107239 -0.953295 0.282363 + outer loop + vertex -471.57 74.2881 57.3832 + vertex -470.402 75.6542 61.5515 + vertex -472.844 75.1096 60.6403 + endloop + endfacet + facet normal 0.128501 -0.952488 0.27614 + outer loop + vertex -469.213 74.878 58.3209 + vertex -470.402 75.6542 61.5515 + vertex -471.57 74.2881 57.3832 + endloop + endfacet + facet normal 0.133361 -0.951377 0.277662 + outer loop + vertex -469.213 74.878 58.3209 + vertex -468.082 76.2311 62.4138 + vertex -470.402 75.6542 61.5515 + endloop + endfacet + facet normal 0.154259 -0.950014 0.271434 + outer loop + vertex -466.959 75.5008 59.2195 + vertex -468.082 76.2311 62.4138 + vertex -469.213 74.878 58.3209 + endloop + endfacet + facet normal 0.138477 -0.942064 0.305515 + outer loop + vertex -467.916 74.2917 55.9248 + vertex -466.959 75.5008 59.2195 + vertex -469.213 74.878 58.3209 + endloop + endfacet + facet normal 0.132557 -0.943811 0.302737 + outer loop + vertex -467.916 74.2917 55.9248 + vertex -469.213 74.878 58.3209 + vertex -470.262 73.6327 54.8981 + endloop + endfacet + facet normal 0.159412 -0.940847 0.29899 + outer loop + vertex -465.71 74.9515 56.8249 + vertex -466.959 75.5008 59.2195 + vertex -467.916 74.2917 55.9248 + endloop + endfacet + facet normal 0.147979 -0.934883 0.32264 + outer loop + vertex -466.575 74.0772 54.6884 + vertex -465.71 74.9515 56.8249 + vertex -467.916 74.2917 55.9248 + endloop + endfacet + facet normal 0.14113 -0.938271 0.3158 + outer loop + vertex -466.575 74.0772 54.6884 + vertex -467.916 74.2917 55.9248 + vertex -468.724 73.3624 53.5249 + endloop + endfacet + facet normal 0.147403 -0.940656 0.305677 + outer loop + vertex -466.575 74.0772 54.6884 + vertex -468.724 73.3624 53.5249 + vertex -466.152 73.7698 53.5388 + endloop + endfacet + facet normal 0.169167 -0.934859 0.312122 + outer loop + vertex -464.432 74.6699 55.3025 + vertex -466.575 74.0772 54.6884 + vertex -466.152 73.7698 53.5388 + endloop + endfacet + facet normal 0.148127 -0.944771 0.292346 + outer loop + vertex -470.074 72.615 51.794 + vertex -466.152 73.7698 53.5388 + vertex -468.724 73.3624 53.5249 + endloop + endfacet + facet normal 0.178095 -0.956149 0.23251 + outer loop + vertex -466.152 73.7698 53.5388 + vertex -470.074 72.615 51.794 + vertex -466.885 73.4208 52.6648 + endloop + endfacet + facet normal 0.168443 -0.934319 0.314125 + outer loop + vertex -464.432 74.6699 55.3025 + vertex -465.71 74.9515 56.8249 + vertex -466.575 74.0772 54.6884 + endloop + endfacet + facet normal 0.176382 -0.930807 0.320136 + outer loop + vertex -464.432 74.6699 55.3025 + vertex -463.441 75.6612 57.6385 + vertex -465.71 74.9515 56.8249 + endloop + endfacet + facet normal 0.188146 -0.937393 0.293078 + outer loop + vertex -463.441 75.6612 57.6385 + vertex -464.728 76.1647 60.0754 + vertex -465.71 74.9515 56.8249 + endloop + endfacet + facet normal 0.192069 -0.936035 0.29487 + outer loop + vertex -463.441 75.6612 57.6385 + vertex -462.375 76.9235 60.9515 + vertex -464.728 76.1647 60.0754 + endloop + endfacet + facet normal 0.208775 -0.94369 0.256635 + outer loop + vertex -462.375 76.9235 60.9515 + vertex -463.64 77.4994 64.0984 + vertex -464.728 76.1647 60.0754 + endloop + endfacet + facet normal 0.180649 -0.947074 0.265362 + outer loop + vertex -464.728 76.1647 60.0754 + vertex -463.64 77.4994 64.0984 + vertex -465.858 76.8378 63.2465 + endloop + endfacet + facet normal 0.180169 -0.947205 0.265219 + outer loop + vertex -464.728 76.1647 60.0754 + vertex -465.858 76.8378 63.2465 + vertex -466.959 75.5008 59.2195 + endloop + endfacet + facet normal 0.199291 -0.954348 0.222492 + outer loop + vertex -463.64 77.4994 64.0984 + vertex -464.659 78.1427 67.7705 + vertex -465.858 76.8378 63.2465 + endloop + endfacet + facet normal 0.172668 -0.957632 0.230491 + outer loop + vertex -465.858 76.8378 63.2465 + vertex -464.659 78.1427 67.7705 + vertex -466.851 77.5486 66.9438 + endloop + endfacet + facet normal 0.174638 -0.957169 0.230931 + outer loop + vertex -465.858 76.8378 63.2465 + vertex -466.851 77.5486 66.9438 + vertex -468.082 76.2311 62.4138 + endloop + endfacet + facet normal 0.151288 -0.959427 0.237932 + outer loop + vertex -468.082 76.2311 62.4138 + vertex -466.851 77.5486 66.9438 + vertex -469.133 76.9895 66.1401 + endloop + endfacet + facet normal 0.191163 -0.963795 0.185894 + outer loop + vertex -464.659 78.1427 67.7705 + vertex -465.557 78.7446 71.8142 + vertex -466.851 77.5486 66.9438 + endloop + endfacet + facet normal 0.162781 -0.967341 0.194306 + outer loop + vertex -466.851 77.5486 66.9438 + vertex -465.557 78.7446 71.8142 + vertex -467.823 78.199 70.9965 + endloop + endfacet + facet normal 0.191046 -0.963822 0.185872 + outer loop + vertex -464.659 78.1427 67.7705 + vertex -463.352 79.3526 72.7004 + vertex -465.557 78.7446 71.8142 + endloop + endfacet + facet normal 0.208401 -0.967231 0.145026 + outer loop + vertex -463.352 79.3526 72.7004 + vertex -464.056 79.9036 77.3869 + vertex -465.557 78.7446 71.8142 + endloop + endfacet + facet normal 0.222302 -0.963875 0.146719 + outer loop + vertex -463.352 79.3526 72.7004 + vertex -461.814 80.4395 77.5099 + vertex -464.056 79.9036 77.3869 + endloop + endfacet + facet normal 0.224657 -0.967221 0.118372 + outer loop + vertex -461.814 80.4395 77.5099 + vertex -460.746 81.5309 84.401 + vertex -464.056 79.9036 77.3869 + endloop + endfacet + facet normal 0.286432 -0.952173 0.106413 + outer loop + vertex -461.814 80.4395 77.5099 + vertex -459.051 81.5038 79.5983 + vertex -460.746 81.5309 84.401 + endloop + endfacet + facet normal 0.29138 -0.950475 0.108149 + outer loop + vertex -455.728 83.3535 86.9016 + vertex -460.746 81.5309 84.401 + vertex -459.051 81.5038 79.5983 + endloop + endfacet + facet normal 0.261702 -0.954868 0.140498 + outer loop + vertex -461.02 80.098 73.71 + vertex -459.051 81.5038 79.5983 + vertex -461.814 80.4395 77.5099 + endloop + endfacet + facet normal 0.293953 -0.947225 0.127892 + outer loop + vertex -458.324 81.0614 74.6488 + vertex -459.051 81.5038 79.5983 + vertex -461.02 80.098 73.71 + endloop + endfacet + facet normal 0.277166 -0.944975 0.173786 + outer loop + vertex -460.139 79.6026 69.6116 + vertex -458.324 81.0614 74.6488 + vertex -461.02 80.098 73.71 + endloop + endfacet + facet normal 0.254812 -0.951961 0.169826 + outer loop + vertex -460.139 79.6026 69.6116 + vertex -461.02 80.098 73.71 + vertex -462.46 78.813 68.6685 + endloop + endfacet + facet normal 0.234814 -0.947831 0.215588 + outer loop + vertex -461.343 78.2608 65.0236 + vertex -460.139 79.6026 69.6116 + vertex -462.46 78.813 68.6685 + endloop + endfacet + facet normal 0.228558 -0.949728 0.213958 + outer loop + vertex -461.343 78.2608 65.0236 + vertex -462.46 78.813 68.6685 + vertex -463.64 77.4994 64.0984 + endloop + endfacet + facet normal 0.263842 -0.942238 0.206336 + outer loop + vertex -459.047 79.1162 65.9943 + vertex -460.139 79.6026 69.6116 + vertex -461.343 78.2608 65.0236 + endloop + endfacet + facet normal 0.244919 -0.937562 0.246968 + outer loop + vertex -459.793 77.8637 61.9791 + vertex -459.047 79.1162 65.9943 + vertex -461.343 78.2608 65.0236 + endloop + endfacet + facet normal 0.24352 -0.938095 0.246326 + outer loop + vertex -459.793 77.8637 61.9791 + vertex -461.343 78.2608 65.0236 + vertex -462.375 76.9235 60.9515 + endloop + endfacet + facet normal 0.226002 -0.931666 0.284468 + outer loop + vertex -462.375 76.9235 60.9515 + vertex -460.885 76.5487 58.5402 + vertex -459.793 77.8637 61.9791 + endloop + endfacet + facet normal 0.272017 -0.92448 0.267102 + outer loop + vertex -459.793 77.8637 61.9791 + vertex -460.885 76.5487 58.5402 + vertex -457.132 77.9972 59.7308 + endloop + endfacet + facet normal 0.26537 -0.928713 0.258982 + outer loop + vertex -457.675 78.8644 63.3974 + vertex -459.793 77.8637 61.9791 + vertex -457.132 77.9972 59.7308 + endloop + endfacet + facet normal 0.308698 -0.914361 0.262009 + outer loop + vertex -457.675 78.8644 63.3974 + vertex -457.132 77.9972 59.7308 + vertex -455.319 79.8044 63.9021 + endloop + endfacet + facet normal 0.279966 -0.930014 0.238103 + outer loop + vertex -457.675 78.8644 63.3974 + vertex -459.047 79.1162 65.9943 + vertex -459.793 77.8637 61.9791 + endloop + endfacet + facet normal 0.284631 -0.928012 0.240373 + outer loop + vertex -457.675 78.8644 63.3974 + vertex -456.828 79.9921 66.7483 + vertex -459.047 79.1162 65.9943 + endloop + endfacet + facet normal 0.317957 -0.919973 0.229245 + outer loop + vertex -455.319 79.8044 63.9021 + vertex -456.828 79.9921 66.7483 + vertex -457.675 78.8644 63.3974 + endloop + endfacet + facet normal 0.32155 -0.918274 0.231038 + outer loop + vertex -455.319 79.8044 63.9021 + vertex -454.626 80.9912 67.6551 + vertex -456.828 79.9921 66.7483 + endloop + endfacet + facet normal 0.363541 -0.905417 0.219222 + outer loop + vertex -453.131 81.035 65.3564 + vertex -454.626 80.9912 67.6551 + vertex -455.319 79.8044 63.9021 + endloop + endfacet + facet normal 0.365989 -0.904036 0.220841 + outer loop + vertex -453.131 81.035 65.3564 + vertex -452.372 82.1432 68.6354 + vertex -454.626 80.9912 67.6551 + endloop + endfacet + facet normal 0.409333 -0.888897 0.205692 + outer loop + vertex -450.762 82.2202 65.7637 + vertex -452.372 82.1432 68.6354 + vertex -453.131 81.035 65.3564 + endloop + endfacet + facet normal 0.417371 -0.884061 0.210328 + outer loop + vertex -450.762 82.2202 65.7637 + vertex -450.13 83.4212 69.5571 + vertex -452.372 82.1432 68.6354 + endloop + endfacet + facet normal 0.457709 -0.866747 0.198122 + outer loop + vertex -448.684 83.6203 67.0873 + vertex -450.13 83.4212 69.5571 + vertex -450.762 82.2202 65.7637 + endloop + endfacet + facet normal 0.469698 -0.858503 0.205807 + outer loop + vertex -448.684 83.6203 67.0873 + vertex -447.908 84.8622 70.4965 + vertex -450.13 83.4212 69.5571 + endloop + endfacet + facet normal 0.50649 -0.840827 0.190993 + outer loop + vertex -446.676 84.9482 67.6095 + vertex -447.908 84.8622 70.4965 + vertex -448.684 83.6203 67.0873 + endloop + endfacet + facet normal 0.522851 -0.829033 0.198324 + outer loop + vertex -446.676 84.9482 67.6095 + vertex -445.729 86.4414 71.354 + vertex -447.908 84.8622 70.4965 + endloop + endfacet + facet normal 0.560783 -0.808077 0.180372 + outer loop + vertex -444.88 86.4976 68.966 + vertex -445.729 86.4414 71.354 + vertex -446.676 84.9482 67.6095 + endloop + endfacet + facet normal 0.545198 -0.812568 0.206137 + outer loop + vertex -444.88 86.4976 68.966 + vertex -446.676 84.9482 67.6095 + vertex -444.806 85.8748 66.3151 + endloop + endfacet + facet normal 0.542341 -0.816141 0.19945 + outer loop + vertex -444.806 85.8748 66.3151 + vertex -446.676 84.9482 67.6095 + vertex -447.75 83.3048 63.8043 + endloop + endfacet + facet normal 0.523368 -0.821316 0.226994 + outer loop + vertex -443.872 85.8956 64.2384 + vertex -444.806 85.8748 66.3151 + vertex -447.75 83.3048 63.8043 + endloop + endfacet + facet normal 0.578397 -0.794041 0.186965 + outer loop + vertex -444.88 86.4976 68.966 + vertex -443.657 88.138 72.1494 + vertex -445.729 86.4414 71.354 + endloop + endfacet + facet normal 0.596643 -0.783321 0.17443 + outer loop + vertex -443.124 87.874 69.1396 + vertex -443.657 88.138 72.1494 + vertex -444.88 86.4976 68.966 + endloop + endfacet + facet normal 0.637077 -0.749811 0.178654 + outer loop + vertex -443.124 87.874 69.1396 + vertex -441.539 90.1094 72.8701 + vertex -443.657 88.138 72.1494 + endloop + endfacet + facet normal 0.649119 -0.741743 0.168704 + outer loop + vertex -440.995 89.8824 69.78 + vertex -441.539 90.1094 72.8701 + vertex -443.124 87.874 69.1396 + endloop + endfacet + facet normal 0.280737 -0.936384 0.210649 + outer loop + vertex -459.047 79.1162 65.9943 + vertex -457.777 80.4483 70.2227 + vertex -460.139 79.6026 69.6116 + endloop + endfacet + facet normal 0.298693 -0.932298 0.203966 + outer loop + vertex -456.828 79.9921 66.7483 + vertex -457.777 80.4483 70.2227 + vertex -459.047 79.1162 65.9943 + endloop + endfacet + facet normal 0.319477 -0.924349 0.208596 + outer loop + vertex -456.828 79.9921 66.7483 + vertex -455.826 81.1142 70.1853 + vertex -457.777 80.4483 70.2227 + endloop + endfacet + facet normal 0.3209 -0.930237 0.177997 + outer loop + vertex -455.826 81.1142 70.1853 + vertex -455.489 82.0398 74.4164 + vertex -457.777 80.4483 70.2227 + endloop + endfacet + facet normal 0.333972 -0.92718 0.169708 + outer loop + vertex -457.777 80.4483 70.2227 + vertex -455.489 82.0398 74.4164 + vertex -458.324 81.0614 74.6488 + endloop + endfacet + facet normal 0.332995 -0.934122 0.128567 + outer loop + vertex -455.489 82.0398 74.4164 + vertex -455.303 82.9266 80.3775 + vertex -458.324 81.0614 74.6488 + endloop + endfacet + facet normal 0.399346 -0.908554 0.12269 + outer loop + vertex -455.303 82.9266 80.3775 + vertex -455.489 82.0398 74.4164 + vertex -451.032 84.5951 78.8304 + endloop + endfacet + facet normal 0.357343 -0.918239 0.170715 + outer loop + vertex -455.489 82.0398 74.4164 + vertex -453.597 82.3322 72.0288 + vertex -451.032 84.5951 78.8304 + endloop + endfacet + facet normal 0.359004 -0.917324 0.172143 + outer loop + vertex -455.826 81.1142 70.1853 + vertex -453.597 82.3322 72.0288 + vertex -455.489 82.0398 74.4164 + endloop + endfacet + facet normal 0.334704 -0.920118 0.203362 + outer loop + vertex -454.626 80.9912 67.6551 + vertex -453.597 82.3322 72.0288 + vertex -455.826 81.1142 70.1853 + endloop + endfacet + facet normal 0.380943 -0.905296 0.18794 + outer loop + vertex -452.372 82.1432 68.6354 + vertex -453.597 82.3322 72.0288 + vertex -454.626 80.9912 67.6551 + endloop + endfacet + facet normal 0.390513 -0.900538 0.19113 + outer loop + vertex -452.372 82.1432 68.6354 + vertex -451.378 83.408 72.5635 + vertex -453.597 82.3322 72.0288 + endloop + endfacet + facet normal 0.432006 -0.884629 0.175507 + outer loop + vertex -450.13 83.4212 69.5571 + vertex -451.378 83.408 72.5635 + vertex -452.372 82.1432 68.6354 + endloop + endfacet + facet normal 0.445683 -0.876656 0.181221 + outer loop + vertex -450.13 83.4212 69.5571 + vertex -449.152 84.8567 74.0965 + vertex -451.378 83.408 72.5635 + endloop + endfacet + facet normal 0.48591 -0.857974 0.166648 + outer loop + vertex -447.908 84.8622 70.4965 + vertex -449.152 84.8567 74.0965 + vertex -450.13 83.4212 69.5571 + endloop + endfacet + facet normal 0.503876 -0.8463 0.172875 + outer loop + vertex -447.908 84.8622 70.4965 + vertex -446.559 86.5511 74.8329 + vertex -449.152 84.8567 74.0965 + endloop + endfacet + facet normal 0.539166 -0.827866 0.154718 + outer loop + vertex -445.729 86.4414 71.354 + vertex -446.559 86.5511 74.8329 + vertex -447.908 84.8622 70.4965 + endloop + endfacet + facet normal 0.563603 -0.810403 0.159996 + outer loop + vertex -445.729 86.4414 71.354 + vertex -444.196 88.3362 75.5518 + vertex -446.559 86.5511 74.8329 + endloop + endfacet + facet normal 0.594456 -0.791789 0.140328 + outer loop + vertex -443.657 88.138 72.1494 + vertex -444.196 88.3362 75.5518 + vertex -445.729 86.4414 71.354 + endloop + endfacet + facet normal 0.334046 -0.920423 0.203065 + outer loop + vertex -454.626 80.9912 67.6551 + vertex -455.826 81.1142 70.1853 + vertex -456.828 79.9921 66.7483 + endloop + endfacet + facet normal 0.22853 -0.95701 0.178622 + outer loop + vertex -462.46 78.813 68.6685 + vertex -461.02 80.098 73.71 + vertex -463.352 79.3526 72.7004 + endloop + endfacet + facet normal 0.293836 -0.941209 0.166689 + outer loop + vertex -457.777 80.4483 70.2227 + vertex -458.324 81.0614 74.6488 + vertex -460.139 79.6026 69.6116 + endloop + endfacet + facet normal 0.327716 -0.935536 0.131811 + outer loop + vertex -458.324 81.0614 74.6488 + vertex -455.303 82.9266 80.3775 + vertex -459.051 81.5038 79.5983 + endloop + endfacet + facet normal 0.246903 -0.959193 0.137794 + outer loop + vertex -461.02 80.098 73.71 + vertex -461.814 80.4395 77.5099 + vertex -463.352 79.3526 72.7004 + endloop + endfacet + facet normal 0.220079 -0.959279 0.177057 + outer loop + vertex -462.46 78.813 68.6685 + vertex -463.352 79.3526 72.7004 + vertex -464.659 78.1427 67.7705 + endloop + endfacet + facet normal 0.199916 -0.954184 0.222636 + outer loop + vertex -463.64 77.4994 64.0984 + vertex -462.46 78.813 68.6685 + vertex -464.659 78.1427 67.7705 + endloop + endfacet + facet normal 0.209256 -0.943539 0.256801 + outer loop + vertex -462.375 76.9235 60.9515 + vertex -461.343 78.2608 65.0236 + vertex -463.64 77.4994 64.0984 + endloop + endfacet + facet normal 0.223892 -0.932531 0.283299 + outer loop + vertex -460.885 76.5487 58.5402 + vertex -462.375 76.9235 60.9515 + vertex -463.441 75.6612 57.6385 + endloop + endfacet + facet normal 0.207736 -0.924092 0.32078 + outer loop + vertex -462.288 75.4469 56.2747 + vertex -460.885 76.5487 58.5402 + vertex -463.441 75.6612 57.6385 + endloop + endfacet + facet normal 0.224913 -0.923757 0.309979 + outer loop + vertex -460.31 76.1114 56.8191 + vertex -460.885 76.5487 58.5402 + vertex -462.288 75.4469 56.2747 + endloop + endfacet + facet normal 0.225497 -0.92416 0.308351 + outer loop + vertex -460.31 76.1114 56.8191 + vertex -462.288 75.4469 56.2747 + vertex -462.557 74.951 54.9852 + endloop + endfacet + facet normal 0.23648 -0.92553 0.295756 + outer loop + vertex -462.557 74.951 54.9852 + vertex -459.24 76.2785 56.4868 + vertex -460.31 76.1114 56.8191 + endloop + endfacet + facet normal 0.19285 -0.928651 0.316886 + outer loop + vertex -462.288 75.4469 56.2747 + vertex -464.432 74.6699 55.3025 + vertex -462.557 74.951 54.9852 + endloop + endfacet + facet normal 0.190051 -0.93707 0.292885 + outer loop + vertex -466.152 73.7698 53.5388 + vertex -462.557 74.951 54.9852 + vertex -464.432 74.6699 55.3025 + endloop + endfacet + facet normal 0.252345 -0.914322 0.316762 + outer loop + vertex -460.31 76.1114 56.8191 + vertex -457.132 77.9972 59.7308 + vertex -460.885 76.5487 58.5402 + endloop + endfacet + facet normal 0.195718 -0.929862 0.311529 + outer loop + vertex -462.288 75.4469 56.2747 + vertex -463.441 75.6612 57.6385 + vertex -464.432 74.6699 55.3025 + endloop + endfacet + facet normal 0.164077 -0.939375 0.301086 + outer loop + vertex -465.71 74.9515 56.8249 + vertex -464.728 76.1647 60.0754 + vertex -466.959 75.5008 59.2195 + endloop + endfacet + facet normal 0.157029 -0.949327 0.272251 + outer loop + vertex -466.959 75.5008 59.2195 + vertex -465.858 76.8378 63.2465 + vertex -468.082 76.2311 62.4138 + endloop + endfacet + facet normal 0.098124 -0.962834 0.251638 + outer loop + vertex -472.844 75.1096 60.6403 + vertex -471.545 76.4543 65.2789 + vertex -474.068 75.9522 64.3417 + endloop + endfacet + facet normal 0.0969943 -0.963034 0.25131 + outer loop + vertex -472.844 75.1096 60.6403 + vertex -474.068 75.9522 64.3417 + vertex -475.376 74.6097 59.702 + endloop + endfacet + facet normal 0.0822156 -0.954502 0.286648 + outer loop + vertex -474.007 73.7393 56.4109 + vertex -472.844 75.1096 60.6403 + vertex -475.376 74.6097 59.702 + endloop + endfacet + facet normal 0.0723782 -0.963339 0.258339 + outer loop + vertex -475.376 74.6097 59.702 + vertex -474.068 75.9522 64.3417 + vertex -476.656 75.4975 63.3709 + endloop + endfacet + facet normal 0.0716365 -0.963456 0.258109 + outer loop + vertex -475.376 74.6097 59.702 + vertex -476.656 75.4975 63.3709 + vertex -477.953 74.1596 58.7369 + endloop + endfacet + facet normal 0.0577551 -0.95492 0.29119 + outer loop + vertex -476.484 73.247 55.4529 + vertex -475.376 74.6097 59.702 + vertex -477.953 74.1596 58.7369 + endloop + endfacet + facet normal 0.0502622 -0.963207 0.264021 + outer loop + vertex -477.953 74.1596 58.7369 + vertex -476.656 75.4975 63.3709 + vertex -479.26 75.1018 62.4231 + endloop + endfacet + facet normal 0.0866483 -0.97078 0.223783 + outer loop + vertex -474.068 75.9522 64.3417 + vertex -475.205 76.7086 68.0633 + vertex -476.656 75.4975 63.3709 + endloop + endfacet + facet normal 0.0614387 -0.970869 0.231599 + outer loop + vertex -476.656 75.4975 63.3709 + vertex -475.205 76.7086 68.0633 + vertex -477.726 76.3154 67.0837 + endloop + endfacet + facet normal 0.0840206 -0.971177 0.223061 + outer loop + vertex -474.068 75.9522 64.3417 + vertex -472.68 77.1755 69.1451 + vertex -475.205 76.7086 68.0633 + endloop + endfacet + facet normal 0.100768 -0.977255 0.186595 + outer loop + vertex -472.68 77.1755 69.1451 + vertex -473.76 77.8191 73.0988 + vertex -475.205 76.7086 68.0633 + endloop + endfacet + facet normal 0.0983379 -0.977618 0.185991 + outer loop + vertex -472.68 77.1755 69.1451 + vertex -471.346 78.187 73.7562 + vertex -473.76 77.8191 73.0988 + endloop + endfacet + facet normal 0.109159 -0.982771 0.149148 + outer loop + vertex -471.346 78.187 73.7562 + vertex -471.201 79.233 80.5422 + vertex -473.76 77.8191 73.0988 + endloop + endfacet + facet normal 0.136179 -0.979556 0.148073 + outer loop + vertex -471.346 78.187 73.7562 + vertex -468.823 78.8187 75.6153 + vertex -471.201 79.233 80.5422 + endloop + endfacet + facet normal 0.128007 -0.981224 0.14427 + outer loop + vertex -465.716 80.239 82.5184 + vertex -471.201 79.233 80.5422 + vertex -468.823 78.8187 75.6153 + endloop + endfacet + facet normal 0.126724 -0.975944 0.177411 + outer loop + vertex -470.203 77.6795 70.1484 + vertex -471.346 78.187 73.7562 + vertex -472.68 77.1755 69.1451 + endloop + endfacet + facet normal 0.113451 -0.970157 0.214299 + outer loop + vertex -471.545 76.4543 65.2789 + vertex -472.68 77.1755 69.1451 + vertex -474.068 75.9522 64.3417 + endloop + endfacet + facet normal 0.15027 -0.959647 0.23769 + outer loop + vertex -468.082 76.2311 62.4138 + vertex -469.133 76.9895 66.1401 + vertex -470.402 75.6542 61.5515 + endloop + endfacet + facet normal 0.110955 -0.97059 0.213647 + outer loop + vertex -471.545 76.4543 65.2789 + vertex -470.203 77.6795 70.1484 + vertex -472.68 77.1755 69.1451 + endloop + endfacet + facet normal 0.167949 -0.966242 0.195369 + outer loop + vertex -466.851 77.5486 66.9438 + vertex -467.823 78.199 70.9965 + vertex -469.133 76.9895 66.1401 + endloop + endfacet + facet normal 0.116347 -0.97778 0.174383 + outer loop + vertex -470.203 77.6795 70.1484 + vertex -468.823 78.8187 75.6153 + vertex -471.346 78.187 73.7562 + endloop + endfacet + facet normal 0.177292 -0.97157 0.156906 + outer loop + vertex -465.557 78.7446 71.8142 + vertex -466.444 79.1997 75.6346 + vertex -467.823 78.199 70.9965 + endloop + endfacet + facet normal 0.172301 -0.972633 0.155873 + outer loop + vertex -465.557 78.7446 71.8142 + vertex -464.056 79.9036 77.3869 + vertex -466.444 79.1997 75.6346 + endloop + endfacet + facet normal 0.264871 -0.960788 0.0820412 + outer loop + vertex -460.746 81.5309 84.401 + vertex -456.048 83.6463 94.0081 + vertex -461.232 82.0953 92.5824 + endloop + endfacet + facet normal 0.31739 -0.946797 0.0532802 + outer loop + vertex -455.728 83.3535 86.9016 + vertex -456.048 83.6463 94.0081 + vertex -460.746 81.5309 84.401 + endloop + endfacet + facet normal 0.278272 -0.959956 0.032402 + outer loop + vertex -456.048 83.6463 94.0081 + vertex -455.796 83.9845 101.863 + vertex -461.232 82.0953 92.5824 + endloop + endfacet + facet normal 0.135792 -0.990448 0.0239346 + outer loop + vertex -460.469 83.0577 109.017 + vertex -459.415 83.3994 117.177 + vertex -465.727 82.3079 107.819 + endloop + endfacet + facet normal 0.127381 -0.990002 0.0605889 + outer loop + vertex -466.311 81.7307 99.6165 + vertex -460.469 83.0577 109.017 + vertex -465.727 82.3079 107.819 + endloop + endfacet + facet normal 0.149016 -0.985489 0.0812772 + outer loop + vertex -466.391 81.0192 91.1356 + vertex -461.135 82.6138 100.833 + vertex -466.311 81.7307 99.6165 + endloop + endfacet + facet normal 0.144391 -0.984411 0.100429 + outer loop + vertex -465.716 80.239 82.5184 + vertex -466.391 81.0192 91.1356 + vertex -471.201 79.233 80.5422 + endloop + endfacet + facet normal 0.0602169 -0.978258 0.198458 + outer loop + vertex -475.205 76.7086 68.0633 + vertex -473.76 77.8191 73.0988 + vertex -476.203 77.2543 71.056 + endloop + endfacet + facet normal 0.073588 -0.976494 0.202596 + outer loop + vertex -475.205 76.7086 68.0633 + vertex -476.203 77.2543 71.056 + vertex -477.726 76.3154 67.0837 + endloop + endfacet + facet normal 0.0630449 -0.970666 0.232017 + outer loop + vertex -476.656 75.4975 63.3709 + vertex -477.726 76.3154 67.0837 + vertex -479.26 75.1018 62.4231 + endloop + endfacet + facet normal 0.0493695 -0.963331 0.263736 + outer loop + vertex -477.953 74.1596 58.7369 + vertex -479.26 75.1018 62.4231 + vertex -480.529 73.7643 57.7754 + endloop + endfacet + facet normal 0.0361372 -0.954625 0.295609 + outer loop + vertex -478.977 72.8043 54.4854 + vertex -477.953 74.1596 58.7369 + vertex -480.529 73.7643 57.7754 + endloop + endfacet + facet normal 0.0360801 -0.954635 0.295585 + outer loop + vertex -478.977 72.8043 54.4854 + vertex -480.529 73.7643 57.7754 + vertex -481.485 72.4163 53.5383 + endloop + endfacet + facet normal 0.0567548 -0.955101 0.290793 + outer loop + vertex -476.484 73.247 55.4529 + vertex -477.953 74.1596 58.7369 + vertex -478.977 72.8043 54.4854 + endloop + endfacet + facet normal 0.0793521 -0.955057 0.285603 + outer loop + vertex -474.007 73.7393 56.4109 + vertex -475.376 74.6097 59.702 + vertex -476.484 73.247 55.4529 + endloop + endfacet + facet normal 0.102854 -0.954216 0.28088 + outer loop + vertex -471.57 74.2881 57.3832 + vertex -472.844 75.1096 60.6403 + vertex -474.007 73.7393 56.4109 + endloop + endfacet + facet normal 0.113479 -0.944341 0.308777 + outer loop + vertex -470.262 73.6327 54.8981 + vertex -469.213 74.878 58.3209 + vertex -471.57 74.2881 57.3832 + endloop + endfacet + facet normal 0.122605 -0.938698 0.322203 + outer loop + vertex -468.724 73.3624 53.5249 + vertex -467.916 74.2917 55.9248 + vertex -470.262 73.6327 54.8981 + endloop + endfacet + facet normal 0.0929984 -0.941304 0.324498 + outer loop + vertex -471.608 72.5811 52.2813 + vertex -472.69 73.0317 53.8984 + vertex -473.907 72.0947 51.5294 + endloop + endfacet + facet normal 0.0682784 -0.941371 0.330391 + outer loop + vertex -473.907 72.0947 51.5294 + vertex -475.067 72.4941 52.907 + vertex -476.257 71.5134 50.3586 + endloop + endfacet + facet normal 0.0490355 -0.940983 0.334884 + outer loop + vertex -476.257 71.5134 50.3586 + vertex -477.449 72.0174 51.9492 + vertex -478.522 71.134 49.6242 + endloop + endfacet + facet normal 0.0294689 -0.940226 0.339273 + outer loop + vertex -478.522 71.134 49.6242 + vertex -479.847 71.5882 50.9979 + vertex -480.916 70.6453 48.4778 + endloop + endfacet + facet normal 0.0123428 -0.939119 0.343371 + outer loop + vertex -480.916 70.6453 48.4778 + vertex -482.324 71.2051 50.0594 + vertex -483.4 70.3211 47.6804 + endloop + endfacet + facet normal -0.00325338 -0.9367 0.350117 + outer loop + vertex -483.4 70.3211 47.6804 + vertex -484.954 70.8387 49.0509 + vertex -486.258 69.7546 46.1382 + endloop + endfacet + facet normal -0.0226922 -0.933579 0.357652 + outer loop + vertex -486.258 69.7546 46.1382 + vertex -484.954 70.8387 49.0509 + vertex -487.728 70.5277 48.063 + endloop + endfacet + facet normal -0.0155145 -0.94199 0.335282 + outer loop + vertex -491.892 68.4973 42.5175 + vertex -488.074 69.029 44.1878 + vertex -490.33 68.8051 43.4544 + endloop + endfacet + facet normal -0.032231 -0.923905 0.381263 + outer loop + vertex -489.132 69.4512 45.1601 + vertex -488.265 69.142 44.4841 + vertex -486.258 69.7546 46.1382 + endloop + endfacet + facet normal -0.0564397 -0.929071 0.365569 + outer loop + vertex -492.77 70.2727 46.7428 + vertex -491.3 69.4321 44.8336 + vertex -490.395 70.3616 47.3355 + endloop + endfacet + facet normal -0.0497999 -0.938947 0.340438 + outer loop + vertex -490.395 70.3616 47.3355 + vertex -492.07 71.4643 50.1317 + vertex -492.77 70.2727 46.7428 + endloop + endfacet + facet normal -0.0230773 -0.933669 0.357394 + outer loop + vertex -486.258 69.7546 46.1382 + vertex -487.728 70.5277 48.063 + vertex -489.132 69.4512 45.1601 + endloop + endfacet + facet normal -0.0487714 -0.938799 0.340996 + outer loop + vertex -490.395 70.3616 47.3355 + vertex -489.427 71.5864 50.8459 + vertex -492.07 71.4643 50.1317 + endloop + endfacet + facet normal -0.0407211 -0.948901 0.312937 + outer loop + vertex -489.427 71.5864 50.8459 + vertex -491.045 72.7823 54.2617 + vertex -492.07 71.4643 50.1317 + endloop + endfacet + facet normal -0.0561688 -0.947037 0.316173 + outer loop + vertex -492.07 71.4643 50.1317 + vertex -491.045 72.7823 54.2617 + vertex -493.694 72.7002 53.5451 + endloop + endfacet + facet normal -0.0551326 -0.946945 0.316633 + outer loop + vertex -492.07 71.4643 50.1317 + vertex -493.694 72.7002 53.5451 + vertex -494.537 71.3543 49.3733 + endloop + endfacet + facet normal -0.0478574 -0.95686 0.28658 + outer loop + vertex -491.045 72.7823 54.2617 + vertex -492.361 74.0124 58.1489 + vertex -493.694 72.7002 53.5451 + endloop + endfacet + facet normal -0.0636716 -0.954738 0.290553 + outer loop + vertex -493.694 72.7002 53.5451 + vertex -492.361 74.0124 58.1489 + vertex -495.021 73.9773 57.4508 + endloop + endfacet + facet normal -0.0468686 -0.956813 0.2869 + outer loop + vertex -491.045 72.7823 54.2617 + vertex -489.695 74.1016 58.8822 + vertex -492.361 74.0124 58.1489 + endloop + endfacet + facet normal -0.0383897 -0.965611 0.257141 + outer loop + vertex -489.695 74.1016 58.8822 + vertex -490.712 75.2471 63.0318 + vertex -492.361 74.0124 58.1489 + endloop + endfacet + facet normal -0.0526932 -0.963763 0.261505 + outer loop + vertex -492.361 74.0124 58.1489 + vertex -490.712 75.2471 63.0318 + vertex -493.36 75.2054 62.3446 + endloop + endfacet + facet normal -0.0355872 -0.96554 0.257808 + outer loop + vertex -489.695 74.1016 58.8822 + vertex -488.095 75.3461 63.7637 + vertex -490.712 75.2471 63.0318 + endloop + endfacet + facet normal -0.0271462 -0.973129 0.228655 + outer loop + vertex -488.095 75.3461 63.7637 + vertex -488.915 76.3894 68.1065 + vertex -490.712 75.2471 63.0318 + endloop + endfacet + facet normal -0.0420192 -0.971439 0.233539 + outer loop + vertex -490.712 75.2471 63.0318 + vertex -488.915 76.3894 68.1065 + vertex -491.519 76.3425 67.443 + endloop + endfacet + facet normal -0.0250682 -0.973094 0.229039 + outer loop + vertex -488.095 75.3461 63.7637 + vertex -486.338 76.4911 68.8209 + vertex -488.915 76.3894 68.1065 + endloop + endfacet + facet normal -0.017623 -0.979015 0.203024 + outer loop + vertex -486.338 76.4911 68.8209 + vertex -487.067 77.4377 73.3223 + vertex -488.915 76.3894 68.1065 + endloop + endfacet + facet normal -0.0337832 -0.977452 0.208438 + outer loop + vertex -488.915 76.3894 68.1065 + vertex -487.067 77.4377 73.3223 + vertex -489.648 77.3914 72.6863 + endloop + endfacet + facet normal -0.0166081 -0.979 0.203185 + outer loop + vertex -486.338 76.4911 68.8209 + vertex -484.476 77.5455 74.0535 + vertex -487.067 77.4377 73.3223 + endloop + endfacet + facet normal -0.0092926 -0.983987 0.178 + outer loop + vertex -484.476 77.5455 74.0535 + vertex -485.043 78.4703 79.1359 + vertex -487.067 77.4377 73.3223 + endloop + endfacet + facet normal -0.0322053 -0.98209 0.185639 + outer loop + vertex -487.067 77.4377 73.3223 + vertex -485.043 78.4703 79.1359 + vertex -487.781 78.259 77.543 + endloop + endfacet + facet normal -0.00385963 -0.983915 0.178594 + outer loop + vertex -484.476 77.5455 74.0535 + vertex -482.529 78.442 79.0345 + vertex -485.043 78.4703 79.1359 + endloop + endfacet + facet normal -0.00491657 -0.988129 0.153545 + outer loop + vertex -482.529 78.442 79.0345 + vertex -481.286 79.5791 86.3921 + vertex -485.043 78.4703 79.1359 + endloop + endfacet + facet normal -0.0239215 -0.986318 0.163109 + outer loop + vertex -481.286 79.5791 86.3921 + vertex -486.585 79.4486 84.8257 + vertex -485.043 78.4703 79.1359 + endloop + endfacet + facet normal 0.0110937 -0.984873 0.172922 + outer loop + vertex -481.774 77.7324 74.9442 + vertex -482.529 78.442 79.0345 + vertex -484.476 77.5455 74.0535 + endloop + endfacet + facet normal 0.00135996 -0.980389 0.197069 + outer loop + vertex -483.741 76.6589 69.6376 + vertex -484.476 77.5455 74.0535 + vertex -486.338 76.4911 68.8209 + endloop + endfacet + facet normal -0.00834176 -0.97465 0.223581 + outer loop + vertex -485.507 75.5088 64.5697 + vertex -486.338 76.4911 68.8209 + vertex -488.095 75.3461 63.7637 + endloop + endfacet + facet normal -0.0191148 -0.967313 0.252863 + outer loop + vertex -487.061 74.2587 59.6819 + vertex -488.095 75.3461 63.7637 + vertex -489.695 74.1016 58.8822 + endloop + endfacet + facet normal -0.0309847 -0.958681 0.28279 + outer loop + vertex -488.357 72.9263 55.0442 + vertex -489.695 74.1016 58.8822 + vertex -491.045 72.7823 54.2617 + endloop + endfacet + facet normal -0.0130475 -0.942683 0.333436 + outer loop + vertex -484.954 70.8387 49.0509 + vertex -486.711 71.7905 51.6729 + vertex -487.728 70.5277 48.063 + endloop + endfacet + facet normal -0.0403347 -0.948861 0.313106 + outer loop + vertex -489.427 71.5864 50.8459 + vertex -488.357 72.9263 55.0442 + vertex -491.045 72.7823 54.2617 + endloop + endfacet + facet normal -0.00380484 -0.952233 0.305347 + outer loop + vertex -484.047 72.0773 52.6006 + vertex -485.704 73.1421 55.9005 + vertex -486.711 71.7905 51.6729 + endloop + endfacet + facet normal -0.0289311 -0.958546 0.283465 + outer loop + vertex -488.357 72.9263 55.0442 + vertex -487.061 74.2587 59.6819 + vertex -489.695 74.1016 58.8822 + endloop + endfacet + facet normal 0.00687411 -0.961619 0.274301 + outer loop + vertex -483.101 73.4251 56.8276 + vertex -484.457 74.4812 60.5639 + vertex -485.704 73.1421 55.9005 + endloop + endfacet + facet normal -0.0180081 -0.967265 0.25313 + outer loop + vertex -487.061 74.2587 59.6819 + vertex -485.507 75.5088 64.5697 + vertex -488.095 75.3461 63.7637 + endloop + endfacet + facet normal 0.0198661 -0.969992 0.242326 + outer loop + vertex -481.868 74.7649 61.487 + vertex -482.907 75.7346 65.4538 + vertex -484.457 74.4812 60.5639 + endloop + endfacet + facet normal -0.00740262 -0.974617 0.223757 + outer loop + vertex -485.507 75.5088 64.5697 + vertex -483.741 76.6589 69.6376 + vertex -486.338 76.4911 68.8209 + endloop + endfacet + facet normal 0.032626 -0.976882 0.211274 + outer loop + vertex -480.284 76.0103 66.3234 + vertex -481.057 76.8882 70.502 + vertex -482.907 75.7346 65.4538 + endloop + endfacet + facet normal 0.00274626 -0.980341 0.19729 + outer loop + vertex -483.741 76.6589 69.6376 + vertex -481.774 77.7324 74.9442 + vertex -484.476 77.5455 74.0535 + endloop + endfacet + facet normal 0.0455718 -0.982306 0.181653 + outer loop + vertex -478.37 77.1216 71.0905 + vertex -478.776 77.9844 75.8577 + vertex -481.057 76.8882 70.502 + endloop + endfacet + facet normal 0.0053391 -0.9851 0.171899 + outer loop + vertex -481.774 77.7324 74.9442 + vertex -479.488 78.8275 81.1491 + vertex -482.529 78.442 79.0345 + endloop + endfacet + facet normal 0.0542402 -0.986791 0.152648 + outer loop + vertex -475.738 78.1191 75.649 + vertex -475.602 79.1167 82.0493 + vertex -478.776 77.9844 75.8577 + endloop + endfacet + facet normal 0.0476657 -0.990211 0.13119 + outer loop + vertex -475.602 79.1167 82.0493 + vertex -471.366 80.3925 90.1399 + vertex -476.11 80.023 89.0746 + endloop + endfacet + facet normal 0.0216123 -0.988581 0.149131 + outer loop + vertex -482.529 78.442 79.0345 + vertex -479.488 78.8275 81.1491 + vertex -481.286 79.5791 86.3921 + endloop + endfacet + facet normal 0.0258576 -0.993067 0.114668 + outer loop + vertex -476.11 80.023 89.0746 + vertex -471.344 81.2115 98.2932 + vertex -476.43 80.8974 96.7196 + endloop + endfacet + facet normal 0.035885 -0.995918 0.0828286 + outer loop + vertex -471.344 81.2115 98.2932 + vertex -470.908 81.9068 106.465 + vertex -476.43 80.8974 96.7196 + endloop + endfacet + facet normal 0.0367832 -0.997127 0.0662107 + outer loop + vertex -470.908 81.9068 106.465 + vertex -464.777 82.7704 116.063 + vertex -470.081 82.4944 114.853 + endloop + endfacet + facet normal 0.0438009 -0.998401 0.0357459 + outer loop + vertex -464.777 82.7704 116.063 + vertex -463.603 83.121 124.418 + vertex -470.081 82.4944 114.853 + endloop + endfacet + facet normal 0.0717454 -0.997273 0.0173029 + outer loop + vertex -463.603 83.121 124.418 + vertex -456.725 83.7772 133.717 + vertex -462.305 83.3604 132.835 + endloop + endfacet + facet normal 0.0556739 -0.998427 0.00659446 + outer loop + vertex -462.305 83.3604 132.835 + vertex -455.219 83.8166 142.077 + vertex -460.925 83.4932 141.279 + endloop + endfacet + facet normal 0.0419488 -0.999111 -0.00427259 + outer loop + vertex -460.925 83.4932 141.279 + vertex -453.607 83.7612 150.458 + vertex -459.466 83.5182 149.755 + endloop + endfacet + facet normal 0.029476 -0.999451 -0.015147 + outer loop + vertex -459.466 83.5182 149.755 + vertex -451.894 83.6036 158.852 + vertex -457.92 83.435 158.249 + endloop + endfacet + facet normal 0.0188524 -0.999464 -0.0267477 + outer loop + vertex -457.92 83.435 158.249 + vertex -450.086 83.3425 167.229 + vertex -456.29 83.2389 166.728 + endloop + endfacet + facet normal 0.00972136 -0.999195 -0.0389268 + outer loop + vertex -456.29 83.2389 166.728 + vertex -448.202 82.9738 175.553 + vertex -454.589 82.9272 175.152 + endloop + endfacet + facet normal 0.00286577 -0.998629 -0.0522727 + outer loop + vertex -454.589 82.9272 175.152 + vertex -446.253 82.4989 183.791 + vertex -452.837 82.4951 183.504 + endloop + endfacet + facet normal -0.00292324 -0.997799 -0.066252 + outer loop + vertex -452.837 82.4951 183.504 + vertex -444.26 81.9093 191.947 + vertex -451.044 81.9405 191.777 + endloop + endfacet + facet normal -0.00665123 -0.996633 -0.0817234 + outer loop + vertex -451.044 81.9405 191.777 + vertex -442.223 81.2062 200.014 + vertex -449.224 81.2555 199.982 + endloop + endfacet + facet normal -0.0099262 -0.995189 -0.0974664 + outer loop + vertex -449.224 81.2555 199.982 + vertex -440.156 80.3799 208 + vertex -447.37 80.4411 208.109 + endloop + endfacet + facet normal -0.0125123 -0.993375 -0.114237 + outer loop + vertex -447.37 80.4411 208.109 + vertex -438.06 79.4288 215.893 + vertex -445.49 79.492 216.157 + endloop + endfacet + facet normal -0.0142206 -0.991186 -0.131712 + outer loop + vertex -445.49 79.492 216.157 + vertex -435.929 78.356 223.673 + vertex -443.589 78.4072 224.115 + endloop + endfacet + facet normal -0.0157479 -0.988793 -0.148459 + outer loop + vertex -443.589 78.4072 224.115 + vertex -433.764 77.1695 231.316 + vertex -441.655 77.2006 231.946 + endloop + endfacet + facet normal -0.0178144 -0.986246 -0.16432 + outer loop + vertex -441.655 77.2006 231.946 + vertex -431.552 75.8759 238.801 + vertex -439.648 75.8883 239.605 + endloop + endfacet + facet normal -0.0569851 -0.983823 -0.16984 + outer loop + vertex -447.56 76.2459 240.217 + vertex -437.487 74.48 247.066 + vertex -445.583 74.8083 247.881 + endloop + endfacet + facet normal -0.0193505 -0.983507 -0.179835 + outer loop + vertex -431.552 75.8759 238.801 + vertex -429.215 74.4998 246.076 + vertex -439.648 75.8883 239.605 + endloop + endfacet + facet normal -0.0200688 -0.980375 -0.196116 + outer loop + vertex -437.487 74.48 247.066 + vertex -426.658 73.0454 253.129 + vertex -435.092 72.9703 254.368 + endloop + endfacet + facet normal 0.0236065 -0.977289 -0.210592 + outer loop + vertex -420.618 75.0061 244.69 + vertex -417.938 73.5891 251.567 + vertex -429.215 74.4998 246.076 + endloop + endfacet + facet normal -0.0222641 -0.977259 -0.210876 + outer loop + vertex -426.658 73.0454 253.129 + vertex -423.824 71.5001 259.992 + vertex -435.092 72.9703 254.368 + endloop + endfacet + facet normal -0.0582817 -0.981242 -0.183759 + outer loop + vertex -437.487 74.48 247.066 + vertex -435.092 72.9703 254.368 + vertex -445.583 74.8083 247.881 + endloop + endfacet + facet normal -0.0857396 -0.983014 -0.162272 + outer loop + vertex -447.56 76.2459 240.217 + vertex -445.583 74.8083 247.881 + vertex -455.473 76.8361 240.822 + endloop + endfacet + facet normal -0.0848955 -0.985165 -0.149137 + outer loop + vertex -457.092 78.1854 232.831 + vertex -447.56 76.2459 240.217 + vertex -455.473 76.8361 240.822 + endloop + endfacet + facet normal -0.0852638 -0.987406 -0.133268 + outer loop + vertex -458.609 79.4172 224.674 + vertex -449.37 77.5784 232.388 + vertex -457.092 78.1854 232.831 + endloop + endfacet + facet normal -0.0858558 -0.989551 -0.115833 + outer loop + vertex -460.08 80.5148 216.388 + vertex -451.089 78.7987 224.385 + vertex -458.609 79.4172 224.674 + endloop + endfacet + facet normal -0.0865143 -0.991495 -0.0972301 + outer loop + vertex -461.538 81.4614 208.032 + vertex -452.772 79.8896 216.261 + vertex -460.08 80.5148 216.388 + endloop + endfacet + facet normal -0.0868468 -0.993138 -0.0783263 + outer loop + vertex -462.989 82.2507 199.634 + vertex -454.437 80.8386 208.055 + vertex -461.538 81.4614 208.032 + endloop + endfacet + facet normal -0.0865429 -0.994426 -0.0602208 + outer loop + vertex -464.425 82.8871 191.19 + vertex -456.086 81.6405 199.79 + vertex -462.989 82.2507 199.634 + endloop + endfacet + facet normal -0.0854649 -0.995412 -0.0430212 + outer loop + vertex -465.839 83.3759 182.69 + vertex -457.714 82.2989 191.466 + vertex -464.425 82.8871 191.19 + endloop + endfacet + facet normal -0.0831949 -0.996169 -0.0269359 + outer loop + vertex -467.225 83.723 174.131 + vertex -459.313 82.8204 183.077 + vertex -465.839 83.3759 182.69 + endloop + endfacet + facet normal -0.0798156 -0.996742 -0.011634 + outer loop + vertex -468.573 83.9316 165.508 + vertex -460.878 83.2091 174.617 + vertex -467.225 83.723 174.131 + endloop + endfacet + facet normal -0.0749231 -0.997185 0.0028155 + outer loop + vertex -469.87 84.0046 156.839 + vertex -462.397 83.4692 166.089 + vertex -468.573 83.9316 165.508 + endloop + endfacet + facet normal -0.0685956 -0.997507 0.0165881 + outer loop + vertex -471.107 83.9452 148.155 + vertex -463.858 83.6023 157.513 + vertex -469.87 84.0046 156.839 + endloop + endfacet + facet normal -0.0605732 -0.997725 0.0296073 + outer loop + vertex -472.289 83.76 139.494 + vertex -465.248 83.6123 148.923 + vertex -471.107 83.9452 148.155 + endloop + endfacet + facet normal -0.0506266 -0.997837 0.04193 + outer loop + vertex -473.43 83.4561 130.885 + vertex -466.567 83.506 140.359 + vertex -472.289 83.76 139.494 + endloop + endfacet + facet normal -0.0392994 -0.997738 0.0545381 + outer loop + vertex -474.517 83.0304 122.313 + vertex -467.826 83.2872 131.834 + vertex -473.43 83.4561 130.885 + endloop + endfacet + facet normal -0.0266422 -0.997295 0.0684989 + outer loop + vertex -475.473 82.4667 113.735 + vertex -469.016 82.9534 123.333 + vertex -474.517 83.0304 122.313 + endloop + endfacet + facet normal -0.0256913 -0.996024 0.0853049 + outer loop + vertex -476.163 81.7492 105.149 + vertex -475.473 82.4667 113.735 + vertex -481.598 81.7908 103.999 + endloop + endfacet + facet normal -0.0322604 -0.992672 0.116457 + outer loop + vertex -481.701 80.7605 95.1874 + vertex -476.163 81.7492 105.149 + vertex -481.598 81.7908 103.999 + endloop + endfacet + facet normal -0.0147341 -0.991084 0.132421 + outer loop + vertex -481.286 79.5791 86.3921 + vertex -481.701 80.7605 95.1874 + vertex -486.585 79.4486 84.8257 + endloop + endfacet + facet normal -0.0194701 -0.986219 0.164298 + outer loop + vertex -487.781 78.259 77.543 + vertex -485.043 78.4703 79.1359 + vertex -486.585 79.4486 84.8257 + endloop + endfacet + facet normal -0.0282486 -0.982085 0.186308 + outer loop + vertex -487.067 77.4377 73.3223 + vertex -487.781 78.259 77.543 + vertex -489.648 77.3914 72.6863 + endloop + endfacet + facet normal -0.0354472 -0.97745 0.208172 + outer loop + vertex -488.915 76.3894 68.1065 + vertex -489.648 77.3914 72.6863 + vertex -491.519 76.3425 67.443 + endloop + endfacet + facet normal -0.0451643 -0.971436 0.232963 + outer loop + vertex -490.712 75.2471 63.0318 + vertex -491.519 76.3425 67.443 + vertex -493.36 75.2054 62.3446 + endloop + endfacet + facet normal -0.0557404 -0.963786 0.260786 + outer loop + vertex -492.361 74.0124 58.1489 + vertex -493.36 75.2054 62.3446 + vertex -495.021 73.9773 57.4508 + endloop + endfacet + facet normal -0.0614768 -0.954662 0.291274 + outer loop + vertex -493.694 72.7002 53.5451 + vertex -495.021 73.9773 57.4508 + vertex -496.239 72.6296 52.7766 + endloop + endfacet + facet normal -0.0701369 -0.94513 0.319078 + outer loop + vertex -494.537 71.3543 49.3733 + vertex -493.694 72.7002 53.5451 + vertex -496.239 72.6296 52.7766 + endloop + endfacet + facet normal -0.0635771 -0.93729 0.342704 + outer loop + vertex -492.77 70.2727 46.7428 + vertex -492.07 71.4643 50.1317 + vertex -494.537 71.3543 49.3733 + endloop + endfacet + facet normal -0.0556878 -0.928916 0.36608 + outer loop + vertex -491.3 69.4321 44.8336 + vertex -492.77 70.2727 46.7428 + vertex -493.204 69.3646 44.3726 + endloop + endfacet + facet normal -0.0608769 -0.920376 0.386267 + outer loop + vertex -491.981 68.862 43.3678 + vertex -491.3 69.4321 44.8336 + vertex -493.204 69.3646 44.3726 + endloop + endfacet + facet normal -0.0520641 -0.920442 0.387396 + outer loop + vertex -493.289 68.5018 42.3361 + vertex -490.33 68.8051 43.4544 + vertex -491.981 68.862 43.3678 + endloop + endfacet + facet normal -0.0537544 -0.918656 0.391384 + outer loop + vertex -490.33 68.8051 43.4544 + vertex -493.289 68.5018 42.3361 + vertex -491.892 68.4973 42.5175 + endloop + endfacet + facet normal -0.0519684 -0.924556 0.377487 + outer loop + vertex -495.243 68.1764 41.2701 + vertex -491.892 68.4973 42.5175 + vertex -493.289 68.5018 42.3361 + endloop + endfacet + facet normal -0.0895129 -0.879811 0.46682 + outer loop + vertex -491.892 68.4973 42.5175 + vertex -495.243 68.1764 41.2701 + vertex -493.873 68.1962 41.5701 + endloop + endfacet + facet normal -0.0440905 -0.92178 0.385199 + outer loop + vertex -493.873 68.1962 41.5701 + vertex -490.537 68.6115 42.9458 + vertex -491.892 68.4973 42.5175 + endloop + endfacet + facet normal -0.0824715 -0.880958 0.465953 + outer loop + vertex -492.713 68.0964 41.5868 + vertex -490.537 68.6115 42.9458 + vertex -493.873 68.1962 41.5701 + endloop + endfacet + facet normal -0.082603 -0.883208 0.461649 + outer loop + vertex -492.713 68.0964 41.5868 + vertex -493.873 68.1962 41.5701 + vertex -495.129 67.7322 40.4575 + endloop + endfacet + facet normal -0.0976649 -0.874527 0.475041 + outer loop + vertex -495.129 67.7322 40.4575 + vertex -493.873 68.1962 41.5701 + vertex -496.302 67.9342 40.5885 + endloop + endfacet + facet normal -0.0988926 -0.877685 0.468924 + outer loop + vertex -495.129 67.7322 40.4575 + vertex -496.302 67.9342 40.5885 + vertex -496.702 67.6902 40.0473 + endloop + endfacet + facet normal -0.0998729 -0.875667 0.472476 + outer loop + vertex -495.129 67.7322 40.4575 + vertex -496.702 67.6902 40.0473 + vertex -495.274 67.2075 39.4546 + endloop + endfacet + facet normal -0.0946171 -0.87644 0.472124 + outer loop + vertex -494.3 67.1137 39.4756 + vertex -495.129 67.7322 40.4575 + vertex -495.274 67.2075 39.4546 + endloop + endfacet + facet normal -0.0942758 -0.870412 0.483214 + outer loop + vertex -492.746 66.3849 38.466 + vertex -494.3 67.1137 39.4756 + vertex -495.274 67.2075 39.4546 + endloop + endfacet + facet normal -0.0999122 -0.875403 0.472955 + outer loop + vertex -492.746 66.3849 38.466 + vertex -495.274 67.2075 39.4546 + vertex -494.377 66.738 38.775 + endloop + endfacet + facet normal -0.0888729 -0.856079 0.509147 + outer loop + vertex -489.983 65.4437 37.3658 + vertex -492.746 66.3849 38.466 + vertex -494.377 66.738 38.775 + endloop + endfacet + facet normal -0.105362 -0.874064 0.474249 + outer loop + vertex -489.983 65.4437 37.3658 + vertex -494.377 66.738 38.775 + vertex -492.742 66.1796 38.1092 + endloop + endfacet + facet normal -0.0849265 -0.852415 0.515923 + outer loop + vertex -488.745 65.2865 37.3099 + vertex -492.746 66.3849 38.466 + vertex -489.983 65.4437 37.3658 + endloop + endfacet + facet normal -0.0806455 -0.830974 0.550436 + outer loop + vertex -489.983 65.4437 37.3658 + vertex -484.301 63.9096 35.8822 + vertex -488.745 65.2865 37.3099 + endloop + endfacet + facet normal -0.0910728 -0.845738 0.525769 + outer loop + vertex -484.301 63.9096 35.8822 + vertex -489.983 65.4437 37.3658 + vertex -486.939 64.5184 36.4045 + endloop + endfacet + facet normal -0.0390069 -0.778742 0.626131 + outer loop + vertex -492.742 66.1796 38.1092 + vertex -486.939 64.5184 36.4045 + vertex -489.983 65.4437 37.3658 + endloop + endfacet + facet normal -0.0907001 -0.859632 0.502798 + outer loop + vertex -488.745 65.2865 37.3099 + vertex -492.103 66.4806 38.7456 + vertex -492.746 66.3849 38.466 + endloop + endfacet + facet normal -0.0755686 -0.846387 0.527179 + outer loop + vertex -488.991 65.6672 37.8858 + vertex -492.103 66.4806 38.7456 + vertex -488.745 65.2865 37.3099 + endloop + endfacet + facet normal -0.0900955 -0.848104 0.522114 + outer loop + vertex -488.991 65.6672 37.8858 + vertex -488.745 65.2865 37.3099 + vertex -483.458 64.0759 36.2557 + endloop + endfacet + facet normal -0.0834586 -0.839764 0.536499 + outer loop + vertex -488.991 65.6672 37.8858 + vertex -483.458 64.0759 36.2557 + vertex -487.577 65.7209 38.1897 + endloop + endfacet + facet normal -0.0775347 -0.855628 0.511751 + outer loop + vertex -487.577 65.7209 38.1897 + vertex -491.368 66.7212 39.2878 + vertex -488.991 65.6672 37.8858 + endloop + endfacet + facet normal -0.0828382 -0.862323 0.499537 + outer loop + vertex -487.577 65.7209 38.1897 + vertex -490.256 66.9981 39.9502 + vertex -491.368 66.7212 39.2878 + endloop + endfacet + facet normal -0.0739351 -0.869854 0.487738 + outer loop + vertex -490.256 66.9981 39.9502 + vertex -492.406 67.5539 40.6157 + vertex -491.368 66.7212 39.2878 + endloop + endfacet + facet normal -0.0840124 -0.872423 0.481477 + outer loop + vertex -491.368 66.7212 39.2878 + vertex -492.406 67.5539 40.6157 + vertex -493.591 67.3905 40.1128 + endloop + endfacet + facet normal -0.078741 -0.867298 0.491522 + outer loop + vertex -491.368 66.7212 39.2878 + vertex -493.591 67.3905 40.1128 + vertex -492.103 66.4806 38.7456 + endloop + endfacet + facet normal -0.0915695 -0.872071 0.480736 + outer loop + vertex -492.103 66.4806 38.7456 + vertex -493.591 67.3905 40.1128 + vertex -494.3 67.1137 39.4756 + endloop + endfacet + facet normal -0.0770024 -0.880581 0.467597 + outer loop + vertex -492.406 67.5539 40.6157 + vertex -492.713 68.0964 41.5868 + vertex -493.591 67.3905 40.1128 + endloop + endfacet + facet normal -0.0751513 -0.880465 0.468118 + outer loop + vertex -492.406 67.5539 40.6157 + vertex -490.921 67.8884 41.4833 + vertex -492.713 68.0964 41.5868 + endloop + endfacet + facet normal -0.0756129 -0.882495 0.464205 + outer loop + vertex -489.176 68.567 43.0575 + vertex -492.713 68.0964 41.5868 + vertex -490.921 67.8884 41.4833 + endloop + endfacet + facet normal -0.0646583 -0.888352 0.454588 + outer loop + vertex -489.073 68.067 42.0952 + vertex -489.176 68.567 43.0575 + vertex -490.921 67.8884 41.4833 + endloop + endfacet + facet normal -0.0703663 -0.880159 0.469435 + outer loop + vertex -488.775 67.276 40.6566 + vertex -489.073 68.067 42.0952 + vertex -490.921 67.8884 41.4833 + endloop + endfacet + facet normal -0.0647763 -0.874864 0.480018 + outer loop + vertex -488.775 67.276 40.6566 + vertex -490.921 67.8884 41.4833 + vertex -490.256 66.9981 39.9502 + endloop + endfacet + facet normal -0.0742447 -0.865121 0.496037 + outer loop + vertex -487.181 66.2119 39.0393 + vertex -488.775 67.276 40.6566 + vertex -490.256 66.9981 39.9502 + endloop + endfacet + facet normal -0.0618667 -0.860705 0.505331 + outer loop + vertex -485.224 66.3072 39.4412 + vertex -488.775 67.276 40.6566 + vertex -487.181 66.2119 39.0393 + endloop + endfacet + facet normal -0.070402 -0.837779 0.541452 + outer loop + vertex -487.181 66.2119 39.0393 + vertex -481.945 64.5111 37.0886 + vertex -485.224 66.3072 39.4412 + endloop + endfacet + facet normal -0.0789947 -0.846704 0.526167 + outer loop + vertex -487.181 66.2119 39.0393 + vertex -487.577 65.7209 38.1897 + vertex -481.945 64.5111 37.0886 + endloop + endfacet + facet normal -0.0683718 -0.867881 0.492045 + outer loop + vertex -485.224 66.3072 39.4412 + vertex -487.028 67.5579 41.3967 + vertex -488.775 67.276 40.6566 + endloop + endfacet + facet normal -0.0431794 -0.859237 0.509752 + outer loop + vertex -484.274 66.8411 40.4217 + vertex -487.028 67.5579 41.3967 + vertex -485.224 66.3072 39.4412 + endloop + endfacet + facet normal -0.0627383 -0.849701 0.523519 + outer loop + vertex -484.274 66.8411 40.4217 + vertex -485.224 66.3072 39.4412 + vertex -479.83 65.1623 38.2295 + endloop + endfacet + facet normal -0.054792 -0.843265 0.534698 + outer loop + vertex -484.274 66.8411 40.4217 + vertex -479.83 65.1623 38.2295 + vertex -482.149 66.9856 40.8673 + endloop + endfacet + facet normal -0.0432142 -0.871419 0.488632 + outer loop + vertex -482.149 66.9856 40.8673 + vertex -485.212 67.8593 42.1546 + vertex -484.274 66.8411 40.4217 + endloop + endfacet + facet normal -0.0498023 -0.87746 0.477058 + outer loop + vertex -482.149 66.9856 40.8673 + vertex -483.375 68.1779 42.9324 + vertex -485.212 67.8593 42.1546 + endloop + endfacet + facet normal -0.0363805 -0.891693 0.451176 + outer loop + vertex -483.375 68.1779 42.9324 + vertex -485.123 68.6085 43.6425 + vertex -485.212 67.8593 42.1546 + endloop + endfacet + facet normal -0.0517233 -0.890718 0.451604 + outer loop + vertex -485.212 67.8593 42.1546 + vertex -485.123 68.6085 43.6425 + vertex -487.145 68.4051 43.0096 + endloop + endfacet + facet normal -0.0457712 -0.885754 0.461893 + outer loop + vertex -485.212 67.8593 42.1546 + vertex -487.145 68.4051 43.0096 + vertex -487.028 67.5579 41.3967 + endloop + endfacet + facet normal -0.0631647 -0.885431 0.460458 + outer loop + vertex -487.028 67.5579 41.3967 + vertex -487.145 68.4051 43.0096 + vertex -489.073 68.067 42.0952 + endloop + endfacet + facet normal -0.0487316 -0.894989 0.443418 + outer loop + vertex -485.123 68.6085 43.6425 + vertex -485.095 69.1044 44.6465 + vertex -487.145 68.4051 43.0096 + endloop + endfacet + facet normal -0.0416608 -0.895356 0.443399 + outer loop + vertex -485.123 68.6085 43.6425 + vertex -483.179 68.9911 44.5977 + vertex -485.095 69.1044 44.6465 + endloop + endfacet + facet normal -0.0410185 -0.89592 0.442318 + outer loop + vertex -483.375 68.1779 42.9324 + vertex -483.179 68.9911 44.5977 + vertex -485.123 68.6085 43.6425 + endloop + endfacet + facet normal -0.0240896 -0.897206 0.440956 + outer loop + vertex -481.546 68.5231 43.7347 + vertex -483.179 68.9911 44.5977 + vertex -483.375 68.1779 42.9324 + endloop + endfacet + facet normal -0.0364106 -0.885162 0.463855 + outer loop + vertex -480.97 67.5494 41.9219 + vertex -481.546 68.5231 43.7347 + vertex -483.375 68.1779 42.9324 + endloop + endfacet + facet normal -0.0228595 -0.88375 0.467401 + outer loop + vertex -478.828 67.757 42.4192 + vertex -481.546 68.5231 43.7347 + vertex -480.97 67.5494 41.9219 + endloop + endfacet + facet normal -0.0265553 -0.886739 0.461507 + outer loop + vertex -478.828 67.757 42.4192 + vertex -479.603 68.918 44.6053 + vertex -481.546 68.5231 43.7347 + endloop + endfacet + facet normal -0.0104403 -0.901666 0.432308 + outer loop + vertex -479.603 68.918 44.6053 + vertex -481.203 69.2717 45.3044 + vertex -481.546 68.5231 43.7347 + endloop + endfacet + facet normal -0.0083593 -0.899837 0.436145 + outer loop + vertex -479.603 68.918 44.6053 + vertex -478.935 69.7995 46.4367 + vertex -481.203 69.2717 45.3044 + endloop + endfacet + facet normal -0.0103555 -0.898234 0.439396 + outer loop + vertex -481.203 69.2717 45.3044 + vertex -478.935 69.7995 46.4367 + vertex -480.929 69.7841 46.3582 + endloop + endfacet + facet normal -0.0314466 -0.895665 0.443616 + outer loop + vertex -481.203 69.2717 45.3044 + vertex -480.929 69.7841 46.3582 + vertex -483.179 68.9911 44.5977 + endloop + endfacet + facet normal 0.00817904 -0.902196 0.431249 + outer loop + vertex -477.317 69.3943 45.5584 + vertex -478.935 69.7995 46.4367 + vertex -479.603 68.918 44.6053 + endloop + endfacet + facet normal -0.00477079 -0.889886 0.456158 + outer loop + vertex -477.394 68.3775 43.5739 + vertex -477.317 69.3943 45.5584 + vertex -479.603 68.918 44.6053 + endloop + endfacet + facet normal 0.00747579 -0.890064 0.455773 + outer loop + vertex -474.979 68.6543 44.075 + vertex -477.317 69.3943 45.5584 + vertex -477.394 68.3775 43.5739 + endloop + endfacet + facet normal 0.0132583 -0.886264 0.46299 + outer loop + vertex -474.979 68.6543 44.075 + vertex -474.604 69.8287 46.3122 + vertex -477.317 69.3943 45.5584 + endloop + endfacet + facet normal 0.0241818 -0.901368 0.432379 + outer loop + vertex -474.604 69.8287 46.3122 + vertex -475.75 70.4503 47.6721 + vertex -477.317 69.3943 45.5584 + endloop + endfacet + facet normal 0.0345567 -0.897621 0.43941 + outer loop + vertex -475.75 70.4503 47.6721 + vertex -474.604 69.8287 46.3122 + vertex -472.807 70.8691 48.2961 + endloop + endfacet + facet normal 0.031579 -0.892472 0.449996 + outer loop + vertex -472.807 70.8691 48.2961 + vertex -471.708 71.8187 50.1024 + vertex -475.75 70.4503 47.6721 + endloop + endfacet + facet normal 0.0349522 -0.894567 0.445565 + outer loop + vertex -475.75 70.4503 47.6721 + vertex -471.708 71.8187 50.1024 + vertex -476.598 70.7043 48.2485 + endloop + endfacet + facet normal 0.0192487 -0.904189 0.426698 + outer loop + vertex -475.75 70.4503 47.6721 + vertex -476.598 70.7043 48.2485 + vertex -478.935 69.7995 46.4367 + endloop + endfacet + facet normal 0.0737204 -0.928578 0.363743 + outer loop + vertex -471.708 71.8187 50.1024 + vertex -472.964 71.7268 50.1224 + vertex -476.598 70.7043 48.2485 + endloop + endfacet + facet normal 0.0179783 -0.891911 0.451853 + outer loop + vertex -476.598 70.7043 48.2485 + vertex -472.964 71.7268 50.1224 + vertex -477.701 70.6324 48.1505 + endloop + endfacet + facet normal 0.0253339 -0.92046 0.390015 + outer loop + vertex -476.598 70.7043 48.2485 + vertex -477.701 70.6324 48.1505 + vertex -480.929 69.7841 46.3582 + endloop + endfacet + facet normal -0.0277652 -0.883266 0.468049 + outer loop + vertex -480.929 69.7841 46.3582 + vertex -477.701 70.6324 48.1505 + vertex -482.12 69.8041 46.3254 + endloop + endfacet + facet normal -0.0269363 -0.904865 0.424846 + outer loop + vertex -480.929 69.7841 46.3582 + vertex -482.12 69.8041 46.3254 + vertex -485.095 69.1044 44.6465 + endloop + endfacet + facet normal -0.0502104 -0.887169 0.458704 + outer loop + vertex -485.095 69.1044 44.6465 + vertex -482.12 69.8041 46.3254 + vertex -486.465 69.1454 44.5758 + endloop + endfacet + facet normal -0.0491962 -0.900972 0.43108 + outer loop + vertex -485.095 69.1044 44.6465 + vertex -486.465 69.1454 44.5758 + vertex -489.176 68.567 43.0575 + endloop + endfacet + facet normal -0.066509 -0.887121 0.456719 + outer loop + vertex -489.176 68.567 43.0575 + vertex -486.465 69.1454 44.5758 + vertex -490.537 68.6115 42.9458 + endloop + endfacet + facet normal -0.00370006 -0.932793 0.360395 + outer loop + vertex -486.465 69.1454 44.5758 + vertex -482.12 69.8041 46.3254 + vertex -483.565 69.7951 46.2872 + endloop + endfacet + facet normal -0.00480343 -0.917158 0.398495 + outer loop + vertex -478.931 70.6015 48.1991 + vertex -483.565 69.7951 46.2872 + vertex -482.12 69.8041 46.3254 + endloop + endfacet + facet normal 0.0369074 -0.940609 0.33748 + outer loop + vertex -482.12 69.8041 46.3254 + vertex -477.701 70.6324 48.1505 + vertex -478.931 70.6015 48.1991 + endloop + endfacet + facet normal 0.0380869 -0.925445 0.376962 + outer loop + vertex -474.412 71.5484 50.067 + vertex -478.931 70.6015 48.1991 + vertex -477.701 70.6324 48.1505 + endloop + endfacet + facet normal 0.107347 -0.956077 0.27275 + outer loop + vertex -477.701 70.6324 48.1505 + vertex -472.964 71.7268 50.1224 + vertex -474.412 71.5484 50.067 + endloop + endfacet + facet normal 0.103697 -0.9414 0.320955 + outer loop + vertex -470.074 72.615 51.794 + vertex -474.412 71.5484 50.067 + vertex -472.964 71.7268 50.1224 + endloop + endfacet + facet normal 0.0727392 -0.901458 0.426711 + outer loop + vertex -472.964 71.7268 50.1224 + vertex -471.708 71.8187 50.1024 + vertex -466.885 73.4208 52.6648 + endloop + endfacet + facet normal 0.060977 -0.898285 0.435161 + outer loop + vertex -472.807 70.8691 48.2961 + vertex -469.062 71.8833 49.865 + vertex -471.708 71.8187 50.1024 + endloop + endfacet + facet normal 0.0499124 -0.888849 0.455473 + outer loop + vertex -469.062 71.8833 49.865 + vertex -472.807 70.8691 48.2961 + vertex -470.89 70.0633 46.5136 + endloop + endfacet + facet normal 0.0699342 -0.89213 0.446333 + outer loop + vertex -470.89 70.0633 46.5136 + vertex -466.397 71.2806 48.2429 + vertex -469.062 71.8833 49.865 + endloop + endfacet + facet normal 0.0787471 -0.885314 0.458278 + outer loop + vertex -464.52 73.3313 51.8818 + vertex -469.062 71.8833 49.865 + vertex -466.397 71.2806 48.2429 + endloop + endfacet + facet normal 0.114484 -0.889563 0.442235 + outer loop + vertex -466.397 71.2806 48.2429 + vertex -462.359 72.7099 50.0723 + vertex -464.52 73.3313 51.8818 + endloop + endfacet + facet normal 0.126055 -0.88227 0.453552 + outer loop + vertex -460.309 74.925 53.8117 + vertex -464.52 73.3313 51.8818 + vertex -462.359 72.7099 50.0723 + endloop + endfacet + facet normal 0.169467 -0.885863 0.431889 + outer loop + vertex -462.359 72.7099 50.0723 + vertex -458.582 74.2832 51.8178 + vertex -460.309 74.925 53.8117 + endloop + endfacet + facet normal 0.189271 -0.875021 0.445551 + outer loop + vertex -456.408 76.6495 55.5412 + vertex -460.309 74.925 53.8117 + vertex -458.582 74.2832 51.8178 + endloop + endfacet + facet normal 0.22942 -0.876564 0.423087 + outer loop + vertex -458.582 74.2832 51.8178 + vertex -454.98 76.0316 53.487 + vertex -456.408 76.6495 55.5412 + endloop + endfacet + facet normal 0.255968 -0.862165 0.437209 + outer loop + vertex -452.721 78.5815 57.1924 + vertex -456.408 76.6495 55.5412 + vertex -454.98 76.0316 53.487 + endloop + endfacet + facet normal 0.291846 -0.861727 0.415033 + outer loop + vertex -454.98 76.0316 53.487 + vertex -451.42 78.0081 55.0872 + vertex -452.721 78.5815 57.1924 + endloop + endfacet + facet normal 0.325856 -0.841672 0.430587 + outer loop + vertex -449.134 80.7713 58.7587 + vertex -452.721 78.5815 57.1924 + vertex -451.42 78.0081 55.0872 + endloop + endfacet + facet normal 0.0327609 -0.897041 0.440732 + outer loop + vertex -474.604 69.8287 46.3122 + vertex -470.89 70.0633 46.5136 + vertex -472.807 70.8691 48.2961 + endloop + endfacet + facet normal 0.0298842 -0.887087 0.460633 + outer loop + vertex -473.223 69.1827 44.9787 + vertex -474.604 69.8287 46.3122 + vertex -474.979 68.6543 44.075 + endloop + endfacet + facet normal 0.00724397 -0.869306 0.494222 + outer loop + vertex -473.223 69.1827 44.9787 + vertex -474.979 68.6543 44.075 + vertex -470.701 67.9486 42.7709 + endloop + endfacet + facet normal 0.00479096 -0.870525 0.492101 + outer loop + vertex -470.701 67.9486 42.7709 + vertex -470.89 70.0633 46.5136 + vertex -473.223 69.1827 44.9787 + endloop + endfacet + facet normal 0.0471537 -0.868645 0.493185 + outer loop + vertex -466.565 68.9785 44.1894 + vertex -470.89 70.0633 46.5136 + vertex -470.701 67.9486 42.7709 + endloop + endfacet + facet normal 0.0462539 -0.869434 0.491879 + outer loop + vertex -466.565 68.9785 44.1894 + vertex -466.397 71.2806 48.2429 + vertex -470.89 70.0633 46.5136 + endloop + endfacet + facet normal 0.0882423 -0.867716 0.489165 + outer loop + vertex -462.864 70.2808 45.8318 + vertex -466.397 71.2806 48.2429 + vertex -466.565 68.9785 44.1894 + endloop + endfacet + facet normal 0.0867067 -0.868868 0.487392 + outer loop + vertex -462.864 70.2808 45.8318 + vertex -462.359 72.7099 50.0723 + vertex -466.397 71.2806 48.2429 + endloop + endfacet + facet normal 0.136045 -0.866552 0.480188 + outer loop + vertex -459.395 71.7494 47.4995 + vertex -462.359 72.7099 50.0723 + vertex -462.864 70.2808 45.8318 + endloop + endfacet + facet normal 0.137846 -0.865361 0.481818 + outer loop + vertex -459.395 71.7494 47.4995 + vertex -458.582 74.2832 51.8178 + vertex -462.359 72.7099 50.0723 + endloop + endfacet + facet normal 0.18575 -0.862339 0.471029 + outer loop + vertex -455.988 73.3756 49.1328 + vertex -458.582 74.2832 51.8178 + vertex -459.395 71.7494 47.4995 + endloop + endfacet + facet normal 0.194531 -0.856755 0.477628 + outer loop + vertex -455.988 73.3756 49.1328 + vertex -454.98 76.0316 53.487 + vertex -458.582 74.2832 51.8178 + endloop + endfacet + facet normal 0.240531 -0.852381 0.464318 + outer loop + vertex -452.623 75.1998 50.7387 + vertex -454.98 76.0316 53.487 + vertex -455.988 73.3756 49.1328 + endloop + endfacet + facet normal 0.254966 -0.842898 0.47383 + outer loop + vertex -452.623 75.1998 50.7387 + vertex -451.42 78.0081 55.0872 + vertex -454.98 76.0316 53.487 + endloop + endfacet + facet normal 0.015533 -0.857147 0.514838 + outer loop + vertex -474.193 66.8899 41.1136 + vertex -470.701 67.9486 42.7709 + vertex -474.979 68.6543 44.075 + endloop + endfacet + facet normal -0.0073198 -0.8599 0.51041 + outer loop + vertex -477.394 68.3775 43.5739 + vertex -474.193 66.8899 41.1136 + vertex -474.979 68.6543 44.075 + endloop + endfacet + facet normal -0.0229983 -0.868476 0.495197 + outer loop + vertex -477.394 68.3775 43.5739 + vertex -478.828 67.757 42.4192 + vertex -474.193 66.8899 41.1136 + endloop + endfacet + facet normal 0.0309731 -0.886589 0.461519 + outer loop + vertex -473.223 69.1827 44.9787 + vertex -470.89 70.0633 46.5136 + vertex -474.604 69.8287 46.3122 + endloop + endfacet + facet normal 0.013312 -0.898409 0.438959 + outer loop + vertex -477.317 69.3943 45.5584 + vertex -475.75 70.4503 47.6721 + vertex -478.935 69.7995 46.4367 + endloop + endfacet + facet normal 0.00344672 -0.882673 0.469976 + outer loop + vertex -477.394 68.3775 43.5739 + vertex -479.603 68.918 44.6053 + vertex -478.828 67.757 42.4192 + endloop + endfacet + facet normal -0.0278622 -0.899872 0.435263 + outer loop + vertex -481.546 68.5231 43.7347 + vertex -481.203 69.2717 45.3044 + vertex -483.179 68.9911 44.5977 + endloop + endfacet + facet normal -0.0217363 -0.871351 0.490179 + outer loop + vertex -480.97 67.5494 41.9219 + vertex -483.375 68.1779 42.9324 + vertex -482.149 66.9856 40.8673 + endloop + endfacet + facet normal -0.045688 -0.858807 0.510258 + outer loop + vertex -480.97 67.5494 41.9219 + vertex -482.149 66.9856 40.8673 + vertex -477.216 65.9651 39.5915 + endloop + endfacet + facet normal -0.0378476 -0.853687 0.519409 + outer loop + vertex -480.97 67.5494 41.9219 + vertex -477.216 65.9651 39.5915 + vertex -478.828 67.757 42.4192 + endloop + endfacet + facet normal -0.00866685 -0.84687 0.53173 + outer loop + vertex -477.216 65.9651 39.5915 + vertex -474.193 66.8899 41.1136 + vertex -478.828 67.757 42.4192 + endloop + endfacet + facet normal -0.0565026 -0.873865 0.482874 + outer loop + vertex -484.274 66.8411 40.4217 + vertex -485.212 67.8593 42.1546 + vertex -487.028 67.5579 41.3967 + endloop + endfacet + facet normal -0.0578815 -0.879795 0.471817 + outer loop + vertex -487.028 67.5579 41.3967 + vertex -489.073 68.067 42.0952 + vertex -488.775 67.276 40.6566 + endloop + endfacet + facet normal -0.0601031 -0.888407 0.455104 + outer loop + vertex -489.073 68.067 42.0952 + vertex -487.145 68.4051 43.0096 + vertex -489.176 68.567 43.0575 + endloop + endfacet + facet normal -0.0797698 -0.876613 0.474538 + outer loop + vertex -490.256 66.9981 39.9502 + vertex -490.921 67.8884 41.4833 + vertex -492.406 67.5539 40.6157 + endloop + endfacet + facet normal -0.0631625 -0.851037 0.521293 + outer loop + vertex -487.181 66.2119 39.0393 + vertex -490.256 66.9981 39.9502 + vertex -487.577 65.7209 38.1897 + endloop + endfacet + facet normal -0.0869949 -0.861553 0.500159 + outer loop + vertex -488.991 65.6672 37.8858 + vertex -491.368 66.7212 39.2878 + vertex -492.103 66.4806 38.7456 + endloop + endfacet + facet normal -0.104514 -0.87739 0.468257 + outer loop + vertex -494.377 66.738 38.775 + vertex -495.274 67.2075 39.4546 + vertex -496.369 67.3904 39.5528 + endloop + endfacet + facet normal -0.114985 -0.886191 0.448824 + outer loop + vertex -494.377 66.738 38.775 + vertex -496.369 67.3904 39.5528 + vertex -498.556 67.9088 40.0162 + endloop + endfacet + facet normal -0.111634 -0.881303 0.459175 + outer loop + vertex -496.369 67.3904 39.5528 + vertex -496.702 67.6902 40.0473 + vertex -498.556 67.9088 40.0162 + endloop + endfacet + facet normal -0.112047 -0.886173 0.449602 + outer loop + vertex -496.702 67.6902 40.0473 + vertex -497.292 67.8483 40.2121 + vertex -498.556 67.9088 40.0162 + endloop + endfacet + facet normal -0.11965 -0.852329 0.509136 + outer loop + vertex -497.292 67.8483 40.2121 + vertex -496.302 67.9342 40.5885 + vertex -498.556 67.9088 40.0162 + endloop + endfacet + facet normal -0.113092 -0.867737 0.483987 + outer loop + vertex -495.243 68.1764 41.2701 + vertex -498.556 67.9088 40.0162 + vertex -496.302 67.9342 40.5885 + endloop + endfacet + facet normal -0.0851816 -0.904418 0.418058 + outer loop + vertex -498.556 67.9088 40.0162 + vertex -495.243 68.1764 41.2701 + vertex -497.194 68.2493 41.0302 + endloop + endfacet + facet normal -0.083275 -0.912712 0.400027 + outer loop + vertex -495.546 68.3852 41.6835 + vertex -497.194 68.2493 41.0302 + vertex -495.243 68.1764 41.2701 + endloop + endfacet + facet normal -0.0856052 -0.865712 0.493169 + outer loop + vertex -492.103 66.4806 38.7456 + vertex -494.3 67.1137 39.4756 + vertex -492.746 66.3849 38.466 + endloop + endfacet + facet normal -0.0873216 -0.874515 0.477073 + outer loop + vertex -494.3 67.1137 39.4756 + vertex -493.591 67.3905 40.1128 + vertex -495.129 67.7322 40.4575 + endloop + endfacet + facet normal -0.0887752 -0.876708 0.472761 + outer loop + vertex -492.713 68.0964 41.5868 + vertex -495.129 67.7322 40.4575 + vertex -493.591 67.3905 40.1128 + endloop + endfacet + facet normal -0.105491 -0.880236 0.462662 + outer loop + vertex -496.369 67.3904 39.5528 + vertex -495.274 67.2075 39.4546 + vertex -496.702 67.6902 40.0473 + endloop + endfacet + facet normal -0.103226 -0.875899 0.471323 + outer loop + vertex -496.702 67.6902 40.0473 + vertex -496.302 67.9342 40.5885 + vertex -497.292 67.8483 40.2121 + endloop + endfacet + facet normal -0.0656679 -0.893683 0.443868 + outer loop + vertex -489.176 68.567 43.0575 + vertex -490.537 68.6115 42.9458 + vertex -492.713 68.0964 41.5868 + endloop + endfacet + facet normal -0.0854111 -0.889574 0.448736 + outer loop + vertex -496.302 67.9342 40.5885 + vertex -493.873 68.1962 41.5701 + vertex -495.243 68.1764 41.2701 + endloop + endfacet + facet normal -0.0669654 -0.916853 0.393569 + outer loop + vertex -493.585 68.8203 43.0197 + vertex -494.769 69.2692 43.8639 + vertex -494.85 68.7091 42.5452 + endloop + endfacet + facet normal -0.0773026 -0.915932 0.393819 + outer loop + vertex -494.85 68.7091 42.5452 + vertex -494.769 69.2692 43.8639 + vertex -496.057 69.2254 43.5093 + endloop + endfacet + facet normal -0.0709168 -0.910286 0.407861 + outer loop + vertex -493.289 68.5018 42.3361 + vertex -495.546 68.3852 41.6835 + vertex -495.243 68.1764 41.2701 + endloop + endfacet + facet normal -0.0760627 -0.915473 0.395125 + outer loop + vertex -494.85 68.7091 42.5452 + vertex -496.057 69.2254 43.5093 + vertex -496.086 68.7213 42.3357 + endloop + endfacet + facet normal -0.0724889 -0.923275 0.377239 + outer loop + vertex -494.769 69.2692 43.8639 + vertex -496.028 69.8963 45.1567 + vertex -496.057 69.2254 43.5093 + endloop + endfacet + facet normal -0.0665724 -0.933051 0.353531 + outer loop + vertex -496.028 69.8963 45.1567 + vertex -494.772 70.1479 46.0575 + vertex -496.813 71.0839 48.1433 + endloop + endfacet + facet normal -0.0805819 -0.941586 0.326991 + outer loop + vertex -496.813 71.0839 48.1433 + vertex -498.643 72.5818 52.0055 + vertex -499.036 71.0116 47.3874 + endloop + endfacet + facet normal -0.0992777 -0.939492 0.32787 + outer loop + vertex -499.036 71.0116 47.3874 + vertex -498.643 72.5818 52.0055 + vertex -500.753 72.5903 51.3909 + endloop + endfacet + facet normal -0.0954584 -0.921987 0.37527 + outer loop + vertex -497.176 69.1902 43.1882 + vertex -497.34 70.0092 45.1588 + vertex -498.312 69.8274 44.4646 + endloop + endfacet + facet normal -0.0889822 -0.920563 0.380324 + outer loop + vertex -497.176 69.1902 43.1882 + vertex -498.312 69.8274 44.4646 + vertex -498.133 69.1387 42.8395 + endloop + endfacet + facet normal -0.0946135 -0.913883 0.394799 + outer loop + vertex -496.967 68.608 41.8906 + vertex -497.176 69.1902 43.1882 + vertex -498.133 69.1387 42.8395 + endloop + endfacet + facet normal -0.0842816 -0.911604 0.402337 + outer loop + vertex -497.194 68.2493 41.0302 + vertex -495.546 68.3852 41.6835 + vertex -496.967 68.608 41.8906 + endloop + endfacet + facet normal -0.106446 -0.913902 0.39173 + outer loop + vertex -497.887 68.6086 41.6692 + vertex -498.881 69.0872 42.5156 + vertex -498.4 68.5361 41.3606 + endloop + endfacet + facet normal -0.120579 -0.914526 0.386139 + outer loop + vertex -498.4 68.5361 41.3606 + vertex -498.881 69.0872 42.5156 + vertex -499.453 69.1168 42.4071 + endloop + endfacet + facet normal -0.0994869 -0.8953 0.434212 + outer loop + vertex -497.194 68.2493 41.0302 + vertex -498.424 68.3441 40.9439 + vertex -498.556 67.9088 40.0162 + endloop + endfacet + facet normal -0.114123 -0.91296 0.391766 + outer loop + vertex -498.4 68.5361 41.3606 + vertex -499.453 69.1168 42.4071 + vertex -499.065 68.7085 41.5687 + endloop + endfacet + facet normal -0.114499 -0.921823 0.370314 + outer loop + vertex -500.066 69.4144 42.9501 + vertex -500.525 70.0145 44.3021 + vertex -500.9 70.1511 44.5261 + endloop + endfacet + facet normal 0.215233 -0.836032 0.504703 + outer loop + vertex -500.066 69.4144 42.9501 + vertex -500.9 70.1511 44.5261 + vertex -501.349 70.4326 45.1838 + endloop + endfacet + facet normal -0.118214 -0.920674 0.372002 + outer loop + vertex -498.881 69.0872 42.5156 + vertex -499.885 69.7552 43.85 + vertex -499.453 69.1168 42.4071 + endloop + endfacet + facet normal -0.0986805 -0.929409 0.355615 + outer loop + vertex -499.885 69.7552 43.85 + vertex -499.3 69.9346 44.4812 + vertex -500.71 71.0128 46.9078 + endloop + endfacet + facet normal -0.139151 -0.93183 0.335156 + outer loop + vertex -500.9 70.1511 44.5261 + vertex -500.525 70.0145 44.3021 + vertex -501.827 71.2832 47.2889 + endloop + endfacet + facet normal -0.0489861 -0.929875 0.364599 + outer loop + vertex -500.9 70.1511 44.5261 + vertex -501.827 71.2832 47.2889 + vertex -501.349 70.4326 45.1838 + endloop + endfacet + facet normal -0.100433 -0.939247 0.328221 + outer loop + vertex -501.827 71.2832 47.2889 + vertex -502.344 72.7078 51.2072 + vertex -503.488 73.1043 51.9919 + endloop + endfacet + facet normal -0.147111 -0.938775 0.311546 + outer loop + vertex -501.827 71.2832 47.2889 + vertex -503.488 73.1043 51.9919 + vertex -503.061 72.1838 49.4197 + endloop + endfacet + facet normal -0.124736 -0.946817 0.296611 + outer loop + vertex -502.344 72.7078 51.2072 + vertex -503.723 74.2873 55.6692 + vertex -503.488 73.1043 51.9919 + endloop + endfacet + facet normal -0.10755 -0.948417 0.298224 + outer loop + vertex -503.488 73.1043 51.9919 + vertex -503.723 74.2873 55.6692 + vertex -504.764 74.6637 56.491 + endloop + endfacet + facet normal -0.151977 -0.946422 0.284935 + outer loop + vertex -503.488 73.1043 51.9919 + vertex -504.764 74.6637 56.491 + vertex -504.473 73.8329 53.8865 + endloop + endfacet + facet normal -0.133395 -0.95411 0.268102 + outer loop + vertex -503.723 74.2873 55.6692 + vertex -504.793 75.728 60.2641 + vertex -504.764 74.6637 56.491 + endloop + endfacet + facet normal -0.131119 -0.954398 0.268201 + outer loop + vertex -504.764 74.6637 56.491 + vertex -504.793 75.728 60.2641 + vertex -505.653 75.9638 60.6825 + endloop + endfacet + facet normal -0.150889 -0.952784 0.263506 + outer loop + vertex -504.764 74.6637 56.491 + vertex -505.653 75.9638 60.6825 + vertex -505.497 75.2679 58.2559 + endloop + endfacet + facet normal -0.14482 -0.95922 0.242744 + outer loop + vertex -504.793 75.728 60.2641 + vertex -505.613 76.9884 64.7553 + vertex -505.653 75.9638 60.6825 + endloop + endfacet + facet normal -0.176534 -0.954138 0.241777 + outer loop + vertex -505.653 75.9638 60.6825 + vertex -505.613 76.9884 64.7553 + vertex -506.14 76.7632 63.4823 + endloop + endfacet + facet normal -0.141314 -0.958129 0.249035 + outer loop + vertex -505.653 75.9638 60.6825 + vertex -506.14 76.7632 63.4823 + vertex -506.148 76.4215 62.163 + endloop + endfacet + facet normal -0.141091 -0.963212 0.228728 + outer loop + vertex -506.14 76.7632 63.4823 + vertex -505.613 76.9884 64.7553 + vertex -506.718 77.6718 66.9519 + endloop + endfacet + facet normal -0.0162223 -0.96791 0.250772 + outer loop + vertex -506.718 77.6718 66.9519 + vertex -506.148 76.4215 62.163 + vertex -506.14 76.7632 63.4823 + endloop + endfacet + facet normal -0.126591 -0.960833 0.246526 + outer loop + vertex -504.793 75.728 60.2641 + vertex -504.199 76.9734 65.4231 + vertex -505.613 76.9884 64.7553 + endloop + endfacet + facet normal -0.115055 -0.96825 0.221933 + outer loop + vertex -505.613 76.9884 64.7553 + vertex -504.199 76.9734 65.4231 + vertex -505.132 78.8015 72.9148 + endloop + endfacet + facet normal -0.0902704 -0.970061 0.22546 + outer loop + vertex -504.199 76.9734 65.4231 + vertex -502.877 78.05 70.5842 + vertex -505.132 78.8015 72.9148 + endloop + endfacet + facet normal -0.105858 -0.971753 0.210927 + outer loop + vertex -503.06 79.0374 75.0418 + vertex -505.132 78.8015 72.9148 + vertex -502.877 78.05 70.5842 + endloop + endfacet + facet normal -0.116594 -0.970671 0.210248 + outer loop + vertex -502.877 78.05 70.5842 + vertex -500.994 78.9387 75.7317 + vertex -503.06 79.0374 75.0418 + endloop + endfacet + facet normal -0.109225 -0.976192 0.1874 + outer loop + vertex -503.06 79.0374 75.0418 + vertex -500.994 78.9387 75.7317 + vertex -502.112 80.2118 81.7123 + endloop + endfacet + facet normal -0.109252 -0.97619 0.187395 + outer loop + vertex -497.414 79.8249 82.4353 + vertex -502.112 80.2118 81.7123 + vertex -500.994 78.9387 75.7317 + endloop + endfacet + facet normal -0.107664 -0.976521 0.186591 + outer loop + vertex -498.611 78.5524 75.0848 + vertex -497.414 79.8249 82.4353 + vertex -500.994 78.9387 75.7317 + endloop + endfacet + facet normal -0.101457 -0.972991 0.20735 + outer loop + vertex -500.47 77.7313 70.3221 + vertex -498.611 78.5524 75.0848 + vertex -500.994 78.9387 75.7317 + endloop + endfacet + facet normal -0.0987885 -0.97347 0.206391 + outer loop + vertex -497.752 77.545 70.7442 + vertex -498.611 78.5524 75.0848 + vertex -500.47 77.7313 70.3221 + endloop + endfacet + facet normal -0.106253 -0.972597 0.206798 + outer loop + vertex -500.47 77.7313 70.3221 + vertex -500.994 78.9387 75.7317 + vertex -502.877 78.05 70.5842 + endloop + endfacet + facet normal -0.103272 -0.968023 0.228617 + outer loop + vertex -502.118 76.6994 65.2089 + vertex -500.47 77.7313 70.3221 + vertex -502.877 78.05 70.5842 + endloop + endfacet + facet normal -0.0994117 -0.968689 0.227508 + outer loop + vertex -499.606 76.5076 65.4895 + vertex -500.47 77.7313 70.3221 + vertex -502.118 76.6994 65.2089 + endloop + endfacet + facet normal -0.103901 -0.96798 0.228517 + outer loop + vertex -502.118 76.6994 65.2089 + vertex -502.877 78.05 70.5842 + vertex -504.199 76.9734 65.4231 + endloop + endfacet + facet normal -0.101201 -0.963273 0.248724 + outer loop + vertex -503.278 75.527 60.1961 + vertex -502.118 76.6994 65.2089 + vertex -504.199 76.9734 65.4231 + endloop + endfacet + facet normal -0.101691 -0.963197 0.248819 + outer loop + vertex -501.181 75.3643 60.4235 + vertex -502.118 76.6994 65.2089 + vertex -503.278 75.527 60.1961 + endloop + endfacet + facet normal -0.116635 -0.962295 0.245733 + outer loop + vertex -503.278 75.527 60.1961 + vertex -504.199 76.9734 65.4231 + vertex -504.793 75.728 60.2641 + endloop + endfacet + facet normal -0.114478 -0.95522 0.272854 + outer loop + vertex -503.723 74.2873 55.6692 + vertex -503.278 75.527 60.1961 + vertex -504.793 75.728 60.2641 + endloop + endfacet + facet normal -0.110706 -0.955731 0.272623 + outer loop + vertex -502.159 74.0931 55.6237 + vertex -503.278 75.527 60.1961 + vertex -503.723 74.2873 55.6692 + endloop + endfacet + facet normal -0.0950986 -0.939321 0.329595 + outer loop + vertex -499.036 71.0116 47.3874 + vertex -500.753 72.5903 51.3909 + vertex -500.71 71.0128 46.9078 + endloop + endfacet + facet normal -0.108803 -0.947185 0.301666 + outer loop + vertex -502.344 72.7078 51.2072 + vertex -502.159 74.0931 55.6237 + vertex -503.723 74.2873 55.6692 + endloop + endfacet + facet normal -0.0914667 -0.949254 0.300918 + outer loop + vertex -498.643 72.5818 52.0055 + vertex -500.074 74.0114 56.0803 + vertex -500.753 72.5903 51.3909 + endloop + endfacet + facet normal -0.103903 -0.955994 0.274371 + outer loop + vertex -502.159 74.0931 55.6237 + vertex -501.181 75.3643 60.4235 + vertex -503.278 75.527 60.1961 + endloop + endfacet + facet normal -0.0869844 -0.958925 0.269994 + outer loop + vertex -497.619 73.9779 56.7523 + vertex -498.685 75.2651 60.9806 + vertex -500.074 74.0114 56.0803 + endloop + endfacet + facet normal -0.101382 -0.963213 0.248884 + outer loop + vertex -501.181 75.3643 60.4235 + vertex -499.606 76.5076 65.4895 + vertex -502.118 76.6994 65.2089 + endloop + endfacet + facet normal -0.0807829 -0.966865 0.24217 + outer loop + vertex -496.031 75.2134 61.6595 + vertex -496.892 76.3955 66.0916 + vertex -498.685 75.2651 60.9806 + endloop + endfacet + facet normal -0.101663 -0.968557 0.227071 + outer loop + vertex -499.606 76.5076 65.4895 + vertex -497.752 77.545 70.7442 + vertex -500.47 77.7313 70.3221 + endloop + endfacet + facet normal -0.0732796 -0.973096 0.218436 + outer loop + vertex -494.176 76.344 66.7734 + vertex -494.978 77.4404 71.3887 + vertex -496.892 76.3955 66.0916 + endloop + endfacet + facet normal -0.101325 -0.973323 0.205855 + outer loop + vertex -497.752 77.545 70.7442 + vertex -495.719 78.5676 76.5804 + vertex -498.611 78.5524 75.0848 + endloop + endfacet + facet normal -0.0656167 -0.978201 0.19702 + outer loop + vertex -492.274 77.393 72.0543 + vertex -493.084 78.3043 76.3087 + vertex -494.978 77.4404 71.3887 + endloop + endfacet + facet normal -0.0554219 -0.982769 0.176331 + outer loop + vertex -493.084 78.3043 76.3087 + vertex -490.28 78.4229 77.8512 + vertex -491.998 79.5492 83.5887 + endloop + endfacet + facet normal -0.0900531 -0.978771 0.184112 + outer loop + vertex -498.611 78.5524 75.0848 + vertex -495.719 78.5676 76.5804 + vertex -497.414 79.8249 82.4353 + endloop + endfacet + facet normal -0.076976 -0.98446 0.157842 + outer loop + vertex -491.998 79.5492 83.5887 + vertex -487.16 80.835 93.9671 + vertex -492.715 81.0831 92.8057 + endloop + endfacet + facet normal -0.0712296 -0.989034 0.129379 + outer loop + vertex -487.16 80.835 93.9671 + vertex -487.234 82.0115 102.92 + vertex -492.715 81.0831 92.8057 + endloop + endfacet + facet normal -0.0767561 -0.990826 0.111234 + outer loop + vertex -487.234 82.0115 102.92 + vertex -481.054 82.6331 112.723 + vertex -486.828 82.9652 111.696 + endloop + endfacet + facet normal -0.0876859 -0.991706 0.0939703 + outer loop + vertex -486.828 82.9652 111.696 + vertex -480.214 83.2969 121.368 + vertex -486.104 83.7261 120.402 + endloop + endfacet + facet normal -0.0977183 -0.992091 0.0787874 + outer loop + vertex -486.104 83.7261 120.402 + vertex -479.238 83.8136 130.019 + vertex -485.25 84.3365 129.148 + endloop + endfacet + facet normal -0.10648 -0.992229 0.0643754 + outer loop + vertex -485.25 84.3365 129.148 + vertex -478.22 84.2036 138.727 + vertex -484.357 84.8125 137.959 + endloop + endfacet + facet normal -0.113596 -0.992287 0.0496258 + outer loop + vertex -484.357 84.8125 137.959 + vertex -477.174 84.4665 147.486 + vertex -483.443 85.1502 146.806 + endloop + endfacet + facet normal -0.119186 -0.992279 0.0343006 + outer loop + vertex -483.443 85.1502 146.806 + vertex -476.083 84.5929 156.257 + vertex -482.495 85.3421 155.652 + endloop + endfacet + facet normal -0.123032 -0.992235 0.0182242 + outer loop + vertex -482.495 85.3421 155.652 + vertex -474.944 84.5777 165.009 + vertex -481.501 85.381 164.475 + endloop + endfacet + facet normal -0.12591 -0.99204 0.00197322 + outer loop + vertex -481.501 85.381 164.475 + vertex -473.763 84.4172 173.715 + vertex -480.485 85.2695 173.263 + endloop + endfacet + facet normal -0.127409 -0.991734 -0.0152194 + outer loop + vertex -480.485 85.2695 173.263 + vertex -472.552 84.1106 182.372 + vertex -479.44 85.001 182.009 + endloop + endfacet + facet normal -0.128075 -0.991212 -0.0330848 + outer loop + vertex -479.44 85.001 182.009 + vertex -471.319 83.6524 190.976 + vertex -478.38 84.5732 190.721 + endloop + endfacet + facet normal -0.128011 -0.990415 -0.0518794 + outer loop + vertex -478.38 84.5732 190.721 + vertex -470.069 83.0371 199.541 + vertex -477.317 83.9805 199.415 + endloop + endfacet + facet normal -0.127015 -0.989284 -0.0719991 + outer loop + vertex -477.317 83.9805 199.415 + vertex -468.815 82.2583 208.079 + vertex -476.248 83.2119 208.089 + endloop + endfacet + facet normal -0.125715 -0.987775 -0.0921782 + outer loop + vertex -476.248 83.2119 208.089 + vertex -467.56 81.3134 216.584 + vertex -475.187 82.2703 216.732 + endloop + endfacet + facet normal -0.124387 -0.985945 -0.111535 + outer loop + vertex -475.187 82.2703 216.732 + vertex -466.289 80.211 225.013 + vertex -474.105 81.1653 225.294 + endloop + endfacet + facet normal -0.123141 -0.983954 -0.129113 + outer loop + vertex -474.105 81.1653 225.294 + vertex -464.963 78.9697 233.307 + vertex -472.966 79.9164 233.725 + endloop + endfacet + facet normal -0.122168 -0.98194 -0.144462 + outer loop + vertex -472.966 79.9164 233.725 + vertex -463.543 77.6043 241.472 + vertex -471.74 78.5352 242.077 + endloop + endfacet + facet normal -0.137127 -0.978385 -0.154787 + outer loop + vertex -479.71 79.5808 242.546 + vertex -470.485 77.0217 250.549 + vertex -478.604 78.0504 251.24 + endloop + endfacet + facet normal -0.150019 -0.976794 -0.152867 + outer loop + vertex -479.71 79.5808 242.546 + vertex -478.604 78.0504 251.24 + vertex -486.765 80.5934 243 + endloop + endfacet + facet normal -0.137716 -0.976785 -0.164089 + outer loop + vertex -470.485 77.0217 250.549 + vertex -469.302 75.376 259.353 + vertex -478.604 78.0504 251.24 + endloop + endfacet + facet normal -0.139165 -0.976854 -0.16245 + outer loop + vertex -478.604 78.0504 251.24 + vertex -469.302 75.376 259.353 + vertex -477.538 76.4079 260.204 + endloop + endfacet + facet normal -0.150422 -0.975448 -0.160853 + outer loop + vertex -478.604 78.0504 251.24 + vertex -477.538 76.4079 260.204 + vertex -485.784 79.0667 251.791 + endloop + endfacet + facet normal -0.139847 -0.97531 -0.170917 + outer loop + vertex -469.302 75.376 259.353 + vertex -468.243 73.6113 268.557 + vertex -477.538 76.4079 260.204 + endloop + endfacet + facet normal -0.127144 -0.976742 -0.172653 + outer loop + vertex -469.302 75.376 259.353 + vertex -459.379 72.7196 267.074 + vertex -468.243 73.6113 268.557 + endloop + endfacet + facet normal -0.124483 -0.97649 -0.175985 + outer loop + vertex -460.584 74.4756 258.182 + vertex -459.379 72.7196 267.074 + vertex -469.302 75.376 259.353 + endloop + endfacet + facet normal -0.122809 -0.980094 -0.155992 + outer loop + vertex -463.543 77.6043 241.472 + vertex -462.047 76.1118 249.671 + vertex -471.74 78.5352 242.077 + endloop + endfacet + facet normal -0.123373 -0.978326 -0.166304 + outer loop + vertex -470.485 77.0217 250.549 + vertex -460.584 74.4756 258.182 + vertex -469.302 75.376 259.353 + endloop + endfacet + facet normal -0.106303 -0.979689 -0.170024 + outer loop + vertex -453.717 75.3705 248.734 + vertex -451.871 73.7679 256.815 + vertex -462.047 76.1118 249.671 + endloop + endfacet + facet normal -0.109138 -0.977897 -0.178342 + outer loop + vertex -460.584 74.4756 258.182 + vertex -450.003 71.9666 265.465 + vertex -459.379 72.7196 267.074 + endloop + endfacet + facet normal -0.111253 -0.975069 -0.191996 + outer loop + vertex -459.379 72.7196 267.074 + vertex -450.003 71.9666 265.465 + vertex -451.026 70.9723 271.107 + endloop + endfacet + facet normal -0.111944 -0.975255 -0.190645 + outer loop + vertex -455.274 71.0983 272.957 + vertex -459.379 72.7196 267.074 + vertex -451.026 70.9723 271.107 + endloop + endfacet + facet normal -0.112236 -0.975088 -0.191326 + outer loop + vertex -451.026 70.9723 271.107 + vertex -449.927 69.9586 275.629 + vertex -455.274 71.0983 272.957 + endloop + endfacet + facet normal -0.114135 -0.975567 -0.187731 + outer loop + vertex -455.274 71.0983 272.957 + vertex -449.927 69.9586 275.629 + vertex -454.721 70.2807 276.87 + endloop + endfacet + facet normal -0.12241 -0.974817 -0.186406 + outer loop + vertex -455.274 71.0983 272.957 + vertex -454.721 70.2807 276.87 + vertex -460.375 71.6905 273.21 + endloop + endfacet + facet normal -0.115446 -0.974362 -0.193107 + outer loop + vertex -449.927 69.9586 275.629 + vertex -448.705 69.057 279.448 + vertex -454.721 70.2807 276.87 + endloop + endfacet + facet normal -0.116943 -0.974827 -0.189834 + outer loop + vertex -454.721 70.2807 276.87 + vertex -448.705 69.057 279.448 + vertex -453.468 69.383 280.708 + endloop + endfacet + facet normal -0.125631 -0.974317 -0.186878 + outer loop + vertex -454.721 70.2807 276.87 + vertex -453.468 69.383 280.708 + vertex -459.281 70.6679 277.916 + endloop + endfacet + facet normal -0.118651 -0.973259 -0.196697 + outer loop + vertex -448.705 69.057 279.448 + vertex -447.174 68.1974 282.777 + vertex -453.468 69.383 280.708 + endloop + endfacet + facet normal -0.119841 -0.973778 -0.193376 + outer loop + vertex -453.468 69.383 280.708 + vertex -447.174 68.1974 282.777 + vertex -451.828 68.5198 284.038 + endloop + endfacet + facet normal -0.121631 -0.972133 -0.200408 + outer loop + vertex -447.174 68.1974 282.777 + vertex -445.537 67.4289 285.511 + vertex -451.828 68.5198 284.038 + endloop + endfacet + facet normal -0.109423 -0.972054 -0.207696 + outer loop + vertex -447.174 68.1974 282.777 + vertex -441.401 67.2721 284.066 + vertex -445.537 67.4289 285.511 + endloop + endfacet + facet normal -0.109687 -0.971858 -0.208472 + outer loop + vertex -441.401 67.2721 284.066 + vertex -439.787 66.7114 285.831 + vertex -445.537 67.4289 285.511 + endloop + endfacet + facet normal -0.109689 -0.971863 -0.208448 + outer loop + vertex -445.537 67.4289 285.511 + vertex -439.787 66.7114 285.831 + vertex -443.644 66.7602 287.633 + endloop + endfacet + facet normal -0.123004 -0.972691 -0.19683 + outer loop + vertex -445.537 67.4289 285.511 + vertex -443.644 66.7602 287.633 + vertex -449.977 67.7197 286.849 + endloop + endfacet + facet normal -0.0933995 -0.970361 -0.222883 + outer loop + vertex -441.401 67.2721 284.066 + vertex -433.467 66.6995 283.234 + vertex -439.787 66.7114 285.831 + endloop + endfacet + facet normal -0.0925838 -0.972521 -0.213617 + outer loop + vertex -441.401 67.2721 284.066 + vertex -441.863 67.9496 281.182 + vertex -433.467 66.6995 283.234 + endloop + endfacet + facet normal -0.0929916 -0.972808 -0.212123 + outer loop + vertex -436.59 68.2 277.722 + vertex -433.467 66.6995 283.234 + vertex -441.863 67.9496 281.182 + endloop + endfacet + facet normal -0.0920422 -0.973207 -0.210705 + outer loop + vertex -444.361 68.8938 277.912 + vertex -436.59 68.2 277.722 + vertex -441.863 67.9496 281.182 + endloop + endfacet + facet normal -0.107083 -0.974038 -0.199458 + outer loop + vertex -444.361 68.8938 277.912 + vertex -441.863 67.9496 281.182 + vertex -448.705 69.057 279.448 + endloop + endfacet + facet normal -0.0919865 -0.975323 -0.200706 + outer loop + vertex -444.361 68.8938 277.912 + vertex -444.613 69.6902 274.158 + vertex -436.59 68.2 277.722 + endloop + endfacet + facet normal -0.0903097 -0.974746 -0.204239 + outer loop + vertex -439.341 69.8962 270.843 + vertex -436.59 68.2 277.722 + vertex -444.613 69.6902 274.158 + endloop + endfacet + facet normal -0.0877882 -0.975795 -0.200294 + outer loop + vertex -446.288 70.5876 270.52 + vertex -439.341 69.8962 270.843 + vertex -444.613 69.6902 274.158 + endloop + endfacet + facet normal -0.103171 -0.975722 -0.193192 + outer loop + vertex -446.288 70.5876 270.52 + vertex -444.613 69.6902 274.158 + vertex -451.026 70.9723 271.107 + endloop + endfacet + facet normal -0.104478 -0.974282 -0.199648 + outer loop + vertex -444.613 69.6902 274.158 + vertex -444.361 68.8938 277.912 + vertex -449.927 69.9586 275.629 + endloop + endfacet + facet normal -0.108638 -0.971475 -0.210796 + outer loop + vertex -441.863 67.9496 281.182 + vertex -441.401 67.2721 284.066 + vertex -447.174 68.1974 282.777 + endloop + endfacet + facet normal -0.106233 -0.973509 -0.202473 + outer loop + vertex -448.705 69.057 279.448 + vertex -441.863 67.9496 281.182 + vertex -447.174 68.1974 282.777 + endloop + endfacet + facet normal -0.105976 -0.974812 -0.196244 + outer loop + vertex -449.927 69.9586 275.629 + vertex -444.361 68.8938 277.912 + vertex -448.705 69.057 279.448 + endloop + endfacet + facet normal -0.102905 -0.975645 -0.193717 + outer loop + vertex -451.026 70.9723 271.107 + vertex -444.613 69.6902 274.158 + vertex -449.927 69.9586 275.629 + endloop + endfacet + facet normal -0.122329 -0.975391 -0.183436 + outer loop + vertex -455.274 71.0983 272.957 + vertex -460.375 71.6905 273.21 + vertex -459.379 72.7196 267.074 + endloop + endfacet + facet normal -0.102903 -0.976242 -0.190688 + outer loop + vertex -446.288 70.5876 270.52 + vertex -451.026 70.9723 271.107 + vertex -450.003 71.9666 265.465 + endloop + endfacet + facet normal -0.0876577 -0.978749 -0.18538 + outer loop + vertex -443.411 73.2596 255.498 + vertex -441.172 71.5978 263.213 + vertex -451.871 73.7679 256.815 + endloop + endfacet + facet normal -0.0876971 -0.975521 -0.201665 + outer loop + vertex -450.003 71.9666 265.465 + vertex -439.341 69.8962 270.843 + vertex -446.288 70.5876 270.52 + endloop + endfacet + facet normal -0.0639788 -0.976759 -0.20457 + outer loop + vertex -432.442 71.3738 261.552 + vertex -429.76 69.7326 268.55 + vertex -441.172 71.5978 263.213 + endloop + endfacet + facet normal -0.0680399 -0.974653 -0.213122 + outer loop + vertex -439.341 69.8962 270.843 + vertex -427.339 68.1612 274.946 + vertex -436.59 68.2 277.722 + endloop + endfacet + facet normal -0.0719936 -0.971383 -0.226344 + outer loop + vertex -427.339 68.1612 274.946 + vertex -426.349 66.9864 279.673 + vertex -436.59 68.2 277.722 + endloop + endfacet + facet normal -0.0308993 -0.97206 -0.232692 + outer loop + vertex -420.754 69.9211 266.566 + vertex -417.804 68.3652 272.675 + vertex -429.76 69.7326 268.55 + endloop + endfacet + facet normal 0.00891134 -0.96375 -0.266658 + outer loop + vertex -408.581 69.1096 270.292 + vertex -405.772 67.7907 275.153 + vertex -417.804 68.3652 272.675 + endloop + endfacet + facet normal -0.0112642 -0.93496 -0.354573 + outer loop + vertex -403.761 66.8167 278.411 + vertex -404.324 66.0864 280.354 + vertex -411.018 66.0432 280.681 + endloop + endfacet + facet normal -0.00784457 -0.957749 -0.287497 + outer loop + vertex -411.018 66.0432 280.681 + vertex -404.324 66.0864 280.354 + vertex -413.053 65.5181 282.486 + endloop + endfacet + facet normal -0.0503813 -0.942295 -0.330971 + outer loop + vertex -411.018 66.0432 280.681 + vertex -413.053 65.5181 282.486 + vertex -420.702 65.9842 282.323 + endloop + endfacet + facet normal -0.0524867 -0.958791 -0.279223 + outer loop + vertex -420.702 65.9842 282.323 + vertex -413.053 65.5181 282.486 + vertex -421.161 65.3428 284.612 + endloop + endfacet + facet normal -0.0404546 -0.971632 -0.233014 + outer loop + vertex -427.339 68.1612 274.946 + vertex -415.69 66.913 278.129 + vertex -426.349 66.9864 279.673 + endloop + endfacet + facet normal -0.0726189 -0.972007 -0.223449 + outer loop + vertex -436.59 68.2 277.722 + vertex -426.349 66.9864 279.673 + vertex -433.467 66.6995 283.234 + endloop + endfacet + facet normal -0.0796451 -0.955581 -0.283764 + outer loop + vertex -420.702 65.9842 282.323 + vertex -421.161 65.3428 284.612 + vertex -427.781 65.7544 285.084 + endloop + endfacet + facet normal -0.0955992 -0.968899 -0.228243 + outer loop + vertex -436.239 66.0764 287.041 + vertex -439.787 66.7114 285.831 + vertex -433.467 66.6995 283.234 + endloop + endfacet + facet normal -0.0775433 -0.966477 -0.244762 + outer loop + vertex -427.781 65.7544 285.084 + vertex -421.161 65.3428 284.612 + vertex -429.885 65.4735 286.859 + endloop + endfacet + facet normal -0.105978 -0.973956 -0.200447 + outer loop + vertex -439.787 66.7114 285.831 + vertex -436.239 66.0764 287.041 + vertex -443.644 66.7602 287.633 + endloop + endfacet + facet normal -0.122781 -0.972421 -0.1983 + outer loop + vertex -449.977 67.7197 286.849 + vertex -443.644 66.7602 287.633 + vertex -448.596 67.0727 289.167 + endloop + endfacet + facet normal -0.122781 -0.972877 -0.19605 + outer loop + vertex -451.828 68.5198 284.038 + vertex -445.537 67.4289 285.511 + vertex -449.977 67.7197 286.849 + endloop + endfacet + facet normal -0.129712 -0.973482 -0.188436 + outer loop + vertex -453.468 69.383 280.708 + vertex -451.828 68.5198 284.038 + vertex -457.981 69.7784 281.771 + endloop + endfacet + facet normal -0.128254 -0.974953 -0.181706 + outer loop + vertex -459.281 70.6679 277.916 + vertex -453.468 69.383 280.708 + vertex -457.981 69.7784 281.771 + endloop + endfacet + facet normal -0.124786 -0.975184 -0.182876 + outer loop + vertex -460.375 71.6905 273.21 + vertex -454.721 70.2807 276.87 + vertex -459.281 70.6679 277.916 + endloop + endfacet + facet normal -0.12886 -0.974381 -0.184327 + outer loop + vertex -468.243 73.6113 268.557 + vertex -459.379 72.7196 267.074 + vertex -460.375 71.6905 273.21 + endloop + endfacet + facet normal -0.141306 -0.974529 -0.174145 + outer loop + vertex -464.27 71.9092 274.853 + vertex -463.623 71.1046 278.831 + vertex -469.067 72.6135 274.804 + endloop + endfacet + facet normal -0.144352 -0.975508 -0.165969 + outer loop + vertex -477.538 76.4079 260.204 + vertex -468.243 73.6113 268.557 + vertex -476.655 74.7071 269.432 + endloop + endfacet + facet normal -0.144405 -0.974796 -0.170056 + outer loop + vertex -469.067 72.6135 274.804 + vertex -463.623 71.1046 278.831 + vertex -467.946 71.5967 279.681 + endloop + endfacet + facet normal -0.144638 -0.974527 -0.171396 + outer loop + vertex -463.623 71.1046 278.831 + vertex -462.307 70.2221 282.739 + vertex -467.946 71.5967 279.681 + endloop + endfacet + facet normal -0.141999 -0.974497 -0.17376 + outer loop + vertex -462.307 70.2221 282.739 + vertex -456.273 68.9149 285.139 + vertex -460.614 69.3602 286.189 + endloop + endfacet + facet normal -0.151922 -0.973551 -0.170641 + outer loop + vertex -460.614 69.3602 286.189 + vertex -458.808 68.554 289.181 + vertex -464.947 69.8572 287.211 + endloop + endfacet + facet normal -0.157668 -0.974339 -0.160635 + outer loop + vertex -463.134 69.0506 290.29 + vertex -457.458 67.9084 291.647 + vertex -461.83 68.418 292.848 + endloop + endfacet + facet normal -0.14635 -0.972573 -0.180787 + outer loop + vertex -454.463 68.1101 288.05 + vertex -453.13 67.4635 290.45 + vertex -458.808 68.554 289.181 + endloop + endfacet + facet normal -0.140548 -0.974107 -0.17709 + outer loop + vertex -453.13 67.4635 290.45 + vertex -448.582 66.7276 290.888 + vertex -452.731 67.074 292.277 + endloop + endfacet + facet normal -0.158833 -0.973371 -0.165289 + outer loop + vertex -457.458 67.9084 291.647 + vertex -457.298 67.584 293.403 + vertex -461.83 68.418 292.848 + endloop + endfacet + facet normal -0.163436 -0.973887 -0.157583 + outer loop + vertex -463.134 69.0506 290.29 + vertex -461.83 68.418 292.848 + vertex -467.52 69.6014 291.435 + endloop + endfacet + facet normal -0.162396 -0.974763 -0.153179 + outer loop + vertex -469.29 70.3931 288.274 + vertex -463.134 69.0506 290.29 + vertex -467.52 69.6014 291.435 + endloop + endfacet + facet normal -0.163865 -0.974301 -0.154551 + outer loop + vertex -471.105 71.2801 284.606 + vertex -469.29 70.3931 288.274 + vertex -475.352 71.8101 285.768 + endloop + endfacet + facet normal -0.155937 -0.974808 -0.159475 + outer loop + vertex -472.453 72.1819 280.412 + vertex -466.655 70.7207 283.675 + vertex -471.105 71.2801 284.606 + endloop + endfacet + facet normal -0.158031 -0.973986 -0.162411 + outer loop + vertex -472.95 72.9614 276.221 + vertex -472.453 72.1819 280.412 + vertex -478.067 73.8834 275.671 + endloop + endfacet + facet normal -0.157782 -0.973714 -0.164274 + outer loop + vertex -472.95 72.9614 276.221 + vertex -478.067 73.8834 275.671 + vertex -476.655 74.7071 269.432 + endloop + endfacet + facet normal -0.152423 -0.974444 -0.165001 + outer loop + vertex -477.538 76.4079 260.204 + vertex -476.655 74.7071 269.432 + vertex -484.83 77.4732 260.648 + endloop + endfacet + facet normal -0.152212 -0.975458 -0.159102 + outer loop + vertex -485.784 79.0667 251.791 + vertex -477.538 76.4079 260.204 + vertex -484.83 77.4732 260.648 + endloop + endfacet + facet normal -0.150001 -0.976794 -0.152885 + outer loop + vertex -486.765 80.5934 243 + vertex -478.604 78.0504 251.24 + vertex -485.784 79.0667 251.791 + endloop + endfacet + facet normal -0.149571 -0.978481 -0.142141 + outer loop + vertex -487.687 82.0046 234.255 + vertex -479.71 79.5808 242.546 + vertex -486.765 80.5934 243 + endloop + endfacet + facet normal -0.150377 -0.980348 -0.127687 + outer loop + vertex -488.531 83.2765 225.484 + vertex -480.755 80.9757 233.991 + vertex -487.687 82.0046 234.255 + endloop + endfacet + facet normal -0.151966 -0.982223 -0.110197 + outer loop + vertex -489.308 84.3856 216.67 + vertex -481.735 82.2331 225.412 + vertex -488.531 83.2765 225.484 + endloop + endfacet + facet normal -0.153907 -0.983939 -0.0904232 + outer loop + vertex -490.069 85.3184 207.814 + vertex -482.651 83.3387 216.73 + vertex -489.308 84.3856 216.67 + endloop + endfacet + facet normal -0.156001 -0.985331 -0.0691899 + outer loop + vertex -490.82 86.061 198.933 + vertex -483.534 84.2731 207.967 + vertex -490.069 85.3184 207.814 + endloop + endfacet + facet normal -0.15771 -0.986327 -0.0478195 + outer loop + vertex -491.558 86.6096 190.05 + vertex -484.423 85.0266 199.169 + vertex -490.82 86.061 198.933 + endloop + endfacet + facet normal -0.158439 -0.986974 -0.0279047 + outer loop + vertex -492.331 86.9853 181.156 + vertex -485.328 85.6007 190.361 + vertex -491.558 86.6096 190.05 + endloop + endfacet + facet normal -0.159122 -0.987223 -0.00837852 + outer loop + vertex -493.075 87.1805 172.259 + vertex -486.221 85.9971 181.547 + vertex -492.331 86.9853 181.156 + endloop + endfacet + facet normal -0.158673 -0.987279 0.0101898 + outer loop + vertex -493.815 87.2074 163.324 + vertex -487.106 86.226 172.711 + vertex -493.075 87.1805 172.259 + endloop + endfacet + facet normal -0.15731 -0.987139 0.0284594 + outer loop + vertex -494.539 87.0632 154.325 + vertex -487.975 86.2916 163.843 + vertex -493.815 87.2074 163.324 + endloop + endfacet + facet normal -0.154523 -0.986925 0.0458381 + outer loop + vertex -495.255 86.7561 145.297 + vertex -488.826 86.1972 154.938 + vertex -494.539 87.0632 154.325 + endloop + endfacet + facet normal -0.150984 -0.986534 0.0628791 + outer loop + vertex -495.954 86.2898 136.304 + vertex -489.644 85.9436 146.022 + vertex -495.255 86.7561 145.297 + endloop + endfacet + facet normal -0.14618 -0.986046 0.0796467 + outer loop + vertex -496.628 85.6674 127.361 + vertex -490.448 85.5384 137.107 + vertex -495.954 86.2898 136.304 + endloop + endfacet + facet normal -0.140296 -0.985462 0.0958171 + outer loop + vertex -497.265 84.8927 118.461 + vertex -491.211 84.9789 128.212 + vertex -496.628 85.6674 127.361 + endloop + endfacet + facet normal -0.132602 -0.984852 0.111731 + outer loop + vertex -497.805 83.9648 109.641 + vertex -491.957 84.2813 119.371 + vertex -497.265 84.8927 118.461 + endloop + endfacet + facet normal -0.124697 -0.983761 0.129096 + outer loop + vertex -498.1 82.8468 100.837 + vertex -492.574 83.4274 110.599 + vertex -497.805 83.9648 109.641 + endloop + endfacet + facet normal -0.115949 -0.98213 0.148244 + outer loop + vertex -497.993 81.4674 91.7814 + vertex -492.885 82.3759 101.795 + vertex -498.1 82.8468 100.837 + endloop + endfacet + facet normal -0.106265 -0.980431 0.165721 + outer loop + vertex -497.414 79.8249 82.4353 + vertex -497.993 81.4674 91.7814 + vertex -502.112 80.2118 81.7123 + endloop + endfacet + facet normal -0.0767194 -0.98003 0.183455 + outer loop + vertex -503.06 79.0374 75.0418 + vertex -502.112 80.2118 81.7123 + vertex -505.132 78.8015 72.9148 + endloop + endfacet + facet normal -0.155556 -0.968609 0.193905 + outer loop + vertex -507.614 80.1678 77.6372 + vertex -508.153 81.5303 84.0107 + vertex -510.857 81.536 81.8695 + endloop + endfacet + facet normal -0.151994 -0.972 0.179204 + outer loop + vertex -508.153 81.5303 84.0107 + vertex -507.406 82.2698 88.6552 + vertex -510.552 83.0358 90.142 + endloop + endfacet + facet normal -0.141812 -0.974629 0.173167 + outer loop + vertex -505.576 81.0804 83.8284 + vertex -502.324 81.9943 91.6355 + vertex -505.398 82.6759 92.954 + endloop + endfacet + facet normal -0.159443 -0.973457 0.164195 + outer loop + vertex -507.406 82.2698 88.6552 + vertex -507.814 83.3843 94.8667 + vertex -510.552 83.0358 90.142 + endloop + endfacet + facet normal -0.149559 -0.977006 0.151959 + outer loop + vertex -505.398 82.6759 92.954 + vertex -502.328 83.3858 100.54 + vertex -505.558 84.0231 101.458 + endloop + endfacet + facet normal -0.168528 -0.973881 0.152164 + outer loop + vertex -507.814 83.3843 94.8667 + vertex -508.073 84.3751 100.921 + vertex -510.84 84.5224 98.7995 + endloop + endfacet + facet normal -0.167055 -0.975805 0.141058 + outer loop + vertex -508.073 84.3751 100.921 + vertex -507.114 84.8977 105.672 + vertex -510.169 85.6233 107.073 + endloop + endfacet + facet normal -0.156229 -0.978593 0.133973 + outer loop + vertex -505.558 84.0231 101.458 + vertex -502.018 84.5292 109.283 + vertex -504.932 85.129 110.267 + endloop + endfacet + facet normal -0.172634 -0.97647 0.129244 + outer loop + vertex -507.114 84.8977 105.672 + vertex -507.249 85.7626 112.025 + vertex -510.169 85.6233 107.073 + endloop + endfacet + facet normal -0.1645 -0.979286 0.11806 + outer loop + vertex -504.932 85.129 110.267 + vertex -501.525 85.5033 118.118 + vertex -504.755 86.1433 118.926 + endloop + endfacet + facet normal -0.179524 -0.97642 0.119892 + outer loop + vertex -507.249 85.7626 112.025 + vertex -507.307 86.5367 118.243 + vertex -510.237 86.8006 116.005 + endloop + endfacet + facet normal -0.176945 -0.978266 0.108101 + outer loop + vertex -507.307 86.5367 118.243 + vertex -506.225 86.8864 123.179 + vertex -509.345 87.5893 124.434 + endloop + endfacet + facet normal -0.168813 -0.98048 0.100803 + outer loop + vertex -504.755 86.1433 118.926 + vertex -500.95 86.3219 127.036 + vertex -503.909 86.9303 127.998 + endloop + endfacet + facet normal -0.181904 -0.978621 0.0959801 + outer loop + vertex -506.225 86.8864 123.179 + vertex -506.272 87.5241 129.593 + vertex -509.345 87.5893 124.434 + endloop + endfacet + facet normal -0.174168 -0.981112 0.0841669 + outer loop + vertex -503.909 86.9303 127.998 + vertex -500.34 86.9843 136.013 + vertex -503.683 87.6443 136.789 + endloop + endfacet + facet normal -0.187586 -0.978483 0.0859247 + outer loop + vertex -506.272 87.5241 129.593 + vertex -506.3 88.0739 135.793 + vertex -509.309 88.4402 133.394 + endloop + endfacet + facet normal -0.183322 -0.98024 0.0743181 + outer loop + vertex -506.3 88.0739 135.793 + vertex -505.258 88.2467 140.642 + vertex -508.461 88.9252 141.69 + endloop + endfacet + facet normal -0.176305 -0.982123 0.065968 + outer loop + vertex -503.683 87.6443 136.789 + vertex -499.75 87.5007 145.16 + vertex -503.077 88.1995 146.674 + endloop + endfacet + facet normal -0.186813 -0.980327 0.0637126 + outer loop + vertex -505.258 88.2467 140.642 + vertex -505.729 88.665 145.695 + vertex -508.461 88.9252 141.69 + endloop + endfacet + facet normal -0.191326 -0.98015 0.05196 + outer loop + vertex -505.729 88.665 145.695 + vertex -504.987 88.8621 152.146 + vertex -508.432 89.4465 150.484 + endloop + endfacet + facet normal -0.178797 -0.982753 0.0471967 + outer loop + vertex -503.077 88.1995 146.674 + vertex -499.086 87.8446 154.405 + vertex -502.182 88.4863 156.037 + endloop + endfacet + facet normal -0.186193 -0.981663 0.0408661 + outer loop + vertex -504.987 88.8621 152.146 + vertex -504.174 88.971 158.467 + vertex -507.524 89.6331 159.109 + endloop + endfacet + facet normal -0.181393 -0.982994 0.0286394 + outer loop + vertex -502.182 88.4863 156.037 + vertex -498.459 88.0152 163.447 + vertex -501.959 88.6992 164.755 + endloop + endfacet + facet normal -0.188652 -0.981645 0.0280091 + outer loop + vertex -504.174 88.971 158.467 + vertex -504.771 89.228 163.456 + vertex -507.524 89.6331 159.109 + endloop + endfacet + facet normal -0.193031 -0.981076 0.0151189 + outer loop + vertex -504.771 89.228 163.456 + vertex -503.991 89.1737 169.891 + vertex -507.54 89.8443 168.091 + endloop + endfacet + facet normal -0.180946 -0.983452 0.00895372 + outer loop + vertex -501.959 88.6992 164.755 + vertex -497.823 88.0078 172.394 + vertex -501.052 88.6157 173.918 + endloop + endfacet + facet normal -0.187341 -0.98229 0.00307794 + outer loop + vertex -503.991 89.1737 169.891 + vertex -503.121 89.0273 176.139 + vertex -506.595 89.6916 176.688 + endloop + endfacet + facet normal -0.181922 -0.983266 -0.0095799 + outer loop + vertex -501.052 88.6157 173.918 + vertex -497.173 87.826 181.303 + vertex -500.809 88.487 182.524 + endloop + endfacet + facet normal -0.189343 -0.981859 -0.0100987 + outer loop + vertex -503.121 89.0273 176.139 + vertex -503.734 89.0949 181.065 + vertex -506.595 89.6916 176.688 + endloop + endfacet + facet normal -0.192427 -0.981042 -0.0229981 + outer loop + vertex -503.734 89.0949 181.065 + vertex -502.934 88.788 187.47 + vertex -506.602 89.5517 185.576 + endloop + endfacet + facet normal -0.181089 -0.983023 -0.0295548 + outer loop + vertex -500.809 88.487 182.524 + vertex -496.518 87.4652 190.215 + vertex -499.897 88.0447 191.641 + endloop + endfacet + facet normal -0.185904 -0.981894 -0.0363745 + outer loop + vertex -502.934 88.788 187.47 + vertex -502.069 88.3906 193.772 + vertex -505.666 89.0576 194.152 + endloop + endfacet + facet normal -0.181089 -0.982191 -0.0500824 + outer loop + vertex -499.897 88.0447 191.641 + vertex -495.864 86.9195 199.126 + vertex -499.671 87.5652 200.229 + endloop + endfacet + facet normal -0.187171 -0.981064 -0.0498088 + outer loop + vertex -502.069 88.3906 193.772 + vertex -502.704 88.268 198.573 + vertex -505.666 89.0576 194.152 + endloop + endfacet + facet normal -0.189764 -0.979619 -0.0658582 + outer loop + vertex -502.704 88.268 198.573 + vertex -501.889 87.6731 205.076 + vertex -505.672 88.5449 203.008 + endloop + endfacet + facet normal -0.177864 -0.981366 -0.0727043 + outer loop + vertex -499.671 87.5652 200.229 + vertex -495.219 86.1803 208.031 + vertex -498.734 86.7144 209.42 + endloop + endfacet + facet normal -0.183225 -0.979832 -0.0797368 + outer loop + vertex -501.889 87.6731 205.076 + vertex -501 86.9908 211.416 + vertex -504.719 87.6677 211.643 + endloop + endfacet + facet normal -0.176287 -0.979879 -0.0935939 + outer loop + vertex -498.734 86.7144 209.42 + vertex -494.58 85.2474 216.956 + vertex -498.581 85.8609 218.068 + endloop + endfacet + facet normal -0.183823 -0.9785 -0.0935287 + outer loop + vertex -501 86.9908 211.416 + vertex -501.699 86.6677 216.171 + vertex -504.719 87.6677 211.643 + endloop + endfacet + facet normal -0.185693 -0.976703 -0.107561 + outer loop + vertex -501.699 86.6677 216.171 + vertex -500.998 85.8392 222.483 + vertex -504.811 86.7864 220.465 + endloop + endfacet + facet normal -0.172399 -0.978375 -0.114286 + outer loop + vertex -498.581 85.8609 218.068 + vertex -493.95 84.1232 225.959 + vertex -497.976 84.6158 227.814 + endloop + endfacet + facet normal -0.175481 -0.977482 -0.117197 + outer loop + vertex -500.998 85.8392 222.483 + vertex -500.566 85.1885 227.264 + vertex -503.873 85.6102 228.698 + endloop + endfacet + facet normal -0.181129 -0.97469 -0.131039 + outer loop + vertex -500.566 85.1885 227.264 + vertex -500.349 84.4475 232.475 + vertex -503.873 85.6102 228.698 + endloop + endfacet + facet normal -0.168893 -0.976661 -0.132699 + outer loop + vertex -497.976 84.6158 227.814 + vertex -493.183 82.8118 234.992 + vertex -497.006 83.211 236.919 + endloop + endfacet + facet normal -0.182626 -0.973342 -0.138757 + outer loop + vertex -500.349 84.4475 232.475 + vertex -499.886 83.3022 239.899 + vertex -503.934 84.3901 237.596 + endloop + endfacet + facet normal -0.166835 -0.975234 -0.145209 + outer loop + vertex -497.006 83.211 236.919 + vertex -492.361 81.3908 243.808 + vertex -496.622 81.8746 245.454 + endloop + endfacet + facet normal -0.17574 -0.973451 -0.146657 + outer loop + vertex -499.886 83.3022 239.899 + vertex -499.496 82.5237 244.601 + vertex -502.977 82.9633 245.852 + endloop + endfacet + facet normal -0.178193 -0.971865 -0.154032 + outer loop + vertex -499.496 82.5237 244.601 + vertex -499.167 81.6611 249.661 + vertex -502.977 82.9633 245.852 + endloop + endfacet + facet normal -0.163922 -0.974196 -0.155153 + outer loop + vertex -496.622 81.8746 245.454 + vertex -491.452 79.8723 252.564 + vertex -495.458 80.269 254.306 + endloop + endfacet + facet normal -0.180248 -0.971113 -0.156364 + outer loop + vertex -499.167 81.6611 249.661 + vertex -498.545 80.3551 257.056 + vertex -502.931 81.5621 254.616 + endloop + endfacet + facet normal -0.163369 -0.973833 -0.157986 + outer loop + vertex -495.458 80.269 254.306 + vertex -490.564 78.3073 261.337 + vertex -494.994 78.7877 262.956 + endloop + endfacet + facet normal -0.187306 -0.96967 -0.157026 + outer loop + vertex -498.545 80.3551 257.056 + vertex -498.045 79.4941 261.776 + vertex -501.739 79.9958 263.085 + endloop + endfacet + facet normal -0.185758 -0.970729 -0.152249 + outer loop + vertex -498.045 79.4941 261.776 + vertex -497.682 78.6011 267.026 + vertex -501.739 79.9958 263.085 + endloop + endfacet + facet normal -0.169756 -0.973765 -0.151544 + outer loop + vertex -497.262 77.5507 273.305 + vertex -497.682 78.6011 267.026 + vertex -493.901 77.0372 272.84 + endloop + endfacet + facet normal -0.162914 -0.974125 -0.156653 + outer loop + vertex -490.564 78.3073 261.337 + vertex -489.61 76.6996 270.341 + vertex -494.994 78.7877 262.956 + endloop + endfacet + facet normal -0.172917 -0.97434 -0.144087 + outer loop + vertex -493.901 77.0372 272.84 + vertex -487.945 74.8468 280.505 + vertex -492.735 75.5977 281.175 + endloop + endfacet + facet normal -0.165126 -0.973753 -0.156651 + outer loop + vertex -484.27 76.0081 269.011 + vertex -483.449 74.6332 276.693 + vertex -489.61 76.6996 270.341 + endloop + endfacet + facet normal -0.169396 -0.973763 -0.151954 + outer loop + vertex -483.449 74.6332 276.693 + vertex -477.195 72.8398 281.213 + vertex -481.254 73.252 283.096 + endloop + endfacet + facet normal -0.178142 -0.973587 -0.142806 + outer loop + vertex -478.451 72.1442 287.151 + vertex -482.721 73.0015 286.634 + vertex -481.254 73.252 283.096 + endloop + endfacet + facet normal -0.181501 -0.97374 -0.13743 + outer loop + vertex -486.195 73.5608 287.306 + vertex -489.574 74.2903 286.6 + vertex -487.945 74.8468 280.505 + endloop + endfacet + facet normal -0.188346 -0.974426 -0.122556 + outer loop + vertex -486.195 73.5608 287.306 + vertex -482.026 72.2958 290.956 + vertex -485.906 72.9774 291.499 + endloop + endfacet + facet normal -0.187626 -0.975334 -0.116278 + outer loop + vertex -482.026 72.2958 290.956 + vertex -480.788 71.5387 295.309 + vertex -485.906 72.9774 291.499 + endloop + endfacet + facet normal -0.179222 -0.974456 -0.135329 + outer loop + vertex -478.451 72.1442 287.151 + vertex -477.776 71.5907 290.244 + vertex -482.721 73.0015 286.634 + endloop + endfacet + facet normal -0.187955 -0.975283 -0.116176 + outer loop + vertex -482.026 72.2958 290.956 + vertex -476.535 70.8939 293.842 + vertex -480.788 71.5387 295.309 + endloop + endfacet + facet normal -0.175196 -0.974842 -0.1378 + outer loop + vertex -473.501 70.9431 289.39 + vertex -472 70.2186 292.607 + vertex -477.776 71.5907 290.244 + endloop + endfacet + facet normal -0.175357 -0.975667 -0.131617 + outer loop + vertex -472 70.2186 292.607 + vertex -466.317 68.9945 294.109 + vertex -470.858 69.6256 295.481 + endloop + endfacet + facet normal -0.17882 -0.976305 -0.121867 + outer loop + vertex -470.858 69.6256 295.481 + vertex -466.285 68.7157 296.061 + vertex -470.179 69.2359 297.607 + endloop + endfacet + facet normal -0.188041 -0.975234 -0.116446 + outer loop + vertex -476.535 70.8939 293.842 + vertex -475.383 70.2789 297.132 + vertex -480.788 71.5387 295.309 + endloop + endfacet + facet normal -0.196242 -0.975724 -0.0972163 + outer loop + vertex -478.629 70.8419 297.719 + vertex -477.412 70.4639 299.056 + vertex -480.789 71.2274 298.21 + endloop + endfacet + facet normal -0.197913 -0.976005 -0.0907982 + outer loop + vertex -480.789 71.2274 298.21 + vertex -477.412 70.4639 299.056 + vertex -479.76 70.8401 300.131 + endloop + endfacet + facet normal -0.195531 -0.975003 -0.105534 + outer loop + vertex -485.906 72.9774 291.499 + vertex -480.788 71.5387 295.309 + vertex -484.89 72.2623 296.224 + endloop + endfacet + facet normal -0.200228 -0.975654 -0.0894877 + outer loop + vertex -480.789 71.2274 298.21 + vertex -479.76 70.8401 300.131 + vertex -482.605 71.5095 299.198 + endloop + endfacet + facet normal -0.20439 -0.976593 -0.0670179 + outer loop + vertex -482.123 71.2758 300.847 + vertex -479.355 70.6594 301.388 + vertex -481.905 71.1496 302.021 + endloop + endfacet + facet normal -0.196767 -0.976481 -0.0881292 + outer loop + vertex -477.412 70.4639 299.056 + vertex -476.265 70.1237 300.265 + vertex -479.76 70.8401 300.131 + endloop + endfacet + facet normal -0.186931 -0.97864 -0.0855651 + outer loop + vertex -474.016 69.807 298.973 + vertex -471.833 69.3593 299.326 + vertex -476.265 70.1237 300.265 + endloop + endfacet + facet normal -0.182349 -0.975312 -0.12456 + outer loop + vertex -471.411 69.2361 299.673 + vertex -471.833 69.3593 299.326 + vertex -464.625 68.2993 297.074 + endloop + endfacet + facet normal -0.201881 -0.97781 -0.0559591 + outer loop + vertex -481.905 71.1496 302.021 + vertex -479.355 70.6594 301.388 + vertex -480.464 70.8291 302.423 + endloop + endfacet + facet normal -0.193605 -0.979966 -0.0467351 + outer loop + vertex -475.949 70.0056 300.985 + vertex -480.464 70.8291 302.423 + vertex -479.355 70.6594 301.388 + endloop + endfacet + facet normal -0.209458 -0.97559 -0.0659671 + outer loop + vertex -482.123 71.2758 300.847 + vertex -481.905 71.1496 302.021 + vertex -484.142 71.6742 301.365 + endloop + endfacet + facet normal -0.210466 -0.97507 -0.0702981 + outer loop + vertex -484.838 71.9737 299.294 + vertex -482.123 71.2758 300.847 + vertex -484.142 71.6742 301.365 + endloop + endfacet + facet normal -0.200548 -0.975698 -0.0882862 + outer loop + vertex -488.036 72.8506 296.868 + vertex -484.89 72.2623 296.224 + vertex -484.838 71.9737 299.294 + endloop + endfacet + facet normal -0.202364 -0.975477 -0.0865617 + outer loop + vertex -491.142 73.8311 293.081 + vertex -488.036 72.8506 296.868 + vertex -489.987 73.2125 297.351 + endloop + endfacet + facet normal -0.198491 -0.977651 -0.0692771 + outer loop + vertex -489.987 73.2125 297.351 + vertex -489.069 72.8137 300.349 + vertex -490.378 73.1923 298.757 + endloop + endfacet + facet normal -0.21739 -0.974644 -0.053019 + outer loop + vertex -490.378 73.1923 298.757 + vertex -489.069 72.8137 300.349 + vertex -489.521 72.8639 301.278 + endloop + endfacet + facet normal -0.217647 -0.974742 -0.0500676 + outer loop + vertex -489.069 72.8137 300.349 + vertex -487.315 72.3351 302.042 + vertex -488.203 72.5048 302.597 + endloop + endfacet + facet normal -0.212573 -0.9752 -0.0616234 + outer loop + vertex -486.309 72.2371 299.997 + vertex -485.874 72.0326 301.73 + vertex -487.95 72.6055 299.827 + endloop + endfacet + facet normal -0.21493 -0.97522 -0.0524502 + outer loop + vertex -485.874 72.0326 301.73 + vertex -483.648 71.4932 302.638 + vertex -485.539 71.8907 302.998 + endloop + endfacet + facet normal -0.213769 -0.975815 -0.0456957 + outer loop + vertex -485.539 71.8907 302.998 + vertex -483.648 71.4932 302.638 + vertex -484.14 71.5573 303.573 + endloop + endfacet + facet normal -0.218606 -0.975056 -0.0384228 + outer loop + vertex -484.14 71.5573 303.573 + vertex -484.475 71.6096 304.151 + vertex -486.652 72.0886 304.383 + endloop + endfacet + facet normal -0.216622 -0.975059 -0.0483311 + outer loop + vertex -487.315 72.3351 302.042 + vertex -486.626 72.1097 303.5 + vertex -488.203 72.5048 302.597 + endloop + endfacet + facet normal -0.241462 -0.970363 0.00959742 + outer loop + vertex -488.488 72.5374 303.579 + vertex -487.559 72.308 303.761 + vertex -486.652 72.0886 304.383 + endloop + endfacet + facet normal -0.214271 -0.975418 -0.051461 + outer loop + vertex -489.069 72.8137 300.349 + vertex -488.203 72.5048 302.597 + vertex -489.521 72.8639 301.278 + endloop + endfacet + facet normal -0.21725 -0.974672 -0.0530703 + outer loop + vertex -490.378 73.1923 298.757 + vertex -489.521 72.8639 301.278 + vertex -490.841 73.2468 299.65 + endloop + endfacet + facet normal -0.218458 -0.974815 -0.0448444 + outer loop + vertex -492.668 73.7248 298.456 + vertex -493.828 73.8543 301.292 + vertex -495.003 74.2372 298.69 + endloop + endfacet + facet normal -0.22955 -0.972871 -0.0287931 + outer loop + vertex -492.983 73.5964 303.27 + vertex -496.601 74.4389 303.645 + vertex -493.828 73.8543 301.292 + endloop + endfacet + facet normal -0.228299 -0.97347 -0.0153829 + outer loop + vertex -492.983 73.5964 303.27 + vertex -494.527 73.9291 305.125 + vertex -496.601 74.4389 303.645 + endloop + endfacet + facet normal -0.240378 -0.970568 -0.0147216 + outer loop + vertex -489.091 72.6494 306.048 + vertex -489.894 72.8995 302.674 + vertex -488.488 72.5374 303.579 + endloop + endfacet + facet normal -0.228487 -0.973423 -0.0155475 + outer loop + vertex -492.983 73.5964 303.27 + vertex -491.184 73.165 303.83 + vertex -494.527 73.9291 305.125 + endloop + endfacet + facet normal -0.226963 -0.973539 -0.0266411 + outer loop + vertex -494.273 73.8559 306.11 + vertex -489.091 72.6494 306.048 + vertex -493.66 73.7074 306.307 + endloop + endfacet + facet normal -0.235398 -0.971899 0.000787976 + outer loop + vertex -493.66 73.7074 306.307 + vertex -498.594 74.9025 306.379 + vertex -494.273 73.8559 306.11 + endloop + endfacet + facet normal -0.233711 -0.971905 0.0279165 + outer loop + vertex -498.071 74.7683 306.082 + vertex -494.273 73.8559 306.11 + vertex -498.594 74.9025 306.379 + endloop + endfacet + facet normal -0.234837 -0.971486 0.0326706 + outer loop + vertex -495.193 74.0834 306.47 + vertex -498.594 74.9025 306.379 + vertex -493.66 73.7074 306.307 + endloop + endfacet + facet normal -0.235218 -0.959201 0.156861 + outer loop + vertex -502.785 75.9469 306.481 + vertex -498.594 74.9025 306.379 + vertex -495.193 74.0834 306.47 + endloop + endfacet + facet normal -0.238216 -0.970701 0.0315093 + outer loop + vertex -495.193 74.0834 306.47 + vertex -498.253 74.8476 306.876 + vertex -502.785 75.9469 306.481 + endloop + endfacet + facet normal -0.24246 -0.965542 0.0945584 + outer loop + vertex -509.815 77.7385 306.749 + vertex -502.785 75.9469 306.481 + vertex -498.253 74.8476 306.876 + endloop + endfacet + facet normal -0.242789 -0.96896 0.0465845 + outer loop + vertex -500.604 75.4748 307.665 + vertex -509.815 77.7385 306.749 + vertex -498.253 74.8476 306.876 + endloop + endfacet + facet normal -0.237511 -0.969364 0.0626248 + outer loop + vertex -500.604 75.4748 307.665 + vertex -498.253 74.8476 306.876 + vertex -493.829 73.8003 307.443 + endloop + endfacet + facet normal -0.238197 -0.970075 0.0470762 + outer loop + vertex -495.459 74.2561 308.589 + vertex -500.604 75.4748 307.665 + vertex -493.829 73.8003 307.443 + endloop + endfacet + facet normal -0.227944 -0.97168 0.06229 + outer loop + vertex -495.459 74.2561 308.589 + vertex -493.829 73.8003 307.443 + vertex -491.826 73.4291 308.984 + endloop + endfacet + facet normal -0.22995 -0.969447 0.0854131 + outer loop + vertex -495.651 74.4345 310.095 + vertex -495.459 74.2561 308.589 + vertex -491.826 73.4291 308.984 + endloop + endfacet + facet normal -0.224315 -0.968916 0.104331 + outer loop + vertex -491.826 73.4291 308.984 + vertex -493.636 74.1878 312.138 + vertex -495.651 74.4345 310.095 + endloop + endfacet + facet normal -0.228412 -0.967495 0.108545 + outer loop + vertex -496.833 74.8888 311.657 + vertex -495.651 74.4345 310.095 + vertex -493.636 74.1878 312.138 + endloop + endfacet + facet normal -0.231562 -0.963331 0.135546 + outer loop + vertex -497.104 75.2159 313.52 + vertex -496.833 74.8888 311.657 + vertex -493.636 74.1878 312.138 + endloop + endfacet + facet normal -0.222156 -0.962087 0.158229 + outer loop + vertex -493.636 74.1878 312.138 + vertex -495.48 75.2273 315.869 + vertex -497.104 75.2159 313.52 + endloop + endfacet + facet normal -0.227775 -0.960125 0.162104 + outer loop + vertex -498.373 75.8186 315.306 + vertex -497.104 75.2159 313.52 + vertex -495.48 75.2273 315.869 + endloop + endfacet + facet normal -0.231958 -0.953978 0.190055 + outer loop + vertex -498.69 76.294 317.305 + vertex -498.373 75.8186 315.306 + vertex -495.48 75.2273 315.869 + endloop + endfacet + facet normal -0.246037 -0.951027 0.18712 + outer loop + vertex -498.69 76.294 317.305 + vertex -503.373 77.1596 315.548 + vertex -498.373 75.8186 315.306 + endloop + endfacet + facet normal -0.248112 -0.954676 0.164423 + outer loop + vertex -503.373 77.1596 315.548 + vertex -502.725 76.6796 313.738 + vertex -498.373 75.8186 315.306 + endloop + endfacet + facet normal -0.250852 -0.954152 0.163303 + outer loop + vertex -503.373 77.1596 315.548 + vertex -512.22 79.1597 313.644 + vertex -502.725 76.6796 313.738 + endloop + endfacet + facet normal -0.251182 -0.955814 0.152732 + outer loop + vertex -512.22 79.1597 313.644 + vertex -509.928 78.312 312.108 + vertex -502.725 76.6796 313.738 + endloop + endfacet + facet normal -0.248615 -0.958641 0.138557 + outer loop + vertex -502.725 76.6796 313.738 + vertex -509.928 78.312 312.108 + vertex -502.093 76.2621 311.985 + endloop + endfacet + facet normal -0.244385 -0.959477 0.140282 + outer loop + vertex -502.725 76.6796 313.738 + vertex -502.093 76.2621 311.985 + vertex -497.104 75.2159 313.52 + endloop + endfacet + facet normal -0.249302 -0.96041 0.124345 + outer loop + vertex -509.928 78.312 312.108 + vertex -511.491 78.4971 310.404 + vertex -502.093 76.2621 311.985 + endloop + endfacet + facet normal -0.247913 -0.962085 0.113721 + outer loop + vertex -502.093 76.2621 311.985 + vertex -511.491 78.4971 310.404 + vertex -501.536 75.9242 310.339 + endloop + endfacet + facet normal -0.244258 -0.962853 0.115115 + outer loop + vertex -502.093 76.2621 311.985 + vertex -501.536 75.9242 310.339 + vertex -496.833 74.8888 311.657 + endloop + endfacet + facet normal -0.24814 -0.962794 0.107023 + outer loop + vertex -511.491 78.4971 310.404 + vertex -509.384 77.8068 309.078 + vertex -501.536 75.9242 310.339 + endloop + endfacet + facet normal -0.24576 -0.965283 0.0884875 + outer loop + vertex -501.536 75.9242 310.339 + vertex -509.384 77.8068 309.078 + vertex -501.169 75.6974 308.886 + endloop + endfacet + facet normal -0.240909 -0.966376 0.0898849 + outer loop + vertex -501.536 75.9242 310.339 + vertex -501.169 75.6974 308.886 + vertex -495.651 74.4345 310.095 + endloop + endfacet + facet normal -0.246251 -0.966144 0.0769804 + outer loop + vertex -509.384 77.8068 309.078 + vertex -511.596 78.2687 307.8 + vertex -501.169 75.6974 308.886 + endloop + endfacet + facet normal -0.245129 -0.967431 0.0631627 + outer loop + vertex -501.169 75.6974 308.886 + vertex -511.596 78.2687 307.8 + vertex -500.604 75.4748 307.665 + endloop + endfacet + facet normal -0.249698 -0.964721 0.083458 + outer loop + vertex -509.384 77.8068 309.078 + vertex -525.735 81.9896 308.509 + vertex -511.596 78.2687 307.8 + endloop + endfacet + facet normal -0.248698 -0.963638 0.0977263 + outer loop + vertex -525.735 81.9896 308.509 + vertex -527.638 82.3066 306.792 + vertex -511.596 78.2687 307.8 + endloop + endfacet + facet normal -0.247544 -0.966491 0.0679416 + outer loop + vertex -509.815 77.7385 306.749 + vertex -511.596 78.2687 307.8 + vertex -527.638 82.3066 306.792 + endloop + endfacet + facet normal -0.24993 -0.963171 0.0991787 + outer loop + vertex -525.735 81.9896 308.509 + vertex -548.076 87.6512 307.192 + vertex -527.638 82.3066 306.792 + endloop + endfacet + facet normal -0.248397 -0.959716 0.131319 + outer loop + vertex -548.076 87.6512 307.192 + vertex -546.095 87.0219 306.34 + vertex -527.638 82.3066 306.792 + endloop + endfacet + facet normal -0.248319 -0.95871 0.138611 + outer loop + vertex -527.638 82.3066 306.792 + vertex -546.095 87.0219 306.34 + vertex -531.637 83.2467 306.131 + endloop + endfacet + facet normal -0.246436 -0.961245 0.123605 + outer loop + vertex -531.637 83.2467 306.131 + vertex -520.504 80.4018 306.202 + vertex -527.638 82.3066 306.792 + endloop + endfacet + facet normal -0.241866 -0.940511 0.238623 + outer loop + vertex -531.637 83.2467 306.131 + vertex -524.893 81.4871 306.03 + vertex -520.504 80.4018 306.202 + endloop + endfacet + facet normal -0.240512 -0.927559 0.285986 + outer loop + vertex -520.504 80.4018 306.202 + vertex -524.893 81.4871 306.03 + vertex -517.195 79.5232 306.135 + endloop + endfacet + facet normal -0.232771 -0.903918 0.358817 + outer loop + vertex -520.504 80.4018 306.202 + vertex -517.195 79.5232 306.135 + vertex -511.319 78.0687 306.283 + endloop + endfacet + facet normal -0.245593 -0.963083 0.11025 + outer loop + vertex -511.319 78.0687 306.283 + vertex -509.815 77.7385 306.749 + vertex -520.504 80.4018 306.202 + endloop + endfacet + facet normal -0.232955 -0.904937 0.356121 + outer loop + vertex -511.319 78.0687 306.283 + vertex -517.195 79.5232 306.135 + vertex -507.537 77.1075 306.315 + endloop + endfacet + facet normal -0.234348 -0.910963 0.339452 + outer loop + vertex -511.319 78.0687 306.283 + vertex -507.537 77.1075 306.315 + vertex -502.785 75.9469 306.481 + endloop + endfacet + facet normal -0.137339 -0.484952 0.86369 + outer loop + vertex -507.537 77.1075 306.315 + vertex -517.195 79.5232 306.135 + vertex -513.231 78.5087 306.196 + endloop + endfacet + facet normal -0.189783 -0.707649 0.680599 + outer loop + vertex -517.195 79.5232 306.135 + vertex -524.893 81.4871 306.03 + vertex -523.038 80.985 306.026 + endloop + endfacet + facet normal -0.227938 -0.895384 0.382534 + outer loop + vertex -524.893 81.4871 306.03 + vertex -531.637 83.2467 306.131 + vertex -529.936 82.764 306.015 + endloop + endfacet + facet normal -0.238563 -0.929262 0.282063 + outer loop + vertex -531.637 83.2467 306.131 + vertex -546.095 87.0219 306.34 + vertex -538.051 84.8664 306.042 + endloop + endfacet + facet normal -0.250206 -0.959803 0.127181 + outer loop + vertex -548.076 87.6512 307.192 + vertex -566.101 92.2756 306.63 + vertex -546.095 87.0219 306.34 + endloop + endfacet + facet normal -0.248322 -0.954672 0.164125 + outer loop + vertex -546.095 87.0219 306.34 + vertex -566.101 92.2756 306.63 + vertex -557.515 89.9781 306.257 + endloop + endfacet + facet normal -0.250213 -0.961988 0.109423 + outer loop + vertex -571.889 93.8833 307.529 + vertex -566.101 92.2756 306.63 + vertex -548.076 87.6512 307.192 + endloop + endfacet + facet normal -0.249951 -0.961324 0.115679 + outer loop + vertex -548.982 88.0889 308.873 + vertex -571.889 93.8833 307.529 + vertex -548.076 87.6512 307.192 + endloop + endfacet + facet normal -0.249973 -0.961214 0.116539 + outer loop + vertex -573.102 94.4198 309.352 + vertex -571.889 93.8833 307.529 + vertex -548.982 88.0889 308.873 + endloop + endfacet + facet normal -0.248642 -0.958087 0.142289 + outer loop + vertex -549.098 88.4902 311.372 + vertex -573.102 94.4198 309.352 + vertex -548.982 88.0889 308.873 + endloop + endfacet + facet normal -0.25108 -0.957482 0.142078 + outer loop + vertex -549.098 88.4902 311.372 + vertex -548.982 88.0889 308.873 + vertex -525.702 82.313 311.088 + endloop + endfacet + facet normal -0.24998 -0.954307 0.163731 + outer loop + vertex -525.982 82.9269 314.24 + vertex -549.098 88.4902 311.372 + vertex -525.702 82.313 311.088 + endloop + endfacet + facet normal -0.253914 -0.95336 0.163197 + outer loop + vertex -525.982 82.9269 314.24 + vertex -525.702 82.313 311.088 + vertex -512.22 79.1597 313.644 + endloop + endfacet + facet normal -0.253151 -0.951985 0.172158 + outer loop + vertex -510.745 79.112 315.549 + vertex -525.982 82.9269 314.24 + vertex -512.22 79.1597 313.644 + endloop + endfacet + facet normal -0.254173 -0.945832 0.201983 + outer loop + vertex -510.745 79.112 315.549 + vertex -512.871 80.0207 317.129 + vertex -525.982 82.9269 314.24 + endloop + endfacet + facet normal -0.255722 -0.943323 0.211538 + outer loop + vertex -526.319 83.8028 317.738 + vertex -525.982 82.9269 314.24 + vertex -512.871 80.0207 317.129 + endloop + endfacet + facet normal -0.254116 -0.940123 0.227143 + outer loop + vertex -511.41 80.1086 319.127 + vertex -526.319 83.8028 317.738 + vertex -512.871 80.0207 317.129 + endloop + endfacet + facet normal -0.255491 -0.939513 0.228122 + outer loop + vertex -511.41 80.1086 319.127 + vertex -512.871 80.0207 317.129 + vertex -504.393 78.185 319.064 + endloop + endfacet + facet normal -0.253447 -0.932963 0.255625 + outer loop + vertex -505.064 78.8769 320.924 + vertex -511.41 80.1086 319.127 + vertex -504.393 78.185 319.064 + endloop + endfacet + facet normal -0.254026 -0.932872 0.255382 + outer loop + vertex -505.064 78.8769 320.924 + vertex -504.393 78.185 319.064 + vertex -500.328 77.4563 320.445 + endloop + endfacet + facet normal -0.248329 -0.92488 0.287976 + outer loop + vertex -500.852 78.2411 322.514 + vertex -505.064 78.8769 320.924 + vertex -500.328 77.4563 320.445 + endloop + endfacet + facet normal -0.21892 -0.929399 0.297139 + outer loop + vertex -500.852 78.2411 322.514 + vertex -500.328 77.4563 320.445 + vertex -497.403 76.6627 320.118 + endloop + endfacet + facet normal -0.222759 -0.930093 0.292069 + outer loop + vertex -497.403 76.6627 320.118 + vertex -498.627 78.2894 324.365 + vertex -500.852 78.2411 322.514 + endloop + endfacet + facet normal -0.227402 -0.941187 0.249909 + outer loop + vertex -500.328 77.4563 320.445 + vertex -499.826 76.9447 318.976 + vertex -497.403 76.6627 320.118 + endloop + endfacet + facet normal -0.216008 -0.950479 0.22345 + outer loop + vertex -499.826 76.9447 318.976 + vertex -498.69 76.294 317.305 + vertex -497.403 76.6627 320.118 + endloop + endfacet + facet normal -0.215893 -0.950517 0.223402 + outer loop + vertex -495.48 75.2273 315.869 + vertex -497.403 76.6627 320.118 + vertex -498.69 76.294 317.305 + endloop + endfacet + facet normal -0.246241 -0.947943 0.201916 + outer loop + vertex -499.826 76.9447 318.976 + vertex -503.873 77.6463 317.334 + vertex -498.69 76.294 317.305 + endloop + endfacet + facet normal -0.251853 -0.942916 0.217899 + outer loop + vertex -504.393 78.185 319.064 + vertex -503.873 77.6463 317.334 + vertex -499.826 76.9447 318.976 + endloop + endfacet + facet normal -0.25122 -0.921204 0.297106 + outer loop + vertex -507.007 80.0871 323.033 + vertex -505.064 78.8769 320.924 + vertex -500.852 78.2411 322.514 + endloop + endfacet + facet normal -0.253344 -0.921244 0.295171 + outer loop + vertex -507.007 80.0871 323.033 + vertex -513.993 81.3012 320.827 + vertex -505.064 78.8769 320.924 + endloop + endfacet + facet normal -0.252648 -0.922327 0.292374 + outer loop + vertex -513.946 81.8722 322.669 + vertex -513.993 81.3012 320.827 + vertex -507.007 80.0871 323.033 + endloop + endfacet + facet normal -0.251046 -0.906484 0.339504 + outer loop + vertex -513.946 81.8722 322.669 + vertex -507.007 80.0871 323.033 + vertex -513.122 82.5755 325.156 + endloop + endfacet + facet normal -0.252918 -0.905803 0.339931 + outer loop + vertex -513.122 82.5755 325.156 + vertex -526.974 85.0628 321.477 + vertex -513.946 81.8722 322.669 + endloop + endfacet + facet normal -0.250401 -0.911354 0.326701 + outer loop + vertex -529.626 87.0852 325.086 + vertex -526.974 85.0628 321.477 + vertex -513.122 82.5755 325.156 + endloop + endfacet + facet normal -0.244462 -0.911385 0.331081 + outer loop + vertex -529.626 87.0852 325.086 + vertex -548.908 90.9401 321.46 + vertex -526.974 85.0628 321.477 + endloop + endfacet + facet normal -0.245148 -0.908885 0.337389 + outer loop + vertex -548.973 92.2687 324.992 + vertex -548.908 90.9401 321.46 + vertex -529.626 87.0852 325.086 + endloop + endfacet + facet normal -0.240375 -0.909974 0.337886 + outer loop + vertex -548.973 92.2687 324.992 + vertex -568.494 96.288 321.93 + vertex -548.908 90.9401 321.46 + endloop + endfacet + facet normal -0.244162 -0.920864 0.303965 + outer loop + vertex -568.494 96.288 321.93 + vertex -571.618 95.9921 318.523 + vertex -548.908 90.9401 321.46 + endloop + endfacet + facet normal -0.242889 -0.928435 0.281094 + outer loop + vertex -548.908 90.9401 321.46 + vertex -571.618 95.9921 318.523 + vertex -548.979 89.8825 317.906 + endloop + endfacet + facet normal -0.248611 -0.927013 0.280785 + outer loop + vertex -548.908 90.9401 321.46 + vertex -548.979 89.8825 317.906 + vertex -526.974 85.0628 321.477 + endloop + endfacet + facet normal -0.247632 -0.930434 0.270131 + outer loop + vertex -526.974 85.0628 321.477 + vertex -548.979 89.8825 317.906 + vertex -526.319 83.8028 317.738 + endloop + endfacet + facet normal -0.255707 -0.928816 0.268171 + outer loop + vertex -526.974 85.0628 321.477 + vertex -526.319 83.8028 317.738 + vertex -513.993 81.3012 320.827 + endloop + endfacet + facet normal -0.250738 -0.940842 0.227919 + outer loop + vertex -548.979 89.8825 317.906 + vertex -549.003 89.0537 314.459 + vertex -526.319 83.8028 317.738 + endloop + endfacet + facet normal -0.245467 -0.942163 0.228201 + outer loop + vertex -548.979 89.8825 317.906 + vertex -572.009 95.1993 315.085 + vertex -549.003 89.0537 314.459 + endloop + endfacet + facet normal -0.248046 -0.948593 0.196582 + outer loop + vertex -572.009 95.1993 315.085 + vertex -572.399 94.654 311.961 + vertex -549.003 89.0537 314.459 + endloop + endfacet + facet normal -0.247201 -0.951832 0.181407 + outer loop + vertex -549.003 89.0537 314.459 + vertex -572.399 94.654 311.961 + vertex -549.098 88.4902 311.372 + endloop + endfacet + facet normal -0.243091 -0.949954 0.1962 + outer loop + vertex -572.399 94.654 311.961 + vertex -572.009 95.1993 315.085 + vertex -585.528 98.254 313.124 + endloop + endfacet + facet normal -0.244537 -0.951746 0.185419 + outer loop + vertex -588.016 98.6139 311.692 + vertex -572.399 94.654 311.961 + vertex -585.528 98.254 313.124 + endloop + endfacet + facet normal -0.242396 -0.953074 0.181367 + outer loop + vertex -585.528 98.254 313.124 + vertex -595.29 100.619 312.505 + vertex -588.016 98.6139 311.692 + endloop + endfacet + facet normal -0.242943 -0.953608 0.177794 + outer loop + vertex -595.29 100.619 312.505 + vertex -596.107 100.596 311.267 + vertex -588.016 98.6139 311.692 + endloop + endfacet + facet normal -0.24276 -0.957229 0.15742 + outer loop + vertex -588.235 98.4542 310.382 + vertex -588.016 98.6139 311.692 + vertex -596.107 100.596 311.267 + endloop + endfacet + facet normal -0.242691 -0.957169 0.157891 + outer loop + vertex -597.674 100.867 310.498 + vertex -588.235 98.4542 310.382 + vertex -596.107 100.596 311.267 + endloop + endfacet + facet normal -0.240555 -0.958489 0.153076 + outer loop + vertex -596.107 100.596 311.267 + vertex -602.117 102.063 311.009 + vertex -597.674 100.867 310.498 + endloop + endfacet + facet normal -0.241884 -0.959555 0.144037 + outer loop + vertex -602.117 102.063 311.009 + vertex -602.326 102.005 310.272 + vertex -597.674 100.867 310.498 + endloop + endfacet + facet normal -0.241713 -0.961532 0.130503 + outer loop + vertex -597.674 100.867 310.498 + vertex -602.326 102.005 310.272 + vertex -597.085 100.624 309.805 + endloop + endfacet + facet normal -0.24313 -0.962759 0.118246 + outer loop + vertex -602.326 102.005 310.272 + vertex -602.57 101.986 309.613 + vertex -597.085 100.624 309.805 + endloop + endfacet + facet normal -0.243077 -0.963918 0.108518 + outer loop + vertex -597.085 100.624 309.805 + vertex -602.57 101.986 309.613 + vertex -598.514 100.914 309.171 + endloop + endfacet + facet normal -0.245395 -0.962658 0.114326 + outer loop + vertex -598.514 100.914 309.171 + vertex -590.776 98.9318 309.095 + vertex -597.085 100.624 309.805 + endloop + endfacet + facet normal -0.243974 -0.961725 0.124747 + outer loop + vertex -590.776 98.9318 309.095 + vertex -588.235 98.4542 310.382 + vertex -597.085 100.624 309.805 + endloop + endfacet + facet normal -0.247017 -0.960065 0.131372 + outer loop + vertex -590.776 98.9318 309.095 + vertex -573.102 94.4198 309.352 + vertex -588.235 98.4542 310.382 + endloop + endfacet + facet normal -0.244943 -0.957551 0.151982 + outer loop + vertex -573.102 94.4198 309.352 + vertex -572.399 94.654 311.961 + vertex -588.235 98.4542 310.382 + endloop + endfacet + facet normal -0.247417 -0.963054 0.106356 + outer loop + vertex -590.776 98.9318 309.095 + vertex -588.539 98.2408 308.039 + vertex -573.102 94.4198 309.352 + endloop + endfacet + facet normal -0.246227 -0.963076 0.108891 + outer loop + vertex -588.539 98.2408 308.039 + vertex -590.776 98.9318 309.095 + vertex -597.18 100.503 308.507 + endloop + endfacet + facet normal -0.247147 -0.964118 0.0969257 + outer loop + vertex -596.964 100.397 308.01 + vertex -588.539 98.2408 308.039 + vertex -597.18 100.503 308.507 + endloop + endfacet + facet normal -0.244365 -0.964693 0.0982556 + outer loop + vertex -597.18 100.503 308.507 + vertex -602.44 101.805 308.216 + vertex -596.964 100.397 308.01 + endloop + endfacet + facet normal -0.244406 -0.964752 0.09757 + outer loop + vertex -596.964 100.397 308.01 + vertex -602.44 101.805 308.216 + vertex -597.274 100.441 307.669 + endloop + endfacet + facet normal -0.242531 -0.963609 0.112412 + outer loop + vertex -597.274 100.441 307.669 + vertex -602.44 101.805 308.216 + vertex -604.941 102.39 307.828 + endloop + endfacet + facet normal -0.244159 -0.966886 0.07428 + outer loop + vertex -597.364 100.429 307.213 + vertex -597.274 100.441 307.669 + vertex -604.941 102.39 307.828 + endloop + endfacet + facet normal -0.244082 -0.966843 0.0750914 + outer loop + vertex -604.09 102.134 307.297 + vertex -597.364 100.429 307.213 + vertex -604.941 102.39 307.828 + endloop + endfacet + facet normal -0.247908 -0.965877 0.0749914 + outer loop + vertex -588.889 98.2624 307.321 + vertex -597.274 100.441 307.669 + vertex -597.364 100.429 307.213 + endloop + endfacet + facet normal -0.247874 -0.965508 0.0797096 + outer loop + vertex -585.64 97.3953 306.924 + vertex -588.889 98.2624 307.321 + vertex -597.364 100.429 307.213 + endloop + endfacet + facet normal -0.251225 -0.967134 -0.0392124 + outer loop + vertex -597.364 100.429 307.213 + vertex -594.781 99.7688 306.95 + vertex -585.64 97.3953 306.924 + endloop + endfacet + facet normal -0.244224 -0.937875 -0.246466 + outer loop + vertex -585.64 97.3953 306.924 + vertex -594.781 99.7688 306.95 + vertex -591.873 99.0229 306.906 + endloop + endfacet + facet normal -0.25042 -0.957473 0.143301 + outer loop + vertex -585.64 97.3953 306.924 + vertex -591.873 99.0229 306.906 + vertex -588.403 98.0947 306.768 + endloop + endfacet + facet normal -0.245347 -0.963092 0.110719 + outer loop + vertex -591.873 99.0229 306.906 + vertex -594.781 99.7688 306.95 + vertex -594.35 99.6505 306.877 + endloop + endfacet + facet normal -0.243019 -0.968929 0.0460236 + outer loop + vertex -594.781 99.7688 306.95 + vertex -597.364 100.429 307.213 + vertex -599.077 100.833 306.667 + endloop + endfacet + facet normal -0.24966 -0.96606 0.0663247 + outer loop + vertex -588.889 98.2624 307.321 + vertex -585.64 97.3953 306.924 + vertex -571.889 93.8833 307.529 + endloop + endfacet + facet normal -0.249439 -0.963961 0.0925211 + outer loop + vertex -588.889 98.2624 307.321 + vertex -571.889 93.8833 307.529 + vertex -588.539 98.2408 308.039 + endloop + endfacet + facet normal -0.246934 -0.964724 0.0912769 + outer loop + vertex -588.539 98.2408 308.039 + vertex -597.274 100.441 307.669 + vertex -588.889 98.2624 307.321 + endloop + endfacet + facet normal -0.241821 -0.964452 0.106561 + outer loop + vertex -606.349 102.787 308.225 + vertex -604.941 102.39 307.828 + vertex -602.44 101.805 308.216 + endloop + endfacet + facet normal -0.242122 -0.965549 0.0953464 + outer loop + vertex -602.44 101.805 308.216 + vertex -606.489 102.864 308.653 + vertex -606.349 102.787 308.225 + endloop + endfacet + facet normal -0.237193 -0.966593 0.0971475 + outer loop + vertex -606.489 102.864 308.653 + vertex -608.103 103.227 308.32 + vertex -606.349 102.787 308.225 + endloop + endfacet + facet normal -0.237193 -0.966593 0.0971482 + outer loop + vertex -608.429 103.37 308.95 + vertex -608.103 103.227 308.32 + vertex -606.489 102.864 308.653 + endloop + endfacet + facet normal -0.237022 -0.966532 0.0981628 + outer loop + vertex -606.489 102.864 308.653 + vertex -606.225 102.871 309.359 + vertex -608.429 103.37 308.95 + endloop + endfacet + facet normal -0.239373 -0.96426 0.113594 + outer loop + vertex -607.671 103.301 309.96 + vertex -608.429 103.37 308.95 + vertex -606.225 102.871 309.359 + endloop + endfacet + facet normal -0.240633 -0.964295 0.11059 + outer loop + vertex -605.474 102.756 309.994 + vertex -607.671 103.301 309.96 + vertex -606.225 102.871 309.359 + endloop + endfacet + facet normal -0.24114 -0.964096 0.111226 + outer loop + vertex -605.474 102.756 309.994 + vertex -606.225 102.871 309.359 + vertex -602.57 101.986 309.613 + endloop + endfacet + facet normal -0.24082 -0.965063 0.103244 + outer loop + vertex -602.57 101.986 309.613 + vertex -606.225 102.871 309.359 + vertex -602.834 101.978 308.924 + endloop + endfacet + facet normal -0.240307 -0.961658 0.132163 + outer loop + vertex -605.474 102.756 309.994 + vertex -605.617 102.885 310.673 + vertex -607.671 103.301 309.96 + endloop + endfacet + facet normal -0.245394 -0.957903 0.149009 + outer loop + vertex -607.174 103.396 311.392 + vertex -607.671 103.301 309.96 + vertex -605.617 102.885 310.673 + endloop + endfacet + facet normal -0.241542 -0.957585 0.157127 + outer loop + vertex -605.149 102.902 311.491 + vertex -607.174 103.396 311.392 + vertex -605.617 102.885 310.673 + endloop + endfacet + facet normal -0.240046 -0.958099 0.15628 + outer loop + vertex -605.149 102.902 311.491 + vertex -605.617 102.885 310.673 + vertex -602.117 102.063 311.009 + endloop + endfacet + facet normal -0.237292 -0.956346 0.17057 + outer loop + vertex -601.774 102.16 312.027 + vertex -605.149 102.902 311.491 + vertex -602.117 102.063 311.009 + endloop + endfacet + facet normal -0.238365 -0.954325 0.180125 + outer loop + vertex -605.454 103.169 312.506 + vertex -605.149 102.902 311.491 + vertex -601.774 102.16 312.027 + endloop + endfacet + facet normal -0.235947 -0.952171 0.194163 + outer loop + vertex -601.801 102.493 313.63 + vertex -605.454 103.169 312.506 + vertex -601.774 102.16 312.027 + endloop + endfacet + facet normal -0.24033 -0.951134 0.193872 + outer loop + vertex -601.801 102.493 313.63 + vertex -601.774 102.16 312.027 + vertex -595.29 100.619 312.505 + endloop + endfacet + facet normal -0.239968 -0.950882 0.195549 + outer loop + vertex -595.29 100.619 312.505 + vertex -594.24 100.62 313.801 + vertex -601.801 102.493 313.63 + endloop + endfacet + facet normal -0.239217 -0.945565 0.220642 + outer loop + vertex -594.24 100.62 313.801 + vertex -596.832 101.655 315.427 + vertex -601.801 102.493 313.63 + endloop + endfacet + facet normal -0.238473 -0.94631 0.218237 + outer loop + vertex -596.832 101.655 315.427 + vertex -603.193 103.202 315.18 + vertex -601.801 102.493 313.63 + endloop + endfacet + facet normal -0.23401 -0.946475 0.222317 + outer loop + vertex -603.193 103.202 315.18 + vertex -605.358 103.511 314.217 + vertex -601.801 102.493 313.63 + endloop + endfacet + facet normal -0.235308 -0.947544 0.216309 + outer loop + vertex -605.358 103.511 314.217 + vertex -605.632 103.392 313.4 + vertex -601.801 102.493 313.63 + endloop + endfacet + facet normal -0.248729 -0.943215 0.22018 + outer loop + vertex -605.632 103.392 313.4 + vertex -605.358 103.511 314.217 + vertex -606.754 103.648 313.227 + endloop + endfacet + facet normal -0.245544 -0.950949 0.188159 + outer loop + vertex -605.632 103.392 313.4 + vertex -606.754 103.648 313.227 + vertex -605.454 103.169 312.506 + endloop + endfacet + facet normal -0.24635 -0.951018 0.186752 + outer loop + vertex -606.754 103.648 313.227 + vertex -607.174 103.396 311.392 + vertex -605.454 103.169 312.506 + endloop + endfacet + facet normal -0.237051 -0.953721 0.184995 + outer loop + vertex -606.754 103.648 313.227 + vertex -607.656 103.615 311.906 + vertex -607.174 103.396 311.392 + endloop + endfacet + facet normal -0.252339 -0.952559 0.170163 + outer loop + vertex -607.656 103.615 311.906 + vertex -608.258 103.511 310.429 + vertex -607.174 103.396 311.392 + endloop + endfacet + facet normal -0.265883 -0.947922 0.175359 + outer loop + vertex -608.258 103.511 310.429 + vertex -607.656 103.615 311.906 + vertex -608.603 103.595 310.36 + endloop + endfacet + facet normal -0.260047 -0.955845 0.136876 + outer loop + vertex -608.92 103.519 309.228 + vertex -608.258 103.511 310.429 + vertex -608.603 103.595 310.36 + endloop + endfacet + facet normal -0.606791 -0.763538 0.220942 + outer loop + vertex -608.603 103.595 310.36 + vertex -609.406 103.505 307.843 + vertex -608.92 103.519 309.228 + endloop + endfacet + facet normal -0.669014 0.707468 0.227836 + outer loop + vertex -609.207 103.504 308.43 + vertex -608.92 103.519 309.228 + vertex -609.406 103.505 307.843 + endloop + endfacet + facet normal -0.245117 -0.966079 0.0812937 + outer loop + vertex -608.543 103.305 308.066 + vertex -609.207 103.504 308.43 + vertex -609.406 103.505 307.843 + endloop + endfacet + facet normal -0.241631 -0.968123 0.065964 + outer loop + vertex -604.941 102.39 307.828 + vertex -608.543 103.305 308.066 + vertex -609.406 103.505 307.843 + endloop + endfacet + facet normal -0.237591 -0.964666 0.113886 + outer loop + vertex -608.543 103.305 308.066 + vertex -604.941 102.39 307.828 + vertex -608.103 103.227 308.32 + endloop + endfacet + facet normal -0.232623 -0.966927 0.104586 + outer loop + vertex -609.207 103.504 308.43 + vertex -608.543 103.305 308.066 + vertex -608.103 103.227 308.32 + endloop + endfacet + facet normal -0.235717 -0.966313 0.103331 + outer loop + vertex -608.92 103.519 309.228 + vertex -609.207 103.504 308.43 + vertex -608.429 103.37 308.95 + endloop + endfacet + facet normal -0.243092 -0.961588 0.127496 + outer loop + vertex -608.258 103.511 310.429 + vertex -608.92 103.519 309.228 + vertex -607.671 103.301 309.96 + endloop + endfacet + facet normal -0.307484 -0.930163 0.200626 + outer loop + vertex -607.529 103.813 313.015 + vertex -608.603 103.595 310.36 + vertex -607.656 103.615 311.906 + endloop + endfacet + facet normal -0.232629 -0.952589 0.196105 + outer loop + vertex -607.656 103.615 311.906 + vertex -606.923 103.846 313.893 + vertex -607.529 103.813 313.015 + endloop + endfacet + facet normal -0.273702 -0.93869 0.209638 + outer loop + vertex -606.923 103.846 313.893 + vertex -607.656 103.615 311.906 + vertex -606.754 103.648 313.227 + endloop + endfacet + facet normal -0.230547 -0.947148 0.223069 + outer loop + vertex -606.923 103.846 313.893 + vertex -606.754 103.648 313.227 + vertex -605.554 103.889 315.493 + endloop + endfacet + facet normal -0.256674 -0.934903 0.245101 + outer loop + vertex -606.923 103.846 313.893 + vertex -605.554 103.889 315.493 + vertex -606.561 104.377 316.299 + endloop + endfacet + facet normal -0.311663 -0.916884 0.249379 + outer loop + vertex -606.561 104.377 316.299 + vertex -607.529 103.813 313.015 + vertex -606.923 103.846 313.893 + endloop + endfacet + facet normal -0.241688 -0.939761 0.241738 + outer loop + vertex -603.193 103.202 315.18 + vertex -605.554 103.889 315.493 + vertex -605.358 103.511 314.217 + endloop + endfacet + facet normal -0.239739 -0.937624 0.251765 + outer loop + vertex -603.193 103.202 315.18 + vertex -602.057 103.362 316.858 + vertex -605.554 103.889 315.493 + endloop + endfacet + facet normal -0.237812 -0.938443 0.250539 + outer loop + vertex -602.057 103.362 316.858 + vertex -603.193 103.202 315.18 + vertex -596.832 101.655 315.427 + endloop + endfacet + facet normal -0.239307 -0.939252 0.246045 + outer loop + vertex -596.832 101.655 315.427 + vertex -595.97 101.969 317.461 + vertex -602.057 103.362 316.858 + endloop + endfacet + facet normal -0.2416 -0.938442 0.246891 + outer loop + vertex -595.97 101.969 317.461 + vertex -596.832 101.655 315.427 + vertex -586.19 99.1835 316.445 + endloop + endfacet + facet normal -0.239933 -0.936208 0.256802 + outer loop + vertex -587.898 100.115 318.245 + vertex -595.97 101.969 317.461 + vertex -586.19 99.1835 316.445 + endloop + endfacet + facet normal -0.241469 -0.936211 0.255346 + outer loop + vertex -587.898 100.115 318.245 + vertex -586.19 99.1835 316.445 + vertex -571.618 95.9921 318.523 + endloop + endfacet + facet normal -0.239199 -0.924439 0.29698 + outer loop + vertex -587.898 100.115 318.245 + vertex -571.618 95.9921 318.523 + vertex -584.973 99.9634 320.129 + endloop + endfacet + facet normal -0.237868 -0.92547 0.29483 + outer loop + vertex -584.973 99.9634 320.129 + vertex -595.625 102.431 319.28 + vertex -587.898 100.115 318.245 + endloop + endfacet + facet normal -0.237922 -0.916414 0.321836 + outer loop + vertex -595.005 102.946 321.207 + vertex -595.625 102.431 319.28 + vertex -584.973 99.9634 320.129 + endloop + endfacet + facet normal -0.235006 -0.911897 0.336476 + outer loop + vertex -584.305 100.74 322.699 + vertex -595.005 102.946 321.207 + vertex -584.973 99.9634 320.129 + endloop + endfacet + facet normal -0.239888 -0.910331 0.33727 + outer loop + vertex -584.305 100.74 322.699 + vertex -584.973 99.9634 320.129 + vertex -568.494 96.288 321.93 + endloop + endfacet + facet normal -0.236871 -0.903187 0.357973 + outer loop + vertex -568.351 97.5555 325.222 + vertex -584.305 100.74 322.699 + vertex -568.494 96.288 321.93 + endloop + endfacet + facet normal -0.238768 -0.891762 0.384383 + outer loop + vertex -586.244 102.59 325.788 + vertex -584.305 100.74 322.699 + vertex -568.351 97.5555 325.222 + endloop + endfacet + facet normal -0.234756 -0.880571 0.411685 + outer loop + vertex -568.206 99.1569 328.73 + vertex -586.244 102.59 325.788 + vertex -568.351 97.5555 325.222 + endloop + endfacet + facet normal -0.238908 -0.879584 0.411407 + outer loop + vertex -568.206 99.1569 328.73 + vertex -568.351 97.5555 325.222 + vertex -549.139 93.8822 328.525 + endloop + endfacet + facet normal -0.237528 -0.88776 0.394288 + outer loop + vertex -549.139 93.8822 328.525 + vertex -568.351 97.5555 325.222 + vertex -548.973 92.2687 324.992 + endloop + endfacet + facet normal -0.241502 -0.886937 0.393725 + outer loop + vertex -549.139 93.8822 328.525 + vertex -548.973 92.2687 324.992 + vertex -530.506 88.8905 328.71 + endloop + endfacet + facet normal -0.240545 -0.890832 0.385431 + outer loop + vertex -530.506 88.8905 328.71 + vertex -548.973 92.2687 324.992 + vertex -529.626 87.0852 325.086 + endloop + endfacet + facet normal -0.245151 -0.890196 0.383995 + outer loop + vertex -530.506 88.8905 328.71 + vertex -529.626 87.0852 325.086 + vertex -515.3 84.7827 328.894 + endloop + endfacet + facet normal -0.244978 -0.890639 0.383077 + outer loop + vertex -515.3 84.7827 328.894 + vertex -529.626 87.0852 325.086 + vertex -513.122 82.5755 325.156 + endloop + endfacet + facet normal -0.25068 -0.890509 0.379676 + outer loop + vertex -515.3 84.7827 328.894 + vertex -513.122 82.5755 325.156 + vertex -505.362 81.9309 328.767 + endloop + endfacet + facet normal -0.249445 -0.892101 0.37674 + outer loop + vertex -505.362 81.9309 328.767 + vertex -513.122 82.5755 325.156 + vertex -503.122 79.9066 325.457 + endloop + endfacet + facet normal -0.256356 -0.892103 0.372067 + outer loop + vertex -505.362 81.9309 328.767 + vertex -503.122 79.9066 325.457 + vertex -500.24 80.1705 328.076 + endloop + endfacet + facet normal -0.236578 -0.866849 0.438866 + outer loop + vertex -583.537 103.827 329.689 + vertex -586.244 102.59 325.788 + vertex -568.206 99.1569 328.73 + endloop + endfacet + facet normal -0.231132 -0.85441 0.465361 + outer loop + vertex -567.345 100.832 332.232 + vertex -583.537 103.827 329.689 + vertex -568.206 99.1569 328.73 + endloop + endfacet + facet normal -0.234313 -0.853385 0.465652 + outer loop + vertex -567.345 100.832 332.232 + vertex -568.206 99.1569 328.73 + vertex -549.077 95.7072 332.033 + endloop + endfacet + facet normal -0.233322 -0.860967 0.451991 + outer loop + vertex -549.077 95.7072 332.033 + vertex -568.206 99.1569 328.73 + vertex -549.139 93.8822 328.525 + endloop + endfacet + facet normal -0.236547 -0.860252 0.451676 + outer loop + vertex -549.077 95.7072 332.033 + vertex -549.139 93.8822 328.525 + vertex -530.775 90.7806 332.235 + endloop + endfacet + facet normal -0.235831 -0.863864 0.44511 + outer loop + vertex -530.775 90.7806 332.235 + vertex -549.139 93.8822 328.525 + vertex -530.506 88.8905 328.71 + endloop + endfacet + facet normal -0.239916 -0.863108 0.444392 + outer loop + vertex -530.775 90.7806 332.235 + vertex -530.506 88.8905 328.71 + vertex -515.934 86.7734 332.465 + endloop + endfacet + facet normal -0.239162 -0.865507 0.440114 + outer loop + vertex -515.934 86.7734 332.465 + vertex -530.506 88.8905 328.71 + vertex -515.3 84.7827 328.894 + endloop + endfacet + facet normal -0.245373 -0.864587 0.438499 + outer loop + vertex -515.934 86.7734 332.465 + vertex -515.3 84.7827 328.894 + vertex -506.325 83.9753 332.325 + endloop + endfacet + facet normal -0.243525 -0.867937 0.432875 + outer loop + vertex -506.325 83.9753 332.325 + vertex -515.3 84.7827 328.894 + vertex -505.362 81.9309 328.767 + endloop + endfacet + facet normal -0.254002 -0.866696 0.429326 + outer loop + vertex -506.325 83.9753 332.325 + vertex -505.362 81.9309 328.767 + vertex -501.404 82.1993 331.651 + endloop + endfacet + facet normal -0.232249 -0.841719 0.487412 + outer loop + vertex -580.961 104.942 332.843 + vertex -583.537 103.827 329.689 + vertex -567.345 100.832 332.232 + endloop + endfacet + facet normal -0.224988 -0.822794 0.521911 + outer loop + vertex -567.439 102.945 335.524 + vertex -580.961 104.942 332.843 + vertex -567.345 100.832 332.232 + endloop + endfacet + facet normal -0.227785 -0.822282 0.521503 + outer loop + vertex -567.439 102.945 335.524 + vertex -567.345 100.832 332.232 + vertex -548.929 97.7693 335.448 + endloop + endfacet + facet normal -0.227053 -0.829254 0.51067 + outer loop + vertex -548.929 97.7693 335.448 + vertex -567.345 100.832 332.232 + vertex -549.077 95.7072 332.033 + endloop + endfacet + facet normal -0.229776 -0.828655 0.510426 + outer loop + vertex -548.929 97.7693 335.448 + vertex -549.077 95.7072 332.033 + vertex -530.786 92.8646 335.653 + endloop + endfacet + facet normal -0.229364 -0.83133 0.506244 + outer loop + vertex -530.786 92.8646 335.653 + vertex -549.077 95.7072 332.033 + vertex -530.775 90.7806 332.235 + endloop + endfacet + facet normal -0.233052 -0.830587 0.505779 + outer loop + vertex -530.786 92.8646 335.653 + vertex -530.775 90.7806 332.235 + vertex -516.109 88.8805 335.873 + endloop + endfacet + facet normal -0.232563 -0.832535 0.502792 + outer loop + vertex -516.109 88.8805 335.873 + vertex -530.775 90.7806 332.235 + vertex -515.934 86.7734 332.465 + endloop + endfacet + facet normal -0.238571 -0.831432 0.501801 + outer loop + vertex -516.109 88.8805 335.873 + vertex -515.934 86.7734 332.465 + vertex -506.647 86.0943 335.755 + endloop + endfacet + facet normal -0.236354 -0.836416 0.494516 + outer loop + vertex -506.647 86.0943 335.755 + vertex -515.934 86.7734 332.465 + vertex -506.325 83.9753 332.325 + endloop + endfacet + facet normal -0.247201 -0.834557 0.492348 + outer loop + vertex -506.647 86.0943 335.755 + vertex -506.325 83.9753 332.325 + vertex -501.911 84.3245 335.133 + endloop + endfacet + facet normal -0.226611 -0.811645 0.538405 + outer loop + vertex -584.9 107.922 335.677 + vertex -580.961 104.942 332.843 + vertex -567.439 102.945 335.524 + endloop + endfacet + facet normal -0.219743 -0.788656 0.574226 + outer loop + vertex -567.665 105.413 338.827 + vertex -584.9 107.922 335.677 + vertex -567.439 102.945 335.524 + endloop + endfacet + facet normal -0.220559 -0.788534 0.57408 + outer loop + vertex -567.665 105.413 338.827 + vertex -567.439 102.945 335.524 + vertex -548.895 100.102 338.744 + endloop + endfacet + facet normal -0.220014 -0.79513 0.565121 + outer loop + vertex -548.895 100.102 338.744 + vertex -567.439 102.945 335.524 + vertex -548.929 97.7693 335.448 + endloop + endfacet + facet normal -0.22169 -0.794812 0.564913 + outer loop + vertex -548.895 100.102 338.744 + vertex -548.929 97.7693 335.448 + vertex -530.759 95.1893 338.948 + endloop + endfacet + facet normal -0.221547 -0.796005 0.563288 + outer loop + vertex -530.759 95.1893 338.948 + vertex -548.929 97.7693 335.448 + vertex -530.786 92.8646 335.653 + endloop + endfacet + facet normal -0.224351 -0.79547 0.562933 + outer loop + vertex -530.759 95.1893 338.948 + vertex -530.786 92.8646 335.653 + vertex -516.124 91.2169 339.167 + endloop + endfacet + facet normal -0.224362 -0.795419 0.563002 + outer loop + vertex -516.124 91.2169 339.167 + vertex -530.786 92.8646 335.653 + vertex -516.109 88.8805 335.873 + endloop + endfacet + facet normal -0.230939 -0.794178 0.562092 + outer loop + vertex -516.124 91.2169 339.167 + vertex -516.109 88.8805 335.873 + vertex -506.827 88.3612 338.953 + endloop + endfacet + facet normal -0.228723 -0.800207 0.554395 + outer loop + vertex -506.827 88.3612 338.953 + vertex -516.109 88.8805 335.873 + vertex -506.647 86.0943 335.755 + endloop + endfacet + facet normal -0.239638 -0.798347 0.552462 + outer loop + vertex -506.827 88.3612 338.953 + vertex -506.647 86.0943 335.755 + vertex -502.217 86.6077 338.418 + endloop + endfacet + facet normal -0.220571 -0.779935 0.585704 + outer loop + vertex -583.232 110.296 339.467 + vertex -584.9 107.922 335.677 + vertex -567.665 105.413 338.827 + endloop + endfacet + facet normal -0.213516 -0.782852 0.584426 + outer loop + vertex -584.9 107.922 335.677 + vertex -583.232 110.296 339.467 + vertex -594.406 111.775 337.366 + endloop + endfacet + facet normal -0.219566 -0.791573 0.570266 + outer loop + vertex -594.406 111.775 337.366 + vertex -596.07 110.183 334.515 + vertex -584.9 107.922 335.677 + endloop + endfacet + facet normal -0.214196 -0.794227 0.568616 + outer loop + vertex -594.406 111.775 337.366 + vertex -599.903 112.042 335.668 + vertex -596.07 110.183 334.515 + endloop + endfacet + facet normal -0.221125 -0.773199 0.594363 + outer loop + vertex -599.182 114.177 338.714 + vertex -599.903 112.042 335.668 + vertex -594.406 111.775 337.366 + endloop + endfacet + facet normal -0.22764 -0.812033 0.537384 + outer loop + vertex -580.961 104.942 332.843 + vertex -584.9 107.922 335.677 + vertex -593.305 107.62 331.66 + endloop + endfacet + facet normal -0.221011 -0.822359 0.52429 + outer loop + vertex -596.07 110.183 334.515 + vertex -593.305 107.62 331.66 + vertex -584.9 107.922 335.677 + endloop + endfacet + facet normal -0.216228 -0.821283 0.527957 + outer loop + vertex -596.07 110.183 334.515 + vertex -600.184 109.981 332.515 + vertex -593.305 107.62 331.66 + endloop + endfacet + facet normal -0.226307 -0.805868 0.547139 + outer loop + vertex -599.903 112.042 335.668 + vertex -600.184 109.981 332.515 + vertex -596.07 110.183 334.515 + endloop + endfacet + facet normal -0.229502 -0.84342 0.48577 + outer loop + vertex -583.537 103.827 329.689 + vertex -580.961 104.942 332.843 + vertex -593.305 107.62 331.66 + endloop + endfacet + facet normal -0.232509 -0.847078 0.477911 + outer loop + vertex -593.305 107.62 331.66 + vertex -595.653 106.026 327.693 + vertex -583.537 103.827 329.689 + endloop + endfacet + facet normal -0.21778 -0.854238 0.472069 + outer loop + vertex -593.305 107.62 331.66 + vertex -600.629 108.141 329.225 + vertex -595.653 106.026 327.693 + endloop + endfacet + facet normal -0.225333 -0.837127 0.498442 + outer loop + vertex -600.184 109.981 332.515 + vertex -600.629 108.141 329.225 + vertex -593.305 107.62 331.66 + endloop + endfacet + facet normal -0.229738 -0.870492 0.435275 + outer loop + vertex -586.244 102.59 325.788 + vertex -583.537 103.827 329.689 + vertex -595.653 106.026 327.693 + endloop + endfacet + facet normal -0.232738 -0.873942 0.426684 + outer loop + vertex -595.653 106.026 327.693 + vertex -598.518 105.205 324.448 + vertex -586.244 102.59 325.788 + endloop + endfacet + facet normal -0.224122 -0.879217 0.420413 + outer loop + vertex -595.653 106.026 327.693 + vertex -602.049 106.793 325.887 + vertex -598.518 105.205 324.448 + endloop + endfacet + facet normal -0.229864 -0.864505 0.446984 + outer loop + vertex -600.629 108.141 329.225 + vertex -602.049 106.793 325.887 + vertex -595.653 106.026 327.693 + endloop + endfacet + facet normal -0.231811 -0.891717 0.388722 + outer loop + vertex -584.305 100.74 322.699 + vertex -586.244 102.59 325.788 + vertex -594.478 103.584 323.157 + endloop + endfacet + facet normal -0.232383 -0.890599 0.390936 + outer loop + vertex -586.244 102.59 325.788 + vertex -598.518 105.205 324.448 + vertex -594.478 103.584 323.157 + endloop + endfacet + facet normal -0.23511 -0.892539 0.384833 + outer loop + vertex -598.518 105.205 324.448 + vertex -599.978 104.646 322.26 + vertex -594.478 103.584 323.157 + endloop + endfacet + facet normal -0.237965 -0.891115 0.386375 + outer loop + vertex -598.518 105.205 324.448 + vertex -603.341 105.575 322.331 + vertex -599.978 104.646 322.26 + endloop + endfacet + facet normal -0.242927 -0.906037 0.34653 + outer loop + vertex -599.978 104.646 322.26 + vertex -603.341 105.575 322.331 + vertex -601.146 104.242 320.385 + endloop + endfacet + facet normal -0.237647 -0.908486 0.343768 + outer loop + vertex -599.978 104.646 322.26 + vertex -601.146 104.242 320.385 + vertex -595.005 102.946 321.207 + endloop + endfacet + facet normal -0.233017 -0.904014 0.358417 + outer loop + vertex -595.005 102.946 321.207 + vertex -594.478 103.584 323.157 + vertex -599.978 104.646 322.26 + endloop + endfacet + facet normal -0.240004 -0.888324 0.391508 + outer loop + vertex -602.049 106.793 325.887 + vertex -603.341 105.575 322.331 + vertex -598.518 105.205 324.448 + endloop + endfacet + facet normal -0.236294 -0.902949 0.358954 + outer loop + vertex -594.478 103.584 323.157 + vertex -595.005 102.946 321.207 + vertex -584.305 100.74 322.699 + endloop + endfacet + facet normal -0.236446 -0.916916 0.321496 + outer loop + vertex -595.625 102.431 319.28 + vertex -595.005 102.946 321.207 + vertex -601.146 104.242 320.385 + endloop + endfacet + facet normal -0.23945 -0.919722 0.311086 + outer loop + vertex -601.146 104.242 320.385 + vertex -600.926 103.57 318.569 + vertex -595.625 102.431 319.28 + endloop + endfacet + facet normal -0.244339 -0.918757 0.310136 + outer loop + vertex -600.926 103.57 318.569 + vertex -601.146 104.242 320.385 + vertex -604.337 104.504 318.647 + endloop + endfacet + facet normal -0.247729 -0.928375 0.277039 + outer loop + vertex -600.926 103.57 318.569 + vertex -604.337 104.504 318.647 + vertex -602.057 103.362 316.858 + endloop + endfacet + facet normal -0.240196 -0.931703 0.272461 + outer loop + vertex -600.926 103.57 318.569 + vertex -602.057 103.362 316.858 + vertex -595.97 101.969 317.461 + endloop + endfacet + facet normal -0.237602 -0.929756 0.281247 + outer loop + vertex -595.97 101.969 317.461 + vertex -595.625 102.431 319.28 + vertex -600.926 103.57 318.569 + endloop + endfacet + facet normal -0.240558 -0.939483 0.243932 + outer loop + vertex -572.009 95.1993 315.085 + vertex -571.618 95.9921 318.523 + vertex -586.19 99.1835 316.445 + endloop + endfacet + facet normal -0.242827 -0.942574 0.229324 + outer loop + vertex -587.698 99.137 314.657 + vertex -572.009 95.1993 315.085 + vertex -586.19 99.1835 316.445 + endloop + endfacet + facet normal -0.240657 -0.928863 0.2816 + outer loop + vertex -595.625 102.431 319.28 + vertex -595.97 101.969 317.461 + vertex -587.898 100.115 318.245 + endloop + endfacet + facet normal -0.24093 -0.943443 0.227746 + outer loop + vertex -586.19 99.1835 316.445 + vertex -596.832 101.655 315.427 + vertex -587.698 99.137 314.657 + endloop + endfacet + facet normal -0.24265 -0.945902 0.215386 + outer loop + vertex -596.832 101.655 315.427 + vertex -594.24 100.62 313.801 + vertex -587.698 99.137 314.657 + endloop + endfacet + facet normal -0.241801 -0.948584 0.204256 + outer loop + vertex -587.698 99.137 314.657 + vertex -594.24 100.62 313.801 + vertex -585.528 98.254 313.124 + endloop + endfacet + facet normal -0.235071 -0.953072 0.190775 + outer loop + vertex -605.632 103.392 313.4 + vertex -605.454 103.169 312.506 + vertex -601.801 102.493 313.63 + endloop + endfacet + facet normal -0.241665 -0.953712 0.178972 + outer loop + vertex -605.149 102.902 311.491 + vertex -605.454 103.169 312.506 + vertex -607.174 103.396 311.392 + endloop + endfacet + facet normal -0.230179 -0.962432 0.144023 + outer loop + vertex -607.174 103.396 311.392 + vertex -608.258 103.511 310.429 + vertex -607.671 103.301 309.96 + endloop + endfacet + facet normal -0.241032 -0.961501 0.131981 + outer loop + vertex -605.617 102.885 310.673 + vertex -605.474 102.756 309.994 + vertex -602.326 102.005 310.272 + endloop + endfacet + facet normal -0.232812 -0.966448 0.108525 + outer loop + vertex -607.671 103.301 309.96 + vertex -608.92 103.519 309.228 + vertex -608.429 103.37 308.95 + endloop + endfacet + facet normal -0.24133 -0.965302 0.0997629 + outer loop + vertex -606.225 102.871 309.359 + vertex -606.489 102.864 308.653 + vertex -602.834 101.978 308.924 + endloop + endfacet + facet normal -0.233243 -0.967329 0.0993636 + outer loop + vertex -608.429 103.37 308.95 + vertex -609.207 103.504 308.43 + vertex -608.103 103.227 308.32 + endloop + endfacet + facet normal -0.241393 -0.965144 0.10113 + outer loop + vertex -602.834 101.978 308.924 + vertex -606.489 102.864 308.653 + vertex -602.44 101.805 308.216 + endloop + endfacet + facet normal -0.234492 -0.963206 0.131333 + outer loop + vertex -606.349 102.787 308.225 + vertex -608.103 103.227 308.32 + vertex -604.941 102.39 307.828 + endloop + endfacet + facet normal -0.244395 -0.964576 0.0993204 + outer loop + vertex -602.834 101.978 308.924 + vertex -602.44 101.805 308.216 + vertex -597.18 100.503 308.507 + endloop + endfacet + facet normal -0.24369 -0.963964 0.106714 + outer loop + vertex -598.514 100.914 309.171 + vertex -602.834 101.978 308.924 + vertex -597.18 100.503 308.507 + endloop + endfacet + facet normal -0.247079 -0.963809 0.100121 + outer loop + vertex -596.964 100.397 308.01 + vertex -597.274 100.441 307.669 + vertex -588.539 98.2408 308.039 + endloop + endfacet + facet normal -0.245828 -0.963892 0.102376 + outer loop + vertex -598.514 100.914 309.171 + vertex -597.18 100.503 308.507 + vertex -590.776 98.9318 309.095 + endloop + endfacet + facet normal -0.243622 -0.964245 0.10431 + outer loop + vertex -602.57 101.986 309.613 + vertex -602.834 101.978 308.924 + vertex -598.514 100.914 309.171 + endloop + endfacet + facet normal -0.240229 -0.963615 0.117199 + outer loop + vertex -602.326 102.005 310.272 + vertex -605.474 102.756 309.994 + vertex -602.57 101.986 309.613 + endloop + endfacet + facet normal -0.239322 -0.960297 0.14337 + outer loop + vertex -602.117 102.063 311.009 + vertex -605.617 102.885 310.673 + vertex -602.326 102.005 310.272 + endloop + endfacet + facet normal -0.24058 -0.955343 0.171583 + outer loop + vertex -601.774 102.16 312.027 + vertex -602.117 102.063 311.009 + vertex -596.107 100.596 311.267 + endloop + endfacet + facet normal -0.244086 -0.961219 0.128374 + outer loop + vertex -597.674 100.867 310.498 + vertex -597.085 100.624 309.805 + vertex -588.235 98.4542 310.382 + endloop + endfacet + facet normal -0.239857 -0.954762 0.175778 + outer loop + vertex -595.29 100.619 312.505 + vertex -601.774 102.16 312.027 + vertex -596.107 100.596 311.267 + endloop + endfacet + facet normal -0.242629 -0.94976 0.197705 + outer loop + vertex -594.24 100.62 313.801 + vertex -595.29 100.619 312.505 + vertex -585.528 98.254 313.124 + endloop + endfacet + facet normal -0.245274 -0.956532 0.157755 + outer loop + vertex -588.016 98.6139 311.692 + vertex -588.235 98.4542 310.382 + vertex -572.399 94.654 311.961 + endloop + endfacet + facet normal -0.243603 -0.94866 0.201749 + outer loop + vertex -587.698 99.137 314.657 + vertex -585.528 98.254 313.124 + vertex -572.009 95.1993 315.085 + endloop + endfacet + facet normal -0.246442 -0.937879 0.244231 + outer loop + vertex -571.618 95.9921 318.523 + vertex -572.009 95.1993 315.085 + vertex -548.979 89.8825 317.906 + endloop + endfacet + facet normal -0.238743 -0.923824 0.299251 + outer loop + vertex -571.618 95.9921 318.523 + vertex -568.494 96.288 321.93 + vertex -584.973 99.9634 320.129 + endloop + endfacet + facet normal -0.241839 -0.901971 0.357719 + outer loop + vertex -568.351 97.5555 325.222 + vertex -568.494 96.288 321.93 + vertex -548.973 92.2687 324.992 + endloop + endfacet + facet normal -0.252262 -0.907157 0.336793 + outer loop + vertex -503.122 79.9066 325.457 + vertex -513.122 82.5755 325.156 + vertex -507.007 80.0871 323.033 + endloop + endfacet + facet normal -0.24614 -0.912558 0.326578 + outer loop + vertex -500.852 78.2411 322.514 + vertex -503.122 79.9066 325.457 + vertex -507.007 80.0871 323.033 + endloop + endfacet + facet normal -0.249619 -0.912567 0.3239 + outer loop + vertex -503.122 79.9066 325.457 + vertex -500.852 78.2411 322.514 + vertex -498.627 78.2894 324.365 + endloop + endfacet + facet normal -0.252616 -0.922335 0.292375 + outer loop + vertex -513.946 81.8722 322.669 + vertex -526.974 85.0628 321.477 + vertex -513.993 81.3012 320.827 + endloop + endfacet + facet normal -0.250012 -0.937775 0.240983 + outer loop + vertex -500.328 77.4563 320.445 + vertex -504.393 78.185 319.064 + vertex -499.826 76.9447 318.976 + endloop + endfacet + facet normal -0.255375 -0.929961 0.264491 + outer loop + vertex -513.993 81.3012 320.827 + vertex -511.41 80.1086 319.127 + vertex -505.064 78.8769 320.924 + endloop + endfacet + facet normal -0.253673 -0.942578 0.217247 + outer loop + vertex -504.393 78.185 319.064 + vertex -512.871 80.0207 317.129 + vertex -503.873 77.6463 317.334 + endloop + endfacet + facet normal -0.255106 -0.929926 0.264874 + outer loop + vertex -511.41 80.1086 319.127 + vertex -513.993 81.3012 320.827 + vertex -526.319 83.8028 317.738 + endloop + endfacet + facet normal -0.249425 -0.944789 0.212512 + outer loop + vertex -526.319 83.8028 317.738 + vertex -549.003 89.0537 314.459 + vertex -525.982 82.9269 314.24 + endloop + endfacet + facet normal -0.254183 -0.945833 0.20197 + outer loop + vertex -512.871 80.0207 317.129 + vertex -510.745 79.112 315.549 + vertex -503.873 77.6463 317.334 + endloop + endfacet + facet normal -0.251399 -0.949383 0.188336 + outer loop + vertex -503.873 77.6463 317.334 + vertex -510.745 79.112 315.549 + vertex -503.373 77.1596 315.548 + endloop + endfacet + facet normal -0.251312 -0.950767 0.18134 + outer loop + vertex -549.003 89.0537 314.459 + vertex -549.098 88.4902 311.372 + vertex -525.982 82.9269 314.24 + endloop + endfacet + facet normal -0.250027 -0.960315 0.123616 + outer loop + vertex -525.702 82.313 311.088 + vertex -548.982 88.0889 308.873 + vertex -525.735 81.9896 308.509 + endloop + endfacet + facet normal -0.251789 -0.959859 0.123582 + outer loop + vertex -525.702 82.313 311.088 + vertex -525.735 81.9896 308.509 + vertex -511.491 78.4971 310.404 + endloop + endfacet + facet normal -0.249105 -0.956316 0.152992 + outer loop + vertex -572.399 94.654 311.961 + vertex -573.102 94.4198 309.352 + vertex -549.098 88.4902 311.372 + endloop + endfacet + facet normal -0.248028 -0.961548 0.117931 + outer loop + vertex -571.889 93.8833 307.529 + vertex -573.102 94.4198 309.352 + vertex -588.539 98.2408 308.039 + endloop + endfacet + facet normal -0.250476 -0.96209 0.10791 + outer loop + vertex -571.889 93.8833 307.529 + vertex -585.64 97.3953 306.924 + vertex -566.101 92.2756 306.63 + endloop + endfacet + facet normal -0.249699 -0.960139 0.12563 + outer loop + vertex -566.101 92.2756 306.63 + vertex -585.64 97.3953 306.924 + vertex -578.032 95.3694 306.561 + endloop + endfacet + facet normal -0.250398 -0.961239 0.115416 + outer loop + vertex -548.982 88.0889 308.873 + vertex -548.076 87.6512 307.192 + vertex -525.735 81.9896 308.509 + endloop + endfacet + facet normal -0.249891 -0.962655 0.104166 + outer loop + vertex -509.384 77.8068 309.078 + vertex -511.491 78.4971 310.404 + vertex -525.735 81.9896 308.509 + endloop + endfacet + facet normal -0.251561 -0.959537 0.126511 + outer loop + vertex -509.928 78.312 312.108 + vertex -525.702 82.313 311.088 + vertex -511.491 78.4971 310.404 + endloop + endfacet + facet normal -0.252206 -0.955789 0.15119 + outer loop + vertex -509.928 78.312 312.108 + vertex -512.22 79.1597 313.644 + vertex -525.702 82.313 311.088 + endloop + endfacet + facet normal -0.252194 -0.952375 0.171408 + outer loop + vertex -510.745 79.112 315.549 + vertex -512.22 79.1597 313.644 + vertex -503.373 77.1596 315.548 + endloop + endfacet + facet normal -0.246913 -0.950262 0.18983 + outer loop + vertex -503.873 77.6463 317.334 + vertex -503.373 77.1596 315.548 + vertex -498.69 76.294 317.305 + endloop + endfacet + facet normal -0.243661 -0.958167 0.15015 + outer loop + vertex -498.373 75.8186 315.306 + vertex -502.725 76.6796 313.738 + vertex -497.104 75.2159 313.52 + endloop + endfacet + facet normal -0.2426 -0.960895 0.133516 + outer loop + vertex -497.104 75.2159 313.52 + vertex -502.093 76.2621 311.985 + vertex -496.833 74.8888 311.657 + endloop + endfacet + facet normal -0.240344 -0.965629 0.0989721 + outer loop + vertex -496.833 74.8888 311.657 + vertex -501.536 75.9242 310.339 + vertex -495.651 74.4345 310.095 + endloop + endfacet + facet normal -0.251426 -0.963907 0.0875691 + outer loop + vertex -493.636 74.1878 312.138 + vertex -491.826 73.4291 308.984 + vertex -490.416 73.2366 310.911 + endloop + endfacet + facet normal -0.237571 -0.968314 0.0769987 + outer loop + vertex -488.791 72.6422 308.45 + vertex -490.416 73.2366 310.911 + vertex -491.826 73.4291 308.984 + endloop + endfacet + facet normal -0.239783 -0.967195 0.0838896 + outer loop + vertex -495.651 74.4345 310.095 + vertex -501.169 75.6974 308.886 + vertex -495.459 74.2561 308.589 + endloop + endfacet + facet normal -0.221027 -0.973839 0.0527768 + outer loop + vertex -489.091 72.6494 306.048 + vertex -491.826 73.4291 308.984 + vertex -493.829 73.8003 307.443 + endloop + endfacet + facet normal -0.218183 -0.973905 0.0624957 + outer loop + vertex -493.829 73.8003 307.443 + vertex -493.254 73.6233 306.692 + vertex -489.091 72.6494 306.048 + endloop + endfacet + facet normal -0.229575 -0.973215 -0.0121921 + outer loop + vertex -493.254 73.6233 306.692 + vertex -495.193 74.0834 306.47 + vertex -489.091 72.6494 306.048 + endloop + endfacet + facet normal -0.241038 -0.968322 0.0652162 + outer loop + vertex -501.169 75.6974 308.886 + vertex -500.604 75.4748 307.665 + vertex -495.459 74.2561 308.589 + endloop + endfacet + facet normal -0.235936 -0.970577 0.0480997 + outer loop + vertex -493.829 73.8003 307.443 + vertex -498.253 74.8476 306.876 + vertex -493.254 73.6233 306.692 + endloop + endfacet + facet normal -0.24486 -0.966832 0.0726632 + outer loop + vertex -511.596 78.2687 307.8 + vertex -509.815 77.7385 306.749 + vertex -500.604 75.4748 307.665 + endloop + endfacet + facet normal -0.242258 -0.965256 0.0979401 + outer loop + vertex -511.319 78.0687 306.283 + vertex -502.785 75.9469 306.481 + vertex -509.815 77.7385 306.749 + endloop + endfacet + facet normal -0.235912 -0.970557 0.0486276 + outer loop + vertex -493.254 73.6233 306.692 + vertex -498.253 74.8476 306.876 + vertex -495.193 74.0834 306.47 + endloop + endfacet + facet normal -0.239149 -0.967581 0.0812078 + outer loop + vertex -502.785 75.9469 306.481 + vertex -507.537 77.1075 306.315 + vertex -498.594 74.9025 306.379 + endloop + endfacet + facet normal -0.237381 -0.958115 0.160208 + outer loop + vertex -498.594 74.9025 306.379 + vertex -507.537 77.1075 306.315 + vertex -502.725 75.9064 306.261 + endloop + endfacet + facet normal -0.203656 -0.943455 0.261567 + outer loop + vertex -495.193 74.0834 306.47 + vertex -493.66 73.7074 306.307 + vertex -489.091 72.6494 306.048 + endloop + endfacet + facet normal -0.236666 -0.971332 0.0224488 + outer loop + vertex -502.725 75.9064 306.261 + vertex -498.071 74.7683 306.082 + vertex -498.594 74.9025 306.379 + endloop + endfacet + facet normal -0.238592 -0.961804 0.134192 + outer loop + vertex -508.334 77.2862 306.178 + vertex -502.725 75.9064 306.261 + vertex -507.537 77.1075 306.315 + endloop + endfacet + facet normal -0.239329 -0.960826 0.13977 + outer loop + vertex -513.231 78.5087 306.196 + vertex -508.334 77.2862 306.178 + vertex -507.537 77.1075 306.315 + endloop + endfacet + facet normal -0.183277 -0.673237 0.716353 + outer loop + vertex -516.507 79.3244 306.124 + vertex -513.231 78.5087 306.196 + vertex -517.195 79.5232 306.135 + endloop + endfacet + facet normal -0.181303 -0.666755 0.722888 + outer loop + vertex -518.503 79.8289 306.089 + vertex -516.507 79.3244 306.124 + vertex -517.195 79.5232 306.135 + endloop + endfacet + facet normal -0.18701 -0.695585 0.693678 + outer loop + vertex -523.038 80.985 306.026 + vertex -518.503 79.8289 306.089 + vertex -517.195 79.5232 306.135 + endloop + endfacet + facet normal -0.080612 -0.306632 0.948408 + outer loop + vertex -529.936 82.764 306.015 + vertex -523.038 80.985 306.026 + vertex -524.893 81.4871 306.03 + endloop + endfacet + facet normal -0.23426 -0.908712 0.345492 + outer loop + vertex -538.051 84.8664 306.042 + vertex -529.936 82.764 306.015 + vertex -531.637 83.2467 306.131 + endloop + endfacet + facet normal -0.250773 -0.965065 0.0759105 + outer loop + vertex -529.511 82.5958 305.695 + vertex -542.94 86.071 305.516 + vertex -532.684 83.2926 304.072 + endloop + endfacet + facet normal -0.242243 -0.938182 0.247252 + outer loop + vertex -544.966 86.6698 306.11 + vertex -538.051 84.8664 306.042 + vertex -546.095 87.0219 306.34 + endloop + endfacet + facet normal -0.246067 -0.940917 0.232649 + outer loop + vertex -550.232 88.0437 306.097 + vertex -544.966 86.6698 306.11 + vertex -546.095 87.0219 306.34 + endloop + endfacet + facet normal -0.253485 -0.96631 0.0446115 + outer loop + vertex -542.94 86.071 305.516 + vertex -556.496 89.6297 305.57 + vertex -545.628 86.6525 302.834 + endloop + endfacet + facet normal -0.246072 -0.944484 0.217711 + outer loop + vertex -557.515 89.9781 306.257 + vertex -550.232 88.0437 306.097 + vertex -546.095 87.0219 306.34 + endloop + endfacet + facet normal -0.249418 -0.956594 0.150729 + outer loop + vertex -564.896 91.9065 306.283 + vertex -557.515 89.9781 306.257 + vertex -566.101 92.2756 306.63 + endloop + endfacet + facet normal -0.253916 -0.965915 0.0503468 + outer loop + vertex -556.496 89.6297 305.57 + vertex -569.853 93.1518 305.779 + vertex -560.16 90.5002 303.794 + endloop + endfacet + facet normal -0.249553 -0.956626 0.150298 + outer loop + vertex -570.579 93.4135 306.438 + vertex -564.896 91.9065 306.283 + vertex -566.101 92.2756 306.63 + endloop + endfacet + facet normal -0.249472 -0.959077 0.133923 + outer loop + vertex -578.032 95.3694 306.561 + vertex -570.579 93.4135 306.438 + vertex -566.101 92.2756 306.63 + endloop + endfacet + facet normal -0.252878 -0.966606 0.0415285 + outer loop + vertex -569.853 93.1518 305.779 + vertex -581.994 96.3356 305.955 + vertex -571.617 93.5083 303.337 + endloop + endfacet + facet normal -0.24999 -0.960553 0.121831 + outer loop + vertex -588.403 98.0947 306.768 + vertex -578.032 95.3694 306.561 + vertex -585.64 97.3953 306.924 + endloop + endfacet + facet normal -0.253074 -0.965755 0.0571899 + outer loop + vertex -581.994 96.3356 305.955 + vertex -592.034 98.9948 306.43 + vertex -587.35 97.6887 305.105 + endloop + endfacet + facet normal -0.240354 -0.936528 0.255237 + outer loop + vertex -594.35 99.6505 306.877 + vertex -588.403 98.0947 306.768 + vertex -591.873 99.0229 306.906 + endloop + endfacet + facet normal -0.245735 -0.963228 0.108656 + outer loop + vertex -599.077 100.833 306.667 + vertex -594.35 99.6505 306.877 + vertex -594.781 99.7688 306.95 + endloop + endfacet + facet normal -0.253791 -0.965716 0.0546143 + outer loop + vertex -595.086 99.729 305.231 + vertex -587.35 97.6887 305.105 + vertex -592.034 98.9948 306.43 + endloop + endfacet + facet normal -0.251468 -0.967786 0.0123699 + outer loop + vertex -595.086 99.729 305.231 + vertex -601.379 101.364 305.236 + vertex -596.489 100.064 302.897 + endloop + endfacet + facet normal -0.249947 -0.968136 0.0154417 + outer loop + vertex -605.04 102.305 304.946 + vertex -601.379 101.364 305.236 + vertex -605.737 102.509 306.479 + endloop + endfacet + facet normal -0.244719 -0.968204 0.0518925 + outer loop + vertex -604.09 102.134 307.297 + vertex -599.077 100.833 306.667 + vertex -597.364 100.429 307.213 + endloop + endfacet + facet normal -0.241348 -0.967166 0.0796273 + outer loop + vertex -609.406 103.505 307.843 + vertex -604.09 102.134 307.297 + vertex -604.941 102.39 307.828 + endloop + endfacet + facet normal -0.241089 -0.970456 0.00950726 + outer loop + vertex -605.737 102.509 306.479 + vertex -608.586 103.213 306.117 + vertex -607.393 102.908 305.167 + endloop + endfacet + facet normal -0.308638 -0.951174 0.00336746 + outer loop + vertex -608.586 103.213 306.117 + vertex -608.898 103.311 305.076 + vertex -608.711 103.249 304.703 + endloop + endfacet + facet normal -0.230784 -0.972089 0.0422067 + outer loop + vertex -611.449 103.942 306.743 + vertex -609.406 103.505 307.843 + vertex -611.921 104.082 307.376 + endloop + endfacet + facet normal -0.244398 -0.969166 0.0314102 + outer loop + vertex -611.921 104.082 307.376 + vertex -613.626 104.482 306.443 + vertex -611.449 103.942 306.743 + endloop + endfacet + facet normal -0.241156 -0.97047 0.00559614 + outer loop + vertex -613.649 104.484 305.838 + vertex -611.449 103.942 306.743 + vertex -613.626 104.482 306.443 + endloop + endfacet + facet normal -0.248872 -0.968518 0.00590752 + outer loop + vertex -613.626 104.482 306.443 + vertex -616.572 105.23 305.067 + vertex -613.649 104.484 305.838 + endloop + endfacet + facet normal -0.238758 -0.970929 -0.0170743 + outer loop + vertex -613.626 104.482 306.443 + vertex -617.46 105.429 306.195 + vertex -616.572 105.23 305.067 + endloop + endfacet + facet normal -0.247131 -0.968683 -0.0240621 + outer loop + vertex -617.46 105.429 306.195 + vertex -621.666 106.542 304.588 + vertex -616.572 105.23 305.067 + endloop + endfacet + facet normal -0.243682 -0.96806 -0.0589823 + outer loop + vertex -616.572 105.23 305.067 + vertex -621.666 106.542 304.588 + vertex -621.404 106.547 303.427 + endloop + endfacet + facet normal -0.260093 -0.963548 -0.0626699 + outer loop + vertex -621.666 106.542 304.588 + vertex -626.764 108.026 302.924 + vertex -621.404 106.547 303.427 + endloop + endfacet + facet normal -0.254154 -0.960176 -0.116054 + outer loop + vertex -621.404 106.547 303.427 + vertex -626.764 108.026 302.924 + vertex -626.648 108.12 301.893 + endloop + endfacet + facet normal -0.275492 -0.954048 -0.117888 + outer loop + vertex -626.764 108.026 302.924 + vertex -632.174 109.775 301.413 + vertex -626.648 108.12 301.893 + endloop + endfacet + facet normal -0.269609 -0.948483 -0.166405 + outer loop + vertex -626.648 108.12 301.893 + vertex -632.174 109.775 301.413 + vertex -632.103 109.924 300.451 + endloop + endfacet + facet normal -0.296298 -0.940359 -0.167131 + outer loop + vertex -632.174 109.775 301.413 + vertex -637.67 111.73 300.157 + vertex -632.103 109.924 300.451 + endloop + endfacet + facet normal -0.291342 -0.932563 -0.213182 + outer loop + vertex -632.103 109.924 300.451 + vertex -637.67 111.73 300.157 + vertex -637.601 111.917 299.245 + endloop + endfacet + facet normal -0.315474 -0.924629 -0.213393 + outer loop + vertex -637.67 111.73 300.157 + vertex -642.982 113.772 299.163 + vertex -637.601 111.917 299.245 + endloop + endfacet + facet normal -0.311617 -0.9153 -0.255187 + outer loop + vertex -637.601 111.917 299.245 + vertex -642.982 113.772 299.163 + vertex -643.054 114.062 298.212 + endloop + endfacet + facet normal -0.331042 -0.909369 -0.251911 + outer loop + vertex -642.982 113.772 299.163 + vertex -647.571 115.662 298.37 + vertex -643.054 114.062 298.212 + endloop + endfacet + facet normal -0.3278 -0.895318 -0.301583 + outer loop + vertex -643.054 114.062 298.212 + vertex -647.571 115.662 298.37 + vertex -647.906 116.093 297.453 + endloop + endfacet + facet normal -0.338607 -0.892978 -0.29654 + outer loop + vertex -647.571 115.662 298.37 + vertex -650.749 117.072 297.754 + vertex -647.906 116.093 297.453 + endloop + endfacet + facet normal -0.338168 -0.881819 -0.328692 + outer loop + vertex -647.906 116.093 297.453 + vertex -650.749 117.072 297.754 + vertex -651.111 117.478 297.037 + endloop + endfacet + facet normal -0.344649 -0.880746 -0.324815 + outer loop + vertex -650.749 117.072 297.754 + vertex -652.3 117.836 297.327 + vertex -651.111 117.478 297.037 + endloop + endfacet + facet normal -0.345869 -0.876367 -0.335194 + outer loop + vertex -651.111 117.478 297.037 + vertex -652.3 117.836 297.327 + vertex -652.187 117.949 296.915 + endloop + endfacet + facet normal 0.393363 0.916622 0.0712045 + outer loop + vertex -651.111 117.478 297.037 + vertex -652.187 117.949 296.915 + vertex -652.719 118.172 296.986 + endloop + endfacet + facet normal -0.294925 -0.728687 -0.618089 + outer loop + vertex -652.719 118.172 296.986 + vertex -649.636 116.93 296.979 + vertex -651.111 117.478 297.037 + endloop + endfacet + facet normal -0.337602 -0.835554 -0.433445 + outer loop + vertex -649.636 116.93 296.979 + vertex -652.719 118.172 296.986 + vertex -648.587 116.707 296.591 + endloop + endfacet + facet normal -0.325497 -0.863866 -0.384431 + outer loop + vertex -647.019 115.832 297.23 + vertex -649.636 116.93 296.979 + vertex -648.587 116.707 296.591 + endloop + endfacet + facet normal -0.340807 -0.885011 -0.317185 + outer loop + vertex -649.636 116.93 296.979 + vertex -647.019 115.832 297.23 + vertex -647.906 116.093 297.453 + endloop + endfacet + facet normal -0.34138 -0.885334 -0.315663 + outer loop + vertex -647.906 116.093 297.453 + vertex -651.111 117.478 297.037 + vertex -649.636 116.93 296.979 + endloop + endfacet + facet normal -0.338936 -0.890617 -0.303189 + outer loop + vertex -647.019 115.832 297.23 + vertex -644.959 114.914 297.623 + vertex -647.906 116.093 297.453 + endloop + endfacet + facet normal -0.309304 -0.864239 -0.396764 + outer loop + vertex -644.959 114.914 297.623 + vertex -647.019 115.832 297.23 + vertex -643.144 114.296 297.554 + endloop + endfacet + facet normal -0.40128 -0.849332 -0.342942 + outer loop + vertex -652.187 117.949 296.915 + vertex -652.3 117.836 297.327 + vertex -652.719 118.172 296.986 + endloop + endfacet + facet normal -0.371029 -0.847897 -0.378692 + outer loop + vertex -653.364 118.015 297.968 + vertex -652.719 118.172 296.986 + vertex -652.3 117.836 297.327 + endloop + endfacet + facet normal -0.351618 -0.872363 -0.339628 + outer loop + vertex -652.3 117.836 297.327 + vertex -652.777 117.584 298.468 + vertex -653.364 118.015 297.968 + endloop + endfacet + facet normal -0.345365 -0.872069 -0.346724 + outer loop + vertex -653.876 117.753 299.139 + vertex -653.364 118.015 297.968 + vertex -652.777 117.584 298.468 + endloop + endfacet + facet normal -0.345423 -0.872003 -0.346835 + outer loop + vertex -652.777 117.584 298.468 + vertex -654.003 117.319 300.356 + vertex -653.876 117.753 299.139 + endloop + endfacet + facet normal -0.332433 -0.876883 -0.347223 + outer loop + vertex -654.704 117.613 300.284 + vertex -653.876 117.753 299.139 + vertex -654.003 117.319 300.356 + endloop + endfacet + facet normal -0.331157 -0.875189 -0.352673 + outer loop + vertex -655.804 117.351 301.968 + vertex -654.704 117.613 300.284 + vertex -654.003 117.319 300.356 + endloop + endfacet + facet normal -0.309458 -0.89253 -0.328064 + outer loop + vertex -654.003 117.319 300.356 + vertex -655.711 117.076 302.628 + vertex -655.804 117.351 301.968 + endloop + endfacet + facet normal -0.308063 -0.892885 -0.32841 + outer loop + vertex -657.697 117.244 304.034 + vertex -655.804 117.351 301.968 + vertex -655.711 117.076 302.628 + endloop + endfacet + facet normal -0.287931 -0.910135 -0.297909 + outer loop + vertex -655.711 117.076 302.628 + vertex -657.827 117.059 304.724 + vertex -657.697 117.244 304.034 + endloop + endfacet + facet normal -0.296918 -0.906966 -0.298751 + outer loop + vertex -659.916 117.338 305.953 + vertex -657.697 117.244 304.034 + vertex -657.827 117.059 304.724 + endloop + endfacet + facet normal -0.285651 -0.91735 -0.277259 + outer loop + vertex -657.827 117.059 304.724 + vertex -660.03 117.203 306.516 + vertex -659.916 117.338 305.953 + endloop + endfacet + facet normal -0.299103 -0.912569 -0.278845 + outer loop + vertex -661.79 117.523 307.358 + vertex -659.916 117.338 305.953 + vertex -660.03 117.203 306.516 + endloop + endfacet + facet normal -0.299366 -0.912368 -0.279222 + outer loop + vertex -659.916 117.338 305.953 + vertex -661.79 117.523 307.358 + vertex -662.127 117.699 307.146 + endloop + endfacet + facet normal -0.310786 -0.900566 -0.303962 + outer loop + vertex -662.127 117.699 307.146 + vertex -659.711 117.555 305.101 + vertex -659.916 117.338 305.953 + endloop + endfacet + facet normal -0.333649 -0.882206 -0.33225 + outer loop + vertex -659.711 117.555 305.101 + vertex -662.127 117.699 307.146 + vertex -662.671 118.379 305.886 + endloop + endfacet + facet normal -0.339353 -0.863298 -0.373573 + outer loop + vertex -660.647 118.51 303.745 + vertex -659.711 117.555 305.101 + vertex -662.671 118.379 305.886 + endloop + endfacet + facet normal -0.362818 -0.844193 -0.394589 + outer loop + vertex -660.647 118.51 303.745 + vertex -662.671 118.379 305.886 + vertex -665.463 120.335 304.268 + endloop + endfacet + facet normal -0.360464 -0.827928 -0.429653 + outer loop + vertex -665.463 120.335 304.268 + vertex -663.679 120.733 302.005 + vertex -660.647 118.51 303.745 + endloop + endfacet + facet normal -0.37402 -0.831547 -0.410655 + outer loop + vertex -658.917 118.814 301.554 + vertex -660.647 118.51 303.745 + vertex -663.679 120.733 302.005 + endloop + endfacet + facet normal -0.372624 -0.824515 -0.425824 + outer loop + vertex -663.679 120.733 302.005 + vertex -662.272 121.223 299.826 + vertex -658.917 118.814 301.554 + endloop + endfacet + facet normal -0.386907 -0.828844 -0.404128 + outer loop + vertex -657.686 119.281 299.417 + vertex -658.917 118.814 301.554 + vertex -662.272 121.223 299.826 + endloop + endfacet + facet normal -0.387256 -0.830421 -0.400543 + outer loop + vertex -662.272 121.223 299.826 + vertex -661.189 121.627 297.939 + vertex -657.686 119.281 299.417 + endloop + endfacet + facet normal -0.394439 -0.833097 -0.387773 + outer loop + vertex -656.384 119.549 297.516 + vertex -657.686 119.281 299.417 + vertex -661.189 121.627 297.939 + endloop + endfacet + facet normal -0.397105 -0.845546 -0.356874 + outer loop + vertex -661.189 121.627 297.939 + vertex -660.311 121.729 296.722 + vertex -656.384 119.549 297.516 + endloop + endfacet + facet normal -0.418008 -0.829411 -0.370603 + outer loop + vertex -660.311 121.729 296.722 + vertex -661.189 121.627 297.939 + vertex -665.461 124.354 296.656 + endloop + endfacet + facet normal -0.420627 -0.830719 -0.364664 + outer loop + vertex -665.461 124.354 296.656 + vertex -661.189 121.627 297.939 + vertex -667.213 124.582 298.157 + endloop + endfacet + facet normal -0.374271 -0.847667 -0.376008 + outer loop + vertex -656.384 119.549 297.516 + vertex -654.811 118.221 298.944 + vertex -657.686 119.281 299.417 + endloop + endfacet + facet normal -0.374271 -0.846056 -0.379618 + outer loop + vertex -654.811 118.221 298.944 + vertex -656.053 117.883 300.922 + vertex -657.686 119.281 299.417 + endloop + endfacet + facet normal -0.345764 -0.864481 -0.364856 + outer loop + vertex -656.053 117.883 300.922 + vertex -654.811 118.221 298.944 + vertex -654.704 117.613 300.284 + endloop + endfacet + facet normal -0.380145 -0.847832 -0.369689 + outer loop + vertex -654.079 118.419 297.737 + vertex -654.811 118.221 298.944 + vertex -656.384 119.549 297.516 + endloop + endfacet + facet normal -0.372658 -0.83815 -0.398284 + outer loop + vertex -654.079 118.419 297.737 + vertex -656.384 119.549 297.516 + vertex -652.719 118.172 296.986 + endloop + endfacet + facet normal -0.373524 -0.859263 -0.349496 + outer loop + vertex -655.143 119.333 296.721 + vertex -652.719 118.172 296.986 + vertex -656.384 119.549 297.516 + endloop + endfacet + facet normal -0.356777 -0.838502 -0.411855 + outer loop + vertex -652.719 118.172 296.986 + vertex -655.143 119.333 296.721 + vertex -654.279 119.263 296.116 + endloop + endfacet + facet normal -0.368641 -0.823895 -0.430466 + outer loop + vertex -655.143 119.333 296.721 + vertex -657.638 120.577 296.478 + vertex -654.279 119.263 296.116 + endloop + endfacet + facet normal -0.36683 -0.856526 -0.363042 + outer loop + vertex -654.811 118.221 298.944 + vertex -654.079 118.419 297.737 + vertex -653.364 118.015 297.968 + endloop + endfacet + facet normal -0.413277 -0.812278 -0.411591 + outer loop + vertex -661.189 121.627 297.939 + vertex -662.272 121.223 299.826 + vertex -667.213 124.582 298.157 + endloop + endfacet + facet normal -0.400213 -0.805606 -0.436838 + outer loop + vertex -667.213 124.582 298.157 + vertex -662.272 121.223 299.826 + vertex -668.565 124.198 300.103 + endloop + endfacet + facet normal -0.361393 -0.845507 -0.393082 + outer loop + vertex -657.686 119.281 299.417 + vertex -656.053 117.883 300.922 + vertex -658.917 118.814 301.554 + endloop + endfacet + facet normal -0.36074 -0.850515 -0.382741 + outer loop + vertex -656.053 117.883 300.922 + vertex -657.625 117.609 303.012 + vertex -658.917 118.814 301.554 + endloop + endfacet + facet normal -0.332359 -0.870093 -0.363973 + outer loop + vertex -657.625 117.609 303.012 + vertex -656.053 117.883 300.922 + vertex -655.804 117.351 301.968 + endloop + endfacet + facet normal -0.399852 -0.804648 -0.438931 + outer loop + vertex -662.272 121.223 299.826 + vertex -663.679 120.733 302.005 + vertex -668.565 124.198 300.103 + endloop + endfacet + facet normal -0.379263 -0.794764 -0.473825 + outer loop + vertex -668.565 124.198 300.103 + vertex -663.679 120.733 302.005 + vertex -670.063 123.616 302.279 + endloop + endfacet + facet normal -0.348813 -0.850628 -0.393398 + outer loop + vertex -658.917 118.814 301.554 + vertex -657.625 117.609 303.012 + vertex -660.647 118.51 303.745 + endloop + endfacet + facet normal -0.38436 -0.808783 -0.445125 + outer loop + vertex -663.679 120.733 302.005 + vertex -665.463 120.335 304.268 + vertex -670.063 123.616 302.279 + endloop + endfacet + facet normal -0.362972 -0.799291 -0.478942 + outer loop + vertex -670.063 123.616 302.279 + vertex -665.463 120.335 304.268 + vertex -671.809 123.083 304.491 + endloop + endfacet + facet normal -0.350466 -0.841041 -0.412096 + outer loop + vertex -667.299 119.874 306.772 + vertex -665.463 120.335 304.268 + vertex -662.671 118.379 305.886 + endloop + endfacet + facet normal -0.347917 -0.869321 -0.351048 + outer loop + vertex -662.671 118.379 305.886 + vertex -664.1 118.238 307.651 + vertex -667.299 119.874 306.772 + endloop + endfacet + facet normal -0.342888 -0.86619 -0.363515 + outer loop + vertex -667.299 119.874 306.772 + vertex -664.1 118.238 307.651 + vertex -665.695 118.565 308.377 + endloop + endfacet + facet normal -0.31411 -0.864998 -0.391297 + outer loop + vertex -667.593 119.242 308.403 + vertex -667.299 119.874 306.772 + vertex -665.695 118.565 308.377 + endloop + endfacet + facet normal -0.334654 -0.856986 -0.391895 + outer loop + vertex -667.593 119.242 308.403 + vertex -670.601 120.574 308.06 + vertex -667.299 119.874 306.772 + endloop + endfacet + facet normal -0.342973 -0.867591 -0.360078 + outer loop + vertex -667.593 119.242 308.403 + vertex -669.068 119.516 309.148 + vertex -670.601 120.574 308.06 + endloop + endfacet + facet normal -0.335383 -0.866502 -0.36972 + outer loop + vertex -670.601 120.574 308.06 + vertex -669.068 119.516 309.148 + vertex -672.186 120.749 309.086 + endloop + endfacet + facet normal -0.3544 -0.843808 -0.402975 + outer loop + vertex -670.601 120.574 308.06 + vertex -672.186 120.749 309.086 + vertex -675.438 122.66 307.946 + endloop + endfacet + facet normal -0.347818 -0.84029 -0.415856 + outer loop + vertex -675.438 122.66 307.946 + vertex -672.186 120.749 309.086 + vertex -676.151 122.38 309.107 + endloop + endfacet + facet normal -0.366026 -0.828317 -0.424164 + outer loop + vertex -680.793 125.013 307.971 + vertex -675.438 122.66 307.946 + vertex -676.151 122.38 309.107 + endloop + endfacet + facet normal -0.357076 -0.821409 -0.444729 + outer loop + vertex -680.46 124.151 309.296 + vertex -680.793 125.013 307.971 + vertex -676.151 122.38 309.107 + endloop + endfacet + facet normal -0.364692 -0.819695 -0.441702 + outer loop + vertex -686.381 127.446 308.07 + vertex -680.793 125.013 307.971 + vertex -680.46 124.151 309.296 + endloop + endfacet + facet normal -0.321521 -0.89565 -0.307303 + outer loop + vertex -667.593 119.242 308.403 + vertex -666.917 118.724 309.207 + vertex -669.068 119.516 309.148 + endloop + endfacet + facet normal -0.323841 -0.895511 -0.305265 + outer loop + vertex -665.695 118.565 308.377 + vertex -666.917 118.724 309.207 + vertex -667.593 119.242 308.403 + endloop + endfacet + facet normal -0.30889 -0.908722 -0.280735 + outer loop + vertex -665.695 118.565 308.377 + vertex -665.458 118.231 309.197 + vertex -666.917 118.724 309.207 + endloop + endfacet + facet normal -0.33392 -0.902784 -0.27107 + outer loop + vertex -664.615 118.111 308.56 + vertex -665.458 118.231 309.197 + vertex -665.695 118.565 308.377 + endloop + endfacet + facet normal -0.323873 -0.894196 -0.309063 + outer loop + vertex -664.1 118.238 307.651 + vertex -664.615 118.111 308.56 + vertex -665.695 118.565 308.377 + endloop + endfacet + facet normal -0.284458 -0.913946 -0.289459 + outer loop + vertex -664.1 118.238 307.651 + vertex -664.196 117.939 308.69 + vertex -664.615 118.111 308.56 + endloop + endfacet + facet normal -0.320643 -0.901924 -0.289346 + outer loop + vertex -662.127 117.699 307.146 + vertex -664.196 117.939 308.69 + vertex -664.1 118.238 307.651 + endloop + endfacet + facet normal -0.304178 -0.914939 -0.26526 + outer loop + vertex -664.196 117.939 308.69 + vertex -662.127 117.699 307.146 + vertex -663.734 117.815 308.587 + endloop + endfacet + facet normal -0.301761 -0.92065 -0.247679 + outer loop + vertex -664.303 117.905 308.947 + vertex -664.196 117.939 308.69 + vertex -663.734 117.815 308.587 + endloop + endfacet + facet normal -0.324931 -0.910434 -0.255988 + outer loop + vertex -664.303 117.905 308.947 + vertex -664.801 117.996 309.254 + vertex -664.196 117.939 308.69 + endloop + endfacet + facet normal -0.324282 -0.910874 -0.255246 + outer loop + vertex -664.196 117.939 308.69 + vertex -664.801 117.996 309.254 + vertex -665.185 118.084 309.429 + endloop + endfacet + facet normal -0.305264 -0.924808 -0.227033 + outer loop + vertex -664.196 117.939 308.69 + vertex -665.185 118.084 309.429 + vertex -665.458 118.231 309.197 + endloop + endfacet + facet normal -0.31128 -0.924554 -0.219782 + outer loop + vertex -665.185 118.084 309.429 + vertex -665.859 118.24 309.725 + vertex -665.458 118.231 309.197 + endloop + endfacet + facet normal -0.308131 -0.926179 -0.217363 + outer loop + vertex -666.688 118.509 309.758 + vertex -665.458 118.231 309.197 + vertex -665.859 118.24 309.725 + endloop + endfacet + facet normal -0.308218 -0.926762 -0.21474 + outer loop + vertex -665.859 118.24 309.725 + vertex -666.402 118.358 309.999 + vertex -666.688 118.509 309.758 + endloop + endfacet + facet normal -0.318195 -0.926145 -0.202503 + outer loop + vertex -666.688 118.509 309.758 + vertex -666.402 118.358 309.999 + vertex -667.813 118.826 310.073 + endloop + endfacet + facet normal -0.317253 -0.927484 -0.197797 + outer loop + vertex -668.372 119.084 309.759 + vertex -666.688 118.509 309.758 + vertex -667.813 118.826 310.073 + endloop + endfacet + facet normal -0.315076 -0.921028 -0.228984 + outer loop + vertex -666.917 118.724 309.207 + vertex -666.688 118.509 309.758 + vertex -668.372 119.084 309.759 + endloop + endfacet + facet normal -0.326478 -0.906204 -0.268713 + outer loop + vertex -666.917 118.724 309.207 + vertex -668.372 119.084 309.759 + vertex -669.068 119.516 309.148 + endloop + endfacet + facet normal -0.324522 -0.906237 -0.27096 + outer loop + vertex -669.068 119.516 309.148 + vertex -668.372 119.084 309.759 + vertex -670.395 119.829 309.691 + endloop + endfacet + facet normal -0.341824 -0.880699 -0.327911 + outer loop + vertex -669.068 119.516 309.148 + vertex -670.395 119.829 309.691 + vertex -672.186 120.749 309.086 + endloop + endfacet + facet normal -0.343459 -0.881438 -0.324196 + outer loop + vertex -672.186 120.749 309.086 + vertex -670.395 119.829 309.691 + vertex -673.161 120.882 309.759 + endloop + endfacet + facet normal -0.358126 -0.86622 -0.348437 + outer loop + vertex -672.186 120.749 309.086 + vertex -673.161 120.882 309.759 + vertex -676.151 122.38 309.107 + endloop + endfacet + facet normal -0.346969 -0.857567 -0.379727 + outer loop + vertex -676.151 122.38 309.107 + vertex -673.161 120.882 309.759 + vertex -676.035 122.068 309.706 + endloop + endfacet + facet normal -0.366619 -0.852262 -0.37315 + outer loop + vertex -676.151 122.38 309.107 + vertex -676.035 122.068 309.706 + vertex -680.46 124.151 309.296 + endloop + endfacet + facet normal -0.401436 -0.892926 -0.203795 + outer loop + vertex -676.035 122.068 309.706 + vertex -675.388 121.695 310.064 + vertex -680.46 124.151 309.296 + endloop + endfacet + facet normal -0.343539 -0.840601 -0.418774 + outer loop + vertex -680.46 124.151 309.296 + vertex -675.388 121.695 310.064 + vertex -681.697 124.289 310.035 + endloop + endfacet + facet normal -0.353554 -0.826443 -0.438169 + outer loop + vertex -680.46 124.151 309.296 + vertex -681.697 124.289 310.035 + vertex -687.066 126.987 309.278 + endloop + endfacet + facet normal -0.340327 -0.81079 -0.476233 + outer loop + vertex -687.066 126.987 309.278 + vertex -681.697 124.289 310.035 + vertex -688.807 127.274 310.034 + endloop + endfacet + facet normal -0.343483 -0.803459 -0.486285 + outer loop + vertex -687.066 126.987 309.278 + vertex -688.807 127.274 310.034 + vertex -692.345 129.143 309.444 + endloop + endfacet + facet normal -0.341492 -0.801268 -0.491277 + outer loop + vertex -692.345 129.143 309.444 + vertex -688.807 127.274 310.034 + vertex -693.885 129.41 310.079 + endloop + endfacet + facet normal -0.343743 -0.795378 -0.499214 + outer loop + vertex -692.345 129.143 309.444 + vertex -693.885 129.41 310.079 + vertex -695.388 130.258 309.762 + endloop + endfacet + facet normal -0.344913 -0.796488 -0.496631 + outer loop + vertex -695.388 130.258 309.762 + vertex -693.885 129.41 310.079 + vertex -696.022 130.32 310.103 + endloop + endfacet + facet normal -0.367872 -0.751627 -0.547473 + outer loop + vertex -695.388 130.258 309.762 + vertex -696.022 130.32 310.103 + vertex -697.477 131.04 310.093 + endloop + endfacet + facet normal -0.404668 -0.824008 -0.396554 + outer loop + vertex -695.782 130.136 310.242 + vertex -697.477 131.04 310.093 + vertex -696.022 130.32 310.103 + endloop + endfacet + facet normal -0.387951 -0.802075 -0.454059 + outer loop + vertex -697.477 131.04 310.093 + vertex -695.782 130.136 310.242 + vertex -696.021 130.219 310.299 + endloop + endfacet + facet normal 0.02553 0.284957 0.9582 + outer loop + vertex -696.021 130.219 310.299 + vertex -694.696 129.592 310.45 + vertex -697.477 131.04 310.093 + endloop + endfacet + facet normal -0.398388 -0.892482 -0.211573 + outer loop + vertex -696.021 130.219 310.299 + vertex -694.648 129.598 310.332 + vertex -694.696 129.592 310.45 + endloop + endfacet + facet normal -0.385632 -0.899214 -0.206642 + outer loop + vertex -694.696 129.592 310.45 + vertex -694.648 129.598 310.332 + vertex -692.786 128.794 310.358 + endloop + endfacet + facet normal -0.386598 -0.904744 -0.178832 + outer loop + vertex -694.696 129.592 310.45 + vertex -692.786 128.794 310.358 + vertex -690.884 127.961 310.461 + endloop + endfacet + facet normal -0.377177 -0.883429 -0.278012 + outer loop + vertex -690.884 127.961 310.461 + vertex -692.482 128.559 310.727 + vertex -694.696 129.592 310.45 + endloop + endfacet + facet normal -0.377965 -0.884182 -0.274526 + outer loop + vertex -692.482 128.559 310.727 + vertex -695.661 129.854 310.934 + vertex -694.696 129.592 310.45 + endloop + endfacet + facet normal -0.40047 -0.852183 -0.336762 + outer loop + vertex -695.661 129.854 310.934 + vertex -697.477 131.04 310.093 + vertex -694.696 129.592 310.45 + endloop + endfacet + facet normal -0.386446 -0.848409 -0.361748 + outer loop + vertex -697.93 130.681 311.418 + vertex -697.477 131.04 310.093 + vertex -695.661 129.854 310.934 + endloop + endfacet + facet normal -0.379339 -0.892308 -0.244722 + outer loop + vertex -692.482 128.559 310.727 + vertex -692.431 128.403 311.219 + vertex -695.661 129.854 310.934 + endloop + endfacet + facet normal -0.3726 -0.894739 -0.246192 + outer loop + vertex -692.482 128.559 310.727 + vertex -686.756 126.173 310.733 + vertex -692.431 128.403 311.219 + endloop + endfacet + facet normal -0.373064 -0.907769 -0.191776 + outer loop + vertex -692.431 128.403 311.219 + vertex -686.756 126.173 310.733 + vertex -688.002 126.523 311.504 + endloop + endfacet + facet normal -0.370085 -0.910219 -0.185844 + outer loop + vertex -688.002 126.523 311.504 + vertex -686.756 126.173 310.733 + vertex -681.409 123.931 311.066 + endloop + endfacet + facet normal -0.374481 -0.899199 -0.226285 + outer loop + vertex -686.756 126.173 310.733 + vertex -692.482 128.559 310.727 + vertex -690.884 127.961 310.461 + endloop + endfacet + facet normal -0.37991 -0.905828 -0.187465 + outer loop + vertex -690.884 127.961 310.461 + vertex -686.945 126.328 310.371 + vertex -686.756 126.173 310.733 + endloop + endfacet + facet normal -0.374986 -0.907217 -0.190637 + outer loop + vertex -686.945 126.328 310.371 + vertex -681.118 123.922 310.357 + vertex -686.756 126.173 310.733 + endloop + endfacet + facet normal -0.378447 -0.900923 -0.212404 + outer loop + vertex -690.884 127.961 310.461 + vertex -690.224 127.717 310.319 + vertex -686.945 126.328 310.371 + endloop + endfacet + facet normal -0.37334 -0.890653 -0.259526 + outer loop + vertex -686.945 126.328 310.371 + vertex -690.224 127.717 310.319 + vertex -688.06 126.829 310.254 + endloop + endfacet + facet normal -0.365096 -0.864185 -0.346249 + outer loop + vertex -689.872 127.6 310.241 + vertex -688.06 126.829 310.254 + vertex -690.224 127.717 310.319 + endloop + endfacet + facet normal -0.366162 -0.857828 -0.360632 + outer loop + vertex -692.267 128.613 310.262 + vertex -689.872 127.6 310.241 + vertex -690.224 127.717 310.319 + endloop + endfacet + facet normal -0.340948 -0.795353 -0.501166 + outer loop + vertex -689.872 127.6 310.241 + vertex -692.267 128.613 310.262 + vertex -688.807 127.274 310.034 + endloop + endfacet + facet normal -0.340806 -0.809256 -0.478494 + outer loop + vertex -688.06 126.829 310.254 + vertex -689.872 127.6 310.241 + vertex -688.807 127.274 310.034 + endloop + endfacet + facet normal -0.338032 -0.807234 -0.483846 + outer loop + vertex -684.527 125.359 310.238 + vertex -688.06 126.829 310.254 + vertex -688.807 127.274 310.034 + endloop + endfacet + facet normal -0.38018 -0.896272 -0.228386 + outer loop + vertex -692.786 128.794 310.358 + vertex -690.224 127.717 310.319 + vertex -690.884 127.961 310.461 + endloop + endfacet + facet normal -0.365564 -0.857658 -0.361643 + outer loop + vertex -692.786 128.794 310.358 + vertex -694.648 129.598 310.332 + vertex -692.267 128.613 310.262 + endloop + endfacet + facet normal -0.363361 -0.851099 -0.378944 + outer loop + vertex -694.427 129.531 310.271 + vertex -692.267 128.613 310.262 + vertex -694.648 129.598 310.332 + endloop + endfacet + facet normal -0.366049 -0.839766 -0.401002 + outer loop + vertex -695.782 130.136 310.242 + vertex -694.427 129.531 310.271 + vertex -694.648 129.598 310.332 + endloop + endfacet + facet normal -0.34937 -0.806103 -0.477638 + outer loop + vertex -694.427 129.531 310.271 + vertex -695.782 130.136 310.242 + vertex -693.885 129.41 310.079 + endloop + endfacet + facet normal -0.347388 -0.812631 -0.467924 + outer loop + vertex -692.267 128.613 310.262 + vertex -694.427 129.531 310.271 + vertex -693.885 129.41 310.079 + endloop + endfacet + facet normal -0.380751 -0.860329 -0.338914 + outer loop + vertex -694.648 129.598 310.332 + vertex -696.021 130.219 310.299 + vertex -695.782 130.136 310.242 + endloop + endfacet + facet normal -0.35008 -0.809297 -0.471681 + outer loop + vertex -696.022 130.32 310.103 + vertex -693.885 129.41 310.079 + vertex -695.782 130.136 310.242 + endloop + endfacet + facet normal -0.34455 -0.808843 -0.476507 + outer loop + vertex -693.885 129.41 310.079 + vertex -688.807 127.274 310.034 + vertex -692.267 128.613 310.262 + endloop + endfacet + facet normal -0.362921 -0.891344 -0.271653 + outer loop + vertex -676.035 122.068 309.706 + vertex -673.161 120.882 309.759 + vertex -675.388 121.695 310.064 + endloop + endfacet + facet normal -0.334341 -0.924763 -0.18174 + outer loop + vertex -670.395 119.829 309.691 + vertex -668.372 119.084 309.759 + vertex -670.667 119.856 310.052 + endloop + endfacet + facet normal -0.353011 -0.91474 -0.196555 + outer loop + vertex -670.395 119.829 309.691 + vertex -670.667 119.856 310.052 + vertex -673.161 120.882 309.759 + endloop + endfacet + facet normal -0.318196 -0.926155 -0.202457 + outer loop + vertex -667.813 118.826 310.073 + vertex -666.402 118.358 309.999 + vertex -666.04 118.158 310.344 + endloop + endfacet + facet normal -0.333541 -0.93467 -0.123054 + outer loop + vertex -666.04 118.158 310.344 + vertex -669.575 119.439 310.195 + vertex -667.813 118.826 310.073 + endloop + endfacet + facet normal -0.311476 -0.926791 -0.209861 + outer loop + vertex -665.659 118.157 309.782 + vertex -666.04 118.158 310.344 + vertex -666.402 118.358 309.999 + endloop + endfacet + facet normal -0.320368 -0.922366 -0.215885 + outer loop + vertex -665.195 118.056 309.527 + vertex -666.04 118.158 310.344 + vertex -665.659 118.157 309.782 + endloop + endfacet + facet normal -0.446848 -0.819216 -0.35946 + outer loop + vertex -666.04 118.158 310.344 + vertex -665.195 118.056 309.527 + vertex -665.383 118.042 309.793 + endloop + endfacet + facet normal 0.1764 0.984314 0.00283405 + outer loop + vertex -665.383 118.042 309.793 + vertex -665.934 118.139 310.149 + vertex -666.04 118.158 310.344 + endloop + endfacet + facet normal -0.343634 -0.934004 -0.097741 + outer loop + vertex -665.934 118.139 310.149 + vertex -665.433 117.928 310.406 + vertex -666.04 118.158 310.344 + endloop + endfacet + facet normal -0.303858 -0.936143 -0.176938 + outer loop + vertex -665.433 117.928 310.406 + vertex -665.934 118.139 310.149 + vertex -664.897 117.816 310.079 + endloop + endfacet + facet normal -0.295584 -0.941557 -0.161559 + outer loop + vertex -663.619 117.326 310.593 + vertex -665.433 117.928 310.406 + vertex -664.897 117.816 310.079 + endloop + endfacet + facet normal -0.297535 -0.941734 -0.156873 + outer loop + vertex -663.619 117.326 310.593 + vertex -664.897 117.816 310.079 + vertex -661.968 116.905 309.993 + endloop + endfacet + facet normal -0.296717 -0.936096 -0.188899 + outer loop + vertex -661.968 116.905 309.993 + vertex -664.897 117.816 310.079 + vertex -663.461 117.487 309.454 + endloop + endfacet + facet normal -0.296978 -0.936148 -0.188234 + outer loop + vertex -661.968 116.905 309.993 + vertex -663.461 117.487 309.454 + vertex -659.588 116.342 309.038 + endloop + endfacet + facet normal -0.28711 -0.944673 -0.158621 + outer loop + vertex -656.99 115.42 309.823 + vertex -661.968 116.905 309.993 + vertex -659.588 116.342 309.038 + endloop + endfacet + facet normal -0.286818 -0.944611 -0.159514 + outer loop + vertex -656.99 115.42 309.823 + vertex -659.588 116.342 309.038 + vertex -653.841 114.693 308.464 + endloop + endfacet + facet normal -0.288741 -0.934707 -0.207249 + outer loop + vertex -653.841 114.693 308.464 + vertex -659.588 116.342 309.038 + vertex -656.98 115.84 307.669 + endloop + endfacet + facet normal -0.289091 -0.934856 -0.206086 + outer loop + vertex -653.841 114.693 308.464 + vertex -656.98 115.84 307.669 + vertex -650.79 114.142 306.687 + endloop + endfacet + facet normal -0.275261 -0.944489 -0.179367 + outer loop + vertex -646.676 112.738 307.764 + vertex -653.841 114.693 308.464 + vertex -650.79 114.142 306.687 + endloop + endfacet + facet normal -0.276525 -0.94492 -0.175101 + outer loop + vertex -646.676 112.738 307.764 + vertex -650.79 114.142 306.687 + vertex -643.387 112.163 305.674 + endloop + endfacet + facet normal -0.260264 -0.954292 -0.146932 + outer loop + vertex -638.724 110.678 307.06 + vertex -646.676 112.738 307.764 + vertex -643.387 112.163 305.674 + endloop + endfacet + facet normal -0.263608 -0.954941 -0.136381 + outer loop + vertex -638.724 110.678 307.06 + vertex -643.387 112.163 305.674 + vertex -635.534 110.11 304.873 + endloop + endfacet + facet normal -0.24767 -0.962444 -0.111185 + outer loop + vertex -630.678 108.672 306.506 + vertex -638.724 110.678 307.06 + vertex -635.534 110.11 304.873 + endloop + endfacet + facet normal -0.253035 -0.962733 -0.0954921 + outer loop + vertex -630.678 108.672 306.506 + vertex -635.534 110.11 304.873 + vertex -628.044 108.179 304.49 + endloop + endfacet + facet normal -0.240509 -0.967511 -0.077963 + outer loop + vertex -623.326 106.868 306.205 + vertex -630.678 108.672 306.506 + vertex -628.044 108.179 304.49 + endloop + endfacet + facet normal -0.247388 -0.967134 -0.058752 + outer loop + vertex -623.326 106.868 306.205 + vertex -628.044 108.179 304.49 + vertex -621.666 106.542 304.588 + endloop + endfacet + facet normal -0.266282 -0.945744 -0.18618 + outer loop + vertex -635.534 110.11 304.873 + vertex -643.387 112.163 305.674 + vertex -640.657 111.822 303.505 + endloop + endfacet + facet normal -0.271699 -0.947573 -0.168182 + outer loop + vertex -635.534 110.11 304.873 + vertex -640.657 111.822 303.505 + vertex -633.295 109.818 302.899 + endloop + endfacet + facet normal -0.253927 -0.956022 -0.146776 + outer loop + vertex -628.044 108.179 304.49 + vertex -635.534 110.11 304.873 + vertex -633.295 109.818 302.899 + endloop + endfacet + facet normal -0.262236 -0.957415 -0.120782 + outer loop + vertex -628.044 108.179 304.49 + vertex -633.295 109.818 302.899 + vertex -626.764 108.026 302.924 + endloop + endfacet + facet normal -0.272847 -0.937981 -0.213883 + outer loop + vertex -633.295 109.818 302.899 + vertex -640.657 111.822 303.505 + vertex -638.691 111.688 301.582 + endloop + endfacet + facet normal -0.281221 -0.941678 -0.184818 + outer loop + vertex -633.295 109.818 302.899 + vertex -638.691 111.688 301.582 + vertex -632.174 109.775 301.413 + endloop + endfacet + facet normal -0.291527 -0.927571 -0.233716 + outer loop + vertex -640.657 111.822 303.505 + vertex -645.63 113.646 302.467 + vertex -638.691 111.688 301.582 + endloop + endfacet + facet normal -0.293161 -0.917494 -0.268814 + outer loop + vertex -638.691 111.688 301.582 + vertex -645.63 113.646 302.467 + vertex -643.877 113.64 300.576 + endloop + endfacet + facet normal -0.30023 -0.922588 -0.242268 + outer loop + vertex -638.691 111.688 301.582 + vertex -643.877 113.64 300.576 + vertex -637.67 111.73 300.157 + endloop + endfacet + facet normal -0.308125 -0.908368 -0.282712 + outer loop + vertex -645.63 113.646 302.467 + vertex -649.867 115.323 301.696 + vertex -643.877 113.64 300.576 + endloop + endfacet + facet normal -0.310186 -0.899949 -0.306393 + outer loop + vertex -643.877 113.64 300.576 + vertex -649.867 115.323 301.696 + vertex -648.303 115.432 299.792 + endloop + endfacet + facet normal -0.316081 -0.905014 -0.28468 + outer loop + vertex -643.877 113.64 300.576 + vertex -648.303 115.432 299.792 + vertex -642.982 113.772 299.163 + endloop + endfacet + facet normal -0.321334 -0.892984 -0.315156 + outer loop + vertex -649.867 115.323 301.696 + vertex -652.707 116.567 301.067 + vertex -648.303 115.432 299.792 + endloop + endfacet + facet normal -0.323694 -0.887381 -0.328295 + outer loop + vertex -648.303 115.432 299.792 + vertex -652.707 116.567 301.067 + vertex -651.324 116.777 299.136 + endloop + endfacet + facet normal -0.328631 -0.891056 -0.313084 + outer loop + vertex -648.303 115.432 299.792 + vertex -651.324 116.777 299.136 + vertex -647.571 115.662 298.37 + endloop + endfacet + facet normal -0.33005 -0.883494 -0.332423 + outer loop + vertex -652.707 116.567 301.067 + vertex -654.003 117.319 300.356 + vertex -651.324 116.777 299.136 + endloop + endfacet + facet normal -0.318385 -0.89081 -0.324174 + outer loop + vertex -649.867 115.323 301.696 + vertex -654.638 116.472 303.224 + vertex -652.707 116.567 301.067 + endloop + endfacet + facet normal -0.319796 -0.889859 -0.325394 + outer loop + vertex -654.638 116.472 303.224 + vertex -655.711 117.076 302.628 + vertex -652.707 116.567 301.067 + endloop + endfacet + facet normal -0.314301 -0.898867 -0.305375 + outer loop + vertex -651.985 115.339 303.831 + vertex -654.638 116.472 303.224 + vertex -649.867 115.323 301.696 + endloop + endfacet + facet normal -0.312072 -0.897299 -0.312193 + outer loop + vertex -651.985 115.339 303.831 + vertex -656.871 116.531 305.288 + vertex -654.638 116.472 303.224 + endloop + endfacet + facet normal -0.311934 -0.897401 -0.31204 + outer loop + vertex -656.871 116.531 305.288 + vertex -657.827 117.059 304.724 + vertex -654.638 116.472 303.224 + endloop + endfacet + facet normal -0.307346 -0.906788 -0.288572 + outer loop + vertex -654.404 115.501 305.896 + vertex -656.871 116.531 305.288 + vertex -651.985 115.339 303.831 + endloop + endfacet + facet normal -0.298418 -0.91317 -0.277611 + outer loop + vertex -648.008 113.803 304.606 + vertex -654.404 115.501 305.896 + vertex -651.985 115.339 303.831 + endloop + endfacet + facet normal -0.301179 -0.915256 -0.267577 + outer loop + vertex -648.008 113.803 304.606 + vertex -651.985 115.339 303.831 + vertex -645.63 113.646 302.467 + endloop + endfacet + facet normal -0.294405 -0.924234 -0.243138 + outer loop + vertex -650.79 114.142 306.687 + vertex -654.404 115.501 305.896 + vertex -648.008 113.803 304.606 + endloop + endfacet + facet normal -0.306021 -0.905962 -0.292548 + outer loop + vertex -654.404 115.501 305.896 + vertex -659.161 116.732 307.06 + vertex -656.871 116.531 305.288 + endloop + endfacet + facet normal -0.307054 -0.90515 -0.293975 + outer loop + vertex -659.161 116.732 307.06 + vertex -660.03 117.203 306.516 + vertex -656.871 116.531 305.288 + endloop + endfacet + facet normal -0.309211 -0.905446 -0.290786 + outer loop + vertex -659.161 116.732 307.06 + vertex -662.127 117.46 307.947 + vertex -660.03 117.203 306.516 + endloop + endfacet + facet normal -0.294145 -0.917864 -0.266466 + outer loop + vertex -660.03 117.203 306.516 + vertex -662.127 117.46 307.947 + vertex -661.79 117.523 307.358 + endloop + endfacet + facet normal -0.310485 -0.909938 -0.274975 + outer loop + vertex -663.734 117.815 308.587 + vertex -661.79 117.523 307.358 + vertex -662.127 117.46 307.947 + endloop + endfacet + facet normal -0.305111 -0.912979 -0.270883 + outer loop + vertex -661.436 117.078 308.457 + vertex -662.127 117.46 307.947 + vertex -659.161 116.732 307.06 + endloop + endfacet + facet normal -0.301309 -0.916288 -0.263873 + outer loop + vertex -656.98 115.84 307.669 + vertex -661.436 117.078 308.457 + vertex -659.161 116.732 307.06 + endloop + endfacet + facet normal -0.308389 -0.913145 -0.266574 + outer loop + vertex -661.436 117.078 308.457 + vertex -664.018 117.78 309.039 + vertex -662.127 117.46 307.947 + endloop + endfacet + facet normal -0.307055 -0.914369 -0.263906 + outer loop + vertex -662.127 117.46 307.947 + vertex -664.018 117.78 309.039 + vertex -663.734 117.815 308.587 + endloop + endfacet + facet normal -0.304976 -0.921162 -0.241765 + outer loop + vertex -663.461 117.487 309.454 + vertex -664.018 117.78 309.039 + vertex -661.436 117.078 308.457 + endloop + endfacet + facet normal -0.307823 -0.921202 -0.237973 + outer loop + vertex -663.461 117.487 309.454 + vertex -665.383 118.042 309.793 + vertex -664.018 117.78 309.039 + endloop + endfacet + facet normal -0.301541 -0.916403 -0.263208 + outer loop + vertex -656.98 115.84 307.669 + vertex -659.161 116.732 307.06 + vertex -654.404 115.501 305.896 + endloop + endfacet + facet normal -0.304593 -0.90542 -0.295697 + outer loop + vertex -645.63 113.646 302.467 + vertex -651.985 115.339 303.831 + vertex -649.867 115.323 301.696 + endloop + endfacet + facet normal -0.286822 -0.924535 -0.250933 + outer loop + vertex -640.657 111.822 303.505 + vertex -648.008 113.803 304.606 + vertex -645.63 113.646 302.467 + endloop + endfacet + facet normal -0.283649 -0.935739 -0.209608 + outer loop + vertex -643.387 112.163 305.674 + vertex -648.008 113.803 304.606 + vertex -640.657 111.822 303.505 + endloop + endfacet + facet normal -0.280043 -0.93388 -0.222361 + outer loop + vertex -643.387 112.163 305.674 + vertex -650.79 114.142 306.687 + vertex -648.008 113.803 304.606 + endloop + endfacet + facet normal -0.292711 -0.923189 -0.249082 + outer loop + vertex -650.79 114.142 306.687 + vertex -656.98 115.84 307.669 + vertex -654.404 115.501 305.896 + endloop + endfacet + facet normal -0.297871 -0.927121 -0.227419 + outer loop + vertex -659.588 116.342 309.038 + vertex -661.436 117.078 308.457 + vertex -656.98 115.84 307.669 + endloop + endfacet + facet normal -0.287465 -0.950842 -0.115166 + outer loop + vertex -659.841 116.168 310.764 + vertex -661.968 116.905 309.993 + vertex -656.99 115.42 309.823 + endloop + endfacet + facet normal -0.286077 -0.950795 -0.118949 + outer loop + vertex -659.841 116.168 310.764 + vertex -663.619 117.326 310.593 + vertex -661.968 116.905 309.993 + endloop + endfacet + facet normal -0.288121 -0.953282 -0.0907756 + outer loop + vertex -661.808 116.704 311.379 + vertex -663.619 117.326 310.593 + vertex -659.841 116.168 310.764 + endloop + endfacet + facet normal -0.283056 -0.953591 -0.102686 + outer loop + vertex -661.808 116.704 311.379 + vertex -664.261 117.476 310.969 + vertex -663.619 117.326 310.593 + endloop + endfacet + facet normal -0.28776 -0.954642 -0.0765004 + outer loop + vertex -662.469 116.865 311.864 + vertex -664.261 117.476 310.969 + vertex -661.808 116.704 311.379 + endloop + endfacet + facet normal -0.298416 -0.927311 -0.225925 + outer loop + vertex -659.588 116.342 309.038 + vertex -663.461 117.487 309.454 + vertex -661.436 117.078 308.457 + endloop + endfacet + facet normal -0.305434 -0.928043 -0.213183 + outer loop + vertex -664.897 117.816 310.079 + vertex -665.383 118.042 309.793 + vertex -663.461 117.487 309.454 + endloop + endfacet + facet normal -0.299421 -0.944642 -0.13416 + outer loop + vertex -664.261 117.476 310.969 + vertex -665.433 117.928 310.406 + vertex -663.619 117.326 310.593 + endloop + endfacet + facet normal -0.352576 -0.935641 -0.0162739 + outer loop + vertex -665.433 117.928 310.406 + vertex -664.261 117.476 310.969 + vertex -666.04 118.158 310.344 + endloop + endfacet + facet normal -0.303915 -0.92796 -0.2157 + outer loop + vertex -664.897 117.816 310.079 + vertex -665.934 118.139 310.149 + vertex -665.383 118.042 309.793 + endloop + endfacet + facet normal -0.316659 -0.919008 -0.234842 + outer loop + vertex -665.859 118.24 309.725 + vertex -665.659 118.157 309.782 + vertex -666.402 118.358 309.999 + endloop + endfacet + facet normal -0.312871 -0.921505 -0.230089 + outer loop + vertex -665.458 118.231 309.197 + vertex -666.688 118.509 309.758 + vertex -666.917 118.724 309.207 + endloop + endfacet + facet normal -0.316642 -0.919002 -0.234891 + outer loop + vertex -665.185 118.084 309.429 + vertex -665.659 118.157 309.782 + vertex -665.859 118.24 309.725 + endloop + endfacet + facet normal -0.317131 -0.918646 -0.235621 + outer loop + vertex -664.801 117.996 309.254 + vertex -665.659 118.157 309.782 + vertex -665.185 118.084 309.429 + endloop + endfacet + facet normal -0.306518 -0.923422 -0.230952 + outer loop + vertex -664.615 118.111 308.56 + vertex -664.196 117.939 308.69 + vertex -665.458 118.231 309.197 + endloop + endfacet + facet normal -0.372242 -0.825047 -0.425126 + outer loop + vertex -665.463 120.335 304.268 + vertex -667.299 119.874 306.772 + vertex -671.809 123.083 304.491 + endloop + endfacet + facet normal -0.343151 -0.814503 -0.467795 + outer loop + vertex -671.809 123.083 304.491 + vertex -667.299 119.874 306.772 + vertex -673.793 122.808 306.426 + endloop + endfacet + facet normal -0.371242 -0.787047 -0.492683 + outer loop + vertex -671.809 123.083 304.491 + vertex -673.793 122.808 306.426 + vertex -678.678 126.32 304.496 + endloop + endfacet + facet normal -0.34878 -0.824374 -0.445825 + outer loop + vertex -673.793 122.808 306.426 + vertex -667.299 119.874 306.772 + vertex -670.601 120.574 308.06 + endloop + endfacet + facet normal -0.344108 -0.822648 -0.452592 + outer loop + vertex -675.438 122.66 307.946 + vertex -673.793 122.808 306.426 + vertex -670.601 120.574 308.06 + endloop + endfacet + facet normal -0.363405 -0.803445 -0.471607 + outer loop + vertex -673.793 122.808 306.426 + vertex -675.438 122.66 307.946 + vertex -680.029 125.661 306.372 + endloop + endfacet + facet normal -0.352486 -0.796797 -0.490783 + outer loop + vertex -680.029 125.661 306.372 + vertex -675.438 122.66 307.946 + vertex -680.793 125.013 307.971 + endloop + endfacet + facet normal -0.366928 -0.788138 -0.494169 + outer loop + vertex -680.029 125.661 306.372 + vertex -680.793 125.013 307.971 + vertex -685.845 128.32 306.449 + endloop + endfacet + facet normal -0.346356 -0.862758 -0.368357 + outer loop + vertex -657.625 117.609 303.012 + vertex -659.711 117.555 305.101 + vertex -660.647 118.51 303.745 + endloop + endfacet + facet normal -0.316564 -0.885853 -0.339192 + outer loop + vertex -659.711 117.555 305.101 + vertex -657.625 117.609 303.012 + vertex -657.697 117.244 304.034 + endloop + endfacet + facet normal -0.327384 -0.883305 -0.335547 + outer loop + vertex -662.671 118.379 305.886 + vertex -662.127 117.699 307.146 + vertex -664.1 118.238 307.651 + endloop + endfacet + facet normal -0.306715 -0.913225 -0.268228 + outer loop + vertex -661.79 117.523 307.358 + vertex -663.734 117.815 308.587 + vertex -662.127 117.699 307.146 + endloop + endfacet + facet normal -0.312255 -0.897459 -0.311551 + outer loop + vertex -656.871 116.531 305.288 + vertex -660.03 117.203 306.516 + vertex -657.827 117.059 304.724 + endloop + endfacet + facet normal -0.300011 -0.904725 -0.302435 + outer loop + vertex -657.697 117.244 304.034 + vertex -659.916 117.338 305.953 + vertex -659.711 117.555 305.101 + endloop + endfacet + facet normal -0.318047 -0.889474 -0.328148 + outer loop + vertex -654.638 116.472 303.224 + vertex -657.827 117.059 304.724 + vertex -655.711 117.076 302.628 + endloop + endfacet + facet normal -0.320102 -0.88465 -0.339012 + outer loop + vertex -655.804 117.351 301.968 + vertex -657.697 117.244 304.034 + vertex -657.625 117.609 303.012 + endloop + endfacet + facet normal -0.325741 -0.882503 -0.339236 + outer loop + vertex -652.707 116.567 301.067 + vertex -655.711 117.076 302.628 + vertex -654.003 117.319 300.356 + endloop + endfacet + facet normal -0.343942 -0.867321 -0.359803 + outer loop + vertex -654.704 117.613 300.284 + vertex -655.804 117.351 301.968 + vertex -656.053 117.883 300.922 + endloop + endfacet + facet normal -0.356246 -0.861197 -0.36253 + outer loop + vertex -653.876 117.753 299.139 + vertex -654.704 117.613 300.284 + vertex -654.811 118.221 298.944 + endloop + endfacet + facet normal -0.332573 -0.879814 -0.339593 + outer loop + vertex -651.324 116.777 299.136 + vertex -654.003 117.319 300.356 + vertex -652.777 117.584 298.468 + endloop + endfacet + facet normal -0.338549 -0.88163 -0.328806 + outer loop + vertex -651.324 116.777 299.136 + vertex -652.777 117.584 298.468 + vertex -650.749 117.072 297.754 + endloop + endfacet + facet normal -0.360075 -0.864212 -0.351402 + outer loop + vertex -653.364 118.015 297.968 + vertex -653.876 117.753 299.139 + vertex -654.811 118.221 298.944 + endloop + endfacet + facet normal -0.361956 -0.854003 -0.373719 + outer loop + vertex -652.719 118.172 296.986 + vertex -653.364 118.015 297.968 + vertex -654.079 118.419 297.737 + endloop + endfacet + facet normal -0.340268 -0.878187 -0.336162 + outer loop + vertex -650.749 117.072 297.754 + vertex -652.777 117.584 298.468 + vertex -652.3 117.836 297.327 + endloop + endfacet + facet normal -0.329771 -0.885961 -0.326073 + outer loop + vertex -647.571 115.662 298.37 + vertex -651.324 116.777 299.136 + vertex -650.749 117.072 297.754 + endloop + endfacet + facet normal -0.31641 -0.897295 -0.30781 + outer loop + vertex -642.982 113.772 299.163 + vertex -648.303 115.432 299.792 + vertex -647.571 115.662 298.37 + endloop + endfacet + facet normal -0.299655 -0.913531 -0.275078 + outer loop + vertex -637.67 111.73 300.157 + vertex -643.877 113.64 300.576 + vertex -642.982 113.772 299.163 + endloop + endfacet + facet normal -0.279694 -0.93266 -0.227853 + outer loop + vertex -632.174 109.775 301.413 + vertex -638.691 111.688 301.582 + vertex -637.67 111.73 300.157 + endloop + endfacet + facet normal -0.260209 -0.950699 -0.168711 + outer loop + vertex -626.764 108.026 302.924 + vertex -633.295 109.818 302.899 + vertex -632.174 109.775 301.413 + endloop + endfacet + facet normal -0.245708 -0.963457 -0.106673 + outer loop + vertex -621.666 106.542 304.588 + vertex -628.044 108.179 304.49 + vertex -626.764 108.026 302.924 + endloop + endfacet + facet normal -0.238095 -0.970024 -0.0486332 + outer loop + vertex -617.46 105.429 306.195 + vertex -623.326 106.868 306.205 + vertex -621.666 106.542 304.588 + endloop + endfacet + facet normal -0.240677 -0.9705 0.0143172 + outer loop + vertex -614.699 104.763 307.506 + vertex -617.46 105.429 306.195 + vertex -613.626 104.482 306.443 + endloop + endfacet + facet normal -0.235262 -0.97193 0.00217929 + outer loop + vertex -614.699 104.763 307.506 + vertex -619.682 105.97 307.803 + vertex -617.46 105.429 306.195 + endloop + endfacet + facet normal -0.238304 -0.971188 -0.00227415 + outer loop + vertex -619.682 105.97 307.803 + vertex -623.326 106.868 306.205 + vertex -617.46 105.429 306.195 + endloop + endfacet + facet normal -0.233267 -0.972306 -0.0143851 + outer loop + vertex -619.682 105.97 307.803 + vertex -626.498 107.599 308.224 + vertex -623.326 106.868 306.205 + endloop + endfacet + facet normal -0.239085 -0.9707 -0.0241054 + outer loop + vertex -626.498 107.599 308.224 + vertex -630.678 108.672 306.506 + vertex -623.326 106.868 306.205 + endloop + endfacet + facet normal -0.234911 -0.971398 -0.0346956 + outer loop + vertex -626.498 107.599 308.224 + vertex -634.424 109.499 308.691 + vertex -630.678 108.672 306.506 + endloop + endfacet + facet normal -0.245086 -0.968028 -0.0534239 + outer loop + vertex -634.424 109.499 308.691 + vertex -638.724 110.678 307.06 + vertex -630.678 108.672 306.506 + endloop + endfacet + facet normal -0.242859 -0.968238 -0.0594485 + outer loop + vertex -634.424 109.499 308.691 + vertex -642.612 111.525 309.144 + vertex -638.724 110.678 307.06 + endloop + endfacet + facet normal -0.257173 -0.962298 -0.0885695 + outer loop + vertex -642.612 111.525 309.144 + vertex -646.676 112.738 307.764 + vertex -638.724 110.678 307.06 + endloop + endfacet + facet normal -0.257149 -0.962298 -0.0886384 + outer loop + vertex -642.612 111.525 309.144 + vertex -650.338 113.554 309.534 + vertex -646.676 112.738 307.764 + endloop + endfacet + facet normal -0.272488 -0.954118 -0.124133 + outer loop + vertex -650.338 113.554 309.534 + vertex -653.841 114.693 308.464 + vertex -646.676 112.738 307.764 + endloop + endfacet + facet normal -0.273031 -0.954183 -0.122427 + outer loop + vertex -650.338 113.554 309.534 + vertex -656.99 115.42 309.823 + vertex -653.841 114.693 308.464 + endloop + endfacet + facet normal -0.257402 -0.965097 0.0482882 + outer loop + vertex -611.449 103.942 306.743 + vertex -613.649 104.484 305.838 + vertex -612.479 104.188 306.16 + endloop + endfacet + facet normal -0.237429 -0.971242 0.0177939 + outer loop + vertex -611.921 104.082 307.376 + vertex -614.699 104.763 307.506 + vertex -613.626 104.482 306.443 + endloop + endfacet + facet normal -0.235775 -0.970541 0.0496023 + outer loop + vertex -613.072 104.416 308.438 + vertex -614.699 104.763 307.506 + vertex -611.921 104.082 307.376 + endloop + endfacet + facet normal -0.23356 -0.971279 0.0454622 + outer loop + vertex -613.072 104.416 308.438 + vertex -617.444 105.497 309.083 + vertex -614.699 104.763 307.506 + endloop + endfacet + facet normal -0.23244 -0.971451 0.0474906 + outer loop + vertex -617.444 105.497 309.083 + vertex -619.682 105.97 307.803 + vertex -614.699 104.763 307.506 + endloop + endfacet + facet normal -0.229295 -0.972467 0.0416164 + outer loop + vertex -617.444 105.497 309.083 + vertex -623.421 106.937 309.787 + vertex -619.682 105.97 307.803 + endloop + endfacet + facet normal -0.229894 -0.972375 0.0404435 + outer loop + vertex -623.421 106.937 309.787 + vertex -626.498 107.599 308.224 + vertex -619.682 105.97 307.803 + endloop + endfacet + facet normal -0.22767 -0.973081 0.0357666 + outer loop + vertex -623.421 106.937 309.787 + vertex -630.849 108.696 310.367 + vertex -626.498 107.599 308.224 + endloop + endfacet + facet normal -0.231493 -0.972443 0.0276748 + outer loop + vertex -630.849 108.696 310.367 + vertex -634.424 109.499 308.691 + vertex -626.498 107.599 308.224 + endloop + endfacet + facet normal -0.231162 -0.972543 0.0269202 + outer loop + vertex -630.849 108.696 310.367 + vertex -638.955 110.633 310.733 + vertex -634.424 109.499 308.691 + endloop + endfacet + facet normal -0.239823 -0.970793 0.00674059 + outer loop + vertex -638.955 110.633 310.733 + vertex -642.612 111.525 309.144 + vertex -634.424 109.499 308.691 + endloop + endfacet + facet normal -0.241404 -0.970366 0.0106205 + outer loop + vertex -638.955 110.633 310.733 + vertex -646.944 112.622 310.887 + vertex -642.612 111.525 309.144 + endloop + endfacet + facet normal -0.255099 -0.966571 -0.0258099 + outer loop + vertex -646.944 112.622 310.887 + vertex -650.338 113.554 309.534 + vertex -642.612 111.525 309.144 + endloop + endfacet + facet normal -0.257136 -0.96616 -0.0204128 + outer loop + vertex -646.944 112.622 310.887 + vertex -654.117 114.531 310.879 + vertex -650.338 113.554 309.534 + endloop + endfacet + facet normal -0.226286 -0.969701 0.0920604 + outer loop + vertex -616.585 105.389 310.055 + vertex -617.444 105.497 309.083 + vertex -613.072 104.416 308.438 + endloop + endfacet + facet normal -0.229028 -0.969609 0.0860497 + outer loop + vertex -616.585 105.389 310.055 + vertex -613.072 104.416 308.438 + vertex -613.807 104.666 309.299 + endloop + endfacet + facet normal -0.222129 -0.968729 0.110557 + outer loop + vertex -613.807 104.666 309.299 + vertex -615.245 105.061 309.874 + vertex -616.585 105.389 310.055 + endloop + endfacet + facet normal -0.220904 -0.968077 0.118441 + outer loop + vertex -615.245 105.061 309.874 + vertex -616.174 105.321 310.263 + vertex -616.585 105.389 310.055 + endloop + endfacet + facet normal -0.222328 -0.967372 0.121494 + outer loop + vertex -616.174 105.321 310.263 + vertex -618.367 105.937 311.154 + vertex -616.585 105.389 310.055 + endloop + endfacet + facet normal -0.222678 -0.967364 0.120923 + outer loop + vertex -621.458 106.76 312.047 + vertex -616.585 105.389 310.055 + vertex -618.367 105.937 311.154 + endloop + endfacet + facet normal -0.223882 -0.967574 0.116948 + outer loop + vertex -618.367 105.937 311.154 + vertex -620.36 106.498 311.984 + vertex -621.458 106.76 312.047 + endloop + endfacet + facet normal -0.222745 -0.966094 0.130566 + outer loop + vertex -620.36 106.498 311.984 + vertex -621.279 106.759 312.344 + vertex -621.458 106.76 312.047 + endloop + endfacet + facet normal -0.228688 -0.964213 0.134148 + outer loop + vertex -621.279 106.759 312.344 + vertex -622.874 107.211 312.875 + vertex -621.458 106.76 312.047 + endloop + endfacet + facet normal -0.232644 -0.964186 0.127367 + outer loop + vertex -626.724 108.273 313.885 + vertex -621.458 106.76 312.047 + vertex -622.874 107.211 312.875 + endloop + endfacet + facet normal -0.227253 -0.962766 0.146419 + outer loop + vertex -622.874 107.211 312.875 + vertex -624.684 107.742 313.555 + vertex -626.724 108.273 313.885 + endloop + endfacet + facet normal -0.226457 -0.962308 0.1506 + outer loop + vertex -624.684 107.742 313.555 + vertex -626.497 108.261 314.145 + vertex -626.724 108.273 313.885 + endloop + endfacet + facet normal -0.233279 -0.959702 0.156693 + outer loop + vertex -626.497 108.261 314.145 + vertex -628.672 108.892 314.774 + vertex -626.724 108.273 313.885 + endloop + endfacet + facet normal -0.144283 -0.902078 0.406741 + outer loop + vertex -628.672 108.892 314.774 + vertex -626.497 108.261 314.145 + vertex -626.95 108.428 314.356 + endloop + endfacet + facet normal -0.0783232 -0.855514 0.511821 + outer loop + vertex -626.497 108.261 314.145 + vertex -624.684 107.742 313.555 + vertex -626.95 108.428 314.356 + endloop + endfacet + facet normal 0.0170149 -0.734709 0.678169 + outer loop + vertex -621.726 106.923 312.594 + vertex -626.95 108.428 314.356 + vertex -624.684 107.742 313.555 + endloop + endfacet + facet normal -0.165968 -0.936792 0.308017 + outer loop + vertex -621.726 106.923 312.594 + vertex -626.326 108.355 314.471 + vertex -626.95 108.428 314.356 + endloop + endfacet + facet normal -0.173701 -0.915367 0.363224 + outer loop + vertex -626.326 108.355 314.471 + vertex -632.144 110.04 315.935 + vertex -626.95 108.428 314.356 + endloop + endfacet + facet normal 0.0701274 -0.573548 0.816165 + outer loop + vertex -626.95 108.428 314.356 + vertex -632.144 110.04 315.935 + vertex -630.134 109.346 315.275 + endloop + endfacet + facet normal -0.15408 -0.912776 0.378285 + outer loop + vertex -626.95 108.428 314.356 + vertex -630.134 109.346 315.275 + vertex -628.672 108.892 314.774 + endloop + endfacet + facet normal -0.190851 -0.936932 0.292806 + outer loop + vertex -630.842 109.529 315.399 + vertex -628.672 108.892 314.774 + vertex -630.134 109.346 315.275 + endloop + endfacet + facet normal -0.126272 -0.843264 0.522456 + outer loop + vertex -633.181 110.237 315.976 + vertex -630.842 109.529 315.399 + vertex -630.134 109.346 315.275 + endloop + endfacet + facet normal -0.236152 -0.949311 0.207461 + outer loop + vertex -630.842 109.529 315.399 + vertex -633.181 110.237 315.976 + vertex -632.442 109.944 315.473 + endloop + endfacet + facet normal -0.242194 -0.960309 0.138379 + outer loop + vertex -628.672 108.892 314.774 + vertex -630.842 109.529 315.399 + vertex -632.442 109.944 315.473 + endloop + endfacet + facet normal -0.146866 -0.871172 0.468497 + outer loop + vertex -630.134 109.346 315.275 + vertex -632.144 110.04 315.935 + vertex -633.181 110.237 315.976 + endloop + endfacet + facet normal -0.196399 -0.949837 0.243386 + outer loop + vertex -620.735 106.752 312.724 + vertex -626.326 108.355 314.471 + vertex -621.726 106.923 312.594 + endloop + endfacet + facet normal -0.192964 -0.959736 0.204137 + outer loop + vertex -616.424 105.433 310.599 + vertex -620.735 106.752 312.724 + vertex -621.726 106.923 312.594 + endloop + endfacet + facet normal -0.182319 -0.956041 0.229662 + outer loop + vertex -616.424 105.433 310.599 + vertex -621.726 106.923 312.594 + vertex -618.367 105.937 311.154 + endloop + endfacet + facet normal 0.0841609 -0.719638 0.68923 + outer loop + vertex -620.36 106.498 311.984 + vertex -618.367 105.937 311.154 + vertex -621.726 106.923 312.594 + endloop + endfacet + facet normal -0.218547 -0.963505 0.154579 + outer loop + vertex -615.949 105.413 311.146 + vertex -620.735 106.752 312.724 + vertex -616.424 105.433 310.599 + endloop + endfacet + facet normal -0.213163 -0.965459 0.149837 + outer loop + vertex -612.606 104.4 309.378 + vertex -615.949 105.413 311.146 + vertex -616.424 105.433 310.599 + endloop + endfacet + facet normal -0.221963 -0.967167 0.123777 + outer loop + vertex -612.606 104.4 309.378 + vertex -616.424 105.433 310.599 + vertex -613.807 104.666 309.299 + endloop + endfacet + facet normal -0.221539 -0.968676 0.112191 + outer loop + vertex -613.807 104.666 309.299 + vertex -611.846 104.134 308.576 + vertex -612.606 104.4 309.378 + endloop + endfacet + facet normal -0.213718 -0.969512 0.119883 + outer loop + vertex -611.846 104.134 308.576 + vertex -609.406 103.505 307.843 + vertex -612.606 104.4 309.378 + endloop + endfacet + facet normal -0.226413 -0.96954 0.0934275 + outer loop + vertex -609.406 103.505 307.843 + vertex -610.406 103.911 309.636 + vertex -612.606 104.4 309.378 + endloop + endfacet + facet normal -0.228676 -0.966198 0.119033 + outer loop + vertex -610.406 103.911 309.636 + vertex -612.749 104.547 310.296 + vertex -612.606 104.4 309.378 + endloop + endfacet + facet normal -0.224545 -0.965361 0.132885 + outer loop + vertex -610.406 103.911 309.636 + vertex -611.481 104.357 311.059 + vertex -612.749 104.547 310.296 + endloop + endfacet + facet normal -0.229192 -0.963089 0.141176 + outer loop + vertex -611.481 104.357 311.059 + vertex -615.105 105.364 312.045 + vertex -612.749 104.547 310.296 + endloop + endfacet + facet normal -0.219611 -0.963325 0.154193 + outer loop + vertex -612.749 104.547 310.296 + vertex -615.105 105.364 312.045 + vertex -615.949 105.413 311.146 + endloop + endfacet + facet normal -0.223946 -0.96165 0.158359 + outer loop + vertex -615.105 105.364 312.045 + vertex -619.887 106.71 313.454 + vertex -615.949 105.413 311.146 + endloop + endfacet + facet normal -0.207292 -0.960417 0.186088 + outer loop + vertex -615.949 105.413 311.146 + vertex -619.887 106.71 313.454 + vertex -620.735 106.752 312.724 + endloop + endfacet + facet normal -0.21777 -0.95559 0.198553 + outer loop + vertex -619.887 106.71 313.454 + vertex -625.46 108.308 315.031 + vertex -620.735 106.752 312.724 + endloop + endfacet + facet normal -0.201169 -0.952119 0.230216 + outer loop + vertex -620.735 106.752 312.724 + vertex -625.46 108.308 315.031 + vertex -626.326 108.355 314.471 + endloop + endfacet + facet normal -0.220169 -0.939993 0.260652 + outer loop + vertex -625.46 108.308 315.031 + vertex -632.059 110.316 316.701 + vertex -626.326 108.355 314.471 + endloop + endfacet + facet normal -0.177816 -0.919222 0.351301 + outer loop + vertex -626.326 108.355 314.471 + vertex -632.059 110.316 316.701 + vertex -632.144 110.04 315.935 + endloop + endfacet + facet normal -0.211278 -0.911714 0.352334 + outer loop + vertex -632.144 110.04 315.935 + vertex -632.059 110.316 316.701 + vertex -640.996 112.963 318.191 + endloop + endfacet + facet normal -0.230699 -0.964571 0.127991 + outer loop + vertex -609.375 103.813 310.75 + vertex -611.481 104.357 311.059 + vertex -610.406 103.911 309.636 + endloop + endfacet + facet normal -0.215738 -0.969811 0.113686 + outer loop + vertex -609.375 103.813 310.75 + vertex -610.406 103.911 309.636 + vertex -608.603 103.595 310.36 + endloop + endfacet + facet normal -0.199161 -0.969021 0.146056 + outer loop + vertex -608.362 103.791 311.984 + vertex -609.375 103.813 310.75 + vertex -608.603 103.595 310.36 + endloop + endfacet + facet normal -0.146213 -0.979374 0.139454 + outer loop + vertex -608.603 103.595 310.36 + vertex -607.529 103.813 313.015 + vertex -608.362 103.791 311.984 + endloop + endfacet + facet normal -0.224639 -0.960002 0.167135 + outer loop + vertex -608.362 103.791 311.984 + vertex -610.076 104.296 312.582 + vertex -609.375 103.813 310.75 + endloop + endfacet + facet normal -0.20744 -0.954976 0.212107 + outer loop + vertex -610.076 104.296 312.582 + vertex -608.362 103.791 311.984 + vertex -608.525 104.485 314.952 + endloop + endfacet + facet normal -0.215494 -0.952055 0.217147 + outer loop + vertex -608.525 104.485 314.952 + vertex -612.004 105.398 315.501 + vertex -610.076 104.296 312.582 + endloop + endfacet + facet normal -0.212863 -0.952234 0.218953 + outer loop + vertex -610.076 104.296 312.582 + vertex -612.004 105.398 315.501 + vertex -613.69 105.301 313.443 + endloop + endfacet + facet normal -0.224051 -0.947556 0.2279 + outer loop + vertex -612.004 105.398 315.501 + vertex -616.959 106.818 316.534 + vertex -613.69 105.301 313.443 + endloop + endfacet + facet normal -0.206768 -0.946985 0.245898 + outer loop + vertex -613.69 105.301 313.443 + vertex -616.959 106.818 316.534 + vertex -618.691 106.728 314.73 + endloop + endfacet + facet normal -0.224173 -0.938619 0.262185 + outer loop + vertex -616.959 106.818 316.534 + vertex -623.303 108.731 317.958 + vertex -618.691 106.728 314.73 + endloop + endfacet + facet normal -0.19683 -0.933938 0.298357 + outer loop + vertex -618.691 106.728 314.73 + vertex -623.303 108.731 317.958 + vertex -624.525 108.416 316.167 + endloop + endfacet + facet normal -0.221919 -0.923261 0.313593 + outer loop + vertex -623.303 108.731 317.958 + vertex -630.472 110.86 319.154 + vertex -624.525 108.416 316.167 + endloop + endfacet + facet normal -0.193411 -0.912175 0.361287 + outer loop + vertex -624.525 108.416 316.167 + vertex -630.472 110.86 319.154 + vertex -630.046 110.028 317.281 + endloop + endfacet + facet normal -0.230624 -0.907611 0.350791 + outer loop + vertex -630.046 110.028 317.281 + vertex -630.472 110.86 319.154 + vertex -638.263 113.055 319.709 + endloop + endfacet + facet normal -0.230932 -0.90783 0.350022 + outer loop + vertex -630.046 110.028 317.281 + vertex -638.263 113.055 319.709 + vertex -632.059 110.316 316.701 + endloop + endfacet + facet normal -0.214411 -0.936122 0.278753 + outer loop + vertex -625.46 108.308 315.031 + vertex -630.046 110.028 317.281 + vertex -632.059 110.316 316.701 + endloop + endfacet + facet normal -0.219259 -0.937569 0.26998 + outer loop + vertex -624.525 108.416 316.167 + vertex -630.046 110.028 317.281 + vertex -625.46 108.308 315.031 + endloop + endfacet + facet normal -0.199309 -0.946337 0.254405 + outer loop + vertex -619.887 106.71 313.454 + vertex -624.525 108.416 316.167 + vertex -625.46 108.308 315.031 + endloop + endfacet + facet normal -0.220803 -0.950165 0.220075 + outer loop + vertex -618.691 106.728 314.73 + vertex -624.525 108.416 316.167 + vertex -619.887 106.71 313.454 + endloop + endfacet + facet normal -0.20772 -0.955842 0.20789 + outer loop + vertex -615.105 105.364 312.045 + vertex -618.691 106.728 314.73 + vertex -619.887 106.71 313.454 + endloop + endfacet + facet normal -0.225199 -0.9566 0.184936 + outer loop + vertex -613.69 105.301 313.443 + vertex -618.691 106.728 314.73 + vertex -615.105 105.364 312.045 + endloop + endfacet + facet normal -0.218259 -0.959561 0.177781 + outer loop + vertex -611.481 104.357 311.059 + vertex -613.69 105.301 313.443 + vertex -615.105 105.364 312.045 + endloop + endfacet + facet normal -0.226421 -0.959075 0.170026 + outer loop + vertex -610.076 104.296 312.582 + vertex -613.69 105.301 313.443 + vertex -611.481 104.357 311.059 + endloop + endfacet + facet normal -0.233634 -0.94951 0.209396 + outer loop + vertex -607.529 103.813 313.015 + vertex -608.525 104.485 314.952 + vertex -608.362 103.791 311.984 + endloop + endfacet + facet normal -0.223745 -0.960144 0.167515 + outer loop + vertex -609.375 103.813 310.75 + vertex -610.076 104.296 312.582 + vertex -611.481 104.357 311.059 + endloop + endfacet + facet normal -0.211541 -0.972003 0.102279 + outer loop + vertex -609.406 103.505 307.843 + vertex -608.603 103.595 310.36 + vertex -610.406 103.911 309.636 + endloop + endfacet + facet normal -0.23074 -0.970884 0.0643723 + outer loop + vertex -609.406 103.505 307.843 + vertex -611.846 104.134 308.576 + vertex -613.072 104.416 308.438 + endloop + endfacet + facet normal -0.229719 -0.965975 0.118835 + outer loop + vertex -612.749 104.547 310.296 + vertex -615.949 105.413 311.146 + vertex -612.606 104.4 309.378 + endloop + endfacet + facet normal -0.160857 -0.938863 0.304404 + outer loop + vertex -624.684 107.742 313.555 + vertex -622.874 107.211 312.875 + vertex -621.726 106.923 312.594 + endloop + endfacet + facet normal -0.147924 -0.926855 0.345048 + outer loop + vertex -622.874 107.211 312.875 + vertex -621.279 106.759 312.344 + vertex -621.726 106.923 312.594 + endloop + endfacet + facet normal -0.0768638 -0.89067 0.448105 + outer loop + vertex -621.279 106.759 312.344 + vertex -620.36 106.498 311.984 + vertex -621.726 106.923 312.594 + endloop + endfacet + facet normal -0.215507 -0.9667 0.138012 + outer loop + vertex -621.458 106.76 312.047 + vertex -621.777 106.686 311.032 + vertex -616.585 105.389 310.055 + endloop + endfacet + facet normal -0.220289 -0.965419 0.13942 + outer loop + vertex -621.458 106.76 312.047 + vertex -627.024 108.17 313.014 + vertex -621.777 106.686 311.032 + endloop + endfacet + facet normal -0.213672 -0.964348 0.156133 + outer loop + vertex -627.024 108.17 313.014 + vertex -628.336 108.273 311.854 + vertex -621.777 106.686 311.032 + endloop + endfacet + facet normal -0.21886 -0.962181 0.162196 + outer loop + vertex -627.024 108.17 313.014 + vertex -633.837 109.839 313.725 + vertex -628.336 108.273 311.854 + endloop + endfacet + facet normal -0.217919 -0.961957 0.164775 + outer loop + vertex -633.837 109.839 313.725 + vertex -635.953 110.081 312.337 + vertex -628.336 108.273 311.854 + endloop + endfacet + facet normal -0.224356 -0.958635 0.175169 + outer loop + vertex -633.837 109.839 313.725 + vertex -641.41 111.651 313.939 + vertex -635.953 110.081 312.337 + endloop + endfacet + facet normal -0.228563 -0.959937 0.162111 + outer loop + vertex -641.41 111.651 313.939 + vertex -643.907 111.989 312.419 + vertex -635.953 110.081 312.337 + endloop + endfacet + facet normal -0.234305 -0.956782 0.172247 + outer loop + vertex -641.41 111.651 313.939 + vertex -648.858 113.428 313.681 + vertex -643.907 111.989 312.419 + endloop + endfacet + facet normal -0.243282 -0.959741 0.140399 + outer loop + vertex -648.858 113.428 313.681 + vertex -651.362 113.846 312.202 + vertex -643.907 111.989 312.419 + endloop + endfacet + facet normal -0.246824 -0.957857 0.146928 + outer loop + vertex -648.858 113.428 313.681 + vertex -655.24 114.985 313.109 + vertex -651.362 113.846 312.202 + endloop + endfacet + facet normal -0.210576 -0.959567 0.186786 + outer loop + vertex -626.724 108.273 313.885 + vertex -627.024 108.17 313.014 + vertex -621.458 106.76 312.047 + endloop + endfacet + facet normal -0.220682 -0.956676 0.189921 + outer loop + vertex -626.724 108.273 313.885 + vertex -632.71 109.826 314.748 + vertex -627.024 108.17 313.014 + endloop + endfacet + facet normal -0.210584 -0.952679 0.21922 + outer loop + vertex -632.71 109.826 314.748 + vertex -633.837 109.839 313.725 + vertex -627.024 108.17 313.014 + endloop + endfacet + facet normal -0.220541 -0.947813 0.230244 + outer loop + vertex -632.71 109.826 314.748 + vertex -639.594 111.541 315.217 + vertex -633.837 109.839 313.725 + endloop + endfacet + facet normal -0.220115 -0.947577 0.23162 + outer loop + vertex -639.594 111.541 315.217 + vertex -641.41 111.651 313.939 + vertex -633.837 109.839 313.725 + endloop + endfacet + facet normal -0.228539 -0.942455 0.244024 + outer loop + vertex -639.594 111.541 315.217 + vertex -646.728 113.249 315.13 + vertex -641.41 111.651 313.939 + endloop + endfacet + facet normal -0.233524 -0.945694 0.226118 + outer loop + vertex -646.728 113.249 315.13 + vertex -648.858 113.428 313.681 + vertex -641.41 111.651 313.939 + endloop + endfacet + facet normal -0.239043 -0.942229 0.234657 + outer loop + vertex -646.728 113.249 315.13 + vertex -653.087 114.719 314.558 + vertex -648.858 113.428 313.681 + endloop + endfacet + facet normal -0.24894 -0.948461 0.196087 + outer loop + vertex -653.087 114.719 314.558 + vertex -655.24 114.985 313.109 + vertex -648.858 113.428 313.681 + endloop + endfacet + facet normal -0.246604 -0.949832 0.192366 + outer loop + vertex -653.087 114.719 314.558 + vertex -657.823 115.784 313.742 + vertex -655.24 114.985 313.109 + endloop + endfacet + facet normal -0.251944 -0.937716 0.239194 + outer loop + vertex -655.906 115.643 315.21 + vertex -657.823 115.784 313.742 + vertex -653.087 114.719 314.558 + endloop + endfacet + facet normal -0.239174 -0.945309 0.22178 + outer loop + vertex -655.906 115.643 315.21 + vertex -658.799 116.166 314.319 + vertex -657.823 115.784 313.742 + endloop + endfacet + facet normal -0.253174 -0.926523 0.278311 + outer loop + vertex -657.068 116.145 315.825 + vertex -658.799 116.166 314.319 + vertex -655.906 115.643 315.21 + endloop + endfacet + facet normal -0.240075 -0.930989 0.274996 + outer loop + vertex -651.209 114.657 315.985 + vertex -653.087 114.719 314.558 + vertex -646.728 113.249 315.13 + endloop + endfacet + facet normal -0.234227 -0.925714 0.296971 + outer loop + vertex -645.105 113.229 316.349 + vertex -651.209 114.657 315.985 + vertex -646.728 113.249 315.13 + endloop + endfacet + facet normal -0.226318 -0.931012 0.286351 + outer loop + vertex -645.105 113.229 316.349 + vertex -646.728 113.249 315.13 + vertex -639.594 111.541 315.217 + endloop + endfacet + facet normal -0.226269 -0.93097 0.286524 + outer loop + vertex -638.547 111.573 316.146 + vertex -645.105 113.229 316.349 + vertex -639.594 111.541 315.217 + endloop + endfacet + facet normal -0.214965 -0.937401 0.273988 + outer loop + vertex -638.547 111.573 316.146 + vertex -639.594 111.541 315.217 + vertex -632.71 109.826 314.748 + endloop + endfacet + facet normal -0.22594 -0.944776 0.237382 + outer loop + vertex -632.442 109.944 315.473 + vertex -638.547 111.573 316.146 + vertex -632.71 109.826 314.748 + endloop + endfacet + facet normal -0.218978 -0.935365 0.277741 + outer loop + vertex -638.267 111.705 316.814 + vertex -638.547 111.573 316.146 + vertex -632.442 109.944 315.473 + endloop + endfacet + facet normal -0.232701 -0.930601 0.282544 + outer loop + vertex -638.267 111.705 316.814 + vertex -644.144 113.305 317.244 + vertex -638.547 111.573 316.146 + endloop + endfacet + facet normal -0.228169 -0.922052 0.312665 + outer loop + vertex -644.004 113.509 317.946 + vertex -644.144 113.305 317.244 + vertex -638.267 111.705 316.814 + endloop + endfacet + facet normal -0.242253 -0.917903 0.314273 + outer loop + vertex -644.004 113.509 317.946 + vertex -649.012 114.883 318.1 + vertex -644.144 113.305 317.244 + endloop + endfacet + facet normal -0.231308 -0.905985 0.354525 + outer loop + vertex -649.012 114.883 318.1 + vertex -649.763 114.722 317.198 + vertex -644.144 113.305 317.244 + endloop + endfacet + facet normal -0.233391 -0.915074 0.328888 + outer loop + vertex -644.144 113.305 317.244 + vertex -649.763 114.722 317.198 + vertex -645.105 113.229 316.349 + endloop + endfacet + facet normal -0.238538 -0.902011 0.359827 + outer loop + vertex -649.012 114.883 318.1 + vertex -652.999 115.847 317.874 + vertex -649.763 114.722 317.198 + endloop + endfacet + facet normal -0.238994 -0.902461 0.358392 + outer loop + vertex -652.999 115.847 317.874 + vertex -654.231 115.689 316.654 + vertex -649.763 114.722 317.198 + endloop + endfacet + facet normal -0.238052 -0.912368 0.333041 + outer loop + vertex -649.763 114.722 317.198 + vertex -654.231 115.689 316.654 + vertex -651.209 114.657 315.985 + endloop + endfacet + facet normal -0.24439 -0.917824 0.312846 + outer loop + vertex -654.231 115.689 316.654 + vertex -655.906 115.643 315.21 + vertex -651.209 114.657 315.985 + endloop + endfacet + facet normal -0.237335 -0.922368 0.30481 + outer loop + vertex -654.231 115.689 316.654 + vertex -657.068 116.145 315.825 + vertex -655.906 115.643 315.21 + endloop + endfacet + facet normal -0.245905 -0.906654 0.342795 + outer loop + vertex -655.755 116.334 317.265 + vertex -657.068 116.145 315.825 + vertex -654.231 115.689 316.654 + endloop + endfacet + facet normal -0.238316 -0.90289 0.357763 + outer loop + vertex -652.999 115.847 317.874 + vertex -655.755 116.334 317.265 + vertex -654.231 115.689 316.654 + endloop + endfacet + facet normal -0.241891 -0.891507 0.38302 + outer loop + vertex -654.761 116.583 318.474 + vertex -655.755 116.334 317.265 + vertex -652.999 115.847 317.874 + endloop + endfacet + facet normal -0.242291 -0.891766 0.382163 + outer loop + vertex -652.483 116.079 318.74 + vertex -654.761 116.583 318.474 + vertex -652.999 115.847 317.874 + endloop + endfacet + facet normal -0.242549 -0.8857 0.395861 + outer loop + vertex -654.134 116.711 319.143 + vertex -654.761 116.583 318.474 + vertex -652.483 116.079 318.74 + endloop + endfacet + facet normal -0.244201 -0.887206 0.391448 + outer loop + vertex -653.055 116.442 319.208 + vertex -654.134 116.711 319.143 + vertex -652.483 116.079 318.74 + endloop + endfacet + facet normal -0.240337 -0.886433 0.39557 + outer loop + vertex -653.055 116.442 319.208 + vertex -652.483 116.079 318.74 + vertex -649.589 115.324 318.806 + endloop + endfacet + facet normal -0.243084 -0.899879 0.362115 + outer loop + vertex -649.589 115.324 318.806 + vertex -652.483 116.079 318.74 + vertex -649.012 114.883 318.1 + endloop + endfacet + facet normal -0.243321 -0.879275 0.409476 + outer loop + vertex -654.271 116.836 319.331 + vertex -654.134 116.711 319.143 + vertex -653.055 116.442 319.208 + endloop + endfacet + facet normal 0.281711 0.936066 -0.210759 + outer loop + vertex -654.271 116.836 319.331 + vertex -653.055 116.442 319.208 + vertex -655.314 117.131 319.249 + endloop + endfacet + facet normal -0.222258 -0.764631 0.60493 + outer loop + vertex -651.889 116.173 319.295 + vertex -655.314 117.131 319.249 + vertex -653.055 116.442 319.208 + endloop + endfacet + facet normal -0.223879 -0.770827 0.596409 + outer loop + vertex -655.314 117.131 319.249 + vertex -651.889 116.173 319.295 + vertex -651.678 116.471 319.76 + endloop + endfacet + facet normal -0.196053 -0.782346 0.591184 + outer loop + vertex -651.889 116.173 319.295 + vertex -649.843 115.552 319.152 + vertex -651.678 116.471 319.76 + endloop + endfacet + facet normal -0.239238 -0.881944 0.406127 + outer loop + vertex -649.843 115.552 319.152 + vertex -651.889 116.173 319.295 + vertex -649.589 115.324 318.806 + endloop + endfacet + facet normal -0.224834 -0.881073 0.416125 + outer loop + vertex -646.442 114.453 318.663 + vertex -649.843 115.552 319.152 + vertex -649.589 115.324 318.806 + endloop + endfacet + facet normal -0.234392 -0.876767 0.419929 + outer loop + vertex -653.055 116.442 319.208 + vertex -649.589 115.324 318.806 + vertex -651.889 116.173 319.295 + endloop + endfacet + facet normal -0.279387 -0.880163 0.383739 + outer loop + vertex -654.134 116.711 319.143 + vertex -654.271 116.836 319.331 + vertex -655.314 117.131 319.249 + endloop + endfacet + facet normal -0.2713 -0.86644 0.41914 + outer loop + vertex -654.761 116.583 318.474 + vertex -654.134 116.711 319.143 + vertex -655.314 117.131 319.249 + endloop + endfacet + facet normal -0.254902 -0.86588 0.430438 + outer loop + vertex -655.314 117.131 319.249 + vertex -656.976 116.939 317.877 + vertex -654.761 116.583 318.474 + endloop + endfacet + facet normal -0.261149 -0.860582 0.437263 + outer loop + vertex -655.314 117.131 319.249 + vertex -660.091 118.408 318.909 + vertex -656.976 116.939 317.877 + endloop + endfacet + facet normal -0.272198 -0.868235 0.414821 + outer loop + vertex -656.976 116.939 317.877 + vertex -660.091 118.408 318.909 + vertex -659.487 117.509 317.424 + endloop + endfacet + facet normal -0.272171 -0.868436 0.414417 + outer loop + vertex -659.487 117.509 317.424 + vertex -657.665 116.72 316.966 + vertex -656.976 116.939 317.877 + endloop + endfacet + facet normal -0.21219 -0.901565 0.377035 + outer loop + vertex -657.328 116.444 316.497 + vertex -656.976 116.939 317.877 + vertex -657.665 116.72 316.966 + endloop + endfacet + facet normal -0.291609 -0.884354 0.364531 + outer loop + vertex -659.487 117.509 317.424 + vertex -658.764 116.723 316.093 + vertex -657.665 116.72 316.966 + endloop + endfacet + facet normal -0.269314 -0.902396 0.336379 + outer loop + vertex -657.665 116.72 316.966 + vertex -658.764 116.723 316.093 + vertex -657.328 116.444 316.497 + endloop + endfacet + facet normal -0.293915 -0.884154 0.36316 + outer loop + vertex -661.982 117.87 316.283 + vertex -658.764 116.723 316.093 + vertex -659.487 117.509 317.424 + endloop + endfacet + facet normal -0.296744 -0.8801 0.370631 + outer loop + vertex -661.982 117.87 316.283 + vertex -659.487 117.509 317.424 + vertex -665.018 119.758 318.335 + endloop + endfacet + facet normal -0.301969 -0.881146 0.363863 + outer loop + vertex -665.018 119.758 318.335 + vertex -668.374 120.256 316.757 + vertex -661.982 117.87 316.283 + endloop + endfacet + facet normal -0.306979 -0.873958 0.376778 + outer loop + vertex -674.652 123.475 319.109 + vertex -668.374 120.256 316.757 + vertex -665.018 119.758 318.335 + endloop + endfacet + facet normal -0.307823 -0.875333 0.372878 + outer loop + vertex -674.652 123.475 319.109 + vertex -665.018 119.758 318.335 + vertex -669.7 122.018 319.775 + endloop + endfacet + facet normal -0.307908 -0.8626 0.401389 + outer loop + vertex -669.7 122.018 319.775 + vertex -674.62 124.036 320.338 + vertex -674.652 123.475 319.109 + endloop + endfacet + facet normal -0.308428 -0.862442 0.40133 + outer loop + vertex -674.62 124.036 320.338 + vertex -677.67 125.102 320.285 + vertex -674.652 123.475 319.109 + endloop + endfacet + facet normal -0.32378 -0.869854 0.372184 + outer loop + vertex -677.67 125.102 320.285 + vertex -680.882 126.262 320.202 + vertex -674.652 123.475 319.109 + endloop + endfacet + facet normal -0.324853 -0.870911 0.368761 + outer loop + vertex -685.858 127.779 319.401 + vertex -674.652 123.475 319.109 + vertex -680.882 126.262 320.202 + endloop + endfacet + facet normal -0.325775 -0.849407 0.415186 + outer loop + vertex -680.882 126.262 320.202 + vertex -685.298 128.139 320.576 + vertex -685.858 127.779 319.401 + endloop + endfacet + facet normal -0.322311 -0.851255 0.414102 + outer loop + vertex -685.298 128.139 320.576 + vertex -687.73 129.026 320.507 + vertex -685.858 127.779 319.401 + endloop + endfacet + facet normal -0.328475 -0.852985 0.405612 + outer loop + vertex -687.73 129.026 320.507 + vertex -688.617 129.352 320.474 + vertex -685.858 127.779 319.401 + endloop + endfacet + facet normal -0.338666 -0.857843 0.386536 + outer loop + vertex -688.617 129.352 320.474 + vertex -689.692 129.73 320.371 + vertex -685.858 127.779 319.401 + endloop + endfacet + facet normal -0.342668 -0.860716 0.376492 + outer loop + vertex -689.692 129.73 320.371 + vertex -693.286 130.99 319.979 + vertex -685.858 127.779 319.401 + endloop + endfacet + facet normal -0.339047 -0.855152 0.392125 + outer loop + vertex -693.286 130.99 319.979 + vertex -694.287 130.283 317.572 + vertex -685.858 127.779 319.401 + endloop + endfacet + facet normal -0.339811 -0.849767 0.403019 + outer loop + vertex -685.937 126.636 316.925 + vertex -685.858 127.779 319.401 + vertex -694.287 130.283 317.572 + endloop + endfacet + facet normal -0.313915 -0.858221 0.406095 + outer loop + vertex -685.937 126.636 316.925 + vertex -677.399 123.608 317.125 + vertex -685.858 127.779 319.401 + endloop + endfacet + facet normal -0.341702 -0.853774 0.392824 + outer loop + vertex -693.286 130.99 319.979 + vertex -698.726 132.908 319.418 + vertex -694.287 130.283 317.572 + endloop + endfacet + facet normal -0.354039 -0.858797 0.370304 + outer loop + vertex -694.287 130.283 317.572 + vertex -698.726 132.908 319.418 + vertex -702 133.564 317.809 + endloop + endfacet + facet normal -0.358115 -0.852293 0.381248 + outer loop + vertex -698.726 132.908 319.418 + vertex -704.544 135.485 319.714 + vertex -702 133.564 317.809 + endloop + endfacet + facet normal -0.363868 -0.852962 0.374241 + outer loop + vertex -708.402 136.356 317.948 + vertex -702 133.564 317.809 + vertex -704.544 135.485 319.714 + endloop + endfacet + facet normal -0.363008 -0.854473 0.371619 + outer loop + vertex -704.544 135.485 319.714 + vertex -710.105 137.823 319.657 + vertex -708.402 136.356 317.948 + endloop + endfacet + facet normal -0.37338 -0.854446 0.361261 + outer loop + vertex -715.785 139.734 318.306 + vertex -708.402 136.356 317.948 + vertex -710.105 137.823 319.657 + endloop + endfacet + facet normal -0.374329 -0.848969 0.373 + outer loop + vertex -710.105 137.823 319.657 + vertex -714.585 140.037 320.201 + vertex -715.785 139.734 318.306 + endloop + endfacet + facet normal -0.370935 -0.851239 0.371214 + outer loop + vertex -714.585 140.037 320.201 + vertex -719.456 141.98 319.788 + vertex -715.785 139.734 318.306 + endloop + endfacet + facet normal -0.381062 -0.854993 0.351822 + outer loop + vertex -724.924 143.795 318.277 + vertex -715.785 139.734 318.306 + vertex -719.456 141.98 319.788 + endloop + endfacet + facet normal -0.38289 -0.847663 0.367235 + outer loop + vertex -719.456 141.98 319.788 + vertex -724.593 144.458 320.151 + vertex -724.924 143.795 318.277 + endloop + endfacet + facet normal -0.381169 -0.84845 0.367209 + outer loop + vertex -724.593 144.458 320.151 + vertex -729.68 146.509 319.61 + vertex -724.924 143.795 318.277 + endloop + endfacet + facet normal -0.392522 -0.854764 0.339567 + outer loop + vertex -733.87 147.772 317.947 + vertex -724.924 143.795 318.277 + vertex -729.68 146.509 319.61 + endloop + endfacet + facet normal -0.396531 -0.846069 0.356273 + outer loop + vertex -729.68 146.509 319.61 + vertex -736.304 149.684 319.779 + vertex -733.87 147.772 317.947 + endloop + endfacet + facet normal -0.402204 -0.846392 0.349073 + outer loop + vertex -742.298 151.87 318.172 + vertex -733.87 147.772 317.947 + vertex -736.304 149.684 319.779 + endloop + endfacet + facet normal -0.401364 -0.850136 0.340846 + outer loop + vertex -736.304 149.684 319.779 + vertex -741.35 152.095 319.848 + vertex -742.298 151.87 318.172 + endloop + endfacet + facet normal -0.414018 -0.841592 0.346859 + outer loop + vertex -741.35 152.095 319.848 + vertex -746.597 154.632 319.743 + vertex -742.298 151.87 318.172 + endloop + endfacet + facet normal -0.41595 -0.842297 0.342814 + outer loop + vertex -750.931 156.025 317.906 + vertex -742.298 151.87 318.172 + vertex -746.597 154.632 319.743 + endloop + endfacet + facet normal -0.417106 -0.839842 0.347402 + outer loop + vertex -746.597 154.632 319.743 + vertex -752.95 157.703 319.54 + vertex -750.931 156.025 317.906 + endloop + endfacet + facet normal -0.432365 -0.839749 0.328455 + outer loop + vertex -759.307 160.457 318.211 + vertex -750.931 156.025 317.906 + vertex -752.95 157.703 319.54 + endloop + endfacet + facet normal -0.433017 -0.829259 0.353306 + outer loop + vertex -752.95 157.703 319.54 + vertex -757.747 160.448 320.103 + vertex -759.307 160.457 318.211 + endloop + endfacet + facet normal -0.434976 -0.827539 0.354929 + outer loop + vertex -757.747 160.448 320.103 + vertex -764.133 163.719 319.902 + vertex -759.307 160.457 318.211 + endloop + endfacet + facet normal -0.444879 -0.831137 0.333608 + outer loop + vertex -768.747 165.51 318.212 + vertex -759.307 160.457 318.211 + vertex -764.133 163.719 319.902 + endloop + endfacet + facet normal -0.444326 -0.832693 0.330448 + outer loop + vertex -764.133 163.719 319.902 + vertex -768.952 166.273 319.859 + vertex -768.747 165.51 318.212 + endloop + endfacet + facet normal -0.460626 -0.825853 0.325253 + outer loop + vertex -768.952 166.273 319.859 + vertex -773.999 169.046 319.752 + vertex -768.747 165.51 318.212 + endloop + endfacet + facet normal -0.462556 -0.826641 0.320478 + outer loop + vertex -777.202 170.124 317.909 + vertex -768.747 165.51 318.212 + vertex -773.999 169.046 319.752 + endloop + endfacet + facet normal -0.464826 -0.822976 0.326569 + outer loop + vertex -773.999 169.046 319.752 + vertex -780.005 172.357 319.547 + vertex -777.202 170.124 317.909 + endloop + endfacet + facet normal -0.482857 -0.823836 0.296888 + outer loop + vertex -785.201 174.898 318.147 + vertex -777.202 170.124 317.909 + vertex -780.005 172.357 319.547 + endloop + endfacet + facet normal -0.484363 -0.814406 0.319587 + outer loop + vertex -780.005 172.357 319.547 + vertex -784.947 175.489 320.039 + vertex -785.201 174.898 318.147 + endloop + endfacet + facet normal -0.486103 -0.8134 0.319506 + outer loop + vertex -784.947 175.489 320.039 + vertex -789.614 178.09 319.56 + vertex -785.201 174.898 318.147 + endloop + endfacet + facet normal -0.503193 -0.818416 0.277474 + outer loop + vertex -793.235 179.764 317.931 + vertex -785.201 174.898 318.147 + vertex -789.614 178.09 319.56 + endloop + endfacet + facet normal -0.507195 -0.809623 0.295404 + outer loop + vertex -789.614 178.09 319.56 + vertex -795.598 181.923 319.789 + vertex -793.235 179.764 317.931 + endloop + endfacet + facet normal -0.519971 -0.807953 0.277205 + outer loop + vertex -800.954 184.838 318.24 + vertex -793.235 179.764 317.931 + vertex -795.598 181.923 319.789 + endloop + endfacet + facet normal -0.518189 -0.816207 0.255512 + outer loop + vertex -795.598 181.923 319.789 + vertex -800.169 184.857 319.893 + vertex -800.954 184.838 318.24 + endloop + endfacet + facet normal -0.532208 -0.805043 0.262029 + outer loop + vertex -800.169 184.857 319.893 + vertex -804.757 187.881 319.866 + vertex -800.954 184.838 318.24 + endloop + endfacet + facet normal -0.541634 -0.805421 0.240684 + outer loop + vertex -809.33 190.462 318.212 + vertex -800.954 184.838 318.24 + vertex -804.757 187.881 319.866 + endloop + endfacet + facet normal -0.539623 -0.810804 0.226724 + outer loop + vertex -804.757 187.881 319.866 + vertex -809.16 190.808 319.855 + vertex -809.33 190.462 318.212 + endloop + endfacet + facet normal -0.558754 -0.797948 0.225995 + outer loop + vertex -809.16 190.808 319.855 + vertex -813.847 194.051 319.715 + vertex -809.33 190.462 318.212 + endloop + endfacet + facet normal -0.563342 -0.798289 0.213028 + outer loop + vertex -817.129 195.874 317.867 + vertex -809.33 190.462 318.212 + vertex -813.847 194.051 319.715 + endloop + endfacet + facet normal -0.564741 -0.796024 0.217745 + outer loop + vertex -813.847 194.051 319.715 + vertex -819.526 198.018 319.489 + vertex -817.129 195.874 317.867 + endloop + endfacet + facet normal -0.588204 -0.789635 0.174625 + outer loop + vertex -824.714 201.575 318.1 + vertex -817.129 195.874 317.867 + vertex -819.526 198.018 319.489 + endloop + endfacet + facet normal -0.590627 -0.778653 0.211802 + outer loop + vertex -819.526 198.018 319.489 + vertex -824.139 201.669 320.045 + vertex -824.714 201.575 318.1 + endloop + endfacet + facet normal -0.597633 -0.772796 0.21359 + outer loop + vertex -824.139 201.669 320.045 + vertex -830.047 206.159 319.763 + vertex -824.714 201.575 318.1 + endloop + endfacet + facet normal -0.608317 -0.773022 0.179968 + outer loop + vertex -832.514 207.652 317.835 + vertex -824.714 201.575 318.1 + vertex -830.047 206.159 319.763 + endloop + endfacet + facet normal -0.610491 -0.770113 0.185002 + outer loop + vertex -830.047 206.159 319.763 + vertex -835.591 210.495 319.517 + vertex -832.514 207.652 317.835 + endloop + endfacet + facet normal -0.635039 -0.762054 0.126485 + outer loop + vertex -840.113 214.035 318.139 + vertex -832.514 207.652 317.835 + vertex -835.591 210.495 319.517 + endloop + endfacet + facet normal -0.637926 -0.754004 0.156618 + outer loop + vertex -835.591 210.495 319.517 + vertex -840.264 214.566 320.083 + vertex -840.113 214.035 318.139 + endloop + endfacet + facet normal -0.638613 -0.753463 0.156417 + outer loop + vertex -840.264 214.566 320.083 + vertex -844.423 218.018 319.729 + vertex -840.113 214.035 318.139 + endloop + endfacet + facet normal -0.655648 -0.748654 0.0981923 + outer loop + vertex -848.094 221.033 318.212 + vertex -840.113 214.035 318.139 + vertex -844.423 218.018 319.729 + endloop + endfacet + facet normal -0.661454 -0.738037 0.133342 + outer loop + vertex -844.423 218.018 319.729 + vertex -848.628 221.88 320.249 + vertex -848.094 221.033 318.212 + endloop + endfacet + facet normal -0.661168 -0.738263 0.133511 + outer loop + vertex -848.628 221.88 320.249 + vertex -852.245 225.039 319.801 + vertex -848.094 221.033 318.212 + endloop + endfacet + facet normal -0.670551 -0.73499 0.100754 + outer loop + vertex -854.281 226.642 317.949 + vertex -848.094 221.033 318.212 + vertex -852.245 225.039 319.801 + endloop + endfacet + facet normal -0.689454 -0.710043 0.143149 + outer loop + vertex -852.245 225.039 319.801 + vertex -856.217 228.996 320.299 + vertex -854.281 226.642 317.949 + endloop + endfacet + facet normal -0.671284 -0.721528 0.169629 + outer loop + vertex -856.217 228.996 320.299 + vertex -858.286 230.364 317.933 + vertex -854.281 226.642 317.949 + endloop + endfacet + facet normal -0.677697 -0.712916 0.180218 + outer loop + vertex -856.217 228.996 320.299 + vertex -860.272 232.729 319.817 + vertex -858.286 230.364 317.933 + endloop + endfacet + facet normal -0.664689 -0.719308 0.201952 + outer loop + vertex -859.986 231.889 317.77 + vertex -858.286 230.364 317.933 + vertex -860.272 232.729 319.817 + endloop + endfacet + facet normal -0.661204 -0.69821 0.274432 + outer loop + vertex -856.217 228.996 320.299 + vertex -852.245 225.039 319.801 + vertex -852.074 225.556 321.53 + endloop + endfacet + facet normal -0.651345 -0.706794 0.276029 + outer loop + vertex -852.245 225.039 319.801 + vertex -848.628 221.88 320.249 + vertex -852.074 225.556 321.53 + endloop + endfacet + facet normal -0.627861 -0.722497 0.289463 + outer loop + vertex -848.628 221.88 320.249 + vertex -844.423 218.018 319.729 + vertex -845.391 219.49 321.303 + endloop + endfacet + facet normal -0.596736 -0.730958 0.331067 + outer loop + vertex -840.264 214.566 320.083 + vertex -835.591 210.495 319.517 + vertex -837.023 212.412 321.168 + endloop + endfacet + facet normal -0.577607 -0.737952 0.348995 + outer loop + vertex -830.047 206.159 319.763 + vertex -824.139 201.669 320.045 + vertex -828.781 205.912 321.335 + endloop + endfacet + facet normal -0.542398 -0.755471 0.367517 + outer loop + vertex -819.526 198.018 319.489 + vertex -813.847 194.051 319.715 + vertex -819.88 199.05 321.088 + endloop + endfacet + facet normal -0.50374 -0.756177 0.417664 + outer loop + vertex -809.16 190.808 319.855 + vertex -804.757 187.881 319.866 + vertex -810.342 192.275 321.084 + endloop + endfacet + facet normal -0.480694 -0.764012 0.430371 + outer loop + vertex -800.169 184.857 319.893 + vertex -795.598 181.923 319.789 + vertex -801.016 186.077 321.113 + endloop + endfacet + facet normal -0.480355 -0.774625 0.411358 + outer loop + vertex -795.598 181.923 319.789 + vertex -789.614 178.09 319.56 + vertex -791.171 179.878 321.108 + endloop + endfacet + facet normal -0.474683 -0.774899 0.417382 + outer loop + vertex -789.614 178.09 319.56 + vertex -784.947 175.489 320.039 + vertex -791.171 179.878 321.108 + endloop + endfacet + facet normal -0.449659 -0.778288 0.438263 + outer loop + vertex -784.947 175.489 320.039 + vertex -780.005 172.357 319.547 + vertex -781.082 173.851 321.095 + endloop + endfacet + facet normal -0.444467 -0.778895 0.44246 + outer loop + vertex -780.005 172.357 319.547 + vertex -773.999 169.046 319.752 + vertex -781.082 173.851 321.095 + endloop + endfacet + facet normal -0.438062 -0.780072 0.446754 + outer loop + vertex -773.999 169.046 319.752 + vertex -768.952 166.273 319.859 + vertex -771.016 168.154 321.12 + endloop + endfacet + facet normal -0.418302 -0.78915 0.449739 + outer loop + vertex -764.133 163.719 319.902 + vertex -757.747 160.448 320.103 + vertex -762.25 163.53 321.323 + endloop + endfacet + facet normal -0.400459 -0.79869 0.44914 + outer loop + vertex -752.95 157.703 319.54 + vertex -746.597 154.632 319.743 + vertex -752.782 158.498 321.103 + endloop + endfacet + facet normal -0.373199 -0.795113 0.478035 + outer loop + vertex -741.35 152.095 319.848 + vertex -736.304 149.684 319.779 + vertex -742.2 153.248 321.103 + endloop + endfacet + facet normal -0.393363 -0.794051 0.463409 + outer loop + vertex -746.597 154.632 319.743 + vertex -741.35 152.095 319.848 + vertex -742.2 153.248 321.103 + endloop + endfacet + facet normal -0.376382 -0.809095 0.451333 + outer loop + vertex -736.304 149.684 319.779 + vertex -729.68 146.509 319.61 + vertex -731.334 148.139 321.153 + endloop + endfacet + facet normal -0.374388 -0.808926 0.453291 + outer loop + vertex -729.68 146.509 319.61 + vertex -724.593 144.458 320.151 + vertex -731.334 148.139 321.153 + endloop + endfacet + facet normal -0.359635 -0.812769 0.458333 + outer loop + vertex -724.593 144.458 320.151 + vertex -719.456 141.98 319.788 + vertex -720.69 143.354 321.257 + endloop + endfacet + facet normal -0.362771 -0.812827 0.455752 + outer loop + vertex -719.456 141.98 319.788 + vertex -714.585 140.037 320.201 + vertex -720.69 143.354 321.257 + endloop + endfacet + facet normal -0.347637 -0.816542 0.460877 + outer loop + vertex -714.585 140.037 320.201 + vertex -710.105 137.823 319.657 + vertex -710.653 138.929 321.203 + endloop + endfacet + facet normal -0.347947 -0.816492 0.460732 + outer loop + vertex -710.105 137.823 319.657 + vertex -704.544 135.485 319.714 + vertex -710.653 138.929 321.203 + endloop + endfacet + facet normal -0.341804 -0.811396 0.474138 + outer loop + vertex -700.59 134.647 321.129 + vertex -710.653 138.929 321.203 + vertex -704.544 135.485 319.714 + endloop + endfacet + facet normal -0.332207 -0.789572 0.51596 + outer loop + vertex -700.59 134.647 321.129 + vertex -709.154 139.433 322.94 + vertex -710.653 138.929 321.203 + endloop + endfacet + facet normal -0.340595 -0.782549 0.521164 + outer loop + vertex -709.154 139.433 322.94 + vertex -719.184 143.8 322.941 + vertex -710.653 138.929 321.203 + endloop + endfacet + facet normal -0.343524 -0.785432 0.514866 + outer loop + vertex -710.653 138.929 321.203 + vertex -719.184 143.8 322.941 + vertex -720.69 143.354 321.257 + endloop + endfacet + facet normal -0.349831 -0.799415 0.48842 + outer loop + vertex -710.653 138.929 321.203 + vertex -720.69 143.354 321.257 + vertex -714.585 140.037 320.201 + endloop + endfacet + facet normal -0.352008 -0.777945 0.520473 + outer loop + vertex -719.184 143.8 322.941 + vertex -729.542 148.466 322.911 + vertex -720.69 143.354 321.257 + endloop + endfacet + facet normal -0.35691 -0.782908 0.509579 + outer loop + vertex -720.69 143.354 321.257 + vertex -729.542 148.466 322.911 + vertex -731.334 148.139 321.153 + endloop + endfacet + facet normal -0.364643 -0.775095 0.516008 + outer loop + vertex -729.542 148.466 322.911 + vertex -740.102 153.403 322.865 + vertex -731.334 148.139 321.153 + endloop + endfacet + facet normal -0.368515 -0.77881 0.507594 + outer loop + vertex -731.334 148.139 321.153 + vertex -740.102 153.403 322.865 + vertex -742.2 153.248 321.103 + endloop + endfacet + facet normal -0.377439 -0.768092 0.517276 + outer loop + vertex -740.102 153.403 322.865 + vertex -750.564 158.529 322.841 + vertex -742.2 153.248 321.103 + endloop + endfacet + facet normal -0.384022 -0.773977 0.503475 + outer loop + vertex -742.2 153.248 321.103 + vertex -750.564 158.529 322.841 + vertex -752.782 158.498 321.103 + endloop + endfacet + facet normal -0.392172 -0.763107 0.513681 + outer loop + vertex -750.564 158.529 322.841 + vertex -760.626 163.711 322.858 + vertex -752.782 158.498 321.103 + endloop + endfacet + facet normal -0.395056 -0.765495 0.507886 + outer loop + vertex -752.782 158.498 321.103 + vertex -760.626 163.711 322.858 + vertex -762.25 163.53 321.323 + endloop + endfacet + facet normal -0.405583 -0.753395 0.517588 + outer loop + vertex -760.626 163.711 322.858 + vertex -770.262 168.901 322.862 + vertex -762.25 163.53 321.323 + endloop + endfacet + facet normal -0.41211 -0.75918 0.503797 + outer loop + vertex -762.25 163.53 321.323 + vertex -770.262 168.901 322.862 + vertex -771.016 168.154 321.12 + endloop + endfacet + facet normal -0.423729 -0.75157 0.505565 + outer loop + vertex -770.262 168.901 322.862 + vertex -779.881 174.311 322.842 + vertex -771.016 168.154 321.12 + endloop + endfacet + facet normal -0.429129 -0.756133 0.494076 + outer loop + vertex -771.016 168.154 321.12 + vertex -779.881 174.311 322.842 + vertex -781.082 173.851 321.095 + endloop + endfacet + facet normal -0.440601 -0.746034 0.499304 + outer loop + vertex -779.881 174.311 322.842 + vertex -789.642 180.078 322.845 + vertex -781.082 173.851 321.095 + endloop + endfacet + facet normal -0.448941 -0.752569 0.481759 + outer loop + vertex -781.082 173.851 321.095 + vertex -789.642 180.078 322.845 + vertex -791.171 179.878 321.108 + endloop + endfacet + facet normal -0.460049 -0.740357 0.490129 + outer loop + vertex -789.642 180.078 322.845 + vertex -799.287 186.067 322.839 + vertex -791.171 179.878 321.108 + endloop + endfacet + facet normal -0.470939 -0.748245 0.467275 + outer loop + vertex -791.171 179.878 321.108 + vertex -799.287 186.067 322.839 + vertex -801.016 186.077 321.113 + endloop + endfacet + facet normal -0.482384 -0.733512 0.478817 + outer loop + vertex -799.287 186.067 322.839 + vertex -808.743 192.276 322.824 + vertex -801.016 186.077 321.113 + endloop + endfacet + facet normal -0.49402 -0.741269 0.454385 + outer loop + vertex -801.016 186.077 321.113 + vertex -808.743 192.276 322.824 + vertex -810.342 192.275 321.084 + endloop + endfacet + facet normal -0.507768 -0.723931 0.467007 + outer loop + vertex -808.743 192.276 322.824 + vertex -818.154 198.889 322.843 + vertex -810.342 192.275 321.084 + endloop + endfacet + facet normal -0.519024 -0.73089 0.443185 + outer loop + vertex -810.342 192.275 321.084 + vertex -818.154 198.889 322.843 + vertex -819.88 199.05 321.088 + endloop + endfacet + facet normal -0.532286 -0.711998 0.457963 + outer loop + vertex -818.154 198.889 322.843 + vertex -827.495 205.92 322.917 + vertex -819.88 199.05 321.088 + endloop + endfacet + facet normal -0.539825 -0.716193 0.442331 + outer loop + vertex -819.88 199.05 321.088 + vertex -827.495 205.92 322.917 + vertex -828.781 205.912 321.335 + endloop + endfacet + facet normal -0.553044 -0.699249 0.452983 + outer loop + vertex -827.495 205.92 322.917 + vertex -836.371 212.956 322.943 + vertex -828.781 205.912 321.335 + endloop + endfacet + facet normal -0.56591 -0.706657 0.424714 + outer loop + vertex -828.781 205.912 321.335 + vertex -836.371 212.956 322.943 + vertex -837.023 212.412 321.168 + endloop + endfacet + facet normal -0.576618 -0.697299 0.425777 + outer loop + vertex -836.371 212.956 322.943 + vertex -844.245 219.424 322.871 + vertex -837.023 212.412 321.168 + endloop + endfacet + facet normal -0.588052 -0.702868 0.400215 + outer loop + vertex -837.023 212.412 321.168 + vertex -844.245 219.424 322.871 + vertex -845.391 219.49 321.303 + endloop + endfacet + facet normal -0.597635 -0.690341 0.407752 + outer loop + vertex -844.245 219.424 322.871 + vertex -850.279 224.624 322.831 + vertex -845.391 219.49 321.303 + endloop + endfacet + facet normal -0.621174 -0.697639 0.356991 + outer loop + vertex -845.391 219.49 321.303 + vertex -850.279 224.624 322.831 + vertex -852.074 225.556 321.53 + endloop + endfacet + facet normal -0.631127 -0.670355 0.390259 + outer loop + vertex -852.074 225.556 321.53 + vertex -850.279 224.624 322.831 + vertex -856.976 231.577 323.944 + endloop + endfacet + facet normal -0.589433 -0.680617 0.435119 + outer loop + vertex -844.245 219.424 322.871 + vertex -850.255 225.478 324.2 + vertex -850.279 224.624 322.831 + endloop + endfacet + facet normal -0.61731 -0.662496 0.424297 + outer loop + vertex -850.279 224.624 322.831 + vertex -850.255 225.478 324.2 + vertex -856.976 231.577 323.944 + endloop + endfacet + facet normal -0.582391 -0.676919 0.450112 + outer loop + vertex -844.549 220.939 324.757 + vertex -850.255 225.478 324.2 + vertex -844.245 219.424 322.871 + endloop + endfacet + facet normal -0.566456 -0.684557 0.458814 + outer loop + vertex -836.371 212.956 322.943 + vertex -844.549 220.939 324.757 + vertex -844.245 219.424 322.871 + endloop + endfacet + facet normal -0.565726 -0.684151 0.460316 + outer loop + vertex -836.283 214.238 324.955 + vertex -844.549 220.939 324.757 + vertex -836.371 212.956 322.943 + endloop + endfacet + facet normal -0.558647 -0.67477 0.482285 + outer loop + vertex -836.283 214.238 324.955 + vertex -845.255 223.377 327.35 + vertex -844.549 220.939 324.757 + endloop + endfacet + facet normal -0.577817 -0.667254 0.47 + outer loop + vertex -845.255 223.377 327.35 + vertex -852.314 228.906 326.52 + vertex -844.549 220.939 324.757 + endloop + endfacet + facet normal -0.57629 -0.666435 0.473026 + outer loop + vertex -844.549 220.939 324.757 + vertex -852.314 228.906 326.52 + vertex -850.255 225.478 324.2 + endloop + endfacet + facet normal -0.615804 -0.660624 0.429374 + outer loop + vertex -850.255 225.478 324.2 + vertex -852.314 228.906 326.52 + vertex -856.976 231.577 323.944 + endloop + endfacet + facet normal -0.615611 -0.661857 0.427748 + outer loop + vertex -858.882 236.392 328.651 + vertex -856.976 231.577 323.944 + vertex -852.314 228.906 326.52 + endloop + endfacet + facet normal -0.592088 -0.653633 0.471376 + outer loop + vertex -852.314 228.906 326.52 + vertex -853.885 232.91 330.1 + vertex -858.882 236.392 328.651 + endloop + endfacet + facet normal -0.591747 -0.652067 0.473966 + outer loop + vertex -859.325 238.525 331.033 + vertex -858.882 236.392 328.651 + vertex -853.885 232.91 330.1 + endloop + endfacet + facet normal -0.560274 -0.631817 0.535631 + outer loop + vertex -858.715 239.727 333.089 + vertex -859.325 238.525 331.033 + vertex -853.885 232.91 330.1 + endloop + endfacet + facet normal -0.572257 -0.63369 0.520538 + outer loop + vertex -853.885 232.91 330.1 + vertex -852.586 234.347 333.277 + vertex -858.715 239.727 333.089 + endloop + endfacet + facet normal -0.560474 -0.619238 0.549922 + outer loop + vertex -857.306 240.587 335.493 + vertex -858.715 239.727 333.089 + vertex -852.586 234.347 333.277 + endloop + endfacet + facet normal -0.548121 -0.615657 0.566153 + outer loop + vertex -852.586 234.347 333.277 + vertex -852.108 236.781 336.387 + vertex -857.306 240.587 335.493 + endloop + endfacet + facet normal -0.537279 -0.592948 0.599787 + outer loop + vertex -858.037 243.984 338.197 + vertex -857.306 240.587 335.493 + vertex -852.108 236.781 336.387 + endloop + endfacet + facet normal -0.530888 -0.589865 0.608456 + outer loop + vertex -852.108 236.781 336.387 + vertex -852.708 241.069 340.02 + vertex -858.037 243.984 338.197 + endloop + endfacet + facet normal -0.529028 -0.578994 0.620399 + outer loop + vertex -858.697 247.41 340.832 + vertex -858.037 243.984 338.197 + vertex -852.708 241.069 340.02 + endloop + endfacet + facet normal -0.520705 -0.572759 0.633099 + outer loop + vertex -856.927 247.711 342.559 + vertex -858.697 247.41 340.832 + vertex -852.708 241.069 340.02 + endloop + endfacet + facet normal -0.501838 -0.568093 0.652249 + outer loop + vertex -852.708 241.069 340.02 + vertex -852.053 244.87 343.835 + vertex -856.927 247.711 342.559 + endloop + endfacet + facet normal -0.494829 -0.545027 0.676824 + outer loop + vertex -857.973 251.284 344.671 + vertex -856.927 247.711 342.559 + vertex -852.053 244.87 343.835 + endloop + endfacet + facet normal -0.48171 -0.53515 0.693952 + outer loop + vertex -856.528 252.869 346.897 + vertex -857.973 251.284 344.671 + vertex -852.053 244.87 343.835 + endloop + endfacet + facet normal -0.485836 -0.536079 0.69035 + outer loop + vertex -852.053 244.87 343.835 + vertex -850.447 247.653 347.127 + vertex -856.528 252.869 346.897 + endloop + endfacet + facet normal -0.47102 -0.517758 0.71419 + outer loop + vertex -855.246 254.732 349.093 + vertex -856.528 252.869 346.897 + vertex -850.447 247.653 347.127 + endloop + endfacet + facet normal -0.442402 -0.505705 0.740637 + outer loop + vertex -850.447 247.653 347.127 + vertex -850.638 252.531 350.343 + vertex -855.246 254.732 349.093 + endloop + endfacet + facet normal -0.435924 -0.480651 0.760884 + outer loop + vertex -856.65 259.009 350.991 + vertex -855.246 254.732 349.093 + vertex -850.638 252.531 350.343 + endloop + endfacet + facet normal -0.479245 -0.482557 0.733118 + outer loop + vertex -855.246 254.732 349.093 + vertex -856.65 259.009 350.991 + vertex -860.154 260.501 349.682 + endloop + endfacet + facet normal -0.440622 -0.506139 0.741401 + outer loop + vertex -842.72 241.624 347.603 + vertex -850.638 252.531 350.343 + vertex -850.447 247.653 347.127 + endloop + endfacet + facet normal -0.434367 -0.503047 0.747174 + outer loop + vertex -842.148 245.735 350.703 + vertex -850.638 252.531 350.343 + vertex -842.72 241.624 347.603 + endloop + endfacet + facet normal -0.422981 -0.507354 0.750785 + outer loop + vertex -833.791 234.471 347.799 + vertex -842.148 245.735 350.703 + vertex -842.72 241.624 347.603 + endloop + endfacet + facet normal -0.418402 -0.505021 0.754913 + outer loop + vertex -833.237 238.632 350.89 + vertex -842.148 245.735 350.703 + vertex -833.791 234.471 347.799 + endloop + endfacet + facet normal -0.401613 -0.511018 0.759978 + outer loop + vertex -824.488 227.173 347.808 + vertex -833.237 238.632 350.89 + vertex -833.791 234.471 347.799 + endloop + endfacet + facet normal -0.404111 -0.512331 0.757767 + outer loop + vertex -823.949 231.345 350.917 + vertex -833.237 238.632 350.89 + vertex -824.488 227.173 347.808 + endloop + endfacet + facet normal -0.382863 -0.519592 0.763833 + outer loop + vertex -815.101 220.177 347.755 + vertex -823.949 231.345 350.917 + vertex -824.488 227.173 347.808 + endloop + endfacet + facet normal -0.384268 -0.520358 0.762605 + outer loop + vertex -814.578 224.36 350.872 + vertex -823.949 231.345 350.917 + vertex -815.101 220.177 347.755 + endloop + endfacet + facet normal -0.362054 -0.52754 0.768517 + outer loop + vertex -805.701 213.664 347.712 + vertex -814.578 224.36 350.872 + vertex -815.101 220.177 347.755 + endloop + endfacet + facet normal -0.364098 -0.528712 0.766744 + outer loop + vertex -805.193 217.845 350.836 + vertex -814.578 224.36 350.872 + vertex -805.701 213.664 347.712 + endloop + endfacet + facet normal -0.345769 -0.534348 0.771308 + outer loop + vertex -796.247 207.538 347.706 + vertex -805.193 217.845 350.836 + vertex -805.701 213.664 347.712 + endloop + endfacet + facet normal -0.346439 -0.534752 0.770727 + outer loop + vertex -795.747 211.72 350.833 + vertex -805.193 217.845 350.836 + vertex -796.247 207.538 347.706 + endloop + endfacet + facet normal -0.331535 -0.539143 0.774215 + outer loop + vertex -786.697 201.68 347.716 + vertex -795.747 211.72 350.833 + vertex -796.247 207.538 347.706 + endloop + endfacet + facet normal -0.329996 -0.538169 0.775549 + outer loop + vertex -786.198 205.872 350.837 + vertex -795.747 211.72 350.833 + vertex -786.697 201.68 347.716 + endloop + endfacet + facet normal -0.31747 -0.541712 0.778306 + outer loop + vertex -777.023 196.019 347.722 + vertex -786.198 205.872 350.837 + vertex -786.697 201.68 347.716 + endloop + endfacet + facet normal -0.319802 -0.543243 0.776282 + outer loop + vertex -776.532 200.197 350.848 + vertex -786.198 205.872 350.837 + vertex -777.023 196.019 347.722 + endloop + endfacet + facet normal -0.307548 -0.546615 0.778862 + outer loop + vertex -767.204 190.502 347.727 + vertex -776.532 200.197 350.848 + vertex -777.023 196.019 347.722 + endloop + endfacet + facet normal -0.305862 -0.545465 0.780331 + outer loop + vertex -766.717 194.691 350.846 + vertex -776.532 200.197 350.848 + vertex -767.204 190.502 347.727 + endloop + endfacet + facet normal -0.294329 -0.548513 0.782626 + outer loop + vertex -757.199 185.133 347.727 + vertex -766.717 194.691 350.846 + vertex -767.204 190.502 347.727 + endloop + endfacet + facet normal -0.295391 -0.549267 0.781697 + outer loop + vertex -756.721 189.319 350.849 + vertex -766.717 194.691 350.846 + vertex -757.199 185.133 347.727 + endloop + endfacet + facet normal -0.283435 -0.552324 0.783966 + outer loop + vertex -747.001 179.9 347.727 + vertex -756.721 189.319 350.849 + vertex -757.199 185.133 347.727 + endloop + endfacet + facet normal -0.283477 -0.552354 0.78393 + outer loop + vertex -746.53 184.089 350.849 + vertex -756.721 189.319 350.849 + vertex -747.001 179.9 347.727 + endloop + endfacet + facet normal -0.27223 -0.555128 0.785954 + outer loop + vertex -736.651 174.822 347.726 + vertex -746.53 184.089 350.849 + vertex -747.001 179.9 347.727 + endloop + endfacet + facet normal -0.272229 -0.555128 0.785954 + outer loop + vertex -736.186 179.013 350.847 + vertex -746.53 184.089 350.849 + vertex -736.651 174.822 347.726 + endloop + endfacet + facet normal -0.261548 -0.557671 0.787779 + outer loop + vertex -726.23 169.929 347.722 + vertex -736.186 179.013 350.847 + vertex -736.651 174.822 347.726 + endloop + endfacet + facet normal -0.261883 -0.557935 0.787481 + outer loop + vertex -725.77 174.12 350.844 + vertex -736.186 179.013 350.847 + vertex -726.23 169.929 347.722 + endloop + endfacet + facet normal -0.251889 -0.56024 0.789103 + outer loop + vertex -715.803 165.235 347.717 + vertex -725.77 174.12 350.844 + vertex -726.23 169.929 347.722 + endloop + endfacet + facet normal -0.252572 -0.560792 0.788492 + outer loop + vertex -715.347 169.423 350.842 + vertex -725.77 174.12 350.844 + vertex -715.803 165.235 347.717 + endloop + endfacet + facet normal -0.242348 -0.563082 0.790067 + outer loop + vertex -705.382 160.74 347.711 + vertex -715.347 169.423 350.842 + vertex -715.803 165.235 347.717 + endloop + endfacet + facet normal -0.242581 -0.563273 0.789859 + outer loop + vertex -704.926 164.925 350.835 + vertex -715.347 169.423 350.842 + vertex -705.382 160.74 347.711 + endloop + endfacet + facet normal -0.233561 -0.565238 0.791173 + outer loop + vertex -694.933 156.414 347.704 + vertex -704.926 164.925 350.835 + vertex -705.382 160.74 347.711 + endloop + endfacet + facet normal -0.233528 -0.565211 0.791203 + outer loop + vertex -694.475 160.596 350.827 + vertex -704.926 164.925 350.835 + vertex -694.933 156.414 347.704 + endloop + endfacet + facet normal -0.22575 -0.566864 0.792277 + outer loop + vertex -684.447 152.24 347.706 + vertex -694.475 160.596 350.827 + vertex -694.933 156.414 347.704 + endloop + endfacet + facet normal -0.225392 -0.566555 0.7926 + outer loop + vertex -683.989 156.424 350.827 + vertex -694.475 160.596 350.827 + vertex -684.447 152.24 347.706 + endloop + endfacet + facet normal -0.218927 -0.567897 0.793451 + outer loop + vertex -673.965 148.229 347.727 + vertex -683.989 156.424 350.827 + vertex -684.447 152.24 347.706 + endloop + endfacet + facet normal -0.218887 -0.567862 0.793487 + outer loop + vertex -673.514 152.418 350.85 + vertex -683.989 156.424 350.827 + vertex -673.965 148.229 347.727 + endloop + endfacet + facet normal -0.212138 -0.569226 0.794342 + outer loop + vertex -663.494 144.378 347.764 + vertex -673.514 152.418 350.85 + vertex -673.965 148.229 347.727 + endloop + endfacet + facet normal -0.212596 -0.569636 0.793925 + outer loop + vertex -663.053 148.572 350.892 + vertex -673.514 152.418 350.85 + vertex -663.494 144.378 347.764 + endloop + endfacet + facet normal -0.203578 -0.571401 0.79502 + outer loop + vertex -652.865 140.598 347.769 + vertex -663.053 148.572 350.892 + vertex -663.494 144.378 347.764 + endloop + endfacet + facet normal -0.204613 -0.572352 0.79407 + outer loop + vertex -652.415 144.782 350.901 + vertex -663.053 148.572 350.892 + vertex -652.865 140.598 347.769 + endloop + endfacet + facet normal -0.193614 -0.574458 0.795306 + outer loop + vertex -641.792 136.729 347.67 + vertex -652.415 144.782 350.901 + vertex -652.865 140.598 347.769 + endloop + endfacet + facet normal -0.196796 -0.577466 0.792341 + outer loop + vertex -641.304 140.885 350.82 + vertex -652.415 144.782 350.901 + vertex -641.792 136.729 347.67 + endloop + endfacet + facet normal -0.18648 -0.579461 0.793379 + outer loop + vertex -630.295 132.762 347.475 + vertex -641.304 140.885 350.82 + vertex -641.792 136.729 347.67 + endloop + endfacet + facet normal -0.191857 -0.584647 0.788276 + outer loop + vertex -629.79 136.924 350.685 + vertex -641.304 140.885 350.82 + vertex -630.295 132.762 347.475 + endloop + endfacet + facet normal -0.184768 -0.586024 0.788946 + outer loop + vertex -619.228 129.144 347.379 + vertex -629.79 136.924 350.685 + vertex -630.295 132.762 347.475 + endloop + endfacet + facet normal -0.18949 -0.590527 0.784456 + outer loop + vertex -618.8 133.386 350.676 + vertex -629.79 136.924 350.685 + vertex -619.228 129.144 347.379 + endloop + endfacet + facet normal -0.18857 -0.590694 0.784552 + outer loop + vertex -610.133 126.727 347.746 + vertex -618.8 133.386 350.676 + vertex -619.228 129.144 347.379 + endloop + endfacet + facet normal -0.185907 -0.588299 0.786984 + outer loop + vertex -609.932 131.037 351.015 + vertex -618.8 133.386 350.676 + vertex -610.133 126.727 347.746 + endloop + endfacet + facet normal -0.192238 -0.587373 0.786154 + outer loop + vertex -604.113 126.231 348.847 + vertex -609.932 131.037 351.015 + vertex -610.133 126.727 347.746 + endloop + endfacet + facet normal -0.175224 -0.573222 0.800446 + outer loop + vertex -604.559 130.292 351.658 + vertex -609.932 131.037 351.015 + vertex -604.113 126.231 348.847 + endloop + endfacet + facet normal -0.17844 -0.573129 0.799802 + outer loop + vertex -604.559 130.292 351.658 + vertex -604.113 126.231 348.847 + vertex -600.311 127.948 350.926 + endloop + endfacet + facet normal -0.497763 -0.496096 0.711422 + outer loop + vertex -856.528 252.869 346.897 + vertex -855.246 254.732 349.093 + vertex -860.154 260.501 349.682 + endloop + endfacet + facet normal -0.491049 -0.494904 0.716897 + outer loop + vertex -860.154 260.501 349.682 + vertex -861.365 257.315 346.653 + vertex -856.528 252.869 346.897 + endloop + endfacet + facet normal -0.509458 -0.483239 0.711993 + outer loop + vertex -860.154 260.501 349.682 + vertex -865.159 265.15 349.256 + vertex -861.365 257.315 346.653 + endloop + endfacet + facet normal -0.520875 -0.485491 0.702131 + outer loop + vertex -861.365 257.315 346.653 + vertex -865.159 265.15 349.256 + vertex -865.844 261.374 346.137 + endloop + endfacet + facet normal -0.538445 -0.476446 0.695037 + outer loop + vertex -865.159 265.15 349.256 + vertex -869.844 270.147 349.052 + vertex -865.844 261.374 346.137 + endloop + endfacet + facet normal -0.536811 -0.47618 0.696482 + outer loop + vertex -865.844 261.374 346.137 + vertex -869.844 270.147 349.052 + vertex -870.564 266.365 345.912 + endloop + endfacet + facet normal -0.556271 -0.46566 0.688275 + outer loop + vertex -869.844 270.147 349.052 + vertex -874.757 276.018 349.053 + vertex -870.564 266.365 345.912 + endloop + endfacet + facet normal -0.554811 -0.465454 0.689592 + outer loop + vertex -870.564 266.365 345.912 + vertex -874.757 276.018 349.053 + vertex -875.526 272.269 345.905 + endloop + endfacet + facet normal -0.580779 -0.450457 0.678073 + outer loop + vertex -874.757 276.018 349.053 + vertex -879.751 282.566 349.126 + vertex -875.526 272.269 345.905 + endloop + endfacet + facet normal -0.573721 -0.449607 0.684615 + outer loop + vertex -875.526 272.269 345.905 + vertex -879.751 282.566 349.126 + vertex -880.555 278.805 345.982 + endloop + endfacet + facet normal -0.607154 -0.42917 0.668713 + outer loop + vertex -879.751 282.566 349.126 + vertex -884.508 289.38 349.18 + vertex -880.555 278.805 345.982 + endloop + endfacet + facet normal -0.604766 -0.428969 0.671002 + outer loop + vertex -880.555 278.805 345.982 + vertex -884.508 289.38 349.18 + vertex -885.342 285.636 346.034 + endloop + endfacet + facet normal -0.474964 -0.543984 0.69173 + outer loop + vertex -843.348 237.805 344.255 + vertex -850.447 247.653 347.127 + vertex -852.053 244.87 343.835 + endloop + endfacet + facet normal -0.464161 -0.539366 0.702595 + outer loop + vertex -842.72 241.624 347.603 + vertex -850.447 247.653 347.127 + vertex -843.348 237.805 344.255 + endloop + endfacet + facet normal -0.452864 -0.544326 0.706133 + outer loop + vertex -834.354 230.596 344.467 + vertex -842.72 241.624 347.603 + vertex -843.348 237.805 344.255 + endloop + endfacet + facet normal -0.450921 -0.543406 0.708082 + outer loop + vertex -833.791 234.471 347.799 + vertex -842.72 241.624 347.603 + vertex -834.354 230.596 344.467 + endloop + endfacet + facet normal -0.432386 -0.550988 0.713761 + outer loop + vertex -825.038 223.292 344.472 + vertex -833.791 234.471 347.799 + vertex -834.354 230.596 344.467 + endloop + endfacet + facet normal -0.433254 -0.551412 0.712906 + outer loop + vertex -824.488 227.173 347.808 + vertex -833.791 234.471 347.799 + vertex -825.038 223.292 344.472 + endloop + endfacet + facet normal -0.41199 -0.559692 0.719033 + outer loop + vertex -815.646 216.297 344.409 + vertex -824.488 227.173 347.808 + vertex -825.038 223.292 344.472 + endloop + endfacet + facet normal -0.413642 -0.560533 0.717428 + outer loop + vertex -815.101 220.177 347.755 + vertex -824.488 227.173 347.808 + vertex -815.646 216.297 344.409 + endloop + endfacet + facet normal -0.389973 -0.569307 0.723748 + outer loop + vertex -806.239 209.793 344.361 + vertex -815.101 220.177 347.755 + vertex -815.646 216.297 344.409 + endloop + endfacet + facet normal -0.391935 -0.570363 0.721854 + outer loop + vertex -805.701 213.664 347.712 + vertex -815.101 220.177 347.755 + vertex -806.239 209.793 344.361 + endloop + endfacet + facet normal -0.373457 -0.576901 0.72644 + outer loop + vertex -796.78 203.662 344.355 + vertex -805.701 213.664 347.712 + vertex -806.239 209.793 344.361 + endloop + endfacet + facet normal -0.373327 -0.576827 0.726566 + outer loop + vertex -796.247 207.538 347.706 + vertex -805.701 213.664 347.712 + vertex -796.78 203.662 344.355 + endloop + endfacet + facet normal -0.35744 -0.582203 0.730258 + outer loop + vertex -787.225 197.809 344.366 + vertex -796.247 207.538 347.706 + vertex -796.78 203.662 344.355 + endloop + endfacet + facet normal -0.358162 -0.582633 0.72956 + outer loop + vertex -786.697 201.68 347.716 + vertex -796.247 207.538 347.706 + vertex -787.225 197.809 344.366 + endloop + endfacet + facet normal -0.344875 -0.586972 0.732479 + outer loop + vertex -777.549 192.137 344.377 + vertex -786.697 201.68 347.716 + vertex -787.225 197.809 344.366 + endloop + endfacet + facet normal -0.343396 -0.586054 0.733907 + outer loop + vertex -777.023 196.019 347.722 + vertex -786.697 201.68 347.716 + vertex -777.549 192.137 344.377 + endloop + endfacet + facet normal -0.331072 -0.589927 0.736463 + outer loop + vertex -767.722 186.626 344.379 + vertex -777.023 196.019 347.722 + vertex -777.549 192.137 344.377 + endloop + endfacet + facet normal -0.332308 -0.590724 0.735266 + outer loop + vertex -767.204 190.502 347.727 + vertex -777.023 196.019 347.722 + vertex -767.722 186.626 344.379 + endloop + endfacet + facet normal -0.319245 -0.594698 0.737847 + outer loop + vertex -757.71 181.252 344.38 + vertex -767.204 190.502 347.727 + vertex -767.722 186.626 344.379 + endloop + endfacet + facet normal -0.319037 -0.594558 0.738049 + outer loop + vertex -757.199 185.133 347.727 + vertex -767.204 190.502 347.727 + vertex -757.71 181.252 344.38 + endloop + endfacet + facet normal -0.306477 -0.598236 0.740396 + outer loop + vertex -747.504 176.021 344.378 + vertex -757.199 185.133 347.727 + vertex -757.71 181.252 344.38 + endloop + endfacet + facet normal -0.307287 -0.598805 0.739599 + outer loop + vertex -747.001 179.9 347.727 + vertex -757.199 185.133 347.727 + vertex -747.504 176.021 344.378 + endloop + endfacet + facet normal -0.295188 -0.602226 0.741746 + outer loop + vertex -737.148 170.942 344.376 + vertex -747.001 179.9 347.727 + vertex -747.504 176.021 344.378 + endloop + endfacet + facet normal -0.295428 -0.602401 0.741509 + outer loop + vertex -736.651 174.822 347.726 + vertex -747.001 179.9 347.727 + vertex -737.148 170.942 344.376 + endloop + endfacet + facet normal -0.284246 -0.605456 0.743389 + outer loop + vertex -726.723 166.045 344.373 + vertex -736.651 174.822 347.726 + vertex -737.148 170.942 344.376 + endloop + endfacet + facet normal -0.283866 -0.605171 0.743767 + outer loop + vertex -726.23 169.929 347.722 + vertex -736.651 174.822 347.726 + vertex -726.723 166.045 344.373 + endloop + endfacet + facet normal -0.27266 -0.608127 0.745545 + outer loop + vertex -716.297 161.362 344.367 + vertex -726.23 169.929 347.722 + vertex -726.723 166.045 344.373 + endloop + endfacet + facet normal -0.273899 -0.60908 0.744312 + outer loop + vertex -715.803 165.235 347.717 + vertex -726.23 169.929 347.722 + vertex -716.297 161.362 344.367 + endloop + endfacet + facet normal -0.263853 -0.611665 0.74582 + outer loop + vertex -705.879 156.864 344.363 + vertex -715.803 165.235 347.717 + vertex -716.297 161.362 344.367 + endloop + endfacet + facet normal -0.263065 -0.611046 0.746605 + outer loop + vertex -705.382 160.74 347.711 + vertex -715.803 165.235 347.717 + vertex -705.879 156.864 344.363 + endloop + endfacet + facet normal -0.253587 -0.613415 0.747941 + outer loop + vertex -695.437 152.543 344.36 + vertex -705.382 160.74 347.711 + vertex -705.879 156.864 344.363 + endloop + endfacet + facet normal -0.253505 -0.61335 0.748022 + outer loop + vertex -694.933 156.414 347.704 + vertex -705.382 160.74 347.711 + vertex -695.437 152.543 344.36 + endloop + endfacet + facet normal -0.245138 -0.615396 0.74913 + outer loop + vertex -684.954 148.37 344.362 + vertex -694.933 156.414 347.704 + vertex -695.437 152.543 344.36 + endloop + endfacet + facet normal -0.245023 -0.615301 0.749245 + outer loop + vertex -684.447 152.24 347.706 + vertex -694.933 156.414 347.704 + vertex -684.954 148.37 344.362 + endloop + endfacet + facet normal -0.237457 -0.617111 0.750192 + outer loop + vertex -674.465 144.351 344.376 + vertex -684.447 152.24 347.706 + vertex -684.954 148.37 344.362 + endloop + endfacet + facet normal -0.237778 -0.61738 0.749869 + outer loop + vertex -673.965 148.229 347.727 + vertex -684.447 152.24 347.706 + vertex -674.465 144.351 344.376 + endloop + endfacet + facet normal -0.229696 -0.619259 0.750838 + outer loop + vertex -663.978 140.485 344.395 + vertex -673.965 148.229 347.727 + vertex -674.465 144.351 344.376 + endloop + endfacet + facet normal -0.230699 -0.620115 0.749824 + outer loop + vertex -663.494 144.378 347.764 + vertex -673.965 148.229 347.727 + vertex -663.978 140.485 344.395 + endloop + endfacet + facet normal -0.219926 -0.622525 0.751063 + outer loop + vertex -653.343 136.706 344.377 + vertex -663.494 144.378 347.764 + vertex -663.978 140.485 344.395 + endloop + endfacet + facet normal -0.222546 -0.62481 0.748389 + outer loop + vertex -652.865 140.598 347.769 + vertex -663.494 144.378 347.764 + vertex -653.343 136.706 344.377 + endloop + endfacet + facet normal -0.209037 -0.627733 0.749836 + outer loop + vertex -642.298 132.872 344.247 + vertex -652.865 140.598 347.769 + vertex -653.343 136.706 344.377 + endloop + endfacet + facet normal -0.214341 -0.632479 0.744331 + outer loop + vertex -641.792 136.729 347.67 + vertex -652.865 140.598 347.769 + vertex -642.298 132.872 344.247 + endloop + endfacet + facet normal -0.201314 -0.63529 0.745573 + outer loop + vertex -630.853 128.945 343.992 + vertex -641.792 136.729 347.67 + vertex -642.298 132.872 344.247 + endloop + endfacet + facet normal -0.20915 -0.642387 0.737289 + outer loop + vertex -630.295 132.762 347.475 + vertex -641.792 136.729 347.67 + vertex -630.853 128.945 343.992 + endloop + endfacet + facet normal -0.199921 -0.644438 0.738059 + outer loop + vertex -619.781 125.272 343.783 + vertex -630.295 132.762 347.475 + vertex -630.853 128.945 343.992 + endloop + endfacet + facet normal -0.206159 -0.649953 0.731478 + outer loop + vertex -619.228 129.144 347.379 + vertex -630.295 132.762 347.475 + vertex -619.781 125.272 343.783 + endloop + endfacet + facet normal -0.202536 -0.650751 0.73178 + outer loop + vertex -610.538 122.628 343.991 + vertex -619.228 129.144 347.379 + vertex -619.781 125.272 343.783 + endloop + endfacet + facet normal -0.202374 -0.650619 0.731942 + outer loop + vertex -610.133 126.727 347.746 + vertex -619.228 129.144 347.379 + vertex -610.538 122.628 343.991 + endloop + endfacet + facet normal -0.207336 -0.649648 0.731416 + outer loop + vertex -604.45 121.938 345.103 + vertex -610.133 126.727 347.746 + vertex -610.538 122.628 343.991 + endloop + endfacet + facet normal -0.189219 -0.636934 0.747336 + outer loop + vertex -604.113 126.231 348.847 + vertex -610.133 126.727 347.746 + vertex -604.45 121.938 345.103 + endloop + endfacet + facet normal -0.506083 -0.51254 0.693674 + outer loop + vertex -857.973 251.284 344.671 + vertex -856.528 252.869 346.897 + vertex -861.365 257.315 346.653 + endloop + endfacet + facet normal -0.532579 -0.540834 0.651043 + outer loop + vertex -856.927 247.711 342.559 + vertex -857.973 251.284 344.671 + vertex -861.601 253.27 343.354 + endloop + endfacet + facet normal -0.528041 -0.518062 0.672893 + outer loop + vertex -861.365 257.315 346.653 + vertex -861.601 253.27 343.354 + vertex -857.973 251.284 344.671 + endloop + endfacet + facet normal -0.54115 -0.51235 0.666824 + outer loop + vertex -861.365 257.315 346.653 + vertex -865.844 261.374 346.137 + vertex -861.601 253.27 343.354 + endloop + endfacet + facet normal -0.545219 -0.513132 0.662897 + outer loop + vertex -861.601 253.27 343.354 + vertex -865.844 261.374 346.137 + vertex -866.528 257.833 342.833 + endloop + endfacet + facet normal -0.563152 -0.502933 0.655681 + outer loop + vertex -865.844 261.374 346.137 + vertex -870.564 266.365 345.912 + vertex -866.528 257.833 342.833 + endloop + endfacet + facet normal -0.565398 -0.503218 0.653526 + outer loop + vertex -866.528 257.833 342.833 + vertex -870.564 266.365 345.912 + vertex -871.279 262.832 342.572 + endloop + endfacet + facet normal -0.585358 -0.491176 0.64506 + outer loop + vertex -870.564 266.365 345.912 + vertex -875.526 272.269 345.905 + vertex -871.279 262.832 342.572 + endloop + endfacet + facet normal -0.580617 -0.490683 0.649703 + outer loop + vertex -871.279 262.832 342.572 + vertex -875.526 272.269 345.905 + vertex -876.251 268.7 342.561 + endloop + endfacet + facet normal -0.606631 -0.474376 0.637939 + outer loop + vertex -875.526 272.269 345.905 + vertex -880.555 278.805 345.982 + vertex -876.251 268.7 342.561 + endloop + endfacet + facet normal -0.603546 -0.474116 0.641051 + outer loop + vertex -876.251 268.7 342.561 + vertex -880.555 278.805 345.982 + vertex -881.29 275.219 342.638 + endloop + endfacet + facet normal -0.637469 -0.451535 0.624298 + outer loop + vertex -880.555 278.805 345.982 + vertex -885.342 285.636 346.034 + vertex -881.29 275.219 342.638 + endloop + endfacet + facet normal -0.634646 -0.451404 0.627264 + outer loop + vertex -881.29 275.219 342.638 + vertex -885.342 285.636 346.034 + vertex -886.102 282.053 342.688 + endloop + endfacet + facet normal -0.497367 -0.570335 0.653715 + outer loop + vertex -844.068 234.335 340.719 + vertex -852.053 244.87 343.835 + vertex -852.708 241.069 340.02 + endloop + endfacet + facet normal -0.493347 -0.568626 0.658235 + outer loop + vertex -843.348 237.805 344.255 + vertex -852.053 244.87 343.835 + vertex -844.068 234.335 340.719 + endloop + endfacet + facet normal -0.480021 -0.57541 0.66218 + outer loop + vertex -834.94 227.031 340.989 + vertex -843.348 237.805 344.255 + vertex -844.068 234.335 340.719 + endloop + endfacet + facet normal -0.475118 -0.573224 0.667591 + outer loop + vertex -834.354 230.596 344.467 + vertex -843.348 237.805 344.255 + vertex -834.94 227.031 340.989 + endloop + endfacet + facet normal -0.456544 -0.581722 0.673176 + outer loop + vertex -825.591 219.712 341.004 + vertex -834.354 230.596 344.467 + vertex -834.94 227.031 340.989 + endloop + endfacet + facet normal -0.456408 -0.581659 0.673323 + outer loop + vertex -825.038 223.292 344.472 + vertex -834.354 230.596 344.467 + vertex -825.591 219.712 341.004 + endloop + endfacet + facet normal -0.433838 -0.591375 0.679751 + outer loop + vertex -816.198 212.738 340.932 + vertex -825.038 223.292 344.472 + vertex -825.591 219.712 341.004 + endloop + endfacet + facet normal -0.437018 -0.592904 0.676373 + outer loop + vertex -815.646 216.297 344.409 + vertex -825.038 223.292 344.472 + vertex -816.198 212.738 340.932 + endloop + endfacet + facet normal -0.413296 -0.602682 0.682613 + outer loop + vertex -806.795 206.232 340.881 + vertex -815.646 216.297 344.409 + vertex -816.198 212.738 340.932 + endloop + endfacet + facet normal -0.432105 -0.629579 0.64569 + outer loop + vertex -806.795 206.232 340.881 + vertex -816.198 212.738 340.932 + vertex -807.349 202.987 337.347 + endloop + endfacet + facet normal -0.412209 -0.63806 0.650356 + outer loop + vertex -797.899 196.877 337.341 + vertex -806.795 206.232 340.881 + vertex -807.349 202.987 337.347 + endloop + endfacet + facet normal -0.428256 -0.662848 0.61419 + outer loop + vertex -797.899 196.877 337.341 + vertex -807.349 202.987 337.347 + vertex -798.402 193.946 333.827 + endloop + endfacet + facet normal -0.4124 -0.669682 0.617619 + outer loop + vertex -788.854 188.082 333.845 + vertex -797.899 196.877 337.341 + vertex -798.402 193.946 333.827 + endloop + endfacet + facet normal -0.425837 -0.691664 0.583321 + outer loop + vertex -788.854 188.082 333.845 + vertex -798.402 193.946 333.827 + vertex -789.199 185.445 330.466 + endloop + endfacet + facet normal -0.410763 -0.697923 0.586666 + outer loop + vertex -779.51 179.754 330.479 + vertex -788.854 188.082 333.845 + vertex -789.199 185.445 330.466 + endloop + endfacet + facet normal -0.421386 -0.71608 0.556473 + outer loop + vertex -779.51 179.754 330.479 + vertex -789.199 185.445 330.466 + vertex -779.638 177.448 327.416 + endloop + endfacet + facet normal -0.406083 -0.72195 0.560255 + outer loop + vertex -769.806 171.919 327.418 + vertex -779.51 179.754 330.479 + vertex -779.638 177.448 327.416 + endloop + endfacet + facet normal -0.413507 -0.735159 0.537171 + outer loop + vertex -769.806 171.919 327.418 + vertex -779.638 177.448 327.416 + vertex -769.898 170.102 324.859 + endloop + endfacet + facet normal -0.39795 -0.741058 0.540804 + outer loop + vertex -759.96 164.766 324.861 + vertex -769.806 171.919 327.418 + vertex -769.898 170.102 324.859 + endloop + endfacet + facet normal -0.401801 -0.748234 0.527922 + outer loop + vertex -759.96 164.766 324.861 + vertex -769.898 170.102 324.859 + vertex -760.626 163.711 322.858 + endloop + endfacet + facet normal -0.397117 -0.740435 0.542268 + outer loop + vertex -759.788 166.552 327.425 + vertex -769.806 171.919 327.418 + vertex -759.96 164.766 324.861 + endloop + endfacet + facet normal -0.382442 -0.746011 0.545166 + outer loop + vertex -749.77 159.55 324.871 + vertex -759.788 166.552 327.425 + vertex -759.96 164.766 324.861 + endloop + endfacet + facet normal -0.38663 -0.754219 0.530727 + outer loop + vertex -749.77 159.55 324.871 + vertex -759.96 164.766 324.861 + vertex -750.564 158.529 322.841 + endloop + endfacet + facet normal -0.382519 -0.746071 0.54503 + outer loop + vertex -749.59 161.323 327.425 + vertex -759.788 166.552 327.425 + vertex -749.77 159.55 324.871 + endloop + endfacet + facet normal -0.368095 -0.751361 0.547689 + outer loop + vertex -739.394 154.481 324.891 + vertex -749.59 161.323 327.425 + vertex -749.77 159.55 324.871 + endloop + endfacet + facet normal -0.371971 -0.759351 0.533876 + outer loop + vertex -739.394 154.481 324.891 + vertex -749.77 159.55 324.871 + vertex -740.102 153.403 322.865 + endloop + endfacet + facet normal -0.367452 -0.750832 0.548844 + outer loop + vertex -739.247 156.27 327.436 + vertex -749.59 161.323 327.425 + vertex -739.394 154.481 324.891 + endloop + endfacet + facet normal -0.354746 -0.755213 0.551188 + outer loop + vertex -728.977 149.605 324.914 + vertex -739.247 156.27 327.436 + vertex -739.394 154.481 324.891 + endloop + endfacet + facet normal -0.358968 -0.764306 0.535703 + outer loop + vertex -728.977 149.605 324.914 + vertex -739.394 154.481 324.891 + vertex -729.542 148.466 322.911 + endloop + endfacet + facet normal -0.354623 -0.755108 0.551411 + outer loop + vertex -728.864 151.402 327.448 + vertex -739.247 156.27 327.436 + vertex -728.977 149.605 324.914 + endloop + endfacet + facet normal -0.342561 -0.759026 0.553654 + outer loop + vertex -718.705 144.987 324.939 + vertex -728.864 151.402 327.448 + vertex -728.977 149.605 324.914 + endloop + endfacet + facet normal -0.34637 -0.767579 0.539305 + outer loop + vertex -718.705 144.987 324.939 + vertex -728.977 149.605 324.914 + vertex -719.184 143.8 322.941 + endloop + endfacet + facet normal -0.342562 -0.759026 0.553652 + outer loop + vertex -718.539 146.753 327.463 + vertex -728.864 151.402 327.448 + vertex -718.705 144.987 324.939 + endloop + endfacet + facet normal -0.331266 -0.762698 0.555477 + outer loop + vertex -708.615 140.618 324.958 + vertex -718.539 146.753 327.463 + vertex -718.705 144.987 324.939 + endloop + endfacet + facet normal -0.334743 -0.770785 0.542068 + outer loop + vertex -708.615 140.618 324.958 + vertex -718.705 144.987 324.939 + vertex -709.154 139.433 322.94 + endloop + endfacet + facet normal -0.324752 -0.775131 0.541949 + outer loop + vertex -699.308 135.304 322.934 + vertex -708.615 140.618 324.958 + vertex -709.154 139.433 322.94 + endloop + endfacet + facet normal -0.323955 -0.774344 0.543548 + outer loop + vertex -698.59 136.428 324.962 + vertex -708.615 140.618 324.958 + vertex -699.308 135.304 322.934 + endloop + endfacet + facet normal -0.313582 -0.779261 0.542604 + outer loop + vertex -689.467 131.333 322.918 + vertex -698.59 136.428 324.962 + vertex -699.308 135.304 322.934 + endloop + endfacet + facet normal -0.314841 -0.78236 0.537391 + outer loop + vertex -689.467 131.333 322.918 + vertex -699.308 135.304 322.934 + vertex -690.567 130.579 321.177 + endloop + endfacet + facet normal -0.303701 -0.789446 0.533423 + outer loop + vertex -681.06 126.932 321.191 + vertex -689.467 131.333 322.918 + vertex -690.567 130.579 321.177 + endloop + endfacet + facet normal -0.300833 -0.786372 0.539554 + outer loop + vertex -679.483 127.449 322.824 + vertex -689.467 131.333 322.918 + vertex -681.06 126.932 321.191 + endloop + endfacet + facet normal -0.286138 -0.798742 0.529279 + outer loop + vertex -671.241 123.287 321 + vertex -679.483 127.449 322.824 + vertex -681.06 126.932 321.191 + endloop + endfacet + facet normal -0.283113 -0.795552 0.535671 + outer loop + vertex -669.449 123.698 322.557 + vertex -679.483 127.449 322.824 + vertex -671.241 123.287 321 + endloop + endfacet + facet normal -0.265235 -0.812257 0.519509 + outer loop + vertex -661.458 119.756 320.474 + vertex -669.449 123.698 322.557 + vertex -671.241 123.287 321 + endloop + endfacet + facet normal -0.261624 -0.80876 0.526744 + outer loop + vertex -659.454 120.125 322.034 + vertex -669.449 123.698 322.557 + vertex -661.458 119.756 320.474 + endloop + endfacet + facet normal -0.241419 -0.828404 0.505434 + outer loop + vertex -651.678 116.471 319.76 + vertex -659.454 120.125 322.034 + vertex -661.458 119.756 320.474 + endloop + endfacet + facet normal -0.233472 -0.821093 0.520861 + outer loop + vertex -649.209 116.635 321.125 + vertex -659.454 120.125 322.034 + vertex -651.678 116.471 319.76 + endloop + endfacet + facet normal -0.209092 -0.851736 0.480444 + outer loop + vertex -640.996 112.963 318.191 + vertex -649.209 116.635 321.125 + vertex -651.678 116.471 319.76 + endloop + endfacet + facet normal -0.223411 -0.862574 0.453932 + outer loop + vertex -638.263 113.055 319.709 + vertex -649.209 116.635 321.125 + vertex -640.996 112.963 318.191 + endloop + endfacet + facet normal -0.196346 -0.892074 0.407005 + outer loop + vertex -638.263 113.055 319.709 + vertex -640.996 112.963 318.191 + vertex -632.059 110.316 316.701 + endloop + endfacet + facet normal -0.260832 -0.806998 0.529832 + outer loop + vertex -659.454 120.125 322.034 + vertex -668.186 124.635 324.606 + vertex -669.449 123.698 322.557 + endloop + endfacet + facet normal -0.283093 -0.794191 0.537698 + outer loop + vertex -668.186 124.635 324.606 + vertex -678.336 128.421 324.854 + vertex -669.449 123.698 322.557 + endloop + endfacet + facet normal -0.277909 -0.781656 0.558373 + outer loop + vertex -668.186 124.635 324.606 + vertex -677.545 129.994 327.449 + vertex -678.336 128.421 324.854 + endloop + endfacet + facet normal -0.295743 -0.774356 0.559383 + outer loop + vertex -677.545 129.994 327.449 + vertex -687.811 133.963 327.516 + vertex -678.336 128.421 324.854 + endloop + endfacet + facet normal -0.295203 -0.773883 0.560321 + outer loop + vertex -678.336 128.421 324.854 + vertex -687.811 133.963 327.516 + vertex -688.499 132.365 324.947 + endloop + endfacet + facet normal -0.299144 -0.783668 0.544405 + outer loop + vertex -678.336 128.421 324.854 + vertex -688.499 132.365 324.947 + vertex -679.483 127.449 322.824 + endloop + endfacet + facet normal -0.30832 -0.768591 0.560541 + outer loop + vertex -687.811 133.963 327.516 + vertex -698.069 138.076 327.513 + vertex -688.499 132.365 324.947 + endloop + endfacet + facet normal -0.308674 -0.768904 0.559918 + outer loop + vertex -688.499 132.365 324.947 + vertex -698.069 138.076 327.513 + vertex -698.59 136.428 324.962 + endloop + endfacet + facet normal -0.319381 -0.76484 0.559479 + outer loop + vertex -698.069 138.076 327.513 + vertex -708.296 142.328 327.488 + vertex -698.59 136.428 324.962 + endloop + endfacet + facet normal -0.313852 -0.751417 0.580404 + outer loop + vertex -698.069 138.076 327.513 + vertex -707.941 144.527 330.527 + vertex -708.296 142.328 327.488 + endloop + endfacet + facet normal -0.324183 -0.747999 0.57914 + outer loop + vertex -707.941 144.527 330.527 + vertex -718.295 148.996 330.503 + vertex -708.296 142.328 327.488 + endloop + endfacet + facet normal -0.324765 -0.748456 0.578222 + outer loop + vertex -708.296 142.328 327.488 + vertex -718.295 148.996 330.503 + vertex -718.539 146.753 327.463 + endloop + endfacet + facet normal -0.33558 -0.744984 0.576528 + outer loop + vertex -718.295 148.996 330.503 + vertex -728.69 153.664 330.485 + vertex -718.539 146.753 327.463 + endloop + endfacet + facet normal -0.327422 -0.726714 0.603888 + outer loop + vertex -718.295 148.996 330.503 + vertex -728.308 156.292 333.855 + vertex -728.69 153.664 330.485 + endloop + endfacet + facet normal -0.339165 -0.722768 0.60214 + outer loop + vertex -728.308 156.292 333.855 + vertex -738.743 161.187 333.852 + vertex -728.69 153.664 330.485 + endloop + endfacet + facet normal -0.339411 -0.722941 0.601795 + outer loop + vertex -728.69 153.664 330.485 + vertex -738.743 161.187 333.852 + vertex -739.101 158.546 330.478 + endloop + endfacet + facet normal -0.348351 -0.74205 0.572725 + outer loop + vertex -728.69 153.664 330.485 + vertex -739.101 158.546 330.478 + vertex -728.864 151.402 327.448 + endloop + endfacet + facet normal -0.351894 -0.718649 0.599762 + outer loop + vertex -738.743 161.187 333.852 + vertex -749.106 166.263 333.854 + vertex -739.101 158.546 330.478 + endloop + endfacet + facet normal -0.352187 -0.718849 0.59935 + outer loop + vertex -739.101 158.546 330.478 + vertex -749.106 166.263 333.854 + vertex -749.447 163.616 330.479 + endloop + endfacet + facet normal -0.36158 -0.738008 0.56974 + outer loop + vertex -739.101 158.546 330.478 + vertex -749.447 163.616 330.479 + vertex -739.247 156.27 327.436 + endloop + endfacet + facet normal -0.365935 -0.713984 0.596924 + outer loop + vertex -749.106 166.263 333.854 + vertex -759.311 171.497 333.859 + vertex -749.447 163.616 330.479 + endloop + endfacet + facet normal -0.365497 -0.713698 0.597535 + outer loop + vertex -749.447 163.616 330.479 + vertex -759.311 171.497 333.859 + vertex -759.646 168.84 330.48 + endloop + endfacet + facet normal -0.375257 -0.732746 0.567684 + outer loop + vertex -749.447 163.616 330.479 + vertex -759.646 168.84 330.48 + vertex -749.59 161.323 327.425 + endloop + endfacet + facet normal -0.379539 -0.708561 0.594888 + outer loop + vertex -759.311 171.497 333.859 + vertex -769.331 176.866 333.86 + vertex -759.646 168.84 330.48 + endloop + endfacet + facet normal -0.38083 -0.709366 0.593101 + outer loop + vertex -759.646 168.84 330.48 + vertex -769.331 176.866 333.86 + vertex -769.663 174.221 330.484 + endloop + endfacet + facet normal -0.390812 -0.727928 0.563371 + outer loop + vertex -759.646 168.84 330.48 + vertex -769.663 174.221 330.484 + vertex -759.788 166.552 327.425 + endloop + endfacet + facet normal -0.395535 -0.703756 0.590152 + outer loop + vertex -769.331 176.866 333.86 + vertex -779.167 182.392 333.857 + vertex -769.663 174.221 330.484 + endloop + endfacet + facet normal -0.395774 -0.703898 0.589822 + outer loop + vertex -769.663 174.221 330.484 + vertex -779.167 182.392 333.857 + vertex -779.51 179.754 330.479 + endloop + endfacet + facet normal -0.382522 -0.680578 0.624892 + outer loop + vertex -769.331 176.866 333.86 + vertex -778.662 185.333 337.37 + vertex -779.167 182.392 333.857 + endloop + endfacet + facet normal -0.396477 -0.675006 0.622232 + outer loop + vertex -778.662 185.333 337.37 + vertex -788.345 191.009 337.357 + vertex -779.167 182.392 333.857 + endloop + endfacet + facet normal -0.397764 -0.675725 0.620628 + outer loop + vertex -779.167 182.392 333.857 + vertex -788.345 191.009 337.357 + vertex -788.854 188.082 333.845 + endloop + endfacet + facet normal -0.381748 -0.649795 0.657293 + outer loop + vertex -778.662 185.333 337.37 + vertex -787.78 194.249 340.889 + vertex -788.345 191.009 337.357 + endloop + endfacet + facet normal -0.395907 -0.644197 0.654422 + outer loop + vertex -787.78 194.249 340.889 + vertex -797.337 200.108 340.874 + vertex -788.345 191.009 337.357 + endloop + endfacet + facet normal -0.397204 -0.644904 0.652937 + outer loop + vertex -788.345 191.009 337.357 + vertex -797.337 200.108 340.874 + vertex -797.899 196.877 337.341 + endloop + endfacet + facet normal -0.378977 -0.616492 0.690155 + outer loop + vertex -787.78 194.249 340.889 + vertex -796.78 203.662 344.355 + vertex -797.337 200.108 340.874 + endloop + endfacet + facet normal -0.395177 -0.610373 0.686498 + outer loop + vertex -796.78 203.662 344.355 + vertex -806.239 209.793 344.361 + vertex -797.337 200.108 340.874 + endloop + endfacet + facet normal -0.394503 -0.61001 0.687209 + outer loop + vertex -797.337 200.108 340.874 + vertex -806.239 209.793 344.361 + vertex -806.795 206.232 340.881 + endloop + endfacet + facet normal -0.378091 -0.615989 0.69109 + outer loop + vertex -787.225 197.809 344.366 + vertex -796.78 203.662 344.355 + vertex -787.78 194.249 340.889 + endloop + endfacet + facet normal -0.364444 -0.620943 0.693982 + outer loop + vertex -778.101 188.58 340.899 + vertex -787.225 197.809 344.366 + vertex -787.78 194.249 340.889 + endloop + endfacet + facet normal -0.364904 -0.621215 0.693497 + outer loop + vertex -777.549 192.137 344.377 + vertex -787.225 197.809 344.366 + vertex -778.101 188.58 340.899 + endloop + endfacet + facet normal -0.351396 -0.625956 0.696204 + outer loop + vertex -768.271 183.065 340.903 + vertex -777.549 192.137 344.377 + vertex -778.101 188.58 340.899 + endloop + endfacet + facet normal -0.367415 -0.654531 0.660754 + outer loop + vertex -768.271 183.065 340.903 + vertex -778.101 188.58 340.899 + vertex -768.83 179.816 337.373 + endloop + endfacet + facet normal -0.353855 -0.659517 0.663193 + outer loop + vertex -758.815 174.439 337.37 + vertex -768.271 183.065 340.903 + vertex -768.83 179.816 337.373 + endloop + endfacet + facet normal -0.368271 -0.68635 0.627137 + outer loop + vertex -758.815 174.439 337.37 + vertex -768.83 179.816 337.373 + vertex -759.311 171.497 333.859 + endloop + endfacet + facet normal -0.353587 -0.659349 0.663502 + outer loop + vertex -758.253 177.692 340.902 + vertex -768.271 183.065 340.903 + vertex -758.815 174.439 337.37 + endloop + endfacet + facet normal -0.339851 -0.664228 0.665809 + outer loop + vertex -748.597 169.209 337.367 + vertex -758.253 177.692 340.902 + vertex -758.815 174.439 337.37 + endloop + endfacet + facet normal -0.353543 -0.690953 0.630548 + outer loop + vertex -748.597 169.209 337.367 + vertex -758.815 174.439 337.37 + vertex -749.106 166.263 333.854 + endloop + endfacet + facet normal -0.340531 -0.664672 0.665018 + outer loop + vertex -748.04 172.457 340.9 + vertex -758.253 177.692 340.902 + vertex -748.597 169.209 337.367 + endloop + endfacet + facet normal -0.327882 -0.669016 0.667017 + outer loop + vertex -738.23 164.125 337.364 + vertex -748.04 172.457 340.9 + vertex -748.597 169.209 337.367 + endloop + endfacet + facet normal -0.341088 -0.695925 0.631939 + outer loop + vertex -738.23 164.125 337.364 + vertex -748.597 169.209 337.367 + vertex -738.743 161.187 333.852 + endloop + endfacet + facet normal -0.327728 -0.668912 0.667197 + outer loop + vertex -737.677 167.378 340.897 + vertex -748.04 172.457 340.9 + vertex -738.23 164.125 337.364 + endloop + endfacet + facet normal -0.315565 -0.672943 0.669004 + outer loop + vertex -727.793 159.229 337.363 + vertex -737.677 167.378 340.897 + vertex -738.23 164.125 337.364 + endloop + endfacet + facet normal -0.32827 -0.700022 0.634199 + outer loop + vertex -727.793 159.229 337.363 + vertex -738.23 164.125 337.364 + vertex -728.308 156.292 333.855 + endloop + endfacet + facet normal -0.316981 -0.703827 0.635728 + outer loop + vertex -717.88 151.603 333.863 + vertex -727.793 159.229 337.363 + vertex -728.308 156.292 333.855 + endloop + endfacet + facet normal -0.316469 -0.703463 0.636385 + outer loop + vertex -717.362 154.539 337.365 + vertex -727.793 159.229 337.363 + vertex -717.88 151.603 333.863 + endloop + endfacet + facet normal -0.30578 -0.706959 0.637736 + outer loop + vertex -707.485 147.124 333.881 + vertex -717.362 154.539 337.365 + vertex -717.88 151.603 333.863 + endloop + endfacet + facet normal -0.315297 -0.729167 0.607374 + outer loop + vertex -707.485 147.124 333.881 + vertex -717.88 151.603 333.863 + vertex -707.941 144.527 330.527 + endloop + endfacet + facet normal -0.3054 -0.732404 0.608535 + outer loop + vertex -697.603 140.24 330.555 + vertex -707.485 147.124 333.881 + vertex -707.941 144.527 330.527 + endloop + endfacet + facet normal -0.304555 -0.731766 0.609725 + outer loop + vertex -697.103 142.82 333.902 + vertex -707.485 147.124 333.881 + vertex -697.603 140.24 330.555 + endloop + endfacet + facet normal -0.294477 -0.735036 0.610742 + outer loop + vertex -687.259 136.105 330.567 + vertex -697.103 142.82 333.902 + vertex -697.603 140.24 330.555 + endloop + endfacet + facet normal -0.301885 -0.753644 0.583854 + outer loop + vertex -687.259 136.105 330.567 + vertex -697.603 140.24 330.555 + vertex -687.811 133.963 327.516 + endloop + endfacet + facet normal -0.293504 -0.734288 0.612108 + outer loop + vertex -686.702 138.671 333.912 + vertex -697.103 142.82 333.902 + vertex -687.259 136.105 330.567 + endloop + endfacet + facet normal -0.28184 -0.738055 0.613058 + outer loop + vertex -676.91 132.117 330.523 + vertex -686.702 138.671 333.912 + vertex -687.259 136.105 330.567 + endloop + endfacet + facet normal -0.289827 -0.758455 0.583734 + outer loop + vertex -676.91 132.117 330.523 + vertex -687.259 136.105 330.567 + vertex -677.545 129.994 327.449 + endloop + endfacet + facet normal -0.272978 -0.764274 0.584268 + outer loop + vertex -667.296 126.182 327.251 + vertex -676.91 132.117 330.523 + vertex -677.545 129.994 327.449 + endloop + endfacet + facet normal -0.27676 -0.767251 0.578558 + outer loop + vertex -666.557 128.275 330.381 + vertex -676.91 132.117 330.523 + vertex -667.296 126.182 327.251 + endloop + endfacet + facet normal -0.254615 -0.774944 0.578475 + outer loop + vertex -657.054 122.542 326.883 + vertex -666.557 128.275 330.381 + vertex -667.296 126.182 327.251 + endloop + endfacet + facet normal -0.265047 -0.800211 0.537971 + outer loop + vertex -657.054 122.542 326.883 + vertex -667.296 126.182 327.251 + vertex -658.031 121.012 324.127 + endloop + endfacet + facet normal -0.236878 -0.811467 0.534239 + outer loop + vertex -647.818 117.549 323.394 + vertex -657.054 122.542 326.883 + vertex -658.031 121.012 324.127 + endloop + endfacet + facet normal -0.252812 -0.823038 0.50862 + outer loop + vertex -646.871 119.077 326.337 + vertex -657.054 122.542 326.883 + vertex -647.818 117.549 323.394 + endloop + endfacet + facet normal -0.225611 -0.833068 0.505071 + outer loop + vertex -638.132 114.432 322.579 + vertex -646.871 119.077 326.337 + vertex -647.818 117.549 323.394 + endloop + endfacet + facet normal -0.238729 -0.841386 0.484849 + outer loop + vertex -636.815 115.781 325.569 + vertex -646.871 119.077 326.337 + vertex -638.132 114.432 322.579 + endloop + endfacet + facet normal -0.211841 -0.852438 0.477989 + outer loop + vertex -629.242 111.669 321.593 + vertex -636.815 115.781 325.569 + vertex -638.132 114.432 322.579 + endloop + endfacet + facet normal -0.257276 -0.794017 0.550769 + outer loop + vertex -658.031 121.012 324.127 + vertex -667.296 126.182 327.251 + vertex -668.186 124.635 324.606 + endloop + endfacet + facet normal -0.263464 -0.781622 0.565379 + outer loop + vertex -656.182 124.578 330.105 + vertex -666.557 128.275 330.381 + vertex -657.054 122.542 326.883 + endloop + endfacet + facet normal -0.238715 -0.790371 0.564207 + outer loop + vertex -646.871 119.077 326.337 + vertex -656.182 124.578 330.105 + vertex -657.054 122.542 326.883 + endloop + endfacet + facet normal -0.247705 -0.796717 0.551257 + outer loop + vertex -645.719 121.006 329.643 + vertex -656.182 124.578 330.105 + vertex -646.871 119.077 326.337 + endloop + endfacet + facet normal -0.222413 -0.80633 0.548054 + outer loop + vertex -636.815 115.781 325.569 + vertex -645.719 121.006 329.643 + vertex -646.871 119.077 326.337 + endloop + endfacet + facet normal -0.234476 -0.813969 0.531485 + outer loop + vertex -635.062 117.468 328.927 + vertex -645.719 121.006 329.643 + vertex -636.815 115.781 325.569 + endloop + endfacet + facet normal -0.207712 -0.826218 0.52366 + outer loop + vertex -626.847 112.562 324.444 + vertex -635.062 117.468 328.927 + vertex -636.815 115.781 325.569 + endloop + endfacet + facet normal -0.227617 -0.836508 0.498442 + outer loop + vertex -624.367 114.004 327.996 + vertex -635.062 117.468 328.927 + vertex -626.847 112.562 324.444 + endloop + endfacet + facet normal -0.199673 -0.851421 0.484988 + outer loop + vertex -616.778 109.216 322.716 + vertex -624.367 114.004 327.996 + vertex -626.847 112.562 324.444 + endloop + endfacet + facet normal -0.251712 -0.751922 0.609307 + outer loop + vertex -656.182 124.578 330.105 + vertex -665.829 130.794 333.789 + vertex -666.557 128.275 330.381 + endloop + endfacet + facet normal -0.270546 -0.745776 0.608789 + outer loop + vertex -665.829 130.794 333.789 + vertex -676.276 134.661 333.885 + vertex -666.557 128.275 330.381 + endloop + endfacet + facet normal -0.260028 -0.718265 0.645353 + outer loop + vertex -665.829 130.794 333.789 + vertex -675.63 137.563 337.375 + vertex -676.276 134.661 333.885 + endloop + endfacet + facet normal -0.273388 -0.714145 0.644403 + outer loop + vertex -675.63 137.563 337.375 + vertex -686.106 141.586 337.389 + vertex -676.276 134.661 333.885 + endloop + endfacet + facet normal -0.272811 -0.7137 0.64514 + outer loop + vertex -676.276 134.661 333.885 + vertex -686.106 141.586 337.389 + vertex -686.702 138.671 333.912 + endloop + endfacet + facet normal -0.283506 -0.710382 0.644191 + outer loop + vertex -686.106 141.586 337.389 + vertex -696.551 145.75 337.384 + vertex -686.702 138.671 333.912 + endloop + endfacet + facet normal -0.273235 -0.684577 0.675794 + outer loop + vertex -686.106 141.586 337.389 + vertex -695.982 148.987 340.893 + vertex -696.551 145.75 337.384 + endloop + endfacet + facet normal -0.282578 -0.681805 0.674752 + outer loop + vertex -695.982 148.987 340.893 + vertex -706.411 153.307 340.891 + vertex -696.551 145.75 337.384 + endloop + endfacet + facet normal -0.282812 -0.681982 0.674476 + outer loop + vertex -696.551 145.75 337.384 + vertex -706.411 153.307 340.891 + vertex -706.959 150.055 337.373 + endloop + endfacet + facet normal -0.293543 -0.708006 0.642308 + outer loop + vertex -696.551 145.75 337.384 + vertex -706.959 150.055 337.373 + vertex -697.103 142.82 333.902 + endloop + endfacet + facet normal -0.292781 -0.678978 0.673252 + outer loop + vertex -706.411 153.307 340.891 + vertex -716.821 157.796 340.891 + vertex -706.959 150.055 337.373 + endloop + endfacet + facet normal -0.293265 -0.679335 0.672681 + outer loop + vertex -706.959 150.055 337.373 + vertex -716.821 157.796 340.891 + vertex -717.362 154.539 337.365 + endloop + endfacet + facet normal -0.303371 -0.676211 0.671345 + outer loop + vertex -716.821 157.796 340.891 + vertex -727.247 162.477 340.894 + vertex -717.362 154.539 337.365 + endloop + endfacet + facet normal -0.289807 -0.646025 0.706161 + outer loop + vertex -716.821 157.796 340.891 + vertex -726.723 166.045 344.373 + vertex -727.247 162.477 340.894 + endloop + endfacet + facet normal -0.301675 -0.642536 0.704372 + outer loop + vertex -726.723 166.045 344.373 + vertex -737.148 170.942 344.376 + vertex -727.247 162.477 340.894 + endloop + endfacet + facet normal -0.301726 -0.642573 0.704317 + outer loop + vertex -727.247 162.477 340.894 + vertex -737.148 170.942 344.376 + vertex -737.677 167.378 340.897 + endloop + endfacet + facet normal -0.313261 -0.639061 0.702473 + outer loop + vertex -737.148 170.942 344.376 + vertex -747.504 176.021 344.378 + vertex -737.677 167.378 340.897 + endloop + endfacet + facet normal -0.289656 -0.645913 0.706325 + outer loop + vertex -716.297 161.362 344.367 + vertex -726.723 166.045 344.373 + vertex -716.821 157.796 340.891 + endloop + endfacet + facet normal -0.279741 -0.64874 0.70773 + outer loop + vertex -706.411 153.307 340.891 + vertex -716.297 161.362 344.367 + vertex -716.821 157.796 340.891 + endloop + endfacet + facet normal -0.279936 -0.648888 0.707517 + outer loop + vertex -705.879 156.864 344.363 + vertex -716.297 161.362 344.367 + vertex -706.411 153.307 340.891 + endloop + endfacet + facet normal -0.270087 -0.651633 0.708821 + outer loop + vertex -695.982 148.987 340.893 + vertex -705.879 156.864 344.363 + vertex -706.411 153.307 340.891 + endloop + endfacet + facet normal -0.269094 -0.650863 0.709906 + outer loop + vertex -695.437 152.543 344.36 + vertex -705.879 156.864 344.363 + vertex -695.982 148.987 340.893 + endloop + endfacet + facet normal -0.260251 -0.653274 0.710987 + outer loop + vertex -685.51 144.818 340.896 + vertex -695.437 152.543 344.36 + vertex -695.982 148.987 340.893 + endloop + endfacet + facet normal -0.260188 -0.653224 0.711056 + outer loop + vertex -684.954 148.37 344.362 + vertex -695.437 152.543 344.36 + vertex -685.51 144.818 340.896 + endloop + endfacet + facet normal -0.251698 -0.655496 0.712021 + outer loop + vertex -675.017 140.79 340.897 + vertex -684.954 148.37 344.362 + vertex -685.51 144.818 340.896 + endloop + endfacet + facet normal -0.264082 -0.687771 0.67619 + outer loop + vertex -675.017 140.79 340.897 + vertex -685.51 144.818 340.896 + vertex -675.63 137.563 337.375 + endloop + endfacet + facet normal -0.252604 -0.691067 0.677213 + outer loop + vertex -665.13 133.674 337.323 + vertex -675.017 140.79 340.897 + vertex -675.63 137.563 337.375 + endloop + endfacet + facet normal -0.254914 -0.692899 0.67447 + outer loop + vertex -664.513 136.913 340.884 + vertex -675.017 140.79 340.897 + vertex -665.13 133.674 337.323 + endloop + endfacet + facet normal -0.239643 -0.697149 0.675688 + outer loop + vertex -654.514 129.894 337.188 + vertex -664.513 136.913 340.884 + vertex -665.13 133.674 337.323 + endloop + endfacet + facet normal -0.245667 -0.701952 0.668514 + outer loop + vertex -653.872 133.126 340.817 + vertex -664.513 136.913 340.884 + vertex -654.514 129.894 337.188 + endloop + endfacet + facet normal -0.226947 -0.707057 0.66975 + outer loop + vertex -643.574 126.124 336.914 + vertex -653.872 133.126 340.817 + vertex -654.514 129.894 337.188 + endloop + endfacet + facet normal -0.235513 -0.713911 0.659443 + outer loop + vertex -642.859 129.322 340.632 + vertex -653.872 133.126 340.817 + vertex -643.574 126.124 336.914 + endloop + endfacet + facet normal -0.216859 -0.719041 0.660267 + outer loop + vertex -632.286 122.338 336.499 + vertex -642.859 129.322 340.632 + vertex -643.574 126.124 336.914 + endloop + endfacet + facet normal -0.229565 -0.729098 0.64476 + outer loop + vertex -631.47 125.456 340.316 + vertex -642.859 129.322 340.632 + vertex -632.286 122.338 336.499 + endloop + endfacet + facet normal -0.215685 -0.733076 0.645042 + outer loop + vertex -621.301 118.768 336.115 + vertex -631.47 125.456 340.316 + vertex -632.286 122.338 336.499 + endloop + endfacet + facet normal -0.228316 -0.742596 0.629622 + outer loop + vertex -620.428 121.806 340.015 + vertex -631.47 125.456 340.316 + vertex -621.301 118.768 336.115 + endloop + endfacet + facet normal -0.221758 -0.74454 0.629669 + outer loop + vertex -611.971 115.961 336.082 + vertex -620.428 121.806 340.015 + vertex -621.301 118.768 336.115 + endloop + endfacet + facet normal -0.227565 -0.748424 0.622957 + outer loop + vertex -611.134 119.004 340.044 + vertex -620.428 121.806 340.015 + vertex -611.971 115.961 336.082 + endloop + endfacet + facet normal -0.228356 -0.748192 0.622946 + outer loop + vertex -605.644 114.493 336.638 + vertex -611.134 119.004 340.044 + vertex -611.971 115.961 336.082 + endloop + endfacet + facet normal -0.222523 -0.745293 0.628508 + outer loop + vertex -604.515 117.611 340.736 + vertex -611.134 119.004 340.044 + vertex -605.644 114.493 336.638 + endloop + endfacet + facet normal -0.240571 -0.739308 0.628927 + outer loop + vertex -604.515 117.611 340.736 + vertex -605.644 114.493 336.638 + vertex -602.109 114.066 337.488 + endloop + endfacet + facet normal -0.254221 -0.741375 0.621076 + outer loop + vertex -602.109 114.066 337.488 + vertex -601.305 116.049 340.185 + vertex -604.515 117.611 340.736 + endloop + endfacet + facet normal -0.231166 -0.74958 0.620236 + outer loop + vertex -601.305 116.049 340.185 + vertex -602.109 114.066 337.488 + vertex -599.182 114.177 338.714 + endloop + endfacet + facet normal -0.252304 -0.655986 0.711354 + outer loop + vertex -674.465 144.351 344.376 + vertex -684.954 148.37 344.362 + vertex -675.017 140.79 340.897 + endloop + endfacet + facet normal -0.24221 -0.65861 0.712438 + outer loop + vertex -664.513 136.913 340.884 + vertex -674.465 144.351 344.376 + vertex -675.017 140.79 340.897 + endloop + endfacet + facet normal -0.244955 -0.660861 0.709407 + outer loop + vertex -663.978 140.485 344.395 + vertex -674.465 144.351 344.376 + vertex -664.513 136.913 340.884 + endloop + endfacet + facet normal -0.231938 -0.66412 0.710738 + outer loop + vertex -653.872 133.126 340.817 + vertex -663.978 140.485 344.395 + vertex -664.513 136.913 340.884 + endloop + endfacet + facet normal -0.235978 -0.667482 0.706245 + outer loop + vertex -653.343 136.706 344.377 + vertex -663.978 140.485 344.395 + vertex -653.872 133.126 340.817 + endloop + endfacet + facet normal -0.219995 -0.671338 0.707748 + outer loop + vertex -642.859 129.322 340.632 + vertex -653.343 136.706 344.377 + vertex -653.872 133.126 340.817 + endloop + endfacet + facet normal -0.226744 -0.677056 0.70013 + outer loop + vertex -642.298 132.872 344.247 + vertex -653.343 136.706 344.377 + vertex -642.859 129.322 340.632 + endloop + endfacet + facet normal -0.211565 -0.680698 0.701349 + outer loop + vertex -631.47 125.456 340.316 + vertex -642.298 132.872 344.247 + vertex -642.859 129.322 340.632 + endloop + endfacet + facet normal -0.220818 -0.688577 0.690725 + outer loop + vertex -630.853 128.945 343.992 + vertex -642.298 132.872 344.247 + vertex -631.47 125.456 340.316 + endloop + endfacet + facet normal -0.209683 -0.691317 0.691457 + outer loop + vertex -620.428 121.806 340.015 + vertex -630.853 128.945 343.992 + vertex -631.47 125.456 340.316 + endloop + endfacet + facet normal -0.21913 -0.699084 0.680634 + outer loop + vertex -619.781 125.272 343.783 + vertex -630.853 128.945 343.992 + vertex -620.428 121.806 340.015 + endloop + endfacet + facet normal -0.213307 -0.700548 0.680979 + outer loop + vertex -611.134 119.004 340.044 + vertex -619.781 125.272 343.783 + vertex -620.428 121.806 340.015 + endloop + endfacet + facet normal -0.216175 -0.702661 0.67789 + outer loop + vertex -610.538 122.628 343.991 + vertex -619.781 125.272 343.783 + vertex -611.134 119.004 340.044 + endloop + endfacet + facet normal -0.218581 -0.702081 0.67772 + outer loop + vertex -604.515 117.611 340.736 + vertex -610.538 122.628 343.991 + vertex -611.134 119.004 340.044 + endloop + endfacet + facet normal -0.20485 -0.69382 0.690398 + outer loop + vertex -604.45 121.938 345.103 + vertex -610.538 122.628 343.991 + vertex -604.515 117.611 340.736 + endloop + endfacet + facet normal -0.272467 -0.683982 0.676706 + outer loop + vertex -685.51 144.818 340.896 + vertex -695.982 148.987 340.893 + vertex -686.106 141.586 337.389 + endloop + endfacet + facet normal -0.262842 -0.686796 0.677662 + outer loop + vertex -675.63 137.563 337.375 + vertex -685.51 144.818 340.896 + vertex -686.106 141.586 337.389 + endloop + endfacet + facet normal -0.264 -0.721336 0.640296 + outer loop + vertex -665.13 133.674 337.323 + vertex -675.63 137.563 337.375 + vertex -665.829 130.794 333.789 + endloop + endfacet + facet normal -0.246623 -0.726663 0.6412 + outer loop + vertex -655.305 127.041 333.584 + vertex -665.13 133.674 337.323 + vertex -665.829 130.794 333.789 + endloop + endfacet + facet normal -0.252206 -0.730944 0.634124 + outer loop + vertex -654.514 129.894 337.188 + vertex -665.13 133.674 337.323 + vertex -655.305 127.041 333.584 + endloop + endfacet + facet normal -0.231527 -0.737317 0.634632 + outer loop + vertex -644.538 123.336 333.208 + vertex -654.514 129.894 337.188 + vertex -655.305 127.041 333.584 + endloop + endfacet + facet normal -0.241019 -0.744473 0.622631 + outer loop + vertex -643.574 126.124 336.914 + vertex -654.514 129.894 337.188 + vertex -644.538 123.336 333.208 + endloop + endfacet + facet normal -0.218731 -0.751652 0.622235 + outer loop + vertex -633.448 119.636 332.637 + vertex -643.574 126.124 336.914 + vertex -644.538 123.336 333.208 + endloop + endfacet + facet normal -0.233475 -0.762359 0.603571 + outer loop + vertex -632.286 122.338 336.499 + vertex -643.574 126.124 336.914 + vertex -633.448 119.636 332.637 + endloop + endfacet + facet normal -0.215422 -0.768532 0.602455 + outer loop + vertex -622.542 116.133 332.068 + vertex -632.286 122.338 336.499 + vertex -633.448 119.636 332.637 + endloop + endfacet + facet normal -0.233412 -0.780608 0.579802 + outer loop + vertex -621.301 118.768 336.115 + vertex -632.286 122.338 336.499 + vertex -622.542 116.133 332.068 + endloop + endfacet + facet normal -0.223154 -0.784199 0.578994 + outer loop + vertex -613.102 113.355 331.944 + vertex -621.301 118.768 336.115 + vertex -622.542 116.133 332.068 + endloop + endfacet + facet normal -0.236217 -0.791828 0.563214 + outer loop + vertex -611.971 115.961 336.082 + vertex -621.301 118.768 336.115 + vertex -613.102 113.355 331.944 + endloop + endfacet + facet normal -0.237594 -0.791359 0.563295 + outer loop + vertex -606.495 111.903 332.691 + vertex -611.971 115.961 336.082 + vertex -613.102 113.355 331.944 + endloop + endfacet + facet normal -0.233065 -0.789265 0.568103 + outer loop + vertex -605.644 114.493 336.638 + vertex -611.971 115.961 336.082 + vertex -606.495 111.903 332.691 + endloop + endfacet + facet normal -0.258136 -0.756732 0.600601 + outer loop + vertex -655.305 127.041 333.584 + vertex -665.829 130.794 333.789 + vertex -656.182 124.578 330.105 + endloop + endfacet + facet normal -0.234586 -0.764634 0.600254 + outer loop + vertex -645.719 121.006 329.643 + vertex -655.305 127.041 333.584 + vertex -656.182 124.578 330.105 + endloop + endfacet + facet normal -0.245264 -0.772292 0.586012 + outer loop + vertex -644.538 123.336 333.208 + vertex -655.305 127.041 333.584 + vertex -645.719 121.006 329.643 + endloop + endfacet + facet normal -0.220191 -0.781516 0.583737 + outer loop + vertex -635.062 117.468 328.927 + vertex -644.538 123.336 333.208 + vertex -645.719 121.006 329.643 + endloop + endfacet + facet normal -0.234925 -0.791287 0.564514 + outer loop + vertex -633.448 119.636 332.637 + vertex -644.538 123.336 333.208 + vertex -635.062 117.468 328.927 + endloop + endfacet + facet normal -0.210862 -0.801284 0.559894 + outer loop + vertex -624.367 114.004 327.996 + vertex -633.448 119.636 332.637 + vertex -635.062 117.468 328.927 + endloop + endfacet + facet normal -0.233936 -0.814547 0.530836 + outer loop + vertex -622.542 116.133 332.068 + vertex -633.448 119.636 332.637 + vertex -624.367 114.004 327.996 + endloop + endfacet + facet normal -0.217348 -0.821559 0.527068 + outer loop + vertex -614.702 111.103 327.461 + vertex -622.542 116.133 332.068 + vertex -624.367 114.004 327.996 + endloop + endfacet + facet normal -0.237994 -0.831201 0.502458 + outer loop + vertex -613.102 113.355 331.944 + vertex -622.542 116.133 332.068 + vertex -614.702 111.103 327.461 + endloop + endfacet + facet normal -0.235849 -0.832024 0.502107 + outer loop + vertex -607.317 109.357 328.036 + vertex -613.102 113.355 331.944 + vertex -614.702 111.103 327.461 + endloop + endfacet + facet normal -0.239459 -0.833374 0.498145 + outer loop + vertex -606.495 111.903 332.691 + vertex -613.102 113.355 331.944 + vertex -607.317 109.357 328.036 + endloop + endfacet + facet normal -0.259738 -0.827167 0.498328 + outer loop + vertex -606.495 111.903 332.691 + vertex -607.317 109.357 328.036 + vertex -603.442 109.65 330.542 + endloop + endfacet + facet normal -0.245075 -0.843708 0.477594 + outer loop + vertex -603.846 108.057 327.521 + vertex -603.442 109.65 330.542 + vertex -607.317 109.357 328.036 + endloop + endfacet + facet normal -0.230887 -0.847612 0.477751 + outer loop + vertex -603.442 109.65 330.542 + vertex -603.846 108.057 327.521 + vertex -600.629 108.141 329.225 + endloop + endfacet + facet normal -0.267433 -0.743387 0.61307 + outer loop + vertex -666.557 128.275 330.381 + vertex -676.276 134.661 333.885 + vertex -676.91 132.117 330.523 + endloop + endfacet + facet normal -0.282445 -0.738523 0.612216 + outer loop + vertex -676.276 134.661 333.885 + vertex -686.702 138.671 333.912 + vertex -676.91 132.117 330.523 + endloop + endfacet + facet normal -0.284214 -0.710922 0.643283 + outer loop + vertex -686.702 138.671 333.912 + vertex -696.551 145.75 337.384 + vertex -697.103 142.82 333.902 + endloop + endfacet + facet normal -0.295312 -0.709326 0.640037 + outer loop + vertex -697.103 142.82 333.902 + vertex -706.959 150.055 337.373 + vertex -707.485 147.124 333.881 + endloop + endfacet + facet normal -0.304856 -0.706286 0.638923 + outer loop + vertex -706.959 150.055 337.373 + vertex -717.362 154.539 337.365 + vertex -707.485 147.124 333.881 + endloop + endfacet + facet normal -0.304631 -0.677119 0.669858 + outer loop + vertex -717.362 154.539 337.365 + vertex -727.247 162.477 340.894 + vertex -727.793 159.229 337.363 + endloop + endfacet + facet normal -0.316221 -0.673403 0.668231 + outer loop + vertex -727.247 162.477 340.894 + vertex -737.677 167.378 340.897 + vertex -727.793 159.229 337.363 + endloop + endfacet + facet normal -0.312993 -0.638873 0.702763 + outer loop + vertex -737.677 167.378 340.897 + vertex -747.504 176.021 344.378 + vertex -748.04 172.457 340.9 + endloop + endfacet + facet normal -0.325321 -0.634988 0.700683 + outer loop + vertex -747.504 176.021 344.378 + vertex -757.71 181.252 344.38 + vertex -748.04 172.457 340.9 + endloop + endfacet + facet normal -0.325303 -0.634975 0.700703 + outer loop + vertex -748.04 172.457 340.9 + vertex -757.71 181.252 344.38 + vertex -758.253 177.692 340.902 + endloop + endfacet + facet normal -0.338536 -0.630648 0.698339 + outer loop + vertex -757.71 181.252 344.38 + vertex -767.722 186.626 344.379 + vertex -758.253 177.692 340.902 + endloop + endfacet + facet normal -0.338005 -0.630305 0.698905 + outer loop + vertex -758.253 177.692 340.902 + vertex -767.722 186.626 344.379 + vertex -768.271 183.065 340.903 + endloop + endfacet + facet normal -0.367502 -0.654582 0.660654 + outer loop + vertex -768.83 179.816 337.373 + vertex -778.101 188.58 340.899 + vertex -778.662 185.333 337.37 + endloop + endfacet + facet normal -0.351201 -0.625836 0.696411 + outer loop + vertex -767.722 186.626 344.379 + vertex -777.549 192.137 344.377 + vertex -768.271 183.065 340.903 + endloop + endfacet + facet normal -0.381078 -0.649413 0.65806 + outer loop + vertex -778.101 188.58 340.899 + vertex -787.78 194.249 340.889 + vertex -778.662 185.333 337.37 + endloop + endfacet + facet normal -0.381862 -0.680192 0.625716 + outer loop + vertex -768.83 179.816 337.373 + vertex -778.662 185.333 337.37 + vertex -769.331 176.866 333.86 + endloop + endfacet + facet normal -0.367323 -0.685769 0.628327 + outer loop + vertex -759.311 171.497 333.859 + vertex -768.83 179.816 337.373 + vertex -769.331 176.866 333.86 + endloop + endfacet + facet normal -0.354383 -0.691493 0.629484 + outer loop + vertex -749.106 166.263 333.854 + vertex -758.815 174.439 337.37 + vertex -759.311 171.497 333.859 + endloop + endfacet + facet normal -0.340596 -0.695596 0.632567 + outer loop + vertex -738.743 161.187 333.852 + vertex -748.597 169.209 337.367 + vertex -749.106 166.263 333.854 + endloop + endfacet + facet normal -0.32862 -0.700264 0.63375 + outer loop + vertex -728.308 156.292 333.855 + vertex -738.23 164.125 337.364 + vertex -738.743 161.187 333.852 + endloop + endfacet + facet normal -0.327164 -0.726528 0.604253 + outer loop + vertex -717.88 151.603 333.863 + vertex -728.308 156.292 333.855 + vertex -718.295 148.996 330.503 + endloop + endfacet + facet normal -0.316501 -0.730058 0.605676 + outer loop + vertex -707.941 144.527 330.527 + vertex -717.88 151.603 333.863 + vertex -718.295 148.996 330.503 + endloop + endfacet + facet normal -0.312895 -0.750655 0.581906 + outer loop + vertex -697.603 140.24 330.555 + vertex -707.941 144.527 330.527 + vertex -698.069 138.076 327.513 + endloop + endfacet + facet normal -0.302546 -0.754177 0.582823 + outer loop + vertex -687.811 133.963 327.516 + vertex -697.603 140.24 330.555 + vertex -698.069 138.076 327.513 + endloop + endfacet + facet normal -0.289251 -0.757992 0.584621 + outer loop + vertex -677.545 129.994 327.449 + vertex -687.259 136.105 330.567 + vertex -687.811 133.963 327.516 + endloop + endfacet + facet normal -0.28103 -0.784299 0.55308 + outer loop + vertex -667.296 126.182 327.251 + vertex -677.545 129.994 327.449 + vertex -668.186 124.635 324.606 + endloop + endfacet + facet normal -0.264278 -0.810033 0.523454 + outer loop + vertex -658.031 121.012 324.127 + vertex -668.186 124.635 324.606 + vertex -659.454 120.125 322.034 + endloop + endfacet + facet normal -0.236123 -0.826369 0.511234 + outer loop + vertex -649.209 116.635 321.125 + vertex -658.031 121.012 324.127 + vertex -659.454 120.125 322.034 + endloop + endfacet + facet normal -0.24846 -0.836077 0.489125 + outer loop + vertex -647.818 117.549 323.394 + vertex -658.031 121.012 324.127 + vertex -649.209 116.635 321.125 + endloop + endfacet + facet normal -0.217073 -0.852054 0.476323 + outer loop + vertex -638.263 113.055 319.709 + vertex -647.818 117.549 323.394 + vertex -649.209 116.635 321.125 + endloop + endfacet + facet normal -0.243921 -0.869968 0.428553 + outer loop + vertex -638.132 114.432 322.579 + vertex -647.818 117.549 323.394 + vertex -638.263 113.055 319.709 + endloop + endfacet + facet normal -0.216156 -0.876391 0.430366 + outer loop + vertex -638.132 114.432 322.579 + vertex -638.263 113.055 319.709 + vertex -630.472 110.86 319.154 + endloop + endfacet + facet normal -0.229174 -0.883461 0.408626 + outer loop + vertex -629.242 111.669 321.593 + vertex -638.132 114.432 322.579 + vertex -630.472 110.86 319.154 + endloop + endfacet + facet normal -0.199642 -0.895516 0.397736 + outer loop + vertex -623.303 108.731 317.958 + vertex -629.242 111.669 321.593 + vertex -630.472 110.86 319.154 + endloop + endfacet + facet normal -0.223729 -0.903718 0.365019 + outer loop + vertex -620.994 109.056 320.179 + vertex -629.242 111.669 321.593 + vertex -623.303 108.731 317.958 + endloop + endfacet + facet normal -0.199967 -0.918026 0.342406 + outer loop + vertex -616.959 106.818 316.534 + vertex -620.994 109.056 320.179 + vertex -623.303 108.731 317.958 + endloop + endfacet + facet normal -0.228005 -0.921755 0.313657 + outer loop + vertex -614.991 107.006 318.517 + vertex -620.994 109.056 320.179 + vertex -616.959 106.818 316.534 + endloop + endfacet + facet normal -0.206376 -0.933481 0.293294 + outer loop + vertex -612.004 105.398 315.501 + vertex -614.991 107.006 318.517 + vertex -616.959 106.818 316.534 + endloop + endfacet + facet normal -0.209005 -0.933678 0.290795 + outer loop + vertex -610.872 106.11 318.6 + vertex -614.991 107.006 318.517 + vertex -612.004 105.398 315.501 + endloop + endfacet + facet normal -0.200174 -0.936415 0.288196 + outer loop + vertex -608.525 104.485 314.952 + vertex -610.872 106.11 318.6 + vertex -612.004 105.398 315.501 + endloop + endfacet + facet normal -0.227361 -0.93554 0.270317 + outer loop + vertex -607.71 105.293 318.433 + vertex -610.872 106.11 318.6 + vertex -608.525 104.485 314.952 + endloop + endfacet + facet normal -0.237919 -0.932404 0.272061 + outer loop + vertex -607.71 105.293 318.433 + vertex -608.525 104.485 314.952 + vertex -606.561 104.377 316.299 + endloop + endfacet + facet normal -0.199836 -0.93481 0.293591 + outer loop + vertex -606.561 104.377 316.299 + vertex -606.003 105.547 320.405 + vertex -607.71 105.293 318.433 + endloop + endfacet + facet normal -0.282182 -0.793329 0.539447 + outer loop + vertex -669.449 123.698 322.557 + vertex -678.336 128.421 324.854 + vertex -679.483 127.449 322.824 + endloop + endfacet + facet normal -0.300131 -0.784639 0.54246 + outer loop + vertex -679.483 127.449 322.824 + vertex -688.499 132.365 324.947 + vertex -689.467 131.333 322.918 + endloop + endfacet + facet normal -0.323705 -0.791626 0.518212 + outer loop + vertex -690.567 130.579 321.177 + vertex -699.308 135.304 322.934 + vertex -700.59 134.647 321.129 + endloop + endfacet + facet normal -0.332545 -0.813905 0.476417 + outer loop + vertex -690.567 130.579 321.177 + vertex -700.59 134.647 321.129 + vertex -693.286 130.99 319.979 + endloop + endfacet + facet normal -0.33573 -0.806862 0.486064 + outer loop + vertex -693.286 130.99 319.979 + vertex -689.692 129.73 320.371 + vertex -690.567 130.579 321.177 + endloop + endfacet + facet normal -0.336795 -0.818783 0.464935 + outer loop + vertex -698.726 132.908 319.418 + vertex -693.286 130.99 319.979 + vertex -700.59 134.647 321.129 + endloop + endfacet + facet normal -0.312392 -0.778082 0.544978 + outer loop + vertex -688.499 132.365 324.947 + vertex -698.59 136.428 324.962 + vertex -689.467 131.333 322.918 + endloop + endfacet + facet normal -0.320344 -0.76569 0.557763 + outer loop + vertex -698.59 136.428 324.962 + vertex -708.296 142.328 327.488 + vertex -708.615 140.618 324.958 + endloop + endfacet + facet normal -0.330617 -0.762127 0.556646 + outer loop + vertex -708.296 142.328 327.488 + vertex -718.539 146.753 327.463 + vertex -708.615 140.618 324.958 + endloop + endfacet + facet normal -0.336638 -0.745804 0.574848 + outer loop + vertex -718.539 146.753 327.463 + vertex -728.69 153.664 330.485 + vertex -728.864 151.402 327.448 + endloop + endfacet + facet normal -0.348619 -0.742253 0.572298 + outer loop + vertex -728.864 151.402 327.448 + vertex -739.101 158.546 330.478 + vertex -739.247 156.27 327.436 + endloop + endfacet + facet normal -0.361007 -0.737587 0.570648 + outer loop + vertex -739.247 156.27 327.436 + vertex -749.447 163.616 330.479 + vertex -749.59 161.323 327.425 + endloop + endfacet + facet normal -0.375925 -0.733214 0.566637 + outer loop + vertex -749.59 161.323 327.425 + vertex -759.646 168.84 330.48 + vertex -759.788 166.552 327.425 + endloop + endfacet + facet normal -0.390222 -0.727535 0.564287 + outer loop + vertex -759.788 166.552 327.425 + vertex -769.663 174.221 330.484 + vertex -769.806 171.919 327.418 + endloop + endfacet + facet normal -0.413759 -0.735339 0.536731 + outer loop + vertex -769.898 170.102 324.859 + vertex -779.638 177.448 327.416 + vertex -779.647 175.59 324.862 + endloop + endfacet + facet normal -0.418016 -0.742895 0.522848 + outer loop + vertex -769.898 170.102 324.859 + vertex -779.647 175.59 324.862 + vertex -770.262 168.901 322.862 + endloop + endfacet + facet normal -0.429472 -0.729403 0.532471 + outer loop + vertex -779.638 177.448 327.416 + vertex -789.299 183.13 327.407 + vertex -779.647 175.59 324.862 + endloop + endfacet + facet normal -0.430108 -0.729841 0.531355 + outer loop + vertex -779.647 175.59 324.862 + vertex -789.299 183.13 327.407 + vertex -789.285 181.27 324.863 + endloop + endfacet + facet normal -0.434554 -0.737384 0.517134 + outer loop + vertex -779.647 175.59 324.862 + vertex -789.285 181.27 324.863 + vertex -779.881 174.311 322.842 + endloop + endfacet + facet normal -0.446722 -0.723345 0.526509 + outer loop + vertex -789.299 183.13 327.407 + vertex -798.787 188.984 327.398 + vertex -789.285 181.27 324.863 + endloop + endfacet + facet normal -0.447132 -0.723613 0.525792 + outer loop + vertex -789.285 181.27 324.863 + vertex -798.787 188.984 327.398 + vertex -798.792 187.136 324.851 + endloop + endfacet + facet normal -0.451582 -0.730853 0.511788 + outer loop + vertex -789.285 181.27 324.863 + vertex -798.792 187.136 324.851 + vertex -789.642 180.078 322.845 + endloop + endfacet + facet normal -0.465649 -0.715906 0.52024 + outer loop + vertex -798.787 188.984 327.398 + vertex -808.128 195.061 327.4 + vertex -798.792 187.136 324.851 + endloop + endfacet + facet normal -0.468952 -0.717933 0.514447 + outer loop + vertex -798.792 187.136 324.851 + vertex -808.128 195.061 327.4 + vertex -808.172 193.262 324.851 + endloop + endfacet + facet normal -0.473184 -0.724414 0.501319 + outer loop + vertex -798.792 187.136 324.851 + vertex -808.172 193.262 324.851 + vertex -799.287 186.067 322.839 + endloop + endfacet + facet normal -0.490529 -0.708115 0.507893 + outer loop + vertex -808.128 195.061 327.4 + vertex -817.44 201.542 327.443 + vertex -808.172 193.262 324.851 + endloop + endfacet + facet normal -0.493985 -0.710069 0.501778 + outer loop + vertex -808.172 193.262 324.851 + vertex -817.44 201.542 327.443 + vertex -817.533 199.792 324.876 + endloop + endfacet + facet normal -0.498161 -0.716007 0.489049 + outer loop + vertex -808.172 193.262 324.851 + vertex -817.533 199.792 324.876 + vertex -808.743 192.276 322.824 + endloop + endfacet + facet normal -0.5183 -0.697856 0.494331 + outer loop + vertex -817.44 201.542 327.443 + vertex -826.873 208.6 327.516 + vertex -817.533 199.792 324.876 + endloop + endfacet + facet normal -0.521324 -0.699432 0.488892 + outer loop + vertex -817.533 199.792 324.876 + vertex -826.873 208.6 327.516 + vertex -826.998 206.895 324.944 + endloop + endfacet + facet normal -0.526134 -0.705703 0.474516 + outer loop + vertex -817.533 199.792 324.876 + vertex -826.998 206.895 324.944 + vertex -818.154 198.889 322.843 + endloop + endfacet + facet normal -0.543475 -0.6873 0.481928 + outer loop + vertex -826.873 208.6 327.516 + vertex -836.337 216.1 327.539 + vertex -826.998 206.895 324.944 + endloop + endfacet + facet normal -0.542589 -0.686859 0.483552 + outer loop + vertex -826.998 206.895 324.944 + vertex -836.337 216.1 327.539 + vertex -836.283 214.238 324.955 + endloop + endfacet + facet normal -0.547809 -0.693437 0.468027 + outer loop + vertex -826.998 206.895 324.944 + vertex -836.283 214.238 324.955 + vertex -827.495 205.92 322.917 + endloop + endfacet + facet normal -0.534312 -0.675817 0.507723 + outer loop + vertex -826.873 208.6 327.516 + vertex -836.185 218.273 330.592 + vertex -836.337 216.1 327.539 + endloop + endfacet + facet normal -0.552761 -0.665631 0.501389 + outer loop + vertex -836.185 218.273 330.592 + vertex -845.295 225.727 330.444 + vertex -836.337 216.1 327.539 + endloop + endfacet + facet normal -0.55434 -0.666303 0.498746 + outer loop + vertex -836.337 216.1 327.539 + vertex -845.295 225.727 330.444 + vertex -845.255 223.377 327.35 + endloop + endfacet + facet normal -0.569953 -0.657949 0.492196 + outer loop + vertex -845.295 225.727 330.444 + vertex -853.885 232.91 330.1 + vertex -845.255 223.377 327.35 + endloop + endfacet + facet normal -0.54004 -0.649411 0.535371 + outer loop + vertex -836.185 218.273 330.592 + vertex -844.777 227.978 333.698 + vertex -845.295 225.727 330.444 + endloop + endfacet + facet normal -0.552165 -0.64187 0.532088 + outer loop + vertex -844.777 227.978 333.698 + vertex -852.586 234.347 333.277 + vertex -845.295 225.727 330.444 + endloop + endfacet + facet normal -0.536554 -0.64799 0.540573 + outer loop + vertex -835.873 220.805 333.937 + vertex -844.777 227.978 333.698 + vertex -836.185 218.273 330.592 + endloop + endfacet + facet normal -0.518869 -0.657603 0.546199 + outer loop + vertex -826.775 210.836 330.578 + vertex -835.873 220.805 333.937 + vertex -836.185 218.273 330.592 + endloop + endfacet + facet normal -0.515698 -0.656258 0.5508 + outer loop + vertex -826.531 213.48 333.956 + vertex -835.873 220.805 333.937 + vertex -826.775 210.836 330.578 + endloop + endfacet + facet normal -0.492848 -0.667606 0.558035 + outer loop + vertex -817.401 203.855 330.505 + vertex -826.531 213.48 333.956 + vertex -826.775 210.836 330.578 + endloop + endfacet + facet normal -0.506109 -0.685062 0.523968 + outer loop + vertex -817.401 203.855 330.505 + vertex -826.775 210.836 330.578 + vertex -817.44 201.542 327.443 + endloop + endfacet + facet normal -0.490182 -0.666422 0.561786 + outer loop + vertex -817.167 206.533 333.886 + vertex -826.531 213.48 333.956 + vertex -817.401 203.855 330.505 + endloop + endfacet + facet normal -0.466881 -0.677196 0.568707 + outer loop + vertex -808.091 197.396 330.456 + vertex -817.167 206.533 333.886 + vertex -817.401 203.855 330.505 + endloop + endfacet + facet normal -0.479158 -0.694647 0.536538 + outer loop + vertex -808.091 197.396 330.456 + vertex -817.401 203.855 330.505 + vertex -808.128 195.061 327.4 + endloop + endfacet + facet normal -0.465813 -0.676689 0.570184 + outer loop + vertex -807.822 200.055 333.832 + vertex -817.167 206.533 333.886 + vertex -808.091 197.396 330.456 + endloop + endfacet + facet normal -0.445445 -0.685709 0.575658 + outer loop + vertex -798.722 191.303 330.448 + vertex -807.822 200.055 333.832 + vertex -808.091 197.396 330.456 + endloop + endfacet + facet normal -0.456938 -0.70334 0.544537 + outer loop + vertex -798.722 191.303 330.448 + vertex -808.091 197.396 330.456 + vertex -798.787 188.984 327.398 + endloop + endfacet + facet normal -0.443891 -0.684919 0.577795 + outer loop + vertex -798.402 193.946 333.827 + vertex -807.822 200.055 333.832 + vertex -798.722 191.303 330.448 + endloop + endfacet + facet normal -0.450366 -0.654713 0.60706 + outer loop + vertex -807.822 200.055 333.832 + vertex -816.732 209.492 337.4 + vertex -817.167 206.533 333.886 + endloop + endfacet + facet normal -0.472805 -0.64432 0.601088 + outer loop + vertex -816.732 209.492 337.4 + vertex -826.115 216.445 337.472 + vertex -817.167 206.533 333.886 + endloop + endfacet + facet normal -0.454097 -0.619477 0.640347 + outer loop + vertex -816.732 209.492 337.4 + vertex -825.591 219.712 341.004 + vertex -826.115 216.445 337.472 + endloop + endfacet + facet normal -0.477503 -0.60858 0.633736 + outer loop + vertex -825.591 219.712 341.004 + vertex -834.94 227.031 340.989 + vertex -826.115 216.445 337.472 + endloop + endfacet + facet normal -0.478233 -0.608903 0.632875 + outer loop + vertex -826.115 216.445 337.472 + vertex -834.94 227.031 340.989 + vertex -835.467 223.759 337.442 + endloop + endfacet + facet normal -0.497249 -0.63338 0.592936 + outer loop + vertex -826.115 216.445 337.472 + vertex -835.467 223.759 337.442 + vertex -826.531 213.48 333.956 + endloop + endfacet + facet normal -0.49801 -0.599197 0.626857 + outer loop + vertex -834.94 227.031 340.989 + vertex -844.068 234.335 340.719 + vertex -835.467 223.759 337.442 + endloop + endfacet + facet normal -0.498876 -0.599575 0.625805 + outer loop + vertex -835.467 223.759 337.442 + vertex -844.068 234.335 340.719 + vertex -844.454 230.91 337.13 + endloop + endfacet + facet normal -0.517007 -0.624106 0.585829 + outer loop + vertex -835.467 223.759 337.442 + vertex -844.454 230.91 337.13 + vertex -835.873 220.805 333.937 + endloop + endfacet + facet normal -0.512436 -0.593057 0.621042 + outer loop + vertex -844.068 234.335 340.719 + vertex -852.708 241.069 340.02 + vertex -844.454 230.91 337.13 + endloop + endfacet + facet normal -0.455501 -0.620122 0.638723 + outer loop + vertex -816.198 212.738 340.932 + vertex -825.591 219.712 341.004 + vertex -816.732 209.492 337.4 + endloop + endfacet + facet normal -0.450464 -0.65476 0.606936 + outer loop + vertex -807.349 202.987 337.347 + vertex -816.732 209.492 337.4 + vertex -807.822 200.055 333.832 + endloop + endfacet + facet normal -0.473842 -0.644781 0.599776 + outer loop + vertex -817.167 206.533 333.886 + vertex -826.115 216.445 337.472 + vertex -826.531 213.48 333.956 + endloop + endfacet + facet normal -0.498141 -0.633762 0.591778 + outer loop + vertex -826.531 213.48 333.956 + vertex -835.467 223.759 337.442 + vertex -835.873 220.805 333.937 + endloop + endfacet + facet normal -0.519201 -0.625039 0.582887 + outer loop + vertex -835.873 220.805 333.937 + vertex -844.454 230.91 337.13 + vertex -844.777 227.978 333.698 + endloop + endfacet + facet normal -0.530937 -0.618955 0.578792 + outer loop + vertex -844.454 230.91 337.13 + vertex -852.108 236.781 336.387 + vertex -844.777 227.978 333.698 + endloop + endfacet + facet normal -0.532785 -0.675141 0.510221 + outer loop + vertex -826.775 210.836 330.578 + vertex -836.185 218.273 330.592 + vertex -826.873 208.6 327.516 + endloop + endfacet + facet normal -0.509853 -0.686813 0.518012 + outer loop + vertex -817.44 201.542 327.443 + vertex -826.775 210.836 330.578 + vertex -826.873 208.6 327.516 + endloop + endfacet + facet normal -0.482068 -0.696116 0.532009 + outer loop + vertex -808.128 195.061 327.4 + vertex -817.401 203.855 330.505 + vertex -817.44 201.542 327.443 + endloop + endfacet + facet normal -0.45776 -0.703787 0.543268 + outer loop + vertex -798.787 188.984 327.398 + vertex -808.091 197.396 330.456 + vertex -808.128 195.061 327.4 + endloop + endfacet + facet normal -0.438944 -0.710704 0.549752 + outer loop + vertex -789.299 183.13 327.407 + vertex -798.722 191.303 330.448 + vertex -798.787 188.984 327.398 + endloop + endfacet + facet normal -0.437768 -0.710023 0.551567 + outer loop + vertex -789.199 185.445 330.466 + vertex -798.722 191.303 330.448 + vertex -789.299 183.13 327.407 + endloop + endfacet + facet normal -0.405802 -0.721771 0.560688 + outer loop + vertex -769.663 174.221 330.484 + vertex -779.51 179.754 330.479 + vertex -769.806 171.919 327.418 + endloop + endfacet + facet normal -0.421811 -0.716338 0.555819 + outer loop + vertex -779.638 177.448 327.416 + vertex -789.199 185.445 330.466 + vertex -789.299 183.13 327.407 + endloop + endfacet + facet normal -0.410757 -0.69792 0.586674 + outer loop + vertex -779.167 182.392 333.857 + vertex -788.854 188.082 333.845 + vertex -779.51 179.754 330.479 + endloop + endfacet + facet normal -0.426873 -0.692223 0.581899 + outer loop + vertex -789.199 185.445 330.466 + vertex -798.402 193.946 333.827 + vertex -798.722 191.303 330.448 + endloop + endfacet + facet normal -0.41235 -0.669655 0.617681 + outer loop + vertex -788.345 191.009 337.357 + vertex -797.899 196.877 337.341 + vertex -788.854 188.082 333.845 + endloop + endfacet + facet normal -0.430194 -0.663826 0.611775 + outer loop + vertex -798.402 193.946 333.827 + vertex -807.349 202.987 337.347 + vertex -807.822 200.055 333.832 + endloop + endfacet + facet normal -0.412936 -0.638436 0.649525 + outer loop + vertex -797.337 200.108 340.874 + vertex -806.795 206.232 340.881 + vertex -797.899 196.877 337.341 + endloop + endfacet + facet normal -0.433143 -0.630084 0.644501 + outer loop + vertex -807.349 202.987 337.347 + vertex -816.198 212.738 340.932 + vertex -816.732 209.492 337.4 + endloop + endfacet + facet normal -0.413238 -0.602653 0.682675 + outer loop + vertex -806.239 209.793 344.361 + vertex -815.646 216.297 344.409 + vertex -806.795 206.232 340.881 + endloop + endfacet + facet normal -0.537109 -0.543757 0.644858 + outer loop + vertex -858.697 247.41 340.832 + vertex -856.927 247.711 342.559 + vertex -861.601 253.27 343.354 + endloop + endfacet + facet normal -0.550206 -0.544996 0.632656 + outer loop + vertex -861.601 253.27 343.354 + vertex -862.62 250.506 340.087 + vertex -858.697 247.41 340.832 + endloop + endfacet + facet normal -0.562906 -0.53609 0.629082 + outer loop + vertex -861.601 253.27 343.354 + vertex -866.528 257.833 342.833 + vertex -862.62 250.506 340.087 + endloop + endfacet + facet normal -0.569549 -0.537067 0.622232 + outer loop + vertex -862.62 250.506 340.087 + vertex -866.528 257.833 342.833 + vertex -867.154 254.459 339.348 + endloop + endfacet + facet normal -0.587419 -0.526165 0.61489 + outer loop + vertex -866.528 257.833 342.833 + vertex -871.279 262.832 342.572 + vertex -867.154 254.459 339.348 + endloop + endfacet + facet normal -0.585651 -0.525998 0.616717 + outer loop + vertex -867.154 254.459 339.348 + vertex -871.279 262.832 342.572 + vertex -871.934 259.46 339.074 + endloop + endfacet + facet normal -0.606463 -0.512665 0.607764 + outer loop + vertex -871.279 262.832 342.572 + vertex -876.251 268.7 342.561 + vertex -871.934 259.46 339.074 + endloop + endfacet + facet normal -0.605053 -0.512567 0.60925 + outer loop + vertex -871.934 259.46 339.074 + vertex -876.251 268.7 342.561 + vertex -876.894 265.31 339.07 + endloop + endfacet + facet normal -0.631263 -0.495021 0.597044 + outer loop + vertex -876.251 268.7 342.561 + vertex -881.29 275.219 342.638 + vertex -876.894 265.31 339.07 + endloop + endfacet + facet normal -0.62935 -0.494927 0.599137 + outer loop + vertex -876.894 265.31 339.07 + vertex -881.29 275.219 342.638 + vertex -881.927 271.796 339.141 + endloop + endfacet + facet normal -0.662988 -0.471027 0.581877 + outer loop + vertex -881.29 275.219 342.638 + vertex -886.102 282.053 342.688 + vertex -881.927 271.796 339.141 + endloop + endfacet + facet normal -0.658217 -0.470966 0.587318 + outer loop + vertex -881.927 271.796 339.141 + vertex -886.102 282.053 342.688 + vertex -886.763 278.613 339.188 + endloop + endfacet + facet normal -0.562976 -0.569228 0.599198 + outer loop + vertex -858.037 243.984 338.197 + vertex -858.697 247.41 340.832 + vertex -862.62 250.506 340.087 + endloop + endfacet + facet normal -0.515967 -0.594655 0.616574 + outer loop + vertex -844.454 230.91 337.13 + vertex -852.708 241.069 340.02 + vertex -852.108 236.781 336.387 + endloop + endfacet + facet normal -0.567356 -0.584065 0.580496 + outer loop + vertex -857.306 240.587 335.493 + vertex -858.037 243.984 338.197 + vertex -862.456 246.355 336.263 + endloop + endfacet + facet normal -0.566327 -0.570353 0.594954 + outer loop + vertex -862.62 250.506 340.087 + vertex -862.456 246.355 336.263 + vertex -858.037 243.984 338.197 + endloop + endfacet + facet normal -0.585041 -0.561817 0.584884 + outer loop + vertex -862.62 250.506 340.087 + vertex -867.154 254.459 339.348 + vertex -862.456 246.355 336.263 + endloop + endfacet + facet normal -0.585895 -0.561941 0.583908 + outer loop + vertex -862.456 246.355 336.263 + vertex -867.154 254.459 339.348 + vertex -867.694 251.155 335.626 + endloop + endfacet + facet normal -0.606897 -0.548582 0.575095 + outer loop + vertex -867.154 254.459 339.348 + vertex -871.934 259.46 339.074 + vertex -867.694 251.155 335.626 + endloop + endfacet + facet normal -0.607494 -0.548612 0.574435 + outer loop + vertex -867.694 251.155 335.626 + vertex -871.934 259.46 339.074 + vertex -872.497 256.258 335.421 + endloop + endfacet + facet normal -0.629726 -0.533516 0.564629 + outer loop + vertex -871.934 259.46 339.074 + vertex -876.894 265.31 339.07 + vertex -872.497 256.258 335.421 + endloop + endfacet + facet normal -0.628159 -0.533474 0.566411 + outer loop + vertex -872.497 256.258 335.421 + vertex -876.894 265.31 339.07 + vertex -877.442 262.087 335.427 + endloop + endfacet + facet normal -0.65502 -0.514346 0.553531 + outer loop + vertex -876.894 265.31 339.07 + vertex -881.927 271.796 339.141 + vertex -877.442 262.087 335.427 + endloop + endfacet + facet normal -0.653058 -0.514331 0.555859 + outer loop + vertex -877.442 262.087 335.427 + vertex -881.927 271.796 339.141 + vertex -882.489 268.558 335.485 + endloop + endfacet + facet normal -0.685212 -0.489789 0.539065 + outer loop + vertex -881.927 271.796 339.141 + vertex -886.763 278.613 339.188 + vertex -882.489 268.558 335.485 + endloop + endfacet + facet normal -0.686058 -0.489761 0.538014 + outer loop + vertex -882.489 268.558 335.485 + vertex -886.763 278.613 339.188 + vertex -887.332 275.375 335.515 + endloop + endfacet + facet normal -0.53779 -0.62178 0.56936 + outer loop + vertex -844.777 227.978 333.698 + vertex -852.108 236.781 336.387 + vertex -852.586 234.347 333.277 + endloop + endfacet + facet normal -0.582825 -0.594356 0.554127 + outer loop + vertex -858.715 239.727 333.089 + vertex -857.306 240.587 335.493 + vertex -862.456 246.355 336.263 + endloop + endfacet + facet normal -0.55996 -0.644642 0.520463 + outer loop + vertex -845.295 225.727 330.444 + vertex -852.586 234.347 333.277 + vertex -853.885 232.91 330.1 + endloop + endfacet + facet normal -0.595414 -0.603993 0.529786 + outer loop + vertex -859.325 238.525 331.033 + vertex -858.715 239.727 333.089 + vertex -863.135 243.187 332.065 + endloop + endfacet + facet normal -0.645308 -0.624784 0.43957 + outer loop + vertex -858.882 236.392 328.651 + vertex -859.325 238.525 331.033 + vertex -863.135 243.187 332.065 + endloop + endfacet + facet normal -0.622167 -0.625798 0.47041 + outer loop + vertex -863.135 243.187 332.065 + vertex -863.607 240.502 327.871 + vertex -858.882 236.392 328.651 + endloop + endfacet + facet normal -0.635951 -0.615587 0.465423 + outer loop + vertex -863.135 243.187 332.065 + vertex -868.188 248.127 331.696 + vertex -863.607 240.502 327.871 + endloop + endfacet + facet normal -0.64102 -0.615307 0.458794 + outer loop + vertex -863.607 240.502 327.871 + vertex -868.188 248.127 331.696 + vertex -868.418 245.187 327.43 + endloop + endfacet + facet normal -0.66082 -0.600787 0.449858 + outer loop + vertex -868.188 248.127 331.696 + vertex -872.937 253.231 331.536 + vertex -868.418 245.187 327.43 + endloop + endfacet + facet normal -0.66202 -0.600652 0.448272 + outer loop + vertex -868.418 245.187 327.43 + vertex -872.937 253.231 331.536 + vertex -873.258 250.415 327.288 + endloop + endfacet + facet normal -0.684681 -0.58256 0.437991 + outer loop + vertex -872.937 253.231 331.536 + vertex -877.934 259.105 331.538 + vertex -873.258 250.415 327.288 + endloop + endfacet + facet normal -0.683574 -0.582711 0.439516 + outer loop + vertex -873.258 250.415 327.288 + vertex -877.934 259.105 331.538 + vertex -878.441 256.492 327.285 + endloop + endfacet + facet normal -0.710239 -0.558872 0.428045 + outer loop + vertex -877.934 259.105 331.538 + vertex -883.03 265.61 331.575 + vertex -878.441 256.492 327.285 + endloop + endfacet + facet normal -0.710231 -0.558874 0.428057 + outer loop + vertex -878.441 256.492 327.285 + vertex -883.03 265.61 331.575 + vertex -883.597 263.06 327.305 + endloop + endfacet + facet normal -0.573565 -0.659427 0.485983 + outer loop + vertex -845.255 223.377 327.35 + vertex -853.885 232.91 330.1 + vertex -852.314 228.906 326.52 + endloop + endfacet + facet normal -0.63616 -0.65323 0.410598 + outer loop + vertex -856.976 231.577 323.944 + vertex -858.882 236.392 328.651 + vertex -863.607 240.502 327.871 + endloop + endfacet + facet normal -0.562182 -0.676513 0.47569 + outer loop + vertex -836.337 216.1 327.539 + vertex -845.255 223.377 327.35 + vertex -836.283 214.238 324.955 + endloop + endfacet + facet normal -0.548877 -0.69404 0.465878 + outer loop + vertex -827.495 205.92 322.917 + vertex -836.283 214.238 324.955 + vertex -836.371 212.956 322.943 + endloop + endfacet + facet normal -0.528483 -0.707072 0.469847 + outer loop + vertex -818.154 198.889 322.843 + vertex -826.998 206.895 324.944 + vertex -827.495 205.92 322.917 + endloop + endfacet + facet normal -0.505375 -0.720547 0.474772 + outer loop + vertex -808.743 192.276 322.824 + vertex -817.533 199.792 324.876 + vertex -818.154 198.889 322.843 + endloop + endfacet + facet normal -0.479081 -0.728456 0.489728 + outer loop + vertex -799.287 186.067 322.839 + vertex -808.172 193.262 324.851 + vertex -808.743 192.276 322.824 + endloop + endfacet + facet normal -0.456335 -0.734364 0.502461 + outer loop + vertex -789.642 180.078 322.845 + vertex -798.792 187.136 324.851 + vertex -799.287 186.067 322.839 + endloop + endfacet + facet normal -0.436284 -0.738735 0.513737 + outer loop + vertex -779.881 174.311 322.842 + vertex -789.285 181.27 324.863 + vertex -789.642 180.078 322.845 + endloop + endfacet + facet normal -0.419609 -0.744194 0.519715 + outer loop + vertex -770.262 168.901 322.862 + vertex -779.647 175.59 324.862 + vertex -779.881 174.311 322.842 + endloop + endfacet + facet normal -0.403623 -0.74976 0.524355 + outer loop + vertex -760.626 163.711 322.858 + vertex -769.898 170.102 324.859 + vertex -770.262 168.901 322.862 + endloop + endfacet + facet normal -0.388331 -0.755695 0.527374 + outer loop + vertex -750.564 158.529 322.841 + vertex -759.96 164.766 324.861 + vertex -760.626 163.711 322.858 + endloop + endfacet + facet normal -0.374172 -0.761368 0.529447 + outer loop + vertex -740.102 153.403 322.865 + vertex -749.77 159.55 324.871 + vertex -750.564 158.529 322.841 + endloop + endfacet + facet normal -0.360251 -0.765542 0.533071 + outer loop + vertex -729.542 148.466 322.911 + vertex -739.394 154.481 324.891 + vertex -740.102 153.403 322.865 + endloop + endfacet + facet normal -0.348195 -0.769381 0.53555 + outer loop + vertex -719.184 143.8 322.941 + vertex -728.977 149.605 324.914 + vertex -729.542 148.466 322.911 + endloop + endfacet + facet normal -0.33602 -0.772047 0.539477 + outer loop + vertex -709.154 139.433 322.94 + vertex -718.705 144.987 324.939 + vertex -719.184 143.8 322.941 + endloop + endfacet + facet normal -0.329849 -0.787256 0.520987 + outer loop + vertex -699.308 135.304 322.934 + vertex -709.154 139.433 322.94 + vertex -700.59 134.647 321.129 + endloop + endfacet + facet normal -0.33929 -0.819107 0.462544 + outer loop + vertex -704.544 135.485 319.714 + vertex -698.726 132.908 319.418 + vertex -700.59 134.647 321.129 + endloop + endfacet + facet normal -0.330529 -0.806086 0.490893 + outer loop + vertex -689.692 129.73 320.371 + vertex -688.617 129.352 320.474 + vertex -690.567 130.579 321.177 + endloop + endfacet + facet normal -0.310854 -0.793397 0.523347 + outer loop + vertex -688.617 129.352 320.474 + vertex -687.73 129.026 320.507 + vertex -690.567 130.579 321.177 + endloop + endfacet + facet normal -0.321651 -0.863857 0.387676 + outer loop + vertex -685.858 127.779 319.401 + vertex -677.399 123.608 317.125 + vertex -674.652 123.475 319.109 + endloop + endfacet + facet normal -0.306377 -0.812971 0.495188 + outer loop + vertex -680.882 126.262 320.202 + vertex -677.67 125.102 320.285 + vertex -681.06 126.932 321.191 + endloop + endfacet + facet normal -0.303675 -0.813479 0.496018 + outer loop + vertex -685.298 128.139 320.576 + vertex -680.882 126.262 320.202 + vertex -681.06 126.932 321.191 + endloop + endfacet + facet normal -0.287645 -0.796459 0.531895 + outer loop + vertex -677.67 125.102 320.285 + vertex -674.62 124.036 320.338 + vertex -681.06 126.932 321.191 + endloop + endfacet + facet normal -0.279474 -0.820457 0.498743 + outer loop + vertex -674.62 124.036 320.338 + vertex -669.7 122.018 319.775 + vertex -671.241 123.287 321 + endloop + endfacet + facet normal -0.27471 -0.819202 0.503431 + outer loop + vertex -669.7 122.018 319.775 + vertex -665.033 120.439 319.752 + vertex -671.241 123.287 321 + endloop + endfacet + facet normal -0.290229 -0.863756 0.411938 + outer loop + vertex -665.033 120.439 319.752 + vertex -669.7 122.018 319.775 + vertex -665.018 119.758 318.335 + endloop + endfacet + facet normal -0.285056 -0.865136 0.412653 + outer loop + vertex -660.091 118.408 318.909 + vertex -665.033 120.439 319.752 + vertex -665.018 119.758 318.335 + endloop + endfacet + facet normal -0.257984 -0.831889 0.49133 + outer loop + vertex -665.033 120.439 319.752 + vertex -660.091 118.408 318.909 + vertex -661.458 119.756 320.474 + endloop + endfacet + facet normal -0.310001 -0.87546 0.370769 + outer loop + vertex -677.399 123.608 317.125 + vertex -668.374 120.256 316.757 + vertex -674.652 123.475 319.109 + endloop + endfacet + facet normal -0.285103 -0.866948 0.408799 + outer loop + vertex -660.091 118.408 318.909 + vertex -665.018 119.758 318.335 + vertex -659.487 117.509 317.424 + endloop + endfacet + facet normal -0.257335 -0.8318 0.491821 + outer loop + vertex -660.091 118.408 318.909 + vertex -655.314 117.131 319.249 + vertex -661.458 119.756 320.474 + endloop + endfacet + facet normal -0.246697 -0.888728 0.386396 + outer loop + vertex -655.755 116.334 317.265 + vertex -654.761 116.583 318.474 + vertex -656.976 116.939 317.877 + endloop + endfacet + facet normal -0.237725 -0.893908 0.38002 + outer loop + vertex -652.483 116.079 318.74 + vertex -652.999 115.847 317.874 + vertex -649.012 114.883 318.1 + endloop + endfacet + facet normal -0.235548 -0.899485 0.368027 + outer loop + vertex -649.589 115.324 318.806 + vertex -649.012 114.883 318.1 + vertex -644.004 113.509 317.946 + endloop + endfacet + facet normal -0.222891 -0.921466 0.318152 + outer loop + vertex -644.144 113.305 317.244 + vertex -645.105 113.229 316.349 + vertex -638.547 111.573 316.146 + endloop + endfacet + facet normal -0.233649 -0.915345 0.32795 + outer loop + vertex -649.763 114.722 317.198 + vertex -651.209 114.657 315.985 + vertex -645.105 113.229 316.349 + endloop + endfacet + facet normal -0.240982 -0.930393 0.276217 + outer loop + vertex -651.209 114.657 315.985 + vertex -655.906 115.643 315.21 + vertex -653.087 114.719 314.558 + endloop + endfacet + facet normal -0.212461 -0.948966 0.233074 + outer loop + vertex -632.442 109.944 315.473 + vertex -632.71 109.826 314.748 + vertex -626.724 108.273 313.885 + endloop + endfacet + facet normal -0.200942 -0.964376 0.172052 + outer loop + vertex -618.367 105.937 311.154 + vertex -616.174 105.321 310.263 + vertex -616.424 105.433 310.599 + endloop + endfacet + facet normal -0.195887 -0.964716 0.175931 + outer loop + vertex -616.174 105.321 310.263 + vertex -615.245 105.061 309.874 + vertex -616.424 105.433 310.599 + endloop + endfacet + facet normal -0.192993 -0.964455 0.180502 + outer loop + vertex -615.245 105.061 309.874 + vertex -613.807 104.666 309.299 + vertex -616.424 105.433 310.599 + endloop + endfacet + facet normal -0.232416 -0.969068 0.0830046 + outer loop + vertex -611.846 104.134 308.576 + vertex -613.807 104.666 309.299 + vertex -613.072 104.416 308.438 + endloop + endfacet + facet normal -0.225178 -0.970055 0.0910426 + outer loop + vertex -616.585 105.389 310.055 + vertex -621.777 106.686 311.032 + vertex -617.444 105.497 309.083 + endloop + endfacet + facet normal -0.222092 -0.970095 0.0979303 + outer loop + vertex -621.777 106.686 311.032 + vertex -623.421 106.937 309.787 + vertex -617.444 105.497 309.083 + endloop + endfacet + facet normal -0.222305 -0.970016 0.0982277 + outer loop + vertex -621.777 106.686 311.032 + vertex -628.336 108.273 311.854 + vertex -623.421 106.937 309.787 + endloop + endfacet + facet normal -0.22202 -0.970013 0.0989035 + outer loop + vertex -628.336 108.273 311.854 + vertex -630.849 108.696 310.367 + vertex -623.421 106.937 309.787 + endloop + endfacet + facet normal -0.223658 -0.96933 0.101862 + outer loop + vertex -628.336 108.273 311.854 + vertex -635.953 110.081 312.337 + vertex -630.849 108.696 310.367 + endloop + endfacet + facet normal -0.22747 -0.969424 0.0920525 + outer loop + vertex -635.953 110.081 312.337 + vertex -638.955 110.633 310.733 + vertex -630.849 108.696 310.367 + endloop + endfacet + facet normal -0.231105 -0.967838 0.0994021 + outer loop + vertex -635.953 110.081 312.337 + vertex -643.907 111.989 312.419 + vertex -638.955 110.633 310.733 + endloop + endfacet + facet normal -0.239587 -0.968003 0.0746196 + outer loop + vertex -643.907 111.989 312.419 + vertex -646.944 112.622 310.887 + vertex -638.955 110.633 310.733 + endloop + endfacet + facet normal -0.243269 -0.966439 0.0825604 + outer loop + vertex -643.907 111.989 312.419 + vertex -651.362 113.846 312.202 + vertex -646.944 112.622 310.887 + endloop + endfacet + facet normal -0.25708 -0.965737 0.03553 + outer loop + vertex -651.362 113.846 312.202 + vertex -654.117 114.531 310.879 + vertex -646.944 112.622 310.887 + endloop + endfacet + facet normal -0.258688 -0.965166 0.0391728 + outer loop + vertex -651.362 113.846 312.202 + vertex -657.518 115.481 311.811 + vertex -654.117 114.531 310.879 + endloop + endfacet + facet normal -0.260887 -0.961088 0.09082 + outer loop + vertex -655.24 114.985 313.109 + vertex -657.518 115.481 311.811 + vertex -651.362 113.846 312.202 + endloop + endfacet + facet normal -0.256405 -0.963068 0.082195 + outer loop + vertex -655.24 114.985 313.109 + vertex -659.821 116.147 312.437 + vertex -657.518 115.481 311.811 + endloop + endfacet + facet normal -0.262282 -0.95543 0.135505 + outer loop + vertex -657.823 115.784 313.742 + vertex -659.821 116.147 312.437 + vertex -655.24 114.985 313.109 + endloop + endfacet + facet normal -0.242462 -0.964723 0.102574 + outer loop + vertex -657.823 115.784 313.742 + vertex -660.663 116.414 312.957 + vertex -659.821 116.147 312.437 + endloop + endfacet + facet normal -0.261472 -0.947253 0.185321 + outer loop + vertex -658.799 116.166 314.319 + vertex -660.663 116.414 312.957 + vertex -657.823 115.784 313.742 + endloop + endfacet + facet normal -0.232606 -0.971114 0.0532208 + outer loop + vertex -613.072 104.416 308.438 + vertex -611.921 104.082 307.376 + vertex -609.406 103.505 307.843 + endloop + endfacet + facet normal -0.23474 -0.972058 -0.00122922 + outer loop + vertex -611.222 103.865 306.129 + vertex -609.798 103.523 305.076 + vertex -610.052 103.583 306.265 + endloop + endfacet + facet normal -0.0845434 -0.975501 0.203102 + outer loop + vertex -610.656 103.721 305.674 + vertex -609.798 103.523 305.076 + vertex -611.222 103.865 306.129 + endloop + endfacet + facet normal -0.242559 -0.970123 0.00511718 + outer loop + vertex -610.656 103.721 305.674 + vertex -611.222 103.865 306.129 + vertex -611.374 103.9 305.556 + endloop + endfacet + facet normal -0.232874 -0.972443 -0.0111235 + outer loop + vertex -610.656 103.721 305.674 + vertex -610.079 103.596 304.574 + vertex -609.798 103.523 305.076 + endloop + endfacet + facet normal -0.259705 -0.964248 0.0527149 + outer loop + vertex -612.479 104.188 306.16 + vertex -611.158 103.854 306.566 + vertex -611.449 103.942 306.743 + endloop + endfacet + facet normal -0.233057 -0.971386 -0.0457613 + outer loop + vertex -615.382 104.938 305.033 + vertex -612.479 104.188 306.16 + vertex -613.649 104.484 305.838 + endloop + endfacet + facet normal -0.0117085 -0.881741 -0.471588 + outer loop + vertex -613.649 104.484 305.838 + vertex -614.998 104.822 305.239 + vertex -615.382 104.938 305.033 + endloop + endfacet + facet normal -0.160068 -0.957925 -0.238239 + outer loop + vertex -614.998 104.822 305.239 + vertex -615.909 105.058 304.902 + vertex -615.382 104.938 305.033 + endloop + endfacet + facet normal -0.103735 -0.903565 -0.415703 + outer loop + vertex -615.909 105.058 304.902 + vertex -618.05 105.635 304.182 + vertex -615.382 104.938 305.033 + endloop + endfacet + facet normal -0.251129 -0.967953 0.00117437 + outer loop + vertex -615.909 105.058 304.902 + vertex -614.998 104.822 305.239 + vertex -616.572 105.23 305.067 + endloop + endfacet + facet normal -0.255175 -0.966758 -0.0162959 + outer loop + vertex -618.05 105.635 304.182 + vertex -615.909 105.058 304.902 + vertex -616.572 105.23 305.067 + endloop + endfacet + facet normal -0.260892 -0.965349 -0.00611131 + outer loop + vertex -616.572 105.23 305.067 + vertex -621.404 106.547 303.427 + vertex -618.05 105.635 304.182 + endloop + endfacet + facet normal -0.253455 -0.967031 0.0247454 + outer loop + vertex -614.998 104.822 305.239 + vertex -613.649 104.484 305.838 + vertex -616.572 105.23 305.067 + endloop + endfacet + facet normal -0.248369 -0.968642 0.00674279 + outer loop + vertex -611.222 103.865 306.129 + vertex -613.145 104.354 305.559 + vertex -611.374 103.9 305.556 + endloop + endfacet + facet normal -0.23945 -0.970796 -0.0147624 + outer loop + vertex -610.656 103.721 305.674 + vertex -611.374 103.9 305.556 + vertex -610.079 103.596 304.574 + endloop + endfacet + facet normal -0.242117 -0.970077 -0.0181434 + outer loop + vertex -610.77 103.769 304.291 + vertex -612.178 104.104 305.15 + vertex -611.851 104.043 304.081 + endloop + endfacet + facet normal -0.256005 -0.964446 -0.0656174 + outer loop + vertex -609.754 103.768 299.592 + vertex -608.017 103.341 299.096 + vertex -610.057 103.667 302.263 + endloop + endfacet + facet normal -0.261955 -0.960923 -0.0894795 + outer loop + vertex -608.017 103.341 299.096 + vertex -609.754 103.768 299.592 + vertex -606.925 103.412 295.136 + endloop + endfacet + facet normal -0.280006 -0.95535 -0.0943563 + outer loop + vertex -606.047 103.162 295.062 + vertex -608.017 103.341 299.096 + vertex -606.925 103.412 295.136 + endloop + endfacet + facet normal -0.246187 -0.96842 -0.0394431 + outer loop + vertex -611.851 104.043 304.081 + vertex -613.167 104.394 303.659 + vertex -611.382 103.984 302.587 + endloop + endfacet + facet normal -0.253928 -0.966187 -0.0447515 + outer loop + vertex -613.167 104.394 303.659 + vertex -614.951 104.845 304.057 + vertex -614.629 104.813 302.905 + endloop + endfacet + facet normal -0.260314 -0.962111 -0.0811176 + outer loop + vertex -612.213 104.463 299.236 + vertex -609.754 103.768 299.592 + vertex -612.444 104.302 301.889 + endloop + endfacet + facet normal -0.258333 -0.961508 -0.0936272 + outer loop + vertex -609.754 103.768 299.592 + vertex -612.213 104.463 299.236 + vertex -608.577 103.879 295.201 + endloop + endfacet + facet normal -0.262371 -0.962709 -0.0659798 + outer loop + vertex -613.817 104.679 301.646 + vertex -614.629 104.813 302.905 + vertex -615.93 105.273 301.38 + endloop + endfacet + facet normal -0.284757 -0.947296 -0.14678 + outer loop + vertex -613.617 105.441 294.43 + vertex -617.965 106.272 297.501 + vertex -616.651 106.429 293.94 + endloop + endfacet + facet normal -0.259914 -0.960809 -0.0963924 + outer loop + vertex -615.93 105.273 301.38 + vertex -618.975 106.205 300.299 + vertex -614.907 105.31 298.247 + endloop + endfacet + facet normal -0.277441 -0.949715 -0.145145 + outer loop + vertex -617.965 106.272 297.501 + vertex -622.117 107.182 299.486 + vertex -621.098 107.283 296.873 + endloop + endfacet + facet normal -0.261125 -0.960542 -0.0957776 + outer loop + vertex -619.185 106.081 302.116 + vertex -622.431 107.042 301.321 + vertex -618.975 106.205 300.299 + endloop + endfacet + facet normal -0.265831 -0.957002 -0.116105 + outer loop + vertex -625.35 107.97 300.36 + vertex -622.431 107.042 301.321 + vertex -626.756 108.269 301.108 + endloop + endfacet + facet normal -0.276475 -0.950986 -0.138519 + outer loop + vertex -625.35 107.97 300.36 + vertex -626.756 108.269 301.108 + vertex -628.485 108.97 299.751 + endloop + endfacet + facet normal -0.273326 -0.951143 -0.143595 + outer loop + vertex -622.117 107.182 299.486 + vertex -625.191 108.172 298.778 + vertex -621.098 107.283 296.873 + endloop + endfacet + facet normal -0.277642 -0.949791 -0.144266 + outer loop + vertex -617.965 106.272 297.501 + vertex -621.098 107.283 296.873 + vertex -616.651 106.429 293.94 + endloop + endfacet + facet normal -0.283936 -0.946876 -0.151017 + outer loop + vertex -613.617 105.441 294.43 + vertex -616.651 106.429 293.94 + vertex -612.451 105.833 289.777 + endloop + endfacet + facet normal -0.294621 -0.943224 -0.153388 + outer loop + vertex -610.097 104.919 290.88 + vertex -613.617 105.441 294.43 + vertex -612.451 105.833 289.777 + endloop + endfacet + facet normal -0.310206 -0.935014 -0.171819 + outer loop + vertex -612.829 107.019 284.009 + vertex -607.931 105.303 284.502 + vertex -612.451 105.833 289.777 + endloop + endfacet + facet normal -0.310311 -0.935108 -0.171113 + outer loop + vertex -607.931 105.303 284.502 + vertex -612.829 107.019 284.009 + vertex -607.206 106.663 275.756 + endloop + endfacet + facet normal -0.329452 -0.92596 -0.18455 + outer loop + vertex -607.206 106.663 275.756 + vertex -612.829 107.019 284.009 + vertex -611.944 108.432 275.341 + endloop + endfacet + facet normal -0.329906 -0.926428 -0.181368 + outer loop + vertex -607.206 106.663 275.756 + vertex -611.944 108.432 275.341 + vertex -606.4 108.026 267.33 + endloop + endfacet + facet normal -0.335054 -0.924541 -0.181555 + outer loop + vertex -603.338 106.793 267.956 + vertex -607.206 106.663 275.756 + vertex -606.4 108.026 267.33 + endloop + endfacet + facet normal -0.335177 -0.924594 -0.18106 + outer loop + vertex -603.338 106.793 267.956 + vertex -606.4 108.026 267.33 + vertex -602.642 108.136 259.81 + endloop + endfacet + facet normal -0.33419 -0.924956 -0.181036 + outer loop + vertex -601.1 107.349 260.983 + vertex -603.338 106.793 267.956 + vertex -602.642 108.136 259.81 + endloop + endfacet + facet normal -0.33498 -0.924882 -0.179949 + outer loop + vertex -601.1 107.349 260.983 + vertex -602.642 108.136 259.81 + vertex -600.52 108.73 252.806 + endloop + endfacet + facet normal -0.321058 -0.929836 -0.179798 + outer loop + vertex -601.1 107.349 260.983 + vertex -600.52 108.73 252.806 + vertex -600.283 108.101 255.638 + endloop + endfacet + facet normal -0.335592 -0.924628 -0.180113 + outer loop + vertex -600.52 108.73 252.806 + vertex -602.642 108.136 259.81 + vertex -602.034 109.459 251.883 + endloop + endfacet + facet normal -0.332122 -0.925817 -0.18044 + outer loop + vertex -601.848 106.068 268.933 + vertex -603.338 106.793 267.956 + vertex -601.1 107.349 260.983 + endloop + endfacet + facet normal -0.342946 -0.92179 -0.18081 + outer loop + vertex -601.848 106.068 268.933 + vertex -601.1 107.349 260.983 + vertex -600.934 106.722 263.867 + endloop + endfacet + facet normal -0.34402 -0.920473 -0.185418 + outer loop + vertex -602.642 108.136 259.81 + vertex -606.4 108.026 267.33 + vertex -605.693 109.39 259.245 + endloop + endfacet + facet normal -0.344986 -0.920107 -0.185441 + outer loop + vertex -606.4 108.026 267.33 + vertex -611.157 109.865 267.054 + vertex -605.693 109.39 259.245 + endloop + endfacet + facet normal -0.322555 -0.930148 -0.175451 + outer loop + vertex -604.146 105.484 276.381 + vertex -607.206 106.663 275.756 + vertex -603.338 106.793 267.956 + endloop + endfacet + facet normal -0.344241 -0.919111 -0.191659 + outer loop + vertex -606.4 108.026 267.33 + vertex -611.944 108.432 275.341 + vertex -611.157 109.865 267.054 + endloop + endfacet + facet normal -0.341171 -0.920274 -0.191569 + outer loop + vertex -611.944 108.432 275.341 + vertex -617.85 110.691 275.003 + vertex -611.157 109.865 267.054 + endloop + endfacet + facet normal -0.355786 -0.911863 -0.204749 + outer loop + vertex -611.157 109.865 267.054 + vertex -617.85 110.691 275.003 + vertex -617.104 112.217 266.911 + endloop + endfacet + facet normal -0.339984 -0.918629 -0.201325 + outer loop + vertex -611.944 108.432 275.341 + vertex -618.784 109.191 283.426 + vertex -617.85 110.691 275.003 + endloop + endfacet + facet normal -0.333801 -0.920953 -0.201052 + outer loop + vertex -618.784 109.191 283.426 + vertex -625.144 111.63 282.813 + vertex -617.85 110.691 275.003 + endloop + endfacet + facet normal -0.353186 -0.909179 -0.220574 + outer loop + vertex -617.85 110.691 275.003 + vertex -625.144 111.63 282.813 + vertex -624.275 113.274 274.645 + endloop + endfacet + facet normal -0.304268 -0.935036 -0.182014 + outer loop + vertex -615.767 106.812 290.193 + vertex -619.764 107.481 293.434 + vertex -618.477 107.922 289.019 + endloop + endfacet + facet normal -0.320871 -0.929043 -0.184176 + outer loop + vertex -612.829 107.019 284.009 + vertex -618.784 109.191 283.426 + vertex -611.944 108.432 275.341 + endloop + endfacet + facet normal -0.318701 -0.926722 -0.199038 + outer loop + vertex -622.069 109.054 289.324 + vertex -624.806 110.241 288.179 + vertex -618.784 109.191 283.426 + endloop + endfacet + facet normal -0.297384 -0.937586 -0.180263 + outer loop + vertex -619.764 107.481 293.434 + vertex -622.907 108.58 292.905 + vertex -618.477 107.922 289.019 + endloop + endfacet + facet normal -0.314045 -0.926019 -0.20944 + outer loop + vertex -622.069 109.054 289.324 + vertex -626.03 109.705 292.383 + vertex -624.806 110.241 288.179 + endloop + endfacet + facet normal -0.291286 -0.938889 -0.18341 + outer loop + vertex -624.178 108.321 296.252 + vertex -627.227 109.383 295.654 + vertex -622.907 108.58 292.905 + endloop + endfacet + facet normal -0.307912 -0.926238 -0.217426 + outer loop + vertex -626.03 109.705 292.383 + vertex -630.247 110.482 295.049 + vertex -629.068 110.839 291.856 + endloop + endfacet + facet normal -0.289602 -0.938001 -0.190486 + outer loop + vertex -628.167 109.173 298.117 + vertex -631.149 110.225 297.472 + vertex -627.227 109.383 295.654 + endloop + endfacet + facet normal -0.307068 -0.924944 -0.224028 + outer loop + vertex -630.247 110.482 295.049 + vertex -634.295 111.415 296.745 + vertex -633.096 111.591 294.375 + endloop + endfacet + facet normal -0.296235 -0.934007 -0.199689 + outer loop + vertex -631.208 109.924 298.967 + vertex -634.448 111.068 298.423 + vertex -631.149 110.225 297.472 + endloop + endfacet + facet normal -0.316515 -0.918229 -0.238063 + outer loop + vertex -634.295 111.415 296.745 + vertex -638.485 112.679 297.437 + vertex -637.254 112.722 295.635 + endloop + endfacet + facet normal -0.31989 -0.919092 -0.230085 + outer loop + vertex -634.295 111.415 296.745 + vertex -637.254 112.722 295.635 + vertex -633.096 111.591 294.375 + endloop + endfacet + facet normal -0.3089 -0.925834 -0.217745 + outer loop + vertex -630.247 110.482 295.049 + vertex -633.096 111.591 294.375 + vertex -629.068 110.839 291.856 + endloop + endfacet + facet normal -0.309977 -0.927609 -0.208459 + outer loop + vertex -626.03 109.705 292.383 + vertex -629.068 110.839 291.856 + vertex -624.806 110.241 288.179 + endloop + endfacet + facet normal -0.331262 -0.918291 -0.216813 + outer loop + vertex -625.144 111.63 282.813 + vertex -618.784 109.191 283.426 + vertex -624.806 110.241 288.179 + endloop + endfacet + facet normal -0.329847 -0.913518 -0.238088 + outer loop + vertex -628.339 111.407 288.475 + vertex -631.953 111.961 291.356 + vertex -631.055 112.666 287.408 + endloop + endfacet + facet normal -0.330802 -0.913134 -0.238236 + outer loop + vertex -631.953 111.961 291.356 + vertex -635.006 113.163 290.989 + vertex -631.055 112.666 287.408 + endloop + endfacet + facet normal -0.354183 -0.896828 -0.265055 + outer loop + vertex -634.685 113.955 287.714 + vertex -638.514 114.633 290.536 + vertex -637.584 115.452 286.521 + endloop + endfacet + facet normal -0.33504 -0.908925 -0.2482 + outer loop + vertex -635.258 112.556 293.551 + vertex -638.739 113.813 293.648 + vertex -635.006 113.163 290.989 + endloop + endfacet + facet normal -0.349101 -0.896259 -0.273585 + outer loop + vertex -643.128 115.714 293.02 + vertex -638.739 113.813 293.648 + vertex -642.836 114.738 295.844 + endloop + endfacet + facet normal -0.365101 -0.884426 -0.290676 + outer loop + vertex -646.677 117.643 291.608 + vertex -643.128 115.714 293.02 + vertex -649.343 117.758 294.607 + endloop + endfacet + facet normal -0.389582 -0.872167 -0.295891 + outer loop + vertex -646.677 117.643 291.608 + vertex -652.805 120.338 291.735 + vertex -645.321 118.56 287.121 + endloop + endfacet + facet normal -0.399302 -0.860597 -0.316119 + outer loop + vertex -645.321 118.56 287.121 + vertex -652.805 120.338 291.735 + vertex -651.7 121.812 286.325 + endloop + endfacet + facet normal -0.362491 -0.893153 -0.266229 + outer loop + vertex -638.514 114.633 290.536 + vertex -642.025 116.36 289.522 + vertex -637.584 115.452 286.521 + endloop + endfacet + facet normal -0.382684 -0.882552 -0.273229 + outer loop + vertex -640.771 116.808 286.408 + vertex -645.321 118.56 287.121 + vertex -638.218 117.181 281.626 + endloop + endfacet + facet normal -0.392268 -0.873652 -0.287851 + outer loop + vertex -638.218 117.181 281.626 + vertex -645.321 118.56 287.121 + vertex -644.38 120.321 280.493 + endloop + endfacet + facet normal -0.359852 -0.89809 -0.252867 + outer loop + vertex -634.685 113.955 287.714 + vertex -637.584 115.452 286.521 + vertex -631.621 114.279 282.201 + endloop + endfacet + facet normal -0.351334 -0.909909 -0.220523 + outer loop + vertex -625.144 111.63 282.813 + vertex -631.621 114.279 282.201 + vertex -624.275 113.274 274.645 + endloop + endfacet + facet normal -0.355236 -0.91208 -0.204739 + outer loop + vertex -617.85 110.691 275.003 + vertex -624.275 113.274 274.645 + vertex -617.104 112.217 266.911 + endloop + endfacet + facet normal -0.356899 -0.91397 -0.193087 + outer loop + vertex -611.157 109.865 267.054 + vertex -617.104 112.217 266.911 + vertex -610.479 111.282 259.091 + endloop + endfacet + facet normal -0.355401 -0.914558 -0.193064 + outer loop + vertex -605.693 109.39 259.245 + vertex -611.157 109.865 267.054 + vertex -610.479 111.282 259.091 + endloop + endfacet + facet normal -0.345213 -0.921051 -0.180255 + outer loop + vertex -602.642 108.136 259.81 + vertex -605.693 109.39 259.245 + vertex -602.034 109.459 251.883 + endloop + endfacet + facet normal -0.33889 -0.924485 -0.17459 + outer loop + vertex -600.52 108.73 252.806 + vertex -602.034 109.459 251.883 + vertex -600.13 110.001 245.322 + endloop + endfacet + facet normal -0.313427 -0.93339 -0.174775 + outer loop + vertex -600.52 108.73 252.806 + vertex -600.13 110.001 245.322 + vertex -599.784 109.522 247.259 + endloop + endfacet + facet normal -0.35794 -0.916899 -0.176562 + outer loop + vertex -601.573 110.769 244.051 + vertex -605.109 110.742 251.36 + vertex -604.668 112.085 243.49 + endloop + endfacet + facet normal -0.377359 -0.910431 -0.169454 + outer loop + vertex -604.371 113.404 235.562 + vertex -609.478 114.056 243.431 + vertex -609.149 115.39 235.531 + endloop + endfacet + facet normal -0.364989 -0.914131 -0.176484 + outer loop + vertex -605.109 110.742 251.36 + vertex -609.924 112.682 251.269 + vertex -604.668 112.085 243.49 + endloop + endfacet + facet normal -0.376298 -0.905496 -0.196156 + outer loop + vertex -609.924 112.682 251.269 + vertex -616.451 113.703 259.075 + vertex -615.894 115.151 251.326 + endloop + endfacet + facet normal -0.383332 -0.902551 -0.196111 + outer loop + vertex -616.451 113.703 259.075 + vertex -622.883 116.453 258.991 + vertex -615.894 115.151 251.326 + endloop + endfacet + facet normal -0.410028 -0.887047 -0.212189 + outer loop + vertex -622.31 117.949 251.316 + vertex -629.257 119.37 258.798 + vertex -628.661 120.913 251.196 + endloop + endfacet + facet normal -0.425308 -0.879885 -0.211932 + outer loop + vertex -629.257 119.37 258.798 + vertex -635.364 122.376 258.574 + vertex -628.661 120.913 251.196 + endloop + endfacet + facet normal -0.389721 -0.895871 -0.213381 + outer loop + vertex -623.548 114.902 266.72 + vertex -629.986 117.773 266.424 + vertex -622.883 116.453 258.991 + endloop + endfacet + facet normal -0.422215 -0.87536 -0.23554 + outer loop + vertex -629.257 119.37 258.798 + vertex -636.18 120.746 266.094 + vertex -635.364 122.376 258.574 + endloop + endfacet + facet normal -0.437161 -0.867986 -0.235562 + outer loop + vertex -636.18 120.746 266.094 + vertex -642.089 123.79 265.844 + vertex -635.364 122.376 258.574 + endloop + endfacet + facet normal -0.447688 -0.859408 -0.246967 + outer loop + vertex -635.364 122.376 258.574 + vertex -642.089 123.79 265.844 + vertex -641.198 125.465 258.402 + endloop + endfacet + facet normal -0.465017 -0.850159 -0.246959 + outer loop + vertex -642.089 123.79 265.844 + vertex -647.742 126.923 265.702 + vertex -641.198 125.465 258.402 + endloop + endfacet + facet normal -0.460081 -0.842726 -0.279532 + outer loop + vertex -642.089 123.79 265.844 + vertex -648.964 125.172 272.993 + vertex -647.742 126.923 265.702 + endloop + endfacet + facet normal -0.478673 -0.832117 -0.280097 + outer loop + vertex -648.964 125.172 272.993 + vertex -654.437 128.368 272.85 + vertex -647.742 126.923 265.702 + endloop + endfacet + facet normal -0.4907 -0.820321 -0.293747 + outer loop + vertex -647.742 126.923 265.702 + vertex -654.437 128.368 272.85 + vertex -653.147 130.189 265.61 + endloop + endfacet + facet normal -0.515233 -0.804954 -0.294251 + outer loop + vertex -654.437 128.368 272.85 + vertex -659.601 131.742 272.664 + vertex -653.147 130.189 265.61 + endloop + endfacet + facet normal -0.507001 -0.794548 -0.33413 + outer loop + vertex -654.437 128.368 272.85 + vertex -661.164 129.861 279.508 + vertex -659.601 131.742 272.664 + endloop + endfacet + facet normal -0.494165 -0.809167 -0.317882 + outer loop + vertex -655.889 126.556 279.72 + vertex -661.164 129.861 279.508 + vertex -654.437 128.368 272.85 + endloop + endfacet + facet normal -0.485674 -0.798096 -0.356599 + outer loop + vertex -655.889 126.556 279.72 + vertex -662.462 127.967 285.514 + vertex -661.164 129.861 279.508 + endloop + endfacet + facet normal -0.507838 -0.784021 -0.356947 + outer loop + vertex -662.462 127.967 285.514 + vertex -667.899 131.526 285.433 + vertex -661.164 129.861 279.508 + endloop + endfacet + facet normal -0.52243 -0.763706 -0.379237 + outer loop + vertex -661.164 129.861 279.508 + vertex -667.899 131.526 285.433 + vertex -666.109 133.429 279.135 + endloop + endfacet + facet normal -0.549844 -0.743373 -0.380879 + outer loop + vertex -667.899 131.526 285.433 + vertex -672.992 135.566 284.9 + vertex -666.109 133.429 279.135 + endloop + endfacet + facet normal -0.55958 -0.726556 -0.398732 + outer loop + vertex -666.109 133.429 279.135 + vertex -672.992 135.566 284.9 + vertex -670.113 136.964 278.313 + endloop + endfacet + facet normal -0.469787 -0.817185 -0.33393 + outer loop + vertex -657.276 124.89 285.749 + vertex -662.462 127.967 285.514 + vertex -655.889 126.556 279.72 + endloop + endfacet + facet normal -0.472168 -0.822622 -0.31678 + outer loop + vertex -648.964 125.172 272.993 + vertex -655.889 126.556 279.72 + vertex -654.437 128.368 272.85 + endloop + endfacet + facet normal -0.457196 -0.837874 -0.298227 + outer loop + vertex -650.341 123.435 279.984 + vertex -655.889 126.556 279.72 + vertex -648.964 125.172 272.993 + endloop + endfacet + facet normal -0.446934 -0.854537 -0.264605 + outer loop + vertex -643.196 122.079 273.239 + vertex -648.964 125.172 272.993 + vertex -642.089 123.79 265.844 + endloop + endfacet + facet normal -0.39503 -0.888271 -0.234363 + outer loop + vertex -630.79 116.072 274.226 + vertex -637.136 119.032 273.704 + vertex -629.986 117.773 266.424 + endloop + endfacet + facet normal -0.432816 -0.8619 -0.264194 + outer loop + vertex -636.18 120.746 266.094 + vertex -643.196 122.079 273.239 + vertex -642.089 123.79 265.844 + endloop + endfacet + facet normal -0.400053 -0.878855 -0.259946 + outer loop + vertex -638.218 117.181 281.626 + vertex -644.38 120.321 280.493 + vertex -637.136 119.032 273.704 + endloop + endfacet + facet normal -0.44132 -0.846674 -0.297286 + outer loop + vertex -643.196 122.079 273.239 + vertex -650.341 123.435 279.984 + vertex -648.964 125.172 272.993 + endloop + endfacet + facet normal -0.406162 -0.867194 -0.288109 + outer loop + vertex -645.321 118.56 287.121 + vertex -651.7 121.812 286.325 + vertex -644.38 120.321 280.493 + endloop + endfacet + facet normal -0.450338 -0.828594 -0.332608 + outer loop + vertex -650.341 123.435 279.984 + vertex -657.276 124.89 285.749 + vertex -655.889 126.556 279.72 + endloop + endfacet + facet normal -0.41814 -0.851131 -0.317387 + outer loop + vertex -652.805 120.338 291.735 + vertex -658.852 123.729 290.609 + vertex -651.7 121.812 286.325 + endloop + endfacet + facet normal -0.475608 -0.785046 -0.396863 + outer loop + vertex -668.262 129.274 290.234 + vertex -662.932 126.358 289.615 + vertex -666.157 126.512 293.174 + endloop + endfacet + facet normal -0.499316 -0.736636 -0.456126 + outer loop + vertex -675.312 133.668 290.855 + vertex -668.262 129.274 290.234 + vertex -673.007 130.38 293.642 + endloop + endfacet + facet normal -0.599793 -0.661431 -0.450286 + outer loop + vertex -677.305 138.105 286.55 + vertex -679.024 140.134 285.859 + vertex -675.076 138.717 282.683 + endloop + endfacet + facet normal -0.630309 -0.613875 -0.475256 + outer loop + vertex -677.251 141.206 281.984 + vertex -680.702 142.015 285.516 + vertex -679.104 143.1 281.996 + endloop + endfacet + facet normal -0.639753 -0.603232 -0.476264 + outer loop + vertex -680.702 142.015 285.516 + vertex -682.011 143.412 285.506 + vertex -679.104 143.1 281.996 + endloop + endfacet + facet normal -0.585995 -0.643211 -0.492838 + outer loop + vertex -680.74 139.153 289.181 + vertex -682.593 141.102 288.839 + vertex -679.024 140.134 285.859 + endloop + endfacet + facet normal -0.672845 -0.558585 -0.485039 + outer loop + vertex -681.542 145.832 282.078 + vertex -683.188 145.117 285.185 + vertex -681.507 146.001 281.835 + endloop + endfacet + facet normal -0.67103 -0.556436 -0.489997 + outer loop + vertex -681.189 145.322 282.175 + vertex -683.278 144.857 285.563 + vertex -681.542 145.832 282.078 + endloop + endfacet + facet normal -0.664663 -0.562791 -0.491416 + outer loop + vertex -680.383 144.43 282.105 + vertex -682.875 144.325 285.596 + vertex -681.189 145.322 282.175 + endloop + endfacet + facet normal -0.657937 -0.574443 -0.486965 + outer loop + vertex -682.011 143.412 285.506 + vertex -682.875 144.325 285.596 + vertex -680.383 144.43 282.105 + endloop + endfacet + facet normal -0.649547 -0.5847 -0.486019 + outer loop + vertex -679.104 143.1 281.996 + vertex -682.011 143.412 285.506 + vertex -680.383 144.43 282.105 + endloop + endfacet + facet normal -0.650419 -0.633921 -0.418448 + outer loop + vertex -677.251 141.206 281.984 + vertex -679.104 143.1 281.996 + vertex -675.933 142.691 277.687 + endloop + endfacet + facet normal -0.692148 -0.607981 -0.388962 + outer loop + vertex -678.017 144.253 278.706 + vertex -678.801 145.532 278.102 + vertex -675.364 144.853 273.047 + endloop + endfacet + facet normal -0.688815 -0.613671 -0.38593 + outer loop + vertex -677.357 147.106 273.023 + vertex -675.364 144.853 273.047 + vertex -678.801 145.532 278.102 + endloop + endfacet + facet normal -0.697007 -0.604649 -0.385463 + outer loop + vertex -679.842 146.29 278.796 + vertex -677.357 147.106 273.023 + vertex -678.801 145.532 278.102 + endloop + endfacet + facet normal -0.729163 -0.560225 -0.393025 + outer loop + vertex -679.842 146.29 278.796 + vertex -679.774 146.871 277.84 + vertex -677.357 147.106 273.023 + endloop + endfacet + facet normal -0.710849 -0.588475 -0.385215 + outer loop + vertex -677.799 148.447 271.789 + vertex -677.357 147.106 273.023 + vertex -679.774 146.871 277.84 + endloop + endfacet + facet normal -0.720591 -0.576469 -0.385268 + outer loop + vertex -680.065 146.842 278.428 + vertex -677.799 148.447 271.789 + vertex -679.774 146.871 277.84 + endloop + endfacet + facet normal -0.634424 -0.6496 -0.418959 + outer loop + vertex -673.23 140.104 277.604 + vertex -677.251 141.206 281.984 + vertex -675.933 142.691 277.687 + endloop + endfacet + facet normal -0.534496 -0.775829 -0.335265 + outer loop + vertex -661.164 129.861 279.508 + vertex -666.109 133.429 279.135 + vertex -659.601 131.742 272.664 + endloop + endfacet + facet normal -0.525621 -0.793689 -0.306235 + outer loop + vertex -653.147 130.189 265.61 + vertex -659.601 131.742 272.664 + vertex -658.24 133.609 265.49 + endloop + endfacet + facet normal -0.496462 -0.828848 -0.257947 + outer loop + vertex -647.742 126.923 265.702 + vertex -653.147 130.189 265.61 + vertex -646.799 128.662 258.3 + endloop + endfacet + facet normal -0.475441 -0.841027 -0.258128 + outer loop + vertex -641.198 125.465 258.402 + vertex -647.742 126.923 265.702 + vertex -646.799 128.662 258.3 + endloop + endfacet + facet normal -0.451343 -0.86481 -0.219986 + outer loop + vertex -635.364 122.376 258.574 + vertex -641.198 125.465 258.402 + vertex -634.747 123.972 251.034 + endloop + endfacet + facet normal -0.433343 -0.873857 -0.220427 + outer loop + vertex -628.661 120.913 251.196 + vertex -635.364 122.376 258.574 + vertex -634.747 123.972 251.034 + endloop + endfacet + facet normal -0.41209 -0.89065 -0.192156 + outer loop + vertex -622.31 117.949 251.316 + vertex -628.661 120.913 251.196 + vertex -621.867 119.412 243.586 + endloop + endfacet + facet normal -0.398816 -0.896595 -0.19252 + outer loop + vertex -615.446 116.565 243.54 + vertex -622.31 117.949 251.316 + vertex -621.867 119.412 243.586 + endloop + endfacet + facet normal -0.384594 -0.907437 -0.16925 + outer loop + vertex -609.478 114.056 243.431 + vertex -615.446 116.565 243.54 + vertex -609.149 115.39 235.531 + endloop + endfacet + facet normal -0.378541 -0.913005 -0.152081 + outer loop + vertex -604.371 113.404 235.562 + vertex -609.149 115.39 235.531 + vertex -604.139 114.634 227.603 + endloop + endfacet + facet normal -0.404668 -0.906737 -0.118622 + outer loop + vertex -608.612 118.739 211.489 + vertex -614.704 120.379 219.735 + vertex -614.555 121.369 211.665 + endloop + endfacet + facet normal -0.396324 -0.907924 -0.136386 + outer loop + vertex -608.924 116.646 227.583 + vertex -614.883 119.223 227.74 + vertex -608.744 117.771 219.571 + endloop + endfacet + facet normal -0.416468 -0.897829 -0.143031 + outer loop + vertex -614.704 120.379 219.735 + vertex -621.302 122.146 227.854 + vertex -621.112 123.33 219.87 + endloop + endfacet + facet normal -0.406804 -0.899743 -0.158031 + outer loop + vertex -615.124 117.939 235.674 + vertex -621.543 120.825 235.765 + vertex -614.883 119.223 227.74 + endloop + endfacet + facet normal -0.42565 -0.886065 -0.183603 + outer loop + vertex -621.543 120.825 235.765 + vertex -628.222 122.427 243.522 + vertex -627.904 123.884 235.75 + endloop + endfacet + facet normal -0.444932 -0.876742 -0.182644 + outer loop + vertex -628.222 122.427 243.522 + vertex -634.307 125.538 243.41 + vertex -627.904 123.884 235.75 + endloop + endfacet + facet normal -0.469666 -0.857317 -0.210765 + outer loop + vertex -634.307 125.538 243.41 + vertex -640.558 127.121 250.902 + vertex -640.111 128.739 243.321 + endloop + endfacet + facet normal -0.491607 -0.845246 -0.209481 + outer loop + vertex -640.558 127.121 250.902 + vertex -646.128 130.38 250.82 + vertex -640.111 128.739 243.321 + endloop + endfacet + facet normal -0.519799 -0.818545 -0.244525 + outer loop + vertex -646.128 130.38 250.82 + vertex -652.156 131.995 258.23 + vertex -651.435 133.768 250.76 + endloop + endfacet + facet normal -0.548006 -0.800417 -0.242943 + outer loop + vertex -652.156 131.995 258.23 + vertex -657.202 135.474 258.15 + vertex -651.435 133.768 250.76 + endloop + endfacet + facet normal -0.583743 -0.759232 -0.287769 + outer loop + vertex -657.202 135.474 258.15 + vertex -662.914 137.145 265.326 + vertex -661.855 139.084 258.064 + endloop + endfacet + facet normal -0.627729 -0.719554 -0.296982 + outer loop + vertex -661.855 139.084 258.064 + vertex -667.101 140.7 265.237 + vertex -666.043 142.748 258.039 + endloop + endfacet + facet normal -0.606197 -0.763227 -0.223627 + outer loop + vertex -656.422 137.301 250.693 + vertex -661.027 140.979 250.626 + vertex -655.837 139.042 243.166 + endloop + endfacet + facet normal -0.569478 -0.790048 -0.226977 + outer loop + vertex -650.906 135.471 243.222 + vertex -656.422 137.301 250.693 + vertex -655.837 139.042 243.166 + endloop + endfacet + facet normal -0.534521 -0.822525 -0.194268 + outer loop + vertex -645.649 132.045 243.266 + vertex -650.906 135.471 243.222 + vertex -645.293 133.616 235.634 + endloop + endfacet + facet normal -0.507484 -0.838981 -0.196395 + outer loop + vertex -639.78 130.277 235.65 + vertex -645.649 132.045 243.266 + vertex -645.293 133.616 235.634 + endloop + endfacet + facet normal -0.480413 -0.860779 -0.168115 + outer loop + vertex -633.99 127.038 235.692 + vertex -639.78 130.277 235.65 + vertex -633.74 128.425 227.876 + endloop + endfacet + facet normal -0.457175 -0.873065 -0.169554 + outer loop + vertex -627.661 125.24 227.886 + vertex -633.99 127.038 235.692 + vertex -633.74 128.425 227.876 + endloop + endfacet + facet normal -0.433545 -0.889833 -0.142254 + outer loop + vertex -621.302 122.146 227.854 + vertex -627.661 125.24 227.886 + vertex -621.112 123.33 219.87 + endloop + endfacet + facet normal -0.417409 -0.901005 -0.118154 + outer loop + vertex -614.704 120.379 219.735 + vertex -621.112 123.33 219.87 + vertex -614.555 121.369 211.665 + endloop + endfacet + facet normal -0.405133 -0.909474 -0.0934014 + outer loop + vertex -608.612 118.739 211.489 + vertex -614.555 121.369 211.665 + vertex -608.491 119.521 203.35 + endloop + endfacet + facet normal -0.396134 -0.915561 -0.0694732 + outer loop + vertex -603.719 117.461 203.284 + vertex -608.491 119.521 203.35 + vertex -603.623 118.04 195.108 + endloop + endfacet + facet normal -0.385043 -0.920265 -0.0696761 + outer loop + vertex -600.52 116.726 195.327 + vertex -603.719 117.461 203.284 + vertex -603.623 118.04 195.108 + endloop + endfacet + facet normal -0.414815 -0.909473 -0.0280674 + outer loop + vertex -608.313 120.743 178.886 + vertex -614.283 123.209 187.24 + vertex -614.244 123.441 179.129 + endloop + endfacet + facet normal -0.41102 -0.910343 -0.048361 + outer loop + vertex -608.412 120.118 195.184 + vertex -614.348 122.788 195.385 + vertex -608.34 120.52 187.016 + endloop + endfacet + facet normal -0.430133 -0.901262 -0.0520763 + outer loop + vertex -614.283 123.209 187.24 + vertex -620.742 125.809 195.582 + vertex -620.678 126.248 187.466 + endloop + endfacet + facet normal -0.425074 -0.902253 -0.0724648 + outer loop + vertex -614.436 122.174 203.539 + vertex -620.835 125.175 203.709 + vertex -614.348 122.788 195.385 + endloop + endfacet + facet normal -0.449565 -0.889906 -0.0771871 + outer loop + vertex -620.742 125.809 195.582 + vertex -627.179 128.346 203.827 + vertex -627.081 128.999 195.728 + endloop + endfacet + facet normal -0.443223 -0.891053 -0.0978691 + outer loop + vertex -620.958 124.346 211.815 + vertex -627.304 127.493 211.905 + vertex -620.835 125.175 203.709 + endloop + endfacet + facet normal -0.472443 -0.87534 -0.102846 + outer loop + vertex -627.179 128.346 203.827 + vertex -633.376 130.734 211.971 + vertex -633.249 131.611 203.921 + endloop + endfacet + facet normal -0.464603 -0.876936 -0.122996 + outer loop + vertex -627.461 126.45 219.931 + vertex -633.54 129.666 219.966 + vertex -627.304 127.493 211.905 + endloop + endfacet + facet normal -0.491288 -0.857766 -0.151243 + outer loop + vertex -633.54 129.666 219.966 + vertex -639.519 131.695 227.88 + vertex -639.314 132.966 220.009 + endloop + endfacet + facet normal -0.516916 -0.842879 -0.149507 + outer loop + vertex -639.519 131.695 227.88 + vertex -645.016 135.062 227.902 + vertex -639.314 132.966 220.009 + endloop + endfacet + facet normal -0.5475 -0.817812 -0.177277 + outer loop + vertex -645.016 135.062 227.902 + vertex -650.513 137.07 235.616 + vertex -650.223 138.544 227.921 + endloop + endfacet + facet normal -0.582324 -0.794108 -0.174046 + outer loop + vertex -650.513 137.07 235.616 + vertex -655.411 140.668 235.587 + vertex -650.223 138.544 227.921 + endloop + endfacet + facet normal -0.623593 -0.754933 -0.202998 + outer loop + vertex -655.411 140.668 235.587 + vertex -660.401 142.764 243.121 + vertex -659.951 144.422 235.576 + endloop + endfacet + facet normal -0.592968 -0.790183 -0.154916 + outer loop + vertex -650.004 139.871 220.116 + vertex -655.106 142.169 227.923 + vertex -654.879 143.523 220.147 + endloop + endfacet + facet normal -0.555634 -0.821505 -0.128065 + outer loop + vertex -644.803 136.361 220.066 + vertex -650.004 139.871 220.116 + vertex -644.637 137.485 212.134 + endloop + endfacet + facet normal -0.526277 -0.840299 -0.130114 + outer loop + vertex -639.149 134.061 212.047 + vertex -644.803 136.361 220.066 + vertex -644.637 137.485 212.134 + endloop + endfacet + facet normal -0.497829 -0.86129 -0.101715 + outer loop + vertex -633.376 130.734 211.971 + vertex -639.149 134.061 212.047 + vertex -633.249 131.611 203.921 + endloop + endfacet + facet normal -0.47325 -0.877602 -0.0764843 + outer loop + vertex -627.179 128.346 203.827 + vertex -633.249 131.611 203.921 + vertex -627.081 128.999 195.728 + endloop + endfacet + facet normal -0.449835 -0.891613 -0.0517113 + outer loop + vertex -620.742 125.809 195.582 + vertex -627.081 128.999 195.728 + vertex -620.678 126.248 187.466 + endloop + endfacet + facet normal -0.429853 -0.902466 -0.0279387 + outer loop + vertex -614.283 123.209 187.24 + vertex -620.678 126.248 187.466 + vertex -614.244 123.441 179.129 + endloop + endfacet + facet normal -0.414193 -0.910175 -0.00510399 + outer loop + vertex -608.313 120.743 178.886 + vertex -614.244 123.441 179.129 + vertex -608.302 120.784 170.791 + endloop + endfacet + facet normal -0.401687 -0.915627 0.0165854 + outer loop + vertex -603.529 118.689 170.725 + vertex -608.302 120.784 170.791 + vertex -603.547 118.55 162.629 + endloop + endfacet + facet normal -0.388024 -0.921499 0.0166572 + outer loop + vertex -600.467 117.26 163.019 + vertex -603.529 118.689 170.725 + vertex -603.547 118.55 162.629 + endloop + endfacet + facet normal -0.412851 -0.908933 0.0582647 + outer loop + vertex -608.441 119.845 146.402 + vertex -614.313 123.055 154.86 + vertex -614.382 122.564 146.712 + endloop + endfacet + facet normal -0.414144 -0.909442 0.0374227 + outer loop + vertex -608.327 120.649 162.696 + vertex -614.265 123.365 162.972 + vertex -608.371 120.335 154.565 + endloop + endfacet + facet normal -0.431348 -0.901435 0.0368063 + outer loop + vertex -614.313 123.055 154.86 + vertex -620.655 126.432 163.26 + vertex -620.699 126.123 155.162 + endloop + endfacet + facet normal -0.431438 -0.902007 0.0156416 + outer loop + vertex -614.242 123.494 171.051 + vertex -620.636 126.557 171.324 + vertex -614.265 123.365 162.972 + endloop + endfacet + facet normal -0.454345 -0.890713 0.0142129 + outer loop + vertex -620.655 126.432 163.26 + vertex -626.969 129.786 171.542 + vertex -626.985 129.665 163.495 + endloop + endfacet + facet normal -0.453264 -0.891347 -0.00716404 + outer loop + vertex -620.644 126.496 179.383 + vertex -626.978 129.715 179.581 + vertex -620.636 126.557 171.324 + endloop + endfacet + facet normal -0.480977 -0.876684 -0.0092518 + outer loop + vertex -626.969 129.786 171.542 + vertex -633.041 133.03 179.749 + vertex -633.027 133.107 171.73 + endloop + endfacet + facet normal -0.478528 -0.877538 -0.0306358 + outer loop + vertex -627.018 129.456 187.642 + vertex -633.079 132.756 187.787 + vertex -626.978 129.715 179.581 + endloop + endfacet + facet normal -0.508882 -0.860189 -0.0333829 + outer loop + vertex -633.041 133.03 179.749 + vertex -638.846 136.146 187.94 + vertex -638.8 136.431 179.925 + endloop + endfacet + facet normal -0.50501 -0.861373 -0.0547855 + outer loop + vertex -633.152 132.286 195.85 + vertex -638.916 135.657 195.978 + vertex -633.079 132.756 187.787 + endloop + endfacet + facet normal -0.536969 -0.841611 -0.0579329 + outer loop + vertex -638.846 136.146 187.94 + vertex -644.397 139.125 196.118 + vertex -644.324 139.63 188.103 + endloop + endfacet + facet normal -0.531672 -0.843209 -0.0795235 + outer loop + vertex -639.016 134.961 204.024 + vertex -644.505 138.412 204.139 + vertex -638.916 135.657 195.978 + endloop + endfacet + facet normal -0.563767 -0.818943 -0.107236 + outer loop + vertex -644.505 138.412 204.139 + vertex -649.832 141.021 212.211 + vertex -649.693 141.97 204.242 + endloop + endfacet + facet normal -0.599858 -0.793213 -0.1048 + outer loop + vertex -649.832 141.021 212.211 + vertex -654.706 144.7 212.27 + vertex -649.693 141.97 204.242 + endloop + endfacet + facet normal -0.642962 -0.754735 -0.130292 + outer loop + vertex -654.706 144.7 212.27 + vertex -659.402 147.333 220.193 + vertex -659.22 148.533 212.341 + endloop + endfacet + facet normal -0.606078 -0.791073 -0.0829032 + outer loop + vertex -649.589 142.705 196.247 + vertex -654.564 145.67 204.327 + vertex -654.457 146.423 196.357 + endloop + endfacet + facet normal -0.567687 -0.821274 -0.05693 + outer loop + vertex -644.397 139.125 196.118 + vertex -649.589 142.705 196.247 + vertex -644.324 139.63 188.103 + endloop + endfacet + facet normal -0.537047 -0.842909 -0.0329301 + outer loop + vertex -638.846 136.146 187.94 + vertex -644.324 139.63 188.103 + vertex -638.8 136.431 179.925 + endloop + endfacet + facet normal -0.508596 -0.860957 -0.00914845 + outer loop + vertex -633.041 133.03 179.749 + vertex -638.8 136.431 179.925 + vertex -633.027 133.107 171.73 + endloop + endfacet + facet normal -0.480393 -0.876941 0.0140567 + outer loop + vertex -626.969 129.786 171.542 + vertex -633.027 133.107 171.73 + vertex -626.985 129.665 163.495 + endloop + endfacet + facet normal -0.453431 -0.890543 0.0365114 + outer loop + vertex -620.655 126.432 163.26 + vertex -626.985 129.665 163.495 + vertex -620.699 126.123 155.162 + endloop + endfacet + facet normal -0.430103 -0.90092 0.0579285 + outer loop + vertex -614.313 123.055 154.86 + vertex -620.699 126.123 155.162 + vertex -614.382 122.564 146.712 + endloop + endfacet + facet normal -0.411409 -0.908074 0.0783866 + outer loop + vertex -608.441 119.845 146.402 + vertex -614.382 122.564 146.712 + vertex -608.551 119.191 138.239 + endloop + endfacet + facet normal -0.396887 -0.91268 0.0974472 + outer loop + vertex -603.772 117.097 138.096 + vertex -608.551 119.191 138.239 + vertex -603.896 116.283 129.965 + endloop + endfacet + facet normal -0.383626 -0.916235 0.115518 + outer loop + vertex -600.798 115.019 130.233 + vertex -603.896 116.283 129.965 + vertex -600.941 114.056 122.114 + endloop + endfacet + facet normal -0.354645 -0.927731 0.116372 + outer loop + vertex -599.393 113.572 122.97 + vertex -600.798 115.019 130.233 + vertex -600.941 114.056 122.114 + endloop + endfacet + facet normal -0.364363 -0.924277 0.113805 + outer loop + vertex -599.244 114.515 131.113 + vertex -600.798 115.019 130.233 + vertex -599.393 113.572 122.97 + endloop + endfacet + facet normal -0.305007 -0.945362 0.115161 + outer loop + vertex -599.244 114.515 131.113 + vertex -599.393 113.572 122.97 + vertex -598.862 113.781 126.097 + endloop + endfacet + facet normal -0.311406 -0.943158 0.116101 + outer loop + vertex -598.955 113.377 122.565 + vertex -598.862 113.781 126.097 + vertex -599.393 113.572 122.97 + endloop + endfacet + facet normal -0.362214 -0.922561 0.132976 + outer loop + vertex -599.393 113.572 122.97 + vertex -600.941 114.056 122.114 + vertex -599.563 112.445 114.692 + endloop + endfacet + facet normal -0.366933 -0.91411 0.172521 + outer loop + vertex -601.611 110.356 98.2512 + vertex -604.405 112.94 106.001 + vertex -604.726 111.563 98.022 + endloop + endfacet + facet normal -0.376551 -0.913795 0.152275 + outer loop + vertex -601.084 112.946 114.129 + vertex -604.182 114.19 113.935 + vertex -601.283 111.714 106.242 + endloop + endfacet + facet normal -0.382712 -0.910515 0.156504 + outer loop + vertex -604.405 112.94 106.001 + vertex -608.96 116.252 114.126 + vertex -609.202 114.991 106.205 + endloop + endfacet + facet normal -0.390571 -0.910559 0.13541 + outer loop + vertex -604.026 115.308 121.901 + vertex -608.793 117.379 122.076 + vertex -604.182 114.19 113.935 + endloop + endfacet + facet normal -0.399085 -0.906275 0.139274 + outer loop + vertex -608.96 116.252 114.126 + vertex -614.727 120.068 122.433 + vertex -614.911 118.93 114.505 + endloop + endfacet + facet normal -0.405931 -0.906316 0.11752 + outer loop + vertex -608.661 118.362 130.114 + vertex -614.591 121.061 130.448 + vertex -608.793 117.379 122.076 + endloop + endfacet + facet normal -0.419626 -0.899604 0.120939 + outer loop + vertex -614.727 120.068 122.433 + vertex -620.981 124.11 130.801 + vertex -621.128 123.104 122.809 + endloop + endfacet + facet normal -0.425558 -0.899528 0.0987424 + outer loop + vertex -614.474 121.896 138.556 + vertex -620.864 124.956 138.888 + vertex -614.591 121.061 130.448 + endloop + endfacet + facet normal -0.44542 -0.889565 0.101371 + outer loop + vertex -620.981 124.11 130.801 + vertex -627.198 128.178 139.181 + vertex -627.318 127.319 131.117 + endloop + endfacet + facet normal -0.450311 -0.889381 0.0788753 + outer loop + vertex -620.769 125.63 147.028 + vertex -627.1 128.859 147.299 + vertex -620.864 124.956 138.888 + endloop + endfacet + facet normal -0.475257 -0.876157 0.0805013 + outer loop + vertex -627.198 128.178 139.181 + vertex -633.164 132.183 147.552 + vertex -633.259 131.49 139.457 + endloop + endfacet + facet normal -0.478808 -0.876015 0.0578045 + outer loop + vertex -627.031 129.357 155.415 + vertex -633.09 132.684 155.646 + vertex -627.1 128.859 147.299 + endloop + endfacet + facet normal -0.50655 -0.860222 0.0585179 + outer loop + vertex -633.164 132.183 147.552 + vertex -638.847 136.097 155.889 + vertex -638.919 135.59 147.819 + endloop + endfacet + facet normal -0.508629 -0.860242 0.0357674 + outer loop + vertex -633.045 132.992 163.704 + vertex -638.801 136.405 163.925 + vertex -633.09 132.684 155.646 + endloop + endfacet + facet normal -0.53804 -0.842177 0.0353728 + outer loop + vertex -638.847 136.097 155.889 + vertex -644.277 139.913 164.157 + vertex -644.317 139.602 156.144 + endloop + endfacet + facet normal -0.538703 -0.8424 0.0127089 + outer loop + vertex -638.788 136.517 171.928 + vertex -644.26 140.02 172.138 + vertex -638.801 136.405 163.925 + endloop + endfacet + facet normal -0.571913 -0.820229 0.0117886 + outer loop + vertex -644.277 139.913 164.157 + vertex -649.442 143.632 172.335 + vertex -649.458 143.528 164.376 + endloop + endfacet + facet normal -0.571075 -0.820827 -0.0107924 + outer loop + vertex -644.277 139.927 180.112 + vertex -649.461 143.531 180.287 + vertex -644.26 140.02 172.138 + endloop + endfacet + facet normal -0.611594 -0.79107 -0.0126809 + outer loop + vertex -649.442 143.632 172.335 + vertex -654.33 147.281 180.444 + vertex -654.314 147.395 172.513 + endloop + endfacet + facet normal -0.608731 -0.792644 -0.0340994 + outer loop + vertex -649.506 143.223 188.256 + vertex -654.378 146.959 188.39 + vertex -649.461 143.531 180.287 + endloop + endfacet + facet normal -0.653768 -0.754347 -0.0595559 + outer loop + vertex -654.378 146.959 188.39 + vertex -658.976 150.304 196.482 + vertex -658.896 150.862 188.539 + endloop + endfacet + facet normal -0.453989 -0.810856 0.369333 + outer loop + vertex -658.482 123.126 50.8488 + vertex -662.202 127.968 56.9066 + vertex -664.354 126.582 51.2165 + endloop + endfacet + facet normal -0.429952 -0.826732 0.362844 + outer loop + vertex -652.359 119.722 50.3493 + vertex -658.482 123.126 50.8488 + vertex -654.991 119.25 46.1533 + endloop + endfacet + facet normal -0.40778 -0.834273 0.371085 + outer loop + vertex -652.961 117.015 43.3864 + vertex -654.594 118.177 44.2052 + vertex -654.25 117.711 43.5362 + endloop + endfacet + facet normal -0.409747 -0.836403 0.364058 + outer loop + vertex -654.25 117.711 43.5362 + vertex -653.096 117.062 43.343 + vertex -652.961 117.015 43.3864 + endloop + endfacet + facet normal -0.429189 -0.661523 0.614967 + outer loop + vertex -653.096 117.062 43.343 + vertex -653.717 117.253 43.1153 + vertex -652.961 117.015 43.3864 + endloop + endfacet + facet normal -0.404382 -0.818848 0.407385 + outer loop + vertex -653.717 117.253 43.1153 + vertex -654.6 117.209 42.1503 + vertex -652.961 117.015 43.3864 + endloop + endfacet + facet normal -0.395219 -0.830048 0.393475 + outer loop + vertex -654.36 116.588 41.0811 + vertex -652.961 117.015 43.3864 + vertex -654.6 117.209 42.1503 + endloop + endfacet + facet normal -0.385445 -0.832825 0.397283 + outer loop + vertex -654.6 117.209 42.1503 + vertex -655.831 116.885 40.2772 + vertex -654.36 116.588 41.0811 + endloop + endfacet + facet normal -0.384168 -0.834887 0.394182 + outer loop + vertex -655.963 116.277 38.8598 + vertex -654.36 116.588 41.0811 + vertex -655.831 116.885 40.2772 + endloop + endfacet + facet normal -0.368955 -0.841127 0.395446 + outer loop + vertex -655.831 116.885 40.2772 + vertex -657.393 116.514 38.0309 + vertex -655.963 116.277 38.8598 + endloop + endfacet + facet normal -0.37004 -0.839553 0.397769 + outer loop + vertex -657.864 116.036 36.583 + vertex -655.963 116.277 38.8598 + vertex -657.393 116.514 38.0309 + endloop + endfacet + facet normal -0.342188 -0.853364 0.393291 + outer loop + vertex -657.393 116.514 38.0309 + vertex -659.212 116.198 35.763 + vertex -657.864 116.036 36.583 + endloop + endfacet + facet normal -0.388011 -0.817779 0.425071 + outer loop + vertex -660.317 117.547 37.3494 + vertex -659.212 116.198 35.763 + vertex -657.393 116.514 38.0309 + endloop + endfacet + facet normal -0.388098 -0.816651 0.427154 + outer loop + vertex -660.317 117.547 37.3494 + vertex -657.393 116.514 38.0309 + vertex -658.9 118.127 39.7455 + endloop + endfacet + facet normal -0.406393 -0.803605 0.434814 + outer loop + vertex -660.317 117.547 37.3494 + vertex -658.9 118.127 39.7455 + vertex -664.468 120.767 39.4213 + endloop + endfacet + facet normal -0.387074 -0.797119 0.463439 + outer loop + vertex -664.468 120.767 39.4213 + vertex -665.963 119.755 36.4311 + vertex -660.317 117.547 37.3494 + endloop + endfacet + facet normal -0.387999 -0.807279 0.4447 + outer loop + vertex -661.489 116.926 35.1981 + vertex -660.317 117.547 37.3494 + vertex -665.963 119.755 36.4311 + endloop + endfacet + facet normal -0.373975 -0.797572 0.473309 + outer loop + vertex -664.164 117.121 33.4133 + vertex -661.489 116.926 35.1981 + vertex -665.963 119.755 36.4311 + endloop + endfacet + facet normal -0.361276 -0.798441 0.481634 + outer loop + vertex -665.963 119.755 36.4311 + vertex -669.31 119.684 33.8021 + vertex -664.164 117.121 33.4133 + endloop + endfacet + facet normal -0.358907 -0.794847 0.489289 + outer loop + vertex -664.164 117.121 33.4133 + vertex -669.31 119.684 33.8021 + vertex -666.202 117.164 31.9894 + endloop + endfacet + facet normal -0.347102 -0.810442 0.471916 + outer loop + vertex -666.202 117.164 31.9894 + vertex -664.569 116.424 31.9196 + vertex -664.164 117.121 33.4133 + endloop + endfacet + facet normal -0.334816 -0.816017 0.471185 + outer loop + vertex -664.569 116.424 31.9196 + vertex -663.839 116.154 31.9699 + vertex -664.164 117.121 33.4133 + endloop + endfacet + facet normal -0.356449 -0.811405 0.463213 + outer loop + vertex -664.164 117.121 33.4133 + vertex -663.839 116.154 31.9699 + vertex -661.448 116.121 33.7524 + endloop + endfacet + facet normal -0.307466 -0.864997 0.396542 + outer loop + vertex -661.448 116.121 33.7524 + vertex -663.839 116.154 31.9699 + vertex -662.292 115.947 32.7172 + endloop + endfacet + facet normal -0.315419 -0.852709 0.41641 + outer loop + vertex -664.527 116.096 31.3297 + vertex -662.292 115.947 32.7172 + vertex -663.839 116.154 31.9699 + endloop + endfacet + facet normal -0.3234 -0.842747 0.430337 + outer loop + vertex -662.292 115.947 32.7172 + vertex -664.527 116.096 31.3297 + vertex -662.735 115.738 31.9752 + endloop + endfacet + facet normal -0.335657 -0.819546 0.464412 + outer loop + vertex -664.569 116.424 31.9196 + vertex -665.501 116.366 31.1433 + vertex -663.839 116.154 31.9699 + endloop + endfacet + facet normal -0.346036 -0.808479 0.476047 + outer loop + vertex -666.202 117.164 31.9894 + vertex -665.501 116.366 31.1433 + vertex -664.569 116.424 31.9196 + endloop + endfacet + facet normal -0.334138 -0.807933 0.485382 + outer loop + vertex -667.306 116.994 30.9453 + vertex -665.501 116.366 31.1433 + vertex -666.202 117.164 31.9894 + endloop + endfacet + facet normal -0.342555 -0.799786 0.492949 + outer loop + vertex -668.688 118.151 31.8634 + vertex -667.306 116.994 30.9453 + vertex -666.202 117.164 31.9894 + endloop + endfacet + facet normal -0.334157 -0.797367 0.502539 + outer loop + vertex -670.013 118.179 31.0256 + vertex -667.306 116.994 30.9453 + vertex -668.688 118.151 31.8634 + endloop + endfacet + facet normal -0.342904 -0.784433 0.516799 + outer loop + vertex -672.491 120.157 32.3844 + vertex -670.013 118.179 31.0256 + vertex -668.688 118.151 31.8634 + endloop + endfacet + facet normal -0.34505 -0.787079 0.51132 + outer loop + vertex -668.688 118.151 31.8634 + vertex -669.31 119.684 33.8021 + vertex -672.491 120.157 32.3844 + endloop + endfacet + facet normal -0.35234 -0.768703 0.533809 + outer loop + vertex -669.31 119.684 33.8021 + vertex -676.518 123.494 34.5317 + vertex -672.491 120.157 32.3844 + endloop + endfacet + facet normal -0.336329 -0.761988 0.553406 + outer loop + vertex -678.35 122.941 32.6569 + vertex -672.491 120.157 32.3844 + vertex -676.518 123.494 34.5317 + endloop + endfacet + facet normal -0.346408 -0.752301 0.560397 + outer loop + vertex -683.625 126.9 34.7103 + vertex -678.35 122.941 32.6569 + vertex -676.518 123.494 34.5317 + endloop + endfacet + facet normal -0.339423 -0.738863 0.582129 + outer loop + vertex -683.625 126.9 34.7103 + vertex -676.518 123.494 34.5317 + vertex -681.925 127.978 37.0696 + endloop + endfacet + facet normal -0.353073 -0.728394 0.587181 + outer loop + vertex -688.43 131.024 36.9366 + vertex -683.625 126.9 34.7103 + vertex -681.925 127.978 37.0696 + endloop + endfacet + facet normal -0.340226 -0.768996 0.541193 + outer loop + vertex -678.35 122.941 32.6569 + vertex -674.051 120.021 31.2099 + vertex -672.491 120.157 32.3844 + endloop + endfacet + facet normal -0.325335 -0.758619 0.564494 + outer loop + vertex -678.9 122.124 31.2422 + vertex -674.051 120.021 31.2099 + vertex -678.35 122.941 32.6569 + endloop + endfacet + facet normal -0.33121 -0.755649 0.565061 + outer loop + vertex -678.35 122.941 32.6569 + vertex -685.319 125.894 32.5213 + vertex -678.9 122.124 31.2422 + endloop + endfacet + facet normal -0.317625 -0.741375 0.591166 + outer loop + vertex -685.319 125.894 32.5213 + vertex -682.879 123.577 30.9264 + vertex -678.9 122.124 31.2422 + endloop + endfacet + facet normal -0.321181 -0.755489 0.571033 + outer loop + vertex -682.879 123.577 30.9264 + vertex -678.66 121.507 30.5608 + vertex -678.9 122.124 31.2422 + endloop + endfacet + facet normal -0.317877 -0.755796 0.572474 + outer loop + vertex -678.66 121.507 30.5608 + vertex -675.404 120.076 30.4794 + vertex -678.9 122.124 31.2422 + endloop + endfacet + facet normal -0.321998 -0.764382 0.558603 + outer loop + vertex -678.66 121.507 30.5608 + vertex -678.774 121.326 30.247 + vertex -675.404 120.076 30.4794 + endloop + endfacet + facet normal -0.327402 -0.785043 0.525848 + outer loop + vertex -678.774 121.326 30.247 + vertex -673.387 118.999 30.1267 + vertex -675.404 120.076 30.4794 + endloop + endfacet + facet normal -0.327723 -0.785403 0.52511 + outer loop + vertex -671.404 118.367 30.4185 + vertex -675.404 120.076 30.4794 + vertex -673.387 118.999 30.1267 + endloop + endfacet + facet normal -0.329167 -0.802945 0.496919 + outer loop + vertex -671.404 118.367 30.4185 + vertex -673.387 118.999 30.1267 + vertex -669.667 117.44 30.0716 + endloop + endfacet + facet normal -0.332453 -0.806257 0.48931 + outer loop + vertex -668.483 117.134 30.3725 + vertex -671.404 118.367 30.4185 + vertex -669.667 117.44 30.0716 + endloop + endfacet + facet normal -0.330919 -0.816843 0.472505 + outer loop + vertex -669.667 117.44 30.0716 + vertex -667.458 116.604 30.1733 + vertex -668.483 117.134 30.3725 + endloop + endfacet + facet normal -0.330987 -0.816912 0.472338 + outer loop + vertex -666.703 116.453 30.4421 + vertex -668.483 117.134 30.3725 + vertex -667.458 116.604 30.1733 + endloop + endfacet + facet normal -0.328128 -0.825263 0.459644 + outer loop + vertex -667.458 116.604 30.1733 + vertex -666.553 116.305 30.2828 + vertex -666.703 116.453 30.4421 + endloop + endfacet + facet normal -0.326728 -0.825145 0.460853 + outer loop + vertex -666.703 116.453 30.4421 + vertex -666.553 116.305 30.2828 + vertex -665.591 116.189 30.7579 + endloop + endfacet + facet normal -0.326113 -0.827842 0.456431 + outer loop + vertex -665.501 116.366 31.1433 + vertex -666.703 116.453 30.4421 + vertex -665.591 116.189 30.7579 + endloop + endfacet + facet normal -0.340659 -0.799067 0.495423 + outer loop + vertex -665.591 116.189 30.7579 + vertex -666.553 116.305 30.2828 + vertex -666.359 116.166 30.1934 + endloop + endfacet + facet normal -0.330057 -0.811911 0.481521 + outer loop + vertex -666.359 116.166 30.1934 + vertex -664.527 116.096 31.3297 + vertex -665.591 116.189 30.7579 + endloop + endfacet + facet normal -0.283915 -0.878229 0.384845 + outer loop + vertex -664.527 116.096 31.3297 + vertex -663.839 116.154 31.9699 + vertex -665.591 116.189 30.7579 + endloop + endfacet + facet normal -0.32399 -0.790923 0.519107 + outer loop + vertex -666.553 116.305 30.2828 + vertex -667.458 116.604 30.1733 + vertex -666.359 116.166 30.1934 + endloop + endfacet + facet normal -0.32997 -0.813599 0.478724 + outer loop + vertex -668.483 117.134 30.3725 + vertex -666.703 116.453 30.4421 + vertex -667.306 116.994 30.9453 + endloop + endfacet + facet normal -0.31991 -0.779785 0.538139 + outer loop + vertex -669.667 117.44 30.0716 + vertex -666.359 116.166 30.1934 + vertex -667.458 116.604 30.1733 + endloop + endfacet + facet normal -0.331547 -0.81624 0.473105 + outer loop + vertex -666.359 116.166 30.1934 + vertex -669.667 117.44 30.0716 + vertex -667.628 116.582 30.0213 + endloop + endfacet + facet normal -0.33173 -0.818406 0.46922 + outer loop + vertex -667.628 116.582 30.0213 + vertex -666.617 116.171 30.019 + vertex -666.359 116.166 30.1934 + endloop + endfacet + facet normal -0.343731 -0.802629 0.487479 + outer loop + vertex -666.617 116.171 30.019 + vertex -665.834 115.669 29.7447 + vertex -666.359 116.166 30.1934 + endloop + endfacet + facet normal -0.408542 -0.810284 0.420158 + outer loop + vertex -664.199 114.469 29.0202 + vertex -666.359 116.166 30.1934 + vertex -665.834 115.669 29.7447 + endloop + endfacet + facet normal -0.348174 -0.784348 0.513393 + outer loop + vertex -664.199 114.469 29.0202 + vertex -665.834 115.669 29.7447 + vertex -665.605 115.227 29.2241 + endloop + endfacet + facet normal -0.343925 -0.779283 0.523864 + outer loop + vertex -664.378 114.298 28.6476 + vertex -664.199 114.469 29.0202 + vertex -665.605 115.227 29.2241 + endloop + endfacet + facet normal -0.322535 -0.768697 0.552337 + outer loop + vertex -665.308 114.73 28.7059 + vertex -664.378 114.298 28.6476 + vertex -665.605 115.227 29.2241 + endloop + endfacet + facet normal -0.303417 -0.768606 0.56319 + outer loop + vertex -665.308 114.73 28.7059 + vertex -665.605 115.227 29.2241 + vertex -667.474 115.55 28.6577 + endloop + endfacet + facet normal -0.291028 -0.732819 0.615044 + outer loop + vertex -666.284 114.462 27.9248 + vertex -665.308 114.73 28.7059 + vertex -667.474 115.55 28.6577 + endloop + endfacet + facet normal -0.291415 -0.732986 0.614662 + outer loop + vertex -673.058 116.992 27.7307 + vertex -666.284 114.462 27.9248 + vertex -667.474 115.55 28.6577 + endloop + endfacet + facet normal -0.291105 -0.727603 0.62117 + outer loop + vertex -670.419 116.757 28.6913 + vertex -673.058 116.992 27.7307 + vertex -667.474 115.55 28.6577 + endloop + endfacet + facet normal -0.304602 -0.759256 0.575107 + outer loop + vertex -667.474 115.55 28.6577 + vertex -667.998 116.242 29.2944 + vertex -670.419 116.757 28.6913 + endloop + endfacet + facet normal -0.305087 -0.754424 0.581176 + outer loop + vertex -670.419 116.757 28.6913 + vertex -667.998 116.242 29.2944 + vertex -671.5 117.573 29.1831 + endloop + endfacet + facet normal -0.300851 -0.752015 0.586483 + outer loop + vertex -670.419 116.757 28.6913 + vertex -671.5 117.573 29.1831 + vertex -675.484 118.569 28.4176 + endloop + endfacet + facet normal -0.300763 -0.740731 0.600716 + outer loop + vertex -675.484 118.569 28.4176 + vertex -671.5 117.573 29.1831 + vertex -676.459 119.511 29.0908 + endloop + endfacet + facet normal -0.298646 -0.739965 0.602712 + outer loop + vertex -675.484 118.569 28.4176 + vertex -676.459 119.511 29.0908 + vertex -682.025 121.198 28.4041 + endloop + endfacet + facet normal -0.297859 -0.734507 0.609737 + outer loop + vertex -682.025 121.198 28.4041 + vertex -676.459 119.511 29.0908 + vertex -682.128 121.882 29.1772 + endloop + endfacet + facet normal -0.297187 -0.734621 0.609927 + outer loop + vertex -687.863 123.76 28.645 + vertex -682.025 121.198 28.4041 + vertex -682.128 121.882 29.1772 + endloop + endfacet + facet normal -0.296532 -0.731456 0.614036 + outer loop + vertex -687.713 124.441 29.5288 + vertex -687.863 123.76 28.645 + vertex -682.128 121.882 29.1772 + endloop + endfacet + facet normal -0.295095 -0.731934 0.61416 + outer loop + vertex -692.492 125.842 28.9025 + vertex -687.863 123.76 28.645 + vertex -687.713 124.441 29.5288 + endloop + endfacet + facet normal -0.293667 -0.721089 0.627528 + outer loop + vertex -687.713 124.441 29.5288 + vertex -694.333 127.347 29.7703 + vertex -692.492 125.842 28.9025 + endloop + endfacet + facet normal -0.281649 -0.714093 0.640894 + outer loop + vertex -694.333 127.347 29.7703 + vertex -696.576 127.15 28.5641 + vertex -692.492 125.842 28.9025 + endloop + endfacet + facet normal -0.283329 -0.721782 0.631471 + outer loop + vertex -692.452 125.207 28.1937 + vertex -692.492 125.842 28.9025 + vertex -696.576 127.15 28.5641 + endloop + endfacet + facet normal -0.274927 -0.707649 0.650883 + outer loop + vertex -693.508 124.915 27.4303 + vertex -692.452 125.207 28.1937 + vertex -696.576 127.15 28.5641 + endloop + endfacet + facet normal -0.260268 -0.696537 0.668652 + outer loop + vertex -696.576 127.15 28.5641 + vertex -696.987 125.69 26.8835 + vertex -693.508 124.915 27.4303 + endloop + endfacet + facet normal -0.259888 -0.689902 0.675643 + outer loop + vertex -693.017 124.011 26.6967 + vertex -693.508 124.915 27.4303 + vertex -696.987 125.69 26.8835 + endloop + endfacet + facet normal -0.24499 -0.658653 0.711446 + outer loop + vertex -693.181 123.465 26.1343 + vertex -693.017 124.011 26.6967 + vertex -696.987 125.69 26.8835 + endloop + endfacet + facet normal -0.23873 -0.651011 0.72055 + outer loop + vertex -696.987 125.69 26.8835 + vertex -695.714 123.87 25.6608 + vertex -693.181 123.465 26.1343 + endloop + endfacet + facet normal -0.238815 -0.631073 0.738048 + outer loop + vertex -691.947 122.45 25.6659 + vertex -693.181 123.465 26.1343 + vertex -695.714 123.87 25.6608 + endloop + endfacet + facet normal -0.227487 -0.600908 0.766263 + outer loop + vertex -691.672 121.932 25.3414 + vertex -691.947 122.45 25.6659 + vertex -695.714 123.87 25.6608 + endloop + endfacet + facet normal -0.237873 -0.603268 0.761239 + outer loop + vertex -691.672 121.932 25.3414 + vertex -687.186 120.466 25.5813 + vertex -691.947 122.45 25.6659 + endloop + endfacet + facet normal -0.247245 -0.624876 0.740541 + outer loop + vertex -687.186 120.466 25.5813 + vertex -688.977 121.647 25.9799 + vertex -691.947 122.45 25.6659 + endloop + endfacet + facet normal -0.258363 -0.63694 0.726331 + outer loop + vertex -688.977 121.647 25.9799 + vertex -687.186 120.466 25.5813 + vertex -681.508 119.093 26.3966 + endloop + endfacet + facet normal -0.263168 -0.653736 0.709487 + outer loop + vertex -688.977 121.647 25.9799 + vertex -681.508 119.093 26.3966 + vertex -688.574 122.075 26.5236 + endloop + endfacet + facet normal -0.258084 -0.657033 0.708308 + outer loop + vertex -688.977 121.647 25.9799 + vertex -688.574 122.075 26.5236 + vertex -693.181 123.465 26.1343 + endloop + endfacet + facet normal -0.275636 -0.681914 0.677508 + outer loop + vertex -681.508 119.093 26.3966 + vertex -682.638 120.562 27.4156 + vertex -688.574 122.075 26.5236 + endloop + endfacet + facet normal -0.275251 -0.677999 0.681582 + outer loop + vertex -689.701 123.079 27.0674 + vertex -688.574 122.075 26.5236 + vertex -682.638 120.562 27.4156 + endloop + endfacet + facet normal -0.282441 -0.702022 0.653753 + outer loop + vertex -689.701 123.079 27.0674 + vertex -682.638 120.562 27.4156 + vertex -688.394 123.225 27.7888 + endloop + endfacet + facet normal -0.279279 -0.707544 0.649142 + outer loop + vertex -689.701 123.079 27.0674 + vertex -688.394 123.225 27.7888 + vertex -693.508 124.915 27.4303 + endloop + endfacet + facet normal -0.288705 -0.713424 0.638495 + outer loop + vertex -682.638 120.562 27.4156 + vertex -682.025 121.198 28.4041 + vertex -688.394 123.225 27.7888 + endloop + endfacet + facet normal -0.290089 -0.720337 0.63005 + outer loop + vertex -687.863 123.76 28.645 + vertex -688.394 123.225 27.7888 + vertex -682.025 121.198 28.4041 + endloop + endfacet + facet normal -0.289177 -0.720894 0.629832 + outer loop + vertex -688.394 123.225 27.7888 + vertex -687.863 123.76 28.645 + vertex -692.452 125.207 28.1937 + endloop + endfacet + facet normal -0.288181 -0.713743 0.638375 + outer loop + vertex -682.025 121.198 28.4041 + vertex -682.638 120.562 27.4156 + vertex -675.484 118.569 28.4176 + endloop + endfacet + facet normal -0.288823 -0.719413 0.631685 + outer loop + vertex -682.638 120.562 27.4156 + vertex -673.058 116.992 27.7307 + vertex -675.484 118.569 28.4176 + endloop + endfacet + facet normal -0.266288 -0.672687 0.69035 + outer loop + vertex -688.574 122.075 26.5236 + vertex -689.701 123.079 27.0674 + vertex -693.017 124.011 26.6967 + endloop + endfacet + facet normal -0.276424 -0.68214 0.67696 + outer loop + vertex -681.508 119.093 26.3966 + vertex -673.058 116.992 27.7307 + vertex -682.638 120.562 27.4156 + endloop + endfacet + facet normal -0.277811 -0.699478 0.658447 + outer loop + vertex -671.312 115.268 26.6355 + vertex -673.058 116.992 27.7307 + vertex -681.508 119.093 26.3966 + endloop + endfacet + facet normal -0.280534 -0.700684 0.656004 + outer loop + vertex -673.058 116.992 27.7307 + vertex -671.312 115.268 26.6355 + vertex -666.284 114.462 27.9248 + endloop + endfacet + facet normal -0.279365 -0.711663 0.644586 + outer loop + vertex -664.224 112.688 26.8598 + vertex -666.284 114.462 27.9248 + vertex -671.312 115.268 26.6355 + endloop + endfacet + facet normal -0.288817 -0.716728 0.634732 + outer loop + vertex -664.224 112.688 26.8598 + vertex -663.008 113.116 27.8956 + vertex -666.284 114.462 27.9248 + endloop + endfacet + facet normal -0.295573 -0.732699 0.613017 + outer loop + vertex -663.008 113.116 27.8956 + vertex -664.378 114.298 28.6476 + vertex -666.284 114.462 27.9248 + endloop + endfacet + facet normal -0.286004 -0.719687 0.632655 + outer loop + vertex -660.688 111.318 26.8986 + vertex -663.008 113.116 27.8956 + vertex -664.224 112.688 26.8598 + endloop + endfacet + facet normal -0.259364 -0.646146 0.717792 + outer loop + vertex -679.039 116.86 25.2792 + vertex -681.508 119.093 26.3966 + vertex -687.186 120.466 25.5813 + endloop + endfacet + facet normal -0.238878 -0.603461 0.760771 + outer loop + vertex -687.845 120.185 25.1517 + vertex -679.039 116.86 25.2792 + vertex -687.186 120.466 25.5813 + endloop + endfacet + facet normal -0.259149 -0.646009 0.717993 + outer loop + vertex -679.039 116.86 25.2792 + vertex -671.312 115.268 26.6355 + vertex -681.508 119.093 26.3966 + endloop + endfacet + facet normal -0.260121 -0.67032 0.694988 + outer loop + vertex -667.169 112.67 25.6802 + vertex -671.312 115.268 26.6355 + vertex -679.039 116.86 25.2792 + endloop + endfacet + facet normal -0.268947 -0.679748 0.682357 + outer loop + vertex -671.312 115.268 26.6355 + vertex -667.169 112.67 25.6802 + vertex -664.224 112.688 26.8598 + endloop + endfacet + facet normal -0.267026 -0.685196 0.677646 + outer loop + vertex -661.005 110.661 26.0777 + vertex -664.224 112.688 26.8598 + vertex -667.169 112.67 25.6802 + endloop + endfacet + facet normal -0.276879 -0.695286 0.663261 + outer loop + vertex -661.005 110.661 26.0777 + vertex -660.688 111.318 26.8986 + vertex -664.224 112.688 26.8598 + endloop + endfacet + facet normal -0.274455 -0.696337 0.663166 + outer loop + vertex -658.92 110.025 26.2728 + vertex -660.688 111.318 26.8986 + vertex -661.005 110.661 26.0777 + endloop + endfacet + facet normal -0.238177 -0.604355 0.760281 + outer loop + vertex -687.845 120.185 25.1517 + vertex -687.186 120.466 25.5813 + vertex -691.672 121.932 25.3414 + endloop + endfacet + facet normal -0.249755 -0.639374 0.727202 + outer loop + vertex -691.947 122.45 25.6659 + vertex -688.977 121.647 25.9799 + vertex -693.181 123.465 26.1343 + endloop + endfacet + facet normal -0.254071 -0.655462 0.711209 + outer loop + vertex -695.714 123.87 25.6608 + vertex -696.987 125.69 26.8835 + vertex -699.528 125.929 26.1962 + endloop + endfacet + facet normal -0.251749 -0.671315 0.697107 + outer loop + vertex -700.025 127.162 27.2038 + vertex -699.528 125.929 26.1962 + vertex -696.987 125.69 26.8835 + endloop + endfacet + facet normal -0.259808 -0.671776 0.693698 + outer loop + vertex -700.025 127.162 27.2038 + vertex -701.624 127.608 27.0375 + vertex -699.528 125.929 26.1962 + endloop + endfacet + facet normal -0.260416 -0.672209 0.69305 + outer loop + vertex -699.528 125.929 26.1962 + vertex -701.624 127.608 27.0375 + vertex -701.694 126.64 26.0723 + endloop + endfacet + facet normal -0.268994 -0.670233 0.691686 + outer loop + vertex -701.624 127.608 27.0375 + vertex -703.856 128.316 26.8552 + vertex -701.694 126.64 26.0723 + endloop + endfacet + facet normal -0.26259 -0.665318 0.698855 + outer loop + vertex -701.694 126.64 26.0723 + vertex -703.856 128.316 26.8552 + vertex -704.064 127.282 25.7924 + endloop + endfacet + facet normal -0.271469 -0.66265 0.697997 + outer loop + vertex -703.856 128.316 26.8552 + vertex -706.323 129.041 26.584 + vertex -704.064 127.282 25.7924 + endloop + endfacet + facet normal -0.266145 -0.658495 0.703954 + outer loop + vertex -704.064 127.282 25.7924 + vertex -706.323 129.041 26.584 + vertex -707.944 128.851 25.7933 + endloop + endfacet + facet normal -0.267137 -0.656444 0.705492 + outer loop + vertex -706.323 129.041 26.584 + vertex -710.082 131.053 27.0325 + vertex -707.944 128.851 25.7933 + endloop + endfacet + facet normal -0.267242 -0.656497 0.705403 + outer loop + vertex -707.944 128.851 25.7933 + vertex -710.082 131.053 27.0325 + vertex -712.242 130.801 25.9797 + endloop + endfacet + facet normal -0.268897 -0.653047 0.707972 + outer loop + vertex -710.082 131.053 27.0325 + vertex -714.041 132.808 27.1476 + vertex -712.242 130.801 25.9797 + endloop + endfacet + facet normal -0.272599 -0.654668 0.705053 + outer loop + vertex -712.242 130.801 25.9797 + vertex -714.041 132.808 27.1476 + vertex -716.112 132.781 26.3217 + endloop + endfacet + facet normal -0.276663 -0.642237 0.714835 + outer loop + vertex -714.041 132.808 27.1476 + vertex -718.822 135.415 27.6399 + vertex -716.112 132.781 26.3217 + endloop + endfacet + facet normal -0.279242 -0.643719 0.712496 + outer loop + vertex -716.112 132.781 26.3217 + vertex -718.822 135.415 27.6399 + vertex -720.753 134.654 26.1952 + endloop + endfacet + facet normal -0.286118 -0.63534 0.717272 + outer loop + vertex -718.822 135.415 27.6399 + vertex -725.714 138.593 27.7053 + vertex -720.753 134.654 26.1952 + endloop + endfacet + facet normal -0.283898 -0.633504 0.719773 + outer loop + vertex -720.753 134.654 26.1952 + vertex -725.714 138.593 27.7053 + vertex -727.495 137.315 25.8782 + endloop + endfacet + facet normal -0.292785 -0.625737 0.723001 + outer loop + vertex -727.495 137.315 25.8782 + vertex -725.714 138.593 27.7053 + vertex -733.588 142.061 27.5187 + endloop + endfacet + facet normal -0.281051 -0.615327 0.736466 + outer loop + vertex -735.653 140.691 25.5857 + vertex -727.495 137.315 25.8782 + vertex -733.588 142.061 27.5187 + endloop + endfacet + facet normal -0.292353 -0.604604 0.740934 + outer loop + vertex -733.588 142.061 27.5187 + vertex -742.368 145.804 27.1082 + vertex -735.653 140.691 25.5857 + endloop + endfacet + facet normal -0.283151 -0.595706 0.751638 + outer loop + vertex -742.105 143.456 25.3466 + vertex -735.653 140.691 25.5857 + vertex -742.368 145.804 27.1082 + endloop + endfacet + facet normal -0.292867 -0.594635 0.748758 + outer loop + vertex -747.382 146.386 25.6092 + vertex -742.105 143.456 25.3466 + vertex -742.368 145.804 27.1082 + endloop + endfacet + facet normal -0.294027 -0.583644 0.756907 + outer loop + vertex -742.368 145.804 27.1082 + vertex -750.984 150.367 27.2795 + vertex -747.382 146.386 25.6092 + endloop + endfacet + facet normal -0.302332 -0.58827 0.750023 + outer loop + vertex -753.471 149.482 25.5831 + vertex -747.382 146.386 25.6092 + vertex -750.984 150.367 27.2795 + endloop + endfacet + facet normal -0.308811 -0.578922 0.754643 + outer loop + vertex -750.984 150.367 27.2795 + vertex -758.929 154.255 27.011 + vertex -753.471 149.482 25.5831 + endloop + endfacet + facet normal -0.310568 -0.58038 0.752799 + outer loop + vertex -758.223 151.638 25.2852 + vertex -753.471 149.482 25.5831 + vertex -758.929 154.255 27.011 + endloop + endfacet + facet normal -0.320634 -0.580332 0.748604 + outer loop + vertex -763.316 154.734 25.5035 + vertex -758.223 151.638 25.2852 + vertex -758.929 154.255 27.011 + endloop + endfacet + facet normal -0.321915 -0.570787 0.755363 + outer loop + vertex -758.929 154.255 27.011 + vertex -767.346 159.179 27.1452 + vertex -763.316 154.734 25.5035 + endloop + endfacet + facet normal -0.330341 -0.575694 0.747965 + outer loop + vertex -770.223 158.36 25.244 + vertex -763.316 154.734 25.5035 + vertex -767.346 159.179 27.1452 + endloop + endfacet + facet normal -0.33859 -0.562093 0.754591 + outer loop + vertex -767.346 159.179 27.1452 + vertex -775.727 163.694 26.7473 + vertex -770.223 158.36 25.244 + endloop + endfacet + facet normal -0.33832 -0.561891 0.754863 + outer loop + vertex -775.733 161.407 25.0424 + vertex -770.223 158.36 25.244 + vertex -775.727 163.694 26.7473 + endloop + endfacet + facet normal -0.349059 -0.559525 0.751724 + outer loop + vertex -780.379 164.488 25.1782 + vertex -775.733 161.407 25.0424 + vertex -775.727 163.694 26.7473 + endloop + endfacet + facet normal -0.349809 -0.5482 0.759678 + outer loop + vertex -775.727 163.694 26.7473 + vertex -784.36 168.964 26.5749 + vertex -780.379 164.488 25.1782 + endloop + endfacet + facet normal -0.358607 -0.553526 0.751671 + outer loop + vertex -785.051 167.11 24.8807 + vertex -780.379 164.488 25.1782 + vertex -784.36 168.964 26.5749 + endloop + endfacet + facet normal -0.370635 -0.547648 0.750141 + outer loop + vertex -789.423 170.328 25.0697 + vertex -785.051 167.11 24.8807 + vertex -784.36 168.964 26.5749 + endloop + endfacet + facet normal -0.370566 -0.546161 0.751258 + outer loop + vertex -784.36 168.964 26.5749 + vertex -791.8 174.143 26.6707 + vertex -789.423 170.328 25.0697 + endloop + endfacet + facet normal -0.390122 -0.552261 0.736758 + outer loop + vertex -795.101 174.189 24.9571 + vertex -789.423 170.328 25.0697 + vertex -791.8 174.143 26.6707 + endloop + endfacet + facet normal -0.393179 -0.541725 0.742929 + outer loop + vertex -791.8 174.143 26.6707 + vertex -798.818 178.957 26.4669 + vertex -795.101 174.189 24.9571 + endloop + endfacet + facet normal -0.405334 -0.547716 0.731923 + outer loop + vertex -800.482 177.601 24.5307 + vertex -795.101 174.189 24.9571 + vertex -798.818 178.957 26.4669 + endloop + endfacet + facet normal -0.416396 -0.536808 0.733792 + outer loop + vertex -800.482 177.601 24.5307 + vertex -798.818 178.957 26.4669 + vertex -804.751 181.954 25.2921 + endloop + endfacet + facet normal -0.421446 -0.55259 0.719046 + outer loop + vertex -798.818 178.957 26.4669 + vertex -804.374 184.236 27.2669 + vertex -804.751 181.954 25.2921 + endloop + endfacet + facet normal -0.434552 -0.547223 0.715341 + outer loop + vertex -804.374 184.236 27.2669 + vertex -808.572 186.566 26.4993 + vertex -804.751 181.954 25.2921 + endloop + endfacet + facet normal -0.436515 -0.548317 0.713305 + outer loop + vertex -804.751 181.954 25.2921 + vertex -808.572 186.566 26.4993 + vertex -809.977 185.69 24.9666 + endloop + endfacet + facet normal -0.442894 -0.54099 0.714965 + outer loop + vertex -808.572 186.566 26.4993 + vertex -812.673 189.343 26.0601 + vertex -809.977 185.69 24.9666 + endloop + endfacet + facet normal -0.446584 -0.542647 0.711405 + outer loop + vertex -809.977 185.69 24.9666 + vertex -812.673 189.343 26.0601 + vertex -814.311 188.991 24.7638 + endloop + endfacet + facet normal -0.450761 -0.534944 0.714597 + outer loop + vertex -812.673 189.343 26.0601 + vertex -816.523 192.313 25.8554 + vertex -814.311 188.991 24.7638 + endloop + endfacet + facet normal -0.455507 -0.536683 0.710271 + outer loop + vertex -814.311 188.991 24.7638 + vertex -816.523 192.313 25.8554 + vertex -818.273 192.266 24.6971 + endloop + endfacet + facet normal -0.457918 -0.530117 0.713644 + outer loop + vertex -816.523 192.313 25.8554 + vertex -820.073 195.27 25.7738 + vertex -818.273 192.266 24.6971 + endloop + endfacet + facet normal -0.463707 -0.531792 0.708642 + outer loop + vertex -818.273 192.266 24.6971 + vertex -820.073 195.27 25.7738 + vertex -821.343 195.082 24.8012 + endloop + endfacet + facet normal -0.465615 -0.527814 0.710363 + outer loop + vertex -820.073 195.27 25.7738 + vertex -823.352 198.039 25.6824 + vertex -821.343 195.082 24.8012 + endloop + endfacet + facet normal -0.466758 -0.528266 0.709276 + outer loop + vertex -821.343 195.082 24.8012 + vertex -823.352 198.039 25.6824 + vertex -824.281 197.313 24.5299 + endloop + endfacet + facet normal -0.47093 -0.523805 0.709826 + outer loop + vertex -823.352 198.039 25.6824 + vertex -826.673 200.889 25.5813 + vertex -824.281 197.313 24.5299 + endloop + endfacet + facet normal -0.473526 -0.524814 0.707349 + outer loop + vertex -824.281 197.313 24.5299 + vertex -826.673 200.889 25.5813 + vertex -827.919 200.399 24.3841 + endloop + endfacet + facet normal -0.476737 -0.520022 0.708731 + outer loop + vertex -826.673 200.889 25.5813 + vertex -830.189 204.053 25.5378 + vertex -827.919 200.399 24.3841 + endloop + endfacet + facet normal -0.480189 -0.521164 0.705554 + outer loop + vertex -827.919 200.399 24.3841 + vertex -830.189 204.053 25.5378 + vertex -831.747 203.825 24.309 + endloop + endfacet + facet normal -0.482651 -0.515942 0.707708 + outer loop + vertex -830.189 204.053 25.5378 + vertex -833.822 207.415 25.5111 + vertex -831.747 203.825 24.309 + endloop + endfacet + facet normal -0.486655 -0.517061 0.704141 + outer loop + vertex -831.747 203.825 24.309 + vertex -833.822 207.415 25.5111 + vertex -835.576 207.428 24.3091 + endloop + endfacet + facet normal -0.48805 -0.512889 0.706224 + outer loop + vertex -833.822 207.415 25.5111 + vertex -837.276 210.575 25.4197 + vertex -835.576 207.428 24.3091 + endloop + endfacet + facet normal -0.4928 -0.514001 0.702104 + outer loop + vertex -835.576 207.428 24.3091 + vertex -837.276 210.575 25.4197 + vertex -838.506 210.42 24.4424 + endloop + endfacet + facet normal -0.49325 -0.51301 0.702513 + outer loop + vertex -837.276 210.575 25.4197 + vertex -839.986 212.83 25.1629 + vertex -838.506 210.42 24.4424 + endloop + endfacet + facet normal -0.490029 -0.511937 0.705544 + outer loop + vertex -838.506 210.42 24.4424 + vertex -839.986 212.83 25.1629 + vertex -841.448 212.924 24.2161 + endloop + endfacet + facet normal -0.489426 -0.514085 0.704399 + outer loop + vertex -839.986 212.83 25.1629 + vertex -842.903 216.009 25.4564 + vertex -841.448 212.924 24.2161 + endloop + endfacet + facet normal -0.49903 -0.51548 0.696599 + outer loop + vertex -841.448 212.924 24.2161 + vertex -842.903 216.009 25.4564 + vertex -845.22 216.497 24.1581 + endloop + endfacet + facet normal -0.499164 -0.514557 0.697185 + outer loop + vertex -842.903 216.009 25.4564 + vertex -846.285 219.199 25.39 + vertex -845.22 216.497 24.1581 + endloop + endfacet + facet normal -0.504683 -0.514824 0.693002 + outer loop + vertex -845.22 216.497 24.1581 + vertex -846.285 219.199 25.39 + vertex -848.993 220.221 24.177 + endloop + endfacet + facet normal -0.50489 -0.521506 0.687835 + outer loop + vertex -846.285 219.199 25.39 + vertex -849.175 222.651 25.8859 + vertex -848.993 220.221 24.177 + endloop + endfacet + facet normal -0.516845 -0.518 0.681577 + outer loop + vertex -848.993 220.221 24.177 + vertex -849.175 222.651 25.8859 + vertex -852.179 223.517 24.2654 + endloop + endfacet + facet normal -0.516989 -0.516323 0.68274 + outer loop + vertex -849.175 222.651 25.8859 + vertex -852.025 225.3 25.7308 + vertex -852.179 223.517 24.2654 + endloop + endfacet + facet normal -0.529188 -0.510911 0.677443 + outer loop + vertex -852.179 223.517 24.2654 + vertex -852.025 225.3 25.7308 + vertex -853.797 225.571 24.5513 + endloop + endfacet + facet normal -0.527963 -0.516197 0.674385 + outer loop + vertex -852.025 225.3 25.7308 + vertex -853.157 226.724 25.9345 + vertex -853.797 225.571 24.5513 + endloop + endfacet + facet normal -0.540965 -0.505937 0.671852 + outer loop + vertex -853.797 225.571 24.5513 + vertex -853.157 226.724 25.9345 + vertex -854.528 226.279 24.4957 + endloop + endfacet + facet normal -0.553851 -0.484146 0.677386 + outer loop + vertex -853.157 226.724 25.9345 + vertex -854.151 227.071 25.3699 + vertex -854.528 226.279 24.4957 + endloop + endfacet + facet normal -0.577348 -0.465612 0.670727 + outer loop + vertex -854.528 226.279 24.4957 + vertex -854.151 227.071 25.3699 + vertex -854.774 226.319 24.3111 + endloop + endfacet + facet normal -0.662413 -0.368794 0.652073 + outer loop + vertex -854.151 227.071 25.3699 + vertex -854.239 227.01 25.2453 + vertex -854.774 226.319 24.3111 + endloop + endfacet + facet normal 0.549973 0.489362 -0.676797 + outer loop + vertex -854.774 226.319 24.3111 + vertex -854.239 227.01 25.2453 + vertex -854.787 226.076 24.125 + endloop + endfacet + facet normal -0.456659 -0.560764 0.690656 + outer loop + vertex -854.787 226.076 24.125 + vertex -854.239 227.01 25.2453 + vertex -854.74 226.316 24.3515 + endloop + endfacet + facet normal -0.376972 -0.61768 0.690191 + outer loop + vertex -853.943 228.086 26.3702 + vertex -854.74 226.316 24.3515 + vertex -854.239 227.01 25.2453 + endloop + endfacet + facet normal -0.54705 -0.510541 0.663388 + outer loop + vertex -854.74 226.316 24.3515 + vertex -853.943 228.086 26.3702 + vertex -855.096 226.917 24.5202 + endloop + endfacet + facet normal -0.54043 -0.517331 0.663554 + outer loop + vertex -855.655 228.495 25.2954 + vertex -855.096 226.917 24.5202 + vertex -853.943 228.086 26.3702 + endloop + endfacet + facet normal -0.480287 -0.517821 0.707945 + outer loop + vertex -855.655 228.495 25.2954 + vertex -856.763 227.09 23.5153 + vertex -855.096 226.917 24.5202 + endloop + endfacet + facet normal -0.486572 -0.490262 0.723112 + outer loop + vertex -855.096 226.917 24.5202 + vertex -856.763 227.09 23.5153 + vertex -855.836 225.799 23.2642 + endloop + endfacet + facet normal -0.485672 -0.490986 0.723225 + outer loop + vertex -855.096 226.917 24.5202 + vertex -855.836 225.799 23.2642 + vertex -854.74 226.316 24.3515 + endloop + endfacet + facet normal -0.505408 -0.495815 0.706208 + outer loop + vertex -855.655 228.495 25.2954 + vertex -858.432 229.215 23.8133 + vertex -856.763 227.09 23.5153 + endloop + endfacet + facet normal -0.504515 -0.506003 0.699589 + outer loop + vertex -857.531 230.963 25.7278 + vertex -858.432 229.215 23.8133 + vertex -855.655 228.495 25.2954 + endloop + endfacet + facet normal -0.516878 -0.496895 0.697089 + outer loop + vertex -857.531 230.963 25.7278 + vertex -860.895 231.868 23.8779 + vertex -858.432 229.215 23.8133 + endloop + endfacet + facet normal -0.517421 -0.490495 0.701206 + outer loop + vertex -860.229 233.398 25.4401 + vertex -860.895 231.868 23.8779 + vertex -857.531 230.963 25.7278 + endloop + endfacet + facet normal -0.515812 -0.49161 0.701611 + outer loop + vertex -860.229 233.398 25.4401 + vertex -863.739 234.86 23.8836 + vertex -860.895 231.868 23.8779 + endloop + endfacet + facet normal -0.516514 -0.500834 0.694535 + outer loop + vertex -862.828 236.544 25.7756 + vertex -863.739 234.86 23.8836 + vertex -860.229 233.398 25.4401 + endloop + endfacet + facet normal -0.528536 -0.491587 0.692092 + outer loop + vertex -862.828 236.544 25.7756 + vertex -866.718 238.047 23.8719 + vertex -863.739 234.86 23.8836 + endloop + endfacet + facet normal -0.528159 -0.480042 0.700434 + outer loop + vertex -866.183 239.644 25.3703 + vertex -866.718 238.047 23.8719 + vertex -862.828 236.544 25.7756 + endloop + endfacet + facet normal -0.531302 -0.478041 0.699425 + outer loop + vertex -866.183 239.644 25.3703 + vertex -869.69 241.288 23.8302 + vertex -866.718 238.047 23.8719 + endloop + endfacet + facet normal -0.530652 -0.47298 0.703348 + outer loop + vertex -868.89 242.765 25.4265 + vertex -869.69 241.288 23.8302 + vertex -866.183 239.644 25.3703 + endloop + endfacet + facet normal -0.538719 -0.466594 0.701479 + outer loop + vertex -868.89 242.765 25.4265 + vertex -872.572 244.545 23.7827 + vertex -869.69 241.288 23.8302 + endloop + endfacet + facet normal -0.535877 -0.447164 0.716156 + outer loop + vertex -872.079 245.81 24.9418 + vertex -872.572 244.545 23.7827 + vertex -868.89 242.765 25.4265 + endloop + endfacet + facet normal -0.533261 -0.44895 0.716992 + outer loop + vertex -872.079 245.81 24.9418 + vertex -875.299 247.811 23.7999 + vertex -872.572 244.545 23.7827 + endloop + endfacet + facet normal -0.538059 -0.464413 0.703429 + outer loop + vertex -874.145 248.703 25.2712 + vertex -875.299 247.811 23.7999 + vertex -872.079 245.81 24.9418 + endloop + endfacet + facet normal -0.550939 -0.448422 0.703835 + outer loop + vertex -874.145 248.703 25.2712 + vertex -877.894 251.199 23.9273 + vertex -875.299 247.811 23.7999 + endloop + endfacet + facet normal -0.553797 -0.456871 0.696116 + outer loop + vertex -876.905 252.291 25.4306 + vertex -877.894 251.199 23.9273 + vertex -874.145 248.703 25.2712 + endloop + endfacet + facet normal -0.567714 -0.442029 0.694487 + outer loop + vertex -876.905 252.291 25.4306 + vertex -880.505 254.718 24.0324 + vertex -877.894 251.199 23.9273 + endloop + endfacet + facet normal -0.568319 -0.4439 0.692796 + outer loop + vertex -879.613 255.849 25.4889 + vertex -880.505 254.718 24.0324 + vertex -876.905 252.291 25.4306 + endloop + endfacet + facet normal -0.583118 -0.428699 0.690066 + outer loop + vertex -879.613 255.849 25.4889 + vertex -882.984 258.226 24.1174 + vertex -880.505 254.718 24.0324 + endloop + endfacet + facet normal -0.584236 -0.432031 0.687035 + outer loop + vertex -882.053 259.275 25.5682 + vertex -882.984 258.226 24.1174 + vertex -879.613 255.849 25.4889 + endloop + endfacet + facet normal -0.598516 -0.416015 0.684624 + outer loop + vertex -882.053 259.275 25.5682 + vertex -885.307 261.713 24.2053 + vertex -882.984 258.226 24.1174 + endloop + endfacet + facet normal -0.599174 -0.417834 0.682939 + outer loop + vertex -884.314 262.672 25.6633 + vertex -885.307 261.713 24.2053 + vertex -882.053 259.275 25.5682 + endloop + endfacet + facet normal -0.612581 -0.401116 0.681066 + outer loop + vertex -884.314 262.672 25.6633 + vertex -887.508 265.212 24.2861 + vertex -885.307 261.713 24.2053 + endloop + endfacet + facet normal -0.613847 -0.404373 0.677993 + outer loop + vertex -886.479 266.109 25.7531 + vertex -887.508 265.212 24.2861 + vertex -884.314 262.672 25.6633 + endloop + endfacet + facet normal -0.627894 -0.385334 0.676215 + outer loop + vertex -886.479 266.109 25.7531 + vertex -889.61 268.76 24.3556 + vertex -887.508 265.212 24.2861 + endloop + endfacet + facet normal -0.631292 -0.39353 0.668284 + outer loop + vertex -888.564 269.626 25.8537 + vertex -889.61 268.76 24.3556 + vertex -886.479 266.109 25.7531 + endloop + endfacet + facet normal -0.646095 -0.372257 0.666323 + outer loop + vertex -888.564 269.626 25.8537 + vertex -891.625 272.392 24.4312 + vertex -889.61 268.76 24.3556 + endloop + endfacet + facet normal -0.649549 -0.380112 0.658484 + outer loop + vertex -890.574 273.239 25.9575 + vertex -891.625 272.392 24.4312 + vertex -888.564 269.626 25.8537 + endloop + endfacet + facet normal -0.665289 -0.35628 0.65609 + outer loop + vertex -890.574 273.239 25.9575 + vertex -893.552 276.131 24.5074 + vertex -891.625 272.392 24.4312 + endloop + endfacet + facet normal -0.668799 -0.363767 0.648368 + outer loop + vertex -892.495 276.944 26.0547 + vertex -893.552 276.131 24.5074 + vertex -890.574 273.239 25.9575 + endloop + endfacet + facet normal -0.683995 -0.339175 0.645841 + outer loop + vertex -892.495 276.944 26.0547 + vertex -895.391 279.994 24.5885 + vertex -893.552 276.131 24.5074 + endloop + endfacet + facet normal -0.687273 -0.345621 0.638907 + outer loop + vertex -894.324 280.762 26.1519 + vertex -895.391 279.994 24.5885 + vertex -892.495 276.944 26.0547 + endloop + endfacet + facet normal -0.702826 -0.31838 0.636137 + outer loop + vertex -894.324 280.762 26.1519 + vertex -897.127 283.974 24.6625 + vertex -895.391 279.994 24.5885 + endloop + endfacet + facet normal -0.705424 -0.323094 0.630862 + outer loop + vertex -896.056 284.693 26.2287 + vertex -897.127 283.974 24.6625 + vertex -894.324 280.762 26.1519 + endloop + endfacet + facet normal -0.719301 -0.296614 0.628193 + outer loop + vertex -896.056 284.693 26.2287 + vertex -898.745 288.065 24.7419 + vertex -897.127 283.974 24.6625 + endloop + endfacet + facet normal -0.721015 -0.299441 0.624878 + outer loop + vertex -897.67 288.734 26.3028 + vertex -898.745 288.065 24.7419 + vertex -896.056 284.693 26.2287 + endloop + endfacet + facet normal -0.734402 -0.271427 0.622078 + outer loop + vertex -897.67 288.734 26.3028 + vertex -900.223 292.231 24.8146 + vertex -898.745 288.065 24.7419 + endloop + endfacet + facet normal -0.73593 -0.273745 0.61925 + outer loop + vertex -899.147 292.853 26.368 + vertex -900.223 292.231 24.8146 + vertex -897.67 288.734 26.3028 + endloop + endfacet + facet normal -0.747658 -0.24672 0.616553 + outer loop + vertex -899.147 292.853 26.368 + vertex -901.547 296.426 24.8882 + vertex -900.223 292.231 24.8146 + endloop + endfacet + facet normal -0.749716 -0.249627 0.612872 + outer loop + vertex -900.472 297.008 26.44 + vertex -901.547 296.426 24.8882 + vertex -899.147 292.853 26.368 + endloop + endfacet + facet normal -0.760534 -0.222206 0.610093 + outer loop + vertex -900.472 297.008 26.44 + vertex -902.701 300.595 24.9677 + vertex -901.547 296.426 24.8882 + endloop + endfacet + facet normal -0.760927 -0.22273 0.609411 + outer loop + vertex -901.629 301.135 26.5035 + vertex -902.701 300.595 24.9677 + vertex -900.472 297.008 26.44 + endloop + endfacet + facet normal -0.771231 -0.193674 0.606377 + outer loop + vertex -901.629 301.135 26.5035 + vertex -903.68 304.714 25.0385 + vertex -902.701 300.595 24.9677 + endloop + endfacet + facet normal -0.772297 -0.195017 0.604587 + outer loop + vertex -902.612 305.215 26.5644 + vertex -903.68 304.714 25.0385 + vertex -901.629 301.135 26.5035 + endloop + endfacet + facet normal -0.78206 -0.163996 0.601238 + outer loop + vertex -902.612 305.215 26.5644 + vertex -904.486 308.814 25.1082 + vertex -903.68 304.714 25.0385 + endloop + endfacet + facet normal -0.783555 -0.16576 0.598802 + outer loop + vertex -903.423 309.289 26.6304 + vertex -904.486 308.814 25.1082 + vertex -902.612 305.215 26.5644 + endloop + endfacet + facet normal -0.792515 -0.133607 0.595037 + outer loop + vertex -903.423 309.289 26.6304 + vertex -905.133 312.949 25.1752 + vertex -904.486 308.814 25.1082 + endloop + endfacet + facet normal -0.793134 -0.134285 0.594058 + outer loop + vertex -904.078 313.403 26.6856 + vertex -905.133 312.949 25.1752 + vertex -903.423 309.289 26.6304 + endloop + endfacet + facet normal -0.800709 -0.103394 0.590063 + outer loop + vertex -904.078 313.403 26.6856 + vertex -905.633 317.157 25.2329 + vertex -905.133 312.949 25.1752 + endloop + endfacet + facet normal -0.802204 -0.104904 0.587762 + outer loop + vertex -904.586 317.606 26.7427 + vertex -905.633 317.157 25.2329 + vertex -904.078 313.403 26.6856 + endloop + endfacet + facet normal -0.808558 -0.075832 0.583509 + outer loop + vertex -904.586 317.606 26.7427 + vertex -905.994 321.452 25.2909 + vertex -905.633 317.157 25.2329 + endloop + endfacet + facet normal -0.807754 -0.0750809 0.584719 + outer loop + vertex -904.95 321.898 26.7907 + vertex -905.994 321.452 25.2909 + vertex -904.586 317.606 26.7427 + endloop + endfacet + facet normal -0.813168 -0.046982 0.58013 + outer loop + vertex -904.95 321.898 26.7907 + vertex -906.211 325.82 25.3406 + vertex -905.994 321.452 25.2909 + endloop + endfacet + facet normal -0.812926 -0.0467731 0.580485 + outer loop + vertex -905.166 326.265 26.84 + vertex -906.211 325.82 25.3406 + vertex -904.95 321.898 26.7907 + endloop + endfacet + facet normal -0.817578 -0.0190561 0.575502 + outer loop + vertex -905.166 326.265 26.84 + vertex -906.282 330.231 25.3865 + vertex -906.211 325.82 25.3406 + endloop + endfacet + facet normal -0.818042 -0.0194327 0.57483 + outer loop + vertex -905.235 330.668 26.8905 + vertex -906.282 330.231 25.3865 + vertex -905.166 326.265 26.84 + endloop + endfacet + facet normal -0.821751 0.00670741 0.569807 + outer loop + vertex -905.235 330.668 26.8905 + vertex -906.213 334.648 25.4337 + vertex -906.282 330.231 25.3865 + endloop + endfacet + facet normal -0.820634 0.00756675 0.571404 + outer loop + vertex -905.167 335.065 26.9302 + vertex -906.213 334.648 25.4337 + vertex -905.235 330.668 26.8905 + endloop + endfacet + facet normal -0.823258 0.0304765 0.566849 + outer loop + vertex -905.167 335.065 26.9302 + vertex -906.018 339.041 25.4807 + vertex -906.213 334.648 25.4337 + endloop + endfacet + facet normal -0.823783 0.0300934 0.566106 + outer loop + vertex -904.978 339.436 26.9731 + vertex -906.018 339.041 25.4807 + vertex -905.167 335.065 26.9302 + endloop + endfacet + facet normal -0.825813 0.0530573 0.561442 + outer loop + vertex -904.978 339.436 26.9731 + vertex -905.71 343.402 25.5219 + vertex -906.018 339.041 25.4807 + endloop + endfacet + facet normal -0.828903 0.0508883 0.557073 + outer loop + vertex -904.683 343.785 27.0142 + vertex -905.71 343.402 25.5219 + vertex -904.978 339.436 26.9731 + endloop + endfacet + facet normal -0.830299 0.0717919 0.552675 + outer loop + vertex -904.683 343.785 27.0142 + vertex -905.305 347.75 25.5654 + vertex -905.71 343.402 25.5219 + endloop + endfacet + facet normal -0.832982 0.0699767 0.548858 + outer loop + vertex -904.294 348.133 27.0503 + vertex -905.305 347.75 25.5654 + vertex -904.683 343.785 27.0142 + endloop + endfacet + facet normal -0.833954 0.0890331 0.544604 + outer loop + vertex -904.294 348.133 27.0503 + vertex -904.813 352.115 25.6045 + vertex -905.305 347.75 25.5654 + endloop + endfacet + facet normal -0.838098 0.0863295 0.538646 + outer loop + vertex -903.819 352.507 27.0888 + vertex -904.813 352.115 25.6045 + vertex -904.294 348.133 27.0503 + endloop + endfacet + facet normal -0.838807 0.104774 0.534252 + outer loop + vertex -903.819 352.507 27.0888 + vertex -904.244 356.507 25.6372 + vertex -904.813 352.115 25.6045 + endloop + endfacet + facet normal -0.840609 0.103633 0.531635 + outer loop + vertex -903.266 356.886 27.1094 + vertex -904.244 356.507 25.6372 + vertex -903.819 352.507 27.0888 + endloop + endfacet + facet normal -0.840927 0.118662 0.527979 + outer loop + vertex -903.266 356.886 27.1094 + vertex -903.605 360.916 25.6635 + vertex -904.244 356.507 25.6372 + endloop + endfacet + facet normal -0.842605 0.117641 0.525526 + outer loop + vertex -902.641 361.277 27.1294 + vertex -903.605 360.916 25.6635 + vertex -903.266 356.886 27.1094 + endloop + endfacet + facet normal -0.842645 0.134399 0.521427 + outer loop + vertex -902.641 361.277 27.1294 + vertex -902.893 365.34 25.6742 + vertex -903.605 360.916 25.6635 + endloop + endfacet + facet normal -0.842579 0.134438 0.521525 + outer loop + vertex -901.93 365.7 27.1368 + vertex -902.893 365.34 25.6742 + vertex -902.641 361.277 27.1294 + endloop + endfacet + facet normal -0.842436 0.147365 0.518252 + outer loop + vertex -901.93 365.7 27.1368 + vertex -902.097 369.827 25.6923 + vertex -902.893 365.34 25.6742 + endloop + endfacet + facet normal -0.845023 0.145924 0.514434 + outer loop + vertex -901.108 370.268 27.1922 + vertex -902.097 369.827 25.6923 + vertex -901.93 365.7 27.1368 + endloop + endfacet + facet normal -0.845004 0.159124 0.510537 + outer loop + vertex -901.108 370.268 27.1922 + vertex -901.199 374.438 25.7406 + vertex -902.097 369.827 25.6923 + endloop + endfacet + facet normal -0.850351 0.156207 0.502496 + outer loop + vertex -900.15 375.054 27.3253 + vertex -901.199 374.438 25.7406 + vertex -901.108 370.268 27.1922 + endloop + endfacet + facet normal -0.850723 0.170465 0.497204 + outer loop + vertex -900.15 375.054 27.3253 + vertex -900.204 379.176 25.819 + vertex -901.199 374.438 25.7406 + endloop + endfacet + facet normal -0.8598 0.165214 0.483166 + outer loop + vertex -899.065 380.077 27.5391 + vertex -900.204 379.176 25.819 + vertex -900.15 375.054 27.3253 + endloop + endfacet + facet normal -0.86099 0.183495 0.47437 + outer loop + vertex -899.065 380.077 27.5391 + vertex -899.18 383.875 25.8607 + vertex -900.204 379.176 25.819 + endloop + endfacet + facet normal -0.85712 0.186223 0.480277 + outer loop + vertex -898.177 384.639 27.3535 + vertex -899.18 383.875 25.8607 + vertex -899.065 380.077 27.5391 + endloop + endfacet + facet normal -0.857442 0.193076 0.476985 + outer loop + vertex -898.177 384.639 27.3535 + vertex -898.124 388.41 25.9229 + vertex -899.18 383.875 25.8607 + endloop + endfacet + facet normal -0.867524 0.187102 0.460863 + outer loop + vertex -897.036 388.891 27.7761 + vertex -898.124 388.41 25.9229 + vertex -898.177 384.639 27.3535 + endloop + endfacet + facet normal -0.866202 0.206355 0.455095 + outer loop + vertex -897.036 388.891 27.7761 + vertex -897.03 392.925 25.9586 + vertex -898.124 388.41 25.9229 + endloop + endfacet + facet normal -0.860489 0.210364 0.464011 + outer loop + vertex -896.015 393.73 27.4759 + vertex -897.03 392.925 25.9586 + vertex -897.036 388.891 27.7761 + endloop + endfacet + facet normal -0.860583 0.213624 0.462344 + outer loop + vertex -896.015 393.73 27.4759 + vertex -895.912 397.392 25.9751 + vertex -897.03 392.925 25.9586 + endloop + endfacet + facet normal -0.868545 0.20861 0.449568 + outer loop + vertex -894.822 397.916 27.8377 + vertex -895.912 397.392 25.9751 + vertex -896.015 393.73 27.4759 + endloop + endfacet + facet normal -0.867229 0.224947 0.4442 + outer loop + vertex -894.822 397.916 27.8377 + vertex -894.765 401.813 25.9754 + vertex -895.912 397.392 25.9751 + endloop + endfacet + facet normal -0.860137 0.230104 0.45521 + outer loop + vertex -893.751 402.601 27.4938 + vertex -894.765 401.813 25.9754 + vertex -894.822 397.916 27.8377 + endloop + endfacet + facet normal -0.860135 0.229617 0.455461 + outer loop + vertex -893.751 402.601 27.4938 + vertex -893.579 406.251 25.9784 + vertex -894.765 401.813 25.9754 + endloop + endfacet + facet normal -0.869075 0.224047 0.441035 + outer loop + vertex -892.499 406.756 27.8502 + vertex -893.579 406.251 25.9784 + vertex -893.751 402.601 27.4938 + endloop + endfacet + facet normal -0.867628 0.238435 0.436315 + outer loop + vertex -892.499 406.756 27.8502 + vertex -892.345 410.731 25.9836 + vertex -893.579 406.251 25.9784 + endloop + endfacet + facet normal -0.85856 0.244755 0.450521 + outer loop + vertex -891.339 411.472 27.4983 + vertex -892.345 410.731 25.9836 + vertex -892.499 406.756 27.8502 + endloop + endfacet + facet normal -0.858593 0.243144 0.45133 + outer loop + vertex -891.339 411.472 27.4983 + vertex -891.073 415.225 25.9815 + vertex -892.345 410.731 25.9836 + endloop + endfacet + facet normal -0.868729 0.237183 0.434804 + outer loop + vertex -890.03 415.619 27.8517 + vertex -891.073 415.225 25.9815 + vertex -891.339 411.472 27.4983 + endloop + endfacet + facet normal -0.867052 0.249423 0.431289 + outer loop + vertex -890.03 415.619 27.8517 + vertex -889.788 419.683 25.9875 + vertex -891.073 415.225 25.9815 + endloop + endfacet + facet normal -0.858594 0.255071 0.444697 + outer loop + vertex -888.82 420.297 27.5042 + vertex -889.788 419.683 25.9875 + vertex -890.03 415.619 27.8517 + endloop + endfacet + facet normal -0.858808 0.251714 0.446194 + outer loop + vertex -888.82 420.297 27.5042 + vertex -888.506 424.051 25.9915 + vertex -889.788 419.683 25.9875 + endloop + endfacet + facet normal -0.867606 0.246638 0.431774 + outer loop + vertex -887.507 424.305 27.8539 + vertex -888.506 424.051 25.9915 + vertex -888.82 420.297 27.5042 + endloop + endfacet + facet normal -0.865559 0.258235 0.429095 + outer loop + vertex -887.507 424.305 27.8539 + vertex -887.222 428.351 25.9927 + vertex -888.506 424.051 25.9915 + endloop + endfacet + facet normal -0.856581 0.264132 0.443287 + outer loop + vertex -886.28 428.877 27.4998 + vertex -887.222 428.351 25.9927 + vertex -887.507 424.305 27.8539 + endloop + endfacet + facet normal -0.857114 0.258432 0.44561 + outer loop + vertex -886.28 428.877 27.4998 + vertex -885.925 432.652 25.9931 + vertex -887.222 428.351 25.9927 + endloop + endfacet + facet normal -0.868855 0.251807 0.426245 + outer loop + vertex -884.951 432.861 27.8564 + vertex -885.925 432.652 25.9931 + vertex -886.28 428.877 27.4998 + endloop + endfacet + facet normal -0.866698 0.263014 0.423861 + outer loop + vertex -884.951 432.861 27.8564 + vertex -884.601 437.015 25.9942 + vertex -885.925 432.652 25.9931 + endloop + endfacet + facet normal -0.858785 0.268063 0.436613 + outer loop + vertex -883.678 437.509 27.5059 + vertex -884.601 437.015 25.9942 + vertex -884.951 432.861 27.8564 + endloop + endfacet + facet normal -0.859362 0.262752 0.4387 + outer loop + vertex -883.678 437.509 27.5059 + vertex -883.249 441.443 25.99 + vertex -884.601 437.015 25.9942 + endloop + endfacet + facet normal -0.870805 0.256554 0.41938 + outer loop + vertex -882.315 441.56 27.8575 + vertex -883.249 441.443 25.99 + vertex -883.678 437.509 27.5059 + endloop + endfacet + facet normal -0.869023 0.264756 0.417975 + outer loop + vertex -882.315 441.56 27.8575 + vertex -881.889 445.9 25.9936 + vertex -883.249 441.443 25.99 + endloop + endfacet + facet normal -0.860729 0.269824 0.431671 + outer loop + vertex -881.014 446.271 27.5067 + vertex -881.889 445.9 25.9936 + vertex -882.315 441.56 27.8575 + endloop + endfacet + facet normal -0.861792 0.262439 0.434097 + outer loop + vertex -881.014 446.271 27.5067 + vertex -880.547 450.305 25.9953 + vertex -881.889 445.9 25.9936 + endloop + endfacet + facet normal -0.873457 0.256261 0.414008 + outer loop + vertex -879.684 450.23 27.8619 + vertex -880.547 450.305 25.9953 + vertex -881.014 446.271 27.5067 + endloop + endfacet + facet normal -0.871009 0.265649 0.413249 + outer loop + vertex -879.684 450.23 27.8619 + vertex -879.232 454.626 25.9897 + vertex -880.547 450.305 25.9953 + endloop + endfacet + facet normal -0.862961 0.270561 0.426725 + outer loop + vertex -878.416 454.843 27.5021 + vertex -879.232 454.626 25.9897 + vertex -879.684 450.23 27.8619 + endloop + endfacet + facet normal -0.864442 0.262664 0.428658 + outer loop + vertex -878.416 454.843 27.5021 + vertex -877.938 458.884 25.9895 + vertex -879.232 454.626 25.9897 + endloop + endfacet + facet normal -0.876119 0.256408 0.408254 + outer loop + vertex -877.122 458.699 27.8568 + vertex -877.938 458.884 25.9895 + vertex -878.416 454.843 27.5021 + endloop + endfacet + facet normal -0.873435 0.265785 0.408007 + outer loop + vertex -877.122 458.699 27.8568 + vertex -876.628 463.159 26.0082 + vertex -877.938 458.884 25.9895 + endloop + endfacet + facet normal -0.865639 0.270448 0.421339 + outer loop + vertex -875.841 463.328 27.5182 + vertex -876.628 463.159 26.0082 + vertex -877.122 458.699 27.8568 + endloop + endfacet + facet normal -0.866446 0.266493 0.4222 + outer loop + vertex -875.841 463.328 27.5182 + vertex -875.257 467.543 26.0555 + vertex -876.628 463.159 26.0082 + endloop + endfacet + facet normal -0.879328 0.260178 0.398861 + outer loop + vertex -874.516 467.234 27.8906 + vertex -875.257 467.543 26.0555 + vertex -875.841 463.328 27.5182 + endloop + endfacet + facet normal -0.877016 0.267436 0.399149 + outer loop + vertex -874.516 467.234 27.8906 + vertex -873.781 472.139 26.2185 + vertex -875.257 467.543 26.0555 + endloop + endfacet + facet normal -0.879654 0.266138 0.394182 + outer loop + vertex -873.335 471.462 27.6729 + vertex -873.781 472.139 26.2185 + vertex -874.516 467.234 27.8906 + endloop + endfacet + facet normal -0.890319 0.241534 0.385998 + outer loop + vertex -873.335 471.462 27.6729 + vertex -871.977 477.699 26.9008 + vertex -873.781 472.139 26.2185 + endloop + endfacet + facet normal -0.88314 0.236883 0.404907 + outer loop + vertex -873.119 476.946 24.8509 + vertex -873.781 472.139 26.2185 + vertex -871.977 477.699 26.9008 + endloop + endfacet + facet normal -0.879929 0.269945 0.390966 + outer loop + vertex -871.808 481.558 24.6172 + vertex -873.119 476.946 24.8509 + vertex -871.977 477.699 26.9008 + endloop + endfacet + facet normal -0.933203 0.212429 0.28984 + outer loop + vertex -871.808 481.558 24.6172 + vertex -871.977 477.699 26.9008 + vertex -870.772 485.621 24.9747 + endloop + endfacet + facet normal -0.975156 0.1798 0.129393 + outer loop + vertex -871.977 477.699 26.9008 + vertex -870.02 488.074 27.2322 + vertex -870.772 485.621 24.9747 + endloop + endfacet + facet normal -0.965591 0.0639442 0.252082 + outer loop + vertex -870.541 490.071 24.7314 + vertex -870.772 485.621 24.9747 + vertex -870.02 488.074 27.2322 + endloop + endfacet + facet normal -0.501013 -0.52764 0.685989 + outer loop + vertex -833.822 207.415 25.5111 + vertex -836.368 211.457 26.7604 + vertex -837.276 210.575 25.4197 + endloop + endfacet + facet normal -0.50254 -0.526132 0.686031 + outer loop + vertex -836.368 211.457 26.7604 + vertex -839.99 214.436 26.3922 + vertex -837.276 210.575 25.4197 + endloop + endfacet + facet normal -0.502626 -0.52617 0.685939 + outer loop + vertex -837.276 210.575 25.4197 + vertex -839.99 214.436 26.3922 + vertex -839.986 212.83 25.1629 + endloop + endfacet + facet normal -0.503993 -0.525688 0.685305 + outer loop + vertex -839.986 212.83 25.1629 + vertex -839.99 214.436 26.3922 + vertex -842.903 216.009 25.4564 + endloop + endfacet + facet normal -0.506167 -0.534975 0.676459 + outer loop + vertex -842.903 216.009 25.4564 + vertex -839.99 214.436 26.3922 + vertex -844.021 219.753 27.5812 + endloop + endfacet + facet normal -0.516944 -0.533987 0.669049 + outer loop + vertex -846.285 219.199 25.39 + vertex -842.903 216.009 25.4564 + vertex -844.021 219.753 27.5812 + endloop + endfacet + facet normal -0.518866 -0.530673 0.670197 + outer loop + vertex -846.285 219.199 25.39 + vertex -844.021 219.753 27.5812 + vertex -849.175 222.651 25.8859 + endloop + endfacet + facet normal -0.522512 -0.546231 0.654685 + outer loop + vertex -849.175 222.651 25.8859 + vertex -844.021 219.753 27.5812 + vertex -849.389 226.117 28.6065 + endloop + endfacet + facet normal -0.537846 -0.54088 0.646661 + outer loop + vertex -852.025 225.3 25.7308 + vertex -849.175 222.651 25.8859 + vertex -849.389 226.117 28.6065 + endloop + endfacet + facet normal -0.546354 -0.527419 0.650635 + outer loop + vertex -852.025 225.3 25.7308 + vertex -849.389 226.117 28.6065 + vertex -853.157 226.724 25.9345 + endloop + endfacet + facet normal -0.543356 -0.538741 0.643834 + outer loop + vertex -849.389 226.117 28.6065 + vertex -852.586 228.07 27.542 + vertex -853.157 226.724 25.9345 + endloop + endfacet + facet normal -0.55088 -0.53331 0.641959 + outer loop + vertex -854.151 227.071 25.3699 + vertex -853.157 226.724 25.9345 + vertex -852.586 228.07 27.542 + endloop + endfacet + facet normal 0.739348 0.223391 -0.635186 + outer loop + vertex -854.151 227.071 25.3699 + vertex -852.586 228.07 27.542 + vertex -854.239 227.01 25.2453 + endloop + endfacet + facet normal -0.562477 -0.518438 0.644082 + outer loop + vertex -853.943 228.086 26.3702 + vertex -854.239 227.01 25.2453 + vertex -852.586 228.07 27.542 + endloop + endfacet + facet normal -0.549002 -0.56141 0.619206 + outer loop + vertex -849.389 226.117 28.6065 + vertex -850.201 230.139 31.5323 + vertex -852.586 228.07 27.542 + endloop + endfacet + facet normal -0.564479 -0.545002 0.619949 + outer loop + vertex -852.586 228.07 27.542 + vertex -850.201 230.139 31.5323 + vertex -852.326 230.388 29.8169 + endloop + endfacet + facet normal -0.554186 -0.573813 0.603006 + outer loop + vertex -850.733 232.903 33.6743 + vertex -852.326 230.388 29.8169 + vertex -850.201 230.139 31.5323 + endloop + endfacet + facet normal -0.552023 -0.574458 0.604375 + outer loop + vertex -850.201 230.139 31.5323 + vertex -848.672 232.83 35.487 + vertex -850.733 232.903 33.6743 + endloop + endfacet + facet normal -0.540024 -0.60054 0.589683 + outer loop + vertex -849.512 235.523 37.4615 + vertex -850.733 232.903 33.6743 + vertex -848.672 232.83 35.487 + endloop + endfacet + facet normal -0.517784 -0.604853 0.605023 + outer loop + vertex -848.672 232.83 35.487 + vertex -847.647 235.365 38.8997 + vertex -849.512 235.523 37.4615 + endloop + endfacet + facet normal -0.508707 -0.626129 0.590915 + outer loop + vertex -848.694 238.107 40.9029 + vertex -849.512 235.523 37.4615 + vertex -847.647 235.365 38.8997 + endloop + endfacet + facet normal -0.53045 -0.612615 0.585941 + outer loop + vertex -849.512 235.523 37.4615 + vertex -848.694 238.107 40.9029 + vertex -851.247 238.502 39.0045 + endloop + endfacet + facet normal -0.51891 -0.642119 0.564283 + outer loop + vertex -850.649 241.009 42.4073 + vertex -851.247 238.502 39.0045 + vertex -848.694 238.107 40.9029 + endloop + endfacet + facet normal -0.551583 -0.622302 0.555424 + outer loop + vertex -850.649 241.009 42.4073 + vertex -854.656 242.475 40.07 + vertex -851.247 238.502 39.0045 + endloop + endfacet + facet normal -0.516872 -0.605457 0.605198 + outer loop + vertex -846.686 232.311 36.6648 + vertex -847.647 235.365 38.8997 + vertex -848.672 232.83 35.487 + endloop + endfacet + facet normal -0.520394 -0.588799 0.618471 + outer loop + vertex -846.686 232.311 36.6648 + vertex -848.672 232.83 35.487 + vertex -847.285 229.296 33.2908 + endloop + endfacet + facet normal -0.511679 -0.593563 0.621182 + outer loop + vertex -846.686 232.311 36.6648 + vertex -847.285 229.296 33.2908 + vertex -843.274 227.977 35.3332 + endloop + endfacet + facet normal -0.502733 -0.58983 0.631949 + outer loop + vertex -845.347 233.846 39.1626 + vertex -846.686 232.311 36.6648 + vertex -843.274 227.977 35.3332 + endloop + endfacet + facet normal -0.476398 -0.611884 0.631382 + outer loop + vertex -845.347 233.846 39.1626 + vertex -847.647 235.365 38.8997 + vertex -846.686 232.311 36.6648 + endloop + endfacet + facet normal -0.47935 -0.617735 0.6234 + outer loop + vertex -845.347 233.846 39.1626 + vertex -846.91 237.827 41.9055 + vertex -847.647 235.365 38.8997 + endloop + endfacet + facet normal -0.452511 -0.632344 0.628789 + outer loop + vertex -847.647 235.365 38.8997 + vertex -846.91 237.827 41.9055 + vertex -848.694 238.107 40.9029 + endloop + endfacet + facet normal -0.448195 -0.646778 0.617089 + outer loop + vertex -848.112 240.495 43.8286 + vertex -848.694 238.107 40.9029 + vertex -846.91 237.827 41.9055 + endloop + endfacet + facet normal -0.351118 -0.646473 0.677339 + outer loop + vertex -846.91 237.827 41.9055 + vertex -846.458 240.208 44.4117 + vertex -848.112 240.495 43.8286 + endloop + endfacet + facet normal -0.399742 -0.627544 0.668128 + outer loop + vertex -844.535 236.465 42.047 + vertex -846.458 240.208 44.4117 + vertex -846.91 237.827 41.9055 + endloop + endfacet + facet normal -0.396628 -0.621322 0.675756 + outer loop + vertex -844.535 236.465 42.047 + vertex -846.91 237.827 41.9055 + vertex -845.347 233.846 39.1626 + endloop + endfacet + facet normal -0.471478 -0.634918 0.612035 + outer loop + vertex -848.694 238.107 40.9029 + vertex -848.112 240.495 43.8286 + vertex -850.649 241.009 42.4073 + endloop + endfacet + facet normal -0.461468 -0.670016 0.581486 + outer loop + vertex -850.232 243.199 45.2624 + vertex -850.649 241.009 42.4073 + vertex -848.112 240.495 43.8286 + endloop + endfacet + facet normal -0.511853 -0.643833 0.568758 + outer loop + vertex -850.232 243.199 45.2624 + vertex -854.264 244.788 43.4319 + vertex -850.649 241.009 42.4073 + endloop + endfacet + facet normal -0.560368 -0.585488 0.585826 + outer loop + vertex -850.733 232.903 33.6743 + vertex -849.512 235.523 37.4615 + vertex -852.317 235.922 35.1767 + endloop + endfacet + facet normal -0.5603 -0.585486 0.585893 + outer loop + vertex -852.317 235.922 35.1767 + vertex -853.627 233.263 31.2669 + vertex -850.733 232.903 33.6743 + endloop + endfacet + facet normal -0.577358 -0.572124 0.582522 + outer loop + vertex -852.317 235.922 35.1767 + vertex -856.927 237.425 32.0837 + vertex -853.627 233.263 31.2669 + endloop + endfacet + facet normal -0.565602 -0.56616 0.599631 + outer loop + vertex -856.927 237.425 32.0837 + vertex -858.028 234.308 28.1027 + vertex -853.627 233.263 31.2669 + endloop + endfacet + facet normal -0.568876 -0.553367 0.608412 + outer loop + vertex -853.627 233.263 31.2669 + vertex -858.028 234.308 28.1027 + vertex -854.705 230.597 27.834 + endloop + endfacet + facet normal -0.55866 -0.560855 0.611017 + outer loop + vertex -853.627 233.263 31.2669 + vertex -854.705 230.597 27.834 + vertex -852.326 230.388 29.8169 + endloop + endfacet + facet normal -0.583316 -0.553407 0.594544 + outer loop + vertex -856.927 237.425 32.0837 + vertex -863.764 240.478 28.2176 + vertex -858.028 234.308 28.1027 + endloop + endfacet + facet normal -0.582203 -0.571554 0.578244 + outer loop + vertex -861.746 242.965 32.7076 + vertex -863.764 240.478 28.2176 + vertex -856.927 237.425 32.0837 + endloop + endfacet + facet normal -0.593471 -0.579175 0.558881 + outer loop + vertex -855.573 240.009 36.1992 + vertex -861.746 242.965 32.7076 + vertex -856.927 237.425 32.0837 + endloop + endfacet + facet normal -0.591059 -0.607546 0.530601 + outer loop + vertex -860.474 245.342 36.8465 + vertex -861.746 242.965 32.7076 + vertex -855.573 240.009 36.1992 + endloop + endfacet + facet normal -0.592469 -0.608515 0.527911 + outer loop + vertex -854.656 242.475 40.07 + vertex -860.474 245.342 36.8465 + vertex -855.573 240.009 36.1992 + endloop + endfacet + facet normal -0.618872 -0.583809 0.525513 + outer loop + vertex -860.474 245.342 36.8465 + vertex -867.803 249.582 32.9263 + vertex -861.746 242.965 32.7076 + endloop + endfacet + facet normal -0.607977 -0.574577 0.547928 + outer loop + vertex -867.803 249.582 32.9263 + vertex -868.049 246.557 29.4805 + vertex -861.746 242.965 32.7076 + endloop + endfacet + facet normal -0.634746 -0.557612 0.534945 + outer loop + vertex -868.049 246.557 29.4805 + vertex -867.803 249.582 32.9263 + vertex -872.63 251.558 29.2576 + endloop + endfacet + facet normal -0.636723 -0.547475 0.543006 + outer loop + vertex -874.086 254.714 30.7325 + vertex -872.63 251.558 29.2576 + vertex -867.803 249.582 32.9263 + endloop + endfacet + facet normal -0.648168 -0.585453 0.486954 + outer loop + vertex -872.113 255.245 33.9969 + vertex -874.086 254.714 30.7325 + vertex -867.803 249.582 32.9263 + endloop + endfacet + facet normal -0.646999 -0.584967 0.489087 + outer loop + vertex -865.905 251.209 37.3825 + vertex -872.113 255.245 33.9969 + vertex -867.803 249.582 32.9263 + endloop + endfacet + facet normal -0.646616 -0.605926 0.463401 + outer loop + vertex -871.125 257.02 37.6972 + vertex -872.113 255.245 33.9969 + vertex -865.905 251.209 37.3825 + endloop + endfacet + facet normal -0.653851 -0.611463 0.445637 + outer loop + vertex -865.052 253.154 41.3017 + vertex -871.125 257.02 37.6972 + vertex -865.905 251.209 37.3825 + endloop + endfacet + facet normal -0.652745 -0.622027 0.432441 + outer loop + vertex -870.579 259.112 41.5291 + vertex -871.125 257.02 37.6972 + vertex -865.052 253.154 41.3017 + endloop + endfacet + facet normal -0.663649 -0.630974 0.401798 + outer loop + vertex -864.832 255.057 44.6547 + vertex -870.579 259.112 41.5291 + vertex -865.052 253.154 41.3017 + endloop + endfacet + facet normal -0.662956 -0.638935 0.390194 + outer loop + vertex -870.211 260.872 45.0383 + vertex -870.579 259.112 41.5291 + vertex -864.832 255.057 44.6547 + endloop + endfacet + facet normal -0.678821 -0.65036 0.340931 + outer loop + vertex -865.049 256.611 47.187 + vertex -870.211 260.872 45.0383 + vertex -864.832 255.057 44.6547 + endloop + endfacet + facet normal -0.678862 -0.654008 0.333796 + outer loop + vertex -870.222 262.245 47.7049 + vertex -870.211 260.872 45.0383 + vertex -865.049 256.611 47.187 + endloop + endfacet + facet normal -0.678793 -0.574763 0.457043 + outer loop + vertex -872.113 255.245 33.9969 + vertex -871.125 257.02 37.6972 + vertex -876.12 260.104 34.1558 + endloop + endfacet + facet normal -0.672159 -0.569806 0.472783 + outer loop + vertex -876.12 260.104 34.1558 + vertex -876.921 258.657 31.2743 + vertex -872.113 255.245 33.9969 + endloop + endfacet + facet normal -0.702759 -0.538108 0.46537 + outer loop + vertex -876.12 260.104 34.1558 + vertex -879.719 262.42 31.3999 + vertex -876.921 258.657 31.2743 + endloop + endfacet + facet normal -0.692255 -0.531073 0.488614 + outer loop + vertex -879.719 262.42 31.3999 + vertex -880.445 261.27 29.1212 + vertex -876.921 258.657 31.2743 + endloop + endfacet + facet normal -0.691459 -0.516013 0.505584 + outer loop + vertex -876.921 258.657 31.2743 + vertex -880.445 261.27 29.1212 + vertex -878.077 257.872 28.8919 + endloop + endfacet + facet normal -0.666779 -0.548653 0.504365 + outer loop + vertex -876.921 258.657 31.2743 + vertex -878.077 257.872 28.8919 + vertex -874.086 254.714 30.7325 + endloop + endfacet + facet normal -0.661276 -0.521249 0.539457 + outer loop + vertex -874.086 254.714 30.7325 + vertex -878.077 257.872 28.8919 + vertex -876.121 255.013 28.5268 + endloop + endfacet + facet normal -0.652042 -0.516878 0.554687 + outer loop + vertex -878.077 257.872 28.8919 + vertex -878.949 257.006 27.0593 + vertex -876.121 255.013 28.5268 + endloop + endfacet + facet normal -0.650831 -0.508398 0.563871 + outer loop + vertex -876.121 255.013 28.5268 + vertex -878.949 257.006 27.0593 + vertex -876.264 253.602 27.0893 + endloop + endfacet + facet normal -0.633996 -0.519378 0.57297 + outer loop + vertex -876.121 255.013 28.5268 + vertex -876.264 253.602 27.0893 + vertex -872.63 251.558 29.2576 + endloop + endfacet + facet normal -0.634039 -0.523353 0.569295 + outer loop + vertex -872.63 251.558 29.2576 + vertex -876.264 253.602 27.0893 + vertex -872.995 249.709 27.1518 + endloop + endfacet + facet normal -0.614422 -0.537078 0.577955 + outer loop + vertex -872.63 251.558 29.2576 + vertex -872.995 249.709 27.1518 + vertex -868.049 246.557 29.4805 + endloop + endfacet + facet normal -0.612508 -0.5235 0.592269 + outer loop + vertex -868.049 246.557 29.4805 + vertex -872.995 249.709 27.1518 + vertex -869.901 245.589 26.7099 + endloop + endfacet + facet normal -0.597585 -0.543667 0.589337 + outer loop + vertex -868.049 246.557 29.4805 + vertex -869.901 245.589 26.7099 + vertex -863.764 240.478 28.2176 + endloop + endfacet + facet normal -0.67145 -0.493459 0.552859 + outer loop + vertex -878.077 257.872 28.8919 + vertex -881.244 260.283 27.1981 + vertex -878.949 257.006 27.0593 + endloop + endfacet + facet normal -0.673463 -0.505735 0.539147 + outer loop + vertex -880.445 261.27 29.1212 + vertex -881.244 260.283 27.1981 + vertex -878.077 257.872 28.8919 + endloop + endfacet + facet normal -0.69383 -0.481725 0.535295 + outer loop + vertex -880.445 261.27 29.1212 + vertex -883.471 263.645 27.3361 + vertex -881.244 260.283 27.1981 + endloop + endfacet + facet normal -0.695056 -0.490628 0.525529 + outer loop + vertex -882.742 264.72 29.3037 + vertex -883.471 263.645 27.3361 + vertex -880.445 261.27 29.1212 + endloop + endfacet + facet normal -0.71348 -0.469023 0.520542 + outer loop + vertex -882.742 264.72 29.3037 + vertex -885.622 267.086 27.4888 + vertex -883.471 263.645 27.3361 + endloop + endfacet + facet normal -0.714432 -0.476295 0.512571 + outer loop + vertex -884.901 268.248 29.5735 + vertex -885.622 267.086 27.4888 + vertex -882.742 264.72 29.3037 + endloop + endfacet + facet normal -0.737555 -0.487017 0.467789 + outer loop + vertex -882.085 265.945 31.6157 + vertex -884.901 268.248 29.5735 + vertex -882.742 264.72 29.3037 + endloop + endfacet + facet normal -0.717218 -0.510427 0.474407 + outer loop + vertex -882.085 265.945 31.6157 + vertex -882.742 264.72 29.3037 + vertex -879.719 262.42 31.3999 + endloop + endfacet + facet normal -0.728808 -0.51667 0.449323 + outer loop + vertex -879.279 263.775 33.6724 + vertex -882.085 265.945 31.6157 + vertex -879.719 262.42 31.3999 + endloop + endfacet + facet normal -0.728753 -0.51832 0.447507 + outer loop + vertex -881.235 267.097 34.3343 + vertex -882.085 265.945 31.6157 + vertex -879.279 263.775 33.6724 + endloop + endfacet + facet normal -0.722101 -0.516855 0.459817 + outer loop + vertex -879.279 263.775 33.6724 + vertex -876.587 263.219 37.2733 + vertex -881.235 267.097 34.3343 + endloop + endfacet + facet normal -0.722599 -0.526068 0.448445 + outer loop + vertex -876.587 263.219 37.2733 + vertex -881.351 269.834 37.3584 + vertex -881.235 267.097 34.3343 + endloop + endfacet + facet normal -0.751346 -0.503333 0.426772 + outer loop + vertex -883.373 270.195 34.2238 + vertex -881.235 267.097 34.3343 + vertex -881.351 269.834 37.3584 + endloop + endfacet + facet normal -0.767596 -0.464397 0.441737 + outer loop + vertex -881.351 269.834 37.3584 + vertex -886.455 274.272 33.1544 + vertex -883.373 270.195 34.2238 + endloop + endfacet + facet normal -0.769873 -0.468242 0.433642 + outer loop + vertex -883.373 270.195 34.2238 + vertex -886.455 274.272 33.1544 + vertex -884.214 269.586 32.0724 + endloop + endfacet + facet normal -0.754318 -0.467179 0.461246 + outer loop + vertex -887.007 271.979 29.9292 + vertex -884.214 269.586 32.0724 + vertex -886.455 274.272 33.1544 + endloop + endfacet + facet normal -0.771049 -0.449204 0.451331 + outer loop + vertex -889.073 275.373 29.7769 + vertex -887.007 271.979 29.9292 + vertex -886.455 274.272 33.1544 + endloop + endfacet + facet normal -0.778304 -0.420456 0.466326 + outer loop + vertex -889.073 275.373 29.7769 + vertex -886.455 274.272 33.1544 + vertex -890.619 278.893 30.3715 + endloop + endfacet + facet normal -0.768699 -0.419088 0.483184 + outer loop + vertex -890.619 278.893 30.3715 + vertex -891.589 277.874 27.9441 + vertex -889.073 275.373 29.7769 + endloop + endfacet + facet normal -0.768124 -0.415713 0.486999 + outer loop + vertex -889.073 275.373 29.7769 + vertex -891.589 277.874 27.9441 + vertex -889.714 274.239 27.7976 + endloop + endfacet + facet normal -0.752507 -0.436019 0.493579 + outer loop + vertex -889.073 275.373 29.7769 + vertex -889.714 274.239 27.7976 + vertex -887.007 271.979 29.9292 + endloop + endfacet + facet normal -0.752637 -0.438124 0.491512 + outer loop + vertex -887.007 271.979 29.9292 + vertex -889.714 274.239 27.7976 + vertex -887.701 270.636 27.6689 + endloop + endfacet + facet normal -0.733198 -0.461504 0.499434 + outer loop + vertex -887.007 271.979 29.9292 + vertex -887.701 270.636 27.6689 + vertex -884.901 268.248 29.5735 + endloop + endfacet + facet normal -0.785599 -0.392128 0.478612 + outer loop + vertex -890.619 278.893 30.3715 + vertex -893.407 281.661 28.063 + vertex -891.589 277.874 27.9441 + endloop + endfacet + facet normal -0.785709 -0.392958 0.47775 + outer loop + vertex -892.756 282.81 30.079 + vertex -893.407 281.661 28.063 + vertex -890.619 278.893 30.3715 + endloop + endfacet + facet normal -0.80372 -0.366685 0.46859 + outer loop + vertex -892.756 282.81 30.079 + vertex -895.134 285.559 28.1498 + vertex -893.407 281.661 28.063 + endloop + endfacet + facet normal -0.803866 -0.36736 0.467809 + outer loop + vertex -894.17 286.566 30.5979 + vertex -895.134 285.559 28.1498 + vertex -892.756 282.81 30.079 + endloop + endfacet + facet normal -0.81024 -0.368136 0.456057 + outer loop + vertex -892.756 282.81 30.079 + vertex -890.372 281.791 33.491 + vertex -894.17 286.566 30.5979 + endloop + endfacet + facet normal -0.811988 -0.374694 0.447527 + outer loop + vertex -890.372 281.791 33.491 + vertex -893.801 289.467 33.6964 + vertex -894.17 286.566 30.5979 + endloop + endfacet + facet normal -0.835896 -0.34748 0.424894 + outer loop + vertex -896.059 290.677 30.2429 + vertex -894.17 286.566 30.5979 + vertex -893.801 289.467 33.6964 + endloop + endfacet + facet normal -0.841857 -0.309605 0.442066 + outer loop + vertex -896.059 290.677 30.2429 + vertex -893.801 289.467 33.6964 + vertex -897.229 294.555 30.7318 + endloop + endfacet + facet normal -0.844223 -0.316905 0.432272 + outer loop + vertex -893.801 289.467 33.6964 + vertex -896.708 297.368 33.8109 + vertex -897.229 294.555 30.7318 + endloop + endfacet + facet normal -0.865661 -0.288005 0.409492 + outer loop + vertex -898.813 298.777 30.3513 + vertex -897.229 294.555 30.7318 + vertex -896.708 297.368 33.8109 + endloop + endfacet + facet normal -0.86906 -0.249194 0.427362 + outer loop + vertex -898.813 298.777 30.3513 + vertex -896.708 297.368 33.8109 + vertex -899.686 302.646 30.8336 + endloop + endfacet + facet normal -0.871067 -0.254394 0.420151 + outer loop + vertex -896.708 297.368 33.8109 + vertex -899.013 305.398 33.8936 + vertex -899.686 302.646 30.8336 + endloop + endfacet + facet normal -0.890318 -0.223577 0.39667 + outer loop + vertex -900.916 306.864 30.4483 + vertex -899.686 302.646 30.8336 + vertex -899.013 305.398 33.8936 + endloop + endfacet + facet normal -0.891442 -0.181655 0.41513 + outer loop + vertex -900.916 306.864 30.4483 + vertex -899.013 305.398 33.8936 + vertex -901.49 310.757 30.9215 + endloop + endfacet + facet normal -0.893342 -0.185853 0.409143 + outer loop + vertex -899.013 305.398 33.8936 + vertex -900.684 313.594 33.968 + vertex -901.49 310.757 30.9215 + endloop + endfacet + facet normal -0.911195 -0.15243 0.382739 + outer loop + vertex -902.372 315.079 30.5408 + vertex -901.49 310.757 30.9215 + vertex -900.684 313.594 33.968 + endloop + endfacet + facet normal -0.909819 -0.11186 0.399646 + outer loop + vertex -902.372 315.079 30.5408 + vertex -900.684 313.594 33.968 + vertex -902.665 319.121 31.0054 + endloop + endfacet + facet normal -0.912434 -0.116786 0.392205 + outer loop + vertex -900.684 313.594 33.968 + vertex -901.736 322.04 34.0364 + vertex -902.665 319.121 31.0054 + endloop + endfacet + facet normal -0.927291 -0.0836722 0.364871 + outer loop + vertex -903.221 323.609 30.6212 + vertex -902.665 319.121 31.0054 + vertex -901.736 322.04 34.0364 + endloop + endfacet + facet normal -0.923676 -0.0466135 0.38033 + outer loop + vertex -903.221 323.609 30.6212 + vertex -901.736 322.04 34.0364 + vertex -903.242 327.766 31.0816 + endloop + endfacet + facet normal -0.92706 -0.0521804 0.371265 + outer loop + vertex -901.736 322.04 34.0364 + vertex -902.198 330.681 34.0982 + vertex -903.242 327.766 31.0816 + endloop + endfacet + facet normal -0.938295 -0.0211651 0.345189 + outer loop + vertex -903.488 332.341 30.6936 + vertex -903.242 327.766 31.0816 + vertex -902.198 330.681 34.0982 + endloop + endfacet + facet normal -0.933407 0.0102874 0.358671 + outer loop + vertex -903.488 332.341 30.6936 + vertex -902.198 330.681 34.0982 + vertex -903.267 336.512 31.148 + endloop + endfacet + facet normal -0.937036 0.00482988 0.3492 + outer loop + vertex -902.198 330.681 34.0982 + vertex -902.133 339.392 34.151 + vertex -903.267 336.512 31.148 + endloop + endfacet + facet normal -0.944791 0.0319607 0.32611 + outer loop + vertex -903.249 341.083 30.7533 + vertex -903.267 336.512 31.148 + vertex -902.133 339.392 34.151 + endloop + endfacet + facet normal -0.939453 0.058623 0.337626 + outer loop + vertex -903.249 341.083 30.7533 + vertex -902.133 339.392 34.151 + vertex -902.825 345.247 31.2077 + endloop + endfacet + facet normal -0.942725 0.0539881 0.329174 + outer loop + vertex -902.133 339.392 34.151 + vertex -901.619 348.109 34.1939 + vertex -902.825 345.247 31.2077 + endloop + endfacet + facet normal -0.947943 0.0773454 0.308903 + outer loop + vertex -902.581 349.82 30.8126 + vertex -902.825 345.247 31.2077 + vertex -901.619 348.109 34.1939 + endloop + endfacet + facet normal -0.942553 0.0998808 0.318775 + outer loop + vertex -902.581 349.82 30.8126 + vertex -901.619 348.109 34.1939 + vertex -901.993 353.98 31.2493 + endloop + endfacet + facet normal -0.945045 0.0965106 0.312371 + outer loop + vertex -901.619 348.109 34.1939 + vertex -900.717 356.847 34.2237 + vertex -901.993 353.98 31.2493 + endloop + endfacet + facet normal -0.948378 0.115739 0.29527 + outer loop + vertex -901.56 358.559 30.8434 + vertex -901.993 353.98 31.2493 + vertex -900.717 356.847 34.2237 + endloop + endfacet + facet normal -0.942718 0.136513 0.304379 + outer loop + vertex -901.56 358.559 30.8434 + vertex -900.717 356.847 34.2237 + vertex -900.808 362.779 31.2789 + endloop + endfacet + facet normal -0.944964 0.13363 0.298641 + outer loop + vertex -900.717 356.847 34.2237 + vertex -899.444 365.751 34.2654 + vertex -900.808 362.779 31.2789 + endloop + endfacet + facet normal -0.947339 0.151092 0.282349 + outer loop + vertex -900.161 367.517 30.9149 + vertex -900.808 362.779 31.2789 + vertex -899.444 365.751 34.2654 + endloop + endfacet + facet normal -0.942206 0.167734 0.290021 + outer loop + vertex -900.161 367.517 30.9149 + vertex -899.444 365.751 34.2654 + vertex -899.214 371.918 31.4457 + endloop + endfacet + facet normal -0.945252 0.164192 0.282028 + outer loop + vertex -899.444 365.751 34.2654 + vertex -897.862 374.899 34.2433 + vertex -899.214 371.918 31.4457 + endloop + endfacet + facet normal -0.946793 0.177802 0.26827 + outer loop + vertex -898.454 376.266 31.2474 + vertex -899.214 371.918 31.4457 + vertex -897.862 374.899 34.2433 + endloop + endfacet + facet normal -0.945504 0.182058 0.269957 + outer loop + vertex -897.862 374.899 34.2433 + vertex -897.624 382.075 30.2367 + vertex -898.454 376.266 31.2474 + endloop + endfacet + facet normal -0.941651 0.187337 0.27964 + outer loop + vertex -895.952 383.933 34.6233 + vertex -897.624 382.075 30.2367 + vertex -897.862 374.899 34.2433 + endloop + endfacet + facet normal -0.952999 0.191628 0.234672 + outer loop + vertex -896.437 376.206 38.9643 + vertex -895.952 383.933 34.6233 + vertex -897.862 374.899 34.2433 + endloop + endfacet + facet normal -0.955776 0.166391 0.2425 + outer loop + vertex -896.437 376.206 38.9643 + vertex -897.862 374.899 34.2433 + vertex -898.004 367.323 38.8833 + endloop + endfacet + facet normal -0.961819 0.167696 0.216293 + outer loop + vertex -896.897 368.313 43.0373 + vertex -896.437 376.206 38.9643 + vertex -898.004 367.323 38.8833 + endloop + endfacet + facet normal -0.964826 0.136891 0.224435 + outer loop + vertex -896.897 368.313 43.0373 + vertex -898.004 367.323 38.8833 + vertex -898.132 359.622 43.0284 + endloop + endfacet + facet normal -0.969607 0.137593 0.202314 + outer loop + vertex -897.3 360.598 46.3503 + vertex -896.897 368.313 43.0373 + vertex -898.132 359.622 43.0284 + endloop + endfacet + facet normal -0.971654 0.101931 0.213306 + outer loop + vertex -897.3 360.598 46.3503 + vertex -898.132 359.622 43.0284 + vertex -898.204 351.999 46.3424 + endloop + endfacet + facet normal -0.979225 0.102763 0.174806 + outer loop + vertex -897.648 353.386 48.6428 + vertex -897.3 360.598 46.3503 + vertex -898.204 351.999 46.3424 + endloop + endfacet + facet normal -0.978233 0.0659396 0.196756 + outer loop + vertex -897.648 353.386 48.6428 + vertex -898.204 351.999 46.3424 + vertex -898.219 344.92 48.6404 + endloop + endfacet + facet normal -0.982805 0.0588884 0.175003 + outer loop + vertex -898.219 344.92 48.6404 + vertex -898.204 351.999 46.3424 + vertex -898.721 343.402 46.3326 + endloop + endfacet + facet normal -0.9793 0.0171669 0.201684 + outer loop + vertex -898.219 344.92 48.6404 + vertex -898.721 343.402 46.3326 + vertex -898.355 335.936 48.7441 + endloop + endfacet + facet normal -0.983529 0.0101066 0.180469 + outer loop + vertex -898.355 335.936 48.7441 + vertex -898.721 343.402 46.3326 + vertex -898.813 334.825 46.3106 + endloop + endfacet + facet normal -0.9719 0.00984159 0.235189 + outer loop + vertex -898.721 343.402 46.3326 + vertex -899.539 342.391 42.9925 + vertex -898.813 334.825 46.3106 + endloop + endfacet + facet normal -0.972737 0.00825952 0.231764 + outer loop + vertex -898.813 334.825 46.3106 + vertex -899.539 342.391 42.9925 + vertex -899.619 333.834 42.963 + endloop + endfacet + facet normal -0.965188 0.00808662 0.261433 + outer loop + vertex -899.539 342.391 42.9925 + vertex -900.684 341.138 38.8065 + vertex -899.619 333.834 42.963 + endloop + endfacet + facet normal -0.965552 0.00727884 0.260107 + outer loop + vertex -899.619 333.834 42.963 + vertex -900.684 341.138 38.8065 + vertex -900.758 332.501 38.7711 + endloop + endfacet + facet normal -0.95553 0.00705001 0.294809 + outer loop + vertex -900.684 341.138 38.8065 + vertex -902.133 339.392 34.151 + vertex -900.758 332.501 38.7711 + endloop + endfacet + facet normal -0.956268 0.00531649 0.292443 + outer loop + vertex -900.758 332.501 38.7711 + vertex -902.133 339.392 34.151 + vertex -902.198 330.681 34.0982 + endloop + endfacet + facet normal -0.973096 0.05825 0.222917 + outer loop + vertex -898.204 351.999 46.3424 + vertex -899.028 350.989 43.0101 + vertex -898.721 343.402 46.3326 + endloop + endfacet + facet normal -0.973538 0.0574713 0.22118 + outer loop + vertex -898.721 343.402 46.3326 + vertex -899.028 350.989 43.0101 + vertex -899.539 342.391 42.9925 + endloop + endfacet + facet normal -0.967124 0.0570352 0.247826 + outer loop + vertex -899.028 350.989 43.0101 + vertex -900.169 349.793 38.8335 + vertex -899.539 342.391 42.9925 + endloop + endfacet + facet normal -0.967243 0.0567958 0.247418 + outer loop + vertex -899.539 342.391 42.9925 + vertex -900.169 349.793 38.8335 + vertex -900.684 341.138 38.8065 + endloop + endfacet + facet normal -0.958582 0.0561809 0.27922 + outer loop + vertex -900.169 349.793 38.8335 + vertex -901.619 348.109 34.1939 + vertex -900.684 341.138 38.8065 + endloop + endfacet + facet normal -0.959041 0.0552028 0.277835 + outer loop + vertex -900.684 341.138 38.8065 + vertex -901.619 348.109 34.1939 + vertex -902.133 339.392 34.151 + endloop + endfacet + facet normal -0.959447 0.098162 0.264247 + outer loop + vertex -900.169 349.793 38.8335 + vertex -900.717 356.847 34.2237 + vertex -901.619 348.109 34.1939 + endloop + endfacet + facet normal -0.959033 0.0989763 0.265443 + outer loop + vertex -899.263 358.502 38.8596 + vertex -900.717 356.847 34.2237 + vertex -900.169 349.793 38.8335 + endloop + endfacet + facet normal -0.95815 0.135732 0.252041 + outer loop + vertex -899.263 358.502 38.8596 + vertex -899.444 365.751 34.2654 + vertex -900.717 356.847 34.2237 + endloop + endfacet + facet normal -0.957965 0.136068 0.252564 + outer loop + vertex -898.004 367.323 38.8833 + vertex -899.444 365.751 34.2654 + vertex -899.263 358.502 38.8596 + endloop + endfacet + facet normal -0.966739 0.0998678 0.235463 + outer loop + vertex -899.028 350.989 43.0101 + vertex -899.263 358.502 38.8596 + vertex -900.169 349.793 38.8335 + endloop + endfacet + facet normal -0.966757 0.0998347 0.235404 + outer loop + vertex -898.132 359.622 43.0284 + vertex -899.263 358.502 38.8596 + vertex -899.028 350.989 43.0101 + endloop + endfacet + facet normal -0.976361 0.106794 0.187922 + outer loop + vertex -896.671 362.095 48.7676 + vertex -897.3 360.598 46.3503 + vertex -897.648 353.386 48.6428 + endloop + endfacet + facet normal -0.975977 0.138503 0.168181 + outer loop + vertex -896.671 362.095 48.7676 + vertex -896.07 369.273 46.3483 + vertex -897.3 360.598 46.3503 + endloop + endfacet + facet normal -0.972742 0.143059 0.182503 + outer loop + vertex -895.375 371.065 48.6447 + vertex -896.07 369.273 46.3483 + vertex -896.671 362.095 48.7676 + endloop + endfacet + facet normal -0.972209 0.168701 0.162323 + outer loop + vertex -895.375 371.065 48.6447 + vertex -894.584 377.844 46.3376 + vertex -896.07 369.273 46.3483 + endloop + endfacet + facet normal -0.966668 0.16778 0.193397 + outer loop + vertex -894.584 377.844 46.3376 + vertex -895.384 377.007 43.067 + vertex -896.07 369.273 46.3483 + endloop + endfacet + facet normal -0.96679 0.167599 0.192946 + outer loop + vertex -896.07 369.273 46.3483 + vertex -895.384 377.007 43.067 + vertex -896.897 368.313 43.0373 + endloop + endfacet + facet normal -0.963241 0.193967 0.185859 + outer loop + vertex -894.584 377.844 46.3376 + vertex -893.649 385.616 43.0754 + vertex -895.384 377.007 43.067 + endloop + endfacet + facet normal -0.959046 0.193101 0.207224 + outer loop + vertex -893.649 385.616 43.0754 + vertex -894.634 385.025 39.0644 + vertex -895.384 377.007 43.067 + endloop + endfacet + facet normal -0.95873 0.193578 0.20824 + outer loop + vertex -895.384 377.007 43.067 + vertex -894.634 385.025 39.0644 + vertex -896.437 376.206 38.9643 + endloop + endfacet + facet normal -0.955091 0.215958 0.202888 + outer loop + vertex -893.649 385.616 43.0754 + vertex -892.66 393.727 39.0971 + vertex -894.634 385.025 39.0644 + endloop + endfacet + facet normal -0.949343 0.214554 0.229596 + outer loop + vertex -892.66 393.727 39.0971 + vertex -893.901 392.895 34.7421 + vertex -894.634 385.025 39.0644 + endloop + endfacet + facet normal -0.949545 0.214263 0.229032 + outer loop + vertex -894.634 385.025 39.0644 + vertex -893.901 392.895 34.7421 + vertex -895.952 383.933 34.6233 + endloop + endfacet + facet normal -0.93906 0.211305 0.271139 + outer loop + vertex -893.901 392.895 34.7421 + vertex -895.476 391.504 30.3727 + vertex -895.952 383.933 34.6233 + endloop + endfacet + facet normal -0.936478 0.230949 0.263952 + outer loop + vertex -893.901 392.895 34.7421 + vertex -893.258 400.438 30.4217 + vertex -895.476 391.504 30.3727 + endloop + endfacet + facet normal -0.936014 0.23155 0.265072 + outer loop + vertex -891.734 401.63 34.7647 + vertex -893.258 400.438 30.4217 + vertex -893.901 392.895 34.7421 + endloop + endfacet + facet normal -0.933308 0.248108 0.259575 + outer loop + vertex -891.734 401.63 34.7647 + vertex -890.924 409.213 30.4261 + vertex -893.258 400.438 30.4217 + endloop + endfacet + facet normal -0.933235 0.248199 0.259748 + outer loop + vertex -889.446 410.235 34.762 + vertex -890.924 409.213 30.4261 + vertex -891.734 401.63 34.7647 + endloop + endfacet + facet normal -0.942401 0.250624 0.221513 + outer loop + vertex -890.537 402.301 39.0948 + vertex -889.446 410.235 34.762 + vertex -891.734 401.63 34.7647 + endloop + endfacet + facet normal -0.945803 0.234161 0.225002 + outer loop + vertex -890.537 402.301 39.0948 + vertex -891.734 401.63 34.7647 + vertex -892.66 393.727 39.0971 + endloop + endfacet + facet normal -0.951243 0.235501 0.199188 + outer loop + vertex -891.724 394.139 43.0793 + vertex -890.537 402.301 39.0948 + vertex -892.66 393.727 39.0971 + endloop + endfacet + facet normal -0.951422 0.235253 0.198627 + outer loop + vertex -889.631 402.614 43.0652 + vertex -890.537 402.301 39.0948 + vertex -891.724 394.139 43.0793 + endloop + endfacet + facet normal -0.954837 0.236066 0.180442 + outer loop + vertex -890.987 394.61 46.3589 + vertex -889.631 402.614 43.0652 + vertex -891.724 394.139 43.0793 + endloop + endfacet + facet normal -0.95863 0.217189 0.184006 + outer loop + vertex -890.987 394.61 46.3589 + vertex -891.724 394.139 43.0793 + vertex -892.886 386.243 46.3451 + endloop + endfacet + facet normal -0.962545 0.218115 0.16104 + outer loop + vertex -892.239 387.343 48.7207 + vertex -890.987 394.61 46.3589 + vertex -892.886 386.243 46.3451 + endloop + endfacet + facet normal -0.965101 0.198495 0.170821 + outer loop + vertex -892.239 387.343 48.7207 + vertex -892.886 386.243 46.3451 + vertex -893.898 379.323 48.6698 + endloop + endfacet + facet normal -0.967434 0.195474 0.160813 + outer loop + vertex -893.898 379.323 48.6698 + vertex -892.886 386.243 46.3451 + vertex -894.584 377.844 46.3376 + endloop + endfacet + facet normal -0.961051 0.219918 0.167382 + outer loop + vertex -890.379 395.385 48.8349 + vertex -890.987 394.61 46.3589 + vertex -892.239 387.343 48.7207 + endloop + endfacet + facet normal -0.958033 0.236966 0.161308 + outer loop + vertex -890.379 395.385 48.8349 + vertex -888.906 403.038 46.3426 + vertex -890.987 394.61 46.3589 + endloop + endfacet + facet normal -0.956666 0.238551 0.166981 + outer loop + vertex -888.225 404.149 48.6528 + vertex -888.906 403.038 46.3426 + vertex -890.379 395.385 48.8349 + endloop + endfacet + facet normal -0.962774 0.239198 0.125899 + outer loop + vertex -888.225 404.149 48.6528 + vertex -890.379 395.385 48.8349 + vertex -889.405 398.882 49.639 + endloop + endfacet + facet normal -0.961717 0.235711 0.139788 + outer loop + vertex -890.314 395.126 49.7174 + vertex -889.405 398.882 49.639 + vertex -890.379 395.385 48.8349 + endloop + endfacet + facet normal -0.965371 0.222518 0.136182 + outer loop + vertex -890.998 392.102 49.8104 + vertex -890.314 395.126 49.7174 + vertex -890.379 395.385 48.8349 + endloop + endfacet + facet normal -0.965767 0.222002 0.134195 + outer loop + vertex -891.658 389.345 49.6189 + vertex -890.998 392.102 49.8104 + vertex -890.379 395.385 48.8349 + endloop + endfacet + facet normal -0.966332 0.221661 0.130649 + outer loop + vertex -890.379 395.385 48.8349 + vertex -892.239 387.343 48.7207 + vertex -891.658 389.345 49.6189 + endloop + endfacet + facet normal -0.950492 0.221661 0.217788 + outer loop + vertex -890.314 395.126 49.7174 + vertex -890.998 392.102 49.8104 + vertex -890.32 394.556 50.2727 + endloop + endfacet + facet normal -0.954202 0.253312 0.159157 + outer loop + vertex -888.225 404.149 48.6528 + vertex -886.714 411.312 46.3152 + vertex -888.906 403.038 46.3426 + endloop + endfacet + facet normal -0.951003 0.252528 0.178392 + outer loop + vertex -886.714 411.312 46.3152 + vertex -887.41 410.988 43.0616 + vertex -888.906 403.038 46.3426 + endloop + endfacet + facet normal -0.951143 0.25235 0.177896 + outer loop + vertex -888.906 403.038 46.3426 + vertex -887.41 410.988 43.0616 + vertex -889.631 402.614 43.0652 + endloop + endfacet + facet normal -0.947907 0.251499 0.195499 + outer loop + vertex -887.41 410.988 43.0616 + vertex -888.288 410.768 39.0852 + vertex -889.631 402.614 43.0652 + endloop + endfacet + facet normal -0.944497 0.265128 0.193992 + outer loop + vertex -887.41 410.988 43.0616 + vertex -885.942 419.126 39.0886 + vertex -888.288 410.768 39.0852 + endloop + endfacet + facet normal -0.939433 0.263696 0.218928 + outer loop + vertex -885.942 419.126 39.0886 + vertex -887.062 418.729 34.7602 + vertex -888.288 410.768 39.0852 + endloop + endfacet + facet normal -0.939419 0.263715 0.218966 + outer loop + vertex -888.288 410.768 39.0852 + vertex -887.062 418.729 34.7602 + vertex -889.446 410.235 34.762 + endloop + endfacet + facet normal -0.93059 0.261245 0.256425 + outer loop + vertex -887.062 418.729 34.7602 + vertex -888.49 417.893 30.4288 + vertex -889.446 410.235 34.762 + endloop + endfacet + facet normal -0.928494 0.271042 0.253842 + outer loop + vertex -887.062 418.729 34.7602 + vertex -885.997 426.434 30.4275 + vertex -888.49 417.893 30.4288 + endloop + endfacet + facet normal -0.928673 0.270827 0.253415 + outer loop + vertex -884.611 427.13 34.7642 + vertex -885.997 426.434 30.4275 + vertex -887.062 418.729 34.7602 + endloop + endfacet + facet normal -0.927235 0.277042 0.251958 + outer loop + vertex -884.611 427.13 34.7642 + vertex -883.451 434.951 30.4322 + vertex -885.997 426.434 30.4275 + endloop + endfacet + facet normal -0.927293 0.276973 0.251819 + outer loop + vertex -882.116 435.475 34.7717 + vertex -883.451 434.951 30.4322 + vertex -884.611 427.13 34.7642 + endloop + endfacet + facet normal -0.935304 0.279399 0.217123 + outer loop + vertex -883.535 427.366 39.0956 + vertex -882.116 435.475 34.7717 + vertex -884.611 427.13 34.7642 + endloop + endfacet + facet normal -0.936885 0.273481 0.21784 + outer loop + vertex -883.535 427.366 39.0956 + vertex -884.611 427.13 34.7642 + vertex -885.942 419.126 39.0886 + endloop + endfacet + facet normal -0.941832 0.274947 0.193278 + outer loop + vertex -885.106 419.195 43.0625 + vertex -883.535 427.366 39.0956 + vertex -885.942 419.126 39.0886 + endloop + endfacet + facet normal -0.941552 0.275307 0.19413 + outer loop + vertex -882.743 427.261 43.0835 + vertex -883.535 427.366 39.0956 + vertex -885.106 419.195 43.0625 + endloop + endfacet + facet normal -0.944648 0.276258 0.17698 + outer loop + vertex -884.458 419.308 46.3471 + vertex -882.743 427.261 43.0835 + vertex -885.106 419.195 43.0625 + endloop + endfacet + facet normal -0.947269 0.266566 0.177832 + outer loop + vertex -884.458 419.308 46.3471 + vertex -885.106 419.195 43.0625 + vertex -886.714 411.312 46.3152 + endloop + endfacet + facet normal -0.94999 0.2674 0.161293 + outer loop + vertex -886.111 412.044 48.6485 + vertex -884.458 419.308 46.3471 + vertex -886.714 411.312 46.3152 + endloop + endfacet + facet normal -0.948552 0.26892 0.167125 + outer loop + vertex -883.863 419.875 48.811 + vertex -884.458 419.308 46.3471 + vertex -886.111 412.044 48.6485 + endloop + endfacet + facet normal -0.951508 0.270185 0.14708 + outer loop + vertex -883.863 419.875 48.811 + vertex -886.111 412.044 48.6485 + vertex -885.384 414.068 49.6381 + endloop + endfacet + facet normal -0.953482 0.269102 0.13585 + outer loop + vertex -885.384 414.068 49.6381 + vertex -884.434 417.403 49.6954 + vertex -883.863 419.875 48.811 + endloop + endfacet + facet normal -0.948042 0.275912 0.158398 + outer loop + vertex -884.434 417.403 49.6954 + vertex -883.665 420.001 49.777 + vertex -883.863 419.875 48.811 + endloop + endfacet + facet normal -0.947557 0.277765 0.158057 + outer loop + vertex -883.665 420.001 49.777 + vertex -882.739 423.275 49.5703 + vertex -883.863 419.875 48.811 + endloop + endfacet + facet normal -0.948454 0.28036 0.147764 + outer loop + vertex -881.512 427.898 48.6785 + vertex -883.863 419.875 48.811 + vertex -882.739 423.275 49.5703 + endloop + endfacet + facet normal -0.946074 0.281985 0.159464 + outer loop + vertex -882.739 423.275 49.5703 + vertex -881.92 425.975 49.6554 + vertex -881.512 427.898 48.6785 + endloop + endfacet + facet normal -0.943485 0.285728 0.167916 + outer loop + vertex -881.92 425.975 49.6554 + vertex -880.769 429.785 49.6439 + vertex -881.512 427.898 48.6785 + endloop + endfacet + facet normal -0.943516 0.286544 0.166346 + outer loop + vertex -879.042 436.044 48.6571 + vertex -881.512 427.898 48.6785 + vertex -880.769 429.785 49.6439 + endloop + endfacet + facet normal -0.942455 0.287049 0.171408 + outer loop + vertex -880.769 429.785 49.6439 + vertex -879.216 434.829 49.7364 + vertex -879.042 436.044 48.6571 + endloop + endfacet + facet normal -0.941516 0.28883 0.173565 + outer loop + vertex -879.216 434.829 49.7364 + vertex -877.931 439.145 49.5218 + vertex -879.042 436.044 48.6571 + endloop + endfacet + facet normal -0.941966 0.290445 0.168352 + outer loop + vertex -876.518 444.236 48.6469 + vertex -879.042 436.044 48.6571 + vertex -877.931 439.145 49.5218 + endloop + endfacet + facet normal -0.940799 0.291048 0.173746 + outer loop + vertex -877.931 439.145 49.5218 + vertex -876.722 442.947 49.7004 + vertex -876.518 444.236 48.6469 + endloop + endfacet + facet normal -0.940021 0.292444 0.175605 + outer loop + vertex -876.722 442.947 49.7004 + vertex -875.478 447.051 49.526 + vertex -876.518 444.236 48.6469 + endloop + endfacet + facet normal -0.940571 0.294889 0.168426 + outer loop + vertex -874.089 451.951 48.7029 + vertex -876.518 444.236 48.6469 + vertex -875.478 447.051 49.526 + endloop + endfacet + facet normal -0.938894 0.295713 0.176161 + outer loop + vertex -875.478 447.051 49.526 + vertex -874.317 450.618 49.7249 + vertex -874.089 451.951 48.7029 + endloop + endfacet + facet normal -0.937343 0.298345 0.179942 + outer loop + vertex -874.317 450.618 49.7249 + vertex -873.072 454.607 49.5932 + vertex -874.089 451.951 48.7029 + endloop + endfacet + facet normal -0.937884 0.301075 0.172415 + outer loop + vertex -871.719 459.284 48.7862 + vertex -874.089 451.951 48.7029 + vertex -873.072 454.607 49.5932 + endloop + endfacet + facet normal -0.933776 0.302992 0.190417 + outer loop + vertex -873.072 454.607 49.5932 + vertex -871.881 458.124 49.8408 + vertex -871.719 459.284 48.7862 + endloop + endfacet + facet normal -0.931905 0.306264 0.194305 + outer loop + vertex -871.881 458.124 49.8408 + vertex -870.605 462.101 49.6921 + vertex -871.719 459.284 48.7862 + endloop + endfacet + facet normal -0.930546 0.301287 0.208109 + outer loop + vertex -869.63 465.819 48.6695 + vertex -871.719 459.284 48.7862 + vertex -870.605 462.101 49.6921 + endloop + endfacet + facet normal -0.924831 0.305048 0.227231 + outer loop + vertex -870.605 462.101 49.6921 + vertex -869.141 466.482 49.7681 + vertex -869.63 465.819 48.6695 + endloop + endfacet + facet normal -0.928609 0.278958 0.244678 + outer loop + vertex -868.084 470.926 48.7113 + vertex -869.63 465.819 48.6695 + vertex -869.141 466.482 49.7681 + endloop + endfacet + facet normal -0.892062 0.293752 0.343416 + outer loop + vertex -869.141 466.482 49.7681 + vertex -868.011 470.005 49.69 + vertex -868.084 470.926 48.7113 + endloop + endfacet + facet normal -0.936378 0.217815 0.275231 + outer loop + vertex -868.011 470.005 49.69 + vertex -867.235 473.825 49.3053 + vertex -868.084 470.926 48.7113 + endloop + endfacet + facet normal -0.903291 0.185224 0.386986 + outer loop + vertex -867.235 473.825 49.3053 + vertex -867.255 478.642 46.9553 + vertex -868.084 470.926 48.7113 + endloop + endfacet + facet normal -0.96392 0.153213 0.217679 + outer loop + vertex -868.42 471.982 46.4827 + vertex -868.084 470.926 48.7113 + vertex -867.255 478.642 46.9553 + endloop + endfacet + facet normal -0.967813 0.155287 0.198053 + outer loop + vertex -867.255 478.642 46.9553 + vertex -867.823 480.089 43.0417 + vertex -868.42 471.982 46.4827 + endloop + endfacet + facet normal -0.966563 0.157141 0.20264 + outer loop + vertex -868.42 471.982 46.4827 + vertex -867.823 480.089 43.0417 + vertex -868.971 472.872 43.1625 + endloop + endfacet + facet normal -0.937771 0.263364 0.226328 + outer loop + vertex -868.42 471.982 46.4827 + vertex -868.971 472.872 43.1625 + vertex -870.264 465.393 46.5078 + endloop + endfacet + facet normal -0.938394 0.263528 0.223538 + outer loop + vertex -869.63 465.819 48.6695 + vertex -868.42 471.982 46.4827 + vertex -870.264 465.393 46.5078 + endloop + endfacet + facet normal -0.942451 0.258037 0.212612 + outer loop + vertex -870.264 465.393 46.5078 + vertex -868.971 472.872 43.1625 + vertex -870.911 465.773 43.1774 + endloop + endfacet + facet normal -0.931091 0.294973 0.214618 + outer loop + vertex -870.264 465.393 46.5078 + vertex -870.911 465.773 43.1774 + vertex -872.496 458.397 46.4418 + endloop + endfacet + facet normal -0.934496 0.296222 0.197407 + outer loop + vertex -871.719 459.284 48.7862 + vertex -870.264 465.393 46.5078 + vertex -872.496 458.397 46.4418 + endloop + endfacet + facet normal -0.935652 0.28999 0.201147 + outer loop + vertex -872.496 458.397 46.4418 + vertex -870.911 465.773 43.1774 + vertex -873.176 458.526 43.091 + endloop + endfacet + facet normal -0.934098 0.29504 0.201025 + outer loop + vertex -872.496 458.397 46.4418 + vertex -873.176 458.526 43.091 + vertex -874.856 450.987 46.3524 + endloop + endfacet + facet normal -0.937178 0.296223 0.184253 + outer loop + vertex -874.089 451.951 48.7029 + vertex -872.496 458.397 46.4418 + vertex -874.856 450.987 46.3524 + endloop + endfacet + facet normal -0.937262 0.291504 0.191222 + outer loop + vertex -874.856 450.987 46.3524 + vertex -873.176 458.526 43.091 + vertex -875.527 450.984 43.0666 + endloop + endfacet + facet normal -0.937324 0.291293 0.191235 + outer loop + vertex -874.856 450.987 46.3524 + vertex -875.527 450.984 43.0666 + vertex -877.275 443.207 46.3423 + endloop + endfacet + facet normal -0.939592 0.292015 0.178589 + outer loop + vertex -876.518 444.236 48.6469 + vertex -874.856 450.987 46.3524 + vertex -877.275 443.207 46.3423 + endloop + endfacet + facet normal -0.9391 0.289277 0.1855 + outer loop + vertex -877.275 443.207 46.3423 + vertex -875.527 450.984 43.0666 + vertex -877.924 443.199 43.0727 + endloop + endfacet + facet normal -0.939465 0.28804 0.185576 + outer loop + vertex -877.275 443.207 46.3423 + vertex -877.924 443.199 43.0727 + vertex -879.718 435.24 46.344 + endloop + endfacet + facet normal -0.941348 0.288615 0.174828 + outer loop + vertex -879.042 436.044 48.6571 + vertex -877.275 443.207 46.3423 + vertex -879.718 435.24 46.344 + endloop + endfacet + facet normal -0.940612 0.28673 0.181758 + outer loop + vertex -879.718 435.24 46.344 + vertex -877.924 443.199 43.0727 + vertex -880.34 435.263 43.0868 + endloop + endfacet + facet normal -0.941447 0.283886 0.181897 + outer loop + vertex -879.718 435.24 46.344 + vertex -880.34 435.263 43.0868 + vertex -882.123 427.253 46.362 + endloop + endfacet + facet normal -0.943555 0.284493 0.169613 + outer loop + vertex -881.512 427.898 48.6785 + vertex -879.718 435.24 46.344 + vertex -882.123 427.253 46.362 + endloop + endfacet + facet normal -0.94229 0.282904 0.179037 + outer loop + vertex -882.123 427.253 46.362 + vertex -880.34 435.263 43.0868 + vertex -882.743 427.261 43.0835 + endloop + endfacet + facet normal -0.939316 0.282004 0.195346 + outer loop + vertex -880.34 435.263 43.0868 + vertex -881.091 435.52 39.1074 + vertex -882.743 427.261 43.0835 + endloop + endfacet + facet normal -0.938468 0.284799 0.195366 + outer loop + vertex -880.34 435.263 43.0868 + vertex -878.648 443.575 39.0983 + vertex -881.091 435.52 39.1074 + endloop + endfacet + facet normal -0.933569 0.283341 0.219469 + outer loop + vertex -878.648 443.575 39.0983 + vertex -879.612 443.751 34.7718 + vertex -881.091 435.52 39.1074 + endloop + endfacet + facet normal -0.93411 0.282675 0.218021 + outer loop + vertex -881.091 435.52 39.1074 + vertex -879.612 443.751 34.7718 + vertex -882.116 435.475 34.7717 + endloop + endfacet + facet normal -0.926312 0.280315 0.251733 + outer loop + vertex -879.612 443.751 34.7718 + vertex -880.869 443.488 30.4363 + vertex -882.116 435.475 34.7717 + endloop + endfacet + facet normal -0.926219 0.280663 0.251685 + outer loop + vertex -879.612 443.751 34.7718 + vertex -878.317 451.919 30.4287 + vertex -880.869 443.488 30.4363 + endloop + endfacet + facet normal -0.925675 0.281276 0.253 + outer loop + vertex -877.137 451.921 34.7435 + vertex -878.317 451.919 30.4287 + vertex -879.612 443.751 34.7718 + endloop + endfacet + facet normal -0.925986 0.280176 0.253085 + outer loop + vertex -877.137 451.921 34.7435 + vertex -875.792 460.294 30.3954 + vertex -878.317 451.919 30.4287 + endloop + endfacet + facet normal -0.92507 0.281182 0.255306 + outer loop + vertex -874.693 460.019 34.6805 + vertex -875.792 460.294 30.3954 + vertex -877.137 451.921 34.7435 + endloop + endfacet + facet normal -0.93287 0.283281 0.222497 + outer loop + vertex -876.232 451.509 39.0619 + vertex -874.693 460.019 34.6805 + vertex -877.137 451.921 34.7435 + endloop + endfacet + facet normal -0.932355 0.284932 0.222547 + outer loop + vertex -876.232 451.509 39.0619 + vertex -877.137 451.921 34.7435 + vertex -878.648 443.575 39.0983 + endloop + endfacet + facet normal -0.937452 0.286371 0.197929 + outer loop + vertex -877.924 443.199 43.0727 + vertex -876.232 451.509 39.0619 + vertex -878.648 443.575 39.0983 + endloop + endfacet + facet normal -0.930909 0.285599 0.227689 + outer loop + vertex -873.858 459.267 39.0374 + vertex -874.693 460.019 34.6805 + vertex -876.232 451.509 39.0619 + endloop + endfacet + facet normal -0.936237 0.28715 0.202497 + outer loop + vertex -875.527 450.984 43.0666 + vertex -873.858 459.267 39.0374 + vertex -876.232 451.509 39.0619 + endloop + endfacet + facet normal -0.933455 0.27786 0.22684 + outer loop + vertex -873.858 459.267 39.0374 + vertex -872.315 467.981 34.7108 + vertex -874.693 460.019 34.6805 + endloop + endfacet + facet normal -0.926293 0.275607 0.256946 + outer loop + vertex -872.315 467.981 34.7108 + vertex -873.282 468.855 30.2869 + vertex -874.693 460.019 34.6805 + endloop + endfacet + facet normal -0.93579 0.245469 0.253066 + outer loop + vertex -872.315 467.981 34.7108 + vertex -870.966 477.251 30.7068 + vertex -873.282 468.855 30.2869 + endloop + endfacet + facet normal -0.934405 0.246875 0.256788 + outer loop + vertex -870.211 475.768 34.8806 + vertex -870.966 477.251 30.7068 + vertex -872.315 467.981 34.7108 + endloop + endfacet + facet normal -0.941265 0.249363 0.227679 + outer loop + vertex -871.571 466.796 39.0864 + vertex -870.211 475.768 34.8806 + vertex -872.315 467.981 34.7108 + endloop + endfacet + facet normal -0.939045 0.25195 0.233915 + outer loop + vertex -869.575 474.183 39.1435 + vertex -870.211 475.768 34.8806 + vertex -871.571 466.796 39.0864 + endloop + endfacet + facet normal -0.943143 0.253201 0.21534 + outer loop + vertex -870.911 465.773 43.1774 + vertex -869.575 474.183 39.1435 + vertex -871.571 466.796 39.0864 + endloop + endfacet + facet normal -0.967026 0.155029 0.202056 + outer loop + vertex -869.575 474.183 39.1435 + vertex -868.956 483.597 34.8806 + vertex -870.211 475.768 34.8806 + endloop + endfacet + facet normal -0.965175 0.154732 0.210938 + outer loop + vertex -868.956 483.597 34.8806 + vertex -869.457 485.556 31.1534 + vertex -870.211 475.768 34.8806 + endloop + endfacet + facet normal -0.966813 0.15536 0.202818 + outer loop + vertex -868.411 481.779 38.8735 + vertex -868.956 483.597 34.8806 + vertex -869.575 474.183 39.1435 + endloop + endfacet + facet normal -0.968211 0.155334 0.196058 + outer loop + vertex -868.971 472.872 43.1625 + vertex -868.411 481.779 38.8735 + vertex -869.575 474.183 39.1435 + endloop + endfacet + facet normal -0.959347 0.161971 0.231126 + outer loop + vertex -870.211 475.768 34.8806 + vertex -869.457 485.556 31.1534 + vertex -870.966 477.251 30.7068 + endloop + endfacet + facet normal -0.930583 0.28114 0.234471 + outer loop + vertex -871.571 466.796 39.0864 + vertex -872.315 467.981 34.7108 + vertex -873.858 459.267 39.0374 + endloop + endfacet + facet normal -0.93605 0.282966 0.209142 + outer loop + vertex -873.176 458.526 43.091 + vertex -871.571 466.796 39.0864 + vertex -873.858 459.267 39.0374 + endloop + endfacet + facet normal -0.926927 0.27493 0.255381 + outer loop + vertex -874.693 460.019 34.6805 + vertex -873.282 468.855 30.2869 + vertex -875.792 460.294 30.3954 + endloop + endfacet + facet normal -0.933512 0.283533 0.219465 + outer loop + vertex -878.648 443.575 39.0983 + vertex -877.137 451.921 34.7435 + vertex -879.612 443.751 34.7718 + endloop + endfacet + facet normal -0.937616 0.285846 0.197909 + outer loop + vertex -877.924 443.199 43.0727 + vertex -878.648 443.575 39.0983 + vertex -880.34 435.263 43.0868 + endloop + endfacet + facet normal -0.935867 0.288295 0.202582 + outer loop + vertex -875.527 450.984 43.0666 + vertex -876.232 451.509 39.0619 + vertex -877.924 443.199 43.0727 + endloop + endfacet + facet normal -0.933594 0.2903 0.210069 + outer loop + vertex -873.176 458.526 43.091 + vertex -873.858 459.267 39.0374 + vertex -875.527 450.984 43.0666 + endloop + endfacet + facet normal -0.931363 0.288398 0.222239 + outer loop + vertex -870.911 465.773 43.1774 + vertex -871.571 466.796 39.0864 + vertex -873.176 458.526 43.091 + endloop + endfacet + facet normal -0.93975 0.257325 0.225063 + outer loop + vertex -868.971 472.872 43.1625 + vertex -869.575 474.183 39.1435 + vertex -870.911 465.773 43.1774 + endloop + endfacet + facet normal -0.967097 0.157183 0.200043 + outer loop + vertex -867.823 480.089 43.0417 + vertex -868.411 481.779 38.8735 + vertex -868.971 472.872 43.1625 + endloop + endfacet + facet normal -0.981394 0.0810342 0.174069 + outer loop + vertex -867.235 473.825 49.3053 + vertex -866.796 477.577 50.0365 + vertex -867.255 478.642 46.9553 + endloop + endfacet + facet normal -0.981326 0.080944 0.174492 + outer loop + vertex -866.796 477.577 50.0365 + vertex -867.235 473.825 49.3053 + vertex -866.766 477.509 50.2382 + endloop + endfacet + facet normal -0.97766 0.189282 -0.0913975 + outer loop + vertex -867.235 473.825 49.3053 + vertex -868.011 470.005 49.69 + vertex -868.227 469.227 50.3841 + endloop + endfacet + facet normal -0.970114 0.168028 -0.17506 + outer loop + vertex -868.227 469.227 50.3841 + vertex -866.766 477.509 50.2382 + vertex -867.235 473.825 49.3053 + endloop + endfacet + facet normal -0.950819 0.306042 0.0477692 + outer loop + vertex -868.011 470.005 49.69 + vertex -869.141 466.482 49.7681 + vertex -868.227 469.227 50.3841 + endloop + endfacet + facet normal -0.922226 0.27682 0.269944 + outer loop + vertex -868.084 470.926 48.7113 + vertex -868.42 471.982 46.4827 + vertex -869.63 465.819 48.6695 + endloop + endfacet + facet normal -0.928607 0.306626 0.208973 + outer loop + vertex -869.141 466.482 49.7681 + vertex -870.605 462.101 49.6921 + vertex -870.691 461.304 50.4765 + endloop + endfacet + facet normal -0.950794 0.296828 0.0887869 + outer loop + vertex -870.691 461.304 50.4765 + vertex -868.227 469.227 50.3841 + vertex -869.141 466.482 49.7681 + endloop + endfacet + facet normal -0.929407 0.301019 0.213519 + outer loop + vertex -869.63 465.819 48.6695 + vertex -870.264 465.393 46.5078 + vertex -871.719 459.284 48.7862 + endloop + endfacet + facet normal -0.929043 0.305864 0.208149 + outer loop + vertex -870.605 462.101 49.6921 + vertex -871.881 458.124 49.8408 + vertex -870.691 461.304 50.4765 + endloop + endfacet + facet normal -0.931167 0.301033 0.205686 + outer loop + vertex -871.881 458.124 49.8408 + vertex -873.072 454.607 49.5932 + vertex -873.226 453.632 50.3262 + endloop + endfacet + facet normal -0.926609 0.301696 0.224446 + outer loop + vertex -873.226 453.632 50.3262 + vertex -870.691 461.304 50.4765 + vertex -871.881 458.124 49.8408 + endloop + endfacet + facet normal -0.932928 0.304413 0.192295 + outer loop + vertex -872.312 455.238 52.2153 + vertex -870.691 461.304 50.4765 + vertex -873.226 453.632 50.3262 + endloop + endfacet + facet normal -0.933631 0.299112 0.197141 + outer loop + vertex -872.312 455.238 52.2153 + vertex -873.226 453.632 50.3262 + vertex -874.526 448.898 51.3499 + endloop + endfacet + facet normal -0.935259 0.301214 0.185904 + outer loop + vertex -872.312 455.238 52.2153 + vertex -874.526 448.898 51.3499 + vertex -874.806 446.187 54.3378 + endloop + endfacet + facet normal -0.937096 0.299983 0.178495 + outer loop + vertex -874.806 446.187 54.3378 + vertex -872.663 452.184 55.5091 + vertex -872.312 455.238 52.2153 + endloop + endfacet + facet normal -0.93326 0.307419 0.185796 + outer loop + vertex -872.663 452.184 55.5091 + vertex -870.619 458.702 54.9918 + vertex -872.312 455.238 52.2153 + endloop + endfacet + facet normal -0.933371 0.30584 0.187833 + outer loop + vertex -869.502 463.936 52.0187 + vertex -872.312 455.238 52.2153 + vertex -870.619 458.702 54.9918 + endloop + endfacet + facet normal -0.938071 0.299279 0.174515 + outer loop + vertex -870.619 458.702 54.9918 + vertex -868.199 466.381 54.827 + vertex -869.502 463.936 52.0187 + endloop + endfacet + facet normal -0.941622 0.268862 0.202637 + outer loop + vertex -867.319 471.716 51.8374 + vertex -869.502 463.936 52.0187 + vertex -868.199 466.381 54.827 + endloop + endfacet + facet normal -0.974983 0.206669 0.0818275 + outer loop + vertex -868.199 466.381 54.827 + vertex -866.166 476.225 54.1891 + vertex -867.319 471.716 51.8374 + endloop + endfacet + facet normal -0.969856 0.146456 0.194757 + outer loop + vertex -866.166 476.225 54.1891 + vertex -866.735 477.441 50.4409 + vertex -867.319 471.716 51.8374 + endloop + endfacet + facet normal -0.969804 0.146505 0.194978 + outer loop + vertex -866.735 477.441 50.4409 + vertex -866.766 477.509 50.2382 + vertex -867.319 471.716 51.8374 + endloop + endfacet + facet normal -0.940358 0.171044 0.294059 + outer loop + vertex -867.319 471.716 51.8374 + vertex -866.766 477.509 50.2382 + vertex -868.227 469.227 50.3841 + endloop + endfacet + facet normal -0.955182 0.210748 0.207877 + outer loop + vertex -867.049 467.136 59.3486 + vertex -866.166 476.225 54.1891 + vertex -868.199 466.381 54.827 + endloop + endfacet + facet normal -0.936522 0.295305 0.189002 + outer loop + vertex -867.049 467.136 59.3486 + vertex -868.199 466.381 54.827 + vertex -869.367 459.78 59.3534 + endloop + endfacet + facet normal -0.936112 0.295177 0.191222 + outer loop + vertex -868.273 459.463 65.1986 + vertex -867.049 467.136 59.3486 + vertex -869.367 459.78 59.3534 + endloop + endfacet + facet normal -0.927614 0.320998 0.191029 + outer loop + vertex -868.273 459.463 65.1986 + vertex -869.367 459.78 59.3534 + vertex -870.585 452.736 65.2763 + endloop + endfacet + facet normal -0.930002 0.321666 0.177843 + outer loop + vertex -869.571 451.948 72.0018 + vertex -868.273 459.463 65.1986 + vertex -870.585 452.736 65.2763 + endloop + endfacet + facet normal -0.932038 0.315924 0.177477 + outer loop + vertex -869.571 451.948 72.0018 + vertex -870.585 452.736 65.2763 + vertex -871.807 445.322 72.0554 + endloop + endfacet + facet normal -0.934317 0.316582 0.163792 + outer loop + vertex -870.834 444.524 79.1524 + vertex -869.571 451.948 72.0018 + vertex -871.807 445.322 72.0554 + endloop + endfacet + facet normal -0.937613 0.307015 0.163167 + outer loop + vertex -870.834 444.524 79.1524 + vertex -871.807 445.322 72.0554 + vertex -873.013 437.871 79.1478 + endloop + endfacet + facet normal -0.939502 0.307642 0.150641 + outer loop + vertex -872.04 437.307 86.3678 + vertex -870.834 444.524 79.1524 + vertex -873.013 437.871 79.1478 + endloop + endfacet + facet normal -0.942282 0.299164 0.150354 + outer loop + vertex -872.04 437.307 86.3678 + vertex -873.013 437.871 79.1478 + vertex -874.166 430.626 86.3371 + endloop + endfacet + facet normal -0.943799 0.299697 0.139376 + outer loop + vertex -873.177 430.326 93.6738 + vertex -872.04 437.307 86.3678 + vertex -874.166 430.626 86.3371 + endloop + endfacet + facet normal -0.946439 0.291247 0.139387 + outer loop + vertex -873.177 430.326 93.6738 + vertex -874.166 430.626 86.3371 + vertex -875.233 423.658 93.6483 + endloop + endfacet + facet normal -0.947762 0.291694 0.129082 + outer loop + vertex -874.248 423.542 101.141 + vertex -873.177 430.326 93.6738 + vertex -875.233 423.658 93.6483 + endloop + endfacet + facet normal -0.950858 0.281323 0.129328 + outer loop + vertex -874.248 423.542 101.141 + vertex -875.233 423.658 93.6483 + vertex -876.203 416.94 101.132 + endloop + endfacet + facet normal -0.952146 0.281719 0.118541 + outer loop + vertex -875.258 416.92 108.771 + vertex -874.248 423.542 101.141 + vertex -876.203 416.94 101.132 + endloop + endfacet + facet normal -0.955939 0.268377 0.118976 + outer loop + vertex -875.258 416.92 108.771 + vertex -876.203 416.94 101.132 + vertex -877.088 410.404 108.768 + endloop + endfacet + facet normal -0.957244 0.268749 0.107041 + outer loop + vertex -876.212 410.441 116.508 + vertex -875.258 416.92 108.771 + vertex -877.088 410.404 108.768 + endloop + endfacet + facet normal -0.961575 0.252572 0.10761 + outer loop + vertex -876.212 410.441 116.508 + vertex -877.088 410.404 108.768 + vertex -877.904 403.997 116.509 + endloop + endfacet + facet normal -0.962882 0.252914 0.0942979 + outer loop + vertex -877.117 404.084 124.315 + vertex -876.212 410.441 116.508 + vertex -877.904 403.997 116.509 + endloop + endfacet + facet normal -0.967347 0.235 0.0949464 + outer loop + vertex -877.117 404.084 124.315 + vertex -877.904 403.997 116.509 + vertex -878.674 397.672 124.317 + endloop + endfacet + facet normal -0.968577 0.235295 0.080594 + outer loop + vertex -877.989 397.801 132.173 + vertex -877.117 404.084 124.315 + vertex -878.674 397.672 124.317 + endloop + endfacet + facet normal -0.972955 0.216218 0.08129 + outer loop + vertex -877.989 397.801 132.173 + vertex -878.674 397.672 124.317 + vertex -879.416 391.38 132.175 + endloop + endfacet + facet normal -0.974041 0.216454 0.0662736 + outer loop + vertex -878.845 391.535 140.063 + vertex -877.989 397.801 132.173 + vertex -879.416 391.38 132.175 + endloop + endfacet + facet normal -0.978356 0.195784 0.0669907 + outer loop + vertex -878.845 391.535 140.063 + vertex -879.416 391.38 132.175 + vertex -880.139 385.068 140.064 + endloop + endfacet + facet normal -0.979262 0.195961 0.0514268 + outer loop + vertex -879.693 385.227 147.95 + vertex -878.845 391.535 140.063 + vertex -880.139 385.068 140.064 + endloop + endfacet + facet normal -0.983564 0.172871 0.0521353 + outer loop + vertex -879.693 385.227 147.95 + vertex -880.139 385.068 140.064 + vertex -880.843 378.683 147.951 + endloop + endfacet + facet normal -0.984263 0.172992 0.0360467 + outer loop + vertex -880.531 378.823 155.804 + vertex -879.693 385.227 147.95 + vertex -880.843 378.683 147.951 + endloop + endfacet + facet normal -0.988407 0.147332 0.0366687 + outer loop + vertex -880.531 378.823 155.804 + vertex -880.843 378.683 147.951 + vertex -881.52 372.187 155.804 + endloop + endfacet + facet normal -0.988877 0.147401 0.0198759 + outer loop + vertex -881.348 372.286 163.624 + vertex -880.531 378.823 155.804 + vertex -881.52 372.187 155.804 + endloop + endfacet + facet normal -0.992691 0.118963 0.0203201 + outer loop + vertex -881.348 372.286 163.624 + vertex -881.52 372.187 155.804 + vertex -882.154 365.564 163.624 + endloop + endfacet + facet normal -0.992892 0.118987 0.00279119 + outer loop + vertex -882.127 365.603 171.447 + vertex -881.348 372.286 163.624 + vertex -882.154 365.564 163.624 + endloop + endfacet + facet normal -0.996215 0.0868697 0.00296491 + outer loop + vertex -882.127 365.603 171.447 + vertex -882.154 365.564 163.624 + vertex -882.718 358.831 171.448 + endloop + endfacet + facet normal -0.996105 0.0868585 -0.0152006 + outer loop + vertex -882.841 358.792 179.323 + vertex -882.127 365.603 171.447 + vertex -882.718 358.831 171.448 + endloop + endfacet + facet normal -0.998633 0.0499386 -0.0154211 + outer loop + vertex -882.841 358.792 179.323 + vertex -882.718 358.831 171.448 + vertex -883.18 352.025 179.324 + endloop + endfacet + facet normal -0.998184 0.0499142 -0.0337163 + outer loop + vertex -883.455 351.887 187.268 + vertex -882.841 358.792 179.323 + vertex -883.18 352.025 179.324 + endloop + endfacet + facet normal -0.999387 0.00574318 -0.0345219 + outer loop + vertex -883.455 351.887 187.268 + vertex -883.18 352.025 179.324 + vertex -883.494 345.152 187.269 + endloop + endfacet + facet normal -0.998567 0.00573452 -0.0532136 + outer loop + vertex -883.921 344.896 195.257 + vertex -883.455 351.887 187.268 + vertex -883.494 345.152 187.269 + endloop + endfacet + facet normal -0.998513 0.00444235 -0.0543413 + outer loop + vertex -883.891 351.654 195.255 + vertex -883.455 351.887 187.268 + vertex -883.921 344.896 195.257 + endloop + endfacet + facet normal -0.997296 0.0044325 -0.0733563 + outer loop + vertex -884.509 344.534 203.235 + vertex -883.891 351.654 195.255 + vertex -883.921 344.896 195.257 + endloop + endfacet + facet normal -0.997196 0.0028312 -0.0747774 + outer loop + vertex -884.49 351.323 203.233 + vertex -883.891 351.654 195.255 + vertex -884.509 344.534 203.235 + endloop + endfacet + facet normal -0.99558 0.00282156 -0.0938726 + outer loop + vertex -885.257 344.064 211.156 + vertex -884.49 351.323 203.233 + vertex -884.509 344.534 203.235 + endloop + endfacet + facet normal -0.995374 0.000395801 -0.0960753 + outer loop + vertex -885.255 350.895 211.155 + vertex -884.49 351.323 203.233 + vertex -885.257 344.064 211.156 + endloop + endfacet + facet normal -0.993312 0.000392268 -0.115462 + outer loop + vertex -886.169 343.49 219 + vertex -885.255 350.895 211.155 + vertex -885.257 344.064 211.156 + endloop + endfacet + facet normal -0.993053 -0.00195865 -0.11765 + outer loop + vertex -886.183 350.371 218.999 + vertex -885.255 350.895 211.155 + vertex -886.169 343.49 219 + endloop + endfacet + facet normal -0.990679 -0.00195726 -0.1362 + outer loop + vertex -887.236 342.815 226.77 + vertex -886.183 350.371 218.999 + vertex -886.169 343.49 219 + endloop + endfacet + facet normal -0.990344 -0.00442923 -0.138558 + outer loop + vertex -887.267 349.752 226.768 + vertex -886.183 350.371 218.999 + vertex -887.236 342.815 226.77 + endloop + endfacet + facet normal -0.987818 -0.00442267 -0.155551 + outer loop + vertex -888.445 342.043 234.468 + vertex -887.267 349.752 226.768 + vertex -887.236 342.815 226.77 + endloop + endfacet + facet normal -0.987321 -0.00750425 -0.158559 + outer loop + vertex -888.498 349.047 234.466 + vertex -887.267 349.752 226.768 + vertex -888.445 342.043 234.468 + endloop + endfacet + facet normal -0.984667 -0.00748767 -0.174286 + outer loop + vertex -889.788 341.194 242.091 + vertex -888.498 349.047 234.466 + vertex -888.445 342.043 234.468 + endloop + endfacet + facet normal -0.984023 -0.0109128 -0.177705 + outer loop + vertex -889.866 348.271 242.091 + vertex -888.498 349.047 234.466 + vertex -889.788 341.194 242.091 + endloop + endfacet + facet normal -0.981188 -0.010882 -0.192746 + outer loop + vertex -891.257 340.291 249.621 + vertex -889.866 348.271 242.091 + vertex -889.788 341.194 242.091 + endloop + endfacet + facet normal -0.980655 -0.0133705 -0.195285 + outer loop + vertex -891.354 347.445 249.619 + vertex -889.866 348.271 242.091 + vertex -891.257 340.291 249.621 + endloop + endfacet + facet normal -0.977682 -0.0133326 -0.209667 + outer loop + vertex -892.833 339.342 257.032 + vertex -891.354 347.445 249.619 + vertex -891.257 340.291 249.621 + endloop + endfacet + facet normal -0.976948 -0.0163767 -0.212849 + outer loop + vertex -892.955 346.581 257.032 + vertex -891.354 347.445 249.619 + vertex -892.833 339.342 257.032 + endloop + endfacet + facet normal -0.973898 -0.0163251 -0.226399 + outer loop + vertex -894.506 338.331 264.3 + vertex -892.955 346.581 257.032 + vertex -892.833 339.342 257.032 + endloop + endfacet + facet normal -0.973313 -0.0184939 -0.228736 + outer loop + vertex -894.645 345.658 264.301 + vertex -892.955 346.581 257.032 + vertex -894.506 338.331 264.3 + endloop + endfacet + facet normal -0.97068 -0.0184431 -0.239668 + outer loop + vertex -896.22 337.222 271.329 + vertex -894.645 345.658 264.301 + vertex -894.506 338.331 264.3 + endloop + endfacet + facet normal -0.970021 -0.0206283 -0.242144 + outer loop + vertex -896.379 344.644 271.331 + vertex -894.645 345.658 264.301 + vertex -896.22 337.222 271.329 + endloop + endfacet + facet normal -0.967926 -0.0205814 -0.250392 + outer loop + vertex -897.891 336.029 277.884 + vertex -896.379 344.644 271.331 + vertex -896.22 337.222 271.329 + endloop + endfacet + facet normal -0.9672 -0.0226933 -0.253001 + outer loop + vertex -898.068 343.546 277.885 + vertex -896.379 344.644 271.331 + vertex -897.891 336.029 277.884 + endloop + endfacet + facet normal -0.964994 -0.0226396 -0.261293 + outer loop + vertex -899.406 334.915 283.578 + vertex -898.068 343.546 277.885 + vertex -897.891 336.029 277.884 + endloop + endfacet + facet normal -0.964202 -0.024566 -0.264027 + outer loop + vertex -899.604 342.5 283.594 + vertex -898.068 343.546 277.885 + vertex -899.406 334.915 283.578 + endloop + endfacet + facet normal -0.959562 -0.024411 -0.280439 + outer loop + vertex -900.705 334.249 288.078 + vertex -899.604 342.5 283.594 + vertex -899.406 334.915 283.578 + endloop + endfacet + facet normal -0.960192 -0.0232064 -0.278377 + outer loop + vertex -900.894 341.811 288.102 + vertex -899.604 342.5 283.594 + vertex -900.705 334.249 288.078 + endloop + endfacet + facet normal -0.949469 -0.0228276 -0.313031 + outer loop + vertex -901.783 334.628 291.322 + vertex -900.894 341.811 288.102 + vertex -900.705 334.249 288.078 + endloop + endfacet + facet normal -0.954237 -0.0157838 -0.298635 + outer loop + vertex -901.905 341.893 291.326 + vertex -900.894 341.811 288.102 + vertex -901.783 334.628 291.322 + endloop + endfacet + facet normal -0.953801 0.0235986 -0.299511 + outer loop + vertex -901.905 341.893 291.326 + vertex -900.702 349.468 288.091 + vertex -900.894 341.811 288.102 + endloop + endfacet + facet normal -0.962434 0.023858 -0.270467 + outer loop + vertex -900.702 349.468 288.091 + vertex -899.422 350.173 283.601 + vertex -900.894 341.811 288.102 + endloop + endfacet + facet normal -0.962381 0.0629204 -0.264318 + outer loop + vertex -900.702 349.468 288.091 + vertex -898.914 357.887 283.585 + vertex -899.422 350.173 283.601 + endloop + endfacet + facet normal -0.965511 0.0631511 -0.252587 + outer loop + vertex -898.914 357.887 283.585 + vertex -897.365 358.796 277.891 + vertex -899.422 350.173 283.601 + endloop + endfacet + facet normal -0.965969 0.0646812 -0.250441 + outer loop + vertex -899.422 350.173 283.601 + vertex -897.365 358.796 277.891 + vertex -897.877 351.151 277.895 + endloop + endfacet + facet normal -0.965984 0.023135 -0.257565 + outer loop + vertex -899.422 350.173 283.601 + vertex -897.877 351.151 277.895 + vertex -899.604 342.5 283.594 + endloop + endfacet + facet normal -0.967723 0.0648023 -0.24354 + outer loop + vertex -897.365 358.796 277.891 + vertex -895.655 359.675 271.332 + vertex -897.877 351.151 277.895 + endloop + endfacet + facet normal -0.968131 0.0665172 -0.241451 + outer loop + vertex -897.877 351.151 277.895 + vertex -895.655 359.675 271.332 + vertex -896.173 352.142 271.333 + endloop + endfacet + facet normal -0.96848 0.0245351 -0.24788 + outer loop + vertex -897.877 351.151 277.895 + vertex -896.173 352.142 271.333 + vertex -898.068 343.546 277.885 + endloop + endfacet + facet normal -0.970022 0.0666487 -0.233698 + outer loop + vertex -895.655 359.675 271.332 + vertex -893.906 360.466 264.297 + vertex -896.173 352.142 271.333 + endloop + endfacet + facet normal -0.97029 0.0679893 -0.232198 + outer loop + vertex -896.173 352.142 271.333 + vertex -893.906 360.466 264.297 + vertex -894.426 353.049 264.299 + endloop + endfacet + facet normal -0.970973 0.0267489 -0.237687 + outer loop + vertex -896.173 352.142 271.333 + vertex -894.426 353.049 264.299 + vertex -896.379 344.644 271.331 + endloop + endfacet + facet normal -0.972861 0.068172 -0.221119 + outer loop + vertex -893.906 360.466 264.297 + vertex -892.203 361.193 257.03 + vertex -894.426 353.049 264.299 + endloop + endfacet + facet normal -0.973071 0.0693965 -0.219811 + outer loop + vertex -894.426 353.049 264.299 + vertex -892.203 361.193 257.03 + vertex -892.725 353.877 257.031 + endloop + endfacet + facet normal -0.974013 0.0288844 -0.224645 + outer loop + vertex -894.426 353.049 264.299 + vertex -892.725 353.877 257.031 + vertex -894.645 345.658 264.301 + endloop + endfacet + facet normal -0.975977 0.0696054 -0.206455 + outer loop + vertex -892.203 361.193 257.03 + vertex -890.586 361.884 249.618 + vertex -892.725 353.877 257.031 + endloop + endfacet + facet normal -0.976228 0.0713221 -0.204674 + outer loop + vertex -892.725 353.877 257.031 + vertex -890.586 361.884 249.618 + vertex -891.114 354.657 249.619 + endloop + endfacet + facet normal -0.97739 0.0307455 -0.209196 + outer loop + vertex -892.725 353.877 257.031 + vertex -891.114 354.657 249.619 + vertex -892.955 346.581 257.032 + endloop + endfacet + facet normal -0.979134 0.0715368 -0.190206 + outer loop + vertex -890.586 361.884 249.618 + vertex -889.075 362.548 242.09 + vertex -891.114 354.657 249.619 + endloop + endfacet + facet normal -0.979368 0.0734468 -0.188268 + outer loop + vertex -891.114 354.657 249.619 + vertex -889.075 362.548 242.09 + vertex -889.611 355.402 242.09 + endloop + endfacet + facet normal -0.980738 0.0326542 -0.192581 + outer loop + vertex -891.114 354.657 249.619 + vertex -889.611 355.402 242.09 + vertex -891.354 347.445 249.619 + endloop + endfacet + facet normal -0.982148 0.0736567 -0.173091 + outer loop + vertex -889.075 362.548 242.09 + vertex -887.684 363.174 234.467 + vertex -889.611 355.402 242.09 + endloop + endfacet + facet normal -0.982351 0.0757247 -0.171034 + outer loop + vertex -889.611 355.402 242.09 + vertex -887.684 363.174 234.467 + vertex -888.229 356.104 234.467 + endloop + endfacet + facet normal -0.98393 0.0352284 -0.175047 + outer loop + vertex -889.611 355.402 242.09 + vertex -888.229 356.104 234.467 + vertex -889.866 348.271 242.091 + endloop + endfacet + facet normal -0.984966 0.0759265 -0.155169 + outer loop + vertex -887.684 363.174 234.467 + vertex -886.428 363.742 226.767 + vertex -888.229 356.104 234.467 + endloop + endfacet + facet normal -0.985105 0.0777899 -0.153353 + outer loop + vertex -888.229 356.104 234.467 + vertex -886.428 363.742 226.767 + vertex -886.981 356.739 226.766 + endloop + endfacet + facet normal -0.986891 0.0375586 -0.15696 + outer loop + vertex -888.229 356.104 234.467 + vertex -886.981 356.739 226.766 + vertex -888.498 349.047 234.466 + endloop + endfacet + facet normal -0.987662 0.0779897 -0.135801 + outer loop + vertex -886.428 363.742 226.767 + vertex -885.32 364.238 218.998 + vertex -886.981 356.739 226.766 + endloop + endfacet + facet normal -0.98777 0.0801424 -0.133746 + outer loop + vertex -886.981 356.739 226.766 + vertex -885.32 364.238 218.998 + vertex -885.883 357.299 218.999 + endloop + endfacet + facet normal -0.989757 0.0405435 -0.136882 + outer loop + vertex -886.981 356.739 226.766 + vertex -885.883 357.299 218.999 + vertex -887.267 349.752 226.768 + endloop + endfacet + facet normal -0.990083 0.0803308 -0.115249 + outer loop + vertex -885.32 364.238 218.998 + vertex -884.373 364.659 211.154 + vertex -885.883 357.299 218.999 + endloop + endfacet + facet normal -0.990124 0.0818878 -0.113796 + outer loop + vertex -885.883 357.299 218.999 + vertex -884.373 364.659 211.154 + vertex -884.943 357.771 211.154 + endloop + endfacet + facet normal -0.992276 0.0428821 -0.116401 + outer loop + vertex -885.883 357.299 218.999 + vertex -884.943 357.771 211.154 + vertex -886.183 350.371 218.999 + endloop + endfacet + facet normal -0.992158 0.0820553 -0.094285 + outer loop + vertex -884.373 364.659 211.154 + vertex -883.592 365.002 203.232 + vertex -884.943 357.771 211.154 + endloop + endfacet + facet normal -0.992162 0.0835064 -0.092961 + outer loop + vertex -884.943 357.771 211.154 + vertex -883.592 365.002 203.232 + vertex -884.168 358.158 203.232 + endloop + endfacet + facet normal -0.99445 0.0450802 -0.0950593 + outer loop + vertex -884.943 357.771 211.154 + vertex -884.168 358.158 203.232 + vertex -885.255 350.895 211.155 + endloop + endfacet + facet normal -0.993785 0.0836438 -0.073456 + outer loop + vertex -883.592 365.002 203.232 + vertex -882.98 365.267 195.254 + vertex -884.168 358.158 203.232 + endloop + endfacet + facet normal -0.993761 0.0848808 -0.07235 + outer loop + vertex -884.168 358.158 203.232 + vertex -882.98 365.267 195.254 + vertex -883.562 358.457 195.255 + endloop + endfacet + facet normal -0.996158 0.0468887 -0.0739594 + outer loop + vertex -884.168 358.158 203.232 + vertex -883.562 358.457 195.255 + vertex -884.49 351.323 203.233 + endloop + endfacet + facet normal -0.994952 0.084984 -0.053367 + outer loop + vertex -882.98 365.267 195.254 + vertex -882.535 365.457 187.267 + vertex -883.562 358.457 195.255 + endloop + endfacet + facet normal -0.994924 0.0857051 -0.0527317 + outer loop + vertex -883.562 358.457 195.255 + vertex -882.535 365.457 187.267 + vertex -883.12 358.668 187.267 + endloop + endfacet + facet normal -0.997384 0.0482258 -0.0538554 + outer loop + vertex -883.562 358.457 195.255 + vertex -883.12 358.668 187.267 + vertex -883.891 351.654 195.255 + endloop + endfacet + facet normal -0.995727 0.0857757 -0.0342033 + outer loop + vertex -882.535 365.457 187.267 + vertex -882.253 365.568 179.322 + vertex -883.12 358.668 187.267 + endloop + endfacet + facet normal -0.995688 0.086465 -0.0336005 + outer loop + vertex -883.12 358.668 187.267 + vertex -882.253 365.568 179.322 + vertex -882.841 358.792 179.323 + endloop + endfacet + facet normal -0.992423 0.118176 -0.0336324 + outer loop + vertex -882.535 365.457 187.267 + vertex -881.453 372.288 179.322 + vertex -882.253 365.568 179.322 + endloop + endfacet + facet normal -0.992863 0.118229 -0.0156725 + outer loop + vertex -881.453 372.288 179.322 + vertex -881.324 372.32 171.447 + vertex -882.253 365.568 179.322 + endloop + endfacet + facet normal -0.992819 0.118644 -0.0153121 + outer loop + vertex -882.253 365.568 179.322 + vertex -881.324 372.32 171.447 + vertex -882.127 365.603 171.447 + endloop + endfacet + facet normal -0.98903 0.146899 -0.0154958 + outer loop + vertex -881.453 372.288 179.322 + vertex -880.342 378.934 171.446 + vertex -881.324 372.32 171.447 + endloop + endfacet + facet normal -0.989146 0.146919 0.00211793 + outer loop + vertex -880.342 378.934 171.446 + vertex -880.363 378.906 163.623 + vertex -881.324 372.32 171.447 + endloop + endfacet + facet normal -0.989102 0.147212 0.00236971 + outer loop + vertex -881.324 372.32 171.447 + vertex -880.363 378.906 163.623 + vertex -881.348 372.286 163.624 + endloop + endfacet + facet normal -0.984978 0.172671 0.00201406 + outer loop + vertex -880.342 378.934 171.446 + vertex -879.223 385.408 163.621 + vertex -880.363 378.906 163.623 + endloop + endfacet + facet normal -0.984799 0.172645 0.0191081 + outer loop + vertex -879.223 385.408 163.621 + vertex -879.387 385.34 155.802 + vertex -880.363 378.906 163.623 + endloop + endfacet + facet normal -0.984749 0.172906 0.0193288 + outer loop + vertex -880.363 378.906 163.623 + vertex -879.387 385.34 155.802 + vertex -880.531 378.823 155.804 + endloop + endfacet + facet normal -0.980477 0.195731 0.0188157 + outer loop + vertex -879.223 385.408 163.621 + vertex -878.108 391.745 155.799 + vertex -879.387 385.34 155.802 + endloop + endfacet + facet normal -0.980041 0.19565 0.0352289 + outer loop + vertex -878.108 391.745 155.799 + vertex -878.408 391.657 147.947 + vertex -879.387 385.34 155.802 + endloop + endfacet + facet normal -0.97999 0.19587 0.0354121 + outer loop + vertex -879.387 385.34 155.802 + vertex -878.408 391.657 147.947 + vertex -879.693 385.227 147.95 + endloop + endfacet + facet normal -0.975686 0.216389 0.034832 + outer loop + vertex -878.108 391.745 155.799 + vertex -877.002 397.996 147.946 + vertex -878.408 391.657 147.947 + endloop + endfacet + facet normal -0.975028 0.216247 0.05057 + outer loop + vertex -877.002 397.996 147.946 + vertex -877.43 397.91 140.06 + vertex -878.408 391.657 147.947 + endloop + endfacet + facet normal -0.974991 0.216385 0.0506847 + outer loop + vertex -878.408 391.657 147.947 + vertex -877.43 397.91 140.06 + vertex -878.845 391.535 140.063 + endloop + endfacet + facet normal -0.970568 0.235554 0.0501178 + outer loop + vertex -877.002 397.996 147.946 + vertex -875.899 404.217 140.065 + vertex -877.43 397.91 140.06 + endloop + endfacet + facet normal -0.969711 0.235336 0.0654047 + outer loop + vertex -875.899 404.217 140.065 + vertex -876.447 404.155 132.173 + vertex -877.43 397.91 140.06 + endloop + endfacet + facet normal -0.969683 0.235428 0.0654815 + outer loop + vertex -877.43 397.91 140.06 + vertex -876.447 404.155 132.173 + vertex -877.989 397.801 132.173 + endloop + endfacet + facet normal -0.965126 0.253603 0.064943 + outer loop + vertex -875.899 404.217 140.065 + vertex -874.786 410.472 132.185 + vertex -876.447 404.155 132.173 + endloop + endfacet + facet normal -0.964078 0.2533 0.0799604 + outer loop + vertex -874.786 410.472 132.185 + vertex -875.442 410.458 124.32 + vertex -876.447 404.155 132.173 + endloop + endfacet + facet normal -0.964087 0.253273 0.0799377 + outer loop + vertex -876.447 404.155 132.173 + vertex -875.442 410.458 124.32 + vertex -877.117 404.084 124.315 + endloop + endfacet + facet normal -0.959587 0.269933 0.0795572 + outer loop + vertex -874.786 410.472 132.185 + vertex -873.651 416.819 124.338 + vertex -875.442 410.458 124.32 + endloop + endfacet + facet normal -0.958385 0.269553 0.0940189 + outer loop + vertex -873.651 416.819 124.338 + vertex -874.403 416.874 116.518 + vertex -875.442 410.458 124.32 + endloop + endfacet + facet normal -0.958455 0.269362 0.0938524 + outer loop + vertex -875.442 410.458 124.32 + vertex -874.403 416.874 116.518 + vertex -876.212 410.441 116.508 + endloop + endfacet + facet normal -0.954416 0.283378 0.093734 + outer loop + vertex -873.651 416.819 124.338 + vertex -872.495 423.293 116.54 + vertex -874.403 416.874 116.518 + endloop + endfacet + facet normal -0.953124 0.282947 0.107218 + outer loop + vertex -872.495 423.293 116.54 + vertex -873.327 423.426 108.789 + vertex -874.403 416.874 116.518 + endloop + endfacet + facet normal -0.953266 0.282589 0.106894 + outer loop + vertex -874.403 416.874 116.518 + vertex -873.327 423.426 108.789 + vertex -875.258 416.92 108.771 + endloop + endfacet + facet normal -0.949855 0.293793 0.107053 + outer loop + vertex -872.495 423.293 116.54 + vertex -871.33 429.877 108.81 + vertex -873.327 423.426 108.789 + endloop + endfacet + facet normal -0.948543 0.293346 0.119226 + outer loop + vertex -871.33 429.877 108.81 + vertex -872.221 430.098 101.172 + vertex -873.327 423.426 108.789 + endloop + endfacet + facet normal -0.948767 0.29282 0.118732 + outer loop + vertex -873.327 423.426 108.789 + vertex -872.221 430.098 101.172 + vertex -874.248 423.542 101.141 + endloop + endfacet + facet normal -0.945438 0.303233 0.119149 + outer loop + vertex -871.33 429.877 108.81 + vertex -870.156 436.53 101.195 + vertex -872.221 430.098 101.172 + endloop + endfacet + facet normal -0.944058 0.302749 0.130756 + outer loop + vertex -870.156 436.53 101.195 + vertex -871.079 436.88 93.7123 + vertex -872.221 430.098 101.172 + endloop + endfacet + facet normal -0.944573 0.301617 0.129648 + outer loop + vertex -872.221 430.098 101.172 + vertex -871.079 436.88 93.7123 + vertex -873.177 430.326 93.6738 + endloop + endfacet + facet normal -0.939968 0.315188 0.130834 + outer loop + vertex -870.156 436.53 101.195 + vertex -868.944 443.242 93.731 + vertex -871.079 436.88 93.7123 + endloop + endfacet + facet normal -0.938236 0.314568 0.144087 + outer loop + vertex -868.944 443.242 93.731 + vertex -869.879 443.813 86.3961 + vertex -871.079 436.88 93.7123 + endloop + endfacet + facet normal -0.939719 0.311537 0.140971 + outer loop + vertex -871.079 436.88 93.7123 + vertex -869.879 443.813 86.3961 + vertex -872.04 437.307 86.3678 + endloop + endfacet + facet normal -0.932344 0.33138 0.144645 + outer loop + vertex -868.944 443.242 93.731 + vertex -867.653 450.087 86.3711 + vertex -869.879 443.813 86.3961 + endloop + endfacet + facet normal -0.92977 0.330536 0.16209 + outer loop + vertex -867.653 450.087 86.3711 + vertex -868.601 450.972 79.1237 + vertex -869.879 443.813 86.3961 + endloop + endfacet + facet normal -0.933378 0.323789 0.154814 + outer loop + vertex -869.879 443.813 86.3961 + vertex -868.601 450.972 79.1237 + vertex -870.834 444.524 79.1524 + endloop + endfacet + facet normal -0.924441 0.344676 0.16312 + outer loop + vertex -867.653 450.087 86.3711 + vertex -866.293 457.204 79.0372 + vertex -868.601 450.972 79.1237 + endloop + endfacet + facet normal -0.920699 0.343595 0.185081 + outer loop + vertex -866.293 457.204 79.0372 + vertex -867.271 458.409 71.9345 + vertex -868.601 450.972 79.1237 + endloop + endfacet + facet normal -0.927496 0.332001 0.171831 + outer loop + vertex -868.601 450.972 79.1237 + vertex -867.271 458.409 71.9345 + vertex -869.571 451.948 72.0018 + endloop + endfacet + facet normal -0.928688 0.322765 0.18265 + outer loop + vertex -866.293 457.204 79.0372 + vertex -865.069 464.751 71.9264 + vertex -867.271 458.409 71.9345 + endloop + endfacet + facet normal -0.924577 0.321365 0.204651 + outer loop + vertex -865.069 464.751 71.9264 + vertex -866.05 466.173 65.259 + vertex -867.271 458.409 71.9345 + endloop + endfacet + facet normal -0.933037 0.307429 0.186894 + outer loop + vertex -867.271 458.409 71.9345 + vertex -866.05 466.173 65.259 + vertex -868.273 459.463 65.1986 + endloop + endfacet + facet normal -0.956678 0.222128 0.188219 + outer loop + vertex -865.069 464.751 71.9264 + vertex -864.431 472.882 65.5703 + vertex -866.05 466.173 65.259 + endloop + endfacet + facet normal -0.953098 0.220371 0.207463 + outer loop + vertex -864.431 472.882 65.5703 + vertex -865.35 474.6 59.5221 + vertex -866.05 466.173 65.259 + endloop + endfacet + facet normal -0.957065 0.213181 0.196417 + outer loop + vertex -866.05 466.173 65.259 + vertex -865.35 474.6 59.5221 + vertex -867.049 467.136 59.3486 + endloop + endfacet + facet normal -0.9508 0.233604 0.203489 + outer loop + vertex -863.449 471.136 72.1618 + vertex -864.431 472.882 65.5703 + vertex -865.069 464.751 71.9264 + endloop + endfacet + facet normal -0.954579 0.235327 0.182758 + outer loop + vertex -864.078 463.284 78.99 + vertex -863.449 471.136 72.1618 + vertex -865.069 464.751 71.9264 + endloop + endfacet + facet normal -0.948349 0.247962 0.197861 + outer loop + vertex -862.437 469.408 79.1796 + vertex -863.449 471.136 72.1618 + vertex -864.078 463.284 78.99 + endloop + endfacet + facet normal -0.952223 0.24968 0.175871 + outer loop + vertex -863.099 461.911 86.2401 + vertex -862.437 469.408 79.1796 + vertex -864.078 463.284 78.99 + endloop + endfacet + facet normal -0.915779 0.353568 0.190626 + outer loop + vertex -863.099 461.911 86.2401 + vertex -864.078 463.284 78.99 + vertex -865.335 456.097 86.2788 + endloop + endfacet + facet normal -0.92036 0.355152 0.163719 + outer loop + vertex -864.412 455.111 93.6078 + vertex -863.099 461.911 86.2401 + vertex -865.335 456.097 86.2788 + endloop + endfacet + facet normal -0.91441 0.369669 0.164922 + outer loop + vertex -864.412 455.111 93.6078 + vertex -865.335 456.097 86.2788 + vertex -866.734 449.336 93.6827 + endloop + endfacet + facet normal -0.91784 0.370748 0.141832 + outer loop + vertex -865.863 448.655 101.094 + vertex -864.412 455.111 93.6078 + vertex -866.734 449.336 93.6827 + endloop + endfacet + facet normal -0.927771 0.345611 0.14069 + outer loop + vertex -865.863 448.655 101.094 + vertex -866.734 449.336 93.6827 + vertex -868.053 442.746 101.168 + endloop + endfacet + facet normal -0.930002 0.34622 0.1234 + outer loop + vertex -867.232 442.261 108.713 + vertex -865.863 448.655 101.094 + vertex -868.053 442.746 101.168 + endloop + endfacet + facet normal -0.938959 0.321375 0.122779 + outer loop + vertex -867.232 442.261 108.713 + vertex -868.053 442.746 101.168 + vertex -869.3 436.189 108.794 + endloop + endfacet + facet normal -0.940612 0.321746 0.108293 + outer loop + vertex -868.536 435.839 116.471 + vertex -867.232 442.261 108.713 + vertex -869.3 436.189 108.794 + endloop + endfacet + facet normal -0.946052 0.305453 0.108092 + outer loop + vertex -868.536 435.839 116.471 + vertex -869.3 436.189 108.794 + vertex -870.528 429.644 116.54 + endloop + endfacet + facet normal -0.947475 0.305751 0.0938442 + outer loop + vertex -869.833 429.412 124.319 + vertex -868.536 435.839 116.471 + vertex -870.528 429.644 116.54 + endloop + endfacet + facet normal -0.951005 0.294595 0.0938263 + outer loop + vertex -869.833 429.412 124.319 + vertex -870.528 429.644 116.54 + vertex -871.767 423.158 124.355 + endloop + endfacet + facet normal -0.952251 0.294894 0.0790887 + outer loop + vertex -871.153 423.034 132.209 + vertex -869.833 429.412 124.319 + vertex -871.767 423.158 124.355 + endloop + endfacet + facet normal -0.955659 0.28363 0.0791775 + outer loop + vertex -871.153 423.034 132.209 + vertex -871.767 423.158 124.355 + vertex -873.011 416.771 132.209 + endloop + endfacet + facet normal -0.956686 0.283934 0.0642915 + outer loop + vertex -872.492 416.733 140.106 + vertex -871.153 423.034 132.209 + vertex -873.011 416.771 132.209 + endloop + endfacet + facet normal -0.96064 0.270207 0.0644859 + outer loop + vertex -872.492 416.733 140.106 + vertex -873.011 416.771 132.209 + vertex -874.25 410.488 140.084 + endloop + endfacet + facet normal -0.961456 0.27049 0.0493759 + outer loop + vertex -873.841 410.503 147.98 + vertex -872.492 416.733 140.106 + vertex -874.25 410.488 140.084 + endloop + endfacet + facet normal -0.965983 0.253796 0.0496421 + outer loop + vertex -873.841 410.503 147.98 + vertex -874.25 410.488 140.084 + vertex -875.479 404.269 147.956 + endloop + endfacet + facet normal -0.966599 0.254018 0.0340718 + outer loop + vertex -875.193 404.307 155.814 + vertex -873.841 410.503 147.98 + vertex -875.479 404.269 147.956 + endloop + endfacet + facet normal -0.971238 0.235622 0.034329 + outer loop + vertex -875.193 404.307 155.814 + vertex -875.479 404.269 147.956 + vertex -876.709 398.058 155.8 + endloop + endfacet + facet normal -0.971643 0.235757 0.0181525 + outer loop + vertex -876.554 398.095 163.621 + vertex -875.193 404.307 155.814 + vertex -876.709 398.058 155.8 + endloop + endfacet + facet normal -0.976172 0.216224 0.018334 + outer loop + vertex -876.554 398.095 163.621 + vertex -876.709 398.058 155.8 + vertex -877.949 391.797 163.618 + endloop + endfacet + facet normal -0.976333 0.216267 0.00147842 + outer loop + vertex -877.934 391.813 171.441 + vertex -876.554 398.095 163.621 + vertex -877.949 391.797 163.618 + endloop + endfacet + facet normal -0.980725 0.195385 0.00153043 + outer loop + vertex -877.934 391.813 171.441 + vertex -877.949 391.797 163.618 + vertex -879.205 385.431 171.443 + endloop + endfacet + facet normal -0.980606 0.195355 -0.0157421 + outer loop + vertex -879.337 385.405 179.318 + vertex -877.934 391.813 171.441 + vertex -879.205 385.431 171.443 + endloop + endfacet + facet normal -0.984957 0.172069 -0.0158933 + outer loop + vertex -879.337 385.405 179.318 + vertex -879.205 385.431 171.443 + vertex -880.472 378.906 179.321 + endloop + endfacet + facet normal -0.984524 0.171985 -0.0336771 + outer loop + vertex -880.758 378.824 187.265 + vertex -879.337 385.405 179.318 + vertex -880.472 378.906 179.321 + endloop + endfacet + facet normal -0.988711 0.145903 -0.0340999 + outer loop + vertex -880.758 378.824 187.265 + vertex -880.472 378.906 179.321 + vertex -881.737 372.19 187.267 + endloop + endfacet + facet normal -0.987929 0.145782 -0.0523806 + outer loop + vertex -882.185 372.027 195.254 + vertex -880.758 378.824 187.265 + vertex -881.737 372.19 187.267 + endloop + endfacet + facet normal -0.991747 0.116654 -0.0531882 + outer loop + vertex -882.185 372.027 195.254 + vertex -881.737 372.19 187.267 + vertex -882.98 365.267 195.254 + endloop + endfacet + facet normal -0.987981 0.145265 -0.0528292 + outer loop + vertex -881.206 378.682 195.252 + vertex -880.758 378.824 187.265 + vertex -882.185 372.027 195.254 + endloop + endfacet + facet normal -0.986816 0.145088 -0.0717171 + outer loop + vertex -882.799 371.792 203.231 + vertex -881.206 378.682 195.252 + vertex -882.185 372.027 195.254 + endloop + endfacet + facet normal -0.990612 0.115659 -0.0728772 + outer loop + vertex -882.799 371.792 203.231 + vertex -882.185 372.027 195.254 + vertex -883.592 365.002 203.232 + endloop + endfacet + facet normal -0.986887 0.144227 -0.0724742 + outer loop + vertex -881.821 378.483 203.229 + vertex -881.206 378.682 195.252 + vertex -882.799 371.792 203.231 + endloop + endfacet + facet normal -0.98529 0.143989 -0.0920335 + outer loop + vertex -883.583 371.493 211.153 + vertex -881.821 378.483 203.229 + vertex -882.799 371.792 203.231 + endloop + endfacet + facet normal -0.989027 0.11437 -0.0935205 + outer loop + vertex -883.583 371.493 211.153 + vertex -882.799 371.792 203.231 + vertex -884.373 364.659 211.154 + endloop + endfacet + facet normal -0.985345 0.143107 -0.0928237 + outer loop + vertex -882.605 378.225 211.15 + vertex -881.821 378.483 203.229 + vertex -883.583 371.493 211.153 + endloop + endfacet + facet normal -0.983339 0.142809 -0.112474 + outer loop + vertex -884.533 371.126 218.997 + vertex -882.605 378.225 211.15 + vertex -883.583 371.493 211.153 + endloop + endfacet + facet normal -0.987022 0.11277 -0.114329 + outer loop + vertex -884.533 371.126 218.997 + vertex -883.583 371.493 211.153 + vertex -885.32 364.238 218.998 + endloop + endfacet + facet normal -0.983382 0.141714 -0.113475 + outer loop + vertex -883.555 377.911 218.995 + vertex -882.605 378.225 211.15 + vertex -884.533 371.126 218.997 + endloop + endfacet + facet normal -0.981059 0.141373 -0.13243 + outer loop + vertex -885.645 370.691 226.766 + vertex -883.555 377.911 218.995 + vertex -884.533 371.126 218.997 + endloop + endfacet + facet normal -0.984664 0.11094 -0.134648 + outer loop + vertex -885.645 370.691 226.766 + vertex -884.533 371.126 218.997 + vertex -886.428 363.742 226.767 + endloop + endfacet + facet normal -0.98108 0.140109 -0.13361 + outer loop + vertex -884.666 377.538 226.764 + vertex -883.555 377.911 218.995 + vertex -885.645 370.691 226.766 + endloop + endfacet + facet normal -0.978577 0.139745 -0.151191 + outer loop + vertex -886.905 370.193 234.465 + vertex -884.666 377.538 226.764 + vertex -885.645 370.691 226.766 + endloop + endfacet + facet normal -0.98208 0.108991 -0.153755 + outer loop + vertex -886.905 370.193 234.465 + vertex -885.645 370.691 226.766 + vertex -887.684 363.174 234.467 + endloop + endfacet + facet normal -0.978568 0.13829 -0.152577 + outer loop + vertex -885.927 377.113 234.463 + vertex -884.666 377.538 226.764 + vertex -886.905 370.193 234.465 + endloop + endfacet + facet normal -0.975975 0.137919 -0.168675 + outer loop + vertex -888.3 369.645 242.089 + vertex -885.927 377.113 234.463 + vertex -886.905 370.193 234.465 + endloop + endfacet + facet normal -0.979366 0.106867 -0.171529 + outer loop + vertex -888.3 369.645 242.089 + vertex -886.905 370.193 234.465 + vertex -889.075 362.548 242.09 + endloop + endfacet + facet normal -0.975936 0.136537 -0.170017 + outer loop + vertex -887.321 376.64 242.087 + vertex -885.927 377.113 234.463 + vertex -888.3 369.645 242.089 + endloop + endfacet + facet normal -0.973228 0.136154 -0.185171 + outer loop + vertex -889.814 369.064 249.617 + vertex -887.321 376.64 242.087 + vertex -888.3 369.645 242.089 + endloop + endfacet + facet normal -0.9765 0.104953 -0.188237 + outer loop + vertex -889.814 369.064 249.617 + vertex -888.3 369.645 242.089 + vertex -890.586 361.884 249.618 + endloop + endfacet + facet normal -0.973171 0.134997 -0.186317 + outer loop + vertex -888.832 376.142 249.615 + vertex -887.321 376.64 242.087 + vertex -889.814 369.064 249.617 + endloop + endfacet + facet normal -0.970358 0.134603 -0.200718 + outer loop + vertex -891.43 368.464 257.029 + vertex -888.832 376.142 249.615 + vertex -889.814 369.064 249.617 + endloop + endfacet + facet normal -0.973507 0.103432 -0.203925 + outer loop + vertex -891.43 368.464 257.029 + vertex -889.814 369.064 249.617 + vertex -892.203 361.193 257.03 + endloop + endfacet + facet normal -0.9703 0.133792 -0.201536 + outer loop + vertex -890.441 375.634 257.027 + vertex -888.832 376.142 249.615 + vertex -891.43 368.464 257.029 + endloop + endfacet + facet normal -0.967467 0.133397 -0.214973 + outer loop + vertex -893.131 367.844 264.3 + vertex -890.441 375.634 257.027 + vertex -891.43 368.464 257.029 + endloop + endfacet + facet normal -0.970527 0.101936 -0.218371 + outer loop + vertex -893.131 367.844 264.3 + vertex -891.43 368.464 257.029 + vertex -893.906 360.466 264.297 + endloop + endfacet + facet normal -0.967407 0.13276 -0.215634 + outer loop + vertex -892.132 375.12 264.297 + vertex -890.441 375.634 257.027 + vertex -893.131 367.844 264.3 + endloop + endfacet + facet normal -0.965003 0.132427 -0.226344 + outer loop + vertex -894.873 367.165 271.33 + vertex -892.132 375.12 264.297 + vertex -893.131 367.844 264.3 + endloop + endfacet + facet normal -0.967918 0.100915 -0.23011 + outer loop + vertex -894.873 367.165 271.33 + vertex -893.131 367.844 264.3 + vertex -895.655 359.675 271.332 + endloop + endfacet + facet normal -0.964864 0.131254 -0.227617 + outer loop + vertex -893.87 374.555 271.336 + vertex -892.132 375.12 264.297 + vertex -894.873 367.165 271.33 + endloop + endfacet + facet normal -0.962985 0.131005 -0.23558 + outer loop + vertex -896.584 366.388 277.888 + vertex -893.87 374.555 271.336 + vertex -894.873 367.165 271.33 + endloop + endfacet + facet normal -0.965676 0.0992261 -0.240051 + outer loop + vertex -896.584 366.388 277.888 + vertex -894.873 367.165 271.33 + vertex -897.365 358.796 277.891 + endloop + endfacet + facet normal -0.962815 0.129906 -0.236879 + outer loop + vertex -895.577 373.858 277.895 + vertex -893.87 374.555 271.336 + vertex -896.584 366.388 277.888 + endloop + endfacet + facet normal -0.961192 0.129694 -0.243493 + outer loop + vertex -898.143 365.534 283.59 + vertex -895.577 373.858 277.895 + vertex -896.584 366.388 277.888 + endloop + endfacet + facet normal -0.963608 0.0972226 -0.249014 + outer loop + vertex -898.143 365.534 283.59 + vertex -896.584 366.388 277.888 + vertex -898.914 357.887 283.585 + endloop + endfacet + facet normal -0.960905 0.096957 -0.259347 + outer loop + vertex -900.192 357.212 288.068 + vertex -898.143 365.534 283.59 + vertex -898.914 357.887 283.585 + endloop + endfacet + facet normal -0.960987 0.0971861 -0.258959 + outer loop + vertex -899.407 364.896 288.041 + vertex -898.143 365.534 283.59 + vertex -900.192 357.212 288.068 + endloop + endfacet + facet normal -0.954111 0.096397 -0.283512 + outer loop + vertex -901.139 357.349 291.304 + vertex -899.407 364.896 288.041 + vertex -900.192 357.212 288.068 + endloop + endfacet + facet normal -0.956908 0.065076 -0.283007 + outer loop + vertex -901.139 357.349 291.304 + vertex -900.192 357.212 288.068 + vertex -901.678 349.523 291.326 + endloop + endfacet + facet normal -0.955197 0.0620391 -0.289395 + outer loop + vertex -901.678 349.523 291.326 + vertex -900.192 357.212 288.068 + vertex -900.702 349.468 288.091 + endloop + endfacet + facet normal -0.956194 0.100597 -0.274905 + outer loop + vertex -900.323 365.06 291.286 + vertex -899.407 364.896 288.041 + vertex -901.139 357.349 291.304 + endloop + endfacet + facet normal -0.952851 0.127544 -0.27533 + outer loop + vertex -900.323 365.06 291.286 + vertex -898.398 372.451 288.05 + vertex -899.407 364.896 288.041 + endloop + endfacet + facet normal -0.958604 0.128287 -0.254205 + outer loop + vertex -898.398 372.451 288.05 + vertex -897.131 373.054 283.577 + vertex -899.407 364.896 288.041 + endloop + endfacet + facet normal -0.955672 0.156143 -0.24962 + outer loop + vertex -898.398 372.451 288.05 + vertex -895.919 380.462 283.568 + vertex -897.131 373.054 283.577 + endloop + endfacet + facet normal -0.957748 0.156492 -0.241307 + outer loop + vertex -895.919 380.462 283.568 + vertex -894.369 381.186 277.887 + vertex -897.131 373.054 283.577 + endloop + endfacet + facet normal -0.957953 0.15767 -0.239723 + outer loop + vertex -897.131 373.054 283.577 + vertex -894.369 381.186 277.887 + vertex -895.577 373.858 277.895 + endloop + endfacet + facet normal -0.959351 0.157907 -0.233904 + outer loop + vertex -894.369 381.186 277.887 + vertex -892.669 381.807 271.335 + vertex -895.577 373.858 277.895 + endloop + endfacet + facet normal -0.955728 0.182767 -0.230608 + outer loop + vertex -894.369 381.186 277.887 + vertex -891.305 388.94 271.331 + vertex -892.669 381.807 271.335 + endloop + endfacet + facet normal -0.957543 0.183117 -0.222666 + outer loop + vertex -891.305 388.94 271.331 + vertex -889.595 389.329 264.301 + vertex -892.669 381.807 271.335 + endloop + endfacet + facet normal -0.957555 0.183358 -0.222414 + outer loop + vertex -892.669 381.807 271.335 + vertex -889.595 389.329 264.301 + vertex -890.945 382.277 264.297 + endloop + endfacet + facet normal -0.961301 0.159043 -0.224957 + outer loop + vertex -892.669 381.807 271.335 + vertex -890.945 382.277 264.297 + vertex -893.87 374.555 271.336 + endloop + endfacet + facet normal -0.959906 0.183802 -0.211654 + outer loop + vertex -889.595 389.329 264.301 + vertex -887.932 389.637 257.023 + vertex -890.945 382.277 264.297 + endloop + endfacet + facet normal -0.959922 0.184381 -0.211075 + outer loop + vertex -890.945 382.277 264.297 + vertex -887.932 389.637 257.023 + vertex -889.267 382.688 257.024 + endloop + endfacet + facet normal -0.963801 0.159903 -0.213352 + outer loop + vertex -890.945 382.277 264.297 + vertex -889.267 382.688 257.024 + vertex -892.132 375.12 264.297 + endloop + endfacet + facet normal -0.962625 0.184903 -0.197898 + outer loop + vertex -887.932 389.637 257.023 + vertex -886.347 389.953 249.609 + vertex -889.267 382.688 257.024 + endloop + endfacet + facet normal -0.962629 0.185429 -0.197385 + outer loop + vertex -889.267 382.688 257.024 + vertex -886.347 389.953 249.609 + vertex -887.667 383.099 249.61 + endloop + endfacet + facet normal -0.966583 0.160864 -0.199598 + outer loop + vertex -889.267 382.688 257.024 + vertex -887.667 383.099 249.61 + vertex -890.441 375.634 257.027 + endloop + endfacet + facet normal -0.965331 0.185952 -0.183189 + outer loop + vertex -886.347 389.953 249.609 + vertex -884.855 390.28 242.08 + vertex -887.667 383.099 249.61 + endloop + endfacet + facet normal -0.96532 0.186894 -0.182286 + outer loop + vertex -887.667 383.099 249.61 + vertex -884.855 390.28 242.08 + vertex -886.165 383.516 242.083 + endloop + endfacet + facet normal -0.969376 0.162113 -0.18447 + outer loop + vertex -887.667 383.099 249.61 + vertex -886.165 383.516 242.083 + vertex -888.832 376.142 249.615 + endloop + endfacet + facet normal -0.967915 0.187405 -0.167394 + outer loop + vertex -884.855 390.28 242.08 + vertex -883.475 390.598 234.457 + vertex -886.165 383.516 242.083 + endloop + endfacet + facet normal -0.96789 0.188171 -0.166674 + outer loop + vertex -886.165 383.516 242.083 + vertex -883.475 390.598 234.457 + vertex -884.776 383.909 234.459 + endloop + endfacet + facet normal -0.972037 0.163345 -0.168708 + outer loop + vertex -886.165 383.516 242.083 + vertex -884.776 383.909 234.459 + vertex -887.321 376.64 242.087 + endloop + endfacet + facet normal -0.970455 0.188674 -0.1504 + outer loop + vertex -883.475 390.598 234.457 + vertex -882.227 390.882 226.758 + vertex -884.776 383.909 234.459 + endloop + endfacet + facet normal -0.970406 0.1896 -0.149545 + outer loop + vertex -884.776 383.909 234.459 + vertex -882.227 390.882 226.758 + vertex -883.52 384.265 226.76 + endloop + endfacet + facet normal -0.974611 0.164987 -0.151372 + outer loop + vertex -884.776 383.909 234.459 + vertex -883.52 384.265 226.76 + vertex -885.927 377.113 234.463 + endloop + endfacet + facet normal -0.972883 0.19009 -0.131777 + outer loop + vertex -882.227 390.882 226.758 + vertex -881.126 391.13 218.989 + vertex -883.52 384.265 226.76 + endloop + endfacet + facet normal -0.972823 0.190895 -0.131049 + outer loop + vertex -883.52 384.265 226.76 + vertex -881.126 391.13 218.989 + vertex -882.413 384.574 218.99 + endloop + endfacet + facet normal -0.977086 0.166473 -0.132625 + outer loop + vertex -883.52 384.265 226.76 + vertex -882.413 384.574 218.99 + vertex -884.666 377.538 226.764 + endloop + endfacet + facet normal -0.975112 0.191348 -0.11199 + outer loop + vertex -881.126 391.13 218.989 + vertex -880.184 391.339 211.145 + vertex -882.413 384.574 218.99 + endloop + endfacet + facet normal -0.975043 0.192076 -0.111343 + outer loop + vertex -882.413 384.574 218.99 + vertex -880.184 391.339 211.145 + vertex -881.465 384.839 211.147 + endloop + endfacet + facet normal -0.979349 0.167865 -0.112682 + outer loop + vertex -882.413 384.574 218.99 + vertex -881.465 384.839 211.147 + vertex -883.555 377.911 218.995 + endloop + endfacet + facet normal -0.977013 0.192471 -0.0916491 + outer loop + vertex -880.184 391.339 211.145 + vertex -879.407 391.509 203.223 + vertex -881.465 384.839 211.147 + endloop + endfacet + facet normal -0.976947 0.193041 -0.0911526 + outer loop + vertex -881.465 384.839 211.147 + vertex -879.407 391.509 203.223 + vertex -880.684 385.05 203.225 + endloop + endfacet + facet normal -0.981277 0.169088 -0.0922171 + outer loop + vertex -881.465 384.839 211.147 + vertex -880.684 385.05 203.225 + vertex -882.605 378.225 211.15 + endloop + endfacet + facet normal -0.978512 0.193355 -0.0716059 + outer loop + vertex -879.407 391.509 203.223 + vertex -878.798 391.64 195.246 + vertex -880.684 385.05 203.225 + endloop + endfacet + facet normal -0.978445 0.193857 -0.0711759 + outer loop + vertex -880.684 385.05 203.225 + vertex -878.798 391.64 195.246 + vertex -880.07 385.217 195.248 + endloop + endfacet + facet normal -0.982786 0.170138 -0.0720082 + outer loop + vertex -880.684 385.05 203.225 + vertex -880.07 385.217 195.248 + vertex -881.821 378.483 203.229 + endloop + endfacet + facet normal -0.979587 0.19409 -0.0523325 + outer loop + vertex -878.798 391.64 195.246 + vertex -878.352 391.735 187.259 + vertex -880.07 385.217 195.248 + endloop + endfacet + facet normal -0.979528 0.194473 -0.0520073 + outer loop + vertex -880.07 385.217 195.248 + vertex -878.352 391.735 187.259 + vertex -879.623 385.334 187.262 + endloop + endfacet + facet normal -0.983876 0.170941 -0.0525945 + outer loop + vertex -880.07 385.217 195.248 + vertex -879.623 385.334 187.262 + vertex -881.206 378.682 195.252 + endloop + endfacet + facet normal -0.980291 0.194631 -0.0338984 + outer loop + vertex -878.352 391.735 187.259 + vertex -878.067 391.791 179.316 + vertex -879.623 385.334 187.262 + endloop + endfacet + facet normal -0.980235 0.19496 -0.0336202 + outer loop + vertex -879.623 385.334 187.262 + vertex -878.067 391.791 179.316 + vertex -879.337 385.405 179.318 + endloop + endfacet + facet normal -0.975856 0.215818 -0.0335906 + outer loop + vertex -878.352 391.735 187.259 + vertex -876.674 398.09 179.322 + vertex -878.067 391.791 179.316 + endloop + endfacet + facet normal -0.976284 0.215896 -0.016067 + outer loop + vertex -876.674 398.09 179.322 + vertex -876.541 398.105 171.446 + vertex -878.067 391.791 179.316 + endloop + endfacet + facet normal -0.976235 0.216133 -0.015867 + outer loop + vertex -878.067 391.791 179.316 + vertex -876.541 398.105 171.446 + vertex -877.934 391.813 171.441 + endloop + endfacet + facet normal -0.971735 0.235535 -0.0159514 + outer loop + vertex -876.674 398.09 179.322 + vertex -875.031 404.335 171.466 + vertex -876.541 398.105 171.446 + endloop + endfacet + facet normal -0.971871 0.235512 0.00116201 + outer loop + vertex -875.031 404.335 171.466 + vertex -875.042 404.329 163.638 + vertex -876.541 398.105 171.446 + endloop + endfacet + facet normal -0.971819 0.235725 0.00134221 + outer loop + vertex -876.541 398.105 171.446 + vertex -875.042 404.329 163.638 + vertex -876.554 398.095 163.621 + endloop + endfacet + facet normal -0.967263 0.253773 0.00114238 + outer loop + vertex -875.031 404.335 171.466 + vertex -873.418 410.518 163.663 + vertex -875.042 404.329 163.638 + endloop + endfacet + facet normal -0.967129 0.253672 0.0176365 + outer loop + vertex -873.418 410.518 163.663 + vertex -873.562 410.513 155.84 + vertex -875.042 404.329 163.638 + endloop + endfacet + facet normal -0.967038 0.254001 0.0179147 + outer loop + vertex -875.042 404.329 163.638 + vertex -873.562 410.513 155.84 + vertex -875.193 404.307 155.814 + endloop + endfacet + facet normal -0.962703 0.26999 0.0175446 + outer loop + vertex -873.418 410.518 163.663 + vertex -871.833 416.678 155.842 + vertex -873.562 410.513 155.84 + endloop + endfacet + facet normal -0.962316 0.269875 0.0333894 + outer loop + vertex -871.833 416.678 155.842 + vertex -872.099 416.702 147.993 + vertex -873.562 410.513 155.84 + endloop + endfacet + facet normal -0.96219 0.270284 0.0337352 + outer loop + vertex -873.562 410.513 155.84 + vertex -872.099 416.702 147.993 + vertex -873.841 410.503 147.98 + endloop + endfacet + facet normal -0.958316 0.283763 0.033298 + outer loop + vertex -871.833 416.678 155.842 + vertex -870.284 422.836 147.945 + vertex -872.099 416.702 147.993 + endloop + endfacet + facet normal -0.957673 0.283695 0.0487749 + outer loop + vertex -870.284 422.836 147.945 + vertex -870.658 422.925 140.08 + vertex -872.099 416.702 147.993 + endloop + endfacet + facet normal -0.957629 0.283827 0.0488864 + outer loop + vertex -872.099 416.702 147.993 + vertex -870.658 422.925 140.08 + vertex -872.492 416.733 140.106 + endloop + endfacet + facet normal -0.953952 0.295973 0.0487372 + outer loop + vertex -870.284 422.836 147.945 + vertex -868.775 429.011 139.98 + vertex -870.658 422.925 140.08 + endloop + endfacet + facet normal -0.953021 0.295945 0.0645486 + outer loop + vertex -868.775 429.011 139.98 + vertex -869.249 429.195 132.133 + vertex -870.658 422.925 140.08 + endloop + endfacet + facet normal -0.953267 0.295279 0.0639792 + outer loop + vertex -870.658 422.925 140.08 + vertex -869.249 429.195 132.133 + vertex -871.153 423.034 132.209 + endloop + endfacet + facet normal -0.948636 0.309704 0.0646066 + outer loop + vertex -868.775 429.011 139.98 + vertex -867.295 435.203 132.026 + vertex -869.249 429.195 132.133 + endloop + endfacet + facet normal -0.947387 0.309596 0.0812935 + outer loop + vertex -867.295 435.203 132.026 + vertex -867.869 435.497 124.213 + vertex -869.249 429.195 132.133 + endloop + endfacet + facet normal -0.948288 0.307337 0.0793388 + outer loop + vertex -869.249 429.195 132.133 + vertex -867.869 435.497 124.213 + vertex -869.833 429.412 124.319 + endloop + endfacet + facet normal -0.940266 0.330526 0.0815605 + outer loop + vertex -867.295 435.203 132.026 + vertex -865.808 441.37 124.174 + vertex -867.869 435.497 124.213 + endloop + endfacet + facet normal -0.938702 0.330095 0.0993825 + outer loop + vertex -865.808 441.37 124.174 + vertex -866.488 441.785 116.375 + vertex -867.869 435.497 124.213 + endloop + endfacet + facet normal -0.940707 0.325538 0.0953733 + outer loop + vertex -867.869 435.497 124.213 + vertex -866.488 441.785 116.375 + vertex -868.536 435.839 116.471 + endloop + endfacet + facet normal -0.926718 0.362194 0.100048 + outer loop + vertex -865.808 441.37 124.174 + vertex -864.273 447.43 116.454 + vertex -866.488 441.785 116.375 + endloop + endfacet + facet normal -0.924886 0.361213 0.118786 + outer loop + vertex -864.273 447.43 116.454 + vertex -865.049 448.006 108.665 + vertex -866.488 441.785 116.375 + endloop + endfacet + facet normal -0.928534 0.353887 0.112195 + outer loop + vertex -866.488 441.785 116.375 + vertex -865.049 448.006 108.665 + vertex -867.232 442.261 108.713 + endloop + endfacet + facet normal -0.909885 0.397142 0.119945 + outer loop + vertex -864.273 447.43 116.454 + vertex -862.683 453.375 108.835 + vertex -865.049 448.006 108.665 + endloop + endfacet + facet normal -0.907498 0.395398 0.141802 + outer loop + vertex -862.683 453.375 108.835 + vertex -863.532 454.202 101.093 + vertex -865.049 448.006 108.665 + endloop + endfacet + facet normal -0.913935 0.384058 0.131232 + outer loop + vertex -865.049 448.006 108.665 + vertex -863.532 454.202 101.093 + vertex -865.863 448.655 101.094 + endloop + endfacet + facet normal -0.904396 0.406837 0.128656 + outer loop + vertex -861.818 452.741 116.918 + vertex -862.683 453.375 108.835 + vertex -864.273 447.43 116.454 + endloop + endfacet + facet normal -0.906058 0.409547 0.106443 + outer loop + vertex -863.508 447.037 124.48 + vertex -861.818 452.741 116.918 + vertex -864.273 447.43 116.454 + endloop + endfacet + facet normal -0.901047 0.418405 0.114243 + outer loop + vertex -860.831 452.589 125.259 + vertex -861.818 452.741 116.918 + vertex -863.508 447.037 124.48 + endloop + endfacet + facet normal -0.90201 0.422356 0.0894043 + outer loop + vertex -862.799 446.809 132.708 + vertex -860.831 452.589 125.259 + vertex -863.508 447.037 124.48 + endloop + endfacet + facet normal -0.922747 0.374781 0.0898706 + outer loop + vertex -862.799 446.809 132.708 + vertex -863.508 447.037 124.48 + vertex -865.19 441.063 132.119 + endloop + endfacet + facet normal -0.923497 0.377079 0.0704625 + outer loop + vertex -864.651 440.885 140.151 + vertex -862.799 446.809 132.708 + vertex -865.19 441.063 132.119 + endloop + endfacet + facet normal -0.937785 0.339963 0.0705989 + outer loop + vertex -864.651 440.885 140.151 + vertex -865.19 441.063 132.119 + vertex -866.81 434.976 139.917 + endloop + endfacet + facet normal -0.938613 0.340991 0.0522609 + outer loop + vertex -866.429 434.81 147.836 + vertex -864.651 440.885 140.151 + vertex -866.81 434.976 139.917 + endloop + endfacet + facet normal -0.947403 0.315766 0.0521563 + outer loop + vertex -866.429 434.81 147.836 + vertex -866.81 434.976 139.917 + vertex -868.41 428.868 147.839 + endloop + endfacet + facet normal -0.948135 0.316001 0.0343922 + outer loop + vertex -868.16 428.765 155.678 + vertex -866.429 434.81 147.836 + vertex -868.41 428.868 147.839 + endloop + endfacet + facet normal -0.953858 0.298287 0.0343419 + outer loop + vertex -868.16 428.765 155.678 + vertex -868.41 428.868 147.839 + vertex -870.031 422.77 155.777 + endloop + endfacet + facet normal -0.954358 0.298162 0.0173187 + outer loop + vertex -869.903 422.728 163.579 + vertex -868.16 428.765 155.678 + vertex -870.031 422.77 155.777 + endloop + endfacet + facet normal -0.958713 0.283849 0.0173127 + outer loop + vertex -869.903 422.728 163.579 + vertex -870.031 422.77 155.777 + vertex -871.698 416.661 163.656 + endloop + endfacet + facet normal -0.958914 0.283697 0.000641347 + outer loop + vertex -871.695 416.651 171.475 + vertex -869.903 422.728 163.579 + vertex -871.698 416.661 163.656 + endloop + endfacet + facet normal -0.963039 0.269361 0.000625769 + outer loop + vertex -871.695 416.651 171.475 + vertex -871.698 416.661 163.656 + vertex -873.41 410.518 171.49 + endloop + endfacet + facet normal -0.962924 0.269286 -0.0161942 + outer loop + vertex -873.545 410.512 179.367 + vertex -871.695 416.651 171.475 + vertex -873.41 410.518 171.49 + endloop + endfacet + facet normal -0.967265 0.253245 -0.0162804 + outer loop + vertex -873.545 410.512 179.367 + vertex -873.41 410.518 171.49 + vertex -875.164 404.324 179.344 + endloop + endfacet + facet normal -0.966833 0.253196 -0.0335391 + outer loop + vertex -875.448 404.296 187.291 + vertex -873.545 410.512 179.367 + vertex -875.164 404.324 179.344 + endloop + endfacet + facet normal -0.971407 0.235008 -0.0337673 + outer loop + vertex -875.448 404.296 187.291 + vertex -875.164 404.324 179.344 + vertex -876.958 398.047 187.267 + endloop + endfacet + facet normal -0.970647 0.234892 -0.0516785 + outer loop + vertex -877.401 397.976 195.255 + vertex -875.448 404.296 187.291 + vertex -876.958 398.047 187.267 + endloop + endfacet + facet normal -0.975202 0.215093 -0.0521056 + outer loop + vertex -877.401 397.976 195.255 + vertex -876.958 398.047 187.267 + vertex -878.798 391.64 195.246 + endloop + endfacet + facet normal -0.970713 0.234556 -0.0519615 + outer loop + vertex -875.886 404.25 195.279 + vertex -875.448 404.296 187.291 + vertex -877.401 397.976 195.255 + endloop + endfacet + facet normal -0.969578 0.234357 -0.0706844 + outer loop + vertex -878.006 397.878 203.232 + vertex -875.886 404.25 195.279 + vertex -877.401 397.976 195.255 + endloop + endfacet + facet normal -0.974133 0.21444 -0.0712757 + outer loop + vertex -878.006 397.878 203.232 + vertex -877.401 397.976 195.255 + vertex -879.407 391.509 203.223 + endloop + endfacet + facet normal -0.969632 0.234051 -0.0709437 + outer loop + vertex -876.485 404.187 203.258 + vertex -875.886 404.25 195.279 + vertex -878.006 397.878 203.232 + endloop + endfacet + facet normal -0.968083 0.233758 -0.0904024 + outer loop + vertex -878.776 397.752 211.153 + vertex -876.485 404.187 203.258 + vertex -878.006 397.878 203.232 + endloop + endfacet + facet normal -0.972648 0.213645 -0.0911646 + outer loop + vertex -878.776 397.752 211.153 + vertex -878.006 397.878 203.232 + vertex -880.184 391.339 211.145 + endloop + endfacet + facet normal -0.968168 0.23323 -0.0908574 + outer loop + vertex -877.248 404.106 211.179 + vertex -876.485 404.187 203.258 + vertex -878.776 397.752 211.153 + endloop + endfacet + facet normal -0.966223 0.23284 -0.110447 + outer loop + vertex -879.71 397.599 218.998 + vertex -877.248 404.106 211.179 + vertex -878.776 397.752 211.153 + endloop + endfacet + facet normal -0.970756 0.212667 -0.111381 + outer loop + vertex -879.71 397.599 218.998 + vertex -878.776 397.752 211.153 + vertex -881.126 391.13 218.989 + endloop + endfacet + facet normal -0.966303 0.232268 -0.110948 + outer loop + vertex -878.173 404.006 219.023 + vertex -877.248 404.106 211.179 + vertex -879.71 397.599 218.998 + endloop + endfacet + facet normal -0.964041 0.231798 -0.129978 + outer loop + vertex -880.802 397.415 226.767 + vertex -878.173 404.006 219.023 + vertex -879.71 397.599 218.998 + endloop + endfacet + facet normal -0.968551 0.211477 -0.131093 + outer loop + vertex -880.802 397.415 226.767 + vertex -879.71 397.599 218.998 + vertex -882.227 390.882 226.758 + endloop + endfacet + facet normal -0.964123 0.231112 -0.130589 + outer loop + vertex -879.254 403.884 226.79 + vertex -878.173 404.006 219.023 + vertex -880.802 397.415 226.767 + endloop + endfacet + facet normal -0.961684 0.230593 -0.148291 + outer loop + vertex -882.04 397.199 234.465 + vertex -879.254 403.884 226.79 + vertex -880.802 397.415 226.767 + endloop + endfacet + facet normal -0.966151 0.210184 -0.149582 + outer loop + vertex -882.04 397.199 234.465 + vertex -880.802 397.415 226.767 + vertex -883.475 390.598 234.457 + endloop + endfacet + facet normal -0.961764 0.229784 -0.149025 + outer loop + vertex -880.481 403.741 234.487 + vertex -879.254 403.884 226.79 + vertex -882.04 397.199 234.465 + endloop + endfacet + facet normal -0.959266 0.229243 -0.165097 + outer loop + vertex -883.409 396.962 242.087 + vertex -880.481 403.741 234.487 + vertex -882.04 397.199 234.465 + endloop + endfacet + facet normal -0.963685 0.208756 -0.166527 + outer loop + vertex -883.409 396.962 242.087 + vertex -882.04 397.199 234.465 + vertex -884.855 390.28 242.08 + endloop + endfacet + facet normal -0.95933 0.22843 -0.165847 + outer loop + vertex -881.836 403.581 242.106 + vertex -880.481 403.741 234.487 + vertex -883.409 396.962 242.087 + endloop + endfacet + facet normal -0.956804 0.227872 -0.180557 + outer loop + vertex -884.886 396.721 249.614 + vertex -881.836 403.581 242.106 + vertex -883.409 396.962 242.087 + endloop + endfacet + facet normal -0.961143 0.207505 -0.18206 + outer loop + vertex -884.886 396.721 249.614 + vertex -883.409 396.962 242.087 + vertex -886.347 389.953 249.609 + endloop + endfacet + facet normal -0.956852 0.227077 -0.181303 + outer loop + vertex -883.298 403.429 249.63 + vertex -881.836 403.581 242.106 + vertex -884.886 396.721 249.614 + endloop + endfacet + facet normal -0.95425 0.226495 -0.19521 + outer loop + vertex -886.455 396.501 257.027 + vertex -883.298 403.429 249.63 + vertex -884.886 396.721 249.614 + endloop + endfacet + facet normal -0.958515 0.206286 -0.196712 + outer loop + vertex -886.455 396.501 257.027 + vertex -884.886 396.721 249.614 + vertex -887.932 389.637 257.023 + endloop + endfacet + facet normal -0.954272 0.225964 -0.195717 + outer loop + vertex -884.848 403.3 257.039 + vertex -883.298 403.429 249.63 + vertex -886.455 396.501 257.027 + endloop + endfacet + facet normal -0.951719 0.225382 -0.208408 + outer loop + vertex -888.1 396.28 264.298 + vertex -884.848 403.3 257.039 + vertex -886.455 396.501 257.027 + endloop + endfacet + facet normal -0.955856 0.205575 -0.209948 + outer loop + vertex -888.1 396.28 264.298 + vertex -886.455 396.501 257.027 + vertex -889.595 389.329 264.301 + endloop + endfacet + facet normal -0.95173 0.224896 -0.208882 + outer loop + vertex -886.474 403.166 264.305 + vertex -884.848 403.3 257.039 + vertex -888.1 396.28 264.298 + endloop + endfacet + facet normal -0.949459 0.224372 -0.21951 + outer loop + vertex -889.796 395.983 271.332 + vertex -886.474 403.166 264.305 + vertex -888.1 396.28 264.298 + endloop + endfacet + facet normal -0.953565 0.20425 -0.221348 + outer loop + vertex -889.796 395.983 271.332 + vertex -888.1 396.28 264.298 + vertex -891.305 388.94 271.331 + endloop + endfacet + facet normal -0.951817 0.203876 -0.229085 + outer loop + vertex -892.997 388.408 277.89 + vertex -889.796 395.983 271.332 + vertex -891.305 388.94 271.331 + endloop + endfacet + facet normal -0.951779 0.203232 -0.22981 + outer loop + vertex -891.467 395.553 277.873 + vertex -889.796 395.983 271.332 + vertex -892.997 388.408 277.89 + endloop + endfacet + facet normal -0.950601 0.202968 -0.234866 + outer loop + vertex -894.523 387.815 283.551 + vertex -891.467 395.553 277.873 + vertex -892.997 388.408 277.89 + endloop + endfacet + facet normal -0.954264 0.180682 -0.23819 + outer loop + vertex -894.523 387.815 283.551 + vertex -892.997 388.408 277.89 + vertex -895.919 380.462 283.568 + endloop + endfacet + facet normal -0.952487 0.180327 -0.24546 + outer loop + vertex -897.155 380.011 288.033 + vertex -894.523 387.815 283.551 + vertex -895.919 380.462 283.568 + endloop + endfacet + facet normal -0.952439 0.180117 -0.245798 + outer loop + vertex -895.731 387.579 288.06 + vertex -894.523 387.815 283.551 + vertex -897.155 380.011 288.033 + endloop + endfacet + facet normal -0.94844 0.179419 -0.261285 + outer loop + vertex -897.966 380.506 291.318 + vertex -895.731 387.579 288.06 + vertex -897.155 380.011 288.033 + endloop + endfacet + facet normal -0.952534 0.159513 -0.259296 + outer loop + vertex -897.966 380.506 291.318 + vertex -897.155 380.011 288.033 + vertex -899.258 372.745 291.289 + endloop + endfacet + facet normal -0.944527 0.158287 -0.287775 + outer loop + vertex -897.966 380.506 291.318 + vertex -899.258 372.745 291.289 + vertex -899.287 375.516 292.908 + endloop + endfacet + facet normal -0.94544 0.15975 -0.283941 + outer loop + vertex -899.287 375.516 292.908 + vertex -898.639 379.369 292.917 + vertex -897.966 380.506 291.318 + endloop + endfacet + facet normal -0.951134 0.155852 -0.266562 + outer loop + vertex -899.258 372.745 291.289 + vertex -897.155 380.011 288.033 + vertex -898.398 372.451 288.05 + endloop + endfacet + facet normal -0.949318 0.182015 -0.256253 + outer loop + vertex -896.522 388.308 291.51 + vertex -895.731 387.579 288.06 + vertex -897.966 380.506 291.318 + endloop + endfacet + facet normal -0.942137 0.181315 -0.281962 + outer loop + vertex -896.522 388.308 291.51 + vertex -897.966 380.506 291.318 + vertex -897.893 383.378 292.922 + endloop + endfacet + facet normal -0.940199 0.17843 -0.290153 + outer loop + vertex -897.893 383.378 292.922 + vertex -897.281 386.623 292.934 + vertex -896.522 388.308 291.51 + endloop + endfacet + facet normal -0.944765 0.200652 -0.259147 + outer loop + vertex -896.522 388.308 291.51 + vertex -894.113 395.184 288.05 + vertex -895.731 387.579 288.06 + endloop + endfacet + facet normal -0.948799 0.20153 -0.243242 + outer loop + vertex -894.113 395.184 288.05 + vertex -892.969 395.14 283.55 + vertex -895.731 387.579 288.06 + endloop + endfacet + facet normal -0.944729 0.220752 -0.242395 + outer loop + vertex -894.113 395.184 288.05 + vertex -891.269 402.413 283.55 + vertex -892.969 395.14 283.55 + endloop + endfacet + facet normal -0.946367 0.221135 -0.23556 + outer loop + vertex -891.269 402.413 283.55 + vertex -889.799 402.648 277.866 + vertex -892.969 395.14 283.55 + endloop + endfacet + facet normal -0.946462 0.222286 -0.234092 + outer loop + vertex -892.969 395.14 283.55 + vertex -889.799 402.648 277.866 + vertex -891.467 395.553 277.873 + endloop + endfacet + facet normal -0.94775 0.222594 -0.228522 + outer loop + vertex -889.799 402.648 277.866 + vertex -888.151 402.955 271.33 + vertex -891.467 395.553 277.873 + endloop + endfacet + facet normal -0.943556 0.241596 -0.226571 + outer loop + vertex -889.799 402.648 277.866 + vertex -886.376 409.897 271.338 + vertex -888.151 402.955 271.33 + endloop + endfacet + facet normal -0.945261 0.242024 -0.218876 + outer loop + vertex -886.376 409.897 271.338 + vertex -884.721 410.012 264.319 + vertex -888.151 402.955 271.33 + endloop + endfacet + facet normal -0.94525 0.242513 -0.218378 + outer loop + vertex -888.151 402.955 271.33 + vertex -884.721 410.012 264.319 + vertex -886.474 403.166 264.305 + endloop + endfacet + facet normal -0.947466 0.24306 -0.207919 + outer loop + vertex -884.721 410.012 264.319 + vertex -883.115 410.058 257.056 + vertex -886.474 403.166 264.305 + endloop + endfacet + facet normal -0.943277 0.259665 -0.206886 + outer loop + vertex -884.721 410.012 264.319 + vertex -881.263 416.793 257.062 + vertex -883.115 410.058 257.056 + endloop + endfacet + facet normal -0.945773 0.26034 -0.194259 + outer loop + vertex -881.263 416.793 257.062 + vertex -879.755 416.735 249.646 + vertex -883.115 410.058 257.056 + endloop + endfacet + facet normal -0.945746 0.260668 -0.193951 + outer loop + vertex -883.115 410.058 257.056 + vertex -879.755 416.735 249.646 + vertex -881.586 410.096 249.648 + endloop + endfacet + facet normal -0.94998 0.244024 -0.19491 + outer loop + vertex -883.115 410.058 257.056 + vertex -881.586 410.096 249.648 + vertex -884.848 403.3 257.039 + endloop + endfacet + facet normal -0.948298 0.261375 -0.180041 + outer loop + vertex -879.755 416.735 249.646 + vertex -878.335 416.702 242.116 + vertex -881.586 410.096 249.648 + endloop + endfacet + facet normal -0.94826 0.261747 -0.179698 + outer loop + vertex -881.586 410.096 249.648 + vertex -878.335 416.702 242.116 + vertex -880.143 410.157 242.124 + endloop + endfacet + facet normal -0.952521 0.24509 -0.180651 + outer loop + vertex -881.586 410.096 249.648 + vertex -880.143 410.157 242.124 + vertex -883.298 403.429 249.63 + endloop + endfacet + facet normal -0.950787 0.262465 -0.164673 + outer loop + vertex -878.335 416.702 242.116 + vertex -877.018 416.686 234.488 + vertex -880.143 410.157 242.124 + endloop + endfacet + facet normal -0.950751 0.262759 -0.164407 + outer loop + vertex -880.143 410.157 242.124 + vertex -877.018 416.686 234.488 + vertex -878.804 410.234 234.506 + endloop + endfacet + facet normal -0.954987 0.246314 -0.165317 + outer loop + vertex -880.143 410.157 242.124 + vertex -878.804 410.234 234.506 + vertex -881.836 403.581 242.106 + endloop + endfacet + facet normal -0.953229 0.263492 -0.148078 + outer loop + vertex -877.018 416.686 234.488 + vertex -875.823 416.68 226.788 + vertex -878.804 410.234 234.506 + endloop + endfacet + facet normal -0.953179 0.263849 -0.14776 + outer loop + vertex -878.804 410.234 234.506 + vertex -875.823 416.68 226.788 + vertex -877.591 410.308 226.811 + endloop + endfacet + facet normal -0.957399 0.247611 -0.14858 + outer loop + vertex -878.804 410.234 234.506 + vertex -877.591 410.308 226.811 + vertex -880.481 403.741 234.487 + endloop + endfacet + facet normal -0.955575 0.264577 -0.129905 + outer loop + vertex -875.823 416.68 226.788 + vertex -874.769 416.675 219.019 + vertex -877.591 410.308 226.811 + endloop + endfacet + facet normal -0.955514 0.264965 -0.129565 + outer loop + vertex -877.591 410.308 226.811 + vertex -874.769 416.675 219.019 + vertex -876.521 410.368 219.044 + endloop + endfacet + facet normal -0.959739 0.248858 -0.130272 + outer loop + vertex -877.591 410.308 226.811 + vertex -876.521 410.368 219.044 + vertex -879.254 403.884 226.79 + endloop + endfacet + facet normal -0.95772 0.265655 -0.110456 + outer loop + vertex -874.769 416.675 219.019 + vertex -873.866 416.669 211.176 + vertex -876.521 410.368 219.044 + endloop + endfacet + facet normal -0.957649 0.26605 -0.110116 + outer loop + vertex -876.521 410.368 219.044 + vertex -873.866 416.669 211.176 + vertex -875.606 410.415 211.202 + endloop + endfacet + facet normal -0.961884 0.250046 -0.110706 + outer loop + vertex -876.521 410.368 219.044 + vertex -875.606 410.415 211.202 + vertex -878.173 404.006 219.023 + endloop + endfacet + facet normal -0.959544 0.266659 -0.0903819 + outer loop + vertex -873.866 416.669 211.176 + vertex -873.122 416.662 203.255 + vertex -875.606 410.415 211.202 + endloop + endfacet + facet normal -0.959481 0.266974 -0.0901152 + outer loop + vertex -875.606 410.415 211.202 + vertex -873.122 416.662 203.255 + vertex -874.852 410.451 203.281 + endloop + endfacet + facet normal -0.963718 0.251078 -0.0905912 + outer loop + vertex -875.606 410.415 211.202 + vertex -874.852 410.451 203.281 + vertex -877.248 404.106 211.179 + endloop + endfacet + facet normal -0.960973 0.267471 -0.070644 + outer loop + vertex -873.122 416.662 203.255 + vertex -872.537 416.655 195.278 + vertex -874.852 410.451 203.281 + endloop + endfacet + facet normal -0.960923 0.267702 -0.07045 + outer loop + vertex -874.852 410.451 203.281 + vertex -872.537 416.655 195.278 + vertex -874.26 410.479 195.303 + endloop + endfacet + facet normal -0.965178 0.251823 -0.0708218 + outer loop + vertex -874.852 410.451 203.281 + vertex -874.26 410.479 195.303 + vertex -876.485 404.187 203.258 + endloop + endfacet + facet normal -0.962004 0.268079 -0.0517873 + outer loop + vertex -872.537 416.655 195.278 + vertex -872.109 416.65 187.29 + vertex -874.26 410.479 195.303 + endloop + endfacet + facet normal -0.961951 0.268306 -0.0515979 + outer loop + vertex -874.26 410.479 195.303 + vertex -872.109 416.65 187.29 + vertex -873.826 410.499 187.314 + endloop + endfacet + facet normal -0.966213 0.252471 -0.0518694 + outer loop + vertex -874.26 410.479 195.303 + vertex -873.826 410.499 187.314 + vertex -875.886 404.25 195.279 + endloop + endfacet + facet normal -0.962665 0.268573 -0.0338223 + outer loop + vertex -872.109 416.65 187.29 + vertex -871.83 416.649 179.347 + vertex -873.826 410.499 187.314 + endloop + endfacet + facet normal -0.962598 0.268844 -0.0335961 + outer loop + vertex -873.826 410.499 187.314 + vertex -871.83 416.649 179.347 + vertex -873.545 410.512 179.367 + endloop + endfacet + facet normal -0.958512 0.283055 -0.0336793 + outer loop + vertex -872.109 416.65 187.29 + vertex -870.038 422.707 179.254 + vertex -871.83 416.649 179.347 + endloop + endfacet + facet normal -0.958856 0.283422 -0.0163637 + outer loop + vertex -870.038 422.707 179.254 + vertex -869.903 422.707 171.389 + vertex -871.83 416.649 179.347 + endloop + endfacet + facet normal -0.95885 0.283442 -0.0163469 + outer loop + vertex -871.83 416.649 179.347 + vertex -869.903 422.707 171.389 + vertex -871.695 416.651 171.475 + endloop + endfacet + facet normal -0.954085 0.299092 -0.0162819 + outer loop + vertex -870.038 422.707 179.254 + vertex -868.033 428.668 171.293 + vertex -869.903 422.707 171.389 + endloop + endfacet + facet normal -0.954131 0.299387 0.00111106 + outer loop + vertex -868.033 428.668 171.293 + vertex -868.033 428.699 163.486 + vertex -869.903 422.707 171.389 + endloop + endfacet + facet normal -0.954292 0.298875 0.000684816 + outer loop + vertex -869.903 422.707 171.389 + vertex -868.033 428.699 163.486 + vertex -869.903 422.728 163.579 + endloop + endfacet + facet normal -0.947523 0.319687 0.0011903 + outer loop + vertex -868.033 428.668 171.293 + vertex -866.045 434.589 163.563 + vertex -868.033 428.699 163.486 + endloop + endfacet + facet normal -0.947423 0.319417 0.0190457 + outer loop + vertex -866.045 434.589 163.563 + vertex -866.172 434.68 155.73 + vertex -868.033 428.699 163.486 + endloop + endfacet + facet normal -0.947795 0.318362 0.0181429 + outer loop + vertex -868.033 428.699 163.486 + vertex -866.172 434.68 155.73 + vertex -868.16 428.765 155.678 + endloop + endfacet + facet normal -0.937854 0.346499 0.0192057 + outer loop + vertex -866.045 434.589 163.563 + vertex -863.999 440.537 156.173 + vertex -866.172 434.68 155.73 + endloop + endfacet + facet normal -0.93782 0.345133 0.0371106 + outer loop + vertex -863.999 440.537 156.173 + vertex -864.247 440.721 148.198 + vertex -866.172 434.68 155.73 + endloop + endfacet + facet normal -0.938189 0.344217 0.0362814 + outer loop + vertex -866.172 434.68 155.73 + vertex -864.247 440.721 148.198 + vertex -866.429 434.81 147.836 + endloop + endfacet + facet normal -0.924712 0.378817 0.0374793 + outer loop + vertex -863.999 440.537 156.173 + vertex -861.842 446.504 149.078 + vertex -864.247 440.721 148.198 + endloop + endfacet + facet normal -0.924886 0.376584 0.0526391 + outer loop + vertex -861.842 446.504 149.078 + vertex -862.153 446.888 140.869 + vertex -864.247 440.721 148.198 + endloop + endfacet + facet normal -0.924209 0.378042 0.0540601 + outer loop + vertex -864.247 440.721 148.198 + vertex -862.153 446.888 140.869 + vertex -864.651 440.885 140.151 + endloop + endfacet + facet normal -0.924524 0.379236 0.0378892 + outer loop + vertex -861.604 446.286 157.077 + vertex -861.842 446.504 149.078 + vertex -863.999 440.537 156.173 + endloop + endfacet + facet normal -0.923998 0.381896 0.0195875 + outer loop + vertex -863.881 440.42 164.019 + vertex -861.604 446.286 157.077 + vertex -863.999 440.537 156.173 + endloop + endfacet + facet normal -0.92465 0.380389 0.0180999 + outer loop + vertex -861.508 446.147 164.868 + vertex -861.604 446.286 157.077 + vertex -863.881 440.42 164.019 + endloop + endfacet + facet normal -0.923914 0.382598 0.00114589 + outer loop + vertex -863.893 440.368 171.819 + vertex -861.508 446.147 164.868 + vertex -863.881 440.42 164.019 + endloop + endfacet + facet normal -0.937813 0.34714 0.000890951 + outer loop + vertex -863.893 440.368 171.819 + vertex -863.881 440.42 164.019 + vertex -866.048 434.548 171.373 + endloop + endfacet + facet normal -0.937271 0.348233 -0.01601 + outer loop + vertex -866.181 434.55 179.235 + vertex -863.893 440.368 171.819 + vertex -866.048 434.548 171.373 + endloop + endfacet + facet normal -0.947319 0.319882 -0.0161708 + outer loop + vertex -866.181 434.55 179.235 + vertex -866.048 434.548 171.373 + vertex -868.166 428.669 179.16 + endloop + endfacet + facet normal -0.94685 0.319942 -0.0333452 + outer loop + vertex -868.436 428.697 187.099 + vertex -866.181 434.55 179.235 + vertex -868.166 428.669 179.16 + endloop + endfacet + facet normal -0.953697 0.298897 -0.0335041 + outer loop + vertex -868.436 428.697 187.099 + vertex -868.166 428.669 179.16 + vertex -870.311 422.724 187.195 + endloop + endfacet + facet normal -0.953053 0.298405 -0.0514245 + outer loop + vertex -870.733 422.752 195.181 + vertex -868.436 428.697 187.099 + vertex -870.311 422.724 187.195 + endloop + endfacet + facet normal -0.95785 0.282592 -0.0516222 + outer loop + vertex -870.733 422.752 195.181 + vertex -870.311 422.724 187.195 + vertex -872.537 416.655 195.278 + endloop + endfacet + facet normal -0.953087 0.298277 -0.0515285 + outer loop + vertex -868.852 428.747 195.083 + vertex -868.436 428.697 187.099 + vertex -870.733 422.752 195.181 + endloop + endfacet + facet normal -0.952086 0.297658 -0.0702208 + outer loop + vertex -871.309 422.791 203.157 + vertex -868.852 428.747 195.083 + vertex -870.733 422.752 195.181 + endloop + endfacet + facet normal -0.956872 0.281828 -0.0704883 + outer loop + vertex -871.309 422.791 203.157 + vertex -870.733 422.752 195.181 + vertex -873.122 416.662 203.255 + endloop + endfacet + facet normal -0.952132 0.297477 -0.0703689 + outer loop + vertex -869.418 428.822 203.06 + vertex -868.852 428.747 195.083 + vertex -871.309 422.791 203.157 + endloop + endfacet + facet normal -0.950725 0.296722 -0.0898753 + outer loop + vertex -872.042 422.842 211.078 + vertex -869.418 428.822 203.06 + vertex -871.309 422.791 203.157 + endloop + endfacet + facet normal -0.955503 0.280848 -0.090216 + outer loop + vertex -872.042 422.842 211.078 + vertex -871.309 422.791 203.157 + vertex -873.866 416.669 211.176 + endloop + endfacet + facet normal -0.950743 0.296645 -0.0899381 + outer loop + vertex -870.135 428.928 210.983 + vertex -869.418 428.822 203.06 + vertex -872.042 422.842 211.078 + endloop + endfacet + facet normal -0.948945 0.295776 -0.109632 + outer loop + vertex -872.928 422.909 218.925 + vertex -870.135 428.928 210.983 + vertex -872.042 422.842 211.078 + endloop + endfacet + facet normal -0.953686 0.279959 -0.110032 + outer loop + vertex -872.928 422.909 218.925 + vertex -872.042 422.842 211.078 + vertex -874.769 416.675 219.019 + endloop + endfacet + facet normal -0.948938 0.295811 -0.109603 + outer loop + vertex -870.996 429.072 218.833 + vertex -870.135 428.928 210.983 + vertex -872.928 422.909 218.925 + endloop + endfacet + facet normal -0.946816 0.294857 -0.128838 + outer loop + vertex -873.96 422.993 226.702 + vertex -870.996 429.072 218.833 + vertex -872.928 422.909 218.925 + endloop + endfacet + facet normal -0.951513 0.279117 -0.129291 + outer loop + vertex -873.96 422.993 226.702 + vertex -872.928 422.909 218.925 + vertex -875.823 416.68 226.788 + endloop + endfacet + facet normal -0.946841 0.29473 -0.128946 + outer loop + vertex -872.002 429.245 226.611 + vertex -870.996 429.072 218.833 + vertex -873.96 422.993 226.702 + endloop + endfacet + facet normal -0.94453 0.293742 -0.146897 + outer loop + vertex -875.129 423.093 234.415 + vertex -872.002 429.245 226.611 + vertex -873.96 422.993 226.702 + endloop + endfacet + facet normal -0.949134 0.278244 -0.147393 + outer loop + vertex -875.129 423.093 234.415 + vertex -873.96 422.993 226.702 + vertex -877.018 416.686 234.488 + endloop + endfacet + facet normal -0.944674 0.292924 -0.147599 + outer loop + vertex -873.148 429.433 234.325 + vertex -872.002 429.245 226.611 + vertex -875.129 423.093 234.415 + endloop + endfacet + facet normal -0.942308 0.291956 -0.163762 + outer loop + vertex -876.422 423.204 242.056 + vertex -873.148 429.433 234.325 + vertex -875.129 423.093 234.415 + endloop + endfacet + facet normal -0.946721 0.276996 -0.164291 + outer loop + vertex -876.422 423.204 242.056 + vertex -875.129 423.093 234.415 + vertex -878.335 416.702 242.116 + endloop + endfacet + facet normal -0.94248 0.290862 -0.164716 + outer loop + vertex -874.421 429.644 241.98 + vertex -873.148 429.433 234.325 + vertex -876.422 423.204 242.056 + endloop + endfacet + facet normal -0.940111 0.289954 -0.179214 + outer loop + vertex -877.819 423.343 249.611 + vertex -874.421 429.644 241.98 + vertex -876.422 423.204 242.056 + endloop + endfacet + facet normal -0.944291 0.275704 -0.179726 + outer loop + vertex -877.819 423.343 249.611 + vertex -876.422 423.204 242.056 + vertex -879.755 416.735 249.646 + endloop + endfacet + facet normal -0.940265 0.288843 -0.1802 + outer loop + vertex -875.796 429.893 249.554 + vertex -874.421 429.644 241.98 + vertex -877.819 423.343 249.611 + endloop + endfacet + facet normal -0.937888 0.287993 -0.19346 + outer loop + vertex -879.303 423.509 257.048 + vertex -875.796 429.893 249.554 + vertex -877.819 423.343 249.611 + endloop + endfacet + facet normal -0.941831 0.274483 -0.193945 + outer loop + vertex -879.303 423.509 257.048 + vertex -877.819 423.343 249.611 + vertex -881.263 416.793 257.062 + endloop + endfacet + facet normal -0.93939 0.273745 -0.206422 + outer loop + vertex -882.845 416.845 264.33 + vertex -879.303 423.509 257.048 + vertex -881.263 416.793 257.062 + endloop + endfacet + facet normal -0.939429 0.27327 -0.206876 + outer loop + vertex -880.856 423.679 264.329 + vertex -879.303 423.509 257.048 + vertex -882.845 416.845 264.33 + endloop + endfacet + facet normal -0.937279 0.272642 -0.217197 + outer loop + vertex -884.471 416.842 271.347 + vertex -880.856 423.679 264.329 + vertex -882.845 416.845 264.33 + endloop + endfacet + facet normal -0.941119 0.258321 -0.218093 + outer loop + vertex -884.471 416.842 271.347 + vertex -882.845 416.845 264.33 + vertex -886.376 409.897 271.338 + endloop + endfacet + facet normal -0.939361 0.25785 -0.226084 + outer loop + vertex -887.999 409.714 277.875 + vertex -884.471 416.842 271.347 + vertex -886.376 409.897 271.338 + endloop + endfacet + facet normal -0.93937 0.256923 -0.227101 + outer loop + vertex -886.07 416.782 277.891 + vertex -884.471 416.842 271.347 + vertex -887.999 409.714 277.875 + endloop + endfacet + facet normal -0.937948 0.256549 -0.233315 + outer loop + vertex -889.441 409.609 283.555 + vertex -886.07 416.782 277.891 + vertex -887.999 409.714 277.875 + endloop + endfacet + facet normal -0.942103 0.239509 -0.234685 + outer loop + vertex -889.441 409.609 283.555 + vertex -887.999 409.714 277.875 + vertex -891.269 402.413 283.55 + endloop + endfacet + facet normal -0.940388 0.239078 -0.241892 + outer loop + vertex -892.36 402.66 288.036 + vertex -889.441 409.609 283.555 + vertex -891.269 402.413 283.55 + endloop + endfacet + facet normal -0.940404 0.239209 -0.2417 + outer loop + vertex -890.527 409.882 288.051 + vertex -889.441 409.609 283.555 + vertex -892.36 402.66 288.036 + endloop + endfacet + facet normal -0.937257 0.238436 -0.254357 + outer loop + vertex -892.938 403.909 291.336 + vertex -890.527 409.882 288.051 + vertex -892.36 402.66 288.036 + endloop + endfacet + facet normal -0.94215 0.223692 -0.249631 + outer loop + vertex -892.938 403.909 291.336 + vertex -892.36 402.66 288.036 + vertex -894.715 396.409 291.323 + endloop + endfacet + facet normal -0.93643 0.222374 -0.271382 + outer loop + vertex -892.938 403.909 291.336 + vertex -894.715 396.409 291.323 + vertex -894.411 399.695 292.965 + endloop + endfacet + facet normal -0.937352 0.224677 -0.266256 + outer loop + vertex -894.411 399.695 292.965 + vertex -893.534 403.386 292.993 + vertex -892.938 403.909 291.336 + endloop + endfacet + facet normal -0.93551 0.237529 -0.261535 + outer loop + vertex -893.534 403.386 292.993 + vertex -892.573 407.136 292.961 + vertex -892.938 403.909 291.336 + endloop + endfacet + facet normal -0.933385 0.239965 -0.26685 + outer loop + vertex -891.129 410.903 291.299 + vertex -892.938 403.909 291.336 + vertex -892.573 407.136 292.961 + endloop + endfacet + facet normal -0.93355 0.240493 -0.265795 + outer loop + vertex -892.573 407.136 292.961 + vertex -891.719 410.399 292.913 + vertex -891.129 410.903 291.299 + endloop + endfacet + facet normal -0.931926 0.250722 -0.262015 + outer loop + vertex -891.719 410.399 292.913 + vertex -890.947 413.049 292.703 + vertex -891.129 410.903 291.299 + endloop + endfacet + facet normal -0.929032 0.254663 -0.268415 + outer loop + vertex -889.274 417.667 291.294 + vertex -891.129 410.903 291.299 + vertex -890.947 413.049 292.703 + endloop + endfacet + facet normal -0.930334 0.257309 -0.261288 + outer loop + vertex -890.947 413.049 292.703 + vertex -890.187 416.215 293.114 + vertex -889.274 417.667 291.294 + endloop + endfacet + facet normal -0.930158 0.260901 -0.258334 + outer loop + vertex -890.187 416.215 293.114 + vertex -889.013 420.028 292.741 + vertex -889.274 417.667 291.294 + endloop + endfacet + facet normal -0.926386 0.265706 -0.26685 + outer loop + vertex -887.186 425.111 291.458 + vertex -889.274 417.667 291.294 + vertex -889.013 420.028 292.741 + endloop + endfacet + facet normal -0.926847 0.266471 -0.264477 + outer loop + vertex -889.013 420.028 292.741 + vertex -888.228 423.18 293.163 + vertex -887.186 425.111 291.458 + endloop + endfacet + facet normal -0.926943 0.270082 -0.260445 + outer loop + vertex -888.228 423.18 293.163 + vertex -887.415 425.781 292.97 + vertex -887.186 425.111 291.458 + endloop + endfacet + facet normal -0.92443 0.276315 -0.26283 + outer loop + vertex -887.415 425.781 292.97 + vertex -886.26 429.553 292.873 + vertex -887.186 425.111 291.458 + endloop + endfacet + facet normal -0.92584 0.275343 -0.258856 + outer loop + vertex -884.789 432.73 290.99 + vertex -887.186 425.111 291.458 + vertex -886.26 429.553 292.873 + endloop + endfacet + facet normal -0.926553 0.280632 -0.250489 + outer loop + vertex -886.26 429.553 292.873 + vertex -884.678 434.6 292.673 + vertex -884.789 432.73 290.99 + endloop + endfacet + facet normal -0.923488 0.285564 -0.256171 + outer loop + vertex -882.71 439.742 291.313 + vertex -884.789 432.73 290.99 + vertex -884.678 434.6 292.673 + endloop + endfacet + facet normal -0.92431 0.28714 -0.251401 + outer loop + vertex -884.678 434.6 292.673 + vertex -883.598 438.587 293.258 + vertex -882.71 439.742 291.313 + endloop + endfacet + facet normal -0.923467 0.293289 -0.247365 + outer loop + vertex -883.598 438.587 293.258 + vertex -881.92 443.658 293.006 + vertex -882.71 439.742 291.313 + endloop + endfacet + facet normal -0.917524 0.298668 -0.262577 + outer loop + vertex -880.181 447.476 291.272 + vertex -882.71 439.742 291.313 + vertex -881.92 443.658 293.006 + endloop + endfacet + facet normal -0.916688 0.295239 -0.269289 + outer loop + vertex -881.92 443.658 293.006 + vertex -880.701 447.337 292.889 + vertex -880.181 447.476 291.272 + endloop + endfacet + facet normal -0.912969 0.308593 -0.266943 + outer loop + vertex -880.701 447.337 292.889 + vertex -879.472 450.824 292.716 + vertex -880.181 447.476 291.272 + endloop + endfacet + facet normal -0.90192 0.317434 -0.292875 + outer loop + vertex -877.683 454.466 291.154 + vertex -880.181 447.476 291.272 + vertex -879.472 450.824 292.716 + endloop + endfacet + facet normal -0.899586 0.30992 -0.307725 + outer loop + vertex -879.472 450.824 292.716 + vertex -878.335 454.041 292.632 + vertex -877.683 454.466 291.154 + endloop + endfacet + facet normal -0.894838 0.330912 -0.299602 + outer loop + vertex -878.335 454.041 292.632 + vertex -877.277 457.104 292.855 + vertex -877.683 454.466 291.154 + endloop + endfacet + facet normal -0.907576 0.332195 -0.256811 + outer loop + vertex -877.277 457.104 292.855 + vertex -878.335 454.041 292.632 + vertex -878.663 454.021 293.767 + endloop + endfacet + facet normal -0.90299 0.321924 -0.28456 + outer loop + vertex -877.277 457.104 292.855 + vertex -878.663 454.021 293.767 + vertex -877.404 458.556 294.902 + endloop + endfacet + facet normal -0.907895 0.319878 -0.270934 + outer loop + vertex -878.663 454.021 293.767 + vertex -879.131 454.674 296.104 + vertex -877.404 458.556 294.902 + endloop + endfacet + facet normal -0.904883 0.313159 -0.288304 + outer loop + vertex -878.036 459.627 298.048 + vertex -877.404 458.556 294.902 + vertex -879.131 454.674 296.104 + endloop + endfacet + facet normal -0.904933 0.313123 -0.288183 + outer loop + vertex -879.131 454.674 296.104 + vertex -879.795 456.545 300.224 + vertex -878.036 459.627 298.048 + endloop + endfacet + facet normal -0.904477 0.308047 -0.295005 + outer loop + vertex -878.594 461.393 301.604 + vertex -878.036 459.627 298.048 + vertex -879.795 456.545 300.224 + endloop + endfacet + facet normal -0.90665 0.306986 -0.289386 + outer loop + vertex -879.826 461.594 305.678 + vertex -878.594 461.393 301.604 + vertex -879.795 456.545 300.224 + endloop + endfacet + facet normal -0.909588 0.302302 -0.285066 + outer loop + vertex -879.795 456.545 300.224 + vertex -881.101 456.166 303.99 + vertex -879.826 461.594 305.678 + endloop + endfacet + facet normal -0.919094 0.296569 -0.259449 + outer loop + vertex -881.101 456.166 303.99 + vertex -881.643 459.01 309.158 + vertex -879.826 461.594 305.678 + endloop + endfacet + facet normal -0.919425 0.293111 -0.26219 + outer loop + vertex -880.458 464.217 310.826 + vertex -879.826 461.594 305.678 + vertex -881.643 459.01 309.158 + endloop + endfacet + facet normal -0.933702 0.259423 -0.24678 + outer loop + vertex -880.458 464.217 310.826 + vertex -879.743 465.301 309.258 + vertex -879.826 461.594 305.678 + endloop + endfacet + facet normal -0.910813 0.297247 -0.286469 + outer loop + vertex -879.826 461.594 305.678 + vertex -879.743 465.301 309.258 + vertex -878.718 463.765 304.406 + endloop + endfacet + facet normal -0.918138 0.298621 -0.260478 + outer loop + vertex -883.052 450.829 304.748 + vertex -881.643 459.01 309.158 + vertex -881.101 456.166 303.99 + endloop + endfacet + facet normal -0.915374 0.295816 -0.273099 + outer loop + vertex -883.052 450.829 304.748 + vertex -881.101 456.166 303.99 + vertex -882.098 449.79 300.424 + endloop + endfacet + facet normal -0.916172 0.293654 -0.272756 + outer loop + vertex -884.514 442.484 300.673 + vertex -883.052 450.829 304.748 + vertex -882.098 449.79 300.424 + endloop + endfacet + facet normal -0.915882 0.293521 -0.273872 + outer loop + vertex -884.514 442.484 300.673 + vertex -882.098 449.79 300.424 + vertex -883.598 442.049 297.145 + endloop + endfacet + facet normal -0.917985 0.287109 -0.273627 + outer loop + vertex -886.003 434.383 297.167 + vertex -884.514 442.484 300.673 + vertex -883.598 442.049 297.145 + endloop + endfacet + facet normal -0.920707 0.287992 -0.263363 + outer loop + vertex -886.003 434.383 297.167 + vertex -883.598 442.049 297.145 + vertex -885.017 435.072 294.474 + endloop + endfacet + facet normal -0.922453 0.279762 -0.266108 + outer loop + vertex -887.348 427.353 294.439 + vertex -886.003 434.383 297.167 + vertex -885.017 435.072 294.474 + endloop + endfacet + facet normal -0.926912 0.281029 -0.248709 + outer loop + vertex -887.348 427.353 294.439 + vertex -885.017 435.072 294.474 + vertex -886.26 429.553 292.873 + endloop + endfacet + facet normal -0.924933 0.277702 -0.259578 + outer loop + vertex -888.293 426.734 297.146 + vertex -886.003 434.383 297.167 + vertex -887.348 427.353 294.439 + endloop + endfacet + facet normal -0.926745 0.269082 -0.26218 + outer loop + vertex -889.4 420.267 294.421 + vertex -888.293 426.734 297.146 + vertex -887.348 427.353 294.439 + endloop + endfacet + facet normal -0.931792 0.270494 -0.242068 + outer loop + vertex -889.4 420.267 294.421 + vertex -887.348 427.353 294.439 + vertex -888.228 423.18 293.163 + endloop + endfacet + facet normal -0.929409 0.266596 -0.255197 + outer loop + vertex -890.469 419.117 297.113 + vertex -888.293 426.734 297.146 + vertex -889.4 420.267 294.421 + endloop + endfacet + facet normal -0.930773 0.257331 -0.259696 + outer loop + vertex -891.549 412.333 294.26 + vertex -890.469 419.117 297.113 + vertex -889.4 420.267 294.421 + endloop + endfacet + facet normal -0.936352 0.258394 -0.237651 + outer loop + vertex -891.549 412.333 294.26 + vertex -889.4 420.267 294.421 + vertex -890.187 416.215 293.114 + endloop + endfacet + facet normal -0.93377 0.254432 -0.251668 + outer loop + vertex -892.576 411.387 297.117 + vertex -890.469 419.117 297.113 + vertex -891.549 412.333 294.26 + endloop + endfacet + facet normal -0.935775 0.241887 -0.256546 + outer loop + vertex -893.618 404.52 294.443 + vertex -892.576 411.387 297.117 + vertex -891.549 412.333 294.26 + endloop + endfacet + facet normal -0.941274 0.243883 -0.233504 + outer loop + vertex -893.618 404.52 294.443 + vertex -891.549 412.333 294.26 + vertex -892.573 407.136 292.961 + endloop + endfacet + facet normal -0.937938 0.239854 -0.250483 + outer loop + vertex -894.579 403.559 297.12 + vertex -892.576 411.387 297.117 + vertex -893.618 404.52 294.443 + endloop + endfacet + facet normal -0.940015 0.224717 -0.256659 + outer loop + vertex -895.483 396.686 294.412 + vertex -894.579 403.559 297.12 + vertex -893.618 404.52 294.443 + endloop + endfacet + facet normal -0.946357 0.226123 -0.230818 + outer loop + vertex -895.483 396.686 294.412 + vertex -893.618 404.52 294.443 + vertex -894.411 399.695 292.965 + endloop + endfacet + facet normal -0.945071 0.22073 -0.241081 + outer loop + vertex -894.411 399.695 292.965 + vertex -895.325 395.77 292.954 + vertex -895.483 396.686 294.412 + endloop + endfacet + facet normal -0.949893 0.207815 -0.233487 + outer loop + vertex -895.325 395.77 292.954 + vertex -896.172 391.874 292.935 + vertex -895.483 396.686 294.412 + endloop + endfacet + facet normal -0.940377 0.20592 -0.270719 + outer loop + vertex -896.172 391.874 292.935 + vertex -895.325 395.77 292.954 + vertex -894.715 396.409 291.323 + endloop + endfacet + facet normal -0.942785 0.221972 -0.248767 + outer loop + vertex -896.468 395.495 297.084 + vertex -894.579 403.559 297.12 + vertex -895.483 396.686 294.412 + endloop + endfacet + facet normal -0.944371 0.205708 -0.256607 + outer loop + vertex -897.252 388.324 294.219 + vertex -896.468 395.495 297.084 + vertex -895.483 396.686 294.412 + endloop + endfacet + facet normal -0.947393 0.202537 -0.247842 + outer loop + vertex -898.234 387.22 297.07 + vertex -896.468 395.495 297.084 + vertex -897.252 388.324 294.219 + endloop + endfacet + facet normal -0.949217 0.182667 -0.256165 + outer loop + vertex -898.845 380.242 294.358 + vertex -898.234 387.22 297.07 + vertex -897.252 388.324 294.219 + endloop + endfacet + facet normal -0.955537 0.184361 -0.230129 + outer loop + vertex -898.845 380.242 294.358 + vertex -897.252 388.324 294.219 + vertex -897.893 383.378 292.922 + endloop + endfacet + facet normal -0.95883 0.181676 -0.218264 + outer loop + vertex -897.281 386.623 292.934 + vertex -897.893 383.378 292.922 + vertex -897.252 388.324 294.219 + endloop + endfacet + facet normal -0.951552 0.180158 -0.249184 + outer loop + vertex -899.812 378.955 297.122 + vertex -898.234 387.22 297.07 + vertex -898.845 380.242 294.358 + endloop + endfacet + facet normal -0.952578 0.159369 -0.259224 + outer loop + vertex -900.188 372.233 294.372 + vertex -899.812 378.955 297.122 + vertex -898.845 380.242 294.358 + endloop + endfacet + facet normal -0.955525 0.155898 -0.250336 + outer loop + vertex -901.149 370.769 297.128 + vertex -899.812 378.955 297.122 + vertex -900.188 372.233 294.372 + endloop + endfacet + facet normal -0.9557 0.132421 -0.262872 + outer loop + vertex -901.28 364.31 294.348 + vertex -901.149 370.769 297.128 + vertex -900.188 372.233 294.372 + endloop + endfacet + facet normal -0.959536 0.127433 -0.251102 + outer loop + vertex -902.225 362.652 297.119 + vertex -901.149 370.769 297.128 + vertex -901.28 364.31 294.348 + endloop + endfacet + facet normal -0.958449 0.0999121 -0.267195 + outer loop + vertex -902.107 356.363 294.346 + vertex -902.225 362.652 297.119 + vertex -901.28 364.31 294.348 + endloop + endfacet + facet normal -0.962207 0.0946202 -0.255352 + outer loop + vertex -903.03 354.429 297.106 + vertex -902.225 362.652 297.119 + vertex -902.107 356.363 294.346 + endloop + endfacet + facet normal -0.958839 0.0619758 -0.277103 + outer loop + vertex -902.641 348.151 294.357 + vertex -903.03 354.429 297.106 + vertex -902.107 356.363 294.346 + endloop + endfacet + facet normal -0.963188 0.0555443 -0.263028 + outer loop + vertex -903.515 345.967 297.096 + vertex -903.03 354.429 297.106 + vertex -902.641 348.151 294.357 + endloop + endfacet + facet normal -0.956968 0.0198511 -0.289512 + outer loop + vertex -902.782 339.214 294.21 + vertex -903.515 345.967 297.096 + vertex -902.641 348.151 294.357 + endloop + endfacet + facet normal -0.96258 0.0112309 -0.270766 + outer loop + vertex -903.616 337.425 297.1 + vertex -903.515 345.967 297.096 + vertex -902.782 339.214 294.21 + endloop + endfacet + facet normal -0.950879 0.0110782 -0.309366 + outer loop + vertex -903.616 337.425 297.1 + vertex -904.77 344.491 300.901 + vertex -903.515 345.967 297.096 + endloop + endfacet + facet normal -0.954416 0.0556684 -0.293241 + outer loop + vertex -904.77 344.491 300.901 + vertex -904.28 352.994 300.918 + vertex -903.515 345.967 297.096 + endloop + endfacet + facet normal -0.952041 0.0555471 -0.300887 + outer loop + vertex -904.77 344.491 300.901 + vertex -905.872 351.55 305.689 + vertex -904.28 352.994 300.918 + endloop + endfacet + facet normal -0.952557 0.0961071 -0.288787 + outer loop + vertex -905.872 351.55 305.689 + vertex -905.022 360.036 305.711 + vertex -904.28 352.994 300.918 + endloop + endfacet + facet normal -0.954148 0.0930292 -0.284511 + outer loop + vertex -904.28 352.994 300.918 + vertex -905.022 360.036 305.711 + vertex -903.464 361.381 300.926 + endloop + endfacet + facet normal -0.955962 0.0931999 -0.2783 + outer loop + vertex -904.28 352.994 300.918 + vertex -903.464 361.381 300.926 + vertex -903.03 354.429 297.106 + endloop + endfacet + facet normal -0.953133 0.126843 -0.274678 + outer loop + vertex -905.022 360.036 305.711 + vertex -903.909 368.433 305.727 + vertex -903.464 361.381 300.926 + endloop + endfacet + facet normal -0.953922 0.125381 -0.272603 + outer loop + vertex -903.464 361.381 300.926 + vertex -903.909 368.433 305.727 + vertex -902.373 369.683 300.928 + endloop + endfacet + facet normal -0.954927 0.125512 -0.268999 + outer loop + vertex -903.464 361.381 300.926 + vertex -902.373 369.683 300.928 + vertex -902.225 362.652 297.119 + endloop + endfacet + facet normal -0.952066 0.15322 -0.264754 + outer loop + vertex -903.909 368.433 305.727 + vertex -902.53 376.933 305.685 + vertex -902.373 369.683 300.928 + endloop + endfacet + facet normal -0.951811 0.153659 -0.265415 + outer loop + vertex -902.373 369.683 300.928 + vertex -902.53 376.933 305.685 + vertex -901.012 378.067 300.899 + endloop + endfacet + facet normal -0.952469 0.153775 -0.262977 + outer loop + vertex -902.373 369.683 300.928 + vertex -901.012 378.067 300.899 + vertex -901.149 370.769 297.128 + endloop + endfacet + facet normal -0.949022 0.181022 -0.258048 + outer loop + vertex -902.53 376.933 305.685 + vertex -900.812 385.85 305.623 + vertex -901.012 378.067 300.899 + endloop + endfacet + facet normal -0.949778 0.179846 -0.256079 + outer loop + vertex -901.012 378.067 300.899 + vertex -900.812 385.85 305.623 + vertex -899.374 386.564 300.79 + endloop + endfacet + facet normal -0.94895 0.179645 -0.259273 + outer loop + vertex -901.012 378.067 300.899 + vertex -899.374 386.564 300.79 + vertex -899.812 378.955 297.122 + endloop + endfacet + facet normal -0.945802 0.206017 -0.251028 + outer loop + vertex -900.812 385.85 305.623 + vertex -898.768 394.622 305.12 + vertex -899.374 386.564 300.79 + endloop + endfacet + facet normal -0.94887 0.201796 -0.242744 + outer loop + vertex -899.374 386.564 300.79 + vertex -898.768 394.622 305.12 + vertex -897.541 395.019 300.653 + endloop + endfacet + facet normal -0.945961 0.200975 -0.254494 + outer loop + vertex -899.374 386.564 300.79 + vertex -897.541 395.019 300.653 + vertex -898.234 387.22 297.07 + endloop + endfacet + facet normal -0.945042 0.22215 -0.239884 + outer loop + vertex -898.768 394.622 305.12 + vertex -896.711 403.196 304.957 + vertex -897.541 395.019 300.653 + endloop + endfacet + facet normal -0.945348 0.221744 -0.239053 + outer loop + vertex -897.541 395.019 300.653 + vertex -896.711 403.196 304.957 + vertex -895.601 403.273 300.639 + endloop + endfacet + facet normal -0.941774 0.22088 -0.253522 + outer loop + vertex -897.541 395.019 300.653 + vertex -895.601 403.273 300.639 + vertex -896.468 395.495 297.084 + endloop + endfacet + facet normal -0.941793 0.237591 -0.237858 + outer loop + vertex -896.711 403.196 304.957 + vertex -894.635 411.395 304.927 + vertex -895.601 403.273 300.639 + endloop + endfacet + facet normal -0.940648 0.23906 -0.240899 + outer loop + vertex -895.601 403.273 300.639 + vertex -894.635 411.395 304.927 + vertex -893.58 411.241 300.655 + endloop + endfacet + facet normal -0.937673 0.23833 -0.252921 + outer loop + vertex -895.601 403.273 300.639 + vertex -893.58 411.241 300.655 + vertex -894.579 403.559 297.12 + endloop + endfacet + facet normal -0.937045 0.253176 -0.240517 + outer loop + vertex -894.635 411.395 304.927 + vertex -892.501 419.333 304.968 + vertex -893.58 411.241 300.655 + endloop + endfacet + facet normal -0.936559 0.253779 -0.241771 + outer loop + vertex -893.58 411.241 300.655 + vertex -892.501 419.333 304.968 + vertex -891.475 419.029 300.674 + endloop + endfacet + facet normal -0.933445 0.252968 -0.254338 + outer loop + vertex -893.58 411.241 300.655 + vertex -891.475 419.029 300.674 + vertex -892.576 411.387 297.117 + endloop + endfacet + facet normal -0.933655 0.26422 -0.241817 + outer loop + vertex -892.501 419.333 304.968 + vertex -890.279 427.233 305.024 + vertex -891.475 419.029 300.674 + endloop + endfacet + facet normal -0.932697 0.265368 -0.244246 + outer loop + vertex -891.475 419.029 300.674 + vertex -890.279 427.233 305.024 + vertex -889.274 426.791 300.705 + endloop + endfacet + facet normal -0.929765 0.264583 -0.255994 + outer loop + vertex -891.475 419.029 300.674 + vertex -889.274 426.791 300.705 + vertex -890.469 419.117 297.113 + endloop + endfacet + facet normal -0.930652 0.272248 -0.244474 + outer loop + vertex -890.279 427.233 305.024 + vertex -887.944 435.252 305.064 + vertex -889.274 426.791 300.705 + endloop + endfacet + facet normal -0.927894 0.275367 -0.251369 + outer loop + vertex -889.274 426.791 300.705 + vertex -887.944 435.252 305.064 + vertex -886.952 434.646 300.735 + endloop + endfacet + facet normal -0.925799 0.27478 -0.259598 + outer loop + vertex -889.274 426.791 300.705 + vertex -886.952 434.646 300.735 + vertex -888.293 426.734 297.146 + endloop + endfacet + facet normal -0.926182 0.280748 -0.25173 + outer loop + vertex -887.944 435.252 305.064 + vertex -885.49 443.305 305.015 + vertex -886.952 434.646 300.735 + endloop + endfacet + facet normal -0.922347 0.284751 -0.261139 + outer loop + vertex -886.952 434.646 300.735 + vertex -885.49 443.305 305.015 + vertex -884.514 442.484 300.673 + endloop + endfacet + facet normal -0.93098 0.282333 -0.231441 + outer loop + vertex -887.944 435.252 305.064 + vertex -886.407 444.168 309.755 + vertex -885.49 443.305 305.015 + endloop + endfacet + facet normal -0.930377 0.284141 -0.231654 + outer loop + vertex -886.407 444.168 309.755 + vertex -883.977 451.917 309.501 + vertex -885.49 443.305 305.015 + endloop + endfacet + facet normal -0.924536 0.290767 -0.246347 + outer loop + vertex -885.49 443.305 305.015 + vertex -883.977 451.917 309.501 + vertex -883.052 450.829 304.748 + endloop + endfacet + facet normal -0.936636 0.287121 -0.200683 + outer loop + vertex -886.407 444.168 309.755 + vertex -884.702 452.888 314.275 + vertex -883.977 451.917 309.501 + endloop + endfacet + facet normal -0.937759 0.283792 -0.200177 + outer loop + vertex -884.702 452.888 314.275 + vertex -882.8 458.622 313.494 + vertex -883.977 451.917 309.501 + endloop + endfacet + facet normal -0.929401 0.295108 -0.221642 + outer loop + vertex -883.977 451.917 309.501 + vertex -882.8 458.622 313.494 + vertex -881.643 459.01 309.158 + endloop + endfacet + facet normal -0.929227 0.295732 -0.221539 + outer loop + vertex -881.643 459.01 309.158 + vertex -882.8 458.622 313.494 + vertex -881.354 464.385 315.121 + endloop + endfacet + facet normal -0.937724 0.279406 -0.206411 + outer loop + vertex -881.354 464.385 315.121 + vertex -880.458 464.217 310.826 + vertex -881.643 459.01 309.158 + endloop + endfacet + facet normal -0.9466 0.247185 -0.206997 + outer loop + vertex -881.354 464.385 315.121 + vertex -880.47 466.897 314.079 + vertex -880.458 464.217 310.826 + endloop + endfacet + facet normal -0.931817 0.278482 -0.232733 + outer loop + vertex -880.458 464.217 310.826 + vertex -880.47 466.897 314.079 + vertex -879.743 465.301 309.258 + endloop + endfacet + facet normal -0.942102 0.279891 -0.184674 + outer loop + vertex -887.116 444.915 314.509 + vertex -884.702 452.888 314.275 + vertex -886.407 444.168 309.755 + endloop + endfacet + facet normal -0.942144 0.27976 -0.18466 + outer loop + vertex -888.861 435.92 309.785 + vertex -887.116 444.915 314.509 + vertex -886.407 444.168 309.755 + endloop + endfacet + facet normal -0.945324 0.275259 -0.174914 + outer loop + vertex -889.563 436.525 314.527 + vertex -887.116 444.915 314.509 + vertex -888.861 435.92 309.785 + endloop + endfacet + facet normal -0.945919 0.27331 -0.174754 + outer loop + vertex -891.211 427.748 309.722 + vertex -889.563 436.525 314.527 + vertex -888.861 435.92 309.785 + endloop + endfacet + facet normal -0.947534 0.270867 -0.169737 + outer loop + vertex -891.917 428.246 314.454 + vertex -889.563 436.525 314.527 + vertex -891.211 427.748 309.722 + endloop + endfacet + facet normal -0.949041 0.26574 -0.169422 + outer loop + vertex -893.449 419.713 309.654 + vertex -891.917 428.246 314.454 + vertex -891.211 427.748 309.722 + endloop + endfacet + facet normal -0.950043 0.264146 -0.166267 + outer loop + vertex -894.167 420.104 314.382 + vertex -891.917 428.246 314.454 + vertex -893.449 419.713 309.654 + endloop + endfacet + facet normal -0.952662 0.254784 -0.165891 + outer loop + vertex -895.617 411.592 309.633 + vertex -894.167 420.104 314.382 + vertex -893.449 419.713 309.654 + endloop + endfacet + facet normal -0.953488 0.253426 -0.163204 + outer loop + vertex -896.355 411.869 314.377 + vertex -894.167 420.104 314.382 + vertex -895.617 411.592 309.633 + endloop + endfacet + facet normal -0.956524 0.241854 -0.162999 + outer loop + vertex -897.773 403.126 309.723 + vertex -896.355 411.869 314.377 + vertex -895.617 411.592 309.633 + endloop + endfacet + facet normal -0.956884 0.241257 -0.161768 + outer loop + vertex -898.503 403.449 314.523 + vertex -896.355 411.869 314.377 + vertex -897.773 403.126 309.723 + endloop + endfacet + facet normal -0.959328 0.231541 -0.161486 + outer loop + vertex -900.025 394.027 310.055 + vertex -898.503 403.449 314.523 + vertex -897.773 403.126 309.723 + endloop + endfacet + facet normal -0.959387 0.231448 -0.16127 + outer loop + vertex -900.481 395.559 314.968 + vertex -898.503 403.449 314.523 + vertex -900.025 394.027 310.055 + endloop + endfacet + facet normal -0.958594 0.234175 -0.162047 + outer loop + vertex -900.481 395.559 314.968 + vertex -900.025 394.027 310.055 + vertex -901.665 388.472 311.73 + endloop + endfacet + facet normal -0.965995 0.221964 -0.132609 + outer loop + vertex -902.175 388.38 315.29 + vertex -900.481 395.559 314.968 + vertex -901.665 388.472 311.73 + endloop + endfacet + facet normal -0.968578 0.209976 -0.133288 + outer loop + vertex -902.913 382.944 312.087 + vertex -902.175 388.38 315.29 + vertex -901.665 388.472 311.73 + endloop + endfacet + facet normal -0.959422 0.203948 -0.194717 + outer loop + vertex -902.913 382.944 312.087 + vertex -901.665 388.472 311.73 + vertex -902.182 383.357 308.921 + endloop + endfacet + facet normal -0.961502 0.191809 -0.196782 + outer loop + vertex -903.185 378.986 309.558 + vertex -902.913 382.944 312.087 + vertex -902.182 383.357 308.921 + endloop + endfacet + facet normal -0.949623 0.180423 -0.256249 + outer loop + vertex -903.185 378.986 309.558 + vertex -902.182 383.357 308.921 + vertex -902.53 376.933 305.685 + endloop + endfacet + facet normal -0.953254 0.168738 -0.250668 + outer loop + vertex -903.185 378.986 309.558 + vertex -902.53 376.933 305.685 + vertex -903.876 374.363 309.076 + endloop + endfacet + facet normal -0.964821 0.165619 -0.204182 + outer loop + vertex -903.876 374.363 309.076 + vertex -903.865 377.986 311.964 + vertex -903.185 378.986 309.558 + endloop + endfacet + facet normal -0.961413 0.173219 -0.213729 + outer loop + vertex -904.608 373.77 311.885 + vertex -903.865 377.986 311.964 + vertex -903.876 374.363 309.076 + endloop + endfacet + facet normal -0.962828 0.161397 -0.216593 + outer loop + vertex -904.646 370.438 309.574 + vertex -904.608 373.77 311.885 + vertex -903.876 374.363 309.076 + endloop + endfacet + facet normal -0.965464 0.155955 -0.208704 + outer loop + vertex -905.268 369.763 311.945 + vertex -904.608 373.77 311.885 + vertex -904.646 370.438 309.574 + endloop + endfacet + facet normal -0.966827 0.140134 -0.213561 + outer loop + vertex -905.175 366.035 309.079 + vertex -905.268 369.763 311.945 + vertex -904.646 370.438 309.574 + endloop + endfacet + facet normal -0.955404 0.143756 -0.257948 + outer loop + vertex -904.646 370.438 309.574 + vertex -903.909 368.433 305.727 + vertex -905.175 366.035 309.079 + endloop + endfacet + facet normal -0.952627 0.153565 -0.262527 + outer loop + vertex -904.646 370.438 309.574 + vertex -903.876 374.363 309.076 + vertex -903.909 368.433 305.727 + endloop + endfacet + facet normal -0.96404 0.14649 -0.221737 + outer loop + vertex -905.904 365.592 311.953 + vertex -905.268 369.763 311.945 + vertex -905.175 366.035 309.079 + endloop + endfacet + facet normal -0.964734 0.139993 -0.222913 + outer loop + vertex -905.859 362.077 309.554 + vertex -905.904 365.592 311.953 + vertex -905.175 366.035 309.079 + endloop + endfacet + facet normal -0.966947 0.13532 -0.216107 + outer loop + vertex -906.491 361.372 311.938 + vertex -905.904 365.592 311.953 + vertex -905.859 362.077 309.554 + endloop + endfacet + facet normal -0.968171 0.114383 -0.222625 + outer loop + vertex -906.272 357.591 309.045 + vertex -906.491 361.372 311.938 + vertex -905.859 362.077 309.554 + endloop + endfacet + facet normal -0.96544 0.120874 -0.2309 + outer loop + vertex -907.017 357.162 311.934 + vertex -906.491 361.372 311.938 + vertex -906.272 357.591 309.045 + endloop + endfacet + facet normal -0.966356 0.109221 -0.232868 + outer loop + vertex -906.84 353.604 309.532 + vertex -907.017 357.162 311.934 + vertex -906.272 357.591 309.045 + endloop + endfacet + facet normal -0.969434 0.102384 -0.222968 + outer loop + vertex -907.464 352.937 311.936 + vertex -907.017 357.162 311.934 + vertex -906.84 353.604 309.532 + endloop + endfacet + facet normal -0.970078 0.0782967 -0.229821 + outer loop + vertex -907.09 349.061 309.04 + vertex -907.464 352.937 311.936 + vertex -906.84 353.604 309.532 + endloop + endfacet + facet normal -0.967107 0.0857894 -0.239465 + outer loop + vertex -907.845 348.642 311.94 + vertex -907.464 352.937 311.936 + vertex -907.09 349.061 309.04 + endloop + endfacet + facet normal -0.967704 0.0718275 -0.241638 + outer loop + vertex -907.516 344.986 309.532 + vertex -907.845 348.642 311.94 + vertex -907.09 349.061 309.04 + endloop + endfacet + facet normal -0.969972 0.0665508 -0.233935 + outer loop + vertex -908.145 344.277 311.938 + vertex -907.845 348.642 311.94 + vertex -907.516 344.986 309.532 + endloop + endfacet + facet normal -0.969465 0.0375569 -0.242338 + outer loop + vertex -907.571 340.359 309.037 + vertex -908.145 344.277 311.938 + vertex -907.516 344.986 309.532 + endloop + endfacet + facet normal -0.966116 0.0465837 -0.25387 + outer loop + vertex -908.357 339.871 311.937 + vertex -908.145 344.277 311.938 + vertex -907.571 340.359 309.037 + endloop + endfacet + facet normal -0.966016 0.0281246 -0.256947 + outer loop + vertex -907.823 336.231 309.531 + vertex -908.357 339.871 311.937 + vertex -907.571 340.359 309.037 + endloop + endfacet + facet normal -0.968372 0.0222089 -0.24852 + outer loop + vertex -908.457 335.488 311.935 + vertex -908.357 339.871 311.937 + vertex -907.823 336.231 309.531 + endloop + endfacet + facet normal -0.966007 -0.0113569 -0.258266 + outer loop + vertex -907.637 331.655 309.038 + vertex -908.457 335.488 311.935 + vertex -907.823 336.231 309.531 + endloop + endfacet + facet normal -0.962743 -0.00147769 -0.270414 + outer loop + vertex -908.45 331.146 311.936 + vertex -908.457 335.488 311.935 + vertex -907.637 331.655 309.038 + endloop + endfacet + facet normal -0.961554 -0.0221823 -0.273718 + outer loop + vertex -907.684 327.593 309.532 + vertex -908.45 331.146 311.936 + vertex -907.637 331.655 309.038 + endloop + endfacet + facet normal -0.963913 -0.028825 -0.26465 + outer loop + vertex -908.322 326.858 311.937 + vertex -908.45 331.146 311.936 + vertex -907.684 327.593 309.532 + endloop + endfacet + facet normal -0.958585 -0.0704581 -0.275954 + outer loop + vertex -907.214 323.127 309.038 + vertex -908.322 326.858 311.937 + vertex -907.684 327.593 309.532 + endloop + endfacet + facet normal -0.954992 -0.0577258 -0.290961 + outer loop + vertex -908.066 322.622 311.937 + vertex -908.322 326.858 311.937 + vertex -907.214 323.127 309.038 + endloop + endfacet + facet normal -0.951944 -0.0837504 -0.294598 + outer loop + vertex -907.015 319.15 309.526 + vertex -908.066 322.622 311.937 + vertex -907.214 323.127 309.038 + endloop + endfacet + facet normal -0.954251 -0.0913008 -0.284728 + outer loop + vertex -907.663 318.427 311.931 + vertex -908.066 322.622 311.937 + vertex -907.015 319.15 309.526 + endloop + endfacet + facet normal -0.945407 -0.136515 -0.295922 + outer loop + vertex -906.222 314.737 309.028 + vertex -907.663 318.427 311.931 + vertex -907.015 319.15 309.526 + endloop + endfacet + facet normal -0.94219 -0.122788 -0.311771 + outer loop + vertex -907.115 314.244 311.923 + vertex -907.663 318.427 311.931 + vertex -906.222 314.737 309.028 + endloop + endfacet + facet normal -0.936727 -0.152418 -0.315136 + outer loop + vertex -905.74 310.777 309.513 + vertex -907.115 314.244 311.923 + vertex -906.222 314.737 309.028 + endloop + endfacet + facet normal -0.938839 -0.160559 -0.304633 + outer loop + vertex -906.395 310.053 311.913 + vertex -907.115 314.244 311.923 + vertex -905.74 310.777 309.513 + endloop + endfacet + facet normal -0.925279 -0.210003 -0.315845 + outer loop + vertex -904.568 306.337 309.029 + vertex -906.395 310.053 311.913 + vertex -905.74 310.777 309.513 + endloop + endfacet + facet normal -0.922162 -0.193789 -0.334759 + outer loop + vertex -905.508 305.841 311.906 + vertex -906.395 310.053 311.913 + vertex -904.568 306.337 309.029 + endloop + endfacet + facet normal -0.914558 -0.223129 -0.337338 + outer loop + vertex -903.775 302.322 309.535 + vertex -905.508 305.841 311.906 + vertex -904.568 306.337 309.029 + endloop + endfacet + facet normal -0.916345 -0.230911 -0.327095 + outer loop + vertex -904.448 301.615 311.92 + vertex -905.508 305.841 311.906 + vertex -903.775 302.322 309.535 + endloop + endfacet + facet normal -0.898478 -0.281353 -0.337013 + outer loop + vertex -902.207 297.823 309.113 + vertex -904.448 301.615 311.92 + vertex -903.775 302.322 309.535 + endloop + endfacet + facet normal -0.895514 -0.263703 -0.358491 + outer loop + vertex -903.232 297.424 311.965 + vertex -904.448 301.615 311.92 + vertex -902.207 297.823 309.113 + endloop + endfacet + facet normal -0.887543 -0.288627 -0.359113 + outer loop + vertex -901.159 293.872 309.697 + vertex -903.232 297.424 311.965 + vertex -902.207 297.823 309.113 + endloop + endfacet + facet normal -0.889823 -0.299372 -0.344372 + outer loop + vertex -901.872 293.292 312.045 + vertex -903.232 297.424 311.965 + vertex -901.159 293.872 309.697 + endloop + endfacet + facet normal -0.873519 -0.339117 -0.349232 + outer loop + vertex -899.441 289.744 309.409 + vertex -901.872 293.292 312.045 + vertex -901.159 293.872 309.697 + endloop + endfacet + facet normal -0.873191 -0.336202 -0.352854 + outer loop + vertex -900.27 289.085 312.088 + vertex -901.872 293.292 312.045 + vertex -899.441 289.744 309.409 + endloop + endfacet + facet normal -0.859738 -0.366162 -0.356055 + outer loop + vertex -897.633 285.244 309.671 + vertex -900.27 289.085 312.088 + vertex -899.441 289.744 309.409 + endloop + endfacet + facet normal -0.859747 -0.366219 -0.355975 + outer loop + vertex -898.521 284.885 312.186 + vertex -900.27 289.085 312.088 + vertex -897.633 285.244 309.671 + endloop + endfacet + facet normal -0.844231 -0.401134 -0.355479 + outer loop + vertex -895.71 281.038 309.85 + vertex -898.521 284.885 312.186 + vertex -897.633 285.244 309.671 + endloop + endfacet + facet normal -0.843464 -0.396058 -0.362914 + outer loop + vertex -896.652 280.863 312.23 + vertex -898.521 284.885 312.186 + vertex -895.71 281.038 309.85 + endloop + endfacet + facet normal -0.826355 -0.433944 -0.358929 + outer loop + vertex -893.68 277.125 309.906 + vertex -896.652 280.863 312.23 + vertex -895.71 281.038 309.85 + endloop + endfacet + facet normal -0.825341 -0.425606 -0.371042 + outer loop + vertex -894.679 277.044 312.221 + vertex -896.652 280.863 312.23 + vertex -893.68 277.125 309.906 + endloop + endfacet + facet normal -0.808626 -0.461346 -0.365081 + outer loop + vertex -891.561 273.414 309.903 + vertex -894.679 277.044 312.221 + vertex -893.68 277.125 309.906 + endloop + endfacet + facet normal -0.807665 -0.451407 -0.379355 + outer loop + vertex -892.607 273.352 312.204 + vertex -894.679 277.044 312.221 + vertex -891.561 273.414 309.903 + endloop + endfacet + facet normal -0.788953 -0.48914 -0.37188 + outer loop + vertex -889.33 269.823 309.893 + vertex -892.607 273.352 312.204 + vertex -891.561 273.414 309.903 + endloop + endfacet + facet normal -0.787947 -0.475762 -0.390885 + outer loop + vertex -890.413 269.72 312.201 + vertex -892.607 273.352 312.204 + vertex -889.33 269.823 309.893 + endloop + endfacet + facet normal -0.770501 -0.508677 -0.384156 + outer loop + vertex -886.978 266.253 309.902 + vertex -890.413 269.72 312.201 + vertex -889.33 269.823 309.893 + endloop + endfacet + facet normal -0.769814 -0.498033 -0.399185 + outer loop + vertex -888.091 266.127 312.206 + vertex -890.413 269.72 312.201 + vertex -886.978 266.253 309.902 + endloop + endfacet + facet normal -0.751974 -0.529749 -0.392302 + outer loop + vertex -884.505 262.728 309.924 + vertex -888.091 266.127 312.206 + vertex -886.978 266.253 309.902 + endloop + endfacet + facet normal -0.751306 -0.517235 -0.409887 + outer loop + vertex -885.653 262.581 312.212 + vertex -888.091 266.127 312.206 + vertex -884.505 262.728 309.924 + endloop + endfacet + facet normal -0.734378 -0.545972 -0.40324 + outer loop + vertex -881.947 259.264 309.954 + vertex -885.653 262.581 312.212 + vertex -884.505 262.728 309.924 + endloop + endfacet + facet normal -0.733879 -0.534886 -0.41871 + outer loop + vertex -883.132 259.121 312.214 + vertex -885.653 262.581 312.212 + vertex -881.947 259.264 309.954 + endloop + endfacet + facet normal -0.716573 -0.563244 -0.411436 + outer loop + vertex -879.34 255.914 309.999 + vertex -883.132 259.121 312.214 + vertex -881.947 259.264 309.954 + endloop + endfacet + facet normal -0.716169 -0.551642 -0.427544 + outer loop + vertex -880.56 255.777 312.22 + vertex -883.132 259.121 312.214 + vertex -879.34 255.914 309.999 + endloop + endfacet + facet normal -0.702414 -0.573656 -0.421346 + outer loop + vertex -876.714 252.65 310.066 + vertex -880.56 255.777 312.22 + vertex -879.34 255.914 309.999 + endloop + endfacet + facet normal -0.701997 -0.562486 -0.436819 + outer loop + vertex -877.966 252.53 312.232 + vertex -880.56 255.777 312.22 + vertex -876.714 252.65 310.066 + endloop + endfacet + facet normal -0.687711 -0.58508 -0.429808 + outer loop + vertex -874.037 249.444 310.147 + vertex -877.966 252.53 312.232 + vertex -876.714 252.65 310.066 + endloop + endfacet + facet normal -0.687402 -0.577633 -0.440247 + outer loop + vertex -875.321 249.365 312.256 + vertex -877.966 252.53 312.232 + vertex -874.037 249.444 310.147 + endloop + endfacet + facet normal -0.672721 -0.60056 -0.432174 + outer loop + vertex -871.256 246.265 310.236 + vertex -875.321 249.365 312.256 + vertex -874.037 249.444 310.147 + endloop + endfacet + facet normal -0.672015 -0.587389 -0.450965 + outer loop + vertex -872.589 246.215 312.288 + vertex -875.321 249.365 312.256 + vertex -871.256 246.265 310.236 + endloop + endfacet + facet normal -0.657904 -0.609508 -0.442336 + outer loop + vertex -868.35 243.071 310.313 + vertex -872.589 246.215 312.288 + vertex -871.256 246.265 310.236 + endloop + endfacet + facet normal -0.657334 -0.601012 -0.454639 + outer loop + vertex -869.706 243.044 312.311 + vertex -872.589 246.215 312.288 + vertex -868.35 243.071 310.313 + endloop + endfacet + facet normal -0.64261 -0.623755 -0.444952 + outer loop + vertex -865.324 239.937 310.338 + vertex -869.706 243.044 312.311 + vertex -868.35 243.071 310.313 + endloop + endfacet + facet normal -0.641677 -0.608568 -0.466794 + outer loop + vertex -866.681 239.862 312.301 + vertex -869.706 243.044 312.311 + vertex -865.324 239.937 310.338 + endloop + endfacet + facet normal -0.629533 -0.626835 -0.459092 + outer loop + vertex -862.354 236.976 310.308 + vertex -866.681 239.862 312.301 + vertex -865.324 239.937 310.338 + endloop + endfacet + facet normal -0.628968 -0.611539 -0.48002 + outer loop + vertex -863.695 236.823 312.261 + vertex -866.681 239.862 312.301 + vertex -862.354 236.976 310.308 + endloop + endfacet + facet normal -0.619702 -0.624993 -0.474714 + outer loop + vertex -859.8 234.458 310.29 + vertex -863.695 236.823 312.261 + vertex -862.354 236.976 310.308 + endloop + endfacet + facet normal -0.620033 -0.611424 -0.49165 + outer loop + vertex -861.124 234.207 312.27 + vertex -863.695 236.823 312.261 + vertex -859.8 234.458 310.29 + endloop + endfacet + facet normal -0.61798 -0.614306 -0.490641 + outer loop + vertex -858.063 232.598 310.43 + vertex -861.124 234.207 312.27 + vertex -859.8 234.458 310.29 + endloop + endfacet + facet normal -0.615332 -0.632722 -0.470138 + outer loop + vertex -859.433 232.388 312.505 + vertex -861.124 234.207 312.27 + vertex -858.063 232.598 310.43 + endloop + endfacet + facet normal -0.635976 -0.603617 -0.480813 + outer loop + vertex -857.424 231.518 310.941 + vertex -859.433 232.388 312.505 + vertex -858.063 232.598 310.43 + endloop + endfacet + facet normal -0.611595 -0.677674 -0.408301 + outer loop + vertex -858.828 231.472 313.12 + vertex -859.433 232.388 312.505 + vertex -857.424 231.518 310.941 + endloop + endfacet + facet normal -0.970899 0.173971 -0.164588 + outer loop + vertex -904.608 373.77 311.885 + vertex -904.373 377.044 313.961 + vertex -903.865 377.986 311.964 + endloop + endfacet + facet normal -0.968065 0.199494 -0.15183 + outer loop + vertex -904.373 377.044 313.961 + vertex -903.524 381.814 314.819 + vertex -903.865 377.986 311.964 + endloop + endfacet + facet normal -0.971862 0.190214 -0.138934 + outer loop + vertex -903.865 377.986 311.964 + vertex -903.524 381.814 314.819 + vertex -902.913 382.944 312.087 + endloop + endfacet + facet normal -0.976368 0.191638 -0.0999003 + outer loop + vertex -904.373 377.044 313.961 + vertex -904.271 378.873 316.475 + vertex -903.524 381.814 314.819 + endloop + endfacet + facet normal -0.975809 0.205061 -0.0758125 + outer loop + vertex -903.524 381.814 314.819 + vertex -904.271 378.873 316.475 + vertex -902.742 387.036 318.878 + endloop + endfacet + facet normal -0.975509 0.206008 -0.0770892 + outer loop + vertex -902.175 388.38 315.29 + vertex -903.524 381.814 314.819 + vertex -902.742 387.036 318.878 + endloop + endfacet + facet normal -0.9737 0.215774 -0.0731441 + outer loop + vertex -902.742 387.036 318.878 + vertex -900.795 395.907 319.126 + vertex -902.175 388.38 315.29 + endloop + endfacet + facet normal -0.97006 0.224745 -0.0920555 + outer loop + vertex -902.175 388.38 315.29 + vertex -900.795 395.907 319.126 + vertex -900.481 395.559 314.968 + endloop + endfacet + facet normal -0.968552 0.230992 -0.0924637 + outer loop + vertex -900.795 395.907 319.126 + vertex -898.83 404.111 319.034 + vertex -900.481 395.559 314.968 + endloop + endfacet + facet normal -0.966026 0.236303 -0.104662 + outer loop + vertex -900.481 395.559 314.968 + vertex -898.83 404.111 319.034 + vertex -898.503 403.449 314.523 + endloop + endfacet + facet normal -0.964281 0.242958 -0.105512 + outer loop + vertex -898.83 404.111 319.034 + vertex -896.742 412.354 318.938 + vertex -898.503 403.449 314.523 + endloop + endfacet + facet normal -0.963786 0.243954 -0.10772 + outer loop + vertex -898.503 403.449 314.523 + vertex -896.742 412.354 318.938 + vertex -896.355 411.869 314.377 + endloop + endfacet + facet normal -0.961122 0.253893 -0.108551 + outer loop + vertex -896.742 412.354 318.938 + vertex -894.573 420.568 318.945 + vertex -896.355 411.869 314.377 + endloop + endfacet + facet normal -0.96044 0.255241 -0.111384 + outer loop + vertex -896.355 411.869 314.377 + vertex -894.573 420.568 318.945 + vertex -894.167 420.104 314.382 + endloop + endfacet + facet normal -0.95787 0.264427 -0.112089 + outer loop + vertex -894.573 420.568 318.945 + vertex -892.326 428.741 319.019 + vertex -894.167 420.104 314.382 + endloop + endfacet + facet normal -0.957218 0.265675 -0.114674 + outer loop + vertex -894.167 420.104 314.382 + vertex -892.326 428.741 319.019 + vertex -891.917 428.246 314.454 + endloop + endfacet + facet normal -0.955941 0.270081 -0.115037 + outer loop + vertex -892.326 428.741 319.019 + vertex -889.986 437.058 319.102 + vertex -891.917 428.246 314.454 + endloop + endfacet + facet normal -0.954647 0.272455 -0.120075 + outer loop + vertex -891.917 428.246 314.454 + vertex -889.986 437.058 319.102 + vertex -889.563 436.525 314.527 + endloop + endfacet + facet normal -0.954248 0.273796 -0.120195 + outer loop + vertex -889.986 437.058 319.102 + vertex -887.554 445.532 319.093 + vertex -889.563 436.525 314.527 + endloop + endfacet + facet normal -0.952184 0.277359 -0.12813 + outer loop + vertex -889.563 436.525 314.527 + vertex -887.554 445.532 319.093 + vertex -887.116 444.915 314.509 + endloop + endfacet + facet normal -0.952403 0.276641 -0.128055 + outer loop + vertex -887.554 445.532 319.093 + vertex -885.169 453.641 318.877 + vertex -887.116 444.915 314.509 + endloop + endfacet + facet normal -0.948446 0.283043 -0.142608 + outer loop + vertex -887.116 444.915 314.509 + vertex -885.169 453.641 318.877 + vertex -884.702 452.888 314.275 + endloop + endfacet + facet normal -0.948494 0.282891 -0.142588 + outer loop + vertex -885.169 453.641 318.877 + vertex -882.862 461.193 318.514 + vertex -884.702 452.888 314.275 + endloop + endfacet + facet normal -0.943141 0.290957 -0.160713 + outer loop + vertex -884.702 452.888 314.275 + vertex -882.862 461.193 318.514 + vertex -882.8 458.622 313.494 + endloop + endfacet + facet normal -0.946763 0.281621 -0.155977 + outer loop + vertex -882.8 458.622 313.494 + vertex -882.862 461.193 318.514 + vertex -881.354 464.385 315.121 + endloop + endfacet + facet normal -0.946272 0.285229 -0.152363 + outer loop + vertex -881.453 466.617 319.92 + vertex -881.354 464.385 315.121 + vertex -882.862 461.193 318.514 + endloop + endfacet + facet normal -0.960474 0.244221 -0.133586 + outer loop + vertex -881.453 466.617 319.92 + vertex -880.881 468.035 318.397 + vertex -881.354 464.385 315.121 + endloop + endfacet + facet normal -0.950018 0.267477 -0.161 + outer loop + vertex -881.354 464.385 315.121 + vertex -880.881 468.035 318.397 + vertex -880.47 466.897 314.079 + endloop + endfacet + facet normal -0.952759 0.286151 -0.101821 + outer loop + vertex -885.169 453.641 318.877 + vertex -883.587 460.206 322.518 + vertex -882.862 461.193 318.514 + endloop + endfacet + facet normal -0.952248 0.288045 -0.101262 + outer loop + vertex -882.862 461.193 318.514 + vertex -883.587 460.206 322.518 + vertex -881.985 465.981 323.888 + endloop + endfacet + facet normal -0.958806 0.271034 -0.0850341 + outer loop + vertex -881.985 465.981 323.888 + vertex -881.453 466.617 319.92 + vertex -882.862 461.193 318.514 + endloop + endfacet + facet normal -0.96304 0.254492 -0.0882531 + outer loop + vertex -881.985 465.981 323.888 + vertex -881.083 468.931 322.547 + vertex -881.453 466.617 319.92 + endloop + endfacet + facet normal -0.956273 0.272835 -0.105367 + outer loop + vertex -881.453 466.617 319.92 + vertex -881.083 468.931 322.547 + vertex -880.881 468.035 318.397 + endloop + endfacet + facet normal -0.961281 0.270745 -0.0513393 + outer loop + vertex -881.985 465.981 323.888 + vertex -881.216 469.269 326.816 + vertex -881.083 468.931 322.547 + endloop + endfacet + facet normal -0.964508 0.261066 -0.0396202 + outer loop + vertex -881.772 467.454 328.394 + vertex -881.216 469.269 326.816 + vertex -881.985 465.981 323.888 + endloop + endfacet + facet normal -0.95899 0.279687 -0.0459665 + outer loop + vertex -881.772 467.454 328.394 + vertex -881.985 465.981 323.888 + vertex -883.26 462.135 327.074 + endloop + endfacet + facet normal -0.961811 0.273205 -0.0166739 + outer loop + vertex -882.205 466.154 332.094 + vertex -881.772 467.454 328.394 + vertex -883.26 462.135 327.074 + endloop + endfacet + facet normal -0.960159 0.278638 -0.0213705 + outer loop + vertex -883.26 462.135 327.074 + vertex -883.794 460.565 330.591 + vertex -882.205 466.154 332.094 + endloop + endfacet + facet normal -0.961676 0.27417 -0.00315091 + outer loop + vertex -883.794 460.565 330.591 + vertex -883.495 461.653 334.156 + vertex -882.205 466.154 332.094 + endloop + endfacet + facet normal -0.961242 0.275706 0.000472449 + outer loop + vertex -882.042 466.713 336.705 + vertex -882.205 466.154 332.094 + vertex -883.495 461.653 334.156 + endloop + endfacet + facet normal -0.962615 0.270636 0.0113207 + outer loop + vertex -883.495 461.653 334.156 + vertex -883.352 462.003 337.991 + vertex -882.042 466.713 336.705 + endloop + endfacet + facet normal -0.961951 0.272559 0.0190373 + outer loop + vertex -881.954 466.761 340.48 + vertex -882.042 466.713 336.705 + vertex -883.352 462.003 337.991 + endloop + endfacet + facet normal -0.963045 0.267802 0.0287455 + outer loop + vertex -883.352 462.003 337.991 + vertex -883.246 461.997 341.594 + vertex -881.954 466.761 340.48 + endloop + endfacet + facet normal -0.961925 0.270276 0.0406262 + outer loop + vertex -881.866 466.557 343.925 + vertex -881.954 466.761 340.48 + vertex -883.246 461.997 341.594 + endloop + endfacet + facet normal -0.962827 0.265268 0.0509534 + outer loop + vertex -883.246 461.997 341.594 + vertex -883.095 461.89 344.994 + vertex -881.866 466.557 343.925 + endloop + endfacet + facet normal -0.960955 0.268459 0.0670443 + outer loop + vertex -881.701 466.333 347.184 + vertex -881.866 466.557 343.925 + vertex -883.095 461.89 344.994 + endloop + endfacet + facet normal -0.961633 0.262625 0.0793132 + outer loop + vertex -883.095 461.89 344.994 + vertex -882.879 461.716 348.193 + vertex -881.701 466.333 347.184 + endloop + endfacet + facet normal -0.958591 0.266474 0.100472 + outer loop + vertex -881.44 466.117 350.252 + vertex -881.701 466.333 347.184 + vertex -882.879 461.716 348.193 + endloop + endfacet + facet normal -0.958804 0.259771 0.114948 + outer loop + vertex -882.879 461.716 348.193 + vertex -882.577 461.521 351.151 + vertex -881.44 466.117 350.252 + endloop + endfacet + facet normal -0.953621 0.264211 0.144219 + outer loop + vertex -881.127 465.768 352.962 + vertex -881.44 466.117 350.252 + vertex -882.577 461.521 351.151 + endloop + endfacet + facet normal -0.955001 0.259434 0.143763 + outer loop + vertex -881.127 465.768 352.962 + vertex -880.609 468.161 352.083 + vertex -881.44 466.117 350.252 + endloop + endfacet + facet normal -0.954003 0.268692 0.132976 + outer loop + vertex -881.44 466.117 350.252 + vertex -880.609 468.161 352.083 + vertex -880.9 468.609 349.087 + endloop + endfacet + facet normal -0.957079 0.265958 0.11518 + outer loop + vertex -884.585 455.278 348.88 + vertex -882.577 461.521 351.151 + vertex -882.879 461.716 348.193 + endloop + endfacet + facet normal -0.960307 0.264104 0.0897713 + outer loop + vertex -884.585 455.278 348.88 + vertex -882.879 461.716 348.193 + vertex -884.883 455.273 345.715 + endloop + endfacet + facet normal -0.959391 0.267444 0.0896799 + outer loop + vertex -886.95 447.733 346.081 + vertex -884.585 455.278 348.88 + vertex -884.883 455.273 345.715 + endloop + endfacet + facet normal -0.96147 0.266865 0.0660144 + outer loop + vertex -886.95 447.733 346.081 + vertex -884.883 455.273 345.715 + vertex -887.24 447.52 342.722 + endloop + endfacet + facet normal -0.96108 0.268299 0.0658897 + outer loop + vertex -889.42 439.691 342.803 + vertex -886.95 447.733 346.081 + vertex -887.24 447.52 342.722 + endloop + endfacet + facet normal -0.962292 0.268411 0.0441611 + outer loop + vertex -889.42 439.691 342.803 + vertex -887.24 447.52 342.722 + vertex -889.697 439.282 339.26 + endloop + endfacet + facet normal -0.96247 0.267754 0.0442508 + outer loop + vertex -891.85 431.552 339.199 + vertex -889.42 439.691 342.803 + vertex -889.697 439.282 339.26 + endloop + endfacet + facet normal -0.963069 0.268072 0.0252279 + outer loop + vertex -891.85 431.552 339.199 + vertex -889.697 439.282 339.26 + vertex -892.109 430.973 335.479 + endloop + endfacet + facet normal -0.964293 0.263558 0.0260159 + outer loop + vertex -894.211 423.289 335.404 + vertex -891.85 431.552 339.199 + vertex -892.109 430.973 335.479 + endloop + endfacet + facet normal -0.964529 0.263775 0.0103089 + outer loop + vertex -894.211 423.289 335.404 + vertex -892.109 430.973 335.479 + vertex -894.455 422.546 331.516 + endloop + endfacet + facet normal -0.966889 0.254908 0.0121519 + outer loop + vertex -896.524 414.703 331.48 + vertex -894.211 423.289 335.404 + vertex -894.455 422.546 331.516 + endloop + endfacet + facet normal -0.966929 0.254998 -0.00500317 + outer loop + vertex -896.524 414.703 331.48 + vertex -894.455 422.546 331.516 + vertex -896.736 413.82 327.436 + endloop + endfacet + facet normal -0.970112 0.242647 -0.00213813 + outer loop + vertex -898.761 405.722 327.425 + vertex -896.524 414.703 331.48 + vertex -896.736 413.82 327.436 + endloop + endfacet + facet normal -0.96987 0.242614 -0.0221376 + outer loop + vertex -898.761 405.722 327.425 + vertex -896.736 413.82 327.436 + vertex -898.894 404.813 323.276 + endloop + endfacet + facet normal -0.973298 0.22876 -0.0189919 + outer loop + vertex -900.843 396.518 323.26 + vertex -898.761 405.722 327.425 + vertex -898.894 404.813 323.276 + endloop + endfacet + facet normal -0.972475 0.228615 -0.0450266 + outer loop + vertex -900.843 396.518 323.26 + vertex -898.894 404.813 323.276 + vertex -900.795 395.907 319.126 + endloop + endfacet + facet normal -0.973161 0.229245 -0.0201317 + outer loop + vertex -900.666 397.635 327.445 + vertex -898.761 405.722 327.425 + vertex -900.843 396.518 323.26 + endloop + endfacet + facet normal -0.976441 0.215172 -0.0162369 + outer loop + vertex -902.585 388.621 323.371 + vertex -900.666 397.635 327.445 + vertex -900.843 396.518 323.26 + endloop + endfacet + facet normal -0.975801 0.214677 -0.0415582 + outer loop + vertex -902.585 388.621 323.371 + vertex -900.843 396.518 323.26 + vertex -902.742 387.036 318.878 + endloop + endfacet + facet normal -0.978338 0.203581 -0.037555 + outer loop + vertex -904.123 380.569 319.793 + vertex -902.585 388.621 323.371 + vertex -902.742 387.036 318.878 + endloop + endfacet + facet normal -0.979828 0.198274 -0.0249718 + outer loop + vertex -904.096 381.161 323.411 + vertex -902.585 388.621 323.371 + vertex -904.123 380.569 319.793 + endloop + endfacet + facet normal -0.982605 0.184319 -0.0226659 + outer loop + vertex -904.123 380.569 319.793 + vertex -905.261 374.504 319.795 + vertex -904.096 381.161 323.411 + endloop + endfacet + facet normal -0.984417 0.175737 -0.00628315 + outer loop + vertex -905.58 372.821 322.732 + vertex -904.096 381.161 323.411 + vertex -905.261 374.504 319.795 + endloop + endfacet + facet normal -0.986004 0.166298 -0.0118654 + outer loop + vertex -906.103 369.462 319.144 + vertex -905.58 372.821 322.732 + vertex -905.261 374.504 319.795 + endloop + endfacet + facet normal -0.983443 0.171787 -0.0576956 + outer loop + vertex -906.103 369.462 319.144 + vertex -905.261 374.504 319.795 + vertex -905.947 369.615 316.929 + endloop + endfacet + facet normal -0.986321 0.153863 -0.0591303 + outer loop + vertex -906.62 365.282 316.886 + vertex -906.103 369.462 319.144 + vertex -905.947 369.615 316.929 + endloop + endfacet + facet normal -0.982513 0.153734 -0.105046 + outer loop + vertex -906.62 365.282 316.886 + vertex -905.947 369.615 316.929 + vertex -906.357 365.306 314.455 + endloop + endfacet + facet normal -0.984839 0.137735 -0.105453 + outer loop + vertex -906.944 361.103 314.448 + vertex -906.62 365.282 316.886 + vertex -906.357 365.306 314.455 + endloop + endfacet + facet normal -0.985113 0.136898 -0.103981 + outer loop + vertex -907.198 361.127 316.889 + vertex -906.62 365.282 316.886 + vertex -906.944 361.103 314.448 + endloop + endfacet + facet normal -0.986939 0.123005 -0.10403 + outer loop + vertex -907.465 356.932 314.46 + vertex -907.198 361.127 316.889 + vertex -906.944 361.103 314.448 + endloop + endfacet + facet normal -0.987021 0.122738 -0.10356 + outer loop + vertex -907.715 356.987 316.911 + vertex -907.198 361.127 316.889 + vertex -907.465 356.932 314.46 + endloop + endfacet + facet normal -0.988978 0.105989 -0.103388 + outer loop + vertex -907.918 352.72 314.473 + vertex -907.715 356.987 316.911 + vertex -907.465 356.932 314.46 + endloop + endfacet + facet normal -0.988743 0.106785 -0.104801 + outer loop + vertex -908.172 352.777 316.929 + vertex -907.715 356.987 316.911 + vertex -907.918 352.72 314.473 + endloop + endfacet + facet normal -0.990531 0.0889577 -0.104568 + outer loop + vertex -908.304 348.418 314.478 + vertex -908.172 352.777 316.929 + vertex -907.918 352.72 314.473 + endloop + endfacet + facet normal -0.990509 0.0890362 -0.104709 + outer loop + vertex -908.558 348.48 316.934 + vertex -908.172 352.777 316.929 + vertex -908.304 348.418 314.478 + endloop + endfacet + facet normal -0.992127 0.0692127 -0.104372 + outer loop + vertex -908.609 344.044 314.475 + vertex -908.558 348.48 316.934 + vertex -908.304 348.418 314.478 + endloop + endfacet + facet normal -0.991966 0.0698298 -0.105489 + outer loop + vertex -908.865 344.118 316.931 + vertex -908.558 348.48 316.934 + vertex -908.609 344.044 314.475 + endloop + endfacet + facet normal -0.993277 0.0487727 -0.104988 + outer loop + vertex -908.825 339.642 314.472 + vertex -908.865 344.118 316.931 + vertex -908.609 344.044 314.475 + endloop + endfacet + facet normal -0.993 0.049909 -0.107051 + outer loop + vertex -909.085 339.744 316.928 + vertex -908.865 344.118 316.931 + vertex -908.825 339.642 314.472 + endloop + endfacet + facet normal -0.994022 0.0255665 -0.106144 + outer loop + vertex -908.938 335.263 314.471 + vertex -909.085 339.744 316.928 + vertex -908.825 339.642 314.472 + endloop + endfacet + facet normal -0.99408 0.0253019 -0.105665 + outer loop + vertex -909.195 335.395 316.926 + vertex -909.085 339.744 316.928 + vertex -908.938 335.263 314.471 + endloop + endfacet + facet normal -0.994545 -0.000775741 -0.10431 + outer loop + vertex -908.934 330.939 314.47 + vertex -909.195 335.395 316.926 + vertex -908.938 335.263 314.471 + endloop + endfacet + facet normal -0.994067 0.00170152 -0.108755 + outer loop + vertex -909.203 331.09 316.926 + vertex -909.195 335.395 316.926 + vertex -908.934 330.939 314.47 + endloop + endfacet + facet normal -0.993851 -0.0291119 -0.106826 + outer loop + vertex -908.809 326.671 314.47 + vertex -909.203 331.09 316.926 + vertex -908.934 330.939 314.47 + endloop + endfacet + facet normal -0.993314 -0.0259137 -0.112496 + outer loop + vertex -909.092 326.834 316.928 + vertex -909.203 331.09 316.926 + vertex -908.809 326.671 314.47 + endloop + endfacet + facet normal -0.992214 -0.0579633 -0.110238 + outer loop + vertex -908.562 322.445 314.471 + vertex -909.092 326.834 316.928 + vertex -908.809 326.671 314.47 + endloop + endfacet + facet normal -0.992116 -0.0572558 -0.11148 + outer loop + vertex -908.849 322.629 316.929 + vertex -909.092 326.834 316.928 + vertex -908.562 322.445 314.471 + endloop + endfacet + facet normal -0.989936 -0.0905729 -0.108735 + outer loop + vertex -908.179 318.254 314.469 + vertex -908.849 322.629 316.929 + vertex -908.562 322.445 314.471 + endloop + endfacet + facet normal -0.989756 -0.0888452 -0.111758 + outer loop + vertex -908.474 318.447 316.93 + vertex -908.849 322.629 316.929 + vertex -908.179 318.254 314.469 + endloop + endfacet + facet normal -0.986164 -0.125358 -0.108468 + outer loop + vertex -907.646 314.068 314.463 + vertex -908.474 318.447 316.93 + vertex -908.179 318.254 314.469 + endloop + endfacet + facet normal -0.986146 -0.125087 -0.108943 + outer loop + vertex -907.944 314.269 316.926 + vertex -908.474 318.447 316.93 + vertex -907.646 314.068 314.463 + endloop + endfacet + facet normal -0.98091 -0.163573 -0.105168 + outer loop + vertex -906.945 309.875 314.452 + vertex -907.944 314.269 316.926 + vertex -907.646 314.068 314.463 + endloop + endfacet + facet normal -0.98084 -0.161079 -0.10957 + outer loop + vertex -907.255 310.082 316.918 + vertex -907.944 314.269 316.926 + vertex -906.945 309.875 314.452 + endloop + endfacet + facet normal -0.973687 -0.202147 -0.105214 + outer loop + vertex -906.073 305.679 314.44 + vertex -907.255 310.082 316.918 + vertex -906.945 309.875 314.452 + endloop + endfacet + facet normal -0.973709 -0.196981 -0.114408 + outer loop + vertex -906.409 305.908 316.906 + vertex -907.255 310.082 316.918 + vertex -906.073 305.679 314.44 + endloop + endfacet + facet normal -0.965472 -0.236312 -0.109633 + outer loop + vertex -905.049 301.494 314.441 + vertex -906.409 305.908 316.906 + vertex -906.073 305.679 314.44 + endloop + endfacet + facet normal -0.965554 -0.233929 -0.113945 + outer loop + vertex -905.405 301.77 316.896 + vertex -906.409 305.908 316.906 + vertex -905.049 301.494 314.441 + endloop + endfacet + facet normal -0.955327 -0.275181 -0.107826 + outer loop + vertex -903.86 297.362 314.456 + vertex -905.405 301.77 316.896 + vertex -905.049 301.494 314.441 + endloop + endfacet + facet normal -0.955633 -0.270726 -0.116071 + outer loop + vertex -904.245 297.678 316.888 + vertex -905.405 301.77 316.896 + vertex -903.86 297.362 314.456 + endloop + endfacet + facet normal -0.944005 -0.311422 -0.108956 + outer loop + vertex -902.504 293.243 314.478 + vertex -904.245 297.678 316.888 + vertex -903.86 297.362 314.456 + endloop + endfacet + facet normal -0.944214 -0.309413 -0.112801 + outer loop + vertex -902.912 293.613 316.88 + vertex -904.245 297.678 316.888 + vertex -902.504 293.243 314.478 + endloop + endfacet + facet normal -0.930697 -0.350651 -0.104153 + outer loop + vertex -900.96 289.14 314.498 + vertex -902.912 293.613 316.88 + vertex -902.504 293.243 314.478 + endloop + endfacet + facet normal -0.931361 -0.345941 -0.113539 + outer loop + vertex -901.411 289.575 316.87 + vertex -902.912 293.613 316.88 + vertex -900.96 289.14 314.498 + endloop + endfacet + facet normal -0.918039 -0.382527 -0.104295 + outer loop + vertex -899.274 285.091 314.508 + vertex -901.411 289.575 316.87 + vertex -900.96 289.14 314.498 + endloop + endfacet + facet normal -0.918599 -0.37931 -0.110907 + outer loop + vertex -899.763 285.589 316.853 + vertex -901.411 289.575 316.87 + vertex -899.274 285.091 314.508 + endloop + endfacet + facet normal -0.902686 -0.418703 -0.0992275 + outer loop + vertex -897.455 281.172 314.495 + vertex -899.763 285.589 316.853 + vertex -899.274 285.091 314.508 + endloop + endfacet + facet normal -0.904648 -0.409254 -0.118844 + outer loop + vertex -897.996 281.688 316.838 + vertex -899.763 285.589 316.853 + vertex -897.455 281.172 314.495 + endloop + endfacet + facet normal -0.888195 -0.446891 -0.106764 + outer loop + vertex -895.539 277.369 314.477 + vertex -897.996 281.688 316.838 + vertex -897.455 281.172 314.495 + endloop + endfacet + facet normal -0.888884 -0.444067 -0.112648 + outer loop + vertex -896.099 277.89 316.835 + vertex -897.996 281.688 316.838 + vertex -895.539 277.369 314.477 + endloop + endfacet + facet normal -0.872627 -0.47776 -0.101332 + outer loop + vertex -893.507 273.658 314.472 + vertex -896.099 277.89 316.835 + vertex -895.539 277.369 314.477 + endloop + endfacet + facet normal -0.874307 -0.471855 -0.113752 + outer loop + vertex -894.092 274.172 316.839 + vertex -896.099 277.89 316.835 + vertex -893.507 273.658 314.472 + endloop + endfacet + facet normal -0.856355 -0.506244 -0.101847 + outer loop + vertex -891.348 270.004 314.476 + vertex -894.092 274.172 316.839 + vertex -893.507 273.658 314.472 + endloop + endfacet + facet normal -0.85794 -0.501304 -0.112397 + outer loop + vertex -891.957 270.515 316.845 + vertex -894.092 274.172 316.839 + vertex -891.348 270.004 314.476 + endloop + endfacet + facet normal -0.83832 -0.535951 -0.0998827 + outer loop + vertex -889.047 266.405 314.481 + vertex -891.957 270.515 316.845 + vertex -891.348 270.004 314.476 + endloop + endfacet + facet normal -0.840358 -0.530281 -0.112251 + outer loop + vertex -889.686 266.917 316.848 + vertex -891.957 270.515 316.845 + vertex -889.047 266.405 314.481 + endloop + endfacet + facet normal -0.824732 -0.556169 -0.10243 + outer loop + vertex -886.652 262.853 314.476 + vertex -889.686 266.917 316.848 + vertex -889.047 266.405 314.481 + endloop + endfacet + facet normal -0.825299 -0.554731 -0.10562 + outer loop + vertex -887.311 263.384 316.845 + vertex -889.686 266.917 316.848 + vertex -886.652 262.853 314.476 + endloop + endfacet + facet normal -0.807376 -0.582434 -0.0944194 + outer loop + vertex -884.162 259.404 314.468 + vertex -887.311 263.384 316.845 + vertex -886.652 262.853 314.476 + endloop + endfacet + facet normal -0.809824 -0.576823 -0.107058 + outer loop + vertex -884.862 259.946 316.838 + vertex -887.311 263.384 316.845 + vertex -884.162 259.404 314.468 + endloop + endfacet + facet normal -0.793146 -0.601333 -0.0965335 + outer loop + vertex -881.629 256.064 314.457 + vertex -884.862 259.946 316.838 + vertex -884.162 259.404 314.468 + endloop + endfacet + facet normal -0.795525 -0.596192 -0.108146 + outer loop + vertex -882.365 256.616 316.829 + vertex -884.862 259.946 316.838 + vertex -881.629 256.064 314.457 + endloop + endfacet + facet normal -0.77902 -0.619351 -0.0976306 + outer loop + vertex -879.062 252.837 314.451 + vertex -882.365 256.616 316.829 + vertex -881.629 256.064 314.457 + endloop + endfacet + facet normal -0.780032 -0.617329 -0.102253 + outer loop + vertex -879.813 253.392 316.828 + vertex -882.365 256.616 316.829 + vertex -879.062 252.837 314.451 + endloop + endfacet + facet normal -0.766758 -0.635028 -0.0939244 + outer loop + vertex -876.445 249.676 314.456 + vertex -879.813 253.392 316.828 + vertex -879.062 252.837 314.451 + endloop + endfacet + facet normal -0.768221 -0.632277 -0.100309 + outer loop + vertex -877.197 250.212 316.834 + vertex -879.813 253.392 316.828 + vertex -876.445 249.676 314.456 + endloop + endfacet + facet normal -0.753423 -0.651155 -0.0913827 + outer loop + vertex -873.718 246.518 314.471 + vertex -877.197 250.212 316.834 + vertex -876.445 249.676 314.456 + endloop + endfacet + facet normal -0.754722 -0.64885 -0.0968961 + outer loop + vertex -874.439 247.002 316.844 + vertex -877.197 250.212 316.834 + vertex -873.718 246.518 314.471 + endloop + endfacet + facet normal -0.740319 -0.666345 -0.088953 + outer loop + vertex -870.818 243.296 314.476 + vertex -874.439 247.002 316.844 + vertex -873.718 246.518 314.471 + endloop + endfacet + facet normal -0.740588 -0.665896 -0.0900684 + outer loop + vertex -871.489 243.723 316.836 + vertex -874.439 247.002 316.844 + vertex -870.818 243.296 314.476 + endloop + endfacet + facet normal -0.727733 -0.68073 -0.0837271 + outer loop + vertex -867.763 240.034 314.447 + vertex -871.489 243.723 316.836 + vertex -870.818 243.296 314.476 + endloop + endfacet + facet normal -0.72881 -0.679035 -0.088025 + outer loop + vertex -868.445 240.46 316.804 + vertex -871.489 243.723 316.836 + vertex -867.763 240.034 314.447 + endloop + endfacet + facet normal -0.715457 -0.693889 -0.0814792 + outer loop + vertex -864.775 236.957 314.414 + vertex -868.445 240.46 316.804 + vertex -867.763 240.034 314.447 + endloop + endfacet + facet normal -0.715819 -0.693357 -0.0828155 + outer loop + vertex -865.559 237.482 316.791 + vertex -868.445 240.46 316.804 + vertex -864.775 236.957 314.414 + endloop + endfacet + facet normal -0.710799 -0.698836 -0.0799483 + outer loop + vertex -862.281 234.413 314.468 + vertex -865.559 237.482 316.791 + vertex -864.775 236.957 314.414 + endloop + endfacet + facet normal -0.71077 -0.698878 -0.0798516 + outer loop + vertex -863.245 235.12 316.869 + vertex -865.559 237.482 316.791 + vertex -862.281 234.413 314.468 + endloop + endfacet + facet normal -0.715574 -0.693547 -0.0833516 + outer loop + vertex -860.678 232.73 314.715 + vertex -863.245 235.12 316.869 + vertex -862.281 234.413 314.468 + endloop + endfacet + facet normal -0.707885 -0.703499 -0.0631441 + outer loop + vertex -861.735 233.588 317.011 + vertex -863.245 235.12 316.869 + vertex -860.678 232.73 314.715 + endloop + endfacet + facet normal -0.731004 -0.677233 -0.0836006 + outer loop + vertex -860.083 232.036 315.131 + vertex -861.735 233.588 317.011 + vertex -860.678 232.73 314.715 + endloop + endfacet + facet normal -0.726741 -0.682774 -0.075279 + outer loop + vertex -860.816 232.624 316.873 + vertex -861.735 233.588 317.011 + vertex -860.083 232.036 315.131 + endloop + endfacet + facet normal -0.539919 -0.839825 0.0563998 + outer loop + vertex -860.816 232.624 316.873 + vertex -860.083 232.036 315.131 + vertex -859.214 231.432 314.444 + endloop + endfacet + facet normal -0.989478 0.137556 -0.0448616 + outer loop + vertex -907.198 361.127 316.889 + vertex -906.689 365.655 319.549 + vertex -906.62 365.282 316.886 + endloop + endfacet + facet normal -0.988346 0.14251 -0.0535123 + outer loop + vertex -907.32 361.113 319.107 + vertex -906.689 365.655 319.549 + vertex -907.198 361.127 316.889 + endloop + endfacet + facet normal -0.990889 0.123481 -0.0537791 + outer loop + vertex -907.715 356.987 316.911 + vertex -907.32 361.113 319.107 + vertex -907.198 361.127 316.889 + endloop + endfacet + facet normal -0.992158 0.117564 -0.042433 + outer loop + vertex -907.781 357.391 319.573 + vertex -907.32 361.113 319.107 + vertex -907.715 356.987 316.911 + endloop + endfacet + facet normal -0.993354 0.107565 -0.0409467 + outer loop + vertex -908.172 352.777 316.929 + vertex -907.781 357.391 319.573 + vertex -907.715 356.987 316.911 + endloop + endfacet + facet normal -0.992543 0.11183 -0.048507 + outer loop + vertex -908.282 352.759 319.148 + vertex -907.781 357.391 319.573 + vertex -908.172 352.777 316.929 + endloop + endfacet + facet normal -0.994792 0.089484 -0.0488049 + outer loop + vertex -908.558 348.48 316.934 + vertex -908.282 352.759 319.148 + vertex -908.172 352.777 316.929 + endloop + endfacet + facet normal -0.995974 0.0824753 -0.035115 + outer loop + vertex -908.617 348.905 319.595 + vertex -908.282 352.759 319.148 + vertex -908.558 348.48 316.934 + endloop + endfacet + facet normal -0.996986 0.0701348 -0.0331643 + outer loop + vertex -908.865 344.118 316.931 + vertex -908.617 348.905 319.595 + vertex -908.558 348.48 316.934 + endloop + endfacet + facet normal -0.996048 0.0766259 -0.0449168 + outer loop + vertex -908.964 344.138 319.152 + vertex -908.617 348.905 319.595 + vertex -908.865 344.118 316.931 + endloop + endfacet + facet normal -0.997741 0.0501004 -0.0447555 + outer loop + vertex -909.085 339.744 316.928 + vertex -908.964 344.138 319.152 + vertex -908.865 344.118 316.931 + endloop + endfacet + facet normal -0.998766 0.0413715 -0.0274573 + outer loop + vertex -909.137 340.262 319.593 + vertex -908.964 344.138 319.152 + vertex -909.085 339.744 316.928 + endloop + endfacet + facet normal -0.99938 0.0253989 -0.0243648 + outer loop + vertex -909.195 335.395 316.926 + vertex -909.137 340.262 319.593 + vertex -909.085 339.744 316.928 + endloop + endfacet + facet normal -0.998828 0.0319647 -0.036356 + outer loop + vertex -909.273 335.494 319.147 + vertex -909.137 340.262 319.593 + vertex -909.195 335.395 316.926 + endloop + endfacet + facet normal -0.999385 0.00171326 -0.0350351 + outer loop + vertex -909.203 331.09 316.926 + vertex -909.273 335.494 319.147 + vertex -909.195 335.395 316.926 + endloop + endfacet + facet normal -0.999798 -0.00635657 -0.0190492 + outer loop + vertex -909.257 331.692 319.592 + vertex -909.273 335.494 319.147 + vertex -909.203 331.09 316.926 + endloop + endfacet + facet normal -0.999554 -0.0260362 -0.0146025 + outer loop + vertex -909.092 326.834 316.928 + vertex -909.257 331.692 319.592 + vertex -909.203 331.09 316.926 + endloop + endfacet + facet normal -0.999399 -0.0176973 -0.0297965 + outer loop + vertex -909.161 326.992 319.15 + vertex -909.257 331.692 319.592 + vertex -909.092 326.834 316.928 + endloop + endfacet + facet normal -0.997979 -0.0575632 -0.0269235 + outer loop + vertex -908.849 322.629 316.929 + vertex -909.161 326.992 319.15 + vertex -909.092 326.834 316.928 + endloop + endfacet + facet normal -0.997637 -0.0684953 -0.00539485 + outer loop + vertex -908.908 323.278 319.596 + vertex -909.161 326.992 319.15 + vertex -908.849 322.629 316.929 + endloop + endfacet + facet normal -0.995997 -0.0893826 -0.000278621 + outer loop + vertex -908.474 318.447 316.93 + vertex -908.908 323.278 319.596 + vertex -908.849 322.629 316.929 + endloop + endfacet + facet normal -0.996646 -0.0799346 -0.0175043 + outer loop + vertex -908.528 318.63 319.155 + vertex -908.908 323.278 319.596 + vertex -908.474 318.447 316.93 + endloop + endfacet + facet normal -0.991948 -0.125911 -0.0136018 + outer loop + vertex -907.944 314.269 316.926 + vertex -908.528 318.63 319.155 + vertex -908.474 318.447 316.93 + endloop + endfacet + facet normal -0.990364 -0.13808 0.0106244 + outer loop + vertex -908.008 314.935 319.598 + vertex -908.528 318.63 319.155 + vertex -907.944 314.269 316.926 + endloop + endfacet + facet normal -0.986601 -0.162292 0.0167522 + outer loop + vertex -907.255 310.082 316.918 + vertex -908.008 314.935 319.598 + vertex -907.944 314.269 316.926 + endloop + endfacet + facet normal -0.988314 -0.152422 -0.00160113 + outer loop + vertex -907.291 310.292 319.146 + vertex -908.008 314.935 319.598 + vertex -907.255 310.082 316.918 + endloop + endfacet + facet normal -0.980077 -0.198598 0.00286718 + outer loop + vertex -906.409 305.908 316.906 + vertex -907.291 310.292 319.146 + vertex -907.255 310.082 316.918 + endloop + endfacet + facet normal -0.977578 -0.209145 0.0244884 + outer loop + vertex -906.497 306.63 319.584 + vertex -907.291 310.292 319.146 + vertex -906.409 305.908 316.906 + endloop + endfacet + facet normal -0.971306 -0.235688 0.0318588 + outer loop + vertex -905.405 301.77 316.896 + vertex -906.497 306.63 319.584 + vertex -906.409 305.908 316.906 + endloop + endfacet + facet normal -0.974602 -0.223766 0.00896762 + outer loop + vertex -905.448 302.044 319.125 + vertex -906.497 306.63 319.584 + vertex -905.405 301.77 316.896 + endloop + endfacet + facet normal -0.961964 -0.27275 0.0152187 + outer loop + vertex -904.245 297.678 316.888 + vertex -905.448 302.044 319.125 + vertex -905.405 301.77 316.896 + endloop + endfacet + facet normal -0.957461 -0.285432 0.0424 + outer loop + vertex -904.361 298.464 319.561 + vertex -905.448 302.044 319.125 + vertex -904.245 297.678 316.888 + endloop + endfacet + facet normal -0.948975 -0.3113 0.0503876 + outer loop + vertex -902.912 293.613 316.88 + vertex -904.361 298.464 319.561 + vertex -904.245 297.678 316.888 + endloop + endfacet + facet normal -0.955103 -0.295676 0.018795 + outer loop + vertex -902.969 293.936 319.097 + vertex -904.361 298.464 319.561 + vertex -902.912 293.613 316.88 + endloop + endfacet + facet normal -0.936963 -0.34839 0.0269345 + outer loop + vertex -901.411 289.575 316.87 + vertex -902.969 293.936 319.097 + vertex -902.912 293.613 316.88 + endloop + endfacet + facet normal -0.930363 -0.361992 0.058185 + outer loop + vertex -901.571 290.415 319.534 + vertex -902.969 293.936 319.097 + vertex -901.411 289.575 316.87 + endloop + endfacet + facet normal -0.9221 -0.381484 0.0648246 + outer loop + vertex -899.763 285.589 316.853 + vertex -901.571 290.415 319.534 + vertex -901.411 289.575 316.87 + endloop + endfacet + facet normal -0.930336 -0.365446 0.0303999 + outer loop + vertex -899.838 285.964 319.072 + vertex -901.571 290.415 319.534 + vertex -899.763 285.589 316.853 + endloop + endfacet + facet normal -0.91018 -0.412371 0.0390285 + outer loop + vertex -897.996 281.688 316.838 + vertex -899.838 285.964 319.072 + vertex -899.763 285.589 316.853 + endloop + endfacet + facet normal -0.90231 -0.425317 0.0703084 + outer loop + vertex -898.206 282.575 319.522 + vertex -899.838 285.964 319.072 + vertex -897.996 281.688 316.838 + endloop + endfacet + facet normal -0.891795 -0.44569 0.077862 + outer loop + vertex -896.099 277.89 316.835 + vertex -898.206 282.575 319.522 + vertex -897.996 281.688 316.838 + endloop + endfacet + facet normal -0.903726 -0.426652 0.0353181 + outer loop + vertex -896.201 278.293 319.073 + vertex -898.206 282.575 319.522 + vertex -896.099 277.89 316.835 + endloop + endfacet + facet normal -0.879204 -0.474316 0.0450054 + outer loop + vertex -894.092 274.172 316.839 + vertex -896.201 278.293 319.073 + vertex -896.099 277.89 316.835 + endloop + endfacet + facet normal -0.868465 -0.48891 0.0820647 + outer loop + vertex -894.342 275.068 319.534 + vertex -896.201 278.293 319.073 + vertex -894.092 274.172 316.839 + endloop + endfacet + facet normal -0.860252 -0.502341 0.0872914 + outer loop + vertex -891.957 270.515 316.845 + vertex -894.342 275.068 319.534 + vertex -894.092 274.172 316.839 + endloop + endfacet + facet normal -0.870337 -0.489242 0.0561705 + outer loop + vertex -892.054 270.945 319.086 + vertex -894.342 275.068 319.534 + vertex -891.957 270.515 316.845 + endloop + endfacet + facet normal -0.843945 -0.532404 0.0655997 + outer loop + vertex -889.686 266.917 316.848 + vertex -892.054 270.945 319.086 + vertex -891.957 270.515 316.845 + endloop + endfacet + facet normal -0.835041 -0.542299 0.09283 + outer loop + vertex -889.985 267.838 319.541 + vertex -892.054 270.945 319.086 + vertex -889.686 266.917 316.848 + endloop + endfacet + facet normal -0.825839 -0.555274 0.0982865 + outer loop + vertex -887.311 263.384 316.845 + vertex -889.985 267.838 319.541 + vertex -889.686 266.917 316.848 + endloop + endfacet + facet normal -0.83928 -0.540344 0.0603005 + outer loop + vertex -887.453 263.854 319.087 + vertex -889.985 267.838 319.541 + vertex -887.311 263.384 316.845 + endloop + endfacet + facet normal -0.812334 -0.578965 0.0700952 + outer loop + vertex -884.862 259.946 316.838 + vertex -887.453 263.854 319.087 + vertex -887.311 263.384 316.845 + endloop + endfacet + facet normal -0.799423 -0.591278 0.106361 + outer loop + vertex -885.221 260.918 319.54 + vertex -887.453 263.854 319.087 + vertex -884.862 259.946 316.838 + endloop + endfacet + facet normal -0.795179 -0.596531 0.108814 + outer loop + vertex -882.365 256.616 316.829 + vertex -885.221 260.918 319.54 + vertex -884.862 259.946 316.838 + endloop + endfacet + facet normal -0.807684 -0.584602 0.0767215 + outer loop + vertex -882.526 257.135 319.085 + vertex -885.221 260.918 319.54 + vertex -882.365 256.616 316.829 + endloop + endfacet + facet normal -0.781203 -0.618277 0.086347 + outer loop + vertex -879.813 253.392 316.828 + vertex -882.526 257.135 319.085 + vertex -882.365 256.616 316.829 + endloop + endfacet + facet normal -0.770136 -0.627452 0.114872 + outer loop + vertex -880.185 254.345 319.543 + vertex -882.526 257.135 319.085 + vertex -879.813 253.392 316.828 + endloop + endfacet + facet normal -0.767066 -0.630901 0.116503 + outer loop + vertex -877.197 250.212 316.834 + vertex -880.185 254.345 319.543 + vertex -879.813 253.392 316.828 + endloop + endfacet + facet normal -0.780077 -0.619845 0.0852763 + outer loop + vertex -877.317 250.674 319.096 + vertex -880.185 254.345 319.543 + vertex -877.197 250.212 316.834 + endloop + endfacet + facet normal -0.755314 -0.648802 0.0925071 + outer loop + vertex -874.439 247.002 316.844 + vertex -877.317 250.674 319.096 + vertex -877.197 250.212 316.834 + endloop + endfacet + facet normal -0.740981 -0.659245 0.127843 + outer loop + vertex -874.742 247.868 319.549 + vertex -877.317 250.674 319.096 + vertex -874.439 247.002 316.844 + endloop + endfacet + facet normal -0.737083 -0.663266 0.129566 + outer loop + vertex -871.489 243.723 316.836 + vertex -874.742 247.868 319.549 + vertex -874.439 247.002 316.844 + endloop + endfacet + facet normal -0.750513 -0.653473 0.0985035 + outer loop + vertex -871.573 244.157 319.079 + vertex -874.742 247.868 319.549 + vertex -871.489 243.723 316.836 + endloop + endfacet + facet normal -0.726706 -0.67898 0.104327 + outer loop + vertex -868.445 240.46 316.804 + vertex -871.573 244.157 319.079 + vertex -871.489 243.723 316.836 + endloop + endfacet + facet normal -0.712202 -0.688068 0.139036 + outer loop + vertex -868.939 241.521 319.522 + vertex -871.573 244.157 319.079 + vertex -868.445 240.46 316.804 + endloop + endfacet + facet normal -0.710777 -0.689384 0.139809 + outer loop + vertex -865.559 237.482 316.791 + vertex -868.939 241.521 319.522 + vertex -868.445 240.46 316.804 + endloop + endfacet + facet normal -0.728914 -0.677331 0.0995343 + outer loop + vertex -865.985 238.278 319.085 + vertex -868.939 241.521 319.522 + vertex -865.559 237.482 316.791 + endloop + endfacet + facet normal -0.711919 -0.693842 0.108415 + outer loop + vertex -863.245 235.12 316.869 + vertex -865.985 238.278 319.085 + vertex -865.559 237.482 316.791 + endloop + endfacet + facet normal -0.692685 -0.705673 0.149043 + outer loop + vertex -864.154 236.599 319.646 + vertex -865.985 238.278 319.085 + vertex -863.245 235.12 316.869 + endloop + endfacet + facet normal -0.712038 -0.689242 0.133965 + outer loop + vertex -861.735 233.588 317.011 + vertex -864.154 236.599 319.646 + vertex -863.245 235.12 316.869 + endloop + endfacet + facet normal -0.733045 -0.673305 0.0964685 + outer loop + vertex -862.096 234.288 319.16 + vertex -864.154 236.599 319.646 + vertex -861.735 233.588 317.011 + endloop + endfacet + facet normal -0.711562 -0.694434 0.106962 + outer loop + vertex -860.816 232.624 316.873 + vertex -862.096 234.288 319.16 + vertex -861.735 233.588 317.011 + endloop + endfacet + facet normal -0.802376 -0.59663 -0.0150555 + outer loop + vertex -861.139 233.022 318.335 + vertex -862.096 234.288 319.16 + vertex -860.816 232.624 316.873 + endloop + endfacet + facet normal -0.994247 0.106721 0.00917717 + outer loop + vertex -908.282 352.759 319.148 + vertex -907.878 356.229 322.64 + vertex -907.781 357.391 319.573 + endloop + endfacet + facet normal -0.992311 0.122818 0.0153356 + outer loop + vertex -907.878 356.229 322.64 + vertex -906.851 364.528 322.616 + vertex -907.781 357.391 319.573 + endloop + endfacet + facet normal -0.992257 0.122821 0.0184583 + outer loop + vertex -907.878 356.229 322.64 + vertex -906.66 365.376 327.238 + vertex -906.851 364.528 322.616 + endloop + endfacet + facet normal -0.988823 0.148475 0.013605 + outer loop + vertex -906.66 365.376 327.238 + vertex -905.434 373.538 327.235 + vertex -906.851 364.528 322.616 + endloop + endfacet + facet normal -0.988453 0.151322 0.00793879 + outer loop + vertex -906.851 364.528 322.616 + vertex -905.434 373.538 327.235 + vertex -905.58 372.821 322.732 + endloop + endfacet + facet normal -0.988468 0.151387 0.0035445 + outer loop + vertex -906.851 364.528 322.616 + vertex -905.58 372.821 322.732 + vertex -906.689 365.655 319.549 + endloop + endfacet + facet normal -0.984773 0.173794 0.00423954 + outer loop + vertex -905.434 373.538 327.235 + vertex -903.997 381.679 327.355 + vertex -905.58 372.821 322.732 + endloop + endfacet + facet normal -0.984663 0.173579 0.0176047 + outer loop + vertex -905.434 373.538 327.235 + vertex -903.732 382.763 331.509 + vertex -903.997 381.679 327.355 + endloop + endfacet + facet normal -0.980873 0.19428 0.0119631 + outer loop + vertex -903.732 382.763 331.509 + vertex -902.143 390.785 331.517 + vertex -903.997 381.679 327.355 + endloop + endfacet + facet normal -0.98085 0.194415 0.0116567 + outer loop + vertex -903.997 381.679 327.355 + vertex -902.143 390.785 331.517 + vertex -902.41 389.68 327.464 + endloop + endfacet + facet normal -0.980883 0.194595 -0.00102197 + outer loop + vertex -903.997 381.679 327.355 + vertex -902.41 389.68 327.464 + vertex -904.096 381.161 323.411 + endloop + endfacet + facet normal -0.976949 0.213383 0.00622692 + outer loop + vertex -902.143 390.785 331.517 + vertex -900.396 398.781 331.508 + vertex -902.41 389.68 327.464 + endloop + endfacet + facet normal -0.976806 0.214079 0.0045907 + outer loop + vertex -902.41 389.68 327.464 + vertex -900.396 398.781 331.508 + vertex -900.666 397.635 327.445 + endloop + endfacet + facet normal -0.973334 0.229392 3.94332e-05 + outer loop + vertex -900.396 398.781 331.508 + vertex -898.514 406.767 331.485 + vertex -900.666 397.635 327.445 + endloop + endfacet + facet normal -0.973179 0.229404 0.0172108 + outer loop + vertex -900.396 398.781 331.508 + vertex -898.189 407.853 335.399 + vertex -898.514 406.767 331.485 + endloop + endfacet + facet normal -0.969717 0.243888 0.0129054 + outer loop + vertex -898.189 407.853 335.399 + vertex -896.236 415.62 335.38 + vertex -898.514 406.767 331.485 + endloop + endfacet + facet normal -0.969852 0.243269 0.0143908 + outer loop + vertex -898.514 406.767 331.485 + vertex -896.236 415.62 335.38 + vertex -896.524 414.703 331.48 + endloop + endfacet + facet normal -0.969318 0.243832 0.0311291 + outer loop + vertex -898.189 407.853 335.399 + vertex -895.879 416.563 339.113 + vertex -896.236 415.62 335.38 + endloop + endfacet + facet normal -0.966482 0.255205 0.0279855 + outer loop + vertex -895.879 416.563 339.113 + vertex -893.901 424.05 339.131 + vertex -896.236 415.62 335.38 + endloop + endfacet + facet normal -0.966499 0.255119 0.0281877 + outer loop + vertex -896.236 415.62 335.38 + vertex -893.901 424.05 339.131 + vertex -894.211 423.289 335.404 + endloop + endfacet + facet normal -0.965704 0.25495 0.0491557 + outer loop + vertex -895.879 416.563 339.113 + vertex -893.513 424.835 342.678 + vertex -893.901 424.05 339.131 + endloop + endfacet + facet normal -0.963697 0.262793 0.0472022 + outer loop + vertex -893.513 424.835 342.678 + vertex -891.514 432.155 342.743 + vertex -893.901 424.05 339.131 + endloop + endfacet + facet normal -0.963654 0.263064 0.0465655 + outer loop + vertex -893.901 424.05 339.131 + vertex -891.514 432.155 342.743 + vertex -891.85 431.552 339.199 + endloop + endfacet + facet normal -0.96237 0.262218 0.0713194 + outer loop + vertex -893.513 424.835 342.678 + vertex -891.094 432.786 346.095 + vertex -891.514 432.155 342.743 + endloop + endfacet + facet normal -0.961366 0.266104 0.0704626 + outer loop + vertex -891.094 432.786 346.095 + vertex -889.059 440.121 346.153 + vertex -891.514 432.155 342.743 + endloop + endfacet + facet normal -0.961318 0.266574 0.0693313 + outer loop + vertex -891.514 432.155 342.743 + vertex -889.059 440.121 346.153 + vertex -889.42 439.691 342.803 + endloop + endfacet + facet normal -0.958886 0.26517 0.101103 + outer loop + vertex -891.094 432.786 346.095 + vertex -888.608 440.563 349.274 + vertex -889.059 440.121 346.153 + endloop + endfacet + facet normal -0.958894 0.265142 0.101108 + outer loop + vertex -888.608 440.563 349.274 + vertex -886.572 447.948 349.212 + vertex -889.059 440.121 346.153 + endloop + endfacet + facet normal -0.958877 0.266582 0.0974087 + outer loop + vertex -889.059 440.121 346.153 + vertex -886.572 447.948 349.212 + vertex -886.95 447.733 346.081 + endloop + endfacet + facet normal -0.954461 0.264235 0.138508 + outer loop + vertex -888.608 440.563 349.274 + vertex -886.104 448.145 352.066 + vertex -886.572 447.948 349.212 + endloop + endfacet + facet normal -0.955236 0.261243 0.138842 + outer loop + vertex -886.104 448.145 352.066 + vertex -884.205 455.241 351.776 + vertex -886.572 447.948 349.212 + endloop + endfacet + facet normal -0.955634 0.264897 0.128815 + outer loop + vertex -886.572 447.948 349.212 + vertex -884.205 455.241 351.776 + vertex -884.585 455.278 348.88 + endloop + endfacet + facet normal -0.954251 0.26234 0.143467 + outer loop + vertex -888.056 441.019 352.113 + vertex -886.104 448.145 352.066 + vertex -888.608 440.563 349.274 + endloop + endfacet + facet normal -0.954101 0.262955 0.143339 + outer loop + vertex -890.579 433.443 349.215 + vertex -888.056 441.019 352.113 + vertex -888.608 440.563 349.274 + endloop + endfacet + facet normal -0.954021 0.2622 0.145243 + outer loop + vertex -889.954 434.143 352.058 + vertex -888.056 441.019 352.113 + vertex -890.579 433.443 349.215 + endloop + endfacet + facet normal -0.954627 0.259542 0.146031 + outer loop + vertex -892.471 426.515 349.163 + vertex -889.954 434.143 352.058 + vertex -890.579 433.443 349.215 + endloop + endfacet + facet normal -0.959742 0.261264 0.103133 + outer loop + vertex -892.471 426.515 349.163 + vertex -890.579 433.443 349.215 + vertex -893.041 425.654 346.034 + endloop + endfacet + facet normal -0.96168 0.252949 0.105772 + outer loop + vertex -894.914 418.54 346.015 + vertex -892.471 426.515 349.163 + vertex -893.041 425.654 346.034 + endloop + endfacet + facet normal -0.96437 0.253742 0.0748672 + outer loop + vertex -894.914 418.54 346.015 + vertex -893.041 425.654 346.034 + vertex -895.44 417.532 342.661 + endloop + endfacet + facet normal -0.966911 0.242708 0.0785839 + outer loop + vertex -897.293 410.145 342.675 + vertex -894.914 418.54 346.015 + vertex -895.44 417.532 342.661 + endloop + endfacet + facet normal -0.968544 0.24307 0.0532814 + outer loop + vertex -897.293 410.145 342.675 + vertex -895.44 417.532 342.661 + vertex -897.782 408.975 339.13 + endloop + endfacet + facet normal -0.9716 0.229352 0.0582301 + outer loop + vertex -899.59 401.308 339.157 + vertex -897.293 410.145 342.675 + vertex -897.782 408.975 339.13 + endloop + endfacet + facet normal -0.972611 0.229514 0.0367507 + outer loop + vertex -899.59 401.308 339.157 + vertex -897.782 408.975 339.13 + vertex -900.04 399.998 335.427 + endloop + endfacet + facet normal -0.976138 0.212846 0.04303 + outer loop + vertex -901.76 392.107 335.451 + vertex -899.59 401.308 339.157 + vertex -900.04 399.998 335.427 + endloop + endfacet + facet normal -0.976785 0.212927 0.0235315 + outer loop + vertex -901.76 392.107 335.451 + vertex -900.04 399.998 335.427 + vertex -902.143 390.785 331.517 + endloop + endfacet + facet normal -0.976183 0.212412 0.0441351 + outer loop + vertex -901.267 393.598 339.175 + vertex -899.59 401.308 339.157 + vertex -901.76 392.107 335.451 + endloop + endfacet + facet normal -0.979641 0.193904 0.0520021 + outer loop + vertex -903.322 384.207 335.476 + vertex -901.267 393.598 339.175 + vertex -901.76 392.107 335.451 + endloop + endfacet + facet normal -0.980521 0.194011 0.0306252 + outer loop + vertex -903.322 384.207 335.476 + vertex -901.76 392.107 335.451 + vertex -903.732 382.763 331.509 + endloop + endfacet + facet normal -0.984256 0.172423 0.0388679 + outer loop + vertex -905.139 374.724 331.523 + vertex -903.322 384.207 335.476 + vertex -903.732 382.763 331.509 + endloop + endfacet + facet normal -0.984333 0.171398 0.0413631 + outer loop + vertex -904.698 376.302 335.497 + vertex -903.322 384.207 335.476 + vertex -905.139 374.724 331.523 + endloop + endfacet + facet normal -0.987797 0.14701 0.0514351 + outer loop + vertex -906.338 366.657 331.554 + vertex -904.698 376.302 335.497 + vertex -905.139 374.724 331.523 + endloop + endfacet + facet normal -0.988673 0.147058 0.0299818 + outer loop + vertex -906.338 366.657 331.554 + vertex -905.139 374.724 331.523 + vertex -906.66 365.376 327.238 + endloop + endfacet + facet normal -0.992123 0.119202 0.0385055 + outer loop + vertex -907.648 357.144 327.267 + vertex -906.338 366.657 331.554 + vertex -906.66 365.376 327.238 + endloop + endfacet + facet normal -0.992203 0.115787 0.046108 + outer loop + vertex -907.284 358.547 331.564 + vertex -906.338 366.657 331.554 + vertex -907.648 357.144 327.267 + endloop + endfacet + facet normal -0.994871 0.0836938 0.0568111 + outer loop + vertex -908.346 348.835 327.275 + vertex -907.284 358.547 331.564 + vertex -907.648 357.144 327.267 + endloop + endfacet + facet normal -0.995596 0.0837408 0.0421396 + outer loop + vertex -908.346 348.835 327.275 + vertex -907.648 357.144 327.267 + vertex -908.631 347.775 322.657 + endloop + endfacet + facet normal -0.99756 0.0483216 0.0503881 + outer loop + vertex -909.043 339.27 322.657 + vertex -908.346 348.835 327.275 + vertex -908.631 347.775 322.657 + endloop + endfacet + facet normal -0.997764 0.0483313 0.0461705 + outer loop + vertex -909.043 339.27 322.657 + vertex -908.631 347.775 322.657 + vertex -909.137 340.262 319.593 + endloop + endfacet + facet normal -0.998942 0.0249482 0.0386316 + outer loop + vertex -909.273 335.494 319.147 + vertex -909.043 339.27 322.657 + vertex -909.137 340.262 319.593 + endloop + endfacet + facet normal -0.998069 0.00314679 0.0620285 + outer loop + vertex -909.273 335.494 319.147 + vertex -909.257 331.692 319.592 + vertex -909.043 339.27 322.657 + endloop + endfacet + facet normal -0.997546 -9.75429e-05 0.0700137 + outer loop + vertex -909.042 330.837 322.656 + vertex -909.043 339.27 322.657 + vertex -909.257 331.692 319.592 + endloop + endfacet + facet normal -0.997684 -0.0263752 0.0626919 + outer loop + vertex -909.161 326.992 319.15 + vertex -909.042 330.837 322.656 + vertex -909.257 331.692 319.592 + endloop + endfacet + facet normal -0.993874 -0.0561317 0.0952008 + outer loop + vertex -909.161 326.992 319.15 + vertex -908.908 323.278 319.596 + vertex -909.042 330.837 322.656 + endloop + endfacet + facet normal -0.993448 -0.0575543 0.0987347 + outer loop + vertex -908.559 322.498 322.659 + vertex -909.042 330.837 322.656 + vertex -908.908 323.278 319.596 + endloop + endfacet + facet normal -0.991855 -0.0897937 0.0903414 + outer loop + vertex -908.528 318.63 319.155 + vertex -908.559 322.498 322.659 + vertex -908.908 323.278 319.596 + endloop + endfacet + facet normal -0.98418 -0.123218 0.127305 + outer loop + vertex -908.528 318.63 319.155 + vertex -908.008 314.935 319.598 + vertex -908.559 322.498 322.659 + endloop + endfacet + facet normal -0.984457 -0.122606 0.125743 + outer loop + vertex -907.526 314.208 322.663 + vertex -908.559 322.498 322.659 + vertex -908.008 314.935 319.598 + endloop + endfacet + facet normal -0.979916 -0.162509 0.115565 + outer loop + vertex -907.291 310.292 319.146 + vertex -907.526 314.208 322.663 + vertex -908.008 314.935 319.598 + endloop + endfacet + facet normal -0.969818 -0.192505 0.149651 + outer loop + vertex -907.291 310.292 319.146 + vertex -906.497 306.63 319.584 + vertex -907.526 314.208 322.663 + endloop + endfacet + facet normal -0.968464 -0.194689 0.155478 + outer loop + vertex -905.878 306.007 322.653 + vertex -907.526 314.208 322.663 + vertex -906.497 306.63 319.584 + endloop + endfacet + facet normal -0.961126 -0.234398 0.145929 + outer loop + vertex -905.448 302.044 319.125 + vertex -905.878 306.007 322.653 + vertex -906.497 306.63 319.584 + endloop + endfacet + facet normal -0.946821 -0.265176 0.182242 + outer loop + vertex -905.448 302.044 319.125 + vertex -904.361 298.464 319.561 + vertex -905.878 306.007 322.653 + endloop + endfacet + facet normal -0.946532 -0.265523 0.183232 + outer loop + vertex -903.61 297.912 322.641 + vertex -905.878 306.007 322.653 + vertex -904.361 298.464 319.561 + endloop + endfacet + facet normal -0.936188 -0.305696 0.173499 + outer loop + vertex -902.969 293.936 319.097 + vertex -903.61 297.912 322.641 + vertex -904.361 298.464 319.561 + endloop + endfacet + facet normal -0.916992 -0.337497 0.212652 + outer loop + vertex -902.969 293.936 319.097 + vertex -901.571 290.415 319.534 + vertex -903.61 297.912 322.641 + endloop + endfacet + facet normal -0.921233 -0.333512 0.20025 + outer loop + vertex -900.729 289.949 322.635 + vertex -903.61 297.912 322.641 + vertex -901.571 290.415 319.534 + endloop + endfacet + facet normal -0.907884 -0.373367 0.190639 + outer loop + vertex -899.838 285.964 319.072 + vertex -900.729 289.949 322.635 + vertex -901.571 290.415 319.534 + endloop + endfacet + facet normal -0.889395 -0.398719 0.223606 + outer loop + vertex -899.838 285.964 319.072 + vertex -898.206 282.575 319.522 + vertex -900.729 289.949 322.635 + endloop + endfacet + facet normal -0.890574 -0.397814 0.220506 + outer loop + vertex -897.284 282.241 322.64 + vertex -900.729 289.949 322.635 + vertex -898.206 282.575 319.522 + endloop + endfacet + facet normal -0.876273 -0.432384 0.212579 + outer loop + vertex -896.201 278.293 319.073 + vertex -897.284 282.241 322.64 + vertex -898.206 282.575 319.522 + endloop + endfacet + facet normal -0.854407 -0.45727 0.246763 + outer loop + vertex -896.201 278.293 319.073 + vertex -894.342 275.068 319.534 + vertex -897.284 282.241 322.64 + endloop + endfacet + facet normal -0.855959 -0.456324 0.243108 + outer loop + vertex -893.336 274.838 322.648 + vertex -897.284 282.241 322.64 + vertex -894.342 275.068 319.534 + endloop + endfacet + facet normal -0.838773 -0.491163 0.234988 + outer loop + vertex -892.054 270.945 319.086 + vertex -893.336 274.838 322.648 + vertex -894.342 275.068 319.534 + endloop + endfacet + facet normal -0.820888 -0.508361 0.260215 + outer loop + vertex -892.054 270.945 319.086 + vertex -889.985 267.838 319.541 + vertex -893.336 274.838 322.648 + endloop + endfacet + facet normal -0.821374 -0.50812 0.25915 + outer loop + vertex -888.931 267.721 322.654 + vertex -893.336 274.838 322.648 + vertex -889.985 267.838 319.541 + endloop + endfacet + facet normal -0.803471 -0.539419 0.251916 + outer loop + vertex -887.453 263.854 319.087 + vertex -888.931 267.721 322.654 + vertex -889.985 267.838 319.541 + endloop + endfacet + facet normal -0.785267 -0.554393 0.275689 + outer loop + vertex -887.453 263.854 319.087 + vertex -885.221 260.918 319.54 + vertex -888.931 267.721 322.654 + endloop + endfacet + facet normal -0.788958 -0.552903 0.268036 + outer loop + vertex -884.146 260.897 322.66 + vertex -888.931 267.721 322.654 + vertex -885.221 260.918 319.54 + endloop + endfacet + facet normal -0.770938 -0.580687 0.261645 + outer loop + vertex -882.526 257.135 319.085 + vertex -884.146 260.897 322.66 + vertex -885.221 260.918 319.54 + endloop + endfacet + facet normal -0.75782 -0.590376 0.277785 + outer loop + vertex -882.526 257.135 319.085 + vertex -880.185 254.345 319.543 + vertex -884.146 260.897 322.66 + endloop + endfacet + facet normal -0.755723 -0.59109 0.28195 + outer loop + vertex -878.994 254.31 322.66 + vertex -884.146 260.897 322.66 + vertex -880.185 254.345 319.543 + endloop + endfacet + facet normal -0.740824 -0.612366 0.27602 + outer loop + vertex -877.317 250.674 319.096 + vertex -878.994 254.31 322.66 + vertex -880.185 254.345 319.543 + endloop + endfacet + facet normal -0.727886 -0.620949 0.290867 + outer loop + vertex -877.317 250.674 319.096 + vertex -874.742 247.868 319.549 + vertex -878.994 254.31 322.66 + endloop + endfacet + facet normal -0.726456 -0.621332 0.293614 + outer loop + vertex -873.54 247.93 322.652 + vertex -878.994 254.31 322.66 + vertex -874.742 247.868 319.549 + endloop + endfacet + facet normal -0.709967 -0.642805 0.28766 + outer loop + vertex -871.573 244.157 319.079 + vertex -873.54 247.93 322.652 + vertex -874.742 247.868 319.549 + endloop + endfacet + facet normal -0.699728 -0.648625 0.299443 + outer loop + vertex -871.573 244.157 319.079 + vertex -868.939 241.521 319.522 + vertex -873.54 247.93 322.652 + endloop + endfacet + facet normal -0.704891 -0.647514 0.289576 + outer loop + vertex -868.305 242.258 322.715 + vertex -873.54 247.93 322.652 + vertex -868.939 241.521 319.522 + endloop + endfacet + facet normal -0.687664 -0.665467 0.290295 + outer loop + vertex -865.985 238.278 319.085 + vertex -868.305 242.258 322.715 + vertex -868.939 241.521 319.522 + endloop + endfacet + facet normal -0.693848 -0.662258 0.282824 + outer loop + vertex -865.985 238.278 319.085 + vertex -864.154 236.599 319.646 + vertex -868.305 242.258 322.715 + endloop + endfacet + facet normal -0.685249 -0.664384 0.298375 + outer loop + vertex -863.66 237.604 323.019 + vertex -868.305 242.258 322.715 + vertex -864.154 236.599 319.646 + endloop + endfacet + facet normal -0.680396 -0.669049 0.299056 + outer loop + vertex -862.096 234.288 319.16 + vertex -863.66 237.604 323.019 + vertex -864.154 236.599 319.646 + endloop + endfacet + facet normal -0.993356 -0.0575486 0.0996583 + outer loop + vertex -908.559 322.498 322.659 + vertex -908.658 332.213 327.275 + vertex -909.042 330.837 322.656 + endloop + endfacet + facet normal -0.991396 -0.0643396 0.113993 + outer loop + vertex -908.124 323.98 327.278 + vertex -908.658 332.213 327.275 + vertex -908.559 322.498 322.659 + endloop + endfacet + facet normal -0.988511 -0.0641434 0.136862 + outer loop + vertex -908.124 323.98 327.278 + vertex -908.184 334.053 331.56 + vertex -908.658 332.213 327.275 + endloop + endfacet + facet normal -0.986808 -0.0683424 0.146763 + outer loop + vertex -907.622 325.94 331.564 + vertex -908.184 334.053 331.56 + vertex -908.124 323.98 327.278 + endloop + endfacet + facet normal -0.981032 -0.0679253 0.181555 + outer loop + vertex -907.622 325.94 331.564 + vertex -907.615 336.354 335.501 + vertex -908.184 334.053 331.56 + endloop + endfacet + facet normal -0.978746 -0.0718975 0.192059 + outer loop + vertex -907.028 328.371 335.499 + vertex -907.615 336.354 335.501 + vertex -907.622 325.94 331.564 + endloop + endfacet + facet normal -0.969758 -0.0712471 0.233439 + outer loop + vertex -907.028 328.371 335.499 + vertex -906.923 338.975 339.173 + vertex -907.615 336.354 335.501 + endloop + endfacet + facet normal -0.969638 -0.0714033 0.233887 + outer loop + vertex -906.344 331.118 339.174 + vertex -906.923 338.975 339.173 + vertex -907.028 328.371 335.499 + endloop + endfacet + facet normal -0.959724 -0.0706647 0.271914 + outer loop + vertex -906.344 331.118 339.174 + vertex -906.136 341.753 342.674 + vertex -906.923 338.975 339.173 + endloop + endfacet + facet normal -0.956545 -0.0740543 0.282025 + outer loop + vertex -905.539 334.033 342.671 + vertex -906.136 341.753 342.674 + vertex -906.344 331.118 339.174 + endloop + endfacet + facet normal -0.945249 -0.0731933 0.318037 + outer loop + vertex -905.539 334.033 342.671 + vertex -905.234 344.627 346.016 + vertex -906.136 341.753 342.674 + endloop + endfacet + facet normal -0.94407 -0.07425 0.321276 + outer loop + vertex -904.638 337.052 346.016 + vertex -905.234 344.627 346.016 + vertex -905.539 334.033 342.671 + endloop + endfacet + facet normal -0.928278 -0.0730083 0.364651 + outer loop + vertex -904.638 337.052 346.016 + vertex -904.236 347.617 349.155 + vertex -905.234 344.627 346.016 + endloop + endfacet + facet normal -0.924737 -0.0756288 0.373017 + outer loop + vertex -903.629 340.194 349.155 + vertex -904.236 347.617 349.155 + vertex -904.638 337.052 346.016 + endloop + endfacet + facet normal -0.997323 -9.80065e-05 0.0731167 + outer loop + vertex -909.042 330.837 322.656 + vertex -908.705 340.506 327.273 + vertex -909.043 339.27 322.657 + endloop + endfacet + facet normal -0.996415 -0.00552721 0.0844181 + outer loop + vertex -908.658 332.213 327.275 + vertex -908.705 340.506 327.273 + vertex -909.042 330.837 322.656 + endloop + endfacet + facet normal -0.994691 -0.00551391 0.102757 + outer loop + vertex -908.658 332.213 327.275 + vertex -908.271 342.207 331.562 + vertex -908.705 340.506 327.273 + endloop + endfacet + facet normal -0.993379 -0.0105558 0.114393 + outer loop + vertex -908.184 334.053 331.56 + vertex -908.271 342.207 331.562 + vertex -908.658 332.213 327.275 + endloop + endfacet + facet normal -0.989342 -0.0105183 0.145233 + outer loop + vertex -908.184 334.053 331.56 + vertex -907.716 344.375 335.5 + vertex -908.271 342.207 331.562 + endloop + endfacet + facet normal -0.988566 -0.0124758 0.150269 + outer loop + vertex -907.615 336.354 335.501 + vertex -907.716 344.375 335.5 + vertex -908.184 334.053 331.56 + endloop + endfacet + facet normal -0.981912 -0.0123867 0.188931 + outer loop + vertex -907.615 336.354 335.501 + vertex -907.04 346.855 339.173 + vertex -907.716 344.375 335.5 + endloop + endfacet + facet normal -0.980686 -0.0145911 0.195044 + outer loop + vertex -906.923 338.975 339.173 + vertex -907.04 346.855 339.173 + vertex -907.615 336.354 335.501 + endloop + endfacet + facet normal -0.973405 -0.0144837 0.228631 + outer loop + vertex -906.923 338.975 339.173 + vertex -906.258 349.483 342.672 + vertex -907.04 346.855 339.173 + endloop + endfacet + facet normal -0.972851 -0.0152837 0.230928 + outer loop + vertex -906.136 341.753 342.674 + vertex -906.258 349.483 342.672 + vertex -906.923 338.975 339.173 + endloop + endfacet + facet normal -0.964006 -0.0151346 0.265449 + outer loop + vertex -906.136 341.753 342.674 + vertex -905.379 352.2 346.017 + vertex -906.258 349.483 342.672 + endloop + endfacet + facet normal -0.961179 -0.0184938 0.275306 + outer loop + vertex -905.234 344.627 346.016 + vertex -905.379 352.2 346.017 + vertex -906.136 341.753 342.674 + endloop + endfacet + facet normal -0.949544 -0.0182713 0.313102 + outer loop + vertex -905.234 344.627 346.016 + vertex -904.398 355.023 349.156 + vertex -905.379 352.2 346.017 + endloop + endfacet + facet normal -0.946892 -0.020833 0.320877 + outer loop + vertex -904.236 347.617 349.155 + vertex -904.398 355.023 349.156 + vertex -905.234 344.627 346.016 + endloop + endfacet + facet normal -0.997829 0.049412 0.0435307 + outer loop + vertex -908.964 344.138 319.152 + vertex -909.137 340.262 319.593 + vertex -908.631 347.775 322.657 + endloop + endfacet + facet normal -0.997276 0.0705386 0.0215506 + outer loop + vertex -908.964 344.138 319.152 + vertex -908.631 347.775 322.657 + vertex -908.617 348.905 319.595 + endloop + endfacet + facet normal -0.995649 0.088782 0.0282937 + outer loop + vertex -908.631 347.775 322.657 + vertex -907.878 356.229 322.64 + vertex -908.617 348.905 319.595 + endloop + endfacet + facet normal -0.99718 0.0428833 0.0615949 + outer loop + vertex -908.705 340.506 327.273 + vertex -908.346 348.835 327.275 + vertex -909.043 339.27 322.657 + endloop + endfacet + facet normal -0.996163 0.0428367 0.0763146 + outer loop + vertex -908.705 340.506 327.273 + vertex -907.951 350.383 331.567 + vertex -908.346 348.835 327.275 + endloop + endfacet + facet normal -0.995602 0.0389233 0.0852191 + outer loop + vertex -908.271 342.207 331.562 + vertex -907.951 350.383 331.567 + vertex -908.705 340.506 327.273 + endloop + endfacet + facet normal -0.992493 0.0387829 0.11599 + outer loop + vertex -908.271 342.207 331.562 + vertex -907.412 352.405 335.5 + vertex -907.951 350.383 331.567 + endloop + endfacet + facet normal -0.992345 0.0777685 0.095934 + outer loop + vertex -907.412 352.405 335.5 + vertex -906.784 360.41 335.509 + vertex -907.951 350.383 331.567 + endloop + endfacet + facet normal -0.992848 0.081098 0.0876153 + outer loop + vertex -907.951 350.383 331.567 + vertex -906.784 360.41 335.509 + vertex -907.284 358.547 331.564 + endloop + endfacet + facet normal -0.990823 0.114726 0.0714747 + outer loop + vertex -906.784 360.41 335.509 + vertex -905.862 368.376 335.508 + vertex -907.284 358.547 331.564 + endloop + endfacet + facet normal -0.98832 0.114441 0.100633 + outer loop + vertex -906.784 360.41 335.509 + vertex -905.255 370.382 339.182 + vertex -905.862 368.376 335.508 + endloop + endfacet + facet normal -0.986065 0.143296 0.0845087 + outer loop + vertex -905.255 370.382 339.182 + vertex -904.127 378.143 339.188 + vertex -905.862 368.376 335.508 + endloop + endfacet + facet normal -0.986186 0.144956 0.0801597 + outer loop + vertex -905.862 368.376 335.508 + vertex -904.127 378.143 339.188 + vertex -904.698 376.302 335.497 + endloop + endfacet + facet normal -0.983104 0.170337 0.0670286 + outer loop + vertex -904.127 378.143 339.188 + vertex -902.787 385.876 339.185 + vertex -904.698 376.302 335.497 + endloop + endfacet + facet normal -0.981173 0.170012 0.0916259 + outer loop + vertex -904.127 378.143 339.188 + vertex -902.153 387.648 342.69 + vertex -902.787 385.876 339.185 + endloop + endfacet + facet normal -0.978185 0.19165 0.0801489 + outer loop + vertex -902.153 387.648 342.69 + vertex -900.678 395.176 342.695 + vertex -902.787 385.876 339.185 + endloop + endfacet + facet normal -0.978202 0.192708 0.0773567 + outer loop + vertex -902.787 385.876 339.185 + vertex -900.678 395.176 342.695 + vertex -901.267 393.598 339.175 + endloop + endfacet + facet normal -0.974953 0.211659 0.0683168 + outer loop + vertex -900.678 395.176 342.695 + vertex -899.049 402.682 342.69 + vertex -901.267 393.598 339.175 + endloop + endfacet + facet normal -0.972914 0.211233 0.0939065 + outer loop + vertex -900.678 395.176 342.695 + vertex -898.419 404.098 346.031 + vertex -899.049 402.682 342.69 + endloop + endfacet + facet normal -0.969948 0.227423 0.0864849 + outer loop + vertex -898.419 404.098 346.031 + vertex -896.717 411.358 346.026 + vertex -899.049 402.682 342.69 + endloop + endfacet + facet normal -0.969943 0.2283 0.0842004 + outer loop + vertex -899.049 402.682 342.69 + vertex -896.717 411.358 346.026 + vertex -897.293 410.145 342.675 + endloop + endfacet + facet normal -0.966852 0.226719 0.117455 + outer loop + vertex -898.419 404.098 346.031 + vertex -896.04 412.624 349.155 + vertex -896.717 411.358 346.026 + endloop + endfacet + facet normal -0.963991 0.241778 0.110744 + outer loop + vertex -896.04 412.624 349.155 + vertex -894.291 419.602 349.146 + vertex -896.717 411.358 346.026 + endloop + endfacet + facet normal -0.964006 0.242085 0.109944 + outer loop + vertex -896.717 411.358 346.026 + vertex -894.291 419.602 349.146 + vertex -894.914 418.54 346.015 + endloop + endfacet + facet normal -0.958585 0.240475 0.1526 + outer loop + vertex -896.04 412.624 349.155 + vertex -893.549 420.743 352.009 + vertex -894.291 419.602 349.146 + endloop + endfacet + facet normal -0.956404 0.252127 0.147391 + outer loop + vertex -893.549 420.743 352.009 + vertex -891.783 427.438 352.016 + vertex -894.291 419.602 349.146 + endloop + endfacet + facet normal -0.956304 0.251418 0.149239 + outer loop + vertex -894.291 419.602 349.146 + vertex -891.783 427.438 352.016 + vertex -892.471 426.515 349.163 + endloop + endfacet + facet normal -0.958661 0.24091 0.151429 + outer loop + vertex -895.247 413.977 352.018 + vertex -893.549 420.743 352.009 + vertex -896.04 412.624 349.155 + endloop + endfacet + facet normal -0.961053 0.225925 0.159172 + outer loop + vertex -897.696 405.574 349.163 + vertex -895.247 413.977 352.018 + vertex -896.04 412.624 349.155 + endloop + endfacet + facet normal -0.961018 0.225767 0.159607 + outer loop + vertex -896.853 407.139 352.022 + vertex -895.247 413.977 352.018 + vertex -897.696 405.574 349.163 + endloop + endfacet + facet normal -0.963215 0.208258 0.169842 + outer loop + vertex -899.23 398.477 349.162 + vertex -896.853 407.139 352.022 + vertex -897.696 405.574 349.163 + endloop + endfacet + facet normal -0.969689 0.209661 0.12548 + outer loop + vertex -899.23 398.477 349.162 + vertex -897.696 405.574 349.163 + vertex -899.999 396.796 346.03 + endloop + endfacet + facet normal -0.972274 0.189593 0.136885 + outer loop + vertex -901.43 389.465 346.022 + vertex -899.23 398.477 349.162 + vertex -899.999 396.796 346.03 + endloop + endfacet + facet normal -0.975765 0.190304 0.10801 + outer loop + vertex -901.43 389.465 346.022 + vertex -899.999 396.796 346.03 + vertex -902.153 387.648 342.69 + endloop + endfacet + facet normal -0.978337 0.168279 0.120577 + outer loop + vertex -903.452 380.099 342.683 + vertex -901.43 389.465 346.022 + vertex -902.153 387.648 342.69 + endloop + endfacet + facet normal -0.97821 0.167509 0.122658 + outer loop + vertex -902.69 382.108 346.018 + vertex -901.43 389.465 346.022 + vertex -903.452 380.099 342.683 + endloop + endfacet + facet normal -0.980148 0.141772 0.138603 + outer loop + vertex -904.55 372.518 342.677 + vertex -902.69 382.108 346.018 + vertex -903.452 380.099 342.683 + endloop + endfacet + facet normal -0.983513 0.14228 0.111617 + outer loop + vertex -904.55 372.518 342.677 + vertex -903.452 380.099 342.683 + vertex -905.255 370.382 339.182 + endloop + endfacet + facet normal -0.985081 0.112857 0.129917 + outer loop + vertex -906.149 362.582 339.178 + vertex -904.55 372.518 342.677 + vertex -905.255 370.382 339.182 + endloop + endfacet + facet normal -0.984563 0.110813 0.135485 + outer loop + vertex -905.409 364.888 342.672 + vertex -904.55 372.518 342.677 + vertex -906.149 362.582 339.178 + endloop + endfacet + facet normal -0.984458 0.0766418 0.158016 + outer loop + vertex -906.761 354.733 339.174 + vertex -905.409 364.888 342.672 + vertex -906.149 362.582 339.178 + endloop + endfacet + facet normal -0.98898 0.0770099 0.126445 + outer loop + vertex -906.761 354.733 339.174 + vertex -906.149 362.582 339.178 + vertex -907.412 352.405 335.5 + endloop + endfacet + facet normal -0.987772 0.037351 0.151364 + outer loop + vertex -907.716 344.375 335.5 + vertex -906.761 354.733 339.174 + vertex -907.412 352.405 335.5 + endloop + endfacet + facet normal -0.986841 0.0349577 0.15787 + outer loop + vertex -907.04 346.855 339.173 + vertex -906.761 354.733 339.174 + vertex -907.716 344.375 335.5 + endloop + endfacet + facet normal -0.98122 0.0347517 0.189736 + outer loop + vertex -907.04 346.855 339.173 + vertex -905.997 357.205 342.672 + vertex -906.761 354.733 339.174 + endloop + endfacet + facet normal -0.980353 0.0330667 0.194461 + outer loop + vertex -906.258 349.483 342.672 + vertex -905.997 357.205 342.672 + vertex -907.04 346.855 339.173 + endloop + endfacet + facet normal -0.973694 0.0328408 0.225482 + outer loop + vertex -906.258 349.483 342.672 + vertex -905.137 359.753 346.015 + vertex -905.997 357.205 342.672 + endloop + endfacet + facet normal -0.97787 0.072698 0.196176 + outer loop + vertex -905.137 359.753 346.015 + vertex -904.579 367.263 346.015 + vertex -905.997 357.205 342.672 + endloop + endfacet + facet normal -0.978938 0.0749309 0.189911 + outer loop + vertex -905.997 357.205 342.672 + vertex -904.579 367.263 346.015 + vertex -905.409 364.888 342.672 + endloop + endfacet + facet normal -0.980087 0.109252 0.16581 + outer loop + vertex -904.579 367.263 346.015 + vertex -903.749 374.712 346.015 + vertex -905.409 364.888 342.672 + endloop + endfacet + facet normal -0.974182 0.108594 0.197929 + outer loop + vertex -904.579 367.263 346.015 + vertex -902.856 376.993 349.156 + vertex -903.749 374.712 346.015 + endloop + endfacet + facet normal -0.974539 0.138669 0.176197 + outer loop + vertex -902.856 376.993 349.156 + vertex -901.832 384.192 349.154 + vertex -903.749 374.712 346.015 + endloop + endfacet + facet normal -0.974811 0.139424 0.174082 + outer loop + vertex -903.749 374.712 346.015 + vertex -901.832 384.192 349.154 + vertex -902.69 382.108 346.018 + endloop + endfacet + facet normal -0.973736 0.165244 0.156626 + outer loop + vertex -901.832 384.192 349.154 + vertex -900.617 391.35 349.158 + vertex -902.69 382.108 346.018 + endloop + endfacet + facet normal -0.965788 0.163872 0.200997 + outer loop + vertex -901.832 384.192 349.154 + vertex -899.681 393.353 352.019 + vertex -900.617 391.35 349.158 + endloop + endfacet + facet normal -0.964882 0.186924 0.18456 + outer loop + vertex -899.681 393.353 352.019 + vertex -898.342 400.261 352.024 + vertex -900.617 391.35 349.158 + endloop + endfacet + facet normal -0.965122 0.18762 0.182587 + outer loop + vertex -900.617 391.35 349.158 + vertex -898.342 400.261 352.024 + vertex -899.23 398.477 349.162 + endloop + endfacet + facet normal -0.96588 0.164088 0.200375 + outer loop + vertex -900.86 386.411 352.023 + vertex -899.681 393.353 352.019 + vertex -901.832 384.192 349.154 + endloop + endfacet + facet normal -0.965567 0.137406 0.220908 + outer loop + vertex -902.856 376.993 349.156 + vertex -900.86 386.411 352.023 + vertex -901.832 384.192 349.154 + endloop + endfacet + facet normal -0.964671 0.135726 0.225804 + outer loop + vertex -901.844 379.413 352.023 + vertex -900.86 386.411 352.023 + vertex -902.856 376.993 349.156 + endloop + endfacet + facet normal -0.96239 0.1059 0.250182 + outer loop + vertex -903.655 369.731 349.158 + vertex -901.844 379.413 352.023 + vertex -902.856 376.993 349.156 + endloop + endfacet + facet normal -0.961005 0.103832 0.256296 + outer loop + vertex -902.609 372.342 352.022 + vertex -901.844 379.413 352.023 + vertex -903.655 369.731 349.158 + endloop + endfacet + facet normal -0.955572 0.0682618 0.286746 + outer loop + vertex -904.179 362.401 349.154 + vertex -902.609 372.342 352.022 + vertex -903.655 369.731 349.158 + endloop + endfacet + facet normal -0.955586 0.0682797 0.286692 + outer loop + vertex -903.119 365.199 352.023 + vertex -902.609 372.342 352.022 + vertex -904.179 362.401 349.154 + endloop + endfacet + facet normal -0.973479 0.107106 0.202155 + outer loop + vertex -903.655 369.731 349.158 + vertex -902.856 376.993 349.156 + vertex -904.579 367.263 346.015 + endloop + endfacet + facet normal -0.970795 0.0721715 0.228797 + outer loop + vertex -905.137 359.753 346.015 + vertex -903.655 369.731 349.158 + vertex -904.579 367.263 346.015 + endloop + endfacet + facet normal -0.968986 0.0692506 0.237215 + outer loop + vertex -904.179 362.401 349.154 + vertex -903.655 369.731 349.158 + vertex -905.137 359.753 346.015 + endloop + endfacet + facet normal -0.972673 0.0312363 0.230069 + outer loop + vertex -905.379 352.2 346.017 + vertex -905.137 359.753 346.015 + vertex -906.258 349.483 342.672 + endloop + endfacet + facet normal -0.963003 0.0309355 0.267709 + outer loop + vertex -905.379 352.2 346.017 + vertex -904.179 362.401 349.154 + vertex -905.137 359.753 346.015 + endloop + endfacet + facet normal -0.961139 0.0286026 0.274581 + outer loop + vertex -904.398 355.023 349.156 + vertex -904.179 362.401 349.154 + vertex -905.379 352.2 346.017 + endloop + endfacet + facet normal -0.983966 0.0753168 0.161673 + outer loop + vertex -905.997 357.205 342.672 + vertex -905.409 364.888 342.672 + vertex -906.761 354.733 339.174 + endloop + endfacet + facet normal -0.980468 0.110335 0.162815 + outer loop + vertex -905.409 364.888 342.672 + vertex -903.749 374.712 346.015 + vertex -904.55 372.518 342.677 + endloop + endfacet + facet normal -0.979743 0.140145 0.143047 + outer loop + vertex -903.749 374.712 346.015 + vertex -902.69 382.108 346.018 + vertex -904.55 372.518 342.677 + endloop + endfacet + facet normal -0.974153 0.166797 0.15233 + outer loop + vertex -902.69 382.108 346.018 + vertex -900.617 391.35 349.158 + vertex -901.43 389.465 346.022 + endloop + endfacet + facet normal -0.972164 0.189018 0.138457 + outer loop + vertex -900.617 391.35 349.158 + vertex -899.23 398.477 349.162 + vertex -901.43 389.465 346.022 + endloop + endfacet + facet normal -0.969718 0.209882 0.124883 + outer loop + vertex -899.999 396.796 346.03 + vertex -897.696 405.574 349.163 + vertex -898.419 404.098 346.031 + endloop + endfacet + facet normal -0.963302 0.208573 0.168959 + outer loop + vertex -898.342 400.261 352.024 + vertex -896.853 407.139 352.022 + vertex -899.23 398.477 349.162 + endloop + endfacet + facet normal -0.966898 0.227249 0.116045 + outer loop + vertex -897.696 405.574 349.163 + vertex -896.04 412.624 349.155 + vertex -898.419 404.098 346.031 + endloop + endfacet + facet normal -0.972887 0.210572 0.0956535 + outer loop + vertex -899.999 396.796 346.03 + vertex -898.419 404.098 346.031 + vertex -900.678 395.176 342.695 + endloop + endfacet + facet normal -0.97585 0.191176 0.105677 + outer loop + vertex -902.153 387.648 342.69 + vertex -899.999 396.796 346.03 + vertex -900.678 395.176 342.695 + endloop + endfacet + facet normal -0.981073 0.168775 0.0949272 + outer loop + vertex -903.452 380.099 342.683 + vertex -902.153 387.648 342.69 + vertex -904.127 378.143 339.188 + endloop + endfacet + facet normal -0.983615 0.142922 0.109889 + outer loop + vertex -905.255 370.382 339.182 + vertex -903.452 380.099 342.683 + vertex -904.127 378.143 339.188 + endloop + endfacet + facet normal -0.988126 0.11322 0.103866 + outer loop + vertex -906.149 362.582 339.178 + vertex -905.255 370.382 339.182 + vertex -906.784 360.41 335.509 + endloop + endfacet + facet normal -0.989103 0.0774793 0.125189 + outer loop + vertex -907.412 352.405 335.5 + vertex -906.149 362.582 339.178 + vertex -906.784 360.41 335.509 + endloop + endfacet + facet normal -0.992162 0.0375172 0.119195 + outer loop + vertex -907.716 344.375 335.5 + vertex -907.412 352.405 335.5 + vertex -908.271 342.207 331.562 + endloop + endfacet + facet normal -0.995541 0.0887795 0.0318886 + outer loop + vertex -908.631 347.775 322.657 + vertex -907.648 357.144 327.267 + vertex -907.878 356.229 322.64 + endloop + endfacet + facet normal -0.994744 0.0812448 0.0623248 + outer loop + vertex -907.951 350.383 331.567 + vertex -907.284 358.547 331.564 + vertex -908.346 348.835 327.275 + endloop + endfacet + facet normal -0.990878 0.115662 0.0691599 + outer loop + vertex -907.284 358.547 331.564 + vertex -905.862 368.376 335.508 + vertex -906.338 366.657 331.554 + endloop + endfacet + facet normal -0.987824 0.145162 0.0559667 + outer loop + vertex -905.862 368.376 335.508 + vertex -904.698 376.302 335.497 + vertex -906.338 366.657 331.554 + endloop + endfacet + facet normal -0.983104 0.171246 0.0646685 + outer loop + vertex -904.698 376.302 335.497 + vertex -902.787 385.876 339.185 + vertex -903.322 384.207 335.476 + endloop + endfacet + facet normal -0.979695 0.192972 0.0543971 + outer loop + vertex -902.787 385.876 339.185 + vertex -901.267 393.598 339.175 + vertex -903.322 384.207 335.476 + endloop + endfacet + facet normal -0.974933 0.212193 0.0669246 + outer loop + vertex -901.267 393.598 339.175 + vertex -899.049 402.682 342.69 + vertex -899.59 401.308 339.157 + endloop + endfacet + facet normal -0.972634 0.229355 0.0371496 + outer loop + vertex -900.04 399.998 335.427 + vertex -897.782 408.975 339.13 + vertex -898.189 407.853 335.399 + endloop + endfacet + facet normal -0.971656 0.228653 0.0600225 + outer loop + vertex -899.049 402.682 342.69 + vertex -897.293 410.145 342.675 + vertex -899.59 401.308 339.157 + endloop + endfacet + facet normal -0.968547 0.243046 0.0533418 + outer loop + vertex -897.782 408.975 339.13 + vertex -895.44 417.532 342.661 + vertex -895.879 416.563 339.113 + endloop + endfacet + facet normal -0.966909 0.242761 0.0784466 + outer loop + vertex -896.717 411.358 346.026 + vertex -894.914 418.54 346.015 + vertex -897.293 410.145 342.675 + endloop + endfacet + facet normal -0.964333 0.254246 0.0736262 + outer loop + vertex -895.44 417.532 342.661 + vertex -893.041 425.654 346.034 + vertex -893.513 424.835 342.678 + endloop + endfacet + facet normal -0.96168 0.252938 0.105799 + outer loop + vertex -894.291 419.602 349.146 + vertex -892.471 426.515 349.163 + vertex -894.914 418.54 346.015 + endloop + endfacet + facet normal -0.959743 0.26119 0.103315 + outer loop + vertex -893.041 425.654 346.034 + vertex -890.579 433.443 349.215 + vertex -891.094 432.786 346.095 + endloop + endfacet + facet normal -0.954618 0.259462 0.146231 + outer loop + vertex -891.783 427.438 352.016 + vertex -889.954 434.143 352.058 + vertex -892.471 426.515 349.163 + endloop + endfacet + facet normal -0.958895 0.264621 0.102452 + outer loop + vertex -890.579 433.443 349.215 + vertex -888.608 440.563 349.274 + vertex -891.094 432.786 346.095 + endloop + endfacet + facet normal -0.962373 0.262179 0.0714127 + outer loop + vertex -893.041 425.654 346.034 + vertex -891.094 432.786 346.095 + vertex -893.513 424.835 342.678 + endloop + endfacet + facet normal -0.965743 0.254674 0.0498209 + outer loop + vertex -895.44 417.532 342.661 + vertex -893.513 424.835 342.678 + vertex -895.879 416.563 339.113 + endloop + endfacet + facet normal -0.969422 0.24322 0.0326281 + outer loop + vertex -897.782 408.975 339.13 + vertex -895.879 416.563 339.113 + vertex -898.189 407.853 335.399 + endloop + endfacet + facet normal -0.973177 0.229413 0.017189 + outer loop + vertex -900.04 399.998 335.427 + vertex -898.189 407.853 335.399 + vertex -900.396 398.781 331.508 + endloop + endfacet + facet normal -0.976717 0.213351 0.0224971 + outer loop + vertex -902.143 390.785 331.517 + vertex -900.04 399.998 335.427 + vertex -900.396 398.781 331.508 + endloop + endfacet + facet normal -0.980499 0.194189 0.0301919 + outer loop + vertex -903.732 382.763 331.509 + vertex -901.76 392.107 335.451 + vertex -902.143 390.785 331.517 + endloop + endfacet + facet normal -0.984808 0.172488 0.0200193 + outer loop + vertex -905.139 374.724 331.523 + vertex -903.732 382.763 331.509 + vertex -905.434 373.538 327.235 + endloop + endfacet + facet normal -0.988555 0.148439 0.0269287 + outer loop + vertex -906.66 365.376 327.238 + vertex -905.139 374.724 331.523 + vertex -905.434 373.538 327.235 + endloop + endfacet + facet normal -0.992536 0.119206 0.0257243 + outer loop + vertex -907.648 357.144 327.267 + vertex -906.66 365.376 327.238 + vertex -907.878 356.229 322.64 + endloop + endfacet + facet normal -0.995631 0.0895756 0.0263801 + outer loop + vertex -908.282 352.759 319.148 + vertex -908.617 348.905 319.595 + vertex -907.878 356.229 322.64 + endloop + endfacet + facet normal -0.992169 0.124353 0.0116923 + outer loop + vertex -907.32 361.113 319.107 + vertex -907.781 357.391 319.573 + vertex -906.851 364.528 322.616 + endloop + endfacet + facet normal -0.990466 0.137751 -0.00157538 + outer loop + vertex -907.32 361.113 319.107 + vertex -906.851 364.528 322.616 + vertex -906.689 365.655 319.549 + endloop + endfacet + facet normal -0.983305 0.151427 -0.100897 + outer loop + vertex -906.357 365.306 314.455 + vertex -905.947 369.615 316.929 + vertex -905.698 369.583 314.458 + endloop + endfacet + facet normal -0.980726 0.167354 -0.100839 + outer loop + vertex -905.947 369.615 316.929 + vertex -905.148 374.311 316.956 + vertex -905.698 369.583 314.458 + endloop + endfacet + facet normal -0.982375 0.162798 -0.0918517 + outer loop + vertex -905.698 369.583 314.458 + vertex -905.148 374.311 316.956 + vertex -904.999 373.732 314.331 + endloop + endfacet + facet normal -0.979374 0.178279 -0.0950956 + outer loop + vertex -905.148 374.311 316.956 + vertex -904.271 378.873 316.475 + vertex -904.999 373.732 314.331 + endloop + endfacet + facet normal -0.981748 0.183484 -0.0500353 + outer loop + vertex -905.148 374.311 316.956 + vertex -904.123 380.569 319.793 + vertex -904.271 378.873 316.475 + endloop + endfacet + facet normal -0.988049 0.147069 -0.0461581 + outer loop + vertex -906.689 365.655 319.549 + vertex -906.103 369.462 319.144 + vertex -906.62 365.282 316.886 + endloop + endfacet + facet normal -0.984541 0.167719 -0.0504906 + outer loop + vertex -905.947 369.615 316.929 + vertex -905.261 374.504 319.795 + vertex -905.148 374.311 316.956 + endloop + endfacet + facet normal -0.988348 0.152202 0.00166789 + outer loop + vertex -906.103 369.462 319.144 + vertex -906.689 365.655 319.549 + vertex -905.58 372.821 322.732 + endloop + endfacet + facet normal -0.984546 0.175117 0.00162758 + outer loop + vertex -905.58 372.821 322.732 + vertex -903.997 381.679 327.355 + vertex -904.096 381.161 323.411 + endloop + endfacet + facet normal -0.981556 0.184111 -0.051488 + outer loop + vertex -905.261 374.504 319.795 + vertex -904.123 380.569 319.793 + vertex -905.148 374.311 316.956 + endloop + endfacet + facet normal -0.980075 0.198408 -0.0093724 + outer loop + vertex -904.096 381.161 323.411 + vertex -902.41 389.68 327.464 + vertex -902.585 388.621 323.371 + endloop + endfacet + facet normal -0.976735 0.214021 -0.0135518 + outer loop + vertex -902.41 389.68 327.464 + vertex -900.666 397.635 327.445 + vertex -902.585 388.621 323.371 + endloop + endfacet + facet normal -0.973346 0.22934 0.000163512 + outer loop + vertex -900.666 397.635 327.445 + vertex -898.514 406.767 331.485 + vertex -898.761 405.722 327.425 + endloop + endfacet + facet normal -0.969838 0.24272 -0.0223834 + outer loop + vertex -898.894 404.813 323.276 + vertex -896.736 413.82 327.436 + vertex -896.839 413.024 323.27 + endloop + endfacet + facet normal -0.968635 0.242396 -0.0546905 + outer loop + vertex -898.894 404.813 323.276 + vertex -896.839 413.024 323.27 + vertex -898.83 404.111 319.034 + endloop + endfacet + facet normal -0.966728 0.25461 -0.024731 + outer loop + vertex -896.736 413.82 327.436 + vertex -894.629 421.822 327.48 + vertex -896.839 413.024 323.27 + endloop + endfacet + facet normal -0.966599 0.255009 -0.0256335 + outer loop + vertex -896.839 413.024 323.27 + vertex -894.629 421.822 327.48 + vertex -894.696 421.148 323.3 + endloop + endfacet + facet normal -0.965094 0.254743 -0.0608198 + outer loop + vertex -896.839 413.024 323.27 + vertex -894.696 421.148 323.3 + vertex -896.742 412.354 318.938 + endloop + endfacet + facet normal -0.96419 0.263824 -0.0270922 + outer loop + vertex -894.629 421.822 327.48 + vertex -892.441 429.827 327.568 + vertex -894.696 421.148 323.3 + endloop + endfacet + facet normal -0.964095 0.264108 -0.0277218 + outer loop + vertex -894.696 421.148 323.3 + vertex -892.441 429.827 327.568 + vertex -892.475 429.266 323.383 + endloop + endfacet + facet normal -0.962504 0.264024 -0.0622726 + outer loop + vertex -894.696 421.148 323.3 + vertex -892.475 429.266 323.383 + vertex -894.573 420.568 318.945 + endloop + endfacet + facet normal -0.962537 0.269651 -0.0284764 + outer loop + vertex -892.441 429.827 327.568 + vertex -890.148 438.021 327.647 + vertex -892.475 429.266 323.383 + endloop + endfacet + facet normal -0.962338 0.270222 -0.0297571 + outer loop + vertex -892.475 429.266 323.383 + vertex -890.148 438.021 327.647 + vertex -890.15 437.552 323.465 + endloop + endfacet + facet normal -0.960621 0.270093 -0.0652402 + outer loop + vertex -892.475 429.266 323.383 + vertex -890.15 437.552 323.465 + vertex -892.326 428.741 319.019 + endloop + endfacet + facet normal -0.961854 0.271918 -0.0299476 + outer loop + vertex -890.148 438.021 327.647 + vertex -887.781 446.389 327.612 + vertex -890.15 437.552 323.465 + endloop + endfacet + facet normal -0.961381 0.273233 -0.0330204 + outer loop + vertex -890.15 437.552 323.465 + vertex -887.781 446.389 327.612 + vertex -887.746 446.012 323.455 + endloop + endfacet + facet normal -0.959752 0.27273 -0.067045 + outer loop + vertex -890.15 437.552 323.465 + vertex -887.746 446.012 323.455 + vertex -889.986 437.058 319.102 + endloop + endfacet + facet normal -0.961396 0.273179 -0.0330156 + outer loop + vertex -887.781 446.389 327.612 + vertex -885.478 454.467 327.383 + vertex -887.746 446.012 323.455 + endloop + endfacet + facet normal -0.960335 0.276006 -0.0397113 + outer loop + vertex -887.746 446.012 323.455 + vertex -885.478 454.467 327.383 + vertex -885.396 454.157 323.242 + endloop + endfacet + facet normal -0.958794 0.274705 -0.0724662 + outer loop + vertex -887.746 446.012 323.455 + vertex -885.396 454.157 323.242 + vertex -887.554 445.532 319.093 + endloop + endfacet + facet normal -0.960274 0.276217 -0.0397258 + outer loop + vertex -885.478 454.467 327.383 + vertex -883.26 462.135 327.074 + vertex -885.396 454.157 323.242 + endloop + endfacet + facet normal -0.95848 0.280723 -0.0501073 + outer loop + vertex -885.396 454.157 323.242 + vertex -883.26 462.135 327.074 + vertex -883.587 460.206 322.518 + endloop + endfacet + facet normal -0.961686 0.273804 -0.0138456 + outer loop + vertex -887.781 446.389 327.612 + vertex -885.491 454.618 331.258 + vertex -885.478 454.467 327.383 + endloop + endfacet + facet normal -0.961916 0.272994 -0.0138146 + outer loop + vertex -885.491 454.618 331.258 + vertex -883.794 460.565 330.591 + vertex -885.478 454.467 327.383 + endloop + endfacet + facet normal -0.96227 0.271937 -0.00926521 + outer loop + vertex -887.719 446.745 331.608 + vertex -885.491 454.618 331.258 + vertex -887.781 446.389 327.612 + endloop + endfacet + facet normal -0.962166 0.27245 0.00293561 + outer loop + vertex -887.719 446.745 331.608 + vertex -885.366 455.019 335.072 + vertex -885.491 454.618 331.258 + endloop + endfacet + facet normal -0.962354 0.271784 0.00301181 + outer loop + vertex -885.366 455.019 335.072 + vertex -883.495 461.653 334.156 + vertex -885.491 454.618 331.258 + endloop + endfacet + facet normal -0.962547 0.271037 0.00656935 + outer loop + vertex -887.602 447.069 335.467 + vertex -885.366 455.019 335.072 + vertex -887.719 446.745 331.608 + endloop + endfacet + facet normal -0.962476 0.271287 0.00654627 + outer loop + vertex -890.051 438.47 331.671 + vertex -887.602 447.069 335.467 + vertex -887.719 446.745 331.608 + endloop + endfacet + facet normal -0.9625 0.27119 -0.00708735 + outer loop + vertex -890.051 438.47 331.671 + vertex -887.719 446.745 331.608 + vertex -890.148 438.021 327.647 + endloop + endfacet + facet normal -0.96266 0.270587 0.00825061 + outer loop + vertex -889.901 438.885 335.548 + vertex -887.602 447.069 335.467 + vertex -890.051 438.47 331.671 + endloop + endfacet + facet normal -0.963088 0.269055 0.00843148 + outer loop + vertex -892.306 430.4 331.599 + vertex -889.901 438.885 335.548 + vertex -890.051 438.47 331.671 + endloop + endfacet + facet normal -0.963071 0.269179 -0.00602699 + outer loop + vertex -892.306 430.4 331.599 + vertex -890.051 438.47 331.671 + vertex -892.441 429.827 327.568 + endloop + endfacet + facet normal -0.963201 0.268615 0.00944569 + outer loop + vertex -892.109 430.973 335.479 + vertex -889.901 438.885 335.548 + vertex -892.306 430.4 331.599 + endloop + endfacet + facet normal -0.962436 0.270656 0.0214849 + outer loop + vertex -889.901 438.885 335.548 + vertex -887.45 447.314 339.184 + vertex -887.602 447.069 335.467 + endloop + endfacet + facet normal -0.962621 0.269993 0.0215362 + outer loop + vertex -887.45 447.314 339.184 + vertex -885.243 455.214 338.795 + vertex -887.602 447.069 335.467 + endloop + endfacet + facet normal -0.962032 0.270543 0.0360702 + outer loop + vertex -887.45 447.314 339.184 + vertex -885.094 455.269 342.348 + vertex -885.243 455.214 338.795 + endloop + endfacet + facet normal -0.962603 0.268496 0.0361256 + outer loop + vertex -885.094 455.269 342.348 + vertex -883.246 461.997 341.594 + vertex -885.243 455.214 338.795 + endloop + endfacet + facet normal -0.962385 0.26851 0.0414441 + outer loop + vertex -887.24 447.52 342.722 + vertex -885.094 455.269 342.348 + vertex -887.45 447.314 339.184 + endloop + endfacet + facet normal -0.962687 0.269529 0.0242661 + outer loop + vertex -889.697 439.282 339.26 + vertex -887.45 447.314 339.184 + vertex -889.901 438.885 335.548 + endloop + endfacet + facet normal -0.962276 0.271508 0.0175842 + outer loop + vertex -887.602 447.069 335.467 + vertex -885.243 455.214 338.795 + vertex -885.366 455.019 335.072 + endloop + endfacet + facet normal -0.962631 0.27024 0.0176623 + outer loop + vertex -885.243 455.214 338.795 + vertex -883.352 462.003 337.991 + vertex -885.366 455.019 335.072 + endloop + endfacet + facet normal -0.962222 0.272109 -0.0092812 + outer loop + vertex -890.148 438.021 327.647 + vertex -887.719 446.745 331.608 + vertex -887.781 446.389 327.612 + endloop + endfacet + facet normal -0.962959 0.26956 -0.00689469 + outer loop + vertex -892.441 429.827 327.568 + vertex -890.051 438.47 331.671 + vertex -890.148 438.021 327.647 + endloop + endfacet + facet normal -0.964592 0.263695 -0.00519536 + outer loop + vertex -894.629 421.822 327.48 + vertex -892.306 430.4 331.599 + vertex -892.441 429.827 327.568 + endloop + endfacet + facet normal -0.964511 0.26398 -0.00583535 + outer loop + vertex -894.455 422.546 331.516 + vertex -892.306 430.4 331.599 + vertex -894.629 421.822 327.48 + endloop + endfacet + facet normal -0.969949 0.243281 -0.00363254 + outer loop + vertex -898.514 406.767 331.485 + vertex -896.524 414.703 331.48 + vertex -898.761 405.722 327.425 + endloop + endfacet + facet normal -0.967044 0.254578 -0.00403879 + outer loop + vertex -896.736 413.82 327.436 + vertex -894.455 422.546 331.516 + vertex -894.629 421.822 327.48 + endloop + endfacet + facet normal -0.966808 0.255254 0.0113477 + outer loop + vertex -896.236 415.62 335.38 + vertex -894.211 423.289 335.404 + vertex -896.524 414.703 331.48 + endloop + endfacet + facet normal -0.96452 0.263814 0.0102212 + outer loop + vertex -894.455 422.546 331.516 + vertex -892.109 430.973 335.479 + vertex -892.306 430.4 331.599 + endloop + endfacet + facet normal -0.964319 0.263431 0.0263085 + outer loop + vertex -893.901 424.05 339.131 + vertex -891.85 431.552 339.199 + vertex -894.211 423.289 335.404 + endloop + endfacet + facet normal -0.962991 0.268425 0.0244008 + outer loop + vertex -892.109 430.973 335.479 + vertex -889.697 439.282 339.26 + vertex -889.901 438.885 335.548 + endloop + endfacet + facet normal -0.962578 0.267112 0.0457742 + outer loop + vertex -891.514 432.155 342.743 + vertex -889.42 439.691 342.803 + vertex -891.85 431.552 339.199 + endloop + endfacet + facet normal -0.962103 0.269529 0.0413679 + outer loop + vertex -889.697 439.282 339.26 + vertex -887.24 447.52 342.722 + vertex -887.45 447.314 339.184 + endloop + endfacet + facet normal -0.961214 0.266962 0.0692705 + outer loop + vertex -889.059 440.121 346.153 + vertex -886.95 447.733 346.081 + vertex -889.42 439.691 342.803 + endloop + endfacet + facet normal -0.96124 0.269092 0.060064 + outer loop + vertex -887.24 447.52 342.722 + vertex -884.883 455.273 345.715 + vertex -885.094 455.269 342.348 + endloop + endfacet + facet normal -0.96199 0.266387 0.0601142 + outer loop + vertex -884.883 455.273 345.715 + vertex -883.095 461.89 344.994 + vertex -885.094 455.269 342.348 + endloop + endfacet + facet normal -0.959429 0.264511 0.0976171 + outer loop + vertex -886.572 447.948 349.212 + vertex -884.585 455.278 348.88 + vertex -886.95 447.733 346.081 + endloop + endfacet + facet normal -0.956733 0.260854 0.128907 + outer loop + vertex -884.205 455.241 351.776 + vertex -882.577 461.521 351.151 + vertex -884.585 455.278 348.88 + endloop + endfacet + facet normal -0.95074 0.262831 0.164357 + outer loop + vertex -884.205 455.241 351.776 + vertex -882.196 461.248 353.791 + vertex -882.577 461.521 351.151 + endloop + endfacet + facet normal -0.952805 0.255538 0.1639 + outer loop + vertex -882.577 461.521 351.151 + vertex -882.196 461.248 353.791 + vertex -881.127 465.768 352.962 + endloop + endfacet + facet normal -0.942745 0.261142 0.207453 + outer loop + vertex -880.757 465.266 355.274 + vertex -881.127 465.768 352.962 + vertex -882.196 461.248 353.791 + endloop + endfacet + facet normal -0.945392 0.252569 0.206015 + outer loop + vertex -880.757 465.266 355.274 + vertex -880.357 467.594 354.253 + vertex -881.127 465.768 352.962 + endloop + endfacet + facet normal -0.94559 0.270826 0.180311 + outer loop + vertex -881.127 465.768 352.962 + vertex -880.357 467.594 354.253 + vertex -880.609 468.161 352.083 + endloop + endfacet + facet normal -0.949136 0.255878 0.183488 + outer loop + vertex -883.733 455.15 354.347 + vertex -882.196 461.248 353.791 + vertex -884.205 455.241 351.776 + endloop + endfacet + facet normal -0.947738 0.261059 0.183415 + outer loop + vertex -886.104 448.145 352.066 + vertex -883.733 455.15 354.347 + vertex -884.205 455.241 351.776 + endloop + endfacet + facet normal -0.946403 0.256349 0.196487 + outer loop + vertex -885.524 448.349 354.593 + vertex -883.733 455.15 354.347 + vertex -886.104 448.145 352.066 + endloop + endfacet + facet normal -0.945442 0.260275 0.19595 + outer loop + vertex -888.056 441.019 352.113 + vertex -885.524 448.349 354.593 + vertex -886.104 448.145 352.066 + endloop + endfacet + facet normal -0.944524 0.257106 0.20438 + outer loop + vertex -887.376 441.523 354.617 + vertex -885.524 448.349 354.593 + vertex -888.056 441.019 352.113 + endloop + endfacet + facet normal -0.944115 0.258992 0.203888 + outer loop + vertex -889.954 434.143 352.058 + vertex -887.376 441.523 354.617 + vertex -888.056 441.019 352.113 + endloop + endfacet + facet normal -0.943816 0.257962 0.206558 + outer loop + vertex -889.19 434.923 354.574 + vertex -887.376 441.523 354.617 + vertex -889.954 434.143 352.058 + endloop + endfacet + facet normal -0.944148 0.256231 0.207196 + outer loop + vertex -891.783 427.438 352.016 + vertex -889.19 434.923 354.574 + vertex -889.954 434.143 352.058 + endloop + endfacet + facet normal -0.944073 0.255982 0.207846 + outer loop + vertex -890.949 428.458 354.545 + vertex -889.19 434.923 354.574 + vertex -891.783 427.438 352.016 + endloop + endfacet + facet normal -0.945213 0.249104 0.210998 + outer loop + vertex -893.549 420.743 352.009 + vertex -890.949 428.458 354.545 + vertex -891.783 427.438 352.016 + endloop + endfacet + facet normal -0.945547 0.250103 0.208301 + outer loop + vertex -892.66 421.988 354.548 + vertex -890.949 428.458 354.545 + vertex -893.549 420.743 352.009 + endloop + endfacet + facet normal -0.947196 0.238121 0.214753 + outer loop + vertex -895.247 413.977 352.018 + vertex -892.66 421.988 354.548 + vertex -893.549 420.743 352.009 + endloop + endfacet + facet normal -0.947072 0.237795 0.215658 + outer loop + vertex -894.303 415.443 354.548 + vertex -892.66 421.988 354.548 + vertex -895.247 413.977 352.018 + endloop + endfacet + facet normal -0.94856 0.222874 0.22486 + outer loop + vertex -896.853 407.139 352.022 + vertex -894.303 415.443 354.548 + vertex -895.247 413.977 352.018 + endloop + endfacet + facet normal -0.949393 0.224807 0.21935 + outer loop + vertex -895.864 408.844 354.558 + vertex -894.303 415.443 354.548 + vertex -896.853 407.139 352.022 + endloop + endfacet + facet normal -0.950553 0.205834 0.232556 + outer loop + vertex -898.342 400.261 352.024 + vertex -895.864 408.844 354.558 + vertex -896.853 407.139 352.022 + endloop + endfacet + facet normal -0.950111 0.204946 0.235131 + outer loop + vertex -897.298 402.204 354.551 + vertex -895.864 408.844 354.558 + vertex -898.342 400.261 352.024 + endloop + endfacet + facet normal -0.950259 0.184041 0.251269 + outer loop + vertex -899.681 393.353 352.019 + vertex -897.298 402.204 354.551 + vertex -898.342 400.261 352.024 + endloop + endfacet + facet normal -0.951157 0.185593 0.246688 + outer loop + vertex -898.598 395.534 354.556 + vertex -897.298 402.204 354.551 + vertex -899.681 393.353 352.019 + endloop + endfacet + facet normal -0.950079 0.161442 0.266995 + outer loop + vertex -900.86 386.411 352.023 + vertex -898.598 395.534 354.556 + vertex -899.681 393.353 352.019 + endloop + endfacet + facet normal -0.94934 0.160353 0.27026 + outer loop + vertex -899.733 388.815 354.556 + vertex -898.598 395.534 354.556 + vertex -900.86 386.411 352.023 + endloop + endfacet + facet normal -0.946265 0.133137 0.294714 + outer loop + vertex -901.844 379.413 352.023 + vertex -899.733 388.815 354.556 + vertex -900.86 386.411 352.023 + endloop + endfacet + facet normal -0.945956 0.132754 0.295877 + outer loop + vertex -900.685 382.026 354.557 + vertex -899.733 388.815 354.556 + vertex -901.844 379.413 352.023 + endloop + endfacet + facet normal -0.940116 0.101562 0.325372 + outer loop + vertex -902.609 372.342 352.022 + vertex -900.685 382.026 354.557 + vertex -901.844 379.413 352.023 + endloop + endfacet + facet normal -0.940078 0.101523 0.325494 + outer loop + vertex -901.427 375.153 354.557 + vertex -900.685 382.026 354.557 + vertex -902.609 372.342 352.022 + endloop + endfacet + facet normal -0.930617 0.0665156 0.359898 + outer loop + vertex -903.119 365.199 352.023 + vertex -901.427 375.153 354.557 + vertex -902.609 372.342 352.022 + endloop + endfacet + facet normal -0.928791 0.0649397 0.36487 + outer loop + vertex -901.914 368.201 354.555 + vertex -901.427 375.153 354.557 + vertex -903.119 365.199 352.023 + endloop + endfacet + facet normal -0.961782 0.25493 0.0999298 + outer loop + vertex -881.44 466.117 350.252 + vertex -880.9 468.609 349.087 + vertex -881.701 466.333 347.184 + endloop + endfacet + facet normal -0.960228 0.265394 0.0867642 + outer loop + vertex -881.701 466.333 347.184 + vertex -880.9 468.609 349.087 + vertex -881.146 468.77 345.88 + endloop + endfacet + facet normal -0.960133 0.267999 0.0795027 + outer loop + vertex -884.883 455.273 345.715 + vertex -882.879 461.716 348.193 + vertex -883.095 461.89 344.994 + endloop + endfacet + facet normal -0.964545 0.255446 0.0663337 + outer loop + vertex -881.701 466.333 347.184 + vertex -881.146 468.77 345.88 + vertex -881.866 466.557 343.925 + endloop + endfacet + facet normal -0.962522 0.265801 0.0538662 + outer loop + vertex -881.866 466.557 343.925 + vertex -881.146 468.77 345.88 + vertex -881.242 469.092 342.571 + endloop + endfacet + facet normal -0.968688 0.242814 0.0518115 + outer loop + vertex -881.242 469.092 342.571 + vertex -881.146 468.77 345.88 + vertex -880.995 469.651 344.569 + endloop + endfacet + facet normal -0.961541 0.269877 0.0510419 + outer loop + vertex -885.094 455.269 342.348 + vertex -883.095 461.89 344.994 + vertex -883.246 461.997 341.594 + endloop + endfacet + facet normal -0.965038 0.259033 0.0400386 + outer loop + vertex -881.866 466.557 343.925 + vertex -881.242 469.092 342.571 + vertex -881.954 466.761 340.48 + endloop + endfacet + facet normal -0.96279 0.268748 0.028448 + outer loop + vertex -881.954 466.761 340.48 + vertex -881.242 469.092 342.571 + vertex -881.324 469.172 339.048 + endloop + endfacet + facet normal -0.969509 0.243447 0.0280267 + outer loop + vertex -881.324 469.172 339.048 + vertex -881.242 469.092 342.571 + vertex -881.097 469.918 340.387 + endloop + endfacet + facet normal -0.970149 0.240997 0.027057 + outer loop + vertex -881.072 469.778 342.549 + vertex -881.097 469.918 340.387 + vertex -881.242 469.092 342.571 + endloop + endfacet + facet normal -0.968987 0.241532 0.052207 + outer loop + vertex -880.995 469.651 344.569 + vertex -881.072 469.778 342.549 + vertex -881.242 469.092 342.571 + endloop + endfacet + facet normal -0.953194 0.297292 0.0551229 + outer loop + vertex -881.072 469.778 342.549 + vertex -880.995 469.651 344.569 + vertex -880.81 470.732 341.936 + endloop + endfacet + facet normal -0.958822 0.28246 0.0296081 + outer loop + vertex -881.097 469.918 340.387 + vertex -881.072 469.778 342.549 + vertex -880.81 470.732 341.936 + endloop + endfacet + facet normal -0.962042 0.271386 0.0287223 + outer loop + vertex -885.243 455.214 338.795 + vertex -883.246 461.997 341.594 + vertex -883.352 462.003 337.991 + endloop + endfacet + facet normal -0.964418 0.263685 0.0192079 + outer loop + vertex -881.954 466.761 340.48 + vertex -881.324 469.172 339.048 + vertex -882.042 466.713 336.705 + endloop + endfacet + facet normal -0.962552 0.27087 0.011097 + outer loop + vertex -882.042 466.713 336.705 + vertex -881.324 469.172 339.048 + vertex -881.337 469.279 335.285 + endloop + endfacet + facet normal -0.969911 0.243241 0.01034 + outer loop + vertex -881.337 469.279 335.285 + vertex -881.324 469.172 339.048 + vertex -881.14 469.96 337.73 + endloop + endfacet + facet normal -0.96843 0.249138 0.00857736 + outer loop + vertex -881.14 469.96 337.73 + vertex -881.13 470.074 335.519 + vertex -881.337 469.279 335.285 + endloop + endfacet + facet normal -0.967732 0.251975 -0.00168522 + outer loop + vertex -881.13 470.074 335.519 + vertex -881.157 469.956 333.353 + vertex -881.337 469.279 335.285 + endloop + endfacet + facet normal -0.962549 0.271093 -0.00278332 + outer loop + vertex -881.157 469.956 333.353 + vertex -881.13 470.074 335.519 + vertex -880.887 470.91 332.754 + endloop + endfacet + facet normal -0.963444 0.267776 -0.00847018 + outer loop + vertex -881.117 470.027 331.086 + vertex -881.157 469.956 333.353 + vertex -880.887 470.91 332.754 + endloop + endfacet + facet normal -0.967649 0.252137 -0.00903045 + outer loop + vertex -881.157 469.956 333.353 + vertex -881.117 470.027 331.086 + vertex -881.298 469.333 331.062 + endloop + endfacet + facet normal -0.967487 0.252359 -0.0168341 + outer loop + vertex -881.117 470.027 331.086 + vertex -881.111 469.91 328.988 + vertex -881.298 469.333 331.062 + endloop + endfacet + facet normal -0.972027 0.233796 -0.0224063 + outer loop + vertex -881.216 469.269 326.816 + vertex -881.298 469.333 331.062 + vertex -881.111 469.91 328.988 + endloop + endfacet + facet normal -0.957055 0.289292 -0.0188598 + outer loop + vertex -881.111 469.91 328.988 + vertex -881.117 470.027 331.086 + vertex -880.844 470.749 328.277 + endloop + endfacet + facet normal -0.958533 0.283805 -0.0258845 + outer loop + vertex -881.045 469.926 326.706 + vertex -881.111 469.91 328.988 + vertex -880.844 470.749 328.277 + endloop + endfacet + facet normal -0.968681 0.246899 -0.0264334 + outer loop + vertex -881.111 469.91 328.988 + vertex -881.045 469.926 326.706 + vertex -881.216 469.269 326.816 + endloop + endfacet + facet normal -0.963593 0.267204 0.00952673 + outer loop + vertex -881.13 470.074 335.519 + vertex -881.14 469.96 337.73 + vertex -880.883 470.901 337.341 + endloop + endfacet + facet normal -0.962362 0.271059 0.0196651 + outer loop + vertex -881.14 469.96 337.73 + vertex -881.097 469.918 340.387 + vertex -880.883 470.901 337.341 + endloop + endfacet + facet normal -0.966035 0.257675 0.0195126 + outer loop + vertex -881.097 469.918 340.387 + vertex -881.14 469.96 337.73 + vertex -881.324 469.172 339.048 + endloop + endfacet + facet normal -0.962006 0.272803 0.0111004 + outer loop + vertex -885.366 455.019 335.072 + vertex -883.352 462.003 337.991 + vertex -883.495 461.653 334.156 + endloop + endfacet + facet normal -0.963951 0.266074 0.00173566 + outer loop + vertex -882.042 466.713 336.705 + vertex -881.337 469.279 335.285 + vertex -882.205 466.154 332.094 + endloop + endfacet + facet normal -0.962067 0.27276 -0.00532163 + outer loop + vertex -882.205 466.154 332.094 + vertex -881.337 469.279 335.285 + vertex -881.298 469.333 331.062 + endloop + endfacet + facet normal -0.970519 0.240954 -0.00581182 + outer loop + vertex -881.298 469.333 331.062 + vertex -881.337 469.279 335.285 + vertex -881.157 469.956 333.353 + endloop + endfacet + facet normal -0.961688 0.274128 -0.00313704 + outer loop + vertex -885.491 454.618 331.258 + vertex -883.495 461.653 334.156 + vertex -883.794 460.565 330.591 + endloop + endfacet + facet normal -0.960608 0.277022 -0.0221603 + outer loop + vertex -885.478 454.467 327.383 + vertex -883.794 460.565 330.591 + vertex -883.26 462.135 327.074 + endloop + endfacet + facet normal -0.963021 0.268802 -0.0183621 + outer loop + vertex -882.205 466.154 332.094 + vertex -881.298 469.333 331.062 + vertex -881.772 467.454 328.394 + endloop + endfacet + facet normal -0.961265 0.274681 -0.0228149 + outer loop + vertex -881.772 467.454 328.394 + vertex -881.298 469.333 331.062 + vertex -881.216 469.269 326.816 + endloop + endfacet + facet normal -0.959468 0.277577 -0.0487042 + outer loop + vertex -883.587 460.206 322.518 + vertex -883.26 462.135 327.074 + vertex -881.985 465.981 323.888 + endloop + endfacet + facet normal -0.957458 0.276542 -0.0824575 + outer loop + vertex -885.396 454.157 323.242 + vertex -883.587 460.206 322.518 + vertex -885.169 453.641 318.877 + endloop + endfacet + facet normal -0.956689 0.279112 -0.0827212 + outer loop + vertex -887.554 445.532 319.093 + vertex -885.396 454.157 323.242 + vertex -885.169 453.641 318.877 + endloop + endfacet + facet normal -0.958673 0.275115 -0.0725061 + outer loop + vertex -889.986 437.058 319.102 + vertex -887.746 446.012 323.455 + vertex -887.554 445.532 319.093 + endloop + endfacet + facet normal -0.960304 0.270828 -0.0668504 + outer loop + vertex -892.326 428.741 319.019 + vertex -890.15 437.552 323.465 + vertex -889.986 437.058 319.102 + endloop + endfacet + facet normal -0.962036 0.265146 -0.0646931 + outer loop + vertex -894.573 420.568 318.945 + vertex -892.475 429.266 323.383 + vertex -892.326 428.741 319.019 + endloop + endfacet + facet normal -0.965038 0.254882 -0.0611262 + outer loop + vertex -896.742 412.354 318.938 + vertex -894.696 421.148 323.3 + vertex -894.573 420.568 318.945 + endloop + endfacet + facet normal -0.967859 0.244405 -0.0592825 + outer loop + vertex -898.83 404.111 319.034 + vertex -896.839 413.024 323.27 + vertex -896.742 412.354 318.938 + endloop + endfacet + facet normal -0.97125 0.23208 -0.0530241 + outer loop + vertex -900.795 395.907 319.126 + vertex -898.894 404.813 323.276 + vertex -898.83 404.111 319.034 + endloop + endfacet + facet normal -0.975586 0.215347 -0.0431009 + outer loop + vertex -902.742 387.036 318.878 + vertex -900.843 396.518 323.26 + vertex -900.795 395.907 319.126 + endloop + endfacet + facet normal -0.977927 0.200476 -0.0588899 + outer loop + vertex -904.123 380.569 319.793 + vertex -902.742 387.036 318.878 + vertex -904.271 378.873 316.475 + endloop + endfacet + facet normal -0.980547 0.175471 -0.0879648 + outer loop + vertex -904.999 373.732 314.331 + vertex -904.271 378.873 316.475 + vertex -904.373 377.044 313.961 + endloop + endfacet + facet normal -0.973992 0.166961 -0.153181 + outer loop + vertex -904.999 373.732 314.331 + vertex -904.373 377.044 313.961 + vertex -904.608 373.77 311.885 + endloop + endfacet + facet normal -0.975363 0.158411 -0.153533 + outer loop + vertex -905.268 369.763 311.945 + vertex -904.999 373.732 314.331 + vertex -904.608 373.77 311.885 + endloop + endfacet + facet normal -0.974859 0.159572 -0.155521 + outer loop + vertex -905.698 369.583 314.458 + vertex -904.999 373.732 314.331 + vertex -905.268 369.763 311.945 + endloop + endfacet + facet normal -0.976436 0.148508 -0.156584 + outer loop + vertex -905.904 365.592 311.953 + vertex -905.698 369.583 314.458 + vertex -905.268 369.763 311.945 + endloop + endfacet + facet normal -0.975689 0.150301 -0.159501 + outer loop + vertex -906.357 365.306 314.455 + vertex -905.698 369.583 314.458 + vertex -905.904 365.592 311.953 + endloop + endfacet + facet normal -0.977395 0.136581 -0.161382 + outer loop + vertex -906.491 361.372 311.938 + vertex -906.357 365.306 314.455 + vertex -905.904 365.592 311.953 + endloop + endfacet + facet normal -0.977316 0.136777 -0.161694 + outer loop + vertex -906.944 361.103 314.448 + vertex -906.357 365.306 314.455 + vertex -906.491 361.372 311.938 + endloop + endfacet + facet normal -0.978908 0.122479 -0.163517 + outer loop + vertex -907.017 357.162 311.934 + vertex -906.944 361.103 314.448 + vertex -906.491 361.372 311.938 + endloop + endfacet + facet normal -0.979144 0.121871 -0.162558 + outer loop + vertex -907.465 356.932 314.46 + vertex -906.944 361.103 314.448 + vertex -907.017 357.162 311.934 + endloop + endfacet + facet normal -0.980913 0.103631 -0.16453 + outer loop + vertex -907.464 352.937 311.936 + vertex -907.465 356.932 314.46 + vertex -907.017 357.162 311.934 + endloop + endfacet + facet normal -0.980449 0.104873 -0.166496 + outer loop + vertex -907.918 352.72 314.473 + vertex -907.465 356.932 314.46 + vertex -907.464 352.937 311.936 + endloop + endfacet + facet normal -0.98188 0.0871642 -0.168269 + outer loop + vertex -907.845 348.642 311.94 + vertex -907.918 352.72 314.473 + vertex -907.464 352.937 311.936 + endloop + endfacet + facet normal -0.981549 0.0880718 -0.169721 + outer loop + vertex -908.304 348.418 314.478 + vertex -907.918 352.72 314.473 + vertex -907.845 348.642 311.94 + endloop + endfacet + facet normal -0.982826 0.0674109 -0.17178 + outer loop + vertex -908.145 344.277 311.938 + vertex -908.304 348.418 314.478 + vertex -907.845 348.642 311.94 + endloop + endfacet + facet normal -0.982413 0.0685855 -0.173669 + outer loop + vertex -908.609 344.044 314.475 + vertex -908.304 348.418 314.478 + vertex -908.145 344.277 311.938 + endloop + endfacet + facet normal -0.983288 0.0473825 -0.175782 + outer loop + vertex -908.357 339.871 311.937 + vertex -908.609 344.044 314.475 + vertex -908.145 344.277 311.938 + endloop + endfacet + facet normal -0.982972 0.0483186 -0.177289 + outer loop + vertex -908.825 339.642 314.472 + vertex -908.609 344.044 314.475 + vertex -908.357 339.871 311.937 + endloop + endfacet + facet normal -0.983461 0.0225236 -0.179716 + outer loop + vertex -908.457 335.488 311.935 + vertex -908.825 339.642 314.472 + vertex -908.357 339.871 311.937 + endloop + endfacet + facet normal -0.982578 0.0252937 -0.184123 + outer loop + vertex -908.938 335.263 314.471 + vertex -908.825 339.642 314.472 + vertex -908.457 335.488 311.935 + endloop + endfacet + facet normal -0.982458 -0.00148468 -0.186476 + outer loop + vertex -908.45 331.146 311.936 + vertex -908.938 335.263 314.471 + vertex -908.457 335.488 311.935 + endloop + endfacet + facet normal -0.982242 -0.000757787 -0.187615 + outer loop + vertex -908.934 330.939 314.47 + vertex -908.938 335.263 314.471 + vertex -908.45 331.146 311.936 + endloop + endfacet + facet normal -0.981387 -0.0293232 -0.189789 + outer loop + vertex -908.322 326.858 311.937 + vertex -908.934 330.939 314.47 + vertex -908.45 331.146 311.936 + endloop + endfacet + facet normal -0.981231 -0.0287447 -0.190683 + outer loop + vertex -908.809 326.671 314.47 + vertex -908.934 330.939 314.47 + vertex -908.322 326.858 311.937 + endloop + endfacet + facet normal -0.979488 -0.0592241 -0.192601 + outer loop + vertex -908.066 322.622 311.937 + vertex -908.809 326.671 314.47 + vertex -908.322 326.858 311.937 + endloop + endfacet + facet normal -0.978997 -0.0572031 -0.195686 + outer loop + vertex -908.562 322.445 314.471 + vertex -908.809 326.671 314.47 + vertex -908.066 322.622 311.937 + endloop + endfacet + facet normal -0.975816 -0.0934771 -0.197597 + outer loop + vertex -907.663 318.427 311.931 + vertex -908.562 322.445 314.471 + vertex -908.066 322.622 311.937 + endloop + endfacet + facet normal -0.974879 -0.0891487 -0.204114 + outer loop + vertex -908.179 318.254 314.469 + vertex -908.562 322.445 314.471 + vertex -907.663 318.427 311.931 + endloop + endfacet + facet normal -0.970367 -0.126681 -0.205764 + outer loop + vertex -907.115 314.244 311.923 + vertex -908.179 318.254 314.469 + vertex -907.663 318.427 311.931 + endloop + endfacet + facet normal -0.969683 -0.123127 -0.211078 + outer loop + vertex -907.646 314.068 314.463 + vertex -908.179 318.254 314.469 + vertex -907.115 314.244 311.923 + endloop + endfacet + facet normal -0.963116 -0.164953 -0.212596 + outer loop + vertex -906.395 310.053 311.913 + vertex -907.646 314.068 314.463 + vertex -907.115 314.244 311.923 + endloop + endfacet + facet normal -0.962319 -0.160159 -0.219754 + outer loop + vertex -906.945 309.875 314.452 + vertex -907.646 314.068 314.463 + vertex -906.395 310.053 311.913 + endloop + endfacet + facet normal -0.954411 -0.200769 -0.220889 + outer loop + vertex -905.508 305.841 311.906 + vertex -906.945 309.875 314.452 + vertex -906.395 310.053 311.913 + endloop + endfacet + facet normal -0.953974 -0.197716 -0.22548 + outer loop + vertex -906.073 305.679 314.44 + vertex -906.945 309.875 314.452 + vertex -905.508 305.841 311.906 + endloop + endfacet + facet normal -0.944689 -0.2377 -0.225968 + outer loop + vertex -904.448 301.615 311.92 + vertex -906.073 305.679 314.44 + vertex -905.508 305.841 311.906 + endloop + endfacet + facet normal -0.943845 -0.231025 -0.236186 + outer loop + vertex -905.049 301.494 314.441 + vertex -906.073 305.679 314.44 + vertex -904.448 301.615 311.92 + endloop + endfacet + facet normal -0.932688 -0.273162 -0.235532 + outer loop + vertex -903.232 297.424 311.965 + vertex -905.049 301.494 314.441 + vertex -904.448 301.615 311.92 + endloop + endfacet + facet normal -0.932238 -0.269054 -0.241957 + outer loop + vertex -903.86 297.362 314.456 + vertex -905.049 301.494 314.441 + vertex -903.232 297.424 311.965 + endloop + endfacet + facet normal -0.920766 -0.307543 -0.240015 + outer loop + vertex -901.872 293.292 312.045 + vertex -903.86 297.362 314.456 + vertex -903.232 297.424 311.965 + endloop + endfacet + facet normal -0.920475 -0.304383 -0.245107 + outer loop + vertex -902.504 293.243 314.478 + vertex -903.86 297.362 314.456 + vertex -901.872 293.292 312.045 + endloop + endfacet + facet normal -0.905861 -0.347509 -0.242185 + outer loop + vertex -900.27 289.085 312.088 + vertex -902.504 293.243 314.478 + vertex -901.872 293.292 312.045 + endloop + endfacet + facet normal -0.905439 -0.341863 -0.251614 + outer loop + vertex -900.96 289.14 314.498 + vertex -902.504 293.243 314.478 + vertex -900.27 289.085 312.088 + endloop + endfacet + facet normal -0.892506 -0.377321 -0.247106 + outer loop + vertex -898.521 284.885 312.186 + vertex -900.96 289.14 314.498 + vertex -900.27 289.085 312.088 + endloop + endfacet + facet normal -0.892107 -0.3721 -0.256293 + outer loop + vertex -899.274 285.091 314.508 + vertex -900.96 289.14 314.498 + vertex -898.521 284.885 312.186 + endloop + endfacet + facet normal -0.877413 -0.410588 -0.24812 + outer loop + vertex -896.652 280.863 312.23 + vertex -899.274 285.091 314.508 + vertex -898.521 284.885 312.186 + endloop + endfacet + facet normal -0.8772 -0.406373 -0.255696 + outer loop + vertex -897.455 281.172 314.495 + vertex -899.274 285.091 314.508 + vertex -896.652 280.863 312.23 + endloop + endfacet + facet normal -0.86158 -0.444624 -0.244927 + outer loop + vertex -894.679 277.044 312.221 + vertex -897.455 281.172 314.495 + vertex -896.652 280.863 312.23 + endloop + endfacet + facet normal -0.86132 -0.432608 -0.266417 + outer loop + vertex -895.539 277.369 314.477 + vertex -897.455 281.172 314.495 + vertex -894.679 277.044 312.221 + endloop + endfacet + facet normal -0.843983 -0.472367 -0.25409 + outer loop + vertex -892.607 273.352 312.204 + vertex -895.539 277.369 314.477 + vertex -894.679 277.044 312.221 + endloop + endfacet + facet normal -0.843999 -0.461822 -0.27274 + outer loop + vertex -893.507 273.658 314.472 + vertex -895.539 277.369 314.477 + vertex -892.607 273.352 312.204 + endloop + endfacet + facet normal -0.8264 -0.499085 -0.260725 + outer loop + vertex -890.413 269.72 312.201 + vertex -893.507 273.658 314.472 + vertex -892.607 273.352 312.204 + endloop + endfacet + facet normal -0.826624 -0.488866 -0.278751 + outer loop + vertex -891.348 270.004 314.476 + vertex -893.507 273.658 314.472 + vertex -890.413 269.72 312.201 + endloop + endfacet + facet normal -0.809167 -0.523271 -0.267277 + outer loop + vertex -888.091 266.127 312.206 + vertex -891.348 270.004 314.476 + vertex -890.413 269.72 312.201 + endloop + endfacet + facet normal -0.809423 -0.517733 -0.277106 + outer loop + vertex -889.047 266.405 314.481 + vertex -891.348 270.004 314.476 + vertex -888.091 266.127 312.206 + endloop + endfacet + facet normal -0.793877 -0.546284 -0.267083 + outer loop + vertex -885.653 262.581 312.212 + vertex -889.047 266.405 314.481 + vertex -888.091 266.127 312.206 + endloop + endfacet + facet normal -0.794541 -0.535555 -0.286156 + outer loop + vertex -886.652 262.853 314.476 + vertex -889.047 266.405 314.481 + vertex -885.653 262.581 312.212 + endloop + endfacet + facet normal -0.777073 -0.566273 -0.274759 + outer loop + vertex -883.132 259.121 312.214 + vertex -886.652 262.853 314.476 + vertex -885.653 262.581 312.212 + endloop + endfacet + facet normal -0.77756 -0.560459 -0.285107 + outer loop + vertex -884.162 259.404 314.468 + vertex -886.652 262.853 314.476 + vertex -883.132 259.121 312.214 + endloop + endfacet + facet normal -0.761918 -0.586544 -0.274676 + outer loop + vertex -880.56 255.777 312.22 + vertex -884.162 259.404 314.468 + vertex -883.132 259.121 312.214 + endloop + endfacet + facet normal -0.762834 -0.57773 -0.290365 + outer loop + vertex -881.629 256.064 314.457 + vertex -884.162 259.404 314.468 + vertex -880.56 255.777 312.22 + endloop + endfacet + facet normal -0.74926 -0.599678 -0.281061 + outer loop + vertex -877.966 252.53 312.232 + vertex -881.629 256.064 314.457 + vertex -880.56 255.777 312.22 + endloop + endfacet + facet normal -0.749734 -0.595717 -0.288131 + outer loop + vertex -879.062 252.837 314.451 + vertex -881.629 256.064 314.457 + vertex -877.966 252.53 312.232 + endloop + endfacet + facet normal -0.736042 -0.617027 -0.278423 + outer loop + vertex -875.321 249.365 312.256 + vertex -879.062 252.837 314.451 + vertex -877.966 252.53 312.232 + endloop + endfacet + facet normal -0.736907 -0.610597 -0.290067 + outer loop + vertex -876.445 249.676 314.456 + vertex -879.062 252.837 314.451 + vertex -875.321 249.365 312.256 + endloop + endfacet + facet normal -0.723709 -0.63053 -0.280497 + outer loop + vertex -872.589 246.215 312.288 + vertex -876.445 249.676 314.456 + vertex -875.321 249.365 312.256 + endloop + endfacet + facet normal -0.72423 -0.626882 -0.287246 + outer loop + vertex -873.718 246.518 314.471 + vertex -876.445 249.676 314.456 + vertex -872.589 246.215 312.288 + endloop + endfacet + facet normal -0.709924 -0.647526 -0.276981 + outer loop + vertex -869.706 243.044 312.311 + vertex -873.718 246.518 314.471 + vertex -872.589 246.215 312.288 + endloop + endfacet + facet normal -0.711022 -0.640272 -0.290688 + outer loop + vertex -870.818 243.296 314.476 + vertex -873.718 246.518 314.471 + vertex -869.706 243.044 312.311 + endloop + endfacet + facet normal -0.696063 -0.660875 -0.280608 + outer loop + vertex -866.681 239.862 312.301 + vertex -870.818 243.296 314.476 + vertex -869.706 243.044 312.311 + endloop + endfacet + facet normal -0.697677 -0.650685 -0.299761 + outer loop + vertex -867.763 240.034 314.447 + vertex -870.818 243.296 314.476 + vertex -866.681 239.862 312.301 + endloop + endfacet + facet normal -0.684314 -0.66834 -0.291611 + outer loop + vertex -863.695 236.823 312.261 + vertex -867.763 240.034 314.447 + vertex -866.681 239.862 312.301 + endloop + endfacet + facet normal -0.685421 -0.662357 -0.302459 + outer loop + vertex -864.775 236.957 314.414 + vertex -867.763 240.034 314.447 + vertex -863.695 236.823 312.261 + endloop + endfacet + facet normal -0.679833 -0.669552 -0.29921 + outer loop + vertex -861.124 234.207 312.27 + vertex -864.775 236.957 314.414 + vertex -863.695 236.823 312.261 + endloop + endfacet + facet normal -0.679149 -0.672347 -0.294459 + outer loop + vertex -862.281 234.413 314.468 + vertex -864.775 236.957 314.414 + vertex -861.124 234.207 312.27 + endloop + endfacet + facet normal -0.680427 -0.670689 -0.295288 + outer loop + vertex -859.433 232.388 312.505 + vertex -862.281 234.413 314.468 + vertex -861.124 234.207 312.27 + endloop + endfacet + facet normal -0.675836 -0.683779 -0.275124 + outer loop + vertex -860.678 232.73 314.715 + vertex -862.281 234.413 314.468 + vertex -859.433 232.388 312.505 + endloop + endfacet + facet normal -0.696818 -0.655413 -0.291337 + outer loop + vertex -858.828 231.472 313.12 + vertex -860.678 232.73 314.715 + vertex -859.433 232.388 312.505 + endloop + endfacet + facet normal -0.671142 -0.707878 -0.220177 + outer loop + vertex -860.083 232.036 315.131 + vertex -860.678 232.73 314.715 + vertex -858.828 231.472 313.12 + endloop + endfacet + facet normal -0.962569 0.189784 -0.1935 + outer loop + vertex -903.865 377.986 311.964 + vertex -902.913 382.944 312.087 + vertex -903.185 378.986 309.558 + endloop + endfacet + facet normal -0.963264 0.197401 -0.182087 + outer loop + vertex -902.182 383.357 308.921 + vertex -901.665 388.472 311.73 + vertex -901.296 387.789 309.037 + endloop + endfacet + facet normal -0.949177 0.196253 -0.246064 + outer loop + vertex -901.296 387.789 309.037 + vertex -900.812 385.85 305.623 + vertex -902.182 383.357 308.921 + endloop + endfacet + facet normal -0.935306 0.233915 -0.265492 + outer loop + vertex -901.296 387.789 309.037 + vertex -900.025 394.027 310.055 + vertex -900.812 385.85 305.623 + endloop + endfacet + facet normal -0.969227 0.208572 -0.130756 + outer loop + vertex -903.524 381.814 314.819 + vertex -902.175 388.38 315.29 + vertex -902.913 382.944 312.087 + endloop + endfacet + facet normal -0.955895 0.225491 -0.1882 + outer loop + vertex -901.296 387.789 309.037 + vertex -901.665 388.472 311.73 + vertex -900.025 394.027 310.055 + endloop + endfacet + facet normal -0.934977 0.277496 -0.220938 + outer loop + vertex -888.861 435.92 309.785 + vertex -886.407 444.168 309.755 + vertex -887.944 435.252 305.064 + endloop + endfacet + facet normal -0.936158 0.273731 -0.220634 + outer loop + vertex -890.279 427.233 305.024 + vertex -888.861 435.92 309.785 + vertex -887.944 435.252 305.064 + endloop + endfacet + facet normal -0.937992 0.271346 -0.215737 + outer loop + vertex -891.211 427.748 309.722 + vertex -888.861 435.92 309.785 + vertex -890.279 427.233 305.024 + endloop + endfacet + facet normal -0.939665 0.265725 -0.215453 + outer loop + vertex -892.501 419.333 304.968 + vertex -891.211 427.748 309.722 + vertex -890.279 427.233 305.024 + endloop + endfacet + facet normal -0.941019 0.263867 -0.211796 + outer loop + vertex -893.449 419.713 309.654 + vertex -891.211 427.748 309.722 + vertex -892.501 419.333 304.968 + endloop + endfacet + facet normal -0.943569 0.254781 -0.211575 + outer loop + vertex -894.635 411.395 304.927 + vertex -893.449 419.713 309.654 + vertex -892.501 419.333 304.968 + endloop + endfacet + facet normal -0.944932 0.25283 -0.207799 + outer loop + vertex -895.617 411.592 309.633 + vertex -893.449 419.713 309.654 + vertex -894.635 411.395 304.927 + endloop + endfacet + facet normal -0.948396 0.239369 -0.207958 + outer loop + vertex -896.711 403.196 304.957 + vertex -895.617 411.592 309.633 + vertex -894.635 411.395 304.927 + endloop + endfacet + facet normal -0.948433 0.239315 -0.207853 + outer loop + vertex -897.773 403.126 309.723 + vertex -895.617 411.592 309.633 + vertex -896.711 403.196 304.957 + endloop + endfacet + facet normal -0.951862 0.224379 -0.208838 + outer loop + vertex -898.768 394.622 305.12 + vertex -897.773 403.126 309.723 + vertex -896.711 403.196 304.957 + endloop + endfacet + facet normal -0.949893 0.227267 -0.214599 + outer loop + vertex -900.025 394.027 310.055 + vertex -897.773 403.126 309.723 + vertex -898.768 394.622 305.12 + endloop + endfacet + facet normal -0.953256 0.209672 -0.217579 + outer loop + vertex -900.812 385.85 305.623 + vertex -900.025 394.027 310.055 + vertex -898.768 394.622 305.12 + endloop + endfacet + facet normal -0.949153 0.181051 -0.257546 + outer loop + vertex -900.812 385.85 305.623 + vertex -902.53 376.933 305.685 + vertex -902.182 383.357 308.921 + endloop + endfacet + facet normal -0.952768 0.153347 -0.26214 + outer loop + vertex -902.53 376.933 305.685 + vertex -903.909 368.433 305.727 + vertex -903.876 374.363 309.076 + endloop + endfacet + facet normal -0.954559 0.127023 -0.269598 + outer loop + vertex -903.909 368.433 305.727 + vertex -905.022 360.036 305.711 + vertex -905.175 366.035 309.079 + endloop + endfacet + facet normal -0.951855 0.13126 -0.277024 + outer loop + vertex -905.859 362.077 309.554 + vertex -905.175 366.035 309.079 + vertex -905.022 360.036 305.711 + endloop + endfacet + facet normal -0.955211 0.118694 -0.27108 + outer loop + vertex -905.859 362.077 309.554 + vertex -905.022 360.036 305.711 + vertex -906.272 357.591 309.045 + endloop + endfacet + facet normal -0.953144 0.0961606 -0.286828 + outer loop + vertex -905.022 360.036 305.711 + vertex -905.872 351.55 305.689 + vertex -906.272 357.591 309.045 + endloop + endfacet + facet normal -0.950926 0.0996914 -0.292919 + outer loop + vertex -906.84 353.604 309.532 + vertex -906.272 357.591 309.045 + vertex -905.872 351.55 305.689 + endloop + endfacet + facet normal -0.954821 0.0834535 -0.285222 + outer loop + vertex -906.84 353.604 309.532 + vertex -905.872 351.55 305.689 + vertex -907.09 349.061 309.04 + endloop + endfacet + facet normal -0.951162 0.0572838 -0.30333 + outer loop + vertex -905.872 351.55 305.689 + vertex -906.388 342.966 305.688 + vertex -907.09 349.061 309.04 + endloop + endfacet + facet normal -0.948585 0.0615165 -0.310488 + outer loop + vertex -907.516 344.986 309.532 + vertex -907.09 349.061 309.04 + vertex -906.388 342.966 305.688 + endloop + endfacet + facet normal -0.952232 0.0437518 -0.302225 + outer loop + vertex -907.516 344.986 309.532 + vertex -906.388 342.966 305.688 + vertex -907.571 340.359 309.037 + endloop + endfacet + facet normal -0.945963 0.0129213 -0.324017 + outer loop + vertex -906.388 342.966 305.688 + vertex -906.506 334.341 305.688 + vertex -907.571 340.359 309.037 + endloop + endfacet + facet normal -0.94316 0.017783 -0.331862 + outer loop + vertex -907.823 336.231 309.531 + vertex -907.571 340.359 309.037 + vertex -906.506 334.341 305.688 + endloop + endfacet + facet normal -0.946568 -0.00365244 -0.322485 + outer loop + vertex -907.823 336.231 309.531 + vertex -906.506 334.341 305.688 + vertex -907.637 331.655 309.038 + endloop + endfacet + facet normal -0.936819 -0.0391039 -0.347621 + outer loop + vertex -906.506 334.341 305.688 + vertex -906.149 325.807 305.685 + vertex -907.637 331.655 309.038 + endloop + endfacet + facet normal -0.933412 -0.03268 -0.357314 + outer loop + vertex -907.684 327.593 309.532 + vertex -907.637 331.655 309.038 + vertex -906.149 325.807 305.685 + endloop + endfacet + facet normal -0.93642 -0.0604064 -0.345643 + outer loop + vertex -907.684 327.593 309.532 + vertex -906.149 325.807 305.685 + vertex -907.214 323.127 309.038 + endloop + endfacet + facet normal -0.922503 -0.0999517 -0.372825 + outer loop + vertex -906.149 325.807 305.685 + vertex -905.236 317.399 305.681 + vertex -907.214 323.127 309.038 + endloop + endfacet + facet normal -0.919137 -0.0929337 -0.38282 + outer loop + vertex -907.015 319.15 309.526 + vertex -907.214 323.127 309.038 + vertex -905.236 317.399 305.681 + endloop + endfacet + facet normal -0.920914 -0.123804 -0.36958 + outer loop + vertex -907.015 319.15 309.526 + vertex -905.236 317.399 305.681 + vertex -906.222 314.737 309.028 + endloop + endfacet + facet normal -0.90185 -0.167131 -0.398415 + outer loop + vertex -905.236 317.399 305.681 + vertex -903.69 309.027 305.692 + vertex -906.222 314.737 309.028 + endloop + endfacet + facet normal -0.898413 -0.159277 -0.40925 + outer loop + vertex -905.74 310.777 309.513 + vertex -906.222 314.737 309.028 + vertex -903.69 309.027 305.692 + endloop + endfacet + facet normal -0.89863 -0.194543 -0.393213 + outer loop + vertex -905.74 310.777 309.513 + vertex -903.69 309.027 305.692 + vertex -904.568 306.337 309.029 + endloop + endfacet + facet normal -0.875495 -0.236835 -0.42121 + outer loop + vertex -903.69 309.027 305.692 + vertex -901.44 300.563 305.776 + vertex -904.568 306.337 309.029 + endloop + endfacet + facet normal -0.871415 -0.226905 -0.434914 + outer loop + vertex -903.775 302.322 309.535 + vertex -904.568 306.337 309.029 + vertex -901.44 300.563 305.776 + endloop + endfacet + facet normal -0.869909 -0.263927 -0.416654 + outer loop + vertex -903.775 302.322 309.535 + vertex -901.44 300.563 305.776 + vertex -902.207 297.823 309.113 + endloop + endfacet + facet normal -0.84686 -0.298769 -0.43996 + outer loop + vertex -901.44 300.563 305.776 + vertex -898.43 291.824 305.917 + vertex -902.207 297.823 309.113 + endloop + endfacet + facet normal -0.84364 -0.290615 -0.451459 + outer loop + vertex -901.159 293.872 309.697 + vertex -902.207 297.823 309.113 + vertex -898.43 291.824 305.917 + endloop + endfacet + facet normal -0.841985 -0.320063 -0.434305 + outer loop + vertex -901.159 293.872 309.697 + vertex -898.43 291.824 305.917 + vertex -899.441 289.744 309.409 + endloop + endfacet + facet normal -0.830744 -0.338406 -0.441979 + outer loop + vertex -896.642 286.208 306.855 + vertex -899.441 289.744 309.409 + vertex -898.43 291.824 305.917 + endloop + endfacet + facet normal -0.826658 -0.338378 -0.449596 + outer loop + vertex -895.583 286.668 304.562 + vertex -896.642 286.208 306.855 + vertex -898.43 291.824 305.917 + endloop + endfacet + facet normal -0.803119 -0.30978 -0.508956 + outer loop + vertex -895.583 286.668 304.562 + vertex -898.43 291.824 305.917 + vertex -893.436 286.042 301.555 + endloop + endfacet + facet normal -0.814684 -0.361887 -0.45313 + outer loop + vertex -893.436 286.042 301.555 + vertex -898.43 291.824 305.917 + vertex -896.857 294.222 301.172 + endloop + endfacet + facet normal -0.825701 -0.3654 -0.429767 + outer loop + vertex -893.436 286.042 301.555 + vertex -896.857 294.222 301.172 + vertex -892.218 288.153 297.42 + endloop + endfacet + facet normal -0.827271 -0.372046 -0.420956 + outer loop + vertex -892.218 288.153 297.42 + vertex -896.857 294.222 301.172 + vertex -895.689 296.113 297.207 + endloop + endfacet + facet normal -0.853536 -0.381718 -0.354637 + outer loop + vertex -892.218 288.153 297.42 + vertex -895.689 296.113 297.207 + vertex -891.683 289.858 294.296 + endloop + endfacet + facet normal -0.851315 -0.374193 -0.367753 + outer loop + vertex -891.683 289.858 294.296 + vertex -895.689 296.113 297.207 + vertex -895.272 298.092 294.227 + endloop + endfacet + facet normal -0.83475 -0.359673 -0.416927 + outer loop + vertex -897.633 285.244 309.671 + vertex -899.441 289.744 309.409 + vertex -896.642 286.208 306.855 + endloop + endfacet + facet normal -0.818614 -0.389994 -0.421634 + outer loop + vertex -894.74 281.808 307.232 + vertex -897.633 285.244 309.671 + vertex -896.642 286.208 306.855 + endloop + endfacet + facet normal -0.799814 -0.385177 -0.460366 + outer loop + vertex -894.74 281.808 307.232 + vertex -896.642 286.208 306.855 + vertex -893.609 282.877 304.373 + endloop + endfacet + facet normal -0.781579 -0.416124 -0.464731 + outer loop + vertex -891.919 278.997 305.004 + vertex -894.74 281.808 307.232 + vertex -893.609 282.877 304.373 + endloop + endfacet + facet normal -0.755909 -0.41209 -0.508707 + outer loop + vertex -891.919 278.997 305.004 + vertex -893.609 282.877 304.373 + vertex -889.19 278.183 301.609 + endloop + endfacet + facet normal -0.747329 -0.444263 -0.494095 + outer loop + vertex -891.919 278.997 305.004 + vertex -889.19 278.183 301.609 + vertex -889.365 275.091 304.655 + endloop + endfacet + facet normal -0.757366 -0.452947 -0.470357 + outer loop + vertex -889.365 275.091 304.655 + vertex -892.674 277.779 307.394 + vertex -891.919 278.997 305.004 + endloop + endfacet + facet normal -0.757212 -0.442174 -0.480742 + outer loop + vertex -890.508 274.021 307.439 + vertex -892.674 277.779 307.394 + vertex -889.365 275.091 304.655 + endloop + endfacet + facet normal -0.740073 -0.467516 -0.483447 + outer loop + vertex -887.451 271.547 305.151 + vertex -890.508 274.021 307.439 + vertex -889.365 275.091 304.655 + endloop + endfacet + facet normal -0.715513 -0.460152 -0.525643 + outer loop + vertex -887.451 271.547 305.151 + vertex -889.365 275.091 304.655 + vertex -884.551 270.877 301.79 + endloop + endfacet + facet normal -0.706265 -0.489026 -0.511902 + outer loop + vertex -887.451 271.547 305.151 + vertex -884.551 270.877 301.79 + vertex -884.675 267.956 304.752 + endloop + endfacet + facet normal -0.715163 -0.498323 -0.490119 + outer loop + vertex -884.675 267.956 304.752 + vertex -888.244 270.426 307.448 + vertex -887.451 271.547 305.151 + endloop + endfacet + facet normal -0.715523 -0.484825 -0.502962 + outer loop + vertex -885.869 266.904 307.463 + vertex -888.244 270.426 307.448 + vertex -884.675 267.956 304.752 + endloop + endfacet + facet normal -0.699106 -0.506889 -0.504296 + outer loop + vertex -882.575 264.568 305.245 + vertex -885.869 266.904 307.463 + vertex -884.675 267.956 304.752 + endloop + endfacet + facet normal -0.673199 -0.497113 -0.547431 + outer loop + vertex -882.575 264.568 305.245 + vertex -884.675 267.956 304.752 + vertex -879.531 264.02 301.999 + endloop + endfacet + facet normal -0.66381 -0.523453 -0.534185 + outer loop + vertex -882.575 264.568 305.245 + vertex -879.531 264.02 301.999 + vertex -879.582 261.103 304.921 + endloop + endfacet + facet normal -0.673429 -0.533902 -0.511314 + outer loop + vertex -879.582 261.103 304.921 + vertex -883.376 263.414 307.506 + vertex -882.575 264.568 305.245 + endloop + endfacet + facet normal -0.674223 -0.514415 -0.529906 + outer loop + vertex -880.79 259.957 307.57 + vertex -883.376 263.414 307.506 + vertex -879.582 261.103 304.921 + endloop + endfacet + facet normal -0.656691 -0.535502 -0.531031 + outer loop + vertex -877.316 257.786 305.464 + vertex -880.79 259.957 307.57 + vertex -879.582 261.103 304.921 + endloop + endfacet + facet normal -0.629245 -0.523812 -0.574171 + outer loop + vertex -877.316 257.786 305.464 + vertex -879.582 261.103 304.921 + vertex -874.186 257.47 302.323 + endloop + endfacet + facet normal -0.620473 -0.545691 -0.563236 + outer loop + vertex -877.316 257.786 305.464 + vertex -874.186 257.47 302.323 + vertex -874.154 254.452 305.212 + endloop + endfacet + facet normal -0.631199 -0.557695 -0.53904 + outer loop + vertex -874.154 254.452 305.212 + vertex -878.142 256.593 307.666 + vertex -877.316 257.786 305.464 + endloop + endfacet + facet normal -0.632192 -0.534989 -0.560464 + outer loop + vertex -875.477 253.307 307.797 + vertex -878.142 256.593 307.666 + vertex -874.154 254.452 305.212 + endloop + endfacet + facet normal -0.615858 -0.553758 -0.56042 + outer loop + vertex -871.864 251.274 305.835 + vertex -875.477 253.307 307.797 + vertex -874.154 254.452 305.212 + endloop + endfacet + facet normal -0.583405 -0.539525 -0.607084 + outer loop + vertex -871.864 251.274 305.835 + vertex -874.154 254.452 305.212 + vertex -868.28 251.043 302.596 + endloop + endfacet + facet normal -0.577018 -0.555314 -0.598896 + outer loop + vertex -871.864 251.274 305.835 + vertex -868.28 251.043 302.596 + vertex -868.786 248.221 305.7 + endloop + endfacet + facet normal -0.590675 -0.570324 -0.570818 + outer loop + vertex -868.786 248.221 305.7 + vertex -872.798 250.108 307.966 + vertex -871.864 251.274 305.835 + endloop + endfacet + facet normal -0.591633 -0.550195 -0.589284 + outer loop + vertex -869.928 246.861 308.116 + vertex -872.798 250.108 307.966 + vertex -868.786 248.221 305.7 + endloop + endfacet + facet normal -0.567067 -0.573779 -0.590942 + outer loop + vertex -865.586 244.665 306.082 + vertex -869.928 246.861 308.116 + vertex -868.786 248.221 305.7 + endloop + endfacet + facet normal -0.546369 -0.558701 -0.623966 + outer loop + vertex -865.586 244.665 306.082 + vertex -868.786 248.221 305.7 + vertex -864.316 246.297 303.51 + endloop + endfacet + facet normal -0.51928 -0.582275 -0.625543 + outer loop + vertex -861.079 242.834 304.045 + vertex -865.586 244.665 306.082 + vertex -864.316 246.297 303.51 + endloop + endfacet + facet normal -0.507461 -0.573886 -0.642758 + outer loop + vertex -861.079 242.834 304.045 + vertex -864.316 246.297 303.51 + vertex -859.774 244.473 301.552 + endloop + endfacet + facet normal -0.478294 -0.597881 -0.643252 + outer loop + vertex -856.844 241.625 302.02 + vertex -861.079 242.834 304.045 + vertex -859.774 244.473 301.552 + endloop + endfacet + facet normal -0.469694 -0.591089 -0.655745 + outer loop + vertex -856.844 241.625 302.02 + vertex -859.774 244.473 301.552 + vertex -855.829 243.402 299.691 + endloop + endfacet + facet normal -0.481864 -0.56257 -0.671804 + outer loop + vertex -858.104 239.875 304.389 + vertex -861.079 242.834 304.045 + vertex -856.844 241.625 302.02 + endloop + endfacet + facet normal -0.460792 -0.578937 -0.672683 + outer loop + vertex -854.45 239.254 302.42 + vertex -858.104 239.875 304.389 + vertex -856.844 241.625 302.02 + endloop + endfacet + facet normal -0.450759 -0.571065 -0.686077 + outer loop + vertex -856.844 241.625 302.02 + vertex -853.478 241.169 300.187 + vertex -854.45 239.254 302.42 + endloop + endfacet + facet normal -0.467919 -0.543061 -0.697234 + outer loop + vertex -855.655 237.436 304.645 + vertex -858.104 239.875 304.389 + vertex -854.45 239.254 302.42 + endloop + endfacet + facet normal -0.45464 -0.553028 -0.698185 + outer loop + vertex -852.996 237.354 302.978 + vertex -855.655 237.436 304.645 + vertex -854.45 239.254 302.42 + endloop + endfacet + facet normal -0.442283 -0.547218 -0.71059 + outer loop + vertex -852.996 237.354 302.978 + vertex -854.45 239.254 302.42 + vertex -851.962 239.462 300.712 + endloop + endfacet + facet normal -0.419852 -0.561159 -0.71332 + outer loop + vertex -852.996 237.354 302.978 + vertex -851.962 239.462 300.712 + vertex -851.399 237.487 301.934 + endloop + endfacet + facet normal -0.432467 -0.530912 -0.728769 + outer loop + vertex -852.631 235.834 303.869 + vertex -852.996 237.354 302.978 + vertex -851.399 237.487 301.934 + endloop + endfacet + facet normal -0.410326 -0.547782 -0.729087 + outer loop + vertex -851.399 237.487 301.934 + vertex -852.742 234.619 304.845 + vertex -852.631 235.834 303.869 + endloop + endfacet + facet normal -0.42962 -0.541079 -0.722953 + outer loop + vertex -853.516 234.57 305.341 + vertex -852.631 235.834 303.869 + vertex -852.742 234.619 304.845 + endloop + endfacet + facet normal -0.420135 -0.564586 -0.710443 + outer loop + vertex -854.5 233.418 306.839 + vertex -853.516 234.57 305.341 + vertex -852.742 234.619 304.845 + endloop + endfacet + facet normal -0.413176 -0.571871 -0.708695 + outer loop + vertex -852.742 234.619 304.845 + vertex -854.62 232.704 307.485 + vertex -854.5 233.418 306.839 + endloop + endfacet + facet normal -0.478755 -0.515136 -0.710935 + outer loop + vertex -854.5 233.418 306.839 + vertex -855.272 234.297 306.722 + vertex -853.516 234.57 305.341 + endloop + endfacet + facet normal -0.47762 -0.517524 -0.709964 + outer loop + vertex -853.516 234.57 305.341 + vertex -855.272 234.297 306.722 + vertex -854.092 235.619 304.965 + endloop + endfacet + facet normal -0.482363 -0.5132 -0.709896 + outer loop + vertex -855.272 234.297 306.722 + vertex -856.973 236.026 306.627 + vertex -854.092 235.619 304.965 + endloop + endfacet + facet normal -0.478122 -0.533728 -0.69752 + outer loop + vertex -854.092 235.619 304.965 + vertex -856.973 236.026 306.627 + vertex -855.655 237.436 304.645 + endloop + endfacet + facet normal -0.485546 -0.526889 -0.697591 + outer loop + vertex -856.973 236.026 306.627 + vertex -859.467 238.437 306.543 + vertex -855.655 237.436 304.645 + endloop + endfacet + facet normal -0.5017 -0.531492 -0.682505 + outer loop + vertex -854.5 233.418 306.839 + vertex -856.637 233.294 308.506 + vertex -855.272 234.297 306.722 + endloop + endfacet + facet normal -0.50809 -0.524292 -0.683346 + outer loop + vertex -856.637 233.294 308.506 + vertex -858.365 235.043 308.449 + vertex -855.272 234.297 306.722 + endloop + endfacet + facet normal -0.506599 -0.535178 -0.675975 + outer loop + vertex -855.272 234.297 306.722 + vertex -858.365 235.043 308.449 + vertex -856.973 236.026 306.627 + endloop + endfacet + facet normal -0.512642 -0.528263 -0.676858 + outer loop + vertex -858.365 235.043 308.449 + vertex -860.911 237.499 308.461 + vertex -856.973 236.026 306.627 + endloop + endfacet + facet normal -0.512571 -0.553423 -0.656501 + outer loop + vertex -856.973 236.026 306.627 + vertex -860.911 237.499 308.461 + vertex -859.467 238.437 306.543 + endloop + endfacet + facet normal -0.523979 -0.540111 -0.658578 + outer loop + vertex -860.911 237.499 308.461 + vertex -863.88 240.411 308.434 + vertex -859.467 238.437 306.543 + endloop + endfacet + facet normal -0.525631 -0.568027 -0.63329 + outer loop + vertex -859.467 238.437 306.543 + vertex -863.88 240.411 308.434 + vertex -862.454 241.376 306.386 + endloop + endfacet + facet normal -0.542452 -0.548883 -0.635982 + outer loop + vertex -863.88 240.411 308.434 + vertex -866.94 243.574 308.315 + vertex -862.454 241.376 306.386 + endloop + endfacet + facet normal -0.54438 -0.574737 -0.611006 + outer loop + vertex -862.454 241.376 306.386 + vertex -866.94 243.574 308.315 + vertex -865.586 244.665 306.082 + endloop + endfacet + facet normal -0.497534 -0.541227 -0.677888 + outer loop + vertex -855.984 232.244 308.865 + vertex -856.637 233.294 308.506 + vertex -854.5 233.418 306.839 + endloop + endfacet + facet normal -0.508863 -0.529024 -0.679111 + outer loop + vertex -855.984 232.244 308.865 + vertex -854.5 233.418 306.839 + vertex -854.62 232.704 307.485 + endloop + endfacet + facet normal -0.464537 -0.514262 -0.72093 + outer loop + vertex -853.516 234.57 305.341 + vertex -854.092 235.619 304.965 + vertex -852.631 235.834 303.869 + endloop + endfacet + facet normal -0.399391 -0.554168 -0.730331 + outer loop + vertex -852.742 234.619 304.845 + vertex -851.399 237.487 301.934 + vertex -850.56 235.476 303.001 + endloop + endfacet + facet normal -0.416692 -0.52915 -0.739167 + outer loop + vertex -850.56 235.476 303.001 + vertex -851.604 233.63 304.911 + vertex -852.742 234.619 304.845 + endloop + endfacet + facet normal -0.428965 -0.542181 -0.722516 + outer loop + vertex -851.604 233.63 304.911 + vertex -853.281 232.637 306.652 + vertex -852.742 234.619 304.845 + endloop + endfacet + facet normal -0.441912 -0.526702 -0.726153 + outer loop + vertex -853.281 232.637 306.652 + vertex -851.604 233.63 304.911 + vertex -851.151 231.382 306.266 + endloop + endfacet + facet normal -0.448932 -0.543939 -0.708936 + outer loop + vertex -852.667 229.613 308.584 + vertex -853.281 232.637 306.652 + vertex -851.151 231.382 306.266 + endloop + endfacet + facet normal -0.460648 -0.533976 -0.708994 + outer loop + vertex -852.667 229.613 308.584 + vertex -851.151 231.382 306.266 + vertex -847.335 226.751 307.275 + endloop + endfacet + facet normal -0.419896 -0.509561 -0.751023 + outer loop + vertex -851.151 231.382 306.266 + vertex -848.52 231.583 304.658 + vertex -847.335 226.751 307.275 + endloop + endfacet + facet normal -0.480028 -0.539351 -0.691862 + outer loop + vertex -855.136 231.595 308.751 + vertex -853.281 232.637 306.652 + vertex -852.667 229.613 308.584 + endloop + endfacet + facet normal -0.412327 -0.529779 -0.741162 + outer loop + vertex -851.151 231.382 306.266 + vertex -851.604 233.63 304.911 + vertex -848.52 231.583 304.658 + endloop + endfacet + facet normal -0.413267 -0.531403 -0.739473 + outer loop + vertex -851.604 233.63 304.911 + vertex -850.56 235.476 303.001 + vertex -848.52 231.583 304.658 + endloop + endfacet + facet normal -0.369417 -0.521148 -0.769373 + outer loop + vertex -848.52 231.583 304.658 + vertex -850.56 235.476 303.001 + vertex -847.718 234.487 302.306 + endloop + endfacet + facet normal -0.375212 -0.518645 -0.76826 + outer loop + vertex -848.52 231.583 304.658 + vertex -847.718 234.487 302.306 + vertex -843.866 228.944 304.167 + endloop + endfacet + facet normal -0.374016 -0.550572 -0.746313 + outer loop + vertex -850.56 235.476 303.001 + vertex -849.601 237.948 300.697 + vertex -847.718 234.487 302.306 + endloop + endfacet + facet normal -0.325475 -0.538522 -0.777213 + outer loop + vertex -847.718 234.487 302.306 + vertex -849.601 237.948 300.697 + vertex -847.638 237.083 300.474 + endloop + endfacet + facet normal -0.333414 -0.536761 -0.775063 + outer loop + vertex -847.718 234.487 302.306 + vertex -847.638 237.083 300.474 + vertex -843.573 232.187 302.116 + endloop + endfacet + facet normal -0.311619 -0.524464 -0.792358 + outer loop + vertex -847.638 237.083 300.474 + vertex -846.407 237.831 299.495 + vertex -843.573 232.187 302.116 + endloop + endfacet + facet normal -0.333214 -0.561115 -0.757706 + outer loop + vertex -849.601 237.948 300.697 + vertex -848.685 239.425 299.201 + vertex -847.638 237.083 300.474 + endloop + endfacet + facet normal -0.372265 -0.551458 -0.746534 + outer loop + vertex -849.601 237.948 300.697 + vertex -850.56 235.476 303.001 + vertex -851.399 237.487 301.934 + endloop + endfacet + facet normal -0.355501 -0.580127 -0.732851 + outer loop + vertex -851.399 237.487 301.934 + vertex -850.001 240.376 298.969 + vertex -849.601 237.948 300.697 + endloop + endfacet + facet normal -0.457767 -0.528768 -0.71474 + outer loop + vertex -852.631 235.834 303.869 + vertex -854.092 235.619 304.965 + vertex -852.996 237.354 302.978 + endloop + endfacet + facet normal -0.387114 -0.5625 -0.730573 + outer loop + vertex -850.001 240.376 298.969 + vertex -851.399 237.487 301.934 + vertex -851.962 239.462 300.712 + endloop + endfacet + facet normal -0.463766 -0.52431 -0.714157 + outer loop + vertex -854.092 235.619 304.965 + vertex -855.655 237.436 304.645 + vertex -852.996 237.354 302.978 + endloop + endfacet + facet normal -0.482765 -0.555822 -0.676757 + outer loop + vertex -855.655 237.436 304.645 + vertex -859.467 238.437 306.543 + vertex -858.104 239.875 304.389 + endloop + endfacet + facet normal -0.497769 -0.542055 -0.677054 + outer loop + vertex -859.467 238.437 306.543 + vertex -862.454 241.376 306.386 + vertex -858.104 239.875 304.389 + endloop + endfacet + facet normal -0.496752 -0.575011 -0.650076 + outer loop + vertex -858.104 239.875 304.389 + vertex -862.454 241.376 306.386 + vertex -861.079 242.834 304.045 + endloop + endfacet + facet normal -0.507438 -0.602174 -0.616354 + outer loop + vertex -859.774 244.473 301.552 + vertex -864.316 246.297 303.51 + vertex -862.725 247.434 301.088 + endloop + endfacet + facet normal -0.502626 -0.598541 -0.623791 + outer loop + vertex -862.725 247.434 301.088 + vertex -858.943 246.192 299.233 + vertex -859.774 244.473 301.552 + endloop + endfacet + facet normal -0.53848 -0.569241 -0.621292 + outer loop + vertex -862.725 247.434 301.088 + vertex -864.316 246.297 303.51 + vertex -868.28 251.043 302.596 + endloop + endfacet + facet normal -0.547471 -0.598134 -0.585245 + outer loop + vertex -862.725 247.434 301.088 + vertex -868.28 251.043 302.596 + vertex -862.979 249.614 299.098 + endloop + endfacet + facet normal -0.519206 -0.554408 -0.650428 + outer loop + vertex -862.454 241.376 306.386 + vertex -865.586 244.665 306.082 + vertex -861.079 242.834 304.045 + endloop + endfacet + facet normal -0.566018 -0.551489 -0.612767 + outer loop + vertex -866.94 243.574 308.315 + vertex -869.928 246.861 308.116 + vertex -865.586 244.665 306.082 + endloop + endfacet + facet normal -0.546172 -0.573586 -0.610488 + outer loop + vertex -864.316 246.297 303.51 + vertex -868.786 248.221 305.7 + vertex -868.28 251.043 302.596 + endloop + endfacet + facet normal -0.615689 -0.545785 -0.56837 + outer loop + vertex -872.798 250.108 307.966 + vertex -875.477 253.307 307.797 + vertex -871.864 251.274 305.835 + endloop + endfacet + facet normal -0.586188 -0.563442 -0.582166 + outer loop + vertex -874.186 257.47 302.323 + vertex -868.28 251.043 302.596 + vertex -874.154 254.452 305.212 + endloop + endfacet + facet normal -0.598891 -0.574101 -0.558335 + outer loop + vertex -868.28 251.043 302.596 + vertex -874.186 257.47 302.323 + vertex -867.87 254.196 298.914 + endloop + endfacet + facet normal -0.598264 -0.592284 -0.539703 + outer loop + vertex -867.87 254.196 298.914 + vertex -874.186 257.47 302.323 + vertex -873.176 259.989 298.439 + endloop + endfacet + facet normal -0.614682 -0.604602 -0.506579 + outer loop + vertex -867.87 254.196 298.914 + vertex -873.176 259.989 298.439 + vertex -867.002 255.942 295.777 + endloop + endfacet + facet normal -0.616363 -0.627069 -0.476321 + outer loop + vertex -867.002 255.942 295.777 + vertex -873.176 259.989 298.439 + vertex -872.85 262.144 295.179 + endloop + endfacet + facet normal -0.656655 -0.531947 -0.534637 + outer loop + vertex -878.142 256.593 307.666 + vertex -880.79 259.957 307.57 + vertex -877.316 257.786 305.464 + endloop + endfacet + facet normal -0.631946 -0.542921 -0.553066 + outer loop + vertex -879.531 264.02 301.999 + vertex -874.186 257.47 302.323 + vertex -879.582 261.103 304.921 + endloop + endfacet + facet normal -0.645794 -0.55291 -0.526537 + outer loop + vertex -874.186 257.47 302.323 + vertex -879.531 264.02 301.999 + vertex -873.176 259.989 298.439 + endloop + endfacet + facet normal -0.646036 -0.56649 -0.511592 + outer loop + vertex -873.176 259.989 298.439 + vertex -879.531 264.02 301.999 + vertex -878.537 266.436 298.07 + endloop + endfacet + facet normal -0.672136 -0.584894 -0.454018 + outer loop + vertex -873.176 259.989 298.439 + vertex -878.537 266.436 298.07 + vertex -872.85 262.144 295.179 + endloop + endfacet + facet normal -0.672419 -0.590356 -0.446467 + outer loop + vertex -872.85 262.144 295.179 + vertex -878.537 266.436 298.07 + vertex -878.427 268.758 294.833 + endloop + endfacet + facet normal -0.699079 -0.505377 -0.505848 + outer loop + vertex -883.376 263.414 307.506 + vertex -885.869 266.904 307.463 + vertex -882.575 264.568 305.245 + endloop + endfacet + facet normal -0.738822 -0.500305 -0.451484 + outer loop + vertex -885.869 266.904 307.463 + vertex -889.33 269.823 309.893 + vertex -888.244 270.426 307.448 + endloop + endfacet + facet normal -0.758045 -0.469717 -0.452474 + outer loop + vertex -889.33 269.823 309.893 + vertex -891.561 273.414 309.903 + vertex -888.244 270.426 307.448 + endloop + endfacet + facet normal -0.758516 -0.478886 -0.441951 + outer loop + vertex -888.244 270.426 307.448 + vertex -891.561 273.414 309.903 + vertex -890.508 274.021 307.439 + endloop + endfacet + facet normal -0.779058 -0.444401 -0.44224 + outer loop + vertex -891.561 273.414 309.903 + vertex -893.68 277.125 309.906 + vertex -890.508 274.021 307.439 + endloop + endfacet + facet normal -0.738304 -0.487678 -0.465915 + outer loop + vertex -886.978 266.253 309.902 + vertex -889.33 269.823 309.893 + vertex -885.869 266.904 307.463 + endloop + endfacet + facet normal -0.717866 -0.518297 -0.464798 + outer loop + vertex -883.376 263.414 307.506 + vertex -886.978 266.253 309.902 + vertex -885.869 266.904 307.463 + endloop + endfacet + facet normal -0.717466 -0.506067 -0.478684 + outer loop + vertex -884.505 262.728 309.924 + vertex -886.978 266.253 309.902 + vertex -883.376 263.414 307.506 + endloop + endfacet + facet normal -0.699168 -0.532101 -0.477528 + outer loop + vertex -880.79 259.957 307.57 + vertex -884.505 262.728 309.924 + vertex -883.376 263.414 307.506 + endloop + endfacet + facet normal -0.698821 -0.520482 -0.49066 + outer loop + vertex -881.947 259.264 309.954 + vertex -884.505 262.728 309.924 + vertex -880.79 259.957 307.57 + endloop + endfacet + facet normal -0.678715 -0.548015 -0.488902 + outer loop + vertex -878.142 256.593 307.666 + vertex -881.947 259.264 309.954 + vertex -880.79 259.957 307.57 + endloop + endfacet + facet normal -0.67838 -0.534759 -0.503819 + outer loop + vertex -879.34 255.914 309.999 + vertex -881.947 259.264 309.954 + vertex -878.142 256.593 307.666 + endloop + endfacet + facet normal -0.661965 -0.55678 -0.501794 + outer loop + vertex -875.477 253.307 307.797 + vertex -879.34 255.914 309.999 + vertex -878.142 256.593 307.666 + endloop + endfacet + facet normal -0.661478 -0.542693 -0.517621 + outer loop + vertex -876.714 252.65 310.066 + vertex -879.34 255.914 309.999 + vertex -875.477 253.307 307.797 + endloop + endfacet + facet normal -0.643634 -0.566361 -0.514752 + outer loop + vertex -872.798 250.108 307.966 + vertex -876.714 252.65 310.066 + vertex -875.477 253.307 307.797 + endloop + endfacet + facet normal -0.642883 -0.550248 -0.53285 + outer loop + vertex -874.037 249.444 310.147 + vertex -876.714 252.65 310.066 + vertex -872.798 250.108 307.966 + endloop + endfacet + facet normal -0.623343 -0.575453 -0.529431 + outer loop + vertex -869.928 246.861 308.116 + vertex -874.037 249.444 310.147 + vertex -872.798 250.108 307.966 + endloop + endfacet + facet normal -0.622263 -0.559678 -0.547311 + outer loop + vertex -871.256 246.265 310.236 + vertex -874.037 249.444 310.147 + vertex -869.928 246.861 308.116 + endloop + endfacet + facet normal -0.604886 -0.582588 -0.542866 + outer loop + vertex -866.94 243.574 308.315 + vertex -871.256 246.265 310.236 + vertex -869.928 246.861 308.116 + endloop + endfacet + facet normal -0.602632 -0.562184 -0.566378 + outer loop + vertex -868.35 243.071 310.313 + vertex -871.256 246.265 310.236 + vertex -866.94 243.574 308.315 + endloop + endfacet + facet normal -0.584743 -0.586934 -0.559986 + outer loop + vertex -863.88 240.411 308.434 + vertex -868.35 243.071 310.313 + vertex -866.94 243.574 308.315 + endloop + endfacet + facet normal -0.582312 -0.566613 -0.582977 + outer loop + vertex -865.324 239.937 310.338 + vertex -868.35 243.071 310.313 + vertex -863.88 240.411 308.434 + endloop + endfacet + facet normal -0.569043 -0.585323 -0.57757 + outer loop + vertex -860.911 237.499 308.461 + vertex -865.324 239.937 310.338 + vertex -863.88 240.411 308.434 + endloop + endfacet + facet normal -0.566794 -0.562467 -0.601976 + outer loop + vertex -862.354 236.976 310.308 + vertex -865.324 239.937 310.338 + vertex -860.911 237.499 308.461 + endloop + endfacet + facet normal -0.557622 -0.575273 -0.59843 + outer loop + vertex -858.365 235.043 308.449 + vertex -862.354 236.976 310.308 + vertex -860.911 237.499 308.461 + endloop + endfacet + facet normal -0.557132 -0.560583 -0.612659 + outer loop + vertex -859.8 234.458 310.29 + vertex -862.354 236.976 310.308 + vertex -858.365 235.043 308.449 + endloop + endfacet + facet normal -0.55296 -0.566265 -0.611211 + outer loop + vertex -856.637 233.294 308.506 + vertex -859.8 234.458 310.29 + vertex -858.365 235.043 308.449 + endloop + endfacet + facet normal -0.553277 -0.563116 -0.613827 + outer loop + vertex -858.063 232.598 310.43 + vertex -859.8 234.458 310.29 + vertex -856.637 233.294 308.506 + endloop + endfacet + facet normal -0.557809 -0.557261 -0.615069 + outer loop + vertex -855.984 232.244 308.865 + vertex -858.063 232.598 310.43 + vertex -856.637 233.294 308.506 + endloop + endfacet + facet normal -0.543963 -0.599517 -0.587098 + outer loop + vertex -857.424 231.518 310.941 + vertex -858.063 232.598 310.43 + vertex -855.984 232.244 308.865 + endloop + endfacet + facet normal -0.675366 -0.510728 -0.532013 + outer loop + vertex -884.551 270.877 301.79 + vertex -879.531 264.02 301.999 + vertex -884.675 267.956 304.752 + endloop + endfacet + facet normal -0.740067 -0.467365 -0.483603 + outer loop + vertex -888.244 270.426 307.448 + vertex -890.508 274.021 307.439 + vertex -887.451 271.547 305.151 + endloop + endfacet + facet normal -0.779816 -0.454605 -0.430373 + outer loop + vertex -890.508 274.021 307.439 + vertex -893.68 277.125 309.906 + vertex -892.674 277.779 307.394 + endloop + endfacet + facet normal -0.799122 -0.420828 -0.42931 + outer loop + vertex -893.68 277.125 309.906 + vertex -895.71 281.038 309.85 + vertex -892.674 277.779 307.394 + endloop + endfacet + facet normal -0.799777 -0.426981 -0.421953 + outer loop + vertex -892.674 277.779 307.394 + vertex -895.71 281.038 309.85 + vertex -894.74 281.808 307.232 + endloop + endfacet + facet normal -0.717018 -0.468072 -0.516521 + outer loop + vertex -889.19 278.183 301.609 + vertex -884.551 270.877 301.79 + vertex -889.365 275.091 304.655 + endloop + endfacet + facet normal -0.738732 -0.480763 -0.472378 + outer loop + vertex -884.551 270.877 301.79 + vertex -889.19 278.183 301.609 + vertex -883.573 273.292 297.802 + endloop + endfacet + facet normal -0.738653 -0.479867 -0.473412 + outer loop + vertex -883.573 273.292 297.802 + vertex -889.19 278.183 301.609 + vertex -888.178 280.552 297.628 + endloop + endfacet + facet normal -0.770833 -0.498436 -0.39671 + outer loop + vertex -883.573 273.292 297.802 + vertex -888.178 280.552 297.628 + vertex -883.384 275.562 294.583 + endloop + endfacet + facet normal -0.769912 -0.490605 -0.408096 + outer loop + vertex -883.384 275.562 294.583 + vertex -888.178 280.552 297.628 + vertex -887.903 282.67 294.564 + endloop + endfacet + facet normal -0.755843 -0.41186 -0.508991 + outer loop + vertex -893.436 286.042 301.555 + vertex -889.19 278.183 301.609 + vertex -893.609 282.877 304.373 + endloop + endfacet + facet normal -0.786927 -0.385763 -0.481595 + outer loop + vertex -895.583 286.668 304.562 + vertex -893.436 286.042 301.555 + vertex -893.609 282.877 304.373 + endloop + endfacet + facet normal -0.783141 -0.426222 -0.452797 + outer loop + vertex -889.19 278.183 301.609 + vertex -893.436 286.042 301.555 + vertex -888.178 280.552 297.628 + endloop + endfacet + facet normal -0.783518 -0.428791 -0.449708 + outer loop + vertex -888.178 280.552 297.628 + vertex -893.436 286.042 301.555 + vertex -892.218 288.153 297.42 + endloop + endfacet + facet normal -0.812905 -0.442472 -0.378686 + outer loop + vertex -888.178 280.552 297.628 + vertex -892.218 288.153 297.42 + vertex -887.903 282.67 294.564 + endloop + endfacet + facet normal -0.812703 -0.441492 -0.380262 + outer loop + vertex -887.903 282.67 294.564 + vertex -892.218 288.153 297.42 + vertex -891.683 289.858 294.296 + endloop + endfacet + facet normal -0.781982 -0.419437 -0.46106 + outer loop + vertex -892.674 277.779 307.394 + vertex -894.74 281.808 307.232 + vertex -891.919 278.997 305.004 + endloop + endfacet + facet normal -0.801394 -0.394903 -0.449243 + outer loop + vertex -893.609 282.877 304.373 + vertex -896.642 286.208 306.855 + vertex -895.583 286.668 304.562 + endloop + endfacet + facet normal -0.818961 -0.392266 -0.418845 + outer loop + vertex -895.71 281.038 309.85 + vertex -897.633 285.244 309.671 + vertex -894.74 281.808 307.232 + endloop + endfacet + facet normal -0.849911 -0.299714 -0.433384 + outer loop + vertex -898.43 291.824 305.917 + vertex -901.44 300.563 305.776 + vertex -896.857 294.222 301.172 + endloop + endfacet + facet normal -0.851358 -0.306116 -0.426009 + outer loop + vertex -896.857 294.222 301.172 + vertex -901.44 300.563 305.776 + vertex -899.762 302.564 300.983 + endloop + endfacet + facet normal -0.862136 -0.309311 -0.401308 + outer loop + vertex -896.857 294.222 301.172 + vertex -899.762 302.564 300.983 + vertex -895.689 296.113 297.207 + endloop + endfacet + facet normal -0.862101 -0.309192 -0.401474 + outer loop + vertex -895.689 296.113 297.207 + vertex -899.762 302.564 300.983 + vertex -898.605 304.355 297.12 + endloop + endfacet + facet normal -0.887154 -0.317354 -0.335028 + outer loop + vertex -895.689 296.113 297.207 + vertex -898.605 304.355 297.12 + vertex -895.272 298.092 294.227 + endloop + endfacet + facet normal -0.88308 -0.30539 -0.35624 + outer loop + vertex -895.272 298.092 294.227 + vertex -898.605 304.355 297.12 + vertex -898.222 306.47 294.357 + endloop + endfacet + facet normal -0.881279 -0.238243 -0.408151 + outer loop + vertex -901.44 300.563 305.776 + vertex -903.69 309.027 305.692 + vertex -899.762 302.564 300.983 + endloop + endfacet + facet normal -0.881767 -0.240104 -0.406002 + outer loop + vertex -899.762 302.564 300.983 + vertex -903.69 309.027 305.692 + vertex -901.996 310.886 300.913 + endloop + endfacet + facet normal -0.892624 -0.242798 -0.379831 + outer loop + vertex -899.762 302.564 300.983 + vertex -901.996 310.886 300.913 + vertex -898.605 304.355 297.12 + endloop + endfacet + facet normal -0.892395 -0.242112 -0.380806 + outer loop + vertex -898.605 304.355 297.12 + vertex -901.996 310.886 300.913 + vertex -900.807 312.56 297.065 + endloop + endfacet + facet normal -0.91555 -0.247898 -0.316724 + outer loop + vertex -898.605 304.355 297.12 + vertex -900.807 312.56 297.065 + vertex -898.222 306.47 294.357 + endloop + endfacet + facet normal -0.911382 -0.237505 -0.336116 + outer loop + vertex -898.222 306.47 294.357 + vertex -900.807 312.56 297.065 + vertex -900.193 314.278 294.184 + endloop + endfacet + facet normal -0.906728 -0.168017 -0.3868 + outer loop + vertex -903.69 309.027 305.692 + vertex -905.236 317.399 305.681 + vertex -901.996 310.886 300.913 + endloop + endfacet + facet normal -0.90761 -0.170906 -0.383453 + outer loop + vertex -901.996 310.886 300.913 + vertex -905.236 317.399 305.681 + vertex -903.549 319.186 300.892 + endloop + endfacet + facet normal -0.917475 -0.172687 -0.358357 + outer loop + vertex -901.996 310.886 300.913 + vertex -903.549 319.186 300.892 + vertex -900.807 312.56 297.065 + endloop + endfacet + facet normal -0.916232 -0.169465 -0.363044 + outer loop + vertex -900.807 312.56 297.065 + vertex -903.549 319.186 300.892 + vertex -902.327 320.768 297.069 + endloop + endfacet + facet normal -0.936995 -0.17334 -0.303305 + outer loop + vertex -900.807 312.56 297.065 + vertex -902.327 320.768 297.069 + vertex -900.193 314.278 294.184 + endloop + endfacet + facet normal -0.931472 -0.161414 -0.326046 + outer loop + vertex -900.193 314.278 294.184 + vertex -902.327 320.768 297.069 + vertex -901.705 322.663 294.352 + endloop + endfacet + facet normal -0.926117 -0.100349 -0.363644 + outer loop + vertex -905.236 317.399 305.681 + vertex -906.149 325.807 305.685 + vertex -903.549 319.186 300.892 + endloop + endfacet + facet normal -0.926978 -0.102772 -0.360763 + outer loop + vertex -903.549 319.186 300.892 + vertex -906.149 325.807 305.685 + vertex -904.48 327.539 300.904 + endloop + endfacet + facet normal -0.934149 -0.103599 -0.341514 + outer loop + vertex -903.549 319.186 300.892 + vertex -904.48 327.539 300.904 + vertex -902.327 320.768 297.069 + endloop + endfacet + facet normal -0.933783 -0.102775 -0.342764 + outer loop + vertex -902.327 320.768 297.069 + vertex -904.48 327.539 300.904 + vertex -903.251 329.053 297.101 + endloop + endfacet + facet normal -0.950936 -0.104889 -0.291066 + outer loop + vertex -902.327 320.768 297.069 + vertex -903.251 329.053 297.101 + vertex -901.705 322.663 294.352 + endloop + endfacet + facet normal -0.945673 -0.0950811 -0.310907 + outer loop + vertex -901.705 322.663 294.352 + vertex -903.251 329.053 297.101 + vertex -902.528 330.738 294.386 + endloop + endfacet + facet normal -0.938919 -0.0391941 -0.341899 + outer loop + vertex -906.149 325.807 305.685 + vertex -906.506 334.341 305.688 + vertex -904.48 327.539 300.904 + endloop + endfacet + facet normal -0.940127 -0.0421502 -0.338208 + outer loop + vertex -904.48 327.539 300.904 + vertex -906.506 334.341 305.688 + vertex -904.862 335.98 300.915 + endloop + endfacet + facet normal -0.945602 -0.0424191 -0.322549 + outer loop + vertex -904.48 327.539 300.904 + vertex -904.862 335.98 300.915 + vertex -903.251 329.053 297.101 + endloop + endfacet + facet normal -0.945016 -0.0412582 -0.32441 + outer loop + vertex -903.251 329.053 297.101 + vertex -904.862 335.98 300.915 + vertex -903.616 337.425 297.1 + endloop + endfacet + facet normal -0.958694 -0.0418467 -0.281343 + outer loop + vertex -903.251 329.053 297.101 + vertex -903.616 337.425 297.1 + vertex -902.528 330.738 294.386 + endloop + endfacet + facet normal -0.954279 -0.0348222 -0.296882 + outer loop + vertex -902.528 330.738 294.386 + vertex -903.616 337.425 297.1 + vertex -902.782 339.214 294.21 + endloop + endfacet + facet normal -0.946793 0.0129326 -0.321585 + outer loop + vertex -906.506 334.341 305.688 + vertex -906.388 342.966 305.688 + vertex -904.862 335.98 300.915 + endloop + endfacet + facet normal -0.948242 0.00975505 -0.317398 + outer loop + vertex -904.862 335.98 300.915 + vertex -906.388 342.966 305.688 + vertex -904.77 344.491 300.901 + endloop + endfacet + facet normal -0.951186 0.0572853 -0.303253 + outer loop + vertex -906.388 342.966 305.688 + vertex -905.872 351.55 305.689 + vertex -904.77 344.491 300.901 + endloop + endfacet + facet normal -0.951588 0.00980798 -0.30722 + outer loop + vertex -904.862 335.98 300.915 + vertex -904.77 344.491 300.901 + vertex -903.616 337.425 297.1 + endloop + endfacet + facet normal -0.954753 0.0550933 -0.292251 + outer loop + vertex -903.515 345.967 297.096 + vertex -904.28 352.994 300.918 + vertex -903.03 354.429 297.106 + endloop + endfacet + facet normal -0.955474 0.0940002 -0.279701 + outer loop + vertex -903.03 354.429 297.106 + vertex -903.464 361.381 300.926 + vertex -902.225 362.652 297.119 + endloop + endfacet + facet normal -0.954133 0.126739 -0.271234 + outer loop + vertex -902.225 362.652 297.119 + vertex -902.373 369.683 300.928 + vertex -901.149 370.769 297.128 + endloop + endfacet + facet normal -0.951447 0.15522 -0.265812 + outer loop + vertex -901.149 370.769 297.128 + vertex -901.012 378.067 300.899 + vertex -899.812 378.955 297.122 + endloop + endfacet + facet normal -0.948981 0.179605 -0.259185 + outer loop + vertex -899.812 378.955 297.122 + vertex -899.374 386.564 300.79 + vertex -898.234 387.22 297.07 + endloop + endfacet + facet normal -0.945049 0.202052 -0.257015 + outer loop + vertex -898.234 387.22 297.07 + vertex -897.541 395.019 300.653 + vertex -896.468 395.495 297.084 + endloop + endfacet + facet normal -0.941126 0.221613 -0.255284 + outer loop + vertex -896.468 395.495 297.084 + vertex -895.601 403.273 300.639 + vertex -894.579 403.559 297.12 + endloop + endfacet + facet normal -0.936595 0.239509 -0.255785 + outer loop + vertex -894.579 403.559 297.12 + vertex -893.58 411.241 300.655 + vertex -892.576 411.387 297.117 + endloop + endfacet + facet normal -0.932417 0.254061 -0.257004 + outer loop + vertex -892.576 411.387 297.117 + vertex -891.475 419.029 300.674 + vertex -890.469 419.117 297.113 + endloop + endfacet + facet normal -0.928144 0.266256 -0.260109 + outer loop + vertex -890.469 419.117 297.113 + vertex -889.274 426.791 300.705 + vertex -888.293 426.734 297.146 + endloop + endfacet + facet normal -0.923272 0.277223 -0.265926 + outer loop + vertex -888.293 426.734 297.146 + vertex -886.952 434.646 300.735 + vertex -886.003 434.383 297.167 + endloop + endfacet + facet normal -0.918983 0.289359 -0.267847 + outer loop + vertex -885.017 435.072 294.474 + vertex -883.598 442.049 297.145 + vertex -882.735 442.52 294.693 + endloop + endfacet + facet normal -0.926222 0.290756 -0.239945 + outer loop + vertex -885.017 435.072 294.474 + vertex -882.735 442.52 294.693 + vertex -883.598 438.587 293.258 + endloop + endfacet + facet normal -0.917058 0.297403 -0.265626 + outer loop + vertex -883.598 442.049 297.145 + vertex -881.237 449.116 296.904 + vertex -882.735 442.52 294.693 + endloop + endfacet + facet normal -0.917244 0.297277 -0.265122 + outer loop + vertex -882.735 442.52 294.693 + vertex -881.237 449.116 296.904 + vertex -880.584 448.715 294.198 + endloop + endfacet + facet normal -0.922278 0.300817 -0.242718 + outer loop + vertex -882.735 442.52 294.693 + vertex -880.584 448.715 294.198 + vertex -881.92 443.658 293.006 + endloop + endfacet + facet normal -0.91353 0.307914 -0.265805 + outer loop + vertex -881.237 449.116 296.904 + vertex -879.131 454.674 296.104 + vertex -880.584 448.715 294.198 + endloop + endfacet + facet normal -0.921121 0.284333 -0.265878 + outer loop + vertex -886.952 434.646 300.735 + vertex -884.514 442.484 300.673 + vertex -886.003 434.383 297.167 + endloop + endfacet + facet normal -0.91331 0.295657 -0.280093 + outer loop + vertex -883.598 442.049 297.145 + vertex -882.098 449.79 300.424 + vertex -881.237 449.116 296.904 + endloop + endfacet + facet normal -0.910946 0.302232 -0.280774 + outer loop + vertex -882.098 449.79 300.424 + vertex -879.795 456.545 300.224 + vertex -881.237 449.116 296.904 + endloop + endfacet + facet normal -0.920876 0.289039 -0.261619 + outer loop + vertex -885.49 443.305 305.015 + vertex -883.052 450.829 304.748 + vertex -884.514 442.484 300.673 + endloop + endfacet + facet normal -0.924045 0.29214 -0.246566 + outer loop + vertex -883.977 451.917 309.501 + vertex -881.643 459.01 309.158 + vertex -883.052 450.829 304.748 + endloop + endfacet + facet normal -0.909753 0.301695 -0.285184 + outer loop + vertex -882.098 449.79 300.424 + vertex -881.101 456.166 303.99 + vertex -879.795 456.545 300.224 + endloop + endfacet + facet normal -0.910438 0.295022 -0.289939 + outer loop + vertex -879.826 461.594 305.678 + vertex -878.718 463.765 304.406 + vertex -878.594 461.393 301.604 + endloop + endfacet + facet normal -0.90031 0.311791 -0.30369 + outer loop + vertex -878.594 461.393 301.604 + vertex -878.718 463.765 304.406 + vertex -877.691 462.536 300.101 + endloop + endfacet + facet normal -0.895404 0.323559 -0.305879 + outer loop + vertex -877.691 462.536 300.101 + vertex -878.718 463.765 304.406 + vertex -877.99 463.72 302.227 + endloop + endfacet + facet normal -0.889255 0.335036 -0.31141 + outer loop + vertex -877.99 463.72 302.227 + vertex -877.44 463.185 300.082 + vertex -877.691 462.536 300.101 + endloop + endfacet + facet normal -0.891231 0.335993 -0.304658 + outer loop + vertex -877.44 463.185 300.082 + vertex -876.981 462.71 298.213 + vertex -877.691 462.536 300.101 + endloop + endfacet + facet normal -0.881448 0.358131 -0.307883 + outer loop + vertex -876.981 462.71 298.213 + vertex -877.44 463.185 300.082 + vertex -877.163 463.707 299.894 + endloop + endfacet + facet normal -0.88263 0.356125 -0.306821 + outer loop + vertex -877.163 463.707 299.894 + vertex -876.606 463.062 297.546 + vertex -876.981 462.71 298.213 + endloop + endfacet + facet normal -0.87481 0.372703 -0.309517 + outer loop + vertex -876.606 463.062 297.546 + vertex -877.163 463.707 299.894 + vertex -875.896 464.195 296.902 + endloop + endfacet + facet normal -0.874695 0.3719 -0.310804 + outer loop + vertex -876.606 463.062 297.546 + vertex -875.896 464.195 296.902 + vertex -876.316 462.257 295.764 + endloop + endfacet + facet normal -0.882304 0.357888 -0.305706 + outer loop + vertex -876.316 462.257 295.764 + vertex -876.981 462.71 298.213 + vertex -876.606 463.062 297.546 + endloop + endfacet + facet normal -0.890147 0.339117 -0.304364 + outer loop + vertex -876.981 462.71 298.213 + vertex -876.316 462.257 295.764 + vertex -876.988 461.356 296.727 + endloop + endfacet + facet normal -0.889784 0.345693 -0.297961 + outer loop + vertex -876.592 460.862 294.972 + vertex -876.988 461.356 296.727 + vertex -876.316 462.257 295.764 + endloop + endfacet + facet normal -0.881116 0.353285 -0.314365 + outer loop + vertex -876.316 462.257 295.764 + vertex -876.297 460.523 293.762 + vertex -876.592 460.862 294.972 + endloop + endfacet + facet normal -0.894009 0.324119 -0.309346 + outer loop + vertex -877.404 458.556 294.902 + vertex -876.592 460.862 294.972 + vertex -876.297 460.523 293.762 + endloop + endfacet + facet normal -0.895676 0.33451 -0.293032 + outer loop + vertex -876.297 460.523 293.762 + vertex -877.277 457.104 292.855 + vertex -877.404 458.556 294.902 + endloop + endfacet + facet normal -0.881972 0.339549 -0.326851 + outer loop + vertex -877.277 457.104 292.855 + vertex -876.297 460.523 293.762 + vertex -875.339 460.784 291.448 + endloop + endfacet + facet normal -0.875471 0.361152 -0.321123 + outer loop + vertex -876.297 460.523 293.762 + vertex -876.316 462.257 295.764 + vertex -875.309 463.089 293.955 + endloop + endfacet + facet normal -0.87529 0.361122 -0.32165 + outer loop + vertex -876.297 460.523 293.762 + vertex -875.309 463.089 293.955 + vertex -875.339 460.784 291.448 + endloop + endfacet + facet normal -0.898675 0.325298 -0.294218 + outer loop + vertex -877.404 458.556 294.902 + vertex -876.988 461.356 296.727 + vertex -876.592 460.862 294.972 + endloop + endfacet + facet normal -0.87289 0.373414 -0.314046 + outer loop + vertex -875.309 463.089 293.955 + vertex -876.316 462.257 295.764 + vertex -875.896 464.195 296.902 + endloop + endfacet + facet normal -0.871188 0.376642 -0.314918 + outer loop + vertex -874.575 465.405 294.694 + vertex -875.309 463.089 293.955 + vertex -875.896 464.195 296.902 + endloop + endfacet + facet normal -0.876401 0.346322 -0.334638 + outer loop + vertex -874.575 465.405 294.694 + vertex -875.896 464.195 296.902 + vertex -874.387 467.966 296.852 + endloop + endfacet + facet normal -0.864394 0.359599 -0.351442 + outer loop + vertex -873.706 467.09 294.282 + vertex -874.575 465.405 294.694 + vertex -874.387 467.966 296.852 + endloop + endfacet + facet normal -0.895291 0.291869 -0.336552 + outer loop + vertex -872.549 470.102 293.815 + vertex -873.706 467.09 294.282 + vertex -874.387 467.966 296.852 + endloop + endfacet + facet normal -0.896027 0.239021 -0.374172 + outer loop + vertex -874.387 467.966 296.852 + vertex -872.658 475.29 297.39 + vertex -872.549 470.102 293.815 + endloop + endfacet + facet normal -0.938397 0.182504 -0.293433 + outer loop + vertex -871.711 473.702 293.376 + vertex -872.549 470.102 293.815 + vertex -872.658 475.29 297.39 + endloop + endfacet + facet normal -0.941274 0.18447 -0.282796 + outer loop + vertex -872.549 470.102 293.815 + vertex -871.711 473.702 293.376 + vertex -870.743 472.295 289.236 + endloop + endfacet + facet normal -0.928142 0.297784 -0.223334 + outer loop + vertex -872.549 470.102 293.815 + vertex -870.743 472.295 289.236 + vertex -873.436 466.101 292.168 + endloop + endfacet + facet normal -0.913754 0.310506 -0.26199 + outer loop + vertex -873.706 467.09 294.282 + vertex -872.549 470.102 293.815 + vertex -873.436 466.101 292.168 + endloop + endfacet + facet normal -0.925179 0.240011 -0.294005 + outer loop + vertex -874.387 467.966 296.852 + vertex -875.024 470.473 300.903 + vertex -872.658 475.29 297.39 + endloop + endfacet + facet normal -0.921763 0.219774 -0.319455 + outer loop + vertex -872.658 475.29 297.39 + vertex -875.024 470.473 300.903 + vertex -873.627 477.223 301.516 + endloop + endfacet + facet normal -0.927782 0.219418 -0.30179 + outer loop + vertex -875.024 470.473 300.903 + vertex -875.884 472.234 304.827 + vertex -873.627 477.223 301.516 + endloop + endfacet + facet normal -0.924186 0.203617 -0.323142 + outer loop + vertex -873.627 477.223 301.516 + vertex -875.884 472.234 304.827 + vertex -874.472 479.27 305.223 + endloop + endfacet + facet normal -0.934442 0.203922 -0.29195 + outer loop + vertex -875.884 472.234 304.827 + vertex -876.673 474.044 308.616 + vertex -874.472 479.27 305.223 + endloop + endfacet + facet normal -0.930846 0.188854 -0.312825 + outer loop + vertex -874.472 479.27 305.223 + vertex -876.673 474.044 308.616 + vertex -875.245 481.598 308.928 + endloop + endfacet + facet normal -0.884388 0.349863 -0.308955 + outer loop + vertex -875.896 464.195 296.902 + vertex -876.475 465.912 300.504 + vertex -874.387 467.966 296.852 + endloop + endfacet + facet normal -0.889677 0.31225 -0.333129 + outer loop + vertex -875.024 470.473 300.903 + vertex -874.387 467.966 296.852 + vertex -876.475 465.912 300.504 + endloop + endfacet + facet normal -0.896542 0.312734 -0.313702 + outer loop + vertex -876.475 465.912 300.504 + vertex -877.342 467.396 304.46 + vertex -875.024 470.473 300.903 + endloop + endfacet + facet normal -0.896952 0.295277 -0.329072 + outer loop + vertex -875.884 472.234 304.827 + vertex -875.024 470.473 300.903 + vertex -877.342 467.396 304.46 + endloop + endfacet + facet normal -0.904204 0.295866 -0.308024 + outer loop + vertex -877.342 467.396 304.46 + vertex -878.185 468.843 308.326 + vertex -875.884 472.234 304.827 + endloop + endfacet + facet normal -0.903973 0.280897 -0.32238 + outer loop + vertex -876.673 474.044 308.616 + vertex -875.884 472.234 304.827 + vertex -878.185 468.843 308.326 + endloop + endfacet + facet normal -0.887649 0.332851 -0.318261 + outer loop + vertex -877.342 467.396 304.46 + vertex -878.976 466.085 307.647 + vertex -878.185 468.843 308.326 + endloop + endfacet + facet normal -0.900346 0.328431 -0.285499 + outer loop + vertex -878.976 466.085 307.647 + vertex -879.767 467.293 311.532 + vertex -878.185 468.843 308.326 + endloop + endfacet + facet normal -0.900542 0.327357 -0.286115 + outer loop + vertex -878.185 468.843 308.326 + vertex -879.767 467.293 311.532 + vertex -878.845 470.351 312.128 + endloop + endfacet + facet normal -0.919904 0.282703 -0.271763 + outer loop + vertex -878.185 468.843 308.326 + vertex -878.845 470.351 312.128 + vertex -876.673 474.044 308.616 + endloop + endfacet + facet normal -0.919714 0.270004 -0.284998 + outer loop + vertex -877.294 475.934 312.412 + vertex -876.673 474.044 308.616 + vertex -878.845 470.351 312.128 + endloop + endfacet + facet normal -0.949484 0.189784 -0.249926 + outer loop + vertex -876.673 474.044 308.616 + vertex -877.294 475.934 312.412 + vertex -875.245 481.598 308.928 + endloop + endfacet + facet normal -0.946146 0.174626 -0.272604 + outer loop + vertex -875.245 481.598 308.928 + vertex -877.294 475.934 312.412 + vertex -875.88 484.06 312.71 + endloop + endfacet + facet normal -0.885369 0.34429 -0.312387 + outer loop + vertex -878.137 464.817 303.872 + vertex -878.976 466.085 307.647 + vertex -877.342 467.396 304.46 + endloop + endfacet + facet normal -0.881387 0.352654 -0.314312 + outer loop + vertex -878.976 466.085 307.647 + vertex -878.137 464.817 303.872 + vertex -879.101 464.997 306.777 + endloop + endfacet + facet normal -0.8775 0.362791 -0.31365 + outer loop + vertex -878.568 464.312 304.494 + vertex -879.101 464.997 306.777 + vertex -878.137 464.817 303.872 + endloop + endfacet + facet normal -0.877922 0.358368 -0.317531 + outer loop + vertex -877.99 463.72 302.227 + vertex -878.568 464.312 304.494 + vertex -878.137 464.817 303.872 + endloop + endfacet + facet normal -0.881088 0.353294 -0.314433 + outer loop + vertex -878.137 464.817 303.872 + vertex -877.163 463.707 299.894 + vertex -877.99 463.72 302.227 + endloop + endfacet + facet normal -0.877541 0.360916 -0.315691 + outer loop + vertex -877.163 463.707 299.894 + vertex -878.137 464.817 303.872 + vertex -876.475 465.912 300.504 + endloop + endfacet + facet normal -0.906439 0.296677 -0.300583 + outer loop + vertex -879.101 464.997 306.777 + vertex -878.568 464.312 304.494 + vertex -878.718 463.765 304.406 + endloop + endfacet + facet normal -0.881283 0.345359 -0.322595 + outer loop + vertex -876.475 465.912 300.504 + vertex -878.137 464.817 303.872 + vertex -877.342 467.396 304.46 + endloop + endfacet + facet normal -0.878619 0.360539 -0.313115 + outer loop + vertex -875.896 464.195 296.902 + vertex -877.163 463.707 299.894 + vertex -876.475 465.912 300.504 + endloop + endfacet + facet normal -0.880374 0.355283 -0.314191 + outer loop + vertex -877.44 463.185 300.082 + vertex -877.99 463.72 302.227 + vertex -877.163 463.707 299.894 + endloop + endfacet + facet normal -0.903747 0.29715 -0.30813 + outer loop + vertex -878.568 464.312 304.494 + vertex -877.99 463.72 302.227 + vertex -878.718 463.765 304.406 + endloop + endfacet + facet normal -0.899853 0.31758 -0.299012 + outer loop + vertex -878.594 461.393 301.604 + vertex -877.691 462.536 300.101 + vertex -878.036 459.627 298.048 + endloop + endfacet + facet normal -0.900089 0.317309 -0.298587 + outer loop + vertex -878.036 459.627 298.048 + vertex -877.691 462.536 300.101 + vertex -876.988 461.356 296.727 + endloop + endfacet + facet normal -0.890367 0.3388 -0.304074 + outer loop + vertex -876.988 461.356 296.727 + vertex -877.691 462.536 300.101 + vertex -876.981 462.71 298.213 + endloop + endfacet + facet normal -0.909308 0.303611 -0.28457 + outer loop + vertex -881.237 449.116 296.904 + vertex -879.795 456.545 300.224 + vertex -879.131 454.674 296.104 + endloop + endfacet + facet normal -0.90044 0.323397 -0.290898 + outer loop + vertex -878.036 459.627 298.048 + vertex -876.988 461.356 296.727 + vertex -877.404 458.556 294.902 + endloop + endfacet + facet normal -0.912462 0.308576 -0.268689 + outer loop + vertex -880.584 448.715 294.198 + vertex -879.131 454.674 296.104 + vertex -878.663 454.021 293.767 + endloop + endfacet + facet normal -0.912865 0.315886 -0.258637 + outer loop + vertex -878.335 454.041 292.632 + vertex -879.472 450.824 292.716 + vertex -878.663 454.021 293.767 + endloop + endfacet + facet normal -0.917909 0.31251 -0.244499 + outer loop + vertex -880.584 448.715 294.198 + vertex -878.663 454.021 293.767 + vertex -879.472 450.824 292.716 + endloop + endfacet + facet normal -0.908611 0.320245 -0.268084 + outer loop + vertex -877.683 454.466 291.154 + vertex -877.415 452.622 288.043 + vertex -880.181 447.476 291.272 + endloop + endfacet + facet normal -0.90891 0.323604 -0.262988 + outer loop + vertex -880.181 447.476 291.272 + vertex -877.415 452.622 288.043 + vertex -879.908 445.658 288.091 + endloop + endfacet + facet normal -0.910856 0.324354 -0.255217 + outer loop + vertex -877.415 452.622 288.043 + vertex -876.565 451.586 283.692 + vertex -879.908 445.658 288.091 + endloop + endfacet + facet normal -0.910908 0.328506 -0.24966 + outer loop + vertex -879.908 445.658 288.091 + vertex -876.565 451.586 283.692 + vertex -878.953 444.954 283.678 + endloop + endfacet + facet normal -0.921457 0.299578 -0.247328 + outer loop + vertex -879.908 445.658 288.091 + vertex -878.953 444.954 283.678 + vertex -882.204 438.555 288.041 + endloop + endfacet + facet normal -0.920528 0.299304 -0.251087 + outer loop + vertex -882.71 439.742 291.313 + vertex -879.908 445.658 288.091 + vertex -882.204 438.555 288.041 + endloop + endfacet + facet normal -0.921472 0.299855 -0.246932 + outer loop + vertex -882.204 438.555 288.041 + vertex -878.953 444.954 283.678 + vertex -881.167 438.092 283.609 + endloop + endfacet + facet normal -0.926654 0.283838 -0.246471 + outer loop + vertex -882.204 438.555 288.041 + vertex -881.167 438.092 283.609 + vertex -884.393 431.394 288.026 + endloop + endfacet + facet normal -0.925454 0.283481 -0.251342 + outer loop + vertex -884.789 432.73 290.99 + vertex -882.204 438.555 288.041 + vertex -884.393 431.394 288.026 + endloop + endfacet + facet normal -0.926732 0.284807 -0.245057 + outer loop + vertex -884.393 431.394 288.026 + vertex -881.167 438.092 283.609 + vertex -883.326 431.044 283.585 + endloop + endfacet + facet normal -0.929713 0.274974 -0.244998 + outer loop + vertex -884.393 431.394 288.026 + vertex -883.326 431.044 283.585 + vertex -886.553 424.124 288.062 + endloop + endfacet + facet normal -0.927842 0.27438 -0.252636 + outer loop + vertex -887.186 425.111 291.458 + vertex -884.393 431.394 288.026 + vertex -886.553 424.124 288.062 + endloop + endfacet + facet normal -0.929843 0.276401 -0.242887 + outer loop + vertex -886.553 424.124 288.062 + vertex -883.326 431.044 283.585 + vertex -885.449 423.899 283.58 + endloop + endfacet + facet normal -0.932632 0.26666 -0.243086 + outer loop + vertex -886.553 424.124 288.062 + vertex -885.449 423.899 283.58 + vertex -888.596 416.966 288.047 + endloop + endfacet + facet normal -0.930508 0.266072 -0.251716 + outer loop + vertex -889.274 417.667 291.294 + vertex -886.553 424.124 288.062 + vertex -888.596 416.966 288.047 + endloop + endfacet + facet normal -0.932731 0.267669 -0.241589 + outer loop + vertex -888.596 416.966 288.047 + vertex -885.449 423.899 283.58 + vertex -887.495 416.754 283.563 + endloop + endfacet + facet normal -0.936188 0.255077 -0.241842 + outer loop + vertex -888.596 416.966 288.047 + vertex -887.495 416.754 283.563 + vertex -890.527 409.882 288.051 + endloop + endfacet + facet normal -0.93343 0.254318 -0.253043 + outer loop + vertex -891.129 410.903 291.299 + vertex -888.596 416.966 288.047 + vertex -890.527 409.882 288.051 + endloop + endfacet + facet normal -0.934197 0.268074 -0.235396 + outer loop + vertex -885.449 423.899 283.58 + vertex -884.027 423.868 277.9 + vertex -887.495 416.754 283.563 + endloop + endfacet + facet normal -0.934235 0.269663 -0.233423 + outer loop + vertex -887.495 416.754 283.563 + vertex -884.027 423.868 277.9 + vertex -886.07 416.782 277.891 + endloop + endfacet + facet normal -0.935614 0.270052 -0.227372 + outer loop + vertex -884.027 423.868 277.9 + vertex -882.454 423.81 271.36 + vertex -886.07 416.782 277.891 + endloop + endfacet + facet normal -0.932286 0.281889 -0.226675 + outer loop + vertex -884.027 423.868 277.9 + vertex -880.35 430.766 271.358 + vertex -882.454 423.81 271.36 + endloop + endfacet + facet normal -0.933912 0.282383 -0.219246 + outer loop + vertex -880.35 430.766 271.358 + vertex -878.779 430.494 264.314 + vertex -882.454 423.81 271.36 + endloop + endfacet + facet normal -0.933784 0.284145 -0.217508 + outer loop + vertex -882.454 423.81 271.36 + vertex -878.779 430.494 264.314 + vertex -880.856 423.679 264.329 + endloop + endfacet + facet normal -0.935837 0.284793 -0.207608 + outer loop + vertex -878.779 430.494 264.314 + vertex -877.254 430.185 257.014 + vertex -880.856 423.679 264.329 + endloop + endfacet + facet normal -0.931448 0.299054 -0.207295 + outer loop + vertex -878.779 430.494 264.314 + vertex -875.131 436.77 256.974 + vertex -877.254 430.185 257.014 + endloop + endfacet + facet normal -0.933594 0.299813 -0.196249 + outer loop + vertex -875.131 436.77 256.974 + vertex -873.699 436.344 249.511 + vertex -877.254 430.185 257.014 + endloop + endfacet + facet normal -0.933269 0.302183 -0.19415 + outer loop + vertex -877.254 430.185 257.014 + vertex -873.699 436.344 249.511 + vertex -875.796 429.893 249.554 + endloop + endfacet + facet normal -0.935491 0.302986 -0.181811 + outer loop + vertex -873.699 436.344 249.511 + vertex -872.353 435.962 241.949 + vertex -875.796 429.893 249.554 + endloop + endfacet + facet normal -0.927683 0.326233 -0.181595 + outer loop + vertex -873.699 436.344 249.511 + vertex -870.204 442.101 242.003 + vertex -872.353 435.962 241.949 + endloop + endfacet + facet normal -0.929928 0.326904 -0.16843 + outer loop + vertex -870.204 442.101 242.003 + vertex -869.012 441.637 234.518 + vertex -872.353 435.962 241.949 + endloop + endfacet + facet normal -0.92938 0.329648 -0.166089 + outer loop + vertex -872.353 435.962 241.949 + vertex -869.012 441.637 234.518 + vertex -871.099 435.656 234.327 + endloop + endfacet + facet normal -0.937341 0.306081 -0.166451 + outer loop + vertex -872.353 435.962 241.949 + vertex -871.099 435.656 234.327 + vertex -874.421 429.644 241.98 + endloop + endfacet + facet normal -0.931511 0.329974 -0.152983 + outer loop + vertex -869.012 441.637 234.518 + vertex -867.859 441.393 226.97 + vertex -871.099 435.656 234.327 + endloop + endfacet + facet normal -0.930566 0.334374 -0.149135 + outer loop + vertex -871.099 435.656 234.327 + vertex -867.859 441.393 226.97 + vertex -869.955 435.415 226.648 + endloop + endfacet + facet normal -0.939111 0.309327 -0.149623 + outer loop + vertex -871.099 435.656 234.327 + vertex -869.955 435.415 226.648 + vertex -873.148 429.433 234.325 + endloop + endfacet + facet normal -0.932722 0.334371 -0.135006 + outer loop + vertex -867.859 441.393 226.97 + vertex -866.804 441.233 219.285 + vertex -869.955 435.415 226.648 + endloop + endfacet + facet normal -0.931408 0.339957 -0.130029 + outer loop + vertex -869.955 435.415 226.648 + vertex -866.804 441.233 219.285 + vertex -868.957 435.185 218.9 + endloop + endfacet + facet normal -0.940808 0.312836 -0.130435 + outer loop + vertex -869.955 435.415 226.648 + vertex -868.957 435.185 218.9 + vertex -872.002 429.245 226.611 + endloop + endfacet + facet normal -0.933712 0.339697 -0.113079 + outer loop + vertex -866.804 441.233 219.285 + vertex -865.954 440.976 211.497 + vertex -868.957 435.185 218.9 + endloop + endfacet + facet normal -0.93277 0.343323 -0.10986 + outer loop + vertex -868.957 435.185 218.9 + vertex -865.954 440.976 211.497 + vertex -868.116 434.964 211.064 + endloop + endfacet + facet normal -0.942498 0.315549 -0.110121 + outer loop + vertex -868.957 435.185 218.9 + vertex -868.116 434.964 211.064 + vertex -870.996 429.072 218.833 + endloop + endfacet + facet normal -0.934867 0.342808 -0.0922288 + outer loop + vertex -865.954 440.976 211.497 + vertex -865.267 440.727 203.611 + vertex -868.116 434.964 211.064 + endloop + endfacet + facet normal -0.93416 0.345313 -0.0900217 + outer loop + vertex -868.116 434.964 211.064 + vertex -865.267 440.727 203.611 + vertex -867.418 434.787 203.148 + endloop + endfacet + facet normal -0.944136 0.316953 -0.0902684 + outer loop + vertex -868.116 434.964 211.064 + vertex -867.418 434.787 203.148 + vertex -870.135 428.928 210.983 + endloop + endfacet + facet normal -0.935952 0.344594 -0.0724518 + outer loop + vertex -865.267 440.727 203.611 + vertex -864.717 440.546 195.642 + vertex -867.418 434.787 203.148 + endloop + endfacet + facet normal -0.935272 0.346839 -0.0704854 + outer loop + vertex -867.418 434.787 203.148 + vertex -864.717 440.546 195.642 + vertex -866.862 434.667 195.171 + endloop + endfacet + facet normal -0.945454 0.317977 -0.0707588 + outer loop + vertex -867.418 434.787 203.148 + vertex -866.862 434.667 195.171 + vertex -869.418 428.822 203.06 + endloop + endfacet + facet normal -0.93674 0.345979 -0.0530779 + outer loop + vertex -864.717 440.546 195.642 + vertex -864.305 440.433 187.642 + vertex -866.862 434.667 195.171 + endloop + endfacet + facet normal -0.93619 0.347689 -0.0515816 + outer loop + vertex -866.862 434.667 195.171 + vertex -864.305 440.433 187.642 + vertex -866.45 434.59 187.181 + endloop + endfacet + facet normal -0.946366 0.318911 -0.0518306 + outer loop + vertex -866.862 434.667 195.171 + vertex -866.45 434.59 187.181 + vertex -868.852 428.747 195.083 + endloop + endfacet + facet normal -0.937311 0.346766 -0.0346647 + outer loop + vertex -864.305 440.433 187.642 + vertex -864.032 440.376 179.684 + vertex -866.45 434.59 187.181 + endloop + endfacet + facet normal -0.936848 0.348134 -0.0334598 + outer loop + vertex -866.45 434.59 187.181 + vertex -864.032 440.376 179.684 + vertex -866.181 434.55 179.235 + endloop + endfacet + facet normal -0.923053 0.383128 -0.0344395 + outer loop + vertex -864.305 440.433 187.642 + vertex -861.682 446.113 180.523 + vertex -864.032 440.376 179.684 + endloop + endfacet + facet normal -0.924291 0.381256 -0.0181646 + outer loop + vertex -861.682 446.113 180.523 + vertex -861.534 446.097 172.633 + vertex -864.032 440.376 179.684 + endloop + endfacet + facet normal -0.923706 0.382737 -0.016756 + outer loop + vertex -864.032 440.376 179.684 + vertex -861.534 446.097 172.633 + vertex -863.893 440.368 171.819 + endloop + endfacet + facet normal -0.923909 0.38086 -0.0365647 + outer loop + vertex -861.964 446.198 188.514 + vertex -861.682 446.113 180.523 + vertex -864.305 440.433 187.642 + endloop + endfacet + facet normal -0.922361 0.382696 -0.0528535 + outer loop + vertex -864.717 440.546 195.642 + vertex -861.964 446.198 188.514 + vertex -864.305 440.433 187.642 + endloop + endfacet + facet normal -0.923632 0.379142 -0.0561621 + outer loop + vertex -862.383 446.361 196.515 + vertex -861.964 446.198 188.514 + vertex -864.717 440.546 195.642 + endloop + endfacet + facet normal -0.921813 0.380833 -0.0722993 + outer loop + vertex -865.267 440.727 203.611 + vertex -862.383 446.361 196.515 + vertex -864.717 440.546 195.642 + endloop + endfacet + facet normal -0.922982 0.377359 -0.075533 + outer loop + vertex -862.934 446.605 204.471 + vertex -862.383 446.361 196.515 + vertex -865.267 440.727 203.611 + endloop + endfacet + facet normal -0.920824 0.378935 -0.0921471 + outer loop + vertex -865.954 440.976 211.497 + vertex -862.934 446.605 204.471 + vertex -865.267 440.727 203.611 + endloop + endfacet + facet normal -0.922188 0.374582 -0.0962204 + outer loop + vertex -863.626 446.918 212.316 + vertex -862.934 446.605 204.471 + vertex -865.954 440.976 211.497 + endloop + endfacet + facet normal -0.91977 0.375912 -0.112752 + outer loop + vertex -866.804 441.233 219.285 + vertex -863.626 446.918 212.316 + vertex -865.954 440.976 211.497 + endloop + endfacet + facet normal -0.921669 0.369262 -0.119042 + outer loop + vertex -864.548 447.124 220.091 + vertex -863.626 446.918 212.316 + vertex -866.804 441.233 219.285 + endloop + endfacet + facet normal -0.919193 0.370346 -0.133896 + outer loop + vertex -867.859 441.393 226.97 + vertex -864.548 447.124 220.091 + vertex -866.804 441.233 219.285 + endloop + endfacet + facet normal -0.92145 0.361464 -0.142383 + outer loop + vertex -865.883 446.735 227.745 + vertex -864.548 447.124 220.091 + vertex -867.859 441.393 226.97 + endloop + endfacet + facet normal -0.919589 0.362201 -0.152204 + outer loop + vertex -869.012 441.637 234.518 + vertex -865.883 446.735 227.745 + vertex -867.859 441.393 226.97 + endloop + endfacet + facet normal -0.919462 0.362709 -0.151763 + outer loop + vertex -866.809 447.323 234.763 + vertex -865.883 446.735 227.745 + vertex -869.012 441.637 234.518 + endloop + endfacet + facet normal -0.916679 0.362355 -0.168518 + outer loop + vertex -870.204 442.101 242.003 + vertex -866.809 447.323 234.763 + vertex -869.012 441.637 234.518 + endloop + endfacet + facet normal -0.917126 0.360496 -0.170068 + outer loop + vertex -867.917 447.975 242.119 + vertex -866.809 447.323 234.763 + vertex -870.204 442.101 242.003 + endloop + endfacet + facet normal -0.914636 0.359809 -0.184332 + outer loop + vertex -871.522 442.6 249.513 + vertex -867.917 447.975 242.119 + vertex -870.204 442.101 242.003 + endloop + endfacet + facet normal -0.9159 0.35406 -0.189128 + outer loop + vertex -869.287 448.432 249.61 + vertex -867.917 447.975 242.119 + vertex -871.522 442.6 249.513 + endloop + endfacet + facet normal -0.913856 0.353456 -0.199841 + outer loop + vertex -872.937 443.139 256.938 + vertex -869.287 448.432 249.61 + vertex -871.522 442.6 249.513 + endloop + endfacet + facet normal -0.92678 0.318095 -0.199735 + outer loop + vertex -872.937 443.139 256.938 + vertex -871.522 442.6 249.513 + vertex -875.131 436.77 256.974 + endloop + endfacet + facet normal -0.924806 0.317358 -0.209804 + outer loop + vertex -876.633 437.226 264.288 + vertex -872.937 443.139 256.938 + vertex -875.131 436.77 256.974 + endloop + endfacet + facet normal -0.925316 0.313743 -0.212968 + outer loop + vertex -874.421 443.716 264.234 + vertex -872.937 443.139 256.938 + vertex -876.633 437.226 264.288 + endloop + endfacet + facet normal -0.923551 0.313071 -0.22145 + outer loop + vertex -878.191 437.624 271.347 + vertex -874.421 443.716 264.234 + vertex -876.633 437.226 264.288 + endloop + endfacet + facet normal -0.930185 0.292541 -0.221757 + outer loop + vertex -878.191 437.624 271.347 + vertex -876.633 437.226 264.288 + vertex -880.35 430.766 271.358 + endloop + endfacet + facet normal -0.92868 0.292057 -0.228597 + outer loop + vertex -881.909 430.938 277.91 + vertex -878.191 437.624 271.347 + vertex -880.35 430.766 271.358 + endloop + endfacet + facet normal -0.928861 0.28861 -0.232212 + outer loop + vertex -879.751 437.895 277.922 + vertex -878.191 437.624 271.347 + vertex -881.909 430.938 277.91 + endloop + endfacet + facet normal -0.927733 0.288269 -0.237091 + outer loop + vertex -883.326 431.044 283.585 + vertex -879.751 437.895 277.922 + vertex -881.909 430.938 277.91 + endloop + endfacet + facet normal -0.922635 0.308428 -0.231552 + outer loop + vertex -879.751 437.895 277.922 + vertex -875.978 444.235 271.335 + vertex -878.191 437.624 271.347 + endloop + endfacet + facet normal -0.922997 0.303709 -0.2363 + outer loop + vertex -877.55 444.619 277.968 + vertex -875.978 444.235 271.335 + vertex -879.751 437.895 277.922 + endloop + endfacet + facet normal -0.922091 0.303439 -0.240153 + outer loop + vertex -881.167 438.092 283.609 + vertex -877.55 444.619 277.968 + vertex -879.751 437.895 277.922 + endloop + endfacet + facet normal -0.910951 0.338706 -0.235472 + outer loop + vertex -877.55 444.619 277.968 + vertex -873.668 450.458 271.348 + vertex -875.978 444.235 271.335 + endloop + endfacet + facet normal -0.912213 0.339162 -0.22986 + outer loop + vertex -873.668 450.458 271.348 + vertex -872.108 449.793 264.178 + vertex -875.978 444.235 271.335 + endloop + endfacet + facet normal -0.911333 0.344675 -0.225102 + outer loop + vertex -875.978 444.235 271.335 + vertex -872.108 449.793 264.178 + vertex -874.421 443.716 264.234 + endloop + endfacet + facet normal -0.913182 0.345461 -0.216229 + outer loop + vertex -872.108 449.793 264.178 + vertex -870.657 449.074 256.9 + vertex -874.421 443.716 264.234 + endloop + endfacet + facet normal -0.892022 0.396463 -0.217056 + outer loop + vertex -872.108 449.793 264.178 + vertex -868.253 454.46 256.861 + vertex -870.657 449.074 256.9 + endloop + endfacet + facet normal -0.894249 0.39754 -0.205622 + outer loop + vertex -868.253 454.46 256.861 + vertex -867.015 453.579 249.772 + vertex -870.657 449.074 256.9 + endloop + endfacet + facet normal -0.893378 0.400761 -0.203141 + outer loop + vertex -870.657 449.074 256.9 + vertex -867.015 453.579 249.772 + vertex -869.287 448.432 249.61 + endloop + endfacet + facet normal -0.895569 0.401378 -0.191969 + outer loop + vertex -867.015 453.579 249.772 + vertex -865.756 453.022 242.736 + vertex -869.287 448.432 249.61 + endloop + endfacet + facet normal -0.894323 0.405848 -0.188346 + outer loop + vertex -869.287 448.432 249.61 + vertex -865.756 453.022 242.736 + vertex -867.917 447.975 242.119 + endloop + endfacet + facet normal -0.896001 0.40563 -0.180684 + outer loop + vertex -865.756 453.022 242.736 + vertex -863.979 453.262 234.462 + vertex -867.917 447.975 242.119 + endloop + endfacet + facet normal -0.89275 0.416686 -0.171379 + outer loop + vertex -867.917 447.975 242.119 + vertex -863.979 453.262 234.462 + vertex -866.809 447.323 234.763 + endloop + endfacet + facet normal -0.896455 0.419975 -0.141386 + outer loop + vertex -863.979 453.262 234.462 + vertex -863.921 451.313 228.304 + vertex -866.809 447.323 234.763 + endloop + endfacet + facet normal -0.901469 0.40493 -0.152921 + outer loop + vertex -866.809 447.323 234.763 + vertex -863.921 451.313 228.304 + vertex -865.883 446.735 227.745 + endloop + endfacet + facet normal -0.903694 0.404394 -0.140723 + outer loop + vertex -863.921 451.313 228.304 + vertex -863.251 450.827 222.604 + vertex -865.883 446.735 227.745 + endloop + endfacet + facet normal -0.902396 0.408663 -0.136661 + outer loop + vertex -864.548 447.124 220.091 + vertex -865.883 446.735 227.745 + vertex -863.251 450.827 222.604 + endloop + endfacet + facet normal -0.902274 0.408829 -0.136969 + outer loop + vertex -862.35 451.296 218.065 + vertex -864.548 447.124 220.091 + vertex -863.251 450.827 222.604 + endloop + endfacet + facet normal -0.901143 0.416741 -0.119448 + outer loop + vertex -862.35 451.296 218.065 + vertex -862.164 450.641 214.379 + vertex -864.548 447.124 220.091 + endloop + endfacet + facet normal -0.900379 0.418846 -0.117833 + outer loop + vertex -863.626 446.918 212.316 + vertex -864.548 447.124 220.091 + vertex -862.164 450.641 214.379 + endloop + endfacet + facet normal -0.902075 0.416625 -0.112622 + outer loop + vertex -861.506 450.953 210.264 + vertex -863.626 446.918 212.316 + vertex -862.164 450.641 214.379 + endloop + endfacet + facet normal -0.900358 0.424629 -0.0951068 + outer loop + vertex -861.506 450.953 210.264 + vertex -861.444 450.266 206.606 + vertex -863.626 446.918 212.316 + endloop + endfacet + facet normal -0.900985 0.423031 -0.0962839 + outer loop + vertex -862.934 446.605 204.471 + vertex -863.626 446.918 212.316 + vertex -861.444 450.266 206.606 + endloop + endfacet + facet normal -0.902762 0.420477 -0.090664 + outer loop + vertex -860.876 450.577 202.4 + vertex -862.934 446.605 204.471 + vertex -861.444 450.266 206.606 + endloop + endfacet + facet normal -0.90079 0.427782 -0.0746929 + outer loop + vertex -860.876 450.577 202.4 + vertex -860.865 449.95 198.669 + vertex -862.934 446.605 204.471 + endloop + endfacet + facet normal -0.901274 0.426614 -0.0755389 + outer loop + vertex -862.383 446.361 196.515 + vertex -862.934 446.605 204.471 + vertex -860.865 449.95 198.669 + endloop + endfacet + facet normal -0.902827 0.424198 -0.0704195 + outer loop + vertex -860.361 450.317 194.417 + vertex -862.383 446.361 196.515 + vertex -860.865 449.95 198.669 + endloop + endfacet + facet normal -0.900443 0.431586 -0.0541856 + outer loop + vertex -860.361 450.317 194.417 + vertex -860.412 449.741 190.671 + vertex -862.383 446.361 196.515 + endloop + endfacet + facet normal -0.90154 0.429053 -0.0560206 + outer loop + vertex -861.964 446.198 188.514 + vertex -862.383 446.361 196.515 + vertex -860.412 449.741 190.671 + endloop + endfacet + facet normal -0.903368 0.425981 -0.0496611 + outer loop + vertex -859.982 450.154 186.407 + vertex -861.964 446.198 188.514 + vertex -860.412 449.741 190.671 + endloop + endfacet + facet normal -0.900778 0.432934 -0.0341678 + outer loop + vertex -859.982 450.154 186.407 + vertex -860.097 449.618 182.653 + vertex -861.964 446.198 188.514 + endloop + endfacet + facet normal -0.902109 0.429977 -0.0363175 + outer loop + vertex -861.682 446.113 180.523 + vertex -861.964 446.198 188.514 + vertex -860.097 449.618 182.653 + endloop + endfacet + facet normal -0.903723 0.427045 -0.0302929 + outer loop + vertex -859.741 450.07 178.396 + vertex -861.682 446.113 180.523 + vertex -860.097 449.618 182.653 + endloop + endfacet + facet normal -0.900808 0.433966 -0.0147543 + outer loop + vertex -859.741 450.07 178.396 + vertex -859.918 449.577 174.698 + vertex -861.682 446.113 180.523 + endloop + endfacet + facet normal -0.902776 0.42974 -0.0178627 + outer loop + vertex -861.534 446.097 172.633 + vertex -861.682 446.113 180.523 + vertex -859.918 449.577 174.698 + endloop + endfacet + facet normal -0.904255 0.426829 -0.0117985 + outer loop + vertex -859.631 450.069 170.529 + vertex -861.534 446.097 172.633 + vertex -859.918 449.577 174.698 + endloop + endfacet + facet normal -0.901042 0.433713 0.00410134 + outer loop + vertex -859.631 450.069 170.529 + vertex -859.867 449.615 166.923 + vertex -861.534 446.097 172.633 + endloop + endfacet + facet normal -0.90377 0.428018 -0.000204311 + outer loop + vertex -861.508 446.147 164.868 + vertex -861.534 446.097 172.633 + vertex -859.867 449.615 166.923 + endloop + endfacet + facet normal -0.905239 0.424856 0.00630283 + outer loop + vertex -859.642 450.153 162.833 + vertex -861.508 446.147 164.868 + vertex -859.867 449.615 166.923 + endloop + endfacet + facet normal -0.902158 0.430894 0.0210195 + outer loop + vertex -859.642 450.153 162.833 + vertex -859.925 449.737 159.225 + vertex -861.508 446.147 164.868 + endloop + endfacet + facet normal -0.903642 0.427882 0.0186868 + outer loop + vertex -861.604 446.286 157.077 + vertex -861.508 446.147 164.868 + vertex -859.925 449.737 159.225 + endloop + endfacet + facet normal -0.905281 0.424004 0.0261976 + outer loop + vertex -859.759 450.348 155.085 + vertex -861.604 446.286 157.077 + vertex -859.925 449.737 159.225 + endloop + endfacet + facet normal -0.901732 0.430232 0.0421863 + outer loop + vertex -859.759 450.348 155.085 + vertex -860.111 449.978 151.335 + vertex -861.604 446.286 157.077 + endloop + endfacet + facet normal -0.904122 0.425532 0.0385428 + outer loop + vertex -861.842 446.504 149.078 + vertex -861.604 446.286 157.077 + vertex -860.111 449.978 151.335 + endloop + endfacet + facet normal -0.906119 0.42027 0.0481727 + outer loop + vertex -860.049 450.606 147.015 + vertex -861.842 446.504 149.078 + vertex -860.111 449.978 151.335 + endloop + endfacet + facet normal -0.902699 0.425769 0.0620854 + outer loop + vertex -860.049 450.606 147.015 + vertex -860.515 450.179 143.18 + vertex -861.842 446.504 149.078 + endloop + endfacet + facet normal -0.908441 0.414537 0.0537942 + outer loop + vertex -862.153 446.888 140.869 + vertex -861.842 446.504 149.078 + vertex -860.515 450.179 143.18 + endloop + endfacet + facet normal -0.909762 0.410755 0.0601147 + outer loop + vertex -860.57 450.621 139.314 + vertex -862.153 446.888 140.869 + vertex -860.515 450.179 143.18 + endloop + endfacet + facet normal -0.913034 0.405488 0.0441396 + outer loop + vertex -860.57 450.621 139.314 + vertex -860.145 452.154 134.04 + vertex -862.153 446.888 140.869 + endloop + endfacet + facet normal -0.900137 0.430401 0.0671431 + outer loop + vertex -862.153 446.888 140.869 + vertex -860.145 452.154 134.04 + vertex -862.799 446.809 132.708 + endloop + endfacet + facet normal -0.89361 0.39014 -0.221925 + outer loop + vertex -869.66 455.392 264.164 + vertex -868.253 454.46 256.861 + vertex -872.108 449.793 264.178 + endloop + endfacet + facet normal -0.891883 0.389365 -0.230088 + outer loop + vertex -873.668 450.458 271.348 + vertex -869.66 455.392 264.164 + vertex -872.108 449.793 264.178 + endloop + endfacet + facet normal -0.893692 0.381133 -0.236752 + outer loop + vertex -871.214 456.237 271.389 + vertex -869.66 455.392 264.164 + vertex -873.668 450.458 271.348 + endloop + endfacet + facet normal -0.892941 0.380837 -0.240039 + outer loop + vertex -875.23 450.999 278.02 + vertex -871.214 456.237 271.389 + vertex -873.668 450.458 271.348 + endloop + endfacet + facet normal -0.89455 0.371702 -0.24823 + outer loop + vertex -872.727 457.036 278.038 + vertex -871.214 456.237 271.389 + vertex -875.23 450.999 278.02 + endloop + endfacet + facet normal -0.894406 0.371644 -0.248833 + outer loop + vertex -876.565 451.586 283.692 + vertex -872.727 457.036 278.038 + vertex -875.23 450.999 278.02 + endloop + endfacet + facet normal -0.895496 0.362137 -0.258736 + outer loop + vertex -873.977 457.938 283.626 + vertex -872.727 457.036 278.038 + vertex -876.565 451.586 283.692 + endloop + endfacet + facet normal -0.911592 0.333366 -0.240557 + outer loop + vertex -875.23 450.999 278.02 + vertex -873.668 450.458 271.348 + vertex -877.55 444.619 277.968 + endloop + endfacet + facet normal -0.910941 0.333151 -0.243304 + outer loop + vertex -878.953 444.954 283.678 + vertex -875.23 450.999 278.02 + vertex -877.55 444.619 277.968 + endloop + endfacet + facet normal -0.924029 0.308906 -0.225271 + outer loop + vertex -875.978 444.235 271.335 + vertex -874.421 443.716 264.234 + vertex -878.191 437.624 271.347 + endloop + endfacet + facet normal -0.91249 0.349177 -0.21316 + outer loop + vertex -874.421 443.716 264.234 + vertex -870.657 449.074 256.9 + vertex -872.937 443.139 256.938 + endloop + endfacet + facet normal -0.914552 0.350035 -0.202659 + outer loop + vertex -870.657 449.074 256.9 + vertex -869.287 448.432 249.61 + vertex -872.937 443.139 256.938 + endloop + endfacet + facet normal -0.928257 0.323078 -0.184282 + outer loop + vertex -871.522 442.6 249.513 + vertex -870.204 442.101 242.003 + vertex -873.699 436.344 249.511 + endloop + endfacet + facet normal -0.926095 0.322327 -0.196096 + outer loop + vertex -875.131 436.77 256.974 + vertex -871.522 442.6 249.513 + vertex -873.699 436.344 249.511 + endloop + endfacet + facet normal -0.931779 0.296182 -0.209915 + outer loop + vertex -876.633 437.226 264.288 + vertex -875.131 436.77 256.974 + vertex -878.779 430.494 264.314 + endloop + endfacet + facet normal -0.929917 0.295554 -0.218863 + outer loop + vertex -880.35 430.766 271.358 + vertex -876.633 437.226 264.288 + vertex -878.779 430.494 264.314 + endloop + endfacet + facet normal -0.932374 0.279589 -0.229149 + outer loop + vertex -881.909 430.938 277.91 + vertex -880.35 430.766 271.358 + vertex -884.027 423.868 277.9 + endloop + endfacet + facet normal -0.931107 0.279217 -0.234684 + outer loop + vertex -885.449 423.899 283.58 + vertex -881.909 430.938 277.91 + vertex -884.027 423.868 277.9 + endloop + endfacet + facet normal -0.931073 0.276763 -0.237709 + outer loop + vertex -883.326 431.044 283.585 + vertex -881.909 430.938 277.91 + vertex -885.449 423.899 283.58 + endloop + endfacet + facet normal -0.927726 0.285098 -0.240923 + outer loop + vertex -881.167 438.092 283.609 + vertex -879.751 437.895 277.922 + vertex -883.326 431.044 283.585 + endloop + endfacet + facet normal -0.922159 0.300048 -0.24412 + outer loop + vertex -878.953 444.954 283.678 + vertex -877.55 444.619 277.968 + vertex -881.167 438.092 283.609 + endloop + endfacet + facet normal -0.911229 0.328619 -0.248335 + outer loop + vertex -876.565 451.586 283.692 + vertex -875.23 450.999 278.02 + vertex -878.953 444.954 283.678 + endloop + endfacet + facet normal -0.89493 0.361883 -0.261038 + outer loop + vertex -877.415 452.622 288.043 + vertex -873.977 457.938 283.626 + vertex -876.565 451.586 283.692 + endloop + endfacet + facet normal -0.89522 0.353227 -0.271683 + outer loop + vertex -874.81 459.168 287.971 + vertex -873.977 457.938 283.626 + vertex -877.415 452.622 288.043 + endloop + endfacet + facet normal -0.89162 0.351647 -0.285234 + outer loop + vertex -877.683 454.466 291.154 + vertex -874.81 459.168 287.971 + vertex -877.415 452.622 288.043 + endloop + endfacet + facet normal -0.89111 0.344386 -0.295502 + outer loop + vertex -875.339 460.784 291.448 + vertex -874.81 459.168 287.971 + vertex -877.683 454.466 291.154 + endloop + endfacet + facet normal -0.91787 0.311354 -0.246115 + outer loop + vertex -879.472 450.824 292.716 + vertex -880.701 447.337 292.889 + vertex -880.584 448.715 294.198 + endloop + endfacet + facet normal -0.925347 0.299276 -0.232737 + outer loop + vertex -880.701 447.337 292.889 + vertex -881.92 443.658 293.006 + vertex -880.584 448.715 294.198 + endloop + endfacet + facet normal -0.920589 0.299735 -0.250349 + outer loop + vertex -880.181 447.476 291.272 + vertex -879.908 445.658 288.091 + vertex -882.71 439.742 291.313 + endloop + endfacet + facet normal -0.923244 0.293166 -0.248343 + outer loop + vertex -881.92 443.658 293.006 + vertex -883.598 438.587 293.258 + vertex -882.735 442.52 294.693 + endloop + endfacet + facet normal -0.924923 0.286997 -0.249298 + outer loop + vertex -883.598 438.587 293.258 + vertex -884.678 434.6 292.673 + vertex -885.017 435.072 294.474 + endloop + endfacet + facet normal -0.925884 0.285853 -0.247034 + outer loop + vertex -882.71 439.742 291.313 + vertex -882.204 438.555 288.041 + vertex -884.789 432.73 290.99 + endloop + endfacet + facet normal -0.92711 0.280901 -0.248115 + outer loop + vertex -884.678 434.6 292.673 + vertex -886.26 429.553 292.873 + vertex -885.017 435.072 294.474 + endloop + endfacet + facet normal -0.928221 0.276718 -0.248663 + outer loop + vertex -884.789 432.73 290.99 + vertex -884.393 431.394 288.026 + vertex -887.186 425.111 291.458 + endloop + endfacet + facet normal -0.926657 0.277227 -0.253874 + outer loop + vertex -886.26 429.553 292.873 + vertex -887.415 425.781 292.97 + vertex -887.348 427.353 294.439 + endloop + endfacet + facet normal -0.929813 0.271899 -0.248031 + outer loop + vertex -887.415 425.781 292.97 + vertex -888.228 423.18 293.163 + vertex -887.348 427.353 294.439 + endloop + endfacet + facet normal -0.930542 0.265716 -0.251966 + outer loop + vertex -888.228 423.18 293.163 + vertex -889.013 420.028 292.741 + vertex -889.4 420.267 294.421 + endloop + endfacet + facet normal -0.930603 0.266536 -0.25087 + outer loop + vertex -887.186 425.111 291.458 + vertex -886.553 424.124 288.062 + vertex -889.274 417.667 291.294 + endloop + endfacet + facet normal -0.931663 0.262015 -0.251698 + outer loop + vertex -889.013 420.028 292.741 + vertex -890.187 416.215 293.114 + vertex -889.4 420.267 294.421 + endloop + endfacet + facet normal -0.935368 0.256241 -0.243777 + outer loop + vertex -890.187 416.215 293.114 + vertex -890.947 413.049 292.703 + vertex -891.549 412.333 294.26 + endloop + endfacet + facet normal -0.933743 0.255968 -0.25021 + outer loop + vertex -889.274 417.667 291.294 + vertex -888.596 416.966 288.047 + vertex -891.129 410.903 291.299 + endloop + endfacet + facet normal -0.935792 0.253171 -0.245352 + outer loop + vertex -890.947 413.049 292.703 + vertex -891.719 410.399 292.913 + vertex -891.549 412.333 294.26 + endloop + endfacet + facet normal -0.942211 0.243276 -0.230336 + outer loop + vertex -891.719 410.399 292.913 + vertex -892.573 407.136 292.961 + vertex -891.549 412.333 294.26 + endloop + endfacet + facet normal -0.940487 0.238974 -0.241611 + outer loop + vertex -892.573 407.136 292.961 + vertex -893.534 403.386 292.993 + vertex -893.618 404.52 294.443 + endloop + endfacet + facet normal -0.945949 0.226465 -0.232151 + outer loop + vertex -893.534 403.386 292.993 + vertex -894.411 399.695 292.965 + vertex -893.618 404.52 294.443 + endloop + endfacet + facet normal -0.938983 0.219382 -0.264919 + outer loop + vertex -895.325 395.77 292.954 + vertex -894.411 399.695 292.965 + vertex -894.715 396.409 291.323 + endloop + endfacet + facet normal -0.941348 0.22021 -0.255679 + outer loop + vertex -894.715 396.409 291.323 + vertex -892.36 402.66 288.036 + vertex -894.113 395.184 288.05 + endloop + endfacet + facet normal -0.937795 0.241197 -0.24973 + outer loop + vertex -891.129 410.903 291.299 + vertex -890.527 409.882 288.051 + vertex -892.938 403.909 291.336 + endloop + endfacet + facet normal -0.936202 0.255205 -0.241655 + outer loop + vertex -890.527 409.882 288.051 + vertex -887.495 416.754 283.563 + vertex -889.441 409.609 283.555 + endloop + endfacet + facet normal -0.937915 0.255663 -0.234418 + outer loop + vertex -887.495 416.754 283.563 + vertex -886.07 416.782 277.891 + vertex -889.441 409.609 283.555 + endloop + endfacet + facet normal -0.935584 0.27127 -0.226044 + outer loop + vertex -886.07 416.782 277.891 + vertex -882.454 423.81 271.36 + vertex -884.471 416.842 271.347 + endloop + endfacet + facet normal -0.937329 0.271761 -0.218082 + outer loop + vertex -882.454 423.81 271.36 + vertex -880.856 423.679 264.329 + vertex -884.471 416.842 271.347 + endloop + endfacet + facet normal -0.93571 0.2861 -0.206383 + outer loop + vertex -880.856 423.679 264.329 + vertex -877.254 430.185 257.014 + vertex -879.303 423.509 257.048 + endloop + endfacet + facet normal -0.938021 0.286871 -0.194478 + outer loop + vertex -877.254 430.185 257.014 + vertex -875.796 429.893 249.554 + vertex -879.303 423.509 257.048 + endloop + endfacet + facet normal -0.935129 0.305292 -0.179807 + outer loop + vertex -875.796 429.893 249.554 + vertex -872.353 435.962 241.949 + vertex -874.421 429.644 241.98 + endloop + endfacet + facet normal -0.936898 0.308603 -0.164277 + outer loop + vertex -874.421 429.644 241.98 + vertex -871.099 435.656 234.327 + vertex -873.148 429.433 234.325 + endloop + endfacet + facet normal -0.938553 0.312189 -0.14716 + outer loop + vertex -873.148 429.433 234.325 + vertex -869.955 435.415 226.648 + vertex -872.002 429.245 226.611 + endloop + endfacet + facet normal -0.940334 0.315031 -0.128557 + outer loop + vertex -872.002 429.245 226.611 + vertex -868.957 435.185 218.9 + vertex -870.996 429.072 218.833 + endloop + endfacet + facet normal -0.942254 0.316579 -0.109249 + outer loop + vertex -870.996 429.072 218.833 + vertex -868.116 434.964 211.064 + vertex -870.135 428.928 210.983 + endloop + endfacet + facet normal -0.943932 0.317746 -0.0896047 + outer loop + vertex -870.135 428.928 210.983 + vertex -867.418 434.787 203.148 + vertex -869.418 428.822 203.06 + endloop + endfacet + facet normal -0.945228 0.318798 -0.0700773 + outer loop + vertex -869.418 428.822 203.06 + vertex -866.862 434.667 195.171 + vertex -868.852 428.747 195.083 + endloop + endfacet + facet normal -0.946181 0.319547 -0.0513037 + outer loop + vertex -868.852 428.747 195.083 + vertex -866.45 434.59 187.181 + vertex -868.436 428.697 187.099 + endloop + endfacet + facet normal -0.95369 0.298921 -0.0334846 + outer loop + vertex -870.311 422.724 187.195 + vertex -868.166 428.669 179.16 + vertex -870.038 422.707 179.254 + endloop + endfacet + facet normal -0.946966 0.319565 -0.0336589 + outer loop + vertex -866.45 434.59 187.181 + vertex -866.181 434.55 179.235 + vertex -868.436 428.697 187.099 + endloop + endfacet + facet normal -0.947253 0.320086 -0.0159987 + outer loop + vertex -868.166 428.669 179.16 + vertex -866.048 434.548 171.373 + vertex -868.033 428.668 171.293 + endloop + endfacet + facet normal -0.937653 0.347159 -0.0169706 + outer loop + vertex -864.032 440.376 179.684 + vertex -863.893 440.368 171.819 + vertex -866.181 434.55 179.235 + endloop + endfacet + facet normal -0.937549 0.34785 0.00153572 + outer loop + vertex -866.048 434.548 171.373 + vertex -863.881 440.42 164.019 + vertex -866.045 434.589 163.563 + endloop + endfacet + facet normal -0.924647 0.380826 -0.000578721 + outer loop + vertex -861.534 446.097 172.633 + vertex -861.508 446.147 164.868 + vertex -863.893 440.368 171.819 + endloop + endfacet + facet normal -0.937827 0.346569 0.0192695 + outer loop + vertex -863.881 440.42 164.019 + vertex -863.999 440.537 156.173 + vertex -866.045 434.589 163.563 + endloop + endfacet + facet normal -0.947446 0.319913 0.00138308 + outer loop + vertex -866.048 434.548 171.373 + vertex -866.045 434.589 163.563 + vertex -868.033 428.668 171.293 + endloop + endfacet + facet normal -0.954023 0.299299 -0.0161114 + outer loop + vertex -868.166 428.669 179.16 + vertex -868.033 428.668 171.293 + vertex -870.038 422.707 179.254 + endloop + endfacet + facet normal -0.958492 0.28313 -0.0336175 + outer loop + vertex -870.311 422.724 187.195 + vertex -870.038 422.707 179.254 + vertex -872.109 416.65 187.29 + endloop + endfacet + facet normal -0.957835 0.282653 -0.051572 + outer loop + vertex -872.537 416.655 195.278 + vertex -870.311 422.724 187.195 + vertex -872.109 416.65 187.29 + endloop + endfacet + facet normal -0.956834 0.281991 -0.0703538 + outer loop + vertex -873.122 416.662 203.255 + vertex -870.733 422.752 195.181 + vertex -872.537 416.655 195.278 + endloop + endfacet + facet normal -0.95545 0.281095 -0.0900111 + outer loop + vertex -873.866 416.669 211.176 + vertex -871.309 422.791 203.157 + vertex -873.122 416.662 203.255 + endloop + endfacet + facet normal -0.953678 0.279995 -0.110002 + outer loop + vertex -874.769 416.675 219.019 + vertex -872.042 422.842 211.078 + vertex -873.866 416.669 211.176 + endloop + endfacet + facet normal -0.951528 0.279031 -0.129365 + outer loop + vertex -875.823 416.68 226.788 + vertex -872.928 422.909 218.925 + vertex -874.769 416.675 219.019 + endloop + endfacet + facet normal -0.949145 0.278173 -0.147455 + outer loop + vertex -877.018 416.686 234.488 + vertex -873.96 422.993 226.702 + vertex -875.823 416.68 226.788 + endloop + endfacet + facet normal -0.946675 0.27733 -0.163994 + outer loop + vertex -878.335 416.702 242.116 + vertex -875.129 423.093 234.415 + vertex -877.018 416.686 234.488 + endloop + endfacet + facet normal -0.94424 0.276129 -0.179341 + outer loop + vertex -879.755 416.735 249.646 + vertex -876.422 423.204 242.056 + vertex -878.335 416.702 242.116 + endloop + endfacet + facet normal -0.941789 0.274897 -0.193561 + outer loop + vertex -881.263 416.793 257.062 + vertex -877.819 423.343 249.611 + vertex -879.755 416.735 249.646 + endloop + endfacet + facet normal -0.943296 0.259372 -0.207169 + outer loop + vertex -882.845 416.845 264.33 + vertex -881.263 416.793 257.062 + vertex -884.721 410.012 264.319 + endloop + endfacet + facet normal -0.9411 0.258787 -0.217622 + outer loop + vertex -886.376 409.897 271.338 + vertex -882.845 416.845 264.33 + vertex -884.721 410.012 264.319 + endloop + endfacet + facet normal -0.943546 0.240662 -0.227603 + outer loop + vertex -887.999 409.714 277.875 + vertex -886.376 409.897 271.338 + vertex -889.799 402.648 277.866 + endloop + endfacet + facet normal -0.942149 0.240314 -0.233677 + outer loop + vertex -891.269 402.413 283.55 + vertex -887.999 409.714 277.875 + vertex -889.799 402.648 277.866 + endloop + endfacet + facet normal -0.944773 0.221036 -0.241966 + outer loop + vertex -892.36 402.66 288.036 + vertex -891.269 402.413 283.55 + vertex -894.113 395.184 288.05 + endloop + endfacet + facet normal -0.946002 0.205223 -0.250925 + outer loop + vertex -894.715 396.409 291.323 + vertex -894.113 395.184 288.05 + vertex -896.522 388.308 291.51 + endloop + endfacet + facet normal -0.939007 0.20305 -0.277554 + outer loop + vertex -894.715 396.409 291.323 + vertex -896.522 388.308 291.51 + vertex -896.172 391.874 292.935 + endloop + endfacet + facet normal -0.939386 0.202681 -0.276539 + outer loop + vertex -896.937 388.333 292.937 + vertex -896.172 391.874 292.935 + vertex -896.522 388.308 291.51 + endloop + endfacet + facet normal -0.941836 0.190256 -0.277035 + outer loop + vertex -897.281 386.623 292.934 + vertex -896.937 388.333 292.937 + vertex -896.522 388.308 291.51 + endloop + endfacet + facet normal -0.953306 0.192497 -0.232708 + outer loop + vertex -896.937 388.333 292.937 + vertex -897.281 386.623 292.934 + vertex -897.252 388.324 294.219 + endloop + endfacet + facet normal -0.950831 0.205169 -0.232004 + outer loop + vertex -896.172 391.874 292.935 + vertex -896.937 388.333 292.937 + vertex -897.252 388.324 294.219 + endloop + endfacet + facet normal -0.951347 0.206539 -0.228649 + outer loop + vertex -897.252 388.324 294.219 + vertex -895.483 396.686 294.412 + vertex -896.172 391.874 292.935 + endloop + endfacet + facet normal -0.948743 0.201233 -0.243706 + outer loop + vertex -895.731 387.579 288.06 + vertex -892.969 395.14 283.55 + vertex -894.523 387.815 283.551 + endloop + endfacet + facet normal -0.950449 0.201597 -0.236653 + outer loop + vertex -892.969 395.14 283.55 + vertex -891.467 395.553 277.873 + vertex -894.523 387.815 283.551 + endloop + endfacet + facet normal -0.947781 0.223553 -0.227454 + outer loop + vertex -891.467 395.553 277.873 + vertex -888.151 402.955 271.33 + vertex -889.796 395.983 271.332 + endloop + endfacet + facet normal -0.949459 0.223951 -0.21994 + outer loop + vertex -888.151 402.955 271.33 + vertex -886.474 403.166 264.305 + vertex -889.796 395.983 271.332 + endloop + endfacet + facet normal -0.947451 0.243407 -0.207583 + outer loop + vertex -886.474 403.166 264.305 + vertex -883.115 410.058 257.056 + vertex -884.848 403.3 257.039 + endloop + endfacet + facet normal -0.949952 0.244466 -0.194491 + outer loop + vertex -884.848 403.3 257.039 + vertex -881.586 410.096 249.648 + vertex -883.298 403.429 249.63 + endloop + endfacet + facet normal -0.952471 0.245707 -0.180076 + outer loop + vertex -883.298 403.429 249.63 + vertex -880.143 410.157 242.124 + vertex -881.836 403.581 242.106 + endloop + endfacet + facet normal -0.954916 0.247018 -0.164673 + outer loop + vertex -881.836 403.581 242.106 + vertex -878.804 410.234 234.506 + vertex -880.481 403.741 234.487 + endloop + endfacet + facet normal -0.957318 0.248288 -0.147971 + outer loop + vertex -880.481 403.741 234.487 + vertex -877.591 410.308 226.811 + vertex -879.254 403.884 226.79 + endloop + endfacet + facet normal -0.959645 0.249529 -0.129677 + outer loop + vertex -879.254 403.884 226.79 + vertex -876.521 410.368 219.044 + vertex -878.173 404.006 219.023 + endloop + endfacet + facet normal -0.961788 0.250647 -0.110182 + outer loop + vertex -878.173 404.006 219.023 + vertex -875.606 410.415 211.202 + vertex -877.248 404.106 211.179 + endloop + endfacet + facet normal -0.963643 0.251495 -0.0902332 + outer loop + vertex -877.248 404.106 211.179 + vertex -874.852 410.451 203.281 + vertex -876.485 404.187 203.258 + endloop + endfacet + facet normal -0.965093 0.25225 -0.0704607 + outer loop + vertex -876.485 404.187 203.258 + vertex -874.26 410.479 195.303 + vertex -875.886 404.25 195.279 + endloop + endfacet + facet normal -0.966145 0.252784 -0.0516064 + outer loop + vertex -875.886 404.25 195.279 + vertex -873.826 410.499 187.314 + vertex -875.448 404.296 187.291 + endloop + endfacet + facet normal -0.971348 0.235286 -0.0335336 + outer loop + vertex -876.958 398.047 187.267 + vertex -875.164 404.324 179.344 + vertex -876.674 398.09 179.322 + endloop + endfacet + facet normal -0.966899 0.252916 -0.0337745 + outer loop + vertex -873.826 410.499 187.314 + vertex -873.545 410.512 179.367 + vertex -875.448 404.296 187.291 + endloop + endfacet + facet normal -0.967189 0.25355 -0.0160226 + outer loop + vertex -875.164 404.324 179.344 + vertex -873.41 410.518 171.49 + vertex -875.031 404.335 171.466 + endloop + endfacet + facet normal -0.962996 0.269013 -0.0164235 + outer loop + vertex -871.83 416.649 179.347 + vertex -871.695 416.651 171.475 + vertex -873.545 410.512 179.367 + endloop + endfacet + facet normal -0.96294 0.269715 0.000924681 + outer loop + vertex -873.41 410.518 171.49 + vertex -871.698 416.661 163.656 + vertex -873.418 410.518 163.663 + endloop + endfacet + facet normal -0.958913 0.283701 0.00064507 + outer loop + vertex -869.903 422.707 171.389 + vertex -869.903 422.728 163.579 + vertex -871.695 416.651 171.475 + endloop + endfacet + facet normal -0.958735 0.283778 0.0172526 + outer loop + vertex -871.698 416.661 163.656 + vertex -870.031 422.77 155.777 + vertex -871.833 416.678 155.842 + endloop + endfacet + facet normal -0.954058 0.299074 0.0180818 + outer loop + vertex -868.033 428.699 163.486 + vertex -868.16 428.765 155.678 + vertex -869.903 422.728 163.579 + endloop + endfacet + facet normal -0.954271 0.297078 0.0333285 + outer loop + vertex -870.031 422.77 155.777 + vertex -868.41 428.868 147.839 + vertex -870.284 422.836 147.945 + endloop + endfacet + facet normal -0.94738 0.318065 0.03615 + outer loop + vertex -866.172 434.68 155.73 + vertex -866.429 434.81 147.836 + vertex -868.16 428.765 155.678 + endloop + endfacet + facet normal -0.948465 0.31295 0.0497704 + outer loop + vertex -868.41 428.868 147.839 + vertex -866.81 434.976 139.917 + vertex -868.775 429.011 139.98 + endloop + endfacet + facet normal -0.937787 0.342982 0.0540249 + outer loop + vertex -864.247 440.721 148.198 + vertex -864.651 440.885 140.151 + vertex -866.429 434.81 147.836 + endloop + endfacet + facet normal -0.93934 0.336296 0.0674128 + outer loop + vertex -866.81 434.976 139.917 + vertex -865.19 441.063 132.119 + vertex -867.295 435.203 132.026 + endloop + endfacet + facet normal -0.923969 0.376089 0.0695567 + outer loop + vertex -862.153 446.888 140.869 + vertex -862.799 446.809 132.708 + vertex -864.651 440.885 140.151 + endloop + endfacet + facet normal -0.924741 0.370698 0.0862391 + outer loop + vertex -865.19 441.063 132.119 + vertex -863.508 447.037 124.48 + vertex -865.808 441.37 124.174 + endloop + endfacet + facet normal -0.900734 0.424624 0.0915016 + outer loop + vertex -860.145 452.154 134.04 + vertex -860.831 452.589 125.259 + vertex -862.799 446.809 132.708 + endloop + endfacet + facet normal -0.923332 0.369053 0.106106 + outer loop + vertex -863.508 447.037 124.48 + vertex -864.273 447.43 116.454 + vertex -865.808 441.37 124.174 + endloop + endfacet + facet normal -0.938095 0.335553 0.0859204 + outer loop + vertex -865.19 441.063 132.119 + vertex -865.808 441.37 124.174 + vertex -867.295 435.203 132.026 + endloop + endfacet + facet normal -0.947438 0.312795 0.0672361 + outer loop + vertex -866.81 434.976 139.917 + vertex -867.295 435.203 132.026 + vertex -868.775 429.011 139.98 + endloop + endfacet + facet normal -0.95354 0.297136 0.0497177 + outer loop + vertex -868.41 428.868 147.839 + vertex -868.775 429.011 139.98 + vertex -870.284 422.836 147.945 + endloop + endfacet + facet normal -0.958297 0.28382 0.0333464 + outer loop + vertex -870.031 422.77 155.777 + vertex -870.284 422.836 147.945 + vertex -871.833 416.678 155.842 + endloop + endfacet + facet normal -0.962791 0.269692 0.0172926 + outer loop + vertex -871.698 416.661 163.656 + vertex -871.833 416.678 155.842 + vertex -873.418 410.518 163.663 + endloop + endfacet + facet normal -0.967329 0.253521 0.000928828 + outer loop + vertex -873.41 410.518 171.49 + vertex -873.418 410.518 163.663 + vertex -875.031 404.335 171.466 + endloop + endfacet + facet normal -0.971782 0.235329 -0.0161249 + outer loop + vertex -875.164 404.324 179.344 + vertex -875.031 404.335 171.466 + vertex -876.674 398.09 179.322 + endloop + endfacet + facet normal -0.975904 0.215564 -0.033804 + outer loop + vertex -876.958 398.047 187.267 + vertex -876.674 398.09 179.322 + vertex -878.352 391.735 187.259 + endloop + endfacet + facet normal -0.975145 0.215419 -0.0518312 + outer loop + vertex -878.798 391.64 195.246 + vertex -876.958 398.047 187.267 + vertex -878.352 391.735 187.259 + endloop + endfacet + facet normal -0.974065 0.214868 -0.0709116 + outer loop + vertex -879.407 391.509 203.223 + vertex -877.401 397.976 195.255 + vertex -878.798 391.64 195.246 + endloop + endfacet + facet normal -0.972582 0.214125 -0.0907498 + outer loop + vertex -880.184 391.339 211.145 + vertex -878.006 397.878 203.232 + vertex -879.407 391.509 203.223 + endloop + endfacet + facet normal -0.970688 0.213241 -0.110875 + outer loop + vertex -881.126 391.13 218.989 + vertex -878.776 397.752 211.153 + vertex -880.184 391.339 211.145 + endloop + endfacet + facet normal -0.968481 0.212196 -0.130448 + outer loop + vertex -882.227 390.882 226.758 + vertex -879.71 397.599 218.998 + vertex -881.126 391.13 218.989 + endloop + endfacet + facet normal -0.966091 0.210965 -0.148869 + outer loop + vertex -883.475 390.598 234.457 + vertex -880.802 397.415 226.767 + vertex -882.227 390.882 226.758 + endloop + endfacet + facet normal -0.963634 0.209655 -0.165691 + outer loop + vertex -884.855 390.28 242.08 + vertex -882.04 397.199 234.465 + vertex -883.475 390.598 234.457 + endloop + endfacet + facet normal -0.961116 0.208216 -0.181387 + outer loop + vertex -886.347 389.953 249.609 + vertex -883.409 396.962 242.087 + vertex -884.855 390.28 242.08 + endloop + endfacet + facet normal -0.958503 0.206945 -0.196077 + outer loop + vertex -887.932 389.637 257.023 + vertex -884.886 396.721 249.614 + vertex -886.347 389.953 249.609 + endloop + endfacet + facet normal -0.955856 0.205723 -0.209802 + outer loop + vertex -889.595 389.329 264.301 + vertex -886.455 396.501 257.027 + vertex -887.932 389.637 257.023 + endloop + endfacet + facet normal -0.953586 0.205081 -0.22049 + outer loop + vertex -891.305 388.94 271.331 + vertex -888.1 396.28 264.298 + vertex -889.595 389.329 264.301 + endloop + endfacet + facet normal -0.955633 0.181661 -0.231872 + outer loop + vertex -892.997 388.408 277.89 + vertex -891.305 388.94 271.331 + vertex -894.369 381.186 277.887 + endloop + endfacet + facet normal -0.954368 0.181422 -0.237207 + outer loop + vertex -895.919 380.462 283.568 + vertex -892.997 388.408 277.89 + vertex -894.369 381.186 277.887 + endloop + endfacet + facet normal -0.955809 0.156661 -0.248769 + outer loop + vertex -897.155 380.011 288.033 + vertex -895.919 380.462 283.568 + vertex -898.398 372.451 288.05 + endloop + endfacet + facet normal -0.954984 0.132421 -0.265462 + outer loop + vertex -899.258 372.745 291.289 + vertex -898.398 372.451 288.05 + vertex -900.323 365.06 291.286 + endloop + endfacet + facet normal -0.958678 0.128525 -0.253807 + outer loop + vertex -899.407 364.896 288.041 + vertex -897.131 373.054 283.577 + vertex -898.143 365.534 283.59 + endloop + endfacet + facet normal -0.961014 0.128856 -0.244638 + outer loop + vertex -897.131 373.054 283.577 + vertex -895.577 373.858 277.895 + vertex -898.143 365.534 283.59 + endloop + endfacet + facet normal -0.959448 0.158735 -0.232943 + outer loop + vertex -895.577 373.858 277.895 + vertex -892.669 381.807 271.335 + vertex -893.87 374.555 271.336 + endloop + endfacet + facet normal -0.961338 0.159494 -0.224478 + outer loop + vertex -893.87 374.555 271.336 + vertex -890.945 382.277 264.297 + vertex -892.132 375.12 264.297 + endloop + endfacet + facet normal -0.96383 0.1604 -0.212847 + outer loop + vertex -892.132 375.12 264.297 + vertex -889.267 382.688 257.024 + vertex -890.441 375.634 257.027 + endloop + endfacet + facet normal -0.966613 0.161641 -0.198827 + outer loop + vertex -890.441 375.634 257.027 + vertex -887.667 383.099 249.61 + vertex -888.832 376.142 249.615 + endloop + endfacet + facet normal -0.969389 0.162893 -0.183712 + outer loop + vertex -888.832 376.142 249.615 + vertex -886.165 383.516 242.083 + vertex -887.321 376.64 242.087 + endloop + endfacet + facet normal -0.972033 0.16454 -0.167568 + outer loop + vertex -887.321 376.64 242.087 + vertex -884.776 383.909 234.459 + vertex -885.927 377.113 234.463 + endloop + endfacet + facet normal -0.974585 0.166035 -0.15039 + outer loop + vertex -885.927 377.113 234.463 + vertex -883.52 384.265 226.76 + vertex -884.666 377.538 226.764 + endloop + endfacet + facet normal -0.97704 0.167456 -0.131721 + outer loop + vertex -884.666 377.538 226.764 + vertex -882.413 384.574 218.99 + vertex -883.555 377.911 218.995 + endloop + endfacet + facet normal -0.979289 0.168736 -0.111897 + outer loop + vertex -883.555 377.911 218.995 + vertex -881.465 384.839 211.147 + vertex -882.605 378.225 211.15 + endloop + endfacet + facet normal -0.981209 0.169852 -0.0915427 + outer loop + vertex -882.605 378.225 211.15 + vertex -880.684 385.05 203.225 + vertex -881.821 378.483 203.229 + endloop + endfacet + facet normal -0.982721 0.170731 -0.0714934 + outer loop + vertex -881.821 378.483 203.229 + vertex -880.07 385.217 195.248 + vertex -881.206 378.682 195.252 + endloop + endfacet + facet normal -0.983807 0.171483 -0.0521294 + outer loop + vertex -881.206 378.682 195.252 + vertex -879.623 385.334 187.262 + vertex -880.758 378.824 187.265 + endloop + endfacet + facet normal -0.988645 0.146462 -0.0336162 + outer loop + vertex -881.737 372.19 187.267 + vertex -880.472 378.906 179.321 + vertex -881.453 372.288 179.322 + endloop + endfacet + facet normal -0.984576 0.171626 -0.0339842 + outer loop + vertex -879.623 385.334 187.262 + vertex -879.337 385.405 179.318 + vertex -880.758 378.824 187.265 + endloop + endfacet + facet normal -0.984912 0.172348 -0.015655 + outer loop + vertex -880.472 378.906 179.321 + vertex -879.205 385.431 171.443 + vertex -880.342 378.934 171.446 + endloop + endfacet + facet normal -0.980663 0.195051 -0.0159999 + outer loop + vertex -878.067 391.791 179.316 + vertex -877.934 391.813 171.441 + vertex -879.337 385.405 179.318 + endloop + endfacet + facet normal -0.980689 0.195569 0.00168595 + outer loop + vertex -879.205 385.431 171.443 + vertex -877.949 391.797 163.618 + vertex -879.223 385.408 163.621 + endloop + endfacet + facet normal -0.97636 0.216147 0.00137703 + outer loop + vertex -876.541 398.105 171.446 + vertex -876.554 398.095 163.621 + vertex -877.934 391.813 171.441 + endloop + endfacet + facet normal -0.976144 0.216339 0.0184302 + outer loop + vertex -877.949 391.797 163.618 + vertex -876.709 398.058 155.8 + vertex -878.108 391.745 155.799 + endloop + endfacet + facet normal -0.971672 0.235642 0.0180565 + outer loop + vertex -875.042 404.329 163.638 + vertex -875.193 404.307 155.814 + vertex -876.554 398.095 163.621 + endloop + endfacet + facet normal -0.971218 0.235695 0.0343898 + outer loop + vertex -876.709 398.058 155.8 + vertex -875.479 404.269 147.956 + vertex -877.002 397.996 147.946 + endloop + endfacet + facet normal -0.966653 0.253833 0.0339161 + outer loop + vertex -873.562 410.513 155.84 + vertex -873.841 410.503 147.98 + vertex -875.193 404.307 155.814 + endloop + endfacet + facet normal -0.965955 0.253889 0.0497198 + outer loop + vertex -875.479 404.269 147.956 + vertex -874.25 410.488 140.084 + vertex -875.899 404.217 140.065 + endloop + endfacet + facet normal -0.961588 0.270082 0.0490298 + outer loop + vertex -872.099 416.702 147.993 + vertex -872.492 416.733 140.106 + vertex -873.841 410.503 147.98 + endloop + endfacet + facet normal -0.960588 0.270361 0.0646175 + outer loop + vertex -874.25 410.488 140.084 + vertex -873.011 416.771 132.209 + vertex -874.786 410.472 132.185 + endloop + endfacet + facet normal -0.95679 0.283641 0.0640408 + outer loop + vertex -870.658 422.925 140.08 + vertex -871.153 423.034 132.209 + vertex -872.492 416.733 140.106 + endloop + endfacet + facet normal -0.955571 0.283871 0.0793871 + outer loop + vertex -873.011 416.771 132.209 + vertex -871.767 423.158 124.355 + vertex -873.651 416.819 124.338 + endloop + endfacet + facet normal -0.952163 0.295125 0.0792899 + outer loop + vertex -869.249 429.195 132.133 + vertex -869.833 429.412 124.319 + vertex -871.153 423.034 132.209 + endloop + endfacet + facet normal -0.95106 0.294457 0.093703 + outer loop + vertex -871.767 423.158 124.355 + vertex -870.528 429.644 116.54 + vertex -872.495 423.293 116.54 + endloop + endfacet + facet normal -0.946894 0.307161 0.0950953 + outer loop + vertex -867.869 435.497 124.213 + vertex -868.536 435.839 116.471 + vertex -869.833 429.412 124.319 + endloop + endfacet + facet normal -0.946439 0.304545 0.107262 + outer loop + vertex -870.528 429.644 116.54 + vertex -869.3 436.189 108.794 + vertex -871.33 429.877 108.81 + endloop + endfacet + facet normal -0.939047 0.325226 0.111437 + outer loop + vertex -866.488 441.785 116.375 + vertex -867.232 442.261 108.713 + vertex -868.536 435.839 116.471 + endloop + endfacet + facet normal -0.94028 0.318511 0.1201 + outer loop + vertex -869.3 436.189 108.794 + vertex -868.053 442.746 101.168 + vertex -870.156 436.53 101.195 + endloop + endfacet + facet normal -0.926462 0.35325 0.129935 + outer loop + vertex -865.049 448.006 108.665 + vertex -865.863 448.655 101.094 + vertex -867.232 442.261 108.713 + endloop + endfacet + facet normal -0.931249 0.338814 0.134093 + outer loop + vertex -868.053 442.746 101.168 + vertex -866.734 449.336 93.6827 + vertex -868.944 443.242 93.731 + endloop + endfacet + facet normal -0.910972 0.382815 0.153569 + outer loop + vertex -863.532 454.202 101.093 + vertex -864.412 455.111 93.6078 + vertex -865.863 448.655 101.094 + endloop + endfacet + facet normal -0.915229 0.372815 0.152855 + outer loop + vertex -863.532 454.202 101.093 + vertex -862.153 460.644 93.6406 + vertex -864.412 455.111 93.6078 + endloop + endfacet + facet normal -0.906061 0.388369 0.167996 + outer loop + vertex -861.243 459.473 101.257 + vertex -862.153 460.644 93.6406 + vertex -863.532 454.202 101.093 + endloop + endfacet + facet normal -0.909567 0.390715 0.141529 + outer loop + vertex -862.683 453.375 108.835 + vertex -861.243 459.473 101.257 + vertex -863.532 454.202 101.093 + endloop + endfacet + facet normal -0.900839 0.405508 0.155091 + outer loop + vertex -860.348 458.431 109.182 + vertex -861.243 459.473 101.257 + vertex -862.683 453.375 108.835 + endloop + endfacet + facet normal -0.903596 0.408593 0.128708 + outer loop + vertex -861.818 452.741 116.918 + vertex -860.348 458.431 109.182 + vertex -862.683 453.375 108.835 + endloop + endfacet + facet normal -0.892336 0.427525 0.144773 + outer loop + vertex -859.37 457.581 117.715 + vertex -860.348 458.431 109.182 + vertex -861.818 452.741 116.918 + endloop + endfacet + facet normal -0.893967 0.433474 0.113679 + outer loop + vertex -860.831 452.589 125.259 + vertex -859.37 457.581 117.715 + vertex -861.818 452.741 116.918 + endloop + endfacet + facet normal -0.862916 0.482007 0.15181 + outer loop + vertex -859.231 456.014 123.479 + vertex -859.37 457.581 117.715 + vertex -860.831 452.589 125.259 + endloop + endfacet + facet normal -0.876327 0.468217 0.113238 + outer loop + vertex -859.231 456.014 123.479 + vertex -860.831 452.589 125.259 + vertex -858.942 455.55 127.634 + endloop + endfacet + facet normal -0.871314 0.482017 0.0920459 + outer loop + vertex -860.831 452.589 125.259 + vertex -860.145 452.154 134.04 + vertex -858.942 455.55 127.634 + endloop + endfacet + facet normal -0.857354 0.503664 0.106144 + outer loop + vertex -858.268 455.863 131.594 + vertex -858.942 455.55 127.634 + vertex -860.145 452.154 134.04 + endloop + endfacet + facet normal -0.865565 0.493601 0.084582 + outer loop + vertex -858.268 455.863 131.594 + vertex -860.145 452.154 134.04 + vertex -858.163 455.357 135.627 + endloop + endfacet + facet normal -0.861665 0.50409 0.0585421 + outer loop + vertex -859.359 452.887 139.297 + vertex -858.163 455.357 135.627 + vertex -860.145 452.154 134.04 + endloop + endfacet + facet normal -0.8797 0.470947 0.0658581 + outer loop + vertex -860.57 450.621 139.314 + vertex -859.359 452.887 139.297 + vertex -860.145 452.154 134.04 + endloop + endfacet + facet normal -0.879656 0.470929 0.0665636 + outer loop + vertex -860.515 450.179 143.18 + vertex -859.359 452.887 139.297 + vertex -860.57 450.621 139.314 + endloop + endfacet + facet normal -0.879115 0.471827 0.0673509 + outer loop + vertex -858.985 452.972 143.573 + vertex -859.359 452.887 139.297 + vertex -860.515 450.179 143.18 + endloop + endfacet + facet normal -0.879046 0.473684 0.0538719 + outer loop + vertex -860.049 450.606 147.015 + vertex -858.985 452.972 143.573 + vertex -860.515 450.179 143.18 + endloop + endfacet + facet normal -0.873868 0.482274 0.061374 + outer loop + vertex -858.749 452.873 147.708 + vertex -858.985 452.972 143.573 + vertex -860.049 450.606 147.015 + endloop + endfacet + facet normal -0.873595 0.48321 0.057795 + outer loop + vertex -860.111 449.978 151.335 + vertex -858.749 452.873 147.708 + vertex -860.049 450.606 147.015 + endloop + endfacet + facet normal -0.876624 0.478279 0.0527215 + outer loop + vertex -858.595 452.709 151.754 + vertex -858.749 452.873 147.708 + vertex -860.111 449.978 151.335 + endloop + endfacet + facet normal -0.876157 0.480769 0.0347893 + outer loop + vertex -859.759 450.348 155.085 + vertex -858.595 452.709 151.754 + vertex -860.111 449.978 151.335 + endloop + endfacet + facet normal -0.87149 0.488613 0.0419792 + outer loop + vertex -858.496 452.547 155.707 + vertex -858.595 452.709 151.754 + vertex -859.759 450.348 155.085 + endloop + endfacet + facet normal -0.871087 0.489712 0.0372748 + outer loop + vertex -859.925 449.737 159.225 + vertex -858.496 452.547 155.707 + vertex -859.759 450.348 155.085 + endloop + endfacet + facet normal -0.875236 0.482762 0.030038 + outer loop + vertex -858.429 452.426 159.593 + vertex -858.496 452.547 155.707 + vertex -859.925 449.737 159.225 + endloop + endfacet + facet normal -0.874554 0.484762 0.0126482 + outer loop + vertex -859.642 450.153 162.833 + vertex -858.429 452.426 159.593 + vertex -859.925 449.737 159.225 + endloop + endfacet + facet normal -0.869908 0.492807 0.0200309 + outer loop + vertex -858.387 452.345 163.437 + vertex -858.429 452.426 159.593 + vertex -859.642 450.153 162.833 + endloop + endfacet + facet normal -0.869628 0.493405 0.0172752 + outer loop + vertex -859.867 449.615 166.923 + vertex -858.387 452.345 163.437 + vertex -859.642 450.153 162.833 + endloop + endfacet + facet normal -0.873249 0.487154 0.0108427 + outer loop + vertex -858.37 452.29 167.269 + vertex -858.387 452.345 163.437 + vertex -859.867 449.615 166.923 + endloop + endfacet + facet normal -0.872436 0.488706 -0.0046947 + outer loop + vertex -859.631 450.069 170.529 + vertex -858.37 452.29 167.269 + vertex -859.867 449.615 166.923 + endloop + endfacet + facet normal -0.868829 0.495111 0.0010654 + outer loop + vertex -858.382 452.26 171.134 + vertex -858.37 452.29 167.269 + vertex -859.631 450.069 170.529 + endloop + endfacet + facet normal -0.868557 0.495587 -0.00121986 + outer loop + vertex -859.918 449.577 174.698 + vertex -858.382 452.26 171.134 + vertex -859.631 450.069 170.529 + endloop + endfacet + facet normal -0.872705 0.488173 -0.00859017 + outer loop + vertex -858.425 452.253 175.055 + vertex -858.382 452.26 171.134 + vertex -859.918 449.577 174.698 + endloop + endfacet + facet normal -0.871641 0.489577 -0.0235728 + outer loop + vertex -859.741 450.07 178.396 + vertex -858.425 452.253 175.055 + vertex -859.918 449.577 174.698 + endloop + endfacet + facet normal -0.867766 0.496668 -0.0174129 + outer loop + vertex -858.5 452.261 179.026 + vertex -858.425 452.253 175.055 + vertex -859.741 450.07 178.396 + endloop + endfacet + facet normal -0.867429 0.497167 -0.0198104 + outer loop + vertex -860.097 449.618 182.653 + vertex -858.5 452.261 179.026 + vertex -859.741 450.07 178.396 + endloop + endfacet + facet normal -0.871884 0.488923 -0.0277809 + outer loop + vertex -858.607 452.298 183.032 + vertex -858.5 452.261 179.026 + vertex -860.097 449.618 182.653 + endloop + endfacet + facet normal -0.870461 0.490329 -0.0432982 + outer loop + vertex -859.982 450.154 186.407 + vertex -858.607 452.298 183.032 + vertex -860.097 449.618 182.653 + endloop + endfacet + facet normal -0.867037 0.496809 -0.037787 + outer loop + vertex -858.749 452.355 187.042 + vertex -858.607 452.298 183.032 + vertex -859.982 450.154 186.407 + endloop + endfacet + facet normal -0.866831 0.497068 -0.0390825 + outer loop + vertex -860.412 449.741 190.671 + vertex -858.749 452.355 187.042 + vertex -859.982 450.154 186.407 + endloop + endfacet + facet normal -0.871933 0.487215 -0.0485203 + outer loop + vertex -858.925 452.438 191.047 + vertex -858.749 452.355 187.042 + vertex -860.412 449.741 190.671 + endloop + endfacet + facet normal -0.870323 0.488393 -0.0633302 + outer loop + vertex -860.361 450.317 194.417 + vertex -858.925 452.438 191.047 + vertex -860.412 449.741 190.671 + endloop + endfacet + facet normal -0.867775 0.493434 -0.0590709 + outer loop + vertex -859.137 452.545 195.048 + vertex -858.925 452.438 191.047 + vertex -860.361 450.317 194.417 + endloop + endfacet + facet normal -0.867568 0.493655 -0.0602529 + outer loop + vertex -860.865 449.95 198.669 + vertex -859.137 452.545 195.048 + vertex -860.361 450.317 194.417 + endloop + endfacet + facet normal -0.872309 0.483999 -0.0694344 + outer loop + vertex -859.384 452.673 199.045 + vertex -859.137 452.545 195.048 + vertex -860.865 449.95 198.669 + endloop + endfacet + facet normal -0.870438 0.485021 -0.0842157 + outer loop + vertex -860.876 450.577 202.4 + vertex -859.384 452.673 199.045 + vertex -860.865 449.95 198.669 + endloop + endfacet + facet normal -0.868261 0.489546 -0.0804212 + outer loop + vertex -859.661 452.837 203.03 + vertex -859.384 452.673 199.045 + vertex -860.876 450.577 202.4 + endloop + endfacet + facet normal -0.868171 0.489629 -0.0808895 + outer loop + vertex -861.444 450.266 206.606 + vertex -859.661 452.837 203.03 + vertex -860.876 450.577 202.4 + endloop + endfacet + facet normal -0.87276 0.479726 -0.0902954 + outer loop + vertex -859.962 453.031 206.973 + vertex -859.661 452.837 203.03 + vertex -861.444 450.266 206.606 + endloop + endfacet + facet normal -0.870644 0.480555 -0.105101 + outer loop + vertex -861.506 450.953 210.264 + vertex -859.962 453.031 206.973 + vertex -861.444 450.266 206.606 + endloop + endfacet + facet normal -0.868703 0.484824 -0.101495 + outer loop + vertex -860.297 453.244 210.857 + vertex -859.962 453.031 206.973 + vertex -861.506 450.953 210.264 + endloop + endfacet + facet normal -0.868582 0.484915 -0.102093 + outer loop + vertex -862.164 450.641 214.379 + vertex -860.297 453.244 210.857 + vertex -861.506 450.953 210.264 + endloop + endfacet + facet normal -0.873858 0.472635 -0.113967 + outer loop + vertex -860.688 453.454 214.733 + vertex -860.297 453.244 210.857 + vertex -862.164 450.641 214.379 + endloop + endfacet + facet normal -0.871601 0.473214 -0.127984 + outer loop + vertex -862.35 451.296 218.065 + vertex -860.688 453.454 214.733 + vertex -862.164 450.641 214.379 + endloop + endfacet + facet normal -0.871084 0.474449 -0.126927 + outer loop + vertex -861.168 453.653 218.765 + vertex -860.688 453.454 214.733 + vertex -862.35 451.296 218.065 + endloop + endfacet + facet normal -0.871743 0.473965 -0.124182 + outer loop + vertex -863.251 450.827 222.604 + vertex -861.168 453.653 218.765 + vertex -862.35 451.296 218.065 + endloop + endfacet + facet normal -0.876827 0.461035 -0.136457 + outer loop + vertex -861.699 453.951 223.187 + vertex -861.168 453.653 218.765 + vertex -863.251 450.827 222.604 + endloop + endfacet + facet normal -0.875638 0.461533 -0.142287 + outer loop + vertex -863.921 451.313 228.304 + vertex -861.699 453.951 223.187 + vertex -863.251 450.827 222.604 + endloop + endfacet + facet normal -0.873923 0.465638 -0.139426 + outer loop + vertex -861.892 454.877 227.488 + vertex -861.699 453.951 223.187 + vertex -863.921 451.313 228.304 + endloop + endfacet + facet normal -0.873386 0.461894 -0.154438 + outer loop + vertex -863.921 451.313 228.304 + vertex -863.979 453.262 234.462 + vertex -861.892 454.877 227.488 + endloop + endfacet + facet normal -0.849754 0.509229 -0.136398 + outer loop + vertex -861.183 456.659 229.723 + vertex -861.892 454.877 227.488 + vertex -863.979 453.262 234.462 + endloop + endfacet + facet normal -0.859243 0.486448 -0.158333 + outer loop + vertex -861.638 456.983 233.188 + vertex -861.183 456.659 229.723 + vertex -863.979 453.262 234.462 + endloop + endfacet + facet normal -0.859188 0.479498 -0.178544 + outer loop + vertex -861.638 456.983 233.188 + vertex -863.979 453.262 234.462 + vertex -862.766 456.605 237.599 + endloop + endfacet + facet normal -0.863324 0.474552 -0.171673 + outer loop + vertex -863.979 453.262 234.462 + vertex -865.756 453.022 242.736 + vertex -862.766 456.605 237.599 + endloop + endfacet + facet normal -0.868693 0.459345 -0.185403 + outer loop + vertex -863.804 457.012 243.47 + vertex -862.766 456.605 237.599 + vertex -865.756 453.022 242.736 + endloop + endfacet + facet normal -0.867169 0.459722 -0.191505 + outer loop + vertex -867.015 453.579 249.772 + vertex -863.804 457.012 243.47 + vertex -865.756 453.022 242.736 + endloop + endfacet + facet normal -0.874502 0.438802 -0.206637 + outer loop + vertex -864.725 458.203 249.9 + vertex -863.804 457.012 243.47 + vertex -867.015 453.579 249.772 + endloop + endfacet + facet normal -0.874374 0.438757 -0.207274 + outer loop + vertex -868.253 454.46 256.861 + vertex -864.725 458.203 249.9 + vertex -867.015 453.579 249.772 + endloop + endfacet + facet normal -0.880864 0.418324 -0.221547 + outer loop + vertex -865.839 459.587 256.943 + vertex -864.725 458.203 249.9 + vertex -868.253 454.46 256.861 + endloop + endfacet + facet normal -0.880557 0.418202 -0.222992 + outer loop + vertex -869.66 455.392 264.164 + vertex -865.839 459.587 256.943 + vertex -868.253 454.46 256.861 + endloop + endfacet + facet normal -0.884168 0.405246 -0.232429 + outer loop + vertex -867.259 460.72 264.321 + vertex -865.839 459.587 256.943 + vertex -869.66 455.392 264.164 + endloop + endfacet + facet normal -0.883054 0.404886 -0.237241 + outer loop + vertex -871.214 456.237 271.389 + vertex -867.259 460.72 264.321 + vertex -869.66 455.392 264.164 + endloop + endfacet + facet normal -0.886189 0.391815 -0.247287 + outer loop + vertex -868.772 461.829 271.498 + vertex -867.259 460.72 264.321 + vertex -871.214 456.237 271.389 + endloop + endfacet + facet normal -0.885858 0.391697 -0.248654 + outer loop + vertex -872.727 457.036 278.038 + vertex -868.772 461.829 271.498 + vertex -871.214 456.237 271.389 + endloop + endfacet + facet normal -0.888442 0.378142 -0.260151 + outer loop + vertex -870.207 462.949 278.027 + vertex -868.772 461.829 271.498 + vertex -872.727 457.036 278.038 + endloop + endfacet + facet normal -0.888537 0.378183 -0.25977 + outer loop + vertex -873.977 457.938 283.626 + vertex -870.207 462.949 278.027 + vertex -872.727 457.036 278.038 + endloop + endfacet + facet normal -0.890235 0.364525 -0.273136 + outer loop + vertex -871.431 464.156 283.626 + vertex -870.207 462.949 278.027 + vertex -873.977 457.938 283.626 + endloop + endfacet + facet normal -0.890042 0.364447 -0.273867 + outer loop + vertex -874.81 459.168 287.971 + vertex -871.431 464.156 283.626 + vertex -873.977 457.938 283.626 + endloop + endfacet + facet normal -0.890444 0.351787 -0.288713 + outer loop + vertex -872.427 465.403 288.218 + vertex -871.431 464.156 283.626 + vertex -874.81 459.168 287.971 + endloop + endfacet + facet normal -0.887629 0.351082 -0.298086 + outer loop + vertex -875.339 460.784 291.448 + vertex -872.427 465.403 288.218 + vertex -874.81 459.168 287.971 + endloop + endfacet + facet normal -0.88797 0.356983 -0.289953 + outer loop + vertex -873.436 466.101 292.168 + vertex -872.427 465.403 288.218 + vertex -875.339 460.784 291.448 + endloop + endfacet + facet normal -0.837453 0.524752 -0.152669 + outer loop + vertex -860.305 456.988 226.039 + vertex -861.892 454.877 227.488 + vertex -861.183 456.659 229.723 + endloop + endfacet + facet normal -0.836597 0.52754 -0.147671 + outer loop + vertex -860.305 456.988 226.039 + vertex -860.169 456.361 223.03 + vertex -861.892 454.877 227.488 + endloop + endfacet + facet normal -0.839082 0.522862 -0.150188 + outer loop + vertex -861.892 454.877 227.488 + vertex -860.169 456.361 223.03 + vertex -861.699 453.951 223.187 + endloop + endfacet + facet normal -0.839852 0.523876 -0.142138 + outer loop + vertex -860.169 456.361 223.03 + vertex -859.785 455.905 219.081 + vertex -861.699 453.951 223.187 + endloop + endfacet + facet normal -0.835673 0.532046 -0.136303 + outer loop + vertex -861.699 453.951 223.187 + vertex -859.785 455.905 219.081 + vertex -861.168 453.653 218.765 + endloop + endfacet + facet normal -0.836522 0.531903 -0.131566 + outer loop + vertex -859.785 455.905 219.081 + vertex -859.333 455.62 215.053 + vertex -861.168 453.653 218.765 + endloop + endfacet + facet normal -0.832544 0.539545 -0.125549 + outer loop + vertex -861.168 453.653 218.765 + vertex -859.333 455.62 215.053 + vertex -860.688 453.454 214.733 + endloop + endfacet + facet normal -0.833809 0.53925 -0.1182 + outer loop + vertex -859.333 455.62 215.053 + vertex -858.928 455.389 211.139 + vertex -860.688 453.454 214.733 + endloop + endfacet + facet normal -0.83067 0.545067 -0.113529 + outer loop + vertex -860.688 453.454 214.733 + vertex -858.928 455.389 211.139 + vertex -860.297 453.244 210.857 + endloop + endfacet + facet normal -0.831933 0.544791 -0.105311 + outer loop + vertex -858.928 455.389 211.139 + vertex -858.585 455.161 207.252 + vertex -860.297 453.244 210.857 + endloop + endfacet + facet normal -0.829366 0.549381 -0.101652 + outer loop + vertex -860.297 453.244 210.857 + vertex -858.585 455.161 207.252 + vertex -859.962 453.031 206.973 + endloop + endfacet + facet normal -0.830704 0.549014 -0.0922718 + outer loop + vertex -858.585 455.161 207.252 + vertex -858.289 454.949 203.321 + vertex -859.962 453.031 206.973 + endloop + endfacet + facet normal -0.829409 0.551262 -0.0904981 + outer loop + vertex -859.962 453.031 206.973 + vertex -858.289 454.949 203.321 + vertex -859.661 452.837 203.03 + endloop + endfacet + facet normal -0.830301 0.550947 -0.0840109 + outer loop + vertex -858.289 454.949 203.321 + vertex -858.005 454.771 199.348 + vertex -859.661 452.837 203.03 + endloop + endfacet + facet normal -0.827549 0.555618 -0.0803207 + outer loop + vertex -859.661 452.837 203.03 + vertex -858.005 454.771 199.348 + vertex -859.384 452.673 199.045 + endloop + endfacet + facet normal -0.828699 0.555104 -0.071531 + outer loop + vertex -858.005 454.771 199.348 + vertex -857.756 454.628 195.354 + vertex -859.384 452.673 199.045 + endloop + endfacet + facet normal -0.826779 0.558279 -0.069002 + outer loop + vertex -859.384 452.673 199.045 + vertex -857.756 454.628 195.354 + vertex -859.137 452.545 195.048 + endloop + endfacet + facet normal -0.827775 0.557748 -0.0608834 + outer loop + vertex -857.756 454.628 195.354 + vertex -857.543 454.507 191.351 + vertex -859.137 452.545 195.048 + endloop + endfacet + facet normal -0.826037 0.560556 -0.0586435 + outer loop + vertex -859.137 452.545 195.048 + vertex -857.543 454.507 191.351 + vertex -858.925 452.438 191.047 + endloop + endfacet + facet normal -0.827074 0.559907 -0.0495195 + outer loop + vertex -857.543 454.507 191.351 + vertex -857.364 454.418 187.351 + vertex -858.925 452.438 191.047 + endloop + endfacet + facet normal -0.82591 0.561751 -0.0480409 + outer loop + vertex -858.925 452.438 191.047 + vertex -857.364 454.418 187.351 + vertex -858.749 452.355 187.042 + endloop + endfacet + facet normal -0.826886 0.561027 -0.0388202 + outer loop + vertex -857.364 454.418 187.351 + vertex -857.222 454.35 183.343 + vertex -858.749 452.355 187.042 + endloop + endfacet + facet normal -0.825646 0.562956 -0.0372681 + outer loop + vertex -858.749 452.355 187.042 + vertex -857.222 454.35 183.343 + vertex -858.607 452.298 183.032 + endloop + endfacet + facet normal -0.826532 0.562182 -0.0282146 + outer loop + vertex -857.222 454.35 183.343 + vertex -857.114 454.308 179.339 + vertex -858.607 452.298 183.032 + endloop + endfacet + facet normal -0.82574 0.563393 -0.0272356 + outer loop + vertex -858.607 452.298 183.032 + vertex -857.114 454.308 179.339 + vertex -858.5 452.261 179.026 + endloop + endfacet + facet normal -0.826656 0.562451 -0.0170065 + outer loop + vertex -857.114 454.308 179.339 + vertex -857.041 454.294 175.361 + vertex -858.5 452.261 179.026 + endloop + endfacet + facet normal -0.826454 0.562755 -0.016757 + outer loop + vertex -858.5 452.261 179.026 + vertex -857.041 454.294 175.361 + vertex -858.425 452.253 175.055 + endloop + endfacet + facet normal -0.827142 0.561933 -0.00818029 + outer loop + vertex -857.041 454.294 175.361 + vertex -856.993 454.307 171.437 + vertex -858.425 452.253 175.055 + endloop + endfacet + facet normal -0.826974 0.562183 -0.00797183 + outer loop + vertex -858.425 452.253 175.055 + vertex -856.993 454.307 171.437 + vertex -858.382 452.26 171.134 + endloop + endfacet + facet normal -0.827763 0.561069 0.00318206 + outer loop + vertex -856.993 454.307 171.437 + vertex -856.983 454.344 167.567 + vertex -858.382 452.26 171.134 + endloop + endfacet + facet normal -0.828948 0.559324 0.00169748 + outer loop + vertex -858.382 452.26 171.134 + vertex -856.983 454.344 167.567 + vertex -858.37 452.29 167.269 + endloop + endfacet + facet normal -0.82967 0.558089 0.0135675 + outer loop + vertex -856.983 454.344 167.567 + vertex -857.004 454.407 163.727 + vertex -858.37 452.29 167.269 + endloop + endfacet + facet normal -0.8312 0.555851 0.0116403 + outer loop + vertex -858.37 452.29 167.269 + vertex -857.004 454.407 163.727 + vertex -858.387 452.345 163.437 + endloop + endfacet + facet normal -0.8317 0.554812 0.0214131 + outer loop + vertex -857.004 454.407 163.727 + vertex -857.041 454.5 159.88 + vertex -858.387 452.345 163.437 + endloop + endfacet + facet normal -0.832105 0.554224 0.0209044 + outer loop + vertex -858.387 452.345 163.437 + vertex -857.041 454.5 159.88 + vertex -858.429 452.426 159.593 + endloop + endfacet + facet normal -0.832661 0.552698 0.0346492 + outer loop + vertex -857.041 454.5 159.88 + vertex -857.115 454.632 155.983 + vertex -858.429 452.426 159.593 + endloop + endfacet + facet normal -0.835266 0.548948 0.0314101 + outer loop + vertex -858.429 452.426 159.593 + vertex -857.115 454.632 155.983 + vertex -858.496 452.547 155.707 + endloop + endfacet + facet normal -0.835639 0.547491 0.0442932 + outer loop + vertex -857.115 454.632 155.983 + vertex -857.21 454.807 152.031 + vertex -858.496 452.547 155.707 + endloop + endfacet + facet normal -0.836301 0.546543 0.0434786 + outer loop + vertex -858.496 452.547 155.707 + vertex -857.21 454.807 152.031 + vertex -858.595 452.709 151.754 + endloop + endfacet + facet normal -0.836556 0.544822 0.0578244 + outer loop + vertex -857.21 454.807 152.031 + vertex -857.351 455.015 148.033 + vertex -858.595 452.709 151.754 + endloop + endfacet + facet normal -0.839852 0.54014 0.0538213 + outer loop + vertex -858.595 452.709 151.754 + vertex -857.351 455.015 148.033 + vertex -858.749 452.873 147.708 + endloop + endfacet + facet normal -0.840051 0.538695 0.064213 + outer loop + vertex -857.351 455.015 148.033 + vertex -857.54 455.202 143.994 + vertex -858.749 452.873 147.708 + endloop + endfacet + facet normal -0.842801 0.534773 0.0608579 + outer loop + vertex -858.749 452.873 147.708 + vertex -857.54 455.202 143.994 + vertex -858.985 452.972 143.573 + endloop + endfacet + facet normal -0.843088 0.533122 0.0705919 + outer loop + vertex -857.54 455.202 143.994 + vertex -857.807 455.322 139.895 + vertex -858.985 452.972 143.573 + endloop + endfacet + facet normal -0.848694 0.525043 0.0636324 + outer loop + vertex -858.985 452.972 143.573 + vertex -857.807 455.322 139.895 + vertex -859.359 452.887 139.297 + endloop + endfacet + facet normal -0.849265 0.522607 0.0750427 + outer loop + vertex -857.807 455.322 139.895 + vertex -858.163 455.357 135.627 + vertex -859.359 452.887 139.297 + endloop + endfacet + facet normal -0.921349 0.357554 0.152548 + outer loop + vertex -866.734 449.336 93.6827 + vertex -865.335 456.097 86.2788 + vertex -867.653 450.087 86.3711 + endloop + endfacet + facet normal -0.91105 0.370949 0.179957 + outer loop + vertex -862.153 460.644 93.6406 + vertex -863.099 461.911 86.2401 + vertex -864.412 455.111 93.6078 + endloop + endfacet + facet normal -0.924813 0.338293 0.174006 + outer loop + vertex -865.335 456.097 86.2788 + vertex -864.078 463.284 78.99 + vertex -866.293 457.204 79.0372 + endloop + endfacet + facet normal -0.945738 0.263079 0.190705 + outer loop + vertex -861.449 467.774 86.3325 + vertex -862.437 469.408 79.1796 + vertex -863.099 461.911 86.2401 + endloop + endfacet + facet normal -0.949836 0.26461 0.166712 + outer loop + vertex -862.153 460.644 93.6406 + vertex -861.449 467.774 86.3325 + vertex -863.099 461.911 86.2401 + endloop + endfacet + facet normal -0.942581 0.27985 0.18228 + outer loop + vertex -860.487 466.223 93.6877 + vertex -861.449 467.774 86.3325 + vertex -862.153 460.644 93.6406 + endloop + endfacet + facet normal -0.946783 0.281323 0.156397 + outer loop + vertex -861.243 459.473 101.257 + vertex -860.487 466.223 93.6877 + vertex -862.153 460.644 93.6406 + endloop + endfacet + facet normal -0.938761 0.298349 0.172382 + outer loop + vertex -859.567 464.769 101.22 + vertex -860.487 466.223 93.6877 + vertex -861.243 459.473 101.257 + endloop + endfacet + facet normal -0.942885 0.299468 0.145898 + outer loop + vertex -860.348 458.431 109.182 + vertex -859.567 464.769 101.22 + vertex -861.243 459.473 101.257 + endloop + endfacet + facet normal -0.934791 0.316853 0.160531 + outer loop + vertex -858.694 463.412 108.978 + vertex -859.567 464.769 101.22 + vertex -860.348 458.431 109.182 + endloop + endfacet + facet normal -0.93815 0.317089 0.13903 + outer loop + vertex -859.37 457.581 117.715 + vertex -858.694 463.412 108.978 + vertex -860.348 458.431 109.182 + endloop + endfacet + facet normal -0.934042 0.326211 0.145435 + outer loop + vertex -857.9 462.192 116.816 + vertex -858.694 463.412 108.978 + vertex -859.37 457.581 117.715 + endloop + endfacet + facet normal -0.92916 0.329122 0.168345 + outer loop + vertex -857.9 462.192 116.816 + vertex -859.37 457.581 117.715 + vertex -858.132 458.353 123.039 + endloop + endfacet + facet normal -0.88536 0.44279 0.141686 + outer loop + vertex -859.231 456.014 123.479 + vertex -858.132 458.353 123.039 + vertex -859.37 457.581 117.715 + endloop + endfacet + facet normal -0.891206 0.439783 0.111099 + outer loop + vertex -858.942 455.55 127.634 + vertex -858.132 458.353 123.039 + vertex -859.231 456.014 123.479 + endloop + endfacet + facet normal -0.876715 0.463615 0.128187 + outer loop + vertex -857.514 458.167 127.938 + vertex -858.132 458.353 123.039 + vertex -858.942 455.55 127.634 + endloop + endfacet + facet normal -0.877632 0.465926 0.112583 + outer loop + vertex -858.268 455.863 131.594 + vertex -857.514 458.167 127.938 + vertex -858.942 455.55 127.634 + endloop + endfacet + facet normal -0.879286 0.463281 0.110576 + outer loop + vertex -857.122 457.908 132.141 + vertex -857.514 458.167 127.938 + vertex -858.268 455.863 131.594 + endloop + endfacet + facet normal -0.878573 0.470513 0.0820182 + outer loop + vertex -858.163 455.357 135.627 + vertex -857.122 457.908 132.141 + vertex -858.268 455.863 131.594 + endloop + endfacet + facet normal -0.869625 0.484502 0.0949282 + outer loop + vertex -856.844 457.613 136.192 + vertex -857.122 457.908 132.141 + vertex -858.163 455.357 135.627 + endloop + endfacet + facet normal -0.869045 0.488796 0.0764223 + outer loop + vertex -857.807 455.322 139.895 + vertex -856.844 457.613 136.192 + vertex -858.163 455.357 135.627 + endloop + endfacet + facet normal -0.861857 0.499945 0.0851872 + outer loop + vertex -856.582 457.383 140.195 + vertex -856.844 457.613 136.192 + vertex -857.807 455.322 139.895 + endloop + endfacet + facet normal -0.861921 0.50206 0.0709091 + outer loop + vertex -857.54 455.202 143.994 + vertex -856.582 457.383 140.195 + vertex -857.807 455.322 139.895 + endloop + endfacet + facet normal -0.855806 0.51141 0.0778191 + outer loop + vertex -856.364 457.145 144.158 + vertex -856.582 457.383 140.195 + vertex -857.54 455.202 143.994 + endloop + endfacet + facet normal -0.856138 0.512798 0.0637671 + outer loop + vertex -857.351 455.015 148.033 + vertex -856.364 457.145 144.158 + vertex -857.54 455.202 143.994 + endloop + endfacet + facet normal -0.853565 0.516715 0.0665758 + outer loop + vertex -856.203 456.899 148.124 + vertex -856.364 457.145 144.158 + vertex -857.351 455.015 148.033 + endloop + endfacet + facet normal -0.853865 0.517364 0.0570066 + outer loop + vertex -857.21 454.807 152.031 + vertex -856.203 456.899 148.124 + vertex -857.351 455.015 148.033 + endloop + endfacet + facet normal -0.851865 0.52041 0.0591528 + outer loop + vertex -856.068 456.669 152.104 + vertex -856.203 456.899 148.124 + vertex -857.21 454.807 152.031 + endloop + endfacet + facet normal -0.852277 0.521276 0.0435267 + outer loop + vertex -857.115 454.632 155.983 + vertex -856.068 456.669 152.104 + vertex -857.21 454.807 152.031 + endloop + endfacet + facet normal -0.848437 0.527148 0.0476471 + outer loop + vertex -855.962 456.481 156.066 + vertex -856.068 456.669 152.104 + vertex -857.115 454.632 155.983 + endloop + endfacet + facet normal -0.848633 0.527881 0.0341114 + outer loop + vertex -857.041 454.5 159.88 + vertex -855.962 456.481 156.066 + vertex -857.115 454.632 155.983 + endloop + endfacet + facet normal -0.846609 0.530977 0.0362927 + outer loop + vertex -855.885 456.336 159.975 + vertex -855.962 456.481 156.066 + vertex -857.041 454.5 159.88 + endloop + endfacet + facet normal -0.846621 0.531782 0.0210011 + outer loop + vertex -857.004 454.407 163.727 + vertex -855.885 456.336 159.975 + vertex -857.041 454.5 159.88 + endloop + endfacet + facet normal -0.842778 0.537672 0.0251766 + outer loop + vertex -855.837 456.23 163.837 + vertex -855.885 456.336 159.975 + vertex -857.004 454.407 163.727 + endloop + endfacet + facet normal -0.842646 0.538303 0.0133156 + outer loop + vertex -856.983 454.344 167.567 + vertex -855.837 456.23 163.837 + vertex -857.004 454.407 163.727 + endloop + endfacet + facet normal -0.841685 0.539778 0.0143566 + outer loop + vertex -855.82 456.156 167.679 + vertex -855.837 456.23 163.837 + vertex -856.983 454.344 167.567 + endloop + endfacet + facet normal -0.841447 0.540332 0.00294922 + outer loop + vertex -856.993 454.307 171.437 + vertex -855.82 456.156 167.679 + vertex -856.983 454.344 167.567 + endloop + endfacet + facet normal -0.840925 0.54114 0.00350999 + outer loop + vertex -855.833 456.11 171.538 + vertex -855.82 456.156 167.679 + vertex -856.993 454.307 171.437 + endloop + endfacet + facet normal -0.840595 0.541599 -0.00841119 + outer loop + vertex -857.041 454.294 175.361 + vertex -855.833 456.11 171.538 + vertex -856.993 454.307 171.437 + endloop + endfacet + facet normal -0.839278 0.543657 -0.00701828 + outer loop + vertex -855.876 456.094 175.468 + vertex -855.833 456.11 171.538 + vertex -857.041 454.294 175.361 + endloop + endfacet + facet normal -0.838901 0.544013 -0.0171668 + outer loop + vertex -857.114 454.308 179.339 + vertex -855.876 456.094 175.468 + vertex -857.041 454.294 175.361 + endloop + endfacet + facet normal -0.839295 0.543391 -0.0175799 + outer loop + vertex -855.951 456.107 179.459 + vertex -855.876 456.094 175.468 + vertex -857.114 454.308 179.339 + endloop + endfacet + facet normal -0.838759 0.543764 -0.028353 + outer loop + vertex -857.222 454.35 183.343 + vertex -855.951 456.107 179.459 + vertex -857.114 454.308 179.339 + endloop + endfacet + facet normal -0.838991 0.543394 -0.0285965 + outer loop + vertex -856.059 456.151 183.462 + vertex -855.951 456.107 179.459 + vertex -857.222 454.35 183.343 + endloop + endfacet + facet normal -0.838386 0.543684 -0.0389342 + outer loop + vertex -857.364 454.418 187.351 + vertex -856.059 456.151 183.462 + vertex -857.222 454.35 183.343 + endloop + endfacet + facet normal -0.839158 0.542433 -0.0397507 + outer loop + vertex -856.201 456.225 187.461 + vertex -856.059 456.151 183.462 + vertex -857.364 454.418 187.351 + endloop + endfacet + facet normal -0.838511 0.542618 -0.049645 + outer loop + vertex -857.543 454.507 191.351 + vertex -856.201 456.225 187.461 + vertex -857.364 454.418 187.351 + endloop + endfacet + facet normal -0.839844 0.540419 -0.051076 + outer loop + vertex -856.378 456.328 191.463 + vertex -856.201 456.225 187.461 + vertex -857.543 454.507 191.351 + endloop + endfacet + facet normal -0.839101 0.540549 -0.0609671 + outer loop + vertex -857.756 454.628 195.354 + vertex -856.378 456.328 191.463 + vertex -857.543 454.507 191.351 + endloop + endfacet + facet normal -0.840341 0.538464 -0.0623174 + outer loop + vertex -856.59 456.46 195.466 + vertex -856.378 456.328 191.463 + vertex -857.756 454.628 195.354 + endloop + endfacet + facet normal -0.839556 0.538532 -0.0716145 + outer loop + vertex -858.005 454.771 199.348 + vertex -856.59 456.46 195.466 + vertex -857.756 454.628 195.354 + endloop + endfacet + facet normal -0.841431 0.535315 -0.0736976 + outer loop + vertex -856.836 456.624 199.458 + vertex -856.59 456.46 195.466 + vertex -858.005 454.771 199.348 + endloop + endfacet + facet normal -0.840461 0.535316 -0.084036 + outer loop + vertex -858.289 454.949 203.321 + vertex -856.836 456.624 199.458 + vertex -858.005 454.771 199.348 + endloop + endfacet + facet normal -0.841207 0.53401 -0.0848825 + outer loop + vertex -857.112 456.819 203.425 + vertex -856.836 456.624 199.458 + vertex -858.289 454.949 203.321 + endloop + endfacet + facet normal -0.840471 0.533955 -0.0921964 + outer loop + vertex -858.585 455.161 207.252 + vertex -857.112 456.819 203.425 + vertex -858.289 454.949 203.321 + endloop + endfacet + facet normal -0.844078 0.527486 -0.0963873 + outer loop + vertex -857.421 457.043 207.358 + vertex -857.112 456.819 203.425 + vertex -858.585 455.161 207.252 + endloop + endfacet + facet normal -0.843087 0.527374 -0.105269 + outer loop + vertex -858.928 455.389 211.139 + vertex -857.421 457.043 207.358 + vertex -858.585 455.161 207.252 + endloop + endfacet + facet normal -0.846192 0.521606 -0.109028 + outer loop + vertex -857.775 457.289 211.279 + vertex -857.421 457.043 207.358 + vertex -858.928 455.389 211.139 + endloop + endfacet + facet normal -0.844976 0.521553 -0.118313 + outer loop + vertex -859.333 455.62 215.053 + vertex -857.775 457.289 211.279 + vertex -858.928 455.389 211.139 + endloop + endfacet + facet normal -0.848087 0.515563 -0.122246 + outer loop + vertex -858.179 457.562 215.235 + vertex -857.775 457.289 211.279 + vertex -859.333 455.62 215.053 + endloop + endfacet + facet normal -0.846674 0.515594 -0.131551 + outer loop + vertex -859.785 455.905 219.081 + vertex -858.179 457.562 215.235 + vertex -859.333 455.62 215.053 + endloop + endfacet + facet normal -0.848867 0.511252 -0.134337 + outer loop + vertex -858.605 457.895 219.194 + vertex -858.179 457.562 215.235 + vertex -859.785 455.905 219.081 + endloop + endfacet + facet normal -0.847839 0.511044 -0.141433 + outer loop + vertex -860.169 456.361 223.03 + vertex -858.605 457.895 219.194 + vertex -859.785 455.905 219.081 + endloop + endfacet + facet normal -0.849709 0.507293 -0.143695 + outer loop + vertex -859.004 458.292 222.956 + vertex -858.605 457.895 219.194 + vertex -860.169 456.361 223.03 + endloop + endfacet + facet normal -0.849672 0.507258 -0.144038 + outer loop + vertex -860.305 456.988 226.039 + vertex -859.004 458.292 222.956 + vertex -860.169 456.361 223.03 + endloop + endfacet + facet normal -0.857112 0.491637 -0.153789 + outer loop + vertex -859.488 458.583 226.584 + vertex -859.004 458.292 222.956 + vertex -860.305 456.988 226.039 + endloop + endfacet + facet normal -0.855355 0.492785 -0.159783 + outer loop + vertex -861.183 456.659 229.723 + vertex -859.488 458.583 226.584 + vertex -860.305 456.988 226.039 + endloop + endfacet + facet normal -0.85685 0.48919 -0.162794 + outer loop + vertex -860.04 458.826 230.217 + vertex -859.488 458.583 226.584 + vertex -861.183 456.659 229.723 + endloop + endfacet + facet normal -0.857927 0.488752 -0.158376 + outer loop + vertex -861.638 456.983 233.188 + vertex -860.04 458.826 230.217 + vertex -861.183 456.659 229.723 + endloop + endfacet + facet normal -0.864131 0.473195 -0.171361 + outer loop + vertex -860.655 459.08 234.021 + vertex -860.04 458.826 230.217 + vertex -861.638 456.983 233.188 + endloop + endfacet + facet normal -0.861407 0.475145 -0.179485 + outer loop + vertex -862.766 456.605 237.599 + vertex -860.655 459.08 234.021 + vertex -861.638 456.983 233.188 + endloop + endfacet + facet normal -0.863218 0.470083 -0.184056 + outer loop + vertex -861.395 459.452 238.442 + vertex -860.655 459.08 234.021 + vertex -862.766 456.605 237.599 + endloop + endfacet + facet normal -0.862897 0.470248 -0.185135 + outer loop + vertex -863.804 457.012 243.47 + vertex -861.395 459.452 238.442 + vertex -862.766 456.605 237.599 + endloop + endfacet + facet normal -0.872598 0.44461 -0.202226 + outer loop + vertex -862.086 460.456 243.633 + vertex -861.395 459.452 238.442 + vertex -863.804 457.012 243.47 + endloop + endfacet + facet normal -0.871563 0.444331 -0.20724 + outer loop + vertex -863.804 457.012 243.47 + vertex -864.725 458.203 249.9 + vertex -862.086 460.456 243.633 + endloop + endfacet + facet normal -0.902317 0.347574 -0.254982 + outer loop + vertex -864.725 458.203 249.9 + vertex -862.627 463.772 250.067 + vertex -862.086 460.456 243.633 + endloop + endfacet + facet normal -0.912182 0.350032 -0.213076 + outer loop + vertex -865.839 459.587 256.943 + vertex -862.627 463.772 250.067 + vertex -864.725 458.203 249.9 + endloop + endfacet + facet normal -0.915049 0.336199 -0.222834 + outer loop + vertex -863.98 464.98 257.446 + vertex -862.627 463.772 250.067 + vertex -865.839 459.587 256.943 + endloop + endfacet + facet normal -0.913876 0.336234 -0.227549 + outer loop + vertex -867.259 460.72 264.321 + vertex -863.98 464.98 257.446 + vertex -865.839 459.587 256.943 + endloop + endfacet + facet normal -0.916589 0.321134 -0.238198 + outer loop + vertex -865.46 466.368 265.011 + vertex -863.98 464.98 257.446 + vertex -867.259 460.72 264.321 + endloop + endfacet + facet normal -0.915394 0.321285 -0.242548 + outer loop + vertex -868.772 461.829 271.498 + vertex -865.46 466.368 265.011 + vertex -867.259 460.72 264.321 + endloop + endfacet + facet normal -0.917174 0.308166 -0.252636 + outer loop + vertex -866.839 467.74 271.692 + vertex -865.46 466.368 265.011 + vertex -868.772 461.829 271.498 + endloop + endfacet + facet normal -0.916731 0.308077 -0.254347 + outer loop + vertex -870.207 462.949 278.027 + vertex -866.839 467.74 271.692 + vertex -868.772 461.829 271.498 + endloop + endfacet + facet normal -0.918131 0.293907 -0.265808 + outer loop + vertex -868.257 469.254 278.262 + vertex -866.839 467.74 271.692 + vertex -870.207 462.949 278.027 + endloop + endfacet + facet normal -0.918588 0.293986 -0.264136 + outer loop + vertex -871.431 464.156 283.626 + vertex -868.257 469.254 278.262 + vertex -870.207 462.949 278.027 + endloop + endfacet + facet normal -0.918984 0.279105 -0.278513 + outer loop + vertex -869.607 470.827 284.293 + vertex -868.257 469.254 278.262 + vertex -871.431 464.156 283.626 + endloop + endfacet + facet normal -0.91995 0.279054 -0.275358 + outer loop + vertex -872.427 465.403 288.218 + vertex -869.607 470.827 284.293 + vertex -871.431 464.156 283.626 + endloop + endfacet + facet normal -0.918721 0.267356 -0.290642 + outer loop + vertex -870.743 472.295 289.236 + vertex -869.607 470.827 284.293 + vertex -872.427 465.403 288.218 + endloop + endfacet + facet normal -0.921397 0.266816 -0.282553 + outer loop + vertex -872.427 465.403 288.218 + vertex -873.436 466.101 292.168 + vertex -870.743 472.295 289.236 + endloop + endfacet + facet normal -0.920286 0.336838 0.199033 + outer loop + vertex -864.078 463.284 78.99 + vertex -865.069 464.751 71.9264 + vertex -866.293 457.204 79.0372 + endloop + endfacet + facet normal -0.917612 0.356471 0.175833 + outer loop + vertex -865.335 456.097 86.2788 + vertex -866.293 457.204 79.0372 + vertex -867.653 450.087 86.3711 + endloop + endfacet + facet normal -0.928845 0.33808 0.15149 + outer loop + vertex -866.734 449.336 93.6827 + vertex -867.653 450.087 86.3711 + vertex -868.944 443.242 93.731 + endloop + endfacet + facet normal -0.938629 0.31801 0.133589 + outer loop + vertex -868.053 442.746 101.168 + vertex -868.944 443.242 93.731 + vertex -870.156 436.53 101.195 + endloop + endfacet + facet normal -0.945044 0.304129 0.119992 + outer loop + vertex -869.3 436.189 108.794 + vertex -870.156 436.53 101.195 + vertex -871.33 429.877 108.81 + endloop + endfacet + facet normal -0.949749 0.294051 0.10729 + outer loop + vertex -870.528 429.644 116.54 + vertex -871.33 429.877 108.81 + vertex -872.495 423.293 116.54 + endloop + endfacet + facet normal -0.954378 0.283478 0.0938224 + outer loop + vertex -871.767 423.158 124.355 + vertex -872.495 423.293 116.54 + vertex -873.651 416.819 124.338 + endloop + endfacet + facet normal -0.959558 0.270014 0.0796272 + outer loop + vertex -873.011 416.771 132.209 + vertex -873.651 416.819 124.338 + vertex -874.786 410.472 132.185 + endloop + endfacet + facet normal -0.96512 0.253622 0.0649593 + outer loop + vertex -874.25 410.488 140.084 + vertex -874.786 410.472 132.185 + vertex -875.899 404.217 140.065 + endloop + endfacet + facet normal -0.970579 0.235516 0.0500865 + outer loop + vertex -875.479 404.269 147.956 + vertex -875.899 404.217 140.065 + vertex -877.002 397.996 147.946 + endloop + endfacet + facet normal -0.975722 0.216244 0.034711 + outer loop + vertex -876.709 398.058 155.8 + vertex -877.002 397.996 147.946 + vertex -878.108 391.745 155.799 + endloop + endfacet + facet normal -0.980518 0.195542 0.0186572 + outer loop + vertex -877.949 391.797 163.618 + vertex -878.108 391.745 155.799 + vertex -879.223 385.408 163.621 + endloop + endfacet + facet normal -0.985029 0.172378 0.00176464 + outer loop + vertex -879.205 385.431 171.443 + vertex -879.223 385.408 163.621 + vertex -880.342 378.934 171.446 + endloop + endfacet + facet normal -0.98908 0.14653 -0.0158145 + outer loop + vertex -880.472 378.906 179.321 + vertex -880.342 378.934 171.446 + vertex -881.453 372.288 179.322 + endloop + endfacet + facet normal -0.992472 0.117629 -0.0341095 + outer loop + vertex -881.737 372.19 187.267 + vertex -881.453 372.288 179.322 + vertex -882.535 365.457 187.267 + endloop + endfacet + facet normal -0.991684 0.117536 -0.0524143 + outer loop + vertex -882.98 365.267 195.254 + vertex -881.737 372.19 187.267 + vertex -882.535 365.457 187.267 + endloop + endfacet + facet normal -0.990567 0.116514 -0.0721161 + outer loop + vertex -883.592 365.002 203.232 + vertex -882.185 372.027 195.254 + vertex -882.98 365.267 195.254 + endloop + endfacet + facet normal -0.988993 0.115467 -0.092526 + outer loop + vertex -884.373 364.659 211.154 + vertex -882.799 371.792 203.231 + vertex -883.592 365.002 203.232 + endloop + endfacet + facet normal -0.987011 0.114134 -0.113065 + outer loop + vertex -885.32 364.238 218.998 + vertex -883.583 371.493 211.153 + vertex -884.373 364.659 211.154 + endloop + endfacet + facet normal -0.984687 0.1125 -0.133171 + outer loop + vertex -886.428 363.742 226.767 + vertex -884.533 371.126 218.997 + vertex -885.32 364.238 218.998 + endloop + endfacet + facet normal -0.982144 0.110653 -0.152149 + outer loop + vertex -887.684 363.174 234.467 + vertex -885.645 370.691 226.766 + vertex -886.428 363.742 226.767 + endloop + endfacet + facet normal -0.979479 0.108699 -0.169724 + outer loop + vertex -889.075 362.548 242.09 + vertex -886.905 370.193 234.465 + vertex -887.684 363.174 234.467 + endloop + endfacet + facet normal -0.976636 0.106567 -0.186615 + outer loop + vertex -890.586 361.884 249.618 + vertex -888.3 369.645 242.089 + vertex -889.075 362.548 242.09 + endloop + endfacet + facet normal -0.973638 0.104644 -0.20268 + outer loop + vertex -892.203 361.193 257.03 + vertex -889.814 369.064 249.617 + vertex -890.586 361.884 249.618 + endloop + endfacet + facet normal -0.970684 0.103131 -0.217109 + outer loop + vertex -893.906 360.466 264.297 + vertex -891.43 368.464 257.029 + vertex -892.203 361.193 257.03 + endloop + endfacet + facet normal -0.968038 0.101678 -0.229267 + outer loop + vertex -895.655 359.675 271.332 + vertex -893.131 367.844 264.3 + vertex -893.906 360.466 264.297 + endloop + endfacet + facet normal -0.965964 0.100709 -0.238269 + outer loop + vertex -897.365 358.796 277.891 + vertex -894.873 367.165 271.33 + vertex -895.655 359.675 271.332 + endloop + endfacet + facet normal -0.964076 0.0990587 -0.246466 + outer loop + vertex -898.914 357.887 283.585 + vertex -896.584 366.388 277.888 + vertex -897.365 358.796 277.891 + endloop + endfacet + facet normal -0.962241 0.0625754 -0.264907 + outer loop + vertex -900.192 357.212 288.068 + vertex -898.914 357.887 283.585 + vertex -900.702 349.468 288.091 + endloop + endfacet + facet normal -0.956813 0.0284337 -0.28931 + outer loop + vertex -901.678 349.523 291.326 + vertex -900.702 349.468 288.091 + vertex -901.905 341.893 291.326 + endloop + endfacet + facet normal -0.962067 0.0230558 -0.271837 + outer loop + vertex -900.894 341.811 288.102 + vertex -899.422 350.173 283.601 + vertex -899.604 342.5 283.594 + endloop + endfacet + facet normal -0.96646 0.0244945 -0.255646 + outer loop + vertex -899.604 342.5 283.594 + vertex -897.877 351.151 277.895 + vertex -898.068 343.546 277.885 + endloop + endfacet + facet normal -0.9691 0.0266998 -0.24522 + outer loop + vertex -898.068 343.546 277.885 + vertex -896.173 352.142 271.333 + vertex -896.379 344.644 271.331 + endloop + endfacet + facet normal -0.971479 0.0288068 -0.235368 + outer loop + vertex -896.379 344.644 271.331 + vertex -894.426 353.049 264.299 + vertex -894.645 345.658 264.301 + endloop + endfacet + facet normal -0.974393 0.0306475 -0.222752 + outer loop + vertex -894.645 345.658 264.301 + vertex -892.725 353.877 257.031 + vertex -892.955 346.581 257.032 + endloop + endfacet + facet normal -0.977733 0.0325529 -0.207312 + outer loop + vertex -892.955 346.581 257.032 + vertex -891.114 354.657 249.619 + vertex -891.354 347.445 249.619 + endloop + endfacet + facet normal -0.981144 0.0351273 -0.190061 + outer loop + vertex -891.354 347.445 249.619 + vertex -889.611 355.402 242.09 + vertex -889.866 348.271 242.091 + endloop + endfacet + facet normal -0.98424 0.0374582 -0.172823 + outer loop + vertex -889.866 348.271 242.091 + vertex -888.229 356.104 234.467 + vertex -888.498 349.047 234.466 + endloop + endfacet + facet normal -0.98722 0.0404364 -0.15415 + outer loop + vertex -888.498 349.047 234.466 + vertex -886.981 356.739 226.766 + vertex -887.267 349.752 226.768 + endloop + endfacet + facet normal -0.989956 0.0427801 -0.134745 + outer loop + vertex -887.267 349.752 226.768 + vertex -885.883 357.299 218.999 + vertex -886.183 350.371 218.999 + endloop + endfacet + facet normal -0.992411 0.0449846 -0.114439 + outer loop + vertex -886.183 350.371 218.999 + vertex -884.943 357.771 211.154 + vertex -885.255 350.895 211.155 + endloop + endfacet + facet normal -0.99452 0.0468089 -0.0934841 + outer loop + vertex -885.255 350.895 211.155 + vertex -884.168 358.158 203.232 + vertex -884.49 351.323 203.233 + endloop + endfacet + facet normal -0.996181 0.0481664 -0.0728196 + outer loop + vertex -884.49 351.323 203.233 + vertex -883.562 358.457 195.255 + vertex -883.891 351.654 195.255 + endloop + endfacet + facet normal -0.997382 0.0492339 -0.05297 + outer loop + vertex -883.891 351.654 195.255 + vertex -883.12 358.668 187.267 + vertex -883.455 351.887 187.268 + endloop + endfacet + facet normal -0.999412 0.00681119 -0.033599 + outer loop + vertex -883.494 345.152 187.269 + vertex -883.18 352.025 179.324 + vertex -883.225 345.302 179.324 + endloop + endfacet + facet normal -0.999864 0.00681616 -0.0150493 + outer loop + vertex -883.18 352.025 179.324 + vertex -883.061 352.068 171.448 + vertex -883.225 345.302 179.324 + endloop + endfacet + facet normal -0.999865 0.00699001 -0.0149 + outer loop + vertex -883.225 345.302 179.324 + vertex -883.061 352.068 171.448 + vertex -883.108 345.348 171.449 + endloop + endfacet + facet normal -0.998882 -0.0447677 -0.0151871 + outer loop + vertex -883.225 345.302 179.324 + vertex -883.108 345.348 171.449 + vertex -882.926 338.62 179.327 + endloop + endfacet + facet normal -0.998421 -0.0447554 -0.0339587 + outer loop + vertex -883.189 338.458 187.272 + vertex -883.225 345.302 179.324 + vertex -882.926 338.62 179.327 + endloop + endfacet + facet normal -0.998369 -0.045448 -0.0345554 + outer loop + vertex -883.494 345.152 187.269 + vertex -883.225 345.302 179.324 + vertex -883.189 338.458 187.272 + endloop + endfacet + facet normal -0.997541 -0.0454178 -0.0533797 + outer loop + vertex -883.604 338.18 195.26 + vertex -883.494 345.152 187.269 + vertex -883.189 338.458 187.272 + endloop + endfacet + facet normal -0.997384 -0.0470959 -0.0548416 + outer loop + vertex -883.921 344.896 195.257 + vertex -883.494 345.152 187.269 + vertex -883.604 338.18 195.26 + endloop + endfacet + facet normal -0.996152 -0.0470461 -0.0739445 + outer loop + vertex -884.177 337.788 203.238 + vertex -883.921 344.896 195.257 + vertex -883.604 338.18 195.26 + endloop + endfacet + facet normal -0.995927 -0.0490048 -0.0756818 + outer loop + vertex -884.509 344.534 203.235 + vertex -883.921 344.896 195.257 + vertex -884.177 337.788 203.238 + endloop + endfacet + facet normal -0.994266 -0.0489315 -0.0950846 + outer loop + vertex -884.91 337.28 211.16 + vertex -884.509 344.534 203.235 + vertex -884.177 337.788 203.238 + endloop + endfacet + facet normal -0.993988 -0.0509451 -0.0969137 + outer loop + vertex -885.257 344.064 211.156 + vertex -884.509 344.534 203.235 + vertex -884.91 337.28 211.16 + endloop + endfacet + facet normal -0.991915 -0.0508511 -0.116268 + outer loop + vertex -885.798 336.657 219.004 + vertex -885.257 344.064 211.156 + vertex -884.91 337.28 211.16 + endloop + endfacet + facet normal -0.991398 -0.0540125 -0.119215 + outer loop + vertex -886.169 343.49 219 + vertex -885.257 344.064 211.156 + vertex -885.798 336.657 219.004 + endloop + endfacet + facet normal -0.989116 -0.0538979 -0.13691 + outer loop + vertex -886.833 335.923 226.772 + vertex -886.169 343.49 219 + vertex -885.798 336.657 219.004 + endloop + endfacet + facet normal -0.988352 -0.0579011 -0.140743 + outer loop + vertex -887.236 342.815 226.77 + vertex -886.169 343.49 219 + vertex -886.833 335.923 226.772 + endloop + endfacet + facet normal -0.985796 -0.0577565 -0.157704 + outer loop + vertex -888.016 335.09 234.47 + vertex -887.236 342.815 226.77 + vertex -886.833 335.923 226.772 + endloop + endfacet + facet normal -0.985109 -0.0608966 -0.160784 + outer loop + vertex -888.445 342.043 234.468 + vertex -887.236 342.815 226.77 + vertex -888.016 335.09 234.47 + endloop + endfacet + facet normal -0.982431 -0.0607369 -0.176465 + outer loop + vertex -889.328 334.171 242.093 + vertex -888.445 342.043 234.468 + vertex -888.016 335.09 234.47 + endloop + endfacet + facet normal -0.981548 -0.064326 -0.180069 + outer loop + vertex -889.788 341.194 242.091 + vertex -888.445 342.043 234.468 + vertex -889.328 334.171 242.093 + endloop + endfacet + facet normal -0.978687 -0.0641432 -0.195083 + outer loop + vertex -890.764 333.19 249.622 + vertex -889.788 341.194 242.091 + vertex -889.328 334.171 242.093 + endloop + endfacet + facet normal -0.977669 -0.067855 -0.198896 + outer loop + vertex -891.257 340.291 249.621 + vertex -889.788 341.194 242.091 + vertex -890.764 333.19 249.622 + endloop + endfacet + facet normal -0.974684 -0.0676505 -0.213106 + outer loop + vertex -892.314 332.16 257.035 + vertex -891.257 340.291 249.621 + vertex -890.764 333.19 249.622 + endloop + endfacet + facet normal -0.973803 -0.0705577 -0.216169 + outer loop + vertex -892.833 339.342 257.032 + vertex -891.257 340.291 249.621 + vertex -892.314 332.16 257.035 + endloop + endfacet + facet normal -0.970623 -0.0703322 -0.230095 + outer loop + vertex -893.957 331.062 264.303 + vertex -892.833 339.342 257.032 + vertex -892.314 332.16 257.035 + endloop + endfacet + facet normal -0.969626 -0.0733193 -0.233343 + outer loop + vertex -894.506 338.331 264.3 + vertex -892.833 339.342 257.032 + vertex -893.957 331.062 264.303 + endloop + endfacet + facet normal -0.966959 -0.0731221 -0.244222 + outer loop + vertex -895.642 329.864 271.331 + vertex -894.506 338.331 264.3 + vertex -893.957 331.062 264.303 + endloop + endfacet + facet normal -0.965875 -0.076063 -0.247589 + outer loop + vertex -896.22 337.222 271.329 + vertex -894.506 338.331 264.3 + vertex -895.642 329.864 271.331 + endloop + endfacet + facet normal -0.963698 -0.0758945 -0.255982 + outer loop + vertex -897.282 328.583 277.885 + vertex -896.22 337.222 271.329 + vertex -895.642 329.864 271.331 + endloop + endfacet + facet normal -0.962496 -0.0787907 -0.259604 + outer loop + vertex -897.891 336.029 277.884 + vertex -896.22 337.222 271.329 + vertex -897.282 328.583 277.885 + endloop + endfacet + facet normal -0.960182 -0.0786027 -0.26809 + outer loop + vertex -898.773 327.393 283.578 + vertex -897.891 336.029 277.884 + vertex -897.282 328.583 277.885 + endloop + endfacet + facet normal -0.959166 -0.0806856 -0.271092 + outer loop + vertex -899.406 334.915 283.578 + vertex -897.891 336.029 277.884 + vertex -898.773 327.393 283.578 + endloop + endfacet + facet normal -0.953761 -0.0802292 -0.289661 + outer loop + vertex -900.078 326.694 288.066 + vertex -899.406 334.915 283.578 + vertex -898.773 327.393 283.578 + endloop + endfacet + facet normal -0.954668 -0.0787408 -0.28707 + outer loop + vertex -900.705 334.249 288.078 + vertex -899.406 334.915 283.578 + vertex -900.078 326.694 288.066 + endloop + endfacet + facet normal -0.942027 -0.0776246 -0.326435 + outer loop + vertex -901.229 327.087 291.295 + vertex -900.705 334.249 288.078 + vertex -900.078 326.694 288.066 + endloop + endfacet + facet normal -0.949056 -0.0686236 -0.307543 + outer loop + vertex -901.783 334.628 291.322 + vertex -900.705 334.249 288.078 + vertex -901.229 327.087 291.295 + endloop + endfacet + facet normal -0.998948 -0.0436132 -0.0141996 + outer loop + vertex -882.926 338.62 179.327 + vertex -883.108 345.348 171.449 + vertex -882.816 338.671 171.451 + endloop + endfacet + facet normal -0.999039 -0.0436135 0.00438276 + outer loop + vertex -883.108 345.348 171.449 + vertex -883.14 345.292 163.625 + vertex -882.816 338.671 171.451 + endloop + endfacet + facet normal -0.999039 -0.0436124 0.00438363 + outer loop + vertex -882.816 338.671 171.451 + vertex -883.14 345.292 163.625 + vertex -882.848 338.609 163.626 + endloop + endfacet + facet normal -0.99877 -0.0435974 0.023596 + outer loop + vertex -883.14 345.292 163.625 + vertex -883.317 345.133 155.805 + vertex -882.848 338.609 163.626 + endloop + endfacet + facet normal -0.998773 -0.0435021 0.0236756 + outer loop + vertex -882.848 338.609 163.626 + vertex -883.317 345.133 155.805 + vertex -883.026 338.436 155.806 + endloop + endfacet + facet normal -0.998166 -0.0434729 0.0421368 + outer loop + vertex -883.317 345.133 155.805 + vertex -883.638 344.87 147.952 + vertex -883.026 338.436 155.806 + endloop + endfacet + facet normal -0.998158 -0.0442847 0.0414713 + outer loop + vertex -883.026 338.436 155.806 + vertex -883.638 344.87 147.952 + vertex -883.339 338.15 147.952 + endloop + endfacet + facet normal -0.997194 -0.0442401 0.060393 + outer loop + vertex -883.638 344.87 147.952 + vertex -884.099 344.503 140.065 + vertex -883.339 338.15 147.952 + endloop + endfacet + facet normal -0.997198 -0.0454639 0.0594076 + outer loop + vertex -883.339 338.15 147.952 + vertex -884.099 344.503 140.065 + vertex -883.791 337.752 140.066 + endloop + endfacet + facet normal -0.995907 -0.0454034 0.0781516 + outer loop + vertex -884.099 344.503 140.065 + vertex -884.697 344.035 132.177 + vertex -883.791 337.752 140.066 + endloop + endfacet + facet normal -0.995915 -0.045911 0.0777483 + outer loop + vertex -883.791 337.752 140.066 + vertex -884.697 344.035 132.177 + vertex -884.383 337.244 132.178 + endloop + endfacet + facet normal -0.994303 -0.0458358 0.0962368 + outer loop + vertex -884.697 344.035 132.177 + vertex -885.431 343.468 124.32 + vertex -884.383 337.244 132.178 + endloop + endfacet + facet normal -0.994358 -0.0477603 0.0947197 + outer loop + vertex -884.383 337.244 132.178 + vertex -885.431 343.468 124.32 + vertex -885.102 336.626 124.321 + endloop + endfacet + facet normal -0.992396 -0.0476642 0.113481 + outer loop + vertex -885.431 343.468 124.32 + vertex -886.291 342.798 116.514 + vertex -885.102 336.626 124.321 + endloop + endfacet + facet normal -0.992451 -0.0490127 0.112423 + outer loop + vertex -885.102 336.626 124.321 + vertex -886.291 342.798 116.514 + vertex -885.951 335.899 116.514 + endloop + endfacet + facet normal -0.990293 -0.0489056 0.130105 + outer loop + vertex -886.291 342.798 116.514 + vertex -887.269 342.015 108.776 + vertex -885.951 335.899 116.514 + endloop + endfacet + facet normal -0.990386 -0.050701 0.128702 + outer loop + vertex -885.951 335.899 116.514 + vertex -887.269 342.015 108.776 + vertex -886.913 335.049 108.775 + endloop + endfacet + facet normal -0.987962 -0.0505779 0.146196 + outer loop + vertex -887.269 342.015 108.776 + vertex -888.354 341.111 101.136 + vertex -886.913 335.049 108.775 + endloop + endfacet + facet normal -0.988146 -0.053538 0.143882 + outer loop + vertex -886.913 335.049 108.775 + vertex -888.354 341.111 101.136 + vertex -887.972 334.073 101.138 + endloop + endfacet + facet normal -0.985761 -0.0534036 0.159447 + outer loop + vertex -888.354 341.111 101.136 + vertex -889.513 340.13 93.641 + vertex -887.972 334.073 101.138 + endloop + endfacet + facet normal -0.985926 -0.0556894 0.157634 + outer loop + vertex -887.972 334.073 101.138 + vertex -889.513 340.13 93.641 + vertex -889.11 333.016 93.6437 + endloop + endfacet + facet normal -0.983774 -0.0555629 0.170589 + outer loop + vertex -889.513 340.13 93.641 + vertex -890.73 339.167 86.3071 + vertex -889.11 333.016 93.6437 + endloop + endfacet + facet normal -0.983915 -0.0572268 0.169224 + outer loop + vertex -889.11 333.016 93.6437 + vertex -890.73 339.167 86.3071 + vertex -890.311 331.974 86.3104 + endloop + endfacet + facet normal -0.981859 -0.0571017 0.180813 + outer loop + vertex -890.73 339.167 86.3071 + vertex -892.005 338.299 79.1104 + vertex -890.311 331.974 86.3104 + endloop + endfacet + facet normal -0.981894 -0.057461 0.180506 + outer loop + vertex -890.311 331.974 86.3104 + vertex -892.005 338.299 79.1104 + vertex -891.578 331.019 79.1135 + endloop + endfacet + facet normal -0.979647 -0.0573243 0.192368 + outer loop + vertex -892.005 338.299 79.1104 + vertex -893.339 337.439 72.0619 + vertex -891.578 331.019 79.1135 + endloop + endfacet + facet normal -0.979517 -0.056199 0.19336 + outer loop + vertex -891.578 331.019 79.1135 + vertex -893.339 337.439 72.0619 + vertex -892.918 330.071 72.0525 + endloop + endfacet + facet normal -0.976852 -0.0560634 0.206441 + outer loop + vertex -893.339 337.439 72.0619 + vertex -894.696 336.299 65.3282 + vertex -892.918 330.071 72.0525 + endloop + endfacet + facet normal -0.977201 -0.0587776 0.204019 + outer loop + vertex -892.918 330.071 72.0525 + vertex -894.696 336.299 65.3282 + vertex -894.248 328.833 65.3235 + endloop + endfacet + facet normal -0.973994 -0.0585944 0.218867 + outer loop + vertex -894.696 336.299 65.3282 + vertex -895.922 334.473 59.3849 + vertex -894.248 328.833 65.3235 + endloop + endfacet + facet normal -0.974776 -0.0642197 0.213746 + outer loop + vertex -894.248 328.833 65.3235 + vertex -895.922 334.473 59.3849 + vertex -895.434 326.955 59.3499 + endloop + endfacet + facet normal -0.970694 -0.0640383 0.231628 + outer loop + vertex -895.922 334.473 59.3849 + vertex -896.847 331.79 54.7648 + vertex -895.434 326.955 59.3499 + endloop + endfacet + facet normal -0.973228 -0.0801545 0.215413 + outer loop + vertex -895.434 326.955 59.3499 + vertex -896.847 331.79 54.7648 + vertex -896.23 324.24 54.7432 + endloop + endfacet + facet normal -0.965227 -0.0795967 0.249001 + outer loop + vertex -896.23 324.24 54.7432 + vertex -896.847 331.79 54.7648 + vertex -897.335 328.462 51.811 + endloop + endfacet + facet normal -0.977045 -0.0421911 0.208815 + outer loop + vertex -897.658 335.974 51.8165 + vertex -897.335 328.462 51.811 + vertex -896.847 331.79 54.7648 + endloop + endfacet + facet normal -0.95713 -0.0413919 0.286687 + outer loop + vertex -897.658 335.974 51.8165 + vertex -897.984 332.47 50.2231 + vertex -897.335 328.462 51.811 + endloop + endfacet + facet normal -0.971086 -0.0663849 0.229312 + outer loop + vertex -897.335 328.462 51.811 + vertex -897.984 332.47 50.2231 + vertex -897.486 325.124 50.205 + endloop + endfacet + facet normal -0.992129 0.00175114 0.125209 + outer loop + vertex -886.291 342.798 116.514 + vertex -887.257 349.033 108.774 + vertex -887.269 342.015 108.776 + endloop + endfacet + facet normal -0.990021 0.00175066 0.140911 + outer loop + vertex -887.257 349.033 108.774 + vertex -888.345 348.207 101.138 + vertex -887.269 342.015 108.776 + endloop + endfacet + facet normal -0.990096 0.00109478 0.14039 + outer loop + vertex -887.269 342.015 108.776 + vertex -888.345 348.207 101.138 + vertex -888.354 341.111 101.136 + endloop + endfacet + facet normal -0.98804 0.0010887 0.154194 + outer loop + vertex -888.345 348.207 101.138 + vertex -889.516 347.308 93.6429 + vertex -888.354 341.111 101.136 + endloop + endfacet + facet normal -0.988241 -0.000509894 0.152904 + outer loop + vertex -888.354 341.111 101.136 + vertex -889.516 347.308 93.6429 + vertex -889.513 340.13 93.641 + endloop + endfacet + facet normal -0.986268 -0.000512105 0.165152 + outer loop + vertex -889.516 347.308 93.6429 + vertex -890.744 346.429 86.3072 + vertex -889.513 340.13 93.641 + endloop + endfacet + facet normal -0.98646 -0.001902 0.16399 + outer loop + vertex -889.513 340.13 93.641 + vertex -890.744 346.429 86.3072 + vertex -890.73 339.167 86.3071 + endloop + endfacet + facet normal -0.98458 -0.00189861 0.174923 + outer loop + vertex -890.744 346.429 86.3072 + vertex -892.021 345.649 79.109 + vertex -890.73 339.167 86.3071 + endloop + endfacet + facet normal -0.984624 -0.00218314 0.174674 + outer loop + vertex -890.73 339.167 86.3071 + vertex -892.021 345.649 79.109 + vertex -892.005 338.299 79.1104 + endloop + endfacet + facet normal -0.982447 -0.00217603 0.186532 + outer loop + vertex -892.021 345.649 79.109 + vertex -893.36 344.89 72.052 + vertex -892.005 338.299 79.1104 + endloop + endfacet + facet normal -0.982504 -0.00251422 0.186227 + outer loop + vertex -892.005 338.299 79.1104 + vertex -893.36 344.89 72.052 + vertex -893.339 337.439 72.0619 + endloop + endfacet + facet normal -0.980247 -0.0024926 0.197764 + outer loop + vertex -893.36 344.89 72.052 + vertex -894.712 343.844 65.3335 + vertex -893.339 337.439 72.0619 + endloop + endfacet + facet normal -0.980199 -0.00223326 0.198001 + outer loop + vertex -893.339 337.439 72.0619 + vertex -894.712 343.844 65.3335 + vertex -894.696 336.299 65.3282 + endloop + endfacet + facet normal -0.977755 -0.00223632 0.209738 + outer loop + vertex -894.712 343.844 65.3335 + vertex -895.983 342.093 59.3895 + vertex -894.696 336.299 65.3282 + endloop + endfacet + facet normal -0.978869 -0.00802526 0.204331 + outer loop + vertex -894.696 336.299 65.3282 + vertex -895.983 342.093 59.3895 + vertex -895.922 334.473 59.3849 + endloop + endfacet + facet normal -0.975374 -0.00800671 0.220411 + outer loop + vertex -895.983 342.093 59.3895 + vertex -896.998 339.401 54.8 + vertex -895.922 334.473 59.3849 + endloop + endfacet + facet normal -0.977974 -0.020371 0.207732 + outer loop + vertex -895.922 334.473 59.3849 + vertex -896.998 339.401 54.8 + vertex -896.847 331.79 54.7648 + endloop + endfacet + facet normal -0.971022 -0.0203735 0.238121 + outer loop + vertex -896.847 331.79 54.7648 + vertex -896.998 339.401 54.8 + vertex -897.658 335.974 51.8165 + endloop + endfacet + facet normal -0.979188 0.0121336 0.202591 + outer loop + vertex -897.555 343.633 51.8555 + vertex -897.658 335.974 51.8165 + vertex -896.998 339.401 54.8 + endloop + endfacet + facet normal -0.973758 0.0289527 0.225737 + outer loop + vertex -896.998 339.401 54.8 + vertex -896.769 347.158 54.7955 + vertex -897.555 343.633 51.8555 + endloop + endfacet + facet normal -0.979202 0.0557264 0.195085 + outer loop + vertex -897.108 351.474 51.8579 + vertex -897.555 343.633 51.8555 + vertex -896.769 347.158 54.7955 + endloop + endfacet + facet normal -0.973672 0.07085 0.216662 + outer loop + vertex -896.769 347.158 54.7955 + vertex -896.196 354.983 54.8099 + vertex -897.108 351.474 51.8579 + endloop + endfacet + facet normal -0.977074 0.0928104 0.191607 + outer loop + vertex -896.37 359.272 51.8465 + vertex -897.108 351.474 51.8579 + vertex -896.196 354.983 54.8099 + endloop + endfacet + facet normal -0.971984 0.105689 0.209947 + outer loop + vertex -896.196 354.983 54.8099 + vertex -895.348 362.74 54.8312 + vertex -896.37 359.272 51.8465 + endloop + endfacet + facet normal -0.974237 0.126153 0.186941 + outer loop + vertex -895.371 366.912 51.8971 + vertex -896.37 359.272 51.8465 + vertex -895.348 362.74 54.8312 + endloop + endfacet + facet normal -0.969852 0.136621 0.201794 + outer loop + vertex -895.348 362.74 54.8312 + vertex -894.271 370.369 54.842 + vertex -895.371 366.912 51.8971 + endloop + endfacet + facet normal -0.971273 0.155595 0.180051 + outer loop + vertex -894.14 374.558 51.9278 + vertex -895.371 366.912 51.8971 + vertex -894.271 370.369 54.842 + endloop + endfacet + facet normal -0.966578 0.166068 0.195314 + outer loop + vertex -894.271 370.369 54.842 + vertex -892.968 377.953 54.8456 + vertex -894.14 374.558 51.9278 + endloop + endfacet + facet normal -0.967251 0.182954 0.175936 + outer loop + vertex -892.664 382.387 51.9033 + vertex -894.14 374.558 51.9278 + vertex -892.968 377.953 54.8456 + endloop + endfacet + facet normal -0.962494 0.192645 0.191031 + outer loop + vertex -892.968 377.953 54.8456 + vertex -891.422 385.777 54.7428 + vertex -892.664 382.387 51.9033 + endloop + endfacet + facet normal -0.962741 0.205854 0.17537 + outer loop + vertex -891.001 390.289 51.7585 + vertex -892.664 382.387 51.9033 + vertex -891.422 385.777 54.7428 + endloop + endfacet + facet normal -0.957656 0.215598 0.190822 + outer loop + vertex -891.422 385.777 54.7428 + vertex -889.508 394.596 54.3865 + vertex -891.001 390.289 51.7585 + endloop + endfacet + facet normal -0.958244 0.223083 0.17889 + outer loop + vertex -889.499 397.056 51.3625 + vertex -891.001 390.289 51.7585 + vertex -889.508 394.596 54.3865 + endloop + endfacet + facet normal -0.952186 0.238254 0.191251 + outer loop + vertex -887.718 403.475 52.232 + vertex -889.499 397.056 51.3625 + vertex -889.508 394.596 54.3865 + endloop + endfacet + facet normal -0.958416 0.233063 0.164683 + outer loop + vertex -889.508 394.596 54.3865 + vertex -887.771 400.916 55.5459 + vertex -887.718 403.475 52.232 + endloop + endfacet + facet normal -0.952919 0.24716 0.17566 + outer loop + vertex -887.771 400.916 55.5459 + vertex -886.164 407.479 55.0307 + vertex -887.718 403.475 52.232 + endloop + endfacet + facet normal -0.952883 0.25367 0.166329 + outer loop + vertex -885.48 412.043 51.9904 + vertex -887.718 403.475 52.232 + vertex -886.164 407.479 55.0307 + endloop + endfacet + facet normal -0.949106 0.260362 0.177226 + outer loop + vertex -886.164 407.479 55.0307 + vertex -884.157 414.912 54.859 + vertex -885.48 412.043 51.9904 + endloop + endfacet + facet normal -0.948416 0.268158 0.169109 + outer loop + vertex -883.346 419.637 51.9162 + vertex -885.48 412.043 51.9904 + vertex -884.157 414.912 54.859 + endloop + endfacet + facet normal -0.945753 0.272528 0.176859 + outer loop + vertex -884.157 414.912 54.859 + vertex -882.029 422.307 54.8427 + vertex -883.346 419.637 51.9162 + endloop + endfacet + facet normal -0.945021 0.27893 0.170687 + outer loop + vertex -881.145 427.101 51.9018 + vertex -883.346 419.637 51.9162 + vertex -882.029 422.307 54.8427 + endloop + endfacet + facet normal -0.943142 0.281906 0.176102 + outer loop + vertex -882.029 422.307 54.8427 + vertex -879.807 429.762 54.812 + vertex -881.145 427.101 51.9018 + endloop + endfacet + facet normal -0.942638 0.28604 0.172091 + outer loop + vertex -878.877 434.596 51.8702 + vertex -881.145 427.101 51.9018 + vertex -879.807 429.762 54.812 + endloop + endfacet + facet normal -0.94101 0.288555 0.176739 + outer loop + vertex -879.807 429.762 54.812 + vertex -877.463 437.463 54.7186 + vertex -878.877 434.596 51.8702 + endloop + endfacet + facet normal -0.940804 0.290438 0.174741 + outer loop + vertex -876.561 442.205 51.6942 + vertex -878.877 434.596 51.8702 + vertex -877.463 437.463 54.7186 + endloop + endfacet + facet normal -0.938646 0.293791 0.180642 + outer loop + vertex -877.463 437.463 54.7186 + vertex -874.806 446.187 54.3378 + vertex -876.561 442.205 51.6942 + endloop + endfacet + facet normal -0.940087 0.293888 0.172818 + outer loop + vertex -876.145 438.968 59.329 + vertex -874.806 446.187 54.3378 + vertex -877.463 437.463 54.7186 + endloop + endfacet + facet normal -0.940802 0.290888 0.174002 + outer loop + vertex -876.145 438.968 59.329 + vertex -877.463 437.463 54.7186 + vertex -878.472 431.387 59.4165 + endloop + endfacet + facet normal -0.941724 0.291108 0.168561 + outer loop + vertex -877.264 431.857 65.3561 + vertex -876.145 438.968 59.329 + vertex -878.472 431.387 59.4165 + endloop + endfacet + facet normal -0.943085 0.286277 0.16922 + outer loop + vertex -877.264 431.857 65.3561 + vertex -878.472 431.387 59.4165 + vertex -879.454 424.634 65.3691 + endloop + endfacet + facet normal -0.944103 0.286575 0.162927 + outer loop + vertex -878.329 424.523 72.0866 + vertex -877.264 431.857 65.3561 + vertex -879.454 424.634 65.3691 + endloop + endfacet + facet normal -0.946546 0.27824 0.163198 + outer loop + vertex -878.329 424.523 72.0866 + vertex -879.454 424.634 65.3691 + vertex -880.399 417.486 72.0769 + endloop + endfacet + facet normal -0.947712 0.278594 0.155649 + outer loop + vertex -879.317 417.228 79.1288 + vertex -878.329 424.523 72.0866 + vertex -880.399 417.486 72.0769 + endloop + endfacet + facet normal -0.95117 0.266499 0.155737 + outer loop + vertex -879.317 417.228 79.1288 + vertex -880.399 417.486 72.0769 + vertex -881.255 410.317 79.1198 + endloop + endfacet + facet normal -0.952379 0.266849 0.147536 + outer loop + vertex -880.169 410.212 86.3176 + vertex -879.317 417.228 79.1288 + vertex -881.255 410.317 79.1198 + endloop + endfacet + facet normal -0.956455 0.251615 0.147929 + outer loop + vertex -880.169 410.212 86.3176 + vertex -881.255 410.317 79.1198 + vertex -881.961 403.4 86.3167 + endloop + endfacet + facet normal -0.957653 0.251932 0.139396 + outer loop + vertex -880.862 403.523 93.6466 + vertex -880.169 410.212 86.3176 + vertex -881.961 403.4 86.3167 + endloop + endfacet + facet normal -0.961894 0.234669 0.140321 + outer loop + vertex -880.862 403.523 93.6466 + vertex -881.961 403.4 86.3167 + vertex -882.506 396.782 93.6497 + endloop + endfacet + facet normal -0.963095 0.234957 0.131309 + outer loop + vertex -881.417 397.061 101.139 + vertex -880.862 403.523 93.6466 + vertex -882.506 396.782 93.6497 + endloop + endfacet + facet normal -0.967303 0.216187 0.132622 + outer loop + vertex -881.417 397.061 101.139 + vertex -882.506 396.782 93.6497 + vertex -882.916 390.353 101.141 + endloop + endfacet + facet normal -0.968616 0.216479 0.122149 + outer loop + vertex -881.877 390.692 108.775 + vertex -881.417 397.061 101.139 + vertex -882.916 390.353 101.141 + endloop + endfacet + facet normal -0.972834 0.195718 0.123644 + outer loop + vertex -881.877 390.692 108.775 + vertex -882.916 390.353 101.141 + vertex -883.227 383.981 108.776 + endloop + endfacet + facet normal -0.974259 0.196004 0.111363 + outer loop + vertex -882.272 384.331 116.513 + vertex -881.877 390.692 108.775 + vertex -883.227 383.981 108.776 + endloop + endfacet + facet normal -0.978469 0.172753 0.112935 + outer loop + vertex -882.272 384.331 116.513 + vertex -883.227 383.981 108.776 + vertex -883.463 377.585 116.514 + endloop + endfacet + facet normal -0.979934 0.173012 0.0989788 + outer loop + vertex -882.612 377.94 124.32 + vertex -882.272 384.331 116.513 + vertex -883.463 377.585 116.514 + endloop + endfacet + facet normal -0.984014 0.146953 0.100609 + outer loop + vertex -882.612 377.94 124.32 + vertex -883.463 377.585 116.514 + vertex -883.627 371.142 124.32 + endloop + endfacet + facet normal -0.985431 0.147164 0.0852518 + outer loop + vertex -882.895 371.497 132.177 + vertex -882.612 377.94 124.32 + vertex -883.627 371.142 124.32 + endloop + endfacet + facet normal -0.989138 0.118556 0.0868901 + outer loop + vertex -882.895 371.497 132.177 + vertex -883.627 371.142 124.32 + vertex -883.715 364.654 132.177 + endloop + endfacet + facet normal -0.990412 0.118709 0.070649 + outer loop + vertex -883.112 364.993 140.065 + vertex -882.895 371.497 132.177 + vertex -883.715 364.654 132.177 + endloop + endfacet + facet normal -0.993587 0.0869707 0.0722539 + outer loop + vertex -883.112 364.993 140.065 + vertex -883.715 364.654 132.177 + vertex -883.711 358.142 140.065 + endloop + endfacet + facet normal -0.994665 0.087065 0.0553317 + outer loop + vertex -883.246 358.442 147.952 + vertex -883.112 364.993 140.065 + vertex -883.711 358.142 140.065 + endloop + endfacet + facet normal -0.997113 0.0503183 0.0568736 + outer loop + vertex -883.246 358.442 147.952 + vertex -883.711 358.142 140.065 + vertex -883.59 351.633 147.951 + endloop + endfacet + facet normal -0.997955 0.0503616 0.0393696 + outer loop + vertex -883.268 351.872 155.804 + vertex -883.246 358.442 147.952 + vertex -883.59 351.633 147.951 + endloop + endfacet + facet normal -0.999143 0.00734089 0.0407303 + outer loop + vertex -883.268 351.872 155.804 + vertex -883.59 351.633 147.951 + vertex -883.317 345.133 155.805 + endloop + endfacet + facet normal -0.997916 0.0508294 0.039761 + outer loop + vertex -882.922 358.656 155.804 + vertex -883.246 358.442 147.952 + vertex -883.268 351.872 155.804 + endloop + endfacet + facet normal -0.99847 0.0508566 0.02169 + outer loop + vertex -883.091 352.017 163.624 + vertex -882.922 358.656 155.804 + vertex -883.268 351.872 155.804 + endloop + endfacet + facet normal -0.99972 0.00727895 0.0225252 + outer loop + vertex -883.091 352.017 163.624 + vertex -883.268 351.872 155.804 + vertex -883.14 345.292 163.625 + endloop + endfacet + facet normal -0.99848 0.0507139 0.0215686 + outer loop + vertex -882.747 358.786 163.624 + vertex -882.922 358.656 155.804 + vertex -883.091 352.017 163.624 + endloop + endfacet + facet normal -0.998707 0.0507247 0.00348513 + outer loop + vertex -883.061 352.068 171.448 + vertex -882.747 358.786 163.624 + vertex -883.091 352.017 163.624 + endloop + endfacet + facet normal -0.998709 0.0506732 0.00344074 + outer loop + vertex -882.718 358.831 171.448 + vertex -882.747 358.786 163.624 + vertex -883.061 352.068 171.448 + endloop + endfacet + facet normal -0.995974 0.0871659 0.0209052 + outer loop + vertex -882.747 358.786 163.624 + vertex -882.328 365.448 155.804 + vertex -882.922 358.656 155.804 + endloop + endfacet + facet normal -0.995456 0.0871201 0.0384277 + outer loop + vertex -882.328 365.448 155.804 + vertex -882.648 365.257 147.951 + vertex -882.922 358.656 155.804 + endloop + endfacet + facet normal -0.992195 0.118919 0.0375236 + outer loop + vertex -882.328 365.448 155.804 + vertex -881.837 372.022 147.951 + vertex -882.648 365.257 147.951 + endloop + endfacet + facet normal -0.991433 0.118827 0.0542302 + outer loop + vertex -881.837 372.022 147.951 + vertex -882.296 371.791 140.065 + vertex -882.648 365.257 147.951 + endloop + endfacet + facet normal -0.991419 0.118911 0.0543006 + outer loop + vertex -882.648 365.257 147.951 + vertex -882.296 371.791 140.065 + vertex -883.112 364.993 140.065 + endloop + endfacet + facet normal -0.987643 0.147423 0.0531722 + outer loop + vertex -881.837 372.022 147.951 + vertex -881.297 378.488 140.065 + vertex -882.296 371.791 140.065 + endloop + endfacet + facet normal -0.986656 0.147276 0.0694258 + outer loop + vertex -881.297 378.488 140.065 + vertex -881.888 378.242 132.177 + vertex -882.296 371.791 140.065 + endloop + endfacet + facet normal -0.986669 0.147213 0.069374 + outer loop + vertex -882.296 371.791 140.065 + vertex -881.888 378.242 132.177 + vertex -882.895 371.497 132.177 + endloop + endfacet + facet normal -0.982517 0.173188 0.0683071 + outer loop + vertex -881.297 378.488 140.065 + vertex -880.721 384.865 132.176 + vertex -881.888 378.242 132.177 + endloop + endfacet + facet normal -0.981361 0.172985 0.0837022 + outer loop + vertex -880.721 384.865 132.176 + vertex -881.434 384.621 124.32 + vertex -881.888 378.242 132.177 + endloop + endfacet + facet normal -0.981342 0.173063 0.083767 + outer loop + vertex -881.888 378.242 132.177 + vertex -881.434 384.621 124.32 + vertex -882.612 377.94 124.32 + endloop + endfacet + facet normal -0.977123 0.195979 0.0826033 + outer loop + vertex -880.721 384.865 132.176 + vertex -880.116 391.193 124.319 + vertex -881.434 384.621 124.32 + endloop + endfacet + facet normal -0.975825 0.195721 0.097258 + outer loop + vertex -880.116 391.193 124.319 + vertex -880.939 390.968 116.513 + vertex -881.434 384.621 124.32 + endloop + endfacet + facet normal -0.97574 0.196019 0.0975057 + outer loop + vertex -881.434 384.621 124.32 + vertex -880.939 390.968 116.513 + vertex -882.272 384.331 116.513 + endloop + endfacet + facet normal -0.971534 0.216485 0.0962086 + outer loop + vertex -880.116 391.193 124.319 + vertex -879.48 397.516 116.511 + vertex -880.939 390.968 116.513 + endloop + endfacet + facet normal -0.970178 0.216186 0.10963 + outer loop + vertex -879.48 397.516 116.511 + vertex -880.399 397.316 108.774 + vertex -880.939 390.968 116.513 + endloop + endfacet + facet normal -0.970082 0.216487 0.109884 + outer loop + vertex -880.939 390.968 116.513 + vertex -880.399 397.316 108.774 + vertex -881.877 390.692 108.775 + endloop + endfacet + facet normal -0.965867 0.235163 0.108628 + outer loop + vertex -879.48 397.516 116.511 + vertex -878.802 403.877 108.772 + vertex -880.399 397.316 108.774 + endloop + endfacet + facet normal -0.964526 0.234841 0.120584 + outer loop + vertex -878.802 403.877 108.772 + vertex -879.797 403.71 101.134 + vertex -880.399 397.316 108.774 + endloop + endfacet + facet normal -0.964476 0.234981 0.120705 + outer loop + vertex -880.399 397.316 108.774 + vertex -879.797 403.71 101.134 + vertex -881.417 397.061 101.139 + endloop + endfacet + facet normal -0.960198 0.252402 0.119634 + outer loop + vertex -878.802 403.877 108.772 + vertex -878.058 410.328 101.132 + vertex -879.797 403.71 101.134 + endloop + endfacet + facet normal -0.958945 0.252076 0.129934 + outer loop + vertex -878.058 410.328 101.132 + vertex -879.096 410.237 93.6444 + vertex -879.797 403.71 101.134 + endloop + endfacet + facet normal -0.95891 0.252165 0.130015 + outer loop + vertex -879.797 403.71 101.134 + vertex -879.096 410.237 93.6444 + vertex -880.862 403.523 93.6466 + endloop + endfacet + facet normal -0.954839 0.267573 0.129178 + outer loop + vertex -878.058 410.328 101.132 + vertex -877.216 416.947 93.6407 + vertex -879.096 410.237 93.6444 + endloop + endfacet + facet normal -0.953594 0.267229 0.138736 + outer loop + vertex -877.216 416.947 93.6407 + vertex -878.261 417.021 86.3171 + vertex -879.096 410.237 93.6444 + endloop + endfacet + facet normal -0.953624 0.267158 0.138667 + outer loop + vertex -879.096 410.237 93.6444 + vertex -878.261 417.021 86.3171 + vertex -880.169 410.212 86.3176 + endloop + endfacet + facet normal -0.949949 0.280101 0.138346 + outer loop + vertex -877.216 416.947 93.6407 + vertex -876.25 423.839 86.3206 + vertex -878.261 417.021 86.3171 + endloop + endfacet + facet normal -0.948649 0.279713 0.147735 + outer loop + vertex -876.25 423.839 86.3206 + vertex -877.278 424.15 79.1331 + vertex -878.261 417.021 86.3171 + endloop + endfacet + facet normal -0.948823 0.279334 0.147336 + outer loop + vertex -878.261 417.021 86.3171 + vertex -877.278 424.15 79.1331 + vertex -879.317 417.228 79.1288 + endloop + endfacet + facet normal -0.945776 0.289277 0.147739 + outer loop + vertex -876.25 423.839 86.3206 + vertex -875.166 431.054 79.1368 + vertex -877.278 424.15 79.1331 + endloop + endfacet + facet normal -0.944399 0.28885 0.157084 + outer loop + vertex -875.166 431.054 79.1368 + vertex -876.183 431.562 72.0869 + vertex -877.278 424.15 79.1331 + endloop + endfacet + facet normal -0.944821 0.287993 0.156117 + outer loop + vertex -877.278 424.15 79.1331 + vertex -876.183 431.562 72.0869 + vertex -878.329 424.523 72.0866 + endloop + endfacet + facet normal -0.942313 0.29549 0.157261 + outer loop + vertex -875.166 431.054 79.1368 + vertex -874.002 438.52 72.0815 + vertex -876.183 431.562 72.0869 + endloop + endfacet + facet normal -0.940919 0.29506 0.166168 + outer loop + vertex -874.002 438.52 72.0815 + vertex -875.034 439.021 65.3517 + vertex -876.183 431.562 72.0869 + endloop + endfacet + facet normal -0.941817 0.293341 0.164111 + outer loop + vertex -876.183 431.562 72.0869 + vertex -875.034 439.021 65.3517 + vertex -877.264 431.857 65.3561 + endloop + endfacet + facet normal -0.939322 0.300034 0.166293 + outer loop + vertex -874.002 438.52 72.0815 + vertex -872.816 445.965 65.346 + vertex -875.034 439.021 65.3517 + endloop + endfacet + facet normal -0.937959 0.299606 0.174553 + outer loop + vertex -872.816 445.965 65.346 + vertex -873.851 446.168 59.4409 + vertex -875.034 439.021 65.3517 + endloop + endfacet + facet normal -0.939577 0.296721 0.170741 + outer loop + vertex -875.034 439.021 65.3517 + vertex -873.851 446.168 59.4409 + vertex -876.145 438.968 59.329 + endloop + endfacet + facet normal -0.936436 0.304391 0.17445 + outer loop + vertex -872.816 445.965 65.346 + vertex -871.655 452.896 59.4858 + vertex -873.851 446.168 59.4409 + endloop + endfacet + facet normal -0.935073 0.303893 0.18245 + outer loop + vertex -871.655 452.896 59.4858 + vertex -872.663 452.184 55.5091 + vertex -873.851 446.168 59.4409 + endloop + endfacet + facet normal -0.933496 0.309507 0.181083 + outer loop + vertex -870.585 452.736 65.2763 + vertex -871.655 452.896 59.4858 + vertex -872.816 445.965 65.346 + endloop + endfacet + facet normal -0.93762 0.303208 0.170101 + outer loop + vertex -871.807 445.322 72.0554 + vertex -872.816 445.965 65.346 + vertex -874.002 438.52 72.0815 + endloop + endfacet + facet normal -0.941495 0.297107 0.159107 + outer loop + vertex -873.013 437.871 79.1478 + vertex -874.002 438.52 72.0815 + vertex -875.166 431.054 79.1368 + endloop + endfacet + facet normal -0.945419 0.290028 0.148547 + outer loop + vertex -874.166 430.626 86.3371 + vertex -875.166 431.054 79.1368 + vertex -876.25 423.839 86.3206 + endloop + endfacet + facet normal -0.949764 0.280521 0.138766 + outer loop + vertex -875.233 423.658 93.6483 + vertex -876.25 423.839 86.3206 + vertex -877.216 416.947 93.6407 + endloop + endfacet + facet normal -0.954733 0.267833 0.12942 + outer loop + vertex -876.203 416.94 101.132 + vertex -877.216 416.947 93.6407 + vertex -878.058 410.328 101.132 + endloop + endfacet + facet normal -0.960252 0.252258 0.119508 + outer loop + vertex -877.088 410.404 108.768 + vertex -878.058 410.328 101.132 + vertex -878.802 403.877 108.772 + endloop + endfacet + facet normal -0.965952 0.234911 0.108413 + outer loop + vertex -877.904 403.997 116.509 + vertex -878.802 403.877 108.772 + vertex -879.48 397.516 116.511 + endloop + endfacet + facet normal -0.971622 0.216196 0.0959676 + outer loop + vertex -878.674 397.672 124.317 + vertex -879.48 397.516 116.511 + vertex -880.116 391.193 124.319 + endloop + endfacet + facet normal -0.977195 0.19571 0.0823813 + outer loop + vertex -879.416 391.38 132.175 + vertex -880.116 391.193 124.319 + vertex -880.721 384.865 132.176 + endloop + endfacet + facet normal -0.982598 0.172842 0.0680218 + outer loop + vertex -880.139 385.068 140.064 + vertex -880.721 384.865 132.176 + vertex -881.297 378.488 140.065 + endloop + endfacet + facet normal -0.987656 0.147359 0.0531189 + outer loop + vertex -880.843 378.683 147.951 + vertex -881.297 378.488 140.065 + vertex -881.837 372.022 147.951 + endloop + endfacet + facet normal -0.992193 0.118933 0.0375355 + outer loop + vertex -881.52 372.187 155.804 + vertex -881.837 372.022 147.951 + vertex -882.328 365.448 155.804 + endloop + endfacet + facet normal -0.995976 0.0871481 0.02089 + outer loop + vertex -882.154 365.564 163.624 + vertex -882.328 365.448 155.804 + vertex -882.747 358.786 163.624 + endloop + endfacet + facet normal -0.995423 0.0873957 0.0386605 + outer loop + vertex -882.922 358.656 155.804 + vertex -882.648 365.257 147.951 + vertex -883.246 358.442 147.952 + endloop + endfacet + facet normal -0.997149 0.049943 0.0565644 + outer loop + vertex -883.59 351.633 147.951 + vertex -883.711 358.142 140.065 + vertex -884.054 351.299 140.065 + endloop + endfacet + facet normal -0.998266 0.00703965 0.0584452 + outer loop + vertex -883.59 351.633 147.951 + vertex -884.054 351.299 140.065 + vertex -883.638 344.87 147.952 + endloop + endfacet + facet normal -0.996013 0.0498865 0.073951 + outer loop + vertex -883.711 358.142 140.065 + vertex -884.316 357.759 132.177 + vertex -884.054 351.299 140.065 + endloop + endfacet + facet normal -0.996026 0.0497763 0.0738611 + outer loop + vertex -884.054 351.299 140.065 + vertex -884.316 357.759 132.177 + vertex -884.66 350.873 132.177 + endloop + endfacet + facet normal -0.997065 0.00660108 0.0762726 + outer loop + vertex -884.054 351.299 140.065 + vertex -884.66 350.873 132.177 + vertex -884.099 344.503 140.065 + endloop + endfacet + facet normal -0.994612 0.0497057 0.0909726 + outer loop + vertex -884.316 357.759 132.177 + vertex -885.058 357.295 124.32 + vertex -884.66 350.873 132.177 + endloop + endfacet + facet normal -0.994731 0.048746 0.0901942 + outer loop + vertex -884.66 350.873 132.177 + vertex -885.058 357.295 124.32 + vertex -885.398 350.357 124.32 + endloop + endfacet + facet normal -0.995639 0.00530198 0.093135 + outer loop + vertex -884.66 350.873 132.177 + vertex -885.398 350.357 124.32 + vertex -884.697 344.035 132.177 + endloop + endfacet + facet normal -0.99303 0.0486641 0.107346 + outer loop + vertex -885.058 357.295 124.32 + vertex -885.929 356.748 116.513 + vertex -885.398 350.357 124.32 + endloop + endfacet + facet normal -0.993136 0.0478875 0.106718 + outer loop + vertex -885.398 350.357 124.32 + vertex -885.929 356.748 116.513 + vertex -886.266 349.747 116.514 + endloop + endfacet + facet normal -0.993901 0.00476201 0.110169 + outer loop + vertex -885.398 350.357 124.32 + vertex -886.266 349.747 116.514 + vertex -885.431 343.468 124.32 + endloop + endfacet + facet normal -0.991284 0.0478004 0.122767 + outer loop + vertex -885.929 356.748 116.513 + vertex -886.918 356.105 108.776 + vertex -886.266 349.747 116.514 + endloop + endfacet + facet normal -0.991324 0.0475296 0.122548 + outer loop + vertex -886.266 349.747 116.514 + vertex -886.918 356.105 108.776 + vertex -887.257 349.033 108.774 + endloop + endfacet + facet normal -0.989397 0.0474347 0.137269 + outer loop + vertex -886.918 356.105 108.776 + vertex -888.013 355.359 101.137 + vertex -887.257 349.033 108.774 + endloop + endfacet + facet normal -0.987474 0.0842614 0.133399 + outer loop + vertex -886.918 356.105 108.776 + vertex -887.402 362.528 101.137 + vertex -888.013 355.359 101.137 + endloop + endfacet + facet normal -0.985755 0.0841146 0.145645 + outer loop + vertex -887.402 362.528 101.137 + vertex -888.571 361.802 93.6453 + vertex -888.013 355.359 101.137 + endloop + endfacet + facet normal -0.985818 0.0838117 0.145389 + outer loop + vertex -888.013 355.359 101.137 + vertex -888.571 361.802 93.6453 + vertex -889.188 354.546 93.6423 + endloop + endfacet + facet normal -0.987652 0.045876 0.149795 + outer loop + vertex -888.013 355.359 101.137 + vertex -889.188 354.546 93.6423 + vertex -888.345 348.207 101.138 + endloop + endfacet + facet normal -0.984179 0.0836679 0.156177 + outer loop + vertex -888.571 361.802 93.6453 + vertex -889.794 361.097 86.3123 + vertex -889.188 354.546 93.6423 + endloop + endfacet + facet normal -0.984312 0.0830706 0.155654 + outer loop + vertex -889.188 354.546 93.6423 + vertex -889.794 361.097 86.3123 + vertex -890.414 353.756 86.3089 + endloop + endfacet + facet normal -0.98609 0.0447341 0.16008 + outer loop + vertex -889.188 354.546 93.6423 + vertex -890.414 353.756 86.3089 + vertex -889.516 347.308 93.6429 + endloop + endfacet + facet normal -0.982681 0.0829281 0.165715 + outer loop + vertex -889.794 361.097 86.3123 + vertex -891.059 360.494 79.1134 + vertex -890.414 353.756 86.3089 + endloop + endfacet + facet normal -0.982681 0.0829259 0.165713 + outer loop + vertex -890.414 353.756 86.3089 + vertex -891.059 360.494 79.1134 + vertex -891.686 353.067 79.1102 + endloop + endfacet + facet normal -0.984495 0.044282 0.169733 + outer loop + vertex -890.414 353.756 86.3089 + vertex -891.686 353.067 79.1102 + vertex -890.744 346.429 86.3072 + endloop + endfacet + facet normal -0.981057 0.0827846 0.175138 + outer loop + vertex -891.059 360.494 79.1134 + vertex -892.366 359.931 72.0605 + vertex -891.686 353.067 79.1102 + endloop + endfacet + facet normal -0.980703 0.0841735 0.176456 + outer loop + vertex -891.686 353.067 79.1102 + vertex -892.366 359.931 72.0605 + vertex -893.013 352.409 72.053 + endloop + endfacet + facet normal -0.982571 0.0443541 0.180521 + outer loop + vertex -891.686 353.067 79.1102 + vertex -893.013 352.409 72.053 + vertex -892.021 345.649 79.109 + endloop + endfacet + facet normal -0.979046 0.084022 0.185496 + outer loop + vertex -892.366 359.931 72.0605 + vertex -893.71 359.109 65.3395 + vertex -893.013 352.409 72.053 + endloop + endfacet + facet normal -0.979181 0.0835227 0.185012 + outer loop + vertex -893.013 352.409 72.053 + vertex -893.71 359.109 65.3395 + vertex -894.361 351.467 65.3412 + endloop + endfacet + facet normal -0.980612 0.0452284 0.19067 + outer loop + vertex -893.013 352.409 72.053 + vertex -894.361 351.467 65.3412 + vertex -893.36 344.89 72.052 + endloop + endfacet + facet normal -0.977203 0.0833563 0.195258 + outer loop + vertex -893.71 359.109 65.3395 + vertex -895.028 357.572 59.3959 + vertex -894.361 351.467 65.3412 + endloop + endfacet + facet normal -0.978174 0.0798955 0.191814 + outer loop + vertex -894.361 351.467 65.3412 + vertex -895.028 357.572 59.3959 + vertex -895.661 349.811 59.4017 + endloop + endfacet + facet normal -0.978432 0.0448855 0.201634 + outer loop + vertex -894.361 351.467 65.3412 + vertex -895.661 349.811 59.4017 + vertex -894.712 343.844 65.3335 + endloop + endfacet + facet normal -0.975819 0.0797123 0.203526 + outer loop + vertex -895.028 357.572 59.3959 + vertex -896.196 354.983 54.8099 + vertex -895.661 349.811 59.4017 + endloop + endfacet + facet normal -0.975713 0.114129 0.186974 + outer loop + vertex -893.71 359.109 65.3395 + vertex -894.129 365.225 59.4178 + vertex -895.028 357.572 59.3959 + endloop + endfacet + facet normal -0.973737 0.113867 0.197158 + outer loop + vertex -894.129 365.225 59.4178 + vertex -895.348 362.74 54.8312 + vertex -895.028 357.572 59.3959 + endloop + endfacet + facet normal -0.974909 0.116692 0.189564 + outer loop + vertex -892.805 366.65 65.3492 + vertex -894.129 365.225 59.4178 + vertex -893.71 359.109 65.3395 + endloop + endfacet + facet normal -0.972563 0.144424 0.182379 + outer loop + vertex -892.805 366.65 65.3492 + vertex -893.01 372.74 59.434 + vertex -894.129 365.225 59.4178 + endloop + endfacet + facet normal -0.970711 0.144127 0.192218 + outer loop + vertex -893.01 372.74 59.434 + vertex -894.271 370.369 54.842 + vertex -894.129 365.225 59.4178 + endloop + endfacet + facet normal -0.971709 0.146922 0.184922 + outer loop + vertex -891.683 374.066 65.354 + vertex -893.01 372.74 59.434 + vertex -892.805 366.65 65.3492 + endloop + endfacet + facet normal -0.973169 0.147148 0.176889 + outer loop + vertex -891.474 367.375 72.0665 + vertex -891.683 374.066 65.354 + vertex -892.805 366.65 65.3492 + endloop + endfacet + facet normal -0.976556 0.116768 0.180842 + outer loop + vertex -891.474 367.375 72.0665 + vertex -892.805 366.65 65.3492 + vertex -892.366 359.931 72.0605 + endloop + endfacet + facet normal -0.97323 0.146964 0.176708 + outer loop + vertex -890.366 374.712 72.0685 + vertex -891.683 374.066 65.354 + vertex -891.474 367.375 72.0665 + endloop + endfacet + facet normal -0.974633 0.147178 0.168609 + outer loop + vertex -890.181 367.859 79.1189 + vertex -890.366 374.712 72.0685 + vertex -891.474 367.375 72.0665 + endloop + endfacet + facet normal -0.978296 0.116459 0.171388 + outer loop + vertex -890.181 367.859 79.1189 + vertex -891.474 367.375 72.0665 + vertex -891.059 360.494 79.1134 + endloop + endfacet + facet normal -0.974937 0.146218 0.167684 + outer loop + vertex -889.091 375.126 79.1197 + vertex -890.366 374.712 72.0685 + vertex -890.181 367.859 79.1189 + endloop + endfacet + facet normal -0.97632 0.146426 0.159247 + outer loop + vertex -888.928 368.386 86.3162 + vertex -889.091 375.126 79.1197 + vertex -890.181 367.859 79.1189 + endloop + endfacet + facet normal -0.9799 0.116313 0.162074 + outer loop + vertex -888.928 368.386 86.3162 + vertex -890.181 367.859 79.1189 + vertex -889.794 361.097 86.3123 + endloop + endfacet + facet normal -0.976522 0.145752 0.15862 + outer loop + vertex -887.855 375.574 86.3163 + vertex -889.091 375.126 79.1197 + vertex -888.928 368.386 86.3162 + endloop + endfacet + facet normal -0.977912 0.14596 0.149614 + outer loop + vertex -887.714 369.005 93.6481 + vertex -887.855 375.574 86.3163 + vertex -888.928 368.386 86.3162 + endloop + endfacet + facet normal -0.981373 0.116615 0.152667 + outer loop + vertex -887.714 369.005 93.6481 + vertex -888.928 368.386 86.3162 + vertex -888.571 361.802 93.6453 + endloop + endfacet + facet normal -0.977931 0.145894 0.149555 + outer loop + vertex -886.654 376.108 93.6485 + vertex -887.855 375.574 86.3163 + vertex -887.714 369.005 93.6481 + endloop + endfacet + facet normal -0.979397 0.146113 0.139397 + outer loop + vertex -886.552 369.645 101.139 + vertex -886.654 376.108 93.6485 + vertex -887.714 369.005 93.6481 + endloop + endfacet + facet normal -0.982843 0.11723 0.142399 + outer loop + vertex -886.552 369.645 101.139 + vertex -887.714 369.005 93.6481 + vertex -887.402 362.528 101.137 + endloop + endfacet + facet normal -0.984466 0.117428 0.130527 + outer loop + vertex -886.31 363.192 108.775 + vertex -886.552 369.645 101.139 + vertex -887.402 362.528 101.137 + endloop + endfacet + facet normal -0.984417 0.117642 0.130707 + outer loop + vertex -885.469 370.227 108.775 + vertex -886.552 369.645 101.139 + vertex -886.31 363.192 108.775 + endloop + endfacet + facet normal -0.986085 0.117843 0.117256 + outer loop + vertex -885.322 363.761 116.513 + vertex -885.469 370.227 108.775 + vertex -886.31 363.192 108.775 + endloop + endfacet + facet normal -0.989075 0.0855997 0.12001 + outer loop + vertex -885.322 363.761 116.513 + vertex -886.31 363.192 108.775 + vertex -885.929 356.748 116.513 + endloop + endfacet + facet normal -0.986071 0.117907 0.117309 + outer loop + vertex -884.489 370.723 116.513 + vertex -885.469 370.227 108.775 + vertex -885.322 363.761 116.513 + endloop + endfacet + facet normal -0.987696 0.118101 0.102514 + outer loop + vertex -884.454 364.244 124.32 + vertex -884.489 370.723 116.513 + vertex -885.322 363.761 116.513 + endloop + endfacet + facet normal -0.990751 0.0861534 0.104832 + outer loop + vertex -884.454 364.244 124.32 + vertex -885.322 363.761 116.513 + vertex -885.058 357.295 124.32 + endloop + endfacet + facet normal -0.987654 0.118306 0.102683 + outer loop + vertex -883.627 371.142 124.32 + vertex -884.489 370.723 116.513 + vertex -884.454 364.244 124.32 + endloop + endfacet + facet normal -0.982451 0.146857 0.114994 + outer loop + vertex -884.489 370.723 116.513 + vertex -884.432 377.162 108.776 + vertex -885.469 370.227 108.775 + endloop + endfacet + facet normal -0.98087 0.14662 0.12805 + outer loop + vertex -884.432 377.162 108.776 + vertex -885.504 376.662 101.14 + vertex -885.469 370.227 108.775 + endloop + endfacet + facet normal -0.9769 0.172764 0.125777 + outer loop + vertex -884.432 377.162 108.776 + vertex -884.284 383.56 101.141 + vertex -885.504 376.662 101.14 + endloop + endfacet + facet normal -0.975455 0.172507 0.136854 + outer loop + vertex -884.284 383.56 101.141 + vertex -885.417 383.096 93.6503 + vertex -885.504 376.662 101.14 + endloop + endfacet + facet normal -0.975394 0.172712 0.137031 + outer loop + vertex -885.504 376.662 101.14 + vertex -885.417 383.096 93.6503 + vertex -886.654 376.108 93.6485 + endloop + endfacet + facet normal -0.97404 0.17247 0.146631 + outer loop + vertex -885.417 383.096 93.6503 + vertex -886.599 382.657 86.3158 + vertex -886.654 376.108 93.6485 + endloop + endfacet + facet normal -0.969884 0.196036 0.14455 + outer loop + vertex -885.417 383.096 93.6503 + vertex -885.187 389.644 86.3131 + vertex -886.599 382.657 86.3158 + endloop + endfacet + facet normal -0.968654 0.195791 0.152887 + outer loop + vertex -885.187 389.644 86.3131 + vertex -886.374 389.396 79.1082 + vertex -886.599 382.657 86.3158 + endloop + endfacet + facet normal -0.968361 0.196623 0.153674 + outer loop + vertex -886.599 382.657 86.3158 + vertex -886.374 389.396 79.1082 + vertex -887.814 382.299 79.1154 + endloop + endfacet + facet normal -0.972629 0.172583 0.155589 + outer loop + vertex -886.599 382.657 86.3158 + vertex -887.814 382.299 79.1154 + vertex -887.855 375.574 86.3163 + endloop + endfacet + facet normal -0.967176 0.19639 0.161253 + outer loop + vertex -886.374 389.396 79.1082 + vertex -887.595 389.177 72.0529 + vertex -887.814 382.299 79.1154 + endloop + endfacet + facet normal -0.96678 0.197464 0.162311 + outer loop + vertex -887.814 382.299 79.1154 + vertex -887.595 389.177 72.0529 + vertex -889.065 381.973 72.0624 + endloop + endfacet + facet normal -0.971134 0.173013 0.164213 + outer loop + vertex -887.814 382.299 79.1154 + vertex -889.065 381.973 72.0624 + vertex -889.091 375.126 79.1197 + endloop + endfacet + facet normal -0.965701 0.197252 0.16886 + outer loop + vertex -887.595 389.177 72.0529 + vertex -888.85 388.781 65.3381 + vertex -889.065 381.973 72.0624 + endloop + endfacet + facet normal -0.965363 0.198132 0.169762 + outer loop + vertex -889.065 381.973 72.0624 + vertex -888.85 388.781 65.3381 + vertex -890.356 381.439 65.3406 + endloop + endfacet + facet normal -0.969537 0.173912 0.172487 + outer loop + vertex -889.065 381.973 72.0624 + vertex -890.356 381.439 65.3406 + vertex -890.366 374.712 72.0685 + endloop + endfacet + facet normal -0.964459 0.197948 0.17503 + outer loop + vertex -888.85 388.781 65.3381 + vertex -890.118 387.91 59.3336 + vertex -890.356 381.439 65.3406 + endloop + endfacet + facet normal -0.964478 0.197901 0.174978 + outer loop + vertex -890.356 381.439 65.3406 + vertex -890.118 387.91 59.3336 + vertex -891.68 380.246 59.3966 + endloop + endfacet + facet normal -0.967984 0.174469 0.180463 + outer loop + vertex -890.356 381.439 65.3406 + vertex -891.68 380.246 59.3966 + vertex -891.683 374.066 65.354 + endloop + endfacet + facet normal -0.963283 0.197712 0.181646 + outer loop + vertex -890.118 387.91 59.3336 + vertex -891.422 385.777 54.7428 + vertex -891.68 380.246 59.3966 + endloop + endfacet + facet normal -0.960969 0.217074 0.171518 + outer loop + vertex -888.85 388.781 65.3381 + vertex -888.421 395.317 59.4702 + vertex -890.118 387.91 59.3336 + endloop + endfacet + facet normal -0.960465 0.216903 0.174527 + outer loop + vertex -888.421 395.317 59.4702 + vertex -889.508 394.596 54.3865 + vertex -890.118 387.91 59.3336 + endloop + endfacet + facet normal -0.960681 0.217741 0.172283 + outer loop + vertex -887.207 396.017 65.3522 + vertex -888.421 395.317 59.4702 + vertex -888.85 388.781 65.3381 + endloop + endfacet + facet normal -0.957262 0.234267 0.169612 + outer loop + vertex -887.207 396.017 65.3522 + vertex -886.688 402.338 59.551 + vertex -888.421 395.317 59.4702 + endloop + endfacet + facet normal -0.956272 0.233955 0.175526 + outer loop + vertex -886.688 402.338 59.551 + vertex -887.771 400.916 55.5459 + vertex -888.421 395.317 59.4702 + endloop + endfacet + facet normal -0.956623 0.235698 0.171228 + outer loop + vertex -885.445 403.173 65.3462 + vertex -886.688 402.338 59.551 + vertex -887.207 396.017 65.3522 + endloop + endfacet + facet normal -0.957635 0.235942 0.165128 + outer loop + vertex -885.978 396.32 72.0494 + vertex -885.445 403.173 65.3462 + vertex -887.207 396.017 65.3522 + endloop + endfacet + facet normal -0.961657 0.217784 0.16669 + outer loop + vertex -885.978 396.32 72.0494 + vertex -887.207 396.017 65.3522 + vertex -887.595 389.177 72.0529 + endloop + endfacet + facet normal -0.957763 0.235641 0.16481 + outer loop + vertex -884.233 403.415 72.0445 + vertex -885.445 403.173 65.3462 + vertex -885.978 396.32 72.0494 + endloop + endfacet + facet normal -0.958876 0.23591 0.157807 + outer loop + vertex -884.791 396.425 79.1047 + vertex -884.233 403.415 72.0445 + vertex -885.978 396.32 72.0494 + endloop + endfacet + facet normal -0.963162 0.217024 0.158808 + outer loop + vertex -884.791 396.425 79.1047 + vertex -885.978 396.32 72.0494 + vertex -886.374 389.396 79.1082 + endloop + endfacet + facet normal -0.959156 0.235234 0.157116 + outer loop + vertex -883.081 403.393 79.1088 + vertex -884.233 403.415 72.0445 + vertex -884.791 396.425 79.1047 + endloop + endfacet + facet normal -0.960274 0.235513 0.149689 + outer loop + vertex -883.636 396.553 86.3141 + vertex -883.081 403.393 79.1088 + vertex -884.791 396.425 79.1047 + endloop + endfacet + facet normal -0.964572 0.216533 0.150714 + outer loop + vertex -883.636 396.553 86.3141 + vertex -884.791 396.425 79.1047 + vertex -885.187 389.644 86.3131 + endloop + endfacet + facet normal -0.965758 0.2168 0.142512 + outer loop + vertex -884.029 389.98 93.6492 + vertex -883.636 396.553 86.3141 + vertex -885.187 389.644 86.3131 + endloop + endfacet + facet normal -0.965944 0.216282 0.142038 + outer loop + vertex -882.506 396.782 93.6497 + vertex -883.636 396.553 86.3141 + vertex -884.029 389.98 93.6492 + endloop + endfacet + facet normal -0.960523 0.234886 0.149075 + outer loop + vertex -881.961 403.4 86.3167 + vertex -883.081 403.393 79.1088 + vertex -883.636 396.553 86.3141 + endloop + endfacet + facet normal -0.95497 0.25208 0.156486 + outer loop + vertex -883.081 403.393 79.1088 + vertex -882.371 410.463 72.054 + vertex -884.233 403.415 72.0445 + endloop + endfacet + facet normal -0.953867 0.251779 0.16354 + outer loop + vertex -882.371 410.463 72.054 + vertex -883.56 410.327 65.3302 + vertex -884.233 403.415 72.0445 + endloop + endfacet + facet normal -0.950202 0.265847 0.162606 + outer loop + vertex -882.371 410.463 72.054 + vertex -881.558 417.473 65.3467 + vertex -883.56 410.327 65.3302 + endloop + endfacet + facet normal -0.949192 0.26555 0.168871 + outer loop + vertex -881.558 417.473 65.3467 + vertex -882.823 416.729 59.4071 + vertex -883.56 410.327 65.3302 + endloop + endfacet + facet normal -0.949896 0.264085 0.167201 + outer loop + vertex -883.56 410.327 65.3302 + vertex -882.823 416.729 59.4071 + vertex -884.835 409.462 59.4503 + endloop + endfacet + facet normal -0.952862 0.251512 0.169695 + outer loop + vertex -883.56 410.327 65.3302 + vertex -884.835 409.462 59.4503 + vertex -885.445 403.173 65.3462 + endloop + endfacet + facet normal -0.948918 0.263849 0.173027 + outer loop + vertex -882.823 416.729 59.4071 + vertex -884.157 414.912 54.859 + vertex -884.835 409.462 59.4503 + endloop + endfacet + facet normal -0.946566 0.275898 0.167015 + outer loop + vertex -881.558 417.473 65.3467 + vertex -880.698 424.009 59.4233 + vertex -882.823 416.729 59.4071 + endloop + endfacet + facet normal -0.945668 0.275624 0.172461 + outer loop + vertex -880.698 424.009 59.4233 + vertex -882.029 422.307 54.8427 + vertex -882.823 416.729 59.4071 + endloop + endfacet + facet normal -0.945862 0.277303 0.168668 + outer loop + vertex -879.454 424.634 65.3691 + vertex -880.698 424.009 59.4233 + vertex -881.558 417.473 65.3467 + endloop + endfacet + facet normal -0.950012 0.266252 0.163053 + outer loop + vertex -880.399 417.486 72.0769 + vertex -881.558 417.473 65.3467 + vertex -882.371 410.463 72.054 + endloop + endfacet + facet normal -0.955108 0.251763 0.156155 + outer loop + vertex -881.255 410.317 79.1198 + vertex -882.371 410.463 72.054 + vertex -883.081 403.393 79.1088 + endloop + endfacet + facet normal -0.953873 0.251765 0.163525 + outer loop + vertex -884.233 403.415 72.0445 + vertex -883.56 410.327 65.3302 + vertex -885.445 403.173 65.3462 + endloop + endfacet + facet normal -0.953389 0.250369 0.168421 + outer loop + vertex -885.445 403.173 65.3462 + vertex -884.835 409.462 59.4503 + vertex -886.688 402.338 59.551 + endloop + endfacet + facet normal -0.952415 0.250195 0.174091 + outer loop + vertex -884.835 409.462 59.4503 + vertex -886.164 407.479 55.0307 + vertex -886.688 402.338 59.551 + endloop + endfacet + facet normal -0.961586 0.217958 0.166871 + outer loop + vertex -887.595 389.177 72.0529 + vertex -887.207 396.017 65.3522 + vertex -888.85 388.781 65.3381 + endloop + endfacet + facet normal -0.962767 0.218032 0.159819 + outer loop + vertex -886.374 389.396 79.1082 + vertex -885.978 396.32 72.0494 + vertex -887.595 389.177 72.0529 + endloop + endfacet + facet normal -0.964293 0.217275 0.151428 + outer loop + vertex -885.187 389.644 86.3131 + vertex -884.791 396.425 79.1047 + vertex -886.374 389.396 79.1082 + endloop + endfacet + facet normal -0.97003 0.195603 0.144159 + outer loop + vertex -884.029 389.98 93.6492 + vertex -885.187 389.644 86.3131 + vertex -885.417 383.096 93.6503 + endloop + endfacet + facet normal -0.971325 0.195862 0.134783 + outer loop + vertex -884.284 383.56 101.141 + vertex -884.029 389.98 93.6492 + vertex -885.417 383.096 93.6503 + endloop + endfacet + facet normal -0.971387 0.195667 0.134614 + outer loop + vertex -882.916 390.353 101.141 + vertex -884.029 389.98 93.6492 + vertex -884.284 383.56 101.141 + endloop + endfacet + facet normal -0.976928 0.172663 0.125692 + outer loop + vertex -883.227 383.981 108.776 + vertex -884.284 383.56 101.141 + vertex -884.432 377.162 108.776 + endloop + endfacet + facet normal -0.982446 0.146874 0.115008 + outer loop + vertex -883.463 377.585 116.514 + vertex -884.432 377.162 108.776 + vertex -884.489 370.723 116.513 + endloop + endfacet + facet normal -0.980885 0.146564 0.128002 + outer loop + vertex -885.469 370.227 108.775 + vertex -885.504 376.662 101.14 + vertex -886.552 369.645 101.139 + endloop + endfacet + facet normal -0.979338 0.146331 0.139584 + outer loop + vertex -885.504 376.662 101.14 + vertex -886.654 376.108 93.6485 + vertex -886.552 369.645 101.139 + endloop + endfacet + facet normal -0.973932 0.172813 0.146939 + outer loop + vertex -886.654 376.108 93.6485 + vertex -886.599 382.657 86.3158 + vertex -887.855 375.574 86.3163 + endloop + endfacet + facet normal -0.972415 0.173236 0.1562 + outer loop + vertex -887.855 375.574 86.3163 + vertex -887.814 382.299 79.1154 + vertex -889.091 375.126 79.1197 + endloop + endfacet + facet normal -0.970752 0.174124 0.165293 + outer loop + vertex -889.091 375.126 79.1197 + vertex -889.065 381.973 72.0624 + vertex -890.366 374.712 72.0685 + endloop + endfacet + facet normal -0.96926 0.174686 0.173261 + outer loop + vertex -890.366 374.712 72.0685 + vertex -890.356 381.439 65.3406 + vertex -891.683 374.066 65.354 + endloop + endfacet + facet normal -0.968688 0.172575 0.178498 + outer loop + vertex -891.683 374.066 65.354 + vertex -891.68 380.246 59.3966 + vertex -893.01 372.74 59.434 + endloop + endfacet + facet normal -0.967149 0.172344 0.186867 + outer loop + vertex -891.68 380.246 59.3966 + vertex -892.968 377.953 54.8456 + vertex -893.01 372.74 59.434 + endloop + endfacet + facet normal -0.976517 0.116896 0.180967 + outer loop + vertex -892.366 359.931 72.0605 + vertex -892.805 366.65 65.3492 + vertex -893.71 359.109 65.3395 + endloop + endfacet + facet normal -0.97815 0.116966 0.171875 + outer loop + vertex -891.059 360.494 79.1134 + vertex -891.474 367.375 72.0665 + vertex -892.366 359.931 72.0605 + endloop + endfacet + facet normal -0.979809 0.116646 0.162382 + outer loop + vertex -889.794 361.097 86.3123 + vertex -890.181 367.859 79.1189 + vertex -891.059 360.494 79.1134 + endloop + endfacet + facet normal -0.981404 0.116496 0.152562 + outer loop + vertex -888.571 361.802 93.6453 + vertex -888.928 368.386 86.3162 + vertex -889.794 361.097 86.3123 + endloop + endfacet + facet normal -0.982946 0.116806 0.142037 + outer loop + vertex -887.402 362.528 101.137 + vertex -887.714 369.005 93.6481 + vertex -888.571 361.802 93.6453 + endloop + endfacet + facet normal -0.987382 0.0847282 0.133786 + outer loop + vertex -886.31 363.192 108.775 + vertex -887.402 362.528 101.137 + vertex -886.918 356.105 108.776 + endloop + endfacet + facet normal -0.989209 0.084883 0.11942 + outer loop + vertex -885.929 356.748 116.513 + vertex -886.31 363.192 108.775 + vertex -886.918 356.105 108.776 + endloop + endfacet + facet normal -0.990821 0.0857508 0.104501 + outer loop + vertex -885.058 357.295 124.32 + vertex -885.322 363.761 116.513 + vertex -885.929 356.748 116.513 + endloop + endfacet + facet normal -0.992323 0.0862902 0.0885972 + outer loop + vertex -884.316 357.759 132.177 + vertex -884.454 364.244 124.32 + vertex -885.058 357.295 124.32 + endloop + endfacet + facet normal -0.992285 0.0865268 0.0887919 + outer loop + vertex -883.715 364.654 132.177 + vertex -884.454 364.244 124.32 + vertex -884.316 357.759 132.177 + endloop + endfacet + facet normal -0.99463 0.087327 0.05555 + outer loop + vertex -882.648 365.257 147.951 + vertex -883.112 364.993 140.065 + vertex -883.246 358.442 147.952 + endloop + endfacet + facet normal -0.993635 0.0866445 0.0719845 + outer loop + vertex -883.711 358.142 140.065 + vertex -883.715 364.654 132.177 + vertex -884.316 357.759 132.177 + endloop + endfacet + facet normal -0.990398 0.118789 0.070715 + outer loop + vertex -882.296 371.791 140.065 + vertex -882.895 371.497 132.177 + vertex -883.112 364.993 140.065 + endloop + endfacet + facet normal -0.989152 0.118485 0.0868313 + outer loop + vertex -883.715 364.654 132.177 + vertex -883.627 371.142 124.32 + vertex -884.454 364.244 124.32 + endloop + endfacet + facet normal -0.98546 0.147034 0.0851439 + outer loop + vertex -881.888 378.242 132.177 + vertex -882.612 377.94 124.32 + vertex -882.895 371.497 132.177 + endloop + endfacet + facet normal -0.983978 0.147104 0.100734 + outer loop + vertex -883.627 371.142 124.32 + vertex -883.463 377.585 116.514 + vertex -884.489 370.723 116.513 + endloop + endfacet + facet normal -0.979983 0.172823 0.0988226 + outer loop + vertex -881.434 384.621 124.32 + vertex -882.272 384.331 116.513 + vertex -882.612 377.94 124.32 + endloop + endfacet + facet normal -0.978422 0.172927 0.11308 + outer loop + vertex -883.463 377.585 116.514 + vertex -883.227 383.981 108.776 + vertex -884.432 377.162 108.776 + endloop + endfacet + facet normal -0.974338 0.195738 0.111141 + outer loop + vertex -880.939 390.968 116.513 + vertex -881.877 390.692 108.775 + vertex -882.272 384.331 116.513 + endloop + endfacet + facet normal -0.972765 0.195944 0.123835 + outer loop + vertex -883.227 383.981 108.776 + vertex -882.916 390.353 101.141 + vertex -884.284 383.56 101.141 + endloop + endfacet + facet normal -0.968713 0.216184 0.121898 + outer loop + vertex -880.399 397.316 108.774 + vertex -881.417 397.061 101.139 + vertex -881.877 390.692 108.775 + endloop + endfacet + facet normal -0.967175 0.216558 0.132947 + outer loop + vertex -882.916 390.353 101.141 + vertex -882.506 396.782 93.6497 + vertex -884.029 389.98 93.6492 + endloop + endfacet + facet normal -0.963198 0.234678 0.13106 + outer loop + vertex -879.797 403.71 101.134 + vertex -880.862 403.523 93.6466 + vertex -881.417 397.061 101.139 + endloop + endfacet + facet normal -0.961701 0.235177 0.140794 + outer loop + vertex -882.506 396.782 93.6497 + vertex -881.961 403.4 86.3167 + vertex -883.636 396.553 86.3141 + endloop + endfacet + facet normal -0.957687 0.251847 0.139315 + outer loop + vertex -879.096 410.237 93.6444 + vertex -880.169 410.212 86.3176 + vertex -880.862 403.523 93.6466 + endloop + endfacet + facet normal -0.956261 0.25208 0.148395 + outer loop + vertex -881.961 403.4 86.3167 + vertex -881.255 410.317 79.1198 + vertex -883.081 403.393 79.1088 + endloop + endfacet + facet normal -0.952394 0.266814 0.1475 + outer loop + vertex -878.261 417.021 86.3171 + vertex -879.317 417.228 79.1288 + vertex -880.169 410.212 86.3176 + endloop + endfacet + facet normal -0.951129 0.26659 0.155834 + outer loop + vertex -881.255 410.317 79.1198 + vertex -880.399 417.486 72.0769 + vertex -882.371 410.463 72.054 + endloop + endfacet + facet normal -0.947542 0.278952 0.156044 + outer loop + vertex -877.278 424.15 79.1331 + vertex -878.329 424.523 72.0866 + vertex -879.317 417.228 79.1288 + endloop + endfacet + facet normal -0.946852 0.277613 0.162487 + outer loop + vertex -880.399 417.486 72.0769 + vertex -879.454 424.634 65.3691 + vertex -881.558 417.473 65.3467 + endloop + endfacet + facet normal -0.943576 0.287614 0.164143 + outer loop + vertex -876.183 431.562 72.0869 + vertex -877.264 431.857 65.3561 + vertex -878.329 424.523 72.0866 + endloop + endfacet + facet normal -0.943839 0.284829 0.167453 + outer loop + vertex -879.454 424.634 65.3691 + vertex -878.472 431.387 59.4165 + vertex -880.698 424.009 59.4233 + endloop + endfacet + facet normal -0.942955 0.284567 0.172794 + outer loop + vertex -878.472 431.387 59.4165 + vertex -879.807 429.762 54.812 + vertex -880.698 424.009 59.4233 + endloop + endfacet + facet normal -0.940701 0.292998 0.170981 + outer loop + vertex -875.034 439.021 65.3517 + vertex -876.145 438.968 59.329 + vertex -877.264 431.857 65.3561 + endloop + endfacet + facet normal -0.938597 0.296315 0.176729 + outer loop + vertex -873.851 446.168 59.4409 + vertex -874.806 446.187 54.3378 + vertex -876.145 438.968 59.329 + endloop + endfacet + facet normal -0.939208 0.290156 0.183569 + outer loop + vertex -876.561 442.205 51.6942 + vertex -877.909 438.731 50.2841 + vertex -878.877 434.596 51.8702 + endloop + endfacet + facet normal -0.941156 0.288025 0.176825 + outer loop + vertex -878.877 434.596 51.8702 + vertex -877.909 438.731 50.2841 + vertex -880.113 431.452 50.4127 + endloop + endfacet + facet normal -0.93873 0.287524 0.190041 + outer loop + vertex -880.113 431.452 50.4127 + vertex -877.909 438.731 50.2841 + vertex -879.216 434.829 49.7364 + endloop + endfacet + facet normal -0.939421 0.291662 0.180062 + outer loop + vertex -876.561 442.205 51.6942 + vertex -875.572 446.301 50.2163 + vertex -877.909 438.731 50.2841 + endloop + endfacet + facet normal -0.936521 0.290907 0.195708 + outer loop + vertex -877.909 438.731 50.2841 + vertex -875.572 446.301 50.2163 + vertex -876.722 442.947 49.7004 + endloop + endfacet + facet normal -0.936663 0.294451 0.189636 + outer loop + vertex -874.526 448.898 51.3499 + vertex -875.572 446.301 50.2163 + vertex -876.561 442.205 51.6942 + endloop + endfacet + facet normal -0.941994 0.288785 0.171027 + outer loop + vertex -878.472 431.387 59.4165 + vertex -877.463 437.463 54.7186 + vertex -879.807 429.762 54.812 + endloop + endfacet + facet normal -0.94093 0.285564 0.181942 + outer loop + vertex -878.877 434.596 51.8702 + vertex -880.113 431.452 50.4127 + vertex -881.145 427.101 51.9018 + endloop + endfacet + facet normal -0.942638 0.283834 0.175702 + outer loop + vertex -881.145 427.101 51.9018 + vertex -880.113 431.452 50.4127 + vertex -882.356 424.087 50.2745 + endloop + endfacet + facet normal -0.940422 0.282917 0.188588 + outer loop + vertex -882.356 424.087 50.2745 + vertex -880.113 431.452 50.4127 + vertex -880.769 429.785 49.6439 + endloop + endfacet + facet normal -0.944243 0.282208 0.169602 + outer loop + vertex -880.698 424.009 59.4233 + vertex -879.807 429.762 54.812 + vertex -882.029 422.307 54.8427 + endloop + endfacet + facet normal -0.942355 0.278174 0.185977 + outer loop + vertex -881.145 427.101 51.9018 + vertex -882.356 424.087 50.2745 + vertex -883.346 419.637 51.9162 + endloop + endfacet + facet normal -0.945024 0.275273 0.176505 + outer loop + vertex -883.346 419.637 51.9162 + vertex -882.356 424.087 50.2745 + vertex -884.534 416.561 50.351 + endloop + endfacet + facet normal -0.936694 0.273293 0.218896 + outer loop + vertex -884.534 416.561 50.351 + vertex -882.356 424.087 50.2745 + vertex -883.665 420.001 49.777 + endloop + endfacet + facet normal -0.947104 0.272899 0.168881 + outer loop + vertex -882.823 416.729 59.4071 + vertex -882.029 422.307 54.8427 + vertex -884.157 414.912 54.859 + endloop + endfacet + facet normal -0.944353 0.267238 0.191784 + outer loop + vertex -883.346 419.637 51.9162 + vertex -884.534 416.561 50.351 + vertex -885.48 412.043 51.9904 + endloop + endfacet + facet normal -0.94779 0.263528 0.179576 + outer loop + vertex -885.48 412.043 51.9904 + vertex -884.534 416.561 50.351 + vertex -886.567 409.25 50.35 + endloop + endfacet + facet normal -0.950571 0.260564 0.168884 + outer loop + vertex -884.835 409.462 59.4503 + vertex -884.157 414.912 54.859 + vertex -886.164 407.479 55.0307 + endloop + endfacet + facet normal -0.94718 0.253045 0.197022 + outer loop + vertex -885.48 412.043 51.9904 + vertex -886.567 409.25 50.35 + vertex -887.718 403.475 52.232 + endloop + endfacet + facet normal -0.950389 0.24986 0.185288 + outer loop + vertex -887.718 403.475 52.232 + vertex -886.567 409.25 50.35 + vertex -888.536 401.808 50.2862 + endloop + endfacet + facet normal -0.953943 0.246988 0.170266 + outer loop + vertex -886.688 402.338 59.551 + vertex -886.164 407.479 55.0307 + vertex -887.771 400.916 55.5459 + endloop + endfacet + facet normal -0.957537 0.231511 0.171829 + outer loop + vertex -888.421 395.317 59.4702 + vertex -887.771 400.916 55.5459 + vertex -889.508 394.596 54.3865 + endloop + endfacet + facet normal -0.951361 0.237323 0.196442 + outer loop + vertex -887.718 403.475 52.232 + vertex -888.536 401.808 50.2862 + vertex -889.499 397.056 51.3625 + endloop + endfacet + facet normal -0.955102 0.234578 0.180978 + outer loop + vertex -889.499 397.056 51.3625 + vertex -888.536 401.808 50.2862 + vertex -890.32 394.556 50.2727 + endloop + endfacet + facet normal -0.952935 0.223429 0.204925 + outer loop + vertex -889.499 397.056 51.3625 + vertex -890.32 394.556 50.2727 + vertex -891.001 390.289 51.7585 + endloop + endfacet + facet normal -0.958963 0.2167 0.182839 + outer loop + vertex -891.001 390.289 51.7585 + vertex -890.32 394.556 50.2727 + vertex -892.06 386.834 50.2956 + endloop + endfacet + facet normal -0.961086 0.215611 0.172704 + outer loop + vertex -890.118 387.91 59.3336 + vertex -889.508 394.596 54.3865 + vertex -891.422 385.777 54.7428 + endloop + endfacet + facet normal -0.956316 0.205106 0.208307 + outer loop + vertex -891.001 390.289 51.7585 + vertex -892.06 386.834 50.2956 + vertex -892.664 382.387 51.9033 + endloop + endfacet + facet normal -0.964188 0.195614 0.179099 + outer loop + vertex -892.664 382.387 51.9033 + vertex -892.06 386.834 50.2956 + vertex -893.77 378.351 50.3593 + endloop + endfacet + facet normal -0.965297 0.193 0.175935 + outer loop + vertex -891.68 380.246 59.3966 + vertex -891.422 385.777 54.7428 + vertex -892.968 377.953 54.8456 + endloop + endfacet + facet normal -0.960116 0.181723 0.212496 + outer loop + vertex -892.664 382.387 51.9033 + vertex -893.77 378.351 50.3593 + vertex -894.14 374.558 51.9278 + endloop + endfacet + facet normal -0.968127 0.170502 0.183466 + outer loop + vertex -894.14 374.558 51.9278 + vertex -893.77 378.351 50.3593 + vertex -895.17 370.46 50.3037 + endloop + endfacet + facet normal -0.969411 0.166562 0.180278 + outer loop + vertex -893.01 372.74 59.434 + vertex -892.968 377.953 54.8456 + vertex -894.271 370.369 54.842 + endloop + endfacet + facet normal -0.962892 0.154079 0.221583 + outer loop + vertex -894.14 374.558 51.9278 + vertex -895.17 370.46 50.3037 + vertex -895.371 366.912 51.8971 + endloop + endfacet + facet normal -0.970883 0.141746 0.193118 + outer loop + vertex -895.371 366.912 51.8971 + vertex -895.17 370.46 50.3037 + vertex -896.277 362.895 50.2879 + endloop + endfacet + facet normal -0.973235 0.137123 0.184423 + outer loop + vertex -894.129 365.225 59.4178 + vertex -894.271 370.369 54.842 + vertex -895.348 362.74 54.8312 + endloop + endfacet + facet normal -0.964607 0.124592 0.2324 + outer loop + vertex -895.371 366.912 51.8971 + vertex -896.277 362.895 50.2879 + vertex -896.37 359.272 51.8465 + endloop + endfacet + facet normal -0.973297 0.111224 0.200804 + outer loop + vertex -896.37 359.272 51.8465 + vertex -896.277 362.895 50.2879 + vertex -897.129 355.471 50.2702 + endloop + endfacet + facet normal -0.976278 0.106217 0.188677 + outer loop + vertex -895.028 357.572 59.3959 + vertex -895.348 362.74 54.8312 + vertex -896.196 354.983 54.8099 + endloop + endfacet + facet normal -0.965451 0.0917863 0.243885 + outer loop + vertex -896.37 359.272 51.8465 + vertex -897.129 355.471 50.2702 + vertex -897.108 351.474 51.8579 + endloop + endfacet + facet normal -0.975159 0.0773146 0.207574 + outer loop + vertex -897.108 351.474 51.8579 + vertex -897.129 355.471 50.2702 + vertex -897.757 347.575 50.2642 + endloop + endfacet + facet normal -0.978358 0.0712342 0.194272 + outer loop + vertex -895.661 349.811 59.4017 + vertex -896.196 354.983 54.8099 + vertex -896.769 347.158 54.7955 + endloop + endfacet + facet normal -0.976528 0.0404577 0.211555 + outer loop + vertex -895.661 349.811 59.4017 + vertex -896.769 347.158 54.7955 + vertex -895.983 342.093 59.3895 + endloop + endfacet + facet normal -0.964544 0.0548719 0.258154 + outer loop + vertex -897.108 351.474 51.8579 + vertex -897.757 347.575 50.2642 + vertex -897.555 343.633 51.8555 + endloop + endfacet + facet normal -0.976247 0.036291 0.213599 + outer loop + vertex -897.555 343.633 51.8555 + vertex -897.757 347.575 50.2642 + vertex -898.051 339.745 50.2517 + endloop + endfacet + facet normal -0.962958 0.0115753 0.269402 + outer loop + vertex -897.555 343.633 51.8555 + vertex -898.051 339.745 50.2517 + vertex -897.658 335.974 51.8165 + endloop + endfacet + facet normal -0.975238 -0.00981142 0.220942 + outer loop + vertex -897.658 335.974 51.8165 + vertex -898.051 339.745 50.2517 + vertex -897.984 332.47 50.2231 + endloop + endfacet + facet normal -0.979457 0.0291062 0.19954 + outer loop + vertex -895.983 342.093 59.3895 + vertex -896.769 347.158 54.7955 + vertex -896.998 339.401 54.8 + endloop + endfacet + facet normal -0.979464 0.0406026 0.197491 + outer loop + vertex -894.712 343.844 65.3335 + vertex -895.661 349.811 59.4017 + vertex -895.983 342.093 59.3895 + endloop + endfacet + facet normal -0.980664 0.0449996 0.190453 + outer loop + vertex -893.36 344.89 72.052 + vertex -894.361 351.467 65.3412 + vertex -894.712 343.844 65.3335 + endloop + endfacet + facet normal -0.982363 0.0453104 0.181408 + outer loop + vertex -892.021 345.649 79.109 + vertex -893.013 352.409 72.053 + vertex -893.36 344.89 72.052 + endloop + endfacet + facet normal -0.984463 0.0444413 0.169876 + outer loop + vertex -890.744 346.429 86.3072 + vertex -891.686 353.067 79.1102 + vertex -892.021 345.649 79.109 + endloop + endfacet + facet normal -0.986159 0.0443592 0.159759 + outer loop + vertex -889.516 347.308 93.6429 + vertex -890.414 353.756 86.3089 + vertex -890.744 346.429 86.3072 + endloop + endfacet + facet normal -0.987834 0.0448124 0.148916 + outer loop + vertex -888.345 348.207 101.138 + vertex -889.188 354.546 93.6423 + vertex -889.516 347.308 93.6429 + endloop + endfacet + facet normal -0.989631 0.0459663 0.136076 + outer loop + vertex -887.257 349.033 108.774 + vertex -888.013 355.359 101.137 + vertex -888.345 348.207 101.138 + endloop + endfacet + facet normal -0.991937 0.0036085 0.126681 + outer loop + vertex -886.266 349.747 116.514 + vertex -887.257 349.033 108.774 + vertex -886.291 342.798 116.514 + endloop + endfacet + facet normal -0.994007 0.00361702 0.109259 + outer loop + vertex -885.431 343.468 124.32 + vertex -886.266 349.747 116.514 + vertex -886.291 342.798 116.514 + endloop + endfacet + facet normal -0.995682 0.00477087 0.0927114 + outer loop + vertex -884.697 344.035 132.177 + vertex -885.398 350.357 124.32 + vertex -885.431 343.468 124.32 + endloop + endfacet + facet normal -0.997152 0.00530902 0.0752355 + outer loop + vertex -884.099 344.503 140.065 + vertex -884.66 350.873 132.177 + vertex -884.697 344.035 132.177 + endloop + endfacet + facet normal -0.998289 0.00660894 0.0580953 + outer loop + vertex -883.638 344.87 147.952 + vertex -884.054 351.299 140.065 + vertex -884.099 344.503 140.065 + endloop + endfacet + facet normal -0.999155 0.00704491 0.0404858 + outer loop + vertex -883.317 345.133 155.805 + vertex -883.59 351.633 147.951 + vertex -883.638 344.87 147.952 + endloop + endfacet + facet normal -0.999718 0.00734404 0.02258 + outer loop + vertex -883.14 345.292 163.625 + vertex -883.268 351.872 155.804 + vertex -883.317 345.133 155.805 + endloop + endfacet + facet normal -0.999965 0.00727902 0.00401931 + outer loop + vertex -883.108 345.348 171.449 + vertex -883.091 352.017 163.624 + vertex -883.14 345.292 163.625 + endloop + endfacet + facet normal -0.999968 0.00699434 0.00377669 + outer loop + vertex -883.061 352.068 171.448 + vertex -883.091 352.017 163.624 + vertex -883.108 345.348 171.449 + endloop + endfacet + facet normal -0.998197 0.0492753 -0.0342726 + outer loop + vertex -883.12 358.668 187.267 + vertex -882.841 358.792 179.323 + vertex -883.455 351.887 187.268 + endloop + endfacet + facet normal -0.998606 0.0506681 -0.014789 + outer loop + vertex -883.18 352.025 179.324 + vertex -882.718 358.831 171.448 + vertex -883.061 352.068 171.448 + endloop + endfacet + facet normal -0.996131 0.0865047 -0.0155089 + outer loop + vertex -882.253 365.568 179.322 + vertex -882.127 365.603 171.447 + vertex -882.841 358.792 179.323 + endloop + endfacet + facet normal -0.996189 0.0871659 0.00322165 + outer loop + vertex -882.718 358.831 171.448 + vertex -882.154 365.564 163.624 + vertex -882.747 358.786 163.624 + endloop + endfacet + facet normal -0.992932 0.118657 0.00250544 + outer loop + vertex -881.324 372.32 171.447 + vertex -881.348 372.286 163.624 + vertex -882.127 365.603 171.447 + endloop + endfacet + facet normal -0.992687 0.118992 0.0203454 + outer loop + vertex -882.154 365.564 163.624 + vertex -881.52 372.187 155.804 + vertex -882.328 365.448 155.804 + endloop + endfacet + facet normal -0.988913 0.147186 0.0196921 + outer loop + vertex -880.363 378.906 163.623 + vertex -880.531 378.823 155.804 + vertex -881.348 372.286 163.624 + endloop + endfacet + facet normal -0.988383 0.147466 0.0367814 + outer loop + vertex -881.52 372.187 155.804 + vertex -880.843 378.683 147.951 + vertex -881.837 372.022 147.951 + endloop + endfacet + facet normal -0.984297 0.172831 0.0359119 + outer loop + vertex -879.387 385.34 155.802 + vertex -879.693 385.227 147.95 + vertex -880.531 378.823 155.804 + endloop + endfacet + facet normal -0.983534 0.173005 0.0522471 + outer loop + vertex -880.843 378.683 147.951 + vertex -880.139 385.068 140.064 + vertex -881.297 378.488 140.065 + endloop + endfacet + facet normal -0.979316 0.195742 0.0512458 + outer loop + vertex -878.408 391.657 147.947 + vertex -878.845 391.535 140.063 + vertex -879.693 385.227 147.95 + endloop + endfacet + facet normal -0.978318 0.195932 0.0671125 + outer loop + vertex -880.139 385.068 140.064 + vertex -879.416 391.38 132.175 + vertex -880.721 384.865 132.176 + endloop + endfacet + facet normal -0.974113 0.216196 0.0660605 + outer loop + vertex -877.43 397.91 140.06 + vertex -877.989 397.801 132.173 + vertex -878.845 391.535 140.063 + endloop + endfacet + facet normal -0.972881 0.216473 0.0815012 + outer loop + vertex -879.416 391.38 132.175 + vertex -878.674 397.672 124.317 + vertex -880.116 391.193 124.319 + endloop + endfacet + facet normal -0.968616 0.235168 0.0804888 + outer loop + vertex -876.447 404.155 132.173 + vertex -877.117 404.084 124.315 + vertex -877.989 397.801 132.173 + endloop + endfacet + facet normal -0.967273 0.235227 0.0951378 + outer loop + vertex -878.674 397.672 124.317 + vertex -877.904 403.997 116.509 + vertex -879.48 397.516 116.511 + endloop + endfacet + facet normal -0.962872 0.252942 0.0943223 + outer loop + vertex -875.442 410.458 124.32 + vertex -876.212 410.441 116.508 + vertex -877.117 404.084 124.315 + endloop + endfacet + facet normal -0.961567 0.252596 0.107631 + outer loop + vertex -877.904 403.997 116.509 + vertex -877.088 410.404 108.768 + vertex -878.802 403.877 108.772 + endloop + endfacet + facet normal -0.957158 0.268977 0.107242 + outer loop + vertex -874.403 416.874 116.518 + vertex -875.258 416.92 108.771 + vertex -876.212 410.441 116.508 + endloop + endfacet + facet normal -0.956011 0.268192 0.11881 + outer loop + vertex -877.088 410.404 108.768 + vertex -876.203 416.94 101.132 + vertex -878.058 410.328 101.132 + endloop + endfacet + facet normal -0.951962 0.282168 0.118955 + outer loop + vertex -873.327 423.426 108.789 + vertex -874.248 423.542 101.141 + vertex -875.258 416.92 108.771 + endloop + endfacet + facet normal -0.951035 0.280908 0.128933 + outer loop + vertex -876.203 416.94 101.132 + vertex -875.233 423.658 93.6483 + vertex -877.216 416.947 93.6407 + endloop + endfacet + facet normal -0.947466 0.292366 0.129735 + outer loop + vertex -872.221 430.098 101.172 + vertex -873.177 430.326 93.6738 + vertex -874.248 423.542 101.141 + endloop + endfacet + facet normal -0.946792 0.290474 0.138599 + outer loop + vertex -875.233 423.658 93.6483 + vertex -874.166 430.626 86.3371 + vertex -876.25 423.839 86.3206 + endloop + endfacet + facet normal -0.943141 0.301093 0.140812 + outer loop + vertex -871.079 436.88 93.7123 + vertex -872.04 437.307 86.3678 + vertex -873.177 430.326 93.6738 + endloop + endfacet + facet normal -0.94304 0.297612 0.148668 + outer loop + vertex -874.166 430.626 86.3371 + vertex -873.013 437.871 79.1478 + vertex -875.166 431.054 79.1368 + endloop + endfacet + facet normal -0.937872 0.310866 0.154138 + outer loop + vertex -869.879 443.813 86.3961 + vertex -870.834 444.524 79.1524 + vertex -872.04 437.307 86.3678 + endloop + endfacet + facet normal -0.939331 0.303719 0.159412 + outer loop + vertex -873.013 437.871 79.1478 + vertex -871.807 445.322 72.0554 + vertex -874.002 438.52 72.0815 + endloop + endfacet + facet normal -0.930822 0.322976 0.171048 + outer loop + vertex -868.601 450.972 79.1237 + vertex -869.571 451.948 72.0018 + vertex -870.834 444.524 79.1524 + endloop + endfacet + facet normal -0.935338 0.310005 0.170409 + outer loop + vertex -871.807 445.322 72.0554 + vertex -870.585 452.736 65.2763 + vertex -872.816 445.965 65.346 + endloop + endfacet + facet normal -0.924414 0.331086 0.189315 + outer loop + vertex -867.271 458.409 71.9345 + vertex -868.273 459.463 65.1986 + vertex -869.571 451.948 72.0018 + endloop + endfacet + facet normal -0.932245 0.313328 0.180957 + outer loop + vertex -870.585 452.736 65.2763 + vertex -869.367 459.78 59.3534 + vertex -871.655 452.896 59.4858 + endloop + endfacet + facet normal -0.930641 0.312962 0.189637 + outer loop + vertex -869.367 459.78 59.3534 + vertex -870.619 458.702 54.9918 + vertex -871.655 452.896 59.4858 + endloop + endfacet + facet normal -0.929286 0.306006 0.206854 + outer loop + vertex -866.05 466.173 65.259 + vertex -867.049 467.136 59.3486 + vertex -868.273 459.463 65.1986 + endloop + endfacet + facet normal -0.954258 0.212213 0.210614 + outer loop + vertex -865.35 474.6 59.5221 + vertex -866.166 476.225 54.1891 + vertex -867.049 467.136 59.3486 + endloop + endfacet + facet normal -0.953623 0.27058 0.131868 + outer loop + vertex -867.319 471.716 51.8374 + vertex -868.227 469.227 50.3841 + vertex -869.502 463.936 52.0187 + endloop + endfacet + facet normal -0.930857 0.29215 0.219441 + outer loop + vertex -869.502 463.936 52.0187 + vertex -868.227 469.227 50.3841 + vertex -870.691 461.304 50.4765 + endloop + endfacet + facet normal -0.934411 0.29855 0.194279 + outer loop + vertex -869.367 459.78 59.3534 + vertex -868.199 466.381 54.827 + vertex -870.619 458.702 54.9918 + endloop + endfacet + facet normal -0.93411 0.307351 0.181587 + outer loop + vertex -871.655 452.896 59.4858 + vertex -870.619 458.702 54.9918 + vertex -872.663 452.184 55.5091 + endloop + endfacet + facet normal -0.937323 0.300452 0.176506 + outer loop + vertex -873.851 446.168 59.4409 + vertex -872.663 452.184 55.5091 + vertex -874.806 446.187 54.3378 + endloop + endfacet + facet normal -0.93863 0.294528 0.17952 + outer loop + vertex -874.526 448.898 51.3499 + vertex -876.561 442.205 51.6942 + vertex -874.806 446.187 54.3378 + endloop + endfacet + facet normal -0.936983 0.29714 0.183769 + outer loop + vertex -874.526 448.898 51.3499 + vertex -873.226 453.632 50.3262 + vertex -875.572 446.301 50.2163 + endloop + endfacet + facet normal -0.931722 0.295037 0.211771 + outer loop + vertex -875.572 446.301 50.2163 + vertex -873.226 453.632 50.3262 + vertex -874.317 450.618 49.7249 + endloop + endfacet + facet normal -0.931549 0.305464 0.197249 + outer loop + vertex -869.502 463.936 52.0187 + vertex -870.691 461.304 50.4765 + vertex -872.312 455.238 52.2153 + endloop + endfacet + facet normal -0.933768 0.299478 0.195934 + outer loop + vertex -871.719 459.284 48.7862 + vertex -872.496 458.397 46.4418 + vertex -874.089 451.951 48.7029 + endloop + endfacet + facet normal -0.933262 0.297764 0.200896 + outer loop + vertex -873.072 454.607 49.5932 + vertex -874.317 450.618 49.7249 + vertex -873.226 453.632 50.3262 + endloop + endfacet + facet normal -0.936452 0.294076 0.191252 + outer loop + vertex -874.317 450.618 49.7249 + vertex -875.478 447.051 49.526 + vertex -875.572 446.301 50.2163 + endloop + endfacet + facet normal -0.937697 0.293861 0.185392 + outer loop + vertex -874.089 451.951 48.7029 + vertex -874.856 450.987 46.3524 + vertex -876.518 444.236 48.6469 + endloop + endfacet + facet normal -0.937458 0.292242 0.189122 + outer loop + vertex -875.478 447.051 49.526 + vertex -876.722 442.947 49.7004 + vertex -875.572 446.301 50.2163 + endloop + endfacet + facet normal -0.939145 0.290036 0.18408 + outer loop + vertex -876.722 442.947 49.7004 + vertex -877.931 439.145 49.5218 + vertex -877.909 438.731 50.2841 + endloop + endfacet + facet normal -0.940046 0.289868 0.179697 + outer loop + vertex -876.518 444.236 48.6469 + vertex -877.275 443.207 46.3423 + vertex -879.042 436.044 48.6571 + endloop + endfacet + facet normal -0.939667 0.288769 0.183407 + outer loop + vertex -877.931 439.145 49.5218 + vertex -879.216 434.829 49.7364 + vertex -877.909 438.731 50.2841 + endloop + endfacet + facet normal -0.940786 0.286351 0.181453 + outer loop + vertex -879.216 434.829 49.7364 + vertex -880.769 429.785 49.6439 + vertex -880.113 431.452 50.4127 + endloop + endfacet + facet normal -0.941925 0.286086 0.175877 + outer loop + vertex -879.042 436.044 48.6571 + vertex -879.718 435.24 46.344 + vertex -881.512 427.898 48.6785 + endloop + endfacet + facet normal -0.936547 0.283746 0.205833 + outer loop + vertex -880.769 429.785 49.6439 + vertex -881.92 425.975 49.6554 + vertex -882.356 424.087 50.2745 + endloop + endfacet + facet normal -0.941193 0.279549 0.189757 + outer loop + vertex -881.92 425.975 49.6554 + vertex -882.739 423.275 49.5703 + vertex -882.356 424.087 50.2745 + endloop + endfacet + facet normal -0.944704 0.279649 0.171265 + outer loop + vertex -881.512 427.898 48.6785 + vertex -882.123 427.253 46.362 + vertex -883.863 419.875 48.811 + endloop + endfacet + facet normal -0.941275 0.278099 0.191473 + outer loop + vertex -882.739 423.275 49.5703 + vertex -883.665 420.001 49.777 + vertex -882.356 424.087 50.2745 + endloop + endfacet + facet normal -0.939931 0.272003 0.206264 + outer loop + vertex -883.665 420.001 49.777 + vertex -884.434 417.403 49.6954 + vertex -884.534 416.561 50.351 + endloop + endfacet + facet normal -0.943812 0.265298 0.197066 + outer loop + vertex -884.434 417.403 49.6954 + vertex -885.384 414.068 49.6381 + vertex -884.534 416.561 50.351 + endloop + endfacet + facet normal -0.951365 0.266407 0.154702 + outer loop + vertex -886.428 410.341 49.6338 + vertex -885.384 414.068 49.6381 + vertex -886.111 412.044 48.6485 + endloop + endfacet + facet normal -0.957189 0.256073 0.134969 + outer loop + vertex -887.427 406.623 49.6024 + vertex -886.428 410.341 49.6338 + vertex -886.111 412.044 48.6485 + endloop + endfacet + facet normal -0.956909 0.256282 0.136547 + outer loop + vertex -886.111 412.044 48.6485 + vertex -888.225 404.149 48.6528 + vertex -887.427 406.623 49.6024 + endloop + endfacet + facet normal -0.95646 0.252096 0.147077 + outer loop + vertex -888.436 402.777 49.6317 + vertex -887.427 406.623 49.6024 + vertex -888.225 404.149 48.6528 + endloop + endfacet + facet normal -0.962384 0.239542 0.128203 + outer loop + vertex -889.405 398.882 49.639 + vertex -888.436 402.777 49.6317 + vertex -888.225 404.149 48.6528 + endloop + endfacet + facet normal -0.949645 0.23652 0.205506 + outer loop + vertex -888.436 402.777 49.6317 + vertex -889.405 398.882 49.639 + vertex -888.536 401.808 50.2862 + endloop + endfacet + facet normal -0.94203 0.248902 0.225005 + outer loop + vertex -887.427 406.623 49.6024 + vertex -888.436 402.777 49.6317 + vertex -888.536 401.808 50.2862 + endloop + endfacet + facet normal -0.944582 0.248069 0.215002 + outer loop + vertex -888.536 401.808 50.2862 + vertex -886.567 409.25 50.35 + vertex -887.427 406.623 49.6024 + endloop + endfacet + facet normal -0.946429 0.252622 0.201131 + outer loop + vertex -886.428 410.341 49.6338 + vertex -887.427 406.623 49.6024 + vertex -886.567 409.25 50.35 + endloop + endfacet + facet normal -0.939738 0.263076 0.218364 + outer loop + vertex -885.384 414.068 49.6381 + vertex -886.428 410.341 49.6338 + vertex -886.567 409.25 50.35 + endloop + endfacet + facet normal -0.942611 0.262084 0.206875 + outer loop + vertex -886.567 409.25 50.35 + vertex -884.534 416.561 50.351 + vertex -885.384 414.068 49.6381 + endloop + endfacet + facet normal -0.94643 0.277831 0.164562 + outer loop + vertex -883.863 419.875 48.811 + vertex -882.123 427.253 46.362 + vertex -884.458 419.308 46.3471 + endloop + endfacet + facet normal -0.943963 0.277078 0.179339 + outer loop + vertex -882.123 427.253 46.362 + vertex -882.743 427.261 43.0835 + vertex -884.458 419.308 46.3471 + endloop + endfacet + facet normal -0.939782 0.28142 0.19394 + outer loop + vertex -882.743 427.261 43.0835 + vertex -881.091 435.52 39.1074 + vertex -883.535 427.366 39.0956 + endloop + endfacet + facet normal -0.93489 0.279919 0.218234 + outer loop + vertex -881.091 435.52 39.1074 + vertex -882.116 435.475 34.7717 + vertex -883.535 427.366 39.0956 + endloop + endfacet + facet normal -0.926529 0.280066 0.25121 + outer loop + vertex -882.116 435.475 34.7717 + vertex -880.869 443.488 30.4363 + vertex -883.451 434.951 30.4322 + endloop + endfacet + facet normal -0.937038 0.273285 0.21743 + outer loop + vertex -885.942 419.126 39.0886 + vertex -884.611 427.13 34.7642 + vertex -887.062 418.729 34.7602 + endloop + endfacet + facet normal -0.944491 0.265136 0.194008 + outer loop + vertex -885.106 419.195 43.0625 + vertex -885.942 419.126 39.0886 + vertex -887.41 410.988 43.0616 + endloop + endfacet + facet normal -0.947696 0.266037 0.176339 + outer loop + vertex -886.714 411.312 46.3152 + vertex -885.106 419.195 43.0625 + vertex -887.41 410.988 43.0616 + endloop + endfacet + facet normal -0.952582 0.25514 0.165806 + outer loop + vertex -886.111 412.044 48.6485 + vertex -886.714 411.312 46.3152 + vertex -888.225 404.149 48.6528 + endloop + endfacet + facet normal -0.959125 0.216518 0.182209 + outer loop + vertex -892.886 386.243 46.3451 + vertex -891.724 394.139 43.0793 + vertex -893.649 385.616 43.0754 + endloop + endfacet + facet normal -0.954741 0.236191 0.180785 + outer loop + vertex -888.906 403.038 46.3426 + vertex -889.631 402.614 43.0652 + vertex -890.987 394.61 46.3589 + endloop + endfacet + facet normal -0.947603 0.251909 0.196442 + outer loop + vertex -889.631 402.614 43.0652 + vertex -888.288 410.768 39.0852 + vertex -890.537 402.301 39.0948 + endloop + endfacet + facet normal -0.942443 0.250567 0.221399 + outer loop + vertex -888.288 410.768 39.0852 + vertex -889.446 410.235 34.762 + vertex -890.537 402.301 39.0948 + endloop + endfacet + facet normal -0.930806 0.26098 0.255908 + outer loop + vertex -889.446 410.235 34.762 + vertex -888.49 417.893 30.4288 + vertex -890.924 409.213 30.4261 + endloop + endfacet + facet normal -0.94585 0.234095 0.224871 + outer loop + vertex -892.66 393.727 39.0971 + vertex -891.734 401.63 34.7647 + vertex -893.901 392.895 34.7421 + endloop + endfacet + facet normal -0.955307 0.215647 0.202199 + outer loop + vertex -891.724 394.139 43.0793 + vertex -892.66 393.727 39.0971 + vertex -893.649 385.616 43.0754 + endloop + endfacet + facet normal -0.962851 0.194523 0.187295 + outer loop + vertex -892.886 386.243 46.3451 + vertex -893.649 385.616 43.0754 + vertex -894.584 377.844 46.3376 + endloop + endfacet + facet normal -0.969154 0.172881 0.17565 + outer loop + vertex -893.898 379.323 48.6698 + vertex -894.584 377.844 46.3376 + vertex -895.375 371.065 48.6447 + endloop + endfacet + facet normal -0.972531 0.100488 0.209966 + outer loop + vertex -898.204 351.999 46.3424 + vertex -898.132 359.622 43.0284 + vertex -899.028 350.989 43.0101 + endloop + endfacet + facet normal -0.969599 0.137606 0.202344 + outer loop + vertex -896.07 369.273 46.3483 + vertex -896.897 368.313 43.0373 + vertex -897.3 360.598 46.3503 + endloop + endfacet + facet normal -0.964703 0.137104 0.224835 + outer loop + vertex -898.132 359.622 43.0284 + vertex -898.004 367.323 38.8833 + vertex -899.263 358.502 38.8596 + endloop + endfacet + facet normal -0.962402 0.166762 0.214415 + outer loop + vertex -895.384 377.007 43.067 + vertex -896.437 376.206 38.9643 + vertex -896.897 368.313 43.0373 + endloop + endfacet + facet normal -0.952726 0.192042 0.235441 + outer loop + vertex -894.634 385.025 39.0644 + vertex -895.952 383.933 34.6233 + vertex -896.437 376.206 38.9643 + endloop + endfacet + facet normal -0.939838 0.210283 0.269232 + outer loop + vertex -895.952 383.933 34.6233 + vertex -895.476 391.504 30.3727 + vertex -897.624 382.075 30.2367 + endloop + endfacet + facet normal -0.956032 0.16596 0.241787 + outer loop + vertex -898.004 367.323 38.8833 + vertex -897.862 374.899 34.2433 + vertex -899.444 365.751 34.2654 + endloop + endfacet + facet normal -0.801982 -0.404703 0.439364 + outer loop + vertex -892.756 282.81 30.079 + vertex -890.619 278.893 30.3715 + vertex -890.372 281.791 33.491 + endloop + endfacet + facet normal -0.820305 -0.337261 0.461903 + outer loop + vertex -894.17 286.566 30.5979 + vertex -896.741 289.558 28.217 + vertex -895.134 285.559 28.1498 + endloop + endfacet + facet normal -0.820273 -0.337088 0.462086 + outer loop + vertex -896.059 290.677 30.2429 + vertex -896.741 289.558 28.217 + vertex -894.17 286.566 30.5979 + endloop + endfacet + facet normal -0.836642 -0.309159 0.452162 + outer loop + vertex -896.059 290.677 30.2429 + vertex -898.213 293.637 28.2814 + vertex -896.741 289.558 28.217 + endloop + endfacet + facet normal -0.836681 -0.309296 0.451997 + outer loop + vertex -897.229 294.555 30.7318 + vertex -898.213 293.637 28.2814 + vertex -896.059 290.677 30.2429 + endloop + endfacet + facet normal -0.850291 -0.279171 0.446172 + outer loop + vertex -897.229 294.555 30.7318 + vertex -899.532 297.745 28.3392 + vertex -898.213 293.637 28.2814 + endloop + endfacet + facet normal -0.850217 -0.278873 0.446499 + outer loop + vertex -898.813 298.777 30.3513 + vertex -899.532 297.745 28.3392 + vertex -897.229 294.555 30.7318 + endloop + endfacet + facet normal -0.864014 -0.250368 0.436801 + outer loop + vertex -898.813 298.777 30.3513 + vertex -900.685 301.831 28.4003 + vertex -899.532 297.745 28.3392 + endloop + endfacet + facet normal -0.863657 -0.249316 0.438107 + outer loop + vertex -899.686 302.646 30.8336 + vertex -900.685 301.831 28.4003 + vertex -898.813 298.777 30.3513 + endloop + endfacet + facet normal -0.875241 -0.217288 0.432133 + outer loop + vertex -899.686 302.646 30.8336 + vertex -901.662 305.884 28.4581 + vertex -900.685 301.831 28.4003 + endloop + endfacet + facet normal -0.874737 -0.215621 0.433985 + outer loop + vertex -900.916 306.864 30.4483 + vertex -901.662 305.884 28.4581 + vertex -899.686 302.646 30.8336 + endloop + endfacet + facet normal -0.88726 -0.183851 0.423048 + outer loop + vertex -900.916 306.864 30.4483 + vertex -902.479 309.942 28.508 + vertex -901.662 305.884 28.4581 + endloop + endfacet + facet normal -0.886586 -0.182162 0.425185 + outer loop + vertex -901.49 310.757 30.9215 + vertex -902.479 309.942 28.508 + vertex -900.916 306.864 30.4483 + endloop + endfacet + facet normal -0.896391 -0.148233 0.417744 + outer loop + vertex -901.49 310.757 30.9215 + vertex -903.137 314.058 28.5565 + vertex -902.479 309.942 28.508 + endloop + endfacet + facet normal -0.895537 -0.145916 0.420382 + outer loop + vertex -902.372 315.079 30.5408 + vertex -903.137 314.058 28.5565 + vertex -901.49 310.757 30.9215 + endloop + endfacet + facet normal -0.905637 -0.114752 0.408231 + outer loop + vertex -902.372 315.079 30.5408 + vertex -903.649 318.268 28.6058 + vertex -903.137 314.058 28.5565 + endloop + endfacet + facet normal -0.904695 -0.112778 0.410863 + outer loop + vertex -902.665 319.121 31.0054 + vertex -903.649 318.268 28.6058 + vertex -902.372 315.079 30.5408 + endloop + endfacet + facet normal -0.911871 -0.0808078 0.402445 + outer loop + vertex -902.665 319.121 31.0054 + vertex -904.008 322.57 28.6558 + vertex -903.649 318.268 28.6058 + endloop + endfacet + facet normal -0.91066 -0.078117 0.405703 + outer loop + vertex -903.221 323.609 30.6212 + vertex -904.008 322.57 28.6558 + vertex -902.665 319.121 31.0054 + endloop + endfacet + facet normal -0.918101 -0.0490231 0.393303 + outer loop + vertex -903.221 323.609 30.6212 + vertex -904.224 326.923 28.6929 + vertex -904.008 322.57 28.6558 + endloop + endfacet + facet normal -0.917617 -0.0481573 0.394539 + outer loop + vertex -903.242 327.766 31.0816 + vertex -904.224 326.923 28.6929 + vertex -903.221 323.609 30.6212 + endloop + endfacet + facet normal -0.922381 -0.0180226 0.385861 + outer loop + vertex -903.242 327.766 31.0816 + vertex -904.292 331.314 28.7373 + vertex -904.224 326.923 28.6929 + endloop + endfacet + facet normal -0.921683 -0.0166764 0.387586 + outer loop + vertex -903.488 332.341 30.6936 + vertex -904.292 331.314 28.7373 + vertex -903.242 327.766 31.0816 + endloop + endfacet + facet normal -0.926579 0.00926063 0.375987 + outer loop + vertex -903.488 332.341 30.6936 + vertex -904.233 335.695 28.7734 + vertex -904.292 331.314 28.7373 + endloop + endfacet + facet normal -0.92721 0.0082405 0.374451 + outer loop + vertex -903.267 336.512 31.148 + vertex -904.233 335.695 28.7734 + vertex -903.488 332.341 30.6936 + endloop + endfacet + facet normal -0.929831 0.0349627 0.366322 + outer loop + vertex -903.267 336.512 31.148 + vertex -904.055 340.058 28.8082 + vertex -904.233 335.695 28.7734 + endloop + endfacet + facet normal -0.929571 0.0354253 0.366936 + outer loop + vertex -903.249 341.083 30.7533 + vertex -904.055 340.058 28.8082 + vertex -903.267 336.512 31.148 + endloop + endfacet + facet normal -0.932487 0.0572961 0.35663 + outer loop + vertex -903.249 341.083 30.7533 + vertex -903.774 344.416 28.8437 + vertex -904.055 340.058 28.8082 + endloop + endfacet + facet normal -0.93326 0.0561207 0.354791 + outer loop + vertex -902.825 345.247 31.2077 + vertex -903.774 344.416 28.8437 + vertex -903.249 341.083 30.7533 + endloop + endfacet + facet normal -0.934441 0.0788012 0.347291 + outer loop + vertex -902.825 345.247 31.2077 + vertex -903.394 348.781 28.8766 + vertex -903.774 344.416 28.8437 + endloop + endfacet + facet normal -0.933697 0.0800494 0.349002 + outer loop + vertex -902.581 349.82 30.8126 + vertex -903.394 348.781 28.8766 + vertex -902.825 345.247 31.2077 + endloop + endfacet + facet normal -0.935246 0.0974268 0.340329 + outer loop + vertex -902.581 349.82 30.8126 + vertex -902.927 353.156 28.9071 + vertex -903.394 348.781 28.8766 + endloop + endfacet + facet normal -0.935706 0.0967627 0.33925 + outer loop + vertex -901.993 353.98 31.2493 + vertex -902.927 353.156 28.9071 + vertex -902.581 349.82 30.8126 + endloop + endfacet + facet normal -0.935918 0.115847 0.332622 + outer loop + vertex -901.993 353.98 31.2493 + vertex -902.382 357.523 28.9192 + vertex -902.927 353.156 28.9071 + endloop + endfacet + facet normal -0.93455 0.118016 0.335692 + outer loop + vertex -901.56 358.559 30.8434 + vertex -902.382 357.523 28.9192 + vertex -901.993 353.98 31.2493 + endloop + endfacet + facet normal -0.935271 0.132581 0.328164 + outer loop + vertex -901.56 358.559 30.8434 + vertex -901.755 361.914 28.9322 + vertex -902.382 357.523 28.9192 + endloop + endfacet + facet normal -0.935186 0.132697 0.328359 + outer loop + vertex -900.808 362.779 31.2789 + vertex -901.755 361.914 28.9322 + vertex -901.56 358.559 30.8434 + endloop + endfacet + facet normal -0.93484 0.149849 0.321899 + outer loop + vertex -900.808 362.779 31.2789 + vertex -901.023 366.4 28.9695 + vertex -901.755 361.914 28.9322 + endloop + endfacet + facet normal -0.933041 0.152481 0.32586 + outer loop + vertex -900.161 367.517 30.9149 + vertex -901.023 366.4 28.9695 + vertex -900.808 362.779 31.2789 + endloop + endfacet + facet normal -0.933344 0.164866 0.318887 + outer loop + vertex -900.161 367.517 30.9149 + vertex -900.161 371.071 29.0786 + vertex -901.023 366.4 28.9695 + endloop + endfacet + facet normal -0.934829 0.163082 0.315433 + outer loop + vertex -899.214 371.918 31.4457 + vertex -900.161 371.071 29.0786 + vertex -900.161 367.517 30.9149 + endloop + endfacet + facet normal -0.934005 0.17797 0.309777 + outer loop + vertex -899.214 371.918 31.4457 + vertex -899.123 376.02 29.3654 + vertex -900.161 371.071 29.0786 + endloop + endfacet + facet normal -0.934418 0.177487 0.308805 + outer loop + vertex -898.454 376.266 31.2474 + vertex -899.123 376.02 29.3654 + vertex -899.214 371.918 31.4457 + endloop + endfacet + facet normal -0.933156 0.186764 0.307147 + outer loop + vertex -898.454 376.266 31.2474 + vertex -897.624 382.075 30.2367 + vertex -899.123 376.02 29.3654 + endloop + endfacet + facet normal -0.779775 -0.426746 0.458082 + outer loop + vertex -886.455 274.272 33.1544 + vertex -890.372 281.791 33.491 + vertex -890.619 278.893 30.3715 + endloop + endfacet + facet normal -0.754399 -0.469586 0.458663 + outer loop + vertex -884.901 268.248 29.5735 + vertex -884.214 269.586 32.0724 + vertex -887.007 271.979 29.9292 + endloop + endfacet + facet normal -0.76727 -0.48517 0.419412 + outer loop + vertex -885.377 276.728 37.9664 + vertex -886.455 274.272 33.1544 + vertex -881.351 269.834 37.3584 + endloop + endfacet + facet normal -0.782066 -0.490704 0.384163 + outer loop + vertex -880.301 271.822 42.0337 + vertex -885.377 276.728 37.9664 + vertex -881.351 269.834 37.3584 + endloop + endfacet + facet normal -0.781902 -0.496649 0.376788 + outer loop + vertex -884.427 278.585 42.3855 + vertex -885.377 276.728 37.9664 + vertex -880.301 271.822 42.0337 + endloop + endfacet + facet normal -0.794319 -0.502392 0.341555 + outer loop + vertex -879.756 273.407 45.6327 + vertex -884.427 278.585 42.3855 + vertex -880.301 271.822 42.0337 + endloop + endfacet + facet normal -0.794366 -0.503909 0.339204 + outer loop + vertex -883.839 280.001 45.8669 + vertex -884.427 278.585 42.3855 + vertex -879.756 273.407 45.6327 + endloop + endfacet + facet normal -0.811444 -0.512418 0.281043 + outer loop + vertex -879.81 274.836 48.0829 + vertex -883.839 280.001 45.8669 + vertex -879.756 273.407 45.6327 + endloop + endfacet + facet normal -0.811118 -0.50955 0.287135 + outer loop + vertex -883.662 281.128 48.3675 + vertex -883.839 280.001 45.8669 + vertex -879.81 274.836 48.0829 + endloop + endfacet + facet normal -0.748422 -0.501038 0.43454 + outer loop + vertex -883.373 270.195 34.2238 + vertex -884.214 269.586 32.0724 + vertex -881.235 267.097 34.3343 + endloop + endfacet + facet normal -0.707441 -0.550131 0.443716 + outer loop + vertex -879.279 263.775 33.6724 + vertex -876.12 260.104 34.1558 + vertex -876.587 263.219 37.2733 + endloop + endfacet + facet normal -0.748506 -0.493358 0.4431 + outer loop + vertex -881.235 267.097 34.3343 + vertex -884.214 269.586 32.0724 + vertex -882.085 265.945 31.6157 + endloop + endfacet + facet normal -0.737629 -0.489723 0.464839 + outer loop + vertex -884.214 269.586 32.0724 + vertex -884.901 268.248 29.5735 + vertex -882.085 265.945 31.6157 + endloop + endfacet + facet normal -0.732403 -0.454721 0.50677 + outer loop + vertex -884.901 268.248 29.5735 + vertex -887.701 270.636 27.6689 + vertex -885.622 267.086 27.4888 + endloop + endfacet + facet normal -0.717123 -0.50304 0.482374 + outer loop + vertex -879.719 262.42 31.3999 + vertex -882.742 264.72 29.3037 + vertex -880.445 261.27 29.1212 + endloop + endfacet + facet normal -0.702143 -0.543416 0.460104 + outer loop + vertex -879.279 263.775 33.6724 + vertex -879.719 262.42 31.3999 + vertex -876.12 260.104 34.1558 + endloop + endfacet + facet normal -0.679753 -0.567234 0.464953 + outer loop + vertex -871.125 257.02 37.6972 + vertex -876.587 263.219 37.2733 + vertex -876.12 260.104 34.1558 + endloop + endfacet + facet normal -0.671583 -0.550886 0.49548 + outer loop + vertex -872.113 255.245 33.9969 + vertex -876.921 258.657 31.2743 + vertex -874.086 254.714 30.7325 + endloop + endfacet + facet normal -0.65113 -0.546485 0.526673 + outer loop + vertex -876.121 255.013 28.5268 + vertex -872.63 251.558 29.2576 + vertex -874.086 254.714 30.7325 + endloop + endfacet + facet normal -0.617788 -0.616478 0.488153 + outer loop + vertex -865.905 251.209 37.3825 + vertex -867.803 249.582 32.9263 + vertex -860.474 245.342 36.8465 + endloop + endfacet + facet normal -0.619248 -0.617537 0.484953 + outer loop + vertex -859.533 247.504 40.801 + vertex -865.905 251.209 37.3825 + vertex -860.474 245.342 36.8465 + endloop + endfacet + facet normal -0.617162 -0.643106 0.45335 + outer loop + vertex -865.052 253.154 41.3017 + vertex -865.905 251.209 37.3825 + vertex -859.533 247.504 40.801 + endloop + endfacet + facet normal -0.619375 -0.644786 0.447913 + outer loop + vertex -859.311 249.599 44.1236 + vertex -865.052 253.154 41.3017 + vertex -859.533 247.504 40.801 + endloop + endfacet + facet normal -0.617849 -0.665679 0.41849 + outer loop + vertex -864.832 255.057 44.6547 + vertex -865.052 253.154 41.3017 + vertex -859.311 249.599 44.1236 + endloop + endfacet + facet normal -0.62373 -0.670068 0.402455 + outer loop + vertex -859.828 251.489 46.4699 + vertex -864.832 255.057 44.6547 + vertex -859.311 249.599 44.1236 + endloop + endfacet + facet normal -0.624584 -0.688337 0.368899 + outer loop + vertex -865.049 256.611 47.187 + vertex -864.832 255.057 44.6547 + vertex -859.828 251.489 46.4699 + endloop + endfacet + facet normal -0.606954 -0.547511 0.576054 + outer loop + vertex -861.746 242.965 32.7076 + vertex -868.049 246.557 29.4805 + vertex -863.764 240.478 28.2176 + endloop + endfacet + facet normal -0.572113 -0.596608 0.562802 + outer loop + vertex -855.573 240.009 36.1992 + vertex -856.927 237.425 32.0837 + vertex -852.317 235.922 35.1767 + endloop + endfacet + facet normal -0.572514 -0.596779 0.562212 + outer loop + vertex -851.247 238.502 39.0045 + vertex -855.573 240.009 36.1992 + vertex -852.317 235.922 35.1767 + endloop + endfacet + facet normal -0.549177 -0.613791 0.567156 + outer loop + vertex -851.247 238.502 39.0045 + vertex -852.317 235.922 35.1767 + vertex -849.512 235.523 37.4615 + endloop + endfacet + facet normal -0.535433 -0.587453 0.606803 + outer loop + vertex -847.285 229.296 33.2908 + vertex -848.672 232.83 35.487 + vertex -850.201 230.139 31.5323 + endloop + endfacet + facet normal -0.569682 -0.560724 0.600875 + outer loop + vertex -852.326 230.388 29.8169 + vertex -850.733 232.903 33.6743 + vertex -853.627 233.263 31.2669 + endloop + endfacet + facet normal -0.539681 -0.563853 0.625151 + outer loop + vertex -847.285 229.296 33.2908 + vertex -850.201 230.139 31.5323 + vertex -849.389 226.117 28.6065 + endloop + endfacet + facet normal -0.529302 -0.572379 0.626276 + outer loop + vertex -847.285 229.296 33.2908 + vertex -849.389 226.117 28.6065 + vertex -843.986 223.989 31.2286 + endloop + endfacet + facet normal -0.52984 -0.550831 0.644868 + outer loop + vertex -844.021 219.753 27.5812 + vertex -843.986 223.989 31.2286 + vertex -849.389 226.117 28.6065 + endloop + endfacet + facet normal -0.516449 -0.556259 0.651042 + outer loop + vertex -843.986 223.989 31.2286 + vertex -844.021 219.753 27.5812 + vertex -839.529 218.005 29.6509 + endloop + endfacet + facet normal -0.516435 -0.545657 0.659965 + outer loop + vertex -839.154 215.423 27.8102 + vertex -839.529 218.005 29.6509 + vertex -844.021 219.753 27.5812 + endloop + endfacet + facet normal -0.514669 -0.546113 0.660966 + outer loop + vertex -835.684 212.79 28.3355 + vertex -839.529 218.005 29.6509 + vertex -839.154 215.423 27.8102 + endloop + endfacet + facet normal -0.508646 -0.535552 0.674139 + outer loop + vertex -835.684 212.79 28.3355 + vertex -839.154 215.423 27.8102 + vertex -836.368 211.457 26.7604 + endloop + endfacet + facet normal -0.506822 -0.536872 0.674463 + outer loop + vertex -832.713 208.188 26.9053 + vertex -835.684 212.79 28.3355 + vertex -836.368 211.457 26.7604 + endloop + endfacet + facet normal -0.498556 -0.534114 0.682762 + outer loop + vertex -831.806 209.31 28.4448 + vertex -835.684 212.79 28.3355 + vertex -832.713 208.188 26.9053 + endloop + endfacet + facet normal -0.497002 -0.535468 0.682834 + outer loop + vertex -829.124 204.858 26.906 + vertex -831.806 209.31 28.4448 + vertex -832.713 208.188 26.9053 + endloop + endfacet + facet normal -0.49056 -0.528525 0.692829 + outer loop + vertex -829.124 204.858 26.906 + vertex -832.713 208.188 26.9053 + vertex -830.189 204.053 25.5378 + endloop + endfacet + facet normal -0.486518 -0.532532 0.692611 + outer loop + vertex -828.195 205.919 28.3747 + vertex -831.806 209.31 28.4448 + vertex -829.124 204.858 26.906 + endloop + endfacet + facet normal -0.485219 -0.533693 0.692629 + outer loop + vertex -825.737 201.791 26.9154 + vertex -828.195 205.919 28.3747 + vertex -829.124 204.858 26.906 + endloop + endfacet + facet normal -0.482349 -0.530509 0.697065 + outer loop + vertex -825.737 201.791 26.9154 + vertex -829.124 204.858 26.906 + vertex -826.673 200.889 25.5813 + endloop + endfacet + facet normal -0.476059 -0.531158 0.700885 + outer loop + vertex -824.846 202.893 28.3561 + vertex -828.195 205.919 28.3747 + vertex -825.737 201.791 26.9154 + endloop + endfacet + facet normal -0.474863 -0.532175 0.700924 + outer loop + vertex -822.424 198.926 26.9856 + vertex -824.846 202.893 28.3561 + vertex -825.737 201.791 26.9154 + endloop + endfacet + facet normal -0.475052 -0.532401 0.700624 + outer loop + vertex -822.424 198.926 26.9856 + vertex -825.737 201.791 26.9154 + vertex -823.352 198.039 25.6824 + endloop + endfacet + facet normal -0.467491 -0.529956 0.70753 + outer loop + vertex -821.517 200.038 28.4175 + vertex -824.846 202.893 28.3561 + vertex -822.424 198.926 26.9856 + endloop + endfacet + facet normal -0.465734 -0.531444 0.707573 + outer loop + vertex -819.004 196.066 27.0883 + vertex -821.517 200.038 28.4175 + vertex -822.424 198.926 26.9856 + endloop + endfacet + facet normal -0.46792 -0.534185 0.704057 + outer loop + vertex -819.004 196.066 27.0883 + vertex -822.424 198.926 26.9856 + vertex -820.073 195.27 25.7738 + endloop + endfacet + facet normal -0.460501 -0.52971 0.712283 + outer loop + vertex -818.1 197.205 28.5198 + vertex -821.517 200.038 28.4175 + vertex -819.004 196.066 27.0883 + endloop + endfacet + facet normal -0.457452 -0.532233 0.712366 + outer loop + vertex -815.454 193.222 27.2433 + vertex -818.1 197.205 28.5198 + vertex -819.004 196.066 27.0883 + endloop + endfacet + facet normal -0.460912 -0.536864 0.706638 + outer loop + vertex -815.454 193.222 27.2433 + vertex -819.004 196.066 27.0883 + vertex -816.523 192.313 25.8554 + endloop + endfacet + facet normal -0.452695 -0.530465 0.716711 + outer loop + vertex -814.738 194.542 28.6716 + vertex -818.1 197.205 28.5198 + vertex -815.454 193.222 27.2433 + endloop + endfacet + facet normal -0.448445 -0.533347 0.717243 + outer loop + vertex -811.924 190.691 27.5679 + vertex -814.738 194.542 28.6716 + vertex -815.454 193.222 27.2433 + endloop + endfacet + facet normal -0.453051 -0.54087 0.708664 + outer loop + vertex -811.924 190.691 27.5679 + vertex -815.454 193.222 27.2433 + vertex -812.673 189.343 26.0601 + endloop + endfacet + facet normal -0.442574 -0.530665 0.722857 + outer loop + vertex -811.928 192.497 28.8913 + vertex -814.738 194.542 28.6716 + vertex -811.924 190.691 27.5679 + endloop + endfacet + facet normal -0.434648 -0.53294 0.725987 + outer loop + vertex -811.928 192.497 28.8913 + vertex -811.924 190.691 27.5679 + vertex -808.514 189.02 28.3824 + endloop + endfacet + facet normal -0.405934 -0.509536 0.758677 + outer loop + vertex -808.514 189.02 28.3824 + vertex -810.69 193.059 29.9311 + vertex -811.928 192.497 28.8913 + endloop + endfacet + facet normal -0.412506 -0.500107 0.761401 + outer loop + vertex -810.69 193.059 29.9311 + vertex -813.935 195.805 29.9769 + vertex -811.928 192.497 28.8913 + endloop + endfacet + facet normal -0.380204 -0.462598 0.800904 + outer loop + vertex -810.69 193.059 29.9311 + vertex -813.06 197.312 31.2623 + vertex -813.935 195.805 29.9769 + endloop + endfacet + facet normal -0.376592 -0.464976 0.801234 + outer loop + vertex -813.06 197.312 31.2623 + vertex -816.222 199.556 31.0785 + vertex -813.935 195.805 29.9769 + endloop + endfacet + facet normal -0.401838 -0.47498 0.782892 + outer loop + vertex -813.935 195.805 29.9769 + vertex -816.222 199.556 31.0785 + vertex -817.208 198.48 29.9198 + endloop + endfacet + facet normal -0.425752 -0.504926 0.750856 + outer loop + vertex -813.935 195.805 29.9769 + vertex -817.208 198.48 29.9198 + vertex -814.738 194.542 28.6716 + endloop + endfacet + facet normal -0.400633 -0.47605 0.78286 + outer loop + vertex -816.222 199.556 31.0785 + vertex -819.721 202.899 31.3208 + vertex -817.208 198.48 29.9198 + endloop + endfacet + facet normal -0.412189 -0.47995 0.774434 + outer loop + vertex -817.208 198.48 29.9198 + vertex -819.721 202.899 31.3208 + vertex -820.588 201.283 29.8579 + endloop + endfacet + facet normal -0.436085 -0.509487 0.74179 + outer loop + vertex -817.208 198.48 29.9198 + vertex -820.588 201.283 29.8579 + vertex -818.1 197.205 28.5198 + endloop + endfacet + facet normal -0.402855 -0.485992 0.775577 + outer loop + vertex -819.721 202.899 31.3208 + vertex -822.927 205.231 31.1171 + vertex -820.588 201.283 29.8579 + endloop + endfacet + facet normal -0.428699 -0.49499 0.755779 + outer loop + vertex -820.588 201.283 29.8579 + vertex -822.927 205.231 31.1171 + vertex -823.925 204.132 29.8309 + endloop + endfacet + facet normal -0.445535 -0.514933 0.732354 + outer loop + vertex -820.588 201.283 29.8579 + vertex -823.925 204.132 29.8309 + vertex -821.517 200.038 28.4175 + endloop + endfacet + facet normal -0.4228 -0.500213 0.755663 + outer loop + vertex -822.927 205.231 31.1171 + vertex -826.396 208.739 31.4981 + vertex -823.925 204.132 29.8309 + endloop + endfacet + facet normal -0.44104 -0.505019 0.741916 + outer loop + vertex -823.925 204.132 29.8309 + vertex -826.396 208.739 31.4981 + vertex -827.249 207.102 29.8764 + endloop + endfacet + facet normal -0.455453 -0.520847 0.721998 + outer loop + vertex -823.925 204.132 29.8309 + vertex -827.249 207.102 29.8764 + vertex -824.846 202.893 28.3561 + endloop + endfacet + facet normal -0.430244 -0.51211 0.743393 + outer loop + vertex -826.396 208.739 31.4981 + vertex -829.696 211.419 31.4341 + vertex -827.249 207.102 29.8764 + endloop + endfacet + facet normal -0.459777 -0.520286 0.719658 + outer loop + vertex -827.249 207.102 29.8764 + vertex -829.696 211.419 31.4341 + vertex -830.824 210.494 30.0448 + endloop + endfacet + facet normal -0.467083 -0.527488 0.709641 + outer loop + vertex -827.249 207.102 29.8764 + vertex -830.824 210.494 30.0448 + vertex -828.195 205.919 28.3747 + endloop + endfacet + facet normal -0.453867 -0.526422 0.718947 + outer loop + vertex -829.696 211.419 31.4341 + vertex -833.714 215.843 32.1376 + vertex -830.824 210.494 30.0448 + endloop + endfacet + facet normal -0.482673 -0.532685 0.695179 + outer loop + vertex -830.824 210.494 30.0448 + vertex -833.714 215.843 32.1376 + vertex -835.003 214.463 30.1849 + endloop + endfacet + facet normal -0.484287 -0.5343 0.692813 + outer loop + vertex -830.824 210.494 30.0448 + vertex -835.003 214.463 30.1849 + vertex -831.806 209.31 28.4448 + endloop + endfacet + facet normal -0.474282 -0.540337 0.695049 + outer loop + vertex -833.714 215.843 32.1376 + vertex -838.91 220.656 32.3332 + vertex -835.003 214.463 30.1849 + endloop + endfacet + facet normal -0.508936 -0.550621 0.661665 + outer loop + vertex -835.003 214.463 30.1849 + vertex -838.91 220.656 32.3332 + vertex -839.529 218.005 29.6509 + endloop + endfacet + facet normal -0.506587 -0.551908 0.662395 + outer loop + vertex -838.91 220.656 32.3332 + vertex -843.986 223.989 31.2286 + vertex -839.529 218.005 29.6509 + endloop + endfacet + facet normal -0.513556 -0.56927 0.642022 + outer loop + vertex -838.91 220.656 32.3332 + vertex -843.274 227.977 35.3332 + vertex -843.986 223.989 31.2286 + endloop + endfacet + facet normal -0.514108 -0.568981 0.641836 + outer loop + vertex -843.986 223.989 31.2286 + vertex -843.274 227.977 35.3332 + vertex -847.285 229.296 33.2908 + endloop + endfacet + facet normal -0.479764 -0.545924 0.686872 + outer loop + vertex -838.91 220.656 32.3332 + vertex -833.714 215.843 32.1376 + vertex -837.406 222.663 34.9786 + endloop + endfacet + facet normal -0.464158 -0.558464 0.687514 + outer loop + vertex -837.406 222.663 34.9786 + vertex -843.274 227.977 35.3332 + vertex -838.91 220.656 32.3332 + endloop + endfacet + facet normal -0.474824 -0.569158 0.671268 + outer loop + vertex -837.406 222.663 34.9786 + vertex -841.349 230.036 38.441 + vertex -843.274 227.977 35.3332 + endloop + endfacet + facet normal -0.445458 -0.59422 0.669679 + outer loop + vertex -843.274 227.977 35.3332 + vertex -841.349 230.036 38.441 + vertex -845.347 233.846 39.1626 + endloop + endfacet + facet normal -0.429918 -0.511697 0.743866 + outer loop + vertex -829.696 211.419 31.4341 + vertex -826.396 208.739 31.4981 + vertex -830.863 215.819 33.7864 + endloop + endfacet + facet normal -0.433506 -0.511578 0.741863 + outer loop + vertex -829.696 211.419 31.4341 + vertex -830.863 215.819 33.7864 + vertex -833.714 215.843 32.1376 + endloop + endfacet + facet normal -0.42651 -0.534817 0.729425 + outer loop + vertex -830.863 215.819 33.7864 + vertex -837.406 222.663 34.9786 + vertex -833.714 215.843 32.1376 + endloop + endfacet + facet normal -0.422083 -0.531459 0.734437 + outer loop + vertex -830.863 215.819 33.7864 + vertex -835.747 224.482 37.2481 + vertex -837.406 222.663 34.9786 + endloop + endfacet + facet normal -0.394083 -0.554833 0.732707 + outer loop + vertex -835.747 224.482 37.2481 + vertex -841.349 230.036 38.441 + vertex -837.406 222.663 34.9786 + endloop + endfacet + facet normal -0.400477 -0.559729 0.72548 + outer loop + vertex -835.747 224.482 37.2481 + vertex -840.164 231.908 40.5393 + vertex -841.349 230.036 38.441 + endloop + endfacet + facet normal -0.381642 -0.493427 0.781588 + outer loop + vertex -824.149 209.516 33.0856 + vertex -830.863 215.819 33.7864 + vertex -826.396 208.739 31.4981 + endloop + endfacet + facet normal -0.392843 -0.474098 0.787975 + outer loop + vertex -822.927 205.231 31.1171 + vertex -824.149 209.516 33.0856 + vertex -826.396 208.739 31.4981 + endloop + endfacet + facet normal -0.394984 -0.474191 0.786848 + outer loop + vertex -822.927 205.231 31.1171 + vertex -819.721 202.899 31.3208 + vertex -824.149 209.516 33.0856 + endloop + endfacet + facet normal -0.352146 -0.453959 0.818483 + outer loop + vertex -817.495 203.715 32.731 + vertex -824.149 209.516 33.0856 + vertex -819.721 202.899 31.3208 + endloop + endfacet + facet normal -0.361202 -0.437715 0.823371 + outer loop + vertex -816.222 199.556 31.0785 + vertex -817.495 203.715 32.731 + vertex -819.721 202.899 31.3208 + endloop + endfacet + facet normal -0.358394 -0.437407 0.82476 + outer loop + vertex -816.222 199.556 31.0785 + vertex -813.06 197.312 31.2623 + vertex -817.495 203.715 32.731 + endloop + endfacet + facet normal -0.329824 -0.422126 0.844409 + outer loop + vertex -810.83 198.157 32.556 + vertex -817.495 203.715 32.731 + vertex -813.06 197.312 31.2623 + endloop + endfacet + facet normal -0.33413 -0.414187 0.846644 + outer loop + vertex -809.606 194.073 31.0411 + vertex -810.83 198.157 32.556 + vertex -813.06 197.312 31.2623 + endloop + endfacet + facet normal -0.3379 -0.414674 0.844908 + outer loop + vertex -809.606 194.073 31.0411 + vertex -806.297 191.85 31.2736 + vertex -810.83 198.157 32.556 + endloop + endfacet + facet normal -0.312129 -0.399607 0.86191 + outer loop + vertex -803.771 192.601 32.5363 + vertex -810.83 198.157 32.556 + vertex -806.297 191.85 31.2736 + endloop + endfacet + facet normal -0.31407 -0.395259 0.863209 + outer loop + vertex -802.409 188.493 31.1506 + vertex -803.771 192.601 32.5363 + vertex -806.297 191.85 31.2736 + endloop + endfacet + facet normal -0.30753 -0.394068 0.866104 + outer loop + vertex -802.409 188.493 31.1506 + vertex -798.475 186.074 31.4468 + vertex -803.771 192.601 32.5363 + endloop + endfacet + facet normal -0.278587 -0.373695 0.884727 + outer loop + vertex -795.938 186.786 32.5465 + vertex -803.771 192.601 32.5363 + vertex -798.475 186.074 31.4468 + endloop + endfacet + facet normal -0.278031 -0.375056 0.884326 + outer loop + vertex -794.507 183.108 31.4365 + vertex -795.938 186.786 32.5465 + vertex -798.475 186.074 31.4468 + endloop + endfacet + facet normal -0.209997 -0.356456 0.910406 + outer loop + vertex -789.081 178.632 30.9357 + vertex -795.938 186.786 32.5465 + vertex -794.507 183.108 31.4365 + endloop + endfacet + facet normal -0.281748 -0.40846 0.868204 + outer loop + vertex -787.912 181.535 32.6807 + vertex -795.938 186.786 32.5465 + vertex -789.081 178.632 30.9357 + endloop + endfacet + facet normal -0.27363 -0.412221 0.869023 + outer loop + vertex -780.5 173.247 31.0831 + vertex -787.912 181.535 32.6807 + vertex -789.081 178.632 30.9357 + endloop + endfacet + facet normal -0.278309 -0.41579 0.865831 + outer loop + vertex -779.803 176.32 32.7829 + vertex -787.912 181.535 32.6807 + vertex -780.5 173.247 31.0831 + endloop + endfacet + facet normal -0.267557 -0.419194 0.867577 + outer loop + vertex -772.24 168.219 31.201 + vertex -779.803 176.32 32.7829 + vertex -780.5 173.247 31.0831 + endloop + endfacet + facet normal -0.263466 -0.415927 0.870397 + outer loop + vertex -771.748 171.386 32.8635 + vertex -779.803 176.32 32.7829 + vertex -772.24 168.219 31.201 + endloop + endfacet + facet normal -0.250271 -0.419195 0.87272 + outer loop + vertex -764.095 163.501 31.2706 + vertex -771.748 171.386 32.8635 + vertex -772.24 168.219 31.201 + endloop + endfacet + facet normal -0.248495 -0.417716 0.873936 + outer loop + vertex -763.646 166.712 32.9334 + vertex -771.748 171.386 32.8635 + vertex -764.095 163.501 31.2706 + endloop + endfacet + facet normal -0.236736 -0.420386 0.875918 + outer loop + vertex -755.906 159.025 31.3359 + vertex -763.646 166.712 32.9334 + vertex -764.095 163.501 31.2706 + endloop + endfacet + facet normal -0.242331 -0.425215 0.872048 + outer loop + vertex -755.408 162.234 33.0387 + vertex -763.646 166.712 32.9334 + vertex -755.906 159.025 31.3359 + endloop + endfacet + facet normal -0.232945 -0.427448 0.873513 + outer loop + vertex -747.581 154.724 31.4515 + vertex -755.408 162.234 33.0387 + vertex -755.906 159.025 31.3359 + endloop + endfacet + facet normal -0.243719 -0.437046 0.86579 + outer loop + vertex -747.059 157.929 33.2161 + vertex -755.408 162.234 33.0387 + vertex -747.581 154.724 31.4515 + endloop + endfacet + facet normal -0.234133 -0.439405 0.86724 + outer loop + vertex -739.195 150.608 31.63 + vertex -747.059 157.929 33.2161 + vertex -747.581 154.724 31.4515 + endloop + endfacet + facet normal -0.251218 -0.454965 0.85434 + outer loop + vertex -738.621 153.767 33.4807 + vertex -747.059 157.929 33.2161 + vertex -739.195 150.608 31.63 + endloop + endfacet + facet normal -0.237874 -0.458513 0.856261 + outer loop + vertex -730.763 146.594 31.8224 + vertex -738.621 153.767 33.4807 + vertex -739.195 150.608 31.63 + endloop + endfacet + facet normal -0.259358 -0.47809 0.839145 + outer loop + vertex -730.031 149.651 33.7905 + vertex -738.621 153.767 33.4807 + vertex -730.763 146.594 31.8224 + endloop + endfacet + facet normal -0.241482 -0.483727 0.841246 + outer loop + vertex -722.133 142.508 31.9508 + vertex -730.031 149.651 33.7905 + vertex -730.763 146.594 31.8224 + endloop + endfacet + facet normal -0.383751 -0.463823 0.798501 + outer loop + vertex -809.606 194.073 31.0411 + vertex -813.06 197.312 31.2623 + vertex -810.69 193.059 29.9311 + endloop + endfacet + facet normal -0.380173 -0.467303 0.798183 + outer loop + vertex -807.316 190.313 29.9304 + vertex -809.606 194.073 31.0411 + vertex -810.69 193.059 29.9311 + endloop + endfacet + facet normal -0.36707 -0.462026 0.807336 + outer loop + vertex -806.297 191.85 31.2736 + vertex -809.606 194.073 31.0411 + vertex -807.316 190.313 29.9304 + endloop + endfacet + facet normal -0.369098 -0.460591 0.807232 + outer loop + vertex -803.662 187.497 29.9942 + vertex -806.297 191.85 31.2736 + vertex -807.316 190.313 29.9304 + endloop + endfacet + facet normal -0.374123 -0.462611 0.803756 + outer loop + vertex -802.409 188.493 31.1506 + vertex -806.297 191.85 31.2736 + vertex -803.662 187.497 29.9942 + endloop + endfacet + facet normal -0.364289 -0.473119 0.802154 + outer loop + vertex -799.366 184.27 30.0421 + vertex -802.409 188.493 31.1506 + vertex -803.662 187.497 29.9942 + endloop + endfacet + facet normal -0.346598 -0.463823 0.815315 + outer loop + vertex -798.475 186.074 31.4468 + vertex -802.409 188.493 31.1506 + vertex -799.366 184.27 30.0421 + endloop + endfacet + facet normal -0.342175 -0.466343 0.815745 + outer loop + vertex -794.399 181.016 30.2654 + vertex -798.475 186.074 31.4468 + vertex -799.366 184.27 30.0421 + endloop + endfacet + facet normal -0.350177 -0.471325 0.809462 + outer loop + vertex -794.507 183.108 31.4365 + vertex -798.475 186.074 31.4468 + vertex -794.399 181.016 30.2654 + endloop + endfacet + facet normal -0.316734 -0.4758 0.820545 + outer loop + vertex -794.507 183.108 31.4365 + vertex -794.399 181.016 30.2654 + vertex -789.081 178.632 30.9357 + endloop + endfacet + facet normal -0.325517 -0.500558 0.802172 + outer loop + vertex -789.294 175.17 28.6892 + vertex -789.081 178.632 30.9357 + vertex -794.399 181.016 30.2654 + endloop + endfacet + facet normal -0.367622 -0.527542 0.765868 + outer loop + vertex -795.694 179.3 28.4619 + vertex -789.294 175.17 28.6892 + vertex -794.399 181.016 30.2654 + endloop + endfacet + facet normal -0.375996 -0.521383 0.76602 + outer loop + vertex -794.399 181.016 30.2654 + vertex -799.366 184.27 30.0421 + vertex -795.694 179.3 28.4619 + endloop + endfacet + facet normal -0.390361 -0.528198 0.754073 + outer loop + vertex -795.694 179.3 28.4619 + vertex -799.366 184.27 30.0421 + vertex -801.141 183.388 28.5052 + endloop + endfacet + facet normal -0.397779 -0.518377 0.757005 + outer loop + vertex -799.366 184.27 30.0421 + vertex -803.662 187.497 29.9942 + vertex -801.141 183.388 28.5052 + endloop + endfacet + facet normal -0.395962 -0.51776 0.758379 + outer loop + vertex -801.141 183.388 28.5052 + vertex -803.662 187.497 29.9942 + vertex -805.018 186.797 28.8081 + endloop + endfacet + facet normal -0.404088 -0.50703 0.761337 + outer loop + vertex -803.662 187.497 29.9942 + vertex -807.316 190.313 29.9304 + vertex -805.018 186.797 28.8081 + endloop + endfacet + facet normal -0.417137 -0.512185 0.750776 + outer loop + vertex -805.018 186.797 28.8081 + vertex -807.316 190.313 29.9304 + vertex -808.514 189.02 28.3824 + endloop + endfacet + facet normal -0.331583 -0.499145 0.800567 + outer loop + vertex -781.742 170.545 28.9331 + vertex -789.081 178.632 30.9357 + vertex -789.294 175.17 28.6892 + endloop + endfacet + facet normal -0.323631 -0.493582 0.807243 + outer loop + vertex -780.5 173.247 31.0831 + vertex -789.081 178.632 30.9357 + vertex -781.742 170.545 28.9331 + endloop + endfacet + facet normal -0.316881 -0.497098 0.807762 + outer loop + vertex -773.422 165.573 29.1377 + vertex -780.5 173.247 31.0831 + vertex -781.742 170.545 28.9331 + endloop + endfacet + facet normal -0.312107 -0.493693 0.8117 + outer loop + vertex -772.24 168.219 31.201 + vertex -780.5 173.247 31.0831 + vertex -773.422 165.573 29.1377 + endloop + endfacet + facet normal -0.299379 -0.50007 0.81259 + outer loop + vertex -765.161 160.799 29.2429 + vertex -772.24 168.219 31.201 + vertex -773.422 165.573 29.1377 + endloop + endfacet + facet normal -0.294584 -0.496527 0.816505 + outer loop + vertex -764.095 163.501 31.2706 + vertex -772.24 168.219 31.201 + vertex -765.161 160.799 29.2429 + endloop + endfacet + facet normal -0.281722 -0.50234 0.817488 + outer loop + vertex -757.004 156.307 29.2942 + vertex -764.095 163.501 31.2706 + vertex -765.161 160.799 29.2429 + endloop + endfacet + facet normal -0.280602 -0.501485 0.818398 + outer loop + vertex -755.906 159.025 31.3359 + vertex -764.095 163.501 31.2706 + vertex -757.004 156.307 29.2942 + endloop + endfacet + facet normal -0.269139 -0.506629 0.81908 + outer loop + vertex -748.752 152.022 29.3548 + vertex -755.906 159.025 31.3359 + vertex -757.004 156.307 29.2942 + endloop + endfacet + facet normal -0.275683 -0.511786 0.81368 + outer loop + vertex -747.581 154.724 31.4515 + vertex -755.906 159.025 31.3359 + vertex -748.752 152.022 29.3548 + endloop + endfacet + facet normal -0.264936 -0.51677 0.8141 + outer loop + vertex -740.304 147.888 29.4799 + vertex -747.581 154.724 31.4515 + vertex -748.752 152.022 29.3548 + endloop + endfacet + facet normal -0.274714 -0.524757 0.805706 + outer loop + vertex -739.195 150.608 31.63 + vertex -747.581 154.724 31.4515 + vertex -740.304 147.888 29.4799 + endloop + endfacet + facet normal -0.264325 -0.52936 0.80617 + outer loop + vertex -731.947 144.004 29.6697 + vertex -739.195 150.608 31.63 + vertex -740.304 147.888 29.4799 + endloop + endfacet + facet normal -0.274176 -0.537568 0.7974 + outer loop + vertex -730.763 146.594 31.8224 + vertex -739.195 150.608 31.63 + vertex -731.947 144.004 29.6697 + endloop + endfacet + facet normal -0.258267 -0.545038 0.797641 + outer loop + vertex -723.718 140.138 29.6922 + vertex -730.763 146.594 31.8224 + vertex -731.947 144.004 29.6697 + endloop + endfacet + facet normal -0.27647 -0.559525 0.781342 + outer loop + vertex -722.133 142.508 31.9508 + vertex -730.763 146.594 31.8224 + vertex -723.718 140.138 29.6922 + endloop + endfacet + facet normal -0.254628 -0.572349 0.779475 + outer loop + vertex -714.446 135.378 29.2263 + vertex -722.133 142.508 31.9508 + vertex -723.718 140.138 29.6922 + endloop + endfacet + facet normal -0.295068 -0.601709 0.742214 + outer loop + vertex -713.931 138.872 32.2633 + vertex -722.133 142.508 31.9508 + vertex -714.446 135.378 29.2263 + endloop + endfacet + facet normal -0.28268 -0.605233 0.744168 + outer loop + vertex -707.948 133.483 30.1535 + vertex -713.931 138.872 32.2633 + vertex -714.446 135.378 29.2263 + endloop + endfacet + facet normal -0.416888 -0.512403 0.750765 + outer loop + vertex -807.316 190.313 29.9304 + vertex -810.69 193.059 29.9311 + vertex -808.514 189.02 28.3824 + endloop + endfacet + facet normal -0.436889 -0.541142 0.718536 + outer loop + vertex -808.572 186.566 26.4993 + vertex -808.514 189.02 28.3824 + vertex -811.924 190.691 27.5679 + endloop + endfacet + facet normal -0.425939 -0.504791 0.750841 + outer loop + vertex -811.928 192.497 28.8913 + vertex -813.935 195.805 29.9769 + vertex -814.738 194.542 28.6716 + endloop + endfacet + facet normal -0.43678 -0.508954 0.741748 + outer loop + vertex -814.738 194.542 28.6716 + vertex -817.208 198.48 29.9198 + vertex -818.1 197.205 28.5198 + endloop + endfacet + facet normal -0.447526 -0.513338 0.73226 + outer loop + vertex -818.1 197.205 28.5198 + vertex -820.588 201.283 29.8579 + vertex -821.517 200.038 28.4175 + endloop + endfacet + facet normal -0.45811 -0.518707 0.721858 + outer loop + vertex -821.517 200.038 28.4175 + vertex -823.925 204.132 29.8309 + vertex -824.846 202.893 28.3561 + endloop + endfacet + facet normal -0.470267 -0.524801 0.70953 + outer loop + vertex -824.846 202.893 28.3561 + vertex -827.249 207.102 29.8764 + vertex -828.195 205.919 28.3747 + endloop + endfacet + facet normal -0.486426 -0.532437 0.692748 + outer loop + vertex -828.195 205.919 28.3747 + vertex -830.824 210.494 30.0448 + vertex -831.806 209.31 28.4448 + endloop + endfacet + facet normal -0.503652 -0.540058 0.674294 + outer loop + vertex -831.806 209.31 28.4448 + vertex -835.003 214.463 30.1849 + vertex -835.684 212.79 28.3355 + endloop + endfacet + facet normal -0.502682 -0.540692 0.67451 + outer loop + vertex -835.003 214.463 30.1849 + vertex -839.529 218.005 29.6509 + vertex -835.684 212.79 28.3355 + endloop + endfacet + facet normal -0.508701 -0.536245 0.673547 + outer loop + vertex -839.154 215.423 27.8102 + vertex -844.021 219.753 27.5812 + vertex -839.99 214.436 26.3922 + endloop + endfacet + facet normal -0.50921 -0.535786 0.673527 + outer loop + vertex -836.368 211.457 26.7604 + vertex -839.154 215.423 27.8102 + vertex -839.99 214.436 26.3922 + endloop + endfacet + facet normal -0.498345 -0.526766 0.6886 + outer loop + vertex -832.713 208.188 26.9053 + vertex -836.368 211.457 26.7604 + vertex -833.822 207.415 25.5111 + endloop + endfacet + facet normal -0.495523 -0.530006 0.68815 + outer loop + vertex -830.189 204.053 25.5378 + vertex -832.713 208.188 26.9053 + vertex -833.822 207.415 25.5111 + endloop + endfacet + facet normal -0.487352 -0.532043 0.692401 + outer loop + vertex -826.673 200.889 25.5813 + vertex -829.124 204.858 26.906 + vertex -830.189 204.053 25.5378 + endloop + endfacet + facet normal -0.479034 -0.533712 0.696906 + outer loop + vertex -823.352 198.039 25.6824 + vertex -825.737 201.791 26.9154 + vertex -826.673 200.889 25.5813 + endloop + endfacet + facet normal -0.471831 -0.5355 0.700439 + outer loop + vertex -820.073 195.27 25.7738 + vertex -822.424 198.926 26.9856 + vertex -823.352 198.039 25.6824 + endloop + endfacet + facet normal -0.464314 -0.538077 0.703482 + outer loop + vertex -816.523 192.313 25.8554 + vertex -819.004 196.066 27.0883 + vertex -820.073 195.27 25.7738 + endloop + endfacet + facet normal -0.455762 -0.542015 0.706046 + outer loop + vertex -812.673 189.343 26.0601 + vertex -815.454 193.222 27.2433 + vertex -816.523 192.313 25.8554 + endloop + endfacet + facet normal -0.445642 -0.545913 0.709494 + outer loop + vertex -812.673 189.343 26.0601 + vertex -808.572 186.566 26.4993 + vertex -811.924 190.691 27.5679 + endloop + endfacet + facet normal -0.432751 -0.54242 0.720074 + outer loop + vertex -804.374 184.236 27.2669 + vertex -808.514 189.02 28.3824 + vertex -808.572 186.566 26.4993 + endloop + endfacet + facet normal -0.43258 -0.542315 0.720256 + outer loop + vertex -805.018 186.797 28.8081 + vertex -808.514 189.02 28.3824 + vertex -804.374 184.236 27.2669 + endloop + endfacet + facet normal -0.420775 -0.543157 0.726587 + outer loop + vertex -805.018 186.797 28.8081 + vertex -804.374 184.236 27.2669 + vertex -801.141 183.388 28.5052 + endloop + endfacet + facet normal -0.420579 -0.551842 0.720128 + outer loop + vertex -804.374 184.236 27.2669 + vertex -798.818 178.957 26.4669 + vertex -801.141 183.388 28.5052 + endloop + endfacet + facet normal -0.406194 -0.549046 0.730448 + outer loop + vertex -795.694 179.3 28.4619 + vertex -801.141 183.388 28.5052 + vertex -798.818 178.957 26.4669 + endloop + endfacet + facet normal -0.40289 -0.556575 0.72657 + outer loop + vertex -791.8 174.143 26.6707 + vertex -795.694 179.3 28.4619 + vertex -798.818 178.957 26.4669 + endloop + endfacet + facet normal -0.378608 -0.545568 0.747671 + outer loop + vertex -789.294 175.17 28.6892 + vertex -795.694 179.3 28.4619 + vertex -791.8 174.143 26.6707 + endloop + endfacet + facet normal -0.37437 -0.551517 0.745437 + outer loop + vertex -784.36 168.964 26.5749 + vertex -789.294 175.17 28.6892 + vertex -791.8 174.143 26.6707 + endloop + endfacet + facet normal -0.356987 -0.542747 0.760253 + outer loop + vertex -781.742 170.545 28.9331 + vertex -789.294 175.17 28.6892 + vertex -784.36 168.964 26.5749 + endloop + endfacet + facet normal -0.350759 -0.549809 0.758075 + outer loop + vertex -775.727 163.694 26.7473 + vertex -781.742 170.545 28.9331 + vertex -784.36 168.964 26.5749 + endloop + endfacet + facet normal -0.345349 -0.546589 0.762872 + outer loop + vertex -773.422 165.573 29.1377 + vertex -781.742 170.545 28.9331 + vertex -775.727 163.694 26.7473 + endloop + endfacet + facet normal -0.335489 -0.555806 0.760609 + outer loop + vertex -767.346 159.179 27.1452 + vertex -773.422 165.573 29.1377 + vertex -775.727 163.694 26.7473 + endloop + endfacet + facet normal -0.328225 -0.550977 0.767263 + outer loop + vertex -765.161 160.799 29.2429 + vertex -773.422 165.573 29.1377 + vertex -767.346 159.179 27.1452 + endloop + endfacet + facet normal -0.316743 -0.562181 0.763954 + outer loop + vertex -758.929 154.255 27.011 + vertex -765.161 160.799 29.2429 + vertex -767.346 159.179 27.1452 + endloop + endfacet + facet normal -0.313024 -0.559765 0.767254 + outer loop + vertex -757.004 156.307 29.2942 + vertex -765.161 160.799 29.2429 + vertex -758.929 154.255 27.011 + endloop + endfacet + facet normal -0.303401 -0.5671 0.765732 + outer loop + vertex -750.984 150.367 27.2795 + vertex -757.004 156.307 29.2942 + vertex -758.929 154.255 27.011 + endloop + endfacet + facet normal -0.298333 -0.56353 0.770345 + outer loop + vertex -748.752 152.022 29.3548 + vertex -757.004 156.307 29.2942 + vertex -750.984 150.367 27.2795 + endloop + endfacet + facet normal -0.28824 -0.573099 0.767121 + outer loop + vertex -742.368 145.804 27.1082 + vertex -748.752 152.022 29.3548 + vertex -750.984 150.367 27.2795 + endloop + endfacet + facet normal -0.293551 -0.576813 0.762309 + outer loop + vertex -740.304 147.888 29.4799 + vertex -748.752 152.022 29.3548 + vertex -742.368 145.804 27.1082 + endloop + endfacet + facet normal -0.284393 -0.583789 0.760467 + outer loop + vertex -733.588 142.061 27.5187 + vertex -740.304 147.888 29.4799 + vertex -742.368 145.804 27.1082 + endloop + endfacet + facet normal -0.290885 -0.589067 0.753914 + outer loop + vertex -731.947 144.004 29.6697 + vertex -740.304 147.888 29.4799 + vertex -733.588 142.061 27.5187 + endloop + endfacet + facet normal -0.280437 -0.596129 0.75232 + outer loop + vertex -725.714 138.593 27.7053 + vertex -731.947 144.004 29.6697 + vertex -733.588 142.061 27.5187 + endloop + endfacet + facet normal -0.283143 -0.598261 0.749609 + outer loop + vertex -723.718 140.138 29.6922 + vertex -731.947 144.004 29.6697 + vertex -725.714 138.593 27.7053 + endloop + endfacet + facet normal -0.272866 -0.607195 0.746229 + outer loop + vertex -725.714 138.593 27.7053 + vertex -718.822 135.415 27.6399 + vertex -723.718 140.138 29.6922 + endloop + endfacet + facet normal -0.274984 -0.608566 0.744333 + outer loop + vertex -714.446 135.378 29.2263 + vertex -723.718 140.138 29.6922 + vertex -718.822 135.415 27.6399 + endloop + endfacet + facet normal -0.269144 -0.63088 0.727704 + outer loop + vertex -714.041 132.808 27.1476 + vertex -714.446 135.378 29.2263 + vertex -718.822 135.415 27.6399 + endloop + endfacet + facet normal -0.258775 -0.631704 0.730743 + outer loop + vertex -714.041 132.808 27.1476 + vertex -710.082 131.053 27.0325 + vertex -714.446 135.378 29.2263 + endloop + endfacet + facet normal -0.281231 -0.644397 0.711099 + outer loop + vertex -710.082 131.053 27.0325 + vertex -707.395 130.917 27.9724 + vertex -714.446 135.378 29.2263 + endloop + endfacet + facet normal -0.290581 -0.655285 0.697254 + outer loop + vertex -707.948 133.483 30.1535 + vertex -714.446 135.378 29.2263 + vertex -707.395 130.917 27.9724 + endloop + endfacet + facet normal -0.280739 -0.656006 0.700601 + outer loop + vertex -703.947 129.873 28.3768 + vertex -707.948 133.483 30.1535 + vertex -707.395 130.917 27.9724 + endloop + endfacet + facet normal -0.284767 -0.678335 0.677325 + outer loop + vertex -703.947 129.873 28.3768 + vertex -707.395 130.917 27.9724 + vertex -703.856 128.316 26.8552 + endloop + endfacet + facet normal -0.271383 -0.68065 0.68049 + outer loop + vertex -701.624 127.608 27.0375 + vertex -703.947 129.873 28.3768 + vertex -703.856 128.316 26.8552 + endloop + endfacet + facet normal -0.280523 -0.685138 0.67223 + outer loop + vertex -701.494 128.885 28.3928 + vertex -703.947 129.873 28.3768 + vertex -701.624 127.608 27.0375 + endloop + endfacet + facet normal -0.262831 -0.68964 0.674771 + outer loop + vertex -700.025 127.162 27.2038 + vertex -701.494 128.885 28.3928 + vertex -701.624 127.608 27.0375 + endloop + endfacet + facet normal -0.265994 -0.690718 0.672425 + outer loop + vertex -699.57 127.983 28.2271 + vertex -701.494 128.885 28.3928 + vertex -700.025 127.162 27.2038 + endloop + endfacet + facet normal -0.264172 -0.691553 0.672286 + outer loop + vertex -699.57 127.983 28.2271 + vertex -700.025 127.162 27.2038 + vertex -696.987 125.69 26.8835 + endloop + endfacet + facet normal -0.267852 -0.693934 0.668364 + outer loop + vertex -699.57 127.983 28.2271 + vertex -700.694 130.004 29.8754 + vertex -701.494 128.885 28.3928 + endloop + endfacet + facet normal -0.293656 -0.680039 0.671799 + outer loop + vertex -700.694 130.004 29.8754 + vertex -703.422 131.671 30.3707 + vertex -701.494 128.885 28.3928 + endloop + endfacet + facet normal -0.284526 -0.669397 0.68626 + outer loop + vertex -700.694 130.004 29.8754 + vertex -701.197 133.382 32.9616 + vertex -703.422 131.671 30.3707 + endloop + endfacet + facet normal -0.317876 -0.642562 0.697186 + outer loop + vertex -701.197 133.382 32.9616 + vertex -707.114 136.037 32.7112 + vertex -703.422 131.671 30.3707 + endloop + endfacet + facet normal -0.286679 -0.629554 0.722134 + outer loop + vertex -707.948 133.483 30.1535 + vertex -703.422 131.671 30.3707 + vertex -707.114 136.037 32.7112 + endloop + endfacet + facet normal -0.305959 -0.621938 0.72082 + outer loop + vertex -707.114 136.037 32.7112 + vertex -713.931 138.872 32.2633 + vertex -707.948 133.483 30.1535 + endloop + endfacet + facet normal -0.287599 -0.66902 0.685346 + outer loop + vertex -701.197 133.382 32.9616 + vertex -700.694 130.004 29.8754 + vertex -698.2 129.684 30.6095 + endloop + endfacet + facet normal -0.340588 -0.685404 0.6436 + outer loop + vertex -698.2 129.684 30.6095 + vertex -697.537 131.461 32.8526 + vertex -701.197 133.382 32.9616 + endloop + endfacet + facet normal -0.33097 -0.66836 0.666148 + outer loop + vertex -697.537 131.461 32.8526 + vertex -697.295 133.664 35.1831 + vertex -701.197 133.382 32.9616 + endloop + endfacet + facet normal -0.353571 -0.620705 0.699795 + outer loop + vertex -700.383 136.962 36.5489 + vertex -701.197 133.382 32.9616 + vertex -697.295 133.664 35.1831 + endloop + endfacet + facet normal -0.365902 -0.627186 0.687571 + outer loop + vertex -697.295 133.664 35.1831 + vertex -696.161 135.992 37.9109 + vertex -700.383 136.962 36.5489 + endloop + endfacet + facet normal -0.367566 -0.586852 0.721457 + outer loop + vertex -699.37 139.607 39.2158 + vertex -700.383 136.962 36.5489 + vertex -696.161 135.992 37.9109 + endloop + endfacet + facet normal -0.400612 -0.604359 0.688665 + outer loop + vertex -696.161 135.992 37.9109 + vertex -695.102 138.116 40.3904 + vertex -699.37 139.607 39.2158 + endloop + endfacet + facet normal -0.397358 -0.572697 0.717025 + outer loop + vertex -697.952 141.607 41.5993 + vertex -699.37 139.607 39.2158 + vertex -695.102 138.116 40.3904 + endloop + endfacet + facet normal -0.437825 -0.591807 0.676812 + outer loop + vertex -695.102 138.116 40.3904 + vertex -693.941 139.328 42.2016 + vertex -697.952 141.607 41.5993 + endloop + endfacet + facet normal -0.432503 -0.578545 0.691539 + outer loop + vertex -693.941 139.328 42.2016 + vertex -693.936 140.899 43.5185 + vertex -697.952 141.607 41.5993 + endloop + endfacet + facet normal -0.439962 -0.529643 0.725198 + outer loop + vertex -697.268 143.298 43.2492 + vertex -697.952 141.607 41.5993 + vertex -693.936 140.899 43.5185 + endloop + endfacet + facet normal -0.448786 -0.543692 0.709218 + outer loop + vertex -693.936 140.899 43.5185 + vertex -693.155 142.971 45.6015 + vertex -697.268 143.298 43.2492 + endloop + endfacet + facet normal -0.477839 -0.405617 0.779195 + outer loop + vertex -696.511 143.729 43.9377 + vertex -697.268 143.298 43.2492 + vertex -693.155 142.971 45.6015 + endloop + endfacet + facet normal 0.0962434 0.964653 0.245319 + outer loop + vertex -695.675 143.55 44.3153 + vertex -696.511 143.729 43.9377 + vertex -693.155 142.971 45.6015 + endloop + endfacet + facet normal -0.458262 -0.651217 0.604907 + outer loop + vertex -693.155 142.971 45.6015 + vertex -696.119 143.781 44.2272 + vertex -695.675 143.55 44.3153 + endloop + endfacet + facet normal -0.446545 -0.42454 0.787631 + outer loop + vertex -695.675 143.55 44.3153 + vertex -697.781 144.27 43.5095 + vertex -696.511 143.729 43.9377 + endloop + endfacet + facet normal -0.431218 -0.471516 0.769236 + outer loop + vertex -696.511 143.729 43.9377 + vertex -699.85 144.859 42.7589 + vertex -697.268 143.298 43.2492 + endloop + endfacet + facet normal -0.426344 -0.556257 0.713309 + outer loop + vertex -693.155 142.971 45.6015 + vertex -693.936 140.899 43.5185 + vertex -689.896 138.879 44.358 + endloop + endfacet + facet normal -0.464801 -0.574781 0.673488 + outer loop + vertex -689.896 138.879 44.358 + vertex -688.718 138.817 45.1181 + vertex -693.155 142.971 45.6015 + endloop + endfacet + facet normal -0.526523 -0.628899 0.572066 + outer loop + vertex -688.941 139.7 45.8842 + vertex -693.155 142.971 45.6015 + vertex -688.718 138.817 45.1181 + endloop + endfacet + facet normal -0.437792 -0.645502 0.625832 + outer loop + vertex -689.896 138.879 44.358 + vertex -684.629 135.443 44.4983 + vertex -688.718 138.817 45.1181 + endloop + endfacet + facet normal -0.440967 -0.607312 0.660848 + outer loop + vertex -690.619 137.92 42.9942 + vertex -689.896 138.879 44.358 + vertex -693.936 140.899 43.5185 + endloop + endfacet + facet normal -0.404264 -0.633461 0.659771 + outer loop + vertex -690.619 137.92 42.9942 + vertex -685.396 135.007 43.3981 + vertex -689.896 138.879 44.358 + endloop + endfacet + facet normal -0.419687 -0.541221 0.728658 + outer loop + vertex -697.268 143.298 43.2492 + vertex -703.429 145.519 41.3509 + vertex -697.952 141.607 41.5993 + endloop + endfacet + facet normal -0.414215 -0.584075 0.698056 + outer loop + vertex -693.936 140.899 43.5185 + vertex -693.941 139.328 42.2016 + vertex -690.619 137.92 42.9942 + endloop + endfacet + facet normal -0.423822 -0.637486 0.643418 + outer loop + vertex -691.253 136.497 41.167 + vertex -690.619 137.92 42.9942 + vertex -693.941 139.328 42.2016 + endloop + endfacet + facet normal -0.387594 -0.657325 0.646293 + outer loop + vertex -691.253 136.497 41.167 + vertex -686.215 133.991 41.6395 + vertex -690.619 137.92 42.9942 + endloop + endfacet + facet normal -0.398062 -0.623727 0.67269 + outer loop + vertex -693.941 139.328 42.2016 + vertex -695.102 138.116 40.3904 + vertex -691.253 136.497 41.167 + endloop + endfacet + facet normal -0.402046 -0.643377 0.65148 + outer loop + vertex -692.164 134.744 38.8738 + vertex -691.253 136.497 41.167 + vertex -695.102 138.116 40.3904 + endloop + endfacet + facet normal -0.359802 -0.666803 0.652623 + outer loop + vertex -692.164 134.744 38.8738 + vertex -687.184 132.576 39.4039 + vertex -691.253 136.497 41.167 + endloop + endfacet + facet normal -0.405834 -0.566704 0.71704 + outer loop + vertex -697.952 141.607 41.5993 + vertex -704.312 143.927 39.8335 + vertex -699.37 139.607 39.2158 + endloop + endfacet + facet normal -0.361908 -0.626046 0.690716 + outer loop + vertex -695.102 138.116 40.3904 + vertex -696.161 135.992 37.9109 + vertex -692.164 134.744 38.8738 + endloop + endfacet + facet normal -0.364062 -0.654928 0.662215 + outer loop + vertex -693.419 132.898 36.3583 + vertex -692.164 134.744 38.8738 + vertex -696.161 135.992 37.9109 + endloop + endfacet + facet normal -0.330132 -0.674903 0.659938 + outer loop + vertex -693.419 132.898 36.3583 + vertex -688.43 131.024 36.9366 + vertex -692.164 134.744 38.8738 + endloop + endfacet + facet normal -0.377623 -0.581849 0.720314 + outer loop + vertex -699.37 139.607 39.2158 + vertex -705.042 141.619 37.8675 + vertex -700.383 136.962 36.5489 + endloop + endfacet + facet normal -0.335672 -0.642935 0.688447 + outer loop + vertex -696.161 135.992 37.9109 + vertex -697.295 133.664 35.1831 + vertex -693.419 132.898 36.3583 + endloop + endfacet + facet normal -0.33277 -0.676366 0.65711 + outer loop + vertex -694.854 131.408 34.0973 + vertex -693.419 132.898 36.3583 + vertex -697.295 133.664 35.1831 + endloop + endfacet + facet normal -0.310898 -0.690828 0.652763 + outer loop + vertex -694.854 131.408 34.0973 + vertex -690.086 129.715 34.5763 + vertex -693.419 132.898 36.3583 + endloop + endfacet + facet normal -0.350908 -0.621736 0.70022 + outer loop + vertex -700.383 136.962 36.5489 + vertex -705.947 138.799 35.3912 + vertex -701.197 133.382 32.9616 + endloop + endfacet + facet normal -0.322954 -0.670805 0.667624 + outer loop + vertex -697.295 133.664 35.1831 + vertex -697.537 131.461 32.8526 + vertex -694.854 131.408 34.0973 + endloop + endfacet + facet normal -0.312387 -0.698657 0.643656 + outer loop + vertex -695.645 130.557 32.7902 + vertex -694.854 131.408 34.0973 + vertex -697.537 131.461 32.8526 + endloop + endfacet + facet normal -0.31967 -0.712588 0.624524 + outer loop + vertex -697.537 131.461 32.8526 + vertex -695.259 129.319 31.5749 + vertex -695.645 130.557 32.7902 + endloop + endfacet + facet normal -0.304999 -0.713813 0.630434 + outer loop + vertex -692.379 129.145 32.7714 + vertex -695.645 130.557 32.7902 + vertex -695.259 129.319 31.5749 + endloop + endfacet + facet normal -0.302329 -0.721535 0.622884 + outer loop + vertex -695.259 129.319 31.5749 + vertex -689.57 126.752 31.3624 + vertex -692.379 129.145 32.7714 + endloop + endfacet + facet normal -0.313201 -0.727191 0.610818 + outer loop + vertex -685.319 125.894 32.5213 + vertex -692.379 129.145 32.7714 + vertex -689.57 126.752 31.3624 + endloop + endfacet + facet normal -0.309681 -0.720305 0.620692 + outer loop + vertex -692.379 129.145 32.7714 + vertex -685.319 125.894 32.5213 + vertex -690.086 129.715 34.5763 + endloop + endfacet + facet normal -0.315994 -0.712667 0.626302 + outer loop + vertex -694.854 131.408 34.0973 + vertex -692.379 129.145 32.7714 + vertex -690.086 129.715 34.5763 + endloop + endfacet + facet normal -0.302653 -0.722177 0.621982 + outer loop + vertex -695.259 129.319 31.5749 + vertex -692.395 127.175 30.4793 + vertex -689.57 126.752 31.3624 + endloop + endfacet + facet normal -0.301632 -0.727618 0.616109 + outer loop + vertex -692.395 127.175 30.4793 + vertex -686.138 124.527 30.4155 + vertex -689.57 126.752 31.3624 + endloop + endfacet + facet normal -0.308798 -0.733932 0.604969 + outer loop + vertex -689.57 126.752 31.3624 + vertex -686.138 124.527 30.4155 + vertex -682.879 123.577 30.9264 + endloop + endfacet + facet normal -0.30967 -0.743524 0.592686 + outer loop + vertex -686.138 124.527 30.4155 + vertex -678.774 121.326 30.247 + vertex -682.879 123.577 30.9264 + endloop + endfacet + facet normal -0.312057 -0.748611 0.58498 + outer loop + vertex -678.774 121.326 30.247 + vertex -686.138 124.527 30.4155 + vertex -681.741 122.467 30.1249 + endloop + endfacet + facet normal -0.316113 -0.761148 0.566327 + outer loop + vertex -681.741 122.467 30.1249 + vertex -678.892 121.229 30.051 + vertex -678.774 121.326 30.247 + endloop + endfacet + facet normal -0.314563 -0.762125 0.565876 + outer loop + vertex -678.892 121.229 30.051 + vertex -675.825 119.94 30.0196 + vertex -678.774 121.326 30.247 + endloop + endfacet + facet normal -0.316337 -0.766187 0.559365 + outer loop + vertex -675.825 119.94 30.0196 + vertex -678.892 121.229 30.051 + vertex -680.903 121.962 29.9175 + endloop + endfacet + facet normal -0.325385 -0.790993 0.518126 + outer loop + vertex -680.903 121.962 29.9175 + vertex -673.606 118.936 29.8798 + vertex -675.825 119.94 30.0196 + endloop + endfacet + facet normal -0.328726 -0.796821 0.506967 + outer loop + vertex -672.538 118.577 30.0086 + vertex -675.825 119.94 30.0196 + vertex -673.606 118.936 29.8798 + endloop + endfacet + facet normal -0.329867 -0.805462 0.492361 + outer loop + vertex -669.667 117.44 30.0716 + vertex -672.538 118.577 30.0086 + vertex -673.606 118.936 29.8798 + endloop + endfacet + facet normal -0.327575 -0.797621 0.506453 + outer loop + vertex -669.667 117.44 30.0716 + vertex -673.606 118.936 29.8798 + vertex -669.556 117.188 29.747 + endloop + endfacet + facet normal -0.316686 -0.775412 0.546302 + outer loop + vertex -673.095 118.503 29.5614 + vertex -669.556 117.188 29.747 + vertex -673.606 118.936 29.8798 + endloop + endfacet + facet normal -0.316726 -0.775427 0.546258 + outer loop + vertex -673.095 118.503 29.5614 + vertex -673.606 118.936 29.8798 + vertex -677.561 120.352 29.5969 + endloop + endfacet + facet normal -0.307198 -0.753098 0.581784 + outer loop + vertex -676.459 119.511 29.0908 + vertex -673.095 118.503 29.5614 + vertex -677.561 120.352 29.5969 + endloop + endfacet + facet normal -0.314123 -0.766566 0.560092 + outer loop + vertex -671.5 117.573 29.1831 + vertex -669.556 117.188 29.747 + vertex -673.095 118.503 29.5614 + endloop + endfacet + facet normal -0.332866 -0.806652 0.488378 + outer loop + vertex -675.825 119.94 30.0196 + vertex -672.538 118.577 30.0086 + vertex -673.387 118.999 30.1267 + endloop + endfacet + facet normal -0.313781 -0.76359 0.564334 + outer loop + vertex -673.606 118.936 29.8798 + vertex -680.903 121.962 29.9175 + vertex -677.561 120.352 29.5969 + endloop + endfacet + facet normal -0.308898 -0.755999 0.577103 + outer loop + vertex -681.904 122.137 29.6108 + vertex -677.561 120.352 29.5969 + vertex -680.903 121.962 29.9175 + endloop + endfacet + facet normal -0.308605 -0.757499 0.575289 + outer loop + vertex -681.904 122.137 29.6108 + vertex -680.903 121.962 29.9175 + vertex -687.713 124.441 29.5288 + endloop + endfacet + facet normal -0.303685 -0.744405 0.594673 + outer loop + vertex -682.128 121.882 29.1772 + vertex -681.904 122.137 29.6108 + vertex -687.713 124.441 29.5288 + endloop + endfacet + facet normal -0.301546 -0.732639 0.610172 + outer loop + vertex -687.713 124.441 29.5288 + vertex -680.903 121.962 29.9175 + vertex -687.972 124.987 30.0555 + endloop + endfacet + facet normal -0.301926 -0.732639 0.609985 + outer loop + vertex -687.713 124.441 29.5288 + vertex -687.972 124.987 30.0555 + vertex -691.407 126.363 30.0089 + endloop + endfacet + facet normal -0.298486 -0.723641 0.622294 + outer loop + vertex -691.043 126.379 30.2015 + vertex -691.407 126.363 30.0089 + vertex -687.972 124.987 30.0555 + endloop + endfacet + facet normal -0.302088 -0.730548 0.612407 + outer loop + vertex -689.574 125.82 30.2597 + vertex -691.043 126.379 30.2015 + vertex -687.972 124.987 30.0555 + endloop + endfacet + facet normal -0.304206 -0.733495 0.60782 + outer loop + vertex -687.501 124.92 30.2106 + vertex -689.574 125.82 30.2597 + vertex -687.972 124.987 30.0555 + endloop + endfacet + facet normal -0.303758 -0.735526 0.605585 + outer loop + vertex -684.948 123.809 30.1425 + vertex -687.501 124.92 30.2106 + vertex -687.972 124.987 30.0555 + endloop + endfacet + facet normal -0.306662 -0.743852 0.593838 + outer loop + vertex -687.972 124.987 30.0555 + vertex -680.903 121.962 29.9175 + vertex -684.948 123.809 30.1425 + endloop + endfacet + facet normal -0.312772 -0.755086 0.576211 + outer loop + vertex -681.741 122.467 30.1249 + vertex -684.948 123.809 30.1425 + vertex -680.903 121.962 29.9175 + endloop + endfacet + facet normal -0.302549 -0.732973 0.609274 + outer loop + vertex -687.501 124.92 30.2106 + vertex -684.948 123.809 30.1425 + vertex -686.138 124.527 30.4155 + endloop + endfacet + facet normal -0.302163 -0.72913 0.614057 + outer loop + vertex -689.574 125.82 30.2597 + vertex -687.501 124.92 30.2106 + vertex -686.138 124.527 30.4155 + endloop + endfacet + facet normal -0.3006 -0.725999 0.618519 + outer loop + vertex -691.043 126.379 30.2015 + vertex -689.574 125.82 30.2597 + vertex -692.395 127.175 30.4793 + endloop + endfacet + facet normal -0.298466 -0.72368 0.622258 + outer loop + vertex -691.407 126.363 30.0089 + vertex -691.043 126.379 30.2015 + vertex -692.395 127.175 30.4793 + endloop + endfacet + facet normal -0.293678 -0.720977 0.627651 + outer loop + vertex -694.333 127.347 29.7703 + vertex -691.407 126.363 30.0089 + vertex -692.395 127.175 30.4793 + endloop + endfacet + facet normal -0.29488 -0.716694 0.631978 + outer loop + vertex -692.395 127.175 30.4793 + vertex -695.891 128.681 30.5557 + vertex -694.333 127.347 29.7703 + endloop + endfacet + facet normal -0.297171 -0.717917 0.629511 + outer loop + vertex -698.2 129.684 30.6095 + vertex -694.333 127.347 29.7703 + vertex -695.891 128.681 30.5557 + endloop + endfacet + facet normal -0.296306 -0.716061 0.632027 + outer loop + vertex -695.891 128.681 30.5557 + vertex -695.259 129.319 31.5749 + vertex -698.2 129.684 30.6095 + endloop + endfacet + facet normal -0.304002 -0.744228 0.594733 + outer loop + vertex -682.128 121.882 29.1772 + vertex -677.561 120.352 29.5969 + vertex -681.904 122.137 29.6108 + endloop + endfacet + facet normal -0.313591 -0.75585 0.574761 + outer loop + vertex -678.892 121.229 30.051 + vertex -681.741 122.467 30.1249 + vertex -680.903 121.962 29.9175 + endloop + endfacet + facet normal -0.303935 -0.734366 0.606902 + outer loop + vertex -684.948 123.809 30.1425 + vertex -681.741 122.467 30.1249 + vertex -686.138 124.527 30.4155 + endloop + endfacet + facet normal -0.301824 -0.728057 0.615496 + outer loop + vertex -686.138 124.527 30.4155 + vertex -692.395 127.175 30.4793 + vertex -689.574 125.82 30.2597 + endloop + endfacet + facet normal -0.294969 -0.716888 0.631716 + outer loop + vertex -695.891 128.681 30.5557 + vertex -692.395 127.175 30.4793 + vertex -695.259 129.319 31.5749 + endloop + endfacet + facet normal -0.301348 -0.705514 0.641436 + outer loop + vertex -695.645 130.557 32.7902 + vertex -692.379 129.145 32.7714 + vertex -694.854 131.408 34.0973 + endloop + endfacet + facet normal -0.299031 -0.703004 0.645264 + outer loop + vertex -697.537 131.461 32.8526 + vertex -698.2 129.684 30.6095 + vertex -695.259 129.319 31.5749 + endloop + endfacet + facet normal -0.283334 -0.697098 0.658617 + outer loop + vertex -700.694 130.004 29.8754 + vertex -699.315 128.815 29.2099 + vertex -698.2 129.684 30.6095 + endloop + endfacet + facet normal -0.273613 -0.70413 0.655239 + outer loop + vertex -696.576 127.15 28.5641 + vertex -698.2 129.684 30.6095 + vertex -699.315 128.815 29.2099 + endloop + endfacet + facet normal -0.269151 -0.699442 0.662071 + outer loop + vertex -699.315 128.815 29.2099 + vertex -699.57 127.983 28.2271 + vertex -696.576 127.15 28.5641 + endloop + endfacet + facet normal -0.280453 -0.69543 0.661607 + outer loop + vertex -699.315 128.815 29.2099 + vertex -700.694 130.004 29.8754 + vertex -699.57 127.983 28.2271 + endloop + endfacet + facet normal -0.276994 -0.676213 0.68265 + outer loop + vertex -701.494 128.885 28.3928 + vertex -703.422 131.671 30.3707 + vertex -703.947 129.873 28.3768 + endloop + endfacet + facet normal -0.272448 -0.668064 0.692432 + outer loop + vertex -703.856 128.316 26.8552 + vertex -707.395 130.917 27.9724 + vertex -706.323 129.041 26.584 + endloop + endfacet + facet normal -0.300038 -0.667832 0.681159 + outer loop + vertex -703.422 131.671 30.3707 + vertex -707.948 133.483 30.1535 + vertex -703.947 129.873 28.3768 + endloop + endfacet + facet normal -0.275359 -0.668536 0.690823 + outer loop + vertex -706.323 129.041 26.584 + vertex -707.395 130.917 27.9724 + vertex -710.082 131.053 27.0325 + endloop + endfacet + facet normal -0.25751 -0.65439 0.710959 + outer loop + vertex -693.181 123.465 26.1343 + vertex -688.574 122.075 26.5236 + vertex -693.017 124.011 26.6967 + endloop + endfacet + facet normal -0.269261 -0.691047 0.670785 + outer loop + vertex -693.017 124.011 26.6967 + vertex -689.701 123.079 27.0674 + vertex -693.508 124.915 27.4303 + endloop + endfacet + facet normal -0.268293 -0.693848 0.668277 + outer loop + vertex -696.987 125.69 26.8835 + vertex -696.576 127.15 28.5641 + vertex -699.57 127.983 28.2271 + endloop + endfacet + facet normal -0.278282 -0.703509 0.653938 + outer loop + vertex -693.508 124.915 27.4303 + vertex -688.394 123.225 27.7888 + vertex -692.452 125.207 28.1937 + endloop + endfacet + facet normal -0.286057 -0.706084 0.647779 + outer loop + vertex -698.2 129.684 30.6095 + vertex -696.576 127.15 28.5641 + vertex -694.333 127.347 29.7703 + endloop + endfacet + facet normal -0.28913 -0.720651 0.630131 + outer loop + vertex -692.452 125.207 28.1937 + vertex -687.863 123.76 28.645 + vertex -692.492 125.842 28.9025 + endloop + endfacet + facet normal -0.305673 -0.752244 0.583688 + outer loop + vertex -676.459 119.511 29.0908 + vertex -677.561 120.352 29.5969 + vertex -682.128 121.882 29.1772 + endloop + endfacet + facet normal -0.308019 -0.760688 0.571382 + outer loop + vertex -671.5 117.573 29.1831 + vertex -673.095 118.503 29.5614 + vertex -676.459 119.511 29.0908 + endloop + endfacet + facet normal -0.312374 -0.776437 0.547329 + outer loop + vertex -667.998 116.242 29.2944 + vertex -669.556 117.188 29.747 + vertex -671.5 117.573 29.1831 + endloop + endfacet + facet normal -0.316377 -0.779693 0.540356 + outer loop + vertex -667.998 116.242 29.2944 + vertex -666.909 116.136 29.7785 + vertex -669.556 117.188 29.747 + endloop + endfacet + facet normal -0.323011 -0.797295 0.509886 + outer loop + vertex -669.556 117.188 29.747 + vertex -666.909 116.136 29.7785 + vertex -667.628 116.582 30.0213 + endloop + endfacet + facet normal -0.315673 -0.781318 0.538417 + outer loop + vertex -665.605 115.227 29.2241 + vertex -666.909 116.136 29.7785 + vertex -667.998 116.242 29.2944 + endloop + endfacet + facet normal -0.292505 -0.722696 0.626219 + outer loop + vertex -670.419 116.757 28.6913 + vertex -675.484 118.569 28.4176 + vertex -673.058 116.992 27.7307 + endloop + endfacet + facet normal -0.305283 -0.759338 0.574637 + outer loop + vertex -667.474 115.55 28.6577 + vertex -665.605 115.227 29.2241 + vertex -667.998 116.242 29.2944 + endloop + endfacet + facet normal -0.297929 -0.724994 0.620985 + outer loop + vertex -666.284 114.462 27.9248 + vertex -664.378 114.298 28.6476 + vertex -665.308 114.73 28.7059 + endloop + endfacet + facet normal -0.368992 -0.764254 0.528924 + outer loop + vertex -664.378 114.298 28.6476 + vertex -663.008 113.116 27.8956 + vertex -664.199 114.469 29.0202 + endloop + endfacet + facet normal -0.32473 -0.786411 0.52546 + outer loop + vertex -666.909 116.136 29.7785 + vertex -665.605 115.227 29.2241 + vertex -665.834 115.669 29.7447 + endloop + endfacet + facet normal 0.676838 0.468818 0.567539 + outer loop + vertex -666.359 116.166 30.1934 + vertex -664.199 114.469 29.0202 + vertex -665.285 115.329 29.6047 + endloop + endfacet + facet normal 0.382601 0.806765 -0.450274 + outer loop + vertex -665.285 115.329 29.6047 + vertex -666.376 116.129 30.1113 + vertex -666.359 116.166 30.1934 + endloop + endfacet + facet normal -0.0570861 -0.903936 0.42384 + outer loop + vertex -666.376 116.129 30.1113 + vertex -666.248 116.24 30.3659 + vertex -666.359 116.166 30.1934 + endloop + endfacet + facet normal 0.351649 0.758036 -0.549294 + outer loop + vertex -666.248 116.24 30.3659 + vertex -665.068 116.071 30.8872 + vertex -666.359 116.166 30.1934 + endloop + endfacet + facet normal -0.333509 -0.803256 0.493509 + outer loop + vertex -665.068 116.071 30.8872 + vertex -666.248 116.24 30.3659 + vertex -665.228 115.81 30.3547 + endloop + endfacet + facet normal -0.332606 -0.803671 0.493443 + outer loop + vertex -663.936 115.469 30.6714 + vertex -665.068 116.071 30.8872 + vertex -665.228 115.81 30.3547 + endloop + endfacet + facet normal -0.333645 -0.794219 0.507836 + outer loop + vertex -663.936 115.469 30.6714 + vertex -665.228 115.81 30.3547 + vertex -662.776 114.63 30.1212 + endloop + endfacet + facet normal -0.335413 -0.795047 0.50537 + outer loop + vertex -662.776 114.63 30.1212 + vertex -660.919 114.162 30.6161 + vertex -663.936 115.469 30.6714 + endloop + endfacet + facet normal -0.338281 -0.801169 0.493654 + outer loop + vertex -662.849 115.358 31.2359 + vertex -663.936 115.469 30.6714 + vertex -660.919 114.162 30.6161 + endloop + endfacet + facet normal -0.34041 -0.802617 0.489824 + outer loop + vertex -660.919 114.162 30.6161 + vertex -659.29 113.958 31.4152 + vertex -662.849 115.358 31.2359 + endloop + endfacet + facet normal -0.341401 -0.805926 0.483661 + outer loop + vertex -661.528 115.142 31.8077 + vertex -662.849 115.358 31.2359 + vertex -659.29 113.958 31.4152 + endloop + endfacet + facet normal -0.348653 -0.813567 0.465349 + outer loop + vertex -658.633 114.364 32.6168 + vertex -661.528 115.142 31.8077 + vertex -659.29 113.958 31.4152 + endloop + endfacet + facet normal -0.346943 -0.814627 0.464772 + outer loop + vertex -653.131 111.524 31.7468 + vertex -658.633 114.364 32.6168 + vertex -659.29 113.958 31.4152 + endloop + endfacet + facet normal -0.343858 -0.804062 0.485021 + outer loop + vertex -655.327 111.713 30.503 + vertex -653.131 111.524 31.7468 + vertex -659.29 113.958 31.4152 + endloop + endfacet + facet normal -0.342464 -0.806344 0.482212 + outer loop + vertex -653.131 111.524 31.7468 + vertex -655.327 111.713 30.503 + vertex -647.604 108.393 30.4361 + endloop + endfacet + facet normal -0.342307 -0.806209 0.482549 + outer loop + vertex -644.589 108.016 31.945 + vertex -653.131 111.524 31.7468 + vertex -647.604 108.393 30.4361 + endloop + endfacet + facet normal -0.340364 -0.809883 0.477747 + outer loop + vertex -644.589 108.016 31.945 + vertex -647.604 108.393 30.4361 + vertex -638.976 104.781 30.4594 + endloop + endfacet + facet normal -0.337355 -0.807487 0.483897 + outer loop + vertex -635.592 104.223 31.8878 + vertex -644.589 108.016 31.945 + vertex -638.976 104.781 30.4594 + endloop + endfacet + facet normal -0.33549 -0.811913 0.477748 + outer loop + vertex -635.592 104.223 31.8878 + vertex -638.976 104.781 30.4594 + vertex -631.432 101.775 30.6482 + endloop + endfacet + facet normal -0.332004 -0.809378 0.484438 + outer loop + vertex -628.359 101.205 31.8024 + vertex -635.592 104.223 31.8878 + vertex -631.432 101.775 30.6482 + endloop + endfacet + facet normal -0.330352 -0.814018 0.477747 + outer loop + vertex -628.359 101.205 31.8024 + vertex -631.432 101.775 30.6482 + vertex -626.37 99.8879 30.9337 + endloop + endfacet + facet normal -0.327902 -0.812795 0.481503 + outer loop + vertex -623.589 99.2966 31.8291 + vertex -628.359 101.205 31.8024 + vertex -626.37 99.8879 30.9337 + endloop + endfacet + facet normal -0.326725 -0.817068 0.475026 + outer loop + vertex -623.589 99.2966 31.8291 + vertex -626.37 99.8879 30.9337 + vertex -623.605 98.9496 31.2211 + endloop + endfacet + facet normal -0.326206 -0.81723 0.475105 + outer loop + vertex -623.605 98.9496 31.2211 + vertex -621.197 98.4211 31.9655 + vertex -623.589 99.2966 31.8291 + endloop + endfacet + facet normal -0.329199 -0.828991 0.452107 + outer loop + vertex -620.955 98.776 32.7922 + vertex -623.589 99.2966 31.8291 + vertex -621.197 98.4211 31.9655 + endloop + endfacet + facet normal -0.328241 -0.829423 0.452013 + outer loop + vertex -621.197 98.4211 31.9655 + vertex -618.453 97.8927 32.9888 + vertex -620.955 98.776 32.7922 + endloop + endfacet + facet normal -0.330511 -0.841216 0.427923 + outer loop + vertex -618.467 98.3371 33.8515 + vertex -620.955 98.776 32.7922 + vertex -618.453 97.8927 32.9888 + endloop + endfacet + facet normal -0.32835 -0.841872 0.428296 + outer loop + vertex -618.453 97.8927 32.9888 + vertex -615.431 97.4141 34.3649 + vertex -618.467 98.3371 33.8515 + endloop + endfacet + facet normal -0.327938 -0.853529 0.404902 + outer loop + vertex -617.216 98.3208 34.8299 + vertex -618.467 98.3371 33.8515 + vertex -615.431 97.4141 34.3649 + endloop + endfacet + facet normal -0.328357 -0.853841 0.403903 + outer loop + vertex -615.976 98.2343 35.6552 + vertex -617.216 98.3208 34.8299 + vertex -615.431 97.4141 34.3649 + endloop + endfacet + facet normal -0.324166 -0.854425 0.406046 + outer loop + vertex -615.431 97.4141 34.3649 + vertex -611.172 96.652 36.1614 + vertex -615.976 98.2343 35.6552 + endloop + endfacet + facet normal -0.32414 -0.854163 0.406619 + outer loop + vertex -616.636 98.9198 36.5692 + vertex -615.976 98.2343 35.6552 + vertex -611.172 96.652 36.1614 + endloop + endfacet + facet normal -0.33107 -0.853948 0.401454 + outer loop + vertex -615.976 98.2343 35.6552 + vertex -616.636 98.9198 36.5692 + vertex -620.056 100.339 36.7678 + endloop + endfacet + facet normal -0.334603 -0.856419 0.393175 + outer loop + vertex -620.056 100.339 36.7678 + vertex -619.679 99.7712 35.8515 + vertex -615.976 98.2343 35.6552 + endloop + endfacet + facet normal -0.344549 -0.854796 0.388085 + outer loop + vertex -620.056 100.339 36.7678 + vertex -624.931 102.461 37.1137 + vertex -619.679 99.7712 35.8515 + endloop + endfacet + facet normal -0.344547 -0.854794 0.38809 + outer loop + vertex -624.931 102.461 37.1137 + vertex -624.426 101.798 36.1019 + vertex -619.679 99.7712 35.8515 + endloop + endfacet + facet normal -0.341749 -0.84986 0.401179 + outer loop + vertex -619.679 99.7712 35.8515 + vertex -624.426 101.798 36.1019 + vertex -620.773 99.7599 34.8959 + endloop + endfacet + facet normal -0.337944 -0.8534 0.396866 + outer loop + vertex -619.679 99.7712 35.8515 + vertex -620.773 99.7599 34.8959 + vertex -617.216 98.3208 34.8299 + endloop + endfacet + facet normal -0.345203 -0.851812 0.394019 + outer loop + vertex -624.426 101.798 36.1019 + vertex -627.074 102.489 35.2756 + vertex -620.773 99.7599 34.8959 + endloop + endfacet + facet normal -0.339888 -0.842789 0.417352 + outer loop + vertex -620.773 99.7599 34.8959 + vertex -627.074 102.489 35.2756 + vertex -622.755 100.052 33.8713 + endloop + endfacet + facet normal -0.336954 -0.847385 0.410367 + outer loop + vertex -620.773 99.7599 34.8959 + vertex -622.755 100.052 33.8713 + vertex -618.467 98.3371 33.8515 + endloop + endfacet + facet normal -0.342092 -0.844108 0.412862 + outer loop + vertex -627.074 102.489 35.2756 + vertex -628.205 102.368 34.0904 + vertex -622.755 100.052 33.8713 + endloop + endfacet + facet normal -0.337086 -0.834502 0.435867 + outer loop + vertex -622.755 100.052 33.8713 + vertex -628.205 102.368 34.0904 + vertex -625.309 100.546 32.8431 + endloop + endfacet + facet normal -0.335646 -0.837742 0.430733 + outer loop + vertex -622.755 100.052 33.8713 + vertex -625.309 100.546 32.8431 + vertex -620.955 98.776 32.7922 + endloop + endfacet + facet normal -0.341325 -0.836423 0.428828 + outer loop + vertex -628.205 102.368 34.0904 + vertex -632.066 103.51 33.2448 + vertex -625.309 100.546 32.8431 + endloop + endfacet + facet normal -0.334114 -0.823903 0.457768 + outer loop + vertex -625.309 100.546 32.8431 + vertex -632.066 103.51 33.2448 + vertex -628.359 101.205 31.8024 + endloop + endfacet + facet normal -0.341388 -0.835854 0.429886 + outer loop + vertex -628.205 102.368 34.0904 + vertex -636.111 106.269 35.3965 + vertex -632.066 103.51 33.2448 + endloop + endfacet + facet normal -0.349311 -0.838447 0.418316 + outer loop + vertex -636.111 106.269 35.3965 + vertex -641.252 107.561 33.6928 + vertex -632.066 103.51 33.2448 + endloop + endfacet + facet normal -0.350261 -0.835473 0.423441 + outer loop + vertex -636.111 106.269 35.3965 + vertex -647.194 111.152 35.8645 + vertex -641.252 107.561 33.6928 + endloop + endfacet + facet normal -0.354284 -0.837565 0.415894 + outer loop + vertex -647.194 111.152 35.8645 + vertex -651.519 111.92 33.7264 + vertex -641.252 107.561 33.6928 + endloop + endfacet + facet normal -0.347872 -0.822724 0.449567 + outer loop + vertex -641.252 107.561 33.6928 + vertex -651.519 111.92 33.7264 + vertex -644.589 108.016 31.945 + endloop + endfacet + facet normal -0.345632 -0.82652 0.444301 + outer loop + vertex -641.252 107.561 33.6928 + vertex -644.589 108.016 31.945 + vertex -635.592 104.223 31.8878 + endloop + endfacet + facet normal -0.34105 -0.823575 0.453221 + outer loop + vertex -635.592 104.223 31.8878 + vertex -632.066 103.51 33.2448 + vertex -641.252 107.561 33.6928 + endloop + endfacet + facet normal -0.356462 -0.833744 0.42167 + outer loop + vertex -651.519 111.92 33.7264 + vertex -647.194 111.152 35.8645 + vertex -654.613 114.303 35.823 + endloop + endfacet + facet normal -0.359562 -0.834362 0.417797 + outer loop + vertex -654.613 114.303 35.823 + vertex -657.471 114.723 34.2013 + vertex -651.519 111.92 33.7264 + endloop + endfacet + facet normal -0.352291 -0.823481 0.444713 + outer loop + vertex -657.471 114.723 34.2013 + vertex -658.633 114.364 32.6168 + vertex -651.519 111.92 33.7264 + endloop + endfacet + facet normal -0.352063 -0.823648 0.444584 + outer loop + vertex -657.471 114.723 34.2013 + vertex -660.432 115.607 33.495 + vertex -658.633 114.364 32.6168 + endloop + endfacet + facet normal -0.345973 -0.821263 0.453685 + outer loop + vertex -660.432 115.607 33.495 + vertex -662.735 115.738 31.9752 + vertex -658.633 114.364 32.6168 + endloop + endfacet + facet normal -0.334528 -0.835942 0.435077 + outer loop + vertex -662.735 115.738 31.9752 + vertex -660.432 115.607 33.495 + vertex -662.292 115.947 32.7172 + endloop + endfacet + facet normal -0.350461 -0.83577 0.422689 + outer loop + vertex -658.314 115.638 35.3122 + vertex -660.432 115.607 33.495 + vertex -657.471 114.723 34.2013 + endloop + endfacet + facet normal -0.340031 -0.845989 0.410708 + outer loop + vertex -660.432 115.607 33.495 + vertex -658.314 115.638 35.3122 + vertex -659.979 115.909 34.4929 + endloop + endfacet + facet normal -0.358797 -0.835515 0.416149 + outer loop + vertex -654.613 114.303 35.823 + vertex -658.314 115.638 35.3122 + vertex -657.471 114.723 34.2013 + endloop + endfacet + facet normal -0.359325 -0.843222 0.399828 + outer loop + vertex -656.114 115.703 37.4272 + vertex -658.314 115.638 35.3122 + vertex -654.613 114.303 35.823 + endloop + endfacet + facet normal -0.362635 -0.843255 0.396758 + outer loop + vertex -651.677 114.047 37.9624 + vertex -656.114 115.703 37.4272 + vertex -654.613 114.303 35.823 + endloop + endfacet + facet normal -0.363224 -0.849118 0.383493 + outer loop + vertex -653.987 115.809 39.6752 + vertex -656.114 115.703 37.4272 + vertex -651.677 114.047 37.9624 + endloop + endfacet + facet normal -0.365433 -0.849387 0.380789 + outer loop + vertex -648.763 113.776 40.154 + vertex -653.987 115.809 39.6752 + vertex -651.677 114.047 37.9624 + endloop + endfacet + facet normal -0.362881 -0.852143 0.377054 + outer loop + vertex -648.763 113.776 40.154 + vertex -651.677 114.047 37.9624 + vertex -643.556 110.533 37.8375 + endloop + endfacet + facet normal -0.361493 -0.851653 0.379487 + outer loop + vertex -643.556 110.533 37.8375 + vertex -640.402 109.799 39.1922 + vertex -648.763 113.776 40.154 + endloop + endfacet + facet normal -0.369864 -0.861565 0.347717 + outer loop + vertex -640.402 109.799 39.1922 + vertex -642.478 111.408 40.9725 + vertex -648.763 113.776 40.154 + endloop + endfacet + facet normal -0.369401 -0.853434 0.367686 + outer loop + vertex -650.131 115.242 42.1812 + vertex -648.763 113.776 40.154 + vertex -642.478 111.408 40.9725 + endloop + endfacet + facet normal -0.371437 -0.853211 0.36615 + outer loop + vertex -650.131 115.242 42.1812 + vertex -652.752 116.188 41.7295 + vertex -648.763 113.776 40.154 + endloop + endfacet + facet normal -0.371562 -0.848909 0.375893 + outer loop + vertex -652.59 116.64 42.9096 + vertex -652.752 116.188 41.7295 + vertex -650.131 115.242 42.1812 + endloop + endfacet + facet normal -0.379886 -0.853518 0.356642 + outer loop + vertex -651.686 116.362 43.2071 + vertex -652.59 116.64 42.9096 + vertex -650.131 115.242 42.1812 + endloop + endfacet + facet normal -0.382922 -0.8539 0.352457 + outer loop + vertex -651.686 116.362 43.2071 + vertex -650.131 115.242 42.1812 + vertex -648.123 114.705 43.0637 + endloop + endfacet + facet normal -0.381872 -0.847769 0.368051 + outer loop + vertex -652.786 116.892 43.2866 + vertex -652.59 116.64 42.9096 + vertex -651.686 116.362 43.2071 + endloop + endfacet + facet normal -0.381494 -0.847229 0.369682 + outer loop + vertex -652.786 116.892 43.2866 + vertex -651.686 116.362 43.2071 + vertex -652.961 117.015 43.3864 + endloop + endfacet + facet normal -0.383091 -0.847555 0.367276 + outer loop + vertex -652.59 116.64 42.9096 + vertex -652.786 116.892 43.2866 + vertex -652.961 117.015 43.3864 + endloop + endfacet + facet normal -0.372863 -0.848354 0.375858 + outer loop + vertex -652.752 116.188 41.7295 + vertex -652.59 116.64 42.9096 + vertex -652.961 117.015 43.3864 + endloop + endfacet + facet normal -0.362287 -0.86128 0.356292 + outer loop + vertex -642.478 111.408 40.9725 + vertex -640.402 109.799 39.1922 + vertex -631.512 105.848 38.6811 + endloop + endfacet + facet normal -0.380179 -0.874208 0.302034 + outer loop + vertex -632.609 106.762 39.9469 + vertex -642.478 111.408 40.9725 + vertex -631.512 105.848 38.6811 + endloop + endfacet + facet normal -0.365904 -0.87558 0.315394 + outer loop + vertex -632.609 106.762 39.9469 + vertex -631.512 105.848 38.6811 + vertex -623.236 102.126 37.9512 + endloop + endfacet + facet normal -0.36971 -0.87817 0.303533 + outer loop + vertex -632.609 106.762 39.9469 + vertex -623.236 102.126 37.9512 + vertex -626.323 103.881 39.2673 + endloop + endfacet + facet normal -0.375851 -0.88488 0.27518 + outer loop + vertex -626.323 103.881 39.2673 + vertex -629.523 105.483 40.0496 + vertex -632.609 106.762 39.9469 + endloop + endfacet + facet normal -0.353726 -0.859161 0.369756 + outer loop + vertex -623.236 102.126 37.9512 + vertex -631.512 105.848 38.6811 + vertex -624.418 102.493 37.6732 + endloop + endfacet + facet normal -0.352637 -0.86458 0.357979 + outer loop + vertex -624.418 102.493 37.6732 + vertex -620.056 100.339 36.7678 + vertex -623.236 102.126 37.9512 + endloop + endfacet + facet normal -0.352897 -0.858267 0.372613 + outer loop + vertex -624.418 102.493 37.6732 + vertex -631.512 105.848 38.6811 + vertex -624.931 102.461 37.1137 + endloop + endfacet + facet normal -0.353714 -0.858861 0.370465 + outer loop + vertex -631.512 105.848 38.6811 + vertex -632.617 105.673 37.2212 + vertex -624.931 102.461 37.1137 + endloop + endfacet + facet normal -0.389718 -0.88445 0.256649 + outer loop + vertex -639.744 110.329 41.4066 + vertex -642.478 111.408 40.9725 + vertex -632.609 106.762 39.9469 + endloop + endfacet + facet normal -0.39087 -0.871657 0.295693 + outer loop + vertex -642.478 111.408 40.9725 + vertex -639.744 110.329 41.4066 + vertex -644.075 112.55 42.2262 + endloop + endfacet + facet normal -0.358653 -0.855366 0.373787 + outer loop + vertex -631.512 105.848 38.6811 + vertex -640.402 109.799 39.1922 + vertex -632.617 105.673 37.2212 + endloop + endfacet + facet normal -0.359306 -0.855811 0.372139 + outer loop + vertex -640.402 109.799 39.1922 + vertex -643.556 110.533 37.8375 + vertex -632.617 105.673 37.2212 + endloop + endfacet + facet normal -0.353187 -0.845607 0.40026 + outer loop + vertex -632.617 105.673 37.2212 + vertex -643.556 110.533 37.8375 + vertex -636.111 106.269 35.3965 + endloop + endfacet + facet normal -0.350274 -0.850114 0.39321 + outer loop + vertex -632.617 105.673 37.2212 + vertex -636.111 106.269 35.3965 + vertex -627.074 102.489 35.2756 + endloop + endfacet + facet normal -0.35919 -0.844342 0.397579 + outer loop + vertex -647.194 111.152 35.8645 + vertex -643.556 110.533 37.8375 + vertex -651.677 114.047 37.9624 + endloop + endfacet + facet normal -0.365688 -0.850895 0.377161 + outer loop + vertex -652.752 116.188 41.7295 + vertex -653.987 115.809 39.6752 + vertex -648.763 113.776 40.154 + endloop + endfacet + facet normal -0.363271 -0.852445 0.375994 + outer loop + vertex -653.987 115.809 39.6752 + vertex -652.752 116.188 41.7295 + vertex -654.36 116.588 41.0811 + endloop + endfacet + facet normal -0.358479 -0.853059 0.379187 + outer loop + vertex -656.114 115.703 37.4272 + vertex -653.987 115.809 39.6752 + vertex -655.963 116.277 38.8598 + endloop + endfacet + facet normal -0.350154 -0.851393 0.39054 + outer loop + vertex -658.314 115.638 35.3122 + vertex -656.114 115.703 37.4272 + vertex -657.864 116.036 36.583 + endloop + endfacet + facet normal -0.361093 -0.845007 0.394431 + outer loop + vertex -651.677 114.047 37.9624 + vertex -654.613 114.303 35.823 + vertex -647.194 111.152 35.8645 + endloop + endfacet + facet normal -0.356959 -0.847699 0.392412 + outer loop + vertex -643.556 110.533 37.8375 + vertex -647.194 111.152 35.8645 + vertex -636.111 106.269 35.3965 + endloop + endfacet + facet normal -0.346064 -0.840787 0.416313 + outer loop + vertex -628.205 102.368 34.0904 + vertex -627.074 102.489 35.2756 + vertex -636.111 106.269 35.3965 + endloop + endfacet + facet normal -0.346393 -0.848087 0.400949 + outer loop + vertex -624.426 101.798 36.1019 + vertex -632.617 105.673 37.2212 + vertex -627.074 102.489 35.2756 + endloop + endfacet + facet normal -0.351422 -0.853829 0.384029 + outer loop + vertex -624.426 101.798 36.1019 + vertex -624.931 102.461 37.1137 + vertex -632.617 105.673 37.2212 + endloop + endfacet + facet normal -0.348806 -0.861474 0.369048 + outer loop + vertex -624.418 102.493 37.6732 + vertex -624.931 102.461 37.1137 + vertex -620.056 100.339 36.7678 + endloop + endfacet + facet normal -0.331412 -0.854552 0.399883 + outer loop + vertex -616.636 98.9198 36.5692 + vertex -623.236 102.126 37.9512 + vertex -620.056 100.339 36.7678 + endloop + endfacet + facet normal -0.348802 -0.869128 0.350648 + outer loop + vertex -623.236 102.126 37.9512 + vertex -616.636 98.9198 36.5692 + vertex -617.898 99.6488 37.1208 + endloop + endfacet + facet normal -0.317108 -0.867222 0.383886 + outer loop + vertex -611.172 96.652 36.1614 + vertex -615.431 97.4141 34.3649 + vertex -613.256 96.7631 34.6905 + endloop + endfacet + facet normal -0.321223 -0.862951 0.39004 + outer loop + vertex -613.256 96.7631 34.6905 + vertex -611.242 95.9652 34.5841 + vertex -611.172 96.652 36.1614 + endloop + endfacet + facet normal -0.382775 -0.840678 0.383072 + outer loop + vertex -610.077 95.1542 33.968 + vertex -611.172 96.652 36.1614 + vertex -611.242 95.9652 34.5841 + endloop + endfacet + facet normal -0.408038 -0.846233 0.342628 + outer loop + vertex -610.077 95.1542 33.968 + vertex -611.242 95.9652 34.5841 + vertex -610.047 94.9764 33.565 + endloop + endfacet + facet normal -0.558319 -0.773734 0.299359 + outer loop + vertex -610.047 94.9764 33.565 + vertex -609.038 93.668 32.0656 + vertex -610.077 95.1542 33.968 + endloop + endfacet + facet normal -0.128876 0.702587 -0.699831 + outer loop + vertex -610.047 94.9764 33.565 + vertex -609.148 93.8823 32.3011 + vertex -609.038 93.668 32.0656 + endloop + endfacet + facet normal -0.405577 -0.813819 0.416181 + outer loop + vertex -610.177 95.1009 33.681 + vertex -609.148 93.8823 32.3011 + vertex -610.047 94.9764 33.565 + endloop + endfacet + facet normal -0.315481 -0.815639 0.484979 + outer loop + vertex -610.177 95.1009 33.681 + vertex -609.64 94.2155 32.5415 + vertex -609.148 93.8823 32.3011 + endloop + endfacet + facet normal -0.268741 -0.817886 0.508763 + outer loop + vertex -610.963 95.57 34.0205 + vertex -609.64 94.2155 32.5415 + vertex -610.177 95.1009 33.681 + endloop + endfacet + facet normal -0.315868 -0.84328 0.434863 + outer loop + vertex -610.177 95.1009 33.681 + vertex -611.242 95.9652 34.5841 + vertex -610.963 95.57 34.0205 + endloop + endfacet + facet normal -0.314639 -0.843387 0.435547 + outer loop + vertex -612.49 96.358 34.4431 + vertex -610.963 95.57 34.0205 + vertex -611.242 95.9652 34.5841 + endloop + endfacet + facet normal -0.303145 -0.834392 0.460318 + outer loop + vertex -611.805 95.8474 33.9683 + vertex -610.963 95.57 34.0205 + vertex -612.49 96.358 34.4431 + endloop + endfacet + facet normal -0.311154 -0.836506 0.451044 + outer loop + vertex -611.805 95.8474 33.9683 + vertex -612.49 96.358 34.4431 + vertex -613.086 96.2448 33.8215 + endloop + endfacet + facet normal -0.310601 -0.830604 0.462194 + outer loop + vertex -613.086 96.2448 33.8215 + vertex -611.858 95.3716 33.0778 + vertex -611.805 95.8474 33.9683 + endloop + endfacet + facet normal -0.305833 -0.832088 0.462705 + outer loop + vertex -611.805 95.8474 33.9683 + vertex -611.858 95.3716 33.0778 + vertex -610.677 94.9837 33.161 + endloop + endfacet + facet normal -0.302694 -0.816233 0.492077 + outer loop + vertex -611.858 95.3716 33.0778 + vertex -610.687 94.2458 31.9306 + vertex -610.677 94.9837 33.161 + endloop + endfacet + facet normal -0.290392 -0.819555 0.493966 + outer loop + vertex -610.677 94.9837 33.161 + vertex -610.687 94.2458 31.9306 + vertex -609.887 94.1417 32.2283 + endloop + endfacet + facet normal -0.335742 -0.822826 0.458513 + outer loop + vertex -609.887 94.1417 32.2283 + vertex -609.64 94.2155 32.5415 + vertex -610.677 94.9837 33.161 + endloop + endfacet + facet normal -0.405293 -0.765454 0.499818 + outer loop + vertex -609.887 94.1417 32.2283 + vertex -609.575 93.0693 30.839 + vertex -609.64 94.2155 32.5415 + endloop + endfacet + facet normal -0.346581 -0.784205 0.514689 + outer loop + vertex -609.64 94.2155 32.5415 + vertex -609.575 93.0693 30.839 + vertex -608.496 92.2494 30.3162 + endloop + endfacet + facet normal -0.257799 -0.785999 0.561913 + outer loop + vertex -609.64 94.2155 32.5415 + vertex -608.496 92.2494 30.3162 + vertex -609.148 93.8823 32.3011 + endloop + endfacet + facet normal -0.245606 -0.786646 0.566451 + outer loop + vertex -609.148 93.8823 32.3011 + vertex -608.496 92.2494 30.3162 + vertex -608.129 92.2737 30.509 + endloop + endfacet + facet normal -0.0890503 0.715534 -0.692879 + outer loop + vertex -609.148 93.8823 32.3011 + vertex -608.129 92.2737 30.509 + vertex -609.038 93.668 32.0656 + endloop + endfacet + facet normal -0.220162 0.65926 -0.718961 + outer loop + vertex -609.038 93.668 32.0656 + vertex -608.129 92.2737 30.509 + vertex -607.836 91.7162 29.9081 + endloop + endfacet + facet normal -0.39582 -0.77978 0.485047 + outer loop + vertex -609.038 93.668 32.0656 + vertex -607.836 91.7162 29.9081 + vertex -608.351 92.8001 31.2306 + endloop + endfacet + facet normal -0.302732 -0.786143 0.538826 + outer loop + vertex -609.887 94.1417 32.2283 + vertex -610.687 94.2458 31.9306 + vertex -609.575 93.0693 30.839 + endloop + endfacet + facet normal -0.296035 -0.784908 0.544319 + outer loop + vertex -611.474 93.2586 30.0794 + vertex -609.575 93.0693 30.839 + vertex -610.687 94.2458 31.9306 + endloop + endfacet + facet normal -0.302079 -0.781923 0.545294 + outer loop + vertex -611.969 94.6964 31.8665 + vertex -611.474 93.2586 30.0794 + vertex -610.687 94.2458 31.9306 + endloop + endfacet + facet normal -0.326236 -0.778659 0.535967 + outer loop + vertex -611.969 94.6964 31.8665 + vertex -613.264 94.8731 31.3349 + vertex -611.474 93.2586 30.0794 + endloop + endfacet + facet normal -0.31718 -0.775895 0.54533 + outer loop + vertex -614.004 94.1024 29.808 + vertex -611.474 93.2586 30.0794 + vertex -613.264 94.8731 31.3349 + endloop + endfacet + facet normal -0.318746 -0.775027 0.54565 + outer loop + vertex -614.8 95.4122 31.2036 + vertex -614.004 94.1024 29.808 + vertex -613.264 94.8731 31.3349 + endloop + endfacet + facet normal -0.326241 -0.810981 0.485671 + outer loop + vertex -614.663 96.0456 32.3531 + vertex -614.8 95.4122 31.2036 + vertex -613.264 94.8731 31.3349 + endloop + endfacet + facet normal -0.325406 -0.810773 0.486578 + outer loop + vertex -614.663 96.0456 32.3531 + vertex -613.264 94.8731 31.3349 + vertex -613.222 95.7043 32.7479 + endloop + endfacet + facet normal -0.321815 -0.828644 0.458022 + outer loop + vertex -614.351 96.4784 33.356 + vertex -614.663 96.0456 32.3531 + vertex -613.222 95.7043 32.7479 + endloop + endfacet + facet normal -0.321849 -0.828657 0.457976 + outer loop + vertex -614.351 96.4784 33.356 + vertex -613.222 95.7043 32.7479 + vertex -613.086 96.2448 33.8215 + endloop + endfacet + facet normal -0.320224 -0.832853 0.451455 + outer loop + vertex -614.351 96.4784 33.356 + vertex -613.086 96.2448 33.8215 + vertex -614.496 96.8686 33.9724 + endloop + endfacet + facet normal -0.327276 -0.831482 0.44892 + outer loop + vertex -614.351 96.4784 33.356 + vertex -614.496 96.8686 33.9724 + vertex -615.759 96.8555 33.0278 + endloop + endfacet + facet normal -0.329537 -0.828967 0.451906 + outer loop + vertex -614.496 96.8686 33.9724 + vertex -616.99 97.4071 33.1416 + vertex -615.759 96.8555 33.0278 + endloop + endfacet + facet normal -0.329226 -0.828498 0.452991 + outer loop + vertex -617.177 97.1293 32.4977 + vertex -615.759 96.8555 33.0278 + vertex -616.99 97.4071 33.1416 + endloop + endfacet + facet normal -0.327812 -0.829133 0.452855 + outer loop + vertex -617.177 97.1293 32.4977 + vertex -616.99 97.4071 33.1416 + vertex -618.659 97.544 32.1842 + endloop + endfacet + facet normal -0.329166 -0.812172 0.481691 + outer loop + vertex -618.659 97.544 32.1842 + vertex -617.677 96.7429 31.5047 + vertex -617.177 97.1293 32.4977 + endloop + endfacet + facet normal -0.32188 -0.8163 0.479632 + outer loop + vertex -617.177 97.1293 32.4977 + vertex -617.677 96.7429 31.5047 + vertex -616.117 96.3848 31.9418 + endloop + endfacet + facet normal -0.32547 -0.797704 0.507679 + outer loop + vertex -617.677 96.7429 31.5047 + vertex -616.074 95.4859 30.5571 + vertex -616.117 96.3848 31.9418 + endloop + endfacet + facet normal -0.30607 -0.802847 0.511623 + outer loop + vertex -616.117 96.3848 31.9418 + vertex -616.074 95.4859 30.5571 + vertex -614.8 95.4122 31.2036 + endloop + endfacet + facet normal -0.309313 -0.791622 0.526935 + outer loop + vertex -617.677 96.7429 31.5047 + vertex -618.024 95.9378 30.0914 + vertex -616.074 95.4859 30.5571 + endloop + endfacet + facet normal -0.31292 -0.750977 0.581476 + outer loop + vertex -618.024 95.9378 30.0914 + vertex -616.248 94.1909 28.7908 + vertex -616.074 95.4859 30.5571 + endloop + endfacet + facet normal -0.294475 -0.756619 0.583792 + outer loop + vertex -616.248 94.1909 28.7908 + vertex -614.004 94.1024 29.808 + vertex -616.074 95.4859 30.5571 + endloop + endfacet + facet normal -0.301513 -0.747312 0.592127 + outer loop + vertex -618.024 95.9378 30.0914 + vertex -618.738 95.077 28.6412 + vertex -616.248 94.1909 28.7908 + endloop + endfacet + facet normal -0.303614 -0.746176 0.592487 + outer loop + vertex -620.372 96.6069 29.7306 + vertex -618.738 95.077 28.6412 + vertex -618.024 95.9378 30.0914 + endloop + endfacet + facet normal -0.284703 -0.738931 0.610676 + outer loop + vertex -620.372 96.6069 29.7306 + vertex -621.414 95.6196 28.0505 + vertex -618.738 95.077 28.6412 + endloop + endfacet + facet normal -0.306619 -0.725375 0.616291 + outer loop + vertex -623.124 97.372 29.2621 + vertex -621.414 95.6196 28.0505 + vertex -620.372 96.6069 29.7306 + endloop + endfacet + facet normal -0.299253 -0.722776 0.622931 + outer loop + vertex -623.124 97.372 29.2621 + vertex -624.306 96.6838 27.8956 + vertex -621.414 95.6196 28.0505 + endloop + endfacet + facet normal -0.31113 -0.713044 0.628305 + outer loop + vertex -626.001 98.1273 28.6949 + vertex -624.306 96.6838 27.8956 + vertex -623.124 97.372 29.2621 + endloop + endfacet + facet normal -0.2873 -0.699494 0.654345 + outer loop + vertex -626.001 98.1273 28.6949 + vertex -627.093 97.2481 27.2752 + vertex -624.306 96.6838 27.8956 + endloop + endfacet + facet normal -0.308967 -0.683632 0.6612 + outer loop + vertex -628.729 98.8629 28.1805 + vertex -627.093 97.2481 27.2752 + vertex -626.001 98.1273 28.6949 + endloop + endfacet + facet normal -0.294895 -0.676829 0.674491 + outer loop + vertex -628.729 98.8629 28.1805 + vertex -629.895 98.2546 27.0601 + vertex -627.093 97.2481 27.2752 + endloop + endfacet + facet normal -0.302124 -0.669864 0.678235 + outer loop + vertex -631.464 99.6015 27.6915 + vertex -629.895 98.2546 27.0601 + vertex -628.729 98.8629 28.1805 + endloop + endfacet + facet normal -0.270739 -0.648759 0.711204 + outer loop + vertex -631.464 99.6015 27.6915 + vertex -632.753 98.7463 26.4207 + vertex -629.895 98.2546 27.0601 + endloop + endfacet + facet normal -0.289576 -0.631871 0.718947 + outer loop + vertex -634.469 100.397 27.1806 + vertex -632.753 98.7463 26.4207 + vertex -631.464 99.6015 27.6915 + endloop + endfacet + facet normal -0.260159 -0.613556 0.745564 + outer loop + vertex -634.469 100.397 27.1806 + vertex -636.679 99.8049 25.9221 + vertex -632.753 98.7463 26.4207 + endloop + endfacet + facet normal -0.272551 -0.59301 0.757664 + outer loop + vertex -637.81 101.372 26.7419 + vertex -636.679 99.8049 25.9221 + vertex -634.469 100.397 27.1806 + endloop + endfacet + facet normal -0.248986 -0.583877 0.772718 + outer loop + vertex -636.679 99.8049 25.9221 + vertex -637.81 101.372 26.7419 + vertex -641.018 101.132 25.5267 + endloop + endfacet + facet normal -0.256964 -0.558427 0.788751 + outer loop + vertex -641.436 102.593 26.4247 + vertex -641.018 101.132 25.5267 + vertex -637.81 101.372 26.7419 + endloop + endfacet + facet normal -0.242438 -0.557494 0.793992 + outer loop + vertex -641.436 102.593 26.4247 + vertex -645.981 102.681 25.0986 + vertex -641.018 101.132 25.5267 + endloop + endfacet + facet normal -0.250774 -0.504724 0.826055 + outer loop + vertex -647.238 104.414 25.7762 + vertex -645.981 102.681 25.0986 + vertex -641.436 102.593 26.4247 + endloop + endfacet + facet normal -0.225305 -0.492062 0.8409 + outer loop + vertex -647.238 104.414 25.7762 + vertex -651.454 104.397 24.6366 + vertex -645.981 102.681 25.0986 + endloop + endfacet + facet normal -0.229203 -0.465377 0.854921 + outer loop + vertex -653.423 106.348 25.1705 + vertex -651.454 104.397 24.6366 + vertex -647.238 104.414 25.7762 + endloop + endfacet + facet normal -0.234559 -0.486724 0.841476 + outer loop + vertex -653.423 106.348 25.1705 + vertex -647.238 104.414 25.7762 + vertex -650.64 105.947 25.7148 + endloop + endfacet + facet normal -0.235552 -0.531347 0.813748 + outer loop + vertex -650.64 105.947 25.7148 + vertex -653.466 107.09 25.6427 + vertex -653.423 106.348 25.1705 + endloop + endfacet + facet normal -0.217578 -0.532863 0.817751 + outer loop + vertex -653.466 107.09 25.6427 + vertex -657.13 108.66 25.6911 + vertex -653.423 106.348 25.1705 + endloop + endfacet + facet normal -0.259716 -0.628573 0.733106 + outer loop + vertex -657.13 108.66 25.6911 + vertex -653.466 107.09 25.6427 + vertex -655.179 108.107 25.9076 + endloop + endfacet + facet normal -0.206265 -0.373139 0.904556 + outer loop + vertex -655.179 108.107 25.9076 + vertex -656.319 108.494 25.8076 + vertex -657.13 108.66 25.6911 + endloop + endfacet + facet normal -0.238718 -0.678514 0.694717 + outer loop + vertex -656.319 108.494 25.8076 + vertex -657.024 109.158 26.2132 + vertex -657.13 108.66 25.6911 + endloop + endfacet + facet normal -0.264186 -0.671039 0.692757 + outer loop + vertex -658.785 110.265 26.6144 + vertex -657.13 108.66 25.6911 + vertex -657.024 109.158 26.2132 + endloop + endfacet + facet normal -0.296835 -0.707619 0.641221 + outer loop + vertex -655.179 108.107 25.9076 + vertex -657.024 109.158 26.2132 + vertex -656.319 108.494 25.8076 + endloop + endfacet + facet normal -0.302887 -0.715011 0.630095 + outer loop + vertex -655.922 109.109 26.6883 + vertex -657.024 109.158 26.2132 + vertex -655.179 108.107 25.9076 + endloop + endfacet + facet normal -0.299388 -0.714323 0.632542 + outer loop + vertex -651.714 106.929 26.2183 + vertex -655.922 109.109 26.6883 + vertex -655.179 108.107 25.9076 + endloop + endfacet + facet normal -0.287514 -0.664198 0.690056 + outer loop + vertex -651.714 106.929 26.2183 + vertex -655.179 108.107 25.9076 + vertex -653.466 107.09 25.6427 + endloop + endfacet + facet normal -0.287031 -0.666629 0.687909 + outer loop + vertex -653.466 107.09 25.6427 + vertex -650.64 105.947 25.7148 + vertex -651.714 106.929 26.2183 + endloop + endfacet + facet normal -0.280103 -0.66253 0.694692 + outer loop + vertex -650.64 105.947 25.7148 + vertex -648.098 105.324 26.1452 + vertex -651.714 106.929 26.2183 + endloop + endfacet + facet normal -0.271192 -0.570667 0.775109 + outer loop + vertex -648.098 105.324 26.1452 + vertex -650.64 105.947 25.7148 + vertex -647.238 104.414 25.7762 + endloop + endfacet + facet normal -0.2624 -0.565196 0.782112 + outer loop + vertex -645.372 104.448 26.4266 + vertex -648.098 105.324 26.1452 + vertex -647.238 104.414 25.7762 + endloop + endfacet + facet normal -0.203981 -0.444637 0.872175 + outer loop + vertex -653.423 106.348 25.1705 + vertex -656.81 106.14 24.2723 + vertex -651.454 104.397 24.6366 + endloop + endfacet + facet normal -0.204257 -0.443143 0.872871 + outer loop + vertex -658.708 108.046 24.7961 + vertex -656.81 106.14 24.2723 + vertex -653.423 106.348 25.1705 + endloop + endfacet + facet normal -0.235324 -0.556584 0.796767 + outer loop + vertex -658.708 108.046 24.7961 + vertex -653.423 106.348 25.1705 + vertex -657.13 108.66 25.6911 + endloop + endfacet + facet normal -0.188567 -0.43025 0.882795 + outer loop + vertex -658.708 108.046 24.7961 + vertex -661.874 107.87 24.0339 + vertex -656.81 106.14 24.2723 + endloop + endfacet + facet normal -0.190201 -0.420226 0.887262 + outer loop + vertex -663.46 109.638 24.5315 + vertex -661.874 107.87 24.0339 + vertex -658.708 108.046 24.7961 + endloop + endfacet + facet normal -0.224368 -0.534196 0.815042 + outer loop + vertex -663.46 109.638 24.5315 + vertex -658.708 108.046 24.7961 + vertex -661.677 109.992 25.254 + endloop + endfacet + facet normal -0.170995 -0.405951 0.897755 + outer loop + vertex -663.46 109.638 24.5315 + vertex -666.934 109.654 23.8767 + vertex -661.874 107.87 24.0339 + endloop + endfacet + facet normal -0.171228 -0.402959 0.899058 + outer loop + vertex -668.476 111.397 24.3643 + vertex -666.934 109.654 23.8767 + vertex -663.46 109.638 24.5315 + endloop + endfacet + facet normal -0.204414 -0.503282 0.839596 + outer loop + vertex -668.476 111.397 24.3643 + vertex -663.46 109.638 24.5315 + vertex -665.839 111.259 24.9238 + endloop + endfacet + facet normal -0.203726 -0.512727 0.83403 + outer loop + vertex -665.839 111.259 24.9238 + vertex -671.283 113.295 24.8455 + vertex -668.476 111.397 24.3643 + endloop + endfacet + facet normal -0.245263 -0.627467 0.739007 + outer loop + vertex -671.283 113.295 24.8455 + vertex -665.839 111.259 24.9238 + vertex -667.169 112.67 25.6802 + endloop + endfacet + facet normal -0.245328 -0.62392 0.741982 + outer loop + vertex -667.169 112.67 25.6802 + vertex -679.039 116.86 25.2792 + vertex -671.283 113.295 24.8455 + endloop + endfacet + facet normal -0.228967 -0.592063 0.772681 + outer loop + vertex -676.182 114.901 24.6243 + vertex -671.283 113.295 24.8455 + vertex -679.039 116.86 25.2792 + endloop + endfacet + facet normal -0.224495 -0.587213 0.777678 + outer loop + vertex -679.852 116.264 24.5944 + vertex -676.182 114.901 24.6243 + vertex -679.039 116.86 25.2792 + endloop + endfacet + facet normal -0.22809 -0.583939 0.779096 + outer loop + vertex -682.958 117.586 24.6762 + vertex -679.852 116.264 24.5944 + vertex -679.039 116.86 25.2792 + endloop + endfacet + facet normal -0.227641 -0.577344 0.784126 + outer loop + vertex -682.958 117.586 24.6762 + vertex -679.039 116.86 25.2792 + vertex -686.907 119.302 24.7926 + endloop + endfacet + facet normal -0.200829 -0.518786 0.830981 + outer loop + vertex -686.06 118.493 24.4921 + vertex -682.958 117.586 24.6762 + vertex -686.907 119.302 24.7926 + endloop + endfacet + facet normal -0.201355 -0.519194 0.830598 + outer loop + vertex -688.209 119.365 24.5165 + vertex -686.06 118.493 24.4921 + vertex -686.907 119.302 24.7926 + endloop + endfacet + facet normal -0.20108 -0.522606 0.828523 + outer loop + vertex -690.943 120.449 24.5369 + vertex -688.209 119.365 24.5165 + vertex -686.907 119.302 24.7926 + endloop + endfacet + facet normal -0.20042 -0.519864 0.830405 + outer loop + vertex -686.907 119.302 24.7926 + vertex -693.123 121.923 24.9334 + vertex -690.943 120.449 24.5369 + endloop + endfacet + facet normal -0.207354 -0.528233 0.823392 + outer loop + vertex -693.763 121.586 24.5564 + vertex -690.943 120.449 24.5369 + vertex -693.123 121.923 24.9334 + endloop + endfacet + facet normal -0.204061 -0.532402 0.821528 + outer loop + vertex -696.219 122.571 24.5844 + vertex -693.763 121.586 24.5564 + vertex -693.123 121.923 24.9334 + endloop + endfacet + facet normal -0.204966 -0.539267 0.816811 + outer loop + vertex -700.047 124.826 25.1123 + vertex -696.219 122.571 24.5844 + vertex -693.123 121.923 24.9334 + endloop + endfacet + facet normal -0.177252 -0.499512 0.847979 + outer loop + vertex -696.219 122.571 24.5844 + vertex -700.047 124.826 25.1123 + vertex -699.398 123.113 24.2391 + endloop + endfacet + facet normal -0.171507 -0.44657 0.878157 + outer loop + vertex -699.398 123.113 24.2391 + vertex -694.339 121.12 24.2136 + vertex -696.219 122.571 24.5844 + endloop + endfacet + facet normal -0.204094 -0.504935 0.838681 + outer loop + vertex -704.362 125.205 24.2909 + vertex -699.398 123.113 24.2391 + vertex -700.047 124.826 25.1123 + endloop + endfacet + facet normal -0.204364 -0.493549 0.845367 + outer loop + vertex -700.047 124.826 25.1123 + vertex -705.911 127.003 24.9661 + vertex -704.362 125.205 24.2909 + endloop + endfacet + facet normal -0.205681 -0.494381 0.844561 + outer loop + vertex -709.439 127.311 24.2869 + vertex -704.362 125.205 24.2909 + vertex -705.911 127.003 24.9661 + endloop + endfacet + facet normal -0.205377 -0.505998 0.837727 + outer loop + vertex -705.911 127.003 24.9661 + vertex -710.776 129.047 25.0078 + vertex -709.439 127.311 24.2869 + endloop + endfacet + facet normal -0.166958 -0.441549 0.881567 + outer loop + vertex -693.763 121.586 24.5564 + vertex -696.219 122.571 24.5844 + vertex -694.339 121.12 24.2136 + endloop + endfacet + facet normal -0.170529 -0.437951 0.882677 + outer loop + vertex -690.943 120.449 24.5369 + vertex -693.763 121.586 24.5564 + vertex -694.339 121.12 24.2136 + endloop + endfacet + facet normal -0.171636 -0.445482 0.878685 + outer loop + vertex -694.339 121.12 24.2136 + vertex -689.033 119.064 24.2078 + vertex -690.943 120.449 24.5369 + endloop + endfacet + facet normal -0.168731 -0.442024 0.880991 + outer loop + vertex -688.209 119.365 24.5165 + vertex -690.943 120.449 24.5369 + vertex -689.033 119.064 24.2078 + endloop + endfacet + facet normal -0.169133 -0.441243 0.881305 + outer loop + vertex -686.06 118.493 24.4921 + vertex -688.209 119.365 24.5165 + vertex -689.033 119.064 24.2078 + endloop + endfacet + facet normal -0.169268 -0.442195 0.880802 + outer loop + vertex -689.033 119.064 24.2078 + vertex -683.659 117.041 24.2248 + vertex -686.06 118.493 24.4921 + endloop + endfacet + facet normal -0.188627 -0.470731 0.861877 + outer loop + vertex -682.958 117.586 24.6762 + vertex -686.06 118.493 24.4921 + vertex -683.659 117.041 24.2248 + endloop + endfacet + facet normal -0.181029 -0.478363 0.859301 + outer loop + vertex -679.852 116.264 24.5944 + vertex -682.958 117.586 24.6762 + vertex -683.659 117.041 24.2248 + endloop + endfacet + facet normal -0.180348 -0.47374 0.862001 + outer loop + vertex -683.659 117.041 24.2248 + vertex -678.63 115.043 24.1789 + vertex -679.852 116.264 24.5944 + endloop + endfacet + facet normal -0.184092 -0.476668 0.859592 + outer loop + vertex -676.182 114.901 24.6243 + vertex -679.852 116.264 24.5944 + vertex -678.63 115.043 24.1789 + endloop + endfacet + facet normal -0.184141 -0.475473 0.860243 + outer loop + vertex -678.63 115.043 24.1789 + vertex -673.681 113.248 24.2463 + vertex -676.182 114.901 24.6243 + endloop + endfacet + facet normal -0.223378 -0.561021 0.797093 + outer loop + vertex -687.845 120.185 25.1517 + vertex -686.907 119.302 24.7926 + vertex -679.039 116.86 25.2792 + endloop + endfacet + facet normal -0.216145 -0.555669 0.802816 + outer loop + vertex -686.907 119.302 24.7926 + vertex -687.845 120.185 25.1517 + vertex -693.123 121.923 24.9334 + endloop + endfacet + facet normal -0.219583 -0.567253 0.79373 + outer loop + vertex -693.123 121.923 24.9334 + vertex -687.845 120.185 25.1517 + vertex -691.672 121.932 25.3414 + endloop + endfacet + facet normal -0.216787 -0.581528 0.78411 + outer loop + vertex -693.123 121.923 24.9334 + vertex -691.672 121.932 25.3414 + vertex -695.714 123.87 25.6608 + endloop + endfacet + facet normal -0.228538 -0.59275 0.772281 + outer loop + vertex -695.714 123.87 25.6608 + vertex -700.047 124.826 25.1123 + vertex -693.123 121.923 24.9334 + endloop + endfacet + facet normal -0.232115 -0.623905 0.746234 + outer loop + vertex -700.047 124.826 25.1123 + vertex -695.714 123.87 25.6608 + vertex -699.528 125.929 26.1962 + endloop + endfacet + facet normal -0.245696 -0.618042 0.746765 + outer loop + vertex -699.528 125.929 26.1962 + vertex -701.694 126.64 26.0723 + vertex -700.047 124.826 25.1123 + endloop + endfacet + facet normal -0.255936 -0.623219 0.738982 + outer loop + vertex -701.694 126.64 26.0723 + vertex -704.064 127.282 25.7924 + vertex -700.047 124.826 25.1123 + endloop + endfacet + facet normal -0.245245 -0.609795 0.753661 + outer loop + vertex -705.911 127.003 24.9661 + vertex -700.047 124.826 25.1123 + vertex -704.064 127.282 25.7924 + endloop + endfacet + facet normal -0.245871 -0.608397 0.754587 + outer loop + vertex -704.064 127.282 25.7924 + vertex -707.944 128.851 25.7933 + vertex -705.911 127.003 24.9661 + endloop + endfacet + facet normal -0.250497 -0.61163 0.75044 + outer loop + vertex -710.776 129.047 25.0078 + vertex -705.911 127.003 24.9661 + vertex -707.944 128.851 25.7933 + endloop + endfacet + facet normal -0.249215 -0.620413 0.743626 + outer loop + vertex -707.944 128.851 25.7933 + vertex -712.242 130.801 25.9797 + vertex -710.776 129.047 25.0078 + endloop + endfacet + facet normal -0.260544 -0.625391 0.735529 + outer loop + vertex -716.309 131.603 25.2216 + vertex -710.776 129.047 25.0078 + vertex -712.242 130.801 25.9797 + endloop + endfacet + facet normal -0.260891 -0.635516 0.726674 + outer loop + vertex -712.242 130.801 25.9797 + vertex -716.112 132.781 26.3217 + vertex -716.309 131.603 25.2216 + endloop + endfacet + facet normal -0.274701 -0.631626 0.724975 + outer loop + vertex -716.112 132.781 26.3217 + vertex -720.753 134.654 26.1952 + vertex -716.309 131.603 25.2216 + endloop + endfacet + facet normal -0.271245 -0.628006 0.729407 + outer loop + vertex -722.263 133.963 25.0391 + vertex -716.309 131.603 25.2216 + vertex -720.753 134.654 26.1952 + endloop + endfacet + facet normal -0.278898 -0.61913 0.734094 + outer loop + vertex -720.753 134.654 26.1952 + vertex -727.495 137.315 25.8782 + vertex -722.263 133.963 25.0391 + endloop + endfacet + facet normal -0.270908 -0.609419 0.745129 + outer loop + vertex -726.666 135.654 24.8214 + vertex -722.263 133.963 25.0391 + vertex -727.495 137.315 25.8782 + endloop + endfacet + facet normal -0.275853 -0.610281 0.742605 + outer loop + vertex -730.588 137.554 24.9258 + vertex -726.666 135.654 24.8214 + vertex -727.495 137.315 25.8782 + endloop + endfacet + facet normal -0.27681 -0.604144 0.747252 + outer loop + vertex -735.653 140.691 25.5857 + vertex -730.588 137.554 24.9258 + vertex -727.495 137.315 25.8782 + endloop + endfacet + facet normal -0.201182 -0.497504 0.84381 + outer loop + vertex -671.283 113.295 24.8455 + vertex -676.182 114.901 24.6243 + vertex -673.681 113.248 24.2463 + endloop + endfacet + facet normal -0.199569 -0.507622 0.838148 + outer loop + vertex -673.681 113.248 24.2463 + vertex -668.476 111.397 24.3643 + vertex -671.283 113.295 24.8455 + endloop + endfacet + facet normal -0.250155 -0.630028 0.735178 + outer loop + vertex -665.839 111.259 24.9238 + vertex -661.677 109.992 25.254 + vertex -667.169 112.67 25.6802 + endloop + endfacet + facet normal -0.226177 -0.529847 0.817377 + outer loop + vertex -661.677 109.992 25.254 + vertex -665.839 111.259 24.9238 + vertex -663.46 109.638 24.5315 + endloop + endfacet + facet normal -0.159946 -0.394592 0.904829 + outer loop + vertex -668.476 111.397 24.3643 + vertex -672.138 111.511 23.7667 + vertex -666.934 109.654 23.8767 + endloop + endfacet + facet normal -0.160039 -0.392174 0.905863 + outer loop + vertex -673.681 113.248 24.2463 + vertex -672.138 111.511 23.7667 + vertex -668.476 111.397 24.3643 + endloop + endfacet + facet normal -0.151126 -0.385472 0.910259 + outer loop + vertex -673.681 113.248 24.2463 + vertex -677.388 113.404 23.6967 + vertex -672.138 111.511 23.7667 + endloop + endfacet + facet normal -0.151182 -0.382664 0.911434 + outer loop + vertex -678.63 115.043 24.1789 + vertex -677.388 113.404 23.6967 + vertex -673.681 113.248 24.2463 + endloop + endfacet + facet normal -0.144502 -0.37844 0.914277 + outer loop + vertex -678.63 115.043 24.1789 + vertex -682.608 115.369 23.6854 + vertex -677.388 113.404 23.6967 + endloop + endfacet + facet normal -0.144701 -0.385156 0.911437 + outer loop + vertex -683.659 117.041 24.2248 + vertex -682.608 115.369 23.6854 + vertex -678.63 115.043 24.1789 + endloop + endfacet + facet normal -0.147221 -0.386436 0.910491 + outer loop + vertex -683.659 117.041 24.2248 + vertex -687.715 117.381 23.7132 + vertex -682.608 115.369 23.6854 + endloop + endfacet + facet normal -0.147122 -0.383115 0.911909 + outer loop + vertex -689.033 119.064 24.2078 + vertex -687.715 117.381 23.7132 + vertex -683.659 117.041 24.2248 + endloop + endfacet + facet normal -0.143574 -0.380789 0.913447 + outer loop + vertex -689.033 119.064 24.2078 + vertex -692.877 119.323 23.7116 + vertex -687.715 117.381 23.7132 + endloop + endfacet + facet normal -0.143464 -0.372871 0.916725 + outer loop + vertex -694.339 121.12 24.2136 + vertex -692.877 119.323 23.7116 + vertex -689.033 119.064 24.2078 + endloop + endfacet + facet normal -0.141113 -0.371244 0.91775 + outer loop + vertex -694.339 121.12 24.2136 + vertex -698.114 121.279 23.6976 + vertex -692.877 119.323 23.7116 + endloop + endfacet + facet normal -0.141129 -0.369976 0.918259 + outer loop + vertex -699.398 123.113 24.2391 + vertex -698.114 121.279 23.6976 + vertex -694.339 121.12 24.2136 + endloop + endfacet + facet normal -0.145821 -0.372717 0.916416 + outer loop + vertex -699.398 123.113 24.2391 + vertex -703.318 123.308 23.6947 + vertex -698.114 121.279 23.6976 + endloop + endfacet + facet normal -0.145846 -0.368728 0.918024 + outer loop + vertex -704.362 125.205 24.2909 + vertex -703.318 123.308 23.6947 + vertex -699.398 123.113 24.2391 + endloop + endfacet + facet normal -0.151937 -0.371427 0.915946 + outer loop + vertex -704.362 125.205 24.2909 + vertex -708.481 125.441 23.7032 + vertex -703.318 123.308 23.6947 + endloop + endfacet + facet normal -0.151938 -0.36463 0.918673 + outer loop + vertex -709.439 127.311 24.2869 + vertex -708.481 125.441 23.7032 + vertex -704.362 125.205 24.2909 + endloop + endfacet + facet normal -0.151001 -0.364246 0.91898 + outer loop + vertex -709.439 127.311 24.2869 + vertex -713.621 127.619 23.7219 + vertex -708.481 125.441 23.7032 + endloop + endfacet + facet normal -0.151108 -0.369779 0.91675 + outer loop + vertex -714.526 129.501 24.332 + vertex -713.621 127.619 23.7219 + vertex -709.439 127.311 24.2869 + endloop + endfacet + facet normal -0.157668 -0.37225 0.914643 + outer loop + vertex -714.526 129.501 24.332 + vertex -718.742 129.846 23.7455 + vertex -713.621 127.619 23.7219 + endloop + endfacet + facet normal -0.157658 -0.371859 0.914803 + outer loop + vertex -719.813 131.78 24.3469 + vertex -718.742 129.846 23.7455 + vertex -714.526 129.501 24.332 + endloop + endfacet + facet normal -0.162712 -0.374099 0.913003 + outer loop + vertex -719.813 131.78 24.3469 + vertex -723.925 132.127 23.7564 + vertex -718.742 129.846 23.7455 + endloop + endfacet + facet normal -0.162236 -0.356164 0.920232 + outer loop + vertex -724.951 133.986 24.295 + vertex -723.925 132.127 23.7564 + vertex -719.813 131.78 24.3469 + endloop + endfacet + facet normal -0.160909 -0.355566 0.920696 + outer loop + vertex -724.951 133.986 24.295 + vertex -729.111 134.466 23.7531 + vertex -723.925 132.127 23.7564 + endloop + endfacet + facet normal -0.16094 -0.356067 0.920497 + outer loop + vertex -729.845 136.186 24.2905 + vertex -729.111 134.466 23.7531 + vertex -724.951 133.986 24.295 + endloop + endfacet + facet normal -0.164471 -0.357236 0.919419 + outer loop + vertex -729.845 136.186 24.2905 + vertex -734.363 136.888 23.7548 + vertex -729.111 134.466 23.7531 + endloop + endfacet + facet normal -0.167531 -0.38646 0.906963 + outer loop + vertex -734.914 138.662 24.4091 + vertex -734.363 136.888 23.7548 + vertex -729.845 136.186 24.2905 + endloop + endfacet + facet normal -0.186297 -0.390319 0.901634 + outer loop + vertex -734.914 138.662 24.4091 + vertex -739.697 139.403 23.7415 + vertex -734.363 136.888 23.7548 + endloop + endfacet + facet normal -0.187813 -0.407102 0.893865 + outer loop + vertex -740.413 141.328 24.4677 + vertex -739.697 139.403 23.7415 + vertex -734.914 138.662 24.4091 + endloop + endfacet + facet normal -0.20282 -0.410807 0.888876 + outer loop + vertex -740.413 141.328 24.4677 + vertex -744.998 141.934 23.7016 + vertex -739.697 139.403 23.7415 + endloop + endfacet + facet normal -0.202947 -0.413216 0.88773 + outer loop + vertex -745.877 143.974 24.4502 + vertex -744.998 141.934 23.7016 + vertex -740.413 141.328 24.4677 + endloop + endfacet + facet normal -0.212562 -0.416043 0.884153 + outer loop + vertex -745.877 143.974 24.4502 + vertex -750.125 144.455 23.6557 + vertex -744.998 141.934 23.7016 + endloop + endfacet + facet normal -0.212701 -0.421947 0.881317 + outer loop + vertex -751.136 146.638 24.4566 + vertex -750.125 144.455 23.6557 + vertex -745.877 143.974 24.4502 + endloop + endfacet + facet normal -0.224132 -0.425563 0.876733 + outer loop + vertex -751.136 146.638 24.4566 + vertex -755.11 146.997 23.6148 + vertex -750.125 144.455 23.6557 + endloop + endfacet + facet normal -0.224221 -0.417252 0.880696 + outer loop + vertex -756.218 149.224 24.3881 + vertex -755.11 146.997 23.6148 + vertex -751.136 146.638 24.4566 + endloop + endfacet + facet normal -0.226759 -0.418142 0.879623 + outer loop + vertex -756.218 149.224 24.3881 + vertex -760.066 149.615 23.5818 + vertex -755.11 146.997 23.6148 + endloop + endfacet + facet normal -0.226752 -0.414905 0.881157 + outer loop + vertex -761.216 151.902 24.3626 + vertex -760.066 149.615 23.5818 + vertex -756.218 149.224 24.3881 + endloop + endfacet + facet normal -0.233171 -0.417191 0.878398 + outer loop + vertex -761.216 151.902 24.3626 + vertex -765.107 152.366 23.5504 + vertex -760.066 149.615 23.5818 + endloop + endfacet + facet normal -0.233053 -0.411305 0.8812 + outer loop + vertex -766.488 154.788 24.3155 + vertex -765.107 152.366 23.5504 + vertex -761.216 151.902 24.3626 + endloop + endfacet + facet normal -0.243175 -0.415578 0.876448 + outer loop + vertex -766.488 154.788 24.3155 + vertex -770.069 155.114 23.4762 + vertex -765.107 152.366 23.5504 + endloop + endfacet + facet normal -0.243529 -0.392898 0.88675 + outer loop + vertex -770.997 157.044 24.0766 + vertex -770.069 155.114 23.4762 + vertex -766.488 154.788 24.3155 + endloop + endfacet + facet normal -0.238781 -0.391244 0.88877 + outer loop + vertex -770.997 157.044 24.0766 + vertex -774.779 157.824 23.4041 + vertex -770.069 155.114 23.4762 + endloop + endfacet + facet normal -0.240612 -0.406461 0.881417 + outer loop + vertex -774.849 159.505 24.1603 + vertex -774.779 157.824 23.4041 + vertex -770.997 157.044 24.0766 + endloop + endfacet + facet normal -0.257106 -0.405295 0.877287 + outer loop + vertex -774.849 159.505 24.1603 + vertex -779.425 160.634 23.3404 + vertex -774.779 157.824 23.4041 + endloop + endfacet + facet normal -0.257703 -0.409144 0.875323 + outer loop + vertex -779.528 162.342 24.1085 + vertex -779.425 160.634 23.3404 + vertex -774.849 159.505 24.1603 + endloop + endfacet + facet normal -0.271866 -0.408254 0.871446 + outer loop + vertex -779.528 162.342 24.1085 + vertex -784.125 163.539 23.2354 + vertex -779.425 160.634 23.3404 + endloop + endfacet + facet normal -0.27258 -0.412678 0.869136 + outer loop + vertex -784.22 165.223 24.0052 + vertex -784.125 163.539 23.2354 + vertex -779.528 162.342 24.1085 + endloop + endfacet + facet normal -0.285009 -0.411755 0.86558 + outer loop + vertex -784.22 165.223 24.0052 + vertex -788.909 166.565 23.0998 + vertex -784.125 163.539 23.2354 + endloop + endfacet + facet normal -0.285705 -0.415578 0.86352 + outer loop + vertex -788.875 168.217 23.9059 + vertex -788.909 166.565 23.0998 + vertex -784.22 165.223 24.0052 + endloop + endfacet + facet normal -0.298836 -0.4136 0.860019 + outer loop + vertex -788.875 168.217 23.9059 + vertex -793.654 169.753 22.9841 + vertex -788.909 166.565 23.0998 + endloop + endfacet + facet normal -0.301363 -0.425488 0.853311 + outer loop + vertex -793.695 171.482 23.8315 + vertex -793.654 169.753 22.9841 + vertex -788.875 168.217 23.9059 + endloop + endfacet + facet normal -0.314732 -0.423843 0.849295 + outer loop + vertex -793.695 171.482 23.8315 + vertex -798.326 172.968 22.8573 + vertex -793.654 169.753 22.9841 + endloop + endfacet + facet normal -0.31303 -0.415408 0.854077 + outer loop + vertex -798.627 174.803 23.639 + vertex -798.326 172.968 22.8573 + vertex -793.695 171.482 23.8315 + endloop + endfacet + facet normal -0.319511 -0.415442 0.851657 + outer loop + vertex -798.627 174.803 23.639 + vertex -802.909 176.17 22.6992 + vertex -798.326 172.968 22.8573 + endloop + endfacet + facet normal -0.315227 -0.393956 0.863383 + outer loop + vertex -803.25 177.916 23.3721 + vertex -802.909 176.17 22.6992 + vertex -798.627 174.803 23.639 + endloop + endfacet + facet normal -0.31578 -0.393982 0.863169 + outer loop + vertex -803.25 177.916 23.3721 + vertex -807.364 179.387 22.5378 + vertex -802.909 176.17 22.6992 + endloop + endfacet + facet normal -0.312043 -0.378956 0.871218 + outer loop + vertex -807.513 180.973 23.1746 + vertex -807.364 179.387 22.5378 + vertex -803.25 177.916 23.3721 + endloop + endfacet + facet normal -0.313078 -0.378912 0.870866 + outer loop + vertex -807.513 180.973 23.1746 + vertex -811.746 182.686 22.3983 + vertex -807.364 179.387 22.5378 + endloop + endfacet + facet normal -0.312704 -0.377685 0.871533 + outer loop + vertex -811.802 184.26 23.0603 + vertex -811.746 182.686 22.3983 + vertex -807.513 180.973 23.1746 + endloop + endfacet + facet normal -0.321211 -0.376837 0.868802 + outer loop + vertex -811.802 184.26 23.0603 + vertex -816.058 186.054 22.2649 + vertex -811.746 182.686 22.3983 + endloop + endfacet + facet normal -0.321035 -0.376288 0.869105 + outer loop + vertex -816.125 187.679 22.9435 + vertex -816.058 186.054 22.2649 + vertex -811.802 184.26 23.0603 + endloop + endfacet + facet normal -0.328631 -0.375547 0.866583 + outer loop + vertex -816.125 187.679 22.9435 + vertex -820.29 189.451 22.1323 + vertex -816.058 186.054 22.2649 + endloop + endfacet + facet normal -0.328596 -0.375435 0.866645 + outer loop + vertex -820.399 191.194 22.846 + vertex -820.29 189.451 22.1323 + vertex -816.125 187.679 22.9435 + endloop + endfacet + facet normal -0.337499 -0.374717 0.863529 + outer loop + vertex -820.399 191.194 22.846 + vertex -824.38 192.838 22.0033 + vertex -820.29 189.451 22.1323 + endloop + endfacet + facet normal -0.336782 -0.372302 0.864852 + outer loop + vertex -824.597 194.71 22.7249 + vertex -824.38 192.838 22.0033 + vertex -820.399 191.194 22.846 + endloop + endfacet + facet normal -0.342671 -0.372121 0.862614 + outer loop + vertex -824.597 194.71 22.7249 + vertex -828.325 196.187 21.8809 + vertex -824.38 192.838 22.0033 + endloop + endfacet + facet normal -0.34067 -0.364847 0.866505 + outer loop + vertex -828.608 198.111 22.5795 + vertex -828.325 196.187 21.8809 + vertex -824.597 194.71 22.7249 + endloop + endfacet + facet normal -0.343094 -0.364855 0.865545 + outer loop + vertex -828.608 198.111 22.5795 + vertex -832.116 199.473 21.7634 + vertex -828.325 196.187 21.8809 + endloop + endfacet + facet normal -0.340781 -0.356203 0.87005 + outer loop + vertex -832.435 201.403 22.4288 + vertex -832.116 199.473 21.7634 + vertex -828.608 198.111 22.5795 + endloop + endfacet + facet normal -0.341224 -0.356215 0.869872 + outer loop + vertex -832.435 201.403 22.4288 + vertex -835.741 202.631 21.6344 + vertex -832.116 199.473 21.7634 + endloop + endfacet + facet normal -0.336929 -0.33918 0.878314 + outer loop + vertex -835.733 204.084 22.1988 + vertex -835.741 202.631 21.6344 + vertex -832.435 201.403 22.4288 + endloop + endfacet + facet normal -0.330363 -0.340053 0.880468 + outer loop + vertex -835.733 204.084 22.1988 + vertex -839.243 205.769 21.5323 + vertex -835.741 202.631 21.6344 + endloop + endfacet + facet normal -0.338525 -0.36174 0.868645 + outer loop + vertex -838.675 207.062 22.2922 + vertex -839.243 205.769 21.5323 + vertex -835.733 204.084 22.1988 + endloop + endfacet + facet normal -0.346839 -0.357252 0.867222 + outer loop + vertex -838.675 207.062 22.2922 + vertex -843.01 209.261 21.4645 + vertex -839.243 205.769 21.5323 + endloop + endfacet + facet normal -0.346957 -0.357547 0.867053 + outer loop + vertex -842.836 211.021 22.2597 + vertex -843.01 209.261 21.4645 + vertex -838.675 207.062 22.2922 + endloop + endfacet + facet normal -0.351416 -0.356491 0.865691 + outer loop + vertex -842.836 211.021 22.2597 + vertex -847.148 213.25 21.4273 + vertex -843.01 209.261 21.4645 + endloop + endfacet + facet normal -0.350083 -0.353209 0.867574 + outer loop + vertex -847.555 215.627 22.2308 + vertex -847.148 213.25 21.4273 + vertex -842.836 211.021 22.2597 + endloop + endfacet + facet normal -0.354834 -0.353351 0.865584 + outer loop + vertex -847.555 215.627 22.2308 + vertex -851.265 217.537 21.4897 + vertex -847.148 213.25 21.4273 + endloop + endfacet + facet normal -0.349497 -0.340094 0.873034 + outer loop + vertex -851.236 219.059 22.094 + vertex -851.265 217.537 21.4897 + vertex -847.555 215.627 22.2308 + endloop + endfacet + facet normal -0.347712 -0.340369 0.873639 + outer loop + vertex -851.265 217.537 21.4897 + vertex -851.236 219.059 22.094 + vertex -853.391 220.566 21.8234 + endloop + endfacet + facet normal -0.340435 -0.335771 0.878272 + outer loop + vertex -853.682 219.794 21.4155 + vertex -851.265 217.537 21.4897 + vertex -853.391 220.566 21.8234 + endloop + endfacet + facet normal -0.336054 -0.337887 0.879147 + outer loop + vertex -853.391 220.566 21.8234 + vertex -855.06 221.312 21.4722 + vertex -853.682 219.794 21.4155 + endloop + endfacet + facet normal -0.334839 -0.334306 0.880978 + outer loop + vertex -854.807 221.978 21.8213 + vertex -855.06 221.312 21.4722 + vertex -853.391 220.566 21.8234 + endloop + endfacet + facet normal -0.367656 -0.367238 0.85438 + outer loop + vertex -854.807 221.978 21.8213 + vertex -853.391 220.566 21.8234 + vertex -854.529 222.227 22.0475 + endloop + endfacet + facet normal -0.362308 -0.373011 0.854163 + outer loop + vertex -854.529 222.227 22.0475 + vertex -855.721 222.723 21.7589 + vertex -854.807 221.978 21.8213 + endloop + endfacet + facet normal -0.357407 -0.355809 0.863516 + outer loop + vertex -855.335 223.152 22.0954 + vertex -855.721 222.723 21.7589 + vertex -854.529 222.227 22.0475 + endloop + endfacet + facet normal -0.376803 -0.371906 0.848355 + outer loop + vertex -854.139 222.335 22.2687 + vertex -855.335 223.152 22.0954 + vertex -854.529 222.227 22.0475 + endloop + endfacet + facet normal -0.37435 -0.377705 0.846877 + outer loop + vertex -854.139 222.335 22.2687 + vertex -854.529 222.227 22.0475 + vertex -853.132 221.111 22.1677 + endloop + endfacet + facet normal -0.375336 -0.378452 0.846107 + outer loop + vertex -852.544 220.878 22.3243 + vertex -854.139 222.335 22.2687 + vertex -853.132 221.111 22.1677 + endloop + endfacet + facet normal -0.374911 -0.376738 0.84706 + outer loop + vertex -853.132 221.111 22.1677 + vertex -851.236 219.059 22.094 + vertex -852.544 220.878 22.3243 + endloop + endfacet + facet normal -0.397945 -0.391121 0.829858 + outer loop + vertex -851.236 219.059 22.094 + vertex -850.546 219.169 22.4768 + vertex -852.544 220.878 22.3243 + endloop + endfacet + facet normal -0.405734 -0.400985 0.821335 + outer loop + vertex -852.844 221.426 22.4432 + vertex -852.544 220.878 22.3243 + vertex -850.546 219.169 22.4768 + endloop + endfacet + facet normal -0.462666 -0.459906 0.757909 + outer loop + vertex -852.844 221.426 22.4432 + vertex -850.546 219.169 22.4768 + vertex -852.045 221.474 22.9607 + endloop + endfacet + facet normal -0.463815 -0.45635 0.759355 + outer loop + vertex -853.752 222.34 22.4384 + vertex -852.844 221.426 22.4432 + vertex -852.045 221.474 22.9607 + endloop + endfacet + facet normal -0.461712 -0.448694 0.765177 + outer loop + vertex -852.045 221.474 22.9607 + vertex -854.394 223.155 22.5287 + vertex -853.752 222.34 22.4384 + endloop + endfacet + facet normal -0.443957 -0.436614 0.782477 + outer loop + vertex -854.394 223.155 22.5287 + vertex -854.522 222.966 22.351 + vertex -853.752 222.34 22.4384 + endloop + endfacet + facet normal -0.386969 -0.357098 0.850139 + outer loop + vertex -854.522 222.966 22.351 + vertex -854.284 222.697 22.3464 + vertex -853.752 222.34 22.4384 + endloop + endfacet + facet normal 0.5597 0.506752 -0.655696 + outer loop + vertex -854.522 222.966 22.351 + vertex -854.914 223.522 22.4464 + vertex -854.284 222.697 22.3464 + endloop + endfacet + facet normal -0.338395 -0.363507 0.867958 + outer loop + vertex -855.008 223.356 22.34 + vertex -854.284 222.697 22.3464 + vertex -854.914 223.522 22.4464 + endloop + endfacet + facet normal -0.0451348 -0.520179 0.852864 + outer loop + vertex -854.946 224.63 23.1206 + vertex -855.008 223.356 22.34 + vertex -854.914 223.522 22.4464 + endloop + endfacet + facet normal 0.62871 0.417535 -0.65604 + outer loop + vertex -854.914 223.522 22.4464 + vertex -854.992 223.833 22.5691 + vertex -854.946 224.63 23.1206 + endloop + endfacet + facet normal -0.491042 -0.476224 0.729444 + outer loop + vertex -854.992 223.833 22.5691 + vertex -854.394 223.155 22.5287 + vertex -854.946 224.63 23.1206 + endloop + endfacet + facet normal -0.475886 -0.474902 0.740271 + outer loop + vertex -852.045 221.474 22.9607 + vertex -854.946 224.63 23.1206 + vertex -854.394 223.155 22.5287 + endloop + endfacet + facet normal -0.426057 -0.423129 0.799648 + outer loop + vertex -854.992 223.833 22.5691 + vertex -854.914 223.522 22.4464 + vertex -854.394 223.155 22.5287 + endloop + endfacet + facet normal -0.38698 -0.467887 0.794562 + outer loop + vertex -854.946 224.63 23.1206 + vertex -856.362 223.72 21.8949 + vertex -855.008 223.356 22.34 + endloop + endfacet + facet normal -0.380798 -0.393016 0.836978 + outer loop + vertex -855.335 223.152 22.0954 + vertex -855.008 223.356 22.34 + vertex -856.362 223.72 21.8949 + endloop + endfacet + facet normal -0.472865 -0.352091 0.807732 + outer loop + vertex -856.362 223.72 21.8949 + vertex -854.946 224.63 23.1206 + vertex -856.627 224.458 22.0611 + endloop + endfacet + facet normal -0.462657 -0.38759 0.797322 + outer loop + vertex -856.533 224.99 22.3746 + vertex -856.627 224.458 22.0611 + vertex -854.946 224.63 23.1206 + endloop + endfacet + facet normal -0.374829 -0.420248 0.826375 + outer loop + vertex -856.533 224.99 22.3746 + vertex -857.658 224.575 21.6535 + vertex -856.627 224.458 22.0611 + endloop + endfacet + facet normal -0.377308 -0.381654 0.843789 + outer loop + vertex -856.627 224.458 22.0611 + vertex -857.658 224.575 21.6535 + vertex -857.361 224.074 21.5592 + endloop + endfacet + facet normal -0.40483 -0.337127 0.849975 + outer loop + vertex -856.627 224.458 22.0611 + vertex -857.361 224.074 21.5592 + vertex -856.362 223.72 21.8949 + endloop + endfacet + facet normal -0.379244 -0.411991 0.828515 + outer loop + vertex -856.533 224.99 22.3746 + vertex -857.924 225.801 22.1412 + vertex -857.658 224.575 21.6535 + endloop + endfacet + facet normal 0.0295462 0.0422338 0.998671 + outer loop + vertex -853.828 222.225 22.3529 + vertex -854.284 222.697 22.3464 + vertex -855.008 223.356 22.34 + endloop + endfacet + facet normal -0.362563 -0.368542 0.855993 + outer loop + vertex -854.139 222.335 22.2687 + vertex -853.828 222.225 22.3529 + vertex -855.008 223.356 22.34 + endloop + endfacet + facet normal -0.33403 -0.310324 0.890013 + outer loop + vertex -854.284 222.697 22.3464 + vertex -853.828 222.225 22.3529 + vertex -852.844 221.426 22.4432 + endloop + endfacet + facet normal -0.436923 -0.442153 0.783326 + outer loop + vertex -854.394 223.155 22.5287 + vertex -854.914 223.522 22.4464 + vertex -854.522 222.966 22.351 + endloop + endfacet + facet normal -0.414116 -0.406735 0.814294 + outer loop + vertex -853.752 222.34 22.4384 + vertex -854.284 222.697 22.3464 + vertex -852.844 221.426 22.4432 + endloop + endfacet + facet normal -0.457693 -0.457598 0.762313 + outer loop + vertex -847.919 217.561 23.089 + vertex -852.045 221.474 22.9607 + vertex -850.546 219.169 22.4768 + endloop + endfacet + facet normal -0.399888 -0.398649 0.825329 + outer loop + vertex -852.844 221.426 22.4432 + vertex -853.828 222.225 22.3529 + vertex -852.544 220.878 22.3243 + endloop + endfacet + facet normal -0.397286 -0.393103 0.829237 + outer loop + vertex -850.546 219.169 22.4768 + vertex -851.236 219.059 22.094 + vertex -847.555 215.627 22.2308 + endloop + endfacet + facet normal -0.446833 -0.431772 0.783526 + outer loop + vertex -847.919 217.561 23.089 + vertex -850.546 219.169 22.4768 + vertex -847.555 215.627 22.2308 + endloop + endfacet + facet normal -0.428233 -0.432641 0.793372 + outer loop + vertex -843.769 213.536 23.1344 + vertex -847.919 217.561 23.089 + vertex -847.555 215.627 22.2308 + endloop + endfacet + facet normal -0.428902 -0.434431 0.792031 + outer loop + vertex -847.555 215.627 22.2308 + vertex -842.836 211.021 22.2597 + vertex -843.769 213.536 23.1344 + endloop + endfacet + facet normal -0.424903 -0.433813 0.794521 + outer loop + vertex -839.029 209.265 23.3374 + vertex -843.769 213.536 23.1344 + vertex -842.836 211.021 22.2597 + endloop + endfacet + facet normal -0.427207 -0.442537 0.788451 + outer loop + vertex -842.836 211.021 22.2597 + vertex -838.675 207.062 22.2922 + vertex -839.029 209.265 23.3374 + endloop + endfacet + facet normal -0.417798 -0.443228 0.793091 + outer loop + vertex -834.402 204.536 23.1313 + vertex -839.029 209.265 23.3374 + vertex -838.675 207.062 22.2922 + endloop + endfacet + facet normal -0.413703 -0.433882 0.800372 + outer loop + vertex -838.675 207.062 22.2922 + vertex -835.733 204.084 22.1988 + vertex -834.402 204.536 23.1313 + endloop + endfacet + facet normal -0.411608 -0.437837 0.799298 + outer loop + vertex -835.733 204.084 22.1988 + vertex -832.435 201.403 22.4288 + vertex -834.402 204.536 23.1313 + endloop + endfacet + facet normal -0.413696 -0.43879 0.797696 + outer loop + vertex -829.897 200.663 23.3374 + vertex -834.402 204.536 23.1313 + vertex -832.435 201.403 22.4288 + endloop + endfacet + facet normal -0.414182 -0.444986 0.794003 + outer loop + vertex -832.435 201.403 22.4288 + vertex -828.608 198.111 22.5795 + vertex -829.897 200.663 23.3374 + endloop + endfacet + facet normal -0.41007 -0.443747 0.796826 + outer loop + vertex -825.885 197.226 23.4882 + vertex -829.897 200.663 23.3374 + vertex -828.608 198.111 22.5795 + endloop + endfacet + facet normal -0.361276 -0.362571 0.859082 + outer loop + vertex -853.828 222.225 22.3529 + vertex -854.139 222.335 22.2687 + vertex -852.544 220.878 22.3243 + endloop + endfacet + facet normal -0.385375 -0.386696 0.837826 + outer loop + vertex -855.008 223.356 22.34 + vertex -855.335 223.152 22.0954 + vertex -854.139 222.335 22.2687 + endloop + endfacet + facet normal -0.362663 -0.350923 0.863324 + outer loop + vertex -855.721 222.723 21.7589 + vertex -855.335 223.152 22.0954 + vertex -856.362 223.72 21.8949 + endloop + endfacet + facet normal -0.365923 -0.36621 0.855565 + outer loop + vertex -853.391 220.566 21.8234 + vertex -853.132 221.111 22.1677 + vertex -854.529 222.227 22.0475 + endloop + endfacet + facet normal -0.333247 -0.335074 0.88129 + outer loop + vertex -854.807 221.978 21.8213 + vertex -855.721 222.723 21.7589 + vertex -855.06 221.312 21.4722 + endloop + endfacet + facet normal -0.364239 -0.367196 0.85586 + outer loop + vertex -853.132 221.111 22.1677 + vertex -853.391 220.566 21.8234 + vertex -851.236 219.059 22.094 + endloop + endfacet + facet normal -0.320209 -0.787179 0.527082 + outer loop + vertex -619.495 97.2398 31.142 + vertex -618.024 95.9378 30.0914 + vertex -617.677 96.7429 31.5047 + endloop + endfacet + facet normal -0.306259 -0.782987 0.541422 + outer loop + vertex -618.024 95.9378 30.0914 + vertex -619.495 97.2398 31.142 + vertex -620.372 96.6069 29.7306 + endloop + endfacet + facet normal -0.314984 -0.777464 0.544367 + outer loop + vertex -621.609 97.8958 30.8555 + vertex -620.372 96.6069 29.7306 + vertex -619.495 97.2398 31.142 + endloop + endfacet + facet normal -0.317237 -0.800166 0.509015 + outer loop + vertex -620.036 97.8394 31.7477 + vertex -621.609 97.8958 30.8555 + vertex -619.495 97.2398 31.142 + endloop + endfacet + facet normal -0.330077 -0.801409 0.498791 + outer loop + vertex -620.036 97.8394 31.7477 + vertex -619.495 97.2398 31.142 + vertex -618.659 97.544 32.1842 + endloop + endfacet + facet normal -0.323693 -0.825505 0.462347 + outer loop + vertex -620.036 97.8394 31.7477 + vertex -618.659 97.544 32.1842 + vertex -619.751 97.9657 32.1725 + endloop + endfacet + facet normal -0.280881 -0.852114 0.441596 + outer loop + vertex -619.751 97.9657 32.1725 + vertex -621.609 97.8958 30.8555 + vertex -620.036 97.8394 31.7477 + endloop + endfacet + facet normal -0.329885 -0.795841 0.507754 + outer loop + vertex -622.847 98.5852 31.1323 + vertex -621.609 97.8958 30.8555 + vertex -619.751 97.9657 32.1725 + endloop + endfacet + facet normal -0.324231 -0.815668 0.479124 + outer loop + vertex -620.293 98.1535 32.1252 + vertex -622.847 98.5852 31.1323 + vertex -619.751 97.9657 32.1725 + endloop + endfacet + facet normal -0.327051 -0.831274 0.449467 + outer loop + vertex -620.293 98.1535 32.1252 + vertex -619.751 97.9657 32.1725 + vertex -617.475 97.6088 33.1684 + endloop + endfacet + facet normal -0.324064 -0.838815 0.437461 + outer loop + vertex -620.293 98.1535 32.1252 + vertex -617.475 97.6088 33.1684 + vertex -618.453 97.8927 32.9888 + endloop + endfacet + facet normal -0.323877 -0.837582 0.439954 + outer loop + vertex -617.475 97.6088 33.1684 + vertex -619.751 97.9657 32.1725 + vertex -616.99 97.4071 33.1416 + endloop + endfacet + facet normal -0.325689 -0.840909 0.432203 + outer loop + vertex -617.475 97.6088 33.1684 + vertex -616.99 97.4071 33.1416 + vertex -615.355 97.1935 33.9579 + endloop + endfacet + facet normal -0.31882 -0.856721 0.405441 + outer loop + vertex -617.475 97.6088 33.1684 + vertex -615.355 97.1935 33.9579 + vertex -615.431 97.4141 34.3649 + endloop + endfacet + facet normal -0.330108 -0.799982 0.501056 + outer loop + vertex -623.29 98.7839 31.1578 + vertex -622.847 98.5852 31.1323 + vertex -620.293 98.1535 32.1252 + endloop + endfacet + facet normal -0.326057 -0.815285 0.478537 + outer loop + vertex -623.29 98.7839 31.1578 + vertex -620.293 98.1535 32.1252 + vertex -621.197 98.4211 31.9655 + endloop + endfacet + facet normal -0.325111 -0.791049 0.518212 + outer loop + vertex -623.29 98.7839 31.1578 + vertex -627.113 99.5522 29.9319 + vertex -622.847 98.5852 31.1323 + endloop + endfacet + facet normal -0.327069 -0.779132 0.53477 + outer loop + vertex -624.823 98.6058 29.9537 + vertex -622.847 98.5852 31.1323 + vertex -627.113 99.5522 29.9319 + endloop + endfacet + facet normal -0.321507 -0.787846 0.525293 + outer loop + vertex -621.609 97.8958 30.8555 + vertex -622.847 98.5852 31.1323 + vertex -624.823 98.6058 29.9537 + endloop + endfacet + facet normal -0.325492 -0.761984 0.559852 + outer loop + vertex -624.823 98.6058 29.9537 + vertex -623.124 97.372 29.2621 + vertex -621.609 97.8958 30.8555 + endloop + endfacet + facet normal -0.311976 -0.753759 0.578376 + outer loop + vertex -624.823 98.6058 29.9537 + vertex -626.001 98.1273 28.6949 + vertex -623.124 97.372 29.2621 + endloop + endfacet + facet normal -0.325946 -0.741301 0.586713 + outer loop + vertex -627.481 99.1808 29.2033 + vertex -626.001 98.1273 28.6949 + vertex -624.823 98.6058 29.9537 + endloop + endfacet + facet normal -0.322413 -0.76742 0.554181 + outer loop + vertex -627.481 99.1808 29.2033 + vertex -624.823 98.6058 29.9537 + vertex -627.113 99.5522 29.9319 + endloop + endfacet + facet normal -0.320726 -0.768386 0.553821 + outer loop + vertex -627.481 99.1808 29.2033 + vertex -627.113 99.5522 29.9319 + vertex -630.101 99.9351 28.7329 + endloop + endfacet + facet normal -0.318319 -0.723098 0.613027 + outer loop + vertex -630.101 99.9351 28.7329 + vertex -628.729 98.8629 28.1805 + vertex -627.481 99.1808 29.2033 + endloop + endfacet + facet normal -0.305477 -0.714887 0.628984 + outer loop + vertex -630.101 99.9351 28.7329 + vertex -631.464 99.6015 27.6915 + vertex -628.729 98.8629 28.1805 + endloop + endfacet + facet normal -0.317706 -0.699542 0.640081 + outer loop + vertex -632.848 100.605 28.1017 + vertex -631.464 99.6015 27.6915 + vertex -630.101 99.9351 28.7329 + endloop + endfacet + facet normal -0.316625 -0.745126 0.586972 + outer loop + vertex -632.848 100.605 28.1017 + vertex -630.101 99.9351 28.7329 + vertex -632.645 100.96 28.662 + endloop + endfacet + facet normal -0.310543 -0.747986 0.586583 + outer loop + vertex -632.848 100.605 28.1017 + vertex -632.645 100.96 28.662 + vertex -635.587 101.409 27.6762 + endloop + endfacet + facet normal -0.301507 -0.667047 0.681279 + outer loop + vertex -635.587 101.409 27.6762 + vertex -634.469 100.397 27.1806 + vertex -632.848 100.605 28.1017 + endloop + endfacet + facet normal -0.283295 -0.655914 0.699657 + outer loop + vertex -635.587 101.409 27.6762 + vertex -637.81 101.372 26.7419 + vertex -634.469 100.397 27.1806 + endloop + endfacet + facet normal -0.293882 -0.624518 0.723609 + outer loop + vertex -638.134 102.046 27.192 + vertex -637.81 101.372 26.7419 + vertex -635.587 101.409 27.6762 + endloop + endfacet + facet normal -0.298331 -0.695222 0.653961 + outer loop + vertex -638.134 102.046 27.192 + vertex -635.587 101.409 27.6762 + vertex -638.064 102.343 27.5397 + endloop + endfacet + facet normal -0.269176 -0.704821 0.656332 + outer loop + vertex -638.064 102.343 27.5397 + vertex -641.436 102.593 26.4247 + vertex -638.134 102.046 27.192 + endloop + endfacet + facet normal -0.291081 -0.598525 0.746351 + outer loop + vertex -642.646 103.529 26.7031 + vertex -641.436 102.593 26.4247 + vertex -638.064 102.343 27.5397 + endloop + endfacet + facet normal -0.267029 -0.575364 0.773079 + outer loop + vertex -641.436 102.593 26.4247 + vertex -642.646 103.529 26.7031 + vertex -647.238 104.414 25.7762 + endloop + endfacet + facet normal -0.273457 -0.621652 0.734009 + outer loop + vertex -638.134 102.046 27.192 + vertex -641.436 102.593 26.4247 + vertex -637.81 101.372 26.7419 + endloop + endfacet + facet normal -0.312221 -0.740665 0.594922 + outer loop + vertex -632.645 100.96 28.662 + vertex -638.064 102.343 27.5397 + vertex -635.587 101.409 27.6762 + endloop + endfacet + facet normal -0.29427 -0.680076 0.671493 + outer loop + vertex -632.848 100.605 28.1017 + vertex -634.469 100.397 27.1806 + vertex -631.464 99.6015 27.6915 + endloop + endfacet + facet normal -0.322818 -0.762292 0.560981 + outer loop + vertex -627.113 99.5522 29.9319 + vertex -632.645 100.96 28.662 + vertex -630.101 99.9351 28.7329 + endloop + endfacet + facet normal -0.311538 -0.730933 0.607191 + outer loop + vertex -627.481 99.1808 29.2033 + vertex -628.729 98.8629 28.1805 + vertex -626.001 98.1273 28.6949 + endloop + endfacet + facet normal -0.309359 -0.776305 0.549225 + outer loop + vertex -621.609 97.8958 30.8555 + vertex -623.124 97.372 29.2621 + vertex -620.372 96.6069 29.7306 + endloop + endfacet + facet normal -0.319434 -0.809503 0.492612 + outer loop + vertex -618.659 97.544 32.1842 + vertex -619.495 97.2398 31.142 + vertex -617.677 96.7429 31.5047 + endloop + endfacet + facet normal -0.325981 -0.831794 0.449282 + outer loop + vertex -616.99 97.4071 33.1416 + vertex -619.751 97.9657 32.1725 + vertex -618.659 97.544 32.1842 + endloop + endfacet + facet normal -0.332273 -0.820408 0.465322 + outer loop + vertex -617.177 97.1293 32.4977 + vertex -616.117 96.3848 31.9418 + vertex -615.759 96.8555 33.0278 + endloop + endfacet + facet normal -0.323663 -0.824457 0.464234 + outer loop + vertex -615.759 96.8555 33.0278 + vertex -616.117 96.3848 31.9418 + vertex -614.663 96.0456 32.3531 + endloop + endfacet + facet normal -0.325436 -0.841321 0.43159 + outer loop + vertex -615.355 97.1935 33.9579 + vertex -616.99 97.4071 33.1416 + vertex -614.496 96.8686 33.9724 + endloop + endfacet + facet normal -0.324551 -0.838727 0.437269 + outer loop + vertex -615.355 97.1935 33.9579 + vertex -614.496 96.8686 33.9724 + vertex -613.256 96.7631 34.6905 + endloop + endfacet + facet normal -0.315003 -0.851654 0.418879 + outer loop + vertex -613.256 96.7631 34.6905 + vertex -614.496 96.8686 33.9724 + vertex -612.49 96.358 34.4431 + endloop + endfacet + facet normal -0.328043 -0.825802 0.458737 + outer loop + vertex -615.759 96.8555 33.0278 + vertex -614.663 96.0456 32.3531 + vertex -614.351 96.4784 33.356 + endloop + endfacet + facet normal -0.326552 -0.81087 0.485647 + outer loop + vertex -616.117 96.3848 31.9418 + vertex -614.8 95.4122 31.2036 + vertex -614.663 96.0456 32.3531 + endloop + endfacet + facet normal -0.321054 -0.775011 0.544318 + outer loop + vertex -614.8 95.4122 31.2036 + vertex -616.074 95.4859 30.5571 + vertex -614.004 94.1024 29.808 + endloop + endfacet + facet normal -0.311744 -0.814911 0.488607 + outer loop + vertex -613.222 95.7043 32.7479 + vertex -613.264 94.8731 31.3349 + vertex -611.969 94.6964 31.8665 + endloop + endfacet + facet normal -0.315979 -0.816077 0.483918 + outer loop + vertex -613.222 95.7043 32.7479 + vertex -611.969 94.6964 31.8665 + vertex -611.858 95.3716 33.0778 + endloop + endfacet + facet normal -0.311546 -0.817538 0.484325 + outer loop + vertex -611.858 95.3716 33.0778 + vertex -611.969 94.6964 31.8665 + vertex -610.687 94.2458 31.9306 + endloop + endfacet + facet normal -0.313591 -0.831582 0.458402 + outer loop + vertex -613.086 96.2448 33.8215 + vertex -613.222 95.7043 32.7479 + vertex -611.858 95.3716 33.0778 + endloop + endfacet + facet normal -0.318558 -0.830441 0.457044 + outer loop + vertex -612.49 96.358 34.4431 + vertex -614.496 96.8686 33.9724 + vertex -613.086 96.2448 33.8215 + endloop + endfacet + facet normal -0.302481 -0.831217 0.466459 + outer loop + vertex -611.805 95.8474 33.9683 + vertex -610.677 94.9837 33.161 + vertex -610.963 95.57 34.0205 + endloop + endfacet + facet normal -0.511113 0.234591 -0.82688 + outer loop + vertex -611.242 95.9652 34.5841 + vertex -610.177 95.1009 33.681 + vertex -610.047 94.9764 33.565 + endloop + endfacet + facet normal -0.204567 -0.852892 0.480342 + outer loop + vertex -611.172 96.652 36.1614 + vertex -610.077 95.1542 33.968 + vertex -610.246 95.8686 35.1644 + endloop + endfacet + facet normal -0.310151 -0.865859 0.39255 + outer loop + vertex -610.246 95.8686 35.1644 + vertex -608.376 95.4005 35.6098 + vertex -611.172 96.652 36.1614 + endloop + endfacet + facet normal -0.314917 -0.842438 0.437179 + outer loop + vertex -610.246 95.8686 35.1644 + vertex -609.229 95.2344 34.6749 + vertex -608.376 95.4005 35.6098 + endloop + endfacet + facet normal -0.314117 -0.843058 0.436559 + outer loop + vertex -608.376 95.4005 35.6098 + vertex -609.229 95.2344 34.6749 + vertex -605.556 93.9361 34.8107 + endloop + endfacet + facet normal -0.311818 -0.841332 0.44151 + outer loop + vertex -608.376 95.4005 35.6098 + vertex -605.556 93.9361 34.8107 + vertex -603.111 93.7737 36.228 + endloop + endfacet + facet normal -0.306997 -0.817632 0.487063 + outer loop + vertex -609.229 95.2344 34.6749 + vertex -607.804 93.731 33.0494 + vertex -605.556 93.9361 34.8107 + endloop + endfacet + facet normal -0.304195 -0.820593 0.483832 + outer loop + vertex -605.556 93.9361 34.8107 + vertex -607.804 93.731 33.0494 + vertex -602.481 91.6022 32.7859 + endloop + endfacet + facet normal -0.297925 -0.818599 0.491057 + outer loop + vertex -605.556 93.9361 34.8107 + vertex -602.481 91.6022 32.7859 + vertex -597.151 91.3738 35.6391 + endloop + endfacet + facet normal -0.288238 -0.833269 0.471785 + outer loop + vertex -594.27 89.6563 34.3656 + vertex -597.151 91.3738 35.6391 + vertex -602.481 91.6022 32.7859 + endloop + endfacet + facet normal -0.286089 -0.832124 0.475103 + outer loop + vertex -597.151 91.3738 35.6391 + vertex -594.27 89.6563 34.3656 + vertex -586.188 88.0126 36.3532 + endloop + endfacet + facet normal -0.293498 -0.875835 0.383107 + outer loop + vertex -587.729 88.8735 37.1406 + vertex -597.151 91.3738 35.6391 + vertex -586.188 88.0126 36.3532 + endloop + endfacet + facet normal -0.283518 -0.87218 0.398647 + outer loop + vertex -587.729 88.8735 37.1406 + vertex -586.188 88.0126 36.3532 + vertex -575.75 85.3237 37.8938 + endloop + endfacet + facet normal -0.282717 -0.883555 0.373364 + outer loop + vertex -575.75 85.3237 37.8938 + vertex -586.188 88.0126 36.3532 + vertex -574.342 84.4874 36.9807 + endloop + endfacet + facet normal -0.269383 -0.880167 0.390817 + outer loop + vertex -575.75 85.3237 37.8938 + vertex -574.342 84.4874 36.9807 + vertex -562.955 81.698 38.5475 + endloop + endfacet + facet normal -0.268345 -0.894248 0.358205 + outer loop + vertex -562.955 81.698 38.5475 + vertex -574.342 84.4874 36.9807 + vertex -561.645 80.916 37.5766 + endloop + endfacet + facet normal -0.250487 -0.890671 0.379423 + outer loop + vertex -562.955 81.698 38.5475 + vertex -561.645 80.916 37.5766 + vertex -549.96 78.2621 39.061 + endloop + endfacet + facet normal -0.249115 -0.907139 0.339175 + outer loop + vertex -549.96 78.2621 39.061 + vertex -561.645 80.916 37.5766 + vertex -548.802 77.587 38.1059 + endloop + endfacet + facet normal -0.227881 -0.903698 0.362492 + outer loop + vertex -549.96 78.2621 39.061 + vertex -548.802 77.587 38.1059 + vertex -537.102 75.1773 39.4541 + endloop + endfacet + facet normal -0.226609 -0.917581 0.326639 + outer loop + vertex -537.102 75.1773 39.4541 + vertex -548.802 77.587 38.1059 + vertex -536.018 74.5656 38.4874 + endloop + endfacet + facet normal -0.204416 -0.914371 0.349485 + outer loop + vertex -537.102 75.1773 39.4541 + vertex -536.018 74.5656 38.4874 + vertex -524.665 72.4667 39.6363 + endloop + endfacet + facet normal -0.204173 -0.917455 0.341452 + outer loop + vertex -524.665 72.4667 39.6363 + vertex -536.018 74.5656 38.4874 + vertex -523.698 71.9055 38.7071 + endloop + endfacet + facet normal -0.19591 -0.870016 0.452429 + outer loop + vertex -536.018 74.5656 38.4874 + vertex -535.252 73.3589 36.4987 + vertex -523.698 71.9055 38.7071 + endloop + endfacet + facet normal -0.217541 -0.869368 0.443706 + outer loop + vertex -536.018 74.5656 38.4874 + vertex -547.988 76.3843 36.1824 + vertex -535.252 73.3589 36.4987 + endloop + endfacet + facet normal -0.212835 -0.844584 0.491303 + outer loop + vertex -547.988 76.3843 36.1824 + vertex -547.036 74.3373 33.0757 + vertex -535.252 73.3589 36.4987 + endloop + endfacet + facet normal -0.213635 -0.842409 0.494679 + outer loop + vertex -535.252 73.3589 36.4987 + vertex -547.036 74.3373 33.0757 + vertex -534.428 71.2621 33.2838 + endloop + endfacet + facet normal -0.19261 -0.843769 0.500955 + outer loop + vertex -535.252 73.3589 36.4987 + vertex -534.428 71.2621 33.2838 + vertex -523.143 70.6383 36.5723 + endloop + endfacet + facet normal -0.233352 -0.843286 0.484164 + outer loop + vertex -547.988 76.3843 36.1824 + vertex -559.543 77.5763 32.6894 + vertex -547.036 74.3373 33.0757 + endloop + endfacet + facet normal -0.234503 -0.840145 0.489045 + outer loop + vertex -560.729 79.6696 35.7166 + vertex -559.543 77.5763 32.6894 + vertex -547.988 76.3843 36.1824 + endloop + endfacet + facet normal -0.251678 -0.839373 0.481779 + outer loop + vertex -560.729 79.6696 35.7166 + vertex -571.94 80.9948 32.1689 + vertex -559.543 77.5763 32.6894 + endloop + endfacet + facet normal -0.254259 -0.832299 0.492576 + outer loop + vertex -573.348 83.1733 35.1233 + vertex -571.94 80.9948 32.1689 + vertex -560.729 79.6696 35.7166 + endloop + endfacet + facet normal -0.266208 -0.832028 0.486684 + outer loop + vertex -573.348 83.1733 35.1233 + vertex -584.246 84.5824 31.571 + vertex -571.94 80.9948 32.1689 + endloop + endfacet + facet normal -0.26869 -0.825068 0.49706 + outer loop + vertex -585.305 86.7287 34.5612 + vertex -584.246 84.5824 31.571 + vertex -573.348 83.1733 35.1233 + endloop + endfacet + facet normal -0.276339 -0.824439 0.4939 + outer loop + vertex -585.305 86.7287 34.5612 + vertex -596.013 88.2333 31.082 + vertex -584.246 84.5824 31.571 + endloop + endfacet + facet normal -0.278297 -0.818589 0.502457 + outer loop + vertex -594.27 89.6563 34.3656 + vertex -596.013 88.2333 31.082 + vertex -585.305 86.7287 34.5612 + endloop + endfacet + facet normal -0.289864 -0.812418 0.505922 + outer loop + vertex -596.013 88.2333 31.082 + vertex -594.27 89.6563 34.3656 + vertex -602.481 91.6022 32.7859 + endloop + endfacet + facet normal -0.279557 -0.802977 0.52638 + outer loop + vertex -602.481 91.6022 32.7859 + vertex -603.613 89.8083 29.4482 + vertex -596.013 88.2333 31.082 + endloop + endfacet + facet normal -0.293467 -0.797002 0.527887 + outer loop + vertex -602.481 91.6022 32.7859 + vertex -606.451 91.1626 29.9149 + vertex -603.613 89.8083 29.4482 + endloop + endfacet + facet normal -0.292886 -0.797679 0.527187 + outer loop + vertex -607.804 93.731 33.0494 + vertex -606.451 91.1626 29.9149 + vertex -602.481 91.6022 32.7859 + endloop + endfacet + facet normal -0.218158 -0.866331 0.449308 + outer loop + vertex -548.802 77.587 38.1059 + vertex -547.988 76.3843 36.1824 + vertex -536.018 74.5656 38.4874 + endloop + endfacet + facet normal -0.239266 -0.865584 0.439904 + outer loop + vertex -548.802 77.587 38.1059 + vertex -560.729 79.6696 35.7166 + vertex -547.988 76.3843 36.1824 + endloop + endfacet + facet normal -0.240907 -0.856959 0.455616 + outer loop + vertex -561.645 80.916 37.5766 + vertex -560.729 79.6696 35.7166 + vertex -548.802 77.587 38.1059 + endloop + endfacet + facet normal -0.258821 -0.85653 0.446507 + outer loop + vertex -561.645 80.916 37.5766 + vertex -573.348 83.1733 35.1233 + vertex -560.729 79.6696 35.7166 + endloop + endfacet + facet normal -0.260276 -0.848425 0.460903 + outer loop + vertex -574.342 84.4874 36.9807 + vertex -573.348 83.1733 35.1233 + vertex -561.645 80.916 37.5766 + endloop + endfacet + facet normal -0.27352 -0.848176 0.453635 + outer loop + vertex -574.342 84.4874 36.9807 + vertex -585.305 86.7287 34.5612 + vertex -573.348 83.1733 35.1233 + endloop + endfacet + facet normal -0.27487 -0.840553 0.466816 + outer loop + vertex -586.188 88.0126 36.3532 + vertex -585.305 86.7287 34.5612 + vertex -574.342 84.4874 36.9807 + endloop + endfacet + facet normal -0.294186 -0.86714 0.401898 + outer loop + vertex -596.134 91.5136 36.6847 + vertex -597.151 91.3738 35.6391 + vertex -587.729 88.8735 37.1406 + endloop + endfacet + facet normal -0.305136 -0.858845 0.411433 + outer loop + vertex -597.151 91.3738 35.6391 + vertex -596.134 91.5136 36.6847 + vertex -603.111 93.7737 36.228 + endloop + endfacet + facet normal -0.302086 -0.854168 0.423251 + outer loop + vertex -597.151 91.3738 35.6391 + vertex -603.111 93.7737 36.228 + vertex -605.556 93.9361 34.8107 + endloop + endfacet + facet normal -0.284447 -0.840137 0.4618 + outer loop + vertex -586.188 88.0126 36.3532 + vertex -594.27 89.6563 34.3656 + vertex -585.305 86.7287 34.5612 + endloop + endfacet + facet normal -0.320028 -0.818755 0.476679 + outer loop + vertex -607.804 93.731 33.0494 + vertex -609.229 95.2344 34.6749 + vertex -610.077 95.1542 33.968 + endloop + endfacet + facet normal -0.301855 -0.836725 0.456919 + outer loop + vertex -609.229 95.2344 34.6749 + vertex -610.246 95.8686 35.1644 + vertex -610.077 95.1542 33.968 + endloop + endfacet + facet normal -0.315347 -0.851873 0.418172 + outer loop + vertex -613.256 96.7631 34.6905 + vertex -612.49 96.358 34.4431 + vertex -611.242 95.9652 34.5841 + endloop + endfacet + facet normal -0.317358 -0.857051 0.405891 + outer loop + vertex -615.355 97.1935 33.9579 + vertex -613.256 96.7631 34.6905 + vertex -615.431 97.4141 34.3649 + endloop + endfacet + facet normal -0.331295 -0.850428 0.408676 + outer loop + vertex -615.976 98.2343 35.6552 + vertex -619.679 99.7712 35.8515 + vertex -617.216 98.3208 34.8299 + endloop + endfacet + facet normal -0.334847 -0.846526 0.413849 + outer loop + vertex -617.216 98.3208 34.8299 + vertex -620.773 99.7599 34.8959 + vertex -618.467 98.3371 33.8515 + endloop + endfacet + facet normal -0.323274 -0.850943 0.413992 + outer loop + vertex -615.431 97.4141 34.3649 + vertex -618.453 97.8927 32.9888 + vertex -617.475 97.6088 33.1684 + endloop + endfacet + facet normal -0.332641 -0.836879 0.434724 + outer loop + vertex -618.467 98.3371 33.8515 + vertex -622.755 100.052 33.8713 + vertex -620.955 98.776 32.7922 + endloop + endfacet + facet normal -0.32567 -0.835939 0.441753 + outer loop + vertex -618.453 97.8927 32.9888 + vertex -621.197 98.4211 31.9655 + vertex -620.293 98.1535 32.1252 + endloop + endfacet + facet normal -0.330427 -0.825671 0.457259 + outer loop + vertex -620.955 98.776 32.7922 + vertex -625.309 100.546 32.8431 + vertex -623.589 99.2966 31.8291 + endloop + endfacet + facet normal -0.327955 -0.810267 0.485709 + outer loop + vertex -621.197 98.4211 31.9655 + vertex -623.605 98.9496 31.2211 + vertex -623.29 98.7839 31.1578 + endloop + endfacet + facet normal -0.324768 -0.804466 0.497353 + outer loop + vertex -626.139 99.5057 30.4659 + vertex -623.605 98.9496 31.2211 + vertex -626.37 99.8879 30.9337 + endloop + endfacet + facet normal -0.325296 -0.804431 0.497064 + outer loop + vertex -626.37 99.8879 30.9337 + vertex -629.093 100.484 30.116 + vertex -626.139 99.5057 30.4659 + endloop + endfacet + facet normal -0.323854 -0.793669 0.514983 + outer loop + vertex -630.035 100.51 29.5634 + vertex -626.139 99.5057 30.4659 + vertex -629.093 100.484 30.116 + endloop + endfacet + facet normal -0.324696 -0.79235 0.516482 + outer loop + vertex -629.093 100.484 30.116 + vertex -634.703 102.267 29.3247 + vertex -630.035 100.51 29.5634 + endloop + endfacet + facet normal -0.322384 -0.784382 0.529919 + outer loop + vertex -632.906 101.278 28.9542 + vertex -630.035 100.51 29.5634 + vertex -634.703 102.267 29.3247 + endloop + endfacet + facet normal -0.318517 -0.780407 0.538064 + outer loop + vertex -635.879 102.074 28.348 + vertex -632.906 101.278 28.9542 + vertex -634.703 102.267 29.3247 + endloop + endfacet + facet normal -0.320341 -0.778412 0.539867 + outer loop + vertex -634.703 102.267 29.3247 + vertex -640.773 103.869 28.0331 + vertex -635.879 102.074 28.348 + endloop + endfacet + facet normal -0.31685 -0.765321 0.560259 + outer loop + vertex -638.625 102.775 27.7534 + vertex -635.879 102.074 28.348 + vertex -640.773 103.869 28.0331 + endloop + endfacet + facet normal -0.30933 -0.755102 0.578045 + outer loop + vertex -641.357 103.509 27.2496 + vertex -638.625 102.775 27.7534 + vertex -640.773 103.869 28.0331 + endloop + endfacet + facet normal -0.310266 -0.754423 0.57843 + outer loop + vertex -640.773 103.869 28.0331 + vertex -646.3 105.302 26.9376 + vertex -641.357 103.509 27.2496 + endloop + endfacet + facet normal -0.305036 -0.735364 0.605139 + outer loop + vertex -643.669 104.087 26.7875 + vertex -641.357 103.509 27.2496 + vertex -646.3 105.302 26.9376 + endloop + endfacet + facet normal -0.302525 -0.657631 0.689928 + outer loop + vertex -641.357 103.509 27.2496 + vertex -643.669 104.087 26.7875 + vertex -642.646 103.529 26.7031 + endloop + endfacet + facet normal -0.286338 -0.632519 0.719674 + outer loop + vertex -643.669 104.087 26.7875 + vertex -645.372 104.448 26.4266 + vertex -642.646 103.529 26.7031 + endloop + endfacet + facet normal -0.286698 -0.701492 0.652467 + outer loop + vertex -645.372 104.448 26.4266 + vertex -643.669 104.087 26.7875 + vertex -646.3 105.302 26.9376 + endloop + endfacet + facet normal -0.293203 -0.704724 0.646063 + outer loop + vertex -648.098 105.324 26.1452 + vertex -645.372 104.448 26.4266 + vertex -646.3 105.302 26.9376 + endloop + endfacet + facet normal -0.296214 -0.696926 0.653109 + outer loop + vertex -646.3 105.302 26.9376 + vertex -651.714 106.929 26.2183 + vertex -648.098 105.324 26.1452 + endloop + endfacet + facet normal -0.299715 -0.721218 0.624512 + outer loop + vertex -646.3 105.302 26.9376 + vertex -652.951 108.385 27.3051 + vertex -651.714 106.929 26.2183 + endloop + endfacet + facet normal -0.305048 -0.722611 0.620305 + outer loop + vertex -652.951 108.385 27.3051 + vertex -655.922 109.109 26.6883 + vertex -651.714 106.929 26.2183 + endloop + endfacet + facet normal -0.310197 -0.742185 0.594088 + outer loop + vertex -640.773 103.869 28.0331 + vertex -648.286 107.066 28.1042 + vertex -646.3 105.302 26.9376 + endloop + endfacet + facet normal -0.311428 -0.74271 0.592786 + outer loop + vertex -648.286 107.066 28.1042 + vertex -652.951 108.385 27.3051 + vertex -646.3 105.302 26.9376 + endloop + endfacet + facet normal -0.311504 -0.743938 0.591203 + outer loop + vertex -648.286 107.066 28.1042 + vertex -656.299 110.833 28.6217 + vertex -652.951 108.385 27.3051 + endloop + endfacet + facet normal -0.315626 -0.746588 0.58565 + outer loop + vertex -656.299 110.833 28.6217 + vertex -658.993 111.454 27.9623 + vertex -652.951 108.385 27.3051 + endloop + endfacet + facet normal -0.307552 -0.711785 0.631485 + outer loop + vertex -638.625 102.775 27.7534 + vertex -641.357 103.509 27.2496 + vertex -638.064 102.343 27.5397 + endloop + endfacet + facet normal -0.31757 -0.718507 0.618787 + outer loop + vertex -635.879 102.074 28.348 + vertex -638.625 102.775 27.7534 + vertex -638.064 102.343 27.5397 + endloop + endfacet + facet normal -0.312225 -0.738429 0.597694 + outer loop + vertex -638.064 102.343 27.5397 + vertex -632.645 100.96 28.662 + vertex -635.879 102.074 28.348 + endloop + endfacet + facet normal -0.320693 -0.767584 0.554951 + outer loop + vertex -634.703 102.267 29.3247 + vertex -643.189 105.69 29.1549 + vertex -640.773 103.869 28.0331 + endloop + endfacet + facet normal -0.321585 -0.768051 0.553788 + outer loop + vertex -643.189 105.69 29.1549 + vertex -648.286 107.066 28.1042 + vertex -640.773 103.869 28.0331 + endloop + endfacet + facet normal -0.321632 -0.764208 0.559053 + outer loop + vertex -643.189 105.69 29.1549 + vertex -651.443 109.291 29.3291 + vertex -648.286 107.066 28.1042 + endloop + endfacet + facet normal -0.324042 -0.765718 0.555583 + outer loop + vertex -651.443 109.291 29.3291 + vertex -656.299 110.833 28.6217 + vertex -648.286 107.066 28.1042 + endloop + endfacet + facet normal -0.324332 -0.768433 0.551652 + outer loop + vertex -656.299 110.833 28.6217 + vertex -651.443 109.291 29.3291 + vertex -658.285 112.472 29.7378 + endloop + endfacet + facet normal -0.328879 -0.770309 0.546317 + outer loop + vertex -661.048 113.441 29.4408 + vertex -656.299 110.833 28.6217 + vertex -658.285 112.472 29.7378 + endloop + endfacet + facet normal -0.331148 -0.782698 0.526995 + outer loop + vertex -658.285 112.472 29.7378 + vertex -662.776 114.63 30.1212 + vertex -661.048 113.441 29.4408 + endloop + endfacet + facet normal -0.330633 -0.782394 0.527771 + outer loop + vertex -662.776 114.63 30.1212 + vertex -664.001 114.899 29.7517 + vertex -661.048 113.441 29.4408 + endloop + endfacet + facet normal -0.321813 -0.769594 0.551509 + outer loop + vertex -661.048 113.441 29.4408 + vertex -664.001 114.899 29.7517 + vertex -661.639 113.356 28.9774 + endloop + endfacet + facet normal -0.327352 -0.773593 0.542581 + outer loop + vertex -664.001 114.899 29.7517 + vertex -664.15 114.663 29.3258 + vertex -661.639 113.356 28.9774 + endloop + endfacet + facet normal -0.32025 -0.764456 0.559506 + outer loop + vertex -661.639 113.356 28.9774 + vertex -664.15 114.663 29.3258 + vertex -662.32 113.454 28.7209 + endloop + endfacet + facet normal -0.323212 -0.75452 0.571168 + outer loop + vertex -662.32 113.454 28.7209 + vertex -658.993 111.454 27.9623 + vertex -661.639 113.356 28.9774 + endloop + endfacet + facet normal -0.315415 -0.749484 0.582055 + outer loop + vertex -658.993 111.454 27.9623 + vertex -656.299 110.833 28.6217 + vertex -661.639 113.356 28.9774 + endloop + endfacet + facet normal -0.308723 -0.74029 0.59721 + outer loop + vertex -662.32 113.454 28.7209 + vertex -662.491 113.381 28.542 + vertex -658.993 111.454 27.9623 + endloop + endfacet + facet normal -0.308353 -0.739843 0.597955 + outer loop + vertex -658.993 111.454 27.9623 + vertex -662.491 113.381 28.542 + vertex -659.174 110.941 27.2338 + endloop + endfacet + facet normal -0.299209 -0.748664 0.591588 + outer loop + vertex -662.32 113.454 28.7209 + vertex -664.15 114.663 29.3258 + vertex -662.491 113.381 28.542 + endloop + endfacet + facet normal -0.28428 -0.740196 0.60934 + outer loop + vertex -662.491 113.381 28.542 + vertex -664.15 114.663 29.3258 + vertex -665.285 115.329 29.6047 + endloop + endfacet + facet normal -0.323422 -0.777552 0.539269 + outer loop + vertex -665.763 115.798 29.9947 + vertex -665.285 115.329 29.6047 + vertex -664.15 114.663 29.3258 + endloop + endfacet + facet normal -0.32146 -0.776416 0.542072 + outer loop + vertex -664.15 114.663 29.3258 + vertex -664.001 114.899 29.7517 + vertex -665.763 115.798 29.9947 + endloop + endfacet + facet normal -0.331115 -0.788791 0.517854 + outer loop + vertex -665.228 115.81 30.3547 + vertex -665.763 115.798 29.9947 + vertex -664.001 114.899 29.7517 + endloop + endfacet + facet normal -0.324968 -0.765864 0.554841 + outer loop + vertex -661.048 113.441 29.4408 + vertex -661.639 113.356 28.9774 + vertex -656.299 110.833 28.6217 + endloop + endfacet + facet normal -0.335654 -0.788185 0.51585 + outer loop + vertex -655.327 111.713 30.503 + vertex -658.285 112.472 29.7378 + vertex -651.443 109.291 29.3291 + endloop + endfacet + facet normal -0.335448 -0.789904 0.513349 + outer loop + vertex -655.327 111.713 30.503 + vertex -660.919 114.162 30.6161 + vertex -658.285 112.472 29.7378 + endloop + endfacet + facet normal -0.318724 -0.769981 0.55276 + outer loop + vertex -632.906 101.278 28.9542 + vertex -635.879 102.074 28.348 + vertex -632.645 100.96 28.662 + endloop + endfacet + facet normal -0.325234 -0.798291 0.506907 + outer loop + vertex -629.093 100.484 30.116 + vertex -631.432 101.775 30.6482 + vertex -634.703 102.267 29.3247 + endloop + endfacet + facet normal -0.328065 -0.790835 0.516676 + outer loop + vertex -638.976 104.781 30.4594 + vertex -634.703 102.267 29.3247 + vertex -631.432 101.775 30.6482 + endloop + endfacet + facet normal -0.32983 -0.792306 0.513287 + outer loop + vertex -638.976 104.781 30.4594 + vertex -643.189 105.69 29.1549 + vertex -634.703 102.267 29.3247 + endloop + endfacet + facet normal -0.330946 -0.787112 0.520509 + outer loop + vertex -638.976 104.781 30.4594 + vertex -647.604 108.393 30.4361 + vertex -643.189 105.69 29.1549 + endloop + endfacet + facet normal -0.333335 -0.788958 0.516171 + outer loop + vertex -647.604 108.393 30.4361 + vertex -651.443 109.291 29.3291 + vertex -643.189 105.69 29.1549 + endloop + endfacet + facet normal -0.324291 -0.788421 0.522712 + outer loop + vertex -626.139 99.5057 30.4659 + vertex -630.035 100.51 29.5634 + vertex -627.113 99.5522 29.9319 + endloop + endfacet + facet normal -0.326717 -0.784218 0.527502 + outer loop + vertex -627.113 99.5522 29.9319 + vertex -623.29 98.7839 31.1578 + vertex -626.139 99.5057 30.4659 + endloop + endfacet + facet normal -0.324303 -0.806568 0.494243 + outer loop + vertex -623.605 98.9496 31.2211 + vertex -626.139 99.5057 30.4659 + vertex -623.29 98.7839 31.1578 + endloop + endfacet + facet normal -0.333256 -0.826569 0.453567 + outer loop + vertex -625.309 100.546 32.8431 + vertex -628.359 101.205 31.8024 + vertex -623.589 99.2966 31.8291 + endloop + endfacet + facet normal -0.326402 -0.799384 0.504427 + outer loop + vertex -626.37 99.8879 30.9337 + vertex -631.432 101.775 30.6482 + vertex -629.093 100.484 30.116 + endloop + endfacet + facet normal -0.33975 -0.826913 0.44809 + outer loop + vertex -632.066 103.51 33.2448 + vertex -635.592 104.223 31.8878 + vertex -628.359 101.205 31.8024 + endloop + endfacet + facet normal -0.348489 -0.823201 0.448214 + outer loop + vertex -651.519 111.92 33.7264 + vertex -653.131 111.524 31.7468 + vertex -644.589 108.016 31.945 + endloop + endfacet + facet normal -0.333718 -0.786747 0.51929 + outer loop + vertex -647.604 108.393 30.4361 + vertex -655.327 111.713 30.503 + vertex -651.443 109.291 29.3291 + endloop + endfacet + facet normal -0.352131 -0.820339 0.450609 + outer loop + vertex -653.131 111.524 31.7468 + vertex -651.519 111.92 33.7264 + vertex -658.633 114.364 32.6168 + endloop + endfacet + facet normal -0.346188 -0.826296 0.444284 + outer loop + vertex -658.633 114.364 32.6168 + vertex -662.735 115.738 31.9752 + vertex -661.528 115.142 31.8077 + endloop + endfacet + facet normal -0.337223 -0.815475 0.470406 + outer loop + vertex -661.528 115.142 31.8077 + vertex -662.735 115.738 31.9752 + vertex -662.849 115.358 31.2359 + endloop + endfacet + facet normal -0.335812 -0.81602 0.470469 + outer loop + vertex -662.735 115.738 31.9752 + vertex -665.068 116.071 30.8872 + vertex -662.849 115.358 31.2359 + endloop + endfacet + facet normal -0.340973 -0.801502 0.491256 + outer loop + vertex -659.29 113.958 31.4152 + vertex -660.919 114.162 30.6161 + vertex -655.327 111.713 30.503 + endloop + endfacet + facet normal -0.336067 -0.790322 0.512298 + outer loop + vertex -660.919 114.162 30.6161 + vertex -662.776 114.63 30.1212 + vertex -658.285 112.472 29.7378 + endloop + endfacet + facet normal -0.329524 -0.788056 0.519982 + outer loop + vertex -664.001 114.899 29.7517 + vertex -662.776 114.63 30.1212 + vertex -665.228 115.81 30.3547 + endloop + endfacet + facet normal -0.335342 -0.806492 0.486946 + outer loop + vertex -663.936 115.469 30.6714 + vertex -662.849 115.358 31.2359 + vertex -665.068 116.071 30.8872 + endloop + endfacet + facet normal -0.328613 -0.792191 0.514245 + outer loop + vertex -665.763 115.798 29.9947 + vertex -665.228 115.81 30.3547 + vertex -666.248 116.24 30.3659 + endloop + endfacet + facet normal -0.330356 -0.792616 0.51247 + outer loop + vertex -666.248 116.24 30.3659 + vertex -666.376 116.129 30.1113 + vertex -665.763 115.798 29.9947 + endloop + endfacet + facet normal -0.314331 -0.775343 0.547758 + outer loop + vertex -665.763 115.798 29.9947 + vertex -666.376 116.129 30.1113 + vertex -665.285 115.329 29.6047 + endloop + endfacet + facet normal -0.374325 -0.79622 0.475304 + outer loop + vertex -664.199 114.469 29.0202 + vertex -662.491 113.381 28.542 + vertex -665.285 115.329 29.6047 + endloop + endfacet + facet normal -0.32765 -0.792353 0.514608 + outer loop + vertex -665.834 115.669 29.7447 + vertex -666.617 116.171 30.019 + vertex -666.909 116.136 29.7785 + endloop + endfacet + facet normal -0.323068 -0.797334 0.509789 + outer loop + vertex -666.909 116.136 29.7785 + vertex -666.617 116.171 30.019 + vertex -667.628 116.582 30.0213 + endloop + endfacet + facet normal -0.323085 -0.798189 0.50844 + outer loop + vertex -667.628 116.582 30.0213 + vertex -669.667 117.44 30.0716 + vertex -669.556 117.188 29.747 + endloop + endfacet + facet normal -0.328474 -0.797452 0.506137 + outer loop + vertex -671.404 118.367 30.4185 + vertex -668.483 117.134 30.3725 + vertex -670.013 118.179 31.0256 + endloop + endfacet + facet normal -0.33395 -0.784362 0.522736 + outer loop + vertex -674.051 120.021 31.2099 + vertex -671.404 118.367 30.4185 + vertex -670.013 118.179 31.0256 + endloop + endfacet + facet normal -0.328219 -0.800826 0.500949 + outer loop + vertex -672.538 118.577 30.0086 + vertex -669.667 117.44 30.0716 + vertex -673.387 118.999 30.1267 + endloop + endfacet + facet normal -0.323679 -0.776494 0.540638 + outer loop + vertex -675.404 120.076 30.4794 + vertex -671.404 118.367 30.4185 + vertex -674.051 120.021 31.2099 + endloop + endfacet + facet normal -0.323825 -0.777451 0.539173 + outer loop + vertex -673.387 118.999 30.1267 + vertex -678.774 121.326 30.247 + vertex -675.825 119.94 30.0196 + endloop + endfacet + facet normal -0.325711 -0.762581 0.558912 + outer loop + vertex -682.879 123.577 30.9264 + vertex -678.774 121.326 30.247 + vertex -678.66 121.507 30.5608 + endloop + endfacet + facet normal -0.311837 -0.73923 0.596906 + outer loop + vertex -689.57 126.752 31.3624 + vertex -682.879 123.577 30.9264 + vertex -685.319 125.894 32.5213 + endloop + endfacet + facet normal -0.324591 -0.738859 0.590532 + outer loop + vertex -685.319 125.894 32.5213 + vertex -678.35 122.941 32.6569 + vertex -683.625 126.9 34.7103 + endloop + endfacet + facet normal -0.331774 -0.733256 0.593516 + outer loop + vertex -690.086 129.715 34.5763 + vertex -685.319 125.894 32.5213 + vertex -683.625 126.9 34.7103 + endloop + endfacet + facet normal -0.328972 -0.7668 0.551176 + outer loop + vertex -678.9 122.124 31.2422 + vertex -675.404 120.076 30.4794 + vertex -674.051 120.021 31.2099 + endloop + endfacet + facet normal -0.352401 -0.768787 0.533648 + outer loop + vertex -676.518 123.494 34.5317 + vertex -669.31 119.684 33.8021 + vertex -674.205 124.022 36.8189 + endloop + endfacet + facet normal -0.368034 -0.752786 0.54577 + outer loop + vertex -681.925 127.978 37.0696 + vertex -676.518 123.494 34.5317 + vertex -674.205 124.022 36.8189 + endloop + endfacet + facet normal -0.36106 -0.74051 0.566816 + outer loop + vertex -681.925 127.978 37.0696 + vertex -674.205 124.022 36.8189 + vertex -680.404 129.112 39.52 + endloop + endfacet + facet normal -0.380833 -0.72614 0.57244 + outer loop + vertex -687.184 132.576 39.4039 + vertex -681.925 127.978 37.0696 + vertex -680.404 129.112 39.52 + endloop + endfacet + facet normal -0.331535 -0.779886 0.530907 + outer loop + vertex -674.051 120.021 31.2099 + vertex -670.013 118.179 31.0256 + vertex -672.491 120.157 32.3844 + endloop + endfacet + facet normal -0.336211 -0.801515 0.494505 + outer loop + vertex -670.013 118.179 31.0256 + vertex -668.483 117.134 30.3725 + vertex -667.306 116.994 30.9453 + endloop + endfacet + facet normal -0.33513 -0.814524 0.473537 + outer loop + vertex -667.306 116.994 30.9453 + vertex -666.703 116.453 30.4421 + vertex -665.501 116.366 31.1433 + endloop + endfacet + facet normal -0.338937 -0.787988 0.514001 + outer loop + vertex -669.31 119.684 33.8021 + vertex -668.688 118.151 31.8634 + vertex -666.202 117.164 31.9894 + endloop + endfacet + facet normal -0.378529 -0.776971 0.503023 + outer loop + vertex -674.205 124.022 36.8189 + vertex -669.31 119.684 33.8021 + vertex -665.963 119.755 36.4311 + endloop + endfacet + facet normal -0.376167 -0.773103 0.510695 + outer loop + vertex -674.205 124.022 36.8189 + vertex -665.963 119.755 36.4311 + vertex -672.258 124.773 39.3898 + endloop + endfacet + facet normal -0.394995 -0.75715 0.52029 + outer loop + vertex -680.404 129.112 39.52 + vertex -674.205 124.022 36.8189 + vertex -672.258 124.773 39.3898 + endloop + endfacet + facet normal -0.387189 -0.743254 0.54558 + outer loop + vertex -680.404 129.112 39.52 + vertex -672.258 124.773 39.3898 + vertex -679.189 130.128 41.7665 + endloop + endfacet + facet normal -0.357618 -0.820317 0.446307 + outer loop + vertex -664.164 117.121 33.4133 + vertex -661.448 116.121 33.7524 + vertex -661.489 116.926 35.1981 + endloop + endfacet + facet normal -0.370623 -0.816028 0.443551 + outer loop + vertex -661.489 116.926 35.1981 + vertex -661.448 116.121 33.7524 + vertex -659.212 116.198 35.763 + endloop + endfacet + facet normal -0.32108 -0.862912 0.390244 + outer loop + vertex -659.212 116.198 35.763 + vertex -661.448 116.121 33.7524 + vertex -659.979 115.909 34.4929 + endloop + endfacet + facet normal -0.405434 -0.784943 0.468496 + outer loop + vertex -672.258 124.773 39.3898 + vertex -665.963 119.755 36.4311 + vertex -664.468 120.767 39.4213 + endloop + endfacet + facet normal -0.400836 -0.775853 0.48722 + outer loop + vertex -672.258 124.773 39.3898 + vertex -664.468 120.767 39.4213 + vertex -670.941 125.528 41.677 + endloop + endfacet + facet normal -0.419527 -0.761945 0.493393 + outer loop + vertex -679.189 130.128 41.7665 + vertex -672.258 124.773 39.3898 + vertex -670.941 125.528 41.677 + endloop + endfacet + facet normal -0.411096 -0.747382 0.521939 + outer loop + vertex -679.189 130.128 41.7665 + vertex -670.941 125.528 41.677 + vertex -678.216 130.749 43.422 + endloop + endfacet + facet normal -0.421954 -0.786987 0.450117 + outer loop + vertex -670.941 125.528 41.677 + vertex -664.468 120.767 39.4213 + vertex -663.294 121.388 41.6059 + endloop + endfacet + facet normal -0.419593 -0.782788 0.459548 + outer loop + vertex -670.941 125.528 41.677 + vertex -663.294 121.388 41.6059 + vertex -670.037 125.963 43.2424 + endloop + endfacet + facet normal -0.434749 -0.793245 0.426328 + outer loop + vertex -670.037 125.963 43.2424 + vertex -663.294 121.388 41.6059 + vertex -662.584 121.771 43.0431 + endloop + endfacet + facet normal -0.444512 -0.808654 0.385341 + outer loop + vertex -670.037 125.963 43.2424 + vertex -662.584 121.771 43.0431 + vertex -669.422 126.034 44.1002 + endloop + endfacet + facet normal -0.454606 -0.817164 0.354367 + outer loop + vertex -669.422 126.034 44.1002 + vertex -662.584 121.771 43.0431 + vertex -662.363 122.003 43.8631 + endloop + endfacet + facet normal -0.48235 -0.855886 0.186542 + outer loop + vertex -669.422 126.034 44.1002 + vertex -662.363 122.003 43.8631 + vertex -668.441 125.611 44.6955 + endloop + endfacet + facet normal -0.502721 -0.831124 0.237708 + outer loop + vertex -676.842 130.803 45.085 + vertex -669.422 126.034 44.1002 + vertex -668.441 125.611 44.6955 + endloop + endfacet + facet normal -0.47263 -0.850078 0.232354 + outer loop + vertex -668.441 125.611 44.6955 + vertex -662.363 122.003 43.8631 + vertex -662.192 122.025 44.2905 + endloop + endfacet + facet normal -0.438538 -0.871421 0.219797 + outer loop + vertex -662.192 122.025 44.2905 + vertex -662.363 122.003 43.8631 + vertex -657.824 119.837 44.3296 + endloop + endfacet + facet normal -0.433466 -0.860436 0.267876 + outer loop + vertex -657.824 119.837 44.3296 + vertex -660.311 121.176 44.6059 + vertex -662.192 122.025 44.2905 + endloop + endfacet + facet normal -0.43283 -0.829881 0.352074 + outer loop + vertex -662.363 122.003 43.8631 + vertex -662.584 121.771 43.0431 + vertex -656.826 118.798 43.1131 + endloop + endfacet + facet normal -0.422117 -0.807735 0.41156 + outer loop + vertex -657.733 118.562 41.7195 + vertex -656.826 118.798 43.1131 + vertex -662.584 121.771 43.0431 + endloop + endfacet + facet normal -0.408791 -0.818027 0.404625 + outer loop + vertex -657.733 118.562 41.7195 + vertex -654.6 117.209 42.1503 + vertex -656.826 118.798 43.1131 + endloop + endfacet + facet normal -0.417756 -0.805079 0.421102 + outer loop + vertex -662.584 121.771 43.0431 + vertex -663.294 121.388 41.6059 + vertex -657.733 118.562 41.7195 + endloop + endfacet + facet normal -0.417278 -0.804039 0.423557 + outer loop + vertex -658.9 118.127 39.7455 + vertex -657.733 118.562 41.7195 + vertex -663.294 121.388 41.6059 + endloop + endfacet + facet normal -0.40214 -0.815081 0.417045 + outer loop + vertex -658.9 118.127 39.7455 + vertex -655.831 116.885 40.2772 + vertex -657.733 118.562 41.7195 + endloop + endfacet + facet normal -0.404837 -0.79915 0.444372 + outer loop + vertex -663.294 121.388 41.6059 + vertex -664.468 120.767 39.4213 + vertex -658.9 118.127 39.7455 + endloop + endfacet + facet normal -0.370283 -0.818952 0.438415 + outer loop + vertex -661.489 116.926 35.1981 + vertex -659.212 116.198 35.763 + vertex -660.317 117.547 37.3494 + endloop + endfacet + facet normal -0.346201 -0.85784 0.37981 + outer loop + vertex -655.963 116.277 38.8598 + vertex -657.864 116.036 36.583 + vertex -656.114 115.703 37.4272 + endloop + endfacet + facet normal -0.402211 -0.816355 0.414477 + outer loop + vertex -658.9 118.127 39.7455 + vertex -657.393 116.514 38.0309 + vertex -655.831 116.885 40.2772 + endloop + endfacet + facet normal -0.35816 -0.853699 0.378047 + outer loop + vertex -654.36 116.588 41.0811 + vertex -655.963 116.277 38.8598 + vertex -653.987 115.809 39.6752 + endloop + endfacet + facet normal -0.408481 -0.815764 0.409478 + outer loop + vertex -657.733 118.562 41.7195 + vertex -655.831 116.885 40.2772 + vertex -654.6 117.209 42.1503 + endloop + endfacet + facet normal -0.363901 -0.851123 0.378373 + outer loop + vertex -652.961 117.015 43.3864 + vertex -654.36 116.588 41.0811 + vertex -652.752 116.188 41.7295 + endloop + endfacet + facet normal -0.406244 -0.817116 0.409009 + outer loop + vertex -656.826 118.798 43.1131 + vertex -654.6 117.209 42.1503 + vertex -653.717 117.253 43.1153 + endloop + endfacet + facet normal -0.41173 -0.828199 0.380217 + outer loop + vertex -656.826 118.798 43.1131 + vertex -653.717 117.253 43.1153 + vertex -654.25 117.711 43.5362 + endloop + endfacet + facet normal -0.4119 -0.831561 0.372619 + outer loop + vertex -656.826 118.798 43.1131 + vertex -654.25 117.711 43.5362 + vertex -657.824 119.837 44.3296 + endloop + endfacet + facet normal -0.39952 -0.827368 0.394773 + outer loop + vertex -654.25 117.711 43.5362 + vertex -653.717 117.253 43.1153 + vertex -653.096 117.062 43.343 + endloop + endfacet + facet normal -0.406641 -0.843826 0.350143 + outer loop + vertex -649.291 116.228 45.4901 + vertex -652.359 119.722 50.3493 + vertex -654.991 119.25 46.1533 + endloop + endfacet + facet normal -0.386239 -0.852023 0.353379 + outer loop + vertex -650.779 116.188 43.7773 + vertex -652.961 117.015 43.3864 + vertex -651.686 116.362 43.2071 + endloop + endfacet + facet normal -0.383704 -0.855227 0.348365 + outer loop + vertex -648.123 114.705 43.0637 + vertex -650.779 116.188 43.7773 + vertex -651.686 116.362 43.2071 + endloop + endfacet + facet normal -0.393318 -0.853115 0.342777 + outer loop + vertex -645.319 113.572 43.4374 + vertex -644.228 113.735 45.0958 + vertex -649.291 116.228 45.4901 + endloop + endfacet + facet normal -0.396652 -0.875574 0.27575 + outer loop + vertex -642.63 111.939 42.3652 + vertex -644.075 112.55 42.2262 + vertex -639.744 110.329 41.4066 + endloop + endfacet + facet normal -0.386802 -0.857618 0.338932 + outer loop + vertex -642.208 112.082 43.2188 + vertex -644.228 113.735 45.0958 + vertex -645.319 113.572 43.4374 + endloop + endfacet + facet normal -0.394678 -0.874924 0.280601 + outer loop + vertex -640.609 110.956 42.1423 + vertex -642.63 111.939 42.3652 + vertex -639.744 110.329 41.4066 + endloop + endfacet + facet normal -0.378486 -0.862515 0.335882 + outer loop + vertex -639.336 110.677 42.8474 + vertex -640.668 112.005 44.757 + vertex -642.208 112.082 43.2188 + endloop + endfacet + facet normal -0.386555 -0.875322 0.290493 + outer loop + vertex -638.446 109.871 41.7524 + vertex -640.609 110.956 42.1423 + vertex -639.744 110.329 41.4066 + endloop + endfacet + facet normal -0.371752 -0.866675 0.332679 + outer loop + vertex -636.469 109.242 42.3114 + vertex -637.595 110.51 44.3565 + vertex -639.336 110.677 42.8474 + endloop + endfacet + facet normal -0.367608 -0.869351 0.330292 + outer loop + vertex -633.31 107.612 41.5373 + vertex -634.622 109.043 43.8451 + vertex -636.469 109.242 42.3114 + endloop + endfacet + facet normal -0.395394 -0.885613 0.243626 + outer loop + vertex -633.275 107.223 40.5416 + vertex -635.667 108.436 41.0682 + vertex -632.609 106.762 39.9469 + endloop + endfacet + facet normal -0.375647 -0.887419 0.267164 + outer loop + vertex -631.714 106.528 40.429 + vertex -633.275 107.223 40.5416 + vertex -632.609 106.762 39.9469 + endloop + endfacet + facet normal -0.362708 -0.871903 0.328981 + outer loop + vertex -630.259 106.204 41.1679 + vertex -631.628 107.577 43.2989 + vertex -633.31 107.612 41.5373 + endloop + endfacet + facet normal -0.376355 -0.886602 0.268874 + outer loop + vertex -629.523 105.483 40.0496 + vertex -631.714 106.528 40.429 + vertex -632.609 106.762 39.9469 + endloop + endfacet + facet normal -0.358223 -0.87407 0.328143 + outer loop + vertex -627.239 104.747 40.5857 + vertex -628.635 106.143 42.7802 + vertex -630.259 106.204 41.1679 + endloop + endfacet + facet normal -0.354984 -0.874938 0.329348 + outer loop + vertex -623.608 102.943 39.7055 + vertex -625.549 104.667 42.1943 + vertex -627.239 104.747 40.5857 + endloop + endfacet + facet normal -0.361365 -0.875809 0.319959 + outer loop + vertex -622.704 102.085 38.4398 + vertex -626.323 103.881 39.2673 + vertex -623.236 102.126 37.9512 + endloop + endfacet + facet normal -0.343769 -0.871129 0.350652 + outer loop + vertex -621.035 101.385 38.3593 + vertex -620.381 101.465 39.1986 + vertex -623.608 102.943 39.7055 + endloop + endfacet + facet normal -0.359692 -0.877203 0.318019 + outer loop + vertex -620.44 100.911 37.7628 + vertex -622.704 102.085 38.4398 + vertex -623.236 102.126 37.9512 + endloop + endfacet + facet normal -0.342811 -0.871782 0.349967 + outer loop + vertex -618.698 100.228 37.7654 + vertex -620.381 101.465 39.1986 + vertex -621.035 101.385 38.3593 + endloop + endfacet + facet normal -0.363683 -0.88306 0.296545 + outer loop + vertex -617.898 99.6488 37.1208 + vertex -620.44 100.911 37.7628 + vertex -623.236 102.126 37.9512 + endloop + endfacet + facet normal -0.335489 -0.867474 0.367338 + outer loop + vertex -618.698 100.228 37.7654 + vertex -615.919 98.8879 37.1386 + vertex -617.314 99.7716 37.952 + endloop + endfacet + facet normal -0.331814 -0.862872 0.381249 + outer loop + vertex -614.379 98.0274 36.5141 + vertex -617.898 99.6488 37.1208 + vertex -616.636 98.9198 36.5692 + endloop + endfacet + facet normal -0.334937 -0.868051 0.366477 + outer loop + vertex -615.919 98.8879 37.1386 + vertex -613.722 97.9053 36.8194 + vertex -614.491 98.4974 37.5192 + endloop + endfacet + facet normal -0.332488 -0.86961 0.365008 + outer loop + vertex -613.722 97.9053 36.8194 + vertex -612.226 97.192 36.4829 + vertex -612.445 97.5788 37.2045 + endloop + endfacet + facet normal -0.33803 -0.876261 0.34337 + outer loop + vertex -611.172 96.652 36.1614 + vertex -614.379 98.0274 36.5141 + vertex -616.636 98.9198 36.5692 + endloop + endfacet + facet normal -0.327831 -0.872094 0.363289 + outer loop + vertex -612.226 97.192 36.4829 + vertex -611.268 96.7574 36.3035 + vertex -611.194 96.9729 36.8883 + endloop + endfacet + facet normal -0.320128 -0.87442 0.364564 + outer loop + vertex -610.771 96.6806 36.5555 + vertex -610.718 96.7999 36.8887 + vertex -611.268 96.7574 36.3035 + endloop + endfacet + facet normal -0.517664 -0.692987 0.501789 + outer loop + vertex -611.172 96.652 36.1614 + vertex -609.392 96.8695 38.2974 + vertex -609.983 96.8257 37.6276 + endloop + endfacet + facet normal -0.326132 -0.872138 0.36471 + outer loop + vertex -610.235 96.8215 37.3726 + vertex -610.718 96.7999 36.8887 + vertex -610.771 96.6806 36.5555 + endloop + endfacet + facet normal -0.343793 -0.875917 0.338491 + outer loop + vertex -607.499 97.8953 42.8108 + vertex -608.229 97.9134 42.1164 + vertex -609.168 97.2123 39.3484 + endloop + endfacet + facet normal -0.32513 -0.891983 0.314098 + outer loop + vertex -605.841 98.76 46.9834 + vertex -606.417 98.787 46.4631 + vertex -607.499 97.8953 42.8108 + endloop + endfacet + facet normal -0.0539675 -0.969038 0.240942 + outer loop + vertex -604.75 99.4627 50.1913 + vertex -604.59 99.7241 51.2787 + vertex -605.527 98.828 47.465 + endloop + endfacet + facet normal 0.368682 0.87668 -0.309041 + outer loop + vertex -604.75 99.4627 50.1913 + vertex -605.527 98.828 47.465 + vertex -605.3 99.1155 48.5514 + endloop + endfacet + facet normal 0.2669 -0.945262 0.187735 + outer loop + vertex -604.59 99.7241 51.2787 + vertex -604.75 99.4627 50.1913 + vertex -604.199 100.26 53.4201 + endloop + endfacet + facet normal 0.201512 0.942399 -0.266976 + outer loop + vertex -605.3 99.1155 48.5514 + vertex -604.199 100.26 53.4201 + vertex -604.75 99.4627 50.1913 + endloop + endfacet + facet normal -0.30305 -0.908163 0.288791 + outer loop + vertex -605.841 98.76 46.9834 + vertex -604.983 99.9432 51.604 + vertex -606.417 98.787 46.4631 + endloop + endfacet + facet normal -0.320295 -0.906151 0.276228 + outer loop + vertex -605.904 99.8941 50.3749 + vertex -604.983 99.9432 51.604 + vertex -605.569 101.822 57.0888 + endloop + endfacet + facet normal -0.344976 -0.902467 0.257961 + outer loop + vertex -604.121 103.822 66.0222 + vertex -607.569 105.032 65.642 + vertex -605.569 101.822 57.0888 + endloop + endfacet + facet normal -0.349933 -0.905769 0.239018 + outer loop + vertex -603.07 105.59 74.2596 + vertex -606.33 106.764 73.9353 + vertex -604.121 103.822 66.0222 + endloop + endfacet + facet normal -0.356118 -0.90827 0.219603 + outer loop + vertex -602.414 107.24 82.1454 + vertex -605.549 108.431 81.99 + vertex -603.07 105.59 74.2596 + endloop + endfacet + facet normal -0.334301 -0.920387 0.202809 + outer loop + vertex -600.87 106.802 82.7067 + vertex -601.986 108.849 90.155 + vertex -602.414 107.24 82.1454 + endloop + endfacet + facet normal -0.239366 -0.946089 0.218221 + outer loop + vertex -600.81 105.55 77.3454 + vertex -600.646 106.034 79.6239 + vertex -600.87 106.802 82.7067 + endloop + endfacet + facet normal -0.312186 -0.926934 0.208166 + outer loop + vertex -600.646 106.034 79.6239 + vertex -600.429 106.503 82.0344 + vertex -600.87 106.802 82.7067 + endloop + endfacet + facet normal -0.313615 -0.926686 0.207119 + outer loop + vertex -600.429 106.503 82.0344 + vertex -600.318 107.302 85.7785 + vertex -600.87 106.802 82.7067 + endloop + endfacet + facet normal -0.266807 -0.942496 0.201283 + outer loop + vertex -600.422 108.437 90.9559 + vertex -600.87 106.802 82.7067 + vertex -600.318 107.302 85.7785 + endloop + endfacet + facet normal -0.264577 -0.943088 0.201457 + outer loop + vertex -600.318 107.302 85.7785 + vertex -600.149 107.759 88.1419 + vertex -600.422 108.437 90.9559 + endloop + endfacet + facet normal -0.318132 -0.928259 0.192683 + outer loop + vertex -600.149 107.759 88.1419 + vertex -599.955 108.204 90.6051 + vertex -600.422 108.437 90.9559 + endloop + endfacet + facet normal -0.318743 -0.928223 0.191845 + outer loop + vertex -599.955 108.204 90.6051 + vertex -599.883 108.931 94.2398 + vertex -600.422 108.437 90.9559 + endloop + endfacet + facet normal -0.265123 -0.946208 0.185471 + outer loop + vertex -599.883 108.931 94.2398 + vertex -599.722 109.355 96.6317 + vertex -600.02 109.944 99.2124 + endloop + endfacet + facet normal -0.325462 -0.929286 0.174646 + outer loop + vertex -599.722 109.355 96.6317 + vertex -599.544 109.76 99.1211 + vertex -600.02 109.944 99.2124 + endloop + endfacet + facet normal -0.325462 -0.929286 0.174646 + outer loop + vertex -599.544 109.76 99.1211 + vertex -599.498 110.402 102.625 + vertex -600.02 109.944 99.2124 + endloop + endfacet + facet normal -0.298848 -0.939653 0.16656 + outer loop + vertex -599.498 110.402 102.625 + vertex -599.36 110.836 105.322 + vertex -599.763 111.282 107.112 + endloop + endfacet + facet normal -0.333772 -0.929622 0.156201 + outer loop + vertex -599.36 110.836 105.322 + vertex -599.256 111.411 108.965 + vertex -599.763 111.282 107.112 + endloop + endfacet + facet normal -0.231443 -0.959473 0.160767 + outer loop + vertex -599.256 111.411 108.965 + vertex -599.214 111.955 112.27 + vertex -599.563 112.445 114.692 + endloop + endfacet + facet normal -0.300219 -0.942409 0.147422 + outer loop + vertex -599.214 111.955 112.27 + vertex -599.174 112.209 113.976 + vertex -599.563 112.445 114.692 + endloop + endfacet + facet normal -0.317896 -0.938254 0.13646 + outer loop + vertex -599.174 112.209 113.976 + vertex -599.055 112.672 117.439 + vertex -599.563 112.445 114.692 + endloop + endfacet + facet normal -0.305589 -0.94261 0.134546 + outer loop + vertex -599.393 113.572 122.97 + vertex -599.563 112.445 114.692 + vertex -599.055 112.672 117.439 + endloop + endfacet + facet normal -0.251757 -0.957571 0.140271 + outer loop + vertex -599.055 112.672 117.439 + vertex -598.997 113.156 120.841 + vertex -599.393 113.572 122.97 + endloop + endfacet + facet normal -0.300564 -0.945035 0.128725 + outer loop + vertex -598.997 113.156 120.841 + vertex -598.955 113.377 122.565 + vertex -599.393 113.572 122.97 + endloop + endfacet + facet normal -0.287115 -0.950686 0.117304 + outer loop + vertex -598.862 113.781 126.097 + vertex -598.816 114.234 129.883 + vertex -599.244 114.515 131.113 + endloop + endfacet + facet normal -0.320236 -0.941642 0.103723 + outer loop + vertex -598.816 114.234 129.883 + vertex -598.813 114.568 132.92 + vertex -599.244 114.515 131.113 + endloop + endfacet + facet normal -0.356507 -0.929232 0.0971092 + outer loop + vertex -599.244 114.515 131.113 + vertex -600.653 115.808 138.311 + vertex -600.798 115.019 130.233 + endloop + endfacet + facet normal -0.388093 -0.918422 0.076712 + outer loop + vertex -600.568 116.456 146.499 + vertex -603.685 117.754 146.268 + vertex -600.653 115.808 138.311 + endloop + endfacet + facet normal -0.389684 -0.919167 0.0572615 + outer loop + vertex -600.511 116.95 154.817 + vertex -603.586 118.232 154.461 + vertex -600.568 116.456 146.499 + endloop + endfacet + facet normal -0.389988 -0.920082 0.0368444 + outer loop + vertex -600.467 117.26 163.019 + vertex -603.547 118.55 162.629 + vertex -600.511 116.95 154.817 + endloop + endfacet + facet normal -0.389962 -0.920696 0.0157382 + outer loop + vertex -600.453 117.391 171.038 + vertex -603.529 118.689 170.725 + vertex -600.467 117.26 163.019 + endloop + endfacet + facet normal -0.389775 -0.920895 -0.00527079 + outer loop + vertex -600.464 117.35 179.084 + vertex -603.529 118.649 178.807 + vertex -600.453 117.391 171.038 + endloop + endfacet + facet normal -0.388346 -0.921145 -0.0260493 + outer loop + vertex -600.484 117.128 187.224 + vertex -603.579 118.441 186.946 + vertex -600.464 117.35 179.084 + endloop + endfacet + facet normal -0.386885 -0.920906 -0.0474635 + outer loop + vertex -600.52 116.726 195.327 + vertex -603.623 118.04 195.108 + vertex -600.484 117.128 187.224 + endloop + endfacet + facet normal -0.384832 -0.92036 -0.0695825 + outer loop + vertex -600.621 116.146 203.546 + vertex -603.719 117.461 203.284 + vertex -600.52 116.726 195.327 + endloop + endfacet + facet normal -0.381695 -0.919756 -0.0914236 + outer loop + vertex -600.77 115.377 211.907 + vertex -603.819 116.687 211.462 + vertex -600.621 116.146 203.546 + endloop + endfacet + facet normal -0.376735 -0.919345 -0.11347 + outer loop + vertex -600.915 114.423 220.122 + vertex -603.973 115.742 219.587 + vertex -600.77 115.377 211.907 + endloop + endfacet + facet normal -0.371813 -0.918535 -0.134342 + outer loop + vertex -601.055 113.313 228.096 + vertex -604.139 114.634 227.603 + vertex -600.915 114.423 220.122 + endloop + endfacet + facet normal -0.34385 -0.92657 -0.152434 + outer loop + vertex -599.572 112.595 229.116 + vertex -601.278 112.082 236.079 + vertex -601.055 113.313 228.096 + endloop + endfacet + facet normal -0.31039 -0.938141 -0.153461 + outer loop + vertex -599.159 112.531 228.671 + vertex -599.24 111.993 232.124 + vertex -599.572 112.595 229.116 + endloop + endfacet + facet normal -0.356128 -0.922615 -0.14817 + outer loop + vertex -595.899 111.052 229.697 + vertex -598.642 111.177 235.515 + vertex -598.278 112.427 226.857 + endloop + endfacet + facet normal -0.303128 -0.93936 -0.160361 + outer loop + vertex -599.354 111.477 235.54 + vertex -599.396 111.199 237.247 + vertex -599.788 111.302 237.385 + endloop + endfacet + facet normal -0.305226 -0.937379 -0.167803 + outer loop + vertex -599.396 111.199 237.247 + vertex -599.466 110.614 240.642 + vertex -599.788 111.302 237.385 + endloop + endfacet + facet normal -0.351694 -0.921756 -0.163331 + outer loop + vertex -595.298 109.634 237.022 + vertex -598.784 109.67 244.322 + vertex -598.642 111.177 235.515 + endloop + endfacet + facet normal -0.310082 -0.935978 -0.166715 + outer loop + vertex -599.466 110.614 240.642 + vertex -599.597 110.004 244.313 + vertex -600.13 110.001 245.322 + endloop + endfacet + facet normal -0.32151 -0.931016 -0.172744 + outer loop + vertex -599.597 110.004 244.313 + vertex -599.784 109.522 247.259 + vertex -600.13 110.001 245.322 + endloop + endfacet + facet normal -0.329806 -0.927478 -0.176106 + outer loop + vertex -599.784 109.522 247.259 + vertex -599.827 109.008 250.046 + vertex -600.52 108.73 252.806 + endloop + endfacet + facet normal -0.343651 -0.922979 -0.173244 + outer loop + vertex -595.113 107.99 245.991 + vertex -599.141 108.116 253.312 + vertex -598.784 109.67 244.322 + endloop + endfacet + facet normal -0.323669 -0.929882 -0.174806 + outer loop + vertex -599.827 109.008 250.046 + vertex -600.052 108.558 252.858 + vertex -600.52 108.73 252.806 + endloop + endfacet + facet normal -0.322908 -0.92925 -0.179514 + outer loop + vertex -600.052 108.558 252.858 + vertex -600.283 108.101 255.638 + vertex -600.52 108.73 252.806 + endloop + endfacet + facet normal -0.337359 -0.923727 -0.18143 + outer loop + vertex -600.283 108.101 255.638 + vertex -600.394 107.529 258.755 + vertex -601.1 107.349 260.983 + endloop + endfacet + facet normal -0.333875 -0.925418 -0.179244 + outer loop + vertex -594.955 106.099 255.928 + vertex -600.052 106.638 262.639 + vertex -599.141 108.116 253.312 + endloop + endfacet + facet normal -0.334827 -0.924788 -0.180714 + outer loop + vertex -600.394 107.529 258.755 + vertex -600.677 107.098 261.485 + vertex -601.1 107.349 260.983 + endloop + endfacet + facet normal -0.333369 -0.925049 -0.182071 + outer loop + vertex -600.677 107.098 261.485 + vertex -600.934 106.722 263.867 + vertex -601.1 107.349 260.983 + endloop + endfacet + facet normal -0.365806 -0.912377 -0.183721 + outer loop + vertex -600.934 106.722 263.867 + vertex -601.076 106.393 265.783 + vertex -601.848 106.068 268.933 + endloop + endfacet + facet normal -0.353675 -0.917631 -0.181291 + outer loop + vertex -601.076 106.393 265.783 + vertex -601.262 106.012 268.072 + vertex -601.848 106.068 268.933 + endloop + endfacet + facet normal -0.328415 -0.927691 -0.177573 + outer loop + vertex -597.641 105.289 265.23 + vertex -600.795 105.265 271.186 + vertex -600.052 106.638 262.639 + endloop + endfacet + facet normal -0.350548 -0.919269 -0.179056 + outer loop + vertex -601.262 106.012 268.072 + vertex -601.818 105.404 272.283 + vertex -601.848 106.068 268.933 + endloop + endfacet + facet normal -0.334987 -0.92565 -0.175944 + outer loop + vertex -601.848 106.068 268.933 + vertex -604.146 105.484 276.381 + vertex -603.338 106.793 267.956 + endloop + endfacet + facet normal -0.323517 -0.930551 -0.171498 + outer loop + vertex -604.146 105.484 276.381 + vertex -607.931 105.303 284.502 + vertex -607.206 106.663 275.756 + endloop + endfacet + facet normal -0.293184 -0.943175 -0.156411 + outer loop + vertex -610.097 104.919 290.88 + vertex -612.451 105.833 289.777 + vertex -607.931 105.303 284.502 + endloop + endfacet + facet normal -0.277425 -0.951192 -0.135162 + outer loop + vertex -610.876 104.573 294.91 + vertex -613.617 105.441 294.43 + vertex -610.097 104.919 290.88 + endloop + endfacet + facet normal -0.274609 -0.955337 -0.109186 + outer loop + vertex -608.577 103.879 295.201 + vertex -612.213 104.463 299.236 + vertex -610.876 104.573 294.91 + endloop + endfacet + facet normal -0.274617 -0.95656 -0.0978666 + outer loop + vertex -606.925 103.412 295.136 + vertex -609.754 103.768 299.592 + vertex -608.577 103.879 295.201 + endloop + endfacet + facet normal -0.286302 -0.947403 -0.143032 + outer loop + vertex -606.162 103.686 291.141 + vertex -607.598 104.25 290.284 + vertex -604.871 104.242 284.878 + endloop + endfacet + facet normal -0.321805 -0.933028 -0.160936 + outer loop + vertex -603.701 103.802 285.088 + vertex -604.871 104.242 284.878 + vertex -602.816 104.781 277.641 + endloop + endfacet + facet normal -0.281172 -0.952304 -0.118569 + outer loop + vertex -606.047 103.162 295.062 + vertex -606.925 103.412 295.136 + vertex -605.015 103.453 290.276 + endloop + endfacet + facet normal -0.25371 -0.963871 -0.0811397 + outer loop + vertex -607.355 103.161 299.158 + vertex -608.017 103.341 299.096 + vertex -606.047 103.162 295.062 + endloop + endfacet + facet normal -0.266574 -0.961968 -0.0596303 + outer loop + vertex -607.166 103.08 299.618 + vertex -608.639 103.309 302.52 + vertex -607.355 103.161 299.158 + endloop + endfacet + facet normal -0.209201 -0.97664 -0.0490803 + outer loop + vertex -607.229 103.057 300.352 + vertex -607.166 103.08 299.618 + vertex -605.918 102.972 296.444 + endloop + endfacet + facet normal 0.141661 -0.987518 0.0688456 + outer loop + vertex -607.229 103.057 300.352 + vertex -605.918 102.972 296.444 + vertex -606.116 102.99 297.103 + endloop + endfacet + facet normal -0.428203 -0.891765 -0.146279 + outer loop + vertex -605.139 102.999 293.779 + vertex -605.868 103.023 295.765 + vertex -604.67 103.206 291.145 + endloop + endfacet + facet normal 0.597218 0.781541 0.180342 + outer loop + vertex -605.372 103.109 293.963 + vertex -606.52 103.039 298.067 + vertex -605.204 103.083 293.519 + endloop + endfacet + facet normal -0.272632 -0.9552 -0.115174 + outer loop + vertex -605.012 102.934 294.562 + vertex -605.372 103.109 293.963 + vertex -603.381 103.181 288.651 + endloop + endfacet + facet normal -0.310499 -0.942307 -0.125087 + outer loop + vertex -602.368 102.654 290.107 + vertex -605.012 102.934 294.562 + vertex -603.381 103.181 288.651 + endloop + endfacet + facet normal -0.285354 -0.952072 -0.110144 + outer loop + vertex -598.325 101.569 289.005 + vertex -603.212 102.362 294.816 + vertex -602.368 102.654 290.107 + endloop + endfacet + facet normal -0.281202 -0.952256 -0.118884 + outer loop + vertex -590.815 100.282 281.55 + vertex -591.615 99.5638 289.198 + vertex -598.325 101.569 289.005 + endloop + endfacet + facet normal -0.298212 -0.942923 -0.148208 + outer loop + vertex -580.616 98.3916 273.059 + vertex -590.815 100.282 281.55 + vertex -590.548 101.551 272.941 + endloop + endfacet + facet normal -0.301485 -0.940388 -0.157406 + outer loop + vertex -598.574 102.593 282.424 + vertex -602.014 103.927 281.041 + vertex -597.53 103.878 272.745 + endloop + endfacet + facet normal -0.306237 -0.937716 -0.164037 + outer loop + vertex -580.396 99.7942 264.032 + vertex -590.548 101.551 272.941 + vertex -590.655 103.334 262.952 + endloop + endfacet + facet normal -0.315041 -0.933635 -0.170515 + outer loop + vertex -597.53 103.878 272.745 + vertex -600.795 105.265 271.186 + vertex -597.641 105.289 265.23 + endloop + endfacet + facet normal -0.329903 -0.927451 -0.176063 + outer loop + vertex -597.641 105.289 265.23 + vertex -600.052 106.638 262.639 + vertex -594.955 106.099 255.928 + endloop + endfacet + facet normal -0.309517 -0.93638 -0.165502 + outer loop + vertex -579.723 101.137 254.932 + vertex -590.655 103.334 262.952 + vertex -587.509 103.956 253.546 + endloop + endfacet + facet normal -0.314894 -0.934249 -0.167394 + outer loop + vertex -579.136 102.429 246.32 + vertex -587.509 103.956 253.546 + vertex -588.421 105.535 246.449 + endloop + endfacet + facet normal -0.339084 -0.925141 -0.170695 + outer loop + vertex -594.955 106.099 255.928 + vertex -599.141 108.116 253.312 + vertex -595.113 107.99 245.991 + endloop + endfacet + facet normal -0.319521 -0.93386 -0.160663 + outer loop + vertex -579.216 103.878 237.776 + vertex -588.421 105.535 246.449 + vertex -588.716 107.171 237.528 + endloop + endfacet + facet normal -0.348832 -0.923085 -0.161958 + outer loop + vertex -595.113 107.99 245.991 + vertex -598.784 109.67 244.322 + vertex -595.298 109.634 237.022 + endloop + endfacet + facet normal -0.323103 -0.934873 -0.147023 + outer loop + vertex -579.236 105.288 228.665 + vertex -588.716 107.171 237.528 + vertex -589.207 108.915 227.514 + endloop + endfacet + facet normal -0.358078 -0.921709 -0.149109 + outer loop + vertex -595.298 109.634 237.022 + vertex -598.642 111.177 235.515 + vertex -595.899 111.052 229.697 + endloop + endfacet + facet normal -0.368479 -0.919581 -0.136359 + outer loop + vertex -595.899 111.052 229.697 + vertex -598.278 112.427 226.857 + vertex -593.657 111.539 220.354 + endloop + endfacet + facet normal -0.359074 -0.924347 -0.129026 + outer loop + vertex -593.657 111.539 220.354 + vertex -598.278 112.427 226.857 + vertex -597.907 113.57 217.637 + endloop + endfacet + facet normal -0.323922 -0.937975 -0.123603 + outer loop + vertex -578.698 106.357 219.388 + vertex -589.207 108.915 227.514 + vertex -586.375 109.195 217.97 + endloop + endfacet + facet normal -0.328115 -0.938574 -0.106858 + outer loop + vertex -578.252 107.196 210.582 + vertex -586.375 109.195 217.97 + vertex -587.393 110.375 210.733 + endloop + endfacet + facet normal -0.371066 -0.922225 -0.108678 + outer loop + vertex -593.657 111.539 220.354 + vertex -597.907 113.57 217.637 + vertex -594.099 112.888 210.419 + endloop + endfacet + facet normal -0.36664 -0.924288 -0.106148 + outer loop + vertex -594.099 112.888 210.419 + vertex -597.907 113.57 217.637 + vertex -597.831 114.528 209.028 + endloop + endfacet + facet normal -0.331372 -0.939468 -0.0871285 + outer loop + vertex -578.444 108.035 201.921 + vertex -587.393 110.375 210.733 + vertex -587.96 111.401 201.825 + endloop + endfacet + facet normal -0.373794 -0.923512 -0.0860427 + outer loop + vertex -594.099 112.888 210.419 + vertex -597.831 114.528 209.028 + vertex -594.593 113.891 201.793 + endloop + endfacet + facet normal -0.37184 -0.924389 -0.0850909 + outer loop + vertex -594.593 113.891 201.793 + vertex -597.831 114.528 209.028 + vertex -597.979 115.301 201.278 + endloop + endfacet + facet normal -0.334431 -0.940205 -0.064582 + outer loop + vertex -578.746 108.741 192.844 + vertex -587.96 111.401 201.825 + vertex -589.146 112.488 192.146 + endloop + endfacet + facet normal -0.374871 -0.92472 -0.0660668 + outer loop + vertex -594.593 113.891 201.793 + vertex -597.979 115.301 201.278 + vertex -595.589 114.767 195.187 + endloop + endfacet + facet normal -0.366928 -0.928137 -0.0626514 + outer loop + vertex -595.589 114.767 195.187 + vertex -597.979 115.301 201.278 + vertex -597.859 115.815 192.955 + endloop + endfacet + facet normal -0.378662 -0.924243 -0.0488909 + outer loop + vertex -595.589 114.767 195.187 + vertex -597.859 115.815 192.955 + vertex -594.458 114.718 187.353 + endloop + endfacet + facet normal -0.364412 -0.930419 -0.0390325 + outer loop + vertex -594.458 114.718 187.353 + vertex -597.859 115.815 192.955 + vertex -597.653 116.113 183.922 + endloop + endfacet + facet normal -0.333398 -0.942168 -0.0341408 + outer loop + vertex -578.713 109.111 183.454 + vertex -589.146 112.488 192.146 + vertex -587.867 112.424 181.419 + endloop + endfacet + facet normal -0.377927 -0.925512 -0.0244548 + outer loop + vertex -594.458 114.718 187.353 + vertex -597.653 116.113 183.922 + vertex -593.886 114.733 177.953 + endloop + endfacet + facet normal -0.36537 -0.930736 -0.0153227 + outer loop + vertex -593.886 114.733 177.953 + vertex -597.653 116.113 183.922 + vertex -597.586 116.239 174.694 + endloop + endfacet + facet normal -0.333418 -0.942749 -0.00749241 + outer loop + vertex -578.363 109.12 174.173 + vertex -587.867 112.424 181.419 + vertex -587.237 112.276 172.024 + endloop + endfacet + facet normal -0.378374 -0.925651 0.00179466 + outer loop + vertex -593.886 114.733 177.953 + vertex -597.586 116.239 174.694 + vertex -593.246 114.451 167.352 + endloop + endfacet + facet normal -0.369279 -0.929284 0.00805584 + outer loop + vertex -593.246 114.451 167.352 + vertex -597.586 116.239 174.694 + vertex -597.745 116.225 165.793 + endloop + endfacet + facet normal -0.332787 -0.942843 0.0173318 + outer loop + vertex -578.152 108.947 165.371 + vertex -587.237 112.276 172.024 + vertex -586.01 111.693 163.88 + endloop + endfacet + facet normal -0.334476 -0.941825 0.0330429 + outer loop + vertex -578.353 108.724 156.756 + vertex -586.01 111.693 163.88 + vertex -588.25 112.218 156.157 + endloop + endfacet + facet normal -0.375549 -0.926333 0.0295083 + outer loop + vertex -593.246 114.451 167.352 + vertex -597.745 116.225 165.793 + vertex -595.025 114.915 159.263 + endloop + endfacet + facet normal -0.372717 -0.92743 0.0309078 + outer loop + vertex -595.025 114.915 159.263 + vertex -597.745 116.225 165.793 + vertex -597.782 115.934 156.61 + endloop + endfacet + facet normal -0.383056 -0.922702 0.043469 + outer loop + vertex -595.025 114.915 159.263 + vertex -597.782 115.934 156.61 + vertex -593.43 113.79 149.447 + endloop + endfacet + facet normal -0.369078 -0.927857 0.0535055 + outer loop + vertex -593.43 113.79 149.447 + vertex -597.782 115.934 156.61 + vertex -597.776 115.404 147.465 + endloop + endfacet + facet normal -0.331965 -0.941592 0.0566008 + outer loop + vertex -578.437 108.26 147.87 + vertex -588.25 112.218 156.157 + vertex -586.22 110.925 146.559 + endloop + endfacet + facet normal -0.333012 -0.940151 0.0722422 + outer loop + vertex -578.443 107.591 139.029 + vertex -586.22 110.925 146.559 + vertex -587.758 110.905 139.216 + endloop + endfacet + facet normal -0.375995 -0.923823 0.0719651 + outer loop + vertex -593.43 113.79 149.447 + vertex -597.776 115.404 147.465 + vertex -594.516 113.463 139.572 + endloop + endfacet + facet normal -0.370822 -0.925706 0.0745649 + outer loop + vertex -594.516 113.463 139.572 + vertex -597.776 115.404 147.465 + vertex -598.053 114.806 138.657 + endloop + endfacet + facet normal -0.33177 -0.938869 0.0919485 + outer loop + vertex -578.972 106.915 130.172 + vertex -587.758 110.905 139.216 + vertex -589.28 110.49 129.48 + endloop + endfacet + facet normal -0.374087 -0.922885 0.0913298 + outer loop + vertex -594.516 113.463 139.572 + vertex -598.053 114.806 138.657 + vertex -595.736 113.256 132.483 + endloop + endfacet + facet normal -0.363684 -0.926547 0.0961539 + outer loop + vertex -595.736 113.256 132.483 + vertex -598.053 114.806 138.657 + vertex -598.124 113.939 130.037 + endloop + endfacet + facet normal -0.373521 -0.921408 0.107193 + outer loop + vertex -595.736 113.256 132.483 + vertex -598.124 113.939 130.037 + vertex -594.673 111.873 124.307 + endloop + endfacet + facet normal -0.358744 -0.92598 0.117741 + outer loop + vertex -594.673 111.873 124.307 + vertex -598.124 113.939 130.037 + vertex -598.054 112.743 120.843 + endloop + endfacet + facet normal -0.326408 -0.937531 0.120391 + outer loop + vertex -579.066 105.824 120.837 + vertex -589.28 110.49 129.48 + vertex -587.946 108.631 118.627 + endloop + endfacet + facet normal -0.368917 -0.920459 0.129056 + outer loop + vertex -594.673 111.873 124.307 + vertex -598.054 112.743 120.843 + vertex -593.912 110.086 113.734 + endloop + endfacet + facet normal -0.355863 -0.92428 0.138089 + outer loop + vertex -593.912 110.086 113.734 + vertex -598.054 112.743 120.843 + vertex -598.367 111.547 112.032 + endloop + endfacet + facet normal -0.323257 -0.935656 0.141612 + outer loop + vertex -578.761 104.42 111.77 + vertex -587.946 108.631 118.627 + vertex -586.727 106.951 110.304 + endloop + endfacet + facet normal -0.323113 -0.93379 0.153736 + outer loop + vertex -579.183 103.176 103.23 + vertex -586.727 106.951 110.304 + vertex -589.558 106.705 102.86 + endloop + endfacet + facet normal -0.360433 -0.920037 0.153689 + outer loop + vertex -593.912 110.086 113.734 + vertex -598.367 111.547 112.032 + vertex -596.017 109.637 106.112 + endloop + endfacet + facet normal -0.352942 -0.922311 0.157396 + outer loop + vertex -596.017 109.637 106.112 + vertex -598.367 111.547 112.032 + vertex -598.738 110.197 103.289 + endloop + endfacet + facet normal -0.360303 -0.918067 0.165333 + outer loop + vertex -596.017 109.637 106.112 + vertex -598.738 110.197 103.289 + vertex -595.511 108.007 98.1599 + endloop + endfacet + facet normal -0.34633 -0.921531 0.175603 + outer loop + vertex -595.511 108.007 98.1599 + vertex -598.738 110.197 103.289 + vertex -598.963 108.616 94.5472 + endloop + endfacet + facet normal -0.31805 -0.931806 0.174876 + outer loop + vertex -579.876 101.812 94.3954 + vertex -589.558 106.705 102.86 + vertex -589.172 104.615 92.4261 + endloop + endfacet + facet normal -0.353898 -0.917089 0.183585 + outer loop + vertex -595.511 108.007 98.1599 + vertex -598.963 108.616 94.5472 + vertex -595.445 106.139 88.9564 + endloop + endfacet + facet normal -0.340225 -0.920205 0.19357 + outer loop + vertex -595.445 106.139 88.9564 + vertex -598.963 108.616 94.5472 + vertex -599.322 106.885 85.6879 + endloop + endfacet + facet normal -0.313377 -0.929602 0.193997 + outer loop + vertex -579.975 100.033 85.3263 + vertex -589.172 104.615 92.4261 + vertex -588.935 102.609 83.1977 + endloop + endfacet + facet normal -0.347888 -0.915112 0.203822 + outer loop + vertex -595.445 106.139 88.9564 + vertex -599.322 106.885 85.6879 + vertex -595.449 103.821 78.5444 + endloop + endfacet + facet normal -0.336593 -0.917694 0.211053 + outer loop + vertex -595.449 103.821 78.5444 + vertex -599.322 106.885 85.6879 + vertex -600.064 105.127 76.8628 + endloop + endfacet + facet normal -0.308705 -0.926951 0.213221 + outer loop + vertex -580.018 98.1504 76.7241 + vertex -588.935 102.609 83.1977 + vertex -588.279 100.556 75.2232 + endloop + endfacet + facet normal -0.306727 -0.923766 0.229291 + outer loop + vertex -580.771 96.3347 68.2588 + vertex -588.279 100.556 75.2232 + vertex -591.908 99.8156 67.385 + endloop + endfacet + facet normal -0.34134 -0.911678 0.228756 + outer loop + vertex -595.449 103.821 78.5444 + vertex -600.064 105.127 76.8628 + vertex -598.324 102.899 70.5773 + endloop + endfacet + facet normal -0.323141 -0.912001 0.252655 + outer loop + vertex -593.361 97.2936 56.4219 + vertex -591.908 99.8156 67.385 + vertex -599.436 100.783 61.2497 + endloop + endfacet + facet normal -0.312727 -0.911923 0.265702 + outer loop + vertex -599.436 100.783 61.2497 + vertex -600.048 98.6269 53.1281 + vertex -593.361 97.2936 56.4219 + endloop + endfacet + facet normal -0.331475 -0.914381 0.232446 + outer loop + vertex -598.324 102.899 70.5773 + vertex -600.064 105.127 76.8628 + vertex -601.131 103.175 67.6616 + endloop + endfacet + facet normal -0.325142 -0.907631 0.265497 + outer loop + vertex -600.048 98.6269 53.1281 + vertex -599.436 100.783 61.2497 + vertex -603.155 99.8535 53.5159 + endloop + endfacet + facet normal -0.315889 -0.908523 0.273496 + outer loop + vertex -600.048 98.6269 53.1281 + vertex -596.724 96.9444 51.3782 + vertex -593.361 97.2936 56.4219 + endloop + endfacet + facet normal -0.309714 -0.904787 0.292298 + outer loop + vertex -592.885 95.6637 51.4819 + vertex -596.724 96.9444 51.3782 + vertex -593.444 94.7443 48.0433 + endloop + endfacet + facet normal -0.307084 -0.901274 0.305621 + outer loop + vertex -593.444 94.7443 48.0433 + vertex -587.937 91.7174 44.6502 + vertex -584.755 92.4797 50.0953 + endloop + endfacet + facet normal -0.310896 -0.899214 0.307828 + outer loop + vertex -595.151 93.8819 43.8388 + vertex -599.052 96.5955 47.826 + vertex -600.704 95.7191 43.5979 + endloop + endfacet + facet normal -0.317521 -0.897574 0.305846 + outer loop + vertex -600.704 95.7191 43.5979 + vertex -602.844 98.0095 48.0975 + vertex -604.33 96.9869 43.554 + endloop + endfacet + facet normal -0.323659 -0.894247 0.309138 + outer loop + vertex -604.33 96.9869 43.554 + vertex -605.046 98.716 47.8056 + vertex -606.205 97.6047 43.378 + endloop + endfacet + facet normal -0.328985 -0.889693 0.316567 + outer loop + vertex -606.205 97.6047 43.378 + vertex -605.912 98.7405 46.8743 + vertex -606.996 97.7246 42.8932 + endloop + endfacet + facet normal -0.329671 -0.886946 0.323487 + outer loop + vertex -606.996 97.7246 42.8932 + vertex -606.214 98.4897 45.7872 + vertex -607.421 97.5895 42.0893 + endloop + endfacet + facet normal -0.320501 -0.883641 0.341258 + outer loop + vertex -608.837 96.5634 38.0487 + vertex -608.182 96.9931 39.7762 + vertex -609.355 96.6784 37.8598 + endloop + endfacet + facet normal -0.319578 -0.884637 0.33954 + outer loop + vertex -607.555 96.0062 37.8028 + vertex -607.426 96.826 40.0603 + vertex -608.837 96.5634 38.0487 + endloop + endfacet + facet normal -0.314873 -0.870307 0.378709 + outer loop + vertex -607.163 95.36 36.5254 + vertex -611.172 96.652 36.1614 + vertex -608.376 95.4005 35.6098 + endloop + endfacet + facet normal -0.317981 -0.885596 0.338537 + outer loop + vertex -603.742 94.5844 37.6647 + vertex -605.582 96.1742 40.0961 + vertex -607.555 96.0062 37.8028 + endloop + endfacet + facet normal -0.313572 -0.871549 0.376929 + outer loop + vertex -603.111 93.7737 36.228 + vertex -607.163 95.36 36.5254 + vertex -608.376 95.4005 35.6098 + endloop + endfacet + facet normal -0.309805 -0.887429 0.341306 + outer loop + vertex -599.729 92.8712 36.9516 + vertex -603.111 93.7737 36.228 + vertex -596.134 91.5136 36.6847 + endloop + endfacet + facet normal -0.313431 -0.886886 0.339402 + outer loop + vertex -598.493 92.8845 38.071 + vertex -602.056 94.9267 40.117 + vertex -603.742 94.5844 37.6647 + endloop + endfacet + facet normal -0.310684 -0.888861 0.336751 + outer loop + vertex -595.666 91.5508 37.215 + vertex -599.729 92.8712 36.9516 + vertex -596.134 91.5136 36.6847 + endloop + endfacet + facet normal -0.306205 -0.888818 0.340943 + outer loop + vertex -591.768 90.6619 38.316 + vertex -596.645 93.1248 40.3565 + vertex -598.493 92.8845 38.071 + endloop + endfacet + facet normal -0.303698 -0.887825 0.345736 + outer loop + vertex -589.524 90.9176 40.9441 + vertex -596.645 93.1248 40.3565 + vertex -591.768 90.6619 38.316 + endloop + endfacet + facet normal -0.295365 -0.899962 0.320669 + outer loop + vertex -581.367 88.6279 42.0315 + vertex -587.937 91.7174 44.6502 + vertex -589.524 90.9176 40.9441 + endloop + endfacet + facet normal -0.285364 -0.903366 0.320151 + outer loop + vertex -581.719 89.8065 45.0436 + vertex -581.367 88.6279 42.0315 + vertex -572.861 86.943 44.8584 + endloop + endfacet + facet normal -0.270671 -0.916303 0.295173 + outer loop + vertex -558.742 83.1847 46.1387 + vertex -570.848 88.6706 52.0682 + vertex -572.861 86.943 44.8584 + endloop + endfacet + facet normal -0.27136 -0.916494 0.293943 + outer loop + vertex -557.445 84.9653 52.8883 + vertex -570.848 88.6706 52.0682 + vertex -558.742 83.1847 46.1387 + endloop + endfacet + facet normal -0.249215 -0.930933 0.266935 + outer loop + vertex -544.912 81.7361 53.3273 + vertex -557.118 87.1367 60.7663 + vertex -557.445 84.9653 52.8883 + endloop + endfacet + facet normal -0.249404 -0.930965 0.26665 + outer loop + vertex -544.935 83.9563 61.0574 + vertex -557.118 87.1367 60.7663 + vertex -544.912 81.7361 53.3273 + endloop + endfacet + facet normal -0.223749 -0.944027 0.242383 + outer loop + vertex -533.26 81.3509 61.6877 + vertex -545.077 86.1257 69.3752 + vertex -544.935 83.9563 61.0574 + endloop + endfacet + facet normal -0.199411 -0.950038 0.240131 + outer loop + vertex -523.393 79.6705 63.233 + vertex -533.792 83.5798 70.0637 + vertex -533.26 81.3509 61.6877 + endloop + endfacet + facet normal -0.17892 -0.95548 0.234618 + outer loop + vertex -516.014 78.7157 64.9719 + vertex -523.982 81.7206 71.1331 + vertex -523.393 79.6705 63.233 + endloop + endfacet + facet normal -0.167745 -0.955547 0.242468 + outer loop + vertex -510.684 77.9723 65.7293 + vertex -516.014 78.7157 64.9719 + vertex -510.39 76.4681 60.0046 + endloop + endfacet + facet normal -0.148118 -0.958344 0.24421 + outer loop + vertex -507.492 76.1663 60.578 + vertex -510.684 77.9723 65.7293 + vertex -510.39 76.4681 60.0046 + endloop + endfacet + facet normal -0.128013 -0.954919 0.267847 + outer loop + vertex -506.301 76.0989 60.9069 + vertex -507.492 76.1663 60.578 + vertex -505.623 74.8421 56.7508 + endloop + endfacet + facet normal -0.0757817 -0.957805 0.277248 + outer loop + vertex -506.301 76.0989 60.9069 + vertex -505.623 74.8421 56.7508 + vertex -505.497 75.2679 58.2559 + endloop + endfacet + facet normal -0.151888 -0.945409 0.288327 + outer loop + vertex -506.804 74.7503 55.8697 + vertex -509.403 74.8796 54.9243 + vertex -505.744 73.213 51.387 + endloop + endfacet + facet normal -0.153479 -0.947802 0.279491 + outer loop + vertex -509.403 74.8796 54.9243 + vertex -514.988 76.8094 58.4018 + vertex -512.703 74.9968 53.5096 + endloop + endfacet + facet normal -0.167776 -0.94737 0.272654 + outer loop + vertex -512.703 74.9968 53.5096 + vertex -514.988 76.8094 58.4018 + vertex -520.637 76.6014 54.2029 + endloop + endfacet + facet normal -0.143134 -0.931505 0.334381 + outer loop + vertex -506.935 71.8107 46.7763 + vertex -511.897 73.5888 49.6057 + vertex -509.628 71.9383 45.9794 + endloop + endfacet + facet normal -0.178881 -0.936437 0.301808 + outer loop + vertex -523.207 75.0335 47.8145 + vertex -514.898 73.248 47.1998 + vertex -520.637 76.6014 54.2029 + endloop + endfacet + facet normal -0.200063 -0.933451 0.297732 + outer loop + vertex -523.207 75.0335 47.8145 + vertex -533.111 79.0739 53.8271 + vertex -533.511 77.0793 47.3054 + endloop + endfacet + facet normal -0.223927 -0.919947 0.321799 + outer loop + vertex -533.511 77.0793 47.3054 + vertex -545.462 79.7832 46.7191 + vertex -533.934 75.3626 42.1029 + endloop + endfacet + facet normal -0.180947 -0.91798 0.352946 + outer loop + vertex -515.833 72.1301 43.6494 + vertex -523.558 73.5149 43.2906 + vertex -515.914 71.1974 41.1817 + endloop + endfacet + facet normal -0.176698 -0.950604 0.255206 + outer loop + vertex -511.019 69.9557 40.326 + vertex -516.301 70.8757 40.0959 + vertex -509.779 69.6455 40.0293 + endloop + endfacet + facet normal -0.181283 -0.969899 0.162582 + outer loop + vertex -513.308 70.2585 39.7509 + vertex -509.779 69.6455 40.0293 + vertex -516.301 70.8757 40.0959 + endloop + endfacet + facet normal -0.165499 -0.920693 0.353461 + outer loop + vertex -510.29 70.2775 41.4188 + vertex -515.833 72.1301 43.6494 + vertex -515.914 71.1974 41.1817 + endloop + endfacet + facet normal -0.154769 -0.932092 0.327493 + outer loop + vertex -506.857 69.3045 40.4395 + vertex -511.019 69.9557 40.326 + vertex -509.779 69.6455 40.0293 + endloop + endfacet + facet normal -0.152038 -0.941742 0.300011 + outer loop + vertex -509.779 69.6455 40.0293 + vertex -505.846 69.034 40.1029 + vertex -506.857 69.3045 40.4395 + endloop + endfacet + facet normal -0.15939 -0.917026 0.365592 + outer loop + vertex -509.983 71.0927 43.5973 + vertex -515.833 72.1301 43.6494 + vertex -510.29 70.2775 41.4188 + endloop + endfacet + facet normal -0.144381 -0.925518 0.350102 + outer loop + vertex -505.956 70.5204 43.7453 + vertex -509.628 71.9383 45.9794 + vertex -509.983 71.0927 43.5973 + endloop + endfacet + facet normal -0.146613 -0.926349 0.346961 + outer loop + vertex -506.935 71.8107 46.7763 + vertex -509.628 71.9383 45.9794 + vertex -505.956 70.5204 43.7453 + endloop + endfacet + facet normal -0.136955 -0.934989 0.327169 + outer loop + vertex -504.502 71.6734 47.4024 + vertex -508.194 73.3172 50.5549 + vertex -506.935 71.8107 46.7763 + endloop + endfacet + facet normal -0.136157 -0.930769 0.33931 + outer loop + vertex -503.211 71.7301 48.0765 + vertex -504.502 71.6734 47.4024 + vertex -501.806 70.2419 44.5576 + endloop + endfacet + facet normal -0.0974371 -0.929989 0.354437 + outer loop + vertex -503.211 71.7301 48.0765 + vertex -501.806 70.2419 44.5576 + vertex -501.349 70.4326 45.1838 + endloop + endfacet + facet normal -0.063256 -0.900006 0.431263 + outer loop + vertex -499.755 69.0167 42.1523 + vertex -498.556 67.9088 40.0162 + vertex -498.424 68.3441 40.9439 + endloop + endfacet + facet normal -0.122859 -0.91921 0.374109 + outer loop + vertex -500.818 69.2014 42.2912 + vertex -503.325 70.3043 44.1779 + vertex -502.449 69.2333 41.834 + endloop + endfacet + facet normal -0.145969 -0.875308 0.46101 + outer loop + vertex -502.075 68.3202 39.8206 + vertex -505.927 68.9316 39.762 + vertex -505.101 68.193 38.621 + endloop + endfacet + facet normal -0.141967 -0.947523 -0.286436 + outer loop + vertex -509.779 69.6455 40.0293 + vertex -513.308 70.2585 39.7509 + vertex -505.846 69.034 40.1029 + endloop + endfacet + facet normal -0.18136 -0.913934 0.363088 + outer loop + vertex -524.665 72.4667 39.6363 + vertex -523.698 71.9055 38.7071 + vertex -513.308 70.2585 39.7509 + endloop + endfacet + facet normal -0.197074 -0.864693 0.462025 + outer loop + vertex -523.698 71.9055 38.7071 + vertex -535.252 73.3589 36.4987 + vertex -523.143 70.6383 36.5723 + endloop + endfacet + facet normal -0.19561 -0.83597 0.512729 + outer loop + vertex -523.143 70.6383 36.5723 + vertex -534.428 71.2621 33.2838 + vertex -522.352 68.4303 33.2739 + endloop + endfacet + facet normal -0.12834 -0.898853 0.419037 + outer loop + vertex -502.075 68.3202 39.8206 + vertex -505.101 68.193 38.621 + vertex -498.556 67.9088 40.0162 + endloop + endfacet + facet normal -0.113458 -0.860477 0.496696 + outer loop + vertex -493.338 66.1627 37.9329 + vertex -493.409 65.8495 37.3743 + vertex -486.915 64.3013 36.1755 + endloop + endfacet + facet normal -0.0995028 -0.874946 0.473887 + outer loop + vertex -498.514 67.7604 39.6878 + vertex -498.006 67.0539 38.4901 + vertex -497.219 67.3483 39.1987 + endloop + endfacet + facet normal -0.123013 -0.89508 0.428603 + outer loop + vertex -497.802 67.6441 39.6493 + vertex -498.514 67.7604 39.6878 + vertex -497.219 67.3483 39.1987 + endloop + endfacet + facet normal -0.173682 -0.932713 0.316039 + outer loop + vertex -495.868 67.088 39.0706 + vertex -498.556 67.9088 40.0162 + vertex -497.802 67.6441 39.6493 + endloop + endfacet +endsolid diff --git a/noether_examples/meshes/outputs/output_6.stl b/noether_examples/meshes/outputs/output_6.stl new file mode 100644 index 00000000..2439d998 --- /dev/null +++ b/noether_examples/meshes/outputs/output_6.stl @@ -0,0 +1,29619 @@ +solid ascii + facet normal 0.00610605 -0.175909 0.984387 + outer loop + vertex 398.632 43.896 27.5293 + vertex 401.396 44.0313 27.5363 + vertex 420.155 48.3883 28.1985 + endloop + endfacet + facet normal 0.00278801 -0.108621 0.994079 + outer loop + vertex 398.632 43.896 27.5293 + vertex 380.516 39.901 27.1435 + vertex 401.396 44.0313 27.5363 + endloop + endfacet + facet normal 0.0291033 -0.239416 0.970481 + outer loop + vertex 380.516 39.901 27.1435 + vertex 381.142 39.1129 26.9303 + vertex 401.396 44.0313 27.5363 + endloop + endfacet + facet normal 0.036074 -0.267196 0.962967 + outer loop + vertex 401.396 44.0313 27.5363 + vertex 381.142 39.1129 26.9303 + vertex 402.271 43.2734 27.2932 + endloop + endfacet + facet normal 0.0275034 -0.276346 0.960665 + outer loop + vertex 401.396 44.0313 27.5363 + vertex 402.271 43.2734 27.2932 + vertex 423.32 48.659 28.2398 + endloop + endfacet + facet normal 0.0343445 -0.258623 0.965368 + outer loop + vertex 381.142 39.1129 26.9303 + vertex 381.189 37.5167 26.501 + vertex 402.271 43.2734 27.2932 + endloop + endfacet + facet normal 0.046566 -0.301582 0.952303 + outer loop + vertex 402.271 43.2734 27.2932 + vertex 381.189 37.5167 26.501 + vertex 401.901 41.5466 26.7645 + endloop + endfacet + facet normal 0.0379439 -0.300005 0.953183 + outer loop + vertex 402.271 43.2734 27.2932 + vertex 401.901 41.5466 26.7645 + vertex 423.485 47.6475 27.8255 + endloop + endfacet + facet normal 0.0391779 -0.26435 0.963631 + outer loop + vertex 381.189 37.5167 26.501 + vertex 381.18 35.2433 25.8778 + vertex 401.901 41.5466 26.7645 + endloop + endfacet + facet normal 0.0491881 -0.295896 0.953953 + outer loop + vertex 401.901 41.5466 26.7645 + vertex 381.18 35.2433 25.8778 + vertex 401.577 39.2187 26.0591 + endloop + endfacet + facet normal 0.043006 -0.295192 0.954469 + outer loop + vertex 401.901 41.5466 26.7645 + vertex 401.577 39.2187 26.0591 + vertex 420.687 45.2771 27.0718 + endloop + endfacet + facet normal 0.0515933 -0.320819 0.945734 + outer loop + vertex 420.687 45.2771 27.0718 + vertex 401.577 39.2187 26.0591 + vertex 421.295 43.2573 26.3534 + endloop + endfacet + facet normal 0.0419007 -0.323576 0.945274 + outer loop + vertex 420.687 45.2771 27.0718 + vertex 421.295 43.2573 26.3534 + vertex 437.307 48.7568 27.5262 + endloop + endfacet + facet normal 0.0423078 -0.26107 0.964392 + outer loop + vertex 381.18 35.2433 25.8778 + vertex 381.389 32.4718 25.1183 + vertex 401.577 39.2187 26.0591 + endloop + endfacet + facet normal 0.0495257 -0.281803 0.958193 + outer loop + vertex 401.577 39.2187 26.0591 + vertex 381.389 32.4718 25.1183 + vertex 401.964 36.5354 25.25 + endloop + endfacet + facet normal 0.0435931 -0.282668 0.958227 + outer loop + vertex 401.577 39.2187 26.0591 + vertex 401.964 36.5354 25.25 + vertex 421.295 43.2573 26.3534 + endloop + endfacet + facet normal 0.053011 -0.308368 0.949789 + outer loop + vertex 421.295 43.2573 26.3534 + vertex 401.964 36.5354 25.25 + vertex 422.546 40.7962 25.4845 + endloop + endfacet + facet normal 0.0419969 -0.31356 0.948639 + outer loop + vertex 421.295 43.2573 26.3534 + vertex 422.546 40.7962 25.4845 + vertex 442.499 47.9975 26.9815 + endloop + endfacet + facet normal 0.0448337 -0.269535 0.961946 + outer loop + vertex 401.964 36.5354 25.25 + vertex 402.403 33.3992 24.3507 + vertex 422.546 40.7962 25.4845 + endloop + endfacet + facet normal 0.0560812 -0.298744 0.952684 + outer loop + vertex 422.546 40.7962 25.4845 + vertex 402.403 33.3992 24.3507 + vertex 423.295 37.6988 24.4692 + endloop + endfacet + facet normal 0.0490704 -0.300396 0.952551 + outer loop + vertex 422.546 40.7962 25.4845 + vertex 423.295 37.6988 24.4692 + vertex 443.233 45.1594 25.7948 + endloop + endfacet + facet normal 0.0460386 -0.250342 0.967062 + outer loop + vertex 402.403 33.3992 24.3507 + vertex 402.595 29.8662 23.427 + vertex 423.295 37.6988 24.4692 + endloop + endfacet + facet normal 0.0538472 -0.270212 0.961294 + outer loop + vertex 423.295 37.6988 24.4692 + vertex 402.595 29.8662 23.427 + vertex 423.766 34.2246 23.4662 + endloop + endfacet + facet normal 0.0506262 -0.270662 0.961342 + outer loop + vertex 423.295 37.6988 24.4692 + vertex 423.766 34.2246 23.4662 + vertex 445.012 42.3002 24.621 + endloop + endfacet + facet normal 0.0630166 -0.301821 0.95128 + outer loop + vertex 445.012 42.3002 24.621 + vertex 423.766 34.2246 23.4662 + vertex 445.426 38.811 23.4865 + endloop + endfacet + facet normal 0.0615941 -0.302001 0.951316 + outer loop + vertex 445.012 42.3002 24.621 + vertex 445.426 38.811 23.4865 + vertex 468.001 47.275 24.7119 + endloop + endfacet + facet normal 0.0739006 -0.33318 0.939963 + outer loop + vertex 468.001 47.275 24.7119 + vertex 445.426 38.811 23.4865 + vertex 465.68 43.1008 23.4147 + endloop + endfacet + facet normal 0.0805813 -0.33637 0.938276 + outer loop + vertex 468.001 47.275 24.7119 + vertex 465.68 43.1008 23.4147 + vertex 483.095 49.7144 24.2901 + endloop + endfacet + facet normal 0.0754174 -0.32343 0.943242 + outer loop + vertex 482.728 46.8528 23.3381 + vertex 483.095 49.7144 24.2901 + vertex 465.68 43.1008 23.4147 + endloop + endfacet + facet normal 0.0759158 -0.323475 0.943186 + outer loop + vertex 483.095 49.7144 24.2901 + vertex 482.728 46.8528 23.3381 + vertex 495.05 52.3356 24.2267 + endloop + endfacet + facet normal 0.078946 -0.329884 0.940715 + outer loop + vertex 495.05 52.3356 24.2267 + vertex 482.728 46.8528 23.3381 + vertex 495.896 50.0918 23.369 + endloop + endfacet + facet normal 0.08019 -0.329436 0.940767 + outer loop + vertex 495.05 52.3356 24.2267 + vertex 495.896 50.0918 23.369 + vertex 502.813 54.3019 24.2537 + endloop + endfacet + facet normal 0.0915887 -0.34664 0.933516 + outer loop + vertex 502.813 54.3019 24.2537 + vertex 495.896 50.0918 23.369 + vertex 503.792 52.6169 23.5319 + endloop + endfacet + facet normal 0.0857805 -0.349755 0.932906 + outer loop + vertex 502.813 54.3019 24.2537 + vertex 503.792 52.6169 23.5319 + vertex 506.158 55.279 24.3123 + endloop + endfacet + facet normal 0.128041 -0.382125 0.915197 + outer loop + vertex 506.158 55.279 24.3123 + vertex 503.792 52.6169 23.5319 + vertex 506.529 54.0004 23.7267 + endloop + endfacet + facet normal 0.0496922 -0.403986 0.913414 + outer loop + vertex 506.158 55.279 24.3123 + vertex 506.529 54.0004 23.7267 + vertex 506.835 54.6873 24.0138 + endloop + endfacet + facet normal 0.0449595 -0.227142 0.972823 + outer loop + vertex 402.595 29.8662 23.427 + vertex 402.545 26.0793 22.5451 + vertex 423.766 34.2246 23.4662 + endloop + endfacet + facet normal 0.0491024 -0.237629 0.970114 + outer loop + vertex 423.766 34.2246 23.4662 + vertex 402.545 26.0793 22.5451 + vertex 423.782 30.4693 22.5455 + endloop + endfacet + facet normal 0.0494055 -0.237625 0.9701 + outer loop + vertex 423.766 34.2246 23.4662 + vertex 423.782 30.4693 22.5455 + vertex 445.426 38.811 23.4865 + endloop + endfacet + facet normal 0.0545079 -0.250468 0.966589 + outer loop + vertex 445.426 38.811 23.4865 + vertex 423.782 30.4693 22.5455 + vertex 445.142 35.0658 22.5321 + endloop + endfacet + facet normal 0.0565006 -0.250582 0.966445 + outer loop + vertex 445.426 38.811 23.4865 + vertex 445.142 35.0658 22.5321 + vertex 465.68 43.1008 23.4147 + endloop + endfacet + facet normal 0.05809 -0.254521 0.965321 + outer loop + vertex 465.68 43.1008 23.4147 + vertex 445.142 35.0658 22.5321 + vertex 465.567 39.6556 22.5131 + endloop + endfacet + facet normal 0.0603578 -0.254557 0.965172 + outer loop + vertex 465.68 43.1008 23.4147 + vertex 465.567 39.6556 22.5131 + vertex 482.728 46.8528 23.3381 + endloop + endfacet + facet normal 0.0589082 -0.251211 0.966138 + outer loop + vertex 482.728 46.8528 23.3381 + vertex 465.567 39.6556 22.5131 + vertex 483.572 43.8853 22.5151 + endloop + endfacet + facet normal 0.0594928 -0.251047 0.966145 + outer loop + vertex 482.728 46.8528 23.3381 + vertex 483.572 43.8853 22.5151 + vertex 495.896 50.0918 23.369 + endloop + endfacet + facet normal 0.0602896 -0.252567 0.965699 + outer loop + vertex 483.572 43.8853 22.5151 + vertex 498.234 47.396 22.518 + vertex 495.896 50.0918 23.369 + endloop + endfacet + facet normal 0.060728 -0.252208 0.965766 + outer loop + vertex 503.792 52.6169 23.5319 + vertex 495.896 50.0918 23.369 + vertex 498.234 47.396 22.518 + endloop + endfacet + facet normal 0.0495051 -0.216277 0.975076 + outer loop + vertex 445.142 35.0658 22.5321 + vertex 445.437 31.3804 21.6997 + vertex 465.567 39.6556 22.5131 + endloop + endfacet + facet normal 0.0494106 -0.216052 0.975131 + outer loop + vertex 465.567 39.6556 22.5131 + vertex 445.437 31.3804 21.6997 + vertex 466.277 36.1737 21.7057 + endloop + endfacet + facet normal 0.0505908 -0.21581 0.975124 + outer loop + vertex 465.567 39.6556 22.5131 + vertex 466.277 36.1737 21.7057 + vertex 483.572 43.8853 22.5151 + endloop + endfacet + facet normal 0.0504224 -0.215442 0.975214 + outer loop + vertex 483.572 43.8853 22.5151 + vertex 466.277 36.1737 21.7057 + vertex 484.486 40.2894 21.6735 + endloop + endfacet + facet normal 0.0513423 -0.215209 0.975217 + outer loop + vertex 483.572 43.8853 22.5151 + vertex 484.486 40.2894 21.6735 + vertex 498.234 47.396 22.518 + endloop + endfacet + facet normal 0.0517795 -0.21603 0.975013 + outer loop + vertex 498.234 47.396 22.518 + vertex 484.486 40.2894 21.6735 + vertex 497.695 42.284 21.4139 + endloop + endfacet + facet normal 0.0585395 -0.216632 0.974497 + outer loop + vertex 498.234 47.396 22.518 + vertex 497.695 42.284 21.4139 + vertex 506.551 47.0265 21.9362 + endloop + endfacet + facet normal 0.0571021 -0.214021 0.975159 + outer loop + vertex 505.761 40.6922 20.5922 + vertex 506.551 47.0265 21.9362 + vertex 497.695 42.284 21.4139 + endloop + endfacet + facet normal 0.0565747 -0.216434 0.974657 + outer loop + vertex 497.695 42.284 21.4139 + vertex 496.466 38.0141 20.5371 + vertex 505.761 40.6922 20.5922 + endloop + endfacet + facet normal 0.0636659 -0.240919 0.968455 + outer loop + vertex 496.466 38.0141 20.5371 + vertex 499.284 35.0522 19.615 + vertex 505.761 40.6922 20.5922 + endloop + endfacet + facet normal 0.0596225 -0.244562 0.967799 + outer loop + vertex 496.466 38.0141 20.5371 + vertex 486.406 32.4236 19.7441 + vertex 499.284 35.0522 19.615 + endloop + endfacet + facet normal 0.0656456 -0.274486 0.959348 + outer loop + vertex 486.406 32.4236 19.7441 + vertex 489.333 28.8599 18.5242 + vertex 499.284 35.0522 19.615 + endloop + endfacet + facet normal 0.066566 -0.275883 0.958883 + outer loop + vertex 499.284 35.0522 19.615 + vertex 489.333 28.8599 18.5242 + vertex 501.75 31.5916 18.4482 + endloop + endfacet + facet normal 0.0660369 -0.276238 0.958818 + outer loop + vertex 499.284 35.0522 19.615 + vertex 501.75 31.5916 18.4482 + vertex 507.658 35.3077 19.1118 + endloop + endfacet + facet normal 0.0647288 -0.275191 0.959208 + outer loop + vertex 486.406 32.4236 19.7441 + vertex 470.997 24.5992 18.5392 + vertex 489.333 28.8599 18.5242 + endloop + endfacet + facet normal 0.0631277 -0.272186 0.960172 + outer loop + vertex 468.782 28.5192 19.796 + vertex 470.997 24.5992 18.5392 + vertex 486.406 32.4236 19.7441 + endloop + endfacet + facet normal 0.0555667 -0.237929 0.969692 + outer loop + vertex 485.043 36.2548 20.7623 + vertex 468.782 28.5192 19.796 + vertex 486.406 32.4236 19.7441 + endloop + endfacet + facet normal 0.0548317 -0.236434 0.970099 + outer loop + vertex 467.33 32.435 20.8325 + vertex 468.782 28.5192 19.796 + vertex 485.043 36.2548 20.7623 + endloop + endfacet + facet normal 0.0499002 -0.213464 0.975676 + outer loop + vertex 484.486 40.2894 21.6735 + vertex 467.33 32.435 20.8325 + vertex 485.043 36.2548 20.7623 + endloop + endfacet + facet normal 0.054009 -0.236732 0.970073 + outer loop + vertex 467.33 32.435 20.8325 + vertex 448.008 23.7873 19.7979 + vertex 468.782 28.5192 19.796 + endloop + endfacet + facet normal 0.0620264 -0.271935 0.960315 + outer loop + vertex 448.008 23.7873 19.7979 + vertex 450.121 19.8126 18.5359 + vertex 468.782 28.5192 19.796 + endloop + endfacet + facet normal 0.0601113 -0.272904 0.960161 + outer loop + vertex 448.008 23.7873 19.7979 + vertex 428.556 15.029 18.5263 + vertex 450.121 19.8126 18.5359 + endloop + endfacet + facet normal 0.0604233 -0.273567 0.959953 + outer loop + vertex 426.22 18.9321 19.7857 + vertex 428.556 15.029 18.5263 + vertex 448.008 23.7873 19.7979 + endloop + endfacet + facet normal 0.0524914 -0.237997 0.969846 + outer loop + vertex 446.405 27.646 20.8315 + vertex 426.22 18.9321 19.7857 + vertex 448.008 23.7873 19.7979 + endloop + endfacet + facet normal 0.0525382 -0.238102 0.969818 + outer loop + vertex 424.563 22.7768 20.8193 + vertex 426.22 18.9321 19.7857 + vertex 446.405 27.646 20.8315 + endloop + endfacet + facet normal 0.0472817 -0.214536 0.975571 + outer loop + vertex 445.437 31.3804 21.6997 + vertex 424.563 22.7768 20.8193 + vertex 446.405 27.646 20.8315 + endloop + endfacet + facet normal 0.0472202 -0.21439 0.975606 + outer loop + vertex 423.842 26.6204 21.6989 + vertex 424.563 22.7768 20.8193 + vertex 445.437 31.3804 21.6997 + endloop + endfacet + facet normal 0.0450227 -0.214805 0.975619 + outer loop + vertex 423.842 26.6204 21.6989 + vertex 403.014 18.2422 20.8154 + vertex 424.563 22.7768 20.8193 + endloop + endfacet + facet normal 0.0500661 -0.238767 0.969785 + outer loop + vertex 403.014 18.2422 20.8154 + vertex 404.605 14.3658 19.7788 + vertex 424.563 22.7768 20.8193 + endloop + endfacet + facet normal 0.0475327 -0.239775 0.969664 + outer loop + vertex 403.014 18.2422 20.8154 + vertex 383.382 10.1534 19.7776 + vertex 404.605 14.3658 19.7788 + endloop + endfacet + facet normal 0.0547896 -0.276334 0.959499 + outer loop + vertex 383.382 10.1534 19.7776 + vertex 386.007 6.31119 18.5211 + vertex 404.605 14.3658 19.7788 + endloop + endfacet + facet normal 0.0549189 -0.276619 0.959409 + outer loop + vertex 404.605 14.3658 19.7788 + vertex 386.007 6.31119 18.5211 + vertex 407.221 10.5286 18.5228 + endloop + endfacet + facet normal 0.0577521 -0.274804 0.959764 + outer loop + vertex 404.605 14.3658 19.7788 + vertex 407.221 10.5286 18.5228 + vertex 426.22 18.9321 19.7857 + endloop + endfacet + facet normal 0.0524177 -0.277854 0.959192 + outer loop + vertex 383.382 10.1534 19.7776 + vertex 364.839 2.32503 18.5232 + vertex 386.007 6.31119 18.5211 + endloop + endfacet + facet normal 0.0520559 -0.277038 0.959448 + outer loop + vertex 362.445 6.22818 19.7801 + vertex 364.839 2.32503 18.5232 + vertex 383.382 10.1534 19.7776 + endloop + endfacet + facet normal 0.0452864 -0.240923 0.969487 + outer loop + vertex 381.92 14.0667 20.8183 + vertex 362.445 6.22818 19.7801 + vertex 383.382 10.1534 19.7776 + endloop + endfacet + facet normal 0.0451312 -0.240551 0.969587 + outer loop + vertex 361.102 10.1683 20.8202 + vertex 362.445 6.22818 19.7801 + vertex 381.92 14.0667 20.8183 + endloop + endfacet + facet normal 0.040279 -0.214635 0.975863 + outer loop + vertex 381.544 18.0257 21.7046 + vertex 361.102 10.1683 20.8202 + vertex 381.92 14.0667 20.8183 + endloop + endfacet + facet normal 0.0425123 -0.214412 0.975818 + outer loop + vertex 381.544 18.0257 21.7046 + vertex 381.92 14.0667 20.8183 + vertex 402.49 22.1659 21.7018 + endloop + endfacet + facet normal 0.0418464 -0.211043 0.976581 + outer loop + vertex 402.545 26.0793 22.5451 + vertex 381.544 18.0257 21.7046 + vertex 402.49 22.1659 21.7018 + endloop + endfacet + facet normal 0.0414416 -0.210012 0.97682 + outer loop + vertex 381.663 21.9471 22.5427 + vertex 381.544 18.0257 21.7046 + vertex 402.545 26.0793 22.5451 + endloop + endfacet + facet normal 0.0396915 -0.209976 0.976901 + outer loop + vertex 381.663 21.9471 22.5427 + vertex 360.75 14.1199 21.7099 + vertex 381.544 18.0257 21.7046 + endloop + endfacet + facet normal 0.0396462 -0.209858 0.976928 + outer loop + vertex 360.892 18.0292 22.544 + vertex 360.75 14.1199 21.7099 + vertex 381.663 21.9471 22.5427 + endloop + endfacet + facet normal 0.0417175 -0.22084 0.974417 + outer loop + vertex 381.796 25.7443 23.3975 + vertex 360.892 18.0292 22.544 + vertex 381.663 21.9471 22.5427 + endloop + endfacet + facet normal 0.042388 -0.220856 0.974385 + outer loop + vertex 381.796 25.7443 23.3975 + vertex 381.663 21.9471 22.5427 + vertex 402.595 29.8662 23.427 + endloop + endfacet + facet normal 0.0407944 -0.218403 0.975006 + outer loop + vertex 361.012 21.8083 23.3855 + vertex 360.892 18.0292 22.544 + vertex 381.796 25.7443 23.3975 + endloop + endfacet + facet normal 0.0446166 -0.238572 0.970099 + outer loop + vertex 381.684 29.2867 24.2739 + vertex 361.012 21.8083 23.3855 + vertex 381.796 25.7443 23.3975 + endloop + endfacet + facet normal 0.0437613 -0.238607 0.97013 + outer loop + vertex 381.684 29.2867 24.2739 + vertex 381.796 25.7443 23.3975 + vertex 402.403 33.3992 24.3507 + endloop + endfacet + facet normal 0.0419485 -0.231417 0.97195 + outer loop + vertex 360.872 25.3473 24.2341 + vertex 361.012 21.8083 23.3855 + vertex 381.684 29.2867 24.2739 + endloop + endfacet + facet normal 0.0458603 -0.252029 0.966632 + outer loop + vertex 381.389 32.4718 25.1183 + vertex 360.872 25.3473 24.2341 + vertex 381.684 29.2867 24.2739 + endloop + endfacet + facet normal 0.0420898 -0.241525 0.969481 + outer loop + vertex 360.554 28.5423 25.0439 + vertex 360.872 25.3473 24.2341 + vertex 381.389 32.4718 25.1183 + endloop + endfacet + facet normal 0.0425725 -0.241474 0.969473 + outer loop + vertex 360.554 28.5423 25.0439 + vertex 339.988 21.593 24.2161 + vertex 360.872 25.3473 24.2341 + endloop + endfacet + facet normal 0.040157 -0.228054 0.97282 + outer loop + vertex 339.988 21.593 24.2161 + vertex 340.163 18.0657 23.382 + vertex 360.872 25.3473 24.2341 + endloop + endfacet + facet normal 0.0385972 -0.228141 0.972863 + outer loop + vertex 339.988 21.593 24.2161 + vertex 319.282 14.5277 23.3807 + vertex 340.163 18.0657 23.382 + endloop + endfacet + facet normal 0.0367459 -0.217216 0.975432 + outer loop + vertex 319.282 14.5277 23.3807 + vertex 319.203 10.7782 22.5488 + vertex 340.163 18.0657 23.382 + endloop + endfacet + facet normal 0.0367867 -0.217331 0.975405 + outer loop + vertex 340.163 18.0657 23.382 + vertex 319.203 10.7782 22.5488 + vertex 340.078 14.3044 22.5471 + endloop + endfacet + facet normal 0.0388548 -0.217358 0.975318 + outer loop + vertex 340.163 18.0657 23.382 + vertex 340.078 14.3044 22.5471 + vertex 361.012 21.8083 23.3855 + endloop + endfacet + facet normal 0.0357466 -0.211172 0.976795 + outer loop + vertex 319.203 10.7782 22.5488 + vertex 319.08 6.89768 21.7143 + vertex 340.078 14.3044 22.5471 + endloop + endfacet + facet normal 0.0354685 -0.210404 0.976971 + outer loop + vertex 340.078 14.3044 22.5471 + vertex 319.08 6.89768 21.7143 + vertex 339.95 10.4128 21.7137 + endloop + endfacet + facet normal 0.0378117 -0.210459 0.976871 + outer loop + vertex 340.078 14.3044 22.5471 + vertex 339.95 10.4128 21.7137 + vertex 360.892 18.0292 22.544 + endloop + endfacet + facet normal 0.0367539 -0.218036 0.975248 + outer loop + vertex 319.08 6.89768 21.7143 + vertex 319.438 2.96171 20.8209 + vertex 339.95 10.4128 21.7137 + endloop + endfacet + facet normal 0.036655 -0.217771 0.975311 + outer loop + vertex 339.95 10.4128 21.7137 + vertex 319.438 2.96171 20.8209 + vertex 340.318 6.47497 20.8206 + endloop + endfacet + facet normal 0.0389469 -0.217548 0.975272 + outer loop + vertex 339.95 10.4128 21.7137 + vertex 340.318 6.47497 20.8206 + vertex 360.75 14.1199 21.7099 + endloop + endfacet + facet normal 0.0384466 -0.216247 0.975581 + outer loop + vertex 360.75 14.1199 21.7099 + vertex 340.318 6.47497 20.8206 + vertex 361.102 10.1683 20.8202 + endloop + endfacet + facet normal 0.0429215 -0.241429 0.969469 + outer loop + vertex 340.318 6.47497 20.8206 + vertex 341.674 2.53342 19.779 + vertex 361.102 10.1683 20.8202 + endloop + endfacet + facet normal 0.0407153 -0.242165 0.96938 + outer loop + vertex 340.318 6.47497 20.8206 + vertex 320.833 -0.980454 19.7765 + vertex 341.674 2.53342 19.779 + endloop + endfacet + facet normal 0.0465885 -0.276993 0.959742 + outer loop + vertex 320.833 -0.980454 19.7765 + vertex 323.327 -4.9113 18.521 + vertex 341.674 2.53342 19.779 + endloop + endfacet + facet normal 0.0471468 -0.278301 0.959336 + outer loop + vertex 341.674 2.53342 19.779 + vertex 323.327 -4.9113 18.521 + vertex 344.036 -1.39791 18.5225 + endloop + endfacet + facet normal 0.0492409 -0.277119 0.959573 + outer loop + vertex 341.674 2.53342 19.779 + vertex 344.036 -1.39791 18.5225 + vertex 362.445 6.22818 19.7801 + endloop + endfacet + facet normal 0.0444993 -0.278236 0.959481 + outer loop + vertex 320.833 -0.980454 19.7765 + vertex 302.304 -8.27867 18.5195 + vertex 323.327 -4.9113 18.521 + endloop + endfacet + facet normal 0.044062 -0.277182 0.959807 + outer loop + vertex 299.818 -4.32474 19.7755 + vertex 302.304 -8.27867 18.5195 + vertex 320.833 -0.980454 19.7765 + endloop + endfacet + facet normal 0.0386371 -0.243095 0.969233 + outer loop + vertex 319.438 2.96171 20.8209 + vertex 299.818 -4.32474 19.7755 + vertex 320.833 -0.980454 19.7765 + endloop + endfacet + facet normal 0.0382477 -0.242085 0.969501 + outer loop + vertex 298.472 -0.364797 20.8174 + vertex 299.818 -4.32474 19.7755 + vertex 319.438 2.96171 20.8209 + endloop + endfacet + facet normal 0.0361368 -0.242778 0.969408 + outer loop + vertex 298.472 -0.364797 20.8174 + vertex 278.741 -7.47664 19.7718 + vertex 299.818 -4.32474 19.7755 + endloop + endfacet + facet normal 0.0412808 -0.277165 0.959935 + outer loop + vertex 278.741 -7.47664 19.7718 + vertex 281.1 -11.4709 18.5171 + vertex 299.818 -4.32474 19.7755 + endloop + endfacet + facet normal 0.0392728 -0.278276 0.959698 + outer loop + vertex 278.741 -7.47664 19.7718 + vertex 259.988 -14.4447 18.5187 + vertex 281.1 -11.4709 18.5171 + endloop + endfacet + facet normal 0.0386849 -0.276777 0.960155 + outer loop + vertex 257.657 -10.4229 19.772 + vertex 259.988 -14.4447 18.5187 + vertex 278.741 -7.47664 19.7718 + endloop + endfacet + facet normal 0.034001 -0.243257 0.969366 + outer loop + vertex 277.428 -3.50079 20.8156 + vertex 257.657 -10.4229 19.772 + vertex 278.741 -7.47664 19.7718 + endloop + endfacet + facet normal 0.0335688 -0.242069 0.969678 + outer loop + vertex 256.37 -6.43215 20.8128 + vertex 257.657 -10.4229 19.772 + vertex 277.428 -3.50079 20.8156 + endloop + endfacet + facet normal 0.0303449 -0.218915 0.975272 + outer loop + vertex 277.117 0.441656 21.7102 + vertex 256.37 -6.43215 20.8128 + vertex 277.428 -3.50079 20.8156 + endloop + endfacet + facet normal 0.0324716 -0.218741 0.975243 + outer loop + vertex 277.117 0.441656 21.7102 + vertex 277.428 -3.50079 20.8156 + vertex 298.13 3.57273 21.7128 + endloop + endfacet + facet normal 0.0313953 -0.211519 0.97687 + outer loop + vertex 298.274 7.44889 22.5475 + vertex 277.117 0.441656 21.7102 + vertex 298.13 3.57273 21.7128 + endloop + endfacet + facet normal 0.0335986 -0.211582 0.976783 + outer loop + vertex 298.274 7.44889 22.5475 + vertex 298.13 3.57273 21.7128 + vertex 319.203 10.7782 22.5488 + endloop + endfacet + facet normal 0.0314897 -0.211796 0.976806 + outer loop + vertex 277.279 4.31562 22.5449 + vertex 277.117 0.441656 21.7102 + vertex 298.274 7.44889 22.5475 + endloop + endfacet + facet normal 0.0323316 -0.217437 0.975539 + outer loop + vertex 298.365 11.1925 23.3789 + vertex 277.279 4.31562 22.5449 + vertex 298.274 7.44889 22.5475 + endloop + endfacet + facet normal 0.034589 -0.217472 0.975453 + outer loop + vertex 298.365 11.1925 23.3789 + vertex 298.274 7.44889 22.5475 + vertex 319.282 14.5277 23.3807 + endloop + endfacet + facet normal 0.0361032 -0.226968 0.973233 + outer loop + vertex 319.115 18.0493 24.2082 + vertex 298.365 11.1925 23.3789 + vertex 319.282 14.5277 23.3807 + endloop + endfacet + facet normal 0.0361278 -0.22704 0.973215 + outer loop + vertex 298.217 14.7118 24.2054 + vertex 298.365 11.1925 23.3789 + vertex 319.115 18.0493 24.2082 + endloop + endfacet + facet normal 0.0370939 -0.233089 0.971748 + outer loop + vertex 318.829 21.2565 24.9884 + vertex 298.217 14.7118 24.2054 + vertex 319.115 18.0493 24.2082 + endloop + endfacet + facet normal 0.0387839 -0.232931 0.97172 + outer loop + vertex 318.829 21.2565 24.9884 + vertex 319.115 18.0493 24.2082 + vertex 339.666 24.7965 25.0053 + endloop + endfacet + facet normal 0.0394454 -0.23682 0.970753 + outer loop + vertex 339.463 27.5927 25.6957 + vertex 318.829 21.2565 24.9884 + vertex 339.666 24.7965 25.0053 + endloop + endfacet + facet normal 0.0394427 -0.23682 0.970753 + outer loop + vertex 339.463 27.5927 25.6957 + vertex 339.666 24.7965 25.0053 + vertex 360.306 31.324 25.7591 + endloop + endfacet + facet normal 0.0407428 -0.244051 0.968906 + outer loop + vertex 360.283 33.5928 26.3316 + vertex 339.463 27.5927 25.6957 + vertex 360.306 31.324 25.7591 + endloop + endfacet + facet normal 0.0379611 -0.244104 0.969006 + outer loop + vertex 360.283 33.5928 26.3316 + vertex 360.306 31.324 25.7591 + vertex 381.189 37.5167 26.501 + endloop + endfacet + facet normal 0.0377591 -0.233974 0.971509 + outer loop + vertex 339.542 29.8829 26.2442 + vertex 339.463 27.5927 25.6957 + vertex 360.283 33.5928 26.3316 + endloop + endfacet + facet normal 0.0385916 -0.2386 0.970351 + outer loop + vertex 360.352 35.2047 26.7252 + vertex 339.542 29.8829 26.2442 + vertex 360.283 33.5928 26.3316 + endloop + endfacet + facet normal 0.0352562 -0.238496 0.970503 + outer loop + vertex 360.352 35.2047 26.7252 + vertex 360.283 33.5928 26.3316 + vertex 381.142 39.1129 26.9303 + endloop + endfacet + facet normal 0.0360252 -0.228787 0.97281 + outer loop + vertex 339.708 31.5008 26.6185 + vertex 339.542 29.8829 26.2442 + vertex 360.352 35.2047 26.7252 + endloop + endfacet + facet normal 0.035703 -0.227004 0.973239 + outer loop + vertex 359.917 36.0381 26.9355 + vertex 339.708 31.5008 26.6185 + vertex 360.352 35.2047 26.7252 + endloop + endfacet + facet normal 0.032998 -0.228358 0.973018 + outer loop + vertex 359.917 36.0381 26.9355 + vertex 360.352 35.2047 26.7252 + vertex 380.516 39.901 27.1435 + endloop + endfacet + facet normal 0.022473 -0.172865 0.984689 + outer loop + vertex 378.74 40.0039 27.2021 + vertex 359.917 36.0381 26.9355 + vertex 380.516 39.901 27.1435 + endloop + endfacet + facet normal 0.0289475 -0.203192 0.978711 + outer loop + vertex 357.703 36.0762 27.0089 + vertex 359.917 36.0381 26.9355 + vertex 378.74 40.0039 27.2021 + endloop + endfacet + facet normal 0.0291948 -0.192842 0.980795 + outer loop + vertex 357.703 36.0762 27.0089 + vertex 339.326 32.3462 26.8226 + vertex 359.917 36.0381 26.9355 + endloop + endfacet + facet normal 0.0309686 -0.201493 0.979 + outer loop + vertex 337.426 32.4388 26.9017 + vertex 339.326 32.3462 26.8226 + vertex 357.703 36.0762 27.0089 + endloop + endfacet + facet normal 0.031154 -0.198247 0.979657 + outer loop + vertex 337.426 32.4388 26.9017 + vertex 318.601 28.8118 26.7664 + vertex 339.326 32.3462 26.8226 + endloop + endfacet + facet normal 0.0341037 -0.215483 0.975912 + outer loop + vertex 318.601 28.8118 26.7664 + vertex 318.994 27.9803 26.569 + vertex 339.326 32.3462 26.8226 + endloop + endfacet + facet normal 0.0349639 -0.219435 0.975 + outer loop + vertex 339.326 32.3462 26.8226 + vertex 318.994 27.9803 26.569 + vertex 339.708 31.5008 26.6185 + endloop + endfacet + facet normal 0.0356007 -0.223171 0.974129 + outer loop + vertex 318.994 27.9803 26.569 + vertex 318.81 26.357 26.2039 + vertex 339.708 31.5008 26.6185 + endloop + endfacet + facet normal 0.0350235 -0.223113 0.974163 + outer loop + vertex 318.994 27.9803 26.569 + vertex 297.92 23.0044 26.1871 + vertex 318.81 26.357 26.2039 + endloop + endfacet + facet normal 0.035732 -0.227522 0.973117 + outer loop + vertex 297.92 23.0044 26.1871 + vertex 297.807 20.717 25.6564 + vertex 318.81 26.357 26.2039 + endloop + endfacet + facet normal 0.0362483 -0.2294 0.972657 + outer loop + vertex 318.81 26.357 26.2039 + vertex 297.807 20.717 25.6564 + vertex 318.683 24.0609 25.6671 + endloop + endfacet + facet normal 0.0371284 -0.229439 0.972615 + outer loop + vertex 318.81 26.357 26.2039 + vertex 318.683 24.0609 25.6671 + vertex 339.542 29.8829 26.2442 + endloop + endfacet + facet normal 0.036705 -0.232249 0.971964 + outer loop + vertex 297.807 20.717 25.6564 + vertex 297.947 17.9138 24.9813 + vertex 318.683 24.0609 25.6671 + endloop + endfacet + facet normal 0.0370036 -0.233229 0.971718 + outer loop + vertex 318.683 24.0609 25.6671 + vertex 297.947 17.9138 24.9813 + vertex 318.829 21.2565 24.9884 + endloop + endfacet + facet normal 0.0347792 -0.232356 0.972009 + outer loop + vertex 297.807 20.717 25.6564 + vertex 276.951 14.7647 24.9798 + vertex 297.947 17.9138 24.9813 + endloop + endfacet + facet normal 0.0348714 -0.232971 0.971858 + outer loop + vertex 276.951 14.7647 24.9798 + vertex 277.235 11.5667 24.203 + vertex 297.947 17.9138 24.9813 + endloop + endfacet + facet normal 0.0347541 -0.2326 0.971951 + outer loop + vertex 297.947 17.9138 24.9813 + vertex 277.235 11.5667 24.203 + vertex 298.217 14.7118 24.2054 + endloop + endfacet + facet normal 0.0339822 -0.227451 0.973196 + outer loop + vertex 277.235 11.5667 24.203 + vertex 277.387 8.05409 23.3767 + vertex 298.217 14.7118 24.2054 + endloop + endfacet + facet normal 0.0317042 -0.227562 0.973247 + outer loop + vertex 277.235 11.5667 24.203 + vertex 256.356 5.11609 23.3749 + vertex 277.387 8.05409 23.3767 + endloop + endfacet + facet normal 0.0304167 -0.218347 0.975397 + outer loop + vertex 256.356 5.11609 23.3749 + vertex 256.246 1.38387 22.5428 + vertex 277.387 8.05409 23.3767 + endloop + endfacet + facet normal 0.0302768 -0.217916 0.975498 + outer loop + vertex 277.387 8.05409 23.3767 + vertex 256.246 1.38387 22.5428 + vertex 277.279 4.31562 22.5449 + endloop + endfacet + facet normal 0.0294584 -0.212046 0.976816 + outer loop + vertex 256.246 1.38387 22.5428 + vertex 256.071 -2.48701 21.7078 + vertex 277.279 4.31562 22.5449 + endloop + endfacet + facet normal 0.0273437 -0.211967 0.976894 + outer loop + vertex 256.246 1.38387 22.5428 + vertex 235.004 -5.20634 21.7075 + vertex 256.071 -2.48701 21.7078 + endloop + endfacet + facet normal 0.028238 -0.218896 0.97534 + outer loop + vertex 235.004 -5.20634 21.7075 + vertex 235.284 -9.15393 20.8134 + vertex 256.071 -2.48701 21.7078 + endloop + endfacet + facet normal 0.0283114 -0.219118 0.975288 + outer loop + vertex 256.071 -2.48701 21.7078 + vertex 235.284 -9.15393 20.8134 + vertex 256.37 -6.43215 20.8128 + endloop + endfacet + facet normal 0.0313528 -0.24268 0.9696 + outer loop + vertex 235.284 -9.15393 20.8134 + vertex 236.588 -13.1531 19.7702 + vertex 256.37 -6.43215 20.8128 + endloop + endfacet + facet normal 0.0290822 -0.243393 0.969492 + outer loop + vertex 235.284 -9.15393 20.8134 + vertex 215.455 -15.6698 19.7724 + vertex 236.588 -13.1531 19.7702 + endloop + endfacet + facet normal 0.033134 -0.277425 0.960176 + outer loop + vertex 215.455 -15.6698 19.7724 + vertex 217.854 -19.727 18.5173 + vertex 236.588 -13.1531 19.7702 + endloop + endfacet + facet normal 0.0334346 -0.278235 0.959931 + outer loop + vertex 236.588 -13.1531 19.7702 + vertex 217.854 -19.727 18.5173 + vertex 238.954 -17.1913 18.5174 + endloop + endfacet + facet normal 0.0358082 -0.276934 0.960221 + outer loop + vertex 236.588 -13.1531 19.7702 + vertex 238.954 -17.1913 18.5174 + vertex 257.657 -10.4229 19.772 + endloop + endfacet + facet normal 0.0306438 -0.2788 0.95986 + outer loop + vertex 215.455 -15.6698 19.7724 + vertex 196.626 -22.0511 18.52 + vertex 217.854 -19.727 18.5173 + endloop + endfacet + facet normal 0.0299441 -0.276851 0.960446 + outer loop + vertex 194.216 -17.9671 19.7723 + vertex 196.626 -22.0511 18.52 + vertex 215.455 -15.6698 19.7724 + endloop + endfacet + facet normal 0.0262936 -0.243101 0.969644 + outer loop + vertex 214.161 -11.657 20.8135 + vertex 194.216 -17.9671 19.7723 + vertex 215.455 -15.6698 19.7724 + endloop + endfacet + facet normal 0.0260956 -0.242501 0.9698 + outer loop + vertex 192.925 -13.9405 20.8139 + vertex 194.216 -17.9671 19.7723 + vertex 214.161 -11.657 20.8135 + endloop + endfacet + facet normal 0.0235578 -0.218899 0.975463 + outer loop + vertex 213.895 -7.70496 21.7068 + vertex 192.925 -13.9405 20.8139 + vertex 214.161 -11.657 20.8135 + endloop + endfacet + facet normal 0.0258618 -0.218738 0.975441 + outer loop + vertex 213.895 -7.70496 21.7068 + vertex 214.161 -11.657 20.8135 + vertex 235.004 -5.20634 21.7075 + endloop + endfacet + facet normal 0.0250631 -0.211991 0.97695 + outer loop + vertex 235.193 -1.33819 22.542 + vertex 213.895 -7.70496 21.7068 + vertex 235.004 -5.20634 21.7075 + endloop + endfacet + facet normal 0.0251772 -0.212362 0.976867 + outer loop + vertex 214.088 -3.84149 22.5417 + vertex 213.895 -7.70496 21.7068 + vertex 235.193 -1.33819 22.542 + endloop + endfacet + facet normal 0.025886 -0.218338 0.97553 + outer loop + vertex 235.303 2.38996 23.3734 + vertex 214.088 -3.84149 22.5417 + vertex 235.193 -1.33819 22.542 + endloop + endfacet + facet normal 0.0282137 -0.21839 0.975454 + outer loop + vertex 235.303 2.38996 23.3734 + vertex 235.193 -1.33819 22.542 + vertex 256.356 5.11609 23.3749 + endloop + endfacet + facet normal 0.0294539 -0.227965 0.973224 + outer loop + vertex 256.193 8.62235 24.2011 + vertex 235.303 2.38996 23.3734 + vertex 256.356 5.11609 23.3749 + endloop + endfacet + facet normal 0.0294404 -0.227922 0.973234 + outer loop + vertex 235.128 5.89051 24.1985 + vertex 235.303 2.38996 23.3734 + vertex 256.193 8.62235 24.2011 + endloop + endfacet + facet normal 0.0301523 -0.233409 0.971911 + outer loop + vertex 255.885 11.8114 24.9765 + vertex 235.128 5.89051 24.1985 + vertex 256.193 8.62235 24.2011 + endloop + endfacet + facet normal 0.0325385 -0.233174 0.97189 + outer loop + vertex 255.885 11.8114 24.9765 + vertex 256.193 8.62235 24.2011 + vertex 276.951 14.7647 24.9798 + endloop + endfacet + facet normal 0.0324197 -0.232327 0.972097 + outer loop + vertex 276.785 17.5599 25.6534 + vertex 255.885 11.8114 24.9765 + vertex 276.951 14.7647 24.9798 + endloop + endfacet + facet normal 0.0323465 -0.232069 0.972161 + outer loop + vertex 255.698 14.5947 25.6471 + vertex 255.885 11.8114 24.9765 + vertex 276.785 17.5599 25.6534 + endloop + endfacet + facet normal 0.0315181 -0.22618 0.973575 + outer loop + vertex 276.868 19.8259 26.1771 + vertex 255.698 14.5947 25.6471 + vertex 276.785 17.5599 25.6534 + endloop + endfacet + facet normal 0.0336972 -0.22624 0.973489 + outer loop + vertex 276.868 19.8259 26.1771 + vertex 276.785 17.5599 25.6534 + vertex 297.92 23.0044 26.1871 + endloop + endfacet + facet normal 0.0327739 -0.22013 0.97492 + outer loop + vertex 298.054 24.6073 26.5445 + vertex 276.868 19.8259 26.1771 + vertex 297.92 23.0044 26.1871 + endloop + endfacet + facet normal 0.0326589 -0.219629 0.975037 + outer loop + vertex 276.956 21.4241 26.5342 + vertex 276.868 19.8259 26.1771 + vertex 298.054 24.6073 26.5445 + endloop + endfacet + facet normal 0.0321874 -0.216506 0.975751 + outer loop + vertex 297.507 25.4234 26.7436 + vertex 276.956 21.4241 26.5342 + vertex 298.054 24.6073 26.5445 + endloop + endfacet + facet normal 0.0335813 -0.215609 0.975902 + outer loop + vertex 297.507 25.4234 26.7436 + vertex 298.054 24.6073 26.5445 + vertex 318.601 28.8118 26.7664 + endloop + endfacet + facet normal 0.0343864 -0.220614 0.974755 + outer loop + vertex 316.576 28.907 26.8594 + vertex 297.507 25.4234 26.7436 + vertex 318.601 28.8118 26.7664 + endloop + endfacet + facet normal 0.0350346 -0.224134 0.973928 + outer loop + vertex 294.812 25.429 26.8419 + vertex 297.507 25.4234 26.7436 + vertex 316.576 28.907 26.8594 + endloop + endfacet + facet normal 0.0349174 -0.235106 0.971342 + outer loop + vertex 294.812 25.429 26.8419 + vertex 276.327 22.226 26.7311 + vertex 297.507 25.4234 26.7436 + endloop + endfacet + facet normal 0.0334743 -0.226848 0.973355 + outer loop + vertex 273.997 22.3044 26.8295 + vertex 276.327 22.226 26.7311 + vertex 294.812 25.429 26.8419 + endloop + endfacet + facet normal 0.0329695 -0.238403 0.970607 + outer loop + vertex 273.997 22.3044 26.8295 + vertex 255.203 19.2487 26.7173 + vertex 276.327 22.226 26.7311 + endloop + endfacet + facet normal 0.0293005 -0.2124 0.976743 + outer loop + vertex 255.203 19.2487 26.7173 + vertex 255.836 18.4464 26.5239 + vertex 276.327 22.226 26.7311 + endloop + endfacet + facet normal 0.0299975 -0.216133 0.975903 + outer loop + vertex 276.327 22.226 26.7311 + vertex 255.836 18.4464 26.5239 + vertex 276.956 21.4241 26.5342 + endloop + endfacet + facet normal 0.0302799 -0.218134 0.975449 + outer loop + vertex 255.836 18.4464 26.5239 + vertex 255.762 16.8588 26.1711 + vertex 276.956 21.4241 26.5342 + endloop + endfacet + facet normal 0.0279193 -0.218044 0.97554 + outer loop + vertex 255.836 18.4464 26.5239 + vertex 234.65 14.1022 26.1592 + vertex 255.762 16.8588 26.1711 + endloop + endfacet + facet normal 0.0288168 -0.22491 0.973953 + outer loop + vertex 234.65 14.1022 26.1592 + vertex 234.601 11.852 25.6411 + vertex 255.762 16.8588 26.1711 + endloop + endfacet + facet normal 0.0291213 -0.226165 0.973654 + outer loop + vertex 255.762 16.8588 26.1711 + vertex 234.601 11.852 25.6411 + vertex 255.698 14.5947 25.6471 + endloop + endfacet + facet normal 0.0298461 -0.231738 0.97232 + outer loop + vertex 234.601 11.852 25.6411 + vertex 234.804 9.07503 24.973 + vertex 255.698 14.5947 25.6471 + endloop + endfacet + facet normal 0.0273371 -0.231929 0.972349 + outer loop + vertex 234.601 11.852 25.6411 + vertex 213.685 6.558 24.9663 + vertex 234.804 9.07503 24.973 + endloop + endfacet + facet normal 0.027435 -0.232749 0.97215 + outer loop + vertex 213.685 6.558 24.9663 + vertex 214.021 3.37928 24.1958 + vertex 234.804 9.07503 24.973 + endloop + endfacet + facet normal 0.0276621 -0.233551 0.971951 + outer loop + vertex 234.804 9.07503 24.973 + vertex 214.021 3.37928 24.1958 + vertex 235.128 5.89051 24.1985 + endloop + endfacet + facet normal 0.0269836 -0.227849 0.973322 + outer loop + vertex 214.021 3.37928 24.1958 + vertex 214.199 -0.11809 23.3722 + vertex 235.128 5.89051 24.1985 + endloop + endfacet + facet normal 0.0245459 -0.227981 0.973356 + outer loop + vertex 214.021 3.37928 24.1958 + vertex 192.988 -2.40699 23.371 + vertex 214.199 -0.11809 23.3722 + endloop + endfacet + facet normal 0.0234933 -0.218228 0.975615 + outer loop + vertex 192.988 -2.40699 23.371 + vertex 192.869 -6.12661 22.5418 + vertex 214.199 -0.11809 23.3722 + endloop + endfacet + facet normal 0.023514 -0.218299 0.975599 + outer loop + vertex 214.199 -0.11809 23.3722 + vertex 192.869 -6.12661 22.5418 + vertex 214.088 -3.84149 22.5417 + endloop + endfacet + facet normal 0.0228494 -0.212127 0.976975 + outer loop + vertex 192.869 -6.12661 22.5418 + vertex 192.661 -9.98799 21.7083 + vertex 214.088 -3.84149 22.5417 + endloop + endfacet + facet normal 0.0204507 -0.212016 0.977052 + outer loop + vertex 192.869 -6.12661 22.5418 + vertex 171.299 -12.0461 21.7088 + vertex 192.661 -9.98799 21.7083 + endloop + endfacet + facet normal 0.0211417 -0.219188 0.975454 + outer loop + vertex 171.299 -12.0461 21.7088 + vertex 171.548 -16.0015 20.8146 + vertex 192.661 -9.98799 21.7083 + endloop + endfacet + facet normal 0.0211727 -0.219293 0.975429 + outer loop + vertex 192.661 -9.98799 21.7083 + vertex 171.548 -16.0015 20.8146 + vertex 192.925 -13.9405 20.8139 + endloop + endfacet + facet normal 0.0234269 -0.242676 0.969824 + outer loop + vertex 171.548 -16.0015 20.8146 + vertex 172.82 -20.0427 19.7727 + vertex 192.925 -13.9405 20.8139 + endloop + endfacet + facet normal 0.0208394 -0.243456 0.969688 + outer loop + vertex 171.548 -16.0015 20.8146 + vertex 151.341 -21.8827 19.7723 + vertex 172.82 -20.0427 19.7727 + endloop + endfacet + facet normal 0.0237409 -0.277325 0.960483 + outer loop + vertex 151.341 -21.8827 19.7723 + vertex 153.665 -26.0259 18.5186 + vertex 172.82 -20.0427 19.7727 + endloop + endfacet + facet normal 0.0241778 -0.278641 0.960091 + outer loop + vertex 172.82 -20.0427 19.7727 + vertex 153.665 -26.0259 18.5186 + vertex 175.214 -24.1542 18.5191 + endloop + endfacet + facet normal 0.0269016 -0.277164 0.960446 + outer loop + vertex 172.82 -20.0427 19.7727 + vertex 175.214 -24.1542 18.5191 + vertex 194.216 -17.9671 19.7723 + endloop + endfacet + facet normal 0.0210411 -0.278735 0.960138 + outer loop + vertex 151.341 -21.8827 19.7723 + vertex 132.171 -27.6438 18.5199 + vertex 153.665 -26.0259 18.5186 + endloop + endfacet + facet normal 0.0205689 -0.277259 0.960575 + outer loop + vertex 129.878 -23.4706 19.7736 + vertex 132.171 -27.6438 18.5199 + vertex 151.341 -21.8827 19.7723 + endloop + endfacet + facet normal 0.0180819 -0.243636 0.969698 + outer loop + vertex 150.094 -17.8262 20.8147 + vertex 129.878 -23.4706 19.7736 + vertex 151.341 -21.8827 19.7723 + endloop + endfacet + facet normal 0.0178941 -0.242994 0.969863 + outer loop + vertex 128.634 -19.4001 20.8164 + vertex 129.878 -23.4706 19.7736 + vertex 150.094 -17.8262 20.8147 + endloop + endfacet + facet normal 0.0161727 -0.219516 0.975475 + outer loop + vertex 149.859 -13.8684 21.7093 + vertex 128.634 -19.4001 20.8164 + vertex 150.094 -17.8262 20.8147 + endloop + endfacet + facet normal 0.0186677 -0.219366 0.975464 + outer loop + vertex 149.859 -13.8684 21.7093 + vertex 150.094 -17.8262 20.8147 + vertex 171.299 -12.0461 21.7088 + endloop + endfacet + facet normal 0.0180465 -0.212057 0.977091 + outer loop + vertex 171.518 -8.18818 22.542 + vertex 149.859 -13.8684 21.7093 + vertex 171.299 -12.0461 21.7088 + endloop + endfacet + facet normal 0.0181071 -0.21228 0.977041 + outer loop + vertex 150.093 -10.0148 22.5422 + vertex 149.859 -13.8684 21.7093 + vertex 171.518 -8.18818 22.542 + endloop + endfacet + facet normal 0.0185973 -0.218031 0.975765 + outer loop + vertex 171.65 -4.47234 23.3698 + vertex 150.093 -10.0148 22.5422 + vertex 171.518 -8.18818 22.542 + endloop + endfacet + facet normal 0.0210578 -0.218104 0.975698 + outer loop + vertex 171.65 -4.47234 23.3698 + vertex 171.518 -8.18818 22.542 + vertex 192.988 -2.40699 23.371 + endloop + endfacet + facet normal 0.0219753 -0.227581 0.973511 + outer loop + vertex 192.807 1.08718 24.1919 + vertex 171.65 -4.47234 23.3698 + vertex 192.988 -2.40699 23.371 + endloop + endfacet + facet normal 0.0218275 -0.227038 0.973641 + outer loop + vertex 171.473 -0.978975 24.1884 + vertex 171.65 -4.47234 23.3698 + vertex 192.807 1.08718 24.1919 + endloop + endfacet + facet normal 0.0223592 -0.232526 0.972333 + outer loop + vertex 192.462 4.26479 24.9597 + vertex 171.473 -0.978975 24.1884 + vertex 192.807 1.08718 24.1919 + endloop + endfacet + facet normal 0.0247932 -0.232263 0.972337 + outer loop + vertex 192.462 4.26479 24.9597 + vertex 192.807 1.08718 24.1919 + vertex 213.685 6.558 24.9663 + endloop + endfacet + facet normal 0.0246795 -0.231211 0.972591 + outer loop + vertex 213.465 9.32885 25.6306 + vertex 192.462 4.26479 24.9597 + vertex 213.685 6.558 24.9663 + endloop + endfacet + facet normal 0.0242982 -0.229679 0.972963 + outer loop + vertex 192.219 7.02798 25.6181 + vertex 192.462 4.26479 24.9597 + vertex 213.465 9.32885 25.6306 + endloop + endfacet + facet normal 0.0236694 -0.22388 0.974329 + outer loop + vertex 213.482 11.5736 26.146 + vertex 192.219 7.02798 25.6181 + vertex 213.465 9.32885 25.6306 + endloop + endfacet + facet normal 0.0261357 -0.223884 0.974265 + outer loop + vertex 213.482 11.5736 26.146 + vertex 213.465 9.32885 25.6306 + vertex 234.65 14.1022 26.1592 + endloop + endfacet + facet normal 0.025253 -0.216503 0.975955 + outer loop + vertex 234.678 15.6788 26.5083 + vertex 213.482 11.5736 26.146 + vertex 234.65 14.1022 26.1592 + endloop + endfacet + facet normal 0.0249086 -0.21476 0.976349 + outer loop + vertex 213.475 13.1432 26.4915 + vertex 213.482 11.5736 26.146 + vertex 234.678 15.6788 26.5083 + endloop + endfacet + facet normal 0.0246338 -0.212465 0.976858 + outer loop + vertex 233.892 16.4706 26.7003 + vertex 213.475 13.1432 26.4915 + vertex 234.678 15.6788 26.5083 + endloop + endfacet + facet normal 0.0266644 -0.210538 0.977222 + outer loop + vertex 233.892 16.4706 26.7003 + vertex 234.678 15.6788 26.5083 + vertex 255.203 19.2487 26.7173 + endloop + endfacet + facet normal 0.030235 -0.237889 0.970822 + outer loop + vertex 252.699 19.3316 26.8156 + vertex 233.892 16.4706 26.7003 + vertex 255.203 19.2487 26.7173 + endloop + endfacet + facet normal 0.027731 -0.221588 0.974746 + outer loop + vertex 230.843 16.5074 26.7954 + vertex 233.892 16.4706 26.7003 + vertex 252.699 19.3316 26.8156 + endloop + endfacet + facet normal 0.0274286 -0.23716 0.971083 + outer loop + vertex 230.843 16.5074 26.7954 + vertex 212.72 13.9409 26.6805 + vertex 233.892 16.4706 26.7003 + endloop + endfacet + facet normal 0.0256797 -0.224942 0.974034 + outer loop + vertex 210.28 14.0709 26.7748 + vertex 212.72 13.9409 26.6805 + vertex 230.843 16.5074 26.7954 + endloop + endfacet + facet normal 0.0247995 -0.239043 0.970692 + outer loop + vertex 210.28 14.0709 26.7748 + vertex 191.726 11.6656 26.6565 + vertex 212.72 13.9409 26.6805 + endloop + endfacet + facet normal 0.0213112 -0.206936 0.978122 + outer loop + vertex 191.726 11.6656 26.6565 + vertex 192.24 10.8346 26.4695 + vertex 212.72 13.9409 26.6805 + endloop + endfacet + facet normal 0.0219148 -0.210857 0.977271 + outer loop + vertex 212.72 13.9409 26.6805 + vertex 192.24 10.8346 26.4695 + vertex 213.475 13.1432 26.4915 + endloop + endfacet + facet normal 0.022131 -0.212842 0.976836 + outer loop + vertex 192.24 10.8346 26.4695 + vertex 192.212 9.26393 26.1279 + vertex 213.475 13.1432 26.4915 + endloop + endfacet + facet normal 0.0198394 -0.212813 0.976892 + outer loop + vertex 192.24 10.8346 26.4695 + vertex 170.849 7.18987 26.11 + vertex 192.212 9.26393 26.1279 + endloop + endfacet + facet normal 0.0205671 -0.220293 0.975217 + outer loop + vertex 170.849 7.18987 26.11 + vertex 170.854 4.957 25.6055 + vertex 192.212 9.26393 26.1279 + endloop + endfacet + facet normal 0.0209642 -0.222208 0.974774 + outer loop + vertex 192.212 9.26393 26.1279 + vertex 170.854 4.957 25.6055 + vertex 192.219 7.02798 25.6181 + endloop + endfacet + facet normal 0.0215782 -0.228533 0.973297 + outer loop + vertex 170.854 4.957 25.6055 + vertex 171.118 2.19556 24.9512 + vertex 192.219 7.02798 25.6181 + endloop + endfacet + facet normal 0.0191615 -0.228763 0.973294 + outer loop + vertex 170.854 4.957 25.6055 + vertex 149.711 0.364609 24.9423 + vertex 171.118 2.19556 24.9512 + endloop + endfacet + facet normal 0.0192948 -0.23032 0.972924 + outer loop + vertex 149.711 0.364609 24.9423 + vertex 150.068 -2.80896 24.184 + vertex 171.118 2.19556 24.9512 + endloop + endfacet + facet normal 0.0195945 -0.231535 0.972629 + outer loop + vertex 171.118 2.19556 24.9512 + vertex 150.068 -2.80896 24.184 + vertex 171.473 -0.978975 24.1884 + endloop + endfacet + facet normal 0.019163 -0.226491 0.973825 + outer loop + vertex 150.068 -2.80896 24.184 + vertex 150.236 -6.30078 23.3685 + vertex 171.473 -0.978975 24.1884 + endloop + endfacet + facet normal 0.0166134 -0.226617 0.973842 + outer loop + vertex 150.068 -2.80896 24.184 + vertex 128.821 -7.87654 23.3672 + vertex 150.236 -6.30078 23.3685 + endloop + endfacet + facet normal 0.0159505 -0.21761 0.975906 + outer loop + vertex 128.821 -7.87654 23.3672 + vertex 128.662 -11.5873 22.5424 + vertex 150.236 -6.30078 23.3685 + endloop + endfacet + facet normal 0.0159821 -0.217734 0.975877 + outer loop + vertex 150.236 -6.30078 23.3685 + vertex 128.662 -11.5873 22.5424 + vertex 150.093 -10.0148 22.5422 + endloop + endfacet + facet normal 0.0155674 -0.212083 0.977128 + outer loop + vertex 128.662 -11.5873 22.5424 + vertex 128.413 -15.4395 21.7102 + vertex 150.093 -10.0148 22.5422 + endloop + endfacet + facet normal 0.0129114 -0.211926 0.9772 + outer loop + vertex 128.662 -11.5873 22.5424 + vertex 106.988 -16.7446 21.7102 + vertex 128.413 -15.4395 21.7102 + endloop + endfacet + facet normal 0.0133685 -0.21943 0.975537 + outer loop + vertex 106.988 -16.7446 21.7102 + vertex 107.212 -20.7084 20.8156 + vertex 128.413 -15.4395 21.7102 + endloop + endfacet + facet normal 0.0133656 -0.219419 0.975539 + outer loop + vertex 128.413 -15.4395 21.7102 + vertex 107.212 -20.7084 20.8156 + vertex 128.634 -19.4001 20.8164 + endloop + endfacet + facet normal 0.014785 -0.242658 0.969999 + outer loop + vertex 107.212 -20.7084 20.8156 + vertex 108.463 -24.7944 19.7744 + vertex 128.634 -19.4001 20.8164 + endloop + endfacet + facet normal 0.0119308 -0.243488 0.96983 + outer loop + vertex 107.212 -20.7084 20.8156 + vertex 87.0215 -25.8535 19.7722 + vertex 108.463 -24.7944 19.7744 + endloop + endfacet + facet normal 0.0136068 -0.277399 0.960659 + outer loop + vertex 87.0215 -25.8535 19.7722 + vertex 89.424 -30.0767 18.5187 + vertex 108.463 -24.7944 19.7744 + endloop + endfacet + facet normal 0.0140925 -0.279035 0.960177 + outer loop + vertex 108.463 -24.7944 19.7744 + vertex 89.424 -30.0767 18.5187 + vertex 110.805 -28.9926 18.52 + endloop + endfacet + facet normal 0.0171853 -0.277433 0.960591 + outer loop + vertex 108.463 -24.7944 19.7744 + vertex 110.805 -28.9926 18.52 + vertex 129.878 -23.4706 19.7736 + endloop + endfacet + facet normal 0.010887 -0.278833 0.960278 + outer loop + vertex 87.0215 -25.8535 19.7722 + vertex 67.8424 -30.9103 18.5213 + vertex 89.424 -30.0767 18.5187 + endloop + endfacet + facet normal 0.0104912 -0.277433 0.960688 + outer loop + vertex 65.482 -26.6599 19.7746 + vertex 67.8424 -30.9103 18.5213 + vertex 87.0215 -25.8535 19.7722 + endloop + endfacet + facet normal 0.00924962 -0.244241 0.96967 + outer loop + vertex 85.7492 -21.7546 20.8168 + vertex 65.482 -26.6599 19.7746 + vertex 87.0215 -25.8535 19.7722 + endloop + endfacet + facet normal 0.00887802 -0.242784 0.97004 + outer loop + vertex 64.2494 -22.544 20.816 + vertex 65.482 -26.6599 19.7746 + vertex 85.7492 -21.7546 20.8168 + endloop + endfacet + facet normal 0.00802146 -0.219459 0.975589 + outer loop + vertex 85.5347 -17.7877 21.7109 + vertex 64.2494 -22.544 20.816 + vertex 85.7492 -21.7546 20.8168 + endloop + endfacet + facet normal 0.0106939 -0.219316 0.975595 + outer loop + vertex 85.5347 -17.7877 21.7109 + vertex 85.7492 -21.7546 20.8168 + vertex 106.988 -16.7446 21.7102 + endloop + endfacet + facet normal 0.0103367 -0.21197 0.977222 + outer loop + vertex 107.244 -12.8959 22.5424 + vertex 85.5347 -17.7877 21.7109 + vertex 106.988 -16.7446 21.7102 + endloop + endfacet + facet normal 0.0103413 -0.211989 0.977217 + outer loop + vertex 85.8016 -13.9421 22.5423 + vertex 85.5347 -17.7877 21.7109 + vertex 107.244 -12.8959 22.5424 + endloop + endfacet + facet normal 0.0106017 -0.217326 0.976041 + outer loop + vertex 107.417 -9.18923 23.3658 + vertex 85.8016 -13.9421 22.5423 + vertex 107.244 -12.8959 22.5424 + endloop + endfacet + facet normal 0.0132731 -0.217439 0.975984 + outer loop + vertex 107.417 -9.18923 23.3658 + vertex 107.244 -12.8959 22.5424 + vertex 128.821 -7.87654 23.3672 + endloop + endfacet + facet normal 0.0138016 -0.226054 0.974017 + outer loop + vertex 128.664 -4.38592 24.1795 + vertex 107.417 -9.18923 23.3658 + vertex 128.821 -7.87654 23.3672 + endloop + endfacet + facet normal 0.0136599 -0.225452 0.974159 + outer loop + vertex 107.274 -5.70049 24.1752 + vertex 107.417 -9.18923 23.3658 + vertex 128.664 -4.38592 24.1795 + endloop + endfacet + facet normal 0.0139157 -0.22961 0.973183 + outer loop + vertex 128.315 -1.2142 24.9328 + vertex 107.274 -5.70049 24.1752 + vertex 128.664 -4.38592 24.1795 + endloop + endfacet + facet normal 0.0164912 -0.229332 0.973208 + outer loop + vertex 128.315 -1.2142 24.9328 + vertex 128.664 -4.38592 24.1795 + vertex 149.711 0.364609 24.9423 + endloop + endfacet + facet normal 0.0163304 -0.227156 0.973722 + outer loop + vertex 149.444 3.12091 25.5898 + vertex 128.315 -1.2142 24.9328 + vertex 149.711 0.364609 24.9423 + endloop + endfacet + facet normal 0.0160498 -0.225835 0.974033 + outer loop + vertex 128.058 1.54013 25.5757 + vertex 128.315 -1.2142 24.9328 + vertex 149.444 3.12091 25.5898 + endloop + endfacet + facet normal 0.0155046 -0.218475 0.975719 + outer loop + vertex 149.448 5.34914 26.0887 + vertex 128.058 1.54013 25.5757 + vertex 149.444 3.12091 25.5898 + endloop + endfacet + facet normal 0.0178206 -0.218471 0.975681 + outer loop + vertex 149.448 5.34914 26.0887 + vertex 149.444 3.12091 25.5898 + vertex 170.849 7.18987 26.11 + endloop + endfacet + facet normal 0.0171172 -0.210314 0.977484 + outer loop + vertex 170.963 8.76674 26.4472 + vertex 149.448 5.34914 26.0887 + vertex 170.849 7.18987 26.11 + endloop + endfacet + facet normal 0.0167517 -0.208064 0.977972 + outer loop + vertex 149.577 6.92016 26.4207 + vertex 149.448 5.34914 26.0887 + vertex 170.963 8.76674 26.4472 + endloop + endfacet + facet normal 0.0164636 -0.204738 0.978678 + outer loop + vertex 170.608 9.61537 26.6307 + vertex 149.577 6.92016 26.4207 + vertex 170.963 8.76674 26.4472 + endloop + endfacet + facet normal 0.0185976 -0.203875 0.97882 + outer loop + vertex 170.608 9.61537 26.6307 + vertex 170.963 8.76674 26.4472 + vertex 191.726 11.6656 26.6565 + endloop + endfacet + facet normal 0.0213912 -0.23257 0.972344 + outer loop + vertex 189.707 11.8744 26.7509 + vertex 170.608 9.61537 26.6307 + vertex 191.726 11.6656 26.6565 + endloop + endfacet + facet normal 0.0199827 -0.220809 0.975112 + outer loop + vertex 168.834 9.85913 26.7223 + vertex 170.608 9.61537 26.6307 + vertex 189.707 11.8744 26.7509 + endloop + endfacet + facet normal 0.0185187 -0.230623 0.972867 + outer loop + vertex 168.834 9.85913 26.7223 + vertex 149.136 7.76113 26.5999 + vertex 170.608 9.61537 26.6307 + endloop + endfacet + facet normal 0.016537 -0.212262 0.977073 + outer loop + vertex 146.785 7.98739 26.6889 + vertex 149.136 7.76113 26.5999 + vertex 168.834 9.85913 26.7223 + endloop + endfacet + facet normal 0.0153802 -0.22332 0.974624 + outer loop + vertex 146.785 7.98739 26.6889 + vertex 127.565 6.14789 26.5707 + vertex 149.136 7.76113 26.5999 + endloop + endfacet + facet normal 0.0135056 -0.198353 0.980038 + outer loop + vertex 127.565 6.14789 26.5707 + vertex 128.165 5.315 26.3938 + vertex 149.136 7.76113 26.5999 + endloop + endfacet + facet normal 0.0138718 -0.201439 0.979403 + outer loop + vertex 149.136 7.76113 26.5999 + vertex 128.165 5.315 26.3938 + vertex 149.577 6.92016 26.4207 + endloop + endfacet + facet normal 0.0142239 -0.206119 0.978424 + outer loop + vertex 128.165 5.315 26.3938 + vertex 128.077 3.75652 26.0668 + vertex 149.577 6.92016 26.4207 + endloop + endfacet + facet normal 0.0119805 -0.206003 0.978478 + outer loop + vertex 128.165 5.315 26.3938 + vertex 106.764 2.42271 26.0469 + vertex 128.077 3.75652 26.0668 + endloop + endfacet + facet normal 0.0125688 -0.215373 0.976451 + outer loop + vertex 106.764 2.42271 26.0469 + vertex 106.725 0.215573 25.5606 + vertex 128.077 3.75652 26.0668 + endloop + endfacet + facet normal 0.0127478 -0.216419 0.976217 + outer loop + vertex 128.077 3.75652 26.0668 + vertex 106.725 0.215573 25.5606 + vertex 128.058 1.54013 25.5757 + endloop + endfacet + facet normal 0.0132537 -0.224546 0.974373 + outer loop + vertex 106.725 0.215573 25.5606 + vertex 106.948 -2.53039 24.9248 + vertex 128.058 1.54013 25.5757 + endloop + endfacet + facet normal 0.0107469 -0.224746 0.974358 + outer loop + vertex 106.725 0.215573 25.5606 + vertex 85.5724 -3.58959 24.9162 + vertex 106.948 -2.53039 24.9248 + endloop + endfacet + facet normal 0.0109198 -0.22823 0.973546 + outer loop + vertex 85.5724 -3.58959 24.9162 + vertex 85.8616 -6.75413 24.1711 + vertex 106.948 -2.53039 24.9248 + endloop + endfacet + facet normal 0.0110813 -0.229003 0.973363 + outer loop + vertex 106.948 -2.53039 24.9248 + vertex 85.8616 -6.75413 24.1711 + vertex 107.274 -5.70049 24.1752 + endloop + endfacet + facet normal 0.0108913 -0.225147 0.974264 + outer loop + vertex 85.8616 -6.75413 24.1711 + vertex 85.9834 -10.2388 23.3645 + vertex 107.274 -5.70049 24.1752 + endloop + endfacet + facet normal 0.00830112 -0.225238 0.974268 + outer loop + vertex 85.8616 -6.75413 24.1711 + vertex 64.5007 -11.0351 23.3634 + vertex 85.9834 -10.2388 23.3645 + endloop + endfacet + facet normal 0.00800338 -0.217208 0.976093 + outer loop + vertex 64.5007 -11.0351 23.3634 + vertex 64.3062 -14.7322 22.5423 + vertex 85.9834 -10.2388 23.3645 + endloop + endfacet + facet normal 0.00797823 -0.217092 0.976119 + outer loop + vertex 85.9834 -10.2388 23.3645 + vertex 64.3062 -14.7322 22.5423 + vertex 85.8016 -13.9421 22.5423 + endloop + endfacet + facet normal 0.00779348 -0.212065 0.977224 + outer loop + vertex 64.3062 -14.7322 22.5423 + vertex 64.038 -18.5738 21.7108 + vertex 85.8016 -13.9421 22.5423 + endloop + endfacet + facet normal 0.00540097 -0.211909 0.977274 + outer loop + vertex 64.3062 -14.7322 22.5423 + vertex 42.5235 -19.1203 21.7112 + vertex 64.038 -18.5738 21.7108 + endloop + endfacet + facet normal 0.00558959 -0.219336 0.975633 + outer loop + vertex 42.5235 -19.1203 21.7112 + vertex 42.7221 -23.0923 20.8171 + vertex 64.038 -18.5738 21.7108 + endloop + endfacet + facet normal 0.00564125 -0.219569 0.975581 + outer loop + vertex 64.038 -18.5738 21.7108 + vertex 42.7221 -23.0923 20.8171 + vertex 64.2494 -22.544 20.816 + endloop + endfacet + facet normal 0.0062477 -0.24339 0.969908 + outer loop + vertex 42.7221 -23.0923 20.8171 + vertex 43.9548 -27.2209 19.7731 + vertex 64.2494 -22.544 20.816 + endloop + endfacet + facet normal 0.00383861 -0.244069 0.96975 + outer loop + vertex 42.7221 -23.0923 20.8171 + vertex 22.4786 -27.5535 19.7744 + vertex 43.9548 -27.2209 19.7731 + endloop + endfacet + facet normal 0.00436474 -0.278079 0.960548 + outer loop + vertex 22.4786 -27.5535 19.7744 + vertex 24.7785 -31.8505 18.52 + vertex 43.9548 -27.2209 19.7731 + endloop + endfacet + facet normal 0.00459114 -0.278949 0.960295 + outer loop + vertex 43.9548 -27.2209 19.7731 + vertex 24.7785 -31.8505 18.52 + vertex 46.2419 -31.497 18.52 + endloop + endfacet + facet normal 0.00717024 -0.277673 0.960649 + outer loop + vertex 43.9548 -27.2209 19.7731 + vertex 46.2419 -31.497 18.52 + vertex 65.482 -26.6599 19.7746 + endloop + endfacet + facet normal 0.00171587 -0.279389 0.960177 + outer loop + vertex 22.4786 -27.5535 19.7744 + vertex 3.39386 -31.9867 18.5185 + vertex 24.7785 -31.8505 18.52 + endloop + endfacet + facet normal 0.00146527 -0.278392 0.960466 + outer loop + vertex 1.13233 -27.6708 19.773 + vertex 3.39386 -31.9867 18.5185 + vertex 22.4786 -27.5535 19.7744 + endloop + endfacet + facet normal 0.00127367 -0.243647 0.969863 + outer loop + vertex 21.2729 -23.4129 20.8162 + vertex 1.13233 -27.6708 19.773 + vertex 22.4786 -27.5535 19.7744 + endloop + endfacet + facet normal 0.00125354 -0.243557 0.969886 + outer loop + vertex -0.0816638 -23.5187 20.8172 + vertex 1.13233 -27.6708 19.773 + vertex 21.2729 -23.4129 20.8162 + endloop + endfacet + facet normal 0.00113609 -0.219811 0.975542 + outer loop + vertex 21.0749 -19.4402 21.7116 + vertex -0.0816638 -23.5187 20.8172 + vertex 21.2729 -23.4129 20.8162 + endloop + endfacet + facet normal 0.00329366 -0.219708 0.97556 + outer loop + vertex 21.0749 -19.4402 21.7116 + vertex 21.2729 -23.4129 20.8162 + vertex 42.5235 -19.1203 21.7112 + endloop + endfacet + facet normal 0.00317799 -0.211951 0.977275 + outer loop + vertex 42.8027 -15.2835 22.5424 + vertex 21.0749 -19.4402 21.7116 + vertex 42.5235 -19.1203 21.7112 + endloop + endfacet + facet normal 0.00320486 -0.212086 0.977246 + outer loop + vertex 21.3644 -15.6074 22.5424 + vertex 21.0749 -19.4402 21.7116 + vertex 42.8027 -15.2835 22.5424 + endloop + endfacet + facet normal 0.00327968 -0.217039 0.976157 + outer loop + vertex 43.0088 -11.5916 23.3626 + vertex 21.3644 -15.6074 22.5424 + vertex 42.8027 -15.2835 22.5424 + endloop + endfacet + facet normal 0.00558432 -0.217159 0.97612 + outer loop + vertex 43.0088 -11.5916 23.3626 + vertex 42.8027 -15.2835 22.5424 + vertex 64.5007 -11.0351 23.3634 + endloop + endfacet + facet normal 0.00579342 -0.225232 0.974288 + outer loop + vertex 64.4052 -7.55509 24.1685 + vertex 43.0088 -11.5916 23.3626 + vertex 64.5007 -11.0351 23.3634 + endloop + endfacet + facet normal 0.00577221 -0.225124 0.974313 + outer loop + vertex 42.9392 -8.11956 24.1652 + vertex 43.0088 -11.5916 23.3626 + vertex 64.4052 -7.55509 24.1685 + endloop + endfacet + facet normal 0.0058473 -0.227976 0.973649 + outer loop + vertex 64.1558 -4.40017 24.9087 + vertex 42.9392 -8.11956 24.1652 + vertex 64.4052 -7.55509 24.1685 + endloop + endfacet + facet normal 0.00827853 -0.22779 0.973675 + outer loop + vertex 64.1558 -4.40017 24.9087 + vertex 64.4052 -7.55509 24.1685 + vertex 85.5724 -3.58959 24.9162 + endloop + endfacet + facet normal 0.00813725 -0.224065 0.97454 + outer loop + vertex 85.3968 -0.852966 25.5469 + vertex 64.1558 -4.40017 24.9087 + vertex 85.5724 -3.58959 24.9162 + endloop + endfacet + facet normal 0.00812015 -0.223967 0.974563 + outer loop + vertex 64.0286 -1.67264 25.5366 + vertex 64.1558 -4.40017 24.9087 + vertex 85.3968 -0.852966 25.5469 + endloop + endfacet + facet normal 0.0077698 -0.214859 0.976614 + outer loop + vertex 85.475 1.34459 26.0297 + vertex 64.0286 -1.67264 25.5366 + vertex 85.3968 -0.852966 25.5469 + endloop + endfacet + facet normal 0.0100959 -0.214934 0.976576 + outer loop + vertex 85.475 1.34459 26.0297 + vertex 85.3968 -0.852966 25.5469 + vertex 106.764 2.42271 26.0469 + endloop + endfacet + facet normal 0.00955435 -0.204277 0.978867 + outer loop + vertex 106.819 3.96331 26.3679 + vertex 85.475 1.34459 26.0297 + vertex 106.764 2.42271 26.0469 + endloop + endfacet + facet normal 0.00946684 -0.203582 0.979012 + outer loop + vertex 85.5403 2.87241 26.3468 + vertex 85.475 1.34459 26.0297 + vertex 106.819 3.96331 26.3679 + endloop + endfacet + facet normal 0.00922464 -0.198877 0.979981 + outer loop + vertex 106.092 4.79266 26.5431 + vertex 85.5403 2.87241 26.3468 + vertex 106.819 3.96331 26.3679 + endloop + endfacet + facet normal 0.0111868 -0.197224 0.980295 + outer loop + vertex 106.092 4.79266 26.5431 + vertex 106.819 3.96331 26.3679 + vertex 127.565 6.14789 26.5707 + endloop + endfacet + facet normal 0.0127338 -0.221628 0.975048 + outer loop + vertex 125.033 6.38388 26.6574 + vertex 106.092 4.79266 26.5431 + vertex 127.565 6.14789 26.5707 + endloop + endfacet + facet normal 0.0112749 -0.204532 0.978795 + outer loop + vertex 103.113 5.02051 26.625 + vertex 106.092 4.79266 26.5431 + vertex 125.033 6.38388 26.6574 + endloop + endfacet + facet normal 0.0101173 -0.218581 0.975766 + outer loop + vertex 103.113 5.02051 26.625 + vertex 84.8639 3.70108 26.5186 + vertex 106.092 4.79266 26.5431 + endloop + endfacet + facet normal 0.00899706 -0.203353 0.979064 + outer loop + vertex 82.6393 4.00411 26.602 + vertex 84.8639 3.70108 26.5186 + vertex 103.113 5.02051 26.625 + endloop + endfacet + facet normal 0.00758416 -0.213155 0.976989 + outer loop + vertex 82.6393 4.00411 26.602 + vertex 63.7 2.85482 26.4983 + vertex 84.8639 3.70108 26.5186 + endloop + endfacet + facet normal 0.0068847 -0.19575 0.98063 + outer loop + vertex 63.7 2.85482 26.4983 + vertex 64.2642 2.02416 26.3285 + vertex 84.8639 3.70108 26.5186 + endloop + endfacet + facet normal 0.00703162 -0.197515 0.980275 + outer loop + vertex 84.8639 3.70108 26.5186 + vertex 64.2642 2.02416 26.3285 + vertex 85.5403 2.87241 26.3468 + endloop + endfacet + facet normal 0.00728038 -0.203727 0.979001 + outer loop + vertex 64.2642 2.02416 26.3285 + vertex 64.1491 0.504276 26.0131 + vertex 85.5403 2.87241 26.3468 + endloop + endfacet + facet normal 0.00516271 -0.203576 0.979046 + outer loop + vertex 64.2642 2.02416 26.3285 + vertex 42.7988 -0.0987656 26.0003 + vertex 64.1491 0.504276 26.0131 + endloop + endfacet + facet normal 0.00547088 -0.214437 0.976723 + outer loop + vertex 42.7988 -0.0987656 26.0003 + vertex 42.6442 -2.26064 25.5265 + vertex 64.1491 0.504276 26.0131 + endloop + endfacet + facet normal 0.00542872 -0.214121 0.976792 + outer loop + vertex 64.1491 0.504276 26.0131 + vertex 42.6442 -2.26064 25.5265 + vertex 64.0286 -1.67264 25.5366 + endloop + endfacet + facet normal 0.00569106 -0.223625 0.974659 + outer loop + vertex 42.6442 -2.26064 25.5265 + vertex 42.7282 -4.97128 24.9041 + vertex 64.0286 -1.67264 25.5366 + endloop + endfacet + facet normal 0.00341266 -0.223695 0.974653 + outer loop + vertex 42.6442 -2.26064 25.5265 + vertex 21.3606 -5.31665 24.8996 + vertex 42.7282 -4.97128 24.9041 + endloop + endfacet + facet normal 0.00348548 -0.228186 0.973611 + outer loop + vertex 21.3606 -5.31665 24.8996 + vertex 21.5383 -8.45648 24.1631 + vertex 42.7282 -4.97128 24.9041 + endloop + endfacet + facet normal 0.00349839 -0.228261 0.973594 + outer loop + vertex 42.7282 -4.97128 24.9041 + vertex 21.5383 -8.45648 24.1631 + vertex 42.9392 -8.11956 24.1652 + endloop + endfacet + facet normal 0.00344867 -0.225107 0.974328 + outer loop + vertex 21.5383 -8.45648 24.1631 + vertex 21.5879 -11.922 23.3623 + vertex 42.9392 -8.11956 24.1652 + endloop + endfacet + facet normal 0.00117396 -0.225139 0.974326 + outer loop + vertex 21.5383 -8.45648 24.1631 + vertex 0.25968 -12.0352 23.3618 + vertex 21.5879 -11.922 23.3623 + endloop + endfacet + facet normal 0.00113276 -0.217379 0.976087 + outer loop + vertex 0.25968 -12.0352 23.3618 + vertex 0.0253544 -15.7154 22.5425 + vertex 21.5879 -11.922 23.3623 + endloop + endfacet + facet normal 0.0011035 -0.21722 0.976122 + outer loop + vertex 21.5879 -11.922 23.3623 + vertex 0.0253544 -15.7154 22.5425 + vertex 21.3644 -15.6074 22.5424 + endloop + endfacet + facet normal 0.00107811 -0.212207 0.977224 + outer loop + vertex 0.0253544 -15.7154 22.5425 + vertex -0.26802 -19.5438 21.7115 + vertex 21.3644 -15.6074 22.5424 + endloop + endfacet + facet normal -0.00107422 -0.21205 0.977258 + outer loop + vertex 0.0253544 -15.7154 22.5425 + vertex -21.5686 -19.4358 21.7115 + vertex -0.26802 -19.5438 21.7115 + endloop + endfacet + facet normal -0.00111287 -0.219673 0.975573 + outer loop + vertex -21.5686 -19.4358 21.7115 + vertex -21.3697 -23.4126 20.8163 + vertex -0.26802 -19.5438 21.7115 + endloop + endfacet + facet normal -0.00113821 -0.219542 0.975602 + outer loop + vertex -0.26802 -19.5438 21.7115 + vertex -21.3697 -23.4126 20.8163 + vertex -0.0816638 -23.5187 20.8172 + endloop + endfacet + facet normal -0.00125459 -0.24293 0.970043 + outer loop + vertex -21.3697 -23.4126 20.8163 + vertex -20.1421 -27.5788 19.7745 + vertex -0.0816638 -23.5187 20.8172 + endloop + endfacet + facet normal -0.00356604 -0.243569 0.969877 + outer loop + vertex -21.3697 -23.4126 20.8163 + vertex -41.483 -27.2696 19.7737 + vertex -20.1421 -27.5788 19.7745 + endloop + endfacet + facet normal -0.00406 -0.277685 0.960664 + outer loop + vertex -41.483 -27.2696 19.7737 + vertex -39.0658 -31.6422 18.52 + vertex -20.1421 -27.5788 19.7745 + endloop + endfacet + facet normal -0.0036961 -0.27924 0.960214 + outer loop + vertex -20.1421 -27.5788 19.7745 + vertex -39.0658 -31.6422 18.52 + vertex -17.8405 -31.9212 18.5205 + endloop + endfacet + facet normal -0.00113369 -0.277989 0.960584 + outer loop + vertex -20.1421 -27.5788 19.7745 + vertex -17.8405 -31.9212 18.5205 + vertex 1.13233 -27.6708 19.773 + endloop + endfacet + facet normal -0.00665043 -0.279003 0.960267 + outer loop + vertex -41.483 -27.2696 19.7737 + vertex -60.6381 -31.129 18.5197 + vertex -39.0658 -31.6422 18.52 + endloop + endfacet + facet normal -0.00694024 -0.277688 0.960646 + outer loop + vertex -62.9653 -26.7332 19.7735 + vertex -60.6381 -31.129 18.5197 + vertex -41.483 -27.2696 19.7737 + endloop + endfacet + facet normal -0.00609939 -0.244009 0.969754 + outer loop + vertex -42.7312 -23.0906 20.8173 + vertex -62.9653 -26.7332 19.7735 + vertex -41.483 -27.2696 19.7737 + endloop + endfacet + facet normal -0.0062513 -0.243221 0.969951 + outer loop + vertex -64.1605 -22.5427 20.8166 + vertex -62.9653 -26.7332 19.7735 + vertex -42.7312 -23.0906 20.8173 + endloop + endfacet + facet normal -0.00564216 -0.21939 0.975621 + outer loop + vertex -42.9111 -19.112 21.711 + vertex -64.1605 -22.5427 20.8166 + vertex -42.7312 -23.0906 20.8173 + endloop + endfacet + facet normal -0.00335086 -0.219293 0.975653 + outer loop + vertex -42.9111 -19.112 21.711 + vertex -42.7312 -23.0906 20.8173 + vertex -21.5686 -19.4358 21.7115 + endloop + endfacet + facet normal -0.00324124 -0.212066 0.97725 + outer loop + vertex -21.2717 -15.6106 22.5426 + vertex -42.9111 -19.112 21.711 + vertex -21.5686 -19.4358 21.7115 + endloop + endfacet + facet normal -0.00318042 -0.212424 0.977173 + outer loop + vertex -42.6068 -15.2902 22.5428 + vertex -42.9111 -19.112 21.711 + vertex -21.2717 -15.6106 22.5426 + endloop + endfacet + facet normal -0.00325322 -0.217271 0.976106 + outer loop + vertex -21.0265 -11.933 23.362 + vertex -42.6068 -15.2902 22.5428 + vertex -21.2717 -15.6106 22.5426 + endloop + endfacet + facet normal -0.00103725 -0.217412 0.976079 + outer loop + vertex -21.0265 -11.933 23.362 + vertex -21.2717 -15.6106 22.5426 + vertex 0.25968 -12.0352 23.3618 + endloop + endfacet + facet normal -0.00107537 -0.225355 0.974276 + outer loop + vertex 0.233556 -8.57208 24.1628 + vertex -21.0265 -11.933 23.362 + vertex 0.25968 -12.0352 23.3618 + endloop + endfacet + facet normal -0.0010794 -0.225331 0.974282 + outer loop + vertex -21.0297 -8.47059 24.1627 + vertex -21.0265 -11.933 23.362 + vertex 0.233556 -8.57208 24.1628 + endloop + endfacet + facet normal -0.00109458 -0.228511 0.973541 + outer loop + vertex 0.081302 -5.43393 24.8993 + vertex -21.0297 -8.47059 24.1627 + vertex 0.233556 -8.57208 24.1628 + endloop + endfacet + facet normal 0.00124068 -0.228403 0.973566 + outer loop + vertex 0.081302 -5.43393 24.8993 + vertex 0.233556 -8.57208 24.1628 + vertex 21.3606 -5.31665 24.8996 + endloop + endfacet + facet normal 0.00121724 -0.224153 0.974553 + outer loop + vertex 21.3071 -2.61323 25.5215 + vertex 0.081302 -5.43393 24.8993 + vertex 21.3606 -5.31665 24.8996 + endloop + endfacet + facet normal 0.00115985 -0.223742 0.974648 + outer loop + vertex 0.0698512 -2.74072 25.5175 + vertex 0.081302 -5.43393 24.8993 + vertex 21.3071 -2.61323 25.5215 + endloop + endfacet + facet normal 0.00110344 -0.214412 0.976743 + outer loop + vertex 21.4991 -0.463146 25.9933 + vertex 0.0698512 -2.74072 25.5175 + vertex 21.3071 -2.61323 25.5215 + endloop + endfacet + facet normal 0.0033501 -0.214602 0.976696 + outer loop + vertex 21.4991 -0.463146 25.9933 + vertex 21.3071 -2.61323 25.5215 + vertex 42.7988 -0.0987656 26.0003 + endloop + endfacet + facet normal 0.00316383 -0.203759 0.979016 + outer loop + vertex 42.9427 1.40868 26.3136 + vertex 21.4991 -0.463146 25.9933 + vertex 42.7988 -0.0987656 26.0003 + endloop + endfacet + facet normal 0.00317021 -0.203829 0.979001 + outer loop + vertex 21.6861 1.03099 26.3038 + vertex 21.4991 -0.463146 25.9933 + vertex 42.9427 1.40868 26.3136 + endloop + endfacet + facet normal 0.00306035 -0.197679 0.980262 + outer loop + vertex 42.3511 2.23805 26.4827 + vertex 21.6861 1.03099 26.3038 + vertex 42.9427 1.40868 26.3136 + endloop + endfacet + facet normal 0.00495518 -0.196379 0.980516 + outer loop + vertex 42.3511 2.23805 26.4827 + vertex 42.9427 1.40868 26.3136 + vertex 63.7 2.85482 26.4983 + endloop + endfacet + facet normal 0.00556416 -0.217346 0.976079 + outer loop + vertex 61.3081 3.16554 26.5811 + vertex 42.3511 2.23805 26.4827 + vertex 63.7 2.85482 26.4983 + endloop + endfacet + facet normal 0.00496639 -0.205403 0.978665 + outer loop + vertex 39.8504 2.56187 26.5633 + vertex 42.3511 2.23805 26.4827 + vertex 61.3081 3.16554 26.5811 + endloop + endfacet + facet normal 0.00337055 -0.217099 0.976144 + outer loop + vertex 39.8504 2.56187 26.5633 + vertex 21.1955 1.86294 26.4723 + vertex 42.3511 2.23805 26.4827 + endloop + endfacet + facet normal 0.00292515 -0.205537 0.978645 + outer loop + vertex 19.0324 2.21475 26.5526 + vertex 21.1955 1.86294 26.4723 + vertex 39.8504 2.56187 26.5633 + endloop + endfacet + facet normal 0.00113783 -0.216011 0.97639 + outer loop + vertex 19.0324 2.21475 26.5526 + vertex 0.192054 1.73646 26.4688 + vertex 21.1955 1.86294 26.4723 + endloop + endfacet + facet normal 0.00101921 -0.196427 0.980518 + outer loop + vertex 0.192054 1.73646 26.4688 + vertex 0.575074 0.898996 26.3006 + vertex 21.1955 1.86294 26.4723 + endloop + endfacet + facet normal 0.00109115 -0.197912 0.980219 + outer loop + vertex 21.1955 1.86294 26.4723 + vertex 0.575074 0.898996 26.3006 + vertex 21.6861 1.03099 26.3038 + endloop + endfacet + facet normal 0.00113087 -0.204234 0.978921 + outer loop + vertex 0.575074 0.898996 26.3006 + vertex 0.310767 -0.596288 25.9889 + vertex 21.6861 1.03099 26.3038 + endloop + endfacet + facet normal -0.000946969 -0.203882 0.978995 + outer loop + vertex 0.575074 0.898996 26.3006 + vertex -20.8204 -0.484604 25.9918 + vertex 0.310767 -0.596288 25.9889 + endloop + endfacet + facet normal -0.00100409 -0.214632 0.976695 + outer loop + vertex -20.8204 -0.484604 25.9918 + vertex -21.1179 -2.631 25.5198 + vertex 0.310767 -0.596288 25.9889 + endloop + endfacet + facet normal -0.00100708 -0.214602 0.976701 + outer loop + vertex 0.310767 -0.596288 25.9889 + vertex -21.1179 -2.631 25.5198 + vertex 0.0698512 -2.74072 25.5175 + endloop + endfacet + facet normal -0.00105647 -0.224095 0.974567 + outer loop + vertex -21.1179 -2.631 25.5198 + vertex -21.1469 -5.33132 24.8988 + vertex 0.0698512 -2.74072 25.5175 + endloop + endfacet + facet normal -0.00338911 -0.22407 0.974567 + outer loop + vertex -21.1179 -2.631 25.5198 + vertex -42.4111 -4.99947 24.9012 + vertex -21.1469 -5.33132 24.8988 + endloop + endfacet + facet normal -0.00345062 -0.228005 0.973654 + outer loop + vertex -42.4111 -4.99947 24.9012 + vertex -42.3279 -8.14488 24.1649 + vertex -21.1469 -5.33132 24.8988 + endloop + endfacet + facet normal -0.00339453 -0.228403 0.973561 + outer loop + vertex -21.1469 -5.33132 24.8988 + vertex -42.3279 -8.14488 24.1649 + vertex -21.0297 -8.47059 24.1627 + endloop + endfacet + facet normal -0.00334785 -0.225356 0.974271 + outer loop + vertex -42.3279 -8.14488 24.1649 + vertex -42.348 -11.613 23.3626 + vertex -21.0297 -8.47059 24.1627 + endloop + endfacet + facet normal -0.00573002 -0.22534 0.974263 + outer loop + vertex -42.3279 -8.14488 24.1649 + vertex -63.7433 -11.0647 23.3636 + vertex -42.348 -11.613 23.3626 + endloop + endfacet + facet normal -0.00552632 -0.217395 0.976068 + outer loop + vertex -63.7433 -11.0647 23.3636 + vertex -64.0201 -14.7423 22.543 + vertex -42.348 -11.613 23.3626 + endloop + endfacet + facet normal -0.00554998 -0.21724 0.976102 + outer loop + vertex -42.348 -11.613 23.3626 + vertex -64.0201 -14.7423 22.543 + vertex -42.6068 -15.2902 22.5428 + endloop + endfacet + facet normal -0.00542665 -0.21242 0.977163 + outer loop + vertex -64.0201 -14.7423 22.543 + vertex -64.3299 -18.5623 21.7108 + vertex -42.6068 -15.2902 22.5428 + endloop + endfacet + facet normal -0.00780138 -0.212233 0.977188 + outer loop + vertex -64.0201 -14.7423 22.543 + vertex -85.7924 -17.7721 21.7111 + vertex -64.3299 -18.5623 21.7108 + endloop + endfacet + facet normal -0.00807368 -0.219628 0.97555 + outer loop + vertex -85.7924 -17.7721 21.7111 + vertex -85.613 -21.7555 20.8158 + vertex -64.3299 -18.5623 21.7108 + endloop + endfacet + facet normal -0.00809244 -0.219511 0.975577 + outer loop + vertex -64.3299 -18.5623 21.7108 + vertex -85.613 -21.7555 20.8158 + vertex -64.1605 -22.5427 20.8166 + endloop + endfacet + facet normal -0.00895943 -0.243144 0.969949 + outer loop + vertex -85.613 -21.7555 20.8158 + vertex -84.428 -25.9608 19.7726 + vertex -64.1605 -22.5427 20.8166 + endloop + endfacet + facet normal -0.0115945 -0.243836 0.969747 + outer loop + vertex -85.613 -21.7555 20.8158 + vertex -105.854 -24.9364 19.774 + vertex -84.428 -25.9608 19.7726 + endloop + endfacet + facet normal -0.0132097 -0.277607 0.960604 + outer loop + vertex -105.854 -24.9364 19.774 + vertex -103.551 -29.3903 18.5185 + vertex -84.428 -25.9608 19.7726 + endloop + endfacet + facet normal -0.0129977 -0.278677 0.960297 + outer loop + vertex -84.428 -25.9608 19.7726 + vertex -103.551 -29.3903 18.5185 + vertex -82.2434 -30.3803 18.5196 + endloop + endfacet + facet normal -0.0100233 -0.277327 0.960723 + outer loop + vertex -84.428 -25.9608 19.7726 + vertex -82.2434 -30.3803 18.5196 + vertex -62.9653 -26.7332 19.7735 + endloop + endfacet + facet normal -0.0164217 -0.27913 0.960113 + outer loop + vertex -105.854 -24.9364 19.774 + vertex -124.946 -28.1297 18.519 + vertex -103.551 -29.3903 18.5185 + endloop + endfacet + facet normal -0.0167468 -0.277383 0.960614 + outer loop + vertex -127.296 -23.6468 19.7725 + vertex -124.946 -28.1297 18.519 + vertex -105.854 -24.9364 19.774 + endloop + endfacet + facet normal -0.0147197 -0.243669 0.969747 + outer loop + vertex -107.072 -20.7147 20.8163 + vertex -127.296 -23.6468 19.7725 + vertex -105.854 -24.9364 19.774 + endloop + endfacet + facet normal -0.0147736 -0.243327 0.969832 + outer loop + vertex -128.523 -19.4103 20.8168 + vertex -127.296 -23.6468 19.7725 + vertex -107.072 -20.7147 20.8163 + endloop + endfacet + facet normal -0.0133317 -0.219615 0.975496 + outer loop + vertex -107.255 -16.7279 21.7113 + vertex -128.523 -19.4103 20.8168 + vertex -107.072 -20.7147 20.8163 + endloop + endfacet + facet normal -0.0106691 -0.219506 0.975553 + outer loop + vertex -107.255 -16.7279 21.7113 + vertex -107.072 -20.7147 20.8163 + vertex -85.7924 -17.7721 21.7111 + endloop + endfacet + facet normal -0.0103091 -0.212107 0.977192 + outer loop + vertex -85.4754 -13.9538 22.5432 + vertex -107.255 -16.7279 21.7113 + vertex -85.7924 -17.7721 21.7111 + endloop + endfacet + facet normal -0.0103067 -0.212125 0.977188 + outer loop + vertex -106.93 -12.9101 22.5435 + vertex -107.255 -16.7279 21.7113 + vertex -85.4754 -13.9538 22.5432 + endloop + endfacet + facet normal -0.0105493 -0.217112 0.97609 + outer loop + vertex -85.1849 -10.2747 23.3647 + vertex -106.93 -12.9101 22.5435 + vertex -85.4754 -13.9538 22.5432 + endloop + endfacet + facet normal -0.00795657 -0.217312 0.97607 + outer loop + vertex -85.1849 -10.2747 23.3647 + vertex -85.4754 -13.9538 22.5432 + vertex -63.7433 -11.0647 23.3636 + endloop + endfacet + facet normal -0.00824328 -0.225092 0.974303 + outer loop + vertex -63.6992 -7.59088 24.1665 + vertex -85.1849 -10.2747 23.3647 + vertex -63.7433 -11.0647 23.3636 + endloop + endfacet + facet normal -0.00824617 -0.22507 0.974308 + outer loop + vertex -85.1146 -6.79335 24.1695 + vertex -85.1849 -10.2747 23.3647 + vertex -63.6992 -7.59088 24.1665 + endloop + endfacet + facet normal -0.00835477 -0.227984 0.973629 + outer loop + vertex -63.7436 -4.43294 24.9056 + vertex -85.1146 -6.79335 24.1695 + vertex -63.6992 -7.59088 24.1665 + endloop + endfacet + facet normal -0.0058514 -0.227954 0.973654 + outer loop + vertex -63.7436 -4.43294 24.9056 + vertex -63.6992 -7.59088 24.1665 + vertex -42.4111 -4.99947 24.9012 + endloop + endfacet + facet normal -0.00573992 -0.223764 0.974627 + outer loop + vertex -42.3337 -2.29166 25.5233 + vertex -63.7436 -4.43294 24.9056 + vertex -42.4111 -4.99947 24.9012 + endloop + endfacet + facet normal -0.00571452 -0.224002 0.974572 + outer loop + vertex -63.6267 -1.70836 25.5325 + vertex -63.7436 -4.43294 24.9056 + vertex -42.3337 -2.29166 25.5233 + endloop + endfacet + facet normal -0.00544762 -0.214294 0.976754 + outer loop + vertex -41.995 -0.136037 25.9981 + vertex -63.6267 -1.70836 25.5325 + vertex -42.3337 -2.29166 25.5233 + endloop + endfacet + facet normal -0.00323907 -0.214627 0.976691 + outer loop + vertex -41.995 -0.136037 25.9981 + vertex -42.3337 -2.29166 25.5233 + vertex -20.8204 -0.484604 25.9918 + endloop + endfacet + facet normal -0.00305334 -0.203388 0.979093 + outer loop + vertex -20.5192 1.01137 26.3035 + vertex -41.995 -0.136037 25.9981 + vertex -20.8204 -0.484604 25.9918 + endloop + endfacet + facet normal -0.00305378 -0.20338 0.979095 + outer loop + vertex -41.6982 1.36251 26.3103 + vertex -41.995 -0.136037 25.9981 + vertex -20.5192 1.01137 26.3035 + endloop + endfacet + facet normal -0.00294397 -0.196783 0.980443 + outer loop + vertex -21.015 1.85801 26.4719 + vertex -41.6982 1.36251 26.3103 + vertex -20.5192 1.01137 26.3035 + endloop + endfacet + facet normal -0.000976709 -0.195676 0.980668 + outer loop + vertex -21.015 1.85801 26.4719 + vertex -20.5192 1.01137 26.3035 + vertex 0.192054 1.73646 26.4688 + endloop + endfacet + facet normal -0.00108951 -0.215251 0.976558 + outer loop + vertex -1.9402 2.11842 26.5506 + vertex -21.015 1.85801 26.4719 + vertex 0.192054 1.73646 26.4688 + endloop + endfacet + facet normal -0.00123433 -0.20529 0.9787 + outer loop + vertex -23.6617 2.26628 26.5542 + vertex -21.015 1.85801 26.4719 + vertex -1.9402 2.11842 26.5506 + endloop + endfacet + facet normal -0.00332021 -0.218245 0.975888 + outer loop + vertex -23.6617 2.26628 26.5542 + vertex -42.2017 2.22756 26.4825 + vertex -21.015 1.85801 26.4719 + endloop + endfacet + facet normal -0.00335742 -0.205532 0.978645 + outer loop + vertex -44.4742 2.66701 26.567 + vertex -42.2017 2.22756 26.4825 + vertex -23.6617 2.26628 26.5542 + endloop + endfacet + facet normal -0.00552468 -0.216291 0.976313 + outer loop + vertex -44.4742 2.66701 26.567 + vertex -63.293 2.83606 26.4979 + vertex -42.2017 2.22756 26.4825 + endloop + endfacet + facet normal -0.00494759 -0.196395 0.980512 + outer loop + vertex -63.293 2.83606 26.4979 + vertex -62.9184 1.96435 26.3252 + vertex -42.2017 2.22756 26.4825 + endloop + endfacet + facet normal -0.00492617 -0.1979 0.98021 + outer loop + vertex -42.2017 2.22756 26.4825 + vertex -62.9184 1.96435 26.3252 + vertex -41.6982 1.36251 26.3103 + endloop + endfacet + facet normal -0.00510457 -0.204159 0.978925 + outer loop + vertex -62.9184 1.96435 26.3252 + vertex -63.2556 0.451242 26.0079 + vertex -41.6982 1.36251 26.3103 + endloop + endfacet + facet normal -0.00731602 -0.203684 0.979009 + outer loop + vertex -62.9184 1.96435 26.3252 + vertex -84.5707 1.28461 26.022 + vertex -63.2556 0.451242 26.0079 + endloop + endfacet + facet normal -0.00773836 -0.214447 0.976705 + outer loop + vertex -84.5707 1.28461 26.022 + vertex -84.9713 -0.885997 25.5422 + vertex -63.2556 0.451242 26.0079 + endloop + endfacet + facet normal -0.00778904 -0.213682 0.976872 + outer loop + vertex -63.2556 0.451242 26.0079 + vertex -84.9713 -0.885997 25.5422 + vertex -63.6267 -1.70836 25.5325 + endloop + endfacet + facet normal -0.00818048 -0.223815 0.974597 + outer loop + vertex -84.9713 -0.885997 25.5422 + vertex -85.125 -3.62102 24.9128 + vertex -63.6267 -1.70836 25.5325 + endloop + endfacet + facet normal -0.0107953 -0.22367 0.974605 + outer loop + vertex -84.9713 -0.885997 25.5422 + vertex -106.513 -2.56031 24.9194 + vertex -85.125 -3.62102 24.9128 + endloop + endfacet + facet normal -0.0110112 -0.228018 0.973595 + outer loop + vertex -106.513 -2.56031 24.9194 + vertex -106.532 -5.74103 24.1742 + vertex -85.125 -3.62102 24.9128 + endloop + endfacet + facet normal -0.0109964 -0.228157 0.973562 + outer loop + vertex -85.125 -3.62102 24.9128 + vertex -106.532 -5.74103 24.1742 + vertex -85.1146 -6.79335 24.1695 + endloop + endfacet + facet normal -0.010858 -0.225344 0.974219 + outer loop + vertex -106.532 -5.74103 24.1742 + vertex -106.626 -9.23009 23.3661 + vertex -85.1146 -6.79335 24.1695 + endloop + endfacet + facet normal -0.0136511 -0.225265 0.974202 + outer loop + vertex -106.532 -5.74103 24.1742 + vertex -128.044 -7.92509 23.3678 + vertex -106.626 -9.23009 23.3661 + endloop + endfacet + facet normal -0.013173 -0.217421 0.975989 + outer loop + vertex -128.044 -7.92509 23.3678 + vertex -128.362 -11.6051 22.5437 + vertex -106.626 -9.23009 23.3661 + endloop + endfacet + facet normal -0.0132112 -0.217095 0.976061 + outer loop + vertex -106.626 -9.23009 23.3661 + vertex -128.362 -11.6051 22.5437 + vertex -106.93 -12.9101 22.5435 + endloop + endfacet + facet normal -0.0129028 -0.21203 0.977178 + outer loop + vertex -128.362 -11.6051 22.5437 + vertex -128.697 -15.4207 21.7113 + vertex -106.93 -12.9101 22.5435 + endloop + endfacet + facet normal -0.0155681 -0.211798 0.977189 + outer loop + vertex -128.362 -11.6051 22.5437 + vertex -150.105 -13.8517 21.7103 + vertex -128.697 -15.4207 21.7113 + endloop + endfacet + facet normal -0.0161034 -0.219103 0.975569 + outer loop + vertex -150.105 -13.8517 21.7103 + vertex -149.949 -17.8441 20.8163 + vertex -128.697 -15.4207 21.7113 + endloop + endfacet + facet normal -0.0160629 -0.219431 0.975496 + outer loop + vertex -128.697 -15.4207 21.7113 + vertex -149.949 -17.8441 20.8163 + vertex -128.523 -19.4103 20.8168 + endloop + endfacet + facet normal -0.0177715 -0.242806 0.969912 + outer loop + vertex -149.949 -17.8441 20.8163 + vertex -148.755 -22.0944 19.7741 + vertex -128.523 -19.4103 20.8168 + endloop + endfacet + facet normal -0.0205622 -0.243532 0.969675 + outer loop + vertex -149.949 -17.8441 20.8163 + vertex -170.16 -20.2898 19.7735 + vertex -148.755 -22.0944 19.7741 + endloop + endfacet + facet normal -0.0233955 -0.277141 0.960544 + outer loop + vertex -170.16 -20.2898 19.7735 + vertex -167.893 -24.8236 18.5206 + vertex -148.755 -22.0944 19.7741 + endloop + endfacet + facet normal -0.0230366 -0.279365 0.959909 + outer loop + vertex -148.755 -22.0944 19.7741 + vertex -167.893 -24.8236 18.5206 + vertex -146.476 -26.5988 18.5179 + endloop + endfacet + facet normal -0.0200383 -0.277979 0.960378 + outer loop + vertex -148.755 -22.0944 19.7741 + vertex -146.476 -26.5988 18.5179 + vertex -127.296 -23.6468 19.7725 + endloop + endfacet + facet normal -0.0263811 -0.278503 0.960073 + outer loop + vertex -170.16 -20.2898 19.7735 + vertex -189.293 -22.7984 18.52 + vertex -167.893 -24.8236 18.5206 + endloop + endfacet + facet normal -0.0265523 -0.27736 0.960399 + outer loop + vertex -191.481 -18.2494 19.7732 + vertex -189.293 -22.7984 18.52 + vertex -170.16 -20.2898 19.7735 + endloop + endfacet + facet normal -0.0232995 -0.243369 0.969654 + outer loop + vertex -171.324 -16.0274 20.8153 + vertex -191.481 -18.2494 19.7732 + vertex -170.16 -20.2898 19.7735 + endloop + endfacet + facet normal -0.0233521 -0.242941 0.96976 + outer loop + vertex -192.613 -13.9772 20.8162 + vertex -191.481 -18.2494 19.7732 + vertex -171.324 -16.0274 20.8153 + endloop + endfacet + facet normal -0.0210875 -0.219428 0.975401 + outer loop + vertex -171.467 -12.0344 21.7105 + vertex -192.613 -13.9772 20.8162 + vertex -171.324 -16.0274 20.8153 + endloop + endfacet + facet normal -0.0186553 -0.219355 0.975467 + outer loop + vertex -171.467 -12.0344 21.7105 + vertex -171.324 -16.0274 20.8153 + vertex -150.105 -13.8517 21.7103 + endloop + endfacet + facet normal -0.018036 -0.212076 0.977087 + outer loop + vertex -149.764 -10.0403 22.5439 + vertex -171.467 -12.0344 21.7105 + vertex -150.105 -13.8517 21.7103 + endloop + endfacet + facet normal -0.0180201 -0.212234 0.977053 + outer loop + vertex -171.108 -8.22719 22.5441 + vertex -171.467 -12.0344 21.7105 + vertex -149.764 -10.0403 22.5439 + endloop + endfacet + facet normal -0.0184473 -0.217264 0.975939 + outer loop + vertex -149.435 -6.36087 23.3692 + vertex -171.108 -8.22719 22.5441 + vertex -149.764 -10.0403 22.5439 + endloop + endfacet + facet normal -0.0158373 -0.217496 0.975933 + outer loop + vertex -149.435 -6.36087 23.3692 + vertex -149.764 -10.0403 22.5439 + vertex -128.044 -7.92509 23.3678 + endloop + endfacet + facet normal -0.0164124 -0.225357 0.974138 + outer loop + vertex -127.933 -4.43164 24.1778 + vertex -149.435 -6.36087 23.3692 + vertex -128.044 -7.92509 23.3678 + endloop + endfacet + facet normal -0.0163538 -0.225953 0.974001 + outer loop + vertex -149.304 -2.86615 24.1822 + vertex -149.435 -6.36087 23.3692 + vertex -127.933 -4.43164 24.1778 + endloop + endfacet + facet normal -0.0165664 -0.228854 0.97332 + outer loop + vertex -127.893 -1.24027 24.9289 + vertex -149.304 -2.86615 24.1822 + vertex -127.933 -4.43164 24.1778 + endloop + endfacet + facet normal -0.0137 -0.228898 0.973354 + outer loop + vertex -127.893 -1.24027 24.9289 + vertex -127.933 -4.43164 24.1778 + vertex -106.513 -2.56031 24.9194 + endloop + endfacet + facet normal -0.0134153 -0.224295 0.974429 + outer loop + vertex -106.333 0.186549 25.5541 + vertex -127.893 -1.24027 24.9289 + vertex -106.513 -2.56031 24.9194 + endloop + endfacet + facet normal -0.0133543 -0.225133 0.974236 + outer loop + vertex -127.69 1.51247 25.5678 + vertex -127.893 -1.24027 24.9289 + vertex -106.333 0.186549 25.5541 + endloop + endfacet + facet normal -0.0127421 -0.215297 0.976466 + outer loop + vertex -105.913 2.3713 26.0413 + vertex -127.69 1.51247 25.5678 + vertex -106.333 0.186549 25.5541 + endloop + endfacet + facet normal -0.0101031 -0.215788 0.976388 + outer loop + vertex -105.913 2.3713 26.0413 + vertex -106.333 0.186549 25.5541 + vertex -84.5707 1.28461 26.022 + endloop + endfacet + facet normal -0.00953602 -0.204692 0.97878 + outer loop + vertex -84.1947 2.81011 26.3447 + vertex -105.913 2.3713 26.0413 + vertex -84.5707 1.28461 26.022 + endloop + endfacet + facet normal -0.00951042 -0.205799 0.978548 + outer loop + vertex -105.532 3.89466 26.3654 + vertex -105.913 2.3713 26.0413 + vertex -84.1947 2.81011 26.3447 + endloop + endfacet + facet normal -0.00908857 -0.197533 0.980254 + outer loop + vertex -84.6192 3.6923 26.5185 + vertex -105.532 3.89466 26.3654 + vertex -84.1947 2.81011 26.3447 + endloop + endfacet + facet normal -0.00694457 -0.196544 0.980471 + outer loop + vertex -84.6192 3.6923 26.5185 + vertex -84.1947 2.81011 26.3447 + vertex -63.293 2.83606 26.4979 + endloop + endfacet + facet normal -0.00768981 -0.215012 0.976581 + outer loop + vertex -65.0777 3.2961 26.5852 + vertex -84.6192 3.6923 26.5185 + vertex -63.293 2.83606 26.4979 + endloop + endfacet + facet normal -0.00747586 -0.204064 0.978929 + outer loop + vertex -87.2904 4.21883 26.6079 + vertex -84.6192 3.6923 26.5185 + vertex -65.0777 3.2961 26.5852 + endloop + endfacet + facet normal -0.00999836 -0.216407 0.976252 + outer loop + vertex -87.2904 4.21883 26.6079 + vertex -105.881 4.78529 26.543 + vertex -84.6192 3.6923 26.5185 + endloop + endfacet + facet normal -0.00972889 -0.207338 0.978221 + outer loop + vertex -107.677 5.28976 26.6321 + vertex -105.881 4.78529 26.543 + vertex -87.2904 4.21883 26.6079 + endloop + endfacet + facet normal -0.01235 -0.216322 0.976244 + outer loop + vertex -107.677 5.28976 26.6321 + vertex -126.977 6.11401 26.5706 + vertex -105.881 4.78529 26.543 + endloop + endfacet + facet normal -0.011442 -0.201971 0.979325 + outer loop + vertex -126.977 6.11401 26.5706 + vertex -126.808 5.22223 26.3887 + vertex -105.881 4.78529 26.543 + endloop + endfacet + facet normal -0.0114018 -0.199893 0.979751 + outer loop + vertex -105.881 4.78529 26.543 + vertex -126.808 5.22223 26.3887 + vertex -105.532 3.89466 26.3654 + endloop + endfacet + facet normal -0.0118903 -0.207693 0.978122 + outer loop + vertex -126.808 5.22223 26.3887 + vertex -127.246 3.69954 26.06 + vertex -105.532 3.89466 26.3654 + endloop + endfacet + facet normal -0.0143088 -0.20702 0.978232 + outer loop + vertex -126.808 5.22223 26.3887 + vertex -148.555 5.2803 26.0828 + vertex -127.246 3.69954 26.06 + endloop + endfacet + facet normal -0.0152071 -0.219092 0.975586 + outer loop + vertex -148.555 5.2803 26.0828 + vertex -149.028 3.08956 25.5835 + vertex -127.246 3.69954 26.06 + endloop + endfacet + facet normal -0.0152895 -0.216588 0.976143 + outer loop + vertex -127.246 3.69954 26.06 + vertex -149.028 3.08956 25.5835 + vertex -127.69 1.51247 25.5678 + endloop + endfacet + facet normal -0.0160345 -0.226646 0.973845 + outer loop + vertex -149.028 3.08956 25.5835 + vertex -149.247 0.330234 24.9377 + vertex -127.69 1.51247 25.5678 + endloop + endfacet + facet normal -0.0188564 -0.226423 0.973847 + outer loop + vertex -149.028 3.08956 25.5835 + vertex -170.547 2.14271 24.9467 + vertex -149.247 0.330234 24.9377 + endloop + endfacet + facet normal -0.0192111 -0.230587 0.972862 + outer loop + vertex -170.547 2.14271 24.9467 + vertex -170.616 -1.05608 24.1871 + vertex -149.247 0.330234 24.9377 + endloop + endfacet + facet normal -0.0192784 -0.229665 0.973079 + outer loop + vertex -149.247 0.330234 24.9377 + vertex -170.616 -1.05608 24.1871 + vertex -149.304 -2.86615 24.1822 + endloop + endfacet + facet normal -0.0190127 -0.226538 0.973817 + outer loop + vertex -170.616 -1.05608 24.1871 + vertex -170.76 -4.55268 23.3709 + vertex -149.304 -2.86615 24.1822 + endloop + endfacet + facet normal -0.0217201 -0.22642 0.973788 + outer loop + vertex -170.616 -1.05608 24.1871 + vertex -191.999 -2.50903 23.3724 + vertex -170.76 -4.55268 23.3709 + endloop + endfacet + facet normal -0.0209118 -0.21802 0.97572 + outer loop + vertex -191.999 -2.50903 23.3724 + vertex -192.358 -6.18079 22.5442 + vertex -170.76 -4.55268 23.3709 + endloop + endfacet + facet normal -0.0209478 -0.217591 0.975815 + outer loop + vertex -170.76 -4.55268 23.3709 + vertex -192.358 -6.18079 22.5442 + vertex -171.108 -8.22719 22.5441 + endloop + endfacet + facet normal -0.0204188 -0.212098 0.977035 + outer loop + vertex -192.358 -6.18079 22.5442 + vertex -192.735 -9.98418 21.7107 + vertex -171.108 -8.22719 22.5441 + endloop + endfacet + facet normal -0.022825 -0.211859 0.977034 + outer loop + vertex -192.358 -6.18079 22.5442 + vertex -213.923 -7.70362 21.7102 + vertex -192.735 -9.98418 21.7107 + endloop + endfacet + facet normal -0.0235987 -0.219047 0.975429 + outer loop + vertex -213.923 -7.70362 21.7102 + vertex -213.798 -11.701 20.8156 + vertex -192.735 -9.98418 21.7107 + endloop + endfacet + facet normal -0.0235838 -0.219211 0.975392 + outer loop + vertex -192.735 -9.98418 21.7107 + vertex -213.798 -11.701 20.8156 + vertex -192.613 -13.9772 20.8162 + endloop + endfacet + facet normal -0.0261002 -0.242632 0.969767 + outer loop + vertex -213.798 -11.701 20.8156 + vertex -212.655 -15.9898 19.7733 + vertex -192.613 -13.9772 20.8162 + endloop + endfacet + facet normal -0.0286642 -0.243259 0.969538 + outer loop + vertex -213.798 -11.701 20.8156 + vertex -233.822 -13.4983 19.7726 + vertex -212.655 -15.9898 19.7733 + endloop + endfacet + facet normal -0.0326008 -0.276705 0.960402 + outer loop + vertex -233.822 -13.4983 19.7726 + vertex -231.521 -18.115 18.5206 + vertex -212.655 -15.9898 19.7733 + endloop + endfacet + facet normal -0.0323137 -0.278888 0.95978 + outer loop + vertex -212.655 -15.9898 19.7733 + vertex -231.521 -18.115 18.5206 + vertex -210.507 -20.5585 18.5181 + endloop + endfacet + facet normal -0.0296373 -0.277744 0.960198 + outer loop + vertex -212.655 -15.9898 19.7733 + vertex -210.507 -20.5585 18.5181 + vertex -191.481 -18.2494 19.7732 + endloop + endfacet + facet normal -0.0354631 -0.278003 0.959925 + outer loop + vertex -233.822 -13.4983 19.7726 + vertex -252.84 -15.4014 18.5189 + vertex -231.521 -18.115 18.5206 + endloop + endfacet + facet normal -0.0355355 -0.277393 0.960099 + outer loop + vertex -255.173 -10.7565 19.7746 + vertex -252.84 -15.4014 18.5189 + vertex -233.822 -13.4983 19.7726 + endloop + endfacet + facet normal -0.0311362 -0.243142 0.969491 + outer loop + vertex -235.007 -9.18877 20.8154 + vertex -255.173 -10.7565 19.7746 + vertex -233.822 -13.4983 19.7726 + endloop + endfacet + facet normal -0.0312668 -0.241699 0.969847 + outer loop + vertex -256.307 -6.439 20.814 + vertex -255.173 -10.7565 19.7746 + vertex -235.007 -9.18877 20.8154 + endloop + endfacet + facet normal -0.0283189 -0.218861 0.975345 + outer loop + vertex -235.132 -5.18722 21.7097 + vertex -256.307 -6.439 20.814 + vertex -235.007 -9.18877 20.8154 + endloop + endfacet + facet normal -0.0259867 -0.218805 0.975423 + outer loop + vertex -235.132 -5.18722 21.7097 + vertex -235.007 -9.18877 20.8154 + vertex -213.923 -7.70362 21.7102 + endloop + endfacet + facet normal -0.0251637 -0.211869 0.976974 + outer loop + vertex -213.542 -3.903 22.5442 + vertex -235.132 -5.18722 21.7097 + vertex -213.923 -7.70362 21.7102 + endloop + endfacet + facet normal -0.0251492 -0.212082 0.976928 + outer loop + vertex -234.75 -1.38851 22.5442 + vertex -235.132 -5.18722 21.7097 + vertex -213.542 -3.903 22.5442 + endloop + endfacet + facet normal -0.0258453 -0.217953 0.975617 + outer loop + vertex -213.177 -0.233837 23.3736 + vertex -234.75 -1.38851 22.5442 + vertex -213.542 -3.903 22.5442 + endloop + endfacet + facet normal -0.023384 -0.2182 0.975624 + outer loop + vertex -213.177 -0.233837 23.3736 + vertex -213.542 -3.903 22.5442 + vertex -191.999 -2.50903 23.3724 + endloop + endfacet + facet normal -0.0243257 -0.226965 0.973599 + outer loop + vertex -191.845 0.987371 24.1913 + vertex -213.177 -0.233837 23.3736 + vertex -191.999 -2.50903 23.3724 + endloop + endfacet + facet normal -0.0242905 -0.227497 0.973476 + outer loop + vertex -213.021 3.26422 24.195 + vertex -213.177 -0.233837 23.3736 + vertex -191.845 0.987371 24.1913 + endloop + endfacet + facet normal -0.0247415 -0.23169 0.972475 + outer loop + vertex -191.77 4.19046 24.9563 + vertex -213.021 3.26422 24.195 + vertex -191.845 0.987371 24.1913 + endloop + endfacet + facet normal -0.0219202 -0.231768 0.972524 + outer loop + vertex -191.77 4.19046 24.9563 + vertex -191.845 0.987371 24.1913 + vertex -170.547 2.14271 24.9467 + endloop + endfacet + facet normal -0.0215644 -0.228085 0.973402 + outer loop + vertex -170.317 4.90604 25.5993 + vertex -191.77 4.19046 24.9563 + vertex -170.547 2.14271 24.9467 + endloop + endfacet + facet normal -0.0215076 -0.229491 0.973073 + outer loop + vertex -191.53 6.95223 25.613 + vertex -191.77 4.19046 24.9563 + vertex -170.317 4.90604 25.5993 + endloop + endfacet + facet normal -0.020594 -0.220034 0.975275 + outer loop + vertex -169.827 7.08938 26.1022 + vertex -191.53 6.95223 25.613 + vertex -170.317 4.90604 25.5993 + endloop + endfacet + facet normal -0.0178758 -0.220625 0.975195 + outer loop + vertex -169.827 7.08938 26.1022 + vertex -170.317 4.90604 25.5993 + vertex -148.555 5.2803 26.0828 + endloop + endfacet + facet normal -0.0168914 -0.209077 0.977753 + outer loop + vertex -148.082 6.80045 26.4161 + vertex -169.827 7.08938 26.1022 + vertex -148.555 5.2803 26.0828 + endloop + endfacet + facet normal -0.0169251 -0.212398 0.977037 + outer loop + vertex -169.361 8.60975 26.4408 + vertex -169.827 7.08938 26.1022 + vertex -148.082 6.80045 26.4161 + endloop + endfacet + facet normal -0.016252 -0.204504 0.978731 + outer loop + vertex -148.373 7.701 26.5994 + vertex -169.361 8.60975 26.4408 + vertex -148.082 6.80045 26.4161 + endloop + endfacet + facet normal -0.0137941 -0.203748 0.978926 + outer loop + vertex -148.373 7.701 26.5994 + vertex -148.082 6.80045 26.4161 + vertex -126.977 6.11401 26.5706 + endloop + endfacet + facet normal -0.0150942 -0.221207 0.97511 + outer loop + vertex -128.814 6.64642 26.6629 + vertex -148.373 7.701 26.5994 + vertex -126.977 6.11401 26.5706 + endloop + endfacet + facet normal -0.0146661 -0.213158 0.976908 + outer loop + vertex -151.026 8.32088 26.6948 + vertex -148.373 7.701 26.5994 + vertex -128.814 6.64642 26.6629 + endloop + endfacet + facet normal -0.0181144 -0.227411 0.97363 + outer loop + vertex -151.026 8.32088 26.6948 + vertex -169.667 9.51777 26.6276 + vertex -148.373 7.701 26.5994 + endloop + endfacet + facet normal -0.017577 -0.218931 0.975582 + outer loop + vertex -171.583 10.0998 26.7237 + vertex -169.667 9.51777 26.6276 + vertex -151.026 8.32088 26.6948 + endloop + endfacet + facet normal -0.0210156 -0.229825 0.973005 + outer loop + vertex -171.583 10.0998 26.7237 + vertex -190.808 11.5699 26.6557 + vertex -169.667 9.51777 26.6276 + endloop + endfacet + facet normal -0.0189157 -0.208258 0.977891 + outer loop + vertex -190.808 11.5699 26.6557 + vertex -190.557 10.6592 26.4666 + vertex -169.667 9.51777 26.6276 + endloop + endfacet + facet normal -0.0188788 -0.207562 0.97804 + outer loop + vertex -169.667 9.51777 26.6276 + vertex -190.557 10.6592 26.4666 + vertex -169.361 8.60975 26.4408 + endloop + endfacet + facet normal -0.0195434 -0.214415 0.976547 + outer loop + vertex -190.557 10.6592 26.4666 + vertex -191.036 9.13865 26.1231 + vertex -169.361 8.60975 26.4408 + endloop + endfacet + facet normal -0.0222327 -0.213595 0.976669 + outer loop + vertex -190.557 10.6592 26.4666 + vertex -212.234 11.4233 26.1402 + vertex -191.036 9.13865 26.1231 + endloop + endfacet + facet normal -0.0233878 -0.224294 0.974241 + outer loop + vertex -212.234 11.4233 26.1402 + vertex -212.708 9.23357 25.6247 + vertex -191.036 9.13865 26.1231 + endloop + endfacet + facet normal -0.0233897 -0.222152 0.974732 + outer loop + vertex -191.036 9.13865 26.1231 + vertex -212.708 9.23357 25.6247 + vertex -191.53 6.95223 25.613 + endloop + endfacet + facet normal -0.0242908 -0.230506 0.972768 + outer loop + vertex -212.708 9.23357 25.6247 + vertex -212.945 6.47098 24.9642 + vertex -191.53 6.95223 25.613 + endloop + endfacet + facet normal -0.0270926 -0.230262 0.972751 + outer loop + vertex -212.708 9.23357 25.6247 + vertex -234.157 8.98999 24.9697 + vertex -212.945 6.47098 24.9642 + endloop + endfacet + facet normal -0.0274189 -0.233008 0.972088 + outer loop + vertex -234.157 8.98999 24.9697 + vertex -234.227 5.78035 24.1984 + vertex -212.945 6.47098 24.9642 + endloop + endfacet + facet normal -0.0274377 -0.232548 0.972198 + outer loop + vertex -212.945 6.47098 24.9642 + vertex -234.227 5.78035 24.1984 + vertex -213.021 3.26422 24.195 + endloop + endfacet + facet normal -0.0268839 -0.227882 0.973318 + outer loop + vertex -234.227 5.78035 24.1984 + vertex -234.384 2.28003 23.3745 + vertex -213.021 3.26422 24.195 + endloop + endfacet + facet normal -0.0294035 -0.227759 0.973274 + outer loop + vertex -234.227 5.78035 24.1984 + vertex -255.662 5.02859 23.3749 + vertex -234.384 2.28003 23.3745 + endloop + endfacet + facet normal -0.0281686 -0.218199 0.975498 + outer loop + vertex -255.662 5.02859 23.3749 + vertex -256.033 1.36119 22.5438 + vertex -234.384 2.28003 23.3745 + endloop + endfacet + facet normal -0.0281791 -0.217992 0.975544 + outer loop + vertex -234.384 2.28003 23.3745 + vertex -256.033 1.36119 22.5438 + vertex -234.75 -1.38851 22.5442 + endloop + endfacet + facet normal -0.02738 -0.211807 0.976928 + outer loop + vertex -256.033 1.36119 22.5438 + vertex -256.426 -2.43543 21.7097 + vertex -234.75 -1.38851 22.5442 + endloop + endfacet + facet normal -0.0295216 -0.211582 0.976914 + outer loop + vertex -256.033 1.36119 22.5438 + vertex -277.729 0.53305 21.7088 + vertex -256.426 -2.43543 21.7097 + endloop + endfacet + facet normal -0.0304715 -0.218399 0.975384 + outer loop + vertex -277.729 0.53305 21.7088 + vertex -277.647 -3.46875 20.8154 + vertex -256.426 -2.43543 21.7097 + endloop + endfacet + facet normal -0.0304313 -0.219091 0.97523 + outer loop + vertex -256.426 -2.43543 21.7097 + vertex -277.647 -3.46875 20.8154 + vertex -256.307 -6.439 20.814 + endloop + endfacet + facet normal -0.033664 -0.242313 0.969614 + outer loop + vertex -277.647 -3.46875 20.8154 + vertex -276.556 -7.79277 19.7726 + vertex -256.307 -6.439 20.814 + endloop + endfacet + facet normal -0.0359834 -0.242845 0.969397 + outer loop + vertex -277.647 -3.46875 20.8154 + vertex -297.784 -4.64319 19.7737 + vertex -276.556 -7.79277 19.7726 + endloop + endfacet + facet normal -0.0410201 -0.276788 0.960055 + outer loop + vertex -297.784 -4.64319 19.7737 + vertex -295.742 -9.29401 18.5201 + vertex -276.556 -7.79277 19.7726 + endloop + endfacet + facet normal -0.040939 -0.277625 0.959817 + outer loop + vertex -276.556 -7.79277 19.7726 + vertex -295.742 -9.29401 18.5201 + vertex -274.425 -12.4349 18.5208 + endloop + endfacet + facet normal -0.0384204 -0.276578 0.960223 + outer loop + vertex -276.556 -7.79277 19.7726 + vertex -274.425 -12.4349 18.5208 + vertex -255.173 -10.7565 19.7746 + endloop + endfacet + facet normal -0.0437241 -0.277859 0.959626 + outer loop + vertex -297.784 -4.64319 19.7737 + vertex -316.663 -6.00707 18.5186 + vertex -295.742 -9.29401 18.5201 + endloop + endfacet + facet normal -0.0438204 -0.276803 0.959927 + outer loop + vertex -318.741 -1.33023 19.7723 + vertex -316.663 -6.00707 18.5186 + vertex -297.784 -4.64319 19.7737 + endloop + endfacet + facet normal -0.0383432 -0.242152 0.96948 + outer loop + vertex -298.83 -0.313467 20.8138 + vertex -318.741 -1.33023 19.7723 + vertex -297.784 -4.64319 19.7737 + endloop + endfacet + facet normal -0.0383657 -0.2418 0.969567 + outer loop + vertex -319.802 3.01462 20.8139 + vertex -318.741 -1.33023 19.7723 + vertex -298.83 -0.313467 20.8138 + endloop + endfacet + facet normal -0.03465 -0.218385 0.975247 + outer loop + vertex -298.9 3.68951 21.7076 + vertex -319.802 3.01462 20.8139 + vertex -298.83 -0.313467 20.8138 + endloop + endfacet + facet normal -0.032612 -0.218366 0.975322 + outer loop + vertex -298.9 3.68951 21.7076 + vertex -298.83 -0.313467 20.8138 + vertex -277.729 0.53305 21.7088 + endloop + endfacet + facet normal -0.0315687 -0.211367 0.976897 + outer loop + vertex -277.322 4.32668 22.5428 + vertex -298.9 3.68951 21.7076 + vertex -277.729 0.53305 21.7088 + endloop + endfacet + facet normal -0.0315658 -0.211444 0.97688 + outer loop + vertex -298.48 7.47899 22.5414 + vertex -298.9 3.68951 21.7076 + vertex -277.322 4.32668 22.5428 + endloop + endfacet + facet normal -0.0325338 -0.217942 0.975419 + outer loop + vertex -276.947 7.99303 23.3745 + vertex -298.48 7.47899 22.5414 + vertex -277.322 4.32668 22.5428 + endloop + endfacet + facet normal -0.0304017 -0.218164 0.975438 + outer loop + vertex -276.947 7.99303 23.3745 + vertex -277.322 4.32668 22.5428 + vertex -255.662 5.02859 23.3749 + endloop + endfacet + facet normal -0.0317499 -0.227845 0.97318 + outer loop + vertex -255.51 8.5323 24.2001 + vertex -276.947 7.99303 23.3745 + vertex -255.662 5.02859 23.3749 + endloop + endfacet + facet normal -0.0317488 -0.227878 0.973172 + outer loop + vertex -276.801 11.501 24.2007 + vertex -276.947 7.99303 23.3745 + vertex -255.51 8.5323 24.2001 + endloop + endfacet + facet normal -0.0325232 -0.233432 0.971829 + outer loop + vertex -255.457 11.7511 24.975 + vertex -276.801 11.501 24.2007 + vertex -255.51 8.5323 24.2001 + endloop + endfacet + facet normal -0.0300219 -0.233489 0.971896 + outer loop + vertex -255.457 11.7511 24.975 + vertex -255.51 8.5323 24.2001 + vertex -234.157 8.98999 24.9697 + endloop + endfacet + facet normal -0.0297705 -0.231551 0.972367 + outer loop + vertex -233.947 11.764 25.6367 + vertex -255.457 11.7511 24.975 + vertex -234.157 8.98999 24.9697 + endloop + endfacet + facet normal -0.0297676 -0.231924 0.972278 + outer loop + vertex -255.284 14.5315 25.6436 + vertex -255.457 11.7511 24.975 + vertex -233.947 11.764 25.6367 + endloop + endfacet + facet normal -0.0287768 -0.22429 0.974098 + outer loop + vertex -233.52 13.9565 26.1541 + vertex -255.284 14.5315 25.6436 + vertex -233.947 11.764 25.6367 + endloop + endfacet + facet normal -0.0261167 -0.224798 0.974055 + outer loop + vertex -233.52 13.9565 26.1541 + vertex -233.947 11.764 25.6367 + vertex -212.234 11.4233 26.1402 + endloop + endfacet + facet normal -0.0249491 -0.214999 0.976296 + outer loop + vertex -211.801 12.9494 26.4874 + vertex -233.52 13.9565 26.1541 + vertex -212.234 11.4233 26.1402 + endloop + endfacet + facet normal -0.0250251 -0.216769 0.975902 + outer loop + vertex -233.146 15.4922 26.5048 + vertex -233.52 13.9565 26.1541 + vertex -211.801 12.9494 26.4874 + endloop + endfacet + facet normal -0.0242027 -0.209876 0.977428 + outer loop + vertex -212.176 13.8789 26.6777 + vertex -233.146 15.4922 26.5048 + vertex -211.801 12.9494 26.4874 + endloop + endfacet + facet normal -0.0215634 -0.208869 0.977706 + outer loop + vertex -212.176 13.8789 26.6777 + vertex -211.801 12.9494 26.4874 + vertex -190.808 11.5699 26.6557 + endloop + endfacet + facet normal -0.0242109 -0.233314 0.9721 + outer loop + vertex -192.943 12.2057 26.7551 + vertex -212.176 13.8789 26.6777 + vertex -190.808 11.5699 26.6557 + endloop + endfacet + facet normal -0.0234189 -0.224111 0.974282 + outer loop + vertex -214.411 14.5503 26.7784 + vertex -212.176 13.8789 26.6777 + vertex -192.943 12.2057 26.7551 + endloop + endfacet + facet normal -0.027419 -0.236959 0.971133 + outer loop + vertex -214.411 14.5503 26.7784 + vertex -233.469 16.4265 26.6981 + vertex -212.176 13.8789 26.6777 + endloop + endfacet + facet normal -0.0259782 -0.222173 0.974661 + outer loop + vertex -235.281 17.0669 26.7958 + vertex -233.469 16.4265 26.6981 + vertex -214.411 14.5503 26.7784 + endloop + endfacet + facet normal -0.0296273 -0.23213 0.972233 + outer loop + vertex -235.281 17.0669 26.7958 + vertex -254.796 19.2015 26.7107 + vertex -233.469 16.4265 26.6981 + endloop + endfacet + facet normal -0.0268213 -0.210588 0.977207 + outer loop + vertex -254.796 19.2015 26.7107 + vertex -254.561 18.2757 26.5177 + vertex -233.469 16.4265 26.6981 + endloop + endfacet + facet normal -0.0268915 -0.211406 0.977028 + outer loop + vertex -233.469 16.4265 26.6981 + vertex -254.561 18.2757 26.5177 + vertex -233.146 15.4922 26.5048 + endloop + endfacet + facet normal -0.027604 -0.216882 0.975808 + outer loop + vertex -254.561 18.2757 26.5177 + vertex -254.914 16.7392 26.1662 + vertex -233.146 15.4922 26.5048 + endloop + endfacet + facet normal -0.030006 -0.216341 0.975857 + outer loop + vertex -254.561 18.2757 26.5177 + vertex -276.328 19.7399 26.173 + vertex -254.914 16.7392 26.1662 + endloop + endfacet + facet normal -0.0312799 -0.225427 0.973758 + outer loop + vertex -276.328 19.7399 26.173 + vertex -276.65 17.5284 25.6507 + vertex -254.914 16.7392 26.1662 + endloop + endfacet + facet normal -0.0312756 -0.225287 0.97379 + outer loop + vertex -254.914 16.7392 26.1662 + vertex -276.65 17.5284 25.6507 + vertex -255.284 14.5315 25.6436 + endloop + endfacet + facet normal -0.032278 -0.23243 0.972077 + outer loop + vertex -276.65 17.5284 25.6507 + vertex -276.772 14.729 24.9773 + vertex -255.284 14.5315 25.6436 + endloop + endfacet + facet normal -0.0346654 -0.232313 0.972023 + outer loop + vertex -276.65 17.5284 25.6507 + vertex -297.966 17.9032 24.9801 + vertex -276.772 14.729 24.9773 + endloop + endfacet + facet normal -0.0348613 -0.23362 0.971703 + outer loop + vertex -297.966 17.9032 24.9801 + vertex -297.958 14.6602 24.2006 + vertex -276.772 14.729 24.9773 + endloop + endfacet + facet normal -0.0348631 -0.233471 0.971739 + outer loop + vertex -276.772 14.729 24.9773 + vertex -297.958 14.6602 24.2006 + vertex -276.801 11.501 24.2007 + endloop + endfacet + facet normal -0.0340077 -0.227742 0.973127 + outer loop + vertex -297.958 14.6602 24.2006 + vertex -298.096 11.1461 23.3734 + vertex -276.801 11.501 24.2007 + endloop + endfacet + facet normal -0.0362201 -0.227642 0.973071 + outer loop + vertex -297.958 14.6602 24.2006 + vertex -319.024 14.4774 23.3738 + vertex -298.096 11.1461 23.3734 + endloop + endfacet + facet normal -0.0346516 -0.217789 0.975381 + outer loop + vertex -319.024 14.4774 23.3738 + vertex -319.409 10.8073 22.5406 + vertex -298.096 11.1461 23.3734 + endloop + endfacet + facet normal -0.0346545 -0.217673 0.975406 + outer loop + vertex -298.096 11.1461 23.3734 + vertex -319.409 10.8073 22.5406 + vertex -298.48 7.47899 22.5414 + endloop + endfacet + facet normal -0.0336425 -0.211309 0.97684 + outer loop + vertex -319.409 10.8073 22.5406 + vertex -319.841 7.01791 21.706 + vertex -298.48 7.47899 22.5414 + endloop + endfacet + facet normal -0.0356725 -0.211073 0.976819 + outer loop + vertex -319.409 10.8073 22.5406 + vertex -340.609 10.5317 21.7068 + vertex -319.841 7.01791 21.706 + endloop + endfacet + facet normal -0.0367786 -0.21761 0.975343 + outer loop + vertex -340.609 10.5317 21.7068 + vertex -340.587 6.52293 20.8133 + vertex -319.841 7.01791 21.706 + endloop + endfacet + facet normal -0.0367753 -0.217711 0.97532 + outer loop + vertex -319.841 7.01791 21.706 + vertex -340.587 6.52293 20.8133 + vertex -319.802 3.01462 20.8139 + endloop + endfacet + facet normal -0.0407996 -0.241554 0.969529 + outer loop + vertex -340.587 6.52293 20.8133 + vertex -339.529 2.16127 19.7711 + vertex -319.802 3.01462 20.8139 + endloop + endfacet + facet normal -0.0429909 -0.242034 0.969315 + outer loop + vertex -340.587 6.52293 20.8133 + vertex -360.33 5.86406 19.7731 + vertex -339.529 2.16127 19.7711 + endloop + endfacet + facet normal -0.0490337 -0.275975 0.959913 + outer loop + vertex -360.33 5.86406 19.7731 + vertex -358.168 1.11683 18.5187 + vertex -339.529 2.16127 19.7711 + endloop + endfacet + facet normal -0.0489555 -0.277016 0.959617 + outer loop + vertex -339.529 2.16127 19.7711 + vertex -358.168 1.11683 18.5187 + vertex -337.402 -2.54927 18.5198 + endloop + endfacet + facet normal -0.046407 -0.275978 0.960043 + outer loop + vertex -339.529 2.16127 19.7711 + vertex -337.402 -2.54927 18.5198 + vertex -318.741 -1.33023 19.7723 + endloop + endfacet + facet normal -0.0516442 -0.277046 0.959468 + outer loop + vertex -360.33 5.86406 19.7731 + vertex -379.144 5.02749 18.5189 + vertex -358.168 1.11683 18.5187 + endloop + endfacet + facet normal -0.0517274 -0.275735 0.959841 + outer loop + vertex -381.248 9.79141 19.7741 + vertex -379.144 5.02749 18.5189 + vertex -360.33 5.86406 19.7731 + endloop + endfacet + facet normal -0.0453137 -0.241578 0.969323 + outer loop + vertex -361.35 10.2382 20.8156 + vertex -381.248 9.79141 19.7741 + vertex -360.33 5.86406 19.7731 + endloop + endfacet + facet normal -0.0453139 -0.241571 0.969324 + outer loop + vertex -382.196 14.1611 20.8187 + vertex -381.248 9.79141 19.7741 + vertex -361.35 10.2382 20.8156 + endloop + endfacet + facet normal -0.0408255 -0.217726 0.975156 + outer loop + vertex -361.337 14.2479 21.7114 + vertex -382.196 14.1611 20.8187 + vertex -361.35 10.2382 20.8156 + endloop + endfacet + facet normal -0.0388262 -0.217749 0.975232 + outer loop + vertex -361.337 14.2479 21.7114 + vertex -361.35 10.2382 20.8156 + vertex -340.609 10.5317 21.7068 + endloop + endfacet + facet normal -0.0376356 -0.21111 0.976737 + outer loop + vertex -340.163 14.3237 22.5436 + vertex -361.337 14.2479 21.7114 + vertex -340.609 10.5317 21.7068 + endloop + endfacet + facet normal -0.0376267 -0.21185 0.976578 + outer loop + vertex -360.867 18.0376 22.5516 + vertex -361.337 14.2479 21.7114 + vertex -340.163 14.3237 22.5436 + endloop + endfacet + facet normal -0.0387354 -0.218028 0.975174 + outer loop + vertex -339.781 18.0007 23.3809 + vertex -360.867 18.0376 22.5516 + vertex -340.163 14.3237 22.5436 + endloop + endfacet + facet normal -0.0367096 -0.218245 0.975203 + outer loop + vertex -339.781 18.0007 23.3809 + vertex -340.163 14.3237 22.5436 + vertex -319.024 14.4774 23.3738 + endloop + endfacet + facet normal -0.0383699 -0.228021 0.9729 + outer loop + vertex -318.91 18.0055 24.2052 + vertex -339.781 18.0007 23.3809 + vertex -319.024 14.4774 23.3738 + endloop + endfacet + facet normal -0.0383596 -0.229108 0.972645 + outer loop + vertex -339.68 21.5404 24.2187 + vertex -339.781 18.0007 23.3809 + vertex -318.91 18.0055 24.2052 + endloop + endfacet + facet normal -0.0392609 -0.234399 0.971347 + outer loop + vertex -318.962 21.2694 24.9907 + vertex -339.68 21.5404 24.2187 + vertex -318.91 18.0055 24.2052 + endloop + endfacet + facet normal -0.0370873 -0.234386 0.971436 + outer loop + vertex -318.962 21.2694 24.9907 + vertex -318.91 18.0055 24.2052 + vertex -297.966 17.9032 24.9801 + endloop + endfacet + facet normal -0.0368081 -0.232646 0.971865 + outer loop + vertex -297.898 20.7189 25.6567 + vertex -318.962 21.2694 24.9907 + vertex -297.966 17.9032 24.9801 + endloop + endfacet + facet normal -0.036824 -0.233502 0.971659 + outer loop + vertex -318.915 24.0942 25.6713 + vertex -318.962 21.2694 24.9907 + vertex -297.898 20.7189 25.6567 + endloop + endfacet + facet normal -0.0356641 -0.226287 0.973407 + outer loop + vertex -297.619 22.9502 26.1856 + vertex -318.915 24.0942 25.6713 + vertex -297.898 20.7189 25.6567 + endloop + endfacet + facet normal -0.0335836 -0.22655 0.97342 + outer loop + vertex -297.619 22.9502 26.1856 + vertex -297.898 20.7189 25.6567 + vertex -276.328 19.7399 26.173 + endloop + endfacet + facet normal -0.0321754 -0.21722 0.975592 + outer loop + vertex -276.014 21.2873 26.5279 + vertex -297.619 22.9502 26.1856 + vertex -276.328 19.7399 26.173 + endloop + endfacet + facet normal -0.032294 -0.218836 0.975227 + outer loop + vertex -297.306 24.5044 26.5447 + vertex -297.619 22.9502 26.1856 + vertex -276.014 21.2873 26.5279 + endloop + endfacet + facet normal -0.0313716 -0.212739 0.976605 + outer loop + vertex -276.348 22.2389 26.7244 + vertex -297.306 24.5044 26.5447 + vertex -276.014 21.2873 26.5279 + endloop + endfacet + facet normal -0.0292631 -0.212042 0.976822 + outer loop + vertex -276.348 22.2389 26.7244 + vertex -276.014 21.2873 26.5279 + vertex -254.796 19.2015 26.7107 + endloop + endfacet + facet normal -0.0323785 -0.234125 0.971667 + outer loop + vertex -256.495 19.8582 26.8124 + vertex -276.348 22.2389 26.7244 + vertex -254.796 19.2015 26.7107 + endloop + endfacet + facet normal -0.0315733 -0.22735 0.973301 + outer loop + vertex -278.74 23.0138 26.8279 + vertex -276.348 22.2389 26.7244 + vertex -256.495 19.8582 26.8124 + endloop + endfacet + facet normal -0.0351676 -0.238086 0.970607 + outer loop + vertex -278.74 23.0138 26.8279 + vertex -297.629 25.4596 26.7434 + vertex -276.348 22.2389 26.7244 + endloop + endfacet + facet normal -0.0333371 -0.22383 0.974058 + outer loop + vertex -299.542 26.1846 26.8445 + vertex -297.629 25.4596 26.7434 + vertex -278.74 23.0138 26.8279 + endloop + endfacet + facet normal -0.0358679 -0.230284 0.972462 + outer loop + vertex -299.542 26.1846 26.8445 + vertex -318.447 28.8037 26.7675 + vertex -297.629 25.4596 26.7434 + endloop + endfacet + facet normal -0.0335642 -0.215967 0.975824 + outer loop + vertex -318.447 28.8037 26.7675 + vertex -318.242 27.8645 26.5667 + vertex -297.629 25.4596 26.7434 + endloop + endfacet + facet normal -0.033378 -0.214344 0.976188 + outer loop + vertex -297.629 25.4596 26.7434 + vertex -318.242 27.8645 26.5667 + vertex -297.306 24.5044 26.5447 + endloop + endfacet + facet normal -0.0343466 -0.220371 0.974811 + outer loop + vertex -318.242 27.8645 26.5667 + vertex -318.622 26.3304 26.2065 + vertex -297.306 24.5044 26.5447 + endloop + endfacet + facet normal -0.0359765 -0.219974 0.974842 + outer loop + vertex -318.242 27.8645 26.5667 + vertex -339.237 29.8342 26.2363 + vertex -318.622 26.3304 26.2065 + endloop + endfacet + facet normal -0.0377431 -0.230348 0.972376 + outer loop + vertex -339.237 29.8342 26.2363 + vertex -339.635 27.6316 25.6991 + vertex -318.622 26.3304 26.2065 + endloop + endfacet + facet normal -0.0376067 -0.22792 0.972953 + outer loop + vertex -318.622 26.3304 26.2065 + vertex -339.635 27.6316 25.6991 + vertex -318.915 24.0942 25.6713 + endloop + endfacet + facet normal -0.0389512 -0.23578 0.971025 + outer loop + vertex -339.635 27.6316 25.6991 + vertex -339.724 24.806 25.0094 + vertex -318.915 24.0942 25.6713 + endloop + endfacet + facet normal -0.040991 -0.2357 0.970961 + outer loop + vertex -339.635 27.6316 25.6991 + vertex -360.249 28.4847 25.0359 + vertex -339.724 24.806 25.0094 + endloop + endfacet + facet normal -0.0414212 -0.238096 0.970358 + outer loop + vertex -360.249 28.4847 25.0359 + vertex -360.309 25.2402 24.2373 + vertex -339.724 24.806 25.0094 + endloop + endfacet + facet normal -0.0413923 -0.235666 0.970952 + outer loop + vertex -339.724 24.806 25.0094 + vertex -360.309 25.2402 24.2373 + vertex -339.68 21.5404 24.2187 + endloop + endfacet + facet normal -0.0404852 -0.230615 0.972203 + outer loop + vertex -360.309 25.2402 24.2373 + vertex -360.464 21.7123 23.394 + vertex -339.68 21.5404 24.2187 + endloop + endfacet + facet normal -0.0427646 -0.230498 0.972133 + outer loop + vertex -360.309 25.2402 24.2373 + vertex -381.147 25.5802 23.4012 + vertex -360.464 21.7123 23.394 + endloop + endfacet + facet normal -0.0408528 -0.22028 0.974581 + outer loop + vertex -381.147 25.5802 23.4012 + vertex -381.64 21.9337 22.5563 + vertex -360.464 21.7123 23.394 + endloop + endfacet + facet normal -0.0408508 -0.218991 0.974871 + outer loop + vertex -360.464 21.7123 23.394 + vertex -381.64 21.9337 22.5563 + vertex -360.867 18.0376 22.5516 + endloop + endfacet + facet normal -0.039583 -0.212233 0.976417 + outer loop + vertex -381.64 21.9337 22.5563 + vertex -382.148 18.16 21.7155 + vertex -360.867 18.0376 22.5516 + endloop + endfacet + facet normal -0.0417888 -0.21193 0.976391 + outer loop + vertex -381.64 21.9337 22.5563 + vertex -403.158 22.2581 21.7058 + vertex -382.148 18.16 21.7155 + endloop + endfacet + facet normal -0.0429384 -0.217827 0.975042 + outer loop + vertex -403.158 22.2581 21.7058 + vertex -403.185 18.2731 20.8143 + vertex -382.148 18.16 21.7155 + endloop + endfacet + facet normal -0.0429371 -0.218125 0.974976 + outer loop + vertex -382.148 18.16 21.7155 + vertex -403.185 18.2731 20.8143 + vertex -382.196 14.1611 20.8187 + endloop + endfacet + facet normal -0.0474086 -0.240955 0.969378 + outer loop + vertex -403.185 18.2731 20.8143 + vertex -402.276 13.9204 19.7769 + vertex -382.196 14.1611 20.8187 + endloop + endfacet + facet normal -0.0497388 -0.241389 0.969153 + outer loop + vertex -403.185 18.2731 20.8143 + vertex -423.382 18.2302 19.7671 + vertex -402.276 13.9204 19.7769 + endloop + endfacet + facet normal -0.0566612 -0.275313 0.959683 + outer loop + vertex -423.382 18.2302 19.7671 + vertex -421.417 13.496 18.525 + vertex -402.276 13.9204 19.7769 + endloop + endfacet + facet normal -0.0565731 -0.277467 0.959068 + outer loop + vertex -402.276 13.9204 19.7769 + vertex -421.417 13.496 18.525 + vertex -400.364 9.18913 18.5208 + endloop + endfacet + facet normal -0.054185 -0.276605 0.959455 + outer loop + vertex -402.276 13.9204 19.7769 + vertex -400.364 9.18913 18.5208 + vertex -381.248 9.79141 19.7741 + endloop + endfacet + facet normal -0.0594119 -0.276334 0.959224 + outer loop + vertex -423.382 18.2302 19.7671 + vertex -442.32 17.9395 18.5104 + vertex -421.417 13.496 18.525 + endloop + endfacet + facet normal -0.0595097 -0.273476 0.960036 + outer loop + vertex -444.863 22.8633 19.7553 + vertex -442.32 17.9395 18.5104 + vertex -423.382 18.2302 19.7671 + endloop + endfacet + facet normal -0.0524292 -0.240624 0.969201 + outer loop + vertex -424.48 22.6158 20.7966 + vertex -444.863 22.8633 19.7553 + vertex -423.382 18.2302 19.7671 + endloop + endfacet + facet normal -0.0524299 -0.239096 0.969579 + outer loop + vertex -446.025 27.3009 20.7868 + vertex -444.863 22.8633 19.7553 + vertex -424.48 22.6158 20.7966 + endloop + endfacet + facet normal -0.0475004 -0.216415 0.975145 + outer loop + vertex -424.513 26.5972 21.6785 + vertex -446.025 27.3009 20.7868 + vertex -424.48 22.6158 20.7966 + endloop + endfacet + facet normal -0.0452192 -0.216419 0.975253 + outer loop + vertex -424.513 26.5972 21.6785 + vertex -424.48 22.6158 20.7966 + vertex -403.158 22.2581 21.7058 + endloop + endfacet + facet normal -0.0442621 -0.211702 0.976331 + outer loop + vertex -402.601 26.0017 22.5428 + vertex -424.513 26.5972 21.6785 + vertex -403.158 22.2581 21.7058 + endloop + endfacet + facet normal -0.0442546 -0.211294 0.97642 + outer loop + vertex -423.917 30.3283 22.5129 + vertex -424.513 26.5972 21.6785 + vertex -402.601 26.0017 22.5428 + endloop + endfacet + facet normal -0.046189 -0.22084 0.974216 + outer loop + vertex -401.967 29.6098 23.3907 + vertex -423.917 30.3283 22.5129 + vertex -402.601 26.0017 22.5428 + endloop + endfacet + facet normal -0.0433296 -0.221346 0.974232 + outer loop + vertex -401.967 29.6098 23.3907 + vertex -402.601 26.0017 22.5428 + vertex -381.147 25.5802 23.4012 + endloop + endfacet + facet normal -0.0454926 -0.232529 0.971525 + outer loop + vertex -380.837 29.0685 24.2506 + vertex -401.967 29.6098 23.3907 + vertex -381.147 25.5802 23.4012 + endloop + endfacet + facet normal -0.0455786 -0.237996 0.970196 + outer loop + vertex -401.472 33.064 24.2613 + vertex -401.967 29.6098 23.3907 + vertex -380.837 29.0685 24.2506 + endloop + endfacet + facet normal -0.0464847 -0.242673 0.968994 + outer loop + vertex -380.591 32.267 25.0635 + vertex -401.472 33.064 24.2613 + vertex -380.837 29.0685 24.2506 + endloop + endfacet + facet normal -0.043851 -0.242893 0.969062 + outer loop + vertex -380.591 32.267 25.0635 + vertex -380.837 29.0685 24.2506 + vertex -360.249 28.4847 25.0359 + endloop + endfacet + facet normal -0.043153 -0.239146 0.970024 + outer loop + vertex -360.018 31.2689 25.7326 + vertex -380.591 32.267 25.0635 + vertex -360.249 28.4847 25.0359 + endloop + endfacet + facet normal -0.0435961 -0.250157 0.967223 + outer loop + vertex -380.265 35.0326 25.7934 + vertex -380.591 32.267 25.0635 + vertex -360.018 31.2689 25.7326 + endloop + endfacet + facet normal -0.0412907 -0.237806 0.970435 + outer loop + vertex -359.552 33.4515 26.2873 + vertex -380.265 35.0326 25.7934 + vertex -360.018 31.2689 25.7326 + endloop + endfacet + facet normal -0.0399596 -0.238087 0.970421 + outer loop + vertex -359.552 33.4515 26.2873 + vertex -360.018 31.2689 25.7326 + vertex -339.237 29.8342 26.2363 + endloop + endfacet + facet normal -0.0376524 -0.225175 0.973591 + outer loop + vertex -338.804 31.356 26.605 + vertex -359.552 33.4515 26.2873 + vertex -339.237 29.8342 26.2363 + endloop + endfacet + facet normal -0.039056 -0.239603 0.970085 + outer loop + vertex -359.205 34.9827 26.6794 + vertex -359.552 33.4515 26.2873 + vertex -338.804 31.356 26.605 + endloop + endfacet + facet normal -0.0361854 -0.223536 0.974024 + outer loop + vertex -339.171 32.3211 26.8129 + vertex -359.205 34.9827 26.6794 + vertex -338.804 31.356 26.605 + endloop + endfacet + facet normal -0.0357817 -0.223393 0.974071 + outer loop + vertex -339.171 32.3211 26.8129 + vertex -338.804 31.356 26.605 + vertex -318.447 28.8037 26.7675 + endloop + endfacet + facet normal -0.0351933 -0.219937 0.974879 + outer loop + vertex -320.367 29.5547 26.8676 + vertex -339.171 32.3211 26.8129 + vertex -318.447 28.8037 26.7675 + endloop + endfacet + facet normal -0.0340114 -0.211867 0.976707 + outer loop + vertex -341.953 33.2322 26.9136 + vertex -339.171 32.3211 26.8129 + vertex -320.367 29.5547 26.8676 + endloop + endfacet + facet normal -0.0311359 -0.195034 0.980302 + outer loop + vertex -341.953 33.2322 26.9136 + vertex -320.367 29.5547 26.8676 + vertex -331.092 31.617 26.9372 + endloop + endfacet + facet normal -0.0264806 -0.163646 0.986164 + outer loop + vertex -331.092 31.617 26.9372 + vertex -338.38 32.8135 26.9401 + vertex -341.953 33.2322 26.9136 + endloop + endfacet + facet normal -0.0276723 -0.173927 0.98437 + outer loop + vertex -338.38 32.8135 26.9401 + vertex -342.124 33.4756 26.9518 + vertex -341.953 33.2322 26.9136 + endloop + endfacet + facet normal -0.0266848 -0.173253 0.984516 + outer loop + vertex -342.124 33.4756 26.9518 + vertex -349.681 34.8686 26.9921 + vertex -341.953 33.2322 26.9136 + endloop + endfacet + facet normal -0.022445 -0.153392 0.98791 + outer loop + vertex -362.171 36.8731 27.0196 + vertex -341.953 33.2322 26.9136 + vertex -349.681 34.8686 26.9921 + endloop + endfacet + facet normal -0.0159942 -0.113273 0.993435 + outer loop + vertex -349.681 34.8686 26.9921 + vertex -357.384 36.2518 27.0258 + vertex -362.171 36.8731 27.0196 + endloop + endfacet + facet normal -0.0223848 -0.162585 0.986441 + outer loop + vertex -357.384 36.2518 27.0258 + vertex -363.441 37.4326 27.083 + vertex -362.171 36.8731 27.0196 + endloop + endfacet + facet normal -0.0226378 -0.163148 0.986342 + outer loop + vertex -363.441 37.4326 27.083 + vertex -370.505 38.6079 27.1153 + vertex -362.171 36.8731 27.0196 + endloop + endfacet + facet normal -0.0344984 -0.224118 0.973951 + outer loop + vertex -363.441 37.4326 27.083 + vertex -357.384 36.2518 27.0258 + vertex -358.449 37.2091 27.2084 + endloop + endfacet + facet normal -0.0351535 -0.241036 0.969879 + outer loop + vertex -358.449 37.2091 27.2084 + vertex -374.006 40.0132 27.3414 + vertex -363.441 37.4326 27.083 + endloop + endfacet + facet normal -0.0367161 -0.24727 0.968251 + outer loop + vertex -370.505 38.6079 27.1153 + vertex -363.441 37.4326 27.083 + vertex -374.006 40.0132 27.3414 + endloop + endfacet + facet normal -0.0399038 -0.254874 0.966151 + outer loop + vertex -375.78 39.6389 27.1694 + vertex -370.505 38.6079 27.1153 + vertex -374.006 40.0132 27.3414 + endloop + endfacet + facet normal -0.0383172 -0.261596 0.964416 + outer loop + vertex -380.519 40.6445 27.2539 + vertex -375.78 39.6389 27.1694 + vertex -374.006 40.0132 27.3414 + endloop + endfacet + facet normal -0.0416101 -0.297016 0.953966 + outer loop + vertex -374.006 40.0132 27.3414 + vertex -390.255 43.1749 27.617 + vertex -380.519 40.6445 27.2539 + endloop + endfacet + facet normal -0.0457942 -0.312381 0.948853 + outer loop + vertex -385.049 41.4331 27.2949 + vertex -380.519 40.6445 27.2539 + vertex -390.255 43.1749 27.617 + endloop + endfacet + facet normal -0.0410202 -0.29895 0.953387 + outer loop + vertex -391.051 42.5967 27.4015 + vertex -385.049 41.4331 27.2949 + vertex -390.255 43.1749 27.617 + endloop + endfacet + facet normal -0.0413598 -0.298527 0.953505 + outer loop + vertex -398.38 44.214 27.5899 + vertex -391.051 42.5967 27.4015 + vertex -390.255 43.1749 27.617 + endloop + endfacet + facet normal -0.0496324 -0.363825 0.930144 + outer loop + vertex -390.255 43.1749 27.617 + vertex -406.588 46.5443 28.0635 + vertex -398.38 44.214 27.5899 + endloop + endfacet + facet normal -0.0538424 -0.377494 0.924446 + outer loop + vertex -404.425 45.3821 27.7149 + vertex -398.38 44.214 27.5899 + vertex -406.588 46.5443 28.0635 + endloop + endfacet + facet normal -0.046883 -0.366035 0.92942 + outer loop + vertex -412.125 46.9935 27.9611 + vertex -404.425 45.3821 27.7149 + vertex -406.588 46.5443 28.0635 + endloop + endfacet + facet normal -0.00109507 -0.111971 0.993711 + outer loop + vertex -398.38 44.214 27.5899 + vertex -404.425 45.3821 27.7149 + vertex -403.558 44.9696 27.6694 + endloop + endfacet + facet normal -0.0455331 -0.344932 0.937523 + outer loop + vertex -390.255 43.1749 27.617 + vertex -404.372 47.9647 28.6937 + vertex -406.588 46.5443 28.0635 + endloop + endfacet + facet normal -0.0341939 -0.360269 0.932221 + outer loop + vertex -404.372 47.9647 28.6937 + vertex -419.137 50.7388 29.2242 + vertex -406.588 46.5443 28.0635 + endloop + endfacet + facet normal -0.0293897 -0.300879 0.953209 + outer loop + vertex -388.26 44.8206 28.198 + vertex -404.372 47.9647 28.6937 + vertex -390.255 43.1749 27.617 + endloop + endfacet + facet normal -0.0338919 -0.322792 0.945863 + outer loop + vertex -388.26 44.8206 28.198 + vertex -403.651 50.6771 29.6452 + vertex -404.372 47.9647 28.6937 + endloop + endfacet + facet normal -0.015164 -0.327385 0.944769 + outer loop + vertex -403.651 50.6771 29.6452 + vertex -420.114 53.662 30.4153 + vertex -404.372 47.9647 28.6937 + endloop + endfacet + facet normal -0.0131886 -0.272394 0.962095 + outer loop + vertex -387.534 47.5165 28.9713 + vertex -403.651 50.6771 29.6452 + vertex -388.26 44.8206 28.198 + endloop + endfacet + facet normal -0.0304892 -0.267978 0.962942 + outer loop + vertex -372.308 41.7573 27.8506 + vertex -387.534 47.5165 28.9713 + vertex -388.26 44.8206 28.198 + endloop + endfacet + facet normal -0.0279205 -0.25501 0.966535 + outer loop + vertex -372.308 41.7573 27.8506 + vertex -388.26 44.8206 28.198 + vertex -374.006 40.0132 27.3414 + endloop + endfacet + facet normal -0.0178483 -0.236231 0.971533 + outer loop + vertex -371.813 44.4543 28.5155 + vertex -387.534 47.5165 28.9713 + vertex -372.308 41.7573 27.8506 + endloop + endfacet + facet normal -0.0306253 -0.233942 0.971768 + outer loop + vertex -356.418 38.7577 27.6293 + vertex -371.813 44.4543 28.5155 + vertex -372.308 41.7573 27.8506 + endloop + endfacet + facet normal -0.0291672 -0.226354 0.973608 + outer loop + vertex -356.418 38.7577 27.6293 + vertex -372.308 41.7573 27.8506 + vertex -358.449 37.2091 27.2084 + endloop + endfacet + facet normal -0.0343853 -0.219866 0.974924 + outer loop + vertex -342.042 34.1472 27.0966 + vertex -356.418 38.7577 27.6293 + vertex -358.449 37.2091 27.2084 + endloop + endfacet + facet normal -0.0338073 -0.216795 0.975632 + outer loop + vertex -342.042 34.1472 27.0966 + vertex -358.449 37.2091 27.2084 + vertex -349.681 34.8686 26.9921 + endloop + endfacet + facet normal -0.0307249 -0.208749 0.977487 + outer loop + vertex -340.443 35.8676 27.5142 + vertex -356.418 38.7577 27.6293 + vertex -342.042 34.1472 27.0966 + endloop + endfacet + facet normal -0.0332475 -0.2065 0.977882 + outer loop + vertex -326.185 31.4963 27.0759 + vertex -340.443 35.8676 27.5142 + vertex -342.042 34.1472 27.0966 + endloop + endfacet + facet normal -0.0326398 -0.202871 0.978661 + outer loop + vertex -326.185 31.4963 27.0759 + vertex -342.042 34.1472 27.0966 + vertex -331.092 31.617 26.9372 + endloop + endfacet + facet normal -0.0326099 -0.201277 0.978991 + outer loop + vertex -331.092 31.617 26.9372 + vertex -322.916 30.2128 26.9209 + vertex -326.185 31.4963 27.0759 + endloop + endfacet + facet normal -0.0325344 -0.20109 0.979032 + outer loop + vertex -322.916 30.2128 26.9209 + vertex -317.652 29.397 26.9282 + vertex -326.185 31.4963 27.0759 + endloop + endfacet + facet normal -0.0318453 -0.19833 0.979618 + outer loop + vertex -310.621 28.8311 27.0422 + vertex -326.185 31.4963 27.0759 + vertex -317.652 29.397 26.9282 + endloop + endfacet + facet normal -0.0319177 -0.199268 0.979425 + outer loop + vertex -317.652 29.397 26.9282 + vertex -313.002 28.5247 26.9023 + vertex -310.621 28.8311 27.0422 + endloop + endfacet + facet normal -0.0315417 -0.201944 0.978889 + outer loop + vertex -313.002 28.5247 26.9023 + vertex -307.738 27.6493 26.8913 + vertex -310.621 28.8311 27.0422 + endloop + endfacet + facet normal -0.0318923 -0.202776 0.978706 + outer loop + vertex -307.738 27.6493 26.8913 + vertex -300.273 26.5951 26.9162 + vertex -310.621 28.8311 27.0422 + endloop + endfacet + facet normal -0.0308872 -0.198179 0.979679 + outer loop + vertex -294.8 26.4297 27.0553 + vertex -310.621 28.8311 27.0422 + vertex -300.273 26.5951 26.9162 + endloop + endfacet + facet normal -0.0309873 -0.202182 0.978858 + outer loop + vertex -300.273 26.5951 26.9162 + vertex -294.191 25.5934 26.9018 + vertex -294.8 26.4297 27.0553 + endloop + endfacet + facet normal -0.0298437 -0.201386 0.979057 + outer loop + vertex -294.191 25.5934 26.9018 + vertex -286.319 24.4052 26.8973 + vertex -294.8 26.4297 27.0553 + endloop + endfacet + facet normal -0.0296071 -0.200412 0.979264 + outer loop + vertex -278.098 23.8129 27.0247 + vertex -294.8 26.4297 27.0553 + vertex -286.319 24.4052 26.8973 + endloop + endfacet + facet normal -0.0296464 -0.200982 0.979146 + outer loop + vertex -286.319 24.4052 26.8973 + vertex -278.585 23.1985 26.8839 + vertex -278.098 23.8129 27.0247 + endloop + endfacet + facet normal -0.0287403 -0.201673 0.979031 + outer loop + vertex -278.585 23.1985 26.8839 + vertex -274.745 22.6301 26.8795 + vertex -278.098 23.8129 27.0247 + endloop + endfacet + facet normal -0.0272083 -0.197442 0.979937 + outer loop + vertex -274.745 22.6301 26.8795 + vertex -267.195 21.5991 26.8814 + vertex -278.098 23.8129 27.0247 + endloop + endfacet + facet normal -0.0281212 -0.201878 0.979007 + outer loop + vertex -261.909 21.5877 27.0309 + vertex -278.098 23.8129 27.0247 + vertex -267.195 21.5991 26.8814 + endloop + endfacet + facet normal -0.0281129 -0.204114 0.978543 + outer loop + vertex -267.195 21.5991 26.8814 + vertex -258.796 20.4014 26.8729 + vertex -261.909 21.5877 27.0309 + endloop + endfacet + facet normal -0.0267453 -0.200626 0.979303 + outer loop + vertex -258.796 20.4014 26.8729 + vertex -253.411 19.7258 26.8815 + vertex -261.909 21.5877 27.0309 + endloop + endfacet + facet normal -0.0256294 -0.195617 0.980345 + outer loop + vertex -246.164 19.351 26.9962 + vertex -261.909 21.5877 27.0309 + vertex -253.411 19.7258 26.8815 + endloop + endfacet + facet normal -0.0258142 -0.199427 0.979573 + outer loop + vertex -253.411 19.7258 26.8815 + vertex -248.762 18.9915 26.8545 + vertex -246.164 19.351 26.9962 + endloop + endfacet + facet normal -0.025375 -0.202369 0.978981 + outer loop + vertex -248.762 18.9915 26.8545 + vertex -243.462 18.2724 26.8433 + vertex -246.164 19.351 26.9962 + endloop + endfacet + facet normal -0.0256411 -0.203015 0.97884 + outer loop + vertex -243.462 18.2724 26.8433 + vertex -235.878 17.438 26.8689 + vertex -246.164 19.351 26.9962 + endloop + endfacet + facet normal -0.0237481 -0.192975 0.980916 + outer loop + vertex -230.219 17.4213 27.0026 + vertex -246.164 19.351 26.9962 + vertex -235.878 17.438 26.8689 + endloop + endfacet + facet normal -0.0237422 -0.196353 0.980246 + outer loop + vertex -235.878 17.438 26.8689 + vertex -229.727 16.61 26.852 + vertex -230.219 17.4213 27.0026 + endloop + endfacet + facet normal -0.0224758 -0.195617 0.980423 + outer loop + vertex -229.727 16.61 26.852 + vertex -221.833 15.6744 26.8463 + vertex -230.219 17.4213 27.0026 + endloop + endfacet + facet normal -0.0218426 -0.192631 0.981028 + outer loop + vertex -213.339 15.3044 26.9627 + vertex -230.219 17.4213 27.0026 + vertex -221.833 15.6744 26.8463 + endloop + endfacet + facet normal -0.0217534 -0.190449 0.981456 + outer loop + vertex -221.833 15.6744 26.8463 + vertex -214.016 14.7012 26.8307 + vertex -213.339 15.3044 26.9627 + endloop + endfacet + facet normal -0.0206449 -0.191648 0.981246 + outer loop + vertex -214.016 14.7012 26.8307 + vertex -210.205 14.2656 26.8258 + vertex -213.339 15.3044 26.9627 + endloop + endfacet + facet normal -0.0191467 -0.187245 0.982127 + outer loop + vertex -210.205 14.2656 26.8258 + vertex -202.746 13.4834 26.8221 + vertex -213.339 15.3044 26.9627 + endloop + endfacet + facet normal -0.0198697 -0.191389 0.981313 + outer loop + vertex -196.109 13.3923 26.9387 + vertex -213.339 15.3044 26.9627 + vertex -202.746 13.4834 26.8221 + endloop + endfacet + facet normal -0.0198855 -0.192926 0.981012 + outer loop + vertex -202.746 13.4834 26.8221 + vertex -194.903 12.5865 26.8047 + vertex -196.109 13.3923 26.9387 + endloop + endfacet + facet normal -0.0188515 -0.19143 0.981325 + outer loop + vertex -194.903 12.5865 26.8047 + vertex -191.794 12.2703 26.8027 + vertex -196.109 13.3923 26.9387 + endloop + endfacet + facet normal -0.0174384 -0.186123 0.982372 + outer loop + vertex -191.794 12.2703 26.8027 + vertex -187.231 11.9129 26.816 + vertex -196.109 13.3923 26.9387 + endloop + endfacet + facet normal -0.0175765 -0.186939 0.982214 + outer loop + vertex -180.64 11.9417 26.9394 + vertex -196.109 13.3923 26.9387 + vertex -187.231 11.9129 26.816 + endloop + endfacet + facet normal -0.017518 -0.194255 0.980795 + outer loop + vertex -187.231 11.9129 26.816 + vertex -179.626 11.0575 26.7824 + vertex -180.64 11.9417 26.9394 + endloop + endfacet + facet normal -0.0172409 -0.193949 0.98086 + outer loop + vertex -179.626 11.0575 26.7824 + vertex -171.175 10.368 26.7946 + vertex -180.64 11.9417 26.9394 + endloop + endfacet + facet normal -0.0155857 -0.184169 0.982771 + outer loop + vertex -163.803 10.2793 26.8949 + vertex -180.64 11.9417 26.9394 + vertex -171.175 10.368 26.7946 + endloop + endfacet + facet normal -0.0156062 -0.186334 0.982363 + outer loop + vertex -171.175 10.368 26.7946 + vertex -165.455 9.73607 26.7656 + vertex -163.803 10.2793 26.8949 + endloop + endfacet + facet normal -0.0146122 -0.189229 0.981824 + outer loop + vertex -165.455 9.73607 26.7656 + vertex -159.842 9.2128 26.7483 + vertex -163.803 10.2793 26.8949 + endloop + endfacet + facet normal -0.0146584 -0.189396 0.981791 + outer loop + vertex -159.842 9.2128 26.7483 + vertex -152.804 8.76387 26.7668 + vertex -163.803 10.2793 26.8949 + endloop + endfacet + facet normal -0.0137366 -0.182812 0.983052 + outer loop + vertex -147.742 9.01885 26.885 + vertex -163.803 10.2793 26.8949 + vertex -152.804 8.76387 26.7668 + endloop + endfacet + facet normal -0.013502 -0.187097 0.982249 + outer loop + vertex -152.804 8.76387 26.7668 + vertex -146.486 8.18716 26.7438 + vertex -147.742 9.01885 26.885 + endloop + endfacet + facet normal -0.0123623 -0.185433 0.982579 + outer loop + vertex -146.486 8.18716 26.7438 + vertex -138.309 7.57042 26.7303 + vertex -147.742 9.01885 26.885 + endloop + endfacet + facet normal -0.0122828 -0.184926 0.982676 + outer loop + vertex -131.36 7.68964 26.8396 + vertex -147.742 9.01885 26.885 + vertex -138.309 7.57042 26.7303 + endloop + endfacet + facet normal -0.0122875 -0.184693 0.982719 + outer loop + vertex -138.309 7.57042 26.7303 + vertex -130.381 6.9229 26.7077 + vertex -131.36 7.68964 26.8396 + endloop + endfacet + facet normal -0.0114262 -0.18363 0.982929 + outer loop + vertex -130.381 6.9229 26.7077 + vertex -127.306 6.71785 26.7052 + vertex -131.36 7.68964 26.8396 + endloop + endfacet + facet normal -0.0105105 -0.179906 0.983628 + outer loop + vertex -127.306 6.71785 26.7052 + vertex -122.741 6.50996 26.7159 + vertex -131.36 7.68964 26.8396 + endloop + endfacet + facet normal -0.010496 -0.179802 0.983647 + outer loop + vertex -116.135 6.7645 26.8329 + vertex -131.36 7.68964 26.8396 + vertex -122.741 6.50996 26.7159 + endloop + endfacet + facet normal -0.0102403 -0.185916 0.982512 + outer loop + vertex -122.741 6.50996 26.7159 + vertex -115.406 5.9463 26.6857 + vertex -116.135 6.7645 26.8329 + endloop + endfacet + facet normal -0.0101243 -0.185816 0.982532 + outer loop + vertex -115.406 5.9463 26.6857 + vertex -107.01 5.54302 26.6959 + vertex -116.135 6.7645 26.8329 + endloop + endfacet + facet normal -0.00893797 -0.177135 0.984146 + outer loop + vertex -99.6599 5.70775 26.7924 + vertex -116.135 6.7645 26.8329 + vertex -107.01 5.54302 26.6959 + endloop + endfacet + facet normal -0.00889002 -0.17907 0.983796 + outer loop + vertex -107.01 5.54302 26.6959 + vertex -101.485 5.12678 26.6701 + vertex -99.6599 5.70775 26.7924 + endloop + endfacet + facet normal -0.0080468 -0.181621 0.983336 + outer loop + vertex -101.485 5.12678 26.6701 + vertex -95.9885 4.8028 26.6553 + vertex -99.6599 5.70775 26.7924 + endloop + endfacet + facet normal -0.00818265 -0.182157 0.983235 + outer loop + vertex -95.9885 4.8028 26.6553 + vertex -88.9118 4.57601 26.6721 + vertex -99.6599 5.70775 26.7924 + endloop + endfacet + facet normal -0.00748901 -0.175695 0.984416 + outer loop + vertex -83.7368 4.99331 26.786 + vertex -99.6599 5.70775 26.7924 + vertex -88.9118 4.57601 26.6721 + endloop + endfacet + facet normal -0.00712529 -0.179994 0.983642 + outer loop + vertex -88.9118 4.57601 26.6721 + vertex -82.7412 4.2343 26.6543 + vertex -83.7368 4.99331 26.786 + endloop + endfacet + facet normal -0.00626934 -0.178907 0.983846 + outer loop + vertex -82.7412 4.2343 26.6543 + vertex -74.5067 3.89062 26.6443 + vertex -83.7368 4.99331 26.786 + endloop + endfacet + facet normal -0.0062184 -0.17849 0.983922 + outer loop + vertex -67.1261 4.20352 26.7477 + vertex -83.7368 4.99331 26.786 + vertex -74.5067 3.89062 26.6443 + endloop + endfacet + facet normal -0.00620759 -0.178731 0.983878 + outer loop + vertex -74.5067 3.89062 26.6443 + vertex -66.5924 3.52148 26.6272 + vertex -67.1261 4.20352 26.7477 + endloop + endfacet + facet normal -0.00561069 -0.178279 0.983964 + outer loop + vertex -66.5924 3.52148 26.6272 + vertex -63.3422 3.40163 26.624 + vertex -67.1261 4.20352 26.7477 + endloop + endfacet + facet normal -0.00481734 -0.174637 0.984621 + outer loop + vertex -63.3422 3.40163 26.624 + vertex -58.5227 3.32497 26.634 + vertex -67.1261 4.20352 26.7477 + endloop + endfacet + facet normal -0.00479793 -0.174451 0.984654 + outer loop + vertex -50.4433 3.65721 26.7322 + vertex -67.1261 4.20352 26.7477 + vertex -58.5227 3.32497 26.634 + endloop + endfacet + facet normal -0.00448888 -0.181585 0.983365 + outer loop + vertex -58.5227 3.32497 26.634 + vertex -51.7337 3.01314 26.6074 + vertex -50.4433 3.65721 26.7322 + endloop + endfacet + facet normal -0.00458027 -0.181408 0.983397 + outer loop + vertex -51.7337 3.01314 26.6074 + vertex -45.6254 2.88838 26.6128 + vertex -50.4433 3.65721 26.7322 + endloop + endfacet + facet normal -0.00363445 -0.175645 0.984447 + outer loop + vertex -45.6254 2.88838 26.6128 + vertex -40.2876 2.85139 26.6259 + vertex -50.4433 3.65721 26.7322 + endloop + endfacet + facet normal -0.00348175 -0.173764 0.984781 + outer loop + vertex -34.2398 3.3776 26.7401 + vertex -50.4433 3.65721 26.7322 + vertex -40.2876 2.85139 26.6259 + endloop + endfacet + facet normal -0.00282848 -0.18099 0.983481 + outer loop + vertex -40.2876 2.85139 26.6259 + vertex -32.328 2.59404 26.6014 + vertex -34.2398 3.3776 26.7401 + endloop + endfacet + facet normal -0.00265436 -0.180579 0.983557 + outer loop + vertex -32.328 2.59404 26.6014 + vertex -24.2525 2.55761 26.6165 + vertex -34.2398 3.3776 26.7401 + endloop + endfacet + facet normal -0.00205751 -0.173501 0.984832 + outer loop + vertex -17.3905 3.01832 26.712 + vertex -34.2398 3.3776 26.7401 + vertex -24.2525 2.55761 26.6165 + endloop + endfacet + facet normal -0.00175483 -0.177849 0.984056 + outer loop + vertex -24.2525 2.55761 26.6165 + vertex -18.4681 2.37871 26.5945 + vertex -17.3905 3.01832 26.712 + endloop + endfacet + facet normal -0.000750169 -0.179487 0.98376 + outer loop + vertex -18.4681 2.37871 26.5945 + vertex -12.5209 2.30094 26.5849 + vertex -17.3905 3.01832 26.712 + endloop + endfacet + facet normal -0.00108758 -0.181705 0.983352 + outer loop + vertex -12.5209 2.30094 26.5849 + vertex -5.80822 2.37814 26.6066 + vertex -17.3905 3.01832 26.712 + endloop + endfacet + facet normal -0.00083851 -0.17733 0.984151 + outer loop + vertex -2.03578 3.0106 26.7237 + vertex -17.3905 3.01832 26.712 + vertex -5.80822 2.37814 26.6066 + endloop + endfacet + facet normal -0.000342553 -0.180192 0.983631 + outer loop + vertex -5.80822 2.37814 26.6066 + vertex -0.108635 2.31615 26.5972 + vertex -2.03578 3.0106 26.7237 + endloop + endfacet + facet normal 0.000331858 -0.178381 0.983961 + outer loop + vertex -0.108635 2.31615 26.5972 + vertex 5.43999 2.37828 26.6066 + vertex -2.03578 3.0106 26.7237 + endloop + endfacet + facet normal 0.000517986 -0.176251 0.984345 + outer loop + vertex 13.8313 2.98941 26.7116 + vertex -2.03578 3.0106 26.7237 + vertex 5.43999 2.37828 26.6066 + endloop + endfacet + facet normal 0.00100341 -0.182714 0.983166 + outer loop + vertex 5.43999 2.37828 26.6066 + vertex 12.0453 2.2932 26.584 + vertex 13.8313 2.98941 26.7116 + endloop + endfacet + facet normal 0.000812034 -0.182239 0.983254 + outer loop + vertex 12.0453 2.2932 26.584 + vertex 18.2762 2.37833 26.5947 + vertex 13.8313 2.98941 26.7116 + endloop + endfacet + facet normal 0.00165285 -0.176329 0.98433 + outer loop + vertex 18.2762 2.37833 26.5947 + vertex 23.5983 2.54578 26.6157 + vertex 13.8313 2.98941 26.7116 + endloop + endfacet + facet normal 0.00174643 -0.174345 0.984683 + outer loop + vertex 30.0167 3.29231 26.7365 + vertex 13.8313 2.98941 26.7116 + vertex 23.5983 2.54578 26.6157 + endloop + endfacet + facet normal 0.00261229 -0.181578 0.983373 + outer loop + vertex 23.5983 2.54578 26.6157 + vertex 31.4672 2.57579 26.6004 + vertex 30.0167 3.29231 26.7365 + endloop + endfacet + facet normal 0.00281755 -0.181176 0.983447 + outer loop + vertex 31.4672 2.57579 26.6004 + vertex 39.6848 2.84183 26.6258 + vertex 30.0167 3.29231 26.7365 + endloop + endfacet + facet normal 0.00320223 -0.17327 0.984869 + outer loop + vertex 47.0965 3.56865 26.7296 + vertex 30.0167 3.29231 26.7365 + vertex 39.6848 2.84183 26.6258 + endloop + endfacet + facet normal 0.003608 -0.177305 0.984149 + outer loop + vertex 39.6848 2.84183 26.6258 + vertex 45.4147 2.87958 26.6116 + vertex 47.0965 3.56865 26.7296 + endloop + endfacet + facet normal 0.00455704 -0.17955 0.983738 + outer loop + vertex 45.4147 2.87958 26.6116 + vertex 51.3768 3.00336 26.6066 + vertex 47.0965 3.56865 26.7296 + endloop + endfacet + facet normal 0.00440702 -0.180643 0.983539 + outer loop + vertex 51.3768 3.00336 26.6066 + vertex 58.4402 3.33042 26.635 + vertex 47.0965 3.56865 26.7296 + endloop + endfacet + facet normal 0.00453042 -0.17516 0.984529 + outer loop + vertex 63.9149 4.07953 26.7431 + vertex 47.0965 3.56865 26.7296 + vertex 58.4402 3.33042 26.635 + endloop + endfacet + facet normal 0.00485406 -0.177466 0.984115 + outer loop + vertex 58.4402 3.33042 26.635 + vertex 63.6872 3.41659 26.6247 + vertex 63.9149 4.07953 26.7431 + endloop + endfacet + facet normal 0.00565097 -0.17773 0.984063 + outer loop + vertex 63.6872 3.41659 26.6247 + vertex 66.8184 3.52692 26.6266 + vertex 63.9149 4.07953 26.7431 + endloop + endfacet + facet normal 0.00604953 -0.175712 0.984423 + outer loop + vertex 66.8184 3.52692 26.6266 + vertex 73.9074 3.86655 26.6437 + vertex 63.9149 4.07953 26.7431 + endloop + endfacet + facet normal 0.00597619 -0.178886 0.983852 + outer loop + vertex 79.7625 4.81509 26.7806 + vertex 63.9149 4.07953 26.7431 + vertex 73.9074 3.86655 26.6437 + endloop + endfacet + facet normal 0.00633396 -0.181037 0.983456 + outer loop + vertex 73.9074 3.86655 26.6437 + vertex 82.2886 4.2149 26.6538 + vertex 79.7625 4.81509 26.7806 + endloop + endfacet + facet normal 0.00703973 -0.178176 0.983973 + outer loop + vertex 82.2886 4.2149 26.6538 + vertex 88.4363 4.55625 26.6716 + vertex 79.7625 4.81509 26.7806 + endloop + endfacet + facet normal 0.00716017 -0.174423 0.984645 + outer loop + vertex 96.2653 5.53032 26.7873 + vertex 79.7625 4.81509 26.7806 + vertex 88.4363 4.55625 26.6716 + endloop + endfacet + facet normal 0.00814643 -0.182182 0.983231 + outer loop + vertex 88.4363 4.55625 26.6716 + vertex 95.4346 4.77532 26.6543 + vertex 96.2653 5.53032 26.7873 + endloop + endfacet + facet normal 0.00801414 -0.182041 0.983258 + outer loop + vertex 95.4346 4.77532 26.6543 + vertex 101.42 5.12269 26.6698 + vertex 96.2653 5.53032 26.7873 + endloop + endfacet + facet normal 0.00857826 -0.175261 0.984485 + outer loop + vertex 101.42 5.12269 26.6698 + vertex 106.588 5.51754 26.695 + vertex 96.2653 5.53032 26.7873 + endloop + endfacet + facet normal 0.00857558 -0.176206 0.984316 + outer loop + vertex 112.239 6.52403 26.826 + vertex 96.2653 5.53032 26.7873 + vertex 106.588 5.51754 26.695 + endloop + endfacet + facet normal 0.00998698 -0.183944 0.982886 + outer loop + vertex 106.588 5.51754 26.695 + vertex 114.869 5.91475 26.6852 + vertex 112.239 6.52403 26.826 + endloop + endfacet + facet normal 0.0100041 -0.183873 0.982899 + outer loop + vertex 114.869 5.91475 26.6852 + vertex 122.533 6.50114 26.7169 + vertex 112.239 6.52403 26.826 + endloop + endfacet + facet normal 0.0100281 -0.178117 0.983958 + outer loop + vertex 128.108 7.4609 26.8339 + vertex 112.239 6.52403 26.826 + vertex 122.533 6.50114 26.7169 + endloop + endfacet + facet normal 0.0104072 -0.18027 0.983562 + outer loop + vertex 122.533 6.50114 26.7169 + vertex 127.623 6.73055 26.7051 + vertex 128.108 7.4609 26.8339 + endloop + endfacet + facet normal 0.0114388 -0.180931 0.983429 + outer loop + vertex 127.623 6.73055 26.7051 + vertex 130.651 6.94234 26.7089 + vertex 128.108 7.4609 26.8339 + endloop + endfacet + facet normal 0.0118531 -0.178984 0.983781 + outer loop + vertex 130.651 6.94234 26.7089 + vertex 137.757 7.53106 26.7304 + vertex 128.108 7.4609 26.8339 + endloop + endfacet + facet normal 0.0118767 -0.183442 0.982959 + outer loop + vertex 143.923 8.72938 26.8795 + vertex 128.108 7.4609 26.8339 + vertex 137.757 7.53106 26.7304 + endloop + endfacet + facet normal 0.0123911 -0.186027 0.982466 + outer loop + vertex 137.757 7.53106 26.7304 + vertex 146.274 8.16688 26.7433 + vertex 143.923 8.72938 26.8795 + endloop + endfacet + facet normal 0.0132263 -0.182685 0.983082 + outer loop + vertex 146.274 8.16688 26.7433 + vertex 152.606 8.74564 26.7657 + vertex 143.923 8.72938 26.8795 + endloop + endfacet + facet normal 0.0132276 -0.180247 0.983532 + outer loop + vertex 160.969 10.0251 26.8877 + vertex 143.923 8.72938 26.8795 + vertex 152.606 8.74564 26.7657 + endloop + endfacet + facet normal 0.0148648 -0.190757 0.981525 + outer loop + vertex 152.606 8.74564 26.7657 + vertex 160.122 9.24314 26.7486 + vertex 160.969 10.0251 26.8877 + endloop + endfacet + facet normal 0.0147357 -0.190622 0.981553 + outer loop + vertex 160.122 9.24314 26.7486 + vertex 166.281 9.81218 26.7666 + vertex 160.969 10.0251 26.8877 + endloop + endfacet + facet normal 0.0150131 -0.184378 0.982741 + outer loop + vertex 166.281 9.81218 26.7666 + vertex 171.045 10.3229 26.7897 + vertex 160.969 10.0251 26.8877 + endloop + endfacet + facet normal 0.014931 -0.18142 0.983292 + outer loop + vertex 177.7 11.5453 26.9141 + vertex 160.969 10.0251 26.8877 + vertex 171.045 10.3229 26.7897 + endloop + endfacet + facet normal 0.0163163 -0.188818 0.981876 + outer loop + vertex 171.045 10.3229 26.7897 + vertex 175.874 10.6925 26.7805 + vertex 177.7 11.5453 26.9141 + endloop + endfacet + facet normal 0.0175852 -0.191452 0.981344 + outer loop + vertex 175.874 10.6925 26.7805 + vertex 181.34 11.1912 26.7798 + vertex 177.7 11.5453 26.9141 + endloop + endfacet + facet normal 0.0174419 -0.192824 0.981078 + outer loop + vertex 181.34 11.1912 26.7798 + vertex 188.641 12.0623 26.8212 + vertex 177.7 11.5453 26.9141 + endloop + endfacet + facet normal 0.0171927 -0.187359 0.982141 + outer loop + vertex 193.721 13.2596 26.9607 + vertex 177.7 11.5453 26.9141 + vertex 188.641 12.0623 26.8212 + endloop + endfacet + facet normal 0.0183535 -0.192173 0.981189 + outer loop + vertex 188.641 12.0623 26.8212 + vertex 194.973 12.6444 26.8168 + vertex 193.721 13.2596 26.9607 + endloop + endfacet + facet normal 0.0194005 -0.190131 0.981567 + outer loop + vertex 194.973 12.6444 26.8168 + vertex 202.772 13.497 26.8278 + vertex 193.721 13.2596 26.9607 + endloop + endfacet + facet normal 0.0194174 -0.190854 0.981426 + outer loop + vertex 210.452 14.975 26.9633 + vertex 193.721 13.2596 26.9607 + vertex 202.772 13.497 26.8278 + endloop + endfacet + facet normal 0.01968 -0.192194 0.98116 + outer loop + vertex 202.772 13.497 26.8278 + vertex 210.537 14.2999 26.8293 + vertex 210.452 14.975 26.9633 + endloop + endfacet + facet normal 0.020842 -0.192048 0.981164 + outer loop + vertex 210.537 14.2999 26.8293 + vertex 214.236 14.7199 26.833 + vertex 210.452 14.975 26.9633 + endloop + endfacet + facet normal 0.021232 -0.186776 0.982173 + outer loop + vertex 214.236 14.7199 26.833 + vertex 221.317 15.6048 26.8482 + vertex 210.452 14.975 26.9633 + endloop + endfacet + facet normal 0.0216136 -0.193602 0.980842 + outer loop + vertex 226.44 16.9476 27.0003 + vertex 210.452 14.975 26.9633 + vertex 221.317 15.6048 26.8482 + endloop + endfacet + facet normal 0.0225473 -0.197083 0.980128 + outer loop + vertex 221.317 15.6048 26.8482 + vertex 229.549 16.5783 26.8545 + vertex 226.44 16.9476 27.0003 + endloop + endfacet + facet normal 0.0231776 -0.192157 0.98109 + outer loop + vertex 229.549 16.5783 26.8545 + vertex 235.564 17.3989 26.8732 + vertex 226.44 16.9476 27.0003 + endloop + endfacet + facet normal 0.0231383 -0.191316 0.981256 + outer loop + vertex 243.105 18.9395 26.9957 + vertex 226.44 16.9476 27.0003 + vertex 235.564 17.3989 26.8732 + endloop + endfacet + facet normal 0.025141 -0.200961 0.979277 + outer loop + vertex 235.564 17.3989 26.8732 + vertex 243.278 18.237 26.8471 + vertex 243.105 18.9395 26.9957 + endloop + endfacet + facet normal 0.0251131 -0.200968 0.979276 + outer loop + vertex 243.278 18.237 26.8471 + vertex 249.114 19.0404 26.8623 + vertex 243.105 18.9395 26.9957 + endloop + endfacet + facet normal 0.0250394 -0.19497 0.98049 + outer loop + vertex 249.114 19.0404 26.8623 + vertex 253.411 19.7177 26.8873 + vertex 243.105 18.9395 26.9957 + endloop + endfacet + facet normal 0.0248987 -0.193052 0.980872 + outer loop + vertex 258.15 21.0586 27.0309 + vertex 243.105 18.9395 26.9957 + vertex 253.411 19.7177 26.8873 + endloop + endfacet + facet normal 0.0263437 -0.198048 0.979838 + outer loop + vertex 253.411 19.7177 26.8873 + vertex 258.813 20.3897 26.8779 + vertex 258.15 21.0586 27.0309 + endloop + endfacet + facet normal 0.0271544 -0.197275 0.979972 + outer loop + vertex 258.813 20.3897 26.8779 + vertex 266.564 21.5032 26.8872 + vertex 258.15 21.0586 27.0309 + endloop + endfacet + facet normal 0.0271587 -0.197362 0.979954 + outer loop + vertex 274.796 23.3181 27.0246 + vertex 258.15 21.0586 27.0309 + vertex 266.564 21.5032 26.8872 + endloop + endfacet + facet normal 0.0271137 -0.19716 0.979996 + outer loop + vertex 266.564 21.5032 26.8872 + vertex 274.544 22.587 26.8845 + vertex 274.796 23.3181 27.0246 + endloop + endfacet + facet normal 0.0282266 -0.197523 0.979892 + outer loop + vertex 274.544 22.587 26.8845 + vertex 278.326 23.1402 26.8871 + vertex 274.796 23.3181 27.0246 + endloop + endfacet + facet normal 0.0285034 -0.192759 0.980832 + outer loop + vertex 278.326 23.1402 26.8871 + vertex 285.469 24.266 26.9007 + vertex 274.796 23.3181 27.0246 + endloop + endfacet + facet normal 0.0289531 -0.19796 0.979782 + outer loop + vertex 290.97 25.8393 27.056 + vertex 274.796 23.3181 27.0246 + vertex 285.469 24.266 26.9007 + endloop + endfacet + facet normal 0.0298474 -0.201023 0.979132 + outer loop + vertex 285.469 24.266 26.9007 + vertex 293.738 25.5148 26.9051 + vertex 290.97 25.8393 27.056 + endloop + endfacet + facet normal 0.0303081 -0.197428 0.979849 + outer loop + vertex 293.738 25.5148 26.9051 + vertex 299.894 26.5268 26.9186 + vertex 290.97 25.8393 27.056 + endloop + endfacet + facet normal 0.0301849 -0.195761 0.980187 + outer loop + vertex 307.567 28.3418 27.0447 + vertex 290.97 25.8393 27.056 + vertex 299.894 26.5268 26.9186 + endloop + endfacet + facet normal 0.0320882 -0.203692 0.978509 + outer loop + vertex 299.894 26.5268 26.9186 + vertex 307.47 27.5823 26.8898 + vertex 307.567 28.3418 27.0447 + endloop + endfacet + facet normal 0.0320081 -0.203682 0.978514 + outer loop + vertex 307.47 27.5823 26.8898 + vertex 313.339 28.5673 26.9029 + vertex 307.567 28.3418 27.0447 + endloop + endfacet + facet normal 0.0318775 -0.19984 0.97931 + outer loop + vertex 313.339 28.5673 26.9029 + vertex 317.646 29.3799 26.9285 + vertex 307.567 28.3418 27.0447 + endloop + endfacet + facet normal 0.03207 -0.201753 0.978911 + outer loop + vertex 322.528 30.8912 27.08 + vertex 307.567 28.3418 27.0447 + vertex 317.646 29.3799 26.9285 + endloop + endfacet + facet normal 0.0332664 -0.205535 0.978084 + outer loop + vertex 317.646 29.3799 26.9285 + vertex 322.933 30.1929 26.9195 + vertex 322.528 30.8912 27.08 + endloop + endfacet + facet normal 0.0332793 -0.205528 0.978085 + outer loop + vertex 322.933 30.1929 26.9195 + vertex 330.48 31.5024 26.9379 + vertex 322.528 30.8912 27.08 + endloop + endfacet + facet normal 0.0335787 -0.209628 0.977204 + outer loop + vertex 338.745 33.5777 27.0991 + vertex 322.528 30.8912 27.08 + vertex 330.48 31.5024 26.9379 + endloop + endfacet + facet normal 0.0347436 -0.214187 0.976175 + outer loop + vertex 330.48 31.5024 26.9379 + vertex 338.245 32.789 26.9438 + vertex 338.745 33.5777 27.0991 + endloop + endfacet + facet normal 0.03431 -0.213927 0.976247 + outer loop + vertex 338.245 32.789 26.9438 + vertex 341.944 33.4358 26.9556 + vertex 338.745 33.5777 27.0991 + endloop + endfacet + facet normal 0.0340756 -0.218249 0.975298 + outer loop + vertex 341.944 33.4358 26.9556 + vertex 348.876 34.7375 27.0047 + vertex 338.745 33.5777 27.0991 + endloop + endfacet + facet normal 0.0342233 -0.219563 0.974998 + outer loop + vertex 354.539 36.5117 27.2054 + vertex 338.745 33.5777 27.0991 + vertex 348.876 34.7375 27.0047 + endloop + endfacet + facet normal 0.0341743 -0.219411 0.975034 + outer loop + vertex 348.876 34.7375 27.0047 + vertex 356.934 36.1916 27.0495 + vertex 354.539 36.5117 27.2054 + endloop + endfacet + facet normal 0.0335731 -0.22347 0.974132 + outer loop + vertex 356.934 36.1916 27.0495 + vertex 363.027 37.3735 27.1106 + vertex 354.539 36.5117 27.2054 + endloop + endfacet + facet normal 0.0342944 -0.230764 0.972405 + outer loop + vertex 371.021 39.4451 27.3203 + vertex 354.539 36.5117 27.2054 + vertex 363.027 37.3735 27.1106 + endloop + endfacet + facet normal 0.0333446 -0.227188 0.97328 + outer loop + vertex 363.027 37.3735 27.1106 + vertex 370.274 38.5862 27.1454 + vertex 371.021 39.4451 27.3203 + endloop + endfacet + facet normal 0.0334738 -0.227294 0.973251 + outer loop + vertex 370.274 38.5862 27.1454 + vertex 376.225 39.7389 27.2099 + vertex 371.021 39.4451 27.3203 + endloop + endfacet + facet normal 0.0340427 -0.238377 0.970576 + outer loop + vertex 376.225 39.7389 27.2099 + vertex 380.741 40.6833 27.2835 + vertex 371.021 39.4451 27.3203 + endloop + endfacet + facet normal 0.0360018 -0.253875 0.966567 + outer loop + vertex 387.008 42.4975 27.5265 + vertex 371.021 39.4451 27.3203 + vertex 380.741 40.6833 27.2835 + endloop + endfacet + facet normal 0.0367065 -0.256223 0.96592 + outer loop + vertex 380.741 40.6833 27.2835 + vertex 385.365 41.4854 27.3205 + vertex 387.008 42.4975 27.5265 + endloop + endfacet + facet normal 0.0341506 -0.252302 0.967046 + outer loop + vertex 385.365 41.4854 27.3205 + vertex 390.482 42.4462 27.3905 + vertex 387.008 42.4975 27.5265 + endloop + endfacet + facet normal 0.03408 -0.255125 0.966307 + outer loop + vertex 390.482 42.4462 27.3905 + vertex 397.299 43.9412 27.5448 + vertex 387.008 42.4975 27.5265 + endloop + endfacet + facet normal 0.0418448 -0.310261 0.94973 + outer loop + vertex 402.179 45.6762 27.8965 + vertex 387.008 42.4975 27.5265 + vertex 397.299 43.9412 27.5448 + endloop + endfacet + facet normal 0.0429179 -0.313082 0.948756 + outer loop + vertex 397.299 43.9412 27.5448 + vertex 403.197 45.0564 27.6459 + vertex 402.179 45.6762 27.8965 + endloop + endfacet + facet normal 0.0376294 -0.320818 0.946393 + outer loop + vertex 403.197 45.0564 27.6459 + vertex 410.834 46.6771 27.8917 + vertex 402.179 45.6762 27.8965 + endloop + endfacet + facet normal 0.00719396 -0.128028 0.991744 + outer loop + vertex 403.197 45.0564 27.6459 + vertex 397.299 43.9412 27.5448 + vertex 398.632 43.896 27.5293 + endloop + endfacet + facet normal 0.00697924 -0.134091 0.990944 + outer loop + vertex 397.299 43.9412 27.5448 + vertex 390.482 42.4462 27.3905 + vertex 398.632 43.896 27.5293 + endloop + endfacet + facet normal 0.025582 -0.192779 0.980909 + outer loop + vertex 385.365 41.4854 27.3205 + vertex 380.741 40.6833 27.2835 + vertex 378.74 40.0039 27.2021 + endloop + endfacet + facet normal 0.0223837 -0.18358 0.98275 + outer loop + vertex 380.741 40.6833 27.2835 + vertex 376.225 39.7389 27.2099 + vertex 378.74 40.0039 27.2021 + endloop + endfacet + facet normal 0.0313692 -0.214478 0.976225 + outer loop + vertex 371.021 39.4451 27.3203 + vertex 356.741 38.8 27.6374 + vertex 354.539 36.5117 27.2054 + endloop + endfacet + facet normal 0.0324194 -0.215442 0.975978 + outer loop + vertex 356.741 38.8 27.6374 + vertex 340.79 35.9467 27.5374 + vertex 354.539 36.5117 27.2054 + endloop + endfacet + facet normal 0.0298411 -0.201138 0.979108 + outer loop + vertex 356.741 38.8 27.6374 + vertex 341.173 38.761 28.1039 + vertex 340.79 35.9467 27.5374 + endloop + endfacet + facet normal 0.0306488 -0.201239 0.979063 + outer loop + vertex 341.173 38.761 28.1039 + vertex 325.207 36.0112 28.0385 + vertex 340.79 35.9467 27.5374 + endloop + endfacet + facet normal 0.0306888 -0.197493 0.979824 + outer loop + vertex 340.79 35.9467 27.5374 + vertex 325.207 36.0112 28.0385 + vertex 324.835 33.1855 27.4806 + endloop + endfacet + facet normal 0.0326994 -0.20906 0.977356 + outer loop + vertex 340.79 35.9467 27.5374 + vertex 324.835 33.1855 27.4806 + vertex 338.745 33.5777 27.0991 + endloop + endfacet + facet normal 0.0306033 -0.197483 0.979829 + outer loop + vertex 325.207 36.0112 28.0385 + vertex 309.116 33.3224 27.9991 + vertex 324.835 33.1855 27.4806 + endloop + endfacet + facet normal 0.0306383 -0.195196 0.980286 + outer loop + vertex 324.835 33.1855 27.4806 + vertex 309.116 33.3224 27.9991 + vertex 308.88 30.5439 27.4532 + endloop + endfacet + facet normal 0.0319271 -0.202963 0.978666 + outer loop + vertex 324.835 33.1855 27.4806 + vertex 308.88 30.5439 27.4532 + vertex 322.528 30.8912 27.08 + endloop + endfacet + facet normal 0.0297059 -0.195125 0.980328 + outer loop + vertex 309.116 33.3224 27.9991 + vertex 292.875 30.7486 27.979 + vertex 308.88 30.5439 27.4532 + endloop + endfacet + facet normal 0.0297352 -0.193607 0.980628 + outer loop + vertex 308.88 30.5439 27.4532 + vertex 292.875 30.7486 27.979 + vertex 292.784 27.9984 27.4387 + endloop + endfacet + facet normal 0.030748 -0.200004 0.979312 + outer loop + vertex 308.88 30.5439 27.4532 + vertex 292.784 27.9984 27.4387 + vertex 307.567 28.3418 27.0447 + endloop + endfacet + facet normal 0.0282984 -0.19357 0.980678 + outer loop + vertex 292.875 30.7486 27.979 + vertex 276.556 28.2796 27.9625 + vertex 292.784 27.9984 27.4387 + endloop + endfacet + facet normal 0.0283114 -0.193021 0.980786 + outer loop + vertex 292.784 27.9984 27.4387 + vertex 276.556 28.2796 27.9625 + vertex 276.467 25.5476 27.4275 + endloop + endfacet + facet normal 0.0290736 -0.198091 0.979752 + outer loop + vertex 292.784 27.9984 27.4387 + vertex 276.467 25.5476 27.4275 + vertex 290.97 25.8393 27.056 + endloop + endfacet + facet normal 0.0265744 -0.192976 0.980844 + outer loop + vertex 276.556 28.2796 27.9625 + vertex 260.198 25.9316 27.9438 + vertex 276.467 25.5476 27.4275 + endloop + endfacet + facet normal 0.0265906 -0.192433 0.98095 + outer loop + vertex 276.467 25.5476 27.4275 + vertex 260.198 25.9316 27.9438 + vertex 260.159 23.2076 27.4105 + endloop + endfacet + facet normal 0.0273237 -0.197534 0.979915 + outer loop + vertex 276.467 25.5476 27.4275 + vertex 260.159 23.2076 27.4105 + vertex 274.796 23.3181 27.0246 + endloop + endfacet + facet normal 0.0247262 -0.192416 0.981002 + outer loop + vertex 260.198 25.9316 27.9438 + vertex 243.824 23.7092 27.9206 + vertex 260.159 23.2076 27.4105 + endloop + endfacet + facet normal 0.0247548 -0.191639 0.981153 + outer loop + vertex 260.159 23.2076 27.4105 + vertex 243.824 23.7092 27.9206 + vertex 243.95 21.0207 27.3923 + endloop + endfacet + facet normal 0.0254694 -0.196927 0.980087 + outer loop + vertex 260.159 23.2076 27.4105 + vertex 243.95 21.0207 27.3923 + vertex 258.15 21.0586 27.0309 + endloop + endfacet + facet normal 0.0228183 -0.191736 0.981181 + outer loop + vertex 243.824 23.7092 27.9206 + vertex 227.459 21.6235 27.8936 + vertex 243.95 21.0207 27.3923 + endloop + endfacet + facet normal 0.0228706 -0.190503 0.98142 + outer loop + vertex 243.95 21.0207 27.3923 + vertex 227.459 21.6235 27.8936 + vertex 227.737 18.9781 27.3736 + endloop + endfacet + facet normal 0.023611 -0.19637 0.980246 + outer loop + vertex 243.95 21.0207 27.3923 + vertex 227.737 18.9781 27.3736 + vertex 243.105 18.9395 26.9957 + endloop + endfacet + facet normal 0.020821 -0.190719 0.981424 + outer loop + vertex 227.459 21.6235 27.8936 + vertex 211.143 19.6917 27.8643 + vertex 227.737 18.9781 27.3736 + endloop + endfacet + facet normal 0.0209447 -0.188178 0.981912 + outer loop + vertex 227.737 18.9781 27.3736 + vertex 211.143 19.6917 27.8643 + vertex 211.532 17.0461 27.349 + endloop + endfacet + facet normal 0.0216568 -0.194136 0.980736 + outer loop + vertex 227.737 18.9781 27.3736 + vertex 211.532 17.0461 27.349 + vertex 226.44 16.9476 27.0003 + endloop + endfacet + facet normal 0.0187326 -0.1885 0.981895 + outer loop + vertex 211.143 19.6917 27.8643 + vertex 194.939 17.9051 27.8305 + vertex 211.532 17.0461 27.349 + endloop + endfacet + facet normal 0.0188532 -0.186394 0.982294 + outer loop + vertex 211.532 17.0461 27.349 + vertex 194.939 17.9051 27.8305 + vertex 195.347 15.2738 27.3234 + endloop + endfacet + facet normal 0.0195702 -0.192924 0.981019 + outer loop + vertex 211.532 17.0461 27.349 + vertex 195.347 15.2738 27.3234 + vertex 210.452 14.975 26.9633 + endloop + endfacet + facet normal 0.0166005 -0.186739 0.982269 + outer loop + vertex 194.939 17.9051 27.8305 + vertex 178.778 16.2722 27.7932 + vertex 195.347 15.2738 27.3234 + endloop + endfacet + facet normal 0.0167733 -0.184104 0.982764 + outer loop + vertex 195.347 15.2738 27.3234 + vertex 178.778 16.2722 27.7932 + vertex 179.105 13.6339 27.2934 + endloop + endfacet + facet normal 0.0174518 -0.190801 0.981474 + outer loop + vertex 195.347 15.2738 27.3234 + vertex 179.105 13.6339 27.2934 + vertex 193.721 13.2596 26.9607 + endloop + endfacet + facet normal 0.0145439 -0.184377 0.982748 + outer loop + vertex 178.778 16.2722 27.7932 + vertex 162.539 14.7745 27.7525 + vertex 179.105 13.6339 27.2934 + endloop + endfacet + facet normal 0.0147539 -0.181538 0.983273 + outer loop + vertex 179.105 13.6339 27.2934 + vertex 162.539 14.7745 27.7525 + vertex 162.71 12.1152 27.259 + endloop + endfacet + facet normal 0.0154167 -0.188662 0.981921 + outer loop + vertex 179.105 13.6339 27.2934 + vertex 162.71 12.1152 27.259 + vertex 177.7 11.5453 26.9141 + endloop + endfacet + facet normal 0.0126375 -0.181675 0.983277 + outer loop + vertex 162.539 14.7745 27.7525 + vertex 146.176 13.409 27.7105 + vertex 162.71 12.1152 27.259 + endloop + endfacet + facet normal 0.0129063 -0.178445 0.983865 + outer loop + vertex 162.71 12.1152 27.259 + vertex 146.176 13.409 27.7105 + vertex 146.117 10.7441 27.228 + endloop + endfacet + facet normal 0.0135152 -0.185783 0.982498 + outer loop + vertex 162.71 12.1152 27.259 + vertex 146.117 10.7441 27.228 + vertex 160.969 10.0251 26.8877 + endloop + endfacet + facet normal 0.0109671 -0.178408 0.983896 + outer loop + vertex 146.176 13.409 27.7105 + vertex 129.807 12.1669 27.6677 + vertex 146.117 10.7441 27.228 + endloop + endfacet + facet normal 0.0111931 -0.175952 0.984335 + outer loop + vertex 146.117 10.7441 27.228 + vertex 129.807 12.1669 27.6677 + vertex 129.732 9.51443 27.1945 + endloop + endfacet + facet normal 0.0117085 -0.182785 0.983083 + outer loop + vertex 146.117 10.7441 27.228 + vertex 129.732 9.51443 27.1945 + vertex 143.923 8.72938 26.8795 + endloop + endfacet + facet normal 0.0093971 -0.175906 0.984362 + outer loop + vertex 129.807 12.1669 27.6677 + vertex 113.556 11.0721 27.6272 + vertex 129.732 9.51443 27.1945 + endloop + endfacet + facet normal 0.00963933 -0.173508 0.984785 + outer loop + vertex 129.732 9.51443 27.1945 + vertex 113.556 11.0721 27.6272 + vertex 113.634 8.43548 27.1619 + endloop + endfacet + facet normal 0.010125 -0.180715 0.983483 + outer loop + vertex 129.732 9.51443 27.1945 + vertex 113.634 8.43548 27.1619 + vertex 128.108 7.4609 26.8339 + endloop + endfacet + facet normal 0.00809405 -0.173555 0.984791 + outer loop + vertex 113.556 11.0721 27.6272 + vertex 97.435 10.1043 27.5892 + vertex 113.634 8.43548 27.1619 + endloop + endfacet + facet normal 0.00826988 -0.171921 0.985076 + outer loop + vertex 113.634 8.43548 27.1619 + vertex 97.435 10.1043 27.5892 + vertex 97.5969 7.49817 27.133 + endloop + endfacet + facet normal 0.00870087 -0.179254 0.983764 + outer loop + vertex 113.634 8.43548 27.1619 + vertex 97.5969 7.49817 27.133 + vertex 112.239 6.52403 26.826 + endloop + endfacet + facet normal 0.00685346 -0.172008 0.985072 + outer loop + vertex 97.435 10.1043 27.5892 + vertex 81.3604 9.26842 27.5551 + vertex 97.5969 7.49817 27.133 + endloop + endfacet + facet normal 0.0069716 -0.170968 0.985252 + outer loop + vertex 97.5969 7.49817 27.133 + vertex 81.3604 9.26842 27.5551 + vertex 81.4749 6.69106 27.107 + endloop + endfacet + facet normal 0.00731722 -0.177832 0.984034 + outer loop + vertex 97.5969 7.49817 27.133 + vertex 81.4749 6.69106 27.107 + vertex 96.2653 5.53032 26.7873 + endloop + endfacet + facet normal 0.00564423 -0.171026 0.98525 + outer loop + vertex 81.3604 9.26842 27.5551 + vertex 65.2323 8.57034 27.5263 + vertex 81.4749 6.69106 27.107 + endloop + endfacet + facet normal 0.00572863 -0.170324 0.985371 + outer loop + vertex 81.4749 6.69106 27.107 + vertex 65.2323 8.57034 27.5263 + vertex 65.2758 6.0092 27.0833 + endloop + endfacet + facet normal 0.00600057 -0.176745 0.984238 + outer loop + vertex 81.4749 6.69106 27.107 + vertex 65.2758 6.0092 27.0833 + vertex 79.7625 4.81509 26.7806 + endloop + endfacet + facet normal 0.00445928 -0.170346 0.985374 + outer loop + vertex 65.2323 8.57034 27.5263 + vertex 49.022 8.00577 27.502 + vertex 65.2758 6.0092 27.0833 + endloop + endfacet + facet normal 0.00447762 -0.170202 0.985399 + outer loop + vertex 65.2758 6.0092 27.0833 + vertex 49.022 8.00577 27.502 + vertex 48.9385 5.4554 27.0619 + endloop + endfacet + facet normal 0.00470462 -0.176853 0.984226 + outer loop + vertex 65.2758 6.0092 27.0833 + vertex 48.9385 5.4554 27.0619 + vertex 63.9149 4.07953 26.7431 + endloop + endfacet + facet normal 0.00323834 -0.170163 0.985411 + outer loop + vertex 49.022 8.00577 27.502 + vertex 32.7445 7.59188 27.4841 + vertex 48.9385 5.4554 27.0619 + endloop + endfacet + facet normal 0.0032489 -0.170086 0.985424 + outer loop + vertex 48.9385 5.4554 27.0619 + vertex 32.7445 7.59188 27.4841 + vertex 32.4005 5.07526 27.0508 + endloop + endfacet + facet normal 0.00340124 -0.176679 0.984263 + outer loop + vertex 48.9385 5.4554 27.0619 + vertex 32.4005 5.07526 27.0508 + vertex 47.0965 3.56865 26.7296 + endloop + endfacet + facet normal 0.00199968 -0.169921 0.985456 + outer loop + vertex 32.7445 7.59188 27.4841 + vertex 16.4791 7.33707 27.4731 + vertex 32.4005 5.07526 27.0508 + endloop + endfacet + facet normal 0.00194612 -0.170286 0.985393 + outer loop + vertex 32.4005 5.07526 27.0508 + vertex 16.4791 7.33707 27.4731 + vertex 16.0308 4.83649 27.0419 + endloop + endfacet + facet normal 0.00203362 -0.176245 0.984344 + outer loop + vertex 32.4005 5.07526 27.0508 + vertex 16.0308 4.83649 27.0419 + vertex 30.0167 3.29231 26.7365 + endloop + endfacet + facet normal 0.00065126 -0.170061 0.985433 + outer loop + vertex 16.4791 7.33707 27.4731 + vertex 0.273026 7.25446 27.4696 + vertex 16.0308 4.83649 27.0419 + endloop + endfacet + facet normal 0.000619807 -0.17026 0.985399 + outer loop + vertex 16.0308 4.83649 27.0419 + vertex 0.273026 7.25446 27.4696 + vertex -0.125221 4.75224 27.0375 + endloop + endfacet + facet normal 0.000654153 -0.176786 0.984249 + outer loop + vertex 16.0308 4.83649 27.0419 + vertex -0.125221 4.75224 27.0375 + vertex 13.8313 2.98941 26.7116 + endloop + endfacet + facet normal -0.000645522 -0.170064 0.985433 + outer loop + vertex 0.273026 7.25446 27.4696 + vertex -15.8964 7.33689 27.4732 + vertex -0.125221 4.75224 27.0375 + endloop + endfacet + facet normal -0.000677534 -0.170254 0.9854 + outer loop + vertex -0.125221 4.75224 27.0375 + vertex -15.8964 7.33689 27.4732 + vertex -16.1778 4.84034 27.0417 + endloop + endfacet + facet normal -0.000712338 -0.176543 0.984293 + outer loop + vertex -0.125221 4.75224 27.0375 + vertex -16.1778 4.84034 27.0417 + vertex -2.03578 3.0106 26.7237 + endloop + endfacet + facet normal -0.00191615 -0.170118 0.985422 + outer loop + vertex -15.8964 7.33689 27.4732 + vertex -32.0644 7.59072 27.4856 + vertex -16.1778 4.84034 27.0417 + endloop + endfacet + facet normal -0.00192753 -0.170182 0.985411 + outer loop + vertex -16.1778 4.84034 27.0417 + vertex -32.0644 7.59072 27.4856 + vertex -32.3293 5.08684 27.0527 + endloop + endfacet + facet normal -0.00202811 -0.176722 0.984259 + outer loop + vertex -16.1778 4.84034 27.0417 + vertex -32.3293 5.08684 27.0527 + vertex -17.3905 3.01832 26.712 + endloop + endfacet + facet normal -0.00318302 -0.170052 0.98543 + outer loop + vertex -32.0644 7.59072 27.4856 + vertex -48.2346 8.0096 27.5057 + vertex -32.3293 5.08684 27.0527 + endloop + endfacet + facet normal -0.00318135 -0.170044 0.985431 + outer loop + vertex -32.3293 5.08684 27.0527 + vertex -48.2346 8.0096 27.5057 + vertex -48.6043 5.47463 27.067 + endloop + endfacet + facet normal -0.00333036 -0.176257 0.984339 + outer loop + vertex -32.3293 5.08684 27.0527 + vertex -48.6043 5.47463 27.067 + vertex -34.2398 3.3776 26.7401 + endloop + endfacet + facet normal -0.0043508 -0.169877 0.985456 + outer loop + vertex -48.2346 8.0096 27.5057 + vertex -64.4084 8.56722 27.5304 + vertex -48.6043 5.47463 27.067 + endloop + endfacet + facet normal -0.00448447 -0.170543 0.98534 + outer loop + vertex -48.6043 5.47463 27.067 + vertex -64.4084 8.56722 27.5304 + vertex -64.942 6.00218 27.084 + endloop + endfacet + facet normal -0.00468143 -0.176608 0.98427 + outer loop + vertex -48.6043 5.47463 27.067 + vertex -64.942 6.00218 27.084 + vertex -50.4433 3.65721 26.7322 + endloop + endfacet + facet normal -0.00546889 -0.170343 0.98537 + outer loop + vertex -64.4084 8.56722 27.5304 + vertex -80.5778 9.25754 27.56 + vertex -64.942 6.00218 27.084 + endloop + endfacet + facet normal -0.00569029 -0.17138 0.985189 + outer loop + vertex -64.942 6.00218 27.084 + vertex -80.5778 9.25754 27.56 + vertex -81.3138 6.69621 27.1102 + endloop + endfacet + facet normal -0.00592291 -0.176831 0.984223 + outer loop + vertex -64.942 6.00218 27.084 + vertex -81.3138 6.69621 27.1102 + vertex -67.1261 4.20352 26.7477 + endloop + endfacet + facet normal -0.00661146 -0.171122 0.985228 + outer loop + vertex -80.5778 9.25754 27.56 + vertex -96.6672 10.077 27.5943 + vertex -81.3138 6.69621 27.1102 + endloop + endfacet + facet normal -0.00694229 -0.172588 0.98497 + outer loop + vertex -81.3138 6.69621 27.1102 + vertex -96.6672 10.077 27.5943 + vertex -97.4477 7.49712 27.1368 + endloop + endfacet + facet normal -0.00717011 -0.17715 0.984158 + outer loop + vertex -81.3138 6.69621 27.1102 + vertex -97.4477 7.49712 27.1368 + vertex -83.7368 4.99331 26.786 + endloop + endfacet + facet normal -0.00784588 -0.172322 0.98501 + outer loop + vertex -96.6672 10.077 27.5943 + vertex -112.682 11.023 27.6323 + vertex -97.4477 7.49712 27.1368 + endloop + endfacet + facet normal -0.00835967 -0.174487 0.984624 + outer loop + vertex -97.4477 7.49712 27.1368 + vertex -112.682 11.023 27.6323 + vertex -113.517 8.43785 27.1671 + endloop + endfacet + facet normal -0.00860965 -0.178733 0.98386 + outer loop + vertex -97.4477 7.49712 27.1368 + vertex -113.517 8.43785 27.1671 + vertex -99.6599 5.70775 26.7924 + endloop + endfacet + facet normal -0.00916146 -0.174235 0.984661 + outer loop + vertex -112.682 11.023 27.6323 + vertex -128.742 12.0932 27.6722 + vertex -113.517 8.43785 27.1671 + endloop + endfacet + facet normal -0.00983041 -0.176953 0.98417 + outer loop + vertex -113.517 8.43785 27.1671 + vertex -128.742 12.0932 27.6722 + vertex -129.526 9.49691 27.1976 + endloop + endfacet + facet normal -0.0100742 -0.180619 0.983502 + outer loop + vertex -113.517 8.43785 27.1671 + vertex -129.526 9.49691 27.1976 + vertex -116.135 6.7645 26.8329 + endloop + endfacet + facet normal -0.0106904 -0.176701 0.984207 + outer loop + vertex -128.742 12.0932 27.6722 + vertex -144.921 13.3013 27.7134 + vertex -129.526 9.49691 27.1976 + endloop + endfacet + facet normal -0.0114559 -0.179723 0.983651 + outer loop + vertex -129.526 9.49691 27.1976 + vertex -144.921 13.3013 27.7134 + vertex -145.631 10.7069 27.2311 + endloop + endfacet + facet normal -0.0116929 -0.182862 0.983069 + outer loop + vertex -129.526 9.49691 27.1976 + vertex -145.631 10.7069 27.2311 + vertex -131.36 7.68964 26.8396 + endloop + endfacet + facet normal -0.0124246 -0.179464 0.983686 + outer loop + vertex -144.921 13.3013 27.7134 + vertex -161.226 14.6604 27.7554 + vertex -145.631 10.7069 27.2311 + endloop + endfacet + facet normal -0.0131403 -0.182219 0.98317 + outer loop + vertex -145.631 10.7069 27.2311 + vertex -161.226 14.6604 27.7554 + vertex -161.881 12.0481 27.2625 + endloop + endfacet + facet normal -0.013354 -0.184796 0.982686 + outer loop + vertex -145.631 10.7069 27.2311 + vertex -161.881 12.0481 27.2625 + vertex -147.742 9.01885 26.885 + endloop + endfacet + facet normal -0.0143457 -0.181924 0.983208 + outer loop + vertex -161.226 14.6604 27.7554 + vertex -177.568 16.1645 27.7953 + vertex -161.881 12.0481 27.2625 + endloop + endfacet + facet normal -0.015128 -0.184834 0.982653 + outer loop + vertex -161.881 12.0481 27.2625 + vertex -177.568 16.1645 27.7953 + vertex -178.236 13.5582 27.2947 + endloop + endfacet + facet normal -0.0153652 -0.187392 0.982165 + outer loop + vertex -161.881 12.0481 27.2625 + vertex -178.236 13.5582 27.2947 + vertex -163.803 10.2793 26.8949 + endloop + endfacet + facet normal -0.0164159 -0.184511 0.982693 + outer loop + vertex -177.568 16.1645 27.7953 + vertex -193.884 17.8094 27.8315 + vertex -178.236 13.5582 27.2947 + endloop + endfacet + facet normal -0.0171367 -0.187101 0.982191 + outer loop + vertex -178.236 13.5582 27.2947 + vertex -193.884 17.8094 27.8315 + vertex -194.501 15.1913 27.322 + endloop + endfacet + facet normal -0.0174147 -0.189861 0.981657 + outer loop + vertex -178.236 13.5582 27.2947 + vertex -194.501 15.1913 27.322 + vertex -180.64 11.9417 26.9394 + endloop + endfacet + facet normal -0.0185042 -0.186786 0.982226 + outer loop + vertex -193.884 17.8094 27.8315 + vertex -210.172 19.5925 27.8638 + vertex -194.501 15.1913 27.322 + endloop + endfacet + facet normal -0.0191883 -0.189164 0.981758 + outer loop + vertex -194.501 15.1913 27.322 + vertex -210.172 19.5925 27.8638 + vertex -210.848 16.973 27.3458 + endloop + endfacet + facet normal -0.0194647 -0.191692 0.981262 + outer loop + vertex -194.501 15.1913 27.322 + vertex -210.848 16.973 27.3458 + vertex -196.109 13.3923 26.9387 + endloop + endfacet + facet normal -0.0205481 -0.18882 0.981797 + outer loop + vertex -210.172 19.5925 27.8638 + vertex -226.465 21.5207 27.8936 + vertex -210.848 16.973 27.3458 + endloop + endfacet + facet normal -0.0211436 -0.190817 0.981398 + outer loop + vertex -210.848 16.973 27.3458 + vertex -226.465 21.5207 27.8936 + vertex -227.342 18.9382 27.3726 + endloop + endfacet + facet normal -0.0214297 -0.193213 0.980923 + outer loop + vertex -210.848 16.973 27.3458 + vertex -227.342 18.9382 27.3726 + vertex -213.339 15.3044 26.9627 + endloop + endfacet + facet normal -0.0224964 -0.19037 0.981455 + outer loop + vertex -226.465 21.5207 27.8936 + vertex -242.754 23.5981 27.9232 + vertex -227.342 18.9382 27.3726 + endloop + endfacet + facet normal -0.0230028 -0.192006 0.981124 + outer loop + vertex -227.342 18.9382 27.3726 + vertex -242.754 23.5981 27.9232 + vertex -243.614 20.992 27.393 + endloop + endfacet + facet normal -0.0233639 -0.194861 0.980553 + outer loop + vertex -227.342 18.9382 27.3726 + vertex -243.614 20.992 27.393 + vertex -230.219 17.4213 27.0026 + endloop + endfacet + facet normal -0.0241925 -0.191622 0.98117 + outer loop + vertex -242.754 23.5981 27.9232 + vertex -258.986 25.7626 27.9457 + vertex -243.614 20.992 27.393 + endloop + endfacet + facet normal -0.0249665 -0.194059 0.980672 + outer loop + vertex -243.614 20.992 27.393 + vertex -258.986 25.7626 27.9457 + vertex -259.723 23.1592 27.4118 + endloop + endfacet + facet normal -0.0254258 -0.197467 0.97998 + outer loop + vertex -243.614 20.992 27.393 + vertex -259.723 23.1592 27.4118 + vertex -246.164 19.351 26.9962 + endloop + endfacet + facet normal -0.0263432 -0.193677 0.980712 + outer loop + vertex -258.986 25.7626 27.9457 + vertex -275.221 28.0699 27.9652 + vertex -259.723 23.1592 27.4118 + endloop + endfacet + facet normal -0.0267863 -0.195044 0.980429 + outer loop + vertex -259.723 23.1592 27.4118 + vertex -275.221 28.0699 27.9652 + vertex -275.871 25.4557 27.4274 + endloop + endfacet + facet normal -0.0273935 -0.199308 0.979554 + outer loop + vertex -259.723 23.1592 27.4118 + vertex -275.871 25.4557 27.4274 + vertex -261.909 21.5877 27.0309 + endloop + endfacet + facet normal -0.028395 -0.194651 0.980462 + outer loop + vertex -275.221 28.0699 27.9652 + vertex -291.465 30.504 27.9781 + vertex -275.871 25.4557 27.4274 + endloop + endfacet + facet normal -0.0285718 -0.195184 0.98035 + outer loop + vertex -275.871 25.4557 27.4274 + vertex -291.465 30.504 27.9781 + vertex -292.127 27.8839 27.4371 + endloop + endfacet + facet normal -0.029337 -0.200303 0.979295 + outer loop + vertex -275.871 25.4557 27.4274 + vertex -292.127 27.8839 27.4371 + vertex -278.098 23.8129 27.0247 + endloop + endfacet + facet normal -0.0301027 -0.194804 0.98038 + outer loop + vertex -291.465 30.504 27.9781 + vertex -307.704 33.0645 27.9882 + vertex -292.127 27.8839 27.4371 + endloop + endfacet + facet normal -0.0302331 -0.195187 0.9803 + outer loop + vertex -292.127 27.8839 27.4371 + vertex -307.704 33.0645 27.9882 + vertex -308.334 30.4291 27.4441 + endloop + endfacet + facet normal -0.0310098 -0.20013 0.979278 + outer loop + vertex -292.127 27.8839 27.4371 + vertex -308.334 30.4291 27.4441 + vertex -294.8 26.4297 27.0553 + endloop + endfacet + facet normal -0.0308558 -0.19504 0.98031 + outer loop + vertex -307.704 33.0645 27.9882 + vertex -323.934 35.757 28.013 + vertex -308.334 30.4291 27.4441 + endloop + endfacet + facet normal -0.0313932 -0.196579 0.979985 + outer loop + vertex -308.334 30.4291 27.4441 + vertex -323.934 35.757 28.013 + vertex -324.408 33.0815 27.4612 + endloop + endfacet + facet normal -0.0320206 -0.200377 0.979196 + outer loop + vertex -308.334 30.4291 27.4441 + vertex -324.408 33.0815 27.4612 + vertex -310.621 28.8311 27.0422 + endloop + endfacet + facet normal -0.0300623 -0.196814 0.97998 + outer loop + vertex -323.934 35.757 28.013 + vertex -340.087 38.5639 28.0812 + vertex -324.408 33.0815 27.4612 + endloop + endfacet + facet normal -0.031804 -0.201677 0.978936 + outer loop + vertex -324.408 33.0815 27.4612 + vertex -340.087 38.5639 28.0812 + vertex -340.443 35.8676 27.5142 + endloop + endfacet + facet normal -0.0274388 -0.202256 0.978948 + outer loop + vertex -340.087 38.5639 28.0812 + vertex -356.06 41.4711 28.2342 + vertex -340.443 35.8676 27.5142 + endloop + endfacet + facet normal -0.0275908 -0.203081 0.978773 + outer loop + vertex -340.087 38.5639 28.0812 + vertex -356.156 45.1421 28.9931 + vertex -356.06 41.4711 28.2342 + endloop + endfacet + facet normal -0.0161608 -0.202843 0.979078 + outer loop + vertex -356.156 45.1421 28.9931 + vertex -371.732 48.0641 29.3414 + vertex -356.06 41.4711 28.2342 + endloop + endfacet + facet normal -0.0247219 -0.222447 0.974631 + outer loop + vertex -356.06 41.4711 28.2342 + vertex -371.732 48.0641 29.3414 + vertex -371.813 44.4543 28.5155 + endloop + endfacet + facet normal -0.00777523 -0.22287 0.974817 + outer loop + vertex -371.732 48.0641 29.3414 + vertex -387.104 51.0841 29.9093 + vertex -371.813 44.4543 28.5155 + endloop + endfacet + facet normal -0.00941892 -0.230882 0.972936 + outer loop + vertex -371.732 48.0641 29.3414 + vertex -386.269 55.1493 30.882 + vertex -387.104 51.0841 29.9093 + endloop + endfacet + facet normal 0.0164727 -0.23589 0.97164 + outer loop + vertex -386.269 55.1493 30.882 + vertex -401.546 58.446 31.9414 + vertex -387.104 51.0841 29.9093 + endloop + endfacet + facet normal 0.0171847 -0.232824 0.972367 + outer loop + vertex -386.269 55.1493 30.882 + vertex -397.778 61.6985 32.6536 + vertex -401.546 58.446 31.9414 + endloop + endfacet + facet normal 0.0435228 -0.261551 0.964208 + outer loop + vertex -397.778 61.6985 32.6536 + vertex -408.002 64.2934 33.819 + vertex -401.546 58.446 31.9414 + endloop + endfacet + facet normal 0.0498655 -0.255012 0.965651 + outer loop + vertex -408.002 64.2934 33.819 + vertex -413.242 63.4879 33.8769 + vertex -401.546 58.446 31.9414 + endloop + endfacet + facet normal 0.0437094 -0.260892 0.964378 + outer loop + vertex -397.778 61.6985 32.6536 + vertex -405.643 66.9722 34.4368 + vertex -408.002 64.2934 33.819 + endloop + endfacet + facet normal 0.0814972 -0.291567 0.953072 + outer loop + vertex -405.643 66.9722 34.4368 + vertex -412.818 68.6338 35.5586 + vertex -408.002 64.2934 33.819 + endloop + endfacet + facet normal 0.0614041 -0.311879 0.948135 + outer loop + vertex -408.002 64.2934 33.819 + vertex -412.818 68.6338 35.5586 + vertex -414.694 66.7042 35.0454 + endloop + endfacet + facet normal 0.0592078 -0.317156 0.946523 + outer loop + vertex -414.694 66.7042 35.0454 + vertex -413.242 63.4879 33.8769 + vertex -408.002 64.2934 33.819 + endloop + endfacet + facet normal 0.109148 -0.295538 0.949075 + outer loop + vertex -414.694 66.7042 35.0454 + vertex -419.451 67.2896 35.7747 + vertex -413.242 63.4879 33.8769 + endloop + endfacet + facet normal 0.0601361 -0.365494 0.928869 + outer loop + vertex -413.242 63.4879 33.8769 + vertex -419.451 67.2896 35.7747 + vertex -420.433 64.5058 34.7429 + endloop + endfacet + facet normal 0.0687637 -0.318601 0.945392 + outer loop + vertex -413.242 63.4879 33.8769 + vertex -420.433 64.5058 34.7429 + vertex -413.571 59.9652 32.7136 + endloop + endfacet + facet normal 0.0355517 -0.362499 0.931306 + outer loop + vertex -413.571 59.9652 32.7136 + vertex -420.433 64.5058 34.7429 + vertex -423.222 62.343 34.0075 + endloop + endfacet + facet normal 0.0354344 -0.362894 0.931156 + outer loop + vertex -413.571 59.9652 32.7136 + vertex -423.222 62.343 34.0075 + vertex -419.258 57.5369 31.9836 + endloop + endfacet + facet normal 0.0475594 -0.354092 0.934 + outer loop + vertex -423.222 62.343 34.0075 + vertex -428.902 62.129 34.2157 + vertex -419.258 57.5369 31.9836 + endloop + endfacet + facet normal 0.0801811 -0.411998 0.90765 + outer loop + vertex -420.433 64.5058 34.7429 + vertex -426.998 66.0264 36.0131 + vertex -423.222 62.343 34.0075 + endloop + endfacet + facet normal 0.0536235 -0.434544 0.899053 + outer loop + vertex -423.222 62.343 34.0075 + vertex -426.998 66.0264 36.0131 + vertex -429.31 64.5332 35.4293 + endloop + endfacet + facet normal 0.0494928 -0.443375 0.894969 + outer loop + vertex -429.31 64.5332 35.4293 + vertex -428.902 62.129 34.2157 + vertex -423.222 62.343 34.0075 + endloop + endfacet + facet normal 0.0993377 -0.434923 0.894972 + outer loop + vertex -429.31 64.5332 35.4293 + vertex -434.285 65.3242 36.3659 + vertex -428.902 62.129 34.2157 + endloop + endfacet + facet normal 0.0796917 -0.511708 0.855455 + outer loop + vertex -429.31 64.5332 35.4293 + vertex -432.635 67.3964 37.4517 + vertex -434.285 65.3242 36.3659 + endloop + endfacet + facet normal 0.0740466 -0.431366 0.899133 + outer loop + vertex -420.433 64.5058 34.7429 + vertex -425.098 68.3549 36.9738 + vertex -426.998 66.0264 36.0131 + endloop + endfacet + facet normal 0.122273 -0.382575 0.915798 + outer loop + vertex -419.451 67.2896 35.7747 + vertex -425.098 68.3549 36.9738 + vertex -420.433 64.5058 34.7429 + endloop + endfacet + facet normal 0.112841 -0.416933 0.901905 + outer loop + vertex -419.451 67.2896 35.7747 + vertex -423.597 71.0108 38.0137 + vertex -425.098 68.3549 36.9738 + endloop + endfacet + facet normal 0.154329 -0.377437 0.913085 + outer loop + vertex -418.484 69.9724 36.7204 + vertex -423.597 71.0108 38.0137 + vertex -419.451 67.2896 35.7747 + endloop + endfacet + facet normal 0.147074 -0.401699 0.903885 + outer loop + vertex -418.484 69.9724 36.7204 + vertex -422.047 73.822 39.0108 + vertex -423.597 71.0108 38.0137 + endloop + endfacet + facet normal 0.173443 -0.380074 0.908549 + outer loop + vertex -416.957 72.6768 37.5601 + vertex -422.047 73.822 39.0108 + vertex -418.484 69.9724 36.7204 + endloop + endfacet + facet normal 0.174453 -0.376976 0.909646 + outer loop + vertex -416.957 72.6768 37.5601 + vertex -420.383 76.8494 39.9464 + vertex -422.047 73.822 39.0108 + endloop + endfacet + facet normal 0.20337 -0.354876 0.912526 + outer loop + vertex -415.389 75.724 38.3956 + vertex -420.383 76.8494 39.9464 + vertex -416.957 72.6768 37.5601 + endloop + endfacet + facet normal 0.205903 -0.347013 0.914979 + outer loop + vertex -415.389 75.724 38.3956 + vertex -418.708 80.1507 40.8214 + vertex -420.383 76.8494 39.9464 + endloop + endfacet + facet normal 0.237696 -0.323643 0.915836 + outer loop + vertex -413.874 79.0709 39.1854 + vertex -418.708 80.1507 40.8214 + vertex -415.389 75.724 38.3956 + endloop + endfacet + facet normal 0.241414 -0.31176 0.91898 + outer loop + vertex -413.874 79.0709 39.1854 + vertex -417.09 83.7025 41.6012 + vertex -418.708 80.1507 40.8214 + endloop + endfacet + facet normal 0.271873 -0.28991 0.917626 + outer loop + vertex -412.423 82.6706 39.8927 + vertex -417.09 83.7025 41.6012 + vertex -413.874 79.0709 39.1854 + endloop + endfacet + facet normal 0.275523 -0.277799 0.92028 + outer loop + vertex -412.423 82.6706 39.8927 + vertex -415.535 87.4833 42.2771 + vertex -417.09 83.7025 41.6012 + endloop + endfacet + facet normal 0.30452 -0.25745 0.917054 + outer loop + vertex -411.036 86.5033 40.508 + vertex -415.535 87.4833 42.2771 + vertex -412.423 82.6706 39.8927 + endloop + endfacet + facet normal 0.308936 -0.242065 0.919762 + outer loop + vertex -411.036 86.5033 40.508 + vertex -414.08 91.4601 42.8351 + vertex -415.535 87.4833 42.2771 + endloop + endfacet + facet normal 0.333323 -0.225107 0.915545 + outer loop + vertex -409.735 90.5287 41.024 + vertex -414.08 91.4601 42.8351 + vertex -411.036 86.5033 40.508 + endloop + endfacet + facet normal 0.336713 -0.212662 0.917278 + outer loop + vertex -409.735 90.5287 41.024 + vertex -412.706 95.596 43.2895 + vertex -414.08 91.4601 42.8351 + endloop + endfacet + facet normal 0.359543 -0.196962 0.912105 + outer loop + vertex -408.51 94.6999 41.4418 + vertex -412.706 95.596 43.2895 + vertex -409.735 90.5287 41.024 + endloop + endfacet + facet normal 0.362341 -0.186222 0.913253 + outer loop + vertex -408.51 94.6999 41.4418 + vertex -411.406 99.854 43.6419 + vertex -412.706 95.596 43.2895 + endloop + endfacet + facet normal 0.380708 -0.173754 0.908224 + outer loop + vertex -407.329 98.9803 41.7656 + vertex -411.406 99.854 43.6419 + vertex -408.51 94.6999 41.4418 + endloop + endfacet + facet normal 0.38251 -0.166597 0.908808 + outer loop + vertex -407.329 98.9803 41.7656 + vertex -410.148 104.214 43.9117 + vertex -411.406 99.854 43.6419 + endloop + endfacet + facet normal 0.397291 -0.156749 0.904207 + outer loop + vertex -406.159 103.355 42.0099 + vertex -410.148 104.214 43.9117 + vertex -407.329 98.9803 41.7656 + endloop + endfacet + facet normal 0.399619 -0.147222 0.904782 + outer loop + vertex -406.159 103.355 42.0099 + vertex -408.942 108.666 44.1033 + vertex -410.148 104.214 43.9117 + endloop + endfacet + facet normal 0.41017 -0.140265 0.901158 + outer loop + vertex -405.016 107.818 42.1848 + vertex -408.942 108.666 44.1033 + vertex -406.159 103.355 42.0099 + endloop + endfacet + facet normal 0.412143 -0.131933 0.901516 + outer loop + vertex -405.016 107.818 42.1848 + vertex -407.786 113.177 44.235 + vertex -408.942 108.666 44.1033 + endloop + endfacet + facet normal 0.420206 -0.126631 0.89855 + outer loop + vertex -403.912 112.341 42.3059 + vertex -407.786 113.177 44.235 + vertex -405.016 107.818 42.1848 + endloop + endfacet + facet normal 0.421394 -0.121478 0.898705 + outer loop + vertex -403.912 112.341 42.3059 + vertex -406.677 117.688 44.3248 + vertex -407.786 113.177 44.235 + endloop + endfacet + facet normal 0.428549 -0.116737 0.895946 + outer loop + vertex -402.848 116.862 42.3857 + vertex -406.677 117.688 44.3248 + vertex -403.912 112.341 42.3059 + endloop + endfacet + facet normal 0.4299 -0.110739 0.89606 + outer loop + vertex -402.848 116.862 42.3857 + vertex -405.627 122.147 44.3722 + vertex -406.677 117.688 44.3248 + endloop + endfacet + facet normal 0.433104 -0.108574 0.894781 + outer loop + vertex -401.824 121.325 42.4317 + vertex -405.627 122.147 44.3722 + vertex -402.848 116.862 42.3857 + endloop + endfacet + facet normal 0.433965 -0.104698 0.894825 + outer loop + vertex -401.824 121.325 42.4317 + vertex -404.615 126.538 44.3954 + vertex -405.627 122.147 44.3722 + endloop + endfacet + facet normal 0.436376 -0.103038 0.893845 + outer loop + vertex -400.834 125.718 42.455 + vertex -404.615 126.538 44.3954 + vertex -401.824 121.325 42.4317 + endloop + endfacet + facet normal 0.436587 -0.102085 0.893852 + outer loop + vertex -400.834 125.718 42.455 + vertex -403.621 130.902 44.4079 + vertex -404.615 126.538 44.3954 + endloop + endfacet + facet normal 0.440841 -0.0991358 0.892094 + outer loop + vertex -399.866 130.087 42.462 + vertex -403.621 130.902 44.4079 + vertex -400.834 125.718 42.455 + endloop + endfacet + facet normal 0.440918 -0.0987848 0.892095 + outer loop + vertex -399.866 130.087 42.462 + vertex -402.632 135.308 44.4074 + vertex -403.621 130.902 44.4079 + endloop + endfacet + facet normal 0.441261 -0.0985497 0.891951 + outer loop + vertex -398.89 134.495 42.4662 + vertex -402.632 135.308 44.4074 + vertex -399.866 130.087 42.462 + endloop + endfacet + facet normal 0.441499 -0.0974609 0.891953 + outer loop + vertex -398.89 134.495 42.4662 + vertex -401.634 139.798 44.4036 + vertex -402.632 135.308 44.4074 + endloop + endfacet + facet normal 0.442944 -0.0964897 0.891342 + outer loop + vertex -397.908 138.986 42.4641 + vertex -401.634 139.798 44.4036 + vertex -398.89 134.495 42.4662 + endloop + endfacet + facet normal 0.442266 -0.0995914 0.891337 + outer loop + vertex -397.908 138.986 42.4641 + vertex -400.614 144.352 44.4067 + vertex -401.634 139.798 44.4036 + endloop + endfacet + facet normal 0.44577 -0.097284 0.889846 + outer loop + vertex -396.912 143.542 42.4633 + vertex -400.614 144.352 44.4067 + vertex -397.908 138.986 42.4641 + endloop + endfacet + facet normal 0.445278 -0.0995268 0.889844 + outer loop + vertex -396.912 143.542 42.4633 + vertex -399.598 148.912 44.408 + vertex -400.614 144.352 44.4067 + endloop + endfacet + facet normal 0.447283 -0.0982129 0.888984 + outer loop + vertex -395.913 148.101 42.4645 + vertex -399.598 148.912 44.408 + vertex -396.912 143.542 42.4633 + endloop + endfacet + facet normal 0.447191 -0.0986286 0.888984 + outer loop + vertex -395.913 148.101 42.4645 + vertex -398.599 153.417 44.4053 + vertex -399.598 148.912 44.408 + endloop + endfacet + facet normal 0.450348 -0.0965353 0.887619 + outer loop + vertex -394.938 152.608 42.4602 + vertex -398.599 153.417 44.4053 + vertex -395.913 148.101 42.4645 + endloop + endfacet + facet normal 0.449871 -0.0987051 0.887623 + outer loop + vertex -394.938 152.608 42.4602 + vertex -397.621 157.835 44.4007 + vertex -398.599 153.417 44.4053 + endloop + endfacet + facet normal 0.450141 -0.0985228 0.887506 + outer loop + vertex -393.974 157.023 42.4613 + vertex -397.621 157.835 44.4007 + vertex -394.938 152.608 42.4602 + endloop + endfacet + facet normal 0.449936 -0.0994477 0.887507 + outer loop + vertex -393.974 157.023 42.4613 + vertex -396.657 162.175 44.3984 + vertex -397.621 157.835 44.4007 + endloop + endfacet + facet normal 0.452819 -0.0974768 0.886258 + outer loop + vertex -393.035 161.367 42.4594 + vertex -396.657 162.175 44.3984 + vertex -393.974 157.023 42.4613 + endloop + endfacet + facet normal 0.452505 -0.0988935 0.886261 + outer loop + vertex -393.035 161.367 42.4594 + vertex -395.703 166.49 44.393 + vertex -396.657 162.175 44.3984 + endloop + endfacet + facet normal 0.454295 -0.097667 0.885481 + outer loop + vertex -392.107 165.683 42.4592 + vertex -395.703 166.49 44.393 + vertex -393.035 161.367 42.4594 + endloop + endfacet + facet normal 0.454121 -0.0984484 0.885484 + outer loop + vertex -392.107 165.683 42.4592 + vertex -394.747 170.842 44.3864 + vertex -395.703 166.49 44.393 + endloop + endfacet + facet normal 0.45409 -0.0984693 0.885498 + outer loop + vertex -391.172 170.036 42.4636 + vertex -394.747 170.842 44.3864 + vertex -392.107 165.683 42.4592 + endloop + endfacet + facet normal 0.454655 -0.0959374 0.885486 + outer loop + vertex -391.172 170.036 42.4636 + vertex -393.785 175.273 44.3727 + vertex -394.747 170.842 44.3864 + endloop + endfacet + facet normal 0.456325 -0.094834 0.884745 + outer loop + vertex -390.233 174.466 42.4541 + vertex -393.785 175.273 44.3727 + vertex -391.172 170.036 42.4636 + endloop + endfacet + facet normal 0.456484 -0.0941229 0.884739 + outer loop + vertex -390.233 174.466 42.4541 + vertex -392.81 179.774 44.3486 + vertex -393.785 175.273 44.3727 + endloop + endfacet + facet normal 0.45277 -0.0965152 0.886388 + outer loop + vertex -389.242 178.955 42.437 + vertex -392.81 179.774 44.3486 + vertex -390.233 174.466 42.4541 + endloop + endfacet + facet normal 0.453902 -0.0914739 0.886344 + outer loop + vertex -389.242 178.955 42.437 + vertex -391.827 184.291 44.3113 + vertex -392.81 179.774 44.3486 + endloop + endfacet + facet normal 0.447636 -0.0954785 0.889104 + outer loop + vertex -388.227 183.454 42.4088 + vertex -391.827 184.291 44.3113 + vertex -389.242 178.955 42.437 + endloop + endfacet + facet normal 0.448706 -0.0907697 0.889058 + outer loop + vertex -388.227 183.454 42.4088 + vertex -390.914 188.813 44.3122 + vertex -391.827 184.291 44.3113 + endloop + endfacet + facet normal 0.453338 -0.0877203 0.887012 + outer loop + vertex -387.34 187.982 42.4033 + vertex -390.914 188.813 44.3122 + vertex -388.227 183.454 42.4088 + endloop + endfacet + facet normal 0.460595 -0.0540947 0.88596 + outer loop + vertex -387.34 187.982 42.4033 + vertex -390.354 193.461 44.3048 + vertex -390.914 188.813 44.3122 + endloop + endfacet + facet normal 0.473107 -0.045092 0.87985 + outer loop + vertex -386.999 192.707 42.4623 + vertex -390.354 193.461 44.3048 + vertex -387.34 187.982 42.4033 + endloop + endfacet + facet normal 0.0976039 -0.361937 0.927079 + outer loop + vertex -414.694 66.7042 35.0454 + vertex -418.484 69.9724 36.7204 + vertex -419.451 67.2896 35.7747 + endloop + endfacet + facet normal 0.107517 -0.351864 0.929856 + outer loop + vertex -412.818 68.6338 35.5586 + vertex -418.484 69.9724 36.7204 + vertex -414.694 66.7042 35.0454 + endloop + endfacet + facet normal 0.108095 -0.349978 0.9305 + outer loop + vertex -412.818 68.6338 35.5586 + vertex -416.957 72.6768 37.5601 + vertex -418.484 69.9724 36.7204 + endloop + endfacet + facet normal 0.135785 -0.32441 0.93612 + outer loop + vertex -411.226 71.4089 36.2894 + vertex -416.957 72.6768 37.5601 + vertex -412.818 68.6338 35.5586 + endloop + endfacet + facet normal 0.135281 -0.326157 0.935586 + outer loop + vertex -411.226 71.4089 36.2894 + vertex -415.389 75.724 38.3956 + vertex -416.957 72.6768 37.5601 + endloop + endfacet + facet normal 0.165372 -0.299166 0.939761 + outer loop + vertex -409.882 74.5936 37.0666 + vertex -415.389 75.724 38.3956 + vertex -411.226 71.4089 36.2894 + endloop + endfacet + facet normal 0.165964 -0.296976 0.940352 + outer loop + vertex -409.882 74.5936 37.0666 + vertex -413.874 79.0709 39.1854 + vertex -415.389 75.724 38.3956 + endloop + endfacet + facet normal 0.19571 -0.271399 0.942359 + outer loop + vertex -408.628 78.0227 37.794 + vertex -413.874 79.0709 39.1854 + vertex -409.882 74.5936 37.0666 + endloop + endfacet + facet normal 0.197373 -0.265021 0.943826 + outer loop + vertex -408.628 78.0227 37.794 + vertex -412.423 82.6706 39.8927 + vertex -413.874 79.0709 39.1854 + endloop + endfacet + facet normal 0.224966 -0.242446 0.943721 + outer loop + vertex -407.414 81.662 38.4393 + vertex -412.423 82.6706 39.8927 + vertex -408.628 78.0227 37.794 + endloop + endfacet + facet normal 0.227138 -0.233985 0.945336 + outer loop + vertex -407.414 81.662 38.4393 + vertex -411.036 86.5033 40.508 + vertex -412.423 82.6706 39.8927 + endloop + endfacet + facet normal 0.251481 -0.215057 0.943667 + outer loop + vertex -406.207 85.4988 38.9922 + vertex -411.036 86.5033 40.508 + vertex -407.414 81.662 38.4393 + endloop + endfacet + facet normal 0.254455 -0.203443 0.945444 + outer loop + vertex -406.207 85.4988 38.9922 + vertex -409.735 90.5287 41.024 + vertex -411.036 86.5033 40.508 + endloop + endfacet + facet normal 0.276245 -0.187056 0.942708 + outer loop + vertex -405.057 89.5265 39.4543 + vertex -409.735 90.5287 41.024 + vertex -406.207 85.4988 38.9922 + endloop + endfacet + facet normal 0.27893 -0.176477 0.943957 + outer loop + vertex -405.057 89.5265 39.4543 + vertex -408.51 94.6999 41.4418 + vertex -409.735 90.5287 41.024 + endloop + endfacet + facet normal 0.297007 -0.163208 0.940824 + outer loop + vertex -403.967 93.7109 39.8363 + vertex -408.51 94.6999 41.4418 + vertex -405.057 89.5265 39.4543 + endloop + endfacet + facet normal 0.299345 -0.153834 0.941662 + outer loop + vertex -403.967 93.7109 39.8363 + vertex -407.329 98.9803 41.7656 + vertex -408.51 94.6999 41.4418 + endloop + endfacet + facet normal 0.313909 -0.143408 0.93856 + outer loop + vertex -402.89 97.9944 40.1306 + vertex -407.329 98.9803 41.7656 + vertex -403.967 93.7109 39.8363 + endloop + endfacet + facet normal 0.315532 -0.136826 0.938998 + outer loop + vertex -402.89 97.9944 40.1306 + vertex -406.159 103.355 42.0099 + vertex -407.329 98.9803 41.7656 + endloop + endfacet + facet normal 0.328083 -0.128096 0.935924 + outer loop + vertex -401.802 102.371 40.3481 + vertex -406.159 103.355 42.0099 + vertex -402.89 97.9944 40.1306 + endloop + endfacet + facet normal 0.329795 -0.121072 0.936257 + outer loop + vertex -401.802 102.371 40.3481 + vertex -405.016 107.818 42.1848 + vertex -406.159 103.355 42.0099 + endloop + endfacet + facet normal 0.337839 -0.115591 0.934079 + outer loop + vertex -400.714 106.843 40.5078 + vertex -405.016 107.818 42.1848 + vertex -401.802 102.371 40.3481 + endloop + endfacet + facet normal 0.339674 -0.107931 0.93433 + outer loop + vertex -400.714 106.843 40.5078 + vertex -403.912 112.341 42.3059 + vertex -405.016 107.818 42.1848 + endloop + endfacet + facet normal 0.345369 -0.104078 0.932678 + outer loop + vertex -399.656 111.372 40.6215 + vertex -403.912 112.341 42.3059 + vertex -400.714 106.843 40.5078 + endloop + endfacet + facet normal 0.346773 -0.0981285 0.932802 + outer loop + vertex -399.656 111.372 40.6215 + vertex -402.848 116.862 42.3857 + vertex -403.912 112.341 42.3059 + endloop + endfacet + facet normal 0.353929 -0.0932636 0.930611 + outer loop + vertex -398.645 115.902 40.6912 + vertex -402.848 116.862 42.3857 + vertex -399.656 111.372 40.6215 + endloop + endfacet + facet normal 0.354476 -0.0909087 0.930635 + outer loop + vertex -398.645 115.902 40.6912 + vertex -401.824 121.325 42.4317 + vertex -402.848 116.862 42.3857 + endloop + endfacet + facet normal 0.35768 -0.0887057 0.929622 + outer loop + vertex -397.651 120.37 40.7351 + vertex -401.824 121.325 42.4317 + vertex -398.645 115.902 40.6912 + endloop + endfacet + facet normal 0.358383 -0.0856581 0.929637 + outer loop + vertex -397.651 120.37 40.7351 + vertex -400.834 125.718 42.455 + vertex -401.824 121.325 42.4317 + endloop + endfacet + facet normal 0.362687 -0.0826468 0.928239 + outer loop + vertex -396.698 124.769 40.7541 + vertex -400.834 125.718 42.455 + vertex -397.651 120.37 40.7351 + endloop + endfacet + facet normal 0.362856 -0.081909 0.928238 + outer loop + vertex -396.698 124.769 40.7541 + vertex -399.866 130.087 42.462 + vertex -400.834 125.718 42.455 + endloop + endfacet + facet normal 0.363093 -0.0817429 0.92816 + outer loop + vertex -395.741 129.138 40.7647 + vertex -399.866 130.087 42.462 + vertex -396.698 124.769 40.7541 + endloop + endfacet + facet normal 0.363194 -0.0813006 0.92816 + outer loop + vertex -395.741 129.138 40.7647 + vertex -398.89 134.495 42.4662 + vertex -399.866 130.087 42.462 + endloop + endfacet + facet normal 0.366391 -0.0790827 0.927094 + outer loop + vertex -394.792 133.548 40.766 + vertex -398.89 134.495 42.4662 + vertex -395.741 129.138 40.7647 + endloop + endfacet + facet normal 0.366251 -0.0796957 0.927097 + outer loop + vertex -394.792 133.548 40.766 + vertex -397.908 138.986 42.4641 + vertex -398.89 134.495 42.4662 + endloop + endfacet + facet normal 0.368233 -0.0783508 0.926426 + outer loop + vertex -393.833 138.039 40.7644 + vertex -397.908 138.986 42.4641 + vertex -394.792 133.548 40.766 + endloop + endfacet + facet normal 0.3678 -0.0802325 0.926437 + outer loop + vertex -393.833 138.039 40.7644 + vertex -396.912 143.542 42.4633 + vertex -397.908 138.986 42.4641 + endloop + endfacet + facet normal 0.368445 -0.0798039 0.926218 + outer loop + vertex -392.851 142.594 40.7664 + vertex -396.912 143.542 42.4633 + vertex -393.833 138.039 40.7644 + endloop + endfacet + facet normal 0.368192 -0.0808968 0.926224 + outer loop + vertex -392.851 142.594 40.7664 + vertex -395.913 148.101 42.4645 + vertex -396.912 143.542 42.4633 + endloop + endfacet + facet normal 0.370595 -0.0793078 0.925402 + outer loop + vertex -391.876 147.154 40.7667 + vertex -395.913 148.101 42.4645 + vertex -392.851 142.594 40.7664 + endloop + endfacet + facet normal 0.370607 -0.0792557 0.925402 + outer loop + vertex -391.876 147.154 40.7667 + vertex -394.938 152.608 42.4602 + vertex -395.913 148.101 42.4645 + endloop + endfacet + facet normal 0.371854 -0.0784222 0.924973 + outer loop + vertex -390.921 151.662 40.765 + vertex -394.938 152.608 42.4602 + vertex -391.876 147.154 40.7667 + endloop + endfacet + facet normal 0.371187 -0.0812916 0.924993 + outer loop + vertex -390.921 151.662 40.765 + vertex -393.974 157.023 42.4613 + vertex -394.938 152.608 42.4602 + endloop + endfacet + facet normal 0.375492 -0.0783696 0.923506 + outer loop + vertex -389.991 156.086 40.7623 + vertex -393.974 157.023 42.4613 + vertex -390.921 151.662 40.765 + endloop + endfacet + facet normal 0.374967 -0.0806338 0.923525 + outer loop + vertex -389.991 156.086 40.7623 + vertex -393.035 161.367 42.4594 + vertex -393.974 157.023 42.4613 + endloop + endfacet + facet normal 0.375872 -0.0800116 0.923211 + outer loop + vertex -389.072 160.434 40.7648 + vertex -393.035 161.367 42.4594 + vertex -389.991 156.086 40.7623 + endloop + endfacet + facet normal 0.375698 -0.0807621 0.923217 + outer loop + vertex -389.072 160.434 40.7648 + vertex -392.107 165.683 42.4592 + vertex -393.035 161.367 42.4594 + endloop + endfacet + facet normal 0.378784 -0.0786295 0.922139 + outer loop + vertex -388.178 164.758 40.7663 + vertex -392.107 165.683 42.4592 + vertex -389.072 160.434 40.7648 + endloop + endfacet + facet normal 0.377967 -0.0821486 0.922167 + outer loop + vertex -388.178 164.758 40.7663 + vertex -391.172 170.036 42.4636 + vertex -392.107 165.683 42.4592 + endloop + endfacet + facet normal 0.378945 -0.081484 0.921825 + outer loop + vertex -387.259 169.114 40.7738 + vertex -391.172 170.036 42.4636 + vertex -388.178 164.758 40.7663 + endloop + endfacet + facet normal 0.379637 -0.0785001 0.921799 + outer loop + vertex -387.259 169.114 40.7738 + vertex -390.233 174.466 42.4541 + vertex -391.172 170.036 42.4636 + endloop + endfacet + facet normal 0.375832 -0.0810342 0.923138 + outer loop + vertex -386.305 173.537 40.7736 + vertex -390.233 174.466 42.4541 + vertex -387.259 169.114 40.7738 + endloop + endfacet + facet normal 0.376195 -0.0794792 0.923126 + outer loop + vertex -386.305 173.537 40.7736 + vertex -389.242 178.955 42.437 + vertex -390.233 174.466 42.4541 + endloop + endfacet + facet normal 0.373537 -0.0812051 0.924054 + outer loop + vertex -385.296 178.012 40.7588 + vertex -389.242 178.955 42.437 + vertex -386.305 173.537 40.7736 + endloop + endfacet + facet normal 0.374133 -0.0786686 0.924032 + outer loop + vertex -385.296 178.012 40.7588 + vertex -388.227 183.454 42.4088 + vertex -389.242 178.955 42.437 + endloop + endfacet + facet normal 0.373291 -0.0792112 0.924326 + outer loop + vertex -384.289 182.511 40.7377 + vertex -388.227 183.454 42.4088 + vertex -385.296 178.012 40.7588 + endloop + endfacet + facet normal 0.374906 -0.07231 0.924238 + outer loop + vertex -384.289 182.511 40.7377 + vertex -387.34 187.982 42.4033 + vertex -388.227 183.454 42.4088 + endloop + endfacet + facet normal 0.381166 -0.0681349 0.921992 + outer loop + vertex -383.506 187.087 40.7522 + vertex -387.34 187.982 42.4033 + vertex -384.289 182.511 40.7377 + endloop + endfacet + facet normal 0.387458 -0.0394339 0.921044 + outer loop + vertex -383.506 187.087 40.7522 + vertex -386.999 192.707 42.4623 + vertex -387.34 187.982 42.4033 + endloop + endfacet + facet normal 0.398376 -0.0313219 0.916687 + outer loop + vertex -383.304 191.889 40.8285 + vertex -386.999 192.707 42.4623 + vertex -383.506 187.087 40.7522 + endloop + endfacet + facet normal 0.0801147 -0.296572 0.951644 + outer loop + vertex -405.643 66.9722 34.4368 + vertex -411.226 71.4089 36.2894 + vertex -412.818 68.6338 35.5586 + endloop + endfacet + facet normal 0.108889 -0.263253 0.958562 + outer loop + vertex -404.669 70.2746 35.2331 + vertex -411.226 71.4089 36.2894 + vertex -405.643 66.9722 34.4368 + endloop + endfacet + facet normal 0.061378 -0.251042 0.966028 + outer loop + vertex -396.906 65.8135 33.5805 + vertex -404.669 70.2746 35.2331 + vertex -405.643 66.9722 34.4368 + endloop + endfacet + facet normal 0.0894447 -0.20537 0.974588 + outer loop + vertex -398.298 69.7663 34.5412 + vertex -404.669 70.2746 35.2331 + vertex -396.906 65.8135 33.5805 + endloop + endfacet + facet normal 0.0513924 -0.218734 0.97443 + outer loop + vertex -398.298 69.7663 34.5412 + vertex -396.906 65.8135 33.5805 + vertex -386.986 66.7602 33.2698 + endloop + endfacet + facet normal 0.0592091 -0.191546 0.979696 + outer loop + vertex -398.298 69.7663 34.5412 + vertex -386.986 66.7602 33.2698 + vertex -397.324 72.8927 35.0936 + endloop + endfacet + facet normal 0.0485791 -0.187048 0.981149 + outer loop + vertex -385.588 59.8401 31.8814 + vertex -386.986 66.7602 33.2698 + vertex -396.906 65.8135 33.5805 + endloop + endfacet + facet normal 0.0136795 -0.194045 0.980897 + outer loop + vertex -371.414 57.7123 31.2628 + vertex -386.986 66.7602 33.2698 + vertex -385.588 59.8401 31.8814 + endloop + endfacet + facet normal 0.0147832 -0.187082 0.982233 + outer loop + vertex -371.414 57.7123 31.2628 + vertex -385.588 59.8401 31.8814 + vertex -371.585 52.4331 30.2598 + endloop + endfacet + facet normal -0.00744752 -0.186399 0.982446 + outer loop + vertex -356.18 49.6537 29.8493 + vertex -371.414 57.7123 31.2628 + vertex -371.585 52.4331 30.2598 + endloop + endfacet + facet normal -0.00746035 -0.186468 0.982433 + outer loop + vertex -356.18 49.6537 29.8493 + vertex -371.585 52.4331 30.2598 + vertex -356.156 45.1421 28.9931 + endloop + endfacet + facet normal -0.0216832 -0.186501 0.982216 + outer loop + vertex -340.199 42.2458 28.7955 + vertex -356.18 49.6537 29.8493 + vertex -356.156 45.1421 28.9931 + endloop + endfacet + facet normal -0.0158369 -0.174225 0.984578 + outer loop + vertex -340.233 46.7562 29.5931 + vertex -356.18 49.6537 29.8493 + vertex -340.199 42.2458 28.7955 + endloop + endfacet + facet normal -0.0247379 -0.174257 0.984389 + outer loop + vertex -324.009 39.4008 28.6987 + vertex -340.233 46.7562 29.5931 + vertex -340.199 42.2458 28.7955 + endloop + endfacet + facet normal -0.0267074 -0.185394 0.982301 + outer loop + vertex -324.009 39.4008 28.6987 + vertex -340.199 42.2458 28.7955 + vertex -323.934 35.757 28.013 + endloop + endfacet + facet normal -0.0221568 -0.16869 0.98542 + outer loop + vertex -324.058 43.8975 29.4674 + vertex -340.233 46.7562 29.5931 + vertex -324.009 39.4008 28.6987 + endloop + endfacet + facet normal -0.0260625 -0.168715 0.98532 + outer loop + vertex -307.747 36.669 28.6611 + vertex -324.058 43.8975 29.4674 + vertex -324.009 39.4008 28.6987 + endloop + endfacet + facet normal -0.0285972 -0.183766 0.982554 + outer loop + vertex -307.747 36.669 28.6611 + vertex -324.009 39.4008 28.6987 + vertex -307.704 33.0645 27.9882 + endloop + endfacet + facet normal -0.0253138 -0.16706 0.985622 + outer loop + vertex -307.783 41.1164 29.414 + vertex -324.058 43.8975 29.4674 + vertex -307.747 36.669 28.6611 + endloop + endfacet + facet normal -0.025643 -0.167061 0.985613 + outer loop + vertex -291.463 34.0766 28.6453 + vertex -307.783 41.1164 29.414 + vertex -307.747 36.669 28.6611 + endloop + endfacet + facet normal -0.0282664 -0.183521 0.982609 + outer loop + vertex -291.463 34.0766 28.6453 + vertex -307.747 36.669 28.6611 + vertex -291.465 30.504 27.9781 + endloop + endfacet + facet normal -0.0257212 -0.167238 0.985581 + outer loop + vertex -291.438 38.4672 29.391 + vertex -307.783 41.1164 29.414 + vertex -291.463 34.0766 28.6453 + endloop + endfacet + facet normal -0.0242428 -0.167253 0.985616 + outer loop + vertex -275.156 31.6165 28.629 + vertex -291.438 38.4672 29.391 + vertex -291.463 34.0766 28.6453 + endloop + endfacet + facet normal -0.0266841 -0.183416 0.982673 + outer loop + vertex -275.156 31.6165 28.629 + vertex -291.463 34.0766 28.6453 + vertex -275.221 28.0699 27.9652 + endloop + endfacet + facet normal -0.0240288 -0.166754 0.985706 + outer loop + vertex -275.037 35.9799 29.3701 + vertex -291.438 38.4672 29.391 + vertex -275.156 31.6165 28.629 + endloop + endfacet + facet normal -0.0222948 -0.166807 0.985737 + outer loop + vertex -258.828 29.2874 28.6042 + vertex -275.037 35.9799 29.3701 + vertex -275.156 31.6165 28.629 + endloop + endfacet + facet normal -0.0245401 -0.182517 0.982896 + outer loop + vertex -258.828 29.2874 28.6042 + vertex -275.156 31.6165 28.629 + vertex -258.986 25.7626 27.9457 + endloop + endfacet + facet normal -0.0220325 -0.166184 0.985849 + outer loop + vertex -258.606 33.6175 29.339 + vertex -275.037 35.9799 29.3701 + vertex -258.828 29.2874 28.6042 + endloop + endfacet + facet normal -0.0205106 -0.166265 0.985868 + outer loop + vertex -242.504 27.0847 28.5723 + vertex -258.606 33.6175 29.339 + vertex -258.828 29.2874 28.6042 + endloop + endfacet + facet normal -0.0225602 -0.181416 0.983148 + outer loop + vertex -242.504 27.0847 28.5723 + vertex -258.828 29.2874 28.6042 + vertex -242.754 23.5981 27.9232 + endloop + endfacet + facet normal -0.0197967 -0.164542 0.986171 + outer loop + vertex -242.176 31.3982 29.2986 + vertex -258.606 33.6175 29.339 + vertex -242.504 27.0847 28.5723 + endloop + endfacet + facet normal -0.0187775 -0.16462 0.986178 + outer loop + vertex -226.197 25.0105 28.5365 + vertex -242.176 31.3982 29.2986 + vertex -242.504 27.0847 28.5723 + endloop + endfacet + facet normal -0.0206897 -0.179608 0.983521 + outer loop + vertex -226.197 25.0105 28.5365 + vertex -242.504 27.0847 28.5723 + vertex -226.465 21.5207 27.8936 + endloop + endfacet + facet normal -0.018216 -0.163244 0.986418 + outer loop + vertex -225.78 29.2915 29.2527 + vertex -242.176 31.3982 29.2986 + vertex -226.197 25.0105 28.5365 + endloop + endfacet + facet normal -0.0170889 -0.163354 0.986419 + outer loop + vertex -209.898 23.0714 28.4978 + vertex -225.78 29.2915 29.2527 + vertex -226.197 25.0105 28.5365 + endloop + endfacet + facet normal -0.0188167 -0.177827 0.983882 + outer loop + vertex -209.898 23.0714 28.4978 + vertex -226.197 25.0105 28.5365 + vertex -210.172 19.5925 27.8638 + endloop + endfacet + facet normal -0.0164032 -0.161639 0.986714 + outer loop + vertex -209.412 27.3272 29.203 + vertex -225.78 29.2915 29.2527 + vertex -209.898 23.0714 28.4978 + endloop + endfacet + facet normal -0.0153138 -0.161763 0.986711 + outer loop + vertex -193.584 21.266 28.455 + vertex -209.412 27.3272 29.203 + vertex -209.898 23.0714 28.4978 + endloop + endfacet + facet normal -0.0169024 -0.176059 0.984235 + outer loop + vertex -193.584 21.266 28.455 + vertex -209.898 23.0714 28.4978 + vertex -193.884 17.8094 27.8315 + endloop + endfacet + facet normal -0.0144242 -0.159487 0.987095 + outer loop + vertex -193.039 25.5149 29.1495 + vertex -209.412 27.3272 29.203 + vertex -193.584 21.266 28.455 + endloop + endfacet + facet normal -0.0133122 -0.159629 0.987087 + outer loop + vertex -177.226 19.6134 28.4084 + vertex -193.039 25.5149 29.1495 + vertex -193.584 21.266 28.455 + endloop + endfacet + facet normal -0.0147296 -0.173591 0.984708 + outer loop + vertex -177.226 19.6134 28.4084 + vertex -193.584 21.266 28.455 + vertex -177.568 16.1645 27.7953 + endloop + endfacet + facet normal -0.0122573 -0.15686 0.987545 + outer loop + vertex -176.637 23.8604 29.0903 + vertex -193.039 25.5149 29.1495 + vertex -177.226 19.6134 28.4084 + endloop + endfacet + facet normal -0.0113692 -0.156981 0.987536 + outer loop + vertex -160.849 18.1097 28.3579 + vertex -176.637 23.8604 29.0903 + vertex -177.226 19.6134 28.4084 + endloop + endfacet + facet normal -0.0126368 -0.17071 0.98524 + outer loop + vertex -160.849 18.1097 28.3579 + vertex -177.226 19.6134 28.4084 + vertex -161.226 14.6604 27.7554 + endloop + endfacet + facet normal -0.0103147 -0.154145 0.987994 + outer loop + vertex -160.253 22.347 29.0252 + vertex -176.637 23.8604 29.0903 + vertex -160.849 18.1097 28.3579 + endloop + endfacet + facet normal -0.00961975 -0.154241 0.987986 + outer loop + vertex -144.534 16.7496 28.3044 + vertex -160.253 22.347 29.0252 + vertex -160.849 18.1097 28.3579 + endloop + endfacet + facet normal -0.0107531 -0.167749 0.985771 + outer loop + vertex -144.534 16.7496 28.3044 + vertex -160.849 18.1097 28.3579 + vertex -144.921 13.3013 27.7134 + endloop + endfacet + facet normal -0.00867108 -0.15163 0.988399 + outer loop + vertex -143.973 20.9682 28.9565 + vertex -160.253 22.347 29.0252 + vertex -144.534 16.7496 28.3044 + endloop + endfacet + facet normal -0.0081388 -0.1517 0.988393 + outer loop + vertex -128.366 15.5315 28.2506 + vertex -143.973 20.9682 28.9565 + vertex -144.534 16.7496 28.3044 + endloop + endfacet + facet normal -0.00914037 -0.164901 0.986268 + outer loop + vertex -128.366 15.5315 28.2506 + vertex -144.534 16.7496 28.3044 + vertex -128.742 12.0932 27.6722 + endloop + endfacet + facet normal -0.00714992 -0.148917 0.988824 + outer loop + vertex -127.861 19.7403 28.8881 + vertex -143.973 20.9682 28.9565 + vertex -128.366 15.5315 28.2506 + endloop + endfacet + facet normal -0.00692759 -0.148943 0.988821 + outer loop + vertex -112.345 14.4369 28.1979 + vertex -127.861 19.7403 28.8881 + vertex -128.366 15.5315 28.2506 + endloop + endfacet + facet normal -0.007875 -0.162705 0.986643 + outer loop + vertex -112.345 14.4369 28.1979 + vertex -128.366 15.5315 28.2506 + vertex -112.682 11.023 27.6323 + endloop + endfacet + facet normal -0.00587975 -0.145937 0.989276 + outer loop + vertex -111.894 18.6513 28.8223 + vertex -127.861 19.7403 28.8881 + vertex -112.345 14.4369 28.1979 + endloop + endfacet + facet normal -0.00576398 -0.145949 0.989275 + outer loop + vertex -96.3816 13.4796 28.1497 + vertex -111.894 18.6513 28.8223 + vertex -112.345 14.4369 28.1979 + endloop + endfacet + facet normal -0.00664603 -0.160544 0.987006 + outer loop + vertex -96.3816 13.4796 28.1497 + vertex -112.345 14.4369 28.1979 + vertex -96.6672 10.077 27.5943 + endloop + endfacet + facet normal -0.00503966 -0.143818 0.989591 + outer loop + vertex -95.9935 17.6673 28.7603 + vertex -111.894 18.6513 28.8223 + vertex -96.3816 13.4796 28.1497 + endloop + endfacet + facet normal -0.00483883 -0.143836 0.98959 + outer loop + vertex -80.3855 12.6385 28.1057 + vertex -95.9935 17.6673 28.7603 + vertex -96.3816 13.4796 28.1497 + endloop + endfacet + facet normal -0.00564403 -0.159028 0.987258 + outer loop + vertex -80.3855 12.6385 28.1057 + vertex -96.3816 13.4796 28.1497 + vertex -80.5778 9.25754 27.56 + endloop + endfacet + facet normal -0.00439527 -0.142485 0.989787 + outer loop + vertex -80.086 16.7844 28.7038 + vertex -95.9935 17.6673 28.7603 + vertex -80.3855 12.6385 28.1057 + endloop + endfacet + facet normal -0.00405319 -0.142509 0.989785 + outer loop + vertex -64.3438 11.911 28.0666 + vertex -80.086 16.7844 28.7038 + vertex -80.3855 12.6385 28.1057 + endloop + endfacet + facet normal -0.00477328 -0.158257 0.987386 + outer loop + vertex -64.3438 11.911 28.0666 + vertex -80.3855 12.6385 28.1057 + vertex -64.4084 8.56722 27.5304 + endloop + endfacet + facet normal -0.00368954 -0.141357 0.989952 + outer loop + vertex -64.1358 16.0239 28.6547 + vertex -80.086 16.7844 28.7038 + vertex -64.3438 11.911 28.0666 + endloop + endfacet + facet normal -0.00323309 -0.141379 0.98995 + outer loop + vertex -48.2668 11.3172 28.0343 + vertex -64.1358 16.0239 28.6547 + vertex -64.3438 11.911 28.0666 + endloop + endfacet + facet normal -0.00384704 -0.157866 0.987453 + outer loop + vertex -48.2668 11.3172 28.0343 + vertex -64.3438 11.911 28.0666 + vertex -48.2346 8.0096 27.5057 + endloop + endfacet + facet normal -0.0029773 -0.140533 0.990072 + outer loop + vertex -48.1402 15.4007 28.6143 + vertex -64.1358 16.0239 28.6547 + vertex -48.2668 11.3172 28.0343 + endloop + endfacet + facet normal -0.00232442 -0.140553 0.99007 + outer loop + vertex -32.1535 10.8811 28.0102 + vertex -48.1402 15.4007 28.6143 + vertex -48.2668 11.3172 28.0343 + endloop + endfacet + facet normal -0.00278772 -0.157531 0.98751 + outer loop + vertex -32.1535 10.8811 28.0102 + vertex -48.2668 11.3172 28.0343 + vertex -32.0644 7.59072 27.4856 + endloop + endfacet + facet normal -0.00219796 -0.140114 0.990133 + outer loop + vertex -32.1189 14.9321 28.5836 + vertex -48.1402 15.4007 28.6143 + vertex -32.1535 10.8811 28.0102 + endloop + endfacet + facet normal -0.00142506 -0.140121 0.990133 + outer loop + vertex -16.0226 10.6086 27.9949 + vertex -32.1189 14.9321 28.5836 + vertex -32.1535 10.8811 28.0102 + endloop + endfacet + facet normal -0.00172157 -0.157526 0.987513 + outer loop + vertex -16.0226 10.6086 27.9949 + vertex -32.1535 10.8811 28.0102 + vertex -15.8964 7.33689 27.4732 + endloop + endfacet + facet normal -0.00136245 -0.139892 0.990166 + outer loop + vertex -16.1013 14.6377 28.564 + vertex -32.1189 14.9321 28.5836 + vertex -16.0226 10.6086 27.9949 + endloop + endfacet + facet normal -0.000487337 -0.139875 0.990169 + outer loop + vertex 0.0983757 10.513 27.9893 + vertex -16.1013 14.6377 28.564 + vertex -16.0226 10.6086 27.9949 + endloop + endfacet + facet normal -0.000592986 -0.15754 0.987512 + outer loop + vertex 0.0983757 10.513 27.9893 + vertex -16.0226 10.6086 27.9949 + vertex 0.273026 7.25446 27.4696 + endloop + endfacet + facet normal -0.000488835 -0.139881 0.990168 + outer loop + vertex -0.0993721 14.5298 28.5567 + vertex -16.1013 14.6377 28.564 + vertex 0.0983757 10.513 27.9893 + endloop + endfacet + facet normal 0.000504691 -0.139833 0.990175 + outer loop + vertex 16.2191 10.6017 27.9936 + vertex -0.0993721 14.5298 28.5567 + vertex 0.0983757 10.513 27.9893 + endloop + endfacet + facet normal 0.000602039 -0.157401 0.987535 + outer loop + vertex 16.2191 10.6017 27.9936 + vertex 0.0983757 10.513 27.9893 + vertex 16.4791 7.33707 27.4731 + endloop + endfacet + facet normal 0.000362531 -0.140412 0.990093 + outer loop + vertex 15.9069 14.6072 28.5618 + vertex -0.0993721 14.5298 28.5567 + vertex 16.2191 10.6017 27.9936 + endloop + endfacet + facet normal 0.00143474 -0.14033 0.990104 + outer loop + vertex 32.363 10.8622 28.0072 + vertex 15.9069 14.6072 28.5618 + vertex 16.2191 10.6017 27.9936 + endloop + endfacet + facet normal 0.00171802 -0.15775 0.987478 + outer loop + vertex 32.363 10.8622 28.0072 + vertex 16.2191 10.6017 27.9936 + vertex 32.7445 7.59188 27.4841 + endloop + endfacet + facet normal 0.00150804 -0.140015 0.990148 + outer loop + vertex 31.9465 14.9055 28.5795 + vertex 15.9069 14.6072 28.5618 + vertex 32.363 10.8622 28.0072 + endloop + endfacet + facet normal 0.00241423 -0.139923 0.990159 + outer loop + vertex 48.5095 11.3048 28.0303 + vertex 31.9465 14.9055 28.5795 + vertex 32.363 10.8622 28.0072 + endloop + endfacet + facet normal 0.0029049 -0.157681 0.987486 + outer loop + vertex 48.5095 11.3048 28.0303 + vertex 32.363 10.8622 28.0072 + vertex 49.022 8.00577 27.502 + endloop + endfacet + facet normal 0.00224352 -0.140692 0.990051 + outer loop + vertex 47.9861 15.3639 28.6083 + vertex 31.9465 14.9055 28.5795 + vertex 48.5095 11.3048 28.0303 + endloop + endfacet + facet normal 0.00323189 -0.140566 0.990066 + outer loop + vertex 64.616 11.8915 28.0611 + vertex 47.9861 15.3639 28.6083 + vertex 48.5095 11.3048 28.0303 + endloop + endfacet + facet normal 0.0038818 -0.15827 0.987388 + outer loop + vertex 64.616 11.8915 28.0611 + vertex 48.5095 11.3048 28.0303 + vertex 65.2323 8.57034 27.5263 + endloop + endfacet + facet normal 0.0031242 -0.141071 0.989995 + outer loop + vertex 63.9987 15.9942 28.6476 + vertex 47.9861 15.3639 28.6083 + vertex 64.616 11.8915 28.0611 + endloop + endfacet + facet normal 0.0040782 -0.14093 0.990011 + outer loop + vertex 80.6752 12.621 28.0987 + vertex 63.9987 15.9942 28.6476 + vertex 64.616 11.8915 28.0611 + endloop + endfacet + facet normal 0.00491003 -0.159098 0.987251 + outer loop + vertex 80.6752 12.621 28.0987 + vertex 64.616 11.8915 28.0611 + vertex 81.3604 9.26842 27.5551 + endloop + endfacet + facet normal 0.00377193 -0.142409 0.989801 + outer loop + vertex 79.9758 16.7527 28.6959 + vertex 63.9987 15.9942 28.6476 + vertex 80.6752 12.621 28.0987 + endloop + endfacet + facet normal 0.00493891 -0.142215 0.989823 + outer loop + vertex 96.7342 13.4835 28.1425 + vertex 79.9758 16.7527 28.6959 + vertex 80.6752 12.621 28.0987 + endloop + endfacet + facet normal 0.00592328 -0.160402 0.987034 + outer loop + vertex 96.7342 13.4835 28.1425 + vertex 80.6752 12.621 28.0987 + vertex 97.435 10.1043 27.5892 + endloop + endfacet + facet normal 0.00455859 -0.144118 0.98955 + outer loop + vertex 95.962 17.6387 28.7513 + vertex 79.9758 16.7527 28.6959 + vertex 96.7342 13.4835 28.1425 + endloop + endfacet + facet normal 0.00576415 -0.143898 0.989576 + outer loop + vertex 112.86 14.4629 28.191 + vertex 95.962 17.6387 28.7513 + vertex 96.7342 13.4835 28.1425 + endloop + endfacet + facet normal 0.00691078 -0.162632 0.986663 + outer loop + vertex 112.86 14.4629 28.191 + vertex 96.7342 13.4835 28.1425 + vertex 113.556 11.0721 27.6272 + endloop + endfacet + facet normal 0.00537422 -0.145921 0.989282 + outer loop + vertex 112.016 18.65 28.8132 + vertex 95.962 17.6387 28.7513 + vertex 112.86 14.4629 28.191 + endloop + endfacet + facet normal 0.00677371 -0.145644 0.989314 + outer loop + vertex 129.077 15.5763 28.2439 + vertex 112.016 18.65 28.8132 + vertex 112.86 14.4629 28.191 + endloop + endfacet + facet normal 0.00810796 -0.164934 0.986271 + outer loop + vertex 129.077 15.5763 28.2439 + vertex 112.86 14.4629 28.191 + vertex 129.807 12.1669 27.6677 + endloop + endfacet + facet normal 0.00618936 -0.148801 0.988848 + outer loop + vertex 128.158 19.7646 28.8799 + vertex 112.016 18.65 28.8132 + vertex 129.077 15.5763 28.2439 + endloop + endfacet + facet normal 0.0079536 -0.148421 0.988892 + outer loop + vertex 145.353 16.8085 28.2979 + vertex 128.158 19.7646 28.8799 + vertex 129.077 15.5763 28.2439 + endloop + endfacet + facet normal 0.00944958 -0.168043 0.985734 + outer loop + vertex 145.353 16.8085 28.2979 + vertex 129.077 15.5763 28.2439 + vertex 146.176 13.409 27.7105 + endloop + endfacet + facet normal 0.00742632 -0.1514 0.988445 + outer loop + vertex 144.361 21.0092 28.9488 + vertex 128.158 19.7646 28.8799 + vertex 145.353 16.8085 28.2979 + endloop + endfacet + facet normal 0.00935759 -0.150952 0.988497 + outer loop + vertex 161.594 18.1718 28.3524 + vertex 144.361 21.0092 28.9488 + vertex 145.353 16.8085 28.2979 + endloop + endfacet + facet normal 0.0110425 -0.170892 0.985228 + outer loop + vertex 161.594 18.1718 28.3524 + vertex 145.353 16.8085 28.2979 + vertex 162.539 14.7745 27.7525 + endloop + endfacet + facet normal 0.0087841 -0.154326 0.987981 + outer loop + vertex 160.565 22.3708 29.0174 + vertex 144.361 21.0092 28.9488 + vertex 161.594 18.1718 28.3524 + endloop + endfacet + facet normal 0.0110028 -0.153792 0.988042 + outer loop + vertex 177.779 19.6638 28.4044 + vertex 160.565 22.3708 29.0174 + vertex 161.594 18.1718 28.3524 + endloop + endfacet + facet normal 0.0128462 -0.173673 0.98472 + outer loop + vertex 177.779 19.6638 28.4044 + vertex 161.594 18.1718 28.3524 + vertex 178.778 16.2722 27.7932 + endloop + endfacet + facet normal 0.0104631 -0.157107 0.987526 + outer loop + vertex 176.768 23.8663 29.0837 + vertex 160.565 22.3708 29.0174 + vertex 177.779 19.6638 28.4044 + endloop + endfacet + facet normal 0.0128801 -0.156535 0.987588 + outer loop + vertex 193.977 21.3017 28.4527 + vertex 176.768 23.8663 29.0837 + vertex 177.779 19.6638 28.4044 + endloop + endfacet + facet normal 0.0148687 -0.176104 0.984259 + outer loop + vertex 193.977 21.3017 28.4527 + vertex 177.779 19.6638 28.4044 + vertex 194.939 17.9051 27.8305 + endloop + endfacet + facet normal 0.0123878 -0.159715 0.987085 + outer loop + vertex 193.028 25.5099 29.1456 + vertex 176.768 23.8663 29.0837 + vertex 193.977 21.3017 28.4527 + endloop + endfacet + facet normal 0.0148771 -0.159162 0.98714 + outer loop + vertex 210.279 23.0948 28.4962 + vertex 193.028 25.5099 29.1456 + vertex 193.977 21.3017 28.4527 + endloop + endfacet + facet normal 0.0169961 -0.178346 0.983821 + outer loop + vertex 210.279 23.0948 28.4962 + vertex 193.977 21.3017 28.4527 + vertex 211.143 19.6917 27.8643 + endloop + endfacet + facet normal 0.0145265 -0.161563 0.986756 + outer loop + vertex 209.399 27.3219 29.2012 + vertex 193.028 25.5099 29.1456 + vertex 210.279 23.0948 28.4962 + endloop + endfacet + facet normal 0.0168514 -0.161086 0.986797 + outer loop + vertex 226.691 25.0529 28.5356 + vertex 209.399 27.3219 29.2012 + vertex 210.279 23.0948 28.4962 + endloop + endfacet + facet normal 0.0190956 -0.179828 0.983513 + outer loop + vertex 226.691 25.0529 28.5356 + vertex 210.279 23.0948 28.4962 + vertex 227.459 21.6235 27.8936 + endloop + endfacet + facet normal 0.0165656 -0.163165 0.98646 + outer loop + vertex 225.87 29.2926 29.2506 + vertex 209.399 27.3219 29.2012 + vertex 226.691 25.0529 28.5356 + endloop + endfacet + facet normal 0.0187553 -0.162746 0.98649 + outer loop + vertex 243.147 27.1562 28.5697 + vertex 225.87 29.2926 29.2506 + vertex 226.691 25.0529 28.5356 + endloop + endfacet + facet normal 0.0210963 -0.181011 0.983255 + outer loop + vertex 243.147 27.1562 28.5697 + vertex 226.691 25.0529 28.5356 + vertex 243.824 23.7092 27.9206 + endloop + endfacet + facet normal 0.0184639 -0.164986 0.986123 + outer loop + vertex 242.386 31.3986 29.2937 + vertex 225.87 29.2926 29.2506 + vertex 243.147 27.1562 28.5697 + endloop + endfacet + facet normal 0.0205848 -0.164609 0.986144 + outer loop + vertex 259.598 29.38 28.5975 + vertex 242.386 31.3986 29.2937 + vertex 243.147 27.1562 28.5697 + endloop + endfacet + facet normal 0.0229866 -0.182336 0.982967 + outer loop + vertex 259.598 29.38 28.5975 + vertex 243.147 27.1562 28.5697 + vertex 260.198 25.9316 27.9438 + endloop + endfacet + facet normal 0.0204795 -0.165458 0.986004 + outer loop + vertex 258.909 33.6625 29.3304 + vertex 242.386 31.3986 29.2937 + vertex 259.598 29.38 28.5975 + endloop + endfacet + facet normal 0.0224401 -0.165145 0.986014 + outer loop + vertex 276.023 31.7637 28.6229 + vertex 258.909 33.6625 29.3304 + vertex 259.598 29.38 28.5975 + endloop + endfacet + facet normal 0.0249603 -0.182476 0.982893 + outer loop + vertex 276.023 31.7637 28.6229 + vertex 259.598 29.38 28.5975 + vertex 276.556 28.2796 27.9625 + endloop + endfacet + facet normal 0.0222383 -0.166858 0.98573 + outer loop + vertex 275.438 36.0496 29.3616 + vertex 258.909 33.6625 29.3304 + vertex 276.023 31.7637 28.6229 + endloop + endfacet + facet normal 0.0239408 -0.166625 0.98573 + outer loop + vertex 292.435 34.2518 28.6449 + vertex 275.438 36.0496 29.3616 + vertex 276.023 31.7637 28.6229 + endloop + endfacet + facet normal 0.0264974 -0.183463 0.982669 + outer loop + vertex 292.435 34.2518 28.6449 + vertex 276.023 31.7637 28.6229 + vertex 292.875 30.7486 27.979 + endloop + endfacet + facet normal 0.0239009 -0.166979 0.985671 + outer loop + vertex 291.943 38.5952 29.3926 + vertex 275.438 36.0496 29.3616 + vertex 292.435 34.2518 28.6449 + endloop + endfacet + facet normal 0.0249129 -0.166863 0.985665 + outer loop + vertex 308.759 36.8649 28.6747 + vertex 291.943 38.5952 29.3926 + vertex 292.435 34.2518 28.6449 + endloop + endfacet + facet normal 0.0277496 -0.184546 0.982432 + outer loop + vertex 308.759 36.8649 28.6747 + vertex 292.435 34.2518 28.6449 + vertex 309.116 33.3224 27.9991 + endloop + endfacet + facet normal 0.0247281 -0.168542 0.985384 + outer loop + vertex 308.347 41.2293 29.4315 + vertex 291.943 38.5952 29.3926 + vertex 308.759 36.8649 28.6747 + endloop + endfacet + facet normal 0.0253299 -0.168484 0.985379 + outer loop + vertex 324.908 39.5685 28.7218 + vertex 308.347 41.2293 29.4315 + vertex 308.759 36.8649 28.6747 + endloop + endfacet + facet normal 0.0283175 -0.186273 0.98209 + outer loop + vertex 324.908 39.5685 28.7218 + vertex 308.759 36.8649 28.6747 + vertex 325.207 36.0112 28.0385 + endloop + endfacet + facet normal 0.0251438 -0.170216 0.985086 + outer loop + vertex 324.528 43.9243 29.4842 + vertex 308.347 41.2293 29.4315 + vertex 324.908 39.5685 28.7218 + endloop + endfacet + facet normal 0.024568 -0.170267 0.985092 + outer loop + vertex 340.833 42.2981 28.7964 + vertex 324.528 43.9243 29.4842 + vertex 324.908 39.5685 28.7218 + endloop + endfacet + facet normal 0.0278805 -0.189495 0.981486 + outer loop + vertex 340.833 42.2981 28.7964 + vertex 324.908 39.5685 28.7218 + vertex 341.173 38.761 28.1039 + endloop + endfacet + facet normal 0.0265646 -0.189623 0.981498 + outer loop + vertex 357.019 41.5807 28.2198 + vertex 340.833 42.2981 28.7964 + vertex 341.173 38.761 28.1039 + endloop + endfacet + facet normal 0.0261647 -0.197417 0.97997 + outer loop + vertex 356.563 45.0842 28.9377 + vertex 340.833 42.2981 28.7964 + vertex 357.019 41.5807 28.2198 + endloop + endfacet + facet normal 0.0230861 -0.197817 0.979967 + outer loop + vertex 372.814 44.5295 28.4429 + vertex 356.563 45.0842 28.9377 + vertex 357.019 41.5807 28.2198 + endloop + endfacet + facet normal 0.0282154 -0.224839 0.973987 + outer loop + vertex 372.814 44.5295 28.4429 + vertex 357.019 41.5807 28.2198 + vertex 372.722 41.7449 27.8028 + endloop + endfacet + facet normal 0.02544 -0.224769 0.97408 + outer loop + vertex 388.533 44.8542 28.1073 + vertex 372.814 44.5295 28.4429 + vertex 372.722 41.7449 27.8028 + endloop + endfacet + facet normal 0.0323001 -0.258803 0.96539 + outer loop + vertex 388.533 44.8542 28.1073 + vertex 372.722 41.7449 27.8028 + vertex 387.008 42.4975 27.5265 + endloop + endfacet + facet normal 0.030438 -0.257687 0.965749 + outer loop + vertex 402.179 45.6762 27.8965 + vertex 388.533 44.8542 28.1073 + vertex 387.008 42.4975 27.5265 + endloop + endfacet + facet normal 0.0335168 -0.313057 0.949143 + outer loop + vertex 404.678 48.2685 28.6633 + vertex 388.533 44.8542 28.1073 + vertex 402.179 45.6762 27.8965 + endloop + endfacet + facet normal 0.030194 -0.310167 0.950203 + outer loop + vertex 418.518 49.0769 28.4874 + vertex 404.678 48.2685 28.6633 + vertex 402.179 45.6762 27.8965 + endloop + endfacet + facet normal 0.021771 -0.26015 0.965323 + outer loop + vertex 404.678 48.2685 28.6633 + vertex 388.857 47.7652 28.8845 + vertex 388.533 44.8542 28.1073 + endloop + endfacet + facet normal 0.0231273 -0.309194 0.950718 + outer loop + vertex 405.97 51.4541 29.6679 + vertex 388.857 47.7652 28.8845 + vertex 404.678 48.2685 28.6633 + endloop + endfacet + facet normal 0.0167476 -0.306884 0.951599 + outer loop + vertex 421.956 52.1178 29.6006 + vertex 405.97 51.4541 29.6679 + vertex 404.678 48.2685 28.6633 + endloop + endfacet + facet normal 0.030779 -0.226982 0.973412 + outer loop + vertex 387.008 42.4975 27.5265 + vertex 372.722 41.7449 27.8028 + vertex 371.021 39.4451 27.3203 + endloop + endfacet + facet normal 0.0259877 -0.260562 0.965107 + outer loop + vertex 388.857 47.7652 28.8845 + vertex 372.814 44.5295 28.4429 + vertex 388.533 44.8542 28.1073 + endloop + endfacet + facet normal 0.0171936 -0.218404 0.975707 + outer loop + vertex 388.857 47.7652 28.8845 + vertex 372.292 48.043 29.2386 + vertex 372.814 44.5295 28.4429 + endloop + endfacet + facet normal 0.016415 -0.253862 0.967101 + outer loop + vertex 388.345 51.3827 29.8428 + vertex 372.292 48.043 29.2386 + vertex 388.857 47.7652 28.8845 + endloop + endfacet + facet normal 0.0106254 -0.254649 0.966975 + outer loop + vertex 405.97 51.4541 29.6679 + vertex 388.345 51.3827 29.8428 + vertex 388.857 47.7652 28.8845 + endloop + endfacet + facet normal 0.0106853 -0.306921 0.951675 + outer loop + vertex 404.519 55.0584 30.8466 + vertex 388.345 51.3827 29.8428 + vertex 405.97 51.4541 29.6679 + endloop + endfacet + facet normal 0.005051 -0.308986 0.951053 + outer loop + vertex 404.519 55.0584 30.8466 + vertex 405.97 51.4541 29.6679 + vertex 415.713 54.345 30.5554 + endloop + endfacet + facet normal 0.00580483 -0.204971 0.978751 + outer loop + vertex 388.345 51.3827 29.8428 + vertex 371.636 52.3464 30.1437 + vertex 372.292 48.043 29.2386 + endloop + endfacet + facet normal 0.0137944 -0.203787 0.978918 + outer loop + vertex 371.636 52.3464 30.1437 + vertex 356.015 49.3736 29.7449 + vertex 372.292 48.043 29.2386 + endloop + endfacet + facet normal 0.015621 -0.182992 0.98299 + outer loop + vertex 372.292 48.043 29.2386 + vertex 356.015 49.3736 29.7449 + vertex 356.563 45.0842 28.9377 + endloop + endfacet + facet normal 0.0208871 -0.182324 0.983017 + outer loop + vertex 356.015 49.3736 29.7449 + vertex 340.394 46.6376 29.5694 + vertex 356.563 45.0842 28.9377 + endloop + endfacet + facet normal 0.0154667 -0.151717 0.988303 + outer loop + vertex 356.015 49.3736 29.7449 + vertex 340.029 51.7791 30.3644 + vertex 340.394 46.6376 29.5694 + endloop + endfacet + facet normal 0.0194363 -0.151431 0.988277 + outer loop + vertex 340.029 51.7791 30.3644 + vertex 324.224 49.1258 30.2687 + vertex 340.394 46.6376 29.5694 + endloop + endfacet + facet normal 0.0199921 -0.147964 0.988791 + outer loop + vertex 340.394 46.6376 29.5694 + vertex 324.224 49.1258 30.2687 + vertex 324.528 43.9243 29.4842 + endloop + endfacet + facet normal 0.0210349 -0.147901 0.988778 + outer loop + vertex 324.224 49.1258 30.2687 + vertex 308.03 46.436 30.2108 + vertex 324.528 43.9243 29.4842 + endloop + endfacet + facet normal 0.0165951 -0.121252 0.992483 + outer loop + vertex 324.224 49.1258 30.2687 + vertex 307.717 52.4845 30.955 + vertex 308.03 46.436 30.2108 + endloop + endfacet + facet normal 0.0165975 -0.121252 0.992483 + outer loop + vertex 307.717 52.4845 30.955 + vertex 291.169 49.7975 30.9035 + vertex 308.03 46.436 30.2108 + endloop + endfacet + facet normal 0.0168 -0.120261 0.9926 + outer loop + vertex 308.03 46.436 30.2108 + vertex 291.169 49.7975 30.9035 + vertex 291.552 43.7518 30.1645 + endloop + endfacet + facet normal 0.0211236 -0.14674 0.988949 + outer loop + vertex 308.03 46.436 30.2108 + vertex 291.552 43.7518 30.1645 + vertex 308.347 41.2293 29.4315 + endloop + endfacet + facet normal 0.0159149 -0.120318 0.992608 + outer loop + vertex 291.169 49.7975 30.9035 + vertex 274.455 47.1808 30.8543 + vertex 291.552 43.7518 30.1645 + endloop + endfacet + facet normal 0.0160561 -0.119629 0.992689 + outer loop + vertex 291.552 43.7518 30.1645 + vertex 274.455 47.1808 30.8543 + vertex 274.94 41.1848 30.1239 + endloop + endfacet + facet normal 0.0202195 -0.146513 0.989002 + outer loop + vertex 291.552 43.7518 30.1645 + vertex 274.94 41.1848 30.1239 + vertex 291.943 38.5952 29.3926 + endloop + endfacet + facet normal 0.0146002 -0.119748 0.992697 + outer loop + vertex 274.455 47.1808 30.8543 + vertex 257.703 44.7197 30.8038 + vertex 274.94 41.1848 30.1239 + endloop + endfacet + facet normal 0.0148944 -0.118345 0.992861 + outer loop + vertex 274.94 41.1848 30.1239 + vertex 257.703 44.7197 30.8038 + vertex 258.303 38.7549 30.0838 + endloop + endfacet + facet normal 0.0187993 -0.145021 0.98925 + outer loop + vertex 274.94 41.1848 30.1239 + vertex 258.303 38.7549 30.0838 + vertex 275.438 36.0496 29.3616 + endloop + endfacet + facet normal 0.0132621 -0.11851 0.992864 + outer loop + vertex 257.703 44.7197 30.8038 + vertex 240.976 42.3945 30.7497 + vertex 258.303 38.7549 30.0838 + endloop + endfacet + facet normal 0.0134069 -0.117835 0.992943 + outer loop + vertex 258.303 38.7549 30.0838 + vertex 240.976 42.3945 30.7497 + vertex 241.68 36.4771 30.0379 + endloop + endfacet + facet normal 0.0170491 -0.144344 0.989381 + outer loop + vertex 258.303 38.7549 30.0838 + vertex 241.68 36.4771 30.0379 + vertex 258.909 33.6625 29.3304 + endloop + endfacet + facet normal 0.0113507 -0.118079 0.992939 + outer loop + vertex 240.976 42.3945 30.7497 + vertex 224.298 40.247 30.685 + vertex 241.68 36.4771 30.0379 + endloop + endfacet + facet normal 0.0118228 -0.115945 0.993185 + outer loop + vertex 241.68 36.4771 30.0379 + vertex 224.298 40.247 30.685 + vertex 225.092 34.3333 29.9851 + endloop + endfacet + facet normal 0.0153172 -0.142895 0.989619 + outer loop + vertex 241.68 36.4771 30.0379 + vertex 225.092 34.3333 29.9851 + vertex 242.386 31.3986 29.2937 + endloop + endfacet + facet normal 0.00981898 -0.116213 0.993176 + outer loop + vertex 224.298 40.247 30.685 + vertex 207.717 38.2359 30.6136 + vertex 225.092 34.3333 29.9851 + endloop + endfacet + facet normal 0.0101351 -0.114831 0.993333 + outer loop + vertex 225.092 34.3333 29.9851 + vertex 207.717 38.2359 30.6136 + vertex 208.572 32.3479 29.9242 + endloop + endfacet + facet normal 0.0134321 -0.142155 0.989753 + outer loop + vertex 225.092 34.3333 29.9851 + vertex 208.572 32.3479 29.9242 + vertex 225.87 29.2926 29.2506 + endloop + endfacet + facet normal 0.00779007 -0.115169 0.993315 + outer loop + vertex 207.717 38.2359 30.6136 + vertex 191.274 36.4119 30.531 + vertex 208.572 32.3479 29.9242 + endloop + endfacet + facet normal 0.00830956 -0.112995 0.993561 + outer loop + vertex 208.572 32.3479 29.9242 + vertex 191.274 36.4119 30.531 + vertex 192.163 30.5358 29.8553 + endloop + endfacet + facet normal 0.0113656 -0.140534 0.990011 + outer loop + vertex 208.572 32.3479 29.9242 + vertex 192.163 30.5358 29.8553 + vertex 209.399 27.3219 29.2012 + endloop + endfacet + facet normal 0.00603564 -0.113336 0.993538 + outer loop + vertex 191.274 36.4119 30.531 + vertex 174.969 34.75 30.4405 + vertex 192.163 30.5358 29.8553 + endloop + endfacet + facet normal 0.0066478 -0.110876 0.993812 + outer loop + vertex 192.163 30.5358 29.8553 + vertex 174.969 34.75 30.4405 + vertex 175.868 28.877 29.7793 + endloop + endfacet + facet normal 0.00944892 -0.138234 0.990355 + outer loop + vertex 192.163 30.5358 29.8553 + vertex 175.868 28.877 29.7793 + vertex 193.028 25.5099 29.1456 + endloop + endfacet + facet normal 0.00445967 -0.111209 0.993787 + outer loop + vertex 174.969 34.75 30.4405 + vertex 158.756 33.2354 30.3438 + vertex 175.868 28.877 29.7793 + endloop + endfacet + facet normal 0.0050326 -0.108991 0.99403 + outer loop + vertex 175.868 28.877 29.7793 + vertex 158.756 33.2354 30.3438 + vertex 159.648 27.3785 29.6971 + endloop + endfacet + facet normal 0.00756016 -0.136164 0.990657 + outer loop + vertex 175.868 28.877 29.7793 + vertex 159.648 27.3785 29.6971 + vertex 176.768 23.8663 29.0837 + endloop + endfacet + facet normal 0.00296735 -0.109302 0.994004 + outer loop + vertex 158.756 33.2354 30.3438 + vertex 142.59 31.8696 30.2418 + vertex 159.648 27.3785 29.6971 + endloop + endfacet + facet normal 0.00376471 -0.106313 0.994326 + outer loop + vertex 159.648 27.3785 29.6971 + vertex 142.59 31.8696 30.2418 + vertex 143.456 26.0123 29.6123 + endloop + endfacet + facet normal 0.00606677 -0.133394 0.991045 + outer loop + vertex 159.648 27.3785 29.6971 + vertex 143.456 26.0123 29.6123 + vertex 160.565 22.3708 29.0174 + endloop + endfacet + facet normal 0.00204308 -0.106565 0.994304 + outer loop + vertex 142.59 31.8696 30.2418 + vertex 126.478 30.6137 30.1404 + vertex 143.456 26.0123 29.6123 + endloop + endfacet + facet normal 0.00278065 -0.103876 0.994586 + outer loop + vertex 143.456 26.0123 29.6123 + vertex 126.478 30.6137 30.1404 + vertex 127.297 24.7651 29.5272 + endloop + endfacet + facet normal 0.00486012 -0.1306 0.991423 + outer loop + vertex 143.456 26.0123 29.6123 + vertex 127.297 24.7651 29.5272 + vertex 144.361 21.0092 28.9488 + endloop + endfacet + facet normal 0.00141947 -0.104065 0.994569 + outer loop + vertex 126.478 30.6137 30.1404 + vertex 110.471 29.4607 30.0426 + vertex 127.297 24.7651 29.5272 + endloop + endfacet + facet normal 0.00212268 -0.101573 0.994826 + outer loop + vertex 127.297 24.7651 29.5272 + vertex 110.471 29.4607 30.0426 + vertex 111.223 23.6258 29.4452 + endloop + endfacet + facet normal 0.00399004 -0.127702 0.991805 + outer loop + vertex 127.297 24.7651 29.5272 + vertex 111.223 23.6258 29.4452 + vertex 128.158 19.7646 28.8799 + endloop + endfacet + facet normal 0.00112448 -0.101701 0.994814 + outer loop + vertex 110.471 29.4607 30.0426 + vertex 94.596 28.4 29.9521 + vertex 111.223 23.6258 29.4452 + endloop + endfacet + facet normal 0.00163053 -0.0999569 0.99499 + outer loop + vertex 111.223 23.6258 29.4452 + vertex 94.596 28.4 29.9521 + vertex 95.2616 22.6031 29.3686 + endloop + endfacet + facet normal 0.00327991 -0.125483 0.99209 + outer loop + vertex 111.223 23.6258 29.4452 + vertex 95.2616 22.6031 29.3686 + vertex 112.016 18.65 28.8132 + endloop + endfacet + facet normal 0.00088499 -0.100042 0.994983 + outer loop + vertex 94.596 28.4 29.9521 + vertex 78.8246 27.4468 29.8702 + vertex 95.2616 22.6031 29.3686 + endloop + endfacet + facet normal 0.00137796 -0.0983858 0.995147 + outer loop + vertex 95.2616 22.6031 29.3686 + vertex 78.8246 27.4468 29.8702 + vertex 79.3807 21.6856 29.2999 + endloop + endfacet + facet normal 0.00281268 -0.123013 0.992401 + outer loop + vertex 95.2616 22.6031 29.3686 + vertex 79.3807 21.6856 29.2999 + vertex 95.962 17.6387 28.7513 + endloop + endfacet + facet normal 0.00072975 -0.0984479 0.995142 + outer loop + vertex 78.8246 27.4468 29.8702 + vertex 63.0812 26.6114 29.7992 + vertex 79.3807 21.6856 29.2999 + endloop + endfacet + facet normal 0.00127917 -0.0966477 0.995318 + outer loop + vertex 79.3807 21.6856 29.2999 + vertex 63.0812 26.6114 29.7992 + vertex 63.5115 20.8696 29.2411 + endloop + endfacet + facet normal 0.00255343 -0.121236 0.99262 + outer loop + vertex 79.3807 21.6856 29.2999 + vertex 63.5115 20.8696 29.2411 + vertex 79.9758 16.7527 28.6959 + endloop + endfacet + facet normal 0.000738878 -0.0966878 0.995314 + outer loop + vertex 63.0812 26.6114 29.7992 + vertex 47.3084 25.899 29.7416 + vertex 63.5115 20.8696 29.2411 + endloop + endfacet + facet normal 0.000966787 -0.0959606 0.995385 + outer loop + vertex 63.5115 20.8696 29.2411 + vertex 47.3084 25.899 29.7416 + vertex 47.6115 20.2044 29.1924 + endloop + endfacet + facet normal 0.00200711 -0.120629 0.992696 + outer loop + vertex 63.5115 20.8696 29.2411 + vertex 47.6115 20.2044 29.1924 + vertex 63.9987 15.9942 28.6476 + endloop + endfacet + facet normal 0.0004797 -0.0959863 0.995383 + outer loop + vertex 47.3084 25.899 29.7416 + vertex 31.5057 25.3697 29.6982 + vertex 47.6115 20.2044 29.1924 + endloop + endfacet + facet normal 0.000716266 -0.0952555 0.995453 + outer loop + vertex 47.6115 20.2044 29.1924 + vertex 31.5057 25.3697 29.6982 + vertex 31.6825 19.7085 29.1564 + endloop + endfacet + facet normal 0.00148239 -0.119672 0.992812 + outer loop + vertex 47.6115 20.2044 29.1924 + vertex 31.6825 19.7085 29.1564 + vertex 47.9861 15.3639 28.6083 + endloop + endfacet + facet normal 0.000450244 -0.0952638 0.995452 + outer loop + vertex 31.5057 25.3697 29.6982 + vertex 15.7022 25.0258 29.6725 + vertex 31.6825 19.7085 29.1564 + endloop + endfacet + facet normal 0.000405457 -0.0953971 0.995439 + outer loop + vertex 31.6825 19.7085 29.1564 + vertex 15.7022 25.0258 29.6725 + vertex 15.7588 19.4108 29.1343 + endloop + endfacet + facet normal 0.000853843 -0.119194 0.992871 + outer loop + vertex 31.6825 19.7085 29.1564 + vertex 15.7588 19.4108 29.1343 + vertex 31.9465 14.9055 28.5795 + endloop + endfacet + facet normal 3.66702e-05 -0.0954008 0.995439 + outer loop + vertex 15.7022 25.0258 29.6725 + vertex -0.0668718 24.9297 29.6638 + vertex 15.7588 19.4108 29.1343 + endloop + endfacet + facet normal 0.000273301 -0.0947284 0.995503 + outer loop + vertex 15.7588 19.4108 29.1343 + vertex -0.0668718 24.9297 29.6638 + vertex -0.139085 19.2985 29.128 + endloop + endfacet + facet normal 0.000441161 -0.118338 0.992973 + outer loop + vertex 15.7588 19.4108 29.1343 + vertex -0.139085 19.2985 29.128 + vertex 15.9069 14.6072 28.5618 + endloop + endfacet + facet normal -8.80779e-05 -0.0947238 0.995504 + outer loop + vertex -0.0668718 24.9297 29.6638 + vertex -15.8089 25.0541 29.6743 + vertex -0.139085 19.2985 29.128 + endloop + endfacet + facet normal -0.000140025 -0.094864 0.99549 + outer loop + vertex -0.139085 19.2985 29.128 + vertex -15.8089 25.0541 29.6743 + vertex -16.0111 19.4152 29.1369 + endloop + endfacet + facet normal -0.000318615 -0.11896 0.992899 + outer loop + vertex -0.139085 19.2985 29.128 + vertex -16.0111 19.4152 29.1369 + vertex -0.0993721 14.5298 28.5567 + endloop + endfacet + facet normal -0.000247623 -0.0948602 0.995491 + outer loop + vertex -15.8089 25.0541 29.6743 + vertex -31.5447 25.3953 29.7029 + vertex -16.0111 19.4152 29.1369 + endloop + endfacet + facet normal -0.000434289 -0.0953407 0.995445 + outer loop + vertex -16.0111 19.4152 29.1369 + vertex -31.5447 25.3953 29.7029 + vertex -31.8862 19.7377 29.1609 + endloop + endfacet + facet normal -0.000919735 -0.119041 0.992889 + outer loop + vertex -16.0111 19.4152 29.1369 + vertex -31.8862 19.7377 29.1609 + vertex -16.1013 14.6377 28.564 + endloop + endfacet + facet normal -0.000437427 -0.0953405 0.995445 + outer loop + vertex -31.5447 25.3953 29.7029 + vertex -47.2926 25.9352 29.7477 + vertex -31.8862 19.7377 29.1609 + endloop + endfacet + facet normal -0.000780332 -0.0961852 0.995363 + outer loop + vertex -31.8862 19.7377 29.1609 + vertex -47.2926 25.9352 29.7477 + vertex -47.7714 20.2569 29.1986 + endloop + endfacet + facet normal -0.00153823 -0.119196 0.99287 + outer loop + vertex -31.8862 19.7377 29.1609 + vertex -47.7714 20.2569 29.1986 + vertex -32.1189 14.9321 28.5836 + endloop + endfacet + facet normal -0.000623846 -0.0961983 0.995362 + outer loop + vertex -47.2926 25.9352 29.7477 + vertex -63.0469 26.6486 29.8067 + vertex -47.7714 20.2569 29.1986 + endloop + endfacet + facet normal -0.000907193 -0.0968693 0.995297 + outer loop + vertex -47.7714 20.2569 29.1986 + vertex -63.0469 26.6486 29.8067 + vertex -63.6557 20.9202 29.2487 + endloop + endfacet + facet normal -0.0018521 -0.119312 0.992855 + outer loop + vertex -47.7714 20.2569 29.1986 + vertex -63.6557 20.9202 29.2487 + vertex -48.1402 15.4007 28.6143 + endloop + endfacet + facet normal -0.000574656 -0.0969043 0.995294 + outer loop + vertex -63.0469 26.6486 29.8067 + vertex -78.7928 27.4816 29.8788 + vertex -63.6557 20.9202 29.2487 + endloop + endfacet + facet normal -0.00117908 -0.0982856 0.995158 + outer loop + vertex -63.6557 20.9202 29.2487 + vertex -78.7928 27.4816 29.8788 + vertex -79.5115 21.7213 29.309 + endloop + endfacet + facet normal -0.00229572 -0.120206 0.992746 + outer loop + vertex -63.6557 20.9202 29.2487 + vertex -79.5115 21.7213 29.309 + vertex -64.1358 16.0239 28.6547 + endloop + endfacet + facet normal -0.000652542 -0.0983507 0.995152 + outer loop + vertex -78.7928 27.4816 29.8788 + vertex -94.5214 28.4227 29.9614 + vertex -79.5115 21.7213 29.309 + endloop + endfacet + facet normal -0.00132363 -0.0998393 0.995003 + outer loop + vertex -79.5115 21.7213 29.309 + vertex -94.5214 28.4227 29.9614 + vertex -95.3387 22.6233 29.3784 + endloop + endfacet + facet normal -0.0025615 -0.121375 0.992603 + outer loop + vertex -79.5115 21.7213 29.309 + vertex -95.3387 22.6233 29.3784 + vertex -80.086 16.7844 28.7038 + endloop + endfacet + facet normal -0.000774506 -0.099916 0.994996 + outer loop + vertex -94.5214 28.4227 29.9614 + vertex -110.268 29.4521 30.0526 + vertex -95.3387 22.6233 29.3784 + endloop + endfacet + facet normal -0.0017439 -0.102014 0.994781 + outer loop + vertex -95.3387 22.6233 29.3784 + vertex -110.268 29.4521 30.0526 + vertex -111.166 23.6392 29.4549 + endloop + endfacet + facet normal -0.00312598 -0.123363 0.992357 + outer loop + vertex -95.3387 22.6233 29.3784 + vertex -111.166 23.6392 29.4549 + vertex -95.9935 17.6673 28.7603 + endloop + endfacet + facet normal -0.00116448 -0.102103 0.994773 + outer loop + vertex -110.268 29.4521 30.0526 + vertex -126.101 30.5816 30.15 + vertex -111.166 23.6392 29.4549 + endloop + endfacet + facet normal -0.00219409 -0.104295 0.994544 + outer loop + vertex -111.166 23.6392 29.4549 + vertex -126.101 30.5816 30.15 + vertex -127.07 24.7532 29.5366 + endloop + endfacet + facet normal -0.00367677 -0.125283 0.992114 + outer loop + vertex -111.166 23.6392 29.4549 + vertex -127.07 24.7532 29.5366 + vertex -111.894 18.6513 28.8223 + endloop + endfacet + facet normal -0.00185453 -0.104351 0.994539 + outer loop + vertex -126.101 30.5816 30.15 + vertex -142.098 31.8265 30.2507 + vertex -127.07 24.7532 29.5366 + endloop + endfacet + facet normal -0.00291515 -0.10658 0.9943 + outer loop + vertex -127.07 24.7532 29.5366 + vertex -142.098 31.8265 30.2507 + vertex -143.125 25.9833 29.6214 + endloop + endfacet + facet normal -0.00453887 -0.127601 0.991815 + outer loop + vertex -127.07 24.7532 29.5366 + vertex -143.125 25.9833 29.6214 + vertex -127.861 19.7403 28.8881 + endloop + endfacet + facet normal -0.0028475 -0.106592 0.994299 + outer loop + vertex -142.098 31.8265 30.2507 + vertex -158.289 33.1968 30.3513 + vertex -143.125 25.9833 29.6214 + endloop + endfacet + facet normal -0.00407856 -0.109151 0.994017 + outer loop + vertex -143.125 25.9833 29.6214 + vertex -158.289 33.1968 30.3513 + vertex -159.36 27.355 29.7054 + endloop + endfacet + facet normal -0.00589154 -0.130451 0.991437 + outer loop + vertex -143.125 25.9833 29.6214 + vertex -159.36 27.355 29.7054 + vertex -143.973 20.9682 28.9565 + endloop + endfacet + facet normal -0.00430356 -0.10911 0.99402 + outer loop + vertex -158.289 33.1968 30.3513 + vertex -174.635 34.717 30.4474 + vertex -159.36 27.355 29.7054 + endloop + endfacet + facet normal -0.0054874 -0.111539 0.993745 + outer loop + vertex -159.36 27.355 29.7054 + vertex -174.635 34.717 30.4474 + vertex -175.726 28.8772 29.7859 + endloop + endfacet + facet normal -0.00752182 -0.133271 0.991051 + outer loop + vertex -159.36 27.355 29.7054 + vertex -175.726 28.8772 29.7859 + vertex -160.253 22.347 29.0252 + endloop + endfacet + facet normal -0.0061328 -0.11142 0.993755 + outer loop + vertex -174.635 34.717 30.4474 + vertex -191.067 36.4028 30.535 + vertex -175.726 28.8772 29.7859 + endloop + endfacet + facet normal -0.00699974 -0.113167 0.993551 + outer loop + vertex -175.726 28.8772 29.7859 + vertex -191.067 36.4028 30.535 + vertex -192.147 30.5427 29.8599 + endloop + endfacet + facet normal -0.00929658 -0.135685 0.990708 + outer loop + vertex -175.726 28.8772 29.7859 + vertex -192.147 30.5427 29.8599 + vertex -176.637 23.8604 29.0903 + endloop + endfacet + facet normal -0.00772304 -0.113034 0.993561 + outer loop + vertex -191.067 36.4028 30.535 + vertex -207.541 38.2332 30.6152 + vertex -192.147 30.5427 29.8599 + endloop + endfacet + facet normal -0.00880346 -0.115172 0.993307 + outer loop + vertex -192.147 30.5427 29.8599 + vertex -207.541 38.2332 30.6152 + vertex -208.578 32.3707 29.9262 + endloop + endfacet + facet normal -0.0113469 -0.137928 0.990377 + outer loop + vertex -192.147 30.5427 29.8599 + vertex -208.578 32.3707 29.9262 + vertex -193.039 25.5149 29.1495 + endloop + endfacet + facet normal -0.00957176 -0.115037 0.993315 + outer loop + vertex -207.541 38.2332 30.6152 + vertex -224.07 40.2351 30.6877 + vertex -208.578 32.3707 29.9262 + endloop + endfacet + facet normal -0.0103275 -0.116508 0.993136 + outer loop + vertex -208.578 32.3707 29.9262 + vertex -224.07 40.2351 30.6877 + vertex -225.032 34.3501 29.9873 + endloop + endfacet + facet normal -0.0131407 -0.139799 0.990093 + outer loop + vertex -208.578 32.3707 29.9262 + vertex -225.032 34.3501 29.9873 + vertex -209.412 27.3272 29.203 + endloop + endfacet + facet normal -0.0109776 -0.116403 0.993141 + outer loop + vertex -224.07 40.2351 30.6877 + vertex -240.677 42.3795 30.7555 + vertex -225.032 34.3501 29.9873 + endloop + endfacet + facet normal -0.0116704 -0.117737 0.992976 + outer loop + vertex -225.032 34.3501 29.9873 + vertex -240.677 42.3795 30.7555 + vertex -241.539 36.4651 30.0441 + endloop + endfacet + facet normal -0.0147343 -0.141566 0.989819 + outer loop + vertex -225.032 34.3501 29.9873 + vertex -241.539 36.4651 30.0441 + vertex -225.78 29.2915 29.2527 + endloop + endfacet + facet normal -0.0125439 -0.11761 0.992981 + outer loop + vertex -240.677 42.3795 30.7555 + vertex -257.349 44.6633 30.8154 + vertex -241.539 36.4651 30.0441 + endloop + endfacet + facet normal -0.0132685 -0.118991 0.992807 + outer loop + vertex -241.539 36.4651 30.0441 + vertex -257.349 44.6633 30.8154 + vertex -258.091 38.7287 30.0942 + endloop + endfacet + facet normal -0.0166307 -0.143504 0.98951 + outer loop + vertex -241.539 36.4651 30.0441 + vertex -258.091 38.7287 30.0942 + vertex -242.176 31.3982 29.2986 + endloop + endfacet + facet normal -0.0146072 -0.118824 0.992808 + outer loop + vertex -257.349 44.6633 30.8154 + vertex -274.013 47.0891 30.8605 + vertex -258.091 38.7287 30.0942 + endloop + endfacet + facet normal -0.0149012 -0.119377 0.992737 + outer loop + vertex -258.091 38.7287 30.0942 + vertex -274.013 47.0891 30.8605 + vertex -274.642 41.113 30.1325 + endloop + endfacet + facet normal -0.018501 -0.14431 0.98936 + outer loop + vertex -258.091 38.7287 30.0942 + vertex -274.642 41.113 30.1325 + vertex -258.606 33.6175 29.339 + endloop + endfacet + facet normal -0.0164802 -0.119211 0.992732 + outer loop + vertex -274.013 47.0891 30.8605 + vertex -290.59 49.6455 30.8923 + vertex -274.642 41.113 30.1325 + endloop + endfacet + facet normal -0.0169664 -0.120109 0.992616 + outer loop + vertex -274.642 41.113 30.1325 + vertex -290.59 49.6455 30.8923 + vertex -291.133 43.6569 30.1584 + endloop + endfacet + facet normal -0.02086 -0.145315 0.989165 + outer loop + vertex -274.642 41.113 30.1325 + vertex -291.133 43.6569 30.1584 + vertex -275.037 35.9799 29.3701 + endloop + endfacet + facet normal -0.0179595 -0.120018 0.992609 + outer loop + vertex -290.59 49.6455 30.8923 + vertex -307.045 52.3852 30.9259 + vertex -291.133 43.6569 30.1584 + endloop + endfacet + facet normal -0.0177466 -0.119635 0.992659 + outer loop + vertex -291.133 43.6569 30.1584 + vertex -307.045 52.3852 30.9259 + vertex -307.548 46.3351 30.1877 + endloop + endfacet + facet normal -0.0218885 -0.144983 0.989192 + outer loop + vertex -291.133 43.6569 30.1584 + vertex -307.548 46.3351 30.1877 + vertex -291.438 38.4672 29.391 + endloop + endfacet + facet normal -0.0159625 -0.119784 0.992672 + outer loop + vertex -307.045 52.3852 30.9259 + vertex -323.376 55.2406 31.0078 + vertex -307.548 46.3351 30.1877 + endloop + endfacet + facet normal -0.0169586 -0.121534 0.992442 + outer loop + vertex -307.548 46.3351 30.1877 + vertex -323.376 55.2406 31.0078 + vertex -323.85 49.1602 30.2551 + endloop + endfacet + facet normal -0.0211594 -0.145694 0.989103 + outer loop + vertex -307.548 46.3351 30.1877 + vertex -323.85 49.1602 30.2551 + vertex -307.783 41.1164 29.414 + endloop + endfacet + facet normal -0.0100737 -0.122074 0.99247 + outer loop + vertex -323.376 55.2406 31.0078 + vertex -339.496 58.084 31.1939 + vertex -323.85 49.1602 30.2551 + endloop + endfacet + facet normal -0.0129586 -0.127063 0.99181 + outer loop + vertex -323.85 49.1602 30.2551 + vertex -339.496 58.084 31.1939 + vertex -339.959 52.0387 30.4134 + endloop + endfacet + facet normal -0.0166158 -0.147371 0.988942 + outer loop + vertex -323.85 49.1602 30.2551 + vertex -339.959 52.0387 30.4134 + vertex -324.058 43.8975 29.4674 + endloop + endfacet + facet normal -0.000149044 -0.128039 0.991769 + outer loop + vertex -339.496 58.084 31.1939 + vertex -355.115 60.7714 31.5386 + vertex -339.959 52.0387 30.4134 + endloop + endfacet + facet normal -0.00520051 -0.136656 0.990605 + outer loop + vertex -339.959 52.0387 30.4134 + vertex -355.115 60.7714 31.5386 + vertex -355.812 54.8887 30.7234 + endloop + endfacet + facet normal -0.00819266 -0.153036 0.988187 + outer loop + vertex -339.959 52.0387 30.4134 + vertex -355.812 54.8887 30.7234 + vertex -340.233 46.7562 29.5931 + endloop + endfacet + facet normal 0.0146304 -0.138945 0.990192 + outer loop + vertex -355.115 60.7714 31.5386 + vertex -370.286 63.3934 32.1306 + vertex -355.812 54.8887 30.7234 + endloop + endfacet + facet normal 0.00660819 -0.152288 0.988314 + outer loop + vertex -355.812 54.8887 30.7234 + vertex -370.286 63.3934 32.1306 + vertex -371.414 57.7123 31.2628 + endloop + endfacet + facet normal 0.0177901 -0.121178 0.992471 + outer loop + vertex -355.115 60.7714 31.5386 + vertex -368.953 69.4295 32.8437 + vertex -370.286 63.3934 32.1306 + endloop + endfacet + facet normal 0.0430295 -0.126579 0.991023 + outer loop + vertex -368.953 69.4295 32.8437 + vertex -381.563 71.2854 33.6283 + vertex -370.286 63.3934 32.1306 + endloop + endfacet + facet normal 0.0416959 -0.12845 0.990839 + outer loop + vertex -370.286 63.3934 32.1306 + vertex -381.563 71.2854 33.6283 + vertex -386.986 66.7602 33.2698 + endloop + endfacet + facet normal 0.065777 -0.15688 0.985425 + outer loop + vertex -381.563 71.2854 33.6283 + vertex -391.878 74.0552 34.7577 + vertex -386.986 66.7602 33.2698 + endloop + endfacet + facet normal 0.0907439 -0.140244 0.98595 + outer loop + vertex -391.878 74.0552 34.7577 + vertex -397.324 72.8927 35.0936 + vertex -386.986 66.7602 33.2698 + endloop + endfacet + facet normal 0.0981036 -0.176624 0.979377 + outer loop + vertex -398.358 76.727 35.8887 + vertex -397.324 72.8927 35.0936 + vertex -391.878 74.0552 34.7577 + endloop + endfacet + facet normal 0.106644 -0.156948 0.981832 + outer loop + vertex -391.878 74.0552 34.7577 + vertex -396.474 79.4035 36.1119 + vertex -398.358 76.727 35.8887 + endloop + endfacet + facet normal 0.145788 -0.183699 0.972111 + outer loop + vertex -396.474 79.4035 36.1119 + vertex -402.229 80.7067 37.2212 + vertex -398.358 76.727 35.8887 + endloop + endfacet + facet normal 0.138599 -0.190598 0.971835 + outer loop + vertex -398.358 76.727 35.8887 + vertex -402.229 80.7067 37.2212 + vertex -403.145 77.1415 36.6527 + endloop + endfacet + facet normal 0.149886 -0.167553 0.974402 + outer loop + vertex -396.474 79.4035 36.1119 + vertex -401.005 84.4129 37.6702 + vertex -402.229 80.7067 37.2212 + endloop + endfacet + facet normal 0.161136 -0.157348 0.974308 + outer loop + vertex -395.096 83.2174 36.5 + vertex -401.005 84.4129 37.6702 + vertex -396.474 79.4035 36.1119 + endloop + endfacet + facet normal 0.111908 -0.140525 0.983732 + outer loop + vertex -389.204 77.7432 35.0477 + vertex -395.096 83.2174 36.5 + vertex -396.474 79.4035 36.1119 + endloop + endfacet + facet normal 0.125907 -0.125546 0.984066 + outer loop + vertex -388.322 82.1081 35.4918 + vertex -395.096 83.2174 36.5 + vertex -389.204 77.7432 35.0477 + endloop + endfacet + facet normal 0.0799097 -0.116847 0.98993 + outer loop + vertex -380.26 76.5516 34.1851 + vertex -388.322 82.1081 35.4918 + vertex -389.204 77.7432 35.0477 + endloop + endfacet + facet normal 0.078867 -0.124096 0.989131 + outer loop + vertex -380.26 76.5516 34.1851 + vertex -389.204 77.7432 35.0477 + vertex -381.563 71.2854 33.6283 + endloop + endfacet + facet normal 0.096431 -0.0931212 0.990974 + outer loop + vertex -381.551 81.4817 34.774 + vertex -388.322 82.1081 35.4918 + vertex -380.26 76.5516 34.1851 + endloop + endfacet + facet normal 0.0560846 -0.103927 0.993002 + outer loop + vertex -381.551 81.4817 34.774 + vertex -380.26 76.5516 34.1851 + vertex -370.069 77.2562 33.6832 + endloop + endfacet + facet normal 0.0654063 -0.0790421 0.994723 + outer loop + vertex -381.551 81.4817 34.774 + vertex -370.069 77.2562 33.6832 + vertex -379.602 85.1532 34.9376 + endloop + endfacet + facet normal 0.0982749 -0.0962977 0.990489 + outer loop + vertex -379.602 85.1532 34.9376 + vertex -387.665 86.341 35.853 + vertex -381.551 81.4817 34.774 + endloop + endfacet + facet normal 0.10039 -0.0827199 0.991503 + outer loop + vertex -379.602 85.1532 34.9376 + vertex -386.849 90.5431 36.1209 + vertex -387.665 86.341 35.853 + endloop + endfacet + facet normal 0.148876 -0.0916971 0.984595 + outer loop + vertex -386.849 90.5431 36.1209 + vertex -393.311 91.5618 37.193 + vertex -387.665 86.341 35.853 + endloop + endfacet + facet normal 0.139759 -0.101649 0.984954 + outer loop + vertex -387.665 86.341 35.853 + vertex -393.311 91.5618 37.193 + vertex -394.193 87.3618 36.8847 + endloop + endfacet + facet normal 0.139084 -0.105638 0.98463 + outer loop + vertex -387.665 86.341 35.853 + vertex -394.193 87.3618 36.8847 + vertex -388.322 82.1081 35.4918 + endloop + endfacet + facet normal 0.149908 -0.0855657 0.98499 + outer loop + vertex -386.849 90.5431 36.1209 + vertex -392.361 95.8292 37.4191 + vertex -393.311 91.5618 37.193 + endloop + endfacet + facet normal 0.156539 -0.0785407 0.984544 + outer loop + vertex -385.933 94.8288 36.3173 + vertex -392.361 95.8292 37.4191 + vertex -386.849 90.5431 36.1209 + endloop + endfacet + facet normal 0.112489 -0.0694415 0.991224 + outer loop + vertex -380.227 89.8998 35.3245 + vertex -385.933 94.8288 36.3173 + vertex -386.849 90.5431 36.1209 + endloop + endfacet + facet normal 0.111375 -0.0707377 0.991258 + outer loop + vertex -378.025 93.6918 35.3477 + vertex -385.933 94.8288 36.3173 + vertex -380.227 89.8998 35.3245 + endloop + endfacet + facet normal 0.078075 -0.0514255 0.99562 + outer loop + vertex -380.227 89.8998 35.3245 + vertex -369.245 85.5412 34.2381 + vertex -378.025 93.6918 35.3477 + endloop + endfacet + facet normal 0.0787773 -0.0506667 0.995604 + outer loop + vertex -369.245 85.5412 34.2381 + vertex -367.795 94.2331 34.5658 + vertex -378.025 93.6918 35.3477 + endloop + endfacet + facet normal 0.0786641 -0.0483478 0.995728 + outer loop + vertex -378.48 98.6808 35.6259 + vertex -378.025 93.6918 35.3477 + vertex -367.795 94.2331 34.5658 + endloop + endfacet + facet normal 0.0848492 -0.0335127 0.99583 + outer loop + vertex -378.48 98.6808 35.6259 + vertex -367.795 94.2331 34.5658 + vertex -376.309 102.672 35.5752 + endloop + endfacet + facet normal 0.119948 -0.0526618 0.991383 + outer loop + vertex -376.309 102.672 35.5752 + vertex -384.078 103.771 36.5734 + vertex -378.48 98.6808 35.6259 + endloop + endfacet + facet normal 0.123673 -0.0485191 0.991136 + outer loop + vertex -378.48 98.6808 35.6259 + vertex -384.078 103.771 36.5734 + vertex -384.985 99.2468 36.4653 + endloop + endfacet + facet normal 0.16888 -0.0574191 0.983963 + outer loop + vertex -384.078 103.771 36.5734 + vertex -390.398 104.714 37.7133 + vertex -384.985 99.2468 36.4653 + endloop + endfacet + facet normal 0.164262 -0.062105 0.98446 + outer loop + vertex -384.985 99.2468 36.4653 + vertex -390.398 104.714 37.7133 + vertex -391.358 100.217 37.5898 + endloop + endfacet + facet normal 0.163323 -0.0680002 0.984226 + outer loop + vertex -384.985 99.2468 36.4653 + vertex -391.358 100.217 37.5898 + vertex -385.933 94.8288 36.3173 + endloop + endfacet + facet normal 0.169201 -0.0553454 0.984026 + outer loop + vertex -384.078 103.771 36.5734 + vertex -389.44 109.277 37.8052 + vertex -390.398 104.714 37.7133 + endloop + endfacet + facet normal 0.173526 -0.0510174 0.983507 + outer loop + vertex -383.175 108.349 36.6517 + vertex -389.44 109.277 37.8052 + vertex -384.078 103.771 36.5734 + endloop + endfacet + facet normal 0.17403 -0.0477074 0.983584 + outer loop + vertex -383.175 108.349 36.6517 + vertex -388.517 113.825 37.8625 + vertex -389.44 109.277 37.8052 + endloop + endfacet + facet normal 0.176346 -0.0453811 0.983281 + outer loop + vertex -382.287 112.895 36.7023 + vertex -388.517 113.825 37.8625 + vertex -383.175 108.349 36.6517 + endloop + endfacet + facet normal 0.130495 -0.0365109 0.990776 + outer loop + vertex -376.763 107.797 35.7868 + vertex -382.287 112.895 36.7023 + vertex -383.175 108.349 36.6517 + endloop + endfacet + facet normal 0.131136 -0.0293102 0.990931 + outer loop + vertex -376.763 107.797 35.7868 + vertex -383.175 108.349 36.6517 + vertex -376.309 102.672 35.5752 + endloop + endfacet + facet normal 0.0834863 -0.0337334 0.995938 + outer loop + vertex -376.763 107.797 35.7868 + vertex -376.309 102.672 35.5752 + vertex -366.232 103.237 34.7495 + endloop + endfacet + facet normal 0.0884293 -0.0222942 0.995833 + outer loop + vertex -376.763 107.797 35.7868 + vertex -366.232 103.237 34.7495 + vertex -374.629 111.759 35.686 + endloop + endfacet + facet normal 0.0867391 -0.0239717 0.995943 + outer loop + vertex -366.232 103.237 34.7495 + vertex -364.684 112.251 34.8317 + vertex -374.629 111.759 35.686 + endloop + endfacet + facet normal 0.0868319 -0.0259465 0.995885 + outer loop + vertex -375.077 116.779 35.8558 + vertex -374.629 111.759 35.686 + vertex -364.684 112.251 34.8317 + endloop + endfacet + facet normal 0.0914089 -0.0153983 0.995694 + outer loop + vertex -375.077 116.779 35.8558 + vertex -364.684 112.251 34.8317 + vertex -372.985 120.634 35.7235 + endloop + endfacet + facet normal 0.128045 -0.0354338 0.991135 + outer loop + vertex -372.985 120.634 35.7235 + vertex -380.561 121.756 36.7423 + vertex -375.077 116.779 35.8558 + endloop + endfacet + facet normal 0.133495 -0.0293352 0.990615 + outer loop + vertex -375.077 116.779 35.8558 + vertex -380.561 121.756 36.7423 + vertex -381.422 117.362 36.7282 + endloop + endfacet + facet normal 0.181283 -0.0386722 0.98267 + outer loop + vertex -380.561 121.756 36.7423 + vertex -386.706 122.696 37.913 + vertex -381.422 117.362 36.7282 + endloop + endfacet + facet normal 0.179986 -0.0399985 0.982856 + outer loop + vertex -381.422 117.362 36.7282 + vertex -386.706 122.696 37.913 + vertex -387.598 118.301 37.8973 + endloop + endfacet + facet normal 0.179901 -0.0405464 0.982849 + outer loop + vertex -381.422 117.362 36.7282 + vertex -387.598 118.301 37.8973 + vertex -382.287 112.895 36.7023 + endloop + endfacet + facet normal 0.12706 -0.030363 0.99143 + outer loop + vertex -374.629 111.759 35.686 + vertex -381.422 117.362 36.7282 + vertex -382.287 112.895 36.7023 + endloop + endfacet + facet normal 0.18122 -0.0390792 0.982666 + outer loop + vertex -380.561 121.756 36.7423 + vertex -385.808 127.065 37.9211 + vertex -386.706 122.696 37.913 + endloop + endfacet + facet normal 0.183672 -0.0365757 0.982307 + outer loop + vertex -379.71 126.131 36.7461 + vertex -385.808 127.065 37.9211 + vertex -380.561 121.756 36.7423 + endloop + endfacet + facet normal 0.1835 -0.037687 0.982297 + outer loop + vertex -379.71 126.131 36.7461 + vertex -384.912 131.478 37.923 + vertex -385.808 127.065 37.9211 + endloop + endfacet + facet normal 0.183929 -0.0372563 0.982233 + outer loop + vertex -378.837 130.567 36.7507 + vertex -384.912 131.478 37.923 + vertex -379.71 126.131 36.7461 + endloop + endfacet + facet normal 0.135804 -0.0277863 0.990346 + outer loop + vertex -373.434 125.592 35.8703 + vertex -378.837 130.567 36.7507 + vertex -379.71 126.131 36.7461 + endloop + endfacet + facet normal 0.13675 -0.0169622 0.99046 + outer loop + vertex -373.434 125.592 35.8703 + vertex -379.71 126.131 36.7461 + vertex -372.985 120.634 35.7235 + endloop + endfacet + facet normal 0.0884505 -0.0214909 0.995849 + outer loop + vertex -373.434 125.592 35.8703 + vertex -372.985 120.634 35.7235 + vertex -363.142 121.184 34.8611 + endloop + endfacet + facet normal 0.0921064 -0.0129133 0.995665 + outer loop + vertex -373.434 125.592 35.8703 + vertex -363.142 121.184 34.8611 + vertex -371.346 129.522 35.7281 + endloop + endfacet + facet normal 0.0892576 -0.0157389 0.995884 + outer loop + vertex -363.142 121.184 34.8611 + vertex -361.584 130.182 34.8636 + vertex -371.346 129.522 35.7281 + endloop + endfacet + facet normal 0.0896033 -0.0210181 0.995756 + outer loop + vertex -371.751 134.594 35.8716 + vertex -371.346 129.522 35.7281 + vertex -361.584 130.182 34.8636 + endloop + endfacet + facet normal 0.0931427 -0.0128181 0.99557 + outer loop + vertex -371.751 134.594 35.8716 + vertex -361.584 130.182 34.8636 + vertex -369.667 138.609 35.7283 + endloop + endfacet + facet normal 0.131861 -0.0330905 0.990716 + outer loop + vertex -369.667 138.609 35.7283 + vertex -377.078 139.652 36.7495 + vertex -371.751 134.594 35.8716 + endloop + endfacet + facet normal 0.137527 -0.0270226 0.990129 + outer loop + vertex -371.751 134.594 35.8716 + vertex -377.078 139.652 36.7495 + vertex -377.966 135.082 36.7482 + endloop + endfacet + facet normal 0.18596 -0.0364359 0.981882 + outer loop + vertex -377.078 139.652 36.7495 + vertex -383.091 140.541 37.9214 + vertex -377.966 135.082 36.7482 + endloop + endfacet + facet normal 0.185347 -0.0370309 0.981975 + outer loop + vertex -377.966 135.082 36.7482 + vertex -383.091 140.541 37.9214 + vertex -384.007 135.977 37.9221 + endloop + endfacet + facet normal 0.185617 -0.03523 0.98199 + outer loop + vertex -377.966 135.082 36.7482 + vertex -384.007 135.977 37.9221 + vertex -378.837 130.567 36.7507 + endloop + endfacet + facet normal 0.13182 -0.0248551 0.990962 + outer loop + vertex -371.346 129.522 35.7281 + vertex -377.966 135.082 36.7482 + vertex -378.837 130.567 36.7507 + endloop + endfacet + facet normal 0.18581 -0.0374342 0.981872 + outer loop + vertex -377.078 139.652 36.7495 + vertex -382.173 145.112 37.9219 + vertex -383.091 140.541 37.9214 + endloop + endfacet + facet normal 0.18751 -0.035792 0.98161 + outer loop + vertex -376.201 144.221 36.7487 + vertex -382.173 145.112 37.9219 + vertex -377.078 139.652 36.7495 + endloop + endfacet + facet normal 0.187229 -0.0376491 0.981594 + outer loop + vertex -376.201 144.221 36.7487 + vertex -381.268 149.631 37.9227 + vertex -382.173 145.112 37.9219 + endloop + endfacet + facet normal 0.188684 -0.0362382 0.981369 + outer loop + vertex -375.335 148.734 36.7488 + vertex -381.268 149.631 37.9227 + vertex -376.201 144.221 36.7487 + endloop + endfacet + facet normal 0.140285 -0.0269497 0.989744 + outer loop + vertex -370.073 143.707 35.866 + vertex -375.335 148.734 36.7488 + vertex -376.201 144.221 36.7487 + endloop + endfacet + facet normal 0.14126 -0.0154933 0.989851 + outer loop + vertex -370.073 143.707 35.866 + vertex -376.201 144.221 36.7487 + vertex -369.667 138.609 35.7283 + endloop + endfacet + facet normal 0.0904143 -0.0196995 0.995709 + outer loop + vertex -370.073 143.707 35.866 + vertex -369.667 138.609 35.7283 + vertex -360.006 139.228 34.8633 + endloop + endfacet + facet normal 0.0931142 -0.0135988 0.995563 + outer loop + vertex -370.073 143.707 35.866 + vertex -360.006 139.228 34.8633 + vertex -368.005 147.644 35.7264 + endloop + endfacet + facet normal 0.0905363 -0.0160696 0.995763 + outer loop + vertex -360.006 139.228 34.8633 + vertex -358.444 148.161 34.8655 + vertex -368.005 147.644 35.7264 + endloop + endfacet + facet normal 0.0907297 -0.0197823 0.995679 + outer loop + vertex -368.421 152.617 35.8632 + vertex -368.005 147.644 35.7264 + vertex -358.444 148.161 34.8655 + endloop + endfacet + facet normal 0.0930101 -0.0146489 0.995557 + outer loop + vertex -368.421 152.617 35.8632 + vertex -358.444 148.161 34.8655 + vertex -366.375 156.43 35.7281 + endloop + endfacet + facet normal 0.133595 -0.03662 0.990359 + outer loop + vertex -366.375 156.43 35.7281 + vertex -373.643 157.525 36.7491 + vertex -368.421 152.617 35.8632 + endloop + endfacet + facet normal 0.141802 -0.0277338 0.989506 + outer loop + vertex -368.421 152.617 35.8632 + vertex -373.643 157.525 36.7491 + vertex -374.488 153.166 36.7479 + endloop + endfacet + facet normal 0.189222 -0.0369183 0.98124 + outer loop + vertex -373.643 157.525 36.7491 + vertex -379.542 158.429 37.9206 + vertex -374.488 153.166 36.7479 + endloop + endfacet + facet normal 0.189197 -0.036943 0.981244 + outer loop + vertex -374.488 153.166 36.7479 + vertex -379.542 158.429 37.9206 + vertex -380.397 154.067 37.9212 + endloop + endfacet + facet normal 0.189342 -0.0359995 0.981251 + outer loop + vertex -374.488 153.166 36.7479 + vertex -380.397 154.067 37.9212 + vertex -375.335 148.734 36.7488 + endloop + endfacet + facet normal 0.134374 -0.025489 0.990603 + outer loop + vertex -368.005 147.644 35.7264 + vertex -374.488 153.166 36.7479 + vertex -375.335 148.734 36.7488 + endloop + endfacet + facet normal 0.188752 -0.0399472 0.981212 + outer loop + vertex -373.643 157.525 36.7491 + vertex -378.658 162.757 37.9267 + vertex -379.542 158.429 37.9206 + endloop + endfacet + facet normal 0.190115 -0.0385934 0.981003 + outer loop + vertex -372.78 161.849 36.7518 + vertex -378.658 162.757 37.9267 + vertex -373.643 157.525 36.7491 + endloop + endfacet + facet normal 0.189808 -0.0405581 0.980983 + outer loop + vertex -372.78 161.849 36.7518 + vertex -377.745 167.102 37.9298 + vertex -378.658 162.757 37.9267 + endloop + endfacet + facet normal 0.190728 -0.0396563 0.980842 + outer loop + vertex -371.889 166.198 36.7544 + vertex -377.745 167.102 37.9298 + vertex -372.78 161.849 36.7518 + endloop + endfacet + facet normal 0.142502 -0.0297854 0.989346 + outer loop + vertex -366.765 161.312 35.8694 + vertex -371.889 166.198 36.7544 + vertex -372.78 161.849 36.7518 + endloop + endfacet + facet normal 0.143652 -0.0171407 0.98948 + outer loop + vertex -366.765 161.312 35.8694 + vertex -372.78 161.849 36.7518 + vertex -366.375 156.43 35.7281 + endloop + endfacet + facet normal 0.0923914 -0.0214165 0.995492 + outer loop + vertex -366.765 161.312 35.8694 + vertex -366.375 156.43 35.7281 + vertex -356.949 156.974 34.865 + endloop + endfacet + facet normal 0.0952092 -0.0150048 0.995344 + outer loop + vertex -366.765 161.312 35.8694 + vertex -356.949 156.974 34.865 + vertex -364.754 165.167 35.7351 + endloop + endfacet + facet normal 0.0942193 -0.0159562 0.995424 + outer loop + vertex -356.949 156.974 34.865 + vertex -355.578 165.878 34.878 + vertex -364.754 165.167 35.7351 + endloop + endfacet + facet normal 0.0946569 -0.0217852 0.995272 + outer loop + vertex -365.19 170.164 35.8859 + vertex -364.754 165.167 35.7351 + vertex -355.578 165.878 34.878 + endloop + endfacet + facet normal 0.0997178 -0.0103612 0.994962 + outer loop + vertex -365.19 170.164 35.8859 + vertex -355.578 165.878 34.878 + vertex -363.411 174.224 35.7499 + endloop + endfacet + facet normal 0.143097 -0.0295584 0.989267 + outer loop + vertex -363.411 174.224 35.7499 + vertex -370.255 175.161 36.7679 + vertex -365.19 170.164 35.8859 + endloop + endfacet + facet normal 0.147084 -0.0254349 0.988797 + outer loop + vertex -365.19 170.164 35.8859 + vertex -370.255 175.161 36.7679 + vertex -370.997 170.625 36.7616 + endloop + endfacet + facet normal 0.198167 -0.0337814 0.979586 + outer loop + vertex -370.255 175.161 36.7679 + vertex -375.856 176 37.9299 + vertex -370.997 170.625 36.7616 + endloop + endfacet + facet normal 0.191391 -0.0401482 0.980692 + outer loop + vertex -370.997 170.625 36.7616 + vertex -375.856 176 37.9299 + vertex -376.79 171.505 37.9282 + endloop + endfacet + facet normal 0.191392 -0.0401409 0.980692 + outer loop + vertex -370.997 170.625 36.7616 + vertex -376.79 171.505 37.9282 + vertex -371.889 166.198 36.7544 + endloop + endfacet + facet normal 0.13723 -0.0292446 0.990107 + outer loop + vertex -364.754 165.167 35.7351 + vertex -370.997 170.625 36.7616 + vertex -371.889 166.198 36.7544 + endloop + endfacet + facet normal 0.198298 -0.0329144 0.979589 + outer loop + vertex -370.255 175.161 36.7679 + vertex -375.121 180.592 37.9354 + vertex -375.856 176 37.9299 + endloop + endfacet + facet normal 0.205704 -0.0259947 0.978269 + outer loop + vertex -369.707 179.791 36.7757 + vertex -375.121 180.592 37.9354 + vertex -370.255 175.161 36.7679 + endloop + endfacet + facet normal 0.205724 -0.0258592 0.978268 + outer loop + vertex -369.707 179.791 36.7757 + vertex -374.575 185.252 37.9437 + vertex -375.121 180.592 37.9354 + endloop + endfacet + facet normal 0.204104 -0.0273668 0.978567 + outer loop + vertex -369.124 184.389 36.7826 + vertex -374.575 185.252 37.9437 + vertex -369.707 179.791 36.7757 + endloop + endfacet + facet normal 0.152061 -0.0207772 0.988153 + outer loop + vertex -364.023 179.374 35.8923 + vertex -369.124 184.389 36.7826 + vertex -369.707 179.791 36.7757 + endloop + endfacet + facet normal 0.15292 -0.00914466 0.988196 + outer loop + vertex -364.023 179.374 35.8923 + vertex -369.707 179.791 36.7757 + vertex -363.411 174.224 35.7499 + endloop + endfacet + facet normal 0.0968502 -0.0159983 0.99517 + outer loop + vertex -364.023 179.374 35.8923 + vertex -363.411 174.224 35.7499 + vertex -354.171 175.119 34.865 + endloop + endfacet + facet normal 0.0991306 -0.0106817 0.995017 + outer loop + vertex -364.023 179.374 35.8923 + vertex -354.171 175.119 34.865 + vertex -361.938 183.392 35.7277 + endloop + endfacet + facet normal 0.106543 -0.00364838 0.994301 + outer loop + vertex -354.171 175.119 34.865 + vertex -351.732 185.346 34.6412 + vertex -361.938 183.392 35.7277 + endloop + endfacet + facet normal 0.1078 -0.0103167 0.994119 + outer loop + vertex -362.828 187.568 35.8675 + vertex -361.938 183.392 35.7277 + vertex -351.732 185.346 34.6412 + endloop + endfacet + facet normal 0.159641 0.00097059 0.987175 + outer loop + vertex -362.828 187.568 35.8675 + vertex -368.598 188.753 36.7994 + vertex -361.938 183.392 35.7277 + endloop + endfacet + facet normal 0.142376 -0.0209603 0.989591 + outer loop + vertex -361.938 183.392 35.7277 + vertex -368.598 188.753 36.7994 + vertex -369.124 184.389 36.7826 + endloop + endfacet + facet normal 0.20043 -0.0279169 0.97931 + outer loop + vertex -368.598 188.753 36.7994 + vertex -373.934 189.87 37.9234 + vertex -369.124 184.389 36.7826 + endloop + endfacet + facet normal 0.0667341 0.0059215 0.997753 + outer loop + vertex -339.677 173.373 33.906 + vertex -351.732 185.346 34.6412 + vertex -354.171 175.119 34.865 + endloop + endfacet + facet normal 0.0651231 -0.00750543 0.997849 + outer loop + vertex -339.677 173.373 33.906 + vertex -354.171 175.119 34.865 + vertex -341.078 164.121 33.9278 + endloop + endfacet + facet normal 0.0384001 -0.00345577 0.999256 + outer loop + vertex -326.299 161.844 33.352 + vertex -339.677 173.373 33.906 + vertex -341.078 164.121 33.9278 + endloop + endfacet + facet normal 0.0381336 -0.00518637 0.999259 + outer loop + vertex -326.299 161.844 33.352 + vertex -341.078 164.121 33.9278 + vertex -327.309 152.863 33.3439 + endloop + endfacet + facet normal 0.0178831 -0.00290781 0.999836 + outer loop + vertex -312.063 150.224 33.0636 + vertex -326.299 161.844 33.352 + vertex -327.309 152.863 33.3439 + endloop + endfacet + facet normal 0.0180435 -0.00198035 0.999835 + outer loop + vertex -312.063 150.224 33.0636 + vertex -327.309 152.863 33.3439 + vertex -313.097 141.29 33.0645 + endloop + endfacet + facet normal 0.00647881 -0.000642383 0.999979 + outer loop + vertex -297.4 138.491 32.961 + vertex -312.063 150.224 33.0636 + vertex -313.097 141.29 33.0645 + endloop + endfacet + facet normal 0.00647117 -0.000685233 0.999979 + outer loop + vertex -297.4 138.491 32.961 + vertex -313.097 141.29 33.0645 + vertex -298.495 129.515 32.962 + endloop + endfacet + facet normal 0.00239517 -0.000187778 0.999997 + outer loop + vertex -282.313 126.74 32.9227 + vertex -297.4 138.491 32.961 + vertex -298.495 129.515 32.962 + endloop + endfacet + facet normal 0.00237549 -0.000302612 0.999997 + outer loop + vertex -282.313 126.74 32.9227 + vertex -298.495 129.515 32.962 + vertex -283.384 117.706 32.9225 + endloop + endfacet + facet normal 0.00272167 -0.000343635 0.999996 + outer loop + vertex -266.77 115.058 32.8764 + vertex -282.313 126.74 32.9227 + vertex -283.384 117.706 32.9225 + endloop + endfacet + facet normal 0.00264572 -0.00082015 0.999996 + outer loop + vertex -266.77 115.058 32.8764 + vertex -283.384 117.706 32.9225 + vertex -267.781 105.987 32.8716 + endloop + endfacet + facet normal 0.00408932 -0.000981068 0.999991 + outer loop + vertex -250.909 103.483 32.8002 + vertex -266.77 115.058 32.8764 + vertex -267.781 105.987 32.8716 + endloop + endfacet + facet normal 0.0038511 -0.00258617 0.999989 + outer loop + vertex -250.909 103.483 32.8002 + vertex -267.781 105.987 32.8716 + vertex -251.88 94.3901 32.7804 + endloop + endfacet + facet normal 0.00488892 -0.002697 0.999984 + outer loop + vertex -234.962 92.0221 32.6913 + vertex -250.909 103.483 32.8002 + vertex -251.88 94.3901 32.7804 + endloop + endfacet + facet normal 0.00432739 -0.00670827 0.999968 + outer loop + vertex -234.962 92.0221 32.6913 + vertex -251.88 94.3901 32.7804 + vertex -235.92 82.9294 32.6344 + endloop + endfacet + facet normal 0.00498108 -0.00677716 0.999965 + outer loop + vertex -219.105 80.7109 32.5356 + vertex -234.962 92.0221 32.6913 + vertex -235.92 82.9294 32.6344 + endloop + endfacet + facet normal 0.00396173 -0.0145 0.999887 + outer loop + vertex -219.105 80.7109 32.5356 + vertex -235.92 82.9294 32.6344 + vertex -220.071 71.6988 32.4088 + endloop + endfacet + facet normal 0.00445963 -0.0145533 0.999884 + outer loop + vertex -203.403 69.6483 32.3046 + vertex -219.105 80.7109 32.5356 + vertex -220.071 71.6988 32.4088 + endloop + endfacet + facet normal 0.0029972 -0.0264286 0.999646 + outer loop + vertex -203.403 69.6483 32.3046 + vertex -220.071 71.6988 32.4088 + vertex -204.39 60.8808 32.0758 + endloop + endfacet + facet normal 0.00361888 -0.0264985 0.999642 + outer loop + vertex -187.851 59.0101 31.9663 + vertex -203.403 69.6483 32.3046 + vertex -204.39 60.8808 32.0758 + endloop + endfacet + facet normal 0.00178728 -0.0426586 0.999088 + outer loop + vertex -187.851 59.0101 31.9663 + vertex -204.39 60.8808 32.0758 + vertex -188.876 50.726 31.6144 + endloop + endfacet + facet normal 0.00246662 -0.0427424 0.999083 + outer loop + vertex -172.441 49.0345 31.5015 + vertex -187.851 59.0101 31.9663 + vertex -188.876 50.726 31.6144 + endloop + endfacet + facet normal 0.000452079 -0.062247 0.998061 + outer loop + vertex -172.441 49.0345 31.5015 + vertex -188.876 50.726 31.6144 + vertex -173.515 41.459 31.0295 + endloop + endfacet + facet normal 0.000873011 -0.0623065 0.998057 + outer loop + vertex -157.189 39.9295 30.9197 + vertex -172.441 49.0345 31.5015 + vertex -173.515 41.459 31.0295 + endloop + endfacet + facet normal -0.00116468 -0.0839423 0.99647 + outer loop + vertex -157.189 39.9295 30.9197 + vertex -173.515 41.459 31.0295 + vertex -158.289 33.1968 30.3513 + endloop + endfacet + facet normal 0.00182925 -0.0607109 0.998154 + outer loop + vertex -156.144 47.5086 31.3788 + vertex -172.441 49.0345 31.5015 + vertex -157.189 39.9295 30.9197 + endloop + endfacet + facet normal 0.00195751 -0.0607285 0.998152 + outer loop + vertex -141.043 38.5522 30.8043 + vertex -156.144 47.5086 31.3788 + vertex -157.189 39.9295 30.9197 + endloop + endfacet + facet normal 0.000128599 -0.0820417 0.996629 + outer loop + vertex -141.043 38.5522 30.8043 + vertex -157.189 39.9295 30.9197 + vertex -142.098 31.8265 30.2507 + endloop + endfacet + facet normal 0.00288945 -0.059163 0.998244 + outer loop + vertex -140.051 46.1294 31.2505 + vertex -156.144 47.5086 31.3788 + vertex -141.043 38.5522 30.8043 + endloop + endfacet + facet normal 0.0026429 -0.0591309 0.998247 + outer loop + vertex -125.111 37.3055 30.6882 + vertex -140.051 46.1294 31.2505 + vertex -141.043 38.5522 30.8043 + endloop + endfacet + facet normal 0.00100351 -0.0799461 0.996799 + outer loop + vertex -125.111 37.3055 30.6882 + vertex -141.043 38.5522 30.8043 + vertex -126.101 30.5816 30.15 + endloop + endfacet + facet normal 0.003406 -0.0578435 0.99832 + outer loop + vertex -124.188 44.8672 31.1232 + vertex -140.051 46.1294 31.2505 + vertex -125.111 37.3055 30.6882 + endloop + endfacet + facet normal 0.00287769 -0.0577794 0.998325 + outer loop + vertex -109.357 36.1618 30.5766 + vertex -124.188 44.8672 31.1232 + vertex -125.111 37.3055 30.6882 + endloop + endfacet + facet normal 0.00139578 -0.0780576 0.996948 + outer loop + vertex -109.357 36.1618 30.5766 + vertex -125.111 37.3055 30.6882 + vertex -110.268 29.4521 30.0526 + endloop + endfacet + facet normal 0.00371258 -0.0563619 0.998404 + outer loop + vertex -108.522 43.7108 30.9997 + vertex -124.188 44.8672 31.1232 + vertex -109.357 36.1618 30.5766 + endloop + endfacet + facet normal 0.00283141 -0.056265 0.998412 + outer loop + vertex -93.7048 35.1029 30.4726 + vertex -108.522 43.7108 30.9997 + vertex -109.357 36.1618 30.5766 + endloop + endfacet + facet normal 0.00145588 -0.0764669 0.997071 + outer loop + vertex -93.7048 35.1029 30.4726 + vertex -109.357 36.1618 30.5766 + vertex -94.5214 28.4227 29.9614 + endloop + endfacet + facet normal 0.00367401 -0.0548193 0.99849 + outer loop + vertex -92.9696 42.6398 30.8837 + vertex -108.522 43.7108 30.9997 + vertex -93.7048 35.1029 30.4726 + endloop + endfacet + facet normal 0.00257153 -0.0547122 0.998499 + outer loop + vertex -78.0827 34.1209 30.3785 + vertex -92.9696 42.6398 30.8837 + vertex -93.7048 35.1029 30.4726 + endloop + endfacet + facet normal 0.00127567 -0.0751987 0.997168 + outer loop + vertex -78.0827 34.1209 30.3785 + vertex -93.7048 35.1029 30.4726 + vertex -78.7928 27.4816 29.8788 + endloop + endfacet + facet normal 0.00326364 -0.0535065 0.998562 + outer loop + vertex -77.4542 41.64 30.7794 + vertex -92.9696 42.6398 30.8837 + vertex -78.0827 34.1209 30.3785 + endloop + endfacet + facet normal 0.0024139 -0.0534358 0.998568 + outer loop + vertex -62.4549 33.2655 30.295 + vertex -77.4542 41.64 30.7794 + vertex -78.0827 34.1209 30.3785 + endloop + endfacet + facet normal 0.00129776 -0.0737017 0.997279 + outer loop + vertex -62.4549 33.2655 30.295 + vertex -78.0827 34.1209 30.3785 + vertex -63.0469 26.6486 29.8067 + endloop + endfacet + facet normal 0.00276262 -0.0528131 0.998601 + outer loop + vertex -61.9422 40.7337 30.6885 + vertex -77.4542 41.64 30.7794 + vertex -62.4549 33.2655 30.295 + endloop + endfacet + facet normal 0.00177799 -0.0527458 0.998606 + outer loop + vertex -46.828 32.5165 30.2276 + vertex -61.9422 40.7337 30.6885 + vertex -62.4549 33.2655 30.295 + endloop + endfacet + facet normal 0.00081203 -0.0727863 0.997347 + outer loop + vertex -46.828 32.5165 30.2276 + vertex -62.4549 33.2655 30.295 + vertex -47.2926 25.9352 29.7477 + endloop + endfacet + facet normal 0.00228855 -0.0518094 0.998654 + outer loop + vertex -46.4349 39.9653 30.6131 + vertex -61.9422 40.7337 30.6885 + vertex -46.828 32.5165 30.2276 + endloop + endfacet + facet normal 0.00136858 -0.0517611 0.998659 + outer loop + vertex -31.214 31.943 30.1765 + vertex -46.4349 39.9653 30.6131 + vertex -46.828 32.5165 30.2276 + endloop + endfacet + facet normal 0.000614742 -0.0721718 0.997392 + outer loop + vertex -31.214 31.943 30.1765 + vertex -46.828 32.5165 30.2276 + vertex -31.5447 25.3953 29.7029 + endloop + endfacet + facet normal 0.00161703 -0.051291 0.998682 + outer loop + vertex -30.9455 39.363 30.5571 + vertex -46.4349 39.9653 30.6131 + vertex -31.214 31.943 30.1765 + endloop + endfacet + facet normal 0.000858799 -0.0512636 0.998685 + outer loop + vertex -15.6119 31.5755 30.1442 + vertex -30.9455 39.363 30.5571 + vertex -31.214 31.943 30.1765 + endloop + endfacet + facet normal 0.000370552 -0.0718814 0.997413 + outer loop + vertex -15.6119 31.5755 30.1442 + vertex -31.214 31.943 30.1765 + vertex -15.8089 25.0541 29.6743 + endloop + endfacet + facet normal 0.000981994 -0.0510217 0.998697 + outer loop + vertex -15.4709 38.9753 30.5221 + vertex -30.9455 39.363 30.5571 + vertex -15.6119 31.5755 30.1442 + endloop + endfacet + facet normal 0.000280728 -0.0510084 0.998698 + outer loop + vertex -0.00250011 31.4402 30.1329 + vertex -15.4709 38.9753 30.5221 + vertex -15.6119 31.5755 30.1442 + endloop + endfacet + facet normal 9.89758e-05 -0.0718609 0.997415 + outer loop + vertex -0.00250011 31.4402 30.1329 + vertex -15.6119 31.5755 30.1442 + vertex -0.0668718 24.9297 29.6638 + endloop + endfacet + facet normal 0.000391209 -0.0507822 0.99871 + outer loop + vertex 0.00957795 38.8441 30.5094 + vertex -15.4709 38.9753 30.5221 + vertex -0.00250011 31.4402 30.1329 + endloop + endfacet + facet normal -0.00023059 -0.0507812 0.99871 + outer loop + vertex 15.6365 31.5587 30.1425 + vertex 0.00957795 38.8441 30.5094 + vertex -0.00250011 31.4402 30.1329 + endloop + endfacet + facet normal -7.07287e-05 -0.0717683 0.997421 + outer loop + vertex 15.6365 31.5587 30.1425 + vertex -0.00250011 31.4402 30.1329 + vertex 15.7022 25.0258 29.6725 + endloop + endfacet + facet normal -0.000270546 -0.0508667 0.998705 + outer loop + vertex 15.5185 38.9727 30.5201 + vertex 0.00957795 38.8441 30.5094 + vertex 15.6365 31.5587 30.1425 + endloop + endfacet + facet normal -0.000687781 -0.0508733 0.998705 + outer loop + vertex 31.307 31.927 30.1721 + vertex 15.5185 38.9727 30.5201 + vertex 15.6365 31.5587 30.1425 + endloop + endfacet + facet normal -0.000186886 -0.072081 0.997399 + outer loop + vertex 31.307 31.927 30.1721 + vertex 15.6365 31.5587 30.1425 + vertex 31.5057 25.3697 29.6982 + endloop + endfacet + facet normal -0.00104115 -0.0516631 0.998664 + outer loop + vertex 31.0578 39.3376 30.5552 + vertex 15.5185 38.9727 30.5201 + vertex 31.307 31.927 30.1721 + endloop + endfacet + facet normal -0.00131175 -0.0516722 0.998663 + outer loop + vertex 46.9782 32.4927 30.2219 + vertex 31.0578 39.3376 30.5552 + vertex 31.307 31.927 30.1721 + endloop + endfacet + facet normal -0.000549493 -0.0726746 0.997356 + outer loop + vertex 46.9782 32.4927 30.2219 + vertex 31.307 31.927 30.1721 + vertex 47.3084 25.899 29.7416 + endloop + endfacet + facet normal -0.00139974 -0.0518763 0.998653 + outer loop + vertex 46.6054 39.9508 30.6088 + vertex 31.0578 39.3376 30.5552 + vertex 46.9782 32.4927 30.2219 + endloop + endfacet + facet normal -0.00181566 -0.051897 0.998651 + outer loop + vertex 62.6223 33.2325 30.2888 + vertex 46.6054 39.9508 30.6088 + vertex 46.9782 32.4927 30.2219 + endloop + endfacet + facet normal -0.000773572 -0.0738084 0.997272 + outer loop + vertex 62.6223 33.2325 30.2888 + vertex 46.9782 32.4927 30.2219 + vertex 63.0812 26.6114 29.7992 + endloop + endfacet + facet normal -0.00216675 -0.0527319 0.998606 + outer loop + vertex 62.1292 40.7207 30.6832 + vertex 46.6054 39.9508 30.6088 + vertex 62.6223 33.2325 30.2888 + endloop + endfacet + facet normal -0.00221703 -0.0527352 0.998606 + outer loop + vertex 78.2474 34.1116 30.3699 + vertex 62.1292 40.7207 30.6832 + vertex 62.6223 33.2325 30.2888 + endloop + endfacet + facet normal -0.000965617 -0.0748477 0.997195 + outer loop + vertex 78.2474 34.1116 30.3699 + vertex 62.6223 33.2325 30.2888 + vertex 78.8246 27.4468 29.8702 + endloop + endfacet + facet normal -0.00271782 -0.0539534 0.99854 + outer loop + vertex 77.6401 41.6225 30.7741 + vertex 62.1292 40.7207 30.6832 + vertex 78.2474 34.1116 30.3699 + endloop + endfacet + facet normal -0.00263939 -0.0539471 0.99854 + outer loop + vertex 93.9123 35.0933 30.4644 + vertex 77.6401 41.6225 30.7741 + vertex 78.2474 34.1116 30.3699 + endloop + endfacet + facet normal -0.0012208 -0.0764427 0.997073 + outer loop + vertex 93.9123 35.0933 30.4644 + vertex 78.2474 34.1116 30.3699 + vertex 94.596 28.4 29.9521 + endloop + endfacet + facet normal -0.00309217 -0.0550725 0.998478 + outer loop + vertex 93.2013 42.6347 30.8781 + vertex 77.6401 41.6225 30.7741 + vertex 93.9123 35.0933 30.4644 + endloop + endfacet + facet normal -0.00289313 -0.0550538 0.998479 + outer loop + vertex 109.694 36.1669 30.5693 + vertex 93.2013 42.6347 30.8781 + vertex 93.9123 35.0933 30.4644 + endloop + endfacet + facet normal -0.00129085 -0.0784544 0.996917 + outer loop + vertex 109.694 36.1669 30.5693 + vertex 93.9123 35.0933 30.4644 + vertex 110.471 29.4607 30.0426 + endloop + endfacet + facet normal -0.00347729 -0.0565394 0.998394 + outer loop + vertex 108.887 43.7267 30.9946 + vertex 93.2013 42.6347 30.8781 + vertex 109.694 36.1669 30.5693 + endloop + endfacet + facet normal -0.00290898 -0.056479 0.9984 + outer loop + vertex 125.625 37.3339 30.6817 + vertex 108.887 43.7267 30.9946 + vertex 109.694 36.1669 30.5693 + endloop + endfacet + facet normal -0.00114172 -0.0804451 0.996758 + outer loop + vertex 125.625 37.3339 30.6817 + vertex 109.694 36.1669 30.5693 + vertex 126.478 30.6137 30.1404 + endloop + endfacet + facet normal -0.00344521 -0.057879 0.998318 + outer loop + vertex 124.734 44.9117 31.118 + vertex 108.887 43.7267 30.9946 + vertex 125.625 37.3339 30.6817 + endloop + endfacet + facet normal -0.00269547 -0.0577913 0.998325 + outer loop + vertex 141.675 38.5982 30.7983 + vertex 124.734 44.9117 31.118 + vertex 125.625 37.3339 30.6817 + endloop + endfacet + facet normal -0.000735537 -0.082512 0.99659 + outer loop + vertex 141.675 38.5982 30.7983 + vertex 125.625 37.3339 30.6817 + vertex 142.59 31.8696 30.2418 + endloop + endfacet + facet normal -0.00335531 -0.0595564 0.998219 + outer loop + vertex 140.711 46.1798 31.2474 + vertex 124.734 44.9117 31.118 + vertex 141.675 38.5982 30.7983 + endloop + endfacet + facet normal -0.00209259 -0.0593966 0.998232 + outer loop + vertex 157.796 39.9786 30.9142 + vertex 140.711 46.1798 31.2474 + vertex 141.675 38.5982 30.7983 + endloop + endfacet + facet normal 5.12611e-05 -0.0842837 0.996442 + outer loop + vertex 157.796 39.9786 30.9142 + vertex 141.675 38.5982 30.7983 + vertex 158.756 33.2354 30.3438 + endloop + endfacet + facet normal -0.00275443 -0.0612141 0.998121 + outer loop + vertex 156.778 47.5587 31.3763 + vertex 140.711 46.1798 31.2474 + vertex 157.796 39.9786 30.9142 + endloop + endfacet + facet normal -0.00121769 -0.0610086 0.998136 + outer loop + vertex 173.986 41.4869 31.0261 + vertex 156.778 47.5587 31.3763 + vertex 157.796 39.9786 30.9142 + endloop + endfacet + facet normal 0.00116402 -0.0864332 0.996257 + outer loop + vertex 173.986 41.4869 31.0261 + vertex 157.796 39.9786 30.9142 + vertex 174.969 34.75 30.4405 + endloop + endfacet + facet normal -0.00175844 -0.0625357 0.998041 + outer loop + vertex 172.94 49.0743 31.4997 + vertex 156.778 47.5587 31.3763 + vertex 173.986 41.4869 31.0261 + endloop + endfacet + facet normal -4.20698e-06 -0.0622949 0.998058 + outer loop + vertex 190.296 43.1535 31.1302 + vertex 172.94 49.0743 31.4997 + vertex 173.986 41.4869 31.0261 + endloop + endfacet + facet normal 0.00265006 -0.0881496 0.996104 + outer loop + vertex 190.296 43.1535 31.1302 + vertex 173.986 41.4869 31.0261 + vertex 191.274 36.4119 30.531 + endloop + endfacet + facet normal -0.000457768 -0.0636193 0.997974 + outer loop + vertex 189.251 50.7525 31.6142 + vertex 172.94 49.0743 31.4997 + vertex 190.296 43.1535 31.1302 + endloop + endfacet + facet normal 0.00157563 -0.0633407 0.997991 + outer loop + vertex 206.776 45.011 31.2221 + vertex 189.251 50.7525 31.6142 + vertex 190.296 43.1535 31.1302 + endloop + endfacet + facet normal 0.00446107 -0.0888445 0.996036 + outer loop + vertex 206.776 45.011 31.2221 + vertex 190.296 43.1535 31.1302 + vertex 207.717 38.2359 30.6136 + endloop + endfacet + facet normal 0.000983936 -0.0651389 0.997876 + outer loop + vertex 205.759 52.6021 31.7186 + vertex 189.251 50.7525 31.6142 + vertex 206.776 45.011 31.2221 + endloop + endfacet + facet normal 0.00277166 -0.0649001 0.997888 + outer loop + vertex 223.423 47.0201 31.3065 + vertex 205.759 52.6021 31.7186 + vertex 206.776 45.011 31.2221 + endloop + endfacet + facet normal 0.00588752 -0.0906313 0.995867 + outer loop + vertex 223.423 47.0201 31.3065 + vertex 206.776 45.011 31.2221 + vertex 224.298 40.247 30.685 + endloop + endfacet + facet normal 0.00263357 -0.065335 0.99786 + outer loop + vertex 222.457 54.6485 31.8085 + vertex 205.759 52.6021 31.7186 + vertex 223.423 47.0201 31.3065 + endloop + endfacet + facet normal 0.00422948 -0.0651336 0.997868 + outer loop + vertex 240.184 49.2119 31.3785 + vertex 222.457 54.6485 31.8085 + vertex 223.423 47.0201 31.3065 + endloop + endfacet + facet normal 0.00761743 -0.0909761 0.995824 + outer loop + vertex 240.184 49.2119 31.3785 + vertex 223.423 47.0201 31.3065 + vertex 240.976 42.3945 30.7497 + endloop + endfacet + facet normal 0.00379467 -0.0665441 0.997776 + outer loop + vertex 239.287 56.8468 31.8912 + vertex 222.457 54.6485 31.8085 + vertex 240.184 49.2119 31.3785 + endloop + endfacet + facet normal 0.00543378 -0.0663518 0.997781 + outer loop + vertex 257.011 51.5573 31.4429 + vertex 239.287 56.8468 31.8912 + vertex 240.184 49.2119 31.3785 + endloop + endfacet + facet normal 0.00903796 -0.0921518 0.995704 + outer loop + vertex 257.011 51.5573 31.4429 + vertex 240.184 49.2119 31.3785 + vertex 257.703 44.7197 30.8038 + endloop + endfacet + facet normal 0.00513531 -0.0673464 0.997716 + outer loop + vertex 256.195 59.218 31.9642 + vertex 239.287 56.8468 31.8912 + vertex 257.011 51.5573 31.4429 + endloop + endfacet + facet normal 0.00641464 -0.0672103 0.997718 + outer loop + vertex 273.867 54.0578 31.503 + vertex 256.195 59.218 31.9642 + vertex 257.011 51.5573 31.4429 + endloop + endfacet + facet normal 0.0102528 -0.0930333 0.99561 + outer loop + vertex 273.867 54.0578 31.503 + vertex 257.011 51.5573 31.4429 + vertex 274.455 47.1808 30.8543 + endloop + endfacet + facet normal 0.0063503 -0.0674293 0.997704 + outer loop + vertex 273.128 61.7667 32.0287 + vertex 256.195 59.218 31.9642 + vertex 273.867 54.0578 31.503 + endloop + endfacet + facet normal 0.00735808 -0.0673327 0.997703 + outer loop + vertex 290.668 56.7079 31.5579 + vertex 273.128 61.7667 32.0287 + vertex 273.867 54.0578 31.503 + endloop + endfacet + facet normal 0.0114841 -0.0934467 0.995558 + outer loop + vertex 290.668 56.7079 31.5579 + vertex 273.867 54.0578 31.503 + vertex 291.169 49.7975 30.9035 + endloop + endfacet + facet normal 0.00712874 -0.068123 0.997651 + outer loop + vertex 289.987 64.4163 32.0891 + vertex 273.128 61.7667 32.0287 + vertex 290.668 56.7079 31.5579 + endloop + endfacet + facet normal 0.00780859 -0.0680628 0.99765 + outer loop + vertex 307.252 59.3895 31.611 + vertex 289.987 64.4163 32.0891 + vertex 290.668 56.7079 31.5579 + endloop + endfacet + facet normal 0.011973 -0.0937749 0.995521 + outer loop + vertex 307.252 59.3895 31.611 + vertex 290.668 56.7079 31.5579 + vertex 307.717 52.4845 30.955 + endloop + endfacet + facet normal 0.0117786 -0.093788 0.995523 + outer loop + vertex 323.903 55.1489 31.0145 + vertex 307.252 59.3895 31.611 + vertex 307.717 52.4845 30.955 + endloop + endfacet + facet normal 0.011679 -0.0941739 0.995487 + outer loop + vertex 323.4 62.0422 31.6725 + vertex 307.252 59.3895 31.611 + vertex 323.903 55.1489 31.0145 + endloop + endfacet + facet normal 0.0085095 -0.0944062 0.995497 + outer loop + vertex 339.641 57.7966 31.1311 + vertex 323.4 62.0422 31.6725 + vertex 323.903 55.1489 31.0145 + endloop + endfacet + facet normal 0.0137671 -0.125502 0.991998 + outer loop + vertex 339.641 57.7966 31.1311 + vertex 323.903 55.1489 31.0145 + vertex 340.029 51.7791 30.3644 + endloop + endfacet + facet normal 0.00755158 -0.125905 0.992014 + outer loop + vertex 355.554 54.5036 30.592 + vertex 339.641 57.7966 31.1311 + vertex 340.029 51.7791 30.3644 + endloop + endfacet + facet normal 0.00510162 -0.137495 0.990489 + outer loop + vertex 355.165 60.5891 31.4388 + vertex 339.641 57.7966 31.1311 + vertex 355.554 54.5036 30.592 + endloop + endfacet + facet normal -0.00666303 -0.138232 0.990377 + outer loop + vertex 371.122 57.5921 31.1278 + vertex 355.165 60.5891 31.4388 + vertex 355.554 54.5036 30.592 + endloop + endfacet + facet normal 0.00270084 -0.184134 0.982897 + outer loop + vertex 371.122 57.5921 31.1278 + vertex 355.554 54.5036 30.592 + vertex 371.636 52.3464 30.1437 + endloop + endfacet + facet normal -0.00904356 -0.185239 0.982652 + outer loop + vertex 387.465 55.7928 30.9391 + vertex 371.122 57.5921 31.1278 + vertex 371.636 52.3464 30.1437 + endloop + endfacet + facet normal -0.0127058 -0.217798 0.975911 + outer loop + vertex 386.85 61.1607 32.129 + vertex 371.122 57.5921 31.1278 + vertex 387.465 55.7928 30.9391 + endloop + endfacet + facet normal -0.0262963 -0.219223 0.97532 + outer loop + vertex 403.241 59.5145 32.2009 + vertex 386.85 61.1607 32.129 + vertex 387.465 55.7928 30.9391 + endloop + endfacet + facet normal -0.0308993 -0.265566 0.963597 + outer loop + vertex 401.956 64.9665 33.6623 + vertex 386.85 61.1607 32.129 + vertex 403.241 59.5145 32.2009 + endloop + endfacet + facet normal -0.0484462 -0.269234 0.961855 + outer loop + vertex 401.956 64.9665 33.6623 + vertex 403.241 59.5145 32.2009 + vertex 412.71 62.6953 33.5682 + endloop + endfacet + facet normal -0.0105358 -0.158532 0.987298 + outer loop + vertex 370.858 63.8687 32.1329 + vertex 355.165 60.5891 31.4388 + vertex 371.122 57.5921 31.1278 + endloop + endfacet + facet normal -0.0267121 -0.159146 0.986894 + outer loop + vertex 386.85 61.1607 32.129 + vertex 370.858 63.8687 32.1329 + vertex 371.122 57.5921 31.1278 + endloop + endfacet + facet normal -0.0312106 -0.185704 0.98211 + outer loop + vertex 387.05 67.6443 33.3613 + vertex 370.858 63.8687 32.1329 + vertex 386.85 61.1607 32.129 + endloop + endfacet + facet normal -0.0530259 -0.184884 0.981329 + outer loop + vertex 401.956 64.9665 33.6623 + vertex 387.05 67.6443 33.3613 + vertex 386.85 61.1607 32.129 + endloop + endfacet + facet normal -0.0580508 -0.213543 0.975207 + outer loop + vertex 397.197 68.0466 34.0534 + vertex 387.05 67.6443 33.3613 + vertex 401.956 64.9665 33.6623 + endloop + endfacet + facet normal -0.0758835 -0.240154 0.967764 + outer loop + vertex 397.197 68.0466 34.0534 + vertex 401.956 64.9665 33.6623 + vertex 403.576 69.2287 34.8469 + endloop + endfacet + facet normal -0.0834604 -0.204347 0.975334 + outer loop + vertex 403.576 69.2287 34.8469 + vertex 395.835 71.1822 34.5938 + vertex 397.197 68.0466 34.0534 + endloop + endfacet + facet normal -0.0897964 -0.230279 0.968973 + outer loop + vertex 403.513 72.9173 35.7178 + vertex 395.835 71.1822 34.5938 + vertex 403.576 69.2287 34.8469 + endloop + endfacet + facet normal -0.109657 -0.230139 0.96696 + outer loop + vertex 410.738 71.145 36.1153 + vertex 403.513 72.9173 35.7178 + vertex 403.576 69.2287 34.8469 + endloop + endfacet + facet normal -0.118517 -0.268741 0.955893 + outer loop + vertex 409.895 74.5978 36.9815 + vertex 403.513 72.9173 35.7178 + vertex 410.738 71.145 36.1153 + endloop + endfacet + facet normal -0.142421 -0.273424 0.951292 + outer loop + vertex 416.925 72.7282 37.4966 + vertex 409.895 74.5978 36.9815 + vertex 410.738 71.145 36.1153 + endloop + endfacet + facet normal -0.154716 -0.324671 0.933087 + outer loop + vertex 415.544 75.9232 38.3792 + vertex 409.895 74.5978 36.9815 + vertex 416.925 72.7282 37.4966 + endloop + endfacet + facet normal -0.181756 -0.334088 0.924851 + outer loop + vertex 422.392 73.9554 39.0143 + vertex 415.544 75.9232 38.3792 + vertex 416.925 72.7282 37.4966 + endloop + endfacet + facet normal -0.0853968 -0.236565 0.967856 + outer loop + vertex 411.34 67.8094 35.1851 + vertex 403.576 69.2287 34.8469 + vertex 401.956 64.9665 33.6623 + endloop + endfacet + facet normal -0.0590776 -0.194411 0.979139 + outer loop + vertex 397.197 68.0466 34.0534 + vertex 395.835 71.1822 34.5938 + vertex 387.05 67.6443 33.3613 + endloop + endfacet + facet normal -0.020465 -0.112323 0.993461 + outer loop + vertex 370.858 63.8687 32.1329 + vertex 354.759 67.6735 32.2314 + vertex 355.165 60.5891 31.4388 + endloop + endfacet + facet normal -0.00471331 -0.111453 0.993758 + outer loop + vertex 354.759 67.6735 32.2314 + vertex 339.132 64.7009 31.8239 + vertex 355.165 60.5891 31.4388 + endloop + endfacet + facet normal -0.0116899 -0.0752365 0.997097 + outer loop + vertex 354.759 67.6735 32.2314 + vertex 338.457 72.4657 32.4019 + vertex 339.132 64.7009 31.8239 + endloop + endfacet + facet normal 0.000531752 -0.0741858 0.997244 + outer loop + vertex 338.457 72.4657 32.4019 + vertex 322.682 69.73 32.2068 + vertex 339.132 64.7009 31.8239 + endloop + endfacet + facet normal 0.00208574 -0.0691304 0.997605 + outer loop + vertex 339.132 64.7009 31.8239 + vertex 322.682 69.73 32.2068 + vertex 323.4 62.0422 31.6725 + endloop + endfacet + facet normal 0.0069447 -0.0686772 0.997615 + outer loop + vertex 322.682 69.73 32.2068 + vertex 306.557 67.0956 32.1377 + vertex 323.4 62.0422 31.6725 + endloop + endfacet + facet normal 0.0030948 -0.0451484 0.998975 + outer loop + vertex 322.682 69.73 32.2068 + vertex 305.67 75.4471 32.5179 + vertex 306.557 67.0956 32.1377 + endloop + endfacet + facet normal 0.00445745 -0.0450036 0.998977 + outer loop + vertex 305.67 75.4471 32.5179 + vertex 289.128 72.7906 32.472 + vertex 306.557 67.0956 32.1377 + endloop + endfacet + facet normal 0.0043854 -0.0452235 0.998967 + outer loop + vertex 306.557 67.0956 32.1377 + vertex 289.128 72.7906 32.472 + vertex 289.987 64.4163 32.0891 + endloop + endfacet + facet normal 0.00373556 -0.0452901 0.998967 + outer loop + vertex 289.128 72.7906 32.472 + vertex 272.263 70.1312 32.4145 + vertex 289.987 64.4163 32.0891 + endloop + endfacet + facet normal 0.000988347 -0.027882 0.999611 + outer loop + vertex 289.128 72.7906 32.472 + vertex 271.317 78.945 32.6613 + vertex 272.263 70.1312 32.4145 + endloop + endfacet + facet normal -0.000131123 -0.028002 0.999608 + outer loop + vertex 271.317 78.945 32.6613 + vertex 254.316 76.3786 32.5871 + vertex 272.263 70.1312 32.4145 + endloop + endfacet + facet normal -2.74137e-05 -0.0277043 0.999616 + outer loop + vertex 272.263 70.1312 32.4145 + vertex 254.316 76.3786 32.5871 + vertex 255.279 67.5743 32.3432 + endloop + endfacet + facet normal 0.00269959 -0.0457995 0.998947 + outer loop + vertex 272.263 70.1312 32.4145 + vertex 255.279 67.5743 32.3432 + vertex 273.128 61.7667 32.0287 + endloop + endfacet + facet normal -0.000931695 -0.0278032 0.999613 + outer loop + vertex 254.316 76.3786 32.5871 + vertex 237.322 73.9608 32.5041 + vertex 255.279 67.5743 32.3432 + endloop + endfacet + facet normal -0.000800208 -0.0274337 0.999623 + outer loop + vertex 255.279 67.5743 32.3432 + vertex 237.322 73.9608 32.5041 + vertex 238.317 65.1772 32.2638 + endloop + endfacet + facet normal 0.00170208 -0.0451194 0.99898 + outer loop + vertex 255.279 67.5743 32.3432 + vertex 238.317 65.1772 32.2638 + vertex 256.195 59.218 31.9642 + endloop + endfacet + facet normal -0.00183352 -0.0275507 0.999619 + outer loop + vertex 237.322 73.9608 32.5041 + vertex 220.421 71.724 32.4114 + vertex 238.317 65.1772 32.2638 + endloop + endfacet + facet normal -0.00158622 -0.0268751 0.999638 + outer loop + vertex 238.317 65.1772 32.2638 + vertex 220.421 71.724 32.4114 + vertex 221.441 62.9492 32.1771 + endloop + endfacet + facet normal 0.000757088 -0.0446001 0.999005 + outer loop + vertex 238.317 65.1772 32.2638 + vertex 221.441 62.9492 32.1771 + vertex 239.287 56.8468 31.8912 + endloop + endfacet + facet normal -0.00278749 -0.0270145 0.999631 + outer loop + vertex 220.421 71.724 32.4114 + vertex 203.681 69.6638 32.3091 + vertex 221.441 62.9492 32.1771 + endloop + endfacet + facet normal -0.00267807 -0.0267253 0.999639 + outer loop + vertex 221.441 62.9492 32.1771 + vertex 203.681 69.6638 32.3091 + vertex 204.714 60.9054 32.0777 + endloop + endfacet + facet normal -0.000512095 -0.0444208 0.999013 + outer loop + vertex 221.441 62.9492 32.1771 + vertex 204.714 60.9054 32.0777 + vertex 222.457 54.6485 31.8085 + endloop + endfacet + facet normal -0.00399061 -0.0268798 0.999631 + outer loop + vertex 203.681 69.6638 32.3091 + vertex 187.169 67.7945 32.1929 + vertex 204.714 60.9054 32.0777 + endloop + endfacet + facet normal -0.00371613 -0.0261812 0.99965 + outer loop + vertex 204.714 60.9054 32.0777 + vertex 187.169 67.7945 32.1929 + vertex 188.194 59.0386 31.9674 + endloop + endfacet + facet normal -0.00176403 -0.043421 0.999055 + outer loop + vertex 204.714 60.9054 32.0777 + vertex 188.194 59.0386 31.9674 + vertex 205.759 52.6021 31.7186 + endloop + endfacet + facet normal -0.00510096 -0.0263429 0.99964 + outer loop + vertex 187.169 67.7945 32.1929 + vertex 170.894 66.1051 32.0653 + vertex 188.194 59.0386 31.9674 + endloop + endfacet + facet normal -0.00486725 -0.025771 0.999656 + outer loop + vertex 188.194 59.0386 31.9674 + vertex 170.894 66.1051 32.0653 + vertex 171.894 57.3552 31.8446 + endloop + endfacet + facet normal -0.00308573 -0.0429786 0.999071 + outer loop + vertex 188.194 59.0386 31.9674 + vertex 171.894 57.3552 31.8446 + vertex 189.251 50.7525 31.6142 + endloop + endfacet + facet normal -0.00596716 -0.0258965 0.999647 + outer loop + vertex 170.894 66.1051 32.0653 + vertex 154.807 64.5741 31.9296 + vertex 171.894 57.3552 31.8446 + endloop + endfacet + facet normal -0.00578103 -0.0254561 0.999659 + outer loop + vertex 171.894 57.3552 31.8446 + vertex 154.807 64.5741 31.9296 + vertex 155.767 55.8348 31.7126 + endloop + endfacet + facet normal -0.00420333 -0.0421428 0.999103 + outer loop + vertex 171.894 57.3552 31.8446 + vertex 155.767 55.8348 31.7126 + vertex 172.94 49.0743 31.4997 + endloop + endfacet + facet normal -0.0068433 -0.0255725 0.99965 + outer loop + vertex 154.807 64.5741 31.9296 + vertex 138.86 63.1921 31.7851 + vertex 155.767 55.8348 31.7126 + endloop + endfacet + facet normal -0.00648555 -0.0247507 0.999673 + outer loop + vertex 155.767 55.8348 31.7126 + vertex 138.86 63.1921 31.7851 + vertex 139.757 54.4531 31.5745 + endloop + endfacet + facet normal -0.00505912 -0.0412246 0.999137 + outer loop + vertex 155.767 55.8348 31.7126 + vertex 139.757 54.4531 31.5745 + vertex 156.778 47.5587 31.3763 + endloop + endfacet + facet normal -0.00714407 -0.0248181 0.999666 + outer loop + vertex 138.86 63.1921 31.7851 + vertex 123.035 61.9169 31.6403 + vertex 139.757 54.4531 31.5745 + endloop + endfacet + facet normal -0.00664237 -0.0236943 0.999697 + outer loop + vertex 139.757 54.4531 31.5745 + vertex 123.035 61.9169 31.6403 + vertex 123.851 53.168 31.4384 + endloop + endfacet + facet normal -0.00531035 -0.040127 0.99918 + outer loop + vertex 139.757 54.4531 31.5745 + vertex 123.851 53.168 31.4384 + vertex 140.711 46.1798 31.2474 + endloop + endfacet + facet normal -0.00709383 -0.0237363 0.999693 + outer loop + vertex 123.035 61.9169 31.6403 + vertex 107.363 60.7264 31.5009 + vertex 123.851 53.168 31.4384 + endloop + endfacet + facet normal -0.00683003 -0.023161 0.999708 + outer loop + vertex 123.851 53.168 31.4384 + vertex 107.363 60.7264 31.5009 + vertex 108.095 51.9897 31.3035 + endloop + endfacet + facet normal -0.00561304 -0.0393764 0.999209 + outer loop + vertex 123.851 53.168 31.4384 + vertex 108.095 51.9897 31.3035 + vertex 124.734 44.9117 31.118 + endloop + endfacet + facet normal -0.00669838 -0.02315 0.99971 + outer loop + vertex 107.363 60.7264 31.5009 + vertex 91.8628 59.6098 31.3712 + vertex 108.095 51.9897 31.3035 + endloop + endfacet + facet normal -0.00640811 -0.0225318 0.999726 + outer loop + vertex 108.095 51.9897 31.3035 + vertex 91.8628 59.6098 31.3712 + vertex 92.5053 50.8839 31.1786 + endloop + endfacet + facet normal -0.00531725 -0.0378597 0.999269 + outer loop + vertex 108.095 51.9897 31.3035 + vertex 92.5053 50.8839 31.1786 + vertex 108.887 43.7267 30.9946 + endloop + endfacet + facet normal -0.0060919 -0.0225086 0.999728 + outer loop + vertex 91.8628 59.6098 31.3712 + vertex 76.4999 58.5721 31.2542 + vertex 92.5053 50.8839 31.1786 + endloop + endfacet + facet normal -0.00580761 -0.0219169 0.999743 + outer loop + vertex 92.5053 50.8839 31.1786 + vertex 76.4999 58.5721 31.2542 + vertex 77.0464 49.859 31.0663 + endloop + endfacet + facet normal -0.00481743 -0.0368054 0.999311 + outer loop + vertex 92.5053 50.8839 31.1786 + vertex 77.0464 49.859 31.0663 + vertex 93.2013 42.6347 30.8781 + endloop + endfacet + facet normal -0.00528252 -0.021884 0.999747 + outer loop + vertex 76.4999 58.5721 31.2542 + vertex 61.194 57.6309 31.1527 + vertex 77.0464 49.859 31.0663 + endloop + endfacet + facet normal -0.00491726 -0.0211392 0.999764 + outer loop + vertex 77.0464 49.859 31.0663 + vertex 61.194 57.6309 31.1527 + vertex 61.6387 48.9217 30.9707 + endloop + endfacet + facet normal -0.00402611 -0.0357457 0.999353 + outer loop + vertex 77.0464 49.859 31.0663 + vertex 61.6387 48.9217 30.9707 + vertex 77.6401 41.6225 30.7741 + endloop + endfacet + facet normal -0.00430385 -0.0211079 0.999768 + outer loop + vertex 61.194 57.6309 31.1527 + vertex 45.8818 56.8196 31.0696 + vertex 61.6387 48.9217 30.9707 + endloop + endfacet + facet normal -0.00411426 -0.0207298 0.999777 + outer loop + vertex 61.6387 48.9217 30.9707 + vertex 45.8818 56.8196 31.0696 + vertex 46.2261 48.1274 30.8908 + endloop + endfacet + facet normal -0.00336421 -0.0352435 0.999373 + outer loop + vertex 61.6387 48.9217 30.9707 + vertex 46.2261 48.1274 30.8908 + vertex 62.1292 40.7207 30.6832 + endloop + endfacet + facet normal -0.00318271 -0.020693 0.999781 + outer loop + vertex 45.8818 56.8196 31.0696 + vertex 30.5531 56.1862 31.0077 + vertex 46.2261 48.1274 30.8908 + endloop + endfacet + facet normal -0.00308532 -0.0205036 0.999785 + outer loop + vertex 46.2261 48.1274 30.8908 + vertex 30.5531 56.1862 31.0077 + vertex 30.7959 47.5161 30.8307 + endloop + endfacet + facet normal -0.00252592 -0.0345857 0.999399 + outer loop + vertex 46.2261 48.1274 30.8908 + vertex 30.7959 47.5161 30.8307 + vertex 46.6054 39.9508 30.6088 + endloop + endfacet + facet normal -0.001995 -0.0204732 0.999788 + outer loop + vertex 30.5531 56.1862 31.0077 + vertex 15.2356 55.786 30.969 + vertex 30.7959 47.5161 30.8307 + endloop + endfacet + facet normal -0.00178399 -0.0200763 0.999797 + outer loop + vertex 30.7959 47.5161 30.8307 + vertex 15.2356 55.786 30.969 + vertex 15.3709 47.113 30.7951 + endloop + endfacet + facet normal -0.00142681 -0.0337121 0.999431 + outer loop + vertex 30.7959 47.5161 30.8307 + vertex 15.3709 47.113 30.7951 + vertex 31.0578 39.3376 30.5552 + endloop + endfacet + facet normal -0.000634898 -0.0200584 0.999799 + outer loop + vertex 15.2356 55.786 30.969 + vertex -0.0484522 55.6447 30.9564 + vertex 15.3709 47.113 30.7951 + endloop + endfacet + facet normal -0.000679568 -0.0201391 0.999797 + outer loop + vertex 15.3709 47.113 30.7951 + vertex -0.0484522 55.6447 30.9564 + vertex -0.0164628 46.9888 30.7821 + endloop + endfacet + facet normal -0.000569262 -0.0337682 0.99943 + outer loop + vertex 15.3709 47.113 30.7951 + vertex -0.0164628 46.9888 30.7821 + vertex 15.5185 38.9727 30.5201 + endloop + endfacet + facet normal 0.000653501 -0.0201342 0.999797 + outer loop + vertex -0.0484522 55.6447 30.9564 + vertex -15.3021 55.7895 30.9693 + vertex -0.0164628 46.9888 30.7821 + endloop + endfacet + facet normal 0.000682015 -0.0200847 0.999798 + outer loop + vertex -0.0164628 46.9888 30.7821 + vertex -15.3021 55.7895 30.9693 + vertex -15.3775 47.1252 30.7953 + endloop + endfacet + facet normal 0.000562907 -0.0334671 0.99944 + outer loop + vertex -0.0164628 46.9888 30.7821 + vertex -15.3775 47.1252 30.7953 + vertex 0.00957795 38.8441 30.5094 + endloop + endfacet + facet normal 0.00206375 -0.0200966 0.999796 + outer loop + vertex -15.3021 55.7895 30.9693 + vertex -30.5542 56.187 31.0088 + vertex -15.3775 47.1252 30.7953 + endloop + endfacet + facet normal 0.0018808 -0.0204029 0.99979 + outer loop + vertex -15.3775 47.1252 30.7953 + vertex -30.5542 56.187 31.0088 + vertex -30.7339 47.5246 30.8324 + endloop + endfacet + facet normal 0.0015387 -0.0335243 0.999437 + outer loop + vertex -15.3775 47.1252 30.7953 + vertex -30.7339 47.5246 30.8324 + vertex -15.4709 38.9753 30.5221 + endloop + endfacet + facet normal 0.00320533 -0.0204303 0.999786 + outer loop + vertex -30.5542 56.187 31.0088 + vertex -45.8242 56.8232 31.0708 + vertex -30.7339 47.5246 30.8324 + endloop + endfacet + facet normal 0.00315067 -0.020519 0.999784 + outer loop + vertex -30.7339 47.5246 30.8324 + vertex -45.8242 56.8232 31.0708 + vertex -46.1091 48.1344 30.8933 + endloop + endfacet + facet normal 0.00262353 -0.0337734 0.999426 + outer loop + vertex -30.7339 47.5246 30.8324 + vertex -46.1091 48.1344 30.8933 + vertex -30.9455 39.363 30.5571 + endloop + endfacet + facet normal 0.00434461 -0.020558 0.999779 + outer loop + vertex -45.8242 56.8232 31.0708 + vertex -61.1179 57.6364 31.1539 + vertex -46.1091 48.1344 30.8933 + endloop + endfacet + facet normal 0.00406741 -0.0209957 0.999771 + outer loop + vertex -46.1091 48.1344 30.8933 + vertex -61.1179 57.6364 31.1539 + vertex -61.5045 48.9372 30.9728 + endloop + endfacet + facet normal 0.00336583 -0.0344139 0.999402 + outer loop + vertex -46.1091 48.1344 30.8933 + vertex -61.5045 48.9372 30.9728 + vertex -46.4349 39.9653 30.6131 + endloop + endfacet + facet normal 0.00532162 -0.0210513 0.999764 + outer loop + vertex -61.1179 57.6364 31.1539 + vertex -76.4233 58.5793 31.2553 + vertex -61.5045 48.9372 30.9728 + endloop + endfacet + facet normal 0.0050235 -0.0215123 0.999756 + outer loop + vertex -61.5045 48.9372 30.9728 + vertex -76.4233 58.5793 31.2553 + vertex -76.9094 49.8643 31.0702 + endloop + endfacet + facet normal 0.00421788 -0.0348588 0.999383 + outer loop + vertex -61.5045 48.9372 30.9728 + vertex -76.9094 49.8643 31.0702 + vertex -61.9422 40.7337 30.6885 + endloop + endfacet + facet normal 0.00616706 -0.0215759 0.999748 + outer loop + vertex -76.4233 58.5793 31.2553 + vertex -91.7399 59.6109 31.372 + vertex -76.9094 49.8643 31.0702 + endloop + endfacet + facet normal 0.00581962 -0.0221043 0.999739 + outer loop + vertex -76.9094 49.8643 31.0702 + vertex -91.7399 59.6109 31.372 + vertex -92.3221 50.8806 31.1824 + endloop + endfacet + facet normal 0.00492287 -0.035662 0.999352 + outer loop + vertex -76.9094 49.8643 31.0702 + vertex -92.3221 50.8806 31.1824 + vertex -77.4542 41.64 30.7794 + endloop + endfacet + facet normal 0.00678361 -0.0221684 0.999731 + outer loop + vertex -91.7399 59.6109 31.372 + vertex -107.104 60.713 31.5007 + vertex -92.3221 50.8806 31.1824 + endloop + endfacet + facet normal 0.00635981 -0.0228052 0.99972 + outer loop + vertex -92.3221 50.8806 31.1824 + vertex -107.104 60.713 31.5007 + vertex -107.779 51.9745 31.3057 + endloop + endfacet + facet normal 0.00537704 -0.0366453 0.999314 + outer loop + vertex -92.3221 50.8806 31.1824 + vertex -107.779 51.9745 31.3057 + vertex -92.9696 42.6398 30.8837 + endloop + endfacet + facet normal 0.00716276 -0.022867 0.999713 + outer loop + vertex -107.104 60.713 31.5007 + vertex -122.595 61.8868 31.6385 + vertex -107.779 51.9745 31.3057 + endloop + endfacet + facet normal 0.00673163 -0.023511 0.999701 + outer loop + vertex -107.779 51.9745 31.3057 + vertex -122.595 61.8868 31.6385 + vertex -123.356 53.1407 31.438 + endloop + endfacet + facet normal 0.00568002 -0.0375095 0.99928 + outer loop + vertex -107.779 51.9745 31.3057 + vertex -123.356 53.1407 31.438 + vertex -108.522 43.7108 30.9997 + endloop + endfacet + facet normal 0.00722137 -0.0235535 0.999696 + outer loop + vertex -122.595 61.8868 31.6385 + vertex -138.302 63.1524 31.7818 + vertex -123.356 53.1407 31.438 + endloop + endfacet + facet normal 0.0067745 -0.0242202 0.999684 + outer loop + vertex -123.356 53.1407 31.438 + vertex -138.302 63.1524 31.7818 + vertex -139.14 54.4005 31.5755 + endloop + endfacet + facet normal 0.00562455 -0.0385798 0.99924 + outer loop + vertex -123.356 53.1407 31.438 + vertex -139.14 54.4005 31.5755 + vertex -124.188 44.8672 31.1232 + endloop + endfacet + facet normal 0.00686985 -0.0242293 0.999683 + outer loop + vertex -138.302 63.1524 31.7818 + vertex -154.271 64.5386 31.9251 + vertex -139.14 54.4005 31.5755 + endloop + endfacet + facet normal 0.00633352 -0.0250292 0.999667 + outer loop + vertex -139.14 54.4005 31.5755 + vertex -154.271 64.5386 31.9251 + vertex -155.176 55.7899 31.7118 + endloop + endfacet + facet normal 0.00504834 -0.0398154 0.999194 + outer loop + vertex -139.14 54.4005 31.5755 + vertex -155.176 55.7899 31.7118 + vertex -140.051 46.1294 31.2505 + endloop + endfacet + facet normal 0.00608928 -0.025004 0.999669 + outer loop + vertex -154.271 64.5386 31.9251 + vertex -170.481 66.0749 32.0623 + vertex -155.176 55.7899 31.7118 + endloop + endfacet + facet normal 0.00576116 -0.0254919 0.999658 + outer loop + vertex -155.176 55.7899 31.7118 + vertex -170.481 66.0749 32.0623 + vertex -171.432 57.3162 31.8444 + endloop + endfacet + facet normal 0.0043303 -0.0406888 0.999162 + outer loop + vertex -155.176 55.7899 31.7118 + vertex -171.432 57.3162 31.8444 + vertex -156.144 47.5086 31.3788 + endloop + endfacet + facet normal 0.00515136 -0.0254258 0.999663 + outer loop + vertex -170.481 66.0749 32.0623 + vertex -186.871 67.7725 32.19 + vertex -171.432 57.3162 31.8444 + endloop + endfacet + facet normal 0.00473123 -0.0260457 0.99965 + outer loop + vertex -171.432 57.3162 31.8444 + vertex -186.871 67.7725 32.19 + vertex -187.851 59.0101 31.9663 + endloop + endfacet + facet normal 0.00631426 -0.014214 0.999879 + outer loop + vertex -170.481 66.0749 32.0623 + vertex -185.922 76.7709 32.3119 + vertex -186.871 67.7725 32.19 + endloop + endfacet + facet normal 0.00554572 -0.014133 0.999885 + outer loop + vertex -185.922 76.7709 32.3119 + vertex -202.436 78.6496 32.43 + vertex -186.871 67.7725 32.19 + endloop + endfacet + facet normal 0.00528772 -0.0145021 0.999881 + outer loop + vertex -186.871 67.7725 32.19 + vertex -202.436 78.6496 32.43 + vertex -203.403 69.6483 32.3046 + endloop + endfacet + facet normal 0.00639266 -0.00669287 0.999957 + outer loop + vertex -185.922 76.7709 32.3119 + vertex -201.482 87.7294 32.4847 + vertex -202.436 78.6496 32.43 + endloop + endfacet + facet normal 0.00566256 -0.00661621 0.999962 + outer loop + vertex -201.482 87.7294 32.4847 + vertex -218.142 89.7928 32.5927 + vertex -202.436 78.6496 32.43 + endloop + endfacet + facet normal 0.00548664 -0.00686416 0.999961 + outer loop + vertex -202.436 78.6496 32.43 + vertex -218.142 89.7928 32.5927 + vertex -219.105 80.7109 32.5356 + endloop + endfacet + facet normal 0.00615516 -0.00263976 0.999978 + outer loop + vertex -201.482 87.7294 32.4847 + vertex -217.18 98.876 32.6107 + vertex -218.142 89.7928 32.5927 + endloop + endfacet + facet normal 0.00560292 -0.00258123 0.999981 + outer loop + vertex -217.18 98.876 32.6107 + vertex -233.995 101.109 32.7107 + vertex -218.142 89.7928 32.5927 + endloop + endfacet + facet normal 0.00550021 -0.00272512 0.999981 + outer loop + vertex -218.142 89.7928 32.5927 + vertex -233.995 101.109 32.7107 + vertex -234.962 92.0221 32.6913 + endloop + endfacet + facet normal 0.00580178 -0.00108354 0.999983 + outer loop + vertex -217.18 98.876 32.6107 + vertex -233.018 110.175 32.7149 + vertex -233.995 101.109 32.7107 + endloop + endfacet + facet normal 0.00520255 -0.00101891 0.999986 + outer loop + vertex -233.018 110.175 32.7149 + vertex -249.921 112.552 32.8052 + vertex -233.995 101.109 32.7107 + endloop + endfacet + facet normal 0.00513015 -0.00111967 0.999986 + outer loop + vertex -233.995 101.109 32.7107 + vertex -249.921 112.552 32.8052 + vertex -250.909 103.483 32.8002 + endloop + endfacet + facet normal 0.00523721 -0.000772383 0.999986 + outer loop + vertex -233.018 110.175 32.7149 + vertex -248.919 121.595 32.807 + vertex -249.921 112.552 32.8052 + endloop + endfacet + facet normal 0.00408768 -0.000644888 0.999991 + outer loop + vertex -248.919 121.595 32.807 + vertex -265.739 124.1 32.8774 + vertex -249.921 112.552 32.8052 + endloop + endfacet + facet normal 0.00413546 -0.000579452 0.999991 + outer loop + vertex -249.921 112.552 32.8052 + vertex -265.739 124.1 32.8774 + vertex -266.77 115.058 32.8764 + endloop + endfacet + facet normal 0.00410628 -0.000520056 0.999991 + outer loop + vertex -248.919 121.595 32.807 + vertex -264.709 133.107 32.8778 + vertex -265.739 124.1 32.8774 + endloop + endfacet + facet normal 0.00256604 -0.000343891 0.999997 + outer loop + vertex -264.709 133.107 32.8778 + vertex -281.25 135.737 32.9212 + vertex -265.739 124.1 32.8774 + endloop + endfacet + facet normal 0.00271187 -0.000149508 0.999996 + outer loop + vertex -265.739 124.1 32.8774 + vertex -281.25 135.737 32.9212 + vertex -282.313 126.74 32.9227 + endloop + endfacet + facet normal 0.00264654 0.000162521 0.999996 + outer loop + vertex -264.709 133.107 32.8778 + vertex -280.224 144.71 32.917 + vertex -281.25 135.737 32.9212 + endloop + endfacet + facet normal 0.00254521 0.000174106 0.999997 + outer loop + vertex -280.224 144.71 32.917 + vertex -296.378 147.442 32.9576 + vertex -281.25 135.737 32.9212 + endloop + endfacet + facet normal 0.00248601 9.75984e-05 0.999997 + outer loop + vertex -281.25 135.737 32.9212 + vertex -296.378 147.442 32.9576 + vertex -297.4 138.491 32.961 + endloop + endfacet + facet normal 0.00250434 -6.75034e-05 0.999997 + outer loop + vertex -280.224 144.71 32.917 + vertex -295.42 156.417 32.9558 + vertex -296.378 147.442 32.9576 + endloop + endfacet + facet normal 0.00712096 -0.000560218 0.999974 + outer loop + vertex -295.42 156.417 32.9558 + vertex -311.129 159.186 33.0692 + vertex -296.378 147.442 32.9576 + endloop + endfacet + facet normal 0.00652205 -0.00131253 0.999978 + outer loop + vertex -296.378 147.442 32.9576 + vertex -311.129 159.186 33.0692 + vertex -312.063 150.224 33.0636 + endloop + endfacet + facet normal 0.00674039 -0.00271933 0.999974 + outer loop + vertex -295.42 156.417 32.9558 + vertex -310.284 168.248 33.0882 + vertex -311.129 159.186 33.0692 + endloop + endfacet + facet normal 0.0173761 -0.00371036 0.999842 + outer loop + vertex -310.284 168.248 33.0882 + vertex -325.304 170.938 33.3592 + vertex -311.129 159.186 33.0692 + endloop + endfacet + facet normal 0.0181478 -0.0027793 0.999831 + outer loop + vertex -311.129 159.186 33.0692 + vertex -325.304 170.938 33.3592 + vertex -326.299 161.844 33.352 + endloop + endfacet + facet normal 0.017894 -0.00081787 0.99984 + outer loop + vertex -310.284 168.248 33.0882 + vertex -325.06 180.271 33.3625 + vertex -325.304 170.938 33.3592 + endloop + endfacet + facet normal 0.0318979 -0.00118436 0.99949 + outer loop + vertex -325.06 180.271 33.3625 + vertex -337.867 182.663 33.774 + vertex -325.304 170.938 33.3592 + endloop + endfacet + facet normal 0.0391238 0.00656724 0.999213 + outer loop + vertex -325.304 170.938 33.3592 + vertex -337.867 182.663 33.774 + vertex -339.677 173.373 33.906 + endloop + endfacet + facet normal 0.0130107 -0.00682093 0.999892 + outer loop + vertex -309.379 177.448 33.1392 + vertex -325.06 180.271 33.3625 + vertex -310.284 168.248 33.0882 + endloop + endfacet + facet normal 0.00615187 -0.00614656 0.999962 + outer loop + vertex -294.486 165.49 32.974 + vertex -309.379 177.448 33.1392 + vertex -310.284 168.248 33.0882 + endloop + endfacet + facet normal 0.00363315 -0.0092834 0.99995 + outer loop + vertex -293.715 174.744 33.0572 + vertex -309.379 177.448 33.1392 + vertex -294.486 165.49 32.974 + endloop + endfacet + facet normal 0.00137837 -0.00909575 0.999958 + outer loop + vertex -278.279 162.8 32.9272 + vertex -293.715 174.744 33.0572 + vertex -294.486 165.49 32.974 + endloop + endfacet + facet normal 0.00257159 -0.00190726 0.999995 + outer loop + vertex -278.279 162.8 32.9272 + vertex -294.486 165.49 32.974 + vertex -279.231 153.704 32.9123 + endloop + endfacet + facet normal 0.00198638 -0.00184601 0.999996 + outer loop + vertex -262.691 151.096 32.8747 + vertex -278.279 162.8 32.9272 + vertex -279.231 153.704 32.9123 + endloop + endfacet + facet normal 0.00226423 -8.37771e-05 0.999997 + outer loop + vertex -262.691 151.096 32.8747 + vertex -279.231 153.704 32.9123 + vertex -263.688 142.094 32.8762 + endloop + endfacet + facet normal 0.00377487 -0.000251058 0.999993 + outer loop + vertex -246.906 139.587 32.8122 + vertex -262.691 151.096 32.8747 + vertex -263.688 142.094 32.8762 + endloop + endfacet + facet normal 0.00370772 -0.000700619 0.999993 + outer loop + vertex -246.906 139.587 32.8122 + vertex -263.688 142.094 32.8762 + vertex -247.911 130.602 32.8096 + endloop + endfacet + facet normal 0.00517381 -0.000864669 0.999986 + outer loop + vertex -231.029 128.215 32.7202 + vertex -246.906 139.587 32.8122 + vertex -247.911 130.602 32.8096 + endloop + endfacet + facet normal 0.00516213 -0.000947273 0.999986 + outer loop + vertex -231.029 128.215 32.7202 + vertex -247.911 130.602 32.8096 + vertex -232.027 119.212 32.7168 + endloop + endfacet + facet normal 0.00592019 -0.00103125 0.999982 + outer loop + vertex -215.217 116.969 32.615 + vertex -231.029 128.215 32.7202 + vertex -232.027 119.212 32.7168 + endloop + endfacet + facet normal 0.00596111 -0.000724649 0.999982 + outer loop + vertex -215.217 116.969 32.615 + vertex -232.027 119.212 32.7168 + vertex -216.203 107.935 32.6143 + endloop + endfacet + facet normal 0.00649499 -0.000782893 0.999979 + outer loop + vertex -199.563 105.864 32.5046 + vertex -215.217 116.969 32.615 + vertex -216.203 107.935 32.6143 + endloop + endfacet + facet normal 0.00647284 -0.000960887 0.999979 + outer loop + vertex -199.563 105.864 32.5046 + vertex -216.203 107.935 32.6143 + vertex -200.527 96.8067 32.5022 + endloop + endfacet + facet normal 0.00714302 -0.00103225 0.999974 + outer loop + vertex -184.059 94.9183 32.3826 + vertex -199.563 105.864 32.5046 + vertex -200.527 96.8067 32.5022 + endloop + endfacet + facet normal 0.00696313 -0.00260095 0.999972 + outer loop + vertex -184.059 94.9183 32.3826 + vertex -200.527 96.8067 32.5022 + vertex -184.991 85.8457 32.3655 + endloop + endfacet + facet normal 0.00779167 -0.00268604 0.999966 + outer loop + vertex -168.675 84.1404 32.2338 + vertex -184.059 94.9183 32.3826 + vertex -184.991 85.8457 32.3655 + endloop + endfacet + facet normal 0.0073985 -0.00644662 0.999952 + outer loop + vertex -168.675 84.1404 32.2338 + vertex -184.991 85.8457 32.3655 + vertex -169.566 75.0671 32.1819 + endloop + endfacet + facet normal 0.00810114 -0.00651558 0.999946 + outer loop + vertex -153.41 73.5312 32.041 + vertex -168.675 84.1404 32.2338 + vertex -169.566 75.0671 32.1819 + endloop + endfacet + facet normal 0.00742809 -0.013589 0.99988 + outer loop + vertex -153.41 73.5312 32.041 + vertex -169.566 75.0671 32.1819 + vertex -154.271 64.5386 31.9251 + endloop + endfacet + facet normal 0.00824497 -0.00630864 0.999946 + outer loop + vertex -152.578 82.6039 32.0914 + vertex -168.675 84.1404 32.2338 + vertex -153.41 73.5312 32.041 + endloop + endfacet + facet normal 0.00868071 -0.00634859 0.999942 + outer loop + vertex -137.511 72.1437 31.8941 + vertex -152.578 82.6039 32.0914 + vertex -153.41 73.5312 32.041 + endloop + endfacet + facet normal 0.00808206 -0.0132019 0.99988 + outer loop + vertex -137.511 72.1437 31.8941 + vertex -153.41 73.5312 32.041 + vertex -138.302 63.1524 31.7818 + endloop + endfacet + facet normal 0.00880077 -0.00617564 0.999942 + outer loop + vertex -136.749 81.2147 31.9435 + vertex -152.578 82.6039 32.0914 + vertex -137.511 72.1437 31.8941 + endloop + endfacet + facet normal 0.0088432 -0.0061792 0.999942 + outer loop + vertex -121.882 70.8742 31.7481 + vertex -136.749 81.2147 31.9435 + vertex -137.511 72.1437 31.8941 + endloop + endfacet + facet normal 0.00830122 -0.0128451 0.999883 + outer loop + vertex -121.882 70.8742 31.7481 + vertex -137.511 72.1437 31.8941 + vertex -122.595 61.8868 31.6385 + endloop + endfacet + facet normal 0.0089958 -0.00595981 0.999942 + outer loop + vertex -121.199 79.9453 31.796 + vertex -136.749 81.2147 31.9435 + vertex -121.882 70.8742 31.7481 + endloop + endfacet + facet normal 0.00869266 -0.00593701 0.999945 + outer loop + vertex -106.476 69.697 31.6072 + vertex -121.199 79.9453 31.796 + vertex -121.882 70.8742 31.7481 + endloop + endfacet + facet normal 0.00819663 -0.0124219 0.999889 + outer loop + vertex -106.476 69.697 31.6072 + vertex -121.882 70.8742 31.7481 + vertex -107.104 60.713 31.5007 + endloop + endfacet + facet normal 0.00886702 -0.00568651 0.999945 + outer loop + vertex -105.88 78.7683 31.6535 + vertex -121.199 79.9453 31.796 + vertex -106.476 69.697 31.6072 + endloop + endfacet + facet normal 0.00823413 -0.00564491 0.99995 + outer loop + vertex -91.2016 68.5913 31.4751 + vertex -105.88 78.7683 31.6535 + vertex -106.476 69.697 31.6072 + endloop + endfacet + facet normal 0.00777733 -0.0119492 0.999898 + outer loop + vertex -91.2016 68.5913 31.4751 + vertex -106.476 69.697 31.6072 + vertex -91.7399 59.6109 31.372 + endloop + endfacet + facet normal 0.00837082 -0.00544776 0.99995 + outer loop + vertex -90.6917 77.6606 31.5203 + vertex -105.88 78.7683 31.6535 + vertex -91.2016 68.5913 31.4751 + endloop + endfacet + facet normal 0.00744339 -0.00539566 0.999958 + outer loop + vertex -75.9764 67.5505 31.3562 + vertex -90.6917 77.6606 31.5203 + vertex -91.2016 68.5913 31.4751 + endloop + endfacet + facet normal 0.00701891 -0.0115991 0.999908 + outer loop + vertex -75.9764 67.5505 31.3562 + vertex -91.2016 68.5913 31.4751 + vertex -76.4233 58.5793 31.2553 + endloop + endfacet + facet normal 0.00758595 -0.00518816 0.999958 + outer loop + vertex -75.5535 76.6183 31.4 + vertex -90.6917 77.6606 31.5203 + vertex -75.9764 67.5505 31.3562 + endloop + endfacet + facet normal 0.0064897 -0.00513707 0.999966 + outer loop + vertex -60.763 66.5993 31.2526 + vertex -75.5535 76.6183 31.4 + vertex -75.9764 67.5505 31.3562 + endloop + endfacet + facet normal 0.00610746 -0.0112455 0.999918 + outer loop + vertex -60.763 66.5993 31.2526 + vertex -75.9764 67.5505 31.3562 + vertex -61.1179 57.6364 31.1539 + endloop + endfacet + facet normal 0.00660275 -0.00497018 0.999966 + outer loop + vertex -60.4266 75.6643 31.2954 + vertex -75.5535 76.6183 31.4 + vertex -60.763 66.5993 31.2526 + endloop + endfacet + facet normal 0.00534814 -0.00492366 0.999974 + outer loop + vertex -45.5615 65.7802 31.1672 + vertex -60.4266 75.6643 31.2954 + vertex -60.763 66.5993 31.2526 + endloop + endfacet + facet normal 0.0050249 -0.010918 0.999928 + outer loop + vertex -45.5615 65.7802 31.1672 + vertex -60.763 66.5993 31.2526 + vertex -45.8242 56.8232 31.0708 + endloop + endfacet + facet normal 0.00541737 -0.00481955 0.999974 + outer loop + vertex -45.3118 74.8384 31.2095 + vertex -60.4266 75.6643 31.2954 + vertex -45.5615 65.7802 31.1672 + endloop + endfacet + facet normal 0.00399606 -0.00478041 0.999981 + outer loop + vertex -30.3842 65.1412 31.1035 + vertex -45.3118 74.8384 31.2095 + vertex -45.5615 65.7802 31.1672 + endloop + endfacet + facet normal 0.00374876 -0.0106499 0.999936 + outer loop + vertex -30.3842 65.1412 31.1035 + vertex -45.5615 65.7802 31.1672 + vertex -30.5542 56.187 31.0088 + endloop + endfacet + facet normal 0.004056 -0.00468815 0.999981 + outer loop + vertex -30.2204 74.1943 31.1453 + vertex -45.3118 74.8384 31.2095 + vertex -30.3842 65.1412 31.1035 + endloop + endfacet + facet normal 0.00248943 -0.00465983 0.999986 + outer loop + vertex -15.2263 64.7339 31.0639 + vertex -30.2204 74.1943 31.1453 + vertex -30.3842 65.1412 31.1035 + endloop + endfacet + facet normal 0.00232991 -0.0105922 0.999941 + outer loop + vertex -15.2263 64.7339 31.0639 + vertex -30.3842 65.1412 31.1035 + vertex -15.3021 55.7895 30.9693 + endloop + endfacet + facet normal 0.00253673 -0.00458486 0.999986 + outer loop + vertex -15.1481 73.7841 31.1052 + vertex -30.2204 74.1943 31.1453 + vertex -15.2263 64.7339 31.0639 + endloop + endfacet + facet normal 0.000849569 -0.00457029 0.999989 + outer loop + vertex -0.0662386 64.591 31.0504 + vertex -15.1481 73.7841 31.1052 + vertex -15.2263 64.7339 31.0639 + endloop + endfacet + facet normal 0.000793682 -0.0104964 0.999945 + outer loop + vertex -0.0662386 64.591 31.0504 + vertex -15.2263 64.7339 31.0639 + vertex -0.0484522 55.6447 30.9564 + endloop + endfacet + facet normal 0.000868254 -0.00453964 0.999989 + outer loop + vertex -0.0713403 73.6468 31.0915 + vertex -15.1481 73.7841 31.1052 + vertex -0.0662386 64.591 31.0504 + endloop + endfacet + facet normal -0.000847652 -0.00454061 0.999989 + outer loop + vertex 15.1224 64.7292 31.0639 + vertex -0.0713403 73.6468 31.0915 + vertex -0.0662386 64.591 31.0504 + endloop + endfacet + facet normal -0.000792318 -0.0106192 0.999943 + outer loop + vertex 15.1224 64.7292 31.0639 + vertex -0.0662386 64.591 31.0504 + vertex 15.2356 55.786 30.969 + endloop + endfacet + facet normal -0.000848596 -0.00454222 0.999989 + outer loop + vertex 15.0321 73.7868 31.1049 + vertex -0.0713403 73.6468 31.0915 + vertex 15.1224 64.7292 31.0639 + endloop + endfacet + facet normal -0.00247214 -0.00455837 0.999987 + outer loop + vertex 30.3467 65.1372 31.1034 + vertex 15.0321 73.7868 31.1049 + vertex 15.1224 64.7292 31.0639 + endloop + endfacet + facet normal -0.00230647 -0.0107354 0.99994 + outer loop + vertex 30.3467 65.1372 31.1034 + vertex 15.1224 64.7292 31.0639 + vertex 30.5531 56.1862 31.0077 + endloop + endfacet + facet normal -0.00250479 -0.00461618 0.999986 + outer loop + vertex 30.1706 74.1964 31.1447 + vertex 15.0321 73.7868 31.1049 + vertex 30.3467 65.1372 31.1034 + endloop + endfacet + facet normal -0.00398556 -0.00464496 0.999981 + outer loop + vertex 45.5819 65.7763 31.1671 + vertex 30.1706 74.1964 31.1447 + vertex 30.3467 65.1372 31.1034 + endloop + endfacet + facet normal -0.00371881 -0.010999 0.999933 + outer loop + vertex 45.5819 65.7763 31.1671 + vertex 30.3467 65.1372 31.1034 + vertex 45.8818 56.8196 31.0696 + endloop + endfacet + facet normal -0.00403679 -0.00473873 0.999981 + outer loop + vertex 45.3205 74.8398 31.209 + vertex 30.1706 74.1964 31.1447 + vertex 45.5819 65.7763 31.1671 + endloop + endfacet + facet normal -0.00528632 -0.00477474 0.999975 + outer loop + vertex 60.8035 66.5997 31.2515 + vertex 45.3205 74.8398 31.209 + vertex 45.5819 65.7763 31.1671 + endloop + endfacet + facet normal -0.00493711 -0.0112257 0.999925 + outer loop + vertex 60.8035 66.5997 31.2515 + vertex 45.5819 65.7763 31.1671 + vertex 61.194 57.6309 31.1527 + endloop + endfacet + facet normal -0.0054013 -0.0049908 0.999973 + outer loop + vertex 60.4536 75.6615 31.2948 + vertex 45.3205 74.8398 31.209 + vertex 60.8035 66.5997 31.2515 + endloop + endfacet + facet normal -0.00649874 -0.00503314 0.999966 + outer loop + vertex 76.0181 67.5486 31.3551 + vertex 60.4536 75.6615 31.2948 + vertex 60.8035 66.5997 31.2515 + endloop + endfacet + facet normal -0.00609064 -0.0115707 0.999915 + outer loop + vertex 76.0181 67.5486 31.3551 + vertex 60.8035 66.5997 31.2515 + vertex 76.4999 58.5721 31.2542 + endloop + endfacet + facet normal -0.00656606 -0.0051623 0.999965 + outer loop + vertex 75.5839 76.6163 31.3991 + vertex 60.4536 75.6615 31.2948 + vertex 76.0181 67.5486 31.3551 + endloop + endfacet + facet normal -0.007473 -0.0052057 0.999959 + outer loop + vertex 91.2913 68.5927 31.4747 + vertex 75.5839 76.6163 31.3991 + vertex 76.0181 67.5486 31.3551 + endloop + endfacet + facet normal -0.00701011 -0.0119709 0.999904 + outer loop + vertex 91.2913 68.5927 31.4747 + vertex 76.0181 67.5486 31.3551 + vertex 91.8628 59.6098 31.3712 + endloop + endfacet + facet normal -0.0075833 -0.00542163 0.999957 + outer loop + vertex 90.7703 77.662 31.5199 + vertex 75.5839 76.6163 31.3991 + vertex 91.2913 68.5927 31.4747 + endloop + endfacet + facet normal -0.00822882 -0.00545869 0.999951 + outer loop + vertex 106.703 69.7121 31.6076 + vertex 90.7703 77.662 31.5199 + vertex 91.2913 68.5927 31.4747 + endloop + endfacet + facet normal -0.00772072 -0.012447 0.999893 + outer loop + vertex 106.703 69.7121 31.6076 + vertex 91.2913 68.5927 31.4747 + vertex 107.363 60.7264 31.5009 + endloop + endfacet + facet normal -0.00836846 -0.00573857 0.999949 + outer loop + vertex 106.091 78.7811 31.6545 + vertex 90.7703 77.662 31.5199 + vertex 106.703 69.7121 31.6076 + endloop + endfacet + facet normal -0.00872605 -0.00576269 0.999945 + outer loop + vertex 122.289 70.9044 31.7505 + vertex 106.091 78.7811 31.6545 + vertex 106.703 69.7121 31.6076 + endloop + endfacet + facet normal -0.00817679 -0.0129352 0.999883 + outer loop + vertex 122.289 70.9044 31.7505 + vertex 106.703 69.7121 31.6076 + vertex 123.035 61.9169 31.6403 + endloop + endfacet + facet normal -0.00881935 -0.00595459 0.999943 + outer loop + vertex 121.596 79.9753 31.7984 + vertex 106.091 78.7811 31.6545 + vertex 122.289 70.9044 31.7505 + endloop + endfacet + facet normal -0.00889614 -0.00596045 0.999943 + outer loop + vertex 138.037 72.1824 31.8982 + vertex 121.596 79.9753 31.7984 + vertex 122.289 70.9044 31.7505 + endloop + endfacet + facet normal -0.00829642 -0.0133425 0.999877 + outer loop + vertex 138.037 72.1824 31.8982 + vertex 122.289 70.9044 31.7505 + vertex 138.86 63.1921 31.7851 + endloop + endfacet + facet normal -0.00901391 -0.00620894 0.99994 + outer loop + vertex 137.263 81.2536 31.9476 + vertex 121.596 79.9753 31.7984 + vertex 138.037 72.1824 31.8982 + endloop + endfacet + facet normal -0.00869983 -0.00618215 0.999943 + outer loop + vertex 153.918 73.5698 32.045 + vertex 137.263 81.2536 31.9476 + vertex 138.037 72.1824 31.8982 + endloop + endfacet + facet normal -0.00804959 -0.0136183 0.999875 + outer loop + vertex 153.918 73.5698 32.045 + vertex 138.037 72.1824 31.8982 + vertex 154.807 64.5741 31.9296 + endloop + endfacet + facet normal -0.00881629 -0.00643462 0.99994 + outer loop + vertex 153.07 82.6406 32.0959 + vertex 137.263 81.2536 31.9476 + vertex 153.918 73.5698 32.045 + endloop + endfacet + facet normal -0.0081574 -0.0063731 0.999946 + outer loop + vertex 169.948 75.0959 32.1855 + vertex 153.07 82.6406 32.0959 + vertex 153.918 73.5698 32.045 + endloop + endfacet + facet normal -0.00741688 -0.0141448 0.999872 + outer loop + vertex 169.948 75.0959 32.1855 + vertex 153.918 73.5698 32.045 + vertex 170.894 66.1051 32.0653 + endloop + endfacet + facet normal -0.00825568 -0.00659298 0.999944 + outer loop + vertex 169.042 84.1674 32.2378 + vertex 153.07 82.6406 32.0959 + vertex 169.948 75.0959 32.1855 + endloop + endfacet + facet normal -0.00737572 -0.00650516 0.999952 + outer loop + vertex 186.186 76.7872 32.3162 + vertex 169.042 84.1674 32.2378 + vertex 169.948 75.0959 32.1855 + endloop + endfacet + facet normal -0.00654922 -0.0144342 0.999874 + outer loop + vertex 186.186 76.7872 32.3162 + vertex 169.948 75.0959 32.1855 + vertex 187.169 67.7945 32.1929 + endloop + endfacet + facet normal -0.0074338 -0.00664009 0.99995 + outer loop + vertex 185.238 85.8618 32.3695 + vertex 169.042 84.1674 32.2378 + vertex 186.186 76.7872 32.3162 + endloop + endfacet + facet normal -0.00636415 -0.00652833 0.999958 + outer loop + vertex 202.683 78.6671 32.4335 + vertex 185.238 85.8618 32.3695 + vertex 186.186 76.7872 32.3162 + endloop + endfacet + facet normal -0.00546342 -0.0144283 0.999881 + outer loop + vertex 202.683 78.6671 32.4335 + vertex 186.186 76.7872 32.3162 + vertex 203.681 69.6638 32.3091 + endloop + endfacet + facet normal -0.00646791 -0.00677994 0.999956 + outer loop + vertex 201.707 87.7426 32.4887 + vertex 185.238 85.8618 32.3695 + vertex 202.683 78.6671 32.4335 + endloop + endfacet + facet normal -0.00549029 -0.00667478 0.999963 + outer loop + vertex 219.419 80.7321 32.5392 + vertex 201.707 87.7426 32.4887 + vertex 202.683 78.6671 32.4335 + endloop + endfacet + facet normal -0.0045015 -0.0146841 0.999882 + outer loop + vertex 219.419 80.7321 32.5392 + vertex 202.683 78.6671 32.4335 + vertex 220.421 71.724 32.4114 + endloop + endfacet + facet normal -0.00554131 -0.00680369 0.999962 + outer loop + vertex 218.434 89.8145 32.5955 + vertex 201.707 87.7426 32.4887 + vertex 219.419 80.7321 32.5392 + endloop + endfacet + facet normal -0.00474121 -0.00671697 0.999966 + outer loop + vertex 236.33 82.982 32.6345 + vertex 218.434 89.8145 32.5955 + vertex 219.419 80.7321 32.5392 + endloop + endfacet + facet normal -0.0036576 -0.0148583 0.999883 + outer loop + vertex 236.33 82.982 32.6345 + vertex 219.419 80.7321 32.5392 + vertex 237.322 73.9608 32.5041 + endloop + endfacet + facet normal -0.00484987 -0.0070016 0.999964 + outer loop + vertex 235.346 92.0714 32.6934 + vertex 218.434 89.8145 32.5955 + vertex 236.33 82.982 32.6345 + endloop + endfacet + facet normal -0.00417047 -0.00692804 0.999967 + outer loop + vertex 253.337 85.4071 32.7222 + vertex 235.346 92.0714 32.6934 + vertex 236.33 82.982 32.6345 + endloop + endfacet + facet normal -0.00297878 -0.0152817 0.999879 + outer loop + vertex 253.337 85.4071 32.7222 + vertex 236.33 82.982 32.6345 + vertex 254.316 76.3786 32.5871 + endloop + endfacet + facet normal -0.00418769 -0.00697451 0.999967 + outer loop + vertex 252.354 94.5082 32.7816 + vertex 235.346 92.0714 32.6934 + vertex 253.337 85.4071 32.7222 + endloop + endfacet + facet normal -0.00321678 -0.00686967 0.999971 + outer loop + vertex 270.332 87.982 32.7946 + vertex 252.354 94.5082 32.7816 + vertex 253.337 85.4071 32.7222 + endloop + endfacet + facet normal -0.00198968 -0.0149666 0.999886 + outer loop + vertex 270.332 87.982 32.7946 + vertex 253.337 85.4071 32.7222 + vertex 271.317 78.945 32.6613 + endloop + endfacet + facet normal -0.000940463 -0.0148522 0.999889 + outer loop + vertex 288.168 81.5926 32.7164 + vertex 270.332 87.982 32.7946 + vertex 271.317 78.945 32.6613 + endloop + endfacet + facet normal -0.000829392 -0.0145422 0.999894 + outer loop + vertex 287.148 90.6161 32.8468 + vertex 270.332 87.982 32.7946 + vertex 288.168 81.5926 32.7164 + endloop + endfacet + facet normal -0.000199444 -0.0144711 0.999895 + outer loop + vertex 304.657 84.2328 32.7579 + vertex 287.148 90.6161 32.8468 + vertex 288.168 81.5926 32.7164 + endloop + endfacet + facet normal 0.00182434 -0.0271059 0.999631 + outer loop + vertex 304.657 84.2328 32.7579 + vertex 288.168 81.5926 32.7164 + vertex 305.67 75.4471 32.5179 + endloop + endfacet + facet normal -0.000441991 -0.0273671 0.999625 + outer loop + vertex 321.768 78.091 32.5974 + vertex 304.657 84.2328 32.7579 + vertex 305.67 75.4471 32.5179 + endloop + endfacet + facet normal -0.000875699 -0.0285746 0.999591 + outer loop + vertex 320.721 86.8848 32.8478 + vertex 304.657 84.2328 32.7579 + vertex 321.768 78.091 32.5974 + endloop + endfacet + facet normal -0.00971463 -0.0296253 0.999514 + outer loop + vertex 337.589 80.9263 32.8352 + vertex 320.721 86.8848 32.8478 + vertex 321.768 78.091 32.5974 + endloop + endfacet + facet normal -0.00573967 -0.0517324 0.998644 + outer loop + vertex 337.589 80.9263 32.8352 + vertex 321.768 78.091 32.5974 + vertex 338.457 72.4657 32.4019 + endloop + endfacet + facet normal -0.0210421 -0.0532877 0.998357 + outer loop + vertex 354.294 75.6511 32.9057 + vertex 337.589 80.9263 32.8352 + vertex 338.457 72.4657 32.4019 + endloop + endfacet + facet normal -0.0229693 -0.0593958 0.99797 + outer loop + vertex 353.46 84.2715 33.3995 + vertex 337.589 80.9263 32.8352 + vertex 354.294 75.6511 32.9057 + endloop + endfacet + facet normal -0.0450412 -0.061481 0.997091 + outer loop + vertex 370.748 79.4775 33.8849 + vertex 353.46 84.2715 33.3995 + vertex 354.294 75.6511 32.9057 + endloop + endfacet + facet normal -0.0368064 -0.0962736 0.994674 + outer loop + vertex 370.748 79.4775 33.8849 + vertex 354.294 75.6511 32.9057 + vertex 370.61 71.2266 33.0812 + endloop + endfacet + facet normal -0.0643464 -0.0956812 0.99333 + outer loop + vertex 385.842 75.301 34.4603 + vertex 370.748 79.4775 33.8849 + vertex 370.61 71.2266 33.0812 + endloop + endfacet + facet normal -0.0632436 -0.0916336 0.993782 + outer loop + vertex 381.257 79.7162 34.5757 + vertex 370.748 79.4775 33.8849 + vertex 385.842 75.301 34.4603 + endloop + endfacet + facet normal -0.0873633 -0.116565 0.989333 + outer loop + vertex 381.257 79.7162 34.5757 + vertex 385.842 75.301 34.4603 + vertex 387.766 80.9538 35.2963 + endloop + endfacet + facet normal -0.0912632 -0.0970713 0.991084 + outer loop + vertex 387.766 80.9538 35.2963 + vertex 379.839 83.5956 34.8251 + vertex 381.257 79.7162 34.5757 + endloop + endfacet + facet normal -0.0930659 -0.10261 0.990359 + outer loop + vertex 387.795 85.5694 35.7772 + vertex 379.839 83.5956 34.8251 + vertex 387.766 80.9538 35.2963 + endloop + endfacet + facet normal -0.123671 -0.102074 0.987059 + outer loop + vertex 394.949 83.0054 36.4084 + vertex 387.795 85.5694 35.7772 + vertex 387.766 80.9538 35.2963 + endloop + endfacet + facet normal -0.114022 -0.134386 0.984347 + outer loop + vertex 394.949 83.0054 36.4084 + vertex 387.766 80.9538 35.2963 + vertex 395.302 78.5676 35.8435 + endloop + endfacet + facet normal -0.14242 -0.136145 0.980398 + outer loop + vertex 401.938 80.5163 37.0781 + vertex 394.949 83.0054 36.4084 + vertex 395.302 78.5676 35.8435 + endloop + endfacet + facet normal -0.126248 -0.187266 0.974163 + outer loop + vertex 401.938 80.5163 37.0781 + vertex 395.302 78.5676 35.8435 + vertex 402.926 76.636 36.4602 + endloop + endfacet + facet normal -0.16148 -0.195157 0.967387 + outer loop + vertex 408.774 78.1473 37.7412 + vertex 401.938 80.5163 37.0781 + vertex 402.926 76.636 36.4602 + endloop + endfacet + facet normal -0.172374 -0.229224 0.957989 + outer loop + vertex 407.51 81.8292 38.3947 + vertex 401.938 80.5163 37.0781 + vertex 408.774 78.1473 37.7412 + endloop + endfacet + facet normal -0.206769 -0.239377 0.948654 + outer loop + vertex 414.052 79.278 39.1769 + vertex 407.51 81.8292 38.3947 + vertex 408.774 78.1473 37.7412 + endloop + endfacet + facet normal -0.220615 -0.279207 0.934544 + outer loop + vertex 412.555 82.8201 39.8817 + vertex 407.51 81.8292 38.3947 + vertex 414.052 79.278 39.1769 + endloop + endfacet + facet normal -0.252754 -0.290473 0.922898 + outer loop + vertex 418.96 80.2476 40.8263 + vertex 412.555 82.8201 39.8817 + vertex 414.052 79.278 39.1769 + endloop + endfacet + facet normal -0.265737 -0.328933 0.906194 + outer loop + vertex 417.3 83.7555 41.6128 + vertex 412.555 82.8201 39.8817 + vertex 418.96 80.2476 40.8263 + endloop + endfacet + facet normal -0.299861 -0.341611 0.890722 + outer loop + vertex 423.559 81.2174 42.7465 + vertex 417.3 83.7555 41.6128 + vertex 418.96 80.2476 40.8263 + endloop + endfacet + facet normal -0.122388 -0.170918 0.977654 + outer loop + vertex 402.926 76.636 36.4602 + vertex 395.302 78.5676 35.8435 + vertex 396.896 74.8798 35.3982 + endloop + endfacet + facet normal -0.0894418 -0.157385 0.983479 + outer loop + vertex 396.896 74.8798 35.3982 + vertex 395.302 78.5676 35.8435 + vertex 385.842 75.301 34.4603 + endloop + endfacet + facet normal -0.0901229 -0.18695 0.978227 + outer loop + vertex 396.896 74.8798 35.3982 + vertex 385.842 75.301 34.4603 + vertex 395.835 71.1822 34.5938 + endloop + endfacet + facet normal -0.101641 -0.183539 0.977743 + outer loop + vertex 403.513 72.9173 35.7178 + vertex 396.896 74.8798 35.3982 + vertex 395.835 71.1822 34.5938 + endloop + endfacet + facet normal -0.109534 -0.211206 0.971285 + outer loop + vertex 402.926 76.636 36.4602 + vertex 396.896 74.8798 35.3982 + vertex 403.513 72.9173 35.7178 + endloop + endfacet + facet normal -0.135081 -0.214455 0.967348 + outer loop + vertex 409.895 74.5978 36.9815 + vertex 402.926 76.636 36.4602 + vertex 403.513 72.9173 35.7178 + endloop + endfacet + facet normal -0.144903 -0.250643 0.957174 + outer loop + vertex 408.774 78.1473 37.7412 + vertex 402.926 76.636 36.4602 + vertex 409.895 74.5978 36.9815 + endloop + endfacet + facet normal -0.174467 -0.258475 0.950133 + outer loop + vertex 415.544 75.9232 38.3792 + vertex 408.774 78.1473 37.7412 + vertex 409.895 74.5978 36.9815 + endloop + endfacet + facet normal -0.188391 -0.305679 0.933311 + outer loop + vertex 414.052 79.278 39.1769 + vertex 408.774 78.1473 37.7412 + vertex 415.544 75.9232 38.3792 + endloop + endfacet + facet normal -0.217693 -0.316337 0.923331 + outer loop + vertex 420.68 76.9855 39.9542 + vertex 414.052 79.278 39.1769 + vertex 415.544 75.9232 38.3792 + endloop + endfacet + facet normal -0.0764163 -0.15347 0.985194 + outer loop + vertex 385.842 75.301 34.4603 + vertex 387.05 67.6443 33.3613 + vertex 395.835 71.1822 34.5938 + endloop + endfacet + facet normal -0.0494129 -0.149542 0.98752 + outer loop + vertex 385.842 75.301 34.4603 + vertex 370.61 71.2266 33.0812 + vertex 387.05 67.6443 33.3613 + endloop + endfacet + facet normal -0.0450314 -0.129194 0.990596 + outer loop + vertex 387.05 67.6443 33.3613 + vertex 370.61 71.2266 33.0812 + vertex 370.858 63.8687 32.1329 + endloop + endfacet + facet normal -0.151718 -0.163769 0.974762 + outer loop + vertex 400.996 84.5661 37.6118 + vertex 394.949 83.0054 36.4084 + vertex 401.938 80.5163 37.0781 + endloop + endfacet + facet normal -0.188186 -0.171244 0.967089 + outer loop + vertex 407.51 81.8292 38.3947 + vertex 400.996 84.5661 37.6118 + vertex 401.938 80.5163 37.0781 + endloop + endfacet + facet normal -0.200837 -0.203907 0.958168 + outer loop + vertex 406.253 85.6569 38.9459 + vertex 400.996 84.5661 37.6118 + vertex 407.51 81.8292 38.3947 + endloop + endfacet + facet normal -0.23719 -0.214309 0.94753 + outer loop + vertex 412.555 82.8201 39.8817 + vertex 406.253 85.6569 38.9459 + vertex 407.51 81.8292 38.3947 + endloop + endfacet + facet normal -0.250511 -0.247747 0.935877 + outer loop + vertex 411.12 86.5706 40.4904 + vertex 406.253 85.6569 38.9459 + vertex 412.555 82.8201 39.8817 + endloop + endfacet + facet normal -0.285542 -0.259014 0.922701 + outer loop + vertex 417.3 83.7555 41.6128 + vertex 411.12 86.5706 40.4904 + vertex 412.555 82.8201 39.8817 + endloop + endfacet + facet normal -0.297501 -0.290559 0.909433 + outer loop + vertex 415.733 87.4921 42.294 + vertex 411.12 86.5706 40.4904 + vertex 417.3 83.7555 41.6128 + endloop + endfacet + facet normal -0.212874 -0.154069 0.964856 + outer loop + vertex 406.253 85.6569 38.9459 + vertex 399.955 88.659 38.0357 + vertex 400.996 84.5661 37.6118 + endloop + endfacet + facet normal -0.172636 -0.144814 0.974282 + outer loop + vertex 399.955 88.659 38.0357 + vertex 394.319 87.3555 36.8433 + vertex 400.996 84.5661 37.6118 + endloop + endfacet + facet normal -0.181552 -0.109041 0.977317 + outer loop + vertex 399.955 88.659 38.0357 + vertex 393.431 91.6433 37.1568 + vertex 394.319 87.3555 36.8433 + endloop + endfacet + facet normal -0.14015 -0.101033 0.984962 + outer loop + vertex 393.431 91.6433 37.1568 + vertex 387.194 90.0166 36.1025 + vertex 394.319 87.3555 36.8433 + endloop + endfacet + facet normal -0.136406 -0.0905815 0.986503 + outer loop + vertex 394.319 87.3555 36.8433 + vertex 387.194 90.0166 36.1025 + vertex 387.795 85.5694 35.7772 + endloop + endfacet + facet normal -0.104395 -0.0865658 0.990761 + outer loop + vertex 387.194 90.0166 36.1025 + vertex 380.833 88.0005 35.2561 + vertex 387.795 85.5694 35.7772 + endloop + endfacet + facet normal -0.108445 -0.0740294 0.991342 + outer loop + vertex 387.194 90.0166 36.1025 + vertex 378.687 92.4718 35.3552 + vertex 380.833 88.0005 35.2561 + endloop + endfacet + facet normal -0.0759063 -0.058499 0.995397 + outer loop + vertex 380.833 88.0005 35.2561 + vertex 378.687 92.4718 35.3552 + vertex 369.217 88.1796 34.3808 + endloop + endfacet + facet normal -0.0761244 -0.080065 0.993879 + outer loop + vertex 380.833 88.0005 35.2561 + vertex 369.217 88.1796 34.3808 + vertex 379.839 83.5956 34.8251 + endloop + endfacet + facet normal -0.0715209 -0.0692866 0.99503 + outer loop + vertex 369.217 88.1796 34.3808 + vertex 370.748 79.4775 33.8849 + vertex 379.839 83.5956 34.8251 + endloop + endfacet + facet normal -0.0806994 -0.0479667 0.995584 + outer loop + vertex 367.755 97.1319 34.6936 + vertex 369.217 88.1796 34.3808 + vertex 378.687 92.4718 35.3552 + endloop + endfacet + facet normal -0.0831558 -0.0538001 0.995083 + outer loop + vertex 379.273 96.8943 35.6433 + vertex 367.755 97.1319 34.6936 + vertex 378.687 92.4718 35.3552 + endloop + endfacet + facet normal -0.112893 -0.0496784 0.992364 + outer loop + vertex 386.35 94.4066 36.3238 + vertex 379.273 96.8943 35.6433 + vertex 378.687 92.4718 35.3552 + endloop + endfacet + facet normal -0.116433 -0.0600169 0.991384 + outer loop + vertex 385.409 98.8053 36.4796 + vertex 379.273 96.8943 35.6433 + vertex 386.35 94.4066 36.3238 + endloop + endfacet + facet normal -0.155038 -0.0680712 0.985561 + outer loop + vertex 392.426 95.9422 37.3857 + vertex 385.409 98.8053 36.4796 + vertex 386.35 94.4066 36.3238 + endloop + endfacet + facet normal -0.149995 -0.0875045 0.984807 + outer loop + vertex 392.426 95.9422 37.3857 + vertex 386.35 94.4066 36.3238 + vertex 393.431 91.6433 37.1568 + endloop + endfacet + facet normal -0.195138 -0.0975842 0.975909 + outer loop + vertex 398.867 92.8201 38.3614 + vertex 392.426 95.9422 37.3857 + vertex 393.431 91.6433 37.1568 + endloop + endfacet + facet normal -0.200201 -0.108719 0.973704 + outer loop + vertex 397.785 97.0885 38.6154 + vertex 392.426 95.9422 37.3857 + vertex 398.867 92.8201 38.3614 + endloop + endfacet + facet normal -0.249902 -0.120552 0.960737 + outer loop + vertex 403.816 93.7568 39.7662 + vertex 397.785 97.0885 38.6154 + vertex 398.867 92.8201 38.3614 + endloop + endfacet + facet normal -0.242459 -0.155253 0.957659 + outer loop + vertex 403.816 93.7568 39.7662 + vertex 398.867 92.8201 38.3614 + vertex 405.012 89.6309 39.4001 + endloop + endfacet + facet normal -0.28624 -0.166694 0.943546 + outer loop + vertex 409.765 90.5211 40.9993 + vertex 403.816 93.7568 39.7662 + vertex 405.012 89.6309 39.4001 + endloop + endfacet + facet normal -0.275017 -0.215015 0.937088 + outer loop + vertex 409.765 90.5211 40.9993 + vertex 405.012 89.6309 39.4001 + vertex 411.12 86.5706 40.4904 + endloop + endfacet + facet normal -0.264272 -0.190601 0.945427 + outer loop + vertex 411.12 86.5706 40.4904 + vertex 405.012 89.6309 39.4001 + vertex 406.253 85.6569 38.9459 + endloop + endfacet + facet normal -0.295368 -0.185928 0.937117 + outer loop + vertex 408.482 94.6504 41.4143 + vertex 403.816 93.7568 39.7662 + vertex 409.765 90.5211 40.9993 + endloop + endfacet + facet normal -0.304803 -0.144529 0.941385 + outer loop + vertex 408.482 94.6504 41.4143 + vertex 402.678 98.0274 40.0535 + vertex 403.816 93.7568 39.7662 + endloop + endfacet + facet normal -0.313106 -0.160979 0.935976 + outer loop + vertex 407.262 98.9202 41.7403 + vertex 402.678 98.0274 40.0535 + vertex 408.482 94.6504 41.4143 + endloop + endfacet + facet normal -0.320565 -0.127622 0.93859 + outer loop + vertex 407.262 98.9202 41.7403 + vertex 401.581 102.421 40.2761 + vertex 402.678 98.0274 40.0535 + endloop + endfacet + facet normal -0.327701 -0.141041 0.934194 + outer loop + vertex 406.084 103.301 41.9888 + vertex 401.581 102.421 40.2761 + vertex 407.262 98.9202 41.7403 + endloop + endfacet + facet normal -0.333406 -0.114904 0.935755 + outer loop + vertex 406.084 103.301 41.9888 + vertex 400.505 106.903 40.4431 + vertex 401.581 102.421 40.2761 + endloop + endfacet + facet normal -0.339005 -0.124998 0.932444 + outer loop + vertex 404.939 107.767 42.1711 + vertex 400.505 106.903 40.4431 + vertex 406.084 103.301 41.9888 + endloop + endfacet + facet normal -0.343642 -0.10315 0.933419 + outer loop + vertex 404.939 107.767 42.1711 + vertex 399.451 111.431 40.5554 + vertex 400.505 106.903 40.4431 + endloop + endfacet + facet normal -0.348082 -0.110922 0.930879 + outer loop + vertex 403.83 112.283 42.2944 + vertex 399.451 111.431 40.5554 + vertex 404.939 107.767 42.1711 + endloop + endfacet + facet normal -0.351204 -0.0958913 0.931376 + outer loop + vertex 403.83 112.283 42.2944 + vertex 398.416 115.948 40.6304 + vertex 399.451 111.431 40.5554 + endloop + endfacet + facet normal -0.354421 -0.101465 0.929565 + outer loop + vertex 402.755 116.796 42.3771 + vertex 398.416 115.948 40.6304 + vertex 403.83 112.283 42.2944 + endloop + endfacet + facet normal -0.357356 -0.0871326 0.929895 + outer loop + vertex 402.755 116.796 42.3771 + vertex 397.426 120.415 40.6684 + vertex 398.416 115.948 40.6304 + endloop + endfacet + facet normal -0.361023 -0.0934957 0.927858 + outer loop + vertex 401.724 121.256 42.4254 + vertex 397.426 120.415 40.6684 + vertex 402.755 116.796 42.3771 + endloop + endfacet + facet normal -0.362869 -0.0843903 0.928011 + outer loop + vertex 401.724 121.256 42.4254 + vertex 396.461 124.81 40.6906 + vertex 397.426 120.415 40.6684 + endloop + endfacet + facet normal -0.364076 -0.0865033 0.927343 + outer loop + vertex 400.734 125.65 42.4467 + vertex 396.461 124.81 40.6906 + vertex 401.724 121.256 42.4254 + endloop + endfacet + facet normal -0.365345 -0.0801975 0.927411 + outer loop + vertex 400.734 125.65 42.4467 + vertex 395.517 129.181 40.6969 + vertex 396.461 124.81 40.6906 + endloop + endfacet + facet normal -0.36732 -0.0836549 0.926325 + outer loop + vertex 399.763 130.019 42.4563 + vertex 395.517 129.181 40.6969 + vertex 400.734 125.65 42.4467 + endloop + endfacet + facet normal -0.367965 -0.0804475 0.926353 + outer loop + vertex 399.763 130.019 42.4563 + vertex 394.566 133.595 40.7025 + vertex 395.517 129.181 40.6969 + endloop + endfacet + facet normal -0.368155 -0.0807749 0.926249 + outer loop + vertex 398.797 134.428 42.4565 + vertex 394.566 133.595 40.7025 + vertex 399.763 130.019 42.4563 + endloop + endfacet + facet normal -0.3689 -0.0770365 0.926271 + outer loop + vertex 398.797 134.428 42.4565 + vertex 393.615 138.091 40.6976 + vertex 394.566 133.595 40.7025 + endloop + endfacet + facet normal -0.370846 -0.0802954 0.925217 + outer loop + vertex 397.819 138.917 42.4542 + vertex 393.615 138.091 40.6976 + vertex 398.797 134.428 42.4565 + endloop + endfacet + facet normal -0.371015 -0.0794479 0.925222 + outer loop + vertex 397.819 138.917 42.4542 + vertex 392.646 142.65 40.7006 + vertex 393.615 138.091 40.6976 + endloop + endfacet + facet normal -0.371698 -0.0805703 0.924851 + outer loop + vertex 396.83 143.473 42.4538 + vertex 392.646 142.65 40.7006 + vertex 397.819 138.917 42.4542 + endloop + endfacet + facet normal -0.372168 -0.0782129 0.924864 + outer loop + vertex 396.83 143.473 42.4538 + vertex 391.686 147.212 40.7 + vertex 392.646 142.65 40.7006 + endloop + endfacet + facet normal -0.373862 -0.0809763 0.923943 + outer loop + vertex 395.845 148.033 42.4548 + vertex 391.686 147.212 40.7 + vertex 396.83 143.473 42.4538 + endloop + endfacet + facet normal -0.374326 -0.0786547 0.923955 + outer loop + vertex 395.845 148.033 42.4548 + vertex 390.739 151.717 40.6996 + vertex 391.686 147.212 40.7 + endloop + endfacet + facet normal -0.375305 -0.0802667 0.92342 + outer loop + vertex 394.878 152.538 42.4533 + vertex 390.739 151.717 40.6996 + vertex 395.845 148.033 42.4548 + endloop + endfacet + facet normal -0.375568 -0.0789534 0.923426 + outer loop + vertex 394.878 152.538 42.4533 + vertex 389.802 156.135 40.6964 + vertex 390.739 151.717 40.6996 + endloop + endfacet + facet normal -0.376515 -0.0805458 0.922902 + outer loop + vertex 393.926 156.958 42.4505 + vertex 389.802 156.135 40.6964 + vertex 394.878 152.538 42.4533 + endloop + endfacet + facet normal -0.376196 -0.0821279 0.922893 + outer loop + vertex 393.926 156.958 42.4505 + vertex 388.855 160.476 40.6966 + vertex 389.802 156.135 40.6964 + endloop + endfacet + facet normal -0.377039 -0.0835808 0.922418 + outer loop + vertex 392.968 161.3 42.4525 + vertex 388.855 160.476 40.6966 + vertex 393.926 156.958 42.4505 + endloop + endfacet + facet normal -0.377179 -0.0828938 0.922423 + outer loop + vertex 392.968 161.3 42.4525 + vertex 387.897 164.79 40.6927 + vertex 388.855 160.476 40.6966 + endloop + endfacet + facet normal -0.377478 -0.0834138 0.922254 + outer loop + vertex 392.003 165.614 42.448 + vertex 387.897 164.79 40.6927 + vertex 392.968 161.3 42.4525 + endloop + endfacet + facet normal -0.377092 -0.0853085 0.922239 + outer loop + vertex 392.003 165.614 42.448 + vertex 386.924 169.138 40.6969 + vertex 387.897 164.79 40.6927 + endloop + endfacet + facet normal -0.378434 -0.087625 0.921471 + outer loop + vertex 391.009 169.96 42.4528 + vertex 386.924 169.138 40.6969 + vertex 392.003 165.614 42.448 + endloop + endfacet + facet normal -0.379339 -0.0832047 0.921509 + outer loop + vertex 391.009 169.96 42.4528 + vertex 385.967 173.562 40.7026 + vertex 386.924 169.138 40.6969 + endloop + endfacet + facet normal -0.380912 -0.0858381 0.920618 + outer loop + vertex 390.01 174.38 42.4517 + vertex 385.967 173.562 40.7026 + vertex 391.009 169.96 42.4528 + endloop + endfacet + facet normal -0.382665 -0.0772459 0.920652 + outer loop + vertex 390.01 174.38 42.4517 + vertex 385.057 178.055 40.7011 + vertex 385.967 173.562 40.7026 + endloop + endfacet + facet normal -0.3866 -0.0835984 0.918451 + outer loop + vertex 389.022 178.874 42.445 + vertex 385.057 178.055 40.7011 + vertex 390.01 174.38 42.4517 + endloop + endfacet + facet normal -0.389019 -0.0718274 0.918425 + outer loop + vertex 389.022 178.874 42.445 + vertex 384.198 182.579 40.6914 + vertex 385.057 178.055 40.7011 + endloop + endfacet + facet normal -0.391359 -0.0754834 0.917137 + outer loop + vertex 388.081 183.403 42.4159 + vertex 384.198 182.579 40.6914 + vertex 389.022 178.874 42.445 + endloop + endfacet + facet normal -0.393394 -0.0656499 0.917023 + outer loop + vertex 388.081 183.403 42.4159 + vertex 383.388 187.12 40.6688 + vertex 384.198 182.579 40.6914 + endloop + endfacet + facet normal -0.394025 -0.0666071 0.916683 + outer loop + vertex 387.264 187.967 42.3963 + vertex 383.388 187.12 40.6688 + vertex 388.081 183.403 42.4159 + endloop + endfacet + facet normal -0.398743 -0.043651 0.916023 + outer loop + vertex 387.264 187.967 42.3963 + vertex 382.747 191.766 40.6113 + vertex 383.388 187.12 40.6688 + endloop + endfacet + facet normal -0.392039 -0.0341371 0.919315 + outer loop + vertex 386.951 192.696 42.4386 + vertex 382.747 191.766 40.6113 + vertex 387.264 187.967 42.3963 + endloop + endfacet + facet normal -0.233534 -0.136404 0.962733 + outer loop + vertex 405.012 89.6309 39.4001 + vertex 398.867 92.8201 38.3614 + vertex 399.955 88.659 38.0357 + endloop + endfacet + facet normal -0.255951 -0.132604 0.957552 + outer loop + vertex 402.678 98.0274 40.0535 + vertex 397.785 97.0885 38.6154 + vertex 403.816 93.7568 39.7662 + endloop + endfacet + facet normal -0.261682 -0.105521 0.959369 + outer loop + vertex 402.678 98.0274 40.0535 + vertex 396.739 101.476 38.8127 + vertex 397.785 97.0885 38.6154 + endloop + endfacet + facet normal -0.210436 -0.0939221 0.973086 + outer loop + vertex 396.739 101.476 38.8127 + vertex 391.435 100.326 37.5547 + vertex 397.785 97.0885 38.6154 + endloop + endfacet + facet normal -0.214803 -0.0745547 0.973808 + outer loop + vertex 396.739 101.476 38.8127 + vertex 390.465 104.802 37.6834 + vertex 391.435 100.326 37.5547 + endloop + endfacet + facet normal -0.163523 -0.0637489 0.984478 + outer loop + vertex 390.465 104.802 37.6834 + vertex 384.484 103.27 36.5908 + vertex 391.435 100.326 37.5547 + endloop + endfacet + facet normal -0.161165 -0.0579363 0.985226 + outer loop + vertex 391.435 100.326 37.5547 + vertex 384.484 103.27 36.5908 + vertex 385.409 98.8053 36.4796 + endloop + endfacet + facet normal -0.117042 -0.048962 0.991919 + outer loop + vertex 384.484 103.27 36.5908 + vertex 376.991 101.389 35.6138 + vertex 385.409 98.8053 36.4796 + endloop + endfacet + facet normal -0.121127 -0.0327854 0.992095 + outer loop + vertex 384.484 103.27 36.5908 + vertex 377.523 105.864 35.8266 + vertex 376.991 101.389 35.6138 + endloop + endfacet + facet normal -0.0872361 -0.0369775 0.995501 + outer loop + vertex 377.523 105.864 35.8266 + vertex 366.178 106.129 34.8424 + vertex 376.991 101.389 35.6138 + endloop + endfacet + facet normal -0.0847875 -0.0313266 0.995906 + outer loop + vertex 366.178 106.129 34.8424 + vertex 367.755 97.1319 34.6936 + vertex 376.991 101.389 35.6138 + endloop + endfacet + facet normal -0.0574511 -0.0265719 0.997995 + outer loop + vertex 366.178 106.129 34.8424 + vertex 350.828 102.197 33.854 + vertex 367.755 97.1319 34.6936 + endloop + endfacet + facet normal -0.0573468 -0.026221 0.99801 + outer loop + vertex 367.755 97.1319 34.6936 + vertex 350.828 102.197 33.854 + vertex 352.205 93.1818 33.6963 + endloop + endfacet + facet normal -0.033384 -0.0225798 0.999188 + outer loop + vertex 350.828 102.197 33.854 + vertex 335.281 98.7824 33.2574 + vertex 352.205 93.1818 33.6963 + endloop + endfacet + facet normal -0.0327642 -0.0207021 0.999249 + outer loop + vertex 352.205 93.1818 33.6963 + vertex 335.281 98.7824 33.2574 + vertex 336.507 89.7765 33.111 + endloop + endfacet + facet normal -0.0291347 -0.0373704 0.998877 + outer loop + vertex 352.205 93.1818 33.6963 + vertex 336.507 89.7765 33.111 + vertex 353.46 84.2715 33.3995 + endloop + endfacet + facet normal -0.052077 -0.0405654 0.997819 + outer loop + vertex 369.217 88.1796 34.3808 + vertex 352.205 93.1818 33.6963 + vertex 353.46 84.2715 33.3995 + endloop + endfacet + facet normal -0.0141994 -0.0181825 0.999734 + outer loop + vertex 335.281 98.7824 33.2574 + vertex 319.592 95.8772 32.9817 + vertex 336.507 89.7765 33.111 + endloop + endfacet + facet normal -0.0136283 -0.0165984 0.999769 + outer loop + vertex 336.507 89.7765 33.111 + vertex 319.592 95.8772 32.9817 + vertex 320.721 86.8848 32.8478 + endloop + endfacet + facet normal -0.00334466 -0.0153088 0.999877 + outer loop + vertex 319.592 95.8772 32.9817 + vertex 303.591 93.2322 32.8877 + vertex 320.721 86.8848 32.8478 + endloop + endfacet + facet normal -0.00477377 -0.00666677 0.999966 + outer loop + vertex 319.592 95.8772 32.9817 + vertex 302.502 102.302 32.943 + vertex 303.591 93.2322 32.8877 + endloop + endfacet + facet normal -0.00138249 -0.00625949 0.999979 + outer loop + vertex 302.502 102.302 32.943 + vertex 286.115 99.704 32.9041 + vertex 303.591 93.2322 32.8877 + endloop + endfacet + facet normal -0.00145759 -0.00646229 0.999978 + outer loop + vertex 303.591 93.2322 32.8877 + vertex 286.115 99.704 32.9041 + vertex 287.148 90.6161 32.8468 + endloop + endfacet + facet normal -0.00190542 -0.00651318 0.999977 + outer loop + vertex 286.115 99.704 32.9041 + vertex 269.337 97.0812 32.855 + vertex 287.148 90.6161 32.8468 + endloop + endfacet + facet normal -0.00253813 -0.00246608 0.999994 + outer loop + vertex 286.115 99.704 32.9041 + vertex 268.343 106.177 32.8749 + vertex 269.337 97.0812 32.855 + endloop + endfacet + facet normal -0.00391722 -0.00261675 0.999989 + outer loop + vertex 268.343 106.177 32.8749 + vertex 251.373 103.603 32.8017 + vertex 269.337 97.0812 32.855 + endloop + endfacet + facet normal -0.00392424 -0.00263608 0.999989 + outer loop + vertex 269.337 97.0812 32.855 + vertex 251.373 103.603 32.8017 + vertex 252.354 94.5082 32.7816 + endloop + endfacet + facet normal -0.00486745 -0.0027378 0.999984 + outer loop + vertex 251.373 103.603 32.8017 + vertex 234.367 101.16 32.7122 + vertex 252.354 94.5082 32.7816 + endloop + endfacet + facet normal -0.0051289 -0.0009178 0.999986 + outer loop + vertex 251.373 103.603 32.8017 + vertex 233.387 110.227 32.7155 + vertex 234.367 101.16 32.7122 + endloop + endfacet + facet normal -0.0057489 -0.0009848 0.999983 + outer loop + vertex 233.387 110.227 32.7155 + vertex 216.477 107.956 32.6161 + vertex 234.367 101.16 32.7122 + endloop + endfacet + facet normal -0.00571812 -0.000903778 0.999983 + outer loop + vertex 234.367 101.16 32.7122 + vertex 216.477 107.956 32.6161 + vertex 217.456 98.8955 32.6135 + endloop + endfacet + facet normal -0.00548183 -0.00266798 0.999981 + outer loop + vertex 234.367 101.16 32.7122 + vertex 217.456 98.8955 32.6135 + vertex 235.346 92.0714 32.6934 + endloop + endfacet + facet normal -0.00635692 -0.000972807 0.999979 + outer loop + vertex 216.477 107.956 32.6161 + vertex 199.772 105.876 32.5079 + vertex 217.456 98.8955 32.6135 + endloop + endfacet + facet normal -0.00634474 -0.000941954 0.999979 + outer loop + vertex 217.456 98.8955 32.6135 + vertex 199.772 105.876 32.5079 + vertex 200.744 96.8208 32.5055 + endloop + endfacet + facet normal -0.00613411 -0.00263856 0.999978 + outer loop + vertex 217.456 98.8955 32.6135 + vertex 200.744 96.8208 32.5055 + vertex 218.434 89.8145 32.5955 + endloop + endfacet + facet normal -0.00715885 -0.0010293 0.999974 + outer loop + vertex 199.772 105.876 32.5079 + vertex 183.354 103.988 32.3884 + vertex 200.744 96.8208 32.5055 + endloop + endfacet + facet normal -0.00715442 -0.00101855 0.999974 + outer loop + vertex 200.744 96.8208 32.5055 + vertex 183.354 103.988 32.3884 + vertex 184.302 94.9371 32.3859 + endloop + endfacet + facet normal -0.00697479 -0.00258621 0.999972 + outer loop + vertex 200.744 96.8208 32.5055 + vertex 184.302 94.9371 32.3859 + vertex 201.707 87.7426 32.4887 + endloop + endfacet + facet normal -0.00807547 -0.001115 0.999967 + outer loop + vertex 183.354 103.988 32.3884 + vertex 167.247 102.291 32.2564 + vertex 184.302 94.9371 32.3859 + endloop + endfacet + facet normal -0.00802999 -0.00100951 0.999967 + outer loop + vertex 184.302 94.9371 32.3859 + vertex 167.247 102.291 32.2564 + vertex 168.144 93.2378 32.2545 + endloop + endfacet + facet normal -0.00785988 -0.0026269 0.999966 + outer loop + vertex 184.302 94.9371 32.3859 + vertex 168.144 93.2378 32.2545 + vertex 185.238 85.8618 32.3695 + endloop + endfacet + facet normal -0.00888645 -0.00109435 0.99996 + outer loop + vertex 167.247 102.291 32.2564 + vertex 151.402 100.767 32.1139 + vertex 168.144 93.2378 32.2545 + endloop + endfacet + facet normal -0.0088495 -0.00101219 0.99996 + outer loop + vertex 168.144 93.2378 32.2545 + vertex 151.402 100.767 32.1139 + vertex 152.236 91.7115 32.1121 + endloop + endfacet + facet normal -0.00868775 -0.00269795 0.999959 + outer loop + vertex 168.144 93.2378 32.2545 + vertex 152.236 91.7115 32.1121 + vertex 169.042 84.1674 32.2378 + endloop + endfacet + facet normal -0.00940922 -0.00106371 0.999955 + outer loop + vertex 151.402 100.767 32.1139 + vertex 135.746 99.3832 31.9651 + vertex 152.236 91.7115 32.1121 + endloop + endfacet + facet normal -0.00938194 -0.00100506 0.999955 + outer loop + vertex 152.236 91.7115 32.1121 + vertex 135.746 99.3832 31.9651 + vertex 136.504 90.3268 31.9632 + endloop + endfacet + facet normal -0.00923769 -0.00264363 0.999954 + outer loop + vertex 152.236 91.7115 32.1121 + vertex 136.504 90.3268 31.9632 + vertex 153.07 82.6406 32.0959 + endloop + endfacet + facet normal -0.00957942 -0.0010216 0.999954 + outer loop + vertex 135.746 99.3832 31.9651 + vertex 120.25 98.1105 31.8154 + vertex 136.504 90.3268 31.9632 + endloop + endfacet + facet normal -0.00952275 -0.00090327 0.999954 + outer loop + vertex 136.504 90.3268 31.9632 + vertex 120.25 98.1105 31.8154 + vertex 120.92 89.0499 31.8136 + endloop + endfacet + facet normal -0.00939175 -0.00250203 0.999953 + outer loop + vertex 136.504 90.3268 31.9632 + vertex 120.92 89.0499 31.8136 + vertex 137.263 81.2536 31.9476 + endloop + endfacet + facet normal -0.00937833 -0.000892594 0.999956 + outer loop + vertex 120.25 98.1105 31.8154 + vertex 104.927 96.9232 31.6706 + vertex 120.92 89.0499 31.8136 + endloop + endfacet + facet normal -0.00934029 -0.000815314 0.999956 + outer loop + vertex 120.92 89.0499 31.8136 + vertex 104.927 96.9232 31.6706 + vertex 105.508 87.8595 31.6687 + endloop + endfacet + facet normal -0.00922101 -0.00235939 0.999955 + outer loop + vertex 120.92 89.0499 31.8136 + vertex 105.508 87.8595 31.6687 + vertex 121.596 79.9753 31.7984 + endloop + endfacet + facet normal -0.00883898 -0.000783178 0.999961 + outer loop + vertex 104.927 96.9232 31.6706 + vertex 89.7821 95.8082 31.5359 + vertex 105.508 87.8595 31.6687 + endloop + endfacet + facet normal -0.00879252 -0.000691253 0.999961 + outer loop + vertex 105.508 87.8595 31.6687 + vertex 89.7821 95.8082 31.5359 + vertex 90.2718 86.7405 31.5339 + endloop + endfacet + facet normal -0.00868815 -0.0021123 0.99996 + outer loop + vertex 105.508 87.8595 31.6687 + vertex 90.2718 86.7405 31.5339 + vertex 106.091 78.7811 31.6545 + endloop + endfacet + facet normal -0.00803784 -0.0006505 0.999967 + outer loop + vertex 89.7821 95.8082 31.5359 + vertex 74.7669 94.7648 31.4145 + vertex 90.2718 86.7405 31.5339 + endloop + endfacet + facet normal -0.00798518 -0.000548732 0.999968 + outer loop + vertex 90.2718 86.7405 31.5339 + vertex 74.7669 94.7648 31.4145 + vertex 75.1737 85.6962 31.4128 + endloop + endfacet + facet normal -0.00788645 -0.00197596 0.999967 + outer loop + vertex 90.2718 86.7405 31.5339 + vertex 75.1737 85.6962 31.4128 + vertex 90.7703 77.662 31.5199 + endloop + endfacet + facet normal -0.00697412 -0.000503381 0.999976 + outer loop + vertex 74.7669 94.7648 31.4145 + vertex 59.8074 93.8135 31.3097 + vertex 75.1737 85.6962 31.4128 + endloop + endfacet + facet normal -0.00693998 -0.000438755 0.999976 + outer loop + vertex 75.1737 85.6962 31.4128 + vertex 59.8074 93.8135 31.3097 + vertex 60.1289 84.7427 31.3079 + endloop + endfacet + facet normal -0.00685249 -0.00181923 0.999975 + outer loop + vertex 75.1737 85.6962 31.4128 + vertex 60.1289 84.7427 31.3079 + vertex 75.5839 76.6163 31.3991 + endloop + endfacet + facet normal -0.00572046 -0.000395539 0.999984 + outer loop + vertex 59.8074 93.8135 31.3097 + vertex 44.839 92.9914 31.2237 + vertex 60.1289 84.7427 31.3079 + endloop + endfacet + facet normal -0.00568927 -0.00033771 0.999984 + outer loop + vertex 60.1289 84.7427 31.3079 + vertex 44.839 92.9914 31.2237 + vertex 45.0772 83.9185 31.222 + endloop + endfacet + facet normal -0.00561744 -0.00164946 0.999983 + outer loop + vertex 60.1289 84.7427 31.3079 + vertex 45.0772 83.9185 31.222 + vertex 60.4536 75.6615 31.2948 + endloop + endfacet + facet normal -0.00428061 -0.000300732 0.999991 + outer loop + vertex 44.839 92.9914 31.2237 + vertex 29.8522 92.3494 31.1594 + vertex 45.0772 83.9185 31.222 + endloop + endfacet + facet normal -0.00426653 -0.00027531 0.999991 + outer loop + vertex 45.0772 83.9185 31.222 + vertex 29.8522 92.3494 31.1594 + vertex 30.0095 83.2754 31.1576 + endloop + endfacet + facet normal -0.00421194 -0.00155406 0.99999 + outer loop + vertex 45.0772 83.9185 31.222 + vertex 30.0095 83.2754 31.1576 + vertex 45.3205 74.8398 31.209 + endloop + endfacet + facet normal -0.00265811 -0.000247436 0.999996 + outer loop + vertex 29.8522 92.3494 31.1594 + vertex 14.8742 91.9389 31.1195 + vertex 30.0095 83.2754 31.1576 + endloop + endfacet + facet normal -0.00264783 -0.000229464 0.999996 + outer loop + vertex 30.0095 83.2754 31.1576 + vertex 14.8742 91.9389 31.1195 + vertex 14.9511 82.863 31.1176 + endloop + endfacet + facet normal -0.00261415 -0.00145919 0.999996 + outer loop + vertex 30.0095 83.2754 31.1576 + vertex 14.9511 82.863 31.1176 + vertex 30.1706 74.1964 31.1447 + endloop + endfacet + facet normal -0.000900777 -0.000214644 1 + outer loop + vertex 14.8742 91.9389 31.1195 + vertex -0.0708954 91.7972 31.106 + vertex 14.9511 82.863 31.1176 + endloop + endfacet + facet normal -0.000895291 -0.000205419 1 + outer loop + vertex 14.9511 82.863 31.1176 + vertex -0.0708954 91.7972 31.106 + vertex -0.0721058 82.7216 31.1041 + endloop + endfacet + facet normal -0.000884009 -0.00140389 0.999999 + outer loop + vertex 14.9511 82.863 31.1176 + vertex -0.0721058 82.7216 31.1041 + vertex 15.0321 73.7868 31.1049 + endloop + endfacet + facet normal 0.000916974 -0.00020566 1 + outer loop + vertex -0.0708954 91.7972 31.106 + vertex -14.9885 91.9384 31.1197 + vertex -0.0721058 82.7216 31.1041 + endloop + endfacet + facet normal 0.00091345 -0.000211364 1 + outer loop + vertex -0.0721058 82.7216 31.1041 + vertex -14.9885 91.9384 31.1197 + vertex -15.067 82.8641 31.1179 + endloop + endfacet + facet normal 0.000902218 -0.00139321 0.999999 + outer loop + vertex -0.0721058 82.7216 31.1041 + vertex -15.067 82.8641 31.1179 + vertex -0.0713403 73.6468 31.0915 + endloop + endfacet + facet normal 0.00267689 -0.00022661 0.999996 + outer loop + vertex -14.9885 91.9384 31.1197 + vertex -29.9033 92.3476 31.1597 + vertex -15.067 82.8641 31.1179 + endloop + endfacet + facet normal 0.00267158 -0.000234925 0.999996 + outer loop + vertex -15.067 82.8641 31.1179 + vertex -29.9033 92.3476 31.1597 + vertex -30.0593 83.2747 31.158 + endloop + endfacet + facet normal 0.00263919 -0.00141754 0.999996 + outer loop + vertex -15.067 82.8641 31.1179 + vertex -30.0593 83.2747 31.158 + vertex -15.1481 73.7841 31.1052 + endloop + endfacet + facet normal 0.00430617 -0.000263029 0.999991 + outer loop + vertex -29.9033 92.3476 31.1597 + vertex -44.8356 92.9891 31.2242 + vertex -30.0593 83.2747 31.158 + endloop + endfacet + facet normal 0.00429767 -0.00027596 0.999991 + outer loop + vertex -30.0593 83.2747 31.158 + vertex -44.8356 92.9891 31.2242 + vertex -45.0696 83.9192 31.2227 + endloop + endfacet + facet normal 0.00424626 -0.00147301 0.99999 + outer loop + vertex -30.0593 83.2747 31.158 + vertex -45.0696 83.9192 31.2227 + vertex -30.2204 74.1943 31.1453 + endloop + endfacet + facet normal 0.00574859 -0.000313392 0.999983 + outer loop + vertex -44.8356 92.9891 31.2242 + vertex -59.7875 93.8127 31.3104 + vertex -45.0696 83.9192 31.2227 + endloop + endfacet + facet normal 0.00570334 -0.000380716 0.999984 + outer loop + vertex -45.0696 83.9192 31.2227 + vertex -59.7875 93.8127 31.3104 + vertex -60.1034 84.7421 31.3087 + endloop + endfacet + facet normal 0.0056367 -0.00159816 0.999983 + outer loop + vertex -45.0696 83.9192 31.2227 + vertex -60.1034 84.7421 31.3087 + vertex -45.3118 74.8384 31.2095 + endloop + endfacet + facet normal 0.00699521 -0.000425704 0.999975 + outer loop + vertex -59.7875 93.8127 31.3104 + vertex -74.7459 94.7661 31.4154 + vertex -60.1034 84.7421 31.3087 + endloop + endfacet + facet normal 0.0069459 -0.000497739 0.999976 + outer loop + vertex -60.1034 84.7421 31.3087 + vertex -74.7459 94.7661 31.4154 + vertex -75.1456 85.6977 31.4137 + endloop + endfacet + facet normal 0.00686863 -0.00171402 0.999975 + outer loop + vertex -60.1034 84.7421 31.3087 + vertex -75.1456 85.6977 31.4137 + vertex -60.4266 75.6643 31.2954 + endloop + endfacet + facet normal 0.00802653 -0.000545365 0.999968 + outer loop + vertex -74.7459 94.7661 31.4154 + vertex -89.7116 95.8052 31.5361 + vertex -75.1456 85.6977 31.4137 + endloop + endfacet + facet normal 0.00797838 -0.000614753 0.999968 + outer loop + vertex -75.1456 85.6977 31.4137 + vertex -89.7116 95.8052 31.5361 + vertex -90.1976 86.7395 31.5344 + endloop + endfacet + facet normal 0.00789213 -0.00186075 0.999967 + outer loop + vertex -75.1456 85.6977 31.4137 + vertex -90.1976 86.7395 31.5344 + vertex -75.5535 76.6183 31.4 + endloop + endfacet + facet normal 0.0088379 -0.000660831 0.999961 + outer loop + vertex -89.7116 95.8052 31.5361 + vertex -104.724 96.9097 31.6695 + vertex -90.1976 86.7395 31.5344 + endloop + endfacet + facet normal 0.0087786 -0.000745542 0.999961 + outer loop + vertex -90.1976 86.7395 31.5344 + vertex -104.724 96.9097 31.6695 + vertex -105.299 87.8461 31.6678 + endloop + endfacet + facet normal 0.00868431 -0.00203224 0.99996 + outer loop + vertex -90.1976 86.7395 31.5344 + vertex -105.299 87.8461 31.6678 + vertex -90.6917 77.6606 31.5203 + endloop + endfacet + facet normal 0.00936851 -0.000782942 0.999956 + outer loop + vertex -104.724 96.9097 31.6695 + vertex -119.868 98.0819 31.8124 + vertex -105.299 87.8461 31.6678 + endloop + endfacet + facet normal 0.00930976 -0.000866572 0.999956 + outer loop + vertex -105.299 87.8461 31.6678 + vertex -119.868 98.0819 31.8124 + vertex -120.533 89.0223 31.8107 + endloop + endfacet + facet normal 0.00920886 -0.00217335 0.999955 + outer loop + vertex -105.299 87.8461 31.6678 + vertex -120.533 89.0223 31.8107 + vertex -105.88 78.7683 31.6535 + endloop + endfacet + facet normal 0.00956155 -0.000885061 0.999954 + outer loop + vertex -119.868 98.0819 31.8124 + vertex -135.246 99.3452 31.9605 + vertex -120.533 89.0223 31.8107 + endloop + endfacet + facet normal 0.00949461 -0.000980484 0.999954 + outer loop + vertex -120.533 89.0223 31.8107 + vertex -135.246 99.3452 31.9605 + vertex -135.999 90.2891 31.9588 + endloop + endfacet + facet normal 0.00938589 -0.00230759 0.999953 + outer loop + vertex -120.533 89.0223 31.8107 + vertex -135.999 90.2891 31.9588 + vertex -121.199 79.9453 31.796 + endloop + endfacet + facet normal 0.00936965 -0.0009701 0.999956 + outer loop + vertex -135.246 99.3452 31.9605 + vertex -150.924 100.732 32.1088 + vertex -135.999 90.2891 31.9588 + endloop + endfacet + facet normal 0.00935183 -0.000995574 0.999956 + outer loop + vertex -135.999 90.2891 31.9588 + vertex -150.924 100.732 32.1088 + vertex -151.75 91.6752 32.1075 + endloop + endfacet + facet normal 0.00922369 -0.00245153 0.999954 + outer loop + vertex -135.999 90.2891 31.9588 + vertex -151.75 91.6752 32.1075 + vertex -136.749 81.2147 31.9435 + endloop + endfacet + facet normal 0.00884912 -0.000949733 0.99996 + outer loop + vertex -150.924 100.732 32.1088 + vertex -166.895 102.268 32.2516 + vertex -151.75 91.6752 32.1075 + endloop + endfacet + facet normal 0.00877844 -0.0010508 0.999961 + outer loop + vertex -151.75 91.6752 32.1075 + vertex -166.895 102.268 32.2516 + vertex -167.789 93.2138 32.2499 + endloop + endfacet + facet normal 0.00863316 -0.00256508 0.999959 + outer loop + vertex -151.75 91.6752 32.1075 + vertex -167.789 93.2138 32.2499 + vertex -152.578 82.6039 32.0914 + endloop + endfacet + facet normal 0.00807228 -0.000981115 0.999967 + outer loop + vertex -166.895 102.268 32.2516 + vertex -183.12 103.974 32.3842 + vertex -167.789 93.2138 32.2499 + endloop + endfacet + facet normal 0.00804981 -0.00101313 0.999967 + outer loop + vertex -167.789 93.2138 32.2499 + vertex -183.12 103.974 32.3842 + vertex -184.059 94.9183 32.3826 + endloop + endfacet + facet normal 0.00810231 -0.000695516 0.999967 + outer loop + vertex -166.895 102.268 32.2516 + vertex -182.169 113.001 32.3828 + vertex -183.12 103.974 32.3842 + endloop + endfacet + facet normal 0.00732548 -0.000613639 0.999973 + outer loop + vertex -182.169 113.001 32.3828 + vertex -198.583 114.892 32.5042 + vertex -183.12 103.974 32.3842 + endloop + endfacet + facet normal 0.00723943 -0.000735522 0.999974 + outer loop + vertex -183.12 103.974 32.3842 + vertex -198.583 114.892 32.5042 + vertex -199.563 105.864 32.5046 + endloop + endfacet + facet normal 0.00729396 -0.000887379 0.999973 + outer loop + vertex -182.169 113.001 32.3828 + vertex -197.595 123.887 32.505 + vertex -198.583 114.892 32.5042 + endloop + endfacet + facet normal 0.00666412 -0.000818223 0.999977 + outer loop + vertex -197.595 123.887 32.505 + vertex -214.221 125.966 32.6175 + vertex -198.583 114.892 32.5042 + endloop + endfacet + facet normal 0.00653788 -0.000996489 0.999978 + outer loop + vertex -198.583 114.892 32.5042 + vertex -214.221 125.966 32.6175 + vertex -215.217 116.969 32.615 + endloop + endfacet + facet normal 0.00661084 -0.00124427 0.999977 + outer loop + vertex -197.595 123.887 32.505 + vertex -213.22 134.94 32.622 + vertex -214.221 125.966 32.6175 + endloop + endfacet + facet normal 0.0059728 -0.00117313 0.999981 + outer loop + vertex -213.22 134.94 32.622 + vertex -230.03 137.195 32.7251 + vertex -214.221 125.966 32.6175 + endloop + endfacet + facet normal 0.00595263 -0.00120153 0.999982 + outer loop + vertex -214.221 125.966 32.6175 + vertex -230.03 137.195 32.7251 + vertex -231.029 128.215 32.7202 + endloop + endfacet + facet normal 0.00594287 -0.00139624 0.999981 + outer loop + vertex -213.22 134.94 32.622 + vertex -229.032 146.187 32.7317 + vertex -230.03 137.195 32.7251 + endloop + endfacet + facet normal 0.00479083 -0.00126835 0.999988 + outer loop + vertex -229.032 146.187 32.7317 + vertex -245.917 148.589 32.8156 + vertex -230.03 137.195 32.7251 + endloop + endfacet + facet normal 0.00503087 -0.000933682 0.999987 + outer loop + vertex -230.03 137.195 32.7251 + vertex -245.917 148.589 32.8156 + vertex -246.906 139.587 32.8122 + endloop + endfacet + facet normal 0.00472169 -0.00175418 0.999987 + outer loop + vertex -229.032 146.187 32.7317 + vertex -245.051 157.693 32.8275 + vertex -245.917 148.589 32.8156 + endloop + endfacet + facet normal 0.00330844 -0.00161982 0.999993 + outer loop + vertex -245.051 157.693 32.8275 + vertex -261.825 160.208 32.8871 + vertex -245.917 148.589 32.8156 + endloop + endfacet + facet normal 0.00327021 -0.00167216 0.999993 + outer loop + vertex -245.917 148.589 32.8156 + vertex -261.825 160.208 32.8871 + vertex -262.691 151.096 32.8747 + endloop + endfacet + facet normal 0.00277027 -0.00520832 0.999983 + outer loop + vertex -245.051 157.693 32.8275 + vertex -261.862 169.599 32.9361 + vertex -261.825 160.208 32.8871 + endloop + endfacet + facet normal 0.00312772 -0.0052069 0.999982 + outer loop + vertex -261.862 169.599 32.9361 + vertex -277.514 172.07 32.9979 + vertex -261.825 160.208 32.8871 + endloop + endfacet + facet normal 0.00122419 -0.0077246 0.999969 + outer loop + vertex -261.825 160.208 32.8871 + vertex -277.514 172.07 32.9979 + vertex -278.279 162.8 32.9272 + endloop + endfacet + facet normal 0.0038085 -0.00374247 0.999986 + outer loop + vertex -244.24 166.947 32.8591 + vertex -261.862 169.599 32.9361 + vertex -245.051 157.693 32.8275 + endloop + endfacet + facet normal 0.00437947 -0.00379253 0.999983 + outer loop + vertex -228.028 155.267 32.7438 + vertex -244.24 166.947 32.8591 + vertex -245.051 157.693 32.8275 + endloop + endfacet + facet normal 0.00441037 -0.00374964 0.999983 + outer loop + vertex -226.762 164.454 32.7726 + vertex -244.24 166.947 32.8591 + vertex -228.028 155.267 32.7438 + endloop + endfacet + facet normal 0.00552838 -0.00390367 0.999977 + outer loop + vertex -211.204 153.004 32.6419 + vertex -226.762 164.454 32.7726 + vertex -228.028 155.267 32.7438 + endloop + endfacet + facet normal 0.00577157 -0.0020957 0.999981 + outer loop + vertex -211.204 153.004 32.6419 + vertex -228.028 155.267 32.7438 + vertex -212.209 143.927 32.6287 + endloop + endfacet + facet normal 0.00668237 -0.00219656 0.999975 + outer loop + vertex -195.578 141.84 32.513 + vertex -211.204 153.004 32.6419 + vertex -212.209 143.927 32.6287 + endloop + endfacet + facet normal 0.00678972 -0.00134089 0.999976 + outer loop + vertex -195.578 141.84 32.513 + vertex -212.209 143.927 32.6287 + vertex -196.595 132.856 32.5078 + endloop + endfacet + facet normal 0.00741501 -0.00141162 0.999972 + outer loop + vertex -180.216 130.961 32.3837 + vertex -195.578 141.84 32.513 + vertex -196.595 132.856 32.5078 + endloop + endfacet + facet normal 0.00746746 -0.000958276 0.999972 + outer loop + vertex -180.216 130.961 32.3837 + vertex -196.595 132.856 32.5078 + vertex -181.202 121.993 32.3825 + endloop + endfacet + facet normal 0.00815796 -0.00103418 0.999966 + outer loop + vertex -165.068 120.287 32.2491 + vertex -180.216 130.961 32.3837 + vertex -181.202 121.993 32.3825 + endloop + endfacet + facet normal 0.00818897 -0.000740973 0.999966 + outer loop + vertex -165.068 120.287 32.2491 + vertex -181.202 121.993 32.3825 + vertex -165.989 111.294 32.25 + endloop + endfacet + facet normal 0.00889633 -0.000813479 0.99996 + outer loop + vertex -150.084 109.76 32.1072 + vertex -165.068 120.287 32.2491 + vertex -165.989 111.294 32.25 + endloop + endfacet + facet normal 0.00891149 -0.000656269 0.99996 + outer loop + vertex -150.084 109.76 32.1072 + vertex -165.989 111.294 32.25 + vertex -150.924 100.732 32.1088 + endloop + endfacet + facet normal 0.00894143 -0.000749283 0.99996 + outer loop + vertex -149.231 118.757 32.1063 + vertex -165.068 120.287 32.2491 + vertex -150.084 109.76 32.1072 + endloop + endfacet + facet normal 0.0094297 -0.000795595 0.999955 + outer loop + vertex -134.492 108.379 31.9591 + vertex -149.231 118.757 32.1063 + vertex -150.084 109.76 32.1072 + endloop + endfacet + facet normal 0.00944452 -0.000628326 0.999955 + outer loop + vertex -134.492 108.379 31.9591 + vertex -150.084 109.76 32.1072 + vertex -135.246 99.3452 31.9605 + endloop + endfacet + facet normal 0.00946425 -0.000746528 0.999955 + outer loop + vertex -133.717 117.378 31.9585 + vertex -149.231 118.757 32.1063 + vertex -134.492 108.379 31.9591 + endloop + endfacet + facet normal 0.00961072 -0.000759131 0.999954 + outer loop + vertex -119.201 107.119 31.8112 + vertex -133.717 117.378 31.9585 + vertex -134.492 108.379 31.9591 + endloop + endfacet + facet normal 0.0096257 -0.000577287 0.999954 + outer loop + vertex -119.201 107.119 31.8112 + vertex -134.492 108.379 31.9591 + vertex -119.868 98.0819 31.8124 + endloop + endfacet + facet normal 0.00966386 -0.000683945 0.999953 + outer loop + vertex -118.519 116.124 31.8107 + vertex -133.717 117.378 31.9585 + vertex -119.201 107.119 31.8112 + endloop + endfacet + facet normal 0.00942641 -0.000665954 0.999955 + outer loop + vertex -104.148 105.95 31.6685 + vertex -118.519 116.124 31.8107 + vertex -119.201 107.119 31.8112 + endloop + endfacet + facet normal 0.00944072 -0.000481696 0.999955 + outer loop + vertex -104.148 105.95 31.6685 + vertex -119.201 107.119 31.8112 + vertex -104.724 96.9097 31.6695 + endloop + endfacet + facet normal 0.00948562 -0.000582313 0.999955 + outer loop + vertex -103.562 114.962 31.6682 + vertex -118.519 116.124 31.8107 + vertex -104.148 105.95 31.6685 + endloop + endfacet + facet normal 0.00889217 -0.000543697 0.99996 + outer loop + vertex -89.2272 104.85 31.5352 + vertex -103.562 114.962 31.6682 + vertex -104.148 105.95 31.6685 + endloop + endfacet + facet normal 0.00890485 -0.000371704 0.99996 + outer loop + vertex -89.2272 104.85 31.5352 + vertex -104.148 105.95 31.6685 + vertex -89.7116 95.8052 31.5361 + endloop + endfacet + facet normal 0.00893701 -0.000480128 0.99996 + outer loop + vertex -88.7346 113.868 31.5351 + vertex -103.562 114.962 31.6682 + vertex -89.2272 104.85 31.5352 + endloop + endfacet + facet normal 0.00807403 -0.000432989 0.999967 + outer loop + vertex -74.3502 103.814 31.4146 + vertex -88.7346 113.868 31.5351 + vertex -89.2272 104.85 31.5352 + endloop + endfacet + facet normal 0.00808593 -0.000262095 0.999967 + outer loop + vertex -74.3502 103.814 31.4146 + vertex -89.2272 104.85 31.5352 + vertex -74.7459 94.7661 31.4154 + endloop + endfacet + facet normal 0.00812577 -0.000358963 0.999967 + outer loop + vertex -73.9495 112.838 31.4146 + vertex -88.7346 113.868 31.5351 + vertex -74.3502 103.814 31.4146 + endloop + endfacet + facet normal 0.00702322 -0.000309999 0.999975 + outer loop + vertex -59.4761 102.865 31.3099 + vertex -73.9495 112.838 31.4146 + vertex -74.3502 103.814 31.4146 + endloop + endfacet + facet normal 0.0070314 -0.00018185 0.999975 + outer loop + vertex -59.4761 102.865 31.3099 + vertex -74.3502 103.814 31.4146 + vertex -59.7875 93.8127 31.3104 + endloop + endfacet + facet normal 0.00706151 -0.000254424 0.999975 + outer loop + vertex -59.163 111.893 31.3099 + vertex -73.9495 112.838 31.4146 + vertex -59.4761 102.865 31.3099 + endloop + endfacet + facet normal 0.00577561 -0.000209825 0.999983 + outer loop + vertex -44.6053 102.044 31.2238 + vertex -59.163 111.893 31.3099 + vertex -59.4761 102.865 31.3099 + endloop + endfacet + facet normal 0.00578148 -0.000103616 0.999983 + outer loop + vertex -44.6053 102.044 31.2238 + vertex -59.4761 102.865 31.3099 + vertex -44.8356 92.9891 31.2242 + endloop + endfacet + facet normal 0.00579911 -0.000175092 0.999983 + outer loop + vertex -44.3748 111.075 31.224 + vertex -59.163 111.893 31.3099 + vertex -44.6053 102.044 31.2238 + endloop + endfacet + facet normal 0.00432478 -0.000137451 0.999991 + outer loop + vertex -29.7512 101.405 31.1595 + vertex -44.3748 111.075 31.224 + vertex -44.6053 102.044 31.2238 + endloop + endfacet + facet normal 0.00432877 -4.48644e-05 0.999991 + outer loop + vertex -29.7512 101.405 31.1595 + vertex -44.6053 102.044 31.2238 + vertex -29.9033 92.3476 31.1597 + endloop + endfacet + facet normal 0.00436981 -6.93533e-05 0.99999 + outer loop + vertex -29.6005 110.433 31.1594 + vertex -44.3748 111.075 31.224 + vertex -29.7512 101.405 31.1595 + endloop + endfacet + facet normal 0.00270818 -4.16159e-05 0.999996 + outer loop + vertex -14.914 100.994 31.1193 + vertex -29.6005 110.433 31.1594 + vertex -29.7512 101.405 31.1595 + endloop + endfacet + facet normal 0.00271004 2.54965e-05 0.999996 + outer loop + vertex -14.914 100.994 31.1193 + vertex -29.7512 101.405 31.1595 + vertex -14.9885 91.9384 31.1197 + endloop + endfacet + facet normal 0.00268376 -7.96073e-05 0.999996 + outer loop + vertex -14.8386 110.028 31.1198 + vertex -29.6005 110.433 31.1594 + vertex -14.914 100.994 31.1193 + endloop + endfacet + facet normal 0.000919727 -6.4892e-05 1 + outer loop + vertex -0.0732694 100.854 31.1056 + vertex -14.8386 110.028 31.1198 + vertex -14.914 100.994 31.1193 + endloop + endfacet + facet normal 0.000920746 4.25741e-05 1 + outer loop + vertex -0.0732694 100.854 31.1056 + vertex -14.914 100.994 31.1193 + vertex -0.0708954 91.7972 31.106 + endloop + endfacet + facet normal 0.000933416 -4.28602e-05 1 + outer loop + vertex -0.075426 109.885 31.106 + vertex -14.8386 110.028 31.1198 + vertex -0.0732694 100.854 31.1056 + endloop + endfacet + facet normal -0.000904598 -4.32991e-05 1 + outer loop + vertex 14.7934 100.994 31.1191 + vertex -0.075426 109.885 31.106 + vertex -0.0732694 100.854 31.1056 + endloop + endfacet + facet normal -0.000905373 3.84713e-05 1 + outer loop + vertex 14.7934 100.994 31.1191 + vertex -0.0732694 100.854 31.1056 + vertex 14.8742 91.9389 31.1195 + endloop + endfacet + facet normal -0.000920714 -7.02529e-05 1 + outer loop + vertex 14.7133 110.026 31.1196 + vertex -0.075426 109.885 31.106 + vertex 14.7934 100.994 31.1191 + endloop + endfacet + facet normal -0.0027016 -8.60431e-05 0.999996 + outer loop + vertex 29.6932 101.407 31.1593 + vertex 14.7133 110.026 31.1196 + vertex 14.7934 100.994 31.1191 + endloop + endfacet + facet normal -0.00270281 -4.21965e-05 0.999996 + outer loop + vertex 29.6932 101.407 31.1593 + vertex 14.7934 100.994 31.1191 + vertex 29.8522 92.3494 31.1594 + endloop + endfacet + facet normal -0.00269535 -7.51769e-05 0.999996 + outer loop + vertex 29.5327 110.434 31.1596 + vertex 14.7133 110.026 31.1196 + vertex 29.6932 101.407 31.1593 + endloop + endfacet + facet normal -0.00430901 -0.000103866 0.999991 + outer loop + vertex 44.5991 102.047 31.2236 + vertex 29.5327 110.434 31.1596 + vertex 29.6932 101.407 31.1593 + endloop + endfacet + facet normal -0.00430903 -0.000103442 0.999991 + outer loop + vertex 44.5991 102.047 31.2236 + vertex 29.6932 101.407 31.1593 + vertex 44.839 92.9914 31.2237 + endloop + endfacet + facet normal -0.00434212 -0.000163355 0.999991 + outer loop + vertex 44.3601 111.074 31.2241 + vertex 29.5327 110.434 31.1596 + vertex 44.5991 102.047 31.2236 + endloop + endfacet + facet normal -0.00576242 -0.00020096 0.999983 + outer loop + vertex 59.486 102.867 31.3096 + vertex 44.3601 111.074 31.2241 + vertex 44.5991 102.047 31.2236 + endloop + endfacet + facet normal -0.00576282 -0.000193652 0.999983 + outer loop + vertex 59.486 102.867 31.3096 + vertex 44.5991 102.047 31.2236 + vertex 59.8074 93.8135 31.3097 + endloop + endfacet + facet normal -0.00579156 -0.000254668 0.999983 + outer loop + vertex 59.1656 111.892 31.31 + vertex 44.3601 111.074 31.2241 + vertex 59.486 102.867 31.3096 + endloop + endfacet + facet normal -0.00702053 -0.000298303 0.999975 + outer loop + vertex 74.3601 103.815 31.4143 + vertex 59.1656 111.892 31.31 + vertex 59.486 102.867 31.3096 + endloop + endfacet + facet normal -0.00702084 -0.000293448 0.999975 + outer loop + vertex 74.3601 103.815 31.4143 + vertex 59.486 102.867 31.3096 + vertex 74.7669 94.7648 31.4145 + endloop + endfacet + facet normal -0.00706007 -0.000372705 0.999975 + outer loop + vertex 73.9552 112.837 31.4148 + vertex 59.1656 111.892 31.31 + vertex 74.3601 103.815 31.4143 + endloop + endfacet + facet normal -0.00809604 -0.000419204 0.999967 + outer loop + vertex 89.2865 104.854 31.5356 + vertex 73.9552 112.837 31.4148 + vertex 74.3601 103.815 31.4143 + endloop + endfacet + facet normal -0.00809656 -0.000411692 0.999967 + outer loop + vertex 89.2865 104.854 31.5356 + vertex 74.3601 103.815 31.4143 + vertex 89.7821 95.8082 31.5359 + endloop + endfacet + facet normal -0.00812665 -0.000477999 0.999967 + outer loop + vertex 88.7887 113.872 31.5359 + vertex 73.9552 112.837 31.4148 + vertex 89.2865 104.854 31.5356 + endloop + endfacet + facet normal -0.00890676 -0.000521062 0.99996 + outer loop + vertex 104.339 105.965 31.6702 + vertex 88.7887 113.872 31.5359 + vertex 89.2865 104.854 31.5356 + endloop + endfacet + facet normal -0.00890557 -0.000537179 0.99996 + outer loop + vertex 104.339 105.965 31.6702 + vertex 89.2865 104.854 31.5356 + vertex 104.927 96.9232 31.6706 + endloop + endfacet + facet normal -0.00895141 -0.000608872 0.99996 + outer loop + vertex 103.749 114.979 31.6704 + vertex 88.7887 113.872 31.5359 + vertex 104.339 105.965 31.6702 + endloop + endfacet + facet normal -0.00944982 -0.000641526 0.999955 + outer loop + vertex 119.573 107.148 31.815 + vertex 103.749 114.979 31.6704 + vertex 104.339 105.965 31.6702 + endloop + endfacet + facet normal -0.00944834 -0.000660664 0.999955 + outer loop + vertex 119.573 107.148 31.815 + vertex 104.339 105.965 31.6702 + vertex 120.25 98.1105 31.8154 + endloop + endfacet + facet normal -0.00949117 -0.000725086 0.999955 + outer loop + vertex 118.887 116.157 31.815 + vertex 103.749 114.979 31.6704 + vertex 119.573 107.148 31.815 + endloop + endfacet + facet normal -0.00964331 -0.000736668 0.999953 + outer loop + vertex 134.979 108.416 31.9645 + vertex 118.887 116.157 31.815 + vertex 119.573 107.148 31.815 + endloop + endfacet + facet normal -0.00964265 -0.000744656 0.999953 + outer loop + vertex 134.979 108.416 31.9645 + vertex 119.573 107.148 31.815 + vertex 135.746 99.3832 31.9651 + endloop + endfacet + facet normal -0.00968984 -0.000833415 0.999953 + outer loop + vertex 134.206 117.42 31.9645 + vertex 118.887 116.157 31.815 + vertex 134.979 108.416 31.9645 + endloop + endfacet + facet normal -0.0094753 -0.000814981 0.999955 + outer loop + vertex 150.556 109.796 32.1132 + vertex 134.206 117.42 31.9645 + vertex 134.979 108.416 31.9645 + endloop + endfacet + facet normal -0.00947601 -0.000806953 0.999955 + outer loop + vertex 150.556 109.796 32.1132 + vertex 134.979 108.416 31.9645 + vertex 151.402 100.767 32.1139 + endloop + endfacet + facet normal -0.00950575 -0.000880293 0.999954 + outer loop + vertex 149.706 118.796 32.113 + vertex 134.206 117.42 31.9645 + vertex 150.556 109.796 32.1132 + endloop + endfacet + facet normal -0.00893142 -0.00082603 0.99996 + outer loop + vertex 166.342 111.32 32.2555 + vertex 149.706 118.796 32.113 + vertex 150.556 109.796 32.1132 + endloop + endfacet + facet normal -0.00893491 -0.000789892 0.99996 + outer loop + vertex 166.342 111.32 32.2555 + vertex 150.556 109.796 32.1132 + vertex 167.247 102.291 32.2564 + endloop + endfacet + facet normal -0.00896204 -0.000894174 0.999959 + outer loop + vertex 165.421 120.315 32.2552 + vertex 149.706 118.796 32.113 + vertex 166.342 111.32 32.2555 + endloop + endfacet + facet normal -0.00811877 -0.000807844 0.999967 + outer loop + vertex 182.404 113.016 32.3872 + vertex 165.421 120.315 32.2552 + vertex 166.342 111.32 32.2555 + endloop + endfacet + facet normal -0.00812716 -0.000728429 0.999967 + outer loop + vertex 182.404 113.016 32.3872 + vertex 166.342 111.32 32.2555 + vertex 183.354 103.988 32.3884 + endloop + endfacet + facet normal -0.00813821 -0.000853072 0.999967 + outer loop + vertex 181.432 122.008 32.387 + vertex 165.421 120.315 32.2552 + vertex 182.404 113.016 32.3872 + endloop + endfacet + facet normal -0.00721239 -0.000752936 0.999974 + outer loop + vertex 198.792 114.903 32.5069 + vertex 181.432 122.008 32.387 + vertex 182.404 113.016 32.3872 + endloop + endfacet + facet normal -0.00722162 -0.00067276 0.999974 + outer loop + vertex 198.792 114.903 32.5069 + vertex 182.404 113.016 32.3872 + vertex 199.772 105.876 32.5079 + endloop + endfacet + facet normal -0.00719764 -0.000716886 0.999974 + outer loop + vertex 197.801 123.899 32.5062 + vertex 181.432 122.008 32.387 + vertex 198.792 114.903 32.5069 + endloop + endfacet + facet normal -0.00640942 -0.00063002 0.999979 + outer loop + vertex 215.489 116.988 32.6152 + vertex 197.801 123.899 32.5062 + vertex 198.792 114.903 32.5069 + endloop + endfacet + facet normal -0.00641278 -0.000603124 0.999979 + outer loop + vertex 215.489 116.988 32.6152 + vertex 198.792 114.903 32.5069 + vertex 216.477 107.956 32.6161 + endloop + endfacet + facet normal -0.00641417 -0.000642186 0.999979 + outer loop + vertex 214.486 125.984 32.6145 + vertex 197.801 123.899 32.5062 + vertex 215.489 116.988 32.6152 + endloop + endfacet + facet normal -0.00581604 -0.0005755 0.999983 + outer loop + vertex 232.402 119.264 32.7149 + vertex 214.486 125.984 32.6145 + vertex 215.489 116.988 32.6152 + endloop + endfacet + facet normal -0.00581801 -0.000560888 0.999983 + outer loop + vertex 232.402 119.264 32.7149 + vertex 215.489 116.988 32.6152 + vertex 233.387 110.227 32.7155 + endloop + endfacet + facet normal -0.00522972 -0.000496746 0.999986 + outer loop + vertex 250.393 112.675 32.8057 + vertex 232.402 119.264 32.7149 + vertex 233.387 110.227 32.7155 + endloop + endfacet + facet normal -0.00523821 -0.000519947 0.999986 + outer loop + vertex 249.411 121.719 32.8052 + vertex 232.402 119.264 32.7149 + vertex 250.393 112.675 32.8057 + endloop + endfacet + facet normal -0.00421688 -0.000409029 0.999991 + outer loop + vertex 267.352 115.252 32.8783 + vertex 249.411 121.719 32.8052 + vertex 250.393 112.675 32.8057 + endloop + endfacet + facet normal -0.00415414 -0.000821869 0.999991 + outer loop + vertex 267.352 115.252 32.8783 + vertex 250.393 112.675 32.8057 + vertex 268.343 106.177 32.8749 + endloop + endfacet + facet normal -0.00273358 -0.000666741 0.999996 + outer loop + vertex 285.089 108.792 32.9224 + vertex 267.352 115.252 32.8783 + vertex 268.343 106.177 32.8749 + endloop + endfacet + facet normal -0.00270917 -0.000599714 0.999996 + outer loop + vertex 284.068 117.864 32.9251 + vertex 267.352 115.252 32.8783 + vertex 285.089 108.792 32.9224 + endloop + endfacet + facet normal -0.00221639 -0.000544247 0.999997 + outer loop + vertex 301.416 111.376 32.96 + vertex 284.068 117.864 32.9251 + vertex 285.089 108.792 32.9224 + endloop + endfacet + facet normal -0.00196791 -0.00211472 0.999996 + outer loop + vertex 301.416 111.376 32.96 + vertex 285.089 108.792 32.9224 + vertex 302.502 102.302 32.943 + endloop + endfacet + facet normal -0.00567905 -0.00255872 0.999981 + outer loop + vertex 318.426 104.932 33.0401 + vertex 301.416 111.376 32.96 + vertex 302.502 102.302 32.943 + endloop + endfacet + facet normal -0.00569581 -0.00260296 0.99998 + outer loop + vertex 317.264 113.987 33.0571 + vertex 301.416 111.376 32.96 + vertex 318.426 104.932 33.0401 + endloop + endfacet + facet normal -0.0173023 -0.00409163 0.999842 + outer loop + vertex 334.01 107.823 33.3217 + vertex 317.264 113.987 33.0571 + vertex 318.426 104.932 33.0401 + endloop + endfacet + facet normal -0.0163172 -0.00940017 0.999823 + outer loop + vertex 334.01 107.823 33.3217 + vertex 318.426 104.932 33.0401 + vertex 335.281 98.7824 33.2574 + endloop + endfacet + facet normal -0.0174941 -0.00461323 0.999836 + outer loop + vertex 332.74 116.855 33.3411 + vertex 317.264 113.987 33.0571 + vertex 334.01 107.823 33.3217 + endloop + endfacet + facet normal -0.0372528 -0.0073913 0.999279 + outer loop + vertex 349.416 111.219 33.9211 + vertex 332.74 116.855 33.3411 + vertex 334.01 107.823 33.3217 + endloop + endfacet + facet normal -0.0360017 -0.0130649 0.999266 + outer loop + vertex 349.416 111.219 33.9211 + vertex 334.01 107.823 33.3217 + vertex 350.828 102.197 33.854 + endloop + endfacet + facet normal -0.0376836 -0.00866874 0.999252 + outer loop + vertex 348.012 120.225 33.9463 + vertex 332.74 116.855 33.3411 + vertex 349.416 111.219 33.9211 + endloop + endfacet + facet normal -0.0616127 -0.0123977 0.998023 + outer loop + vertex 364.607 115.139 34.9076 + vertex 348.012 120.225 33.9463 + vertex 349.416 111.219 33.9211 + endloop + endfacet + facet normal -0.0602369 -0.0177293 0.998027 + outer loop + vertex 364.607 115.139 34.9076 + vertex 349.416 111.219 33.9211 + vertex 366.178 106.129 34.8424 + endloop + endfacet + facet normal -0.0874991 -0.0224673 0.995911 + outer loop + vertex 364.607 115.139 34.9076 + vertex 366.178 106.129 34.8424 + vertex 375.28 110.421 35.7389 + endloop + endfacet + facet normal -0.0892589 -0.0264931 0.995656 + outer loop + vertex 375.834 114.915 35.9081 + vertex 364.607 115.139 34.9076 + vertex 375.28 110.421 35.7389 + endloop + endfacet + facet normal -0.12683 -0.0217133 0.991687 + outer loop + vertex 382.682 112.338 36.7275 + vertex 375.834 114.915 35.9081 + vertex 375.28 110.421 35.7389 + endloop + endfacet + facet normal -0.122962 -0.0366793 0.991733 + outer loop + vertex 382.682 112.338 36.7275 + vertex 375.28 110.421 35.7389 + vertex 383.582 107.798 36.6712 + endloop + endfacet + facet normal -0.17124 -0.0461522 0.984148 + outer loop + vertex 389.516 109.342 37.776 + vertex 382.682 112.338 36.7275 + vertex 383.582 107.798 36.6712 + endloop + endfacet + facet normal -0.168832 -0.0553618 0.984089 + outer loop + vertex 389.516 109.342 37.776 + vertex 383.582 107.798 36.6712 + vertex 390.465 104.802 37.6834 + endloop + endfacet + facet normal -0.220819 -0.0660036 0.973079 + outer loop + vertex 395.734 105.966 38.9581 + vertex 389.516 109.342 37.776 + vertex 390.465 104.802 37.6834 + endloop + endfacet + facet normal -0.223679 -0.0716402 0.972026 + outer loop + vertex 394.732 110.503 39.0621 + vertex 389.516 109.342 37.776 + vertex 395.734 105.966 38.9581 + endloop + endfacet + facet normal -0.226334 -0.0599107 0.972206 + outer loop + vertex 394.732 110.503 39.0621 + vertex 388.575 113.88 37.8366 + vertex 389.516 109.342 37.776 + endloop + endfacet + facet normal -0.228 -0.0631652 0.97161 + outer loop + vertex 393.75 115.034 39.1261 + vertex 388.575 113.88 37.8366 + vertex 394.732 110.503 39.0621 + endloop + endfacet + facet normal -0.229763 -0.0553291 0.971673 + outer loop + vertex 393.75 115.034 39.1261 + vertex 387.647 118.357 37.8722 + vertex 388.575 113.88 37.8366 + endloop + endfacet + facet normal -0.1765 -0.0443855 0.983299 + outer loop + vertex 387.647 118.357 37.8722 + vertex 381.814 116.843 36.7569 + vertex 388.575 113.88 37.8366 + endloop + endfacet + facet normal -0.17469 -0.0400717 0.983808 + outer loop + vertex 388.575 113.88 37.8366 + vertex 381.814 116.843 36.7569 + vertex 382.682 112.338 36.7275 + endloop + endfacet + facet normal -0.177905 -0.0389525 0.983276 + outer loop + vertex 387.647 118.357 37.8722 + vertex 380.94 121.267 36.774 + vertex 381.814 116.843 36.7569 + endloop + endfacet + facet normal -0.126331 -0.0287978 0.99157 + outer loop + vertex 380.94 121.267 36.774 + vertex 373.618 119.395 35.7867 + vertex 381.814 116.843 36.7569 + endloop + endfacet + facet normal -0.128769 -0.0368529 0.99099 + outer loop + vertex 381.814 116.843 36.7569 + vertex 373.618 119.395 35.7867 + vertex 375.834 114.915 35.9081 + endloop + endfacet + facet normal -0.129223 -0.017427 0.991462 + outer loop + vertex 380.94 121.267 36.774 + vertex 374.165 123.785 35.9352 + vertex 373.618 119.395 35.7867 + endloop + endfacet + facet normal -0.0908373 -0.0223473 0.995615 + outer loop + vertex 374.165 123.785 35.9352 + vertex 363.056 124.079 34.9282 + vertex 373.618 119.395 35.7867 + endloop + endfacet + facet normal -0.0888015 -0.0177063 0.995892 + outer loop + vertex 363.056 124.079 34.9282 + vertex 364.607 115.139 34.9076 + vertex 373.618 119.395 35.7867 + endloop + endfacet + facet normal -0.0906105 -0.013139 0.9958 + outer loop + vertex 374.165 123.785 35.9352 + vertex 371.982 128.243 35.7954 + vertex 363.056 124.079 34.9282 + endloop + endfacet + facet normal -0.0892935 -0.0159784 0.995877 + outer loop + vertex 361.494 133.031 34.9318 + vertex 363.056 124.079 34.9282 + vertex 371.982 128.243 35.7954 + endloop + endfacet + facet normal -0.0914353 -0.0207205 0.995595 + outer loop + vertex 372.51 132.673 35.9361 + vertex 361.494 133.031 34.9318 + vertex 371.982 128.243 35.7954 + endloop + endfacet + facet normal -0.130773 -0.015897 0.991285 + outer loop + vertex 379.229 130.066 36.7807 + vertex 372.51 132.673 35.9361 + vertex 371.982 128.243 35.7954 + endloop + endfacet + facet normal -0.128487 -0.0250445 0.991395 + outer loop + vertex 379.229 130.066 36.7807 + vertex 371.982 128.243 35.7954 + vertex 380.085 125.653 36.7801 + endloop + endfacet + facet normal -0.181029 -0.03523 0.982847 + outer loop + vertex 385.855 127.138 37.8961 + vertex 379.229 130.066 36.7807 + vertex 380.085 125.653 36.7801 + endloop + endfacet + facet normal -0.18005 -0.0390592 0.982882 + outer loop + vertex 385.855 127.138 37.8961 + vertex 380.085 125.653 36.7801 + vertex 386.754 122.768 37.8872 + endloop + endfacet + facet normal -0.235668 -0.0504798 0.970522 + outer loop + vertex 391.853 123.898 39.184 + vertex 385.855 127.138 37.8961 + vertex 386.754 122.768 37.8872 + endloop + endfacet + facet normal -0.234828 -0.0542682 0.970521 + outer loop + vertex 391.853 123.898 39.184 + vertex 386.754 122.768 37.8872 + vertex 392.788 119.501 39.1645 + endloop + endfacet + facet normal -0.232899 -0.0504436 0.971192 + outer loop + vertex 392.788 119.501 39.1645 + vertex 386.754 122.768 37.8872 + vertex 387.647 118.357 37.8722 + endloop + endfacet + facet normal -0.236177 -0.0514931 0.970345 + outer loop + vertex 390.932 128.271 39.192 + vertex 385.855 127.138 37.8961 + vertex 391.853 123.898 39.184 + endloop + endfacet + facet normal -0.237076 -0.0474501 0.970332 + outer loop + vertex 390.932 128.271 39.192 + vertex 384.969 131.557 37.8959 + vertex 385.855 127.138 37.8961 + endloop + endfacet + facet normal -0.23806 -0.0493685 0.969995 + outer loop + vertex 390.014 132.69 39.1916 + vertex 384.969 131.557 37.8959 + vertex 390.932 128.271 39.192 + endloop + endfacet + facet normal -0.238659 -0.0466832 0.969981 + outer loop + vertex 390.014 132.69 39.1916 + vertex 384.075 136.066 37.8927 + vertex 384.969 131.557 37.8959 + endloop + endfacet + facet normal -0.181432 -0.035316 0.982769 + outer loop + vertex 384.075 136.066 37.8927 + vertex 378.354 134.554 36.7822 + vertex 384.969 131.557 37.8959 + endloop + endfacet + facet normal -0.181627 -0.0357675 0.982717 + outer loop + vertex 384.969 131.557 37.8959 + vertex 378.354 134.554 36.7822 + vertex 379.229 130.066 36.7807 + endloop + endfacet + facet normal -0.181563 -0.0348158 0.982763 + outer loop + vertex 384.075 136.066 37.8927 + vertex 377.473 139.122 36.7813 + vertex 378.354 134.554 36.7822 + endloop + endfacet + facet normal -0.129627 -0.0248014 0.991253 + outer loop + vertex 377.473 139.122 36.7813 + vertex 370.307 137.247 35.7973 + vertex 378.354 134.554 36.7822 + endloop + endfacet + facet normal -0.132556 -0.0337932 0.990599 + outer loop + vertex 378.354 134.554 36.7822 + vertex 370.307 137.247 35.7973 + vertex 372.51 132.673 35.9361 + endloop + endfacet + facet normal -0.132021 -0.0155825 0.991124 + outer loop + vertex 377.473 139.122 36.7813 + vertex 370.806 141.777 35.9351 + vertex 370.307 137.247 35.7973 + endloop + endfacet + facet normal -0.092036 -0.0201251 0.995552 + outer loop + vertex 370.806 141.777 35.9351 + vertex 359.896 142.052 34.932 + vertex 370.307 137.247 35.7973 + endloop + endfacet + facet normal -0.0901476 -0.0159883 0.9958 + outer loop + vertex 359.896 142.052 34.932 + vertex 361.494 133.031 34.9318 + vertex 370.307 137.247 35.7973 + endloop + endfacet + facet normal -0.0634259 -0.0112556 0.997923 + outer loop + vertex 359.896 142.052 34.932 + vertex 345.165 138.189 33.9521 + vertex 361.494 133.031 34.9318 + endloop + endfacet + facet normal -0.0631303 -0.010314 0.997952 + outer loop + vertex 361.494 133.031 34.9318 + vertex 345.165 138.189 33.9521 + vertex 346.604 129.207 33.9503 + endloop + endfacet + facet normal -0.0387632 -0.00641047 0.999228 + outer loop + vertex 345.165 138.189 33.9521 + vertex 330.188 134.871 33.3499 + vertex 346.604 129.207 33.9503 + endloop + endfacet + facet normal -0.0384605 -0.00553133 0.999245 + outer loop + vertex 346.604 129.207 33.9503 + vertex 330.188 134.871 33.3499 + vertex 331.473 125.881 33.3495 + endloop + endfacet + facet normal -0.038259 -0.00644809 0.999247 + outer loop + vertex 346.604 129.207 33.9503 + vertex 331.473 125.881 33.3495 + vertex 348.012 120.225 33.9463 + endloop + endfacet + facet normal -0.0625145 -0.0102503 0.997991 + outer loop + vertex 363.056 124.079 34.9282 + vertex 346.604 129.207 33.9503 + vertex 348.012 120.225 33.9463 + endloop + endfacet + facet normal -0.0182249 -0.00264029 0.99983 + outer loop + vertex 330.188 134.871 33.3499 + vertex 314.957 132.056 33.0648 + vertex 331.473 125.881 33.3495 + endloop + endfacet + facet normal -0.0181957 -0.002562 0.999831 + outer loop + vertex 331.473 125.881 33.3495 + vertex 314.957 132.056 33.0648 + vertex 316.109 123.036 33.0626 + endloop + endfacet + facet normal -0.0180287 -0.00346363 0.999831 + outer loop + vertex 331.473 125.881 33.3495 + vertex 316.109 123.036 33.0626 + vertex 332.74 116.855 33.3411 + endloop + endfacet + facet normal -0.00616697 -0.00102602 0.99998 + outer loop + vertex 314.957 132.056 33.0648 + vertex 299.28 129.48 32.9655 + vertex 316.109 123.036 33.0626 + endloop + endfacet + facet normal -0.00617476 -0.00104638 0.99998 + outer loop + vertex 316.109 123.036 33.0626 + vertex 299.28 129.48 32.9655 + vertex 300.346 120.439 32.9626 + endloop + endfacet + facet normal -0.00611763 -0.00139306 0.99998 + outer loop + vertex 316.109 123.036 33.0626 + vertex 300.346 120.439 32.9626 + vertex 317.264 113.987 33.0571 + endloop + endfacet + facet normal -0.00232228 -0.000592032 0.999997 + outer loop + vertex 299.28 129.48 32.9655 + vertex 283.056 126.912 32.9263 + vertex 300.346 120.439 32.9626 + endloop + endfacet + facet normal -0.00224227 -0.000378317 0.999997 + outer loop + vertex 300.346 120.439 32.9626 + vertex 283.056 126.912 32.9263 + vertex 284.068 117.864 32.9251 + endloop + endfacet + facet normal -0.00280191 -0.000440857 0.999996 + outer loop + vertex 283.056 126.912 32.9263 + vertex 266.363 124.3 32.8783 + vertex 284.068 117.864 32.9251 + endloop + endfacet + facet normal -0.00276109 -0.000701696 0.999996 + outer loop + vertex 283.056 126.912 32.9263 + vertex 265.382 133.314 32.882 + vertex 266.363 124.3 32.8783 + endloop + endfacet + facet normal -0.00433237 -0.000872711 0.99999 + outer loop + vertex 265.382 133.314 32.882 + vertex 248.423 130.727 32.8062 + vertex 266.363 124.3 32.8783 + endloop + endfacet + facet normal -0.0042246 -0.000571886 0.999991 + outer loop + vertex 266.363 124.3 32.8783 + vertex 248.423 130.727 32.8062 + vertex 249.411 121.719 32.8052 + endloop + endfacet + facet normal -0.00528735 -0.000688481 0.999986 + outer loop + vertex 248.423 130.727 32.8062 + vertex 231.404 128.266 32.7145 + vertex 249.411 121.719 32.8052 + endloop + endfacet + facet normal -0.00526224 -0.000862146 0.999986 + outer loop + vertex 248.423 130.727 32.8062 + vertex 230.393 137.242 32.717 + vertex 231.404 128.266 32.7145 + endloop + endfacet + facet normal -0.0059039 -0.000934469 0.999982 + outer loop + vertex 230.393 137.242 32.717 + vertex 213.465 134.954 32.6149 + vertex 231.404 128.266 32.7145 + endloop + endfacet + facet normal -0.00581662 -0.00070034 0.999983 + outer loop + vertex 231.404 128.266 32.7145 + vertex 213.465 134.954 32.6149 + vertex 214.486 125.984 32.6145 + endloop + endfacet + facet normal -0.00642067 -0.00076914 0.999979 + outer loop + vertex 213.465 134.954 32.6149 + vertex 196.781 132.865 32.5061 + vertex 214.486 125.984 32.6145 + endloop + endfacet + facet normal -0.00640001 -0.000934093 0.999979 + outer loop + vertex 213.465 134.954 32.6149 + vertex 195.752 141.847 32.5079 + vertex 196.781 132.865 32.5061 + endloop + endfacet + facet normal -0.00723149 -0.00102941 0.999973 + outer loop + vertex 195.752 141.847 32.5079 + vertex 179.432 139.958 32.388 + vertex 196.781 132.865 32.5061 + endloop + endfacet + facet normal -0.00719159 -0.000931812 0.999974 + outer loop + vertex 196.781 132.865 32.5061 + vertex 179.432 139.958 32.388 + vertex 180.446 130.979 32.3869 + endloop + endfacet + facet normal -0.00720489 -0.000816696 0.999974 + outer loop + vertex 196.781 132.865 32.5061 + vertex 180.446 130.979 32.3869 + vertex 197.801 123.899 32.5062 + endloop + endfacet + facet normal -0.00813523 -0.00103836 0.999966 + outer loop + vertex 179.432 139.958 32.388 + vertex 163.514 138.27 32.2567 + vertex 180.446 130.979 32.3869 + endloop + endfacet + facet normal -0.00811088 -0.000981811 0.999967 + outer loop + vertex 180.446 130.979 32.3869 + vertex 163.514 138.27 32.2567 + vertex 164.474 129.284 32.2557 + endloop + endfacet + facet normal -0.00812135 -0.000883149 0.999967 + outer loop + vertex 180.446 130.979 32.3869 + vertex 164.474 129.284 32.2557 + vertex 181.432 122.008 32.387 + endloop + endfacet + facet normal -0.00900554 -0.00107742 0.999959 + outer loop + vertex 163.514 138.27 32.2567 + vertex 147.953 136.767 32.115 + vertex 164.474 129.284 32.2557 + endloop + endfacet + facet normal -0.00898939 -0.00104177 0.999959 + outer loop + vertex 164.474 129.284 32.2557 + vertex 147.953 136.767 32.115 + vertex 148.836 127.772 32.1135 + endloop + endfacet + facet normal -0.00899347 -0.000999585 0.999959 + outer loop + vertex 164.474 129.284 32.2557 + vertex 148.836 127.772 32.1135 + vertex 165.421 120.315 32.2552 + endloop + endfacet + facet normal -0.00961304 -0.00110298 0.999953 + outer loop + vertex 147.953 136.767 32.115 + vertex 132.643 135.407 31.9663 + vertex 148.836 127.772 32.1135 + endloop + endfacet + facet normal -0.00956147 -0.000993614 0.999954 + outer loop + vertex 148.836 127.772 32.1135 + vertex 132.643 135.407 31.9663 + vertex 133.432 126.406 31.9649 + endloop + endfacet + facet normal -0.00956252 -0.000981872 0.999954 + outer loop + vertex 148.836 127.772 32.1135 + vertex 133.432 126.406 31.9649 + vertex 149.706 118.796 32.113 + endloop + endfacet + facet normal -0.00981693 -0.001016 0.999951 + outer loop + vertex 132.643 135.407 31.9663 + vertex 117.526 134.16 31.8166 + vertex 133.432 126.406 31.9649 + endloop + endfacet + facet normal -0.00974829 -0.000875222 0.999952 + outer loop + vertex 133.432 126.406 31.9649 + vertex 117.526 134.16 31.8166 + vertex 118.206 125.149 31.8154 + endloop + endfacet + facet normal -0.00974754 -0.000884312 0.999952 + outer loop + vertex 133.432 126.406 31.9649 + vertex 118.206 125.149 31.8154 + vertex 134.206 117.42 31.9645 + endloop + endfacet + facet normal -0.00962578 -0.000865972 0.999953 + outer loop + vertex 117.526 134.16 31.8166 + vertex 102.582 132.995 31.6717 + vertex 118.206 125.149 31.8154 + endloop + endfacet + facet normal -0.00955325 -0.000721526 0.999954 + outer loop + vertex 118.206 125.149 31.8154 + vertex 102.582 132.995 31.6717 + vertex 103.163 123.977 31.6708 + endloop + endfacet + facet normal -0.00954994 -0.000763896 0.999954 + outer loop + vertex 118.206 125.149 31.8154 + vertex 103.163 123.977 31.6708 + vertex 118.887 116.157 31.815 + endloop + endfacet + facet normal -0.00906996 -0.000690386 0.999959 + outer loop + vertex 102.582 132.995 31.6717 + vertex 87.8123 131.898 31.537 + vertex 103.163 123.977 31.6708 + endloop + endfacet + facet normal -0.00901965 -0.000592889 0.999959 + outer loop + vertex 103.163 123.977 31.6708 + vertex 87.8123 131.898 31.537 + vertex 88.2922 122.873 31.536 + endloop + endfacet + facet normal -0.00901725 -0.000625244 0.999959 + outer loop + vertex 103.163 123.977 31.6708 + vertex 88.2922 122.873 31.536 + vertex 103.749 114.979 31.6704 + endloop + endfacet + facet normal -0.00824502 -0.000551699 0.999966 + outer loop + vertex 87.8123 131.898 31.537 + vertex 73.1547 130.865 31.4156 + vertex 88.2922 122.873 31.536 + endloop + endfacet + facet normal -0.00818223 -0.000432777 0.999966 + outer loop + vertex 88.2922 122.873 31.536 + vertex 73.1547 130.865 31.4156 + vertex 73.5503 121.839 31.4149 + endloop + endfacet + facet normal -0.00817979 -0.000467586 0.999966 + outer loop + vertex 88.2922 122.873 31.536 + vertex 73.5503 121.839 31.4149 + vertex 88.7887 113.872 31.5359 + endloop + endfacet + facet normal -0.0071227 -0.000386341 0.999975 + outer loop + vertex 73.1547 130.865 31.4156 + vertex 58.5375 129.924 31.3111 + vertex 73.5503 121.839 31.4149 + endloop + endfacet + facet normal -0.00710656 -0.000356364 0.999975 + outer loop + vertex 73.5503 121.839 31.4149 + vertex 58.5375 129.924 31.3111 + vertex 58.8507 120.895 31.3101 + endloop + endfacet + facet normal -0.00710806 -0.000333014 0.999975 + outer loop + vertex 73.5503 121.839 31.4149 + vertex 58.8507 120.895 31.3101 + vertex 73.9552 112.837 31.4148 + endloop + endfacet + facet normal -0.00590136 -0.000314557 0.999983 + outer loop + vertex 58.5375 129.924 31.3111 + vertex 43.9081 129.101 31.2245 + vertex 58.8507 120.895 31.3101 + endloop + endfacet + facet normal -0.00583375 -0.000191449 0.999983 + outer loop + vertex 58.8507 120.895 31.3101 + vertex 43.9081 129.101 31.2245 + vertex 44.1294 120.076 31.2241 + endloop + endfacet + facet normal -0.00583251 -0.000213731 0.999983 + outer loop + vertex 58.8507 120.895 31.3101 + vertex 44.1294 120.076 31.2241 + vertex 59.1656 111.892 31.31 + endloop + endfacet + facet normal -0.00437311 -0.000155632 0.99999 + outer loop + vertex 43.9081 129.101 31.2245 + vertex 29.2408 128.463 31.1603 + vertex 44.1294 120.076 31.2241 + endloop + endfacet + facet normal -0.0043551 -0.000123647 0.999991 + outer loop + vertex 44.1294 120.076 31.2241 + vertex 29.2408 128.463 31.1603 + vertex 29.381 119.439 31.1598 + endloop + endfacet + facet normal -0.00435559 -0.00011225 0.999991 + outer loop + vertex 44.1294 120.076 31.2241 + vertex 29.381 119.439 31.1598 + vertex 44.3601 111.074 31.2241 + endloop + endfacet + facet normal -0.00273496 -9.84861e-05 0.999996 + outer loop + vertex 29.2408 128.463 31.1603 + vertex 14.5699 128.053 31.1201 + vertex 29.381 119.439 31.1598 + endloop + endfacet + facet normal -0.00273388 -9.66327e-05 0.999996 + outer loop + vertex 29.381 119.439 31.1598 + vertex 14.5699 128.053 31.1201 + vertex 14.6356 119.028 31.1194 + endloop + endfacet + facet normal -0.00273472 -6.64044e-05 0.999996 + outer loop + vertex 29.381 119.439 31.1598 + vertex 14.6356 119.028 31.1194 + vertex 29.5327 110.434 31.1596 + endloop + endfacet + facet normal -0.000925714 -8.34583e-05 1 + outer loop + vertex 14.5699 128.053 31.1201 + vertex -0.0692545 127.916 31.1066 + vertex 14.6356 119.028 31.1194 + endloop + endfacet + facet normal -0.000909116 -5.59965e-05 1 + outer loop + vertex 14.6356 119.028 31.1194 + vertex -0.0692545 127.916 31.1066 + vertex -0.0756773 118.891 31.106 + endloop + endfacet + facet normal -0.000909765 1.37639e-05 1 + outer loop + vertex 14.6356 119.028 31.1194 + vertex -0.0756773 118.891 31.106 + vertex 14.7133 110.026 31.1196 + endloop + endfacet + facet normal 0.000925862 -5.73025e-05 1 + outer loop + vertex -0.0692545 127.916 31.1066 + vertex -14.6828 128.06 31.1201 + vertex -0.0756773 118.891 31.106 + endloop + endfacet + facet normal 0.000937599 -3.86036e-05 1 + outer loop + vertex -0.0756773 118.891 31.106 + vertex -14.6828 128.06 31.1201 + vertex -14.7614 119.036 31.1198 + endloop + endfacet + facet normal 0.000937925 -5.48006e-06 1 + outer loop + vertex -0.0756773 118.891 31.106 + vertex -14.7614 119.036 31.1198 + vertex -0.075426 109.885 31.106 + endloop + endfacet + facet normal 0.00275048 -5.4394e-05 0.999996 + outer loop + vertex -14.6828 128.06 31.1201 + vertex -29.2871 128.473 31.1603 + vertex -14.7614 119.036 31.1198 + endloop + endfacet + facet normal 0.00270708 -0.000121206 0.999996 + outer loop + vertex -14.7614 119.036 31.1198 + vertex -29.2871 128.473 31.1603 + vertex -29.4448 119.444 31.1596 + endloop + endfacet + facet normal 0.00270968 -2.7471e-05 0.999996 + outer loop + vertex -14.7614 119.036 31.1198 + vertex -29.4448 119.444 31.1596 + vertex -14.8386 110.028 31.1198 + endloop + endfacet + facet normal 0.00441321 -0.000150999 0.99999 + outer loop + vertex -29.2871 128.473 31.1603 + vertex -43.8972 129.116 31.2249 + vertex -29.4448 119.444 31.1596 + endloop + endfacet + facet normal 0.0043813 -0.000198679 0.99999 + outer loop + vertex -29.4448 119.444 31.1596 + vertex -43.8972 129.116 31.2249 + vertex -44.1387 120.085 31.2241 + endloop + endfacet + facet normal 0.00438576 -9.65584e-05 0.99999 + outer loop + vertex -29.4448 119.444 31.1596 + vertex -44.1387 120.085 31.2241 + vertex -29.6005 110.433 31.1594 + endloop + endfacet + facet normal 0.00588319 -0.000238836 0.999983 + outer loop + vertex -43.8972 129.116 31.2249 + vertex -58.511 129.933 31.311 + vertex -44.1387 120.085 31.2241 + endloop + endfacet + facet normal 0.00585122 -0.000285486 0.999983 + outer loop + vertex -44.1387 120.085 31.2241 + vertex -58.511 129.933 31.311 + vertex -58.84 120.904 31.3104 + endloop + endfacet + facet normal 0.00585803 -0.000163213 0.999983 + outer loop + vertex -44.1387 120.085 31.2241 + vertex -58.84 120.904 31.3104 + vertex -44.3748 111.075 31.224 + endloop + endfacet + facet normal 0.00716904 -0.000333511 0.999974 + outer loop + vertex -58.511 129.933 31.311 + vertex -73.1153 130.873 31.416 + vertex -58.84 120.904 31.3104 + endloop + endfacet + facet normal 0.00708173 -0.000458543 0.999975 + outer loop + vertex -58.84 120.904 31.3104 + vertex -73.1153 130.873 31.416 + vertex -73.5369 121.844 31.4149 + endloop + endfacet + facet normal 0.00709167 -0.000303041 0.999975 + outer loop + vertex -58.84 120.904 31.3104 + vertex -73.5369 121.844 31.4149 + vertex -59.163 111.893 31.3099 + endloop + endfacet + facet normal 0.00824776 -0.000512999 0.999966 + outer loop + vertex -73.1153 130.873 31.416 + vertex -87.7102 131.894 31.537 + vertex -73.5369 121.844 31.4149 + endloop + endfacet + facet normal 0.00815616 -0.000642185 0.999967 + outer loop + vertex -73.5369 121.844 31.4149 + vertex -87.7102 131.894 31.537 + vertex -88.2272 122.869 31.5354 + endloop + endfacet + facet normal 0.00817255 -0.000407169 0.999967 + outer loop + vertex -73.5369 121.844 31.4149 + vertex -88.2272 122.869 31.5354 + vertex -73.9495 112.838 31.4146 + endloop + endfacet + facet normal 0.00904977 -0.000693372 0.999959 + outer loop + vertex -87.7102 131.894 31.537 + vertex -102.337 132.971 31.6701 + vertex -88.2272 122.869 31.5354 + endloop + endfacet + facet normal 0.00898987 -0.000777036 0.999959 + outer loop + vertex -88.2272 122.869 31.5354 + vertex -102.337 132.971 31.6701 + vertex -102.955 123.955 31.6686 + endloop + endfacet + facet normal 0.00900761 -0.00053661 0.999959 + outer loop + vertex -88.2272 122.869 31.5354 + vertex -102.955 123.955 31.6686 + vertex -88.7346 113.868 31.5351 + endloop + endfacet + facet normal 0.00961817 -0.000820135 0.999953 + outer loop + vertex -102.337 132.971 31.6701 + vertex -117.095 134.117 31.813 + vertex -102.955 123.955 31.6686 + endloop + endfacet + facet normal 0.0095173 -0.000960498 0.999954 + outer loop + vertex -102.955 123.955 31.6686 + vertex -117.095 134.117 31.813 + vertex -117.813 125.109 31.8111 + endloop + endfacet + facet normal 0.00953787 -0.000695639 0.999954 + outer loop + vertex -102.955 123.955 31.6686 + vertex -117.813 125.109 31.8111 + vertex -103.562 114.962 31.6682 + endloop + endfacet + facet normal 0.00975938 -0.000979811 0.999952 + outer loop + vertex -117.095 134.117 31.813 + vertex -132.092 135.351 31.9605 + vertex -117.813 125.109 31.8111 + endloop + endfacet + facet normal 0.00968878 -0.00107825 0.999952 + outer loop + vertex -117.813 125.109 31.8111 + vertex -132.092 135.351 31.9605 + vertex -132.912 126.353 31.9588 + endloop + endfacet + facet normal 0.00971081 -0.000810869 0.999953 + outer loop + vertex -117.813 125.109 31.8111 + vertex -132.912 126.353 31.9588 + vertex -118.519 116.124 31.8107 + endloop + endfacet + facet normal 0.00954925 -0.00106555 0.999954 + outer loop + vertex -132.092 135.351 31.9605 + vertex -147.428 136.712 32.1084 + vertex -132.912 126.353 31.9588 + endloop + endfacet + facet normal 0.00947934 -0.00116351 0.999954 + outer loop + vertex -132.912 126.353 31.9588 + vertex -147.428 136.712 32.1084 + vertex -148.34 127.726 32.1066 + endloop + endfacet + facet normal 0.00950372 -0.000889541 0.999954 + outer loop + vertex -132.912 126.353 31.9588 + vertex -148.34 127.726 32.1066 + vertex -133.717 117.378 31.9585 + endloop + endfacet + facet normal 0.00901659 -0.00111651 0.999959 + outer loop + vertex -147.428 136.712 32.1084 + vertex -163.143 138.238 32.2519 + vertex -148.34 127.726 32.1066 + endloop + endfacet + facet normal 0.00893574 -0.00123038 0.999959 + outer loop + vertex -148.34 127.726 32.1066 + vertex -163.143 138.238 32.2519 + vertex -164.117 129.254 32.2495 + endloop + endfacet + facet normal 0.00896518 -0.00092635 0.999959 + outer loop + vertex -148.34 127.726 32.1066 + vertex -164.117 129.254 32.2495 + vertex -149.231 118.757 32.1063 + endloop + endfacet + facet normal 0.00829502 -0.00116094 0.999965 + outer loop + vertex -163.143 138.238 32.2519 + vertex -179.202 139.939 32.387 + vertex -164.117 129.254 32.2495 + endloop + endfacet + facet normal 0.00819742 -0.00129873 0.999966 + outer loop + vertex -164.117 129.254 32.2495 + vertex -179.202 139.939 32.387 + vertex -180.216 130.961 32.3837 + endloop + endfacet + facet normal 0.00816849 -0.00235513 0.999964 + outer loop + vertex -163.143 138.238 32.2519 + vertex -178.239 149.019 32.4006 + vertex -179.202 139.939 32.387 + endloop + endfacet + facet normal 0.00744635 -0.00227859 0.99997 + outer loop + vertex -178.239 149.019 32.4006 + vertex -194.583 150.916 32.5266 + vertex -179.202 139.939 32.387 + endloop + endfacet + facet normal 0.00742049 -0.00231484 0.99997 + outer loop + vertex -179.202 139.939 32.387 + vertex -194.583 150.916 32.5266 + vertex -195.578 141.84 32.513 + endloop + endfacet + facet normal 0.00706342 -0.00557843 0.999959 + outer loop + vertex -178.239 149.019 32.4006 + vertex -193.466 160.119 32.57 + vertex -194.583 150.916 32.5266 + endloop + endfacet + facet normal 0.00582172 -0.0054277 0.999968 + outer loop + vertex -193.466 160.119 32.57 + vertex -210.527 162.268 32.681 + vertex -194.583 150.916 32.5266 + endloop + endfacet + facet normal 0.00634893 -0.00468728 0.999969 + outer loop + vertex -194.583 150.916 32.5266 + vertex -210.527 162.268 32.681 + vertex -211.204 153.004 32.6419 + endloop + endfacet + facet normal 0.00689783 -0.00580558 0.999959 + outer loop + vertex -177.709 158.288 32.4507 + vertex -193.466 160.119 32.57 + vertex -178.239 149.019 32.4006 + endloop + endfacet + facet normal 0.00787199 -0.00586124 0.999952 + outer loop + vertex -162.226 147.318 32.2645 + vertex -177.709 158.288 32.4507 + vertex -178.239 149.019 32.4006 + endloop + endfacet + facet normal 0.00805995 -0.00559595 0.999952 + outer loop + vertex -161.247 156.544 32.3083 + vertex -177.709 158.288 32.4507 + vertex -162.226 147.318 32.2645 + endloop + endfacet + facet normal 0.0086668 -0.00566026 0.999946 + outer loop + vertex -146.551 145.8 32.1201 + vertex -161.247 156.544 32.3083 + vertex -162.226 147.318 32.2645 + endloop + endfacet + facet normal 0.00900699 -0.00214895 0.999957 + outer loop + vertex -146.551 145.8 32.1201 + vertex -162.226 147.318 32.2645 + vertex -147.428 136.712 32.1084 + endloop + endfacet + facet normal 0.00898163 -0.00522959 0.999946 + outer loop + vertex -145.76 155.048 32.1613 + vertex -161.247 156.544 32.3083 + vertex -146.551 145.8 32.1201 + endloop + endfacet + facet normal 0.00927357 -0.00525455 0.999943 + outer loop + vertex -131.326 144.449 31.9718 + vertex -145.76 155.048 32.1613 + vertex -146.551 145.8 32.1201 + endloop + endfacet + facet normal 0.00955897 -0.00203979 0.999952 + outer loop + vertex -131.326 144.449 31.9718 + vertex -146.551 145.8 32.1201 + vertex -132.092 135.351 31.9605 + endloop + endfacet + facet normal 0.00955369 -0.00487306 0.999942 + outer loop + vertex -130.724 153.717 32.0112 + vertex -145.76 155.048 32.1613 + vertex -131.326 144.449 31.9718 + endloop + endfacet + facet normal 0.00954184 -0.00487229 0.999943 + outer loop + vertex -116.399 143.22 31.8234 + vertex -130.724 153.717 32.0112 + vertex -131.326 144.449 31.9718 + endloop + endfacet + facet normal 0.00978754 -0.00188924 0.99995 + outer loop + vertex -116.399 143.22 31.8234 + vertex -131.326 144.449 31.9718 + vertex -117.095 134.117 31.813 + endloop + endfacet + facet normal 0.00976245 -0.00457121 0.999942 + outer loop + vertex -115.565 152.475 31.8575 + vertex -130.724 153.717 32.0112 + vertex -116.399 143.22 31.8234 + endloop + endfacet + facet normal 0.00940218 -0.00453875 0.999945 + outer loop + vertex -101.755 142.085 31.6805 + vertex -115.565 152.475 31.8575 + vertex -116.399 143.22 31.8234 + endloop + endfacet + facet normal 0.00961765 -0.00175894 0.999952 + outer loop + vertex -101.755 142.085 31.6805 + vertex -116.399 143.22 31.8234 + vertex -102.337 132.971 31.6701 + endloop + endfacet + facet normal 0.00959162 -0.00428693 0.999945 + outer loop + vertex -101.539 151.394 31.7183 + vertex -115.565 152.475 31.8575 + vertex -101.755 142.085 31.6805 + endloop + endfacet + facet normal 0.00888949 -0.00427061 0.999951 + outer loop + vertex -87.2521 141.014 31.547 + vertex -101.539 151.394 31.7183 + vertex -101.755 142.085 31.6805 + endloop + endfacet + facet normal 0.00908984 -0.00155868 0.999957 + outer loop + vertex -87.2521 141.014 31.547 + vertex -101.755 142.085 31.6805 + vertex -87.7102 131.894 31.537 + endloop + endfacet + facet normal 0.00903423 -0.00407139 0.999951 + outer loop + vertex -86.9011 150.312 31.5817 + vertex -101.539 151.394 31.7183 + vertex -87.2521 141.014 31.547 + endloop + endfacet + facet normal 0.00805683 -0.00403452 0.999959 + outer loop + vertex -72.7213 139.995 31.4258 + vertex -86.9011 150.312 31.5817 + vertex -87.2521 141.014 31.547 + endloop + endfacet + facet normal 0.00823972 -0.00142659 0.999965 + outer loop + vertex -72.7213 139.995 31.4258 + vertex -87.2521 141.014 31.547 + vertex -73.1153 130.873 31.416 + endloop + endfacet + facet normal 0.00813606 -0.00392562 0.999959 + outer loop + vertex -72.4034 149.28 31.4597 + vertex -86.9011 150.312 31.5817 + vertex -72.7213 139.995 31.4258 + endloop + endfacet + facet normal 0.00699165 -0.00388646 0.999968 + outer loop + vertex -58.1992 139.055 31.3206 + vertex -72.4034 149.28 31.4597 + vertex -72.7213 139.995 31.4258 + endloop + endfacet + facet normal 0.00715936 -0.0012962 0.999974 + outer loop + vertex -58.1992 139.055 31.3206 + vertex -72.7213 139.995 31.4258 + vertex -58.511 129.933 31.311 + endloop + endfacet + facet normal 0.00704998 -0.00380542 0.999968 + outer loop + vertex -57.9539 148.333 31.3542 + vertex -72.4034 149.28 31.4597 + vertex -58.1992 139.055 31.3206 + endloop + endfacet + facet normal 0.00573242 -0.00377061 0.999976 + outer loop + vertex -43.679 138.238 31.2343 + vertex -57.9539 148.333 31.3542 + vertex -58.1992 139.055 31.3206 + endloop + endfacet + facet normal 0.00587845 -0.00117602 0.999982 + outer loop + vertex -43.679 138.238 31.2343 + vertex -58.1992 139.055 31.3206 + vertex -43.8972 129.116 31.2249 + endloop + endfacet + facet normal 0.00579453 -0.00368279 0.999976 + outer loop + vertex -43.5629 147.516 31.2678 + vertex -57.9539 148.333 31.3542 + vertex -43.679 138.238 31.2343 + endloop + endfacet + facet normal 0.00429008 -0.00366398 0.999984 + outer loop + vertex -29.1453 137.596 31.1696 + vertex -43.5629 147.516 31.2678 + vertex -43.679 138.238 31.2343 + endloop + endfacet + facet normal 0.00440377 -0.00108976 0.99999 + outer loop + vertex -29.1453 137.596 31.1696 + vertex -43.679 138.238 31.2343 + vertex -29.2871 128.473 31.1603 + endloop + endfacet + facet normal 0.00435773 -0.00356565 0.999984 + outer loop + vertex -28.9946 146.866 31.202 + vertex -43.5629 147.516 31.2678 + vertex -29.1453 137.596 31.1696 + endloop + endfacet + facet normal 0.00267303 -0.00353828 0.99999 + outer loop + vertex -14.6069 137.182 31.1293 + vertex -28.9946 146.866 31.202 + vertex -29.1453 137.596 31.1696 + endloop + endfacet + facet normal 0.0027445 -0.00102935 0.999996 + outer loop + vertex -14.6069 137.182 31.1293 + vertex -29.1453 137.596 31.1696 + vertex -14.6828 128.06 31.1201 + endloop + endfacet + facet normal 0.00274574 -0.00343026 0.99999 + outer loop + vertex -14.5821 146.445 31.161 + vertex -28.9946 146.866 31.202 + vertex -14.6069 137.182 31.1293 + endloop + endfacet + facet normal 0.000923463 -0.00342539 0.999994 + outer loop + vertex -0.057923 137.035 31.1153 + vertex -14.5821 146.445 31.161 + vertex -14.6069 137.182 31.1293 + endloop + endfacet + facet normal 0.000948424 -0.000963942 0.999999 + outer loop + vertex -0.057923 137.035 31.1153 + vertex -14.6069 137.182 31.1293 + vertex -0.0692545 127.916 31.1066 + endloop + endfacet + facet normal 0.000956688 -0.00337411 0.999994 + outer loop + vertex -1.52547e-14 146.292 31.1465 + vertex -14.5821 146.445 31.161 + vertex -0.057923 137.035 31.1153 + endloop + endfacet + facet normal -0.000879139 -0.00336262 0.999994 + outer loop + vertex 14.4797 137.171 31.1286 + vertex -1.52547e-14 146.292 31.1465 + vertex -0.057923 137.035 31.1153 + endloop + endfacet + facet normal -0.000901888 -0.000936286 0.999999 + outer loop + vertex 14.4797 137.171 31.1286 + vertex -0.057923 137.035 31.1153 + vertex 14.5699 128.053 31.1201 + endloop + endfacet + facet normal -0.000921714 -0.00343021 0.999994 + outer loop + vertex 14.0427 146.434 31.1599 + vertex -1.52547e-14 146.292 31.1465 + vertex 14.4797 137.171 31.1286 + endloop + endfacet + facet normal -0.00270369 -0.00351425 0.99999 + outer loop + vertex 29.1198 137.59 31.1696 + vertex 14.0427 146.434 31.1599 + vertex 14.4797 137.171 31.1286 + endloop + endfacet + facet normal -0.00277395 -0.00106073 0.999996 + outer loop + vertex 29.1198 137.59 31.1696 + vertex 14.4797 137.171 31.1286 + vertex 29.2408 128.463 31.1603 + endloop + endfacet + facet normal -0.00273861 -0.00357378 0.99999 + outer loop + vertex 29.5047 146.885 31.2039 + vertex 14.0427 146.434 31.1599 + vertex 29.1198 137.59 31.1696 + endloop + endfacet + facet normal -0.00424697 -0.00351129 0.999985 + outer loop + vertex 43.6683 138.226 31.2337 + vertex 29.5047 146.885 31.2039 + vertex 29.1198 137.59 31.1696 + endloop + endfacet + facet normal -0.0043518 -0.00111448 0.99999 + outer loop + vertex 43.6683 138.226 31.2337 + vertex 29.1198 137.59 31.1696 + vertex 43.9081 129.101 31.2245 + endloop + endfacet + facet normal -0.00434029 -0.00366394 0.999984 + outer loop + vertex 42.7798 147.476 31.2637 + vertex 29.5047 146.885 31.2039 + vertex 43.6683 138.226 31.2337 + endloop + endfacet + facet normal -0.00572038 -0.00379648 0.999976 + outer loop + vertex 58.2028 139.044 31.3199 + vertex 42.7798 147.476 31.2637 + vertex 43.6683 138.226 31.2337 + endloop + endfacet + facet normal -0.00586775 -0.00117832 0.999982 + outer loop + vertex 58.2028 139.044 31.3199 + vertex 43.6683 138.226 31.2337 + vertex 58.5375 129.924 31.3111 + endloop + endfacet + facet normal -0.00576323 -0.00387487 0.999976 + outer loop + vertex 58.3227 148.355 31.3567 + vertex 42.7798 147.476 31.2637 + vertex 58.2028 139.044 31.3199 + endloop + endfacet + facet normal -0.00697936 -0.00385918 0.999968 + outer loop + vertex 72.8501 139.994 31.4258 + vertex 58.3227 148.355 31.3567 + vertex 58.2028 139.044 31.3199 + endloop + endfacet + facet normal -0.00714175 -0.00135568 0.999974 + outer loop + vertex 72.8501 139.994 31.4258 + vertex 58.2028 139.044 31.3199 + vertex 73.1547 130.865 31.4156 + endloop + endfacet + facet normal -0.00706909 -0.00401509 0.999967 + outer loop + vertex 72.8473 149.311 31.4632 + vertex 58.3227 148.355 31.3567 + vertex 72.8501 139.994 31.4258 + endloop + endfacet + facet normal -0.00804613 -0.00401536 0.99996 + outer loop + vertex 87.3218 141.014 31.5463 + vertex 72.8473 149.311 31.4632 + vertex 72.8501 139.994 31.4258 + endloop + endfacet + facet normal -0.00822601 -0.00146459 0.999965 + outer loop + vertex 87.3218 141.014 31.5463 + vertex 72.8501 139.994 31.4258 + vertex 87.8123 131.898 31.537 + endloop + endfacet + facet normal -0.00811494 -0.00413541 0.999959 + outer loop + vertex 86.2504 150.264 31.5759 + vertex 72.8473 149.311 31.4632 + vertex 87.3218 141.014 31.5463 + endloop + endfacet + facet normal -0.00892406 -0.00422911 0.999951 + outer loop + vertex 101.975 142.107 31.6817 + vertex 86.2504 150.264 31.5759 + vertex 87.3218 141.014 31.5463 + endloop + endfacet + facet normal -0.00911251 -0.00170316 0.999957 + outer loop + vertex 101.975 142.107 31.6817 + vertex 87.3218 141.014 31.5463 + vertex 102.582 132.995 31.6717 + endloop + endfacet + facet normal -0.00899589 -0.0043676 0.99995 + outer loop + vertex 101.632 151.401 31.7192 + vertex 86.2504 150.264 31.5759 + vertex 101.975 142.107 31.6817 + endloop + endfacet + facet normal -0.00942147 -0.00438332 0.999946 + outer loop + vertex 116.852 143.264 31.827 + vertex 101.632 151.401 31.7192 + vertex 101.975 142.107 31.6817 + endloop + endfacet + facet normal -0.00961846 -0.00185077 0.999952 + outer loop + vertex 116.852 143.264 31.827 + vertex 101.975 142.107 31.6817 + vertex 117.526 134.16 31.8166 + endloop + endfacet + facet normal -0.00956919 -0.00465966 0.999943 + outer loop + vertex 116.006 152.51 31.862 + vertex 101.632 151.401 31.7192 + vertex 116.852 143.264 31.827 + endloop + endfacet + facet normal -0.0095877 -0.00466135 0.999943 + outer loop + vertex 131.858 144.501 31.9766 + vertex 116.006 152.51 31.862 + vertex 116.852 143.264 31.827 + endloop + endfacet + facet normal -0.00980845 -0.00198324 0.99995 + outer loop + vertex 131.858 144.501 31.9766 + vertex 116.852 143.264 31.827 + vertex 132.643 135.407 31.9663 + endloop + endfacet + facet normal -0.00973146 -0.00494594 0.99994 + outer loop + vertex 131.264 153.763 32.0167 + vertex 116.006 152.51 31.862 + vertex 131.858 144.501 31.9766 + endloop + endfacet + facet normal -0.00932274 -0.00491973 0.999944 + outer loop + vertex 147.122 145.854 32.1256 + vertex 131.264 153.763 32.0167 + vertex 131.858 144.501 31.9766 + endloop + endfacet + facet normal -0.00957779 -0.00204481 0.999952 + outer loop + vertex 147.122 145.854 32.1256 + vertex 131.858 144.501 31.9766 + vertex 147.953 136.767 32.115 + endloop + endfacet + facet normal -0.00950051 -0.00527626 0.999941 + outer loop + vertex 146.587 155.124 32.1694 + vertex 131.264 153.763 32.0167 + vertex 147.122 145.854 32.1256 + endloop + endfacet + facet normal -0.00865633 -0.00522761 0.999949 + outer loop + vertex 162.565 147.35 32.2671 + vertex 146.587 155.124 32.1694 + vertex 147.122 145.854 32.1256 + endloop + endfacet + facet normal -0.00896135 -0.00207842 0.999958 + outer loop + vertex 162.565 147.35 32.2671 + vertex 147.122 145.854 32.1256 + vertex 163.514 138.27 32.2567 + endloop + endfacet + facet normal -0.00891355 -0.00575631 0.999944 + outer loop + vertex 161.226 156.541 32.3081 + vertex 146.587 155.124 32.1694 + vertex 162.565 147.35 32.2671 + endloop + endfacet + facet normal -0.00776987 -0.00558977 0.999954 + outer loop + vertex 178.474 149.042 32.4002 + vertex 161.226 156.541 32.3081 + vertex 162.565 147.35 32.2671 + endloop + endfacet + facet normal -0.00813065 -0.00219945 0.999965 + outer loop + vertex 178.474 149.042 32.4002 + vertex 162.565 147.35 32.2671 + vertex 179.432 139.958 32.388 + endloop + endfacet + facet normal -0.00799369 -0.00610463 0.999949 + outer loop + vertex 178.097 158.332 32.4539 + vertex 161.226 156.541 32.3081 + vertex 178.474 149.042 32.4002 + endloop + endfacet + facet normal -0.00683869 -0.00605773 0.999958 + outer loop + vertex 194.745 150.927 32.5229 + vertex 178.097 158.332 32.4539 + vertex 178.474 149.042 32.4002 + endloop + endfacet + facet normal -0.00725696 -0.00244821 0.999971 + outer loop + vertex 194.745 150.927 32.5229 + vertex 178.474 149.042 32.4002 + vertex 195.752 141.847 32.5079 + endloop + endfacet + facet normal -0.00638637 -0.00235173 0.999977 + outer loop + vertex 212.437 143.944 32.6194 + vertex 194.745 150.927 32.5229 + vertex 195.752 141.847 32.5079 + endloop + endfacet + facet normal -0.00654077 -0.00274292 0.999975 + outer loop + vertex 211.44 153.028 32.6378 + vertex 194.745 150.927 32.5229 + vertex 212.437 143.944 32.6194 + endloop + endfacet + facet normal -0.00592695 -0.00267558 0.999979 + outer loop + vertex 229.393 146.242 32.7261 + vertex 211.44 153.028 32.6378 + vertex 212.437 143.944 32.6194 + endloop + endfacet + facet normal -0.00606082 -0.00168789 0.99998 + outer loop + vertex 229.393 146.242 32.7261 + vertex 212.437 143.944 32.6194 + vertex 230.393 137.242 32.717 + endloop + endfacet + facet normal -0.00536319 -0.00161041 0.999984 + outer loop + vertex 247.433 139.711 32.8123 + vertex 229.393 146.242 32.7261 + vertex 230.393 137.242 32.717 + endloop + endfacet + facet normal -0.00549621 -0.00197785 0.999983 + outer loop + vertex 246.457 148.713 32.8248 + vertex 229.393 146.242 32.7261 + vertex 247.433 139.711 32.8123 + endloop + endfacet + facet normal -0.0043515 -0.00185374 0.999989 + outer loop + vertex 264.398 142.3 32.8909 + vertex 246.457 148.713 32.8248 + vertex 247.433 139.711 32.8123 + endloop + endfacet + facet normal -0.00440796 -0.00148383 0.999989 + outer loop + vertex 264.398 142.3 32.8909 + vertex 247.433 139.711 32.8123 + vertex 265.382 133.314 32.882 + endloop + endfacet + facet normal -0.00278813 -0.00130641 0.999995 + outer loop + vertex 282.05 135.924 32.9318 + vertex 264.398 142.3 32.8909 + vertex 265.382 133.314 32.882 + endloop + endfacet + facet normal -0.00276878 -0.00125285 0.999995 + outer loop + vertex 281.041 144.896 32.9403 + vertex 264.398 142.3 32.8909 + vertex 282.05 135.924 32.9318 + endloop + endfacet + facet normal -0.00222689 -0.00119189 0.999997 + outer loop + vertex 298.217 138.475 32.9709 + vertex 281.041 144.896 32.9403 + vertex 282.05 135.924 32.9318 + endloop + endfacet + facet normal -0.00227741 -0.000871702 0.999997 + outer loop + vertex 298.217 138.475 32.9709 + vertex 282.05 135.924 32.9318 + vertex 299.28 129.48 32.9655 + endloop + endfacet + facet normal -0.00193801 -0.000419064 0.999998 + outer loop + vertex 297.116 147.417 32.9725 + vertex 281.041 144.896 32.9403 + vertex 298.217 138.475 32.9709 + endloop + endfacet + facet normal -0.00607361 -0.000928232 0.999981 + outer loop + vertex 313.776 141.024 33.0677 + vertex 297.116 147.417 32.9725 + vertex 298.217 138.475 32.9709 + endloop + endfacet + facet normal -0.00604122 -0.0011259 0.999981 + outer loop + vertex 313.776 141.024 33.0677 + vertex 298.217 138.475 32.9709 + vertex 314.957 132.056 33.0648 + endloop + endfacet + facet normal -0.00573554 -4.71822e-05 0.999984 + outer loop + vertex 312.569 149.949 33.0612 + vertex 297.116 147.417 32.9725 + vertex 313.776 141.024 33.0677 + endloop + endfacet + facet normal -0.0182796 -0.0017442 0.999831 + outer loop + vertex 328.871 143.821 33.3486 + vertex 312.569 149.949 33.0612 + vertex 313.776 141.024 33.0677 + endloop + endfacet + facet normal -0.0181342 -0.00252896 0.999832 + outer loop + vertex 328.871 143.821 33.3486 + vertex 313.776 141.024 33.0677 + vertex 330.188 134.871 33.3499 + endloop + endfacet + facet normal -0.0182189 -0.00158253 0.999833 + outer loop + vertex 327.587 152.76 33.3394 + vertex 312.569 149.949 33.0612 + vertex 328.871 143.821 33.3486 + endloop + endfacet + facet normal -0.0392628 -0.00460371 0.999218 + outer loop + vertex 343.717 147.142 33.9473 + vertex 327.587 152.76 33.3394 + vertex 328.871 143.821 33.3486 + endloop + endfacet + facet normal -0.0390034 -0.0057646 0.999222 + outer loop + vertex 343.717 147.142 33.9473 + vertex 328.871 143.821 33.3486 + vertex 345.165 138.189 33.9521 + endloop + endfacet + facet normal -0.0394829 -0.00523679 0.999207 + outer loop + vertex 342.38 156.092 33.9414 + vertex 327.587 152.76 33.3394 + vertex 343.717 147.142 33.9473 + endloop + endfacet + facet normal -0.0644704 -0.00896934 0.997879 + outer loop + vertex 358.321 151.004 34.9255 + vertex 342.38 156.092 33.9414 + vertex 343.717 147.142 33.9473 + endloop + endfacet + facet normal -0.064054 -0.0105466 0.997891 + outer loop + vertex 358.321 151.004 34.9255 + vertex 343.717 147.142 33.9473 + vertex 359.896 142.052 34.932 + endloop + endfacet + facet normal -0.091293 -0.0153408 0.995706 + outer loop + vertex 358.321 151.004 34.9255 + vertex 359.896 142.052 34.932 + vertex 368.607 146.327 35.7966 + endloop + endfacet + facet normal -0.0933754 -0.0199723 0.995431 + outer loop + vertex 369.103 150.771 35.9322 + vertex 358.321 151.004 34.9255 + vertex 368.607 146.327 35.7966 + endloop + endfacet + facet normal -0.133707 -0.0153356 0.990902 + outer loop + vertex 375.699 148.218 36.7827 + vertex 369.103 150.771 35.9322 + vertex 368.607 146.327 35.7966 + endloop + endfacet + facet normal -0.130847 -0.0261432 0.991058 + outer loop + vertex 375.699 148.218 36.7827 + vertex 368.607 146.327 35.7966 + vertex 376.589 143.7 36.781 + endloop + endfacet + facet normal -0.183336 -0.0364808 0.982373 + outer loop + vertex 382.246 145.212 37.893 + vertex 375.699 148.218 36.7827 + vertex 376.589 143.7 36.781 + endloop + endfacet + facet normal -0.183374 -0.0363345 0.982371 + outer loop + vertex 382.246 145.212 37.893 + vertex 376.589 143.7 36.781 + vertex 383.156 140.636 37.8936 + endloop + endfacet + facet normal -0.241844 -0.0479668 0.969129 + outer loop + vertex 388.138 141.758 39.1924 + vertex 382.246 145.212 37.893 + vertex 383.156 140.636 37.8936 + endloop + endfacet + facet normal -0.241558 -0.0492486 0.969136 + outer loop + vertex 388.138 141.758 39.1924 + vertex 383.156 140.636 37.8936 + vertex 389.076 137.191 39.194 + endloop + endfacet + facet normal -0.241249 -0.0486788 0.969242 + outer loop + vertex 389.076 137.191 39.194 + vertex 383.156 140.636 37.8936 + vertex 384.075 136.066 37.8927 + endloop + endfacet + facet normal -0.243241 -0.0505301 0.968649 + outer loop + vertex 387.197 146.321 39.1942 + vertex 382.246 145.212 37.893 + vertex 388.138 141.758 39.1924 + endloop + endfacet + facet normal -0.243447 -0.0496072 0.968645 + outer loop + vertex 387.197 146.321 39.1942 + vertex 381.335 149.717 37.8947 + vertex 382.246 145.212 37.893 + endloop + endfacet + facet normal -0.243161 -0.0490748 0.968744 + outer loop + vertex 386.277 150.829 39.1916 + vertex 381.335 149.717 37.8947 + vertex 387.197 146.321 39.1942 + endloop + endfacet + facet normal -0.242906 -0.0502125 0.968749 + outer loop + vertex 386.277 150.829 39.1916 + vertex 380.426 154.128 37.8954 + vertex 381.335 149.717 37.8947 + endloop + endfacet + facet normal -0.243306 -0.0509779 0.968609 + outer loop + vertex 385.353 155.241 39.1916 + vertex 380.426 154.128 37.8954 + vertex 386.277 150.829 39.1916 + endloop + endfacet + facet normal -0.243586 -0.0497347 0.968603 + outer loop + vertex 385.353 155.241 39.1916 + vertex 379.522 158.472 37.8911 + vertex 380.426 154.128 37.8954 + endloop + endfacet + facet normal -0.244641 -0.0517903 0.96823 + outer loop + vertex 384.422 159.581 39.1885 + vertex 379.522 158.472 37.8911 + vertex 385.353 155.241 39.1916 + endloop + endfacet + facet normal -0.244904 -0.0506218 0.968225 + outer loop + vertex 384.422 159.581 39.1885 + vertex 378.61 162.793 37.8864 + vertex 379.522 158.472 37.8911 + endloop + endfacet + facet normal -0.246238 -0.0532283 0.967747 + outer loop + vertex 383.478 163.897 39.1858 + vertex 378.61 162.793 37.8864 + vertex 384.422 159.581 39.1885 + endloop + endfacet + facet normal -0.246546 -0.0518648 0.967742 + outer loop + vertex 383.478 163.897 39.1858 + vertex 377.713 167.156 37.8916 + vertex 378.61 162.793 37.8864 + endloop + endfacet + facet normal -0.247681 -0.054036 0.967333 + outer loop + vertex 382.54 168.253 39.189 + vertex 377.713 167.156 37.8916 + vertex 383.478 163.897 39.1858 + endloop + endfacet + facet normal -0.248952 -0.0484116 0.967305 + outer loop + vertex 382.54 168.253 39.189 + vertex 376.892 171.607 37.9032 + vertex 377.713 167.156 37.8916 + endloop + endfacet + facet normal -0.251109 -0.0523374 0.966543 + outer loop + vertex 381.649 172.688 39.1976 + vertex 376.892 171.607 37.9032 + vertex 382.54 168.253 39.189 + endloop + endfacet + facet normal -0.253441 -0.0419574 0.966441 + outer loop + vertex 381.649 172.688 39.1976 + vertex 376.171 176.138 37.9108 + vertex 376.892 171.607 37.9032 + endloop + endfacet + facet normal -0.256608 -0.0473916 0.965353 + outer loop + vertex 380.834 177.195 39.2022 + vertex 376.171 176.138 37.9108 + vertex 381.649 172.688 39.1976 + endloop + endfacet + facet normal -0.258212 -0.0401911 0.965252 + outer loop + vertex 380.834 177.195 39.2022 + vertex 375.469 180.702 37.9131 + vertex 376.171 176.138 37.9108 + endloop + endfacet + facet normal -0.260167 -0.0434262 0.964587 + outer loop + vertex 380.077 181.726 39.202 + vertex 375.469 180.702 37.9131 + vertex 380.834 177.195 39.2022 + endloop + endfacet + facet normal -0.260595 -0.0414622 0.964557 + outer loop + vertex 380.077 181.726 39.202 + vertex 374.772 185.282 37.9216 + vertex 375.469 180.702 37.9131 + endloop + endfacet + facet normal -0.262078 -0.0438577 0.96405 + outer loop + vertex 379.308 186.255 39.1991 + vertex 374.772 185.282 37.9216 + vertex 380.077 181.726 39.202 + endloop + endfacet + facet normal -0.261185 -0.0480736 0.964091 + outer loop + vertex 379.308 186.255 39.1991 + vertex 373.934 189.87 37.9234 + vertex 374.772 185.282 37.9216 + endloop + endfacet + facet normal -0.253944 -0.036448 0.966532 + outer loop + vertex 378.534 190.852 39.169 + vertex 373.934 189.87 37.9234 + vertex 379.308 186.255 39.1991 + endloop + endfacet + facet normal -0.182897 -0.0352651 0.982499 + outer loop + vertex 383.156 140.636 37.8936 + vertex 376.589 143.7 36.781 + vertex 377.473 139.122 36.7813 + endloop + endfacet + facet normal -0.183804 -0.0375492 0.982245 + outer loop + vertex 381.335 149.717 37.8947 + vertex 375.699 148.218 36.7827 + vertex 382.246 145.212 37.893 + endloop + endfacet + facet normal -0.18406 -0.0365788 0.982234 + outer loop + vertex 381.335 149.717 37.8947 + vertex 374.818 152.646 36.7825 + vertex 375.699 148.218 36.7827 + endloop + endfacet + facet normal -0.184771 -0.0382346 0.982038 + outer loop + vertex 380.426 154.128 37.8954 + vertex 374.818 152.646 36.7825 + vertex 381.335 149.717 37.8947 + endloop + endfacet + facet normal -0.185418 -0.0357635 0.982009 + outer loop + vertex 380.426 154.128 37.8954 + vertex 373.948 157.005 36.7771 + vertex 374.818 152.646 36.7825 + endloop + endfacet + facet normal -0.13215 -0.0251222 0.990911 + outer loop + vertex 373.948 157.005 36.7771 + vertex 366.935 155.186 35.7956 + vertex 374.818 152.646 36.7825 + endloop + endfacet + facet normal -0.135533 -0.0359302 0.990121 + outer loop + vertex 374.818 152.646 36.7825 + vertex 366.935 155.186 35.7956 + vertex 369.103 150.771 35.9322 + endloop + endfacet + facet normal -0.134745 -0.0150382 0.990766 + outer loop + vertex 373.948 157.005 36.7771 + vertex 367.434 159.518 35.9293 + vertex 366.935 155.186 35.7956 + endloop + endfacet + facet normal -0.0952724 -0.0197295 0.995256 + outer loop + vertex 367.434 159.518 35.9293 + vertex 356.871 159.884 34.9254 + vertex 366.935 155.186 35.7956 + endloop + endfacet + facet normal -0.0931843 -0.0152052 0.995533 + outer loop + vertex 356.871 159.884 34.9254 + vertex 358.321 151.004 34.9255 + vertex 366.935 155.186 35.7956 + endloop + endfacet + facet normal -0.0950884 -0.0141103 0.995369 + outer loop + vertex 367.434 159.518 35.9293 + vertex 365.373 163.961 35.7954 + vertex 356.871 159.884 34.9254 + endloop + endfacet + facet normal -0.0947422 -0.0148371 0.995391 + outer loop + vertex 355.621 168.833 34.9398 + vertex 356.871 159.884 34.9254 + vertex 365.373 163.961 35.7954 + endloop + endfacet + facet normal -0.0971418 -0.0196958 0.995076 + outer loop + vertex 365.96 168.367 35.9399 + vertex 355.621 168.833 34.9398 + vertex 365.373 163.961 35.7954 + endloop + endfacet + facet normal -0.138035 -0.0140974 0.990327 + outer loop + vertex 372.239 165.713 36.7773 + vertex 365.96 168.367 35.9399 + vertex 365.373 163.961 35.7954 + endloop + endfacet + facet normal -0.135034 -0.0259545 0.990501 + outer loop + vertex 372.239 165.713 36.7773 + vertex 365.373 163.961 35.7954 + vertex 373.073 161.336 36.7763 + endloop + endfacet + facet normal -0.187345 -0.0359149 0.981637 + outer loop + vertex 378.61 162.793 37.8864 + vertex 372.239 165.713 36.7773 + vertex 373.073 161.336 36.7763 + endloop + endfacet + facet normal -0.186714 -0.0383334 0.981666 + outer loop + vertex 378.61 162.793 37.8864 + vertex 373.073 161.336 36.7763 + vertex 379.522 158.472 37.8911 + endloop + endfacet + facet normal -0.186357 -0.0374901 0.981767 + outer loop + vertex 379.522 158.472 37.8911 + vertex 373.073 161.336 36.7763 + vertex 373.948 157.005 36.7771 + endloop + endfacet + facet normal -0.189162 -0.0400736 0.981128 + outer loop + vertex 377.713 167.156 37.8916 + vertex 372.239 165.713 36.7773 + vertex 378.61 162.793 37.8864 + endloop + endfacet + facet normal -0.190682 -0.0342504 0.981054 + outer loop + vertex 377.713 167.156 37.8916 + vertex 371.493 170.175 36.7881 + vertex 372.239 165.713 36.7773 + endloop + endfacet + facet normal -0.192431 -0.0380303 0.980573 + outer loop + vertex 376.892 171.607 37.9032 + vertex 371.493 170.175 36.7881 + vertex 377.713 167.156 37.8916 + endloop + endfacet + facet normal -0.194284 -0.0309536 0.980457 + outer loop + vertex 376.892 171.607 37.9032 + vertex 370.838 174.713 36.8015 + vertex 371.493 170.175 36.7881 + endloop + endfacet + facet normal -0.13828 -0.022894 0.990129 + outer loop + vertex 370.838 174.713 36.8015 + vertex 364.062 172.927 35.8139 + vertex 371.493 170.175 36.7881 + endloop + endfacet + facet normal -0.141383 -0.0315101 0.989453 + outer loop + vertex 371.493 170.175 36.7881 + vertex 364.062 172.927 35.8139 + vertex 365.96 168.367 35.9399 + endloop + endfacet + facet normal -0.141538 -0.0103913 0.989878 + outer loop + vertex 370.838 174.713 36.8015 + vertex 364.693 177.414 35.9512 + vertex 364.062 172.927 35.8139 + endloop + endfacet + facet normal -0.145835 -0.0204134 0.989098 + outer loop + vertex 370.162 179.284 36.7963 + vertex 364.693 177.414 35.9512 + vertex 370.838 174.713 36.8015 + endloop + endfacet + facet normal -0.196401 -0.0278933 0.980127 + outer loop + vertex 376.171 176.138 37.9108 + vertex 370.162 179.284 36.7963 + vertex 370.838 174.713 36.8015 + endloop + endfacet + facet normal -0.197917 -0.0309286 0.979731 + outer loop + vertex 375.469 180.702 37.9131 + vertex 370.162 179.284 36.7963 + vertex 376.171 176.138 37.9108 + endloop + endfacet + facet normal -0.197656 -0.0319195 0.979752 + outer loop + vertex 375.469 180.702 37.9131 + vertex 369.426 184.009 36.8018 + vertex 370.162 179.284 36.7963 + endloop + endfacet + facet normal -0.139453 -0.0228672 0.989965 + outer loop + vertex 369.426 184.009 36.8018 + vertex 362.473 181.941 35.7745 + vertex 370.162 179.284 36.7963 + endloop + endfacet + facet normal -0.144186 -0.00674097 0.989528 + outer loop + vertex 369.426 184.009 36.8018 + vertex 363.686 187.743 35.9907 + vertex 362.473 181.941 35.7745 + endloop + endfacet + facet normal -0.158165 -0.0287895 0.986993 + outer loop + vertex 368.997 188.836 36.8737 + vertex 363.686 187.743 35.9907 + vertex 369.426 184.009 36.8018 + endloop + endfacet + facet normal -0.197583 -0.0321899 0.979757 + outer loop + vertex 374.772 185.282 37.9216 + vertex 368.997 188.836 36.8737 + vertex 369.426 184.009 36.8018 + endloop + endfacet + facet normal -0.200397 -0.0369801 0.979017 + outer loop + vertex 373.934 189.87 37.9234 + vertex 368.997 188.836 36.8737 + vertex 374.772 185.282 37.9216 + endloop + endfacet + facet normal -0.19765 -0.0319074 0.979753 + outer loop + vertex 374.772 185.282 37.9216 + vertex 369.426 184.009 36.8018 + vertex 375.469 180.702 37.9131 + endloop + endfacet + facet normal -0.142217 -0.031106 0.989347 + outer loop + vertex 370.162 179.284 36.7963 + vertex 362.473 181.941 35.7745 + vertex 364.693 177.414 35.9512 + endloop + endfacet + facet normal -0.195138 -0.0326992 0.980231 + outer loop + vertex 376.171 176.138 37.9108 + vertex 370.838 174.713 36.8015 + vertex 376.892 171.607 37.9032 + endloop + endfacet + facet normal -0.143068 -0.0263096 0.989363 + outer loop + vertex 371.493 170.175 36.7881 + vertex 365.96 168.367 35.9399 + vertex 372.239 165.713 36.7773 + endloop + endfacet + facet normal -0.0968451 -0.012814 0.995217 + outer loop + vertex 365.96 168.367 35.9399 + vertex 364.062 172.927 35.8139 + vertex 355.621 168.833 34.9398 + endloop + endfacet + facet normal -0.0966659 -0.0131863 0.99523 + outer loop + vertex 354.15 177.641 34.9137 + vertex 355.621 168.833 34.9398 + vertex 364.062 172.927 35.8139 + endloop + endfacet + facet normal -0.0982853 -0.0166315 0.995019 + outer loop + vertex 364.693 177.414 35.9512 + vertex 354.15 177.641 34.9137 + vertex 364.062 172.927 35.8139 + endloop + endfacet + facet normal -0.0981371 -0.00927082 0.99513 + outer loop + vertex 364.693 177.414 35.9512 + vertex 362.473 181.941 35.7745 + vertex 354.15 177.641 34.9137 + endloop + endfacet + facet normal -0.103879 0.00195324 0.994588 + outer loop + vertex 351.489 185.298 34.6207 + vertex 354.15 177.641 34.9137 + vertex 362.473 181.941 35.7745 + endloop + endfacet + facet normal -0.108781 -0.0143029 0.993963 + outer loop + vertex 363.686 187.743 35.9907 + vertex 351.489 185.298 34.6207 + vertex 362.473 181.941 35.7745 + endloop + endfacet + facet normal -0.0655031 0.0154108 0.997733 + outer loop + vertex 351.489 185.298 34.6207 + vertex 338.248 182.736 33.791 + vertex 354.15 177.641 34.9137 + endloop + endfacet + facet normal -0.0687964 0.00510439 0.997618 + outer loop + vertex 354.15 177.641 34.9137 + vertex 338.248 182.736 33.791 + vertex 340.199 174.189 33.9692 + endloop + endfacet + facet normal -0.034589 0.012948 0.999318 + outer loop + vertex 338.248 182.736 33.791 + vertex 324.675 180.2 33.354 + vertex 340.199 174.189 33.9692 + endloop + endfacet + facet normal -0.0406908 -0.00282619 0.999168 + outer loop + vertex 340.199 174.189 33.9692 + vertex 324.675 180.2 33.354 + vertex 325.702 171.03 33.3699 + endloop + endfacet + facet normal -0.0398696 -0.00659645 0.999183 + outer loop + vertex 340.199 174.189 33.9692 + vertex 325.702 171.03 33.3699 + vertex 341.289 165.136 33.953 + endloop + endfacet + facet normal -0.0661843 -0.00976501 0.99776 + outer loop + vertex 355.621 168.833 34.9398 + vertex 340.199 174.189 33.9692 + vertex 341.289 165.136 33.953 + endloop + endfacet + facet normal -0.0400889 -0.00717779 0.99917 + outer loop + vertex 341.289 165.136 33.953 + vertex 325.702 171.03 33.3699 + vertex 326.507 161.804 33.3359 + endloop + endfacet + facet normal -0.0403211 -0.00614739 0.999168 + outer loop + vertex 341.289 165.136 33.953 + vertex 326.507 161.804 33.3359 + vertex 342.38 156.092 33.9414 + endloop + endfacet + facet normal -0.0653634 -0.00916639 0.997819 + outer loop + vertex 356.871 159.884 34.9254 + vertex 341.289 165.136 33.953 + vertex 342.38 156.092 33.9414 + endloop + endfacet + facet normal -0.0189007 -0.00533222 0.999807 + outer loop + vertex 325.702 171.03 33.3699 + vertex 310.633 168.141 33.0696 + vertex 326.507 161.804 33.3359 + endloop + endfacet + facet normal -0.0184062 -0.00409288 0.999822 + outer loop + vertex 326.507 161.804 33.3359 + vertex 310.633 168.141 33.0696 + vertex 311.444 158.932 33.0469 + endloop + endfacet + facet normal -0.0188298 -0.00187026 0.999821 + outer loop + vertex 326.507 161.804 33.3359 + vertex 311.444 158.932 33.0469 + vertex 327.587 152.76 33.3394 + endloop + endfacet + facet normal -0.00625903 -0.00302264 0.999976 + outer loop + vertex 310.633 168.141 33.0696 + vertex 295.061 165.473 32.9641 + vertex 311.444 158.932 33.0469 + endloop + endfacet + facet normal -0.00545202 -0.00100088 0.999985 + outer loop + vertex 311.444 158.932 33.0469 + vertex 295.061 165.473 32.9641 + vertex 295.996 156.362 32.9601 + endloop + endfacet + facet normal -0.00576455 0.000877528 0.999983 + outer loop + vertex 311.444 158.932 33.0469 + vertex 295.996 156.362 32.9601 + vertex 312.569 149.949 33.0612 + endloop + endfacet + facet normal -0.00164332 -0.000609985 0.999998 + outer loop + vertex 295.061 165.473 32.9641 + vertex 278.97 162.899 32.9361 + vertex 295.996 156.362 32.9601 + endloop + endfacet + facet normal -0.00131821 0.000236756 0.999999 + outer loop + vertex 295.996 156.362 32.9601 + vertex 278.97 162.899 32.9361 + vertex 279.993 153.852 32.9396 + endloop + endfacet + facet normal -0.00146991 0.00120391 0.999998 + outer loop + vertex 295.996 156.362 32.9601 + vertex 279.993 153.852 32.9396 + vertex 297.116 147.417 32.9725 + endloop + endfacet + facet normal -0.00192437 0.000168216 0.999998 + outer loop + vertex 278.97 162.899 32.9361 + vertex 262.42 160.338 32.9047 + vertex 279.993 153.852 32.9396 + endloop + endfacet + facet normal -0.00222164 -0.000637206 0.999997 + outer loop + vertex 279.993 153.852 32.9396 + vertex 262.42 160.338 32.9047 + vertex 263.411 151.286 32.9011 + endloop + endfacet + facet normal -0.00229098 -0.000189114 0.999997 + outer loop + vertex 279.993 153.852 32.9396 + vertex 263.411 151.286 32.9011 + vertex 281.041 144.896 32.9403 + endloop + endfacet + facet normal -0.00372599 -0.000801875 0.999993 + outer loop + vertex 262.42 160.338 32.9047 + vertex 245.531 157.795 32.8397 + vertex 263.411 151.286 32.9011 + endloop + endfacet + facet normal -0.00418807 -0.00207127 0.999989 + outer loop + vertex 263.411 151.286 32.9011 + vertex 245.531 157.795 32.8397 + vertex 246.457 148.713 32.8248 + endloop + endfacet + facet normal -0.00517333 -0.00217167 0.999984 + outer loop + vertex 245.531 157.795 32.8397 + vertex 228.504 155.34 32.7463 + vertex 246.457 148.713 32.8248 + endloop + endfacet + facet normal -0.00493676 -0.00381234 0.999981 + outer loop + vertex 245.531 157.795 32.8397 + vertex 227.695 164.584 32.7775 + vertex 228.504 155.34 32.7463 + endloop + endfacet + facet normal -0.00508962 -0.00382572 0.99998 + outer loop + vertex 227.695 164.584 32.7775 + vertex 211.121 162.346 32.6846 + vertex 228.504 155.34 32.7463 + endloop + endfacet + facet normal -0.00564859 -0.00521273 0.99997 + outer loop + vertex 228.504 155.34 32.7463 + vertex 211.121 162.346 32.6846 + vertex 211.44 153.028 32.6378 + endloop + endfacet + facet normal -0.00584407 -0.00521942 0.999969 + outer loop + vertex 211.121 162.346 32.6846 + vertex 193.041 160.068 32.5671 + vertex 211.44 153.028 32.6378 + endloop + endfacet + facet normal -0.00452583 -0.0027327 0.999986 + outer loop + vertex 244.861 167.038 32.8619 + vertex 227.695 164.584 32.7775 + vertex 245.531 157.795 32.8397 + endloop + endfacet + facet normal -0.00344698 -0.00265451 0.999991 + outer loop + vertex 262.42 160.338 32.9047 + vertex 244.861 167.038 32.8619 + vertex 245.531 157.795 32.8397 + endloop + endfacet + facet normal -0.0038206 -0.00363365 0.999986 + outer loop + vertex 261.481 169.541 32.9345 + vertex 244.861 167.038 32.8619 + vertex 262.42 160.338 32.9047 + endloop + endfacet + facet normal -0.00137468 -0.00338399 0.999993 + outer loop + vertex 278.97 162.899 32.9361 + vertex 261.481 169.541 32.9345 + vertex 262.42 160.338 32.9047 + endloop + endfacet + facet normal -0.0028114 -0.00716743 0.99997 + outer loop + vertex 278.491 172.228 33.0016 + vertex 261.481 169.541 32.9345 + vertex 278.97 162.899 32.9361 + endloop + endfacet + facet normal -0.000612545 -0.00705456 0.999975 + outer loop + vertex 295.061 165.473 32.9641 + vertex 278.491 172.228 33.0016 + vertex 278.97 162.899 32.9361 + endloop + endfacet + facet normal -0.00194154 -0.0103142 0.999945 + outer loop + vertex 294.726 174.915 33.0608 + vertex 278.491 172.228 33.0016 + vertex 295.061 165.473 32.9641 + endloop + endfacet + facet normal -0.00499076 -0.010422 0.999933 + outer loop + vertex 310.633 168.141 33.0696 + vertex 294.726 174.915 33.0608 + vertex 295.061 165.473 32.9641 + endloop + endfacet + facet normal -0.00410201 -0.0083351 0.999957 + outer loop + vertex 310.379 177.624 33.1476 + vertex 294.726 174.915 33.0608 + vertex 310.633 168.141 33.0696 + endloop + endfacet + facet normal -0.0182526 -0.00871236 0.999795 + outer loop + vertex 325.702 171.03 33.3699 + vertex 310.379 177.624 33.1476 + vertex 310.633 168.141 33.0696 + endloop + endfacet + facet normal -0.0144558 0.000113075 0.999896 + outer loop + vertex 324.675 180.2 33.354 + vertex 310.379 177.624 33.1476 + vertex 325.702 171.03 33.3699 + endloop + endfacet + facet normal -0.0655706 -0.00798767 0.997816 + outer loop + vertex 354.15 177.641 34.9137 + vertex 340.199 174.189 33.9692 + vertex 355.621 168.833 34.9398 + endloop + endfacet + facet normal -0.0659148 -0.0108118 0.997767 + outer loop + vertex 355.621 168.833 34.9398 + vertex 341.289 165.136 33.953 + vertex 356.871 159.884 34.9254 + endloop + endfacet + facet normal -0.137715 -0.0340477 0.989887 + outer loop + vertex 373.073 161.336 36.7763 + vertex 365.373 163.961 35.7954 + vertex 367.434 159.518 35.9293 + endloop + endfacet + facet normal -0.139638 -0.0280463 0.989805 + outer loop + vertex 373.073 161.336 36.7763 + vertex 367.434 159.518 35.9293 + vertex 373.948 157.005 36.7771 + endloop + endfacet + facet normal -0.186278 -0.0377927 0.98177 + outer loop + vertex 379.522 158.472 37.8911 + vertex 373.948 157.005 36.7771 + vertex 380.426 154.128 37.8954 + endloop + endfacet + facet normal -0.133479 -0.034363 0.990456 + outer loop + vertex 376.589 143.7 36.781 + vertex 368.607 146.327 35.7966 + vertex 370.806 141.777 35.9351 + endloop + endfacet + facet normal -0.138291 -0.0274759 0.99001 + outer loop + vertex 374.818 152.646 36.7825 + vertex 369.103 150.771 35.9322 + vertex 375.699 148.218 36.7827 + endloop + endfacet + facet normal -0.0932772 -0.0150126 0.995527 + outer loop + vertex 369.103 150.771 35.9322 + vertex 366.935 155.186 35.7956 + vertex 358.321 151.004 34.9255 + endloop + endfacet + facet normal -0.0649884 -0.010602 0.99783 + outer loop + vertex 356.871 159.884 34.9254 + vertex 342.38 156.092 33.9414 + vertex 358.321 151.004 34.9255 + endloop + endfacet + facet normal -0.0396799 -0.00436171 0.999203 + outer loop + vertex 342.38 156.092 33.9414 + vertex 326.507 161.804 33.3359 + vertex 327.587 152.76 33.3394 + endloop + endfacet + facet normal -0.0183835 -0.000702546 0.999831 + outer loop + vertex 327.587 152.76 33.3394 + vertex 311.444 158.932 33.0469 + vertex 312.569 149.949 33.0612 + endloop + endfacet + facet normal -0.00585063 0.00065505 0.999983 + outer loop + vertex 312.569 149.949 33.0612 + vertex 295.996 156.362 32.9601 + vertex 297.116 147.417 32.9725 + endloop + endfacet + facet normal -0.00197977 -0.000152722 0.999998 + outer loop + vertex 297.116 147.417 32.9725 + vertex 279.993 153.852 32.9396 + vertex 281.041 144.896 32.9403 + endloop + endfacet + facet normal -0.00274103 -0.00143076 0.999995 + outer loop + vertex 281.041 144.896 32.9403 + vertex 263.411 151.286 32.9011 + vertex 264.398 142.3 32.8909 + endloop + endfacet + facet normal -0.00425996 -0.00159761 0.99999 + outer loop + vertex 263.411 151.286 32.9011 + vertex 246.457 148.713 32.8248 + vertex 264.398 142.3 32.8909 + endloop + endfacet + facet normal -0.00538507 -0.00274533 0.999982 + outer loop + vertex 246.457 148.713 32.8248 + vertex 228.504 155.34 32.7463 + vertex 229.393 146.242 32.7261 + endloop + endfacet + facet normal -0.00597509 -0.00280295 0.999978 + outer loop + vertex 228.504 155.34 32.7463 + vertex 211.44 153.028 32.6378 + vertex 229.393 146.242 32.7261 + endloop + endfacet + facet normal -0.00613379 -0.00597675 0.999963 + outer loop + vertex 211.44 153.028 32.6378 + vertex 193.041 160.068 32.5671 + vertex 194.745 150.927 32.5229 + endloop + endfacet + facet normal -0.00686316 -0.00611276 0.999958 + outer loop + vertex 193.041 160.068 32.5671 + vertex 178.097 158.332 32.4539 + vertex 194.745 150.927 32.5229 + endloop + endfacet + facet normal 0.00825779 -0.0022301 0.999963 + outer loop + vertex -162.226 147.318 32.2645 + vertex -178.239 149.019 32.4006 + vertex -163.143 138.238 32.2519 + endloop + endfacet + facet normal 0.00890217 -0.00229522 0.999958 + outer loop + vertex -147.428 136.712 32.1084 + vertex -162.226 147.318 32.2645 + vertex -163.143 138.238 32.2519 + endloop + endfacet + facet normal 0.00944926 -0.0021916 0.999953 + outer loop + vertex -132.092 135.351 31.9605 + vertex -146.551 145.8 32.1201 + vertex -147.428 136.712 32.1084 + endloop + endfacet + facet normal 0.00967138 -0.00204926 0.999951 + outer loop + vertex -117.095 134.117 31.813 + vertex -131.326 144.449 31.9718 + vertex -132.092 135.351 31.9605 + endloop + endfacet + facet normal 0.00953666 -0.00187007 0.999953 + outer loop + vertex -102.337 132.971 31.6701 + vertex -116.399 143.22 31.8234 + vertex -117.095 134.117 31.813 + endloop + endfacet + facet normal 0.00897433 -0.0017179 0.999958 + outer loop + vertex -87.7102 131.894 31.537 + vertex -101.755 142.085 31.6805 + vertex -102.337 132.971 31.6701 + endloop + endfacet + facet normal 0.00817783 -0.00151289 0.999965 + outer loop + vertex -73.1153 130.873 31.416 + vertex -87.2521 141.014 31.547 + vertex -87.7102 131.894 31.537 + endloop + endfacet + facet normal 0.00710183 -0.00137746 0.999974 + outer loop + vertex -58.511 129.933 31.311 + vertex -72.7213 139.995 31.4258 + vertex -73.1153 130.873 31.416 + endloop + endfacet + facet normal 0.00582658 -0.00125066 0.999982 + outer loop + vertex -43.8972 129.116 31.2249 + vertex -58.1992 139.055 31.3206 + vertex -58.511 129.933 31.311 + endloop + endfacet + facet normal 0.00436974 -0.00113993 0.99999 + outer loop + vertex -29.2871 128.473 31.1603 + vertex -43.679 138.238 31.2343 + vertex -43.8972 129.116 31.2249 + endloop + endfacet + facet normal 0.0027219 -0.00106363 0.999996 + outer loop + vertex -14.6828 128.06 31.1201 + vertex -29.1453 137.596 31.1696 + vertex -29.2871 128.473 31.1603 + endloop + endfacet + facet normal 0.000916416 -0.00101416 0.999999 + outer loop + vertex -0.0692545 127.916 31.1066 + vertex -14.6069 137.182 31.1293 + vertex -14.6828 128.06 31.1201 + endloop + endfacet + facet normal -0.000917446 -0.000961624 0.999999 + outer loop + vertex 14.5699 128.053 31.1201 + vertex -0.057923 137.035 31.1153 + vertex -0.0692545 127.916 31.1066 + endloop + endfacet + facet normal -0.00271109 -0.000954178 0.999996 + outer loop + vertex 29.2408 128.463 31.1603 + vertex 14.4797 137.171 31.1286 + vertex 14.5699 128.053 31.1201 + endloop + endfacet + facet normal -0.00433281 -0.00108141 0.99999 + outer loop + vertex 43.9081 129.101 31.2245 + vertex 29.1198 137.59 31.1696 + vertex 29.2408 128.463 31.1603 + endloop + endfacet + facet normal -0.00585414 -0.00115394 0.999982 + outer loop + vertex 58.5375 129.924 31.3111 + vertex 43.6683 138.226 31.2337 + vertex 43.9081 129.101 31.2245 + endloop + endfacet + facet normal -0.00706885 -0.00122238 0.999974 + outer loop + vertex 73.1547 130.865 31.4156 + vertex 58.2028 139.044 31.3199 + vertex 58.5375 129.924 31.3111 + endloop + endfacet + facet normal -0.00818593 -0.00139051 0.999966 + outer loop + vertex 87.8123 131.898 31.537 + vertex 72.8501 139.994 31.4258 + vertex 73.1547 130.865 31.4156 + endloop + endfacet + facet normal -0.0090093 -0.00150673 0.999958 + outer loop + vertex 102.582 132.995 31.6717 + vertex 87.3218 141.014 31.5463 + vertex 87.8123 131.898 31.537 + endloop + endfacet + facet normal -0.00955819 -0.00173281 0.999953 + outer loop + vertex 117.526 134.16 31.8166 + vertex 101.975 142.107 31.6817 + vertex 102.582 132.995 31.6717 + endloop + endfacet + facet normal -0.00974729 -0.0018603 0.999951 + outer loop + vertex 132.643 135.407 31.9663 + vertex 116.852 143.264 31.827 + vertex 117.526 134.16 31.8166 + endloop + endfacet + facet normal -0.00953695 -0.00195981 0.999953 + outer loop + vertex 147.953 136.767 32.115 + vertex 131.858 144.501 31.9766 + vertex 132.643 135.407 31.9663 + endloop + endfacet + facet normal -0.00891788 -0.00198445 0.999958 + outer loop + vertex 163.514 138.27 32.2567 + vertex 147.122 145.854 32.1256 + vertex 147.953 136.767 32.115 + endloop + endfacet + facet normal -0.00803521 -0.00198164 0.999966 + outer loop + vertex 179.432 139.958 32.388 + vertex 162.565 147.35 32.2671 + vertex 163.514 138.27 32.2567 + endloop + endfacet + facet normal -0.00710852 -0.00209173 0.999973 + outer loop + vertex 195.752 141.847 32.5079 + vertex 178.474 149.042 32.4002 + vertex 179.432 139.958 32.388 + endloop + endfacet + facet normal -0.00652436 -0.00125365 0.999978 + outer loop + vertex 212.437 143.944 32.6194 + vertex 195.752 141.847 32.5079 + vertex 213.465 134.954 32.6149 + endloop + endfacet + facet normal -0.00587086 -0.00117896 0.999982 + outer loop + vertex 230.393 137.242 32.717 + vertex 212.437 143.944 32.6194 + vertex 213.465 134.954 32.6149 + endloop + endfacet + facet normal -0.00541168 -0.00127576 0.999985 + outer loop + vertex 247.433 139.711 32.8123 + vertex 230.393 137.242 32.717 + vertex 248.423 130.727 32.8062 + endloop + endfacet + facet normal -0.00428975 -0.00115213 0.99999 + outer loop + vertex 265.382 133.314 32.882 + vertex 247.433 139.711 32.8123 + vertex 248.423 130.727 32.8062 + endloop + endfacet + facet normal -0.00284608 -0.000936324 0.999996 + outer loop + vertex 282.05 135.924 32.9318 + vertex 265.382 133.314 32.882 + vertex 283.056 126.912 32.9263 + endloop + endfacet + facet normal -0.00227785 -0.000872861 0.999997 + outer loop + vertex 299.28 129.48 32.9655 + vertex 282.05 135.924 32.9318 + vertex 283.056 126.912 32.9263 + endloop + endfacet + facet normal -0.00611775 -0.00132547 0.99998 + outer loop + vertex 314.957 132.056 33.0648 + vertex 298.217 138.475 32.9709 + vertex 299.28 129.48 32.9655 + endloop + endfacet + facet normal -0.0182088 -0.00272782 0.99983 + outer loop + vertex 330.188 134.871 33.3499 + vertex 313.776 141.024 33.0677 + vertex 314.957 132.056 33.0648 + endloop + endfacet + facet normal -0.0389442 -0.00559304 0.999226 + outer loop + vertex 345.165 138.189 33.9521 + vertex 328.871 143.821 33.3486 + vertex 330.188 134.871 33.3499 + endloop + endfacet + facet normal -0.0638131 -0.00977662 0.997914 + outer loop + vertex 359.896 142.052 34.932 + vertex 343.717 147.142 33.9473 + vertex 345.165 138.189 33.9521 + endloop + endfacet + facet normal -0.0918952 -0.0141063 0.995669 + outer loop + vertex 370.806 141.777 35.9351 + vertex 368.607 146.327 35.7966 + vertex 359.896 142.052 34.932 + endloop + endfacet + facet normal -0.136164 -0.026236 0.990339 + outer loop + vertex 376.589 143.7 36.781 + vertex 370.806 141.777 35.9351 + vertex 377.473 139.122 36.7813 + endloop + endfacet + facet normal -0.182473 -0.0368711 0.982519 + outer loop + vertex 383.156 140.636 37.8936 + vertex 377.473 139.122 36.7813 + vertex 384.075 136.066 37.8927 + endloop + endfacet + facet normal -0.240793 -0.0507184 0.96925 + outer loop + vertex 389.076 137.191 39.194 + vertex 384.075 136.066 37.8927 + vertex 390.014 132.69 39.1916 + endloop + endfacet + facet normal -0.17889 -0.0362531 0.983201 + outer loop + vertex 386.754 122.768 37.8872 + vertex 380.085 125.653 36.7801 + vertex 380.94 121.267 36.774 + endloop + endfacet + facet normal -0.181487 -0.0363134 0.982723 + outer loop + vertex 384.969 131.557 37.8959 + vertex 379.229 130.066 36.7807 + vertex 385.855 127.138 37.8961 + endloop + endfacet + facet normal -0.134845 -0.0266426 0.990508 + outer loop + vertex 378.354 134.554 36.7822 + vertex 372.51 132.673 35.9361 + vertex 379.229 130.066 36.7807 + endloop + endfacet + facet normal -0.0912209 -0.0137315 0.995736 + outer loop + vertex 372.51 132.673 35.9361 + vertex 370.307 137.247 35.7973 + vertex 361.494 133.031 34.9318 + endloop + endfacet + facet normal -0.0628604 -0.0113664 0.997958 + outer loop + vertex 361.494 133.031 34.9318 + vertex 346.604 129.207 33.9503 + vertex 363.056 124.079 34.9282 + endloop + endfacet + facet normal -0.130981 -0.03306 0.990834 + outer loop + vertex 380.085 125.653 36.7801 + vertex 371.982 128.243 35.7954 + vertex 374.165 123.785 35.9352 + endloop + endfacet + facet normal -0.132797 -0.0272741 0.990768 + outer loop + vertex 380.085 125.653 36.7801 + vertex 374.165 123.785 35.9352 + vertex 380.94 121.267 36.774 + endloop + endfacet + facet normal -0.178085 -0.0393857 0.983227 + outer loop + vertex 386.754 122.768 37.8872 + vertex 380.94 121.267 36.774 + vertex 387.647 118.357 37.8722 + endloop + endfacet + facet normal -0.231184 -0.0581275 0.971172 + outer loop + vertex 392.788 119.501 39.1645 + vertex 387.647 118.357 37.8722 + vertex 393.75 115.034 39.1261 + endloop + endfacet + facet normal -0.172386 -0.0488812 0.983816 + outer loop + vertex 388.575 113.88 37.8366 + vertex 382.682 112.338 36.7275 + vertex 389.516 109.342 37.776 + endloop + endfacet + facet normal -0.124676 -0.0422597 0.991297 + outer loop + vertex 383.582 107.798 36.6712 + vertex 375.28 110.421 35.7389 + vertex 377.523 105.864 35.8266 + endloop + endfacet + facet normal -0.13046 -0.0315934 0.99095 + outer loop + vertex 381.814 116.843 36.7569 + vertex 375.834 114.915 35.9081 + vertex 382.682 112.338 36.7275 + endloop + endfacet + facet normal -0.0890904 -0.0170914 0.995877 + outer loop + vertex 375.834 114.915 35.9081 + vertex 373.618 119.395 35.7867 + vertex 364.607 115.139 34.9076 + endloop + endfacet + facet normal -0.0618041 -0.0130263 0.998003 + outer loop + vertex 363.056 124.079 34.9282 + vertex 348.012 120.225 33.9463 + vertex 364.607 115.139 34.9076 + endloop + endfacet + facet normal -0.0382071 -0.00629594 0.99925 + outer loop + vertex 348.012 120.225 33.9463 + vertex 331.473 125.881 33.3495 + vertex 332.74 116.855 33.3411 + endloop + endfacet + facet normal -0.0178142 -0.00288624 0.999837 + outer loop + vertex 332.74 116.855 33.3411 + vertex 316.109 123.036 33.0626 + vertex 317.264 113.987 33.0571 + endloop + endfacet + facet normal -0.00596227 -0.000985687 0.999982 + outer loop + vertex 317.264 113.987 33.0571 + vertex 300.346 120.439 32.9626 + vertex 301.416 111.376 32.96 + endloop + endfacet + facet normal -0.00221613 -0.000543555 0.999997 + outer loop + vertex 300.346 120.439 32.9626 + vertex 284.068 117.864 32.9251 + vertex 301.416 111.376 32.96 + endloop + endfacet + facet normal -0.00275441 -0.000310183 0.999996 + outer loop + vertex 284.068 117.864 32.9251 + vertex 266.363 124.3 32.8783 + vertex 267.352 115.252 32.8783 + endloop + endfacet + facet normal -0.00423974 -0.000472449 0.999991 + outer loop + vertex 266.363 124.3 32.8783 + vertex 249.411 121.719 32.8052 + vertex 267.352 115.252 32.8783 + endloop + endfacet + facet normal -0.00523476 -0.000543854 0.999986 + outer loop + vertex 249.411 121.719 32.8052 + vertex 231.404 128.266 32.7145 + vertex 232.402 119.264 32.7149 + endloop + endfacet + facet normal -0.00582885 -0.000609663 0.999983 + outer loop + vertex 231.404 128.266 32.7145 + vertex 214.486 125.984 32.6145 + vertex 232.402 119.264 32.7149 + endloop + endfacet + facet normal -0.00640375 -0.000725601 0.999979 + outer loop + vertex 214.486 125.984 32.6145 + vertex 196.781 132.865 32.5061 + vertex 197.801 123.899 32.5062 + endloop + endfacet + facet normal -0.00719025 -0.000780825 0.999974 + outer loop + vertex 197.801 123.899 32.5062 + vertex 180.446 130.979 32.3869 + vertex 181.432 122.008 32.387 + endloop + endfacet + facet normal -0.00813232 -0.000908719 0.999967 + outer loop + vertex 181.432 122.008 32.387 + vertex 164.474 129.284 32.2557 + vertex 165.421 120.315 32.2552 + endloop + endfacet + facet normal -0.00895921 -0.000923384 0.999959 + outer loop + vertex 165.421 120.315 32.2552 + vertex 148.836 127.772 32.1135 + vertex 149.706 118.796 32.113 + endloop + endfacet + facet normal -0.00950723 -0.00086362 0.999954 + outer loop + vertex 149.706 118.796 32.113 + vertex 133.432 126.406 31.9649 + vertex 134.206 117.42 31.9645 + endloop + endfacet + facet normal -0.00969467 -0.000774845 0.999953 + outer loop + vertex 134.206 117.42 31.9645 + vertex 118.206 125.149 31.8154 + vertex 118.887 116.157 31.815 + endloop + endfacet + facet normal -0.00949651 -0.000656447 0.999955 + outer loop + vertex 118.887 116.157 31.815 + vertex 103.163 123.977 31.6708 + vertex 103.749 114.979 31.6704 + endloop + endfacet + facet normal -0.00895868 -0.000510556 0.99996 + outer loop + vertex 103.749 114.979 31.6704 + vertex 88.2922 122.873 31.536 + vertex 88.7887 113.872 31.5359 + endloop + endfacet + facet normal -0.00813355 -0.000379133 0.999967 + outer loop + vertex 88.7887 113.872 31.5359 + vertex 73.5503 121.839 31.4149 + vertex 73.9552 112.837 31.4148 + endloop + endfacet + facet normal -0.00706747 -0.000256922 0.999975 + outer loop + vertex 73.9552 112.837 31.4148 + vertex 58.8507 120.895 31.3101 + vertex 59.1656 111.892 31.31 + endloop + endfacet + facet normal -0.00579738 -0.000149197 0.999983 + outer loop + vertex 59.1656 111.892 31.31 + vertex 44.1294 120.076 31.2241 + vertex 44.3601 111.074 31.2241 + endloop + endfacet + facet normal -0.00434514 -9.35338e-05 0.999991 + outer loop + vertex 44.3601 111.074 31.2241 + vertex 29.381 119.439 31.1598 + vertex 29.5327 110.434 31.1596 + endloop + endfacet + facet normal -0.00269737 -1.65656e-06 0.999996 + outer loop + vertex 29.5327 110.434 31.1596 + vertex 14.6356 119.028 31.1194 + vertex 14.7133 110.026 31.1196 + endloop + endfacet + facet normal -0.000921332 -5.53193e-06 1 + outer loop + vertex 14.7133 110.026 31.1196 + vertex -0.0756773 118.891 31.106 + vertex -0.075426 109.885 31.106 + endloop + endfacet + facet normal 0.000933712 -1.22415e-05 1 + outer loop + vertex -0.075426 109.885 31.106 + vertex -14.7614 119.036 31.1198 + vertex -14.8386 110.028 31.1198 + endloop + endfacet + facet normal 0.00268411 -6.71428e-05 0.999996 + outer loop + vertex -14.8386 110.028 31.1198 + vertex -29.4448 119.444 31.1596 + vertex -29.6005 110.433 31.1594 + endloop + endfacet + facet normal 0.00436743 -0.000124161 0.99999 + outer loop + vertex -29.6005 110.433 31.1594 + vertex -44.1387 120.085 31.2241 + vertex -44.3748 111.075 31.224 + endloop + endfacet + facet normal 0.00579461 -0.000256557 0.999983 + outer loop + vertex -44.3748 111.075 31.224 + vertex -58.84 120.904 31.3104 + vertex -59.163 111.893 31.3099 + endloop + endfacet + facet normal 0.00705502 -0.000355981 0.999975 + outer loop + vertex -59.163 111.893 31.3099 + vertex -73.5369 121.844 31.4149 + vertex -73.9495 112.838 31.4146 + endloop + endfacet + facet normal 0.00811689 -0.000486398 0.999967 + outer loop + vertex -73.9495 112.838 31.4146 + vertex -88.2272 122.869 31.5354 + vertex -88.7346 113.868 31.5351 + endloop + endfacet + facet normal 0.00892417 -0.00065425 0.99996 + outer loop + vertex -88.7346 113.868 31.5351 + vertex -102.955 123.955 31.6686 + vertex -103.562 114.962 31.6682 + endloop + endfacet + facet normal 0.00946934 -0.000791904 0.999955 + outer loop + vertex -103.562 114.962 31.6682 + vertex -117.813 125.109 31.8111 + vertex -118.519 116.124 31.8107 + endloop + endfacet + facet normal 0.00964583 -0.000902302 0.999953 + outer loop + vertex -118.519 116.124 31.8107 + vertex -132.912 126.353 31.9588 + vertex -133.717 117.378 31.9585 + endloop + endfacet + facet normal 0.00944405 -0.000973875 0.999955 + outer loop + vertex -133.717 117.378 31.9585 + vertex -148.34 127.726 32.1066 + vertex -149.231 118.757 32.1063 + endloop + endfacet + facet normal 0.00891784 -0.000993505 0.99996 + outer loop + vertex -149.231 118.757 32.1063 + vertex -164.117 129.254 32.2495 + vertex -165.068 120.287 32.2491 + endloop + endfacet + facet normal 0.00812077 -0.000837953 0.999967 + outer loop + vertex -165.989 111.294 32.25 + vertex -181.202 121.993 32.3825 + vertex -182.169 113.001 32.3828 + endloop + endfacet + facet normal 0.00823745 -0.000921373 0.999966 + outer loop + vertex -164.117 129.254 32.2495 + vertex -180.216 130.961 32.3837 + vertex -165.068 120.287 32.2491 + endloop + endfacet + facet normal 0.00734093 -0.00113758 0.999972 + outer loop + vertex -181.202 121.993 32.3825 + vertex -196.595 132.856 32.5078 + vertex -197.595 123.887 32.505 + endloop + endfacet + facet normal 0.00754699 -0.00122525 0.999971 + outer loop + vertex -179.202 139.939 32.387 + vertex -195.578 141.84 32.513 + vertex -180.216 130.961 32.3837 + endloop + endfacet + facet normal 0.00668101 -0.00149423 0.999977 + outer loop + vertex -196.595 132.856 32.5078 + vertex -212.209 143.927 32.6287 + vertex -213.22 134.94 32.622 + endloop + endfacet + facet normal 0.0066576 -0.00223122 0.999975 + outer loop + vertex -194.583 150.916 32.5266 + vertex -211.204 153.004 32.6419 + vertex -195.578 141.84 32.513 + endloop + endfacet + facet normal 0.00585693 -0.00197664 0.999981 + outer loop + vertex -212.209 143.927 32.6287 + vertex -228.028 155.267 32.7438 + vertex -229.032 146.187 32.7317 + endloop + endfacet + facet normal 0.00502295 -0.00459046 0.999977 + outer loop + vertex -210.527 162.268 32.681 + vertex -226.762 164.454 32.7726 + vertex -211.204 153.004 32.6419 + endloop + endfacet + facet normal 0.00465716 -0.00184402 0.999987 + outer loop + vertex -228.028 155.267 32.7438 + vertex -245.051 157.693 32.8275 + vertex -229.032 146.187 32.7317 + endloop + endfacet + facet normal 0.00593304 -0.00141006 0.999981 + outer loop + vertex -212.209 143.927 32.6287 + vertex -229.032 146.187 32.7317 + vertex -213.22 134.94 32.622 + endloop + endfacet + facet normal 0.00673419 -0.00106989 0.999977 + outer loop + vertex -196.595 132.856 32.5078 + vertex -213.22 134.94 32.622 + vertex -197.595 123.887 32.505 + endloop + endfacet + facet normal 0.00738468 -0.000758807 0.999972 + outer loop + vertex -181.202 121.993 32.3825 + vertex -197.595 123.887 32.505 + vertex -182.169 113.001 32.3828 + endloop + endfacet + facet normal 0.00814172 -0.000639434 0.999967 + outer loop + vertex -165.989 111.294 32.25 + vertex -182.169 113.001 32.3828 + vertex -166.895 102.268 32.2516 + endloop + endfacet + facet normal 0.00887191 -0.000712739 0.99996 + outer loop + vertex -150.924 100.732 32.1088 + vertex -165.989 111.294 32.25 + vertex -166.895 102.268 32.2516 + endloop + endfacet + facet normal 0.00939344 -0.000701108 0.999956 + outer loop + vertex -135.246 99.3452 31.9605 + vertex -150.084 109.76 32.1072 + vertex -150.924 100.732 32.1088 + endloop + endfacet + facet normal 0.0095817 -0.000639784 0.999954 + outer loop + vertex -119.868 98.0819 31.8124 + vertex -134.492 108.379 31.9591 + vertex -135.246 99.3452 31.9605 + endloop + endfacet + facet normal 0.0093858 -0.000559584 0.999956 + outer loop + vertex -104.724 96.9097 31.6695 + vertex -119.201 107.119 31.8112 + vertex -119.868 98.0819 31.8124 + endloop + endfacet + facet normal 0.00885383 -0.000444315 0.999961 + outer loop + vertex -89.7116 95.8052 31.5361 + vertex -104.148 105.95 31.6685 + vertex -104.724 96.9097 31.6695 + endloop + endfacet + facet normal 0.0080418 -0.00032548 0.999968 + outer loop + vertex -74.7459 94.7661 31.4154 + vertex -89.2272 104.85 31.5352 + vertex -89.7116 95.8052 31.5361 + endloop + endfacet + facet normal 0.00700864 -0.000214987 0.999975 + outer loop + vertex -59.7875 93.8127 31.3104 + vertex -74.3502 103.814 31.4146 + vertex -74.7459 94.7661 31.4154 + endloop + endfacet + facet normal 0.00575825 -0.00013805 0.999983 + outer loop + vertex -44.8356 92.9891 31.2242 + vertex -59.4761 102.865 31.3099 + vertex -59.7875 93.8127 31.3104 + endloop + endfacet + facet normal 0.00431462 -6.63177e-05 0.999991 + outer loop + vertex -29.9033 92.3476 31.1597 + vertex -44.6053 102.044 31.2238 + vertex -44.8356 92.9891 31.2242 + endloop + endfacet + facet normal 0.00268264 -1.72325e-05 0.999996 + outer loop + vertex -14.9885 91.9384 31.1197 + vertex -29.7512 101.405 31.1595 + vertex -29.9033 92.3476 31.1597 + endloop + endfacet + facet normal 0.000919301 4.02417e-05 1 + outer loop + vertex -0.0708954 91.7972 31.106 + vertex -14.914 100.994 31.1193 + vertex -14.9885 91.9384 31.1197 + endloop + endfacet + facet normal -0.000903212 4.2096e-05 1 + outer loop + vertex 14.8742 91.9389 31.1195 + vertex -0.0732694 100.854 31.1056 + vertex -0.0708954 91.7972 31.106 + endloop + endfacet + facet normal -0.00266552 2.27677e-05 0.999996 + outer loop + vertex 29.8522 92.3494 31.1594 + vertex 14.7934 100.994 31.1191 + vertex 14.8742 91.9389 31.1195 + endloop + endfacet + facet normal -0.00429049 -7.00757e-05 0.999991 + outer loop + vertex 44.839 92.9914 31.2237 + vertex 29.6932 101.407 31.1593 + vertex 29.8522 92.3494 31.1594 + endloop + endfacet + facet normal -0.00573443 -0.000141213 0.999984 + outer loop + vertex 59.8074 93.8135 31.3097 + vertex 44.5991 102.047 31.2236 + vertex 44.839 92.9914 31.2237 + endloop + endfacet + facet normal -0.00699104 -0.00023726 0.999976 + outer loop + vertex 74.7669 94.7648 31.4145 + vertex 59.486 102.867 31.3096 + vertex 59.8074 93.8135 31.3097 + endloop + endfacet + facet normal -0.00805941 -0.000340131 0.999967 + outer loop + vertex 89.7821 95.8082 31.5359 + vertex 74.3601 103.815 31.4143 + vertex 74.7669 94.7648 31.4145 + endloop + endfacet + facet normal -0.00886324 -0.000453691 0.999961 + outer loop + vertex 104.927 96.9232 31.6706 + vertex 89.2865 104.854 31.5356 + vertex 89.7821 95.8082 31.5359 + endloop + endfacet + facet normal -0.00940337 -0.000569553 0.999956 + outer loop + vertex 120.25 98.1105 31.8154 + vertex 104.339 105.965 31.6702 + vertex 104.927 96.9232 31.6706 + endloop + endfacet + facet normal -0.00960808 -0.00067264 0.999954 + outer loop + vertex 135.746 99.3832 31.9651 + vertex 119.573 107.148 31.815 + vertex 120.25 98.1105 31.8154 + endloop + endfacet + facet normal -0.00943894 -0.000727368 0.999955 + outer loop + vertex 151.402 100.767 32.1139 + vertex 134.979 108.416 31.9645 + vertex 135.746 99.3832 31.9651 + endloop + endfacet + facet normal -0.00891912 -0.000754788 0.99996 + outer loop + vertex 167.247 102.291 32.2564 + vertex 150.556 109.796 32.1132 + vertex 151.402 100.767 32.1139 + endloop + endfacet + facet normal -0.00811835 -0.000707973 0.999967 + outer loop + vertex 183.354 103.988 32.3884 + vertex 166.342 111.32 32.2555 + vertex 167.247 102.291 32.2564 + endloop + endfacet + facet normal -0.0072046 -0.000631351 0.999974 + outer loop + vertex 199.772 105.876 32.5079 + vertex 182.404 113.016 32.3872 + vertex 183.354 103.988 32.3884 + endloop + endfacet + facet normal -0.00640532 -0.000584152 0.999979 + outer loop + vertex 216.477 107.956 32.6161 + vertex 198.792 114.903 32.5069 + vertex 199.772 105.876 32.5079 + endloop + endfacet + facet normal -0.00580901 -0.000537074 0.999983 + outer loop + vertex 233.387 110.227 32.7155 + vertex 215.489 116.988 32.6152 + vertex 216.477 107.956 32.6161 + endloop + endfacet + facet normal -0.0051578 -0.000996282 0.999986 + outer loop + vertex 250.393 112.675 32.8057 + vertex 233.387 110.227 32.7155 + vertex 251.373 103.603 32.8017 + endloop + endfacet + facet normal -0.00417902 -0.000890612 0.999991 + outer loop + vertex 268.343 106.177 32.8749 + vertex 250.393 112.675 32.8057 + vertex 251.373 103.603 32.8017 + endloop + endfacet + facet normal -0.00247825 -0.00230167 0.999994 + outer loop + vertex 285.089 108.792 32.9224 + vertex 268.343 106.177 32.8749 + vertex 286.115 99.704 32.9041 + endloop + endfacet + facet normal -0.00201823 -0.00224973 0.999995 + outer loop + vertex 302.502 102.302 32.943 + vertex 285.089 108.792 32.9224 + vertex 286.115 99.704 32.9041 + endloop + endfacet + facet normal -0.00493121 -0.00708559 0.999963 + outer loop + vertex 318.426 104.932 33.0401 + vertex 302.502 102.302 32.943 + vertex 319.592 95.8772 32.9817 + endloop + endfacet + facet normal -0.0159924 -0.00850957 0.999836 + outer loop + vertex 335.281 98.7824 33.2574 + vertex 318.426 104.932 33.0401 + vertex 319.592 95.8772 32.9817 + endloop + endfacet + facet normal -0.0356857 -0.0121181 0.99929 + outer loop + vertex 350.828 102.197 33.854 + vertex 334.01 107.823 33.3217 + vertex 335.281 98.7824 33.2574 + endloop + endfacet + facet normal -0.0599575 -0.0168032 0.998059 + outer loop + vertex 366.178 106.129 34.8424 + vertex 349.416 111.219 33.9211 + vertex 350.828 102.197 33.854 + endloop + endfacet + facet normal -0.0869606 -0.0236135 0.995932 + outer loop + vertex 377.523 105.864 35.8266 + vertex 375.28 110.421 35.7389 + vertex 366.178 106.129 34.8424 + endloop + endfacet + facet normal -0.124627 -0.0424151 0.991297 + outer loop + vertex 383.582 107.798 36.6712 + vertex 377.523 105.864 35.8266 + vertex 384.484 103.27 36.5908 + endloop + endfacet + facet normal -0.166896 -0.0507171 0.984669 + outer loop + vertex 390.465 104.802 37.6834 + vertex 383.582 107.798 36.6712 + vertex 384.484 103.27 36.5908 + endloop + endfacet + facet normal -0.217603 -0.0801983 0.972737 + outer loop + vertex 395.734 105.966 38.9581 + vertex 390.465 104.802 37.6834 + vertex 396.739 101.476 38.8127 + endloop + endfacet + facet normal -0.266723 -0.115102 0.956875 + outer loop + vertex 401.581 102.421 40.2761 + vertex 396.739 101.476 38.8127 + vertex 402.678 98.0274 40.0535 + endloop + endfacet + facet normal -0.271614 -0.091813 0.958017 + outer loop + vertex 401.581 102.421 40.2761 + vertex 395.734 105.966 38.9581 + vertex 396.739 101.476 38.8127 + endloop + endfacet + facet normal -0.277284 -0.102159 0.955341 + outer loop + vertex 400.505 106.903 40.4431 + vertex 395.734 105.966 38.9581 + vertex 401.581 102.421 40.2761 + endloop + endfacet + facet normal -0.281072 -0.0839382 0.956009 + outer loop + vertex 400.505 106.903 40.4431 + vertex 394.732 110.503 39.0621 + vertex 395.734 105.966 38.9581 + endloop + endfacet + facet normal -0.284414 -0.0898842 0.954479 + outer loop + vertex 399.451 111.431 40.5554 + vertex 394.732 110.503 39.0621 + vertex 400.505 106.903 40.4431 + endloop + endfacet + facet normal -0.287301 -0.075782 0.954838 + outer loop + vertex 399.451 111.431 40.5554 + vertex 393.75 115.034 39.1261 + vertex 394.732 110.503 39.0621 + endloop + endfacet + facet normal -0.291113 -0.0824931 0.953125 + outer loop + vertex 398.416 115.948 40.6304 + vertex 393.75 115.034 39.1261 + vertex 399.451 111.431 40.5554 + endloop + endfacet + facet normal -0.293361 -0.0713673 0.953334 + outer loop + vertex 398.416 115.948 40.6304 + vertex 392.788 119.501 39.1645 + vertex 393.75 115.034 39.1261 + endloop + endfacet + facet normal -0.294507 -0.073392 0.952827 + outer loop + vertex 397.426 120.415 40.6684 + vertex 392.788 119.501 39.1645 + vertex 398.416 115.948 40.6304 + endloop + endfacet + facet normal -0.29576 -0.0671496 0.952899 + outer loop + vertex 397.426 120.415 40.6684 + vertex 391.853 123.898 39.184 + vertex 392.788 119.501 39.1645 + endloop + endfacet + facet normal -0.297435 -0.0701427 0.952162 + outer loop + vertex 396.461 124.81 40.6906 + vertex 391.853 123.898 39.184 + vertex 397.426 120.415 40.6684 + endloop + endfacet + facet normal -0.298547 -0.0645933 0.952207 + outer loop + vertex 396.461 124.81 40.6906 + vertex 390.932 128.271 39.192 + vertex 391.853 123.898 39.184 + endloop + endfacet + facet normal -0.299324 -0.0659824 0.951867 + outer loop + vertex 395.517 129.181 40.6969 + vertex 390.932 128.271 39.192 + vertex 396.461 124.81 40.6906 + endloop + endfacet + facet normal -0.30007 -0.0622513 0.951884 + outer loop + vertex 395.517 129.181 40.6969 + vertex 390.014 132.69 39.1916 + vertex 390.932 128.271 39.192 + endloop + endfacet + facet normal -0.302409 -0.0663547 0.950866 + outer loop + vertex 394.566 133.595 40.7025 + vertex 390.014 132.69 39.1916 + vertex 395.517 129.181 40.6969 + endloop + endfacet + facet normal -0.302947 -0.0636671 0.950878 + outer loop + vertex 394.566 133.595 40.7025 + vertex 389.076 137.191 39.194 + vertex 390.014 132.69 39.1916 + endloop + endfacet + facet normal -0.302538 -0.0629684 0.951055 + outer loop + vertex 393.615 138.091 40.6976 + vertex 389.076 137.191 39.194 + vertex 394.566 133.595 40.7025 + endloop + endfacet + facet normal -0.302766 -0.0618226 0.951058 + outer loop + vertex 393.615 138.091 40.6976 + vertex 388.138 141.758 39.1924 + vertex 389.076 137.191 39.194 + endloop + endfacet + facet normal -0.304919 -0.0654192 0.950129 + outer loop + vertex 392.646 142.65 40.7006 + vertex 388.138 141.758 39.1924 + vertex 393.615 138.091 40.6976 + endloop + endfacet + facet normal -0.305336 -0.0633232 0.950137 + outer loop + vertex 392.646 142.65 40.7006 + vertex 387.197 146.321 39.1942 + vertex 388.138 141.758 39.1924 + endloop + endfacet + facet normal -0.305902 -0.0642631 0.949892 + outer loop + vertex 391.686 147.212 40.7 + vertex 387.197 146.321 39.1942 + vertex 392.646 142.65 40.7006 + endloop + endfacet + facet normal -0.306356 -0.0619815 0.949897 + outer loop + vertex 391.686 147.212 40.7 + vertex 386.277 150.829 39.1916 + vertex 387.197 146.321 39.1942 + endloop + endfacet + facet normal -0.307976 -0.0646975 0.949192 + outer loop + vertex 390.739 151.717 40.6996 + vertex 386.277 150.829 39.1916 + vertex 391.686 147.212 40.7 + endloop + endfacet + facet normal -0.308008 -0.0645391 0.949192 + outer loop + vertex 390.739 151.717 40.6996 + vertex 385.353 155.241 39.1916 + vertex 386.277 150.829 39.1916 + endloop + endfacet + facet normal -0.308055 -0.0646208 0.949171 + outer loop + vertex 389.802 156.135 40.6964 + vertex 385.353 155.241 39.1916 + vertex 390.739 151.717 40.6996 + endloop + endfacet + facet normal -0.307903 -0.0653751 0.949169 + outer loop + vertex 389.802 156.135 40.6964 + vertex 384.422 159.581 39.1885 + vertex 385.353 155.241 39.1916 + endloop + endfacet + facet normal -0.309108 -0.067492 0.948629 + outer loop + vertex 388.855 160.476 40.6966 + vertex 384.422 159.581 39.1885 + vertex 389.802 156.135 40.6964 + endloop + endfacet + facet normal -0.309206 -0.0670073 0.948631 + outer loop + vertex 388.855 160.476 40.6966 + vertex 383.478 163.897 39.1858 + vertex 384.422 159.581 39.1885 + endloop + endfacet + facet normal -0.309703 -0.0678882 0.948407 + outer loop + vertex 387.897 164.79 40.6927 + vertex 383.478 163.897 39.1858 + vertex 388.855 160.476 40.6966 + endloop + endfacet + facet normal -0.309804 -0.0673964 0.948409 + outer loop + vertex 387.897 164.79 40.6927 + vertex 382.54 168.253 39.189 + vertex 383.478 163.897 39.1858 + endloop + endfacet + facet normal -0.311693 -0.0706928 0.947549 + outer loop + vertex 386.924 169.138 40.6969 + vertex 382.54 168.253 39.189 + vertex 387.897 164.79 40.6927 + endloop + endfacet + facet normal -0.31291 -0.0647175 0.947575 + outer loop + vertex 386.924 169.138 40.6969 + vertex 381.649 172.688 39.1976 + vertex 382.54 168.253 39.189 + endloop + endfacet + facet normal -0.315757 -0.0694901 0.946292 + outer loop + vertex 385.967 173.562 40.7026 + vertex 381.649 172.688 39.1976 + vertex 386.924 169.138 40.6969 + endloop + endfacet + facet normal -0.317986 -0.0584735 0.946291 + outer loop + vertex 385.967 173.562 40.7026 + vertex 380.834 177.195 39.2022 + vertex 381.649 172.688 39.1976 + endloop + endfacet + facet normal -0.322047 -0.064954 0.944493 + outer loop + vertex 385.057 178.055 40.7011 + vertex 380.834 177.195 39.2022 + vertex 385.967 173.562 40.7026 + endloop + endfacet + facet normal -0.324229 -0.0541272 0.944429 + outer loop + vertex 385.057 178.055 40.7011 + vertex 380.077 181.726 39.202 + vertex 380.834 177.195 39.2022 + endloop + endfacet + facet normal -0.32821 -0.0602399 0.942682 + outer loop + vertex 384.198 182.579 40.6914 + vertex 380.077 181.726 39.202 + vertex 385.057 178.055 40.7011 + endloop + endfacet + facet normal -0.329222 -0.0552705 0.942634 + outer loop + vertex 384.198 182.579 40.6914 + vertex 379.308 186.255 39.1991 + vertex 380.077 181.726 39.202 + endloop + endfacet + facet normal -0.328317 -0.0539063 0.943028 + outer loop + vertex 383.388 187.12 40.6688 + vertex 379.308 186.255 39.1991 + vertex 384.198 182.579 40.6914 + endloop + endfacet + facet normal -0.329268 -0.0492867 0.942949 + outer loop + vertex 383.388 187.12 40.6688 + vertex 378.534 190.852 39.169 + vertex 379.308 186.255 39.1991 + endloop + endfacet + facet normal -0.317492 -0.0320499 0.947719 + outer loop + vertex 382.747 191.766 40.6113 + vertex 378.534 190.852 39.169 + vertex 383.388 187.12 40.6688 + endloop + endfacet + facet normal -0.205756 -0.0841236 0.974981 + outer loop + vertex 397.785 97.0885 38.6154 + vertex 391.435 100.326 37.5547 + vertex 392.426 95.9422 37.3857 + endloop + endfacet + facet normal -0.157163 -0.0735102 0.984833 + outer loop + vertex 391.435 100.326 37.5547 + vertex 385.409 98.8053 36.4796 + vertex 392.426 95.9422 37.3857 + endloop + endfacet + facet normal -0.118436 -0.0536412 0.991512 + outer loop + vertex 385.409 98.8053 36.4796 + vertex 376.991 101.389 35.6138 + vertex 379.273 96.8943 35.6433 + endloop + endfacet + facet normal -0.0828488 -0.0355378 0.995928 + outer loop + vertex 379.273 96.8943 35.6433 + vertex 376.991 101.389 35.6138 + vertex 367.755 97.1319 34.6936 + endloop + endfacet + facet normal -0.0529337 -0.0435019 0.99765 + outer loop + vertex 367.755 97.1319 34.6936 + vertex 352.205 93.1818 33.6963 + vertex 369.217 88.1796 34.3808 + endloop + endfacet + facet normal -0.107507 -0.0706723 0.991689 + outer loop + vertex 386.35 94.4066 36.3238 + vertex 378.687 92.4718 35.3552 + vertex 387.194 90.0166 36.1025 + endloop + endfacet + facet normal -0.146393 -0.077868 0.986157 + outer loop + vertex 393.431 91.6433 37.1568 + vertex 386.35 94.4066 36.3238 + vertex 387.194 90.0166 36.1025 + endloop + endfacet + facet normal -0.188656 -0.125552 0.973984 + outer loop + vertex 398.867 92.8201 38.3614 + vertex 393.431 91.6433 37.1568 + vertex 399.955 88.659 38.0357 + endloop + endfacet + facet normal -0.223968 -0.179442 0.957935 + outer loop + vertex 405.012 89.6309 39.4001 + vertex 399.955 88.659 38.0357 + vertex 406.253 85.6569 38.9459 + endloop + endfacet + facet normal -0.163465 -0.12155 0.979033 + outer loop + vertex 400.996 84.5661 37.6118 + vertex 394.319 87.3555 36.8433 + vertex 394.949 83.0054 36.4084 + endloop + endfacet + facet normal -0.128854 -0.117107 0.984725 + outer loop + vertex 394.319 87.3555 36.8433 + vertex 387.795 85.5694 35.7772 + vertex 394.949 83.0054 36.4084 + endloop + endfacet + facet normal -0.100269 -0.0744496 0.992171 + outer loop + vertex 387.795 85.5694 35.7772 + vertex 380.833 88.0005 35.2561 + vertex 379.839 83.5956 34.8251 + endloop + endfacet + facet normal -0.106541 -0.109871 0.988219 + outer loop + vertex 395.302 78.5676 35.8435 + vertex 387.766 80.9538 35.2963 + vertex 385.842 75.301 34.4603 + endloop + endfacet + facet normal -0.0633734 -0.0870792 0.994184 + outer loop + vertex 381.257 79.7162 34.5757 + vertex 379.839 83.5956 34.8251 + vertex 370.748 79.4775 33.8849 + endloop + endfacet + facet normal -0.0340705 -0.0861437 0.9957 + outer loop + vertex 370.61 71.2266 33.0812 + vertex 354.294 75.6511 32.9057 + vertex 354.759 67.6735 32.2314 + endloop + endfacet + facet normal -0.045981 -0.0648964 0.996832 + outer loop + vertex 369.217 88.1796 34.3808 + vertex 353.46 84.2715 33.3995 + vertex 370.748 79.4775 33.8849 + endloop + endfacet + facet normal -0.0282343 -0.034591 0.999003 + outer loop + vertex 353.46 84.2715 33.3995 + vertex 336.507 89.7765 33.111 + vertex 337.589 80.9263 32.8352 + endloop + endfacet + facet normal -0.0107165 -0.0324614 0.999416 + outer loop + vertex 336.507 89.7765 33.111 + vertex 320.721 86.8848 32.8478 + vertex 337.589 80.9263 32.8352 + endloop + endfacet + facet normal -0.00315275 -0.014791 0.999886 + outer loop + vertex 320.721 86.8848 32.8478 + vertex 303.591 93.2322 32.8877 + vertex 304.657 84.2328 32.7579 + endloop + endfacet + facet normal -0.00018817 -0.0144401 0.999896 + outer loop + vertex 303.591 93.2322 32.8877 + vertex 287.148 90.6161 32.8468 + vertex 304.657 84.2328 32.7579 + endloop + endfacet + facet normal -0.00203251 -0.00686329 0.999974 + outer loop + vertex 287.148 90.6161 32.8468 + vertex 269.337 97.0812 32.855 + vertex 270.332 87.982 32.7946 + endloop + endfacet + facet normal -0.00326332 -0.0069979 0.99997 + outer loop + vertex 269.337 97.0812 32.855 + vertex 252.354 94.5082 32.7816 + vertex 270.332 87.982 32.7946 + endloop + endfacet + facet normal -0.00481507 -0.00259617 0.999985 + outer loop + vertex 252.354 94.5082 32.7816 + vertex 234.367 101.16 32.7122 + vertex 235.346 92.0714 32.6934 + endloop + endfacet + facet normal -0.00544219 -0.00256406 0.999982 + outer loop + vertex 235.346 92.0714 32.6934 + vertex 217.456 98.8955 32.6135 + vertex 218.434 89.8145 32.5955 + endloop + endfacet + facet normal -0.00607561 -0.00249083 0.999978 + outer loop + vertex 218.434 89.8145 32.5955 + vertex 200.744 96.8208 32.5055 + vertex 201.707 87.7426 32.4887 + endloop + endfacet + facet normal -0.00695298 -0.00253342 0.999973 + outer loop + vertex 201.707 87.7426 32.4887 + vertex 184.302 94.9371 32.3859 + vertex 185.238 85.8618 32.3695 + endloop + endfacet + facet normal -0.00785498 -0.00261555 0.999966 + outer loop + vertex 185.238 85.8618 32.3695 + vertex 168.144 93.2378 32.2545 + vertex 169.042 84.1674 32.2378 + endloop + endfacet + facet normal -0.00863863 -0.00258851 0.999959 + outer loop + vertex 169.042 84.1674 32.2378 + vertex 152.236 91.7115 32.1121 + vertex 153.07 82.6406 32.0959 + endloop + endfacet + facet normal -0.00916314 -0.00248293 0.999955 + outer loop + vertex 153.07 82.6406 32.0959 + vertex 136.504 90.3268 31.9632 + vertex 137.263 81.2536 31.9476 + endloop + endfacet + facet normal -0.00932749 -0.00236732 0.999954 + outer loop + vertex 137.263 81.2536 31.9476 + vertex 120.92 89.0499 31.8136 + vertex 121.596 79.9753 31.7984 + endloop + endfacet + facet normal -0.0091133 -0.00213957 0.999956 + outer loop + vertex 121.596 79.9753 31.7984 + vertex 105.508 87.8595 31.6687 + vertex 106.091 78.7811 31.6545 + endloop + endfacet + facet normal -0.00864038 -0.00201735 0.999961 + outer loop + vertex 106.091 78.7811 31.6545 + vertex 90.2718 86.7405 31.5339 + vertex 90.7703 77.662 31.5199 + endloop + endfacet + facet normal -0.00782842 -0.00186331 0.999968 + outer loop + vertex 90.7703 77.662 31.5199 + vertex 75.1737 85.6962 31.4128 + vertex 75.5839 76.6163 31.3991 + endloop + endfacet + facet normal -0.00678517 -0.0016912 0.999976 + outer loop + vertex 75.5839 76.6163 31.3991 + vertex 60.1289 84.7427 31.3079 + vertex 60.4536 75.6615 31.2948 + endloop + endfacet + facet normal -0.00558598 -0.00159088 0.999983 + outer loop + vertex 60.4536 75.6615 31.2948 + vertex 45.0772 83.9185 31.222 + vertex 45.3205 74.8398 31.209 + endloop + endfacet + facet normal -0.00417493 -0.00148688 0.99999 + outer loop + vertex 45.3205 74.8398 31.209 + vertex 30.0095 83.2754 31.1576 + vertex 30.1706 74.1964 31.1447 + endloop + endfacet + facet normal -0.00259133 -0.00141912 0.999996 + outer loop + vertex 30.1706 74.1964 31.1447 + vertex 14.9511 82.863 31.1176 + vertex 15.0321 73.7868 31.1049 + endloop + endfacet + facet normal -0.00087778 -0.00139336 0.999999 + outer loop + vertex 15.0321 73.7868 31.1049 + vertex -0.0721058 82.7216 31.1041 + vertex -0.0713403 73.6468 31.0915 + endloop + endfacet + facet normal 0.000896832 -0.00140197 0.999999 + outer loop + vertex -0.0713403 73.6468 31.0915 + vertex -15.067 82.8641 31.1179 + vertex -15.1481 73.7841 31.1052 + endloop + endfacet + facet normal 0.00262222 -0.0014442 0.999996 + outer loop + vertex -15.1481 73.7841 31.1052 + vertex -30.0593 83.2747 31.158 + vertex -30.2204 74.1943 31.1453 + endloop + endfacet + facet normal 0.00418957 -0.00155957 0.99999 + outer loop + vertex -30.2204 74.1943 31.1453 + vertex -45.0696 83.9192 31.2227 + vertex -45.3118 74.8384 31.2095 + endloop + endfacet + facet normal 0.00558961 -0.00166849 0.999983 + outer loop + vertex -45.3118 74.8384 31.2095 + vertex -60.1034 84.7421 31.3087 + vertex -60.4266 75.6643 31.2954 + endloop + endfacet + facet normal 0.00680199 -0.00181178 0.999975 + outer loop + vertex -60.4266 75.6643 31.2954 + vertex -75.1456 85.6977 31.4137 + vertex -75.5535 76.6183 31.4 + endloop + endfacet + facet normal 0.00780662 -0.00198448 0.999968 + outer loop + vertex -75.5535 76.6183 31.4 + vertex -90.1976 86.7395 31.5344 + vertex -90.6917 77.6606 31.5203 + endloop + endfacet + facet normal 0.00861252 -0.00213519 0.999961 + outer loop + vertex -90.6917 77.6606 31.5203 + vertex -105.299 87.8461 31.6678 + vertex -105.88 78.7683 31.6535 + endloop + endfacet + facet normal 0.00912816 -0.00228869 0.999956 + outer loop + vertex -105.88 78.7683 31.6535 + vertex -120.533 89.0223 31.8107 + vertex -121.199 79.9453 31.796 + endloop + endfacet + facet normal 0.00928193 -0.00245634 0.999954 + outer loop + vertex -121.199 79.9453 31.796 + vertex -135.999 90.2891 31.9588 + vertex -136.749 81.2147 31.9435 + endloop + endfacet + facet normal 0.0091139 -0.00260898 0.999955 + outer loop + vertex -136.749 81.2147 31.9435 + vertex -151.75 91.6752 32.1075 + vertex -152.578 82.6039 32.0914 + endloop + endfacet + facet normal 0.00859754 -0.00261616 0.99996 + outer loop + vertex -152.578 82.6039 32.0914 + vertex -167.789 93.2138 32.2499 + vertex -168.675 84.1404 32.2338 + endloop + endfacet + facet normal 0.00725566 -0.00665102 0.999952 + outer loop + vertex -169.566 75.0671 32.1819 + vertex -184.991 85.8457 32.3655 + vertex -185.922 76.7709 32.3119 + endloop + endfacet + facet normal 0.0078891 -0.00254696 0.999966 + outer loop + vertex -167.789 93.2138 32.2499 + vertex -184.059 94.9183 32.3826 + vertex -168.675 84.1404 32.2338 + endloop + endfacet + facet normal 0.00692589 -0.00265373 0.999972 + outer loop + vertex -184.991 85.8457 32.3655 + vertex -200.527 96.8067 32.5022 + vertex -201.482 87.7294 32.4847 + endloop + endfacet + facet normal 0.00721744 -0.000926835 0.999974 + outer loop + vertex -183.12 103.974 32.3842 + vertex -199.563 105.864 32.5046 + vertex -184.059 94.9183 32.3826 + endloop + endfacet + facet normal 0.00638499 -0.00108465 0.999979 + outer loop + vertex -200.527 96.8067 32.5022 + vertex -216.203 107.935 32.6143 + vertex -217.18 98.876 32.6107 + endloop + endfacet + facet normal 0.00657941 -0.00066388 0.999978 + outer loop + vertex -198.583 114.892 32.5042 + vertex -215.217 116.969 32.615 + vertex -199.563 105.864 32.5046 + endloop + endfacet + facet normal 0.00586488 -0.000859677 0.999982 + outer loop + vertex -216.203 107.935 32.6143 + vertex -232.027 119.212 32.7168 + vertex -233.018 110.175 32.7149 + endloop + endfacet + facet normal 0.0059882 -0.000935629 0.999982 + outer loop + vertex -214.221 125.966 32.6175 + vertex -231.029 128.215 32.7202 + vertex -215.217 116.969 32.615 + endloop + endfacet + facet normal 0.00521259 -0.000876907 0.999986 + outer loop + vertex -232.027 119.212 32.7168 + vertex -247.911 130.602 32.8096 + vertex -248.919 121.595 32.807 + endloop + endfacet + facet normal 0.00500779 -0.00109645 0.999987 + outer loop + vertex -230.03 137.195 32.7251 + vertex -246.906 139.587 32.8122 + vertex -231.029 128.215 32.7202 + endloop + endfacet + facet normal 0.00401784 -0.000274843 0.999992 + outer loop + vertex -247.911 130.602 32.8096 + vertex -263.688 142.094 32.8762 + vertex -264.709 133.107 32.8778 + endloop + endfacet + facet normal 0.00340723 -0.000755299 0.999994 + outer loop + vertex -245.917 148.589 32.8156 + vertex -262.691 151.096 32.8747 + vertex -246.906 139.587 32.8122 + endloop + endfacet + facet normal 0.00250572 0.000239521 0.999997 + outer loop + vertex -263.688 142.094 32.8762 + vertex -279.231 153.704 32.9123 + vertex -280.224 144.71 32.917 + endloop + endfacet + facet normal 0.00219371 -0.00156986 0.999996 + outer loop + vertex -261.825 160.208 32.8871 + vertex -278.279 162.8 32.9272 + vertex -262.691 151.096 32.8747 + endloop + endfacet + facet normal 0.00230999 -0.00224584 0.999995 + outer loop + vertex -279.231 153.704 32.9123 + vertex -294.486 165.49 32.974 + vertex -295.42 156.417 32.9558 + endloop + endfacet + facet normal 0.00236649 -0.00781884 0.999967 + outer loop + vertex -277.514 172.07 32.9979 + vertex -293.715 174.744 33.0572 + vertex -278.279 162.8 32.9272 + endloop + endfacet + facet normal 0.00675314 -0.00270331 0.999974 + outer loop + vertex -294.486 165.49 32.974 + vertex -310.284 168.248 33.0882 + vertex -295.42 156.417 32.9558 + endloop + endfacet + facet normal 0.00272245 0.000215594 0.999996 + outer loop + vertex -279.231 153.704 32.9123 + vertex -295.42 156.417 32.9558 + vertex -280.224 144.71 32.917 + endloop + endfacet + facet normal 0.00245249 -9.69806e-05 0.999997 + outer loop + vertex -263.688 142.094 32.8762 + vertex -280.224 144.71 32.917 + vertex -264.709 133.107 32.8778 + endloop + endfacet + facet normal 0.00394913 -0.000735597 0.999992 + outer loop + vertex -247.911 130.602 32.8096 + vertex -264.709 133.107 32.8778 + vertex -248.919 121.595 32.807 + endloop + endfacet + facet normal 0.00522492 -0.000789501 0.999986 + outer loop + vertex -232.027 119.212 32.7168 + vertex -248.919 121.595 32.807 + vertex -233.018 110.175 32.7149 + endloop + endfacet + facet normal 0.0058427 -0.00102618 0.999982 + outer loop + vertex -216.203 107.935 32.6143 + vertex -233.018 110.175 32.7149 + vertex -217.18 98.876 32.6107 + endloop + endfacet + facet normal 0.0061995 -0.00257732 0.999977 + outer loop + vertex -200.527 96.8067 32.5022 + vertex -217.18 98.876 32.6107 + vertex -201.482 87.7294 32.4847 + endloop + endfacet + facet normal 0.00647831 -0.00657126 0.999957 + outer loop + vertex -184.991 85.8457 32.3655 + vertex -201.482 87.7294 32.4847 + vertex -185.922 76.7709 32.3119 + endloop + endfacet + facet normal 0.00649438 -0.013954 0.999882 + outer loop + vertex -169.566 75.0671 32.1819 + vertex -185.922 76.7709 32.3119 + vertex -170.481 66.0749 32.0623 + endloop + endfacet + facet normal 0.00713215 -0.0140188 0.999876 + outer loop + vertex -154.271 64.5386 31.9251 + vertex -169.566 75.0671 32.1819 + vertex -170.481 66.0749 32.0623 + endloop + endfacet + facet normal 0.00779222 -0.0136237 0.999877 + outer loop + vertex -138.302 63.1524 31.7818 + vertex -153.41 73.5312 32.041 + vertex -154.271 64.5386 31.9251 + endloop + endfacet + facet normal 0.00805735 -0.0131997 0.99988 + outer loop + vertex -122.595 61.8868 31.6385 + vertex -137.511 72.1437 31.8941 + vertex -138.302 63.1524 31.7818 + endloop + endfacet + facet normal 0.00792598 -0.0128154 0.999886 + outer loop + vertex -107.104 60.713 31.5007 + vertex -121.882 70.8742 31.7481 + vertex -122.595 61.8868 31.6385 + endloop + endfacet + facet normal 0.00748762 -0.0123724 0.999895 + outer loop + vertex -91.7399 59.6109 31.372 + vertex -106.476 69.697 31.6072 + vertex -107.104 60.713 31.5007 + endloop + endfacet + facet normal 0.0068205 -0.0118919 0.999906 + outer loop + vertex -76.4233 58.5793 31.2553 + vertex -91.2016 68.5913 31.4751 + vertex -91.7399 59.6109 31.372 + endloop + endfacet + facet normal 0.00590836 -0.0115438 0.999916 + outer loop + vertex -61.1179 57.6364 31.1539 + vertex -75.9764 67.5505 31.3562 + vertex -76.4233 58.5793 31.2553 + endloop + endfacet + facet normal 0.00484324 -0.0111955 0.999926 + outer loop + vertex -45.8242 56.8232 31.0708 + vertex -60.763 66.5993 31.2526 + vertex -61.1179 57.6364 31.1539 + endloop + endfacet + facet normal 0.00360398 -0.0108764 0.999934 + outer loop + vertex -30.5542 56.187 31.0088 + vertex -45.5615 65.7802 31.1672 + vertex -45.8242 56.8232 31.0708 + endloop + endfacet + facet normal 0.00231102 -0.0106227 0.999941 + outer loop + vertex -15.3021 55.7895 30.9693 + vertex -30.3842 65.1412 31.1035 + vertex -30.5542 56.187 31.0088 + endloop + endfacet + facet normal 0.000744324 -0.0105788 0.999944 + outer loop + vertex -0.0484522 55.6447 30.9564 + vertex -15.2263 64.7339 31.0639 + vertex -15.3021 55.7895 30.9693 + endloop + endfacet + facet normal -0.000723398 -0.0104994 0.999945 + outer loop + vertex 15.2356 55.786 30.969 + vertex -0.0662386 64.591 31.0504 + vertex -0.0484522 55.6447 30.9564 + endloop + endfacet + facet normal -0.00225233 -0.0106376 0.999941 + outer loop + vertex 30.5531 56.1862 31.0077 + vertex 15.1224 64.7292 31.0639 + vertex 15.2356 55.786 30.969 + endloop + endfacet + facet normal -0.00359356 -0.010765 0.999936 + outer loop + vertex 45.8818 56.8196 31.0696 + vertex 30.3467 65.1372 31.1034 + vertex 30.5531 56.1862 31.0077 + endloop + endfacet + facet normal -0.00483836 -0.0110364 0.999927 + outer loop + vertex 61.194 57.6309 31.1527 + vertex 45.5819 65.7763 31.1671 + vertex 45.8818 56.8196 31.0696 + endloop + endfacet + facet normal -0.0059364 -0.0112691 0.999919 + outer loop + vertex 76.4999 58.5721 31.2542 + vertex 60.8035 66.5997 31.2515 + vertex 61.194 57.6309 31.1527 + endloop + endfacet + facet normal -0.00682945 -0.0116103 0.999909 + outer loop + vertex 91.8628 59.6098 31.3712 + vertex 76.0181 67.5486 31.3551 + vertex 76.4999 58.5721 31.2542 + endloop + endfacet + facet normal -0.00750299 -0.0120022 0.9999 + outer loop + vertex 107.363 60.7264 31.5009 + vertex 91.2913 68.5927 31.4747 + vertex 91.8628 59.6098 31.3712 + endloop + endfacet + facet normal -0.00795191 -0.012464 0.999891 + outer loop + vertex 123.035 61.9169 31.6403 + vertex 106.703 69.7121 31.6076 + vertex 107.363 60.7264 31.5009 + endloop + endfacet + facet normal -0.00810405 -0.0129292 0.999884 + outer loop + vertex 138.86 63.1921 31.7851 + vertex 122.289 70.9044 31.7505 + vertex 123.035 61.9169 31.6403 + endloop + endfacet + facet normal -0.00790837 -0.013307 0.99988 + outer loop + vertex 154.807 64.5741 31.9296 + vertex 138.037 72.1824 31.8982 + vertex 138.86 63.1921 31.7851 + endloop + endfacet + facet normal -0.00714617 -0.0135291 0.999883 + outer loop + vertex 170.894 66.1051 32.0653 + vertex 153.918 73.5698 32.045 + vertex 154.807 64.5741 31.9296 + endloop + endfacet + facet normal -0.0063803 -0.0140358 0.999881 + outer loop + vertex 187.169 67.7945 32.1929 + vertex 169.948 75.0959 32.1855 + vertex 170.894 66.1051 32.0653 + endloop + endfacet + facet normal -0.00541538 -0.0143104 0.999883 + outer loop + vertex 203.681 69.6638 32.3091 + vertex 186.186 76.7872 32.3162 + vertex 187.169 67.7945 32.1929 + endloop + endfacet + facet normal -0.00435325 -0.0143054 0.999888 + outer loop + vertex 220.421 71.724 32.4114 + vertex 202.683 78.6671 32.4335 + vertex 203.681 69.6638 32.3091 + endloop + endfacet + facet normal -0.00355178 -0.0145786 0.999887 + outer loop + vertex 237.322 73.9608 32.5041 + vertex 219.419 80.7321 32.5392 + vertex 220.421 71.724 32.4114 + endloop + endfacet + facet normal -0.00278828 -0.0147628 0.999887 + outer loop + vertex 254.316 76.3786 32.5871 + vertex 236.33 82.982 32.6345 + vertex 237.322 73.9608 32.5041 + endloop + endfacet + facet normal -0.00206741 -0.0151829 0.999883 + outer loop + vertex 271.317 78.945 32.6613 + vertex 253.337 85.4071 32.7222 + vertex 254.316 76.3786 32.5871 + endloop + endfacet + facet normal 0.00107044 -0.0276446 0.999617 + outer loop + vertex 288.168 81.5926 32.7164 + vertex 271.317 78.945 32.6613 + vertex 289.128 72.7906 32.472 + endloop + endfacet + facet normal 0.00165753 -0.0275805 0.999618 + outer loop + vertex 305.67 75.4471 32.5179 + vertex 288.168 81.5926 32.7164 + vertex 289.128 72.7906 32.472 + endloop + endfacet + facet normal 0.00268267 -0.0463718 0.998921 + outer loop + vertex 321.768 78.091 32.5974 + vertex 305.67 75.4471 32.5179 + vertex 322.682 69.73 32.2068 + endloop + endfacet + facet normal -0.00418216 -0.0471199 0.99888 + outer loop + vertex 338.457 72.4657 32.4019 + vertex 321.768 78.091 32.5974 + vertex 322.682 69.73 32.2068 + endloop + endfacet + facet normal -0.0145855 -0.085057 0.996269 + outer loop + vertex 354.294 75.6511 32.9057 + vertex 338.457 72.4657 32.4019 + vertex 354.759 67.6735 32.2314 + endloop + endfacet + facet normal -0.0243238 -0.128598 0.991398 + outer loop + vertex 370.61 71.2266 33.0812 + vertex 354.759 67.6735 32.2314 + vertex 370.858 63.8687 32.1329 + endloop + endfacet + facet normal -0.00173818 -0.0999678 0.994989 + outer loop + vertex 355.165 60.5891 31.4388 + vertex 339.132 64.7009 31.8239 + vertex 339.641 57.7966 31.1311 + endloop + endfacet + facet normal 0.00721131 -0.0993125 0.99503 + outer loop + vertex 339.132 64.7009 31.8239 + vertex 323.4 62.0422 31.6725 + vertex 339.641 57.7966 31.1311 + endloop + endfacet + facet normal 0.00729276 -0.0675241 0.997691 + outer loop + vertex 323.4 62.0422 31.6725 + vertex 306.557 67.0956 32.1377 + vertex 307.252 59.3895 31.611 + endloop + endfacet + facet normal 0.00798473 -0.0674616 0.99769 + outer loop + vertex 306.557 67.0956 32.1377 + vertex 289.987 64.4163 32.0891 + vertex 307.252 59.3895 31.611 + endloop + endfacet + facet normal 0.003601 -0.0457064 0.998948 + outer loop + vertex 289.987 64.4163 32.0891 + vertex 272.263 70.1312 32.4145 + vertex 273.128 61.7667 32.0287 + endloop + endfacet + facet normal 0.00296654 -0.044981 0.998983 + outer loop + vertex 273.128 61.7667 32.0287 + vertex 255.279 67.5743 32.3432 + vertex 256.195 59.218 31.9642 + endloop + endfacet + facet normal 0.00192076 -0.0444648 0.999009 + outer loop + vertex 256.195 59.218 31.9642 + vertex 238.317 65.1772 32.2638 + vertex 239.287 56.8468 31.8912 + endloop + endfacet + facet normal 0.0008767 -0.0442511 0.99902 + outer loop + vertex 239.287 56.8468 31.8912 + vertex 221.441 62.9492 32.1771 + vertex 222.457 54.6485 31.8085 + endloop + endfacet + facet normal -8.43251e-05 -0.0432101 0.999066 + outer loop + vertex 222.457 54.6485 31.8085 + vertex 204.714 60.9054 32.0777 + vertex 205.759 52.6021 31.7186 + endloop + endfacet + facet normal -0.00152896 -0.0427805 0.999083 + outer loop + vertex 205.759 52.6021 31.7186 + vertex 188.194 59.0386 31.9674 + vertex 189.251 50.7525 31.6142 + endloop + endfacet + facet normal -0.00269491 -0.0419528 0.999116 + outer loop + vertex 189.251 50.7525 31.6142 + vertex 171.894 57.3552 31.8446 + vertex 172.94 49.0743 31.4997 + endloop + endfacet + facet normal -0.00377998 -0.0410688 0.999149 + outer loop + vertex 172.94 49.0743 31.4997 + vertex 155.767 55.8348 31.7126 + vertex 156.778 47.5587 31.3763 + endloop + endfacet + facet normal -0.00457996 -0.0400431 0.999187 + outer loop + vertex 156.778 47.5587 31.3763 + vertex 139.757 54.4531 31.5745 + vertex 140.711 46.1798 31.2474 + endloop + endfacet + facet normal -0.00497046 -0.0393079 0.999215 + outer loop + vertex 140.711 46.1798 31.2474 + vertex 123.851 53.168 31.4384 + vertex 124.734 44.9117 31.118 + endloop + endfacet + facet normal -0.00495232 -0.0378248 0.999272 + outer loop + vertex 124.734 44.9117 31.118 + vertex 108.095 51.9897 31.3035 + vertex 108.887 43.7267 30.9946 + endloop + endfacet + facet normal -0.00485762 -0.0368087 0.999311 + outer loop + vertex 108.887 43.7267 30.9946 + vertex 92.5053 50.8839 31.1786 + vertex 93.2013 42.6347 30.8781 + endloop + endfacet + facet normal -0.00435362 -0.0357692 0.999351 + outer loop + vertex 93.2013 42.6347 30.8781 + vertex 77.0464 49.859 31.0663 + vertex 77.6401 41.6225 30.7741 + endloop + endfacet + facet normal -0.00380891 -0.03527 0.999371 + outer loop + vertex 77.6401 41.6225 30.7741 + vertex 61.6387 48.9217 30.9707 + vertex 62.1292 40.7207 30.6832 + endloop + endfacet + facet normal -0.00306922 -0.0346108 0.999396 + outer loop + vertex 62.1292 40.7207 30.6832 + vertex 46.2261 48.1274 30.8908 + vertex 46.6054 39.9508 30.6088 + endloop + endfacet + facet normal -0.00211804 -0.0337342 0.999429 + outer loop + vertex 46.6054 39.9508 30.6088 + vertex 30.7959 47.5161 30.8307 + vertex 31.0578 39.3376 30.5552 + endloop + endfacet + facet normal -0.00146264 -0.0337843 0.999428 + outer loop + vertex 31.0578 39.3376 30.5552 + vertex 15.3709 47.113 30.7951 + vertex 15.5185 38.9727 30.5201 + endloop + endfacet + facet normal -0.00041536 -0.0334703 0.99944 + outer loop + vertex 15.5185 38.9727 30.5201 + vertex -0.0164628 46.9888 30.7821 + vertex 0.00957795 38.8441 30.5094 + endloop + endfacet + facet normal 0.000538257 -0.0335129 0.999438 + outer loop + vertex 0.00957795 38.8441 30.5094 + vertex -15.3775 47.1252 30.7953 + vertex -15.4709 38.9753 30.5221 + endloop + endfacet + facet normal 0.00141649 -0.0337422 0.99943 + outer loop + vertex -15.4709 38.9753 30.5221 + vertex -30.7339 47.5246 30.8324 + vertex -30.9455 39.363 30.5571 + endloop + endfacet + facet normal 0.00227763 -0.0343706 0.999407 + outer loop + vertex -30.9455 39.363 30.5571 + vertex -46.1091 48.1344 30.8933 + vertex -46.4349 39.9653 30.6131 + endloop + endfacet + facet normal 0.0031349 -0.0348012 0.999389 + outer loop + vertex -46.4349 39.9653 30.6131 + vertex -61.5045 48.9372 30.9728 + vertex -61.9422 40.7337 30.6885 + endloop + endfacet + facet normal 0.00377356 -0.0355861 0.999359 + outer loop + vertex -61.9422 40.7337 30.6885 + vertex -76.9094 49.8643 31.0702 + vertex -77.4542 41.64 30.7794 + endloop + endfacet + facet normal 0.0043604 -0.0365657 0.999322 + outer loop + vertex -77.4542 41.64 30.7794 + vertex -92.3221 50.8806 31.1824 + vertex -92.9696 42.6398 30.8837 + endloop + endfacet + facet normal 0.00487693 -0.0374375 0.999287 + outer loop + vertex -92.9696 42.6398 30.8837 + vertex -107.779 51.9745 31.3057 + vertex -108.522 43.7108 30.9997 + endloop + endfacet + facet normal 0.00503612 -0.0385208 0.999245 + outer loop + vertex -108.522 43.7108 30.9997 + vertex -123.356 53.1407 31.438 + vertex -124.188 44.8672 31.1232 + endloop + endfacet + facet normal 0.00484934 -0.0397936 0.999196 + outer loop + vertex -124.188 44.8672 31.1232 + vertex -139.14 54.4005 31.5755 + vertex -140.051 46.1294 31.2505 + endloop + endfacet + facet normal 0.00447847 -0.040706 0.999161 + outer loop + vertex -140.051 46.1294 31.2505 + vertex -155.176 55.7899 31.7118 + vertex -156.144 47.5086 31.3788 + endloop + endfacet + facet normal 0.00360568 -0.0418162 0.999119 + outer loop + vertex -156.144 47.5086 31.3788 + vertex -171.432 57.3162 31.8444 + vertex -172.441 49.0345 31.5015 + endloop + endfacet + facet normal -0.000130236 -0.0632084 0.998 + outer loop + vertex -173.515 41.459 31.0295 + vertex -188.876 50.726 31.6144 + vertex -189.95 43.1268 31.133 + endloop + endfacet + facet normal -0.00241531 -0.0856224 0.996325 + outer loop + vertex -173.515 41.459 31.0295 + vertex -189.95 43.1268 31.133 + vertex -174.635 34.717 30.4474 + endloop + endfacet + facet normal -0.000874603 -0.0631036 0.998007 + outer loop + vertex -188.876 50.726 31.6144 + vertex -205.405 52.5814 31.7172 + vertex -189.95 43.1268 31.133 + endloop + endfacet + facet normal -0.00164512 -0.0643581 0.997926 + outer loop + vertex -189.95 43.1268 31.133 + vertex -205.405 52.5814 31.7172 + vertex -206.458 44.9742 31.2249 + endloop + endfacet + facet normal -0.00428717 -0.0878768 0.996122 + outer loop + vertex -189.95 43.1268 31.133 + vertex -206.458 44.9742 31.2249 + vertex -191.067 36.4028 30.535 + endloop + endfacet + facet normal -0.00231902 -0.0642652 0.99793 + outer loop + vertex -205.405 52.5814 31.7172 + vertex -222.037 54.6132 31.8094 + vertex -206.458 44.9742 31.2249 + endloop + endfacet + facet normal -0.00293628 -0.0652588 0.997864 + outer loop + vertex -206.458 44.9742 31.2249 + vertex -222.037 54.6132 31.8094 + vertex -223.045 46.9932 31.3081 + endloop + endfacet + facet normal -0.00585362 -0.0891496 0.996001 + outer loop + vertex -206.458 44.9742 31.2249 + vertex -223.045 46.9932 31.3081 + vertex -207.541 38.2332 30.6152 + endloop + endfacet + facet normal -0.00343256 -0.0651933 0.997867 + outer loop + vertex -222.037 54.6132 31.8094 + vertex -238.785 56.8018 31.8948 + vertex -223.045 46.9932 31.3081 + endloop + endfacet + facet normal -0.00400766 -0.0661124 0.997804 + outer loop + vertex -223.045 46.9932 31.3081 + vertex -238.785 56.8018 31.8948 + vertex -239.735 49.1671 31.3851 + endloop + endfacet + facet normal -0.00717167 -0.0903355 0.995886 + outer loop + vertex -223.045 46.9932 31.3081 + vertex -239.735 49.1671 31.3851 + vertex -224.07 40.2351 30.6877 + endloop + endfacet + facet normal -0.00451274 -0.0660497 0.997806 + outer loop + vertex -238.785 56.8018 31.8948 + vertex -255.627 59.125 31.9724 + vertex -239.735 49.1671 31.3851 + endloop + endfacet + facet normal -0.00516366 -0.0670843 0.997734 + outer loop + vertex -239.735 49.1671 31.3851 + vertex -255.627 59.125 31.9724 + vertex -256.506 51.478 31.4537 + endloop + endfacet + facet normal -0.00849354 -0.091193 0.995797 + outer loop + vertex -239.735 49.1671 31.3851 + vertex -256.506 51.478 31.4537 + vertex -240.677 42.3795 30.7555 + endloop + endfacet + facet normal -0.0062523 -0.0669593 0.997736 + outer loop + vertex -255.627 59.125 31.9724 + vertex -272.466 61.593 32.0325 + vertex -256.506 51.478 31.4537 + endloop + endfacet + facet normal -0.0066648 -0.0676076 0.99769 + outer loop + vertex -256.506 51.478 31.4537 + vertex -272.466 61.593 32.0325 + vertex -273.269 53.9209 31.5073 + endloop + endfacet + facet normal -0.0102261 -0.0920013 0.995706 + outer loop + vertex -256.506 51.478 31.4537 + vertex -273.269 53.9209 31.5073 + vertex -257.349 44.6633 30.8154 + endloop + endfacet + facet normal -0.00831829 -0.0674345 0.997689 + outer loop + vertex -272.466 61.593 32.0325 + vertex -289.162 64.2206 32.0709 + vertex -273.269 53.9209 31.5073 + endloop + endfacet + facet normal -0.00856155 -0.0678083 0.997662 + outer loop + vertex -273.269 53.9209 31.5073 + vertex -289.162 64.2206 32.0709 + vertex -289.911 56.5265 31.5416 + endloop + endfacet + facet normal -0.0124923 -0.0928871 0.995598 + outer loop + vertex -273.269 53.9209 31.5073 + vertex -289.911 56.5265 31.5416 + vertex -274.013 47.0891 30.8605 + endloop + endfacet + facet normal -0.00925242 -0.067741 0.99766 + outer loop + vertex -289.162 64.2206 32.0709 + vertex -305.628 67.0097 32.1076 + vertex -289.911 56.5265 31.5416 + endloop + endfacet + facet normal -0.00908082 -0.0674847 0.997679 + outer loop + vertex -289.911 56.5265 31.5416 + vertex -305.628 67.0097 32.1076 + vertex -306.383 59.286 31.5783 + endloop + endfacet + facet normal -0.0132969 -0.0926237 0.995612 + outer loop + vertex -289.911 56.5265 31.5416 + vertex -306.383 59.286 31.5783 + vertex -290.59 49.6455 30.8923 + endloop + endfacet + facet normal -0.00599472 -0.0677865 0.997682 + outer loop + vertex -305.628 67.0097 32.1076 + vertex -321.906 69.8768 32.2046 + vertex -306.383 59.286 31.5783 + endloop + endfacet + facet normal -0.00635582 -0.0683135 0.997644 + outer loop + vertex -306.383 59.286 31.5783 + vertex -321.906 69.8768 32.2046 + vertex -322.715 62.1488 31.6703 + endloop + endfacet + facet normal -0.0107117 -0.0930975 0.995599 + outer loop + vertex -306.383 59.286 31.5783 + vertex -322.715 62.1488 31.6703 + vertex -307.045 52.3852 30.9259 + endloop + endfacet + facet normal 0.00337975 -0.0693285 0.997588 + outer loop + vertex -321.906 69.8768 32.2046 + vertex -338.1 72.6665 32.4533 + vertex -322.715 62.1488 31.6703 + endloop + endfacet + facet normal 0.000848347 -0.0730121 0.997331 + outer loop + vertex -322.715 62.1488 31.6703 + vertex -338.1 72.6665 32.4533 + vertex -338.908 64.9692 31.8905 + endloop + endfacet + facet normal -0.00303563 -0.0951658 0.995457 + outer loop + vertex -322.715 62.1488 31.6703 + vertex -338.908 64.9692 31.8905 + vertex -323.376 55.2406 31.0078 + endloop + endfacet + facet normal 0.0179912 -0.0747914 0.997037 + outer loop + vertex -338.1 72.6665 32.4533 + vertex -354.208 75.1872 32.9331 + vertex -338.908 64.9692 31.8905 + endloop + endfacet + facet normal 0.0117106 -0.0841295 0.996386 + outer loop + vertex -338.908 64.9692 31.8905 + vertex -354.208 75.1872 32.9331 + vertex -354.687 67.5287 32.2921 + endloop + endfacet + facet normal 0.00886868 -0.101402 0.994806 + outer loop + vertex -338.908 64.9692 31.8905 + vertex -354.687 67.5287 32.2921 + vertex -339.496 58.084 31.1939 + endloop + endfacet + facet normal 0.035927 -0.0855849 0.995683 + outer loop + vertex -354.208 75.1872 32.9331 + vertex -370.069 77.2562 33.6832 + vertex -354.687 67.5287 32.2921 + endloop + endfacet + facet normal 0.0247078 -0.103136 0.99436 + outer loop + vertex -354.687 67.5287 32.2921 + vertex -370.069 77.2562 33.6832 + vertex -368.953 69.4295 32.8437 + endloop + endfacet + facet normal 0.0379426 -0.0705337 0.996788 + outer loop + vertex -354.208 75.1872 32.9331 + vertex -369.245 85.5412 34.2381 + vertex -370.069 77.2562 33.6832 + endloop + endfacet + facet normal 0.0455572 -0.0595259 0.997187 + outer loop + vertex -353.177 83.4747 33.3807 + vertex -369.245 85.5412 34.2381 + vertex -354.208 75.1872 32.9331 + endloop + endfacet + facet normal 0.0208861 -0.0565095 0.998184 + outer loop + vertex -338.1 72.6665 32.4533 + vertex -353.177 83.4747 33.3807 + vertex -354.208 75.1872 32.9331 + endloop + endfacet + facet normal 0.024881 -0.0509543 0.998391 + outer loop + vertex -337.083 81.0216 32.8544 + vertex -353.177 83.4747 33.3807 + vertex -338.1 72.6665 32.4533 + endloop + endfacet + facet normal 0.0271447 -0.0362279 0.998975 + outer loop + vertex -337.083 81.0216 32.8544 + vertex -351.88 92.2374 33.6632 + vertex -353.177 83.4747 33.3807 + endloop + endfacet + facet normal 0.0515959 -0.039811 0.997874 + outer loop + vertex -351.88 92.2374 33.6632 + vertex -367.795 94.2331 34.5658 + vertex -353.177 83.4747 33.3807 + endloop + endfacet + facet normal 0.0528976 -0.0295608 0.998162 + outer loop + vertex -351.88 92.2374 33.6632 + vertex -366.232 103.237 34.7495 + vertex -367.795 94.2331 34.5658 + endloop + endfacet + facet normal 0.0557257 -0.0258658 0.998111 + outer loop + vertex -350.521 101.237 33.8206 + vertex -366.232 103.237 34.7495 + vertex -351.88 92.2374 33.6632 + endloop + endfacet + facet normal 0.031208 -0.0221838 0.999267 + outer loop + vertex -335.949 89.8361 33.1124 + vertex -350.521 101.237 33.8206 + vertex -351.88 92.2374 33.6632 + endloop + endfacet + facet normal 0.0328098 -0.020136 0.999259 + outer loop + vertex -334.761 98.8584 33.2552 + vertex -350.521 101.237 33.8206 + vertex -335.949 89.8361 33.1124 + endloop + endfacet + facet normal 0.0138562 -0.017647 0.999748 + outer loop + vertex -320 87.1014 32.8431 + vertex -334.761 98.8584 33.2552 + vertex -335.949 89.8361 33.1124 + endloop + endfacet + facet normal 0.0118124 -0.029542 0.999494 + outer loop + vertex -320 87.1014 32.8431 + vertex -335.949 89.8361 33.1124 + vertex -320.992 78.2712 32.5938 + endloop + endfacet + facet normal 0.00112028 -0.0283436 0.999598 + outer loop + vertex -304.792 75.4031 32.4943 + vertex -320 87.1014 32.8431 + vertex -320.992 78.2712 32.5938 + endloop + endfacet + facet normal -0.0019792 -0.0458273 0.998947 + outer loop + vertex -304.792 75.4031 32.4943 + vertex -320.992 78.2712 32.5938 + vertex -305.628 67.0097 32.1076 + endloop + endfacet + facet normal 0.00114333 -0.0283136 0.999598 + outer loop + vertex -303.873 84.2288 32.7432 + vertex -320 87.1014 32.8431 + vertex -304.792 75.4031 32.4943 + endloop + endfacet + facet normal -0.00244859 -0.0279398 0.999607 + outer loop + vertex -288.337 72.5999 32.4563 + vertex -303.873 84.2288 32.7432 + vertex -304.792 75.4031 32.4943 + endloop + endfacet + facet normal -0.00542523 -0.0454042 0.998954 + outer loop + vertex -288.337 72.5999 32.4563 + vertex -304.792 75.4031 32.4943 + vertex -289.162 64.2206 32.0709 + endloop + endfacet + facet normal -0.00228796 -0.0277253 0.999613 + outer loop + vertex -287.432 81.419 32.7029 + vertex -303.873 84.2288 32.7432 + vertex -288.337 72.5999 32.4563 + endloop + endfacet + facet normal -0.00186823 -0.0277684 0.999613 + outer loop + vertex -271.608 69.9547 32.4141 + vertex -287.432 81.419 32.7029 + vertex -288.337 72.5999 32.4563 + endloop + endfacet + facet normal -0.00461121 -0.0451065 0.998972 + outer loop + vertex -271.608 69.9547 32.4141 + vertex -288.337 72.5999 32.4563 + vertex -272.466 61.593 32.0325 + endloop + endfacet + facet normal -0.00166688 -0.0274907 0.999621 + outer loop + vertex -270.693 78.7645 32.6579 + vertex -287.432 81.419 32.7029 + vertex -271.608 69.9547 32.4141 + endloop + endfacet + facet normal -0.000187981 -0.0276442 0.999618 + outer loop + vertex -254.723 67.4712 32.3485 + vertex -270.693 78.7645 32.6579 + vertex -271.608 69.9547 32.4141 + endloop + endfacet + facet normal -0.00270298 -0.0447266 0.998996 + outer loop + vertex -254.723 67.4712 32.3485 + vertex -271.608 69.9547 32.4141 + vertex -255.627 59.125 31.9724 + endloop + endfacet + facet normal -9.22395e-05 -0.0275089 0.999622 + outer loop + vertex -253.791 76.266 32.5907 + vertex -270.693 78.7645 32.6579 + vertex -254.723 67.4712 32.3485 + endloop + endfacet + facet normal 0.000972085 -0.0276216 0.999618 + outer loop + vertex -237.835 65.1224 32.2672 + vertex -253.791 76.266 32.5907 + vertex -254.723 67.4712 32.3485 + endloop + endfacet + facet normal -0.00138589 -0.0445546 0.999006 + outer loop + vertex -237.835 65.1224 32.2672 + vertex -254.723 67.4712 32.3485 + vertex -238.785 56.8018 31.8948 + endloop + endfacet + facet normal 0.00134974 -0.0270812 0.999632 + outer loop + vertex -236.88 73.9128 32.5041 + vertex -253.791 76.266 32.5907 + vertex -237.835 65.1224 32.2672 + endloop + endfacet + facet normal 0.00188705 -0.0271395 0.99963 + outer loop + vertex -221.047 62.9195 32.1757 + vertex -236.88 73.9128 32.5041 + vertex -237.835 65.1224 32.2672 + endloop + endfacet + facet normal -0.000330635 -0.044015 0.999031 + outer loop + vertex -221.047 62.9195 32.1757 + vertex -237.835 65.1224 32.2672 + vertex -222.037 54.6132 31.8094 + endloop + endfacet + facet normal 0.0021411 -0.0267739 0.999639 + outer loop + vertex -220.071 71.6988 32.4088 + vertex -236.88 73.9128 32.5041 + vertex -221.047 62.9195 32.1757 + endloop + endfacet + facet normal 0.00305377 -0.0148444 0.999885 + outer loop + vertex -236.88 73.9128 32.5041 + vertex -252.84 85.2941 32.7218 + vertex -253.791 76.266 32.5907 + endloop + endfacet + facet normal 0.00200391 -0.014734 0.999889 + outer loop + vertex -252.84 85.2941 32.7218 + vertex -269.744 87.7927 32.7925 + vertex -253.791 76.266 32.5907 + endloop + endfacet + facet normal 0.00317375 -0.00682186 0.999972 + outer loop + vertex -252.84 85.2941 32.7218 + vertex -268.771 96.8925 32.8515 + vertex -269.744 87.7927 32.7925 + endloop + endfacet + facet normal 0.00173912 -0.00666843 0.999976 + outer loop + vertex -268.771 96.8925 32.8515 + vertex -285.463 99.5483 32.8982 + vertex -269.744 87.7927 32.7925 + endloop + endfacet + facet normal 0.00172123 -0.00669234 0.999976 + outer loop + vertex -269.744 87.7927 32.7925 + vertex -285.463 99.5483 32.8982 + vertex -286.468 90.4492 32.8391 + endloop + endfacet + facet normal 0.000408836 -0.014953 0.999888 + outer loop + vertex -269.744 87.7927 32.7925 + vertex -286.468 90.4492 32.8391 + vertex -270.693 78.7645 32.6579 + endloop + endfacet + facet normal 0.00133709 -0.00664992 0.999977 + outer loop + vertex -285.463 99.5483 32.8982 + vertex -301.818 102.357 32.9388 + vertex -286.468 90.4492 32.8391 + endloop + endfacet + facet normal 0.00125771 -0.00675225 0.999976 + outer loop + vertex -286.468 90.4492 32.8391 + vertex -301.818 102.357 32.9388 + vertex -302.872 93.2658 32.8787 + endloop + endfacet + facet normal -0.000167669 -0.0150522 0.999887 + outer loop + vertex -286.468 90.4492 32.8391 + vertex -302.872 93.2658 32.8787 + vertex -287.432 81.419 32.7029 + endloop + endfacet + facet normal 0.00504459 -0.0071908 0.999961 + outer loop + vertex -301.818 102.357 32.9388 + vertex -317.807 105.22 33.04 + vertex -302.872 93.2658 32.8787 + endloop + endfacet + facet normal 0.00505291 -0.0071804 0.999961 + outer loop + vertex -302.872 93.2658 32.8787 + vertex -317.807 105.22 33.04 + vertex -318.93 96.1366 32.9805 + endloop + endfacet + facet normal 0.00358572 -0.0153842 0.999875 + outer loop + vertex -302.872 93.2658 32.8787 + vertex -318.93 96.1366 32.9805 + vertex -303.873 84.2288 32.7432 + endloop + endfacet + facet normal 0.0161029 -0.00854538 0.999834 + outer loop + vertex -317.807 105.22 33.04 + vertex -333.533 107.928 33.3164 + vertex -318.93 96.1366 32.9805 + endloop + endfacet + facet normal 0.0158206 -0.00889496 0.999835 + outer loop + vertex -318.93 96.1366 32.9805 + vertex -333.533 107.928 33.3164 + vertex -334.761 98.8584 33.2552 + endloop + endfacet + facet normal 0.0350037 -0.0114887 0.999321 + outer loop + vertex -333.533 107.928 33.3164 + vertex -349.149 110.273 33.8904 + vertex -334.761 98.8584 33.2552 + endloop + endfacet + facet normal 0.0355463 -0.00787913 0.999337 + outer loop + vertex -333.533 107.928 33.3164 + vertex -347.756 119.294 33.912 + vertex -349.149 110.273 33.8904 + endloop + endfacet + facet normal 0.0601358 -0.011673 0.998122 + outer loop + vertex -347.756 119.294 33.912 + vertex -363.142 121.184 34.8611 + vertex -349.149 110.273 33.8904 + endloop + endfacet + facet normal 0.058775 -0.0134234 0.998181 + outer loop + vertex -349.149 110.273 33.8904 + vertex -363.142 121.184 34.8611 + vertex -364.684 112.251 34.8317 + endloop + endfacet + facet normal 0.0583722 -0.0165754 0.998157 + outer loop + vertex -349.149 110.273 33.8904 + vertex -364.684 112.251 34.8317 + vertex -350.521 101.237 33.8206 + endloop + endfacet + facet normal 0.0360014 -0.00730897 0.999325 + outer loop + vertex -332.264 116.981 33.3369 + vertex -347.756 119.294 33.912 + vertex -333.533 107.928 33.3164 + endloop + endfacet + facet normal 0.0361496 -0.00631701 0.999326 + outer loop + vertex -332.264 116.981 33.3369 + vertex -346.334 128.318 33.9175 + vertex -347.756 119.294 33.912 + endloop + endfacet + facet normal 0.060673 -0.0101821 0.998106 + outer loop + vertex -346.334 128.318 33.9175 + vertex -361.584 130.182 34.8636 + vertex -347.756 119.294 33.912 + endloop + endfacet + facet normal 0.0606285 -0.0105457 0.998105 + outer loop + vertex -346.334 128.318 33.9175 + vertex -360.006 139.228 34.8633 + vertex -361.584 130.182 34.8636 + endloop + endfacet + facet normal 0.0615641 -0.00936926 0.998059 + outer loop + vertex -344.903 137.32 33.9138 + vertex -360.006 139.228 34.8633 + vertex -346.334 128.318 33.9175 + endloop + endfacet + facet normal 0.0367241 -0.00542083 0.999311 + outer loop + vertex -330.965 126.013 33.3403 + vertex -344.903 137.32 33.9138 + vertex -346.334 128.318 33.9175 + endloop + endfacet + facet normal 0.0370257 -0.00504861 0.999302 + outer loop + vertex -329.664 135.007 33.3375 + vertex -344.903 137.32 33.9138 + vertex -330.965 126.013 33.3403 + endloop + endfacet + facet normal 0.017527 -0.00222678 0.999844 + outer loop + vertex -315.444 123.333 33.0622 + vertex -329.664 135.007 33.3375 + vertex -330.965 126.013 33.3403 + endloop + endfacet + facet normal 0.0174605 -0.00261174 0.999844 + outer loop + vertex -315.444 123.333 33.0622 + vertex -330.965 126.013 33.3403 + vertex -316.639 114.29 33.0595 + endloop + endfacet + facet normal 0.00614781 -0.00111692 0.99998 + outer loop + vertex -300.73 111.439 32.9585 + vertex -315.444 123.333 33.0622 + vertex -316.639 114.29 33.0595 + endloop + endfacet + facet normal 0.00583385 -0.00286879 0.999979 + outer loop + vertex -300.73 111.439 32.9585 + vertex -316.639 114.29 33.0595 + vertex -301.818 102.357 32.9388 + endloop + endfacet + facet normal 0.00614086 -0.00112553 0.999981 + outer loop + vertex -299.621 120.495 32.9618 + vertex -315.444 123.333 33.0622 + vertex -300.73 111.439 32.9585 + endloop + endfacet + facet normal 0.00235753 -0.000662038 0.999997 + outer loop + vertex -284.436 108.639 32.9182 + vertex -299.621 120.495 32.9618 + vertex -300.73 111.439 32.9585 + endloop + endfacet + facet normal 0.00205366 -0.0024304 0.999995 + outer loop + vertex -284.436 108.639 32.9182 + vertex -300.73 111.439 32.9585 + vertex -285.463 99.5483 32.8982 + endloop + endfacet + facet normal 0.00229585 -0.00074104 0.999997 + outer loop + vertex -283.384 117.706 32.9225 + vertex -299.621 120.495 32.9618 + vertex -284.436 108.639 32.9182 + endloop + endfacet + facet normal 0.00619665 -0.000814502 0.99998 + outer loop + vertex -299.621 120.495 32.9618 + vertex -314.245 132.336 33.0621 + vertex -315.444 123.333 33.0622 + endloop + endfacet + facet normal 0.00621667 -0.000789767 0.99998 + outer loop + vertex -298.495 129.515 32.962 + vertex -314.245 132.336 33.0621 + vertex -299.621 120.495 32.9618 + endloop + endfacet + facet normal 0.0172647 -0.00285111 0.999847 + outer loop + vertex -316.639 114.29 33.0595 + vertex -330.965 126.013 33.3403 + vertex -332.264 116.981 33.3369 + endloop + endfacet + facet normal 0.0170094 -0.004334 0.999846 + outer loop + vertex -316.639 114.29 33.0595 + vertex -332.264 116.981 33.3369 + vertex -317.807 105.22 33.04 + endloop + endfacet + facet normal 0.0174557 -0.00231366 0.999845 + outer loop + vertex -314.245 132.336 33.0621 + vertex -329.664 135.007 33.3375 + vertex -315.444 123.333 33.0622 + endloop + endfacet + facet normal 0.0173556 -0.00289141 0.999845 + outer loop + vertex -314.245 132.336 33.0621 + vertex -328.417 143.94 33.3417 + vertex -329.664 135.007 33.3375 + endloop + endfacet + facet normal 0.0373586 -0.00568227 0.999286 + outer loop + vertex -328.417 143.94 33.3417 + vertex -343.506 146.235 33.9188 + vertex -329.664 135.007 33.3375 + endloop + endfacet + facet normal 0.0373448 -0.00577324 0.999286 + outer loop + vertex -328.417 143.94 33.3417 + vertex -342.235 155.124 33.9227 + vertex -343.506 146.235 33.9188 + endloop + endfacet + facet normal 0.062729 -0.00940423 0.997986 + outer loop + vertex -342.235 155.124 33.9227 + vertex -356.949 156.974 34.865 + vertex -343.506 146.235 33.9188 + endloop + endfacet + facet normal 0.0619011 -0.0104442 0.998028 + outer loop + vertex -343.506 146.235 33.9188 + vertex -356.949 156.974 34.865 + vertex -358.444 148.161 34.8655 + endloop + endfacet + facet normal 0.0619243 -0.010264 0.998028 + outer loop + vertex -343.506 146.235 33.9188 + vertex -358.444 148.161 34.8655 + vertex -344.903 137.32 33.9138 + endloop + endfacet + facet normal 0.0379935 -0.00497078 0.999266 + outer loop + vertex -327.309 152.863 33.3439 + vertex -342.235 155.124 33.9227 + vertex -328.417 143.94 33.3417 + endloop + endfacet + facet normal 0.0176487 -0.00253338 0.999841 + outer loop + vertex -313.097 141.29 33.0645 + vertex -328.417 143.94 33.3417 + vertex -314.245 132.336 33.0621 + endloop + endfacet + facet normal 0.0368305 -0.00633417 0.999301 + outer loop + vertex -329.664 135.007 33.3375 + vertex -343.506 146.235 33.9188 + vertex -344.903 137.32 33.9138 + endloop + endfacet + facet normal 0.0366904 -0.00564503 0.999311 + outer loop + vertex -330.965 126.013 33.3403 + vertex -346.334 128.318 33.9175 + vertex -332.264 116.981 33.3369 + endloop + endfacet + facet normal 0.0167795 -0.00461668 0.999849 + outer loop + vertex -317.807 105.22 33.04 + vertex -332.264 116.981 33.3369 + vertex -333.533 107.928 33.3164 + endloop + endfacet + facet normal 0.00581449 -0.00289283 0.999979 + outer loop + vertex -301.818 102.357 32.9388 + vertex -316.639 114.29 33.0595 + vertex -317.807 105.22 33.04 + endloop + endfacet + facet normal 0.00206402 -0.0024171 0.999995 + outer loop + vertex -285.463 99.5483 32.8982 + vertex -300.73 111.439 32.9585 + vertex -301.818 102.357 32.9388 + endloop + endfacet + facet normal 0.00240707 -0.00247033 0.999994 + outer loop + vertex -268.771 96.8925 32.8515 + vertex -284.436 108.639 32.9182 + vertex -285.463 99.5483 32.8982 + endloop + endfacet + facet normal 0.00240298 -0.00247578 0.999994 + outer loop + vertex -267.781 105.987 32.8716 + vertex -284.436 108.639 32.9182 + vertex -268.771 96.8925 32.8515 + endloop + endfacet + facet normal 0.00320432 -0.00677988 0.999972 + outer loop + vertex -251.88 94.3901 32.7804 + vertex -268.771 96.8925 32.8515 + vertex -252.84 85.2941 32.7218 + endloop + endfacet + facet normal 0.00309585 -0.0147854 0.999886 + outer loop + vertex -235.92 82.9294 32.6344 + vertex -252.84 85.2941 32.7218 + vertex -236.88 73.9128 32.5041 + endloop + endfacet + facet normal 0.0017442 -0.0150933 0.999885 + outer loop + vertex -253.791 76.266 32.5907 + vertex -269.744 87.7927 32.7925 + vertex -270.693 78.7645 32.6579 + endloop + endfacet + facet normal 0.000298508 -0.0151019 0.999886 + outer loop + vertex -270.693 78.7645 32.6579 + vertex -286.468 90.4492 32.8391 + vertex -287.432 81.419 32.7029 + endloop + endfacet + facet normal -0.000108358 -0.0149749 0.999888 + outer loop + vertex -287.432 81.419 32.7029 + vertex -302.872 93.2658 32.8787 + vertex -303.873 84.2288 32.7432 + endloop + endfacet + facet normal 0.00340818 -0.0156086 0.999872 + outer loop + vertex -303.873 84.2288 32.7432 + vertex -318.93 96.1366 32.9805 + vertex -320 87.1014 32.8431 + endloop + endfacet + facet normal 0.010948 -0.0306589 0.99947 + outer loop + vertex -320.992 78.2712 32.5938 + vertex -335.949 89.8361 33.1124 + vertex -337.083 81.0216 32.8544 + endloop + endfacet + facet normal 0.00811177 -0.0471936 0.998853 + outer loop + vertex -320.992 78.2712 32.5938 + vertex -337.083 81.0216 32.8544 + vertex -321.906 69.8768 32.2046 + endloop + endfacet + facet normal 0.0144406 -0.0169135 0.999753 + outer loop + vertex -318.93 96.1366 32.9805 + vertex -334.761 98.8584 33.2552 + vertex -320 87.1014 32.8431 + endloop + endfacet + facet normal 0.0339094 -0.0128693 0.999342 + outer loop + vertex -334.761 98.8584 33.2552 + vertex -349.149 110.273 33.8904 + vertex -350.521 101.237 33.8206 + endloop + endfacet + facet normal 0.029563 -0.0330404 0.999017 + outer loop + vertex -335.949 89.8361 33.1124 + vertex -351.88 92.2374 33.6632 + vertex -337.083 81.0216 32.8544 + endloop + endfacet + facet normal 0.00693634 -0.0487904 0.998785 + outer loop + vertex -321.906 69.8768 32.2046 + vertex -337.083 81.0216 32.8544 + vertex -338.1 72.6665 32.4533 + endloop + endfacet + facet normal -0.00216374 -0.0460785 0.998935 + outer loop + vertex -305.628 67.0097 32.1076 + vertex -320.992 78.2712 32.5938 + vertex -321.906 69.8768 32.2046 + endloop + endfacet + facet normal -0.00547881 -0.045479 0.99895 + outer loop + vertex -289.162 64.2206 32.0709 + vertex -304.792 75.4031 32.4943 + vertex -305.628 67.0097 32.1076 + endloop + endfacet + facet normal -0.00485697 -0.0454602 0.998954 + outer loop + vertex -272.466 61.593 32.0325 + vertex -288.337 72.5999 32.4563 + vertex -289.162 64.2206 32.0709 + endloop + endfacet + facet normal -0.00306834 -0.0452648 0.99897 + outer loop + vertex -255.627 59.125 31.9724 + vertex -271.608 69.9547 32.4141 + vertex -272.466 61.593 32.0325 + endloop + endfacet + facet normal -0.00158257 -0.0448479 0.998993 + outer loop + vertex -238.785 56.8018 31.8948 + vertex -254.723 67.4712 32.3485 + vertex -255.627 59.125 31.9724 + endloop + endfacet + facet normal -0.000739449 -0.0446283 0.999003 + outer loop + vertex -222.037 54.6132 31.8094 + vertex -237.835 65.1224 32.2672 + vertex -238.785 56.8018 31.8948 + endloop + endfacet + facet normal 0.000153973 -0.0440726 0.999028 + outer loop + vertex -205.405 52.5814 31.7172 + vertex -221.047 62.9195 32.1757 + vertex -222.037 54.6132 31.8094 + endloop + endfacet + facet normal 0.000703637 -0.0432426 0.999064 + outer loop + vertex -204.39 60.8808 32.0758 + vertex -221.047 62.9195 32.1757 + vertex -205.405 52.5814 31.7172 + endloop + endfacet + facet normal 0.00310659 -0.0417556 0.999123 + outer loop + vertex -171.432 57.3162 31.8444 + vertex -187.851 59.0101 31.9663 + vertex -172.441 49.0345 31.5015 + endloop + endfacet + facet normal 0.00135232 -0.0433218 0.99906 + outer loop + vertex -188.876 50.726 31.6144 + vertex -204.39 60.8808 32.0758 + vertex -205.405 52.5814 31.7172 + endloop + endfacet + facet normal 0.00398582 -0.0259625 0.999655 + outer loop + vertex -186.871 67.7725 32.19 + vertex -203.403 69.6483 32.3046 + vertex -187.851 59.0101 31.9663 + endloop + endfacet + facet normal 0.0027149 -0.0268375 0.999636 + outer loop + vertex -204.39 60.8808 32.0758 + vertex -220.071 71.6988 32.4088 + vertex -221.047 62.9195 32.1757 + endloop + endfacet + facet normal 0.00455142 -0.0144231 0.999886 + outer loop + vertex -202.436 78.6496 32.43 + vertex -219.105 80.7109 32.5356 + vertex -203.403 69.6483 32.3046 + endloop + endfacet + facet normal 0.00371288 -0.0148511 0.999883 + outer loop + vertex -220.071 71.6988 32.4088 + vertex -235.92 82.9294 32.6344 + vertex -236.88 73.9128 32.5041 + endloop + endfacet + facet normal 0.00495891 -0.00680824 0.999965 + outer loop + vertex -218.142 89.7928 32.5927 + vertex -234.962 92.0221 32.6913 + vertex -219.105 80.7109 32.5356 + endloop + endfacet + facet normal 0.00420045 -0.00688503 0.999967 + outer loop + vertex -235.92 82.9294 32.6344 + vertex -251.88 94.3901 32.7804 + vertex -252.84 85.2941 32.7218 + endloop + endfacet + facet normal 0.00491355 -0.00266274 0.999984 + outer loop + vertex -233.995 101.109 32.7107 + vertex -250.909 103.483 32.8002 + vertex -234.962 92.0221 32.6913 + endloop + endfacet + facet normal 0.00381924 -0.00262986 0.999989 + outer loop + vertex -251.88 94.3901 32.7804 + vertex -267.781 105.987 32.8716 + vertex -268.771 96.8925 32.8515 + endloop + endfacet + facet normal 0.00407223 -0.00100449 0.999991 + outer loop + vertex -249.921 112.552 32.8052 + vertex -266.77 115.058 32.8764 + vertex -250.909 103.483 32.8002 + endloop + endfacet + facet normal 0.00267232 -0.000784733 0.999996 + outer loop + vertex -267.781 105.987 32.8716 + vertex -283.384 117.706 32.9225 + vertex -284.436 108.639 32.9182 + endloop + endfacet + facet normal 0.00266999 -0.000412386 0.999996 + outer loop + vertex -265.739 124.1 32.8774 + vertex -282.313 126.74 32.9227 + vertex -266.77 115.058 32.8764 + endloop + endfacet + facet normal 0.00236994 -0.000309713 0.999997 + outer loop + vertex -283.384 117.706 32.9225 + vertex -298.495 129.515 32.962 + vertex -299.621 120.495 32.9618 + endloop + endfacet + facet normal 0.00244916 -0.000118471 0.999997 + outer loop + vertex -281.25 135.737 32.9212 + vertex -297.4 138.491 32.961 + vertex -282.313 126.74 32.9227 + endloop + endfacet + facet normal 0.00616807 -0.00106112 0.99998 + outer loop + vertex -298.495 129.515 32.962 + vertex -313.097 141.29 33.0645 + vertex -314.245 132.336 33.0621 + endloop + endfacet + facet normal 0.0066871 -0.000382061 0.999978 + outer loop + vertex -296.378 147.442 32.9576 + vertex -312.063 150.224 33.0636 + vertex -297.4 138.491 32.961 + endloop + endfacet + facet normal 0.0176636 -0.00244713 0.999841 + outer loop + vertex -313.097 141.29 33.0645 + vertex -327.309 152.863 33.3439 + vertex -328.417 143.94 33.3417 + endloop + endfacet + facet normal 0.0181915 -0.00252982 0.999831 + outer loop + vertex -311.129 159.186 33.0692 + vertex -326.299 161.844 33.352 + vertex -312.063 150.224 33.0636 + endloop + endfacet + facet normal 0.0379215 -0.00544614 0.999266 + outer loop + vertex -327.309 152.863 33.3439 + vertex -341.078 164.121 33.9278 + vertex -342.235 155.124 33.9227 + endloop + endfacet + facet normal 0.0643161 -0.00884027 0.99789 + outer loop + vertex -341.078 164.121 33.9278 + vertex -355.578 165.878 34.878 + vertex -342.235 155.124 33.9227 + endloop + endfacet + facet normal 0.0371909 -0.00486085 0.999296 + outer loop + vertex -325.304 170.938 33.3592 + vertex -339.677 173.373 33.906 + vertex -326.299 161.844 33.352 + endloop + endfacet + facet normal 0.0643687 -0.00840712 0.997891 + outer loop + vertex -341.078 164.121 33.9278 + vertex -354.171 175.119 34.865 + vertex -355.578 165.878 34.878 + endloop + endfacet + facet normal 0.0627953 0.00193893 0.998025 + outer loop + vertex -337.867 182.663 33.774 + vertex -351.732 185.346 34.6412 + vertex -339.677 173.373 33.906 + endloop + endfacet + facet normal 0.140762 -0.0325118 0.989509 + outer loop + vertex -361.938 183.392 35.7277 + vertex -369.124 184.389 36.7826 + vertex -364.023 179.374 35.8923 + endloop + endfacet + facet normal 0.20462 -0.0240802 0.978545 + outer loop + vertex -369.124 184.389 36.7826 + vertex -373.934 189.87 37.9234 + vertex -374.575 185.252 37.9437 + endloop + endfacet + facet normal 0.144581 -0.0187824 0.989315 + outer loop + vertex -363.411 174.224 35.7499 + vertex -369.707 179.791 36.7757 + vertex -370.255 175.161 36.7679 + endloop + endfacet + facet normal 0.0965967 -0.0133191 0.995234 + outer loop + vertex -355.578 165.878 34.878 + vertex -354.171 175.119 34.865 + vertex -363.411 174.224 35.7499 + endloop + endfacet + facet normal 0.14777 -0.0169579 0.988876 + outer loop + vertex -365.19 170.164 35.8859 + vertex -370.997 170.625 36.7616 + vertex -364.754 165.167 35.7351 + endloop + endfacet + facet normal 0.0625181 -0.0110794 0.997982 + outer loop + vertex -342.235 155.124 33.9227 + vertex -355.578 165.878 34.878 + vertex -356.949 156.974 34.865 + endloop + endfacet + facet normal 0.13616 -0.0365552 0.990012 + outer loop + vertex -364.754 165.167 35.7351 + vertex -371.889 166.198 36.7544 + vertex -366.765 161.312 35.8694 + endloop + endfacet + facet normal 0.190522 -0.0409743 0.980827 + outer loop + vertex -371.889 166.198 36.7544 + vertex -376.79 171.505 37.9282 + vertex -377.745 167.102 37.9298 + endloop + endfacet + facet normal 0.134971 -0.0275858 0.990465 + outer loop + vertex -366.375 156.43 35.7281 + vertex -372.78 161.849 36.7518 + vertex -373.643 157.525 36.7491 + endloop + endfacet + facet normal 0.0920658 -0.0155623 0.995631 + outer loop + vertex -358.444 148.161 34.8655 + vertex -356.949 156.974 34.865 + vertex -366.375 156.43 35.7281 + endloop + endfacet + facet normal 0.142947 -0.0152415 0.989613 + outer loop + vertex -368.421 152.617 35.8632 + vertex -374.488 153.166 36.7479 + vertex -368.005 147.644 35.7264 + endloop + endfacet + facet normal 0.0613618 -0.010969 0.998055 + outer loop + vertex -344.903 137.32 33.9138 + vertex -358.444 148.161 34.8655 + vertex -360.006 139.228 34.8633 + endloop + endfacet + facet normal 0.132988 -0.0347238 0.990509 + outer loop + vertex -368.005 147.644 35.7264 + vertex -375.335 148.734 36.7488 + vertex -370.073 143.707 35.866 + endloop + endfacet + facet normal 0.18861 -0.0367198 0.981365 + outer loop + vertex -375.335 148.734 36.7488 + vertex -380.397 154.067 37.9212 + vertex -381.268 149.631 37.9227 + endloop + endfacet + facet normal 0.132965 -0.0253251 0.990797 + outer loop + vertex -369.667 138.609 35.7283 + vertex -376.201 144.221 36.7487 + vertex -377.078 139.652 36.7495 + endloop + endfacet + facet normal 0.0901662 -0.0156971 0.995803 + outer loop + vertex -361.584 130.182 34.8636 + vertex -360.006 139.228 34.8633 + vertex -369.667 138.609 35.7283 + endloop + endfacet + facet normal 0.138332 -0.0169689 0.990241 + outer loop + vertex -371.751 134.594 35.8716 + vertex -377.966 135.082 36.7482 + vertex -371.346 129.522 35.7281 + endloop + endfacet + facet normal 0.0602535 -0.0107166 0.998126 + outer loop + vertex -347.756 119.294 33.912 + vertex -361.584 130.182 34.8636 + vertex -363.142 121.184 34.8611 + endloop + endfacet + facet normal 0.130597 -0.0335336 0.990868 + outer loop + vertex -371.346 129.522 35.7281 + vertex -378.837 130.567 36.7507 + vertex -373.434 125.592 35.8703 + endloop + endfacet + facet normal 0.183992 -0.0368359 0.982237 + outer loop + vertex -378.837 130.567 36.7507 + vertex -384.007 135.977 37.9221 + vertex -384.912 131.478 37.923 + endloop + endfacet + facet normal 0.129452 -0.0260352 0.991244 + outer loop + vertex -372.985 120.634 35.7235 + vertex -379.71 126.131 36.7461 + vertex -380.561 121.756 36.7423 + endloop + endfacet + facet normal 0.0882905 -0.0185108 0.995923 + outer loop + vertex -364.684 112.251 34.8317 + vertex -363.142 121.184 34.8611 + vertex -372.985 120.634 35.7235 + endloop + endfacet + facet normal 0.134224 -0.0215433 0.990717 + outer loop + vertex -375.077 116.779 35.8558 + vertex -381.422 117.362 36.7282 + vertex -374.629 111.759 35.686 + endloop + endfacet + facet normal 0.0566284 -0.0188231 0.998218 + outer loop + vertex -350.521 101.237 33.8206 + vertex -364.684 112.251 34.8317 + vertex -366.232 103.237 34.7495 + endloop + endfacet + facet normal 0.125268 -0.0422553 0.991223 + outer loop + vertex -374.629 111.759 35.686 + vertex -382.287 112.895 36.7023 + vertex -376.763 107.797 35.7868 + endloop + endfacet + facet normal 0.176569 -0.0439205 0.983308 + outer loop + vertex -382.287 112.895 36.7023 + vertex -387.598 118.301 37.8973 + vertex -388.517 113.825 37.8625 + endloop + endfacet + facet normal 0.121652 -0.0409305 0.991729 + outer loop + vertex -376.309 102.672 35.5752 + vertex -383.175 108.349 36.6517 + vertex -384.078 103.771 36.5734 + endloop + endfacet + facet normal 0.0835446 -0.0348368 0.995895 + outer loop + vertex -367.795 94.2331 34.5658 + vertex -366.232 103.237 34.7495 + vertex -376.309 102.672 35.5752 + endloop + endfacet + facet normal 0.124091 -0.0439571 0.991297 + outer loop + vertex -378.48 98.6808 35.6259 + vertex -384.985 99.2468 36.4653 + vertex -378.025 93.6918 35.3477 + endloop + endfacet + facet normal 0.0473938 -0.0455167 0.997839 + outer loop + vertex -353.177 83.4747 33.3807 + vertex -367.795 94.2331 34.5658 + vertex -369.245 85.5412 34.2381 + endloop + endfacet + facet normal 0.0698854 -0.0718971 0.994961 + outer loop + vertex -380.227 89.8998 35.3245 + vertex -379.602 85.1532 34.9376 + vertex -369.245 85.5412 34.2381 + endloop + endfacet + facet normal 0.113351 -0.0575329 0.991888 + outer loop + vertex -378.025 93.6918 35.3477 + vertex -384.985 99.2468 36.4653 + vertex -385.933 94.8288 36.3173 + endloop + endfacet + facet normal 0.157246 -0.074246 0.984765 + outer loop + vertex -385.933 94.8288 36.3173 + vertex -391.358 100.217 37.5898 + vertex -392.361 95.8292 37.4191 + endloop + endfacet + facet normal 0.112852 -0.0659483 0.991421 + outer loop + vertex -380.227 89.8998 35.3245 + vertex -386.849 90.5431 36.1209 + vertex -379.602 85.1532 34.9376 + endloop + endfacet + facet normal 0.0699401 -0.0735864 0.994833 + outer loop + vertex -370.069 77.2562 33.6832 + vertex -369.245 85.5412 34.2381 + vertex -379.602 85.1532 34.9376 + endloop + endfacet + facet normal 0.0557457 -0.0986266 0.993562 + outer loop + vertex -368.953 69.4295 32.8437 + vertex -370.069 77.2562 33.6832 + vertex -380.26 76.5516 34.1851 + endloop + endfacet + facet normal 0.0957912 -0.0994085 0.990425 + outer loop + vertex -381.551 81.4817 34.774 + vertex -387.665 86.341 35.853 + vertex -388.322 82.1081 35.4918 + endloop + endfacet + facet normal 0.127059 -0.119099 0.984719 + outer loop + vertex -388.322 82.1081 35.4918 + vertex -394.193 87.3618 36.8847 + vertex -395.096 83.2174 36.5 + endloop + endfacet + facet normal 0.164331 -0.143173 0.975959 + outer loop + vertex -395.096 83.2174 36.5 + vertex -399.945 88.4538 38.0846 + vertex -401.005 84.4129 37.6702 + endloop + endfacet + facet normal 0.178864 -0.129521 0.975311 + outer loop + vertex -394.193 87.3618 36.8847 + vertex -399.945 88.4538 38.0846 + vertex -395.096 83.2174 36.5 + endloop + endfacet + facet normal 0.180285 -0.122711 0.97593 + outer loop + vertex -394.193 87.3618 36.8847 + vertex -398.965 92.6447 38.4305 + vertex -399.945 88.4538 38.0846 + endloop + endfacet + facet normal 0.191973 -0.111883 0.975002 + outer loop + vertex -393.311 91.5618 37.193 + vertex -398.965 92.6447 38.4305 + vertex -394.193 87.3618 36.8847 + endloop + endfacet + facet normal 0.193413 -0.104921 0.975491 + outer loop + vertex -393.311 91.5618 37.193 + vertex -397.966 96.9181 38.692 + vertex -398.965 92.6447 38.4305 + endloop + endfacet + facet normal 0.20253 -0.0967183 0.974488 + outer loop + vertex -392.361 95.8292 37.4191 + vertex -397.966 96.9181 38.692 + vertex -393.311 91.5618 37.193 + endloop + endfacet + facet normal 0.203714 -0.0909794 0.974794 + outer loop + vertex -392.361 95.8292 37.4191 + vertex -396.932 101.293 38.8843 + vertex -397.966 96.9181 38.692 + endloop + endfacet + facet normal 0.209646 -0.0858057 0.974005 + outer loop + vertex -391.358 100.217 37.5898 + vertex -396.932 101.293 38.8843 + vertex -392.361 95.8292 37.4191 + endloop + endfacet + facet normal 0.210902 -0.0796107 0.97426 + outer loop + vertex -391.358 100.217 37.5898 + vertex -395.901 105.773 39.0272 + vertex -396.932 101.293 38.8843 + endloop + endfacet + facet normal 0.21824 -0.0733211 0.973137 + outer loop + vertex -390.398 104.714 37.7133 + vertex -395.901 105.773 39.0272 + vertex -391.358 100.217 37.5898 + endloop + endfacet + facet normal 0.218812 -0.0704509 0.97322 + outer loop + vertex -390.398 104.714 37.7133 + vertex -394.895 110.317 39.1299 + vertex -395.901 105.773 39.0272 + endloop + endfacet + facet normal 0.22348 -0.0665065 0.972437 + outer loop + vertex -389.44 109.277 37.8052 + vertex -394.895 110.317 39.1299 + vertex -390.398 104.714 37.7133 + endloop + endfacet + facet normal 0.224459 -0.0615029 0.972541 + outer loop + vertex -389.44 109.277 37.8052 + vertex -393.93 114.855 39.1942 + vertex -394.895 110.317 39.1299 + endloop + endfacet + facet normal 0.227983 -0.0585082 0.971906 + outer loop + vertex -388.517 113.825 37.8625 + vertex -393.93 114.855 39.1942 + vertex -389.44 109.277 37.8052 + endloop + endfacet + facet normal 0.228104 -0.0578852 0.971915 + outer loop + vertex -388.517 113.825 37.8625 + vertex -392.968 119.33 39.2349 + vertex -393.93 114.855 39.1942 + endloop + endfacet + facet normal 0.231377 -0.0550864 0.971303 + outer loop + vertex -387.598 118.301 37.8973 + vertex -392.968 119.33 39.2349 + vertex -388.517 113.825 37.8625 + endloop + endfacet + facet normal 0.231792 -0.0529452 0.971323 + outer loop + vertex -387.598 118.301 37.8973 + vertex -392.041 123.729 39.2534 + vertex -392.968 119.33 39.2349 + endloop + endfacet + facet normal 0.234114 -0.0509325 0.970874 + outer loop + vertex -386.706 122.696 37.913 + vertex -392.041 123.729 39.2534 + vertex -387.598 118.301 37.8973 + endloop + endfacet + facet normal 0.23404 -0.0513138 0.970872 + outer loop + vertex -386.706 122.696 37.913 + vertex -391.116 128.099 39.2616 + vertex -392.041 123.729 39.2534 + endloop + endfacet + facet normal 0.235347 -0.0501822 0.970615 + outer loop + vertex -385.808 127.065 37.9211 + vertex -391.116 128.099 39.2616 + vertex -386.706 122.696 37.913 + endloop + endfacet + facet normal 0.235612 -0.0488313 0.97062 + outer loop + vertex -385.808 127.065 37.9211 + vertex -390.202 132.506 39.2614 + vertex -391.116 128.099 39.2616 + endloop + endfacet + facet normal 0.236146 -0.0483734 0.970513 + outer loop + vertex -384.912 131.478 37.923 + vertex -390.202 132.506 39.2614 + vertex -385.808 127.065 37.9211 + endloop + endfacet + facet normal 0.235816 -0.0500654 0.970507 + outer loop + vertex -384.912 131.478 37.923 + vertex -389.256 136.999 39.2632 + vertex -390.202 132.506 39.2614 + endloop + endfacet + facet normal 0.238514 -0.0478102 0.969962 + outer loop + vertex -384.007 135.977 37.9221 + vertex -389.256 136.999 39.2632 + vertex -384.912 131.478 37.923 + endloop + endfacet + facet normal 0.238148 -0.0496824 0.969957 + outer loop + vertex -384.007 135.977 37.9221 + vertex -388.304 141.558 39.2631 + vertex -389.256 136.999 39.2632 + endloop + endfacet + facet normal 0.240162 -0.0480323 0.969544 + outer loop + vertex -383.091 140.541 37.9214 + vertex -388.304 141.558 39.2631 + vertex -384.007 135.977 37.9221 + endloop + endfacet + facet normal 0.239802 -0.0498742 0.96954 + outer loop + vertex -383.091 140.541 37.9214 + vertex -387.356 146.122 39.2634 + vertex -388.304 141.558 39.2631 + endloop + endfacet + facet normal 0.241375 -0.048594 0.969215 + outer loop + vertex -382.173 145.112 37.9219 + vertex -387.356 146.122 39.2634 + vertex -383.091 140.541 37.9214 + endloop + endfacet + facet normal 0.241317 -0.0488908 0.969214 + outer loop + vertex -382.173 145.112 37.9219 + vertex -386.433 150.636 39.2612 + vertex -387.356 146.122 39.2634 + endloop + endfacet + facet normal 0.241726 -0.0485543 0.969129 + outer loop + vertex -381.268 149.631 37.9227 + vertex -386.433 150.636 39.2612 + vertex -382.173 145.112 37.9219 + endloop + endfacet + facet normal 0.241371 -0.0503753 0.969125 + outer loop + vertex -381.268 149.631 37.9227 + vertex -385.516 155.066 39.2632 + vertex -386.433 150.636 39.2612 + endloop + endfacet + facet normal 0.244565 -0.0477148 0.968458 + outer loop + vertex -380.397 154.067 37.9212 + vertex -385.516 155.066 39.2632 + vertex -381.268 149.631 37.9227 + endloop + endfacet + facet normal 0.244205 -0.0495553 0.968457 + outer loop + vertex -380.397 154.067 37.9212 + vertex -384.634 159.425 39.2637 + vertex -385.516 155.066 39.2632 + endloop + endfacet + facet normal 0.245967 -0.0480694 0.968086 + outer loop + vertex -379.542 158.429 37.9206 + vertex -384.634 159.425 39.2637 + vertex -380.397 154.067 37.9212 + endloop + endfacet + facet normal 0.245533 -0.0502829 0.968083 + outer loop + vertex -379.542 158.429 37.9206 + vertex -383.759 163.753 39.2667 + vertex -384.634 159.425 39.2637 + endloop + endfacet + facet normal 0.244345 -0.0512863 0.968331 + outer loop + vertex -378.658 162.757 37.9267 + vertex -383.759 163.753 39.2667 + vertex -379.542 158.429 37.9206 + endloop + endfacet + facet normal 0.244211 -0.0519703 0.968328 + outer loop + vertex -378.658 162.757 37.9267 + vertex -382.852 168.105 39.2715 + vertex -383.759 163.753 39.2667 + endloop + endfacet + facet normal 0.244204 -0.0519764 0.96833 + outer loop + vertex -377.745 167.102 37.9298 + vertex -382.852 168.105 39.2715 + vertex -378.658 162.757 37.9267 + endloop + endfacet + facet normal 0.2438 -0.0540166 0.96832 + outer loop + vertex -377.745 167.102 37.9298 + vertex -381.877 172.517 39.2721 + vertex -382.852 168.105 39.2715 + endloop + endfacet + facet normal 0.245239 -0.0528451 0.968021 + outer loop + vertex -376.79 171.505 37.9282 + vertex -381.877 172.517 39.2721 + vertex -377.745 167.102 37.9298 + endloop + endfacet + facet normal 0.244937 -0.0543552 0.968014 + outer loop + vertex -376.79 171.505 37.9282 + vertex -380.858 176.988 39.2654 + vertex -381.877 172.517 39.2721 + endloop + endfacet + facet normal 0.248015 -0.0519131 0.967364 + outer loop + vertex -375.856 176 37.9299 + vertex -380.858 176.988 39.2654 + vertex -376.79 171.505 37.9282 + endloop + endfacet + facet normal 0.248729 -0.0483009 0.967368 + outer loop + vertex -375.856 176 37.9299 + vertex -379.944 181.521 39.2567 + vertex -380.858 176.988 39.2654 + endloop + endfacet + facet normal 0.256409 -0.0422014 0.965647 + outer loop + vertex -375.121 180.592 37.9354 + vertex -379.944 181.521 39.2567 + vertex -375.856 176 37.9299 + endloop + endfacet + facet normal 0.257016 -0.0390107 0.965619 + outer loop + vertex -375.121 180.592 37.9354 + vertex -379.299 186.16 39.2725 + vertex -379.944 181.521 39.2567 + endloop + endfacet + facet normal 0.264759 -0.0327529 0.963758 + outer loop + vertex -374.575 185.252 37.9437 + vertex -379.299 186.16 39.2725 + vertex -375.121 180.592 37.9354 + endloop + endfacet + facet normal 0.266428 -0.0237897 0.963561 + outer loop + vertex -374.575 185.252 37.9437 + vertex -378.84 190.918 39.263 + vertex -379.299 186.16 39.2725 + endloop + endfacet + facet normal 0.257036 -0.0314034 0.965892 + outer loop + vertex -373.934 189.87 37.9234 + vertex -378.84 190.918 39.263 + vertex -374.575 185.252 37.9437 + endloop + endfacet + facet normal 0.108184 -0.155635 0.981873 + outer loop + vertex -389.204 77.7432 35.0477 + vertex -396.474 79.4035 36.1119 + vertex -391.878 74.0552 34.7577 + endloop + endfacet + facet normal 0.141579 -0.164239 0.976207 + outer loop + vertex -398.358 76.727 35.8887 + vertex -403.145 77.1415 36.6527 + vertex -397.324 72.8927 35.0936 + endloop + endfacet + facet normal 0.106496 -0.210666 0.97174 + outer loop + vertex -397.324 72.8927 35.0936 + vertex -403.145 77.1415 36.6527 + vertex -403.912 73.6546 35.9809 + endloop + endfacet + facet normal 0.10726 -0.205296 0.972805 + outer loop + vertex -397.324 72.8927 35.0936 + vertex -403.912 73.6546 35.9809 + vertex -398.298 69.7663 34.5412 + endloop + endfacet + facet normal 0.0731471 -0.130772 0.98871 + outer loop + vertex -381.563 71.2854 33.6283 + vertex -389.204 77.7432 35.0477 + vertex -391.878 74.0552 34.7577 + endloop + endfacet + facet normal 0.0446679 -0.115965 0.992248 + outer loop + vertex -381.563 71.2854 33.6283 + vertex -368.953 69.4295 32.8437 + vertex -380.26 76.5516 34.1851 + endloop + endfacet + facet normal 0.0234544 -0.112265 0.993401 + outer loop + vertex -354.687 67.5287 32.2921 + vertex -368.953 69.4295 32.8437 + vertex -355.115 60.7714 31.5386 + endloop + endfacet + facet normal 0.00282704 -0.111004 0.993816 + outer loop + vertex -339.496 58.084 31.1939 + vertex -354.687 67.5287 32.2921 + vertex -355.115 60.7714 31.5386 + endloop + endfacet + facet normal -0.00617478 -0.100132 0.994955 + outer loop + vertex -323.376 55.2406 31.0078 + vertex -338.908 64.9692 31.8905 + vertex -339.496 58.084 31.1939 + endloop + endfacet + facet normal -0.0115025 -0.094357 0.995472 + outer loop + vertex -307.045 52.3852 30.9259 + vertex -322.715 62.1488 31.6703 + vertex -323.376 55.2406 31.0078 + endloop + endfacet + facet normal -0.0134275 -0.0928361 0.995591 + outer loop + vertex -290.59 49.6455 30.8923 + vertex -306.383 59.286 31.5783 + vertex -307.045 52.3852 30.9259 + endloop + endfacet + facet normal -0.0123886 -0.0927137 0.995616 + outer loop + vertex -274.013 47.0891 30.8605 + vertex -289.911 56.5265 31.5416 + vertex -290.59 49.6455 30.8923 + endloop + endfacet + facet normal -0.0108499 -0.0930662 0.995601 + outer loop + vertex -257.349 44.6633 30.8154 + vertex -273.269 53.9209 31.5073 + vertex -274.013 47.0891 30.8605 + endloop + endfacet + facet normal -0.00904612 -0.0921472 0.995704 + outer loop + vertex -240.677 42.3795 30.7555 + vertex -256.506 51.478 31.4537 + vertex -257.349 44.6633 30.8154 + endloop + endfacet + facet normal -0.00772532 -0.0912993 0.995794 + outer loop + vertex -224.07 40.2351 30.6877 + vertex -239.735 49.1671 31.3851 + vertex -240.677 42.3795 30.7555 + endloop + endfacet + facet normal -0.00657951 -0.0904249 0.995882 + outer loop + vertex -207.541 38.2332 30.6152 + vertex -223.045 46.9932 31.3081 + vertex -224.07 40.2351 30.6877 + endloop + endfacet + facet normal -0.0050714 -0.0892747 0.995994 + outer loop + vertex -191.067 36.4028 30.535 + vertex -206.458 44.9742 31.2249 + vertex -207.541 38.2332 30.6152 + endloop + endfacet + facet normal -0.00371456 -0.0879714 0.996116 + outer loop + vertex -174.635 34.717 30.4474 + vertex -189.95 43.1268 31.133 + vertex -191.067 36.4028 30.535 + endloop + endfacet + facet normal -0.0021103 -0.0856727 0.996321 + outer loop + vertex -158.289 33.1968 30.3513 + vertex -173.515 41.459 31.0295 + vertex -174.635 34.717 30.4474 + endloop + endfacet + facet normal -0.000920428 -0.083982 0.996467 + outer loop + vertex -142.098 31.8265 30.2507 + vertex -157.189 39.9295 30.9197 + vertex -158.289 33.1968 30.3513 + endloop + endfacet + facet normal -0.000102465 -0.0820057 0.996632 + outer loop + vertex -126.101 30.5816 30.15 + vertex -141.043 38.5522 30.8043 + vertex -142.098 31.8265 30.2507 + endloop + endfacet + facet normal 0.000434532 -0.0798628 0.996806 + outer loop + vertex -110.268 29.4521 30.0526 + vertex -125.111 37.3055 30.6882 + vertex -126.101 30.5816 30.15 + endloop + endfacet + facet normal 0.000672202 -0.07796 0.996956 + outer loop + vertex -94.5214 28.4227 29.9614 + vertex -109.357 36.1618 30.5766 + vertex -110.268 29.4521 30.0526 + endloop + endfacet + facet normal 0.00067262 -0.0763717 0.997079 + outer loop + vertex -78.7928 27.4816 29.8788 + vertex -93.7048 35.1029 30.4726 + vertex -94.5214 28.4227 29.9614 + endloop + endfacet + facet normal 0.000586189 -0.0751254 0.997174 + outer loop + vertex -63.0469 26.6486 29.8067 + vertex -78.0827 34.1209 30.3785 + vertex -78.7928 27.4816 29.8788 + endloop + endfacet + facet normal 0.000405625 -0.0736223 0.997286 + outer loop + vertex -47.2926 25.9352 29.7477 + vertex -62.4549 33.2655 30.295 + vertex -63.0469 26.6486 29.8067 + endloop + endfacet + facet normal 0.000342351 -0.0727533 0.99735 + outer loop + vertex -31.5447 25.3953 29.7029 + vertex -46.828 32.5165 30.2276 + vertex -47.2926 25.9352 29.7477 + endloop + endfacet + facet normal 0.000248275 -0.0721534 0.997394 + outer loop + vertex -15.8089 25.0541 29.6743 + vertex -31.214 31.943 30.1765 + vertex -31.5447 25.3953 29.7029 + endloop + endfacet + facet normal 9.37448e-05 -0.0718731 0.997414 + outer loop + vertex -0.0668718 24.9297 29.6638 + vertex -15.6119 31.5755 30.1442 + vertex -15.8089 25.0541 29.6743 + endloop + endfacet + facet normal -0.000107906 -0.0718589 0.997415 + outer loop + vertex 15.7022 25.0258 29.6725 + vertex -0.00250011 31.4402 30.1329 + vertex -0.0668718 24.9297 29.6638 + endloop + endfacet + facet normal -6.42754e-05 -0.0717683 0.997421 + outer loop + vertex 31.5057 25.3697 29.6982 + vertex 15.6365 31.5587 30.1425 + vertex 15.7022 25.0258 29.6725 + endloop + endfacet + facet normal -0.000326314 -0.0720852 0.997398 + outer loop + vertex 47.3084 25.899 29.7416 + vertex 31.307 31.927 30.1721 + vertex 31.5057 25.3697 29.6982 + endloop + endfacet + facet normal -0.00035371 -0.0726649 0.997356 + outer loop + vertex 63.0812 26.6114 29.7992 + vertex 46.9782 32.4927 30.2219 + vertex 47.3084 25.899 29.7416 + endloop + endfacet + facet normal -0.000587892 -0.0737956 0.997273 + outer loop + vertex 78.8246 27.4468 29.8702 + vertex 62.6223 33.2325 30.2888 + vertex 63.0812 26.6114 29.7992 + endloop + endfacet + facet normal -0.000650931 -0.0748206 0.997197 + outer loop + vertex 94.596 28.4 29.9521 + vertex 78.2474 34.1116 30.3699 + vertex 78.8246 27.4468 29.8702 + endloop + endfacet + facet normal -0.000580352 -0.0763778 0.997079 + outer loop + vertex 110.471 29.4607 30.0426 + vertex 93.9123 35.0933 30.4644 + vertex 94.596 28.4 29.9521 + endloop + endfacet + facet normal -0.00044667 -0.0783572 0.996925 + outer loop + vertex 126.478 30.6137 30.1404 + vertex 109.694 36.1669 30.5693 + vertex 110.471 29.4607 30.0426 + endloop + endfacet + facet normal -1.9539e-05 -0.0803036 0.99677 + outer loop + vertex 142.59 31.8696 30.2418 + vertex 125.625 37.3339 30.6817 + vertex 126.478 30.6137 30.1404 + endloop + endfacet + facet normal 0.000671552 -0.082322 0.996606 + outer loop + vertex 158.756 33.2354 30.3438 + vertex 141.675 38.5982 30.7983 + vertex 142.59 31.8696 30.2418 + endloop + endfacet + facet normal 0.00190388 -0.0840217 0.996462 + outer loop + vertex 174.969 34.75 30.4405 + vertex 157.796 39.9786 30.9142 + vertex 158.756 33.2354 30.3438 + endloop + endfacet + facet normal 0.00324765 -0.086131 0.996279 + outer loop + vertex 191.274 36.4119 30.531 + vertex 173.986 41.4869 31.0261 + vertex 174.969 34.75 30.4405 + endloop + endfacet + facet normal 0.00474511 -0.0878474 0.996123 + outer loop + vertex 207.717 38.2359 30.6136 + vertex 190.296 43.1535 31.1302 + vertex 191.274 36.4119 30.531 + endloop + endfacet + facet normal 0.00645379 -0.0885692 0.996049 + outer loop + vertex 224.298 40.247 30.685 + vertex 206.776 45.011 31.2221 + vertex 207.717 38.2359 30.6136 + endloop + endfacet + facet normal 0.00777397 -0.0903883 0.995876 + outer loop + vertex 240.976 42.3945 30.7497 + vertex 223.423 47.0201 31.3065 + vertex 224.298 40.247 30.685 + endloop + endfacet + facet normal 0.00939639 -0.0907698 0.995828 + outer loop + vertex 257.703 44.7197 30.8038 + vertex 240.184 49.2119 31.3785 + vertex 240.976 42.3945 30.7497 + endloop + endfacet + facet normal 0.0105147 -0.0920022 0.995703 + outer loop + vertex 274.455 47.1808 30.8543 + vertex 257.011 51.5573 31.4429 + vertex 257.703 44.7197 30.8038 + endloop + endfacet + facet normal 0.0116164 -0.0929164 0.995606 + outer loop + vertex 291.169 49.7975 30.9035 + vertex 273.867 54.0578 31.503 + vertex 274.455 47.1808 30.8543 + endloop + endfacet + facet normal 0.012066 -0.0934043 0.995555 + outer loop + vertex 307.717 52.4845 30.955 + vertex 290.668 56.7079 31.5579 + vertex 291.169 49.7975 30.9035 + endloop + endfacet + facet normal 0.0164364 -0.122014 0.992392 + outer loop + vertex 323.903 55.1489 31.0145 + vertex 307.717 52.4845 30.955 + vertex 324.224 49.1258 30.2687 + endloop + endfacet + facet normal 0.0144905 -0.12212 0.99241 + outer loop + vertex 340.029 51.7791 30.3644 + vertex 323.903 55.1489 31.0145 + vertex 324.224 49.1258 30.2687 + endloop + endfacet + facet normal 0.0139071 -0.161681 0.986745 + outer loop + vertex 355.554 54.5036 30.592 + vertex 340.029 51.7791 30.3644 + vertex 356.015 49.3736 29.7449 + endloop + endfacet + facet normal 0.00572099 -0.16241 0.986707 + outer loop + vertex 371.636 52.3464 30.1437 + vertex 355.554 54.5036 30.592 + vertex 356.015 49.3736 29.7449 + endloop + endfacet + facet normal 0.00360557 -0.240563 0.970627 + outer loop + vertex 387.465 55.7928 30.9391 + vertex 371.636 52.3464 30.1437 + vertex 388.345 51.3827 29.8428 + endloop + endfacet + facet normal -0.00517088 -0.242209 0.97021 + outer loop + vertex 404.519 55.0584 30.8466 + vertex 387.465 55.7928 30.9391 + vertex 388.345 51.3827 29.8428 + endloop + endfacet + facet normal -0.00742278 -0.292733 0.956166 + outer loop + vertex 403.241 59.5145 32.2009 + vertex 387.465 55.7928 30.9391 + vertex 404.519 55.0584 30.8466 + endloop + endfacet + facet normal -0.0182688 -0.295537 0.955157 + outer loop + vertex 403.241 59.5145 32.2009 + vertex 404.519 55.0584 30.8466 + vertex 414.435 58.2056 32.01 + endloop + endfacet + facet normal 0.0281366 -0.207592 0.977811 + outer loop + vertex 372.722 41.7449 27.8028 + vertex 357.019 41.5807 28.2198 + vertex 356.741 38.8 27.6374 + endloop + endfacet + facet normal 0.0222809 -0.217663 0.97577 + outer loop + vertex 372.292 48.043 29.2386 + vertex 356.563 45.0842 28.9377 + vertex 372.814 44.5295 28.4429 + endloop + endfacet + facet normal 0.0218294 -0.173179 0.984648 + outer loop + vertex 356.563 45.0842 28.9377 + vertex 340.394 46.6376 29.5694 + vertex 340.833 42.2981 28.7964 + endloop + endfacet + facet normal 0.0242833 -0.172928 0.984635 + outer loop + vertex 340.394 46.6376 29.5694 + vertex 324.528 43.9243 29.4842 + vertex 340.833 42.2981 28.7964 + endloop + endfacet + facet normal 0.0212201 -0.146734 0.988948 + outer loop + vertex 324.528 43.9243 29.4842 + vertex 308.03 46.436 30.2108 + vertex 308.347 41.2293 29.4315 + endloop + endfacet + facet normal 0.0211706 -0.14644 0.988993 + outer loop + vertex 308.347 41.2293 29.4315 + vertex 291.552 43.7518 30.1645 + vertex 291.943 38.5952 29.3926 + endloop + endfacet + facet normal 0.0204821 -0.144856 0.989241 + outer loop + vertex 291.943 38.5952 29.3926 + vertex 274.94 41.1848 30.1239 + vertex 275.438 36.0496 29.3616 + endloop + endfacet + facet normal 0.0189472 -0.144118 0.989379 + outer loop + vertex 275.438 36.0496 29.3616 + vertex 258.303 38.7549 30.0838 + vertex 258.909 33.6625 29.3304 + endloop + endfacet + facet normal 0.0173418 -0.142615 0.989626 + outer loop + vertex 258.909 33.6625 29.3304 + vertex 241.68 36.4771 30.0379 + vertex 242.386 31.3986 29.2937 + endloop + endfacet + facet normal 0.0155026 -0.141838 0.989769 + outer loop + vertex 242.386 31.3986 29.2937 + vertex 225.092 34.3333 29.9851 + vertex 225.87 29.2926 29.2506 + endloop + endfacet + facet normal 0.0137996 -0.140137 0.990036 + outer loop + vertex 225.87 29.2926 29.2506 + vertex 208.572 32.3479 29.9242 + vertex 209.399 27.3219 29.2012 + endloop + endfacet + facet normal 0.0118862 -0.137819 0.990386 + outer loop + vertex 209.399 27.3219 29.2012 + vertex 192.163 30.5358 29.8553 + vertex 193.028 25.5099 29.1456 + endloop + endfacet + facet normal 0.00995078 -0.13574 0.990694 + outer loop + vertex 193.028 25.5099 29.1456 + vertex 175.868 28.877 29.7793 + vertex 176.768 23.8663 29.0837 + endloop + endfacet + facet normal 0.00822378 -0.133003 0.991081 + outer loop + vertex 176.768 23.8663 29.0837 + vertex 159.648 27.3785 29.6971 + vertex 160.565 22.3708 29.0174 + endloop + endfacet + facet normal 0.00674736 -0.130263 0.991456 + outer loop + vertex 160.565 22.3708 29.0174 + vertex 143.456 26.0123 29.6123 + vertex 144.361 21.0092 28.9488 + endloop + endfacet + facet normal 0.00557101 -0.127434 0.991831 + outer loop + vertex 144.361 21.0092 28.9488 + vertex 127.297 24.7651 29.5272 + vertex 128.158 19.7646 28.8799 + endloop + endfacet + facet normal 0.00455197 -0.125282 0.992111 + outer loop + vertex 128.158 19.7646 28.8799 + vertex 111.223 23.6258 29.4452 + vertex 112.016 18.65 28.8132 + endloop + endfacet + facet normal 0.0039095 -0.12286 0.992416 + outer loop + vertex 112.016 18.65 28.8132 + vertex 95.2616 22.6031 29.3686 + vertex 95.962 17.6387 28.7513 + endloop + endfacet + facet normal 0.00327491 -0.12115 0.992629 + outer loop + vertex 95.962 17.6387 28.7513 + vertex 79.3807 21.6856 29.2999 + vertex 79.9758 16.7527 28.6959 + endloop + endfacet + facet normal 0.00272571 -0.120558 0.992703 + outer loop + vertex 79.9758 16.7527 28.6959 + vertex 63.5115 20.8696 29.2411 + vertex 63.9987 15.9942 28.6476 + endloop + endfacet + facet normal 0.00227264 -0.119611 0.992818 + outer loop + vertex 63.9987 15.9942 28.6476 + vertex 47.6115 20.2044 29.1924 + vertex 47.9861 15.3639 28.6083 + endloop + endfacet + facet normal 0.00162279 -0.119153 0.992875 + outer loop + vertex 47.9861 15.3639 28.6083 + vertex 31.6825 19.7085 29.1564 + vertex 31.9465 14.9055 28.5795 + endloop + endfacet + facet normal 0.00110145 -0.118318 0.992975 + outer loop + vertex 31.9465 14.9055 28.5795 + vertex 15.7588 19.4108 29.1343 + vertex 15.9069 14.6072 28.5618 + endloop + endfacet + facet normal 0.000257954 -0.118956 0.9929 + outer loop + vertex 15.9069 14.6072 28.5618 + vertex -0.139085 19.2985 29.128 + vertex -0.0993721 14.5298 28.5567 + endloop + endfacet + facet normal -0.000347134 -0.119052 0.992888 + outer loop + vertex -0.0993721 14.5298 28.5567 + vertex -16.0111 19.4152 29.1369 + vertex -16.1013 14.6377 28.564 + endloop + endfacet + facet normal -0.000979263 -0.119223 0.992867 + outer loop + vertex -16.1013 14.6377 28.564 + vertex -31.8862 19.7377 29.1609 + vertex -32.1189 14.9321 28.5836 + endloop + endfacet + facet normal -0.00158497 -0.119332 0.992853 + outer loop + vertex -32.1189 14.9321 28.5836 + vertex -47.7714 20.2569 29.1986 + vertex -48.1402 15.4007 28.6143 + endloop + endfacet + facet normal -0.00217897 -0.120218 0.992745 + outer loop + vertex -48.1402 15.4007 28.6143 + vertex -63.6557 20.9202 29.2487 + vertex -64.1358 16.0239 28.6547 + endloop + endfacet + facet normal -0.00272775 -0.121356 0.992605 + outer loop + vertex -64.1358 16.0239 28.6547 + vertex -79.5115 21.7213 29.309 + vertex -80.086 16.7844 28.7038 + endloop + endfacet + facet normal -0.00332349 -0.123338 0.992359 + outer loop + vertex -80.086 16.7844 28.7038 + vertex -95.3387 22.6233 29.3784 + vertex -95.9935 17.6673 28.7603 + endloop + endfacet + facet normal -0.00388099 -0.125254 0.992117 + outer loop + vertex -95.9935 17.6673 28.7603 + vertex -111.166 23.6392 29.4549 + vertex -111.894 18.6513 28.8223 + endloop + endfacet + facet normal -0.00461793 -0.127589 0.991816 + outer loop + vertex -111.894 18.6513 28.8223 + vertex -127.07 24.7532 29.5366 + vertex -127.861 19.7403 28.8881 + endloop + endfacet + facet normal -0.00573351 -0.130477 0.991435 + outer loop + vertex -127.861 19.7403 28.8881 + vertex -143.125 25.9833 29.6214 + vertex -143.973 20.9682 28.9565 + endloop + endfacet + facet normal -0.00711114 -0.133343 0.991044 + outer loop + vertex -143.973 20.9682 28.9565 + vertex -159.36 27.355 29.7054 + vertex -160.253 22.347 29.0252 + endloop + endfacet + facet normal -0.00861016 -0.135808 0.990698 + outer loop + vertex -160.253 22.347 29.0252 + vertex -175.726 28.8772 29.7859 + vertex -176.637 23.8604 29.0903 + endloop + endfacet + facet normal -0.0103549 -0.138102 0.990364 + outer loop + vertex -176.637 23.8604 29.0903 + vertex -192.147 30.5427 29.8599 + vertex -193.039 25.5149 29.1495 + endloop + endfacet + facet normal -0.0122513 -0.139944 0.990084 + outer loop + vertex -193.039 25.5149 29.1495 + vertex -208.578 32.3707 29.9262 + vertex -209.412 27.3272 29.203 + endloop + endfacet + facet normal -0.0139977 -0.141674 0.989814 + outer loop + vertex -209.412 27.3272 29.203 + vertex -225.032 34.3501 29.9873 + vertex -225.78 29.2915 29.2527 + endloop + endfacet + facet normal -0.0156861 -0.143622 0.989508 + outer loop + vertex -225.78 29.2915 29.2527 + vertex -241.539 36.4651 30.0441 + vertex -242.176 31.3982 29.2986 + endloop + endfacet + facet normal -0.0170756 -0.144454 0.989364 + outer loop + vertex -242.176 31.3982 29.2986 + vertex -258.091 38.7287 30.0942 + vertex -258.606 33.6175 29.339 + endloop + endfacet + facet normal -0.0190462 -0.145457 0.989181 + outer loop + vertex -258.606 33.6175 29.339 + vertex -274.642 41.113 30.1325 + vertex -275.037 35.9799 29.3701 + endloop + endfacet + facet normal -0.0207331 -0.145054 0.989207 + outer loop + vertex -275.037 35.9799 29.3701 + vertex -291.133 43.6569 30.1584 + vertex -291.438 38.4672 29.391 + endloop + endfacet + facet normal -0.0222165 -0.145644 0.989088 + outer loop + vertex -291.438 38.4672 29.391 + vertex -307.548 46.3351 30.1877 + vertex -307.783 41.1164 29.414 + endloop + endfacet + facet normal -0.0219013 -0.147152 0.988871 + outer loop + vertex -307.783 41.1164 29.414 + vertex -323.85 49.1602 30.2551 + vertex -324.058 43.8975 29.4674 + endloop + endfacet + facet normal -0.0192661 -0.152453 0.988123 + outer loop + vertex -324.058 43.8975 29.4674 + vertex -339.959 52.0387 30.4134 + vertex -340.233 46.7562 29.5931 + endloop + endfacet + facet normal -0.0138985 -0.163719 0.986409 + outer loop + vertex -340.233 46.7562 29.5931 + vertex -355.812 54.8887 30.7234 + vertex -356.18 49.6537 29.8493 + endloop + endfacet + facet normal 0.00424218 -0.164975 0.986289 + outer loop + vertex -355.812 54.8887 30.7234 + vertex -371.414 57.7123 31.2628 + vertex -356.18 49.6537 29.8493 + endloop + endfacet + facet normal 0.00282505 -0.208754 0.977964 + outer loop + vertex -371.585 52.4331 30.2598 + vertex -385.588 59.8401 31.8814 + vertex -386.269 55.1493 30.882 + endloop + endfacet + facet normal 0.0295005 -0.212365 0.976745 + outer loop + vertex -385.588 59.8401 31.8814 + vertex -397.778 61.6985 32.6536 + vertex -386.269 55.1493 30.882 + endloop + endfacet + facet normal 0.0273684 -0.225182 0.973932 + outer loop + vertex -397.778 61.6985 32.6536 + vertex -385.588 59.8401 31.8814 + vertex -396.906 65.8135 33.5805 + endloop + endfacet + facet normal 0.0355058 -0.157798 0.986833 + outer loop + vertex -370.286 63.3934 32.1306 + vertex -386.986 66.7602 33.2698 + vertex -371.414 57.7123 31.2628 + endloop + endfacet + facet normal 0.0865255 -0.23363 0.968468 + outer loop + vertex -398.298 69.7663 34.5412 + vertex -403.912 73.6546 35.9809 + vertex -404.669 70.2746 35.2331 + endloop + endfacet + facet normal 0.10579 -0.277689 0.954828 + outer loop + vertex -404.669 70.2746 35.2331 + vertex -409.882 74.5936 37.0666 + vertex -411.226 71.4089 36.2894 + endloop + endfacet + facet normal 0.136467 -0.243021 0.960374 + outer loop + vertex -403.912 73.6546 35.9809 + vertex -409.882 74.5936 37.0666 + vertex -404.669 70.2746 35.2331 + endloop + endfacet + facet normal 0.134594 -0.252427 0.958209 + outer loop + vertex -403.912 73.6546 35.9809 + vertex -408.628 78.0227 37.794 + vertex -409.882 74.5936 37.0666 + endloop + endfacet + facet normal 0.164489 -0.221396 0.961211 + outer loop + vertex -403.145 77.1415 36.6527 + vertex -408.628 78.0227 37.794 + vertex -403.912 73.6546 35.9809 + endloop + endfacet + facet normal 0.163764 -0.224991 0.9605 + outer loop + vertex -403.145 77.1415 36.6527 + vertex -407.414 81.662 38.4393 + vertex -408.628 78.0227 37.794 + endloop + endfacet + facet normal 0.188634 -0.201747 0.961101 + outer loop + vertex -402.229 80.7067 37.2212 + vertex -407.414 81.662 38.4393 + vertex -403.145 77.1415 36.6527 + endloop + endfacet + facet normal 0.189437 -0.198142 0.961693 + outer loop + vertex -402.229 80.7067 37.2212 + vertex -406.207 85.4988 38.9922 + vertex -407.414 81.662 38.4393 + endloop + endfacet + facet normal 0.205736 -0.184386 0.96108 + outer loop + vertex -401.005 84.4129 37.6702 + vertex -406.207 85.4988 38.9922 + vertex -402.229 80.7067 37.2212 + endloop + endfacet + facet normal 0.209168 -0.170221 0.962951 + outer loop + vertex -401.005 84.4129 37.6702 + vertex -405.057 89.5265 39.4543 + vertex -406.207 85.4988 38.9922 + endloop + endfacet + facet normal 0.22462 -0.157516 0.961631 + outer loop + vertex -399.945 88.4538 38.0846 + vertex -405.057 89.5265 39.4543 + vertex -401.005 84.4129 37.6702 + endloop + endfacet + facet normal 0.227113 -0.147013 0.962708 + outer loop + vertex -399.945 88.4538 38.0846 + vertex -403.967 93.7109 39.8363 + vertex -405.057 89.5265 39.4543 + endloop + endfacet + facet normal 0.241129 -0.135706 0.960958 + outer loop + vertex -398.965 92.6447 38.4305 + vertex -403.967 93.7109 39.8363 + vertex -399.945 88.4538 38.0846 + endloop + endfacet + facet normal 0.243128 -0.127196 0.961618 + outer loop + vertex -398.965 92.6447 38.4305 + vertex -402.89 97.9944 40.1306 + vertex -403.967 93.7109 39.8363 + endloop + endfacet + facet normal 0.25453 -0.118254 0.959807 + outer loop + vertex -397.966 96.9181 38.692 + vertex -402.89 97.9944 40.1306 + vertex -398.965 92.6447 38.4305 + endloop + endfacet + facet normal 0.25614 -0.111412 0.960198 + outer loop + vertex -397.966 96.9181 38.692 + vertex -401.802 102.371 40.3481 + vertex -402.89 97.9944 40.1306 + endloop + endfacet + facet normal 0.264931 -0.10473 0.958563 + outer loop + vertex -396.932 101.293 38.8843 + vertex -401.802 102.371 40.3481 + vertex -397.966 96.9181 38.692 + endloop + endfacet + facet normal 0.266259 -0.0990516 0.958799 + outer loop + vertex -396.932 101.293 38.8843 + vertex -400.714 106.843 40.5078 + vertex -401.802 102.371 40.3481 + endloop + endfacet + facet normal 0.273711 -0.0935219 0.957254 + outer loop + vertex -395.901 105.773 39.0272 + vertex -400.714 106.843 40.5078 + vertex -396.932 101.293 38.8843 + endloop + endfacet + facet normal 0.274929 -0.0882476 0.957406 + outer loop + vertex -395.901 105.773 39.0272 + vertex -399.656 111.372 40.6215 + vertex -400.714 106.843 40.5078 + endloop + endfacet + facet normal 0.280952 -0.083823 0.956054 + outer loop + vertex -394.895 110.317 39.1299 + vertex -399.656 111.372 40.6215 + vertex -395.901 105.773 39.0272 + endloop + endfacet + facet normal 0.282346 -0.0776894 0.956162 + outer loop + vertex -394.895 110.317 39.1299 + vertex -398.645 115.902 40.6912 + vertex -399.656 111.372 40.6215 + endloop + endfacet + facet normal 0.286686 -0.074485 0.955125 + outer loop + vertex -393.93 114.855 39.1942 + vertex -398.645 115.902 40.6912 + vertex -394.895 110.317 39.1299 + endloop + endfacet + facet normal 0.28697 -0.0732255 0.955137 + outer loop + vertex -393.93 114.855 39.1942 + vertex -397.651 120.37 40.7351 + vertex -398.645 115.902 40.6912 + endloop + endfacet + facet normal 0.289938 -0.0710185 0.954407 + outer loop + vertex -392.968 119.33 39.2349 + vertex -397.651 120.37 40.7351 + vertex -393.93 114.855 39.1942 + endloop + endfacet + facet normal 0.290797 -0.0671725 0.954424 + outer loop + vertex -392.968 119.33 39.2349 + vertex -396.698 124.769 40.7541 + vertex -397.651 120.37 40.7351 + endloop + endfacet + facet normal 0.292723 -0.0657163 0.953936 + outer loop + vertex -392.041 123.729 39.2534 + vertex -396.698 124.769 40.7541 + vertex -392.968 119.33 39.2349 + endloop + endfacet + facet normal 0.292577 -0.0663676 0.953936 + outer loop + vertex -392.041 123.729 39.2534 + vertex -395.741 129.138 40.7647 + vertex -396.698 124.769 40.7541 + endloop + endfacet + facet normal 0.295374 -0.0642537 0.953219 + outer loop + vertex -391.116 128.099 39.2616 + vertex -395.741 129.138 40.7647 + vertex -392.041 123.729 39.2534 + endloop + endfacet + facet normal 0.295468 -0.063834 0.953218 + outer loop + vertex -391.116 128.099 39.2616 + vertex -394.792 133.548 40.766 + vertex -395.741 129.138 40.7647 + endloop + endfacet + facet normal 0.298177 -0.061811 0.952507 + outer loop + vertex -390.202 132.506 39.2614 + vertex -394.792 133.548 40.766 + vertex -391.116 128.099 39.2616 + endloop + endfacet + facet normal 0.29784 -0.0633021 0.952515 + outer loop + vertex -390.202 132.506 39.2614 + vertex -393.833 138.039 40.7644 + vertex -394.792 133.548 40.766 + endloop + endfacet + facet normal 0.29803 -0.0631641 0.952464 + outer loop + vertex -389.256 136.999 39.2632 + vertex -393.833 138.039 40.7644 + vertex -390.202 132.506 39.2614 + endloop + endfacet + facet normal 0.297712 -0.064571 0.95247 + outer loop + vertex -389.256 136.999 39.2632 + vertex -392.851 142.594 40.7664 + vertex -393.833 138.039 40.7644 + endloop + endfacet + facet normal 0.300377 -0.0626678 0.95176 + outer loop + vertex -388.304 141.558 39.2631 + vertex -392.851 142.594 40.7664 + vertex -389.256 136.999 39.2632 + endloop + endfacet + facet normal 0.300025 -0.0642209 0.951767 + outer loop + vertex -388.304 141.558 39.2631 + vertex -391.876 147.154 40.7667 + vertex -392.851 142.594 40.7664 + endloop + endfacet + facet normal 0.302023 -0.0628015 0.95123 + outer loop + vertex -387.356 146.122 39.2634 + vertex -391.876 147.154 40.7667 + vertex -388.304 141.558 39.2631 + endloop + endfacet + facet normal 0.301846 -0.0635833 0.951234 + outer loop + vertex -387.356 146.122 39.2634 + vertex -390.921 151.662 40.765 + vertex -391.876 147.154 40.7667 + endloop + endfacet + facet normal 0.304347 -0.0617894 0.950555 + outer loop + vertex -386.433 150.636 39.2612 + vertex -390.921 151.662 40.765 + vertex -387.356 146.122 39.2634 + endloop + endfacet + facet normal 0.304 -0.0633244 0.950565 + outer loop + vertex -386.433 150.636 39.2612 + vertex -389.991 156.086 40.7623 + vertex -390.921 151.662 40.765 + endloop + endfacet + facet normal 0.304001 -0.0633237 0.950565 + outer loop + vertex -385.516 155.066 39.2632 + vertex -389.991 156.086 40.7623 + vertex -386.433 150.636 39.2612 + endloop + endfacet + facet normal 0.303676 -0.0647598 0.950572 + outer loop + vertex -385.516 155.066 39.2632 + vertex -389.072 160.434 40.7648 + vertex -389.991 156.086 40.7623 + endloop + endfacet + facet normal 0.30704 -0.0622757 0.949657 + outer loop + vertex -384.634 159.425 39.2637 + vertex -389.072 160.434 40.7648 + vertex -385.516 155.066 39.2632 + endloop + endfacet + facet normal 0.30671 -0.063737 0.949666 + outer loop + vertex -384.634 159.425 39.2637 + vertex -388.178 164.758 40.7663 + vertex -389.072 160.434 40.7648 + endloop + endfacet + facet normal 0.307882 -0.0628681 0.949345 + outer loop + vertex -383.759 163.753 39.2667 + vertex -388.178 164.758 40.7663 + vertex -384.634 159.425 39.2637 + endloop + endfacet + facet normal 0.307089 -0.06638 0.949363 + outer loop + vertex -383.759 163.753 39.2667 + vertex -387.259 169.114 40.7738 + vertex -388.178 164.758 40.7663 + endloop + endfacet + facet normal 0.308499 -0.0653504 0.948977 + outer loop + vertex -382.852 168.105 39.2715 + vertex -387.259 169.114 40.7738 + vertex -383.759 163.753 39.2667 + endloop + endfacet + facet normal 0.308248 -0.0664557 0.948982 + outer loop + vertex -382.852 168.105 39.2715 + vertex -386.305 173.537 40.7736 + vertex -387.259 169.114 40.7738 + endloop + endfacet + facet normal 0.306314 -0.0678315 0.949511 + outer loop + vertex -381.877 172.517 39.2721 + vertex -386.305 173.537 40.7736 + vertex -382.852 168.105 39.2715 + endloop + endfacet + facet normal 0.306723 -0.0660483 0.949504 + outer loop + vertex -381.877 172.517 39.2721 + vertex -385.296 178.012 40.7588 + vertex -386.305 173.537 40.7736 + endloop + endfacet + facet normal 0.304115 -0.0678631 0.950215 + outer loop + vertex -380.858 176.988 39.2654 + vertex -385.296 178.012 40.7588 + vertex -381.877 172.517 39.2721 + endloop + endfacet + facet normal 0.305043 -0.0638172 0.950198 + outer loop + vertex -380.858 176.988 39.2654 + vertex -384.289 182.511 40.7377 + vertex -385.296 178.012 40.7588 + endloop + endfacet + facet normal 0.30964 -0.0606212 0.94892 + outer loop + vertex -379.944 181.521 39.2567 + vertex -384.289 182.511 40.7377 + vertex -380.858 176.988 39.2654 + endloop + endfacet + facet normal 0.31064 -0.0561531 0.948867 + outer loop + vertex -379.944 181.521 39.2567 + vertex -383.506 187.087 40.7522 + vertex -384.289 182.511 40.7377 + endloop + endfacet + facet normal 0.322015 -0.0479736 0.945518 + outer loop + vertex -379.299 186.16 39.2725 + vertex -383.506 187.087 40.7522 + vertex -379.944 181.521 39.2567 + endloop + endfacet + facet normal 0.326042 -0.0287266 0.944919 + outer loop + vertex -379.299 186.16 39.2725 + vertex -383.304 191.889 40.8285 + vertex -383.506 187.087 40.7522 + endloop + endfacet + facet normal 0.325074 -0.0294873 0.945229 + outer loop + vertex -378.84 190.918 39.263 + vertex -383.304 191.889 40.8285 + vertex -379.299 186.16 39.2725 + endloop + endfacet + facet normal 0.0643114 -0.232248 0.970528 + outer loop + vertex -396.906 65.8135 33.5805 + vertex -405.643 66.9722 34.4368 + vertex -397.778 61.6985 32.6536 + endloop + endfacet + facet normal 0.00339347 -0.205823 0.978583 + outer loop + vertex -371.585 52.4331 30.2598 + vertex -386.269 55.1493 30.882 + vertex -371.732 48.0641 29.3414 + endloop + endfacet + facet normal -0.0166048 -0.205152 0.978589 + outer loop + vertex -356.156 45.1421 28.9931 + vertex -371.585 52.4331 30.2598 + vertex -371.732 48.0641 29.3414 + endloop + endfacet + facet normal -0.0225193 -0.191046 0.981323 + outer loop + vertex -340.199 42.2458 28.7955 + vertex -356.156 45.1421 28.9931 + vertex -340.087 38.5639 28.0812 + endloop + endfacet + facet normal -0.0290831 -0.191207 0.981119 + outer loop + vertex -323.934 35.757 28.013 + vertex -340.199 42.2458 28.7955 + vertex -340.087 38.5639 28.0812 + endloop + endfacet + facet normal -0.0292588 -0.185432 0.982221 + outer loop + vertex -307.704 33.0645 27.9882 + vertex -324.009 39.4008 28.6987 + vertex -323.934 35.757 28.013 + endloop + endfacet + facet normal -0.0283609 -0.183765 0.982561 + outer loop + vertex -291.465 30.504 27.9781 + vertex -307.747 36.669 28.6611 + vertex -307.704 33.0645 27.9882 + endloop + endfacet + facet normal -0.0267267 -0.183529 0.982651 + outer loop + vertex -275.221 28.0699 27.9652 + vertex -291.463 34.0766 28.6453 + vertex -291.465 30.504 27.9781 + endloop + endfacet + facet normal -0.0248883 -0.183457 0.982713 + outer loop + vertex -258.986 25.7626 27.9457 + vertex -275.156 31.6165 28.629 + vertex -275.221 28.0699 27.9652 + endloop + endfacet + facet normal -0.0229857 -0.182591 0.98292 + outer loop + vertex -242.754 23.5981 27.9232 + vertex -258.828 29.2874 28.6042 + vertex -258.986 25.7626 27.9457 + endloop + endfacet + facet normal -0.0213625 -0.181503 0.983158 + outer loop + vertex -226.465 21.5207 27.8936 + vertex -242.504 27.0847 28.5723 + vertex -242.754 23.5981 27.9232 + endloop + endfacet + facet normal -0.0194659 -0.179703 0.983528 + outer loop + vertex -210.172 19.5925 27.8638 + vertex -226.197 25.0105 28.5365 + vertex -226.465 21.5207 27.8936 + endloop + endfacet + facet normal -0.0175314 -0.177929 0.983887 + outer loop + vertex -193.884 17.8094 27.8315 + vertex -209.898 23.0714 28.4978 + vertex -210.172 19.5925 27.8638 + endloop + endfacet + facet normal -0.015572 -0.176174 0.984236 + outer loop + vertex -177.568 16.1645 27.7953 + vertex -193.584 21.266 28.455 + vertex -193.884 17.8094 27.8315 + endloop + endfacet + facet normal -0.0135854 -0.173703 0.984704 + outer loop + vertex -161.226 14.6604 27.7554 + vertex -177.226 19.6134 28.4084 + vertex -177.568 16.1645 27.7953 + endloop + endfacet + facet normal -0.0116992 -0.170811 0.985234 + outer loop + vertex -144.921 13.3013 27.7134 + vertex -160.849 18.1097 28.3579 + vertex -161.226 14.6604 27.7554 + endloop + endfacet + facet normal -0.0100241 -0.16783 0.985765 + outer loop + vertex -128.742 12.0932 27.6722 + vertex -144.534 16.7496 28.3044 + vertex -144.921 13.3013 27.7134 + endloop + endfacet + facet normal -0.00853976 -0.164965 0.986262 + outer loop + vertex -112.682 11.023 27.6323 + vertex -128.366 15.5315 28.2506 + vertex -128.742 12.0932 27.6722 + endloop + endfacet + facet normal -0.00727738 -0.162763 0.986638 + outer loop + vertex -96.6672 10.077 27.5943 + vertex -112.345 14.4369 28.1979 + vertex -112.682 11.023 27.6323 + endloop + endfacet + facet normal -0.00607134 -0.160592 0.987002 + outer loop + vertex -80.5778 9.25754 27.56 + vertex -96.3816 13.4796 28.1497 + vertex -96.6672 10.077 27.5943 + endloop + endfacet + facet normal -0.00498393 -0.159065 0.987256 + outer loop + vertex -64.4084 8.56722 27.5304 + vertex -80.3855 12.6385 28.1057 + vertex -80.5778 9.25754 27.56 + endloop + endfacet + facet normal -0.00394777 -0.158273 0.987388 + outer loop + vertex -48.2346 8.0096 27.5057 + vertex -64.3438 11.911 28.0666 + vertex -64.4084 8.56722 27.5304 + endloop + endfacet + facet normal -0.0028646 -0.157858 0.987458 + outer loop + vertex -32.0644 7.59072 27.4856 + vertex -48.2668 11.3172 28.0343 + vertex -48.2346 8.0096 27.5057 + endloop + endfacet + facet normal -0.0017165 -0.157503 0.987517 + outer loop + vertex -15.8964 7.33689 27.4732 + vertex -32.1535 10.8811 28.0102 + vertex -32.0644 7.59072 27.4856 + endloop + endfacet + facet normal -0.000580916 -0.157483 0.987522 + outer loop + vertex 0.273026 7.25446 27.4696 + vertex -16.0226 10.6086 27.9949 + vertex -15.8964 7.33689 27.4732 + endloop + endfacet + facet normal 0.000586667 -0.157479 0.987522 + outer loop + vertex 16.4791 7.33707 27.4731 + vertex 0.0983757 10.513 27.9893 + vertex 0.273026 7.25446 27.4696 + endloop + endfacet + facet normal 0.00180069 -0.157308 0.987548 + outer loop + vertex 32.7445 7.59188 27.4841 + vertex 16.2191 10.6017 27.9936 + vertex 16.4791 7.33707 27.4731 + endloop + endfacet + facet normal 0.00291693 -0.157613 0.987497 + outer loop + vertex 49.022 8.00577 27.502 + vertex 32.363 10.8622 28.0072 + vertex 32.7445 7.59188 27.4841 + endloop + endfacet + facet normal 0.00400916 -0.157514 0.987509 + outer loop + vertex 65.2323 8.57034 27.5263 + vertex 48.5095 11.3048 28.0303 + vertex 49.022 8.00577 27.502 + endloop + endfacet + facet normal 0.00507882 -0.158053 0.987418 + outer loop + vertex 81.3604 9.26842 27.5551 + vertex 64.616 11.8915 28.0611 + vertex 65.2323 8.57034 27.5263 + endloop + endfacet + facet normal 0.00616435 -0.158847 0.987284 + outer loop + vertex 97.435 10.1043 27.5892 + vertex 80.6752 12.621 28.0987 + vertex 81.3604 9.26842 27.5551 + endloop + endfacet + facet normal 0.0072825 -0.160126 0.98707 + outer loop + vertex 113.556 11.0721 27.6272 + vertex 96.7342 13.4835 28.1425 + vertex 97.435 10.1043 27.5892 + endloop + endfacet + facet normal 0.00847585 -0.162317 0.986702 + outer loop + vertex 129.807 12.1669 27.6677 + vertex 112.86 14.4629 28.191 + vertex 113.556 11.0721 27.6272 + endloop + endfacet + facet normal 0.00990967 -0.164557 0.986318 + outer loop + vertex 146.176 13.409 27.7105 + vertex 129.077 15.5763 28.2439 + vertex 129.807 12.1669 27.6677 + endloop + endfacet + facet normal 0.0114538 -0.167568 0.985794 + outer loop + vertex 162.539 14.7745 27.7525 + vertex 145.353 16.8085 28.2979 + vertex 146.176 13.409 27.7105 + endloop + endfacet + facet normal 0.0132387 -0.170295 0.985304 + outer loop + vertex 178.778 16.2722 27.7932 + vertex 161.594 18.1718 28.3524 + vertex 162.539 14.7745 27.7525 + endloop + endfacet + facet normal 0.0152058 -0.172994 0.984806 + outer loop + vertex 194.939 17.9051 27.8305 + vertex 177.779 19.6638 28.4044 + vertex 178.778 16.2722 27.7932 + endloop + endfacet + facet normal 0.017287 -0.175434 0.984339 + outer loop + vertex 211.143 19.6917 27.8643 + vertex 193.977 21.3017 28.4527 + vertex 194.939 17.9051 27.8305 + endloop + endfacet + facet normal 0.0192842 -0.177777 0.983882 + outer loop + vertex 227.459 21.6235 27.8936 + vertex 210.279 23.0948 28.4962 + vertex 211.143 19.6917 27.8643 + endloop + endfacet + facet normal 0.0212367 -0.179357 0.983555 + outer loop + vertex 243.824 23.7092 27.9206 + vertex 226.691 25.0529 28.5356 + vertex 227.459 21.6235 27.8936 + endloop + endfacet + facet normal 0.0231216 -0.180618 0.983282 + outer loop + vertex 260.198 25.9316 27.9438 + vertex 243.147 27.1562 28.5697 + vertex 243.824 23.7092 27.9206 + endloop + endfacet + facet normal 0.0249952 -0.18199 0.982983 + outer loop + vertex 276.556 28.2796 27.9625 + vertex 259.598 29.38 28.5975 + vertex 260.198 25.9316 27.9438 + endloop + endfacet + facet normal 0.0265804 -0.182229 0.982897 + outer loop + vertex 292.875 30.7486 27.979 + vertex 276.023 31.7637 28.6229 + vertex 276.556 28.2796 27.9625 + endloop + endfacet + facet normal 0.0278283 -0.183295 0.982664 + outer loop + vertex 309.116 33.3224 27.9991 + vertex 292.435 34.2518 28.6449 + vertex 292.875 30.7486 27.979 + endloop + endfacet + facet normal 0.0284237 -0.184477 0.982426 + outer loop + vertex 325.207 36.0112 28.0385 + vertex 308.759 36.8649 28.6747 + vertex 309.116 33.3224 27.9991 + endloop + endfacet + facet normal 0.0280625 -0.186295 0.982093 + outer loop + vertex 341.173 38.761 28.1039 + vertex 324.908 39.5685 28.7218 + vertex 325.207 36.0112 28.0385 + endloop + endfacet + facet normal 0.0298164 -0.207743 0.977729 + outer loop + vertex 357.019 41.5807 28.2198 + vertex 341.173 38.761 28.1039 + vertex 356.741 38.8 27.6374 + endloop + endfacet + facet normal 0.0319022 -0.227767 0.973193 + outer loop + vertex 372.722 41.7449 27.8028 + vertex 356.741 38.8 27.6374 + vertex 371.021 39.4451 27.3203 + endloop + endfacet + facet normal 0.0249333 -0.179413 0.983458 + outer loop + vertex 363.027 37.3735 27.1106 + vertex 356.934 36.1916 27.0495 + vertex 357.703 36.0762 27.0089 + endloop + endfacet + facet normal 0.0260837 -0.184063 0.982568 + outer loop + vertex 370.274 38.5862 27.1454 + vertex 363.027 37.3735 27.1106 + vertex 357.703 36.0762 27.0089 + endloop + endfacet + facet normal 0.0258574 -0.173612 0.984475 + outer loop + vertex 356.934 36.1916 27.0495 + vertex 348.876 34.7375 27.0047 + vertex 357.703 36.0762 27.0089 + endloop + endfacet + facet normal 0.0321753 -0.208628 0.977466 + outer loop + vertex 354.539 36.5117 27.2054 + vertex 340.79 35.9467 27.5374 + vertex 338.745 33.5777 27.0991 + endloop + endfacet + facet normal 0.0203397 -0.145622 0.989131 + outer loop + vertex 348.876 34.7375 27.0047 + vertex 341.944 33.4358 26.9556 + vertex 337.426 32.4388 26.9017 + endloop + endfacet + facet normal 0.0254273 -0.170777 0.984982 + outer loop + vertex 337.426 32.4388 26.9017 + vertex 357.703 36.0762 27.0089 + vertex 348.876 34.7375 27.0047 + endloop + endfacet + facet normal 0.0296754 -0.18753 0.981811 + outer loop + vertex 341.944 33.4358 26.9556 + vertex 338.245 32.789 26.9438 + vertex 337.426 32.4388 26.9017 + endloop + endfacet + facet normal 0.0307176 -0.18991 0.981321 + outer loop + vertex 338.245 32.789 26.9438 + vertex 330.48 31.5024 26.9379 + vertex 337.426 32.4388 26.9017 + endloop + endfacet + facet normal 0.0327235 -0.204909 0.978234 + outer loop + vertex 316.576 28.907 26.8594 + vertex 337.426 32.4388 26.9017 + vertex 330.48 31.5024 26.9379 + endloop + endfacet + facet normal 0.0325769 -0.20359 0.978514 + outer loop + vertex 338.745 33.5777 27.0991 + vertex 324.835 33.1855 27.4806 + vertex 322.528 30.8912 27.08 + endloop + endfacet + facet normal 0.038781 -0.237133 0.970703 + outer loop + vertex 330.48 31.5024 26.9379 + vertex 322.933 30.1929 26.9195 + vertex 316.576 28.907 26.8594 + endloop + endfacet + facet normal 0.0361128 -0.224092 0.973899 + outer loop + vertex 322.933 30.1929 26.9195 + vertex 317.646 29.3799 26.9285 + vertex 316.576 28.907 26.8594 + endloop + endfacet + facet normal 0.0318813 -0.200649 0.979144 + outer loop + vertex 322.528 30.8912 27.08 + vertex 308.88 30.5439 27.4532 + vertex 307.567 28.3418 27.0447 + endloop + endfacet + facet normal 0.0367504 -0.225484 0.973553 + outer loop + vertex 317.646 29.3799 26.9285 + vertex 313.339 28.5673 26.9029 + vertex 316.576 28.907 26.8594 + endloop + endfacet + facet normal 0.038385 -0.241561 0.969626 + outer loop + vertex 313.339 28.5673 26.9029 + vertex 307.47 27.5823 26.8898 + vertex 316.576 28.907 26.8594 + endloop + endfacet + facet normal 0.0436367 -0.27789 0.959621 + outer loop + vertex 294.812 25.429 26.8419 + vertex 316.576 28.907 26.8594 + vertex 307.47 27.5823 26.8898 + endloop + endfacet + facet normal 0.0369584 -0.238872 0.970348 + outer loop + vertex 307.47 27.5823 26.8898 + vertex 299.894 26.5268 26.9186 + vertex 294.812 25.429 26.8419 + endloop + endfacet + facet normal 0.0307379 -0.199432 0.979429 + outer loop + vertex 307.567 28.3418 27.0447 + vertex 292.784 27.9984 27.4387 + vertex 290.97 25.8393 27.056 + endloop + endfacet + facet normal 0.0376938 -0.242216 0.96949 + outer loop + vertex 299.894 26.5268 26.9186 + vertex 293.738 25.5148 26.9051 + vertex 294.812 25.429 26.8419 + endloop + endfacet + facet normal 0.0370703 -0.248813 0.967842 + outer loop + vertex 293.738 25.5148 26.9051 + vertex 285.469 24.266 26.9007 + vertex 294.812 25.429 26.8419 + endloop + endfacet + facet normal 0.0383895 -0.259557 0.964964 + outer loop + vertex 273.997 22.3044 26.8295 + vertex 294.812 25.429 26.8419 + vertex 285.469 24.266 26.9007 + endloop + endfacet + facet normal 0.0290841 -0.198798 0.979609 + outer loop + vertex 290.97 25.8393 27.056 + vertex 276.467 25.5476 27.4275 + vertex 274.796 23.3181 27.0246 + endloop + endfacet + facet normal 0.0463119 -0.305383 0.951103 + outer loop + vertex 285.469 24.266 26.9007 + vertex 278.326 23.1402 26.8871 + vertex 273.997 22.3044 26.8295 + endloop + endfacet + facet normal 0.0374098 -0.260224 0.964823 + outer loop + vertex 278.326 23.1402 26.8871 + vertex 274.544 22.587 26.8845 + vertex 273.997 22.3044 26.8295 + endloop + endfacet + facet normal 0.0350972 -0.255985 0.966043 + outer loop + vertex 274.544 22.587 26.8845 + vertex 266.564 21.5032 26.8872 + vertex 273.997 22.3044 26.8295 + endloop + endfacet + facet normal 0.027326 -0.198595 0.979701 + outer loop + vertex 274.796 23.3181 27.0246 + vertex 260.159 23.2076 27.4105 + vertex 258.15 21.0586 27.0309 + endloop + endfacet + facet normal 0.0312728 -0.237796 0.970812 + outer loop + vertex 258.813 20.3897 26.8779 + vertex 253.411 19.7177 26.8873 + vertex 252.699 19.3316 26.8156 + endloop + endfacet + facet normal 0.025469 -0.197088 0.980055 + outer loop + vertex 258.15 21.0586 27.0309 + vertex 243.95 21.0207 27.3923 + vertex 243.105 18.9395 26.9957 + endloop + endfacet + facet normal 0.0320682 -0.239195 0.970442 + outer loop + vertex 253.411 19.7177 26.8873 + vertex 249.114 19.0404 26.8623 + vertex 252.699 19.3316 26.8156 + endloop + endfacet + facet normal 0.029369 -0.240158 0.970289 + outer loop + vertex 243.278 18.237 26.8471 + vertex 235.564 17.3989 26.8732 + vertex 230.843 16.5074 26.7954 + endloop + endfacet + facet normal 0.0236187 -0.195337 0.980452 + outer loop + vertex 243.105 18.9395 26.9957 + vertex 227.737 18.9781 27.3736 + vertex 226.44 16.9476 27.0003 + endloop + endfacet + facet normal 0.030717 -0.24714 0.968493 + outer loop + vertex 235.564 17.3989 26.8732 + vertex 229.549 16.5783 26.8545 + vertex 230.843 16.5074 26.7954 + endloop + endfacet + facet normal 0.0299105 -0.259244 0.965349 + outer loop + vertex 229.549 16.5783 26.8545 + vertex 221.317 15.6048 26.8482 + vertex 230.843 16.5074 26.7954 + endloop + endfacet + facet normal 0.0304862 -0.265418 0.963651 + outer loop + vertex 210.28 14.0709 26.7748 + vertex 230.843 16.5074 26.7954 + vertex 221.317 15.6048 26.8482 + endloop + endfacet + facet normal 0.0216587 -0.193966 0.980769 + outer loop + vertex 226.44 16.9476 27.0003 + vertex 211.532 17.0461 27.349 + vertex 210.452 14.975 26.9633 + endloop + endfacet + facet normal 0.0361036 -0.30526 0.951584 + outer loop + vertex 221.317 15.6048 26.8482 + vertex 214.236 14.7199 26.833 + vertex 210.28 14.0709 26.7748 + endloop + endfacet + facet normal 0.0287773 -0.261781 0.964698 + outer loop + vertex 214.236 14.7199 26.833 + vertex 210.537 14.2999 26.8293 + vertex 210.28 14.0709 26.7748 + endloop + endfacet + facet normal 0.0266466 -0.259545 0.965363 + outer loop + vertex 210.537 14.2999 26.8293 + vertex 202.772 13.497 26.8278 + vertex 210.28 14.0709 26.7748 + endloop + endfacet + facet normal 0.0195817 -0.192455 0.98111 + outer loop + vertex 210.452 14.975 26.9633 + vertex 195.347 15.2738 27.3234 + vertex 193.721 13.2596 26.9607 + endloop + endfacet + facet normal 0.0301281 -0.28795 0.957171 + outer loop + vertex 202.772 13.497 26.8278 + vertex 194.973 12.6444 26.8168 + vertex 189.707 11.8744 26.7509 + endloop + endfacet + facet normal 0.0224134 -0.236408 0.971395 + outer loop + vertex 194.973 12.6444 26.8168 + vertex 188.641 12.0623 26.8212 + vertex 189.707 11.8744 26.7509 + endloop + endfacet + facet normal 0.0174761 -0.189994 0.98163 + outer loop + vertex 193.721 13.2596 26.9607 + vertex 179.105 13.6339 27.2934 + vertex 177.7 11.5453 26.9141 + endloop + endfacet + facet normal 0.0225878 -0.2355 0.971612 + outer loop + vertex 188.641 12.0623 26.8212 + vertex 181.34 11.1912 26.7798 + vertex 189.707 11.8744 26.7509 + endloop + endfacet + facet normal 0.0199055 -0.235973 0.971556 + outer loop + vertex 175.874 10.6925 26.7805 + vertex 171.045 10.3229 26.7897 + vertex 168.834 9.85913 26.7223 + endloop + endfacet + facet normal 0.0154721 -0.187355 0.98217 + outer loop + vertex 177.7 11.5453 26.9141 + vertex 162.71 12.1152 27.259 + vertex 160.969 10.0251 26.8877 + endloop + endfacet + facet normal 0.0212879 -0.242332 0.96996 + outer loop + vertex 171.045 10.3229 26.7897 + vertex 166.281 9.81218 26.7666 + vertex 168.834 9.85913 26.7223 + endloop + endfacet + facet normal 0.0215915 -0.264268 0.964208 + outer loop + vertex 166.281 9.81218 26.7666 + vertex 160.122 9.24314 26.7486 + vertex 168.834 9.85913 26.7223 + endloop + endfacet + facet normal 0.0243787 -0.304193 0.952298 + outer loop + vertex 146.785 7.98739 26.6889 + vertex 168.834 9.85913 26.7223 + vertex 160.122 9.24314 26.7486 + endloop + endfacet + facet normal 0.0177602 -0.23483 0.971874 + outer loop + vertex 160.122 9.24314 26.7486 + vertex 152.606 8.74564 26.7657 + vertex 146.785 7.98739 26.6889 + endloop + endfacet + facet normal 0.0135699 -0.184745 0.982693 + outer loop + vertex 160.969 10.0251 26.8877 + vertex 146.117 10.7441 27.228 + vertex 143.923 8.72938 26.8795 + endloop + endfacet + facet normal 0.0186391 -0.241412 0.970244 + outer loop + vertex 152.606 8.74564 26.7657 + vertex 146.274 8.16688 26.7433 + vertex 146.785 7.98739 26.6889 + endloop + endfacet + facet normal 0.0168918 -0.24604 0.969112 + outer loop + vertex 146.274 8.16688 26.7433 + vertex 137.757 7.53106 26.7304 + vertex 146.785 7.98739 26.6889 + endloop + endfacet + facet normal 0.0117573 -0.181963 0.983235 + outer loop + vertex 143.923 8.72938 26.8795 + vertex 129.732 9.51443 27.1945 + vertex 128.108 7.4609 26.8339 + endloop + endfacet + facet normal 0.0169841 -0.259876 0.965493 + outer loop + vertex 130.651 6.94234 26.7089 + vertex 127.623 6.73055 26.7051 + vertex 125.033 6.38388 26.6574 + endloop + endfacet + facet normal 0.025954 -0.347511 0.937317 + outer loop + vertex 137.757 7.53106 26.7304 + vertex 130.651 6.94234 26.7089 + vertex 125.033 6.38388 26.6574 + endloop + endfacet + facet normal 0.017205 -0.252383 0.967474 + outer loop + vertex 125.033 6.38388 26.6574 + vertex 146.785 7.98739 26.6889 + vertex 137.757 7.53106 26.7304 + endloop + endfacet + facet normal 0.0125189 -0.227634 0.973666 + outer loop + vertex 127.623 6.73055 26.7051 + vertex 122.533 6.50114 26.7169 + vertex 125.033 6.38388 26.6574 + endloop + endfacet + facet normal 0.0101561 -0.180281 0.983563 + outer loop + vertex 128.108 7.4609 26.8339 + vertex 113.634 8.43548 27.1619 + vertex 112.239 6.52403 26.826 + endloop + endfacet + facet normal 0.0116638 -0.21908 0.975637 + outer loop + vertex 114.869 5.91475 26.6852 + vertex 106.588 5.51754 26.695 + vertex 103.113 5.02051 26.625 + endloop + endfacet + facet normal 0.00873562 -0.17876 0.983854 + outer loop + vertex 112.239 6.52403 26.826 + vertex 97.5969 7.49817 27.133 + vertex 96.2653 5.53032 26.7873 + endloop + endfacet + facet normal 0.0123073 -0.223439 0.97464 + outer loop + vertex 106.588 5.51754 26.695 + vertex 101.42 5.12269 26.6698 + vertex 103.113 5.02051 26.625 + endloop + endfacet + facet normal 0.0113137 -0.238351 0.971113 + outer loop + vertex 101.42 5.12269 26.6698 + vertex 95.4346 4.77532 26.6543 + vertex 103.113 5.02051 26.625 + endloop + endfacet + facet normal 0.0122418 -0.268354 0.963243 + outer loop + vertex 82.6393 4.00411 26.602 + vertex 103.113 5.02051 26.625 + vertex 95.4346 4.77532 26.6543 + endloop + endfacet + facet normal 0.00934468 -0.221099 0.975207 + outer loop + vertex 95.4346 4.77532 26.6543 + vertex 88.4363 4.55625 26.6716 + vertex 82.6393 4.00411 26.602 + endloop + endfacet + facet normal 0.0073113 -0.177904 0.984021 + outer loop + vertex 96.2653 5.53032 26.7873 + vertex 81.4749 6.69106 27.107 + vertex 79.7625 4.81509 26.7806 + endloop + endfacet + facet normal 0.00958784 -0.22358 0.974638 + outer loop + vertex 88.4363 4.55625 26.6716 + vertex 82.2886 4.2149 26.6538 + vertex 82.6393 4.00411 26.602 + endloop + endfacet + facet normal 0.00820413 -0.225761 0.974148 + outer loop + vertex 82.2886 4.2149 26.6538 + vertex 73.9074 3.86655 26.6437 + vertex 82.6393 4.00411 26.602 + endloop + endfacet + facet normal 0.00591981 -0.177683 0.98407 + outer loop + vertex 79.7625 4.81509 26.7806 + vertex 65.2758 6.0092 27.0833 + vertex 63.9149 4.07953 26.7431 + endloop + endfacet + facet normal 0.0127731 -0.314285 0.949243 + outer loop + vertex 73.9074 3.86655 26.6437 + vertex 66.8184 3.52692 26.6266 + vertex 61.3081 3.16554 26.5811 + endloop + endfacet + facet normal 0.00837041 -0.237136 0.97144 + outer loop + vertex 61.3081 3.16554 26.5811 + vertex 82.6393 4.00411 26.602 + vertex 73.9074 3.86655 26.6437 + endloop + endfacet + facet normal 0.00799549 -0.244017 0.969738 + outer loop + vertex 66.8184 3.52692 26.6266 + vertex 63.6872 3.41659 26.6247 + vertex 61.3081 3.16554 26.5811 + endloop + endfacet + facet normal 0.00556617 -0.221916 0.97505 + outer loop + vertex 63.6872 3.41659 26.6247 + vertex 58.4402 3.33042 26.635 + vertex 61.3081 3.16554 26.5811 + endloop + endfacet + facet normal 0.00461171 -0.177824 0.984052 + outer loop + vertex 63.9149 4.07953 26.7431 + vertex 48.9385 5.4554 27.0619 + vertex 47.0965 3.56865 26.7296 + endloop + endfacet + facet normal 0.00607981 -0.253569 0.967298 + outer loop + vertex 51.3768 3.00336 26.6066 + vertex 45.4147 2.87958 26.6116 + vertex 39.8504 2.56187 26.5633 + endloop + endfacet + facet normal 0.00384237 -0.215774 0.976436 + outer loop + vertex 45.4147 2.87958 26.6116 + vertex 39.6848 2.84183 26.6258 + vertex 39.8504 2.56187 26.5633 + endloop + endfacet + facet normal 0.00327609 -0.177855 0.984051 + outer loop + vertex 47.0965 3.56865 26.7296 + vertex 32.4005 5.07526 27.0508 + vertex 30.0167 3.29231 26.7365 + endloop + endfacet + facet normal 0.00395719 -0.215709 0.97645 + outer loop + vertex 39.6848 2.84183 26.6258 + vertex 31.4672 2.57579 26.6004 + vertex 39.8504 2.56187 26.5633 + endloop + endfacet + facet normal 0.00383629 -0.259782 0.96566 + outer loop + vertex 19.0324 2.21475 26.5526 + vertex 39.8504 2.56187 26.5633 + vertex 31.4672 2.57579 26.6004 + endloop + endfacet + facet normal 0.00275615 -0.223768 0.974639 + outer loop + vertex 31.4672 2.57579 26.6004 + vertex 23.5983 2.54578 26.6157 + vertex 19.0324 2.21475 26.5526 + endloop + endfacet + facet normal 0.00181829 -0.178129 0.984005 + outer loop + vertex 30.0167 3.29231 26.7365 + vertex 16.0308 4.83649 27.0419 + vertex 13.8313 2.98941 26.7116 + endloop + endfacet + facet normal 0.00350318 -0.233629 0.972319 + outer loop + vertex 23.5983 2.54578 26.6157 + vertex 18.2762 2.37833 26.5947 + vertex 19.0324 2.21475 26.5526 + endloop + endfacet + facet normal 0.00164658 -0.241706 0.970348 + outer loop + vertex 18.2762 2.37833 26.5947 + vertex 12.0453 2.2932 26.584 + vertex 19.0324 2.21475 26.5526 + endloop + endfacet + facet normal 0.000515635 -0.177847 0.984058 + outer loop + vertex 13.8313 2.98941 26.7116 + vertex -0.125221 4.75224 27.0375 + vertex -2.03578 3.0106 26.7237 + endloop + endfacet + facet normal 0.0010256 -0.238404 0.971165 + outer loop + vertex 5.43999 2.37828 26.6066 + vertex -0.108635 2.31615 26.5972 + vertex -1.9402 2.11842 26.5506 + endloop + endfacet + facet normal -0.00081431 -0.222262 0.974987 + outer loop + vertex -0.108635 2.31615 26.5972 + vertex -5.80822 2.37814 26.6066 + vertex -1.9402 2.11842 26.5506 + endloop + endfacet + facet normal -0.000838568 -0.177489 0.984122 + outer loop + vertex -2.03578 3.0106 26.7237 + vertex -16.1778 4.84034 27.0417 + vertex -17.3905 3.01832 26.712 + endloop + endfacet + facet normal -0.00184542 -0.260962 0.965347 + outer loop + vertex -12.5209 2.30094 26.5849 + vertex -18.4681 2.37871 26.5945 + vertex -23.6617 2.26628 26.5542 + endloop + endfacet + facet normal -0.00292966 -0.214919 0.976627 + outer loop + vertex -18.4681 2.37871 26.5945 + vertex -24.2525 2.55761 26.6165 + vertex -23.6617 2.26628 26.5542 + endloop + endfacet + facet normal -0.00214484 -0.17754 0.984111 + outer loop + vertex -17.3905 3.01832 26.712 + vertex -32.3293 5.08684 27.0527 + vertex -34.2398 3.3776 26.7401 + endloop + endfacet + facet normal -0.00279522 -0.214659 0.976685 + outer loop + vertex -24.2525 2.55761 26.6165 + vertex -32.328 2.59404 26.6014 + vertex -23.6617 2.26628 26.5542 + endloop + endfacet + facet normal -0.00426129 -0.252127 0.967685 + outer loop + vertex -44.4742 2.66701 26.567 + vertex -23.6617 2.26628 26.5542 + vertex -32.328 2.59404 26.6014 + endloop + endfacet + facet normal -0.00408578 -0.219135 0.975686 + outer loop + vertex -32.328 2.59404 26.6014 + vertex -40.2876 2.85139 26.6259 + vertex -44.4742 2.66701 26.567 + endloop + endfacet + facet normal -0.00354963 -0.177718 0.984075 + outer loop + vertex -34.2398 3.3776 26.7401 + vertex -48.6043 5.47463 27.067 + vertex -50.4433 3.65721 26.7322 + endloop + endfacet + facet normal -0.00393469 -0.222334 0.974963 + outer loop + vertex -40.2876 2.85139 26.6259 + vertex -45.6254 2.88838 26.6128 + vertex -44.4742 2.66701 26.567 + endloop + endfacet + facet normal -0.00557304 -0.230462 0.973065 + outer loop + vertex -45.6254 2.88838 26.6128 + vertex -51.7337 3.01314 26.6074 + vertex -44.4742 2.66701 26.567 + endloop + endfacet + facet normal -0.00629192 -0.220165 0.975442 + outer loop + vertex -51.7337 3.01314 26.6074 + vertex -58.5227 3.32497 26.634 + vertex -65.0777 3.2961 26.5852 + endloop + endfacet + facet normal -0.0071911 -0.263416 0.964656 + outer loop + vertex -65.0777 3.2961 26.5852 + vertex -44.4742 2.66701 26.567 + vertex -51.7337 3.01314 26.6074 + endloop + endfacet + facet normal -0.00491527 -0.178016 0.984015 + outer loop + vertex -50.4433 3.65721 26.7322 + vertex -64.942 6.00218 27.084 + vertex -67.1261 4.20352 26.7477 + endloop + endfacet + facet normal -0.00607035 -0.255743 0.966726 + outer loop + vertex -58.5227 3.32497 26.634 + vertex -63.3422 3.40163 26.624 + vertex -65.0777 3.2961 26.5852 + endloop + endfacet + facet normal -0.00761868 -0.232432 0.972583 + outer loop + vertex -63.3422 3.40163 26.624 + vertex -66.5924 3.52148 26.6272 + vertex -65.0777 3.2961 26.5852 + endloop + endfacet + facet normal -0.00621705 -0.178462 0.983927 + outer loop + vertex -67.1261 4.20352 26.7477 + vertex -81.3138 6.69621 27.1102 + vertex -83.7368 4.99331 26.786 + endloop + endfacet + facet normal -0.00905928 -0.245331 0.969397 + outer loop + vertex -74.5067 3.89062 26.6443 + vertex -82.7412 4.2343 26.6543 + vertex -87.2904 4.21883 26.6079 + endloop + endfacet + facet normal -0.00922177 -0.217456 0.976027 + outer loop + vertex -82.7412 4.2343 26.6543 + vertex -88.9118 4.57601 26.6721 + vertex -87.2904 4.21883 26.6079 + endloop + endfacet + facet normal -0.00767572 -0.17985 0.983664 + outer loop + vertex -83.7368 4.99331 26.786 + vertex -97.4477 7.49712 27.1368 + vertex -99.6599 5.70775 26.7924 + endloop + endfacet + facet normal -0.0093086 -0.217834 0.975941 + outer loop + vertex -88.9118 4.57601 26.6721 + vertex -95.9885 4.8028 26.6553 + vertex -87.2904 4.21883 26.6079 + endloop + endfacet + facet normal -0.0128082 -0.261562 0.965102 + outer loop + vertex -95.9885 4.8028 26.6553 + vertex -101.485 5.12678 26.6701 + vertex -107.677 5.28976 26.6321 + endloop + endfacet + facet normal -0.0135607 -0.27987 0.959942 + outer loop + vertex -107.677 5.28976 26.6321 + vertex -87.2904 4.21883 26.6079 + vertex -95.9885 4.8028 26.6553 + endloop + endfacet + facet normal -0.011664 -0.215437 0.976448 + outer loop + vertex -101.485 5.12678 26.6701 + vertex -107.01 5.54302 26.6959 + vertex -107.677 5.28976 26.6321 + endloop + endfacet + facet normal -0.00924403 -0.181873 0.983279 + outer loop + vertex -99.6599 5.70775 26.7924 + vertex -113.517 8.43785 27.1671 + vertex -116.135 6.7645 26.8329 + endloop + endfacet + facet normal -0.0115529 -0.215715 0.976388 + outer loop + vertex -107.01 5.54302 26.6959 + vertex -115.406 5.9463 26.6857 + vertex -107.677 5.28976 26.6321 + endloop + endfacet + facet normal -0.0136526 -0.229815 0.973139 + outer loop + vertex -115.406 5.9463 26.6857 + vertex -122.741 6.50996 26.7159 + vertex -128.814 6.64642 26.6629 + endloop + endfacet + facet normal -0.0149577 -0.255015 0.966821 + outer loop + vertex -128.814 6.64642 26.6629 + vertex -107.677 5.28976 26.6321 + vertex -115.406 5.9463 26.6857 + endloop + endfacet + facet normal -0.0107391 -0.183798 0.982905 + outer loop + vertex -116.135 6.7645 26.8329 + vertex -129.526 9.49691 27.1976 + vertex -131.36 7.68964 26.8396 + endloop + endfacet + facet normal -0.0143847 -0.265999 0.963866 + outer loop + vertex -122.741 6.50996 26.7159 + vertex -127.306 6.71785 26.7052 + vertex -128.814 6.64642 26.6629 + endloop + endfacet + facet normal -0.0155318 -0.245039 0.969389 + outer loop + vertex -127.306 6.71785 26.7052 + vertex -130.381 6.9229 26.7077 + vertex -128.814 6.64642 26.6629 + endloop + endfacet + facet normal -0.0123693 -0.185984 0.982475 + outer loop + vertex -131.36 7.68964 26.8396 + vertex -145.631 10.7069 27.2311 + vertex -147.742 9.01885 26.885 + endloop + endfacet + facet normal -0.0181007 -0.261141 0.965131 + outer loop + vertex -138.309 7.57042 26.7303 + vertex -146.486 8.18716 26.7438 + vertex -151.026 8.32088 26.6948 + endloop + endfacet + facet normal -0.017193 -0.22719 0.973699 + outer loop + vertex -146.486 8.18716 26.7438 + vertex -152.804 8.76387 26.7668 + vertex -151.026 8.32088 26.6948 + endloop + endfacet + facet normal -0.0141932 -0.188621 0.981947 + outer loop + vertex -147.742 9.01885 26.885 + vertex -161.881 12.0481 27.2625 + vertex -163.803 10.2793 26.8949 + endloop + endfacet + facet normal -0.0170009 -0.226448 0.973875 + outer loop + vertex -152.804 8.76387 26.7668 + vertex -159.842 9.2128 26.7483 + vertex -151.026 8.32088 26.6948 + endloop + endfacet + facet normal -0.0232731 -0.281386 0.959312 + outer loop + vertex -159.842 9.2128 26.7483 + vertex -165.455 9.73607 26.7656 + vertex -171.583 10.0998 26.7237 + endloop + endfacet + facet normal -0.0249399 -0.303637 0.952461 + outer loop + vertex -171.583 10.0998 26.7237 + vertex -151.026 8.32088 26.6948 + vertex -159.842 9.2128 26.7483 + endloop + endfacet + facet normal -0.0201417 -0.226983 0.97369 + outer loop + vertex -165.455 9.73607 26.7656 + vertex -171.175 10.368 26.7946 + vertex -171.583 10.0998 26.7237 + endloop + endfacet + facet normal -0.0163077 -0.191444 0.981368 + outer loop + vertex -163.803 10.2793 26.8949 + vertex -178.236 13.5582 27.2947 + vertex -180.64 11.9417 26.9394 + endloop + endfacet + facet normal -0.0199483 -0.227261 0.973629 + outer loop + vertex -171.175 10.368 26.7946 + vertex -179.626 11.0575 26.7824 + vertex -171.583 10.0998 26.7237 + endloop + endfacet + facet normal -0.0181301 -0.192843 0.981062 + outer loop + vertex -180.64 11.9417 26.9394 + vertex -194.501 15.1913 27.322 + vertex -196.109 13.3923 26.9387 + endloop + endfacet + facet normal -0.0243588 -0.275269 0.961059 + outer loop + vertex -187.231 11.9129 26.816 + vertex -191.794 12.2703 26.8027 + vertex -192.943 12.2057 26.7551 + endloop + endfacet + facet normal -0.0255689 -0.257382 0.965971 + outer loop + vertex -191.794 12.2703 26.8027 + vertex -194.903 12.5865 26.8047 + vertex -192.943 12.2057 26.7551 + endloop + endfacet + facet normal -0.0202592 -0.194889 0.980616 + outer loop + vertex -196.109 13.3923 26.9387 + vertex -210.848 16.973 27.3458 + vertex -213.339 15.3044 26.9627 + endloop + endfacet + facet normal -0.0311649 -0.301726 0.952885 + outer loop + vertex -202.746 13.4834 26.8221 + vertex -210.205 14.2656 26.8258 + vertex -214.411 14.5503 26.7784 + endloop + endfacet + facet normal -0.0284794 -0.260001 0.965188 + outer loop + vertex -210.205 14.2656 26.8258 + vertex -214.016 14.7012 26.8307 + vertex -214.411 14.5503 26.7784 + endloop + endfacet + facet normal -0.0299911 -0.256367 0.966114 + outer loop + vertex -214.016 14.7012 26.8307 + vertex -221.833 15.6744 26.8463 + vertex -214.411 14.5503 26.7784 + endloop + endfacet + facet normal -0.022354 -0.196694 0.98021 + outer loop + vertex -213.339 15.3044 26.9627 + vertex -227.342 18.9382 27.3726 + vertex -230.219 17.4213 27.0026 + endloop + endfacet + facet normal -0.0332482 -0.286374 0.957541 + outer loop + vertex -221.833 15.6744 26.8463 + vertex -229.727 16.61 26.852 + vertex -235.281 17.0669 26.7958 + endloop + endfacet + facet normal -0.0305369 -0.259912 0.965149 + outer loop + vertex -235.281 17.0669 26.7958 + vertex -214.411 14.5503 26.7784 + vertex -221.833 15.6744 26.8463 + endloop + endfacet + facet normal -0.0294449 -0.238522 0.970691 + outer loop + vertex -229.727 16.61 26.852 + vertex -235.878 17.438 26.8689 + vertex -235.281 17.0669 26.7958 + endloop + endfacet + facet normal -0.0244643 -0.198897 0.979715 + outer loop + vertex -230.219 17.4213 27.0026 + vertex -243.614 20.992 27.393 + vertex -246.164 19.351 26.9962 + endloop + endfacet + facet normal -0.0295353 -0.238661 0.970654 + outer loop + vertex -235.878 17.438 26.8689 + vertex -243.462 18.2724 26.8433 + vertex -235.281 17.0669 26.7958 + endloop + endfacet + facet normal -0.0319874 -0.238186 0.970693 + outer loop + vertex -248.762 18.9915 26.8545 + vertex -253.411 19.7258 26.8815 + vertex -256.495 19.8582 26.8124 + endloop + endfacet + facet normal -0.0263529 -0.200694 0.9793 + outer loop + vertex -246.164 19.351 26.9962 + vertex -259.723 23.1592 27.4118 + vertex -261.909 21.5877 27.0309 + endloop + endfacet + facet normal -0.0322182 -0.244369 0.969147 + outer loop + vertex -253.411 19.7258 26.8815 + vertex -258.796 20.4014 26.8729 + vertex -256.495 19.8582 26.8124 + endloop + endfacet + facet normal -0.0281215 -0.201879 0.979007 + outer loop + vertex -261.909 21.5877 27.0309 + vertex -275.871 25.4557 27.4274 + vertex -278.098 23.8129 27.0247 + endloop + endfacet + facet normal -0.0409598 -0.298189 0.953628 + outer loop + vertex -267.195 21.5991 26.8814 + vertex -274.745 22.6301 26.8795 + vertex -278.74 23.0138 26.8279 + endloop + endfacet + facet normal -0.0375138 -0.260822 0.964658 + outer loop + vertex -274.745 22.6301 26.8795 + vertex -278.585 23.1985 26.8839 + vertex -278.74 23.0138 26.8279 + endloop + endfacet + facet normal -0.0388424 -0.259772 0.964889 + outer loop + vertex -278.585 23.1985 26.8839 + vertex -286.319 24.4052 26.8973 + vertex -278.74 23.0138 26.8279 + endloop + endfacet + facet normal -0.0298751 -0.202118 0.978905 + outer loop + vertex -278.098 23.8129 27.0247 + vertex -292.127 27.8839 27.4371 + vertex -294.8 26.4297 27.0553 + endloop + endfacet + facet normal -0.0399224 -0.268091 0.962566 + outer loop + vertex -286.319 24.4052 26.8973 + vertex -294.191 25.5934 26.9018 + vertex -299.542 26.1846 26.8445 + endloop + endfacet + facet normal -0.0387354 -0.259197 0.965047 + outer loop + vertex -299.542 26.1846 26.8445 + vertex -278.74 23.0138 26.8279 + vertex -286.319 24.4052 26.8973 + endloop + endfacet + facet normal -0.0362649 -0.234119 0.971531 + outer loop + vertex -294.191 25.5934 26.9018 + vertex -300.273 26.5951 26.9162 + vertex -299.542 26.1846 26.8445 + endloop + endfacet + facet normal -0.0313579 -0.201284 0.979031 + outer loop + vertex -294.8 26.4297 27.0553 + vertex -308.334 30.4291 27.4441 + vertex -310.621 28.8311 27.0422 + endloop + endfacet + facet normal -0.0363035 -0.234184 0.971514 + outer loop + vertex -300.273 26.5951 26.9162 + vertex -307.738 27.6493 26.8913 + vertex -299.542 26.1846 26.8445 + endloop + endfacet + facet normal -0.0414759 -0.262886 0.963935 + outer loop + vertex -320.367 29.5547 26.8676 + vertex -299.542 26.1846 26.8445 + vertex -307.738 27.6493 26.8913 + endloop + endfacet + facet normal -0.0393681 -0.248868 0.967737 + outer loop + vertex -307.738 27.6493 26.8913 + vertex -313.002 28.5247 26.9023 + vertex -320.367 29.5547 26.8676 + endloop + endfacet + facet normal -0.0340664 -0.21065 0.976968 + outer loop + vertex -313.002 28.5247 26.9023 + vertex -317.652 29.397 26.9282 + vertex -320.367 29.5547 26.8676 + endloop + endfacet + facet normal -0.0324079 -0.201607 0.97893 + outer loop + vertex -310.621 28.8311 27.0422 + vertex -324.408 33.0815 27.4612 + vertex -326.185 31.4963 27.0759 + endloop + endfacet + facet normal -0.0340943 -0.211174 0.976854 + outer loop + vertex -317.652 29.397 26.9282 + vertex -322.916 30.2128 26.9209 + vertex -320.367 29.5547 26.8676 + endloop + endfacet + facet normal -0.0318891 -0.202165 0.978832 + outer loop + vertex -324.408 33.0815 27.4612 + vertex -340.443 35.8676 27.5142 + vertex -326.185 31.4963 27.0759 + endloop + endfacet + facet normal -0.0315946 -0.213514 0.976429 + outer loop + vertex -340.443 35.8676 27.5142 + vertex -356.06 41.4711 28.2342 + vertex -356.418 38.7577 27.6293 + endloop + endfacet + facet normal -0.0232075 -0.214619 0.976422 + outer loop + vertex -356.06 41.4711 28.2342 + vertex -371.813 44.4543 28.5155 + vertex -356.418 38.7577 27.6293 + endloop + endfacet + facet normal -0.0210084 -0.25186 0.967536 + outer loop + vertex -371.813 44.4543 28.5155 + vertex -387.104 51.0841 29.9093 + vertex -387.534 47.5165 28.9713 + endloop + endfacet + facet normal 0.000418307 -0.254333 0.967117 + outer loop + vertex -387.104 51.0841 29.9093 + vertex -402.31 54.0346 30.6918 + vertex -387.534 47.5165 28.9713 + endloop + endfacet + facet normal -0.00326358 -0.272026 0.962284 + outer loop + vertex -387.104 51.0841 29.9093 + vertex -401.546 58.446 31.9414 + vertex -402.31 54.0346 30.6918 + endloop + endfacet + facet normal 0.0267225 -0.27673 0.960576 + outer loop + vertex -401.546 58.446 31.9414 + vertex -413.571 59.9652 32.7136 + vertex -402.31 54.0346 30.6918 + endloop + endfacet + facet normal -0.017133 -0.29131 0.956475 + outer loop + vertex -387.534 47.5165 28.9713 + vertex -402.31 54.0346 30.6918 + vertex -403.651 50.6771 29.6452 + endloop + endfacet + facet normal 0.0103992 -0.301368 0.953451 + outer loop + vertex -402.31 54.0346 30.6918 + vertex -419.258 57.5369 31.9836 + vertex -403.651 50.6771 29.6452 + endloop + endfacet + facet normal -0.00485442 -0.13739 0.990505 + outer loop + vertex -391.051 42.5967 27.4015 + vertex -398.38 44.214 27.5899 + vertex -403.558 44.9696 27.6694 + endloop + endfacet + facet normal -0.0134477 -0.128792 0.99158 + outer loop + vertex -380.519 40.6445 27.2539 + vertex -385.049 41.4331 27.2949 + vertex -382.442 40.7186 27.2374 + endloop + endfacet + facet normal -0.0400323 -0.289124 0.956454 + outer loop + vertex -374.006 40.0132 27.3414 + vertex -388.26 44.8206 28.198 + vertex -390.255 43.1749 27.617 + endloop + endfacet + facet normal -0.0142465 -0.150193 0.988554 + outer loop + vertex -375.78 39.6389 27.1694 + vertex -380.519 40.6445 27.2539 + vertex -382.442 40.7186 27.2374 + endloop + endfacet + facet normal -0.036305 -0.247347 0.968247 + outer loop + vertex -358.449 37.2091 27.2084 + vertex -372.308 41.7573 27.8506 + vertex -374.006 40.0132 27.3414 + endloop + endfacet + facet normal -0.0363357 -0.226064 0.973435 + outer loop + vertex -357.384 36.2518 27.0258 + vertex -349.681 34.8686 26.9921 + vertex -358.449 37.2091 27.2084 + endloop + endfacet + facet normal -0.0328829 -0.206684 0.977855 + outer loop + vertex -349.681 34.8686 26.9921 + vertex -342.124 33.4756 26.9518 + vertex -342.042 34.1472 27.0966 + endloop + endfacet + facet normal -0.0334725 -0.20661 0.977851 + outer loop + vertex -342.124 33.4756 26.9518 + vertex -338.38 32.8135 26.9401 + vertex -342.042 34.1472 27.0966 + endloop + endfacet + facet normal -0.033588 -0.206919 0.977781 + outer loop + vertex -338.38 32.8135 26.9401 + vertex -331.092 31.617 26.9372 + vertex -342.042 34.1472 27.0966 + endloop + endfacet + facet normal -0.0347315 -0.213598 0.976304 + outer loop + vertex -322.916 30.2128 26.9209 + vertex -331.092 31.617 26.9372 + vertex -320.367 29.5547 26.8676 + endloop + endfacet + facet normal -0.0321542 -0.206334 0.977953 + outer loop + vertex -341.953 33.2322 26.9136 + vertex -359.773 35.9947 26.9106 + vertex -339.171 32.3211 26.8129 + endloop + endfacet + facet normal -0.0328819 -0.21103 0.976926 + outer loop + vertex -362.171 36.8731 27.0196 + vertex -359.773 35.9947 26.9106 + vertex -341.953 33.2322 26.9136 + endloop + endfacet + facet normal -0.026331 -0.19362 0.980723 + outer loop + vertex -362.171 36.8731 27.0196 + vertex -380.438 39.8907 27.1249 + vertex -359.773 35.9947 26.9106 + endloop + endfacet + facet normal -0.0418722 -0.274943 0.960548 + outer loop + vertex -380.438 39.8907 27.1249 + vertex -379.812 38.8484 26.8539 + vertex -359.773 35.9947 26.9106 + endloop + endfacet + facet normal -0.037255 -0.242343 0.969475 + outer loop + vertex -359.773 35.9947 26.9106 + vertex -379.812 38.8484 26.8539 + vertex -359.205 34.9827 26.6794 + endloop + endfacet + facet normal -0.0423987 -0.26943 0.962086 + outer loop + vertex -379.812 38.8484 26.8539 + vertex -379.91 37.2514 26.4023 + vertex -359.205 34.9827 26.6794 + endloop + endfacet + facet normal -0.0408065 -0.269539 0.962125 + outer loop + vertex -379.812 38.8484 26.8539 + vertex -400.989 41.4333 26.6799 + vertex -379.91 37.2514 26.4023 + endloop + endfacet + facet normal -0.0462516 -0.29644 0.953931 + outer loop + vertex -400.989 41.4333 26.6799 + vertex -400.884 39.081 25.954 + vertex -379.91 37.2514 26.4023 + endloop + endfacet + facet normal -0.0431369 -0.257975 0.965188 + outer loop + vertex -379.91 37.2514 26.4023 + vertex -400.884 39.081 25.954 + vertex -380.265 35.0326 25.7934 + endloop + endfacet + facet normal -0.0468728 -0.276789 0.959787 + outer loop + vertex -400.884 39.081 25.954 + vertex -401.094 36.2551 25.1287 + vertex -380.265 35.0326 25.7934 + endloop + endfacet + facet normal -0.0487477 -0.276635 0.959738 + outer loop + vertex -400.884 39.081 25.954 + vertex -422.304 40.6957 25.3314 + vertex -401.094 36.2551 25.1287 + endloop + endfacet + facet normal -0.0514286 -0.289263 0.955867 + outer loop + vertex -422.304 40.6957 25.3314 + vertex -422.662 37.4386 24.3265 + vertex -401.094 36.2551 25.1287 + endloop + endfacet + facet normal -0.0499779 -0.256459 0.965262 + outer loop + vertex -401.094 36.2551 25.1287 + vertex -422.662 37.4386 24.3265 + vertex -401.472 33.064 24.2613 + endloop + endfacet + facet normal -0.0492543 -0.252968 0.96622 + outer loop + vertex -422.662 37.4386 24.3265 + vertex -423.223 33.9479 23.384 + vertex -401.472 33.064 24.2613 + endloop + endfacet + facet normal -0.0533617 -0.252297 0.966178 + outer loop + vertex -422.662 37.4386 24.3265 + vertex -445.226 38.8599 23.4514 + vertex -423.223 33.9479 23.384 + endloop + endfacet + facet normal -0.0499275 -0.236969 0.970234 + outer loop + vertex -445.226 38.8599 23.4514 + vertex -445.558 35.077 22.5104 + vertex -423.223 33.9479 23.384 + endloop + endfacet + facet normal -0.0494228 -0.224712 0.973171 + outer loop + vertex -423.223 33.9479 23.384 + vertex -445.558 35.077 22.5104 + vertex -423.917 30.3283 22.5129 + endloop + endfacet + facet normal -0.046798 -0.212749 0.975986 + outer loop + vertex -445.558 35.077 22.5104 + vertex -445.992 31.2748 21.6608 + vertex -423.917 30.3283 22.5129 + endloop + endfacet + facet normal -0.0491105 -0.212473 0.975932 + outer loop + vertex -445.558 35.077 22.5104 + vertex -466.719 36.2552 21.702 + vertex -445.992 31.2748 21.6608 + endloop + endfacet + facet normal -0.0489674 -0.211879 0.976068 + outer loop + vertex -466.719 36.2552 21.702 + vertex -466.392 32.2489 20.8488 + vertex -445.992 31.2748 21.6608 + endloop + endfacet + facet normal -0.0490556 -0.214141 0.97557 + outer loop + vertex -445.992 31.2748 21.6608 + vertex -466.392 32.2489 20.8488 + vertex -446.025 27.3009 20.7868 + endloop + endfacet + facet normal -0.0543524 -0.235877 0.970262 + outer loop + vertex -466.392 32.2489 20.8488 + vertex -466.342 27.9888 19.8159 + vertex -446.025 27.3009 20.7868 + endloop + endfacet + facet normal -0.0547162 -0.235876 0.970242 + outer loop + vertex -466.392 32.2489 20.8488 + vertex -484.473 33.3427 20.095 + vertex -466.342 27.9888 19.8159 + endloop + endfacet + facet normal -0.0634807 -0.265135 0.962119 + outer loop + vertex -484.473 33.3427 20.095 + vertex -486.535 28.6287 18.6599 + vertex -466.342 27.9888 19.8159 + endloop + endfacet + facet normal -0.0636294 -0.274702 0.959422 + outer loop + vertex -466.342 27.9888 19.8159 + vertex -486.535 28.6287 18.6599 + vertex -464.105 22.904 18.5084 + endloop + endfacet + facet normal -0.0627643 -0.274361 0.959576 + outer loop + vertex -466.342 27.9888 19.8159 + vertex -464.105 22.904 18.5084 + vertex -444.863 22.8633 19.7553 + endloop + endfacet + facet normal -0.0615734 -0.265939 0.962021 + outer loop + vertex -486.535 28.6287 18.6599 + vertex -484.473 33.3427 20.095 + vertex -498.64 34.1177 19.4026 + endloop + endfacet + facet normal -0.0694727 -0.28264 0.956707 + outer loop + vertex -498.64 34.1177 19.4026 + vertex -501.423 30.7835 18.2155 + vertex -486.535 28.6287 18.6599 + endloop + endfacet + facet normal -0.0702466 -0.282037 0.956828 + outer loop + vertex -498.64 34.1177 19.4026 + vertex -506.714 33.1492 18.5243 + vertex -501.423 30.7835 18.2155 + endloop + endfacet + facet normal -0.0724019 -0.267661 0.960789 + outer loop + vertex -505.776 37.9755 19.9395 + vertex -506.714 33.1492 18.5243 + vertex -498.64 34.1177 19.4026 + endloop + endfacet + facet normal -0.0571186 -0.240528 0.96896 + outer loop + vertex -496.808 38.8171 20.677 + vertex -505.776 37.9755 19.9395 + vertex -498.64 34.1177 19.4026 + endloop + endfacet + facet normal -0.0582182 -0.23082 0.971253 + outer loop + vertex -505.518 42.0217 20.9166 + vertex -505.776 37.9755 19.9395 + vertex -496.808 38.8171 20.677 + endloop + endfacet + facet normal -0.052474 -0.215496 0.975094 + outer loop + vertex -501.029 43.6099 21.5091 + vertex -505.518 42.0217 20.9166 + vertex -496.808 38.8171 20.677 + endloop + endfacet + facet normal -0.0522359 -0.215296 0.975151 + outer loop + vertex -501.029 43.6099 21.5091 + vertex -496.808 38.8171 20.677 + vertex -486.993 41.534 21.8026 + endloop + endfacet + facet normal -0.0530505 -0.220989 0.973832 + outer loop + vertex -499.759 47.8612 22.543 + vertex -501.029 43.6099 21.5091 + vertex -486.993 41.534 21.8026 + endloop + endfacet + facet normal -0.0547611 -0.22434 0.972971 + outer loop + vertex -486.993 41.534 21.8026 + vertex -484.383 45.4707 22.8573 + vertex -499.759 47.8612 22.543 + endloop + endfacet + facet normal -0.052421 -0.225833 0.972755 + outer loop + vertex -484.383 45.4707 22.8573 + vertex -486.993 41.534 21.8026 + vertex -466.943 40.3171 22.6007 + endloop + endfacet + facet normal -0.0621247 -0.258239 0.964082 + outer loop + vertex -468.298 44.5795 23.655 + vertex -484.383 45.4707 22.8573 + vertex -466.943 40.3171 22.6007 + endloop + endfacet + facet normal -0.0549983 -0.256213 0.965054 + outer loop + vertex -468.298 44.5795 23.655 + vertex -466.943 40.3171 22.6007 + vertex -445.226 38.8599 23.4514 + endloop + endfacet + facet normal -0.0620643 -0.284419 0.956689 + outer loop + vertex -444.863 42.4839 24.5524 + vertex -468.298 44.5795 23.655 + vertex -445.226 38.8599 23.4514 + endloop + endfacet + facet normal -0.0664897 -0.342224 0.937263 + outer loop + vertex -467.684 48.2303 25.0317 + vertex -468.298 44.5795 23.655 + vertex -444.863 42.4839 24.5524 + endloop + endfacet + facet normal -0.0675702 -0.346382 0.935657 + outer loop + vertex -444.252 45.7506 25.8058 + vertex -467.684 48.2303 25.0317 + vertex -444.863 42.4839 24.5524 + endloop + endfacet + facet normal -0.0598812 -0.347816 0.935649 + outer loop + vertex -444.252 45.7506 25.8058 + vertex -444.863 42.4839 24.5524 + vertex -422.304 40.6957 25.3314 + endloop + endfacet + facet normal -0.0547046 -0.3261 0.943751 + outer loop + vertex -422.483 43.6697 26.3486 + vertex -444.252 45.7506 25.8058 + vertex -422.304 40.6957 25.3314 + endloop + endfacet + facet normal -0.080045 -0.339867 0.937061 + outer loop + vertex -468.298 44.5795 23.655 + vertex -467.684 48.2303 25.0317 + vertex -482.609 49.1371 24.0856 + endloop + endfacet + facet normal -0.0750774 -0.324809 0.942795 + outer loop + vertex -483.234 47.4471 23.4536 + vertex -468.298 44.5795 23.655 + vertex -482.609 49.1371 24.0856 + endloop + endfacet + facet normal -0.0734127 -0.325398 0.942723 + outer loop + vertex -482.609 49.1371 24.0856 + vertex -493.532 49.8438 23.4789 + vertex -483.234 47.4471 23.4536 + endloop + endfacet + facet normal -0.0738263 -0.334583 0.93947 + outer loop + vertex -492.781 52.0239 24.3143 + vertex -493.532 49.8438 23.4789 + vertex -482.609 49.1371 24.0856 + endloop + endfacet + facet normal -0.080249 -0.332457 0.939698 + outer loop + vertex -493.532 49.8438 23.4789 + vertex -492.781 52.0239 24.3143 + vertex -501.071 53.3366 24.0708 + endloop + endfacet + facet normal -0.0764994 -0.324866 0.942661 + outer loop + vertex -501.071 53.3366 24.0708 + vertex -501.425 51.2597 23.3263 + vertex -493.532 49.8438 23.4789 + endloop + endfacet + facet normal -0.0828563 -0.323731 0.942514 + outer loop + vertex -501.071 53.3366 24.0708 + vertex -504.914 52.1933 23.3403 + vertex -501.425 51.2597 23.3263 + endloop + endfacet + facet normal -0.0832827 -0.322536 0.942886 + outer loop + vertex -505.89 54.8194 24.1524 + vertex -504.914 52.1933 23.3403 + vertex -501.071 53.3366 24.0708 + endloop + endfacet + facet normal -0.122902 -0.334601 0.934311 + outer loop + vertex -505.89 54.8194 24.1524 + vertex -506.816 53.3584 23.5074 + vertex -504.914 52.1933 23.3403 + endloop + endfacet + facet normal -0.101484 -0.347271 0.932257 + outer loop + vertex -506.726 55.5448 24.3316 + vertex -506.816 53.3584 23.5074 + vertex -505.89 54.8194 24.1524 + endloop + endfacet + facet normal -0.171615 0.35363 -0.919508 + outer loop + vertex -506.726 55.5448 24.3316 + vertex -506.523 54.3103 23.8188 + vertex -506.816 53.3584 23.5074 + endloop + endfacet + facet normal 0.13536 0.399008 -0.906901 + outer loop + vertex -506.076 56.0029 24.6302 + vertex -506.523 54.3103 23.8188 + vertex -506.726 55.5448 24.3316 + endloop + endfacet + facet normal -0.0619927 -0.255101 0.964925 + outer loop + vertex -483.234 47.4471 23.4536 + vertex -484.383 45.4707 22.8573 + vertex -468.298 44.5795 23.655 + endloop + endfacet + facet normal -0.0575697 -0.257557 0.964547 + outer loop + vertex -483.234 47.4471 23.4536 + vertex -493.532 49.8438 23.4789 + vertex -484.383 45.4707 22.8573 + endloop + endfacet + facet normal -0.0606868 -0.263811 0.962663 + outer loop + vertex -484.383 45.4707 22.8573 + vertex -493.532 49.8438 23.4789 + vertex -499.759 47.8612 22.543 + endloop + endfacet + facet normal -0.0642045 -0.253911 0.965094 + outer loop + vertex -501.425 51.2597 23.3263 + vertex -499.759 47.8612 22.543 + vertex -493.532 49.8438 23.4789 + endloop + endfacet + facet normal -0.0640674 -0.25385 0.965119 + outer loop + vertex -501.425 51.2597 23.3263 + vertex -504.914 52.1933 23.3403 + vertex -499.759 47.8612 22.543 + endloop + endfacet + facet normal -0.0721414 -0.262906 0.962121 + outer loop + vertex -506.416 50.0813 22.6506 + vertex -499.759 47.8612 22.543 + vertex -504.914 52.1933 23.3403 + endloop + endfacet + facet normal -0.0752237 -0.260823 0.962451 + outer loop + vertex -506.816 53.3584 23.5074 + vertex -506.416 50.0813 22.6506 + vertex -504.914 52.1933 23.3403 + endloop + endfacet + facet normal -0.0520405 -0.218445 0.974461 + outer loop + vertex -466.943 40.3171 22.6007 + vertex -486.993 41.534 21.8026 + vertex -466.719 36.2552 21.702 + endloop + endfacet + facet normal -0.0498097 -0.209914 0.97645 + outer loop + vertex -486.993 41.534 21.8026 + vertex -482.027 36.6778 21.012 + vertex -466.719 36.2552 21.702 + endloop + endfacet + facet normal -0.0579363 -0.219542 0.973881 + outer loop + vertex -499.759 47.8612 22.543 + vertex -506.328 45.8493 21.6987 + vertex -501.029 43.6099 21.5091 + endloop + endfacet + facet normal -0.057714 -0.22021 0.973744 + outer loop + vertex -506.416 50.0813 22.6506 + vertex -506.328 45.8493 21.6987 + vertex -499.759 47.8612 22.543 + endloop + endfacet + facet normal -0.069025 -0.220276 0.972992 + outer loop + vertex -506.328 45.8493 21.6987 + vertex -506.416 50.0813 22.6506 + vertex -508.767 47.7226 21.9498 + endloop + endfacet + facet normal -0.0625828 -0.212185 0.975224 + outer loop + vertex -508.767 47.7226 21.9498 + vertex -509.268 41.9962 20.6717 + vertex -506.328 45.8493 21.6987 + endloop + endfacet + facet normal -0.0622303 -0.212445 0.97519 + outer loop + vertex -505.518 42.0217 20.9166 + vertex -506.328 45.8493 21.6987 + vertex -509.268 41.9962 20.6717 + endloop + endfacet + facet normal -0.0536002 -0.213048 0.97557 + outer loop + vertex -509.268 41.9962 20.6717 + vertex -508.767 47.7226 21.9498 + vertex -512.826 44.2271 20.9634 + endloop + endfacet + facet normal -0.0607215 -0.224027 0.972689 + outer loop + vertex -512.826 44.2271 20.9634 + vertex -512.755 39.125 19.7927 + vertex -509.268 41.9962 20.6717 + endloop + endfacet + facet normal -0.0558294 -0.224027 0.972983 + outer loop + vertex -512.826 44.2271 20.9634 + vertex -518.687 41.5105 20.0016 + vertex -512.755 39.125 19.7927 + endloop + endfacet + facet normal -0.0672678 -0.251812 0.965435 + outer loop + vertex -518.687 41.5105 20.0016 + vertex -517.403 36.6413 18.8211 + vertex -512.755 39.125 19.7927 + endloop + endfacet + facet normal -0.0640875 -0.257284 0.964208 + outer loop + vertex -512.755 39.125 19.7927 + vertex -517.403 36.6413 18.8211 + vertex -511.777 34.6922 18.6749 + endloop + endfacet + facet normal -0.0580267 -0.256122 0.964901 + outer loop + vertex -512.755 39.125 19.7927 + vertex -511.777 34.6922 18.6749 + vertex -509.363 35.8267 19.1212 + endloop + endfacet + facet normal -0.0656209 -0.25143 0.965649 + outer loop + vertex -518.687 41.5105 20.0016 + vertex -526.84 39.2784 18.8664 + vertex -517.403 36.6413 18.8211 + endloop + endfacet + facet normal -0.0663936 -0.248912 0.966248 + outer loop + vertex -527.824 44.1069 20.0426 + vertex -526.84 39.2784 18.8664 + vertex -518.687 41.5105 20.0016 + endloop + endfacet + facet normal -0.057435 -0.217515 0.974366 + outer loop + vertex -518.983 46.3126 21.0562 + vertex -527.824 44.1069 20.0426 + vertex -518.687 41.5105 20.0016 + endloop + endfacet + facet normal -0.0584991 -0.213617 0.975164 + outer loop + vertex -528.576 48.8813 21.0434 + vertex -527.824 44.1069 20.0426 + vertex -518.983 46.3126 21.0562 + endloop + endfacet + facet normal -0.0557273 -0.203253 0.977539 + outer loop + vertex -518.822 50.9633 22.0323 + vertex -528.576 48.8813 21.0434 + vertex -518.983 46.3126 21.0562 + endloop + endfacet + facet normal -0.0560393 -0.203239 0.977524 + outer loop + vertex -518.822 50.9633 22.0323 + vertex -518.983 46.3126 21.0562 + vertex -511.682 48.9306 22.0191 + endloop + endfacet + facet normal -0.0615471 -0.222557 0.972975 + outer loop + vertex -518.822 50.9633 22.0323 + vertex -511.682 48.9306 22.0191 + vertex -511.383 52.0048 22.7411 + endloop + endfacet + facet normal -0.0607056 -0.227781 0.971818 + outer loop + vertex -515.012 53.3826 22.8374 + vertex -518.822 50.9633 22.0323 + vertex -511.383 52.0048 22.7411 + endloop + endfacet + facet normal -0.0646484 -0.221936 0.972916 + outer loop + vertex -515.012 53.3826 22.8374 + vertex -520.752 54.3589 22.6787 + vertex -518.822 50.9633 22.0323 + endloop + endfacet + facet normal -0.0627768 -0.220939 0.973265 + outer loop + vertex -529.522 53.6707 21.9567 + vertex -518.822 50.9633 22.0323 + vertex -520.752 54.3589 22.6787 + endloop + endfacet + facet normal -0.0630562 -0.218044 0.9739 + outer loop + vertex -526.094 56.0794 22.718 + vertex -529.522 53.6707 21.9567 + vertex -520.752 54.3589 22.6787 + endloop + endfacet + facet normal -0.0643223 -0.216336 0.974198 + outer loop + vertex -526.094 56.0794 22.718 + vertex -532.461 57.3006 22.5688 + vertex -529.522 53.6707 21.9567 + endloop + endfacet + facet normal -0.0617715 -0.214372 0.974797 + outer loop + vertex -541.348 56.7362 21.8815 + vertex -529.522 53.6707 21.9567 + vertex -532.461 57.3006 22.5688 + endloop + endfacet + facet normal -0.0619407 -0.212258 0.975249 + outer loop + vertex -537.962 59.1698 22.6263 + vertex -541.348 56.7362 21.8815 + vertex -532.461 57.3006 22.5688 + endloop + endfacet + facet normal -0.0636925 -0.209939 0.975638 + outer loop + vertex -537.962 59.1698 22.6263 + vertex -544.225 60.4336 22.4893 + vertex -541.348 56.7362 21.8815 + endloop + endfacet + facet normal -0.0619063 -0.208615 0.976037 + outer loop + vertex -553.179 59.898 21.8069 + vertex -541.348 56.7362 21.8815 + vertex -544.225 60.4336 22.4893 + endloop + endfacet + facet normal -0.0623565 -0.202652 0.977263 + outer loop + vertex -549.594 62.3064 22.5351 + vertex -553.179 59.898 21.8069 + vertex -544.225 60.4336 22.4893 + endloop + endfacet + facet normal -0.0640015 -0.200317 0.977638 + outer loop + vertex -549.594 62.3064 22.5351 + vertex -555.861 63.5793 22.3856 + vertex -553.179 59.898 21.8069 + endloop + endfacet + facet normal -0.0610683 -0.198275 0.978242 + outer loop + vertex -564.956 63.1083 21.7224 + vertex -553.179 59.898 21.8069 + vertex -555.861 63.5793 22.3856 + endloop + endfacet + facet normal -0.0614429 -0.192604 0.979351 + outer loop + vertex -561.241 65.4677 22.4195 + vertex -564.956 63.1083 21.7224 + vertex -555.861 63.5793 22.3856 + endloop + endfacet + facet normal -0.0634461 -0.189586 0.979812 + outer loop + vertex -561.241 65.4677 22.4195 + vertex -567.586 66.7889 22.2643 + vertex -564.956 63.1083 21.7224 + endloop + endfacet + facet normal -0.0594946 -0.186875 0.98058 + outer loop + vertex -576.595 66.3876 21.6412 + vertex -564.956 63.1083 21.7224 + vertex -567.586 66.7889 22.2643 + endloop + endfacet + facet normal -0.0598424 -0.180802 0.981697 + outer loop + vertex -573.013 68.7157 22.2883 + vertex -576.595 66.3876 21.6412 + vertex -567.586 66.7889 22.2643 + endloop + endfacet + facet normal -0.0610138 -0.179068 0.981943 + outer loop + vertex -573.013 68.7157 22.2883 + vertex -579.285 70.0782 22.1471 + vertex -576.595 66.3876 21.6412 + endloop + endfacet + facet normal -0.0584499 -0.177266 0.982426 + outer loop + vertex -587.464 69.6733 21.5874 + vertex -576.595 66.3876 21.6412 + vertex -579.285 70.0782 22.1471 + endloop + endfacet + facet normal -0.0587951 -0.171644 0.983403 + outer loop + vertex -584.57 72.0343 22.1725 + vertex -587.464 69.6733 21.5874 + vertex -579.285 70.0782 22.1471 + endloop + endfacet + facet normal -0.060484 -0.169635 0.983649 + outer loop + vertex -584.57 72.0343 22.1725 + vertex -590.149 73.3562 22.0574 + vertex -587.464 69.6733 21.5874 + endloop + endfacet + facet normal -0.0578173 -0.167752 0.984132 + outer loop + vertex -595.538 72.6663 21.6232 + vertex -587.464 69.6733 21.5874 + vertex -590.149 73.3562 22.0574 + endloop + endfacet + facet normal -0.0580232 -0.166292 0.984368 + outer loop + vertex -594.776 75.145 22.0869 + vertex -595.538 72.6663 21.6232 + vertex -590.149 73.3562 22.0574 + endloop + endfacet + facet normal -0.0572428 -0.166533 0.984373 + outer loop + vertex -594.776 75.145 22.0869 + vertex -598.956 75.8347 21.9605 + vertex -595.538 72.6663 21.6232 + endloop + endfacet + facet normal -0.0502303 -0.159138 0.985978 + outer loop + vertex -598.956 75.8347 21.9605 + vertex -601.673 73.3189 21.416 + vertex -595.538 72.6663 21.6232 + endloop + endfacet + facet normal -0.0498009 -0.154879 0.986677 + outer loop + vertex -596.173 68.0586 20.8679 + vertex -595.538 72.6663 21.6232 + vertex -601.673 73.3189 21.416 + endloop + endfacet + facet normal -0.0480085 -0.153044 0.987053 + outer loop + vertex -601.673 73.3189 21.416 + vertex -602.204 68.5415 20.6494 + vertex -596.173 68.0586 20.8679 + endloop + endfacet + facet normal -0.0506124 -0.188404 0.980787 + outer loop + vertex -602.204 68.5415 20.6494 + vertex -600.917 63.7814 19.8015 + vertex -596.173 68.0586 20.8679 + endloop + endfacet + facet normal -0.0604549 -0.177839 0.982201 + outer loop + vertex -593.799 63.1597 20.127 + vertex -596.173 68.0586 20.8679 + vertex -600.917 63.7814 19.8015 + endloop + endfacet + facet normal -0.0569337 -0.176209 0.982705 + outer loop + vertex -596.173 68.0586 20.8679 + vertex -593.799 63.1597 20.127 + vertex -586.479 64.8313 20.8508 + endloop + endfacet + facet normal -0.0516832 -0.160454 0.985689 + outer loop + vertex -587.464 69.6733 21.5874 + vertex -596.173 68.0586 20.8679 + vertex -586.479 64.8313 20.8508 + endloop + endfacet + facet normal -0.0541942 -0.187375 0.980792 + outer loop + vertex -586.479 64.8313 20.8508 + vertex -593.799 63.1597 20.127 + vertex -585.848 60.0562 19.9734 + endloop + endfacet + facet normal -0.0576956 -0.187787 0.980514 + outer loop + vertex -586.479 64.8313 20.8508 + vertex -585.848 60.0562 19.9734 + vertex -575.724 61.5309 20.8516 + endloop + endfacet + facet normal -0.0520342 -0.169338 0.984184 + outer loop + vertex -576.595 66.3876 21.6412 + vertex -586.479 64.8313 20.8508 + vertex -575.724 61.5309 20.8516 + endloop + endfacet + facet normal -0.0565705 -0.194742 0.979222 + outer loop + vertex -575.724 61.5309 20.8516 + vertex -585.848 60.0562 19.9734 + vertex -574.819 56.6904 19.9412 + endloop + endfacet + facet normal -0.0580876 -0.194999 0.979082 + outer loop + vertex -575.724 61.5309 20.8516 + vertex -574.819 56.6904 19.9412 + vertex -564.052 58.2345 20.8876 + endloop + endfacet + facet normal -0.0533538 -0.178199 0.982547 + outer loop + vertex -564.956 63.1083 21.7224 + vertex -575.724 61.5309 20.8516 + vertex -564.052 58.2345 20.8876 + endloop + endfacet + facet normal -0.0572194 -0.200414 0.978039 + outer loop + vertex -564.052 58.2345 20.8876 + vertex -574.819 56.6904 19.9412 + vertex -563.029 53.3915 19.955 + endloop + endfacet + facet normal -0.0583895 -0.200639 0.977924 + outer loop + vertex -564.052 58.2345 20.8876 + vertex -563.029 53.3915 19.955 + vertex -552.127 55.0061 20.9372 + endloop + endfacet + facet normal -0.0544733 -0.186127 0.981015 + outer loop + vertex -553.179 59.898 21.8069 + vertex -564.052 58.2345 20.8876 + vertex -552.127 55.0061 20.9372 + endloop + endfacet + facet normal -0.0575802 -0.205516 0.976958 + outer loop + vertex -552.127 55.0061 20.9372 + vertex -563.029 53.3915 19.955 + vertex -551.056 50.1746 19.9839 + endloop + endfacet + facet normal -0.0584374 -0.205689 0.976871 + outer loop + vertex -552.127 55.0061 20.9372 + vertex -551.056 50.1746 19.9839 + vertex -540.123 51.852 20.9912 + endloop + endfacet + facet normal -0.054956 -0.19239 0.979778 + outer loop + vertex -541.348 56.7362 21.8815 + vertex -552.127 55.0061 20.9372 + vertex -540.123 51.852 20.9912 + endloop + endfacet + facet normal -0.0577649 -0.209597 0.97608 + outer loop + vertex -540.123 51.852 20.9912 + vertex -551.056 50.1746 19.9839 + vertex -539.085 47.0426 20.0199 + endloop + endfacet + facet normal -0.0583672 -0.209715 0.976019 + outer loop + vertex -540.123 51.852 20.9912 + vertex -539.085 47.0426 20.0199 + vertex -528.576 48.8813 21.0434 + endloop + endfacet + facet normal -0.0552541 -0.197567 0.978731 + outer loop + vertex -529.522 53.6707 21.9567 + vertex -540.123 51.852 20.9912 + vertex -528.576 48.8813 21.0434 + endloop + endfacet + facet normal -0.0664094 -0.242734 0.967817 + outer loop + vertex -551.056 50.1746 19.9839 + vertex -550.111 45.3817 18.8467 + vertex -539.085 47.0426 20.0199 + endloop + endfacet + facet normal -0.0659003 -0.245623 0.967123 + outer loop + vertex -539.085 47.0426 20.0199 + vertex -550.111 45.3817 18.8467 + vertex -538.181 42.2482 18.8638 + endloop + endfacet + facet normal -0.065993 -0.245638 0.967113 + outer loop + vertex -539.085 47.0426 20.0199 + vertex -538.181 42.2482 18.8638 + vertex -527.824 44.1069 20.0426 + endloop + endfacet + facet normal -0.0668425 -0.242808 0.967769 + outer loop + vertex -551.056 50.1746 19.9839 + vertex -561.985 48.5801 18.8291 + vertex -550.111 45.3817 18.8467 + endloop + endfacet + facet normal -0.067129 -0.241133 0.968168 + outer loop + vertex -563.029 53.3915 19.955 + vertex -561.985 48.5801 18.8291 + vertex -551.056 50.1746 19.9839 + endloop + endfacet + facet normal -0.0673352 -0.241172 0.968144 + outer loop + vertex -563.029 53.3915 19.955 + vertex -573.725 51.8298 18.822 + vertex -561.985 48.5801 18.8291 + endloop + endfacet + facet normal -0.0678195 -0.238339 0.968811 + outer loop + vertex -574.819 56.6904 19.9412 + vertex -573.725 51.8298 18.822 + vertex -563.029 53.3915 19.955 + endloop + endfacet + facet normal -0.0676235 -0.2383 0.968834 + outer loop + vertex -574.819 56.6904 19.9412 + vertex -585.31 55.2074 18.8442 + vertex -573.725 51.8298 18.822 + endloop + endfacet + facet normal -0.0684209 -0.233484 0.96995 + outer loop + vertex -585.848 60.0562 19.9734 + vertex -585.31 55.2074 18.8442 + vertex -574.819 56.6904 19.9412 + endloop + endfacet + facet normal -0.0679751 -0.233444 0.969991 + outer loop + vertex -585.848 60.0562 19.9734 + vertex -596.137 58.7895 18.9476 + vertex -585.31 55.2074 18.8442 + endloop + endfacet + facet normal -0.0691638 -0.225283 0.971835 + outer loop + vertex -593.799 63.1597 20.127 + vertex -596.137 58.7895 18.9476 + vertex -585.848 60.0562 19.9734 + endloop + endfacet + facet normal -0.0643331 -0.227799 0.971581 + outer loop + vertex -596.137 58.7895 18.9476 + vertex -593.799 63.1597 20.127 + vertex -600.917 63.7814 19.8015 + endloop + endfacet + facet normal -0.0732146 -0.235866 0.969024 + outer loop + vertex -600.917 63.7814 19.8015 + vertex -603.359 59.6148 18.6028 + vertex -596.137 58.7895 18.9476 + endloop + endfacet + facet normal -0.0605291 -0.243041 0.968126 + outer loop + vertex -600.917 63.7814 19.8015 + vertex -605.376 61.5303 18.9576 + vertex -603.359 59.6148 18.6028 + endloop + endfacet + facet normal -0.0705689 -0.22457 0.971899 + outer loop + vertex -604.748 66.3269 20.1115 + vertex -605.376 61.5303 18.9576 + vertex -600.917 63.7814 19.8015 + endloop + endfacet + facet normal -0.0406199 -0.228675 0.972655 + outer loop + vertex -605.376 61.5303 18.9576 + vertex -604.748 66.3269 20.1115 + vertex -607.214 64.2598 19.5225 + endloop + endfacet + facet normal -0.0447897 -0.18693 0.981352 + outer loop + vertex -602.204 68.5415 20.6494 + vertex -604.748 66.3269 20.1115 + vertex -600.917 63.7814 19.8015 + endloop + endfacet + facet normal -0.0583286 -0.171876 0.98339 + outer loop + vertex -604.614 71.0596 20.9466 + vertex -604.748 66.3269 20.1115 + vertex -602.204 68.5415 20.6494 + endloop + endfacet + facet normal -0.039225 -0.154058 0.987283 + outer loop + vertex -601.673 73.3189 21.416 + vertex -604.614 71.0596 20.9466 + vertex -602.204 68.5415 20.6494 + endloop + endfacet + facet normal -0.045609 -0.145947 0.98824 + outer loop + vertex -604.579 75.2813 21.5717 + vertex -604.614 71.0596 20.9466 + vertex -601.673 73.3189 21.416 + endloop + endfacet + facet normal -0.0488639 -0.150698 0.987371 + outer loop + vertex -604.579 75.2813 21.5717 + vertex -601.673 73.3189 21.416 + vertex -603.886 77.2982 21.9139 + endloop + endfacet + facet normal -0.0455656 -0.151829 0.987356 + outer loop + vertex -604.683 78.0935 21.9994 + vertex -604.579 75.2813 21.5717 + vertex -603.886 77.2982 21.9139 + endloop + endfacet + facet normal 0.0500979 -0.148344 0.987666 + outer loop + vertex -604.683 78.0935 21.9994 + vertex -604.883 77.6955 21.9498 + vertex -604.579 75.2813 21.5717 + endloop + endfacet + facet normal -0.025571 -0.157796 0.987141 + outer loop + vertex -604.883 77.6955 21.9498 + vertex -606.422 74.18 21.3479 + vertex -604.579 75.2813 21.5717 + endloop + endfacet + facet normal -0.0578058 -0.155516 0.986141 + outer loop + vertex -602.142 77.0613 21.9787 + vertex -603.886 77.2982 21.9139 + vertex -601.673 73.3189 21.416 + endloop + endfacet + facet normal -0.032738 -0.146125 0.988724 + outer loop + vertex -604.614 71.0596 20.9466 + vertex -604.579 75.2813 21.5717 + vertex -606.422 74.18 21.3479 + endloop + endfacet + facet normal -0.054068 -0.15509 0.98642 + outer loop + vertex -598.956 75.8347 21.9605 + vertex -602.142 77.0613 21.9787 + vertex -601.673 73.3189 21.416 + endloop + endfacet + facet normal -0.0528721 -0.154441 0.986586 + outer loop + vertex -595.538 72.6663 21.6232 + vertex -596.173 68.0586 20.8679 + vertex -587.464 69.6733 21.5874 + endloop + endfacet + facet normal -0.053487 -0.160798 0.985537 + outer loop + vertex -587.464 69.6733 21.5874 + vertex -586.479 64.8313 20.8508 + vertex -576.595 66.3876 21.6412 + endloop + endfacet + facet normal -0.0547015 -0.16978 0.983963 + outer loop + vertex -576.595 66.3876 21.6412 + vertex -575.724 61.5309 20.8516 + vertex -564.956 63.1083 21.7224 + endloop + endfacet + facet normal -0.0557361 -0.178605 0.982341 + outer loop + vertex -564.956 63.1083 21.7224 + vertex -564.052 58.2345 20.8876 + vertex -553.179 59.898 21.8069 + endloop + endfacet + facet normal -0.0560082 -0.186431 0.98087 + outer loop + vertex -553.179 59.898 21.8069 + vertex -552.127 55.0061 20.9372 + vertex -541.348 56.7362 21.8815 + endloop + endfacet + facet normal -0.0561775 -0.192674 0.979653 + outer loop + vertex -541.348 56.7362 21.8815 + vertex -540.123 51.852 20.9912 + vertex -529.522 53.6707 21.9567 + endloop + endfacet + facet normal -0.0569652 -0.223042 0.973143 + outer loop + vertex -508.251 51.4378 22.7946 + vertex -511.383 52.0048 22.7411 + vertex -511.682 48.9306 22.0191 + endloop + endfacet + facet normal -0.0543672 -0.226403 0.972515 + outer loop + vertex -507.809 50.501 22.6012 + vertex -508.251 51.4378 22.7946 + vertex -511.682 48.9306 22.0191 + endloop + endfacet + facet normal -0.0626941 -0.207261 0.976275 + outer loop + vertex -508.767 47.7226 21.9498 + vertex -507.809 50.501 22.6012 + vertex -511.682 48.9306 22.0191 + endloop + endfacet + facet normal -0.0550203 -0.205898 0.977026 + outer loop + vertex -511.682 48.9306 22.0191 + vertex -518.983 46.3126 21.0562 + vertex -512.826 44.2271 20.9634 + endloop + endfacet + facet normal -0.0569794 -0.197877 0.978569 + outer loop + vertex -529.522 53.6707 21.9567 + vertex -528.576 48.8813 21.0434 + vertex -518.822 50.9633 22.0323 + endloop + endfacet + facet normal -0.05763 -0.213496 0.975243 + outer loop + vertex -528.576 48.8813 21.0434 + vertex -539.085 47.0426 20.0199 + vertex -527.824 44.1069 20.0426 + endloop + endfacet + facet normal -0.0653533 -0.248729 0.966366 + outer loop + vertex -527.824 44.1069 20.0426 + vertex -538.181 42.2482 18.8638 + vertex -526.84 39.2784 18.8664 + endloop + endfacet + facet normal -0.0590218 -0.217588 0.974254 + outer loop + vertex -518.983 46.3126 21.0562 + vertex -518.687 41.5105 20.0016 + vertex -512.826 44.2271 20.9634 + endloop + endfacet + facet normal -0.0614586 -0.20432 0.976973 + outer loop + vertex -511.682 48.9306 22.0191 + vertex -512.826 44.2271 20.9634 + vertex -508.767 47.7226 21.9498 + endloop + endfacet + facet normal -0.0529329 -0.212974 0.975623 + outer loop + vertex -482.027 36.6778 21.012 + vertex -486.993 41.534 21.8026 + vertex -496.808 38.8171 20.677 + endloop + endfacet + facet normal -0.0548996 -0.227078 0.972328 + outer loop + vertex -484.473 33.3427 20.095 + vertex -482.027 36.6778 21.012 + vertex -496.808 38.8171 20.677 + endloop + endfacet + facet normal -0.0542144 -0.210914 0.976 + outer loop + vertex -506.328 45.8493 21.6987 + vertex -505.518 42.0217 20.9166 + vertex -501.029 43.6099 21.5091 + endloop + endfacet + facet normal -0.0618399 -0.23055 0.971093 + outer loop + vertex -505.776 37.9755 19.9395 + vertex -505.518 42.0217 20.9166 + vertex -509.268 41.9962 20.6717 + endloop + endfacet + facet normal -0.0604582 -0.239257 0.969072 + outer loop + vertex -496.808 38.8171 20.677 + vertex -498.64 34.1177 19.4026 + vertex -484.473 33.3427 20.095 + endloop + endfacet + facet normal -0.054294 -0.227504 0.972262 + outer loop + vertex -482.027 36.6778 21.012 + vertex -484.473 33.3427 20.095 + vertex -466.392 32.2489 20.8488 + endloop + endfacet + facet normal -0.0498458 -0.211938 0.976011 + outer loop + vertex -466.719 36.2552 21.702 + vertex -482.027 36.6778 21.012 + vertex -466.392 32.2489 20.8488 + endloop + endfacet + facet normal -0.0493869 -0.218334 0.974624 + outer loop + vertex -466.943 40.3171 22.6007 + vertex -466.719 36.2552 21.702 + vertex -445.558 35.077 22.5104 + endloop + endfacet + facet normal -0.0538799 -0.236593 0.970114 + outer loop + vertex -445.226 38.8599 23.4514 + vertex -466.943 40.3171 22.6007 + vertex -445.558 35.077 22.5104 + endloop + endfacet + facet normal -0.0550729 -0.285181 0.95689 + outer loop + vertex -444.863 42.4839 24.5524 + vertex -445.226 38.8599 23.4514 + vertex -422.662 37.4386 24.3265 + endloop + endfacet + facet normal -0.0558937 -0.288743 0.955774 + outer loop + vertex -422.304 40.6957 25.3314 + vertex -444.863 42.4839 24.5524 + vertex -422.662 37.4386 24.3265 + endloop + endfacet + facet normal -0.0520098 -0.326001 0.943938 + outer loop + vertex -422.483 43.6697 26.3486 + vertex -422.304 40.6957 25.3314 + vertex -400.884 39.081 25.954 + endloop + endfacet + facet normal -0.0455421 -0.296421 0.953971 + outer loop + vertex -400.989 41.4333 26.6799 + vertex -422.483 43.6697 26.3486 + vertex -400.884 39.081 25.954 + endloop + endfacet + facet normal -0.0459477 -0.312555 0.948788 + outer loop + vertex -401.156 43.1257 27.2293 + vertex -400.989 41.4333 26.6799 + vertex -379.812 38.8484 26.8539 + endloop + endfacet + facet normal -0.0426063 -0.312302 0.949027 + outer loop + vertex -401.156 43.1257 27.2293 + vertex -423.66 46.3141 27.2682 + vertex -400.989 41.4333 26.6799 + endloop + endfacet + facet normal -0.0506397 -0.34806 0.936104 + outer loop + vertex -423.66 46.3141 27.2682 + vertex -422.483 43.6697 26.3486 + vertex -400.989 41.4333 26.6799 + endloop + endfacet + facet normal -0.0480104 -0.347066 0.936611 + outer loop + vertex -423.66 46.3141 27.2682 + vertex -444.945 48.9213 27.1433 + vertex -422.483 43.6697 26.3486 + endloop + endfacet + facet normal -0.0609718 -0.399208 0.914831 + outer loop + vertex -444.945 48.9213 27.1433 + vertex -444.252 45.7506 25.8058 + vertex -422.483 43.6697 26.3486 + endloop + endfacet + facet normal -0.0651604 -0.399878 0.914249 + outer loop + vertex -444.945 48.9213 27.1433 + vertex -464.73 50.9506 26.6207 + vertex -444.252 45.7506 25.8058 + endloop + endfacet + facet normal -0.076128 -0.440014 0.894758 + outer loop + vertex -464.73 50.9506 26.6207 + vertex -467.684 48.2303 25.0317 + vertex -444.252 45.7506 25.8058 + endloop + endfacet + facet normal -0.0853891 -0.431803 0.897917 + outer loop + vertex -467.684 48.2303 25.0317 + vertex -464.73 50.9506 26.6207 + vertex -482.146 52.9277 25.9153 + endloop + endfacet + facet normal -0.0377336 -0.27267 0.961368 + outer loop + vertex -380.438 39.8907 27.1249 + vertex -401.156 43.1257 27.2293 + vertex -379.812 38.8484 26.8539 + endloop + endfacet + facet normal -0.0438084 -0.311188 0.949338 + outer loop + vertex -401.603 44.1527 27.5453 + vertex -401.156 43.1257 27.2293 + vertex -380.438 39.8907 27.1249 + endloop + endfacet + facet normal -0.0144267 -0.168849 0.985536 + outer loop + vertex -382.442 40.7186 27.2374 + vertex -401.603 44.1527 27.5453 + vertex -380.438 39.8907 27.1249 + endloop + endfacet + facet normal -0.0191437 -0.194732 0.98067 + outer loop + vertex -403.558 44.9696 27.6694 + vertex -401.603 44.1527 27.5453 + vertex -382.442 40.7186 27.2374 + endloop + endfacet + facet normal 0.00103062 -0.147731 0.989027 + outer loop + vertex -403.558 44.9696 27.6694 + vertex -422.542 48.681 28.2435 + vertex -401.603 44.1527 27.5453 + endloop + endfacet + facet normal -0.0372981 -0.308692 0.95043 + outer loop + vertex -401.603 44.1527 27.5453 + vertex -422.859 47.8667 27.9174 + vertex -401.156 43.1257 27.2293 + endloop + endfacet + facet normal -0.0272327 -0.19904 0.979613 + outer loop + vertex -382.442 40.7186 27.2374 + vertex -380.438 39.8907 27.1249 + vertex -362.171 36.8731 27.0196 + endloop + endfacet + facet normal -0.0387562 -0.243128 0.96922 + outer loop + vertex -359.773 35.9947 26.9106 + vertex -359.205 34.9827 26.6794 + vertex -339.171 32.3211 26.8129 + endloop + endfacet + facet normal -0.0392334 -0.239564 0.970088 + outer loop + vertex -359.205 34.9827 26.6794 + vertex -379.91 37.2514 26.4023 + vertex -359.552 33.4515 26.2873 + endloop + endfacet + facet normal -0.0427104 -0.258044 0.965189 + outer loop + vertex -379.91 37.2514 26.4023 + vertex -380.265 35.0326 25.7934 + vertex -359.552 33.4515 26.2873 + endloop + endfacet + facet normal -0.0455324 -0.249921 0.967195 + outer loop + vertex -380.265 35.0326 25.7934 + vertex -401.094 36.2551 25.1287 + vertex -380.591 32.267 25.0635 + endloop + endfacet + facet normal -0.0468841 -0.25684 0.965316 + outer loop + vertex -401.094 36.2551 25.1287 + vertex -401.472 33.064 24.2613 + vertex -380.591 32.267 25.0635 + endloop + endfacet + facet normal -0.0487855 -0.237527 0.970155 + outer loop + vertex -401.472 33.064 24.2613 + vertex -423.223 33.9479 23.384 + vertex -401.967 29.6098 23.3907 + endloop + endfacet + facet normal -0.0462943 -0.225315 0.973185 + outer loop + vertex -423.223 33.9479 23.384 + vertex -423.917 30.3283 22.5129 + vertex -401.967 29.6098 23.3907 + endloop + endfacet + facet normal -0.0467341 -0.210892 0.976392 + outer loop + vertex -423.917 30.3283 22.5129 + vertex -445.992 31.2748 21.6608 + vertex -424.513 26.5972 21.6785 + endloop + endfacet + facet normal -0.0474477 -0.214171 0.975643 + outer loop + vertex -445.992 31.2748 21.6608 + vertex -446.025 27.3009 20.7868 + vertex -424.513 26.5972 21.6785 + endloop + endfacet + facet normal -0.0544339 -0.239568 0.969352 + outer loop + vertex -446.025 27.3009 20.7868 + vertex -466.342 27.9888 19.8159 + vertex -444.863 22.8633 19.7553 + endloop + endfacet + facet normal -0.062754 -0.27499 0.959397 + outer loop + vertex -444.863 22.8633 19.7553 + vertex -464.105 22.904 18.5084 + vertex -442.32 17.9395 18.5104 + endloop + endfacet + facet normal -0.0497592 -0.240025 0.969491 + outer loop + vertex -424.48 22.6158 20.7966 + vertex -423.382 18.2302 19.7671 + vertex -403.185 18.2731 20.8143 + endloop + endfacet + facet normal -0.0452292 -0.21779 0.974947 + outer loop + vertex -403.158 22.2581 21.7058 + vertex -424.48 22.6158 20.7966 + vertex -403.185 18.2731 20.8143 + endloop + endfacet + facet normal -0.0417898 -0.212076 0.976359 + outer loop + vertex -402.601 26.0017 22.5428 + vertex -403.158 22.2581 21.7058 + vertex -381.64 21.9337 22.5563 + endloop + endfacet + facet normal -0.0433148 -0.21994 0.974551 + outer loop + vertex -381.147 25.5802 23.4012 + vertex -402.601 26.0017 22.5428 + vertex -381.64 21.9337 22.5563 + endloop + endfacet + facet normal -0.04278 -0.232785 0.971587 + outer loop + vertex -380.837 29.0685 24.2506 + vertex -381.147 25.5802 23.4012 + vertex -360.309 25.2402 24.2373 + endloop + endfacet + facet normal -0.0437593 -0.238032 0.970271 + outer loop + vertex -360.249 28.4847 25.0359 + vertex -380.837 29.0685 24.2506 + vertex -360.309 25.2402 24.2373 + endloop + endfacet + facet normal -0.0411123 -0.239326 0.970068 + outer loop + vertex -360.018 31.2689 25.7326 + vertex -360.249 28.4847 25.0359 + vertex -339.635 27.6316 25.6991 + endloop + endfacet + facet normal -0.0394516 -0.23004 0.972381 + outer loop + vertex -339.237 29.8342 26.2363 + vertex -360.018 31.2689 25.7326 + vertex -339.635 27.6316 25.6991 + endloop + endfacet + facet normal -0.0364749 -0.225502 0.97356 + outer loop + vertex -338.804 31.356 26.605 + vertex -339.237 29.8342 26.2363 + vertex -318.242 27.8645 26.5667 + endloop + endfacet + facet normal -0.0348975 -0.216236 0.975717 + outer loop + vertex -318.447 28.8037 26.7675 + vertex -338.804 31.356 26.605 + vertex -318.242 27.8645 26.5667 + endloop + endfacet + facet normal -0.0340571 -0.217123 0.97555 + outer loop + vertex -320.367 29.5547 26.8676 + vertex -318.447 28.8037 26.7675 + vertex -299.542 26.1846 26.8445 + endloop + endfacet + facet normal -0.0314781 -0.213741 0.976383 + outer loop + vertex -297.629 25.4596 26.7434 + vertex -297.306 24.5044 26.5447 + vertex -276.348 22.2389 26.7244 + endloop + endfacet + facet normal -0.0341897 -0.218458 0.975247 + outer loop + vertex -297.306 24.5044 26.5447 + vertex -318.622 26.3304 26.2065 + vertex -297.619 22.9502 26.1856 + endloop + endfacet + facet normal -0.0357543 -0.228166 0.972966 + outer loop + vertex -318.622 26.3304 26.2065 + vertex -318.915 24.0942 25.6713 + vertex -297.619 22.9502 26.1856 + endloop + endfacet + facet normal -0.0388895 -0.233452 0.97159 + outer loop + vertex -318.915 24.0942 25.6713 + vertex -339.724 24.806 25.0094 + vertex -318.962 21.2694 24.9907 + endloop + endfacet + facet normal -0.039266 -0.235659 0.971042 + outer loop + vertex -339.724 24.806 25.0094 + vertex -339.68 21.5404 24.2187 + vertex -318.962 21.2694 24.9907 + endloop + endfacet + facet normal -0.040487 -0.229031 0.972577 + outer loop + vertex -339.68 21.5404 24.2187 + vertex -360.464 21.7123 23.394 + vertex -339.781 18.0007 23.3809 + endloop + endfacet + facet normal -0.0387269 -0.219232 0.974904 + outer loop + vertex -360.464 21.7123 23.394 + vertex -360.867 18.0376 22.5516 + vertex -339.781 18.0007 23.3809 + endloop + endfacet + facet normal -0.0395847 -0.211602 0.976554 + outer loop + vertex -360.867 18.0376 22.5516 + vertex -382.148 18.16 21.7155 + vertex -361.337 14.2479 21.7114 + endloop + endfacet + facet normal -0.0408194 -0.218168 0.975057 + outer loop + vertex -382.148 18.16 21.7155 + vertex -382.196 14.1611 20.8187 + vertex -361.337 14.2479 21.7114 + endloop + endfacet + facet normal -0.0473833 -0.241973 0.969125 + outer loop + vertex -382.196 14.1611 20.8187 + vertex -402.276 13.9204 19.7769 + vertex -381.248 9.79141 19.7741 + endloop + endfacet + facet normal -0.0541798 -0.276709 0.959425 + outer loop + vertex -381.248 9.79141 19.7741 + vertex -400.364 9.18913 18.5208 + vertex -379.144 5.02749 18.5189 + endloop + endfacet + facet normal -0.0430343 -0.241099 0.969546 + outer loop + vertex -361.35 10.2382 20.8156 + vertex -360.33 5.86406 19.7731 + vertex -340.587 6.52293 20.8133 + endloop + endfacet + facet normal -0.0388297 -0.217604 0.975264 + outer loop + vertex -340.609 10.5317 21.7068 + vertex -361.35 10.2382 20.8156 + vertex -340.587 6.52293 20.8133 + endloop + endfacet + facet normal -0.0356666 -0.211347 0.97676 + outer loop + vertex -340.163 14.3237 22.5436 + vertex -340.609 10.5317 21.7068 + vertex -319.409 10.8073 22.5406 + endloop + endfacet + facet normal -0.0367205 -0.217566 0.975355 + outer loop + vertex -319.024 14.4774 23.3738 + vertex -340.163 14.3237 22.5436 + vertex -319.409 10.8073 22.5406 + endloop + endfacet + facet normal -0.0362118 -0.228106 0.972963 + outer loop + vertex -318.91 18.0055 24.2052 + vertex -319.024 14.4774 23.3738 + vertex -297.958 14.6602 24.2006 + endloop + endfacet + facet normal -0.0370904 -0.233607 0.971624 + outer loop + vertex -297.966 17.9032 24.9801 + vertex -318.91 18.0055 24.2052 + vertex -297.958 14.6602 24.2006 + endloop + endfacet + facet normal -0.0346694 -0.232713 0.971927 + outer loop + vertex -297.898 20.7189 25.6567 + vertex -297.966 17.9032 24.9801 + vertex -276.65 17.5284 25.6507 + endloop + endfacet + facet normal -0.0335259 -0.225101 0.973759 + outer loop + vertex -276.328 19.7399 26.173 + vertex -297.898 20.7189 25.6567 + vertex -276.65 17.5284 25.6507 + endloop + endfacet + facet normal -0.0300886 -0.217638 0.975566 + outer loop + vertex -276.014 21.2873 26.5279 + vertex -276.328 19.7399 26.173 + vertex -254.561 18.2757 26.5177 + endloop + endfacet + facet normal -0.0291767 -0.211147 0.977019 + outer loop + vertex -254.796 19.2015 26.7107 + vertex -276.014 21.2873 26.5279 + vertex -254.561 18.2757 26.5177 + endloop + endfacet + facet normal -0.028906 -0.225473 0.97382 + outer loop + vertex -256.495 19.8582 26.8124 + vertex -254.796 19.2015 26.7107 + vertex -235.281 17.0669 26.7958 + endloop + endfacet + facet normal -0.0242531 -0.210546 0.977283 + outer loop + vertex -233.469 16.4265 26.6981 + vertex -233.146 15.4922 26.5048 + vertex -212.176 13.8789 26.6777 + endloop + endfacet + facet normal -0.0275654 -0.216166 0.975967 + outer loop + vertex -233.146 15.4922 26.5048 + vertex -254.914 16.7392 26.1662 + vertex -233.52 13.9565 26.1541 + endloop + endfacet + facet normal -0.0288063 -0.225696 0.973772 + outer loop + vertex -254.914 16.7392 26.1662 + vertex -255.284 14.5315 25.6436 + vertex -233.52 13.9565 26.1541 + endloop + endfacet + facet normal -0.0322768 -0.231757 0.972238 + outer loop + vertex -255.284 14.5315 25.6436 + vertex -276.772 14.729 24.9773 + vertex -255.457 11.7511 24.975 + endloop + endfacet + facet normal -0.0325216 -0.233509 0.971811 + outer loop + vertex -276.772 14.729 24.9773 + vertex -276.801 11.501 24.2007 + vertex -255.457 11.7511 24.975 + endloop + endfacet + facet normal -0.0340069 -0.227772 0.973121 + outer loop + vertex -276.801 11.501 24.2007 + vertex -298.096 11.1461 23.3734 + vertex -276.947 7.99303 23.3745 + endloop + endfacet + facet normal -0.0325352 -0.217899 0.975429 + outer loop + vertex -298.096 11.1461 23.3734 + vertex -298.48 7.47899 22.5414 + vertex -276.947 7.99303 23.3745 + endloop + endfacet + facet normal -0.0336456 -0.211209 0.976862 + outer loop + vertex -298.48 7.47899 22.5414 + vertex -319.841 7.01791 21.706 + vertex -298.9 3.68951 21.7076 + endloop + endfacet + facet normal -0.0346783 -0.217708 0.975398 + outer loop + vertex -319.841 7.01791 21.706 + vertex -319.802 3.01462 20.8139 + vertex -298.9 3.68951 21.7076 + endloop + endfacet + facet normal -0.0407559 -0.242329 0.969338 + outer loop + vertex -319.802 3.01462 20.8139 + vertex -339.529 2.16127 19.7711 + vertex -318.741 -1.33023 19.7723 + endloop + endfacet + facet normal -0.046255 -0.277779 0.959531 + outer loop + vertex -318.741 -1.33023 19.7723 + vertex -337.402 -2.54927 18.5198 + vertex -316.663 -6.00707 18.5186 + endloop + endfacet + facet normal -0.0360682 -0.241653 0.969692 + outer loop + vertex -298.83 -0.313467 20.8138 + vertex -297.784 -4.64319 19.7737 + vertex -277.647 -3.46875 20.8154 + endloop + endfacet + facet normal -0.032609 -0.218426 0.975308 + outer loop + vertex -277.729 0.53305 21.7088 + vertex -298.83 -0.313467 20.8138 + vertex -277.647 -3.46875 20.8154 + endloop + endfacet + facet normal -0.0295212 -0.21159 0.976913 + outer loop + vertex -277.322 4.32668 22.5428 + vertex -277.729 0.53305 21.7088 + vertex -256.033 1.36119 22.5438 + endloop + endfacet + facet normal -0.0304097 -0.217969 0.975482 + outer loop + vertex -255.662 5.02859 23.3749 + vertex -277.322 4.32668 22.5428 + vertex -256.033 1.36119 22.5438 + endloop + endfacet + facet normal -0.0293947 -0.227958 0.973227 + outer loop + vertex -255.51 8.5323 24.2001 + vertex -255.662 5.02859 23.3749 + vertex -234.227 5.78035 24.1984 + endloop + endfacet + facet normal -0.0300385 -0.232937 0.972028 + outer loop + vertex -234.157 8.98999 24.9697 + vertex -255.51 8.5323 24.2001 + vertex -234.227 5.78035 24.1984 + endloop + endfacet + facet normal -0.0270647 -0.231762 0.972396 + outer loop + vertex -233.947 11.764 25.6367 + vertex -234.157 8.98999 24.9697 + vertex -212.708 9.23357 25.6247 + endloop + endfacet + facet normal -0.0261056 -0.223721 0.974304 + outer loop + vertex -212.234 11.4233 26.1402 + vertex -233.947 11.764 25.6367 + vertex -212.708 9.23357 25.6247 + endloop + endfacet + facet normal -0.0223008 -0.215728 0.976199 + outer loop + vertex -211.801 12.9494 26.4874 + vertex -212.234 11.4233 26.1402 + vertex -190.557 10.6592 26.4666 + endloop + endfacet + facet normal -0.0215685 -0.208949 0.977689 + outer loop + vertex -190.808 11.5699 26.6557 + vertex -211.801 12.9494 26.4874 + vertex -190.557 10.6592 26.4666 + endloop + endfacet + facet normal -0.0203298 -0.220757 0.975117 + outer loop + vertex -192.943 12.2057 26.7551 + vertex -190.808 11.5699 26.6557 + vertex -171.583 10.0998 26.7237 + endloop + endfacet + facet normal -0.0163458 -0.206753 0.978257 + outer loop + vertex -169.667 9.51777 26.6276 + vertex -169.361 8.60975 26.4408 + vertex -148.373 7.701 26.5994 + endloop + endfacet + facet normal -0.0194845 -0.211639 0.977154 + outer loop + vertex -169.361 8.60975 26.4408 + vertex -191.036 9.13865 26.1231 + vertex -169.827 7.08938 26.1022 + endloop + endfacet + facet normal -0.0205627 -0.222772 0.974654 + outer loop + vertex -191.036 9.13865 26.1231 + vertex -191.53 6.95223 25.613 + vertex -169.827 7.08938 26.1022 + endloop + endfacet + facet normal -0.0243281 -0.229244 0.973065 + outer loop + vertex -191.53 6.95223 25.613 + vertex -212.945 6.47098 24.9642 + vertex -191.77 4.19046 24.9563 + endloop + endfacet + facet normal -0.0246928 -0.232627 0.972253 + outer loop + vertex -212.945 6.47098 24.9642 + vertex -213.021 3.26422 24.195 + vertex -191.77 4.19046 24.9563 + endloop + endfacet + facet normal -0.026912 -0.227372 0.973436 + outer loop + vertex -213.021 3.26422 24.195 + vertex -234.384 2.28003 23.3745 + vertex -213.177 -0.233837 23.3736 + endloop + endfacet + facet normal -0.0258282 -0.218229 0.975556 + outer loop + vertex -234.384 2.28003 23.3745 + vertex -234.75 -1.38851 22.5442 + vertex -213.177 -0.233837 23.3736 + endloop + endfacet + facet normal -0.0273773 -0.211856 0.976917 + outer loop + vertex -234.75 -1.38851 22.5442 + vertex -256.426 -2.43543 21.7097 + vertex -235.132 -5.18722 21.7097 + endloop + endfacet + facet normal -0.0283063 -0.219045 0.975304 + outer loop + vertex -256.426 -2.43543 21.7097 + vertex -256.307 -6.439 20.814 + vertex -235.132 -5.18722 21.7097 + endloop + endfacet + facet normal -0.033667 -0.242275 0.969623 + outer loop + vertex -256.307 -6.439 20.814 + vertex -276.556 -7.79277 19.7726 + vertex -255.173 -10.7565 19.7746 + endloop + endfacet + facet normal -0.0382055 -0.278611 0.959644 + outer loop + vertex -255.173 -10.7565 19.7746 + vertex -274.425 -12.4349 18.5208 + vertex -252.84 -15.4014 18.5189 + endloop + endfacet + facet normal -0.0287383 -0.242538 0.969716 + outer loop + vertex -235.007 -9.18877 20.8154 + vertex -233.822 -13.4983 19.7726 + vertex -213.798 -11.701 20.8156 + endloop + endfacet + facet normal -0.0259627 -0.219105 0.975356 + outer loop + vertex -213.923 -7.70362 21.7102 + vertex -235.007 -9.18877 20.8154 + vertex -213.798 -11.701 20.8156 + endloop + endfacet + facet normal -0.0228055 -0.212106 0.97698 + outer loop + vertex -213.542 -3.903 22.5442 + vertex -213.923 -7.70362 21.7102 + vertex -192.358 -6.18079 22.5442 + endloop + endfacet + facet normal -0.0234151 -0.217775 0.975718 + outer loop + vertex -191.999 -2.50903 23.3724 + vertex -213.542 -3.903 22.5442 + vertex -192.358 -6.18079 22.5442 + endloop + endfacet + facet normal -0.0216687 -0.22709 0.973633 + outer loop + vertex -191.845 0.987371 24.1913 + vertex -191.999 -2.50903 23.3724 + vertex -170.616 -1.05608 24.1871 + endloop + endfacet + facet normal -0.0219987 -0.230516 0.97282 + outer loop + vertex -170.547 2.14271 24.9467 + vertex -191.845 0.987371 24.1913 + vertex -170.616 -1.05608 24.1871 + endloop + endfacet + facet normal -0.0187599 -0.228318 0.973406 + outer loop + vertex -170.317 4.90604 25.5993 + vertex -170.547 2.14271 24.9467 + vertex -149.028 3.08956 25.5835 + endloop + endfacet + facet normal -0.0179224 -0.218523 0.975667 + outer loop + vertex -148.555 5.2803 26.0828 + vertex -170.317 4.90604 25.5993 + vertex -149.028 3.08956 25.5835 + endloop + endfacet + facet normal -0.0143078 -0.209853 0.977628 + outer loop + vertex -148.082 6.80045 26.4161 + vertex -148.555 5.2803 26.0828 + vertex -126.808 5.22223 26.3887 + endloop + endfacet + facet normal -0.0137519 -0.202386 0.979209 + outer loop + vertex -126.977 6.11401 26.5706 + vertex -148.082 6.80045 26.4161 + vertex -126.808 5.22223 26.3887 + endloop + endfacet + facet normal -0.0121436 -0.21141 0.977322 + outer loop + vertex -128.814 6.64642 26.6629 + vertex -126.977 6.11401 26.5706 + vertex -107.677 5.28976 26.6321 + endloop + endfacet + facet normal -0.00910085 -0.199031 0.979951 + outer loop + vertex -105.881 4.78529 26.543 + vertex -105.532 3.89466 26.3654 + vertex -84.6192 3.6923 26.5185 + endloop + endfacet + facet normal -0.0119199 -0.205217 0.978644 + outer loop + vertex -105.532 3.89466 26.3654 + vertex -127.246 3.69954 26.06 + vertex -105.913 2.3713 26.0413 + endloop + endfacet + facet normal -0.0126622 -0.217104 0.976066 + outer loop + vertex -127.246 3.69954 26.06 + vertex -127.69 1.51247 25.5678 + vertex -105.913 2.3713 26.0413 + endloop + endfacet + facet normal -0.0161402 -0.22493 0.974241 + outer loop + vertex -127.69 1.51247 25.5678 + vertex -149.247 0.330234 24.9377 + vertex -127.893 -1.24027 24.9289 + endloop + endfacet + facet normal -0.0164933 -0.229724 0.973116 + outer loop + vertex -149.247 0.330234 24.9377 + vertex -149.304 -2.86615 24.1822 + vertex -127.893 -1.24027 24.9289 + endloop + endfacet + facet normal -0.0190732 -0.225846 0.973976 + outer loop + vertex -149.304 -2.86615 24.1822 + vertex -170.76 -4.55268 23.3709 + vertex -149.435 -6.36087 23.3692 + endloop + endfacet + facet normal -0.0183936 -0.217832 0.975813 + outer loop + vertex -170.76 -4.55268 23.3709 + vertex -171.108 -8.22719 22.5441 + vertex -149.435 -6.36087 23.3692 + endloop + endfacet + facet normal -0.0204268 -0.212008 0.977054 + outer loop + vertex -171.108 -8.22719 22.5441 + vertex -192.735 -9.98418 21.7107 + vertex -171.467 -12.0344 21.7105 + endloop + endfacet + facet normal -0.0211155 -0.219151 0.975462 + outer loop + vertex -192.735 -9.98418 21.7107 + vertex -192.613 -13.9772 20.8162 + vertex -171.467 -12.0344 21.7105 + endloop + endfacet + facet normal -0.0259922 -0.243585 0.969531 + outer loop + vertex -192.613 -13.9772 20.8162 + vertex -212.655 -15.9898 19.7733 + vertex -191.481 -18.2494 19.7732 + endloop + endfacet + facet normal -0.0295094 -0.278656 0.959938 + outer loop + vertex -191.481 -18.2494 19.7732 + vertex -210.507 -20.5585 18.5181 + vertex -189.293 -22.7984 18.52 + endloop + endfacet + facet normal -0.0206726 -0.242707 0.969879 + outer loop + vertex -171.324 -16.0274 20.8153 + vertex -170.16 -20.2898 19.7735 + vertex -149.949 -17.8441 20.8163 + endloop + endfacet + facet normal -0.018674 -0.219189 0.975504 + outer loop + vertex -150.105 -13.8517 21.7103 + vertex -171.324 -16.0274 20.8153 + vertex -149.949 -17.8441 20.8163 + endloop + endfacet + facet normal -0.0155121 -0.2123 0.977081 + outer loop + vertex -149.764 -10.0403 22.5439 + vertex -150.105 -13.8517 21.7103 + vertex -128.362 -11.6051 22.5437 + endloop + endfacet + facet normal -0.0158696 -0.217191 0.976 + outer loop + vertex -128.044 -7.92509 23.3678 + vertex -149.764 -10.0403 22.5439 + vertex -128.362 -11.6051 22.5437 + endloop + endfacet + facet normal -0.0136306 -0.225451 0.974159 + outer loop + vertex -127.933 -4.43164 24.1778 + vertex -128.044 -7.92509 23.3678 + vertex -106.532 -5.74103 24.1742 + endloop + endfacet + facet normal -0.0137863 -0.227995 0.973565 + outer loop + vertex -106.513 -2.56031 24.9194 + vertex -127.933 -4.43164 24.1778 + vertex -106.532 -5.74103 24.1742 + endloop + endfacet + facet normal -0.0107278 -0.224469 0.974422 + outer loop + vertex -106.333 0.186549 25.5541 + vertex -106.513 -2.56031 24.9194 + vertex -84.9713 -0.885997 25.5422 + endloop + endfacet + facet normal -0.0102013 -0.214008 0.976779 + outer loop + vertex -84.5707 1.28461 26.022 + vertex -106.333 0.186549 25.5541 + vertex -84.9713 -0.885997 25.5422 + endloop + endfacet + facet normal -0.00726286 -0.205233 0.978686 + outer loop + vertex -84.1947 2.81011 26.3447 + vertex -84.5707 1.28461 26.022 + vertex -62.9184 1.96435 26.3252 + endloop + endfacet + facet normal -0.00694274 -0.197218 0.980335 + outer loop + vertex -63.293 2.83606 26.4979 + vertex -84.1947 2.81011 26.3447 + vertex -62.9184 1.96435 26.3252 + endloop + endfacet + facet normal -0.00544573 -0.206651 0.9784 + outer loop + vertex -65.0777 3.2961 26.5852 + vertex -63.293 2.83606 26.4979 + vertex -44.4742 2.66701 26.567 + endloop + endfacet + facet normal -0.00294374 -0.196792 0.980441 + outer loop + vertex -42.2017 2.22756 26.4825 + vertex -41.6982 1.36251 26.3103 + vertex -21.015 1.85801 26.4719 + endloop + endfacet + facet normal -0.00515787 -0.202979 0.97917 + outer loop + vertex -41.6982 1.36251 26.3103 + vertex -63.2556 0.451242 26.0079 + vertex -41.995 -0.136037 25.9981 + endloop + endfacet + facet normal -0.00546522 -0.214066 0.976804 + outer loop + vertex -63.2556 0.451242 26.0079 + vertex -63.6267 -1.70836 25.5325 + vertex -41.995 -0.136037 25.9981 + endloop + endfacet + facet normal -0.00817257 -0.223898 0.974578 + outer loop + vertex -63.6267 -1.70836 25.5325 + vertex -85.125 -3.62102 24.9128 + vertex -63.7436 -4.43294 24.9056 + endloop + endfacet + facet normal -0.00833453 -0.228154 0.973589 + outer loop + vertex -85.125 -3.62102 24.9128 + vertex -85.1146 -6.79335 24.1695 + vertex -63.7436 -4.43294 24.9056 + endloop + endfacet + facet normal -0.0108984 -0.225013 0.974295 + outer loop + vertex -85.1146 -6.79335 24.1695 + vertex -106.626 -9.23009 23.3661 + vertex -85.1849 -10.2747 23.3647 + endloop + endfacet + facet normal -0.0105231 -0.217313 0.976045 + outer loop + vertex -106.626 -9.23009 23.3661 + vertex -106.93 -12.9101 22.5435 + vertex -85.1849 -10.2747 23.3647 + endloop + endfacet + facet normal -0.012918 -0.211906 0.977205 + outer loop + vertex -106.93 -12.9101 22.5435 + vertex -128.697 -15.4207 21.7113 + vertex -107.255 -16.7279 21.7113 + endloop + endfacet + facet normal -0.0133705 -0.219328 0.97556 + outer loop + vertex -128.697 -15.4207 21.7113 + vertex -128.523 -19.4103 20.8168 + vertex -107.255 -16.7279 21.7113 + endloop + endfacet + facet normal -0.0175856 -0.244084 0.969595 + outer loop + vertex -128.523 -19.4103 20.8168 + vertex -148.755 -22.0944 19.7741 + vertex -127.296 -23.6468 19.7725 + endloop + endfacet + facet normal -0.0198815 -0.278887 0.960118 + outer loop + vertex -127.296 -23.6468 19.7725 + vertex -146.476 -26.5988 18.5179 + vertex -124.946 -28.1297 18.519 + endloop + endfacet + facet normal -0.0117581 -0.242874 0.969987 + outer loop + vertex -107.072 -20.7147 20.8163 + vertex -105.854 -24.9364 19.774 + vertex -85.613 -21.7555 20.8158 + endloop + endfacet + facet normal -0.0106355 -0.219733 0.975502 + outer loop + vertex -85.7924 -17.7721 21.7111 + vertex -107.072 -20.7147 20.8163 + vertex -85.613 -21.7555 20.8158 + endloop + endfacet + facet normal -0.00778984 -0.212311 0.977171 + outer loop + vertex -85.4754 -13.9538 22.5432 + vertex -85.7924 -17.7721 21.7111 + vertex -64.0201 -14.7423 22.543 + endloop + endfacet + facet normal -0.0079701 -0.217216 0.976091 + outer loop + vertex -63.7433 -11.0647 23.3636 + vertex -85.4754 -13.9538 22.5432 + vertex -64.0201 -14.7423 22.543 + endloop + endfacet + facet normal -0.00576113 -0.225125 0.974313 + outer loop + vertex -63.6992 -7.59088 24.1665 + vertex -63.7433 -11.0647 23.3636 + vertex -42.3279 -8.14488 24.1649 + endloop + endfacet + facet normal -0.00583733 -0.228063 0.973629 + outer loop + vertex -42.4111 -4.99947 24.9012 + vertex -63.6992 -7.59088 24.1665 + vertex -42.3279 -8.14488 24.1649 + endloop + endfacet + facet normal -0.00341755 -0.223829 0.974622 + outer loop + vertex -42.3337 -2.29166 25.5233 + vertex -42.4111 -4.99947 24.9012 + vertex -21.1179 -2.631 25.5198 + endloop + endfacet + facet normal -0.00326528 -0.214332 0.976756 + outer loop + vertex -20.8204 -0.484604 25.9918 + vertex -42.3337 -2.29166 25.5233 + vertex -21.1179 -2.631 25.5198 + endloop + endfacet + facet normal -0.000952948 -0.203794 0.979013 + outer loop + vertex -20.5192 1.01137 26.3035 + vertex -20.8204 -0.484604 25.9918 + vertex 0.575074 0.898996 26.3006 + endloop + endfacet + facet normal -0.000918057 -0.197278 0.980347 + outer loop + vertex 0.192054 1.73646 26.4688 + vertex -20.5192 1.01137 26.3035 + vertex 0.575074 0.898996 26.3006 + endloop + endfacet + facet normal 0.000845719 -0.204923 0.978778 + outer loop + vertex -1.9402 2.11842 26.5506 + vertex 0.192054 1.73646 26.4688 + vertex 19.0324 2.21475 26.5526 + endloop + endfacet + facet normal 0.00300897 -0.196825 0.980434 + outer loop + vertex 21.1955 1.86294 26.4723 + vertex 21.6861 1.03099 26.3038 + vertex 42.3511 2.23805 26.4827 + endloop + endfacet + facet normal 0.00107901 -0.203579 0.979058 + outer loop + vertex 21.6861 1.03099 26.3038 + vertex 0.310767 -0.596288 25.9889 + vertex 21.4991 -0.463146 25.9933 + endloop + endfacet + facet normal 0.00115021 -0.214833 0.97665 + outer loop + vertex 0.310767 -0.596288 25.9889 + vertex 0.0698512 -2.74072 25.5175 + vertex 21.4991 -0.463146 25.9933 + endloop + endfacet + facet normal -0.00110084 -0.223751 0.974646 + outer loop + vertex 0.0698512 -2.74072 25.5175 + vertex -21.1469 -5.33132 24.8988 + vertex 0.081302 -5.43393 24.8993 + endloop + endfacet + facet normal -0.00112293 -0.228324 0.973585 + outer loop + vertex -21.1469 -5.33132 24.8988 + vertex -21.0297 -8.47059 24.1627 + vertex 0.081302 -5.43393 24.8993 + endloop + endfacet + facet normal -0.00335155 -0.225332 0.974276 + outer loop + vertex -21.0297 -8.47059 24.1627 + vertex -42.348 -11.613 23.3626 + vertex -21.0265 -11.933 23.362 + endloop + endfacet + facet normal -0.00323239 -0.217398 0.976078 + outer loop + vertex -42.348 -11.613 23.3626 + vertex -42.6068 -15.2902 22.5428 + vertex -21.0265 -11.933 23.362 + endloop + endfacet + facet normal -0.00545395 -0.212249 0.9772 + outer loop + vertex -42.6068 -15.2902 22.5428 + vertex -64.3299 -18.5623 21.7108 + vertex -42.9111 -19.112 21.711 + endloop + endfacet + facet normal -0.00563786 -0.219415 0.975615 + outer loop + vertex -64.3299 -18.5623 21.7108 + vertex -64.1605 -22.5427 20.8166 + vertex -42.9111 -19.112 21.711 + endloop + endfacet + facet normal -0.00882099 -0.243907 0.969759 + outer loop + vertex -64.1605 -22.5427 20.8166 + vertex -84.428 -25.9608 19.7726 + vertex -62.9653 -26.7332 19.7735 + endloop + endfacet + facet normal -0.009672 -0.279017 0.960237 + outer loop + vertex -62.9653 -26.7332 19.7735 + vertex -82.2434 -30.3803 18.5196 + vertex -60.6381 -31.129 18.5197 + endloop + endfacet + facet normal -0.00361824 -0.243314 0.969941 + outer loop + vertex -42.7312 -23.0906 20.8173 + vertex -41.483 -27.2696 19.7737 + vertex -21.3697 -23.4126 20.8163 + endloop + endfacet + facet normal -0.00326318 -0.219775 0.975545 + outer loop + vertex -21.5686 -19.4358 21.7115 + vertex -42.7312 -23.0906 20.8173 + vertex -21.3697 -23.4126 20.8163 + endloop + endfacet + facet normal -0.00104164 -0.21223 0.977219 + outer loop + vertex -21.2717 -15.6106 22.5426 + vertex -21.5686 -19.4358 21.7115 + vertex 0.0253544 -15.7154 22.5425 + endloop + endfacet + facet normal -0.00106634 -0.217246 0.976116 + outer loop + vertex 0.25968 -12.0352 23.3618 + vertex -21.2717 -15.6106 22.5426 + vertex 0.0253544 -15.7154 22.5425 + endloop + endfacet + facet normal 0.00120922 -0.225339 0.97428 + outer loop + vertex 0.233556 -8.57208 24.1628 + vertex 0.25968 -12.0352 23.3618 + vertex 21.5383 -8.45648 24.1631 + endloop + endfacet + facet normal 0.00122534 -0.228309 0.973588 + outer loop + vertex 21.3606 -5.31665 24.8996 + vertex 0.233556 -8.57208 24.1628 + vertex 21.5383 -8.45648 24.1631 + endloop + endfacet + facet normal 0.00347495 -0.224109 0.974558 + outer loop + vertex 21.3071 -2.61323 25.5215 + vertex 21.3606 -5.31665 24.8996 + vertex 42.6442 -2.26064 25.5265 + endloop + endfacet + facet normal 0.0033122 -0.214291 0.976764 + outer loop + vertex 42.7988 -0.0987656 26.0003 + vertex 21.3071 -2.61323 25.5215 + vertex 42.6442 -2.26064 25.5265 + endloop + endfacet + facet normal 0.00520027 -0.203943 0.978969 + outer loop + vertex 42.9427 1.40868 26.3136 + vertex 42.7988 -0.0987656 26.0003 + vertex 64.2642 2.02416 26.3285 + endloop + endfacet + facet normal 0.00499836 -0.196983 0.980394 + outer loop + vertex 63.7 2.85482 26.4983 + vertex 42.9427 1.40868 26.3136 + vertex 64.2642 2.02416 26.3285 + endloop + endfacet + facet normal 0.00713575 -0.205906 0.978546 + outer loop + vertex 61.3081 3.16554 26.5811 + vertex 63.7 2.85482 26.4983 + vertex 82.6393 4.00411 26.602 + endloop + endfacet + facet normal 0.00895101 -0.196007 0.980562 + outer loop + vertex 84.8639 3.70108 26.5186 + vertex 85.5403 2.87241 26.3468 + vertex 106.092 4.79266 26.5431 + endloop + endfacet + facet normal 0.00725402 -0.203495 0.979049 + outer loop + vertex 85.5403 2.87241 26.3468 + vertex 64.1491 0.504276 26.0131 + vertex 85.475 1.34459 26.0297 + endloop + endfacet + facet normal 0.00767906 -0.214237 0.976752 + outer loop + vertex 64.1491 0.504276 26.0131 + vertex 64.0286 -1.67264 25.5366 + vertex 85.475 1.34459 26.0297 + endloop + endfacet + facet normal 0.00576377 -0.224075 0.974555 + outer loop + vertex 64.0286 -1.67264 25.5366 + vertex 42.7282 -4.97128 24.9041 + vertex 64.1558 -4.40017 24.9087 + endloop + endfacet + facet normal 0.00587145 -0.228108 0.973618 + outer loop + vertex 42.7282 -4.97128 24.9041 + vertex 42.9392 -8.11956 24.1652 + vertex 64.1558 -4.40017 24.9087 + endloop + endfacet + facet normal 0.00346049 -0.225171 0.974313 + outer loop + vertex 42.9392 -8.11956 24.1652 + vertex 21.5879 -11.922 23.3623 + vertex 43.0088 -11.5916 23.3626 + endloop + endfacet + facet normal 0.00333979 -0.217349 0.976088 + outer loop + vertex 21.5879 -11.922 23.3623 + vertex 21.3644 -15.6074 22.5424 + vertex 43.0088 -11.5916 23.3626 + endloop + endfacet + facet normal 0.00102525 -0.211929 0.977284 + outer loop + vertex 21.3644 -15.6074 22.5424 + vertex -0.26802 -19.5438 21.7115 + vertex 21.0749 -19.4402 21.7116 + endloop + endfacet + facet normal 0.00106175 -0.219444 0.975625 + outer loop + vertex -0.26802 -19.5438 21.7115 + vertex -0.0816638 -23.5187 20.8172 + vertex 21.0749 -19.4402 21.7116 + endloop + endfacet + facet normal -0.000986721 -0.244173 0.969731 + outer loop + vertex -0.0816638 -23.5187 20.8172 + vertex -20.1421 -27.5788 19.7745 + vertex 1.13233 -27.6708 19.773 + endloop + endfacet + facet normal -0.000772728 -0.279473 0.960153 + outer loop + vertex 1.13233 -27.6708 19.773 + vertex -17.8405 -31.9212 18.5205 + vertex 3.39386 -31.9867 18.5185 + endloop + endfacet + facet normal 0.00359154 -0.243011 0.970017 + outer loop + vertex 21.2729 -23.4129 20.8162 + vertex 22.4786 -27.5535 19.7744 + vertex 42.7221 -23.0923 20.8171 + endloop + endfacet + facet normal 0.00323916 -0.21945 0.975618 + outer loop + vertex 42.5235 -19.1203 21.7112 + vertex 21.2729 -23.4129 20.8162 + vertex 42.7221 -23.0923 20.8171 + endloop + endfacet + facet normal 0.00544238 -0.212106 0.977231 + outer loop + vertex 42.8027 -15.2835 22.5424 + vertex 42.5235 -19.1203 21.7112 + vertex 64.3062 -14.7322 22.5423 + endloop + endfacet + facet normal 0.00557014 -0.21709 0.976136 + outer loop + vertex 64.5007 -11.0351 23.3634 + vertex 42.8027 -15.2835 22.5424 + vertex 64.3062 -14.7322 22.5423 + endloop + endfacet + facet normal 0.00828539 -0.225163 0.974286 + outer loop + vertex 64.4052 -7.55509 24.1685 + vertex 64.5007 -11.0351 23.3634 + vertex 85.8616 -6.75413 24.1711 + endloop + endfacet + facet normal 0.00840831 -0.228453 0.973519 + outer loop + vertex 85.5724 -3.58959 24.9162 + vertex 64.4052 -7.55509 24.1685 + vertex 85.8616 -6.75413 24.1711 + endloop + endfacet + facet normal 0.0105906 -0.223911 0.974552 + outer loop + vertex 85.3968 -0.852966 25.5469 + vertex 85.5724 -3.58959 24.9162 + vertex 106.725 0.215573 25.5606 + endloop + endfacet + facet normal 0.0101599 -0.215338 0.976487 + outer loop + vertex 106.764 2.42271 26.0469 + vertex 85.3968 -0.852966 25.5469 + vertex 106.725 0.215573 25.5606 + endloop + endfacet + facet normal 0.0117511 -0.204347 0.978828 + outer loop + vertex 106.819 3.96331 26.3679 + vertex 106.764 2.42271 26.0469 + vertex 128.165 5.315 26.3938 + endloop + endfacet + facet normal 0.0114602 -0.199772 0.979775 + outer loop + vertex 127.565 6.14789 26.5707 + vertex 106.819 3.96331 26.3679 + vertex 128.165 5.315 26.3938 + endloop + endfacet + facet normal 0.0139977 -0.209078 0.977799 + outer loop + vertex 125.033 6.38388 26.6574 + vertex 127.565 6.14789 26.5707 + vertex 146.785 7.98739 26.6889 + endloop + endfacet + facet normal 0.0159003 -0.200413 0.979582 + outer loop + vertex 149.136 7.76113 26.5999 + vertex 149.577 6.92016 26.4207 + vertex 170.608 9.61537 26.6307 + endloop + endfacet + facet normal 0.0144915 -0.207895 0.978044 + outer loop + vertex 149.577 6.92016 26.4207 + vertex 128.077 3.75652 26.0668 + vertex 149.448 5.34914 26.0887 + endloop + endfacet + facet normal 0.0151296 -0.216431 0.976181 + outer loop + vertex 128.077 3.75652 26.0668 + vertex 128.058 1.54013 25.5757 + vertex 149.448 5.34914 26.0887 + endloop + endfacet + facet normal 0.0135574 -0.226064 0.974018 + outer loop + vertex 128.058 1.54013 25.5757 + vertex 106.948 -2.53039 24.9248 + vertex 128.315 -1.2142 24.9328 + endloop + endfacet + facet normal 0.0137224 -0.228738 0.973391 + outer loop + vertex 106.948 -2.53039 24.9248 + vertex 107.274 -5.70049 24.1752 + vertex 128.315 -1.2142 24.9328 + endloop + endfacet + facet normal 0.0109838 -0.225563 0.974167 + outer loop + vertex 107.274 -5.70049 24.1752 + vertex 85.9834 -10.2388 23.3645 + vertex 107.417 -9.18923 23.3658 + endloop + endfacet + facet normal 0.0105746 -0.217208 0.976068 + outer loop + vertex 85.9834 -10.2388 23.3645 + vertex 85.8016 -13.9421 22.5423 + vertex 107.417 -9.18923 23.3658 + endloop + endfacet + facet normal 0.0077396 -0.211822 0.977278 + outer loop + vertex 85.8016 -13.9421 22.5423 + vertex 64.038 -18.5738 21.7108 + vertex 85.5347 -17.7877 21.7109 + endloop + endfacet + facet normal 0.00801838 -0.219445 0.975592 + outer loop + vertex 64.038 -18.5738 21.7108 + vertex 64.2494 -22.544 20.816 + vertex 85.5347 -17.7877 21.7109 + endloop + endfacet + facet normal 0.00627951 -0.243521 0.969875 + outer loop + vertex 64.2494 -22.544 20.816 + vertex 43.9548 -27.2209 19.7731 + vertex 65.482 -26.6599 19.7746 + endloop + endfacet + facet normal 0.0075188 -0.278962 0.960273 + outer loop + vertex 65.482 -26.6599 19.7746 + vertex 46.2419 -31.497 18.52 + vertex 67.8424 -30.9103 18.5213 + endloop + endfacet + facet normal 0.0119218 -0.243455 0.969839 + outer loop + vertex 85.7492 -21.7546 20.8168 + vertex 87.0215 -25.8535 19.7722 + vertex 107.212 -20.7084 20.8156 + endloop + endfacet + facet normal 0.0107582 -0.219578 0.975536 + outer loop + vertex 106.988 -16.7446 21.7102 + vertex 85.7492 -21.7546 20.8168 + vertex 107.212 -20.7084 20.8156 + endloop + endfacet + facet normal 0.0129616 -0.21213 0.977155 + outer loop + vertex 107.244 -12.8959 22.5424 + vertex 106.988 -16.7446 21.7102 + vertex 128.662 -11.5873 22.5424 + endloop + endfacet + facet normal 0.0132902 -0.21751 0.975968 + outer loop + vertex 128.821 -7.87654 23.3672 + vertex 107.244 -12.8959 22.5424 + vertex 128.662 -11.5873 22.5424 + endloop + endfacet + facet normal 0.0164439 -0.225932 0.974004 + outer loop + vertex 128.664 -4.38592 24.1795 + vertex 128.821 -7.87654 23.3672 + vertex 150.068 -2.80896 24.184 + endloop + endfacet + facet normal 0.0167878 -0.230598 0.972904 + outer loop + vertex 149.711 0.364609 24.9423 + vertex 128.664 -4.38592 24.1795 + vertex 150.068 -2.80896 24.184 + endloop + endfacet + facet normal 0.0187483 -0.226924 0.973732 + outer loop + vertex 149.444 3.12091 25.5898 + vertex 149.711 0.364609 24.9423 + vertex 170.854 4.957 25.6055 + endloop + endfacet + facet normal 0.0181799 -0.220308 0.975261 + outer loop + vertex 170.849 7.18987 26.11 + vertex 149.444 3.12091 25.5898 + vertex 170.854 4.957 25.6055 + endloop + endfacet + facet normal 0.0194307 -0.210465 0.977408 + outer loop + vertex 170.963 8.76674 26.4472 + vertex 170.849 7.18987 26.11 + vertex 192.24 10.8346 26.4695 + endloop + endfacet + facet normal 0.0192088 -0.208187 0.9779 + outer loop + vertex 191.726 11.6656 26.6565 + vertex 170.963 8.76674 26.4472 + vertex 192.24 10.8346 26.4695 + endloop + endfacet + facet normal 0.0225824 -0.222141 0.974753 + outer loop + vertex 189.707 11.8744 26.7509 + vertex 191.726 11.6656 26.6565 + vertex 210.28 14.0709 26.7748 + endloop + endfacet + facet normal 0.024049 -0.208925 0.977636 + outer loop + vertex 212.72 13.9409 26.6805 + vertex 213.475 13.1432 26.4915 + vertex 233.892 16.4706 26.7003 + endloop + endfacet + facet normal 0.0224924 -0.214782 0.976403 + outer loop + vertex 213.475 13.1432 26.4915 + vertex 192.212 9.26393 26.1279 + vertex 213.482 11.5736 26.146 + endloop + endfacet + facet normal 0.0232981 -0.222189 0.974725 + outer loop + vertex 192.212 9.26393 26.1279 + vertex 192.219 7.02798 25.6181 + vertex 213.482 11.5736 26.146 + endloop + endfacet + facet normal 0.0218996 -0.229891 0.97297 + outer loop + vertex 192.219 7.02798 25.6181 + vertex 171.118 2.19556 24.9512 + vertex 192.462 4.26479 24.9597 + endloop + endfacet + facet normal 0.0220329 -0.231265 0.972641 + outer loop + vertex 171.118 2.19556 24.9512 + vertex 171.473 -0.978975 24.1884 + vertex 192.462 4.26479 24.9597 + endloop + endfacet + facet normal 0.0193393 -0.227169 0.973663 + outer loop + vertex 171.473 -0.978975 24.1884 + vertex 150.236 -6.30078 23.3685 + vertex 171.65 -4.47234 23.3698 + endloop + endfacet + facet normal 0.0185407 -0.217818 0.975813 + outer loop + vertex 150.236 -6.30078 23.3685 + vertex 150.093 -10.0148 22.5422 + vertex 171.65 -4.47234 23.3698 + endloop + endfacet + facet normal 0.015583 -0.212143 0.977114 + outer loop + vertex 150.093 -10.0148 22.5422 + vertex 128.413 -15.4395 21.7102 + vertex 149.859 -13.8684 21.7093 + endloop + endfacet + facet normal 0.0161046 -0.219264 0.975533 + outer loop + vertex 128.413 -15.4395 21.7102 + vertex 128.634 -19.4001 20.8164 + vertex 149.859 -13.8684 21.7093 + endloop + endfacet + facet normal 0.015107 -0.243805 0.969707 + outer loop + vertex 128.634 -19.4001 20.8164 + vertex 108.463 -24.7944 19.7744 + vertex 129.878 -23.4706 19.7736 + endloop + endfacet + facet normal 0.0176003 -0.278776 0.960195 + outer loop + vertex 129.878 -23.4706 19.7736 + vertex 110.805 -28.9926 18.52 + vertex 132.171 -27.6438 18.5199 + endloop + endfacet + facet normal 0.0206637 -0.242878 0.969837 + outer loop + vertex 150.094 -17.8262 20.8147 + vertex 151.341 -21.8827 19.7723 + vertex 171.548 -16.0015 20.8146 + endloop + endfacet + facet normal 0.0186623 -0.219347 0.975468 + outer loop + vertex 171.299 -12.0461 21.7088 + vertex 150.094 -17.8262 20.8147 + vertex 171.548 -16.0015 20.8146 + endloop + endfacet + facet normal 0.0204971 -0.21218 0.977016 + outer loop + vertex 171.518 -8.18818 22.542 + vertex 171.299 -12.0461 21.7088 + vertex 192.869 -6.12661 22.5418 + endloop + endfacet + facet normal 0.0210752 -0.218166 0.975684 + outer loop + vertex 192.988 -2.40699 23.371 + vertex 171.518 -8.18818 22.542 + vertex 192.869 -6.12661 22.5418 + endloop + endfacet + facet normal 0.0243945 -0.227449 0.973484 + outer loop + vertex 192.807 1.08718 24.1919 + vertex 192.988 -2.40699 23.371 + vertex 214.021 3.37928 24.1958 + endloop + endfacet + facet normal 0.0249954 -0.233008 0.972154 + outer loop + vertex 213.685 6.558 24.9663 + vertex 192.807 1.08718 24.1919 + vertex 214.021 3.37928 24.1958 + endloop + endfacet + facet normal 0.0270985 -0.231015 0.972573 + outer loop + vertex 213.465 9.32885 25.6306 + vertex 213.685 6.558 24.9663 + vertex 234.601 11.852 25.6411 + endloop + endfacet + facet normal 0.0263649 -0.224875 0.974031 + outer loop + vertex 234.65 14.1022 26.1592 + vertex 213.465 9.32885 25.6306 + vertex 234.601 11.852 25.6411 + endloop + endfacet + facet normal 0.0276029 -0.21653 0.975886 + outer loop + vertex 234.678 15.6788 26.5083 + vertex 234.65 14.1022 26.1592 + vertex 255.836 18.4464 26.5239 + endloop + endfacet + facet normal 0.0272637 -0.21394 0.976466 + outer loop + vertex 255.203 19.2487 26.7173 + vertex 234.678 15.6788 26.5083 + vertex 255.836 18.4464 26.5239 + endloop + endfacet + facet normal 0.0307793 -0.225052 0.97386 + outer loop + vertex 252.699 19.3316 26.8156 + vertex 255.203 19.2487 26.7173 + vertex 273.997 22.3044 26.8295 + endloop + endfacet + facet normal 0.0318411 -0.214747 0.97615 + outer loop + vertex 276.327 22.226 26.7311 + vertex 276.956 21.4241 26.5342 + vertex 297.507 25.4234 26.7436 + endloop + endfacet + facet normal 0.030587 -0.219534 0.975125 + outer loop + vertex 276.956 21.4241 26.5342 + vertex 255.762 16.8588 26.1711 + vertex 276.868 19.8259 26.1771 + endloop + endfacet + facet normal 0.0315264 -0.226213 0.973568 + outer loop + vertex 255.762 16.8588 26.1711 + vertex 255.698 14.5947 25.6471 + vertex 276.868 19.8259 26.1771 + endloop + endfacet + facet normal 0.0299816 -0.232236 0.972197 + outer loop + vertex 255.698 14.5947 25.6471 + vertex 234.804 9.07503 24.973 + vertex 255.885 11.8114 24.9765 + endloop + endfacet + facet normal 0.0301195 -0.233298 0.971939 + outer loop + vertex 234.804 9.07503 24.973 + vertex 235.128 5.89051 24.1985 + vertex 255.885 11.8114 24.9765 + endloop + endfacet + facet normal 0.0270435 -0.228051 0.973273 + outer loop + vertex 235.128 5.89051 24.1985 + vertex 214.199 -0.11809 23.3722 + vertex 235.303 2.38996 23.3734 + endloop + endfacet + facet normal 0.025891 -0.218354 0.975526 + outer loop + vertex 214.199 -0.11809 23.3722 + vertex 214.088 -3.84149 22.5417 + vertex 235.303 2.38996 23.3734 + endloop + endfacet + facet normal 0.0228899 -0.212265 0.976944 + outer loop + vertex 214.088 -3.84149 22.5417 + vertex 192.661 -9.98799 21.7083 + vertex 213.895 -7.70496 21.7068 + endloop + endfacet + facet normal 0.0236274 -0.219125 0.975411 + outer loop + vertex 192.661 -9.98799 21.7083 + vertex 192.925 -13.9405 20.8139 + vertex 213.895 -7.70496 21.7068 + endloop + endfacet + facet normal 0.0236132 -0.243264 0.969673 + outer loop + vertex 192.925 -13.9405 20.8139 + vertex 172.82 -20.0427 19.7727 + vertex 194.216 -17.9671 19.7723 + endloop + endfacet + facet normal 0.0272968 -0.278308 0.960104 + outer loop + vertex 194.216 -17.9671 19.7723 + vertex 175.214 -24.1542 18.5191 + vertex 196.626 -22.0511 18.52 + endloop + endfacet + facet normal 0.0287249 -0.242349 0.969764 + outer loop + vertex 214.161 -11.657 20.8135 + vertex 215.455 -15.6698 19.7724 + vertex 235.284 -9.15393 20.8134 + endloop + endfacet + facet normal 0.0259656 -0.219063 0.975365 + outer loop + vertex 235.004 -5.20634 21.7075 + vertex 214.161 -11.657 20.8135 + vertex 235.284 -9.15393 20.8134 + endloop + endfacet + facet normal 0.0273819 -0.212087 0.976867 + outer loop + vertex 235.193 -1.33819 22.542 + vertex 235.004 -5.20634 21.7075 + vertex 256.246 1.38387 22.5428 + endloop + endfacet + facet normal 0.0281851 -0.218298 0.975475 + outer loop + vertex 256.356 5.11609 23.3749 + vertex 235.193 -1.33819 22.542 + vertex 256.246 1.38387 22.5428 + endloop + endfacet + facet normal 0.0317946 -0.227845 0.973178 + outer loop + vertex 256.193 8.62235 24.2011 + vertex 256.356 5.11609 23.3749 + vertex 277.235 11.5667 24.203 + endloop + endfacet + facet normal 0.0325419 -0.233186 0.971888 + outer loop + vertex 276.951 14.7647 24.9798 + vertex 256.193 8.62235 24.2011 + vertex 277.235 11.5667 24.203 + endloop + endfacet + facet normal 0.0347273 -0.232179 0.972053 + outer loop + vertex 276.785 17.5599 25.6534 + vertex 276.951 14.7647 24.9798 + vertex 297.807 20.717 25.6564 + endloop + endfacet + facet normal 0.0340177 -0.227456 0.973194 + outer loop + vertex 297.92 23.0044 26.1871 + vertex 276.785 17.5599 25.6534 + vertex 297.807 20.717 25.6564 + endloop + endfacet + facet normal 0.0343336 -0.220242 0.974841 + outer loop + vertex 298.054 24.6073 26.5445 + vertex 297.92 23.0044 26.1871 + vertex 318.994 27.9803 26.569 + endloop + endfacet + facet normal 0.0336026 -0.215712 0.975879 + outer loop + vertex 318.601 28.8118 26.7664 + vertex 298.054 24.6073 26.5445 + vertex 318.994 27.9803 26.569 + endloop + endfacet + facet normal 0.0346395 -0.216191 0.975737 + outer loop + vertex 316.576 28.907 26.8594 + vertex 318.601 28.8118 26.7664 + vertex 337.426 32.4388 26.9017 + endloop + endfacet + facet normal 0.0340652 -0.219829 0.974944 + outer loop + vertex 339.326 32.3462 26.8226 + vertex 339.708 31.5008 26.6185 + vertex 359.917 36.0381 26.9355 + endloop + endfacet + facet normal 0.0370327 -0.228877 0.972751 + outer loop + vertex 339.708 31.5008 26.6185 + vertex 318.81 26.357 26.2039 + vertex 339.542 29.8829 26.2442 + endloop + endfacet + facet normal 0.0384301 -0.23399 0.971479 + outer loop + vertex 339.542 29.8829 26.2442 + vertex 318.683 24.0609 25.6671 + vertex 339.463 27.5927 25.6957 + endloop + endfacet + facet normal 0.0421941 -0.245264 0.968538 + outer loop + vertex 360.306 31.324 25.7591 + vertex 339.666 24.7965 25.0053 + vertex 360.554 28.5423 25.0439 + endloop + endfacet + facet normal 0.0405751 -0.245417 0.968568 + outer loop + vertex 360.306 31.324 25.7591 + vertex 360.554 28.5423 25.0439 + vertex 381.18 35.2433 25.8778 + endloop + endfacet + facet normal 0.0382878 -0.233154 0.971686 + outer loop + vertex 318.683 24.0609 25.6671 + vertex 318.829 21.2565 24.9884 + vertex 339.463 27.5927 25.6957 + endloop + endfacet + facet normal 0.0395759 -0.235273 0.971123 + outer loop + vertex 339.666 24.7965 25.0053 + vertex 319.115 18.0493 24.2082 + vertex 339.988 21.593 24.2161 + endloop + endfacet + facet normal 0.0368728 -0.232413 0.971918 + outer loop + vertex 297.947 17.9138 24.9813 + vertex 298.217 14.7118 24.2054 + vertex 318.829 21.2565 24.9884 + endloop + endfacet + facet normal 0.0338822 -0.227148 0.973271 + outer loop + vertex 298.217 14.7118 24.2054 + vertex 277.387 8.05409 23.3767 + vertex 298.365 11.1925 23.3789 + endloop + endfacet + facet normal 0.0325078 -0.217962 0.975416 + outer loop + vertex 277.387 8.05409 23.3767 + vertex 277.279 4.31562 22.5449 + vertex 298.365 11.1925 23.3789 + endloop + endfacet + facet normal 0.0293526 -0.211725 0.976888 + outer loop + vertex 277.279 4.31562 22.5449 + vertex 256.071 -2.48701 21.7078 + vertex 277.117 0.441656 21.7102 + endloop + endfacet + facet normal 0.032544 -0.218947 0.975194 + outer loop + vertex 298.13 3.57273 21.7128 + vertex 277.428 -3.50079 20.8156 + vertex 298.472 -0.364797 20.8174 + endloop + endfacet + facet normal 0.0346487 -0.218758 0.975164 + outer loop + vertex 298.13 3.57273 21.7128 + vertex 298.472 -0.364797 20.8174 + vertex 319.08 6.89768 21.7143 + endloop + endfacet + facet normal 0.0303591 -0.218957 0.975262 + outer loop + vertex 256.071 -2.48701 21.7078 + vertex 256.37 -6.43215 20.8128 + vertex 277.117 0.441656 21.7102 + endloop + endfacet + facet normal 0.0313776 -0.242751 0.969581 + outer loop + vertex 256.37 -6.43215 20.8128 + vertex 236.588 -13.1531 19.7702 + vertex 257.657 -10.4229 19.772 + endloop + endfacet + facet normal 0.0362527 -0.278097 0.959869 + outer loop + vertex 257.657 -10.4229 19.772 + vertex 238.954 -17.1913 18.5174 + vertex 259.988 -14.4447 18.5187 + endloop + endfacet + facet normal 0.0360689 -0.242597 0.969456 + outer loop + vertex 277.428 -3.50079 20.8156 + vertex 278.741 -7.47664 19.7718 + vertex 298.472 -0.364797 20.8174 + endloop + endfacet + facet normal 0.0418189 -0.278502 0.959525 + outer loop + vertex 299.818 -4.32474 19.7755 + vertex 281.1 -11.4709 18.5171 + vertex 302.304 -8.27867 18.5195 + endloop + endfacet + facet normal 0.0407919 -0.242358 0.969329 + outer loop + vertex 319.438 2.96171 20.8209 + vertex 320.833 -0.980454 19.7765 + vertex 340.318 6.47497 20.8206 + endloop + endfacet + facet normal 0.0344655 -0.218252 0.975284 + outer loop + vertex 319.08 6.89768 21.7143 + vertex 298.472 -0.364797 20.8174 + vertex 319.438 2.96171 20.8209 + endloop + endfacet + facet normal 0.0334363 -0.211119 0.976888 + outer loop + vertex 319.203 10.7782 22.5488 + vertex 298.13 3.57273 21.7128 + vertex 319.08 6.89768 21.7143 + endloop + endfacet + facet normal 0.0344906 -0.217188 0.97552 + outer loop + vertex 319.282 14.5277 23.3807 + vertex 298.274 7.44889 22.5475 + vertex 319.203 10.7782 22.5488 + endloop + endfacet + facet normal 0.0381466 -0.226858 0.97318 + outer loop + vertex 319.115 18.0493 24.2082 + vertex 319.282 14.5277 23.3807 + vertex 339.988 21.593 24.2161 + endloop + endfacet + facet normal 0.0403825 -0.235189 0.97111 + outer loop + vertex 339.666 24.7965 25.0053 + vertex 339.988 21.593 24.2161 + vertex 360.554 28.5423 25.0439 + endloop + endfacet + facet normal 0.0413838 -0.231443 0.971968 + outer loop + vertex 360.872 25.3473 24.2341 + vertex 340.163 18.0657 23.382 + vertex 361.012 21.8083 23.3855 + endloop + endfacet + facet normal 0.0392271 -0.21837 0.975077 + outer loop + vertex 361.012 21.8083 23.3855 + vertex 340.078 14.3044 22.5471 + vertex 360.892 18.0292 22.544 + endloop + endfacet + facet normal 0.0375667 -0.209802 0.977022 + outer loop + vertex 360.892 18.0292 22.544 + vertex 339.95 10.4128 21.7137 + vertex 360.75 14.1199 21.7099 + endloop + endfacet + facet normal 0.0426429 -0.214736 0.975741 + outer loop + vertex 402.49 22.1659 21.7018 + vertex 381.92 14.0667 20.8183 + vertex 403.014 18.2422 20.8154 + endloop + endfacet + facet normal 0.0408275 -0.216025 0.975534 + outer loop + vertex 360.75 14.1199 21.7099 + vertex 361.102 10.1683 20.8202 + vertex 381.544 18.0257 21.7046 + endloop + endfacet + facet normal 0.0428687 -0.2413 0.969503 + outer loop + vertex 361.102 10.1683 20.8202 + vertex 341.674 2.53342 19.779 + vertex 362.445 6.22818 19.7801 + endloop + endfacet + facet normal 0.0497779 -0.278352 0.959188 + outer loop + vertex 362.445 6.22818 19.7801 + vertex 344.036 -1.39791 18.5225 + vertex 364.839 2.32503 18.5232 + endloop + endfacet + facet normal 0.047656 -0.240064 0.969587 + outer loop + vertex 381.92 14.0667 20.8183 + vertex 383.382 10.1534 19.7776 + vertex 403.014 18.2422 20.8154 + endloop + endfacet + facet normal 0.0448683 -0.214431 0.975708 + outer loop + vertex 402.49 22.1659 21.7018 + vertex 403.014 18.2422 20.8154 + vertex 423.842 26.6204 21.6989 + endloop + endfacet + facet normal 0.0447703 -0.213961 0.975816 + outer loop + vertex 423.782 30.4693 22.5455 + vertex 402.49 22.1659 21.7018 + vertex 423.842 26.6204 21.6989 + endloop + endfacet + facet normal 0.0502013 -0.239078 0.969702 + outer loop + vertex 424.563 22.7768 20.8193 + vertex 404.605 14.3658 19.7788 + vertex 426.22 18.9321 19.7857 + endloop + endfacet + facet normal 0.0578534 -0.275022 0.959696 + outer loop + vertex 426.22 18.9321 19.7857 + vertex 407.221 10.5286 18.5228 + vertex 428.556 15.029 18.5263 + endloop + endfacet + facet normal 0.0542629 -0.237282 0.969924 + outer loop + vertex 446.405 27.646 20.8315 + vertex 448.008 23.7873 19.7979 + vertex 467.33 32.435 20.8325 + endloop + endfacet + facet normal 0.0489525 -0.214081 0.975589 + outer loop + vertex 466.277 36.1737 21.7057 + vertex 446.405 27.646 20.8315 + vertex 467.33 32.435 20.8325 + endloop + endfacet + facet normal 0.0623522 -0.272603 0.960104 + outer loop + vertex 468.782 28.5192 19.796 + vertex 450.121 19.8126 18.5359 + vertex 470.997 24.5992 18.5392 + endloop + endfacet + facet normal 0.0557504 -0.237865 0.969697 + outer loop + vertex 485.043 36.2548 20.7623 + vertex 486.406 32.4236 19.7441 + vertex 496.466 38.0141 20.5371 + endloop + endfacet + facet normal 0.0523865 -0.215327 0.975136 + outer loop + vertex 497.695 42.284 21.4139 + vertex 485.043 36.2548 20.7623 + vertex 496.466 38.0141 20.5371 + endloop + endfacet + facet normal 0.0554863 -0.213847 0.97529 + outer loop + vertex 506.551 47.0265 21.9362 + vertex 505.761 40.6922 20.5922 + vertex 512.727 44.2679 20.98 + endloop + endfacet + facet normal 0.0599017 -0.204561 0.977019 + outer loop + vertex 512.727 44.2679 20.98 + vertex 512.145 49.1433 22.0364 + vertex 506.551 47.0265 21.9362 + endloop + endfacet + facet normal 0.0639551 -0.215152 0.974484 + outer loop + vertex 508.244 50.7454 22.6461 + vertex 506.551 47.0265 21.9362 + vertex 512.145 49.1433 22.0364 + endloop + endfacet + facet normal 0.0622139 -0.2191 0.973717 + outer loop + vertex 509.082 51.7825 22.826 + vertex 508.244 50.7454 22.6461 + vertex 512.145 49.1433 22.0364 + endloop + endfacet + facet normal 0.0626341 -0.218635 0.973794 + outer loop + vertex 509.082 51.7825 22.826 + vertex 512.145 49.1433 22.0364 + vertex 511.755 52.1385 22.734 + endloop + endfacet + facet normal 0.0618347 -0.218746 0.973821 + outer loop + vertex 512.145 49.1433 22.0364 + vertex 519.129 51.0485 22.0209 + vertex 511.755 52.1385 22.734 + endloop + endfacet + facet normal 0.0611665 -0.222706 0.972965 + outer loop + vertex 514.958 53.329 22.8051 + vertex 511.755 52.1385 22.734 + vertex 519.129 51.0485 22.0209 + endloop + endfacet + facet normal 0.0630449 -0.219481 0.973578 + outer loop + vertex 514.958 53.329 22.8051 + vertex 519.129 51.0485 22.0209 + vertex 520.645 54.2855 22.6525 + endloop + endfacet + facet normal 0.0613325 -0.218733 0.973855 + outer loop + vertex 519.129 51.0485 22.0209 + vertex 529.55 53.6553 21.9501 + vertex 520.645 54.2855 22.6525 + endloop + endfacet + facet normal 0.061385 -0.218136 0.973986 + outer loop + vertex 525.995 56.0232 22.7044 + vertex 520.645 54.2855 22.6525 + vertex 529.55 53.6553 21.9501 + endloop + endfacet + facet normal 0.0630046 -0.215835 0.974395 + outer loop + vertex 525.995 56.0232 22.7044 + vertex 529.55 53.6553 21.9501 + vertex 532.438 57.2829 22.5669 + endloop + endfacet + facet normal 0.0613098 -0.214552 0.974786 + outer loop + vertex 529.55 53.6553 21.9501 + vertex 541.323 56.7291 21.8862 + vertex 532.438 57.2829 22.5669 + endloop + endfacet + facet normal 0.0613906 -0.213526 0.975007 + outer loop + vertex 537.974 59.1725 22.6321 + vertex 532.438 57.2829 22.5669 + vertex 541.323 56.7291 21.8862 + endloop + endfacet + facet normal 0.0639754 -0.210157 0.975572 + outer loop + vertex 537.974 59.1725 22.6321 + vertex 541.323 56.7291 21.8862 + vertex 544.242 60.4428 22.4948 + endloop + endfacet + facet normal 0.0620036 -0.20868 0.976017 + outer loop + vertex 541.323 56.7291 21.8862 + vertex 553.161 59.9286 21.8182 + vertex 544.242 60.4428 22.4948 + endloop + endfacet + facet normal 0.0624304 -0.202856 0.977217 + outer loop + vertex 549.613 62.3183 22.541 + vertex 544.242 60.4428 22.4948 + vertex 553.161 59.9286 21.8182 + endloop + endfacet + facet normal 0.0644678 -0.19997 0.977679 + outer loop + vertex 549.613 62.3183 22.541 + vertex 553.161 59.9286 21.8182 + vertex 555.87 63.6065 22.3918 + endloop + endfacet + facet normal 0.0610758 -0.197581 0.978382 + outer loop + vertex 553.161 59.9286 21.8182 + vertex 564.95 63.1732 21.7375 + vertex 555.87 63.6065 22.3918 + endloop + endfacet + facet normal 0.0614131 -0.192123 0.979447 + outer loop + vertex 561.243 65.5041 22.4272 + vertex 555.87 63.6065 22.3918 + vertex 564.95 63.1732 21.7375 + endloop + endfacet + facet normal 0.063113 -0.189537 0.979843 + outer loop + vertex 561.243 65.5041 22.4272 + vertex 564.95 63.1732 21.7375 + vertex 567.573 66.8424 22.2783 + endloop + endfacet + facet normal 0.0594099 -0.186996 0.980563 + outer loop + vertex 564.95 63.1732 21.7375 + vertex 576.597 66.4106 21.6492 + vertex 567.573 66.8424 22.2783 + endloop + endfacet + facet normal 0.0598772 -0.179285 0.981973 + outer loop + vertex 572.985 68.7812 22.3023 + vertex 567.573 66.8424 22.2783 + vertex 576.597 66.4106 21.6492 + endloop + endfacet + facet normal 0.060478 -0.178403 0.982097 + outer loop + vertex 572.985 68.7812 22.3023 + vertex 576.597 66.4106 21.6492 + vertex 579.25 70.1186 22.1595 + endloop + endfacet + facet normal 0.0573669 -0.176257 0.982671 + outer loop + vertex 576.597 66.4106 21.6492 + vertex 587.514 69.4787 21.5622 + vertex 579.25 70.1186 22.1595 + endloop + endfacet + facet normal 0.0580105 -0.169085 0.983893 + outer loop + vertex 584.562 72.049 22.178 + vertex 579.25 70.1186 22.1595 + vertex 587.514 69.4787 21.5622 + endloop + endfacet + facet normal 0.0584768 -0.168565 0.983954 + outer loop + vertex 584.562 72.049 22.178 + vertex 587.514 69.4787 21.5622 + vertex 590.292 73.2528 22.0437 + endloop + endfacet + facet normal 0.0557776 -0.166639 0.984439 + outer loop + vertex 587.514 69.4787 21.5622 + vertex 596.561 72.1358 21.4994 + vertex 590.292 73.2528 22.0437 + endloop + endfacet + facet normal 0.0567153 -0.161748 0.985201 + outer loop + vertex 595.012 75.0349 22.0646 + vertex 590.292 73.2528 22.0437 + vertex 596.561 72.1358 21.4994 + endloop + endfacet + facet normal 0.0579583 -0.16109 0.985236 + outer loop + vertex 595.012 75.0349 22.0646 + vertex 596.561 72.1358 21.4994 + vertex 599.222 75.8643 21.9525 + endloop + endfacet + facet normal 0.0543766 -0.158608 0.985843 + outer loop + vertex 599.222 75.8643 21.9525 + vertex 596.561 72.1358 21.4994 + vertex 602.326 74.1226 21.5011 + endloop + endfacet + facet normal 0.055959 -0.155878 0.98619 + outer loop + vertex 602.216 77.1921 21.9925 + vertex 599.222 75.8643 21.9525 + vertex 602.326 74.1226 21.5011 + endloop + endfacet + facet normal 0.059403 -0.155726 0.986013 + outer loop + vertex 602.216 77.1921 21.9925 + vertex 602.326 74.1226 21.5011 + vertex 603.919 77.3945 21.9218 + endloop + endfacet + facet normal 0.0495731 -0.151102 0.987274 + outer loop + vertex 602.326 74.1226 21.5011 + vertex 604.599 75.379 21.5792 + vertex 603.919 77.3945 21.9218 + endloop + endfacet + facet normal 0.0485408 -0.15145 0.987272 + outer loop + vertex 604.654 78.0509 21.9864 + vertex 603.919 77.3945 21.9218 + vertex 604.599 75.379 21.5792 + endloop + endfacet + facet normal -0.0647305 -0.14902 0.986713 + outer loop + vertex 604.654 78.0509 21.9864 + vertex 604.599 75.379 21.5792 + vertex 604.839 77.6302 21.935 + endloop + endfacet + facet normal 0.0226624 -0.158403 0.987114 + outer loop + vertex 606.365 74.1372 21.3394 + vertex 604.839 77.6302 21.935 + vertex 604.599 75.379 21.5792 + endloop + endfacet + facet normal 0.0318318 -0.145696 0.988817 + outer loop + vertex 604.599 75.379 21.5792 + vertex 604.537 71.2998 20.9802 + vertex 606.365 74.1372 21.3394 + endloop + endfacet + facet normal 0.0466275 -0.145831 0.98821 + outer loop + vertex 602.326 74.1226 21.5011 + vertex 604.537 71.2998 20.9802 + vertex 604.599 75.379 21.5792 + endloop + endfacet + facet normal 0.0418766 -0.149491 0.987876 + outer loop + vertex 601.433 69.3222 20.8125 + vertex 604.537 71.2998 20.9802 + vertex 602.326 74.1226 21.5011 + endloop + endfacet + facet normal 0.055123 -0.169949 0.98391 + outer loop + vertex 601.433 69.3222 20.8125 + vertex 604.688 66.596 20.1593 + vertex 604.537 71.2998 20.9802 + endloop + endfacet + facet normal 0.045848 -0.180679 0.982473 + outer loop + vertex 601.405 64.6059 19.9465 + vertex 604.688 66.596 20.1593 + vertex 601.433 69.3222 20.8125 + endloop + endfacet + facet normal 0.0575881 -0.180637 0.981862 + outer loop + vertex 601.405 64.6059 19.9465 + vertex 601.433 69.3222 20.8125 + vertex 595.511 67.1818 20.766 + endloop + endfacet + facet normal 0.0549277 -0.186427 0.980932 + outer loop + vertex 595.511 67.1818 20.766 + vertex 595.219 62.493 19.8913 + vertex 601.405 64.6059 19.9465 + endloop + endfacet + facet normal 0.0581815 -0.18659 0.980714 + outer loop + vertex 586.626 64.5815 20.7985 + vertex 595.219 62.493 19.8913 + vertex 595.511 67.1818 20.766 + endloop + endfacet + facet normal 0.0512866 -0.162971 0.985297 + outer loop + vertex 586.626 64.5815 20.7985 + vertex 595.511 67.1818 20.766 + vertex 587.514 69.4787 21.5622 + endloop + endfacet + facet normal 0.0572195 -0.190265 0.980064 + outer loop + vertex 585.965 59.8434 19.9172 + vertex 595.219 62.493 19.8913 + vertex 586.626 64.5815 20.7985 + endloop + endfacet + facet normal 0.0580721 -0.190371 0.979993 + outer loop + vertex 575.751 61.5517 20.8543 + vertex 585.965 59.8434 19.9172 + vertex 586.626 64.5815 20.7985 + endloop + endfacet + facet normal 0.0524514 -0.170122 0.984026 + outer loop + vertex 575.751 61.5517 20.8543 + vertex 586.626 64.5815 20.7985 + vertex 576.597 66.4106 21.6492 + endloop + endfacet + facet normal 0.0571379 -0.195439 0.97905 + outer loop + vertex 574.805 56.726 19.9462 + vertex 585.965 59.8434 19.9172 + vertex 575.751 61.5517 20.8543 + endloop + endfacet + facet normal 0.0583822 -0.195661 0.978932 + outer loop + vertex 564.026 58.3022 20.9041 + vertex 574.805 56.726 19.9462 + vertex 575.751 61.5517 20.8543 + endloop + endfacet + facet normal 0.0535789 -0.178275 0.982521 + outer loop + vertex 564.026 58.3022 20.9041 + vertex 575.751 61.5517 20.8543 + vertex 564.95 63.1732 21.7375 + endloop + endfacet + facet normal 0.057629 -0.200272 0.978044 + outer loop + vertex 562.983 53.4345 19.9688 + vertex 574.805 56.726 19.9462 + vertex 564.026 58.3022 20.9041 + endloop + endfacet + facet normal 0.0585158 -0.200445 0.977956 + outer loop + vertex 552.069 55.0227 20.9473 + vertex 562.983 53.4345 19.9688 + vertex 564.026 58.3022 20.9041 + endloop + endfacet + facet normal 0.0546469 -0.186299 0.980972 + outer loop + vertex 552.069 55.0227 20.9473 + vertex 564.026 58.3022 20.9041 + vertex 553.161 59.9286 21.8182 + endloop + endfacet + facet normal 0.0577455 -0.205164 0.977023 + outer loop + vertex 550.994 50.1636 19.9905 + vertex 562.983 53.4345 19.9688 + vertex 552.069 55.0227 20.9473 + endloop + endfacet + facet normal 0.0582793 -0.205271 0.976968 + outer loop + vertex 540.127 51.8424 20.9915 + vertex 550.994 50.1636 19.9905 + vertex 552.069 55.0227 20.9473 + endloop + endfacet + facet normal 0.0549728 -0.192817 0.979694 + outer loop + vertex 540.127 51.8424 20.9915 + vertex 552.069 55.0227 20.9473 + vertex 541.323 56.7291 21.8862 + endloop + endfacet + facet normal 0.0574738 -0.209924 0.976027 + outer loop + vertex 539.162 47.0511 20.0178 + vertex 550.994 50.1636 19.9905 + vertex 540.127 51.8424 20.9915 + endloop + endfacet + facet normal 0.0580977 -0.210037 0.975966 + outer loop + vertex 528.86 48.9549 21.0408 + vertex 539.162 47.0511 20.0178 + vertex 540.127 51.8424 20.9915 + endloop + endfacet + facet normal 0.0548711 -0.197399 0.978786 + outer loop + vertex 528.86 48.9549 21.0408 + vertex 540.127 51.8424 20.9915 + vertex 529.55 53.6553 21.9501 + endloop + endfacet + facet normal 0.0574065 -0.213406 0.975276 + outer loop + vertex 528.251 44.2434 20.0457 + vertex 539.162 47.0511 20.0178 + vertex 528.86 48.9549 21.0408 + endloop + endfacet + facet normal 0.0583407 -0.21351 0.975197 + outer loop + vertex 519.586 46.5449 21.068 + vertex 528.251 44.2434 20.0457 + vertex 528.86 48.9549 21.0408 + endloop + endfacet + facet normal 0.0551838 -0.20133 0.977968 + outer loop + vertex 519.586 46.5449 21.068 + vertex 528.86 48.9549 21.0408 + vertex 519.129 51.0485 22.0209 + endloop + endfacet + facet normal 0.0573476 -0.216939 0.974499 + outer loop + vertex 519.29 41.7621 20.0207 + vertex 528.251 44.2434 20.0457 + vertex 519.586 46.5449 21.068 + endloop + endfacet + facet normal 0.0595473 -0.217042 0.974344 + outer loop + vertex 512.727 44.2679 20.98 + vertex 519.29 41.7621 20.0207 + vertex 519.586 46.5449 21.068 + endloop + endfacet + facet normal 0.0565306 -0.224375 0.972862 + outer loop + vertex 512.618 39.1607 19.8084 + vertex 519.29 41.7621 20.0207 + vertex 512.727 44.2679 20.98 + endloop + endfacet + facet normal 0.0676441 -0.252259 0.965293 + outer loop + vertex 512.618 39.1607 19.8084 + vertex 517.871 36.8235 18.8295 + vertex 519.29 41.7621 20.0207 + endloop + endfacet + facet normal 0.0650192 -0.251591 0.965647 + outer loop + vertex 517.871 36.8235 18.8295 + vertex 527.138 39.3759 18.8705 + vertex 519.29 41.7621 20.0207 + endloop + endfacet + facet normal 0.0651822 -0.257305 0.964129 + outer loop + vertex 512.08 34.872 18.7002 + vertex 517.871 36.8235 18.8295 + vertex 512.618 39.1607 19.8084 + endloop + endfacet + facet normal 0.0644154 -0.257228 0.964202 + outer loop + vertex 512.08 34.872 18.7002 + vertex 512.618 39.1607 19.8084 + vertex 507.658 35.3077 19.1118 + endloop + endfacet + facet normal 0.0660895 -0.248429 0.966393 + outer loop + vertex 519.29 41.7621 20.0207 + vertex 527.138 39.3759 18.8705 + vertex 528.251 44.2434 20.0457 + endloop + endfacet + facet normal 0.0652666 -0.248265 0.966491 + outer loop + vertex 527.138 39.3759 18.8705 + vertex 538.25 42.2572 18.8603 + vertex 528.251 44.2434 20.0457 + endloop + endfacet + facet normal 0.0657769 -0.246018 0.967031 + outer loop + vertex 528.251 44.2434 20.0457 + vertex 538.25 42.2572 18.8603 + vertex 539.162 47.0511 20.0178 + endloop + endfacet + facet normal 0.0658275 -0.246027 0.967025 + outer loop + vertex 538.25 42.2572 18.8603 + vertex 550.064 45.3591 18.8453 + vertex 539.162 47.0511 20.0178 + endloop + endfacet + facet normal 0.0662861 -0.243494 0.967635 + outer loop + vertex 539.162 47.0511 20.0178 + vertex 550.064 45.3591 18.8453 + vertex 550.994 50.1636 19.9905 + endloop + endfacet + facet normal 0.0669823 -0.243611 0.967557 + outer loop + vertex 550.064 45.3591 18.8453 + vertex 561.946 48.5867 18.8353 + vertex 550.994 50.1636 19.9905 + endloop + endfacet + facet normal 0.0674555 -0.240813 0.968225 + outer loop + vertex 550.994 50.1636 19.9905 + vertex 561.946 48.5867 18.8353 + vertex 562.983 53.4345 19.9688 + endloop + endfacet + facet normal 0.0675456 -0.24083 0.968214 + outer loop + vertex 561.946 48.5867 18.8353 + vertex 573.705 51.871 18.8319 + vertex 562.983 53.4345 19.9688 + endloop + endfacet + facet normal 0.068062 -0.237806 0.968925 + outer loop + vertex 562.983 53.4345 19.9688 + vertex 573.705 51.871 18.8319 + vertex 574.805 56.726 19.9462 + endloop + endfacet + facet normal 0.0678188 -0.237757 0.968954 + outer loop + vertex 573.705 51.871 18.8319 + vertex 585.187 55.1253 18.8268 + vertex 574.805 56.726 19.9462 + endloop + endfacet + facet normal 0.0682545 -0.235325 0.969517 + outer loop + vertex 574.805 56.726 19.9462 + vertex 585.187 55.1253 18.8268 + vertex 585.965 59.8434 19.9172 + endloop + endfacet + facet normal 0.0681992 -0.235317 0.969523 + outer loop + vertex 585.187 55.1253 18.8268 + vertex 595.365 58.0088 18.8107 + vertex 585.965 59.8434 19.9172 + endloop + endfacet + facet normal 0.0690249 -0.231592 0.970361 + outer loop + vertex 585.965 59.8434 19.9172 + vertex 595.365 58.0088 18.8107 + vertex 595.219 62.493 19.8913 + endloop + endfacet + facet normal 0.0704267 -0.231526 0.970276 + outer loop + vertex 595.219 62.493 19.8913 + vertex 595.365 58.0088 18.8107 + vertex 602.23 60.0924 18.8096 + endloop + endfacet + facet normal 0.0704275 -0.231524 0.970277 + outer loop + vertex 602.23 60.0924 18.8096 + vertex 601.405 64.6059 19.9465 + vertex 595.219 62.493 19.8913 + endloop + endfacet + facet normal 0.0605366 -0.233388 0.970497 + outer loop + vertex 602.23 60.0924 18.8096 + vertex 605.337 61.7171 19.0065 + vertex 601.405 64.6059 19.9465 + endloop + endfacet + facet normal 0.0705889 -0.220467 0.972837 + outer loop + vertex 601.405 64.6059 19.9465 + vertex 605.337 61.7171 19.0065 + vertex 604.688 66.596 20.1593 + endloop + endfacet + facet normal 0.03699 -0.225122 0.973628 + outer loop + vertex 604.688 66.596 20.1593 + vertex 605.337 61.7171 19.0065 + vertex 607.219 64.2499 19.5206 + endloop + endfacet + facet normal 0.0487804 -0.156372 0.986493 + outer loop + vertex 596.561 72.1358 21.4994 + vertex 595.511 67.1818 20.766 + vertex 601.433 69.3222 20.8125 + endloop + endfacet + facet normal 0.0518361 -0.151238 0.987137 + outer loop + vertex 601.433 69.3222 20.8125 + vertex 602.326 74.1226 21.5011 + vertex 596.561 72.1358 21.4994 + endloop + endfacet + facet normal 0.0530226 -0.157218 0.986139 + outer loop + vertex 587.514 69.4787 21.5622 + vertex 595.511 67.1818 20.766 + vertex 596.561 72.1358 21.4994 + endloop + endfacet + facet normal 0.0537699 -0.16339 0.985095 + outer loop + vertex 576.597 66.4106 21.6492 + vertex 586.626 64.5815 20.7985 + vertex 587.514 69.4787 21.5622 + endloop + endfacet + facet normal 0.0548518 -0.170508 0.983828 + outer loop + vertex 564.95 63.1732 21.7375 + vertex 575.751 61.5517 20.8543 + vertex 576.597 66.4106 21.6492 + endloop + endfacet + facet normal 0.0559005 -0.17868 0.982318 + outer loop + vertex 553.161 59.9286 21.8182 + vertex 564.026 58.3022 20.9041 + vertex 564.95 63.1732 21.7375 + endloop + endfacet + facet normal 0.0560613 -0.18659 0.980837 + outer loop + vertex 541.323 56.7291 21.8862 + vertex 552.069 55.0227 20.9473 + vertex 553.161 59.9286 21.8182 + endloop + endfacet + facet normal 0.0557037 -0.192982 0.97962 + outer loop + vertex 529.55 53.6553 21.9501 + vertex 540.127 51.8424 20.9915 + vertex 541.323 56.7291 21.8862 + endloop + endfacet + facet normal 0.0560683 -0.197555 0.978687 + outer loop + vertex 519.129 51.0485 22.0209 + vertex 528.86 48.9549 21.0408 + vertex 529.55 53.6553 21.9501 + endloop + endfacet + facet normal 0.0570378 -0.201128 0.977903 + outer loop + vertex 512.145 49.1433 22.0364 + vertex 519.586 46.5449 21.068 + vertex 519.129 51.0485 22.0209 + endloop + endfacet + facet normal 0.0555507 -0.205111 0.977161 + outer loop + vertex 512.727 44.2679 20.98 + vertex 519.586 46.5449 21.068 + vertex 512.145 49.1433 22.0364 + endloop + endfacet + facet normal 0.0610578 -0.224407 0.972581 + outer loop + vertex 512.618 39.1607 19.8084 + vertex 512.727 44.2679 20.98 + vertex 505.761 40.6922 20.5922 + endloop + endfacet + facet normal 0.0513728 -0.213254 0.975645 + outer loop + vertex 484.486 40.2894 21.6735 + vertex 485.043 36.2548 20.7623 + vertex 497.695 42.284 21.4139 + endloop + endfacet + facet normal 0.0500464 -0.213776 0.9756 + outer loop + vertex 466.277 36.1737 21.7057 + vertex 467.33 32.435 20.8325 + vertex 484.486 40.2894 21.6735 + endloop + endfacet + facet normal 0.0489622 -0.214103 0.975583 + outer loop + vertex 445.437 31.3804 21.6997 + vertex 446.405 27.646 20.8315 + vertex 466.277 36.1737 21.7057 + endloop + endfacet + facet normal 0.0476711 -0.216436 0.975132 + outer loop + vertex 445.142 35.0658 22.5321 + vertex 423.842 26.6204 21.6989 + vertex 445.437 31.3804 21.6997 + endloop + endfacet + facet normal 0.0466477 -0.213915 0.975738 + outer loop + vertex 423.782 30.4693 22.5455 + vertex 423.842 26.6204 21.6989 + vertex 445.142 35.0658 22.5321 + endloop + endfacet + facet normal 0.0436081 -0.211051 0.976502 + outer loop + vertex 402.545 26.0793 22.5451 + vertex 402.49 22.1659 21.7018 + vertex 423.782 30.4693 22.5455 + endloop + endfacet + facet normal 0.0448317 -0.227142 0.972829 + outer loop + vertex 402.595 29.8662 23.427 + vertex 381.663 21.9471 22.5427 + vertex 402.545 26.0793 22.5451 + endloop + endfacet + facet normal 0.0482149 -0.250205 0.966992 + outer loop + vertex 402.403 33.3992 24.3507 + vertex 381.796 25.7443 23.3975 + vertex 402.595 29.8662 23.427 + endloop + endfacet + facet normal 0.0497902 -0.268827 0.961901 + outer loop + vertex 401.964 36.5354 25.25 + vertex 381.684 29.2867 24.2739 + vertex 402.403 33.3992 24.3507 + endloop + endfacet + facet normal 0.043634 -0.252248 0.966678 + outer loop + vertex 381.389 32.4718 25.1183 + vertex 381.684 29.2867 24.2739 + vertex 401.964 36.5354 25.25 + endloop + endfacet + facet normal 0.0457415 -0.260789 0.964312 + outer loop + vertex 381.18 35.2433 25.8778 + vertex 360.554 28.5423 25.0439 + vertex 381.389 32.4718 25.1183 + endloop + endfacet + facet normal 0.0441526 -0.264315 0.963425 + outer loop + vertex 381.189 37.5167 26.501 + vertex 360.306 31.324 25.7591 + vertex 381.18 35.2433 25.8778 + endloop + endfacet + facet normal 0.0406728 -0.258386 0.965185 + outer loop + vertex 381.142 39.1129 26.9303 + vertex 360.283 33.5928 26.3316 + vertex 381.189 37.5167 26.501 + endloop + endfacet + facet normal 0.0346371 -0.235245 0.971319 + outer loop + vertex 380.516 39.901 27.1435 + vertex 360.352 35.2047 26.7252 + vertex 381.142 39.1129 26.9303 + endloop + endfacet + facet normal 0.0212927 -0.191304 0.9813 + outer loop + vertex 378.74 40.0039 27.2021 + vertex 380.516 39.901 27.1435 + vertex 398.632 43.896 27.5293 + endloop + endfacet +endsolid diff --git a/noether_examples/meshes/outputs/output_7.stl b/noether_examples/meshes/outputs/output_7.stl new file mode 100644 index 00000000..02adb43c --- /dev/null +++ b/noether_examples/meshes/outputs/output_7.stl @@ -0,0 +1,51270 @@ +solid ascii + facet normal 0.0281915 -0.134004 -0.99058 + outer loop + vertex 484.813 30.935 1.24497 + vertex 484.784 35.2426 0.661441 + vertex 498.389 35.1798 1.05711 + endloop + endfacet + facet normal 0.0283765 -0.111464 -0.993363 + outer loop + vertex 498.389 35.1798 1.05711 + vertex 484.784 35.2426 0.661441 + vertex 497.455 39.3847 0.558603 + endloop + endfacet + facet normal 0.0234215 -0.112565 -0.993368 + outer loop + vertex 498.389 35.1798 1.05711 + vertex 497.455 39.3847 0.558603 + vertex 506.446 39.1921 0.792429 + endloop + endfacet + facet normal 0.037704 -0.140978 -0.989294 + outer loop + vertex 506.446 39.1921 0.792429 + vertex 507.098 34.852 1.43578 + vertex 498.389 35.1798 1.05711 + endloop + endfacet + facet normal 0.0314634 -0.141929 -0.989377 + outer loop + vertex 507.098 34.852 1.43578 + vertex 506.446 39.1921 0.792429 + vertex 512.75 38.6877 1.06526 + endloop + endfacet + facet normal 0.0341927 -0.109962 -0.993347 + outer loop + vertex 512.185 43.0549 0.562369 + vertex 512.75 38.6877 1.06526 + vertex 506.446 39.1921 0.792429 + endloop + endfacet + facet normal 0.0126738 -0.0781996 -0.996857 + outer loop + vertex 506.446 39.1921 0.792429 + vertex 505.257 44.4048 0.368389 + vertex 512.185 43.0549 0.562369 + endloop + endfacet + facet normal 0.0153286 -0.0647071 -0.997787 + outer loop + vertex 512.258 46.7952 0.320928 + vertex 512.185 43.0549 0.562369 + vertex 505.257 44.4048 0.368389 + endloop + endfacet + facet normal 0.00665997 -0.0393457 -0.999203 + outer loop + vertex 510.4 49.7361 0.192737 + vertex 512.258 46.7952 0.320928 + vertex 505.257 44.4048 0.368389 + endloop + endfacet + facet normal 0.00767873 -0.0403269 -0.999157 + outer loop + vertex 505.257 44.4048 0.368389 + vertex 504.043 49.4915 0.153757 + vertex 510.4 49.7361 0.192737 + endloop + endfacet + facet normal 0.00710994 -0.0254705 -0.99965 + outer loop + vertex 508.919 53.6845 0.0816009 + vertex 510.4 49.7361 0.192737 + vertex 504.043 49.4915 0.153757 + endloop + endfacet + facet normal 0.00475198 -0.0227298 -0.99973 + outer loop + vertex 504.043 49.4915 0.153757 + vertex 502.518 53.5924 0.0532711 + vertex 508.919 53.6845 0.0816009 + endloop + endfacet + facet normal 0.00462646 -0.0139615 -0.999892 + outer loop + vertex 507.164 57.4791 0.020499 + vertex 508.919 53.6845 0.0816009 + vertex 502.518 53.5924 0.0532711 + endloop + endfacet + facet normal 0.00215311 -0.0110051 -0.999937 + outer loop + vertex 502.518 53.5924 0.0532711 + vertex 500.571 57.3225 0.00802684 + vertex 507.164 57.4791 0.020499 + endloop + endfacet + facet normal 0.00201813 -0.00532153 -0.999984 + outer loop + vertex 504.979 60.968 -0.0024776 + vertex 507.164 57.4791 0.020499 + vertex 500.571 57.3225 0.00802684 + endloop + endfacet + facet normal 0.000460112 -0.00343778 -0.999994 + outer loop + vertex 500.571 57.3225 0.00802684 + vertex 498.195 60.7548 -0.00486613 + vertex 504.979 60.968 -0.0024776 + endloop + endfacet + facet normal 0.000371783 -0.000626633 -1 + outer loop + vertex 502.318 64.1366 -0.00545239 + vertex 504.979 60.968 -0.0024776 + vertex 498.195 60.7548 -0.00486613 + endloop + endfacet + facet normal -0.000169318 3.30779e-05 -1 + outer loop + vertex 498.195 60.7548 -0.00486613 + vertex 495.153 63.9526 -0.00424526 + vertex 502.318 64.1366 -0.00545239 + endloop + endfacet + facet normal -0.000186921 0.000718629 -1 + outer loop + vertex 499.269 67.0107 -0.00281699 + vertex 502.318 64.1366 -0.00545239 + vertex 495.153 63.9526 -0.00424526 + endloop + endfacet + facet normal -0.000130244 0.000642349 -1 + outer loop + vertex 495.153 63.9526 -0.00424526 + vertex 490.703 67.312 -0.00150783 + vertex 499.269 67.0107 -0.00281699 + endloop + endfacet + facet normal -0.000131191 0.000615437 -1 + outer loop + vertex 497.289 69.3526 -0.00111599 + vertex 499.269 67.0107 -0.00281699 + vertex 490.703 67.312 -0.00150783 + endloop + endfacet + facet normal -1.20551e-05 0.000230927 -1 + outer loop + vertex 493.666 70.8552 -0.000725335 + vertex 497.289 69.3526 -0.00111599 + vertex 490.703 67.312 -0.00150783 + endloop + endfacet + facet normal -2.71035e-05 0.00024351 -1 + outer loop + vertex 490.703 67.312 -0.00150783 + vertex 486.467 70.2601 -0.000675126 + vertex 493.666 70.8552 -0.000725335 + endloop + endfacet + facet normal -1.09319e-05 4.78721e-05 -1 + outer loop + vertex 490.188 72.8465 -0.000591988 + vertex 493.666 70.8552 -0.000725335 + vertex 486.467 70.2601 -0.000675126 + endloop + endfacet + facet normal -1.3108e-05 5.10028e-05 -1 + outer loop + vertex 486.467 70.2601 -0.000675126 + vertex 482.637 72.7985 -0.000495455 + vertex 490.188 72.8465 -0.000591988 + endloop + endfacet + facet normal -1.29778e-05 3.054e-05 -1 + outer loop + vertex 487.912 74.5677 -0.000509883 + vertex 490.188 72.8465 -0.000591988 + vertex 482.637 72.7985 -0.000495455 + endloop + endfacet + facet normal -2.19975e-05 5.74338e-05 -1 + outer loop + vertex 483.926 75.5988 -0.000362971 + vertex 487.912 74.5677 -0.000509883 + vertex 482.637 72.7985 -0.000495455 + endloop + endfacet + facet normal -1.49729e-05 5.42013e-05 -1 + outer loop + vertex 482.637 72.7985 -0.000495455 + vertex 475.942 74.6234 -0.000296295 + vertex 483.926 75.5988 -0.000362971 + endloop + endfacet + facet normal -1.65101e-05 6.67844e-05 -1 + outer loop + vertex 480.104 77.1986 -0.000193036 + vertex 483.926 75.5988 -0.000362971 + vertex 475.942 74.6234 -0.000296295 + endloop + endfacet + facet normal -1.08808e-05 5.76853e-05 -1 + outer loop + vertex 475.942 74.6234 -0.000296295 + vertex 472.612 77.0867 -0.000117973 + vertex 480.104 77.1986 -0.000193036 + endloop + endfacet + facet normal -1.081e-05 5.29472e-05 -1 + outer loop + vertex 478.087 78.7559 -8.87765e-05 + vertex 480.104 77.1986 -0.000193036 + vertex 472.612 77.0867 -0.000117973 + endloop + endfacet + facet normal -4.44965e-06 3.20858e-05 -1 + outer loop + vertex 474.599 79.6605 -4.42277e-05 + vertex 478.087 78.7559 -8.87765e-05 + vertex 472.612 77.0867 -0.000117973 + endloop + endfacet + facet normal -5.73849e-06 3.30804e-05 -1 + outer loop + vertex 472.612 77.0867 -0.000117973 + vertex 467.143 78.5781 -3.72542e-05 + vertex 474.599 79.6605 -4.42277e-05 + endloop + endfacet + facet normal -3.21722e-06 1.57156e-05 -1 + outer loop + vertex 470.833 80.7297 -1.5309e-05 + vertex 474.599 79.6605 -4.42277e-05 + vertex 467.143 78.5781 -3.72542e-05 + endloop + endfacet + facet normal -2.12654e-06 1.38456e-05 -1 + outer loop + vertex 467.143 78.5781 -3.72542e-05 + vertex 463.204 80.6637 9.62153e-15 + vertex 470.833 80.7297 -1.5309e-05 + endloop + endfacet + facet normal -2.07792e-06 8.2234e-06 -1 + outer loop + vertex 463.204 80.6637 9.62153e-15 + vertex 471.785 82.832 9.62153e-15 + vertex 470.833 80.7297 -1.5309e-05 + endloop + endfacet + facet normal -1.80251e-06 8.09861e-06 -1 + outer loop + vertex 477.448 82.2531 -1.48955e-05 + vertex 470.833 80.7297 -1.5309e-05 + vertex 471.785 82.832 9.62153e-15 + endloop + endfacet + facet normal -1.88273e-06 7.31395e-06 -1 + outer loop + vertex 471.785 82.832 9.62153e-15 + vertex 482.011 85.4642 9.62153e-15 + vertex 477.448 82.2531 -1.48955e-05 + endloop + endfacet + facet normal -2.02769e-06 7.51993e-06 -1 + outer loop + vertex 477.448 82.2531 -1.48955e-05 + vertex 482.011 85.4642 9.62153e-15 + vertex 485.527 84.3248 -1.56985e-05 + endloop + endfacet + facet normal -3.70157e-06 1.40477e-05 -1 + outer loop + vertex 477.448 82.2531 -1.48955e-05 + vertex 485.527 84.3248 -1.56985e-05 + vertex 480.627 81.0487 -4.35821e-05 + endloop + endfacet + facet normal -3.3447e-06 1.49897e-05 -1 + outer loop + vertex 474.599 79.6605 -4.42277e-05 + vertex 477.448 82.2531 -1.48955e-05 + vertex 480.627 81.0487 -4.35821e-05 + endloop + endfacet + facet normal -5.01002e-06 1.60047e-05 -1 + outer loop + vertex 480.627 81.0487 -4.35821e-05 + vertex 485.527 84.3248 -1.56985e-05 + vertex 488.041 82.9228 -5.07319e-05 + endloop + endfacet + facet normal -8.86291e-06 3.12469e-05 -1 + outer loop + vertex 480.627 81.0487 -4.35821e-05 + vertex 488.041 82.9228 -5.07319e-05 + vertex 483.349 79.696 -0.000109978 + endloop + endfacet + facet normal -9.41355e-06 3.01386e-05 -1 + outer loop + vertex 478.087 78.7559 -8.87765e-05 + vertex 480.627 81.0487 -4.35821e-05 + vertex 483.349 79.696 -0.000109978 + endloop + endfacet + facet normal -1.17897e-05 3.55023e-05 -1 + outer loop + vertex 483.349 79.696 -0.000109978 + vertex 488.041 82.9228 -5.07319e-05 + vertex 491.087 81.6078 -0.00013333 + endloop + endfacet + facet normal -1.6698e-05 5.5368e-05 -1 + outer loop + vertex 483.349 79.696 -0.000109978 + vertex 491.087 81.6078 -0.00013333 + vertex 486.549 78.3062 -0.000240353 + endloop + endfacet + facet normal -1.6813e-05 5.51034e-05 -1 + outer loop + vertex 480.104 77.1986 -0.000193036 + vertex 483.349 79.696 -0.000109978 + vertex 486.549 78.3062 -0.000240353 + endloop + endfacet + facet normal -2.1544e-05 6.20291e-05 -1 + outer loop + vertex 486.549 78.3062 -0.000240353 + vertex 491.087 81.6078 -0.00013333 + vertex 494.693 80.3688 -0.000287876 + endloop + endfacet + facet normal -2.39716e-05 7.16148e-05 -1 + outer loop + vertex 486.549 78.3062 -0.000240353 + vertex 494.693 80.3688 -0.000287876 + vertex 490.203 77.0038 -0.000421218 + endloop + endfacet + facet normal -2.47932e-05 6.93096e-05 -1 + outer loop + vertex 483.926 75.5988 -0.000362971 + vertex 486.549 78.3062 -0.000240353 + vertex 490.203 77.0038 -0.000421218 + endloop + endfacet + facet normal -2.90878e-05 7.84419e-05 -1 + outer loop + vertex 490.203 77.0038 -0.000421218 + vertex 494.693 80.3688 -0.000287876 + vertex 498.369 79.0914 -0.000495 + endloop + endfacet + facet normal -2.36143e-05 5.70309e-05 -1 + outer loop + vertex 490.203 77.0038 -0.000421218 + vertex 498.369 79.0914 -0.000495 + vertex 493.581 75.61 -0.000580487 + endloop + endfacet + facet normal -2.31479e-05 5.81615e-05 -1 + outer loop + vertex 487.912 74.5677 -0.000509883 + vertex 490.203 77.0038 -0.000421218 + vertex 493.581 75.61 -0.000580487 + endloop + endfacet + facet normal -2.3994e-05 5.75529e-05 -1 + outer loop + vertex 493.581 75.61 -0.000580487 + vertex 498.369 79.0914 -0.000495 + vertex 501.833 77.6627 -0.000660342 + endloop + endfacet + facet normal -1.26575e-05 1.19801e-05 -1 + outer loop + vertex 493.581 75.61 -0.000580487 + vertex 501.833 77.6627 -0.000660342 + vertex 496.821 73.9729 -0.000641101 + endloop + endfacet + facet normal -1.02493e-05 1.6745e-05 -1 + outer loop + vertex 490.188 72.8465 -0.000591988 + vertex 493.581 75.61 -0.000580487 + vertex 496.821 73.9729 -0.000641101 + endloop + endfacet + facet normal -8.67624e-06 6.57179e-06 -1 + outer loop + vertex 496.821 73.9729 -0.000641101 + vertex 501.833 77.6627 -0.000660342 + vertex 505.185 76.0729 -0.000699877 + endloop + endfacet + facet normal -1.37927e-05 2.69525e-05 -1 + outer loop + vertex 496.821 73.9729 -0.000641101 + vertex 505.185 76.0729 -0.000699877 + vertex 500.162 72.2389 -0.000733923 + endloop + endfacet + facet normal -9.02164e-06 3.61461e-05 -1 + outer loop + vertex 493.666 70.8552 -0.000725335 + vertex 496.821 73.9729 -0.000641101 + vertex 500.162 72.2389 -0.000733923 + endloop + endfacet + facet normal -2.69003e-05 4.4127e-05 -1 + outer loop + vertex 500.162 72.2389 -0.000733923 + vertex 505.185 76.0729 -0.000699877 + vertex 508.437 74.2983 -0.000865658 + endloop + endfacet + facet normal -8.6619e-05 0.000284098 -1 + outer loop + vertex 500.162 72.2389 -0.000733923 + vertex 508.437 74.2983 -0.000865658 + vertex 503.232 70.2824 -0.00155571 + endloop + endfacet + facet normal -0.000112165 0.000244008 -1 + outer loop + vertex 497.289 69.3526 -0.00111599 + vertex 500.162 72.2389 -0.000733923 + vertex 503.232 70.2824 -0.00155571 + endloop + endfacet + facet normal -0.000158612 0.000377408 -1 + outer loop + vertex 503.232 70.2824 -0.00155571 + vertex 508.437 74.2983 -0.000865658 + vertex 511.646 72.278 -0.002137 + endloop + endfacet + facet normal -0.000245338 0.000743035 -1 + outer loop + vertex 503.232 70.2824 -0.00155571 + vertex 511.646 72.278 -0.002137 + vertex 506.167 67.8961 -0.0040488 + endloop + endfacet + facet normal -0.000270041 0.000712658 -1 + outer loop + vertex 499.269 67.0107 -0.00281699 + vertex 503.232 70.2824 -0.00155571 + vertex 506.167 67.8961 -0.0040488 + endloop + endfacet + facet normal -0.00034479 0.000867382 -1 + outer loop + vertex 506.167 67.8961 -0.0040488 + vertex 511.646 72.278 -0.002137 + vertex 514.692 69.9104 -0.00524107 + endloop + endfacet + facet normal -0.000279279 0.000590117 -1 + outer loop + vertex 506.167 67.8961 -0.0040488 + vertex 514.692 69.9104 -0.00524107 + vertex 509.059 65.1298 -0.00648902 + endloop + endfacet + facet normal -0.000245868 0.000625053 -1 + outer loop + vertex 502.318 64.1366 -0.00545239 + vertex 506.167 67.8961 -0.0040488 + vertex 509.059 65.1298 -0.00648902 + endloop + endfacet + facet normal -0.000280549 0.000591615 -1 + outer loop + vertex 509.059 65.1298 -0.00648902 + vertex 514.692 69.9104 -0.00524107 + vertex 517.516 67.1856 -0.00764539 + endloop + endfacet + facet normal 0.000258513 -0.00162595 -0.999999 + outer loop + vertex 509.059 65.1298 -0.00648902 + vertex 517.516 67.1856 -0.00764539 + vertex 511.543 61.9921 -0.000745221 + endloop + endfacet + facet normal 0.000489132 -0.00144342 -0.999999 + outer loop + vertex 504.979 60.968 -0.0024776 + vertex 509.059 65.1298 -0.00648902 + vertex 511.543 61.9921 -0.000745221 + endloop + endfacet + facet normal 0.000500952 -0.0019048 -0.999998 + outer loop + vertex 511.543 61.9921 -0.000745221 + vertex 517.516 67.1856 -0.00764539 + vertex 519.991 64.0936 -0.00051588 + endloop + endfacet + facet normal 0.00182309 -0.00722007 -0.999972 + outer loop + vertex 511.543 61.9921 -0.000745221 + vertex 519.991 64.0936 -0.00051588 + vertex 513.617 58.5193 0.0281119 + endloop + endfacet + facet normal 0.00229771 -0.00693655 -0.999973 + outer loop + vertex 507.164 57.4791 0.020499 + vertex 511.543 61.9921 -0.000745221 + vertex 513.617 58.5193 0.0281119 + endloop + endfacet + facet normal 0.00207768 -0.00751116 -0.99997 + outer loop + vertex 513.617 58.5193 0.0281119 + vertex 519.991 64.0936 -0.00051588 + vertex 522.084 60.6664 0.0295745 + endloop + endfacet + facet normal 0.00415368 -0.0156969 -0.999868 + outer loop + vertex 513.617 58.5193 0.0281119 + vertex 522.084 60.6664 0.0295745 + vertex 515.32 54.8094 0.0934255 + endloop + endfacet + facet normal 0.00457161 -0.0155051 -0.999869 + outer loop + vertex 508.919 53.6845 0.0816009 + vertex 513.617 58.5193 0.0281119 + vertex 515.32 54.8094 0.0934255 + endloop + endfacet + facet normal 0.00393013 -0.0154388 -0.999873 + outer loop + vertex 515.32 54.8094 0.0934255 + vertex 522.084 60.6664 0.0295745 + vertex 523.801 57.0143 0.0927167 + endloop + endfacet + facet normal 0.00658921 -0.025667 -0.999649 + outer loop + vertex 515.32 54.8094 0.0934255 + vertex 523.801 57.0143 0.0927167 + vertex 516.774 51.137 0.197301 + endloop + endfacet + facet normal 0.00637531 -0.0257516 -0.999648 + outer loop + vertex 510.4 49.7361 0.192737 + vertex 515.32 54.8094 0.0934255 + vertex 516.774 51.137 0.197301 + endloop + endfacet + facet normal 0.00651928 -0.0255834 -0.999651 + outer loop + vertex 516.774 51.137 0.197301 + vertex 523.801 57.0143 0.0927167 + vertex 525.172 53.2471 0.19807 + endloop + endfacet + facet normal 0.0105361 -0.0415714 -0.99908 + outer loop + vertex 516.774 51.137 0.197301 + vertex 525.172 53.2471 0.19807 + vertex 517.852 47.465 0.361468 + endloop + endfacet + facet normal 0.0121595 -0.0410946 -0.999081 + outer loop + vertex 512.258 46.7952 0.320928 + vertex 516.774 51.137 0.197301 + vertex 517.852 47.465 0.361468 + endloop + endfacet + facet normal 0.0122673 -0.0437598 -0.998967 + outer loop + vertex 517.852 47.465 0.361468 + vertex 525.172 53.2471 0.19807 + vertex 526.389 49.4319 0.380133 + endloop + endfacet + facet normal 0.0193024 -0.0743098 -0.997048 + outer loop + vertex 517.852 47.465 0.361468 + vertex 526.389 49.4319 0.380133 + vertex 518.747 43.571 0.669013 + endloop + endfacet + facet normal 0.0219979 -0.0736896 -0.997039 + outer loop + vertex 512.185 43.0549 0.562369 + vertex 517.852 47.465 0.361468 + vertex 518.747 43.571 0.669013 + endloop + endfacet + facet normal 0.0224532 -0.0783991 -0.996669 + outer loop + vertex 518.747 43.571 0.669013 + vertex 526.389 49.4319 0.380133 + vertex 527.536 45.5084 0.714603 + endloop + endfacet + facet normal 0.0339478 -0.130678 -0.990844 + outer loop + vertex 518.747 43.571 0.669013 + vertex 527.536 45.5084 0.714603 + vertex 519.518 39.3254 1.25534 + endloop + endfacet + facet normal 0.0400345 -0.129562 -0.990763 + outer loop + vertex 512.75 38.6877 1.06526 + vertex 518.747 43.571 0.669013 + vertex 519.518 39.3254 1.25534 + endloop + endfacet + facet normal 0.0371254 -0.134741 -0.990185 + outer loop + vertex 519.518 39.3254 1.25534 + vertex 527.536 45.5084 0.714603 + vertex 528.835 41.4761 1.31203 + endloop + endfacet + facet normal 0.0357932 -0.135169 -0.990176 + outer loop + vertex 527.536 45.5084 0.714603 + vertex 538.501 48.3958 0.7168 + vertex 528.835 41.4761 1.31203 + endloop + endfacet + facet normal 0.0368599 -0.136638 -0.989935 + outer loop + vertex 528.835 41.4761 1.31203 + vertex 538.501 48.3958 0.7168 + vertex 540.129 44.4659 1.31987 + endloop + endfacet + facet normal 0.0368558 -0.13664 -0.989935 + outer loop + vertex 538.501 48.3958 0.7168 + vertex 550.544 51.7258 0.705559 + vertex 540.129 44.4659 1.31987 + endloop + endfacet + facet normal 0.0371157 -0.137008 -0.989874 + outer loop + vertex 540.129 44.4659 1.31987 + vertex 550.544 51.7258 0.705559 + vertex 552.154 47.775 1.31275 + endloop + endfacet + facet normal 0.0378321 -0.136718 -0.989887 + outer loop + vertex 550.544 51.7258 0.705559 + vertex 562.826 55.199 0.695241 + vertex 552.154 47.775 1.31275 + endloop + endfacet + facet normal 0.0373635 -0.136053 -0.989997 + outer loop + vertex 552.154 47.775 1.31275 + vertex 562.826 55.199 0.695241 + vertex 564.271 51.1735 1.30299 + endloop + endfacet + facet normal 0.0376026 -0.135968 -0.989999 + outer loop + vertex 562.826 55.199 0.695241 + vertex 574.843 58.5672 0.689075 + vertex 564.271 51.1735 1.30299 + endloop + endfacet + facet normal 0.0379503 -0.136458 -0.989919 + outer loop + vertex 564.271 51.1735 1.30299 + vertex 574.843 58.5672 0.689075 + vertex 576.113 54.4642 1.30337 + endloop + endfacet + facet normal 0.037048 -0.136737 -0.989914 + outer loop + vertex 574.843 58.5672 0.689075 + vertex 585.666 61.3097 0.715328 + vertex 576.113 54.4642 1.30337 + endloop + endfacet + facet normal 0.0401618 -0.14102 -0.989192 + outer loop + vertex 576.113 54.4642 1.30337 + vertex 585.666 61.3097 0.715328 + vertex 586.98 57.3274 1.33638 + endloop + endfacet + facet normal 0.0371357 -0.142015 -0.989168 + outer loop + vertex 585.666 61.3097 0.715328 + vertex 593.52 62.81 0.79479 + vertex 586.98 57.3274 1.33638 + endloop + endfacet + facet normal 0.0477585 -0.154458 -0.986844 + outer loop + vertex 586.98 57.3274 1.33638 + vertex 593.52 62.81 0.79479 + vertex 596.71 59.819 1.41729 + endloop + endfacet + facet normal 0.0554655 -0.146411 -0.987668 + outer loop + vertex 596.71 59.819 1.41729 + vertex 593.52 62.81 0.79479 + vertex 599.882 66.2469 0.642567 + endloop + endfacet + facet normal 0.0253161 -0.131926 -0.990936 + outer loop + vertex 599.882 66.2469 0.642567 + vertex 602.347 63.0779 1.12745 + vertex 596.71 59.819 1.41729 + endloop + endfacet + facet normal 0.0302943 -0.128109 -0.991297 + outer loop + vertex 599.882 66.2469 0.642567 + vertex 603.912 66.8304 0.690325 + vertex 602.347 63.0779 1.12745 + endloop + endfacet + facet normal 0.0459729 -0.134481 -0.989849 + outer loop + vertex 602.347 63.0779 1.12745 + vertex 603.912 66.8304 0.690325 + vertex 604.987 62.684 1.30359 + endloop + endfacet + facet normal 0.0349836 -0.137338 -0.989906 + outer loop + vertex 604.987 62.684 1.30359 + vertex 603.912 66.8304 0.690325 + vertex 606.481 66.6559 0.805322 + endloop + endfacet + facet normal 0.0527416 -0.143804 -0.9882 + outer loop + vertex 606.481 66.6559 0.805322 + vertex 607.273 62.3069 1.48044 + vertex 604.987 62.684 1.30359 + endloop + endfacet + facet normal 0.0239894 -0.0841626 -0.996163 + outer loop + vertex 599.882 66.2469 0.642567 + vertex 602.729 70.0476 0.39002 + vertex 603.912 66.8304 0.690325 + endloop + endfacet + facet normal 0.0365788 -0.0795315 -0.996161 + outer loop + vertex 603.912 66.8304 0.690325 + vertex 602.729 70.0476 0.39002 + vertex 605.003 71.221 0.379833 + endloop + endfacet + facet normal 0.0391405 -0.0801573 -0.996013 + outer loop + vertex 605.003 71.221 0.379833 + vertex 606.481 66.6559 0.805322 + vertex 603.912 66.8304 0.690325 + endloop + endfacet + facet normal 0.019282 -0.0865931 -0.996057 + outer loop + vertex 606.481 66.6559 0.805322 + vertex 605.003 71.221 0.379833 + vertex 609.452 71.0422 0.481519 + endloop + endfacet + facet normal 0.0207007 -0.0526267 -0.9984 + outer loop + vertex 608.049 75.2089 0.232782 + vertex 609.452 71.0422 0.481519 + vertex 605.003 71.221 0.379833 + endloop + endfacet + facet normal 0.00801802 -0.0429635 -0.999044 + outer loop + vertex 605.003 71.221 0.379833 + vertex 603.639 75.9322 0.166284 + vertex 608.049 75.2089 0.232782 + endloop + endfacet + facet normal 0.010454 -0.0281605 -0.999549 + outer loop + vertex 606.538 79.1557 0.105789 + vertex 608.049 75.2089 0.232782 + vertex 603.639 75.9322 0.166284 + endloop + endfacet + facet normal 0.00337408 -0.0217972 -0.999757 + outer loop + vertex 603.639 75.9322 0.166284 + vertex 601.744 80.415 0.062151 + vertex 606.538 79.1557 0.105789 + endloop + endfacet + facet normal 0.00447537 -0.0176072 -0.999835 + outer loop + vertex 605.68 82.4335 0.0442283 + vertex 606.538 79.1557 0.105789 + vertex 601.744 80.415 0.062151 + endloop + endfacet + facet normal 0.00119585 -0.0112115 -0.999936 + outer loop + vertex 603.093 84.7584 0.0150658 + vertex 605.68 82.4335 0.0442283 + vertex 601.744 80.415 0.062151 + endloop + endfacet + facet normal 0.00203706 -0.0114728 -0.999932 + outer loop + vertex 601.744 80.415 0.062151 + vertex 598.646 84.2093 0.0123065 + vertex 603.093 84.7584 0.0150658 + endloop + endfacet + facet normal 0.00126795 -0.00524381 -0.999985 + outer loop + vertex 600.397 87.7812 -0.00420325 + vertex 603.093 84.7584 0.0150658 + vertex 598.646 84.2093 0.0123065 + endloop + endfacet + facet normal 0.00069433 -0.00496258 -0.999987 + outer loop + vertex 598.646 84.2093 0.0123065 + vertex 595.813 87.5797 -0.0063863 + vertex 600.397 87.7812 -0.00420325 + endloop + endfacet + facet normal 0.000519195 -0.000977377 -0.999999 + outer loop + vertex 597.767 90.6449 -0.008368 + vertex 600.397 87.7812 -0.00420325 + vertex 595.813 87.5797 -0.0063863 + endloop + endfacet + facet normal -0.000108476 -0.000577383 -1 + outer loop + vertex 595.813 87.5797 -0.0063863 + vertex 592.647 90.9683 -0.0079993 + vertex 597.767 90.6449 -0.008368 + endloop + endfacet + facet normal -2.10365e-05 0.000807143 -1 + outer loop + vertex 596.01 92.9615 -0.00646122 + vertex 597.767 90.6449 -0.008368 + vertex 592.647 90.9683 -0.0079993 + endloop + endfacet + facet normal -0.000162344 0.00104561 -0.999999 + outer loop + vertex 592.662 94.2979 -0.00452027 + vertex 596.01 92.9615 -0.00646122 + vertex 592.647 90.9683 -0.0079993 + endloop + endfacet + facet normal -0.00010363 0.00104534 -0.999999 + outer loop + vertex 592.647 90.9683 -0.0079993 + vertex 587.823 93.5972 -0.00475128 + vertex 592.662 94.2979 -0.00452027 + endloop + endfacet + facet normal -7.3673e-05 0.000838463 -1 + outer loop + vertex 589.194 96.1851 -0.00268244 + vertex 592.662 94.2979 -0.00452027 + vertex 587.823 93.5972 -0.00475128 + endloop + endfacet + facet normal -3.63537e-05 0.000818695 -1 + outer loop + vertex 587.823 93.5972 -0.00475128 + vertex 583.335 96.3876 -0.00230365 + vertex 589.194 96.1851 -0.00268244 + endloop + endfacet + facet normal -4.87516e-05 0.000460076 -1 + outer loop + vertex 587.035 97.8208 -0.00182464 + vertex 589.194 96.1851 -0.00268244 + vertex 583.335 96.3876 -0.00230365 + endloop + endfacet + facet normal -5.89497e-06 0.00034943 -1 + outer loop + vertex 583.515 98.7628 -0.00147475 + vertex 587.035 97.8208 -0.00182464 + vertex 583.335 96.3876 -0.00230365 + endloop + endfacet + facet normal -1.84076e-05 0.000350376 -1 + outer loop + vertex 583.335 96.3876 -0.00230365 + vertex 577.299 98.5545 -0.00143332 + vertex 583.515 98.7628 -0.00147475 + endloop + endfacet + facet normal -1.60041e-05 0.000278656 -1 + outer loop + vertex 581.022 100.051 -0.00107588 + vertex 583.515 98.7628 -0.00147475 + vertex 577.299 98.5545 -0.00143332 + endloop + endfacet + facet normal -1.89472e-05 0.000285978 -1 + outer loop + vertex 577.389 100.843 -0.0007805 + vertex 581.022 100.051 -0.00107588 + vertex 577.299 98.5545 -0.00143332 + endloop + endfacet + facet normal -1.87218e-05 0.000285969 -1 + outer loop + vertex 577.299 98.5545 -0.00143332 + vertex 571.405 100.593 -0.00074007 + vertex 577.389 100.843 -0.0007805 + endloop + endfacet + facet normal -1.6757e-05 0.000239015 -1 + outer loop + vertex 574.791 102.019 -0.000455891 + vertex 577.389 100.843 -0.0007805 + vertex 571.405 100.593 -0.00074007 + endloop + endfacet + facet normal -6.1451e-06 0.000213823 -1 + outer loop + vertex 571.078 102.664 -0.000295103 + vertex 574.791 102.019 -0.000455891 + vertex 571.405 100.593 -0.00074007 + endloop + endfacet + facet normal -1.67623e-05 0.00021215 -1 + outer loop + vertex 571.405 100.593 -0.00074007 + vertex 565.028 102.192 -0.000294006 + vertex 571.078 102.664 -0.000295103 + endloop + endfacet + facet normal -1.0133e-05 0.000127329 -1 + outer loop + vertex 568.3 103.669 -0.000139081 + vertex 571.078 102.664 -0.000295103 + vertex 565.028 102.192 -0.000294006 + endloop + endfacet + facet normal -7.42865e-09 0.000104902 -1 + outer loop + vertex 564.607 104.217 -8.15806e-05 + vertex 568.3 103.669 -0.000139081 + vertex 565.028 102.192 -0.000294006 + endloop + endfacet + facet normal -6.8107e-06 0.000103486 -1 + outer loop + vertex 565.028 102.192 -0.000294006 + vertex 559.428 103.938 -7.5108e-05 + vertex 564.607 104.217 -8.15806e-05 + endloop + endfacet + facet normal -3.47747e-06 4.14557e-05 -1 + outer loop + vertex 562.336 105.267 -3.01433e-05 + vertex 564.607 104.217 -8.15806e-05 + vertex 559.428 103.938 -7.5108e-05 + endloop + endfacet + facet normal 1.5857e-06 3.03736e-05 -1 + outer loop + vertex 559.825 105.853 -1.63296e-05 + vertex 562.336 105.267 -3.01433e-05 + vertex 559.428 103.938 -7.5108e-05 + endloop + endfacet + facet normal -4.93651e-06 3.17249e-05 -1 + outer loop + vertex 559.428 103.938 -7.5108e-05 + vertex 552.55 105.235 9.62153e-15 + vertex 559.825 105.853 -1.63296e-05 + endloop + endfacet + facet normal -3.10641e-06 1.01566e-05 -1 + outer loop + vertex 552.55 105.235 9.62153e-15 + vertex 562.338 108.229 9.62153e-15 + vertex 559.825 105.853 -1.63296e-05 + endloop + endfacet + facet normal -1.12064e-06 8.05669e-06 -1 + outer loop + vertex 565.593 107.64 -8.39019e-06 + vertex 559.825 105.853 -1.63296e-05 + vertex 562.338 108.229 9.62153e-15 + endloop + endfacet + facet normal -1.63507e-06 5.21179e-06 -1 + outer loop + vertex 562.338 108.229 9.62153e-15 + vertex 572.869 111.533 9.62153e-15 + vertex 565.593 107.64 -8.39019e-06 + endloop + endfacet + facet normal -6.77026e-07 3.42096e-06 -1 + outer loop + vertex 565.593 107.64 -8.39019e-06 + vertex 572.869 111.533 9.62153e-15 + vertex 574.302 110.312 -5.1469e-06 + endloop + endfacet + facet normal -2.37954e-06 8.97091e-06 -1 + outer loop + vertex 565.593 107.64 -8.39019e-06 + vertex 574.302 110.312 -5.1469e-06 + vertex 568.05 106.718 -2.25163e-05 + endloop + endfacet + facet normal -1.52238e-06 1.12532e-05 -1 + outer loop + vertex 562.336 105.267 -3.01433e-05 + vertex 565.593 107.64 -8.39019e-06 + vertex 568.05 106.718 -2.25163e-05 + endloop + endfacet + facet normal -1.1314e-06 6.80002e-06 -1 + outer loop + vertex 568.05 106.718 -2.25163e-05 + vertex 574.302 110.312 -5.1469e-06 + vertex 577.211 109.473 -1.41457e-05 + endloop + endfacet + facet normal -4.6579e-06 1.85252e-05 -1 + outer loop + vertex 568.05 106.718 -2.25163e-05 + vertex 577.211 109.473 -1.41457e-05 + vertex 571.341 105.994 -5.12404e-05 + endloop + endfacet + facet normal -2.71701e-06 2.73561e-05 -1 + outer loop + vertex 564.607 104.217 -8.15806e-05 + vertex 568.05 106.718 -2.25163e-05 + vertex 571.341 105.994 -5.12404e-05 + endloop + endfacet + facet normal -3.0511e-06 1.58136e-05 -1 + outer loop + vertex 571.341 105.994 -5.12404e-05 + vertex 577.211 109.473 -1.41457e-05 + vertex 580.732 108.818 -3.52398e-05 + endloop + endfacet + facet normal -9.5052e-06 3.72787e-05 -1 + outer loop + vertex 571.341 105.994 -5.12404e-05 + vertex 580.732 108.818 -3.52398e-05 + vertex 574.71 105.261 -0.000110592 + endloop + endfacet + facet normal -7.31671e-06 4.73348e-05 -1 + outer loop + vertex 568.3 103.669 -0.000139081 + vertex 571.341 105.994 -5.12404e-05 + vertex 574.71 105.261 -0.000110592 + endloop + endfacet + facet normal -6.41979e-06 3.20544e-05 -1 + outer loop + vertex 574.71 105.261 -0.000110592 + vertex 580.732 108.818 -3.52398e-05 + vertex 584.091 108.09 -8.01622e-05 + endloop + endfacet + facet normal -1.66032e-05 6.58343e-05 -1 + outer loop + vertex 574.71 105.261 -0.000110592 + vertex 584.091 108.09 -8.01622e-05 + vertex 577.981 104.451 -0.00021826 + endloop + endfacet + facet normal -1.13711e-05 8.69522e-05 -1 + outer loop + vertex 571.078 102.664 -0.000295103 + vertex 574.71 105.261 -0.000110592 + vertex 577.981 104.451 -0.00021826 + endloop + endfacet + facet normal -1.34224e-05 6.04926e-05 -1 + outer loop + vertex 577.981 104.451 -0.00021826 + vertex 584.091 108.09 -8.01622e-05 + vertex 587.308 107.259 -0.000173558 + endloop + endfacet + facet normal -2.78434e-05 0.000108385 -1 + outer loop + vertex 577.981 104.451 -0.00021826 + vertex 587.308 107.259 -0.000173558 + vertex 581.164 103.546 -0.000405018 + endloop + endfacet + facet normal -2.24873e-05 0.000127223 -1 + outer loop + vertex 574.791 102.019 -0.000455891 + vertex 577.981 104.451 -0.00021826 + vertex 581.164 103.546 -0.000405018 + endloop + endfacet + facet normal -2.40066e-05 0.000102038 -1 + outer loop + vertex 581.164 103.546 -0.000405018 + vertex 587.308 107.259 -0.000173558 + vertex 590.497 106.339 -0.000344058 + endloop + endfacet + facet normal -3.98162e-05 0.000154862 -1 + outer loop + vertex 581.164 103.546 -0.000405018 + vertex 590.497 106.339 -0.000344058 + vertex 584.327 102.566 -0.000682582 + endloop + endfacet + facet normal -3.12357e-05 0.00018258 -1 + outer loop + vertex 577.389 100.843 -0.0007805 + vertex 581.164 103.546 -0.000405018 + vertex 584.327 102.566 -0.000682582 + endloop + endfacet + facet normal -3.83786e-05 0.000152511 -1 + outer loop + vertex 584.327 102.566 -0.000682582 + vertex 590.497 106.339 -0.000344058 + vertex 593.729 105.365 -0.000616572 + endloop + endfacet + facet normal -4.90346e-05 0.000188308 -1 + outer loop + vertex 584.327 102.566 -0.000682582 + vertex 593.729 105.365 -0.000616572 + vertex 587.48 101.541 -0.00103023 + endloop + endfacet + facet normal -4.16359e-05 0.000211065 -1 + outer loop + vertex 581.022 100.051 -0.00107588 + vertex 584.327 102.566 -0.000682582 + vertex 587.48 101.541 -0.00103023 + endloop + endfacet + facet normal -4.96045e-05 0.000189239 -1 + outer loop + vertex 587.48 101.541 -0.00103023 + vertex 593.729 105.365 -0.000616572 + vertex 596.914 104.324 -0.000971553 + endloop + endfacet + facet normal -5.06039e-05 0.000192627 -1 + outer loop + vertex 587.48 101.541 -0.00103023 + vertex 596.914 104.324 -0.000971553 + vertex 590.536 100.435 -0.00139789 + endloop + endfacet + facet normal -4.11565e-05 0.000218723 -1 + outer loop + vertex 583.515 98.7628 -0.00147475 + vertex 587.48 101.541 -0.00103023 + vertex 590.536 100.435 -0.00139789 + endloop + endfacet + facet normal -5.15346e-05 0.000194154 -1 + outer loop + vertex 590.536 100.435 -0.00139789 + vertex 596.914 104.324 -0.000971553 + vertex 600.022 103.205 -0.00134909 + endloop + endfacet + facet normal -5.51627e-05 0.000206582 -1 + outer loop + vertex 590.536 100.435 -0.00139789 + vertex 600.022 103.205 -0.00134909 + vertex 593.5 99.2021 -0.00181616 + endloop + endfacet + facet normal -4.7013e-05 0.00022617 -1 + outer loop + vertex 587.035 97.8208 -0.00182464 + vertex 590.536 100.435 -0.00139789 + vertex 593.5 99.2021 -0.00181616 + endloop + endfacet + facet normal -5.42279e-05 0.000205058 -1 + outer loop + vertex 593.5 99.2021 -0.00181616 + vertex 600.022 103.205 -0.00134909 + vertex 603.082 101.973 -0.00176767 + endloop + endfacet + facet normal -9.42021e-05 0.000343314 -1 + outer loop + vertex 593.5 99.2021 -0.00181616 + vertex 603.082 101.973 -0.00176767 + vertex 596.492 97.7506 -0.0025963 + endloop + endfacet + facet normal -7.17661e-05 0.000389565 -1 + outer loop + vertex 589.194 96.1851 -0.00268244 + vertex 593.5 99.2021 -0.00181616 + vertex 596.492 97.7506 -0.0025963 + endloop + endfacet + facet normal -9.02205e-05 0.000337099 -1 + outer loop + vertex 596.492 97.7506 -0.0025963 + vertex 603.082 101.973 -0.00176767 + vertex 606.102 100.584 -0.00250835 + endloop + endfacet + facet normal -0.000173993 0.000621276 -1 + outer loop + vertex 596.492 97.7506 -0.0025963 + vertex 606.102 100.584 -0.00250835 + vertex 599.544 96.1721 -0.00410799 + endloop + endfacet + facet normal -0.00013161 0.000703218 -1 + outer loop + vertex 592.662 94.2979 -0.00452027 + vertex 596.492 97.7506 -0.0025963 + vertex 599.544 96.1721 -0.00410799 + endloop + endfacet + facet normal -0.00020263 0.00066385 -1 + outer loop + vertex 599.544 96.1721 -0.00410799 + vertex 606.102 100.584 -0.00250835 + vertex 609.066 99.0017 -0.00415917 + endloop + endfacet + facet normal -0.000285693 0.000943396 -1 + outer loop + vertex 599.544 96.1721 -0.00410799 + vertex 609.066 99.0017 -0.00415917 + vertex 602.314 94.349 -0.00661958 + endloop + endfacet + facet normal -0.000246019 0.00100369 -0.999999 + outer loop + vertex 596.01 92.9615 -0.00646122 + vertex 599.544 96.1721 -0.00410799 + vertex 602.314 94.349 -0.00661958 + endloop + endfacet + facet normal -0.000298426 0.000961872 -0.999999 + outer loop + vertex 602.314 94.349 -0.00661958 + vertex 609.066 99.0017 -0.00415917 + vertex 611.949 97.1317 -0.00681815 + endloop + endfacet + facet normal -0.000177873 0.000544487 -1 + outer loop + vertex 602.314 94.349 -0.00661958 + vertex 611.949 97.1317 -0.00681815 + vertex 604.924 92.0588 -0.00833068 + endloop + endfacet + facet normal -0.000116226 0.000614729 -1 + outer loop + vertex 597.767 90.6449 -0.008368 + vertex 602.314 94.349 -0.00661958 + vertex 604.924 92.0588 -0.00833068 + endloop + endfacet + facet normal -0.000123593 0.000469318 -1 + outer loop + vertex 604.924 92.0588 -0.00833068 + vertex 611.949 97.1317 -0.00681815 + vertex 614.722 94.8954 -0.00821034 + endloop + endfacet + facet normal 0.000441432 -0.0014823 -0.999999 + outer loop + vertex 604.924 92.0588 -0.00833068 + vertex 614.722 94.8954 -0.00821034 + vertex 607.577 89.4059 -0.00322703 + endloop + endfacet + facet normal 0.000465871 -0.00145786 -0.999999 + outer loop + vertex 600.397 87.7812 -0.00420325 + vertex 604.924 92.0588 -0.00833068 + vertex 607.577 89.4059 -0.00322703 + endloop + endfacet + facet normal 0.000563694 -0.00164142 -0.999998 + outer loop + vertex 607.577 89.4059 -0.00322703 + vertex 614.722 94.8954 -0.00821034 + vertex 617.333 92.3192 -0.00250965 + endloop + endfacet + facet normal 0.00161382 -0.00515802 -0.999985 + outer loop + vertex 607.577 89.4059 -0.00322703 + vertex 617.333 92.3192 -0.00250965 + vertex 610.001 86.5879 0.0152203 + endloop + endfacet + facet normal 0.00143022 -0.00531592 -0.999985 + outer loop + vertex 603.093 84.7584 0.0150658 + vertex 607.577 89.4059 -0.00322703 + vertex 610.001 86.5879 0.0152203 + endloop + endfacet + facet normal 0.00199399 -0.00564435 -0.999982 + outer loop + vertex 610.001 86.5879 0.0152203 + vertex 617.333 92.3192 -0.00250965 + vertex 619.659 89.4317 0.0184266 + endloop + endfacet + facet normal 0.00358862 -0.0110599 -0.999932 + outer loop + vertex 610.001 86.5879 0.0152203 + vertex 619.659 89.4317 0.0184266 + vertex 611.984 83.5555 0.0558797 + endloop + endfacet + facet normal 0.00379281 -0.0109264 -0.999933 + outer loop + vertex 605.68 82.4335 0.0442283 + vertex 610.001 86.5879 0.0152203 + vertex 611.984 83.5555 0.0558797 + endloop + endfacet + facet normal 0.00390289 -0.0114703 -0.999927 + outer loop + vertex 611.984 83.5555 0.0558797 + vertex 619.659 89.4317 0.0184266 + vertex 621.669 86.2363 0.0629278 + endloop + endfacet + facet normal 0.00605221 -0.0192351 -0.999797 + outer loop + vertex 611.984 83.5555 0.0558797 + vertex 621.669 86.2363 0.0629278 + vertex 613.604 80.0955 0.132248 + endloop + endfacet + facet normal 0.00628776 -0.0191249 -0.999797 + outer loop + vertex 606.538 79.1557 0.105789 + vertex 611.984 83.5555 0.0558797 + vertex 613.604 80.0955 0.132248 + endloop + endfacet + facet normal 0.00625614 -0.0195029 -0.99979 + outer loop + vertex 613.604 80.0955 0.132248 + vertex 621.669 86.2363 0.0629278 + vertex 623.369 82.7475 0.141624 + endloop + endfacet + facet normal 0.0101075 -0.0336868 -0.999381 + outer loop + vertex 613.604 80.0955 0.132248 + vertex 623.369 82.7475 0.141624 + vertex 615.137 76.3398 0.274349 + endloop + endfacet + facet normal 0.0111664 -0.0332546 -0.999385 + outer loop + vertex 608.049 75.2089 0.232782 + vertex 613.604 80.0955 0.132248 + vertex 615.137 76.3398 0.274349 + endloop + endfacet + facet normal 0.0116139 -0.0356204 -0.999298 + outer loop + vertex 615.137 76.3398 0.274349 + vertex 623.369 82.7475 0.141624 + vertex 624.871 79.0566 0.290644 + endloop + endfacet + facet normal 0.0193758 -0.0634413 -0.997797 + outer loop + vertex 615.137 76.3398 0.274349 + vertex 624.871 79.0566 0.290644 + vertex 616.517 72.3817 0.552808 + endloop + endfacet + facet normal 0.0219296 -0.0625512 -0.997801 + outer loop + vertex 609.452 71.0422 0.481519 + vertex 615.137 76.3398 0.274349 + vertex 616.517 72.3817 0.552808 + endloop + endfacet + facet normal 0.0297254 -0.103859 -0.994148 + outer loop + vertex 609.452 71.0422 0.481519 + vertex 616.517 72.3817 0.552808 + vertex 610.646 66.7451 0.966109 + endloop + endfacet + facet normal 0.0405416 -0.100848 -0.994076 + outer loop + vertex 609.452 71.0422 0.481519 + vertex 610.646 66.7451 0.966109 + vertex 606.481 66.6559 0.805322 + endloop + endfacet + facet normal 0.0408026 -0.115276 -0.992495 + outer loop + vertex 610.646 66.7451 0.966109 + vertex 616.517 72.3817 0.552808 + vertex 617.888 68.1798 1.09723 + endloop + endfacet + facet normal 0.0364406 -0.1167 -0.992498 + outer loop + vertex 616.517 72.3817 0.552808 + vertex 626.326 75.1789 0.584062 + vertex 617.888 68.1798 1.09723 + endloop + endfacet + facet normal 0.0374671 -0.117924 -0.992315 + outer loop + vertex 617.888 68.1798 1.09723 + vertex 626.326 75.1789 0.584062 + vertex 628.028 71.1152 1.13124 + endloop + endfacet + facet normal 0.0376967 -0.117829 -0.992318 + outer loop + vertex 626.326 75.1789 0.584062 + vertex 637.599 78.8231 0.579611 + vertex 628.028 71.1152 1.13124 + endloop + endfacet + facet normal 0.0375854 -0.117692 -0.992339 + outer loop + vertex 628.028 71.1152 1.13124 + vertex 637.599 78.8231 0.579611 + vertex 639.439 74.8135 1.12482 + endloop + endfacet + facet normal 0.0386777 -0.117193 -0.992356 + outer loop + vertex 637.599 78.8231 0.579611 + vertex 649.095 82.7035 0.569414 + vertex 639.439 74.8135 1.12482 + endloop + endfacet + facet normal 0.0390352 -0.117626 -0.99229 + outer loop + vertex 639.439 74.8135 1.12482 + vertex 649.095 82.7035 0.569414 + vertex 650.828 78.638 1.1195 + endloop + endfacet + facet normal 0.0404275 -0.117035 -0.992305 + outer loop + vertex 649.095 82.7035 0.569414 + vertex 660.343 86.5795 0.570491 + vertex 650.828 78.638 1.1195 + endloop + endfacet + facet normal 0.0401004 -0.116647 -0.992364 + outer loop + vertex 650.828 78.638 1.1195 + vertex 660.343 86.5795 0.570491 + vertex 661.982 82.4706 1.1197 + endloop + endfacet + facet normal 0.0413837 -0.116136 -0.992371 + outer loop + vertex 660.343 86.5795 0.570491 + vertex 671.445 90.5092 0.573569 + vertex 661.982 82.4706 1.1197 + endloop + endfacet + facet normal 0.0416467 -0.116442 -0.992324 + outer loop + vertex 661.982 82.4706 1.1197 + vertex 671.445 90.5092 0.573569 + vertex 673.105 86.4121 1.12403 + endloop + endfacet + facet normal 0.0426677 -0.116029 -0.992329 + outer loop + vertex 671.445 90.5092 0.573569 + vertex 682.558 94.586 0.574749 + vertex 673.105 86.4121 1.12403 + endloop + endfacet + facet normal 0.0423657 -0.115684 -0.992382 + outer loop + vertex 673.105 86.4121 1.12403 + vertex 682.558 94.586 0.574749 + vertex 684.275 90.52 1.12202 + endloop + endfacet + facet normal 0.0439329 -0.115023 -0.992391 + outer loop + vertex 682.558 94.586 0.574749 + vertex 693.665 98.8227 0.575371 + vertex 684.275 90.52 1.12202 + endloop + endfacet + facet normal 0.0441454 -0.115261 -0.992354 + outer loop + vertex 684.275 90.52 1.12202 + vertex 693.665 98.8227 0.575371 + vertex 695.421 94.7805 1.12302 + endloop + endfacet + facet normal 0.0455535 -0.11465 -0.992361 + outer loop + vertex 693.665 98.8227 0.575371 + vertex 704.67 103.192 0.575747 + vertex 695.421 94.7805 1.12302 + endloop + endfacet + facet normal 0.0453958 -0.114479 -0.992388 + outer loop + vertex 695.421 94.7805 1.12302 + vertex 704.67 103.192 0.575747 + vertex 706.443 99.1643 1.12147 + endloop + endfacet + facet normal 0.0467556 -0.113881 -0.992394 + outer loop + vertex 704.67 103.192 0.575747 + vertex 715.526 107.683 0.571862 + vertex 706.443 99.1643 1.12147 + endloop + endfacet + facet normal 0.0478399 -0.115025 -0.99221 + outer loop + vertex 706.443 99.1643 1.12147 + vertex 715.526 107.683 0.571862 + vertex 717.309 103.667 1.12342 + endloop + endfacet + facet normal 0.0494874 -0.114294 -0.992214 + outer loop + vertex 715.526 107.683 0.571862 + vertex 726.262 112.314 0.573875 + vertex 717.309 103.667 1.12342 + endloop + endfacet + facet normal 0.0491302 -0.113928 -0.992273 + outer loop + vertex 717.309 103.667 1.12342 + vertex 726.262 112.314 0.573875 + vertex 728.044 108.306 1.12227 + endloop + endfacet + facet normal 0.0509356 -0.113126 -0.992274 + outer loop + vertex 726.262 112.314 0.573875 + vertex 736.927 117.117 0.573762 + vertex 728.044 108.306 1.12227 + endloop + endfacet + facet normal 0.0509141 -0.113104 -0.992278 + outer loop + vertex 728.044 108.306 1.12227 + vertex 736.927 117.117 0.573762 + vertex 738.721 113.123 1.12108 + endloop + endfacet + facet normal 0.0527154 -0.112295 -0.992276 + outer loop + vertex 736.927 117.117 0.573762 + vertex 747.554 122.116 0.572657 + vertex 738.721 113.123 1.12108 + endloop + endfacet + facet normal 0.0536885 -0.113241 -0.992116 + outer loop + vertex 738.721 113.123 1.12108 + vertex 747.554 122.116 0.572657 + vertex 749.383 118.146 1.12472 + endloop + endfacet + facet normal 0.0553792 -0.112461 -0.992112 + outer loop + vertex 747.554 122.116 0.572657 + vertex 758.124 127.31 0.573852 + vertex 749.383 118.146 1.12472 + endloop + endfacet + facet normal 0.0546918 -0.111812 -0.992223 + outer loop + vertex 749.383 118.146 1.12472 + vertex 758.124 127.31 0.573852 + vertex 759.97 123.357 1.12108 + endloop + endfacet + facet normal 0.056815 -0.11082 -0.992215 + outer loop + vertex 758.124 127.31 0.573852 + vertex 768.588 132.687 0.572446 + vertex 759.97 123.357 1.12108 + endloop + endfacet + facet normal 0.0576331 -0.111568 -0.992084 + outer loop + vertex 759.97 123.357 1.12108 + vertex 768.588 132.687 0.572446 + vertex 770.441 128.748 1.12313 + endloop + endfacet + facet normal 0.0596591 -0.110613 -0.992071 + outer loop + vertex 768.588 132.687 0.572446 + vertex 778.938 138.254 0.574208 + vertex 770.441 128.748 1.12313 + endloop + endfacet + facet normal 0.0594122 -0.110394 -0.992111 + outer loop + vertex 770.441 128.748 1.12313 + vertex 778.938 138.254 0.574208 + vertex 780.809 134.334 1.12243 + endloop + endfacet + facet normal 0.061524 -0.109384 -0.992094 + outer loop + vertex 778.938 138.254 0.574208 + vertex 789.184 144.021 0.573796 + vertex 780.809 134.334 1.12243 + endloop + endfacet + facet normal 0.061811 -0.10963 -0.992049 + outer loop + vertex 780.809 134.334 1.12243 + vertex 789.184 144.021 0.573796 + vertex 791.072 140.122 1.12225 + endloop + endfacet + facet normal 0.0641391 -0.108499 -0.992025 + outer loop + vertex 789.184 144.021 0.573796 + vertex 799.315 149.996 0.57526 + vertex 791.072 140.122 1.12225 + endloop + endfacet + facet normal 0.0642072 -0.108555 -0.992015 + outer loop + vertex 791.072 140.122 1.12225 + vertex 799.315 149.996 0.57526 + vertex 801.206 146.115 1.12234 + endloop + endfacet + facet normal 0.0665461 -0.107412 -0.991985 + outer loop + vertex 799.315 149.996 0.57526 + vertex 809.286 156.192 0.573258 + vertex 801.206 146.115 1.12234 + endloop + endfacet + facet normal 0.0673231 -0.108028 -0.991866 + outer loop + vertex 801.206 146.115 1.12234 + vertex 809.286 156.192 0.573258 + vertex 811.194 152.347 1.12155 + endloop + endfacet + facet normal 0.0706573 -0.106366 -0.991813 + outer loop + vertex 809.286 156.192 0.573258 + vertex 819.033 162.667 0.573193 + vertex 811.194 152.347 1.12155 + endloop + endfacet + facet normal 0.071686 -0.107139 -0.991656 + outer loop + vertex 811.194 152.347 1.12155 + vertex 819.033 162.667 0.573193 + vertex 820.998 158.883 1.12408 + endloop + endfacet + facet normal 0.0756106 -0.105091 -0.991584 + outer loop + vertex 819.033 162.667 0.573193 + vertex 828.518 169.5 0.572306 + vertex 820.998 158.883 1.12408 + endloop + endfacet + facet normal 0.0756119 -0.105092 -0.991584 + outer loop + vertex 820.998 158.883 1.12408 + vertex 828.518 169.5 0.572306 + vertex 830.559 165.771 1.12316 + endloop + endfacet + facet normal 0.0800121 -0.10267 -0.991492 + outer loop + vertex 828.518 169.5 0.572306 + vertex 837.7 176.677 0.570094 + vertex 830.559 165.771 1.12316 + endloop + endfacet + facet normal 0.0780668 -0.101411 -0.991777 + outer loop + vertex 830.559 165.771 1.12316 + vertex 837.7 176.677 0.570094 + vertex 839.806 172.969 1.11506 + endloop + endfacet + facet normal 0.0819956 -0.0991663 -0.991687 + outer loop + vertex 837.7 176.677 0.570094 + vertex 846.477 183.981 0.565441 + vertex 839.806 172.969 1.11506 + endloop + endfacet + facet normal 0.0830646 -0.0998063 -0.991534 + outer loop + vertex 839.806 172.969 1.11506 + vertex 846.477 183.981 0.565441 + vertex 848.637 180.287 1.11817 + endloop + endfacet + facet normal 0.0859203 -0.0981253 -0.991458 + outer loop + vertex 846.477 183.981 0.565441 + vertex 854.617 190.978 0.578383 + vertex 848.637 180.287 1.11817 + endloop + endfacet + facet normal 0.0878852 -0.0992103 -0.991178 + outer loop + vertex 848.637 180.287 1.11817 + vertex 854.617 190.978 0.578383 + vertex 856.905 187.362 1.14315 + endloop + endfacet + facet normal 0.0901752 -0.0977522 -0.991117 + outer loop + vertex 854.617 190.978 0.578383 + vertex 861.865 197.169 0.627104 + vertex 856.905 187.362 1.14315 + endloop + endfacet + facet normal 0.0940978 -0.0997064 -0.990558 + outer loop + vertex 856.905 187.362 1.14315 + vertex 861.865 197.169 0.627104 + vertex 864.383 193.695 1.21607 + endloop + endfacet + facet normal 0.0962193 -0.0981607 -0.990508 + outer loop + vertex 864.383 193.695 1.21607 + vertex 861.865 197.169 0.627104 + vertex 868.132 202.26 0.731407 + endloop + endfacet + facet normal 0.0964463 -0.0982582 -0.990476 + outer loop + vertex 868.132 202.26 0.731407 + vertex 870.892 198.695 1.35385 + vertex 864.383 193.695 1.21607 + endloop + endfacet + facet normal 0.100345 -0.0952245 -0.990385 + outer loop + vertex 870.892 198.695 1.35385 + vertex 868.132 202.26 0.731407 + vertex 873.717 206.265 0.912235 + endloop + endfacet + facet normal 0.06461 -0.0591314 -0.996157 + outer loop + vertex 865.43 205.859 0.342515 + vertex 868.132 202.26 0.731407 + vertex 861.865 197.169 0.627104 + endloop + endfacet + facet normal 0.0567147 -0.0559141 -0.996823 + outer loop + vertex 861.865 197.169 0.627104 + vertex 859.423 200.683 0.29108 + vertex 865.43 205.859 0.342515 + endloop + endfacet + facet normal 0.0336779 -0.0291573 -0.999007 + outer loop + vertex 862.451 209.143 0.146244 + vertex 865.43 205.859 0.342515 + vertex 859.423 200.683 0.29108 + endloop + endfacet + facet normal 0.0274314 -0.0269259 -0.999261 + outer loop + vertex 859.423 200.683 0.29108 + vertex 856.619 203.691 0.133051 + vertex 862.451 209.143 0.146244 + endloop + endfacet + facet normal 0.0137163 -0.0122531 -0.999831 + outer loop + vertex 858.227 211.737 0.0565088 + vertex 862.451 209.143 0.146244 + vertex 856.619 203.691 0.133051 + endloop + endfacet + facet normal 0.0145263 -0.0124149 -0.999817 + outer loop + vertex 856.619 203.691 0.133051 + vertex 853.462 205.082 0.0699114 + vertex 858.227 211.737 0.0565088 + endloop + endfacet + facet normal 0.00742559 -0.00733075 -0.999946 + outer loop + vertex 853.462 205.082 0.0699114 + vertex 851.75 208.649 0.0310576 + vertex 858.227 211.737 0.0565088 + endloop + endfacet + facet normal 0.00639365 -0.0051668 -0.999966 + outer loop + vertex 854.661 215.742 0.0130199 + vertex 858.227 211.737 0.0565088 + vertex 851.75 208.649 0.0310576 + endloop + endfacet + facet normal 0.00424007 -0.00428304 -0.999982 + outer loop + vertex 851.75 208.649 0.0310576 + vertex 848.24 211.462 0.00412448 + vertex 854.661 215.742 0.0130199 + endloop + endfacet + facet normal 0.002715 -0.0019949 -0.999994 + outer loop + vertex 850.209 218.204 -0.00398058 + vertex 854.661 215.742 0.0130199 + vertex 848.24 211.462 0.00412448 + endloop + endfacet + facet normal 0.00190774 -0.0017592 -0.999997 + outer loop + vertex 848.24 211.462 0.00412448 + vertex 843.831 213.355 -0.0076174 + vertex 850.209 218.204 -0.00398058 + endloop + endfacet + facet normal 0.000579568 -1.22741e-05 -1 + outer loop + vertex 844.234 220.263 -0.00746872 + vertex 850.209 218.204 -0.00398058 + vertex 843.831 213.355 -0.0076174 + endloop + endfacet + facet normal 0.00042144 -3.05304e-06 -1 + outer loop + vertex 843.831 213.355 -0.0076174 + vertex 839.401 213.762 -0.00948546 + vertex 844.234 220.263 -0.00746872 + endloop + endfacet + facet normal -0.000382792 0.000594801 -1 + outer loop + vertex 839.401 213.762 -0.00948546 + vertex 836.4 215.97 -0.00702368 + vertex 844.234 220.263 -0.00746872 + endloop + endfacet + facet normal -0.000292585 0.000430204 -1 + outer loop + vertex 838.024 222 -0.00490477 + vertex 844.234 220.263 -0.00746872 + vertex 836.4 215.97 -0.00702368 + endloop + endfacet + facet normal -0.00043468 0.000468479 -1 + outer loop + vertex 836.4 215.97 -0.00702368 + vertex 831.683 217.196 -0.00439846 + vertex 838.024 222 -0.00490477 + endloop + endfacet + facet normal -0.000284107 0.000269684 -1 + outer loop + vertex 831.655 223.04 -0.00281442 + vertex 838.024 222 -0.00490477 + vertex 831.683 217.196 -0.00439846 + endloop + endfacet + facet normal -0.000289621 0.000269657 -1 + outer loop + vertex 831.683 217.196 -0.00439846 + vertex 827.19 217.023 -0.00314393 + vertex 831.655 223.04 -0.00281442 + endloop + endfacet + facet normal -0.000182795 0.000190393 -1 + outer loop + vertex 827.19 217.023 -0.00314393 + vertex 824.4 218.43 -0.00236589 + vertex 831.655 223.04 -0.00281442 + endloop + endfacet + facet normal -0.000180328 0.000186511 -1 + outer loop + vertex 826.213 222.931 -0.00185353 + vertex 831.655 223.04 -0.00281442 + vertex 824.4 218.43 -0.00236589 + endloop + endfacet + facet normal -0.000161402 0.000178885 -1 + outer loop + vertex 824.4 218.43 -0.00236589 + vertex 820.531 219.13 -0.00161633 + vertex 826.213 222.931 -0.00185353 + endloop + endfacet + facet normal -0.000154289 0.000168251 -1 + outer loop + vertex 823.166 224.201 -0.00116974 + vertex 826.213 222.931 -0.00185353 + vertex 820.531 219.13 -0.00161633 + endloop + endfacet + facet normal -0.00014655 0.000164228 -1 + outer loop + vertex 820.531 219.13 -0.00161633 + vertex 816.599 219.802 -0.000929789 + vertex 823.166 224.201 -0.00116974 + endloop + endfacet + facet normal -0.000124706 0.00013162 -1 + outer loop + vertex 819.287 224.972 -0.000584532 + vertex 823.166 224.201 -0.00116974 + vertex 816.599 219.802 -0.000929789 + endloop + endfacet + facet normal -9.81468e-05 0.000117811 -1 + outer loop + vertex 816.599 219.802 -0.000929789 + vertex 812.408 220.913 -0.00038754 + vertex 819.287 224.972 -0.000584532 + endloop + endfacet + facet normal -8.1243e-05 8.91603e-05 -1 + outer loop + vertex 816.45 226.008 -0.000261652 + vertex 819.287 224.972 -0.000584532 + vertex 812.408 220.913 -0.00038754 + endloop + endfacet + facet normal -4.06205e-05 5.69346e-05 -1 + outer loop + vertex 812.239 225.318 -0.000129894 + vertex 816.45 226.008 -0.000261652 + vertex 812.408 220.913 -0.00038754 + endloop + endfacet + facet normal -4.98453e-05 5.65794e-05 -1 + outer loop + vertex 812.408 220.913 -0.00038754 + vertex 806.828 220.416 -0.00013754 + vertex 812.239 225.318 -0.000129894 + endloop + endfacet + facet normal -1.92674e-05 2.28272e-05 -1 + outer loop + vertex 807.719 225.309 -4.29977e-05 + vertex 812.239 225.318 -0.000129894 + vertex 806.828 220.416 -0.00013754 + endloop + endfacet + facet normal -2.04077e-05 2.30349e-05 -1 + outer loop + vertex 806.828 220.416 -0.00013754 + vertex 802.258 220.51 -4.20859e-05 + vertex 807.719 225.309 -4.29977e-05 + endloop + endfacet + facet normal -6.80287e-06 7.55196e-06 -1 + outer loop + vertex 803.151 225.364 -1.15097e-05 + vertex 807.719 225.309 -4.29977e-05 + vertex 802.258 220.51 -4.20859e-05 + endloop + endfacet + facet normal -7.21937e-06 7.62864e-06 -1 + outer loop + vertex 802.258 220.51 -4.20859e-05 + vertex 797.807 220.439 -1.04959e-05 + vertex 803.151 225.364 -1.15097e-05 + endloop + endfacet + facet normal -1.92184e-06 1.87974e-06 -1 + outer loop + vertex 797.628 224.631 -2.27459e-06 + vertex 803.151 225.364 -1.15097e-05 + vertex 797.807 220.439 -1.04959e-05 + endloop + endfacet + facet normal -2.22515e-06 1.86684e-06 -1 + outer loop + vertex 797.807 220.439 -1.04959e-05 + vertex 793.571 219.569 -2.69649e-06 + vertex 797.628 224.631 -2.27459e-06 + endloop + endfacet + facet normal -5.74773e-07 5.4404e-07 -1 + outer loop + vertex 793.571 219.569 -2.69649e-06 + vertex 790.848 220.565 -5.89566e-07 + vertex 797.628 224.631 -2.27459e-06 + endloop + endfacet + facet normal -4.61632e-07 3.55375e-07 -1 + outer loop + vertex 793.684 225.068 -2.98064e-07 + vertex 797.628 224.631 -2.27459e-06 + vertex 790.848 220.565 -5.89566e-07 + endloop + endfacet + facet normal -1.11616e-07 1.34997e-07 -1 + outer loop + vertex 790.848 220.565 -5.89566e-07 + vertex 787.3 221.998 9.62153e-15 + vertex 793.684 225.068 -2.98064e-07 + endloop + endfacet + facet normal -9.53415e-08 1.01159e-07 -1 + outer loop + vertex 793.885 228.204 9.62153e-15 + vertex 793.684 225.068 -2.98064e-07 + vertex 787.3 221.998 9.62153e-15 + endloop + endfacet + facet normal -1.32811e-07 1.03561e-07 -1 + outer loop + vertex 793.684 225.068 -2.98064e-07 + vertex 793.885 228.204 9.62153e-15 + vertex 798.589 229.304 -5.1098e-07 + endloop + endfacet + facet normal -1.41659e-07 1.41433e-07 -1 + outer loop + vertex 793.885 228.204 9.62153e-15 + vertex 799.221 233.549 9.5926e-15 + vertex 798.589 229.304 -5.1098e-07 + endloop + endfacet + facet normal -1.78593e-07 1.46928e-07 -1 + outer loop + vertex 803.571 234.129 -6.91618e-07 + vertex 798.589 229.304 -5.1098e-07 + vertex 799.221 233.549 9.5926e-15 + endloop + endfacet + facet normal -1.81595e-07 1.69442e-07 -1 + outer loop + vertex 799.221 233.549 9.5926e-15 + vertex 804.369 239.066 9.39008e-15 + vertex 803.571 234.129 -6.91618e-07 + endloop + endfacet + facet normal -2.45468e-07 1.7977e-07 -1 + outer loop + vertex 803.571 234.129 -6.91618e-07 + vertex 804.369 239.066 9.39008e-15 + vertex 808.171 239.076 -9.31552e-07 + endloop + endfacet + facet normal -6.68375e-07 5.73057e-07 -1 + outer loop + vertex 803.571 234.129 -6.91618e-07 + vertex 808.171 239.076 -9.31552e-07 + vertex 807.953 234.151 -3.60787e-06 + endloop + endfacet + facet normal -6.68176e-07 5.32942e-07 -1 + outer loop + vertex 803.365 229.71 -2.90931e-06 + vertex 803.571 234.129 -6.91618e-07 + vertex 807.953 234.151 -3.60787e-06 + endloop + endfacet + facet normal -2.14134e-06 2.05478e-06 -1 + outer loop + vertex 803.365 229.71 -2.90931e-06 + vertex 807.953 234.151 -3.60787e-06 + vertex 807.963 229.702 -1.27714e-05 + endloop + endfacet + facet normal -2.14129e-06 2.08438e-06 -1 + outer loop + vertex 803.365 229.71 -2.90931e-06 + vertex 807.963 229.702 -1.27714e-05 + vertex 803.151 225.364 -1.15097e-05 + endloop + endfacet + facet normal -2.57908e-06 2.05372e-06 -1 + outer loop + vertex 807.963 229.702 -1.27714e-05 + vertex 807.953 234.151 -3.60787e-06 + vertex 812.231 233.885 -1.51867e-05 + endloop + endfacet + facet normal -7.31535e-06 6.88562e-06 -1 + outer loop + vertex 807.963 229.702 -1.27714e-05 + vertex 812.231 233.885 -1.51867e-05 + vertex 812.312 229.476 -4.6145e-05 + endloop + endfacet + facet normal -7.29449e-06 7.28626e-06 -1 + outer loop + vertex 807.963 229.702 -1.27714e-05 + vertex 812.312 229.476 -4.6145e-05 + vertex 807.719 225.309 -4.29977e-05 + endloop + endfacet + facet normal -9.17744e-06 6.85116e-06 -1 + outer loop + vertex 812.312 229.476 -4.6145e-05 + vertex 812.231 233.885 -1.51867e-05 + vertex 816.534 233.655 -5.62628e-05 + endloop + endfacet + facet normal -1.92676e-05 1.70458e-05 -1 + outer loop + vertex 812.312 229.476 -4.6145e-05 + vertex 816.534 233.655 -5.62628e-05 + vertex 816.631 229.41 -0.00013048 + endloop + endfacet + facet normal -1.92149e-05 2.04799e-05 -1 + outer loop + vertex 812.312 229.476 -4.6145e-05 + vertex 816.631 229.41 -0.00013048 + vertex 812.239 225.318 -0.000129894 + endloop + endfacet + facet normal -2.5839e-05 1.68965e-05 -1 + outer loop + vertex 816.631 229.41 -0.00013048 + vertex 816.534 233.655 -5.62628e-05 + vertex 820.922 233.524 -0.000171844 + endloop + endfacet + facet normal -4.96799e-05 4.17622e-05 -1 + outer loop + vertex 816.631 229.41 -0.00013048 + vertex 820.922 233.524 -0.000171844 + vertex 820.75 229.264 -0.000341216 + endloop + endfacet + facet normal -4.96997e-05 4.12018e-05 -1 + outer loop + vertex 816.631 229.41 -0.00013048 + vertex 820.75 229.264 -0.000341216 + vertex 816.45 226.008 -0.000261652 + endloop + endfacet + facet normal -6.00304e-05 4.21808e-05 -1 + outer loop + vertex 820.75 229.264 -0.000341216 + vertex 820.922 233.524 -0.000171844 + vertex 825.351 233.385 -0.000443588 + endloop + endfacet + facet normal -9.682e-05 8.32561e-05 -1 + outer loop + vertex 820.75 229.264 -0.000341216 + vertex 825.351 233.385 -0.000443588 + vertex 824.904 228.812 -0.000781097 + endloop + endfacet + facet normal -9.61448e-05 8.94611e-05 -1 + outer loop + vertex 820.75 229.264 -0.000341216 + vertex 824.904 228.812 -0.000781097 + vertex 819.287 224.972 -0.000584532 + endloop + endfacet + facet normal -0.000102571 8.38174e-05 -1 + outer loop + vertex 824.904 228.812 -0.000781097 + vertex 825.351 233.385 -0.000443588 + vertex 829.87 233.083 -0.000932414 + endloop + endfacet + facet normal -0.000139429 0.000126667 -1 + outer loop + vertex 824.904 228.812 -0.000781097 + vertex 829.87 233.083 -0.000932414 + vertex 829.583 227.808 -0.0015605 + endloop + endfacet + facet normal -0.000137407 0.000136094 -1 + outer loop + vertex 824.904 228.812 -0.000781097 + vertex 829.583 227.808 -0.0015605 + vertex 823.166 224.201 -0.00116974 + endloop + endfacet + facet normal -0.000131009 0.000126209 -1 + outer loop + vertex 829.583 227.808 -0.0015605 + vertex 829.87 233.083 -0.000932414 + vertex 834.492 232.848 -0.0015675 + endloop + endfacet + facet normal -0.000147624 0.000142392 -1 + outer loop + vertex 829.583 227.808 -0.0015605 + vertex 834.492 232.848 -0.0015675 + vertex 834.882 228.733 -0.00221117 + endloop + endfacet + facet normal -0.000156778 0.000194861 -1 + outer loop + vertex 829.583 227.808 -0.0015605 + vertex 834.882 228.733 -0.00221117 + vertex 831.655 223.04 -0.00281442 + endloop + endfacet + facet normal -0.000206212 0.000222888 -1 + outer loop + vertex 834.882 228.733 -0.00221117 + vertex 838.618 227.386 -0.00328175 + vertex 831.655 223.04 -0.00281442 + endloop + endfacet + facet normal -0.000213298 0.000203244 -1 + outer loop + vertex 834.882 228.733 -0.00221117 + vertex 838.921 232.41 -0.00232532 + vertex 838.618 227.386 -0.00328175 + endloop + endfacet + facet normal -0.000207159 0.000202873 -1 + outer loop + vertex 838.618 227.386 -0.00328175 + vertex 838.921 232.41 -0.00232532 + vertex 843.308 231.558 -0.00340692 + endloop + endfacet + facet normal -0.000298286 0.000305311 -1 + outer loop + vertex 838.618 227.386 -0.00328175 + vertex 843.308 231.558 -0.00340692 + vertex 843.552 226.333 -0.00507496 + endloop + endfacet + facet normal -0.000292266 0.000333528 -1 + outer loop + vertex 838.618 227.386 -0.00328175 + vertex 843.552 226.333 -0.00507496 + vertex 838.024 222 -0.00490477 + endloop + endfacet + facet normal -0.000277008 0.000306305 -1 + outer loop + vertex 843.552 226.333 -0.00507496 + vertex 843.308 231.558 -0.00340692 + vertex 847.803 230.743 -0.00490166 + endloop + endfacet + facet normal -0.000300973 0.000329405 -1 + outer loop + vertex 843.552 226.333 -0.00507496 + vertex 847.803 230.743 -0.00490166 + vertex 848.044 226.14 -0.00649029 + endloop + endfacet + facet normal -0.000299632 0.000360688 -1 + outer loop + vertex 843.552 226.333 -0.00507496 + vertex 848.044 226.14 -0.00649029 + vertex 844.234 220.263 -0.00746872 + endloop + endfacet + facet normal 8.72594e-05 0.000109913 -1 + outer loop + vertex 848.044 226.14 -0.00649029 + vertex 851.462 224.108 -0.00641531 + vertex 844.234 220.263 -0.00746872 + endloop + endfacet + facet normal 4.18382e-05 3.34894e-05 -1 + outer loop + vertex 848.044 226.14 -0.00649029 + vertex 852.1 229.688 -0.00620177 + vertex 851.462 224.108 -0.00641531 + endloop + endfacet + facet normal 0.000322805 1.39163e-06 -1 + outer loop + vertex 851.462 224.108 -0.00641531 + vertex 852.1 229.688 -0.00620177 + vertex 856.407 228.21 -0.00481342 + endloop + endfacet + facet normal 0.00110103 -0.000936873 -0.999999 + outer loop + vertex 851.462 224.108 -0.00641531 + vertex 856.407 228.21 -0.00481342 + vertex 856.015 222.143 0.000439147 + endloop + endfacet + facet normal 0.00121606 -0.000670455 -0.999999 + outer loop + vertex 851.462 224.108 -0.00641531 + vertex 856.015 222.143 0.000439147 + vertex 850.209 218.204 -0.00398058 + endloop + endfacet + facet normal 0.00144936 -0.00095937 -0.999998 + outer loop + vertex 856.015 222.143 0.000439147 + vertex 856.407 228.21 -0.00481342 + vertex 860.787 226.389 0.00328112 + endloop + endfacet + facet normal 0.00320426 -0.00293132 -0.999991 + outer loop + vertex 856.015 222.143 0.000439147 + vertex 860.787 226.389 0.00328112 + vertex 860.218 219.638 0.0212482 + endloop + endfacet + facet normal 0.00335684 -0.00267525 -0.999991 + outer loop + vertex 856.015 222.143 0.000439147 + vertex 860.218 219.638 0.0212482 + vertex 854.661 215.742 0.0130199 + endloop + endfacet + facet normal 0.00330307 -0.00293965 -0.99999 + outer loop + vertex 860.218 219.638 0.0212482 + vertex 860.787 226.389 0.00328112 + vertex 864.92 224.129 0.0235783 + endloop + endfacet + facet normal 0.00697614 -0.00678556 -0.999953 + outer loop + vertex 860.218 219.638 0.0212482 + vertex 864.92 224.129 0.0235783 + vertex 864.099 216.792 0.0676391 + endloop + endfacet + facet normal 0.00732596 -0.00630863 -0.999953 + outer loop + vertex 860.218 219.638 0.0212482 + vertex 864.099 216.792 0.0676391 + vertex 858.227 211.737 0.0565088 + endloop + endfacet + facet normal 0.00859841 -0.00696709 -0.999939 + outer loop + vertex 864.099 216.792 0.0676391 + vertex 864.92 224.129 0.0235783 + vertex 868.678 221.492 0.0742695 + endloop + endfacet + facet normal 0.01729 -0.015436 -0.999731 + outer loop + vertex 864.099 216.792 0.0676391 + vertex 868.678 221.492 0.0742695 + vertex 867.583 213.786 0.174313 + endloop + endfacet + facet normal 0.0183348 -0.014225 -0.999731 + outer loop + vertex 864.099 216.792 0.0676391 + vertex 867.583 213.786 0.174313 + vertex 862.451 209.143 0.146244 + endloop + endfacet + facet normal 0.0240642 -0.0163965 -0.999576 + outer loop + vertex 867.583 213.786 0.174313 + vertex 868.678 221.492 0.0742695 + vertex 872.082 218.525 0.204872 + endloop + endfacet + facet normal 0.0427922 -0.0341797 -0.998499 + outer loop + vertex 867.583 213.786 0.174313 + vertex 872.082 218.525 0.204872 + vertex 870.612 210.358 0.421449 + endloop + endfacet + facet normal 0.0439737 -0.0331346 -0.998483 + outer loop + vertex 867.583 213.786 0.174313 + vertex 870.612 210.358 0.421449 + vertex 865.43 205.859 0.342515 + endloop + endfacet + facet normal 0.0491735 -0.0353194 -0.998166 + outer loop + vertex 870.612 210.358 0.421449 + vertex 872.082 218.525 0.204872 + vertex 875.377 215.191 0.485188 + endloop + endfacet + facet normal 0.0759242 -0.0617342 -0.995201 + outer loop + vertex 870.612 210.358 0.421449 + vertex 875.377 215.191 0.485188 + vertex 873.717 206.265 0.912235 + endloop + endfacet + facet normal 0.076288 -0.0614569 -0.99519 + outer loop + vertex 870.612 210.358 0.421449 + vertex 873.717 206.265 0.912235 + vertex 868.132 202.26 0.731407 + endloop + endfacet + facet normal 0.0762717 -0.0617973 -0.99517 + outer loop + vertex 873.717 206.265 0.912235 + vertex 875.377 215.191 0.485188 + vertex 878.775 211.498 0.974893 + endloop + endfacet + facet normal 0.078169 -0.0600462 -0.99513 + outer loop + vertex 875.377 215.191 0.485188 + vertex 880.263 221.232 0.504423 + vertex 878.775 211.498 0.974893 + endloop + endfacet + facet normal 0.0706674 -0.0589298 -0.995758 + outer loop + vertex 878.775 211.498 0.974893 + vertex 880.263 221.232 0.504423 + vertex 884.207 218.134 0.967703 + endloop + endfacet + facet normal 0.0742949 -0.0543109 -0.995756 + outer loop + vertex 880.263 221.232 0.504423 + vertex 885.392 228.332 0.499886 + vertex 884.207 218.134 0.967703 + endloop + endfacet + facet normal 0.0705175 -0.0538856 -0.996054 + outer loop + vertex 884.207 218.134 0.967703 + vertex 885.392 228.332 0.499886 + vertex 889.85 225.7 0.957858 + endloop + endfacet + facet normal 0.0732938 -0.0491911 -0.996097 + outer loop + vertex 885.392 228.332 0.499886 + vertex 890.402 235.912 0.494195 + vertex 889.85 225.7 0.957858 + endloop + endfacet + facet normal 0.0724201 -0.0491468 -0.996163 + outer loop + vertex 889.85 225.7 0.957858 + vertex 890.402 235.912 0.494195 + vertex 895.167 233.517 0.958754 + endloop + endfacet + facet normal 0.0749389 -0.0441446 -0.996211 + outer loop + vertex 890.402 235.912 0.494195 + vertex 894.963 243.613 0.496059 + vertex 895.167 233.517 0.958754 + endloop + endfacet + facet normal 0.073416 -0.0441805 -0.996322 + outer loop + vertex 895.167 233.517 0.958754 + vertex 894.963 243.613 0.496059 + vertex 899.985 241.441 0.962449 + endloop + endfacet + facet normal 0.0756716 -0.0389757 -0.996371 + outer loop + vertex 894.963 243.613 0.496059 + vertex 898.997 251.412 0.497401 + vertex 899.985 241.441 0.962449 + endloop + endfacet + facet normal 0.073005 -0.0392486 -0.996559 + outer loop + vertex 899.985 241.441 0.962449 + vertex 898.997 251.412 0.497401 + vertex 904.27 249.461 0.960437 + endloop + endfacet + facet normal 0.0752427 -0.0332127 -0.996612 + outer loop + vertex 898.997 251.412 0.497401 + vertex 902.537 259.428 0.497436 + vertex 904.27 249.461 0.960437 + endloop + endfacet + facet normal 0.073739 -0.033479 -0.996715 + outer loop + vertex 904.27 249.461 0.960437 + vertex 902.537 259.428 0.497436 + vertex 908.042 257.697 0.962891 + endloop + endfacet + facet normal 0.0755366 -0.027775 -0.996756 + outer loop + vertex 902.537 259.428 0.497436 + vertex 905.618 267.795 0.497837 + vertex 908.042 257.697 0.962891 + endloop + endfacet + facet normal 0.0727809 -0.028445 -0.996942 + outer loop + vertex 908.042 257.697 0.962891 + vertex 905.618 267.795 0.497837 + vertex 911.369 266.326 0.959542 + endloop + endfacet + facet normal 0.0743283 -0.0223997 -0.996982 + outer loop + vertex 905.618 267.795 0.497837 + vertex 908.239 276.549 0.496514 + vertex 911.369 266.326 0.959542 + endloop + endfacet + facet normal 0.0736675 -0.022604 -0.997027 + outer loop + vertex 911.369 266.326 0.959542 + vertex 908.239 276.549 0.496514 + vertex 914.204 275.409 0.963103 + endloop + endfacet + facet normal 0.0747418 -0.016999 -0.997058 + outer loop + vertex 908.239 276.549 0.496514 + vertex 910.325 285.617 0.498307 + vertex 914.204 275.409 0.963103 + endloop + endfacet + facet normal 0.0726452 -0.017802 -0.997199 + outer loop + vertex 914.204 275.409 0.963103 + vertex 910.325 285.617 0.498307 + vertex 916.461 284.785 0.960138 + endloop + endfacet + facet normal 0.0734242 -0.0120676 -0.997228 + outer loop + vertex 910.325 285.617 0.498307 + vertex 911.82 294.861 0.496486 + vertex 916.461 284.785 0.960138 + endloop + endfacet + facet normal 0.073187 -0.0121776 -0.997244 + outer loop + vertex 916.461 284.785 0.960138 + vertex 911.82 294.861 0.496486 + vertex 918.041 294.246 0.96056 + endloop + endfacet + facet normal 0.0737185 -0.00680748 -0.997256 + outer loop + vertex 911.82 294.861 0.496486 + vertex 912.691 304.219 0.497005 + vertex 918.041 294.246 0.96056 + endloop + endfacet + facet normal 0.0735101 -0.00691995 -0.99727 + outer loop + vertex 918.041 294.246 0.96056 + vertex 912.691 304.219 0.497005 + vertex 918.938 303.753 0.960715 + endloop + endfacet + facet normal 0.0738671 -0.00213114 -0.997266 + outer loop + vertex 912.691 304.219 0.497005 + vertex 912.973 313.714 0.497597 + vertex 918.938 303.753 0.960715 + endloop + endfacet + facet normal 0.0741803 -0.00194254 -0.997243 + outer loop + vertex 918.938 303.753 0.960715 + vertex 912.973 313.714 0.497597 + vertex 919.201 313.454 0.961414 + endloop + endfacet + facet normal 0.0743388 0.00187907 -0.997231 + outer loop + vertex 912.973 313.714 0.497597 + vertex 912.725 323.348 0.497288 + vertex 919.201 313.454 0.961414 + endloop + endfacet + facet normal 0.0750017 0.00231531 -0.997181 + outer loop + vertex 919.201 313.454 0.961414 + vertex 912.725 323.348 0.497288 + vertex 918.889 323.325 0.960884 + endloop + endfacet + facet normal 0.075013 0.00562199 -0.997167 + outer loop + vertex 912.725 323.348 0.497288 + vertex 912.009 333.042 0.498107 + vertex 918.889 323.325 0.960884 + endloop + endfacet + facet normal 0.076026 0.00634311 -0.997086 + outer loop + vertex 918.889 323.325 0.960884 + vertex 912.009 333.042 0.498107 + vertex 918.067 333.191 0.960906 + endloop + endfacet + facet normal 0.0759693 0.00861683 -0.997073 + outer loop + vertex 912.009 333.042 0.498107 + vertex 910.891 342.71 0.496458 + vertex 918.067 333.191 0.960906 + endloop + endfacet + facet normal 0.0771343 0.00949977 -0.996975 + outer loop + vertex 918.067 333.191 0.960906 + vertex 910.891 342.71 0.496458 + vertex 916.815 342.975 0.957285 + endloop + endfacet + facet normal 0.0770506 0.0113458 -0.996963 + outer loop + vertex 910.891 342.71 0.496458 + vertex 909.427 352.344 0.492948 + vertex 916.815 342.975 0.957285 + endloop + endfacet + facet normal 0.0790306 0.0129158 -0.996789 + outer loop + vertex 916.815 342.975 0.957285 + vertex 909.427 352.344 0.492948 + vertex 915.191 352.725 0.954875 + endloop + endfacet + facet normal 0.0789502 0.0141195 -0.996779 + outer loop + vertex 909.427 352.344 0.492948 + vertex 907.664 361.971 0.489691 + vertex 915.191 352.725 0.954875 + endloop + endfacet + facet normal 0.0831154 0.0175297 -0.996386 + outer loop + vertex 915.191 352.725 0.954875 + vertex 907.664 361.971 0.489691 + vertex 913.246 362.489 0.964451 + endloop + endfacet + facet normal 0.083106 0.0176299 -0.996385 + outer loop + vertex 907.664 361.971 0.489691 + vertex 905.645 371.596 0.49155 + vertex 913.246 362.489 0.964451 + endloop + endfacet + facet normal 0.0879864 0.0217298 -0.995885 + outer loop + vertex 913.246 362.489 0.964451 + vertex 905.645 371.596 0.49155 + vertex 911.027 372.261 0.981559 + endloop + endfacet + facet normal 0.088098 0.0208333 -0.995894 + outer loop + vertex 905.645 371.596 0.49155 + vertex 903.406 381.18 0.493992 + vertex 911.027 372.261 0.981559 + endloop + endfacet + facet normal 0.0914378 0.0237067 -0.995529 + outer loop + vertex 911.027 372.261 0.981559 + vertex 903.406 381.18 0.493992 + vertex 908.556 381.998 0.986477 + endloop + endfacet + facet normal 0.0914717 0.0234945 -0.99553 + outer loop + vertex 903.406 381.18 0.493992 + vertex 900.986 390.673 0.49564 + vertex 908.556 381.998 0.986477 + endloop + endfacet + facet normal 0.0950696 0.0266576 -0.995114 + outer loop + vertex 908.556 381.998 0.986477 + vertex 900.986 390.673 0.49564 + vertex 905.889 391.59 0.988669 + endloop + endfacet + facet normal 0.0951416 0.0262742 -0.995117 + outer loop + vertex 900.986 390.673 0.49564 + vertex 898.42 400.047 0.497889 + vertex 905.889 391.59 0.988669 + endloop + endfacet + facet normal 0.098518 0.0292798 -0.994704 + outer loop + vertex 905.889 391.59 0.988669 + vertex 898.42 400.047 0.497889 + vertex 903.079 401.017 0.987815 + endloop + endfacet + facet normal 0.0986334 0.0287282 -0.994709 + outer loop + vertex 898.42 400.047 0.497889 + vertex 895.729 409.334 0.499276 + vertex 903.079 401.017 0.987815 + endloop + endfacet + facet normal 0.104361 0.0338331 -0.993964 + outer loop + vertex 903.079 401.017 0.987815 + vertex 895.729 409.334 0.499276 + vertex 900.126 410.395 0.997051 + endloop + endfacet + facet normal 0.104842 0.0318443 -0.993979 + outer loop + vertex 895.729 409.334 0.499276 + vertex 892.924 418.575 0.499466 + vertex 900.126 410.395 0.997051 + endloop + endfacet + facet normal 0.109265 0.0357755 -0.993369 + outer loop + vertex 900.126 410.395 0.997051 + vertex 892.924 418.575 0.499466 + vertex 897.037 419.751 0.994233 + endloop + endfacet + facet normal 0.109628 0.0345101 -0.993373 + outer loop + vertex 892.924 418.575 0.499466 + vertex 890.031 427.765 0.499443 + vertex 897.037 419.751 0.994233 + endloop + endfacet + facet normal 0.115317 0.0395359 -0.992542 + outer loop + vertex 897.037 419.751 0.994233 + vertex 890.031 427.765 0.499443 + vertex 893.873 429 0.994921 + endloop + endfacet + facet normal 0.115853 0.0378697 -0.992544 + outer loop + vertex 890.031 427.765 0.499443 + vertex 887.082 436.897 0.50356 + vertex 893.873 429 0.994921 + endloop + endfacet + facet normal 0.122254 0.0434357 -0.991548 + outer loop + vertex 893.873 429 0.994921 + vertex 887.082 436.897 0.50356 + vertex 890.66 438.159 1.00003 + endloop + endfacet + facet normal 0.123073 0.041112 -0.991546 + outer loop + vertex 887.082 436.897 0.50356 + vertex 884.091 445.972 0.508654 + vertex 890.66 438.159 1.00003 + endloop + endfacet + facet normal 0.129993 0.0470021 -0.9904 + outer loop + vertex 890.66 438.159 1.00003 + vertex 884.091 445.972 0.508654 + vertex 887.381 447.304 1.00367 + endloop + endfacet + facet normal 0.131167 0.0440956 -0.990379 + outer loop + vertex 884.091 445.972 0.508654 + vertex 881.048 454.961 0.505806 + vertex 887.381 447.304 1.00367 + endloop + endfacet + facet normal 0.13508 0.047377 -0.989701 + outer loop + vertex 887.381 447.304 1.00367 + vertex 881.048 454.961 0.505806 + vertex 883.955 456.378 0.97052 + endloop + endfacet + facet normal 0.136433 0.0445858 -0.989646 + outer loop + vertex 881.048 454.961 0.505806 + vertex 877.911 463.813 0.472195 + vertex 883.955 456.378 0.97052 + endloop + endfacet + facet normal 0.140292 0.0477699 -0.988957 + outer loop + vertex 883.955 456.378 0.97052 + vertex 877.911 463.813 0.472195 + vertex 880.208 465.209 0.865458 + endloop + endfacet + facet normal 0.141021 0.0465581 -0.988911 + outer loop + vertex 877.911 463.813 0.472195 + vertex 874.808 472.561 0.441496 + vertex 880.208 465.209 0.865458 + endloop + endfacet + facet normal 0.169161 0.0675524 -0.983271 + outer loop + vertex 880.208 465.209 0.865458 + vertex 874.808 472.561 0.441496 + vertex 877.184 473.498 0.914723 + endloop + endfacet + facet normal 0.173143 0.0574231 -0.983221 + outer loop + vertex 874.808 472.561 0.441496 + vertex 871.884 481.529 0.450477 + vertex 877.184 473.498 0.914723 + endloop + endfacet + facet normal 0.19881 0.0747099 -0.977186 + outer loop + vertex 877.184 473.498 0.914723 + vertex 871.884 481.529 0.450477 + vertex 874.076 482.42 0.964467 + endloop + endfacet + facet normal 0.208819 0.0498124 -0.976685 + outer loop + vertex 871.884 481.529 0.450477 + vertex 869.378 490.962 0.395619 + vertex 874.076 482.42 0.964467 + endloop + endfacet + facet normal 0.187635 0.0378396 -0.98151 + outer loop + vertex 874.076 482.42 0.964467 + vertex 869.378 490.962 0.395619 + vertex 871.294 491.673 0.789366 + endloop + endfacet + facet normal 0.0787076 0.0264954 -0.996546 + outer loop + vertex 887.082 436.897 0.50356 + vertex 880.564 445.038 0.205286 + vertex 884.091 445.972 0.508654 + endloop + endfacet + facet normal 0.0790391 0.0252449 -0.996552 + outer loop + vertex 880.564 445.038 0.205286 + vertex 877.781 454 0.211553 + vertex 884.091 445.972 0.508654 + endloop + endfacet + facet normal 0.0816982 0.0273451 -0.996282 + outer loop + vertex 884.091 445.972 0.508654 + vertex 877.781 454 0.211553 + vertex 881.048 454.961 0.505806 + endloop + endfacet + facet normal 0.0822055 0.025622 -0.996286 + outer loop + vertex 877.781 454 0.211553 + vertex 874.966 462.857 0.207094 + vertex 881.048 454.961 0.505806 + endloop + endfacet + facet normal 0.0815468 0.0251122 -0.996353 + outer loop + vertex 881.048 454.961 0.505806 + vertex 874.966 462.857 0.207094 + vertex 877.911 463.813 0.472195 + endloop + endfacet + facet normal 0.0818218 0.0242647 -0.996352 + outer loop + vertex 874.966 462.857 0.207094 + vertex 872.127 471.668 0.188517 + vertex 877.911 463.813 0.472195 + endloop + endfacet + facet normal 0.0851107 0.0266986 -0.996014 + outer loop + vertex 877.911 463.813 0.472195 + vertex 872.127 471.668 0.188517 + vertex 874.808 472.561 0.441496 + endloop + endfacet + facet normal 0.0856681 0.0250248 -0.996009 + outer loop + vertex 872.127 471.668 0.188517 + vertex 869.419 480.676 0.181878 + vertex 874.808 472.561 0.441496 + endloop + endfacet + facet normal 0.097072 0.0326382 -0.994742 + outer loop + vertex 874.808 472.561 0.441496 + vertex 869.419 480.676 0.181878 + vertex 871.884 481.529 0.450477 + endloop + endfacet + facet normal 0.100473 0.0227782 -0.994679 + outer loop + vertex 869.419 480.676 0.181878 + vertex 867.28 490.214 0.184242 + vertex 871.884 481.529 0.450477 + endloop + endfacet + facet normal 0.0935012 0.0190584 -0.995437 + outer loop + vertex 871.884 481.529 0.450477 + vertex 867.28 490.214 0.184242 + vertex 869.378 490.962 0.395619 + endloop + endfacet + facet normal 0.0427253 0.00982899 -0.999039 + outer loop + vertex 869.419 480.676 0.181878 + vertex 864.714 489.33 0.0658062 + vertex 867.28 490.214 0.184242 + endloop + endfacet + facet normal 0.0412869 0.00904606 -0.999106 + outer loop + vertex 866.602 479.867 0.0581461 + vertex 864.714 489.33 0.0658062 + vertex 869.419 480.676 0.181878 + endloop + endfacet + facet normal 0.0161833 0.00403815 -0.999861 + outer loop + vertex 866.602 479.867 0.0581461 + vertex 861.845 488.371 0.0155097 + vertex 864.714 489.33 0.0658062 + endloop + endfacet + facet normal 0.0136765 0.00263597 -0.999903 + outer loop + vertex 863.44 479.044 0.0127336 + vertex 861.845 488.371 0.0155097 + vertex 866.602 479.867 0.0581461 + endloop + endfacet + facet normal 0.0135773 0.00301708 -0.999903 + outer loop + vertex 869.056 470.938 0.0645225 + vertex 863.44 479.044 0.0127336 + vertex 866.602 479.867 0.0581461 + endloop + endfacet + facet normal 0.038021 0.00973484 -0.99923 + outer loop + vertex 869.056 470.938 0.0645225 + vertex 866.602 479.867 0.0581461 + vertex 872.127 471.668 0.188517 + endloop + endfacet + facet normal 0.013701 0.00310279 -0.999901 + outer loop + vertex 865.684 470.226 0.0161161 + vertex 863.44 479.044 0.0127336 + vertex 869.056 470.938 0.0645225 + endloop + endfacet + facet normal 0.0135728 0.00370974 -0.999901 + outer loop + vertex 871.657 462.162 0.0672775 + vertex 865.684 470.226 0.0161161 + vertex 869.056 470.938 0.0645225 + endloop + endfacet + facet normal 0.039801 0.0114853 -0.999142 + outer loop + vertex 871.657 462.162 0.0672775 + vertex 869.056 470.938 0.0645225 + vertex 874.966 462.857 0.207094 + endloop + endfacet + facet normal 0.0145872 0.00446125 -0.999884 + outer loop + vertex 868.095 461.505 0.0123865 + vertex 865.684 470.226 0.0161161 + vertex 871.657 462.162 0.0672775 + endloop + endfacet + facet normal 0.0145135 0.00486125 -0.999883 + outer loop + vertex 874.255 453.327 0.0620335 + vertex 868.095 461.505 0.0123865 + vertex 871.657 462.162 0.0672775 + endloop + endfacet + facet normal 0.0400093 0.0123579 -0.999123 + outer loop + vertex 874.255 453.327 0.0620335 + vertex 871.657 462.162 0.0672775 + vertex 877.781 454 0.211553 + endloop + endfacet + facet normal 0.0142312 0.0046486 -0.999888 + outer loop + vertex 870.529 452.72 0.00617226 + vertex 868.095 461.505 0.0123865 + vertex 874.255 453.327 0.0620335 + endloop + endfacet + facet normal 0.0141747 0.00499528 -0.999887 + outer loop + vertex 876.843 444.409 0.0541719 + vertex 870.529 452.72 0.00617226 + vertex 874.255 453.327 0.0620335 + endloop + endfacet + facet normal 0.0385369 0.0120652 -0.999184 + outer loop + vertex 876.843 444.409 0.0541719 + vertex 874.255 453.327 0.0620335 + vertex 880.564 445.038 0.205286 + endloop + endfacet + facet normal 0.0384756 0.0124268 -0.999182 + outer loop + vertex 883.323 436.007 0.199188 + vertex 876.843 444.409 0.0541719 + vertex 880.564 445.038 0.205286 + endloop + endfacet + facet normal 0.0360629 0.0105642 -0.999294 + outer loop + vertex 879.408 435.443 0.0519631 + vertex 876.843 444.409 0.0541719 + vertex 883.323 436.007 0.199188 + endloop + endfacet + facet normal 0.0360145 0.0109 -0.999292 + outer loop + vertex 886.042 426.937 0.198257 + vertex 879.408 435.443 0.0519631 + vertex 883.323 436.007 0.199188 + endloop + endfacet + facet normal 0.070864 0.0213479 -0.997258 + outer loop + vertex 886.042 426.937 0.198257 + vertex 883.323 436.007 0.199188 + vertex 890.031 427.765 0.499443 + endloop + endfacet + facet normal 0.0337275 0.00911477 -0.99939 + outer loop + vertex 881.931 426.451 0.0550793 + vertex 879.408 435.443 0.0519631 + vertex 886.042 426.937 0.198257 + endloop + endfacet + facet normal 0.0336659 0.00963517 -0.999387 + outer loop + vertex 888.7 417.832 0.199999 + vertex 881.931 426.451 0.0550793 + vertex 886.042 426.937 0.198257 + endloop + endfacet + facet normal 0.0672898 0.0194496 -0.997544 + outer loop + vertex 888.7 417.832 0.199999 + vertex 886.042 426.937 0.198257 + vertex 892.924 418.575 0.499466 + endloop + endfacet + facet normal 0.0324687 0.00869418 -0.999435 + outer loop + vertex 884.394 417.428 0.0566049 + vertex 881.931 426.451 0.0550793 + vertex 888.7 417.832 0.199999 + endloop + endfacet + facet normal 0.032437 0.00903173 -0.999433 + outer loop + vertex 891.274 408.682 0.200873 + vertex 884.394 417.428 0.0566049 + vertex 888.7 417.832 0.199999 + endloop + endfacet + facet normal 0.0642014 0.0179699 -0.997775 + outer loop + vertex 891.274 408.682 0.200873 + vertex 888.7 417.832 0.199999 + vertex 895.729 409.334 0.499276 + endloop + endfacet + facet normal 0.0312899 0.00812864 -0.999477 + outer loop + vertex 886.784 408.355 0.0576326 + vertex 884.394 417.428 0.0566049 + vertex 891.274 408.682 0.200873 + endloop + endfacet + facet normal 0.0312718 0.00837679 -0.999476 + outer loop + vertex 893.75 399.469 0.201107 + vertex 886.784 408.355 0.0576326 + vertex 891.274 408.682 0.200873 + endloop + endfacet + facet normal 0.0613754 0.0164651 -0.997979 + outer loop + vertex 893.75 399.469 0.201107 + vertex 891.274 408.682 0.200873 + vertex 898.42 400.047 0.497889 + endloop + endfacet + facet normal 0.0302673 0.00758876 -0.999513 + outer loop + vertex 889.085 399.212 0.0579032 + vertex 886.784 408.355 0.0576326 + vertex 893.75 399.469 0.201107 + endloop + endfacet + facet normal 0.0302634 0.00765927 -0.999513 + outer loop + vertex 896.11 390.168 0.201294 + vertex 889.085 399.212 0.0579032 + vertex 893.75 399.469 0.201107 + endloop + endfacet + facet normal 0.0587178 0.0148796 -0.998164 + outer loop + vertex 896.11 390.168 0.201294 + vertex 893.75 399.469 0.201107 + vertex 900.986 390.673 0.49564 + endloop + endfacet + facet normal 0.0292425 0.00686574 -0.999549 + outer loop + vertex 891.281 389.988 0.0587739 + vertex 889.085 399.212 0.0579032 + vertex 896.11 390.168 0.201294 + endloop + endfacet + facet normal 0.0292441 0.00682328 -0.999549 + outer loop + vertex 898.333 380.773 0.202206 + vertex 891.281 389.988 0.0587739 + vertex 896.11 390.168 0.201294 + endloop + endfacet + facet normal 0.0563605 0.0132402 -0.998323 + outer loop + vertex 898.333 380.773 0.202206 + vertex 896.11 390.168 0.201294 + vertex 903.406 381.18 0.493992 + endloop + endfacet + facet normal 0.0280038 0.00587339 -0.999591 + outer loop + vertex 893.349 380.679 0.0620175 + vertex 891.281 389.988 0.0587739 + vertex 898.333 380.773 0.202206 + endloop + endfacet + facet normal 0.0280032 0.00590554 -0.99959 + outer loop + vertex 900.389 371.304 0.203863 + vertex 893.349 380.679 0.0620175 + vertex 898.333 380.773 0.202206 + endloop + endfacet + facet normal 0.0540138 0.0115536 -0.998473 + outer loop + vertex 900.389 371.304 0.203863 + vertex 898.333 380.773 0.202206 + vertex 905.645 371.596 0.49155 + endloop + endfacet + facet normal 0.0272662 0.0053518 -0.999614 + outer loop + vertex 895.262 371.307 0.0640199 + vertex 893.349 380.679 0.0620175 + vertex 900.389 371.304 0.203863 + endloop + endfacet + facet normal 0.027266 0.00489418 -0.999616 + outer loop + vertex 902.246 361.801 0.207975 + vertex 895.262 371.307 0.0640199 + vertex 900.389 371.304 0.203863 + endloop + endfacet + facet normal 0.0516158 0.00965158 -0.99862 + outer loop + vertex 902.246 361.801 0.207975 + vertex 900.389 371.304 0.203863 + vertex 907.664 361.971 0.489691 + endloop + endfacet + facet normal 0.0272368 0.00487267 -0.999617 + outer loop + vertex 896.99 361.903 0.0652748 + vertex 895.262 371.307 0.0640199 + vertex 902.246 361.801 0.207975 + endloop + endfacet + facet normal 0.0272273 0.00438429 -0.99962 + outer loop + vertex 903.866 352.288 0.210373 + vertex 896.99 361.903 0.0652748 + vertex 902.246 361.801 0.207975 + endloop + endfacet + facet normal 0.0506573 0.00837422 -0.998681 + outer loop + vertex 903.866 352.288 0.210373 + vertex 902.246 361.801 0.207975 + vertex 909.427 352.344 0.492948 + endloop + endfacet + facet normal 0.026967 0.00419809 -0.999628 + outer loop + vertex 898.502 352.494 0.0665305 + vertex 896.99 361.903 0.0652748 + vertex 903.866 352.288 0.210373 + endloop + endfacet + facet normal 0.0269521 0.00380909 -0.999629 + outer loop + vertex 905.21 342.764 0.210343 + vertex 898.502 352.494 0.0665305 + vertex 903.866 352.288 0.210373 + endloop + endfacet + facet normal 0.0503686 0.00711567 -0.998705 + outer loop + vertex 905.21 342.764 0.210343 + vertex 903.866 352.288 0.210373 + vertex 910.891 342.71 0.496458 + endloop + endfacet + facet normal 0.0265675 0.0035437 -0.999641 + outer loop + vertex 899.76 343.081 0.0666081 + vertex 898.502 352.494 0.0665305 + vertex 905.21 342.764 0.210343 + endloop + endfacet + facet normal 0.0265227 0.00277148 -0.999644 + outer loop + vertex 906.237 333.226 0.211125 + vertex 899.76 343.081 0.0666081 + vertex 905.21 342.764 0.210343 + endloop + endfacet + facet normal 0.0498186 0.00527792 -0.998744 + outer loop + vertex 906.237 333.226 0.211125 + vertex 905.21 342.764 0.210343 + vertex 912.009 333.042 0.498107 + endloop + endfacet + facet normal 0.0264227 0.00270573 -0.999647 + outer loop + vertex 900.724 333.666 0.0666074 + vertex 899.76 343.081 0.0666081 + vertex 906.237 333.226 0.211125 + endloop + endfacet + facet normal 0.026347 0.00175763 -0.999651 + outer loop + vertex 906.892 323.697 0.211633 + vertex 900.724 333.666 0.0666074 + vertex 906.237 333.226 0.211125 + endloop + endfacet + facet normal 0.0491076 0.00332209 -0.998788 + outer loop + vertex 906.892 323.697 0.211633 + vertex 906.237 333.226 0.211125 + vertex 912.725 323.348 0.497288 + endloop + endfacet + facet normal 0.0263566 0.00176354 -0.999651 + outer loop + vertex 901.346 324.278 0.0664482 + vertex 900.724 333.666 0.0666074 + vertex 906.892 323.697 0.211633 + endloop + endfacet + facet normal 0.0262503 0.000748315 -0.999655 + outer loop + vertex 907.118 314.241 0.210493 + vertex 901.346 324.278 0.0664482 + vertex 906.892 323.697 0.211633 + endloop + endfacet + facet normal 0.0490932 0.00129449 -0.998793 + outer loop + vertex 907.118 314.241 0.210493 + vertex 906.892 323.697 0.211633 + vertex 912.973 313.714 0.497597 + endloop + endfacet + facet normal 0.026073 0.000646328 -0.99966 + outer loop + vertex 901.57 314.974 0.0662778 + vertex 901.346 324.278 0.0664482 + vertex 907.118 314.241 0.210493 + endloop + endfacet + facet normal 0.025862 -0.000952429 -0.999665 + outer loop + vertex 906.846 304.917 0.212356 + vertex 901.57 314.974 0.0662778 + vertex 907.118 314.241 0.210493 + endloop + endfacet + facet normal 0.048455 -0.00160979 -0.998824 + outer loop + vertex 906.846 304.917 0.212356 + vertex 907.118 314.241 0.210493 + vertex 912.691 304.219 0.497005 + endloop + endfacet + facet normal 0.02657 -0.000580727 -0.999647 + outer loop + vertex 901.335 305.798 0.0653655 + vertex 901.57 314.974 0.0662778 + vertex 906.846 304.917 0.212356 + endloop + endfacet + facet normal 0.0262916 -0.00232162 -0.999652 + outer loop + vertex 906.031 295.73 0.212241 + vertex 901.335 305.798 0.0653655 + vertex 906.846 304.917 0.212356 + endloop + endfacet + facet normal 0.0484015 -0.00428448 -0.998819 + outer loop + vertex 906.031 295.73 0.212241 + vertex 906.846 304.917 0.212356 + vertex 911.82 294.861 0.496486 + endloop + endfacet + facet normal 0.0264507 -0.0022474 -0.999648 + outer loop + vertex 900.587 296.776 0.065837 + vertex 901.335 305.798 0.0653655 + vertex 906.031 295.73 0.212241 + endloop + endfacet + facet normal 0.0261524 -0.0037996 -0.999651 + outer loop + vertex 904.652 286.696 0.210504 + vertex 900.587 296.776 0.065837 + vertex 906.031 295.73 0.212241 + endloop + endfacet + facet normal 0.0492739 -0.00732894 -0.998758 + outer loop + vertex 904.652 286.696 0.210504 + vertex 906.031 295.73 0.212241 + vertex 910.325 285.617 0.498307 + endloop + endfacet + facet normal 0.0262768 -0.00374941 -0.999648 + outer loop + vertex 899.314 287.928 0.0655775 + vertex 900.587 296.776 0.065837 + vertex 904.652 286.696 0.210504 + endloop + endfacet + facet normal 0.0257832 -0.00588806 -0.99965 + outer loop + vertex 902.718 277.88 0.212545 + vertex 899.314 287.928 0.0655775 + vertex 904.652 286.696 0.210504 + endloop + endfacet + facet normal 0.0487366 -0.0109236 -0.998752 + outer loop + vertex 902.718 277.88 0.212545 + vertex 904.652 286.696 0.210504 + vertex 908.239 276.549 0.496514 + endloop + endfacet + facet normal 0.0264326 -0.00566789 -0.999635 + outer loop + vertex 897.525 279.31 0.0671353 + vertex 899.314 287.928 0.0655775 + vertex 902.718 277.88 0.212545 + endloop + endfacet + facet normal 0.025997 -0.0072495 -0.999636 + outer loop + vertex 900.302 269.372 0.211413 + vertex 897.525 279.31 0.0671353 + vertex 902.718 277.88 0.212545 + endloop + endfacet + facet normal 0.0496578 -0.0139687 -0.998669 + outer loop + vertex 900.302 269.372 0.211413 + vertex 902.718 277.88 0.212545 + vertex 905.618 267.795 0.497837 + endloop + endfacet + facet normal 0.026508 -0.00710655 -0.999623 + outer loop + vertex 895.287 271.009 0.0667891 + vertex 897.525 279.31 0.0671353 + vertex 900.302 269.372 0.211413 + endloop + endfacet + facet normal 0.0258358 -0.00916528 -0.999624 + outer loop + vertex 897.438 261.241 0.21195 + vertex 895.287 271.009 0.0667891 + vertex 900.302 269.372 0.211413 + endloop + endfacet + facet normal 0.0496719 -0.0175602 -0.998611 + outer loop + vertex 897.438 261.241 0.21195 + vertex 900.302 269.372 0.211413 + vertex 902.537 259.428 0.497436 + endloop + endfacet + facet normal 0.0270677 -0.00889357 -0.999594 + outer loop + vertex 892.629 263.084 0.0653314 + vertex 895.287 271.009 0.0667891 + vertex 897.438 261.241 0.21195 + endloop + endfacet + facet normal 0.0262964 -0.0109057 -0.999595 + outer loop + vertex 894.132 253.445 0.210031 + vertex 892.629 263.084 0.0653314 + vertex 897.438 261.241 0.21195 + endloop + endfacet + facet normal 0.050183 -0.0210357 -0.998518 + outer loop + vertex 894.132 253.445 0.210031 + vertex 897.438 261.241 0.21195 + vertex 898.997 251.412 0.497401 + endloop + endfacet + facet normal 0.0265412 -0.0108674 -0.999589 + outer loop + vertex 889.514 255.484 0.0652548 + vertex 892.629 263.084 0.0653314 + vertex 894.132 253.445 0.210031 + endloop + endfacet + facet normal 0.0257017 -0.012769 -0.999588 + outer loop + vertex 890.32 245.849 0.20906 + vertex 889.514 255.484 0.0652548 + vertex 894.132 253.445 0.210031 + endloop + endfacet + facet normal 0.0497575 -0.02484 -0.998452 + outer loop + vertex 890.32 245.849 0.20906 + vertex 894.132 253.445 0.210031 + vertex 894.963 243.613 0.496059 + endloop + endfacet + facet normal 0.0267235 -0.0126831 -0.999562 + outer loop + vertex 885.906 248.056 0.0630468 + vertex 889.514 255.484 0.0652548 + vertex 890.32 245.849 0.20906 + endloop + endfacet + facet normal 0.0255591 -0.0150116 -0.999561 + outer loop + vertex 885.986 238.326 0.21122 + vertex 885.906 248.056 0.0630468 + vertex 890.32 245.849 0.20906 + endloop + endfacet + facet normal 0.0485398 -0.0282506 -0.998422 + outer loop + vertex 885.986 238.326 0.21122 + vertex 890.32 245.849 0.20906 + vertex 890.402 235.912 0.494195 + endloop + endfacet + facet normal 0.0261683 -0.0150064 -0.999545 + outer loop + vertex 881.782 240.682 0.0657871 + vertex 885.906 248.056 0.0630468 + vertex 885.986 238.326 0.21122 + endloop + endfacet + facet normal 0.0252173 -0.016703 -0.999542 + outer loop + vertex 881.292 230.974 0.215646 + vertex 881.782 240.682 0.0657871 + vertex 885.986 238.326 0.21122 + endloop + endfacet + facet normal 0.0487614 -0.0317352 -0.998306 + outer loop + vertex 881.292 230.974 0.215646 + vertex 885.986 238.326 0.21122 + vertex 885.392 228.332 0.499886 + endloop + endfacet + facet normal 0.0259395 -0.0167392 -0.999523 + outer loop + vertex 877.356 233.511 0.0709929 + vertex 881.782 240.682 0.0657871 + vertex 881.292 230.974 0.215646 + endloop + endfacet + facet normal 0.0250991 -0.0180427 -0.999522 + outer loop + vertex 876.576 224.223 0.219082 + vertex 877.356 233.511 0.0709929 + vertex 881.292 230.974 0.215646 + endloop + endfacet + facet normal 0.0490479 -0.0347725 -0.998191 + outer loop + vertex 876.576 224.223 0.219082 + vertex 881.292 230.974 0.215646 + vertex 880.263 221.232 0.504423 + endloop + endfacet + facet normal 0.0255187 -0.0180778 -0.999511 + outer loop + vertex 872.947 226.992 0.0763461 + vertex 877.356 233.511 0.0709929 + vertex 876.576 224.223 0.219082 + endloop + endfacet + facet normal 0.0257298 -0.017801 -0.99951 + outer loop + vertex 872.082 218.525 0.204872 + vertex 872.947 226.992 0.0763461 + vertex 876.576 224.223 0.219082 + endloop + endfacet + facet normal 0.00945691 -0.00721627 -0.999929 + outer loop + vertex 872.947 226.992 0.0763461 + vertex 873.356 235.837 0.0163814 + vertex 877.356 233.511 0.0709929 + endloop + endfacet + facet normal 0.00977286 -0.00667295 -0.99993 + outer loop + vertex 873.356 235.837 0.0163814 + vertex 877.574 242.852 0.0107946 + vertex 877.356 233.511 0.0709929 + endloop + endfacet + facet normal 0.00212124 -0.00207199 -0.999996 + outer loop + vertex 873.356 235.837 0.0163814 + vertex 873.227 244.725 -0.00230819 + vertex 877.574 242.852 0.0107946 + endloop + endfacet + facet normal 0.00241556 -0.00138894 -0.999996 + outer loop + vertex 873.227 244.725 -0.00230819 + vertex 877.009 251.829 -0.00303809 + vertex 877.574 242.852 0.0107946 + endloop + endfacet + facet normal 0.00219812 -0.00140261 -0.999997 + outer loop + vertex 877.574 242.852 0.0107946 + vertex 877.009 251.829 -0.00303809 + vertex 881.508 250.089 0.00929118 + endloop + endfacet + facet normal 0.0101225 -0.00571019 -0.999932 + outer loop + vertex 877.574 242.852 0.0107946 + vertex 881.508 250.089 0.00929118 + vertex 881.782 240.682 0.0657871 + endloop + endfacet + facet normal 0.00236685 -0.000966527 -0.999997 + outer loop + vertex 877.009 251.829 -0.00303809 + vertex 880.327 258.974 -0.00209164 + vertex 881.508 250.089 0.00929118 + endloop + endfacet + facet normal 0.00221465 -0.000986753 -0.999997 + outer loop + vertex 881.508 250.089 0.00929118 + vertex 880.327 258.974 -0.00209164 + vertex 884.961 257.373 0.00975167 + endloop + endfacet + facet normal 0.0100483 -0.00470067 -0.999938 + outer loop + vertex 881.508 250.089 0.00929118 + vertex 884.961 257.373 0.00975167 + vertex 885.906 248.056 0.0630468 + endloop + endfacet + facet normal 0.00230259 -0.00073218 -0.999997 + outer loop + vertex 880.327 258.974 -0.00209164 + vertex 883.142 266.252 -0.000937953 + vertex 884.961 257.373 0.00975167 + endloop + endfacet + facet normal 0.00241157 -0.000709855 -0.999997 + outer loop + vertex 884.961 257.373 0.00975167 + vertex 883.142 266.252 -0.000937953 + vertex 887.897 264.802 0.0115571 + endloop + endfacet + facet normal 0.0105595 -0.00392934 -0.999937 + outer loop + vertex 884.961 257.373 0.00975167 + vertex 887.897 264.802 0.0115571 + vertex 889.514 255.484 0.0652548 + endloop + endfacet + facet normal 0.00242885 -0.000653198 -0.999997 + outer loop + vertex 883.142 266.252 -0.000937953 + vertex 885.515 273.836 -0.000127673 + vertex 887.897 264.802 0.0115571 + endloop + endfacet + facet normal 0.00220594 -0.000711963 -0.999997 + outer loop + vertex 887.897 264.802 0.0115571 + vertex 885.515 273.836 -0.000127673 + vertex 890.403 272.547 0.0115714 + endloop + endfacet + facet normal 0.0101687 -0.00328859 -0.999943 + outer loop + vertex 887.897 264.802 0.0115571 + vertex 890.403 272.547 0.0115714 + vertex 892.629 263.084 0.0653314 + endloop + endfacet + facet normal 0.00224726 -0.000555219 -0.999997 + outer loop + vertex 885.515 273.836 -0.000127673 + vertex 887.491 281.798 -0.00010853 + vertex 890.403 272.547 0.0115714 + endloop + endfacet + facet normal 0.00226043 -0.000551073 -0.999997 + outer loop + vertex 890.403 272.547 0.0115714 + vertex 887.491 281.798 -0.00010853 + vertex 892.49 280.669 0.0118144 + endloop + endfacet + facet normal 0.0104676 -0.00266055 -0.999942 + outer loop + vertex 890.403 272.547 0.0115714 + vertex 892.49 280.669 0.0118144 + vertex 895.287 271.009 0.0667891 + endloop + endfacet + facet normal 0.00228423 -0.000445721 -0.999997 + outer loop + vertex 887.491 281.798 -0.00010853 + vertex 889.055 290.095 -0.000235254 + vertex 892.49 280.669 0.0118144 + endloop + endfacet + facet normal 0.00230204 -0.000439229 -0.999997 + outer loop + vertex 892.49 280.669 0.0118144 + vertex 889.055 290.095 -0.000235254 + vertex 894.147 289.118 0.0119158 + endloop + endfacet + facet normal 0.0104381 -0.00203402 -0.999943 + outer loop + vertex 892.49 280.669 0.0118144 + vertex 894.147 289.118 0.0119158 + vertex 897.525 279.31 0.0671353 + endloop + endfacet + facet normal 0.00232505 -0.000319302 -0.999997 + outer loop + vertex 889.055 290.095 -0.000235254 + vertex 890.165 298.641 -0.000382994 + vertex 894.147 289.118 0.0119158 + endloop + endfacet + facet normal 0.00222474 -0.000361243 -0.999997 + outer loop + vertex 894.147 289.118 0.0119158 + vertex 890.165 298.641 -0.000382994 + vertex 895.329 297.808 0.0114085 + endloop + endfacet + facet normal 0.0100549 -0.00142716 -0.999948 + outer loop + vertex 894.147 289.118 0.0119158 + vertex 895.329 297.808 0.0114085 + vertex 899.314 287.928 0.0655775 + endloop + endfacet + facet normal 0.00225259 -0.000188657 -0.999997 + outer loop + vertex 890.165 298.641 -0.000382994 + vertex 890.804 307.379 -0.000592307 + vertex 895.329 297.808 0.0114085 + endloop + endfacet + facet normal 0.00234038 -0.000147147 -0.999997 + outer loop + vertex 895.329 297.808 0.0114085 + vertex 890.804 307.379 -0.000592307 + vertex 896.01 306.68 0.0116968 + endloop + endfacet + facet normal 0.0102053 -0.000750846 -0.999948 + outer loop + vertex 895.329 297.808 0.0114085 + vertex 896.01 306.68 0.0116968 + vertex 900.587 296.776 0.065837 + endloop + endfacet + facet normal 0.00235579 -3.24122e-05 -0.999997 + outer loop + vertex 890.804 307.379 -0.000592307 + vertex 890.984 316.285 -0.000454767 + vertex 896.01 306.68 0.0116968 + endloop + endfacet + facet normal 0.00231559 -5.34475e-05 -0.999997 + outer loop + vertex 896.01 306.68 0.0116968 + vertex 890.984 316.285 -0.000454767 + vertex 896.216 315.716 0.0116901 + endloop + endfacet + facet normal 0.0100404 -0.000229297 -0.99995 + outer loop + vertex 896.01 306.68 0.0116968 + vertex 896.216 315.716 0.0116901 + vertex 901.335 305.798 0.0653655 + endloop + endfacet + facet normal 0.00232576 4.00335e-05 -0.999997 + outer loop + vertex 890.984 316.285 -0.000454767 + vertex 890.759 325.335 -0.000617243 + vertex 896.216 315.716 0.0116901 + endloop + endfacet + facet normal 0.0023101 3.11468e-05 -0.999997 + outer loop + vertex 896.216 315.716 0.0116901 + vertex 890.759 325.335 -0.000617243 + vertex 895.989 324.887 0.011451 + endloop + endfacet + facet normal 0.0102265 0.000227232 -0.999948 + outer loop + vertex 896.216 315.716 0.0116901 + vertex 895.989 324.887 0.011451 + vertex 901.57 314.974 0.0662778 + endloop + endfacet + facet normal 0.00232106 0.000159051 -0.999997 + outer loop + vertex 890.759 325.335 -0.000617243 + vertex 890.179 334.481 -0.000508267 + vertex 895.989 324.887 0.011451 + endloop + endfacet + facet normal 0.00230971 0.000152177 -0.999997 + outer loop + vertex 895.989 324.887 0.011451 + vertex 890.179 334.481 -0.000508267 + vertex 895.389 334.151 0.0114748 + endloop + endfacet + facet normal 0.0103421 0.000672454 -0.999946 + outer loop + vertex 895.989 324.887 0.011451 + vertex 895.389 334.151 0.0114748 + vertex 901.346 324.278 0.0664482 + endloop + endfacet + facet normal 0.00231357 0.000213151 -0.999997 + outer loop + vertex 890.179 334.481 -0.000508267 + vertex 889.3 343.674 -0.000581636 + vertex 895.389 334.151 0.0114748 + endloop + endfacet + facet normal 0.00245371 0.00030275 -0.999997 + outer loop + vertex 895.389 334.151 0.0114748 + vertex 889.3 343.674 -0.000581636 + vertex 894.469 343.449 0.0120331 + endloop + endfacet + facet normal 0.0104327 0.00109198 -0.999945 + outer loop + vertex 895.389 334.151 0.0114748 + vertex 894.469 343.449 0.0120331 + vertex 900.724 333.666 0.0666074 + endloop + endfacet + facet normal 0.00245468 0.000324911 -0.999997 + outer loop + vertex 889.3 343.674 -0.000581636 + vertex 888.164 352.881 -0.000379226 + vertex 894.469 343.449 0.0120331 + endloop + endfacet + facet normal 0.0022773 0.00020634 -0.999997 + outer loop + vertex 894.469 343.449 0.0120331 + vertex 888.164 352.881 -0.000379226 + vertex 893.279 352.759 0.0112427 + endloop + endfacet + facet normal 0.0104013 0.00124528 -0.999945 + outer loop + vertex 894.469 343.449 0.0120331 + vertex 893.279 352.759 0.0112427 + vertex 899.76 343.081 0.0666081 + endloop + endfacet + facet normal 0.00228079 0.000352914 -0.999997 + outer loop + vertex 888.164 352.881 -0.000379226 + vertex 886.808 362.095 -0.000220579 + vertex 893.279 352.759 0.0112427 + endloop + endfacet + facet normal 0.00243857 0.000462269 -0.999997 + outer loop + vertex 893.279 352.759 0.0112427 + vertex 886.808 362.095 -0.000220579 + vertex 891.851 362.069 0.0120654 + endloop + endfacet + facet normal 0.0106727 0.00172476 -0.999942 + outer loop + vertex 893.279 352.759 0.0112427 + vertex 891.851 362.069 0.0120654 + vertex 898.502 352.494 0.0665305 + endloop + endfacet + facet normal 0.00243831 0.000412504 -0.999997 + outer loop + vertex 886.808 362.095 -0.000220579 + vertex 885.262 371.317 -0.000186785 + vertex 891.851 362.069 0.0120654 + endloop + endfacet + facet normal 0.00243773 0.000412087 -0.999997 + outer loop + vertex 891.851 362.069 0.0120654 + vertex 885.262 371.317 -0.000186785 + vertex 890.223 371.377 0.0119329 + endloop + endfacet + facet normal 0.0104118 0.00180667 -0.999944 + outer loop + vertex 891.851 362.069 0.0120654 + vertex 890.223 371.377 0.0119329 + vertex 896.99 361.903 0.0652748 + endloop + endfacet + facet normal 0.00243692 0.000480041 -0.999997 + outer loop + vertex 885.262 371.317 -0.000186785 + vertex 883.556 380.513 6.95455e-05 + vertex 890.223 371.377 0.0119329 + endloop + endfacet + facet normal 0.00229762 0.000378374 -0.999997 + outer loop + vertex 890.223 371.377 0.0119329 + vertex 883.556 380.513 6.95455e-05 + vertex 888.424 380.662 0.0113125 + endloop + endfacet + facet normal 0.0103643 0.00194136 -0.999944 + outer loop + vertex 890.223 371.377 0.0119329 + vertex 888.424 380.662 0.0113125 + vertex 895.262 371.307 0.0640199 + endloop + endfacet + facet normal 0.00229553 0.000446349 -0.999997 + outer loop + vertex 883.556 380.513 6.95455e-05 + vertex 881.713 389.663 -7.59015e-05 + vertex 888.424 380.662 0.0113125 + endloop + endfacet + facet normal 0.00216575 0.000349582 -0.999998 + outer loop + vertex 888.424 380.662 0.0113125 + vertex 881.713 389.663 -7.59015e-05 + vertex 886.482 389.889 0.0103307 + endloop + endfacet + facet normal 0.0102887 0.00205983 -0.999945 + outer loop + vertex 888.424 380.662 0.0113125 + vertex 886.482 389.889 0.0103307 + vertex 893.349 380.679 0.0620175 + endloop + endfacet + facet normal 0.00216034 0.000463647 -0.999998 + outer loop + vertex 881.713 389.663 -7.59015e-05 + vertex 879.758 398.738 -9.21254e-05 + vertex 886.482 389.889 0.0103307 + endloop + endfacet + facet normal 0.00194698 0.000301532 -0.999998 + outer loop + vertex 886.482 389.889 0.0103307 + vertex 879.758 398.738 -9.21254e-05 + vertex 884.419 399.041 0.00907377 + endloop + endfacet + facet normal 0.0100499 0.00212806 -0.999947 + outer loop + vertex 886.482 389.889 0.0103307 + vertex 884.419 399.041 0.00907377 + vertex 891.281 389.988 0.0587739 + endloop + endfacet + facet normal 0.0019399 0.000410491 -0.999998 + outer loop + vertex 879.758 398.738 -9.21254e-05 + vertex 877.71 407.737 -0.000370784 + vertex 884.419 399.041 0.00907377 + endloop + endfacet + facet normal 0.0019955 0.000453383 -0.999998 + outer loop + vertex 884.419 399.041 0.00907377 + vertex 877.71 407.737 -0.000370784 + vertex 882.258 408.11 0.00887281 + endloop + endfacet + facet normal 0.0103733 0.00244988 -0.999943 + outer loop + vertex 884.419 399.041 0.00907377 + vertex 882.258 408.11 0.00887281 + vertex 889.085 399.212 0.0579032 + endloop + endfacet + facet normal 0.00199455 0.000465012 -0.999998 + outer loop + vertex 877.71 407.737 -0.000370784 + vertex 875.588 416.666 -0.000450039 + vertex 882.258 408.11 0.00887281 + endloop + endfacet + facet normal 0.00191953 0.000406542 -0.999998 + outer loop + vertex 882.258 408.11 0.00887281 + vertex 875.588 416.666 -0.000450039 + vertex 880.016 417.112 0.00823019 + endloop + endfacet + facet normal 0.010632 0.00257579 -0.99994 + outer loop + vertex 882.258 408.11 0.00887281 + vertex 880.016 417.112 0.00823019 + vertex 886.784 408.355 0.0576326 + endloop + endfacet + facet normal 0.00191952 0.000406588 -0.999998 + outer loop + vertex 875.588 416.666 -0.000450039 + vertex 873.408 425.549 -0.00102307 + vertex 880.016 417.112 0.00823019 + endloop + endfacet + facet normal 0.00174558 0.000270355 -0.999998 + outer loop + vertex 880.016 417.112 0.00823019 + vertex 873.408 425.549 -0.00102307 + vertex 877.71 426.063 0.00662554 + endloop + endfacet + facet normal 0.0108599 0.00261804 -0.999938 + outer loop + vertex 880.016 417.112 0.00823019 + vertex 877.71 426.063 0.00662554 + vertex 884.394 417.428 0.0566049 + endloop + endfacet + facet normal 0.001745 0.000275151 -0.999998 + outer loop + vertex 873.408 425.549 -0.00102307 + vertex 871.183 434.401 -0.00246998 + vertex 877.71 426.063 0.00662554 + endloop + endfacet + facet normal 0.00173427 0.000266752 -0.999998 + outer loop + vertex 877.71 426.063 0.00662554 + vertex 871.183 434.401 -0.00246998 + vertex 875.353 434.979 0.00491505 + endloop + endfacet + facet normal 0.0112246 0.0027763 -0.999933 + outer loop + vertex 877.71 426.063 0.00662554 + vertex 875.353 434.979 0.00491505 + vertex 881.931 426.451 0.0550793 + endloop + endfacet + facet normal 0.00173525 0.000259708 -0.999998 + outer loop + vertex 871.183 434.401 -0.00246998 + vertex 868.923 443.22 -0.00410237 + vertex 875.353 434.979 0.00491505 + endloop + endfacet + facet normal 0.00185774 0.000355284 -0.999998 + outer loop + vertex 875.353 434.979 0.00491505 + vertex 868.923 443.22 -0.00410237 + vertex 872.954 443.87 0.00361685 + endloop + endfacet + facet normal 0.0112684 0.00289471 -0.999932 + outer loop + vertex 875.353 434.979 0.00491505 + vertex 872.954 443.87 0.00361685 + vertex 879.408 435.443 0.0519631 + endloop + endfacet + facet normal 0.00185292 0.000385163 -0.999998 + outer loop + vertex 868.923 443.22 -0.00410237 + vertex 866.636 452.002 -0.00495654 + vertex 872.954 443.87 0.00361685 + endloop + endfacet + facet normal 0.00267099 0.00102065 -0.999996 + outer loop + vertex 872.954 443.87 0.00361685 + vertex 866.636 452.002 -0.00495654 + vertex 870.529 452.72 0.00617226 + endloop + endfacet + facet normal 0.00267113 0.00101985 -0.999996 + outer loop + vertex 866.636 452.002 -0.00495654 + vertex 864.339 460.726 -0.00219604 + vertex 870.529 452.72 0.00617226 + endloop + endfacet + facet normal 0.000419763 0.000426973 -1 + outer loop + vertex 866.636 452.002 -0.00495654 + vertex 860.435 459.783 -0.00423708 + vertex 864.339 460.726 -0.00219604 + endloop + endfacet + facet normal 0.000416788 0.000439289 -1 + outer loop + vertex 860.435 459.783 -0.00423708 + vertex 858.275 468.408 -0.00134871 + vertex 864.339 460.726 -0.00219604 + endloop + endfacet + facet normal 0.00075815 0.00070874 -0.999999 + outer loop + vertex 864.339 460.726 -0.00219604 + vertex 858.275 468.408 -0.00134871 + vertex 862.067 469.394 0.00222427 + endloop + endfacet + facet normal 0.00358135 0.00144885 -0.999993 + outer loop + vertex 864.339 460.726 -0.00219604 + vertex 862.067 469.394 0.00222427 + vertex 868.095 461.505 0.0123865 + endloop + endfacet + facet normal 0.000812978 0.000497796 -1 + outer loop + vertex 858.275 468.408 -0.00134871 + vertex 856.332 477.105 0.00140049 + vertex 862.067 469.394 0.00222427 + endloop + endfacet + facet normal 0.000346978 0.000151222 -1 + outer loop + vertex 862.067 469.394 0.00222427 + vertex 856.332 477.105 0.00140049 + vertex 859.987 478.13 0.00282391 + endloop + endfacet + facet normal 0.00362591 0.00093167 -0.999993 + outer loop + vertex 862.067 469.394 0.00222427 + vertex 859.987 478.13 0.00282391 + vertex 865.684 470.226 0.0161161 + endloop + endfacet + facet normal 0.000414969 -9.10181e-05 -1 + outer loop + vertex 856.332 477.105 0.00140049 + vertex 854.941 486.149 8.08399e-15 + vertex 859.987 478.13 0.00282391 + endloop + endfacet + facet normal 0.000320359 -0.000150564 -1 + outer loop + vertex 859.987 478.13 0.00282391 + vertex 854.941 486.149 8.08399e-15 + vertex 858.583 487.309 0.000992115 + endloop + endfacet + facet normal 0.00280885 0.000230203 -0.999996 + outer loop + vertex 859.987 478.13 0.00282391 + vertex 858.583 487.309 0.000992115 + vertex 863.44 479.044 0.0127336 + endloop + endfacet + facet normal 4.6249e-05 -0.000147738 -1 + outer loop + vertex 856.332 477.105 0.00140049 + vertex 851.435 485.051 9.14893e-15 + vertex 854.941 486.149 8.08399e-15 + endloop + endfacet + facet normal 0.00055666 0.000166792 -1 + outer loop + vertex 852.517 475.992 -0.000908466 + vertex 851.435 485.051 9.14893e-15 + vertex 856.332 477.105 0.00140049 + endloop + endfacet + facet normal -2.99108e-05 9.671e-05 -1 + outer loop + vertex 852.517 475.992 -0.000908466 + vertex 847.491 483.831 9.57562e-15 + vertex 851.435 485.051 9.14893e-15 + endloop + endfacet + facet normal 0.000604069 0.000503229 -1 + outer loop + vertex 848.575 474.834 -0.00387305 + vertex 847.491 483.831 9.57562e-15 + vertex 852.517 475.992 -0.000908466 + endloop + endfacet + facet normal 0.000603393 0.000505528 -1 + outer loop + vertex 854.357 467.319 -0.00418305 + vertex 848.575 474.834 -0.00387305 + vertex 852.517 475.992 -0.000908466 + endloop + endfacet + facet normal 0.000583979 0.00050141 -1 + outer loop + vertex 854.357 467.319 -0.00418305 + vertex 852.517 475.992 -0.000908466 + vertex 858.275 468.408 -0.00134871 + endloop + endfacet + facet normal 0.000458439 0.000393994 -1 + outer loop + vertex 850.374 466.19 -0.00645363 + vertex 848.575 474.834 -0.00387305 + vertex 854.357 467.319 -0.00418305 + endloop + endfacet + facet normal 0.000500855 0.000244231 -1 + outer loop + vertex 856.442 458.73 -0.0052364 + vertex 850.374 466.19 -0.00645363 + vertex 854.357 467.319 -0.00418305 + endloop + endfacet + facet normal 0.000204774 0.000172352 -1 + outer loop + vertex 856.442 458.73 -0.0052364 + vertex 854.357 467.319 -0.00418305 + vertex 860.435 459.783 -0.00423708 + endloop + endfacet + facet normal 0.000234174 6.09466e-05 -1 + outer loop + vertex 862.625 451.114 -0.0042528 + vertex 856.442 458.73 -0.0052364 + vertex 860.435 459.783 -0.00423708 + endloop + endfacet + facet normal 3.19702e-05 -0.000103197 -1 + outer loop + vertex 858.555 450.107 -0.00427903 + vertex 856.442 458.73 -0.0052364 + vertex 862.625 451.114 -0.0042528 + endloop + endfacet + facet normal 4.50641e-05 -0.000156132 -1 + outer loop + vertex 864.802 442.392 -0.00279299 + vertex 858.555 450.107 -0.00427903 + vertex 862.625 451.114 -0.0042528 + endloop + endfacet + facet normal -0.000270562 -0.000234923 -1 + outer loop + vertex 864.802 442.392 -0.00279299 + vertex 862.625 451.114 -0.0042528 + vertex 868.923 443.22 -0.00410237 + endloop + endfacet + facet normal 8.79947e-05 -0.000121369 -1 + outer loop + vertex 860.655 441.438 -0.00304211 + vertex 858.555 450.107 -0.00427903 + vertex 864.802 442.392 -0.00279299 + endloop + endfacet + facet normal 8.82568e-05 -0.000122507 -1 + outer loop + vertex 866.956 433.633 -0.00152982 + vertex 860.655 441.438 -0.00304211 + vertex 864.802 442.392 -0.00279299 + endloop + endfacet + facet normal -0.00018778 -0.000190381 -1 + outer loop + vertex 866.956 433.633 -0.00152982 + vertex 864.802 442.392 -0.00279299 + vertex 871.183 434.401 -0.00246998 + endloop + endfacet + facet normal 0.000179891 -4.8531e-05 -1 + outer loop + vertex 862.733 432.737 -0.00224597 + vertex 860.655 441.438 -0.00304211 + vertex 866.956 433.633 -0.00152982 + endloop + endfacet + facet normal 0.000176119 -3.07585e-05 -1 + outer loop + vertex 869.079 424.846 -0.000885608 + vertex 862.733 432.737 -0.00224597 + vertex 866.956 433.633 -0.00152982 + endloop + endfacet + facet normal -1.91027e-05 -7.79345e-05 -1 + outer loop + vertex 869.079 424.846 -0.000885608 + vertex 866.956 433.633 -0.00152982 + vertex 873.408 425.549 -0.00102307 + endloop + endfacet + facet normal 0.000242418 2.2564e-05 -1 + outer loop + vertex 864.787 424.006 -0.00194494 + vertex 862.733 432.737 -0.00224597 + vertex 869.079 424.846 -0.000885608 + endloop + endfacet + facet normal 0.000239638 3.67706e-05 -1 + outer loop + vertex 871.162 416.031 -0.000710594 + vertex 864.787 424.006 -0.00194494 + vertex 869.079 424.846 -0.000885608 + endloop + endfacet + facet normal 5.96904e-05 -5.74871e-06 -1 + outer loop + vertex 871.162 416.031 -0.000710594 + vertex 869.079 424.846 -0.000885608 + vertex 875.588 416.666 -0.000450039 + endloop + endfacet + facet normal 0.000255495 4.94446e-05 -1 + outer loop + vertex 866.804 415.251 -0.00186264 + vertex 864.787 424.006 -0.00194494 + vertex 871.162 416.031 -0.000710594 + endloop + endfacet + facet normal 0.000254497 5.50152e-05 -1 + outer loop + vertex 873.192 407.166 -0.000681636 + vertex 866.804 415.251 -0.00186264 + vertex 871.162 416.031 -0.000710594 + endloop + endfacet + facet normal 6.72715e-05 1.21389e-05 -1 + outer loop + vertex 873.192 407.166 -0.000681636 + vertex 871.162 416.031 -0.000710594 + vertex 877.71 407.737 -0.000370784 + endloop + endfacet + facet normal 0.000264224 6.27011e-05 -1 + outer loop + vertex 868.769 406.451 -0.00189516 + vertex 866.804 415.251 -0.00186264 + vertex 873.192 407.166 -0.000681636 + endloop + endfacet + facet normal 0.000263581 6.66793e-05 -1 + outer loop + vertex 875.152 398.239 -0.000760332 + vertex 868.769 406.451 -0.00189516 + vertex 873.192 407.166 -0.000681636 + endloop + endfacet + facet normal 0.000140771 3.97186e-05 -1 + outer loop + vertex 875.152 398.239 -0.000760332 + vertex 873.192 407.166 -0.000681636 + vertex 879.758 398.738 -9.21254e-05 + endloop + endfacet + facet normal 0.000261335 6.49332e-05 -1 + outer loop + vertex 870.665 397.593 -0.00197485 + vertex 868.769 406.451 -0.00189516 + vertex 875.152 398.239 -0.000760332 + endloop + endfacet + facet normal 0.000260033 7.39767e-05 -1 + outer loop + vertex 877.022 389.24 -0.000939722 + vertex 870.665 397.593 -0.00197485 + vertex 875.152 398.239 -0.000760332 + endloop + endfacet + facet normal 0.000178998 5.71358e-05 -1 + outer loop + vertex 877.022 389.24 -0.000939722 + vertex 875.152 398.239 -0.000760332 + vertex 881.713 389.663 -7.59015e-05 + endloop + endfacet + facet normal 0.000241712 6.00332e-05 -1 + outer loop + vertex 872.477 388.66 -0.00207326 + vertex 870.665 397.593 -0.00197485 + vertex 877.022 389.24 -0.000939722 + endloop + endfacet + facet normal 0.000241544 6.13487e-05 -1 + outer loop + vertex 878.786 380.168 -0.00107027 + vertex 872.477 388.66 -0.00207326 + vertex 877.022 389.24 -0.000939722 + endloop + endfacet + facet normal 0.00023463 6.00044e-05 -1 + outer loop + vertex 878.786 380.168 -0.00107027 + vertex 877.022 389.24 -0.000939722 + vertex 883.556 380.513 6.95455e-05 + endloop + endfacet + facet normal 0.000227345 5.07995e-05 -1 + outer loop + vertex 874.183 379.663 -0.00214237 + vertex 872.477 388.66 -0.00207326 + vertex 878.786 380.168 -0.00107027 + endloop + endfacet + facet normal 0.000227062 5.33865e-05 -1 + outer loop + vertex 880.42 371.05 -0.00118601 + vertex 874.183 379.663 -0.00214237 + vertex 878.786 380.168 -0.00107027 + endloop + endfacet + facet normal 0.000203656 4.91918e-05 -1 + outer loop + vertex 880.42 371.05 -0.00118601 + vertex 878.786 380.168 -0.00107027 + vertex 885.262 371.317 -0.000186785 + endloop + endfacet + facet normal 0.000213936 4.38822e-05 -1 + outer loop + vertex 875.763 370.623 -0.00220095 + vertex 874.183 379.663 -0.00214237 + vertex 880.42 371.05 -0.00118601 + endloop + endfacet + facet normal 0.000213517 4.84614e-05 -1 + outer loop + vertex 881.899 361.919 -0.0013126 + vertex 875.763 370.623 -0.00220095 + vertex 880.42 371.05 -0.00118601 + endloop + endfacet + facet normal 0.000220689 4.96236e-05 -1 + outer loop + vertex 881.899 361.919 -0.0013126 + vertex 880.42 371.05 -0.00118601 + vertex 886.808 362.095 -0.000220579 + endloop + endfacet + facet normal 0.000194474 3.50371e-05 -1 + outer loop + vertex 877.195 361.57 -0.0022398 + vertex 875.763 370.623 -0.00220095 + vertex 881.899 361.919 -0.0013126 + endloop + endfacet + facet normal 0.000194688 3.2143e-05 -1 + outer loop + vertex 883.199 352.792 -0.00135305 + vertex 877.195 361.57 -0.0022398 + vertex 881.899 361.919 -0.0013126 + endloop + endfacet + facet normal 0.000195533 3.22632e-05 -1 + outer loop + vertex 883.199 352.792 -0.00135305 + vertex 881.899 361.919 -0.0013126 + vertex 888.164 352.881 -0.000379226 + endloop + endfacet + facet normal 0.000188401 2.78424e-05 -1 + outer loop + vertex 878.449 352.527 -0.00225517 + vertex 877.195 361.57 -0.0022398 + vertex 883.199 352.792 -0.00135305 + endloop + endfacet + facet normal 0.00018836 2.85649e-05 -1 + outer loop + vertex 884.287 343.68 -0.00140837 + vertex 878.449 352.527 -0.00225517 + vertex 883.199 352.792 -0.00135305 + endloop + endfacet + facet normal 0.000164924 2.57663e-05 -1 + outer loop + vertex 884.287 343.68 -0.00140837 + vertex 883.199 352.792 -0.00135305 + vertex 889.3 343.674 -0.000581636 + endloop + endfacet + facet normal 0.000176529 2.07584e-05 -1 + outer loop + vertex 879.499 343.502 -0.00225719 + vertex 878.449 352.527 -0.00225517 + vertex 884.287 343.68 -0.00140837 + endloop + endfacet + facet normal 0.000176688 1.64995e-05 -1 + outer loop + vertex 885.13 334.589 -0.00140943 + vertex 879.499 343.502 -0.00225719 + vertex 884.287 343.68 -0.00140837 + endloop + endfacet + facet normal 0.000178823 1.66975e-05 -1 + outer loop + vertex 885.13 334.589 -0.00140943 + vertex 884.287 343.68 -0.00140837 + vertex 890.179 334.481 -0.000508267 + endloop + endfacet + facet normal 0.000177098 1.67586e-05 -1 + outer loop + vertex 880.31 334.503 -0.00226441 + vertex 879.499 343.502 -0.00225719 + vertex 885.13 334.589 -0.00140943 + endloop + endfacet + facet normal 0.000177258 7.8577e-06 -1 + outer loop + vertex 885.684 325.546 -0.00138213 + vertex 880.31 334.503 -0.00226441 + vertex 885.13 334.589 -0.00140943 + endloop + endfacet + facet normal 0.000150994 6.24621e-06 -1 + outer loop + vertex 885.684 325.546 -0.00138213 + vertex 885.13 334.589 -0.00140943 + vertex 890.759 325.335 -0.000617243 + endloop + endfacet + facet normal 0.000181511 1.04097e-05 -1 + outer loop + vertex 880.843 325.56 -0.0022608 + vertex 880.31 334.503 -0.00226441 + vertex 885.684 325.546 -0.00138213 + endloop + endfacet + facet normal 0.00018149 3.0223e-06 -1 + outer loop + vertex 885.903 316.61 -0.00136949 + vertex 880.843 325.56 -0.0022608 + vertex 885.684 325.546 -0.00138213 + endloop + endfacet + facet normal 0.000180199 2.99074e-06 -1 + outer loop + vertex 885.903 316.61 -0.00136949 + vertex 885.684 325.546 -0.00138213 + vertex 890.984 316.285 -0.000454767 + endloop + endfacet + facet normal 0.000180966 2.72624e-06 -1 + outer loop + vertex 881.049 316.726 -0.00224763 + vertex 880.843 325.56 -0.0022608 + vertex 885.903 316.61 -0.00136949 + endloop + endfacet + facet normal 0.00018075 -6.30123e-06 -1 + outer loop + vertex 885.729 307.823 -0.00134554 + vertex 881.049 316.726 -0.00224763 + vertex 885.903 316.61 -0.00136949 + endloop + endfacet + facet normal 0.000147941 -5.65219e-06 -1 + outer loop + vertex 885.729 307.823 -0.00134554 + vertex 885.903 316.61 -0.00136949 + vertex 890.804 307.379 -0.000592307 + endloop + endfacet + facet normal 0.000180682 -6.33733e-06 -1 + outer loop + vertex 880.873 308.046 -0.00222437 + vertex 881.049 316.726 -0.00224763 + vertex 885.729 307.823 -0.00134554 + endloop + endfacet + facet normal 0.000179976 -2.16709e-05 -1 + outer loop + vertex 885.118 299.21 -0.00126881 + vertex 880.873 308.046 -0.00222437 + vertex 885.729 307.823 -0.00134554 + endloop + endfacet + facet normal 0.000173148 -2.11867e-05 -1 + outer loop + vertex 885.118 299.21 -0.00126881 + vertex 885.729 307.823 -0.00134554 + vertex 890.165 298.641 -0.000382994 + endloop + endfacet + facet normal 0.000182719 -2.0353e-05 -1 + outer loop + vertex 880.272 299.546 -0.00216123 + vertex 880.873 308.046 -0.00222437 + vertex 885.118 299.21 -0.00126881 + endloop + endfacet + facet normal 0.000181415 -3.91956e-05 -1 + outer loop + vertex 884.054 290.795 -0.00113208 + vertex 880.272 299.546 -0.00216123 + vertex 885.118 299.21 -0.00126881 + endloop + endfacet + facet normal 0.000173987 -3.8256e-05 -1 + outer loop + vertex 884.054 290.795 -0.00113208 + vertex 885.118 299.21 -0.00126881 + vertex 889.055 290.095 -0.000235254 + endloop + endfacet + facet normal 0.000182275 -3.88236e-05 -1 + outer loop + vertex 879.225 291.247 -0.00202973 + vertex 880.272 299.546 -0.00216123 + vertex 884.054 290.795 -0.00113208 + endloop + endfacet + facet normal 0.000181157 -5.07847e-05 -1 + outer loop + vertex 882.554 282.636 -0.000989461 + vertex 879.225 291.247 -0.00202973 + vertex 884.054 290.795 -0.00113208 + endloop + endfacet + facet normal 0.000170152 -4.87616e-05 -1 + outer loop + vertex 882.554 282.636 -0.000989461 + vertex 884.054 290.795 -0.00113208 + vertex 887.491 281.798 -0.00010853 + endloop + endfacet + facet normal 0.000173718 -5.36601e-05 -1 + outer loop + vertex 877.755 283.208 -0.00185381 + vertex 879.225 291.247 -0.00202973 + vertex 882.554 282.636 -0.000989461 + endloop + endfacet + facet normal 0.000174949 -4.33241e-05 -1 + outer loop + vertex 880.65 274.815 -0.000983716 + vertex 877.755 283.208 -0.00185381 + vertex 882.554 282.636 -0.000989461 + endloop + endfacet + facet normal 0.000167587 -4.15317e-05 -1 + outer loop + vertex 880.65 274.815 -0.000983716 + vertex 882.554 282.636 -0.000989461 + vertex 885.515 273.836 -0.000127673 + endloop + endfacet + facet normal 0.000160277 -4.83858e-05 -1 + outer loop + vertex 875.892 275.511 -0.00177991 + vertex 877.755 283.208 -0.00185381 + vertex 880.65 274.815 -0.000983716 + endloop + endfacet + facet normal 0.000170581 2.20856e-05 -1 + outer loop + vertex 878.363 267.377 -0.00153806 + vertex 875.892 275.511 -0.00177991 + vertex 880.65 274.815 -0.000983716 + endloop + endfacet + facet normal 0.000133457 3.34981e-05 -1 + outer loop + vertex 878.363 267.377 -0.00153806 + vertex 880.65 274.815 -0.000983716 + vertex 883.142 266.252 -0.000937953 + endloop + endfacet + facet normal 0.000116835 5.75861e-06 -1 + outer loop + vertex 873.644 268.196 -0.00208469 + vertex 875.892 275.511 -0.00177991 + vertex 878.363 267.377 -0.00153806 + endloop + endfacet + facet normal 0.000133478 0.000101629 -1 + outer loop + vertex 875.633 260.237 -0.0026282 + vertex 873.644 268.196 -0.00208469 + vertex 878.363 267.377 -0.00153806 + endloop + endfacet + facet normal 0.000140883 9.87973e-05 -1 + outer loop + vertex 875.633 260.237 -0.0026282 + vertex 878.363 267.377 -0.00153806 + vertex 880.327 258.974 -0.00209164 + endloop + endfacet + facet normal 6.19944e-05 8.37703e-05 -1 + outer loop + vertex 870.974 261.183 -0.00283769 + vertex 873.644 268.196 -0.00208469 + vertex 875.633 260.237 -0.0026282 + endloop + endfacet + facet normal 7.16683e-05 0.000131372 -1 + outer loop + vertex 872.421 253.225 -0.0037795 + vertex 870.974 261.183 -0.00283769 + vertex 875.633 260.237 -0.0026282 + endloop + endfacet + facet normal 0.000185659 7.91474e-05 -1 + outer loop + vertex 872.421 253.225 -0.0037795 + vertex 875.633 260.237 -0.0026282 + vertex 877.009 251.829 -0.00303809 + endloop + endfacet + facet normal 3.75978e-05 0.00012518 -1 + outer loop + vertex 867.836 254.296 -0.00381779 + vertex 870.974 261.183 -0.00283769 + vertex 872.421 253.225 -0.0037795 + endloop + endfacet + facet normal 2.3616e-05 6.53366e-05 -1 + outer loop + vertex 868.762 246.249 -0.00432171 + vertex 867.836 254.296 -0.00381779 + vertex 872.421 253.225 -0.0037795 + endloop + endfacet + facet normal 0.000405033 -0.000134691 -1 + outer loop + vertex 868.762 246.249 -0.00432171 + vertex 872.421 253.225 -0.0037795 + vertex 873.227 244.725 -0.00230819 + endloop + endfacet + facet normal 0.000277016 -0.000509722 -1 + outer loop + vertex 869.175 237.841 7.84901e-05 + vertex 868.762 246.249 -0.00432171 + vertex 873.227 244.725 -0.00230819 + endloop + endfacet + facet normal 0.000764574 -0.000485779 -1 + outer loop + vertex 864.806 239.47 -0.00405376 + vertex 868.762 246.249 -0.00432171 + vertex 869.175 237.841 7.84901e-05 + endloop + endfacet + facet normal 0.000633827 -0.000836333 -0.999999 + outer loop + vertex 865.05 231.602 0.00268125 + vertex 864.806 239.47 -0.00405376 + vertex 869.175 237.841 7.84901e-05 + endloop + endfacet + facet normal 0.00327399 -0.00258216 -0.999991 + outer loop + vertex 865.05 231.602 0.00268125 + vertex 869.175 237.841 7.84901e-05 + vertex 869.14 229.482 0.021546 + endloop + endfacet + facet normal 0.00313481 -0.00285066 -0.999991 + outer loop + vertex 864.92 224.129 0.0235783 + vertex 865.05 231.602 0.00268125 + vertex 869.14 229.482 0.021546 + endloop + endfacet + facet normal 0.00266322 -0.00257958 -0.999993 + outer loop + vertex 869.14 229.482 0.021546 + vertex 869.175 237.841 7.84901e-05 + vertex 873.356 235.837 0.0163814 + endloop + endfacet + facet normal 0.00119762 -0.000818847 -0.999999 + outer loop + vertex 860.709 233.325 -0.00392802 + vertex 864.806 239.47 -0.00405376 + vertex 865.05 231.602 0.00268125 + endloop + endfacet + facet normal 0.00111504 -0.00102694 -0.999999 + outer loop + vertex 860.787 226.389 0.00328112 + vertex 860.709 233.325 -0.00392802 + vertex 865.05 231.602 0.00268125 + endloop + endfacet + facet normal 0.00021046 -0.000160763 -1 + outer loop + vertex 860.709 233.325 -0.00392802 + vertex 860.343 240.735 -0.00519629 + vertex 864.806 239.47 -0.00405376 + endloop + endfacet + facet normal 0.000240009 -5.65209e-05 -1 + outer loop + vertex 860.343 240.735 -0.00519629 + vertex 864.244 247.422 -0.00463805 + vertex 864.806 239.47 -0.00405376 + endloop + endfacet + facet normal -3.45724e-05 0.000103657 -1 + outer loop + vertex 860.343 240.735 -0.00519629 + vertex 859.758 248.303 -0.00439161 + vertex 864.244 247.422 -0.00463805 + endloop + endfacet + facet normal -3.70584e-05 9.10078e-05 -1 + outer loop + vertex 859.758 248.303 -0.00439161 + vertex 863.314 255.081 -0.00390652 + vertex 864.244 247.422 -0.00463805 + endloop + endfacet + facet normal 3.69785e-05 9.99942e-05 -1 + outer loop + vertex 864.244 247.422 -0.00463805 + vertex 863.314 255.081 -0.00390652 + vertex 867.836 254.296 -0.00381779 + endloop + endfacet + facet normal 3.01078e-05 6.0408e-05 -1 + outer loop + vertex 863.314 255.081 -0.00390652 + vertex 866.423 261.868 -0.00340296 + vertex 867.836 254.296 -0.00381779 + endloop + endfacet + facet normal -3.64622e-06 7.58688e-05 -1 + outer loop + vertex 863.314 255.081 -0.00390652 + vertex 862 262.35 -0.00335024 + vertex 866.423 261.868 -0.00340296 + endloop + endfacet + facet normal -1.11885e-05 6.73359e-06 -1 + outer loop + vertex 862 262.35 -0.00335024 + vertex 864.655 269.168 -0.00333403 + vertex 866.423 261.868 -0.00340296 + endloop + endfacet + facet normal 6.06507e-05 2.4128e-05 -1 + outer loop + vertex 866.423 261.868 -0.00340296 + vertex 864.655 269.168 -0.00333403 + vertex 869.07 268.775 -0.00307572 + endloop + endfacet + facet normal 0.000124155 -2.1478e-07 -1 + outer loop + vertex 866.423 261.868 -0.00340296 + vertex 869.07 268.775 -0.00307572 + vertex 870.974 261.183 -0.00283769 + endloop + endfacet + facet normal 5.56593e-05 -3.19283e-05 -1 + outer loop + vertex 864.655 269.168 -0.00333403 + vertex 866.901 276.288 -0.00343631 + vertex 869.07 268.775 -0.00307572 + endloop + endfacet + facet normal 9.30537e-05 -2.11315e-05 -1 + outer loop + vertex 869.07 268.775 -0.00307572 + vertex 866.901 276.288 -0.00343631 + vertex 871.305 275.984 -0.00302014 + endloop + endfacet + facet normal 0.00020943 -5.72012e-05 -1 + outer loop + vertex 869.07 268.775 -0.00307572 + vertex 871.305 275.984 -0.00302014 + vertex 873.644 268.196 -0.00208469 + endloop + endfacet + facet normal 9.14272e-05 -4.47303e-05 -1 + outer loop + vertex 866.901 276.288 -0.00343631 + vertex 868.771 283.792 -0.00360108 + vertex 871.305 275.984 -0.00302014 + endloop + endfacet + facet normal 9.80556e-05 -4.25787e-05 -1 + outer loop + vertex 871.305 275.984 -0.00302014 + vertex 868.771 283.792 -0.00360108 + vertex 873.161 283.576 -0.00316132 + endloop + endfacet + facet normal 0.000261822 -8.26311e-05 -1 + outer loop + vertex 871.305 275.984 -0.00302014 + vertex 873.161 283.576 -0.00316132 + vertex 875.892 275.511 -0.00177991 + endloop + endfacet + facet normal 9.8265e-05 -3.83236e-05 -1 + outer loop + vertex 868.771 283.792 -0.00360108 + vertex 870.252 291.639 -0.00375621 + vertex 873.161 283.576 -0.00316132 + endloop + endfacet + facet normal 9.46412e-05 -3.96311e-05 -1 + outer loop + vertex 873.161 283.576 -0.00316132 + vertex 870.252 291.639 -0.00375621 + vertex 874.628 291.511 -0.00333697 + endloop + endfacet + facet normal 0.000278747 -7.36669e-05 -1 + outer loop + vertex 873.161 283.576 -0.00316132 + vertex 874.628 291.511 -0.00333697 + vertex 877.755 283.208 -0.00185381 + endloop + endfacet + facet normal 9.50752e-05 -2.47403e-05 -1 + outer loop + vertex 870.252 291.639 -0.00375621 + vertex 871.312 299.748 -0.00385606 + vertex 874.628 291.511 -0.00333697 + endloop + endfacet + facet normal 9.07509e-05 -2.64814e-05 -1 + outer loop + vertex 874.628 291.511 -0.00333697 + vertex 871.312 299.748 -0.00385606 + vertex 875.672 299.708 -0.00345932 + endloop + endfacet + facet normal 0.000281452 -5.07635e-05 -1 + outer loop + vertex 874.628 291.511 -0.00333697 + vertex 875.672 299.708 -0.00345932 + vertex 879.225 291.247 -0.00202973 + endloop + endfacet + facet normal 9.08756e-05 -1.28831e-05 -1 + outer loop + vertex 871.312 299.748 -0.00385606 + vertex 871.935 308.065 -0.00390664 + vertex 875.672 299.708 -0.00345932 + endloop + endfacet + facet normal 9.09017e-05 -1.28715e-05 -1 + outer loop + vertex 875.672 299.708 -0.00345932 + vertex 871.935 308.065 -0.00390664 + vertex 876.278 308.111 -0.00351241 + endloop + endfacet + facet normal 0.00028129 -2.65968e-05 -1 + outer loop + vertex 875.672 299.708 -0.00345932 + vertex 876.278 308.111 -0.00351241 + vertex 880.272 299.546 -0.00216123 + endloop + endfacet + facet normal 9.08099e-05 -4.10391e-06 -1 + outer loop + vertex 871.935 308.065 -0.00390664 + vertex 872.137 316.568 -0.00392311 + vertex 876.278 308.111 -0.00351241 + endloop + endfacet + facet normal 9.04755e-05 -4.26764e-06 -1 + outer loop + vertex 876.278 308.111 -0.00351241 + vertex 872.137 316.568 -0.00392311 + vertex 876.465 316.696 -0.00353215 + endloop + endfacet + facet normal 0.000280196 -8.39485e-06 -1 + outer loop + vertex 876.278 308.111 -0.00351241 + vertex 876.465 316.696 -0.00353215 + vertex 880.873 308.046 -0.00222437 + endloop + endfacet + facet normal 9.03095e-05 1.33332e-06 -1 + outer loop + vertex 872.137 316.568 -0.00392311 + vertex 871.965 325.231 -0.00392711 + vertex 876.465 316.696 -0.00353215 + endloop + endfacet + facet normal 9.01558e-05 1.25231e-06 -1 + outer loop + vertex 876.465 316.696 -0.00353215 + vertex 871.965 325.231 -0.00392711 + vertex 876.276 325.439 -0.00353825 + endloop + endfacet + facet normal 0.000280186 5.36205e-06 -1 + outer loop + vertex 876.465 316.696 -0.00353215 + vertex 876.276 325.439 -0.00353825 + vertex 881.049 316.726 -0.00224763 + endloop + endfacet + facet normal 8.994e-05 5.72135e-06 -1 + outer loop + vertex 871.965 325.231 -0.00392711 + vertex 871.47 334.009 -0.00392139 + vertex 876.276 325.439 -0.00353825 + endloop + endfacet + facet normal 8.75911e-05 4.40431e-06 -1 + outer loop + vertex 876.276 325.439 -0.00353825 + vertex 871.47 334.009 -0.00392139 + vertex 875.764 334.295 -0.00354408 + endloop + endfacet + facet normal 0.000279292 1.54852e-05 -1 + outer loop + vertex 876.276 325.439 -0.00353825 + vertex 875.764 334.295 -0.00354408 + vertex 880.843 325.56 -0.0022608 + endloop + endfacet + facet normal 8.74598e-05 6.37469e-06 -1 + outer loop + vertex 871.47 334.009 -0.00392139 + vertex 870.702 342.852 -0.00393226 + vertex 875.764 334.295 -0.00354408 + endloop + endfacet + facet normal 9.13804e-05 8.69411e-06 -1 + outer loop + vertex 875.764 334.295 -0.00354408 + vertex 870.702 342.852 -0.00393226 + vertex 874.976 343.212 -0.0035385 + endloop + endfacet + facet normal 0.000280316 2.53768e-05 -1 + outer loop + vertex 875.764 334.295 -0.00354408 + vertex 874.976 343.212 -0.0035385 + vertex 880.31 334.503 -0.00226441 + endloop + endfacet + facet normal 9.11714e-05 1.11752e-05 -1 + outer loop + vertex 870.702 342.852 -0.00393226 + vertex 869.697 351.725 -0.00392466 + vertex 874.976 343.212 -0.0035385 + endloop + endfacet + facet normal 8.9764e-05 1.03025e-05 -1 + outer loop + vertex 874.976 343.212 -0.0035385 + vertex 869.697 351.725 -0.00392466 + vertex 873.954 352.159 -0.0035381 + endloop + endfacet + facet normal 0.000281237 3.21828e-05 -1 + outer loop + vertex 874.976 343.212 -0.0035385 + vertex 873.954 352.159 -0.0035381 + vertex 879.499 343.502 -0.00225719 + endloop + endfacet + facet normal 8.95526e-05 1.23769e-05 -1 + outer loop + vertex 869.697 351.725 -0.00392466 + vertex 868.49 360.622 -0.00392264 + vertex 873.954 352.159 -0.0035381 + endloop + endfacet + facet normal 8.931e-05 1.22203e-05 -1 + outer loop + vertex 873.954 352.159 -0.0035381 + vertex 868.49 360.622 -0.00392264 + vertex 872.729 361.125 -0.0035379 + endloop + endfacet + facet normal 0.00028223 3.85695e-05 -1 + outer loop + vertex 873.954 352.159 -0.0035381 + vertex 872.729 361.125 -0.0035379 + vertex 878.449 352.527 -0.00225517 + endloop + endfacet + facet normal 8.90643e-05 1.42904e-05 -1 + outer loop + vertex 868.49 360.622 -0.00392264 + vertex 867.11 369.533 -0.00391823 + vertex 872.729 361.125 -0.0035379 + endloop + endfacet + facet normal 8.97457e-05 1.47458e-05 -1 + outer loop + vertex 872.729 361.125 -0.0035379 + vertex 867.11 369.533 -0.00391823 + vertex 871.331 370.104 -0.00353102 + endloop + endfacet + facet normal 0.000286198 4.53474e-05 -1 + outer loop + vertex 872.729 361.125 -0.0035379 + vertex 871.331 370.104 -0.00353102 + vertex 877.195 361.57 -0.0022398 + endloop + endfacet + facet normal 8.97463e-05 1.47415e-05 -1 + outer loop + vertex 867.11 369.533 -0.00391823 + vertex 865.582 378.438 -0.0039241 + vertex 871.331 370.104 -0.00353102 + endloop + endfacet + facet normal 9.42855e-05 1.78727e-05 -1 + outer loop + vertex 871.331 370.104 -0.00353102 + vertex 865.582 378.438 -0.0039241 + vertex 869.784 379.073 -0.00351651 + endloop + endfacet + facet normal 0.000293945 5.22934e-05 -1 + outer loop + vertex 871.331 370.104 -0.00353102 + vertex 869.784 379.073 -0.00351651 + vertex 875.763 370.623 -0.00220095 + endloop + endfacet + facet normal 9.42693e-05 1.79798e-05 -1 + outer loop + vertex 865.582 378.438 -0.0039241 + vertex 863.93 387.305 -0.00392044 + vertex 869.784 379.073 -0.00351651 + endloop + endfacet + facet normal 9.90433e-05 2.13754e-05 -1 + outer loop + vertex 869.784 379.073 -0.00351651 + vertex 863.93 387.305 -0.00392044 + vertex 868.115 388.001 -0.00349104 + endloop + endfacet + facet normal 0.000304402 5.97796e-05 -1 + outer loop + vertex 869.784 379.073 -0.00351651 + vertex 868.115 388.001 -0.00349104 + vertex 874.183 379.663 -0.00214237 + endloop + endfacet + facet normal 9.91556e-05 2.07005e-05 -1 + outer loop + vertex 863.93 387.305 -0.00392044 + vertex 862.173 396.112 -0.00391227 + vertex 868.115 388.001 -0.00349104 + endloop + endfacet + facet normal 0.000105248 2.51636e-05 -1 + outer loop + vertex 868.115 388.001 -0.00349104 + vertex 862.173 396.112 -0.00391227 + vertex 866.341 396.868 -0.00345461 + endloop + endfacet + facet normal 0.000314917 6.71084e-05 -1 + outer loop + vertex 868.115 388.001 -0.00349104 + vertex 866.341 396.868 -0.00345461 + vertex 872.477 388.66 -0.00207326 + endloop + endfacet + facet normal 0.000105517 2.36807e-05 -1 + outer loop + vertex 862.173 396.112 -0.00391227 + vertex 860.332 404.853 -0.00389956 + vertex 866.341 396.868 -0.00345461 + endloop + endfacet + facet normal 0.000107781 2.53841e-05 -1 + outer loop + vertex 866.341 396.868 -0.00345461 + vertex 860.332 404.853 -0.00389956 + vertex 864.481 405.669 -0.00343173 + endloop + endfacet + facet normal 0.000330085 7.23774e-05 -1 + outer loop + vertex 866.341 396.868 -0.00345461 + vertex 864.481 405.669 -0.00343173 + vertex 870.665 397.593 -0.00197485 + endloop + endfacet + facet normal 0.000108113 2.36962e-05 -1 + outer loop + vertex 860.332 404.853 -0.00389956 + vertex 858.422 413.54 -0.00390022 + vertex 864.481 405.669 -0.00343173 + endloop + endfacet + facet normal 0.000113486 2.78319e-05 -1 + outer loop + vertex 864.481 405.669 -0.00343173 + vertex 858.422 413.54 -0.00390022 + vertex 862.555 414.408 -0.00340707 + endloop + endfacet + facet normal 0.000343966 7.86255e-05 -1 + outer loop + vertex 864.481 405.669 -0.00343173 + vertex 862.555 414.408 -0.00340707 + vertex 868.769 406.451 -0.00189516 + endloop + endfacet + facet normal 0.000114383 2.35595e-05 -1 + outer loop + vertex 858.422 413.54 -0.00390022 + vertex 856.462 422.188 -0.00392067 + vertex 862.555 414.408 -0.00340707 + endloop + endfacet + facet normal 0.000111005 2.0914e-05 -1 + outer loop + vertex 862.555 414.408 -0.00340707 + vertex 856.462 422.188 -0.00392067 + vertex 860.578 423.107 -0.00344451 + endloop + endfacet + facet normal 0.000348605 7.48925e-05 -1 + outer loop + vertex 862.555 414.408 -0.00340707 + vertex 860.578 423.107 -0.00344451 + vertex 866.804 415.251 -0.00186264 + endloop + endfacet + facet normal 0.000112631 1.362e-05 -1 + outer loop + vertex 856.462 422.188 -0.00392067 + vertex 854.468 430.814 -0.0040278 + vertex 860.578 423.107 -0.00344451 + endloop + endfacet + facet normal 9.61053e-05 5.17144e-07 -1 + outer loop + vertex 860.578 423.107 -0.00344451 + vertex 854.468 430.814 -0.0040278 + vertex 858.566 431.781 -0.00363339 + endloop + endfacet + facet normal 0.000343891 5.79916e-05 -1 + outer loop + vertex 860.578 423.107 -0.00344451 + vertex 858.566 431.781 -0.00363339 + vertex 864.787 424.006 -0.00194494 + endloop + endfacet + facet normal 9.90506e-05 -1.19631e-05 -1 + outer loop + vertex 854.468 430.814 -0.0040278 + vertex 852.454 439.418 -0.00433022 + vertex 858.566 431.781 -0.00363339 + endloop + endfacet + facet normal 5.95736e-05 -4.35594e-05 -1 + outer loop + vertex 858.566 431.781 -0.00363339 + vertex 852.454 439.418 -0.00433022 + vertex 856.531 440.434 -0.00413156 + endloop + endfacet + facet normal 0.000328475 1.96895e-05 -1 + outer loop + vertex 858.566 431.781 -0.00363339 + vertex 856.531 440.434 -0.00413156 + vertex 862.733 432.737 -0.00224597 + endloop + endfacet + facet normal 6.48124e-05 -6.45909e-05 -1 + outer loop + vertex 852.454 439.418 -0.00433022 + vertex 850.425 447.997 -0.00501582 + vertex 856.531 440.434 -0.00413156 + endloop + endfacet + facet normal 1.51629e-05 -0.000104677 -1 + outer loop + vertex 856.531 440.434 -0.00413156 + vertex 850.425 447.997 -0.00501582 + vertex 854.479 449.056 -0.00506518 + endloop + endfacet + facet normal 0.000274643 -4.29056e-05 -1 + outer loop + vertex 856.531 440.434 -0.00413156 + vertex 854.479 449.056 -0.00506518 + vertex 860.655 441.438 -0.00304211 + endloop + endfacet + facet normal 1.95186e-05 -0.000121354 -1 + outer loop + vertex 850.425 447.997 -0.00501582 + vertex 848.387 456.537 -0.006092 + vertex 854.479 449.056 -0.00506518 + endloop + endfacet + facet normal 4.74963e-06 -0.00013338 -1 + outer loop + vertex 854.479 449.056 -0.00506518 + vertex 848.387 456.537 -0.006092 + vertex 852.414 457.637 -0.00621949 + endloop + endfacet + facet normal 0.000214252 -8.29653e-05 -1 + outer loop + vertex 854.479 449.056 -0.00506518 + vertex 852.414 457.637 -0.00621949 + vertex 858.555 450.107 -0.00427903 + endloop + endfacet + facet normal -4.56206e-06 -9.92681e-05 -1 + outer loop + vertex 848.387 456.537 -0.006092 + vertex 846.379 465.056 -0.00692847 + vertex 852.414 457.637 -0.00621949 + endloop + endfacet + facet normal 0.000118601 9.11276e-07 -1 + outer loop + vertex 852.414 457.637 -0.00621949 + vertex 846.379 465.056 -0.00692847 + vertex 850.374 466.19 -0.00645363 + endloop + endfacet + facet normal 6.95176e-05 0.000173761 -1 + outer loop + vertex 846.379 465.056 -0.00692847 + vertex 844.599 473.665 -0.00555623 + vertex 850.374 466.19 -0.00645363 + endloop + endfacet + facet normal -7.92637e-05 0.000143006 -1 + outer loop + vertex 846.379 465.056 -0.00692847 + vertex 840.65 472.482 -0.00541239 + vertex 844.599 473.665 -0.00555623 + endloop + endfacet + facet normal -0.000210435 0.000580872 -1 + outer loop + vertex 840.65 472.482 -0.00541239 + vertex 839.633 481.432 9.15718e-15 + vertex 844.599 473.665 -0.00555623 + endloop + endfacet + facet normal -0.000182269 0.000598883 -1 + outer loop + vertex 844.599 473.665 -0.00555623 + vertex 839.633 481.432 9.15718e-15 + vertex 843.485 482.604 9.50374e-15 + endloop + endfacet + facet normal 0.000232209 0.000650539 -1 + outer loop + vertex 844.599 473.665 -0.00555623 + vertex 843.485 482.604 9.50374e-15 + vertex 848.575 474.834 -0.00387305 + endloop + endfacet + facet normal -0.000177033 0.000584668 -1 + outer loop + vertex 840.65 472.482 -0.00541239 + vertex 835.717 480.246 8.66469e-15 + vertex 839.633 481.432 9.15718e-15 + endloop + endfacet + facet normal -0.000413359 0.000434507 -1 + outer loop + vertex 836.69 471.242 -0.00431428 + vertex 835.717 480.246 8.66469e-15 + vertex 840.65 472.482 -0.00541239 + endloop + endfacet + facet normal -0.000279945 8.44809e-06 -1 + outer loop + vertex 842.393 463.892 -0.00597273 + vertex 836.69 471.242 -0.00431428 + vertex 840.65 472.482 -0.00541239 + endloop + endfacet + facet normal -0.00038044 -6.95162e-05 -1 + outer loop + vertex 838.443 462.671 -0.00438535 + vertex 836.69 471.242 -0.00431428 + vertex 842.393 463.892 -0.00597273 + endloop + endfacet + facet normal -0.000340019 -0.000200308 -1 + outer loop + vertex 844.386 455.414 -0.00495224 + vertex 838.443 462.671 -0.00438535 + vertex 842.393 463.892 -0.00597273 + endloop + endfacet + facet normal -0.00023553 -0.000175745 -1 + outer loop + vertex 844.386 455.414 -0.00495224 + vertex 842.393 463.892 -0.00597273 + vertex 848.387 456.537 -0.006092 + endloop + endfacet + facet normal -0.000315382 -0.000180135 -1 + outer loop + vertex 840.425 454.238 -0.00349128 + vertex 838.443 462.671 -0.00438535 + vertex 844.386 455.414 -0.00495224 + endloop + endfacet + facet normal -0.000316368 -0.000176813 -1 + outer loop + vertex 846.408 446.918 -0.00408976 + vertex 840.425 454.238 -0.00349128 + vertex 844.386 455.414 -0.00495224 + endloop + endfacet + facet normal -0.000191046 -0.000146983 -1 + outer loop + vertex 846.408 446.918 -0.00408976 + vertex 844.386 455.414 -0.00495224 + vertex 850.425 447.997 -0.00501582 + endloop + endfacet + facet normal -0.000263384 -0.000133509 -1 + outer loop + vertex 842.433 445.797 -0.00289324 + vertex 840.425 454.238 -0.00349128 + vertex 846.408 446.918 -0.00408976 + endloop + endfacet + facet normal -0.000268317 -0.000116022 -1 + outer loop + vertex 848.424 438.388 -0.00364121 + vertex 842.433 445.797 -0.00289324 + vertex 846.408 446.918 -0.00408976 + endloop + endfacet + facet normal -0.000148577 -8.77148e-05 -1 + outer loop + vertex 848.424 438.388 -0.00364121 + vertex 846.408 446.918 -0.00408976 + vertex 852.454 439.418 -0.00433022 + endloop + endfacet + facet normal -0.00023006 -8.50842e-05 -1 + outer loop + vertex 844.442 437.322 -0.00263433 + vertex 842.433 445.797 -0.00289324 + vertex 848.424 438.388 -0.00364121 + endloop + endfacet + facet normal -0.000232748 -7.50474e-05 -1 + outer loop + vertex 850.433 429.831 -0.00346641 + vertex 844.442 437.322 -0.00263433 + vertex 848.424 438.388 -0.00364121 + endloop + endfacet + facet normal -0.000126898 -5.02066e-05 -1 + outer loop + vertex 850.433 429.831 -0.00346641 + vertex 848.424 438.388 -0.00364121 + vertex 854.468 430.814 -0.0040278 + endloop + endfacet + facet normal -0.00021416 -6.01836e-05 -1 + outer loop + vertex 846.449 428.819 -0.00255233 + vertex 844.442 437.322 -0.00263433 + vertex 850.433 429.831 -0.00346641 + endloop + endfacet + facet normal -0.00021522 -5.60118e-05 -1 + outer loop + vertex 852.424 421.252 -0.00341455 + vertex 846.449 428.819 -0.00255233 + vertex 850.433 429.831 -0.00346641 + endloop + endfacet + facet normal -0.000117619 -3.33524e-05 -1 + outer loop + vertex 852.424 421.252 -0.00341455 + vertex 850.433 429.831 -0.00346641 + vertex 856.462 422.188 -0.00392067 + endloop + endfacet + facet normal -0.00020904 -5.11311e-05 -1 + outer loop + vertex 848.444 420.295 -0.00253345 + vertex 846.449 428.819 -0.00255233 + vertex 852.424 421.252 -0.00341455 + endloop + endfacet + facet normal -0.000209609 -4.87651e-05 -1 + outer loop + vertex 854.383 412.653 -0.00340582 + vertex 848.444 420.295 -0.00253345 + vertex 852.424 421.252 -0.00341455 + endloop + endfacet + facet normal -0.000116369 -2.75245e-05 -1 + outer loop + vertex 854.383 412.653 -0.00340582 + vertex 852.424 421.252 -0.00341455 + vertex 858.422 413.54 -0.00390022 + endloop + endfacet + facet normal -0.000209328 -4.85464e-05 -1 + outer loop + vertex 850.411 411.744 -0.00253014 + vertex 848.444 420.295 -0.00253345 + vertex 854.383 412.653 -0.00340582 + endloop + endfacet + facet normal -0.000209827 -4.63672e-05 -1 + outer loop + vertex 856.292 404.016 -0.00340596 + vertex 850.411 411.744 -0.00253014 + vertex 854.383 412.653 -0.00340582 + endloop + endfacet + facet normal -0.000116841 -2.58121e-05 -1 + outer loop + vertex 856.292 404.016 -0.00340596 + vertex 854.383 412.653 -0.00340582 + vertex 860.332 404.853 -0.00389956 + endloop + endfacet + facet normal -0.000211111 -4.73448e-05 -1 + outer loop + vertex 852.33 403.155 -0.00252868 + vertex 850.411 411.744 -0.00253014 + vertex 856.292 404.016 -0.00340596 + endloop + endfacet + facet normal -0.000211706 -4.4607e-05 -1 + outer loop + vertex 858.133 395.327 -0.00340791 + vertex 852.33 403.155 -0.00252868 + vertex 856.292 404.016 -0.00340596 + endloop + endfacet + facet normal -0.000119925 -2.51716e-05 -1 + outer loop + vertex 858.133 395.327 -0.00340791 + vertex 856.292 404.016 -0.00340596 + vertex 862.173 396.112 -0.00391227 + endloop + endfacet + facet normal -0.000213033 -4.5591e-05 -1 + outer loop + vertex 854.18 394.516 -0.00252891 + vertex 852.33 403.155 -0.00252868 + vertex 858.133 395.327 -0.00340791 + endloop + endfacet + facet normal -0.000213639 -4.26409e-05 -1 + outer loop + vertex 859.885 386.575 -0.00340923 + vertex 854.18 394.516 -0.00252891 + vertex 858.133 395.327 -0.00340791 + endloop + endfacet + facet normal -0.000122028 -2.42913e-05 -1 + outer loop + vertex 859.885 386.575 -0.00340923 + vertex 858.133 395.327 -0.00340791 + vertex 863.93 387.305 -0.00392044 + endloop + endfacet + facet normal -0.000214549 -4.32946e-05 -1 + outer loop + vertex 855.941 385.818 -0.00253019 + vertex 854.18 394.516 -0.00252891 + vertex 859.885 386.575 -0.00340923 + endloop + endfacet + facet normal -0.00021514 -4.02183e-05 -1 + outer loop + vertex 861.533 377.768 -0.00340948 + vertex 855.941 385.818 -0.00253019 + vertex 859.885 386.575 -0.00340923 + endloop + endfacet + facet normal -0.000123288 -2.30352e-05 -1 + outer loop + vertex 861.533 377.768 -0.00340948 + vertex 859.885 386.575 -0.00340923 + vertex 865.582 378.438 -0.0039241 + endloop + endfacet + facet normal -0.000216079 -4.08709e-05 -1 + outer loop + vertex 857.594 377.064 -0.00252942 + vertex 855.941 385.818 -0.00253019 + vertex 861.533 377.768 -0.00340948 + endloop + endfacet + facet normal -0.000216795 -3.68665e-05 -1 + outer loop + vertex 863.055 368.924 -0.0034133 + vertex 857.594 377.064 -0.00252942 + vertex 861.533 377.768 -0.00340948 + endloop + endfacet + facet normal -0.000121435 -2.04602e-05 -1 + outer loop + vertex 863.055 368.924 -0.0034133 + vertex 861.533 377.768 -0.00340948 + vertex 867.11 369.533 -0.00391823 + endloop + endfacet + facet normal -0.000217982 -3.7663e-05 -1 + outer loop + vertex 859.118 368.279 -0.00253097 + vertex 857.594 377.064 -0.00252942 + vertex 863.055 368.924 -0.0034133 + endloop + endfacet + facet normal -0.000218603 -3.3871e-05 -1 + outer loop + vertex 864.428 360.076 -0.00341375 + vertex 859.118 368.279 -0.00253097 + vertex 863.055 368.924 -0.0034133 + endloop + endfacet + facet normal -0.000122707 -1.89906e-05 -1 + outer loop + vertex 864.428 360.076 -0.00341375 + vertex 863.055 368.924 -0.0034133 + vertex 868.49 360.622 -0.00392264 + endloop + endfacet + facet normal -0.000219418 -3.43985e-05 -1 + outer loop + vertex 860.49 359.49 -0.00252966 + vertex 859.118 368.279 -0.00253097 + vertex 864.428 360.076 -0.00341375 + endloop + endfacet + facet normal -0.000220047 -3.01804e-05 -1 + outer loop + vertex 865.625 351.244 -0.00341072 + vertex 860.49 359.49 -0.00252966 + vertex 864.428 360.076 -0.00341375 + endloop + endfacet + facet normal -0.000124178 -1.71808e-05 -1 + outer loop + vertex 865.625 351.244 -0.00341072 + vertex 864.428 360.076 -0.00341375 + vertex 869.697 351.725 -0.00392466 + endloop + endfacet + facet normal -0.000219714 -2.99727e-05 -1 + outer loop + vertex 861.685 350.719 -0.00252932 + vertex 860.49 359.49 -0.00252966 + vertex 865.625 351.244 -0.00341072 + endloop + endfacet + facet normal -0.000220403 -2.47978e-05 -1 + outer loop + vertex 866.619 342.437 -0.00341132 + vertex 861.685 350.719 -0.00252932 + vertex 865.625 351.244 -0.00341072 + endloop + endfacet + facet normal -0.000126154 -1.41646e-05 -1 + outer loop + vertex 866.619 342.437 -0.00341132 + vertex 865.625 351.244 -0.00341072 + vertex 870.702 342.852 -0.00393226 + endloop + endfacet + facet normal -0.000220627 -2.49309e-05 -1 + outer loop + vertex 862.673 341.974 -0.00252916 + vertex 861.685 350.719 -0.00252932 + vertex 866.619 342.437 -0.00341132 + endloop + endfacet + facet normal -0.00022128 -1.93547e-05 -1 + outer loop + vertex 867.374 333.663 -0.00340849 + vertex 862.673 341.974 -0.00252916 + vertex 866.619 342.437 -0.00341132 + endloop + endfacet + facet normal -0.000124262 -1.10103e-05 -1 + outer loop + vertex 867.374 333.663 -0.00340849 + vertex 866.619 342.437 -0.00341132 + vertex 871.47 334.009 -0.00392139 + endloop + endfacet + facet normal -0.00022024 -1.87664e-05 -1 + outer loop + vertex 863.419 333.265 -0.00253019 + vertex 862.673 341.974 -0.00252916 + vertex 867.374 333.663 -0.00340849 + endloop + endfacet + facet normal -0.000220914 -1.20677e-05 -1 + outer loop + vertex 867.853 324.955 -0.00340943 + vertex 863.419 333.265 -0.00253019 + vertex 867.374 333.663 -0.00340849 + endloop + endfacet + facet normal -0.000125444 -6.80589e-06 -1 + outer loop + vertex 867.853 324.955 -0.00340943 + vertex 867.374 333.663 -0.00340849 + vertex 871.965 325.231 -0.00392711 + endloop + endfacet + facet normal -0.000220741 -1.19755e-05 -1 + outer loop + vertex 863.883 324.622 -0.00252909 + vertex 863.419 333.265 -0.00253019 + vertex 867.853 324.955 -0.00340943 + endloop + endfacet + facet normal -0.000221381 -4.34851e-06 -1 + outer loop + vertex 868.007 316.364 -0.00340596 + vertex 863.883 324.622 -0.00252909 + vertex 867.853 324.955 -0.00340943 + endloop + endfacet + facet normal -0.000125061 -2.63225e-06 -1 + outer loop + vertex 868.007 316.364 -0.00340596 + vertex 867.853 324.955 -0.00340943 + vertex 872.137 316.568 -0.00392311 + endloop + endfacet + facet normal -0.000220252 -3.78498e-06 -1 + outer loop + vertex 864.021 316.097 -0.00252718 + vertex 863.883 324.622 -0.00252909 + vertex 868.007 316.364 -0.00340596 + endloop + endfacet + facet normal -0.000220795 4.32519e-06 -1 + outer loop + vertex 867.784 307.935 -0.0033932 + vertex 864.021 316.097 -0.00252718 + vertex 868.007 316.364 -0.00340596 + endloop + endfacet + facet normal -0.000123748 1.75878e-06 -1 + outer loop + vertex 867.784 307.935 -0.0033932 + vertex 868.007 316.364 -0.00340596 + vertex 871.935 308.065 -0.00390664 + endloop + endfacet + facet normal -0.000218472 5.39585e-06 -1 + outer loop + vertex 863.771 307.737 -0.00251754 + vertex 864.021 316.097 -0.00252718 + vertex 867.784 307.935 -0.0033932 + endloop + endfacet + facet normal -0.000218851 1.30659e-05 -1 + outer loop + vertex 867.138 299.693 -0.00335966 + vertex 863.771 307.737 -0.00251754 + vertex 867.784 307.935 -0.0033932 + endloop + endfacet + facet normal -0.000119005 5.24805e-06 -1 + outer loop + vertex 867.138 299.693 -0.00335966 + vertex 867.784 307.935 -0.0033932 + vertex 871.312 299.748 -0.00385606 + endloop + endfacet + facet normal -0.000214124 1.50452e-05 -1 + outer loop + vertex 863.097 299.564 -0.0024962 + vertex 863.771 307.737 -0.00251754 + vertex 867.138 299.693 -0.00335966 + endloop + endfacet + facet normal -0.000214316 2.10182e-05 -1 + outer loop + vertex 866.055 291.659 -0.00329637 + vertex 863.097 299.564 -0.0024962 + vertex 867.138 299.693 -0.00335966 + endloop + endfacet + facet normal -0.000109531 6.89057e-06 -1 + outer loop + vertex 866.055 291.659 -0.00329637 + vertex 867.138 299.693 -0.00335966 + vertex 870.252 291.639 -0.00375621 + endloop + endfacet + facet normal -0.000207769 2.34685e-05 -1 + outer loop + vertex 861.977 291.6 -0.00245046 + vertex 863.097 299.564 -0.0024962 + vertex 866.055 291.659 -0.00329637 + endloop + endfacet + facet normal -0.000207774 2.3813e-05 -1 + outer loop + vertex 864.539 283.893 -0.0031664 + vertex 861.977 291.6 -0.00245046 + vertex 866.055 291.659 -0.00329637 + endloop + endfacet + facet normal -0.000102655 3.29898e-06 -1 + outer loop + vertex 864.539 283.893 -0.0031664 + vertex 866.055 291.659 -0.00329637 + vertex 868.771 283.792 -0.00360108 + endloop + endfacet + facet normal -0.000193686 2.84968e-05 -1 + outer loop + vertex 860.426 283.9 -0.00236942 + vertex 861.977 291.6 -0.00245046 + vertex 864.539 283.893 -0.0031664 + endloop + endfacet + facet normal -0.000193684 2.94016e-05 -1 + outer loop + vertex 862.641 276.464 -0.00301714 + vertex 860.426 283.9 -0.00236942 + vertex 864.539 283.893 -0.0031664 + endloop + endfacet + facet normal -9.81852e-05 4.99711e-06 -1 + outer loop + vertex 862.641 276.464 -0.00301714 + vertex 864.539 283.893 -0.0031664 + vertex 866.901 276.288 -0.00343631 + endloop + endfacet + facet normal -0.000181861 3.29242e-05 -1 + outer loop + vertex 858.479 276.543 -0.0022576 + vertex 860.426 283.9 -0.00236942 + vertex 862.641 276.464 -0.00301714 + endloop + endfacet + facet normal -0.000181768 3.78372e-05 -1 + outer loop + vertex 860.361 269.422 -0.0028691 + vertex 858.479 276.543 -0.0022576 + vertex 862.641 276.464 -0.00301714 + endloop + endfacet + facet normal -0.000107451 1.37731e-05 -1 + outer loop + vertex 860.361 269.422 -0.0028691 + vertex 862.641 276.464 -0.00301714 + vertex 864.655 269.168 -0.00333403 + endloop + endfacet + facet normal -0.000173594 3.9997e-05 -1 + outer loop + vertex 856.159 269.562 -0.00213403 + vertex 858.479 276.543 -0.0022576 + vertex 860.361 269.422 -0.0028691 + endloop + endfacet + facet normal -0.000173166 5.28319e-05 -1 + outer loop + vertex 857.676 262.674 -0.00276074 + vertex 856.159 269.562 -0.00213403 + vertex 860.361 269.422 -0.0028691 + endloop + endfacet + facet normal -0.000133551 3.70714e-05 -1 + outer loop + vertex 857.676 262.674 -0.00276074 + vertex 860.361 269.422 -0.0028691 + vertex 862 262.35 -0.00335024 + endloop + endfacet + facet normal -0.000130642 7.58963e-05 -1 + outer loop + vertex 858.885 255.647 -0.00345193 + vertex 857.676 262.674 -0.00276074 + vertex 862 262.35 -0.00335024 + endloop + endfacet + facet normal -0.000170306 6.90762e-05 -1 + outer loop + vertex 854.535 256.046 -0.00268361 + vertex 857.676 262.674 -0.00276074 + vertex 858.885 255.647 -0.00345193 + endloop + endfacet + facet normal -0.000167238 0.000102521 -1 + outer loop + vertex 855.322 248.954 -0.00354232 + vertex 854.535 256.046 -0.00268361 + vertex 858.885 255.647 -0.00345193 + endloop + endfacet + facet normal -0.000175734 0.000107043 -1 + outer loop + vertex 855.322 248.954 -0.00354232 + vertex 858.885 255.647 -0.00345193 + vertex 859.758 248.303 -0.00439161 + endloop + endfacet + facet normal -0.000169793 0.000147564 -1 + outer loop + vertex 855.872 241.698 -0.0047064 + vertex 855.322 248.954 -0.00354232 + vertex 859.758 248.303 -0.00439161 + endloop + endfacet + facet normal -0.000237067 0.000142461 -1 + outer loop + vertex 851.435 242.436 -0.00354934 + vertex 855.322 248.954 -0.00354232 + vertex 855.872 241.698 -0.0047064 + endloop + endfacet + facet normal -0.000230755 0.000180442 -1 + outer loop + vertex 851.845 235.708 -0.004858 + vertex 851.435 242.436 -0.00354934 + vertex 855.872 241.698 -0.0047064 + endloop + endfacet + facet normal -0.000154286 0.000129033 -1 + outer loop + vertex 851.845 235.708 -0.004858 + vertex 855.872 241.698 -0.0047064 + vertex 856.274 234.673 -0.00567486 + endloop + endfacet + facet normal -0.000133585 0.000217579 -1 + outer loop + vertex 852.1 229.688 -0.00620177 + vertex 851.845 235.708 -0.004858 + vertex 856.274 234.673 -0.00567486 + endloop + endfacet + facet normal -0.000250382 0.000212641 -1 + outer loop + vertex 847.803 230.743 -0.00490166 + vertex 851.845 235.708 -0.004858 + vertex 852.1 229.688 -0.00620177 + endloop + endfacet + facet normal -0.000269809 0.000228457 -1 + outer loop + vertex 847.803 230.743 -0.00490166 + vertex 847.418 236.533 -0.003475 + vertex 851.845 235.708 -0.004858 + endloop + endfacet + facet normal -8.08733e-05 0.000133227 -1 + outer loop + vertex 856.274 234.673 -0.00567486 + vertex 855.872 241.698 -0.0047064 + vertex 860.343 240.735 -0.00519629 + endloop + endfacet + facet normal -0.000279306 0.000177481 -1 + outer loop + vertex 847.418 236.533 -0.003475 + vertex 851.435 242.436 -0.00354934 + vertex 851.845 235.708 -0.004858 + endloop + endfacet + facet normal -0.000216904 0.000135015 -1 + outer loop + vertex 847.418 236.533 -0.003475 + vertex 847.039 243.016 -0.0025176 + vertex 851.435 242.436 -0.00354934 + endloop + endfacet + facet normal -0.000219077 0.000118543 -1 + outer loop + vertex 847.039 243.016 -0.0025176 + vertex 850.938 249.431 -0.00261135 + vertex 851.435 242.436 -0.00354934 + endloop + endfacet + facet normal -0.000175723 9.21927e-05 -1 + outer loop + vertex 847.039 243.016 -0.0025176 + vertex 846.607 249.782 -0.00181793 + vertex 850.938 249.431 -0.00261135 + endloop + endfacet + facet normal -0.000176429 8.3485e-05 -1 + outer loop + vertex 846.607 249.782 -0.00181793 + vertex 850.234 256.313 -0.00191259 + vertex 850.938 249.431 -0.00261135 + endloop + endfacet + facet normal -0.000174078 8.37258e-05 -1 + outer loop + vertex 850.938 249.431 -0.00261135 + vertex 850.234 256.313 -0.00191259 + vertex 854.535 256.046 -0.00268361 + endloop + endfacet + facet normal -0.00017497 6.93173e-05 -1 + outer loop + vertex 850.234 256.313 -0.00191259 + vertex 853.427 262.878 -0.00201612 + vertex 854.535 256.046 -0.00268361 + endloop + endfacet + facet normal -0.000167956 6.59065e-05 -1 + outer loop + vertex 850.234 256.313 -0.00191259 + vertex 849.217 262.987 -0.00130185 + vertex 853.427 262.878 -0.00201612 + endloop + endfacet + facet normal -0.000168162 5.79723e-05 -1 + outer loop + vertex 849.217 262.987 -0.00130185 + vertex 852.009 269.618 -0.00138694 + vertex 853.427 262.878 -0.00201612 + endloop + endfacet + facet normal -0.000179277 5.56341e-05 -1 + outer loop + vertex 853.427 262.878 -0.00201612 + vertex 852.009 269.618 -0.00138694 + vertex 856.159 269.562 -0.00213403 + endloop + endfacet + facet normal -0.000179357 4.9746e-05 -1 + outer loop + vertex 852.009 269.618 -0.00138694 + vertex 854.39 276.54 -0.0014697 + vertex 856.159 269.562 -0.00213403 + endloop + endfacet + facet normal -0.000161775 4.36975e-05 -1 + outer loop + vertex 852.009 269.618 -0.00138694 + vertex 850.344 276.48 -0.00081773 + vertex 854.39 276.54 -0.0014697 + endloop + endfacet + facet normal -0.000161732 4.07564e-05 -1 + outer loop + vertex 850.344 276.48 -0.00081773 + vertex 852.404 283.72 -0.000855916 + vertex 854.39 276.54 -0.0014697 + endloop + endfacet + facet normal -0.000172583 3.77554e-05 -1 + outer loop + vertex 854.39 276.54 -0.0014697 + vertex 852.404 283.72 -0.000855916 + vertex 856.389 283.836 -0.00153927 + endloop + endfacet + facet normal -0.000192727 4.32751e-05 -1 + outer loop + vertex 854.39 276.54 -0.0014697 + vertex 856.389 283.836 -0.00153927 + vertex 858.479 276.543 -0.0022576 + endloop + endfacet + facet normal -0.000172482 3.4289e-05 -1 + outer loop + vertex 852.404 283.72 -0.000855916 + vertex 854.06 291.296 -0.000881661 + vertex 856.389 283.836 -0.00153927 + endloop + endfacet + facet normal -0.000181442 3.14911e-05 -1 + outer loop + vertex 856.389 283.836 -0.00153927 + vertex 854.06 291.296 -0.000881661 + vertex 857.985 291.475 -0.00158821 + endloop + endfacet + facet normal -0.000206247 3.6672e-05 -1 + outer loop + vertex 856.389 283.836 -0.00153927 + vertex 857.985 291.475 -0.00158821 + vertex 860.426 283.9 -0.00236942 + endloop + endfacet + facet normal -0.000181189 2.5926e-05 -1 + outer loop + vertex 854.06 291.296 -0.000881661 + vertex 855.269 299.136 -0.000897515 + vertex 857.985 291.475 -0.00158821 + endloop + endfacet + facet normal -0.000186827 2.39272e-05 -1 + outer loop + vertex 857.985 291.475 -0.00158821 + vertex 855.269 299.136 -0.000897515 + vertex 859.147 299.374 -0.00161628 + endloop + endfacet + facet normal -0.000216872 2.83465e-05 -1 + outer loop + vertex 857.985 291.475 -0.00158821 + vertex 859.147 299.374 -0.00161628 + vertex 861.977 291.6 -0.00245046 + endloop + endfacet + facet normal -0.000186361 1.63329e-05 -1 + outer loop + vertex 855.269 299.136 -0.000897515 + vertex 856.017 307.185 -0.000905361 + vertex 859.147 299.374 -0.00161628 + endloop + endfacet + facet normal -0.000189442 1.50983e-05 -1 + outer loop + vertex 859.147 299.374 -0.00161628 + vertex 856.017 307.185 -0.000905361 + vertex 859.857 307.483 -0.00162851 + endloop + endfacet + facet normal -0.000223634 1.80956e-05 -1 + outer loop + vertex 859.147 299.374 -0.00161628 + vertex 859.857 307.483 -0.00162851 + vertex 863.097 299.564 -0.0024962 + endloop + endfacet + facet normal -0.000188779 6.53474e-06 -1 + outer loop + vertex 856.017 307.185 -0.000905361 + vertex 856.321 315.423 -0.000909014 + vertex 859.857 307.483 -0.00162851 + endloop + endfacet + facet normal -0.000190578 5.73321e-06 -1 + outer loop + vertex 859.857 307.483 -0.00162851 + vertex 856.321 315.423 -0.000909014 + vertex 860.133 315.78 -0.00163341 + endloop + endfacet + facet normal -0.000227644 6.96316e-06 -1 + outer loop + vertex 859.857 307.483 -0.00162851 + vertex 860.133 315.78 -0.00163341 + vertex 863.771 307.737 -0.00251754 + endloop + endfacet + facet normal -0.000189869 -1.84085e-06 -1 + outer loop + vertex 856.321 315.423 -0.000909014 + vertex 856.231 323.824 -0.000907305 + vertex 860.133 315.78 -0.00163341 + endloop + endfacet + facet normal -0.000191788 -2.77219e-06 -1 + outer loop + vertex 860.133 315.78 -0.00163341 + vertex 856.231 323.824 -0.000907305 + vertex 860.019 324.242 -0.00163495 + endloop + endfacet + facet normal -0.000229587 -3.28259e-06 -1 + outer loop + vertex 860.133 315.78 -0.00163341 + vertex 860.019 324.242 -0.00163495 + vertex 864.021 316.097 -0.00252718 + endloop + endfacet + facet normal -0.000190982 -1.00805e-05 -1 + outer loop + vertex 856.231 323.824 -0.000907305 + vertex 855.79 332.345 -0.000909139 + vertex 860.019 324.242 -0.00163495 + endloop + endfacet + facet normal -0.000191079 -1.01308e-05 -1 + outer loop + vertex 860.019 324.242 -0.00163495 + vertex 855.79 332.345 -0.000909139 + vertex 859.566 332.823 -0.00163537 + endloop + endfacet + facet normal -0.000230151 -1.21924e-05 -1 + outer loop + vertex 860.019 324.242 -0.00163495 + vertex 859.566 332.823 -0.00163537 + vertex 863.883 324.622 -0.00252909 + endloop + endfacet + facet normal -0.000190347 -1.59203e-05 -1 + outer loop + vertex 855.79 332.345 -0.000909139 + vertex 855.06 340.936 -0.000906779 + vertex 859.566 332.823 -0.00163537 + endloop + endfacet + facet normal -0.000191335 -1.64689e-05 -1 + outer loop + vertex 859.566 332.823 -0.00163537 + vertex 855.06 340.936 -0.000906779 + vertex 858.826 341.471 -0.00163627 + endloop + endfacet + facet normal -0.000229928 -1.97697e-05 -1 + outer loop + vertex 859.566 332.823 -0.00163537 + vertex 858.826 341.471 -0.00163627 + vertex 863.419 333.265 -0.00253019 + endloop + endfacet + facet normal -0.000190567 -2.1877e-05 -1 + outer loop + vertex 855.06 340.936 -0.000906779 + vertex 854.073 349.564 -0.000907625 + vertex 858.826 341.471 -0.00163627 + endloop + endfacet + facet normal -0.000190065 -2.15824e-05 -1 + outer loop + vertex 858.826 341.471 -0.00163627 + vertex 854.073 349.564 -0.000907625 + vertex 857.841 350.156 -0.00163647 + endloop + endfacet + facet normal -0.000228726 -2.59678e-05 -1 + outer loop + vertex 858.826 341.471 -0.00163627 + vertex 857.841 350.156 -0.00163647 + vertex 862.673 341.974 -0.00252916 + endloop + endfacet + facet normal -0.000189305 -2.64129e-05 -1 + outer loop + vertex 854.073 349.564 -0.000907625 + vertex 852.871 358.219 -0.000908557 + vertex 857.841 350.156 -0.00163647 + endloop + endfacet + facet normal -0.000188689 -2.60328e-05 -1 + outer loop + vertex 857.841 350.156 -0.00163647 + vertex 852.871 358.219 -0.000908557 + vertex 856.644 358.868 -0.00163741 + endloop + endfacet + facet normal -0.000227655 -3.13867e-05 -1 + outer loop + vertex 857.841 350.156 -0.00163647 + vertex 856.644 358.868 -0.00163741 + vertex 861.685 350.719 -0.00252932 + endloop + endfacet + facet normal -0.000188021 -2.99138e-05 -1 + outer loop + vertex 852.871 358.219 -0.000908557 + vertex 851.483 366.896 -0.00090721 + vertex 856.644 358.868 -0.00163741 + endloop + endfacet + facet normal -0.000187338 -2.94745e-05 -1 + outer loop + vertex 856.644 358.868 -0.00163741 + vertex 851.483 366.896 -0.00090721 + vertex 855.266 367.6 -0.00163663 + endloop + endfacet + facet normal -0.000226215 -3.56096e-05 -1 + outer loop + vertex 856.644 358.868 -0.00163741 + vertex 855.266 367.6 -0.00163663 + vertex 860.49 359.49 -0.00252966 + endloop + endfacet + facet normal -0.00018658 -3.35496e-05 -1 + outer loop + vertex 851.483 366.896 -0.00090721 + vertex 849.934 375.572 -0.000909211 + vertex 855.266 367.6 -0.00163663 + endloop + endfacet + facet normal -0.000184926 -3.24436e-05 -1 + outer loop + vertex 855.266 367.6 -0.00163663 + vertex 849.934 375.572 -0.000909211 + vertex 853.733 376.33 -0.0016363 + endloop + endfacet + facet normal -0.000225184 -3.95149e-05 -1 + outer loop + vertex 855.266 367.6 -0.00163663 + vertex 853.733 376.33 -0.0016363 + vertex 859.118 368.279 -0.00253097 + endloop + endfacet + facet normal -0.00018424 -3.58858e-05 -1 + outer loop + vertex 849.934 375.572 -0.000909211 + vertex 848.249 384.221 -0.000909212 + vertex 853.733 376.33 -0.0016363 + endloop + endfacet + facet normal -0.000182664 -3.47911e-05 -1 + outer loop + vertex 853.733 376.33 -0.0016363 + vertex 848.249 384.221 -0.000909212 + vertex 852.068 385.031 -0.00163488 + endloop + endfacet + facet normal -0.000223238 -4.25551e-05 -1 + outer loop + vertex 853.733 376.33 -0.0016363 + vertex 852.068 385.031 -0.00163488 + vertex 857.594 377.064 -0.00252942 + endloop + endfacet + facet normal -0.000182005 -3.79025e-05 -1 + outer loop + vertex 848.249 384.221 -0.000909212 + vertex 846.45 392.823 -0.000907801 + vertex 852.068 385.031 -0.00163488 + endloop + endfacet + facet normal -0.000181367 -3.74432e-05 -1 + outer loop + vertex 852.068 385.031 -0.00163488 + vertex 846.45 392.823 -0.000907801 + vertex 850.29 393.679 -0.00163629 + endloop + endfacet + facet normal -0.000221834 -4.5761e-05 -1 + outer loop + vertex 852.068 385.031 -0.00163488 + vertex 850.29 393.679 -0.00163629 + vertex 855.941 385.818 -0.00253019 + endloop + endfacet + facet normal -0.000180795 -4.00104e-05 -1 + outer loop + vertex 846.45 392.823 -0.000907801 + vertex 844.559 401.367 -0.000907734 + vertex 850.29 393.679 -0.00163629 + endloop + endfacet + facet normal -0.000179477 -3.90273e-05 -1 + outer loop + vertex 850.29 393.679 -0.00163629 + vertex 844.559 401.367 -0.000907734 + vertex 848.422 402.27 -0.00163636 + endloop + endfacet + facet normal -0.000219207 -4.76649e-05 -1 + outer loop + vertex 850.29 393.679 -0.00163629 + vertex 848.422 402.27 -0.00163636 + vertex 854.18 394.516 -0.00252891 + endloop + endfacet + facet normal -0.000178942 -4.13129e-05 -1 + outer loop + vertex 844.559 401.367 -0.000907734 + vertex 842.604 409.852 -0.00090853 + vertex 848.422 402.27 -0.00163636 + endloop + endfacet + facet normal -0.000177595 -4.02793e-05 -1 + outer loop + vertex 848.422 402.27 -0.00163636 + vertex 842.604 409.852 -0.00090853 + vertex 846.487 410.809 -0.0016366 + endloop + endfacet + facet normal -0.000217185 -4.92524e-05 -1 + outer loop + vertex 848.422 402.27 -0.00163636 + vertex 846.487 410.809 -0.0016366 + vertex 852.33 403.155 -0.00252868 + endloop + endfacet + facet normal -0.000177191 -4.19195e-05 -1 + outer loop + vertex 842.604 409.852 -0.00090853 + vertex 840.615 418.286 -0.000909528 + vertex 846.487 410.809 -0.0016366 + endloop + endfacet + facet normal -0.000176039 -4.10152e-05 -1 + outer loop + vertex 846.487 410.809 -0.0016366 + vertex 840.615 418.286 -0.000909528 + vertex 844.508 419.306 -0.00163681 + endloop + endfacet + facet normal -0.000215741 -5.02599e-05 -1 + outer loop + vertex 846.487 410.809 -0.0016366 + vertex 844.508 419.306 -0.00163681 + vertex 850.411 411.744 -0.00253014 + endloop + endfacet + facet normal -0.000175738 -4.21661e-05 -1 + outer loop + vertex 840.615 418.286 -0.000909528 + vertex 838.611 426.683 -0.000911458 + vertex 844.508 419.306 -0.00163681 + endloop + endfacet + facet normal -0.000176083 -4.24419e-05 -1 + outer loop + vertex 844.508 419.306 -0.00163681 + vertex 838.611 426.683 -0.000911458 + vertex 842.51 427.769 -0.00164404 + endloop + endfacet + facet normal -0.000214885 -5.16063e-05 -1 + outer loop + vertex 844.508 419.306 -0.00163681 + vertex 842.51 427.769 -0.00164404 + vertex 848.444 420.295 -0.00253345 + endloop + endfacet + facet normal -0.000175792 -4.34849e-05 -1 + outer loop + vertex 838.611 426.683 -0.000911458 + vertex 836.603 435.054 -0.000922511 + vertex 842.51 427.769 -0.00164404 + endloop + endfacet + facet normal -0.000179263 -4.62989e-05 -1 + outer loop + vertex 842.51 427.769 -0.00164404 + vertex 836.603 435.054 -0.000922511 + vertex 840.505 436.208 -0.00167535 + endloop + endfacet + facet normal -0.000215911 -5.50057e-05 -1 + outer loop + vertex 842.51 427.769 -0.00164404 + vertex 840.505 436.208 -0.00167535 + vertex 846.449 428.819 -0.00255233 + endloop + endfacet + facet normal -0.000178465 -4.89973e-05 -1 + outer loop + vertex 836.603 435.054 -0.000922511 + vertex 834.592 443.409 -0.000972932 + vertex 840.505 436.208 -0.00167535 + endloop + endfacet + facet normal -0.000193367 -6.12337e-05 -1 + outer loop + vertex 840.505 436.208 -0.00167535 + vertex 834.592 443.409 -0.000972932 + vertex 838.502 444.618 -0.00180304 + endloop + endfacet + facet normal -0.00022415 -6.85649e-05 -1 + outer loop + vertex 840.505 436.208 -0.00167535 + vertex 838.502 444.618 -0.00180304 + vertex 844.442 437.322 -0.00263433 + endloop + endfacet + facet normal -0.000191424 -6.75109e-05 -1 + outer loop + vertex 834.592 443.409 -0.000972932 + vertex 832.573 451.755 -0.00115002 + vertex 838.502 444.618 -0.00180304 + endloop + endfacet + facet normal -0.000225466 -9.57881e-05 -1 + outer loop + vertex 838.502 444.618 -0.00180304 + vertex 832.573 451.755 -0.00115002 + vertex 836.5 453.005 -0.00215504 + endloop + endfacet + facet normal -0.000247036 -0.000100937 -1 + outer loop + vertex 838.502 444.618 -0.00180304 + vertex 836.5 453.005 -0.00215504 + vertex 842.433 445.797 -0.00289324 + endloop + endfacet + facet normal -0.000223745 -0.000101194 -1 + outer loop + vertex 832.573 451.755 -0.00115002 + vertex 830.573 460.13 -0.00154998 + vertex 836.5 453.005 -0.00215504 + endloop + endfacet + facet normal -0.00027335 -0.000142456 -1 + outer loop + vertex 836.5 453.005 -0.00215504 + vertex 830.573 460.13 -0.00154998 + vertex 834.521 461.396 -0.00280946 + endloop + endfacet + facet normal -0.000294139 -0.000147359 -1 + outer loop + vertex 836.5 453.005 -0.00215504 + vertex 834.521 461.396 -0.00280946 + vertex 840.425 454.238 -0.00349128 + endloop + endfacet + facet normal -0.000290086 -9.02736e-05 -1 + outer loop + vertex 830.573 460.13 -0.00154998 + vertex 828.755 468.68 -0.00179446 + vertex 834.521 461.396 -0.00280946 + endloop + endfacet + facet normal -0.000271262 -7.53722e-05 -1 + outer loop + vertex 834.521 461.396 -0.00280946 + vertex 828.755 468.68 -0.00179446 + vertex 832.734 469.958 -0.00296996 + endloop + endfacet + facet normal -0.000370543 -9.60967e-05 -1 + outer loop + vertex 834.521 461.396 -0.00280946 + vertex 832.734 469.958 -0.00296996 + vertex 838.443 462.671 -0.00438535 + endloop + endfacet + facet normal -0.000343462 0.000149401 -1 + outer loop + vertex 828.755 468.68 -0.00179446 + vertex 827.484 477.767 7.6003e-15 + vertex 832.734 469.958 -0.00296996 + endloop + endfacet + facet normal -9.50759e-05 0.000316376 -1 + outer loop + vertex 832.734 469.958 -0.00296996 + vertex 827.484 477.767 7.6003e-15 + vertex 831.542 478.987 8.09901e-15 + endloop + endfacet + facet normal -0.000428235 0.000272411 -1 + outer loop + vertex 832.734 469.958 -0.00296996 + vertex 831.542 478.987 8.09901e-15 + vertex 836.69 471.242 -0.00431428 + endloop + endfacet + facet normal -5.68073e-05 0.000189512 -1 + outer loop + vertex 828.755 468.68 -0.00179446 + vertex 823.456 476.56 7.23027e-15 + vertex 827.484 477.767 7.6003e-15 + endloop + endfacet + facet normal -0.000235103 6.96092e-05 -1 + outer loop + vertex 824.676 467.506 -0.000917104 + vertex 823.456 476.56 7.23027e-15 + vertex 828.755 468.68 -0.00179446 + endloop + endfacet + facet normal -2.91301e-05 9.7371e-05 -1 + outer loop + vertex 824.676 467.506 -0.000917104 + vertex 819.374 475.339 7.04897e-15 + vertex 823.456 476.56 7.23027e-15 + endloop + endfacet + facet normal -0.000129778 2.92297e-05 -1 + outer loop + vertex 820.432 466.471 -0.000396523 + vertex 819.374 475.339 7.04897e-15 + vertex 824.676 467.506 -0.000917104 + endloop + endfacet + facet normal -0.000111392 -4.61293e-05 -1 + outer loop + vertex 826.517 458.953 -0.000727645 + vertex 820.432 466.471 -0.000396523 + vertex 824.676 467.506 -0.000917104 + endloop + endfacet + facet normal -0.000184785 -6.19279e-05 -1 + outer loop + vertex 826.517 458.953 -0.000727645 + vertex 824.676 467.506 -0.000917104 + vertex 830.573 460.13 -0.00154998 + endloop + endfacet + facet normal -9.7061e-05 -3.45279e-05 -1 + outer loop + vertex 822.318 457.927 -0.000284679 + vertex 820.432 466.471 -0.000396523 + vertex 826.517 458.953 -0.000727645 + endloop + endfacet + facet normal -9.38116e-05 -4.78282e-05 -1 + outer loop + vertex 828.588 450.561 -0.000520531 + vertex 822.318 457.927 -0.000284679 + vertex 826.517 458.953 -0.000727645 + endloop + endfacet + facet normal -0.000140199 -5.92752e-05 -1 + outer loop + vertex 828.588 450.561 -0.000520531 + vertex 826.517 458.953 -0.000727645 + vertex 832.573 451.755 -0.00115002 + endloop + endfacet + facet normal -7.14462e-05 -2.87928e-05 -1 + outer loop + vertex 824.509 449.469 -0.000197619 + vertex 822.318 457.927 -0.000284679 + vertex 828.588 450.561 -0.000520531 + endloop + endfacet + facet normal -7.19938e-05 -2.67465e-05 -1 + outer loop + vertex 830.669 442.212 -0.000447002 + vertex 824.509 449.469 -0.000197619 + vertex 828.588 450.561 -0.000520531 + endloop + endfacet + facet normal -0.000122091 -3.92296e-05 -1 + outer loop + vertex 830.669 442.212 -0.000447002 + vertex 828.588 450.561 -0.000520531 + vertex 834.592 443.409 -0.000972932 + endloop + endfacet + facet normal -6.38918e-05 -1.98691e-05 -1 + outer loop + vertex 826.704 441.064 -0.000170908 + vertex 824.509 449.469 -0.000197619 + vertex 830.669 442.212 -0.000447002 + endloop + endfacet + facet normal -6.44006e-05 -1.81118e-05 -1 + outer loop + vertex 832.72 433.886 -0.000428342 + vertex 826.704 441.064 -0.000170908 + vertex 830.669 442.212 -0.000447002 + endloop + endfacet + facet normal -0.000117866 -3.12875e-05 -1 + outer loop + vertex 832.72 433.886 -0.000428342 + vertex 830.669 442.212 -0.000447002 + vertex 836.603 435.054 -0.000922511 + endloop + endfacet + facet normal -6.26269e-05 -1.66251e-05 -1 + outer loop + vertex 828.838 432.725 -0.000165862 + vertex 826.704 441.064 -0.000170908 + vertex 832.72 433.886 -0.000428342 + endloop + endfacet + facet normal -6.28843e-05 -1.57646e-05 -1 + outer loop + vertex 834.748 425.57 -0.000424728 + vertex 828.838 432.725 -0.000165862 + vertex 832.72 433.886 -0.000428342 + endloop + endfacet + facet normal -0.000117608 -2.91051e-05 -1 + outer loop + vertex 834.748 425.57 -0.000424728 + vertex 832.72 433.886 -0.000428342 + vertex 838.611 426.683 -0.000911458 + endloop + endfacet + facet normal -6.27362e-05 -1.56422e-05 -1 + outer loop + vertex 830.909 424.44 -0.000166209 + vertex 828.838 432.725 -0.000165862 + vertex 834.748 425.57 -0.000424728 + endloop + endfacet + facet normal -6.28507e-05 -1.52532e-05 -1 + outer loop + vertex 836.761 417.242 -0.000424211 + vertex 830.909 424.44 -0.000166209 + vertex 834.748 425.57 -0.000424728 + endloop + endfacet + facet normal -0.000118171 -2.86243e-05 -1 + outer loop + vertex 836.761 417.242 -0.000424211 + vertex 834.748 425.57 -0.000424728 + vertex 840.615 418.286 -0.000909528 + endloop + endfacet + facet normal -6.32725e-05 -1.55961e-05 -1 + outer loop + vertex 832.941 416.174 -0.000165901 + vertex 830.909 424.44 -0.000166209 + vertex 836.761 417.242 -0.000424211 + endloop + endfacet + facet normal -6.33687e-05 -1.52521e-05 -1 + outer loop + vertex 838.762 408.874 -0.000423394 + vertex 832.941 416.174 -0.000165901 + vertex 836.761 417.242 -0.000424211 + endloop + endfacet + facet normal -0.000118988 -2.85533e-05 -1 + outer loop + vertex 838.762 408.874 -0.000423394 + vertex 836.761 417.242 -0.000424211 + vertex 842.604 409.852 -0.00090853 + endloop + endfacet + facet normal -6.35205e-05 -1.53731e-05 -1 + outer loop + vertex 834.956 407.875 -0.000166247 + vertex 832.941 416.174 -0.000165901 + vertex 838.762 408.874 -0.000423394 + endloop + endfacet + facet normal -6.37345e-05 -1.45581e-05 -1 + outer loop + vertex 840.736 400.444 -0.000426458 + vertex 834.956 407.875 -0.000166247 + vertex 838.762 408.874 -0.000423394 + endloop + endfacet + facet normal -0.000119226 -2.75497e-05 -1 + outer loop + vertex 840.736 400.444 -0.000426458 + vertex 838.762 408.874 -0.000423394 + vertex 844.559 401.367 -0.000907734 + endloop + endfacet + facet normal -6.51132e-05 -1.56305e-05 -1 + outer loop + vertex 836.95 399.509 -0.000165322 + vertex 834.956 407.875 -0.000166247 + vertex 840.736 400.444 -0.000426458 + endloop + endfacet + facet normal -6.52983e-05 -1.48814e-05 -1 + outer loop + vertex 842.653 391.951 -0.000425281 + vertex 836.95 399.509 -0.000165322 + vertex 840.736 400.444 -0.000426458 + endloop + endfacet + facet normal -0.000120783 -2.74087e-05 -1 + outer loop + vertex 842.653 391.951 -0.000425281 + vertex 840.736 400.444 -0.000426458 + vertex 846.45 392.823 -0.000907801 + endloop + endfacet + facet normal -6.54023e-05 -1.49599e-05 -1 + outer loop + vertex 838.894 391.066 -0.000166227 + vertex 836.95 399.509 -0.000165322 + vertex 842.653 391.951 -0.000425281 + endloop + endfacet + facet normal -6.55993e-05 -1.41226e-05 -1 + outer loop + vertex 844.48 383.398 -0.000424358 + vertex 838.894 391.066 -0.000166227 + vertex 842.653 391.951 -0.000425281 + endloop + endfacet + facet normal -0.00012289 -2.63622e-05 -1 + outer loop + vertex 844.48 383.398 -0.000424358 + vertex 842.653 391.951 -0.000425281 + vertex 848.249 384.221 -0.000909212 + endloop + endfacet + facet normal -6.60701e-05 -1.44656e-05 -1 + outer loop + vertex 840.752 382.561 -0.000165954 + vertex 838.894 391.066 -0.000166227 + vertex 844.48 383.398 -0.000424358 + endloop + endfacet + facet normal -6.63534e-05 -1.32032e-05 -1 + outer loop + vertex 846.189 374.797 -0.000424188 + vertex 840.752 382.561 -0.000165954 + vertex 844.48 383.398 -0.000424358 + endloop + endfacet + facet normal -0.000124406 -2.47373e-05 -1 + outer loop + vertex 846.189 374.797 -0.000424188 + vertex 844.48 383.398 -0.000424358 + vertex 849.934 375.572 -0.000909211 + endloop + endfacet + facet normal -6.68754e-05 -1.35687e-05 -1 + outer loop + vertex 842.489 374.009 -0.000166046 + vertex 840.752 382.561 -0.000165954 + vertex 846.189 374.797 -0.000424188 + endloop + endfacet + facet normal -6.7188e-05 -1.21022e-05 -1 + outer loop + vertex 847.756 366.172 -0.000425068 + vertex 842.489 374.009 -0.000166046 + vertex 846.189 374.797 -0.000424188 + endloop + endfacet + facet normal -0.000124965 -2.2597e-05 -1 + outer loop + vertex 847.756 366.172 -0.000425068 + vertex 846.189 374.797 -0.000424188 + vertex 851.483 366.896 -0.00090721 + endloop + endfacet + facet normal -6.78666e-05 -1.25582e-05 -1 + outer loop + vertex 844.079 365.432 -0.00016622 + vertex 842.489 374.009 -0.000166046 + vertex 847.756 366.172 -0.000425068 + endloop + endfacet + facet normal -6.81445e-05 -1.11763e-05 -1 + outer loop + vertex 849.158 357.549 -0.000424267 + vertex 844.079 365.432 -0.00016622 + vertex 847.756 366.172 -0.000425068 + endloop + endfacet + facet normal -0.000126714 -2.07024e-05 -1 + outer loop + vertex 849.158 357.549 -0.000424267 + vertex 847.756 366.172 -0.000425068 + vertex 852.871 358.219 -0.000908557 + endloop + endfacet + facet normal -6.8353e-05 -1.13107e-05 -1 + outer loop + vertex 845.497 356.86 -0.000166233 + vertex 844.079 365.432 -0.00016622 + vertex 849.158 357.549 -0.000424267 + endloop + endfacet + facet normal -6.86815e-05 -9.56448e-06 -1 + outer loop + vertex 850.368 348.947 -0.000425079 + vertex 845.497 356.86 -0.000166233 + vertex 849.158 357.549 -0.000424267 + endloop + endfacet + facet normal -0.000127264 -1.78032e-05 -1 + outer loop + vertex 850.368 348.947 -0.000425079 + vertex 849.158 357.549 -0.000424267 + vertex 854.073 349.564 -0.000907625 + endloop + endfacet + facet normal -6.92569e-05 -9.91871e-06 -1 + outer loop + vertex 846.718 348.312 -0.000166009 + vertex 845.497 356.86 -0.000166233 + vertex 850.368 348.947 -0.000425079 + endloop + endfacet + facet normal -6.9601e-05 -7.94035e-06 -1 + outer loop + vertex 851.354 340.375 -0.000425646 + vertex 846.718 348.312 -0.000166009 + vertex 850.368 348.947 -0.000425079 + endloop + endfacet + facet normal -0.000127635 -1.46163e-05 -1 + outer loop + vertex 851.354 340.375 -0.000425646 + vertex 850.368 348.947 -0.000425079 + vertex 855.06 340.936 -0.000906779 + endloop + endfacet + facet normal -7.04958e-05 -8.46296e-06 -1 + outer loop + vertex 847.71 339.796 -0.00016388 + vertex 846.718 348.312 -0.000166009 + vertex 851.354 340.375 -0.000425646 + endloop + endfacet + facet normal -7.08827e-05 -6.02953e-06 -1 + outer loop + vertex 852.081 331.842 -0.00042574 + vertex 847.71 339.796 -0.00016388 + vertex 851.354 340.375 -0.000425646 + endloop + endfacet + facet normal -0.000128839 -1.09685e-05 -1 + outer loop + vertex 852.081 331.842 -0.00042574 + vertex 851.354 340.375 -0.000425646 + vertex 855.79 332.345 -0.000909139 + endloop + endfacet + facet normal -7.01099e-05 -5.60483e-06 -1 + outer loop + vertex 848.429 331.317 -0.000166767 + vertex 847.71 339.796 -0.00016388 + vertex 852.081 331.842 -0.00042574 + endloop + endfacet + facet normal -7.03996e-05 -3.58896e-06 -1 + outer loop + vertex 852.506 323.378 -0.00042529 + vertex 848.429 331.317 -0.000166767 + vertex 852.081 331.842 -0.00042574 + endloop + endfacet + facet normal -0.000128648 -6.51453e-06 -1 + outer loop + vertex 852.506 323.378 -0.00042529 + vertex 852.081 331.842 -0.00042574 + vertex 856.231 323.824 -0.000907305 + endloop + endfacet + facet normal -7.01842e-05 -3.47838e-06 -1 + outer loop + vertex 848.841 322.907 -0.000166412 + vertex 848.429 331.317 -0.000166767 + vertex 852.506 323.378 -0.00042529 + endloop + endfacet + facet normal -7.05391e-05 -7.1549e-07 -1 + outer loop + vertex 852.578 315.033 -0.000424335 + vertex 848.841 322.907 -0.000166412 + vertex 852.506 323.378 -0.00042529 + endloop + endfacet + facet normal -0.000129344 -1.21657e-06 -1 + outer loop + vertex 852.578 315.033 -0.000424335 + vertex 852.506 323.378 -0.00042529 + vertex 856.321 315.423 -0.000909014 + endloop + endfacet + facet normal -7.03645e-05 -6.32657e-07 -1 + outer loop + vertex 848.893 314.617 -0.000164822 + vertex 848.841 322.907 -0.000166412 + vertex 852.578 315.033 -0.000424335 + endloop + endfacet + facet normal -7.07356e-05 2.64877e-06 -1 + outer loop + vertex 852.241 306.852 -0.000422212 + vertex 848.893 314.617 -0.000164822 + vertex 852.578 315.033 -0.000424335 + endloop + endfacet + facet normal -0.000128416 5.02036e-06 -1 + outer loop + vertex 852.241 306.852 -0.000422212 + vertex 852.578 315.033 -0.000424335 + vertex 856.017 307.185 -0.000905361 + endloop + endfacet + facet normal -6.94128e-05 3.21914e-06 -1 + outer loop + vertex 848.521 306.493 -0.000165118 + vertex 848.893 314.617 -0.000164822 + vertex 852.241 306.852 -0.000422212 + endloop + endfacet + facet normal -6.97267e-05 6.4646e-06 -1 + outer loop + vertex 851.449 298.861 -0.00041865 + vertex 848.521 306.493 -0.000165118 + vertex 852.241 306.852 -0.000422212 + endloop + endfacet + facet normal -0.000126231 1.20644e-05 -1 + outer loop + vertex 851.449 298.861 -0.00041865 + vertex 852.241 306.852 -0.000422212 + vertex 855.269 299.136 -0.000897515 + endloop + endfacet + facet normal -6.83313e-05 7.00008e-06 -1 + outer loop + vertex 847.685 298.557 -0.00016355 + vertex 848.521 306.493 -0.000165118 + vertex 851.449 298.861 -0.00041865 + endloop + endfacet + facet normal -6.85915e-05 1.02186e-05 -1 + outer loop + vertex 850.186 291.079 -0.000411496 + vertex 847.685 298.557 -0.00016355 + vertex 851.449 298.861 -0.00041865 + endloop + endfacet + facet normal -0.000122421 1.89595e-05 -1 + outer loop + vertex 850.186 291.079 -0.000411496 + vertex 851.449 298.861 -0.00041865 + vertex 854.06 291.296 -0.000881661 + endloop + endfacet + facet normal -6.68196e-05 1.08112e-05 -1 + outer loop + vertex 846.368 290.826 -0.000159174 + vertex 847.685 298.557 -0.00016355 + vertex 850.186 291.079 -0.000411496 + endloop + endfacet + facet normal -6.70254e-05 1.3919e-05 -1 + outer loop + vertex 848.466 283.56 -0.000400883 + vertex 846.368 290.826 -0.000159174 + vertex 850.186 291.079 -0.000411496 + endloop + endfacet + facet normal -0.000116557 2.52481e-05 -1 + outer loop + vertex 848.466 283.56 -0.000400883 + vertex 850.186 291.079 -0.000411496 + vertex 852.404 283.72 -0.000855916 + endloop + endfacet + facet normal -6.39142e-05 1.4817e-05 -1 + outer loop + vertex 844.582 283.358 -0.000155643 + vertex 846.368 290.826 -0.000159174 + vertex 848.466 283.56 -0.000400883 + endloop + endfacet + facet normal -6.39876e-05 1.62307e-05 -1 + outer loop + vertex 846.338 276.372 -0.0003814 + vertex 844.582 283.358 -0.000155643 + vertex 848.466 283.56 -0.000400883 + endloop + endfacet + facet normal -0.000109727 2.97703e-05 -1 + outer loop + vertex 846.338 276.372 -0.0003814 + vertex 848.466 283.56 -0.000400883 + vertex 850.344 276.48 -0.00081773 + endloop + endfacet + facet normal -0.000109793 3.21965e-05 -1 + outer loop + vertex 847.897 269.609 -0.0007703 + vertex 846.338 276.372 -0.0003814 + vertex 850.344 276.48 -0.00081773 + endloop + endfacet + facet normal -0.000101736 3.40535e-05 -1 + outer loop + vertex 843.819 269.549 -0.000357458 + vertex 846.338 276.372 -0.0003814 + vertex 847.897 269.609 -0.0007703 + endloop + endfacet + facet normal -0.00010177 3.64211e-05 -1 + outer loop + vertex 845.039 263.028 -0.000719124 + vertex 843.819 269.549 -0.000357458 + vertex 847.897 269.609 -0.0007703 + endloop + endfacet + facet normal -0.00013896 5.25725e-05 -1 + outer loop + vertex 845.039 263.028 -0.000719124 + vertex 847.897 269.609 -0.0007703 + vertex 849.217 262.987 -0.00130185 + endloop + endfacet + facet normal -0.000138917 5.69637e-05 -1 + outer loop + vertex 845.972 256.483 -0.00122161 + vertex 845.039 263.028 -0.000719124 + vertex 849.217 262.987 -0.00130185 + endloop + endfacet + facet normal -0.000129044 5.83719e-05 -1 + outer loop + vertex 841.737 256.583 -0.000669205 + vertex 845.039 263.028 -0.000719124 + vertex 845.972 256.483 -0.00122161 + endloop + endfacet + facet normal -0.000128962 6.18188e-05 -1 + outer loop + vertex 842.308 250.032 -0.00114788 + vertex 841.737 256.583 -0.000669205 + vertex 845.972 256.483 -0.00122161 + endloop + endfacet + facet normal -0.000151517 7.46296e-05 -1 + outer loop + vertex 842.308 250.032 -0.00114788 + vertex 845.972 256.483 -0.00122161 + vertex 846.607 249.782 -0.00181793 + endloop + endfacet + facet normal -0.000151223 7.96919e-05 -1 + outer loop + vertex 842.69 243.468 -0.00172869 + vertex 842.308 250.032 -0.00114788 + vertex 846.607 249.782 -0.00181793 + endloop + endfacet + facet normal -0.000143943 8.01152e-05 -1 + outer loop + vertex 838.36 243.801 -0.00107886 + vertex 842.308 250.032 -0.00114788 + vertex 842.69 243.468 -0.00172869 + endloop + endfacet + facet normal -0.000143439 8.66753e-05 -1 + outer loop + vertex 838.654 237.76 -0.00164455 + vertex 838.36 243.801 -0.00107886 + vertex 842.69 243.468 -0.00172869 + endloop + endfacet + facet normal -0.000164997 0.000101917 -1 + outer loop + vertex 838.654 237.76 -0.00164455 + vertex 842.69 243.468 -0.00172869 + vertex 843.017 237.222 -0.00241921 + endloop + endfacet + facet normal -0.000162877 0.000119111 -1 + outer loop + vertex 838.921 232.41 -0.00232532 + vertex 838.654 237.76 -0.00164455 + vertex 843.017 237.222 -0.00241921 + endloop + endfacet + facet normal -0.000159278 0.000119291 -1 + outer loop + vertex 834.492 232.848 -0.0015675 + vertex 838.654 237.76 -0.00164455 + vertex 838.921 232.41 -0.00232532 + endloop + endfacet + facet normal -0.00013619 9.97254e-05 -1 + outer loop + vertex 834.492 232.848 -0.0015675 + vertex 834.25 238.107 -0.00101009 + vertex 838.654 237.76 -0.00164455 + endloop + endfacet + facet normal -0.000170822 0.000101613 -1 + outer loop + vertex 843.017 237.222 -0.00241921 + vertex 842.69 243.468 -0.00172869 + vertex 847.039 243.016 -0.0025176 + endloop + endfacet + facet normal -0.000137195 8.69788e-05 -1 + outer loop + vertex 834.25 238.107 -0.00101009 + vertex 838.36 243.801 -0.00107886 + vertex 838.654 237.76 -0.00164455 + endloop + endfacet + facet normal -0.00011249 6.91415e-05 -1 + outer loop + vertex 834.25 238.107 -0.00101009 + vertex 834.008 244.015 -0.000574395 + vertex 838.36 243.801 -0.00107886 + endloop + endfacet + facet normal -0.000112666 6.55748e-05 -1 + outer loop + vertex 834.008 244.015 -0.000574395 + vertex 838.024 250.2 -0.000621345 + vertex 838.36 243.801 -0.00107886 + endloop + endfacet + facet normal -7.90669e-05 4.37556e-05 -1 + outer loop + vertex 834.008 244.015 -0.000574395 + vertex 833.737 250.29 -0.000278434 + vertex 838.024 250.2 -0.000621345 + endloop + endfacet + facet normal -7.90776e-05 4.32501e-05 -1 + outer loop + vertex 833.737 250.29 -0.000278434 + vertex 837.527 256.628 -0.000304036 + vertex 838.024 250.2 -0.000621345 + endloop + endfacet + facet normal -8.62943e-05 4.26926e-05 -1 + outer loop + vertex 838.024 250.2 -0.000621345 + vertex 837.527 256.628 -0.000304036 + vertex 841.737 256.583 -0.000669205 + endloop + endfacet + facet normal -8.63108e-05 4.11658e-05 -1 + outer loop + vertex 837.527 256.628 -0.000304036 + vertex 840.891 263.019 -0.000331304 + vertex 841.737 256.583 -0.000669205 + endloop + endfacet + facet normal -5.03069e-05 2.22139e-05 -1 + outer loop + vertex 837.527 256.628 -0.000304036 + vertex 836.786 262.965 -0.000125943 + vertex 840.891 263.019 -0.000331304 + endloop + endfacet + facet normal -5.03033e-05 2.19336e-05 -1 + outer loop + vertex 836.786 262.965 -0.000125943 + vertex 839.791 269.444 -0.000135039 + vertex 840.891 263.019 -0.000331304 + endloop + endfacet + facet normal -5.57714e-05 2.09974e-05 -1 + outer loop + vertex 840.891 263.019 -0.000331304 + vertex 839.791 269.444 -0.000135039 + vertex 843.819 269.549 -0.000357458 + endloop + endfacet + facet normal -5.57374e-05 1.96911e-05 -1 + outer loop + vertex 839.791 269.444 -0.000135039 + vertex 842.383 276.217 -0.000146134 + vertex 843.819 269.549 -0.000357458 + endloop + endfacet + facet normal -2.59313e-05 8.28504e-06 -1 + outer loop + vertex 839.791 269.444 -0.000135039 + vertex 838.485 276.025 -4.66567e-05 + vertex 842.383 276.217 -0.000146134 + endloop + endfacet + facet normal -2.59098e-05 7.84865e-06 -1 + outer loop + vertex 838.485 276.025 -4.66567e-05 + vertex 840.76 283.114 -4.99434e-05 + vertex 842.383 276.217 -0.000146134 + endloop + endfacet + facet normal -2.81232e-05 7.32771e-06 -1 + outer loop + vertex 842.383 276.217 -0.000146134 + vertex 840.76 283.114 -4.99434e-05 + vertex 844.582 283.358 -0.000155643 + endloop + endfacet + facet normal -2.80939e-05 6.86915e-06 -1 + outer loop + vertex 840.76 283.114 -4.99434e-05 + vertex 842.613 290.536 -5.10295e-05 + vertex 844.582 283.358 -0.000155643 + endloop + endfacet + facet normal -1.03109e-05 2.42847e-06 -1 + outer loop + vertex 840.76 283.114 -4.99434e-05 + vertex 838.939 290.23 -1.38844e-05 + vertex 842.613 290.536 -5.10295e-05 + endloop + endfacet + facet normal -1.02679e-05 1.9126e-06 -1 + outer loop + vertex 838.939 290.23 -1.38844e-05 + vertex 840.374 297.863 -1.40199e-05 + vertex 842.613 290.536 -5.10295e-05 + endloop + endfacet + facet normal -1.09895e-05 1.692e-06 -1 + outer loop + vertex 842.613 290.536 -5.10295e-05 + vertex 840.374 297.863 -1.40199e-05 + vertex 843.986 298.221 -5.31145e-05 + endloop + endfacet + facet normal -2.91804e-05 4.94188e-06 -1 + outer loop + vertex 842.613 290.536 -5.10295e-05 + vertex 843.986 298.221 -5.31145e-05 + vertex 846.368 290.826 -0.000159174 + endloop + endfacet + facet normal -1.09446e-05 1.23956e-06 -1 + outer loop + vertex 840.374 297.863 -1.40199e-05 + vertex 841.299 305.708 -1.44283e-05 + vertex 843.986 298.221 -5.31145e-05 + endloop + endfacet + facet normal -1.07437e-05 1.31166e-06 -1 + outer loop + vertex 843.986 298.221 -5.31145e-05 + vertex 841.299 305.708 -1.44283e-05 + vertex 844.872 306.105 -5.2293e-05 + endloop + endfacet + facet normal -3.01768e-05 3.4957e-06 -1 + outer loop + vertex 843.986 298.221 -5.31145e-05 + vertex 844.872 306.105 -5.2293e-05 + vertex 847.685 298.557 -0.00016355 + endloop + endfacet + facet normal -1.06604e-05 5.62565e-07 -1 + outer loop + vertex 841.299 305.708 -1.44283e-05 + vertex 841.731 313.732 -1.45203e-05 + vertex 844.872 306.105 -5.2293e-05 + endloop + endfacet + facet normal -1.11217e-05 3.72615e-07 -1 + outer loop + vertex 844.872 306.105 -5.2293e-05 + vertex 841.731 313.732 -1.45203e-05 + vertex 845.269 314.176 -5.37005e-05 + endloop + endfacet + facet normal -3.10685e-05 1.35365e-06 -1 + outer loop + vertex 844.872 306.105 -5.2293e-05 + vertex 845.269 314.176 -5.37005e-05 + vertex 848.521 306.493 -0.000165118 + endloop + endfacet + facet normal -1.10709e-05 -3.05833e-08 -1 + outer loop + vertex 841.731 313.732 -1.45203e-05 + vertex 841.716 321.914 -1.4605e-05 + vertex 845.269 314.176 -5.37005e-05 + endloop + endfacet + facet normal -1.09884e-05 7.29589e-09 -1 + outer loop + vertex 845.269 314.176 -5.37005e-05 + vertex 841.716 321.914 -1.4605e-05 + vertex 845.239 322.412 -5.33124e-05 + endloop + endfacet + facet normal -3.06557e-05 -6.39754e-08 -1 + outer loop + vertex 845.269 314.176 -5.37005e-05 + vertex 845.239 322.412 -5.33124e-05 + vertex 848.893 314.617 -0.000164822 + endloop + endfacet + facet normal -1.09144e-05 -5.16727e-07 -1 + outer loop + vertex 841.716 321.914 -1.4605e-05 + vertex 841.318 330.22 -1.4542e-05 + vertex 845.239 322.412 -5.33124e-05 + endloop + endfacet + facet normal -1.08304e-05 -4.74559e-07 -1 + outer loop + vertex 845.239 322.412 -5.33124e-05 + vertex 841.318 330.22 -1.4542e-05 + vertex 844.837 330.771 -5.2921e-05 + endloop + endfacet + facet normal -3.12009e-05 -1.45521e-06 -1 + outer loop + vertex 845.239 322.412 -5.33124e-05 + vertex 844.837 330.771 -5.2921e-05 + vertex 848.841 322.907 -0.000166412 + endloop + endfacet + facet normal -1.07582e-05 -9.35386e-07 -1 + outer loop + vertex 841.318 330.22 -1.4542e-05 + vertex 840.593 338.601 -1.45892e-05 + vertex 844.837 330.771 -5.2921e-05 + endloop + endfacet + facet normal -1.09686e-05 -1.04943e-06 -1 + outer loop + vertex 844.837 330.771 -5.2921e-05 + vertex 840.593 338.601 -1.45892e-05 + vertex 844.113 339.199 -5.38269e-05 + endloop + endfacet + facet normal -3.12659e-05 -2.79247e-06 -1 + outer loop + vertex 844.837 330.771 -5.2921e-05 + vertex 844.113 339.199 -5.38269e-05 + vertex 848.429 331.317 -0.000166767 + endloop + endfacet + facet normal -1.09281e-05 -1.28799e-06 -1 + outer loop + vertex 840.593 338.601 -1.45892e-05 + vertex 839.585 347.017 -1.44074e-05 + vertex 844.113 339.199 -5.38269e-05 + endloop + endfacet + facet normal -1.09586e-05 -1.30571e-06 -1 + outer loop + vertex 844.113 339.199 -5.38269e-05 + vertex 839.585 347.017 -1.44074e-05 + vertex 843.116 347.664 -5.39552e-05 + endloop + endfacet + facet normal -3.00052e-05 -3.54875e-06 -1 + outer loop + vertex 844.113 339.199 -5.38269e-05 + vertex 843.116 347.664 -5.39552e-05 + vertex 847.71 339.796 -0.00016388 + endloop + endfacet + facet normal -1.08961e-05 -1.64717e-06 -1 + outer loop + vertex 839.585 347.017 -1.44074e-05 + vertex 838.333 355.462 -1.4683e-05 + vertex 843.116 347.664 -5.39552e-05 + endloop + endfacet + facet normal -1.08257e-05 -1.60398e-06 -1 + outer loop + vertex 843.116 347.664 -5.39552e-05 + vertex 838.333 355.462 -1.4683e-05 + vertex 841.882 356.158 -5.42211e-05 + endloop + endfacet + facet normal -3.03114e-05 -4.43471e-06 -1 + outer loop + vertex 843.116 347.664 -5.39552e-05 + vertex 841.882 356.158 -5.42211e-05 + vertex 846.718 348.312 -0.000166009 + endloop + endfacet + facet normal -1.07773e-05 -1.85055e-06 -1 + outer loop + vertex 838.333 355.462 -1.4683e-05 + vertex 836.871 363.933 -1.4602e-05 + vertex 841.882 356.158 -5.42211e-05 + endloop + endfacet + facet normal -1.03261e-05 -1.55974e-06 -1 + outer loop + vertex 841.882 356.158 -5.42211e-05 + vertex 836.871 363.933 -1.4602e-05 + vertex 840.446 364.68 -5.26804e-05 + endloop + endfacet + facet normal -3.00379e-05 -4.88228e-06 -1 + outer loop + vertex 841.882 356.158 -5.42211e-05 + vertex 840.446 364.68 -5.26804e-05 + vertex 845.497 356.86 -0.000166233 + endloop + endfacet + facet normal -1.02372e-05 -1.9849e-06 -1 + outer loop + vertex 836.871 363.933 -1.4602e-05 + vertex 835.225 372.413 -1.45822e-05 + vertex 840.446 364.68 -5.26804e-05 + endloop + endfacet + facet normal -1.0459e-05 -2.13461e-06 -1 + outer loop + vertex 840.446 364.68 -5.26804e-05 + vertex 835.225 372.413 -1.45822e-05 + vertex 838.827 373.209 -5.3958e-05 + endloop + endfacet + facet normal -3.00434e-05 -5.85116e-06 -1 + outer loop + vertex 840.446 364.68 -5.26804e-05 + vertex 838.827 373.209 -5.3958e-05 + vertex 844.079 365.432 -0.00016622 + endloop + endfacet + facet normal -1.04366e-05 -2.23585e-06 -1 + outer loop + vertex 835.225 372.413 -1.45822e-05 + vertex 833.422 380.873 -1.46835e-05 + vertex 838.827 373.209 -5.3958e-05 + endloop + endfacet + facet normal -1.03151e-05 -2.15017e-06 -1 + outer loop + vertex 838.827 373.209 -5.3958e-05 + vertex 833.422 380.873 -1.46835e-05 + vertex 837.059 381.716 -5.4004e-05 + endloop + endfacet + facet normal -2.92806e-05 -6.09355e-06 -1 + outer loop + vertex 838.827 373.209 -5.3958e-05 + vertex 837.059 381.716 -5.4004e-05 + vertex 842.489 374.009 -0.000166046 + endloop + endfacet + facet normal -1.02697e-05 -2.34617e-06 -1 + outer loop + vertex 833.422 380.873 -1.46835e-05 + vertex 831.496 389.283 -1.46307e-05 + vertex 837.059 381.716 -5.4004e-05 + endloop + endfacet + facet normal -1.00476e-05 -2.18294e-06 -1 + outer loop + vertex 837.059 381.716 -5.4004e-05 + vertex 831.496 389.283 -1.46307e-05 + vertex 835.168 390.173 -5.34694e-05 + endloop + endfacet + facet normal -2.88463e-05 -6.38538e-06 -1 + outer loop + vertex 837.059 381.716 -5.4004e-05 + vertex 835.168 390.173 -5.34694e-05 + vertex 840.752 382.561 -0.000165954 + endloop + endfacet + facet normal -1.00012e-05 -2.37442e-06 -1 + outer loop + vertex 831.496 389.283 -1.46307e-05 + vertex 829.49 397.616 -1.43573e-05 + vertex 835.168 390.173 -5.34694e-05 + endloop + endfacet + facet normal -1.00792e-05 -2.43394e-06 -1 + outer loop + vertex 835.168 390.173 -5.34694e-05 + vertex 829.49 397.616 -1.43573e-05 + vertex 833.194 398.558 -5.3982e-05 + endloop + endfacet + facet normal -2.86289e-05 -6.80083e-06 -1 + outer loop + vertex 835.168 390.173 -5.34694e-05 + vertex 833.194 398.558 -5.3982e-05 + vertex 838.894 391.066 -0.000166227 + endloop + endfacet + facet normal -1.00646e-05 -2.49145e-06 -1 + outer loop + vertex 829.49 397.616 -1.43573e-05 + vertex 827.45 405.852 -1.4345e-05 + vertex 833.194 398.558 -5.3982e-05 + endloop + endfacet + facet normal -9.86711e-06 -2.33593e-06 -1 + outer loop + vertex 833.194 398.558 -5.3982e-05 + vertex 827.45 405.852 -1.4345e-05 + vertex 831.179 406.86 -5.34937e-05 + endloop + endfacet + facet normal -2.79457e-05 -6.7236e-06 -1 + outer loop + vertex 833.194 398.558 -5.3982e-05 + vertex 831.179 406.86 -5.34937e-05 + vertex 836.95 399.509 -0.000165322 + endloop + endfacet + facet normal -9.82811e-06 -2.48016e-06 -1 + outer loop + vertex 827.45 405.852 -1.4345e-05 + vertex 825.392 414.017 -1.43614e-05 + vertex 831.179 406.86 -5.34937e-05 + endloop + endfacet + facet normal -9.85501e-06 -2.50191e-06 -1 + outer loop + vertex 831.179 406.86 -5.34937e-05 + vertex 825.392 414.017 -1.43614e-05 + vertex 829.147 415.09 -5.40536e-05 + endloop + endfacet + facet normal -2.79832e-05 -6.97902e-06 -1 + outer loop + vertex 831.179 406.86 -5.34937e-05 + vertex 829.147 415.09 -5.40536e-05 + vertex 834.956 407.875 -0.000166247 + endloop + endfacet + facet normal -9.83477e-06 -2.57269e-06 -1 + outer loop + vertex 825.392 414.017 -1.43614e-05 + vertex 823.28 422.192 -1.46269e-05 + vertex 829.147 415.09 -5.40536e-05 + endloop + endfacet + facet normal -9.54202e-06 -2.33086e-06 -1 + outer loop + vertex 829.147 415.09 -5.40536e-05 + vertex 823.28 422.192 -1.46269e-05 + vertex 827.081 423.305 -5.3495e-05 + endloop + endfacet + facet normal -2.75174e-05 -6.84987e-06 -1 + outer loop + vertex 829.147 415.09 -5.40536e-05 + vertex 827.081 423.305 -5.3495e-05 + vertex 832.941 416.174 -0.000165901 + endloop + endfacet + facet normal -9.47741e-06 -2.55153e-06 -1 + outer loop + vertex 823.28 422.192 -1.46269e-05 + vertex 821.056 430.477 -1.46865e-05 + vertex 827.081 423.305 -5.3495e-05 + endloop + endfacet + facet normal -9.43531e-06 -2.51616e-06 -1 + outer loop + vertex 827.081 423.305 -5.3495e-05 + vertex 821.056 430.477 -1.46865e-05 + vertex 824.938 431.582 -5.41032e-05 + endloop + endfacet + facet normal -2.73294e-05 -7.1487e-06 -1 + outer loop + vertex 827.081 423.305 -5.3495e-05 + vertex 824.938 431.582 -5.41032e-05 + vertex 830.909 424.44 -0.000166209 + endloop + endfacet + facet normal -9.39003e-06 -2.67517e-06 -1 + outer loop + vertex 821.056 430.477 -1.46865e-05 + vertex 818.682 438.918 -1.49812e-05 + vertex 824.938 431.582 -5.41032e-05 + endloop + endfacet + facet normal -9.36981e-06 -2.65792e-06 -1 + outer loop + vertex 824.938 431.582 -5.41032e-05 + vertex 818.682 438.918 -1.49812e-05 + vertex 822.688 439.972 -5.53146e-05 + endloop + endfacet + facet normal -2.65349e-05 -7.26259e-06 -1 + outer loop + vertex 824.938 431.582 -5.41032e-05 + vertex 822.688 439.972 -5.53146e-05 + vertex 828.838 432.725 -0.000165862 + endloop + endfacet + facet normal -9.30501e-06 -2.90418e-06 -1 + outer loop + vertex 818.682 438.918 -1.49812e-05 + vertex 816.222 447.47 -1.6922e-05 + vertex 822.688 439.972 -5.53146e-05 + endloop + endfacet + facet normal -1.0309e-05 -3.77e-06 -1 + outer loop + vertex 822.688 439.972 -5.53146e-05 + vertex 816.222 447.47 -1.6922e-05 + vertex 820.354 448.459 -6.32531e-05 + endloop + endfacet + facet normal -2.65412e-05 -8.23333e-06 -1 + outer loop + vertex 822.688 439.972 -5.53146e-05 + vertex 820.354 448.459 -6.32531e-05 + vertex 826.704 441.064 -0.000170908 + endloop + endfacet + facet normal -1.02964e-05 -3.82258e-06 -1 + outer loop + vertex 816.222 447.47 -1.6922e-05 + vertex 813.822 456.009 -2.48557e-05 + vertex 820.354 448.459 -6.32531e-05 + endloop + endfacet + facet normal -1.42655e-05 -7.25663e-06 -1 + outer loop + vertex 820.354 448.459 -6.32531e-05 + vertex 813.822 456.009 -2.48557e-05 + vertex 818.034 456.993 -9.20785e-05 + endloop + endfacet + facet normal -2.95672e-05 -1.14173e-05 -1 + outer loop + vertex 820.354 448.459 -6.32531e-05 + vertex 818.034 456.993 -9.20785e-05 + vertex 824.509 449.469 -0.000197619 + endloop + endfacet + facet normal -1.46821e-05 -5.47375e-06 -1 + outer loop + vertex 813.822 456.009 -2.48557e-05 + vertex 811.876 464.485 -4.26826e-05 + vertex 818.034 456.993 -9.20785e-05 + endloop + endfacet + facet normal -2.13271e-05 -1.09354e-05 -1 + outer loop + vertex 818.034 456.993 -9.20785e-05 + vertex 811.876 464.485 -4.26826e-05 + vertex 816.087 465.521 -0.000143803 + endloop + endfacet + facet normal -4.15587e-05 -1.55551e-05 -1 + outer loop + vertex 818.034 456.993 -9.20785e-05 + vertex 816.087 465.521 -0.000143803 + vertex 822.318 457.927 -0.000284679 + endloop + endfacet + facet normal -2.46646e-05 2.62436e-06 -1 + outer loop + vertex 811.876 464.485 -4.26826e-05 + vertex 811.036 472.85 7.54425e-15 + vertex 816.087 465.521 -0.000143803 + endloop + endfacet + facet normal -4.85578e-06 1.62751e-05 -1 + outer loop + vertex 816.087 465.521 -0.000143803 + vertex 811.036 472.85 7.54425e-15 + vertex 815.14 474.074 7.1337e-15 + endloop + endfacet + facet normal -6.03777e-05 1.0133e-05 -1 + outer loop + vertex 816.087 465.521 -0.000143803 + vertex 815.14 474.074 7.1337e-15 + vertex 820.432 466.471 -0.000396523 + endloop + endfacet + facet normal -1.47707e-06 4.95403e-06 -1 + outer loop + vertex 811.876 464.485 -4.26826e-05 + vertex 807.052 471.662 8.31163e-15 + vertex 811.036 472.85 7.54425e-15 + endloop + endfacet + facet normal -8.42781e-06 2.81925e-07 -1 + outer loop + vertex 807.986 463.224 -1.02484e-05 + vertex 807.052 471.662 8.31163e-15 + vertex 811.876 464.485 -4.26826e-05 + endloop + endfacet + facet normal -3.5045e-07 1.17586e-06 -1 + outer loop + vertex 807.986 463.224 -1.02484e-05 + vertex 802.74 470.377 9.62153e-15 + vertex 807.052 471.662 8.31163e-15 + endloop + endfacet + facet normal -3.16401e-06 -8.87997e-07 -1 + outer loop + vertex 805.089 462.006 -6.18834e-14 + vertex 802.74 470.377 9.62153e-15 + vertex 807.986 463.224 -1.02484e-05 + endloop + endfacet + facet normal -2.98504e-06 -1.31371e-06 -1 + outer loop + vertex 810.045 454.915 -5.47871e-06 + vertex 805.089 462.006 -6.18834e-14 + vertex 807.986 463.224 -1.02484e-05 + endloop + endfacet + facet normal -4.63134e-06 -1.72165e-06 -1 + outer loop + vertex 810.045 454.915 -5.47871e-06 + vertex 807.986 463.224 -1.02484e-05 + vertex 813.822 456.009 -2.48557e-05 + endloop + endfacet + facet normal -1.84697e-06 -5.1828e-07 -1 + outer loop + vertex 807.435 453.646 -1.15187e-13 + vertex 805.089 462.006 -6.18834e-14 + vertex 810.045 454.915 -5.47871e-06 + endloop + endfacet + facet normal -1.74535e-06 -7.27176e-07 -1 + outer loop + vertex 812.462 446.434 -3.52942e-06 + vertex 807.435 453.646 -1.15187e-13 + vertex 810.045 454.915 -5.47871e-06 + endloop + endfacet + facet normal -3.24373e-06 -1.15415e-06 -1 + outer loop + vertex 812.462 446.434 -3.52942e-06 + vertex 810.045 454.915 -5.47871e-06 + vertex 816.222 447.47 -1.6922e-05 + endloop + endfacet + facet normal -1.17504e-06 -3.29652e-07 -1 + outer loop + vertex 809.77 445.321 -1.49279e-13 + vertex 807.435 453.646 -1.15187e-13 + vertex 812.462 446.434 -3.52942e-06 + endloop + endfacet + facet normal -1.15482e-06 -3.78575e-07 -1 + outer loop + vertex 814.966 437.93 -3.20277e-06 + vertex 809.77 445.321 -1.49279e-13 + vertex 812.462 446.434 -3.52942e-06 + endloop + endfacet + facet normal -2.93014e-06 -9.01512e-07 -1 + outer loop + vertex 814.966 437.93 -3.20277e-06 + vertex 812.462 446.434 -3.52942e-06 + vertex 818.682 438.918 -1.49812e-05 + endloop + endfacet + facet normal -1.02547e-06 -2.87636e-07 -1 + outer loop + vertex 811.99 437.406 -1.6861e-13 + vertex 809.77 445.321 -1.49279e-13 + vertex 814.966 437.93 -3.20277e-06 + endloop + endfacet + facet normal -1.02345e-06 -2.99129e-07 -1 + outer loop + vertex 817.39 429.525 -3.1685e-06 + vertex 811.99 437.406 -1.6861e-13 + vertex 814.966 437.93 -3.20277e-06 + endloop + endfacet + facet normal -2.92196e-06 -8.46456e-07 -1 + outer loop + vertex 817.39 429.525 -3.1685e-06 + vertex 814.966 437.93 -3.20277e-06 + vertex 821.056 430.477 -1.46865e-05 + endloop + endfacet + facet normal -9.93544e-07 -2.78643e-07 -1 + outer loop + vertex 814.342 429.022 -1.79209e-13 + vertex 811.99 437.406 -1.6861e-13 + vertex 817.39 429.525 -3.1685e-06 + endloop + endfacet + facet normal -9.9553e-07 -2.6661e-07 -1 + outer loop + vertex 819.68 421.233 -3.23815e-06 + vertex 814.342 429.022 -1.79209e-13 + vertex 817.39 429.525 -3.1685e-06 + endloop + endfacet + facet normal -2.94902e-06 -8.06253e-07 -1 + outer loop + vertex 819.68 421.233 -3.23815e-06 + vertex 817.39 429.525 -3.1685e-06 + vertex 823.28 422.192 -1.46269e-05 + endloop + endfacet + facet normal -1.02656e-06 -2.8788e-07 -1 + outer loop + vertex 816.698 420.619 -1.82429e-13 + vertex 814.342 429.022 -1.79209e-13 + vertex 819.68 421.233 -3.23815e-06 + endloop + endfacet + facet normal -1.02904e-06 -2.75851e-07 -1 + outer loop + vertex 821.849 413.086 -3.22218e-06 + vertex 816.698 420.619 -1.82429e-13 + vertex 819.68 421.233 -3.23815e-06 + endloop + endfacet + facet normal -2.9382e-06 -7.83999e-07 -1 + outer loop + vertex 821.849 413.086 -3.22218e-06 + vertex 819.68 421.233 -3.23815e-06 + vertex 825.392 414.017 -1.43614e-05 + endloop + endfacet + facet normal -1.05809e-06 -2.95712e-07 -1 + outer loop + vertex 818.936 412.61 -1.80457e-13 + vertex 816.698 420.619 -1.82429e-13 + vertex 821.849 413.086 -3.22218e-06 + endloop + endfacet + facet normal -1.06132e-06 -2.75894e-07 -1 + outer loop + vertex 823.949 405.001 -3.22092e-06 + vertex 818.936 412.61 -1.80457e-13 + vertex 821.849 413.086 -3.22218e-06 + endloop + endfacet + facet normal -2.98859e-06 -7.76609e-07 -1 + outer loop + vertex 823.949 405.001 -3.22092e-06 + vertex 821.849 413.086 -3.22218e-06 + vertex 827.45 405.852 -1.4345e-05 + endloop + endfacet + facet normal -1.10113e-06 -3.0212e-07 -1 + outer loop + vertex 821.094 404.747 -1.75299e-13 + vertex 818.936 412.61 -1.80457e-13 + vertex 823.949 405.001 -3.22092e-06 + endloop + endfacet + facet normal -1.10305e-06 -2.80531e-07 -1 + outer loop + vertex 826.04 396.779 -3.22014e-06 + vertex 821.094 404.747 -1.75299e-13 + vertex 823.949 405.001 -3.22092e-06 + endloop + endfacet + facet normal -3.04e-06 -7.72973e-07 -1 + outer loop + vertex 826.04 396.779 -3.22014e-06 + vertex 823.949 405.001 -3.22092e-06 + vertex 829.49 397.616 -1.43573e-05 + endloop + endfacet + facet normal -1.13689e-06 -3.01536e-07 -1 + outer loop + vertex 823.414 396 -1.66986e-13 + vertex 821.094 404.747 -1.75299e-13 + vertex 826.04 396.779 -3.22014e-06 + endloop + endfacet + facet normal -1.14489e-06 -2.7458e-07 -1 + outer loop + vertex 828.096 388.472 -3.29374e-06 + vertex 823.414 396 -1.66986e-13 + vertex 826.04 396.779 -3.22014e-06 + endloop + endfacet + facet normal -3.15058e-06 -7.71126e-07 -1 + outer loop + vertex 828.096 388.472 -3.29374e-06 + vertex 826.04 396.779 -3.22014e-06 + vertex 831.496 389.283 -1.46307e-05 + endloop + endfacet + facet normal -1.18649e-06 -3.00453e-07 -1 + outer loop + vertex 825.42 388.079 -1.57776e-13 + vertex 823.414 396 -1.66986e-13 + vertex 828.096 388.472 -3.29374e-06 + endloop + endfacet + facet normal -1.18931e-06 -2.81271e-07 -1 + outer loop + vertex 830.048 380.128 -3.26875e-06 + vertex 825.42 388.079 -1.57776e-13 + vertex 828.096 388.472 -3.29374e-06 + endloop + endfacet + facet normal -3.21633e-06 -7.55558e-07 -1 + outer loop + vertex 830.048 380.128 -3.26875e-06 + vertex 828.096 388.472 -3.29374e-06 + vertex 833.422 380.873 -1.46835e-05 + endloop + endfacet + facet normal -1.19778e-06 -2.86206e-07 -1 + outer loop + vertex 827.439 379.627 -1.46658e-13 + vertex 825.42 388.079 -1.57776e-13 + vertex 830.048 380.128 -3.26875e-06 + endloop + endfacet + facet normal -1.20226e-06 -2.62922e-07 -1 + outer loop + vertex 831.88 371.728 -3.26249e-06 + vertex 827.439 379.627 -1.46658e-13 + vertex 830.048 380.128 -3.26875e-06 + endloop + endfacet + facet normal -3.23938e-06 -7.0716e-07 -1 + outer loop + vertex 831.88 371.728 -3.26249e-06 + vertex 830.048 380.128 -3.26875e-06 + vertex 835.225 372.413 -1.45822e-05 + endloop + endfacet + facet normal -1.21436e-06 -2.69726e-07 -1 + outer loop + vertex 829.242 371.51 -1.35061e-13 + vertex 827.439 379.627 -1.46658e-13 + vertex 831.88 371.728 -3.26249e-06 + endloop + endfacet + facet normal -1.21673e-06 -2.40937e-07 -1 + outer loop + vertex 833.554 363.298 -3.26753e-06 + vertex 829.242 371.51 -1.35061e-13 + vertex 831.88 371.728 -3.26249e-06 + endloop + endfacet + facet normal -3.29157e-06 -6.52818e-07 -1 + outer loop + vertex 833.554 363.298 -3.26753e-06 + vertex 831.88 371.728 -3.26249e-06 + vertex 836.871 363.933 -1.4602e-05 + endloop + endfacet + facet normal -1.23358e-06 -2.49786e-07 -1 + outer loop + vertex 830.988 362.889 -1.22034e-13 + vertex 829.242 371.51 -1.35061e-13 + vertex 833.554 363.298 -3.26753e-06 + endloop + endfacet + facet normal -1.23829e-06 -2.20322e-07 -1 + outer loop + vertex 835.043 354.854 -3.25163e-06 + vertex 830.988 362.889 -1.22034e-13 + vertex 833.554 363.298 -3.26753e-06 + endloop + endfacet + facet normal -3.36449e-06 -5.95392e-07 -1 + outer loop + vertex 835.043 354.854 -3.25163e-06 + vertex 833.554 363.298 -3.26753e-06 + vertex 838.333 355.462 -1.4683e-05 + endloop + endfacet + facet normal -1.24463e-06 -2.23521e-07 -1 + outer loop + vertex 832.492 354.512 -1.08916e-13 + vertex 830.988 362.889 -1.22034e-13 + vertex 835.043 354.854 -3.25163e-06 + endloop + endfacet + facet normal -1.24912e-06 -1.89976e-07 -1 + outer loop + vertex 836.31 346.464 -3.23973e-06 + vertex 832.492 354.512 -1.08916e-13 + vertex 835.043 354.854 -3.25163e-06 + endloop + endfacet + facet normal -3.3251e-06 -5.03353e-07 -1 + outer loop + vertex 836.31 346.464 -3.23973e-06 + vertex 835.043 354.854 -3.25163e-06 + vertex 839.585 347.017 -1.44074e-05 + endloop + endfacet + facet normal -1.25558e-06 -1.9304e-07 -1 + outer loop + vertex 833.761 346.261 -9.5751e-14 + vertex 832.492 354.512 -1.08916e-13 + vertex 836.31 346.464 -3.23973e-06 + endloop + endfacet + facet normal -1.25803e-06 -1.62267e-07 -1 + outer loop + vertex 837.329 338.089 -3.16315e-06 + vertex 833.761 346.261 -9.5751e-14 + vertex 836.31 346.464 -3.23973e-06 + endloop + endfacet + facet normal -3.43354e-06 -4.27062e-07 -1 + outer loop + vertex 837.329 338.089 -3.16315e-06 + vertex 836.31 346.464 -3.23973e-06 + vertex 840.593 338.601 -1.45892e-05 + endloop + endfacet + facet normal -1.23646e-06 -1.52851e-07 -1 + outer loop + vertex 834.806 337.802 -8.22002e-14 + vertex 833.761 346.261 -9.5751e-14 + vertex 837.329 338.089 -3.16315e-06 + endloop + endfacet + facet normal -1.2427e-06 -9.81816e-08 -1 + outer loop + vertex 838.059 329.775 -3.25384e-06 + vertex 834.806 337.802 -8.22002e-14 + vertex 837.329 338.089 -3.16315e-06 + endloop + endfacet + facet normal -3.42456e-06 -2.89714e-07 -1 + outer loop + vertex 838.059 329.775 -3.25384e-06 + vertex 837.329 338.089 -3.16315e-06 + vertex 841.318 330.22 -1.4542e-05 + endloop + endfacet + facet normal -1.2814e-06 -1.13862e-07 -1 + outer loop + vertex 835.517 329.802 -6.9525e-14 + vertex 834.806 337.802 -8.22002e-14 + vertex 838.059 329.775 -3.25384e-06 + endloop + endfacet + facet normal -1.28083e-06 -6.04977e-08 -1 + outer loop + vertex 838.451 321.525 -3.25704e-06 + vertex 835.517 329.802 -6.9525e-14 + vertex 838.059 329.775 -3.25384e-06 + endloop + endfacet + facet normal -3.45566e-06 -1.63882e-07 -1 + outer loop + vertex 838.451 321.525 -3.25704e-06 + vertex 838.059 329.775 -3.25384e-06 + vertex 841.716 321.914 -1.4605e-05 + endloop + endfacet + facet normal -1.28163e-06 -6.07819e-08 -1 + outer loop + vertex 835.919 321.324 -5.64604e-14 + vertex 835.517 329.802 -6.9525e-14 + vertex 838.451 321.525 -3.25704e-06 + endloop + endfacet + facet normal -1.28637e-06 -1.08218e-09 -1 + outer loop + vertex 838.446 313.368 -3.24178e-06 + vertex 835.919 321.324 -5.64604e-14 + vertex 838.451 321.525 -3.25704e-06 + endloop + endfacet + facet normal -3.43301e-06 2.34939e-10 -1 + outer loop + vertex 838.446 313.368 -3.24178e-06 + vertex 838.451 321.525 -3.25704e-06 + vertex 841.731 313.732 -1.45203e-05 + endloop + endfacet + facet normal -1.27131e-06 3.70005e-09 -1 + outer loop + vertex 835.896 313.271 -4.46536e-14 + vertex 835.919 321.324 -5.64604e-14 + vertex 838.446 313.368 -3.24178e-06 + endloop + endfacet + facet normal -1.27381e-06 6.9431e-08 -1 + outer loop + vertex 837.974 305.362 -3.1967e-06 + vertex 835.896 313.271 -4.46536e-14 + vertex 838.446 313.368 -3.24178e-06 + endloop + endfacet + facet normal -3.39813e-06 1.94611e-07 -1 + outer loop + vertex 837.974 305.362 -3.1967e-06 + vertex 838.446 313.368 -3.24178e-06 + vertex 841.299 305.708 -1.44283e-05 + endloop + endfacet + facet normal -1.23478e-06 7.96885e-08 -1 + outer loop + vertex 835.365 305.049 -3.35253e-14 + vertex 835.896 313.271 -4.46536e-14 + vertex 837.974 305.362 -3.1967e-06 + endloop + endfacet + facet normal -1.24288e-06 1.47254e-07 -1 + outer loop + vertex 837 297.579 -3.13233e-06 + vertex 835.365 305.049 -3.35253e-14 + vertex 837.974 305.362 -3.1967e-06 + endloop + endfacet + facet normal -3.26135e-06 3.99831e-07 -1 + outer loop + vertex 837 297.579 -3.13233e-06 + vertex 837.974 305.362 -3.1967e-06 + vertex 840.374 297.863 -1.40199e-05 + endloop + endfacet + facet normal -1.18954e-06 1.58928e-07 -1 + outer loop + vertex 834.389 297.745 -2.46234e-14 + vertex 835.365 305.049 -3.35253e-14 + vertex 837 297.579 -3.13233e-06 + endloop + endfacet + facet normal -1.18638e-06 2.08619e-07 -1 + outer loop + vertex 835.513 290.035 -2.94129e-06 + vertex 834.389 297.745 -2.46234e-14 + vertex 837 297.579 -3.13233e-06 + endloop + endfacet + facet normal -3.22913e-06 6.11432e-07 -1 + outer loop + vertex 835.513 290.035 -2.94129e-06 + vertex 837 297.579 -3.13233e-06 + vertex 838.939 290.23 -1.38844e-05 + endloop + endfacet + facet normal -3.23757e-06 7.59898e-07 -1 + outer loop + vertex 837.02 282.854 -1.32784e-05 + vertex 835.513 290.035 -2.94129e-06 + vertex 838.939 290.23 -1.38844e-05 + endloop + endfacet + facet normal -3.00451e-06 8.08824e-07 -1 + outer loop + vertex 833.522 282.687 -2.902e-06 + vertex 835.513 290.035 -2.94129e-06 + vertex 837.02 282.854 -1.32784e-05 + endloop + endfacet + facet normal -3.00767e-06 8.7513e-07 -1 + outer loop + vertex 834.67 275.815 -1.23684e-05 + vertex 833.522 282.687 -2.902e-06 + vertex 837.02 282.854 -1.32784e-05 + endloop + endfacet + facet normal -9.1464e-06 2.92516e-06 -1 + outer loop + vertex 834.67 275.815 -1.23684e-05 + vertex 837.02 282.854 -1.32784e-05 + vertex 838.485 276.025 -4.66567e-05 + endloop + endfacet + facet normal -9.15746e-06 3.12672e-06 -1 + outer loop + vertex 835.813 269.303 -4.32033e-05 + vertex 834.67 275.815 -1.23684e-05 + vertex 838.485 276.025 -4.66567e-05 + endloop + endfacet + facet normal -8.3584e-06 3.26705e-06 -1 + outer loop + vertex 831.909 269.129 -1.11352e-05 + vertex 834.67 275.815 -1.23684e-05 + vertex 835.813 269.303 -4.32033e-05 + endloop + endfacet + facet normal -8.36555e-06 3.42761e-06 -1 + outer loop + vertex 832.723 262.86 -3.94365e-05 + vertex 831.909 269.129 -1.11352e-05 + vertex 835.813 269.303 -4.32033e-05 + endloop + endfacet + facet normal -2.15471e-05 9.74971e-06 -1 + outer loop + vertex 832.723 262.86 -3.94365e-05 + vertex 835.813 269.303 -4.32033e-05 + vertex 836.786 262.965 -0.000125943 + endloop + endfacet + facet normal -2.15495e-05 9.84363e-06 -1 + outer loop + vertex 833.337 256.616 -0.000114128 + vertex 832.723 262.86 -3.94365e-05 + vertex 836.786 262.965 -0.000125943 + endloop + endfacet + facet normal -1.91079e-05 1.00835e-05 -1 + outer loop + vertex 829.162 256.529 -3.52205e-05 + vertex 832.723 262.86 -3.94365e-05 + vertex 833.337 256.616 -0.000114128 + endloop + endfacet + facet normal -1.91101e-05 1.01925e-05 -1 + outer loop + vertex 829.431 250.299 -0.000103861 + vertex 829.162 256.529 -3.52205e-05 + vertex 833.337 256.616 -0.000114128 + endloop + endfacet + facet normal -4.04877e-05 2.34128e-05 -1 + outer loop + vertex 829.431 250.299 -0.000103861 + vertex 833.337 256.616 -0.000114128 + vertex 833.737 250.29 -0.000278434 + endloop + endfacet + facet normal -4.04892e-05 2.26856e-05 -1 + outer loop + vertex 829.611 244.12 -0.000251354 + vertex 829.431 250.299 -0.000103861 + vertex 833.737 250.29 -0.000278434 + endloop + endfacet + facet normal -3.62569e-05 2.2809e-05 -1 + outer loop + vertex 825.185 244.143 -9.03411e-05 + vertex 829.431 250.299 -0.000103861 + vertex 829.611 244.12 -0.000251354 + endloop + endfacet + facet normal -3.62639e-05 2.14444e-05 -1 + outer loop + vertex 825.289 238.429 -0.000216667 + vertex 825.185 244.143 -9.03411e-05 + vertex 829.611 244.12 -0.000251354 + endloop + endfacet + facet normal -6.66173e-05 4.44954e-05 -1 + outer loop + vertex 825.289 238.429 -0.000216667 + vertex 829.611 244.12 -0.000251354 + vertex 829.782 238.321 -0.000520781 + endloop + endfacet + facet normal -6.6625e-05 4.41741e-05 -1 + outer loop + vertex 825.351 233.385 -0.000443588 + vertex 825.289 238.429 -0.000216667 + vertex 829.782 238.321 -0.000520781 + endloop + endfacet + facet normal -7.24204e-05 4.43239e-05 -1 + outer loop + vertex 829.782 238.321 -0.000520781 + vertex 829.611 244.12 -0.000251354 + vertex 834.008 244.015 -0.000574395 + endloop + endfacet + facet normal -3.16867e-05 2.15283e-05 -1 + outer loop + vertex 820.811 238.487 -7.35154e-05 + vertex 825.185 244.143 -9.03411e-05 + vertex 825.289 238.429 -0.000216667 + endloop + endfacet + facet normal -3.17184e-05 1.91038e-05 -1 + outer loop + vertex 820.922 233.524 -0.000171844 + vertex 820.811 238.487 -7.35154e-05 + vertex 825.289 238.429 -0.000216667 + endloop + endfacet + facet normal -1.4672e-05 8.3707e-06 -1 + outer loop + vertex 820.811 238.487 -7.35154e-05 + vertex 820.794 244.125 -2.60631e-05 + vertex 825.185 244.143 -9.03411e-05 + endloop + endfacet + facet normal -1.46768e-05 9.59089e-06 -1 + outer loop + vertex 820.794 244.125 -2.60631e-05 + vertex 825.131 250.229 -3.1178e-05 + vertex 825.185 244.143 -9.03411e-05 + endloop + endfacet + facet normal -5.60974e-06 3.14813e-06 -1 + outer loop + vertex 820.794 244.125 -2.60631e-05 + vertex 820.902 250.144 -7.72577e-06 + vertex 825.131 250.229 -3.1178e-05 + endloop + endfacet + facet normal -5.61653e-06 3.4834e-06 -1 + outer loop + vertex 820.902 250.144 -7.72577e-06 + vertex 825.023 256.385 -9.12852e-06 + vertex 825.131 250.229 -3.1178e-05 + endloop + endfacet + facet normal -6.42539e-06 3.46917e-06 -1 + outer loop + vertex 825.131 250.229 -3.1178e-05 + vertex 825.023 256.385 -9.12852e-06 + vertex 829.162 256.529 -3.52205e-05 + endloop + endfacet + facet normal -6.43009e-06 3.60356e-06 -1 + outer loop + vertex 825.023 256.385 -9.12852e-06 + vertex 828.707 262.702 -1.00547e-05 + vertex 829.162 256.529 -3.52205e-05 + endloop + endfacet + facet normal -2.09482e-06 1.07514e-06 -1 + outer loop + vertex 825.023 256.385 -9.12852e-06 + vertex 824.891 262.585 -2.18654e-06 + vertex 828.707 262.702 -1.00547e-05 + endloop + endfacet + facet normal -2.09405e-06 1.0501e-06 -1 + outer loop + vertex 824.891 262.585 -2.18654e-06 + vertex 828.191 268.977 -2.38509e-06 + vertex 828.707 262.702 -1.00547e-05 + endloop + endfacet + facet normal -2.39581e-06 1.02529e-06 -1 + outer loop + vertex 828.707 262.702 -1.00547e-05 + vertex 828.191 268.977 -2.38509e-06 + vertex 831.909 269.129 -1.11352e-05 + endloop + endfacet + facet normal -2.39446e-06 9.92378e-07 -1 + outer loop + vertex 828.191 268.977 -2.38509e-06 + vertex 831.072 275.658 -2.65349e-06 + vertex 831.909 269.129 -1.11352e-05 + endloop + endfacet + facet normal -8.98341e-07 3.47214e-07 -1 + outer loop + vertex 828.191 268.977 -2.38509e-06 + vertex 828.115 275.65 -3.87083e-15 + vertex 831.072 275.658 -2.65349e-06 + endloop + endfacet + facet normal -8.98297e-07 3.30306e-07 -1 + outer loop + vertex 828.115 275.65 -3.87083e-15 + vertex 830.662 282.575 -9.33552e-15 + vertex 831.072 275.658 -2.65349e-06 + endloop + endfacet + facet normal -1.02736e-06 3.22647e-07 -1 + outer loop + vertex 831.072 275.658 -2.65349e-06 + vertex 830.662 282.575 -9.33552e-15 + vertex 833.522 282.687 -2.902e-06 + endloop + endfacet + facet normal -1.02619e-06 2.92713e-07 -1 + outer loop + vertex 830.662 282.575 -9.33552e-15 + vertex 832.843 290.221 -1.64848e-14 + vertex 833.522 282.687 -2.902e-06 + endloop + endfacet + facet normal -7.7333e-07 3.48633e-07 -1 + outer loop + vertex 825.048 268.845 5.44795e-16 + vertex 828.115 275.65 -3.87083e-15 + vertex 828.191 268.977 -2.38509e-06 + endloop + endfacet + facet normal -7.74168e-07 3.68642e-07 -1 + outer loop + vertex 824.891 262.585 -2.18654e-06 + vertex 825.048 268.845 5.44795e-16 + vertex 828.191 268.977 -2.38509e-06 + endloop + endfacet + facet normal -6.88658e-07 3.66501e-07 -1 + outer loop + vertex 821.893 262.917 3.61983e-15 + vertex 825.048 268.845 5.44795e-16 + vertex 824.891 262.585 -2.18654e-06 + endloop + endfacet + facet normal -6.89174e-07 3.61841e-07 -1 + outer loop + vertex 821.139 256.342 -1.85959e-06 + vertex 821.893 262.917 3.61983e-15 + vertex 824.891 262.585 -2.18654e-06 + endloop + endfacet + facet normal -5.66533e-07 3.47779e-07 -1 + outer loop + vertex 818.024 256.614 6.11807e-15 + vertex 821.893 262.917 3.61983e-15 + vertex 821.139 256.342 -1.85959e-06 + endloop + endfacet + facet normal -5.67144e-07 3.40805e-07 -1 + outer loop + vertex 817 250.236 -1.59345e-06 + vertex 818.024 256.614 6.11807e-15 + vertex 821.139 256.342 -1.85959e-06 + endloop + endfacet + facet normal -1.54788e-06 1.00552e-06 -1 + outer loop + vertex 817 250.236 -1.59345e-06 + vertex 821.139 256.342 -1.85959e-06 + vertex 820.902 250.144 -7.72577e-06 + endloop + endfacet + facet normal -1.5507e-06 8.86152e-07 -1 + outer loop + vertex 816.554 244.19 -6.25776e-06 + vertex 817 250.236 -1.59345e-06 + vertex 820.902 250.144 -7.72577e-06 + endloop + endfacet + facet normal -1.23264e-06 8.62638e-07 -1 + outer loop + vertex 812.626 244.422 -1.21689e-06 + vertex 817 250.236 -1.59345e-06 + vertex 816.554 244.19 -6.25776e-06 + endloop + endfacet + facet normal -1.23979e-06 7.41708e-07 -1 + outer loop + vertex 812.233 238.848 -4.86369e-06 + vertex 812.626 244.422 -1.21689e-06 + vertex 816.554 244.19 -6.25776e-06 + endloop + endfacet + facet normal -3.63285e-06 2.67709e-06 -1 + outer loop + vertex 812.233 238.848 -4.86369e-06 + vertex 816.554 244.19 -6.25776e-06 + vertex 816.44 238.612 -2.07788e-05 + endloop + endfacet + facet normal -3.66625e-06 2.08187e-06 -1 + outer loop + vertex 812.231 233.885 -1.51867e-05 + vertex 812.233 238.848 -4.86369e-06 + vertex 816.44 238.612 -2.07788e-05 + endloop + endfacet + facet normal -4.62957e-06 2.69735e-06 -1 + outer loop + vertex 816.44 238.612 -2.07788e-05 + vertex 816.554 244.19 -6.25776e-06 + vertex 820.794 244.125 -2.60631e-05 + endloop + endfacet + facet normal -9.27663e-07 7.19688e-07 -1 + outer loop + vertex 808.171 239.076 -9.31552e-07 + vertex 812.626 244.422 -1.21689e-06 + vertex 812.233 238.848 -4.86369e-06 + endloop + endfacet + facet normal -3.36036e-07 2.26665e-07 -1 + outer loop + vertex 808.171 239.076 -9.31552e-07 + vertex 809.093 244.552 8.87132e-15 + vertex 812.626 244.422 -1.21689e-06 + endloop + endfacet + facet normal -3.34757e-07 2.61515e-07 -1 + outer loop + vertex 809.093 244.552 8.87132e-15 + vertex 813.924 250.736 7.76998e-15 + vertex 812.626 244.422 -1.21689e-06 + endloop + endfacet + facet normal -4.70843e-07 2.89479e-07 -1 + outer loop + vertex 812.626 244.422 -1.21689e-06 + vertex 813.924 250.736 7.76998e-15 + vertex 817 250.236 -1.59345e-06 + endloop + endfacet + facet normal -4.65156e-07 3.24442e-07 -1 + outer loop + vertex 813.924 250.736 7.76998e-15 + vertex 818.024 256.614 6.11807e-15 + vertex 817 250.236 -1.59345e-06 + endloop + endfacet + facet normal -1.88346e-06 1.07964e-06 -1 + outer loop + vertex 821.139 256.342 -1.85959e-06 + vertex 824.891 262.585 -2.18654e-06 + vertex 825.023 256.385 -9.12852e-06 + endloop + endfacet + facet normal -1.88278e-06 1.01829e-06 -1 + outer loop + vertex 820.902 250.144 -7.72577e-06 + vertex 821.139 256.342 -1.85959e-06 + vertex 825.023 256.385 -9.12852e-06 + endloop + endfacet + facet normal -4.62295e-06 3.13033e-06 -1 + outer loop + vertex 816.554 244.19 -6.25776e-06 + vertex 820.902 250.144 -7.72577e-06 + vertex 820.794 244.125 -2.60631e-05 + endloop + endfacet + facet normal -1.18253e-05 8.37958e-06 -1 + outer loop + vertex 816.44 238.612 -2.07788e-05 + vertex 820.794 244.125 -2.60631e-05 + vertex 820.811 238.487 -7.35154e-05 + endloop + endfacet + facet normal -1.18666e-05 6.93225e-06 -1 + outer loop + vertex 816.534 233.655 -5.62628e-05 + vertex 816.44 238.612 -2.07788e-05 + vertex 820.811 238.487 -7.35154e-05 + endloop + endfacet + facet normal -1.70602e-05 9.56993e-06 -1 + outer loop + vertex 825.185 244.143 -9.03411e-05 + vertex 825.131 250.229 -3.1178e-05 + vertex 829.431 250.299 -0.000103861 + endloop + endfacet + facet normal -1.70718e-05 1.02805e-05 -1 + outer loop + vertex 825.131 250.229 -3.1178e-05 + vertex 829.162 256.529 -3.52205e-05 + vertex 829.431 250.299 -0.000103861 + endloop + endfacet + facet normal -7.45516e-06 3.5281e-06 -1 + outer loop + vertex 829.162 256.529 -3.52205e-05 + vertex 828.707 262.702 -1.00547e-05 + vertex 832.723 262.86 -3.94365e-05 + endloop + endfacet + facet normal -7.45585e-06 3.54581e-06 -1 + outer loop + vertex 828.707 262.702 -1.00547e-05 + vertex 831.909 269.129 -1.11352e-05 + vertex 832.723 262.86 -3.94365e-05 + endloop + endfacet + facet normal -2.74202e-06 9.47841e-07 -1 + outer loop + vertex 831.909 269.129 -1.11352e-05 + vertex 831.072 275.658 -2.65349e-06 + vertex 834.67 275.815 -1.23684e-05 + endloop + endfacet + facet normal -2.74079e-06 9.19718e-07 -1 + outer loop + vertex 831.072 275.658 -2.65349e-06 + vertex 833.522 282.687 -2.902e-06 + vertex 834.67 275.815 -1.23684e-05 + endloop + endfacet + facet normal -1.08152e-06 2.87727e-07 -1 + outer loop + vertex 833.522 282.687 -2.902e-06 + vertex 832.843 290.221 -1.64848e-14 + vertex 835.513 290.035 -2.94129e-06 + endloop + endfacet + facet normal -1.08602e-06 2.23242e-07 -1 + outer loop + vertex 832.843 290.221 -1.64848e-14 + vertex 834.389 297.745 -2.46234e-14 + vertex 835.513 290.035 -2.94129e-06 + endloop + endfacet + facet normal -7.12548e-06 -3.73909e-06 -1 + outer loop + vertex 813.822 456.009 -2.48557e-05 + vertex 807.986 463.224 -1.02484e-05 + vertex 811.876 464.485 -4.26826e-05 + endloop + endfacet + facet normal -4.49503e-06 -2.19229e-06 -1 + outer loop + vertex 816.222 447.47 -1.6922e-05 + vertex 810.045 454.915 -5.47871e-06 + vertex 813.822 456.009 -2.48557e-05 + endloop + endfacet + facet normal -3.24218e-06 -1.15978e-06 -1 + outer loop + vertex 818.682 438.918 -1.49812e-05 + vertex 812.462 446.434 -3.52942e-06 + vertex 816.222 447.47 -1.6922e-05 + endloop + endfacet + facet normal -2.94071e-06 -8.61771e-07 -1 + outer loop + vertex 821.056 430.477 -1.46865e-05 + vertex 814.966 437.93 -3.20277e-06 + vertex 818.682 438.918 -1.49812e-05 + endloop + endfacet + facet normal -2.93527e-06 -7.95204e-07 -1 + outer loop + vertex 823.28 422.192 -1.46269e-05 + vertex 817.39 429.525 -3.1685e-06 + vertex 821.056 430.477 -1.46865e-05 + endloop + endfacet + facet normal -2.95203e-06 -7.9495e-07 -1 + outer loop + vertex 825.392 414.017 -1.43614e-05 + vertex 819.68 421.233 -3.23815e-06 + vertex 823.28 422.192 -1.46269e-05 + endloop + endfacet + facet normal -2.94833e-06 -7.45433e-07 -1 + outer loop + vertex 827.45 405.852 -1.4345e-05 + vertex 821.849 413.086 -3.22218e-06 + vertex 825.392 414.017 -1.43614e-05 + endloop + endfacet + facet normal -2.99727e-06 -7.40911e-07 -1 + outer loop + vertex 829.49 397.616 -1.43573e-05 + vertex 823.949 405.001 -3.22092e-06 + vertex 827.45 405.852 -1.4345e-05 + endloop + endfacet + facet normal -3.05698e-06 -7.02991e-07 -1 + outer loop + vertex 831.496 389.283 -1.46307e-05 + vertex 826.04 396.779 -3.22014e-06 + vertex 829.49 397.616 -1.43573e-05 + endloop + endfacet + facet normal -3.16318e-06 -7.18304e-07 -1 + outer loop + vertex 833.422 380.873 -1.46835e-05 + vertex 828.096 388.472 -3.29374e-06 + vertex 831.496 389.283 -1.46307e-05 + endloop + endfacet + facet normal -3.22861e-06 -6.99938e-07 -1 + outer loop + vertex 835.225 372.413 -1.45822e-05 + vertex 830.048 380.128 -3.26875e-06 + vertex 833.422 380.873 -1.46835e-05 + endloop + endfacet + facet normal -3.25527e-06 -6.29571e-07 -1 + outer loop + vertex 836.871 363.933 -1.4602e-05 + vertex 831.88 371.728 -3.26249e-06 + vertex 835.225 372.413 -1.45822e-05 + endloop + endfacet + facet normal -3.30903e-06 -5.61568e-07 -1 + outer loop + vertex 838.333 355.462 -1.4683e-05 + vertex 833.554 363.298 -3.26753e-06 + vertex 836.871 363.933 -1.4602e-05 + endloop + endfacet + facet normal -3.37604e-06 -5.32874e-07 -1 + outer loop + vertex 839.585 347.017 -1.44074e-05 + vertex 835.043 354.854 -3.25163e-06 + vertex 838.333 355.462 -1.4683e-05 + endloop + endfacet + facet normal -3.34601e-06 -3.79381e-07 -1 + outer loop + vertex 840.593 338.601 -1.45892e-05 + vertex 836.31 346.464 -3.23973e-06 + vertex 839.585 347.017 -1.44074e-05 + endloop + endfacet + facet normal -3.45282e-06 -3.04037e-07 -1 + outer loop + vertex 841.318 330.22 -1.4542e-05 + vertex 837.329 338.089 -3.16315e-06 + vertex 840.593 338.601 -1.45892e-05 + endloop + endfacet + facet normal -3.44256e-06 -1.57788e-07 -1 + outer loop + vertex 841.716 321.914 -1.4605e-05 + vertex 838.059 329.775 -3.25384e-06 + vertex 841.318 330.22 -1.4542e-05 + endloop + endfacet + facet normal -3.47324e-06 -1.66991e-08 -1 + outer loop + vertex 841.731 313.732 -1.45203e-05 + vertex 838.451 321.525 -3.25704e-06 + vertex 841.716 321.914 -1.4605e-05 + endloop + endfacet + facet normal -3.4523e-06 1.74432e-07 -1 + outer loop + vertex 841.299 305.708 -1.44283e-05 + vertex 838.446 313.368 -3.24178e-06 + vertex 841.731 313.732 -1.45203e-05 + endloop + endfacet + facet normal -3.41436e-06 3.50877e-07 -1 + outer loop + vertex 840.374 297.863 -1.40199e-05 + vertex 837.974 305.362 -3.1967e-06 + vertex 841.299 305.708 -1.44283e-05 + endloop + endfacet + facet normal -3.27808e-06 5.98526e-07 -1 + outer loop + vertex 838.939 290.23 -1.38844e-05 + vertex 837 297.579 -3.13233e-06 + vertex 840.374 297.863 -1.40199e-05 + endloop + endfacet + facet normal -9.9793e-06 2.51336e-06 -1 + outer loop + vertex 837.02 282.854 -1.32784e-05 + vertex 838.939 290.23 -1.38844e-05 + vertex 840.76 283.114 -4.99434e-05 + endloop + endfacet + facet normal -9.99527e-06 2.74304e-06 -1 + outer loop + vertex 838.485 276.025 -4.66567e-05 + vertex 837.02 282.854 -1.32784e-05 + vertex 840.76 283.114 -4.99434e-05 + endloop + endfacet + facet normal -2.33976e-05 8.78783e-06 -1 + outer loop + vertex 835.813 269.303 -4.32033e-05 + vertex 838.485 276.025 -4.66567e-05 + vertex 839.791 269.444 -0.000135039 + endloop + endfacet + facet normal -2.34216e-05 9.46218e-06 -1 + outer loop + vertex 836.786 262.965 -0.000125943 + vertex 835.813 269.303 -4.32033e-05 + vertex 839.791 269.444 -0.000135039 + endloop + endfacet + facet normal -4.5386e-05 2.279e-05 -1 + outer loop + vertex 833.337 256.616 -0.000114128 + vertex 836.786 262.965 -0.000125943 + vertex 837.527 256.628 -0.000304036 + endloop + endfacet + facet normal -4.53869e-05 2.31027e-05 -1 + outer loop + vertex 833.737 250.29 -0.000278434 + vertex 833.337 256.616 -0.000114128 + vertex 837.527 256.628 -0.000304036 + endloop + endfacet + facet normal -7.24271e-05 4.40416e-05 -1 + outer loop + vertex 829.611 244.12 -0.000251354 + vertex 833.737 250.29 -0.000278434 + vertex 834.008 244.015 -0.000574395 + endloop + endfacet + facet normal -0.000106212 6.93988e-05 -1 + outer loop + vertex 829.782 238.321 -0.000520781 + vertex 834.008 244.015 -0.000574395 + vertex 834.25 238.107 -0.00101009 + endloop + endfacet + facet normal -0.000105857 7.68141e-05 -1 + outer loop + vertex 829.87 233.083 -0.000932414 + vertex 829.782 238.321 -0.000520781 + vertex 834.25 238.107 -0.00101009 + endloop + endfacet + facet normal -0.000120353 6.51707e-05 -1 + outer loop + vertex 838.36 243.801 -0.00107886 + vertex 838.024 250.2 -0.000621345 + vertex 842.308 250.032 -0.00114788 + endloop + endfacet + facet normal -0.000120455 6.25613e-05 -1 + outer loop + vertex 838.024 250.2 -0.000621345 + vertex 841.737 256.583 -0.000669205 + vertex 842.308 250.032 -0.00114788 + endloop + endfacet + facet normal -9.35947e-05 4.02092e-05 -1 + outer loop + vertex 841.737 256.583 -0.000669205 + vertex 840.891 263.019 -0.000331304 + vertex 845.039 263.028 -0.000719124 + endloop + endfacet + facet normal -9.35898e-05 3.79515e-05 -1 + outer loop + vertex 840.891 263.019 -0.000331304 + vertex 843.819 269.549 -0.000357458 + vertex 845.039 263.028 -0.000719124 + endloop + endfacet + facet normal -6.02213e-05 1.87256e-05 -1 + outer loop + vertex 843.819 269.549 -0.000357458 + vertex 842.383 276.217 -0.000146134 + vertex 846.338 276.372 -0.0003814 + endloop + endfacet + facet normal -6.01613e-05 1.71924e-05 -1 + outer loop + vertex 842.383 276.217 -0.000146134 + vertex 844.582 283.358 -0.000155643 + vertex 846.338 276.372 -0.0003814 + endloop + endfacet + facet normal -2.93036e-05 6.53736e-06 -1 + outer loop + vertex 844.582 283.358 -0.000155643 + vertex 842.613 290.536 -5.10295e-05 + vertex 846.368 290.826 -0.000159174 + endloop + endfacet + facet normal -3.0276e-05 4.58893e-06 -1 + outer loop + vertex 846.368 290.826 -0.000159174 + vertex 843.986 298.221 -5.31145e-05 + vertex 847.685 298.557 -0.00016355 + endloop + endfacet + facet normal -3.12535e-05 3.09452e-06 -1 + outer loop + vertex 847.685 298.557 -0.00016355 + vertex 844.872 306.105 -5.2293e-05 + vertex 848.521 306.493 -0.000165118 + endloop + endfacet + facet normal -3.08396e-05 1.45051e-06 -1 + outer loop + vertex 848.521 306.493 -0.000165118 + vertex 845.269 314.176 -5.37005e-05 + vertex 848.893 314.617 -0.000164822 + endloop + endfacet + facet normal -3.13475e-05 -3.88217e-07 -1 + outer loop + vertex 848.893 314.617 -0.000164822 + vertex 845.239 322.412 -5.33124e-05 + vertex 848.841 322.907 -0.000166412 + endloop + endfacet + facet normal -3.14499e-05 -1.58198e-06 -1 + outer loop + vertex 848.841 322.907 -0.000166412 + vertex 844.837 330.771 -5.2921e-05 + vertex 848.429 331.317 -0.000166767 + endloop + endfacet + facet normal -3.02251e-05 -2.22254e-06 -1 + outer loop + vertex 848.429 331.317 -0.000166767 + vertex 844.113 339.199 -5.38269e-05 + vertex 847.71 339.796 -0.00016388 + endloop + endfacet + facet normal -3.04266e-05 -3.79482e-06 -1 + outer loop + vertex 847.71 339.796 -0.00016388 + vertex 843.116 347.664 -5.39552e-05 + vertex 846.718 348.312 -0.000166009 + endloop + endfacet + facet normal -3.01447e-05 -4.33199e-06 -1 + outer loop + vertex 846.718 348.312 -0.000166009 + vertex 841.882 356.158 -5.42211e-05 + vertex 845.497 356.86 -0.000166233 + endloop + endfacet + facet normal -3.02197e-05 -4.99974e-06 -1 + outer loop + vertex 845.497 356.86 -0.000166233 + vertex 840.446 364.68 -5.26804e-05 + vertex 844.079 365.432 -0.00016622 + endloop + endfacet + facet normal -2.94248e-05 -5.4334e-06 -1 + outer loop + vertex 844.079 365.432 -0.00016622 + vertex 838.827 373.209 -5.3958e-05 + vertex 842.489 374.009 -0.000166046 + endloop + endfacet + facet normal -2.89641e-05 -5.87059e-06 -1 + outer loop + vertex 842.489 374.009 -0.000166046 + vertex 837.059 381.716 -5.4004e-05 + vertex 840.752 382.561 -0.000165954 + endloop + endfacet + facet normal -2.87461e-05 -6.31187e-06 -1 + outer loop + vertex 840.752 382.561 -0.000165954 + vertex 835.168 390.173 -5.34694e-05 + vertex 838.894 391.066 -0.000166227 + endloop + endfacet + facet normal -2.80397e-05 -6.35249e-06 -1 + outer loop + vertex 838.894 391.066 -0.000166227 + vertex 833.194 398.558 -5.3982e-05 + vertex 836.95 399.509 -0.000165322 + endloop + endfacet + facet normal -2.80334e-05 -6.79239e-06 -1 + outer loop + vertex 836.95 399.509 -0.000165322 + vertex 831.179 406.86 -5.34937e-05 + vertex 834.956 407.875 -0.000166247 + endloop + endfacet + facet normal -2.75745e-05 -6.64997e-06 -1 + outer loop + vertex 834.956 407.875 -0.000166247 + vertex 829.147 415.09 -5.40536e-05 + vertex 832.941 416.174 -0.000165901 + endloop + endfacet + facet normal -2.74375e-05 -6.78419e-06 -1 + outer loop + vertex 832.941 416.174 -0.000165901 + vertex 827.081 423.305 -5.3495e-05 + vertex 830.909 424.44 -0.000166209 + endloop + endfacet + facet normal -2.67179e-05 -6.63758e-06 -1 + outer loop + vertex 830.909 424.44 -0.000166209 + vertex 824.938 431.582 -5.41032e-05 + vertex 828.838 432.725 -0.000165862 + endloop + endfacet + facet normal -2.67545e-05 -7.44895e-06 -1 + outer loop + vertex 828.838 432.725 -0.000165862 + vertex 822.688 439.972 -5.53146e-05 + vertex 826.704 441.064 -0.000170908 + endloop + endfacet + facet normal -2.96849e-05 -1.09329e-05 -1 + outer loop + vertex 826.704 441.064 -0.000170908 + vertex 820.354 448.459 -6.32531e-05 + vertex 824.509 449.469 -0.000197619 + endloop + endfacet + facet normal -4.04238e-05 -2.07599e-05 -1 + outer loop + vertex 824.509 449.469 -0.000197619 + vertex 818.034 456.993 -9.20785e-05 + vertex 822.318 457.927 -0.000284679 + endloop + endfacet + facet normal -5.27526e-05 -2.47422e-05 -1 + outer loop + vertex 822.318 457.927 -0.000284679 + vertex 816.087 465.521 -0.000143803 + vertex 820.432 466.471 -0.000396523 + endloop + endfacet + facet normal -1.28961e-05 4.31759e-05 -1 + outer loop + vertex 820.432 466.471 -0.000396523 + vertex 815.14 474.074 7.1337e-15 + vertex 819.374 475.339 7.04897e-15 + endloop + endfacet + facet normal -0.000194936 -7.0043e-05 -1 + outer loop + vertex 830.573 460.13 -0.00154998 + vertex 824.676 467.506 -0.000917104 + vertex 828.755 468.68 -0.00179446 + endloop + endfacet + facet normal -0.000176654 -8.9947e-05 -1 + outer loop + vertex 832.573 451.755 -0.00115002 + vertex 826.517 458.953 -0.000727645 + vertex 830.573 460.13 -0.00154998 + endloop + endfacet + facet normal -0.000141359 -5.54032e-05 -1 + outer loop + vertex 834.592 443.409 -0.000972932 + vertex 828.588 450.561 -0.000520531 + vertex 832.573 451.755 -0.00115002 + endloop + endfacet + facet normal -0.000123172 -3.56865e-05 -1 + outer loop + vertex 836.603 435.054 -0.000922511 + vertex 830.669 442.212 -0.000447002 + vertex 834.592 443.409 -0.000972932 + endloop + endfacet + facet normal -0.000118342 -2.97052e-05 -1 + outer loop + vertex 838.611 426.683 -0.000911458 + vertex 832.72 433.886 -0.000428342 + vertex 836.603 435.054 -0.000922511 + endloop + endfacet + facet normal -0.000117826 -2.83467e-05 -1 + outer loop + vertex 840.615 418.286 -0.000909528 + vertex 834.748 425.57 -0.000424728 + vertex 838.611 426.683 -0.000911458 + endloop + endfacet + facet normal -0.000118331 -2.80339e-05 -1 + outer loop + vertex 842.604 409.852 -0.00090853 + vertex 836.761 417.242 -0.000424211 + vertex 840.615 418.286 -0.000909528 + endloop + endfacet + facet normal -0.00011924 -2.75607e-05 -1 + outer loop + vertex 844.559 401.367 -0.000907734 + vertex 838.762 408.874 -0.000423394 + vertex 842.604 409.852 -0.00090853 + endloop + endfacet + facet normal -0.000119494 -2.64415e-05 -1 + outer loop + vertex 846.45 392.823 -0.000907801 + vertex 840.736 400.444 -0.000426458 + vertex 844.559 401.367 -0.000907734 + endloop + endfacet + facet normal -0.00012129 -2.5204e-05 -1 + outer loop + vertex 848.249 384.221 -0.000909212 + vertex 842.653 391.951 -0.000425281 + vertex 846.45 392.823 -0.000907801 + endloop + endfacet + facet normal -0.000123398 -2.40353e-05 -1 + outer loop + vertex 849.934 375.572 -0.000909211 + vertex 844.48 383.398 -0.000424358 + vertex 848.249 384.221 -0.000909212 + endloop + endfacet + facet normal -0.000124863 -2.25283e-05 -1 + outer loop + vertex 851.483 366.896 -0.00090721 + vertex 846.189 374.797 -0.000424188 + vertex 849.934 375.572 -0.000909211 + endloop + endfacet + facet normal -0.000125487 -1.9913e-05 -1 + outer loop + vertex 852.871 358.219 -0.000908557 + vertex 847.756 366.172 -0.000425068 + vertex 851.483 366.896 -0.00090721 + endloop + endfacet + facet normal -0.00012724 -1.77885e-05 -1 + outer loop + vertex 854.073 349.564 -0.000907625 + vertex 849.158 357.549 -0.000424267 + vertex 852.871 358.219 -0.000908557 + endloop + endfacet + facet normal -0.00012778 -1.47014e-05 -1 + outer loop + vertex 855.06 340.936 -0.000906779 + vertex 850.368 348.947 -0.000425079 + vertex 854.073 349.564 -0.000907625 + endloop + endfacet + facet normal -0.000128237 -1.06359e-05 -1 + outer loop + vertex 855.79 332.345 -0.000909139 + vertex 851.354 340.375 -0.000425646 + vertex 855.06 340.936 -0.000906779 + endloop + endfacet + facet normal -0.000129391 -6.89902e-06 -1 + outer loop + vertex 856.231 323.824 -0.000907305 + vertex 852.081 331.842 -0.00042574 + vertex 855.79 332.345 -0.000909139 + endloop + endfacet + facet normal -0.000129286 -1.18856e-06 -1 + outer loop + vertex 856.321 315.423 -0.000909014 + vertex 852.506 323.378 -0.00042529 + vertex 856.231 323.824 -0.000907305 + endloop + endfacet + facet normal -0.000129925 4.35918e-06 -1 + outer loop + vertex 856.017 307.185 -0.000905361 + vertex 852.578 315.033 -0.000424335 + vertex 856.321 315.423 -0.000909014 + endloop + endfacet + facet normal -0.000128943 1.10004e-05 -1 + outer loop + vertex 855.269 299.136 -0.000897515 + vertex 852.241 306.852 -0.000422212 + vertex 856.017 307.185 -0.000905361 + endloop + endfacet + facet normal -0.000126623 1.75092e-05 -1 + outer loop + vertex 854.06 291.296 -0.000881661 + vertex 851.449 298.861 -0.00041865 + vertex 855.269 299.136 -0.000897515 + endloop + endfacet + facet normal -0.00012267 2.34051e-05 -1 + outer loop + vertex 852.404 283.72 -0.000855916 + vertex 850.186 291.079 -0.000411496 + vertex 854.06 291.296 -0.000881661 + endloop + endfacet + facet normal -0.000116666 2.79301e-05 -1 + outer loop + vertex 850.344 276.48 -0.00081773 + vertex 848.466 283.56 -0.000400883 + vertex 852.404 283.72 -0.000855916 + endloop + endfacet + facet normal -0.000150066 4.65387e-05 -1 + outer loop + vertex 847.897 269.609 -0.0007703 + vertex 850.344 276.48 -0.00081773 + vertex 852.009 269.618 -0.00138694 + endloop + endfacet + facet normal -0.000150075 5.03567e-05 -1 + outer loop + vertex 849.217 262.987 -0.00130185 + vertex 847.897 269.609 -0.0007703 + vertex 852.009 269.618 -0.00138694 + endloop + endfacet + facet normal -0.000159444 6.72037e-05 -1 + outer loop + vertex 845.972 256.483 -0.00122161 + vertex 849.217 262.987 -0.00130185 + vertex 850.234 256.313 -0.00191259 + endloop + endfacet + facet normal -0.000159176 7.39035e-05 -1 + outer loop + vertex 846.607 249.782 -0.00181793 + vertex 845.972 256.483 -0.00122161 + vertex 850.234 256.313 -0.00191259 + endloop + endfacet + facet normal -0.000171777 9.24444e-05 -1 + outer loop + vertex 842.69 243.468 -0.00172869 + vertex 846.607 249.782 -0.00181793 + vertex 847.039 243.016 -0.0025176 + endloop + endfacet + facet normal -0.000218777 0.000134906 -1 + outer loop + vertex 843.017 237.222 -0.00241921 + vertex 847.039 243.016 -0.0025176 + vertex 847.418 236.533 -0.003475 + endloop + endfacet + facet normal -0.00021432 0.000163361 -1 + outer loop + vertex 843.308 231.558 -0.00340692 + vertex 843.017 237.222 -0.00241921 + vertex 847.418 236.533 -0.003475 + endloop + endfacet + facet normal -0.000199313 0.000119945 -1 + outer loop + vertex 851.435 242.436 -0.00354934 + vertex 850.938 249.431 -0.00261135 + vertex 855.322 248.954 -0.00354232 + endloop + endfacet + facet normal -0.000201627 9.87055e-05 -1 + outer loop + vertex 850.938 249.431 -0.00261135 + vertex 854.535 256.046 -0.00268361 + vertex 855.322 248.954 -0.00354232 + endloop + endfacet + facet normal -0.000171874 6.98196e-05 -1 + outer loop + vertex 854.535 256.046 -0.00268361 + vertex 853.427 262.878 -0.00201612 + vertex 857.676 262.674 -0.00276074 + endloop + endfacet + facet normal -0.000172682 5.29386e-05 -1 + outer loop + vertex 853.427 262.878 -0.00201612 + vertex 856.159 269.562 -0.00213403 + vertex 857.676 262.674 -0.00276074 + endloop + endfacet + facet normal -0.00019273 4.6357e-05 -1 + outer loop + vertex 856.159 269.562 -0.00213403 + vertex 854.39 276.54 -0.0014697 + vertex 858.479 276.543 -0.0022576 + endloop + endfacet + facet normal -0.00020629 3.93885e-05 -1 + outer loop + vertex 858.479 276.543 -0.0022576 + vertex 856.389 283.836 -0.00153927 + vertex 860.426 283.9 -0.00236942 + endloop + endfacet + facet normal -0.000217024 3.31988e-05 -1 + outer loop + vertex 860.426 283.9 -0.00236942 + vertex 857.985 291.475 -0.00158821 + vertex 861.977 291.6 -0.00245046 + endloop + endfacet + facet normal -0.000224002 2.57508e-05 -1 + outer loop + vertex 861.977 291.6 -0.00245046 + vertex 859.147 299.374 -0.00161628 + vertex 863.097 299.564 -0.0024962 + endloop + endfacet + facet normal -0.000228245 1.62096e-05 -1 + outer loop + vertex 863.097 299.564 -0.0024962 + vertex 859.857 307.483 -0.00162851 + vertex 863.771 307.737 -0.00251754 + endloop + endfacet + facet normal -0.000230324 5.75112e-06 -1 + outer loop + vertex 863.771 307.737 -0.00251754 + vertex 860.133 315.78 -0.00163341 + vertex 864.021 316.097 -0.00252718 + endloop + endfacet + facet normal -0.000230961 -3.95811e-06 -1 + outer loop + vertex 864.021 316.097 -0.00252718 + vertex 860.019 324.242 -0.00163495 + vertex 863.883 324.622 -0.00252909 + endloop + endfacet + facet normal -0.00023076 -1.25133e-05 -1 + outer loop + vertex 863.883 324.622 -0.00252909 + vertex 859.566 332.823 -0.00163537 + vertex 863.419 333.265 -0.00253019 + endloop + endfacet + facet normal -0.000229564 -1.95658e-05 -1 + outer loop + vertex 863.419 333.265 -0.00253019 + vertex 858.826 341.471 -0.00163627 + vertex 862.673 341.974 -0.00252916 + endloop + endfacet + facet normal -0.00022847 -2.58165e-05 -1 + outer loop + vertex 862.673 341.974 -0.00252916 + vertex 857.841 350.156 -0.00163647 + vertex 861.685 350.719 -0.00252932 + endloop + endfacet + facet normal -0.000226966 -3.09608e-05 -1 + outer loop + vertex 861.685 350.719 -0.00252932 + vertex 856.644 358.868 -0.00163741 + vertex 860.49 359.49 -0.00252966 + endloop + endfacet + facet normal -0.000225908 -3.54115e-05 -1 + outer loop + vertex 860.49 359.49 -0.00252966 + vertex 855.266 367.6 -0.00163663 + vertex 859.118 368.279 -0.00253097 + endloop + endfacet + facet normal -0.00022397 -3.87025e-05 -1 + outer loop + vertex 859.118 368.279 -0.00253097 + vertex 853.733 376.33 -0.0016363 + vertex 857.594 377.064 -0.00252942 + endloop + endfacet + facet normal -0.000222578 -4.20975e-05 -1 + outer loop + vertex 857.594 377.064 -0.00252942 + vertex 852.068 385.031 -0.00163488 + vertex 855.941 385.818 -0.00253019 + endloop + endfacet + facet normal -0.000219914 -4.43808e-05 -1 + outer loop + vertex 855.941 385.818 -0.00253019 + vertex 850.29 393.679 -0.00163629 + vertex 854.18 394.516 -0.00252891 + endloop + endfacet + facet normal -0.000217784 -4.66083e-05 -1 + outer loop + vertex 854.18 394.516 -0.00252891 + vertex 848.422 402.27 -0.00163636 + vertex 852.33 403.155 -0.00252868 + endloop + endfacet + facet normal -0.000216167 -4.84745e-05 -1 + outer loop + vertex 852.33 403.155 -0.00252868 + vertex 846.487 410.809 -0.0016366 + vertex 850.411 411.744 -0.00253014 + endloop + endfacet + facet normal -0.000215309 -4.99223e-05 -1 + outer loop + vertex 850.411 411.744 -0.00253014 + vertex 844.508 419.306 -0.00163681 + vertex 848.444 420.295 -0.00253345 + endloop + endfacet + facet normal -0.00021648 -5.28721e-05 -1 + outer loop + vertex 848.444 420.295 -0.00253345 + vertex 842.51 427.769 -0.00164404 + vertex 846.449 428.819 -0.00255233 + endloop + endfacet + facet normal -0.000225747 -6.29181e-05 -1 + outer loop + vertex 846.449 428.819 -0.00255233 + vertex 840.505 436.208 -0.00167535 + vertex 844.442 437.322 -0.00263433 + endloop + endfacet + facet normal -0.000250345 -8.98926e-05 -1 + outer loop + vertex 844.442 437.322 -0.00263433 + vertex 838.502 444.618 -0.00180304 + vertex 842.433 445.797 -0.00289324 + endloop + endfacet + facet normal -0.000296048 -0.00014128 -1 + outer loop + vertex 842.433 445.797 -0.00289324 + vertex 836.5 453.005 -0.00215504 + vertex 840.425 454.238 -0.00349128 + endloop + endfacet + facet normal -0.000341248 -0.000186214 -1 + outer loop + vertex 840.425 454.238 -0.00349128 + vertex 834.521 461.396 -0.00280946 + vertex 838.443 462.671 -0.00438535 + endloop + endfacet + facet normal -0.000321145 -5.73891e-05 -1 + outer loop + vertex 838.443 462.671 -0.00438535 + vertex 832.734 469.958 -0.00296996 + vertex 836.69 471.242 -0.00431428 + endloop + endfacet + facet normal -0.000139924 0.000464054 -1 + outer loop + vertex 836.69 471.242 -0.00431428 + vertex 831.542 478.987 8.09901e-15 + vertex 835.717 480.246 8.66469e-15 + endloop + endfacet + facet normal -0.00024433 1.5672e-05 -1 + outer loop + vertex 842.393 463.892 -0.00597273 + vertex 840.65 472.482 -0.00541239 + vertex 846.379 465.056 -0.00692847 + endloop + endfacet + facet normal -0.000197489 -0.00014474 -1 + outer loop + vertex 848.387 456.537 -0.006092 + vertex 842.393 463.892 -0.00597273 + vertex 846.379 465.056 -0.00692847 + endloop + endfacet + facet normal -0.000233826 -0.000181816 -1 + outer loop + vertex 850.425 447.997 -0.00501582 + vertex 844.386 455.414 -0.00495224 + vertex 848.387 456.537 -0.006092 + endloop + endfacet + facet normal -0.000196575 -0.000126409 -1 + outer loop + vertex 852.454 439.418 -0.00433022 + vertex 846.408 446.918 -0.00408976 + vertex 850.425 447.997 -0.00501582 + endloop + endfacet + facet normal -0.000152869 -7.09273e-05 -1 + outer loop + vertex 854.468 430.814 -0.0040278 + vertex 848.424 438.388 -0.00364121 + vertex 852.454 439.418 -0.00433022 + endloop + endfacet + facet normal -0.000128847 -4.221e-05 -1 + outer loop + vertex 856.462 422.188 -0.00392067 + vertex 850.433 429.831 -0.00346641 + vertex 854.468 430.814 -0.0040278 + endloop + endfacet + facet normal -0.000118573 -2.92384e-05 -1 + outer loop + vertex 858.422 413.54 -0.00390022 + vertex 852.424 421.252 -0.00341455 + vertex 856.462 422.188 -0.00392067 + endloop + endfacet + facet normal -0.000116759 -2.57493e-05 -1 + outer loop + vertex 860.332 404.853 -0.00389956 + vertex 854.383 412.653 -0.00340582 + vertex 858.422 413.54 -0.00390022 + endloop + endfacet + facet normal -0.000117368 -2.3269e-05 -1 + outer loop + vertex 862.173 396.112 -0.00391227 + vertex 856.292 404.016 -0.00340596 + vertex 860.332 404.853 -0.00389956 + endloop + endfacet + facet normal -0.000120334 -2.30672e-05 -1 + outer loop + vertex 863.93 387.305 -0.00392044 + vertex 858.133 395.327 -0.00340791 + vertex 862.173 396.112 -0.00391227 + endloop + endfacet + facet normal -0.00012237 -2.23925e-05 -1 + outer loop + vertex 865.582 378.438 -0.0039241 + vertex 859.885 386.575 -0.00340923 + vertex 863.93 387.305 -0.00392044 + endloop + endfacet + facet normal -0.000123485 -2.18484e-05 -1 + outer loop + vertex 867.11 369.533 -0.00391823 + vertex 861.533 377.768 -0.00340948 + vertex 865.582 378.438 -0.0039241 + endloop + endfacet + facet normal -0.000121749 -1.83635e-05 -1 + outer loop + vertex 868.49 360.622 -0.00392264 + vertex 863.055 368.924 -0.0034133 + vertex 867.11 369.533 -0.00391823 + endloop + endfacet + facet normal -0.000123046 -1.64667e-05 -1 + outer loop + vertex 869.697 351.725 -0.00392466 + vertex 864.428 360.076 -0.00341375 + vertex 868.49 360.622 -0.00392264 + endloop + endfacet + facet normal -0.000124642 -1.32499e-05 -1 + outer loop + vertex 870.702 342.852 -0.00393226 + vertex 865.625 351.244 -0.00341072 + vertex 869.697 351.725 -0.00392466 + endloop + endfacet + facet normal -0.000126353 -1.22141e-05 -1 + outer loop + vertex 871.47 334.009 -0.00392139 + vertex 866.619 342.437 -0.00341132 + vertex 870.702 342.852 -0.00393226 + endloop + endfacet + facet normal -0.000124654 -6.37527e-06 -1 + outer loop + vertex 871.965 325.231 -0.00392711 + vertex 867.374 333.663 -0.00340849 + vertex 871.47 334.009 -0.00392139 + endloop + endfacet + facet normal -0.000125703 -2.95987e-06 -1 + outer loop + vertex 872.137 316.568 -0.00392311 + vertex 867.853 324.955 -0.00340943 + vertex 871.965 325.231 -0.00392711 + endloop + endfacet + facet normal -0.000125243 1.05132e-06 -1 + outer loop + vertex 871.935 308.065 -0.00390664 + vertex 868.007 316.364 -0.00340596 + vertex 872.137 316.568 -0.00392311 + endloop + endfacet + facet normal -0.000123793 3.18483e-06 -1 + outer loop + vertex 871.312 299.748 -0.00385606 + vertex 867.784 307.935 -0.0033932 + vertex 871.935 308.065 -0.00390664 + endloop + endfacet + facet normal -0.000118979 3.23822e-06 -1 + outer loop + vertex 870.252 291.639 -0.00375621 + vertex 867.138 299.693 -0.00335966 + vertex 871.312 299.748 -0.00385606 + endloop + endfacet + facet normal -0.000109561 9.15523e-07 -1 + outer loop + vertex 868.771 283.792 -0.00360108 + vertex 866.055 291.659 -0.00329637 + vertex 870.252 291.639 -0.00375621 + endloop + endfacet + facet normal -0.000102647 3.61134e-06 -1 + outer loop + vertex 866.901 276.288 -0.00343631 + vertex 864.539 283.893 -0.0031664 + vertex 868.771 283.792 -0.00360108 + endloop + endfacet + facet normal -9.77094e-05 1.6462e-05 -1 + outer loop + vertex 864.655 269.168 -0.00333403 + vertex 862.641 276.464 -0.00301714 + vertex 866.901 276.288 -0.00343631 + endloop + endfacet + facet normal -0.000105694 4.35308e-05 -1 + outer loop + vertex 862 262.35 -0.00335024 + vertex 860.361 269.422 -0.0028691 + vertex 864.655 269.168 -0.00333403 + endloop + endfacet + facet normal -9.5046e-05 5.93504e-05 -1 + outer loop + vertex 858.885 255.647 -0.00345193 + vertex 862 262.35 -0.00335024 + vertex 863.314 255.081 -0.00390652 + endloop + endfacet + facet normal -8.76129e-05 0.000117528 -1 + outer loop + vertex 859.758 248.303 -0.00439161 + vertex 858.885 255.647 -0.00345193 + vertex 863.314 255.081 -0.00390652 + endloop + endfacet + facet normal -8.81343e-05 9.95174e-05 -1 + outer loop + vertex 855.872 241.698 -0.0047064 + vertex 859.758 248.303 -0.00439161 + vertex 860.343 240.735 -0.00519629 + endloop + endfacet + facet normal 0.000347038 -0.000154026 -1 + outer loop + vertex 856.274 234.673 -0.00567486 + vertex 860.343 240.735 -0.00519629 + vertex 860.709 233.325 -0.00392802 + endloop + endfacet + facet normal 0.000355569 -0.000125956 -1 + outer loop + vertex 856.407 228.21 -0.00481342 + vertex 856.274 234.673 -0.00567486 + vertex 860.709 233.325 -0.00392802 + endloop + endfacet + facet normal 5.1891e-05 -6.98159e-05 -1 + outer loop + vertex 864.806 239.47 -0.00405376 + vertex 864.244 247.422 -0.00463805 + vertex 868.762 246.249 -0.00432171 + endloop + endfacet + facet normal 8.89225e-05 7.28505e-05 -1 + outer loop + vertex 864.244 247.422 -0.00463805 + vertex 867.836 254.296 -0.00381779 + vertex 868.762 246.249 -0.00432171 + endloop + endfacet + facet normal 0.000136254 8.02242e-05 -1 + outer loop + vertex 867.836 254.296 -0.00381779 + vertex 866.423 261.868 -0.00340296 + vertex 870.974 261.183 -0.00283769 + endloop + endfacet + facet normal 0.000219672 2.37411e-05 -1 + outer loop + vertex 870.974 261.183 -0.00283769 + vertex 869.07 268.775 -0.00307572 + vertex 873.644 268.196 -0.00208469 + endloop + endfacet + facet normal 0.000266202 -4.01459e-05 -1 + outer loop + vertex 873.644 268.196 -0.00208469 + vertex 871.305 275.984 -0.00302014 + vertex 875.892 275.511 -0.00177991 + endloop + endfacet + facet normal 0.000278481 -7.69895e-05 -1 + outer loop + vertex 875.892 275.511 -0.00177991 + vertex 873.161 283.576 -0.00316132 + vertex 877.755 283.208 -0.00185381 + endloop + endfacet + facet normal 0.000280167 -7.3132e-05 -1 + outer loop + vertex 877.755 283.208 -0.00185381 + vertex 874.628 291.511 -0.00333697 + vertex 879.225 291.247 -0.00202973 + endloop + endfacet + facet normal 0.000280422 -5.11962e-05 -1 + outer loop + vertex 879.225 291.247 -0.00202973 + vertex 875.672 299.708 -0.00345932 + vertex 880.272 299.546 -0.00216123 + endloop + endfacet + facet normal 0.000279933 -2.72295e-05 -1 + outer loop + vertex 880.272 299.546 -0.00216123 + vertex 876.278 308.111 -0.00351241 + vertex 880.873 308.046 -0.00222437 + endloop + endfacet + facet normal 0.000280277 -8.35358e-06 -1 + outer loop + vertex 880.873 308.046 -0.00222437 + vertex 876.465 316.696 -0.00353215 + vertex 881.049 316.726 -0.00224763 + endloop + endfacet + facet normal 0.000279568 5.02358e-06 -1 + outer loop + vertex 881.049 316.726 -0.00224763 + vertex 876.276 325.439 -0.00353825 + vertex 880.843 325.56 -0.0022608 + endloop + endfacet + facet normal 0.000280729 1.63207e-05 -1 + outer loop + vertex 880.843 325.56 -0.0022608 + vertex 875.764 334.295 -0.00354408 + vertex 880.31 334.503 -0.00226441 + endloop + endfacet + facet normal 0.000281622 2.61767e-05 -1 + outer loop + vertex 880.31 334.503 -0.00226441 + vertex 874.976 343.212 -0.0035385 + vertex 879.499 343.502 -0.00225719 + endloop + endfacet + facet normal 0.000282678 3.31057e-05 -1 + outer loop + vertex 879.499 343.502 -0.00225719 + vertex 873.954 352.159 -0.0035381 + vertex 878.449 352.527 -0.00225517 + endloop + endfacet + facet normal 0.000286585 4.14667e-05 -1 + outer loop + vertex 878.449 352.527 -0.00225517 + vertex 872.729 361.125 -0.0035379 + vertex 877.195 361.57 -0.0022398 + endloop + endfacet + facet normal 0.000294121 5.07912e-05 -1 + outer loop + vertex 877.195 361.57 -0.0022398 + vertex 871.331 370.104 -0.00353102 + vertex 875.763 370.623 -0.00220095 + endloop + endfacet + facet normal 0.000304413 5.97001e-05 -1 + outer loop + vertex 875.763 370.623 -0.00220095 + vertex 869.784 379.073 -0.00351651 + vertex 874.183 379.663 -0.00214237 + endloop + endfacet + facet normal 0.000314873 6.73998e-05 -1 + outer loop + vertex 874.183 379.663 -0.00214237 + vertex 868.115 388.001 -0.00349104 + vertex 872.477 388.66 -0.00207326 + endloop + endfacet + facet normal 0.000329181 7.7771e-05 -1 + outer loop + vertex 872.477 388.66 -0.00207326 + vertex 866.341 396.868 -0.00345461 + vertex 870.665 397.593 -0.00197485 + endloop + endfacet + facet normal 0.000343264 8.24698e-05 -1 + outer loop + vertex 870.665 397.593 -0.00197485 + vertex 864.481 405.669 -0.00343173 + vertex 868.769 406.451 -0.00189516 + endloop + endfacet + facet normal 0.000347342 8.12624e-05 -1 + outer loop + vertex 868.769 406.451 -0.00189516 + vertex 862.555 414.408 -0.00340707 + vertex 866.804 415.251 -0.00186264 + endloop + endfacet + facet normal 0.000341484 6.92493e-05 -1 + outer loop + vertex 866.804 415.251 -0.00186264 + vertex 860.578 423.107 -0.00344451 + vertex 864.787 424.006 -0.00194494 + endloop + endfacet + facet normal 0.000323443 4.16306e-05 -1 + outer loop + vertex 864.787 424.006 -0.00194494 + vertex 858.566 431.781 -0.00363339 + vertex 862.733 432.737 -0.00224597 + endloop + endfacet + facet normal 0.000270731 -2.68343e-05 -1 + outer loop + vertex 862.733 432.737 -0.00224597 + vertex 856.531 440.434 -0.00413156 + vertex 860.655 441.438 -0.00304211 + endloop + endfacet + facet normal 0.00021615 -9.03271e-05 -1 + outer loop + vertex 860.655 441.438 -0.00304211 + vertex 854.479 449.056 -0.00506518 + vertex 858.555 450.107 -0.00427903 + endloop + endfacet + facet normal 0.000257065 -4.80476e-05 -1 + outer loop + vertex 858.555 450.107 -0.00427903 + vertex 852.414 457.637 -0.00621949 + vertex 856.442 458.73 -0.0052364 + endloop + endfacet + facet normal 0.000236176 2.89499e-05 -1 + outer loop + vertex 852.414 457.637 -0.00621949 + vertex 850.374 466.19 -0.00645363 + vertex 856.442 458.73 -0.0052364 + endloop + endfacet + facet normal 0.000316293 0.000364406 -1 + outer loop + vertex 850.374 466.19 -0.00645363 + vertex 844.599 473.665 -0.00555623 + vertex 848.575 474.834 -0.00387305 + endloop + endfacet + facet normal -0.0001272 0.000415125 -1 + outer loop + vertex 848.575 474.834 -0.00387305 + vertex 843.485 482.604 9.50374e-15 + vertex 847.491 483.831 9.57562e-15 + endloop + endfacet + facet normal 0.000481722 0.000423775 -1 + outer loop + vertex 858.275 468.408 -0.00134871 + vertex 852.517 475.992 -0.000908466 + vertex 856.332 477.105 0.00140049 + endloop + endfacet + facet normal 0.000589242 0.000482485 -1 + outer loop + vertex 860.435 459.783 -0.00423708 + vertex 854.357 467.319 -0.00418305 + vertex 858.275 468.408 -0.00134871 + endloop + endfacet + facet normal -0.000166517 -4.02347e-05 -1 + outer loop + vertex 862.625 451.114 -0.0042528 + vertex 860.435 459.783 -0.00423708 + vertex 866.636 452.002 -0.00495654 + endloop + endfacet + facet normal -0.000145492 -0.000135137 -1 + outer loop + vertex 868.923 443.22 -0.00410237 + vertex 862.625 451.114 -0.0042528 + vertex 866.636 452.002 -0.00495654 + endloop + endfacet + facet normal -0.00026683 -0.000253508 -1 + outer loop + vertex 871.183 434.401 -0.00246998 + vertex 864.802 442.392 -0.00279299 + vertex 868.923 443.22 -0.00410237 + endloop + endfacet + facet normal -0.000184257 -0.000209763 -1 + outer loop + vertex 873.408 425.549 -0.00102307 + vertex 866.956 433.633 -0.00152982 + vertex 871.183 434.401 -0.00246998 + endloop + endfacet + facet normal -2.04659e-05 -6.95359e-05 -1 + outer loop + vertex 875.588 416.666 -0.000450039 + vertex 869.079 424.846 -0.000885608 + vertex 873.408 425.549 -0.00102307 + endloop + endfacet + facet normal 5.8155e-05 4.94129e-06 -1 + outer loop + vertex 877.71 407.737 -0.000370784 + vertex 871.162 416.031 -0.000710594 + vertex 875.588 416.666 -0.000450039 + endloop + endfacet + facet normal 7.06861e-05 -1.48801e-05 -1 + outer loop + vertex 879.758 398.738 -9.21254e-05 + vertex 873.192 407.166 -0.000681636 + vertex 877.71 407.737 -0.000370784 + endloop + endfacet + facet normal 0.000141956 2.87961e-05 -1 + outer loop + vertex 881.713 389.663 -7.59015e-05 + vertex 875.152 398.239 -0.000760332 + vertex 879.758 398.738 -9.21254e-05 + endloop + endfacet + facet normal 0.000182271 2.08077e-05 -1 + outer loop + vertex 883.556 380.513 6.95455e-05 + vertex 877.022 389.24 -0.000939722 + vertex 881.713 389.663 -7.59015e-05 + endloop + endfacet + facet normal 0.000233816 7.12602e-05 -1 + outer loop + vertex 885.262 371.317 -0.000186785 + vertex 878.786 380.168 -0.00107027 + vertex 883.556 380.513 6.95455e-05 + endloop + endfacet + facet normal 0.000204279 3.79166e-05 -1 + outer loop + vertex 886.808 362.095 -0.000220579 + vertex 880.42 371.05 -0.00118601 + vertex 885.262 371.317 -0.000186785 + endloop + endfacet + facet normal 0.000220687 4.96996e-05 -1 + outer loop + vertex 888.164 352.881 -0.000379226 + vertex 881.899 361.919 -0.0013126 + vertex 886.808 362.095 -0.000220579 + endloop + endfacet + facet normal 0.000195284 4.60836e-05 -1 + outer loop + vertex 889.3 343.674 -0.000581636 + vertex 883.199 352.792 -0.00135305 + vertex 888.164 352.881 -0.000379226 + endloop + endfacet + facet normal 0.000164902 7.7804e-06 -1 + outer loop + vertex 890.179 334.481 -0.000508267 + vertex 884.287 343.68 -0.00140837 + vertex 889.3 343.674 -0.000581636 + endloop + endfacet + facet normal 0.000178964 2.326e-05 -1 + outer loop + vertex 890.759 325.335 -0.000617243 + vertex 885.13 334.589 -0.00140943 + vertex 890.179 334.481 -0.000508267 + endloop + endfacet + facet normal 0.000150144 -1.42086e-05 -1 + outer loop + vertex 890.984 316.285 -0.000454767 + vertex 885.684 325.546 -0.00138213 + vertex 890.759 325.335 -0.000617243 + endloop + endfacet + facet normal 0.000180761 1.17725e-05 -1 + outer loop + vertex 890.804 307.379 -0.000592307 + vertex 885.903 316.61 -0.00136949 + vertex 890.984 316.285 -0.000454767 + endloop + endfacet + facet normal 0.000145411 -3.45857e-05 -1 + outer loop + vertex 890.165 298.641 -0.000382994 + vertex 885.729 307.823 -0.00134554 + vertex 890.804 307.379 -0.000592307 + endloop + endfacet + facet normal 0.000171082 -3.95103e-05 -1 + outer loop + vertex 889.055 290.095 -0.000235254 + vertex 885.118 299.21 -0.00126881 + vertex 890.165 298.641 -0.000382994 + endloop + endfacet + facet normal 0.000172649 -4.78079e-05 -1 + outer loop + vertex 887.491 281.798 -0.00010853 + vertex 884.054 290.795 -0.00113208 + vertex 889.055 290.095 -0.000235254 + endloop + endfacet + facet normal 0.00017161 -4.0178e-05 -1 + outer loop + vertex 885.515 273.836 -0.000127673 + vertex 882.554 282.636 -0.000989461 + vertex 887.491 281.798 -0.00010853 + endloop + endfacet + facet normal 0.000185763 4.87216e-05 -1 + outer loop + vertex 883.142 266.252 -0.000937953 + vertex 880.65 274.815 -0.000983716 + vertex 885.515 273.836 -0.000127673 + endloop + endfacet + facet normal 0.000149287 0.000100761 -1 + outer loop + vertex 880.327 258.974 -0.00209164 + vertex 878.363 267.377 -0.00153806 + vertex 883.142 266.252 -0.000937953 + endloop + endfacet + facet normal 0.000133292 7.05746e-05 -1 + outer loop + vertex 877.009 251.829 -0.00303809 + vertex 875.633 260.237 -0.0026282 + vertex 880.327 258.974 -0.00209164 + endloop + endfacet + facet normal 0.000112148 -0.000162458 -1 + outer loop + vertex 873.227 244.725 -0.00230819 + vertex 872.421 253.225 -0.0037795 + vertex 877.009 251.829 -0.00303809 + endloop + endfacet + facet normal 0.00291198 -0.00206048 -0.999994 + outer loop + vertex 869.175 237.841 7.84901e-05 + vertex 873.227 244.725 -0.00230819 + vertex 873.356 235.837 0.0163814 + endloop + endfacet + facet normal 0.00966671 -0.00722597 -0.999927 + outer loop + vertex 869.14 229.482 0.021546 + vertex 873.356 235.837 0.0163814 + vertex 872.947 226.992 0.0763461 + endloop + endfacet + facet normal 0.00971071 -0.00715871 -0.999927 + outer loop + vertex 868.678 221.492 0.0742695 + vertex 869.14 229.482 0.021546 + vertex 872.947 226.992 0.0763461 + endloop + endfacet + facet normal 0.00962772 -0.00666956 -0.999931 + outer loop + vertex 877.356 233.511 0.0709929 + vertex 877.574 242.852 0.0107946 + vertex 881.782 240.682 0.0657871 + endloop + endfacet + facet normal 0.00957447 -0.0057262 -0.999938 + outer loop + vertex 881.782 240.682 0.0657871 + vertex 881.508 250.089 0.00929118 + vertex 885.906 248.056 0.0630468 + endloop + endfacet + facet normal 0.0102479 -0.00468042 -0.999937 + outer loop + vertex 885.906 248.056 0.0630468 + vertex 884.961 257.373 0.00975167 + vertex 889.514 255.484 0.0652548 + endloop + endfacet + facet normal 0.00989414 -0.00404487 -0.999943 + outer loop + vertex 889.514 255.484 0.0652548 + vertex 887.897 264.802 0.0115571 + vertex 892.629 263.084 0.0653314 + endloop + endfacet + facet normal 0.0102779 -0.00326289 -0.999942 + outer loop + vertex 892.629 263.084 0.0653314 + vertex 890.403 272.547 0.0115714 + vertex 895.287 271.009 0.0667891 + endloop + endfacet + facet normal 0.0102522 -0.00272293 -0.999944 + outer loop + vertex 895.287 271.009 0.0667891 + vertex 892.49 280.669 0.0118144 + vertex 897.525 279.31 0.0671353 + endloop + endfacet + facet normal 0.0098701 -0.00222971 -0.999949 + outer loop + vertex 897.525 279.31 0.0671353 + vertex 894.147 289.118 0.0119158 + vertex 899.314 287.928 0.0655775 + endloop + endfacet + facet normal 0.0100742 -0.00141939 -0.999948 + outer loop + vertex 899.314 287.928 0.0655775 + vertex 895.329 297.808 0.0114085 + vertex 900.587 296.776 0.065837 + endloop + endfacet + facet normal 0.00993316 -0.000876621 -0.99995 + outer loop + vertex 900.587 296.776 0.065837 + vertex 896.01 306.68 0.0116968 + vertex 901.335 305.798 0.0653655 + endloop + endfacet + facet normal 0.0101727 -0.000160971 -0.999948 + outer loop + vertex 901.335 305.798 0.0653655 + vertex 896.216 315.716 0.0116901 + vertex 901.57 314.974 0.0662778 + endloop + endfacet + facet normal 0.0102959 0.00026631 -0.999947 + outer loop + vertex 901.57 314.974 0.0662778 + vertex 895.989 324.887 0.011451 + vertex 901.346 324.278 0.0664482 + endloop + endfacet + facet normal 0.0103976 0.000705983 -0.999946 + outer loop + vertex 901.346 324.278 0.0664482 + vertex 895.389 334.151 0.0114748 + vertex 900.724 333.666 0.0666074 + endloop + endfacet + facet normal 0.0103887 0.00106387 -0.999945 + outer loop + vertex 900.724 333.666 0.0666074 + vertex 894.469 343.449 0.0120331 + vertex 899.76 343.081 0.0666081 + endloop + endfacet + facet normal 0.010657 0.00141655 -0.999942 + outer loop + vertex 899.76 343.081 0.0666081 + vertex 893.279 352.759 0.0112427 + vertex 898.502 352.494 0.0665305 + endloop + endfacet + facet normal 0.0104032 0.00153753 -0.999945 + outer loop + vertex 898.502 352.494 0.0665305 + vertex 891.851 362.069 0.0120654 + vertex 896.99 361.903 0.0652748 + endloop + endfacet + facet normal 0.010362 0.00177108 -0.999945 + outer loop + vertex 896.99 361.903 0.0652748 + vertex 890.223 371.377 0.0119329 + vertex 895.262 371.307 0.0640199 + endloop + endfacet + facet normal 0.0102893 0.00188653 -0.999945 + outer loop + vertex 895.262 371.307 0.0640199 + vertex 888.424 380.662 0.0113125 + vertex 893.349 380.679 0.0620175 + endloop + endfacet + facet normal 0.0100549 0.00188551 -0.999948 + outer loop + vertex 893.349 380.679 0.0620175 + vertex 886.482 389.889 0.0103307 + vertex 891.281 389.988 0.0587739 + endloop + endfacet + facet normal 0.010376 0.00237524 -0.999943 + outer loop + vertex 891.281 389.988 0.0587739 + vertex 884.419 399.041 0.00907377 + vertex 889.085 399.212 0.0579032 + endloop + endfacet + facet normal 0.0106283 0.00264556 -0.99994 + outer loop + vertex 889.085 399.212 0.0579032 + vertex 882.258 408.11 0.00887281 + vertex 886.784 408.355 0.0576326 + endloop + endfacet + facet normal 0.0108508 0.00274486 -0.999937 + outer loop + vertex 886.784 408.355 0.0576326 + vertex 880.016 417.112 0.00823019 + vertex 884.394 417.428 0.0566049 + endloop + endfacet + facet normal 0.0112139 0.00289207 -0.999933 + outer loop + vertex 884.394 417.428 0.0566049 + vertex 877.71 426.063 0.00662554 + vertex 881.931 426.451 0.0550793 + endloop + endfacet + facet normal 0.0112773 0.00281694 -0.999932 + outer loop + vertex 881.931 426.451 0.0550793 + vertex 875.353 434.979 0.00491505 + vertex 879.408 435.443 0.0519631 + endloop + endfacet + facet normal 0.0124676 0.00381348 -0.999915 + outer loop + vertex 879.408 435.443 0.0519631 + vertex 872.954 443.87 0.00361685 + vertex 876.843 444.409 0.0541719 + endloop + endfacet + facet normal 0.0124821 0.00370909 -0.999915 + outer loop + vertex 872.954 443.87 0.00361685 + vertex 870.529 452.72 0.00617226 + vertex 876.843 444.409 0.0541719 + endloop + endfacet + facet normal 0.00353224 0.00168558 -0.999992 + outer loop + vertex 870.529 452.72 0.00617226 + vertex 864.339 460.726 -0.00219604 + vertex 868.095 461.505 0.0123865 + endloop + endfacet + facet normal 0.00351807 0.00140049 -0.999993 + outer loop + vertex 868.095 461.505 0.0123865 + vertex 862.067 469.394 0.00222427 + vertex 865.684 470.226 0.0161161 + endloop + endfacet + facet normal 0.00278384 0.00032478 -0.999996 + outer loop + vertex 865.684 470.226 0.0161161 + vertex 859.987 478.13 0.00282391 + vertex 863.44 479.044 0.0127336 + endloop + endfacet + facet normal 0.00412298 0.00100255 -0.999991 + outer loop + vertex 863.44 479.044 0.0127336 + vertex 858.583 487.309 0.000992115 + vertex 861.845 488.371 0.0155097 + endloop + endfacet + facet normal 0.0405909 0.0114686 -0.99911 + outer loop + vertex 872.127 471.668 0.188517 + vertex 866.602 479.867 0.0581461 + vertex 869.419 480.676 0.181878 + endloop + endfacet + facet normal 0.0379305 0.0101155 -0.999229 + outer loop + vertex 874.966 462.857 0.207094 + vertex 869.056 470.938 0.0645225 + vertex 872.127 471.668 0.188517 + endloop + endfacet + facet normal 0.039671 0.0121038 -0.999139 + outer loop + vertex 877.781 454 0.211553 + vertex 871.657 462.162 0.0672775 + vertex 874.966 462.857 0.207094 + endloop + endfacet + facet normal 0.0398711 0.013082 -0.999119 + outer loop + vertex 880.564 445.038 0.205286 + vertex 874.255 453.327 0.0620335 + vertex 877.781 454 0.211553 + endloop + endfacet + facet normal 0.0751348 0.0236226 -0.996894 + outer loop + vertex 883.323 436.007 0.199188 + vertex 880.564 445.038 0.205286 + vertex 887.082 436.897 0.50356 + endloop + endfacet + facet normal 0.0748931 0.0246409 -0.996887 + outer loop + vertex 890.031 427.765 0.499443 + vertex 883.323 436.007 0.199188 + vertex 887.082 436.897 0.50356 + endloop + endfacet + facet normal 0.0706767 0.0222477 -0.997251 + outer loop + vertex 892.924 418.575 0.499466 + vertex 886.042 426.937 0.198257 + vertex 890.031 427.765 0.499443 + endloop + endfacet + facet normal 0.0671229 0.0203951 -0.997536 + outer loop + vertex 895.729 409.334 0.499276 + vertex 888.7 417.832 0.199999 + vertex 892.924 418.575 0.499466 + endloop + endfacet + facet normal 0.0640912 0.0187198 -0.997768 + outer loop + vertex 898.42 400.047 0.497889 + vertex 891.274 408.682 0.200873 + vertex 895.729 409.334 0.499276 + endloop + endfacet + facet normal 0.0613069 0.017016 -0.997974 + outer loop + vertex 900.986 390.673 0.49564 + vertex 893.75 399.469 0.201107 + vertex 898.42 400.047 0.497889 + endloop + endfacet + facet normal 0.0586909 0.0151371 -0.998161 + outer loop + vertex 903.406 381.18 0.493992 + vertex 896.11 390.168 0.201294 + vertex 900.986 390.673 0.49564 + endloop + endfacet + facet normal 0.0563463 0.0134167 -0.998321 + outer loop + vertex 905.645 371.596 0.49155 + vertex 898.333 380.773 0.202206 + vertex 903.406 381.18 0.493992 + endloop + endfacet + facet normal 0.0540153 0.0115265 -0.998474 + outer loop + vertex 907.664 361.971 0.489691 + vertex 900.389 371.304 0.203863 + vertex 905.645 371.596 0.49155 + endloop + endfacet + facet normal 0.0516329 0.00911673 -0.998625 + outer loop + vertex 909.427 352.344 0.492948 + vertex 902.246 361.801 0.207975 + vertex 907.664 361.971 0.489691 + endloop + endfacet + facet normal 0.0506682 0.00733592 -0.998689 + outer loop + vertex 910.891 342.71 0.496458 + vertex 903.866 352.288 0.210373 + vertex 909.427 352.344 0.492948 + endloop + endfacet + facet normal 0.050355 0.00565391 -0.998715 + outer loop + vertex 912.009 333.042 0.498107 + vertex 905.21 342.764 0.210343 + vertex 910.891 342.71 0.496458 + endloop + endfacet + facet normal 0.0497707 0.00375865 -0.998754 + outer loop + vertex 912.725 323.348 0.497288 + vertex 906.237 333.226 0.211125 + vertex 912.009 333.042 0.498107 + endloop + endfacet + facet normal 0.048983 0.00122718 -0.998799 + outer loop + vertex 912.973 313.714 0.497597 + vertex 906.892 323.697 0.211633 + vertex 912.725 323.348 0.497288 + endloop + endfacet + facet normal 0.0488524 -0.00138828 -0.998805 + outer loop + vertex 912.691 304.219 0.497005 + vertex 907.118 314.241 0.210493 + vertex 912.973 313.714 0.497597 + endloop + endfacet + facet normal 0.0481196 -0.00442426 -0.998832 + outer loop + vertex 911.82 294.861 0.496486 + vertex 906.846 304.917 0.212356 + vertex 912.691 304.219 0.497005 + endloop + endfacet + facet normal 0.0478538 -0.00793373 -0.998823 + outer loop + vertex 910.325 285.617 0.498307 + vertex 906.031 295.73 0.212241 + vertex 911.82 294.861 0.496486 + endloop + endfacet + facet normal 0.0485794 -0.0109794 -0.998759 + outer loop + vertex 908.239 276.549 0.496514 + vertex 904.652 286.696 0.210504 + vertex 910.325 285.617 0.498307 + endloop + endfacet + facet normal 0.0478787 -0.0144827 -0.998748 + outer loop + vertex 905.618 267.795 0.497837 + vertex 902.718 277.88 0.212545 + vertex 908.239 276.549 0.496514 + endloop + endfacet + facet normal 0.0485147 -0.0178218 -0.998663 + outer loop + vertex 902.537 259.428 0.497436 + vertex 900.302 269.372 0.211413 + vertex 905.618 267.795 0.497837 + endloop + endfacet + facet normal 0.0483309 -0.0213321 -0.998604 + outer loop + vertex 898.997 251.412 0.497401 + vertex 897.438 261.241 0.21195 + vertex 902.537 259.428 0.497436 + endloop + endfacet + facet normal 0.0485487 -0.0249438 -0.998509 + outer loop + vertex 894.963 243.613 0.496059 + vertex 894.132 253.445 0.210031 + vertex 898.997 251.412 0.497401 + endloop + endfacet + facet normal 0.0481119 -0.0282547 -0.998442 + outer loop + vertex 890.402 235.912 0.494195 + vertex 890.32 245.849 0.20906 + vertex 894.963 243.613 0.496059 + endloop + endfacet + facet normal 0.0466997 -0.0316156 -0.998409 + outer loop + vertex 885.392 228.332 0.499886 + vertex 885.986 238.326 0.21122 + vertex 890.402 235.912 0.494195 + endloop + endfacet + facet normal 0.0469451 -0.0345535 -0.9983 + outer loop + vertex 880.263 221.232 0.504423 + vertex 881.292 230.974 0.215646 + vertex 885.392 228.332 0.499886 + endloop + endfacet + facet normal 0.0482085 -0.0358076 -0.998195 + outer loop + vertex 875.377 215.191 0.485188 + vertex 876.576 224.223 0.219082 + vertex 880.263 221.232 0.504423 + endloop + endfacet + facet normal 0.0486247 -0.0358622 -0.998173 + outer loop + vertex 872.082 218.525 0.204872 + vertex 876.576 224.223 0.219082 + vertex 875.377 215.191 0.485188 + endloop + endfacet + facet normal 0.0230757 -0.017531 -0.99958 + outer loop + vertex 868.678 221.492 0.0742695 + vertex 872.947 226.992 0.0763461 + vertex 872.082 218.525 0.204872 + endloop + endfacet + facet normal 0.00851245 -0.00708955 -0.999939 + outer loop + vertex 864.92 224.129 0.0235783 + vertex 869.14 229.482 0.021546 + vertex 868.678 221.492 0.0742695 + endloop + endfacet + facet normal 0.00334969 -0.00285438 -0.99999 + outer loop + vertex 860.787 226.389 0.00328112 + vertex 865.05 231.602 0.00268125 + vertex 864.92 224.129 0.0235783 + endloop + endfacet + facet normal 0.00142271 -0.00102348 -0.999998 + outer loop + vertex 856.407 228.21 -0.00481342 + vertex 860.709 233.325 -0.00392802 + vertex 860.787 226.389 0.00328112 + endloop + endfacet + facet normal 0.000278543 -0.000127544 -1 + outer loop + vertex 852.1 229.688 -0.00620177 + vertex 856.274 234.673 -0.00567486 + vertex 856.407 228.21 -0.00481342 + endloop + endfacet + facet normal -0.000220698 0.000333607 -1 + outer loop + vertex 848.044 226.14 -0.00649029 + vertex 847.803 230.743 -0.00490166 + vertex 852.1 229.688 -0.00620177 + endloop + endfacet + facet normal -0.000291385 0.000227023 -1 + outer loop + vertex 843.308 231.558 -0.00340692 + vertex 847.418 236.533 -0.003475 + vertex 847.803 230.743 -0.00490166 + endloop + endfacet + facet normal -0.000214839 0.000163335 -1 + outer loop + vertex 838.921 232.41 -0.00232532 + vertex 843.017 237.222 -0.00241921 + vertex 843.308 231.558 -0.00340692 + endloop + endfacet + facet normal -0.000157081 0.000141494 -1 + outer loop + vertex 834.882 228.733 -0.00221117 + vertex 834.492 232.848 -0.0015675 + vertex 838.921 232.41 -0.00232532 + endloop + endfacet + facet normal -0.000132344 9.99022e-05 -1 + outer loop + vertex 829.87 233.083 -0.000932414 + vertex 834.25 238.107 -0.00101009 + vertex 834.492 232.848 -0.0015675 + endloop + endfacet + facet normal -0.000103036 7.68611e-05 -1 + outer loop + vertex 825.351 233.385 -0.000443588 + vertex 829.782 238.321 -0.000520781 + vertex 829.87 233.083 -0.000932414 + endloop + endfacet + facet normal -5.99649e-05 4.42553e-05 -1 + outer loop + vertex 820.922 233.524 -0.000171844 + vertex 825.289 238.429 -0.000216667 + vertex 825.351 233.385 -0.000443588 + endloop + endfacet + facet normal -2.57694e-05 1.92367e-05 -1 + outer loop + vertex 816.534 233.655 -5.62628e-05 + vertex 820.811 238.487 -7.35154e-05 + vertex 820.922 233.524 -0.000171844 + endloop + endfacet + facet normal -9.17035e-06 6.98347e-06 -1 + outer loop + vertex 812.231 233.885 -1.51867e-05 + vertex 816.44 238.612 -2.07788e-05 + vertex 816.534 233.655 -5.62628e-05 + endloop + endfacet + facet normal -2.57737e-06 2.08133e-06 -1 + outer loop + vertex 807.953 234.151 -3.60787e-06 + vertex 812.233 238.848 -4.86369e-06 + vertex 812.231 233.885 -1.51867e-05 + endloop + endfacet + facet normal -9.3521e-07 5.84886e-07 -1 + outer loop + vertex 807.953 234.151 -3.60787e-06 + vertex 808.171 239.076 -9.31552e-07 + vertex 812.233 238.848 -4.86369e-06 + endloop + endfacet + facet normal -2.45544e-07 2.11433e-07 -1 + outer loop + vertex 804.369 239.066 9.39008e-15 + vertex 809.093 244.552 8.87132e-15 + vertex 808.171 239.076 -9.31552e-07 + endloop + endfacet + facet normal -5.4707e-07 5.27308e-07 -1 + outer loop + vertex 798.589 229.304 -5.1098e-07 + vertex 803.571 234.129 -6.91618e-07 + vertex 803.365 229.71 -2.90931e-06 + endloop + endfacet + facet normal -5.4383e-07 4.89247e-07 -1 + outer loop + vertex 798.589 229.304 -5.1098e-07 + vertex 803.365 229.71 -2.90931e-06 + vertex 797.628 224.631 -2.27459e-06 + endloop + endfacet + facet normal -1.16856e-07 1.22028e-07 -1 + outer loop + vertex 783.798 215.375 -3.98937e-07 + vertex 787.3 221.998 9.62153e-15 + vertex 790.848 220.565 -5.89566e-07 + endloop + endfacet + facet normal -3.97138e-07 5.02828e-07 -1 + outer loop + vertex 783.798 215.375 -3.98937e-07 + vertex 790.848 220.565 -5.89566e-07 + vertex 787.774 215.083 -2.12514e-06 + endloop + endfacet + facet normal -3.99106e-07 4.76072e-07 -1 + outer loop + vertex 780.367 209.151 -1.99251e-06 + vertex 783.798 215.375 -3.98937e-07 + vertex 787.774 215.083 -2.12514e-06 + endloop + endfacet + facet normal -1.59376e-06 1.96804e-06 -1 + outer loop + vertex 780.367 209.151 -1.99251e-06 + vertex 787.774 215.083 -2.12514e-06 + vertex 784.535 209.028 -8.87879e-06 + endloop + endfacet + facet normal -1.59284e-06 1.99896e-06 -1 + outer loop + vertex 776.534 202.645 -8.89437e-06 + vertex 780.367 209.151 -1.99251e-06 + vertex 784.535 209.028 -8.87879e-06 + endloop + endfacet + facet normal -5.69851e-06 7.14514e-06 -1 + outer loop + vertex 776.534 202.645 -8.89437e-06 + vertex 784.535 209.028 -8.87879e-06 + vertex 780.725 202.397 -3.45484e-05 + endloop + endfacet + facet normal -5.68083e-06 7.44375e-06 -1 + outer loop + vertex 772.3 196.008 -3.42444e-05 + vertex 776.534 202.645 -8.89437e-06 + vertex 780.725 202.397 -3.45484e-05 + endloop + endfacet + facet normal -1.56471e-05 2.05863e-05 -1 + outer loop + vertex 772.3 196.008 -3.42444e-05 + vertex 780.725 202.397 -3.45484e-05 + vertex 776.538 195.647 -0.00010798 + endloop + endfacet + facet normal -1.55315e-05 2.1945e-05 -1 + outer loop + vertex 767.748 189.433 -0.00010784 + vertex 772.3 196.008 -3.42444e-05 + vertex 776.538 195.647 -0.00010798 + endloop + endfacet + facet normal -3.54859e-05 5.01683e-05 -1 + outer loop + vertex 767.748 189.433 -0.00010784 + vertex 776.538 195.647 -0.00010798 + vertex 772.014 188.987 -0.000281573 + endloop + endfacet + facet normal -3.51601e-05 5.32827e-05 -1 + outer loop + vertex 762.88 182.953 -0.000281908 + vertex 767.748 189.433 -0.00010784 + vertex 772.014 188.987 -0.000281573 + endloop + endfacet + facet normal -6.55525e-05 9.92923e-05 -1 + outer loop + vertex 762.88 182.953 -0.000281908 + vertex 772.014 188.987 -0.000281573 + vertex 767.101 182.416 -0.000611942 + endloop + endfacet + facet normal -6.49289e-05 0.000104192 -1 + outer loop + vertex 757.676 176.537 -0.000612583 + vertex 762.88 182.953 -0.000281908 + vertex 767.101 182.416 -0.000611942 + endloop + endfacet + facet normal -9.64647e-05 0.000154745 -1 + outer loop + vertex 757.676 176.537 -0.000612583 + vertex 767.101 182.416 -0.000611942 + vertex 761.78 175.888 -0.00110891 + endloop + endfacet + facet normal -9.54869e-05 0.000160929 -1 + outer loop + vertex 752.145 170.168 -0.00110937 + vertex 757.676 176.537 -0.000612583 + vertex 761.78 175.888 -0.00110891 + endloop + endfacet + facet normal -0.0001163 0.00019599 -1 + outer loop + vertex 752.145 170.168 -0.00110937 + vertex 761.78 175.888 -0.00110891 + vertex 756.094 169.39 -0.00172108 + endloop + endfacet + facet normal -0.000114968 0.000202758 -1 + outer loop + vertex 746.299 163.844 -0.00171955 + vertex 752.145 170.168 -0.00110937 + vertex 756.094 169.39 -0.00172108 + endloop + endfacet + facet normal -0.000135205 0.000238498 -1 + outer loop + vertex 746.299 163.844 -0.00171955 + vertex 756.094 169.39 -0.00172108 + vertex 750.098 162.916 -0.00245439 + endloop + endfacet + facet normal -0.000133228 0.000246597 -1 + outer loop + vertex 740.143 157.54 -0.00245397 + vertex 746.299 163.844 -0.00171955 + vertex 750.098 162.916 -0.00245439 + endloop + endfacet + facet normal -0.000193792 0.000358733 -1 + outer loop + vertex 740.143 157.54 -0.00245397 + vertex 750.098 162.916 -0.00245439 + vertex 743.83 156.424 -0.00356871 + endloop + endfacet + facet normal -0.000190663 0.000369068 -1 + outer loop + vertex 733.715 151.206 -0.00356595 + vertex 740.143 157.54 -0.00245397 + vertex 743.83 156.424 -0.00356871 + endloop + endfacet + facet normal -0.000314732 0.000609572 -1 + outer loop + vertex 733.715 151.206 -0.00356595 + vertex 743.83 156.424 -0.00356871 + vertex 737.296 149.848 -0.00552084 + endloop + endfacet + facet normal -0.000309458 0.000623477 -1 + outer loop + vertex 727.044 144.791 -0.0055014 + vertex 733.715 151.206 -0.00356595 + vertex 737.296 149.848 -0.00552084 + endloop + endfacet + facet normal -0.000353677 0.000713116 -1 + outer loop + vertex 727.044 144.791 -0.0055014 + vertex 737.296 149.848 -0.00552084 + vertex 730.509 143.136 -0.00790684 + endloop + endfacet + facet normal -0.000347808 0.00072541 -1 + outer loop + vertex 720.149 138.245 -0.00785114 + vertex 727.044 144.791 -0.0055014 + vertex 730.509 143.136 -0.00790684 + endloop + endfacet + facet normal -1.95914e-05 3.01147e-05 -1 + outer loop + vertex 720.149 138.245 -0.00785114 + vertex 730.509 143.136 -0.00790684 + vertex 723.446 136.247 -0.00797592 + endloop + endfacet + facet normal -2.50151e-05 2.11655e-05 -1 + outer loop + vertex 712.99 131.522 -0.00781437 + vertex 720.149 138.245 -0.00785114 + vertex 723.446 136.247 -0.00797592 + endloop + endfacet + facet normal 0.000891641 -0.0020072 -0.999998 + outer loop + vertex 712.99 131.522 -0.00781437 + vertex 723.446 136.247 -0.00797592 + vertex 716.047 129.15 -0.000327041 + endloop + endfacet + facet normal 0.000852201 -0.00205804 -0.999998 + outer loop + vertex 705.465 124.57 8.06235e-05 + vertex 712.99 131.522 -0.00781437 + vertex 716.047 129.15 -0.000327041 + endloop + endfacet + facet normal 0.00221953 -0.00521726 -0.999984 + outer loop + vertex 705.465 124.57 8.06235e-05 + vertex 716.047 129.15 -0.000327041 + vertex 708.198 121.819 0.0204988 + endloop + endfacet + facet normal 0.002146 -0.00529029 -0.999984 + outer loop + vertex 697.452 117.362 0.0210174 + vertex 705.465 124.57 8.06235e-05 + vertex 708.198 121.819 0.0204988 + endloop + endfacet + facet normal 0.00392496 -0.00957931 -0.999946 + outer loop + vertex 697.452 117.362 0.0210174 + vertex 708.198 121.819 0.0204988 + vertex 699.759 114.244 0.0599441 + endloop + endfacet + facet normal 0.00385463 -0.00963136 -0.999946 + outer loop + vertex 688.854 109.908 0.0596692 + vertex 697.452 117.362 0.0210174 + vertex 699.759 114.244 0.0599441 + endloop + endfacet + facet normal 0.00692076 -0.017343 -0.999826 + outer loop + vertex 688.854 109.908 0.0596692 + vertex 699.759 114.244 0.0599441 + vertex 690.684 106.454 0.132237 + endloop + endfacet + facet normal 0.00679817 -0.0174079 -0.999825 + outer loop + vertex 679.673 102.256 0.130465 + vertex 688.854 109.908 0.0596692 + vertex 690.684 106.454 0.132237 + endloop + endfacet + facet normal 0.0132044 -0.0342104 -0.999327 + outer loop + vertex 679.673 102.256 0.130465 + vertex 690.684 106.454 0.132237 + vertex 681.131 98.5196 0.277642 + endloop + endfacet + facet normal 0.012891 -0.0343327 -0.999327 + outer loop + vertex 670.071 94.4664 0.274219 + vertex 679.673 102.256 0.130465 + vertex 681.131 98.5196 0.277642 + endloop + endfacet + facet normal 0.024804 -0.0668421 -0.997455 + outer loop + vertex 670.071 94.4664 0.274219 + vertex 681.131 98.5196 0.277642 + vertex 671.445 90.5092 0.573569 + endloop + endfacet + facet normal 0.0126649 -0.0340542 -0.99934 + outer loop + vertex 668.667 98.2219 0.128457 + vertex 679.673 102.256 0.130465 + vertex 670.071 94.4664 0.274219 + endloop + endfacet + facet normal 0.0122075 -0.0342252 -0.99934 + outer loop + vertex 658.981 90.5363 0.273348 + vertex 668.667 98.2219 0.128457 + vertex 670.071 94.4664 0.274219 + endloop + endfacet + facet normal 0.0237303 -0.0667399 -0.997488 + outer loop + vertex 658.981 90.5363 0.273348 + vertex 670.071 94.4664 0.274219 + vertex 660.343 86.5795 0.570491 + endloop + endfacet + facet normal 0.0122668 -0.0342998 -0.999336 + outer loop + vertex 657.598 94.2916 0.127485 + vertex 668.667 98.2219 0.128457 + vertex 658.981 90.5363 0.273348 + endloop + endfacet + facet normal 0.0116391 -0.0345309 -0.999336 + outer loop + vertex 647.674 86.6193 0.277013 + vertex 657.598 94.2916 0.127485 + vertex 658.981 90.5363 0.273348 + endloop + endfacet + facet normal 0.0226367 -0.0662735 -0.997545 + outer loop + vertex 647.674 86.6193 0.277013 + vertex 658.981 90.5363 0.273348 + vertex 649.095 82.7035 0.569414 + endloop + endfacet + facet normal 0.0118499 -0.0348034 -0.999324 + outer loop + vertex 646.27 90.3488 0.130469 + vertex 657.598 94.2916 0.127485 + vertex 647.674 86.6193 0.277013 + endloop + endfacet + facet normal 0.0112365 -0.0350344 -0.999323 + outer loop + vertex 636.11 82.6913 0.284691 + vertex 646.27 90.3488 0.130469 + vertex 647.674 86.6193 0.277013 + endloop + endfacet + facet normal 0.022258 -0.067479 -0.997472 + outer loop + vertex 636.11 82.6913 0.284691 + vertex 647.674 86.6193 0.277013 + vertex 637.599 78.8231 0.579611 + endloop + endfacet + facet normal 0.0112926 -0.0351087 -0.99932 + outer loop + vertex 634.664 86.3899 0.138407 + vertex 646.27 90.3488 0.130469 + vertex 636.11 82.6913 0.284691 + endloop + endfacet + facet normal 0.0108777 -0.0352709 -0.999319 + outer loop + vertex 624.871 79.0566 0.290644 + vertex 634.664 86.3899 0.138407 + vertex 636.11 82.6913 0.284691 + endloop + endfacet + facet normal 0.0212984 -0.0674891 -0.997493 + outer loop + vertex 624.871 79.0566 0.290644 + vertex 636.11 82.6913 0.284691 + vertex 626.326 75.1789 0.584062 + endloop + endfacet + facet normal 0.00552748 -0.018209 -0.999819 + outer loop + vertex 634.664 86.3899 0.138407 + vertex 644.584 93.8361 0.057637 + vertex 646.27 90.3488 0.130469 + endloop + endfacet + facet normal 0.00605887 -0.0179522 -0.99982 + outer loop + vertex 644.584 93.8361 0.057637 + vertex 655.908 97.7877 0.0553113 + vertex 646.27 90.3488 0.130469 + endloop + endfacet + facet normal 0.00328528 -0.0100036 -0.999945 + outer loop + vertex 644.584 93.8361 0.057637 + vertex 653.813 100.981 0.0164806 + vertex 655.908 97.7877 0.0553113 + endloop + endfacet + facet normal 0.00360845 -0.00979157 -0.999946 + outer loop + vertex 653.813 100.981 0.0164806 + vertex 664.791 104.886 0.0178536 + vertex 655.908 97.7877 0.0553113 + endloop + endfacet + facet normal 0.00357644 -0.00975152 -0.999946 + outer loop + vertex 655.908 97.7877 0.0553113 + vertex 664.791 104.886 0.0178536 + vertex 666.939 101.711 0.0565048 + endloop + endfacet + facet normal 0.00635656 -0.0175683 -0.999825 + outer loop + vertex 655.908 97.7877 0.0553113 + vertex 666.939 101.711 0.0565048 + vertex 657.598 94.2916 0.127485 + endloop + endfacet + facet normal 0.00373353 -0.00964528 -0.999947 + outer loop + vertex 664.791 104.886 0.0178536 + vertex 675.681 108.88 0.0199952 + vertex 666.939 101.711 0.0565048 + endloop + endfacet + facet normal 0.00366501 -0.00956172 -0.999948 + outer loop + vertex 666.939 101.711 0.0565048 + vertex 675.681 108.88 0.0199952 + vertex 677.897 105.729 0.0582448 + endloop + endfacet + facet normal 0.00653323 -0.0173836 -0.999828 + outer loop + vertex 666.939 101.711 0.0565048 + vertex 677.897 105.729 0.0582448 + vertex 668.667 98.2219 0.128457 + endloop + endfacet + facet normal 0.00372852 -0.00951705 -0.999948 + outer loop + vertex 675.681 108.88 0.0199952 + vertex 686.588 113.04 0.0210654 + vertex 677.897 105.729 0.0582448 + endloop + endfacet + facet normal 0.0037851 -0.00958431 -0.999947 + outer loop + vertex 677.897 105.729 0.0582448 + vertex 686.588 113.04 0.0210654 + vertex 688.854 109.908 0.0596692 + endloop + endfacet + facet normal 0.00212732 -0.00531952 -0.999984 + outer loop + vertex 675.681 108.88 0.0199952 + vertex 683.946 115.826 0.000626263 + vertex 686.588 113.04 0.0210654 + endloop + endfacet + facet normal 0.00211747 -0.00532886 -0.999984 + outer loop + vertex 683.946 115.826 0.000626263 + vertex 694.76 120.128 0.000599471 + vertex 686.588 113.04 0.0210654 + endloop + endfacet + facet normal 0.00211326 -0.005324 -0.999984 + outer loop + vertex 686.588 113.04 0.0210654 + vertex 694.76 120.128 0.000599471 + vertex 697.452 117.362 0.0210174 + endloop + endfacet + facet normal 0.000829735 -0.00209191 -0.999997 + outer loop + vertex 683.946 115.826 0.000626263 + vertex 691.79 122.535 -0.00689925 + vertex 694.76 120.128 0.000599471 + endloop + endfacet + facet normal 0.000825511 -0.00209713 -0.999997 + outer loop + vertex 691.79 122.535 -0.00689925 + vertex 702.449 126.958 -0.00737613 + vertex 694.76 120.128 0.000599471 + endloop + endfacet + facet normal 0.00081823 -0.00208893 -0.999997 + outer loop + vertex 694.76 120.128 0.000599471 + vertex 702.449 126.958 -0.00737613 + vertex 705.465 124.57 8.06235e-05 + endloop + endfacet + facet normal -2.43095e-05 -4.92297e-05 -1 + outer loop + vertex 691.79 122.535 -0.00689925 + vertex 699.25 128.999 -0.00739885 + vertex 702.449 126.958 -0.00737613 + endloop + endfacet + facet normal -1.66374e-05 -3.72062e-05 -1 + outer loop + vertex 699.25 128.999 -0.00739885 + vertex 709.743 133.543 -0.00774247 + vertex 702.449 126.958 -0.00737613 + endloop + endfacet + facet normal -3.36052e-05 -1.84112e-05 -1 + outer loop + vertex 702.449 126.958 -0.00737613 + vertex 709.743 133.543 -0.00774247 + vertex 712.99 131.522 -0.00781437 + endloop + endfacet + facet normal -0.000347998 0.000727972 -1 + outer loop + vertex 699.25 128.999 -0.00739885 + vertex 706.375 135.24 -0.00533496 + vertex 709.743 133.543 -0.00774247 + endloop + endfacet + facet normal -0.000344519 0.000734873 -1 + outer loop + vertex 706.375 135.24 -0.00533496 + vertex 716.735 139.924 -0.00546217 + vertex 709.743 133.543 -0.00774247 + endloop + endfacet + facet normal -0.000340645 0.000730627 -1 + outer loop + vertex 709.743 133.543 -0.00774247 + vertex 716.735 139.924 -0.00546217 + vertex 720.149 138.245 -0.00785114 + endloop + endfacet + facet normal -0.000299658 0.000635646 -1 + outer loop + vertex 706.375 135.24 -0.00533496 + vertex 713.251 141.327 -0.00352603 + vertex 716.735 139.924 -0.00546217 + endloop + endfacet + facet normal -0.000301276 0.00063163 -1 + outer loop + vertex 713.251 141.327 -0.00352603 + vertex 723.511 146.172 -0.00355685 + vertex 716.735 139.924 -0.00546217 + endloop + endfacet + facet normal -0.00030278 0.000633262 -1 + outer loop + vertex 716.735 139.924 -0.00546217 + vertex 723.511 146.172 -0.00355685 + vertex 727.044 144.791 -0.0055014 + endloop + endfacet + facet normal -0.000185585 0.000386639 -1 + outer loop + vertex 713.251 141.327 -0.00352603 + vertex 719.929 147.338 -0.00244124 + vertex 723.511 146.172 -0.00355685 + endloop + endfacet + facet normal -0.000188068 0.000379011 -1 + outer loop + vertex 719.929 147.338 -0.00244124 + vertex 730.08 152.348 -0.00245175 + vertex 723.511 146.172 -0.00355685 + endloop + endfacet + facet normal -0.00018765 0.000378566 -1 + outer loop + vertex 723.511 146.172 -0.00355685 + vertex 730.08 152.348 -0.00245175 + vertex 733.715 151.206 -0.00356595 + endloop + endfacet + facet normal -0.000129157 0.000259631 -1 + outer loop + vertex 719.929 147.338 -0.00244124 + vertex 726.383 153.329 -0.00171936 + vertex 730.08 152.348 -0.00245175 + endloop + endfacet + facet normal -0.000130825 0.000253348 -1 + outer loop + vertex 726.383 153.329 -0.00171936 + vertex 736.396 158.495 -0.00172055 + vertex 730.08 152.348 -0.00245175 + endloop + endfacet + facet normal -0.000131076 0.000253606 -1 + outer loop + vertex 730.08 152.348 -0.00245175 + vertex 736.396 158.495 -0.00172055 + vertex 740.143 157.54 -0.00245397 + endloop + endfacet + facet normal -0.000111824 0.000216519 -1 + outer loop + vertex 726.383 153.329 -0.00171936 + vertex 732.552 159.332 -0.00110945 + vertex 736.396 158.495 -0.00172055 + endloop + endfacet + facet normal -0.000113273 0.000209867 -1 + outer loop + vertex 732.552 159.332 -0.00110945 + vertex 742.403 164.652 -0.00110884 + vertex 736.396 158.495 -0.00172055 + endloop + endfacet + facet normal -0.000113227 0.000209822 -1 + outer loop + vertex 736.396 158.495 -0.00172055 + vertex 742.403 164.652 -0.00110884 + vertex 746.299 163.844 -0.00171955 + endloop + endfacet + facet normal -9.30648e-05 0.000172447 -1 + outer loop + vertex 732.552 159.332 -0.00110945 + vertex 738.411 165.369 -0.000613762 + vertex 742.403 164.652 -0.00110884 + endloop + endfacet + facet normal -9.40771e-05 0.000166807 -1 + outer loop + vertex 738.411 165.369 -0.000613762 + vertex 748.102 170.85 -0.000611067 + vertex 742.403 164.652 -0.00110884 + endloop + endfacet + facet normal -9.49626e-05 0.000167621 -1 + outer loop + vertex 742.403 164.652 -0.00110884 + vertex 748.102 170.85 -0.000611067 + vertex 752.145 170.168 -0.00110937 + endloop + endfacet + facet normal -6.3671e-05 0.000113053 -1 + outer loop + vertex 738.411 165.369 -0.000613762 + vertex 743.995 171.455 -0.000281148 + vertex 748.102 170.85 -0.000611067 + endloop + endfacet + facet normal -6.43565e-05 0.000108402 -1 + outer loop + vertex 743.995 171.455 -0.000281148 + vertex 753.514 177.107 -0.000281166 + vertex 748.102 170.85 -0.000611067 + endloop + endfacet + facet normal -6.47414e-05 0.000108735 -1 + outer loop + vertex 748.102 170.85 -0.000611067 + vertex 753.514 177.107 -0.000281166 + vertex 757.676 176.537 -0.000612583 + endloop + endfacet + facet normal -3.46435e-05 5.83518e-05 -1 + outer loop + vertex 743.995 171.455 -0.000281148 + vertex 749.35 177.61 -0.000107541 + vertex 753.514 177.107 -0.000281166 + endloop + endfacet + facet normal -3.49384e-05 5.59114e-05 -1 + outer loop + vertex 749.35 177.61 -0.000107541 + vertex 758.66 183.425 -0.000107739 + vertex 753.514 177.107 -0.000281166 + endloop + endfacet + facet normal -3.50278e-05 5.59843e-05 -1 + outer loop + vertex 753.514 177.107 -0.000281166 + vertex 758.66 183.425 -0.000107739 + vertex 762.88 182.953 -0.000281908 + endloop + endfacet + facet normal -1.53814e-05 2.45957e-05 -1 + outer loop + vertex 749.35 177.61 -0.000107541 + vertex 754.498 183.836 -3.35861e-05 + vertex 758.66 183.425 -0.000107739 + endloop + endfacet + facet normal -1.54987e-05 2.34095e-05 -1 + outer loop + vertex 754.498 183.836 -3.35861e-05 + vertex 763.539 189.815 -3.37483e-05 + vertex 758.66 183.425 -0.000107739 + endloop + endfacet + facet normal -1.54774e-05 2.33932e-05 -1 + outer loop + vertex 758.66 183.425 -0.000107739 + vertex 763.539 189.815 -3.37483e-05 + vertex 767.748 189.433 -0.00010784 + endloop + endfacet + facet normal -5.33363e-06 8.03819e-06 -1 + outer loop + vertex 754.498 183.836 -3.35861e-05 + vertex 759.391 190.146 -8.96823e-06 + vertex 763.539 189.815 -3.37483e-05 + endloop + endfacet + facet normal -5.36601e-06 7.63159e-06 -1 + outer loop + vertex 759.391 190.146 -8.96823e-06 + vertex 768.116 196.295 -8.85605e-06 + vertex 763.539 189.815 -3.37483e-05 + endloop + endfacet + facet normal -5.53596e-06 7.75163e-06 -1 + outer loop + vertex 763.539 189.815 -3.37483e-05 + vertex 768.116 196.295 -8.85605e-06 + vertex 772.3 196.008 -3.42444e-05 + endloop + endfacet + facet normal -1.53952e-06 2.20253e-06 -1 + outer loop + vertex 759.391 190.146 -8.96823e-06 + vertex 763.979 196.542 -1.9423e-06 + vertex 768.116 196.295 -8.85605e-06 + endloop + endfacet + facet normal -1.54833e-06 2.05518e-06 -1 + outer loop + vertex 763.979 196.542 -1.9423e-06 + vertex 772.346 202.813 -2.00971e-06 + vertex 768.116 196.295 -8.85605e-06 + endloop + endfacet + facet normal -1.56092e-06 2.06334e-06 -1 + outer loop + vertex 768.116 196.295 -8.85605e-06 + vertex 772.346 202.813 -2.00971e-06 + vertex 776.534 202.645 -8.89437e-06 + endloop + endfacet + facet normal -3.86573e-07 5.05051e-07 -1 + outer loop + vertex 763.979 196.542 -1.9423e-06 + vertex 768.329 203.016 -3.54231e-07 + vertex 772.346 202.813 -2.00971e-06 + endloop + endfacet + facet normal -3.87415e-07 4.88424e-07 -1 + outer loop + vertex 768.329 203.016 -3.54231e-07 + vertex 776.227 209.238 -3.7522e-07 + vertex 772.346 202.813 -2.00971e-06 + endloop + endfacet + facet normal -3.8055e-07 4.84277e-07 -1 + outer loop + vertex 772.346 202.813 -2.00971e-06 + vertex 776.227 209.238 -3.7522e-07 + vertex 780.367 209.151 -1.99251e-06 + endloop + endfacet + facet normal -9.81364e-08 1.21204e-07 -1 + outer loop + vertex 768.329 203.016 -3.54231e-07 + vertex 772.648 209.436 9.62153e-15 + vertex 776.227 209.238 -3.7522e-07 + endloop + endfacet + facet normal -9.82929e-08 1.18374e-07 -1 + outer loop + vertex 772.648 209.436 9.62153e-15 + vertex 779.909 215.465 9.62153e-15 + vertex 776.227 209.238 -3.7522e-07 + endloop + endfacet + facet normal -9.98264e-08 1.19281e-07 -1 + outer loop + vertex 776.227 209.238 -3.7522e-07 + vertex 779.909 215.465 9.62153e-15 + vertex 783.798 215.375 -3.98937e-07 + endloop + endfacet + facet normal -9.13413e-08 1.16632e-07 -1 + outer loop + vertex 765.143 203.558 9.62153e-15 + vertex 772.648 209.436 9.62153e-15 + vertex 768.329 203.016 -3.54231e-07 + endloop + endfacet + facet normal -9.01511e-08 1.2363e-07 -1 + outer loop + vertex 760.049 196.864 -3.6844e-07 + vertex 765.143 203.558 9.62153e-15 + vertex 768.329 203.016 -3.54231e-07 + endloop + endfacet + facet normal -9.28497e-08 1.25683e-07 -1 + outer loop + vertex 756.831 197.418 9.62153e-15 + vertex 765.143 203.558 9.62153e-15 + vertex 760.049 196.864 -3.6844e-07 + endloop + endfacet + facet normal -9.21897e-08 1.29514e-07 -1 + outer loop + vertex 751.385 190.812 -3.53513e-07 + vertex 756.831 197.418 9.62153e-15 + vertex 760.049 196.864 -3.6844e-07 + endloop + endfacet + facet normal -3.74143e-07 5.33165e-07 -1 + outer loop + vertex 751.385 190.812 -3.53513e-07 + vertex 760.049 196.864 -3.6844e-07 + vertex 755.293 190.45 -2.00876e-06 + endloop + endfacet + facet normal -3.72258e-07 5.53532e-07 -1 + outer loop + vertex 746.317 184.529 -1.94492e-06 + vertex 751.385 190.812 -3.53513e-07 + vertex 755.293 190.45 -2.00876e-06 + endloop + endfacet + facet normal -1.55025e-06 2.33928e-06 -1 + outer loop + vertex 746.317 184.529 -1.94492e-06 + vertex 755.293 190.45 -2.00876e-06 + vertex 750.387 184.199 -9.02666e-06 + endloop + endfacet + facet normal -1.54176e-06 2.44412e-06 -1 + outer loop + vertex 741.166 178.437 -8.89052e-06 + vertex 746.317 184.529 -1.94492e-06 + vertex 750.387 184.199 -9.02666e-06 + endloop + endfacet + facet normal -5.43544e-06 8.67638e-06 -1 + outer loop + vertex 741.166 178.437 -8.89052e-06 + vertex 750.387 184.199 -9.02666e-06 + vertex 745.233 178.052 -3.43364e-05 + endloop + endfacet + facet normal -5.39928e-06 9.05811e-06 -1 + outer loop + vertex 735.819 172.461 -3.41576e-05 + vertex 741.166 178.437 -8.89052e-06 + vertex 745.233 178.052 -3.43364e-05 + endloop + endfacet + facet normal -1.5108e-05 2.54034e-05 -1 + outer loop + vertex 735.819 172.461 -3.41576e-05 + vertex 745.233 178.052 -3.43364e-05 + vertex 739.885 171.991 -0.000107531 + endloop + endfacet + facet normal -1.49831e-05 2.64831e-05 -1 + outer loop + vertex 730.307 166.57 -0.000107572 + vertex 735.819 172.461 -3.41576e-05 + vertex 739.885 171.991 -0.000107531 + endloop + endfacet + facet normal -3.4245e-05 6.05194e-05 -1 + outer loop + vertex 730.307 166.57 -0.000107572 + vertex 739.885 171.991 -0.000107531 + vertex 734.363 166.004 -0.000280728 + endloop + endfacet + facet normal -3.38796e-05 6.31375e-05 -1 + outer loop + vertex 724.619 160.744 -0.000282682 + vertex 730.307 166.57 -0.000107572 + vertex 734.363 166.004 -0.000280728 + endloop + endfacet + facet normal -6.28063e-05 0.000116728 -1 + outer loop + vertex 724.619 160.744 -0.000282682 + vertex 734.363 166.004 -0.000280728 + vertex 728.617 160.077 -0.000611727 + endloop + endfacet + facet normal -6.21842e-05 0.000120455 -1 + outer loop + vertex 718.71 154.965 -0.000611343 + vertex 724.619 160.744 -0.000282682 + vertex 728.617 160.077 -0.000611727 + endloop + endfacet + facet normal -9.24868e-05 0.000179189 -1 + outer loop + vertex 718.71 154.965 -0.000611343 + vertex 728.617 160.077 -0.000611727 + vertex 722.591 154.193 -0.00110874 + endloop + endfacet + facet normal -9.1418e-05 0.000184561 -1 + outer loop + vertex 712.544 149.234 -0.00110556 + vertex 718.71 154.965 -0.000611343 + vertex 722.591 154.193 -0.00110874 + endloop + endfacet + facet normal -0.000110431 0.00022308 -1 + outer loop + vertex 712.544 149.234 -0.00110556 + vertex 722.591 154.193 -0.00110874 + vertex 716.28 148.345 -0.0017164 + endloop + endfacet + facet normal -0.00010913 0.000228546 -1 + outer loop + vertex 706.125 143.548 -0.00170451 + vertex 712.544 149.234 -0.00110556 + vertex 716.28 148.345 -0.0017164 + endloop + endfacet + facet normal -0.000123763 0.000259523 -1 + outer loop + vertex 706.125 143.548 -0.00170451 + vertex 716.28 148.345 -0.0017164 + vertex 709.722 142.518 -0.00241705 + endloop + endfacet + facet normal -0.0001229 0.000262537 -1 + outer loop + vertex 699.463 137.879 -0.00237397 + vertex 706.125 143.548 -0.00170451 + vertex 709.722 142.518 -0.00241705 + endloop + endfacet + facet normal -0.000175335 0.000378512 -1 + outer loop + vertex 699.463 137.879 -0.00237397 + vertex 709.722 142.518 -0.00241705 + vertex 702.943 136.667 -0.0034432 + endloop + endfacet + facet normal -0.000177208 0.000373136 -1 + outer loop + vertex 692.555 132.167 -0.00328127 + vertex 699.463 137.879 -0.00237397 + vertex 702.943 136.667 -0.0034432 + endloop + endfacet + facet normal -0.0002786 0.000607223 -1 + outer loop + vertex 692.555 132.167 -0.00328127 + vertex 702.943 136.667 -0.0034432 + vertex 695.936 130.719 -0.00510229 + endloop + endfacet + facet normal -0.00028088 0.000601896 -1 + outer loop + vertex 685.37 126.331 -0.00477546 + vertex 692.555 132.167 -0.00328127 + vertex 695.936 130.719 -0.00510229 + endloop + endfacet + facet normal -0.000312213 0.000677348 -1 + outer loop + vertex 685.37 126.331 -0.00477546 + vertex 695.936 130.719 -0.00510229 + vertex 688.639 124.594 -0.0069728 + endloop + endfacet + facet normal -0.000305393 0.000690181 -1 + outer loop + vertex 677.916 120.325 -0.00664462 + vertex 685.37 126.331 -0.00477546 + vertex 688.639 124.594 -0.0069728 + endloop + endfacet + facet normal -1.92147e-05 -2.86158e-05 -1 + outer loop + vertex 677.916 120.325 -0.00664462 + vertex 688.639 124.594 -0.0069728 + vertex 681.02 118.249 -0.00664483 + endloop + endfacet + facet normal 1.79088e-05 2.68659e-05 -1 + outer loop + vertex 670.217 114.126 -0.00694906 + vertex 677.916 120.325 -0.00664462 + vertex 681.02 118.249 -0.00664483 + endloop + endfacet + facet normal 0.000762331 -0.00192358 -0.999998 + outer loop + vertex 670.217 114.126 -0.00694906 + vertex 681.02 118.249 -0.00664483 + vertex 673.091 111.685 -6.27067e-05 + endloop + endfacet + facet normal 0.00080906 -0.00186857 -0.999998 + outer loop + vertex 662.251 107.708 -0.00140186 + vertex 670.217 114.126 -0.00694906 + vertex 673.091 111.685 -6.27067e-05 + endloop + endfacet + facet normal 0.00197511 -0.00504695 -0.999985 + outer loop + vertex 662.251 107.708 -0.00140186 + vertex 673.091 111.685 -6.27067e-05 + vertex 664.791 104.886 0.0178536 + endloop + endfacet + facet normal 0.000719707 -0.00175766 -0.999998 + outer loop + vertex 659.435 110.169 -0.00775571 + vertex 670.217 114.126 -0.00694906 + vertex 662.251 107.708 -0.00140186 + endloop + endfacet + facet normal 0.000726544 -0.00174984 -0.999998 + outer loop + vertex 651.33 103.825 -0.00254341 + vertex 659.435 110.169 -0.00775571 + vertex 662.251 107.708 -0.00140186 + endloop + endfacet + facet normal 0.00189412 -0.00503441 -0.999986 + outer loop + vertex 651.33 103.825 -0.00254341 + vertex 662.251 107.708 -0.00140186 + vertex 653.813 100.981 0.0164806 + endloop + endfacet + facet normal 0.00173168 -0.00517622 -0.999985 + outer loop + vertex 642.524 97.0433 0.0173141 + vertex 651.33 103.825 -0.00254341 + vertex 653.813 100.981 0.0164806 + endloop + endfacet + facet normal 0.00185589 -0.0053375 -0.999984 + outer loop + vertex 640.096 99.9132 -0.00251053 + vertex 651.33 103.825 -0.00254341 + vertex 642.524 97.0433 0.0173141 + endloop + endfacet + facet normal 0.00173019 -0.00544384 -0.999984 + outer loop + vertex 630.924 93.0871 0.0187808 + vertex 640.096 99.9132 -0.00251053 + vertex 642.524 97.0433 0.0173141 + endloop + endfacet + facet normal 0.00365199 -0.0110787 -0.999932 + outer loop + vertex 630.924 93.0871 0.0187808 + vertex 642.524 97.0433 0.0173141 + vertex 632.967 89.873 0.0618538 + endloop + endfacet + facet normal 0.00350176 -0.0111742 -0.999931 + outer loop + vertex 621.669 86.2363 0.0629278 + vertex 630.924 93.0871 0.0187808 + vertex 632.967 89.873 0.0618538 + endloop + endfacet + facet normal 0.00322041 -0.0105036 -0.99994 + outer loop + vertex 632.967 89.873 0.0618538 + vertex 642.524 97.0433 0.0173141 + vertex 644.584 93.8361 0.057637 + endloop + endfacet + facet normal 0.00191236 -0.00568861 -0.999982 + outer loop + vertex 628.564 95.9866 -0.00222715 + vertex 640.096 99.9132 -0.00251053 + vertex 630.924 93.0871 0.0187808 + endloop + endfacet + facet normal 0.00188464 -0.00571117 -0.999982 + outer loop + vertex 619.659 89.4317 0.0184266 + vertex 628.564 95.9866 -0.00222715 + vertex 630.924 93.0871 0.0187808 + endloop + endfacet + facet normal 0.000577659 -0.0017687 -0.999998 + outer loop + vertex 628.564 95.9866 -0.00222715 + vertex 637.406 102.431 -0.00851683 + vertex 640.096 99.9132 -0.00251053 + endloop + endfacet + facet normal 0.000614266 -0.00172959 -0.999998 + outer loop + vertex 637.406 102.431 -0.00851683 + vertex 648.569 106.309 -0.00836704 + vertex 640.096 99.9132 -0.00251053 + endloop + endfacet + facet normal -0.000123534 0.000394231 -1 + outer loop + vertex 637.406 102.431 -0.00851683 + vertex 645.626 108.439 -0.0071637 + vertex 648.569 106.309 -0.00836704 + endloop + endfacet + facet normal -0.000119053 0.000400424 -1 + outer loop + vertex 645.626 108.439 -0.0071637 + vertex 656.434 112.279 -0.00691258 + vertex 648.569 106.309 -0.00836704 + endloop + endfacet + facet normal -5.69557e-05 0.000318628 -1 + outer loop + vertex 648.569 106.309 -0.00836704 + vertex 656.434 112.279 -0.00691258 + vertex 659.435 110.169 -0.00775571 + endloop + endfacet + facet normal -7.81397e-05 0.000288493 -1 + outer loop + vertex 656.434 112.279 -0.00691258 + vertex 667.163 116.218 -0.00661471 + vertex 659.435 110.169 -0.00775571 + endloop + endfacet + facet normal -0.000272184 0.000817096 -1 + outer loop + vertex 656.434 112.279 -0.00691258 + vertex 663.998 117.991 -0.00430407 + vertex 667.163 116.218 -0.00661471 + endloop + endfacet + facet normal -0.000304692 0.000759087 -1 + outer loop + vertex 663.998 117.991 -0.00430407 + vertex 674.7 122.082 -0.00445969 + vertex 667.163 116.218 -0.00661471 + endloop + endfacet + facet normal -0.00028121 0.000728907 -1 + outer loop + vertex 667.163 116.218 -0.00661471 + vertex 674.7 122.082 -0.00445969 + vertex 677.916 120.325 -0.00664462 + endloop + endfacet + facet normal -0.000239782 0.00058927 -1 + outer loop + vertex 663.998 117.991 -0.00430407 + vertex 671.424 123.571 -0.00279644 + vertex 674.7 122.082 -0.00445969 + endloop + endfacet + facet normal -0.000249844 0.000567136 -1 + outer loop + vertex 671.424 123.571 -0.00279644 + vertex 682.043 127.802 -0.00305024 + vertex 674.7 122.082 -0.00445969 + endloop + endfacet + facet normal -0.000261362 0.000581921 -1 + outer loop + vertex 674.7 122.082 -0.00445969 + vertex 682.043 127.802 -0.00305024 + vertex 685.37 126.331 -0.00477546 + endloop + endfacet + facet normal -0.000153182 0.000324506 -1 + outer loop + vertex 671.424 123.571 -0.00279644 + vertex 678.668 129.059 -0.00212559 + vertex 682.043 127.802 -0.00305024 + endloop + endfacet + facet normal -0.00015124 0.000329719 -1 + outer loop + vertex 678.668 129.059 -0.00212559 + vertex 689.125 133.401 -0.00227512 + vertex 682.043 127.802 -0.00305024 + endloop + endfacet + facet normal -0.000167352 0.000350097 -1 + outer loop + vertex 682.043 127.802 -0.00305024 + vertex 689.125 133.401 -0.00227512 + vertex 692.555 132.167 -0.00328127 + endloop + endfacet + facet normal -0.000113631 0.000239166 -1 + outer loop + vertex 678.668 129.059 -0.00212559 + vertex 685.636 134.478 -0.00162105 + vertex 689.125 133.401 -0.00227512 + endloop + endfacet + facet normal -0.000111732 0.000245318 -1 + outer loop + vertex 685.636 134.478 -0.00162105 + vertex 695.918 138.934 -0.00167696 + vertex 689.125 133.401 -0.00227512 + endloop + endfacet + facet normal -0.000120469 0.000256046 -1 + outer loop + vertex 689.125 133.401 -0.00227512 + vertex 695.918 138.934 -0.00167696 + vertex 699.463 137.879 -0.00237397 + endloop + endfacet + facet normal -0.000104136 0.000227786 -1 + outer loop + vertex 685.636 134.478 -0.00162105 + vertex 692.289 139.872 -0.00108541 + vertex 695.918 138.934 -0.00167696 + endloop + endfacet + facet normal -0.000104292 0.000227181 -1 + outer loop + vertex 692.289 139.872 -0.00108541 + vertex 702.438 144.463 -0.00110085 + vertex 695.918 138.934 -0.00167696 + endloop + endfacet + facet normal -0.000106668 0.000229983 -1 + outer loop + vertex 695.918 138.934 -0.00167696 + vertex 702.438 144.463 -0.00110085 + vertex 706.125 143.548 -0.00170451 + endloop + endfacet + facet normal -8.87943e-05 0.000192922 -1 + outer loop + vertex 692.289 139.872 -0.00108541 + vertex 698.666 145.287 -0.000606936 + vertex 702.438 144.463 -0.00110085 + endloop + endfacet + facet normal -8.96696e-05 0.000188915 -1 + outer loop + vertex 698.666 145.287 -0.000606936 + vertex 708.714 150.034 -0.00061109 + vertex 702.438 144.463 -0.00110085 + endloop + endfacet + facet normal -8.96334e-05 0.000188874 -1 + outer loop + vertex 702.438 144.463 -0.00110085 + vertex 708.714 150.034 -0.00061109 + vertex 712.544 149.234 -0.00110556 + endloop + endfacet + facet normal -6.12759e-05 0.000128818 -1 + outer loop + vertex 698.666 145.287 -0.000606936 + vertex 704.829 150.756 -0.000280061 + vertex 708.714 150.034 -0.00061109 + endloop + endfacet + facet normal -6.19512e-05 0.000125183 -1 + outer loop + vertex 704.829 150.756 -0.000280061 + vertex 714.767 155.661 -0.000281687 + vertex 708.714 150.034 -0.00061109 + endloop + endfacet + facet normal -6.15968e-05 0.000124802 -1 + outer loop + vertex 708.714 150.034 -0.00061109 + vertex 714.767 155.661 -0.000281687 + vertex 718.71 154.965 -0.000611343 + endloop + endfacet + facet normal -3.33949e-05 6.73275e-05 -1 + outer loop + vertex 704.829 150.756 -0.000280061 + vertex 710.823 156.286 -0.000107912 + vertex 714.767 155.661 -0.000281687 + endloop + endfacet + facet normal -3.36784e-05 6.55376e-05 -1 + outer loop + vertex 710.823 156.286 -0.000107912 + vertex 720.621 161.339 -0.000106727 + vertex 714.767 155.661 -0.000281687 + endloop + endfacet + facet normal -3.41918e-05 6.60669e-05 -1 + outer loop + vertex 714.767 155.661 -0.000281687 + vertex 720.621 161.339 -0.000106727 + vertex 724.619 160.744 -0.000282682 + endloop + endfacet + facet normal -1.45468e-05 2.84411e-05 -1 + outer loop + vertex 710.823 156.286 -0.000107912 + vertex 716.661 161.868 -3.40733e-05 + vertex 720.621 161.339 -0.000106727 + endloop + endfacet + facet normal -1.47092e-05 2.72251e-05 -1 + outer loop + vertex 716.661 161.868 -3.40733e-05 + vertex 726.293 167.07 -3.41294e-05 + vertex 720.621 161.339 -0.000106727 + endloop + endfacet + facet normal -1.48863e-05 2.74004e-05 -1 + outer loop + vertex 720.621 161.339 -0.000106727 + vertex 726.293 167.07 -3.41294e-05 + vertex 730.307 166.57 -0.000107572 + endloop + endfacet + facet normal -5.29086e-06 9.78586e-06 -1 + outer loop + vertex 716.661 161.868 -3.40733e-05 + vertex 722.323 167.511 -8.81415e-06 + vertex 726.293 167.07 -3.41294e-05 + endloop + endfacet + facet normal -5.33573e-06 9.38149e-06 -1 + outer loop + vertex 722.323 167.511 -8.81415e-06 + vertex 731.797 172.875 -9.04226e-06 + vertex 726.293 167.07 -3.41294e-05 + endloop + endfacet + facet normal -5.28495e-06 9.33334e-06 -1 + outer loop + vertex 726.293 167.07 -3.41294e-05 + vertex 731.797 172.875 -9.04226e-06 + vertex 735.819 172.461 -3.41576e-05 + endloop + endfacet + facet normal -1.52725e-06 2.65491e-06 -1 + outer loop + vertex 722.323 167.511 -8.81415e-06 + vertex 727.808 173.255 -1.94125e-06 + vertex 731.797 172.875 -9.04226e-06 + endloop + endfacet + facet normal -1.535e-06 2.5735e-06 -1 + outer loop + vertex 727.808 173.255 -1.94125e-06 + vertex 737.13 178.792 -1.99974e-06 + vertex 731.797 172.875 -9.04226e-06 + endloop + endfacet + facet normal -1.48531e-06 2.52872e-06 -1 + outer loop + vertex 731.797 172.875 -9.04226e-06 + vertex 737.13 178.792 -1.99974e-06 + vertex 741.166 178.437 -8.89052e-06 + endloop + endfacet + facet normal -3.59895e-07 5.95294e-07 -1 + outer loop + vertex 727.808 173.255 -1.94125e-06 + vertex 733.249 179.178 -3.72987e-07 + vertex 737.13 178.792 -1.99974e-06 + endloop + endfacet + facet normal -3.61419e-07 5.79982e-07 -1 + outer loop + vertex 733.249 179.178 -3.72987e-07 + vertex 742.403 184.895 -3.65545e-07 + vertex 737.13 178.792 -1.99974e-06 + endloop + endfacet + facet normal -3.50071e-07 5.70178e-07 -1 + outer loop + vertex 737.13 178.792 -1.99974e-06 + vertex 742.403 184.895 -3.65545e-07 + vertex 746.317 184.529 -1.94492e-06 + endloop + endfacet + facet normal -8.86143e-08 1.43185e-07 -1 + outer loop + vertex 733.249 179.178 -3.72987e-07 + vertex 738.917 185.291 9.62153e-15 + vertex 742.403 184.895 -3.65545e-07 + endloop + endfacet + facet normal -8.9442e-08 1.35884e-07 -1 + outer loop + vertex 738.917 185.291 9.62153e-15 + vertex 748.154 191.371 9.62153e-15 + vertex 742.403 184.895 -3.65545e-07 + endloop + endfacet + facet normal -8.63684e-08 1.33154e-07 -1 + outer loop + vertex 742.403 184.895 -3.65545e-07 + vertex 748.154 191.371 9.62153e-15 + vertex 751.385 190.812 -3.53513e-07 + endloop + endfacet + facet normal -9.0269e-08 1.44719e-07 -1 + outer loop + vertex 729.981 179.717 9.62153e-15 + vertex 738.917 185.291 9.62153e-15 + vertex 733.249 179.178 -3.72987e-07 + endloop + endfacet + facet normal -8.94014e-08 1.49981e-07 -1 + outer loop + vertex 723.98 173.675 -3.69784e-07 + vertex 729.981 179.717 9.62153e-15 + vertex 733.249 179.178 -3.72987e-07 + endloop + endfacet + facet normal -8.83852e-08 1.48972e-07 -1 + outer loop + vertex 720.665 174.19 9.62153e-15 + vertex 729.981 179.717 9.62153e-15 + vertex 723.98 173.675 -3.69784e-07 + endloop + endfacet + facet normal -8.75014e-08 1.54659e-07 -1 + outer loop + vertex 714.617 168.377 -3.69752e-07 + vertex 720.665 174.19 9.62153e-15 + vertex 723.98 173.675 -3.69784e-07 + endloop + endfacet + facet normal -3.56298e-07 6.29775e-07 -1 + outer loop + vertex 714.617 168.377 -3.69752e-07 + vertex 723.98 173.675 -3.69784e-07 + vertex 718.381 167.921 -1.99838e-06 + endloop + endfacet + facet normal -3.54e-07 6.48723e-07 -1 + outer loop + vertex 708.849 162.776 -1.96202e-06 + vertex 714.617 168.377 -3.69752e-07 + vertex 718.381 167.921 -1.99838e-06 + endloop + endfacet + facet normal -1.5143e-06 2.79819e-06 -1 + outer loop + vertex 708.849 162.776 -1.96202e-06 + vertex 718.381 167.921 -1.99838e-06 + vertex 712.74 162.339 -9.076e-06 + endloop + endfacet + facet normal -1.50286e-06 2.90005e-06 -1 + outer loop + vertex 703.051 157.34 -9.01122e-06 + vertex 708.849 162.776 -1.96202e-06 + vertex 712.74 162.339 -9.076e-06 + endloop + endfacet + facet normal -5.11284e-06 9.89732e-06 -1 + outer loop + vertex 703.051 157.34 -9.01122e-06 + vertex 712.74 162.339 -9.076e-06 + vertex 706.919 156.842 -3.37186e-05 + endloop + endfacet + facet normal -5.06058e-06 1.03031e-05 -1 + outer loop + vertex 697.091 151.992 -3.39478e-05 + vertex 703.051 157.34 -9.01122e-06 + vertex 706.919 156.842 -3.37186e-05 + endloop + endfacet + facet normal -1.44561e-05 2.93442e-05 -1 + outer loop + vertex 697.091 151.992 -3.39478e-05 + vertex 706.919 156.842 -3.37186e-05 + vertex 700.941 151.408 -0.000106756 + endloop + endfacet + facet normal -1.43206e-05 3.0236e-05 -1 + outer loop + vertex 691.002 146.713 -0.000106379 + vertex 697.091 151.992 -3.39478e-05 + vertex 700.941 151.408 -0.000106756 + endloop + endfacet + facet normal -3.32455e-05 7.02994e-05 -1 + outer loop + vertex 691.002 146.713 -0.000106379 + vertex 700.941 151.408 -0.000106756 + vertex 694.833 146.037 -0.000281297 + endloop + endfacet + facet normal -3.29365e-05 7.20498e-05 -1 + outer loop + vertex 684.793 141.495 -0.000277841 + vertex 691.002 146.713 -0.000106379 + vertex 694.833 146.037 -0.000281297 + endloop + endfacet + facet normal -5.91899e-05 0.000130087 -1 + outer loop + vertex 684.793 141.495 -0.000277841 + vertex 694.833 146.037 -0.000281297 + vertex 688.568 140.722 -0.000601878 + endloop + endfacet + facet normal -5.86706e-05 0.000132622 -1 + outer loop + vertex 678.392 136.313 -0.00058949 + vertex 684.793 141.495 -0.000277841 + vertex 688.568 140.722 -0.000601878 + endloop + endfacet + facet normal -8.29165e-05 0.000188591 -1 + outer loop + vertex 678.392 136.313 -0.00058949 + vertex 688.568 140.722 -0.000601878 + vertex 682.058 135.44 -0.00105815 + endloop + endfacet + facet normal -8.2709e-05 0.000189462 -1 + outer loop + vertex 671.708 131.142 -0.00101647 + vertex 678.392 136.313 -0.00058949 + vertex 682.058 135.44 -0.00105815 + endloop + endfacet + facet normal -9.03866e-05 0.000207949 -1 + outer loop + vertex 671.708 131.142 -0.00101647 + vertex 682.058 135.44 -0.00105815 + vertex 675.229 130.157 -0.00153942 + endloop + endfacet + facet normal -9.11883e-05 0.000205083 -1 + outer loop + vertex 664.715 125.967 -0.00143992 + vertex 671.708 131.142 -0.00101647 + vertex 675.229 130.157 -0.00153942 + endloop + endfacet + facet normal -8.89493e-05 0.000199464 -1 + outer loop + vertex 664.715 125.967 -0.00143992 + vertex 675.229 130.157 -0.00153942 + vertex 668.098 124.847 -0.00196435 + endloop + endfacet + facet normal -8.94671e-05 0.000197901 -1 + outer loop + vertex 657.501 120.792 -0.0018188 + vertex 664.715 125.967 -0.00143992 + vertex 668.098 124.847 -0.00196435 + endloop + endfacet + facet normal -0.000129716 0.000303077 -1 + outer loop + vertex 657.501 120.792 -0.0018188 + vertex 668.098 124.847 -0.00196435 + vertex 660.771 119.496 -0.00263564 + endloop + endfacet + facet normal -0.000124118 0.000317209 -1 + outer loop + vertex 650.145 115.587 -0.00255678 + vertex 657.501 120.792 -0.0018188 + vertex 660.771 119.496 -0.00263564 + endloop + endfacet + facet normal -0.000245291 0.000646583 -1 + outer loop + vertex 650.145 115.587 -0.00255678 + vertex 660.771 119.496 -0.00263564 + vertex 653.32 114.067 -0.00431831 + endloop + endfacet + facet normal -0.000232425 0.000673459 -1 + outer loop + vertex 642.566 110.244 -0.00439372 + vertex 650.145 115.587 -0.00255678 + vertex 653.32 114.067 -0.00431831 + endloop + endfacet + facet normal -0.000336046 0.000964912 -0.999999 + outer loop + vertex 642.566 110.244 -0.00439372 + vertex 653.32 114.067 -0.00431831 + vertex 645.626 108.439 -0.0071637 + endloop + endfacet + facet normal -0.000332382 0.000971123 -0.999999 + outer loop + vertex 634.524 104.588 -0.00721281 + vertex 642.566 110.244 -0.00439372 + vertex 645.626 108.439 -0.0071637 + endloop + endfacet + facet normal -0.000339439 0.000981158 -0.999999 + outer loop + vertex 631.52 106.415 -0.00440042 + vertex 642.566 110.244 -0.00439372 + vertex 634.524 104.588 -0.00721281 + endloop + endfacet + facet normal -0.000343804 0.000973979 -0.999999 + outer loop + vertex 623.104 100.726 -0.0070485 + vertex 631.52 106.415 -0.00440042 + vertex 634.524 104.588 -0.00721281 + endloop + endfacet + facet normal -0.000150278 0.000401783 -1 + outer loop + vertex 623.104 100.726 -0.0070485 + vertex 634.524 104.588 -0.00721281 + vertex 625.933 98.5347 -0.00835394 + endloop + endfacet + facet normal -0.000145312 0.000408193 -1 + outer loop + vertex 614.722 94.8954 -0.00821034 + vertex 623.104 100.726 -0.0070485 + vertex 625.933 98.5347 -0.00835394 + endloop + endfacet + facet normal -0.000150948 0.000402735 -1 + outer loop + vertex 625.933 98.5347 -0.00835394 + vertex 634.524 104.588 -0.00721281 + vertex 637.406 102.431 -0.00851683 + endloop + endfacet + facet normal -0.000330393 0.000954141 -0.999999 + outer loop + vertex 620.157 102.58 -0.00430571 + vertex 631.52 106.415 -0.00440042 + vertex 623.104 100.726 -0.0070485 + endloop + endfacet + facet normal -0.000328856 0.000956584 -0.999999 + outer loop + vertex 611.949 97.1317 -0.00681815 + vertex 620.157 102.58 -0.00430571 + vertex 623.104 100.726 -0.0070485 + endloop + endfacet + facet normal -0.000246155 0.000704575 -1 + outer loop + vertex 620.157 102.58 -0.00430571 + vertex 628.455 107.97 -0.00255034 + vertex 631.52 106.415 -0.00440042 + endloop + endfacet + facet normal -0.000244842 0.000707162 -1 + outer loop + vertex 628.455 107.97 -0.00255034 + vertex 639.447 111.781 -0.00254702 + vertex 631.52 106.415 -0.00440042 + endloop + endfacet + facet normal -0.000119194 0.000344708 -1 + outer loop + vertex 628.455 107.97 -0.00255034 + vertex 636.28 113.107 -0.0017123 + vertex 639.447 111.781 -0.00254702 + endloop + endfacet + facet normal -0.000122562 0.000336665 -1 + outer loop + vertex 636.28 113.107 -0.0017123 + vertex 646.925 116.898 -0.00174072 + vertex 639.447 111.781 -0.00254702 + endloop + endfacet + facet normal -0.000118662 0.000330965 -1 + outer loop + vertex 639.447 111.781 -0.00254702 + vertex 646.925 116.898 -0.00174072 + vertex 650.145 115.587 -0.00255678 + endloop + endfacet + facet normal -7.05481e-05 0.000190607 -1 + outer loop + vertex 636.28 113.107 -0.0017123 + vertex 643.648 118.057 -0.00128868 + vertex 646.925 116.898 -0.00174072 + endloop + endfacet + facet normal -7.3212e-05 0.00018307 -1 + outer loop + vertex 643.648 118.057 -0.00128868 + vertex 654.169 121.931 -0.00134962 + vertex 646.925 116.898 -0.00174072 + endloop + endfacet + facet normal -7.65457e-05 0.000187867 -1 + outer loop + vertex 646.925 116.898 -0.00174072 + vertex 654.169 121.931 -0.00134962 + vertex 657.501 120.792 -0.0018188 + endloop + endfacet + facet normal -7.24827e-05 0.000181089 -1 + outer loop + vertex 643.648 118.057 -0.00128868 + vertex 650.755 122.959 -0.000916077 + vertex 654.169 121.931 -0.00134962 + endloop + endfacet + facet normal -7.31313e-05 0.000178935 -1 + outer loop + vertex 650.755 122.959 -0.000916077 + vertex 661.248 126.974 -0.000965039 + vertex 654.169 121.931 -0.00134962 + endloop + endfacet + facet normal -8.15825e-05 0.000190799 -1 + outer loop + vertex 654.169 121.931 -0.00134962 + vertex 661.248 126.974 -0.000965039 + vertex 664.715 125.967 -0.00143992 + endloop + endfacet + facet normal -7.21039e-05 0.00017625 -1 + outer loop + vertex 650.755 122.959 -0.000916077 + vertex 657.693 127.893 -0.000546803 + vertex 661.248 126.974 -0.000965039 + endloop + endfacet + facet normal -7.22605e-05 0.000175644 -1 + outer loop + vertex 657.693 127.893 -0.000546803 + vertex 668.097 132.038 -0.000570465 + vertex 661.248 126.974 -0.000965039 + endloop + endfacet + facet normal -7.7986e-05 0.000183388 -1 + outer loop + vertex 661.248 126.974 -0.000965039 + vertex 668.097 132.038 -0.000570465 + vertex 671.708 131.142 -0.00101647 + endloop + endfacet + facet normal -5.44061e-05 0.000130835 -1 + outer loop + vertex 657.693 127.893 -0.000546803 + vertex 664.435 132.858 -0.000263951 + vertex 668.097 132.038 -0.000570465 + endloop + endfacet + facet normal -5.46633e-05 0.000129685 -1 + outer loop + vertex 664.435 132.858 -0.000263951 + vertex 674.673 137.11 -0.000272181 + vertex 668.097 132.038 -0.000570465 + endloop + endfacet + facet normal -5.69111e-05 0.0001326 -1 + outer loop + vertex 668.097 132.038 -0.000570465 + vertex 674.673 137.11 -0.000272181 + vertex 678.392 136.313 -0.00058949 + endloop + endfacet + facet normal -3.11124e-05 7.29786e-05 -1 + outer loop + vertex 664.435 132.858 -0.000263951 + vertex 670.951 137.836 -0.000103445 + vertex 674.673 137.11 -0.000272181 + endloop + endfacet + facet normal -3.13267e-05 7.18794e-05 -1 + outer loop + vertex 670.951 137.836 -0.000103445 + vertex 681.016 142.196 -0.000105303 + vertex 674.673 137.11 -0.000272181 + endloop + endfacet + facet normal -3.21462e-05 7.29015e-05 -1 + outer loop + vertex 674.673 137.11 -0.000272181 + vertex 681.016 142.196 -0.000105303 + vertex 684.793 141.495 -0.000277841 + endloop + endfacet + facet normal -1.38343e-05 3.15051e-05 -1 + outer loop + vertex 670.951 137.836 -0.000103445 + vertex 677.275 142.831 -3.35319e-05 + vertex 681.016 142.196 -0.000105303 + endloop + endfacet + facet normal -1.39555e-05 3.07913e-05 -1 + outer loop + vertex 677.275 142.831 -3.35319e-05 + vertex 687.207 147.323 -3.38188e-05 + vertex 681.016 142.196 -0.000105303 + endloop + endfacet + facet normal -1.41313e-05 3.10036e-05 -1 + outer loop + vertex 681.016 142.196 -0.000105303 + vertex 687.207 147.323 -3.38188e-05 + vertex 691.002 146.713 -0.000106379 + endloop + endfacet + facet normal -4.9985e-06 1.09877e-05 -1 + outer loop + vertex 677.275 142.831 -3.35319e-05 + vertex 683.447 147.875 -8.96261e-06 + vertex 687.207 147.323 -3.38188e-05 + endloop + endfacet + facet normal -5.04511e-06 1.06701e-05 -1 + outer loop + vertex 683.447 147.875 -8.96261e-06 + vertex 693.276 152.518 -9.0167e-06 + vertex 687.207 147.323 -3.38188e-05 + endloop + endfacet + facet normal -5.06311e-06 1.06911e-05 -1 + outer loop + vertex 687.207 147.323 -3.38188e-05 + vertex 693.276 152.518 -9.0167e-06 + vertex 697.091 151.992 -3.39478e-05 + endloop + endfacet + facet normal -1.45035e-06 3.05909e-06 -1 + outer loop + vertex 683.447 147.875 -8.96261e-06 + vertex 689.487 153.011 -2.01388e-06 + vertex 693.276 152.518 -9.0167e-06 + endloop + endfacet + facet normal -1.46255e-06 2.96531e-06 -1 + outer loop + vertex 689.487 153.011 -2.01388e-06 + vertex 699.207 157.804 -2.01434e-06 + vertex 693.276 152.518 -9.0167e-06 + endloop + endfacet + facet normal -1.46211e-06 2.96482e-06 -1 + outer loop + vertex 693.276 152.518 -9.0167e-06 + vertex 699.207 157.804 -2.01434e-06 + vertex 703.051 157.34 -9.01122e-06 + endloop + endfacet + facet normal -3.57257e-07 7.24265e-07 -1 + outer loop + vertex 689.487 153.011 -2.01388e-06 + vertex 695.503 158.292 -3.37871e-07 + vertex 699.207 157.804 -2.01434e-06 + endloop + endfacet + facet normal -3.60893e-07 6.96659e-07 -1 + outer loop + vertex 695.503 158.292 -3.37871e-07 + vertex 705.133 163.258 -3.5338e-07 + vertex 699.207 157.804 -2.01434e-06 + endloop + endfacet + facet normal -3.44641e-07 6.79e-07 -1 + outer loop + vertex 699.207 157.804 -2.01434e-06 + vertex 705.133 163.258 -3.5338e-07 + vertex 708.849 162.776 -1.96202e-06 + endloop + endfacet + facet normal -8.21568e-08 1.56182e-07 -1 + outer loop + vertex 695.503 158.292 -3.37871e-07 + vertex 701.963 163.854 9.62153e-15 + vertex 705.133 163.258 -3.5338e-07 + endloop + endfacet + facet normal -8.273e-08 1.53131e-07 -1 + outer loop + vertex 701.963 163.854 9.62153e-15 + vertex 711.606 169.063 9.62153e-15 + vertex 705.133 163.258 -3.5338e-07 + endloop + endfacet + facet normal -8.68705e-08 1.57748e-07 -1 + outer loop + vertex 705.133 163.258 -3.5338e-07 + vertex 711.606 169.063 9.62153e-15 + vertex 714.617 168.377 -3.69752e-07 + endloop + endfacet + facet normal -7.80665e-08 1.5143e-07 -1 + outer loop + vertex 692.219 158.83 9.62153e-15 + vertex 701.963 163.854 9.62153e-15 + vertex 695.503 158.292 -3.37871e-07 + endloop + endfacet + facet normal -7.62757e-08 1.62358e-07 -1 + outer loop + vertex 685.882 153.549 -3.74161e-07 + vertex 692.219 158.83 9.62153e-15 + vertex 695.503 158.292 -3.37871e-07 + endloop + endfacet + facet normal -8.5586e-08 1.73529e-07 -1 + outer loop + vertex 683.154 154.359 9.62153e-15 + vertex 692.219 158.83 9.62153e-15 + vertex 685.882 153.549 -3.74161e-07 + endloop + endfacet + facet normal -8.50492e-08 1.75335e-07 -1 + outer loop + vertex 676.162 148.96 -3.51956e-07 + vertex 683.154 154.359 9.62153e-15 + vertex 685.882 153.549 -3.74161e-07 + endloop + endfacet + facet normal -3.45253e-07 7.2657e-07 -1 + outer loop + vertex 676.162 148.96 -3.51956e-07 + vertex 685.882 153.549 -3.74161e-07 + vertex 679.719 148.398 -1.9886e-06 + endloop + endfacet + facet normal -3.4195e-07 7.47478e-07 -1 + outer loop + vertex 669.892 143.954 -1.94986e-06 + vertex 676.162 148.96 -3.51956e-07 + vertex 679.719 148.398 -1.9886e-06 + endloop + endfacet + facet normal -1.38135e-06 3.04603e-06 -1 + outer loop + vertex 669.892 143.954 -1.94986e-06 + vertex 679.719 148.398 -1.9886e-06 + vertex 673.571 143.408 -8.6963e-06 + endloop + endfacet + facet normal -1.37009e-06 3.12186e-06 -1 + outer loop + vertex 663.613 139.094 -8.52055e-06 + vertex 669.892 143.954 -1.94986e-06 + vertex 673.571 143.408 -8.6963e-06 + endloop + endfacet + facet normal -4.85037e-06 1.11555e-05 -1 + outer loop + vertex 663.613 139.094 -8.52055e-06 + vertex 673.571 143.408 -8.6963e-06 + vertex 667.264 138.494 -3.29223e-05 + endloop + endfacet + facet normal -4.8207e-06 1.1336e-05 -1 + outer loop + vertex 657.136 134.287 -3.17845e-05 + vertex 663.613 139.094 -8.52055e-06 + vertex 667.264 138.494 -3.29223e-05 + endloop + endfacet + facet normal -1.31205e-05 3.13189e-05 -1 + outer loop + vertex 657.136 134.287 -3.17845e-05 + vertex 667.264 138.494 -3.29223e-05 + vertex 660.768 133.606 -0.000100755 + endloop + endfacet + facet normal -1.29572e-05 3.21901e-05 -1 + outer loop + vertex 650.474 129.506 -9.93526e-05 + vertex 657.136 134.287 -3.17845e-05 + vertex 660.768 133.606 -0.000100755 + endloop + endfacet + facet normal -2.84409e-05 7.10656e-05 -1 + outer loop + vertex 650.474 129.506 -9.93526e-05 + vertex 660.768 133.606 -0.000100755 + vertex 654.084 128.736 -0.000256823 + endloop + endfacet + facet normal -2.8286e-05 7.17912e-05 -1 + outer loop + vertex 643.705 124.763 -0.000248429 + vertex 650.474 129.506 -9.93526e-05 + vertex 654.084 128.736 -0.000256823 + endloop + endfacet + facet normal -4.78298e-05 0.000122854 -1 + outer loop + vertex 643.705 124.763 -0.000248429 + vertex 654.084 128.736 -0.000256823 + vertex 647.258 123.899 -0.00052454 + endloop + endfacet + facet normal -4.72691e-05 0.000125159 -1 + outer loop + vertex 636.847 120.065 -0.000512294 + vertex 643.705 124.763 -0.000248429 + vertex 647.258 123.899 -0.00052454 + endloop + endfacet + facet normal -6.16233e-05 0.000164136 -1 + outer loop + vertex 636.847 120.065 -0.000512294 + vertex 647.258 123.899 -0.00052454 + vertex 640.289 119.104 -0.00088213 + endloop + endfacet + facet normal -6.06579e-05 0.000167595 -1 + outer loop + vertex 629.756 115.349 -0.000872403 + vertex 636.847 120.065 -0.000512294 + vertex 640.289 119.104 -0.00088213 + endloop + endfacet + facet normal -6.28727e-05 0.000173809 -1 + outer loop + vertex 629.756 115.349 -0.000872403 + vertex 640.289 119.104 -0.00088213 + vertex 633.058 114.283 -0.00126532 + endloop + endfacet + facet normal -6.13741e-05 0.000178451 -1 + outer loop + vertex 622.182 110.51 -0.00127128 + vertex 629.756 115.349 -0.000872403 + vertex 633.058 114.283 -0.00126532 + endloop + endfacet + facet normal -6.70447e-05 0.000194793 -1 + outer loop + vertex 622.182 110.51 -0.00127128 + vertex 633.058 114.283 -0.00126532 + vertex 625.342 109.314 -0.00171612 + endloop + endfacet + facet normal -6.56411e-05 0.000198502 -1 + outer loop + vertex 614.088 105.515 -0.00173132 + vertex 622.182 110.51 -0.00127128 + vertex 625.342 109.314 -0.00171612 + endloop + endfacet + facet normal -0.000111174 0.000333422 -1 + outer loop + vertex 614.088 105.515 -0.00173132 + vertex 625.342 109.314 -0.00171612 + vertex 617.144 104.152 -0.0025257 + endloop + endfacet + facet normal -0.000110097 0.000335838 -1 + outer loop + vertex 606.102 100.584 -0.00250835 + vertex 614.088 105.515 -0.00173132 + vertex 617.144 104.152 -0.0025257 + endloop + endfacet + facet normal -0.000118862 0.000345632 -1 + outer loop + vertex 617.144 104.152 -0.0025257 + vertex 625.342 109.314 -0.00171612 + vertex 628.455 107.97 -0.00255034 + endloop + endfacet + facet normal -6.23043e-05 0.000193094 -1 + outer loop + vertex 610.981 106.73 -0.00130318 + vertex 622.182 110.51 -0.00127128 + vertex 614.088 105.515 -0.00173132 + endloop + endfacet + facet normal -6.04116e-05 0.000197934 -1 + outer loop + vertex 603.082 101.973 -0.00176767 + vertex 610.981 106.73 -0.00130318 + vertex 614.088 105.515 -0.00173132 + endloop + endfacet + facet normal -5.80471e-05 0.000180477 -1 + outer loop + vertex 610.981 106.73 -0.00130318 + vertex 618.935 111.594 -0.000887035 + vertex 622.182 110.51 -0.00127128 + endloop + endfacet + facet normal -5.73688e-05 0.000179368 -1 + outer loop + vertex 607.799 107.836 -0.000922252 + vertex 618.935 111.594 -0.000887035 + vertex 610.981 106.73 -0.00130318 + endloop + endfacet + facet normal -5.53666e-05 0.00018513 -1 + outer loop + vertex 600.022 103.205 -0.00134909 + vertex 607.799 107.836 -0.000922252 + vertex 610.981 106.73 -0.00130318 + endloop + endfacet + facet normal -5.53399e-05 0.000173356 -1 + outer loop + vertex 607.799 107.836 -0.000922252 + vertex 615.613 112.597 -0.000529285 + vertex 618.935 111.594 -0.000887035 + endloop + endfacet + facet normal -5.68178e-05 0.00016846 -1 + outer loop + vertex 615.613 112.597 -0.000529285 + vertex 626.375 116.331 -0.000511741 + vertex 618.935 111.594 -0.000887035 + endloop + endfacet + facet normal -5.74632e-05 0.000169473 -1 + outer loop + vertex 618.935 111.594 -0.000887035 + vertex 626.375 116.331 -0.000511741 + vertex 629.756 115.349 -0.000872403 + endloop + endfacet + facet normal -4.25561e-05 0.000127354 -1 + outer loop + vertex 615.613 112.597 -0.000529285 + vertex 622.93 117.236 -0.000249922 + vertex 626.375 116.331 -0.000511741 + endloop + endfacet + facet normal -4.35443e-05 0.000123592 -1 + outer loop + vertex 622.93 117.236 -0.000249922 + vertex 633.351 120.949 -0.000244842 + vertex 626.375 116.331 -0.000511741 + endloop + endfacet + facet normal -4.47812e-05 0.000125461 -1 + outer loop + vertex 626.375 116.331 -0.000511741 + vertex 633.351 120.949 -0.000244842 + vertex 636.847 120.065 -0.000512294 + endloop + endfacet + facet normal -2.52912e-05 7.23577e-05 -1 + outer loop + vertex 622.93 117.236 -0.000249922 + vertex 629.846 121.76 -9.75112e-05 + vertex 633.351 120.949 -0.000244842 + endloop + endfacet + facet normal -2.58005e-05 7.01571e-05 -1 + outer loop + vertex 629.846 121.76 -9.75112e-05 + vertex 640.149 125.555 -9.70748e-05 + vertex 633.351 120.949 -0.000244842 + endloop + endfacet + facet normal -2.6659e-05 7.14242e-05 -1 + outer loop + vertex 633.351 120.949 -0.000244842 + vertex 640.149 125.555 -9.70748e-05 + vertex 643.705 124.763 -0.000248429 + endloop + endfacet + facet normal -1.19834e-05 3.26469e-05 -1 + outer loop + vertex 629.846 121.76 -9.75112e-05 + vertex 636.621 126.276 -3.12422e-05 + vertex 640.149 125.555 -9.70748e-05 + endloop + endfacet + facet normal -1.21818e-05 3.16764e-05 -1 + outer loop + vertex 636.621 126.276 -3.12422e-05 + vertex 646.894 130.208 -3.18373e-05 + vertex 640.149 125.555 -9.70748e-05 + endloop + endfacet + facet normal -1.25465e-05 3.2205e-05 -1 + outer loop + vertex 640.149 125.555 -9.70748e-05 + vertex 646.894 130.208 -3.18373e-05 + vertex 650.474 129.506 -9.93526e-05 + endloop + endfacet + facet normal -4.51701e-06 1.16504e-05 -1 + outer loop + vertex 636.621 126.276 -3.12422e-05 + vertex 643.341 130.85 -8.30951e-06 + vertex 646.894 130.208 -3.18373e-05 + endloop + endfacet + facet normal -4.56217e-06 1.14004e-05 -1 + outer loop + vertex 643.341 130.85 -8.30951e-06 + vertex 653.531 134.909 -8.52928e-06 + vertex 646.894 130.208 -3.18373e-05 + endloop + endfacet + facet normal -4.50032e-06 1.1313e-05 -1 + outer loop + vertex 646.894 130.208 -3.18373e-05 + vertex 653.531 134.909 -8.52928e-06 + vertex 657.136 134.287 -3.17845e-05 + endloop + endfacet + facet normal -1.31508e-06 3.24771e-06 -1 + outer loop + vertex 643.341 130.85 -8.30951e-06 + vertex 649.945 135.498 -1.9006e-06 + vertex 653.531 134.909 -8.52928e-06 + endloop + endfacet + facet normal -1.32506e-06 3.1869e-06 -1 + outer loop + vertex 649.945 135.498 -1.9006e-06 + vertex 659.976 139.66 -1.92701e-06 + vertex 653.531 134.909 -8.52928e-06 + endloop + endfacet + facet normal -1.31811e-06 3.17748e-06 -1 + outer loop + vertex 653.531 134.909 -8.52928e-06 + vertex 659.976 139.66 -1.92701e-06 + vertex 663.613 139.094 -8.52055e-06 + endloop + endfacet + facet normal -3.18365e-07 7.60876e-07 -1 + outer loop + vertex 649.945 135.498 -1.9006e-06 + vertex 656.499 140.262 -3.62369e-07 + vertex 659.976 139.66 -1.92701e-06 + endloop + endfacet + facet normal -3.20948e-07 7.45955e-07 -1 + outer loop + vertex 656.499 140.262 -3.62369e-07 + vertex 666.33 144.516 -3.44388e-07 + vertex 659.976 139.66 -1.92701e-06 + endloop + endfacet + facet normal -3.31068e-07 7.59199e-07 -1 + outer loop + vertex 659.976 139.66 -1.92701e-06 + vertex 666.33 144.516 -3.44388e-07 + vertex 669.892 143.954 -1.94986e-06 + endloop + endfacet + facet normal -7.45735e-08 1.7657e-07 -1 + outer loop + vertex 656.499 140.262 -3.62369e-07 + vertex 663.267 145.172 9.62153e-15 + vertex 666.33 144.516 -3.44388e-07 + endloop + endfacet + facet normal -7.62273e-08 1.6886e-07 -1 + outer loop + vertex 663.267 145.172 9.62153e-15 + vertex 672.924 149.532 9.62153e-15 + vertex 666.33 144.516 -3.44388e-07 + endloop + endfacet + facet normal -7.83914e-08 1.71705e-07 -1 + outer loop + vertex 666.33 144.516 -3.44388e-07 + vertex 672.924 149.532 9.62153e-15 + vertex 676.162 148.96 -3.51956e-07 + endloop + endfacet + facet normal -7.92458e-08 1.8301e-07 -1 + outer loop + vertex 653.741 141.047 9.62153e-15 + vertex 663.267 145.172 9.62153e-15 + vertex 656.499 140.262 -3.62369e-07 + endloop + endfacet + facet normal -7.8198e-08 1.86691e-07 -1 + outer loop + vertex 646.571 136.141 -3.55344e-07 + vertex 653.741 141.047 9.62153e-15 + vertex 656.499 140.262 -3.62369e-07 + endloop + endfacet + facet normal -7.66931e-08 1.84492e-07 -1 + outer loop + vertex 643.948 136.976 9.62153e-15 + vertex 653.741 141.047 9.62153e-15 + vertex 646.571 136.141 -3.55344e-07 + endloop + endfacet + facet normal -7.43783e-08 1.91759e-07 -1 + outer loop + vertex 636.53 132.136 -3.76492e-07 + vertex 643.948 136.976 9.62153e-15 + vertex 646.571 136.141 -3.55344e-07 + endloop + endfacet + facet normal -2.92659e-07 7.39023e-07 -1 + outer loop + vertex 636.53 132.136 -3.76492e-07 + vertex 646.571 136.141 -3.55344e-07 + vertex 639.825 131.466 -1.83619e-06 + endloop + endfacet + facet normal -2.80751e-07 7.97572e-07 -1 + outer loop + vertex 629.73 127.599 -2.08617e-06 + vertex 636.53 132.136 -3.76492e-07 + vertex 639.825 131.466 -1.83619e-06 + endloop + endfacet + facet normal -1.21601e-06 3.23916e-06 -1 + outer loop + vertex 629.73 127.599 -2.08617e-06 + vertex 639.825 131.466 -1.83619e-06 + vertex 633.133 126.943 -8.34928e-06 + endloop + endfacet + facet normal -1.17141e-06 3.47058e-06 -1 + outer loop + vertex 622.992 123.204 -9.44451e-06 + vertex 629.73 127.599 -2.08617e-06 + vertex 633.133 126.943 -8.34928e-06 + endloop + endfacet + facet normal -4.39273e-06 1.22089e-05 -1 + outer loop + vertex 622.992 123.204 -9.44451e-06 + vertex 633.133 126.943 -8.34928e-06 + vertex 626.38 122.505 -3.2868e-05 + endloop + endfacet + facet normal -4.23649e-06 1.29657e-05 -1 + outer loop + vertex 616.105 118.845 -3.67909e-05 + vertex 622.992 123.204 -9.44451e-06 + vertex 626.38 122.505 -3.2868e-05 + endloop + endfacet + facet normal -1.17041e-05 3.39309e-05 -1 + outer loop + vertex 616.105 118.845 -3.67909e-05 + vertex 626.38 122.505 -3.2868e-05 + vertex 619.486 118.071 -0.000102633 + endloop + endfacet + facet normal -1.12383e-05 3.59656e-05 -1 + outer loop + vertex 608.87 114.394 -0.000115572 + vertex 616.105 118.845 -3.67909e-05 + vertex 619.486 118.071 -0.000102633 + endloop + endfacet + facet normal -2.55231e-05 7.72084e-05 -1 + outer loop + vertex 608.87 114.394 -0.000115572 + vertex 619.486 118.071 -0.000102633 + vertex 612.228 113.527 -0.000268207 + endloop + endfacet + facet normal -2.45791e-05 8.08645e-05 -1 + outer loop + vertex 601.238 109.819 -0.000297895 + vertex 608.87 114.394 -0.000115572 + vertex 612.228 113.527 -0.000268207 + endloop + endfacet + facet normal -4.21388e-05 0.000132915 -1 + outer loop + vertex 601.238 109.819 -0.000297895 + vertex 612.228 113.527 -0.000268207 + vertex 604.54 108.86 -0.000564465 + endloop + endfacet + facet normal -4.02528e-05 0.000139411 -1 + outer loop + vertex 593.729 105.365 -0.000616572 + vertex 601.238 109.819 -0.000297895 + vertex 604.54 108.86 -0.000564465 + endloop + endfacet + facet normal -4.11041e-05 0.00013121 -1 + outer loop + vertex 604.54 108.86 -0.000564465 + vertex 612.228 113.527 -0.000268207 + vertex 615.613 112.597 -0.000529285 + endloop + endfacet + facet normal -2.58454e-05 8.29772e-05 -1 + outer loop + vertex 597.971 110.718 -0.000138899 + vertex 608.87 114.394 -0.000115572 + vertex 601.238 109.819 -0.000297895 + endloop + endfacet + facet normal -2.43507e-05 8.84123e-05 -1 + outer loop + vertex 590.497 106.339 -0.000344058 + vertex 597.971 110.718 -0.000138899 + vertex 601.238 109.819 -0.000297895 + endloop + endfacet + facet normal -1.15292e-05 4.05299e-05 -1 + outer loop + vertex 597.971 110.718 -0.000138899 + vertex 605.595 115.203 -4.49898e-05 + vertex 608.87 114.394 -0.000115572 + endloop + endfacet + facet normal -1.34511e-05 4.37964e-05 -1 + outer loop + vertex 594.771 111.553 -5.926e-05 + vertex 605.595 115.203 -4.49898e-05 + vertex 597.971 110.718 -0.000138899 + endloop + endfacet + facet normal -1.23374e-05 4.80615e-05 -1 + outer loop + vertex 587.308 107.259 -0.000173558 + vertex 594.771 111.553 -5.926e-05 + vertex 597.971 110.718 -0.000138899 + endloop + endfacet + facet normal -4.74246e-06 1.79724e-05 -1 + outer loop + vertex 594.771 111.553 -5.926e-05 + vertex 602.387 115.959 -1.61899e-05 + vertex 605.595 115.203 -4.49898e-05 + endloop + endfacet + facet normal -5.16982e-06 1.61587e-05 -1 + outer loop + vertex 602.387 115.959 -1.61899e-05 + vertex 612.833 119.581 -1.16761e-05 + vertex 605.595 115.203 -4.49898e-05 + endloop + endfacet + facet normal -4.34677e-06 1.47978e-05 -1 + outer loop + vertex 605.595 115.203 -4.49898e-05 + vertex 612.833 119.581 -1.16761e-05 + vertex 616.105 118.845 -3.67909e-05 + endloop + endfacet + facet normal -1.36767e-06 5.19141e-06 -1 + outer loop + vertex 602.387 115.959 -1.61899e-05 + vertex 609.594 120.283 -3.60255e-06 + vertex 612.833 119.581 -1.16761e-05 + endloop + endfacet + facet normal -1.51224e-06 4.52399e-06 -1 + outer loop + vertex 609.594 120.283 -3.60255e-06 + vertex 619.708 123.895 -2.55364e-06 + vertex 612.833 119.581 -1.16761e-05 + endloop + endfacet + facet normal -1.23807e-06 4.08714e-06 -1 + outer loop + vertex 612.833 119.581 -1.16761e-05 + vertex 619.708 123.895 -2.55364e-06 + vertex 622.992 123.204 -9.44451e-06 + endloop + endfacet + facet normal -3.32643e-07 1.22161e-06 -1 + outer loop + vertex 609.594 120.283 -3.60255e-06 + vertex 616.5 124.587 -6.41395e-07 + vertex 619.708 123.895 -2.55364e-06 + endloop + endfacet + facet normal -3.69153e-07 1.05236e-06 -1 + outer loop + vertex 616.5 124.587 -6.41395e-07 + vertex 626.522 128.293 -4.41141e-07 + vertex 619.708 123.895 -2.55364e-06 + endloop + endfacet + facet normal -3.0613e-07 9.54709e-07 -1 + outer loop + vertex 619.708 123.895 -2.55364e-06 + vertex 626.522 128.293 -4.41141e-07 + vertex 629.73 127.599 -2.08617e-06 + endloop + endfacet + facet normal -8.1662e-08 2.74883e-07 -1 + outer loop + vertex 616.5 124.587 -6.41395e-07 + vertex 623.751 129.075 9.62153e-15 + vertex 626.522 128.293 -4.41141e-07 + endloop + endfacet + facet normal -9.17025e-08 2.39299e-07 -1 + outer loop + vertex 623.751 129.075 9.62153e-15 + vertex 633.578 132.841 9.62153e-15 + vertex 626.522 128.293 -4.41141e-07 + endloop + endfacet + facet normal -7.61718e-08 2.152e-07 -1 + outer loop + vertex 626.522 128.293 -4.41141e-07 + vertex 633.578 132.841 9.62153e-15 + vertex 636.53 132.136 -3.76492e-07 + endloop + endfacet + facet normal -1.30415e-07 3.53659e-07 -1 + outer loop + vertex 613.228 125.194 9.62153e-15 + vertex 623.751 129.075 9.62153e-15 + vertex 616.5 124.587 -6.41395e-07 + endloop + endfacet + facet normal -1.16792e-07 4.27122e-07 -1 + outer loop + vertex 606.258 120.933 -1.00598e-06 + vertex 613.228 125.194 9.62153e-15 + vertex 616.5 124.587 -6.41395e-07 + endloop + endfacet + facet normal -2.00392e-07 5.63868e-07 -1 + outer loop + vertex 603.196 121.629 9.62153e-15 + vertex 613.228 125.194 9.62153e-15 + vertex 606.258 120.933 -1.00598e-06 + endloop + endfacet + facet normal -1.70636e-07 6.94795e-07 -1 + outer loop + vertex 595.638 117.276 -1.73488e-06 + vertex 603.196 121.629 9.62153e-15 + vertex 606.258 120.933 -1.00598e-06 + endloop + endfacet + facet normal -6.99508e-07 2.23051e-06 -1 + outer loop + vertex 595.638 117.276 -1.73488e-06 + vertex 606.258 120.933 -1.00598e-06 + vertex 599.063 116.637 -5.55462e-06 + endloop + endfacet + facet normal -6.07177e-07 2.72566e-06 -1 + outer loop + vertex 588.038 112.947 -8.92028e-06 + vertex 595.638 117.276 -1.73488e-06 + vertex 599.063 116.637 -5.55462e-06 + endloop + endfacet + facet normal -2.53856e-06 8.49494e-06 -1 + outer loop + vertex 588.038 112.947 -8.92028e-06 + vertex 599.063 116.637 -5.55462e-06 + vertex 591.514 112.298 -2.3252e-05 + endloop + endfacet + facet normal -2.20571e-06 1.02786e-05 -1 + outer loop + vertex 580.732 108.818 -3.52398e-05 + vertex 588.038 112.947 -8.92028e-06 + vertex 591.514 112.298 -2.3252e-05 + endloop + endfacet + facet normal -1.74758e-06 7.11883e-06 -1 + outer loop + vertex 591.514 112.298 -2.3252e-05 + vertex 599.063 116.637 -5.55462e-06 + vertex 602.387 115.959 -1.61899e-05 + endloop + endfacet + facet normal -1.03574e-06 3.478e-06 -1 + outer loop + vertex 584.736 113.652 -3.04828e-06 + vertex 595.638 117.276 -1.73488e-06 + vertex 588.038 112.947 -8.92028e-06 + endloop + endfacet + facet normal -8.74943e-07 4.23118e-06 -1 + outer loop + vertex 577.211 109.473 -1.41457e-05 + vertex 584.736 113.652 -3.04828e-06 + vertex 588.038 112.947 -8.92028e-06 + endloop + endfacet + facet normal -2.71969e-07 1.18051e-06 -1 + outer loop + vertex 584.736 113.652 -3.04828e-06 + vertex 593.093 118.159 9.62153e-15 + vertex 595.638 117.276 -1.73488e-06 + endloop + endfacet + facet normal -5.86733e-07 1.76406e-06 -1 + outer loop + vertex 583.066 114.824 9.62153e-15 + vertex 593.093 118.159 9.62153e-15 + vertex 584.736 113.652 -3.04828e-06 + endloop + endfacet + facet normal -4.33407e-07 1.98256e-06 -1 + outer loop + vertex 574.302 110.312 -5.1469e-06 + vertex 583.066 114.824 9.62153e-15 + vertex 584.736 113.652 -3.04828e-06 + endloop + endfacet + facet normal -4.31146e-07 1.78103e-06 -1 + outer loop + vertex 599.063 116.637 -5.55462e-06 + vertex 606.258 120.933 -1.00598e-06 + vertex 609.594 120.283 -3.60255e-06 + endloop + endfacet + facet normal -3.39042e-07 9.87172e-07 -1 + outer loop + vertex 593.093 118.159 9.62153e-15 + vertex 603.196 121.629 9.62153e-15 + vertex 595.638 117.276 -1.73488e-06 + endloop + endfacet + facet normal -4.90752e-07 1.47528e-06 -1 + outer loop + vertex 606.258 120.933 -1.00598e-06 + vertex 616.5 124.587 -6.41395e-07 + vertex 609.594 120.283 -3.60255e-06 + endloop + endfacet + facet normal -1.94454e-06 6.15304e-06 -1 + outer loop + vertex 599.063 116.637 -5.55462e-06 + vertex 609.594 120.283 -3.60255e-06 + vertex 602.387 115.959 -1.61899e-05 + endloop + endfacet + facet normal -6.32091e-06 2.07008e-05 -1 + outer loop + vertex 591.514 112.298 -2.3252e-05 + vertex 602.387 115.959 -1.61899e-05 + vertex 594.771 111.553 -5.926e-05 + endloop + endfacet + facet normal -5.674e-06 2.35292e-05 -1 + outer loop + vertex 584.091 108.09 -8.01622e-05 + vertex 591.514 112.298 -2.3252e-05 + vertex 594.771 111.553 -5.926e-05 + endloop + endfacet + facet normal -2.44662e-05 7.55201e-05 -1 + outer loop + vertex 612.228 113.527 -0.000268207 + vertex 619.486 118.071 -0.000102633 + vertex 622.93 117.236 -0.000249922 + endloop + endfacet + facet normal -1.22509e-05 3.76115e-05 -1 + outer loop + vertex 605.595 115.203 -4.49898e-05 + vertex 616.105 118.845 -3.67909e-05 + vertex 608.87 114.394 -0.000115572 + endloop + endfacet + facet normal -1.14444e-05 3.35272e-05 -1 + outer loop + vertex 619.486 118.071 -0.000102633 + vertex 626.38 122.505 -3.2868e-05 + vertex 629.846 121.76 -9.75112e-05 + endloop + endfacet + facet normal -4.62199e-06 1.35747e-05 -1 + outer loop + vertex 612.833 119.581 -1.16761e-05 + vertex 622.992 123.204 -9.44451e-06 + vertex 616.105 118.845 -3.67909e-05 + endloop + endfacet + facet normal -4.26764e-06 1.20186e-05 -1 + outer loop + vertex 626.38 122.505 -3.2868e-05 + vertex 633.133 126.943 -8.34928e-06 + vertex 636.621 126.276 -3.12422e-05 + endloop + endfacet + facet normal -1.31991e-06 3.69828e-06 -1 + outer loop + vertex 619.708 123.895 -2.55364e-06 + vertex 629.73 127.599 -2.08617e-06 + vertex 622.992 123.204 -9.44451e-06 + endloop + endfacet + facet normal -1.26223e-06 3.30754e-06 -1 + outer loop + vertex 633.133 126.943 -8.34928e-06 + vertex 639.825 131.466 -1.83619e-06 + vertex 643.341 130.85 -8.30951e-06 + endloop + endfacet + facet normal -3.25594e-07 8.64778e-07 -1 + outer loop + vertex 626.522 128.293 -4.41141e-07 + vertex 636.53 132.136 -3.76492e-07 + vertex 629.73 127.599 -2.08617e-06 + endloop + endfacet + facet normal -3.11846e-07 7.66708e-07 -1 + outer loop + vertex 639.825 131.466 -1.83619e-06 + vertex 646.571 136.141 -3.55344e-07 + vertex 649.945 135.498 -1.9006e-06 + endloop + endfacet + facet normal -7.97897e-08 2.00051e-07 -1 + outer loop + vertex 633.578 132.841 9.62153e-15 + vertex 643.948 136.976 9.62153e-15 + vertex 636.53 132.136 -3.76492e-07 + endloop + endfacet + facet normal -3.14081e-07 7.54983e-07 -1 + outer loop + vertex 646.571 136.141 -3.55344e-07 + vertex 656.499 140.262 -3.62369e-07 + vertex 649.945 135.498 -1.9006e-06 + endloop + endfacet + facet normal -1.28114e-06 3.19948e-06 -1 + outer loop + vertex 639.825 131.466 -1.83619e-06 + vertex 649.945 135.498 -1.9006e-06 + vertex 643.341 130.85 -8.30951e-06 + endloop + endfacet + facet normal -4.37725e-06 1.1445e-05 -1 + outer loop + vertex 633.133 126.943 -8.34928e-06 + vertex 643.341 130.85 -8.30951e-06 + vertex 636.621 126.276 -3.12422e-05 + endloop + endfacet + facet normal -1.17188e-05 3.22502e-05 -1 + outer loop + vertex 626.38 122.505 -3.2868e-05 + vertex 636.621 126.276 -3.12422e-05 + vertex 629.846 121.76 -9.75112e-05 + endloop + endfacet + facet normal -2.52484e-05 7.22924e-05 -1 + outer loop + vertex 619.486 118.071 -0.000102633 + vertex 629.846 121.76 -9.75112e-05 + vertex 622.93 117.236 -0.000249922 + endloop + endfacet + facet normal -4.22815e-05 0.000126921 -1 + outer loop + vertex 612.228 113.527 -0.000268207 + vertex 622.93 117.236 -0.000249922 + vertex 615.613 112.597 -0.000529285 + endloop + endfacet + facet normal -5.53124e-05 0.000173311 -1 + outer loop + vertex 604.54 108.86 -0.000564465 + vertex 615.613 112.597 -0.000529285 + vertex 607.799 107.836 -0.000922252 + endloop + endfacet + facet normal -5.33755e-05 0.000179472 -1 + outer loop + vertex 596.914 104.324 -0.000971553 + vertex 604.54 108.86 -0.000564465 + vertex 607.799 107.836 -0.000922252 + endloop + endfacet + facet normal -6.74133e-05 0.000195365 -1 + outer loop + vertex 625.342 109.314 -0.00171612 + vertex 633.058 114.283 -0.00126532 + vertex 636.28 113.107 -0.0017123 + endloop + endfacet + facet normal -5.96339e-05 0.000175728 -1 + outer loop + vertex 618.935 111.594 -0.000887035 + vertex 629.756 115.349 -0.000872403 + vertex 622.182 110.51 -0.00127128 + endloop + endfacet + facet normal -6.55903e-05 0.000177886 -1 + outer loop + vertex 633.058 114.283 -0.00126532 + vertex 640.289 119.104 -0.00088213 + vertex 643.648 118.057 -0.00128868 + endloop + endfacet + facet normal -5.88139e-05 0.000164822 -1 + outer loop + vertex 626.375 116.331 -0.000511741 + vertex 636.847 120.065 -0.000512294 + vertex 629.756 115.349 -0.000872403 + endloop + endfacet + facet normal -6.61049e-05 0.000170649 -1 + outer loop + vertex 640.289 119.104 -0.00088213 + vertex 647.258 123.899 -0.00052454 + vertex 650.755 122.959 -0.000916077 + endloop + endfacet + facet normal -4.55076e-05 0.000122588 -1 + outer loop + vertex 633.351 120.949 -0.000244842 + vertex 643.705 124.763 -0.000248429 + vertex 636.847 120.065 -0.000512294 + endloop + endfacet + facet normal -5.07077e-05 0.000126916 -1 + outer loop + vertex 647.258 123.899 -0.00052454 + vertex 654.084 128.736 -0.000256823 + vertex 657.693 127.893 -0.000546803 + endloop + endfacet + facet normal -2.69892e-05 6.99407e-05 -1 + outer loop + vertex 640.149 125.555 -9.70748e-05 + vertex 650.474 129.506 -9.93526e-05 + vertex 643.705 124.763 -0.000248429 + endloop + endfacet + facet normal -2.96573e-05 7.27347e-05 -1 + outer loop + vertex 654.084 128.736 -0.000256823 + vertex 660.768 133.606 -0.000100755 + vertex 664.435 132.858 -0.000263951 + endloop + endfacet + facet normal -1.26369e-05 3.17437e-05 -1 + outer loop + vertex 646.894 130.208 -3.18373e-05 + vertex 657.136 134.287 -3.17845e-05 + vertex 650.474 129.506 -9.93526e-05 + endloop + endfacet + facet normal -1.34546e-05 3.1763e-05 -1 + outer loop + vertex 660.768 133.606 -0.000100755 + vertex 667.264 138.494 -3.29223e-05 + vertex 670.951 137.836 -0.000103445 + endloop + endfacet + facet normal -4.55754e-06 1.09814e-05 -1 + outer loop + vertex 653.531 134.909 -8.52928e-06 + vertex 663.613 139.094 -8.52055e-06 + vertex 657.136 134.287 -3.17845e-05 + endloop + endfacet + facet normal -4.94941e-06 1.12826e-05 -1 + outer loop + vertex 667.264 138.494 -3.29223e-05 + vertex 673.571 143.408 -8.6963e-06 + vertex 677.275 142.831 -3.35319e-05 + endloop + endfacet + facet normal -1.33402e-06 3.07527e-06 -1 + outer loop + vertex 659.976 139.66 -1.92701e-06 + vertex 669.892 143.954 -1.94986e-06 + vertex 663.613 139.094 -8.52055e-06 + endloop + endfacet + facet normal -1.43445e-06 3.11145e-06 -1 + outer loop + vertex 673.571 143.408 -8.6963e-06 + vertex 679.719 148.398 -1.9886e-06 + vertex 683.447 147.875 -8.96261e-06 + endloop + endfacet + facet normal -3.34406e-07 7.38029e-07 -1 + outer loop + vertex 666.33 144.516 -3.44388e-07 + vertex 676.162 148.96 -3.51956e-07 + vertex 669.892 143.954 -1.94986e-06 + endloop + endfacet + facet normal -3.46218e-07 7.27724e-07 -1 + outer loop + vertex 679.719 148.398 -1.9886e-06 + vertex 685.882 153.549 -3.74161e-07 + vertex 689.487 153.011 -2.01388e-06 + endloop + endfacet + facet normal -7.91084e-08 1.67641e-07 -1 + outer loop + vertex 672.924 149.532 9.62153e-15 + vertex 683.154 154.359 9.62153e-15 + vertex 676.162 148.96 -3.51956e-07 + endloop + endfacet + facet normal -3.48263e-07 7.14021e-07 -1 + outer loop + vertex 685.882 153.549 -3.74161e-07 + vertex 695.503 158.292 -3.37871e-07 + vertex 689.487 153.011 -2.01388e-06 + endloop + endfacet + facet normal -1.443e-06 3.05045e-06 -1 + outer loop + vertex 679.719 148.398 -1.9886e-06 + vertex 689.487 153.011 -2.01388e-06 + vertex 683.447 147.875 -8.96261e-06 + endloop + endfacet + facet normal -4.99582e-06 1.09844e-05 -1 + outer loop + vertex 673.571 143.408 -8.6963e-06 + vertex 683.447 147.875 -8.96261e-06 + vertex 677.275 142.831 -3.35319e-05 + endloop + endfacet + facet normal -1.35621e-05 3.11606e-05 -1 + outer loop + vertex 667.264 138.494 -3.29223e-05 + vertex 677.275 142.831 -3.35319e-05 + vertex 670.951 137.836 -0.000103445 + endloop + endfacet + facet normal -2.99249e-05 7.14238e-05 -1 + outer loop + vertex 660.768 133.606 -0.000100755 + vertex 670.951 137.836 -0.000103445 + vertex 664.435 132.858 -0.000263951 + endloop + endfacet + facet normal -5.09032e-05 0.000126079 -1 + outer loop + vertex 654.084 128.736 -0.000256823 + vertex 664.435 132.858 -0.000263951 + vertex 657.693 127.893 -0.000546803 + endloop + endfacet + facet normal -6.6658e-05 0.000168591 -1 + outer loop + vertex 647.258 123.899 -0.00052454 + vertex 657.693 127.893 -0.000546803 + vertex 650.755 122.959 -0.000916077 + endloop + endfacet + facet normal -6.70483e-05 0.00017321 -1 + outer loop + vertex 640.289 119.104 -0.00088213 + vertex 650.755 122.959 -0.000916077 + vertex 643.648 118.057 -0.00128868 + endloop + endfacet + facet normal -6.96428e-05 0.000189259 -1 + outer loop + vertex 633.058 114.283 -0.00126532 + vertex 643.648 118.057 -0.00128868 + vertex 636.28 113.107 -0.0017123 + endloop + endfacet + facet normal -0.000119234 0.000344769 -1 + outer loop + vertex 625.342 109.314 -0.00171612 + vertex 636.28 113.107 -0.0017123 + vertex 628.455 107.97 -0.00255034 + endloop + endfacet + facet normal -0.000233421 0.000684972 -1 + outer loop + vertex 617.144 104.152 -0.0025257 + vertex 628.455 107.97 -0.00255034 + vertex 620.157 102.58 -0.00430571 + endloop + endfacet + facet normal -0.000233907 0.000684042 -1 + outer loop + vertex 609.066 99.0017 -0.00415917 + vertex 617.144 104.152 -0.0025257 + vertex 620.157 102.58 -0.00430571 + endloop + endfacet + facet normal -0.000244098 0.000706063 -1 + outer loop + vertex 631.52 106.415 -0.00440042 + vertex 639.447 111.781 -0.00254702 + vertex 642.566 110.244 -0.00439372 + endloop + endfacet + facet normal -0.000248753 0.000696618 -1 + outer loop + vertex 639.447 111.781 -0.00254702 + vertex 650.145 115.587 -0.00255678 + vertex 642.566 110.244 -0.00439372 + endloop + endfacet + facet normal -0.000227126 0.000621653 -1 + outer loop + vertex 653.32 114.067 -0.00431831 + vertex 660.771 119.496 -0.00263564 + vertex 663.998 117.991 -0.00430407 + endloop + endfacet + facet normal -0.000124211 0.00031734 -1 + outer loop + vertex 646.925 116.898 -0.00174072 + vertex 657.501 120.792 -0.0018188 + vertex 650.145 115.587 -0.00255678 + endloop + endfacet + facet normal -0.000132494 0.000306881 -1 + outer loop + vertex 660.771 119.496 -0.00263564 + vertex 668.098 124.847 -0.00196435 + vertex 671.424 123.571 -0.00279644 + endloop + endfacet + facet normal -7.83934e-05 0.000182466 -1 + outer loop + vertex 654.169 121.931 -0.00134962 + vertex 664.715 125.967 -0.00143992 + vertex 657.501 120.792 -0.0018188 + endloop + endfacet + facet normal -0.000101372 0.000216146 -1 + outer loop + vertex 668.098 124.847 -0.00196435 + vertex 675.229 130.157 -0.00153942 + vertex 678.668 129.059 -0.00212559 + endloop + endfacet + facet normal -8.13113e-05 0.000191734 -1 + outer loop + vertex 661.248 126.974 -0.000965039 + vertex 671.708 131.142 -0.00101647 + vertex 664.715 125.967 -0.00143992 + endloop + endfacet + facet normal -9.8592e-05 0.000218557 -1 + outer loop + vertex 675.229 130.157 -0.00153942 + vertex 682.058 135.44 -0.00105815 + vertex 685.636 134.478 -0.00162105 + endloop + endfacet + facet normal -7.79916e-05 0.000183365 -1 + outer loop + vertex 668.097 132.038 -0.000570465 + vertex 678.392 136.313 -0.00058949 + vertex 671.708 131.142 -0.00101647 + endloop + endfacet + facet normal -8.5997e-05 0.000192388 -1 + outer loop + vertex 682.058 135.44 -0.00105815 + vertex 688.568 140.722 -0.000601878 + vertex 692.289 139.872 -0.00108541 + endloop + endfacet + facet normal -5.72756e-05 0.000130899 -1 + outer loop + vertex 674.673 137.11 -0.000272181 + vertex 684.793 141.495 -0.000277841 + vertex 678.392 136.313 -0.00058949 + endloop + endfacet + facet normal -5.94499e-05 0.000130393 -1 + outer loop + vertex 688.568 140.722 -0.000601878 + vertex 694.833 146.037 -0.000281297 + vertex 698.666 145.287 -0.000606936 + endloop + endfacet + facet normal -3.24188e-05 7.14339e-05 -1 + outer loop + vertex 681.016 142.196 -0.000105303 + vertex 691.002 146.713 -0.000106379 + vertex 684.793 141.495 -0.000277841 + endloop + endfacet + facet normal -3.28578e-05 6.98586e-05 -1 + outer loop + vertex 694.833 146.037 -0.000281297 + vertex 700.941 151.408 -0.000106756 + vertex 704.829 150.756 -0.000280061 + endloop + endfacet + facet normal -1.42651e-05 3.01719e-05 -1 + outer loop + vertex 687.207 147.323 -3.38188e-05 + vertex 697.091 151.992 -3.39478e-05 + vertex 691.002 146.713 -0.000106379 + endloop + endfacet + facet normal -1.47746e-05 2.96946e-05 -1 + outer loop + vertex 700.941 151.408 -0.000106756 + vertex 706.919 156.842 -3.37186e-05 + vertex 710.823 156.286 -0.000107912 + endloop + endfacet + facet normal -5.10908e-06 1.03572e-05 -1 + outer loop + vertex 693.276 152.518 -9.0167e-06 + vertex 703.051 157.34 -9.01122e-06 + vertex 697.091 151.992 -3.39478e-05 + endloop + endfacet + facet normal -5.17849e-06 9.96684e-06 -1 + outer loop + vertex 706.919 156.842 -3.37186e-05 + vertex 712.74 162.339 -9.076e-06 + vertex 716.661 161.868 -3.40733e-05 + endloop + endfacet + facet normal -1.47368e-06 2.86893e-06 -1 + outer loop + vertex 699.207 157.804 -2.01434e-06 + vertex 708.849 162.776 -1.96202e-06 + vertex 703.051 157.34 -9.01122e-06 + endloop + endfacet + facet normal -1.44494e-06 2.7281e-06 -1 + outer loop + vertex 712.74 162.339 -9.076e-06 + vertex 718.381 167.921 -1.99838e-06 + vertex 722.323 167.511 -8.81415e-06 + endloop + endfacet + facet normal -3.49212e-07 6.43793e-07 -1 + outer loop + vertex 705.133 163.258 -3.5338e-07 + vertex 714.617 168.377 -3.69752e-07 + vertex 708.849 162.776 -1.96202e-06 + endloop + endfacet + facet normal -3.42839e-07 6.16677e-07 -1 + outer loop + vertex 718.381 167.921 -1.99838e-06 + vertex 723.98 173.675 -3.69784e-07 + vertex 727.808 173.255 -1.94125e-06 + endloop + endfacet + facet normal -8.75604e-08 1.5472e-07 -1 + outer loop + vertex 711.606 169.063 9.62153e-15 + vertex 720.665 174.19 9.62153e-15 + vertex 714.617 168.377 -3.69752e-07 + endloop + endfacet + facet normal -3.46532e-07 5.83021e-07 -1 + outer loop + vertex 723.98 173.675 -3.69784e-07 + vertex 733.249 179.178 -3.72987e-07 + vertex 727.808 173.255 -1.94125e-06 + endloop + endfacet + facet normal -1.45931e-06 2.59004e-06 -1 + outer loop + vertex 718.381 167.921 -1.99838e-06 + vertex 727.808 173.255 -1.94125e-06 + vertex 722.323 167.511 -8.81415e-06 + endloop + endfacet + facet normal -5.20998e-06 9.7047e-06 -1 + outer loop + vertex 712.74 162.339 -9.076e-06 + vertex 722.323 167.511 -8.81415e-06 + vertex 716.661 161.868 -3.40733e-05 + endloop + endfacet + facet normal -1.49005e-05 2.8811e-05 -1 + outer loop + vertex 706.919 156.842 -3.37186e-05 + vertex 716.661 161.868 -3.40733e-05 + vertex 710.823 156.286 -0.000107912 + endloop + endfacet + facet normal -3.32996e-05 6.72242e-05 -1 + outer loop + vertex 700.941 151.408 -0.000106756 + vertex 710.823 156.286 -0.000107912 + vertex 704.829 150.756 -0.000280061 + endloop + endfacet + facet normal -6.00322e-05 0.000127417 -1 + outer loop + vertex 694.833 146.037 -0.000281297 + vertex 704.829 150.756 -0.000280061 + vertex 698.666 145.287 -0.000606936 + endloop + endfacet + facet normal -8.64936e-05 0.000190213 -1 + outer loop + vertex 688.568 140.722 -0.000601878 + vertex 698.666 145.287 -0.000606936 + vertex 692.289 139.872 -0.00108541 + endloop + endfacet + facet normal -9.81096e-05 0.000220352 -1 + outer loop + vertex 682.058 135.44 -0.00105815 + vertex 692.289 139.872 -0.00108541 + vertex 685.636 134.478 -0.00162105 + endloop + endfacet + facet normal -9.9728e-05 0.000221293 -1 + outer loop + vertex 675.229 130.157 -0.00153942 + vertex 685.636 134.478 -0.00162105 + vertex 678.668 129.059 -0.00212559 + endloop + endfacet + facet normal -0.000134961 0.000300448 -1 + outer loop + vertex 668.098 124.847 -0.00196435 + vertex 678.668 129.059 -0.00212559 + vertex 671.424 123.571 -0.00279644 + endloop + endfacet + facet normal -0.000241292 0.00059128 -1 + outer loop + vertex 660.771 119.496 -0.00263564 + vertex 671.424 123.571 -0.00279644 + vertex 663.998 117.991 -0.00430407 + endloop + endfacet + facet normal -0.000324329 0.000886149 -1 + outer loop + vertex 653.32 114.067 -0.00431831 + vertex 663.998 117.991 -0.00430407 + vertex 656.434 112.279 -0.00691258 + endloop + endfacet + facet normal -0.000304144 0.000921301 -1 + outer loop + vertex 645.626 108.439 -0.0071637 + vertex 653.32 114.067 -0.00431831 + vertex 656.434 112.279 -0.00691258 + endloop + endfacet + facet normal -0.000140223 0.000417062 -1 + outer loop + vertex 634.524 104.588 -0.00721281 + vertex 645.626 108.439 -0.0071637 + vertex 637.406 102.431 -0.00851683 + endloop + endfacet + facet normal 0.000593994 -0.00179112 -0.999998 + outer loop + vertex 625.933 98.5347 -0.00835394 + vertex 637.406 102.431 -0.00851683 + vertex 628.564 95.9866 -0.00222715 + endloop + endfacet + facet normal 0.000605991 -0.00177873 -0.999998 + outer loop + vertex 617.333 92.3192 -0.00250965 + vertex 625.933 98.5347 -0.00835394 + vertex 628.564 95.9866 -0.00222715 + endloop + endfacet + facet normal 0.000586692 -0.00169306 -0.999998 + outer loop + vertex 640.096 99.9132 -0.00251053 + vertex 648.569 106.309 -0.00836704 + vertex 651.33 103.825 -0.00254341 + endloop + endfacet + facet normal 0.000637707 -0.00163634 -0.999998 + outer loop + vertex 648.569 106.309 -0.00836704 + vertex 659.435 110.169 -0.00775571 + vertex 651.33 103.825 -0.00254341 + endloop + endfacet + facet normal 1.05315e-05 0.000175193 -1 + outer loop + vertex 659.435 110.169 -0.00775571 + vertex 667.163 116.218 -0.00661471 + vertex 670.217 114.126 -0.00694906 + endloop + endfacet + facet normal 0.000827341 -0.00200211 -0.999998 + outer loop + vertex 673.091 111.685 -6.27067e-05 + vertex 681.02 118.249 -0.00664483 + vertex 683.946 115.826 0.000626263 + endloop + endfacet + facet normal -4.0977e-05 9.99931e-05 -1 + outer loop + vertex 667.163 116.218 -0.00661471 + vertex 677.916 120.325 -0.00664462 + vertex 670.217 114.126 -0.00694906 + endloop + endfacet + facet normal -5.85002e-06 -4.46618e-05 -1 + outer loop + vertex 681.02 118.249 -0.00664483 + vertex 688.639 124.594 -0.0069728 + vertex 691.79 122.535 -0.00689925 + endloop + endfacet + facet normal -0.000303586 0.000687938 -1 + outer loop + vertex 674.7 122.082 -0.00445969 + vertex 685.37 126.331 -0.00477546 + vertex 677.916 120.325 -0.00664462 + endloop + endfacet + facet normal -0.000330193 0.000698769 -1 + outer loop + vertex 688.639 124.594 -0.0069728 + vertex 695.936 130.719 -0.00510229 + vertex 699.25 128.999 -0.00739885 + endloop + endfacet + facet normal -0.000262523 0.000579294 -1 + outer loop + vertex 682.043 127.802 -0.00305024 + vertex 692.555 132.167 -0.00328127 + vertex 685.37 126.331 -0.00477546 + endloop + endfacet + facet normal -0.000292162 0.000623202 -1 + outer loop + vertex 695.936 130.719 -0.00510229 + vertex 702.943 136.667 -0.0034432 + vertex 706.375 135.24 -0.00533496 + endloop + endfacet + facet normal -0.000164563 0.000357845 -1 + outer loop + vertex 689.125 133.401 -0.00227512 + vertex 699.463 137.879 -0.00237397 + vertex 692.555 132.167 -0.00328127 + endloop + endfacet + facet normal -0.000183405 0.00038786 -1 + outer loop + vertex 702.943 136.667 -0.0034432 + vertex 709.722 142.518 -0.00241705 + vertex 713.251 141.327 -0.00352603 + endloop + endfacet + facet normal -0.000119668 0.000258739 -1 + outer loop + vertex 695.918 138.934 -0.00167696 + vertex 706.125 143.548 -0.00170451 + vertex 699.463 137.879 -0.00237397 + endloop + endfacet + facet normal -0.000126273 0.000262347 -1 + outer loop + vertex 709.722 142.518 -0.00241705 + vertex 716.28 148.345 -0.0017164 + vertex 719.929 147.338 -0.00244124 + endloop + endfacet + facet normal -0.000107486 0.00022669 -1 + outer loop + vertex 702.438 144.463 -0.00110085 + vertex 712.544 149.234 -0.00110556 + vertex 706.125 143.548 -0.00170451 + endloop + endfacet + facet normal -0.000110263 0.000222899 -1 + outer loop + vertex 716.28 148.345 -0.0017164 + vertex 722.591 154.193 -0.00110874 + vertex 726.383 153.329 -0.00171936 + endloop + endfacet + facet normal -9.06963e-05 0.000183785 -1 + outer loop + vertex 708.714 150.034 -0.00061109 + vertex 718.71 154.965 -0.000611343 + vertex 712.544 149.234 -0.00110556 + endloop + endfacet + facet normal -9.25645e-05 0.000179269 -1 + outer loop + vertex 722.591 154.193 -0.00110874 + vertex 728.617 160.077 -0.000611727 + vertex 732.552 159.332 -0.00110945 + endloop + endfacet + facet normal -6.23362e-05 0.00012061 -1 + outer loop + vertex 714.767 155.661 -0.000281687 + vertex 724.619 160.744 -0.000282682 + vertex 718.71 154.965 -0.000611343 + endloop + endfacet + facet normal -6.37946e-05 0.000117686 -1 + outer loop + vertex 728.617 160.077 -0.000611727 + vertex 734.363 166.004 -0.000280728 + vertex 738.411 165.369 -0.000613762 + endloop + endfacet + facet normal -3.45325e-05 6.3775e-05 -1 + outer loop + vertex 720.621 161.339 -0.000106727 + vertex 730.307 166.57 -0.000107572 + vertex 724.619 160.744 -0.000282682 + endloop + endfacet + facet normal -3.43515e-05 6.06175e-05 -1 + outer loop + vertex 734.363 166.004 -0.000280728 + vertex 739.885 171.991 -0.000107531 + vertex 743.995 171.455 -0.000281148 + endloop + endfacet + facet normal -1.49987e-05 2.64976e-05 -1 + outer loop + vertex 726.293 167.07 -3.41294e-05 + vertex 735.819 172.461 -3.41576e-05 + vertex 730.307 166.57 -0.000107572 + endloop + endfacet + facet normal -1.5056e-05 2.53576e-05 -1 + outer loop + vertex 739.885 171.991 -0.000107531 + vertex 745.233 178.052 -3.43364e-05 + vertex 749.35 177.61 -0.000107541 + endloop + endfacet + facet normal -5.32051e-06 8.98764e-06 -1 + outer loop + vertex 731.797 172.875 -9.04226e-06 + vertex 741.166 178.437 -8.89052e-06 + vertex 735.819 172.461 -3.41576e-05 + endloop + endfacet + facet normal -5.22539e-06 8.50022e-06 -1 + outer loop + vertex 745.233 178.052 -3.43364e-05 + vertex 750.387 184.199 -9.02666e-06 + vertex 754.498 183.836 -3.35861e-05 + endloop + endfacet + facet normal -1.49612e-06 2.40553e-06 -1 + outer loop + vertex 737.13 178.792 -1.99974e-06 + vertex 746.317 184.529 -1.94492e-06 + vertex 741.166 178.437 -8.89052e-06 + endloop + endfacet + facet normal -1.52612e-06 2.32034e-06 -1 + outer loop + vertex 750.387 184.199 -9.02666e-06 + vertex 755.293 190.45 -2.00876e-06 + vertex 759.391 190.146 -8.96823e-06 + endloop + endfacet + facet normal -3.53081e-07 5.38065e-07 -1 + outer loop + vertex 742.403 184.895 -3.65545e-07 + vertex 751.385 190.812 -3.53513e-07 + vertex 746.317 184.529 -1.94492e-06 + endloop + endfacet + facet normal -3.57882e-07 5.21108e-07 -1 + outer loop + vertex 755.293 190.45 -2.00876e-06 + vertex 760.049 196.864 -3.6844e-07 + vertex 763.979 196.542 -1.9423e-06 + endloop + endfacet + facet normal -8.76464e-08 1.25769e-07 -1 + outer loop + vertex 748.154 191.371 9.62153e-15 + vertex 756.831 197.418 9.62153e-15 + vertex 751.385 190.812 -3.53513e-07 + endloop + endfacet + facet normal -3.60621e-07 4.87613e-07 -1 + outer loop + vertex 760.049 196.864 -3.6844e-07 + vertex 768.329 203.016 -3.54231e-07 + vertex 763.979 196.542 -1.9423e-06 + endloop + endfacet + facet normal -1.5351e-06 2.19936e-06 -1 + outer loop + vertex 755.293 190.45 -2.00876e-06 + vertex 763.979 196.542 -1.9423e-06 + vertex 759.391 190.146 -8.96823e-06 + endloop + endfacet + facet normal -5.27047e-06 7.98921e-06 -1 + outer loop + vertex 750.387 184.199 -9.02666e-06 + vertex 759.391 190.146 -8.96823e-06 + vertex 754.498 183.836 -3.35861e-05 + endloop + endfacet + facet normal -1.51577e-05 2.44108e-05 -1 + outer loop + vertex 745.233 178.052 -3.43364e-05 + vertex 754.498 183.836 -3.35861e-05 + vertex 749.35 177.61 -0.000107541 + endloop + endfacet + facet normal -3.46464e-05 5.83543e-05 -1 + outer loop + vertex 739.885 171.991 -0.000107531 + vertex 749.35 177.61 -0.000107541 + vertex 743.995 171.455 -0.000281148 + endloop + endfacet + facet normal -6.44148e-05 0.000113735 -1 + outer loop + vertex 734.363 166.004 -0.000280728 + vertex 743.995 171.455 -0.000281148 + vertex 738.411 165.369 -0.000613762 + endloop + endfacet + facet normal -9.37326e-05 0.000173095 -1 + outer loop + vertex 728.617 160.077 -0.000611727 + vertex 738.411 165.369 -0.000613762 + vertex 732.552 159.332 -0.00110945 + endloop + endfacet + facet normal -0.000111738 0.00021643 -1 + outer loop + vertex 722.591 154.193 -0.00110874 + vertex 732.552 159.332 -0.00110945 + vertex 726.383 153.329 -0.00171936 + endloop + endfacet + facet normal -0.000127511 0.000257858 -1 + outer loop + vertex 716.28 148.345 -0.0017164 + vertex 726.383 153.329 -0.00171936 + vertex 719.929 147.338 -0.00244124 + endloop + endfacet + facet normal -0.000184299 0.00038521 -1 + outer loop + vertex 709.722 142.518 -0.00241705 + vertex 719.929 147.338 -0.00244124 + vertex 713.251 141.327 -0.00352603 + endloop + endfacet + facet normal -0.000291037 0.000625909 -1 + outer loop + vertex 702.943 136.667 -0.0034432 + vertex 713.251 141.327 -0.00352603 + vertex 706.375 135.24 -0.00533496 + endloop + endfacet + facet normal -0.000327299 0.000704342 -1 + outer loop + vertex 695.936 130.719 -0.00510229 + vertex 706.375 135.24 -0.00533496 + vertex 699.25 128.999 -0.00739885 + endloop + endfacet + facet normal -1.54889e-05 -5.94098e-05 -1 + outer loop + vertex 688.639 124.594 -0.0069728 + vertex 699.25 128.999 -0.00739885 + vertex 691.79 122.535 -0.00689925 + endloop + endfacet + facet normal 0.000790738 -0.00204632 -0.999998 + outer loop + vertex 681.02 118.249 -0.00664483 + vertex 691.79 122.535 -0.00689925 + vertex 683.946 115.826 0.000626263 + endloop + endfacet + facet normal 0.00206455 -0.00524484 -0.999984 + outer loop + vertex 673.091 111.685 -6.27067e-05 + vertex 683.946 115.826 0.000626263 + vertex 675.681 108.88 0.0199952 + endloop + endfacet + facet normal 0.00210591 -0.00520664 -0.999984 + outer loop + vertex 664.791 104.886 0.0178536 + vertex 673.091 111.685 -6.27067e-05 + vertex 675.681 108.88 0.0199952 + endloop + endfacet + facet normal 0.00193377 -0.00508415 -0.999985 + outer loop + vertex 653.813 100.981 0.0164806 + vertex 662.251 107.708 -0.00140186 + vertex 664.791 104.886 0.0178536 + endloop + endfacet + facet normal 0.00352227 -0.0103097 -0.999941 + outer loop + vertex 642.524 97.0433 0.0173141 + vertex 653.813 100.981 0.0164806 + vertex 644.584 93.8361 0.057637 + endloop + endfacet + facet normal 0.00611718 -0.0189944 -0.999801 + outer loop + vertex 632.967 89.873 0.0618538 + vertex 644.584 93.8361 0.057637 + vertex 634.664 86.3899 0.138407 + endloop + endfacet + facet normal 0.00587838 -0.0191107 -0.9998 + outer loop + vertex 623.369 82.7475 0.141624 + vertex 632.967 89.873 0.0618538 + vertex 634.664 86.3899 0.138407 + endloop + endfacet + facet normal 0.00592395 -0.0177774 -0.999824 + outer loop + vertex 646.27 90.3488 0.130469 + vertex 655.908 97.7877 0.0553113 + vertex 657.598 94.2916 0.127485 + endloop + endfacet + facet normal 0.00630113 -0.0174985 -0.999827 + outer loop + vertex 657.598 94.2916 0.127485 + vertex 666.939 101.711 0.0565048 + vertex 668.667 98.2219 0.128457 + endloop + endfacet + facet normal 0.00657167 -0.0174308 -0.999826 + outer loop + vertex 668.667 98.2219 0.128457 + vertex 677.897 105.729 0.0582448 + vertex 679.673 102.256 0.130465 + endloop + endfacet + facet normal 0.0128533 -0.0337879 -0.999346 + outer loop + vertex 681.131 98.5196 0.277642 + vertex 690.684 106.454 0.132237 + vertex 692.193 102.737 0.27733 + endloop + endfacet + facet normal 0.0252076 -0.066193 -0.997488 + outer loop + vertex 681.131 98.5196 0.277642 + vertex 692.193 102.737 0.27733 + vertex 682.558 94.586 0.574749 + endloop + endfacet + facet normal 0.0133236 -0.0335969 -0.999347 + outer loop + vertex 690.684 106.454 0.132237 + vertex 701.632 110.804 0.13197 + vertex 692.193 102.737 0.27733 + endloop + endfacet + facet normal 0.0133061 -0.0335764 -0.999348 + outer loop + vertex 692.193 102.737 0.27733 + vertex 701.632 110.804 0.13197 + vertex 703.174 107.097 0.277065 + endloop + endfacet + facet normal 0.0262154 -0.0660925 -0.997469 + outer loop + vertex 692.193 102.737 0.27733 + vertex 703.174 107.097 0.277065 + vertex 693.665 98.8227 0.575371 + endloop + endfacet + facet normal 0.0137783 -0.03338 -0.999348 + outer loop + vertex 701.632 110.804 0.13197 + vertex 712.447 115.283 0.131489 + vertex 703.174 107.097 0.277065 + endloop + endfacet + facet normal 0.0138846 -0.0335004 -0.999342 + outer loop + vertex 703.174 107.097 0.277065 + vertex 712.447 115.283 0.131489 + vertex 714.014 111.581 0.277358 + endloop + endfacet + facet normal 0.0272685 -0.0658556 -0.997457 + outer loop + vertex 703.174 107.097 0.277065 + vertex 714.014 111.581 0.277358 + vertex 704.67 103.192 0.575747 + endloop + endfacet + facet normal 0.0143527 -0.0333022 -0.999342 + outer loop + vertex 712.447 115.283 0.131489 + vertex 723.137 119.9 0.131147 + vertex 714.014 111.581 0.277358 + endloop + endfacet + facet normal 0.0143281 -0.0332752 -0.999344 + outer loop + vertex 714.014 111.581 0.277358 + vertex 723.137 119.9 0.131147 + vertex 724.73 116.204 0.277045 + endloop + endfacet + facet normal 0.0278341 -0.0645774 -0.997524 + outer loop + vertex 714.014 111.581 0.277358 + vertex 724.73 116.204 0.277045 + vertex 715.526 107.683 0.571862 + endloop + endfacet + facet normal 0.0148485 -0.0330508 -0.999343 + outer loop + vertex 723.137 119.9 0.131147 + vertex 733.749 124.685 0.130564 + vertex 724.73 116.204 0.277045 + endloop + endfacet + facet normal 0.0149776 -0.033188 -0.999337 + outer loop + vertex 724.73 116.204 0.277045 + vertex 733.749 124.685 0.130564 + vertex 735.371 120.998 0.277345 + endloop + endfacet + facet normal 0.0291427 -0.0646348 -0.997483 + outer loop + vertex 724.73 116.204 0.277045 + vertex 735.371 120.998 0.277345 + vertex 726.262 112.314 0.573875 + endloop + endfacet + facet normal 0.0155068 -0.0329551 -0.999337 + outer loop + vertex 733.749 124.685 0.130564 + vertex 744.318 129.663 0.130429 + vertex 735.371 120.998 0.277345 + endloop + endfacet + facet normal 0.0154846 -0.0329322 -0.999338 + outer loop + vertex 735.371 120.998 0.277345 + vertex 744.318 129.663 0.130429 + vertex 745.971 125.984 0.277256 + endloop + endfacet + facet normal 0.030151 -0.0641074 -0.997487 + outer loop + vertex 735.371 120.998 0.277345 + vertex 745.971 125.984 0.277256 + vertex 736.927 117.117 0.573762 + endloop + endfacet + facet normal 0.0160766 -0.0326662 -0.999337 + outer loop + vertex 744.318 129.663 0.130429 + vertex 754.83 134.836 0.130438 + vertex 745.971 125.984 0.277256 + endloop + endfacet + facet normal 0.0160515 -0.0326411 -0.999338 + outer loop + vertex 745.971 125.984 0.277256 + vertex 754.83 134.836 0.130438 + vertex 756.513 131.167 0.277314 + endloop + endfacet + facet normal 0.031177 -0.06341 -0.9975 + outer loop + vertex 745.971 125.984 0.277256 + vertex 756.513 131.167 0.277314 + vertex 747.554 122.116 0.572657 + endloop + endfacet + facet normal 0.01671 -0.0323391 -0.999337 + outer loop + vertex 754.83 134.836 0.130438 + vertex 765.246 140.197 0.131109 + vertex 756.513 131.167 0.277314 + endloop + endfacet + facet normal 0.01657 -0.0322038 -0.999344 + outer loop + vertex 756.513 131.167 0.277314 + vertex 765.246 140.197 0.131109 + vertex 766.96 136.536 0.277486 + endloop + endfacet + facet normal 0.0324696 -0.0631355 -0.997477 + outer loop + vertex 756.513 131.167 0.277314 + vertex 766.96 136.536 0.277486 + vertex 758.124 127.31 0.573852 + endloop + endfacet + facet normal 0.0171818 -0.0319172 -0.999343 + outer loop + vertex 765.246 140.197 0.131109 + vertex 775.548 145.746 0.131002 + vertex 766.96 136.536 0.277486 + endloop + endfacet + facet normal 0.0167558 -0.0315203 -0.999363 + outer loop + vertex 766.96 136.536 0.277486 + vertex 775.548 145.746 0.131002 + vertex 777.291 142.093 0.275449 + endloop + endfacet + facet normal 0.0333319 -0.0623393 -0.997498 + outer loop + vertex 766.96 136.536 0.277486 + vertex 777.291 142.093 0.275449 + vertex 768.588 132.687 0.572446 + endloop + endfacet + facet normal 0.0175398 -0.0311463 -0.999361 + outer loop + vertex 775.548 145.746 0.131002 + vertex 785.743 151.494 0.130784 + vertex 777.291 142.093 0.275449 + endloop + endfacet + facet normal 0.0178079 -0.0313872 -0.999349 + outer loop + vertex 777.291 142.093 0.275449 + vertex 785.743 151.494 0.130784 + vertex 787.512 147.848 0.276814 + endloop + endfacet + facet normal 0.0353105 -0.0624697 -0.997422 + outer loop + vertex 777.291 142.093 0.275449 + vertex 787.512 147.848 0.276814 + vertex 778.938 138.254 0.574208 + endloop + endfacet + facet normal 0.0183727 -0.0311132 -0.999347 + outer loop + vertex 785.743 151.494 0.130784 + vertex 795.821 157.445 0.130794 + vertex 787.512 147.848 0.276814 + endloop + endfacet + facet normal 0.0181772 -0.0309441 -0.999356 + outer loop + vertex 787.512 147.848 0.276814 + vertex 795.821 157.445 0.130794 + vertex 797.62 153.809 0.276116 + endloop + endfacet + facet normal 0.0362291 -0.0615583 -0.997446 + outer loop + vertex 787.512 147.848 0.276814 + vertex 797.62 153.809 0.276116 + vertex 789.184 144.021 0.573796 + endloop + endfacet + facet normal 0.019023 -0.0305255 -0.999353 + outer loop + vertex 795.821 157.445 0.130794 + vertex 805.725 163.605 0.131171 + vertex 797.62 153.809 0.276116 + endloop + endfacet + facet normal 0.0191387 -0.0306212 -0.999348 + outer loop + vertex 797.62 153.809 0.276116 + vertex 805.725 163.605 0.131171 + vertex 807.563 159.986 0.277266 + endloop + endfacet + facet normal 0.0381846 -0.0612793 -0.99739 + outer loop + vertex 797.62 153.809 0.276116 + vertex 807.563 159.986 0.277266 + vertex 799.315 149.996 0.57526 + endloop + endfacet + facet normal 0.0200339 -0.0301664 -0.999344 + outer loop + vertex 805.725 163.605 0.131171 + vertex 815.374 170.019 0.130998 + vertex 807.563 159.986 0.277266 + endloop + endfacet + facet normal 0.0201159 -0.0302302 -0.999341 + outer loop + vertex 807.563 159.986 0.277266 + vertex 815.374 170.019 0.130998 + vertex 817.259 166.427 0.277584 + endloop + endfacet + facet normal 0.0397408 -0.0597708 -0.997421 + outer loop + vertex 807.563 159.986 0.277266 + vertex 817.259 166.427 0.277584 + vertex 809.286 156.192 0.573258 + endloop + endfacet + facet normal 0.0214128 -0.0295494 -0.999334 + outer loop + vertex 815.374 170.019 0.130998 + vertex 824.693 176.77 0.131053 + vertex 817.259 166.427 0.277584 + endloop + endfacet + facet normal 0.0212895 -0.0294609 -0.999339 + outer loop + vertex 817.259 166.427 0.277584 + vertex 824.693 176.77 0.131053 + vertex 826.659 173.217 0.277694 + endloop + endfacet + facet normal 0.0422506 -0.0584833 -0.997394 + outer loop + vertex 817.259 166.427 0.277584 + vertex 826.659 173.217 0.277694 + vertex 819.033 162.667 0.573193 + endloop + endfacet + facet normal 0.0226777 -0.0286923 -0.999331 + outer loop + vertex 824.693 176.77 0.131053 + vertex 833.679 183.852 0.131628 + vertex 826.659 173.217 0.277694 + endloop + endfacet + facet normal 0.0216731 -0.0280299 -0.999372 + outer loop + vertex 826.659 173.217 0.277694 + vertex 833.679 183.852 0.131628 + vertex 835.754 180.347 0.274938 + endloop + endfacet + facet normal 0.0443121 -0.0569046 -0.997396 + outer loop + vertex 826.659 173.217 0.277694 + vertex 835.754 180.347 0.274938 + vertex 828.518 169.5 0.572306 + endloop + endfacet + facet normal 0.0226931 -0.0274259 -0.999366 + outer loop + vertex 833.679 183.852 0.131628 + vertex 842.25 190.984 0.130505 + vertex 835.754 180.347 0.274938 + endloop + endfacet + facet normal 0.0226048 -0.027372 -0.99937 + outer loop + vertex 835.754 180.347 0.274938 + vertex 842.25 190.984 0.130505 + vertex 844.413 187.575 0.272831 + endloop + endfacet + facet normal 0.0462458 -0.0556935 -0.997376 + outer loop + vertex 835.754 180.347 0.274938 + vertex 844.413 187.575 0.272831 + vertex 837.7 176.677 0.570094 + endloop + endfacet + facet normal 0.0230854 -0.0270668 -0.999367 + outer loop + vertex 842.25 190.984 0.130505 + vertex 849.983 197.579 0.130538 + vertex 844.413 187.575 0.272831 + endloop + endfacet + facet normal 0.0242199 -0.0276978 -0.999323 + outer loop + vertex 844.413 187.575 0.272831 + vertex 849.983 197.579 0.130538 + vertex 852.376 194.489 0.274169 + endloop + endfacet + facet normal 0.047165 -0.0541213 -0.99742 + outer loop + vertex 844.413 187.575 0.272831 + vertex 852.376 194.489 0.274169 + vertex 846.477 183.981 0.565441 + endloop + endfacet + facet normal 0.0251949 -0.0269428 -0.999319 + outer loop + vertex 849.983 197.579 0.130538 + vertex 856.619 203.691 0.133051 + vertex 852.376 194.489 0.274169 + endloop + endfacet + facet normal 0.011465 -0.0134398 -0.999844 + outer loop + vertex 842.25 190.984 0.130505 + vertex 847.536 200.563 0.062363 + vertex 849.983 197.579 0.130538 + endloop + endfacet + facet normal 0.0115 -0.0134111 -0.999844 + outer loop + vertex 847.536 200.563 0.062363 + vertex 853.462 205.082 0.0699114 + vertex 849.983 197.579 0.130538 + endloop + endfacet + facet normal 0.0113352 -0.0133682 -0.999846 + outer loop + vertex 839.749 194.141 0.0599522 + vertex 847.536 200.563 0.062363 + vertex 842.25 190.984 0.130505 + endloop + endfacet + facet normal 0.00634529 -0.00731804 -0.999953 + outer loop + vertex 839.749 194.141 0.0599522 + vertex 844.679 203.482 0.0228792 + vertex 847.536 200.563 0.062363 + endloop + endfacet + facet normal 0.00643767 -0.00722763 -0.999953 + outer loop + vertex 844.679 203.482 0.0228792 + vertex 851.75 208.649 0.0310576 + vertex 847.536 200.563 0.062363 + endloop + endfacet + facet normal 0.00652015 -0.00741033 -0.999951 + outer loop + vertex 836.778 196.942 0.0198234 + vertex 844.679 203.482 0.0228792 + vertex 839.749 194.141 0.0599522 + endloop + endfacet + facet normal 0.00642043 -0.00751612 -0.999951 + outer loop + vertex 831.258 187.065 0.0586196 + vertex 836.778 196.942 0.0198234 + vertex 839.749 194.141 0.0599522 + endloop + endfacet + facet normal 0.011726 -0.0138828 -0.999835 + outer loop + vertex 831.258 187.065 0.0586196 + vertex 839.749 194.141 0.0599522 + vertex 833.679 183.852 0.131628 + endloop + endfacet + facet normal 0.00632818 -0.00746457 -0.999952 + outer loop + vertex 828.37 189.88 0.0193315 + vertex 836.778 196.942 0.0198234 + vertex 831.258 187.065 0.0586196 + endloop + endfacet + facet normal 0.00611471 -0.00768355 -0.999952 + outer loop + vertex 822.367 180.024 0.0583567 + vertex 828.37 189.88 0.0193315 + vertex 831.258 187.065 0.0586196 + endloop + endfacet + facet normal 0.0113144 -0.0142491 -0.999834 + outer loop + vertex 822.367 180.024 0.0583567 + vertex 831.258 187.065 0.0586196 + vertex 824.693 176.77 0.131053 + endloop + endfacet + facet normal 0.00605295 -0.00764594 -0.999952 + outer loop + vertex 819.58 182.905 0.0194565 + vertex 828.37 189.88 0.0193315 + vertex 822.367 180.024 0.0583567 + endloop + endfacet + facet normal 0.00572269 -0.00796554 -0.999952 + outer loop + vertex 813.11 173.316 0.0588142 + vertex 819.58 182.905 0.0194565 + vertex 822.367 180.024 0.0583567 + endloop + endfacet + facet normal 0.0105585 -0.014639 -0.999837 + outer loop + vertex 813.11 173.316 0.0588142 + vertex 822.367 180.024 0.0583567 + vertex 815.374 170.019 0.130998 + endloop + endfacet + facet normal 0.00587775 -0.00807016 -0.99995 + outer loop + vertex 810.406 176.25 0.0192392 + vertex 819.58 182.905 0.0194565 + vertex 813.11 173.316 0.0588142 + endloop + endfacet + facet normal 0.00557435 -0.00834968 -0.99995 + outer loop + vertex 803.517 166.932 0.0586434 + vertex 810.406 176.25 0.0192392 + vertex 813.11 173.316 0.0588142 + endloop + endfacet + facet normal 0.0100737 -0.0151108 -0.999835 + outer loop + vertex 803.517 166.932 0.0586434 + vertex 813.11 173.316 0.0588142 + vertex 805.725 163.605 0.131171 + endloop + endfacet + facet normal 0.0054404 -0.00825066 -0.999951 + outer loop + vertex 800.838 169.894 0.0196239 + vertex 810.406 176.25 0.0192392 + vertex 803.517 166.932 0.0586434 + endloop + endfacet + facet normal 0.00524925 -0.00842351 -0.999951 + outer loop + vertex 793.648 160.789 0.0585834 + vertex 800.838 169.894 0.0196239 + vertex 803.517 166.932 0.0586434 + endloop + endfacet + facet normal 0.00957355 -0.0153708 -0.999836 + outer loop + vertex 793.648 160.789 0.0585834 + vertex 803.517 166.932 0.0586434 + vertex 795.821 157.445 0.130794 + endloop + endfacet + facet normal 0.00524029 -0.00841643 -0.999951 + outer loop + vertex 791.006 163.771 0.0196355 + vertex 800.838 169.894 0.0196239 + vertex 793.648 160.789 0.0585834 + endloop + endfacet + facet normal 0.0050599 -0.00857625 -0.99995 + outer loop + vertex 783.603 154.85 0.0586951 + vertex 791.006 163.771 0.0196355 + vertex 793.648 160.789 0.0585834 + endloop + endfacet + facet normal 0.00921575 -0.0156047 -0.999836 + outer loop + vertex 783.603 154.85 0.0586951 + vertex 793.648 160.789 0.0585834 + vertex 785.743 151.494 0.130784 + endloop + endfacet + facet normal 0.00511095 -0.0086186 -0.99995 + outer loop + vertex 781.004 157.851 0.0195446 + vertex 791.006 163.771 0.0196355 + vertex 783.603 154.85 0.0586951 + endloop + endfacet + facet normal 0.00496526 -0.00874479 -0.999949 + outer loop + vertex 773.449 149.114 0.0584288 + vertex 781.004 157.851 0.0195446 + vertex 783.603 154.85 0.0586951 + endloop + endfacet + facet normal 0.00901883 -0.0159218 -0.999833 + outer loop + vertex 773.449 149.114 0.0584288 + vertex 783.603 154.85 0.0586951 + vertex 775.548 145.746 0.131002 + endloop + endfacet + facet normal 0.00490432 -0.00869209 -0.99995 + outer loop + vertex 770.882 152.131 0.019621 + vertex 781.004 157.851 0.0195446 + vertex 773.449 149.114 0.0584288 + endloop + endfacet + facet normal 0.00476301 -0.00881231 -0.99995 + outer loop + vertex 763.18 143.576 0.0583224 + vertex 770.882 152.131 0.019621 + vertex 773.449 149.114 0.0584288 + endloop + endfacet + facet normal 0.00874238 -0.0161908 -0.999831 + outer loop + vertex 763.18 143.576 0.0583224 + vertex 773.449 149.114 0.0584288 + vertex 765.246 140.197 0.131109 + endloop + endfacet + facet normal 0.00469556 -0.00875157 -0.999951 + outer loop + vertex 760.64 146.605 0.0198858 + vertex 770.882 152.131 0.019621 + vertex 763.18 143.576 0.0583224 + endloop + endfacet + facet normal 0.00453432 -0.00888673 -0.99995 + outer loop + vertex 752.788 138.224 0.0587641 + vertex 760.64 146.605 0.0198858 + vertex 763.18 143.576 0.0583224 + endloop + endfacet + facet normal 0.0082797 -0.0161591 -0.999835 + outer loop + vertex 752.788 138.224 0.0587641 + vertex 763.18 143.576 0.0583224 + vertex 754.83 134.836 0.130438 + endloop + endfacet + facet normal 0.00463816 -0.00898401 -0.999949 + outer loop + vertex 750.295 141.272 0.0198148 + vertex 760.64 146.605 0.0198858 + vertex 752.788 138.224 0.0587641 + endloop + endfacet + facet normal 0.00449315 -0.00910258 -0.999948 + outer loop + vertex 742.313 133.064 0.0586749 + vertex 750.295 141.272 0.0198148 + vertex 752.788 138.224 0.0587641 + endloop + endfacet + facet normal 0.00806041 -0.0163432 -0.999834 + outer loop + vertex 742.313 133.064 0.0586749 + vertex 752.788 138.224 0.0587641 + vertex 744.318 129.663 0.130429 + endloop + endfacet + facet normal 0.00448389 -0.00909358 -0.999949 + outer loop + vertex 739.857 136.127 0.0198002 + vertex 750.295 141.272 0.0198148 + vertex 742.313 133.064 0.0586749 + endloop + endfacet + facet normal 0.0043521 -0.00919924 -0.999948 + outer loop + vertex 731.782 128.098 0.0585199 + vertex 739.857 136.127 0.0198002 + vertex 742.313 133.064 0.0586749 + endloop + endfacet + facet normal 0.00783659 -0.0165896 -0.999832 + outer loop + vertex 731.782 128.098 0.0585199 + vertex 742.313 133.064 0.0586749 + vertex 733.749 124.685 0.130564 + endloop + endfacet + facet normal 0.00431602 -0.00916295 -0.999949 + outer loop + vertex 729.362 131.176 0.0198683 + vertex 739.857 136.127 0.0198002 + vertex 731.782 128.098 0.0585199 + endloop + endfacet + facet normal 0.00415072 -0.00929289 -0.999948 + outer loop + vertex 721.201 123.322 0.0589821 + vertex 729.362 131.176 0.0198683 + vertex 731.782 128.098 0.0585199 + endloop + endfacet + facet normal 0.00754574 -0.0168147 -0.99983 + outer loop + vertex 721.201 123.322 0.0589821 + vertex 731.782 128.098 0.0585199 + vertex 723.137 119.9 0.131147 + endloop + endfacet + facet normal 0.00420531 -0.00934961 -0.999947 + outer loop + vertex 718.82 126.415 0.0200535 + vertex 729.362 131.176 0.0198683 + vertex 721.201 123.322 0.0589821 + endloop + endfacet + facet normal 0.00405309 -0.00946674 -0.999947 + outer loop + vertex 710.542 118.713 0.0594118 + vertex 718.82 126.415 0.0200535 + vertex 721.201 123.322 0.0589821 + endloop + endfacet + facet normal 0.00729162 -0.0169565 -0.99983 + outer loop + vertex 710.542 118.713 0.0594118 + vertex 721.201 123.322 0.0589821 + vertex 712.447 115.283 0.131489 + endloop + endfacet + facet normal 0.0040552 -0.00946901 -0.999947 + outer loop + vertex 708.198 121.819 0.0204988 + vertex 718.82 126.415 0.0200535 + vertex 710.542 118.713 0.0594118 + endloop + endfacet + facet normal 0.00230945 -0.0051521 -0.999984 + outer loop + vertex 718.82 126.415 0.0200535 + vertex 726.552 133.896 -0.000633994 + vertex 729.362 131.176 0.0198683 + endloop + endfacet + facet normal 0.00238786 -0.00507107 -0.999984 + outer loop + vertex 726.552 133.896 -0.000633994 + vertex 737.004 138.828 -0.000685646 + vertex 729.362 131.176 0.0198683 + endloop + endfacet + facet normal 0.000912966 -0.00194533 -0.999998 + outer loop + vertex 726.552 133.896 -0.000633994 + vertex 733.856 141.16 -0.00809689 + vertex 737.004 138.828 -0.000685646 + endloop + endfacet + facet normal 0.000942116 -0.00190598 -0.999998 + outer loop + vertex 733.856 141.16 -0.00809689 + vertex 744.207 146.264 -0.00807369 + vertex 737.004 138.828 -0.000685646 + endloop + endfacet + facet normal 0.000929802 -0.00189405 -0.999998 + outer loop + vertex 737.004 138.828 -0.000685646 + vertex 744.207 146.264 -0.00807369 + vertex 747.403 143.955 -0.000727864 + endloop + endfacet + facet normal 0.00245644 -0.00499036 -0.999985 + outer loop + vertex 737.004 138.828 -0.000685646 + vertex 747.403 143.955 -0.000727864 + vertex 739.857 136.127 0.0198002 + endloop + endfacet + facet normal 0.000954428 -0.00185997 -0.999998 + outer loop + vertex 744.207 146.264 -0.00807369 + vertex 754.471 151.557 -0.00812153 + vertex 747.403 143.955 -0.000727864 + endloop + endfacet + facet normal 0.000968699 -0.00187324 -0.999998 + outer loop + vertex 747.403 143.955 -0.000727864 + vertex 754.471 151.557 -0.00812153 + vertex 757.708 149.268 -0.000698137 + endloop + endfacet + facet normal 0.00253944 -0.00491976 -0.999985 + outer loop + vertex 747.403 143.955 -0.000727864 + vertex 757.708 149.268 -0.000698137 + vertex 750.295 141.272 0.0198148 + endloop + endfacet + facet normal 0.000996761 -0.00183354 -0.999998 + outer loop + vertex 754.471 151.557 -0.00812153 + vertex 764.616 157.034 -0.00805099 + vertex 757.708 149.268 -0.000698137 + endloop + endfacet + facet normal 0.000974967 -0.00181415 -0.999998 + outer loop + vertex 757.708 149.268 -0.000698137 + vertex 764.616 157.034 -0.00805099 + vertex 767.903 154.771 -0.000740931 + endloop + endfacet + facet normal 0.00261424 -0.00485132 -0.999985 + outer loop + vertex 757.708 149.268 -0.000698137 + vertex 767.903 154.771 -0.000740931 + vertex 760.64 146.605 0.0198858 + endloop + endfacet + facet normal 0.000996303 -0.00178316 -0.999998 + outer loop + vertex 764.616 157.034 -0.00805099 + vertex 774.66 162.712 -0.00817003 + vertex 767.903 154.771 -0.000740931 + endloop + endfacet + facet normal 0.00103326 -0.0018146 -0.999998 + outer loop + vertex 767.903 154.771 -0.000740931 + vertex 774.66 162.712 -0.00817003 + vertex 777.98 160.468 -0.00066679 + endloop + endfacet + facet normal 0.0026666 -0.00470365 -0.999985 + outer loop + vertex 767.903 154.771 -0.000740931 + vertex 777.98 160.468 -0.00066679 + vertex 770.882 152.131 0.019621 + endloop + endfacet + facet normal 0.00105643 -0.00178032 -0.999998 + outer loop + vertex 774.66 162.712 -0.00817003 + vertex 784.579 168.587 -0.00814962 + vertex 777.98 160.468 -0.00066679 + endloop + endfacet + facet normal 0.00100409 -0.00173778 -0.999998 + outer loop + vertex 777.98 160.468 -0.00066679 + vertex 784.579 168.587 -0.00814962 + vertex 787.953 166.371 -0.000911935 + endloop + endfacet + facet normal 0.00269997 -0.00460272 -0.999986 + outer loop + vertex 777.98 160.468 -0.00066679 + vertex 787.953 166.371 -0.000911935 + vertex 781.004 157.851 0.0195446 + endloop + endfacet + facet normal 0.0010383 -0.00168568 -0.999998 + outer loop + vertex 784.579 168.587 -0.00814962 + vertex 794.334 174.66 -0.00825865 + vertex 787.953 166.371 -0.000911935 + endloop + endfacet + facet normal 0.00105105 -0.0016955 -0.999998 + outer loop + vertex 787.953 166.371 -0.000911935 + vertex 794.334 174.66 -0.00825865 + vertex 797.748 172.47 -0.00095758 + endloop + endfacet + facet normal 0.00283982 -0.00456828 -0.999986 + outer loop + vertex 787.953 166.371 -0.000911935 + vertex 797.748 172.47 -0.00095758 + vertex 791.006 163.771 0.0196355 + endloop + endfacet + facet normal 0.00107983 -0.00165065 -0.999998 + outer loop + vertex 794.334 174.66 -0.00825865 + vertex 803.816 180.952 -0.00840559 + vertex 797.748 172.47 -0.00095758 + endloop + endfacet + facet normal 0.00111324 -0.00167456 -0.999998 + outer loop + vertex 797.748 172.47 -0.00095758 + vertex 803.816 180.952 -0.00840559 + vertex 807.262 178.792 -0.000952294 + endloop + endfacet + facet normal 0.00295463 -0.00444577 -0.999986 + outer loop + vertex 797.748 172.47 -0.00095758 + vertex 807.262 178.792 -0.000952294 + vertex 800.838 169.894 0.0196239 + endloop + endfacet + facet normal 0.00115449 -0.00160875 -0.999998 + outer loop + vertex 803.816 180.952 -0.00840559 + vertex 812.911 187.518 -0.00846828 + vertex 807.262 178.792 -0.000952294 + endloop + endfacet + facet normal 0.00116126 -0.00161313 -0.999998 + outer loop + vertex 807.262 178.792 -0.000952294 + vertex 812.911 187.518 -0.00846828 + vertex 816.396 185.399 -0.00100384 + endloop + endfacet + facet normal 0.00302971 -0.00419607 -0.999987 + outer loop + vertex 807.262 178.792 -0.000952294 + vertex 816.396 185.399 -0.00100384 + vertex 810.406 176.25 0.0192392 + endloop + endfacet + facet normal 0.00120841 -0.00153556 -0.999998 + outer loop + vertex 812.911 187.518 -0.00846828 + vertex 821.552 194.348 -0.00851403 + vertex 816.396 185.399 -0.00100384 + endloop + endfacet + facet normal 0.00118026 -0.00151935 -0.999998 + outer loop + vertex 816.396 185.399 -0.00100384 + vertex 821.552 194.348 -0.00851403 + vertex 825.1 192.295 -0.00120832 + endloop + endfacet + facet normal 0.00321934 -0.00409302 -0.999986 + outer loop + vertex 816.396 185.399 -0.00100384 + vertex 825.1 192.295 -0.00120832 + vertex 819.58 182.905 0.0194565 + endloop + endfacet + facet normal 0.0012002 -0.00148487 -0.999998 + outer loop + vertex 821.552 194.348 -0.00851403 + vertex 829.7 201.207 -0.0089189 + vertex 825.1 192.295 -0.00120832 + endloop + endfacet + facet normal 0.00124131 -0.0015061 -0.999998 + outer loop + vertex 825.1 192.295 -0.00120832 + vertex 829.7 201.207 -0.0089189 + vertex 833.356 199.266 -0.00145851 + endloop + endfacet + facet normal 0.00333605 -0.0039871 -0.999986 + outer loop + vertex 825.1 192.295 -0.00120832 + vertex 833.356 199.266 -0.00145851 + vertex 828.37 189.88 0.0193315 + endloop + endfacet + facet normal 0.00124585 -0.00149754 -0.999998 + outer loop + vertex 829.7 201.207 -0.0089189 + vertex 837.164 207.57 -0.00914959 + vertex 833.356 199.266 -0.00145851 + endloop + endfacet + facet normal 0.00155451 -0.00163908 -0.999997 + outer loop + vertex 833.356 199.266 -0.00145851 + vertex 837.164 207.57 -0.00914959 + vertex 841.089 205.843 -0.000217352 + endloop + endfacet + facet normal 0.00352913 -0.00396083 -0.999986 + outer loop + vertex 833.356 199.266 -0.00145851 + vertex 841.089 205.843 -0.000217352 + vertex 836.778 196.942 0.0198234 + endloop + endfacet + facet normal 0.00158732 -0.00156448 -0.999998 + outer loop + vertex 837.164 207.57 -0.00914959 + vertex 843.831 213.355 -0.0076174 + vertex 841.089 205.843 -0.000217352 + endloop + endfacet + facet normal -2.03312e-05 -1.24077e-05 -1 + outer loop + vertex 829.7 201.207 -0.0089189 + vertex 833.347 209.123 -0.00909127 + vertex 837.164 207.57 -0.00914959 + endloop + endfacet + facet normal -3.25695e-05 -4.24699e-05 -1 + outer loop + vertex 833.347 209.123 -0.00909127 + vertex 839.401 213.762 -0.00948546 + vertex 837.164 207.57 -0.00914959 + endloop + endfacet + facet normal -9.03063e-05 1.98234e-05 -1 + outer loop + vertex 825.899 202.876 -0.00854254 + vertex 833.347 209.123 -0.00909127 + vertex 829.7 201.207 -0.0089189 + endloop + endfacet + facet normal -0.000509653 0.000519757 -1 + outer loop + vertex 825.899 202.876 -0.00854254 + vertex 829.411 210.609 -0.00631312 + vertex 833.347 209.123 -0.00909127 + endloop + endfacet + facet normal -0.000506568 0.00052793 -1 + outer loop + vertex 829.411 210.609 -0.00631312 + vertex 836.4 215.97 -0.00702368 + vertex 833.347 209.123 -0.00909127 + endloop + endfacet + facet normal -0.000467326 0.000500535 -1 + outer loop + vertex 821.943 204.243 -0.00600933 + vertex 829.411 210.609 -0.00631312 + vertex 825.899 202.876 -0.00854254 + endloop + endfacet + facet normal -0.000460876 0.000519206 -1 + outer loop + vertex 817.797 196.065 -0.00834489 + vertex 821.943 204.243 -0.00600933 + vertex 825.899 202.876 -0.00854254 + endloop + endfacet + facet normal -3.77691e-05 1.59097e-05 -1 + outer loop + vertex 817.797 196.065 -0.00834489 + vertex 825.899 202.876 -0.00854254 + vertex 821.552 194.348 -0.00851403 + endloop + endfacet + facet normal -0.000443547 0.000510422 -1 + outer loop + vertex 813.893 197.45 -0.0059063 + vertex 821.943 204.243 -0.00600933 + vertex 817.797 196.065 -0.00834489 + endloop + endfacet + facet normal -0.000433786 0.000537921 -1 + outer loop + vertex 809.194 189.273 -0.00826663 + vertex 813.893 197.45 -0.0059063 + vertex 817.797 196.065 -0.00834489 + endloop + endfacet + facet normal -3.73519e-05 3.5789e-05 -1 + outer loop + vertex 809.194 189.273 -0.00826663 + vertex 817.797 196.065 -0.00834489 + vertex 812.911 187.518 -0.00846828 + endloop + endfacet + facet normal -0.000440694 0.000541891 -1 + outer loop + vertex 805.334 190.698 -0.00579296 + vertex 813.893 197.45 -0.0059063 + vertex 809.194 189.273 -0.00826663 + endloop + endfacet + facet normal -0.000427572 0.000577442 -1 + outer loop + vertex 800.145 182.748 -0.00816535 + vertex 805.334 190.698 -0.00579296 + vertex 809.194 189.273 -0.00826663 + endloop + endfacet + facet normal -4.35118e-05 4.48224e-05 -1 + outer loop + vertex 800.145 182.748 -0.00816535 + vertex 809.194 189.273 -0.00826663 + vertex 803.816 180.952 -0.00840559 + endloop + endfacet + facet normal -0.00043067 0.000579464 -1 + outer loop + vertex 796.335 184.217 -0.00567342 + vertex 805.334 190.698 -0.00579296 + vertex 800.145 182.748 -0.00816535 + endloop + endfacet + facet normal -0.000418455 0.000611133 -1 + outer loop + vertex 790.708 176.49 -0.00804105 + vertex 796.335 184.217 -0.00567342 + vertex 800.145 182.748 -0.00816535 + endloop + endfacet + facet normal -3.97708e-05 4.01085e-05 -1 + outer loop + vertex 790.708 176.49 -0.00804105 + vertex 800.145 182.748 -0.00816535 + vertex 794.334 174.66 -0.00825865 + endloop + endfacet + facet normal -0.000411289 0.000605915 -1 + outer loop + vertex 786.962 177.997 -0.00558664 + vertex 796.335 184.217 -0.00567342 + vertex 790.708 176.49 -0.00804105 + endloop + endfacet + facet normal -0.000399476 0.000635263 -1 + outer loop + vertex 781.005 170.446 -0.00800429 + vertex 786.962 177.997 -0.00558664 + vertex 790.708 176.49 -0.00804105 + endloop + endfacet + facet normal -2.3882e-05 3.22595e-05 -1 + outer loop + vertex 781.005 170.446 -0.00800429 + vertex 790.708 176.49 -0.00804105 + vertex 784.579 168.587 -0.00814962 + endloop + endfacet + facet normal -0.000400441 0.000636024 -1 + outer loop + vertex 777.296 171.977 -0.00554519 + vertex 786.962 177.997 -0.00558664 + vertex 781.005 170.446 -0.00800429 + endloop + endfacet + facet normal -0.000393152 0.000653675 -1 + outer loop + vertex 771.124 164.593 -0.00794568 + vertex 777.296 171.977 -0.00554519 + vertex 781.005 170.446 -0.00800429 + endloop + endfacet + facet normal -3.62409e-05 5.11652e-05 -1 + outer loop + vertex 771.124 164.593 -0.00794568 + vertex 781.005 170.446 -0.00800429 + vertex 774.66 162.712 -0.00817003 + endloop + endfacet + facet normal -0.000385045 0.000646899 -1 + outer loop + vertex 767.463 166.148 -0.00552939 + vertex 777.296 171.977 -0.00554519 + vertex 771.124 164.593 -0.00794568 + endloop + endfacet + facet normal -0.000376217 0.000667673 -1 + outer loop + vertex 761.132 158.941 -0.00795956 + vertex 767.463 166.148 -0.00552939 + vertex 771.124 164.593 -0.00794568 + endloop + endfacet + facet normal -1.26492e-05 2.48229e-05 -1 + outer loop + vertex 761.132 158.941 -0.00795956 + vertex 771.124 164.593 -0.00794568 + vertex 764.616 157.034 -0.00805099 + endloop + endfacet + facet normal -0.000381359 0.000672191 -1 + outer loop + vertex 757.517 160.521 -0.00551909 + vertex 767.463 166.148 -0.00552939 + vertex 761.132 158.941 -0.00795956 + endloop + endfacet + facet normal -0.000374065 0.000688874 -1 + outer loop + vertex 751.029 153.487 -0.0079379 + vertex 757.517 160.521 -0.00551909 + vertex 761.132 158.941 -0.00795956 + endloop + endfacet + facet normal -2.72631e-05 4.65253e-05 -1 + outer loop + vertex 751.029 153.487 -0.0079379 + vertex 761.132 158.941 -0.00795956 + vertex 754.471 151.557 -0.00812153 + endloop + endfacet + facet normal -0.000369753 0.000684896 -1 + outer loop + vertex 747.465 155.093 -0.00551998 + vertex 757.517 160.521 -0.00551909 + vertex 751.029 153.487 -0.0079379 + endloop + endfacet + facet normal -0.000362825 0.000700269 -1 + outer loop + vertex 740.812 148.217 -0.00792091 + vertex 747.465 155.093 -0.00551998 + vertex 751.029 153.487 -0.0079379 + endloop + endfacet + facet normal -2.2149e-05 3.97217e-05 -1 + outer loop + vertex 740.812 148.217 -0.00792091 + vertex 751.029 153.487 -0.0079379 + vertex 744.207 146.264 -0.00807369 + endloop + endfacet + facet normal -0.000359401 0.000696956 -1 + outer loop + vertex 737.296 149.848 -0.00552084 + vertex 747.465 155.093 -0.00551998 + vertex 740.812 148.217 -0.00792091 + endloop + endfacet + facet normal -0.000319141 0.00059117 -1 + outer loop + vertex 747.465 155.093 -0.00551998 + vertex 753.834 161.827 -0.00357165 + vertex 757.517 160.521 -0.00551909 + endloop + endfacet + facet normal -0.000325029 0.000574557 -1 + outer loop + vertex 753.834 161.827 -0.00357165 + vertex 763.733 167.43 -0.00357027 + vertex 757.517 160.521 -0.00551909 + endloop + endfacet + facet normal -0.00019687 0.000348106 -1 + outer loop + vertex 753.834 161.827 -0.00357165 + vertex 759.946 168.492 -0.00245498 + vertex 763.733 167.43 -0.00357027 + endloop + endfacet + facet normal -0.000200024 0.000336862 -1 + outer loop + vertex 759.946 168.492 -0.00245498 + vertex 769.687 174.272 -0.00245615 + vertex 763.733 167.43 -0.00357027 + endloop + endfacet + facet normal -0.000200311 0.000337112 -1 + outer loop + vertex 763.733 167.43 -0.00357027 + vertex 769.687 174.272 -0.00245615 + vertex 773.522 173.235 -0.00357389 + endloop + endfacet + facet normal -0.000332777 0.000560457 -1 + outer loop + vertex 763.733 167.43 -0.00357027 + vertex 773.522 173.235 -0.00357389 + vertex 767.463 166.148 -0.00552939 + endloop + endfacet + facet normal -0.000203509 0.000325287 -1 + outer loop + vertex 769.687 174.272 -0.00245615 + vertex 779.254 180.24 -0.00246191 + vertex 773.522 173.235 -0.00357389 + endloop + endfacet + facet normal -0.000208236 0.000329155 -1 + outer loop + vertex 773.522 173.235 -0.00357389 + vertex 779.254 180.24 -0.00246191 + vertex 783.132 179.228 -0.0036026 + endloop + endfacet + facet normal -0.000341386 0.000542686 -1 + outer loop + vertex 773.522 173.235 -0.00357389 + vertex 783.132 179.228 -0.0036026 + vertex 777.296 171.977 -0.00554519 + endloop + endfacet + facet normal -0.000212046 0.000314558 -1 + outer loop + vertex 779.254 180.24 -0.00246191 + vertex 788.523 186.386 -0.00249408 + vertex 783.132 179.228 -0.0036026 + endloop + endfacet + facet normal -0.000216454 0.000317877 -1 + outer loop + vertex 783.132 179.228 -0.0036026 + vertex 788.523 186.386 -0.00249408 + vertex 792.457 185.412 -0.0036554 + endloop + endfacet + facet normal -0.000350827 0.000520514 -1 + outer loop + vertex 783.132 179.228 -0.0036026 + vertex 792.457 185.412 -0.0036554 + vertex 786.962 177.997 -0.00558664 + endloop + endfacet + facet normal -0.000221395 0.000297918 -1 + outer loop + vertex 788.523 186.386 -0.00249408 + vertex 797.401 192.759 -0.00256078 + vertex 792.457 185.412 -0.0036554 + endloop + endfacet + facet normal -0.000231703 0.000304853 -1 + outer loop + vertex 792.457 185.412 -0.0036554 + vertex 797.401 192.759 -0.00256078 + vertex 801.39 191.842 -0.00376489 + endloop + endfacet + facet normal -0.000368079 0.000494305 -1 + outer loop + vertex 792.457 185.412 -0.0036554 + vertex 801.39 191.842 -0.00376489 + vertex 796.335 184.217 -0.00567342 + endloop + endfacet + facet normal -0.000236727 0.000283004 -1 + outer loop + vertex 797.401 192.759 -0.00256078 + vertex 805.871 199.401 -0.00268637 + vertex 801.39 191.842 -0.00376489 + endloop + endfacet + facet normal -0.000239746 0.000284794 -1 + outer loop + vertex 801.39 191.842 -0.00376489 + vertex 805.871 199.401 -0.00268637 + vertex 809.905 198.543 -0.00389773 + endloop + endfacet + facet normal -0.000380011 0.000463012 -1 + outer loop + vertex 801.39 191.842 -0.00376489 + vertex 809.905 198.543 -0.00389773 + vertex 805.334 190.698 -0.00579296 + endloop + endfacet + facet normal -0.000243182 0.000268645 -1 + outer loop + vertex 805.871 199.401 -0.00268637 + vertex 813.92 206.13 -0.00283605 + vertex 809.905 198.543 -0.00389773 + endloop + endfacet + facet normal -0.000238278 0.000266049 -1 + outer loop + vertex 809.905 198.543 -0.00389773 + vertex 813.92 206.13 -0.00283605 + vertex 817.924 205.298 -0.0040115 + endloop + endfacet + facet normal -0.000383451 0.000438403 -1 + outer loop + vertex 809.905 198.543 -0.00389773 + vertex 817.924 205.298 -0.0040115 + vertex 813.893 197.45 -0.0059063 + endloop + endfacet + facet normal -0.000239254 0.000261346 -1 + outer loop + vertex 813.92 206.13 -0.00283605 + vertex 821.3 212.353 -0.00297538 + vertex 817.924 205.298 -0.0040115 + endloop + endfacet + facet normal -0.000245036 0.000264112 -1 + outer loop + vertex 817.924 205.298 -0.0040115 + vertex 821.3 212.353 -0.00297538 + vertex 825.214 211.564 -0.00414283 + endloop + endfacet + facet normal -0.000385074 0.00042703 -1 + outer loop + vertex 817.924 205.298 -0.0040115 + vertex 825.214 211.564 -0.00414283 + vertex 821.943 204.243 -0.00600933 + endloop + endfacet + facet normal -0.000243616 0.000271161 -1 + outer loop + vertex 821.3 212.353 -0.00297538 + vertex 827.19 217.023 -0.00314393 + vertex 825.214 211.564 -0.00414283 + endloop + endfacet + facet normal -0.000174492 0.000184544 -1 + outer loop + vertex 813.92 206.13 -0.00283605 + vertex 817.481 213.113 -0.0021688 + vertex 821.3 212.353 -0.00297538 + endloop + endfacet + facet normal -0.000173637 0.000188842 -1 + outer loop + vertex 817.481 213.113 -0.0021688 + vertex 824.4 218.43 -0.00236589 + vertex 821.3 212.353 -0.00297538 + endloop + endfacet + facet normal -0.000177968 0.000186317 -1 + outer loop + vertex 809.864 206.775 -0.00199416 + vertex 817.481 213.113 -0.0021688 + vertex 813.92 206.13 -0.00283605 + endloop + endfacet + facet normal -0.000163631 0.000169087 -1 + outer loop + vertex 809.864 206.775 -0.00199416 + vertex 813.441 213.667 -0.00141411 + vertex 817.481 213.113 -0.0021688 + endloop + endfacet + facet normal -0.000162906 0.00017438 -1 + outer loop + vertex 813.441 213.667 -0.00141411 + vertex 820.531 219.13 -0.00161633 + vertex 817.481 213.113 -0.0021688 + endloop + endfacet + facet normal -0.000156304 0.000165284 -1 + outer loop + vertex 805.702 207.272 -0.0012615 + vertex 813.441 213.667 -0.00141411 + vertex 809.864 206.775 -0.00199416 + endloop + endfacet + facet normal -0.000156059 0.000167341 -1 + outer loop + vertex 801.786 200.076 -0.00185451 + vertex 805.702 207.272 -0.0012615 + vertex 809.864 206.775 -0.00199416 + endloop + endfacet + facet normal -0.000172697 0.000187405 -1 + outer loop + vertex 801.786 200.076 -0.00185451 + vertex 809.864 206.775 -0.00199416 + vertex 805.871 199.401 -0.00268637 + endloop + endfacet + facet normal -0.000143583 0.000160551 -1 + outer loop + vertex 797.636 200.63 -0.00116962 + vertex 805.702 207.272 -0.0012615 + vertex 801.786 200.076 -0.00185451 + endloop + endfacet + facet normal -0.000142322 0.000169999 -1 + outer loop + vertex 793.36 193.507 -0.00177183 + vertex 797.636 200.63 -0.00116962 + vertex 801.786 200.076 -0.00185451 + endloop + endfacet + facet normal -0.00015966 0.000192242 -1 + outer loop + vertex 793.36 193.507 -0.00177183 + vertex 801.786 200.076 -0.00185451 + vertex 797.401 192.759 -0.00256078 + endloop + endfacet + facet normal -0.000130662 0.000162999 -1 + outer loop + vertex 789.241 194.144 -0.00112992 + vertex 797.636 200.63 -0.00116962 + vertex 793.36 193.507 -0.00177183 + endloop + endfacet + facet normal -0.000128806 0.000175011 -1 + outer loop + vertex 784.524 187.195 -0.00173861 + vertex 789.241 194.144 -0.00112992 + vertex 793.36 193.507 -0.00177183 + endloop + endfacet + facet normal -0.000148091 0.000202001 -1 + outer loop + vertex 784.524 187.195 -0.00173861 + vertex 793.36 193.507 -0.00177183 + vertex 788.523 186.386 -0.00249408 + endloop + endfacet + facet normal -0.000124327 0.000171971 -1 + outer loop + vertex 780.448 187.88 -0.00111392 + vertex 789.241 194.144 -0.00112992 + vertex 784.524 187.195 -0.00173861 + endloop + endfacet + facet normal -0.000122491 0.000182892 -1 + outer loop + vertex 775.3 181.083 -0.00172639 + vertex 780.448 187.88 -0.00111392 + vertex 784.524 187.195 -0.00173861 + endloop + endfacet + facet normal -0.000141037 0.000210886 -1 + outer loop + vertex 775.3 181.083 -0.00172639 + vertex 784.524 187.195 -0.00173861 + vertex 779.254 180.24 -0.00246191 + endloop + endfacet + facet normal -0.00012013 0.000181104 -1 + outer loop + vertex 771.253 181.8 -0.00111047 + vertex 780.448 187.88 -0.00111392 + vertex 775.3 181.083 -0.00172639 + endloop + endfacet + facet normal -0.000118624 0.000189611 -1 + outer loop + vertex 765.781 175.143 -0.00172352 + vertex 771.253 181.8 -0.00111047 + vertex 775.3 181.083 -0.00172639 + endloop + endfacet + facet normal -0.000138267 0.000221088 -1 + outer loop + vertex 765.781 175.143 -0.00172352 + vertex 775.3 181.083 -0.00172639 + vertex 769.687 174.272 -0.00245615 + endloop + endfacet + facet normal -0.000118364 0.000189397 -1 + outer loop + vertex 761.78 175.888 -0.00110891 + vertex 771.253 181.8 -0.00111047 + vertex 765.781 175.143 -0.00172352 + endloop + endfacet + facet normal -9.84694e-05 0.000148347 -1 + outer loop + vertex 771.253 181.8 -0.00111047 + vertex 776.264 188.473 -0.000613979 + vertex 780.448 187.88 -0.00111392 + endloop + endfacet + facet normal -9.96571e-05 0.000139967 -1 + outer loop + vertex 776.264 188.473 -0.000613979 + vertex 785.057 194.706 -0.0006179 + vertex 780.448 187.88 -0.00111392 + endloop + endfacet + facet normal -6.74531e-05 9.45334e-05 -1 + outer loop + vertex 776.264 188.473 -0.000613979 + vertex 780.806 195.21 -0.000283479 + vertex 785.057 194.706 -0.0006179 + endloop + endfacet + facet normal -6.81732e-05 8.84638e-05 -1 + outer loop + vertex 780.806 195.21 -0.000283479 + vertex 789.182 201.609 -0.000288437 + vertex 785.057 194.706 -0.0006179 + endloop + endfacet + facet normal -7.14701e-05 9.04339e-05 -1 + outer loop + vertex 785.057 194.706 -0.0006179 + vertex 789.182 201.609 -0.000288437 + vertex 793.422 201.13 -0.00063469 + endloop + endfacet + facet normal -0.000104472 0.000133399 -1 + outer loop + vertex 785.057 194.706 -0.0006179 + vertex 793.422 201.13 -0.00063469 + vertex 789.241 194.144 -0.00112992 + endloop + endfacet + facet normal -7.19773e-05 8.59399e-05 -1 + outer loop + vertex 789.182 201.609 -0.000288437 + vertex 797.125 208.094 -0.000302773 + vertex 793.422 201.13 -0.00063469 + endloop + endfacet + facet normal -7.88673e-05 8.96037e-05 -1 + outer loop + vertex 793.422 201.13 -0.00063469 + vertex 797.125 208.094 -0.000302773 + vertex 801.435 207.694 -0.000678508 + endloop + endfacet + facet normal -0.000111551 0.000129503 -1 + outer loop + vertex 793.422 201.13 -0.00063469 + vertex 801.435 207.694 -0.000678508 + vertex 797.636 200.63 -0.00116962 + endloop + endfacet + facet normal -7.89772e-05 8.84182e-05 -1 + outer loop + vertex 797.125 208.094 -0.000302773 + vertex 804.717 214.493 -0.000336606 + vertex 801.435 207.694 -0.000678508 + endloop + endfacet + facet normal -8.88939e-05 9.32055e-05 -1 + outer loop + vertex 801.435 207.694 -0.000678508 + vertex 804.717 214.493 -0.000336606 + vertex 809.222 214.162 -0.000767866 + endloop + endfacet + facet normal -0.000123272 0.000134594 -1 + outer loop + vertex 801.435 207.694 -0.000678508 + vertex 809.222 214.162 -0.000767866 + vertex 805.702 207.272 -0.0012615 + endloop + endfacet + facet normal -8.85329e-05 9.81259e-05 -1 + outer loop + vertex 804.717 214.493 -0.000336606 + vertex 812.408 220.913 -0.00038754 + vertex 809.222 214.162 -0.000767866 + endloop + endfacet + facet normal -4.48546e-05 4.7932e-05 -1 + outer loop + vertex 797.125 208.094 -0.000302773 + vertex 800.189 214.709 -0.000123137 + vertex 804.717 214.493 -0.000336606 + endloop + endfacet + facet normal -4.47764e-05 4.95696e-05 -1 + outer loop + vertex 800.189 214.709 -0.000123137 + vertex 806.828 220.416 -0.00013754 + vertex 804.717 214.493 -0.000336606 + endloop + endfacet + facet normal -4.02064e-05 4.57791e-05 -1 + outer loop + vertex 792.864 208.492 -0.000113233 + vertex 800.189 214.709 -0.000123137 + vertex 797.125 208.094 -0.000302773 + endloop + endfacet + facet normal -1.8702e-05 2.0442e-05 -1 + outer loop + vertex 792.864 208.492 -0.000113233 + vertex 795.902 214.962 -3.77973e-05 + vertex 800.189 214.709 -0.000123137 + endloop + endfacet + facet normal -1.86905e-05 2.06361e-05 -1 + outer loop + vertex 795.902 214.962 -3.77973e-05 + vertex 802.258 220.51 -4.20859e-05 + vertex 800.189 214.709 -0.000123137 + endloop + endfacet + facet normal -1.70463e-05 1.96645e-05 -1 + outer loop + vertex 788.675 208.82 -3.53756e-05 + vertex 795.902 214.962 -3.77973e-05 + vertex 792.864 208.492 -0.000113233 + endloop + endfacet + facet normal -1.69993e-05 2.02645e-05 -1 + outer loop + vertex 784.945 202.047 -0.00010922 + vertex 788.675 208.82 -3.53756e-05 + vertex 792.864 208.492 -0.000113233 + endloop + endfacet + facet normal -3.75812e-05 4.55535e-05 -1 + outer loop + vertex 784.945 202.047 -0.00010922 + vertex 792.864 208.492 -0.000113233 + vertex 789.182 201.609 -0.000288437 + endloop + endfacet + facet normal -1.60589e-05 1.97466e-05 -1 + outer loop + vertex 780.725 202.397 -3.45484e-05 + vertex 788.675 208.82 -3.53756e-05 + vertex 784.945 202.047 -0.00010922 + endloop + endfacet + facet normal -6.70842e-06 7.49968e-06 -1 + outer loop + vertex 788.675 208.82 -3.53756e-05 + vertex 791.74 215.007 -9.53741e-06 + vertex 795.902 214.962 -3.77973e-05 + endloop + endfacet + facet normal -6.71041e-06 7.31779e-06 -1 + outer loop + vertex 791.74 215.007 -9.53741e-06 + vertex 797.807 220.439 -1.04959e-05 + vertex 795.902 214.962 -3.77973e-05 + endloop + endfacet + facet normal -6.04044e-06 7.16876e-06 -1 + outer loop + vertex 784.535 209.028 -8.87879e-06 + vertex 791.74 215.007 -9.53741e-06 + vertex 788.675 208.82 -3.53756e-05 + endloop + endfacet + facet normal -4.01014e-05 4.69015e-05 -1 + outer loop + vertex 789.182 201.609 -0.000288437 + vertex 792.864 208.492 -0.000113233 + vertex 797.125 208.094 -0.000302773 + endloop + endfacet + facet normal -3.73202e-05 4.80772e-05 -1 + outer loop + vertex 780.806 195.21 -0.000283479 + vertex 784.945 202.047 -0.00010922 + vertex 789.182 201.609 -0.000288437 + endloop + endfacet + facet normal -3.62559e-05 4.7433e-05 -1 + outer loop + vertex 776.538 195.647 -0.00010798 + vertex 784.945 202.047 -0.00010922 + vertex 780.806 195.21 -0.000283479 + endloop + endfacet + facet normal -6.68225e-05 9.41083e-05 -1 + outer loop + vertex 772.014 188.987 -0.000281573 + vertex 780.806 195.21 -0.000283479 + vertex 776.264 188.473 -0.000613979 + endloop + endfacet + facet normal -9.80816e-05 0.000148055 -1 + outer loop + vertex 767.101 182.416 -0.000611942 + vertex 776.264 188.473 -0.000613979 + vertex 771.253 181.8 -0.00111047 + endloop + endfacet + facet normal -0.000103262 0.000142401 -1 + outer loop + vertex 780.448 187.88 -0.00111392 + vertex 785.057 194.706 -0.0006179 + vertex 789.241 194.144 -0.00112992 + endloop + endfacet + facet normal -0.000110649 0.000137095 -1 + outer loop + vertex 789.241 194.144 -0.00112992 + vertex 793.422 201.13 -0.00063469 + vertex 797.636 200.63 -0.00116962 + endloop + endfacet + facet normal -0.000123158 0.000135745 -1 + outer loop + vertex 797.636 200.63 -0.00116962 + vertex 801.435 207.694 -0.000678508 + vertex 805.702 207.272 -0.0012615 + endloop + endfacet + facet normal -0.000136544 0.000141372 -1 + outer loop + vertex 805.702 207.272 -0.0012615 + vertex 809.222 214.162 -0.000767866 + vertex 813.441 213.667 -0.00141411 + endloop + endfacet + facet normal -0.000135675 0.000148771 -1 + outer loop + vertex 809.222 214.162 -0.000767866 + vertex 816.599 219.802 -0.000929789 + vertex 813.441 213.667 -0.00141411 + endloop + endfacet + facet normal -0.000177391 0.000189947 -1 + outer loop + vertex 805.871 199.401 -0.00268637 + vertex 809.864 206.775 -0.00199416 + vertex 813.92 206.13 -0.00283605 + endloop + endfacet + facet normal -0.000170796 0.000198918 -1 + outer loop + vertex 797.401 192.759 -0.00256078 + vertex 801.786 200.076 -0.00185451 + vertex 805.871 199.401 -0.00268637 + endloop + endfacet + facet normal -0.000156763 0.000207892 -1 + outer loop + vertex 788.523 186.386 -0.00249408 + vertex 793.36 193.507 -0.00177183 + vertex 797.401 192.759 -0.00256078 + endloop + endfacet + facet normal -0.000145595 0.000214341 -1 + outer loop + vertex 779.254 180.24 -0.00246191 + vertex 784.524 187.195 -0.00173861 + vertex 788.523 186.386 -0.00249408 + endloop + endfacet + facet normal -0.000138771 0.000221504 -1 + outer loop + vertex 769.687 174.272 -0.00245615 + vertex 775.3 181.083 -0.00172639 + vertex 779.254 180.24 -0.00246191 + endloop + endfacet + facet normal -0.00013637 0.000229597 -1 + outer loop + vertex 759.946 168.492 -0.00245498 + vertex 765.781 175.143 -0.00172352 + vertex 769.687 174.272 -0.00245615 + endloop + endfacet + facet normal -0.000136859 0.000230026 -1 + outer loop + vertex 756.094 169.39 -0.00172108 + vertex 765.781 175.143 -0.00172352 + vertex 759.946 168.492 -0.00245498 + endloop + endfacet + facet normal -0.000197412 0.000348603 -1 + outer loop + vertex 750.098 162.916 -0.00245439 + vertex 759.946 168.492 -0.00245498 + vertex 753.834 161.827 -0.00357165 + endloop + endfacet + facet normal -0.000320034 0.000592015 -1 + outer loop + vertex 743.83 156.424 -0.00356871 + vertex 753.834 161.827 -0.00357165 + vertex 747.465 155.093 -0.00551998 + endloop + endfacet + facet normal -0.000327248 0.000576554 -1 + outer loop + vertex 757.517 160.521 -0.00551909 + vertex 763.733 167.43 -0.00357027 + vertex 767.463 166.148 -0.00552939 + endloop + endfacet + facet normal -0.000334866 0.000562243 -1 + outer loop + vertex 767.463 166.148 -0.00552939 + vertex 773.522 173.235 -0.00357389 + vertex 777.296 171.977 -0.00554519 + endloop + endfacet + facet normal -0.000343228 0.000544168 -1 + outer loop + vertex 777.296 171.977 -0.00554519 + vertex 783.132 179.228 -0.0036026 + vertex 786.962 177.997 -0.00558664 + endloop + endfacet + facet normal -0.000358299 0.000526053 -1 + outer loop + vertex 786.962 177.997 -0.00558664 + vertex 792.457 185.412 -0.0036554 + vertex 796.335 184.217 -0.00567342 + endloop + endfacet + facet normal -0.000370474 0.000495893 -1 + outer loop + vertex 796.335 184.217 -0.00567342 + vertex 801.39 191.842 -0.00376489 + vertex 805.334 190.698 -0.00579296 + endloop + endfacet + facet normal -0.000377164 0.000461353 -1 + outer loop + vertex 805.334 190.698 -0.00579296 + vertex 809.905 198.543 -0.00389773 + vertex 813.893 197.45 -0.0059063 + endloop + endfacet + facet normal -0.00038225 0.000437787 -1 + outer loop + vertex 813.893 197.45 -0.0059063 + vertex 817.924 205.298 -0.0040115 + vertex 821.943 204.243 -0.00600933 + endloop + endfacet + facet normal -0.000416729 0.000441176 -1 + outer loop + vertex 821.943 204.243 -0.00600933 + vertex 825.214 211.564 -0.00414283 + vertex 829.411 210.609 -0.00631312 + endloop + endfacet + facet normal -0.00041816 0.000434886 -1 + outer loop + vertex 825.214 211.564 -0.00414283 + vertex 831.683 217.196 -0.00439846 + vertex 829.411 210.609 -0.00631312 + endloop + endfacet + facet normal -8.20986e-05 3.85064e-05 -1 + outer loop + vertex 821.552 194.348 -0.00851403 + vertex 825.899 202.876 -0.00854254 + vertex 829.7 201.207 -0.0089189 + endloop + endfacet + facet normal -3.04754e-05 3.18579e-05 -1 + outer loop + vertex 812.911 187.518 -0.00846828 + vertex 817.797 196.065 -0.00834489 + vertex 821.552 194.348 -0.00851403 + endloop + endfacet + facet normal -3.55235e-05 3.96593e-05 -1 + outer loop + vertex 803.816 180.952 -0.00840559 + vertex 809.194 189.273 -0.00826663 + vertex 812.911 187.518 -0.00846828 + endloop + endfacet + facet normal -4.42451e-05 4.3323e-05 -1 + outer loop + vertex 794.334 174.66 -0.00825865 + vertex 800.145 182.748 -0.00816535 + vertex 803.816 180.952 -0.00840559 + endloop + endfacet + facet normal -3.81488e-05 4.33241e-05 -1 + outer loop + vertex 784.579 168.587 -0.00814962 + vertex 790.708 176.49 -0.00804105 + vertex 794.334 174.66 -0.00825865 + endloop + endfacet + facet normal -2.06865e-05 3.84032e-05 -1 + outer loop + vertex 774.66 162.712 -0.00817003 + vertex 781.005 170.446 -0.00800429 + vertex 784.579 168.587 -0.00814962 + endloop + endfacet + facet normal -3.84412e-05 4.70283e-05 -1 + outer loop + vertex 764.616 157.034 -0.00805099 + vertex 771.124 164.593 -0.00794568 + vertex 774.66 162.712 -0.00817003 + endloop + endfacet + facet normal -9.52695e-06 3.05269e-05 -1 + outer loop + vertex 754.471 151.557 -0.00812153 + vertex 761.132 158.941 -0.00795956 + vertex 764.616 157.034 -0.00805099 + endloop + endfacet + facet normal -2.79863e-05 4.52354e-05 -1 + outer loop + vertex 744.207 146.264 -0.00807369 + vertex 751.029 153.487 -0.0079379 + vertex 754.471 151.557 -0.00812153 + endloop + endfacet + facet normal -1.95634e-05 4.42173e-05 -1 + outer loop + vertex 733.856 141.16 -0.00809689 + vertex 740.812 148.217 -0.00792091 + vertex 744.207 146.264 -0.00807369 + endloop + endfacet + facet normal -2.65895e-05 5.11421e-05 -1 + outer loop + vertex 730.509 143.136 -0.00790684 + vertex 740.812 148.217 -0.00792091 + vertex 733.856 141.16 -0.00809689 + endloop + endfacet + facet normal 0.000900651 -0.00193294 -0.999998 + outer loop + vertex 723.446 136.247 -0.00797592 + vertex 733.856 141.16 -0.00809689 + vertex 726.552 133.896 -0.000633994 + endloop + endfacet + facet normal 0.00228914 -0.00513111 -0.999984 + outer loop + vertex 716.047 129.15 -0.000327041 + vertex 726.552 133.896 -0.000633994 + vertex 718.82 126.415 0.0200535 + endloop + endfacet + facet normal 0.00238383 -0.00506705 -0.999984 + outer loop + vertex 729.362 131.176 0.0198683 + vertex 737.004 138.828 -0.000685646 + vertex 739.857 136.127 0.0198002 + endloop + endfacet + facet normal 0.00246569 -0.00499928 -0.999984 + outer loop + vertex 739.857 136.127 0.0198002 + vertex 747.403 143.955 -0.000727864 + vertex 750.295 141.272 0.0198148 + endloop + endfacet + facet normal 0.0025463 -0.00492612 -0.999985 + outer loop + vertex 750.295 141.272 0.0198148 + vertex 757.708 149.268 -0.000698137 + vertex 760.64 146.605 0.0198858 + endloop + endfacet + facet normal 0.00257033 -0.00481227 -0.999985 + outer loop + vertex 760.64 146.605 0.0198858 + vertex 767.903 154.771 -0.000740931 + vertex 770.882 152.131 0.019621 + endloop + endfacet + facet normal 0.00263551 -0.00467718 -0.999986 + outer loop + vertex 770.882 152.131 0.019621 + vertex 777.98 160.468 -0.00066679 + vertex 781.004 157.851 0.0195446 + endloop + endfacet + facet normal 0.0027652 -0.00465591 -0.999985 + outer loop + vertex 781.004 157.851 0.0195446 + vertex 787.953 166.371 -0.000911935 + vertex 791.006 163.771 0.0196355 + endloop + endfacet + facet normal 0.0028475 -0.00457424 -0.999985 + outer loop + vertex 791.006 163.771 0.0196355 + vertex 797.748 172.47 -0.00095758 + vertex 800.838 169.894 0.0196239 + endloop + endfacet + facet normal 0.00287455 -0.00438795 -0.999986 + outer loop + vertex 800.838 169.894 0.0196239 + vertex 807.262 178.792 -0.000952294 + vertex 810.406 176.25 0.0192392 + endloop + endfacet + facet normal 0.00310168 -0.00424319 -0.999986 + outer loop + vertex 810.406 176.25 0.0192392 + vertex 816.396 185.399 -0.00100384 + vertex 819.58 182.905 0.0194565 + endloop + endfacet + facet normal 0.00324617 -0.00410879 -0.999986 + outer loop + vertex 819.58 182.905 0.0194565 + vertex 825.1 192.295 -0.00120832 + vertex 828.37 189.88 0.0193315 + endloop + endfacet + facet normal 0.00346482 -0.0040555 -0.999986 + outer loop + vertex 828.37 189.88 0.0193315 + vertex 833.356 199.266 -0.00145851 + vertex 836.778 196.942 0.0198234 + endloop + endfacet + facet normal 0.00375602 -0.00407072 -0.999985 + outer loop + vertex 836.778 196.942 0.0198234 + vertex 841.089 205.843 -0.000217352 + vertex 844.679 203.482 0.0228792 + endloop + endfacet + facet normal 0.00377864 -0.00403633 -0.999985 + outer loop + vertex 841.089 205.843 -0.000217352 + vertex 848.24 211.462 0.00412448 + vertex 844.679 203.482 0.0228792 + endloop + endfacet + facet normal 0.0111297 -0.013531 -0.999847 + outer loop + vertex 833.679 183.852 0.131628 + vertex 839.749 194.141 0.0599522 + vertex 842.25 190.984 0.130505 + endloop + endfacet + facet normal 0.0112741 -0.0142234 -0.999835 + outer loop + vertex 824.693 176.77 0.131053 + vertex 831.258 187.065 0.0586196 + vertex 833.679 183.852 0.131628 + endloop + endfacet + facet normal 0.0106649 -0.0147134 -0.999835 + outer loop + vertex 815.374 170.019 0.130998 + vertex 822.367 180.024 0.0583567 + vertex 824.693 176.77 0.131053 + endloop + endfacet + facet normal 0.00997783 -0.0150379 -0.999837 + outer loop + vertex 805.725 163.605 0.131171 + vertex 813.11 173.316 0.0588142 + vertex 815.374 170.019 0.130998 + endloop + endfacet + facet normal 0.00962234 -0.0154104 -0.999835 + outer loop + vertex 795.821 157.445 0.130794 + vertex 803.517 166.932 0.0586434 + vertex 805.725 163.605 0.131171 + endloop + endfacet + facet normal 0.00921474 -0.0156039 -0.999836 + outer loop + vertex 785.743 151.494 0.130784 + vertex 793.648 160.789 0.0585834 + vertex 795.821 157.445 0.130794 + endloop + endfacet + facet normal 0.008893 -0.0158105 -0.999835 + outer loop + vertex 775.548 145.746 0.131002 + vertex 783.603 154.85 0.0586951 + vertex 785.743 151.494 0.130784 + endloop + endfacet + facet normal 0.00867977 -0.0161332 -0.999832 + outer loop + vertex 765.246 140.197 0.131109 + vertex 773.449 149.114 0.0584288 + vertex 775.548 145.746 0.131002 + endloop + endfacet + facet normal 0.00848054 -0.0163509 -0.99983 + outer loop + vertex 754.83 134.836 0.130438 + vertex 763.18 143.576 0.0583224 + vertex 765.246 140.197 0.131109 + endloop + endfacet + facet normal 0.00802778 -0.0163109 -0.999835 + outer loop + vertex 744.318 129.663 0.130429 + vertex 752.788 138.224 0.0587641 + vertex 754.83 134.836 0.130438 + endloop + endfacet + facet normal 0.00776558 -0.016517 -0.999833 + outer loop + vertex 733.749 124.685 0.130564 + vertex 742.313 133.064 0.0586749 + vertex 744.318 129.663 0.130429 + endloop + endfacet + facet normal 0.00751046 -0.0167775 -0.999831 + outer loop + vertex 723.137 119.9 0.131147 + vertex 731.782 128.098 0.0585199 + vertex 733.749 124.685 0.130564 + endloop + endfacet + facet normal 0.00729284 -0.0169578 -0.99983 + outer loop + vertex 712.447 115.283 0.131489 + vertex 721.201 123.322 0.0589821 + vertex 723.137 119.9 0.131147 + endloop + endfacet + facet normal 0.00703599 -0.0170984 -0.999829 + outer loop + vertex 701.632 110.804 0.13197 + vertex 710.542 118.713 0.0594118 + vertex 712.447 115.283 0.131489 + endloop + endfacet + facet normal 0.00704045 -0.0171034 -0.999829 + outer loop + vertex 699.759 114.244 0.0599441 + vertex 710.542 118.713 0.0594118 + vertex 701.632 110.804 0.13197 + endloop + endfacet + facet normal 0.00674389 -0.0173428 -0.999827 + outer loop + vertex 677.897 105.729 0.0582448 + vertex 688.854 109.908 0.0596692 + vertex 679.673 102.256 0.130465 + endloop + endfacet + facet normal 0.00681874 -0.0172241 -0.999828 + outer loop + vertex 690.684 106.454 0.132237 + vertex 699.759 114.244 0.0599441 + vertex 701.632 110.804 0.13197 + endloop + endfacet + facet normal 0.00380276 -0.00957153 -0.999947 + outer loop + vertex 686.588 113.04 0.0210654 + vertex 697.452 117.362 0.0210174 + vertex 688.854 109.908 0.0596692 + endloop + endfacet + facet normal 0.00391855 -0.00957217 -0.999947 + outer loop + vertex 699.759 114.244 0.0599441 + vertex 708.198 121.819 0.0204988 + vertex 710.542 118.713 0.0594118 + endloop + endfacet + facet normal 0.00214689 -0.00529128 -0.999984 + outer loop + vertex 694.76 120.128 0.000599471 + vertex 705.465 124.57 8.06235e-05 + vertex 697.452 117.362 0.0210174 + endloop + endfacet + facet normal 0.00221207 -0.00520928 -0.999984 + outer loop + vertex 708.198 121.819 0.0204988 + vertex 716.047 129.15 -0.000327041 + vertex 718.82 126.415 0.0200535 + endloop + endfacet + facet normal 0.00084708 -0.0020525 -0.999998 + outer loop + vertex 702.449 126.958 -0.00737613 + vertex 712.99 131.522 -0.00781437 + vertex 705.465 124.57 8.06235e-05 + endloop + endfacet + facet normal 0.000865253 -0.00197969 -0.999998 + outer loop + vertex 716.047 129.15 -0.000327041 + vertex 723.446 136.247 -0.00797592 + vertex 726.552 133.896 -0.000633994 + endloop + endfacet + facet normal -1.53656e-05 1.08913e-05 -1 + outer loop + vertex 709.743 133.543 -0.00774247 + vertex 720.149 138.245 -0.00785114 + vertex 712.99 131.522 -0.00781437 + endloop + endfacet + facet normal -3.16843e-05 4.25129e-05 -1 + outer loop + vertex 723.446 136.247 -0.00797592 + vertex 730.509 143.136 -0.00790684 + vertex 733.856 141.16 -0.00809689 + endloop + endfacet + facet normal -0.000344778 0.000722218 -1 + outer loop + vertex 716.735 139.924 -0.00546217 + vertex 727.044 144.791 -0.0055014 + vertex 720.149 138.245 -0.00785114 + endloop + endfacet + facet normal -0.000352471 0.000711897 -1 + outer loop + vertex 730.509 143.136 -0.00790684 + vertex 737.296 149.848 -0.00552084 + vertex 740.812 148.217 -0.00792091 + endloop + endfacet + facet normal -0.000307432 0.00062137 -1 + outer loop + vertex 723.511 146.172 -0.00355685 + vertex 733.715 151.206 -0.00356595 + vertex 727.044 144.791 -0.0055014 + endloop + endfacet + facet normal -0.000313905 0.00060875 -1 + outer loop + vertex 737.296 149.848 -0.00552084 + vertex 743.83 156.424 -0.00356871 + vertex 747.465 155.093 -0.00551998 + endloop + endfacet + facet normal -0.00019064 0.000369044 -1 + outer loop + vertex 730.08 152.348 -0.00245175 + vertex 740.143 157.54 -0.00245397 + vertex 733.715 151.206 -0.00356595 + endloop + endfacet + facet normal -0.000194312 0.000359235 -1 + outer loop + vertex 743.83 156.424 -0.00356871 + vertex 750.098 162.916 -0.00245439 + vertex 753.834 161.827 -0.00357165 + endloop + endfacet + facet normal -0.000132935 0.00024631 -1 + outer loop + vertex 736.396 158.495 -0.00172055 + vertex 746.299 163.844 -0.00171955 + vertex 740.143 157.54 -0.00245397 + endloop + endfacet + facet normal -0.00013494 0.000238253 -1 + outer loop + vertex 750.098 162.916 -0.00245439 + vertex 756.094 169.39 -0.00172108 + vertex 759.946 168.492 -0.00245498 + endloop + endfacet + facet normal -0.000114737 0.000202545 -1 + outer loop + vertex 742.403 164.652 -0.00110884 + vertex 752.145 170.168 -0.00110937 + vertex 746.299 163.844 -0.00171955 + endloop + endfacet + facet normal -0.000117019 0.000196619 -1 + outer loop + vertex 756.094 169.39 -0.00172108 + vertex 761.78 175.888 -0.00110891 + vertex 765.781 175.143 -0.00172352 + endloop + endfacet + facet normal -9.60147e-05 0.000161388 -1 + outer loop + vertex 748.102 170.85 -0.000611067 + vertex 757.676 176.537 -0.000612583 + vertex 752.145 170.168 -0.00110937 + endloop + endfacet + facet normal -9.7021e-05 0.000155198 -1 + outer loop + vertex 761.78 175.888 -0.00110891 + vertex 767.101 182.416 -0.000611942 + vertex 771.253 181.8 -0.00111047 + endloop + endfacet + facet normal -6.53198e-05 0.000104509 -1 + outer loop + vertex 753.514 177.107 -0.000281166 + vertex 762.88 182.953 -0.000281908 + vertex 757.676 176.537 -0.000612583 + endloop + endfacet + facet normal -6.61424e-05 9.97333e-05 -1 + outer loop + vertex 767.101 182.416 -0.000611942 + vertex 772.014 188.987 -0.000281573 + vertex 776.264 188.473 -0.000613979 + endloop + endfacet + facet normal -3.53163e-05 5.34001e-05 -1 + outer loop + vertex 758.66 183.425 -0.000107739 + vertex 767.748 189.433 -0.00010784 + vertex 762.88 182.953 -0.000281908 + endloop + endfacet + facet normal -3.59438e-05 5.04793e-05 -1 + outer loop + vertex 772.014 188.987 -0.000281573 + vertex 776.538 195.647 -0.00010798 + vertex 780.806 195.21 -0.000283479 + endloop + endfacet + facet normal -1.56044e-05 2.19954e-05 -1 + outer loop + vertex 763.539 189.815 -3.37483e-05 + vertex 772.3 196.008 -3.42444e-05 + vertex 767.748 189.433 -0.00010784 + endloop + endfacet + facet normal -1.59726e-05 2.07882e-05 -1 + outer loop + vertex 776.538 195.647 -0.00010798 + vertex 780.725 202.397 -3.45484e-05 + vertex 784.945 202.047 -0.00010922 + endloop + endfacet + facet normal -5.56225e-06 7.3681e-06 -1 + outer loop + vertex 768.116 196.295 -8.85605e-06 + vertex 776.534 202.645 -8.89437e-06 + vertex 772.3 196.008 -3.42444e-05 + endloop + endfacet + facet normal -6.03201e-06 7.33676e-06 -1 + outer loop + vertex 780.725 202.397 -3.45484e-05 + vertex 784.535 209.028 -8.87879e-06 + vertex 788.675 208.82 -3.53756e-05 + endloop + endfacet + facet normal -1.56417e-06 1.98208e-06 -1 + outer loop + vertex 772.346 202.813 -2.00971e-06 + vertex 780.367 209.151 -1.99251e-06 + vertex 776.534 202.645 -8.89437e-06 + endloop + endfacet + facet normal -1.82905e-06 2.09391e-06 -1 + outer loop + vertex 784.535 209.028 -8.87879e-06 + vertex 787.774 215.083 -2.12514e-06 + vertex 791.74 215.007 -9.53741e-06 + endloop + endfacet + facet normal -1.8264e-06 2.23284e-06 -1 + outer loop + vertex 787.774 215.083 -2.12514e-06 + vertex 793.571 219.569 -2.69649e-06 + vertex 791.74 215.007 -9.53741e-06 + endloop + endfacet + facet normal -3.80932e-07 4.66052e-07 -1 + outer loop + vertex 776.227 209.238 -3.7522e-07 + vertex 783.798 215.375 -3.98937e-07 + vertex 780.367 209.151 -1.99251e-06 + endloop + endfacet + facet normal -9.99692e-08 1.13098e-07 -1 + outer loop + vertex 779.909 215.465 9.62153e-15 + vertex 787.3 221.998 9.62153e-15 + vertex 783.798 215.375 -3.98937e-07 + endloop + endfacet + facet normal -4.48939e-07 4.69733e-07 -1 + outer loop + vertex 797.628 224.631 -2.27459e-06 + vertex 793.684 225.068 -2.98064e-07 + vertex 798.589 229.304 -5.1098e-07 + endloop + endfacet + facet normal -5.57056e-07 5.92501e-07 -1 + outer loop + vertex 787.774 215.083 -2.12514e-06 + vertex 790.848 220.565 -5.89566e-07 + vertex 793.571 219.569 -2.69649e-06 + endloop + endfacet + facet normal -2.34298e-06 2.44021e-06 -1 + outer loop + vertex 791.74 215.007 -9.53741e-06 + vertex 793.571 219.569 -2.69649e-06 + vertex 797.807 220.439 -1.04959e-05 + endloop + endfacet + facet normal -1.94775e-06 2.07485e-06 -1 + outer loop + vertex 803.151 225.364 -1.15097e-05 + vertex 797.628 224.631 -2.27459e-06 + vertex 803.365 229.71 -2.90931e-06 + endloop + endfacet + facet normal -7.21722e-06 7.49403e-06 -1 + outer loop + vertex 795.902 214.962 -3.77973e-05 + vertex 797.807 220.439 -1.04959e-05 + vertex 802.258 220.51 -4.20859e-05 + endloop + endfacet + facet normal -6.80639e-06 7.2591e-06 -1 + outer loop + vertex 807.719 225.309 -4.29977e-05 + vertex 803.151 225.364 -1.15097e-05 + vertex 807.963 229.702 -1.27714e-05 + endloop + endfacet + facet normal -2.04446e-05 2.12616e-05 -1 + outer loop + vertex 800.189 214.709 -0.000123137 + vertex 802.258 220.51 -4.20859e-05 + vertex 806.828 220.416 -0.00013754 + endloop + endfacet + facet normal -1.92631e-05 2.04807e-05 -1 + outer loop + vertex 812.239 225.318 -0.000129894 + vertex 807.719 225.309 -4.29977e-05 + vertex 812.312 229.476 -4.6145e-05 + endloop + endfacet + facet normal -4.93659e-05 5.12054e-05 -1 + outer loop + vertex 804.717 214.493 -0.000336606 + vertex 806.828 220.416 -0.00013754 + vertex 812.408 220.913 -0.00038754 + endloop + endfacet + facet normal -3.79393e-05 4.05764e-05 -1 + outer loop + vertex 816.45 226.008 -0.000261652 + vertex 812.239 225.318 -0.000129894 + vertex 816.631 229.41 -0.00013048 + endloop + endfacet + facet normal -8.27949e-05 8.49109e-05 -1 + outer loop + vertex 819.287 224.972 -0.000584532 + vertex 816.45 226.008 -0.000261652 + vertex 820.75 229.264 -0.000341216 + endloop + endfacet + facet normal -0.000101718 0.00010435 -1 + outer loop + vertex 809.222 214.162 -0.000767866 + vertex 812.408 220.913 -0.00038754 + vertex 816.599 219.802 -0.000929789 + endloop + endfacet + facet normal -0.000124764 0.000131328 -1 + outer loop + vertex 823.166 224.201 -0.00116974 + vertex 819.287 224.972 -0.000584532 + vertex 824.904 228.812 -0.000781097 + endloop + endfacet + facet normal -0.000148098 0.000155164 -1 + outer loop + vertex 813.441 213.667 -0.00141411 + vertex 816.599 219.802 -0.000929789 + vertex 820.531 219.13 -0.00161633 + endloop + endfacet + facet normal -0.000154798 0.00016703 -1 + outer loop + vertex 826.213 222.931 -0.00185353 + vertex 823.166 224.201 -0.00116974 + vertex 829.583 227.808 -0.0015605 + endloop + endfacet + facet normal -0.000162275 0.00017406 -1 + outer loop + vertex 817.481 213.113 -0.0021688 + vertex 820.531 219.13 -0.00161633 + vertex 824.4 218.43 -0.00236589 + endloop + endfacet + facet normal -0.000180291 0.000184643 -1 + outer loop + vertex 831.655 223.04 -0.00281442 + vertex 826.213 222.931 -0.00185353 + vertex 829.583 227.808 -0.0015605 + endloop + endfacet + facet normal -0.000181543 0.000192875 -1 + outer loop + vertex 821.3 212.353 -0.00297538 + vertex 824.4 218.43 -0.00236589 + vertex 827.19 217.023 -0.00314393 + endloop + endfacet + facet normal -0.000290331 0.000288069 -1 + outer loop + vertex 825.214 211.564 -0.00414283 + vertex 827.19 217.023 -0.00314393 + vertex 831.683 217.196 -0.00439846 + endloop + endfacet + facet normal -0.000274003 0.000331517 -1 + outer loop + vertex 838.024 222 -0.00490477 + vertex 831.655 223.04 -0.00281442 + vertex 838.618 227.386 -0.00328175 + endloop + endfacet + facet normal -0.000441338 0.00044288 -1 + outer loop + vertex 829.411 210.609 -0.00631312 + vertex 831.683 217.196 -0.00439846 + vertex 836.4 215.97 -0.00702368 + endloop + endfacet + facet normal -0.000312431 0.00035925 -1 + outer loop + vertex 844.234 220.263 -0.00746872 + vertex 838.024 222 -0.00490477 + vertex 843.552 226.333 -0.00507496 + endloop + endfacet + facet normal -0.000450399 0.00050288 -1 + outer loop + vertex 833.347 209.123 -0.00909127 + vertex 836.4 215.97 -0.00702368 + vertex 839.401 213.762 -0.00948546 + endloop + endfacet + facet normal 0.00040333 -0.000199974 -1 + outer loop + vertex 837.164 207.57 -0.00914959 + vertex 839.401 213.762 -0.00948546 + vertex 843.831 213.355 -0.0076174 + endloop + endfacet + facet normal 0.000411594 -0.000499704 -1 + outer loop + vertex 850.209 218.204 -0.00398058 + vertex 844.234 220.263 -0.00746872 + vertex 851.462 224.108 -0.00641531 + endloop + endfacet + facet normal 0.00193661 -0.00169196 -0.999997 + outer loop + vertex 841.089 205.843 -0.000217352 + vertex 843.831 213.355 -0.0076174 + vertex 848.24 211.462 0.00412448 + endloop + endfacet + facet normal 0.00244536 -0.0024825 -0.999994 + outer loop + vertex 854.661 215.742 0.0130199 + vertex 850.209 218.204 -0.00398058 + vertex 856.015 222.143 0.000439147 + endloop + endfacet + facet normal 0.00426416 -0.00425299 -0.999982 + outer loop + vertex 844.679 203.482 0.0228792 + vertex 848.24 211.462 0.00412448 + vertex 851.75 208.649 0.0310576 + endloop + endfacet + facet normal 0.00559981 -0.00587373 -0.999967 + outer loop + vertex 858.227 211.737 0.0565088 + vertex 854.661 215.742 0.0130199 + vertex 860.218 219.638 0.0212482 + endloop + endfacet + facet normal 0.0070142 -0.00752816 -0.999947 + outer loop + vertex 847.536 200.563 0.062363 + vertex 851.75 208.649 0.0310576 + vertex 853.462 205.082 0.0699114 + endloop + endfacet + facet normal 0.0136485 -0.0144068 -0.999803 + outer loop + vertex 849.983 197.579 0.130538 + vertex 853.462 205.082 0.0699114 + vertex 856.619 203.691 0.133051 + endloop + endfacet + facet normal 0.0131859 -0.0131165 -0.999827 + outer loop + vertex 862.451 209.143 0.146244 + vertex 858.227 211.737 0.0565088 + vertex 864.099 216.792 0.0676391 + endloop + endfacet + facet normal 0.0266797 -0.0276266 -0.999262 + outer loop + vertex 852.376 194.489 0.274169 + vertex 856.619 203.691 0.133051 + vertex 859.423 200.683 0.29108 + endloop + endfacet + facet normal 0.0501768 -0.0543659 -0.99726 + outer loop + vertex 852.376 194.489 0.274169 + vertex 859.423 200.683 0.29108 + vertex 854.617 190.978 0.578383 + endloop + endfacet + facet normal 0.0326675 -0.0300743 -0.999014 + outer loop + vertex 865.43 205.859 0.342515 + vertex 862.451 209.143 0.146244 + vertex 867.583 213.786 0.174313 + endloop + endfacet + facet normal 0.0657565 -0.0582678 -0.996133 + outer loop + vertex 868.132 202.26 0.731407 + vertex 865.43 205.859 0.342515 + vertex 870.612 210.358 0.421449 + endloop + endfacet + facet normal 0.0553078 -0.0568942 -0.996847 + outer loop + vertex 854.617 190.978 0.578383 + vertex 859.423 200.683 0.29108 + vertex 861.865 197.169 0.627104 + endloop + endfacet + facet normal 0.0489762 -0.0551339 -0.997277 + outer loop + vertex 846.477 183.981 0.565441 + vertex 852.376 194.489 0.274169 + vertex 854.617 190.978 0.578383 + endloop + endfacet + facet normal 0.0453686 -0.0551551 -0.997447 + outer loop + vertex 837.7 176.677 0.570094 + vertex 844.413 187.575 0.272831 + vertex 846.477 183.981 0.565441 + endloop + endfacet + facet normal 0.0441589 -0.0568027 -0.997408 + outer loop + vertex 828.518 169.5 0.572306 + vertex 835.754 180.347 0.274938 + vertex 837.7 176.677 0.570094 + endloop + endfacet + facet normal 0.0418038 -0.0581613 -0.997432 + outer loop + vertex 819.033 162.667 0.573193 + vertex 826.659 173.217 0.277694 + vertex 828.518 169.5 0.572306 + endloop + endfacet + facet normal 0.0396602 -0.0597082 -0.997428 + outer loop + vertex 809.286 156.192 0.573258 + vertex 817.259 166.427 0.277584 + vertex 819.033 162.667 0.573193 + endloop + endfacet + facet normal 0.0375584 -0.060764 -0.997445 + outer loop + vertex 799.315 149.996 0.57526 + vertex 807.563 159.986 0.277266 + vertex 809.286 156.192 0.573258 + endloop + endfacet + facet normal 0.0366828 -0.061948 -0.997405 + outer loop + vertex 789.184 144.021 0.573796 + vertex 797.62 153.809 0.276116 + vertex 799.315 149.996 0.57526 + endloop + endfacet + facet normal 0.0349271 -0.0621281 -0.997457 + outer loop + vertex 778.938 138.254 0.574208 + vertex 787.512 147.848 0.276814 + vertex 789.184 144.021 0.573796 + endloop + endfacet + facet normal 0.0340571 -0.0630083 -0.997432 + outer loop + vertex 768.588 132.687 0.572446 + vertex 777.291 142.093 0.275449 + vertex 778.938 138.254 0.574208 + endloop + endfacet + facet normal 0.0321568 -0.062837 -0.997506 + outer loop + vertex 758.124 127.31 0.573852 + vertex 766.96 136.536 0.277486 + vertex 768.588 132.687 0.572446 + endloop + endfacet + facet normal 0.0313664 -0.0635968 -0.997483 + outer loop + vertex 747.554 122.116 0.572657 + vertex 756.513 131.167 0.277314 + vertex 758.124 127.31 0.573852 + endloop + endfacet + facet normal 0.0299567 -0.0639098 -0.997506 + outer loop + vertex 736.927 117.117 0.573762 + vertex 745.971 125.984 0.277256 + vertex 747.554 122.116 0.572657 + endloop + endfacet + facet normal 0.0290577 -0.064546 -0.997492 + outer loop + vertex 726.262 112.314 0.573875 + vertex 735.371 120.998 0.277345 + vertex 736.927 117.117 0.573762 + endloop + endfacet + facet normal 0.0282237 -0.0649969 -0.997486 + outer loop + vertex 715.526 107.683 0.571862 + vertex 724.73 116.204 0.277045 + vertex 726.262 112.314 0.573875 + endloop + endfacet + facet normal 0.0265619 -0.065071 -0.997527 + outer loop + vertex 704.67 103.192 0.575747 + vertex 714.014 111.581 0.277358 + vertex 715.526 107.683 0.571862 + endloop + endfacet + facet normal 0.0263244 -0.0662174 -0.997458 + outer loop + vertex 693.665 98.8227 0.575371 + vertex 703.174 107.097 0.277065 + vertex 704.67 103.192 0.575747 + endloop + endfacet + facet normal 0.0253867 -0.066404 -0.99747 + outer loop + vertex 682.558 94.586 0.574749 + vertex 692.193 102.737 0.27733 + vertex 693.665 98.8227 0.575371 + endloop + endfacet + facet normal 0.0244836 -0.0664559 -0.997489 + outer loop + vertex 671.445 90.5092 0.573569 + vertex 681.131 98.5196 0.277642 + vertex 682.558 94.586 0.574749 + endloop + endfacet + facet normal 0.0240316 -0.0671103 -0.997456 + outer loop + vertex 660.343 86.5795 0.570491 + vertex 670.071 94.4664 0.274219 + vertex 671.445 90.5092 0.573569 + endloop + endfacet + facet normal 0.0231627 -0.0669353 -0.997488 + outer loop + vertex 649.095 82.7035 0.569414 + vertex 658.981 90.5363 0.273348 + vertex 660.343 86.5795 0.570491 + endloop + endfacet + facet normal 0.021611 -0.0666456 -0.997543 + outer loop + vertex 637.599 78.8231 0.579611 + vertex 647.674 86.6193 0.277013 + vertex 649.095 82.7035 0.569414 + endloop + endfacet + facet normal 0.0215118 -0.067766 -0.997469 + outer loop + vertex 626.326 75.1789 0.584062 + vertex 636.11 82.6913 0.284691 + vertex 637.599 78.8231 0.579611 + endloop + endfacet + facet normal 0.0223148 -0.0671081 -0.997496 + outer loop + vertex 616.517 72.3817 0.552808 + vertex 624.871 79.0566 0.290644 + vertex 626.326 75.1789 0.584062 + endloop + endfacet + facet normal 0.0112505 -0.0357683 -0.999297 + outer loop + vertex 623.369 82.7475 0.141624 + vertex 634.664 86.3899 0.138407 + vertex 624.871 79.0566 0.290644 + endloop + endfacet + facet normal 0.00619258 -0.0195338 -0.99979 + outer loop + vertex 621.669 86.2363 0.0629278 + vertex 632.967 89.873 0.0618538 + vertex 623.369 82.7475 0.141624 + endloop + endfacet + facet normal 0.00377876 -0.0115484 -0.999926 + outer loop + vertex 619.659 89.4317 0.0184266 + vertex 630.924 93.0871 0.0187808 + vertex 621.669 86.2363 0.0629278 + endloop + endfacet + facet normal 0.00189447 -0.00572451 -0.999982 + outer loop + vertex 617.333 92.3192 -0.00250965 + vertex 628.564 95.9866 -0.00222715 + vertex 619.659 89.4317 0.0184266 + endloop + endfacet + facet normal 0.000530826 -0.00167473 -0.999998 + outer loop + vertex 614.722 94.8954 -0.00821034 + vertex 625.933 98.5347 -0.00835394 + vertex 617.333 92.3192 -0.00250965 + endloop + endfacet + facet normal -0.000158083 0.000426553 -1 + outer loop + vertex 611.949 97.1317 -0.00681815 + vertex 623.104 100.726 -0.0070485 + vertex 614.722 94.8954 -0.00821034 + endloop + endfacet + facet normal -0.000315201 0.000936012 -1 + outer loop + vertex 609.066 99.0017 -0.00415917 + vertex 620.157 102.58 -0.00430571 + vertex 611.949 97.1317 -0.00681815 + endloop + endfacet + facet normal -0.000211016 0.000648137 -1 + outer loop + vertex 606.102 100.584 -0.00250835 + vertex 617.144 104.152 -0.0025257 + vertex 609.066 99.0017 -0.00415917 + endloop + endfacet + facet normal -9.90376e-05 0.000317929 -1 + outer loop + vertex 603.082 101.973 -0.00176767 + vertex 614.088 105.515 -0.00173132 + vertex 606.102 100.584 -0.00250835 + endloop + endfacet + facet normal -5.84243e-05 0.000194634 -1 + outer loop + vertex 600.022 103.205 -0.00134909 + vertex 610.981 106.73 -0.00130318 + vertex 603.082 101.973 -0.00176767 + endloop + endfacet + facet normal -5.50047e-05 0.000184522 -1 + outer loop + vertex 596.914 104.324 -0.000971553 + vertex 607.799 107.836 -0.000922252 + vertex 600.022 103.205 -0.00134909 + endloop + endfacet + facet normal -5.30018e-05 0.000178844 -1 + outer loop + vertex 593.729 105.365 -0.000616572 + vertex 604.54 108.86 -0.000564465 + vertex 596.914 104.324 -0.000971553 + endloop + endfacet + facet normal -4.16262e-05 0.000141726 -1 + outer loop + vertex 590.497 106.339 -0.000344058 + vertex 601.238 109.819 -0.000297895 + vertex 593.729 105.365 -0.000616572 + endloop + endfacet + facet normal -2.6756e-05 9.25176e-05 -1 + outer loop + vertex 587.308 107.259 -0.000173558 + vertex 597.971 110.718 -0.000138899 + vertex 590.497 106.339 -0.000344058 + endloop + endfacet + facet normal -1.53013e-05 5.32127e-05 -1 + outer loop + vertex 584.091 108.09 -8.01622e-05 + vertex 594.771 111.553 -5.926e-05 + vertex 587.308 107.259 -0.000173558 + endloop + endfacet + facet normal -7.55109e-06 2.68397e-05 -1 + outer loop + vertex 580.732 108.818 -3.52398e-05 + vertex 591.514 112.298 -2.3252e-05 + vertex 584.091 108.09 -8.01622e-05 + endloop + endfacet + facet normal -3.61592e-06 1.27742e-05 -1 + outer loop + vertex 577.211 109.473 -1.41457e-05 + vertex 588.038 112.947 -8.92028e-06 + vertex 580.732 108.818 -3.52398e-05 + endloop + endfacet + facet normal -1.53156e-06 5.41362e-06 -1 + outer loop + vertex 574.302 110.312 -5.1469e-06 + vertex 584.736 113.652 -3.04828e-06 + vertex 577.211 109.473 -1.41457e-05 + endloop + endfacet + facet normal -9.86791e-07 3.0574e-06 -1 + outer loop + vertex 572.869 111.533 9.62153e-15 + vertex 583.066 114.824 9.62153e-15 + vertex 574.302 110.312 -5.1469e-06 + endloop + endfacet + facet normal -6.4998e-06 2.34355e-05 -1 + outer loop + vertex 552.55 105.235 9.62153e-15 + vertex 559.428 103.938 -7.5108e-05 + vertex 555.265 103.618 -5.55499e-05 + endloop + endfacet + facet normal -6.88746e-06 2.27847e-05 -1 + outer loop + vertex 552.205 105.131 9.62153e-15 + vertex 552.55 105.235 9.62153e-15 + vertex 555.265 103.618 -5.55499e-05 + endloop + endfacet + facet normal -7.18367e-06 2.21856e-05 -1 + outer loop + vertex 550.77 102.792 -4.15866e-05 + vertex 552.205 105.131 9.62153e-15 + vertex 555.265 103.618 -5.55499e-05 + endloop + endfacet + facet normal -1.24356e-05 5.07646e-05 -1 + outer loop + vertex 550.77 102.792 -4.15866e-05 + vertex 555.265 103.618 -5.55499e-05 + vertex 555.618 101.728 -0.000155898 + endloop + endfacet + facet normal -1.41947e-05 4.27503e-05 -1 + outer loop + vertex 550.77 102.792 -4.15866e-05 + vertex 555.618 101.728 -0.000155898 + vertex 549.883 100.145 -0.000142138 + endloop + endfacet + facet normal -1.65317e-05 4.35337e-05 -1 + outer loop + vertex 549.883 100.145 -0.000142138 + vertex 545.607 100.673 -4.84727e-05 + vertex 550.77 102.792 -4.15866e-05 + endloop + endfacet + facet normal -6.52188e-06 1.91422e-05 -1 + outer loop + vertex 545.607 100.673 -4.84727e-05 + vertex 544.383 102.789 9.62153e-15 + vertex 550.77 102.792 -4.15866e-05 + endloop + endfacet + facet normal -6.52336e-06 2.1789e-05 -1 + outer loop + vertex 544.383 102.789 9.62153e-15 + vertex 551.859 105.027 9.62153e-15 + vertex 550.77 102.792 -4.15866e-05 + endloop + endfacet + facet normal -6.43534e-06 1.91922e-05 -1 + outer loop + vertex 538.377 98.8868 -3.62295e-05 + vertex 544.383 102.789 9.62153e-15 + vertex 545.607 100.673 -4.84727e-05 + endloop + endfacet + facet normal -1.18688e-05 4.11832e-05 -1 + outer loop + vertex 538.377 98.8868 -3.62295e-05 + vertex 545.607 100.673 -4.84727e-05 + vertex 542.156 97.853 -0.000123658 + endloop + endfacet + facet normal -1.27405e-05 3.79968e-05 -1 + outer loop + vertex 532.361 95.0854 -0.00010403 + vertex 538.377 98.8868 -3.62295e-05 + vertex 542.156 97.853 -0.000123658 + endloop + endfacet + facet normal -2.32797e-05 7.52955e-05 -1 + outer loop + vertex 532.361 95.0854 -0.00010403 + vertex 542.156 97.853 -0.000123658 + vertex 536.181 94.0068 -0.000274171 + endloop + endfacet + facet normal -2.4181e-05 7.21035e-05 -1 + outer loop + vertex 524.893 90.8233 -0.000230761 + vertex 532.361 95.0854 -0.00010403 + vertex 536.181 94.0068 -0.000274171 + endloop + endfacet + facet normal -3.43099e-05 0.000108018 -1 + outer loop + vertex 524.893 90.8233 -0.000230761 + vertex 536.181 94.0068 -0.000274171 + vertex 528.544 89.6164 -0.00048638 + endloop + endfacet + facet normal -3.54287e-05 0.000104633 -1 + outer loop + vertex 516.714 86.3403 -0.000410034 + vertex 524.893 90.8233 -0.000230761 + vertex 528.544 89.6164 -0.00048638 + endloop + endfacet + facet normal -3.62743e-05 0.000107687 -1 + outer loop + vertex 516.714 86.3403 -0.000410034 + vertex 528.544 89.6164 -0.00048638 + vertex 520.287 85.0343 -0.000680277 + endloop + endfacet + facet normal -3.72886e-05 0.000104911 -1 + outer loop + vertex 508.73 81.877 -0.000580571 + vertex 516.714 86.3403 -0.000410034 + vertex 520.287 85.0343 -0.000680277 + endloop + endfacet + facet normal -2.46851e-05 5.87777e-05 -1 + outer loop + vertex 508.73 81.877 -0.000580571 + vertex 520.287 85.0343 -0.000680277 + vertex 512.205 80.4497 -0.000750259 + endloop + endfacet + facet normal -2.45506e-05 5.91051e-05 -1 + outer loop + vertex 501.833 77.6627 -0.000660342 + vertex 508.73 81.877 -0.000580571 + vertex 512.205 80.4497 -0.000750259 + endloop + endfacet + facet normal -2.70673e-05 6.29769e-05 -1 + outer loop + vertex 512.205 80.4497 -0.000750259 + vertex 520.287 85.0343 -0.000680277 + vertex 523.761 83.6181 -0.000863511 + endloop + endfacet + facet normal -9.48195e-06 -1.16182e-06 -1 + outer loop + vertex 512.205 80.4497 -0.000750259 + vertex 523.761 83.6181 -0.000863511 + vertex 515.585 78.875 -0.000780474 + endloop + endfacet + facet normal -8.18636e-06 1.61866e-06 -1 + outer loop + vertex 505.185 76.0729 -0.000699877 + vertex 512.205 80.4497 -0.000750259 + vertex 515.585 78.875 -0.000780474 + endloop + endfacet + facet normal -1.29917e-05 4.8883e-06 -1 + outer loop + vertex 515.585 78.875 -0.000780474 + vertex 523.761 83.6181 -0.000863511 + vertex 527.205 82.0706 -0.000915822 + endloop + endfacet + facet normal -3.78869e-05 9.54155e-05 -1 + outer loop + vertex 515.585 78.875 -0.000780474 + vertex 527.205 82.0706 -0.000915822 + vertex 518.926 77.1151 -0.001075 + endloop + endfacet + facet normal -4.29827e-05 8.57398e-05 -1 + outer loop + vertex 508.437 74.2983 -0.000865658 + vertex 515.585 78.875 -0.000780474 + vertex 518.926 77.1151 -0.001075 + endloop + endfacet + facet normal -5.16758e-05 0.000118452 -1 + outer loop + vertex 518.926 77.1151 -0.001075 + vertex 527.205 82.0706 -0.000915822 + vertex 530.629 80.3395 -0.00129782 + endloop + endfacet + facet normal -0.000165842 0.000532816 -1 + outer loop + vertex 518.926 77.1151 -0.001075 + vertex 530.629 80.3395 -0.00129782 + vertex 522.184 75.0978 -0.00269003 + endloop + endfacet + facet normal -0.000186238 0.000499883 -1 + outer loop + vertex 511.646 72.278 -0.002137 + vertex 518.926 77.1151 -0.001075 + vertex 522.184 75.0978 -0.00269003 + endloop + endfacet + facet normal -0.000195467 0.000580549 -1 + outer loop + vertex 522.184 75.0978 -0.00269003 + vertex 530.629 80.3395 -0.00129782 + vertex 533.982 78.3463 -0.00311022 + endloop + endfacet + facet normal -0.000332845 0.00107948 -0.999999 + outer loop + vertex 522.184 75.0978 -0.00269003 + vertex 533.982 78.3463 -0.00311022 + vertex 525.291 72.7614 -0.00624639 + endloop + endfacet + facet normal -0.000371423 0.00102817 -0.999999 + outer loop + vertex 514.692 69.9104 -0.00524107 + vertex 522.184 75.0978 -0.00269003 + vertex 525.291 72.7614 -0.00624639 + endloop + endfacet + facet normal -0.000342981 0.00109525 -0.999999 + outer loop + vertex 525.291 72.7614 -0.00624639 + vertex 533.982 78.3463 -0.00311022 + vertex 537.174 76.0238 -0.00674899 + endloop + endfacet + facet normal -0.000229499 0.000681892 -1 + outer loop + vertex 525.291 72.7614 -0.00624639 + vertex 537.174 76.0238 -0.00674899 + vertex 528.157 70.0662 -0.0087419 + endloop + endfacet + facet normal -0.000274655 0.000633875 -1 + outer loop + vertex 517.516 67.1856 -0.00764539 + vertex 525.291 72.7614 -0.00624639 + vertex 528.157 70.0662 -0.0087419 + endloop + endfacet + facet normal -0.000205703 0.000645874 -1 + outer loop + vertex 528.157 70.0662 -0.0087419 + vertex 537.174 76.0238 -0.00674899 + vertex 540.114 73.3427 -0.00908523 + endloop + endfacet + facet normal 0.000520993 -0.00200602 -0.999998 + outer loop + vertex 528.157 70.0662 -0.0087419 + vertex 540.114 73.3427 -0.00908523 + vertex 530.689 67.0022 -0.00127584 + endloop + endfacet + facet normal 0.00048291 -0.00203749 -0.999998 + outer loop + vertex 519.991 64.0936 -0.00051588 + vertex 528.157 70.0662 -0.0087419 + vertex 530.689 67.0022 -0.00127584 + endloop + endfacet + facet normal 0.000521737 -0.00200712 -0.999998 + outer loop + vertex 530.689 67.0022 -0.00127584 + vertex 540.114 73.3427 -0.00908523 + vertex 542.72 70.2941 -0.00160602 + endloop + endfacet + facet normal 0.00194509 -0.00720912 -0.999972 + outer loop + vertex 530.689 67.0022 -0.00127584 + vertex 542.72 70.2941 -0.00160602 + vertex 532.835 63.6055 0.0273858 + endloop + endfacet + facet normal 0.00179335 -0.00730498 -0.999972 + outer loop + vertex 522.084 60.6664 0.0295745 + vertex 530.689 67.0022 -0.00127584 + vertex 532.835 63.6055 0.0273858 + endloop + endfacet + facet normal 0.0017153 -0.00686952 -0.999975 + outer loop + vertex 532.835 63.6055 0.0273858 + vertex 542.72 70.2941 -0.00160602 + vertex 544.949 66.9239 0.0253694 + endloop + endfacet + facet normal 0.00379847 -0.0144743 -0.999888 + outer loop + vertex 532.835 63.6055 0.0273858 + vertex 544.949 66.9239 0.0253694 + vertex 534.59 59.9588 0.086843 + endloop + endfacet + facet normal 0.00345143 -0.0146413 -0.999887 + outer loop + vertex 523.801 57.0143 0.0927167 + vertex 532.835 63.6055 0.0273858 + vertex 534.59 59.9588 0.086843 + endloop + endfacet + facet normal 0.00340817 -0.0138939 -0.999898 + outer loop + vertex 534.59 59.9588 0.086843 + vertex 544.949 66.9239 0.0253694 + vertex 546.744 63.2938 0.0819276 + endloop + endfacet + facet normal 0.00647169 -0.0250578 -0.999665 + outer loop + vertex 534.59 59.9588 0.086843 + vertex 546.744 63.2938 0.0819276 + vertex 536.02 56.168 0.191117 + endloop + endfacet + facet normal 0.00614018 -0.0251827 -0.999664 + outer loop + vertex 525.172 53.2471 0.19807 + vertex 534.59 59.9588 0.086843 + vertex 536.02 56.168 0.191117 + endloop + endfacet + facet normal 0.00575627 -0.0239815 -0.999696 + outer loop + vertex 536.02 56.168 0.191117 + vertex 546.744 63.2938 0.0819276 + vertex 548.148 59.5056 0.180887 + endloop + endfacet + facet normal 0.0112905 -0.04409 -0.998964 + outer loop + vertex 536.02 56.168 0.191117 + vertex 548.148 59.5056 0.180887 + vertex 537.236 52.3014 0.375517 + endloop + endfacet + facet normal 0.0112425 -0.0441051 -0.998964 + outer loop + vertex 526.389 49.4319 0.380133 + vertex 536.02 56.168 0.191117 + vertex 537.236 52.3014 0.375517 + endloop + endfacet + facet normal 0.0106083 -0.0430581 -0.999016 + outer loop + vertex 537.236 52.3014 0.375517 + vertex 548.148 59.5056 0.180887 + vertex 549.299 55.6324 0.360046 + endloop + endfacet + facet normal 0.0208989 -0.0803141 -0.99655 + outer loop + vertex 537.236 52.3014 0.375517 + vertex 549.299 55.6324 0.360046 + vertex 538.501 48.3958 0.7168 + endloop + endfacet + facet normal 0.0114365 -0.042812 -0.999018 + outer loop + vertex 548.148 59.5056 0.180887 + vertex 560.564 62.9946 0.173496 + vertex 549.299 55.6324 0.360046 + endloop + endfacet + facet normal 0.0114209 -0.0427881 -0.999019 + outer loop + vertex 549.299 55.6324 0.360046 + vertex 560.564 62.9946 0.173496 + vertex 561.678 59.1403 0.351317 + endloop + endfacet + facet normal 0.0222611 -0.0810347 -0.996463 + outer loop + vertex 549.299 55.6324 0.360046 + vertex 561.678 59.1403 0.351317 + vertex 550.544 51.7258 0.705559 + endloop + endfacet + facet normal 0.0119618 -0.0426318 -0.999019 + outer loop + vertex 560.564 62.9946 0.173496 + vertex 572.632 66.4533 0.1704 + vertex 561.678 59.1403 0.351317 + endloop + endfacet + facet normal 0.0117128 -0.0422592 -0.999038 + outer loop + vertex 561.678 59.1403 0.351317 + vertex 572.632 66.4533 0.1704 + vertex 573.802 62.5979 0.347203 + endloop + endfacet + facet normal 0.0225848 -0.0803787 -0.996508 + outer loop + vertex 561.678 59.1403 0.351317 + vertex 573.802 62.5979 0.347203 + vertex 562.826 55.199 0.695241 + endloop + endfacet + facet normal 0.0121668 -0.0421214 -0.999038 + outer loop + vertex 572.632 66.4533 0.1704 + vertex 583.794 69.6066 0.173389 + vertex 573.802 62.5979 0.347203 + endloop + endfacet + facet normal 0.0120282 -0.041924 -0.999048 + outer loop + vertex 573.802 62.5979 0.347203 + vertex 583.794 69.6066 0.173389 + vertex 585.033 65.56 0.358119 + endloop + endfacet + facet normal 0.0217803 -0.0789086 -0.996644 + outer loop + vertex 573.802 62.5979 0.347203 + vertex 585.033 65.56 0.358119 + vertex 574.843 58.5672 0.689075 + endloop + endfacet + facet normal 0.011739 -0.0420126 -0.999048 + outer loop + vertex 583.794 69.6066 0.173389 + vertex 593.903 72.0693 0.188614 + vertex 585.033 65.56 0.358119 + endloop + endfacet + facet normal 0.0149732 -0.0464136 -0.99881 + outer loop + vertex 585.033 65.56 0.358119 + vertex 593.903 72.0693 0.188614 + vertex 593.915 66.9948 0.4246 + endloop + endfacet + facet normal 0.0204943 -0.0806982 -0.996528 + outer loop + vertex 585.033 65.56 0.358119 + vertex 593.915 66.9948 0.4246 + vertex 585.666 61.3097 0.715328 + endloop + endfacet + facet normal 0.00928071 -0.0464303 -0.998878 + outer loop + vertex 593.915 66.9948 0.4246 + vertex 593.903 72.0693 0.188614 + vertex 599.679 71.0459 0.289852 + endloop + endfacet + facet normal 0.0273813 -0.0721237 -0.99702 + outer loop + vertex 599.679 71.0459 0.289852 + vertex 599.882 66.2469 0.642567 + vertex 593.915 66.9948 0.4246 + endloop + endfacet + facet normal 0.0110041 -0.0367408 -0.999264 + outer loop + vertex 599.584 74.6643 0.155763 + vertex 599.679 71.0459 0.289852 + vertex 593.903 72.0693 0.188614 + endloop + endfacet + facet normal 0.00407144 -0.0215696 -0.999759 + outer loop + vertex 597.009 77.3781 0.0867264 + vertex 599.584 74.6643 0.155763 + vertex 593.903 72.0693 0.188614 + endloop + endfacet + facet normal 0.00670496 -0.0231095 -0.99971 + outer loop + vertex 593.903 72.0693 0.188614 + vertex 590.799 75.7464 0.0827961 + vertex 597.009 77.3781 0.0867264 + endloop + endfacet + facet normal 0.00388958 -0.0123943 -0.999916 + outer loop + vertex 593.714 81.103 0.0277385 + vertex 597.009 77.3781 0.0867264 + vertex 590.799 75.7464 0.0827961 + endloop + endfacet + facet normal 0.0046786 -0.0128236 -0.999907 + outer loop + vertex 590.799 75.7464 0.0827961 + vertex 587.914 78.3003 0.0365448 + vertex 593.714 81.103 0.0277385 + endloop + endfacet + facet normal 0.001959 -0.00719592 -0.999972 + outer loop + vertex 587.914 78.3003 0.0365448 + vertex 587.677 82.5749 0.00532008 + vertex 593.714 81.103 0.0277385 + endloop + endfacet + facet normal 0.00204088 -0.00686014 -0.999974 + outer loop + vertex 592.722 85.1653 -0.00215639 + vertex 593.714 81.103 0.0277385 + vertex 587.677 82.5749 0.00532008 + endloop + endfacet + facet normal -9.53699e-05 -0.00270045 -0.999996 + outer loop + vertex 589.717 87.4475 -0.00803275 + vertex 592.722 85.1653 -0.00215639 + vertex 587.677 82.5749 0.00532008 + endloop + endfacet + facet normal 0.000581572 -0.00298386 -0.999995 + outer loop + vertex 587.677 82.5749 0.00532008 + vertex 583.922 85.7664 -0.00638703 + vertex 589.717 87.4475 -0.00803275 + endloop + endfacet + facet normal -0.000250983 -0.000113737 -1 + outer loop + vertex 586.383 89.9354 -0.00747879 + vertex 589.717 87.4475 -0.00803275 + vertex 583.922 85.7664 -0.00638703 + endloop + endfacet + facet normal -8.54691e-05 -0.000211429 -1 + outer loop + vertex 583.922 85.7664 -0.00638703 + vertex 580.449 88.3665 -0.00663992 + vertex 586.383 89.9354 -0.00747879 + endloop + endfacet + facet normal -0.000336281 0.000737196 -1 + outer loop + vertex 582.766 92.0916 -0.00467304 + vertex 586.383 89.9354 -0.00747879 + vertex 580.449 88.3665 -0.00663992 + endloop + endfacet + facet normal -0.000269523 0.000695668 -1 + outer loop + vertex 580.449 88.3665 -0.00663992 + vertex 576.668 90.482 -0.00414908 + vertex 582.766 92.0916 -0.00467304 + endloop + endfacet + facet normal -0.00021365 0.000483974 -1 + outer loop + vertex 578.097 94.0881 -0.00270929 + vertex 582.766 92.0916 -0.00467304 + vertex 576.668 90.482 -0.00414908 + endloop + endfacet + facet normal -0.000226228 0.000488961 -1 + outer loop + vertex 576.668 90.482 -0.00414908 + vertex 572.689 91.7518 -0.00262808 + vertex 578.097 94.0881 -0.00270929 + endloop + endfacet + facet normal -8.48489e-05 0.000161666 -1 + outer loop + vertex 572.689 91.7518 -0.00262808 + vertex 570.717 94.0819 -0.00208405 + vertex 578.097 94.0881 -0.00270929 + endloop + endfacet + facet normal -8.48659e-05 0.000182017 -1 + outer loop + vertex 575.514 96.2812 -0.00209091 + vertex 578.097 94.0881 -0.00270929 + vertex 570.717 94.0819 -0.00208405 + endloop + endfacet + facet normal -4.90142e-05 0.000103807 -1 + outer loop + vertex 570.612 97.1485 -0.00176059 + vertex 575.514 96.2812 -0.00209091 + vertex 570.717 94.0819 -0.00208405 + endloop + endfacet + facet normal -3.25248e-05 0.00010437 -1 + outer loop + vertex 570.717 94.0819 -0.00208405 + vertex 565.575 94.8539 -0.00183626 + vertex 570.612 97.1485 -0.00176059 + endloop + endfacet + facet normal -5.19047e-05 0.000146909 -1 + outer loop + vertex 565.575 94.8539 -0.00183626 + vertex 563.297 96.5047 -0.00147549 + vertex 570.612 97.1485 -0.00176059 + endloop + endfacet + facet normal -5.83368e-05 0.000219985 -1 + outer loop + vertex 566.769 98.933 -0.00114384 + vertex 570.612 97.1485 -0.00176059 + vertex 563.297 96.5047 -0.00147549 + endloop + endfacet + facet normal -6.45626e-05 0.000228887 -1 + outer loop + vertex 563.297 96.5047 -0.00147549 + vertex 559.838 98.345 -0.000830932 + vertex 566.769 98.933 -0.00114384 + endloop + endfacet + facet normal -6.53882e-05 0.000238619 -1 + outer loop + vertex 564.092 100.262 -0.000651723 + vertex 566.769 98.933 -0.00114384 + vertex 559.838 98.345 -0.000830932 + endloop + endfacet + facet normal -4.26988e-05 0.00018826 -1 + outer loop + vertex 560.172 100.817 -0.000379746 + vertex 564.092 100.262 -0.000651723 + vertex 559.838 98.345 -0.000830932 + endloop + endfacet + facet normal -5.21017e-05 0.000189529 -1 + outer loop + vertex 559.838 98.345 -0.000830932 + vertex 554.505 99.2854 -0.000374827 + vertex 560.172 100.817 -0.000379746 + endloop + endfacet + facet normal -2.86255e-05 0.000102684 -1 + outer loop + vertex 555.618 101.728 -0.000155898 + vertex 560.172 100.817 -0.000379746 + vertex 554.505 99.2854 -0.000374827 + endloop + endfacet + facet normal -2.40485e-05 0.000125569 -1 + outer loop + vertex 555.618 101.728 -0.000155898 + vertex 559.895 102.339 -0.000182041 + vertex 560.172 100.817 -0.000379746 + endloop + endfacet + facet normal -2.45404e-05 0.00012548 -1 + outer loop + vertex 560.172 100.817 -0.000379746 + vertex 559.895 102.339 -0.000182041 + vertex 563.469 101.339 -0.000395186 + endloop + endfacet + facet normal -1.74903e-05 0.000150687 -1 + outer loop + vertex 563.469 101.339 -0.000395186 + vertex 559.895 102.339 -0.000182041 + vertex 565.028 102.192 -0.000294006 + endloop + endfacet + facet normal -4.37334e-05 0.000198699 -1 + outer loop + vertex 567.153 100.469 -0.000729249 + vertex 563.469 101.339 -0.000395186 + vertex 565.028 102.192 -0.000294006 + endloop + endfacet + facet normal -3.9865e-05 0.00021507 -1 + outer loop + vertex 564.092 100.262 -0.000651723 + vertex 563.469 101.339 -0.000395186 + vertex 567.153 100.469 -0.000729249 + endloop + endfacet + facet normal -5.70929e-05 0.000161223 -1 + outer loop + vertex 550.36 95.8198 -0.00069693 + vertex 554.505 99.2854 -0.000374827 + vertex 559.838 98.345 -0.000830932 + endloop + endfacet + facet normal -6.35434e-05 0.000185433 -1 + outer loop + vertex 550.36 95.8198 -0.00069693 + vertex 559.838 98.345 -0.000830932 + vertex 554.233 94.4798 -0.0011915 + endloop + endfacet + facet normal -6.80542e-05 0.000172396 -1 + outer loop + vertex 543.558 91.5517 -0.000969863 + vertex 550.36 95.8198 -0.00069693 + vertex 554.233 94.4798 -0.0011915 + endloop + endfacet + facet normal -4.76494e-05 9.80116e-05 -1 + outer loop + vertex 543.558 91.5517 -0.000969863 + vertex 554.233 94.4798 -0.0011915 + vertex 547.147 90.1517 -0.00127807 + endloop + endfacet + facet normal -4.83247e-05 9.62807e-05 -1 + outer loop + vertex 535.603 86.9159 -0.00103177 + vertex 543.558 91.5517 -0.000969863 + vertex 547.147 90.1517 -0.00127807 + endloop + endfacet + facet normal -2.28109e-05 5.26006e-06 -1 + outer loop + vertex 535.603 86.9159 -0.00103177 + vertex 547.147 90.1517 -0.00127807 + vertex 539.131 85.3986 -0.00112022 + endloop + endfacet + facet normal -2.02613e-05 1.11877e-05 -1 + outer loop + vertex 527.205 82.0706 -0.000915822 + vertex 535.603 86.9159 -0.00103177 + vertex 539.131 85.3986 -0.00112022 + endloop + endfacet + facet normal -3.31994e-05 2.27804e-05 -1 + outer loop + vertex 539.131 85.3986 -0.00112022 + vertex 547.147 90.1517 -0.00127807 + vertex 550.738 88.6497 -0.0014315 + endloop + endfacet + facet normal -6.32583e-05 0.000130095 -1 + outer loop + vertex 539.131 85.3986 -0.00112022 + vertex 550.738 88.6497 -0.0014315 + vertex 542.653 83.6894 -0.00156536 + endloop + endfacet + facet normal -6.02345e-05 0.000136326 -1 + outer loop + vertex 530.629 80.3395 -0.00129782 + vertex 539.131 85.3986 -0.00112022 + vertex 542.653 83.6894 -0.00156536 + endloop + endfacet + facet normal -6.55873e-05 0.000133892 -1 + outer loop + vertex 542.653 83.6894 -0.00156536 + vertex 550.738 88.6497 -0.0014315 + vertex 554.334 86.9646 -0.00189299 + endloop + endfacet + facet normal -0.000191143 0.0005817 -1 + outer loop + vertex 542.653 83.6894 -0.00156536 + vertex 554.334 86.9646 -0.00189299 + vertex 546.096 81.7079 -0.00337616 + endloop + endfacet + facet normal -0.000185896 0.000590816 -1 + outer loop + vertex 533.982 78.3463 -0.00311022 + vertex 542.653 83.6894 -0.00156536 + vertex 546.096 81.7079 -0.00337616 + endloop + endfacet + facet normal -0.000169823 0.000548288 -1 + outer loop + vertex 546.096 81.7079 -0.00337616 + vertex 554.334 86.9646 -0.00189299 + vertex 557.818 85.0003 -0.00356167 + endloop + endfacet + facet normal -0.000304577 0.00102806 -0.999999 + outer loop + vertex 546.096 81.7079 -0.00337616 + vertex 557.818 85.0003 -0.00356167 + vertex 549.37 79.3972 -0.0067488 + endloop + endfacet + facet normal -0.000290052 0.00104864 -0.999999 + outer loop + vertex 537.174 76.0238 -0.00674899 + vertex 546.096 81.7079 -0.00337616 + vertex 549.37 79.3972 -0.0067488 + endloop + endfacet + facet normal -0.000243539 0.000936029 -1 + outer loop + vertex 549.37 79.3972 -0.0067488 + vertex 557.818 85.0003 -0.00356167 + vertex 561.145 82.7226 -0.0065038 + endloop + endfacet + facet normal -0.000127077 0.000523646 -1 + outer loop + vertex 549.37 79.3972 -0.0067488 + vertex 561.145 82.7226 -0.0065038 + vertex 552.393 76.7317 -0.00852878 + endloop + endfacet + facet normal -0.000105848 0.000547724 -1 + outer loop + vertex 540.114 73.3427 -0.00908523 + vertex 549.37 79.3972 -0.0067488 + vertex 552.393 76.7317 -0.00852878 + endloop + endfacet + facet normal 2.21017e-05 0.000305719 -1 + outer loop + vertex 552.393 76.7317 -0.00852878 + vertex 561.145 82.7226 -0.0065038 + vertex 564.268 80.0951 -0.00723806 + endloop + endfacet + facet normal 0.000686402 -0.0020397 -0.999998 + outer loop + vertex 552.393 76.7317 -0.00852878 + vertex 564.268 80.0951 -0.00723806 + vertex 555.088 73.7061 -0.000507243 + endloop + endfacet + facet normal 0.000658415 -0.00206463 -0.999998 + outer loop + vertex 542.72 70.2941 -0.00160602 + vertex 552.393 76.7317 -0.00852878 + vertex 555.088 73.7061 -0.000507243 + endloop + endfacet + facet normal 0.000787345 -0.00218473 -0.999997 + outer loop + vertex 555.088 73.7061 -0.000507243 + vertex 564.268 80.0951 -0.00723806 + vertex 567.087 77.0931 0.00154024 + endloop + endfacet + facet normal 0.00199975 -0.00647977 -0.999977 + outer loop + vertex 555.088 73.7061 -0.000507243 + vertex 567.087 77.0931 0.00154024 + vertex 557.386 70.3591 0.0257755 + endloop + endfacet + facet normal 0.00185072 -0.00658207 -0.999977 + outer loop + vertex 544.949 66.9239 0.0253694 + vertex 555.088 73.7061 -0.000507243 + vertex 557.386 70.3591 0.0257755 + endloop + endfacet + facet normal 0.00200012 -0.00648031 -0.999977 + outer loop + vertex 557.386 70.3591 0.0257755 + vertex 567.087 77.0931 0.00154024 + vertex 569.422 73.7381 0.0279525 + endloop + endfacet + facet normal 0.0037524 -0.0127221 -0.999912 + outer loop + vertex 557.386 70.3591 0.0257755 + vertex 569.422 73.7381 0.0279525 + vertex 559.2 66.7559 0.0784257 + endloop + endfacet + facet normal 0.00331609 -0.0129417 -0.999911 + outer loop + vertex 546.744 63.2938 0.0819276 + vertex 557.386 70.3591 0.0257755 + vertex 559.2 66.7559 0.0784257 + endloop + endfacet + facet normal 0.00363993 -0.0125575 -0.999915 + outer loop + vertex 559.2 66.7559 0.0784257 + vertex 569.422 73.7381 0.0279525 + vertex 571.197 70.1473 0.0795087 + endloop + endfacet + facet normal 0.00656064 -0.02289 -0.999716 + outer loop + vertex 559.2 66.7559 0.0784257 + vertex 571.197 70.1473 0.0795087 + vertex 560.564 62.9946 0.173496 + endloop + endfacet + facet normal 0.00367825 -0.0125385 -0.999915 + outer loop + vertex 569.422 73.7381 0.0279525 + vertex 580.242 76.6984 0.0306335 + vertex 571.197 70.1473 0.0795087 + endloop + endfacet + facet normal 0.00367251 -0.0125306 -0.999915 + outer loop + vertex 571.197 70.1473 0.0795087 + vertex 580.242 76.6984 0.0306335 + vertex 581.929 73.1579 0.0811986 + endloop + endfacet + facet normal 0.00636451 -0.0221272 -0.999735 + outer loop + vertex 571.197 70.1473 0.0795087 + vertex 581.929 73.1579 0.0811986 + vertex 572.632 66.4533 0.1704 + endloop + endfacet + facet normal 0.0034126 -0.0126545 -0.999914 + outer loop + vertex 580.242 76.6984 0.0306335 + vertex 587.914 78.3003 0.0365448 + vertex 581.929 73.1579 0.0811986 + endloop + endfacet + facet normal 0.00202887 -0.00650995 -0.999977 + outer loop + vertex 569.422 73.7381 0.0279525 + vertex 578.058 80.1883 0.00348116 + vertex 580.242 76.6984 0.0306335 + endloop + endfacet + facet normal 0.00183612 -0.00663061 -0.999976 + outer loop + vertex 578.058 80.1883 0.00348116 + vertex 587.677 82.5749 0.00532008 + vertex 580.242 76.6984 0.0306335 + endloop + endfacet + facet normal 0.00200447 -0.00647728 -0.999977 + outer loop + vertex 567.087 77.0931 0.00154024 + vertex 578.058 80.1883 0.00348116 + vertex 569.422 73.7381 0.0279525 + endloop + endfacet + facet normal 0.000858657 -0.00241623 -0.999997 + outer loop + vertex 567.087 77.0931 0.00154024 + vertex 575.089 83.2427 -0.00644759 + vertex 578.058 80.1883 0.00348116 + endloop + endfacet + facet normal 0.000732313 -0.00253901 -0.999997 + outer loop + vertex 575.089 83.2427 -0.00644759 + vertex 583.922 85.7664 -0.00638703 + vertex 578.058 80.1883 0.00348116 + endloop + endfacet + facet normal 0.000725429 -0.00224287 -0.999997 + outer loop + vertex 564.268 80.0951 -0.00723806 + vertex 575.089 83.2427 -0.00644759 + vertex 567.087 77.0931 0.00154024 + endloop + endfacet + facet normal 4.43236e-05 9.87532e-05 -1 + outer loop + vertex 564.268 80.0951 -0.00723806 + vertex 571.776 85.8278 -0.00633916 + vertex 575.089 83.2427 -0.00644759 + endloop + endfacet + facet normal -3.41453e-05 -1.82089e-06 -1 + outer loop + vertex 571.776 85.8278 -0.00633916 + vertex 580.449 88.3665 -0.00663992 + vertex 575.089 83.2427 -0.00644759 + endloop + endfacet + facet normal -4.90911e-05 0.000221094 -1 + outer loop + vertex 561.145 82.7226 -0.0065038 + vertex 571.776 85.8278 -0.00633916 + vertex 564.268 80.0951 -0.00723806 + endloop + endfacet + facet normal -0.000223143 0.000816985 -1 + outer loop + vertex 561.145 82.7226 -0.0065038 + vertex 568.271 87.9639 -0.00381202 + vertex 571.776 85.8278 -0.00633916 + endloop + endfacet + facet normal -0.000264713 0.000748781 -1 + outer loop + vertex 568.271 87.9639 -0.00381202 + vertex 576.668 90.482 -0.00414908 + vertex 571.776 85.8278 -0.00633916 + endloop + endfacet + facet normal -0.000275917 0.000888742 -1 + outer loop + vertex 557.818 85.0003 -0.00356167 + vertex 568.271 87.9639 -0.00381202 + vertex 561.145 82.7226 -0.0065038 + endloop + endfacet + facet normal -0.00016939 0.000512998 -1 + outer loop + vertex 557.818 85.0003 -0.00356167 + vertex 564.919 89.8988 -0.0022516 + vertex 568.271 87.9639 -0.00381202 + endloop + endfacet + facet normal -0.000170391 0.000511263 -1 + outer loop + vertex 564.919 89.8988 -0.0022516 + vertex 572.689 91.7518 -0.00262808 + vertex 568.271 87.9639 -0.00381202 + endloop + endfacet + facet normal -0.000180576 0.000529213 -1 + outer loop + vertex 554.334 86.9646 -0.00189299 + vertex 564.919 89.8988 -0.0022516 + vertex 557.818 85.0003 -0.00356167 + endloop + endfacet + facet normal -7.00351e-05 0.000130437 -1 + outer loop + vertex 554.334 86.9646 -0.00189299 + vertex 561.34 91.5692 -0.00178304 + vertex 564.919 89.8988 -0.0022516 + endloop + endfacet + facet normal -6.81429e-05 0.000134492 -1 + outer loop + vertex 561.34 91.5692 -0.00178304 + vertex 570.717 94.0819 -0.00208405 + vertex 564.919 89.8988 -0.0022516 + endloop + endfacet + facet normal -6.83836e-05 0.000127924 -1 + outer loop + vertex 550.738 88.6497 -0.0014315 + vertex 561.34 91.5692 -0.00178304 + vertex 554.334 86.9646 -0.00189299 + endloop + endfacet + facet normal -4.17469e-05 3.11921e-05 -1 + outer loop + vertex 550.738 88.6497 -0.0014315 + vertex 557.661 92.9853 -0.00158528 + vertex 561.34 91.5692 -0.00178304 + endloop + endfacet + facet normal -4.00918e-05 3.54922e-05 -1 + outer loop + vertex 557.661 92.9853 -0.00158528 + vertex 565.575 94.8539 -0.00183626 + vertex 561.34 91.5692 -0.00178304 + endloop + endfacet + facet normal -3.45128e-05 1.96406e-05 -1 + outer loop + vertex 547.147 90.1517 -0.00127807 + vertex 557.661 92.9853 -0.00158528 + vertex 550.738 88.6497 -0.0014315 + endloop + endfacet + facet normal -3.54695e-05 7.42207e-05 -1 + outer loop + vertex 532.084 88.3127 -0.000803283 + vertex 543.558 91.5517 -0.000969863 + vertex 535.603 86.9159 -0.00103177 + endloop + endfacet + facet normal -3.51215e-05 7.50975e-05 -1 + outer loop + vertex 523.761 83.6181 -0.000863511 + vertex 532.084 88.3127 -0.000803283 + vertex 535.603 86.9159 -0.00103177 + endloop + endfacet + facet normal -5.55839e-05 0.000145475 -1 + outer loop + vertex 532.084 88.3127 -0.000803283 + vertex 539.892 92.8351 -0.000579367 + vertex 543.558 91.5517 -0.000969863 + endloop + endfacet + facet normal -4.35762e-05 0.000124745 -1 + outer loop + vertex 528.544 89.6164 -0.00048638 + vertex 539.892 92.8351 -0.000579367 + vertex 532.084 88.3127 -0.000803283 + endloop + endfacet + facet normal -6.1939e-05 0.000121405 -1 + outer loop + vertex 547.147 90.1517 -0.00127807 + vertex 554.233 94.4798 -0.0011915 + vertex 557.661 92.9853 -0.00158528 + endloop + endfacet + facet normal -5.96333e-05 0.000126695 -1 + outer loop + vertex 554.233 94.4798 -0.0011915 + vertex 563.297 96.5047 -0.00147549 + vertex 557.661 92.9853 -0.00158528 + endloop + endfacet + facet normal -5.4e-05 0.00015 -1 + outer loop + vertex 539.892 92.8351 -0.000579367 + vertex 550.36 95.8198 -0.00069693 + vertex 543.558 91.5517 -0.000969863 + endloop + endfacet + facet normal -5.21419e-05 0.000143483 -1 + outer loop + vertex 539.892 92.8351 -0.000579367 + vertex 546.216 96.9087 -0.000324597 + vertex 550.36 95.8198 -0.00069693 + endloop + endfacet + facet normal -4.19405e-05 0.000127647 -1 + outer loop + vertex 536.181 94.0068 -0.000274171 + vertex 546.216 96.9087 -0.000324597 + vertex 539.892 92.8351 -0.000579367 + endloop + endfacet + facet normal -4.9779e-05 0.000152475 -1 + outer loop + vertex 546.216 96.9087 -0.000324597 + vertex 554.505 99.2854 -0.000374827 + vertex 550.36 95.8198 -0.00069693 + endloop + endfacet + facet normal -3.29171e-05 9.36677e-05 -1 + outer loop + vertex 546.216 96.9087 -0.000324597 + vertex 549.883 100.145 -0.000142138 + vertex 554.505 99.2854 -0.000374827 + endloop + endfacet + facet normal -2.87951e-05 8.89973e-05 -1 + outer loop + vertex 542.156 97.853 -0.000123658 + vertex 549.883 100.145 -0.000142138 + vertex 546.216 96.9087 -0.000324597 + endloop + endfacet + facet normal -3.88146e-05 0.000215678 -1 + outer loop + vertex 560.172 100.817 -0.000379746 + vertex 563.469 101.339 -0.000395186 + vertex 564.092 100.262 -0.000651723 + endloop + endfacet + facet normal -4.43235e-05 0.000281053 -1 + outer loop + vertex 564.092 100.262 -0.000651723 + vertex 567.153 100.469 -0.000729249 + vertex 566.769 98.933 -0.00114384 + endloop + endfacet + facet normal -3.76526e-05 0.000279387 -1 + outer loop + vertex 566.769 98.933 -0.00114384 + vertex 567.153 100.469 -0.000729249 + vertex 571.575 99.0121 -0.00130272 + endloop + endfacet + facet normal -1.28967e-05 0.00035455 -1 + outer loop + vertex 571.575 99.0121 -0.00130272 + vertex 567.153 100.469 -0.000729249 + vertex 571.405 100.593 -0.00074007 + endloop + endfacet + facet normal -7.71688e-05 0.000205192 -1 + outer loop + vertex 554.233 94.4798 -0.0011915 + vertex 559.838 98.345 -0.000830932 + vertex 563.297 96.5047 -0.00147549 + endloop + endfacet + facet normal -3.74167e-05 0.000265037 -1 + outer loop + vertex 566.769 98.933 -0.00114384 + vertex 571.575 99.0121 -0.00130272 + vertex 570.612 97.1485 -0.00176059 + endloop + endfacet + facet normal -3.95917e-05 0.000266161 -1 + outer loop + vertex 570.612 97.1485 -0.00176059 + vertex 571.575 99.0121 -0.00130272 + vertex 575.2 97.7069 -0.0017936 + endloop + endfacet + facet normal 9.32142e-06 0.000402002 -1 + outer loop + vertex 575.2 97.7069 -0.0017936 + vertex 571.575 99.0121 -0.00130272 + vertex 577.299 98.5545 -0.00143332 + endloop + endfacet + facet normal 2.97517e-05 0.000351403 -1 + outer loop + vertex 579.037 96.4281 -0.0021288 + vertex 575.2 97.7069 -0.0017936 + vertex 577.299 98.5545 -0.00143332 + endloop + endfacet + facet normal -1.92788e-05 0.000204274 -1 + outer loop + vertex 575.514 96.2812 -0.00209091 + vertex 575.2 97.7069 -0.0017936 + vertex 579.037 96.4281 -0.0021288 + endloop + endfacet + facet normal -6.28356e-05 0.000131823 -1 + outer loop + vertex 557.661 92.9853 -0.00158528 + vertex 563.297 96.5047 -0.00147549 + vertex 565.575 94.8539 -0.00183626 + endloop + endfacet + facet normal -4.2416e-05 3.8489e-05 -1 + outer loop + vertex 561.34 91.5692 -0.00178304 + vertex 565.575 94.8539 -0.00183626 + vertex 570.717 94.0819 -0.00208405 + endloop + endfacet + facet normal -3.17249e-05 0.000201528 -1 + outer loop + vertex 570.612 97.1485 -0.00176059 + vertex 575.2 97.7069 -0.0017936 + vertex 575.514 96.2812 -0.00209091 + endloop + endfacet + facet normal -2.14654e-05 0.000256688 -1 + outer loop + vertex 575.514 96.2812 -0.00209091 + vertex 579.037 96.4281 -0.0021288 + vertex 578.097 94.0881 -0.00270929 + endloop + endfacet + facet normal -0.000128253 0.00029957 -1 + outer loop + vertex 578.097 94.0881 -0.00270929 + vertex 579.037 96.4281 -0.0021288 + vertex 583.208 94.4078 -0.00326902 + endloop + endfacet + facet normal -3.60593e-05 0.000489928 -1 + outer loop + vertex 583.208 94.4078 -0.00326902 + vertex 579.037 96.4281 -0.0021288 + vertex 583.335 96.3876 -0.00230365 + endloop + endfacet + facet normal -8.66503e-05 0.000160142 -1 + outer loop + vertex 564.919 89.8988 -0.0022516 + vertex 570.717 94.0819 -0.00208405 + vertex 572.689 91.7518 -0.00262808 + endloop + endfacet + facet normal -0.000205896 0.000552668 -1 + outer loop + vertex 568.271 87.9639 -0.00381202 + vertex 572.689 91.7518 -0.00262808 + vertex 576.668 90.482 -0.00414908 + endloop + endfacet + facet normal -0.000149216 0.000634658 -1 + outer loop + vertex 578.097 94.0881 -0.00270929 + vertex 583.208 94.4078 -0.00326902 + vertex 582.766 92.0916 -0.00467304 + endloop + endfacet + facet normal -0.000284588 0.000660506 -1 + outer loop + vertex 582.766 92.0916 -0.00467304 + vertex 583.208 94.4078 -0.00326902 + vertex 586.437 92.4604 -0.00547418 + endloop + endfacet + facet normal -0.000172566 0.000846223 -1 + outer loop + vertex 586.437 92.4604 -0.00547418 + vertex 583.208 94.4078 -0.00326902 + vertex 587.823 93.5972 -0.00475128 + endloop + endfacet + facet normal -0.000283121 0.000980979 -0.999999 + outer loop + vertex 589.622 90.643 -0.00815887 + vertex 586.437 92.4604 -0.00547418 + vertex 587.823 93.5972 -0.00475128 + endloop + endfacet + facet normal -0.000385125 0.000802198 -1 + outer loop + vertex 586.383 89.9354 -0.00747879 + vertex 586.437 92.4604 -0.00547418 + vertex 589.622 90.643 -0.00815887 + endloop + endfacet + facet normal -0.00024903 0.000732298 -1 + outer loop + vertex 571.776 85.8278 -0.00633916 + vertex 576.668 90.482 -0.00414908 + vertex 580.449 88.3665 -0.00663992 + endloop + endfacet + facet normal -0.000298635 0.000800339 -1 + outer loop + vertex 582.766 92.0916 -0.00467304 + vertex 586.437 92.4604 -0.00547418 + vertex 586.383 89.9354 -0.00747879 + endloop + endfacet + facet normal 2.50748e-05 -6.37653e-05 -1 + outer loop + vertex 575.089 83.2427 -0.00644759 + vertex 580.449 88.3665 -0.00663992 + vertex 583.922 85.7664 -0.00638703 + endloop + endfacet + facet normal -0.000200005 -4.54103e-05 -1 + outer loop + vertex 586.383 89.9354 -0.00747879 + vertex 589.622 90.643 -0.00815887 + vertex 589.717 87.4475 -0.00803275 + endloop + endfacet + facet normal -0.000193015 -4.52025e-05 -1 + outer loop + vertex 589.717 87.4475 -0.00803275 + vertex 589.622 90.643 -0.00815887 + vertex 592.904 87.9476 -0.00867036 + endloop + endfacet + facet normal 2.86037e-05 0.000224587 -1 + outer loop + vertex 592.904 87.9476 -0.00867036 + vertex 589.622 90.643 -0.00815887 + vertex 592.647 90.9683 -0.0079993 + endloop + endfacet + facet normal 0.000852365 -0.00266523 -0.999996 + outer loop + vertex 578.058 80.1883 0.00348116 + vertex 583.922 85.7664 -0.00638703 + vertex 587.677 82.5749 0.00532008 + endloop + endfacet + facet normal 0.000169086 -0.00235232 -0.999997 + outer loop + vertex 589.717 87.4475 -0.00803275 + vertex 592.904 87.9476 -0.00867036 + vertex 592.722 85.1653 -0.00215639 + endloop + endfacet + facet normal 0.00177087 -0.00245714 -0.999995 + outer loop + vertex 592.722 85.1653 -0.00215639 + vertex 592.904 87.9476 -0.00867036 + vertex 595.553 84.6698 0.00407443 + endloop + endfacet + facet normal 0.000326785 -0.00362414 -0.999993 + outer loop + vertex 595.553 84.6698 0.00407443 + vertex 592.904 87.9476 -0.00867036 + vertex 595.813 87.5797 -0.0063863 + endloop + endfacet + facet normal 0.000953617 -0.00712578 -0.999974 + outer loop + vertex 592.722 85.1653 -0.00215639 + vertex 595.553 84.6698 0.00407443 + vertex 593.714 81.103 0.0277385 + endloop + endfacet + facet normal 0.00282281 -0.00808911 -0.999963 + outer loop + vertex 593.714 81.103 0.0277385 + vertex 595.553 84.6698 0.00407443 + vertex 598.151 80.9928 0.0411541 + endloop + endfacet + facet normal 0.00129636 -0.00916776 -0.999957 + outer loop + vertex 598.151 80.9928 0.0411541 + vertex 595.553 84.6698 0.00407443 + vertex 598.646 84.2093 0.0123065 + endloop + endfacet + facet normal 0.00226933 -0.00717871 -0.999972 + outer loop + vertex 580.242 76.6984 0.0306335 + vertex 587.677 82.5749 0.00532008 + vertex 587.914 78.3003 0.0365448 + endloop + endfacet + facet normal 0.0041099 -0.0134659 -0.999901 + outer loop + vertex 581.929 73.1579 0.0811986 + vertex 587.914 78.3003 0.0365448 + vertex 590.799 75.7464 0.0827961 + endloop + endfacet + facet normal 0.00672381 -0.0224229 -0.999726 + outer loop + vertex 581.929 73.1579 0.0811986 + vertex 590.799 75.7464 0.0827961 + vertex 583.794 69.6066 0.173389 + endloop + endfacet + facet normal 0.00268943 -0.0134558 -0.999906 + outer loop + vertex 593.714 81.103 0.0277385 + vertex 598.151 80.9928 0.0411541 + vertex 597.009 77.3781 0.0867264 + endloop + endfacet + facet normal 0.00570222 -0.0144072 -0.99988 + outer loop + vertex 597.009 77.3781 0.0867264 + vertex 598.151 80.9928 0.0411541 + vertex 600.674 77.2814 0.109018 + endloop + endfacet + facet normal 0.00325971 -0.0160671 -0.999866 + outer loop + vertex 600.674 77.2814 0.109018 + vertex 598.151 80.9928 0.0411541 + vertex 601.744 80.415 0.062151 + endloop + endfacet + facet normal 0.00554956 -0.0201676 -0.999781 + outer loop + vertex 597.009 77.3781 0.0867264 + vertex 600.674 77.2814 0.109018 + vertex 599.584 74.6643 0.155763 + endloop + endfacet + facet normal 0.014003 -0.0236833 -0.999621 + outer loop + vertex 599.584 74.6643 0.155763 + vertex 600.674 77.2814 0.109018 + vertex 602.296 73.5493 0.220167 + endloop + endfacet + facet normal 0.00717947 -0.0266496 -0.999619 + outer loop + vertex 602.296 73.5493 0.220167 + vertex 600.674 77.2814 0.109018 + vertex 603.639 75.9322 0.166284 + endloop + endfacet + facet normal 0.00859958 -0.0368048 -0.999285 + outer loop + vertex 599.584 74.6643 0.155763 + vertex 602.296 73.5493 0.220167 + vertex 599.679 71.0459 0.289852 + endloop + endfacet + facet normal 0.0176626 -0.0462634 -0.998773 + outer loop + vertex 599.679 71.0459 0.289852 + vertex 602.296 73.5493 0.220167 + vertex 602.729 70.0476 0.39002 + endloop + endfacet + facet normal 0.00706182 -0.0228084 -0.999715 + outer loop + vertex 583.794 69.6066 0.173389 + vertex 590.799 75.7464 0.0827961 + vertex 593.903 72.0693 0.188614 + endloop + endfacet + facet normal 0.00661788 -0.0224785 -0.999725 + outer loop + vertex 572.632 66.4533 0.1704 + vertex 581.929 73.1579 0.0811986 + vertex 583.794 69.6066 0.173389 + endloop + endfacet + facet normal 0.00611308 -0.0222249 -0.999734 + outer loop + vertex 560.564 62.9946 0.173496 + vertex 571.197 70.1473 0.0795087 + vertex 572.632 66.4533 0.1704 + endloop + endfacet + facet normal 0.00590439 -0.0231279 -0.999715 + outer loop + vertex 548.148 59.5056 0.180887 + vertex 559.2 66.7559 0.0784257 + vertex 560.564 62.9946 0.173496 + endloop + endfacet + facet normal 0.00632602 -0.0237704 -0.999697 + outer loop + vertex 546.744 63.2938 0.0819276 + vertex 559.2 66.7559 0.0784257 + vertex 548.148 59.5056 0.180887 + endloop + endfacet + facet normal 0.00381485 -0.0136929 -0.999899 + outer loop + vertex 544.949 66.9239 0.0253694 + vertex 557.386 70.3591 0.0257755 + vertex 546.744 63.2938 0.0819276 + endloop + endfacet + facet normal 0.0019425 -0.00671927 -0.999976 + outer loop + vertex 542.72 70.2941 -0.00160602 + vertex 555.088 73.7061 -0.000507243 + vertex 544.949 66.9239 0.0253694 + endloop + endfacet + facet normal 0.000584449 -0.0019535 -0.999998 + outer loop + vertex 540.114 73.3427 -0.00908523 + vertex 552.393 76.7317 -0.00852878 + vertex 542.72 70.2941 -0.00160602 + endloop + endfacet + facet normal -0.000184938 0.000668639 -1 + outer loop + vertex 537.174 76.0238 -0.00674899 + vertex 549.37 79.3972 -0.0067488 + vertex 540.114 73.3427 -0.00908523 + endloop + endfacet + facet normal -0.000330594 0.00111228 -0.999999 + outer loop + vertex 533.982 78.3463 -0.00311022 + vertex 546.096 81.7079 -0.00337616 + vertex 537.174 76.0238 -0.00674899 + endloop + endfacet + facet normal -0.00018766 0.00059368 -1 + outer loop + vertex 530.629 80.3395 -0.00129782 + vertex 542.653 83.6894 -0.00156536 + vertex 533.982 78.3463 -0.00311022 + endloop + endfacet + facet normal -5.07213e-05 0.00012034 -1 + outer loop + vertex 527.205 82.0706 -0.000915822 + vertex 539.131 85.3986 -0.00112022 + vertex 530.629 80.3395 -0.00129782 + endloop + endfacet + facet normal -1.45831e-05 1.34609e-06 -1 + outer loop + vertex 523.761 83.6181 -0.000863511 + vertex 535.603 86.9159 -0.00103177 + vertex 527.205 82.0706 -0.000915822 + endloop + endfacet + facet normal -2.75782e-05 6.17237e-05 -1 + outer loop + vertex 520.287 85.0343 -0.000680277 + vertex 532.084 88.3127 -0.000803283 + vertex 523.761 83.6181 -0.000863511 + endloop + endfacet + facet normal -3.13626e-05 9.43107e-05 -1 + outer loop + vertex 505.071 83.1645 -0.000344403 + vertex 516.714 86.3403 -0.000410034 + vertex 508.73 81.877 -0.000580571 + endloop + endfacet + facet normal -3.26401e-05 9.06808e-05 -1 + outer loop + vertex 498.369 79.0914 -0.000495 + vertex 505.071 83.1645 -0.000344403 + vertex 508.73 81.877 -0.000580571 + endloop + endfacet + facet normal -2.97364e-05 8.83491e-05 -1 + outer loop + vertex 505.071 83.1645 -0.000344403 + vertex 512.953 87.5286 -0.000193229 + vertex 516.714 86.3403 -0.000410034 + endloop + endfacet + facet normal -2.41277e-05 7.82188e-05 -1 + outer loop + vertex 501.272 84.3426 -0.000160585 + vertex 512.953 87.5286 -0.000193229 + vertex 505.071 83.1645 -0.000344403 + endloop + endfacet + facet normal -2.54069e-05 7.40932e-05 -1 + outer loop + vertex 494.693 80.3688 -0.000287876 + vertex 501.272 84.3426 -0.000160585 + vertex 505.071 83.1645 -0.000344403 + endloop + endfacet + facet normal -1.67883e-05 5.13088e-05 -1 + outer loop + vertex 501.272 84.3426 -0.000160585 + vertex 509.118 88.632 -7.2225e-05 + vertex 512.953 87.5286 -0.000193229 + endloop + endfacet + facet normal -1.60791e-05 5.37744e-05 -1 + outer loop + vertex 509.118 88.632 -7.2225e-05 + vertex 521.043 91.9202 -8.71479e-05 + vertex 512.953 87.5286 -0.000193229 + endloop + endfacet + facet normal -1.99483e-05 6.09017e-05 -1 + outer loop + vertex 512.953 87.5286 -0.000193229 + vertex 521.043 91.9202 -8.71479e-05 + vertex 524.893 90.8233 -0.000230761 + endloop + endfacet + facet normal -8.81205e-06 2.74196e-05 -1 + outer loop + vertex 509.118 88.632 -7.2225e-05 + vertex 517.19 92.9502 -2.49518e-05 + vertex 521.043 91.9202 -8.71479e-05 + endloop + endfacet + facet normal -8.4745e-06 2.86823e-05 -1 + outer loop + vertex 517.19 92.9502 -2.49518e-05 + vertex 528.397 96.0873 -2.99501e-05 + vertex 521.043 91.9202 -8.71479e-05 + endloop + endfacet + facet normal -1.05243e-05 3.22999e-05 -1 + outer loop + vertex 521.043 91.9202 -8.71479e-05 + vertex 528.397 96.0873 -2.99501e-05 + vertex 532.361 95.0854 -0.00010403 + endloop + endfacet + facet normal -4.3603e-06 1.39841e-05 -1 + outer loop + vertex 517.19 92.9502 -2.49518e-05 + vertex 524.469 97.0041 9.62153e-15 + vertex 528.397 96.0873 -2.99501e-05 + endloop + endfacet + facet normal -4.20757e-06 1.46386e-05 -1 + outer loop + vertex 524.469 97.0041 9.62153e-15 + vertex 534.878 99.9961 9.62153e-15 + vertex 528.397 96.0873 -2.99501e-05 + endloop + endfacet + facet normal -5.195e-06 1.62758e-05 -1 + outer loop + vertex 528.397 96.0873 -2.99501e-05 + vertex 534.878 99.9961 9.62153e-15 + vertex 538.377 98.8868 -3.62295e-05 + endloop + endfacet + facet normal -3.49057e-06 1.24225e-05 -1 + outer loop + vertex 513.933 94.0437 9.62153e-15 + vertex 524.469 97.0041 9.62153e-15 + vertex 517.19 92.9502 -2.49518e-05 + endloop + endfacet + facet normal -3.65582e-06 1.19304e-05 -1 + outer loop + vertex 505.741 89.7868 -2.0837e-05 + vertex 513.933 94.0437 9.62153e-15 + vertex 517.19 92.9502 -2.49518e-05 + endloop + endfacet + facet normal -2.85347e-06 1.03863e-05 -1 + outer loop + vertex 503.331 91.131 9.62153e-15 + vertex 513.933 94.0437 9.62153e-15 + vertex 505.741 89.7868 -2.0837e-05 + endloop + endfacet + facet normal -3.0248e-06 1.00791e-05 -1 + outer loop + vertex 494.974 86.8494 -1.78761e-05 + vertex 503.331 91.131 9.62153e-15 + vertex 505.741 89.7868 -2.0837e-05 + endloop + endfacet + facet normal -5.71517e-06 1.99403e-05 -1 + outer loop + vertex 494.974 86.8494 -1.78761e-05 + vertex 505.741 89.7868 -2.0837e-05 + vertex 497.712 85.5174 -6.00845e-05 + endloop + endfacet + facet normal -6.10283e-06 1.91434e-05 -1 + outer loop + vertex 488.041 82.9228 -5.07319e-05 + vertex 494.974 86.8494 -1.78761e-05 + vertex 497.712 85.5174 -6.00845e-05 + endloop + endfacet + facet normal -7.34814e-06 2.30112e-05 -1 + outer loop + vertex 497.712 85.5174 -6.00845e-05 + vertex 505.741 89.7868 -2.0837e-05 + vertex 509.118 88.632 -7.2225e-05 + endloop + endfacet + facet normal -2.35896e-06 8.77947e-06 -1 + outer loop + vertex 492.652 88.2617 9.62153e-15 + vertex 503.331 91.131 9.62153e-15 + vertex 494.974 86.8494 -1.78761e-05 + endloop + endfacet + facet normal -2.51022e-06 8.53082e-06 -1 + outer loop + vertex 485.527 84.3248 -1.56985e-05 + vertex 492.652 88.2617 9.62153e-15 + vertex 494.974 86.8494 -1.78761e-05 + endloop + endfacet + facet normal -6.99932e-06 2.40311e-05 -1 + outer loop + vertex 505.741 89.7868 -2.0837e-05 + vertex 517.19 92.9502 -2.49518e-05 + vertex 509.118 88.632 -7.2225e-05 + endloop + endfacet + facet normal -1.33659e-05 4.50485e-05 -1 + outer loop + vertex 497.712 85.5174 -6.00845e-05 + vertex 509.118 88.632 -7.2225e-05 + vertex 501.272 84.3426 -0.000160585 + endloop + endfacet + facet normal -1.41415e-05 4.26988e-05 -1 + outer loop + vertex 491.087 81.6078 -0.00013333 + vertex 497.712 85.5174 -6.00845e-05 + vertex 501.272 84.3426 -0.000160585 + endloop + endfacet + facet normal -4.44393e-05 0.000122401 -1 + outer loop + vertex 520.287 85.0343 -0.000680277 + vertex 528.544 89.6164 -0.00048638 + vertex 532.084 88.3127 -0.000803283 + endloop + endfacet + facet normal -2.85542e-05 9.20899e-05 -1 + outer loop + vertex 512.953 87.5286 -0.000193229 + vertex 524.893 90.8233 -0.000230761 + vertex 516.714 86.3403 -0.000410034 + endloop + endfacet + facet normal -4.32359e-05 0.000123545 -1 + outer loop + vertex 528.544 89.6164 -0.00048638 + vertex 536.181 94.0068 -0.000274171 + vertex 539.892 92.8351 -0.000579367 + endloop + endfacet + facet normal -1.9229e-05 6.34266e-05 -1 + outer loop + vertex 521.043 91.9202 -8.71479e-05 + vertex 532.361 95.0854 -0.00010403 + vertex 524.893 90.8233 -0.000230761 + endloop + endfacet + facet normal -2.96723e-05 8.52257e-05 -1 + outer loop + vertex 536.181 94.0068 -0.000274171 + vertex 542.156 97.853 -0.000123658 + vertex 546.216 96.9087 -0.000324597 + endloop + endfacet + facet normal -1.01289e-05 3.38642e-05 -1 + outer loop + vertex 528.397 96.0873 -2.99501e-05 + vertex 538.377 98.8868 -3.62295e-05 + vertex 532.361 95.0854 -0.00010403 + endloop + endfacet + facet normal -4.98043e-06 1.69525e-05 -1 + outer loop + vertex 534.878 99.9961 9.62153e-15 + vertex 544.383 102.789 9.62153e-15 + vertex 538.377 98.8868 -3.62295e-05 + endloop + endfacet + facet normal -1.61719e-05 4.64487e-05 -1 + outer loop + vertex 542.156 97.853 -0.000123658 + vertex 545.607 100.673 -4.84727e-05 + vertex 549.883 100.145 -0.000142138 + endloop + endfacet + facet normal -3.10348e-05 0.000103783 -1 + outer loop + vertex 554.505 99.2854 -0.000374827 + vertex 549.883 100.145 -0.000142138 + vertex 555.618 101.728 -0.000155898 + endloop + endfacet + facet normal -1.33401e-05 5.05954e-05 -1 + outer loop + vertex 555.618 101.728 -0.000155898 + vertex 555.265 103.618 -5.55499e-05 + vertex 559.895 102.339 -0.000182041 + endloop + endfacet + facet normal -6.58954e-06 2.18212e-05 -1 + outer loop + vertex 551.859 105.027 9.62153e-15 + vertex 552.205 105.131 9.62153e-15 + vertex 550.77 102.792 -4.15866e-05 + endloop + endfacet + facet normal -9.62281e-06 6.40475e-05 -1 + outer loop + vertex 559.895 102.339 -0.000182041 + vertex 555.265 103.618 -5.55499e-05 + vertex 559.428 103.938 -7.5108e-05 + endloop + endfacet + facet normal -2.54715e-06 1.26593e-05 -1 + outer loop + vertex 559.825 105.853 -1.63296e-05 + vertex 565.593 107.64 -8.39019e-06 + vertex 562.336 105.267 -3.01433e-05 + endloop + endfacet + facet normal -7.16593e-06 3.3481e-05 -1 + outer loop + vertex 562.336 105.267 -3.01433e-05 + vertex 568.05 106.718 -2.25163e-05 + vertex 564.607 104.217 -8.15806e-05 + endloop + endfacet + facet normal -2.00608e-05 6.10041e-05 -1 + outer loop + vertex 559.428 103.938 -7.5108e-05 + vertex 565.028 102.192 -0.000294006 + vertex 559.895 102.339 -0.000182041 + endloop + endfacet + facet normal -8.34784e-06 4.86829e-05 -1 + outer loop + vertex 564.607 104.217 -8.15806e-05 + vertex 571.341 105.994 -5.12404e-05 + vertex 568.3 103.669 -0.000139081 + endloop + endfacet + facet normal -2.02434e-05 9.93587e-05 -1 + outer loop + vertex 568.3 103.669 -0.000139081 + vertex 574.71 105.261 -0.000110592 + vertex 571.078 102.664 -0.000295103 + endloop + endfacet + facet normal -9.57588e-06 0.000240811 -1 + outer loop + vertex 565.028 102.192 -0.000294006 + vertex 571.405 100.593 -0.00074007 + vertex 567.153 100.469 -0.000729249 + endloop + endfacet + facet normal -2.14368e-05 0.000125845 -1 + outer loop + vertex 571.078 102.664 -0.000295103 + vertex 577.981 104.451 -0.00021826 + vertex 574.791 102.019 -0.000455891 + endloop + endfacet + facet normal -3.80119e-05 0.000192046 -1 + outer loop + vertex 574.791 102.019 -0.000455891 + vertex 581.164 103.546 -0.000405018 + vertex 577.389 100.843 -0.0007805 + endloop + endfacet + facet normal 5.68808e-06 0.000356555 -1 + outer loop + vertex 571.405 100.593 -0.00074007 + vertex 577.299 98.5545 -0.00143332 + vertex 571.575 99.0121 -0.00130272 + endloop + endfacet + facet normal -3.66995e-05 0.000204578 -1 + outer loop + vertex 577.389 100.843 -0.0007805 + vertex 584.327 102.566 -0.000682582 + vertex 581.022 100.051 -0.00107588 + endloop + endfacet + facet normal -4.45061e-05 0.000223503 -1 + outer loop + vertex 581.022 100.051 -0.00107588 + vertex 587.48 101.541 -0.00103023 + vertex 583.515 98.7628 -0.00147475 + endloop + endfacet + facet normal -3.78875e-05 0.000296111 -1 + outer loop + vertex 577.299 98.5545 -0.00143332 + vertex 583.335 96.3876 -0.00230365 + vertex 579.037 96.4281 -0.0021288 + endloop + endfacet + facet normal -4.10188e-05 0.000218144 -1 + outer loop + vertex 583.515 98.7628 -0.00147475 + vertex 590.536 100.435 -0.00139789 + vertex 587.035 97.8208 -0.00182464 + endloop + endfacet + facet normal -8.63827e-05 0.000410427 -1 + outer loop + vertex 587.035 97.8208 -0.00182464 + vertex 593.5 99.2021 -0.00181616 + vertex 589.194 96.1851 -0.00268244 + endloop + endfacet + facet normal -0.000232948 0.000502518 -1 + outer loop + vertex 583.335 96.3876 -0.00230365 + vertex 587.823 93.5972 -0.00475128 + vertex 583.208 94.4078 -0.00326902 + endloop + endfacet + facet normal -0.000141374 0.000714049 -1 + outer loop + vertex 589.194 96.1851 -0.00268244 + vertex 596.492 97.7506 -0.0025963 + vertex 592.662 94.2979 -0.00452027 + endloop + endfacet + facet normal -6.69326e-05 0.00111268 -0.999999 + outer loop + vertex 587.823 93.5972 -0.00475128 + vertex 592.647 90.9683 -0.0079993 + vertex 589.622 90.643 -0.00815887 + endloop + endfacet + facet normal -0.0001995 0.000952499 -1 + outer loop + vertex 592.662 94.2979 -0.00452027 + vertex 599.544 96.1721 -0.00410799 + vertex 596.01 92.9615 -0.00646122 + endloop + endfacet + facet normal -0.000176775 0.000689069 -1 + outer loop + vertex 596.01 92.9615 -0.00646122 + vertex 602.314 94.349 -0.00661958 + vertex 597.767 90.6449 -0.008368 + endloop + endfacet + facet normal 0.000821937 0.000292105 -1 + outer loop + vertex 592.647 90.9683 -0.0079993 + vertex 595.813 87.5797 -0.0063863 + vertex 592.904 87.9476 -0.00867036 + endloop + endfacet + facet normal 0.000247585 -0.00122687 -0.999999 + outer loop + vertex 597.767 90.6449 -0.008368 + vertex 604.924 92.0588 -0.00833068 + vertex 600.397 87.7812 -0.00420325 + endloop + endfacet + facet normal 0.00209804 -0.00378284 -0.999991 + outer loop + vertex 595.813 87.5797 -0.0063863 + vertex 598.646 84.2093 0.0123065 + vertex 595.553 84.6698 0.00407443 + endloop + endfacet + facet normal 0.00131343 -0.00520325 -0.999986 + outer loop + vertex 600.397 87.7812 -0.00420325 + vertex 607.577 89.4059 -0.00322703 + vertex 603.093 84.7584 0.0150658 + endloop + endfacet + facet normal 0.0042956 -0.00962915 -0.999944 + outer loop + vertex 598.646 84.2093 0.0123065 + vertex 601.744 80.415 0.062151 + vertex 598.151 80.9928 0.0411541 + endloop + endfacet + facet normal 0.00258284 -0.00966816 -0.99995 + outer loop + vertex 603.093 84.7584 0.0150658 + vertex 610.001 86.5879 0.0152203 + vertex 605.68 82.4335 0.0442283 + endloop + endfacet + facet normal 0.00495917 -0.0174806 -0.999835 + outer loop + vertex 605.68 82.4335 0.0442283 + vertex 611.984 83.5555 0.0558797 + vertex 606.538 79.1557 0.105789 + endloop + endfacet + facet normal 0.0108228 -0.0186479 -0.999768 + outer loop + vertex 601.744 80.415 0.062151 + vertex 603.639 75.9322 0.166284 + vertex 600.674 77.2814 0.109018 + endloop + endfacet + facet normal 0.00763224 -0.0292403 -0.999543 + outer loop + vertex 606.538 79.1557 0.105789 + vertex 613.604 80.0955 0.132248 + vertex 608.049 75.2089 0.232782 + endloop + endfacet + facet normal 0.0266014 -0.0375799 -0.998939 + outer loop + vertex 603.639 75.9322 0.166284 + vertex 605.003 71.221 0.379833 + vertex 602.296 73.5493 0.220167 + endloop + endfacet + facet normal 0.0145804 -0.0546884 -0.998397 + outer loop + vertex 608.049 75.2089 0.232782 + vertex 615.137 76.3398 0.274349 + vertex 609.452 71.0422 0.481519 + endloop + endfacet + facet normal 0.0192949 -0.0460607 -0.998752 + outer loop + vertex 602.729 70.0476 0.39002 + vertex 602.296 73.5493 0.220167 + vertex 605.003 71.221 0.379833 + endloop + endfacet + facet normal 0.0088851 -0.0729244 -0.997298 + outer loop + vertex 599.679 71.0459 0.289852 + vertex 602.729 70.0476 0.39002 + vertex 599.882 66.2469 0.642567 + endloop + endfacet + facet normal 0.025034 -0.0904332 -0.995588 + outer loop + vertex 593.52 62.81 0.79479 + vertex 593.915 66.9948 0.4246 + vertex 599.882 66.2469 0.642567 + endloop + endfacet + facet normal 0.0273876 -0.0906481 -0.995506 + outer loop + vertex 585.666 61.3097 0.715328 + vertex 593.915 66.9948 0.4246 + vertex 593.52 62.81 0.79479 + endloop + endfacet + facet normal 0.0227781 -0.0803561 -0.996506 + outer loop + vertex 574.843 58.5672 0.689075 + vertex 585.033 65.56 0.358119 + vertex 585.666 61.3097 0.715328 + endloop + endfacet + facet normal 0.0216178 -0.0789506 -0.996644 + outer loop + vertex 562.826 55.199 0.695241 + vertex 573.802 62.5979 0.347203 + vertex 574.843 58.5672 0.689075 + endloop + endfacet + facet normal 0.0219465 -0.0805646 -0.996508 + outer loop + vertex 550.544 51.7258 0.705559 + vertex 561.678 59.1403 0.351317 + vertex 562.826 55.199 0.695241 + endloop + endfacet + facet normal 0.0215389 -0.0812647 -0.99646 + outer loop + vertex 538.501 48.3958 0.7168 + vertex 549.299 55.6324 0.360046 + vertex 550.544 51.7258 0.705559 + endloop + endfacet + facet normal 0.0213139 -0.0801799 -0.996553 + outer loop + vertex 527.536 45.5084 0.714603 + vertex 537.236 52.3014 0.375517 + vertex 538.501 48.3958 0.7168 + endloop + endfacet + facet normal 0.020469 -0.078979 -0.996666 + outer loop + vertex 526.389 49.4319 0.380133 + vertex 537.236 52.3014 0.375517 + vertex 527.536 45.5084 0.714603 + endloop + endfacet + facet normal 0.0112318 -0.0440899 -0.998964 + outer loop + vertex 525.172 53.2471 0.19807 + vertex 536.02 56.168 0.191117 + vertex 526.389 49.4319 0.380133 + endloop + endfacet + facet normal 0.00644512 -0.0256104 -0.999651 + outer loop + vertex 523.801 57.0143 0.0927167 + vertex 534.59 59.9588 0.086843 + vertex 525.172 53.2471 0.19807 + endloop + endfacet + facet normal 0.00400698 -0.0154027 -0.999873 + outer loop + vertex 522.084 60.6664 0.0295745 + vertex 532.835 63.6055 0.0273858 + vertex 523.801 57.0143 0.0927167 + endloop + endfacet + facet normal 0.00198625 -0.00756698 -0.999969 + outer loop + vertex 519.991 64.0936 -0.00051588 + vertex 530.689 67.0022 -0.00127584 + vertex 522.084 60.6664 0.0295745 + endloop + endfacet + facet normal 0.000428354 -0.00196291 -0.999998 + outer loop + vertex 517.516 67.1856 -0.00764539 + vertex 528.157 70.0662 -0.0087419 + vertex 519.991 64.0936 -0.00051588 + endloop + endfacet + facet normal -0.000259782 0.000613138 -1 + outer loop + vertex 514.692 69.9104 -0.00524107 + vertex 525.291 72.7614 -0.00624639 + vertex 517.516 67.1856 -0.00764539 + endloop + endfacet + facet normal -0.000299997 0.000925021 -1 + outer loop + vertex 511.646 72.278 -0.002137 + vertex 522.184 75.0978 -0.00269003 + vertex 514.692 69.9104 -0.00524107 + endloop + endfacet + facet normal -0.000132462 0.000418939 -1 + outer loop + vertex 508.437 74.2983 -0.000865658 + vertex 518.926 77.1151 -0.001075 + vertex 511.646 72.278 -0.002137 + endloop + endfacet + facet normal -2.204e-05 5.3033e-05 -1 + outer loop + vertex 505.185 76.0729 -0.000699877 + vertex 515.585 78.875 -0.000780474 + vertex 508.437 74.2983 -0.000865658 + endloop + endfacet + facet normal -9.79877e-06 4.20471e-06 -1 + outer loop + vertex 501.833 77.6627 -0.000660342 + vertex 512.205 80.4497 -0.000750259 + vertex 505.185 76.0729 -0.000699877 + endloop + endfacet + facet normal -2.38361e-05 5.79358e-05 -1 + outer loop + vertex 498.369 79.0914 -0.000495 + vertex 508.73 81.877 -0.000580571 + vertex 501.833 77.6627 -0.000660342 + endloop + endfacet + facet normal -2.76742e-05 8.25096e-05 -1 + outer loop + vertex 494.693 80.3688 -0.000287876 + vertex 505.071 83.1645 -0.000344403 + vertex 498.369 79.0914 -0.000495 + endloop + endfacet + facet normal -2.03023e-05 6.56428e-05 -1 + outer loop + vertex 491.087 81.6078 -0.00013333 + vertex 501.272 84.3426 -0.000160585 + vertex 494.693 80.3688 -0.000287876 + endloop + endfacet + facet normal -1.09891e-05 3.73567e-05 -1 + outer loop + vertex 488.041 82.9228 -5.07319e-05 + vertex 497.712 85.5174 -6.00845e-05 + vertex 491.087 81.6078 -0.00013333 + endloop + endfacet + facet normal -4.6703e-06 1.6614e-05 -1 + outer loop + vertex 485.527 84.3248 -1.56985e-05 + vertex 494.974 86.8494 -1.78761e-05 + vertex 488.041 82.9228 -5.07319e-05 + endloop + endfacet + facet normal -1.99959e-06 7.60663e-06 -1 + outer loop + vertex 482.011 85.4642 9.62153e-15 + vertex 492.652 88.2617 9.62153e-15 + vertex 485.527 84.3248 -1.56985e-05 + endloop + endfacet + facet normal -3.19157e-06 1.18339e-05 -1 + outer loop + vertex 463.204 80.6637 9.62153e-15 + vertex 467.143 78.5781 -3.72542e-05 + vertex 457.044 77.1858 -2.14988e-05 + endloop + endfacet + facet normal -2.6944e-06 1.09534e-05 -1 + outer loop + vertex 444.334 76.0218 9.62153e-15 + vertex 463.204 80.6637 9.62153e-15 + vertex 457.044 77.1858 -2.14988e-05 + endloop + endfacet + facet normal -2.96843e-06 1.39458e-05 -1 + outer loop + vertex 457.044 77.1858 -2.14988e-05 + vertex 445.785 74.208 -2.96051e-05 + vertex 444.334 76.0218 9.62153e-15 + endloop + endfacet + facet normal -3.24821e-06 1.37219e-05 -1 + outer loop + vertex 425.402 71.5403 9.62153e-15 + vertex 444.334 76.0218 9.62153e-15 + vertex 445.785 74.208 -2.96051e-05 + endloop + endfacet + facet normal -3.89805e-06 1.86873e-05 -1 + outer loop + vertex 445.785 74.208 -2.96051e-05 + vertex 429.811 70.373 -3.90026e-05 + vertex 425.402 71.5403 9.62153e-15 + endloop + endfacet + facet normal -4.08773e-06 1.79708e-05 -1 + outer loop + vertex 429.811 70.373 -3.90026e-05 + vertex 407.043 67.3643 9.62153e-15 + vertex 425.402 71.5403 9.62153e-15 + endloop + endfacet + facet normal -4.99872e-06 2.48648e-05 -1 + outer loop + vertex 410.905 66.0926 -5.0929e-05 + vertex 407.043 67.3643 9.62153e-15 + vertex 429.811 70.373 -3.90026e-05 + endloop + endfacet + facet normal -7.69696e-06 3.67825e-05 -1 + outer loop + vertex 433.772 69.0507 -0.000118125 + vertex 410.905 66.0926 -5.0929e-05 + vertex 429.811 70.373 -3.90026e-05 + endloop + endfacet + facet normal -7.32768e-06 3.78887e-05 -1 + outer loop + vertex 433.772 69.0507 -0.000118125 + vertex 429.811 70.373 -3.90026e-05 + vertex 449.973 72.8947 -9.11986e-05 + endloop + endfacet + facet normal -1.10573e-05 5.36077e-05 -1 + outer loop + vertex 453.524 71.4601 -0.000207362 + vertex 433.772 69.0507 -0.000118125 + vertex 449.973 72.8947 -9.11986e-05 + endloop + endfacet + facet normal -1.05746e-05 5.48022e-05 -1 + outer loop + vertex 453.524 71.4601 -0.000207362 + vertex 449.973 72.8947 -9.11986e-05 + vertex 465.252 74.4377 -0.000168208 + endloop + endfacet + facet normal -1.32445e-05 6.53184e-05 -1 + outer loop + vertex 466.682 72.7664 -0.000296308 + vertex 453.524 71.4601 -0.000207362 + vertex 465.252 74.4377 -0.000168208 + endloop + endfacet + facet normal -1.31191e-05 6.54257e-05 -1 + outer loop + vertex 466.682 72.7664 -0.000296308 + vertex 465.252 74.4377 -0.000168208 + vertex 475.942 74.6234 -0.000296295 + endloop + endfacet + facet normal -1.40173e-05 6.99045e-05 -1 + outer loop + vertex 471.73 71.6834 -0.000442774 + vertex 466.682 72.7664 -0.000296308 + vertex 475.942 74.6234 -0.000296295 + endloop + endfacet + facet normal -1.30144e-05 7.45785e-05 -1 + outer loop + vertex 471.73 71.6834 -0.000442774 + vertex 456.918 69.9872 -0.000376505 + vertex 466.682 72.7664 -0.000296308 + endloop + endfacet + facet normal -1.29043e-05 7.36167e-05 -1 + outer loop + vertex 460.653 68.3737 -0.000543482 + vertex 456.918 69.9872 -0.000376505 + vertex 471.73 71.6834 -0.000442774 + endloop + endfacet + facet normal -6.28654e-06 5.14683e-05 -1 + outer loop + vertex 476.036 69.8033 -0.000566609 + vertex 460.653 68.3737 -0.000543482 + vertex 471.73 71.6834 -0.000442774 + endloop + endfacet + facet normal -9.36974e-06 4.44063e-05 -1 + outer loop + vertex 476.036 69.8033 -0.000566609 + vertex 471.73 71.6834 -0.000442774 + vertex 482.637 72.7985 -0.000495455 + endloop + endfacet + facet normal -4.40572e-06 3.123e-05 -1 + outer loop + vertex 464.201 66.5016 -0.000617582 + vertex 460.653 68.3737 -0.000543482 + vertex 476.036 69.8033 -0.000566609 + endloop + endfacet + facet normal -9.4884e-06 4.94486e-05 -1 + outer loop + vertex 479.37 67.5661 -0.000708875 + vertex 464.201 66.5016 -0.000617582 + vertex 476.036 69.8033 -0.000566609 + endloop + endfacet + facet normal -1.23797e-05 4.51393e-05 -1 + outer loop + vertex 479.37 67.5661 -0.000708875 + vertex 476.036 69.8033 -0.000566609 + vertex 486.467 70.2601 -0.000675126 + endloop + endfacet + facet normal -8.25938e-06 3.1935e-05 -1 + outer loop + vertex 467.221 64.4801 -0.000707079 + vertex 464.201 66.5016 -0.000617582 + vertex 479.37 67.5661 -0.000708875 + endloop + endfacet + facet normal -4.1495e-05 0.000162783 -1 + outer loop + vertex 480.521 65.3709 -0.00111395 + vertex 467.221 64.4801 -0.000707079 + vertex 479.37 67.5661 -0.000708875 + endloop + endfacet + facet normal -6.71511e-05 0.000149339 -1 + outer loop + vertex 480.521 65.3709 -0.00111395 + vertex 479.37 67.5661 -0.000708875 + vertex 490.703 67.312 -0.00150783 + endloop + endfacet + facet normal -0.000144835 0.000556852 -1 + outer loop + vertex 485.028 63.5343 -0.00278942 + vertex 480.521 65.3709 -0.00111395 + vertex 490.703 67.312 -0.00150783 + endloop + endfacet + facet normal -0.000132709 0.000586608 -1 + outer loop + vertex 485.028 63.5343 -0.00278942 + vertex 470.221 62.3455 -0.00152189 + vertex 480.521 65.3709 -0.00111395 + endloop + endfacet + facet normal -0.000149655 0.000797662 -1 + outer loop + vertex 473.437 59.8799 -0.00396979 + vertex 470.221 62.3455 -0.00152189 + vertex 485.028 63.5343 -0.00278942 + endloop + endfacet + facet normal -0.000132576 0.000743494 -1 + outer loop + vertex 488.334 60.6405 -0.0053793 + vertex 473.437 59.8799 -0.00396979 + vertex 485.028 63.5343 -0.00278942 + endloop + endfacet + facet normal -0.000172611 0.000697754 -1 + outer loop + vertex 488.334 60.6405 -0.0053793 + vertex 485.028 63.5343 -0.00278942 + vertex 495.153 63.9526 -0.00424526 + endloop + endfacet + facet normal -0.000126852 0.000631366 -1 + outer loop + vertex 476.117 56.9316 -0.00617119 + vertex 473.437 59.8799 -0.00396979 + vertex 488.334 60.6405 -0.0053793 + endloop + endfacet + facet normal 0.000291499 -0.000746697 -1 + outer loop + vertex 490.916 57.3862 -0.00219656 + vertex 476.117 56.9316 -0.00617119 + vertex 488.334 60.6405 -0.0053793 + endloop + endfacet + facet normal 6.28001e-05 -0.000928193 -1 + outer loop + vertex 490.916 57.3862 -0.00219656 + vertex 488.334 60.6405 -0.0053793 + vertex 498.195 60.7548 -0.00486613 + endloop + endfacet + facet normal 0.000322955 -0.00177066 -0.999998 + outer loop + vertex 478.461 53.6618 0.000375578 + vertex 476.117 56.9316 -0.00617119 + vertex 490.916 57.3862 -0.00219656 + endloop + endfacet + facet normal 0.00150373 -0.00571945 -0.999983 + outer loop + vertex 493.1 53.8538 0.0212914 + vertex 478.461 53.6618 0.000375578 + vertex 490.916 57.3862 -0.00219656 + endloop + endfacet + facet normal 0.00101912 -0.00601903 -0.999981 + outer loop + vertex 493.1 53.8538 0.0212914 + vertex 490.916 57.3862 -0.00219656 + vertex 500.571 57.3225 0.00802684 + endloop + endfacet + facet normal 0.00152965 -0.00769779 -0.999969 + outer loop + vertex 480.463 50.1221 0.0306868 + vertex 478.461 53.6618 0.000375578 + vertex 493.1 53.8538 0.0212914 + endloop + endfacet + facet normal 0.00357801 -0.0146343 -0.999887 + outer loop + vertex 494.867 50.0538 0.0832301 + vertex 480.463 50.1221 0.0306868 + vertex 493.1 53.8538 0.0212914 + endloop + endfacet + facet normal 0.00298147 -0.0149116 -0.999884 + outer loop + vertex 494.867 50.0538 0.0832301 + vertex 493.1 53.8538 0.0212914 + vertex 502.518 53.5924 0.0532711 + endloop + endfacet + facet normal 0.00357019 -0.0162642 -0.999861 + outer loop + vertex 482.078 46.3977 0.0970375 + vertex 480.463 50.1221 0.0306868 + vertex 494.867 50.0538 0.0832301 + endloop + endfacet + facet normal 0.00633197 -0.025924 -0.999644 + outer loop + vertex 495.989 46.0398 0.194434 + vertex 482.078 46.3977 0.0970375 + vertex 494.867 50.0538 0.0832301 + endloop + endfacet + facet normal 0.00609073 -0.0259914 -0.999644 + outer loop + vertex 495.989 46.0398 0.194434 + vertex 494.867 50.0538 0.0832301 + vertex 504.043 49.4915 0.153757 + endloop + endfacet + facet normal 0.00633433 -0.025833 -0.999646 + outer loop + vertex 483.123 42.6789 0.199759 + vertex 482.078 46.3977 0.0970375 + vertex 495.989 46.0398 0.194434 + endloop + endfacet + facet normal 0.00934722 -0.0373664 -0.999258 + outer loop + vertex 495.209 42.4729 0.320519 + vertex 483.123 42.6789 0.199759 + vertex 495.989 46.0398 0.194434 + endloop + endfacet + facet normal 0.0120591 -0.0379577 -0.999207 + outer loop + vertex 495.209 42.4729 0.320519 + vertex 495.989 46.0398 0.194434 + vertex 505.257 44.4048 0.368389 + endloop + endfacet + facet normal 0.0171472 -0.0644558 -0.997773 + outer loop + vertex 497.455 39.3847 0.558603 + vertex 495.209 42.4729 0.320519 + vertex 505.257 44.4048 0.368389 + endloop + endfacet + facet normal 0.0163482 -0.0650349 -0.997749 + outer loop + vertex 497.455 39.3847 0.558603 + vertex 484.089 39.0723 0.359975 + vertex 495.209 42.4729 0.320519 + endloop + endfacet + facet normal 0.00926818 -0.0418987 -0.999079 + outer loop + vertex 484.089 39.0723 0.359975 + vertex 483.123 42.6789 0.199759 + vertex 495.209 42.4729 0.320519 + endloop + endfacet + facet normal 0.00985201 -0.0417424 -0.99908 + outer loop + vertex 484.089 39.0723 0.359975 + vertex 465.669 38.5405 0.200552 + vertex 483.123 42.6789 0.199759 + endloop + endfacet + facet normal 0.00611848 -0.0259963 -0.999643 + outer loop + vertex 465.669 38.5405 0.200552 + vertex 464.46 42.2531 0.0966054 + vertex 483.123 42.6789 0.199759 + endloop + endfacet + facet normal 0.00599341 -0.026037 -0.999643 + outer loop + vertex 465.669 38.5405 0.200552 + vertex 443.568 37.6378 0.091558 + vertex 464.46 42.2531 0.0966054 + endloop + endfacet + facet normal 0.00354853 -0.0149696 -0.999882 + outer loop + vertex 443.568 37.6378 0.091558 + vertex 442.004 41.2956 0.0312441 + vertex 464.46 42.2531 0.0966054 + endloop + endfacet + facet normal 0.00358518 -0.0158299 -0.999868 + outer loop + vertex 464.46 42.2531 0.0966054 + vertex 442.004 41.2956 0.0312441 + vertex 462.825 45.9039 0.032942 + endloop + endfacet + facet normal 0.00373295 -0.0157637 -0.999869 + outer loop + vertex 464.46 42.2531 0.0966054 + vertex 462.825 45.9039 0.032942 + vertex 482.078 46.3977 0.0970375 + endloop + endfacet + facet normal 0.00179801 -0.0077552 -0.999968 + outer loop + vertex 442.004 41.2956 0.0312441 + vertex 440.15 44.7935 0.000782135 + vertex 462.825 45.9039 0.032942 + endloop + endfacet + facet normal 0.00181175 -0.008036 -0.999966 + outer loop + vertex 462.825 45.9039 0.032942 + vertex 440.15 44.7935 0.000782135 + vertex 460.869 49.405 0.00126101 + endloop + endfacet + facet normal 0.00179609 -0.00804476 -0.999966 + outer loop + vertex 462.825 45.9039 0.032942 + vertex 460.869 49.405 0.00126101 + vertex 480.463 50.1221 0.0306868 + endloop + endfacet + facet normal 0.000550271 -0.00236841 -0.999997 + outer loop + vertex 440.15 44.7935 0.000782135 + vertex 438.027 48.047 -0.00809154 + vertex 460.869 49.405 0.00126101 + endloop + endfacet + facet normal 0.000539493 -0.00218713 -0.999997 + outer loop + vertex 460.869 49.405 0.00126101 + vertex 438.027 48.047 -0.00809154 + vertex 458.662 52.6636 -0.0070566 + endloop + endfacet + facet normal 0.000487414 -0.0022224 -0.999997 + outer loop + vertex 460.869 49.405 0.00126101 + vertex 458.662 52.6636 -0.0070566 + vertex 478.461 53.6618 0.000375578 + endloop + endfacet + facet normal -9.08959e-05 0.000630444 -1 + outer loop + vertex 438.027 48.047 -0.00809154 + vertex 435.62 50.9916 -0.00601632 + vertex 458.662 52.6636 -0.0070566 + endloop + endfacet + facet normal -8.86263e-05 0.000599166 -1 + outer loop + vertex 458.662 52.6636 -0.0070566 + vertex 435.62 50.9916 -0.00601632 + vertex 456.143 55.6129 -0.0050663 + endloop + endfacet + facet normal -9.45424e-05 0.000594115 -1 + outer loop + vertex 458.662 52.6636 -0.0070566 + vertex 456.143 55.6129 -0.0050663 + vertex 476.117 56.9316 -0.00617119 + endloop + endfacet + facet normal -0.000202487 0.00110482 -0.999999 + outer loop + vertex 435.62 50.9916 -0.00601632 + vertex 432.973 53.6152 -0.00258165 + vertex 456.143 55.6129 -0.0050663 + endloop + endfacet + facet normal -0.000188533 0.000942977 -1 + outer loop + vertex 456.143 55.6129 -0.0050663 + vertex 432.973 53.6152 -0.00258165 + vertex 453.345 58.2157 -0.00208435 + endloop + endfacet + facet normal -0.000173303 0.000959351 -1 + outer loop + vertex 456.143 55.6129 -0.0050663 + vertex 453.345 58.2157 -0.00208435 + vertex 473.437 59.8799 -0.00396979 + endloop + endfacet + facet normal -0.000101732 0.000558599 -1 + outer loop + vertex 432.973 53.6152 -0.00258165 + vertex 430.102 55.9293 -0.000997001 + vertex 453.345 58.2157 -0.00208435 + endloop + endfacet + facet normal -8.89464e-05 0.000428622 -1 + outer loop + vertex 453.345 58.2157 -0.00208435 + vertex 430.102 55.9293 -0.000997001 + vertex 450.328 60.4771 -0.000846779 + endloop + endfacet + facet normal -7.58371e-05 0.000446109 -1 + outer loop + vertex 453.345 58.2157 -0.00208435 + vertex 450.328 60.4771 -0.000846779 + vertex 470.221 62.3455 -0.00152189 + endloop + endfacet + facet normal -6.16494e-05 0.000295053 -1 + outer loop + vertex 470.221 62.3455 -0.00152189 + vertex 450.328 60.4771 -0.000846779 + vertex 467.221 64.4801 -0.000707079 + endloop + endfacet + facet normal -9.00897e-06 7.29156e-05 -1 + outer loop + vertex 450.328 60.4771 -0.000846779 + vertex 447.184 62.4893 -0.000671729 + vertex 467.221 64.4801 -0.000707079 + endloop + endfacet + facet normal -1.21589e-05 6.79936e-05 -1 + outer loop + vertex 450.328 60.4771 -0.000846779 + vertex 427.041 57.9808 -0.000733359 + vertex 447.184 62.4893 -0.000671729 + endloop + endfacet + facet normal 8.45764e-07 9.89094e-06 -1 + outer loop + vertex 427.041 57.9808 -0.000733359 + vertex 423.834 59.8339 -0.000717742 + vertex 447.184 62.4893 -0.000671729 + endloop + endfacet + facet normal -3.09254e-07 2.00474e-05 -1 + outer loop + vertex 447.184 62.4893 -0.000671729 + vertex 423.834 59.8339 -0.000717742 + vertex 443.888 64.3347 -0.000633714 + endloop + endfacet + facet normal -1.17869e-06 1.84945e-05 -1 + outer loop + vertex 447.184 62.4893 -0.000671729 + vertex 443.888 64.3347 -0.000633714 + vertex 464.201 66.5016 -0.000617582 + endloop + endfacet + facet normal -1.13449e-05 6.92176e-05 -1 + outer loop + vertex 423.834 59.8339 -0.000717742 + vertex 420.579 61.5415 -0.00056262 + vertex 443.888 64.3347 -0.000633714 + endloop + endfacet + facet normal -1.18253e-05 7.32258e-05 -1 + outer loop + vertex 443.888 64.3347 -0.000633714 + vertex 420.579 61.5415 -0.00056262 + vertex 440.528 66.0342 -0.000469531 + endloop + endfacet + facet normal -1.21194e-05 7.26443e-05 -1 + outer loop + vertex 443.888 64.3347 -0.000633714 + vertex 440.528 66.0342 -0.000469531 + vertex 460.653 68.3737 -0.000543482 + endloop + endfacet + facet normal -1.906e-05 0.000105349 -1 + outer loop + vertex 420.579 61.5415 -0.00056262 + vertex 417.392 63.1417 -0.000333293 + vertex 440.528 66.0342 -0.000469531 + endloop + endfacet + facet normal -1.75428e-05 9.32137e-05 -1 + outer loop + vertex 440.528 66.0342 -0.000469531 + vertex 417.392 63.1417 -0.000333293 + vertex 437.211 67.5974 -0.000265625 + endloop + endfacet + facet normal -1.70552e-05 9.42482e-05 -1 + outer loop + vertex 440.528 66.0342 -0.000469531 + vertex 437.211 67.5974 -0.000265625 + vertex 456.918 69.9872 -0.000376505 + endloop + endfacet + facet normal -1.52816e-05 7.96218e-05 -1 + outer loop + vertex 456.918 69.9872 -0.000376505 + vertex 437.211 67.5974 -0.000265625 + vertex 453.524 71.4601 -0.000207362 + endloop + endfacet + facet normal -1.60653e-05 8.66419e-05 -1 + outer loop + vertex 417.392 63.1417 -0.000333293 + vertex 414.289 64.6665 -0.000151331 + vertex 437.211 67.5974 -0.000265625 + endloop + endfacet + facet normal -1.37918e-05 6.88625e-05 -1 + outer loop + vertex 437.211 67.5974 -0.000265625 + vertex 414.289 64.6665 -0.000151331 + vertex 433.772 69.0507 -0.000118125 + endloop + endfacet + facet normal -1.66808e-05 8.53893e-05 -1 + outer loop + vertex 417.392 63.1417 -0.000333293 + vertex 393.675 60.1968 -0.000189128 + vertex 414.289 64.6665 -0.000151331 + endloop + endfacet + facet normal -1.1242e-05 6.03052e-05 -1 + outer loop + vertex 393.675 60.1968 -0.000189128 + vertex 390.807 61.7237 -6.4812e-05 + vertex 414.289 64.6665 -0.000151331 + endloop + endfacet + facet normal -9.64071e-06 4.75278e-05 -1 + outer loop + vertex 414.289 64.6665 -0.000151331 + vertex 390.807 61.7237 -6.4812e-05 + vertex 410.905 66.0926 -5.0929e-05 + endloop + endfacet + facet normal -6.2615e-06 3.19825e-05 -1 + outer loop + vertex 390.807 61.7237 -6.4812e-05 + vertex 387.362 63.0757 9.62153e-15 + vertex 410.905 66.0926 -5.0929e-05 + endloop + endfacet + facet normal -6.51899e-06 3.13264e-05 -1 + outer loop + vertex 390.807 61.7237 -6.4812e-05 + vertex 368.447 59.1395 9.62153e-15 + vertex 387.362 63.0757 9.62153e-15 + endloop + endfacet + facet normal -7.43068e-06 3.92149e-05 -1 + outer loop + vertex 370.917 57.5747 -7.97152e-05 + vertex 368.447 59.1395 9.62153e-15 + vertex 390.807 61.7237 -6.4812e-05 + endloop + endfacet + facet normal -7.70068e-06 3.87887e-05 -1 + outer loop + vertex 370.917 57.5747 -7.97152e-05 + vertex 349.99 55.4752 9.62153e-15 + vertex 368.447 59.1395 9.62153e-15 + endloop + endfacet + facet normal -8.49397e-06 4.66958e-05 -1 + outer loop + vertex 351.428 53.7034 -9.49564e-05 + vertex 349.99 55.4752 9.62153e-15 + vertex 370.917 57.5747 -7.97152e-05 + endloop + endfacet + facet normal -1.34127e-05 7.14568e-05 -1 + outer loop + vertex 373.52 55.9938 -0.000227604 + vertex 351.428 53.7034 -9.49564e-05 + vertex 370.917 57.5747 -7.97152e-05 + endloop + endfacet + facet normal -1.31e-05 7.19717e-05 -1 + outer loop + vertex 373.52 55.9938 -0.000227604 + vertex 370.917 57.5747 -7.97152e-05 + vertex 393.675 60.1968 -0.000189128 + endloop + endfacet + facet normal -1.91076e-05 0.000100779 -1 + outer loop + vertex 396.654 58.6445 -0.000402496 + vertex 373.52 55.9938 -0.000227604 + vertex 393.675 60.1968 -0.000189128 + endloop + endfacet + facet normal -2.09817e-05 0.000117135 -1 + outer loop + vertex 376.469 54.4325 -0.000472357 + vertex 373.52 55.9938 -0.000227604 + vertex 396.654 58.6445 -0.000402496 + endloop + endfacet + facet normal -2.09727e-05 0.000117092 -1 + outer loop + vertex 399.779 57.0316 -0.000656875 + vertex 376.469 54.4325 -0.000472357 + vertex 396.654 58.6445 -0.000402496 + endloop + endfacet + facet normal -2.089e-05 0.000117252 -1 + outer loop + vertex 399.779 57.0316 -0.000656875 + vertex 396.654 58.6445 -0.000402496 + vertex 420.579 61.5415 -0.00056262 + endloop + endfacet + facet normal -2.24288e-05 0.00013015 -1 + outer loop + vertex 379.486 52.7948 -0.00075316 + vertex 376.469 54.4325 -0.000472357 + vertex 399.779 57.0316 -0.000656875 + endloop + endfacet + facet normal -9.69801e-06 6.9175e-05 -1 + outer loop + vertex 402.914 55.3032 -0.000806851 + vertex 379.486 52.7948 -0.00075316 + vertex 399.779 57.0316 -0.000656875 + endloop + endfacet + facet normal -1.04331e-05 6.78415e-05 -1 + outer loop + vertex 402.914 55.3032 -0.000806851 + vertex 399.779 57.0316 -0.000656875 + vertex 423.834 59.8339 -0.000717742 + endloop + endfacet + facet normal -1.00385e-05 7.23555e-05 -1 + outer loop + vertex 382.464 51.0352 -0.000910373 + vertex 379.486 52.7948 -0.00075316 + vertex 402.914 55.3032 -0.000806851 + endloop + endfacet + facet normal 3.68325e-06 6.60703e-06 -1 + outer loop + vertex 405.966 53.4198 -0.000808055 + vertex 382.464 51.0352 -0.000910373 + vertex 402.914 55.3032 -0.000806851 + endloop + endfacet + facet normal 2.5217e-06 4.72491e-06 -1 + outer loop + vertex 405.966 53.4198 -0.000808055 + vertex 402.914 55.3032 -0.000806851 + vertex 427.041 57.9808 -0.000733359 + endloop + endfacet + facet normal -1.8344e-05 0.000101139 -1 + outer loop + vertex 430.102 55.9293 -0.000997001 + vertex 405.966 53.4198 -0.000808055 + vertex 427.041 57.9808 -0.000733359 + endloop + endfacet + facet normal -2.15852e-05 0.000132312 -1 + outer loop + vertex 408.883 51.3387 -0.00114636 + vertex 405.966 53.4198 -0.000808055 + vertex 430.102 55.9293 -0.000997001 + endloop + endfacet + facet normal -2.22016e-05 0.000131448 -1 + outer loop + vertex 408.883 51.3387 -0.00114636 + vertex 385.344 49.1198 -0.000915432 + vertex 405.966 53.4198 -0.000808055 + endloop + endfacet + facet normal -2.28548e-05 0.000138377 -1 + outer loop + vertex 388.109 47.014 -0.00127001 + vertex 385.344 49.1198 -0.000915432 + vertex 408.883 51.3387 -0.00114636 + endloop + endfacet + facet normal -0.000122722 0.000618105 -1 + outer loop + vertex 411.625 49.0058 -0.00292492 + vertex 388.109 47.014 -0.00127001 + vertex 408.883 51.3387 -0.00114636 + endloop + endfacet + facet normal -0.000118465 0.000623109 -1 + outer loop + vertex 411.625 49.0058 -0.00292492 + vertex 408.883 51.3387 -0.00114636 + vertex 432.973 53.6152 -0.00258165 + endloop + endfacet + facet normal -0.000123908 0.000632103 -1 + outer loop + vertex 390.733 44.6619 -0.00308202 + vertex 388.109 47.014 -0.00127001 + vertex 411.625 49.0058 -0.00292492 + endloop + endfacet + facet normal -0.000228674 0.00113598 -0.999999 + outer loop + vertex 414.176 46.3743 -0.00649751 + vertex 390.733 44.6619 -0.00308202 + vertex 411.625 49.0058 -0.00292492 + endloop + endfacet + facet normal -0.000223284 0.0011412 -0.999999 + outer loop + vertex 414.176 46.3743 -0.00649751 + vertex 411.625 49.0058 -0.00292492 + vertex 435.62 50.9916 -0.00601632 + endloop + endfacet + facet normal -0.000225559 0.00109333 -0.999999 + outer loop + vertex 393.168 42.0083 -0.00653233 + vertex 390.733 44.6619 -0.00308202 + vertex 414.176 46.3743 -0.00649751 + endloop + endfacet + facet normal -0.000108289 0.000529045 -1 + outer loop + vertex 416.489 43.418 -0.00831198 + vertex 393.168 42.0083 -0.00653233 + vertex 414.176 46.3743 -0.00649751 + endloop + endfacet + facet normal -0.000104161 0.000532275 -1 + outer loop + vertex 416.489 43.418 -0.00831198 + vertex 414.176 46.3743 -0.00649751 + vertex 438.027 48.047 -0.00809154 + endloop + endfacet + facet normal -9.64864e-05 0.000333789 -1 + outer loop + vertex 395.369 39.0223 -0.00774147 + vertex 393.168 42.0083 -0.00653233 + vertex 416.489 43.418 -0.00831198 + endloop + endfacet + facet normal 0.000458399 -0.00233219 -0.999997 + outer loop + vertex 418.517 40.1492 0.000241414 + vertex 395.369 39.0223 -0.00774147 + vertex 416.489 43.418 -0.00831198 + endloop + endfacet + facet normal 0.000517784 -0.00229534 -0.999997 + outer loop + vertex 418.517 40.1492 0.000241414 + vertex 416.489 43.418 -0.00831198 + vertex 440.15 44.7935 0.000782135 + endloop + endfacet + facet normal 0.000464296 -0.00245333 -0.999997 + outer loop + vertex 397.259 35.7206 0.00123576 + vertex 395.369 39.0223 -0.00774147 + vertex 418.517 40.1492 0.000241414 + endloop + endfacet + facet normal 0.00152264 -0.00753377 -0.99997 + outer loop + vertex 420.246 36.6268 0.0294109 + vertex 397.259 35.7206 0.00123576 + vertex 418.517 40.1492 0.000241414 + endloop + endfacet + facet normal 0.00168383 -0.00745468 -0.999971 + outer loop + vertex 420.246 36.6268 0.0294109 + vertex 418.517 40.1492 0.000241414 + vertex 442.004 41.2956 0.0312441 + endloop + endfacet + facet normal 0.00150993 -0.00721129 -0.999973 + outer loop + vertex 398.859 32.1737 0.0292317 + vertex 397.259 35.7206 0.00123576 + vertex 420.246 36.6268 0.0294109 + endloop + endfacet + facet normal 0.00295329 -0.0141431 -0.999896 + outer loop + vertex 421.742 32.955 0.0857676 + vertex 398.859 32.1737 0.0292317 + vertex 420.246 36.6268 0.0294109 + endloop + endfacet + facet normal 0.00327183 -0.0140133 -0.999896 + outer loop + vertex 421.742 32.955 0.0857676 + vertex 420.246 36.6268 0.0294109 + vertex 443.568 37.6378 0.091558 + endloop + endfacet + facet normal 0.00561173 -0.0249196 -0.999674 + outer loop + vertex 444.862 33.9048 0.191877 + vertex 421.742 32.955 0.0857676 + vertex 443.568 37.6378 0.091558 + endloop + endfacet + facet normal 0.00554965 -0.0234042 -0.999711 + outer loop + vertex 423.065 29.2234 0.18047 + vertex 421.742 32.955 0.0857676 + vertex 444.862 33.9048 0.191877 + endloop + endfacet + facet normal 0.00989392 -0.0436338 -0.998999 + outer loop + vertex 445.751 30.0848 0.367524 + vertex 423.065 29.2234 0.18047 + vertex 444.862 33.9048 0.191877 + endloop + endfacet + facet normal 0.0101327 -0.0435783 -0.998999 + outer loop + vertex 445.751 30.0848 0.367524 + vertex 444.862 33.9048 0.191877 + vertex 466.579 34.7669 0.374539 + endloop + endfacet + facet normal 0.0183154 -0.0799823 -0.996628 + outer loop + vertex 466.781 30.7516 0.700488 + vertex 445.751 30.0848 0.367524 + vertex 466.579 34.7669 0.374539 + endloop + endfacet + facet normal 0.017797 -0.0800089 -0.996635 + outer loop + vertex 466.781 30.7516 0.700488 + vertex 466.579 34.7669 0.374539 + vertex 484.784 35.2426 0.661441 + endloop + endfacet + facet normal 0.0176792 -0.0752744 -0.997006 + outer loop + vertex 484.784 35.2426 0.661441 + vertex 466.579 34.7669 0.374539 + vertex 484.089 39.0723 0.359975 + endloop + endfacet + facet normal 0.0183184 -0.0800802 -0.99662 + outer loop + vertex 445.88 26.0392 0.694956 + vertex 445.751 30.0848 0.367524 + vertex 466.781 30.7516 0.700488 + endloop + endfacet + facet normal 0.0311482 -0.136994 -0.990082 + outer loop + vertex 465.962 26.3325 1.28617 + vertex 445.88 26.0392 0.694956 + vertex 466.781 30.7516 0.700488 + endloop + endfacet + facet normal 0.03129 -0.137019 -0.990074 + outer loop + vertex 465.962 26.3325 1.28617 + vertex 466.781 30.7516 0.700488 + vertex 484.813 30.935 1.24497 + endloop + endfacet + facet normal 0.0311506 -0.137216 -0.990051 + outer loop + vertex 444.831 21.5871 1.27901 + vertex 445.88 26.0392 0.694956 + vertex 465.962 26.3325 1.28617 + endloop + endfacet + facet normal 0.0297985 -0.136908 -0.990135 + outer loop + vertex 444.831 21.5871 1.27901 + vertex 424.327 21.4051 0.687087 + vertex 445.88 26.0392 0.694956 + endloop + endfacet + facet normal 0.0178452 -0.0813037 -0.99653 + outer loop + vertex 424.327 21.4051 0.687087 + vertex 424.054 25.4222 0.354468 + vertex 445.88 26.0392 0.694956 + endloop + endfacet + facet normal 0.0170092 -0.0813611 -0.99654 + outer loop + vertex 424.327 21.4051 0.687087 + vertex 402.691 21.0019 0.350721 + vertex 424.054 25.4222 0.354468 + endloop + endfacet + facet normal 0.00919506 -0.0435933 -0.999007 + outer loop + vertex 402.691 21.0019 0.350721 + vertex 401.605 24.7769 0.176004 + vertex 424.054 25.4222 0.354468 + endloop + endfacet + facet normal 0.00918782 -0.0433382 -0.999018 + outer loop + vertex 424.054 25.4222 0.354468 + vertex 401.605 24.7769 0.176004 + vertex 423.065 29.2234 0.18047 + endloop + endfacet + facet normal 0.00501265 -0.0231876 -0.999719 + outer loop + vertex 401.605 24.7769 0.176004 + vertex 400.281 28.4951 0.0831192 + vertex 423.065 29.2234 0.18047 + endloop + endfacet + facet normal 0.0045696 -0.0233455 -0.999717 + outer loop + vertex 401.605 24.7769 0.176004 + vertex 379.403 24.344 0.0846257 + vertex 400.281 28.4951 0.0831192 + endloop + endfacet + facet normal 0.0026177 -0.0135285 -0.999905 + outer loop + vertex 379.403 24.344 0.0846257 + vertex 378.072 28.03 0.0312719 + vertex 400.281 28.4951 0.0831192 + endloop + endfacet + facet normal 0.00261994 -0.0136355 -0.999904 + outer loop + vertex 400.281 28.4951 0.0831192 + vertex 378.072 28.03 0.0312719 + vertex 398.859 32.1737 0.0292317 + endloop + endfacet + facet normal 0.00138314 -0.007431 -0.999971 + outer loop + vertex 378.072 28.03 0.0312719 + vertex 376.588 31.5937 0.00273644 + vertex 398.859 32.1737 0.0292317 + endloop + endfacet + facet normal 0.00132696 -0.0074544 -0.999971 + outer loop + vertex 378.072 28.03 0.0312719 + vertex 356.185 27.734 0.00443432 + vertex 376.588 31.5937 0.00273644 + endloop + endfacet + facet normal 0.000469048 -0.00291936 -0.999996 + outer loop + vertex 356.185 27.734 0.00443432 + vertex 354.548 31.0852 -0.00611701 + vertex 376.588 31.5937 0.00273644 + endloop + endfacet + facet normal 0.000462133 -0.00261959 -0.999996 + outer loop + vertex 376.588 31.5937 0.00273644 + vertex 354.548 31.0852 -0.00611701 + vertex 374.829 34.924 -0.00680035 + endloop + endfacet + facet normal 0.000451528 -0.00262519 -0.999996 + outer loop + vertex 376.588 31.5937 0.00273644 + vertex 374.829 34.924 -0.00680035 + vertex 397.259 35.7206 0.00123576 + endloop + endfacet + facet normal -3.20389e-05 -8.73826e-06 -1 + outer loop + vertex 354.548 31.0852 -0.00611701 + vertex 352.61 34.1281 -0.00608152 + vertex 374.829 34.924 -0.00680035 + endloop + endfacet + facet normal -3.84284e-05 0.000169624 -1 + outer loop + vertex 374.829 34.924 -0.00680035 + vertex 352.61 34.1281 -0.00608152 + vertex 372.767 37.942 -0.00620917 + endloop + endfacet + facet normal -7.47154e-05 0.000144821 -1 + outer loop + vertex 374.829 34.924 -0.00680035 + vertex 372.767 37.942 -0.00620917 + vertex 395.369 39.0223 -0.00774147 + endloop + endfacet + facet normal -0.000169346 0.000861518 -1 + outer loop + vertex 352.61 34.1281 -0.00608152 + vertex 350.43 36.8406 -0.00337536 + vertex 372.767 37.942 -0.00620917 + endloop + endfacet + facet normal -0.000175494 0.00098621 -0.999999 + outer loop + vertex 372.767 37.942 -0.00620917 + vertex 350.43 36.8406 -0.00337536 + vertex 370.454 40.6265 -0.00315582 + endloop + endfacet + facet normal -0.000207005 0.000959068 -1 + outer loop + vertex 372.767 37.942 -0.00620917 + vertex 370.454 40.6265 -0.00315582 + vertex 393.168 42.0083 -0.00653233 + endloop + endfacet + facet normal -0.000100165 0.000587779 -1 + outer loop + vertex 350.43 36.8406 -0.00337536 + vertex 348.077 39.2489 -0.00172414 + vertex 370.454 40.6265 -0.00315582 + endloop + endfacet + facet normal -0.000101396 0.000607787 -1 + outer loop + vertex 370.454 40.6265 -0.00315582 + vertex 348.077 39.2489 -0.00172414 + vertex 367.966 43.0063 -0.00145713 + endloop + endfacet + facet normal -0.000114566 0.000594017 -1 + outer loop + vertex 370.454 40.6265 -0.00315582 + vertex 367.966 43.0063 -0.00145713 + vertex 390.733 44.6619 -0.00308202 + endloop + endfacet + facet normal -1.87331e-05 0.000170223 -1 + outer loop + vertex 348.077 39.2489 -0.00172414 + vertex 345.602 41.4091 -0.00131005 + vertex 367.966 43.0063 -0.00145713 + endloop + endfacet + facet normal -1.76072e-05 0.000154458 -1 + outer loop + vertex 367.966 43.0063 -0.00145713 + vertex 345.602 41.4091 -0.00131005 + vertex 365.345 45.1387 -0.00108162 + endloop + endfacet + facet normal -2.0689e-05 0.00015067 -1 + outer loop + vertex 367.966 43.0063 -0.00145713 + vertex 365.345 45.1387 -0.00108162 + vertex 388.109 47.014 -0.00127001 + endloop + endfacet + facet normal 1.87427e-06 5.13278e-05 -1 + outer loop + vertex 345.602 41.4091 -0.00131005 + vertex 343.039 43.3821 -0.00121358 + vertex 365.345 45.1387 -0.00108162 + endloop + endfacet + facet normal 4.14088e-06 2.25438e-05 -1 + outer loop + vertex 365.345 45.1387 -0.00108162 + vertex 343.039 43.3821 -0.00121358 + vertex 362.624 47.082 -0.00104907 + endloop + endfacet + facet normal 3.8916e-06 2.21948e-05 -1 + outer loop + vertex 365.345 45.1387 -0.00108162 + vertex 362.624 47.082 -0.00104907 + vertex 385.344 49.1198 -0.000915432 + endloop + endfacet + facet normal 4.9746e-06 1.01201e-05 -1 + outer loop + vertex 385.344 49.1198 -0.000915432 + vertex 362.624 47.082 -0.00104907 + vertex 382.464 51.0352 -0.000910373 + endloop + endfacet + facet normal -1.09235e-05 8.99079e-05 -1 + outer loop + vertex 362.624 47.082 -0.00104907 + vertex 359.836 48.88 -0.000856966 + vertex 382.464 51.0352 -0.000910373 + endloop + endfacet + facet normal -1.12347e-05 8.94253e-05 -1 + outer loop + vertex 362.624 47.082 -0.00104907 + vertex 340.416 45.2111 -0.000966882 + vertex 359.836 48.88 -0.000856966 + endloop + endfacet + facet normal -2.62534e-05 0.000168921 -1 + outer loop + vertex 340.416 45.2111 -0.000966882 + vertex 337.751 46.9223 -0.000607862 + vertex 359.836 48.88 -0.000856966 + endloop + endfacet + facet normal -2.43158e-05 0.000147063 -1 + outer loop + vertex 359.836 48.88 -0.000856966 + vertex 337.751 46.9223 -0.000607862 + vertex 356.985 50.5535 -0.000541534 + endloop + endfacet + facet normal -2.40923e-05 0.000147444 -1 + outer loop + vertex 359.836 48.88 -0.000856966 + vertex 356.985 50.5535 -0.000541534 + vertex 379.486 52.7948 -0.00075316 + endloop + endfacet + facet normal -2.47808e-05 0.000149526 -1 + outer loop + vertex 337.751 46.9223 -0.000607862 + vertex 335.033 48.5357 -0.000299254 + vertex 356.985 50.5535 -0.000541534 + endloop + endfacet + facet normal -2.32097e-05 0.000132434 -1 + outer loop + vertex 356.985 50.5535 -0.000541534 + vertex 335.033 48.5357 -0.000299254 + vertex 354.104 52.1333 -0.000265449 + endloop + endfacet + facet normal -2.29203e-05 0.000132962 -1 + outer loop + vertex 356.985 50.5535 -0.000541534 + vertex 354.104 52.1333 -0.000265449 + vertex 376.469 54.4325 -0.000472357 + endloop + endfacet + facet normal -1.59302e-05 9.38441e-05 -1 + outer loop + vertex 335.033 48.5357 -0.000299254 + vertex 332.266 50.0923 -0.0001091 + vertex 354.104 52.1333 -0.000265449 + endloop + endfacet + facet normal -1.49302e-05 8.31444e-05 -1 + outer loop + vertex 354.104 52.1333 -0.000265449 + vertex 332.266 50.0923 -0.0001091 + vertex 351.428 53.7034 -9.49564e-05 + endloop + endfacet + facet normal -9.53034e-06 5.449e-05 -1 + outer loop + vertex 332.266 50.0923 -0.0001091 + vertex 329.465 51.6046 9.62153e-15 + vertex 351.428 53.7034 -9.49564e-05 + endloop + endfacet + facet normal -9.68118e-06 5.42106e-05 -1 + outer loop + vertex 332.266 50.0923 -0.0001091 + vertex 310.642 48.2431 9.62153e-15 + vertex 329.465 51.6046 9.62153e-15 + endloop + endfacet + facet normal -1.02199e-05 6.05102e-05 -1 + outer loop + vertex 313.413 46.724 -0.000120236 + vertex 310.642 48.2431 9.62153e-15 + vertex 332.266 50.0923 -0.0001091 + endloop + endfacet + facet normal -1.02383e-05 6.04767e-05 -1 + outer loop + vertex 313.413 46.724 -0.000120236 + vertex 292.762 45.2161 9.62153e-15 + vertex 310.642 48.2431 9.62153e-15 + endloop + endfacet + facet normal -1.06151e-05 6.5637e-05 -1 + outer loop + vertex 294.354 43.5033 -0.000129328 + vertex 292.762 45.2161 9.62153e-15 + vertex 313.413 46.724 -0.000120236 + endloop + endfacet + facet normal -1.70061e-05 0.000103455 -1 + outer loop + vertex 315.914 45.1203 -0.000328691 + vertex 294.354 43.5033 -0.000129328 + vertex 313.413 46.724 -0.000120236 + endloop + endfacet + facet normal -1.69558e-05 0.000103534 -1 + outer loop + vertex 315.914 45.1203 -0.000328691 + vertex 313.413 46.724 -0.000120236 + vertex 335.033 48.5357 -0.000299254 + endloop + endfacet + facet normal -1.75442e-05 0.00011063 -1 + outer loop + vertex 296.613 41.8567 -0.000351123 + vertex 294.354 43.5033 -0.000129328 + vertex 315.914 45.1203 -0.000328691 + endloop + endfacet + facet normal -2.65149e-05 0.000163683 -1 + outer loop + vertex 318.429 43.4669 -0.000666007 + vertex 296.613 41.8567 -0.000351123 + vertex 315.914 45.1203 -0.000328691 + endloop + endfacet + facet normal -2.63165e-05 0.000163985 -1 + outer loop + vertex 318.429 43.4669 -0.000666007 + vertex 315.914 45.1203 -0.000328691 + vertex 337.751 46.9223 -0.000607862 + endloop + endfacet + facet normal -2.7428e-05 0.000176054 -1 + outer loop + vertex 298.954 40.1741 -0.000711555 + vertex 296.613 41.8567 -0.000351123 + vertex 318.429 43.4669 -0.000666007 + endloop + endfacet + facet normal -2.97339e-05 0.000189692 -1 + outer loop + vertex 320.924 41.7258 -0.00107047 + vertex 298.954 40.1741 -0.000711555 + vertex 318.429 43.4669 -0.000666007 + endloop + endfacet + facet normal -2.88345e-05 0.000190981 -1 + outer loop + vertex 320.924 41.7258 -0.00107047 + vertex 318.429 43.4669 -0.000666007 + vertex 340.416 45.2111 -0.000966882 + endloop + endfacet + facet normal -1.49673e-05 0.000113428 -1 + outer loop + vertex 343.039 43.3821 -0.00121358 + vertex 320.924 41.7258 -0.00107047 + vertex 340.416 45.2111 -0.000966882 + endloop + endfacet + facet normal -1.74564e-05 0.00014666 -1 + outer loop + vertex 323.392 39.8692 -0.00138583 + vertex 320.924 41.7258 -0.00107047 + vertex 343.039 43.3821 -0.00121358 + endloop + endfacet + facet normal -1.98391e-05 0.000143493 -1 + outer loop + vertex 323.392 39.8692 -0.00138583 + vertex 301.291 38.406 -0.00115733 + vertex 320.924 41.7258 -0.00107047 + endloop + endfacet + facet normal -2.20099e-05 0.000176282 -1 + outer loop + vertex 303.608 36.5247 -0.00153997 + vertex 301.291 38.406 -0.00115733 + vertex 323.392 39.8692 -0.00138583 + endloop + endfacet + facet normal -7.12592e-06 8.82376e-05 -1 + outer loop + vertex 325.807 37.8696 -0.00157948 + vertex 303.608 36.5247 -0.00153997 + vertex 323.392 39.8692 -0.00138583 + endloop + endfacet + facet normal -3.04731e-06 9.31625e-05 -1 + outer loop + vertex 325.807 37.8696 -0.00157948 + vertex 323.392 39.8692 -0.00138583 + vertex 345.602 41.4091 -0.00131005 + endloop + endfacet + facet normal -9.85255e-06 0.000133243 -1 + outer loop + vertex 305.875 34.5009 -0.00183196 + vertex 303.608 36.5247 -0.00153997 + vertex 325.807 37.8696 -0.00157948 + endloop + endfacet + facet normal -2.33882e-05 0.000213331 -1 + outer loop + vertex 328.137 35.683 -0.00210045 + vertex 305.875 34.5009 -0.00183196 + vertex 325.807 37.8696 -0.00157948 + endloop + endfacet + facet normal -1.9936e-05 0.00021701 -1 + outer loop + vertex 328.137 35.683 -0.00210045 + vertex 325.807 37.8696 -0.00157948 + vertex 348.077 39.2489 -0.00172414 + endloop + endfacet + facet normal -2.63944e-05 0.000269945 -1 + outer loop + vertex 308.062 32.291 -0.00248624 + vertex 305.875 34.5009 -0.00183196 + vertex 328.137 35.683 -0.00210045 + endloop + endfacet + facet normal -8.49524e-05 0.00061651 -1 + outer loop + vertex 330.352 33.2499 -0.00378863 + vertex 308.062 32.291 -0.00248624 + vertex 328.137 35.683 -0.00210045 + endloop + endfacet + facet normal -8.90109e-05 0.000612816 -1 + outer loop + vertex 330.352 33.2499 -0.00378863 + vertex 328.137 35.683 -0.00210045 + vertex 350.43 36.8406 -0.00337536 + endloop + endfacet + facet normal -8.70491e-05 0.000665245 -1 + outer loop + vertex 310.141 29.8359 -0.00430041 + vertex 308.062 32.291 -0.00248624 + vertex 330.352 33.2499 -0.00378863 + endloop + endfacet + facet normal -0.00011918 0.000855462 -1 + outer loop + vertex 332.404 30.5144 -0.00637332 + vertex 310.141 29.8359 -0.00430041 + vertex 330.352 33.2499 -0.00378863 + endloop + endfacet + facet normal -0.000136256 0.000842652 -1 + outer loop + vertex 332.404 30.5144 -0.00637332 + vertex 330.352 33.2499 -0.00378863 + vertex 352.61 34.1281 -0.00608152 + endloop + endfacet + facet normal -0.00011985 0.000877457 -1 + outer loop + vertex 312.069 27.0815 -0.00694838 + vertex 310.141 29.8359 -0.00430041 + vertex 332.404 30.5144 -0.00637332 + endloop + endfacet + facet normal 4.13995e-05 -7.77174e-05 -1 + outer loop + vertex 334.225 27.4518 -0.00605992 + vertex 312.069 27.0815 -0.00694838 + vertex 332.404 30.5144 -0.00637332 + endloop + endfacet + facet normal 1.39982e-05 -9.40103e-05 -1 + outer loop + vertex 334.225 27.4518 -0.00605992 + vertex 332.404 30.5144 -0.00637332 + vertex 354.548 31.0852 -0.00611701 + endloop + endfacet + facet normal 4.16685e-05 -9.38096e-05 -1 + outer loop + vertex 313.775 24.0002 -0.00658824 + vertex 312.069 27.0815 -0.00694838 + vertex 334.225 27.4518 -0.00605992 + endloop + endfacet + facet normal 0.000528322 -0.0029771 -0.999995 + outer loop + vertex 335.754 24.0825 0.00477862 + vertex 313.775 24.0002 -0.00658824 + vertex 334.225 27.4518 -0.00605992 + endloop + endfacet + facet normal 0.000516197 -0.0029826 -0.999995 + outer loop + vertex 335.754 24.0825 0.00477862 + vertex 334.225 27.4518 -0.00605992 + vertex 356.185 27.734 0.00443432 + endloop + endfacet + facet normal 0.00133366 -0.00755657 -0.999971 + outer loop + vertex 357.553 24.1525 0.0333237 + vertex 335.754 24.0825 0.00477862 + vertex 356.185 27.734 0.00443432 + endloop + endfacet + facet normal 0.00133387 -0.00762315 -0.99997 + outer loop + vertex 337.016 20.4823 0.0339083 + vertex 335.754 24.0825 0.00477862 + vertex 357.553 24.1525 0.0333237 + endloop + endfacet + facet normal 0.00241304 -0.0136618 -0.999904 + outer loop + vertex 358.779 20.4512 0.086853 + vertex 337.016 20.4823 0.0339083 + vertex 357.553 24.1525 0.0333237 + endloop + endfacet + facet normal 0.00246735 -0.0136438 -0.999904 + outer loop + vertex 358.779 20.4512 0.086853 + vertex 357.553 24.1525 0.0333237 + vertex 379.403 24.344 0.0846257 + endloop + endfacet + facet normal 0.00432015 -0.0234596 -0.999715 + outer loop + vertex 380.677 20.6247 0.177412 + vertex 358.779 20.4512 0.086853 + vertex 379.403 24.344 0.0846257 + endloop + endfacet + facet normal 0.00432018 -0.023463 -0.999715 + outer loop + vertex 359.961 16.7173 0.179596 + vertex 358.779 20.4512 0.086853 + vertex 380.677 20.6247 0.177412 + endloop + endfacet + facet normal 0.00816751 -0.04386 -0.999004 + outer loop + vertex 381.751 16.8511 0.351861 + vertex 359.961 16.7173 0.179596 + vertex 380.677 20.6247 0.177412 + endloop + endfacet + facet normal 0.00861436 -0.043733 -0.999006 + outer loop + vertex 381.751 16.8511 0.351861 + vertex 380.677 20.6247 0.177412 + vertex 402.691 21.0019 0.350721 + endloop + endfacet + facet normal 0.0162001 -0.0820015 -0.996501 + outer loop + vertex 403.116 17.0163 0.685601 + vertex 381.751 16.8511 0.351861 + vertex 402.691 21.0019 0.350721 + endloop + endfacet + facet normal 0.0162022 -0.082337 -0.996473 + outer loop + vertex 382.177 12.8711 0.687668 + vertex 381.751 16.8511 0.351861 + vertex 403.116 17.0163 0.685601 + endloop + endfacet + facet normal 0.0274537 -0.139167 -0.989888 + outer loop + vertex 402.448 12.6466 1.28142 + vertex 382.177 12.8711 0.687668 + vertex 403.116 17.0163 0.685601 + endloop + endfacet + facet normal 0.0287115 -0.139351 -0.989827 + outer loop + vertex 402.448 12.6466 1.28142 + vertex 403.116 17.0163 0.685601 + vertex 423.498 16.9964 1.27961 + endloop + endfacet + facet normal 0.0287161 -0.138448 -0.989953 + outer loop + vertex 423.498 16.9964 1.27961 + vertex 403.116 17.0163 0.685601 + vertex 424.327 21.4051 0.687087 + endloop + endfacet + facet normal 0.0274478 -0.139557 -0.989834 + outer loop + vertex 381.484 8.51044 1.28324 + vertex 382.177 12.8711 0.687668 + vertex 402.448 12.6466 1.28142 + endloop + endfacet + facet normal 0.026312 -0.139384 -0.989889 + outer loop + vertex 381.484 8.51044 1.28324 + vertex 361.299 8.93906 0.68637 + vertex 382.177 12.8711 0.687668 + endloop + endfacet + facet normal 0.015537 -0.0821694 -0.996497 + outer loop + vertex 361.299 8.93906 0.68637 + vertex 360.955 12.9282 0.352068 + vertex 382.177 12.8711 0.687668 + endloop + endfacet + facet normal 0.014661 -0.0822455 -0.996504 + outer loop + vertex 361.299 8.93906 0.68637 + vertex 340.137 9.20805 0.352823 + vertex 360.955 12.9282 0.352068 + endloop + endfacet + facet normal 0.00775685 -0.0436104 -0.999019 + outer loop + vertex 340.137 9.20805 0.352823 + vertex 339.232 13.0118 0.179749 + vertex 360.955 12.9282 0.352068 + endloop + endfacet + facet normal 0.00775756 -0.0434389 -0.999026 + outer loop + vertex 360.955 12.9282 0.352068 + vertex 339.232 13.0118 0.179749 + vertex 359.961 16.7173 0.179596 + endloop + endfacet + facet normal 0.00414564 -0.023233 -0.999721 + outer loop + vertex 339.232 13.0118 0.179749 + vertex 338.142 16.7657 0.087988 + vertex 359.961 16.7173 0.179596 + endloop + endfacet + facet normal 0.0039604 -0.0232868 -0.999721 + outer loop + vertex 339.232 13.0118 0.179749 + vertex 317.416 13.2672 0.0873746 + vertex 338.142 16.7657 0.087988 + endloop + endfacet + facet normal 0.00233914 -0.0136822 -0.999904 + outer loop + vertex 317.416 13.2672 0.0873746 + vertex 316.37 17.0002 0.0338486 + vertex 338.142 16.7657 0.087988 + endloop + endfacet + facet normal 0.00233742 -0.0138417 -0.999901 + outer loop + vertex 338.142 16.7657 0.087988 + vertex 316.37 17.0002 0.0338486 + vertex 337.016 20.4823 0.0339083 + endloop + endfacet + facet normal 0.0013025 -0.00770557 -0.999969 + outer loop + vertex 316.37 17.0002 0.0338486 + vertex 315.2 20.6142 0.00447487 + vertex 337.016 20.4823 0.0339083 + endloop + endfacet + facet normal 0.00127371 -0.0077149 -0.999969 + outer loop + vertex 316.37 17.0002 0.0338486 + vertex 294.548 17.3284 0.00351979 + vertex 315.2 20.6142 0.00447487 + endloop + endfacet + facet normal 0.000515764 -0.00295103 -0.999996 + outer loop + vertex 294.548 17.3284 0.00351979 + vertex 293.219 20.7283 -0.00719892 + vertex 315.2 20.6142 0.00447487 + endloop + endfacet + facet normal 0.000515247 -0.00305052 -0.999995 + outer loop + vertex 315.2 20.6142 0.00447487 + vertex 293.219 20.7283 -0.00719892 + vertex 313.775 24.0002 -0.00658824 + endloop + endfacet + facet normal 4.43671e-05 -9.21002e-05 -1 + outer loop + vertex 293.219 20.7283 -0.00719892 + vertex 291.629 23.8284 -0.00755498 + vertex 313.775 24.0002 -0.00658824 + endloop + endfacet + facet normal 3.07153e-05 -9.91023e-05 -1 + outer loop + vertex 293.219 20.7283 -0.00719892 + vertex 271.119 20.7591 -0.00788078 + vertex 291.629 23.8284 -0.00755498 + endloop + endfacet + facet normal -0.000126057 0.000948515 -1 + outer loop + vertex 271.119 20.7591 -0.00788078 + vertex 269.445 23.5525 -0.00502022 + vertex 291.629 23.8284 -0.00755498 + endloop + endfacet + facet normal -0.000125919 0.000937405 -1 + outer loop + vertex 291.629 23.8284 -0.00755498 + vertex 269.445 23.5525 -0.00502022 + vertex 289.826 26.602 -0.00472797 + endloop + endfacet + facet normal -0.000120116 0.000941177 -1 + outer loop + vertex 291.629 23.8284 -0.00755498 + vertex 289.826 26.602 -0.00472797 + vertex 312.069 27.0815 -0.00694838 + endloop + endfacet + facet normal -9.75997e-05 0.000748136 -1 + outer loop + vertex 269.445 23.5525 -0.00502022 + vertex 267.638 26.0473 -0.00297743 + vertex 289.826 26.602 -0.00472797 + endloop + endfacet + facet normal -9.66998e-05 0.000712141 -1 + outer loop + vertex 289.826 26.602 -0.00472797 + vertex 267.638 26.0473 -0.00297743 + vertex 287.883 29.0773 -0.00277726 + endloop + endfacet + facet normal -9.28066e-05 0.000715198 -1 + outer loop + vertex 289.826 26.602 -0.00472797 + vertex 287.883 29.0773 -0.00277726 + vertex 310.141 29.8359 -0.00430041 + endloop + endfacet + facet normal -4.10895e-05 0.000340594 -1 + outer loop + vertex 267.638 26.0473 -0.00297743 + vertex 265.737 28.2999 -0.0021321 + vertex 287.883 29.0773 -0.00277726 + endloop + endfacet + facet normal -3.97256e-05 0.000301743 -1 + outer loop + vertex 287.883 29.0773 -0.00277726 + vertex 265.737 28.2999 -0.0021321 + vertex 285.837 31.3084 -0.00202277 + endloop + endfacet + facet normal -3.44087e-05 0.000306618 -1 + outer loop + vertex 287.883 29.0773 -0.00277726 + vertex 285.837 31.3084 -0.00202277 + vertex 308.062 32.291 -0.00248624 + endloop + endfacet + facet normal -2.16986e-05 0.000181306 -1 + outer loop + vertex 265.737 28.2999 -0.0021321 + vertex 263.765 30.3681 -0.00171433 + vertex 285.837 31.3084 -0.00202277 + endloop + endfacet + facet normal -2.08489e-05 0.000161361 -1 + outer loop + vertex 285.837 31.3084 -0.00202277 + vertex 263.765 30.3681 -0.00171433 + vertex 283.717 33.3552 -0.0016483 + endloop + endfacet + facet normal -1.68461e-05 0.000165507 -1 + outer loop + vertex 285.837 31.3084 -0.00202277 + vertex 283.717 33.3552 -0.0016483 + vertex 305.875 34.5009 -0.00183196 + endloop + endfacet + facet normal -2.82994e-05 0.000211125 -1 + outer loop + vertex 263.765 30.3681 -0.00171433 + vertex 261.75 32.295 -0.00125049 + vertex 283.717 33.3552 -0.0016483 + endloop + endfacet + facet normal -2.75501e-05 0.000195602 -1 + outer loop + vertex 283.717 33.3552 -0.0016483 + vertex 261.75 32.295 -0.00125049 + vertex 281.552 35.2598 -0.00121611 + endloop + endfacet + facet normal -2.6002e-05 0.000197362 -1 + outer loop + vertex 283.717 33.3552 -0.0016483 + vertex 281.552 35.2598 -0.00121611 + vertex 303.608 36.5247 -0.00153997 + endloop + endfacet + facet normal -3.32718e-05 0.000233817 -1 + outer loop + vertex 261.75 32.295 -0.00125049 + vertex 259.724 34.1084 -0.000759085 + vertex 281.552 35.2598 -0.00121611 + endloop + endfacet + facet normal -3.28156e-05 0.000225168 -1 + outer loop + vertex 281.552 35.2598 -0.00121611 + vertex 259.724 34.1084 -0.000759085 + vertex 279.371 37.0504 -0.000741364 + endloop + endfacet + facet normal -3.2896e-05 0.00022507 -1 + outer loop + vertex 281.552 35.2598 -0.00121611 + vertex 279.371 37.0504 -0.000741364 + vertex 301.291 38.406 -0.00115733 + endloop + endfacet + facet normal -3.1957e-05 0.000209886 -1 + outer loop + vertex 301.291 38.406 -0.00115733 + vertex 279.371 37.0504 -0.000741364 + vertex 298.954 40.1741 -0.000711555 + endloop + endfacet + facet normal -2.80067e-05 0.000185121 -1 + outer loop + vertex 279.371 37.0504 -0.000741364 + vertex 277.188 38.7562 -0.000364441 + vertex 298.954 40.1741 -0.000711555 + endloop + endfacet + facet normal -2.7419e-05 0.000185873 -1 + outer loop + vertex 279.371 37.0504 -0.000741364 + vertex 257.702 35.8364 -0.000372878 + vertex 277.188 38.7562 -0.000364441 + endloop + endfacet + facet normal -1.73006e-05 0.000118347 -1 + outer loop + vertex 257.702 35.8364 -0.000372878 + vertex 255.658 37.5167 -0.000138656 + vertex 277.188 38.7562 -0.000364441 + endloop + endfacet + facet normal -1.71447e-05 0.00011564 -1 + outer loop + vertex 277.188 38.7562 -0.000364441 + vertex 255.658 37.5167 -0.000138656 + vertex 275.027 40.419 -0.0001351 + endloop + endfacet + facet normal -1.7664e-05 0.000114965 -1 + outer loop + vertex 277.188 38.7562 -0.000364441 + vertex 275.027 40.419 -0.0001351 + vertex 296.613 41.8567 -0.000351123 + endloop + endfacet + facet normal -1.05366e-05 7.15408e-05 -1 + outer loop + vertex 255.658 37.5167 -0.000138656 + vertex 253.688 39.1647 9.62153e-15 + vertex 275.027 40.419 -0.0001351 + endloop + endfacet + facet normal -1.04183e-05 6.95276e-05 -1 + outer loop + vertex 275.027 40.419 -0.0001351 + vertex 253.688 39.1647 9.62153e-15 + vertex 273.01 42.06 9.62153e-15 + endloop + endfacet + facet normal -1.07345e-05 6.9139e-05 -1 + outer loop + vertex 275.027 40.419 -0.0001351 + vertex 273.01 42.06 9.62153e-15 + vertex 294.354 43.5033 -0.000129328 + endloop + endfacet + facet normal -1.00736e-05 7.20944e-05 -1 + outer loop + vertex 255.658 37.5167 -0.000138656 + vertex 234.181 36.4389 9.62153e-15 + vertex 253.688 39.1647 9.62153e-15 + endloop + endfacet + facet normal -1.00861e-05 7.23434e-05 -1 + outer loop + vertex 236.335 34.8101 -0.000139564 + vertex 234.181 36.4389 9.62153e-15 + vertex 255.658 37.5167 -0.000138656 + endloop + endfacet + facet normal -9.47861e-06 7.3147e-05 -1 + outer loop + vertex 236.335 34.8101 -0.000139564 + vertex 215.646 34.0371 9.62153e-15 + vertex 234.181 36.4389 9.62153e-15 + endloop + endfacet + facet normal -9.50464e-06 7.38437e-05 -1 + outer loop + vertex 216.975 32.2996 -0.000140942 + vertex 215.646 34.0371 9.62153e-15 + vertex 236.335 34.8101 -0.000139564 + endloop + endfacet + facet normal -1.57494e-05 0.000122 -1 + outer loop + vertex 238.181 33.1039 -0.000376789 + vertex 216.975 32.2996 -0.000140942 + vertex 236.335 34.8101 -0.000139564 + endloop + endfacet + facet normal -1.67281e-05 0.000120941 -1 + outer loop + vertex 238.181 33.1039 -0.000376789 + vertex 236.335 34.8101 -0.000139564 + vertex 257.702 35.8364 -0.000372878 + endloop + endfacet + facet normal -2.67091e-05 0.000192248 -1 + outer loop + vertex 259.724 34.1084 -0.000759085 + vertex 238.181 33.1039 -0.000376789 + vertex 257.702 35.8364 -0.000372878 + endloop + endfacet + facet normal -2.68072e-05 0.000194351 -1 + outer loop + vertex 240.043 31.3537 -0.000766866 + vertex 238.181 33.1039 -0.000376789 + vertex 259.724 34.1084 -0.000759085 + endloop + endfacet + facet normal -2.5313e-05 0.000195941 -1 + outer loop + vertex 240.043 31.3537 -0.000766866 + vertex 218.633 30.568 -0.00037888 + vertex 238.181 33.1039 -0.000376789 + endloop + endfacet + facet normal -2.53484e-05 0.000196905 -1 + outer loop + vertex 220.35 28.7999 -0.00077055 + vertex 218.633 30.568 -0.00037888 + vertex 240.043 31.3537 -0.000766866 + endloop + endfacet + facet normal -3.1148e-05 0.000241626 -1 + outer loop + vertex 241.922 29.5226 -0.00126785 + vertex 220.35 28.7999 -0.00077055 + vertex 240.043 31.3537 -0.000766866 + endloop + endfacet + facet normal -3.26889e-05 0.000240045 -1 + outer loop + vertex 241.922 29.5226 -0.00126785 + vertex 240.043 31.3537 -0.000766866 + vertex 261.75 32.295 -0.00125049 + endloop + endfacet + facet normal -3.11996e-05 0.000243165 -1 + outer loop + vertex 222.078 26.9477 -0.00127483 + vertex 220.35 28.7999 -0.00077055 + vertex 241.922 29.5226 -0.00126785 + endloop + endfacet + facet normal -2.79561e-05 0.000218168 -1 + outer loop + vertex 243.787 27.5744 -0.001745 + vertex 222.078 26.9477 -0.00127483 + vertex 241.922 29.5226 -0.00126785 + endloop + endfacet + facet normal -2.88527e-05 0.00021731 -1 + outer loop + vertex 243.787 27.5744 -0.001745 + vertex 241.922 29.5226 -0.00126785 + vertex 263.765 30.3681 -0.00171433 + endloop + endfacet + facet normal -2.80458e-05 0.000221274 -1 + outer loop + vertex 223.793 24.9824 -0.00175779 + vertex 222.078 26.9477 -0.00127483 + vertex 243.787 27.5744 -0.001745 + endloop + endfacet + facet normal -2.43993e-05 0.000193146 -1 + outer loop + vertex 245.609 25.4848 -0.00219306 + vertex 223.793 24.9824 -0.00175779 + vertex 243.787 27.5744 -0.001745 + endloop + endfacet + facet normal -2.40295e-05 0.000193468 -1 + outer loop + vertex 245.609 25.4848 -0.00219306 + vertex 243.787 27.5744 -0.001745 + vertex 265.737 28.2999 -0.0021321 + endloop + endfacet + facet normal -2.45023e-05 0.00019762 -1 + outer loop + vertex 225.465 22.873 -0.00221562 + vertex 223.793 24.9824 -0.00175779 + vertex 245.609 25.4848 -0.00219306 + endloop + endfacet + facet normal -4.37934e-05 0.000346407 -1 + outer loop + vertex 247.365 23.2124 -0.00305713 + vertex 225.465 22.873 -0.00221562 + vertex 245.609 25.4848 -0.00219306 + endloop + endfacet + facet normal -4.44385e-05 0.000345909 -1 + outer loop + vertex 247.365 23.2124 -0.00305713 + vertex 245.609 25.4848 -0.00219306 + vertex 267.638 26.0473 -0.00297743 + endloop + endfacet + facet normal -4.3953e-05 0.000356703 -1 + outer loop + vertex 227.076 20.5816 -0.00310382 + vertex 225.465 22.873 -0.00221562 + vertex 247.365 23.2124 -0.00305713 + endloop + endfacet + facet normal -9.73387e-05 0.000768405 -1 + outer loop + vertex 249.035 20.6978 -0.00515189 + vertex 227.076 20.5816 -0.00310382 + vertex 247.365 23.2124 -0.00305713 + endloop + endfacet + facet normal -0.000100709 0.000766167 -1 + outer loop + vertex 249.035 20.6978 -0.00515189 + vertex 247.365 23.2124 -0.00305713 + vertex 269.445 23.5525 -0.00502022 + endloop + endfacet + facet normal -9.73186e-05 0.000764623 -1 + outer loop + vertex 228.609 18.0505 -0.00518826 + vertex 227.076 20.5816 -0.00310382 + vertex 249.035 20.6978 -0.00515189 + endloop + endfacet + facet normal -0.000124261 0.000972503 -1 + outer loop + vertex 250.582 17.8891 -0.00807561 + vertex 228.609 18.0505 -0.00518826 + vertex 249.035 20.6978 -0.00515189 + endloop + endfacet + facet normal -0.000126265 0.000971399 -1 + outer loop + vertex 250.582 17.8891 -0.00807561 + vertex 249.035 20.6978 -0.00515189 + vertex 271.119 20.7591 -0.00788078 + endloop + endfacet + facet normal 1.22294e-05 -1.96259e-05 -1 + outer loop + vertex 272.599 17.6459 -0.00780158 + vertex 250.582 17.8891 -0.00807561 + vertex 271.119 20.7591 -0.00788078 + endloop + endfacet + facet normal 1.18658e-05 -5.25392e-05 -1 + outer loop + vertex 251.944 14.7595 -0.00789502 + vertex 250.582 17.8891 -0.00807561 + vertex 272.599 17.6459 -0.00780158 + endloop + endfacet + facet normal 0.000439047 -0.00310944 -0.999995 + outer loop + vertex 273.823 14.232 0.00335141 + vertex 251.944 14.7595 -0.00789502 + vertex 272.599 17.6459 -0.00780158 + endloop + endfacet + facet normal 0.000470998 -0.00309799 -0.999995 + outer loop + vertex 273.823 14.232 0.00335141 + vertex 272.599 17.6459 -0.00780158 + vertex 294.548 17.3284 0.00351979 + endloop + endfacet + facet normal 0.00118058 -0.00784716 -0.999969 + outer loop + vertex 295.631 13.7031 0.0332488 + vertex 273.823 14.232 0.00335141 + vertex 294.548 17.3284 0.00351979 + endloop + endfacet + facet normal 0.0011839 -0.00771017 -0.99997 + outer loop + vertex 274.828 10.5957 0.0325784 + vertex 273.823 14.232 0.00335141 + vertex 295.631 13.7031 0.0332488 + endloop + endfacet + facet normal 0.00209154 -0.0137866 -0.999903 + outer loop + vertex 296.608 9.96038 0.0868962 + vertex 274.828 10.5957 0.0325784 + vertex 295.631 13.7031 0.0332488 + endloop + endfacet + facet normal 0.00220914 -0.0137559 -0.999903 + outer loop + vertex 296.608 9.96038 0.0868962 + vertex 295.631 13.7031 0.0332488 + vertex 317.416 13.2672 0.0873746 + endloop + endfacet + facet normal 0.00376374 -0.0235378 -0.999716 + outer loop + vertex 318.434 9.50248 0.179848 + vertex 296.608 9.96038 0.0868962 + vertex 317.416 13.2672 0.0873746 + endloop + endfacet + facet normal 0.00376828 -0.0233223 -0.999721 + outer loop + vertex 297.573 6.18333 0.178646 + vertex 296.608 9.96038 0.0868962 + vertex 318.434 9.50248 0.179848 + endloop + endfacet + facet normal 0.00699233 -0.0435864 -0.999025 + outer loop + vertex 319.282 5.68674 0.352258 + vertex 297.573 6.18333 0.178646 + vertex 318.434 9.50248 0.179848 + endloop + endfacet + facet normal 0.00737223 -0.043502 -0.999026 + outer loop + vertex 319.282 5.68674 0.352258 + vertex 318.434 9.50248 0.179848 + vertex 340.137 9.20805 0.352823 + endloop + endfacet + facet normal 0.0139595 -0.0825159 -0.996492 + outer loop + vertex 340.393 5.20771 0.68766 + vertex 319.282 5.68674 0.352258 + vertex 340.137 9.20805 0.352823 + endloop + endfacet + facet normal 0.0139684 -0.0821478 -0.996522 + outer loop + vertex 319.507 1.68498 0.6853 + vertex 319.282 5.68674 0.352258 + vertex 340.393 5.20771 0.68766 + endloop + endfacet + facet normal 0.0235638 -0.139041 -0.990006 + outer loop + vertex 339.515 0.843709 1.27968 + vertex 319.507 1.68498 0.6853 + vertex 340.393 5.20771 0.68766 + endloop + endfacet + facet normal 0.0247984 -0.139281 -0.989942 + outer loop + vertex 339.515 0.843709 1.27968 + vertex 340.393 5.20771 0.68766 + vertex 360.494 4.57401 1.28036 + endloop + endfacet + facet normal 0.0247982 -0.139285 -0.989942 + outer loop + vertex 360.494 4.57401 1.28036 + vertex 340.393 5.20771 0.68766 + vertex 361.299 8.93906 0.68637 + endloop + endfacet + facet normal 0.0235101 -0.140203 -0.989844 + outer loop + vertex 318.636 -2.66404 1.28059 + vertex 319.507 1.68498 0.6853 + vertex 339.515 0.843709 1.27968 + endloop + endfacet + facet normal 0.022206 -0.13995 -0.98991 + outer loop + vertex 318.636 -2.66404 1.28059 + vertex 298.582 -1.64038 0.686028 + vertex 319.507 1.68498 0.6853 + endloop + endfacet + facet normal 0.0130942 -0.0826149 -0.996496 + outer loop + vertex 298.582 -1.64038 0.686028 + vertex 298.38 2.36129 0.351611 + vertex 319.507 1.68498 0.6853 + endloop + endfacet + facet normal 0.0123562 -0.0826527 -0.996502 + outer loop + vertex 298.582 -1.64038 0.686028 + vertex 277.417 -0.771201 0.35149 + vertex 298.38 2.36129 0.351611 + endloop + endfacet + facet normal 0.00655188 -0.0438082 -0.999018 + outer loop + vertex 277.417 -0.771201 0.35149 + vertex 276.65 3.05875 0.178513 + vertex 298.38 2.36129 0.351611 + endloop + endfacet + facet normal 0.00655129 -0.0438266 -0.999018 + outer loop + vertex 298.38 2.36129 0.351611 + vertex 276.65 3.05875 0.178513 + vertex 297.573 6.18333 0.178646 + endloop + endfacet + facet normal 0.00352378 -0.0235536 -0.999716 + outer loop + vertex 276.65 3.05875 0.178513 + vertex 275.738 6.84275 0.0861456 + vertex 297.573 6.18333 0.178646 + endloop + endfacet + facet normal 0.00328512 -0.0236111 -0.999716 + outer loop + vertex 276.65 3.05875 0.178513 + vertex 254.833 3.92778 0.086296 + vertex 275.738 6.84275 0.0861456 + endloop + endfacet + facet normal 0.00194153 -0.0139755 -0.9999 + outer loop + vertex 254.833 3.92778 0.086296 + vertex 253.99 7.68655 0.0321245 + vertex 275.738 6.84275 0.0861456 + endloop + endfacet + facet normal 0.00194835 -0.0137999 -0.999903 + outer loop + vertex 275.738 6.84275 0.0861456 + vertex 253.99 7.68655 0.0321245 + vertex 274.828 10.5957 0.0325784 + endloop + endfacet + facet normal 0.00109812 -0.00770973 -0.99997 + outer loop + vertex 253.99 7.68655 0.0321245 + vertex 253.07 11.334 0.00299278 + vertex 274.828 10.5957 0.0325784 + endloop + endfacet + facet normal 0.00101221 -0.0077314 -0.99997 + outer loop + vertex 253.99 7.68655 0.0321245 + vertex 232.299 8.64421 0.00276331 + vertex 253.07 11.334 0.00299278 + endloop + endfacet + facet normal 0.000399339 -0.00299854 -0.999995 + outer loop + vertex 232.299 8.64421 0.00276331 + vertex 231.273 12.0813 -0.00795278 + vertex 253.07 11.334 0.00299278 + endloop + endfacet + facet normal 0.000397655 -0.00304765 -0.999995 + outer loop + vertex 253.07 11.334 0.00299278 + vertex 231.273 12.0813 -0.00795278 + vertex 251.944 14.7595 -0.00789502 + endloop + endfacet + facet normal 8.88203e-06 -4.69869e-05 -1 + outer loop + vertex 231.273 12.0813 -0.00795278 + vertex 230.026 15.2244 -0.00811154 + vertex 251.944 14.7595 -0.00789502 + endloop + endfacet + facet normal 7.5291e-06 -4.75233e-05 -1 + outer loop + vertex 231.273 12.0813 -0.00795278 + vertex 209.418 12.7731 -0.0081502 + vertex 230.026 15.2244 -0.00811154 + endloop + endfacet + facet normal -0.000114981 0.000982399 -1 + outer loop + vertex 209.418 12.7731 -0.0081502 + vertex 208.129 15.6133 -0.00521172 + vertex 230.026 15.2244 -0.00811154 + endloop + endfacet + facet normal -0.000115083 0.000976665 -1 + outer loop + vertex 230.026 15.2244 -0.00811154 + vertex 208.129 15.6133 -0.00521172 + vertex 228.609 18.0505 -0.00518826 + endloop + endfacet + facet normal -9.14877e-05 0.000778396 -1 + outer loop + vertex 208.129 15.6133 -0.00521172 + vertex 206.735 18.1612 -0.00310094 + vertex 228.609 18.0505 -0.00518826 + endloop + endfacet + facet normal -8.37375e-05 0.000782636 -1 + outer loop + vertex 208.129 15.6133 -0.00521172 + vertex 186.282 15.9508 -0.00311817 + vertex 206.735 18.1612 -0.00310094 + endloop + endfacet + facet normal -3.84237e-05 0.000363336 -1 + outer loop + vertex 186.282 15.9508 -0.00311817 + vertex 184.96 18.2746 -0.00222305 + vertex 206.735 18.1612 -0.00310094 + endloop + endfacet + facet normal -3.84644e-05 0.000355529 -1 + outer loop + vertex 206.735 18.1612 -0.00310094 + vertex 184.96 18.2746 -0.00222305 + vertex 205.268 20.4695 -0.00222382 + endloop + endfacet + facet normal -4.21654e-05 0.000353175 -1 + outer loop + vertex 206.735 18.1612 -0.00310094 + vertex 205.268 20.4695 -0.00222382 + vertex 227.076 20.5816 -0.00310382 + endloop + endfacet + facet normal -2.17406e-05 0.000200798 -1 + outer loop + vertex 184.96 18.2746 -0.00222305 + vertex 183.588 20.4183 -0.00176278 + vertex 205.268 20.4695 -0.00222382 + endloop + endfacet + facet normal -2.17424e-05 0.000201547 -1 + outer loop + vertex 205.268 20.4695 -0.00222382 + vertex 183.588 20.4183 -0.00176278 + vertex 203.745 22.5964 -0.00176205 + endloop + endfacet + facet normal -2.34344e-05 0.000200336 -1 + outer loop + vertex 205.268 20.4695 -0.00222382 + vertex 203.745 22.5964 -0.00176205 + vertex 225.465 22.873 -0.00221562 + endloop + endfacet + facet normal -2.43767e-05 0.000225926 -1 + outer loop + vertex 183.588 20.4183 -0.00176278 + vertex 182.186 22.42 -0.00127636 + vertex 203.745 22.5964 -0.00176205 + endloop + endfacet + facet normal -2.4373e-05 0.000225474 -1 + outer loop + vertex 203.745 22.5964 -0.00176205 + vertex 182.186 22.42 -0.00127636 + vertex 202.187 24.5807 -0.00127667 + endloop + endfacet + facet normal -2.64308e-05 0.000223859 -1 + outer loop + vertex 203.745 22.5964 -0.00176205 + vertex 202.187 24.5807 -0.00127667 + vertex 223.793 24.9824 -0.00175779 + endloop + endfacet + facet normal -2.67602e-05 0.000247573 -1 + outer loop + vertex 182.186 22.42 -0.00127636 + vertex 180.775 24.3058 -0.000771707 + vertex 202.187 24.5807 -0.00127667 + endloop + endfacet + facet normal -2.67617e-05 0.000247688 -1 + outer loop + vertex 202.187 24.5807 -0.00127667 + vertex 180.775 24.3058 -0.000771707 + vertex 200.614 26.4505 -0.000771444 + endloop + endfacet + facet normal -2.91443e-05 0.000245684 -1 + outer loop + vertex 202.187 24.5807 -0.00127667 + vertex 200.614 26.4505 -0.000771444 + vertex 222.078 26.9477 -0.00127483 + endloop + endfacet + facet normal -2.17465e-05 0.000201293 -1 + outer loop + vertex 180.775 24.3058 -0.000771707 + vertex 179.365 26.1047 -0.000378941 + vertex 200.614 26.4505 -0.000771444 + endloop + endfacet + facet normal -2.17492e-05 0.000201461 -1 + outer loop + vertex 200.614 26.4505 -0.000771444 + vertex 179.365 26.1047 -0.000378941 + vertex 199.043 28.2329 -0.000378188 + endloop + endfacet + facet normal -2.37287e-05 0.000199716 -1 + outer loop + vertex 200.614 26.4505 -0.000771444 + vertex 199.043 28.2329 -0.000378188 + vertex 220.35 28.7999 -0.00077055 + endloop + endfacet + facet normal -1.34577e-05 0.000124793 -1 + outer loop + vertex 179.365 26.1047 -0.000378941 + vertex 177.991 27.8653 -0.000140755 + vertex 199.043 28.2329 -0.000378188 + endloop + endfacet + facet normal -1.3452e-05 0.000124466 -1 + outer loop + vertex 199.043 28.2329 -0.000378188 + vertex 177.991 27.8653 -0.000140755 + vertex 197.516 29.9784 -0.000140388 + endloop + endfacet + facet normal -1.4737e-05 0.000123341 -1 + outer loop + vertex 199.043 28.2329 -0.000378188 + vertex 197.516 29.9784 -0.000140388 + vertex 218.633 30.568 -0.00037888 + endloop + endfacet + facet normal -1.47358e-05 0.000123297 -1 + outer loop + vertex 218.633 30.568 -0.00037888 + vertex 197.516 29.9784 -0.000140388 + vertex 216.975 32.2996 -0.000140942 + endloop + endfacet + facet normal -8.84638e-06 7.39241e-05 -1 + outer loop + vertex 197.516 29.9784 -0.000140388 + vertex 196.004 31.6966 9.62153e-15 + vertex 216.975 32.2996 -0.000140942 + endloop + endfacet + facet normal -8.08075e-06 7.45975e-05 -1 + outer loop + vertex 197.516 29.9784 -0.000140388 + vertex 176.856 29.6224 9.43606e-15 + vertex 196.004 31.6966 9.62153e-15 + endloop + endfacet + facet normal -8.08566e-06 7.48825e-05 -1 + outer loop + vertex 177.991 27.8653 -0.000140755 + vertex 176.856 29.6224 9.43606e-15 + vertex 197.516 29.9784 -0.000140388 + endloop + endfacet + facet normal -7.32537e-06 7.53736e-05 -1 + outer loop + vertex 177.991 27.8653 -0.000140755 + vertex 157.174 27.7095 5.19677e-15 + vertex 176.856 29.6224 9.43606e-15 + endloop + endfacet + facet normal -7.32679e-06 7.55634e-05 -1 + outer loop + vertex 158.33 25.957 -0.000140895 + vertex 157.174 27.7095 5.19677e-15 + vertex 177.991 27.8653 -0.000140755 + endloop + endfacet + facet normal -6.51308e-06 7.61002e-05 -1 + outer loop + vertex 158.33 25.957 -0.000140895 + vertex 137.543 26.0294 -1.02639e-14 + vertex 157.174 27.7095 5.19677e-15 + endloop + endfacet + facet normal -6.51294e-06 7.61407e-05 -1 + outer loop + vertex 138.562 24.2661 -0.00014089 + vertex 137.543 26.0294 -1.02639e-14 + vertex 158.33 25.957 -0.000140895 + endloop + endfacet + facet normal -1.08703e-05 0.000127083 -1 + outer loop + vertex 159.562 24.1841 -0.000379589 + vertex 138.562 24.2661 -0.00014089 + vertex 158.33 25.957 -0.000140895 + endloop + endfacet + facet normal -1.22028e-05 0.000126158 -1 + outer loop + vertex 159.562 24.1841 -0.000379589 + vertex 158.33 25.957 -0.000140895 + vertex 179.365 26.1047 -0.000378941 + endloop + endfacet + facet normal -1.08734e-05 0.000126304 -1 + outer loop + vertex 139.67 22.4804 -0.000378484 + vertex 138.562 24.2661 -0.00014089 + vertex 159.562 24.1841 -0.000379589 + endloop + endfacet + facet normal -1.75314e-05 0.000204041 -1 + outer loop + vertex 160.807 22.3692 -0.00077174 + vertex 139.67 22.4804 -0.000378484 + vertex 159.562 24.1841 -0.000379589 + endloop + endfacet + facet normal -1.96473e-05 0.000202589 -1 + outer loop + vertex 160.807 22.3692 -0.00077174 + vertex 159.562 24.1841 -0.000379589 + vertex 180.775 24.3058 -0.000771707 + endloop + endfacet + facet normal -1.75258e-05 0.0002051 -1 + outer loop + vertex 140.756 20.6537 -0.000772184 + vertex 139.67 22.4804 -0.000378484 + vertex 160.807 22.3692 -0.00077174 + endloop + endfacet + facet normal -2.15007e-05 0.000251558 -1 + outer loop + vertex 162.058 20.4672 -0.0012771 + vertex 140.756 20.6537 -0.000772184 + vertex 160.807 22.3692 -0.00077174 + endloop + endfacet + facet normal -2.4197e-05 0.000249784 -1 + outer loop + vertex 162.058 20.4672 -0.0012771 + vertex 160.807 22.3692 -0.00077174 + vertex 182.186 22.42 -0.00127636 + endloop + endfacet + facet normal -2.15039e-05 0.000251192 -1 + outer loop + vertex 141.853 18.739 -0.00127673 + vertex 140.756 20.6537 -0.000772184 + vertex 162.058 20.4672 -0.0012771 + endloop + endfacet + facet normal -1.96239e-05 0.000229213 -1 + outer loop + vertex 163.306 18.4508 -0.00176377 + vertex 141.853 18.739 -0.00127673 + vertex 162.058 20.4672 -0.0012771 + endloop + endfacet + facet normal -2.20407e-05 0.000227717 -1 + outer loop + vertex 163.306 18.4508 -0.00176377 + vertex 162.058 20.4672 -0.0012771 + vertex 183.588 20.4183 -0.00176278 + endloop + endfacet + facet normal -1.96224e-05 0.00022932 -1 + outer loop + vertex 142.946 16.7093 -0.00176363 + vertex 141.853 18.739 -0.00127673 + vertex 163.306 18.4508 -0.00176377 + endloop + endfacet + facet normal -1.74604e-05 0.000204045 -1 + outer loop + vertex 164.526 16.2938 -0.0022252 + vertex 142.946 16.7093 -0.00176363 + vertex 163.306 18.4508 -0.00176377 + endloop + endfacet + facet normal -1.95591e-05 0.000202857 -1 + outer loop + vertex 164.526 16.2938 -0.0022252 + vertex 163.306 18.4508 -0.00176377 + vertex 184.96 18.2746 -0.00222305 + endloop + endfacet + facet normal -1.74605e-05 0.000204039 -1 + outer loop + vertex 144.014 14.539 -0.00222509 + vertex 142.946 16.7093 -0.00176363 + vertex 164.526 16.2938 -0.0022252 + endloop + endfacet + facet normal -3.10151e-05 0.000362484 -1 + outer loop + vertex 165.701 13.9559 -0.00310909 + vertex 144.014 14.539 -0.00222509 + vertex 164.526 16.2938 -0.0022252 + endloop + endfacet + facet normal -3.53641e-05 0.000360299 -1 + outer loop + vertex 165.701 13.9559 -0.00310909 + vertex 164.526 16.2938 -0.0022252 + vertex 186.282 15.9508 -0.00311817 + endloop + endfacet + facet normal -7.62378e-05 0.00078199 -1 + outer loop + vertex 187.537 13.3884 -0.00521763 + vertex 165.701 13.9559 -0.00310909 + vertex 186.282 15.9508 -0.00311817 + endloop + endfacet + facet normal -7.62411e-05 0.000781863 -1 + outer loop + vertex 166.817 11.3806 -0.00520769 + vertex 165.701 13.9559 -0.00310909 + vertex 187.537 13.3884 -0.00521763 + endloop + endfacet + facet normal -9.67759e-05 0.000993784 -1 + outer loop + vertex 188.698 10.5351 -0.00816548 + vertex 166.817 11.3806 -0.00520769 + vertex 187.537 13.3884 -0.00521763 + endloop + endfacet + facet normal -0.000106184 0.000989956 -1 + outer loop + vertex 188.698 10.5351 -0.00816548 + vertex 187.537 13.3884 -0.00521763 + vertex 209.418 12.7731 -0.0081502 + endloop + endfacet + facet normal 1.90454e-06 -1.08071e-05 -1 + outer loop + vertex 210.55 9.61722 -0.00811394 + vertex 188.698 10.5351 -0.00816548 + vertex 209.418 12.7731 -0.0081502 + endloop + endfacet + facet normal 1.7872e-07 -5.1891e-05 -1 + outer loop + vertex 189.71 7.36692 -0.00800089 + vertex 188.698 10.5351 -0.00816548 + vertex 210.55 9.61722 -0.00811394 + endloop + endfacet + facet normal 0.00033337 -0.00313757 -0.999995 + outer loop + vertex 211.47 6.16941 0.00301071 + vertex 189.71 7.36692 -0.00800089 + vertex 210.55 9.61722 -0.00811394 + endloop + endfacet + facet normal 0.000360068 -0.00313044 -0.999995 + outer loop + vertex 211.47 6.16941 0.00301071 + vertex 210.55 9.61722 -0.00811394 + vertex 232.299 8.64421 0.00276331 + endloop + endfacet + facet normal 0.000927055 -0.00790241 -0.999968 + outer loop + vertex 233.133 4.98956 0.0324181 + vertex 211.47 6.16941 0.00301071 + vertex 232.299 8.64421 0.00276331 + endloop + endfacet + facet normal 0.00093422 -0.00777089 -0.999969 + outer loop + vertex 212.223 2.5054 0.0321872 + vertex 211.47 6.16941 0.00301071 + vertex 233.133 4.98956 0.0324181 + endloop + endfacet + facet normal 0.00165681 -0.0138533 -0.999903 + outer loop + vertex 233.908 1.21955 0.0859343 + vertex 212.223 2.5054 0.0321872 + vertex 233.133 4.98956 0.0324181 + endloop + endfacet + facet normal 0.00180631 -0.0138226 -0.999903 + outer loop + vertex 233.908 1.21955 0.0859343 + vertex 233.133 4.98956 0.0324181 + vertex 254.833 3.92778 0.086296 + endloop + endfacet + facet normal 0.00306803 -0.023571 -0.999717 + outer loop + vertex 255.691 0.133416 0.178393 + vertex 233.908 1.21955 0.0859343 + vertex 254.833 3.92778 0.086296 + endloop + endfacet + facet normal 0.0030635 -0.0236618 -0.999715 + outer loop + vertex 234.714 -2.58121 0.178363 + vertex 233.908 1.21955 0.0859343 + vertex 255.691 0.133416 0.178393 + endloop + endfacet + facet normal 0.00568847 -0.0439458 -0.999018 + outer loop + vertex 256.413 -3.70421 0.35132 + vertex 234.714 -2.58121 0.178363 + vertex 255.691 0.133416 0.178393 + endloop + endfacet + facet normal 0.00613328 -0.0438622 -0.999019 + outer loop + vertex 256.413 -3.70421 0.35132 + vertex 255.691 0.133416 0.178393 + vertex 277.417 -0.771201 0.35149 + endloop + endfacet + facet normal 0.0115927 -0.0829573 -0.996486 + outer loop + vertex 277.578 -4.77542 0.686721 + vertex 256.413 -3.70421 0.35132 + vertex 277.417 -0.771201 0.35149 + endloop + endfacet + facet normal 0.0116136 -0.0825555 -0.996519 + outer loop + vertex 256.535 -7.71091 0.68467 + vertex 256.413 -3.70421 0.35132 + vertex 277.578 -4.77542 0.686721 + endloop + endfacet + facet normal 0.0195711 -0.139603 -0.990014 + outer loop + vertex 276.655 -9.10552 1.27906 + vertex 256.535 -7.71091 0.68467 + vertex 277.578 -4.77542 0.686721 + endloop + endfacet + facet normal 0.0209148 -0.139881 -0.989947 + outer loop + vertex 276.655 -9.10552 1.27906 + vertex 277.578 -4.77542 0.686721 + vertex 297.717 -5.97456 1.28163 + endloop + endfacet + facet normal 0.0208941 -0.140205 -0.989902 + outer loop + vertex 297.717 -5.97456 1.28163 + vertex 277.578 -4.77542 0.686721 + vertex 298.582 -1.64038 0.686028 + endloop + endfacet + facet normal 0.0194898 -0.140711 -0.989859 + outer loop + vertex 255.538 -12.0384 1.28018 + vertex 256.535 -7.71091 0.68467 + vertex 276.655 -9.10552 1.27906 + endloop + endfacet + facet normal 0.0180998 -0.1404 -0.989929 + outer loop + vertex 255.538 -12.0384 1.28018 + vertex 235.48 -10.4332 0.68579 + vertex 256.535 -7.71091 0.68467 + endloop + endfacet + facet normal 0.0106717 -0.0829501 -0.996497 + outer loop + vertex 235.48 -10.4332 0.68579 + vertex 235.395 -6.42549 0.351276 + vertex 256.535 -7.71091 0.68467 + endloop + endfacet + facet normal 0.00983656 -0.0829684 -0.996504 + outer loop + vertex 235.48 -10.4332 0.68579 + vertex 214.325 -8.92927 0.351757 + vertex 235.395 -6.42549 0.351276 + endloop + endfacet + facet normal 0.0052116 -0.0440488 -0.999016 + outer loop + vertex 214.325 -8.92927 0.351757 + vertex 213.684 -5.07883 0.178636 + vertex 235.395 -6.42549 0.351276 + endloop + endfacet + facet normal 0.00521392 -0.0440116 -0.999017 + outer loop + vertex 235.395 -6.42549 0.351276 + vertex 213.684 -5.07883 0.178636 + vertex 234.714 -2.58121 0.178363 + endloop + endfacet + facet normal 0.00280364 -0.0237164 -0.999715 + outer loop + vertex 213.684 -5.07883 0.178636 + vertex 212.93 -1.26995 0.0861626 + vertex 234.714 -2.58121 0.178363 + endloop + endfacet + facet normal 0.00257582 -0.0237615 -0.999714 + outer loop + vertex 213.684 -5.07883 0.178636 + vertex 191.836 -3.54554 0.0859007 + vertex 212.93 -1.26995 0.0861626 + endloop + endfacet + facet normal 0.0015142 -0.0139208 -0.999902 + outer loop + vertex 191.836 -3.54554 0.0859007 + vertex 191.197 0.238572 0.0322495 + vertex 212.93 -1.26995 0.0861626 + endloop + endfacet + facet normal 0.0015078 -0.014013 -0.999901 + outer loop + vertex 212.93 -1.26995 0.0861626 + vertex 191.197 0.238572 0.0322495 + vertex 212.223 2.5054 0.0321872 + endloop + endfacet + facet normal 0.000842465 -0.00784167 -0.999969 + outer loop + vertex 191.197 0.238572 0.0322495 + vertex 190.531 3.91001 0.00289749 + vertex 212.223 2.5054 0.0321872 + endloop + endfacet + facet normal 0.000767314 -0.00785529 -0.999969 + outer loop + vertex 191.197 0.238572 0.0322495 + vertex 169.462 1.87003 0.00275527 + vertex 190.531 3.91001 0.00289749 + endloop + endfacet + facet normal 0.000301467 -0.00304391 -0.999995 + outer loop + vertex 169.462 1.87003 0.00275527 + vertex 168.742 5.33591 -0.0080116 + vertex 190.531 3.91001 0.00289749 + endloop + endfacet + facet normal 0.000299002 -0.00308157 -0.999995 + outer loop + vertex 190.531 3.91001 0.00289749 + vertex 168.742 5.33591 -0.0080116 + vertex 189.71 7.36692 -0.00800089 + endloop + endfacet + facet normal 4.37115e-06 -3.98549e-05 -1 + outer loop + vertex 168.742 5.33591 -0.0080116 + vertex 167.847 8.51425 -0.00814219 + vertex 189.71 7.36692 -0.00800089 + endloop + endfacet + facet normal 6.18238e-06 -3.9345e-05 -1 + outer loop + vertex 168.742 5.33591 -0.0080116 + vertex 146.919 6.72517 -0.00820118 + vertex 167.847 8.51425 -0.00814219 + endloop + endfacet + facet normal -8.36584e-05 0.00101157 -0.999999 + outer loop + vertex 146.919 6.72517 -0.00820118 + vertex 146.018 9.60154 -0.00521613 + vertex 167.847 8.51425 -0.00814219 + endloop + endfacet + facet normal -8.4565e-05 0.000993371 -1 + outer loop + vertex 167.847 8.51425 -0.00814219 + vertex 146.018 9.60154 -0.00521613 + vertex 166.817 11.3806 -0.00520769 + endloop + endfacet + facet normal -6.69358e-05 0.000787273 -1 + outer loop + vertex 146.018 9.60154 -0.00521613 + vertex 145.041 12.1887 -0.00311395 + vertex 166.817 11.3806 -0.00520769 + endloop + endfacet + facet normal -5.79549e-05 0.000790663 -1 + outer loop + vertex 146.018 9.60154 -0.00521613 + vertex 124.369 10.6656 -0.00312017 + vertex 145.041 12.1887 -0.00311395 + endloop + endfacet + facet normal -2.68241e-05 0.000368149 -1 + outer loop + vertex 124.369 10.6656 -0.00312017 + vertex 123.488 13.0268 -0.00222726 + vertex 145.041 12.1887 -0.00311395 + endloop + endfacet + facet normal -2.6891e-05 0.00036643 -1 + outer loop + vertex 145.041 12.1887 -0.00311395 + vertex 123.488 13.0268 -0.00222726 + vertex 144.014 14.539 -0.00222509 + endloop + endfacet + facet normal -1.50844e-05 0.000206177 -1 + outer loop + vertex 123.488 13.0268 -0.00222726 + vertex 122.573 15.208 -0.00176375 + vertex 144.014 14.539 -0.00222509 + endloop + endfacet + facet normal -1.2727e-05 0.000207166 -1 + outer loop + vertex 123.488 13.0268 -0.00222726 + vertex 102.202 13.9588 -0.00176326 + vertex 122.573 15.208 -0.00176375 + endloop + endfacet + facet normal -1.42321e-05 0.000231712 -1 + outer loop + vertex 102.202 13.9588 -0.00176326 + vertex 101.418 16.0084 -0.00127719 + vertex 122.573 15.208 -0.00176375 + endloop + endfacet + facet normal -1.42302e-05 0.000231761 -1 + outer loop + vertex 122.573 15.208 -0.00176375 + vertex 101.418 16.0084 -0.00127719 + vertex 121.635 17.2503 -0.00127706 + endloop + endfacet + facet normal -1.69799e-05 0.000230499 -1 + outer loop + vertex 122.573 15.208 -0.00176375 + vertex 121.635 17.2503 -0.00127706 + vertex 142.946 16.7093 -0.00176363 + endloop + endfacet + facet normal -1.55948e-05 0.000253975 -1 + outer loop + vertex 101.418 16.0084 -0.00127719 + vertex 100.63 17.946 -0.000772805 + vertex 121.635 17.2503 -0.00127706 + endloop + endfacet + facet normal -1.55534e-05 0.000255224 -1 + outer loop + vertex 121.635 17.2503 -0.00127706 + vertex 100.63 17.946 -0.000772805 + vertex 120.688 19.1736 -0.000771455 + endloop + endfacet + facet normal -1.86631e-05 0.000253692 -1 + outer loop + vertex 121.635 17.2503 -0.00127706 + vertex 120.688 19.1736 -0.000771455 + vertex 141.853 18.739 -0.00127673 + endloop + endfacet + facet normal -1.27001e-05 0.000208605 -1 + outer loop + vertex 100.63 17.946 -0.000772805 + vertex 99.8448 19.7913 -0.000377896 + vertex 120.688 19.1736 -0.000771455 + endloop + endfacet + facet normal -1.27634e-05 0.000206467 -1 + outer loop + vertex 120.688 19.1736 -0.000771455 + vertex 99.8448 19.7913 -0.000377896 + vertex 119.755 21.0142 -0.000379537 + endloop + endfacet + facet normal -1.51734e-05 0.000205246 -1 + outer loop + vertex 120.688 19.1736 -0.000771455 + vertex 119.755 21.0142 -0.000379537 + vertex 140.756 20.6537 -0.000772184 + endloop + endfacet + facet normal -7.92586e-06 0.000127704 -1 + outer loop + vertex 99.8448 19.7913 -0.000377896 + vertex 99.0906 21.6015 -0.00014075 + vertex 119.755 21.0142 -0.000379537 + endloop + endfacet + facet normal -7.90611e-06 0.000128399 -1 + outer loop + vertex 119.755 21.0142 -0.000379537 + vertex 99.0906 21.6015 -0.00014075 + vertex 118.828 22.8129 -0.000141258 + endloop + endfacet + facet normal -9.3459e-06 0.000127657 -1 + outer loop + vertex 119.755 21.0142 -0.000379537 + vertex 118.828 22.8129 -0.000141258 + vertex 139.67 22.4804 -0.000378484 + endloop + endfacet + facet normal -4.76108e-06 7.71553e-05 -1 + outer loop + vertex 99.0906 21.6015 -0.00014075 + vertex 98.604 23.3957 -1.0264e-13 + vertex 118.828 22.8129 -0.000141258 + endloop + endfacet + facet normal -4.75331e-06 7.74251e-05 -1 + outer loop + vertex 118.828 22.8129 -0.000141258 + vertex 98.604 23.3957 -1.0264e-13 + vertex 117.55 24.5589 -4.50522e-14 + endloop + endfacet + facet normal -5.6357e-06 7.67792e-05 -1 + outer loop + vertex 118.828 22.8129 -0.000141258 + vertex 117.55 24.5589 -4.50522e-14 + vertex 138.562 24.2661 -0.00014089 + endloop + endfacet + facet normal -3.79024e-06 7.74186e-05 -1 + outer loop + vertex 99.0906 21.6015 -0.00014075 + vertex 78.5674 22.4148 -1.94749e-13 + vertex 98.604 23.3957 -1.0264e-13 + endloop + endfacet + facet normal -3.81595e-06 7.67698e-05 -1 + outer loop + vertex 79.3431 20.6332 -0.00013973 + vertex 78.5674 22.4148 -1.94749e-13 + vertex 99.0906 21.6015 -0.00014075 + endloop + endfacet + facet normal -2.8501e-06 7.71903e-05 -1 + outer loop + vertex 79.3431 20.6332 -0.00013973 + vertex 59.6337 21.7157 -2.99726e-13 + vertex 78.5674 22.4148 -1.94749e-13 + endloop + endfacet + facet normal -2.80427e-06 7.80248e-05 -1 + outer loop + vertex 59.4689 19.9043 -0.000140872 + vertex 59.6337 21.7157 -2.99726e-13 + vertex 79.3431 20.6332 -0.00013973 + endloop + endfacet + facet normal -4.73516e-06 0.000130671 -1 + outer loop + vertex 79.9197 18.8203 -0.000379351 + vertex 59.4689 19.9043 -0.000140872 + vertex 79.3431 20.6332 -0.00013973 + endloop + endfacet + facet normal -6.27098e-06 0.000130182 -1 + outer loop + vertex 79.9197 18.8203 -0.000379351 + vertex 79.3431 20.6332 -0.00013973 + vertex 99.8448 19.7913 -0.000377896 + endloop + endfacet + facet normal -4.77349e-06 0.000129948 -1 + outer loop + vertex 59.9504 18.0847 -0.000379616 + vertex 59.4689 19.9043 -0.000140872 + vertex 79.9197 18.8203 -0.000379351 + endloop + endfacet + facet normal -7.67732e-06 0.000208778 -1 + outer loop + vertex 80.5444 16.9633 -0.00077185 + vertex 59.9504 18.0847 -0.000379616 + vertex 79.9197 18.8203 -0.000379351 + endloop + endfacet + facet normal -1.02202e-05 0.000207923 -1 + outer loop + vertex 80.5444 16.9633 -0.00077185 + vertex 79.9197 18.8203 -0.000379351 + vertex 100.63 17.946 -0.000772805 + endloop + endfacet + facet normal -7.70765e-06 0.000208221 -1 + outer loop + vertex 60.4115 16.2203 -0.000771377 + vertex 59.9504 18.0847 -0.000379616 + vertex 80.5444 16.9633 -0.00077185 + endloop + endfacet + facet normal -9.49226e-06 0.000256579 -1 + outer loop + vertex 81.1724 15.0192 -0.00127663 + vertex 60.4115 16.2203 -0.000771377 + vertex 80.5444 16.9633 -0.00077185 + endloop + endfacet + facet normal -1.25167e-05 0.000255602 -1 + outer loop + vertex 81.1724 15.0192 -0.00127663 + vertex 80.5444 16.9633 -0.00077185 + vertex 101.418 16.0084 -0.00127719 + endloop + endfacet + facet normal -9.46193e-06 0.000257104 -1 + outer loop + vertex 60.8781 14.271 -0.00127697 + vertex 60.4115 16.2203 -0.000771377 + vertex 81.1724 15.0192 -0.00127663 + endloop + endfacet + facet normal -8.59828e-06 0.000233678 -1 + outer loop + vertex 81.7979 12.9596 -0.0017633 + vertex 60.8781 14.271 -0.00127697 + vertex 81.1724 15.0192 -0.00127663 + endloop + endfacet + facet normal -1.14006e-05 0.000232827 -1 + outer loop + vertex 81.7979 12.9596 -0.0017633 + vertex 81.1724 15.0192 -0.00127663 + vertex 102.202 13.9588 -0.00176326 + endloop + endfacet + facet normal -1.01432e-05 0.000207151 -1 + outer loop + vertex 102.964 11.7672 -0.002225 + vertex 81.7979 12.9596 -0.0017633 + vertex 102.202 13.9588 -0.00176326 + endloop + endfacet + facet normal -1.0314e-05 0.00020412 -1 + outer loop + vertex 82.41 10.7615 -0.00221829 + vertex 81.7979 12.9596 -0.0017633 + vertex 102.964 11.7672 -0.002225 + endloop + endfacet + facet normal -1.83099e-05 0.00036754 -1 + outer loop + vertex 103.7 9.3974 -0.00310945 + vertex 82.41 10.7615 -0.00221829 + vertex 102.964 11.7672 -0.002225 + endloop + endfacet + facet normal -2.29803e-05 0.000366091 -1 + outer loop + vertex 103.7 9.3974 -0.00310945 + vertex 102.964 11.7672 -0.002225 + vertex 124.369 10.6656 -0.00312017 + endloop + endfacet + facet normal -4.9263e-05 0.000794456 -1 + outer loop + vertex 125.207 8.06828 -0.0052249 + vertex 103.7 9.3974 -0.00310945 + vertex 124.369 10.6656 -0.00312017 + endloop + endfacet + facet normal -4.93074e-05 0.000793738 -1 + outer loop + vertex 104.399 6.79215 -0.00521184 + vertex 103.7 9.3974 -0.00310945 + vertex 125.207 8.06828 -0.0052249 + endloop + endfacet + facet normal -6.28339e-05 0.00101429 -0.999999 + outer loop + vertex 125.979 5.18253 -0.00820038 + vertex 104.399 6.79215 -0.00521184 + vertex 125.207 8.06828 -0.0052249 + endloop + endfacet + facet normal -7.45286e-05 0.00101117 -0.999999 + outer loop + vertex 125.979 5.18253 -0.00820038 + vertex 125.207 8.06828 -0.0052249 + vertex 146.919 6.72517 -0.00820118 + endloop + endfacet + facet normal 5.2899e-06 -7.23216e-05 -1 + outer loop + vertex 147.696 3.53655 -0.00796646 + vertex 125.979 5.18253 -0.00820038 + vertex 146.919 6.72517 -0.00820118 + endloop + endfacet + facet normal 8.87093e-06 -2.50726e-05 -1 + outer loop + vertex 126.64 1.98667 -0.00811439 + vertex 125.979 5.18253 -0.00820038 + vertex 147.696 3.53655 -0.00796646 + endloop + endfacet + facet normal 0.000234051 -0.00308432 -0.999995 + outer loop + vertex 148.313 0.0641408 0.00288804 + vertex 126.64 1.98667 -0.00811439 + vertex 147.696 3.53655 -0.00796646 + endloop + endfacet + facet normal 0.000256751 -0.00308029 -0.999995 + outer loop + vertex 148.313 0.0641408 0.00288804 + vertex 147.696 3.53655 -0.00796646 + vertex 169.462 1.87003 0.00275527 + endloop + endfacet + facet normal 0.000672575 -0.00794994 -0.999968 + outer loop + vertex 170.041 -1.80721 0.0323798 + vertex 148.313 0.0641408 0.00288804 + vertex 169.462 1.87003 0.00275527 + endloop + endfacet + facet normal 0.000683596 -0.007822 -0.999969 + outer loop + vertex 148.808 -3.62118 0.032054 + vertex 148.313 0.0641408 0.00288804 + vertex 170.041 -1.80721 0.0323798 + endloop + endfacet + facet normal 0.00120832 -0.0139639 -0.999902 + outer loop + vertex 170.612 -5.59765 0.0860046 + vertex 148.808 -3.62118 0.032054 + vertex 170.041 -1.80721 0.0323798 + endloop + endfacet + facet normal 0.0013433 -0.0139436 -0.999902 + outer loop + vertex 170.612 -5.59765 0.0860046 + vertex 170.041 -1.80721 0.0323798 + vertex 191.836 -3.54554 0.0859007 + endloop + endfacet + facet normal 0.00228484 -0.0236814 -0.999717 + outer loop + vertex 192.539 -7.36165 0.177905 + vertex 170.612 -5.59765 0.0860046 + vertex 191.836 -3.54554 0.0859007 + endloop + endfacet + facet normal 0.00227649 -0.0237852 -0.999715 + outer loop + vertex 171.26 -9.4202 0.178426 + vertex 170.612 -5.59765 0.0860046 + vertex 192.539 -7.36165 0.177905 + endloop + endfacet + facet normal 0.00419638 -0.0436307 -0.999039 + outer loop + vertex 193.151 -11.2165 0.348825 + vertex 171.26 -9.4202 0.178426 + vertex 192.539 -7.36165 0.177905 + endloop + endfacet + facet normal 0.00484027 -0.0435286 -0.99904 + outer loop + vertex 193.151 -11.2165 0.348825 + vertex 192.539 -7.36165 0.177905 + vertex 214.325 -8.92927 0.351757 + endloop + endfacet + facet normal 0.00911117 -0.0830702 -0.996502 + outer loop + vertex 214.386 -12.9354 0.68627 + vertex 193.151 -11.2165 0.348825 + vertex 214.325 -8.92927 0.351757 + endloop + endfacet + facet normal 0.00902505 -0.0841171 -0.996415 + outer loop + vertex 193.161 -15.2229 0.687137 + vertex 193.151 -11.2165 0.348825 + vertex 214.386 -12.9354 0.68627 + endloop + endfacet + facet normal 0.015053 -0.140046 -0.990031 + outer loop + vertex 213.387 -17.2336 1.27909 + vertex 193.161 -15.2229 0.687137 + vertex 214.386 -12.9354 0.68627 + endloop + endfacet + facet normal 0.0166685 -0.140411 -0.989953 + outer loop + vertex 213.387 -17.2336 1.27909 + vertex 214.386 -12.9354 0.68627 + vertex 234.476 -14.7465 1.28142 + endloop + endfacet + facet normal 0.0166529 -0.140575 -0.98993 + outer loop + vertex 234.476 -14.7465 1.28142 + vertex 214.386 -12.9354 0.68627 + vertex 235.48 -10.4332 0.68579 + endloop + endfacet + facet normal 0.0149806 -0.140745 -0.989932 + outer loop + vertex 192.123 -19.5115 1.28117 + vertex 193.161 -15.2229 0.687137 + vertex 213.387 -17.2336 1.27909 + endloop + endfacet + facet normal 0.0137046 -0.140445 -0.989994 + outer loop + vertex 192.123 -19.5115 1.28117 + vertex 171.81 -17.2899 0.684801 + vertex 193.161 -15.2229 0.687137 + endloop + endfacet + facet normal 0.00813038 -0.0828581 -0.996528 + outer loop + vertex 171.81 -17.2899 0.684801 + vertex 171.816 -13.2831 0.351701 + vertex 193.161 -15.2229 0.687137 + endloop + endfacet + facet normal 0.00714336 -0.0828573 -0.996536 + outer loop + vertex 171.81 -17.2899 0.684801 + vertex 150.425 -15.1148 0.350662 + vertex 171.816 -13.2831 0.351701 + endloop + endfacet + facet normal 0.00382223 -0.0440708 -0.999021 + outer loop + vertex 150.425 -15.1148 0.350662 + vertex 149.907 -11.2468 0.178046 + vertex 171.816 -13.2831 0.351701 + endloop + endfacet + facet normal 0.00380417 -0.0442643 -0.999013 + outer loop + vertex 171.816 -13.2831 0.351701 + vertex 149.907 -11.2468 0.178046 + vertex 171.26 -9.4202 0.178426 + endloop + endfacet + facet normal 0.00203979 -0.0236377 -0.999719 + outer loop + vertex 149.907 -11.2468 0.178046 + vertex 149.313 -7.41434 0.0862187 + vertex 171.26 -9.4202 0.178426 + endloop + endfacet + facet normal 0.00175373 -0.023682 -0.999718 + outer loop + vertex 149.907 -11.2468 0.178046 + vertex 128.005 -8.98222 0.0859804 + vertex 149.313 -7.41434 0.0862187 + endloop + endfacet + facet normal 0.00104232 -0.0140136 -0.999901 + outer loop + vertex 128.005 -8.98222 0.0859804 + vertex 127.568 -5.18122 0.0322539 + vertex 149.313 -7.41434 0.0862187 + endloop + endfacet + facet normal 0.00102921 -0.0141412 -0.999899 + outer loop + vertex 149.313 -7.41434 0.0862187 + vertex 127.568 -5.18122 0.0322539 + vertex 148.808 -3.62118 0.032054 + endloop + endfacet + facet normal 0.000569826 -0.00788648 -0.999969 + outer loop + vertex 127.568 -5.18122 0.0322539 + vertex 127.155 -1.49234 0.00292557 + vertex 148.808 -3.62118 0.032054 + endloop + endfacet + facet normal 0.000483956 -0.00789609 -0.999969 + outer loop + vertex 127.568 -5.18122 0.0322539 + vertex 106.003 -2.78752 0.0029158 + vertex 127.155 -1.49234 0.00292557 + endloop + endfacet + facet normal 0.000190965 -0.00311116 -0.999995 + outer loop + vertex 106.003 -2.78752 0.0029158 + vertex 105.587 0.696333 -0.00800251 + vertex 127.155 -1.49234 0.00292557 + endloop + endfacet + facet normal 0.00018748 -0.00314551 -0.999995 + outer loop + vertex 127.155 -1.49234 0.00292557 + vertex 105.587 0.696333 -0.00800251 + vertex 126.64 1.98667 -0.00811439 + endloop + endfacet + facet normal -2.28949e-06 -4.935e-05 -1 + outer loop + vertex 105.587 0.696333 -0.00800251 + vertex 105.042 3.89846 -0.00815929 + vertex 126.64 1.98667 -0.00811439 + endloop + endfacet + facet normal 1.62611e-06 -4.86834e-05 -1 + outer loop + vertex 105.587 0.696333 -0.00800251 + vertex 84.0758 2.87335 -0.00814348 + vertex 105.042 3.89846 -0.00815929 + endloop + endfacet + facet normal -4.97427e-05 0.00100196 -0.999999 + outer loop + vertex 84.0758 2.87335 -0.00814348 + vertex 83.5616 5.7731 -0.00521247 + vertex 105.042 3.89846 -0.00815929 + endloop + endfacet + facet normal -4.92472e-05 0.00100764 -0.999999 + outer loop + vertex 105.042 3.89846 -0.00815929 + vertex 83.5616 5.7731 -0.00521247 + vertex 104.399 6.79215 -0.00521184 + endloop + endfacet + facet normal -3.88295e-05 0.000794613 -1 + outer loop + vertex 83.5616 5.7731 -0.00521247 + vertex 83.0008 8.38548 -0.00311486 + vertex 104.399 6.79215 -0.00521184 + endloop + endfacet + facet normal -2.91776e-05 0.000796686 -1 + outer loop + vertex 83.5616 5.7731 -0.00521247 + vertex 62.2529 7.61983 -0.00311947 + vertex 83.0008 8.38548 -0.00311486 + endloop + endfacet + facet normal -1.35237e-05 0.000372495 -1 + outer loop + vertex 62.2529 7.61983 -0.00311947 + vertex 61.8086 10.0018 -0.0022262 + vertex 83.0008 8.38548 -0.00311486 + endloop + endfacet + facet normal -1.3408e-05 0.000374011 -1 + outer loop + vertex 83.0008 8.38548 -0.00311486 + vertex 61.8086 10.0018 -0.0022262 + vertex 82.41 10.7615 -0.00221829 + endloop + endfacet + facet normal -7.31446e-06 0.000208764 -1 + outer loop + vertex 61.8086 10.0018 -0.0022262 + vertex 61.3479 12.2055 -0.00176276 + vertex 82.41 10.7615 -0.00221829 + endloop + endfacet + facet normal -5.35009e-06 0.000209175 -1 + outer loop + vertex 61.8086 10.0018 -0.0022262 + vertex 40.8861 11.6799 -0.00176325 + vertex 61.3479 12.2055 -0.00176276 + endloop + endfacet + facet normal -5.99479e-06 0.00023427 -1 + outer loop + vertex 40.8861 11.6799 -0.00176325 + vertex 40.573 13.7499 -0.00127642 + vertex 61.3479 12.2055 -0.00176276 + endloop + endfacet + facet normal -6.02792e-06 0.000233825 -1 + outer loop + vertex 61.3479 12.2055 -0.00176276 + vertex 40.573 13.7499 -0.00127642 + vertex 60.8781 14.271 -0.00127697 + endloop + endfacet + facet normal -6.62739e-06 0.000257183 -1 + outer loop + vertex 40.573 13.7499 -0.00127642 + vertex 40.2656 15.7048 -0.000771612 + vertex 60.8781 14.271 -0.00127697 + endloop + endfacet + facet normal -3.90127e-06 0.000257612 -1 + outer loop + vertex 40.573 13.7499 -0.00127642 + vertex 20.1747 15.4003 -0.000771689 + vertex 40.2656 15.7048 -0.000771612 + endloop + endfacet + facet normal -3.17545e-06 0.000209731 -1 + outer loop + vertex 20.1747 15.4003 -0.000771689 + vertex 20.0381 17.2709 -0.000378917 + vertex 40.2656 15.7048 -0.000771612 + endloop + endfacet + facet normal -3.14415e-06 0.000210135 -1 + outer loop + vertex 40.2656 15.7048 -0.000771612 + vertex 20.0381 17.2709 -0.000378917 + vertex 39.9718 17.572 -0.000378337 + endloop + endfacet + facet normal -5.35658e-06 0.000209787 -1 + outer loop + vertex 40.2656 15.7048 -0.000771612 + vertex 39.9718 17.572 -0.000378337 + vertex 60.4115 16.2203 -0.000771377 + endloop + endfacet + facet normal -1.9384e-06 0.000130289 -1 + outer loop + vertex 20.0381 17.2709 -0.000378917 + vertex 19.9148 19.0995 -0.000140441 + vertex 39.9718 17.572 -0.000378337 + endloop + endfacet + facet normal -1.99605e-06 0.000129532 -1 + outer loop + vertex 39.9718 17.572 -0.000378337 + vertex 19.9148 19.0995 -0.000140441 + vertex 39.6235 19.3971 -0.000141227 + endloop + endfacet + facet normal -3.38183e-06 0.000129268 -1 + outer loop + vertex 39.9718 17.572 -0.000378337 + vertex 39.6235 19.3971 -0.000141227 + vertex 59.9504 18.0847 -0.000379616 + endloop + endfacet + facet normal -1.21114e-06 7.7557e-05 -1 + outer loop + vertex 19.9148 19.0995 -0.000140441 + vertex 19.992 20.9115 -4.9257e-13 + vertex 39.6235 19.3971 -0.000141227 + endloop + endfacet + facet normal -1.14209e-06 7.84521e-05 -1 + outer loop + vertex 39.6235 19.3971 -0.000141227 + vertex 19.992 20.9115 -4.9257e-13 + vertex 38.5271 21.1813 -4.14108e-13 + endloop + endfacet + facet normal -1.97401e-06 7.79409e-05 -1 + outer loop + vertex 39.6235 19.3971 -0.000141227 + vertex 38.5271 21.1813 -4.14108e-13 + vertex 59.4689 19.9043 -0.000140872 + endloop + endfacet + facet normal -3.73348e-07 7.75213e-05 -1 + outer loop + vertex 19.9148 19.0995 -0.000140441 + vertex -2.37131e-13 20.8152 -5.33167e-13 + vertex 19.992 20.9115 -4.9257e-13 + endloop + endfacet + facet normal -3.55601e-07 7.77273e-05 -1 + outer loop + vertex 0.164981 19 -0.000141147 + vertex -2.37131e-13 20.8152 -5.33167e-13 + vertex 19.9148 19.0995 -0.000140441 + endloop + endfacet + facet normal 3.65813e-07 7.77929e-05 -1 + outer loop + vertex 0.164981 19 -0.000141147 + vertex -19.5314 20.907 -5.14874e-13 + vertex -2.37131e-13 20.8152 -5.33167e-13 + endloop + endfacet + facet normal 2.85654e-07 7.6965e-05 -1 + outer loop + vertex -19.4523 19.0894 -0.000139869 + vertex -19.5314 20.907 -5.14874e-13 + vertex 0.164981 19 -0.000141147 + endloop + endfacet + facet normal 5.26974e-07 0.000129911 -1 + outer loop + vertex 0.185054 17.1686 -0.000379056 + vertex -19.4523 19.0894 -0.000139869 + vertex 0.164981 19 -0.000141147 + endloop + endfacet + facet normal -6.62485e-07 0.000129898 -1 + outer loop + vertex 0.185054 17.1686 -0.000379056 + vertex 0.164981 19 -0.000141147 + vertex 20.0381 17.2709 -0.000378917 + endloop + endfacet + facet normal 6.93737e-07 0.000131616 -1 + outer loop + vertex -19.6061 17.2638 -0.000380261 + vertex -19.4523 19.0894 -0.000139869 + vertex 0.185054 17.1686 -0.000379056 + endloop + endfacet + facet normal 1.07124e-06 0.000210123 -1 + outer loop + vertex 0.174475 15.2978 -0.000772173 + vertex -19.6061 17.2638 -0.000380261 + vertex 0.185054 17.1686 -0.000379056 + endloop + endfacet + facet normal -1.05252e-06 0.000210135 -1 + outer loop + vertex 0.174475 15.2978 -0.000772173 + vertex 0.185054 17.1686 -0.000379056 + vertex 20.1747 15.4003 -0.000771689 + endloop + endfacet + facet normal -1.29656e-06 0.000257761 -1 + outer loop + vertex 20.3262 13.4423 -0.00127658 + vertex 0.174475 15.2978 -0.000772173 + vertex 20.1747 15.4003 -0.000771689 + endloop + endfacet + facet normal -1.33497e-06 0.000257344 -1 + outer loop + vertex 0.171201 13.3397 -0.00127608 + vertex 0.174475 15.2978 -0.000772173 + vertex 20.3262 13.4423 -0.00127658 + endloop + endfacet + facet normal -1.2155e-06 0.000233872 -1 + outer loop + vertex 20.4858 11.371 -0.0017612 + vertex 0.171201 13.3397 -0.00127608 + vertex 20.3262 13.4423 -0.00127658 + endloop + endfacet + facet normal -3.639e-06 0.000233686 -1 + outer loop + vertex 20.4858 11.371 -0.0017612 + vertex 20.3262 13.4423 -0.00127658 + vertex 40.8861 11.6799 -0.00176325 + endloop + endfacet + facet normal -3.21337e-06 0.000205577 -1 + outer loop + vertex 41.1946 9.47262 -0.002218 + vertex 20.4858 11.371 -0.0017612 + vertex 40.8861 11.6799 -0.00176325 + endloop + endfacet + facet normal -2.9022e-06 0.000208971 -1 + outer loop + vertex 20.6453 9.16189 -0.00222329 + vertex 20.4858 11.371 -0.0017612 + vertex 41.1946 9.47262 -0.002218 + endloop + endfacet + facet normal -5.35197e-06 0.000370979 -1 + outer loop + vertex 41.492 7.08734 -0.00310448 + vertex 20.6453 9.16189 -0.00222329 + vertex 41.1946 9.47262 -0.002218 + endloop + endfacet + facet normal -1.02217e-05 0.000370372 -1 + outer loop + vertex 41.492 7.08734 -0.00310448 + vertex 41.1946 9.47262 -0.002218 + vertex 62.2529 7.61983 -0.00311947 + endloop + endfacet + facet normal -2.11329e-05 0.000795778 -1 + outer loop + vertex 62.6742 5.00244 -0.00521124 + vertex 41.492 7.08734 -0.00310448 + vertex 62.2529 7.61983 -0.00311947 + endloop + endfacet + facet normal -2.01982e-05 0.000805273 -1 + outer loop + vertex 41.7787 4.46588 -0.00522126 + vertex 41.492 7.08734 -0.00310448 + vertex 62.6742 5.00244 -0.00521124 + endloop + endfacet + facet normal -2.53072e-05 0.00100424 -0.999999 + outer loop + vertex 63.0605 2.09779 -0.00813796 + vertex 41.7787 4.46588 -0.00522126 + vertex 62.6742 5.00244 -0.00521124 + endloop + endfacet + facet normal -3.72645e-05 0.00100264 -0.999999 + outer loop + vertex 63.0605 2.09779 -0.00813796 + vertex 62.6742 5.00244 -0.00521124 + vertex 84.0758 2.87335 -0.00814348 + endloop + endfacet + facet normal 1.90491e-06 -5.87287e-05 -1 + outer loop + vertex 84.5053 -0.333963 -0.0079543 + vertex 63.0605 2.09779 -0.00813796 + vertex 84.0758 2.87335 -0.00814348 + endloop + endfacet + facet normal 5.53154e-06 -2.67468e-05 -1 + outer loop + vertex 63.3744 -1.11277 -0.00805036 + vertex 63.0605 2.09779 -0.00813796 + vertex 84.5053 -0.333963 -0.0079543 + endloop + endfacet + facet normal 0.000119529 -0.00311977 -0.999995 + outer loop + vertex 84.8216 -3.82135 0.00296341 + vertex 63.3744 -1.11277 -0.00805036 + vertex 84.5053 -0.333963 -0.0079543 + endloop + endfacet + facet normal 0.000149886 -0.00311702 -0.999995 + outer loop + vertex 84.8216 -3.82135 0.00296341 + vertex 84.5053 -0.333963 -0.0079543 + vertex 106.003 -2.78752 0.0029158 + endloop + endfacet + facet normal 0.00038347 -0.00790283 -0.999969 + outer loop + vertex 106.333 -6.48058 0.0322288 + vertex 84.8216 -3.82135 0.00296341 + vertex 106.003 -2.78752 0.0029158 + endloop + endfacet + facet normal 0.000383493 -0.00790264 -0.999969 + outer loop + vertex 85.0695 -7.51737 0.0322676 + vertex 84.8216 -3.82135 0.00296341 + vertex 106.333 -6.48058 0.0322288 + endloop + endfacet + facet normal 0.000678536 -0.0139538 -0.999902 + outer loop + vertex 106.705 -10.2874 0.0856056 + vertex 85.0695 -7.51737 0.0322676 + vertex 106.333 -6.48058 0.0322288 + endloop + endfacet + facet normal 0.000871469 -0.0139349 -0.999903 + outer loop + vertex 106.705 -10.2874 0.0856056 + vertex 106.333 -6.48058 0.0322288 + vertex 128.005 -8.98222 0.0859804 + endloop + endfacet + facet normal 0.00147822 -0.0238369 -0.999715 + outer loop + vertex 128.55 -12.8185 0.178259 + vertex 106.705 -10.2874 0.0856056 + vertex 128.005 -8.98222 0.0859804 + endloop + endfacet + facet normal 0.00144899 -0.024089 -0.999709 + outer loop + vertex 107.204 -14.1248 0.178796 + vertex 106.705 -10.2874 0.0856056 + vertex 128.55 -12.8185 0.178259 + endloop + endfacet + facet normal 0.00268364 -0.044264 -0.999016 + outer loop + vertex 129.031 -16.6914 0.35115 + vertex 107.204 -14.1248 0.178796 + vertex 128.55 -12.8185 0.178259 + endloop + endfacet + facet normal 0.00323426 -0.0441957 -0.999018 + outer loop + vertex 129.031 -16.6914 0.35115 + vertex 128.55 -12.8185 0.178259 + vertex 150.425 -15.1148 0.350662 + endloop + endfacet + facet normal 0.00613692 -0.0835819 -0.996482 + outer loop + vertex 150.376 -19.1202 0.686323 + vertex 129.031 -16.6914 0.35115 + vertex 150.425 -15.1148 0.350662 + endloop + endfacet + facet normal 0.00622231 -0.0828401 -0.996543 + outer loop + vertex 128.966 -20.6951 0.683553 + vertex 129.031 -16.6914 0.35115 + vertex 150.376 -19.1202 0.686323 + endloop + endfacet + facet normal 0.0104679 -0.14057 -0.990015 + outer loop + vertex 149.262 -23.3853 1.28014 + vertex 128.966 -20.6951 0.683553 + vertex 150.376 -19.1202 0.686323 + endloop + endfacet + facet normal 0.0118741 -0.140928 -0.989949 + outer loop + vertex 149.262 -23.3853 1.28014 + vertex 150.376 -19.1202 0.686323 + vertex 170.73 -21.5675 1.27886 + endloop + endfacet + facet normal 0.0119275 -0.140499 -0.990009 + outer loop + vertex 170.73 -21.5675 1.27886 + vertex 150.376 -19.1202 0.686323 + vertex 171.81 -17.2899 0.684801 + endloop + endfacet + facet normal 0.0102472 -0.142184 -0.989787 + outer loop + vertex 127.803 -24.9465 1.28224 + vertex 128.966 -20.6951 0.683553 + vertex 149.262 -23.3853 1.28014 + endloop + endfacet + facet normal 0.00857701 -0.141738 -0.989867 + outer loop + vertex 127.803 -24.9465 1.28224 + vertex 107.549 -22.0058 0.685673 + vertex 128.966 -20.6951 0.683553 + endloop + endfacet + facet normal 0.00500822 -0.0834398 -0.9965 + outer loop + vertex 107.549 -22.0058 0.685673 + vertex 107.649 -18.0045 0.35113 + vertex 128.966 -20.6951 0.683553 + endloop + endfacet + facet normal 0.00407648 -0.0834171 -0.996506 + outer loop + vertex 107.549 -22.0058 0.685673 + vertex 86.2338 -19.0541 0.351385 + vertex 107.649 -18.0045 0.35113 + endloop + endfacet + facet normal 0.00216389 -0.0443943 -0.999012 + outer loop + vertex 86.2338 -19.0541 0.351385 + vertex 85.8256 -15.1734 0.17805 + vertex 107.649 -18.0045 0.35113 + endloop + endfacet + facet normal 0.00219903 -0.0441241 -0.999024 + outer loop + vertex 107.649 -18.0045 0.35113 + vertex 85.8256 -15.1734 0.17805 + vertex 107.204 -14.1248 0.178796 + endloop + endfacet + facet normal 0.00120495 -0.0238559 -0.999715 + outer loop + vertex 85.8256 -15.1734 0.17805 + vertex 85.3778 -11.3269 0.0857214 + vertex 107.204 -14.1248 0.178796 + endloop + endfacet + facet normal 0.000865365 -0.0238954 -0.999714 + outer loop + vertex 85.8256 -15.1734 0.17805 + vertex 64.0008 -12.1124 0.0859942 + vertex 85.3778 -11.3269 0.0857214 + endloop + endfacet + facet normal 0.00050295 -0.0140335 -0.999901 + outer loop + vertex 64.0008 -12.1124 0.0859942 + vertex 63.7582 -8.30041 0.0323709 + vertex 85.3778 -11.3269 0.0857214 + endloop + endfacet + facet normal 0.00050916 -0.0139892 -0.999902 + outer loop + vertex 85.3778 -11.3269 0.0857214 + vertex 63.7582 -8.30041 0.0323709 + vertex 85.0695 -7.51737 0.0322676 + endloop + endfacet + facet normal 0.000289927 -0.00802253 -0.999968 + outer loop + vertex 63.7582 -8.30041 0.0323709 + vertex 63.5904 -4.60417 0.00266815 + vertex 85.0695 -7.51737 0.0322676 + endloop + endfacet + facet normal 0.000194527 -0.00802686 -0.999968 + outer loop + vertex 63.7582 -8.30041 0.0323709 + vertex 42.3528 -5.14649 0.00289001 + vertex 63.5904 -4.60417 0.00266815 + endloop + endfacet + facet normal 6.90615e-05 -0.00311357 -0.999995 + outer loop + vertex 42.3528 -5.14649 0.00289001 + vertex 42.235 -1.65506 -0.007989 + vertex 63.5904 -4.60417 0.00266815 + endloop + endfacet + facet normal 7.5731e-05 -0.00306527 -0.999995 + outer loop + vertex 63.5904 -4.60417 0.00266815 + vertex 42.235 -1.65506 -0.007989 + vertex 63.3744 -1.11277 -0.00805036 + endloop + endfacet + facet normal -1.54247e-06 -5.30066e-05 -1 + outer loop + vertex 42.235 -1.65506 -0.007989 + vertex 42.0351 1.55888 -0.00815906 + vertex 63.3744 -1.11277 -0.00805036 + endloop + endfacet + facet normal 3.10228e-07 -5.28914e-05 -1 + outer loop + vertex 42.235 -1.65506 -0.007989 + vertex 21.0739 1.24045 -0.00814872 + vertex 42.0351 1.55888 -0.00815906 + endloop + endfacet + facet normal -1.58325e-05 0.00100973 -0.999999 + outer loop + vertex 21.0739 1.24045 -0.00814872 + vertex 20.9422 4.15049 -0.00520828 + vertex 42.0351 1.55888 -0.00815906 + endloop + endfacet + facet normal -1.58985e-05 0.00100919 -0.999999 + outer loop + vertex 42.0351 1.55888 -0.00815906 + vertex 20.9422 4.15049 -0.00520828 + vertex 41.7787 4.46588 -0.00522126 + endloop + endfacet + facet normal -1.26734e-05 0.000796126 -1 + outer loop + vertex 20.9422 4.15049 -0.00520828 + vertex 20.7966 6.77327 -0.00311837 + vertex 41.7787 4.46588 -0.00522126 + endloop + endfacet + facet normal -4.52896e-06 0.000796578 -1 + outer loop + vertex 20.9422 4.15049 -0.00520828 + vertex 0.187211 6.66808 -0.00310883 + vertex 20.7966 6.77327 -0.00311837 + endloop + endfacet + facet normal -2.34932e-06 0.000369536 -1 + outer loop + vertex 0.187211 6.66808 -0.00310883 + vertex 0.181599 9.05728 -0.00222592 + vertex 20.7966 6.77327 -0.00311837 + endloop + endfacet + facet normal -1.78672e-06 0.000374614 -1 + outer loop + vertex 20.7966 6.77327 -0.00311837 + vertex 0.181599 9.05728 -0.00222592 + vertex 20.6453 9.16189 -0.00222329 + endloop + endfacet + facet normal -9.4863e-07 0.000210665 -1 + outer loop + vertex 0.181599 9.05728 -0.00222592 + vertex 0.17308 11.2673 -0.00176034 + vertex 20.6453 9.16189 -0.00222329 + endloop + endfacet + facet normal 1.15753e-06 0.000210673 -1 + outer loop + vertex 0.181599 9.05728 -0.00222592 + vertex -20.0972 11.3653 -0.00176316 + vertex 0.17308 11.2673 -0.00176034 + endloop + endfacet + facet normal 1.27495e-06 0.000234963 -1 + outer loop + vertex -20.0972 11.3653 -0.00176316 + vertex -19.9449 13.4358 -0.00127647 + vertex 0.17308 11.2673 -0.00176034 + endloop + endfacet + facet normal 1.13594e-06 0.000233674 -1 + outer loop + vertex 0.17308 11.2673 -0.00176034 + vertex -19.9449 13.4358 -0.00127647 + vertex 0.171201 13.3397 -0.00127608 + endloop + endfacet + facet normal 1.25288e-06 0.000258144 -1 + outer loop + vertex -19.9449 13.4358 -0.00127647 + vertex -19.781 15.392 -0.00077127 + vertex 0.171201 13.3397 -0.00127608 + endloop + endfacet + facet normal 3.88308e-06 0.000257924 -1 + outer loop + vertex -19.9449 13.4358 -0.00127647 + vertex -39.7692 15.6899 -0.000772057 + vertex -19.781 15.392 -0.00077127 + endloop + endfacet + facet normal 3.17644e-06 0.000210507 -1 + outer loop + vertex -39.7692 15.6899 -0.000772057 + vertex -39.4345 17.5551 -0.000378362 + vertex -19.781 15.392 -0.00077127 + endloop + endfacet + facet normal 2.9691e-06 0.000208623 -1 + outer loop + vertex -19.781 15.392 -0.00077127 + vertex -39.4345 17.5551 -0.000378362 + vertex -19.6061 17.2638 -0.000380261 + endloop + endfacet + facet normal 1.81749e-06 0.000130233 -1 + outer loop + vertex -39.4345 17.5551 -0.000378362 + vertex -39.0555 19.3788 -0.000140159 + vertex -19.6061 17.2638 -0.000380261 + endloop + endfacet + facet normal 3.33755e-06 0.000129918 -1 + outer loop + vertex -39.4345 17.5551 -0.000378362 + vertex -58.9179 19.8849 -0.000140705 + vertex -39.0555 19.3788 -0.000140159 + endloop + endfacet + facet normal 2.01457e-06 7.79914e-05 -1 + outer loop + vertex -58.9179 19.8849 -0.000140705 + vertex -57.9982 21.6653 -3.67156e-13 + vertex -39.0555 19.3788 -0.000140159 + endloop + endfacet + facet normal 1.92216e-06 7.72258e-05 -1 + outer loop + vertex -39.0555 19.3788 -0.000140159 + vertex -57.9982 21.6653 -3.67156e-13 + vertex -38.6566 21.1838 -4.53707e-13 + endloop + endfacet + facet normal 1.15736e-06 7.73948e-05 -1 + outer loop + vertex -39.0555 19.3788 -0.000140159 + vertex -38.6566 21.1838 -4.53707e-13 + vertex -19.4523 19.0894 -0.000139869 + endloop + endfacet + facet normal 2.83959e-06 7.75652e-05 -1 + outer loop + vertex -58.9179 19.8849 -0.000140705 + vertex -79.1304 22.4389 -2.66476e-13 + vertex -57.9982 21.6653 -3.67156e-13 + endloop + endfacet + facet normal 2.80542e-06 7.72947e-05 -1 + outer loop + vertex -78.7566 20.6109 -0.000140247 + vertex -79.1304 22.4389 -2.66476e-13 + vertex -58.9179 19.8849 -0.000140705 + endloop + endfacet + facet normal 4.71901e-06 0.000129588 -1 + outer loop + vertex -59.342 18.0614 -0.000379007 + vertex -78.7566 20.6109 -0.000140247 + vertex -58.9179 19.8849 -0.000140705 + endloop + endfacet + facet normal 4.87204e-06 0.000130753 -1 + outer loop + vertex -79.2862 18.7946 -0.000380317 + vertex -78.7566 20.6109 -0.000140247 + vertex -59.342 18.0614 -0.000379007 + endloop + endfacet + facet normal 7.74653e-06 0.000208952 -1 + outer loop + vertex -59.8327 16.2 -0.000771751 + vertex -79.2862 18.7946 -0.000380317 + vertex -59.342 18.0614 -0.000379007 + endloop + endfacet + facet normal 5.31373e-06 0.000209593 -1 + outer loop + vertex -59.8327 16.2 -0.000771751 + vertex -59.342 18.0614 -0.000379007 + vertex -39.7692 15.6899 -0.000772057 + endloop + endfacet + facet normal 6.52292e-06 0.000257152 -1 + outer loop + vertex -40.0957 13.7366 -0.00127648 + vertex -59.8327 16.2 -0.000771751 + vertex -39.7692 15.6899 -0.000772057 + endloop + endfacet + facet normal 6.545e-06 0.000257329 -1 + outer loop + vertex -60.3163 14.2515 -0.00127633 + vertex -59.8327 16.2 -0.000771751 + vertex -40.0957 13.7366 -0.00127648 + endloop + endfacet + facet normal 5.94519e-06 0.000233773 -1 + outer loop + vertex -40.4042 11.6683 -0.00176183 + vertex -60.3163 14.2515 -0.00127633 + vertex -40.0957 13.7366 -0.00127648 + endloop + endfacet + facet normal 3.42864e-06 0.000234148 -1 + outer loop + vertex -40.4042 11.6683 -0.00176183 + vertex -40.0957 13.7366 -0.00127648 + vertex -20.0972 11.3653 -0.00176316 + endloop + endfacet + facet normal 3.03969e-06 0.000208085 -1 + outer loop + vertex -20.2422 9.15542 -0.00222344 + vertex -40.4042 11.6683 -0.00176183 + vertex -20.0972 11.3653 -0.00176316 + endloop + endfacet + facet normal 3.25302e-06 0.000209796 -1 + outer loop + vertex -40.6972 9.46145 -0.00222577 + vertex -40.4042 11.6683 -0.00176183 + vertex -20.2422 9.15542 -0.00222344 + endloop + endfacet + facet normal 5.69118e-06 0.00037276 -1 + outer loop + vertex -20.3781 6.76703 -0.00311451 + vertex -40.6972 9.46145 -0.00222577 + vertex -20.2422 9.15542 -0.00222344 + endloop + endfacet + facet normal 2.07068e-06 0.000372966 -1 + outer loop + vertex -20.3781 6.76703 -0.00311451 + vertex -20.2422 9.15542 -0.00222344 + vertex 0.187211 6.66808 -0.00310883 + endloop + endfacet + facet normal 4.13919e-06 0.000802888 -1 + outer loop + vertex 0.198304 4.04405 -0.00521559 + vertex -20.3781 6.76703 -0.00311451 + vertex 0.187211 6.66808 -0.00310883 + endloop + endfacet + facet normal 3.9609e-06 0.000801541 -1 + outer loop + vertex -20.5046 4.14354 -0.00521784 + vertex -20.3781 6.76703 -0.00311451 + vertex 0.198304 4.04405 -0.00521559 + endloop + endfacet + facet normal 5.04762e-06 0.00102767 -0.999999 + outer loop + vertex 0.201599 1.13445 -0.00820569 + vertex -20.5046 4.14354 -0.00521784 + vertex 0.198304 4.04405 -0.00521559 + endloop + endfacet + facet normal -2.48953e-06 0.00102767 -0.999999 + outer loop + vertex 0.201599 1.13445 -0.00820569 + vertex 0.198304 4.04405 -0.00521559 + vertex 21.0739 1.24045 -0.00814872 + endloop + endfacet + facet normal 2.78816e-06 -1.15696e-05 -1 + outer loop + vertex 21.1582 -1.97378 -0.00811129 + vertex 0.201599 1.13445 -0.00820569 + vertex 21.0739 1.24045 -0.00814872 + endloop + endfacet + facet normal -6.99869e-06 -7.75553e-05 -1 + outer loop + vertex 0.175319 -2.08171 -0.00795607 + vertex 0.201599 1.13445 -0.00820569 + vertex 21.1582 -1.97378 -0.00811129 + endloop + endfacet + facet normal 8.88222e-06 -0.00316519 -0.999995 + outer loop + vertex 21.1802 -5.46643 0.00294388 + vertex 0.175319 -2.08171 -0.00795607 + vertex 21.1582 -1.97378 -0.00811129 + endloop + endfacet + facet normal 4.52815e-05 -0.00316497 -0.999995 + outer loop + vertex 21.1802 -5.46643 0.00294388 + vertex 21.1582 -1.97378 -0.00811129 + vertex 42.3528 -5.14649 0.00289001 + endloop + endfacet + facet normal 0.000117057 -0.00791483 -0.999969 + outer loop + vertex 42.4377 -8.84577 0.03218 + vertex 21.1802 -5.46643 0.00294388 + vertex 42.3528 -5.14649 0.00289001 + endloop + endfacet + facet normal 0.000117113 -0.00791447 -0.999969 + outer loop + vertex 21.185 -9.16542 0.0322208 + vertex 21.1802 -5.46643 0.00294388 + vertex 42.4377 -8.84577 0.03218 + endloop + endfacet + facet normal 0.000210662 -0.0141344 -0.9999 + outer loop + vertex 42.6187 -12.6585 0.086114 + vertex 21.185 -9.16542 0.0322208 + vertex 42.4377 -8.84577 0.03218 + endloop + endfacet + facet normal 0.000355191 -0.0141275 -0.9999 + outer loop + vertex 42.6187 -12.6585 0.086114 + vertex 42.4377 -8.84577 0.03218 + vertex 64.0008 -12.1124 0.0859942 + endloop + endfacet + facet normal 0.000605288 -0.0239205 -0.999714 + outer loop + vertex 64.3982 -15.9635 0.178381 + vertex 42.6187 -12.6585 0.086114 + vertex 64.0008 -12.1124 0.0859942 + endloop + endfacet + facet normal 0.000608295 -0.0239007 -0.999714 + outer loop + vertex 42.9667 -16.5137 0.178494 + vertex 42.6187 -12.6585 0.086114 + vertex 64.3982 -15.9635 0.178381 + endloop + endfacet + facet normal 0.00113751 -0.0445163 -0.999008 + outer loop + vertex 64.7679 -19.8487 0.351929 + vertex 42.9667 -16.5137 0.178494 + vertex 64.3982 -15.9635 0.178381 + endloop + endfacet + facet normal 0.00162093 -0.0444704 -0.999009 + outer loop + vertex 64.7679 -19.8487 0.351929 + vertex 64.3982 -15.9635 0.178381 + vertex 86.2338 -19.0541 0.351385 + endloop + endfacet + facet normal 0.00307165 -0.0836577 -0.99649 + outer loop + vertex 86.1085 -23.0527 0.686696 + vertex 64.7679 -19.8487 0.351929 + vertex 86.2338 -19.0541 0.351385 + endloop + endfacet + facet normal 0.00315764 -0.0830899 -0.996537 + outer loop + vertex 64.6271 -23.8461 0.68478 + vertex 64.7679 -19.8487 0.351929 + vertex 86.1085 -23.0527 0.686696 + endloop + endfacet + facet normal 0.00529328 -0.14093 -0.990005 + outer loop + vertex 84.9549 -27.2731 1.2813 + vertex 64.6271 -23.8461 0.68478 + vertex 86.1085 -23.0527 0.686696 + endloop + endfacet + facet normal 0.00669992 -0.141306 -0.989943 + outer loop + vertex 84.9549 -27.2731 1.2813 + vertex 86.1085 -23.0527 0.686696 + vertex 106.398 -26.2413 1.27915 + endloop + endfacet + facet normal 0.00681692 -0.140581 -0.990046 + outer loop + vertex 106.398 -26.2413 1.27915 + vertex 86.1085 -23.0527 0.686696 + vertex 107.549 -22.0058 0.685673 + endloop + endfacet + facet normal 0.00522764 -0.14131 -0.989952 + outer loop + vertex 63.4548 -28.0525 1.27903 + vertex 64.6271 -23.8461 0.68478 + vertex 84.9549 -27.2731 1.2813 + endloop + endfacet + facet normal 0.00359206 -0.140865 -0.990022 + outer loop + vertex 63.4548 -28.0525 1.27903 + vertex 43.1247 -24.3998 0.685547 + vertex 64.6271 -23.8461 0.68478 + endloop + endfacet + facet normal 0.00211377 -0.0834658 -0.996508 + outer loop + vertex 43.1247 -24.3998 0.685547 + vertex 43.3007 -20.4041 0.351243 + vertex 64.6271 -23.8461 0.68478 + endloop + endfacet + facet normal 0.00130594 -0.0834306 -0.996513 + outer loop + vertex 43.1247 -24.3998 0.685547 + vertex 21.9042 -20.7333 0.350764 + vertex 43.3007 -20.4041 0.351243 + endloop + endfacet + facet normal 0.000700654 -0.044086 -0.999027 + outer loop + vertex 21.9042 -20.7333 0.350764 + vertex 21.6044 -16.838 0.178661 + vertex 43.3007 -20.4041 0.351243 + endloop + endfacet + facet normal 0.00066485 -0.0443034 -0.999018 + outer loop + vertex 43.3007 -20.4041 0.351243 + vertex 21.6044 -16.838 0.178661 + vertex 42.9667 -16.5137 0.178494 + endloop + endfacet + facet normal 0.00035908 -0.0241652 -0.999708 + outer loop + vertex 21.6044 -16.838 0.178661 + vertex 21.2994 -12.9825 0.0853539 + vertex 42.9667 -16.5137 0.178494 + endloop + endfacet + facet normal 8.34237e-05 -0.024187 -0.999707 + outer loop + vertex 21.6044 -16.838 0.178661 + vertex 0.0807233 -13.0868 0.0861066 + vertex 21.2994 -12.9825 0.0853539 + endloop + endfacet + facet normal 3.38251e-05 -0.0140981 -0.999901 + outer loop + vertex 0.0807233 -13.0868 0.0861066 + vertex 0.0252995 -9.27115 0.0323063 + vertex 21.2994 -12.9825 0.0853539 + endloop + endfacet + facet normal 6.55014e-05 -0.0139166 -0.999903 + outer loop + vertex 21.2994 -12.9825 0.0853539 + vertex 0.0252995 -9.27115 0.0323063 + vertex 21.185 -9.16542 0.0322208 + endloop + endfacet + facet normal 3.55314e-05 -0.00791888 -0.999969 + outer loop + vertex 0.0252995 -9.27115 0.0323063 + vertex 0.0988668 -5.57306 0.00302325 + vertex 21.185 -9.16542 0.0322208 + endloop + endfacet + facet normal -3.29862e-05 -0.00791752 -0.999969 + outer loop + vertex 0.0252995 -9.27115 0.0323063 + vertex -20.9415 -5.47044 0.00290482 + vertex 0.0988668 -5.57306 0.00302325 + endloop + endfacet + facet normal -9.75138e-06 -0.00315351 -0.999995 + outer loop + vertex -20.9415 -5.47044 0.00290482 + vertex -20.7687 -1.97996 -0.00810417 + vertex 0.0988668 -5.57306 0.00302325 + endloop + endfacet + facet normal -8.20461e-06 -0.00314452 -0.999995 + outer loop + vertex 0.0988668 -5.57306 0.00302325 + vertex -20.7687 -1.97996 -0.00810417 + vertex 0.175319 -2.08171 -0.00795607 + endloop + endfacet + facet normal 6.98967e-06 -1.67342e-05 -1 + outer loop + vertex -20.7687 -1.97996 -0.00810417 + vertex -20.627 1.23385 -0.00815696 + vertex 0.175319 -2.08171 -0.00795607 + endloop + endfacet + facet normal -4.60231e-07 -1.64057e-05 -1 + outer loop + vertex -20.7687 -1.97996 -0.00810417 + vertex -41.4924 1.54426 -0.00815245 + vertex -20.627 1.23385 -0.00815696 + endloop + endfacet + facet normal 1.47741e-05 0.00100762 -0.999999 + outer loop + vertex -41.4924 1.54426 -0.00815245 + vertex -41.2433 4.45233 -0.00521853 + vertex -20.627 1.23385 -0.00815696 + endloop + endfacet + facet normal 1.5064e-05 0.00100948 -0.999999 + outer loop + vertex -20.627 1.23385 -0.00815696 + vertex -41.2433 4.45233 -0.00521853 + vertex -20.5046 4.14354 -0.00521784 + endloop + endfacet + facet normal 1.19279e-05 0.000798857 -1 + outer loop + vertex -41.2433 4.45233 -0.00521853 + vertex -40.979 7.07433 -0.00312077 + vertex -20.5046 4.14354 -0.00521784 + endloop + endfacet + facet normal 1.97576e-05 0.000798068 -1 + outer loop + vertex -41.2433 4.45233 -0.00521853 + vertex -61.6492 7.60005 -0.0031096 + vertex -40.979 7.07433 -0.00312077 + endloop + endfacet + facet normal 8.92963e-06 0.000372339 -1 + outer loop + vertex -61.6492 7.60005 -0.0031096 + vertex -61.2222 9.98298 -0.00221853 + vertex -40.979 7.07433 -0.00312077 + endloop + endfacet + facet normal 9.14657e-06 0.000373849 -1 + outer loop + vertex -40.979 7.07433 -0.00312077 + vertex -61.2222 9.98298 -0.00221853 + vertex -40.6972 9.46145 -0.00222577 + endloop + endfacet + facet normal 4.89163e-06 0.000206395 -1 + outer loop + vertex -61.2222 9.98298 -0.00221853 + vertex -60.777 12.1871 -0.00176143 + vertex -40.6972 9.46145 -0.00222577 + endloop + endfacet + facet normal 7.62054e-06 0.000205844 -1 + outer loop + vertex -61.2222 9.98298 -0.00221853 + vertex -81.1891 12.9359 -0.00176284 + vertex -60.777 12.1871 -0.00176143 + endloop + endfacet + facet normal 8.63226e-06 0.000233423 -1 + outer loop + vertex -81.1891 12.9359 -0.00176284 + vertex -80.5754 14.9959 -0.0012767 + vertex -60.777 12.1871 -0.00176143 + endloop + endfacet + facet normal 8.58231e-06 0.000233071 -1 + outer loop + vertex -60.777 12.1871 -0.00176143 + vertex -80.5754 14.9959 -0.0012767 + vertex -60.3163 14.2515 -0.00127633 + endloop + endfacet + facet normal 9.47085e-06 0.000257253 -1 + outer loop + vertex -80.5754 14.9959 -0.0012767 + vertex -79.9436 16.9367 -0.000771431 + vertex -60.3163 14.2515 -0.00127633 + endloop + endfacet + facet normal 1.24829e-05 0.000256272 -1 + outer loop + vertex -80.5754 14.9959 -0.0012767 + vertex -100.045 17.915 -0.000771653 + vertex -79.9436 16.9367 -0.000771431 + endloop + endfacet + facet normal 1.01473e-05 0.000208281 -1 + outer loop + vertex -100.045 17.915 -0.000771653 + vertex -99.2313 19.761 -0.000378909 + vertex -79.9436 16.9367 -0.000771431 + endloop + endfacet + facet normal 9.95971e-06 0.000207 -1 + outer loop + vertex -79.9436 16.9367 -0.000771431 + vertex -99.2313 19.761 -0.000378909 + vertex -79.2862 18.7946 -0.000380317 + endloop + endfacet + facet normal 6.20482e-06 0.000129508 -1 + outer loop + vertex -99.2313 19.761 -0.000378909 + vertex -98.3714 21.5627 -0.000140238 + vertex -79.2862 18.7946 -0.000380317 + endloop + endfacet + facet normal 7.87091e-06 0.000128713 -1 + outer loop + vertex -99.2313 19.761 -0.000378909 + vertex -118.187 22.7708 -0.000140707 + vertex -98.3714 21.5627 -0.000140238 + endloop + endfacet + facet normal 4.73242e-06 7.72346e-05 -1 + outer loop + vertex -118.187 22.7708 -0.000140707 + vertex -116.642 24.4979 -1.40269e-13 + vertex -98.3714 21.5627 -0.000140238 + endloop + endfacet + facet normal 4.67913e-06 7.69029e-05 -1 + outer loop + vertex -98.3714 21.5627 -0.000140238 + vertex -116.642 24.4979 -1.40269e-13 + vertex -97.7837 23.3505 -1.91469e-13 + endloop + endfacet + facet normal 3.74623e-06 7.72096e-05 -1 + outer loop + vertex -98.3714 21.5627 -0.000140238 + vertex -97.7837 23.3505 -1.91469e-13 + vertex -78.7566 20.6109 -0.000140247 + endloop + endfacet + facet normal 5.60206e-06 7.64567e-05 -1 + outer loop + vertex -118.187 22.7708 -0.000140707 + vertex -137.542 26.0293 -1.07888e-13 + vertex -116.642 24.4979 -1.40269e-13 + endloop + endfacet + facet normal 5.59278e-06 7.64016e-05 -1 + outer loop + vertex -137.984 24.219 -0.000140783 + vertex -137.542 26.0293 -1.07888e-13 + vertex -118.187 22.7708 -0.000140707 + endloop + endfacet + facet normal 9.29359e-06 0.000126992 -1 + outer loop + vertex -119.151 20.9735 -0.00037791 + vertex -137.984 24.219 -0.000140783 + vertex -118.187 22.7708 -0.000140707 + endloop + endfacet + facet normal 9.40952e-06 0.000127665 -1 + outer loop + vertex -139.001 22.4282 -0.000378981 + vertex -137.984 24.219 -0.000140783 + vertex -119.151 20.9735 -0.00037791 + endloop + endfacet + facet normal 1.52458e-05 0.000207307 -1 + outer loop + vertex -120.106 19.1394 -0.000772703 + vertex -139.001 22.4282 -0.000378981 + vertex -119.151 20.9735 -0.00037791 + endloop + endfacet + facet normal 1.27827e-05 0.00020859 -1 + outer loop + vertex -120.106 19.1394 -0.000772703 + vertex -119.151 20.9735 -0.00037791 + vertex -100.045 17.915 -0.000771653 + endloop + endfacet + facet normal 1.55939e-05 0.000254652 -1 + outer loop + vertex -100.831 15.9801 -0.00127663 + vertex -120.106 19.1394 -0.000772703 + vertex -100.045 17.915 -0.000771653 + endloop + endfacet + facet normal 1.54918e-05 0.000254029 -1 + outer loop + vertex -121.055 17.2126 -0.00127685 + vertex -120.106 19.1394 -0.000772703 + vertex -100.831 15.9801 -0.00127663 + endloop + endfacet + facet normal 1.41448e-05 0.000231927 -1 + outer loop + vertex -101.598 13.9284 -0.00176333 + vertex -121.055 17.2126 -0.00127685 + vertex -100.831 15.9801 -0.00127663 + endloop + endfacet + facet normal 1.13531e-05 0.00023297 -1 + outer loop + vertex -101.598 13.9284 -0.00176333 + vertex -100.831 15.9801 -0.00127663 + vertex -81.1891 12.9359 -0.00176284 + endloop + endfacet + facet normal 1.01018e-05 0.000207239 -1 + outer loop + vertex -81.7851 10.7369 -0.00222459 + vertex -101.598 13.9284 -0.00176333 + vertex -81.1891 12.9359 -0.00176284 + endloop + endfacet + facet normal 1.02467e-05 0.000208139 -1 + outer loop + vertex -102.346 11.7364 -0.00222723 + vertex -101.598 13.9284 -0.00176333 + vertex -81.7851 10.7369 -0.00222459 + endloop + endfacet + facet normal 1.81235e-05 0.000370175 -1 + outer loop + vertex -82.3582 8.35903 -0.00311521 + vertex -102.346 11.7364 -0.00222723 + vertex -81.7851 10.7369 -0.00222459 + endloop + endfacet + facet normal 1.3875e-05 0.0003712 -1 + outer loop + vertex -82.3582 8.35903 -0.00311521 + vertex -81.7851 10.7369 -0.00222459 + vertex -61.6492 7.60005 -0.0031096 + endloop + endfacet + facet normal 2.96278e-05 0.000801022 -1 + outer loop + vertex -62.0509 4.98227 -0.00521841 + vertex -82.3582 8.35903 -0.00311521 + vertex -61.6492 7.60005 -0.0031096 + endloop + endfacet + facet normal 2.94737e-05 0.000800096 -1 + outer loop + vertex -82.8972 5.74552 -0.00522216 + vertex -82.3582 8.35903 -0.00311521 + vertex -62.0509 4.98227 -0.00521841 + endloop + endfacet + facet normal 3.69933e-05 0.00100547 -0.999999 + outer loop + vertex -62.4271 2.07713 -0.00815337 + vertex -82.8972 5.74552 -0.00522216 + vertex -62.0509 4.98227 -0.00521841 + endloop + endfacet + facet normal 2.56746e-05 0.00100694 -0.999999 + outer loop + vertex -62.4271 2.07713 -0.00815337 + vertex -62.0509 4.98227 -0.00521841 + vertex -41.4924 1.54426 -0.00815245 + endloop + endfacet + facet normal -1.04401e-06 -4.27533e-05 -1 + outer loop + vertex -41.7478 -1.66736 -0.00801487 + vertex -62.4271 2.07713 -0.00815337 + vertex -41.4924 1.54426 -0.00815245 + endloop + endfacet + facet normal -1.34235e-06 -4.4401e-05 -1 + outer loop + vertex -62.7964 -1.132 -0.00801039 + vertex -62.4271 2.07713 -0.00815337 + vertex -41.7478 -1.66736 -0.00801487 + endloop + endfacet + facet normal -7.90292e-05 -0.00309881 -0.999995 + outer loop + vertex -42.0188 -5.15555 0.00281585 + vertex -62.7964 -1.132 -0.00801039 + vertex -41.7478 -1.66736 -0.00801487 + endloop + endfacet + facet normal -4.21179e-05 -0.00310168 -0.999995 + outer loop + vertex -42.0188 -5.15555 0.00281585 + vertex -41.7478 -1.66736 -0.00801487 + vertex -20.9415 -5.47044 0.00290482 + endloop + endfacet + facet normal -0.000114214 -0.00792737 -0.999969 + outer loop + vertex -21.0944 -9.16786 0.032234 + vertex -42.0188 -5.15555 0.00281585 + vertex -20.9415 -5.47044 0.00290482 + endloop + endfacet + facet normal -0.000108323 -0.00789665 -0.999969 + outer loop + vertex -42.2523 -8.8518 0.0320301 + vertex -42.0188 -5.15555 0.00281585 + vertex -21.0944 -9.16786 0.032234 + endloop + endfacet + facet normal -0.000200311 -0.0140547 -0.999901 + outer loop + vertex -21.1012 -12.9845 0.0858827 + vertex -42.2523 -8.8518 0.0320301 + vertex -21.0944 -9.16786 0.032234 + endloop + endfacet + facet normal -5.72757e-05 -0.014055 -0.999901 + outer loop + vertex -21.1012 -12.9845 0.0858827 + vertex -21.0944 -9.16786 0.032234 + vertex 0.0807233 -13.0868 0.0861066 + endloop + endfacet + facet normal -0.00010434 -0.0238039 -0.999717 + outer loop + vertex 0.335185 -16.9498 0.17806 + vertex -21.1012 -12.9845 0.0858827 + vertex 0.0807233 -13.0868 0.0861066 + endloop + endfacet + facet normal -0.00013313 -0.0239594 -0.999713 + outer loop + vertex -20.889 -16.8475 0.178436 + vertex -21.1012 -12.9845 0.0858827 + vertex 0.335185 -16.9498 0.17806 + endloop + endfacet + facet normal -0.000232179 -0.0445241 -0.999008 + outer loop + vertex 0.604051 -20.8456 0.35163 + vertex -20.889 -16.8475 0.178436 + vertex 0.335185 -16.9498 0.17806 + endloop + endfacet + facet normal 0.000194095 -0.0444947 -0.99901 + outer loop + vertex 0.604051 -20.8456 0.35163 + vertex 0.335185 -16.9498 0.17806 + vertex 21.9042 -20.7333 0.350764 + endloop + endfacet + facet normal 0.00040149 -0.0837906 -0.996483 + outer loop + vertex 21.6982 -24.7272 0.686517 + vertex 0.604051 -20.8456 0.35163 + vertex 21.9042 -20.7333 0.350764 + endloop + endfacet + facet normal 0.000569823 -0.0828824 -0.996559 + outer loop + vertex 0.392157 -24.8386 0.683598 + vertex 0.604051 -20.8456 0.35163 + vertex 21.6982 -24.7272 0.686517 + endloop + endfacet + facet normal 0.00087161 -0.140785 -0.99004 + outer loop + vertex 20.4666 -28.9089 1.28007 + vertex 0.392157 -24.8386 0.683598 + vertex 21.6982 -24.7272 0.686517 + endloop + endfacet + facet normal 0.00207052 -0.141131 -0.989989 + outer loop + vertex 20.4666 -28.9089 1.28007 + vertex 21.6982 -24.7272 0.686517 + vertex 41.9121 -28.594 1.28004 + endloop + endfacet + facet normal 0.00210865 -0.140935 -0.990017 + outer loop + vertex 41.9121 -28.594 1.28004 + vertex 21.6982 -24.7272 0.686517 + vertex 43.1247 -24.3998 0.685547 + endloop + endfacet + facet normal 0.000548166 -0.142347 -0.989817 + outer loop + vertex -0.85661 -29.0069 1.28236 + vertex 0.392157 -24.8386 0.683598 + vertex 20.4666 -28.9089 1.28007 + endloop + endfacet + facet normal -0.000839185 -0.14194 -0.989875 + outer loop + vertex -0.85661 -29.0069 1.28236 + vertex -20.9001 -24.7378 0.687191 + vertex 0.392157 -24.8386 0.683598 + endloop + endfacet + facet normal -0.000567254 -0.0842792 -0.996442 + outer loop + vertex -20.9001 -24.7378 0.687191 + vertex -20.6471 -20.7484 0.349622 + vertex 0.392157 -24.8386 0.683598 + endloop + endfacet + facet normal -0.00135902 -0.0842293 -0.996445 + outer loop + vertex -20.9001 -24.7378 0.687191 + vertex -41.959 -20.4337 0.352089 + vertex -20.6471 -20.7484 0.349622 + endloop + endfacet + facet normal -0.000777018 -0.0447915 -0.998996 + outer loop + vertex -41.959 -20.4337 0.352089 + vertex -42.1547 -16.5338 0.177382 + vertex -20.6471 -20.7484 0.349622 + endloop + endfacet + facet normal -0.000597903 -0.0438791 -0.999037 + outer loop + vertex -20.6471 -20.7484 0.349622 + vertex -42.1547 -16.5338 0.177382 + vertex -20.889 -16.8475 0.178436 + endloop + endfacet + facet normal -0.000298467 -0.0235869 -0.999722 + outer loop + vertex -42.1547 -16.5338 0.177382 + vertex -42.3174 -12.6654 0.086163 + vertex -20.889 -16.8475 0.178436 + endloop + endfacet + facet normal -0.000590814 -0.0235992 -0.999721 + outer loop + vertex -42.1547 -16.5338 0.177382 + vertex -63.6092 -12.1241 0.0859691 + vertex -42.3174 -12.6654 0.086163 + endloop + endfacet + facet normal -0.000347965 -0.0140462 -0.999901 + outer loop + vertex -63.6092 -12.1241 0.0859691 + vertex -63.4767 -8.30904 0.03233 + vertex -42.3174 -12.6654 0.086163 + endloop + endfacet + facet normal -0.000376926 -0.0141868 -0.999899 + outer loop + vertex -42.3174 -12.6654 0.086163 + vertex -63.4767 -8.30904 0.03233 + vertex -42.2523 -8.8518 0.0320301 + endloop + endfacet + facet normal -0.00021756 -0.00795491 -0.999968 + outer loop + vertex -63.4767 -8.30904 0.03233 + vertex -63.1651 -4.61699 0.00289141 + vertex -42.2523 -8.8518 0.0320301 + endloop + endfacet + facet normal -0.000292579 -0.00794858 -0.999968 + outer loop + vertex -63.4767 -8.30904 0.03233 + vertex -84.3534 -3.83994 0.00291421 + vertex -63.1651 -4.61699 0.00289141 + endloop + endfacet + facet normal -0.000115408 -0.00311754 -0.999995 + outer loop + vertex -84.3534 -3.83994 0.00291421 + vertex -83.8857 -0.359462 -0.00799034 + vertex -63.1651 -4.61699 0.00289141 + endloop + endfacet + facet normal -0.000115096 -0.00311602 -0.999995 + outer loop + vertex -63.1651 -4.61699 0.00289141 + vertex -83.8857 -0.359462 -0.00799034 + vertex -62.7964 -1.132 -0.00801039 + endloop + endfacet + facet normal -3.33092e-06 -6.49739e-05 -1 + outer loop + vertex -83.8857 -0.359462 -0.00799034 + vertex -83.4034 2.84585 -0.0082002 + vertex -62.7964 -1.132 -0.00801039 + endloop + endfacet + facet normal -5.74204e-06 -6.46111e-05 -1 + outer loop + vertex -83.8857 -0.359462 -0.00799034 + vertex -104.376 3.86426 -0.00814558 + vertex -83.4034 2.84585 -0.0082002 + endloop + endfacet + facet normal 4.60621e-05 0.00100222 -0.999999 + outer loop + vertex -104.376 3.86426 -0.00814558 + vertex -103.743 6.75842 -0.00521583 + vertex -83.4034 2.84585 -0.0082002 + endloop + endfacet + facet normal 4.91828e-05 0.00101844 -0.999999 + outer loop + vertex -83.4034 2.84585 -0.0082002 + vertex -103.743 6.75842 -0.00521583 + vertex -82.8972 5.74552 -0.00522216 + endloop + endfacet + facet normal 3.82789e-05 0.000794037 -1 + outer loop + vertex -103.743 6.75842 -0.00521583 + vertex -103.065 9.36525 -0.00311995 + vertex -82.8972 5.74552 -0.00522216 + endloop + endfacet + facet normal 4.77033e-05 0.000791584 -1 + outer loop + vertex -103.743 6.75842 -0.00521583 + vertex -123.748 10.6258 -0.00310874 + vertex -103.065 9.36525 -0.00311995 + endloop + endfacet + facet normal 2.18102e-05 0.000366744 -1 + outer loop + vertex -123.748 10.6258 -0.00310874 + vertex -122.883 12.9876 -0.00222369 + vertex -103.065 9.36525 -0.00311995 + endloop + endfacet + facet normal 2.23527e-05 0.000369712 -1 + outer loop + vertex -103.065 9.36525 -0.00311995 + vertex -122.883 12.9876 -0.00222369 + vertex -102.346 11.7364 -0.00222723 + endloop + endfacet + facet normal 1.23508e-05 0.000205548 -1 + outer loop + vertex -122.883 12.9876 -0.00222369 + vertex -121.981 15.1702 -0.00176395 + vertex -102.346 11.7364 -0.00222723 + endloop + endfacet + facet normal 1.49316e-05 0.000204482 -1 + outer loop + vertex -122.883 12.9876 -0.00222369 + vertex -142.323 16.6597 -0.0017631 + vertex -121.981 15.1702 -0.00176395 + endloop + endfacet + facet normal 1.6818e-05 0.000230244 -1 + outer loop + vertex -142.323 16.6597 -0.0017631 + vertex -141.236 18.6914 -0.00127703 + vertex -121.981 15.1702 -0.00176395 + endloop + endfacet + facet normal 1.69217e-05 0.000230811 -1 + outer loop + vertex -121.981 15.1702 -0.00176395 + vertex -141.236 18.6914 -0.00127703 + vertex -121.055 17.2126 -0.00127685 + endloop + endfacet + facet normal 1.85911e-05 0.000253594 -1 + outer loop + vertex -141.236 18.6914 -0.00127703 + vertex -140.127 20.6035 -0.000771502 + vertex -121.055 17.2126 -0.00127685 + endloop + endfacet + facet normal 2.14828e-05 0.000251917 -1 + outer loop + vertex -141.236 18.6914 -0.00127703 + vertex -160.084 22.3026 -0.000772227 + vertex -140.127 20.6035 -0.000771502 + endloop + endfacet + facet normal 1.74652e-05 0.000204725 -1 + outer loop + vertex -160.084 22.3026 -0.000772227 + vertex -158.795 24.1131 -0.000379046 + vertex -140.127 20.6035 -0.000771502 + endloop + endfacet + facet normal 1.74016e-05 0.000204387 -1 + outer loop + vertex -140.127 20.6035 -0.000771502 + vertex -158.795 24.1131 -0.000379046 + vertex -139.001 22.4282 -0.000378981 + endloop + endfacet + facet normal 1.07837e-05 0.000126643 -1 + outer loop + vertex -158.795 24.1131 -0.000379046 + vertex -157.527 25.883 -0.000141231 + vertex -139.001 22.4282 -0.000378981 + endloop + endfacet + facet normal 1.21138e-05 0.00012569 -1 + outer loop + vertex -158.795 24.1131 -0.000379046 + vertex -177.186 27.7833 -0.000140526 + vertex -157.527 25.883 -0.000141231 + endloop + endfacet + facet normal 7.25794e-06 7.54559e-05 -1 + outer loop + vertex -177.186 27.7833 -0.000140526 + vertex -175.512 29.4847 -9.04322e-14 + vertex -157.527 25.883 -0.000141231 + endloop + endfacet + facet normal 7.3243e-06 7.57872e-05 -1 + outer loop + vertex -157.527 25.883 -0.000141231 + vertex -175.512 29.4847 -9.04322e-14 + vertex -156.643 27.6611 -9.44466e-14 + endloop + endfacet + facet normal 6.51023e-06 7.61918e-05 -1 + outer loop + vertex -157.527 25.883 -0.000141231 + vertex -156.643 27.6611 -9.44466e-14 + vertex -137.984 24.219 -0.000140783 + endloop + endfacet + facet normal 8.06513e-06 7.46617e-05 -1 + outer loop + vertex -177.186 27.7833 -0.000140526 + vertex -196.286 31.7287 -8.99784e-14 + vertex -175.512 29.4847 -9.04322e-14 + endloop + endfacet + facet normal 8.07296e-06 7.46996e-05 -1 + outer loop + vertex -196.702 29.8881 -0.000140852 + vertex -196.286 31.7287 -8.99784e-14 + vertex -177.186 27.7833 -0.000140526 + endloop + endfacet + facet normal 1.35245e-05 0.000125248 -1 + outer loop + vertex -178.531 26.0199 -0.000379573 + vertex -196.702 29.8881 -0.000140852 + vertex -177.186 27.7833 -0.000140526 + endloop + endfacet + facet normal 1.33494e-05 0.000124425 -1 + outer loop + vertex -198.205 28.1401 -0.00037841 + vertex -196.702 29.8881 -0.000140852 + vertex -178.531 26.0199 -0.000379573 + endloop + endfacet + facet normal 2.15502e-05 0.000200526 -1 + outer loop + vertex -179.969 24.2205 -0.000771394 + vertex -198.205 28.1401 -0.00037841 + vertex -178.531 26.0199 -0.000379573 + endloop + endfacet + facet normal 1.94604e-05 0.000202196 -1 + outer loop + vertex -179.969 24.2205 -0.000771394 + vertex -178.531 26.0199 -0.000379573 + vertex -160.084 22.3026 -0.000772227 + endloop + endfacet + facet normal 2.40136e-05 0.000249403 -1 + outer loop + vertex -161.359 20.4008 -0.00127714 + vertex -179.969 24.2205 -0.000771394 + vertex -160.084 22.3026 -0.000772227 + endloop + endfacet + facet normal 2.41182e-05 0.000249913 -1 + outer loop + vertex -181.392 22.3335 -0.00127731 + vertex -179.969 24.2205 -0.000771394 + vertex -161.359 20.4008 -0.00127714 + endloop + endfacet + facet normal 2.19446e-05 0.000227382 -1 + outer loop + vertex -162.596 18.3841 -0.00176284 + vertex -181.392 22.3335 -0.00127731 + vertex -161.359 20.4008 -0.00127714 + endloop + endfacet + facet normal 1.94584e-05 0.000228906 -1 + outer loop + vertex -162.596 18.3841 -0.00176284 + vertex -161.359 20.4008 -0.00127714 + vertex -142.323 16.6597 -0.0017631 + endloop + endfacet + facet normal 1.71687e-05 0.000201988 -1 + outer loop + vertex -143.377 14.4884 -0.00221977 + vertex -162.596 18.3841 -0.00176284 + vertex -142.323 16.6597 -0.0017631 + endloop + endfacet + facet normal 1.75341e-05 0.000203791 -1 + outer loop + vertex -163.803 16.2253 -0.00222394 + vertex -162.596 18.3841 -0.00176284 + vertex -143.377 14.4884 -0.00221977 + endloop + endfacet + facet normal 3.15533e-05 0.000368652 -1 + outer loop + vertex -144.386 12.1372 -0.0031184 + vertex -163.803 16.2253 -0.00222394 + vertex -143.377 14.4884 -0.00221977 + endloop + endfacet + facet normal 2.75889e-05 0.000370353 -1 + outer loop + vertex -144.386 12.1372 -0.0031184 + vertex -143.377 14.4884 -0.00221977 + vertex -123.748 10.6258 -0.00310874 + endloop + endfacet + facet normal 5.82426e-05 0.000788951 -1 + outer loop + vertex -124.564 8.02741 -0.00520629 + vertex -144.386 12.1372 -0.0031184 + vertex -123.748 10.6258 -0.00310874 + endloop + endfacet + facet normal 5.81992e-05 0.000788742 -1 + outer loop + vertex -145.342 9.54836 -0.00521595 + vertex -144.386 12.1372 -0.0031184 + vertex -124.564 8.02741 -0.00520629 + endloop + endfacet + facet normal 7.3351e-05 0.000995739 -1 + outer loop + vertex -125.324 5.14044 -0.0081367 + vertex -145.342 9.54836 -0.00521595 + vertex -124.564 8.02741 -0.00520629 + endloop + endfacet + facet normal 6.04463e-05 0.000999136 -0.999999 + outer loop + vertex -125.324 5.14044 -0.0081367 + vertex -124.564 8.02741 -0.00520629 + vertex -104.376 3.86426 -0.00814558 + endloop + endfacet + facet normal -4.03873e-06 -5.93389e-05 -1 + outer loop + vertex -104.974 0.665124 -0.00795333 + vertex -125.324 5.14044 -0.0081367 + vertex -104.376 3.86426 -0.00814558 + endloop + endfacet + facet normal 2.43092e-06 -2.99208e-05 -1 + outer loop + vertex -126.04 1.94883 -0.00804295 + vertex -125.324 5.14044 -0.0081367 + vertex -104.974 0.665124 -0.00795333 + endloop + endfacet + facet normal -0.000185313 -0.00311079 -0.999995 + outer loop + vertex -105.541 -2.80999 0.00296205 + vertex -126.04 1.94883 -0.00804295 + vertex -104.974 0.665124 -0.00795333 + endloop + endfacet + facet normal -0.000153729 -0.00311594 -0.999995 + outer loop + vertex -105.541 -2.80999 0.00296205 + vertex -104.974 0.665124 -0.00795333 + vertex -84.3534 -3.83994 0.00291421 + endloop + endfacet + facet normal -0.000385592 -0.00788563 -0.999969 + outer loop + vertex -84.7478 -7.52944 0.0321612 + vertex -105.541 -2.80999 0.00296205 + vertex -84.3534 -3.83994 0.00291421 + endloop + endfacet + facet normal -0.00038786 -0.00789563 -0.999969 + outer loop + vertex -106.016 -6.49478 0.0322411 + vertex -105.541 -2.80999 0.00296205 + vertex -84.7478 -7.52944 0.0321612 + endloop + endfacet + facet normal -0.000687198 -0.0140488 -0.999901 + outer loop + vertex -84.944 -11.3429 0.0858767 + vertex -106.016 -6.49478 0.0322411 + vertex -84.7478 -7.52944 0.0321612 + endloop + endfacet + facet normal -0.000510409 -0.0140579 -0.999901 + outer loop + vertex -84.944 -11.3429 0.0858767 + vertex -84.7478 -7.52944 0.0321612 + vertex -63.6092 -12.1241 0.0859691 + endloop + endfacet + facet normal -0.000872788 -0.0239546 -0.999713 + outer loop + vertex -63.4967 -15.9914 0.178536 + vertex -84.944 -11.3429 0.0858767 + vertex -63.6092 -12.1241 0.0859691 + endloop + endfacet + facet normal -0.000845224 -0.0238275 -0.999716 + outer loop + vertex -84.8792 -15.212 0.178039 + vertex -84.944 -11.3429 0.0858767 + vertex -63.4967 -15.9914 0.178536 + endloop + endfacet + facet normal -0.00158412 -0.0440994 -0.999026 + outer loop + vertex -63.3331 -19.897 0.350679 + vertex -84.8792 -15.212 0.178039 + vertex -63.4967 -15.9914 0.178536 + endloop + endfacet + facet normal -0.00104083 -0.0440767 -0.999028 + outer loop + vertex -63.3331 -19.897 0.350679 + vertex -63.4967 -15.9914 0.178536 + vertex -41.959 -20.4337 0.352089 + endloop + endfacet + facet normal -0.00202363 -0.0832106 -0.99653 + outer loop + vertex -42.2243 -24.4233 0.685759 + vertex -63.3331 -19.897 0.350679 + vertex -41.959 -20.4337 0.352089 + endloop + endfacet + facet normal -0.00205743 -0.0833672 -0.996517 + outer loop + vertex -63.6248 -23.8824 0.684695 + vertex -63.3331 -19.897 0.350679 + vertex -42.2243 -24.4233 0.685759 + endloop + endfacet + facet normal -0.00351965 -0.141211 -0.989973 + outer loop + vertex -43.4779 -28.5679 1.28141 + vertex -63.6248 -23.8824 0.684695 + vertex -42.2243 -24.4233 0.685759 + endloop + endfacet + facet normal -0.00226371 -0.141583 -0.989924 + outer loop + vertex -43.4779 -28.5679 1.28141 + vertex -42.2243 -24.4233 0.685759 + vertex -22.1314 -28.8945 1.27931 + endloop + endfacet + facet normal -0.0020049 -0.140442 -0.990087 + outer loop + vertex -22.1314 -28.8945 1.27931 + vertex -42.2243 -24.4233 0.685759 + vertex -20.9001 -24.7378 0.687191 + endloop + endfacet + facet normal -0.00354217 -0.141306 -0.98996 + outer loop + vertex -64.8959 -28.0134 1.2789 + vertex -63.6248 -23.8824 0.684695 + vertex -43.4779 -28.5679 1.28141 + endloop + endfacet + facet normal -0.00521082 -0.140801 -0.990024 + outer loop + vertex -64.8959 -28.0134 1.2789 + vertex -85.0824 -23.098 0.686082 + vertex -63.6248 -23.8824 0.684695 + endloop + endfacet + facet normal -0.00311509 -0.0834572 -0.996506 + outer loop + vertex -85.0824 -23.098 0.686082 + vertex -84.7544 -19.1166 0.351614 + vertex -63.6248 -23.8824 0.684695 + endloop + endfacet + facet normal -0.00389366 -0.0833933 -0.996509 + outer loop + vertex -85.0824 -23.098 0.686082 + vertex -106.163 -18.0839 0.34884 + vertex -84.7544 -19.1166 0.351614 + endloop + endfacet + facet normal -0.00197376 -0.0436001 -0.999047 + outer loop + vertex -106.163 -18.0839 0.34884 + vertex -106.258 -14.1748 0.17843 + vertex -84.7544 -19.1166 0.351614 + endloop + endfacet + facet normal -0.00217619 -0.0444796 -0.999008 + outer loop + vertex -84.7544 -19.1166 0.351614 + vertex -106.258 -14.1748 0.17843 + vertex -84.8792 -15.212 0.178039 + endloop + endfacet + facet normal -0.00117706 -0.0238847 -0.999714 + outer loop + vertex -106.258 -14.1748 0.17843 + vertex -106.275 -10.3058 0.0860128 + vertex -84.8792 -15.212 0.178039 + endloop + endfacet + facet normal -0.00145623 -0.0238859 -0.999714 + outer loop + vertex -106.258 -14.1748 0.17843 + vertex -127.586 -9.00746 0.0860338 + vertex -106.275 -10.3058 0.0860128 + endloop + endfacet + facet normal -0.000854541 -0.01401 -0.999901 + outer loop + vertex -127.586 -9.00746 0.0860338 + vertex -127.26 -5.19879 0.0323907 + vertex -106.275 -10.3058 0.0860128 + endloop + endfacet + facet normal -0.000864125 -0.0140494 -0.999901 + outer loop + vertex -106.275 -10.3058 0.0860128 + vertex -127.26 -5.19879 0.0323907 + vertex -106.016 -6.49478 0.0322411 + endloop + endfacet + facet normal -0.000493988 -0.00798206 -0.999968 + outer loop + vertex -127.26 -5.19879 0.0323907 + vertex -126.707 -1.52062 0.00275725 + vertex -106.016 -6.49478 0.0322411 + endloop + endfacet + facet normal -0.000590105 -0.00796762 -0.999968 + outer loop + vertex -127.26 -5.19879 0.0323907 + vertex -147.832 0.0264346 0.00289662 + vertex -126.707 -1.52062 0.00275725 + endloop + endfacet + facet normal -0.000232872 -0.0030897 -0.999995 + outer loop + vertex -147.832 0.0264346 0.00289662 + vertex -147.064 3.48728 -0.00797521 + vertex -126.707 -1.52062 0.00275725 + endloop + endfacet + facet normal -0.000227803 -0.0030691 -0.999995 + outer loop + vertex -126.707 -1.52062 0.00275725 + vertex -147.064 3.48728 -0.00797521 + vertex -126.04 1.94883 -0.00804295 + endloop + endfacet + facet normal -7.27877e-06 -5.54391e-05 -1 + outer loop + vertex -147.064 3.48728 -0.00797521 + vertex -146.235 6.6712 -0.00815776 + vertex -126.04 1.94883 -0.00804295 + endloop + endfacet + facet normal -5.47584e-06 -5.59087e-05 -1 + outer loop + vertex -147.064 3.48728 -0.00797521 + vertex -167.074 8.44202 -0.00814265 + vertex -146.235 6.6712 -0.00815776 + endloop + endfacet + facet normal 8.34545e-05 0.000990634 -1 + outer loop + vertex -167.074 8.44202 -0.00814265 + vertex -166.054 11.309 -0.00521736 + vertex -146.235 6.6712 -0.00815776 + endloop + endfacet + facet normal 8.47542e-05 0.000996188 -1 + outer loop + vertex -146.235 6.6712 -0.00815776 + vertex -166.054 11.309 -0.00521736 + vertex -145.342 9.54836 -0.00521595 + endloop + endfacet + facet normal 6.74717e-05 0.000792889 -1 + outer loop + vertex -166.054 11.309 -0.00521736 + vertex -164.964 13.8869 -0.00309987 + vertex -145.342 9.54836 -0.00521595 + endloop + endfacet + facet normal 7.69973e-05 0.000788862 -1 + outer loop + vertex -166.054 11.309 -0.00521736 + vertex -185.441 15.8615 -0.00311882 + vertex -164.964 13.8869 -0.00309987 + endloop + endfacet + facet normal 3.60668e-05 0.000364416 -1 + outer loop + vertex -185.441 15.8615 -0.00311882 + vertex -184.138 18.1868 -0.00222447 + vertex -164.964 13.8869 -0.00309987 + endloop + endfacet + facet normal 3.45038e-05 0.000357446 -1 + outer loop + vertex -164.964 13.8869 -0.00309987 + vertex -184.138 18.1868 -0.00222447 + vertex -163.803 16.2253 -0.00222394 + endloop + endfacet + facet normal 1.95776e-05 0.000202701 -1 + outer loop + vertex -184.138 18.1868 -0.00222447 + vertex -182.781 20.3309 -0.00176329 + vertex -163.803 16.2253 -0.00222394 + endloop + endfacet + facet normal 2.16945e-05 0.000201361 -1 + outer loop + vertex -184.138 18.1868 -0.00222447 + vertex -202.909 22.4991 -0.00176335 + vertex -182.781 20.3309 -0.00176329 + endloop + endfacet + facet normal 2.43483e-05 0.000225996 -1 + outer loop + vertex -202.909 22.4991 -0.00176335 + vertex -201.366 24.4863 -0.0012767 + vertex -182.781 20.3309 -0.00176329 + endloop + endfacet + facet normal 2.4309e-05 0.00022582 -1 + outer loop + vertex -182.781 20.3309 -0.00176329 + vertex -201.366 24.4863 -0.0012767 + vertex -181.392 22.3335 -0.00127731 + endloop + endfacet + facet normal 2.66146e-05 0.000247211 -1 + outer loop + vertex -201.366 24.4863 -0.0012767 + vertex -199.795 26.3581 -0.00077216 + vertex -181.392 22.3335 -0.00127731 + endloop + endfacet + facet normal 2.91177e-05 0.00024511 -1 + outer loop + vertex -201.366 24.4863 -0.0012767 + vertex -219.639 28.717 -0.000771784 + vertex -199.795 26.3581 -0.00077216 + endloop + endfacet + facet normal 2.36505e-05 0.000199117 -1 + outer loop + vertex -219.639 28.717 -0.000771784 + vertex -217.895 30.4823 -0.000379043 + vertex -199.795 26.3581 -0.00077216 + endloop + endfacet + facet normal 2.37917e-05 0.000199737 -1 + outer loop + vertex -199.795 26.3581 -0.00077216 + vertex -217.895 30.4823 -0.000379043 + vertex -198.205 28.1401 -0.00037841 + endloop + endfacet + facet normal 1.47185e-05 0.000123462 -1 + outer loop + vertex -217.895 30.4823 -0.000379043 + vertex -216.094 32.1938 -0.000141217 + vertex -198.205 28.1401 -0.00037841 + endloop + endfacet + facet normal 1.58321e-05 0.00012229 -1 + outer loop + vertex -217.895 30.4823 -0.000379043 + vertex -235.793 34.7468 -0.000140899 + vertex -216.094 32.1938 -0.000141217 + endloop + endfacet + facet normal 9.60503e-06 7.42401e-05 -1 + outer loop + vertex -235.793 34.7468 -0.000140899 + vertex -233.608 36.3619 -8.95212e-14 + vertex -216.094 32.1938 -0.000141217 + endloop + endfacet + facet normal 9.54396e-06 7.39835e-05 -1 + outer loop + vertex -216.094 32.1938 -0.000141217 + vertex -233.608 36.3619 -8.95212e-14 + vertex -214.067 33.8412 -8.97699e-14 + endloop + endfacet + facet normal 8.90882e-06 7.4765e-05 -1 + outer loop + vertex -216.094 32.1938 -0.000141217 + vertex -214.067 33.8412 -8.97699e-14 + vertex -196.702 29.8881 -0.000140852 + endloop + endfacet + facet normal 1.02473e-05 7.33711e-05 -1 + outer loop + vertex -235.793 34.7468 -0.000140899 + vertex -254.02 39.2128 -8.924e-14 + vertex -233.608 36.3619 -8.95212e-14 + endloop + endfacet + facet normal 1.02345e-05 7.33189e-05 -1 + outer loop + vertex -255.491 37.5022 -0.00014047 + vertex -254.02 39.2128 -8.924e-14 + vertex -235.793 34.7468 -0.000140899 + endloop + endfacet + facet normal 1.69944e-05 0.000121644 -1 + outer loop + vertex -237.657 33.0453 -0.00037955 + vertex -255.491 37.5022 -0.00014047 + vertex -235.793 34.7468 -0.000140899 + endloop + endfacet + facet normal 1.69019e-05 0.000121273 -1 + outer loop + vertex -257.424 35.8101 -0.00037836 + vertex -255.491 37.5022 -0.00014047 + vertex -237.657 33.0453 -0.00037955 + endloop + endfacet + facet normal 2.71877e-05 0.000194813 -1 + outer loop + vertex -239.555 31.298 -0.000771552 + vertex -257.424 35.8101 -0.00037836 + vertex -237.657 33.0453 -0.00037955 + endloop + endfacet + facet normal 2.54758e-05 0.000196673 -1 + outer loop + vertex -239.555 31.298 -0.000771552 + vertex -237.657 33.0453 -0.00037955 + vertex -219.639 28.717 -0.000771784 + endloop + endfacet + facet normal 3.15214e-05 0.000243324 -1 + outer loop + vertex -221.364 26.8636 -0.00127712 + vertex -239.555 31.298 -0.000771552 + vertex -219.639 28.717 -0.000771784 + endloop + endfacet + facet normal 3.15509e-05 0.000243445 -1 + outer loop + vertex -241.434 29.4652 -0.00127701 + vertex -239.555 31.298 -0.000771552 + vertex -221.364 26.8636 -0.00127712 + endloop + endfacet + facet normal 2.88155e-05 0.000222342 -1 + outer loop + vertex -223.059 24.8932 -0.00176408 + vertex -241.434 29.4652 -0.00127701 + vertex -221.364 26.8636 -0.00127712 + endloop + endfacet + facet normal 2.66716e-05 0.000224187 -1 + outer loop + vertex -223.059 24.8932 -0.00176408 + vertex -221.364 26.8636 -0.00127712 + vertex -202.909 22.4991 -0.00176335 + endloop + endfacet + facet normal 2.39036e-05 0.000200888 -1 + outer loop + vertex -204.413 20.3709 -0.00222685 + vertex -223.059 24.8932 -0.00176408 + vertex -202.909 22.4991 -0.00176335 + endloop + endfacet + facet normal 2.36904e-05 0.000200009 -1 + outer loop + vertex -224.71 22.7823 -0.00222539 + vertex -223.059 24.8932 -0.00176408 + vertex -204.413 20.3709 -0.00222685 + endloop + endfacet + facet normal 4.22047e-05 0.000355845 -1 + outer loop + vertex -205.862 18.0609 -0.00310998 + vertex -224.71 22.7823 -0.00222539 + vertex -204.413 20.3709 -0.00222685 + endloop + endfacet + facet normal 3.81654e-05 0.000358378 -1 + outer loop + vertex -205.862 18.0609 -0.00310998 + vertex -204.413 20.3709 -0.00222685 + vertex -185.441 15.8615 -0.00311882 + endloop + endfacet + facet normal 8.3519e-05 0.000779476 -1 + outer loop + vertex -186.673 13.2972 -0.0052206 + vertex -205.862 18.0609 -0.00310998 + vertex -185.441 15.8615 -0.00311882 + endloop + endfacet + facet normal 8.34693e-05 0.000779276 -1 + outer loop + vertex -207.232 15.5114 -0.00521116 + vertex -205.862 18.0609 -0.00310998 + vertex -186.673 13.2972 -0.0052206 + endloop + endfacet + facet normal 0.000107268 0.00100025 -0.999999 + outer loop + vertex -187.824 10.4432 -0.00819874 + vertex -207.232 15.5114 -0.00521116 + vertex -186.673 13.2972 -0.0052206 + endloop + endfacet + facet normal 9.94717e-05 0.00100339 -0.999999 + outer loop + vertex -187.824 10.4432 -0.00819874 + vertex -186.673 13.2972 -0.0052206 + vertex -167.074 8.44202 -0.00814265 + endloop + endfacet + facet normal -5.68795e-07 -3.39272e-05 -1 + outer loop + vertex -168.023 5.26883 -0.00803445 + vertex -187.824 10.4432 -0.00819874 + vertex -167.074 8.44202 -0.00814265 + endloop + endfacet + facet normal -1.10751e-05 -7.4133e-05 -1 + outer loop + vertex -188.885 7.27947 -0.00795246 + vertex -187.824 10.4432 -0.00819874 + vertex -168.023 5.26883 -0.00803445 + endloop + endfacet + facet normal -0.000303735 -0.00311069 -0.999995 + outer loop + vertex -168.889 1.81649 0.00296784 + vertex -188.885 7.27947 -0.00795246 + vertex -168.023 5.26883 -0.00803445 + endloop + endfacet + facet normal -0.000268569 -0.00311951 -0.999995 + outer loop + vertex -168.889 1.81649 0.00296784 + vertex -168.023 5.26883 -0.00803445 + vertex -147.832 0.0264346 0.00289662 + endloop + endfacet + facet normal -0.000668298 -0.00782169 -0.999969 + outer loop + vertex -148.474 -3.64752 0.0320634 + vertex -168.889 1.81649 0.00296784 + vertex -147.832 0.0264346 0.00289662 + endloop + endfacet + facet normal -0.000682851 -0.00787607 -0.999969 + outer loop + vertex -169.613 -1.84887 0.0323316 + vertex -168.889 1.81649 0.00296784 + vertex -148.474 -3.64752 0.0320634 + endloop + endfacet + facet normal -0.00121329 -0.01411 -0.9999 + outer loop + vertex -148.859 -7.45035 0.086193 + vertex -169.613 -1.84887 0.0323316 + vertex -148.474 -3.64752 0.0320634 + endloop + endfacet + facet normal -0.00104156 -0.0141273 -0.9999 + outer loop + vertex -148.859 -7.45035 0.086193 + vertex -148.474 -3.64752 0.0320634 + vertex -127.586 -9.00746 0.0860338 + endloop + endfacet + facet normal -0.00174853 -0.0237858 -0.999716 + outer loop + vertex -127.618 -12.8777 0.178175 + vertex -148.859 -7.45035 0.086193 + vertex -127.586 -9.00746 0.0860338 + endloop + endfacet + facet normal -0.00171635 -0.0236599 -0.999719 + outer loop + vertex -148.947 -11.3222 0.177977 + vertex -148.859 -7.45035 0.086193 + vertex -127.618 -12.8777 0.178175 + endloop + endfacet + facet normal -0.00323077 -0.0444239 -0.999008 + outer loop + vertex -127.568 -16.785 0.351761 + vertex -148.947 -11.3222 0.177977 + vertex -127.618 -12.8777 0.178175 + endloop + endfacet + facet normal -0.00283174 -0.0444189 -0.999009 + outer loop + vertex -127.568 -16.785 0.351761 + vertex -127.618 -12.8777 0.178175 + vertex -106.163 -18.0839 0.34884 + endloop + endfacet + facet normal -0.00525546 -0.0843663 -0.996421 + outer loop + vertex -106.537 -22.0582 0.68732 + vertex -127.568 -16.785 0.351761 + vertex -106.163 -18.0839 0.34884 + endloop + endfacet + facet normal -0.00498307 -0.0832859 -0.996513 + outer loop + vertex -127.943 -20.7585 0.685728 + vertex -127.568 -16.785 0.351761 + vertex -106.537 -22.0582 0.68732 + endloop + endfacet + facet normal -0.00846956 -0.140696 -0.990017 + outer loop + vertex -107.887 -26.1586 1.28159 + vertex -127.943 -20.7585 0.685728 + vertex -106.537 -22.0582 0.68732 + endloop + endfacet + facet normal -0.00699738 -0.141173 -0.98996 + outer loop + vertex -107.887 -26.1586 1.28159 + vertex -106.537 -22.0582 0.68732 + vertex -86.4097 -27.2136 1.28022 + endloop + endfacet + facet normal -0.00687641 -0.140708 -0.990027 + outer loop + vertex -86.4097 -27.2136 1.28022 + vertex -106.537 -22.0582 0.68732 + vertex -85.0824 -23.098 0.686082 + endloop + endfacet + facet normal -0.00854823 -0.140984 -0.989975 + outer loop + vertex -129.258 -24.8449 1.27904 + vertex -127.943 -20.7585 0.685728 + vertex -107.887 -26.1586 1.28159 + endloop + endfacet + facet normal -0.0101882 -0.140465 -0.990033 + outer loop + vertex -129.258 -24.8449 1.27904 + vertex -149.32 -19.1997 0.684556 + vertex -127.943 -20.7585 0.685728 + endloop + endfacet + facet normal -0.00601683 -0.0832636 -0.996509 + outer loop + vertex -149.32 -19.1997 0.684556 + vertex -148.928 -15.2308 0.350571 + vertex -127.943 -20.7585 0.685728 + endloop + endfacet + facet normal -0.00707695 -0.0831591 -0.996511 + outer loop + vertex -149.32 -19.1997 0.684556 + vertex -170.233 -13.428 0.351426 + vertex -148.928 -15.2308 0.350571 + endloop + endfacet + facet normal -0.00379656 -0.0443922 -0.999007 + outer loop + vertex -170.233 -13.428 0.351426 + vertex -170.209 -9.5198 0.177667 + vertex -148.928 -15.2308 0.350571 + endloop + endfacet + facet normal -0.00372636 -0.044131 -0.999019 + outer loop + vertex -148.928 -15.2308 0.350571 + vertex -170.209 -9.5198 0.177667 + vertex -148.947 -11.3222 0.177977 + endloop + endfacet + facet normal -0.00199057 -0.0236542 -0.999718 + outer loop + vertex -170.209 -9.5198 0.177667 + vertex -170.074 -5.65038 0.0858444 + vertex -148.947 -11.3222 0.177977 + endloop + endfacet + facet normal -0.0022962 -0.0236435 -0.999718 + outer loop + vertex -170.209 -9.5198 0.177667 + vertex -191.189 -3.61428 0.0861881 + vertex -170.074 -5.65038 0.0858444 + endloop + endfacet + facet normal -0.00136869 -0.0140249 -0.999901 + outer loop + vertex -191.189 -3.61428 0.0861881 + vertex -190.665 0.180399 0.0322457 + vertex -170.074 -5.65038 0.0858444 + endloop + endfacet + facet normal -0.00133704 -0.0139132 -0.999902 + outer loop + vertex -170.074 -5.65038 0.0858444 + vertex -190.665 0.180399 0.0322457 + vertex -169.613 -1.84887 0.0323316 + endloop + endfacet + facet normal -0.000754463 -0.00786936 -0.999969 + outer loop + vertex -190.665 0.180399 0.0322457 + vertex -189.857 3.83788 0.00285277 + vertex -169.613 -1.84887 0.0323316 + endloop + endfacet + facet normal -0.000849946 -0.00784825 -0.999969 + outer loop + vertex -190.665 0.180399 0.0322457 + vertex -210.759 6.08835 0.00295668 + vertex -189.857 3.83788 0.00285277 + endloop + endfacet + facet normal -0.000337421 -0.00308784 -0.999995 + outer loop + vertex -210.759 6.08835 0.00295668 + vertex -209.689 9.51933 -0.00799881 + vertex -189.857 3.83788 0.00285277 + endloop + endfacet + facet normal -0.000325883 -0.00304756 -0.999995 + outer loop + vertex -189.857 3.83788 0.00285277 + vertex -209.689 9.51933 -0.00799881 + vertex -188.885 7.27947 -0.00795246 + endloop + endfacet + facet normal -2.71936e-06 -4.59492e-05 -1 + outer loop + vertex -209.689 9.51933 -0.00799881 + vertex -208.508 12.6696 -0.00814677 + vertex -188.885 7.27947 -0.00795246 + endloop + endfacet + facet normal -5.20558e-06 -4.50172e-05 -1 + outer loop + vertex -209.689 9.51933 -0.00799881 + vertex -229.215 15.1285 -0.00814967 + vertex -208.508 12.6696 -0.00814677 + endloop + endfacet + facet normal 0.000116679 0.000981387 -1 + outer loop + vertex -229.215 15.1285 -0.00814967 + vertex -227.808 17.9551 -0.0052116 + vertex -208.508 12.6696 -0.00814677 + endloop + endfacet + facet normal 0.000116497 0.000980719 -1 + outer loop + vertex -208.508 12.6696 -0.00814677 + vertex -227.808 17.9551 -0.0052116 + vertex -207.232 15.5114 -0.00521116 + endloop + endfacet + facet normal 9.16644e-05 0.000771632 -1 + outer loop + vertex -227.808 17.9551 -0.0052116 + vertex -226.3 20.4889 -0.00311821 + vertex -207.232 15.5114 -0.00521116 + endloop + endfacet + facet normal 9.8944e-05 0.000767299 -1 + outer loop + vertex -227.808 17.9551 -0.0052116 + vertex -246.811 23.1459 -0.00310893 + vertex -226.3 20.4889 -0.00311821 + endloop + endfacet + facet normal 4.54771e-05 0.000354557 -1 + outer loop + vertex -246.811 23.1459 -0.00310893 + vertex -245.077 25.421 -0.00222344 + vertex -226.3 20.4889 -0.00311821 + endloop + endfacet + facet normal 4.61909e-05 0.000357274 -1 + outer loop + vertex -226.3 20.4889 -0.00311821 + vertex -245.077 25.421 -0.00222344 + vertex -224.71 22.7823 -0.00222539 + endloop + endfacet + facet normal 2.55362e-05 0.000197846 -1 + outer loop + vertex -245.077 25.421 -0.00222344 + vertex -243.279 27.5136 -0.0017635 + vertex -224.71 22.7823 -0.00222539 + endloop + endfacet + facet normal 2.74145e-05 0.000196232 -1 + outer loop + vertex -245.077 25.421 -0.00222344 + vertex -263.508 30.3428 -0.0017629 + vertex -243.279 27.5136 -0.0017635 + endloop + endfacet + facet normal 3.07537e-05 0.000220108 -1 + outer loop + vertex -263.508 30.3428 -0.0017629 + vertex -261.517 32.2734 -0.00127671 + vertex -243.279 27.5136 -0.0017635 + endloop + endfacet + facet normal 3.07735e-05 0.000220184 -1 + outer loop + vertex -243.279 27.5136 -0.0017635 + vertex -261.517 32.2734 -0.00127671 + vertex -241.434 29.4652 -0.00127701 + endloop + endfacet + facet normal 3.36489e-05 0.000240747 -1 + outer loop + vertex -261.517 32.2734 -0.00127671 + vertex -259.484 34.087 -0.000771695 + vertex -241.434 29.4652 -0.00127701 + endloop + endfacet + facet normal 3.57261e-05 0.000238419 -1 + outer loop + vertex -261.517 32.2734 -0.00127671 + vertex -279.276 37.0502 -0.000772295 + vertex -259.484 34.087 -0.000771695 + endloop + endfacet + facet normal 2.90127e-05 0.000193579 -1 + outer loop + vertex -279.276 37.0502 -0.000772295 + vertex -277.05 38.7479 -0.000379067 + vertex -259.484 34.087 -0.000771695 + endloop + endfacet + facet normal 2.90158e-05 0.00019359 -1 + outer loop + vertex -259.484 34.087 -0.000771695 + vertex -277.05 38.7479 -0.000379067 + vertex -257.424 35.8101 -0.00037836 + endloop + endfacet + facet normal 1.79913e-05 0.000119944 -1 + outer loop + vertex -277.05 38.7479 -0.000379067 + vertex -274.897 40.4084 -0.000141184 + vertex -257.424 35.8101 -0.00037836 + endloop + endfacet + facet normal 1.88826e-05 0.000118789 -1 + outer loop + vertex -277.05 38.7479 -0.000379067 + vertex -294.055 43.4562 -0.000140878 + vertex -274.897 40.4084 -0.000141184 + endloop + endfacet + facet normal 1.14168e-05 7.18617e-05 -1 + outer loop + vertex -294.055 43.4562 -0.000140878 + vertex -291.894 45.0733 -8.86618e-14 + vertex -274.897 40.4084 -0.000141184 + endloop + endfacet + facet normal 1.15536e-05 7.23604e-05 -1 + outer loop + vertex -274.897 40.4084 -0.000141184 + vertex -291.894 45.0733 -8.86618e-14 + vertex -273.387 42.1184 -8.89533e-14 + endloop + endfacet + facet normal 1.09524e-05 7.28914e-05 -1 + outer loop + vertex -274.897 40.4084 -0.000141184 + vertex -273.387 42.1184 -8.89533e-14 + vertex -255.491 37.5022 -0.00014047 + endloop + endfacet + facet normal 1.20191e-05 7.10567e-05 -1 + outer loop + vertex -294.055 43.4562 -0.000140878 + vertex -310.935 48.2941 -8.8344e-14 + vertex -291.894 45.0733 -8.86618e-14 + endloop + endfacet + facet normal 1.17494e-05 7.01157e-05 -1 + outer loop + vertex -312.983 46.6429 -0.000139834 + vertex -310.935 48.2941 -8.8344e-14 + vertex -294.055 43.4562 -0.000140878 + endloop + endfacet + facet normal 1.98445e-05 0.000118198 -1 + outer loop + vertex -296.401 41.8275 -0.000379938 + vertex -312.983 46.6429 -0.000139834 + vertex -294.055 43.4562 -0.000140878 + endloop + endfacet + facet normal 1.97783e-05 0.000117971 -1 + outer loop + vertex -315.476 45.039 -0.000378346 + vertex -312.983 46.6429 -0.000139834 + vertex -296.401 41.8275 -0.000379938 + endloop + endfacet + facet normal 3.17436e-05 0.000189039 -1 + outer loop + vertex -298.805 40.1596 -0.000771564 + vertex -315.476 45.039 -0.000378346 + vertex -296.401 41.8275 -0.000379938 + endloop + endfacet + facet normal 3.03749e-05 0.000191012 -1 + outer loop + vertex -298.805 40.1596 -0.000771564 + vertex -296.401 41.8275 -0.000379938 + vertex -279.276 37.0502 -0.000772295 + endloop + endfacet + facet normal 3.75703e-05 0.000236205 -1 + outer loop + vertex -281.471 35.2607 -0.00127745 + vertex -298.805 40.1596 -0.000771564 + vertex -279.276 37.0502 -0.000772295 + endloop + endfacet + facet normal 3.77868e-05 0.000236971 -1 + outer loop + vertex -301.166 38.4015 -0.00127741 + vertex -298.805 40.1596 -0.000771564 + vertex -281.471 35.2607 -0.00127745 + endloop + endfacet + facet normal 3.44156e-05 0.000215831 -1 + outer loop + vertex -283.61 33.3534 -0.00176273 + vertex -301.166 38.4015 -0.00127741 + vertex -281.471 35.2607 -0.00127745 + endloop + endfacet + facet normal 3.2618e-05 0.000217847 -1 + outer loop + vertex -283.61 33.3534 -0.00176273 + vertex -281.471 35.2607 -0.00127745 + vertex -263.508 30.3428 -0.0017629 + endloop + endfacet + facet normal 2.89458e-05 0.000193327 -1 + outer loop + vertex -265.455 28.2706 -0.00221987 + vertex -283.61 33.3534 -0.00176273 + vertex -263.508 30.3428 -0.0017629 + endloop + endfacet + facet normal 2.95432e-05 0.000195461 -1 + outer loop + vertex -285.708 31.3032 -0.00222543 + vertex -283.61 33.3534 -0.00176273 + vertex -265.455 28.2706 -0.00221987 + endloop + endfacet + facet normal 5.33237e-05 0.000354272 -1 + outer loop + vertex -267.328 26.0142 -0.00311913 + vertex -285.708 31.3032 -0.00222543 + vertex -265.455 28.2706 -0.00221987 + endloop + endfacet + facet normal 5.0367e-05 0.000356726 -1 + outer loop + vertex -267.328 26.0142 -0.00311913 + vertex -265.455 28.2706 -0.00221987 + vertex -246.811 23.1459 -0.00310893 + endloop + endfacet + facet normal 0.000107497 0.000765383 -1 + outer loop + vertex -248.456 20.6292 -0.00521201 + vertex -267.328 26.0142 -0.00311913 + vertex -246.811 23.1459 -0.00310893 + endloop + endfacet + facet normal 0.000106443 0.000761691 -1 + outer loop + vertex -269.112 23.5164 -0.00521157 + vertex -267.328 26.0142 -0.00311913 + vertex -248.456 20.6292 -0.00521201 + endloop + endfacet + facet normal 0.000135712 0.000971088 -1 + outer loop + vertex -249.991 17.8188 -0.00814951 + vertex -269.112 23.5164 -0.00521157 + vertex -248.456 20.6292 -0.00521201 + endloop + endfacet + facet normal 0.000126392 0.00097618 -1 + outer loop + vertex -249.991 17.8188 -0.00814951 + vertex -248.456 20.6292 -0.00521201 + vertex -229.215 15.1285 -0.00814967 + endloop + endfacet + facet normal -4.38115e-06 -3.37755e-05 -1 + outer loop + vertex -230.513 11.9922 -0.00803805 + vertex -249.991 17.8188 -0.00814951 + vertex -229.215 15.1285 -0.00814967 + endloop + endfacet + facet normal -7.09094e-06 -4.28342e-05 -1 + outer loop + vertex -251.407 14.6972 -0.00800576 + vertex -249.991 17.8188 -0.00814951 + vertex -230.513 11.9922 -0.00803805 + endloop + endfacet + facet normal -0.000397695 -0.00305986 -0.999995 + outer loop + vertex -231.686 8.57321 0.00288992 + vertex -251.407 14.6972 -0.00800576 + vertex -230.513 11.9922 -0.00803805 + endloop + endfacet + facet normal -0.000361609 -0.00307223 -0.999995 + outer loop + vertex -231.686 8.57321 0.00288992 + vertex -230.513 11.9922 -0.00803805 + vertex -210.759 6.08835 0.00295668 + endloop + endfacet + facet normal -0.000916583 -0.00774605 -0.99997 + outer loop + vertex -211.657 2.4392 0.032047 + vertex -231.686 8.57321 0.00288992 + vertex -210.759 6.08835 0.00295668 + endloop + endfacet + facet normal -0.000940224 -0.00782324 -0.999969 + outer loop + vertex -232.665 4.93525 0.0322717 + vertex -231.686 8.57321 0.00288992 + vertex -211.657 2.4392 0.032047 + endloop + endfacet + facet normal -0.00167116 -0.013975 -0.999901 + outer loop + vertex -212.249 -1.34982 0.0859941 + vertex -232.665 4.93525 0.0322717 + vertex -211.657 2.4392 0.032047 + endloop + endfacet + facet normal -0.00149633 -0.0140024 -0.999901 + outer loop + vertex -212.249 -1.34982 0.0859941 + vertex -211.657 2.4392 0.032047 + vertex -191.189 -3.61428 0.0861881 + endloop + endfacet + facet normal -0.00254457 -0.0237515 -0.999715 + outer loop + vertex -191.382 -7.48272 0.178588 + vertex -212.249 -1.34982 0.0859941 + vertex -191.189 -3.61428 0.0861881 + endloop + endfacet + facet normal -0.00251411 -0.0236479 -0.999717 + outer loop + vertex -212.495 -5.21705 0.17809 + vertex -212.249 -1.34982 0.0859941 + vertex -191.382 -7.48272 0.178588 + endloop + endfacet + facet normal -0.00470604 -0.0440736 -0.999017 + outer loop + vertex -191.451 -11.3934 0.351435 + vertex -212.495 -5.21705 0.17809 + vertex -191.382 -7.48272 0.178588 + endloop + endfacet + facet normal -0.0042277 -0.044082 -0.999019 + outer loop + vertex -191.451 -11.3934 0.351435 + vertex -191.382 -7.48272 0.178588 + vertex -170.233 -13.428 0.351426 + endloop + endfacet + facet normal -0.00797499 -0.0831592 -0.996504 + outer loop + vertex -170.666 -17.3934 0.685806 + vertex -191.451 -11.3934 0.351435 + vertex -170.233 -13.428 0.351426 + endloop + endfacet + facet normal -0.0080543 -0.0834326 -0.996481 + outer loop + vertex -191.922 -15.3532 0.686793 + vertex -191.451 -11.3934 0.351435 + vertex -170.666 -17.3934 0.685806 + endloop + endfacet + facet normal -0.0135655 -0.140854 -0.989937 + outer loop + vertex -172.064 -21.4457 1.28155 + vertex -191.922 -15.3532 0.686793 + vertex -170.666 -17.3934 0.685806 + endloop + endfacet + facet normal -0.0121096 -0.141349 -0.989886 + outer loop + vertex -172.064 -21.4457 1.28155 + vertex -170.666 -17.3934 0.685806 + vertex -150.66 -23.2693 1.2801 + endloop + endfacet + facet normal -0.011983 -0.140924 -0.989948 + outer loop + vertex -150.66 -23.2693 1.2801 + vertex -170.666 -17.3934 0.685806 + vertex -149.32 -19.1997 0.684556 + endloop + endfacet + facet normal -0.0135283 -0.140735 -0.989955 + outer loop + vertex -193.338 -19.3908 1.28014 + vertex -191.922 -15.3532 0.686793 + vertex -172.064 -21.4457 1.28155 + endloop + endfacet + facet normal -0.0149411 -0.140247 -0.990004 + outer loop + vertex -193.338 -19.3908 1.28014 + vertex -213.099 -13.0818 0.684626 + vertex -191.922 -15.3532 0.686793 + endloop + endfacet + facet normal -0.00877002 -0.0827174 -0.996534 + outer loop + vertex -213.099 -13.0818 0.684626 + vertex -212.605 -9.12532 0.351863 + vertex -191.922 -15.3532 0.686793 + endloop + endfacet + facet normal -0.00971411 -0.0825994 -0.996535 + outer loop + vertex -213.099 -13.0818 0.684626 + vertex -233.782 -6.62047 0.350678 + vertex -212.605 -9.12532 0.351863 + endloop + endfacet + facet normal -0.00512637 -0.0438135 -0.999027 + outer loop + vertex -233.782 -6.62047 0.350678 + vertex -233.628 -2.71114 0.178443 + vertex -212.605 -9.12532 0.351863 + endloop + endfacet + facet normal -0.00526628 -0.0442715 -0.999006 + outer loop + vertex -212.605 -9.12532 0.351863 + vertex -233.628 -2.71114 0.178443 + vertex -212.495 -5.21705 0.17809 + endloop + endfacet + facet normal -0.00284114 -0.0238194 -0.999712 + outer loop + vertex -233.628 -2.71114 0.178443 + vertex -233.332 1.15073 0.0855855 + vertex -212.495 -5.21705 0.17809 + endloop + endfacet + facet normal -0.00311268 -0.0237985 -0.999712 + outer loop + vertex -233.628 -2.71114 0.178443 + vertex -254.482 3.89078 0.0862112 + vertex -233.332 1.15073 0.0855855 + endloop + endfacet + facet normal -0.00184388 -0.0140046 -0.9999 + outer loop + vertex -254.482 3.89078 0.0862112 + vertex -253.753 7.66463 0.0320105 + vertex -233.332 1.15073 0.0855855 + endloop + endfacet + facet normal -0.00177033 -0.013774 -0.999904 + outer loop + vertex -233.332 1.15073 0.0855855 + vertex -253.753 7.66463 0.0320105 + vertex -232.665 4.93525 0.0322717 + endloop + endfacet + facet normal -0.000991096 -0.00775334 -0.999969 + outer loop + vertex -253.753 7.66463 0.0320105 + vertex -252.685 11.2922 0.00282502 + vertex -232.665 4.93525 0.0322717 + endloop + endfacet + facet normal -0.00108571 -0.00772547 -0.99997 + outer loop + vertex -253.753 7.66463 0.0320105 + vertex -273.689 14.2279 0.00295034 + vertex -252.685 11.2922 0.00282502 + endloop + endfacet + facet normal -0.000431364 -0.00304367 -0.999995 + outer loop + vertex -273.689 14.2279 0.00295034 + vertex -272.309 17.6179 -0.0079634 + vertex -252.685 11.2922 0.00282502 + endloop + endfacet + facet normal -0.000424253 -0.00302161 -0.999995 + outer loop + vertex -252.685 11.2922 0.00282502 + vertex -272.309 17.6179 -0.0079634 + vertex -251.407 14.6972 -0.00800576 + endloop + endfacet + facet normal -9.1559e-06 -5.10172e-05 -1 + outer loop + vertex -272.309 17.6179 -0.0079634 + vertex -270.775 20.7229 -0.00813585 + vertex -251.407 14.6972 -0.00800576 + endloop + endfacet + facet normal -6.65223e-06 -5.22541e-05 -1 + outer loop + vertex -272.309 17.6179 -0.0079634 + vertex -291.441 23.8162 -0.00816001 + vertex -270.775 20.7229 -0.00813585 + endloop + endfacet + facet normal 0.000145628 0.000965131 -1 + outer loop + vertex -291.441 23.8162 -0.00816001 + vertex -289.644 26.5891 -0.00522215 + vertex -270.775 20.7229 -0.00813585 + endloop + endfacet + facet normal 0.000144325 0.000960939 -1 + outer loop + vertex -270.775 20.7229 -0.00813585 + vertex -289.644 26.5891 -0.00522215 + vertex -269.112 23.5164 -0.00521157 + endloop + endfacet + facet normal 0.000115 0.000764987 -1 + outer loop + vertex -289.644 26.5891 -0.00522215 + vertex -287.733 29.0694 -0.00310496 + vertex -269.112 23.5164 -0.00521157 + endloop + endfacet + facet normal 0.000121841 0.000759714 -1 + outer loop + vertex -289.644 26.5891 -0.00522215 + vertex -307.916 32.2853 -0.00312098 + vertex -287.733 29.0694 -0.00310496 + endloop + endfacet + facet normal 5.68955e-05 0.000352103 -1 + outer loop + vertex -307.916 32.2853 -0.00312098 + vertex -305.754 34.499 -0.00221851 + vertex -287.733 29.0694 -0.00310496 + endloop + endfacet + facet normal 5.45405e-05 0.000344287 -1 + outer loop + vertex -287.733 29.0694 -0.00310496 + vertex -305.754 34.499 -0.00221851 + vertex -285.708 31.3032 -0.00222543 + endloop + endfacet + facet normal 3.01603e-05 0.000191354 -1 + outer loop + vertex -305.754 34.499 -0.00221851 + vertex -303.493 36.5229 -0.00176302 + vertex -285.708 31.3032 -0.00222543 + endloop + endfacet + facet normal 3.19255e-05 0.000189382 -1 + outer loop + vertex -305.754 34.499 -0.00221851 + vertex -323.159 39.8419 -0.00176233 + vertex -303.493 36.5229 -0.00176302 + endloop + endfacet + facet normal 3.60691e-05 0.000213935 -1 + outer loop + vertex -323.159 39.8419 -0.00176233 + vertex -320.642 41.687 -0.0012768 + vertex -303.493 36.5229 -0.00176302 + endloop + endfacet + facet normal 3.6047e-05 0.000213862 -1 + outer loop + vertex -303.493 36.5229 -0.00176302 + vertex -320.642 41.687 -0.0012768 + vertex -301.166 38.4015 -0.00127741 + endloop + endfacet + facet normal 3.94928e-05 0.000234288 -1 + outer loop + vertex -320.642 41.687 -0.0012768 + vertex -318.067 43.408 -0.00077188 + vertex -301.166 38.4015 -0.00127741 + endloop + endfacet + facet normal 4.12412e-05 0.000231671 -1 + outer loop + vertex -320.642 41.687 -0.0012768 + vertex -337.23 46.8176 -0.000772319 + vertex -318.067 43.408 -0.00077188 + endloop + endfacet + facet normal 3.3462e-05 0.000187948 -1 + outer loop + vertex -337.23 46.8176 -0.000772319 + vertex -334.458 48.4164 -0.000379036 + vertex -318.067 43.408 -0.00077188 + endloop + endfacet + facet normal 3.34989e-05 0.000188069 -1 + outer loop + vertex -318.067 43.408 -0.00077188 + vertex -334.458 48.4164 -0.000379036 + vertex -315.476 45.039 -0.000378346 + endloop + endfacet + facet normal 2.06714e-05 0.000115974 -1 + outer loop + vertex -334.458 48.4164 -0.000379036 + vertex -331.875 50.0082 -0.000141049 + vertex -315.476 45.039 -0.000378346 + endloop + endfacet + facet normal 2.14818e-05 0.00011466 -1 + outer loop + vertex -334.458 48.4164 -0.000379036 + vertex -350.93 53.5884 -0.000139872 + vertex -331.875 50.0082 -0.000141049 + endloop + endfacet + facet normal 1.27163e-05 6.8008e-05 -1 + outer loop + vertex -350.93 53.5884 -0.000139872 + vertex -349.099 55.3028 -8.76525e-14 + vertex -331.875 50.0082 -0.000141049 + endloop + endfacet + facet normal 1.29573e-05 6.87918e-05 -1 + outer loop + vertex -331.875 50.0082 -0.000141049 + vertex -349.099 55.3028 -8.76525e-14 + vertex -329.464 51.6044 -8.80174e-14 + endloop + endfacet + facet normal 1.24538e-05 6.95524e-05 -1 + outer loop + vertex -331.875 50.0082 -0.000141049 + vertex -329.464 51.6044 -8.80174e-14 + vertex -312.983 46.6429 -0.000139834 + endloop + endfacet + facet normal 1.33401e-05 6.73418e-05 -1 + outer loop + vertex -350.93 53.5884 -0.000139872 + vertex -367.645 58.9767 -8.729e-14 + vertex -349.099 55.3028 -8.76525e-14 + endloop + endfacet + facet normal 1.3483e-05 6.77849e-05 -1 + outer loop + vertex -370.499 57.4758 -0.00014022 + vertex -367.645 58.9767 -8.729e-14 + vertex -350.93 53.5884 -0.000139872 + endloop + endfacet + facet normal 2.26908e-05 0.000114138 -1 + outer loop + vertex -353.649 52.022 -0.00038035 + vertex -370.499 57.4758 -0.00014022 + vertex -350.93 53.5884 -0.000139872 + endloop + endfacet + facet normal 2.23504e-05 0.000113086 -1 + outer loop + vertex -373.243 55.9085 -0.000378775 + vertex -370.499 57.4758 -0.00014022 + vertex -353.649 52.022 -0.00038035 + endloop + endfacet + facet normal 3.59289e-05 0.000181543 -1 + outer loop + vertex -356.512 50.4327 -0.000771756 + vertex -373.243 55.9085 -0.000378775 + vertex -353.649 52.022 -0.00038035 + endloop + endfacet + facet normal 3.44932e-05 0.00018413 -1 + outer loop + vertex -356.512 50.4327 -0.000771756 + vertex -353.649 52.022 -0.00038035 + vertex -337.23 46.8176 -0.000772319 + endloop + endfacet + facet normal 4.28558e-05 0.000228733 -1 + outer loop + vertex -339.993 45.1288 -0.00127698 + vertex -356.512 50.4327 -0.000771756 + vertex -337.23 46.8176 -0.000772319 + endloop + endfacet + facet normal 4.31658e-05 0.000229698 -1 + outer loop + vertex -359.382 48.7649 -0.00127873 + vertex -356.512 50.4327 -0.000771756 + vertex -339.993 45.1288 -0.00127698 + endloop + endfacet + facet normal 3.95642e-05 0.000210493 -1 + outer loop + vertex -342.686 43.3153 -0.00176526 + vertex -359.382 48.7649 -0.00127873 + vertex -339.993 45.1288 -0.00127698 + endloop + endfacet + facet normal 3.80047e-05 0.000212809 -1 + outer loop + vertex -342.686 43.3153 -0.00176526 + vertex -339.993 45.1288 -0.00127698 + vertex -323.159 39.8419 -0.00176233 + endloop + endfacet + facet normal 3.42102e-05 0.000191478 -1 + outer loop + vertex -325.584 37.8448 -0.00222766 + vertex -342.686 43.3153 -0.00176526 + vertex -323.159 39.8419 -0.00176233 + endloop + endfacet + facet normal 3.42196e-05 0.000191507 -1 + outer loop + vertex -345.287 41.3484 -0.00223093 + vertex -342.686 43.3153 -0.00176526 + vertex -325.584 37.8448 -0.00222766 + endloop + endfacet + facet normal 6.08033e-05 0.000341005 -1 + outer loop + vertex -327.912 35.6571 -0.00311528 + vertex -345.287 41.3484 -0.00223093 + vertex -325.584 37.8448 -0.00222766 + endloop + endfacet + facet normal 5.77622e-05 0.000344242 -1 + outer loop + vertex -327.912 35.6571 -0.00311528 + vertex -325.584 37.8448 -0.00222766 + vertex -307.916 32.2853 -0.00312098 + endloop + endfacet + facet normal 0.000125559 0.000746305 -1 + outer loop + vertex -309.977 29.8283 -0.00521336 + vertex -327.912 35.6571 -0.00311528 + vertex -307.916 32.2853 -0.00312098 + endloop + endfacet + facet normal 0.000127602 0.000752592 -1 + outer loop + vertex -330.107 33.2192 -0.00523013 + vertex -327.912 35.6571 -0.00311528 + vertex -309.977 29.8283 -0.00521336 + endloop + endfacet + facet normal 0.000162197 0.000957969 -1 + outer loop + vertex -311.895 27.072 -0.00816493 + vertex -330.107 33.2192 -0.00523013 + vertex -309.977 29.8283 -0.00521336 + endloop + endfacet + facet normal 0.000153671 0.000963904 -1 + outer loop + vertex -311.895 27.072 -0.00816493 + vertex -309.977 29.8283 -0.00521336 + vertex -291.441 23.8162 -0.00816001 + endloop + endfacet + facet normal -5.21079e-06 -3.42455e-05 -1 + outer loop + vertex -293.092 20.7281 -0.00804565 + vertex -311.895 27.072 -0.00816493 + vertex -291.441 23.8162 -0.00816001 + endloop + endfacet + facet normal -5.55411e-06 -3.52631e-05 -1 + outer loop + vertex -313.662 24.001 -0.00804682 + vertex -311.895 27.072 -0.00816493 + vertex -293.092 20.7281 -0.00804565 + endloop + endfacet + facet normal -0.000480949 -0.00302307 -0.999995 + outer loop + vertex -294.575 17.3529 0.00287101 + vertex -313.662 24.001 -0.00804682 + vertex -293.092 20.7281 -0.00804565 + endloop + endfacet + facet normal -0.000450533 -0.00303644 -0.999995 + outer loop + vertex -294.575 17.3529 0.00287101 + vertex -293.092 20.7281 -0.00804565 + vertex -273.689 14.2279 0.00295034 + endloop + endfacet + facet normal -0.0011532 -0.00773261 -0.999969 + outer loop + vertex -274.846 10.6138 0.0322308 + vertex -294.575 17.3529 0.00287101 + vertex -273.689 14.2279 0.00295034 + endloop + endfacet + facet normal -0.00115479 -0.00773725 -0.999969 + outer loop + vertex -295.818 13.7517 0.0321708 + vertex -294.575 17.3529 0.00287101 + vertex -274.846 10.6138 0.0322308 + endloop + endfacet + facet normal -0.00206054 -0.0137909 -0.999903 + outer loop + vertex -275.656 6.84692 0.0858541 + vertex -295.818 13.7517 0.0321708 + vertex -274.846 10.6138 0.0322308 + endloop + endfacet + facet normal -0.00191298 -0.0138226 -0.999903 + outer loop + vertex -275.656 6.84692 0.0858541 + vertex -274.846 10.6138 0.0322308 + vertex -254.482 3.89078 0.0862112 + endloop + endfacet + facet normal -0.00328112 -0.023622 -0.999716 + outer loop + vertex -254.843 0.030964 0.178598 + vertex -275.656 6.84692 0.0858541 + vertex -254.482 3.89078 0.0862112 + endloop + endfacet + facet normal -0.00325462 -0.0235411 -0.999718 + outer loop + vertex -276.074 2.9916 0.177999 + vertex -275.656 6.84692 0.0858541 + vertex -254.843 0.030964 0.178598 + endloop + endfacet + facet normal -0.00610442 -0.0439767 -0.999014 + outer loop + vertex -255.047 -3.87514 0.351789 + vertex -276.074 2.9916 0.177999 + vertex -254.843 0.030964 0.178598 + endloop + endfacet + facet normal -0.0057322 -0.0439962 -0.999015 + outer loop + vertex -255.047 -3.87514 0.351789 + vertex -254.843 0.030964 0.178598 + vertex -233.782 -6.62047 0.350678 + endloop + endfacet + facet normal -0.0107704 -0.0830216 -0.99649 + outer loop + vertex -234.316 -10.5699 0.685503 + vertex -255.047 -3.87514 0.351789 + vertex -233.782 -6.62047 0.350678 + endloop + endfacet + facet normal -0.0107016 -0.0828097 -0.996508 + outer loop + vertex -255.61 -7.82125 0.685757 + vertex -255.047 -3.87514 0.351789 + vertex -234.316 -10.5699 0.685503 + endloop + endfacet + facet normal -0.0181248 -0.140315 -0.989941 + outer loop + vertex -235.764 -14.5793 1.28029 + vertex -255.61 -7.82125 0.685757 + vertex -234.316 -10.5699 0.685503 + endloop + endfacet + facet normal -0.0168152 -0.140782 -0.989898 + outer loop + vertex -235.764 -14.5793 1.28029 + vertex -234.316 -10.5699 0.685503 + vertex -214.536 -17.1035 1.27868 + endloop + endfacet + facet normal -0.0166492 -0.140286 -0.989971 + outer loop + vertex -214.536 -17.1035 1.27868 + vertex -234.316 -10.5699 0.685503 + vertex -213.099 -13.0818 0.684626 + endloop + endfacet + facet normal -0.0182983 -0.140818 -0.989866 + outer loop + vertex -257.057 -11.8204 1.28143 + vertex -255.61 -7.82125 0.685757 + vertex -235.764 -14.5793 1.28029 + endloop + endfacet + facet normal -0.0195524 -0.14037 -0.989906 + outer loop + vertex -257.057 -11.8204 1.28143 + vertex -276.918 -4.85227 0.68564 + vertex -255.61 -7.82125 0.685757 + endloop + endfacet + facet normal -0.0115532 -0.0829587 -0.996486 + outer loop + vertex -276.918 -4.85227 0.68564 + vertex -276.319 -0.912128 0.350672 + vertex -255.61 -7.82125 0.685757 + endloop + endfacet + facet normal -0.0124029 -0.0828296 -0.996487 + outer loop + vertex -276.918 -4.85227 0.68564 + vertex -297.468 2.24285 0.351656 + vertex -276.319 -0.912128 0.350672 + endloop + endfacet + facet normal -0.00658412 -0.0438236 -0.999018 + outer loop + vertex -297.468 2.24285 0.351656 + vertex -297.171 6.14463 0.178539 + vertex -276.319 -0.912128 0.350672 + endloop + endfacet + facet normal -0.00656801 -0.0437761 -0.99902 + outer loop + vertex -276.319 -0.912128 0.350672 + vertex -297.171 6.14463 0.178539 + vertex -276.074 2.9916 0.177999 + endloop + endfacet + facet normal -0.00356604 -0.0236895 -0.999713 + outer loop + vertex -297.171 6.14463 0.178539 + vertex -296.7 9.99403 0.085642 + vertex -276.074 2.9916 0.177999 + endloop + endfacet + facet normal -0.00377387 -0.0236641 -0.999713 + outer loop + vertex -297.171 6.14463 0.178539 + vertex -317.527 13.3052 0.0858828 + vertex -296.7 9.99403 0.085642 + endloop + endfacet + facet normal -0.00219779 -0.0137509 -0.999903 + outer loop + vertex -317.527 13.3052 0.0858828 + vertex -316.573 17.0531 0.0322466 + vertex -296.7 9.99403 0.085642 + endloop + endfacet + facet normal -0.00218525 -0.0137156 -0.999904 + outer loop + vertex -296.7 9.99403 0.085642 + vertex -316.573 17.0531 0.0322466 + vertex -295.818 13.7517 0.0321708 + endloop + endfacet + facet normal -0.0012411 -0.00777978 -0.999969 + outer loop + vertex -316.573 17.0531 0.0322466 + vertex -315.252 20.6421 0.00268411 + vertex -295.818 13.7517 0.0321708 + endloop + endfacet + facet normal -0.00130888 -0.00775484 -0.999969 + outer loop + vertex -316.573 17.0531 0.0322466 + vertex -335.722 24.0827 0.00279461 + vertex -315.252 20.6421 0.00268411 + endloop + endfacet + facet normal -0.000508034 -0.00299035 -0.999995 + outer loop + vertex -335.722 24.0827 0.00279461 + vertex -334.035 27.4268 -0.00806209 + vertex -315.252 20.6421 0.00268411 + endloop + endfacet + facet normal -0.000496891 -0.0029595 -0.999995 + outer loop + vertex -315.252 20.6421 0.00268411 + vertex -334.035 27.4268 -0.00806209 + vertex -313.662 24.001 -0.00804682 + endloop + endfacet + facet normal -5.74593e-06 -3.86292e-05 -1 + outer loop + vertex -334.035 27.4268 -0.00806209 + vertex -332.155 30.4815 -0.0081909 + vertex -313.662 24.001 -0.00804682 + endloop + endfacet + facet normal -3.80921e-06 -3.98214e-05 -1 + outer loop + vertex -334.035 27.4268 -0.00806209 + vertex -352.283 34.0526 -0.00825643 + vertex -332.155 30.4815 -0.0081909 + endloop + endfacet + facet normal 0.000173706 0.000960762 -1 + outer loop + vertex -352.283 34.0526 -0.00825643 + vertex -350.108 36.7711 -0.00526676 + vertex -332.155 30.4815 -0.0081909 + endloop + endfacet + facet normal 0.000171163 0.000953503 -1 + outer loop + vertex -332.155 30.4815 -0.0081909 + vertex -350.108 36.7711 -0.00526676 + vertex -330.107 33.2192 -0.00523013 + endloop + endfacet + facet normal 0.000135223 0.000751123 -1 + outer loop + vertex -350.108 36.7711 -0.00526676 + vertex -347.768 39.1862 -0.00313627 + vertex -330.107 33.2192 -0.00523013 + endloop + endfacet + facet normal 0.00014216 0.000744401 -1 + outer loop + vertex -350.108 36.7711 -0.00526676 + vertex -367.589 42.9118 -0.00318076 + vertex -347.768 39.1862 -0.00313627 + endloop + endfacet + facet normal 6.87767e-05 0.000353974 -1 + outer loop + vertex -367.589 42.9118 -0.00318076 + vertex -364.951 45.0424 -0.00224514 + vertex -347.768 39.1862 -0.00313627 + endloop + endfacet + facet normal 6.53005e-05 0.000343775 -1 + outer loop + vertex -347.768 39.1862 -0.00313627 + vertex -364.951 45.0424 -0.00224514 + vertex -345.287 41.3484 -0.00223093 + endloop + endfacet + facet normal 3.68509e-05 0.000192326 -1 + outer loop + vertex -364.951 45.0424 -0.00224514 + vertex -362.203 46.9774 -0.00177169 + vertex -345.287 41.3484 -0.00223093 + endloop + endfacet + facet normal 3.86572e-05 0.00018976 -1 + outer loop + vertex -364.951 45.0424 -0.00224514 + vertex -381.926 50.9079 -0.00178829 + vertex -362.203 46.9774 -0.00177169 + endloop + endfacet + facet normal 4.3504e-05 0.000214082 -1 + outer loop + vertex -381.926 50.9079 -0.00178829 + vertex -379.01 52.6653 -0.00128521 + vertex -362.203 46.9774 -0.00177169 + endloop + endfacet + facet normal 4.19727e-05 0.000209557 -1 + outer loop + vertex -362.203 46.9774 -0.00177169 + vertex -379.01 52.6653 -0.00128521 + vertex -359.382 48.7649 -0.00127873 + endloop + endfacet + facet normal 4.57461e-05 0.000228545 -1 + outer loop + vertex -379.01 52.6653 -0.00128521 + vertex -376.117 54.3239 -0.000773797 + vertex -359.382 48.7649 -0.00127873 + endloop + endfacet + facet normal 4.76682e-05 0.000225192 -1 + outer loop + vertex -379.01 52.6653 -0.00128521 + vertex -396.21 58.5506 -0.000779787 + vertex -376.117 54.3239 -0.000773797 + endloop + endfacet + facet normal 3.86674e-05 0.000182404 -1 + outer loop + vertex -396.21 58.5506 -0.000779787 + vertex -393.303 60.1203 -0.000381065 + vertex -376.117 54.3239 -0.000773797 + endloop + endfacet + facet normal 3.79874e-05 0.000180387 -1 + outer loop + vertex -376.117 54.3239 -0.000773797 + vertex -393.303 60.1203 -0.000381065 + vertex -373.243 55.9085 -0.000378775 + endloop + endfacet + facet normal 2.37409e-05 0.000112532 -1 + outer loop + vertex -393.303 60.1203 -0.000381065 + vertex -390.364 61.6332 -0.000141022 + vertex -373.243 55.9085 -0.000378775 + endloop + endfacet + facet normal 2.44432e-05 0.000111168 -1 + outer loop + vertex -393.303 60.1203 -0.000381065 + vertex -410.171 65.9846 -0.000141442 + vertex -390.364 61.6332 -0.000141022 + endloop + endfacet + facet normal 1.507e-05 6.85016e-05 -1 + outer loop + vertex -410.171 65.9846 -0.000141442 + vertex -405.858 67.1005 -8.64885e-14 + vertex -390.364 61.6332 -0.000141022 + endloop + endfacet + facet normal 1.46904e-05 6.74258e-05 -1 + outer loop + vertex -390.364 61.6332 -0.000141022 + vertex -405.858 67.1005 -8.64885e-14 + vertex -388.407 63.2985 -8.68636e-14 + endloop + endfacet + facet normal 1.42583e-05 6.79334e-05 -1 + outer loop + vertex -390.364 61.6332 -0.000141022 + vertex -388.407 63.2985 -8.68636e-14 + vertex -370.499 57.4758 -0.00014022 + endloop + endfacet + facet normal 1.53279e-05 6.75049e-05 -1 + outer loop + vertex -410.171 65.9846 -0.000141442 + vertex -424.982 71.4429 -8.60601e-14 + vertex -405.858 67.1005 -8.64885e-14 + endloop + endfacet + facet normal 1.55633e-05 6.81438e-05 -1 + outer loop + vertex -429.618 70.423 -0.000141659 + vertex -424.982 71.4429 -8.60601e-14 + vertex -410.171 65.9846 -0.000141442 + endloop + endfacet + facet normal 2.52455e-05 0.000110567 -1 + outer loop + vertex -413.615 64.5949 -0.000382043 + vertex -429.618 70.423 -0.000141659 + vertex -410.171 65.9846 -0.000141442 + endloop + endfacet + facet normal 2.52557e-05 0.000110595 -1 + outer loop + vertex -433.61 69.1212 -0.000386453 + vertex -429.618 70.423 -0.000141659 + vertex -413.615 64.5949 -0.000382043 + endloop + endfacet + facet normal 4.14441e-05 0.000182109 -1 + outer loop + vertex -416.771 63.0696 -0.000790606 + vertex -433.61 69.1212 -0.000386453 + vertex -413.615 64.5949 -0.000382043 + endloop + endfacet + facet normal 4.08308e-05 0.000183378 -1 + outer loop + vertex -416.771 63.0696 -0.000790606 + vertex -413.615 64.5949 -0.000382043 + vertex -396.21 58.5506 -0.000779787 + endloop + endfacet + facet normal 5.04323e-05 0.000227063 -1 + outer loop + vertex -399.16 56.9117 -0.00130072 + vertex -416.771 63.0696 -0.000790606 + vertex -396.21 58.5506 -0.000779787 + endloop + endfacet + facet normal 5.28784e-05 0.000234058 -1 + outer loop + vertex -419.862 61.4388 -0.00133576 + vertex -416.771 63.0696 -0.000790606 + vertex -399.16 56.9117 -0.00130072 + endloop + endfacet + facet normal 4.93304e-05 0.000217834 -1 + outer loop + vertex -402.172 55.1804 -0.00182641 + vertex -419.862 61.4388 -0.00133576 + vertex -399.16 56.9117 -0.00130072 + endloop + endfacet + facet normal 4.82489e-05 0.000219715 -1 + outer loop + vertex -402.172 55.1804 -0.00182641 + vertex -399.16 56.9117 -0.00130072 + vertex -381.926 50.9079 -0.00178829 + endloop + endfacet + facet normal 4.3474e-05 0.000197089 -1 + outer loop + vertex -384.809 49.008 -0.00228808 + vertex -402.172 55.1804 -0.00182641 + vertex -381.926 50.9079 -0.00178829 + endloop + endfacet + facet normal 4.69137e-05 0.000206765 -1 + outer loop + vertex -405.201 53.3214 -0.00235289 + vertex -402.172 55.1804 -0.00182641 + vertex -384.809 49.008 -0.00228808 + endloop + endfacet + facet normal 7.73407e-05 0.000350612 -1 + outer loop + vertex -387.601 46.915 -0.00323786 + vertex -405.201 53.3214 -0.00235289 + vertex -384.809 49.008 -0.00228808 + endloop + endfacet + facet normal 7.3907e-05 0.000355193 -1 + outer loop + vertex -387.601 46.915 -0.00323786 + vertex -384.809 49.008 -0.00228808 + vertex -367.589 42.9118 -0.00318076 + endloop + endfacet + facet normal 0.000151708 0.000744111 -1 + outer loop + vertex -370.074 40.5236 -0.00533481 + vertex -387.601 46.915 -0.00323786 + vertex -367.589 42.9118 -0.00318076 + endloop + endfacet + facet normal 0.000154006 0.000750415 -1 + outer loop + vertex -390.229 44.5615 -0.00540864 + vertex -387.601 46.915 -0.00323786 + vertex -370.074 40.5236 -0.00533481 + endloop + endfacet + facet normal 0.000193547 0.000947779 -1 + outer loop + vertex -372.378 37.8287 -0.0083349 + vertex -390.229 44.5615 -0.00540864 + vertex -370.074 40.5236 -0.00533481 + endloop + endfacet + facet normal 0.000183603 0.00095628 -1 + outer loop + vertex -372.378 37.8287 -0.0083349 + vertex -370.074 40.5236 -0.00533481 + vertex -352.283 34.0526 -0.00825643 + endloop + endfacet + facet normal 1.79677e-06 -1.12183e-05 -1 + outer loop + vertex -354.28 31.0159 -0.00822595 + vertex -372.378 37.8287 -0.0083349 + vertex -352.283 34.0526 -0.00825643 + endloop + endfacet + facet normal -3.96168e-06 -2.65159e-05 -1 + outer loop + vertex -374.488 34.8131 -0.00824657 + vertex -372.378 37.8287 -0.0083349 + vertex -354.28 31.0159 -0.00822595 + endloop + endfacet + facet normal -0.00055184 -0.00294234 -0.999996 + outer loop + vertex -356.066 27.6873 0.00255405 + vertex -374.488 34.8131 -0.00824657 + vertex -354.28 31.0159 -0.00822595 + endloop + endfacet + facet normal -0.000513164 -0.0029631 -0.999995 + outer loop + vertex -356.066 27.6873 0.00255405 + vertex -354.28 31.0159 -0.00822595 + vertex -335.722 24.0827 0.00279461 + endloop + endfacet + facet normal -0.00133544 -0.00760416 -0.99997 + outer loop + vertex -337.14 20.5069 0.0318798 + vertex -356.066 27.6873 0.00255405 + vertex -335.722 24.0827 0.00279461 + endloop + endfacet + facet normal -0.00136073 -0.00767081 -0.99997 + outer loop + vertex -357.563 24.1245 0.0319212 + vertex -356.066 27.6873 0.00255405 + vertex -337.14 20.5069 0.0318798 + endloop + endfacet + facet normal -0.00241099 -0.0136003 -0.999905 + outer loop + vertex -338.162 16.7662 0.085226 + vertex -357.563 24.1245 0.0319212 + vertex -337.14 20.5069 0.0318798 + endloop + endfacet + facet normal -0.00225626 -0.0136426 -0.999904 + outer loop + vertex -338.162 16.7662 0.085226 + vertex -337.14 20.5069 0.0318798 + vertex -317.527 13.3052 0.0858828 + endloop + endfacet + facet normal -0.00388074 -0.0233284 -0.99972 + outer loop + vertex -318.062 9.45836 0.177729 + vertex -338.162 16.7662 0.085226 + vertex -317.527 13.3052 0.0858828 + endloop + endfacet + facet normal -0.00398226 -0.0236075 -0.999713 + outer loop + vertex -338.739 12.9237 0.178262 + vertex -338.162 16.7662 0.085226 + vertex -318.062 9.45836 0.177729 + endloop + endfacet + facet normal -0.00732991 -0.0435822 -0.999023 + outer loop + vertex -318.393 5.55748 0.350332 + vertex -338.739 12.9237 0.178262 + vertex -318.062 9.45836 0.177729 + endloop + endfacet + facet normal -0.00684688 -0.0436232 -0.999025 + outer loop + vertex -318.393 5.55748 0.350332 + vertex -318.062 9.45836 0.177729 + vertex -297.468 2.24285 0.351656 + endloop + endfacet + facet normal -0.013025 -0.0826241 -0.996496 + outer loop + vertex -298.109 -1.69243 0.686329 + vertex -318.393 5.55748 0.350332 + vertex -297.468 2.24285 0.351656 + endloop + endfacet + facet normal -0.0129618 -0.0824482 -0.996511 + outer loop + vertex -319.056 1.62476 0.684338 + vertex -318.393 5.55748 0.350332 + vertex -298.109 -1.69243 0.686329 + endloop + endfacet + facet normal -0.0220458 -0.139807 -0.989933 + outer loop + vertex -299.671 -5.65721 1.28104 + vertex -319.056 1.62476 0.684338 + vertex -298.109 -1.69243 0.686329 + endloop + endfacet + facet normal -0.0210573 -0.140191 -0.989901 + outer loop + vertex -299.671 -5.65721 1.28104 + vertex -298.109 -1.69243 0.686329 + vertex -278.411 -8.83541 1.27891 + endloop + endfacet + facet normal -0.0208541 -0.139638 -0.989983 + outer loop + vertex -278.411 -8.83541 1.27891 + vertex -298.109 -1.69243 0.686329 + vertex -276.918 -4.85227 0.68564 + endloop + endfacet + facet normal -0.0221385 -0.14005 -0.989897 + outer loop + vertex -320.607 -2.33218 1.27885 + vertex -319.056 1.62476 0.684338 + vertex -299.671 -5.65721 1.28104 + endloop + endfacet + facet normal -0.023381 -0.139569 -0.989936 + outer loop + vertex -320.607 -2.33218 1.27885 + vertex -339.784 5.08787 0.68564 + vertex -319.056 1.62476 0.684338 + endloop + endfacet + facet normal -0.0138126 -0.0822975 -0.996512 + outer loop + vertex -339.784 5.08787 0.68564 + vertex -339.11 9.02149 0.351441 + vertex -319.056 1.62476 0.684338 + endloop + endfacet + facet normal -0.014458 -0.082187 -0.996512 + outer loop + vertex -339.784 5.08787 0.68564 + vertex -359.69 12.6463 0.351064 + vertex -339.11 9.02149 0.351441 + endloop + endfacet + facet normal -0.00764918 -0.0435311 -0.999023 + outer loop + vertex -359.69 12.6463 0.351064 + vertex -359.291 16.5504 0.1779 + vertex -339.11 9.02149 0.351441 + endloop + endfacet + facet normal -0.00767725 -0.0436063 -0.999019 + outer loop + vertex -339.11 9.02149 0.351441 + vertex -359.291 16.5504 0.1779 + vertex -338.739 12.9237 0.178262 + endloop + endfacet + facet normal -0.00409905 -0.0233289 -0.999719 + outer loop + vertex -359.291 16.5504 0.1779 + vertex -358.654 20.3923 0.0856329 + vertex -338.739 12.9237 0.178262 + endloop + endfacet + facet normal -0.00439193 -0.0232803 -0.999719 + outer loop + vertex -359.291 16.5504 0.1779 + vertex -379.127 24.2388 0.0860028 + vertex -358.654 20.3923 0.0856329 + endloop + endfacet + facet normal -0.00260901 -0.0137905 -0.999902 + outer loop + vertex -379.127 24.2388 0.0860028 + vertex -377.97 27.9577 0.0316942 + vertex -358.654 20.3923 0.0856329 + endloop + endfacet + facet normal -0.00255174 -0.0136443 -0.999904 + outer loop + vertex -358.654 20.3923 0.0856329 + vertex -377.97 27.9577 0.0316942 + vertex -357.563 24.1245 0.0319212 + endloop + endfacet + facet normal -0.00141029 -0.00756743 -0.99997 + outer loop + vertex -377.97 27.9577 0.0316942 + vertex -376.378 31.5047 0.00260651 + vertex -357.563 24.1245 0.0319212 + endloop + endfacet + facet normal -0.00150221 -0.00752617 -0.999971 + outer loop + vertex -377.97 27.9577 0.0316942 + vertex -396.907 35.6261 0.00242638 + vertex -376.378 31.5047 0.00260651 + endloop + endfacet + facet normal -0.000581154 -0.00293841 -0.999996 + outer loop + vertex -396.907 35.6261 0.00242638 + vertex -394.901 38.909 -0.00838602 + vertex -376.378 31.5047 0.00260651 + endloop + endfacet + facet normal -0.000584408 -0.00294655 -0.999995 + outer loop + vertex -376.378 31.5047 0.00260651 + vertex -394.901 38.909 -0.00838602 + vertex -374.488 34.8131 -0.00824657 + endloop + endfacet + facet normal 3.0537e-06 -1.8827e-05 -1 + outer loop + vertex -394.901 38.909 -0.00838602 + vertex -392.665 41.8969 -0.00843545 + vertex -374.488 34.8131 -0.00824657 + endloop + endfacet + facet normal -4.66002e-07 -1.61934e-05 -1 + outer loop + vertex -394.901 38.909 -0.00838602 + vertex -413.499 46.3238 -0.00849743 + vertex -392.665 41.8969 -0.00843545 + endloop + endfacet + facet normal 0.000203159 0.000942094 -1 + outer loop + vertex -413.499 46.3238 -0.00849743 + vertex -410.918 48.954 -0.00549512 + vertex -392.665 41.8969 -0.00843545 + endloop + endfacet + facet normal 0.000205465 0.000948059 -1 + outer loop + vertex -392.665 41.8969 -0.00843545 + vertex -410.918 48.954 -0.00549512 + vertex -390.229 44.5615 -0.00540864 + endloop + endfacet + facet normal 0.00016268 0.000746538 -1 + outer loop + vertex -410.918 48.954 -0.00549512 + vertex -408.144 51.2712 -0.00331393 + vertex -390.229 44.5615 -0.00540864 + endloop + endfacet + facet normal 0.000165994 0.00074257 -1 + outer loop + vertex -410.918 48.954 -0.00549512 + vertex -429.272 55.8875 -0.00339314 + vertex -408.144 51.2712 -0.00331393 + endloop + endfacet + facet normal 8.08501e-05 0.000352879 -1 + outer loop + vertex -429.272 55.8875 -0.00339314 + vertex -426.18 57.9039 -0.00243168 + vertex -408.144 51.2712 -0.00331393 + endloop + endfacet + facet normal 8.08126e-05 0.000352777 -1 + outer loop + vertex -408.144 51.2712 -0.00331393 + vertex -426.18 57.9039 -0.00243168 + vertex -405.201 53.3214 -0.00235289 + endloop + endfacet + facet normal 4.98077e-05 0.000210832 -1 + outer loop + vertex -426.18 57.9039 -0.00243168 + vertex -422.994 59.7236 -0.00188934 + vertex -405.201 53.3214 -0.00235289 + endloop + endfacet + facet normal 4.95941e-05 0.000211206 -1 + outer loop + vertex -426.18 57.9039 -0.00243168 + vertex -443.526 64.1624 -0.00197006 + vertex -422.994 59.7236 -0.00188934 + endloop + endfacet + facet normal 5.42845e-05 0.000232901 -1 + outer loop + vertex -443.526 64.1624 -0.00197006 + vertex -440.201 65.8457 -0.00139756 + vertex -422.994 59.7236 -0.00188934 + endloop + endfacet + facet normal 5.22802e-05 0.000227268 -1 + outer loop + vertex -422.994 59.7236 -0.00188934 + vertex -440.201 65.8457 -0.00139756 + vertex -419.862 61.4388 -0.00133576 + endloop + endfacet + facet normal 5.47882e-05 0.000238843 -1 + outer loop + vertex -440.201 65.8457 -0.00139756 + vertex -437.127 67.5668 -0.000818038 + vertex -419.862 61.4388 -0.00133576 + endloop + endfacet + facet normal 5.26224e-05 0.000242712 -1 + outer loop + vertex -440.201 65.8457 -0.00139756 + vertex -455.071 71.1967 -0.00088133 + vertex -437.127 67.5668 -0.000818038 + endloop + endfacet + facet normal 4.09205e-05 0.000184861 -1 + outer loop + vertex -455.071 71.1967 -0.00088133 + vertex -452.849 73.4245 -0.000378524 + vertex -437.127 67.5668 -0.000818038 + endloop + endfacet + facet normal 4.09653e-05 0.000184982 -1 + outer loop + vertex -437.127 67.5668 -0.000818038 + vertex -452.849 73.4245 -0.000378524 + vertex -433.61 69.1212 -0.000386453 + endloop + endfacet + facet normal 2.26891e-05 0.000103276 -1 + outer loop + vertex -452.849 73.4245 -0.000378524 + vertex -447.428 74.5919 -0.000134971 + vertex -433.61 69.1212 -0.000386453 + endloop + endfacet + facet normal 2.27433e-05 0.000103024 -1 + outer loop + vertex -447.428 74.5919 -0.000134971 + vertex -452.849 73.4245 -0.000378524 + vertex -459.643 77.5703 -0.00010593 + endloop + endfacet + facet normal 8.50927e-06 4.46482e-05 -1 + outer loop + vertex -459.643 77.5703 -0.00010593 + vertex -462.5 80.4873 -8.51677e-14 + vertex -447.428 74.5919 -0.000134971 + endloop + endfacet + facet normal 1.51376e-05 6.15934e-05 -1 + outer loop + vertex -462.5 80.4873 -8.51677e-14 + vertex -444.124 75.9713 -8.56133e-14 + vertex -447.428 74.5919 -0.000134971 + endloop + endfacet + facet normal 1.44358e-05 6.32744e-05 -1 + outer loop + vertex -447.428 74.5919 -0.000134971 + vertex -444.124 75.9713 -8.56133e-14 + vertex -429.618 70.423 -0.000141659 + endloop + endfacet + facet normal 1.20442e-05 4.811e-05 -1 + outer loop + vertex -459.643 77.5703 -0.00010593 + vertex -462.852 80.5755 -8.5159e-14 + vertex -462.5 80.4873 -8.51677e-14 + endloop + endfacet + facet normal 5.54813e-06 4.11737e-05 -1 + outer loop + vertex -465.647 78.8718 -8.56564e-05 + vertex -462.852 80.5755 -8.5159e-14 + vertex -459.643 77.5703 -0.00010593 + endloop + endfacet + facet normal 1.17328e-05 6.97063e-05 -1 + outer loop + vertex -463.864 76.7707 -0.000211199 + vertex -465.647 78.8718 -8.56564e-05 + vertex -459.643 77.5703 -0.00010593 + endloop + endfacet + facet normal 1.53595e-05 7.2784e-05 -1 + outer loop + vertex -469.485 77.3218 -0.00025741 + vertex -465.647 78.8718 -8.56564e-05 + vertex -463.864 76.7707 -0.000211199 + endloop + endfacet + facet normal 2.22401e-05 0.000142947 -1 + outer loop + vertex -465.241 75.0098 -0.000493535 + vertex -469.485 77.3218 -0.00025741 + vertex -463.864 76.7707 -0.000211199 + endloop + endfacet + facet normal 2.70821e-05 0.00013916 -1 + outer loop + vertex -465.241 75.0098 -0.000493535 + vertex -463.864 76.7707 -0.000211199 + vertex -452.849 73.4245 -0.000378524 + endloop + endfacet + facet normal 2.80768e-05 0.000153659 -1 + outer loop + vertex -473.162 75.6644 -0.000615351 + vertex -469.485 77.3218 -0.00025741 + vertex -465.241 75.0098 -0.000493535 + endloop + endfacet + facet normal 3.46593e-05 0.000233315 -1 + outer loop + vertex -468.238 73.3554 -0.000983408 + vertex -473.162 75.6644 -0.000615351 + vertex -465.241 75.0098 -0.000493535 + endloop + endfacet + facet normal 4.34072e-05 0.000217468 -1 + outer loop + vertex -468.238 73.3554 -0.000983408 + vertex -465.241 75.0098 -0.000493535 + vertex -455.071 71.1967 -0.00088133 + endloop + endfacet + facet normal 5.01995e-05 0.000258896 -1 + outer loop + vertex -455.071 71.1967 -0.00088133 + vertex -458.253 69.4989 -0.00148061 + vertex -468.238 73.3554 -0.000983408 + endloop + endfacet + facet normal 4.94273e-05 0.000256897 -1 + outer loop + vertex -471.685 71.8262 -0.0015466 + vertex -468.238 73.3554 -0.000983408 + vertex -458.253 69.4989 -0.00148061 + endloop + endfacet + facet normal 4.59807e-05 0.000237006 -1 + outer loop + vertex -458.253 69.4989 -0.00148061 + vertex -461.711 67.8329 -0.00203445 + vertex -471.685 71.8262 -0.0015466 + endloop + endfacet + facet normal 3.7177e-05 0.000215018 -1 + outer loop + vertex -475.337 70.1471 -0.0020434 + vertex -471.685 71.8262 -0.0015466 + vertex -461.711 67.8329 -0.00203445 + endloop + endfacet + facet normal 3.49552e-05 0.000201937 -1 + outer loop + vertex -461.711 67.8329 -0.00203445 + vertex -465.191 66.0135 -0.00252349 + vertex -475.337 70.1471 -0.0020434 + endloop + endfacet + facet normal 3.42258e-05 0.000200147 -1 + outer loop + vertex -478.969 68.2085 -0.00255574 + vertex -475.337 70.1471 -0.0020434 + vertex -465.191 66.0135 -0.00252349 + endloop + endfacet + facet normal 6.23173e-05 0.000376481 -1 + outer loop + vertex -465.191 66.0135 -0.00252349 + vertex -468.503 63.9599 -0.00350301 + vertex -478.969 68.2085 -0.00255574 + endloop + endfacet + facet normal 8.28899e-05 0.000427164 -1 + outer loop + vertex -482.262 66.0928 -0.00373242 + vertex -478.969 68.2085 -0.00255574 + vertex -468.503 63.9599 -0.00350301 + endloop + endfacet + facet normal 0.000150244 0.000861657 -1 + outer loop + vertex -468.503 63.9599 -0.00350301 + vertex -471.565 61.631 -0.00596982 + vertex -482.262 66.0928 -0.00373242 + endloop + endfacet + facet normal 0.000185389 0.000945918 -1 + outer loop + vertex -485.262 63.7733 -0.00648273 + vertex -482.262 66.0928 -0.00373242 + vertex -471.565 61.631 -0.00596982 + endloop + endfacet + facet normal 0.000209173 0.00109799 -0.999999 + outer loop + vertex -471.565 61.631 -0.00596982 + vertex -474.436 58.9836 -0.00947722 + vertex -485.262 63.7733 -0.00648273 + endloop + endfacet + facet normal 0.000154016 0.000973317 -1 + outer loop + vertex -487.997 61.0084 -0.0095951 + vertex -485.262 63.7733 -0.00648273 + vertex -474.436 58.9836 -0.00947722 + endloop + endfacet + facet normal -2.1598e-05 -0.000202879 -1 + outer loop + vertex -474.436 58.9836 -0.00947722 + vertex -476.965 55.9457 -0.00880626 + vertex -487.997 61.0084 -0.0095951 + endloop + endfacet + facet normal -0.000358933 -0.000937962 -0.999999 + outer loop + vertex -490.46 57.8147 -0.00571577 + vertex -487.997 61.0084 -0.0095951 + vertex -476.965 55.9457 -0.00880626 + endloop + endfacet + facet normal -0.000798013 -0.0041081 -0.999991 + outer loop + vertex -476.965 55.9457 -0.00880626 + vertex -479.124 52.5876 0.00671191 + vertex -490.46 57.8147 -0.00571577 + endloop + endfacet + facet normal -0.00145543 -0.00553375 -0.999984 + outer loop + vertex -492.696 54.3796 0.0165481 + vertex -490.46 57.8147 -0.00571577 + vertex -479.124 52.5876 0.00671191 + endloop + endfacet + facet normal -0.00199299 -0.0096052 -0.999952 + outer loop + vertex -479.124 52.5876 0.00671191 + vertex -481.104 49.0729 0.0444176 + vertex -492.696 54.3796 0.0165481 + endloop + endfacet + facet normal -0.0030351 -0.0118815 -0.999925 + outer loop + vertex -494.554 50.7477 0.0653434 + vertex -492.696 54.3796 0.0165481 + vertex -481.104 49.0729 0.0444176 + endloop + endfacet + facet normal -0.00353175 -0.0158709 -0.999868 + outer loop + vertex -481.104 49.0729 0.0444176 + vertex -482.607 45.3991 0.108045 + vertex -494.554 50.7477 0.0653434 + endloop + endfacet + facet normal -0.004967 -0.0190762 -0.999806 + outer loop + vertex -496.165 47.0489 0.143917 + vertex -494.554 50.7477 0.0653434 + vertex -482.607 45.3991 0.108045 + endloop + endfacet + facet normal -0.00579552 -0.0258877 -0.999648 + outer loop + vertex -482.607 45.3991 0.108045 + vertex -483.749 41.6757 0.211087 + vertex -496.165 47.0489 0.143917 + endloop + endfacet + facet normal -0.00895108 -0.0331761 -0.999409 + outer loop + vertex -497.038 43.2843 0.276714 + vertex -496.165 47.0489 0.143917 + vertex -483.749 41.6757 0.211087 + endloop + endfacet + facet normal -0.0110925 -0.0508987 -0.998642 + outer loop + vertex -483.749 41.6757 0.211087 + vertex -484.259 37.7755 0.415536 + vertex -497.038 43.2843 0.276714 + endloop + endfacet + facet normal -0.0187005 -0.0685187 -0.997475 + outer loop + vertex -497.183 39.2701 0.555169 + vertex -497.038 43.2843 0.276714 + vertex -484.259 37.7755 0.415536 + endloop + endfacet + facet normal -0.0220578 -0.0977843 -0.994963 + outer loop + vertex -484.259 37.7755 0.415536 + vertex -484.028 33.5131 0.82932 + vertex -497.183 39.2701 0.555169 + endloop + endfacet + facet normal -0.03673 -0.131108 -0.990687 + outer loop + vertex -496.639 34.1271 1.21564 + vertex -497.183 39.2701 0.555169 + vertex -484.028 33.5131 0.82932 + endloop + endfacet + facet normal -0.0377899 -0.155087 -0.987178 + outer loop + vertex -484.028 33.5131 0.82932 + vertex -482.588 29.3247 1.4322 + vertex -496.639 34.1271 1.21564 + endloop + endfacet + facet normal -0.0367584 -0.154746 -0.98727 + outer loop + vertex -482.588 29.3247 1.4322 + vertex -484.028 33.5131 0.82932 + vertex -467.427 26.5014 1.31025 + endloop + endfacet + facet normal -0.0314053 -0.142214 -0.989338 + outer loop + vertex -467.427 26.5014 1.31025 + vertex -484.028 33.5131 0.82932 + vertex -466.694 30.5675 0.70251 + endloop + endfacet + facet normal -0.0316528 -0.142169 -0.989336 + outer loop + vertex -467.427 26.5014 1.31025 + vertex -466.694 30.5675 0.70251 + vertex -447.261 22.2865 1.27075 + endloop + endfacet + facet normal -0.029762 -0.137779 -0.990016 + outer loop + vertex -447.261 22.2865 1.27075 + vertex -466.694 30.5675 0.70251 + vertex -445.687 26.227 0.675033 + endloop + endfacet + facet normal -0.0298839 -0.13773 -0.990019 + outer loop + vertex -447.261 22.2865 1.27075 + vertex -445.687 26.227 0.675033 + vertex -425.517 17.5796 1.26922 + endloop + endfacet + facet normal -0.0300456 -0.138104 -0.989962 + outer loop + vertex -425.517 17.5796 1.26922 + vertex -445.687 26.227 0.675033 + vertex -423.597 21.4312 0.673648 + endloop + endfacet + facet normal -0.0291266 -0.138556 -0.989926 + outer loop + vertex -425.517 17.5796 1.26922 + vertex -423.597 21.4312 0.673648 + vertex -403.83 12.9625 1.27738 + endloop + endfacet + facet normal -0.0291429 -0.138594 -0.98992 + outer loop + vertex -403.83 12.9625 1.27738 + vertex -423.597 21.4312 0.673648 + vertex -401.975 16.8105 0.684014 + endloop + endfacet + facet normal -0.0278908 -0.13919 -0.989873 + outer loop + vertex -403.83 12.9625 1.27738 + vertex -401.975 16.8105 0.684014 + vertex -382.697 8.70089 1.28116 + endloop + endfacet + facet normal -0.027764 -0.138892 -0.989918 + outer loop + vertex -382.697 8.70089 1.28116 + vertex -401.975 16.8105 0.684014 + vertex -381.023 12.5907 0.688458 + endloop + endfacet + facet normal -0.0263188 -0.139507 -0.989871 + outer loop + vertex -382.697 8.70089 1.28116 + vertex -381.023 12.5907 0.688458 + vertex -361.938 4.79045 1.28035 + endloop + endfacet + facet normal -0.0262101 -0.139244 -0.989911 + outer loop + vertex -361.938 4.79045 1.28035 + vertex -381.023 12.5907 0.688458 + vertex -360.386 8.71791 0.686779 + endloop + endfacet + facet normal -0.0246858 -0.13984 -0.989866 + outer loop + vertex -361.938 4.79045 1.28035 + vertex -360.386 8.71791 0.686779 + vertex -341.308 1.13885 1.28171 + endloop + endfacet + facet normal -0.0247019 -0.13988 -0.98986 + outer loop + vertex -341.308 1.13885 1.28171 + vertex -360.386 8.71791 0.686779 + vertex -339.784 5.08787 0.68564 + endloop + endfacet + facet normal -0.0155579 -0.0824757 -0.996472 + outer loop + vertex -381.023 12.5907 0.688458 + vertex -380.258 16.501 0.352859 + vertex -360.386 8.71791 0.686779 + endloop + endfacet + facet normal -0.0155307 -0.0824064 -0.996478 + outer loop + vertex -360.386 8.71791 0.686779 + vertex -380.258 16.501 0.352859 + vertex -359.69 12.6463 0.351064 + endloop + endfacet + facet normal -0.00827783 -0.0437047 -0.99901 + outer loop + vertex -380.258 16.501 0.352859 + vertex -379.814 20.3999 0.178609 + vertex -359.69 12.6463 0.351064 + endloop + endfacet + facet normal -0.00878113 -0.0436473 -0.999008 + outer loop + vertex -380.258 16.501 0.352859 + vertex -400.562 24.5722 0.178688 + vertex -379.814 20.3999 0.178609 + endloop + endfacet + facet normal -0.00472011 -0.0234528 -0.999714 + outer loop + vertex -400.562 24.5722 0.178688 + vertex -399.822 28.3959 0.0854967 + vertex -379.814 20.3999 0.178609 + endloop + endfacet + facet normal -0.00465267 -0.0232841 -0.999718 + outer loop + vertex -379.814 20.3999 0.178609 + vertex -399.822 28.3959 0.0854967 + vertex -379.127 24.2388 0.0860028 + endloop + endfacet + facet normal -0.00269837 -0.0135551 -0.999904 + outer loop + vertex -399.822 28.3959 0.0854967 + vertex -398.592 32.1028 0.0319247 + vertex -379.127 24.2388 0.0860028 + endloop + endfacet + facet normal -0.00285648 -0.0135026 -0.999905 + outer loop + vertex -399.822 28.3959 0.0854967 + vertex -419.772 36.6087 0.0315821 + vertex -398.592 32.1028 0.0319247 + endloop + endfacet + facet normal -0.00159262 -0.00756199 -0.99997 + outer loop + vertex -419.772 36.6087 0.0315821 + vertex -417.999 40.1104 0.0022782 + vertex -398.592 32.1028 0.0319247 + endloop + endfacet + facet normal -0.0016093 -0.0076024 -0.99997 + outer loop + vertex -398.592 32.1028 0.0319247 + vertex -417.999 40.1104 0.0022782 + vertex -396.907 35.6261 0.00242638 + endloop + endfacet + facet normal -0.000609946 -0.00290194 -0.999996 + outer loop + vertex -417.999 40.1104 0.0022782 + vertex -415.873 43.3656 -0.00846512 + vertex -396.907 35.6261 0.00242638 + endloop + endfacet + facet normal -0.000616384 -0.00289773 -0.999996 + outer loop + vertex -417.999 40.1104 0.0022782 + vertex -437.412 48.045 -0.00874824 + vertex -415.873 43.3656 -0.00846512 + endloop + endfacet + facet normal 1.87125e-05 2.56315e-05 -1 + outer loop + vertex -437.412 48.045 -0.00874824 + vertex -434.91 50.9847 -0.00862606 + vertex -415.873 43.3656 -0.00846512 + endloop + endfacet + facet normal 3.09101e-06 -1.34e-05 -1 + outer loop + vertex -415.873 43.3656 -0.00846512 + vertex -434.91 50.9847 -0.00862606 + vertex -413.499 46.3238 -0.00849743 + endloop + endfacet + facet normal 0.000212969 0.000950716 -1 + outer loop + vertex -434.91 50.9847 -0.00862606 + vertex -432.196 53.6022 -0.00555969 + vertex -413.499 46.3238 -0.00849743 + endloop + endfacet + facet normal 0.000208822 0.000955015 -1 + outer loop + vertex -434.91 50.9847 -0.00862606 + vertex -453.124 58.0609 -0.00567163 + vertex -432.196 53.6022 -0.00555969 + endloop + endfacet + facet normal 0.000165904 0.000753575 -1 + outer loop + vertex -453.124 58.0609 -0.00567163 + vertex -450.073 60.348 -0.003442 + vertex -432.196 53.6022 -0.00555969 + endloop + endfacet + facet normal 0.000161356 0.000741524 -1 + outer loop + vertex -432.196 53.6022 -0.00555969 + vertex -450.073 60.348 -0.003442 + vertex -429.272 55.8875 -0.00339314 + endloop + endfacet + facet normal 7.64302e-05 0.000345476 -1 + outer loop + vertex -450.073 60.348 -0.003442 + vertex -446.805 62.3431 -0.00250301 + vertex -429.272 55.8875 -0.00339314 + endloop + endfacet + facet normal 7.1647e-05 0.00035331 -1 + outer loop + vertex -450.073 60.348 -0.003442 + vertex -465.191 66.0135 -0.00252349 + vertex -446.805 62.3431 -0.00250301 + endloop + endfacet + facet normal 0.000154086 0.000769339 -1 + outer loop + vertex -453.124 58.0609 -0.00567163 + vertex -468.503 63.9599 -0.00350301 + vertex -450.073 60.348 -0.003442 + endloop + endfacet + facet normal 0.000231075 0.00101229 -0.999999 + outer loop + vertex -455.937 55.44 -0.00897496 + vertex -453.124 58.0609 -0.00567163 + vertex -434.91 50.9847 -0.00862606 + endloop + endfacet + facet normal 0.000215398 0.00102912 -0.999999 + outer loop + vertex -455.937 55.44 -0.00897496 + vertex -471.565 61.631 -0.00596982 + vertex -453.124 58.0609 -0.00567163 + endloop + endfacet + facet normal 2.15173e-05 2.3244e-05 -1 + outer loop + vertex -437.412 48.045 -0.00874824 + vertex -455.937 55.44 -0.00897496 + vertex -434.91 50.9847 -0.00862606 + endloop + endfacet + facet normal 3.66003e-05 6.10285e-05 -1 + outer loop + vertex -458.519 52.4866 -0.0092497 + vertex -455.937 55.44 -0.00897496 + vertex -437.412 48.045 -0.00874824 + endloop + endfacet + facet normal -0.00058699 -0.00290232 -0.999996 + outer loop + vertex -439.631 44.8034 0.0019623 + vertex -458.519 52.4866 -0.0092497 + vertex -437.412 48.045 -0.00874824 + endloop + endfacet + facet normal -0.000674318 -0.003117 -0.999995 + outer loop + vertex -460.759 49.2197 0.00244411 + vertex -458.519 52.4866 -0.0092497 + vertex -439.631 44.8034 0.0019623 + endloop + endfacet + facet normal -0.00162611 -0.00767062 -0.999969 + outer loop + vertex -441.479 41.3208 0.031682 + vertex -460.759 49.2197 0.00244411 + vertex -439.631 44.8034 0.0019623 + endloop + endfacet + facet normal -0.00166521 -0.00764989 -0.999969 + outer loop + vertex -441.479 41.3208 0.031682 + vertex -439.631 44.8034 0.0019623 + vertex -419.772 36.6087 0.0315821 + endloop + endfacet + facet normal -0.00297029 -0.013662 -0.999902 + outer loop + vertex -421.069 32.9252 0.0857655 + vertex -441.479 41.3208 0.031682 + vertex -419.772 36.6087 0.0315821 + endloop + endfacet + facet normal -0.00302223 -0.0137883 -0.9999 + outer loop + vertex -442.845 37.6542 0.0863731 + vertex -441.479 41.3208 0.031682 + vertex -421.069 32.9252 0.0857655 + endloop + endfacet + facet normal -0.0050349 -0.0230562 -0.999721 + outer loop + vertex -421.896 29.1245 0.177585 + vertex -442.845 37.6542 0.0863731 + vertex -421.069 32.9252 0.0857655 + endloop + endfacet + facet normal -0.0048753 -0.0230909 -0.999721 + outer loop + vertex -421.896 29.1245 0.177585 + vertex -421.069 32.9252 0.0857655 + vertex -400.562 24.5722 0.178688 + endloop + endfacet + facet normal -0.00908912 -0.0428392 -0.999041 + outer loop + vertex -401.073 20.6864 0.349968 + vertex -421.896 29.1245 0.177585 + vertex -400.562 24.5722 0.178688 + endloop + endfacet + facet normal -0.00899082 -0.0425969 -0.999052 + outer loop + vertex -422.554 25.2778 0.347522 + vertex -421.896 29.1245 0.177585 + vertex -401.073 20.6864 0.349968 + endloop + endfacet + facet normal -0.0173788 -0.0818395 -0.996494 + outer loop + vertex -401.975 16.8105 0.684014 + vertex -422.554 25.2778 0.347522 + vertex -401.073 20.6864 0.349968 + endloop + endfacet + facet normal -0.0092435 -0.0425536 -0.999051 + outer loop + vertex -422.554 25.2778 0.347522 + vertex -443.808 33.8903 0.177328 + vertex -421.896 29.1245 0.177585 + endloop + endfacet + facet normal -0.00904896 -0.042074 -0.999074 + outer loop + vertex -444.624 30.0815 0.345116 + vertex -443.808 33.8903 0.177328 + vertex -422.554 25.2778 0.347522 + endloop + endfacet + facet normal -0.0172649 -0.0798194 -0.99666 + outer loop + vertex -423.597 21.4312 0.673648 + vertex -444.624 30.0815 0.345116 + vertex -422.554 25.2778 0.347522 + endloop + endfacet + facet normal -0.00904493 -0.0420748 -0.999074 + outer loop + vertex -444.624 30.0815 0.345116 + vertex -465.209 38.3408 0.183643 + vertex -443.808 33.8903 0.177328 + endloop + endfacet + facet normal -0.00513908 -0.0232926 -0.999715 + outer loop + vertex -465.209 38.3408 0.183643 + vertex -464.131 42.0816 0.0909461 + vertex -443.808 33.8903 0.177328 + endloop + endfacet + facet normal -0.00497489 -0.0228854 -0.999726 + outer loop + vertex -443.808 33.8903 0.177328 + vertex -464.131 42.0816 0.0909461 + vertex -442.845 37.6542 0.0863731 + endloop + endfacet + facet normal -0.00314973 -0.0141103 -0.999895 + outer loop + vertex -464.131 42.0816 0.0909461 + vertex -462.617 45.7156 0.0348934 + vertex -442.845 37.6542 0.0863731 + endloop + endfacet + facet normal -0.00308274 -0.0141382 -0.999895 + outer loop + vertex -464.131 42.0816 0.0909461 + vertex -481.104 49.0729 0.0444176 + vertex -462.617 45.7156 0.0348934 + endloop + endfacet + facet normal -0.00510902 -0.0233013 -0.999715 + outer loop + vertex -465.209 38.3408 0.183643 + vertex -482.607 45.3991 0.108045 + vertex -464.131 42.0816 0.0909461 + endloop + endfacet + facet normal -0.00947247 -0.0431394 -0.999024 + outer loop + vertex -466.04 34.5352 0.355858 + vertex -465.209 38.3408 0.183643 + vertex -444.624 30.0815 0.345116 + endloop + endfacet + facet normal -0.0172505 -0.0805466 -0.996602 + outer loop + vertex -445.687 26.227 0.675033 + vertex -466.04 34.5352 0.355858 + vertex -444.624 30.0815 0.345116 + endloop + endfacet + facet normal -0.00924726 -0.0431886 -0.999024 + outer loop + vertex -466.04 34.5352 0.355858 + vertex -483.749 41.6757 0.211087 + vertex -465.209 38.3408 0.183643 + endloop + endfacet + facet normal -0.00496623 -0.0228876 -0.999726 + outer loop + vertex -443.808 33.8903 0.177328 + vertex -442.845 37.6542 0.0863731 + vertex -421.896 29.1245 0.177585 + endloop + endfacet + facet normal -0.00301891 -0.0137895 -0.9999 + outer loop + vertex -442.845 37.6542 0.0863731 + vertex -462.617 45.7156 0.0348934 + vertex -441.479 41.3208 0.031682 + endloop + endfacet + facet normal -0.00187102 -0.0082684 -0.999964 + outer loop + vertex -462.617 45.7156 0.0348934 + vertex -460.759 49.2197 0.00244411 + vertex -441.479 41.3208 0.031682 + endloop + endfacet + facet normal -0.00175956 -0.00832747 -0.999964 + outer loop + vertex -462.617 45.7156 0.0348934 + vertex -479.124 52.5876 0.00671191 + vertex -460.759 49.2197 0.00244411 + endloop + endfacet + facet normal -0.000616037 -0.00315697 -0.999995 + outer loop + vertex -460.759 49.2197 0.00244411 + vertex -476.965 55.9457 -0.00880626 + vertex -458.519 52.4866 -0.0092497 + endloop + endfacet + facet normal 3.85191e-05 5.93511e-05 -1 + outer loop + vertex -458.519 52.4866 -0.0092497 + vertex -474.436 58.9836 -0.00947722 + vertex -455.937 55.44 -0.00897496 + endloop + endfacet + facet normal -0.000611422 -0.00288559 -0.999996 + outer loop + vertex -439.631 44.8034 0.0019623 + vertex -437.412 48.045 -0.00874824 + vertex -417.999 40.1104 0.0022782 + endloop + endfacet + facet normal -0.00162266 -0.00754679 -0.99997 + outer loop + vertex -419.772 36.6087 0.0315821 + vertex -439.631 44.8034 0.0019623 + vertex -417.999 40.1104 0.0022782 + endloop + endfacet + facet normal -0.00292821 -0.0136768 -0.999902 + outer loop + vertex -421.069 32.9252 0.0857655 + vertex -419.772 36.6087 0.0315821 + vertex -399.822 28.3959 0.0854967 + endloop + endfacet + facet normal -0.00500065 -0.0233986 -0.999714 + outer loop + vertex -400.562 24.5722 0.178688 + vertex -421.069 32.9252 0.0857655 + vertex -399.822 28.3959 0.0854967 + endloop + endfacet + facet normal -0.00849098 -0.0429181 -0.999043 + outer loop + vertex -401.073 20.6864 0.349968 + vertex -400.562 24.5722 0.178688 + vertex -380.258 16.501 0.352859 + endloop + endfacet + facet normal -0.0164117 -0.0823086 -0.996472 + outer loop + vertex -381.023 12.5907 0.688458 + vertex -401.073 20.6864 0.349968 + vertex -380.258 16.501 0.352859 + endloop + endfacet + facet normal -0.0163213 -0.0820853 -0.996492 + outer loop + vertex -401.975 16.8105 0.684014 + vertex -401.073 20.6864 0.349968 + vertex -381.023 12.5907 0.688458 + endloop + endfacet + facet normal -0.0166171 -0.0799947 -0.996657 + outer loop + vertex -423.597 21.4312 0.673648 + vertex -422.554 25.2778 0.347522 + vertex -401.975 16.8105 0.684014 + endloop + endfacet + facet normal -0.017533 -0.0804689 -0.996603 + outer loop + vertex -445.687 26.227 0.675033 + vertex -444.624 30.0815 0.345116 + vertex -423.597 21.4312 0.673648 + endloop + endfacet + facet normal -0.0186524 -0.083969 -0.996294 + outer loop + vertex -466.694 30.5675 0.70251 + vertex -466.04 34.5352 0.355858 + vertex -445.687 26.227 0.675033 + endloop + endfacet + facet normal -0.0182108 -0.084042 -0.996296 + outer loop + vertex -466.694 30.5675 0.70251 + vertex -484.259 37.7755 0.415536 + vertex -466.04 34.5352 0.355858 + endloop + endfacet + facet normal -0.0281172 -0.130248 -0.991083 + outer loop + vertex -496.639 34.1271 1.21564 + vertex -504.733 39.7548 0.705673 + vertex -497.183 39.2701 0.555169 + endloop + endfacet + facet normal -0.0254764 -0.0876381 -0.995827 + outer loop + vertex -504.733 39.7548 0.705673 + vertex -503.912 43.2489 0.377162 + vertex -497.183 39.2701 0.555169 + endloop + endfacet + facet normal -0.0337109 -0.0856952 -0.995751 + outer loop + vertex -503.912 43.2489 0.377162 + vertex -504.733 39.7548 0.705673 + vertex -508.009 44.828 0.379981 + endloop + endfacet + facet normal -0.0182605 -0.0455994 -0.998793 + outer loop + vertex -503.997 46.8866 0.212629 + vertex -503.912 43.2489 0.377162 + vertex -508.009 44.828 0.379981 + endloop + endfacet + facet normal -0.0218789 -0.0385646 -0.999017 + outer loop + vertex -508.009 44.828 0.379981 + vertex -506.652 49.9215 0.153641 + vertex -503.997 46.8866 0.212629 + endloop + endfacet + facet normal -0.00750112 -0.0259942 -0.999634 + outer loop + vertex -502.602 50.8254 0.0997427 + vertex -503.997 46.8866 0.212629 + vertex -506.652 49.9215 0.153641 + endloop + endfacet + facet normal -0.00878774 -0.020236 -0.999757 + outer loop + vertex -506.652 49.9215 0.153641 + vertex -504.913 53.9433 0.0569463 + vertex -502.602 50.8254 0.0997427 + endloop + endfacet + facet normal -0.0031426 -0.0160533 -0.999866 + outer loop + vertex -500.72 54.577 0.0335942 + vertex -502.602 50.8254 0.0997427 + vertex -504.913 53.9433 0.0569463 + endloop + endfacet + facet normal -0.00398683 -0.0104703 -0.999937 + outer loop + vertex -504.913 53.9433 0.0569463 + vertex -502.881 57.6426 0.0101082 + vertex -500.72 54.577 0.0335942 + endloop + endfacet + facet normal -0.00122001 -0.00852074 -0.999963 + outer loop + vertex -498.548 58.1407 0.000577288 + vertex -500.72 54.577 0.0335942 + vertex -502.881 57.6426 0.0101082 + endloop + endfacet + facet normal -0.00176848 -0.00375125 -0.999991 + outer loop + vertex -502.881 57.6426 0.0101082 + vertex -500.549 61.094 -0.00696282 + vertex -498.548 58.1407 0.000577288 + endloop + endfacet + facet normal -0.000196516 -0.0026863 -0.999996 + outer loop + vertex -496.17 61.5159 -0.00895678 + vertex -498.548 58.1407 0.000577288 + vertex -500.549 61.094 -0.00696282 + endloop + endfacet + facet normal -0.000474895 0.000202294 -1 + outer loop + vertex -500.549 61.094 -0.00696282 + vertex -497.702 64.3565 -0.0076547 + vertex -496.17 61.5159 -0.00895678 + endloop + endfacet + facet normal 0.00010561 0.000515346 -1 + outer loop + vertex -493.28 64.5746 -0.00707534 + vertex -496.17 61.5159 -0.00895678 + vertex -497.702 64.3565 -0.0076547 + endloop + endfacet + facet normal 8.40814e-05 0.000951801 -1 + outer loop + vertex -497.702 64.3565 -0.0076547 + vertex -493.647 67.803 -0.00403331 + vertex -493.28 64.5746 -0.00707534 + endloop + endfacet + facet normal 0.000237061 0.000969157 -1 + outer loop + vertex -490.055 66.6556 -0.00429381 + vertex -493.28 64.5746 -0.00707534 + vertex -493.647 67.803 -0.00403331 + endloop + endfacet + facet normal 0.000113523 0.000582422 -1 + outer loop + vertex -487.753 68.7948 -0.0027866 + vertex -490.055 66.6556 -0.00429381 + vertex -493.647 67.803 -0.00403331 + endloop + endfacet + facet normal 0.000142925 0.000407701 -1 + outer loop + vertex -493.647 67.803 -0.00403331 + vertex -489.079 70.734 -0.00218554 + vertex -487.753 68.7948 -0.0027866 + endloop + endfacet + facet normal 1.41573e-05 0.000319639 -1 + outer loop + vertex -483.921 70.9943 -0.00202931 + vertex -487.753 68.7948 -0.0027866 + vertex -489.079 70.734 -0.00218554 + endloop + endfacet + facet normal 1.61677e-05 0.000279802 -1 + outer loop + vertex -489.079 70.734 -0.00218554 + vertex -484.755 73.1952 -0.00142696 + vertex -483.921 70.9943 -0.00202931 + endloop + endfacet + facet normal -2.72577e-06 0.000272644 -1 + outer loop + vertex -479.807 72.9177 -0.00151611 + vertex -483.921 70.9943 -0.00202931 + vertex -484.755 73.1952 -0.00142696 + endloop + endfacet + facet normal -1.73744e-06 0.000290266 -1 + outer loop + vertex -484.755 73.1952 -0.00142696 + vertex -479.081 75.1713 -0.000863239 + vertex -479.807 72.9177 -0.00151611 + endloop + endfacet + facet normal 1.88233e-05 0.000283641 -1 + outer loop + vertex -475.951 74.1773 -0.00108627 + vertex -479.807 72.9177 -0.00151611 + vertex -479.081 75.1713 -0.000863239 + endloop + endfacet + facet normal 1.83703e-05 0.000282215 -1 + outer loop + vertex -473.162 75.6644 -0.000615351 + vertex -475.951 74.1773 -0.00108627 + vertex -479.081 75.1713 -0.000863239 + endloop + endfacet + facet normal 2.62556e-05 0.00018758 -1 + outer loop + vertex -479.081 75.1713 -0.000863239 + vertex -474.22 77.3524 -0.000326486 + vertex -473.162 75.6644 -0.000615351 + endloop + endfacet + facet normal 8.83344e-06 0.000226404 -1 + outer loop + vertex -474.22 77.3524 -0.000326486 + vertex -479.081 75.1713 -0.000863239 + vertex -479.47 77.0869 -0.000432971 + endloop + endfacet + facet normal 1.25814e-05 0.000152285 -1 + outer loop + vertex -479.47 77.0869 -0.000432971 + vertex -476.382 78.4092 -0.000192754 + vertex -474.22 77.3524 -0.000326486 + endloop + endfacet + facet normal -6.59026e-06 0.000113065 -1 + outer loop + vertex -476.382 78.4092 -0.000192754 + vertex -473.272 79.384 -0.000103036 + vertex -474.22 77.3524 -0.000326486 + endloop + endfacet + facet normal 8.15295e-06 0.000106182 -1 + outer loop + vertex -469.625 79.0713 -0.00010651 + vertex -474.22 77.3524 -0.000326486 + vertex -473.272 79.384 -0.000103036 + endloop + endfacet + facet normal 2.90823e-06 4.5023e-05 -1 + outer loop + vertex -473.272 79.384 -0.000103036 + vertex -470.547 80.6958 -3.60481e-05 + vertex -469.625 79.0713 -0.00010651 + endloop + endfacet + facet normal 5.11172e-06 4.62734e-05 -1 + outer loop + vertex -463.204 80.6637 -8.51503e-14 + vertex -469.625 79.0713 -0.00010651 + vertex -470.547 80.6958 -3.60481e-05 + endloop + endfacet + facet normal 4.99577e-06 1.97708e-05 -1 + outer loop + vertex -471.785 82.832 -8.49364e-14 + vertex -463.204 80.6637 -8.51503e-14 + vertex -470.547 80.6958 -3.60481e-05 + endloop + endfacet + facet normal 3.24808e-06 1.87577e-05 -1 + outer loop + vertex -470.547 80.6958 -3.60481e-05 + vertex -475.738 81.887 -3.05653e-05 + vertex -471.785 82.832 -8.49364e-14 + endloop + endfacet + facet normal 4.00912e-06 1.55745e-05 -1 + outer loop + vertex -482.011 85.4642 -8.46767e-14 + vertex -471.785 82.832 -8.49364e-14 + vertex -475.738 81.887 -3.05653e-05 + endloop + endfacet + facet normal 2.91978e-06 1.36643e-05 -1 + outer loop + vertex -475.738 81.887 -3.05653e-05 + vertex -483.855 83.9352 -2.62794e-05 + vertex -482.011 85.4642 -8.46767e-14 + endloop + endfacet + facet normal 3.43013e-06 1.30485e-05 -1 + outer loop + vertex -483.855 83.9352 -2.62794e-05 + vertex -492.652 88.2617 -8.44007e-14 + vertex -482.011 85.4642 -8.46767e-14 + endloop + endfacet + facet normal 3.33388e-06 1.28528e-05 -1 + outer loop + vertex -494.34 86.6836 -2.59106e-05 + vertex -492.652 88.2617 -8.44007e-14 + vertex -483.855 83.9352 -2.62794e-05 + endloop + endfacet + facet normal 6.91786e-06 2.65255e-05 -1 + outer loop + vertex -486.923 82.6644 -8.12096e-05 + vertex -494.34 86.6836 -2.59106e-05 + vertex -483.855 83.9352 -2.62794e-05 + endloop + endfacet + facet normal 6.55829e-06 2.73934e-05 -1 + outer loop + vertex -486.923 82.6644 -8.12096e-05 + vertex -483.855 83.9352 -2.62794e-05 + vertex -478.407 80.5674 -8.28019e-05 + endloop + endfacet + facet normal 1.45617e-05 5.98962e-05 -1 + outer loop + vertex -481.932 79.4125 -0.000203308 + vertex -486.923 82.6644 -8.12096e-05 + vertex -478.407 80.5674 -8.28019e-05 + endloop + endfacet + facet normal 1.33811e-05 6.35e-05 -1 + outer loop + vertex -481.932 79.4125 -0.000203308 + vertex -478.407 80.5674 -8.28019e-05 + vertex -476.382 78.4092 -0.000192754 + endloop + endfacet + facet normal 1.47484e-05 6.01827e-05 -1 + outer loop + vertex -490.853 81.5609 -0.000205576 + vertex -486.923 82.6644 -8.12096e-05 + vertex -481.932 79.4125 -0.000203308 + endloop + endfacet + facet normal 2.62199e-05 0.000107815 -1 + outer loop + vertex -485.82 78.1928 -0.000436746 + vertex -490.853 81.5609 -0.000205576 + vertex -481.932 79.4125 -0.000203308 + endloop + endfacet + facet normal 2.1817e-05 0.000121848 -1 + outer loop + vertex -485.82 78.1928 -0.000436746 + vertex -481.932 79.4125 -0.000203308 + vertex -479.47 77.0869 -0.000432971 + endloop + endfacet + facet normal 3.032e-05 0.000170668 -1 + outer loop + vertex -483.693 75.5904 -0.000816404 + vertex -485.82 78.1928 -0.000436746 + vertex -479.47 77.0869 -0.000432971 + endloop + endfacet + facet normal 2.89429e-05 0.000169543 -1 + outer loop + vertex -489.492 76.8938 -0.000763264 + vertex -485.82 78.1928 -0.000436746 + vertex -483.693 75.5904 -0.000816404 + endloop + endfacet + facet normal 3.19665e-05 0.000182995 -1 + outer loop + vertex -487.299 74.5053 -0.00113023 + vertex -489.492 76.8938 -0.000763264 + vertex -483.693 75.5904 -0.000816404 + endloop + endfacet + facet normal 1.1917e-05 0.000249628 -1 + outer loop + vertex -487.299 74.5053 -0.00113023 + vertex -483.693 75.5904 -0.000816404 + vertex -484.755 73.1952 -0.00142696 + endloop + endfacet + facet normal 8.01589e-06 0.000242053 -1 + outer loop + vertex -489.815 72.831 -0.00155569 + vertex -487.299 74.5053 -0.00113023 + vertex -484.755 73.1952 -0.00142696 + endloop + endfacet + facet normal 3.65828e-05 0.000199119 -1 + outer loop + vertex -489.815 72.831 -0.00155569 + vertex -492.717 75.4654 -0.00113729 + vertex -487.299 74.5053 -0.00113023 + endloop + endfacet + facet normal 2.44034e-05 0.000185702 -1 + outer loop + vertex -495.912 73.822 -0.00152045 + vertex -492.717 75.4654 -0.00113729 + vertex -489.815 72.831 -0.00155569 + endloop + endfacet + facet normal 3.54082e-05 0.00025341 -1 + outer loop + vertex -493.361 70.8396 -0.00218588 + vertex -495.912 73.822 -0.00152045 + vertex -489.815 72.831 -0.00155569 + endloop + endfacet + facet normal 7.55508e-06 0.000303007 -1 + outer loop + vertex -493.361 70.8396 -0.00218588 + vertex -489.815 72.831 -0.00155569 + vertex -489.079 70.734 -0.00218554 + endloop + endfacet + facet normal 2.44726e-05 0.000244055 -1 + outer loop + vertex -499.215 72.0847 -0.00202528 + vertex -495.912 73.822 -0.00152045 + vertex -493.361 70.8396 -0.00218588 + endloop + endfacet + facet normal 5.96567e-05 0.000409485 -1 + outer loop + vertex -496.658 69.2851 -0.00301913 + vertex -499.215 72.0847 -0.00202528 + vertex -493.361 70.8396 -0.00218588 + endloop + endfacet + facet normal -3.57054e-05 0.000611748 -1 + outer loop + vertex -496.658 69.2851 -0.00301913 + vertex -493.361 70.8396 -0.00218588 + vertex -493.647 67.803 -0.00403331 + endloop + endfacet + facet normal 0.000115875 0.00091975 -1 + outer loop + vertex -498.898 66.99 -0.00538957 + vertex -496.658 69.2851 -0.00301913 + vertex -493.647 67.803 -0.00403331 + endloop + endfacet + facet normal 0.000188797 0.000848571 -1 + outer loop + vertex -498.898 66.99 -0.00538957 + vertex -502.243 70.1244 -0.00336127 + vertex -496.658 69.2851 -0.00301913 + endloop + endfacet + facet normal 0.000264063 0.000928884 -1 + outer loop + vertex -505.168 67.7493 -0.00633985 + vertex -502.243 70.1244 -0.00336127 + vertex -498.898 66.99 -0.00538957 + endloop + endfacet + facet normal 0.000239806 0.000728585 -1 + outer loop + vertex -501.873 64.1088 -0.00820209 + vertex -505.168 67.7493 -0.00633985 + vertex -498.898 66.99 -0.00538957 + endloop + endfacet + facet normal 7.80614e-05 0.00089556 -1 + outer loop + vertex -501.873 64.1088 -0.00820209 + vertex -498.898 66.99 -0.00538957 + vertex -497.702 64.3565 -0.0076547 + endloop + endfacet + facet normal 0.000187526 0.000681266 -1 + outer loop + vertex -507.983 64.9699 -0.00876114 + vertex -505.168 67.7493 -0.00633985 + vertex -501.873 64.1088 -0.00820209 + endloop + endfacet + facet normal -7.32522e-05 -0.00116887 -0.999999 + outer loop + vertex -504.446 60.9171 -0.00428303 + vertex -507.983 64.9699 -0.00876114 + vertex -501.873 64.1088 -0.00820209 + endloop + endfacet + facet normal -0.000655968 -0.00069916 -1 + outer loop + vertex -504.446 60.9171 -0.00428303 + vertex -501.873 64.1088 -0.00820209 + vertex -500.549 61.094 -0.00696282 + endloop + endfacet + facet normal -0.000551318 -0.0015861 -0.999999 + outer loop + vertex -510.461 61.8307 -0.00241539 + vertex -507.983 64.9699 -0.00876114 + vertex -504.446 60.9171 -0.00428303 + endloop + endfacet + facet normal -0.00123434 -0.00608395 -0.999981 + outer loop + vertex -506.648 57.4365 0.019612 + vertex -510.461 61.8307 -0.00241539 + vertex -504.446 60.9171 -0.00428303 + endloop + endfacet + facet normal -0.00222411 -0.00545766 -0.999983 + outer loop + vertex -506.648 57.4365 0.019612 + vertex -504.446 60.9171 -0.00428303 + vertex -502.881 57.6426 0.0101082 + endloop + endfacet + facet normal -0.00226562 -0.00697886 -0.999973 + outer loop + vertex -512.628 58.3792 0.0265814 + vertex -510.461 61.8307 -0.00241539 + vertex -506.648 57.4365 0.019612 + endloop + endfacet + facet normal -0.00337982 -0.0140473 -0.999896 + outer loop + vertex -508.578 53.7058 0.0785475 + vertex -512.628 58.3792 0.0265814 + vertex -506.648 57.4365 0.019612 + endloop + endfacet + facet normal -0.00503871 -0.0131892 -0.9999 + outer loop + vertex -508.578 53.7058 0.0785475 + vertex -506.648 57.4365 0.019612 + vertex -504.913 53.9433 0.0569463 + endloop + endfacet + facet normal -0.00420791 -0.0147647 -0.999882 + outer loop + vertex -514.391 54.6798 0.0886296 + vertex -512.628 58.3792 0.0265814 + vertex -508.578 53.7058 0.0785475 + endloop + endfacet + facet normal -0.00587148 -0.0246956 -0.999678 + outer loop + vertex -510.179 49.8079 0.184243 + vertex -514.391 54.6798 0.0886296 + vertex -508.578 53.7058 0.0785475 + endloop + endfacet + facet normal -0.00790614 -0.0238599 -0.999684 + outer loop + vertex -510.179 49.8079 0.184243 + vertex -508.578 53.7058 0.0785475 + vertex -506.652 49.9215 0.153641 + endloop + endfacet + facet normal -0.00587886 -0.024702 -0.999678 + outer loop + vertex -515.856 51.0221 0.187625 + vertex -514.391 54.6798 0.0886296 + vertex -510.179 49.8079 0.184243 + endloop + endfacet + facet normal -0.00832863 -0.0361567 -0.999311 + outer loop + vertex -511.677 46.7995 0.305573 + vertex -515.856 51.0221 0.187625 + vertex -510.179 49.8079 0.184243 + endloop + endfacet + facet normal -0.001097 -0.0397518 -0.999209 + outer loop + vertex -511.677 46.7995 0.305573 + vertex -510.179 49.8079 0.184243 + vertex -508.009 44.828 0.379981 + endloop + endfacet + facet normal -0.0147404 -0.0650755 -0.997771 + outer loop + vertex -511.851 43.0955 0.549726 + vertex -511.677 46.7995 0.305573 + vertex -508.009 44.828 0.379981 + endloop + endfacet + facet normal -0.00543017 -0.0855758 -0.996317 + outer loop + vertex -508.009 44.828 0.379981 + vertex -508.783 39.4702 0.84439 + vertex -511.851 43.0955 0.549726 + endloop + endfacet + facet normal -0.0363882 -0.111511 -0.993097 + outer loop + vertex -512.393 38.7322 1.05952 + vertex -511.851 43.0955 0.549726 + vertex -508.783 39.4702 0.84439 + endloop + endfacet + facet normal -0.0295512 -0.14381 -0.989164 + outer loop + vertex -508.783 39.4702 0.84439 + vertex -509.269 35.1963 1.48026 + vertex -512.393 38.7322 1.05952 + endloop + endfacet + facet normal -0.0248784 -0.112963 -0.993288 + outer loop + vertex -512.393 38.7322 1.05952 + vertex -517.818 43.4724 0.656316 + vertex -511.851 43.0955 0.549726 + endloop + endfacet + facet normal -0.0224336 -0.0731927 -0.997065 + outer loop + vertex -517.818 43.4724 0.656316 + vertex -516.95 47.3787 0.350031 + vertex -511.851 43.0955 0.549726 + endloop + endfacet + facet normal -0.0189687 -0.0739638 -0.997081 + outer loop + vertex -517.818 43.4724 0.656316 + vertex -525.941 49.3375 0.37578 + vertex -516.95 47.3787 0.350031 + endloop + endfacet + facet normal -0.012336 -0.0434932 -0.998978 + outer loop + vertex -525.941 49.3375 0.37578 + vertex -524.792 53.1648 0.194953 + vertex -516.95 47.3787 0.350031 + endloop + endfacet + facet normal -0.0107261 -0.0413144 -0.999089 + outer loop + vertex -516.95 47.3787 0.350031 + vertex -524.792 53.1648 0.194953 + vertex -515.856 51.0221 0.187625 + endloop + endfacet + facet normal -0.00685773 -0.0251801 -0.999659 + outer loop + vertex -524.792 53.1648 0.194953 + vertex -523.407 56.9192 0.0908859 + vertex -515.856 51.0221 0.187625 + endloop + endfacet + facet normal -0.00650566 -0.0253099 -0.999658 + outer loop + vertex -524.792 53.1648 0.194953 + vertex -534.722 59.9483 0.0878296 + vertex -523.407 56.9192 0.0908859 + endloop + endfacet + facet normal -0.0037053 -0.0148497 -0.999883 + outer loop + vertex -534.722 59.9483 0.0878296 + vertex -532.952 63.5932 0.0271396 + vertex -523.407 56.9192 0.0908859 + endloop + endfacet + facet normal -0.00396701 -0.0152239 -0.999876 + outer loop + vertex -523.407 56.9192 0.0908859 + vertex -532.952 63.5932 0.0271396 + vertex -521.641 60.5618 0.0284169 + endloop + endfacet + facet normal -0.00402466 -0.015196 -0.999876 + outer loop + vertex -523.407 56.9192 0.0908859 + vertex -521.641 60.5618 0.0284169 + vertex -514.391 54.6798 0.0886296 + endloop + endfacet + facet normal -0.00188196 -0.00744372 -0.999971 + outer loop + vertex -532.952 63.5932 0.0271396 + vertex -530.799 66.9952 -0.00223643 + vertex -521.641 60.5618 0.0284169 + endloop + endfacet + facet normal -0.00194785 -0.00753752 -0.99997 + outer loop + vertex -521.641 60.5618 0.0284169 + vertex -530.799 66.9952 -0.00223643 + vertex -519.543 63.997 -0.0015637 + endloop + endfacet + facet normal -0.00201849 -0.00749438 -0.99997 + outer loop + vertex -521.641 60.5618 0.0284169 + vertex -519.543 63.997 -0.0015637 + vertex -512.628 58.3792 0.0265814 + endloop + endfacet + facet normal -0.000511794 -0.00214589 -0.999998 + outer loop + vertex -530.799 66.9952 -0.00223643 + vertex -528.277 70.0631 -0.0101109 + vertex -519.543 63.997 -0.0015637 + endloop + endfacet + facet normal -0.00051233 -0.00214666 -0.999998 + outer loop + vertex -519.543 63.997 -0.0015637 + vertex -528.277 70.0631 -0.0101109 + vertex -517.045 67.0903 -0.00948373 + endloop + endfacet + facet normal -0.000590747 -0.00208333 -0.999998 + outer loop + vertex -519.543 63.997 -0.0015637 + vertex -517.045 67.0903 -0.00948373 + vertex -510.461 61.8307 -0.00241539 + endloop + endfacet + facet normal 0.000214614 0.000599895 -1 + outer loop + vertex -528.277 70.0631 -0.0101109 + vertex -525.42 72.761 -0.0078794 + vertex -517.045 67.0903 -0.00948373 + endloop + endfacet + facet normal 0.000221445 0.000609984 -1 + outer loop + vertex -517.045 67.0903 -0.00948373 + vertex -525.42 72.761 -0.0078794 + vertex -514.232 69.8193 -0.00719625 + endloop + endfacet + facet normal 0.000222262 0.000609143 -1 + outer loop + vertex -517.045 67.0903 -0.00948373 + vertex -514.232 69.8193 -0.00719625 + vertex -507.983 64.9699 -0.00876114 + endloop + endfacet + facet normal 0.000358355 0.00113068 -0.999999 + outer loop + vertex -525.42 72.761 -0.0078794 + vertex -522.307 75.0976 -0.0041219 + vertex -514.232 69.8193 -0.00719625 + endloop + endfacet + facet normal 0.000306919 0.00105199 -0.999999 + outer loop + vertex -514.232 69.8193 -0.00719625 + vertex -522.307 75.0976 -0.0041219 + vertex -511.205 72.1885 -0.00377482 + endloop + endfacet + facet normal 0.000328444 0.00102449 -0.999999 + outer loop + vertex -514.232 69.8193 -0.00719625 + vertex -511.205 72.1885 -0.00377482 + vertex -505.168 67.7493 -0.00633985 + endloop + endfacet + facet normal 0.00020466 0.000661743 -1 + outer loop + vertex -522.307 75.0976 -0.0041219 + vertex -519.055 77.122 -0.00211672 + vertex -511.205 72.1885 -0.00377482 + endloop + endfacet + facet normal 0.000164006 0.000597055 -1 + outer loop + vertex -511.205 72.1885 -0.00377482 + vertex -519.055 77.122 -0.00211672 + vertex -508.028 74.2155 -0.00204347 + endloop + endfacet + facet normal 0.000178441 0.00057443 -1 + outer loop + vertex -511.205 72.1885 -0.00377482 + vertex -508.028 74.2155 -0.00204347 + vertex -502.243 70.1244 -0.00336127 + endloop + endfacet + facet normal 0.000121487 0.000493897 -1 + outer loop + vertex -502.243 70.1244 -0.00336127 + vertex -508.028 74.2155 -0.00204347 + vertex -499.215 72.0847 -0.00202528 + endloop + endfacet + facet normal 5.54427e-05 0.000220755 -1 + outer loop + vertex -508.028 74.2155 -0.00204347 + vertex -504.776 75.988 -0.0014719 + vertex -499.215 72.0847 -0.00202528 + endloop + endfacet + facet normal 5.66941e-05 0.000218459 -1 + outer loop + vertex -508.028 74.2155 -0.00204347 + vertex -515.707 78.8864 -0.00145844 + vertex -504.776 75.988 -0.0014719 + endloop + endfacet + facet normal 3.17559e-05 0.000124407 -1 + outer loop + vertex -515.707 78.8864 -0.00145844 + vertex -512.301 80.4578 -0.00115479 + vertex -504.776 75.988 -0.0014719 + endloop + endfacet + facet normal 3.65136e-05 0.000132417 -1 + outer loop + vertex -504.776 75.988 -0.0014719 + vertex -512.301 80.4578 -0.00115479 + vertex -501.474 77.5883 -0.0011394 + endloop + endfacet + facet normal 3.01097e-05 0.000145631 -1 + outer loop + vertex -504.776 75.988 -0.0014719 + vertex -501.474 77.5883 -0.0011394 + vertex -495.912 73.822 -0.00152045 + endloop + endfacet + facet normal 4.02275e-05 0.000146431 -1 + outer loop + vertex -512.301 80.4578 -0.00115479 + vertex -508.906 81.903 -0.000806566 + vertex -501.474 77.5883 -0.0011394 + endloop + endfacet + facet normal 4.34893e-05 0.000152049 -1 + outer loop + vertex -501.474 77.5883 -0.0011394 + vertex -508.906 81.903 -0.000806566 + vertex -498.169 79.0541 -0.000772844 + endloop + endfacet + facet normal 3.93609e-05 0.000161355 -1 + outer loop + vertex -501.474 77.5883 -0.0011394 + vertex -498.169 79.0541 -0.000772844 + vertex -492.717 75.4654 -0.00113729 + endloop + endfacet + facet normal 4.24367e-05 0.000166028 -1 + outer loop + vertex -492.717 75.4654 -0.00113729 + vertex -498.169 79.0541 -0.000772844 + vertex -489.492 76.8938 -0.000763264 + endloop + endfacet + facet normal 3.86597e-05 0.000150857 -1 + outer loop + vertex -498.169 79.0541 -0.000772844 + vertex -494.71 80.385 -0.000438314 + vertex -489.492 76.8938 -0.000763264 + endloop + endfacet + facet normal 4.069e-05 0.000145579 -1 + outer loop + vertex -498.169 79.0541 -0.000772844 + vertex -505.486 83.2449 -0.000460444 + vertex -494.71 80.385 -0.000438314 + endloop + endfacet + facet normal 3.10454e-05 0.000109239 -1 + outer loop + vertex -505.486 83.2449 -0.000460444 + vertex -501.861 84.4626 -0.0002149 + vertex -494.71 80.385 -0.000438314 + endloop + endfacet + facet normal 2.84332e-05 0.000104658 -1 + outer loop + vertex -494.71 80.385 -0.000438314 + vertex -501.861 84.4626 -0.0002149 + vertex -490.853 81.5609 -0.000205576 + endloop + endfacet + facet normal 1.67651e-05 6.03905e-05 -1 + outer loop + vertex -501.861 84.4626 -0.0002149 + vertex -497.916 85.5452 -8.33771e-05 + vertex -490.853 81.5609 -0.000205576 + endloop + endfacet + facet normal 1.68029e-05 6.02527e-05 -1 + outer loop + vertex -501.861 84.4626 -0.0002149 + vertex -509.83 88.7777 -8.8799e-05 + vertex -497.916 85.5452 -8.33771e-05 + endloop + endfacet + facet normal 8.29438e-06 2.88931e-05 -1 + outer loop + vertex -509.83 88.7777 -8.8799e-05 + vertex -505.98 89.8235 -2.66509e-05 + vertex -497.916 85.5452 -8.33771e-05 + endloop + endfacet + facet normal 7.40627e-06 2.72191e-05 -1 + outer loop + vertex -497.916 85.5452 -8.33771e-05 + vertex -505.98 89.8235 -2.66509e-05 + vertex -494.34 86.6836 -2.59106e-05 + endloop + endfacet + facet normal 3.59667e-06 1.3097e-05 -1 + outer loop + vertex -505.98 89.8235 -2.66509e-05 + vertex -503.331 91.131 -8.41176e-14 + vertex -494.34 86.6836 -2.59106e-05 + endloop + endfacet + facet normal 3.59766e-06 1.3095e-05 -1 + outer loop + vertex -505.98 89.8235 -2.66509e-05 + vertex -513.933 94.0437 -8.38302e-14 + vertex -503.331 91.131 -8.41176e-14 + endloop + endfacet + facet normal 4.09218e-06 1.4027e-05 -1 + outer loop + vertex -517.69 93.0587 -2.91892e-05 + vertex -513.933 94.0437 -8.38302e-14 + vertex -505.98 89.8235 -2.66509e-05 + endloop + endfacet + facet normal 4.0194e-06 1.43045e-05 -1 + outer loop + vertex -517.69 93.0587 -2.91892e-05 + vertex -524.469 97.0041 -8.35381e-14 + vertex -513.933 94.0437 -8.38302e-14 + endloop + endfacet + facet normal 4.67023e-06 1.54228e-05 -1 + outer loop + vertex -528.718 96.1771 -3.25992e-05 + vertex -524.469 97.0041 -8.35381e-14 + vertex -517.69 93.0587 -2.91892e-05 + endloop + endfacet + facet normal 9.32459e-06 3.1883e-05 -1 + outer loop + vertex -521.535 92.0314 -9.77935e-05 + vertex -528.718 96.1771 -3.25992e-05 + vertex -517.69 93.0587 -2.91892e-05 + endloop + endfacet + facet normal 9.47493e-06 3.13203e-05 -1 + outer loop + vertex -521.535 92.0314 -9.77935e-05 + vertex -517.69 93.0587 -2.91892e-05 + vertex -509.83 88.7777 -8.8799e-05 + endloop + endfacet + facet normal 1.89862e-05 6.55355e-05 -1 + outer loop + vertex -513.539 87.6481 -0.000233251 + vertex -521.535 92.0314 -9.77935e-05 + vertex -509.83 88.7777 -8.8799e-05 + endloop + endfacet + facet normal 2.24544e-05 7.18619e-05 -1 + outer loop + vertex -525.042 90.8581 -0.000260867 + vertex -521.535 92.0314 -9.77935e-05 + vertex -513.539 87.6481 -0.000233251 + endloop + endfacet + facet normal 3.48382e-05 0.000116239 -1 + outer loop + vertex -517.012 86.3979 -0.000499567 + vertex -525.042 90.8581 -0.000260867 + vertex -513.539 87.6481 -0.000233251 + endloop + endfacet + facet normal 3.50388e-05 0.000115682 -1 + outer loop + vertex -517.012 86.3979 -0.000499567 + vertex -513.539 87.6481 -0.000233251 + vertex -505.486 83.2449 -0.000460444 + endloop + endfacet + facet normal 4.35747e-05 0.000146886 -1 + outer loop + vertex -508.906 81.903 -0.000806566 + vertex -517.012 86.3979 -0.000499567 + vertex -505.486 83.2449 -0.000460444 + endloop + endfacet + facet normal 4.6227e-05 0.00015167 -1 + outer loop + vertex -520.476 85.0725 -0.000860716 + vertex -517.012 86.3979 -0.000499567 + vertex -508.906 81.903 -0.000806566 + endloop + endfacet + facet normal 4.67533e-05 0.000150294 -1 + outer loop + vertex -520.476 85.0725 -0.000860716 + vertex -528.539 89.6192 -0.000554336 + vertex -517.012 86.3979 -0.000499567 + endloop + endfacet + facet normal 5.16545e-05 0.000158985 -1 + outer loop + vertex -532.114 88.3286 -0.00094422 + vertex -528.539 89.6192 -0.000554336 + vertex -520.476 85.0725 -0.000860716 + endloop + endfacet + facet normal 4.40674e-05 0.000131866 -1 + outer loop + vertex -523.984 83.6651 -0.00120091 + vertex -532.114 88.3286 -0.00094422 + vertex -520.476 85.0725 -0.000860716 + endloop + endfacet + facet normal 4.17405e-05 0.000137667 -1 + outer loop + vertex -523.984 83.6651 -0.00120091 + vertex -520.476 85.0725 -0.000860716 + vertex -512.301 80.4578 -0.00115479 + endloop + endfacet + facet normal 4.67953e-05 0.000136622 -1 + outer loop + vertex -535.702 86.9505 -0.00130038 + vertex -532.114 88.3286 -0.00094422 + vertex -523.984 83.6651 -0.00120091 + endloop + endfacet + facet normal 3.77447e-05 0.000104343 -1 + outer loop + vertex -527.476 82.1229 -0.00149364 + vertex -535.702 86.9505 -0.00130038 + vertex -523.984 83.6651 -0.00120091 + endloop + endfacet + facet normal 3.40099e-05 0.0001128 -1 + outer loop + vertex -527.476 82.1229 -0.00149364 + vertex -523.984 83.6651 -0.00120091 + vertex -515.707 78.8864 -0.00145844 + endloop + endfacet + facet normal 6.93809e-05 0.000241424 -1 + outer loop + vertex -519.055 77.122 -0.00211672 + vertex -527.476 82.1229 -0.00149364 + vertex -515.707 78.8864 -0.00145844 + endloop + endfacet + facet normal 7.62534e-05 0.000252997 -1 + outer loop + vertex -530.915 80.3856 -0.00219537 + vertex -527.476 82.1229 -0.00149364 + vertex -519.055 77.122 -0.00211672 + endloop + endfacet + facet normal 7.84481e-05 0.000248653 -1 + outer loop + vertex -530.915 80.3856 -0.00219537 + vertex -539.279 85.4438 -0.00159378 + vertex -527.476 82.1229 -0.00149364 + endloop + endfacet + facet normal 8.36671e-05 0.000257283 -1 + outer loop + vertex -542.797 83.7284 -0.00232946 + vertex -539.279 85.4438 -0.00159378 + vertex -530.915 80.3856 -0.00219537 + endloop + endfacet + facet normal 0.000214078 0.000720833 -1 + outer loop + vertex -534.258 78.386 -0.00435249 + vertex -542.797 83.7284 -0.00232946 + vertex -530.915 80.3856 -0.00219537 + endloop + endfacet + facet normal 0.000216516 0.000716757 -1 + outer loop + vertex -534.258 78.386 -0.00435249 + vertex -530.915 80.3856 -0.00219537 + vertex -522.307 75.0976 -0.0041219 + endloop + endfacet + facet normal 0.000209713 0.000713856 -1 + outer loop + vertex -546.214 81.7452 -0.00446186 + vertex -542.797 83.7284 -0.00232946 + vertex -534.258 78.386 -0.00435249 + endloop + endfacet + facet normal 0.000344875 0.00119493 -0.999999 + outer loop + vertex -537.435 76.0669 -0.00821937 + vertex -546.214 81.7452 -0.00446186 + vertex -534.258 78.386 -0.00435249 + endloop + endfacet + facet normal 0.000353733 0.00118279 -0.999999 + outer loop + vertex -537.435 76.0669 -0.00821937 + vertex -534.258 78.386 -0.00435249 + vertex -525.42 72.761 -0.0078794 + endloop + endfacet + facet normal 0.000314747 0.00114835 -0.999999 + outer loop + vertex -549.453 79.4374 -0.00813134 + vertex -546.214 81.7452 -0.00446186 + vertex -537.435 76.0669 -0.00821937 + endloop + endfacet + facet normal 0.000172881 0.000642524 -1 + outer loop + vertex -540.357 73.3896 -0.0104447 + vertex -549.453 79.4374 -0.00813134 + vertex -537.435 76.0669 -0.00821937 + endloop + endfacet + facet normal 0.000197241 0.000615942 -1 + outer loop + vertex -540.357 73.3896 -0.0104447 + vertex -537.435 76.0669 -0.00821937 + vertex -528.277 70.0631 -0.0101109 + endloop + endfacet + facet normal 0.000130074 0.000578141 -1 + outer loop + vertex -552.474 76.7886 -0.0100557 + vertex -549.453 79.4374 -0.00813134 + vertex -540.357 73.3896 -0.0104447 + endloop + endfacet + facet normal -0.000597957 -0.00201732 -0.999998 + outer loop + vertex -542.971 70.3521 -0.00275374 + vertex -552.474 76.7886 -0.0100557 + vertex -540.357 73.3896 -0.0104447 + endloop + endfacet + facet normal -0.000529994 -0.00207582 -0.999998 + outer loop + vertex -542.971 70.3521 -0.00275374 + vertex -540.357 73.3896 -0.0104447 + vertex -530.799 66.9952 -0.00223643 + endloop + endfacet + facet normal -0.000649433 -0.00209332 -0.999998 + outer loop + vertex -555.19 73.7762 -0.00198594 + vertex -552.474 76.7886 -0.0100557 + vertex -542.971 70.3521 -0.00275374 + endloop + endfacet + facet normal -0.0020303 -0.00702108 -0.999973 + outer loop + vertex -545.197 66.9779 0.025456 + vertex -555.19 73.7762 -0.00198594 + vertex -542.971 70.3521 -0.00275374 + endloop + endfacet + facet normal -0.00183832 -0.0071477 -0.999973 + outer loop + vertex -545.197 66.9779 0.025456 + vertex -542.971 70.3521 -0.00275374 + vertex -532.952 63.5932 0.0271396 + endloop + endfacet + facet normal -0.00180069 -0.00668355 -0.999976 + outer loop + vertex -557.511 70.435 0.0245236 + vertex -555.19 73.7762 -0.00198594 + vertex -545.197 66.9779 0.025456 + endloop + endfacet + facet normal -0.00373209 -0.013563 -0.999901 + outer loop + vertex -546.998 63.347 0.0814305 + vertex -557.511 70.435 0.0245236 + vertex -545.197 66.9779 0.025456 + endloop + endfacet + facet normal -0.00329392 -0.0137803 -0.9999 + outer loop + vertex -546.998 63.347 0.0814305 + vertex -545.197 66.9779 0.025456 + vertex -534.722 59.9483 0.0878296 + endloop + endfacet + facet normal -0.0063663 -0.0248774 -0.99967 + outer loop + vertex -536.114 56.149 0.191241 + vertex -546.998 63.347 0.0814305 + vertex -534.722 59.9483 0.0878296 + endloop + endfacet + facet normal -0.00590202 -0.0241757 -0.99969 + outer loop + vertex -548.371 59.5446 0.181487 + vertex -546.998 63.347 0.0814305 + vertex -536.114 56.149 0.191241 + endloop + endfacet + facet normal -0.0113518 -0.0438455 -0.998974 + outer loop + vertex -537.273 52.269 0.374705 + vertex -548.371 59.5446 0.181487 + vertex -536.114 56.149 0.191241 + endloop + endfacet + facet normal -0.0112557 -0.0438742 -0.998974 + outer loop + vertex -537.273 52.269 0.374705 + vertex -536.114 56.149 0.191241 + vertex -525.941 49.3375 0.37578 + endloop + endfacet + facet normal -0.0206298 -0.080108 -0.996573 + outer loop + vertex -527.137 45.4304 0.714604 + vertex -537.273 52.269 0.374705 + vertex -525.941 49.3375 0.37578 + endloop + endfacet + facet normal -0.0211243 -0.0808374 -0.996503 + outer loop + vertex -538.534 48.3668 0.718001 + vertex -537.273 52.269 0.374705 + vertex -527.137 45.4304 0.714604 + endloop + endfacet + facet normal -0.0355438 -0.136812 -0.989959 + outer loop + vertex -528.609 41.4241 1.32113 + vertex -538.534 48.3668 0.718001 + vertex -527.137 45.4304 0.714604 + endloop + endfacet + facet normal -0.0371879 -0.136211 -0.989982 + outer loop + vertex -528.609 41.4241 1.32113 + vertex -527.137 45.4304 0.714604 + vertex -518.781 39.2568 1.25013 + endloop + endfacet + facet normal -0.0338898 -0.131809 -0.990696 + outer loop + vertex -518.781 39.2568 1.25013 + vertex -527.137 45.4304 0.714604 + vertex -517.818 43.4724 0.656316 + endloop + endfacet + facet normal -0.0358946 -0.137306 -0.989878 + outer loop + vertex -540.184 44.4479 1.32141 + vertex -538.534 48.3668 0.718001 + vertex -528.609 41.4241 1.32113 + endloop + endfacet + facet normal -0.036947 -0.136867 -0.9899 + outer loop + vertex -540.184 44.4479 1.32141 + vertex -550.671 51.7316 0.705744 + vertex -538.534 48.3668 0.718001 + endloop + endfacet + facet normal -0.0213376 -0.0805908 -0.996519 + outer loop + vertex -550.671 51.7316 0.705744 + vertex -549.488 55.6567 0.362987 + vertex -538.534 48.3668 0.718001 + endloop + endfacet + facet normal -0.0220951 -0.0803628 -0.996521 + outer loop + vertex -550.671 51.7316 0.705744 + vertex -561.762 59.1749 0.351405 + vertex -549.488 55.6567 0.362987 + endloop + endfacet + facet normal -0.0112989 -0.0427067 -0.999024 + outer loop + vertex -561.762 59.1749 0.351405 + vertex -560.676 63.0542 0.173299 + vertex -549.488 55.6567 0.362987 + endloop + endfacet + facet normal -0.0116788 -0.0432806 -0.998995 + outer loop + vertex -549.488 55.6567 0.362987 + vertex -560.676 63.0542 0.173299 + vertex -548.371 59.5446 0.181487 + endloop + endfacet + facet normal -0.00592872 -0.0231205 -0.999715 + outer loop + vertex -560.676 63.0542 0.173299 + vertex -559.325 66.8282 0.078 + vertex -548.371 59.5446 0.181487 + endloop + endfacet + facet normal -0.00644665 -0.022935 -0.999716 + outer loop + vertex -560.676 63.0542 0.173299 + vertex -571.185 70.1843 0.0774869 + vertex -559.325 66.8282 0.078 + endloop + endfacet + facet normal -0.00355933 -0.0127314 -0.999913 + outer loop + vertex -571.185 70.1843 0.0774869 + vertex -569.441 73.7619 0.0257265 + vertex -559.325 66.8282 0.078 + endloop + endfacet + facet normal -0.00371413 -0.0129572 -0.999909 + outer loop + vertex -559.325 66.8282 0.078 + vertex -569.441 73.7619 0.0257265 + vertex -557.511 70.435 0.0245236 + endloop + endfacet + facet normal -0.00191002 -0.0064877 -0.999977 + outer loop + vertex -569.441 73.7619 0.0257265 + vertex -567.123 77.127 -0.000533707 + vertex -557.511 70.435 0.0245236 + endloop + endfacet + facet normal -0.00192855 -0.00647493 -0.999977 + outer loop + vertex -569.441 73.7619 0.0257265 + vertex -578.179 80.0389 0.001935 + vertex -567.123 77.127 -0.000533707 + endloop + endfacet + facet normal -0.000837507 -0.00233221 -0.999997 + outer loop + vertex -578.179 80.0389 0.001935 + vertex -575.233 83.1976 -0.00789911 + vertex -567.123 77.127 -0.000533707 + endloop + endfacet + facet normal -0.000684144 -0.00212732 -0.999998 + outer loop + vertex -567.123 77.127 -0.000533707 + vertex -575.233 83.1976 -0.00789911 + vertex -564.225 80.1114 -0.00886458 + endloop + endfacet + facet normal -0.000711616 -0.00210065 -0.999998 + outer loop + vertex -567.123 77.127 -0.000533707 + vertex -564.225 80.1114 -0.00886458 + vertex -555.19 73.7762 -0.00198594 + endloop + endfacet + facet normal -2.19621e-05 0.000234495 -1 + outer loop + vertex -575.233 83.1976 -0.00789911 + vertex -571.646 85.6837 -0.00739494 + vertex -564.225 80.1114 -0.00886458 + endloop + endfacet + facet normal 6.91628e-05 0.000355848 -1 + outer loop + vertex -564.225 80.1114 -0.00886458 + vertex -571.646 85.6837 -0.00739494 + vertex -561.061 82.7182 -0.00771809 + endloop + endfacet + facet normal 1.71194e-05 0.000419021 -1 + outer loop + vertex -564.225 80.1114 -0.00886458 + vertex -561.061 82.7182 -0.00771809 + vertex -552.474 76.7886 -0.0100557 + endloop + endfacet + facet normal 0.000233251 0.000941556 -1 + outer loop + vertex -571.646 85.6837 -0.00739494 + vertex -568.369 87.9361 -0.00450985 + vertex -561.061 82.7182 -0.00771809 + endloop + endfacet + facet normal 0.000285168 0.00101427 -0.999999 + outer loop + vertex -561.061 82.7182 -0.00771809 + vertex -568.369 87.9361 -0.00450985 + vertex -557.791 85.0215 -0.00444941 + endloop + endfacet + facet normal 0.00026083 0.00104882 -0.999999 + outer loop + vertex -561.061 82.7182 -0.00771809 + vertex -557.791 85.0215 -0.00444941 + vertex -549.453 79.4374 -0.00813134 + endloop + endfacet + facet normal 0.000177127 0.000622141 -1 + outer loop + vertex -568.369 87.9361 -0.00450985 + vertex -564.912 89.9197 -0.0026633 + vertex -557.791 85.0215 -0.00444941 + endloop + endfacet + facet normal 0.000198442 0.000653127 -1 + outer loop + vertex -557.791 85.0215 -0.00444941 + vertex -564.912 89.9197 -0.0026633 + vertex -554.325 86.9975 -0.00247099 + endloop + endfacet + facet normal 0.000188636 0.00067033 -1 + outer loop + vertex -557.791 85.0215 -0.00444941 + vertex -554.325 86.9975 -0.00247099 + vertex -546.214 81.7452 -0.00446186 + endloop + endfacet + facet normal 7.91545e-05 0.000220961 -1 + outer loop + vertex -564.912 89.9197 -0.0026633 + vertex -561.287 91.6162 -0.00200151 + vertex -554.325 86.9975 -0.00247099 + endloop + endfacet + facet normal 8.33038e-05 0.000227216 -1 + outer loop + vertex -554.325 86.9975 -0.00247099 + vertex -561.287 91.6162 -0.00200151 + vertex -550.728 88.6884 -0.00178714 + endloop + endfacet + facet normal 7.91924e-05 0.000235961 -1 + outer loop + vertex -554.325 86.9975 -0.00247099 + vertex -550.728 88.6884 -0.00178714 + vertex -542.797 83.7284 -0.00232946 + endloop + endfacet + facet normal 4.72793e-05 9.7294e-05 -1 + outer loop + vertex -561.287 91.6162 -0.00200151 + vertex -557.555 93.0583 -0.00168477 + vertex -550.728 88.6884 -0.00178714 + endloop + endfacet + facet normal 4.74235e-05 9.75193e-05 -1 + outer loop + vertex -550.728 88.6884 -0.00178714 + vertex -557.555 93.0583 -0.00168477 + vertex -547.066 90.1554 -0.00147045 + endloop + endfacet + facet normal 4.57268e-05 0.000101754 -1 + outer loop + vertex -550.728 88.6884 -0.00178714 + vertex -547.066 90.1554 -0.00147045 + vertex -539.279 85.4438 -0.00159378 + endloop + endfacet + facet normal 4.18567e-05 9.53573e-05 -1 + outer loop + vertex -539.279 85.4438 -0.00159378 + vertex -547.066 90.1554 -0.00147045 + vertex -535.702 86.9505 -0.00130038 + endloop + endfacet + facet normal 5.55849e-05 0.000144038 -1 + outer loop + vertex -547.066 90.1554 -0.00147045 + vertex -543.429 91.5095 -0.00107322 + vertex -535.702 86.9505 -0.00130038 + endloop + endfacet + facet normal 5.63112e-05 0.000142087 -1 + outer loop + vertex -547.066 90.1554 -0.00147045 + vertex -553.821 94.3201 -0.00125905 + vertex -543.429 91.5095 -0.00107322 + endloop + endfacet + facet normal 6.9917e-05 0.000192393 -1 + outer loop + vertex -553.821 94.3201 -0.00125905 + vertex -550.294 95.6826 -0.000750355 + vertex -543.429 91.5095 -0.00107322 + endloop + endfacet + facet normal 5.9252e-05 0.000174847 -1 + outer loop + vertex -543.429 91.5095 -0.00107322 + vertex -550.294 95.6826 -0.000750355 + vertex -539.761 92.7939 -0.000631331 + endloop + endfacet + facet normal 5.99755e-05 0.000172781 -1 + outer loop + vertex -543.429 91.5095 -0.00107322 + vertex -539.761 92.7939 -0.000631331 + vertex -532.114 88.3286 -0.00094422 + endloop + endfacet + facet normal 5.36743e-05 0.00015451 -1 + outer loop + vertex -550.294 95.6826 -0.000750355 + vertex -546.28 96.8979 -0.000347132 + vertex -539.761 92.7939 -0.000631331 + endloop + endfacet + facet normal 4.50034e-05 0.000140736 -1 + outer loop + vertex -539.761 92.7939 -0.000631331 + vertex -546.28 96.8979 -0.000347132 + vertex -536.05 93.9903 -0.000295917 + endloop + endfacet + facet normal 4.58925e-05 0.000137978 -1 + outer loop + vertex -539.761 92.7939 -0.000631331 + vertex -536.05 93.9903 -0.000295917 + vertex -528.539 89.6192 -0.000554336 + endloop + endfacet + facet normal 3.91473e-05 0.000126387 -1 + outer loop + vertex -528.539 89.6192 -0.000554336 + vertex -536.05 93.9903 -0.000295917 + vertex -525.042 90.8581 -0.000260867 + endloop + endfacet + facet normal 2.581e-05 7.95154e-05 -1 + outer loop + vertex -536.05 93.9903 -0.000295917 + vertex -532.435 95.1311 -0.000111914 + vertex -525.042 90.8581 -0.000260867 + endloop + endfacet + facet normal 2.52989e-05 8.1135e-05 -1 + outer loop + vertex -536.05 93.9903 -0.000295917 + vertex -542.181 97.9458 -0.000130102 + vertex -532.435 95.1311 -0.000111914 + endloop + endfacet + facet normal 1.35746e-05 4.05399e-05 -1 + outer loop + vertex -542.181 97.9458 -0.000130102 + vertex -538.533 99.0128 -3.73283e-05 + vertex -532.435 95.1311 -0.000111914 + endloop + endfacet + facet normal 1.10471e-05 3.65694e-05 -1 + outer loop + vertex -532.435 95.1311 -0.000111914 + vertex -538.533 99.0128 -3.73283e-05 + vertex -528.718 96.1771 -3.25992e-05 + endloop + endfacet + facet normal 5.52098e-06 1.74419e-05 -1 + outer loop + vertex -538.533 99.0128 -3.73283e-05 + vertex -534.878 99.9961 -8.32429e-14 + vertex -528.718 96.1771 -3.25992e-05 + endloop + endfacet + facet normal 5.33129e-06 1.81468e-05 -1 + outer loop + vertex -538.533 99.0128 -3.73283e-05 + vertex -544.383 102.789 -8.29674e-14 + vertex -534.878 99.9961 -8.32429e-14 + endloop + endfacet + facet normal 6.62516e-06 2.01516e-05 -1 + outer loop + vertex -546.603 101.37 -4.3286e-05 + vertex -544.383 102.789 -8.29674e-14 + vertex -538.533 99.0128 -3.73283e-05 + endloop + endfacet + facet normal 6.22208e-06 2.07827e-05 -1 + outer loop + vertex -551.859 105.027 -8.27466e-14 + vertex -544.383 102.789 -8.29674e-14 + vertex -546.603 101.37 -4.3286e-05 + endloop + endfacet + facet normal 6.67916e-06 2.14397e-05 -1 + outer loop + vertex -552.078 102.925 -4.6514e-05 + vertex -551.859 105.027 -8.27466e-14 + vertex -546.603 101.37 -4.3286e-05 + endloop + endfacet + facet normal 1.42193e-05 4.79869e-05 -1 + outer loop + vertex -546.603 101.37 -4.3286e-05 + vertex -550.331 100.279 -0.00014869 + vertex -552.078 102.925 -4.6514e-05 + endloop + endfacet + facet normal 1.23481e-05 4.67523e-05 -1 + outer loop + vertex -555.998 101.856 -0.000144923 + vertex -552.078 102.925 -4.6514e-05 + vertex -550.331 100.279 -0.00014869 + endloop + endfacet + facet normal 3.10223e-05 0.000113845 -1 + outer loop + vertex -550.331 100.279 -0.00014869 + vertex -555.685 99.4053 -0.000414203 + vertex -555.998 101.856 -0.000144923 + endloop + endfacet + facet normal 2.00295e-05 0.000112442 -1 + outer loop + vertex -559.977 101.268 -0.00029069 + vertex -555.998 101.856 -0.000144923 + vertex -555.685 99.4053 -0.000414203 + endloop + endfacet + facet normal 4.77737e-05 0.000176355 -1 + outer loop + vertex -562.611 100.065 -0.000628778 + vertex -559.977 101.268 -0.00029069 + vertex -555.685 99.4053 -0.000414203 + endloop + endfacet + facet normal 5.06175e-05 0.000206227 -1 + outer loop + vertex -555.685 99.4053 -0.000414203 + vertex -559.259 97.6954 -0.00094773 + vertex -562.611 100.065 -0.000628778 + endloop + endfacet + facet normal 6.62058e-05 0.000228276 -1 + outer loop + vertex -566.596 98.4201 -0.00126801 + vertex -562.611 100.065 -0.000628778 + vertex -559.259 97.6954 -0.00094773 + endloop + endfacet + facet normal 6.62255e-05 0.000228475 -1 + outer loop + vertex -559.259 97.6954 -0.00094773 + vertex -561.682 96.1909 -0.00145189 + vertex -566.596 98.4201 -0.00126801 + endloop + endfacet + facet normal 5.1263e-05 0.000195492 -1 + outer loop + vertex -561.682 96.1909 -0.00145189 + vertex -566.963 95.5811 -0.00184184 + vertex -566.596 98.4201 -0.00126801 + endloop + endfacet + facet normal 6.4152e-05 0.000193825 -1 + outer loop + vertex -571.79 97.6722 -0.0017462 + vertex -566.596 98.4201 -0.00126801 + vertex -566.963 95.5811 -0.00184184 + endloop + endfacet + facet normal 4.35971e-05 0.000146377 -1 + outer loop + vertex -574.569 95.8383 -0.00213579 + vertex -571.79 97.6722 -0.0017462 + vertex -566.963 95.5811 -0.00184184 + endloop + endfacet + facet normal 4.28233e-05 0.000123495 -1 + outer loop + vertex -566.963 95.5811 -0.00184184 + vertex -569.315 93.5041 -0.00219909 + vertex -574.569 95.8383 -0.00213579 + endloop + endfacet + facet normal 9.42432e-05 0.000239221 -1 + outer loop + vertex -569.315 93.5041 -0.00219909 + vertex -574.435 92.4279 -0.00293896 + vertex -574.569 95.8383 -0.00213579 + endloop + endfacet + facet normal 4.90994e-05 0.000237443 -1 + outer loop + vertex -579.324 94.649 -0.00265164 + vertex -574.569 95.8383 -0.00213579 + vertex -574.435 92.4279 -0.00293896 + endloop + endfacet + facet normal 0.000188194 0.00054364 -1 + outer loop + vertex -581.75 92.1609 -0.00446087 + vertex -579.324 94.649 -0.00265164 + vertex -574.435 92.4279 -0.00293896 + endloop + endfacet + facet normal 0.000185601 0.000614673 -1 + outer loop + vertex -574.435 92.4279 -0.00293896 + vertex -576.226 89.7323 -0.00492838 + vertex -581.75 92.1609 -0.00446087 + endloop + endfacet + facet normal 0.000273016 0.000813507 -1 + outer loop + vertex -576.226 89.7323 -0.00492838 + vertex -580.38 88.2308 -0.00728403 + vertex -581.75 92.1609 -0.00446087 + endloop + endfacet + facet normal 0.000305553 0.000824849 -1 + outer loop + vertex -586.43 90.0831 -0.00760482 + vertex -581.75 92.1609 -0.00446087 + vertex -580.38 88.2308 -0.00728403 + endloop + endfacet + facet normal 2.89516e-05 -7.86171e-05 -1 + outer loop + vertex -580.38 88.2308 -0.00728403 + vertex -585.154 85.7514 -0.00722734 + vertex -586.43 90.0831 -0.00760482 + endloop + endfacet + facet normal 0.000467276 5.04909e-05 -1 + outer loop + vertex -589.918 88.4038 -0.00931934 + vertex -586.43 90.0831 -0.00760482 + vertex -585.154 85.7514 -0.00722734 + endloop + endfacet + facet normal -0.000521364 -0.0017251 -0.999998 + outer loop + vertex -591.538 85.3459 -0.0031994 + vertex -589.918 88.4038 -0.00931934 + vertex -585.154 85.7514 -0.00722734 + endloop + endfacet + facet normal -0.000425593 -0.00323276 -0.999995 + outer loop + vertex -585.154 85.7514 -0.00722734 + vertex -587.133 81.6205 0.00696929 + vertex -591.538 85.3459 -0.0031994 + endloop + endfacet + facet normal -0.00264727 -0.0058596 -0.999979 + outer loop + vertex -593.457 80.9773 0.0274787 + vertex -591.538 85.3459 -0.0031994 + vertex -587.133 81.6205 0.00696929 + endloop + endfacet + facet normal -0.00246179 -0.00768284 -0.999967 + outer loop + vertex -587.133 81.6205 0.00696929 + vertex -587.735 78.0842 0.03562 + vertex -593.457 80.9773 0.0274787 + endloop + endfacet + facet normal -0.00519539 -0.0130892 -0.999901 + outer loop + vertex -587.735 78.0842 0.03562 + vertex -590.734 75.7278 0.0820466 + vertex -593.457 80.9773 0.0274787 + endloop + endfacet + facet normal -0.00395407 -0.0124453 -0.999915 + outer loop + vertex -596.999 77.3782 0.0862832 + vertex -593.457 80.9773 0.0274787 + vertex -590.734 75.7278 0.0820466 + endloop + endfacet + facet normal -0.00681635 -0.0233129 -0.999705 + outer loop + vertex -590.734 75.7278 0.0820466 + vertex -593.899 72.0924 0.188406 + vertex -596.999 77.3782 0.0862832 + endloop + endfacet + facet normal -0.00395988 -0.0216385 -0.999758 + outer loop + vertex -599.625 74.6912 0.15484 + vertex -596.999 77.3782 0.0862832 + vertex -593.899 72.0924 0.188406 + endloop + endfacet + facet normal -0.0110163 -0.0371803 -0.999248 + outer loop + vertex -599.667 71.0495 0.290799 + vertex -599.625 74.6912 0.15484 + vertex -593.899 72.0924 0.188406 + endloop + endfacet + facet normal -0.00937578 -0.0462178 -0.998887 + outer loop + vertex -593.899 72.0924 0.188406 + vertex -593.917 67.0095 0.423758 + vertex -599.667 71.0495 0.290799 + endloop + endfacet + facet normal -0.0277743 -0.0723407 -0.996993 + outer loop + vertex -599.856 66.2373 0.645224 + vertex -599.667 71.0495 0.290799 + vertex -593.917 67.0095 0.423758 + endloop + endfacet + facet normal -0.0253958 -0.0902339 -0.995597 + outer loop + vertex -593.917 67.0095 0.423758 + vertex -593.502 62.8055 0.794206 + vertex -599.856 66.2373 0.645224 + endloop + endfacet + facet normal -0.0556355 -0.145873 -0.987738 + outer loop + vertex -593.502 62.8055 0.794206 + vertex -596.706 59.8171 1.41601 + vertex -599.856 66.2373 0.645224 + endloop + endfacet + facet normal -0.02411 -0.130814 -0.991114 + outer loop + vertex -602.368 63.0885 1.12195 + vertex -599.856 66.2373 0.645224 + vertex -596.706 59.8171 1.41601 + endloop + endfacet + facet normal -0.0294758 -0.126594 -0.991517 + outer loop + vertex -602.368 63.0885 1.12195 + vertex -603.911 66.8305 0.690053 + vertex -599.856 66.2373 0.645224 + endloop + endfacet + facet normal -0.0233619 -0.0844408 -0.996155 + outer loop + vertex -603.911 66.8305 0.690053 + vertex -602.73 70.0509 0.389379 + vertex -599.856 66.2373 0.645224 + endloop + endfacet + facet normal -0.0372396 -0.0793532 -0.996151 + outer loop + vertex -602.73 70.0509 0.389379 + vertex -603.911 66.8305 0.690053 + vertex -604.995 71.2177 0.381081 + endloop + endfacet + facet normal -0.0201922 -0.0462888 -0.998724 + outer loop + vertex -602.327 73.5647 0.218361 + vertex -602.73 70.0509 0.389379 + vertex -604.995 71.2177 0.381081 + endloop + endfacet + facet normal -0.0281435 -0.0372623 -0.998909 + outer loop + vertex -604.995 71.2177 0.381081 + vertex -603.664 75.9401 0.167437 + vertex -602.327 73.5647 0.218361 + endloop + endfacet + facet normal -0.00803836 -0.0259566 -0.999631 + outer loop + vertex -600.706 77.2904 0.108588 + vertex -602.327 73.5647 0.218361 + vertex -603.664 75.9401 0.167437 + endloop + endfacet + facet normal -0.0113588 -0.0186882 -0.999761 + outer loop + vertex -603.664 75.9401 0.167437 + vertex -601.797 80.4221 0.0624451 + vertex -600.706 77.2904 0.108588 + endloop + endfacet + facet normal -0.00330145 -0.0158825 -0.999868 + outer loop + vertex -598.105 80.9645 0.0416374 + vertex -600.706 77.2904 0.108588 + vertex -601.797 80.4221 0.0624451 + endloop + endfacet + facet normal -0.00418507 -0.00987115 -0.999943 + outer loop + vertex -601.797 80.4221 0.0624451 + vertex -598.637 84.1836 0.0120873 + vertex -598.105 80.9645 0.0416374 + endloop + endfacet + facet normal -0.000956294 -0.00933733 -0.999956 + outer loop + vertex -595.361 84.6927 0.0042001 + vertex -598.105 80.9645 0.0416374 + vertex -598.637 84.1836 0.0120873 + endloop + endfacet + facet normal -0.00181355 -0.00382166 -0.999991 + outer loop + vertex -598.637 84.1836 0.0120873 + vertex -595.839 87.5791 -0.00596367 + vertex -595.361 84.6927 0.0042001 + endloop + endfacet + facet normal -0.000180208 -0.00355113 -0.999994 + outer loop + vertex -592.79 88.135 -0.00848738 + vertex -595.361 84.6927 0.0042001 + vertex -595.839 87.5791 -0.00596367 + endloop + endfacet + facet normal -0.000890959 0.000348063 -1 + outer loop + vertex -595.839 87.5791 -0.00596367 + vertex -592.69 90.9615 -0.00759267 + vertex -592.79 88.135 -0.00848738 + endloop + endfacet + facet normal -8.30113e-05 0.000319485 -1 + outer loop + vertex -589.64 90.8089 -0.00789463 + vertex -592.79 88.135 -0.00848738 + vertex -592.69 90.9615 -0.00759267 + endloop + endfacet + facet normal -3.63537e-05 0.00125197 -0.999999 + outer loop + vertex -592.69 90.9615 -0.00759267 + vertex -587.776 93.5699 -0.00450561 + vertex -589.64 90.8089 -0.00789463 + endloop + endfacet + facet normal 0.000276337 0.00104096 -0.999999 + outer loop + vertex -586.241 92.4985 -0.00519661 + vertex -589.64 90.8089 -0.00789463 + vertex -587.776 93.5699 -0.00450561 + endloop + endfacet + facet normal 0.000135488 0.000839093 -1 + outer loop + vertex -583.193 94.4818 -0.00311952 + vertex -586.241 92.4985 -0.00519661 + vertex -587.776 93.5699 -0.00450561 + endloop + endfacet + facet normal 0.000206183 0.000483785 -1 + outer loop + vertex -587.776 93.5699 -0.00450561 + vertex -583.302 96.3577 -0.00223434 + vertex -583.193 94.4818 -0.00311952 + endloop + endfacet + facet normal 2.41148e-05 0.00047327 -1 + outer loop + vertex -579.059 96.4341 -0.00209586 + vertex -583.193 94.4818 -0.00311952 + vertex -583.302 96.3577 -0.00223434 + endloop + endfacet + facet normal 2.71933e-05 0.000302298 -1 + outer loop + vertex -583.302 96.3577 -0.00223434 + vertex -577.321 98.5442 -0.00141074 + vertex -579.059 96.4341 -0.00209586 + endloop + endfacet + facet normal -3.96876e-05 0.000357369 -1 + outer loop + vertex -575.283 97.7161 -0.00178756 + vertex -579.059 96.4341 -0.00209586 + vertex -577.321 98.5442 -0.00141074 + endloop + endfacet + facet normal -1.77314e-05 0.000411423 -1 + outer loop + vertex -571.764 99.0137 -0.00131609 + vertex -575.283 97.7161 -0.00178756 + vertex -577.321 98.5442 -0.00141074 + endloop + endfacet + facet normal -1.47447e-05 0.000376076 -1 + outer loop + vertex -577.321 98.5442 -0.00141074 + vertex -571.438 100.591 -0.000727614 + vertex -571.764 99.0137 -0.00131609 + endloop + endfacet + facet normal 1.36021e-05 0.000370209 -1 + outer loop + vertex -566.916 100.381 -0.000744124 + vertex -571.764 99.0137 -0.00131609 + vertex -571.438 100.591 -0.000727614 + endloop + endfacet + facet normal 7.5664e-06 0.000240696 -1 + outer loop + vertex -571.438 100.591 -0.000727614 + vertex -565.056 102.226 -0.000285875 + vertex -566.916 100.381 -0.000744124 + endloop + endfacet + facet normal 4.31938e-05 0.000204796 -1 + outer loop + vertex -563.109 101.401 -0.000370725 + vertex -566.916 100.381 -0.000744124 + vertex -565.056 102.226 -0.000285875 + endloop + endfacet + facet normal 1.80666e-05 0.000145494 -1 + outer loop + vertex -559.876 102.44 -0.000161103 + vertex -563.109 101.401 -0.000370725 + vertex -565.056 102.226 -0.000285875 + endloop + endfacet + facet normal 2.18309e-05 5.45169e-05 -1 + outer loop + vertex -565.056 102.226 -0.000285875 + vertex -559.381 103.913 -7.00412e-05 + vertex -559.876 102.44 -0.000161103 + endloop + endfacet + facet normal 8.72755e-06 5.89178e-05 -1 + outer loop + vertex -555.465 103.652 -5.1242e-05 + vertex -559.876 102.44 -0.000161103 + vertex -559.381 103.913 -7.00412e-05 + endloop + endfacet + facet normal 6.19646e-06 2.09471e-05 -1 + outer loop + vertex -559.381 103.913 -7.00412e-05 + vertex -552.55 105.235 -8.2726e-14 + vertex -555.465 103.652 -5.1242e-05 + endloop + endfacet + facet normal 6.28352e-06 2.07868e-05 -1 + outer loop + vertex -552.55 105.235 -8.2726e-14 + vertex -552.205 105.131 -8.27363e-14 + vertex -555.465 103.652 -5.1242e-05 + endloop + endfacet + facet normal 5.99071e-06 2.14321e-05 -1 + outer loop + vertex -555.465 103.652 -5.1242e-05 + vertex -552.205 105.131 -8.27363e-14 + vertex -552.078 102.925 -4.6514e-05 + endloop + endfacet + facet normal 4.1281e-06 3.16286e-05 -1 + outer loop + vertex -552.55 105.235 -8.2726e-14 + vertex -559.381 103.913 -7.00412e-05 + vertex -559.422 105.645 -1.54023e-05 + endloop + endfacet + facet normal 2.78425e-06 9.10326e-06 -1 + outer loop + vertex -562.338 108.229 -8.24307e-14 + vertex -552.55 105.235 -8.2726e-14 + vertex -559.422 105.645 -1.54023e-05 + endloop + endfacet + facet normal 6.80209e-08 6.03819e-06 -1 + outer loop + vertex -559.422 105.645 -1.54023e-05 + vertex -563.688 106.724 -9.17726e-06 + vertex -562.338 108.229 -8.24307e-14 + endloop + endfacet + facet normal 1.24465e-06 4.98257e-06 -1 + outer loop + vertex -563.688 106.724 -9.17726e-06 + vertex -572.144 109.845 -4.15409e-06 + vertex -562.338 108.229 -8.24307e-14 + endloop + endfacet + facet normal 8.92296e-07 2.84421e-06 -1 + outer loop + vertex -572.869 111.533 -8.21047e-14 + vertex -562.338 108.229 -8.24307e-14 + vertex -572.144 109.845 -4.15409e-06 + endloop + endfacet + facet normal 9.22119e-07 2.85702e-06 -1 + outer loop + vertex -572.144 109.845 -4.15409e-06 + vertex -583.066 114.824 -8.178e-14 + vertex -572.869 111.533 -8.21047e-14 + endloop + endfacet + facet normal 3.8292e-07 1.67426e-06 -1 + outer loop + vertex -584.337 113.574 -2.57903e-06 + vertex -583.066 114.824 -8.178e-14 + vertex -572.144 109.845 -4.15409e-06 + endloop + endfacet + facet normal 1.35267e-06 4.84482e-06 -1 + outer loop + vertex -576.779 109.384 -1.2657e-05 + vertex -584.337 113.574 -2.57903e-06 + vertex -572.144 109.845 -4.15409e-06 + endloop + endfacet + facet normal 1.17862e-06 6.59452e-06 -1 + outer loop + vertex -576.779 109.384 -1.2657e-05 + vertex -572.144 109.845 -4.15409e-06 + vertex -567.356 106.477 -2.07193e-05 + endloop + endfacet + facet normal 4.57131e-06 1.75927e-05 -1 + outer loop + vertex -571.341 106 -4.73401e-05 + vertex -576.779 109.384 -1.2657e-05 + vertex -567.356 106.477 -2.07193e-05 + endloop + endfacet + facet normal 3.20042e-06 2.90312e-05 -1 + outer loop + vertex -571.341 106 -4.73401e-05 + vertex -567.356 106.477 -2.07193e-05 + vertex -564.605 104.205 -7.78898e-05 + endloop + endfacet + facet normal 7.97442e-06 4.69481e-05 -1 + outer loop + vertex -568.458 103.719 -0.0001314 + vertex -571.341 106 -4.73401e-05 + vertex -564.605 104.205 -7.78898e-05 + endloop + endfacet + facet normal 6.65707e-07 0.000104957 -1 + outer loop + vertex -568.458 103.719 -0.0001314 + vertex -564.605 104.205 -7.78898e-05 + vertex -565.056 102.226 -0.000285875 + endloop + endfacet + facet normal 9.05476e-06 0.000124065 -1 + outer loop + vertex -571.218 102.708 -0.000281846 + vertex -568.458 103.719 -0.0001314 + vertex -565.056 102.226 -0.000285875 + endloop + endfacet + facet normal 1.93315e-05 9.60122e-05 -1 + outer loop + vertex -571.218 102.708 -0.000281846 + vertex -574.881 105.314 -0.00010243 + vertex -568.458 103.719 -0.0001314 + endloop + endfacet + facet normal 9.82897e-06 8.26553e-05 -1 + outer loop + vertex -578.076 104.479 -0.000202919 + vertex -574.881 105.314 -0.00010243 + vertex -571.218 102.708 -0.000281846 + endloop + endfacet + facet normal 1.96973e-05 0.000120883 -1 + outer loop + vertex -574.856 102.037 -0.000434577 + vertex -578.076 104.479 -0.000202919 + vertex -571.218 102.708 -0.000281846 + endloop + endfacet + facet normal 3.22505e-06 0.000210248 -1 + outer loop + vertex -574.856 102.037 -0.000434577 + vertex -571.218 102.708 -0.000281846 + vertex -571.438 100.591 -0.000727614 + endloop + endfacet + facet normal 1.36463e-05 0.00023488 -1 + outer loop + vertex -577.378 100.836 -0.000751126 + vertex -574.856 102.037 -0.000434577 + vertex -571.438 100.591 -0.000727614 + endloop + endfacet + facet normal 3.63108e-05 0.000187298 -1 + outer loop + vertex -577.378 100.836 -0.000751126 + vertex -581.179 103.553 -0.000380247 + vertex -574.856 102.037 -0.000434577 + endloop + endfacet + facet normal 2.89539e-05 0.000177005 -1 + outer loop + vertex -584.304 102.567 -0.000645393 + vertex -581.179 103.553 -0.000380247 + vertex -577.378 100.836 -0.000751126 + endloop + endfacet + facet normal 3.54231e-05 0.000202901 -1 + outer loop + vertex -581.037 100.059 -0.0010384 + vertex -584.304 102.567 -0.000645393 + vertex -577.378 100.836 -0.000751126 + endloop + endfacet + facet normal 1.73077e-05 0.000288201 -1 + outer loop + vertex -581.037 100.059 -0.0010384 + vertex -577.378 100.836 -0.000751126 + vertex -577.321 98.5442 -0.00141074 + endloop + endfacet + facet normal 1.26037e-05 0.000276664 -1 + outer loop + vertex -583.474 98.7391 -0.00143436 + vertex -581.037 100.059 -0.0010384 + vertex -577.321 98.5442 -0.00141074 + endloop + endfacet + facet normal 4.26143e-05 0.000221252 -1 + outer loop + vertex -583.474 98.7391 -0.00143436 + vertex -587.459 101.541 -0.000984211 + vertex -581.037 100.059 -0.0010384 + endloop + endfacet + facet normal 4.00644e-05 0.000217625 -1 + outer loop + vertex -590.514 100.427 -0.00134901 + vertex -587.459 101.541 -0.000984211 + vertex -583.474 98.7391 -0.00143436 + endloop + endfacet + facet normal 4.00438e-05 0.00021754 -1 + outer loop + vertex -587.027 97.7987 -0.00178119 + vertex -590.514 100.427 -0.00134901 + vertex -583.474 98.7391 -0.00143436 + endloop + endfacet + facet normal 8.5443e-06 0.000336546 -1 + outer loop + vertex -587.027 97.7987 -0.00178119 + vertex -583.474 98.7391 -0.00143436 + vertex -583.302 96.3577 -0.00223434 + endloop + endfacet + facet normal 4.76399e-05 0.000437612 -1 + outer loop + vertex -589.211 96.1533 -0.00260531 + vertex -587.027 97.7987 -0.00178119 + vertex -583.302 96.3577 -0.00223434 + endloop + endfacet + facet normal 8.18938e-05 0.000392138 -1 + outer loop + vertex -589.211 96.1533 -0.00260531 + vertex -593.498 99.1909 -0.00176516 + vertex -587.027 97.7987 -0.00178119 + endloop + endfacet + facet normal 7.14016e-05 0.000377333 -1 + outer loop + vertex -596.475 97.7212 -0.00253233 + vertex -593.498 99.1909 -0.00176516 + vertex -589.211 96.1533 -0.00260531 + endloop + endfacet + facet normal 0.000137468 0.000683407 -1 + outer loop + vertex -592.714 94.2617 -0.00437945 + vertex -596.475 97.7212 -0.00253233 + vertex -589.211 96.1533 -0.00260531 + endloop + endfacet + facet normal 8.4065e-05 0.000782283 -1 + outer loop + vertex -592.714 94.2617 -0.00437945 + vertex -589.211 96.1533 -0.00260531 + vertex -587.776 93.5699 -0.00450561 + endloop + endfacet + facet normal 0.000139687 0.000685819 -1 + outer loop + vertex -599.561 96.149 -0.0040417 + vertex -596.475 97.7212 -0.00253233 + vertex -592.714 94.2617 -0.00437945 + endloop + endfacet + facet normal 0.000206722 0.000929055 -1 + outer loop + vertex -596.004 92.9025 -0.00632248 + vertex -599.561 96.149 -0.0040417 + vertex -592.714 94.2617 -0.00437945 + endloop + endfacet + facet normal 0.00018775 0.000974981 -1 + outer loop + vertex -596.004 92.9025 -0.00632248 + vertex -592.714 94.2617 -0.00437945 + vertex -592.69 90.9615 -0.00759267 + endloop + endfacet + facet normal 7.8817e-05 0.000788979 -1 + outer loop + vertex -597.779 90.5964 -0.00828188 + vertex -596.004 92.9025 -0.00632248 + vertex -592.69 90.9615 -0.00759267 + endloop + endfacet + facet normal 0.000192106 0.000701772 -1 + outer loop + vertex -597.779 90.5964 -0.00828188 + vertex -602.361 94.3359 -0.00653785 + vertex -596.004 92.9025 -0.00632248 + endloop + endfacet + facet normal 0.000110712 0.000602035 -1 + outer loop + vertex -604.96 92.0475 -0.0082032 + vertex -602.361 94.3359 -0.00653785 + vertex -597.779 90.5964 -0.00828188 + endloop + endfacet + facet normal -0.000262627 -0.0012453 -0.999999 + outer loop + vertex -600.448 87.7592 -0.00404786 + vertex -604.96 92.0475 -0.0082032 + vertex -597.779 90.5964 -0.00828188 + endloop + endfacet + facet normal -0.000457216 -0.00106226 -0.999999 + outer loop + vertex -600.448 87.7592 -0.00404786 + vertex -597.779 90.5964 -0.00828188 + vertex -595.839 87.5791 -0.00596367 + endloop + endfacet + facet normal -0.000451091 -0.00144358 -0.999999 + outer loop + vertex -607.586 89.3965 -0.00319154 + vertex -604.96 92.0475 -0.0082032 + vertex -600.448 87.7592 -0.00404786 + endloop + endfacet + facet normal -0.00131677 -0.0052176 -0.999986 + outer loop + vertex -603.131 84.7507 0.0151828 + vertex -607.586 89.3965 -0.00319154 + vertex -600.448 87.7592 -0.00404786 + endloop + endfacet + facet normal -0.00134416 -0.00519317 -0.999986 + outer loop + vertex -603.131 84.7507 0.0151828 + vertex -600.448 87.7592 -0.00404786 + vertex -598.637 84.1836 0.0120873 + endloop + endfacet + facet normal -0.00145153 -0.00534683 -0.999985 + outer loop + vertex -610.016 86.5936 0.0153226 + vertex -607.586 89.3965 -0.00319154 + vertex -603.131 84.7507 0.0151828 + endloop + endfacet + facet normal -0.00259696 -0.00962601 -0.99995 + outer loop + vertex -605.691 82.4307 0.0441653 + vertex -610.016 86.5936 0.0153226 + vertex -603.131 84.7507 0.0151828 + endloop + endfacet + facet normal -0.0011148 -0.0112614 -0.999936 + outer loop + vertex -605.691 82.4307 0.0441653 + vertex -603.131 84.7507 0.0151828 + vertex -601.797 80.4221 0.0624451 + endloop + endfacet + facet normal -0.00442008 -0.0176683 -0.999834 + outer loop + vertex -606.541 79.1553 0.105803 + vertex -605.691 82.4307 0.0441653 + vertex -601.797 80.4221 0.0624451 + endloop + endfacet + facet normal -0.00500345 -0.0175169 -0.999834 + outer loop + vertex -606.541 79.1553 0.105803 + vertex -611.974 83.5556 0.0558987 + vertex -605.691 82.4307 0.0441653 + endloop + endfacet + facet normal -0.00629672 -0.0191132 -0.999797 + outer loop + vertex -613.592 80.095 0.132243 + vertex -611.974 83.5556 0.0558987 + vertex -606.541 79.1553 0.105803 + endloop + endfacet + facet normal -0.00765213 -0.0292896 -0.999542 + outer loop + vertex -608.053 75.2137 0.232881 + vertex -613.592 80.095 0.132243 + vertex -606.541 79.1553 0.105803 + endloop + endfacet + facet normal -0.0102189 -0.0283051 -0.999547 + outer loop + vertex -608.053 75.2137 0.232881 + vertex -606.541 79.1553 0.105803 + vertex -603.664 75.9401 0.167437 + endloop + endfacet + facet normal -0.0111361 -0.0332393 -0.999385 + outer loop + vertex -615.121 76.3353 0.274326 + vertex -613.592 80.095 0.132243 + vertex -608.053 75.2137 0.232881 + endloop + endfacet + facet normal -0.0146485 -0.0554094 -0.998356 + outer loop + vertex -609.489 71.0604 0.484461 + vertex -615.121 76.3353 0.274326 + vertex -608.053 75.2137 0.232881 + endloop + endfacet + facet normal -0.021101 -0.0531788 -0.998362 + outer loop + vertex -609.489 71.0604 0.484461 + vertex -608.053 75.2137 0.232881 + vertex -604.995 71.2177 0.381081 + endloop + endfacet + facet normal -0.0199288 -0.0852167 -0.996163 + outer loop + vertex -604.995 71.2177 0.381081 + vertex -606.462 66.649 0.80127 + vertex -609.489 71.0604 0.484461 + endloop + endfacet + facet normal -0.0215719 -0.0627781 -0.997794 + outer loop + vertex -616.511 72.3793 0.553282 + vertex -615.121 76.3353 0.274326 + vertex -609.489 71.0604 0.484461 + endloop + endfacet + facet normal -0.0290927 -0.103001 -0.994256 + outer loop + vertex -610.632 66.7398 0.9655 + vertex -616.511 72.3793 0.553282 + vertex -609.489 71.0604 0.484461 + endloop + endfacet + facet normal -0.0413224 -0.0997541 -0.994154 + outer loop + vertex -610.632 66.7398 0.9655 + vertex -609.489 71.0604 0.484461 + vertex -606.462 66.649 0.80127 + endloop + endfacet + facet normal -0.0406017 -0.114873 -0.99255 + outer loop + vertex -617.869 68.1713 1.09582 + vertex -616.511 72.3793 0.553282 + vertex -610.632 66.7398 0.9655 + endloop + endfacet + facet normal -0.0362882 -0.116265 -0.992555 + outer loop + vertex -617.869 68.1713 1.09582 + vertex -626.324 75.1774 0.584281 + vertex -616.511 72.3793 0.553282 + endloop + endfacet + facet normal -0.0223719 -0.067407 -0.997475 + outer loop + vertex -626.324 75.1774 0.584281 + vertex -624.85 79.0464 0.289763 + vertex -616.511 72.3793 0.553282 + endloop + endfacet + facet normal -0.0216283 -0.0676901 -0.997472 + outer loop + vertex -626.324 75.1774 0.584281 + vertex -636.117 82.6928 0.28661 + vertex -624.85 79.0464 0.289763 + endloop + endfacet + facet normal -0.0112474 -0.0356166 -0.999302 + outer loop + vertex -636.117 82.6928 0.28661 + vertex -634.661 86.3882 0.138515 + vertex -624.85 79.0464 0.289763 + endloop + endfacet + facet normal -0.0112056 -0.0355608 -0.999305 + outer loop + vertex -624.85 79.0464 0.289763 + vertex -634.661 86.3882 0.138515 + vertex -623.343 82.7374 0.141525 + endloop + endfacet + facet normal -0.0114654 -0.0354548 -0.999306 + outer loop + vertex -624.85 79.0464 0.289763 + vertex -623.343 82.7374 0.141525 + vertex -615.121 76.3353 0.274326 + endloop + endfacet + facet normal -0.0058938 -0.0190948 -0.9998 + outer loop + vertex -634.661 86.3882 0.138515 + vertex -632.954 89.8686 0.0619849 + vertex -623.343 82.7374 0.141525 + endloop + endfacet + facet normal -0.00624196 -0.0195639 -0.999789 + outer loop + vertex -623.343 82.7374 0.141525 + vertex -632.954 89.8686 0.0619849 + vertex -621.633 86.2242 0.0626142 + endloop + endfacet + facet normal -0.00625163 -0.0195591 -0.999789 + outer loop + vertex -623.343 82.7374 0.141525 + vertex -621.633 86.2242 0.0626142 + vertex -613.592 80.095 0.132243 + endloop + endfacet + facet normal -0.00351615 -0.0110959 -0.999932 + outer loop + vertex -632.954 89.8686 0.0619849 + vertex -630.915 93.0882 0.0190883 + vertex -621.633 86.2242 0.0626142 + endloop + endfacet + facet normal -0.00374621 -0.011407 -0.999928 + outer loop + vertex -621.633 86.2242 0.0626142 + vertex -630.915 93.0882 0.0190883 + vertex -619.653 89.437 0.018545 + endloop + endfacet + facet normal -0.00383235 -0.011354 -0.999928 + outer loop + vertex -621.633 86.2242 0.0626142 + vertex -619.653 89.437 0.018545 + vertex -611.974 83.5556 0.0558987 + endloop + endfacet + facet normal -0.00359187 -0.01104 -0.999933 + outer loop + vertex -611.974 83.5556 0.0558987 + vertex -619.653 89.437 0.018545 + vertex -610.016 86.5936 0.0153226 + endloop + endfacet + facet normal -0.00200169 -0.00565066 -0.999982 + outer loop + vertex -619.653 89.437 0.018545 + vertex -617.326 92.3224 -0.00241722 + vertex -610.016 86.5936 0.0153226 + endloop + endfacet + facet normal -0.00189179 -0.00573928 -0.999982 + outer loop + vertex -619.653 89.437 0.018545 + vertex -628.55 95.9881 -0.00222225 + vertex -617.326 92.3224 -0.00241722 + endloop + endfacet + facet normal -0.00059957 -0.00178264 -0.999998 + outer loop + vertex -628.55 95.9881 -0.00222225 + vertex -625.917 98.5381 -0.00834659 + vertex -617.326 92.3224 -0.00241722 + endloop + endfacet + facet normal -0.000533946 -0.00169194 -0.999998 + outer loop + vertex -617.326 92.3224 -0.00241722 + vertex -625.917 98.5381 -0.00834659 + vertex -614.708 94.8935 -0.0081649 + endloop + endfacet + facet normal -0.000575161 -0.00164998 -0.999998 + outer loop + vertex -617.326 92.3224 -0.00241722 + vertex -614.708 94.8935 -0.0081649 + vertex -607.586 89.3965 -0.00319154 + endloop + endfacet + facet normal 0.000151573 0.000416293 -1 + outer loop + vertex -625.917 98.5381 -0.00834659 + vertex -623.09 100.731 -0.00700521 + vertex -614.708 94.8935 -0.0081649 + endloop + endfacet + facet normal 0.000158891 0.000426799 -1 + outer loop + vertex -614.708 94.8935 -0.0081649 + vertex -623.09 100.731 -0.00700521 + vertex -611.936 97.1286 -0.00677035 + endloop + endfacet + facet normal 0.00013083 0.00046161 -1 + outer loop + vertex -614.708 94.8935 -0.0081649 + vertex -611.936 97.1286 -0.00677035 + vertex -604.96 92.0475 -0.0082032 + endloop + endfacet + facet normal 0.000330332 0.000957658 -0.999999 + outer loop + vertex -623.09 100.731 -0.00700521 + vertex -620.142 102.587 -0.00425394 + vertex -611.936 97.1286 -0.00677035 + endloop + endfacet + facet normal 0.000314254 0.000933485 -1 + outer loop + vertex -611.936 97.1286 -0.00677035 + vertex -620.142 102.587 -0.00425394 + vertex -609.078 99.0067 -0.00411934 + endloop + endfacet + facet normal 0.000302011 0.000952111 -1 + outer loop + vertex -611.936 97.1286 -0.00677035 + vertex -609.078 99.0067 -0.00411934 + vertex -602.361 94.3359 -0.00653785 + endloop + endfacet + facet normal 0.000288004 0.000931968 -1 + outer loop + vertex -602.361 94.3359 -0.00653785 + vertex -609.078 99.0067 -0.00411934 + vertex -599.561 96.149 -0.0040417 + endloop + endfacet + facet normal 0.000207751 0.000664703 -1 + outer loop + vertex -609.078 99.0067 -0.00411934 + vertex -606.087 100.58 -0.00245224 + vertex -599.561 96.149 -0.0040417 + endloop + endfacet + facet normal 0.000214362 0.000652135 -1 + outer loop + vertex -609.078 99.0067 -0.00411934 + vertex -617.137 104.161 -0.00248577 + vertex -606.087 100.58 -0.00245224 + endloop + endfacet + facet normal 0.00011262 0.000338169 -1 + outer loop + vertex -617.137 104.161 -0.00248577 + vertex -614.082 105.523 -0.00168104 + vertex -606.087 100.58 -0.00245224 + endloop + endfacet + facet normal 9.85709e-05 0.000315446 -1 + outer loop + vertex -606.087 100.58 -0.00245224 + vertex -614.082 105.523 -0.00168104 + vertex -603.078 101.974 -0.00171576 + endloop + endfacet + facet normal 9.05993e-05 0.000332653 -1 + outer loop + vertex -606.087 100.58 -0.00245224 + vertex -603.078 101.974 -0.00171576 + vertex -596.475 97.7212 -0.00253233 + endloop + endfacet + facet normal 5.99894e-05 0.000195808 -1 + outer loop + vertex -614.082 105.523 -0.00168104 + vertex -610.981 106.738 -0.0012571 + vertex -603.078 101.974 -0.00171576 + endloop + endfacet + facet normal 5.84039e-05 0.000193178 -1 + outer loop + vertex -603.078 101.974 -0.00171576 + vertex -610.981 106.738 -0.0012571 + vertex -600.027 103.214 -0.00129816 + endloop + endfacet + facet normal 5.40673e-05 0.000203852 -1 + outer loop + vertex -603.078 101.974 -0.00171576 + vertex -600.027 103.214 -0.00129816 + vertex -593.498 99.1909 -0.00176516 + endloop + endfacet + facet normal 5.46274e-05 0.000204761 -1 + outer loop + vertex -593.498 99.1909 -0.00176516 + vertex -600.027 103.214 -0.00129816 + vertex -590.514 100.427 -0.00134901 + endloop + endfacet + facet normal 5.10185e-05 0.000192439 -1 + outer loop + vertex -600.027 103.214 -0.00129816 + vertex -596.894 104.325 -0.000924487 + vertex -590.514 100.427 -0.00134901 + endloop + endfacet + facet normal 5.47085e-05 0.000182036 -1 + outer loop + vertex -600.027 103.214 -0.00129816 + vertex -607.803 107.843 -0.000880783 + vertex -596.894 104.325 -0.000924487 + endloop + endfacet + facet normal 5.19029e-05 0.000173337 -1 + outer loop + vertex -607.803 107.843 -0.000880783 + vertex -604.527 108.862 -0.000534267 + vertex -596.894 104.325 -0.000924487 + endloop + endfacet + facet normal 5.17802e-05 0.000173131 -1 + outer loop + vertex -596.894 104.325 -0.000924487 + vertex -604.527 108.862 -0.000534267 + vertex -593.695 105.361 -0.000579429 + endloop + endfacet + facet normal 4.81018e-05 0.000184493 -1 + outer loop + vertex -596.894 104.325 -0.000924487 + vertex -593.695 105.361 -0.000579429 + vertex -587.459 101.541 -0.000984211 + endloop + endfacet + facet normal 4.76601e-05 0.000183772 -1 + outer loop + vertex -587.459 101.541 -0.000984211 + vertex -593.695 105.361 -0.000579429 + vertex -584.304 102.567 -0.000645393 + endloop + endfacet + facet normal 3.65161e-05 0.000146322 -1 + outer loop + vertex -593.695 105.361 -0.000579429 + vertex -590.459 106.33 -0.000319436 + vertex -584.304 102.567 -0.000645393 + endloop + endfacet + facet normal 3.9928e-05 0.000134935 -1 + outer loop + vertex -593.695 105.361 -0.000579429 + vertex -601.208 109.813 -0.000278744 + vertex -590.459 106.33 -0.000319436 + endloop + endfacet + facet normal 2.34785e-05 8.41588e-05 -1 + outer loop + vertex -601.208 109.813 -0.000278744 + vertex -597.946 110.708 -0.000126816 + vertex -590.459 106.33 -0.000319436 + endloop + endfacet + facet normal 2.51124e-05 8.69533e-05 -1 + outer loop + vertex -590.459 106.33 -0.000319436 + vertex -597.946 110.708 -0.000126816 + vertex -587.329 107.264 -0.00015962 + endloop + endfacet + facet normal 2.22939e-05 9.64004e-05 -1 + outer loop + vertex -590.459 106.33 -0.000319436 + vertex -587.329 107.264 -0.00015962 + vertex -581.179 103.553 -0.000380247 + endloop + endfacet + facet normal 2.63839e-05 0.000103178 -1 + outer loop + vertex -581.179 103.553 -0.000380247 + vertex -587.329 107.264 -0.00015962 + vertex -578.076 104.479 -0.000202919 + endloop + endfacet + facet normal 1.23006e-05 5.64003e-05 -1 + outer loop + vertex -587.329 107.264 -0.00015962 + vertex -584.2 108.12 -7.28562e-05 + vertex -578.076 104.479 -0.000202919 + endloop + endfacet + facet normal 1.4205e-05 4.94373e-05 -1 + outer loop + vertex -587.329 107.264 -0.00015962 + vertex -594.812 111.561 -5.35164e-05 + vertex -584.2 108.12 -7.28562e-05 + endloop + endfacet + facet normal 5.03822e-06 2.11619e-05 -1 + outer loop + vertex -594.812 111.561 -5.35164e-05 + vertex -591.601 112.324 -2.11782e-05 + vertex -584.2 108.12 -7.28562e-05 + endloop + endfacet + facet normal 6.92528e-06 2.4484e-05 -1 + outer loop + vertex -584.2 108.12 -7.28562e-05 + vertex -591.601 112.324 -2.11782e-05 + vertex -580.785 108.841 -3.15548e-05 + endloop + endfacet + facet normal 5.80133e-06 2.98081e-05 -1 + outer loop + vertex -584.2 108.12 -7.28562e-05 + vertex -580.785 108.841 -3.15548e-05 + vertex -574.881 105.314 -0.00010243 + endloop + endfacet + facet normal 8.81595e-06 3.48543e-05 -1 + outer loop + vertex -574.881 105.314 -0.00010243 + vertex -580.785 108.841 -3.15548e-05 + vertex -571.341 106 -4.73401e-05 + endloop + endfacet + facet normal 2.04525e-06 9.33015e-06 -1 + outer loop + vertex -591.601 112.324 -2.11782e-05 + vertex -588 112.951 -7.96299e-06 + vertex -580.785 108.841 -3.15548e-05 + endloop + endfacet + facet normal 3.18256e-06 1.13266e-05 -1 + outer loop + vertex -580.785 108.841 -3.15548e-05 + vertex -588 112.951 -7.96299e-06 + vertex -576.779 109.384 -1.2657e-05 + endloop + endfacet + facet normal 2.31468e-06 7.783e-06 -1 + outer loop + vertex -591.601 112.324 -2.11782e-05 + vertex -599.114 116.651 -4.89268e-06 + vertex -588 112.951 -7.96299e-06 + endloop + endfacet + facet normal 5.25257e-07 2.40771e-06 -1 + outer loop + vertex -599.114 116.651 -4.89268e-06 + vertex -595.608 117.275 -1.54829e-06 + vertex -588 112.951 -7.96299e-06 + endloop + endfacet + facet normal 9.37052e-07 3.13228e-06 -1 + outer loop + vertex -588 112.951 -7.96299e-06 + vertex -595.608 117.275 -1.54829e-06 + vertex -584.337 113.574 -2.57903e-06 + endloop + endfacet + facet normal 2.50089e-07 1.04015e-06 -1 + outer loop + vertex -595.608 117.275 -1.54829e-06 + vertex -593.093 118.159 -8.14509e-14 + vertex -584.337 113.574 -2.57903e-06 + endloop + endfacet + facet normal 3.04268e-07 8.85922e-07 -1 + outer loop + vertex -595.608 117.275 -1.54829e-06 + vertex -603.196 121.629 -8.11086e-14 + vertex -593.093 118.159 -8.14509e-14 + endloop + endfacet + facet normal 1.55783e-07 6.27139e-07 -1 + outer loop + vertex -606.281 120.939 -9.1335e-07 + vertex -603.196 121.629 -8.11086e-14 + vertex -595.608 117.275 -1.54829e-06 + endloop + endfacet + facet normal 1.817e-07 5.11271e-07 -1 + outer loop + vertex -606.281 120.939 -9.1335e-07 + vertex -613.228 125.194 -8.07568e-14 + vertex -603.196 121.629 -8.11086e-14 + endloop + endfacet + facet normal 1.07402e-07 3.89977e-07 -1 + outer loop + vertex -616.514 124.59 -5.88605e-07 + vertex -613.228 125.194 -8.07568e-14 + vertex -606.281 120.939 -9.1335e-07 + endloop + endfacet + facet normal 4.43557e-07 1.33216e-06 -1 + outer loop + vertex -609.625 120.288 -3.26363e-06 + vertex -616.514 124.59 -5.88605e-07 + vertex -606.281 120.939 -9.1335e-07 + endloop + endfacet + facet normal 3.94029e-07 1.58667e-06 -1 + outer loop + vertex -609.625 120.288 -3.26363e-06 + vertex -606.281 120.939 -9.1335e-07 + vertex -599.114 116.651 -4.89268e-06 + endloop + endfacet + facet normal 1.75632e-06 5.52379e-06 -1 + outer loop + vertex -602.432 115.967 -1.44979e-05 + vertex -609.625 120.288 -3.26363e-06 + vertex -599.114 116.651 -4.89268e-06 + endloop + endfacet + facet normal 1.33476e-06 4.82202e-06 -1 + outer loop + vertex -612.837 119.579 -1.09705e-05 + vertex -609.625 120.288 -3.26363e-06 + vertex -602.432 115.967 -1.44979e-05 + endloop + endfacet + facet normal 4.86233e-06 1.49847e-05 -1 + outer loop + vertex -605.592 115.199 -4.13779e-05 + vertex -612.837 119.579 -1.09705e-05 + vertex -602.432 115.967 -1.44979e-05 + endloop + endfacet + facet normal 4.47229e-06 1.65881e-05 -1 + outer loop + vertex -605.592 115.199 -4.13779e-05 + vertex -602.432 115.967 -1.44979e-05 + vertex -594.812 111.561 -5.35164e-05 + endloop + endfacet + facet normal 1.24453e-05 4.02126e-05 -1 + outer loop + vertex -597.946 110.708 -0.000126816 + vertex -605.592 115.199 -4.13779e-05 + vertex -594.812 111.561 -5.35164e-05 + endloop + endfacet + facet normal 1.11667e-05 3.80358e-05 -1 + outer loop + vertex -608.845 114.385 -0.00010865 + vertex -605.592 115.199 -4.13779e-05 + vertex -597.946 110.708 -0.000126816 + endloop + endfacet + facet normal 1.17362e-05 3.57584e-05 -1 + outer loop + vertex -608.845 114.385 -0.00010865 + vertex -616.093 118.839 -3.4428e-05 + vertex -605.592 115.199 -4.13779e-05 + endloop + endfacet + facet normal 1.10193e-05 3.4592e-05 -1 + outer loop + vertex -619.475 118.067 -9.84294e-05 + vertex -616.093 118.839 -3.4428e-05 + vertex -608.845 114.385 -0.00010865 + endloop + endfacet + facet normal 2.42573e-05 7.28138e-05 -1 + outer loop + vertex -612.218 113.524 -0.000253165 + vertex -619.475 118.067 -9.84294e-05 + vertex -608.845 114.385 -0.00010865 + endloop + endfacet + facet normal 2.33803e-05 7.62475e-05 -1 + outer loop + vertex -612.218 113.524 -0.000253165 + vertex -608.845 114.385 -0.00010865 + vertex -601.208 109.813 -0.000278744 + endloop + endfacet + facet normal 4.05481e-05 0.000127174 -1 + outer loop + vertex -604.527 108.862 -0.000534267 + vertex -612.218 113.524 -0.000253165 + vertex -601.208 109.813 -0.000278744 + endloop + endfacet + facet normal 4.0328e-05 0.000126811 -1 + outer loop + vertex -615.611 112.598 -0.000507387 + vertex -612.218 113.524 -0.000253165 + vertex -604.527 108.862 -0.000534267 + endloop + endfacet + facet normal 4.14325e-05 0.000122762 -1 + outer loop + vertex -615.611 112.598 -0.000507387 + vertex -622.929 117.235 -0.000241415 + vertex -612.218 113.524 -0.000253165 + endloop + endfacet + facet normal 4.20002e-05 0.000123658 -1 + outer loop + vertex -626.377 116.331 -0.000497982 + vertex -622.929 117.235 -0.000241415 + vertex -615.611 112.598 -0.000507387 + endloop + endfacet + facet normal 5.57382e-05 0.000163281 -1 + outer loop + vertex -618.943 111.6 -0.000856216 + vertex -626.377 116.331 -0.000497982 + vertex -615.611 112.598 -0.000507387 + endloop + endfacet + facet normal 5.4378e-05 0.000167819 -1 + outer loop + vertex -618.943 111.6 -0.000856216 + vertex -615.611 112.598 -0.000507387 + vertex -607.803 107.843 -0.000880783 + endloop + endfacet + facet normal 5.71626e-05 0.000176078 -1 + outer loop + vertex -610.981 106.738 -0.0012571 + vertex -618.943 111.6 -0.000856216 + vertex -607.803 107.843 -0.000880783 + endloop + endfacet + facet normal 5.81585e-05 0.000177709 -1 + outer loop + vertex -622.182 110.515 -0.00123739 + vertex -618.943 111.6 -0.000856216 + vertex -610.981 106.738 -0.0012571 + endloop + endfacet + facet normal 5.97284e-05 0.000173023 -1 + outer loop + vertex -622.182 110.515 -0.00123739 + vertex -629.759 115.35 -0.000853249 + vertex -618.943 111.6 -0.000856216 + endloop + endfacet + facet normal 6.11756e-05 0.00017529 -1 + outer loop + vertex -633.058 114.284 -0.00124195 + vertex -629.759 115.35 -0.000853249 + vertex -622.182 110.515 -0.00123739 + endloop + endfacet + facet normal 6.69233e-05 0.000191873 -1 + outer loop + vertex -625.34 109.32 -0.00167799 + vertex -633.058 114.284 -0.00124195 + vertex -622.182 110.515 -0.00123739 + endloop + endfacet + facet normal 6.56104e-05 0.000195343 -1 + outer loop + vertex -625.34 109.32 -0.00167799 + vertex -622.182 110.515 -0.00123739 + vertex -614.082 105.523 -0.00168104 + endloop + endfacet + facet normal 6.6647e-05 0.000191444 -1 + outer loop + vertex -636.282 113.11 -0.00168169 + vertex -633.058 114.284 -0.00124195 + vertex -625.34 109.32 -0.00167799 + endloop + endfacet + facet normal 0.000119384 0.000343704 -1 + outer loop + vertex -628.447 107.975 -0.00251101 + vertex -636.282 113.11 -0.00168169 + vertex -625.34 109.32 -0.00167799 + endloop + endfacet + facet normal 0.000118695 0.000345297 -1 + outer loop + vertex -628.447 107.975 -0.00251101 + vertex -625.34 109.32 -0.00167799 + vertex -617.137 104.161 -0.00248577 + endloop + endfacet + facet normal 0.000231877 0.000680867 -1 + outer loop + vertex -620.142 102.587 -0.00425394 + vertex -628.447 107.975 -0.00251101 + vertex -617.137 104.161 -0.00248577 + endloop + endfacet + facet normal 0.000246419 0.000703281 -1 + outer loop + vertex -631.514 106.421 -0.00435983 + vertex -628.447 107.975 -0.00251101 + vertex -620.142 102.587 -0.00425394 + endloop + endfacet + facet normal 0.000245685 0.00070473 -1 + outer loop + vertex -631.514 106.421 -0.00435983 + vertex -639.442 111.78 -0.00253135 + vertex -628.447 107.975 -0.00251101 + endloop + endfacet + facet normal 0.000244177 0.000702499 -1 + outer loop + vertex -642.566 110.245 -0.00437252 + vertex -639.442 111.78 -0.00253135 + vertex -631.514 106.421 -0.00435983 + endloop + endfacet + facet normal 0.000342304 0.000986147 -0.999999 + outer loop + vertex -634.518 104.592 -0.00719143 + vertex -642.566 110.245 -0.00437252 + vertex -631.514 106.421 -0.00435983 + endloop + endfacet + facet normal 0.000346934 0.000978542 -0.999999 + outer loop + vertex -634.518 104.592 -0.00719143 + vertex -631.514 106.421 -0.00435983 + vertex -623.09 100.731 -0.00700521 + endloop + endfacet + facet normal 0.000333061 0.000972985 -0.999999 + outer loop + vertex -645.625 108.437 -0.00714957 + vertex -642.566 110.245 -0.00437252 + vertex -634.518 104.592 -0.00719143 + endloop + endfacet + facet normal 0.000146428 0.000433866 -1 + outer loop + vertex -637.404 102.434 -0.00855055 + vertex -645.625 108.437 -0.00714957 + vertex -634.518 104.592 -0.00719143 + endloop + endfacet + facet normal 0.000159137 0.000416877 -1 + outer loop + vertex -637.404 102.434 -0.00855055 + vertex -634.518 104.592 -0.00719143 + vertex -625.917 98.5381 -0.00834659 + endloop + endfacet + facet normal 0.000114765 0.000390509 -1 + outer loop + vertex -648.568 106.306 -0.00831957 + vertex -645.625 108.437 -0.00714957 + vertex -637.404 102.434 -0.00855055 + endloop + endfacet + facet normal -0.000628498 -0.00175228 -0.999998 + outer loop + vertex -640.09 99.9116 -0.00244271 + vertex -648.568 106.306 -0.00831957 + vertex -637.404 102.434 -0.00855055 + endloop + endfacet + facet normal -0.000590432 -0.00179283 -0.999998 + outer loop + vertex -640.09 99.9116 -0.00244271 + vertex -637.404 102.434 -0.00855055 + vertex -628.55 95.9881 -0.00222225 + endloop + endfacet + facet normal -0.00194101 -0.00576526 -0.999981 + outer loop + vertex -630.915 93.0882 0.0190883 + vertex -640.09 99.9116 -0.00244271 + vertex -628.55 95.9881 -0.00222225 + endloop + endfacet + facet normal -0.00169902 -0.00543989 -0.999984 + outer loop + vertex -642.52 97.0413 0.0173002 + vertex -640.09 99.9116 -0.00244271 + vertex -630.915 93.0882 0.0190883 + endloop + endfacet + facet normal -0.0018476 -0.00531411 -0.999984 + outer loop + vertex -642.52 97.0413 0.0173002 + vertex -651.329 103.823 -0.00246585 + vertex -640.09 99.9116 -0.00244271 + endloop + endfacet + facet normal -0.00176764 -0.00521026 -0.999985 + outer loop + vertex -653.809 100.978 0.0167436 + vertex -651.329 103.823 -0.00246585 + vertex -642.52 97.0413 0.0173002 + endloop + endfacet + facet normal -0.00352479 -0.010249 -0.999941 + outer loop + vertex -644.59 93.8383 0.0574279 + vertex -653.809 100.978 0.0167436 + vertex -642.52 97.0413 0.0173002 + endloop + endfacet + facet normal -0.00318076 -0.0104714 -0.99994 + outer loop + vertex -644.59 93.8383 0.0574279 + vertex -642.52 97.0413 0.0173002 + vertex -632.954 89.8686 0.0619849 + endloop + endfacet + facet normal -0.00327211 -0.0099228 -0.999945 + outer loop + vertex -655.913 97.7891 0.0552738 + vertex -653.809 100.978 0.0167436 + vertex -644.59 93.8383 0.0574279 + endloop + endfacet + facet normal -0.00613417 -0.0181252 -0.999817 + outer loop + vertex -646.272 90.3484 0.131009 + vertex -655.913 97.7891 0.0552738 + vertex -644.59 93.8383 0.0574279 + endloop + endfacet + facet normal -0.00562019 -0.0183727 -0.999815 + outer loop + vertex -646.272 90.3484 0.131009 + vertex -644.59 93.8383 0.0574279 + vertex -634.661 86.3882 0.138515 + endloop + endfacet + facet normal -0.00586843 -0.0177809 -0.999825 + outer loop + vertex -657.599 94.2917 0.127368 + vertex -655.913 97.7891 0.0552738 + vertex -646.272 90.3484 0.131009 + endloop + endfacet + facet normal -0.0115805 -0.0341891 -0.999348 + outer loop + vertex -647.675 86.6202 0.274823 + vertex -657.599 94.2917 0.127368 + vertex -646.272 90.3484 0.131009 + endloop + endfacet + facet normal -0.0107091 -0.0345172 -0.999347 + outer loop + vertex -647.675 86.6202 0.274823 + vertex -646.272 90.3484 0.131009 + vertex -636.117 82.6928 0.28661 + endloop + endfacet + facet normal -0.0219279 -0.0675295 -0.997476 + outer loop + vertex -637.601 78.8222 0.581281 + vertex -647.675 86.6202 0.274823 + vertex -636.117 82.6928 0.28661 + endloop + endfacet + facet normal -0.0222287 -0.0679168 -0.997443 + outer loop + vertex -649.099 82.7025 0.573304 + vertex -647.675 86.6202 0.274823 + vertex -637.601 78.8222 0.581281 + endloop + endfacet + facet normal -0.0386364 -0.116525 -0.992436 + outer loop + vertex -639.437 74.8135 1.12342 + vertex -649.099 82.7025 0.573304 + vertex -637.601 78.8222 0.581281 + endloop + endfacet + facet normal -0.0371797 -0.117189 -0.992413 + outer loop + vertex -639.437 74.8135 1.12342 + vertex -637.601 78.8222 0.581281 + vertex -628.028 71.1151 1.13273 + endloop + endfacet + facet normal -0.0378969 -0.11807 -0.992282 + outer loop + vertex -628.028 71.1151 1.13273 + vertex -637.601 78.8222 0.581281 + vertex -626.324 75.1774 0.584281 + endloop + endfacet + facet normal -0.0388917 -0.116834 -0.99239 + outer loop + vertex -650.828 78.6382 1.11958 + vertex -649.099 82.7025 0.573304 + vertex -639.437 74.8135 1.12342 + endloop + endfacet + facet normal -0.0396613 -0.116508 -0.992398 + outer loop + vertex -650.828 78.6382 1.11958 + vertex -660.34 86.5802 0.567327 + vertex -649.099 82.7025 0.573304 + endloop + endfacet + facet normal -0.0223884 -0.0664417 -0.997539 + outer loop + vertex -660.34 86.5802 0.567327 + vertex -658.981 90.5364 0.273327 + vertex -649.099 82.7025 0.573304 + endloop + endfacet + facet normal -0.0235826 -0.0660315 -0.997539 + outer loop + vertex -660.34 86.5802 0.567327 + vertex -670.071 94.4664 0.275362 + vertex -658.981 90.5364 0.273327 + endloop + endfacet + facet normal -0.0123538 -0.0343437 -0.999334 + outer loop + vertex -670.071 94.4664 0.275362 + vertex -668.665 98.221 0.128936 + vertex -658.981 90.5364 0.273327 + endloop + endfacet + facet normal -0.0123235 -0.0343056 -0.999335 + outer loop + vertex -658.981 90.5364 0.273327 + vertex -668.665 98.221 0.128936 + vertex -657.599 94.2917 0.127368 + endloop + endfacet + facet normal -0.00639145 -0.0176001 -0.999825 + outer loop + vertex -668.665 98.221 0.128936 + vertex -666.942 101.712 0.0564716 + vertex -657.599 94.2917 0.127368 + endloop + endfacet + facet normal -0.00658624 -0.017504 -0.999825 + outer loop + vertex -668.665 98.221 0.128936 + vertex -677.898 105.729 0.0583069 + vertex -666.942 101.712 0.0564716 + endloop + endfacet + facet normal -0.003675 -0.00956497 -0.999948 + outer loop + vertex -677.898 105.729 0.0583069 + vertex -675.681 108.88 0.0200259 + vertex -666.942 101.712 0.0564716 + endloop + endfacet + facet normal -0.00371124 -0.00960915 -0.999947 + outer loop + vertex -666.942 101.712 0.0564716 + vertex -675.681 108.88 0.0200259 + vertex -664.79 104.886 0.0179893 + endloop + endfacet + facet normal -0.00356239 -0.00971005 -0.999947 + outer loop + vertex -666.942 101.712 0.0564716 + vertex -664.79 104.886 0.0179893 + vertex -655.913 97.7891 0.0552738 + endloop + endfacet + facet normal -0.00210036 -0.00521693 -0.999984 + outer loop + vertex -675.681 108.88 0.0200259 + vertex -673.092 111.684 -4.43638e-05 + vertex -664.79 104.886 0.0179893 + endloop + endfacet + facet normal -0.00199617 -0.00508972 -0.999985 + outer loop + vertex -664.79 104.886 0.0179893 + vertex -673.092 111.684 -4.43638e-05 + vertex -662.256 107.71 -0.00144437 + endloop + endfacet + facet normal -0.00194186 -0.00513846 -0.999985 + outer loop + vertex -664.79 104.886 0.0179893 + vertex -662.256 107.71 -0.00144437 + vertex -653.809 100.978 0.0167436 + endloop + endfacet + facet normal -0.000814631 -0.00186861 -0.999998 + outer loop + vertex -673.092 111.684 -4.43638e-05 + vertex -670.219 114.126 -0.00694629 + vertex -662.256 107.71 -0.00144437 + endloop + endfacet + facet normal -0.000711218 -0.00174026 -0.999998 + outer loop + vertex -662.256 107.71 -0.00144437 + vertex -670.219 114.126 -0.00694629 + vertex -659.438 110.17 -0.00773031 + endloop + endfacet + facet normal -0.000712071 -0.00173928 -0.999998 + outer loop + vertex -662.256 107.71 -0.00144437 + vertex -659.438 110.17 -0.00773031 + vertex -651.329 103.823 -0.00246585 + endloop + endfacet + facet normal -0.000639503 -0.00164656 -0.999998 + outer loop + vertex -651.329 103.823 -0.00246585 + vertex -659.438 110.17 -0.00773031 + vertex -648.568 106.306 -0.00831957 + endloop + endfacet + facet normal 5.59e-05 0.000309754 -1 + outer loop + vertex -659.438 110.17 -0.00773031 + vertex -656.439 112.28 -0.00690903 + vertex -648.568 106.306 -0.00831957 + endloop + endfacet + facet normal 7.55875e-05 0.000281767 -1 + outer loop + vertex -659.438 110.17 -0.00773031 + vertex -667.165 116.217 -0.00661044 + vertex -656.439 112.28 -0.00690903 + endloop + endfacet + facet normal 0.000272362 0.000817846 -1 + outer loop + vertex -667.165 116.217 -0.00661044 + vertex -664 117.991 -0.00429801 + vertex -656.439 112.28 -0.00690903 + endloop + endfacet + facet normal 0.00032534 0.000887994 -1 + outer loop + vertex -656.439 112.28 -0.00690903 + vertex -664 117.991 -0.00429801 + vertex -653.326 114.069 -0.00430804 + endloop + endfacet + facet normal 0.000305561 0.000922421 -1 + outer loop + vertex -656.439 112.28 -0.00690903 + vertex -653.326 114.069 -0.00430804 + vertex -645.625 108.437 -0.00714957 + endloop + endfacet + facet normal 0.00022702 0.000620409 -1 + outer loop + vertex -664 117.991 -0.00429801 + vertex -660.773 119.495 -0.00263199 + vertex -653.326 114.069 -0.00430804 + endloop + endfacet + facet normal 0.000246822 0.000647583 -1 + outer loop + vertex -653.326 114.069 -0.00430804 + vertex -660.773 119.495 -0.00263199 + vertex -650.148 115.587 -0.00254079 + endloop + endfacet + facet normal 0.000233841 0.000674755 -1 + outer loop + vertex -653.326 114.069 -0.00430804 + vertex -650.148 115.587 -0.00254079 + vertex -642.566 110.245 -0.00437252 + endloop + endfacet + facet normal 0.000125013 0.000316481 -1 + outer loop + vertex -660.773 119.495 -0.00263199 + vertex -657.502 120.79 -0.00181326 + vertex -650.148 115.587 -0.00254079 + endloop + endfacet + facet normal 0.00012414 0.000315247 -1 + outer loop + vertex -650.148 115.587 -0.00254079 + vertex -657.502 120.79 -0.00181326 + vertex -646.926 116.897 -0.0017278 + endloop + endfacet + facet normal 0.000118191 0.000329876 -1 + outer loop + vertex -650.148 115.587 -0.00254079 + vertex -646.926 116.897 -0.0017278 + vertex -639.442 111.78 -0.00253135 + endloop + endfacet + facet normal 0.000125517 0.00034059 -1 + outer loop + vertex -639.442 111.78 -0.00253135 + vertex -646.926 116.897 -0.0017278 + vertex -636.282 113.11 -0.00168169 + endloop + endfacet + facet normal 7.12899e-05 0.000188185 -1 + outer loop + vertex -646.926 116.897 -0.0017278 + vertex -643.65 118.056 -0.00127615 + vertex -636.282 113.11 -0.00168169 + endloop + endfacet + facet normal 7.35083e-05 0.000181914 -1 + outer loop + vertex -646.926 116.897 -0.0017278 + vertex -654.17 121.93 -0.00134465 + vertex -643.65 118.056 -0.00127615 + endloop + endfacet + facet normal 7.27268e-05 0.000179792 -1 + outer loop + vertex -654.17 121.93 -0.00134465 + vertex -650.756 122.958 -0.000911556 + vertex -643.65 118.056 -0.00127615 + endloop + endfacet + facet normal 6.68861e-05 0.000171326 -1 + outer loop + vertex -643.65 118.056 -0.00127615 + vertex -650.756 122.958 -0.000911556 + vertex -640.293 119.103 -0.000872149 + endloop + endfacet + facet normal 6.56484e-05 0.000175295 -1 + outer loop + vertex -643.65 118.056 -0.00127615 + vertex -640.293 119.103 -0.000872149 + vertex -633.058 114.284 -0.00124195 + endloop + endfacet + facet normal 6.59154e-05 0.000168692 -1 + outer loop + vertex -650.756 122.958 -0.000911556 + vertex -647.258 123.899 -0.000522339 + vertex -640.293 119.103 -0.000872149 + endloop + endfacet + facet normal 6.15366e-05 0.000162331 -1 + outer loop + vertex -640.293 119.103 -0.000872149 + vertex -647.258 123.899 -0.000522339 + vertex -636.85 120.064 -0.000504399 + endloop + endfacet + facet normal 6.06987e-05 0.000165335 -1 + outer loop + vertex -640.293 119.103 -0.000872149 + vertex -636.85 120.064 -0.000504399 + vertex -629.759 115.35 -0.000853249 + endloop + endfacet + facet normal 5.81927e-05 0.000161565 -1 + outer loop + vertex -629.759 115.35 -0.000853249 + vertex -636.85 120.064 -0.000504399 + vertex -626.377 116.331 -0.000497982 + endloop + endfacet + facet normal 4.43552e-05 0.000122738 -1 + outer loop + vertex -636.85 120.064 -0.000504399 + vertex -633.353 120.948 -0.000240727 + vertex -626.377 116.331 -0.000497982 + endloop + endfacet + facet normal 4.49442e-05 0.000120409 -1 + outer loop + vertex -636.85 120.064 -0.000504399 + vertex -643.708 124.763 -0.000246752 + vertex -633.353 120.948 -0.000240727 + endloop + endfacet + facet normal 2.67621e-05 7.1059e-05 -1 + outer loop + vertex -643.708 124.763 -0.000246752 + vertex -640.151 125.554 -9.53503e-05 + vertex -633.353 120.948 -0.000240727 + endloop + endfacet + facet normal 2.55873e-05 6.93252e-05 -1 + outer loop + vertex -633.353 120.948 -0.000240727 + vertex -640.151 125.554 -9.53503e-05 + vertex -629.845 121.759 -9.47717e-05 + endloop + endfacet + facet normal 2.52103e-05 7.09564e-05 -1 + outer loop + vertex -633.353 120.948 -0.000240727 + vertex -629.845 121.759 -9.47717e-05 + vertex -622.929 117.235 -0.000241415 + endloop + endfacet + facet normal 2.45489e-05 6.99452e-05 -1 + outer loop + vertex -622.929 117.235 -0.000241415 + vertex -629.845 121.759 -9.47717e-05 + vertex -619.475 118.067 -9.84294e-05 + endloop + endfacet + facet normal 1.12241e-05 3.25177e-05 -1 + outer loop + vertex -629.845 121.759 -9.47717e-05 + vertex -626.371 122.501 -3.16355e-05 + vertex -619.475 118.067 -9.84294e-05 + endloop + endfacet + facet normal 1.14749e-05 3.13436e-05 -1 + outer loop + vertex -629.845 121.759 -9.47717e-05 + vertex -636.619 126.275 -3.09312e-05 + vertex -626.371 122.501 -3.16355e-05 + endloop + endfacet + facet normal 4.19997e-06 1.15905e-05 -1 + outer loop + vertex -636.619 126.275 -3.09312e-05 + vertex -633.126 126.942 -8.53885e-06 + vertex -626.371 122.501 -3.16355e-05 + endloop + endfacet + facet normal 4.24959e-06 1.16659e-05 -1 + outer loop + vertex -626.371 122.501 -3.16355e-05 + vertex -633.126 126.942 -8.53885e-06 + vertex -622.983 123.201 -9.07665e-06 + endloop + endfacet + facet normal 4.11551e-06 1.2315e-05 -1 + outer loop + vertex -626.371 122.501 -3.16355e-05 + vertex -622.983 123.201 -9.07665e-06 + vertex -616.093 118.839 -3.4428e-05 + endloop + endfacet + facet normal 4.331e-06 1.26555e-05 -1 + outer loop + vertex -616.093 118.839 -3.4428e-05 + vertex -622.983 123.201 -9.07665e-06 + vertex -612.837 119.579 -1.09705e-05 + endloop + endfacet + facet normal 1.21586e-06 3.9289e-06 -1 + outer loop + vertex -622.983 123.201 -9.07665e-06 + vertex -619.712 123.894 -2.37451e-06 + vertex -612.837 119.579 -1.09705e-05 + endloop + endfacet + facet normal 1.28962e-06 3.581e-06 -1 + outer loop + vertex -622.983 123.201 -9.07665e-06 + vertex -629.722 127.595 -2.0297e-06 + vertex -619.712 123.894 -2.37451e-06 + endloop + endfacet + facet normal 3.02268e-07 9.10666e-07 -1 + outer loop + vertex -629.722 127.595 -2.0297e-06 + vertex -626.521 128.293 -4.27515e-07 + vertex -619.712 123.894 -2.37451e-06 + endloop + endfacet + facet normal 3.45742e-07 9.77973e-07 -1 + outer loop + vertex -619.712 123.894 -2.37451e-06 + vertex -626.521 128.293 -4.27515e-07 + vertex -616.514 124.59 -5.88605e-07 + endloop + endfacet + facet normal 8.05589e-08 2.61239e-07 -1 + outer loop + vertex -626.521 128.293 -4.27515e-07 + vertex -623.751 129.075 -8.0374e-14 + vertex -616.514 124.59 -5.88605e-07 + endloop + endfacet + facet normal 8.88529e-08 2.31863e-07 -1 + outer loop + vertex -626.521 128.293 -4.27515e-07 + vertex -633.578 132.841 -8.00024e-14 + vertex -623.751 129.075 -8.0374e-14 + endloop + endfacet + facet normal 7.75013e-08 2.1425e-07 -1 + outer loop + vertex -636.529 132.136 -3.79589e-07 + vertex -633.578 132.841 -8.00024e-14 + vertex -626.521 128.293 -4.27515e-07 + endloop + endfacet + facet normal 8.04783e-08 2.01778e-07 -1 + outer loop + vertex -636.529 132.136 -3.79589e-07 + vertex -643.948 136.976 -7.95944e-14 + vertex -633.578 132.841 -8.00024e-14 + endloop + endfacet + facet normal 7.4755e-08 1.93005e-07 -1 + outer loop + vertex -646.568 136.14 -3.57353e-07 + vertex -643.948 136.976 -7.95944e-14 + vertex -636.529 132.136 -3.79589e-07 + endloop + endfacet + facet normal 3.11344e-07 7.86261e-07 -1 + outer loop + vertex -639.821 131.466 -1.93142e-06 + vertex -646.568 136.14 -3.57353e-07 + vertex -636.529 132.136 -3.79589e-07 + endloop + endfacet + facet normal 3.04504e-07 8.19874e-07 -1 + outer loop + vertex -639.821 131.466 -1.93142e-06 + vertex -636.529 132.136 -3.79589e-07 + vertex -629.722 127.595 -2.0297e-06 + endloop + endfacet + facet normal 1.27056e-06 3.34043e-06 -1 + outer loop + vertex -633.126 126.942 -8.53885e-06 + vertex -639.821 131.466 -1.93142e-06 + vertex -629.722 127.595 -2.0297e-06 + endloop + endfacet + facet normal 1.24617e-06 3.30434e-06 -1 + outer loop + vertex -643.34 130.849 -8.35414e-06 + vertex -639.821 131.466 -1.93142e-06 + vertex -633.126 126.942 -8.53885e-06 + endloop + endfacet + facet normal 1.26647e-06 3.1886e-06 -1 + outer loop + vertex -643.34 130.849 -8.35414e-06 + vertex -649.944 135.497 -1.89905e-06 + vertex -639.821 131.466 -1.93142e-06 + endloop + endfacet + facet normal 1.33375e-06 3.28421e-06 -1 + outer loop + vertex -653.532 134.909 -8.61437e-06 + vertex -649.944 135.497 -1.89905e-06 + vertex -643.34 130.849 -8.35414e-06 + endloop + endfacet + facet normal 4.47454e-06 1.11689e-05 -1 + outer loop + vertex -646.896 130.208 -3.14324e-05 + vertex -653.532 134.909 -8.61437e-06 + vertex -643.34 130.849 -8.35414e-06 + endloop + endfacet + facet normal 4.42586e-06 1.14389e-05 -1 + outer loop + vertex -646.896 130.208 -3.14324e-05 + vertex -643.34 130.849 -8.35414e-06 + vertex -636.619 126.275 -3.09312e-05 + endloop + endfacet + facet normal 1.19092e-05 3.09955e-05 -1 + outer loop + vertex -640.151 125.554 -9.53503e-05 + vertex -646.896 130.208 -3.14324e-05 + vertex -636.619 126.275 -3.09312e-05 + endloop + endfacet + facet normal 1.25617e-05 3.19413e-05 -1 + outer loop + vertex -650.476 129.506 -9.88097e-05 + vertex -646.896 130.208 -3.14324e-05 + vertex -640.151 125.554 -9.53503e-05 + endloop + endfacet + facet normal 1.26478e-05 3.15023e-05 -1 + outer loop + vertex -650.476 129.506 -9.88097e-05 + vertex -657.136 134.288 -3.24178e-05 + vertex -646.896 130.208 -3.14324e-05 + endloop + endfacet + facet normal 1.29605e-05 3.19378e-05 -1 + outer loop + vertex -660.768 133.607 -0.000101244 + vertex -657.136 134.288 -3.24178e-05 + vertex -650.476 129.506 -9.88097e-05 + endloop + endfacet + facet normal 2.8416e-05 7.07324e-05 -1 + outer loop + vertex -654.086 128.735 -0.000255923 + vertex -660.768 133.607 -0.000101244 + vertex -650.476 129.506 -9.88097e-05 + endloop + endfacet + facet normal 2.82518e-05 7.15013e-05 -1 + outer loop + vertex -654.086 128.735 -0.000255923 + vertex -650.476 129.506 -9.88097e-05 + vertex -643.708 124.763 -0.000246752 + endloop + endfacet + facet normal 4.77852e-05 0.000122534 -1 + outer loop + vertex -647.258 123.899 -0.000522339 + vertex -654.086 128.735 -0.000255923 + vertex -643.708 124.763 -0.000246752 + endloop + endfacet + facet normal 5.07272e-05 0.000126687 -1 + outer loop + vertex -657.693 127.892 -0.000545744 + vertex -654.086 128.735 -0.000255923 + vertex -647.258 123.899 -0.000522339 + endloop + endfacet + facet normal 5.09307e-05 0.000125817 -1 + outer loop + vertex -657.693 127.892 -0.000545744 + vertex -664.434 132.858 -0.00026428 + vertex -654.086 128.735 -0.000255923 + endloop + endfacet + facet normal 5.40941e-05 0.000130111 -1 + outer loop + vertex -668.098 132.038 -0.000569226 + vertex -664.434 132.858 -0.00026428 + vertex -657.693 127.892 -0.000545744 + endloop + endfacet + facet normal 7.21472e-05 0.000175424 -1 + outer loop + vertex -661.247 126.973 -0.000963364 + vertex -668.098 132.038 -0.000569226 + vertex -657.693 127.892 -0.000545744 + endloop + endfacet + facet normal 7.21183e-05 0.000175536 -1 + outer loop + vertex -661.247 126.973 -0.000963364 + vertex -657.693 127.892 -0.000545744 + vertex -650.756 122.958 -0.000911556 + endloop + endfacet + facet normal 7.81372e-05 0.000183528 -1 + outer loop + vertex -671.708 131.141 -0.00101579 + vertex -668.098 132.038 -0.000569226 + vertex -661.247 126.973 -0.000963364 + endloop + endfacet + facet normal 8.14118e-05 0.000191746 -1 + outer loop + vertex -664.715 125.967 -0.00143867 + vertex -671.708 131.141 -0.00101579 + vertex -661.247 126.973 -0.000963364 + endloop + endfacet + facet normal 8.18012e-05 0.000190404 -1 + outer loop + vertex -664.715 125.967 -0.00143867 + vertex -661.247 126.973 -0.000963364 + vertex -654.17 121.93 -0.00134465 + endloop + endfacet + facet normal 7.8477e-05 0.00018172 -1 + outer loop + vertex -657.502 120.79 -0.00181326 + vertex -664.715 125.967 -0.00143867 + vertex -654.17 121.93 -0.00134465 + endloop + endfacet + facet normal 8.88946e-05 0.000196236 -1 + outer loop + vertex -668.1 124.846 -0.00195942 + vertex -664.715 125.967 -0.00143867 + vertex -657.502 120.79 -0.00181326 + endloop + endfacet + facet normal 8.83779e-05 0.000197798 -1 + outer loop + vertex -668.1 124.846 -0.00195942 + vertex -675.23 130.157 -0.00153924 + vertex -664.715 125.967 -0.00143867 + endloop + endfacet + facet normal 0.000102502 0.000216763 -1 + outer loop + vertex -678.667 129.058 -0.00212975 + vertex -675.23 130.157 -0.00153924 + vertex -668.1 124.846 -0.00195942 + endloop + endfacet + facet normal 0.000137761 0.00030524 -1 + outer loop + vertex -671.423 123.57 -0.00280693 + vertex -678.667 129.058 -0.00212975 + vertex -668.1 124.846 -0.00195942 + endloop + endfacet + facet normal 0.000135473 0.000311195 -1 + outer loop + vertex -671.423 123.57 -0.00280693 + vertex -668.1 124.846 -0.00195942 + vertex -660.773 119.495 -0.00263199 + endloop + endfacet + facet normal 0.000151888 0.000323888 -1 + outer loop + vertex -682.044 127.802 -0.00304939 + vertex -678.667 129.058 -0.00212975 + vertex -671.423 123.57 -0.00280693 + endloop + endfacet + facet normal 0.00024756 0.000563986 -1 + outer loop + vertex -674.701 122.081 -0.00445767 + vertex -682.044 127.802 -0.00304939 + vertex -671.423 123.57 -0.00280693 + endloop + endfacet + facet normal 0.000238305 0.000584369 -1 + outer loop + vertex -674.701 122.081 -0.00445767 + vertex -671.423 123.57 -0.00280693 + vertex -664 117.991 -0.00429801 + endloop + endfacet + facet normal 0.000260114 0.000580101 -1 + outer loop + vertex -685.374 126.334 -0.00476713 + vertex -682.044 127.802 -0.00304939 + vertex -674.701 122.081 -0.00445767 + endloop + endfacet + facet normal 0.000302733 0.000687075 -1 + outer loop + vertex -677.917 120.325 -0.00663814 + vertex -685.374 126.334 -0.00476713 + vertex -674.701 122.081 -0.00445767 + endloop + endfacet + facet normal 0.000280564 0.000727672 -1 + outer loop + vertex -677.917 120.325 -0.00663814 + vertex -674.701 122.081 -0.00445767 + vertex -667.165 116.217 -0.00661044 + endloop + endfacet + facet normal 4.10277e-05 0.000100652 -1 + outer loop + vertex -670.219 114.126 -0.00694629 + vertex -677.917 120.325 -0.00663814 + vertex -667.165 116.217 -0.00661044 + endloop + endfacet + facet normal -2.45158e-05 1.92634e-05 -1 + outer loop + vertex -681.019 118.247 -0.00660212 + vertex -677.917 120.325 -0.00663814 + vertex -670.219 114.126 -0.00694629 + endloop + endfacet + facet normal 1.28311e-05 -3.64898e-05 -1 + outer loop + vertex -681.019 118.247 -0.00660212 + vertex -688.635 124.592 -0.00693136 + vertex -677.917 120.325 -0.00663814 + endloop + endfacet + facet normal 1.04503e-05 -3.93481e-05 -1 + outer loop + vertex -691.79 122.535 -0.0068834 + vertex -688.635 124.592 -0.00693136 + vertex -681.019 118.247 -0.00660212 + endloop + endfacet + facet normal -0.000798769 -0.00207228 -0.999998 + outer loop + vertex -683.943 115.825 0.000754535 + vertex -691.79 122.535 -0.0068834 + vertex -681.019 118.247 -0.00660212 + endloop + endfacet + facet normal -0.000843621 -0.00201814 -0.999998 + outer loop + vertex -683.943 115.825 0.000754535 + vertex -681.019 118.247 -0.00660212 + vertex -673.092 111.684 -4.43638e-05 + endloop + endfacet + facet normal -0.000829487 -0.0021082 -0.999997 + outer loop + vertex -694.759 120.128 0.000654732 + vertex -691.79 122.535 -0.0068834 + vertex -683.943 115.825 0.000754535 + endloop + endfacet + facet normal -0.00209401 -0.00528672 -0.999984 + outer loop + vertex -686.59 113.042 0.021011 + vertex -694.759 120.128 0.000654732 + vertex -683.943 115.825 0.000754535 + endloop + endfacet + facet normal -0.00210366 -0.00527754 -0.999984 + outer loop + vertex -686.59 113.042 0.021011 + vertex -683.943 115.825 0.000754535 + vertex -675.681 108.88 0.0200259 + endloop + endfacet + facet normal -0.00213285 -0.00533149 -0.999984 + outer loop + vertex -697.448 117.36 0.0211464 + vertex -694.759 120.128 0.000654732 + vertex -686.59 113.042 0.021011 + endloop + endfacet + facet normal -0.00385758 -0.00966817 -0.999946 + outer loop + vertex -688.851 109.907 0.0600416 + vertex -697.448 117.36 0.0211464 + vertex -686.59 113.042 0.021011 + endloop + endfacet + facet normal -0.00384819 -0.00967494 -0.999946 + outer loop + vertex -688.851 109.907 0.0600416 + vertex -686.59 113.042 0.021011 + vertex -677.898 105.729 0.0583069 + endloop + endfacet + facet normal -0.00679588 -0.017404 -0.999825 + outer loop + vertex -679.674 102.257 0.130834 + vertex -688.851 109.907 0.0600416 + vertex -677.898 105.729 0.0583069 + endloop + endfacet + facet normal -0.00666147 -0.0172428 -0.999829 + outer loop + vertex -690.687 106.456 0.131798 + vertex -688.851 109.907 0.0600416 + vertex -679.674 102.257 0.130834 + endloop + endfacet + facet normal -0.0128845 -0.0335653 -0.999353 + outer loop + vertex -681.131 98.5204 0.275102 + vertex -690.687 106.456 0.131798 + vertex -679.674 102.257 0.130834 + endloop + endfacet + facet normal -0.0123561 -0.0337712 -0.999353 + outer loop + vertex -681.131 98.5204 0.275102 + vertex -679.674 102.257 0.130834 + vertex -670.071 94.4664 0.275362 + endloop + endfacet + facet normal -0.0244221 -0.0666866 -0.997475 + outer loop + vertex -671.445 90.5095 0.57352 + vertex -681.131 98.5204 0.275102 + vertex -670.071 94.4664 0.275362 + endloop + endfacet + facet normal -0.0249173 -0.0672835 -0.997423 + outer loop + vertex -682.559 94.5859 0.576189 + vertex -681.131 98.5204 0.275102 + vertex -671.445 90.5095 0.57352 + endloop + endfacet + facet normal -0.042831 -0.116128 -0.99231 + outer loop + vertex -673.105 86.4124 1.12467 + vertex -682.559 94.5859 0.576189 + vertex -671.445 90.5095 0.57352 + endloop + endfacet + facet normal -0.0415685 -0.116639 -0.992304 + outer loop + vertex -673.105 86.4124 1.12467 + vertex -671.445 90.5095 0.57352 + vertex -661.983 82.4708 1.12206 + endloop + endfacet + facet normal -0.0420065 -0.117149 -0.992226 + outer loop + vertex -661.983 82.4708 1.12206 + vertex -671.445 90.5095 0.57352 + vertex -660.34 86.5802 0.567327 + endloop + endfacet + facet normal -0.0422725 -0.115489 -0.992409 + outer loop + vertex -684.275 90.5201 1.12243 + vertex -682.559 94.5859 0.576189 + vertex -673.105 86.4124 1.12467 + endloop + endfacet + facet normal -0.0437218 -0.114878 -0.992417 + outer loop + vertex -684.275 90.5201 1.12243 + vertex -693.665 98.8229 0.575026 + vertex -682.559 94.5859 0.576189 + endloop + endfacet + facet normal -0.0251421 -0.0661774 -0.997491 + outer loop + vertex -693.665 98.8229 0.575026 + vertex -692.195 102.737 0.278264 + vertex -682.559 94.5859 0.576189 + endloop + endfacet + facet normal -0.0261381 -0.0658032 -0.99749 + outer loop + vertex -693.665 98.8229 0.575026 + vertex -703.174 107.096 0.278403 + vertex -692.195 102.737 0.278264 + endloop + endfacet + facet normal -0.0134458 -0.0338346 -0.999337 + outer loop + vertex -703.174 107.096 0.278403 + vertex -701.633 110.804 0.132129 + vertex -692.195 102.737 0.278264 + endloop + endfacet + facet normal -0.0134971 -0.0338946 -0.999334 + outer loop + vertex -692.195 102.737 0.278264 + vertex -701.633 110.804 0.132129 + vertex -690.687 106.456 0.131798 + endloop + endfacet + facet normal -0.00688822 -0.0172607 -0.999827 + outer loop + vertex -701.633 110.804 0.132129 + vertex -699.761 114.244 0.0598488 + vertex -690.687 106.456 0.131798 + endloop + endfacet + facet normal -0.007075 -0.0171591 -0.999828 + outer loop + vertex -701.633 110.804 0.132129 + vertex -710.542 118.713 0.0594363 + vertex -699.761 114.244 0.0598488 + endloop + endfacet + facet normal -0.00393045 -0.00957363 -0.999946 + outer loop + vertex -710.542 118.713 0.0594363 + vertex -708.198 121.819 0.0204907 + vertex -699.761 114.244 0.0598488 + endloop + endfacet + facet normal -0.00389253 -0.00953139 -0.999947 + outer loop + vertex -699.761 114.244 0.0598488 + vertex -708.198 121.819 0.0204907 + vertex -697.448 117.36 0.0211464 + endloop + endfacet + facet normal -0.00214691 -0.00532295 -0.999984 + outer loop + vertex -708.198 121.819 0.0204907 + vertex -705.469 124.572 -2.13548e-05 + vertex -697.448 117.36 0.0211464 + endloop + endfacet + facet normal -0.00223415 -0.00523645 -0.999984 + outer loop + vertex -708.198 121.819 0.0204907 + vertex -716.048 129.151 -0.000362539 + vertex -705.469 124.572 -2.13548e-05 + endloop + endfacet + facet normal -0.000844713 -0.0020262 -0.999998 + outer loop + vertex -716.048 129.151 -0.000362539 + vertex -712.988 131.521 -0.00775065 + vertex -705.469 124.572 -2.13548e-05 + endloop + endfacet + facet normal -0.000845128 -0.00202665 -0.999998 + outer loop + vertex -705.469 124.572 -2.13548e-05 + vertex -712.988 131.521 -0.00775065 + vertex -702.452 126.96 -0.00741182 + endloop + endfacet + facet normal -0.000800959 -0.00208243 -0.999998 + outer loop + vertex -705.469 124.572 -2.13548e-05 + vertex -702.452 126.96 -0.00741182 + vertex -694.759 120.128 0.000654732 + endloop + endfacet + facet normal 2.93377e-05 -6.51568e-06 -1 + outer loop + vertex -712.988 131.521 -0.00775065 + vertex -709.739 133.54 -0.00766849 + vertex -702.452 126.96 -0.00741182 + endloop + endfacet + facet normal 2.27977e-05 -1.37584e-05 -1 + outer loop + vertex -702.452 126.96 -0.00741182 + vertex -709.739 133.54 -0.00766849 + vertex -699.25 128.999 -0.00736689 + endloop + endfacet + facet normal 3.55439e-05 -3.37734e-05 -1 + outer loop + vertex -702.452 126.96 -0.00741182 + vertex -699.25 128.999 -0.00736689 + vertex -691.79 122.535 -0.0068834 + endloop + endfacet + facet normal 0.000336963 0.000711858 -1 + outer loop + vertex -709.739 133.54 -0.00766849 + vertex -706.375 135.24 -0.00532514 + vertex -699.25 128.999 -0.00736689 + endloop + endfacet + facet normal 0.000324685 0.000697841 -1 + outer loop + vertex -699.25 128.999 -0.00736689 + vertex -706.375 135.24 -0.00532514 + vertex -695.934 130.718 -0.00509065 + endloop + endfacet + facet normal 0.00032806 0.000691329 -1 + outer loop + vertex -699.25 128.999 -0.00736689 + vertex -695.934 130.718 -0.00509065 + vertex -688.635 124.592 -0.00693136 + endloop + endfacet + facet normal 0.000307446 0.000666769 -1 + outer loop + vertex -688.635 124.592 -0.00693136 + vertex -695.934 130.718 -0.00509065 + vertex -685.374 126.334 -0.00476713 + endloop + endfacet + facet normal 0.000278282 0.000596521 -1 + outer loop + vertex -695.934 130.718 -0.00509065 + vertex -692.553 132.166 -0.00328594 + vertex -685.374 126.334 -0.00476713 + endloop + endfacet + facet normal 0.000275691 0.000602571 -1 + outer loop + vertex -695.934 130.718 -0.00509065 + vertex -702.944 136.667 -0.00343863 + vertex -692.553 132.166 -0.00328594 + endloop + endfacet + facet normal 0.000176196 0.000372863 -1 + outer loop + vertex -702.944 136.667 -0.00343863 + vertex -699.463 137.879 -0.0023733 + vertex -692.553 132.166 -0.00328594 + endloop + endfacet + facet normal 0.000165735 0.00036021 -1 + outer loop + vertex -692.553 132.166 -0.00328594 + vertex -699.463 137.879 -0.0023733 + vertex -689.127 133.401 -0.00227304 + endloop + endfacet + facet normal 0.000168692 0.00035201 -1 + outer loop + vertex -692.553 132.166 -0.00328594 + vertex -689.127 133.401 -0.00227304 + vertex -682.044 127.802 -0.00304939 + endloop + endfacet + facet normal 0.000120519 0.000255829 -1 + outer loop + vertex -699.463 137.879 -0.0023733 + vertex -695.919 138.933 -0.00167644 + vertex -689.127 133.401 -0.00227304 + endloop + endfacet + facet normal 0.000111136 0.000244308 -1 + outer loop + vertex -689.127 133.401 -0.00227304 + vertex -695.919 138.933 -0.00167644 + vertex -685.635 134.478 -0.00162197 + endloop + endfacet + facet normal 0.000112851 0.000238746 -1 + outer loop + vertex -689.127 133.401 -0.00227304 + vertex -685.635 134.478 -0.00162197 + vertex -678.667 129.058 -0.00212975 + endloop + endfacet + facet normal 0.000103745 0.000227247 -1 + outer loop + vertex -695.919 138.933 -0.00167644 + vertex -692.287 139.872 -0.00108634 + vertex -685.635 134.478 -0.00162197 + endloop + endfacet + facet normal 9.83406e-05 0.000220582 -1 + outer loop + vertex -685.635 134.478 -0.00162197 + vertex -692.287 139.872 -0.00108634 + vertex -682.058 135.44 -0.00105808 + endloop + endfacet + facet normal 9.88224e-05 0.00021879 -1 + outer loop + vertex -685.635 134.478 -0.00162197 + vertex -682.058 135.44 -0.00105808 + vertex -675.23 130.157 -0.00153924 + endloop + endfacet + facet normal 9.04676e-05 0.000207992 -1 + outer loop + vertex -675.23 130.157 -0.00153924 + vertex -682.058 135.44 -0.00105808 + vertex -671.708 131.141 -0.00101579 + endloop + endfacet + facet normal 8.27612e-05 0.000189437 -1 + outer loop + vertex -682.058 135.44 -0.00105808 + vertex -678.392 136.313 -0.000589239 + vertex -671.708 131.141 -0.00101579 + endloop + endfacet + facet normal 8.28973e-05 0.000188866 -1 + outer loop + vertex -682.058 135.44 -0.00105808 + vertex -688.57 140.721 -0.000600489 + vertex -678.392 136.313 -0.000589239 + endloop + endfacet + facet normal 5.85261e-05 0.00013259 -1 + outer loop + vertex -688.57 140.721 -0.000600489 + vertex -684.794 141.494 -0.000276926 + vertex -678.392 136.313 -0.000589239 + endloop + endfacet + facet normal 5.70261e-05 0.000130737 -1 + outer loop + vertex -678.392 136.313 -0.000589239 + vertex -684.794 141.494 -0.000276926 + vertex -674.673 137.11 -0.000272898 + endloop + endfacet + facet normal 5.67602e-05 0.000131978 -1 + outer loop + vertex -678.392 136.313 -0.000589239 + vertex -674.673 137.11 -0.000272898 + vertex -668.098 132.038 -0.000569226 + endloop + endfacet + facet normal 3.17736e-05 7.24366e-05 -1 + outer loop + vertex -684.794 141.494 -0.000276926 + vertex -681.016 142.197 -0.000106024 + vertex -674.673 137.11 -0.000272898 + endloop + endfacet + facet normal 3.13269e-05 7.18794e-05 -1 + outer loop + vertex -674.673 137.11 -0.000272898 + vertex -681.016 142.197 -0.000106024 + vertex -670.951 137.836 -0.000104168 + endloop + endfacet + facet normal 3.11252e-05 7.29139e-05 -1 + outer loop + vertex -674.673 137.11 -0.000272898 + vertex -670.951 137.836 -0.000104168 + vertex -664.434 132.858 -0.00026428 + endloop + endfacet + facet normal 2.99056e-05 7.13172e-05 -1 + outer loop + vertex -664.434 132.858 -0.00026428 + vertex -670.951 137.836 -0.000104168 + vertex -660.768 133.607 -0.000101244 + endloop + endfacet + facet normal 1.36172e-05 3.20971e-05 -1 + outer loop + vertex -670.951 137.836 -0.000104168 + vertex -667.266 138.494 -3.28666e-05 + vertex -660.768 133.607 -0.000101244 + endloop + endfacet + facet normal 1.37237e-05 3.15009e-05 -1 + outer loop + vertex -670.951 137.836 -0.000104168 + vertex -677.275 142.831 -3.36056e-05 + vertex -667.266 138.494 -3.28666e-05 + endloop + endfacet + facet normal 4.91726e-06 1.11776e-05 -1 + outer loop + vertex -677.275 142.831 -3.36056e-05 + vertex -673.57 143.408 -8.93518e-06 + vertex -667.266 138.494 -3.28666e-05 + endloop + endfacet + facet normal 4.80608e-06 1.1035e-05 -1 + outer loop + vertex -667.266 138.494 -3.28666e-05 + vertex -673.57 143.408 -8.93518e-06 + vertex -663.614 139.094 -8.69129e-06 + endloop + endfacet + facet normal 4.75502e-06 1.13456e-05 -1 + outer loop + vertex -667.266 138.494 -3.28666e-05 + vertex -663.614 139.094 -8.69129e-06 + vertex -657.136 134.288 -3.24178e-05 + endloop + endfacet + facet normal 4.66814e-06 1.12285e-05 -1 + outer loop + vertex -657.136 134.288 -3.24178e-05 + vertex -663.614 139.094 -8.69129e-06 + vertex -653.532 134.909 -8.61437e-06 + endloop + endfacet + facet normal 1.3507e-06 3.23585e-06 -1 + outer loop + vertex -663.614 139.094 -8.69129e-06 + vertex -659.976 139.66 -1.94594e-06 + vertex -653.532 134.909 -8.61437e-06 + endloop + endfacet + facet normal 1.36496e-06 3.14424e-06 -1 + outer loop + vertex -663.614 139.094 -8.69129e-06 + vertex -669.89 143.953 -1.97951e-06 + vertex -659.976 139.66 -1.94594e-06 + endloop + endfacet + facet normal 3.33245e-07 7.61735e-07 -1 + outer loop + vertex -669.89 143.953 -1.97951e-06 + vertex -666.33 144.516 -3.64239e-07 + vertex -659.976 139.66 -1.94594e-06 + endloop + endfacet + facet normal 3.24987e-07 7.5093e-07 -1 + outer loop + vertex -659.976 139.66 -1.94594e-06 + vertex -666.33 144.516 -3.64239e-07 + vertex -656.499 140.262 -3.64194e-07 + endloop + endfacet + facet normal 3.22428e-07 7.65716e-07 -1 + outer loop + vertex -659.976 139.66 -1.94594e-06 + vertex -656.499 140.262 -3.64194e-07 + vertex -649.944 135.497 -1.89905e-06 + endloop + endfacet + facet normal 3.13276e-07 7.53126e-07 -1 + outer loop + vertex -649.944 135.497 -1.89905e-06 + vertex -656.499 140.262 -3.64194e-07 + vertex -646.568 136.14 -3.57353e-07 + endloop + endfacet + facet normal 7.85812e-08 1.87668e-07 -1 + outer loop + vertex -656.499 140.262 -3.64194e-07 + vertex -653.741 141.047 -7.91927e-14 + vertex -646.568 136.14 -3.57353e-07 + endloop + endfacet + facet normal 7.9645e-08 1.83932e-07 -1 + outer loop + vertex -656.499 140.262 -3.64194e-07 + vertex -663.267 145.172 -7.87857e-14 + vertex -653.741 141.047 -7.91927e-14 + endloop + endfacet + facet normal 7.95463e-08 1.83796e-07 -1 + outer loop + vertex -666.33 144.516 -3.64239e-07 + vertex -663.267 145.172 -7.87857e-14 + vertex -656.499 140.262 -3.64194e-07 + endloop + endfacet + facet normal 8.06483e-08 1.78654e-07 -1 + outer loop + vertex -666.33 144.516 -3.64239e-07 + vertex -672.924 149.532 -7.83557e-14 + vertex -663.267 145.172 -7.87857e-14 + endloop + endfacet + facet normal 8.29359e-08 1.81662e-07 -1 + outer loop + vertex -676.161 148.961 -3.72233e-07 + vertex -672.924 149.532 -7.83557e-14 + vertex -666.33 144.516 -3.64239e-07 + endloop + endfacet + facet normal 8.36944e-08 1.77359e-07 -1 + outer loop + vertex -676.161 148.961 -3.72233e-07 + vertex -683.154 154.359 -7.78793e-14 + vertex -672.924 149.532 -7.83557e-14 + endloop + endfacet + facet normal 8.4589e-08 1.78518e-07 -1 + outer loop + vertex -685.88 153.547 -3.75486e-07 + vertex -683.154 154.359 -7.78793e-14 + vertex -676.161 148.961 -3.72233e-07 + endloop + endfacet + facet normal 3.43577e-07 7.27262e-07 -1 + outer loop + vertex -679.716 148.397 -2.00386e-06 + vertex -685.88 153.547 -3.75486e-07 + vertex -676.161 148.961 -3.72233e-07 + endloop + endfacet + facet normal 3.40399e-07 7.47288e-07 -1 + outer loop + vertex -679.716 148.397 -2.00386e-06 + vertex -676.161 148.961 -3.72233e-07 + vertex -669.89 143.953 -1.97951e-06 + endloop + endfacet + facet normal 1.42437e-06 3.14442e-06 -1 + outer loop + vertex -673.57 143.408 -8.93518e-06 + vertex -679.716 148.397 -2.00386e-06 + vertex -669.89 143.953 -1.97951e-06 + endloop + endfacet + facet normal 1.42147e-06 3.14084e-06 -1 + outer loop + vertex -683.447 147.875 -8.94598e-06 + vertex -679.716 148.397 -2.00386e-06 + vertex -673.57 143.408 -8.93518e-06 + endloop + endfacet + facet normal 1.43598e-06 3.0371e-06 -1 + outer loop + vertex -683.447 147.875 -8.94598e-06 + vertex -689.485 153.01 -2.02031e-06 + vertex -679.716 148.397 -2.00386e-06 + endloop + endfacet + facet normal 1.45549e-06 3.06004e-06 -1 + outer loop + vertex -693.275 152.518 -9.04255e-06 + vertex -689.485 153.01 -2.02031e-06 + vertex -683.447 147.875 -8.94598e-06 + endloop + endfacet + facet normal 5.11283e-06 1.08016e-05 -1 + outer loop + vertex -687.207 147.324 -3.41186e-05 + vertex -693.275 152.518 -9.04255e-06 + vertex -683.447 147.875 -8.94598e-06 + endloop + endfacet + facet normal 5.0701e-06 1.10931e-05 -1 + outer loop + vertex -687.207 147.324 -3.41186e-05 + vertex -683.447 147.875 -8.94598e-06 + vertex -677.275 142.831 -3.36056e-05 + endloop + endfacet + facet normal 1.40945e-05 3.10412e-05 -1 + outer loop + vertex -681.016 142.197 -0.000106024 + vertex -687.207 147.324 -3.41186e-05 + vertex -677.275 142.831 -3.36056e-05 + endloop + endfacet + facet normal 1.4266e-05 3.12482e-05 -1 + outer loop + vertex -691.002 146.714 -0.000107329 + vertex -687.207 147.324 -3.41186e-05 + vertex -681.016 142.197 -0.000106024 + endloop + endfacet + facet normal 1.43851e-05 3.0507e-05 -1 + outer loop + vertex -691.002 146.714 -0.000107329 + vertex -697.091 151.992 -3.38908e-05 + vertex -687.207 147.324 -3.41186e-05 + endloop + endfacet + facet normal 1.42603e-05 3.0363e-05 -1 + outer loop + vertex -700.941 151.407 -0.000106546 + vertex -697.091 151.992 -3.38908e-05 + vertex -691.002 146.714 -0.000107329 + endloop + endfacet + facet normal 3.29578e-05 6.99551e-05 -1 + outer loop + vertex -694.834 146.036 -0.000280999 + vertex -700.941 151.407 -0.000106546 + vertex -691.002 146.714 -0.000107329 + endloop + endfacet + facet normal 3.27038e-05 7.13921e-05 -1 + outer loop + vertex -694.834 146.036 -0.000280999 + vertex -691.002 146.714 -0.000107329 + vertex -684.794 141.494 -0.000276926 + endloop + endfacet + facet normal 3.31924e-05 7.02219e-05 -1 + outer loop + vertex -704.828 150.756 -0.000281285 + vertex -700.941 151.407 -0.000106546 + vertex -694.834 146.036 -0.000280999 + endloop + endfacet + facet normal 6.04545e-05 0.000127947 -1 + outer loop + vertex -698.664 145.287 -0.000608391 + vertex -704.828 150.756 -0.000281285 + vertex -694.834 146.036 -0.000280999 + endloop + endfacet + facet normal 5.99151e-05 0.000130706 -1 + outer loop + vertex -698.664 145.287 -0.000608391 + vertex -694.834 146.036 -0.000280999 + vertex -688.57 140.721 -0.000600489 + endloop + endfacet + facet normal 8.71244e-05 0.00019085 -1 + outer loop + vertex -692.287 139.872 -0.00108634 + vertex -698.664 145.287 -0.000608391 + vertex -688.57 140.721 -0.000600489 + endloop + endfacet + facet normal 8.81065e-05 0.000192006 -1 + outer loop + vertex -702.44 144.462 -0.00109958 + vertex -698.664 145.287 -0.000608391 + vertex -692.287 139.872 -0.00108634 + endloop + endfacet + facet normal 8.89671e-05 0.000188069 -1 + outer loop + vertex -702.44 144.462 -0.00109958 + vertex -708.714 150.033 -0.000609992 + vertex -698.664 145.287 -0.000608391 + endloop + endfacet + facet normal 9.00242e-05 0.00018926 -1 + outer loop + vertex -712.543 149.234 -0.00110591 + vertex -708.714 150.033 -0.000609992 + vertex -702.44 144.462 -0.00109958 + endloop + endfacet + facet normal 0.000107712 0.000226705 -1 + outer loop + vertex -706.125 143.548 -0.00170379 + vertex -712.543 149.234 -0.00110591 + vertex -702.44 144.462 -0.00109958 + endloop + endfacet + facet normal 0.000106813 0.000230328 -1 + outer loop + vertex -706.125 143.548 -0.00170379 + vertex -702.44 144.462 -0.00109958 + vertex -695.919 138.933 -0.00167644 + endloop + endfacet + facet normal 0.000108894 0.00022804 -1 + outer loop + vertex -716.281 148.345 -0.00171579 + vertex -712.543 149.234 -0.00110591 + vertex -706.125 143.548 -0.00170379 + endloop + endfacet + facet normal 0.000125443 0.000263074 -1 + outer loop + vertex -709.718 142.517 -0.00242552 + vertex -716.281 148.345 -0.00171579 + vertex -706.125 143.548 -0.00170379 + endloop + endfacet + facet normal 0.000124915 0.000264915 -1 + outer loop + vertex -709.718 142.517 -0.00242552 + vertex -706.125 143.548 -0.00170379 + vertex -699.463 137.879 -0.0023733 + endloop + endfacet + facet normal 0.000126748 0.000264545 -1 + outer loop + vertex -719.929 147.338 -0.00244444 + vertex -716.281 148.345 -0.00171579 + vertex -709.718 142.517 -0.00242552 + endloop + endfacet + facet normal 0.00018186 0.00038128 -1 + outer loop + vertex -713.252 141.328 -0.00352187 + vertex -719.929 147.338 -0.00244444 + vertex -709.718 142.517 -0.00242552 + endloop + endfacet + facet normal 0.000181268 0.000383039 -1 + outer loop + vertex -713.252 141.328 -0.00352187 + vertex -709.718 142.517 -0.00242552 + vertex -702.944 136.667 -0.00343863 + endloop + endfacet + facet normal 0.000290269 0.000624108 -1 + outer loop + vertex -706.375 135.24 -0.00532514 + vertex -713.252 141.328 -0.00352187 + vertex -702.944 136.667 -0.00343863 + endloop + endfacet + facet normal 0.000298526 0.000633436 -1 + outer loop + vertex -716.733 139.923 -0.0054511 + vertex -713.252 141.328 -0.00352187 + vertex -706.375 135.24 -0.00532514 + endloop + endfacet + facet normal 0.000300562 0.000628391 -1 + outer loop + vertex -716.733 139.923 -0.0054511 + vertex -723.51 146.172 -0.00356122 + vertex -713.252 141.328 -0.00352187 + endloop + endfacet + facet normal 0.000302111 0.000630071 -1 + outer loop + vertex -727.044 144.79 -0.00549887 + vertex -723.51 146.172 -0.00356122 + vertex -716.733 139.923 -0.0054511 + endloop + endfacet + facet normal 0.000346239 0.000723535 -1 + outer loop + vertex -720.15 138.246 -0.0078468 + vertex -727.044 144.79 -0.00549887 + vertex -716.733 139.923 -0.0054511 + endloop + endfacet + facet normal 0.000345176 0.000725701 -1 + outer loop + vertex -720.15 138.246 -0.0078468 + vertex -716.733 139.923 -0.0054511 + vertex -709.739 133.54 -0.00766849 + endloop + endfacet + facet normal 0.000347031 0.00072437 -1 + outer loop + vertex -730.51 143.136 -0.00789981 + vertex -727.044 144.79 -0.00549887 + vertex -720.15 138.246 -0.0078468 + endloop + endfacet + facet normal 2.22315e-05 3.6258e-05 -1 + outer loop + vertex -723.447 136.248 -0.00799256 + vertex -730.51 143.136 -0.00789981 + vertex -720.15 138.246 -0.0078468 + endloop + endfacet + facet normal 3.21338e-05 1.99211e-05 -1 + outer loop + vertex -723.447 136.248 -0.00799256 + vertex -720.15 138.246 -0.0078468 + vertex -712.988 131.521 -0.00775065 + endloop + endfacet + facet normal 1.49811e-05 2.88243e-05 -1 + outer loop + vertex -733.853 141.159 -0.00800691 + vertex -730.51 143.136 -0.00789981 + vertex -723.447 136.248 -0.00799256 + endloop + endfacet + facet normal -0.000917426 -0.00194696 -0.999998 + outer loop + vertex -726.55 133.895 -0.00056541 + vertex -733.853 141.159 -0.00800691 + vertex -723.447 136.248 -0.00799256 + endloop + endfacet + facet normal -0.000881656 -0.00199413 -0.999998 + outer loop + vertex -726.55 133.895 -0.00056541 + vertex -723.447 136.248 -0.00799256 + vertex -716.048 129.151 -0.000362539 + endloop + endfacet + facet normal -0.00229313 -0.00511814 -0.999984 + outer loop + vertex -718.823 126.416 0.0199951 + vertex -726.55 133.895 -0.00056541 + vertex -716.048 129.151 -0.000362539 + endloop + endfacet + facet normal -0.00230104 -0.00512631 -0.999984 + outer loop + vertex -729.363 131.177 0.019843 + vertex -726.55 133.895 -0.00056541 + vertex -718.823 126.416 0.0199951 + endloop + endfacet + facet normal -0.00422662 -0.00938945 -0.999947 + outer loop + vertex -721.199 123.322 0.0590938 + vertex -729.363 131.177 0.019843 + vertex -718.823 126.416 0.0199951 + endloop + endfacet + facet normal -0.00407762 -0.00950387 -0.999947 + outer loop + vertex -721.199 123.322 0.0590938 + vertex -718.823 126.416 0.0199951 + vertex -710.542 118.713 0.0594363 + endloop + endfacet + facet normal -0.0073226 -0.0170079 -0.999829 + outer loop + vertex -712.445 115.282 0.131744 + vertex -721.199 123.322 0.0590938 + vertex -710.542 118.713 0.0594363 + endloop + endfacet + facet normal -0.0072006 -0.0168751 -0.999832 + outer loop + vertex -723.139 119.901 0.130808 + vertex -721.199 123.322 0.0590938 + vertex -712.445 115.282 0.131744 + endloop + endfacet + facet normal -0.0141389 -0.0329401 -0.999357 + outer loop + vertex -714.015 111.581 0.275939 + vertex -723.139 119.901 0.130808 + vertex -712.445 115.282 0.131744 + endloop + endfacet + facet normal -0.0135101 -0.0332068 -0.999357 + outer loop + vertex -714.015 111.581 0.275939 + vertex -712.445 115.282 0.131744 + vertex -703.174 107.096 0.278403 + endloop + endfacet + facet normal -0.0267305 -0.0651633 -0.997517 + outer loop + vertex -704.67 103.193 0.573508 + vertex -714.015 111.581 0.275939 + vertex -703.174 107.096 0.278403 + endloop + endfacet + facet normal -0.027296 -0.0657913 -0.99746 + outer loop + vertex -715.527 107.683 0.574422 + vertex -714.015 111.581 0.275939 + vertex -704.67 103.193 0.573508 + endloop + endfacet + facet normal -0.0473271 -0.114222 -0.992327 + outer loop + vertex -706.441 99.1646 1.12164 + vertex -715.527 107.683 0.574422 + vertex -704.67 103.193 0.573508 + endloop + endfacet + facet normal -0.0455232 -0.115015 -0.99232 + outer loop + vertex -706.441 99.1646 1.12164 + vertex -704.67 103.193 0.573508 + vertex -695.422 94.7807 1.12424 + endloop + endfacet + facet normal -0.0455387 -0.115031 -0.992317 + outer loop + vertex -695.422 94.7807 1.12424 + vertex -704.67 103.193 0.573508 + vertex -693.665 98.8229 0.575026 + endloop + endfacet + facet normal -0.0473096 -0.114204 -0.99233 + outer loop + vertex -717.308 103.667 1.12158 + vertex -715.527 107.683 0.574422 + vertex -706.441 99.1646 1.12164 + endloop + endfacet + facet normal -0.0489938 -0.113457 -0.992334 + outer loop + vertex -717.308 103.667 1.12158 + vertex -726.263 112.315 0.574966 + vertex -715.527 107.683 0.574422 + endloop + endfacet + facet normal -0.0281942 -0.0652406 -0.997471 + outer loop + vertex -726.263 112.315 0.574966 + vertex -724.731 116.204 0.277226 + vertex -715.527 107.683 0.574422 + endloop + endfacet + facet normal -0.0292565 -0.0648219 -0.997468 + outer loop + vertex -726.263 112.315 0.574966 + vertex -735.371 120.998 0.277823 + vertex -724.731 116.204 0.277226 + endloop + endfacet + facet normal -0.0150567 -0.0332998 -0.999332 + outer loop + vertex -735.371 120.998 0.277823 + vertex -733.751 124.686 0.130521 + vertex -724.731 116.204 0.277226 + endloop + endfacet + facet normal -0.0149257 -0.0331606 -0.999339 + outer loop + vertex -724.731 116.204 0.277226 + vertex -733.751 124.686 0.130521 + vertex -723.139 119.901 0.130808 + endloop + endfacet + facet normal -0.00751412 -0.0167239 -0.999832 + outer loop + vertex -733.751 124.686 0.130521 + vertex -731.782 128.098 0.0586454 + vertex -723.139 119.901 0.130808 + endloop + endfacet + facet normal -0.00781122 -0.0165525 -0.999832 + outer loop + vertex -733.751 124.686 0.130521 + vertex -742.314 133.064 0.0587179 + vertex -731.782 128.098 0.0586454 + endloop + endfacet + facet normal -0.00434803 -0.00920734 -0.999948 + outer loop + vertex -742.314 133.064 0.0587179 + vertex -739.857 136.127 0.0198255 + vertex -731.782 128.098 0.0586454 + endloop + endfacet + facet normal -0.00433636 -0.0091956 -0.999948 + outer loop + vertex -731.782 128.098 0.0586454 + vertex -739.857 136.127 0.0198255 + vertex -729.363 131.177 0.019843 + endloop + endfacet + facet normal -0.00237853 -0.00504546 -0.999984 + outer loop + vertex -739.857 136.127 0.0198255 + vertex -737.002 138.827 -0.000587174 + vertex -729.363 131.177 0.019843 + endloop + endfacet + facet normal -0.00244271 -0.00497759 -0.999985 + outer loop + vertex -739.857 136.127 0.0198255 + vertex -747.402 143.955 -0.000706493 + vertex -737.002 138.827 -0.000587174 + endloop + endfacet + facet normal -0.000929649 -0.00190879 -0.999998 + outer loop + vertex -747.402 143.955 -0.000706493 + vertex -744.208 146.265 -0.00808552 + vertex -737.002 138.827 -0.000587174 + endloop + endfacet + facet normal -0.000937429 -0.00191632 -0.999998 + outer loop + vertex -737.002 138.827 -0.000587174 + vertex -744.208 146.265 -0.00808552 + vertex -733.853 141.159 -0.00800691 + endloop + endfacet + facet normal 2.75223e-05 4.04137e-05 -1 + outer loop + vertex -744.208 146.265 -0.00808552 + vertex -740.812 148.218 -0.00791316 + vertex -733.853 141.159 -0.00800691 + endloop + endfacet + facet normal 2.66884e-05 4.18636e-05 -1 + outer loop + vertex -744.208 146.265 -0.00808552 + vertex -751.03 153.488 -0.00796524 + vertex -740.812 148.218 -0.00791316 + endloop + endfacet + facet normal 0.00036862 0.000704846 -1 + outer loop + vertex -751.03 153.488 -0.00796524 + vertex -747.462 155.092 -0.00551937 + vertex -740.812 148.218 -0.00791316 + endloop + endfacet + facet normal 0.000360943 0.000697419 -1 + outer loop + vertex -740.812 148.218 -0.00791316 + vertex -747.462 155.092 -0.00551937 + vertex -737.299 149.849 -0.00550708 + endloop + endfacet + facet normal 0.000353341 0.000713792 -1 + outer loop + vertex -740.812 148.218 -0.00791316 + vertex -737.299 149.849 -0.00550708 + vertex -730.51 143.136 -0.00789981 + endloop + endfacet + facet normal 0.000313662 0.000605756 -1 + outer loop + vertex -747.462 155.092 -0.00551937 + vertex -743.828 156.424 -0.00357252 + vertex -737.299 149.849 -0.00550708 + endloop + endfacet + facet normal 0.000312954 0.000605052 -1 + outer loop + vertex -737.299 149.849 -0.00550708 + vertex -743.828 156.424 -0.00357252 + vertex -733.715 151.206 -0.00356473 + endloop + endfacet + facet normal 0.000307013 0.000620742 -1 + outer loop + vertex -737.299 149.849 -0.00550708 + vertex -733.715 151.206 -0.00356473 + vertex -727.044 144.79 -0.00549887 + endloop + endfacet + facet normal 0.000192595 0.000371781 -1 + outer loop + vertex -743.828 156.424 -0.00357252 + vertex -740.147 157.54 -0.00244857 + vertex -733.715 151.206 -0.00356473 + endloop + endfacet + facet normal 0.000189894 0.000369038 -1 + outer loop + vertex -733.715 151.206 -0.00356473 + vertex -740.147 157.54 -0.00244857 + vertex -730.08 152.347 -0.00245325 + endloop + endfacet + facet normal 0.00018698 0.000378315 -1 + outer loop + vertex -733.715 151.206 -0.00356473 + vertex -730.08 152.347 -0.00245325 + vertex -723.51 146.172 -0.00356122 + endloop + endfacet + facet normal 0.000188182 0.000379594 -1 + outer loop + vertex -723.51 146.172 -0.00356122 + vertex -730.08 152.347 -0.00245325 + vertex -719.929 147.338 -0.00244444 + endloop + endfacet + facet normal 0.000129045 0.000259751 -1 + outer loop + vertex -730.08 152.347 -0.00245325 + vertex -726.382 153.329 -0.00172101 + vertex -719.929 147.338 -0.00244444 + endloop + endfacet + facet normal 0.00013076 0.000253288 -1 + outer loop + vertex -730.08 152.347 -0.00245325 + vertex -736.395 158.495 -0.00172184 + vertex -726.382 153.329 -0.00172101 + endloop + endfacet + facet normal 0.000112293 0.000217494 -1 + outer loop + vertex -736.395 158.495 -0.00172184 + vertex -732.554 159.332 -0.0011085 + vertex -726.382 153.329 -0.00172101 + endloop + endfacet + facet normal 0.00011205 0.000217244 -1 + outer loop + vertex -726.382 153.329 -0.00172101 + vertex -732.554 159.332 -0.0011085 + vertex -722.591 154.193 -0.00110854 + endloop + endfacet + facet normal 0.000110681 0.00022325 -1 + outer loop + vertex -726.382 153.329 -0.00172101 + vertex -722.591 154.193 -0.00110854 + vertex -716.281 148.345 -0.00171579 + endloop + endfacet + facet normal 9.23701e-05 0.00017909 -1 + outer loop + vertex -732.554 159.332 -0.0011085 + vertex -728.617 160.077 -0.000611431 + vertex -722.591 154.193 -0.00110854 + endloop + endfacet + facet normal 9.22072e-05 0.000178923 -1 + outer loop + vertex -722.591 154.193 -0.00110854 + vertex -728.617 160.077 -0.000611431 + vertex -718.708 154.966 -0.000612212 + endloop + endfacet + facet normal 9.11604e-05 0.000184183 -1 + outer loop + vertex -722.591 154.193 -0.00110854 + vertex -718.708 154.966 -0.000612212 + vertex -712.543 149.234 -0.00110591 + endloop + endfacet + facet normal 6.2271e-05 0.000120883 -1 + outer loop + vertex -728.617 160.077 -0.000611431 + vertex -724.619 160.744 -0.000281863 + vertex -718.708 154.966 -0.000612212 + endloop + endfacet + facet normal 6.26427e-05 0.000121263 -1 + outer loop + vertex -718.708 154.966 -0.000612212 + vertex -724.619 160.744 -0.000281863 + vertex -714.767 155.66 -0.000281119 + endloop + endfacet + facet normal 6.1967e-05 0.000125096 -1 + outer loop + vertex -718.708 154.966 -0.000612212 + vertex -714.767 155.66 -0.000281119 + vertex -708.714 150.033 -0.000609992 + endloop + endfacet + facet normal 6.14127e-05 0.0001245 -1 + outer loop + vertex -708.714 150.033 -0.000609992 + vertex -714.767 155.66 -0.000281119 + vertex -704.828 150.756 -0.000281285 + endloop + endfacet + facet normal 3.32509e-05 6.74242e-05 -1 + outer loop + vertex -714.767 155.66 -0.000281119 + vertex -710.823 156.285 -0.000107844 + vertex -704.828 150.756 -0.000281285 + endloop + endfacet + facet normal 3.35952e-05 6.52507e-05 -1 + outer loop + vertex -714.767 155.66 -0.000281119 + vertex -720.62 161.339 -0.00010724 + vertex -710.823 156.285 -0.000107844 + endloop + endfacet + facet normal 1.46851e-05 2.85896e-05 -1 + outer loop + vertex -720.62 161.339 -0.00010724 + vertex -716.661 161.867 -3.39852e-05 + vertex -710.823 156.285 -0.000107844 + endloop + endfacet + facet normal 1.47596e-05 2.86675e-05 -1 + outer loop + vertex -710.823 156.285 -0.000107844 + vertex -716.661 161.867 -3.39852e-05 + vertex -706.919 156.843 -3.42448e-05 + endloop + endfacet + facet normal 1.46525e-05 2.94184e-05 -1 + outer loop + vertex -710.823 156.285 -0.000107844 + vertex -706.919 156.843 -3.42448e-05 + vertex -700.941 151.407 -0.000106546 + endloop + endfacet + facet normal 5.16636e-06 1.00682e-05 -1 + outer loop + vertex -716.661 161.867 -3.39852e-05 + vertex -712.741 162.337 -9.00162e-06 + vertex -706.919 156.843 -3.42448e-05 + endloop + endfacet + facet normal 5.1953e-06 1.00988e-05 -1 + outer loop + vertex -706.919 156.843 -3.42448e-05 + vertex -712.741 162.337 -9.00162e-06 + vertex -703.05 157.341 -9.11288e-06 + endloop + endfacet + facet normal 5.15905e-06 1.03803e-05 -1 + outer loop + vertex -706.919 156.843 -3.42448e-05 + vertex -703.05 157.341 -9.11288e-06 + vertex -697.091 151.992 -3.38908e-05 + endloop + endfacet + facet normal 5.09206e-06 1.03056e-05 -1 + outer loop + vertex -697.091 151.992 -3.38908e-05 + vertex -703.05 157.341 -9.11288e-06 + vertex -693.275 152.518 -9.04255e-06 + endloop + endfacet + facet normal 1.51368e-06 3.05325e-06 -1 + outer loop + vertex -703.05 157.341 -9.11288e-06 + vertex -699.205 157.802 -1.88591e-06 + vertex -693.275 152.518 -9.04255e-06 + endloop + endfacet + facet normal 1.52768e-06 2.93648e-06 -1 + outer loop + vertex -703.05 157.341 -9.11288e-06 + vertex -708.846 162.774 -2.01251e-06 + vertex -699.205 157.802 -1.88591e-06 + endloop + endfacet + facet normal 3.56663e-07 6.66055e-07 -1 + outer loop + vertex -708.846 162.774 -2.01251e-06 + vertex -705.132 163.259 -3.65135e-07 + vertex -699.205 157.802 -1.88591e-06 + endloop + endfacet + facet normal 3.25377e-07 6.32075e-07 -1 + outer loop + vertex -699.205 157.802 -1.88591e-06 + vertex -705.132 163.259 -3.65135e-07 + vertex -695.507 158.296 -3.70324e-07 + endloop + endfacet + facet normal 3.19489e-07 6.76136e-07 -1 + outer loop + vertex -699.205 157.802 -1.88591e-06 + vertex -695.507 158.296 -3.70324e-07 + vertex -689.485 153.01 -2.02031e-06 + endloop + endfacet + facet normal 3.50212e-07 7.1114e-07 -1 + outer loop + vertex -689.485 153.01 -2.02031e-06 + vertex -695.507 158.296 -3.70324e-07 + vertex -685.88 153.547 -3.75486e-07 + endloop + endfacet + facet normal 8.45817e-08 1.72576e-07 -1 + outer loop + vertex -695.507 158.296 -3.70324e-07 + vertex -692.219 158.83 -7.74382e-14 + vertex -685.88 153.547 -3.75486e-07 + endloop + endfacet + facet normal 8.56327e-08 1.66107e-07 -1 + outer loop + vertex -695.507 158.296 -3.70324e-07 + vertex -701.963 163.854 -7.69426e-14 + vertex -692.219 158.83 -7.74382e-14 + endloop + endfacet + facet normal 8.43304e-08 1.64594e-07 -1 + outer loop + vertex -705.132 163.259 -3.65135e-07 + vertex -701.963 163.854 -7.69426e-14 + vertex -695.507 158.296 -3.70324e-07 + endloop + endfacet + facet normal 8.55145e-08 1.58285e-07 -1 + outer loop + vertex -705.132 163.259 -3.65135e-07 + vertex -711.606 169.063 -7.64286e-14 + vertex -701.963 163.854 -7.69426e-14 + endloop + endfacet + facet normal 8.28065e-08 1.55265e-07 -1 + outer loop + vertex -714.614 168.375 -3.55943e-07 + vertex -711.606 169.063 -7.64286e-14 + vertex -705.132 163.259 -3.65135e-07 + endloop + endfacet + facet normal 8.42633e-08 1.48894e-07 -1 + outer loop + vertex -714.614 168.375 -3.55943e-07 + vertex -720.665 174.19 -7.59228e-14 + vertex -711.606 169.063 -7.64286e-14 + endloop + endfacet + facet normal 9.04199e-08 1.553e-07 -1 + outer loop + vertex -723.982 173.676 -3.79758e-07 + vertex -720.665 174.19 -7.59228e-14 + vertex -714.614 168.375 -3.55943e-07 + endloop + endfacet + facet normal 3.66021e-07 6.42351e-07 -1 + outer loop + vertex -718.383 167.922 -2.02628e-06 + vertex -723.982 173.676 -3.79758e-07 + vertex -714.614 168.375 -3.55943e-07 + endloop + endfacet + facet normal 3.62772e-07 6.69385e-07 -1 + outer loop + vertex -718.383 167.922 -2.02628e-06 + vertex -714.614 168.375 -3.55943e-07 + vertex -708.846 162.774 -2.01251e-06 + endloop + endfacet + facet normal 1.48597e-06 2.75018e-06 -1 + outer loop + vertex -712.741 162.337 -9.00162e-06 + vertex -718.383 167.922 -2.02628e-06 + vertex -708.846 162.774 -2.01251e-06 + endloop + endfacet + facet normal 1.5083e-06 2.77274e-06 -1 + outer loop + vertex -722.322 167.512 -9.10536e-06 + vertex -718.383 167.922 -2.02628e-06 + vertex -712.741 162.337 -9.00162e-06 + endloop + endfacet + facet normal 1.51806e-06 2.67897e-06 -1 + outer loop + vertex -722.322 167.512 -9.10536e-06 + vertex -727.81 173.257 -2.04407e-06 + vertex -718.383 167.922 -2.02628e-06 + endloop + endfacet + facet normal 1.50064e-06 2.66233e-06 -1 + outer loop + vertex -731.798 172.874 -9.04889e-06 + vertex -727.81 173.257 -2.04407e-06 + vertex -722.322 167.512 -9.10536e-06 + endloop + endfacet + facet normal 5.26494e-06 9.31427e-06 -1 + outer loop + vertex -726.294 167.07 -3.41349e-05 + vertex -731.798 172.874 -9.04889e-06 + vertex -722.322 167.512 -9.10536e-06 + endloop + endfacet + facet normal 5.22745e-06 9.65082e-06 -1 + outer loop + vertex -726.294 167.07 -3.41349e-05 + vertex -722.322 167.512 -9.10536e-06 + vertex -716.661 161.867 -3.39852e-05 + endloop + endfacet + facet normal 5.29552e-06 9.34327e-06 -1 + outer loop + vertex -735.819 172.461 -3.4205e-05 + vertex -731.798 172.874 -9.04889e-06 + vertex -726.294 167.07 -3.41349e-05 + endloop + endfacet + facet normal 1.50348e-05 2.65509e-05 -1 + outer loop + vertex -730.307 166.571 -0.000107727 + vertex -735.819 172.461 -3.4205e-05 + vertex -726.294 167.07 -3.41349e-05 + endloop + endfacet + facet normal 1.49141e-05 2.75216e-05 -1 + outer loop + vertex -730.307 166.571 -0.000107727 + vertex -726.294 167.07 -3.41349e-05 + vertex -720.62 161.339 -0.00010724 + endloop + endfacet + facet normal 3.42456e-05 6.33158e-05 -1 + outer loop + vertex -724.619 160.744 -0.000281863 + vertex -730.307 166.571 -0.000107727 + vertex -720.62 161.339 -0.00010724 + endloop + endfacet + facet normal 3.42893e-05 6.33584e-05 -1 + outer loop + vertex -734.361 166.005 -0.000282542 + vertex -730.307 166.571 -0.000107727 + vertex -724.619 160.744 -0.000281863 + endloop + endfacet + facet normal 3.46071e-05 6.10791e-05 -1 + outer loop + vertex -734.361 166.005 -0.000282542 + vertex -739.885 171.991 -0.000108075 + vertex -730.307 166.571 -0.000107727 + endloop + endfacet + facet normal 3.42562e-05 6.07553e-05 -1 + outer loop + vertex -743.994 171.456 -0.000281399 + vertex -739.885 171.991 -0.000108075 + vertex -734.361 166.005 -0.000282542 + endloop + endfacet + facet normal 6.37321e-05 0.000112852 -1 + outer loop + vertex -738.412 165.368 -0.000612639 + vertex -743.994 171.456 -0.000281399 + vertex -734.361 166.005 -0.000282542 + endloop + endfacet + facet normal 6.31352e-05 0.000116648 -1 + outer loop + vertex -738.412 165.368 -0.000612639 + vertex -734.361 166.005 -0.000282542 + vertex -728.617 160.077 -0.000611431 + endloop + endfacet + facet normal 6.37583e-05 0.000112876 -1 + outer loop + vertex -748.1 170.851 -0.000611508 + vertex -743.994 171.456 -0.000281399 + vertex -738.412 165.368 -0.000612639 + endloop + endfacet + facet normal 9.44987e-05 0.000167198 -1 + outer loop + vertex -742.402 164.653 -0.00110933 + vertex -748.1 170.851 -0.000611508 + vertex -738.412 165.368 -0.000612639 + endloop + endfacet + facet normal 9.3481e-05 0.000172873 -1 + outer loop + vertex -742.402 164.653 -0.00110933 + vertex -738.412 165.368 -0.000612639 + vertex -732.554 159.332 -0.0011085 + endloop + endfacet + facet normal 9.47353e-05 0.000167416 -1 + outer loop + vertex -752.145 170.168 -0.00110899 + vertex -748.1 170.851 -0.000611508 + vertex -742.402 164.653 -0.00110933 + endloop + endfacet + facet normal 0.000114976 0.000203173 -1 + outer loop + vertex -746.297 163.844 -0.00172147 + vertex -752.145 170.168 -0.00110899 + vertex -742.402 164.653 -0.00110933 + endloop + endfacet + facet normal 0.000113514 0.000210216 -1 + outer loop + vertex -746.297 163.844 -0.00172147 + vertex -742.402 164.653 -0.00110933 + vertex -736.395 158.495 -0.00172184 + endloop + endfacet + facet normal 0.000131644 0.000243779 -1 + outer loop + vertex -740.147 157.54 -0.00244857 + vertex -746.297 163.844 -0.00172147 + vertex -736.395 158.495 -0.00172184 + endloop + endfacet + facet normal 0.000131449 0.000243589 -1 + outer loop + vertex -750.1 162.917 -0.00244725 + vertex -746.297 163.844 -0.00172147 + vertex -740.147 157.54 -0.00244857 + endloop + endfacet + facet normal 0.000133428 0.000235475 -1 + outer loop + vertex -750.1 162.917 -0.00244725 + vertex -756.092 169.39 -0.00172231 + vertex -746.297 163.844 -0.00172147 + endloop + endfacet + facet normal 0.000135091 0.000237014 -1 + outer loop + vertex -759.946 168.492 -0.00245599 + vertex -756.092 169.39 -0.00172231 + vertex -750.1 162.917 -0.00244725 + endloop + endfacet + facet normal 0.00019941 0.000350607 -1 + outer loop + vertex -753.833 161.827 -0.00357355 + vertex -759.946 168.492 -0.00245599 + vertex -750.1 162.917 -0.00244725 + endloop + endfacet + facet normal 0.000195918 0.000362572 -1 + outer loop + vertex -753.833 161.827 -0.00357355 + vertex -750.1 162.917 -0.00244725 + vertex -743.828 156.424 -0.00357252 + endloop + endfacet + facet normal 0.000198336 0.000349621 -1 + outer loop + vertex -763.73 167.429 -0.00357806 + vertex -759.946 168.492 -0.00245599 + vertex -753.833 161.827 -0.00357355 + endloop + endfacet + facet normal 0.000325141 0.000573665 -1 + outer loop + vertex -757.518 160.522 -0.00552058 + vertex -763.73 167.429 -0.00357806 + vertex -753.833 161.827 -0.00357355 + endloop + endfacet + facet normal 0.000319104 0.000590713 -1 + outer loop + vertex -757.518 160.522 -0.00552058 + vertex -753.833 161.827 -0.00357355 + vertex -747.462 155.092 -0.00551937 + endloop + endfacet + facet normal 0.000324583 0.000573164 -1 + outer loop + vertex -767.464 166.149 -0.00552375 + vertex -763.73 167.429 -0.00357806 + vertex -757.518 160.522 -0.00552058 + endloop + endfacet + facet normal 0.000384681 0.000679391 -1 + outer loop + vertex -761.133 158.942 -0.00798442 + vertex -767.464 166.149 -0.00552375 + vertex -757.518 160.522 -0.00552058 + endloop + endfacet + facet normal 0.000377533 0.000695746 -1 + outer loop + vertex -761.133 158.942 -0.00798442 + vertex -757.518 160.522 -0.00552058 + vertex -751.03 153.488 -0.00796524 + endloop + endfacet + facet normal 1.4029e-05 2.24685e-05 -1 + outer loop + vertex -754.467 151.555 -0.00805688 + vertex -761.133 158.942 -0.00798442 + vertex -751.03 153.488 -0.00796524 + endloop + endfacet + facet normal 5.49734e-06 1.47696e-05 -1 + outer loop + vertex -764.616 157.034 -0.00803175 + vertex -761.133 158.942 -0.00798442 + vertex -754.467 151.555 -0.00805688 + endloop + endfacet + facet normal -0.000990773 -0.00183076 -0.999998 + outer loop + vertex -757.708 149.268 -0.000659758 + vertex -764.616 157.034 -0.00803175 + vertex -754.467 151.555 -0.00805688 + endloop + endfacet + facet normal -0.000966324 -0.00186541 -0.999998 + outer loop + vertex -757.708 149.268 -0.000659758 + vertex -754.467 151.555 -0.00805688 + vertex -747.402 143.955 -0.000706493 + endloop + endfacet + facet normal -0.00252309 -0.00488479 -0.999985 + outer loop + vertex -750.299 141.274 0.0196984 + vertex -757.708 149.268 -0.000659758 + vertex -747.402 143.955 -0.000706493 + endloop + endfacet + facet normal -0.00253579 -0.00489656 -0.999985 + outer loop + vertex -760.644 146.607 0.0198175 + vertex -757.708 149.268 -0.000659758 + vertex -750.299 141.274 0.0196984 + endloop + endfacet + facet normal -0.00465667 -0.00901061 -0.999949 + outer loop + vertex -752.79 138.225 0.0587756 + vertex -760.644 146.607 0.0198175 + vertex -750.299 141.274 0.0196984 + endloop + endfacet + facet normal -0.00450543 -0.00913414 -0.999948 + outer loop + vertex -752.79 138.225 0.0587756 + vertex -750.299 141.274 0.0196984 + vertex -742.314 133.064 0.0587179 + endloop + endfacet + facet normal -0.00812098 -0.0164731 -0.999831 + outer loop + vertex -744.318 129.663 0.131031 + vertex -752.79 138.225 0.0587756 + vertex -742.314 133.064 0.0587179 + endloop + endfacet + facet normal -0.00813817 -0.0164901 -0.999831 + outer loop + vertex -754.828 134.835 0.131263 + vertex -752.79 138.225 0.0587756 + vertex -744.318 129.663 0.131031 + endloop + endfacet + facet normal -0.0159448 -0.0323514 -0.999349 + outer loop + vertex -745.973 125.985 0.276508 + vertex -754.828 134.835 0.131263 + vertex -744.318 129.663 0.131031 + endloop + endfacet + facet normal -0.015242 -0.0326676 -0.99935 + outer loop + vertex -745.973 125.985 0.276508 + vertex -744.318 129.663 0.131031 + vertex -735.371 120.998 0.277823 + endloop + endfacet + facet normal -0.0297988 -0.0636144 -0.99753 + outer loop + vertex -736.925 117.117 0.571752 + vertex -745.973 125.985 0.276508 + vertex -735.371 120.998 0.277823 + endloop + endfacet + facet normal -0.0303818 -0.0642074 -0.997474 + outer loop + vertex -747.555 122.116 0.57371 + vertex -745.973 125.985 0.276508 + vertex -736.925 117.117 0.571752 + endloop + endfacet + facet normal -0.0531577 -0.112636 -0.992213 + outer loop + vertex -738.72 113.123 1.12125 + vertex -747.555 122.116 0.57371 + vertex -736.925 117.117 0.571752 + endloop + endfacet + facet normal -0.0509408 -0.113633 -0.992216 + outer loop + vertex -738.72 113.123 1.12125 + vertex -736.925 117.117 0.571752 + vertex -728.046 108.307 1.12478 + endloop + endfacet + facet normal -0.0508294 -0.113521 -0.992234 + outer loop + vertex -728.046 108.307 1.12478 + vertex -736.925 117.117 0.571752 + vertex -726.263 112.315 0.574966 + endloop + endfacet + facet normal -0.0532206 -0.112697 -0.992203 + outer loop + vertex -749.382 118.146 1.12267 + vertex -747.555 122.116 0.57371 + vertex -738.72 113.123 1.12125 + endloop + endfacet + facet normal -0.0550165 -0.11187 -0.992199 + outer loop + vertex -749.382 118.146 1.12267 + vertex -758.124 127.31 0.574138 + vertex -747.555 122.116 0.57371 + endloop + endfacet + facet normal -0.0312768 -0.0635622 -0.997488 + outer loop + vertex -758.124 127.31 0.574138 + vertex -756.513 131.167 0.277859 + vertex -747.555 122.116 0.57371 + endloop + endfacet + facet normal -0.0323258 -0.0631233 -0.997482 + outer loop + vertex -758.124 127.31 0.574138 + vertex -766.962 136.537 0.276669 + vertex -756.513 131.167 0.277859 + endloop + endfacet + facet normal -0.0164714 -0.0322729 -0.999343 + outer loop + vertex -766.962 136.537 0.276669 + vertex -765.25 140.198 0.130223 + vertex -756.513 131.167 0.277859 + endloop + endfacet + facet normal -0.0165371 -0.0323365 -0.99934 + outer loop + vertex -756.513 131.167 0.277859 + vertex -765.25 140.198 0.130223 + vertex -754.828 134.835 0.131263 + endloop + endfacet + facet normal -0.00820045 -0.0161328 -0.999836 + outer loop + vertex -765.25 140.198 0.130223 + vertex -763.176 143.575 0.0587118 + vertex -754.828 134.835 0.131263 + endloop + endfacet + facet normal -0.00857294 -0.015904 -0.999837 + outer loop + vertex -765.25 140.198 0.130223 + vertex -773.446 149.114 0.0586741 + vertex -763.176 143.575 0.0587118 + endloop + endfacet + facet normal -0.00477701 -0.00886504 -0.999949 + outer loop + vertex -773.446 149.114 0.0586741 + vertex -770.882 152.131 0.0196757 + vertex -763.176 143.575 0.0587118 + endloop + endfacet + facet normal -0.00476176 -0.00885131 -0.999949 + outer loop + vertex -763.176 143.575 0.0587118 + vertex -770.882 152.131 0.0196757 + vertex -760.644 146.607 0.0198175 + endloop + endfacet + facet normal -0.00256992 -0.00478887 -0.999985 + outer loop + vertex -770.882 152.131 0.0196757 + vertex -767.9 154.77 -0.000625074 + vertex -760.644 146.607 0.0198175 + endloop + endfacet + facet normal -0.00264559 -0.00470337 -0.999985 + outer loop + vertex -770.882 152.131 0.0196757 + vertex -777.984 160.47 -0.000756052 + vertex -767.9 154.77 -0.000625074 + endloop + endfacet + facet normal -0.00100207 -0.00179577 -0.999998 + outer loop + vertex -777.984 160.47 -0.000756052 + vertex -774.658 162.711 -0.00811446 + vertex -767.9 154.77 -0.000625074 + endloop + endfacet + facet normal -0.0010117 -0.00180396 -0.999998 + outer loop + vertex -767.9 154.77 -0.000625074 + vertex -774.658 162.711 -0.00811446 + vertex -764.616 157.034 -0.00803175 + endloop + endfacet + facet normal 3.02513e-05 3.89388e-05 -1 + outer loop + vertex -774.658 162.711 -0.00811446 + vertex -771.123 164.592 -0.00793429 + vertex -764.616 157.034 -0.00803175 + endloop + endfacet + facet normal 3.01952e-05 3.90442e-05 -1 + outer loop + vertex -774.658 162.711 -0.00811446 + vertex -781.006 170.446 -0.00800414 + vertex -771.123 164.592 -0.00793429 + endloop + endfacet + facet normal 0.000394935 0.000654789 -1 + outer loop + vertex -781.006 170.446 -0.00800414 + vertex -777.299 171.978 -0.0055372 + vertex -771.123 164.592 -0.00793429 + endloop + endfacet + facet normal 0.00038409 0.000645721 -1 + outer loop + vertex -771.123 164.592 -0.00793429 + vertex -777.299 171.978 -0.0055372 + vertex -767.464 166.149 -0.00552375 + endloop + endfacet + facet normal 0.000332982 0.000559492 -1 + outer loop + vertex -777.299 171.978 -0.0055372 + vertex -773.521 173.235 -0.00357601 + vertex -767.464 166.149 -0.00552375 + endloop + endfacet + facet normal 0.00033943 0.000540113 -1 + outer loop + vertex -777.299 171.978 -0.0055372 + vertex -783.133 179.228 -0.00360156 + vertex -773.521 173.235 -0.00357601 + endloop + endfacet + facet normal 0.000207231 0.000328093 -1 + outer loop + vertex -783.133 179.228 -0.00360156 + vertex -779.252 180.239 -0.00246553 + vertex -773.521 173.235 -0.00357601 + endloop + endfacet + facet normal 0.000204885 0.000326173 -1 + outer loop + vertex -773.521 173.235 -0.00357601 + vertex -779.252 180.239 -0.00246553 + vertex -769.688 174.272 -0.00245233 + endloop + endfacet + facet normal 0.000201226 0.000339692 -1 + outer loop + vertex -773.521 173.235 -0.00357601 + vertex -769.688 174.272 -0.00245233 + vertex -763.73 167.429 -0.00357806 + endloop + endfacet + facet normal 0.000139491 0.000221361 -1 + outer loop + vertex -779.252 180.239 -0.00246553 + vertex -775.297 181.084 -0.00172689 + vertex -769.688 174.272 -0.00245233 + endloop + endfacet + facet normal 0.000137815 0.000219981 -1 + outer loop + vertex -769.688 174.272 -0.00245233 + vertex -775.297 181.084 -0.00172689 + vertex -765.783 175.143 -0.00172262 + endloop + endfacet + facet normal 0.000135723 0.000229367 -1 + outer loop + vertex -769.688 174.272 -0.00245233 + vertex -765.783 175.143 -0.00172262 + vertex -759.946 168.492 -0.00245599 + endloop + endfacet + facet normal 0.000119046 0.000189925 -1 + outer loop + vertex -775.297 181.084 -0.00172689 + vertex -771.254 181.799 -0.00110968 + vertex -765.783 175.143 -0.00172262 + endloop + endfacet + facet normal 0.00011815 0.000189188 -1 + outer loop + vertex -765.783 175.143 -0.00172262 + vertex -771.254 181.799 -0.00110968 + vertex -761.78 175.888 -0.00110874 + endloop + endfacet + facet normal 0.000116761 0.00019665 -1 + outer loop + vertex -765.783 175.143 -0.00172262 + vertex -761.78 175.888 -0.00110874 + vertex -756.092 169.39 -0.00172231 + endloop + endfacet + facet normal 0.000116673 0.000196573 -1 + outer loop + vertex -756.092 169.39 -0.00172231 + vertex -761.78 175.888 -0.00110874 + vertex -752.145 170.168 -0.00110899 + endloop + endfacet + facet normal 9.54295e-05 0.00016079 -1 + outer loop + vertex -761.78 175.888 -0.00110874 + vertex -757.675 176.537 -0.000612643 + vertex -752.145 170.168 -0.00110899 + endloop + endfacet + facet normal 9.6392e-05 0.000154702 -1 + outer loop + vertex -761.78 175.888 -0.00110874 + vertex -767.1 182.416 -0.000611603 + vertex -757.675 176.537 -0.000612643 + endloop + endfacet + facet normal 6.49601e-05 0.000104314 -1 + outer loop + vertex -767.1 182.416 -0.000611603 + vertex -762.88 182.953 -0.000281436 + vertex -757.675 176.537 -0.000612643 + endloop + endfacet + facet normal 6.50067e-05 0.000104352 -1 + outer loop + vertex -757.675 176.537 -0.000612643 + vertex -762.88 182.953 -0.000281436 + vertex -753.512 177.107 -0.000282458 + endloop + endfacet + facet normal 6.44602e-05 0.00010834 -1 + outer loop + vertex -757.675 176.537 -0.000612643 + vertex -753.512 177.107 -0.000282458 + vertex -748.1 170.851 -0.000611508 + endloop + endfacet + facet normal 3.49207e-05 5.61371e-05 -1 + outer loop + vertex -762.88 182.953 -0.000281436 + vertex -758.661 183.424 -0.000107659 + vertex -753.512 177.107 -0.000282458 + endloop + endfacet + facet normal 3.52675e-05 5.64199e-05 -1 + outer loop + vertex -753.512 177.107 -0.000282458 + vertex -758.661 183.424 -0.000107659 + vertex -749.35 177.61 -0.000107338 + endloop + endfacet + facet normal 3.49882e-05 5.87335e-05 -1 + outer loop + vertex -753.512 177.107 -0.000282458 + vertex -749.35 177.61 -0.000107338 + vertex -743.994 171.456 -0.000281399 + endloop + endfacet + facet normal 1.52442e-05 2.43558e-05 -1 + outer loop + vertex -758.661 183.424 -0.000107659 + vertex -754.496 183.837 -3.41182e-05 + vertex -749.35 177.61 -0.000107338 + endloop + endfacet + facet normal 1.51093e-05 2.42443e-05 -1 + outer loop + vertex -749.35 177.61 -0.000107338 + vertex -754.496 183.837 -3.41182e-05 + vertex -745.232 178.052 -3.43973e-05 + endloop + endfacet + facet normal 1.49872e-05 2.53802e-05 -1 + outer loop + vertex -749.35 177.61 -0.000107338 + vertex -745.232 178.052 -3.43973e-05 + vertex -739.885 171.991 -0.000108075 + endloop + endfacet + facet normal 1.52158e-05 2.55819e-05 -1 + outer loop + vertex -739.885 171.991 -0.000108075 + vertex -745.232 178.052 -3.43973e-05 + vertex -735.819 172.461 -3.4205e-05 + endloop + endfacet + facet normal 5.42542e-06 9.09948e-06 -1 + outer loop + vertex -745.232 178.052 -3.43973e-05 + vertex -741.167 178.437 -8.83888e-06 + vertex -735.819 172.461 -3.4205e-05 + endloop + endfacet + facet normal 5.4627e-06 8.70532e-06 -1 + outer loop + vertex -745.232 178.052 -3.43973e-05 + vertex -750.388 184.198 -9.05839e-06 + vertex -741.167 178.437 -8.83888e-06 + endloop + endfacet + facet normal 1.53554e-06 2.41963e-06 -1 + outer loop + vertex -750.388 184.198 -9.05839e-06 + vertex -746.316 184.529 -2.00573e-06 + vertex -741.167 178.437 -8.83888e-06 + endloop + endfacet + facet normal 1.48827e-06 2.37968e-06 -1 + outer loop + vertex -741.167 178.437 -8.83888e-06 + vertex -746.316 184.529 -2.00573e-06 + vertex -737.13 178.791 -1.98874e-06 + endloop + endfacet + facet normal 1.47568e-06 2.52311e-06 -1 + outer loop + vertex -741.167 178.437 -8.83888e-06 + vertex -737.13 178.791 -1.98874e-06 + vertex -731.798 172.874 -9.04889e-06 + endloop + endfacet + facet normal 3.63134e-07 5.78397e-07 -1 + outer loop + vertex -746.316 184.529 -2.00573e-06 + vertex -742.405 184.897 -3.72636e-07 + vertex -737.13 178.791 -1.98874e-06 + endloop + endfacet + facet normal 3.63204e-07 5.78458e-07 -1 + outer loop + vertex -737.13 178.791 -1.98874e-06 + vertex -742.405 184.897 -3.72636e-07 + vertex -733.245 179.175 -3.55744e-07 + endloop + endfacet + facet normal 3.59537e-07 6.15565e-07 -1 + outer loop + vertex -737.13 178.791 -1.98874e-06 + vertex -733.245 179.175 -3.55744e-07 + vertex -727.81 173.257 -2.04407e-06 + endloop + endfacet + facet normal 3.66768e-07 6.22207e-07 -1 + outer loop + vertex -727.81 173.257 -2.04407e-06 + vertex -733.245 179.175 -3.55744e-07 + vertex -723.982 173.676 -3.79758e-07 + endloop + endfacet + facet normal 8.45834e-08 1.46853e-07 -1 + outer loop + vertex -733.245 179.175 -3.55744e-07 + vertex -729.981 179.717 -7.53775e-14 + vertex -723.982 173.676 -3.79758e-07 + endloop + endfacet + facet normal 8.60585e-08 1.37969e-07 -1 + outer loop + vertex -733.245 179.175 -3.55744e-07 + vertex -738.917 185.291 -7.48276e-14 + vertex -729.981 179.717 -7.53775e-14 + endloop + endfacet + facet normal 9.07511e-08 1.4232e-07 -1 + outer loop + vertex -742.405 184.897 -3.72636e-07 + vertex -738.917 185.291 -7.48276e-14 + vertex -733.245 179.175 -3.55744e-07 + endloop + endfacet + facet normal 9.11801e-08 1.38524e-07 -1 + outer loop + vertex -742.405 184.897 -3.72636e-07 + vertex -748.154 191.371 -7.42277e-14 + vertex -738.917 185.291 -7.48276e-14 + endloop + endfacet + facet normal 9.26119e-08 1.39796e-07 -1 + outer loop + vertex -751.384 190.812 -3.77211e-07 + vertex -748.154 191.371 -7.42277e-14 + vertex -742.405 184.897 -3.72636e-07 + endloop + endfacet + facet normal 9.35678e-08 1.34266e-07 -1 + outer loop + vertex -751.384 190.812 -3.77211e-07 + vertex -756.831 197.418 -7.36311e-14 + vertex -748.154 191.371 -7.42277e-14 + endloop + endfacet + facet normal 9.50016e-08 1.35448e-07 -1 + outer loop + vertex -760.049 196.864 -3.8074e-07 + vertex -756.831 197.418 -7.36311e-14 + vertex -751.384 190.812 -3.77211e-07 + endloop + endfacet + facet normal 3.74917e-07 5.36254e-07 -1 + outer loop + vertex -755.29 190.449 -2.03668e-06 + vertex -760.049 196.864 -3.8074e-07 + vertex -751.384 190.812 -3.77211e-07 + endloop + endfacet + facet normal 3.72728e-07 5.59778e-07 -1 + outer loop + vertex -755.29 190.449 -2.03668e-06 + vertex -751.384 190.812 -3.77211e-07 + vertex -746.316 184.529 -2.00573e-06 + endloop + endfacet + facet normal 3.70615e-07 5.33063e-07 -1 + outer loop + vertex -763.978 196.542 -2.00851e-06 + vertex -760.049 196.864 -3.8074e-07 + vertex -755.29 190.449 -2.03668e-06 + endloop + endfacet + facet normal 1.54061e-06 2.20129e-06 -1 + outer loop + vertex -759.391 190.145 -9.02166e-06 + vertex -763.978 196.542 -2.00851e-06 + vertex -755.29 190.449 -2.03668e-06 + endloop + endfacet + facet normal 1.53149e-06 2.32442e-06 -1 + outer loop + vertex -759.391 190.145 -9.02166e-06 + vertex -755.29 190.449 -2.03668e-06 + vertex -750.388 184.198 -9.05839e-06 + endloop + endfacet + facet normal 5.38308e-06 8.15461e-06 -1 + outer loop + vertex -754.496 183.837 -3.41182e-05 + vertex -759.391 190.145 -9.02166e-06 + vertex -750.388 184.198 -9.05839e-06 + endloop + endfacet + facet normal 5.29096e-06 8.08314e-06 -1 + outer loop + vertex -763.54 189.815 -3.36469e-05 + vertex -759.391 190.145 -9.02166e-06 + vertex -754.496 183.837 -3.41182e-05 + endloop + endfacet + facet normal 5.33305e-06 7.55494e-06 -1 + outer loop + vertex -763.54 189.815 -3.36469e-05 + vertex -768.114 196.294 -9.08965e-06 + vertex -759.391 190.145 -9.02166e-06 + endloop + endfacet + facet normal 5.48921e-06 7.66518e-06 -1 + outer loop + vertex -772.3 196.007 -3.42698e-05 + vertex -768.114 196.294 -9.08965e-06 + vertex -763.54 189.815 -3.36469e-05 + endloop + endfacet + facet normal 1.56966e-05 2.21059e-05 -1 + outer loop + vertex -767.747 189.433 -0.000108129 + vertex -772.3 196.007 -3.42698e-05 + vertex -763.54 189.815 -3.36469e-05 + endloop + endfacet + facet normal 1.55729e-05 2.34701e-05 -1 + outer loop + vertex -767.747 189.433 -0.000108129 + vertex -763.54 189.815 -3.36469e-05 + vertex -758.661 183.424 -0.000107659 + endloop + endfacet + facet normal 1.51689e-05 2.17405e-05 -1 + outer loop + vertex -776.542 195.646 -0.000106463 + vertex -772.3 196.007 -3.42698e-05 + vertex -767.747 189.433 -0.000108129 + endloop + endfacet + facet normal 3.55973e-05 5.06581e-05 -1 + outer loop + vertex -772.011 188.988 -0.00028247 + vertex -776.542 195.646 -0.000106463 + vertex -767.747 189.433 -0.000108129 + endloop + endfacet + facet normal 3.53235e-05 5.32767e-05 -1 + outer loop + vertex -772.011 188.988 -0.00028247 + vertex -767.747 189.433 -0.000108129 + vertex -762.88 182.953 -0.000281436 + endloop + endfacet + facet normal 3.64067e-05 5.12089e-05 -1 + outer loop + vertex -780.805 195.21 -0.000283969 + vertex -776.542 195.646 -0.000106463 + vertex -772.011 188.988 -0.00028247 + endloop + endfacet + facet normal 6.64539e-05 9.36714e-05 -1 + outer loop + vertex -776.265 188.473 -0.000613436 + vertex -780.805 195.21 -0.000283969 + vertex -772.011 188.988 -0.00028247 + endloop + endfacet + facet normal 6.57801e-05 9.92389e-05 -1 + outer loop + vertex -776.265 188.473 -0.000613436 + vertex -772.011 188.988 -0.00028247 + vertex -767.1 182.416 -0.000611603 + endloop + endfacet + facet normal 9.79453e-05 0.000147913 -1 + outer loop + vertex -771.254 181.799 -0.00110968 + vertex -776.265 188.473 -0.000613436 + vertex -767.1 182.416 -0.000611603 + endloop + endfacet + facet normal 9.8582e-05 0.000148391 -1 + outer loop + vertex -780.448 187.88 -0.00111374 + vertex -776.265 188.473 -0.000613436 + vertex -771.254 181.799 -0.00110968 + endloop + endfacet + facet normal 9.9799e-05 0.000139802 -1 + outer loop + vertex -780.448 187.88 -0.00111374 + vertex -785.054 194.706 -0.000619067 + vertex -776.265 188.473 -0.000613436 + endloop + endfacet + facet normal 0.000102577 0.000141676 -1 + outer loop + vertex -789.244 194.143 -0.00112869 + vertex -785.054 194.706 -0.000619067 + vertex -780.448 187.88 -0.00111374 + endloop + endfacet + facet normal 0.000123704 0.000171349 -1 + outer loop + vertex -784.531 187.194 -0.00173643 + vertex -789.244 194.143 -0.00112869 + vertex -780.448 187.88 -0.00111374 + endloop + endfacet + facet normal 0.000121822 0.000182553 -1 + outer loop + vertex -784.531 187.194 -0.00173643 + vertex -780.448 187.88 -0.00111374 + vertex -775.297 181.084 -0.00172689 + endloop + endfacet + facet normal 0.000129747 0.000175446 -1 + outer loop + vertex -793.356 193.508 -0.00177368 + vertex -789.244 194.143 -0.00112869 + vertex -784.531 187.194 -0.00173643 + endloop + endfacet + facet normal 0.000149523 0.000203088 -1 + outer loop + vertex -788.519 186.386 -0.00249667 + vertex -793.356 193.508 -0.00177368 + vertex -784.531 187.194 -0.00173643 + endloop + endfacet + facet normal 0.000146844 0.000216308 -1 + outer loop + vertex -788.519 186.386 -0.00249667 + vertex -784.531 187.194 -0.00173643 + vertex -779.252 180.239 -0.00246553 + endloop + endfacet + facet normal 0.000155774 0.000207333 -1 + outer loop + vertex -797.403 192.759 -0.0025594 + vertex -793.356 193.508 -0.00177368 + vertex -788.519 186.386 -0.00249667 + endloop + endfacet + facet normal 0.000222176 0.00029991 -1 + outer loop + vertex -792.451 185.412 -0.00366272 + vertex -797.403 192.759 -0.0025594 + vertex -788.519 186.386 -0.00249667 + endloop + endfacet + facet normal 0.000217663 0.000318125 -1 + outer loop + vertex -792.451 185.412 -0.00366272 + vertex -788.519 186.386 -0.00249667 + vertex -783.133 179.228 -0.00360156 + endloop + endfacet + facet normal 0.000350688 0.000518593 -1 + outer loop + vertex -786.959 177.996 -0.00558203 + vertex -792.451 185.412 -0.00366272 + vertex -783.133 179.228 -0.00360156 + endloop + endfacet + facet normal 0.000355673 0.000522285 -1 + outer loop + vertex -796.337 184.217 -0.0056686 + vertex -792.451 185.412 -0.00366272 + vertex -786.959 177.996 -0.00558203 + endloop + endfacet + facet normal 0.000411958 0.000607139 -1 + outer loop + vertex -790.711 176.49 -0.00804231 + vertex -796.337 184.217 -0.0056686 + vertex -786.959 177.996 -0.00558203 + endloop + endfacet + facet normal 0.000400225 0.000636366 -1 + outer loop + vertex -790.711 176.49 -0.00804231 + vertex -786.959 177.996 -0.00558203 + vertex -781.006 170.446 -0.00800414 + endloop + endfacet + facet normal 1.88624e-05 2.39732e-05 -1 + outer loop + vertex -784.577 168.586 -0.00811609 + vertex -790.711 176.49 -0.00804231 + vertex -781.006 170.446 -0.00800414 + endloop + endfacet + facet normal 4.07241e-05 4.09395e-05 -1 + outer loop + vertex -794.335 174.661 -0.00826478 + vertex -790.711 176.49 -0.00804231 + vertex -784.577 168.586 -0.00811609 + endloop + endfacet + facet normal -0.00104824 -0.00170826 -0.999998 + outer loop + vertex -787.949 166.37 -0.000795884 + vertex -794.335 174.661 -0.00826478 + vertex -784.577 168.586 -0.00811609 + endloop + endfacet + facet normal -0.00102678 -0.00174091 -0.999998 + outer loop + vertex -787.949 166.37 -0.000795884 + vertex -784.577 168.586 -0.00811609 + vertex -777.984 160.47 -0.000756052 + endloop + endfacet + facet normal -0.00275235 -0.00465529 -0.999985 + outer loop + vertex -780.999 157.849 0.0197426 + vertex -787.949 166.37 -0.000795884 + vertex -777.984 160.47 -0.000756052 + endloop + endfacet + facet normal -0.00269256 -0.00460653 -0.999986 + outer loop + vertex -791.012 163.773 0.0194128 + vertex -787.949 166.37 -0.000795884 + vertex -780.999 157.849 0.0197426 + endloop + endfacet + facet normal -0.00507243 -0.00862889 -0.99995 + outer loop + vertex -783.601 154.849 0.0588284 + vertex -791.012 163.773 0.0194128 + vertex -780.999 157.849 0.0197426 + endloop + endfacet + facet normal -0.00494915 -0.00873577 -0.99995 + outer loop + vertex -783.601 154.849 0.0588284 + vertex -780.999 157.849 0.0197426 + vertex -773.446 149.114 0.0586741 + endloop + endfacet + facet normal -0.0089712 -0.015857 -0.999834 + outer loop + vertex -775.551 145.747 0.130952 + vertex -783.601 154.849 0.0588284 + vertex -773.446 149.114 0.0586741 + endloop + endfacet + facet normal -0.00893017 -0.0158207 -0.999835 + outer loop + vertex -785.741 151.494 0.131032 + vertex -783.601 154.849 0.0588284 + vertex -775.551 145.747 0.130952 + endloop + endfacet + facet normal -0.0178268 -0.0315958 -0.999342 + outer loop + vertex -777.29 142.093 0.277493 + vertex -785.741 151.494 0.131032 + vertex -775.551 145.747 0.130952 + endloop + endfacet + facet normal -0.0172317 -0.0318792 -0.999343 + outer loop + vertex -777.29 142.093 0.277493 + vertex -775.551 145.747 0.130952 + vertex -766.962 136.537 0.276669 + endloop + endfacet + facet normal -0.0339384 -0.062931 -0.997441 + outer loop + vertex -768.59 132.689 0.574847 + vertex -777.29 142.093 0.277493 + vertex -766.962 136.537 0.276669 + endloop + endfacet + facet normal -0.0333785 -0.0624147 -0.997492 + outer loop + vertex -778.938 138.253 0.572921 + vertex -777.29 142.093 0.277493 + vertex -768.59 132.689 0.574847 + endloop + endfacet + facet normal -0.0589278 -0.109923 -0.992192 + outer loop + vertex -770.44 128.747 1.12136 + vertex -778.938 138.253 0.572921 + vertex -768.59 132.689 0.574847 + endloop + endfacet + facet normal -0.0568451 -0.110903 -0.992204 + outer loop + vertex -770.44 128.747 1.12136 + vertex -768.59 132.689 0.574847 + vertex -759.972 123.358 1.12401 + endloop + endfacet + facet normal -0.057252 -0.111275 -0.992139 + outer loop + vertex -759.972 123.358 1.12401 + vertex -768.59 132.689 0.574847 + vertex -758.124 127.31 0.574138 + endloop + endfacet + facet normal -0.0598838 -0.110769 -0.99204 + outer loop + vertex -780.809 134.334 1.12347 + vertex -778.938 138.253 0.572921 + vertex -770.44 128.747 1.12136 + endloop + endfacet + facet normal -0.0619975 -0.109758 -0.992023 + outer loop + vertex -780.809 134.334 1.12347 + vertex -789.183 144.021 0.575069 + vertex -778.938 138.253 0.572921 + endloop + endfacet + facet normal -0.0354511 -0.0626007 -0.997409 + outer loop + vertex -789.183 144.021 0.575069 + vertex -787.512 147.848 0.275473 + vertex -778.938 138.253 0.572921 + endloop + endfacet + facet normal -0.036798 -0.0620113 -0.997397 + outer loop + vertex -789.183 144.021 0.575069 + vertex -797.617 153.809 0.277659 + vertex -787.512 147.848 0.275473 + endloop + endfacet + facet normal -0.0187155 -0.0313585 -0.999333 + outer loop + vertex -797.617 153.809 0.277659 + vertex -795.823 157.445 0.129972 + vertex -787.512 147.848 0.275473 + endloop + endfacet + facet normal -0.0180802 -0.0308088 -0.999362 + outer loop + vertex -787.512 147.848 0.275473 + vertex -795.823 157.445 0.129972 + vertex -785.741 151.494 0.131032 + endloop + endfacet + facet normal -0.00905277 -0.0155149 -0.999839 + outer loop + vertex -795.823 157.445 0.129972 + vertex -793.651 160.79 0.0584057 + vertex -785.741 151.494 0.131032 + endloop + endfacet + facet normal -0.00950539 -0.015221 -0.999839 + outer loop + vertex -795.823 157.445 0.129972 + vertex -803.514 166.931 0.0586786 + vertex -793.651 160.79 0.0584057 + endloop + endfacet + facet normal -0.0053052 -0.00847559 -0.99995 + outer loop + vertex -803.514 166.931 0.0586786 + vertex -800.846 169.896 0.0193918 + vertex -793.651 160.79 0.0584057 + endloop + endfacet + facet normal -0.00524566 -0.00842855 -0.999951 + outer loop + vertex -793.651 160.79 0.0584057 + vertex -800.846 169.896 0.0193918 + vertex -791.012 163.773 0.0194128 + endloop + endfacet + facet normal -0.00279853 -0.00449819 -0.999986 + outer loop + vertex -800.846 169.896 0.0193918 + vertex -797.743 172.469 -0.000865558 + vertex -791.012 163.773 0.0194128 + endloop + endfacet + facet normal -0.00289502 -0.00438185 -0.999986 + outer loop + vertex -800.846 169.896 0.0193918 + vertex -807.266 178.793 -0.00100761 + vertex -797.743 172.469 -0.000865558 + endloop + endfacet + facet normal -0.00108788 -0.00166061 -0.999998 + outer loop + vertex -807.266 178.793 -0.00100761 + vertex -803.813 180.952 -0.00834832 + vertex -797.743 172.469 -0.000865558 + endloop + endfacet + facet normal -0.00109837 -0.00166812 -0.999998 + outer loop + vertex -797.743 172.469 -0.000865558 + vertex -803.813 180.952 -0.00834832 + vertex -794.335 174.661 -0.00826478 + endloop + endfacet + facet normal 3.53845e-05 4.00318e-05 -1 + outer loop + vertex -803.813 180.952 -0.00834832 + vertex -800.141 182.747 -0.00814651 + vertex -794.335 174.661 -0.00826478 + endloop + endfacet + facet normal 3.79851e-05 3.47115e-05 -1 + outer loop + vertex -803.813 180.952 -0.00834832 + vertex -809.196 189.273 -0.00826392 + vertex -800.141 182.747 -0.00814651 + endloop + endfacet + facet normal 0.000427495 0.00057512 -1 + outer loop + vertex -809.196 189.273 -0.00826392 + vertex -805.331 190.697 -0.00579308 + vertex -800.141 182.747 -0.00814651 + endloop + endfacet + facet normal 0.000428814 0.000575981 -1 + outer loop + vertex -800.141 182.747 -0.00814651 + vertex -805.331 190.697 -0.00579308 + vertex -796.337 184.217 -0.0056686 + endloop + endfacet + facet normal 0.000371925 0.000497019 -1 + outer loop + vertex -805.331 190.697 -0.00579308 + vertex -801.394 191.841 -0.00375987 + vertex -796.337 184.217 -0.0056686 + endloop + endfacet + facet normal 0.000381497 0.000464078 -1 + outer loop + vertex -805.331 190.697 -0.00579308 + vertex -809.904 198.542 -0.00389696 + vertex -801.394 191.841 -0.00375987 + endloop + endfacet + facet normal 0.000239812 0.000284125 -1 + outer loop + vertex -809.904 198.542 -0.00389696 + vertex -805.87 199.397 -0.00268653 + vertex -801.394 191.841 -0.00375987 + endloop + endfacet + facet normal 0.000236034 0.000281887 -1 + outer loop + vertex -801.394 191.841 -0.00375987 + vertex -805.87 199.397 -0.00268653 + vertex -797.403 192.759 -0.0025594 + endloop + endfacet + facet normal 0.000170369 0.000198137 -1 + outer loop + vertex -805.87 199.397 -0.00268653 + vertex -801.783 200.073 -0.00185623 + vertex -797.403 192.759 -0.0025594 + endloop + endfacet + facet normal 0.00017214 0.000187431 -1 + outer loop + vertex -805.87 199.397 -0.00268653 + vertex -809.868 206.774 -0.00199197 + vertex -801.783 200.073 -0.00185623 + endloop + endfacet + facet normal 0.000155433 0.000167274 -1 + outer loop + vertex -809.868 206.774 -0.00199197 + vertex -805.702 207.271 -0.00126145 + vertex -801.783 200.073 -0.00185623 + endloop + endfacet + facet normal 0.000143766 0.000160921 -1 + outer loop + vertex -801.783 200.073 -0.00185623 + vertex -805.702 207.271 -0.00126145 + vertex -797.634 200.63 -0.00117017 + endloop + endfacet + facet normal 0.000142505 0.000170323 -1 + outer loop + vertex -801.783 200.073 -0.00185623 + vertex -797.634 200.63 -0.00117017 + vertex -793.356 193.508 -0.00177368 + endloop + endfacet + facet normal 0.000123293 0.000136048 -1 + outer loop + vertex -805.702 207.271 -0.00126145 + vertex -801.436 207.695 -0.000677861 + vertex -797.634 200.63 -0.00117017 + endloop + endfacet + facet normal 0.000111905 0.000129918 -1 + outer loop + vertex -797.634 200.63 -0.00117017 + vertex -801.436 207.695 -0.000677861 + vertex -793.423 201.13 -0.000634054 + endloop + endfacet + facet normal 0.000111039 0.000137214 -1 + outer loop + vertex -797.634 200.63 -0.00117017 + vertex -793.423 201.13 -0.000634054 + vertex -789.244 194.143 -0.00112869 + endloop + endfacet + facet normal 7.8709e-05 8.9399e-05 -1 + outer loop + vertex -801.436 207.695 -0.000677861 + vertex -797.125 208.093 -0.00030293 + vertex -793.423 201.13 -0.000634054 + endloop + endfacet + facet normal 7.15335e-05 8.55844e-05 -1 + outer loop + vertex -793.423 201.13 -0.000634054 + vertex -797.125 208.093 -0.00030293 + vertex -789.179 201.607 -0.000289586 + endloop + endfacet + facet normal 7.10154e-05 9.0195e-05 -1 + outer loop + vertex -793.423 201.13 -0.000634054 + vertex -789.179 201.607 -0.000289586 + vertex -785.054 194.706 -0.000619067 + endloop + endfacet + facet normal 6.83499e-05 8.86017e-05 -1 + outer loop + vertex -785.054 194.706 -0.000619067 + vertex -789.179 201.607 -0.000289586 + vertex -780.805 195.21 -0.000283969 + endloop + endfacet + facet normal 3.75139e-05 4.8233e-05 -1 + outer loop + vertex -789.179 201.607 -0.000289586 + vertex -784.943 202.046 -0.000109537 + vertex -780.805 195.21 -0.000283969 + endloop + endfacet + facet normal 3.7748e-05 4.59738e-05 -1 + outer loop + vertex -789.179 201.607 -0.000289586 + vertex -792.867 208.492 -0.000112289 + vertex -784.943 202.046 -0.000109537 + endloop + endfacet + facet normal 1.68324e-05 2.02639e-05 -1 + outer loop + vertex -792.867 208.492 -0.000112289 + vertex -788.679 208.822 -3.51048e-05 + vertex -784.943 202.046 -0.000109537 + endloop + endfacet + facet normal 1.61778e-05 1.9903e-05 -1 + outer loop + vertex -784.943 202.046 -0.000109537 + vertex -788.679 208.822 -3.51048e-05 + vertex -780.728 202.396 -3.43618e-05 + endloop + endfacet + facet normal 1.61137e-05 2.06738e-05 -1 + outer loop + vertex -784.943 202.046 -0.000109537 + vertex -780.728 202.396 -3.43618e-05 + vertex -776.542 195.646 -0.000106463 + endloop + endfacet + facet normal 5.87075e-06 7.14894e-06 -1 + outer loop + vertex -788.679 208.822 -3.51048e-05 + vertex -784.527 209.021 -9.30332e-06 + vertex -780.728 202.396 -3.43618e-05 + endloop + endfacet + facet normal 5.62118e-06 7.00582e-06 -1 + outer loop + vertex -780.728 202.396 -3.43618e-05 + vertex -784.527 209.021 -9.30332e-06 + vertex -776.533 202.644 -9.05105e-06 + endloop + endfacet + facet normal 5.59958e-06 7.37185e-06 -1 + outer loop + vertex -780.728 202.396 -3.43618e-05 + vertex -776.533 202.644 -9.05105e-06 + vertex -772.3 196.007 -3.42698e-05 + endloop + endfacet + facet normal 1.67708e-06 2.06244e-06 -1 + outer loop + vertex -784.527 209.021 -9.30332e-06 + vertex -780.364 209.149 -2.0585e-06 + vertex -776.533 202.644 -9.05105e-06 + endloop + endfacet + facet normal 1.59581e-06 2.01458e-06 -1 + outer loop + vertex -776.533 202.644 -9.05105e-06 + vertex -780.364 209.149 -2.0585e-06 + vertex -772.346 202.813 -2.02726e-06 + endloop + endfacet + facet normal 1.59169e-06 2.11672e-06 -1 + outer loop + vertex -776.533 202.644 -9.05105e-06 + vertex -772.346 202.813 -2.02726e-06 + vertex -768.114 196.294 -9.08965e-06 + endloop + endfacet + facet normal 1.58558e-06 2.11276e-06 -1 + outer loop + vertex -768.114 196.294 -9.08965e-06 + vertex -772.346 202.813 -2.02726e-06 + vertex -763.978 196.542 -2.00851e-06 + endloop + endfacet + facet normal 3.85706e-07 5.11683e-07 -1 + outer loop + vertex -772.346 202.813 -2.02726e-06 + vertex -768.326 203.015 -3.73457e-07 + vertex -763.978 196.542 -2.00851e-06 + endloop + endfacet + facet normal 3.86812e-07 4.89662e-07 -1 + outer loop + vertex -772.346 202.813 -2.02726e-06 + vertex -776.227 209.237 -3.83037e-07 + vertex -768.326 203.015 -3.73457e-07 + endloop + endfacet + facet normal 1.0004e-07 1.25498e-07 -1 + outer loop + vertex -776.227 209.237 -3.83037e-07 + vertex -772.648 209.436 -7.24453e-14 + vertex -768.326 203.015 -3.73457e-07 + endloop + endfacet + facet normal 9.6328e-08 1.23e-07 -1 + outer loop + vertex -768.326 203.015 -3.73457e-07 + vertex -772.648 209.436 -7.24453e-14 + vertex -765.143 203.558 -7.30252e-14 + endloop + endfacet + facet normal 9.52441e-08 1.29347e-07 -1 + outer loop + vertex -768.326 203.015 -3.73457e-07 + vertex -765.143 203.558 -7.30252e-14 + vertex -760.049 196.864 -3.8074e-07 + endloop + endfacet + facet normal 1.00302e-07 1.20794e-07 -1 + outer loop + vertex -776.227 209.237 -3.83037e-07 + vertex -779.909 215.465 -7.18505e-14 + vertex -772.648 209.436 -7.24453e-14 + endloop + endfacet + facet normal 9.26134e-08 1.16249e-07 -1 + outer loop + vertex -783.802 215.379 -3.70537e-07 + vertex -779.909 215.465 -7.18505e-14 + vertex -776.227 209.237 -3.83037e-07 + endloop + endfacet + facet normal 3.94613e-07 4.88684e-07 -1 + outer loop + vertex -780.364 209.149 -2.0585e-06 + vertex -783.802 215.379 -3.70537e-07 + vertex -776.227 209.237 -3.83037e-07 + endloop + endfacet + facet normal 4.21694e-07 5.03628e-07 -1 + outer loop + vertex -787.768 215.075 -2.1959e-06 + vertex -783.802 215.379 -3.70537e-07 + vertex -780.364 209.149 -2.0585e-06 + endloop + endfacet + facet normal 4.20273e-07 5.22165e-07 -1 + outer loop + vertex -787.768 215.075 -2.1959e-06 + vertex -790.838 220.555 -6.25173e-07 + vertex -783.802 215.379 -3.70537e-07 + endloop + endfacet + facet normal 1.26565e-07 1.22867e-07 -1 + outer loop + vertex -790.838 220.555 -6.25173e-07 + vertex -787.3 221.998 -7.12059e-14 + vertex -783.802 215.379 -3.70537e-07 + endloop + endfacet + facet normal 1.18211e-07 1.43352e-07 -1 + outer loop + vertex -787.3 221.998 -7.12059e-14 + vertex -790.838 220.555 -6.25173e-07 + vertex -793.678 225.063 -3.14643e-07 + endloop + endfacet + facet normal 1.00638e-07 1.06779e-07 -1 + outer loop + vertex -793.678 225.063 -3.14643e-07 + vertex -793.885 228.204 -7.05936e-14 + vertex -787.3 221.998 -7.12059e-14 + endloop + endfacet + facet normal 1.33255e-07 1.08926e-07 -1 + outer loop + vertex -793.885 228.204 -7.05936e-14 + vertex -793.678 225.063 -3.14643e-07 + vertex -798.59 229.304 -5.07226e-07 + endloop + endfacet + facet normal 1.40604e-07 1.4038e-07 -1 + outer loop + vertex -799.221 233.549 -7.00952e-14 + vertex -793.885 228.204 -7.05936e-14 + vertex -798.59 229.304 -5.07226e-07 + endloop + endfacet + facet normal 1.73703e-07 1.45299e-07 -1 + outer loop + vertex -798.59 229.304 -5.07226e-07 + vertex -803.569 234.128 -6.71064e-07 + vertex -799.221 233.549 -7.00952e-14 + endloop + endfacet + facet normal 1.76255e-07 1.6446e-07 -1 + outer loop + vertex -804.369 239.066 -6.97534e-14 + vertex -799.221 233.549 -7.00952e-14 + vertex -803.569 234.128 -6.71064e-07 + endloop + endfacet + facet normal 2.43147e-07 1.75302e-07 -1 + outer loop + vertex -803.569 234.128 -6.71064e-07 + vertex -808.169 239.074 -9.22701e-07 + vertex -804.369 239.066 -6.97534e-14 + endloop + endfacet + facet normal 2.43213e-07 2.09425e-07 -1 + outer loop + vertex -808.169 239.074 -9.22701e-07 + vertex -809.093 244.552 -6.97309e-14 + vertex -804.369 239.066 -6.97534e-14 + endloop + endfacet + facet normal 3.51928e-07 2.2775e-07 -1 + outer loop + vertex -812.632 244.429 -1.27378e-06 + vertex -809.093 244.552 -6.97309e-14 + vertex -808.169 239.074 -9.22701e-07 + endloop + endfacet + facet normal 9.23277e-07 7.03932e-07 -1 + outer loop + vertex -812.23 238.845 -4.83331e-06 + vertex -812.632 244.429 -1.27378e-06 + vertex -808.169 239.074 -9.22701e-07 + endloop + endfacet + facet normal 9.30641e-07 5.73493e-07 -1 + outer loop + vertex -812.23 238.845 -4.83331e-06 + vertex -808.169 239.074 -9.22701e-07 + vertex -807.957 234.153 -3.54662e-06 + endloop + endfacet + facet normal 2.66127e-06 2.15e-06 -1 + outer loop + vertex -812.232 233.891 -1.54892e-05 + vertex -812.23 238.845 -4.83331e-06 + vertex -807.957 234.153 -3.54662e-06 + endloop + endfacet + facet normal 2.66147e-06 2.14662e-06 -1 + outer loop + vertex -812.232 233.891 -1.54892e-05 + vertex -807.957 234.153 -3.54662e-06 + vertex -807.958 229.702 -1.31061e-05 + endloop + endfacet + facet normal 7.2096e-06 6.78705e-06 -1 + outer loop + vertex -812.314 229.476 -4.60417e-05 + vertex -812.232 233.891 -1.54892e-05 + vertex -807.958 229.702 -1.31061e-05 + endloop + endfacet + facet normal 7.17692e-06 7.41768e-06 -1 + outer loop + vertex -812.314 229.476 -4.60417e-05 + vertex -807.958 229.702 -1.31061e-05 + vertex -807.706 225.299 -4.39604e-05 + endloop + endfacet + facet normal 1.87139e-05 2.01426e-05 -1 + outer loop + vertex -807.706 225.299 -4.39604e-05 + vertex -812.245 225.32 -0.000128475 + vertex -812.314 229.476 -4.60417e-05 + endloop + endfacet + facet normal 1.92048e-05 2.01507e-05 -1 + outer loop + vertex -816.631 229.408 -0.000130315 + vertex -812.314 229.476 -4.60417e-05 + vertex -812.245 225.32 -0.000128475 + endloop + endfacet + facet normal 3.80955e-05 4.04146e-05 -1 + outer loop + vertex -812.245 225.32 -0.000128475 + vertex -816.452 226.007 -0.000260966 + vertex -816.631 229.408 -0.000130315 + endloop + endfacet + facet normal 5.0569e-05 4.10693e-05 -1 + outer loop + vertex -820.743 229.269 -0.000343977 + vertex -816.631 229.408 -0.000130315 + vertex -816.452 226.007 -0.000260966 + endloop + endfacet + facet normal 8.31452e-05 8.39211e-05 -1 + outer loop + vertex -816.452 226.007 -0.000260966 + vertex -819.291 224.974 -0.00058368 + vertex -820.743 229.269 -0.000343977 + endloop + endfacet + facet normal 9.5949e-05 8.82486e-05 -1 + outer loop + vertex -824.898 228.814 -0.000782857 + vertex -820.743 229.269 -0.000343977 + vertex -819.291 224.974 -0.00058368 + endloop + endfacet + facet normal 0.000125494 0.000131398 -1 + outer loop + vertex -819.291 224.974 -0.00058368 + vertex -823.156 224.192 -0.00117147 + vertex -824.898 228.814 -0.000782857 + endloop + endfacet + facet normal 0.000136432 0.000135521 -1 + outer loop + vertex -829.587 227.806 -0.00155914 + vertex -824.898 228.814 -0.000782857 + vertex -823.156 224.192 -0.00117147 + endloop + endfacet + facet normal 0.000153922 0.000166646 -1 + outer loop + vertex -823.156 224.192 -0.00117147 + vertex -826.22 222.935 -0.00185259 + vertex -829.587 227.806 -0.00155914 + endloop + endfacet + facet normal 0.000180923 0.000185311 -1 + outer loop + vertex -826.22 222.935 -0.00185259 + vertex -831.653 223.039 -0.00281623 + vertex -829.587 227.806 -0.00155914 + endloop + endfacet + facet normal 0.000158667 0.000194954 -1 + outer loop + vertex -834.873 228.735 -0.00221666 + vertex -829.587 227.806 -0.00155914 + vertex -831.653 223.039 -0.00281623 + endloop + endfacet + facet normal 0.000205754 0.000221573 -1 + outer loop + vertex -838.613 227.385 -0.0032853 + vertex -834.873 228.735 -0.00221666 + vertex -831.653 223.039 -0.00281623 + endloop + endfacet + facet normal 0.000273323 0.000329781 -1 + outer loop + vertex -831.653 223.039 -0.00281623 + vertex -838.031 222.004 -0.00490085 + vertex -838.613 227.385 -0.0032853 + endloop + endfacet + facet normal 0.000291752 0.000331773 -1 + outer loop + vertex -843.557 226.332 -0.00507708 + vertex -838.613 227.385 -0.0032853 + vertex -838.031 222.004 -0.00490085 + endloop + endfacet + facet normal 0.00031273 0.000358557 -1 + outer loop + vertex -838.031 222.004 -0.00490085 + vertex -844.234 220.263 -0.00746506 + vertex -843.557 226.332 -0.00507708 + endloop + endfacet + facet normal 0.000299115 0.000360076 -1 + outer loop + vertex -848.04 226.141 -0.00648702 + vertex -843.557 226.332 -0.00507708 + vertex -844.234 220.263 -0.00746506 + endloop + endfacet + facet normal -9.18595e-05 0.000106896 -1 + outer loop + vertex -851.46 224.111 -0.00638992 + vertex -848.04 226.141 -0.00648702 + vertex -844.234 220.263 -0.00746506 + endloop + endfacet + facet normal -0.000413378 -0.000496791 -1 + outer loop + vertex -844.234 220.263 -0.00746506 + vertex -850.209 218.205 -0.00397295 + vertex -851.46 224.111 -0.00638992 + endloop + endfacet + facet normal -0.00122278 -0.000668238 -0.999999 + outer loop + vertex -856.012 222.144 0.000491262 + vertex -851.46 224.111 -0.00638992 + vertex -850.209 218.205 -0.00397295 + endloop + endfacet + facet normal -0.0024754 -0.00251371 -0.999994 + outer loop + vertex -850.209 218.205 -0.00397295 + vertex -854.649 215.735 0.0132274 + vertex -856.012 222.144 0.000491262 + endloop + endfacet + facet normal -0.00335609 -0.00270103 -0.999991 + outer loop + vertex -860.221 219.643 0.0213712 + vertex -856.012 222.144 0.000491262 + vertex -854.649 215.735 0.0132274 + endloop + endfacet + facet normal -0.00555859 -0.00584127 -0.999967 + outer loop + vertex -854.649 215.735 0.0132274 + vertex -858.238 211.748 0.056468 + vertex -860.221 219.643 0.0213712 + endloop + endfacet + facet normal -0.00724602 -0.00626489 -0.999954 + outer loop + vertex -864.113 216.798 0.0674032 + vertex -860.221 219.643 0.0213712 + vertex -858.238 211.748 0.056468 + endloop + endfacet + facet normal -0.0132963 -0.0133044 -0.999823 + outer loop + vertex -858.238 211.748 0.056468 + vertex -862.443 209.139 0.147096 + vertex -864.113 216.798 0.0674032 + endloop + endfacet + facet normal -0.0187453 -0.0144919 -0.999719 + outer loop + vertex -867.576 213.784 0.17602 + vertex -864.113 216.798 0.0674032 + vertex -862.443 209.139 0.147096 + endloop + endfacet + facet normal -0.032362 -0.029546 -0.999039 + outer loop + vertex -862.443 209.139 0.147096 + vertex -865.443 205.865 0.341112 + vertex -867.576 213.784 0.17602 + endloop + endfacet + facet normal -0.0438117 -0.0326191 -0.998507 + outer loop + vertex -870.612 210.352 0.421352 + vertex -867.576 213.784 0.17602 + vertex -865.443 205.865 0.341112 + endloop + endfacet + facet normal -0.0656648 -0.057838 -0.996164 + outer loop + vertex -865.443 205.865 0.341112 + vertex -868.144 202.272 0.727818 + vertex -870.612 210.352 0.421352 + endloop + endfacet + facet normal -0.0765917 -0.0611381 -0.995186 + outer loop + vertex -873.719 206.263 0.911617 + vertex -870.612 210.352 0.421352 + vertex -868.144 202.272 0.727818 + endloop + endfacet + facet normal -0.0761992 -0.0614377 -0.995198 + outer loop + vertex -873.719 206.263 0.911617 + vertex -875.374 215.191 0.487184 + vertex -870.612 210.352 0.421352 + endloop + endfacet + facet normal -0.0497353 -0.0353589 -0.998136 + outer loop + vertex -875.374 215.191 0.487184 + vertex -872.085 218.524 0.205253 + vertex -870.612 210.352 0.421352 + endloop + endfacet + facet normal -0.0489044 -0.0361801 -0.998148 + outer loop + vertex -875.374 215.191 0.487184 + vertex -876.578 224.22 0.218912 + vertex -872.085 218.524 0.205253 + endloop + endfacet + facet normal -0.0254658 -0.0176895 -0.999519 + outer loop + vertex -876.578 224.22 0.218912 + vertex -872.946 226.995 0.0772785 + vertex -872.085 218.524 0.205253 + endloop + endfacet + facet normal -0.0230391 -0.0174437 -0.999582 + outer loop + vertex -872.085 218.524 0.205253 + vertex -872.946 226.995 0.0772785 + vertex -868.677 221.494 0.0748844 + endloop + endfacet + facet normal -0.0238453 -0.0165187 -0.999579 + outer loop + vertex -872.085 218.524 0.205253 + vertex -868.677 221.494 0.0748844 + vertex -867.576 213.784 0.17602 + endloop + endfacet + facet normal -0.00990468 -0.00725103 -0.999925 + outer loop + vertex -872.946 226.995 0.0772785 + vertex -869.143 229.479 0.02159 + vertex -868.677 221.494 0.0748844 + endloop + endfacet + facet normal -0.00852555 -0.00717069 -0.999938 + outer loop + vertex -868.677 221.494 0.0748844 + vertex -869.143 229.479 0.02159 + vertex -864.916 224.131 0.023903 + endloop + endfacet + facet normal -0.00872464 -0.00688667 -0.999938 + outer loop + vertex -868.677 221.494 0.0748844 + vertex -864.916 224.131 0.023903 + vertex -864.113 216.798 0.0674032 + endloop + endfacet + facet normal -0.00308082 -0.0028674 -0.999991 + outer loop + vertex -869.143 229.479 0.02159 + vertex -865.046 231.606 0.00287056 + vertex -864.916 224.131 0.023903 + endloop + endfacet + facet normal -0.0034418 -0.0028737 -0.99999 + outer loop + vertex -864.916 224.131 0.023903 + vertex -865.046 231.606 0.00287056 + vertex -860.794 226.386 0.00323414 + endloop + endfacet + facet normal -0.00338509 -0.00297732 -0.99999 + outer loop + vertex -864.916 224.131 0.023903 + vertex -860.794 226.386 0.00323414 + vertex -860.221 219.643 0.0213712 + endloop + endfacet + facet normal -0.00116209 -0.00101642 -0.999999 + outer loop + vertex -865.046 231.606 0.00287056 + vertex -860.709 233.324 -0.00391609 + vertex -860.794 226.386 0.00323414 + endloop + endfacet + facet normal -0.0014117 -0.00101337 -0.999998 + outer loop + vertex -860.794 226.386 0.00323414 + vertex -860.709 233.324 -0.00391609 + vertex -856.409 228.208 -0.00480247 + endloop + endfacet + facet normal -0.00143115 -0.000966578 -0.999999 + outer loop + vertex -860.794 226.386 0.00323414 + vertex -856.409 228.208 -0.00480247 + vertex -856.012 222.144 0.000491262 + endloop + endfacet + facet normal -0.000356043 -0.000126014 -1 + outer loop + vertex -860.709 233.324 -0.00391609 + vertex -856.273 234.671 -0.00566517 + vertex -856.409 228.208 -0.00480247 + endloop + endfacet + facet normal -0.00027526 -0.000127713 -1 + outer loop + vertex -856.409 228.208 -0.00480247 + vertex -856.273 234.671 -0.00566517 + vertex -852.097 229.691 -0.00617868 + endloop + endfacet + facet normal -0.000319637 1.33249e-06 -1 + outer loop + vertex -856.409 228.208 -0.00480247 + vertex -852.097 229.691 -0.00617868 + vertex -851.46 224.111 -0.00638992 + endloop + endfacet + facet normal 0.000133903 0.00021542 -1 + outer loop + vertex -856.273 234.671 -0.00566517 + vertex -851.844 235.715 -0.00484718 + vertex -852.097 229.691 -0.00617868 + endloop + endfacet + facet normal 0.000246297 0.000210692 -1 + outer loop + vertex -852.097 229.691 -0.00617868 + vertex -851.844 235.715 -0.00484718 + vertex -847.803 230.743 -0.00489929 + endloop + endfacet + facet normal 0.000216135 0.000333838 -1 + outer loop + vertex -852.097 229.691 -0.00617868 + vertex -847.803 230.743 -0.00489929 + vertex -848.04 226.141 -0.00648702 + endloop + endfacet + facet normal 0.000268339 0.000228609 -1 + outer loop + vertex -851.844 235.715 -0.00484718 + vertex -847.418 236.527 -0.00347373 + vertex -847.803 230.743 -0.00489929 + endloop + endfacet + facet normal 0.000290871 0.00022711 -1 + outer loop + vertex -847.803 230.743 -0.00489929 + vertex -847.418 236.527 -0.00347373 + vertex -843.308 231.557 -0.00340706 + endloop + endfacet + facet normal 0.000276493 0.000306452 -1 + outer loop + vertex -847.803 230.743 -0.00489929 + vertex -843.308 231.557 -0.00340706 + vertex -843.557 226.332 -0.00507708 + endloop + endfacet + facet normal 0.000213829 0.000163401 -1 + outer loop + vertex -847.418 236.527 -0.00347373 + vertex -843.018 237.22 -0.00241975 + vertex -843.308 231.557 -0.00340706 + endloop + endfacet + facet normal 0.000215234 0.000163329 -1 + outer loop + vertex -843.308 231.557 -0.00340706 + vertex -843.018 237.22 -0.00241975 + vertex -838.926 232.414 -0.00232392 + endloop + endfacet + facet normal 0.000207272 0.00020408 -1 + outer loop + vertex -843.308 231.557 -0.00340706 + vertex -838.926 232.414 -0.00232392 + vertex -838.613 227.385 -0.0032853 + endloop + endfacet + facet normal 0.000162664 0.000118568 -1 + outer loop + vertex -843.018 237.22 -0.00241975 + vertex -838.655 237.763 -0.00164559 + vertex -838.926 232.414 -0.00232392 + endloop + endfacet + facet normal 0.000159202 0.000118743 -1 + outer loop + vertex -838.926 232.414 -0.00232392 + vertex -838.655 237.763 -0.00164559 + vertex -834.494 232.849 -0.00156674 + endloop + endfacet + facet normal 0.000156765 0.000143556 -1 + outer loop + vertex -838.926 232.414 -0.00232392 + vertex -834.494 232.849 -0.00156674 + vertex -834.873 228.735 -0.00221666 + endloop + endfacet + facet normal 0.000136691 9.9685e-05 -1 + outer loop + vertex -838.655 237.763 -0.00164559 + vertex -834.252 238.106 -0.00100956 + vertex -834.494 232.849 -0.00156674 + endloop + endfacet + facet normal 0.000132037 9.98998e-05 -1 + outer loop + vertex -834.494 232.849 -0.00156674 + vertex -834.252 238.106 -0.00100956 + vertex -829.869 233.083 -0.000932658 + endloop + endfacet + facet normal 0.00013073 0.0001257 -1 + outer loop + vertex -834.494 232.849 -0.00156674 + vertex -829.869 233.083 -0.000932658 + vertex -829.587 227.806 -0.00155914 + endloop + endfacet + facet normal 0.000105669 7.68911e-05 -1 + outer loop + vertex -834.252 238.106 -0.00100956 + vertex -829.782 238.319 -0.000520871 + vertex -829.869 233.083 -0.000932658 + endloop + endfacet + facet normal 0.000103523 7.69267e-05 -1 + outer loop + vertex -829.869 233.083 -0.000932658 + vertex -829.782 238.319 -0.000520871 + vertex -825.354 233.382 -0.00044234 + endloop + endfacet + facet normal 0.000103 8.48355e-05 -1 + outer loop + vertex -829.869 233.083 -0.000932658 + vertex -825.354 233.382 -0.00044234 + vertex -824.898 228.814 -0.000782857 + endloop + endfacet + facet normal 6.62699e-05 4.35213e-05 -1 + outer loop + vertex -829.782 238.319 -0.000520871 + vertex -825.288 238.434 -0.000218081 + vertex -825.354 233.382 -0.00044234 + endloop + endfacet + facet normal 5.95706e-05 4.36088e-05 -1 + outer loop + vertex -825.354 233.382 -0.00044234 + vertex -825.288 238.434 -0.000218081 + vertex -820.922 233.526 -0.000172022 + endloop + endfacet + facet normal 5.95934e-05 4.29085e-05 -1 + outer loop + vertex -825.354 233.382 -0.00044234 + vertex -820.922 233.526 -0.000172022 + vertex -820.743 229.269 -0.000343977 + endloop + endfacet + facet normal 3.19125e-05 1.90045e-05 -1 + outer loop + vertex -825.288 238.434 -0.000218081 + vertex -820.812 238.492 -7.41122e-05 + vertex -820.922 233.526 -0.000172022 + endloop + endfacet + facet normal 2.59061e-05 1.91385e-05 -1 + outer loop + vertex -820.922 233.526 -0.000172022 + vertex -820.812 238.492 -7.41122e-05 + vertex -816.533 233.65 -5.5954e-05 + endloop + endfacet + facet normal 2.59681e-05 1.69367e-05 -1 + outer loop + vertex -820.922 233.526 -0.000172022 + vertex -816.533 233.65 -5.5954e-05 + vertex -816.631 229.408 -0.000130315 + endloop + endfacet + facet normal 1.20532e-05 6.89925e-06 -1 + outer loop + vertex -820.812 238.492 -7.41122e-05 + vertex -816.438 238.607 -2.06102e-05 + vertex -816.533 233.65 -5.5954e-05 + endloop + endfacet + facet normal 9.01723e-06 6.95738e-06 -1 + outer loop + vertex -816.533 233.65 -5.5954e-05 + vertex -816.438 238.607 -2.06102e-05 + vertex -812.232 233.891 -1.54892e-05 + endloop + endfacet + facet normal 1.20137e-05 8.40515e-06 -1 + outer loop + vertex -820.812 238.492 -7.41122e-05 + vertex -820.795 244.13 -2.65211e-05 + vertex -816.438 238.607 -2.06102e-05 + endloop + endfacet + facet normal 4.69739e-06 2.63477e-06 -1 + outer loop + vertex -820.795 244.13 -2.65211e-05 + vertex -816.559 244.199 -6.4419e-06 + vertex -816.438 238.607 -2.06102e-05 + endloop + endfacet + facet normal 3.60121e-06 2.61117e-06 -1 + outer loop + vertex -816.438 238.607 -2.06102e-05 + vertex -816.559 244.199 -6.4419e-06 + vertex -812.23 238.845 -4.83331e-06 + endloop + endfacet + facet normal 4.68894e-06 3.1592e-06 -1 + outer loop + vertex -820.795 244.13 -2.65211e-05 + vertex -820.904 250.147 -8.02221e-06 + vertex -816.559 244.199 -6.4419e-06 + endloop + endfacet + facet normal 1.64111e-06 9.33021e-07 -1 + outer loop + vertex -820.904 250.147 -8.02221e-06 + vertex -816.997 250.231 -1.53242e-06 + vertex -816.559 244.199 -6.4419e-06 + endloop + endfacet + facet normal 1.26311e-06 9.05558e-07 -1 + outer loop + vertex -816.559 244.199 -6.4419e-06 + vertex -816.997 250.231 -1.53242e-06 + vertex -812.632 244.429 -1.27378e-06 + endloop + endfacet + facet normal 4.50303e-07 2.94151e-07 -1 + outer loop + vertex -816.997 250.231 -1.53242e-06 + vertex -813.924 250.736 -7.02221e-14 + vertex -812.632 244.429 -1.27378e-06 + endloop + endfacet + facet normal 4.47365e-07 3.12033e-07 -1 + outer loop + vertex -816.997 250.231 -1.53242e-06 + vertex -818.024 256.614 -7.12941e-14 + vertex -813.924 250.736 -7.02221e-14 + endloop + endfacet + facet normal 5.88686e-07 3.34764e-07 -1 + outer loop + vertex -821.138 256.341 -1.92442e-06 + vertex -818.024 256.614 -7.12941e-14 + vertex -816.997 250.231 -1.53242e-06 + endloop + endfacet + facet normal 5.86471e-07 3.60018e-07 -1 + outer loop + vertex -821.138 256.341 -1.92442e-06 + vertex -821.893 262.917 -7.31705e-14 + vertex -818.024 256.614 -7.12941e-14 + endloop + endfacet + facet normal 6.942e-07 3.72389e-07 -1 + outer loop + vertex -824.89 262.584 -2.20485e-06 + vertex -821.893 262.917 -7.31705e-14 + vertex -821.138 256.341 -1.92442e-06 + endloop + endfacet + facet normal 1.83921e-06 1.0607e-06 -1 + outer loop + vertex -825.02 256.381 -9.02341e-06 + vertex -824.89 262.584 -2.20485e-06 + vertex -821.138 256.341 -1.92442e-06 + endloop + endfacet + facet normal 1.83914e-06 1.05385e-06 -1 + outer loop + vertex -825.02 256.381 -9.02341e-06 + vertex -821.138 256.341 -1.92442e-06 + vertex -820.904 250.147 -8.02221e-06 + endloop + endfacet + facet normal 5.67775e-06 3.58861e-06 -1 + outer loop + vertex -825.128 250.228 -3.17159e-05 + vertex -825.02 256.381 -9.02341e-06 + vertex -820.904 250.147 -8.02221e-06 + endloop + endfacet + facet normal 6.55547e-06 3.57328e-06 -1 + outer loop + vertex -829.16 256.529 -3.56326e-05 + vertex -825.02 256.381 -9.02341e-06 + vertex -825.128 250.228 -3.17159e-05 + endloop + endfacet + facet normal 1.68724e-05 1.01751e-05 -1 + outer loop + vertex -829.432 250.299 -0.000103619 + vertex -829.16 256.529 -3.56326e-05 + vertex -825.128 250.228 -3.17159e-05 + endloop + endfacet + facet normal 1.68591e-05 9.36591e-06 -1 + outer loop + vertex -829.432 250.299 -0.000103619 + vertex -825.128 250.228 -3.17159e-05 + vertex -825.183 244.135 -8.97115e-05 + endloop + endfacet + facet normal 3.65846e-05 2.29644e-05 -1 + outer loop + vertex -829.61 244.118 -0.000252058 + vertex -829.432 250.299 -0.000103619 + vertex -825.183 244.135 -8.97115e-05 + endloop + endfacet + facet normal 3.65891e-05 2.18396e-05 -1 + outer loop + vertex -829.61 244.118 -0.000252058 + vertex -825.183 244.135 -8.97115e-05 + vertex -825.288 238.434 -0.000218081 + endloop + endfacet + facet normal 4.05825e-05 2.28495e-05 -1 + outer loop + vertex -833.737 250.288 -0.000278546 + vertex -829.432 250.299 -0.000103619 + vertex -829.61 244.118 -0.000252058 + endloop + endfacet + facet normal 7.19616e-05 4.38361e-05 -1 + outer loop + vertex -834.008 244.01 -0.000573303 + vertex -833.737 250.288 -0.000278546 + vertex -829.61 244.118 -0.000252058 + endloop + endfacet + facet normal 7.19523e-05 4.42183e-05 -1 + outer loop + vertex -834.008 244.01 -0.000573303 + vertex -829.61 244.118 -0.000252058 + vertex -829.782 238.319 -0.000520871 + endloop + endfacet + facet normal 7.90342e-05 4.35302e-05 -1 + outer loop + vertex -838.024 250.199 -0.00062128 + vertex -833.737 250.288 -0.000278546 + vertex -834.008 244.01 -0.000573303 + endloop + endfacet + facet normal 0.000113122 6.56489e-05 -1 + outer loop + vertex -838.36 243.801 -0.00107932 + vertex -838.024 250.199 -0.00062128 + vertex -834.008 244.01 -0.000573303 + endloop + endfacet + facet normal 0.00011295 6.92326e-05 -1 + outer loop + vertex -838.36 243.801 -0.00107932 + vertex -834.008 244.01 -0.000573303 + vertex -834.252 238.106 -0.00100956 + endloop + endfacet + facet normal 0.000120162 6.52791e-05 -1 + outer loop + vertex -842.309 250.031 -0.0011472 + vertex -838.024 250.199 -0.00062128 + vertex -838.36 243.801 -0.00107932 + endloop + endfacet + facet normal 0.000144123 8.04689e-05 -1 + outer loop + vertex -842.69 243.47 -0.00172999 + vertex -842.309 250.031 -0.0011472 + vertex -838.36 243.801 -0.00107932 + endloop + endfacet + facet normal 0.000143641 8.67758e-05 -1 + outer loop + vertex -842.69 243.47 -0.00172999 + vertex -838.36 243.801 -0.00107932 + vertex -838.655 237.763 -0.00164559 + endloop + endfacet + facet normal 0.000151757 8.00263e-05 -1 + outer loop + vertex -846.606 249.782 -0.0018191 + vertex -842.309 250.031 -0.0011472 + vertex -842.69 243.47 -0.00172999 + endloop + endfacet + facet normal 0.000171757 9.24332e-05 -1 + outer loop + vertex -847.038 243.014 -0.00251891 + vertex -846.606 249.782 -0.0018191 + vertex -842.69 243.47 -0.00172999 + endloop + endfacet + facet normal 0.000170819 0.000101392 -1 + outer loop + vertex -847.038 243.014 -0.00251891 + vertex -842.69 243.47 -0.00172999 + vertex -843.018 237.22 -0.00241975 + endloop + endfacet + facet normal 0.000174555 9.22545e-05 -1 + outer loop + vertex -850.94 249.429 -0.00260836 + vertex -846.606 249.782 -0.0018191 + vertex -847.038 243.014 -0.00251891 + endloop + endfacet + facet normal 0.000218205 0.000118811 -1 + outer loop + vertex -851.433 242.434 -0.00354677 + vertex -850.94 249.429 -0.00260836 + vertex -847.038 243.014 -0.00251891 + endloop + endfacet + facet normal 0.000216128 0.000134534 -1 + outer loop + vertex -851.433 242.434 -0.00354677 + vertex -847.038 243.014 -0.00251891 + vertex -847.418 236.527 -0.00347373 + endloop + endfacet + facet normal 0.000199664 0.000120116 -1 + outer loop + vertex -855.321 248.951 -0.00354036 + vertex -850.94 249.429 -0.00260836 + vertex -851.433 242.434 -0.00354677 + endloop + endfacet + facet normal 0.000237249 0.000142541 -1 + outer loop + vertex -855.873 241.694 -0.00470579 + vertex -855.321 248.951 -0.00354036 + vertex -851.433 242.434 -0.00354677 + endloop + endfacet + facet normal 0.00023111 0.000179382 -1 + outer loop + vertex -855.873 241.694 -0.00470579 + vertex -851.433 242.434 -0.00354677 + vertex -851.844 235.715 -0.00484718 + endloop + endfacet + facet normal 0.000169106 0.000147729 -1 + outer loop + vertex -859.757 248.303 -0.00438624 + vertex -855.321 248.951 -0.00354036 + vertex -855.873 241.694 -0.00470579 + endloop + endfacet + facet normal 8.89205e-05 0.000100607 -1 + outer loop + vertex -860.344 240.732 -0.00520011 + vertex -859.757 248.303 -0.00438624 + vertex -855.873 241.694 -0.00470579 + endloop + endfacet + facet normal 8.21818e-05 0.000131916 -1 + outer loop + vertex -860.344 240.732 -0.00520011 + vertex -855.873 241.694 -0.00470579 + vertex -856.273 234.671 -0.00566517 + endloop + endfacet + facet normal 3.40546e-05 0.000104859 -1 + outer loop + vertex -864.246 247.423 -0.00463138 + vertex -859.757 248.303 -0.00438624 + vertex -860.344 240.732 -0.00520011 + endloop + endfacet + facet normal -0.000249845 -6.06947e-05 -1 + outer loop + vertex -864.803 239.469 -0.00400922 + vertex -864.246 247.423 -0.00463138 + vertex -860.344 240.732 -0.00520011 + endloop + endfacet + facet normal -0.000221034 -0.000162434 -1 + outer loop + vertex -864.803 239.469 -0.00400922 + vertex -860.344 240.732 -0.00520011 + vertex -860.709 233.324 -0.00391609 + endloop + endfacet + facet normal -6.29433e-05 -7.38048e-05 -1 + outer loop + vertex -868.758 246.245 -0.00426038 + vertex -864.246 247.423 -0.00463138 + vertex -864.803 239.469 -0.00400922 + endloop + endfacet + facet normal -0.000801654 -0.000504975 -1 + outer loop + vertex -869.171 237.84 0.000314864 + vertex -868.758 246.245 -0.00426038 + vertex -864.803 239.469 -0.00400922 + endloop + endfacet + facet normal -0.000671392 -0.000854208 -0.999999 + outer loop + vertex -869.171 237.84 0.000314864 + vertex -864.803 239.469 -0.00400922 + vertex -865.046 231.606 0.00287056 + endloop + endfacet + facet normal -0.000269042 -0.000531129 -1 + outer loop + vertex -873.226 244.723 -0.00225004 + vertex -868.758 246.245 -0.00426038 + vertex -869.171 237.84 0.000314864 + endloop + endfacet + facet normal -0.00288382 -0.00207158 -0.999994 + outer loop + vertex -873.357 235.836 0.0165357 + vertex -873.226 244.723 -0.00225004 + vertex -869.171 237.84 0.000314864 + endloop + endfacet + facet normal -0.00265305 -0.00255363 -0.999993 + outer loop + vertex -873.357 235.836 0.0165357 + vertex -869.171 237.84 0.000314864 + vertex -869.143 229.479 0.02159 + endloop + endfacet + facet normal -0.00225317 -0.00208082 -0.999995 + outer loop + vertex -877.569 242.85 0.0114333 + vertex -873.226 244.723 -0.00225004 + vertex -873.357 235.836 0.0165357 + endloop + endfacet + facet normal -0.0099545 -0.00670638 -0.999928 + outer loop + vertex -877.355 233.512 0.0719312 + vertex -877.569 242.85 0.0114333 + vertex -873.357 235.836 0.0165357 + endloop + endfacet + facet normal -0.00960049 -0.00731546 -0.999927 + outer loop + vertex -877.355 233.512 0.0719312 + vertex -873.357 235.836 0.0165357 + vertex -872.946 226.995 0.0772785 + endloop + endfacet + facet normal -0.00958817 -0.00669802 -0.999932 + outer loop + vertex -881.782 240.682 0.0663541 + vertex -877.569 242.85 0.0114333 + vertex -877.355 233.512 0.0719312 + endloop + endfacet + facet normal -0.0259086 -0.0167748 -0.999524 + outer loop + vertex -881.291 230.973 0.216573 + vertex -881.782 240.682 0.0663541 + vertex -877.355 233.512 0.0719312 + endloop + endfacet + facet normal -0.0251718 -0.0179168 -0.999523 + outer loop + vertex -881.291 230.973 0.216573 + vertex -877.355 233.512 0.0719312 + vertex -876.578 224.22 0.218912 + endloop + endfacet + facet normal -0.0493866 -0.034819 -0.998173 + outer loop + vertex -880.261 221.232 0.505398 + vertex -881.291 230.973 0.216573 + vertex -876.578 224.22 0.218912 + endloop + endfacet + facet normal -0.046503 -0.0345186 -0.998322 + outer loop + vertex -885.392 228.329 0.499002 + vertex -881.291 230.973 0.216573 + vertex -880.261 221.232 0.505398 + endloop + endfacet + facet normal -0.0744873 -0.0547473 -0.995718 + outer loop + vertex -884.205 218.136 0.970622 + vertex -885.392 228.329 0.499002 + vertex -880.261 221.232 0.505398 + endloop + endfacet + facet normal -0.0713083 -0.0587967 -0.99572 + outer loop + vertex -884.205 218.136 0.970622 + vertex -880.261 221.232 0.505398 + vertex -878.774 211.495 0.973875 + endloop + endfacet + facet normal -0.0775162 -0.0597198 -0.995201 + outer loop + vertex -878.774 211.495 0.973875 + vertex -880.261 221.232 0.505398 + vertex -875.374 215.191 0.487184 + endloop + endfacet + facet normal -0.0706098 -0.0543098 -0.996024 + outer loop + vertex -889.848 225.699 0.958303 + vertex -885.392 228.329 0.499002 + vertex -884.205 218.136 0.970622 + endloop + endfacet + facet normal -0.0735976 -0.0492569 -0.996071 + outer loop + vertex -889.848 225.699 0.958303 + vertex -890.402 235.912 0.494201 + vertex -885.392 228.329 0.499002 + endloop + endfacet + facet normal -0.0469738 -0.0316679 -0.998394 + outer loop + vertex -890.402 235.912 0.494201 + vertex -885.991 238.326 0.210101 + vertex -885.392 228.329 0.499002 + endloop + endfacet + facet normal -0.0488654 -0.0282137 -0.998407 + outer loop + vertex -890.402 235.912 0.494201 + vertex -890.322 245.85 0.209431 + vertex -885.991 238.326 0.210101 + endloop + endfacet + facet normal -0.0254903 -0.0147601 -0.999566 + outer loop + vertex -890.322 245.85 0.209431 + vertex -885.903 248.056 0.0641783 + vertex -885.991 238.326 0.210101 + endloop + endfacet + facet normal -0.0258778 -0.0147565 -0.999556 + outer loop + vertex -885.991 238.326 0.210101 + vertex -885.903 248.056 0.0641783 + vertex -881.782 240.682 0.0663541 + endloop + endfacet + facet normal -0.00980918 -0.00577681 -0.999935 + outer loop + vertex -885.903 248.056 0.0641783 + vertex -881.509 250.089 0.00932606 + vertex -881.782 240.682 0.0663541 + endloop + endfacet + facet normal -0.0102964 -0.00472429 -0.999936 + outer loop + vertex -885.903 248.056 0.0641783 + vertex -884.952 257.37 0.0103808 + vertex -881.509 250.089 0.00932606 + endloop + endfacet + facet normal -0.00238227 -0.000981717 -0.999997 + outer loop + vertex -884.952 257.37 0.0103808 + vertex -880.329 258.975 -0.00220771 + vertex -881.509 250.089 0.00932606 + endloop + endfacet + facet normal -0.00237126 -0.000983178 -0.999997 + outer loop + vertex -881.509 250.089 0.00932606 + vertex -880.329 258.975 -0.00220771 + vertex -877.012 251.83 -0.00305032 + endloop + endfacet + facet normal -0.00217991 -0.00147747 -0.999997 + outer loop + vertex -881.509 250.089 0.00932606 + vertex -877.012 251.83 -0.00305032 + vertex -877.569 242.85 0.0114333 + endloop + endfacet + facet normal -0.000108066 6.77507e-05 -1 + outer loop + vertex -880.329 258.975 -0.00220771 + vertex -875.635 260.237 -0.00262951 + vertex -877.012 251.83 -0.00305032 + endloop + endfacet + facet normal -0.0001841 8.02018e-05 -1 + outer loop + vertex -877.012 251.83 -0.00305032 + vertex -875.635 260.237 -0.00262951 + vertex -872.424 253.227 -0.00378291 + endloop + endfacet + facet normal -0.000107889 -0.000170064 -1 + outer loop + vertex -877.012 251.83 -0.00305032 + vertex -872.424 253.227 -0.00378291 + vertex -873.226 244.723 -0.00225004 + endloop + endfacet + facet normal -7.22324e-05 0.000131449 -1 + outer loop + vertex -875.635 260.237 -0.00262951 + vertex -870.974 261.183 -0.00284185 + vertex -872.424 253.227 -0.00378291 + endloop + endfacet + facet normal -3.45144e-05 0.000124575 -1 + outer loop + vertex -872.424 253.227 -0.00378291 + vertex -870.974 261.183 -0.00284185 + vertex -867.833 254.294 -0.00380855 + endloop + endfacet + facet normal -1.91324e-05 5.83386e-05 -1 + outer loop + vertex -872.424 253.227 -0.00378291 + vertex -867.833 254.294 -0.00380855 + vertex -868.758 246.245 -0.00426038 + endloop + endfacet + facet normal -0.000135388 7.85876e-05 -1 + outer loop + vertex -870.974 261.183 -0.00284185 + vertex -866.425 261.869 -0.00340379 + vertex -867.833 254.294 -0.00380855 + endloop + endfacet + facet normal -3.16458e-05 5.93083e-05 -1 + outer loop + vertex -867.833 254.294 -0.00380855 + vertex -866.425 261.869 -0.00340379 + vertex -863.311 255.08 -0.00390502 + endloop + endfacet + facet normal -3.86468e-05 9.95817e-05 -1 + outer loop + vertex -867.833 254.294 -0.00380855 + vertex -863.311 255.08 -0.00390502 + vertex -864.246 247.423 -0.00463138 + endloop + endfacet + facet normal 4.04279e-06 7.56727e-05 -1 + outer loop + vertex -866.425 261.869 -0.00340379 + vertex -862 262.35 -0.00334956 + vertex -863.311 255.08 -0.00390502 + endloop + endfacet + facet normal 9.49812e-05 5.92623e-05 -1 + outer loop + vertex -863.311 255.08 -0.00390502 + vertex -862 262.35 -0.00334956 + vertex -858.888 255.649 -0.0034511 + endloop + endfacet + facet normal 8.75524e-05 0.000116936 -1 + outer loop + vertex -863.311 255.08 -0.00390502 + vertex -858.888 255.649 -0.0034511 + vertex -859.757 248.303 -0.00438624 + endloop + endfacet + facet normal 0.000130584 7.57958e-05 -1 + outer loop + vertex -862 262.35 -0.00334956 + vertex -857.678 262.674 -0.00276058 + vertex -858.888 255.649 -0.0034511 + endloop + endfacet + facet normal 0.000169881 6.90254e-05 -1 + outer loop + vertex -858.888 255.649 -0.0034511 + vertex -857.678 262.674 -0.00276058 + vertex -854.533 256.045 -0.00268395 + endloop + endfacet + facet normal 0.000166871 0.000102188 -1 + outer loop + vertex -858.888 255.649 -0.0034511 + vertex -854.533 256.045 -0.00268395 + vertex -855.321 248.951 -0.00354036 + endloop + endfacet + facet normal 0.000171458 6.97735e-05 -1 + outer loop + vertex -857.678 262.674 -0.00276058 + vertex -853.422 262.879 -0.0020166 + vertex -854.533 256.045 -0.00268395 + endloop + endfacet + facet normal 0.00017513 6.91765e-05 -1 + outer loop + vertex -854.533 256.045 -0.00268395 + vertex -853.422 262.879 -0.0020166 + vertex -850.234 256.312 -0.00191251 + endloop + endfacet + facet normal 0.000174258 8.31914e-05 -1 + outer loop + vertex -854.533 256.045 -0.00268395 + vertex -850.234 256.312 -0.00191251 + vertex -850.94 249.429 -0.00260836 + endloop + endfacet + facet normal 0.000168479 6.59472e-05 -1 + outer loop + vertex -853.422 262.879 -0.0020166 + vertex -849.219 262.988 -0.00130137 + vertex -850.234 256.312 -0.00191251 + endloop + endfacet + facet normal 0.000159307 6.73409e-05 -1 + outer loop + vertex -850.234 256.312 -0.00191251 + vertex -849.219 262.988 -0.00130137 + vertex -845.971 256.483 -0.00122195 + endloop + endfacet + facet normal 0.000159038 7.40486e-05 -1 + outer loop + vertex -850.234 256.312 -0.00191251 + vertex -845.971 256.483 -0.00122195 + vertex -846.606 249.782 -0.0018191 + endloop + endfacet + facet normal 0.00013856 5.69808e-05 -1 + outer loop + vertex -849.219 262.988 -0.00130137 + vertex -845.038 263.029 -0.0007197 + vertex -845.971 256.483 -0.00122195 + endloop + endfacet + facet normal 0.000129524 5.82686e-05 -1 + outer loop + vertex -845.971 256.483 -0.00122195 + vertex -845.038 263.029 -0.0007197 + vertex -841.739 256.583 -0.000667959 + endloop + endfacet + facet normal 0.000129439 6.1869e-05 -1 + outer loop + vertex -845.971 256.483 -0.00122195 + vertex -841.739 256.583 -0.000667959 + vertex -842.309 250.031 -0.0011472 + endloop + endfacet + facet normal 9.38511e-05 4.00101e-05 -1 + outer loop + vertex -845.038 263.029 -0.0007197 + vertex -840.892 263.018 -0.000331028 + vertex -841.739 256.583 -0.000667959 + endloop + endfacet + facet normal 8.58283e-05 4.10653e-05 -1 + outer loop + vertex -841.739 256.583 -0.000667959 + vertex -840.892 263.018 -0.000331028 + vertex -837.526 256.628 -0.000304575 + endloop + endfacet + facet normal 8.58117e-05 4.26208e-05 -1 + outer loop + vertex -841.739 256.583 -0.000667959 + vertex -837.526 256.628 -0.000304575 + vertex -838.024 250.199 -0.00062128 + endloop + endfacet + facet normal 5.03032e-05 2.23547e-05 -1 + outer loop + vertex -840.892 263.018 -0.000331028 + vertex -836.786 262.965 -0.000125694 + vertex -837.526 256.628 -0.000304575 + endloop + endfacet + facet normal 4.55182e-05 2.29135e-05 -1 + outer loop + vertex -837.526 256.628 -0.000304575 + vertex -836.786 262.965 -0.000125694 + vertex -833.337 256.615 -0.00011416 + endloop + endfacet + facet normal 4.55188e-05 2.31047e-05 -1 + outer loop + vertex -837.526 256.628 -0.000304575 + vertex -833.337 256.615 -0.00011416 + vertex -833.737 250.288 -0.000278546 + endloop + endfacet + facet normal 2.15366e-05 9.8842e-06 -1 + outer loop + vertex -836.786 262.965 -0.000125694 + vertex -832.725 262.861 -3.92602e-05 + vertex -833.337 256.615 -0.00011416 + endloop + endfacet + facet normal 1.90099e-05 1.01316e-05 -1 + outer loop + vertex -833.337 256.615 -0.00011416 + vertex -832.725 262.861 -3.92602e-05 + vertex -829.16 256.529 -3.56326e-05 + endloop + endfacet + facet normal 7.33141e-06 3.55542e-06 -1 + outer loop + vertex -832.725 262.861 -3.92602e-05 + vertex -828.705 262.703 -1.03445e-05 + vertex -829.16 256.529 -3.56326e-05 + endloop + endfacet + facet normal 7.32889e-06 3.4909e-06 -1 + outer loop + vertex -832.725 262.861 -3.92602e-05 + vertex -831.908 269.131 -1.1381e-05 + vertex -828.705 262.703 -1.03445e-05 + endloop + endfacet + facet normal 2.45318e-06 1.06123e-06 -1 + outer loop + vertex -831.908 269.131 -1.1381e-05 + vertex -828.191 268.977 -2.42559e-06 + vertex -828.705 262.703 -1.03445e-05 + endloop + endfacet + facet normal 2.16768e-06 1.08461e-06 -1 + outer loop + vertex -828.705 262.703 -1.03445e-05 + vertex -828.191 268.977 -2.42559e-06 + vertex -824.89 262.584 -2.20485e-06 + endloop + endfacet + facet normal 7.87305e-07 3.71945e-07 -1 + outer loop + vertex -828.191 268.977 -2.42559e-06 + vertex -825.048 268.845 -7.56606e-14 + vertex -824.89 262.584 -2.20485e-06 + endloop + endfacet + facet normal 7.86578e-07 3.54606e-07 -1 + outer loop + vertex -828.191 268.977 -2.42559e-06 + vertex -828.115 275.65 -7.94049e-14 + vertex -825.048 268.845 -7.56606e-14 + endloop + endfacet + facet normal 9.0398e-07 3.53279e-07 -1 + outer loop + vertex -831.072 275.658 -2.6701e-06 + vertex -828.115 275.65 -7.94049e-14 + vertex -828.191 268.977 -2.42559e-06 + endloop + endfacet + facet normal 9.03925e-07 3.32375e-07 -1 + outer loop + vertex -831.072 275.658 -2.6701e-06 + vertex -830.662 282.575 -8.41863e-14 + vertex -828.115 275.65 -7.94049e-14 + endloop + endfacet + facet normal 1.02594e-06 3.25135e-07 -1 + outer loop + vertex -833.522 282.687 -2.89781e-06 + vertex -830.662 282.575 -8.41863e-14 + vertex -831.072 275.658 -2.6701e-06 + endloop + endfacet + facet normal 2.7243e-06 9.16993e-07 -1 + outer loop + vertex -834.671 275.815 -1.23294e-05 + vertex -833.522 282.687 -2.89781e-06 + vertex -831.072 275.658 -2.6701e-06 + endloop + endfacet + facet normal 2.72728e-06 9.85387e-07 -1 + outer loop + vertex -834.671 275.815 -1.23294e-05 + vertex -831.072 275.658 -2.6701e-06 + vertex -831.908 269.131 -1.1381e-05 + endloop + endfacet + facet normal 8.37186e-06 3.31851e-06 -1 + outer loop + vertex -835.813 269.304 -4.35028e-05 + vertex -834.671 275.815 -1.23294e-05 + vertex -831.908 269.131 -1.1381e-05 + endloop + endfacet + facet normal 9.16837e-06 3.17872e-06 -1 + outer loop + vertex -838.487 276.024 -4.66493e-05 + vertex -834.671 275.815 -1.23294e-05 + vertex -835.813 269.304 -4.35028e-05 + endloop + endfacet + facet normal 2.39296e-05 9.0503e-06 -1 + outer loop + vertex -839.787 269.446 -0.000137298 + vertex -838.487 276.024 -4.66493e-05 + vertex -835.813 269.304 -4.35028e-05 + endloop + endfacet + facet normal 2.39382e-05 9.29137e-06 -1 + outer loop + vertex -839.787 269.446 -0.000137298 + vertex -835.813 269.304 -4.35028e-05 + vertex -836.786 262.965 -0.000125694 + endloop + endfacet + facet normal 2.60407e-05 8.63291e-06 -1 + outer loop + vertex -842.383 276.217 -0.000146457 + vertex -838.487 276.024 -4.66493e-05 + vertex -839.787 269.446 -0.000137298 + endloop + endfacet + facet normal 5.5212e-05 1.98189e-05 -1 + outer loop + vertex -843.819 269.55 -0.000357859 + vertex -842.383 276.217 -0.000146457 + vertex -839.787 269.446 -0.000137298 + endloop + endfacet + facet normal 5.5233e-05 2.06416e-05 -1 + outer loop + vertex -843.819 269.55 -0.000357859 + vertex -839.787 269.446 -0.000137298 + vertex -840.892 263.018 -0.000331028 + endloop + endfacet + facet normal 5.97732e-05 1.88369e-05 -1 + outer loop + vertex -846.341 276.37 -0.000380117 + vertex -842.383 276.217 -0.000146457 + vertex -843.819 269.55 -0.000357859 + endloop + endfacet + facet normal 0.000101597 3.43006e-05 -1 + outer loop + vertex -847.898 269.61 -0.000770202 + vertex -846.341 276.37 -0.000380117 + vertex -843.819 269.55 -0.000357859 + endloop + endfacet + facet normal 0.000101629 3.64887e-05 -1 + outer loop + vertex -847.898 269.61 -0.000770202 + vertex -843.819 269.55 -0.000357859 + vertex -845.038 263.029 -0.0007197 + endloop + endfacet + facet normal 0.000109866 3.23961e-05 -1 + outer loop + vertex -850.346 276.478 -0.000816676 + vertex -846.341 276.37 -0.000380117 + vertex -847.898 269.61 -0.000770202 + endloop + endfacet + facet normal 0.000150019 4.6709e-05 -1 + outer loop + vertex -852.01 269.618 -0.00138672 + vertex -850.346 276.478 -0.000816676 + vertex -847.898 269.61 -0.000770202 + endloop + endfacet + facet normal 0.000150027 5.02756e-05 -1 + outer loop + vertex -852.01 269.618 -0.00138672 + vertex -847.898 269.61 -0.000770202 + vertex -849.219 262.988 -0.00130137 + endloop + endfacet + facet normal 0.00016243 4.36986e-05 -1 + outer loop + vertex -854.387 276.543 -0.00147024 + vertex -850.346 276.478 -0.000816676 + vertex -852.01 269.618 -0.00138672 + endloop + endfacet + facet normal 0.000179266 4.94782e-05 -1 + outer loop + vertex -856.159 269.562 -0.00213322 + vertex -854.387 276.543 -0.00147024 + vertex -852.01 269.618 -0.00138672 + endloop + endfacet + facet normal 0.000179179 5.59292e-05 -1 + outer loop + vertex -856.159 269.562 -0.00213322 + vertex -852.01 269.618 -0.00138672 + vertex -853.422 262.879 -0.0020166 + endloop + endfacet + facet normal 0.000192042 4.62356e-05 -1 + outer loop + vertex -858.48 276.543 -0.00225626 + vertex -854.387 276.543 -0.00147024 + vertex -856.159 269.562 -0.00213322 + endloop + endfacet + facet normal 0.000173843 4.01836e-05 -1 + outer loop + vertex -860.363 269.42 -0.00286973 + vertex -858.48 276.543 -0.00225626 + vertex -856.159 269.562 -0.00213322 + endloop + endfacet + facet normal 0.000173415 5.28403e-05 -1 + outer loop + vertex -860.363 269.42 -0.00286973 + vertex -856.159 269.562 -0.00213322 + vertex -857.678 262.674 -0.00276058 + endloop + endfacet + facet normal 0.00018152 3.81545e-05 -1 + outer loop + vertex -862.639 276.466 -0.00301408 + vertex -858.48 276.543 -0.00225626 + vertex -860.363 269.42 -0.00286973 + endloop + endfacet + facet normal 0.00010634 1.3867e-05 -1 + outer loop + vertex -864.653 269.169 -0.00332951 + vertex -862.639 276.466 -0.00301408 + vertex -860.363 269.42 -0.00286973 + endloop + endfacet + facet normal 0.000104597 4.36466e-05 -1 + outer loop + vertex -864.653 269.169 -0.00332951 + vertex -860.363 269.42 -0.00286973 + vertex -862 262.35 -0.00334956 + endloop + endfacet + facet normal 9.81225e-05 1.6136e-05 -1 + outer loop + vertex -866.902 276.288 -0.00343527 + vertex -862.639 276.466 -0.00301408 + vertex -864.653 269.169 -0.00332951 + endloop + endfacet + facet normal -5.50075e-05 -3.22318e-05 -1 + outer loop + vertex -869.071 268.776 -0.00307381 + vertex -866.902 276.288 -0.00343527 + vertex -864.653 269.169 -0.00332951 + endloop + endfacet + facet normal -6.0086e-05 2.47577e-05 -1 + outer loop + vertex -869.071 268.776 -0.00307381 + vertex -864.653 269.169 -0.00332951 + vertex -866.425 261.869 -0.00340379 + endloop + endfacet + facet normal -9.21566e-05 -2.15045e-05 -1 + outer loop + vertex -871.307 275.983 -0.00302277 + vertex -866.902 276.288 -0.00343527 + vertex -869.071 268.776 -0.00307381 + endloop + endfacet + facet normal -0.000211812 -5.8619e-05 -1 + outer loop + vertex -873.647 268.198 -0.00207063 + vertex -871.307 275.983 -0.00302277 + vertex -869.071 268.776 -0.00307381 + endloop + endfacet + facet normal -0.000222392 2.51791e-05 -1 + outer loop + vertex -873.647 268.198 -0.00207063 + vertex -869.071 268.776 -0.00307381 + vertex -870.974 261.183 -0.00284185 + endloop + endfacet + facet normal -0.000266911 -4.20548e-05 -1 + outer loop + vertex -875.892 275.511 -0.00177904 + vertex -871.307 275.983 -0.00302277 + vertex -873.647 268.198 -0.00207063 + endloop + endfacet + facet normal -0.000116091 4.23814e-06 -1 + outer loop + vertex -878.359 267.375 -0.00152719 + vertex -875.892 275.511 -0.00177904 + vertex -873.647 268.198 -0.00207063 + endloop + endfacet + facet normal -0.000133424 0.000103521 -1 + outer loop + vertex -878.359 267.375 -0.00152719 + vertex -873.647 268.198 -0.00207063 + vertex -875.635 260.237 -0.00262951 + endloop + endfacet + facet normal -0.000170015 2.05855e-05 -1 + outer loop + vertex -880.649 274.815 -0.000984687 + vertex -875.892 275.511 -0.00177904 + vertex -878.359 267.375 -0.00152719 + endloop + endfacet + facet normal -0.000133977 3.16785e-05 -1 + outer loop + vertex -883.144 266.253 -0.000921577 + vertex -880.649 274.815 -0.000984687 + vertex -878.359 267.375 -0.00152719 + endloop + endfacet + facet normal -0.000154012 0.000117149 -1 + outer loop + vertex -883.144 266.253 -0.000921577 + vertex -878.359 267.375 -0.00152719 + vertex -880.329 258.975 -0.00220771 + endloop + endfacet + facet normal -0.000189616 4.78952e-05 -1 + outer loop + vertex -885.516 273.836 -0.000108742 + vertex -880.649 274.815 -0.000984687 + vertex -883.144 266.253 -0.000921577 + endloop + endfacet + facet normal -0.00236567 -0.000632711 -0.999997 + outer loop + vertex -887.904 264.804 0.011255 + vertex -885.516 273.836 -0.000108742 + vertex -883.144 266.253 -0.000921577 + endloop + endfacet + facet normal -0.00231436 -0.000801215 -0.999997 + outer loop + vertex -887.904 264.804 0.011255 + vertex -883.144 266.253 -0.000921577 + vertex -884.952 257.37 0.0103808 + endloop + endfacet + facet normal -0.0103731 -0.0040006 -0.999938 + outer loop + vertex -889.517 255.485 0.0652731 + vertex -887.904 264.804 0.011255 + vertex -884.952 257.37 0.0103808 + endloop + endfacet + facet normal -0.00984345 -0.00409231 -0.999943 + outer loop + vertex -892.631 263.084 0.0648305 + vertex -887.904 264.804 0.011255 + vertex -889.517 255.485 0.0652731 + endloop + endfacet + facet normal -0.0267233 -0.0110101 -0.999582 + outer loop + vertex -894.129 253.446 0.211047 + vertex -892.631 263.084 0.0648305 + vertex -889.517 255.485 0.0652731 + endloop + endfacet + facet normal -0.0259372 -0.0127883 -0.999582 + outer loop + vertex -894.129 253.446 0.211047 + vertex -889.517 255.485 0.0652731 + vertex -890.322 245.85 0.209431 + endloop + endfacet + facet normal -0.0496809 -0.0246901 -0.99846 + outer loop + vertex -894.965 243.613 0.49575 + vertex -894.129 253.446 0.211047 + vertex -890.322 245.85 0.209431 + endloop + endfacet + facet normal -0.0484355 -0.0247975 -0.998518 + outer loop + vertex -898.998 251.412 0.497717 + vertex -894.129 253.446 0.211047 + vertex -894.965 243.613 0.49575 + endloop + endfacet + facet normal -0.0757872 -0.0389435 -0.996363 + outer loop + vertex -899.985 241.441 0.962554 + vertex -898.998 251.412 0.497717 + vertex -894.965 243.613 0.49575 + endloop + endfacet + facet normal -0.0734228 -0.044396 -0.996312 + outer loop + vertex -899.985 241.441 0.962554 + vertex -894.965 243.613 0.49575 + vertex -895.164 233.516 0.960365 + endloop + endfacet + facet normal -0.0752101 -0.0443547 -0.996181 + outer loop + vertex -895.164 233.516 0.960365 + vertex -894.965 243.613 0.49575 + vertex -890.402 235.912 0.494201 + endloop + endfacet + facet normal -0.0732648 -0.0392015 -0.996542 + outer loop + vertex -904.267 249.461 0.961884 + vertex -898.998 251.412 0.497717 + vertex -899.985 241.441 0.962554 + endloop + endfacet + facet normal -0.0754435 -0.0333309 -0.996593 + outer loop + vertex -904.267 249.461 0.961884 + vertex -902.537 259.429 0.497499 + vertex -898.998 251.412 0.497717 + endloop + endfacet + facet normal -0.0483119 -0.0213539 -0.998604 + outer loop + vertex -902.537 259.429 0.497499 + vertex -897.438 261.241 0.212066 + vertex -898.998 251.412 0.497717 + endloop + endfacet + facet normal -0.0497154 -0.0174051 -0.998612 + outer loop + vertex -902.537 259.429 0.497499 + vertex -900.299 269.374 0.212736 + vertex -897.438 261.241 0.212066 + endloop + endfacet + facet normal -0.0262538 -0.00915238 -0.999613 + outer loop + vertex -900.299 269.374 0.212736 + vertex -895.29 271.009 0.066213 + vertex -897.438 261.241 0.212066 + endloop + endfacet + facet normal -0.0271876 -0.00894667 -0.99959 + outer loop + vertex -897.438 261.241 0.212066 + vertex -895.29 271.009 0.066213 + vertex -892.631 263.084 0.0648305 + endloop + endfacet + facet normal -0.0100757 -0.0032058 -0.999944 + outer loop + vertex -895.29 271.009 0.066213 + vertex -890.399 272.547 0.0120048 + vertex -892.631 263.084 0.0648305 + endloop + endfacet + facet normal -0.010266 -0.00260073 -0.999944 + outer loop + vertex -895.29 271.009 0.066213 + vertex -892.487 280.668 0.0123124 + vertex -890.399 272.547 0.0120048 + endloop + endfacet + facet normal -0.0023415 -0.000563939 -0.999997 + outer loop + vertex -892.487 280.668 0.0123124 + vertex -887.491 281.798 -2.14173e-05 + vertex -890.399 272.547 0.0120048 + endloop + endfacet + facet normal -0.00233071 -0.000567331 -0.999997 + outer loop + vertex -890.399 272.547 0.0120048 + vertex -887.491 281.798 -2.14173e-05 + vertex -885.516 273.836 -0.000108742 + endloop + endfacet + facet normal -0.00018083 -3.39002e-05 -1 + outer loop + vertex -887.491 281.798 -2.14173e-05 + vertex -882.553 282.636 -0.000942726 + vertex -885.516 273.836 -0.000108742 + endloop + endfacet + facet normal -0.000177287 -5.47878e-05 -1 + outer loop + vertex -887.491 281.798 -2.14173e-05 + vertex -884.053 290.794 -0.00112391 + vertex -882.553 282.636 -0.000942726 + endloop + endfacet + facet normal -0.000182294 -5.5708e-05 -1 + outer loop + vertex -884.053 290.794 -0.00112391 + vertex -879.227 291.246 -0.00202886 + vertex -882.553 282.636 -0.000942726 + endloop + endfacet + facet normal -0.000183103 -5.53954e-05 -1 + outer loop + vertex -882.553 282.636 -0.000942726 + vertex -879.227 291.246 -0.00202886 + vertex -877.754 283.208 -0.00185317 + endloop + endfacet + facet normal -0.000184976 -3.96852e-05 -1 + outer loop + vertex -882.553 282.636 -0.000942726 + vertex -877.754 283.208 -0.00185317 + vertex -880.649 274.815 -0.000984687 + endloop + endfacet + facet normal -0.000280731 -7.32783e-05 -1 + outer loop + vertex -879.227 291.246 -0.00202886 + vertex -874.628 291.511 -0.00333926 + vertex -877.754 283.208 -0.00185317 + endloop + endfacet + facet normal -0.00027899 -7.39336e-05 -1 + outer loop + vertex -877.754 283.208 -0.00185317 + vertex -874.628 291.511 -0.00333926 + vertex -873.162 283.575 -0.00316163 + endloop + endfacet + facet normal -0.00027874 -7.70624e-05 -1 + outer loop + vertex -877.754 283.208 -0.00185317 + vertex -873.162 283.575 -0.00316163 + vertex -875.892 275.511 -0.00177904 + endloop + endfacet + facet normal -9.35363e-05 -3.96669e-05 -1 + outer loop + vertex -874.628 291.511 -0.00333926 + vertex -870.252 291.638 -0.00375361 + vertex -873.162 283.575 -0.00316163 + endloop + endfacet + facet normal -9.8461e-05 -3.78899e-05 -1 + outer loop + vertex -873.162 283.575 -0.00316163 + vertex -870.252 291.638 -0.00375361 + vertex -868.772 283.791 -0.00360204 + endloop + endfacet + facet normal -9.82447e-05 -4.22908e-05 -1 + outer loop + vertex -873.162 283.575 -0.00316163 + vertex -868.772 283.791 -0.00360204 + vertex -871.307 275.983 -0.00302277 + endloop + endfacet + facet normal 0.000111543 1.72832e-06 -1 + outer loop + vertex -870.252 291.638 -0.00375361 + vertex -866.052 291.661 -0.00328503 + vertex -868.772 283.791 -0.00360204 + endloop + endfacet + facet normal 0.000102377 4.8965e-06 -1 + outer loop + vertex -868.772 283.791 -0.00360204 + vertex -866.052 291.661 -0.00328503 + vertex -864.543 283.89 -0.00316866 + endloop + endfacet + facet normal 0.000102414 3.29434e-06 -1 + outer loop + vertex -868.772 283.791 -0.00360204 + vertex -864.543 283.89 -0.00316866 + vertex -866.902 276.288 -0.00343527 + endloop + endfacet + facet normal 0.000205785 2.49695e-05 -1 + outer loop + vertex -866.052 291.661 -0.00328503 + vertex -861.975 291.601 -0.00244769 + vertex -864.543 283.89 -0.00316866 + endloop + endfacet + facet normal 0.000194355 2.87762e-05 -1 + outer loop + vertex -864.543 283.89 -0.00316866 + vertex -861.975 291.601 -0.00244769 + vertex -860.428 283.898 -0.00236858 + endloop + endfacet + facet normal 0.000194354 2.90354e-05 -1 + outer loop + vertex -864.543 283.89 -0.00316866 + vertex -860.428 283.898 -0.00236858 + vertex -862.639 276.466 -0.00301408 + endloop + endfacet + facet normal 0.000216833 3.32922e-05 -1 + outer loop + vertex -861.975 291.601 -0.00244769 + vertex -857.986 291.474 -0.00158691 + vertex -860.428 283.898 -0.00236858 + endloop + endfacet + facet normal 0.000206105 3.67498e-05 -1 + outer loop + vertex -860.428 283.898 -0.00236858 + vertex -857.986 291.474 -0.00158691 + vertex -856.388 283.837 -0.00153823 + endloop + endfacet + facet normal 0.000206145 3.93191e-05 -1 + outer loop + vertex -860.428 283.898 -0.00236858 + vertex -856.388 283.837 -0.00153823 + vertex -858.48 276.543 -0.00225626 + endloop + endfacet + facet normal 0.000180849 3.14654e-05 -1 + outer loop + vertex -857.986 291.474 -0.00158691 + vertex -854.058 291.296 -0.000882144 + vertex -856.388 283.837 -0.00153823 + endloop + endfacet + facet normal 0.000172015 3.42246e-05 -1 + outer loop + vertex -856.388 283.837 -0.00153823 + vertex -854.058 291.296 -0.000882144 + vertex -852.403 283.721 -0.000856669 + endloop + endfacet + facet normal 0.000172122 3.78987e-05 -1 + outer loop + vertex -856.388 283.837 -0.00153823 + vertex -852.403 283.721 -0.000856669 + vertex -854.387 276.543 -0.00147024 + endloop + endfacet + facet normal 0.000122781 2.34662e-05 -1 + outer loop + vertex -854.058 291.296 -0.000882144 + vertex -850.185 291.079 -0.000411717 + vertex -852.403 283.721 -0.000856669 + endloop + endfacet + facet normal 0.000116985 2.52127e-05 -1 + outer loop + vertex -852.403 283.721 -0.000856669 + vertex -850.185 291.079 -0.000411717 + vertex -848.467 283.559 -0.000400333 + endloop + endfacet + facet normal 0.000117088 2.77297e-05 -1 + outer loop + vertex -852.403 283.721 -0.000856669 + vertex -848.467 283.559 -0.000400333 + vertex -850.346 276.478 -0.000816676 + endloop + endfacet + facet normal 6.65407e-05 1.36881e-05 -1 + outer loop + vertex -850.185 291.079 -0.000411717 + vertex -846.365 290.829 -0.000160962 + vertex -848.467 283.559 -0.000400333 + endloop + endfacet + facet normal 6.39572e-05 1.44351e-05 -1 + outer loop + vertex -848.467 283.559 -0.000400333 + vertex -846.365 290.829 -0.000160962 + vertex -844.585 283.357 -0.00015493 + endloop + endfacet + facet normal 6.40456e-05 1.61333e-05 -1 + outer loop + vertex -848.467 283.559 -0.000400333 + vertex -844.585 283.357 -0.00015493 + vertex -846.341 276.37 -0.000380117 + endloop + endfacet + facet normal 2.95366e-05 6.23193e-06 -1 + outer loop + vertex -846.365 290.829 -0.000160962 + vertex -842.611 290.539 -5.18894e-05 + vertex -844.585 283.357 -0.00015493 + endloop + endfacet + facet normal 2.79418e-05 6.67014e-06 -1 + outer loop + vertex -844.585 283.357 -0.00015493 + vertex -842.611 290.539 -5.18894e-05 + vertex -840.761 283.114 -4.97246e-05 + endloop + endfacet + facet normal 2.79911e-05 7.4431e-06 -1 + outer loop + vertex -844.585 283.357 -0.00015493 + vertex -840.761 283.114 -4.97246e-05 + vertex -842.383 276.217 -0.000146457 + endloop + endfacet + facet normal 1.05254e-05 2.33083e-06 -1 + outer loop + vertex -842.611 290.539 -5.18894e-05 + vertex -838.939 290.23 -1.39533e-05 + vertex -840.761 283.114 -4.97246e-05 + endloop + endfacet + facet normal 9.92132e-06 2.48555e-06 -1 + outer loop + vertex -840.761 283.114 -4.97246e-05 + vertex -838.939 290.23 -1.39533e-05 + vertex -837.021 282.854 -1.3257e-05 + endloop + endfacet + facet normal 9.94007e-06 2.75563e-06 -1 + outer loop + vertex -840.761 283.114 -4.97246e-05 + vertex -837.021 282.854 -1.3257e-05 + vertex -838.487 276.024 -4.66493e-05 + endloop + endfacet + facet normal 3.25833e-06 7.52899e-07 -1 + outer loop + vertex -838.939 290.23 -1.39533e-05 + vertex -835.513 290.035 -2.93856e-06 + vertex -837.021 282.854 -1.3257e-05 + endloop + endfacet + facet normal 2.99934e-06 8.07269e-07 -1 + outer loop + vertex -837.021 282.854 -1.3257e-05 + vertex -835.513 290.035 -2.93856e-06 + vertex -833.522 282.687 -2.89781e-06 + endloop + endfacet + facet normal 1.08043e-06 2.87249e-07 -1 + outer loop + vertex -835.513 290.035 -2.93856e-06 + vertex -832.843 290.221 -9.05812e-14 + vertex -833.522 282.687 -2.89781e-06 + endloop + endfacet + facet normal 1.08491e-06 2.23014e-07 -1 + outer loop + vertex -835.513 290.035 -2.93856e-06 + vertex -834.389 297.745 -9.79775e-14 + vertex -832.843 290.221 -9.05812e-14 + endloop + endfacet + facet normal 1.16436e-06 2.11436e-07 -1 + outer loop + vertex -837.002 297.579 -3.07686e-06 + vertex -834.389 297.745 -9.79775e-14 + vertex -835.513 290.035 -2.93856e-06 + endloop + endfacet + facet normal 1.16789e-06 1.56035e-07 -1 + outer loop + vertex -837.002 297.579 -3.07686e-06 + vertex -835.365 305.049 -1.06159e-13 + vertex -834.389 297.745 -9.79775e-14 + endloop + endfacet + facet normal 1.26041e-06 1.35769e-07 -1 + outer loop + vertex -837.976 305.364 -3.24787e-06 + vertex -835.365 305.049 -1.06159e-13 + vertex -837.002 297.579 -3.07686e-06 + endloop + endfacet + facet normal 3.41513e-06 4.05423e-07 -1 + outer loop + vertex -840.373 297.866 -1.4473e-05 + vertex -837.976 305.364 -3.24787e-06 + vertex -837.002 297.579 -3.07686e-06 + endloop + endfacet + facet normal 3.42969e-06 5.76086e-07 -1 + outer loop + vertex -840.373 297.866 -1.4473e-05 + vertex -837.002 297.579 -3.07686e-06 + vertex -838.939 290.23 -1.39533e-05 + endloop + endfacet + facet normal 3.41222e-06 4.06354e-07 -1 + outer loop + vertex -841.3 305.707 -1.4452e-05 + vertex -837.976 305.364 -3.24787e-06 + vertex -840.373 297.866 -1.4473e-05 + endloop + endfacet + facet normal 1.08706e-05 1.28871e-06 -1 + outer loop + vertex -843.987 298.221 -5.33042e-05 + vertex -841.3 305.707 -1.4452e-05 + vertex -840.373 297.866 -1.4473e-05 + endloop + endfacet + facet normal 1.09179e-05 1.77106e-06 -1 + outer loop + vertex -843.987 298.221 -5.33042e-05 + vertex -840.373 297.866 -1.4473e-05 + vertex -842.611 290.539 -5.18894e-05 + endloop + endfacet + facet normal 1.10568e-05 1.2219e-06 -1 + outer loop + vertex -844.87 306.106 -5.34282e-05 + vertex -841.3 305.707 -1.4452e-05 + vertex -843.987 298.221 -5.33042e-05 + endloop + endfacet + facet normal 2.99822e-05 3.34028e-06 -1 + outer loop + vertex -847.687 298.556 -0.000163115 + vertex -844.87 306.106 -5.34282e-05 + vertex -843.987 298.221 -5.33042e-05 + endloop + endfacet + facet normal 3.01209e-05 4.87312e-06 -1 + outer loop + vertex -847.687 298.556 -0.000163115 + vertex -843.987 298.221 -5.33042e-05 + vertex -846.365 290.829 -0.000160962 + endloop + endfacet + facet normal 3.10763e-05 2.932e-06 -1 + outer loop + vertex -848.52 306.493 -0.000165746 + vertex -844.87 306.106 -5.34282e-05 + vertex -847.687 298.556 -0.000163115 + endloop + endfacet + facet normal 6.87729e-05 6.89074e-06 -1 + outer loop + vertex -851.448 298.861 -0.000419655 + vertex -848.52 306.493 -0.000165746 + vertex -847.687 298.556 -0.000163115 + endloop + endfacet + facet normal 6.90401e-05 1.01803e-05 -1 + outer loop + vertex -851.448 298.861 -0.000419655 + vertex -847.687 298.556 -0.000163115 + vertex -850.185 291.079 -0.000411717 + endloop + endfacet + facet normal 7.00729e-05 6.39207e-06 -1 + outer loop + vertex -852.239 306.853 -0.000424 + vertex -848.52 306.493 -0.000165746 + vertex -851.448 298.861 -0.000419655 + endloop + endfacet + facet normal 0.000125562 1.18843e-05 -1 + outer loop + vertex -855.27 299.135 -0.000896355 + vertex -852.239 306.853 -0.000424 + vertex -851.448 298.861 -0.000419655 + endloop + endfacet + facet normal 0.000125976 1.76647e-05 -1 + outer loop + vertex -855.27 299.135 -0.000896355 + vertex -851.448 298.861 -0.000419655 + vertex -854.058 291.296 -0.000882144 + endloop + endfacet + facet normal 0.000128029 1.09155e-05 -1 + outer loop + vertex -856.018 307.185 -0.000904261 + vertex -852.239 306.853 -0.000424 + vertex -855.27 299.135 -0.000896355 + endloop + endfacet + facet normal 0.000186272 1.6328e-05 -1 + outer loop + vertex -859.148 299.373 -0.00161486 + vertex -856.018 307.185 -0.000904261 + vertex -855.27 299.135 -0.000896355 + endloop + endfacet + facet normal 0.000186739 2.39374e-05 -1 + outer loop + vertex -859.148 299.373 -0.00161486 + vertex -855.27 299.135 -0.000896355 + vertex -857.986 291.474 -0.00158691 + endloop + endfacet + facet normal 0.000189699 1.49545e-05 -1 + outer loop + vertex -859.858 307.483 -0.0016282 + vertex -856.018 307.185 -0.000904261 + vertex -859.148 299.373 -0.00161486 + endloop + endfacet + facet normal 0.000223793 1.7938e-05 -1 + outer loop + vertex -863.098 299.563 -0.00249527 + vertex -859.858 307.483 -0.0016282 + vertex -859.148 299.373 -0.00161486 + endloop + endfacet + facet normal 0.000224163 2.56191e-05 -1 + outer loop + vertex -863.098 299.563 -0.00249527 + vertex -859.148 299.373 -0.00161486 + vertex -861.975 291.601 -0.00244769 + endloop + endfacet + facet normal 0.000228284 1.6101e-05 -1 + outer loop + vertex -863.772 307.737 -0.00251754 + vertex -859.858 307.483 -0.0016282 + vertex -863.098 299.563 -0.00249527 + endloop + endfacet + facet normal 0.000214299 1.49478e-05 -1 + outer loop + vertex -867.138 299.693 -0.00335925 + vertex -863.772 307.737 -0.00251754 + vertex -863.098 299.563 -0.00249527 + endloop + endfacet + facet normal 0.000214454 1.97732e-05 -1 + outer loop + vertex -867.138 299.693 -0.00335925 + vertex -863.098 299.563 -0.00249527 + vertex -866.052 291.661 -0.00328503 + endloop + endfacet + facet normal 0.000219272 1.28664e-05 -1 + outer loop + vertex -867.785 307.935 -0.00339498 + vertex -863.772 307.737 -0.00251754 + vertex -867.138 299.693 -0.00335925 + endloop + endfacet + facet normal 0.000120096 5.08633e-06 -1 + outer loop + vertex -871.313 299.747 -0.00386034 + vertex -867.785 307.935 -0.00339498 + vertex -867.138 299.693 -0.00335925 + endloop + endfacet + facet normal 0.000120063 2.54549e-06 -1 + outer loop + vertex -871.313 299.747 -0.00386034 + vertex -867.138 299.693 -0.00335925 + vertex -870.252 291.638 -0.00375361 + endloop + endfacet + facet normal 0.000123414 3.65691e-06 -1 + outer loop + vertex -871.935 308.065 -0.00390666 + vertex -867.785 307.935 -0.00339498 + vertex -871.313 299.747 -0.00386034 + endloop + endfacet + facet normal -9.17285e-05 -1.24254e-05 -1 + outer loop + vertex -875.672 299.708 -0.00345999 + vertex -871.935 308.065 -0.00390666 + vertex -871.313 299.747 -0.00386034 + endloop + endfacet + facet normal -9.1601e-05 -2.63994e-05 -1 + outer loop + vertex -875.672 299.708 -0.00345999 + vertex -871.313 299.747 -0.00386034 + vertex -874.628 291.511 -0.00333926 + endloop + endfacet + facet normal -9.22996e-05 -1.217e-05 -1 + outer loop + vertex -876.277 308.11 -0.00350644 + vertex -871.935 308.065 -0.00390666 + vertex -875.672 299.708 -0.00345999 + endloop + endfacet + facet normal -0.000280406 -2.57064e-05 -1 + outer loop + vertex -880.27 299.545 -0.00216642 + vertex -876.277 308.11 -0.00350644 + vertex -875.672 299.708 -0.00345999 + endloop + endfacet + facet normal -0.000279484 -5.17302e-05 -1 + outer loop + vertex -880.27 299.545 -0.00216642 + vertex -875.672 299.708 -0.00345999 + vertex -879.227 291.246 -0.00202886 + endloop + endfacet + facet normal -0.000277036 -2.72776e-05 -1 + outer loop + vertex -880.872 308.045 -0.00223169 + vertex -876.277 308.11 -0.00350644 + vertex -880.27 299.545 -0.00216642 + endloop + endfacet + facet normal -0.000184756 -2.07492e-05 -1 + outer loop + vertex -885.119 299.21 -0.00126363 + vertex -880.872 308.045 -0.00223169 + vertex -880.27 299.545 -0.00216642 + endloop + endfacet + facet normal -0.000183437 -3.98484e-05 -1 + outer loop + vertex -885.119 299.21 -0.00126363 + vertex -880.27 299.545 -0.00216642 + vertex -884.053 290.794 -0.00112391 + endloop + endfacet + facet normal -0.00018801 -4.04279e-05 -1 + outer loop + vertex -889.053 290.094 -0.000155509 + vertex -885.119 299.21 -0.00126363 + vertex -884.053 290.794 -0.00112391 + endloop + endfacet + facet normal -0.000165218 -5.02633e-05 -1 + outer loop + vertex -890.167 298.642 -0.000401164 + vertex -885.119 299.21 -0.00126363 + vertex -889.053 290.094 -0.000155509 + endloop + endfacet + facet normal -0.00231863 -0.000330805 -0.999997 + outer loop + vertex -894.147 289.118 0.0119778 + vertex -890.167 298.642 -0.000401164 + vertex -889.053 290.094 -0.000155509 + endloop + endfacet + facet normal -0.00228828 -0.000489153 -0.999997 + outer loop + vertex -894.147 289.118 0.0119778 + vertex -889.053 290.094 -0.000155509 + vertex -892.487 280.668 0.0123124 + endloop + endfacet + facet normal -0.0102885 -0.00206088 -0.999945 + outer loop + vertex -897.527 279.31 0.0669738 + vertex -894.147 289.118 0.0119778 + vertex -892.487 280.668 0.0123124 + endloop + endfacet + facet normal -0.00998284 -0.00216626 -0.999948 + outer loop + vertex -899.313 287.929 0.0661333 + vertex -894.147 289.118 0.0119778 + vertex -897.527 279.31 0.0669738 + endloop + endfacet + facet normal -0.0261357 -0.00551359 -0.999643 + outer loop + vertex -902.722 277.878 0.210705 + vertex -899.313 287.929 0.0661333 + vertex -897.527 279.31 0.0669738 + endloop + endfacet + facet normal -0.0255798 -0.00752978 -0.999644 + outer loop + vertex -902.722 277.878 0.210705 + vertex -897.527 279.31 0.0669738 + vertex -900.299 269.374 0.212736 + endloop + endfacet + facet normal -0.0491016 -0.014234 -0.998692 + outer loop + vertex -905.62 267.793 0.49691 + vertex -902.722 277.878 0.210705 + vertex -900.299 269.374 0.212736 + endloop + endfacet + facet normal -0.0486773 -0.0143565 -0.998711 + outer loop + vertex -908.236 276.551 0.498494 + vertex -902.722 277.878 0.210705 + vertex -905.62 267.793 0.49691 + endloop + endfacet + facet normal -0.075275 -0.0223 -0.996913 + outer loop + vertex -911.363 266.328 0.963336 + vertex -908.236 276.551 0.498494 + vertex -905.62 267.793 0.49691 + endloop + endfacet + facet normal -0.0737674 -0.0281959 -0.996877 + outer loop + vertex -911.363 266.328 0.963336 + vertex -905.62 267.793 0.49691 + vertex -908.043 257.696 0.96182 + endloop + endfacet + facet normal -0.075291 -0.0278255 -0.996773 + outer loop + vertex -908.043 257.696 0.96182 + vertex -905.62 267.793 0.49691 + vertex -902.537 259.429 0.497499 + endloop + endfacet + facet normal -0.0729522 -0.0230178 -0.99707 + outer loop + vertex -914.206 275.407 0.961696 + vertex -908.236 276.551 0.498494 + vertex -911.363 266.328 0.963336 + endloop + endfacet + facet normal -0.074054 -0.0172802 -0.997105 + outer loop + vertex -914.206 275.407 0.961696 + vertex -910.328 285.615 0.496784 + vertex -908.236 276.551 0.498494 + endloop + endfacet + facet normal -0.0480002 -0.0112671 -0.998784 + outer loop + vertex -910.328 285.615 0.496784 + vertex -904.65 286.697 0.211705 + vertex -908.236 276.551 0.498494 + endloop + endfacet + facet normal -0.0487261 -0.00746098 -0.998784 + outer loop + vertex -910.328 285.615 0.496784 + vertex -906.034 295.731 0.211738 + vertex -904.65 286.697 0.211705 + endloop + endfacet + facet normal -0.025811 -0.00395049 -0.999659 + outer loop + vertex -906.034 295.731 0.211738 + vertex -900.584 296.777 0.0668949 + vertex -904.65 286.697 0.211705 + endloop + endfacet + facet normal -0.0264123 -0.00370774 -0.999644 + outer loop + vertex -904.65 286.697 0.211705 + vertex -900.584 296.777 0.0668949 + vertex -899.313 287.929 0.0661333 + endloop + endfacet + facet normal -0.0102927 -0.00139235 -0.999946 + outer loop + vertex -900.584 296.777 0.0668949 + vertex -895.331 297.808 0.0113898 + vertex -899.313 287.929 0.0661333 + endloop + endfacet + facet normal -0.0104213 -0.000736812 -0.999945 + outer loop + vertex -900.584 296.777 0.0668949 + vertex -896.011 306.68 0.0119328 + vertex -895.331 297.808 0.0113898 + endloop + endfacet + facet normal -0.00235639 -0.000119235 -0.999997 + outer loop + vertex -896.011 306.68 0.0119328 + vertex -890.802 307.379 -0.000423453 + vertex -895.331 297.808 0.0113898 + endloop + endfacet + facet normal -0.00225606 -0.000166713 -0.999997 + outer loop + vertex -895.331 297.808 0.0113898 + vertex -890.802 307.379 -0.000423453 + vertex -890.167 298.642 -0.000401164 + endloop + endfacet + facet normal -0.000177015 -1.54316e-05 -1 + outer loop + vertex -890.802 307.379 -0.000423453 + vertex -885.731 307.824 -0.00132804 + vertex -890.167 298.642 -0.000401164 + endloop + endfacet + facet normal -0.000177783 -6.67669e-06 -1 + outer loop + vertex -890.802 307.379 -0.000423453 + vertex -885.903 316.61 -0.00135611 + vertex -885.731 307.824 -0.00132804 + endloop + endfacet + facet normal -0.000184125 -6.80088e-06 -1 + outer loop + vertex -885.903 316.61 -0.00135611 + vertex -881.049 316.726 -0.00225067 + vertex -885.731 307.824 -0.00132804 + endloop + endfacet + facet normal -0.000185701 -5.97174e-06 -1 + outer loop + vertex -885.731 307.824 -0.00132804 + vertex -881.049 316.726 -0.00225067 + vertex -880.872 308.045 -0.00223169 + endloop + endfacet + facet normal -0.000281522 -7.92493e-06 -1 + outer loop + vertex -881.049 316.726 -0.00225067 + vertex -876.466 316.696 -0.00354064 + vertex -880.872 308.045 -0.00223169 + endloop + endfacet + facet normal -0.000281429 6.27465e-06 -1 + outer loop + vertex -881.049 316.726 -0.00225067 + vertex -876.276 325.439 -0.00353913 + vertex -876.466 316.696 -0.00354064 + endloop + endfacet + facet normal -8.8317e-05 2.08741e-06 -1 + outer loop + vertex -876.276 325.439 -0.00353913 + vertex -871.965 325.231 -0.0039203 + vertex -876.466 316.696 -0.00354064 + endloop + endfacet + facet normal -8.82364e-05 2.04487e-06 -1 + outer loop + vertex -876.466 316.696 -0.00354064 + vertex -871.965 325.231 -0.0039203 + vertex -872.138 316.568 -0.0039228 + endloop + endfacet + facet normal -8.84725e-05 -5.9303e-06 -1 + outer loop + vertex -876.466 316.696 -0.00354064 + vertex -872.138 316.568 -0.0039228 + vertex -876.277 308.11 -0.00350644 + endloop + endfacet + facet normal 0.000124559 -2.19206e-06 -1 + outer loop + vertex -871.965 325.231 -0.0039203 + vertex -867.853 324.955 -0.0034075 + vertex -872.138 316.568 -0.0039228 + endloop + endfacet + facet normal 0.000125055 -2.44556e-06 -1 + outer loop + vertex -872.138 316.568 -0.0039228 + vertex -867.853 324.955 -0.0034075 + vertex -868.008 316.364 -0.00340581 + endloop + endfacet + facet normal 0.00012523 1.08994e-06 -1 + outer loop + vertex -872.138 316.568 -0.0039228 + vertex -868.008 316.364 -0.00340581 + vertex -871.935 308.065 -0.00390666 + endloop + endfacet + facet normal 0.000221225 -4.17487e-06 -1 + outer loop + vertex -867.853 324.955 -0.0034075 + vertex -863.884 324.622 -0.00252809 + vertex -868.008 316.364 -0.00340581 + endloop + endfacet + facet normal 0.000220394 -3.76013e-06 -1 + outer loop + vertex -868.008 316.364 -0.00340581 + vertex -863.884 324.622 -0.00252809 + vertex -864.019 316.098 -0.00252583 + endloop + endfacet + facet normal 0.000220949 4.55297e-06 -1 + outer loop + vertex -868.008 316.364 -0.00340581 + vertex -864.019 316.098 -0.00252583 + vertex -867.785 307.935 -0.00339498 + endloop + endfacet + facet normal 0.000230835 -3.92572e-06 -1 + outer loop + vertex -863.884 324.622 -0.00252809 + vertex -860.019 324.241 -0.00163428 + vertex -864.019 316.098 -0.00252583 + endloop + endfacet + facet normal 0.000229164 -3.10472e-06 -1 + outer loop + vertex -864.019 316.098 -0.00252583 + vertex -860.019 324.241 -0.00163428 + vertex -860.132 315.78 -0.00163397 + endloop + endfacet + facet normal 0.000229893 5.82033e-06 -1 + outer loop + vertex -864.019 316.098 -0.00252583 + vertex -860.132 315.78 -0.00163397 + vertex -863.772 307.737 -0.00251754 + endloop + endfacet + facet normal 0.000190848 -2.59175e-06 -1 + outer loop + vertex -860.019 324.241 -0.00163428 + vertex -856.228 323.824 -0.000909781 + vertex -860.132 315.78 -0.00163397 + endloop + endfacet + facet normal 0.000190564 -2.45388e-06 -1 + outer loop + vertex -860.132 315.78 -0.00163397 + vertex -856.228 323.824 -0.000909781 + vertex -856.323 315.422 -0.000907308 + endloop + endfacet + facet normal 0.000191323 5.62092e-06 -1 + outer loop + vertex -860.132 315.78 -0.00163397 + vertex -856.323 315.422 -0.000907308 + vertex -859.858 307.483 -0.0016282 + endloop + endfacet + facet normal 0.000129769 -1.7649e-06 -1 + outer loop + vertex -856.228 323.824 -0.000909781 + vertex -852.506 323.378 -0.000425987 + vertex -856.323 315.422 -0.000907308 + endloop + endfacet + facet normal 0.000128957 -1.37525e-06 -1 + outer loop + vertex -856.323 315.422 -0.000907308 + vertex -852.506 323.378 -0.000425987 + vertex -852.579 315.033 -0.000423916 + endloop + endfacet + facet normal 0.000129561 4.42793e-06 -1 + outer loop + vertex -856.323 315.422 -0.000907308 + vertex -852.579 315.033 -0.000423916 + vertex -856.018 307.185 -0.000904261 + endloop + endfacet + facet normal 7.06269e-05 -8.6545e-07 -1 + outer loop + vertex -852.506 323.378 -0.000425987 + vertex -848.841 322.907 -0.000166764 + vertex -852.579 315.033 -0.000423916 + endloop + endfacet + facet normal 7.00867e-05 -6.09086e-07 -1 + outer loop + vertex -852.579 315.033 -0.000423916 + vertex -848.841 322.907 -0.000166764 + vertex -848.893 314.617 -0.000165338 + endloop + endfacet + facet normal 7.04877e-05 2.94198e-06 -1 + outer loop + vertex -852.579 315.033 -0.000423916 + vertex -848.893 314.617 -0.000165338 + vertex -852.239 306.853 -0.000424 + endloop + endfacet + facet normal 3.14797e-05 -3.68351e-07 -1 + outer loop + vertex -848.841 322.907 -0.000166764 + vertex -845.24 322.412 -5.32229e-05 + vertex -848.893 314.617 -0.000165338 + endloop + endfacet + facet normal 3.06517e-05 1.96047e-08 -1 + outer loop + vertex -848.893 314.617 -0.000165338 + vertex -845.24 322.412 -5.32229e-05 + vertex -845.267 314.177 -5.41982e-05 + endloop + endfacet + facet normal 3.08268e-05 1.46487e-06 -1 + outer loop + vertex -848.893 314.617 -0.000165338 + vertex -845.267 314.177 -5.41982e-05 + vertex -848.52 306.493 -0.000165746 + endloop + endfacet + facet normal 1.09645e-05 8.30798e-08 -1 + outer loop + vertex -845.24 322.412 -5.32229e-05 + vertex -841.716 321.914 -1.46249e-05 + vertex -845.267 314.177 -5.41982e-05 + endloop + endfacet + facet normal 1.12612e-05 -5.30872e-08 -1 + outer loop + vertex -845.267 314.177 -5.41982e-05 + vertex -841.716 321.914 -1.46249e-05 + vertex -841.733 313.731 -1.43726e-05 + endloop + endfacet + facet normal 1.13262e-05 4.6224e-07 -1 + outer loop + vertex -845.267 314.177 -5.41982e-05 + vertex -841.733 313.731 -1.43726e-05 + vertex -844.87 306.106 -5.34282e-05 + endloop + endfacet + facet normal 3.47582e-06 -3.76992e-08 -1 + outer loop + vertex -841.716 321.914 -1.46249e-05 + vertex -838.453 321.526 -3.26742e-06 + vertex -841.733 313.731 -1.43726e-05 + endloop + endfacet + facet normal 3.39609e-06 -4.15366e-09 -1 + outer loop + vertex -841.733 313.731 -1.43726e-05 + vertex -838.453 321.526 -3.26742e-06 + vertex -838.445 313.366 -3.20658e-06 + endloop + endfacet + facet normal 3.41809e-06 1.93965e-07 -1 + outer loop + vertex -841.733 313.731 -1.43726e-05 + vertex -838.445 313.366 -3.20658e-06 + vertex -841.3 305.707 -1.4452e-05 + endloop + endfacet + facet normal 1.28909e-06 -6.2025e-09 -1 + outer loop + vertex -838.453 321.526 -3.26742e-06 + vertex -835.919 321.324 -1.27488e-13 + vertex -838.445 313.366 -3.20658e-06 + endloop + endfacet + facet normal 1.25802e-06 3.66136e-09 -1 + outer loop + vertex -838.445 313.366 -3.20658e-06 + vertex -835.919 321.324 -1.27488e-13 + vertex -835.896 313.271 -1.16476e-13 + endloop + endfacet + facet normal 1.26084e-06 7.90642e-08 -1 + outer loop + vertex -838.445 313.366 -3.20658e-06 + vertex -835.896 313.271 -1.16476e-13 + vertex -837.976 305.364 -3.24787e-06 + endloop + endfacet + facet normal 1.28472e-06 -6.09285e-08 -1 + outer loop + vertex -838.453 321.526 -3.26742e-06 + vertex -835.517 329.802 -1.39716e-13 + vertex -835.919 321.324 -1.27488e-13 + endloop + endfacet + facet normal 1.2783e-06 -5.865e-08 -1 + outer loop + vertex -838.057 329.773 -3.24493e-06 + vertex -835.517 329.802 -1.39716e-13 + vertex -838.453 321.526 -3.26742e-06 + endloop + endfacet + facet normal 1.27892e-06 -1.13643e-07 -1 + outer loop + vertex -838.057 329.773 -3.24493e-06 + vertex -834.806 337.802 -1.51602e-13 + vertex -835.517 329.802 -1.39716e-13 + endloop + endfacet + facet normal 1.2753e-06 -1.12173e-07 -1 + outer loop + vertex -837.328 338.089 -3.24869e-06 + vertex -834.806 337.802 -1.51602e-13 + vertex -838.057 329.773 -3.24493e-06 + endloop + endfacet + facet normal 3.47152e-06 -3.04572e-07 -1 + outer loop + vertex -841.317 330.22 -1.4697e-05 + vertex -837.328 338.089 -3.24869e-06 + vertex -838.057 329.773 -3.24493e-06 + endloop + endfacet + facet normal 3.48905e-06 -1.76574e-07 -1 + outer loop + vertex -841.317 330.22 -1.4697e-05 + vertex -838.057 329.773 -3.24493e-06 + vertex -841.716 321.914 -1.46249e-05 + endloop + endfacet + facet normal 3.36406e-06 -2.50114e-07 -1 + outer loop + vertex -840.592 338.599 -1.43561e-05 + vertex -837.328 338.089 -3.24869e-06 + vertex -841.317 330.22 -1.4697e-05 + endloop + endfacet + facet normal 1.10314e-05 -9.12911e-07 -1 + outer loop + vertex -844.835 330.771 -5.40118e-05 + vertex -840.592 338.599 -1.43561e-05 + vertex -841.317 330.22 -1.4697e-05 + endloop + endfacet + facet normal 1.10755e-05 -6.31569e-07 -1 + outer loop + vertex -844.835 330.771 -5.40118e-05 + vertex -841.317 330.22 -1.4697e-05 + vertex -845.24 322.412 -5.32229e-05 + endloop + endfacet + facet normal 1.11977e-05 -1.00306e-06 -1 + outer loop + vertex -844.112 339.199 -5.437e-05 + vertex -840.592 338.599 -1.43561e-05 + vertex -844.835 330.771 -5.40118e-05 + endloop + endfacet + facet normal 3.0615e-05 -2.6687e-06 -1 + outer loop + vertex -848.432 331.317 -0.000165594 + vertex -844.112 339.199 -5.437e-05 + vertex -844.835 330.771 -5.40118e-05 + endloop + endfacet + facet normal 3.08135e-05 -1.36075e-06 -1 + outer loop + vertex -848.432 331.317 -0.000165594 + vertex -844.835 330.771 -5.40118e-05 + vertex -848.841 322.907 -0.000166764 + endloop + endfacet + facet normal 3.07401e-05 -2.73728e-06 -1 + outer loop + vertex -847.708 339.795 -0.00016653 + vertex -844.112 339.199 -5.437e-05 + vertex -848.432 331.317 -0.000165594 + endloop + endfacet + facet normal 6.97736e-05 -6.07277e-06 -1 + outer loop + vertex -852.084 331.842 -0.000423583 + vertex -847.708 339.795 -0.00016653 + vertex -848.432 331.317 -0.000165594 + endloop + endfacet + facet normal 7.01841e-05 -3.21576e-06 -1 + outer loop + vertex -852.084 331.842 -0.000423583 + vertex -848.432 331.317 -0.000165594 + vertex -852.506 323.378 -0.000425987 + endloop + endfacet + facet normal 7.03007e-05 -6.36284e-06 -1 + outer loop + vertex -851.354 340.375 -0.00042653 + vertex -847.708 339.795 -0.00016653 + vertex -852.084 331.842 -0.000423583 + endloop + endfacet + facet normal 0.000128944 -1.13825e-05 -1 + outer loop + vertex -855.792 332.345 -0.000907447 + vertex -851.354 340.375 -0.00042653 + vertex -852.084 331.842 -0.000423583 + endloop + endfacet + facet normal 0.000129626 -6.35898e-06 -1 + outer loop + vertex -855.792 332.345 -0.000907447 + vertex -852.084 331.842 -0.000423583 + vertex -856.228 323.824 -0.000909781 + endloop + endfacet + facet normal 0.00012862 -1.12036e-05 -1 + outer loop + vertex -855.058 340.936 -0.000909231 + vertex -851.354 340.375 -0.00042653 + vertex -855.792 332.345 -0.000907447 + endloop + endfacet + facet normal 0.000190934 -1.65309e-05 -1 + outer loop + vertex -859.565 332.822 -0.00163575 + vertex -855.058 340.936 -0.000909231 + vertex -855.792 332.345 -0.000907447 + endloop + endfacet + facet normal 0.000191721 -1.03024e-05 -1 + outer loop + vertex -859.565 332.822 -0.00163575 + vertex -855.792 332.345 -0.000907447 + vertex -860.019 324.241 -0.00163428 + endloop + endfacet + facet normal 0.000190132 -1.60852e-05 -1 + outer loop + vertex -858.828 341.471 -0.00163463 + vertex -855.058 340.936 -0.000909231 + vertex -859.565 332.822 -0.00163575 + endloop + endfacet + facet normal 0.000229495 -1.94422e-05 -1 + outer loop + vertex -863.419 333.264 -0.00252874 + vertex -858.828 341.471 -0.00163463 + vertex -859.565 332.822 -0.00163575 + endloop + endfacet + facet normal 0.000230294 -1.24763e-05 -1 + outer loop + vertex -863.419 333.264 -0.00252874 + vertex -859.565 332.822 -0.00163575 + vertex -863.884 324.622 -0.00252809 + endloop + endfacet + facet normal 0.000229942 -1.96919e-05 -1 + outer loop + vertex -862.674 341.974 -0.0025289 + vertex -858.828 341.471 -0.00163463 + vertex -863.419 333.264 -0.00252874 + endloop + endfacet + facet normal 0.00022102 -1.89286e-05 -1 + outer loop + vertex -867.375 333.663 -0.00341074 + vertex -862.674 341.974 -0.0025289 + vertex -863.419 333.264 -0.00252874 + endloop + endfacet + facet normal 0.000221664 -1.2535e-05 -1 + outer loop + vertex -867.375 333.663 -0.00341074 + vertex -863.419 333.264 -0.00252874 + vertex -867.853 324.955 -0.0034075 + endloop + endfacet + facet normal 0.000221118 -1.89841e-05 -1 + outer loop + vertex -866.619 342.436 -0.00340999 + vertex -862.674 341.974 -0.0025289 + vertex -867.375 333.663 -0.00341074 + endloop + endfacet + facet normal 0.000125425 -1.07312e-05 -1 + outer loop + vertex -871.471 334.009 -0.00392818 + vertex -866.619 342.436 -0.00340999 + vertex -867.375 333.663 -0.00341074 + endloop + endfacet + facet normal 0.000125658 -7.96908e-06 -1 + outer loop + vertex -871.471 334.009 -0.00392818 + vertex -867.375 333.663 -0.00341074 + vertex -871.965 325.231 -0.0039203 + endloop + endfacet + facet normal 0.00012504 -1.05097e-05 -1 + outer loop + vertex -870.702 342.851 -0.0039249 + vertex -866.619 342.436 -0.00340999 + vertex -871.471 334.009 -0.00392818 + endloop + endfacet + facet normal -8.79428e-05 8.02407e-06 -1 + outer loop + vertex -875.764 334.295 -0.00354836 + vertex -870.702 342.851 -0.0039249 + vertex -871.471 334.009 -0.00392818 + endloop + endfacet + facet normal -8.8207e-05 4.05868e-06 -1 + outer loop + vertex -875.764 334.295 -0.00354836 + vertex -871.471 334.009 -0.00392818 + vertex -876.276 325.439 -0.00353913 + endloop + endfacet + facet normal -0.000279808 1.51397e-05 -1 + outer loop + vertex -880.843 325.56 -0.0022595 + vertex -875.764 334.295 -0.00354836 + vertex -876.276 325.439 -0.00353913 + endloop + endfacet + facet normal -0.000282447 1.66742e-05 -1 + outer loop + vertex -880.31 334.503 -0.00226085 + vertex -875.764 334.295 -0.00354836 + vertex -880.843 325.56 -0.0022595 + endloop + endfacet + facet normal -0.000185154 1.08786e-05 -1 + outer loop + vertex -885.685 325.547 -0.00136309 + vertex -880.31 334.503 -0.00226085 + vertex -880.843 325.56 -0.0022595 + endloop + endfacet + facet normal -0.000185135 3.73077e-06 -1 + outer loop + vertex -885.685 325.547 -0.00136309 + vertex -880.843 325.56 -0.0022595 + vertex -885.903 316.61 -0.00135611 + endloop + endfacet + facet normal -0.000184665 3.71932e-06 -1 + outer loop + vertex -890.984 316.284 -0.000419039 + vertex -885.685 325.547 -0.00136309 + vertex -885.903 316.61 -0.00135611 + endloop + endfacet + facet normal -0.000165618 -7.17657e-06 -1 + outer loop + vertex -890.759 325.334 -0.000521252 + vertex -885.685 325.547 -0.00136309 + vertex -890.984 316.284 -0.000419039 + endloop + endfacet + facet normal -0.00223633 4.42962e-05 -0.999997 + outer loop + vertex -896.219 315.716 0.011263 + vertex -890.759 325.334 -0.000521252 + vertex -890.984 316.284 -0.000419039 + endloop + endfacet + facet normal -0.00221796 -0.000125242 -0.999998 + outer loop + vertex -896.219 315.716 0.011263 + vertex -890.984 316.284 -0.000419039 + vertex -896.011 306.68 0.0119328 + endloop + endfacet + facet normal -0.0101288 -0.000307562 -0.999949 + outer loop + vertex -901.335 305.8 0.0661369 + vertex -896.219 315.716 0.011263 + vertex -896.011 306.68 0.0119328 + endloop + endfacet + facet normal -0.0103119 -0.000213076 -0.999947 + outer loop + vertex -901.568 314.972 0.0665892 + vertex -896.219 315.716 0.011263 + vertex -901.335 305.8 0.0661369 + endloop + endfacet + facet normal -0.026374 -0.000621791 -0.999652 + outer loop + vertex -906.848 304.917 0.21213 + vertex -901.568 314.972 0.0665892 + vertex -901.335 305.8 0.0661369 + endloop + endfacet + facet normal -0.0261099 -0.00227139 -0.999656 + outer loop + vertex -906.848 304.917 0.21213 + vertex -901.335 305.8 0.0661369 + vertex -906.034 295.731 0.211738 + endloop + endfacet + facet normal -0.0487829 -0.00428087 -0.9988 + outer loop + vertex -911.818 294.862 0.497967 + vertex -906.848 304.917 0.21213 + vertex -906.034 295.731 0.211738 + endloop + endfacet + facet normal -0.0480954 -0.00462161 -0.998832 + outer loop + vertex -912.691 304.219 0.496725 + vertex -906.848 304.917 0.21213 + vertex -911.818 294.862 0.497967 + endloop + endfacet + facet normal -0.0736627 -0.00700772 -0.997259 + outer loop + vertex -918.039 294.246 0.96181 + vertex -912.691 304.219 0.496725 + vertex -911.818 294.862 0.497967 + endloop + endfacet + facet normal -0.0731328 -0.0123451 -0.997246 + outer loop + vertex -918.039 294.246 0.96181 + vertex -911.818 294.862 0.497967 + vertex -916.456 284.785 0.962889 + endloop + endfacet + facet normal -0.0742332 -0.0118352 -0.997171 + outer loop + vertex -916.456 284.785 0.962889 + vertex -911.818 294.862 0.497967 + vertex -910.328 285.615 0.496784 + endloop + endfacet + facet normal -0.0739561 -0.0068494 -0.997238 + outer loop + vertex -918.935 303.754 0.962977 + vertex -912.691 304.219 0.496725 + vertex -918.039 294.246 0.96181 + endloop + endfacet + facet normal -0.0743154 -0.00202098 -0.997233 + outer loop + vertex -918.935 303.754 0.962977 + vertex -912.972 313.715 0.498445 + vertex -912.691 304.219 0.496725 + endloop + endfacet + facet normal -0.0490004 -0.00127074 -0.998798 + outer loop + vertex -912.972 313.715 0.498445 + vertex -907.118 314.241 0.210546 + vertex -912.691 304.219 0.496725 + endloop + endfacet + facet normal -0.049231 0.001302 -0.998787 + outer loop + vertex -912.972 313.715 0.498445 + vertex -906.892 323.697 0.211732 + vertex -907.118 314.241 0.210546 + endloop + endfacet + facet normal -0.0262038 0.000751734 -0.999656 + outer loop + vertex -906.892 323.697 0.211732 + vertex -901.346 324.278 0.0667943 + vertex -907.118 314.241 0.210546 + endloop + endfacet + facet normal -0.0260178 0.000644734 -0.999661 + outer loop + vertex -907.118 314.241 0.210546 + vertex -901.346 324.278 0.0667943 + vertex -901.568 314.972 0.0665892 + endloop + endfacet + facet normal -0.0104299 0.000271667 -0.999946 + outer loop + vertex -901.346 324.278 0.0667943 + vertex -895.991 324.888 0.0111069 + vertex -901.568 314.972 0.0665892 + endloop + endfacet + facet normal -0.0104853 0.000757523 -0.999945 + outer loop + vertex -901.346 324.278 0.0667943 + vertex -895.389 334.151 0.0118092 + vertex -895.991 324.888 0.0111069 + endloop + endfacet + facet normal -0.00238009 0.000230564 -0.999997 + outer loop + vertex -895.389 334.151 0.0118092 + vertex -890.18 334.483 -0.000511741 + vertex -895.991 324.888 0.0111069 + endloop + endfacet + facet normal -0.00223462 0.000142461 -0.999997 + outer loop + vertex -895.991 324.888 0.0111069 + vertex -890.18 334.483 -0.000511741 + vertex -890.759 325.334 -0.000521252 + endloop + endfacet + facet normal -0.000169286 1.1753e-05 -1 + outer loop + vertex -890.18 334.483 -0.000511741 + vertex -885.129 334.588 -0.00136552 + vertex -890.759 325.334 -0.000521252 + endloop + endfacet + facet normal -0.000169373 1.59292e-05 -1 + outer loop + vertex -890.18 334.483 -0.000511741 + vertex -884.287 343.678 -0.00136344 + vertex -885.129 334.588 -0.00136552 + endloop + endfacet + facet normal -0.000185947 1.74657e-05 -1 + outer loop + vertex -884.287 343.678 -0.00136344 + vertex -879.499 343.502 -0.00225676 + vertex -885.129 334.588 -0.00136552 + endloop + endfacet + facet normal -0.000185486 1.71744e-05 -1 + outer loop + vertex -885.129 334.588 -0.00136552 + vertex -879.499 343.502 -0.00225676 + vertex -880.31 334.503 -0.00226085 + endloop + endfacet + facet normal -0.00028249 2.59189e-05 -1 + outer loop + vertex -879.499 343.502 -0.00225676 + vertex -874.977 343.212 -0.00354176 + vertex -880.31 334.503 -0.00226085 + endloop + endfacet + facet normal -0.000282071 3.24646e-05 -1 + outer loop + vertex -879.499 343.502 -0.00225676 + vertex -873.955 352.157 -0.00353957 + vertex -874.977 343.212 -0.00354176 + endloop + endfacet + facet normal -8.84133e-05 1.03444e-05 -1 + outer loop + vertex -873.955 352.157 -0.00353957 + vertex -869.698 351.725 -0.00392044 + vertex -874.977 343.212 -0.00354176 + endloop + endfacet + facet normal -8.87334e-05 1.05429e-05 -1 + outer loop + vertex -874.977 343.212 -0.00354176 + vertex -869.698 351.725 -0.00392044 + vertex -870.702 342.851 -0.0039249 + endloop + endfacet + facet normal 0.000123905 -1.35181e-05 -1 + outer loop + vertex -869.698 351.725 -0.00392044 + vertex -865.625 351.244 -0.00340935 + vertex -870.702 342.851 -0.0039249 + endloop + endfacet + facet normal 0.00012352 -1.67787e-05 -1 + outer loop + vertex -869.698 351.725 -0.00392044 + vertex -864.427 360.076 -0.00340959 + vertex -865.625 351.244 -0.00340935 + endloop + endfacet + facet normal 0.000219187 -2.97531e-05 -1 + outer loop + vertex -864.427 360.076 -0.00340959 + vertex -860.49 359.49 -0.0025292 + vertex -865.625 351.244 -0.00340935 + endloop + endfacet + facet normal 0.000219489 -2.9941e-05 -1 + outer loop + vertex -865.625 351.244 -0.00340935 + vertex -860.49 359.49 -0.0025292 + vertex -861.685 350.719 -0.00252889 + endloop + endfacet + facet normal 0.000220179 -2.47608e-05 -1 + outer loop + vertex -865.625 351.244 -0.00340935 + vertex -861.685 350.719 -0.00252889 + vertex -866.619 342.436 -0.00340999 + endloop + endfacet + facet normal 0.000227408 -3.102e-05 -1 + outer loop + vertex -860.49 359.49 -0.0025292 + vertex -856.645 358.869 -0.00163543 + vertex -861.685 350.719 -0.00252889 + endloop + endfacet + facet normal 0.000227908 -3.13294e-05 -1 + outer loop + vertex -861.685 350.719 -0.00252889 + vertex -856.645 358.869 -0.00163543 + vertex -857.842 350.156 -0.00163527 + endloop + endfacet + facet normal 0.000228711 -2.58431e-05 -1 + outer loop + vertex -861.685 350.719 -0.00252889 + vertex -857.842 350.156 -0.00163527 + vertex -862.674 341.974 -0.0025289 + endloop + endfacet + facet normal 0.000187768 -2.58148e-05 -1 + outer loop + vertex -856.645 358.869 -0.00163543 + vertex -852.87 358.219 -0.000909881 + vertex -857.842 350.156 -0.00163527 + endloop + endfacet + facet normal 0.000189003 -2.65768e-05 -1 + outer loop + vertex -857.842 350.156 -0.00163527 + vertex -852.87 358.219 -0.000909881 + vertex -854.074 349.564 -0.000907337 + endloop + endfacet + facet normal 0.000189784 -2.16136e-05 -1 + outer loop + vertex -857.842 350.156 -0.00163527 + vertex -854.074 349.564 -0.000907337 + vertex -858.828 341.471 -0.00163463 + endloop + endfacet + facet normal 0.000127812 -1.80674e-05 -1 + outer loop + vertex -852.87 358.219 -0.000909881 + vertex -849.159 357.549 -0.000423458 + vertex -854.074 349.564 -0.000907337 + endloop + endfacet + facet normal 0.000127193 -1.7687e-05 -1 + outer loop + vertex -854.074 349.564 -0.000907337 + vertex -849.159 357.549 -0.000423458 + vertex -850.368 348.947 -0.000425127 + endloop + endfacet + facet normal 0.000127749 -1.43481e-05 -1 + outer loop + vertex -854.074 349.564 -0.000907337 + vertex -850.368 348.947 -0.000425127 + vertex -855.058 340.936 -0.000909231 + endloop + endfacet + facet normal 6.85697e-05 -9.44561e-06 -1 + outer loop + vertex -849.159 357.549 -0.000423458 + vertex -845.498 356.86 -0.000165924 + vertex -850.368 348.947 -0.000425127 + endloop + endfacet + facet normal 6.96093e-05 -1.00855e-05 -1 + outer loop + vertex -850.368 348.947 -0.000425127 + vertex -845.498 356.86 -0.000165924 + vertex -846.72 348.313 -0.000164761 + endloop + endfacet + facet normal 6.99928e-05 -7.88078e-06 -1 + outer loop + vertex -850.368 348.947 -0.000425127 + vertex -846.72 348.313 -0.000164761 + vertex -851.354 340.375 -0.00042653 + endloop + endfacet + facet normal 3.01162e-05 -4.4406e-06 -1 + outer loop + vertex -845.498 356.86 -0.000165924 + vertex -841.883 356.158 -5.3947e-05 + vertex -846.72 348.313 -0.000164761 + endloop + endfacet + facet normal 3.00297e-05 -4.38733e-06 -1 + outer loop + vertex -846.72 348.313 -0.000164761 + vertex -841.883 356.158 -5.3947e-05 + vertex -843.118 347.664 -5.37466e-05 + endloop + endfacet + facet normal 3.0226e-05 -3.29759e-06 -1 + outer loop + vertex -846.72 348.313 -0.000164761 + vertex -843.118 347.664 -5.37466e-05 + vertex -847.708 339.795 -0.00016653 + endloop + endfacet + facet normal 1.07315e-05 -1.58303e-06 -1 + outer loop + vertex -841.883 356.158 -5.3947e-05 + vertex -838.336 355.463 -1.47805e-05 + vertex -843.118 347.664 -5.37466e-05 + endloop + endfacet + facet normal 1.07666e-05 -1.60451e-06 -1 + outer loop + vertex -843.118 347.664 -5.37466e-05 + vertex -838.336 355.463 -1.47805e-05 + vertex -839.587 347.018 -1.46927e-05 + endloop + endfacet + facet normal 1.08406e-05 -1.19964e-06 -1 + outer loop + vertex -843.118 347.664 -5.37466e-05 + vertex -839.587 347.018 -1.46927e-05 + vertex -844.112 339.199 -5.437e-05 + endloop + endfacet + facet normal 3.45992e-06 -5.22676e-07 -1 + outer loop + vertex -838.336 355.463 -1.47805e-05 + vertex -835.042 354.853 -3.06385e-06 + vertex -839.587 347.018 -1.46927e-05 + endloop + endfacet + facet normal 3.40849e-06 -4.92846e-07 -1 + outer loop + vertex -839.587 347.018 -1.46927e-05 + vertex -835.042 354.853 -3.06385e-06 + vertex -836.312 346.465 -3.25937e-06 + endloop + endfacet + facet normal 3.41605e-06 -4.48042e-07 -1 + outer loop + vertex -839.587 347.018 -1.46927e-05 + vertex -836.312 346.465 -3.25937e-06 + vertex -840.592 338.599 -1.43561e-05 + endloop + endfacet + facet normal 1.18071e-06 -1.55487e-07 -1 + outer loop + vertex -835.042 354.853 -3.06385e-06 + vertex -832.492 354.512 -1.7667e-13 + vertex -836.312 346.465 -3.25937e-06 + endloop + endfacet + facet normal 1.26184e-06 -1.94003e-07 -1 + outer loop + vertex -836.312 346.465 -3.25937e-06 + vertex -832.492 354.512 -1.7667e-13 + vertex -833.761 346.261 -1.64318e-13 + endloop + endfacet + facet normal 1.26498e-06 -1.54751e-07 -1 + outer loop + vertex -836.312 346.465 -3.25937e-06 + vertex -833.761 346.261 -1.64318e-13 + vertex -837.328 338.089 -3.24869e-06 + endloop + endfacet + facet normal 1.17334e-06 -2.10719e-07 -1 + outer loop + vertex -835.042 354.853 -3.06385e-06 + vertex -830.988 362.889 -1.88961e-13 + vertex -832.492 354.512 -1.7667e-13 + endloop + endfacet + facet normal 1.24281e-06 -2.45766e-07 -1 + outer loop + vertex -833.557 363.3 -3.29376e-06 + vertex -830.988 362.889 -1.88961e-13 + vertex -835.042 354.853 -3.06385e-06 + endloop + endfacet + facet normal 1.24189e-06 -2.51469e-07 -1 + outer loop + vertex -833.557 363.3 -3.29376e-06 + vertex -829.242 371.51 -2.01137e-13 + vertex -830.988 362.889 -1.88961e-13 + endloop + endfacet + facet normal 1.21894e-06 -2.39408e-07 -1 + outer loop + vertex -831.881 371.728 -3.26843e-06 + vertex -829.242 371.51 -2.01137e-13 + vertex -833.557 363.3 -3.29376e-06 + endloop + endfacet + facet normal 3.31931e-06 -6.57114e-07 -1 + outer loop + vertex -836.872 363.933 -1.47134e-05 + vertex -831.881 371.728 -3.26843e-06 + vertex -833.557 363.3 -3.29376e-06 + endloop + endfacet + facet normal 3.33615e-06 -5.68965e-07 -1 + outer loop + vertex -836.872 363.933 -1.47134e-05 + vertex -833.557 363.3 -3.29376e-06 + vertex -838.336 355.463 -1.47805e-05 + endloop + endfacet + facet normal 3.26056e-06 -6.19492e-07 -1 + outer loop + vertex -835.225 372.413 -1.45972e-05 + vertex -831.881 371.728 -3.26843e-06 + vertex -836.872 363.933 -1.47134e-05 + endloop + endfacet + facet normal 1.0657e-05 -2.05586e-06 -1 + outer loop + vertex -840.444 364.68 -5.43134e-05 + vertex -835.225 372.413 -1.45972e-05 + vertex -836.872 363.933 -1.47134e-05 + endloop + endfacet + facet normal 1.06998e-05 -1.85102e-06 -1 + outer loop + vertex -840.444 364.68 -5.43134e-05 + vertex -836.872 363.933 -1.47134e-05 + vertex -841.883 356.158 -5.3947e-05 + endloop + endfacet + facet normal 1.04365e-05 -1.90704e-06 -1 + outer loop + vertex -838.828 373.209 -5.37187e-05 + vertex -835.225 372.413 -1.45972e-05 + vertex -840.444 364.68 -5.43134e-05 + endloop + endfacet + facet normal 2.96951e-05 -5.55477e-06 -1 + outer loop + vertex -844.079 365.432 -0.000166443 + vertex -838.828 373.209 -5.37187e-05 + vertex -840.444 364.68 -5.43134e-05 + endloop + endfacet + facet normal 2.98106e-05 -4.99649e-06 -1 + outer loop + vertex -844.079 365.432 -0.000166443 + vertex -840.444 364.68 -5.43134e-05 + vertex -845.498 356.86 -0.000165924 + endloop + endfacet + facet normal 2.918e-05 -5.20698e-06 -1 + outer loop + vertex -842.49 374.009 -0.000164745 + vertex -838.828 373.209 -5.37187e-05 + vertex -844.079 365.432 -0.000166443 + endloop + endfacet + facet normal 6.78887e-05 -1.23769e-05 -1 + outer loop + vertex -847.756 366.172 -0.000425228 + vertex -842.49 374.009 -0.000164745 + vertex -844.079 365.432 -0.000166443 + endloop + endfacet + facet normal 6.81077e-05 -1.12883e-05 -1 + outer loop + vertex -847.756 366.172 -0.000425228 + vertex -844.079 365.432 -0.000166443 + vertex -849.159 357.549 -0.000423458 + endloop + endfacet + facet normal 6.82719e-05 -1.26344e-05 -1 + outer loop + vertex -846.187 374.796 -0.00042711 + vertex -842.49 374.009 -0.000164745 + vertex -847.756 366.172 -0.000425228 + endloop + endfacet + facet normal 0.000124836 -2.29214e-05 -1 + outer loop + vertex -851.483 366.896 -0.000907116 + vertex -846.187 374.796 -0.00042711 + vertex -847.756 366.172 -0.000425228 + endloop + endfacet + facet normal 0.000125455 -1.97359e-05 -1 + outer loop + vertex -851.483 366.896 -0.000907116 + vertex -847.756 366.172 -0.000425228 + vertex -852.87 358.219 -0.000909881 + endloop + endfacet + facet normal 0.000124083 -2.24161e-05 -1 + outer loop + vertex -849.934 375.572 -0.000909367 + vertex -846.187 374.796 -0.00042711 + vertex -851.483 366.896 -0.000907116 + endloop + endfacet + facet normal 0.000186727 -3.36021e-05 -1 + outer loop + vertex -855.266 367.6 -0.0016371 + vertex -849.934 375.572 -0.000909367 + vertex -851.483 366.896 -0.000907116 + endloop + endfacet + facet normal 0.000187435 -2.97968e-05 -1 + outer loop + vertex -855.266 367.6 -0.0016371 + vertex -851.483 366.896 -0.000907116 + vertex -856.645 358.869 -0.00163543 + endloop + endfacet + facet normal 0.000184591 -3.21735e-05 -1 + outer loop + vertex -853.733 376.331 -0.00163514 + vertex -849.934 375.572 -0.000909367 + vertex -855.266 367.6 -0.0016371 + endloop + endfacet + facet normal 0.000225294 -3.93173e-05 -1 + outer loop + vertex -859.119 368.28 -0.00253183 + vertex -853.733 376.331 -0.00163514 + vertex -855.266 367.6 -0.0016371 + endloop + endfacet + facet normal 0.000225956 -3.55649e-05 -1 + outer loop + vertex -859.119 368.28 -0.00253183 + vertex -855.266 367.6 -0.0016371 + vertex -860.49 359.49 -0.0025292 + endloop + endfacet + facet normal 0.00022482 -3.90005e-05 -1 + outer loop + vertex -857.594 377.065 -0.00253169 + vertex -853.733 376.331 -0.00163514 + vertex -859.119 368.28 -0.00253183 + endloop + endfacet + facet normal 0.000217096 -3.76601e-05 -1 + outer loop + vertex -863.055 368.924 -0.00341057 + vertex -857.594 377.065 -0.00253169 + vertex -859.119 368.28 -0.00253183 + endloop + endfacet + facet normal 0.000217712 -3.38938e-05 -1 + outer loop + vertex -863.055 368.924 -0.00341057 + vertex -859.119 368.28 -0.00253183 + vertex -864.427 360.076 -0.00340959 + endloop + endfacet + facet normal 0.000124202 -1.93836e-05 -1 + outer loop + vertex -868.491 360.622 -0.00392486 + vertex -863.055 368.924 -0.00341057 + vertex -864.427 360.076 -0.00340959 + endloop + endfacet + facet normal 0.000125337 -2.01269e-05 -1 + outer loop + vertex -867.11 369.534 -0.00393116 + vertex -863.055 368.924 -0.00341057 + vertex -868.491 360.622 -0.00392486 + endloop + endfacet + facet normal -8.79239e-05 1.29173e-05 -1 + outer loop + vertex -872.73 361.125 -0.00354568 + vertex -867.11 369.534 -0.00393116 + vertex -868.491 360.622 -0.00392486 + endloop + endfacet + facet normal -8.8109e-05 1.13576e-05 -1 + outer loop + vertex -872.73 361.125 -0.00354568 + vertex -868.491 360.622 -0.00392486 + vertex -873.955 352.157 -0.00353957 + endloop + endfacet + facet normal -0.000281918 3.78396e-05 -1 + outer loop + vertex -878.45 352.527 -0.00225846 + vertex -872.73 361.125 -0.00354568 + vertex -873.955 352.157 -0.00353957 + endloop + endfacet + facet normal -0.000288507 4.22227e-05 -1 + outer loop + vertex -877.194 361.571 -0.00223884 + vertex -872.73 361.125 -0.00354568 + vertex -878.45 352.527 -0.00225846 + endloop + endfacet + facet normal -0.0001947 2.91994e-05 -1 + outer loop + vertex -883.199 352.792 -0.00132609 + vertex -877.194 361.571 -0.00223884 + vertex -878.45 352.527 -0.00225846 + endloop + endfacet + facet normal -0.000194803 2.73529e-05 -1 + outer loop + vertex -883.199 352.792 -0.00132609 + vertex -878.45 352.527 -0.00225846 + vertex -884.287 343.678 -0.00136344 + endloop + endfacet + facet normal -0.000196175 2.75167e-05 -1 + outer loop + vertex -889.3 343.674 -0.00038006 + vertex -883.199 352.792 -0.00132609 + vertex -884.287 343.678 -0.00136344 + endloop + endfacet + facet normal -0.000214141 3.95395e-05 -1 + outer loop + vertex -888.164 352.88 -0.000259262 + vertex -883.199 352.792 -0.00132609 + vertex -889.3 343.674 -0.00038006 + endloop + endfacet + facet normal -0.00242808 0.000312667 -0.999997 + outer loop + vertex -894.47 343.45 0.0121021 + vertex -888.164 352.88 -0.000259262 + vertex -889.3 343.674 -0.00038006 + endloop + endfacet + facet normal -0.00242628 0.000271338 -0.999997 + outer loop + vertex -894.47 343.45 0.0121021 + vertex -889.3 343.674 -0.00038006 + vertex -895.389 334.151 0.0118092 + endloop + endfacet + facet normal -0.0102908 0.00104876 -0.999946 + outer loop + vertex -900.725 333.668 0.0662244 + vertex -894.47 343.45 0.0121021 + vertex -895.389 334.151 0.0118092 + endloop + endfacet + facet normal -0.0104553 0.00115398 -0.999945 + outer loop + vertex -899.76 343.082 0.0669975 + vertex -894.47 343.45 0.0121021 + vertex -900.725 333.668 0.0662244 + endloop + endfacet + facet normal -0.0266269 0.00281184 -0.999641 + outer loop + vertex -906.237 333.226 0.211788 + vertex -899.76 343.082 0.0669975 + vertex -900.725 333.668 0.0662244 + endloop + endfacet + facet normal -0.0265485 0.00183019 -0.999646 + outer loop + vertex -906.237 333.226 0.211788 + vertex -900.725 333.668 0.0662244 + vertex -906.892 323.697 0.211732 + endloop + endfacet + facet normal -0.0490965 0.00337963 -0.998788 + outer loop + vertex -912.725 323.348 0.497315 + vertex -906.237 333.226 0.211788 + vertex -906.892 323.697 0.211732 + endloop + endfacet + facet normal -0.0493823 0.00356775 -0.998774 + outer loop + vertex -912.01 333.04 0.496552 + vertex -906.237 333.226 0.211788 + vertex -912.725 323.348 0.497315 + endloop + endfacet + facet normal -0.0751399 0.00546978 -0.997158 + outer loop + vertex -918.889 323.324 0.961603 + vertex -912.01 333.04 0.496552 + vertex -912.725 323.348 0.497315 + endloop + endfacet + facet normal -0.0751291 0.00238457 -0.997171 + outer loop + vertex -918.889 323.324 0.961603 + vertex -912.725 323.348 0.497315 + vertex -919.201 313.453 0.961553 + endloop + endfacet + facet normal -0.0742197 0.00178611 -0.99724 + outer loop + vertex -919.201 313.453 0.961553 + vertex -912.725 323.348 0.497315 + vertex -912.972 313.715 0.498445 + endloop + endfacet + facet normal -0.0764274 0.00638634 -0.997055 + outer loop + vertex -918.066 333.189 0.961726 + vertex -912.01 333.04 0.496552 + vertex -918.889 323.324 0.961603 + endloop + endfacet + facet normal -0.0763662 0.0088284 -0.997041 + outer loop + vertex -918.066 333.189 0.961726 + vertex -910.892 342.708 0.496512 + vertex -912.01 333.04 0.496552 + endloop + endfacet + facet normal -0.0500656 0.00578644 -0.998729 + outer loop + vertex -910.892 342.708 0.496512 + vertex -905.211 342.765 0.212087 + vertex -912.01 333.04 0.496552 + endloop + endfacet + facet normal -0.0500758 0.00683412 -0.998722 + outer loop + vertex -910.892 342.708 0.496512 + vertex -903.866 352.285 0.209797 + vertex -905.211 342.765 0.212087 + endloop + endfacet + facet normal -0.0268455 0.0035521 -0.999633 + outer loop + vertex -903.866 352.285 0.209797 + vertex -898.502 352.494 0.0664911 + vertex -905.211 342.765 0.212087 + endloop + endfacet + facet normal -0.0268133 0.0035299 -0.999634 + outer loop + vertex -905.211 342.765 0.212087 + vertex -898.502 352.494 0.0664911 + vertex -899.76 343.082 0.0669975 + endloop + endfacet + facet normal -0.0104786 0.0013467 -0.999944 + outer loop + vertex -898.502 352.494 0.0664911 + vertex -893.278 352.758 0.0121019 + vertex -899.76 343.082 0.0669975 + endloop + endfacet + facet normal -0.010491 0.00159227 -0.999944 + outer loop + vertex -898.502 352.494 0.0664911 + vertex -891.852 362.069 0.0119616 + vertex -893.278 352.758 0.0121019 + endloop + endfacet + facet normal -0.00241427 0.000354826 -0.999997 + outer loop + vertex -891.852 362.069 0.0119616 + vertex -886.808 362.098 -0.000205639 + vertex -893.278 352.758 0.0121019 + endloop + endfacet + facet normal -0.00242577 0.000362793 -0.999997 + outer loop + vertex -893.278 352.758 0.0121019 + vertex -886.808 362.098 -0.000205639 + vertex -888.164 352.88 -0.000259262 + endloop + endfacet + facet normal -0.00021455 3.73904e-05 -1 + outer loop + vertex -886.808 362.098 -0.000205639 + vertex -881.899 361.919 -0.00126546 + vertex -888.164 352.88 -0.000259262 + endloop + endfacet + facet normal -0.000214255 4.54758e-05 -1 + outer loop + vertex -886.808 362.098 -0.000205639 + vertex -880.419 371.05 -0.00116725 + vertex -881.899 361.919 -0.00126546 + endloop + endfacet + facet normal -0.000219615 4.63444e-05 -1 + outer loop + vertex -880.419 371.05 -0.00116725 + vertex -875.764 370.622 -0.00220954 + vertex -881.899 361.919 -0.00126546 + endloop + endfacet + facet normal -0.000204248 3.55115e-05 -1 + outer loop + vertex -881.899 361.919 -0.00126546 + vertex -875.764 370.622 -0.00220954 + vertex -877.194 361.571 -0.00223884 + endloop + endfacet + facet normal -0.000291598 4.93143e-05 -1 + outer loop + vertex -875.764 370.622 -0.00220954 + vertex -871.332 370.102 -0.00352756 + vertex -877.194 361.571 -0.00223884 + endloop + endfacet + facet normal -0.000291437 5.06852e-05 -1 + outer loop + vertex -875.764 370.622 -0.00220954 + vertex -869.785 379.073 -0.00352371 + vertex -871.332 370.102 -0.00352756 + endloop + endfacet + facet normal -9.13047e-05 1.61733e-05 -1 + outer loop + vertex -869.785 379.073 -0.00352371 + vertex -865.583 378.437 -0.00391769 + vertex -871.332 370.102 -0.00352756 + endloop + endfacet + facet normal -9.32434e-05 1.75106e-05 -1 + outer loop + vertex -871.332 370.102 -0.00352756 + vertex -865.583 378.437 -0.00391769 + vertex -867.11 369.534 -0.00393116 + endloop + endfacet + facet normal 0.000122484 -1.95014e-05 -1 + outer loop + vertex -865.583 378.437 -0.00391769 + vertex -861.533 377.767 -0.0034086 + vertex -867.11 369.534 -0.00393116 + endloop + endfacet + facet normal 0.000121918 -2.29192e-05 -1 + outer loop + vertex -865.583 378.437 -0.00391769 + vertex -859.886 386.576 -0.00340969 + vertex -861.533 377.767 -0.0034086 + endloop + endfacet + facet normal 0.000215465 -4.04105e-05 -1 + outer loop + vertex -859.886 386.576 -0.00340969 + vertex -855.941 385.817 -0.00252905 + vertex -861.533 377.767 -0.0034086 + endloop + endfacet + facet normal 0.000215427 -4.03843e-05 -1 + outer loop + vertex -861.533 377.767 -0.0034086 + vertex -855.941 385.817 -0.00252905 + vertex -857.594 377.065 -0.00253169 + endloop + endfacet + facet normal 0.000222219 -4.1667e-05 -1 + outer loop + vertex -855.941 385.817 -0.00252905 + vertex -852.067 385.03 -0.00163549 + vertex -857.594 377.065 -0.00253169 + endloop + endfacet + facet normal 0.000221429 -4.55621e-05 -1 + outer loop + vertex -855.941 385.817 -0.00252905 + vertex -850.29 393.679 -0.00163597 + vertex -852.067 385.03 -0.00163549 + endloop + endfacet + facet normal 0.000180967 -3.72464e-05 -1 + outer loop + vertex -850.29 393.679 -0.00163597 + vertex -846.449 392.823 -0.000909069 + vertex -852.067 385.03 -0.00163549 + endloop + endfacet + facet normal 0.000182612 -3.84324e-05 -1 + outer loop + vertex -852.067 385.03 -0.00163549 + vertex -846.449 392.823 -0.000909069 + vertex -848.25 384.222 -0.000907325 + endloop + endfacet + facet normal 0.000183308 -3.51443e-05 -1 + outer loop + vertex -852.067 385.03 -0.00163549 + vertex -848.25 384.222 -0.000907325 + vertex -853.733 376.331 -0.00163514 + endloop + endfacet + facet normal 0.00012205 -2.57539e-05 -1 + outer loop + vertex -846.449 392.823 -0.000909069 + vertex -842.654 391.952 -0.000423371 + vertex -848.25 384.222 -0.000907325 + endloop + endfacet + facet normal 0.000122229 -2.58836e-05 -1 + outer loop + vertex -848.25 384.222 -0.000907325 + vertex -842.654 391.952 -0.000423371 + vertex -844.48 383.397 -0.0004252 + endloop + endfacet + facet normal 0.000122717 -2.36526e-05 -1 + outer loop + vertex -848.25 384.222 -0.000907325 + vertex -844.48 383.397 -0.0004252 + vertex -849.934 375.572 -0.000909367 + endloop + endfacet + facet normal 6.52593e-05 -1.37198e-05 -1 + outer loop + vertex -842.654 391.952 -0.000423371 + vertex -838.895 391.067 -0.00016593 + vertex -844.48 383.397 -0.0004252 + endloop + endfacet + facet normal 6.64693e-05 -1.4601e-05 -1 + outer loop + vertex -844.48 383.397 -0.0004252 + vertex -838.895 391.067 -0.00016593 + vertex -840.753 382.561 -0.000165246 + endloop + endfacet + facet normal 6.68192e-05 -1.30406e-05 -1 + outer loop + vertex -844.48 383.397 -0.0004252 + vertex -840.753 382.561 -0.000165246 + vertex -846.187 374.796 -0.00042711 + endloop + endfacet + facet normal 2.85205e-05 -6.31089e-06 -1 + outer loop + vertex -838.895 391.067 -0.00016593 + vertex -835.168 390.173 -5.39962e-05 + vertex -840.753 382.561 -0.000165246 + endloop + endfacet + facet normal 2.86815e-05 -6.42902e-06 -1 + outer loop + vertex -840.753 382.561 -0.000165246 + vertex -835.168 390.173 -5.39962e-05 + vertex -837.059 381.716 -5.38582e-05 + endloop + endfacet + facet normal 2.88006e-05 -5.9087e-06 -1 + outer loop + vertex -840.753 382.561 -0.000165246 + vertex -837.059 381.716 -5.38582e-05 + vertex -842.49 374.009 -0.000164745 + endloop + endfacet + facet normal 1.01526e-05 -2.28626e-06 -1 + outer loop + vertex -835.168 390.173 -5.39962e-05 + vertex -831.496 389.283 -1.46843e-05 + vertex -837.059 381.716 -5.38582e-05 + endloop + endfacet + facet normal 1.02359e-05 -2.34751e-06 -1 + outer loop + vertex -837.059 381.716 -5.38582e-05 + vertex -831.496 389.283 -1.46843e-05 + vertex -833.422 380.873 -1.46559e-05 + endloop + endfacet + facet normal 1.02806e-05 -2.15445e-06 -1 + outer loop + vertex -837.059 381.716 -5.38582e-05 + vertex -833.422 380.873 -1.46559e-05 + vertex -838.828 373.209 -5.37187e-05 + endloop + endfacet + facet normal 3.17698e-06 -7.30938e-07 -1 + outer loop + vertex -831.496 389.283 -1.46843e-05 + vertex -828.096 388.472 -3.28837e-06 + vertex -833.422 380.873 -1.46559e-05 + endloop + endfacet + facet normal 3.21347e-06 -7.56515e-07 -1 + outer loop + vertex -833.422 380.873 -1.46559e-05 + vertex -828.096 388.472 -3.28837e-06 + vertex -830.046 380.126 -3.24053e-06 + endloop + endfacet + facet normal 3.22716e-06 -6.94584e-07 -1 + outer loop + vertex -833.422 380.873 -1.46559e-05 + vertex -830.046 380.126 -3.24053e-06 + vertex -835.225 372.413 -1.45972e-05 + endloop + endfacet + facet normal 1.18715e-06 -2.83094e-07 -1 + outer loop + vertex -828.096 388.472 -3.28837e-06 + vertex -825.42 388.079 -2.22217e-13 + vertex -830.046 380.126 -3.24053e-06 + endloop + endfacet + facet normal 1.18881e-06 -2.84063e-07 -1 + outer loop + vertex -830.046 380.126 -3.24053e-06 + vertex -825.42 388.079 -2.22217e-13 + vertex -827.439 379.627 -2.11934e-13 + endloop + endfacet + facet normal 1.1939e-06 -2.57526e-07 -1 + outer loop + vertex -830.046 380.126 -3.24053e-06 + vertex -827.439 379.627 -2.11934e-13 + vertex -831.881 371.728 -3.26843e-06 + endloop + endfacet + facet normal 1.18467e-06 -2.99992e-07 -1 + outer loop + vertex -828.096 388.472 -3.28837e-06 + vertex -823.414 396 -2.30646e-13 + vertex -825.42 388.079 -2.22217e-13 + endloop + endfacet + facet normal 1.12571e-06 -2.63323e-07 -1 + outer loop + vertex -826.04 396.779 -3.16116e-06 + vertex -823.414 396 -2.30646e-13 + vertex -828.096 388.472 -3.28837e-06 + endloop + endfacet + facet normal 1.11601e-06 -2.95998e-07 -1 + outer loop + vertex -826.04 396.779 -3.16116e-06 + vertex -821.094 404.747 -2.38096e-13 + vertex -823.414 396 -2.30646e-13 + endloop + endfacet + facet normal 1.11906e-06 -2.97893e-07 -1 + outer loop + vertex -823.95 405.001 -3.27161e-06 + vertex -821.094 404.747 -2.38096e-13 + vertex -826.04 396.779 -3.16116e-06 + endloop + endfacet + facet normal 3.17715e-06 -8.21045e-07 -1 + outer loop + vertex -829.494 397.616 -1.48227e-05 + vertex -823.95 405.001 -3.27161e-06 + vertex -826.04 396.779 -3.16116e-06 + endloop + endfacet + facet normal 3.18653e-06 -7.82347e-07 -1 + outer loop + vertex -829.494 397.616 -1.48227e-05 + vertex -826.04 396.779 -3.16116e-06 + vertex -831.496 389.283 -1.46843e-05 + endloop + endfacet + facet normal 3.06237e-06 -7.34871e-07 -1 + outer loop + vertex -827.45 405.852 -1.46171e-05 + vertex -823.95 405.001 -3.27161e-06 + vertex -829.494 397.616 -1.48227e-05 + endloop + endfacet + facet normal 1.00397e-05 -2.46608e-06 -1 + outer loop + vertex -833.194 398.558 -5.42935e-05 + vertex -827.45 405.852 -1.46171e-05 + vertex -829.494 397.616 -1.48227e-05 + endloop + endfacet + facet normal 1.00557e-05 -2.40285e-06 -1 + outer loop + vertex -833.194 398.558 -5.42935e-05 + vertex -829.494 397.616 -1.48227e-05 + vertex -835.168 390.173 -5.39962e-05 + endloop + endfacet + facet normal 9.88006e-06 -2.3404e-06 -1 + outer loop + vertex -831.179 406.86 -5.38151e-05 + vertex -827.45 405.852 -1.46171e-05 + vertex -833.194 398.558 -5.42935e-05 + endloop + endfacet + facet normal 2.80344e-05 -6.74673e-06 -1 + outer loop + vertex -836.95 399.508 -0.000165992 + vertex -831.179 406.86 -5.38151e-05 + vertex -833.194 398.558 -5.42935e-05 + endloop + endfacet + facet normal 2.81011e-05 -6.48319e-06 -1 + outer loop + vertex -836.95 399.508 -0.000165992 + vertex -833.194 398.558 -5.42935e-05 + vertex -838.895 391.067 -0.00016593 + endloop + endfacet + facet normal 2.79711e-05 -6.69706e-06 -1 + outer loop + vertex -834.955 407.875 -0.000166247 + vertex -831.179 406.86 -5.38151e-05 + vertex -836.95 399.508 -0.000165992 + endloop + endfacet + facet normal 6.46642e-05 -1.54423e-05 -1 + outer loop + vertex -840.736 400.445 -0.000425283 + vertex -834.955 407.875 -0.000166247 + vertex -836.95 399.508 -0.000165992 + endloop + endfacet + facet normal 6.4808e-05 -1.48609e-05 -1 + outer loop + vertex -840.736 400.445 -0.000425283 + vertex -836.95 399.508 -0.000165992 + vertex -842.654 391.952 -0.000423371 + endloop + endfacet + facet normal 6.4347e-05 -1.51956e-05 -1 + outer loop + vertex -838.762 408.873 -0.000426327 + vertex -834.955 407.875 -0.000166247 + vertex -840.736 400.445 -0.000425283 + endloop + endfacet + facet normal 0.000119623 -2.81427e-05 -1 + outer loop + vertex -844.559 401.366 -0.000908529 + vertex -838.762 408.873 -0.000426327 + vertex -840.736 400.445 -0.000425283 + endloop + endfacet + facet normal 0.000120019 -2.6498e-05 -1 + outer loop + vertex -844.559 401.366 -0.000908529 + vertex -840.736 400.445 -0.000425283 + vertex -846.449 392.823 -0.000909069 + endloop + endfacet + facet normal 0.000118695 -2.74259e-05 -1 + outer loop + vertex -842.604 409.851 -0.000909288 + vertex -838.762 408.873 -0.000426327 + vertex -844.559 401.366 -0.000908529 + endloop + endfacet + facet normal 0.000178288 -4.11508e-05 -1 + outer loop + vertex -848.423 402.271 -0.00163467 + vertex -842.604 409.851 -0.000909288 + vertex -844.559 401.366 -0.000908529 + endloop + endfacet + facet normal 0.000178858 -3.87191e-05 -1 + outer loop + vertex -848.423 402.271 -0.00163467 + vertex -844.559 401.366 -0.000908529 + vertex -850.29 393.679 -0.00163597 + endloop + endfacet + facet normal 0.000219269 -4.75014e-05 -1 + outer loop + vertex -854.18 394.516 -0.00252867 + vertex -848.423 402.271 -0.00163467 + vertex -850.29 393.679 -0.00163597 + endloop + endfacet + facet normal 0.000218123 -4.66506e-05 -1 + outer loop + vertex -852.33 403.156 -0.00252827 + vertex -848.423 402.271 -0.00163467 + vertex -854.18 394.516 -0.00252867 + endloop + endfacet + facet normal 0.000212884 -4.55292e-05 -1 + outer loop + vertex -858.133 395.327 -0.00340706 + vertex -852.33 403.156 -0.00252827 + vertex -854.18 394.516 -0.00252867 + endloop + endfacet + facet normal 0.000213512 -4.24744e-05 -1 + outer loop + vertex -858.133 395.327 -0.00340706 + vertex -854.18 394.516 -0.00252867 + vertex -859.886 386.576 -0.00340969 + endloop + endfacet + facet normal 0.000121626 -2.40664e-05 -1 + outer loop + vertex -863.93 387.305 -0.00391911 + vertex -858.133 395.327 -0.00340706 + vertex -859.886 386.576 -0.00340969 + endloop + endfacet + facet normal 0.000118838 -2.20517e-05 -1 + outer loop + vertex -862.174 396.111 -0.00390464 + vertex -858.133 395.327 -0.00340706 + vertex -863.93 387.305 -0.00391911 + endloop + endfacet + facet normal -9.87606e-05 2.13367e-05 -1 + outer loop + vertex -868.115 388.001 -0.00349094 + vertex -862.174 396.111 -0.00390464 + vertex -863.93 387.305 -0.00391911 + endloop + endfacet + facet normal -9.86308e-05 2.21165e-05 -1 + outer loop + vertex -868.115 388.001 -0.00349094 + vertex -863.93 387.305 -0.00391911 + vertex -869.785 379.073 -0.00352371 + endloop + endfacet + facet normal -0.000304236 6.05697e-05 -1 + outer loop + vertex -874.183 379.663 -0.00214994 + vertex -868.115 388.001 -0.00349094 + vertex -869.785 379.073 -0.00352371 + endloop + endfacet + facet normal -0.000317319 7.00899e-05 -1 + outer loop + vertex -872.476 388.662 -0.00206093 + vertex -868.115 388.001 -0.00349094 + vertex -874.183 379.663 -0.00214994 + endloop + endfacet + facet normal -0.000237765 5.49976e-05 -1 + outer loop + vertex -878.786 380.165 -0.00102773 + vertex -872.476 388.662 -0.00206093 + vertex -874.183 379.663 -0.00214994 + endloop + endfacet + facet normal -0.000237454 5.78473e-05 -1 + outer loop + vertex -878.786 380.165 -0.00102773 + vertex -874.183 379.663 -0.00214994 + vertex -880.419 371.05 -0.00116725 + endloop + endfacet + facet normal -0.000239915 5.82883e-05 -1 + outer loop + vertex -885.262 371.314 9.90328e-06 + vertex -878.786 380.165 -0.00102773 + vertex -880.419 371.05 -0.00116725 + endloop + endfacet + facet normal -0.000226619 4.85608e-05 -1 + outer loop + vertex -883.555 380.515 6.98469e-05 + vertex -878.786 380.165 -0.00102773 + vertex -885.262 371.314 9.90328e-06 + endloop + endfacet + facet normal -0.0023866 0.000449317 -0.999997 + outer loop + vertex -890.224 371.377 0.0118798 + vertex -883.555 380.515 6.98469e-05 + vertex -885.262 371.314 9.90328e-06 + endloop + endfacet + facet normal -0.00238712 0.00040876 -0.999997 + outer loop + vertex -890.224 371.377 0.0118798 + vertex -885.262 371.314 9.90328e-06 + vertex -891.852 362.069 0.0119616 + endloop + endfacet + facet normal -0.0104458 0.00181837 -0.999944 + outer loop + vertex -896.991 361.903 0.0653464 + vertex -890.224 371.377 0.0118798 + vertex -891.852 362.069 0.0119616 + endloop + endfacet + facet normal -0.0103681 0.00176288 -0.999945 + outer loop + vertex -895.262 371.305 0.0639983 + vertex -890.224 371.377 0.0118798 + vertex -896.991 361.903 0.0653464 + endloop + endfacet + facet normal -0.0272585 0.00486835 -0.999617 + outer loop + vertex -902.247 361.799 0.20816 + vertex -895.262 371.305 0.0639983 + vertex -896.991 361.903 0.0653464 + endloop + endfacet + facet normal -0.0272506 0.00446671 -0.999619 + outer loop + vertex -902.247 361.799 0.20816 + vertex -896.991 361.903 0.0653464 + vertex -903.866 352.285 0.209797 + endloop + endfacet + facet normal -0.0506933 0.00845739 -0.998678 + outer loop + vertex -909.427 352.34 0.492553 + vertex -902.247 361.799 0.20816 + vertex -903.866 352.285 0.209797 + endloop + endfacet + facet normal -0.051967 0.00942658 -0.998604 + outer loop + vertex -907.665 361.972 0.49175 + vertex -902.247 361.799 0.20816 + vertex -909.427 352.34 0.492553 + endloop + endfacet + facet normal -0.0796058 0.0144846 -0.996721 + outer loop + vertex -915.189 352.726 0.958348 + vertex -907.665 361.972 0.49175 + vertex -909.427 352.34 0.492553 + endloop + endfacet + facet normal -0.0796896 0.0132473 -0.996732 + outer loop + vertex -915.189 352.726 0.958348 + vertex -909.427 352.34 0.492553 + vertex -916.814 342.972 0.958591 + endloop + endfacet + facet normal -0.0772801 0.0113369 -0.996945 + outer loop + vertex -916.814 342.972 0.958591 + vertex -909.427 352.34 0.492553 + vertex -910.892 342.708 0.496512 + endloop + endfacet + facet normal -0.0832021 0.0174285 -0.99638 + outer loop + vertex -913.244 362.502 0.966903 + vertex -907.665 361.972 0.49175 + vertex -915.189 352.726 0.958348 + endloop + endfacet + facet normal -0.0832076 0.0173713 -0.996381 + outer loop + vertex -913.244 362.502 0.966903 + vertex -905.644 371.597 0.490786 + vertex -907.665 361.972 0.49175 + endloop + endfacet + facet normal -0.0538385 0.0112045 -0.998487 + outer loop + vertex -905.644 371.597 0.490786 + vertex -900.39 371.301 0.204182 + vertex -907.665 361.972 0.49175 + endloop + endfacet + facet normal -0.0538185 0.0115574 -0.998484 + outer loop + vertex -905.644 371.597 0.490786 + vertex -898.334 380.771 0.202981 + vertex -900.39 371.301 0.204182 + endloop + endfacet + facet normal -0.0281279 0.00597979 -0.999586 + outer loop + vertex -898.334 380.771 0.202981 + vertex -893.35 380.677 0.0621508 + vertex -900.39 371.301 0.204182 + endloop + endfacet + facet normal -0.0273313 0.00538122 -0.999612 + outer loop + vertex -900.39 371.301 0.204182 + vertex -893.35 380.677 0.0621508 + vertex -895.262 371.305 0.0639983 + endloop + endfacet + facet normal -0.0103159 0.00190834 -0.999945 + outer loop + vertex -893.35 380.677 0.0621508 + vertex -888.425 380.661 0.0113127 + vertex -895.262 371.305 0.0639983 + endloop + endfacet + facet normal -0.0103154 0.00207668 -0.999945 + outer loop + vertex -893.35 380.677 0.0621508 + vertex -886.482 389.889 0.0104362 + vertex -888.425 380.661 0.0113127 + endloop + endfacet + facet normal -0.00214748 0.000357117 -0.999998 + outer loop + vertex -886.482 389.889 0.0104362 + vertex -881.713 389.661 0.000113579 + vertex -888.425 380.661 0.0113127 + endloop + endfacet + facet normal -0.00229466 0.000466873 -0.999997 + outer loop + vertex -888.425 380.661 0.0113127 + vertex -881.713 389.661 0.000113579 + vertex -883.555 380.515 6.98469e-05 + endloop + endfacet + facet normal -0.000203591 4.57803e-05 -1 + outer loop + vertex -881.713 389.661 0.000113579 + vertex -877.022 389.238 -0.000860822 + vertex -883.555 380.515 6.98469e-05 + endloop + endfacet + facet normal -0.000202667 5.60371e-05 -1 + outer loop + vertex -881.713 389.661 0.000113579 + vertex -875.151 398.239 -0.000735543 + vertex -877.022 389.238 -0.000860822 + endloop + endfacet + facet normal -0.000266437 6.92897e-05 -1 + outer loop + vertex -875.151 398.239 -0.000735543 + vertex -870.665 397.592 -0.00197564 + vertex -877.022 389.238 -0.000860822 + endloop + endfacet + facet normal -0.000256176 6.14814e-05 -1 + outer loop + vertex -877.022 389.238 -0.000860822 + vertex -870.665 397.592 -0.00197564 + vertex -872.476 388.662 -0.00206093 + endloop + endfacet + facet normal -0.000331906 7.68327e-05 -1 + outer loop + vertex -870.665 397.592 -0.00197564 + vertex -866.34 396.87 -0.0034667 + vertex -872.476 388.662 -0.00206093 + endloop + endfacet + facet normal -0.000332311 7.4403e-05 -1 + outer loop + vertex -870.665 397.592 -0.00197564 + vertex -864.482 405.667 -0.00342976 + vertex -866.34 396.87 -0.0034667 + endloop + endfacet + facet normal -0.000108758 2.71756e-05 -1 + outer loop + vertex -864.482 405.667 -0.00342976 + vertex -860.332 404.854 -0.00390317 + vertex -866.34 396.87 -0.0034667 + endloop + endfacet + facet normal -0.000101206 2.1492e-05 -1 + outer loop + vertex -866.34 396.87 -0.0034667 + vertex -860.332 404.854 -0.00390317 + vertex -862.174 396.111 -0.00390464 + endloop + endfacet + facet normal 0.000118305 -2.47587e-05 -1 + outer loop + vertex -860.332 404.854 -0.00390317 + vertex -856.293 404.016 -0.00340454 + vertex -862.174 396.111 -0.00390464 + endloop + endfacet + facet normal 0.000117887 -2.67773e-05 -1 + outer loop + vertex -860.332 404.854 -0.00390317 + vertex -854.383 412.654 -0.00341075 + vertex -856.293 404.016 -0.00340454 + endloop + endfacet + facet normal 0.000210956 -4.73497e-05 -1 + outer loop + vertex -854.383 412.654 -0.00341075 + vertex -850.411 411.743 -0.00252962 + vertex -856.293 404.016 -0.00340454 + endloop + endfacet + facet normal 0.000210882 -4.72934e-05 -1 + outer loop + vertex -856.293 404.016 -0.00340454 + vertex -850.411 411.743 -0.00252962 + vertex -852.33 403.156 -0.00252827 + endloop + endfacet + facet normal 0.000216378 -4.8522e-05 -1 + outer loop + vertex -850.411 411.743 -0.00252962 + vertex -846.487 410.81 -0.00163531 + vertex -852.33 403.156 -0.00252827 + endloop + endfacet + facet normal 0.000215926 -5.04257e-05 -1 + outer loop + vertex -850.411 411.743 -0.00252962 + vertex -844.508 419.306 -0.0016365 + vertex -846.487 410.81 -0.00163531 + endloop + endfacet + facet normal 0.000176391 -4.12186e-05 -1 + outer loop + vertex -844.508 419.306 -0.0016365 + vertex -840.615 418.287 -0.000907686 + vertex -846.487 410.81 -0.00163531 + endloop + endfacet + facet normal 0.000176752 -4.15021e-05 -1 + outer loop + vertex -846.487 410.81 -0.00163531 + vertex -840.615 418.287 -0.000907686 + vertex -842.604 409.851 -0.000909288 + endloop + endfacet + facet normal 0.000117673 -2.75667e-05 -1 + outer loop + vertex -840.615 418.287 -0.000907686 + vertex -836.761 417.242 -0.000425362 + vertex -842.604 409.851 -0.000909288 + endloop + endfacet + facet normal 0.000117461 -2.8347e-05 -1 + outer loop + vertex -840.615 418.287 -0.000907686 + vertex -834.748 425.57 -0.000424985 + vertex -836.761 417.242 -0.000425362 + endloop + endfacet + facet normal 6.30699e-05 -1.51997e-05 -1 + outer loop + vertex -834.748 425.57 -0.000424985 + vertex -830.909 424.441 -0.000165709 + vertex -836.761 417.242 -0.000425362 + endloop + endfacet + facet normal 6.33773e-05 -1.54496e-05 -1 + outer loop + vertex -836.761 417.242 -0.000425362 + vertex -830.909 424.441 -0.000165709 + vertex -832.941 416.174 -0.000166784 + endloop + endfacet + facet normal 6.34852e-05 -1.50635e-05 -1 + outer loop + vertex -836.761 417.242 -0.000425362 + vertex -832.941 416.174 -0.000166784 + vertex -838.762 408.873 -0.000426327 + endloop + endfacet + facet normal 2.71779e-05 -6.55091e-06 -1 + outer loop + vertex -830.909 424.441 -0.000165709 + vertex -827.08 423.307 -5.4222e-05 + vertex -832.941 416.174 -0.000166784 + endloop + endfacet + facet normal 2.77016e-05 -6.98121e-06 -1 + outer loop + vertex -832.941 416.174 -0.000166784 + vertex -827.08 423.307 -5.4222e-05 + vertex -829.146 415.09 -5.40942e-05 + endloop + endfacet + facet normal 2.7753e-05 -6.80126e-06 -1 + outer loop + vertex -832.941 416.174 -0.000166784 + vertex -829.146 415.09 -5.40942e-05 + vertex -834.955 407.875 -0.000166247 + endloop + endfacet + facet normal 9.77478e-06 -2.47345e-06 -1 + outer loop + vertex -827.08 423.307 -5.4222e-05 + vertex -823.28 422.192 -1.43141e-05 + vertex -829.146 415.09 -5.40942e-05 + endloop + endfacet + facet normal 9.77257e-06 -2.47162e-06 -1 + outer loop + vertex -829.146 415.09 -5.40942e-05 + vertex -823.28 422.192 -1.43141e-05 + vertex -825.391 414.017 -1.47449e-05 + endloop + endfacet + facet normal 9.77898e-06 -2.44919e-06 -1 + outer loop + vertex -829.146 415.09 -5.40942e-05 + vertex -825.391 414.017 -1.47449e-05 + vertex -831.179 406.86 -5.38151e-05 + endloop + endfacet + facet normal 2.89388e-06 -6.94811e-07 -1 + outer loop + vertex -823.28 422.192 -1.43141e-05 + vertex -819.678 421.231 -3.22326e-06 + vertex -825.391 414.017 -1.47449e-05 + endloop + endfacet + facet normal 3.02437e-06 -7.9815e-07 -1 + outer loop + vertex -825.391 414.017 -1.47449e-05 + vertex -819.678 421.231 -3.22326e-06 + vertex -821.851 413.088 -3.29641e-06 + endloop + endfacet + facet normal 3.02923e-06 -7.79624e-07 -1 + outer loop + vertex -825.391 414.017 -1.47449e-05 + vertex -821.851 413.088 -3.29641e-06 + vertex -827.45 405.852 -1.46171e-05 + endloop + endfacet + facet normal 1.02731e-06 -2.65181e-07 -1 + outer loop + vertex -819.678 421.231 -3.22326e-06 + vertex -816.698 420.619 -2.4366e-13 + vertex -821.851 413.088 -3.29641e-06 + endloop + endfacet + facet normal 1.08149e-06 -3.02253e-07 -1 + outer loop + vertex -821.851 413.088 -3.29641e-06 + vertex -816.698 420.619 -2.4366e-13 + vertex -818.936 412.61 -2.42478e-13 + endloop + endfacet + facet normal 1.0844e-06 -2.84507e-07 -1 + outer loop + vertex -821.851 413.088 -3.29641e-06 + vertex -818.936 412.61 -2.42478e-13 + vertex -823.95 405.001 -3.27161e-06 + endloop + endfacet + facet normal 1.02286e-06 -2.86841e-07 -1 + outer loop + vertex -819.678 421.231 -3.22326e-06 + vertex -814.342 429.022 -2.39611e-13 + vertex -816.698 420.619 -2.4366e-13 + endloop + endfacet + facet normal 1.00632e-06 -2.75516e-07 -1 + outer loop + vertex -817.389 429.526 -3.20522e-06 + vertex -814.342 429.022 -2.39611e-13 + vertex -819.678 421.231 -3.22326e-06 + endloop + endfacet + facet normal 1.00526e-06 -2.81929e-07 -1 + outer loop + vertex -817.389 429.526 -3.20522e-06 + vertex -811.99 437.406 -2.28185e-13 + vertex -814.342 429.022 -2.39611e-13 + endloop + endfacet + facet normal 1.04697e-06 -3.10502e-07 -1 + outer loop + vertex -814.966 437.93 -3.2786e-06 + vertex -811.99 437.406 -2.28185e-13 + vertex -817.389 429.526 -3.20522e-06 + endloop + endfacet + facet normal 2.78471e-06 -8.11376e-07 -1 + outer loop + vertex -821.054 430.473 -1.41807e-05 + vertex -814.966 437.93 -3.2786e-06 + vertex -817.389 429.526 -3.20522e-06 + endloop + endfacet + facet normal 2.80384e-06 -7.37357e-07 -1 + outer loop + vertex -821.054 430.473 -1.41807e-05 + vertex -817.389 429.526 -3.20522e-06 + vertex -823.28 422.192 -1.43141e-05 + endloop + endfacet + facet normal 2.92357e-06 -9.24739e-07 -1 + outer loop + vertex -818.679 438.917 -1.50443e-05 + vertex -814.966 437.93 -3.2786e-06 + vertex -821.054 430.473 -1.41807e-05 + endloop + endfacet + facet normal 9.54203e-06 -2.78664e-06 -1 + outer loop + vertex -824.937 431.584 -5.43274e-05 + vertex -818.679 438.917 -1.50443e-05 + vertex -821.054 430.473 -1.41807e-05 + endloop + endfacet + facet normal 9.62281e-06 -2.50418e-06 -1 + outer loop + vertex -824.937 431.584 -5.43274e-05 + vertex -821.054 430.473 -1.41807e-05 + vertex -827.08 423.307 -5.4222e-05 + endloop + endfacet + facet normal 9.43785e-06 -2.69773e-06 -1 + outer loop + vertex -822.687 439.973 -5.57222e-05 + vertex -818.679 438.917 -1.50443e-05 + vertex -824.937 431.584 -5.43274e-05 + endloop + endfacet + facet normal 2.68715e-05 -7.37385e-06 -1 + outer loop + vertex -828.836 432.725 -0.000167521 + vertex -822.687 439.973 -5.57222e-05 + vertex -824.937 431.584 -5.43274e-05 + endloop + endfacet + facet normal 2.69895e-05 -6.971e-06 -1 + outer loop + vertex -828.836 432.725 -0.000167521 + vertex -824.937 431.584 -5.43274e-05 + vertex -830.909 424.441 -0.000165709 + endloop + endfacet + facet normal 2.6639e-05 -7.17656e-06 -1 + outer loop + vertex -826.704 441.065 -0.000170577 + vertex -822.687 439.973 -5.57222e-05 + vertex -828.836 432.725 -0.000167521 + endloop + endfacet + facet normal 6.27402e-05 -1.64056e-05 -1 + outer loop + vertex -832.719 433.887 -0.000430212 + vertex -826.704 441.065 -0.000170577 + vertex -828.836 432.725 -0.000167521 + endloop + endfacet + facet normal 6.28731e-05 -1.59611e-05 -1 + outer loop + vertex -832.719 433.887 -0.000430212 + vertex -828.836 432.725 -0.000167521 + vertex -834.748 425.57 -0.000424985 + endloop + endfacet + facet normal 0.000117468 -2.9275e-05 -1 + outer loop + vertex -838.611 426.683 -0.00091138 + vertex -832.719 433.887 -0.000430212 + vertex -834.748 425.57 -0.000424985 + endloop + endfacet + facet normal 0.000117167 -2.90284e-05 -1 + outer loop + vertex -836.603 435.056 -0.000919155 + vertex -832.719 433.887 -0.000430212 + vertex -838.611 426.683 -0.00091138 + endloop + endfacet + facet normal 0.000175938 -4.31233e-05 -1 + outer loop + vertex -842.509 427.769 -0.00164413 + vertex -836.603 435.056 -0.000919155 + vertex -838.611 426.683 -0.00091138 + endloop + endfacet + facet normal 0.000176113 -4.2497e-05 -1 + outer loop + vertex -842.509 427.769 -0.00164413 + vertex -838.611 426.683 -0.00091138 + vertex -844.508 419.306 -0.0016365 + endloop + endfacet + facet normal 0.000214807 -5.16359e-05 -1 + outer loop + vertex -848.444 420.295 -0.0025329 + vertex -842.509 427.769 -0.00164413 + vertex -844.508 419.306 -0.0016365 + endloop + endfacet + facet normal 0.000216598 -5.30585e-05 -1 + outer loop + vertex -846.449 428.819 -0.0025531 + vertex -842.509 427.769 -0.00164413 + vertex -848.444 420.295 -0.0025329 + endloop + endfacet + facet normal 0.000210328 -5.15911e-05 -1 + outer loop + vertex -852.424 421.254 -0.00341952 + vertex -846.449 428.819 -0.0025531 + vertex -848.444 420.295 -0.0025329 + endloop + endfacet + facet normal 0.000210934 -4.90763e-05 -1 + outer loop + vertex -852.424 421.254 -0.00341952 + vertex -848.444 420.295 -0.0025329 + vertex -854.383 412.654 -0.00341075 + endloop + endfacet + facet normal 0.000112731 -2.67026e-05 -1 + outer loop + vertex -858.423 413.539 -0.00388976 + vertex -852.424 421.254 -0.00341952 + vertex -854.383 412.654 -0.00341075 + endloop + endfacet + facet normal 0.000117843 -3.06775e-05 -1 + outer loop + vertex -856.462 422.189 -0.00392403 + vertex -852.424 421.254 -0.00341952 + vertex -858.423 413.539 -0.00388976 + endloop + endfacet + facet normal -0.000113161 2.16912e-05 -1 + outer loop + vertex -862.555 414.407 -0.00340325 + vertex -856.462 422.189 -0.00392403 + vertex -858.423 413.539 -0.00388976 + endloop + endfacet + facet normal -0.0001119 2.76929e-05 -1 + outer loop + vertex -862.555 414.407 -0.00340325 + vertex -858.423 413.539 -0.00388976 + vertex -864.482 405.667 -0.00342976 + endloop + endfacet + facet normal -0.000343039 7.86305e-05 -1 + outer loop + vertex -868.769 406.451 -0.00189736 + vertex -862.555 414.407 -0.00340325 + vertex -864.482 405.667 -0.00342976 + endloop + endfacet + facet normal -0.000350308 8.43077e-05 -1 + outer loop + vertex -866.802 415.254 -0.00184418 + vertex -862.555 414.407 -0.00340325 + vertex -868.769 406.451 -0.00189736 + endloop + endfacet + facet normal -0.000269592 6.62739e-05 -1 + outer loop + vertex -873.193 407.166 -0.000657469 + vertex -866.802 415.254 -0.00184418 + vertex -868.769 406.451 -0.00189736 + endloop + endfacet + facet normal -0.000269337 6.78519e-05 -1 + outer loop + vertex -873.193 407.166 -0.000657469 + vertex -868.769 406.451 -0.00189736 + vertex -875.151 398.239 -0.000735543 + endloop + endfacet + facet normal -0.000148588 4.13536e-05 -1 + outer loop + vertex -879.758 398.739 -3.04423e-05 + vertex -873.193 407.166 -0.000657469 + vertex -875.151 398.239 -0.000735543 + endloop + endfacet + facet normal -0.000112926 1.35701e-05 -1 + outer loop + vertex -877.71 407.735 -0.000139566 + vertex -873.193 407.166 -0.000657469 + vertex -879.758 398.739 -3.04423e-05 + endloop + endfacet + facet normal -0.00206565 0.000457993 -0.999998 + outer loop + vertex -884.419 399.039 0.00973596 + vertex -877.71 407.735 -0.000139566 + vertex -879.758 398.739 -3.04423e-05 + endloop + endfacet + facet normal -0.00207002 0.000390136 -0.999998 + outer loop + vertex -884.419 399.039 0.00973596 + vertex -879.758 398.739 -3.04423e-05 + vertex -886.482 389.889 0.0104362 + endloop + endfacet + facet normal -0.0101884 0.00222037 -0.999946 + outer loop + vertex -891.282 389.986 0.0595581 + vertex -884.419 399.039 0.00973596 + vertex -886.482 389.889 0.0104362 + endloop + endfacet + facet normal -0.0103664 0.00235531 -0.999943 + outer loop + vertex -889.086 399.212 0.0585258 + vertex -884.419 399.039 0.00973596 + vertex -891.282 389.986 0.0595581 + endloop + endfacet + facet normal -0.02899 0.00678776 -0.999557 + outer loop + vertex -896.111 390.165 0.200819 + vertex -889.086 399.212 0.0585258 + vertex -891.282 389.986 0.0595581 + endloop + endfacet + facet normal -0.0289957 0.00663375 -0.999558 + outer loop + vertex -896.111 390.165 0.200819 + vertex -891.282 389.986 0.0595581 + vertex -898.334 380.771 0.202981 + endloop + endfacet + facet normal -0.0565227 0.0131502 -0.998315 + outer loop + vertex -903.406 381.184 0.495559 + vertex -896.111 390.165 0.200819 + vertex -898.334 380.771 0.202981 + endloop + endfacet + facet normal -0.058836 0.0150346 -0.998154 + outer loop + vertex -900.985 390.672 0.495809 + vertex -896.111 390.165 0.200819 + vertex -903.406 381.184 0.495559 + endloop + endfacet + facet normal -0.0914733 0.0233599 -0.995534 + outer loop + vertex -908.552 382.011 0.987778 + vertex -900.985 390.672 0.495809 + vertex -903.406 381.184 0.495559 + endloop + endfacet + facet normal -0.0913626 0.0240449 -0.995527 + outer loop + vertex -908.552 382.011 0.987778 + vertex -903.406 381.184 0.495559 + vertex -911.021 372.278 0.979355 + endloop + endfacet + facet normal -0.0878263 0.0209999 -0.995914 + outer loop + vertex -911.021 372.278 0.979355 + vertex -903.406 381.184 0.495559 + vertex -905.644 371.597 0.490786 + endloop + endfacet + facet normal -0.0946224 0.0261315 -0.99517 + outer loop + vertex -905.887 391.592 0.986024 + vertex -900.985 390.672 0.495809 + vertex -908.552 382.011 0.987778 + endloop + endfacet + facet normal -0.0946171 0.0261595 -0.99517 + outer loop + vertex -905.887 391.592 0.986024 + vertex -898.421 400.044 0.498376 + vertex -900.985 390.672 0.495809 + endloop + endfacet + facet normal -0.0614013 0.0170725 -0.997967 + outer loop + vertex -898.421 400.044 0.498376 + vertex -893.751 399.466 0.201116 + vertex -900.985 390.672 0.495809 + endloop + endfacet + facet normal -0.0614561 0.016632 -0.997971 + outer loop + vertex -898.421 400.044 0.498376 + vertex -891.276 408.68 0.202262 + vertex -893.751 399.466 0.201116 + endloop + endfacet + facet normal -0.0316232 0.00861876 -0.999463 + outer loop + vertex -891.276 408.68 0.202262 + vertex -886.784 408.353 0.0573326 + vertex -893.751 399.466 0.201116 + endloop + endfacet + facet normal -0.0301477 0.00746128 -0.999518 + outer loop + vertex -893.751 399.466 0.201116 + vertex -886.784 408.353 0.0573326 + vertex -889.086 399.212 0.0585258 + endloop + endfacet + facet normal -0.0105763 0.00253279 -0.999941 + outer loop + vertex -886.784 408.353 0.0573326 + vertex -882.258 408.111 0.00884213 + vertex -889.086 399.212 0.0585258 + endloop + endfacet + facet normal -0.0105741 0.00257475 -0.999941 + outer loop + vertex -886.784 408.353 0.0573326 + vertex -880.016 417.112 0.00831606 + vertex -882.258 408.111 0.00884213 + endloop + endfacet + facet normal -0.00192832 0.000421751 -0.999998 + outer loop + vertex -880.016 417.112 0.00831606 + vertex -875.588 416.667 -0.000410306 + vertex -882.258 408.111 0.00884213 + endloop + endfacet + facet normal -0.00193955 0.000430506 -0.999998 + outer loop + vertex -882.258 408.111 0.00884213 + vertex -875.588 416.667 -0.000410306 + vertex -877.71 407.735 -0.000139566 + endloop + endfacet + facet normal -5.98538e-05 -1.60881e-05 -1 + outer loop + vertex -875.588 416.667 -0.000410306 + vertex -871.163 416.029 -0.000664913 + vertex -877.71 407.735 -0.000139566 + endloop + endfacet + facet normal -5.89585e-05 -9.8813e-06 -1 + outer loop + vertex -875.588 416.667 -0.000410306 + vertex -869.079 424.846 -0.000874878 + vertex -871.163 416.029 -0.000664913 + endloop + endfacet + facet normal -0.000239046 3.26736e-05 -1 + outer loop + vertex -869.079 424.846 -0.000874878 + vertex -864.787 424.008 -0.00192838 + vertex -871.163 416.029 -0.000664913 + endloop + endfacet + facet normal -0.000261463 5.05868e-05 -1 + outer loop + vertex -871.163 416.029 -0.000664913 + vertex -864.787 424.008 -0.00192838 + vertex -866.802 415.254 -0.00184418 + endloop + endfacet + facet normal -0.000347176 7.03232e-05 -1 + outer loop + vertex -864.787 424.008 -0.00192838 + vertex -860.578 423.108 -0.0034529 + vertex -866.802 415.254 -0.00184418 + endloop + endfacet + facet normal -0.00034941 5.98742e-05 -1 + outer loop + vertex -864.787 424.008 -0.00192838 + vertex -858.566 431.781 -0.00363639 + vertex -860.578 423.108 -0.0034529 + endloop + endfacet + facet normal -9.25969e-05 3.18868e-07 -1 + outer loop + vertex -858.566 431.781 -0.00363639 + vertex -854.469 430.813 -0.00401613 + vertex -860.578 423.108 -0.0034529 + endloop + endfacet + facet normal -0.000111116 1.5003e-05 -1 + outer loop + vertex -860.578 423.108 -0.0034529 + vertex -854.469 430.813 -0.00401613 + vertex -856.462 422.189 -0.00392403 + endloop + endfacet + facet normal 0.000126076 -3.98199e-05 -1 + outer loop + vertex -854.469 430.813 -0.00401613 + vertex -850.433 429.831 -0.00346821 + vertex -856.462 422.189 -0.00392403 + endloop + endfacet + facet normal 0.000123879 -4.8851e-05 -1 + outer loop + vertex -854.469 430.813 -0.00401613 + vertex -848.425 438.388 -0.0036375 + vertex -850.433 429.831 -0.00346821 + endloop + endfacet + facet normal 0.00023182 -7.41799e-05 -1 + outer loop + vertex -848.425 438.388 -0.0036375 + vertex -844.443 437.321 -0.00263521 + vertex -850.433 429.831 -0.00346821 + endloop + endfacet + facet normal 0.000214405 -6.02529e-05 -1 + outer loop + vertex -850.433 429.831 -0.00346821 + vertex -844.443 437.321 -0.00263521 + vertex -846.449 428.819 -0.0025531 + endloop + endfacet + facet normal 0.000225274 -6.28179e-05 -1 + outer loop + vertex -844.443 437.321 -0.00263521 + vertex -840.505 436.207 -0.00167817 + vertex -846.449 428.819 -0.0025531 + endloop + endfacet + facet normal 0.000223839 -6.78891e-05 -1 + outer loop + vertex -844.443 437.321 -0.00263521 + vertex -838.501 444.619 -0.00180082 + vertex -840.505 436.207 -0.00167817 + endloop + endfacet + facet normal 0.000193074 -6.05621e-05 -1 + outer loop + vertex -838.501 444.619 -0.00180082 + vertex -834.592 443.409 -0.000972676 + vertex -840.505 436.207 -0.00167817 + endloop + endfacet + facet normal 0.000179854 -4.97079e-05 -1 + outer loop + vertex -840.505 436.207 -0.00167817 + vertex -834.592 443.409 -0.000972676 + vertex -836.603 435.056 -0.000919155 + endloop + endfacet + facet normal 0.000123445 -3.61273e-05 -1 + outer loop + vertex -834.592 443.409 -0.000972676 + vertex -830.67 442.212 -0.000445262 + vertex -836.603 435.056 -0.000919155 + endloop + endfacet + facet normal 0.00012246 -3.93557e-05 -1 + outer loop + vertex -834.592 443.409 -0.000972676 + vertex -828.589 450.561 -0.000518993 + vertex -830.67 442.212 -0.000445262 + endloop + endfacet + facet normal 7.14066e-05 -2.66301e-05 -1 + outer loop + vertex -828.589 450.561 -0.000518993 + vertex -824.508 449.471 -0.000198573 + vertex -830.67 442.212 -0.000445262 + endloop + endfacet + facet normal 6.35062e-05 -1.99236e-05 -1 + outer loop + vertex -830.67 442.212 -0.000445262 + vertex -824.508 449.471 -0.000198573 + vertex -826.704 441.065 -0.000170577 + endloop + endfacet + facet normal 3.01909e-05 -1.12189e-05 -1 + outer loop + vertex -824.508 449.471 -0.000198573 + vertex -820.353 448.459 -6.1792e-05 + vertex -826.704 441.065 -0.000170577 + endloop + endfacet + facet normal 3.00368e-05 -1.18516e-05 -1 + outer loop + vertex -824.508 449.471 -0.000198573 + vertex -818.034 456.995 -9.32965e-05 + vertex -820.353 448.459 -6.1792e-05 + endloop + endfacet + facet normal 1.44095e-05 -7.60576e-06 -1 + outer loop + vertex -818.034 456.995 -9.32965e-05 + vertex -813.835 456.009 -2.52825e-05 + vertex -820.353 448.459 -6.1792e-05 + endloop + endfacet + facet normal 1.00696e-05 -3.85851e-06 -1 + outer loop + vertex -820.353 448.459 -6.1792e-05 + vertex -813.835 456.009 -2.52825e-05 + vertex -816.214 447.471 -1.63004e-05 + endloop + endfacet + facet normal 1.01534e-05 -3.50732e-06 -1 + outer loop + vertex -820.353 448.459 -6.1792e-05 + vertex -816.214 447.471 -1.63004e-05 + vertex -822.687 439.973 -5.57222e-05 + endloop + endfacet + facet normal 4.59294e-06 -2.3321e-06 -1 + outer loop + vertex -813.835 456.009 -2.52825e-05 + vertex -810.031 454.917 -5.26593e-06 + vertex -816.214 447.471 -1.63004e-05 + endloop + endfacet + facet normal 3.08153e-06 -1.07702e-06 -1 + outer loop + vertex -816.214 447.471 -1.63004e-05 + vertex -810.031 454.917 -5.26593e-06 + vertex -812.468 446.432 -3.6356e-06 + endloop + endfacet + facet normal 3.09241e-06 -1.03777e-06 -1 + outer loop + vertex -816.214 447.471 -1.63004e-05 + vertex -812.468 446.432 -3.6356e-06 + vertex -818.679 438.917 -1.50443e-05 + endloop + endfacet + facet normal 1.6958e-06 -6.79101e-07 -1 + outer loop + vertex -810.031 454.917 -5.26593e-06 + vertex -807.435 453.646 -1.7316e-13 + vertex -812.468 446.432 -3.6356e-06 + endloop + endfacet + facet normal 1.20827e-06 -3.38973e-07 -1 + outer loop + vertex -812.468 446.432 -3.6356e-06 + vertex -807.435 453.646 -1.7316e-13 + vertex -809.77 445.321 -2.08073e-13 + endloop + endfacet + facet normal 1.18691e-06 -3.90854e-07 -1 + outer loop + vertex -812.468 446.432 -3.6356e-06 + vertex -809.77 445.321 -2.08073e-13 + vertex -814.966 437.93 -3.2786e-06 + endloop + endfacet + facet normal 1.78329e-06 -5.00411e-07 -1 + outer loop + vertex -810.031 454.917 -5.26593e-06 + vertex -805.089 462.006 -1.19031e-13 + vertex -807.435 453.646 -1.7316e-13 + endloop + endfacet + facet normal 2.94863e-06 -1.3128e-06 -1 + outer loop + vertex -807.99 463.224 -1.01536e-05 + vertex -805.089 462.006 -1.19031e-13 + vertex -810.031 454.917 -5.26593e-06 + endloop + endfacet + facet normal 3.13078e-06 -8.78671e-07 -1 + outer loop + vertex -807.99 463.224 -1.01536e-05 + vertex -802.74 470.377 -4.67003e-14 + vertex -805.089 462.006 -1.19031e-13 + endloop + endfacet + facet normal 3.47132e-07 1.16472e-06 -1 + outer loop + vertex -807.052 471.662 -4.70875e-14 + vertex -802.74 470.377 -4.67003e-14 + vertex -807.99 463.224 -1.01536e-05 + endloop + endfacet + facet normal 8.46984e-06 2.61727e-07 -1 + outer loop + vertex -811.878 464.485 -4.27538e-05 + vertex -807.052 471.662 -4.70875e-14 + vertex -807.99 463.224 -1.01536e-05 + endloop + endfacet + facet normal 7.17907e-06 -3.71854e-06 -1 + outer loop + vertex -811.878 464.485 -4.27538e-05 + vertex -807.99 463.224 -1.01536e-05 + vertex -813.835 456.009 -2.52825e-05 + endloop + endfacet + facet normal 1.47947e-06 4.96208e-06 -1 + outer loop + vertex -811.036 472.85 -4.72355e-14 + vertex -807.052 471.662 -4.70875e-14 + vertex -811.878 464.485 -4.27538e-05 + endloop + endfacet + facet normal 2.45267e-05 2.64211e-06 -1 + outer loop + vertex -816.09 465.522 -0.000143317 + vertex -811.036 472.85 -4.72355e-14 + vertex -811.878 464.485 -4.27538e-05 + endloop + endfacet + facet normal 2.12385e-05 -1.07086e-05 -1 + outer loop + vertex -816.09 465.522 -0.000143317 + vertex -811.878 464.485 -4.27538e-05 + vertex -818.034 456.995 -9.32965e-05 + endloop + endfacet + facet normal 4.14436e-05 -1.53155e-05 -1 + outer loop + vertex -822.318 457.928 -0.000285117 + vertex -816.09 465.522 -0.000143317 + vertex -818.034 456.995 -9.32965e-05 + endloop + endfacet + facet normal 5.35747e-05 -2.52643e-05 -1 + outer loop + vertex -820.424 466.469 -0.000399425 + vertex -816.09 465.522 -0.000143317 + vertex -822.318 457.928 -0.000285117 + endloop + endfacet + facet normal 9.70331e-05 -3.49018e-05 -1 + outer loop + vertex -826.517 458.953 -0.000728327 + vertex -820.424 466.469 -0.000399425 + vertex -822.318 457.928 -0.000285117 + endloop + endfacet + facet normal 9.38107e-05 -4.8104e-05 -1 + outer loop + vertex -826.517 458.953 -0.000728327 + vertex -822.318 457.928 -0.000285117 + vertex -828.589 450.561 -0.000518993 + endloop + endfacet + facet normal 0.000141065 -5.97704e-05 -1 + outer loop + vertex -832.572 451.757 -0.00115243 + vertex -826.517 458.953 -0.000728327 + vertex -828.589 450.561 -0.000518993 + endloop + endfacet + facet normal 0.000176838 -8.98726e-05 -1 + outer loop + vertex -830.572 460.126 -0.00155092 + vertex -826.517 458.953 -0.000728327 + vertex -832.572 451.757 -0.00115243 + endloop + endfacet + facet normal 0.000223141 -0.000100938 -1 + outer loop + vertex -836.5 453.005 -0.00215492 + vertex -830.572 460.126 -0.00155092 + vertex -832.572 451.757 -0.00115243 + endloop + endfacet + facet normal 0.000224754 -9.58616e-05 -1 + outer loop + vertex -836.5 453.005 -0.00215492 + vertex -832.572 451.757 -0.00115243 + vertex -838.501 444.619 -0.00180082 + endloop + endfacet + facet normal 0.000247255 -0.000101231 -1 + outer loop + vertex -842.433 445.797 -0.00289226 + vertex -836.5 453.005 -0.00215492 + vertex -838.501 444.619 -0.00180082 + endloop + endfacet + facet normal 0.000295298 -0.000140777 -1 + outer loop + vertex -840.426 454.238 -0.00348786 + vertex -836.5 453.005 -0.00215492 + vertex -842.433 445.797 -0.00289226 + endloop + endfacet + facet normal 0.000263533 -0.000133224 -1 + outer loop + vertex -846.408 446.918 -0.00408902 + vertex -840.426 454.238 -0.00348786 + vertex -842.433 445.797 -0.00289226 + endloop + endfacet + facet normal 0.000268287 -0.000116363 -1 + outer loop + vertex -846.408 446.918 -0.00408902 + vertex -842.433 445.797 -0.00289226 + vertex -848.425 438.388 -0.0036375 + endloop + endfacet + facet normal 0.000149984 -8.83942e-05 -1 + outer loop + vertex -852.453 439.419 -0.00433288 + vertex -846.408 446.918 -0.00408902 + vertex -848.425 438.388 -0.0036375 + endloop + endfacet + facet normal 0.000195924 -0.00012543 -1 + outer loop + vertex -850.425 447.997 -0.00501138 + vertex -846.408 446.918 -0.00408902 + vertex -852.453 439.419 -0.00433288 + endloop + endfacet + facet normal -6.57126e-05 -6.35613e-05 -1 + outer loop + vertex -856.531 440.434 -0.00412941 + vertex -850.425 447.997 -0.00501138 + vertex -852.453 439.419 -0.00433288 + endloop + endfacet + facet normal -6.05327e-05 -4.27449e-05 -1 + outer loop + vertex -856.531 440.434 -0.00412941 + vertex -852.453 439.419 -0.00433288 + vertex -858.566 431.781 -0.00363639 + endloop + endfacet + facet normal -0.000326521 1.98144e-05 -1 + outer loop + vertex -862.734 432.735 -0.00225672 + vertex -856.531 440.434 -0.00412941 + vertex -858.566 431.781 -0.00363639 + endloop + endfacet + facet normal -0.00027009 -2.56499e-05 -1 + outer loop + vertex -860.655 441.438 -0.00304145 + vertex -856.531 440.434 -0.00412941 + vertex -862.734 432.735 -0.00225672 + endloop + endfacet + facet normal -0.000183185 -4.6411e-05 -1 + outer loop + vertex -866.956 433.632 -0.00152489 + vertex -860.655 441.438 -0.00304145 + vertex -862.734 432.735 -0.00225672 + endloop + endfacet + facet normal -0.000179812 -3.05307e-05 -1 + outer loop + vertex -866.956 433.632 -0.00152489 + vertex -862.734 432.735 -0.00225672 + vertex -869.079 424.846 -0.000874878 + endloop + endfacet + facet normal 1.16171e-05 -7.67916e-05 -1 + outer loop + vertex -873.408 425.55 -0.000979222 + vertex -866.956 433.632 -0.00152489 + vertex -869.079 424.846 -0.000874878 + endloop + endfacet + facet normal 0.000152369 -0.000189163 -1 + outer loop + vertex -871.183 434.4 -0.00231439 + vertex -866.956 433.632 -0.00152489 + vertex -873.408 425.55 -0.000979222 + endloop + endfacet + facet normal -0.00184812 0.00031373 -0.999998 + outer loop + vertex -877.711 426.062 0.00713268 + vertex -871.183 434.4 -0.00231439 + vertex -873.408 425.55 -0.000979222 + endloop + endfacet + facet normal -0.00184464 0.00034297 -0.999998 + outer loop + vertex -877.711 426.062 0.00713268 + vertex -873.408 425.55 -0.000979222 + vertex -880.016 417.112 0.00831606 + endloop + endfacet + facet normal -0.0109611 0.00269141 -0.999936 + outer loop + vertex -884.394 417.427 0.0571574 + vertex -877.711 426.062 0.00713268 + vertex -880.016 417.112 0.00831606 + endloop + endfacet + facet normal -0.0109492 0.00268215 -0.999936 + outer loop + vertex -881.931 426.452 0.0543919 + vertex -877.711 426.062 0.00713268 + vertex -884.394 417.427 0.0571574 + endloop + endfacet + facet normal -0.0324701 0.00855642 -0.999436 + outer loop + vertex -888.7 417.831 0.200503 + vertex -881.931 426.452 0.0543919 + vertex -884.394 417.427 0.0571574 + endloop + endfacet + facet normal -0.0324345 0.00893647 -0.999434 + outer loop + vertex -888.7 417.831 0.200503 + vertex -884.394 417.427 0.0571574 + vertex -891.276 408.68 0.202262 + endloop + endfacet + facet normal -0.064238 0.0178878 -0.997774 + outer loop + vertex -895.731 409.332 0.500761 + vertex -888.7 417.831 0.200503 + vertex -891.276 408.68 0.202262 + endloop + endfacet + facet normal -0.0674261 0.0205342 -0.997513 + outer loop + vertex -892.925 418.575 0.501413 + vertex -888.7 417.831 0.200503 + vertex -895.731 409.332 0.500761 + endloop + endfacet + facet normal -0.104381 0.0317497 -0.99403 + outer loop + vertex -900.127 410.39 0.9962 + vertex -892.925 418.575 0.501413 + vertex -895.731 409.332 0.500761 + endloop + endfacet + facet normal -0.103982 0.0333996 -0.994018 + outer loop + vertex -900.127 410.39 0.9962 + vertex -895.731 409.332 0.500761 + vertex -903.08 401.014 0.990029 + endloop + endfacet + facet normal -0.0989622 0.028926 -0.994671 + outer loop + vertex -903.08 401.014 0.990029 + vertex -895.731 409.332 0.500761 + vertex -898.421 400.044 0.498376 + endloop + endfacet + facet normal -0.109352 0.0361646 -0.993345 + outer loop + vertex -897.038 419.749 0.996935 + vertex -892.925 418.575 0.501413 + vertex -900.127 410.39 0.9962 + endloop + endfacet + facet normal -0.109872 0.0343462 -0.993352 + outer loop + vertex -897.038 419.749 0.996935 + vertex -890.031 427.763 0.499013 + vertex -892.925 418.575 0.501413 + endloop + endfacet + facet normal -0.0706079 0.0219784 -0.997262 + outer loop + vertex -890.031 427.763 0.499013 + vertex -886.042 426.936 0.198366 + vertex -892.925 418.575 0.501413 + endloop + endfacet + facet normal -0.0707834 0.0211339 -0.997268 + outer loop + vertex -890.031 427.763 0.499013 + vertex -883.323 436.004 0.197509 + vertex -886.042 426.936 0.198366 + endloop + endfacet + facet normal -0.035395 0.0105206 -0.999318 + outer loop + vertex -883.323 436.004 0.197509 + vertex -879.408 435.444 0.0529624 + vertex -886.042 426.936 0.198366 + endloop + endfacet + facet normal -0.0338957 0.00935042 -0.999382 + outer loop + vertex -886.042 426.936 0.198366 + vertex -879.408 435.444 0.0529624 + vertex -881.931 426.452 0.0543919 + endloop + endfacet + facet normal -0.0116058 0.003097 -0.999928 + outer loop + vertex -879.408 435.444 0.0529624 + vertex -875.353 434.981 0.00445679 + vertex -881.931 426.452 0.0543919 + endloop + endfacet + facet normal -0.0116111 0.00305077 -0.999928 + outer loop + vertex -879.408 435.444 0.0529624 + vertex -872.954 443.87 0.00371868 + vertex -875.353 434.981 0.00445679 + endloop + endfacet + facet normal -0.00187589 0.000423258 -0.999998 + outer loop + vertex -872.954 443.87 0.00371868 + vertex -868.923 443.22 -0.00411789 + vertex -875.353 434.981 0.00445679 + endloop + endfacet + facet normal -0.00159554 0.000204462 -0.999999 + outer loop + vertex -875.353 434.981 0.00445679 + vertex -868.923 443.22 -0.00411789 + vertex -871.183 434.4 -0.00231439 + endloop + endfacet + facet normal 0.000271939 -0.000274193 -1 + outer loop + vertex -868.923 443.22 -0.00411789 + vertex -864.802 442.393 -0.00277042 + vertex -871.183 434.4 -0.00231439 + endloop + endfacet + facet normal 0.000278943 -0.000239291 -1 + outer loop + vertex -868.923 443.22 -0.00411789 + vertex -862.625 451.113 -0.00424983 + vertex -864.802 442.393 -0.00277042 + endloop + endfacet + facet normal -4.53368e-05 -0.000158338 -1 + outer loop + vertex -862.625 451.113 -0.00424983 + vertex -858.555 450.106 -0.004275 + vertex -864.802 442.393 -0.00277042 + endloop + endfacet + facet normal -9.29411e-05 -0.000119787 -1 + outer loop + vertex -864.802 442.393 -0.00277042 + vertex -858.555 450.106 -0.004275 + vertex -860.655 441.438 -0.00304145 + endloop + endfacet + facet normal -0.000218117 -8.94671e-05 -1 + outer loop + vertex -858.555 450.106 -0.004275 + vertex -854.478 449.056 -0.00507025 + vertex -860.655 441.438 -0.00304145 + endloop + endfacet + facet normal -0.000216329 -8.25238e-05 -1 + outer loop + vertex -858.555 450.106 -0.004275 + vertex -852.413 457.637 -0.00622509 + vertex -854.478 449.056 -0.00507025 + endloop + endfacet + facet normal -6.83871e-08 -0.000134573 -1 + outer loop + vertex -852.413 457.637 -0.00622509 + vertex -848.387 456.537 -0.00607734 + vertex -854.478 449.056 -0.00507025 + endloop + endfacet + facet normal -1.7043e-05 -0.000120751 -1 + outer loop + vertex -854.478 449.056 -0.00507025 + vertex -848.387 456.537 -0.00607734 + vertex -850.425 447.997 -0.00501138 + endloop + endfacet + facet normal 0.000231279 -0.000180005 -1 + outer loop + vertex -848.387 456.537 -0.00607734 + vertex -844.386 455.414 -0.0049498 + vertex -850.425 447.997 -0.00501138 + endloop + endfacet + facet normal 0.000232881 -0.000174297 -1 + outer loop + vertex -848.387 456.537 -0.00607734 + vertex -842.393 463.892 -0.00596336 + vertex -844.386 455.414 -0.0049498 + endloop + endfacet + facet normal 0.000338764 -0.000199185 -1 + outer loop + vertex -842.393 463.892 -0.00596336 + vertex -838.443 462.672 -0.00438229 + vertex -844.386 455.414 -0.0049498 + endloop + endfacet + facet normal 0.000315677 -0.000180281 -1 + outer loop + vertex -844.386 455.414 -0.0049498 + vertex -838.443 462.672 -0.00438229 + vertex -840.426 454.238 -0.00348786 + endloop + endfacet + facet normal 0.00034536 -0.000187261 -1 + outer loop + vertex -838.443 462.672 -0.00438229 + vertex -834.526 461.403 -0.0027917 + vertex -840.426 454.238 -0.00348786 + endloop + endfacet + facet normal 0.000373745 -9.96709e-05 -1 + outer loop + vertex -838.443 462.672 -0.00438229 + vertex -832.732 469.955 -0.00297358 + vertex -834.526 461.403 -0.0027917 + endloop + endfacet + facet normal 0.000274441 -7.88392e-05 -1 + outer loop + vertex -832.732 469.955 -0.00297358 + vertex -828.758 468.683 -0.00178271 + vertex -834.526 461.403 -0.0027917 + endloop + endfacet + facet normal 0.000285539 -8.76314e-05 -1 + outer loop + vertex -834.526 461.403 -0.0027917 + vertex -828.758 468.683 -0.00178271 + vertex -830.572 460.126 -0.00155092 + endloop + endfacet + facet normal 0.000193001 -6.8011e-05 -1 + outer loop + vertex -828.758 468.683 -0.00178271 + vertex -824.68 467.507 -0.00091564 + vertex -830.572 460.126 -0.00155092 + endloop + endfacet + facet normal 0.000232693 6.96935e-05 -1 + outer loop + vertex -828.758 468.683 -0.00178271 + vertex -823.456 476.56 -4.67305e-14 + vertex -824.68 467.507 -0.00091564 + endloop + endfacet + facet normal 2.90835e-05 9.72153e-05 -1 + outer loop + vertex -823.456 476.56 -4.67305e-14 + vertex -819.374 475.339 -4.70262e-14 + vertex -824.68 467.507 -0.00091564 + endloop + endfacet + facet normal 0.000128567 2.98108e-05 -1 + outer loop + vertex -824.68 467.507 -0.00091564 + vertex -819.374 475.339 -4.70262e-14 + vertex -820.424 466.469 -0.000399425 + endloop + endfacet + facet normal 1.29915e-05 4.34953e-05 -1 + outer loop + vertex -819.374 475.339 -4.70262e-14 + vertex -815.14 474.074 -4.72096e-14 + vertex -820.424 466.469 -0.000399425 + endloop + endfacet + facet normal 5.64501e-05 0.00018832 -1 + outer loop + vertex -827.484 477.767 -4.63559e-14 + vertex -823.456 476.56 -4.67305e-14 + vertex -828.758 468.683 -0.00178271 + endloop + endfacet + facet normal 0.000346923 0.000147581 -1 + outer loop + vertex -832.732 469.955 -0.00297358 + vertex -827.484 477.767 -4.63559e-14 + vertex -828.758 468.683 -0.00178271 + endloop + endfacet + facet normal 9.51716e-05 0.000316694 -1 + outer loop + vertex -831.542 478.987 -4.59294e-14 + vertex -827.484 477.767 -4.63559e-14 + vertex -832.732 469.955 -0.00297358 + endloop + endfacet + facet normal 0.000427332 0.000272951 -1 + outer loop + vertex -836.69 471.242 -0.00431377 + vertex -831.542 478.987 -4.59294e-14 + vertex -832.732 469.955 -0.00297358 + endloop + endfacet + facet normal 0.000139906 0.000463994 -1 + outer loop + vertex -835.717 480.246 -4.54802e-14 + vertex -831.542 478.987 -4.59294e-14 + vertex -836.69 471.242 -0.00431377 + endloop + endfacet + facet normal 0.000413835 0.0004344 -1 + outer loop + vertex -840.65 472.482 -0.00541383 + vertex -835.717 480.246 -4.54802e-14 + vertex -836.69 471.242 -0.00431377 + endloop + endfacet + facet normal 0.000280036 7.14529e-06 -1 + outer loop + vertex -840.65 472.482 -0.00541383 + vertex -836.69 471.242 -0.00431377 + vertex -842.393 463.892 -0.00596336 + endloop + endfacet + facet normal 0.00025447 1.23333e-05 -1 + outer loop + vertex -846.374 465.055 -0.00696212 + vertex -840.65 472.482 -0.00541383 + vertex -842.393 463.892 -0.00596336 + endloop + endfacet + facet normal 7.84315e-05 0.000148013 -1 + outer loop + vertex -844.6 473.665 -0.00554853 + vertex -840.65 472.482 -0.00541383 + vertex -846.374 465.055 -0.00696212 + endloop + endfacet + facet normal -7.54753e-05 0.000179735 -1 + outer loop + vertex -850.374 466.19 -0.00645622 + vertex -844.6 473.665 -0.00554853 + vertex -846.374 465.055 -0.00696212 + endloop + endfacet + facet normal -0.000125665 2.94494e-06 -1 + outer loop + vertex -850.374 466.19 -0.00645622 + vertex -846.374 465.055 -0.00696212 + vertex -852.413 457.637 -0.00622509 + endloop + endfacet + facet normal -0.000237763 2.96765e-05 -1 + outer loop + vertex -856.442 458.73 -0.00523474 + vertex -850.374 466.19 -0.00645622 + vertex -852.413 457.637 -0.00622509 + endloop + endfacet + facet normal -0.000500389 0.000243307 -1 + outer loop + vertex -854.358 467.318 -0.00418823 + vertex -850.374 466.19 -0.00645622 + vertex -856.442 458.73 -0.00523474 + endloop + endfacet + facet normal -0.000201264 0.000170704 -1 + outer loop + vertex -860.436 459.784 -0.00425103 + vertex -854.358 467.318 -0.00418823 + vertex -856.442 458.73 -0.00523474 + endloop + endfacet + facet normal -0.000230961 5.81664e-05 -1 + outer loop + vertex -860.436 459.784 -0.00425103 + vertex -856.442 458.73 -0.00523474 + vertex -862.625 451.113 -0.00424983 + endloop + endfacet + facet normal 0.000166404 -4.21461e-05 -1 + outer loop + vertex -866.636 452.002 -0.00495482 + vertex -860.436 459.784 -0.00425103 + vertex -862.625 451.113 -0.00424983 + endloop + endfacet + facet normal -0.000377273 0.000391047 -1 + outer loop + vertex -864.339 460.727 -0.00240966 + vertex -860.436 459.784 -0.00425103 + vertex -866.636 452.002 -0.00495482 + endloop + endfacet + facet normal -0.00271284 0.00100601 -0.999996 + outer loop + vertex -870.528 452.718 0.00632378 + vertex -864.339 460.727 -0.00240966 + vertex -866.636 452.002 -0.00495482 + endloop + endfacet + facet normal -0.00270723 0.00103654 -0.999996 + outer loop + vertex -870.528 452.718 0.00632378 + vertex -866.636 452.002 -0.00495482 + vertex -872.954 443.87 0.00371868 + endloop + endfacet + facet normal -0.0126023 0.00374896 -0.999914 + outer loop + vertex -876.843 444.409 0.0547637 + vertex -870.528 452.718 0.00632378 + vertex -872.954 443.87 0.00371868 + endloop + endfacet + facet normal -0.0141329 0.0049125 -0.999888 + outer loop + vertex -874.255 453.327 0.0619896 + vertex -870.528 452.718 0.00632378 + vertex -876.843 444.409 0.0547637 + endloop + endfacet + facet normal -0.038445 0.0119688 -0.999189 + outer loop + vertex -880.564 445.039 0.205472 + vertex -874.255 453.327 0.0619896 + vertex -876.843 444.409 0.0547637 + endloop + endfacet + facet normal -0.0383402 0.0125872 -0.999185 + outer loop + vertex -880.564 445.039 0.205472 + vertex -876.843 444.409 0.0547637 + vertex -883.323 436.004 0.197509 + endloop + endfacet + facet normal -0.0754321 0.0239105 -0.996864 + outer loop + vertex -887.082 436.897 0.503346 + vertex -880.564 445.039 0.205472 + vertex -883.323 436.004 0.197509 + endloop + endfacet + facet normal -0.0789683 0.0267538 -0.996518 + outer loop + vertex -884.091 445.974 0.510047 + vertex -880.564 445.039 0.205472 + vertex -887.082 436.897 0.503346 + endloop + endfacet + facet normal -0.122637 0.041138 -0.991599 + outer loop + vertex -890.659 438.16 0.998235 + vertex -884.091 445.974 0.510047 + vertex -887.082 436.897 0.503346 + endloop + endfacet + facet normal -0.12196 0.0430578 -0.991601 + outer loop + vertex -890.659 438.16 0.998235 + vertex -887.082 436.897 0.503346 + vertex -893.873 428.999 0.995653 + endloop + endfacet + facet normal -0.116104 0.0379654 -0.992511 + outer loop + vertex -893.873 428.999 0.995653 + vertex -887.082 436.897 0.503346 + vertex -890.031 427.763 0.499013 + endloop + endfacet + facet normal -0.129682 0.0471323 -0.990435 + outer loop + vertex -887.38 447.304 1.00402 + vertex -884.091 445.974 0.510047 + vertex -890.659 438.16 0.998235 + endloop + endfacet + facet normal -0.130981 0.0439111 -0.990412 + outer loop + vertex -887.38 447.304 1.00402 + vertex -881.047 454.962 0.506 + vertex -884.091 445.974 0.510047 + endloop + endfacet + facet normal -0.135057 0.0473282 -0.989707 + outer loop + vertex -883.955 456.379 0.970543 + vertex -881.047 454.962 0.506 + vertex -887.38 447.304 1.00402 + endloop + endfacet + facet normal -0.136508 0.0443319 -0.989647 + outer loop + vertex -883.955 456.379 0.970543 + vertex -877.913 463.809 0.46997 + vertex -881.047 454.962 0.506 + endloop + endfacet + facet normal -0.141538 0.0484827 -0.988745 + outer loop + vertex -880.207 465.211 0.86718 + vertex -877.913 463.809 0.46997 + vertex -883.955 456.379 0.970543 + endloop + endfacet + facet normal -0.142241 0.047319 -0.9887 + outer loop + vertex -880.207 465.211 0.86718 + vertex -874.807 472.563 0.442128 + vertex -877.913 463.809 0.46997 + endloop + endfacet + facet normal -0.168845 0.0671698 -0.983351 + outer loop + vertex -877.186 473.496 0.914274 + vertex -874.807 472.563 0.442128 + vertex -880.207 465.211 0.86718 + endloop + endfacet + facet normal -0.172736 0.0572317 -0.983304 + outer loop + vertex -877.186 473.496 0.914274 + vertex -871.887 481.531 0.451159 + vertex -874.807 472.563 0.442128 + endloop + endfacet + facet normal -0.199034 0.0749294 -0.977124 + outer loop + vertex -874.079 482.42 0.965843 + vertex -871.887 481.531 0.451159 + vertex -877.186 473.496 0.914274 + endloop + endfacet + facet normal -0.209077 0.0498827 -0.976626 + outer loop + vertex -874.079 482.42 0.965843 + vertex -869.378 490.962 0.395619 + vertex -871.887 481.531 0.451159 + endloop + endfacet + facet normal -0.187661 0.037769 -0.981507 + outer loop + vertex -871.294 491.673 0.789366 + vertex -869.378 490.962 0.395619 + vertex -874.079 482.42 0.965843 + endloop + endfacet + facet normal -0.0793388 0.0253579 -0.996525 + outer loop + vertex -884.091 445.974 0.510047 + vertex -877.781 454 0.211885 + vertex -880.564 445.039 0.205472 + endloop + endfacet + facet normal -0.0816914 0.0272164 -0.996286 + outer loop + vertex -881.047 454.962 0.506 + vertex -877.781 454 0.211885 + vertex -884.091 445.974 0.510047 + endloop + endfacet + facet normal -0.0821476 0.0256672 -0.99629 + outer loop + vertex -881.047 454.962 0.506 + vertex -874.966 462.861 0.208064 + vertex -877.781 454 0.211885 + endloop + endfacet + facet normal -0.0395284 0.0121266 -0.999145 + outer loop + vertex -874.966 462.861 0.208064 + vertex -871.656 462.162 0.0686367 + vertex -877.781 454 0.211885 + endloop + endfacet + facet normal -0.0400818 0.0125424 -0.999118 + outer loop + vertex -877.781 454 0.211885 + vertex -871.656 462.162 0.0686367 + vertex -874.255 453.327 0.0619896 + endloop + endfacet + facet normal -0.0150565 0.00518133 -0.999873 + outer loop + vertex -871.656 462.162 0.0686367 + vertex -868.095 461.507 0.0116233 + vertex -874.255 453.327 0.0619896 + endloop + endfacet + facet normal -0.0151445 0.00470307 -0.999874 + outer loop + vertex -871.656 462.162 0.0686367 + vertex -865.679 470.224 0.0160261 + vertex -868.095 461.507 0.0116233 + endloop + endfacet + facet normal -0.00347312 0.00146781 -0.999993 + outer loop + vertex -865.679 470.224 0.0160261 + vertex -862.066 469.393 0.00225984 + vertex -868.095 461.507 0.0116233 + endloop + endfacet + facet normal -0.0034369 0.00144012 -0.999993 + outer loop + vertex -868.095 461.507 0.0116233 + vertex -862.066 469.393 0.00225984 + vertex -864.339 460.727 -0.00240966 + endloop + endfacet + facet normal -0.000765741 0.000739642 -0.999999 + outer loop + vertex -862.066 469.393 0.00225984 + vertex -858.274 468.409 -0.00137163 + vertex -864.339 460.727 -0.00240966 + endloop + endfacet + facet normal -0.000827323 0.000502342 -1 + outer loop + vertex -862.066 469.393 0.00225984 + vertex -856.329 477.103 0.0013866 + vertex -858.274 468.409 -0.00137163 + endloop + endfacet + facet normal -0.000479056 0.000424424 -1 + outer loop + vertex -856.329 477.103 0.0013866 + vertex -852.517 475.992 -0.000911235 + vertex -858.274 468.409 -0.00137163 + endloop + endfacet + facet normal -0.000579633 0.000500784 -1 + outer loop + vertex -858.274 468.409 -0.00137163 + vertex -852.517 475.992 -0.000911235 + vertex -854.358 467.318 -0.00418823 + endloop + endfacet + facet normal -0.00060271 0.000505681 -1 + outer loop + vertex -852.517 475.992 -0.000911235 + vertex -848.575 474.833 -0.00387321 + vertex -854.358 467.318 -0.00418823 + endloop + endfacet + facet normal -0.000603448 0.000503168 -1 + outer loop + vertex -852.517 475.992 -0.000911235 + vertex -847.491 483.831 -4.46642e-14 + vertex -848.575 474.833 -0.00387321 + endloop + endfacet + facet normal 0.000127204 0.000415139 -1 + outer loop + vertex -847.491 483.831 -4.46642e-14 + vertex -843.485 482.604 -4.48017e-14 + vertex -848.575 474.833 -0.00387321 + endloop + endfacet + facet normal -0.000230547 0.000649466 -1 + outer loop + vertex -848.575 474.833 -0.00387321 + vertex -843.485 482.604 -4.48017e-14 + vertex -844.6 473.665 -0.00554853 + endloop + endfacet + facet normal 0.000182009 0.000598031 -1 + outer loop + vertex -843.485 482.604 -4.48017e-14 + vertex -839.633 481.432 -4.50944e-14 + vertex -844.6 473.665 -0.00554853 + endloop + endfacet + facet normal 3.00021e-05 9.70051e-05 -1 + outer loop + vertex -851.435 485.051 -4.48057e-14 + vertex -847.491 483.831 -4.46642e-14 + vertex -852.517 475.992 -0.000911235 + endloop + endfacet + facet normal -0.000554159 0.000166787 -1 + outer loop + vertex -856.329 477.103 0.0013866 + vertex -851.435 485.051 -4.48057e-14 + vertex -852.517 475.992 -0.000911235 + endloop + endfacet + facet normal -4.57887e-05 -0.000146268 -1 + outer loop + vertex -854.941 486.149 -4.53053e-14 + vertex -851.435 485.051 -4.48057e-14 + vertex -856.329 477.103 0.0013866 + endloop + endfacet + facet normal -0.000451346 -8.40094e-05 -1 + outer loop + vertex -859.99 478.131 0.00295251 + vertex -854.941 486.149 -4.53053e-14 + vertex -856.329 477.103 0.0013866 + endloop + endfacet + facet normal -0.000324587 -0.000163839 -1 + outer loop + vertex -858.583 487.309 0.000992115 + vertex -854.941 486.149 -4.53053e-14 + vertex -859.99 478.131 0.00295251 + endloop + endfacet + facet normal -0.00291799 0.000233799 -0.999996 + outer loop + vertex -863.443 479.045 0.0132423 + vertex -858.583 487.309 0.000992115 + vertex -859.99 478.131 0.00295251 + endloop + endfacet + facet normal -0.00287081 0.000412039 -0.999996 + outer loop + vertex -863.443 479.045 0.0132423 + vertex -859.99 478.131 0.00295251 + vertex -865.679 470.224 0.0160261 + endloop + endfacet + facet normal -0.0137708 0.00317478 -0.9999 + outer loop + vertex -869.058 470.94 0.0648404 + vertex -863.443 479.045 0.0132423 + vertex -865.679 470.224 0.0160261 + endloop + endfacet + facet normal -0.0133346 0.00287255 -0.999907 + outer loop + vertex -866.599 479.866 0.0576936 + vertex -863.443 479.045 0.0132423 + vertex -869.058 470.94 0.0648404 + endloop + endfacet + facet normal -0.0381525 0.00970955 -0.999225 + outer loop + vertex -872.129 471.671 0.189211 + vertex -866.599 479.866 0.0576936 + vertex -869.058 470.94 0.0648404 + endloop + endfacet + facet normal -0.0380563 0.0101137 -0.999224 + outer loop + vertex -872.129 471.671 0.189211 + vertex -869.058 470.94 0.0648404 + vertex -874.966 462.861 0.208064 + endloop + endfacet + facet normal -0.0808641 0.0239011 -0.996439 + outer loop + vertex -877.913 463.809 0.46997 + vertex -872.129 471.671 0.189211 + vertex -874.966 462.861 0.208064 + endloop + endfacet + facet normal -0.0850767 0.0270152 -0.996008 + outer loop + vertex -874.807 472.563 0.442128 + vertex -872.129 471.671 0.189211 + vertex -877.913 463.809 0.46997 + endloop + endfacet + facet normal -0.0857822 0.0248942 -0.996003 + outer loop + vertex -874.807 472.563 0.442128 + vertex -869.417 480.673 0.180598 + vertex -872.129 471.671 0.189211 + endloop + endfacet + facet normal -0.0975661 0.0327684 -0.994689 + outer loop + vertex -871.887 481.531 0.451159 + vertex -869.417 480.673 0.180598 + vertex -874.807 472.563 0.442128 + endloop + endfacet + facet normal -0.100955 0.0229944 -0.994625 + outer loop + vertex -871.887 481.531 0.451159 + vertex -867.28 490.214 0.184242 + vertex -869.417 480.673 0.180598 + endloop + endfacet + facet normal -0.0426859 0.0099435 -0.999039 + outer loop + vertex -867.28 490.214 0.184242 + vertex -864.714 489.33 0.0658062 + vertex -869.417 480.673 0.180598 + endloop + endfacet + facet normal -0.0409964 0.00902459 -0.999119 + outer loop + vertex -869.417 480.673 0.180598 + vertex -864.714 489.33 0.0658062 + vertex -866.599 479.866 0.0576936 + endloop + endfacet + facet normal -0.0161697 0.00407873 -0.999861 + outer loop + vertex -864.714 489.33 0.0658062 + vertex -861.845 488.371 0.0155097 + vertex -866.599 479.866 0.0576936 + endloop + endfacet + facet normal -0.0935143 0.0190213 -0.995436 + outer loop + vertex -869.378 490.962 0.395619 + vertex -867.28 490.214 0.184242 + vertex -871.887 481.531 0.451159 + endloop + endfacet + facet normal -0.0403709 0.0112082 -0.999122 + outer loop + vertex -869.417 480.673 0.180598 + vertex -866.599 479.866 0.0576936 + vertex -872.129 471.671 0.189211 + endloop + endfacet + facet normal -0.0134205 0.00254195 -0.999907 + outer loop + vertex -866.599 479.866 0.0576936 + vertex -861.845 488.371 0.0155097 + vertex -863.443 479.045 0.0132423 + endloop + endfacet + facet normal -0.00413939 0.000952171 -0.999991 + outer loop + vertex -861.845 488.371 0.0155097 + vertex -858.583 487.309 0.000992115 + vertex -863.443 479.045 0.0132423 + endloop + endfacet + facet normal -0.00038015 0.000169607 -1 + outer loop + vertex -859.99 478.131 0.00295251 + vertex -856.329 477.103 0.0013866 + vertex -862.066 469.393 0.00225984 + endloop + endfacet + facet normal -0.00359599 0.000933794 -0.999993 + outer loop + vertex -865.679 470.224 0.0160261 + vertex -859.99 478.131 0.00295251 + vertex -862.066 469.393 0.00225984 + endloop + endfacet + facet normal -0.0136774 0.00361525 -0.9999 + outer loop + vertex -869.058 470.94 0.0648404 + vertex -865.679 470.224 0.0160261 + vertex -871.656 462.162 0.0686367 + endloop + endfacet + facet normal -0.0396995 0.0113165 -0.999148 + outer loop + vertex -874.966 462.861 0.208064 + vertex -869.058 470.94 0.0648404 + vertex -871.656 462.162 0.0686367 + endloop + endfacet + facet normal -0.080665 0.0245201 -0.99644 + outer loop + vertex -877.913 463.809 0.46997 + vertex -874.966 462.861 0.208064 + vertex -881.047 454.962 0.506 + endloop + endfacet + facet normal -0.0399693 0.0131306 -0.999115 + outer loop + vertex -877.781 454 0.211885 + vertex -874.255 453.327 0.0619896 + vertex -880.564 445.039 0.205472 + endloop + endfacet + facet normal -0.014195 0.00453254 -0.999889 + outer loop + vertex -874.255 453.327 0.0619896 + vertex -868.095 461.507 0.0116233 + vertex -870.528 452.718 0.00632378 + endloop + endfacet + facet normal -0.00341447 0.0015482 -0.999993 + outer loop + vertex -868.095 461.507 0.0116233 + vertex -864.339 460.727 -0.00240966 + vertex -870.528 452.718 0.00632378 + endloop + endfacet + facet normal -0.000368765 0.000426249 -1 + outer loop + vertex -864.339 460.727 -0.00240966 + vertex -858.274 468.409 -0.00137163 + vertex -860.436 459.784 -0.00425103 + endloop + endfacet + facet normal -0.00058528 0.000480507 -1 + outer loop + vertex -858.274 468.409 -0.00137163 + vertex -854.358 467.318 -0.00418823 + vertex -860.436 459.784 -0.00425103 + endloop + endfacet + facet normal -0.000457698 0.000394099 -1 + outer loop + vertex -854.358 467.318 -0.00418823 + vertex -848.575 474.833 -0.00387321 + vertex -850.374 466.19 -0.00645622 + endloop + endfacet + facet normal -0.000314375 0.000364273 -1 + outer loop + vertex -848.575 474.833 -0.00387321 + vertex -844.6 473.665 -0.00554853 + vertex -850.374 466.19 -0.00645622 + endloop + endfacet + facet normal 0.000208193 0.000581287 -1 + outer loop + vertex -844.6 473.665 -0.00554853 + vertex -839.633 481.432 -4.50944e-14 + vertex -840.65 472.482 -0.00541383 + endloop + endfacet + facet normal 0.000177079 0.000584822 -1 + outer loop + vertex -839.633 481.432 -4.50944e-14 + vertex -835.717 480.246 -4.54802e-14 + vertex -840.65 472.482 -0.00541383 + endloop + endfacet + facet normal 0.000319899 -5.7443e-05 -1 + outer loop + vertex -836.69 471.242 -0.00431377 + vertex -832.732 469.955 -0.00297358 + vertex -838.443 462.672 -0.00438229 + endloop + endfacet + facet normal 0.00037881 -6.94939e-05 -1 + outer loop + vertex -842.393 463.892 -0.00596336 + vertex -836.69 471.242 -0.00431377 + vertex -838.443 462.672 -0.00438229 + endloop + endfacet + facet normal 0.000206281 -0.000152618 -1 + outer loop + vertex -846.374 465.055 -0.00696212 + vertex -842.393 463.892 -0.00596336 + vertex -848.387 456.537 -0.00607734 + endloop + endfacet + facet normal 7.81513e-06 -0.000105719 -1 + outer loop + vertex -852.413 457.637 -0.00622509 + vertex -846.374 465.055 -0.00696212 + vertex -848.387 456.537 -0.00607734 + endloop + endfacet + facet normal -0.000258804 -4.78811e-05 -1 + outer loop + vertex -856.442 458.73 -0.00523474 + vertex -852.413 457.637 -0.00622509 + vertex -858.555 450.106 -0.004275 + endloop + endfacet + facet normal -3.17786e-05 -0.000103506 -1 + outer loop + vertex -862.625 451.113 -0.00424983 + vertex -856.442 458.73 -0.00523474 + vertex -858.555 450.106 -0.004275 + endloop + endfacet + facet normal 0.000146181 -0.000133357 -1 + outer loop + vertex -866.636 452.002 -0.00495482 + vertex -862.625 451.113 -0.00424983 + vertex -868.923 443.22 -0.00411789 + endloop + endfacet + facet normal -0.00188055 0.000394341 -0.999998 + outer loop + vertex -872.954 443.87 0.00371868 + vertex -866.636 452.002 -0.00495482 + vertex -868.923 443.22 -0.00411789 + endloop + endfacet + facet normal -0.0125946 0.00380425 -0.999913 + outer loop + vertex -876.843 444.409 0.0547637 + vertex -872.954 443.87 0.00371868 + vertex -879.408 435.444 0.0529624 + endloop + endfacet + facet normal -0.0354216 0.010335 -0.999319 + outer loop + vertex -883.323 436.004 0.197509 + vertex -876.843 444.409 0.0547637 + vertex -879.408 435.444 0.0529624 + endloop + endfacet + facet normal -0.0752283 0.0247671 -0.996859 + outer loop + vertex -887.082 436.897 0.503346 + vertex -883.323 436.004 0.197509 + vertex -890.031 427.763 0.499013 + endloop + endfacet + facet normal -0.115631 0.039434 -0.992509 + outer loop + vertex -893.873 428.999 0.995653 + vertex -890.031 427.763 0.499013 + vertex -897.038 419.749 0.996935 + endloop + endfacet + facet normal -0.0676089 0.0195003 -0.997521 + outer loop + vertex -892.925 418.575 0.501413 + vertex -886.042 426.936 0.198366 + vertex -888.7 417.831 0.200503 + endloop + endfacet + facet normal -0.0338605 0.00964901 -0.99938 + outer loop + vertex -886.042 426.936 0.198366 + vertex -881.931 426.452 0.0543919 + vertex -888.7 417.831 0.200503 + endloop + endfacet + facet normal -0.0109571 0.00259658 -0.999937 + outer loop + vertex -881.931 426.452 0.0543919 + vertex -875.353 434.981 0.00445679 + vertex -877.711 426.062 0.00713268 + endloop + endfacet + facet normal -0.00160665 0.000124707 -0.999999 + outer loop + vertex -875.353 434.981 0.00445679 + vertex -871.183 434.4 -0.00231439 + vertex -877.711 426.062 0.00713268 + endloop + endfacet + facet normal 0.000154027 -0.000180044 -1 + outer loop + vertex -871.183 434.4 -0.00231439 + vertex -864.802 442.393 -0.00277042 + vertex -866.956 433.632 -0.00152489 + endloop + endfacet + facet normal -9.28386e-05 -0.000119342 -1 + outer loop + vertex -864.802 442.393 -0.00277042 + vertex -860.655 441.438 -0.00304145 + vertex -866.956 433.632 -0.00152489 + endloop + endfacet + facet normal -0.000274499 -4.3759e-05 -1 + outer loop + vertex -860.655 441.438 -0.00304145 + vertex -854.478 449.056 -0.00507025 + vertex -856.531 440.434 -0.00412941 + endloop + endfacet + facet normal -1.31801e-05 -0.000105974 -1 + outer loop + vertex -854.478 449.056 -0.00507025 + vertex -850.425 447.997 -0.00501138 + vertex -856.531 440.434 -0.00412941 + endloop + endfacet + facet normal 0.000190239 -0.00014659 -1 + outer loop + vertex -850.425 447.997 -0.00501138 + vertex -844.386 455.414 -0.0049498 + vertex -846.408 446.918 -0.00408902 + endloop + endfacet + facet normal 0.00031674 -0.000176701 -1 + outer loop + vertex -844.386 455.414 -0.0049498 + vertex -840.426 454.238 -0.00348786 + vertex -846.408 446.918 -0.00408902 + endloop + endfacet + facet normal 0.000293987 -0.000144951 -1 + outer loop + vertex -840.426 454.238 -0.00348786 + vertex -834.526 461.403 -0.0027917 + vertex -836.5 453.005 -0.00215492 + endloop + endfacet + facet normal 0.000268935 -0.000139061 -1 + outer loop + vertex -834.526 461.403 -0.0027917 + vertex -830.572 460.126 -0.00155092 + vertex -836.5 453.005 -0.00215492 + endloop + endfacet + facet normal 0.00018501 -6.16311e-05 -1 + outer loop + vertex -830.572 460.126 -0.00155092 + vertex -824.68 467.507 -0.00091564 + vertex -826.517 458.953 -0.000728327 + endloop + endfacet + facet normal 0.000110181 -4.55601e-05 -1 + outer loop + vertex -824.68 467.507 -0.00091564 + vertex -820.424 466.469 -0.000399425 + vertex -826.517 458.953 -0.000728327 + endloop + endfacet + facet normal 6.12717e-05 9.9542e-06 -1 + outer loop + vertex -820.424 466.469 -0.000399425 + vertex -815.14 474.074 -4.72096e-14 + vertex -816.09 465.522 -0.000143317 + endloop + endfacet + facet normal 4.83949e-06 1.62205e-05 -1 + outer loop + vertex -815.14 474.074 -4.72096e-14 + vertex -811.036 472.85 -4.72355e-14 + vertex -816.09 465.522 -0.000143317 + endloop + endfacet + facet normal 4.75796e-06 -1.75732e-06 -1 + outer loop + vertex -813.835 456.009 -2.52825e-05 + vertex -807.99 463.224 -1.01536e-05 + vertex -810.031 454.917 -5.26593e-06 + endloop + endfacet + facet normal 1.49036e-05 -5.5017e-06 -1 + outer loop + vertex -818.034 456.995 -9.32965e-05 + vertex -811.878 464.485 -4.27538e-05 + vertex -813.835 456.009 -2.52825e-05 + endloop + endfacet + facet normal 4.02787e-05 -2.06634e-05 -1 + outer loop + vertex -822.318 457.928 -0.000285117 + vertex -818.034 456.995 -9.32965e-05 + vertex -824.508 449.471 -0.000198573 + endloop + endfacet + facet normal 7.08833e-05 -2.85889e-05 -1 + outer loop + vertex -828.589 450.561 -0.000518993 + vertex -822.318 457.928 -0.000285117 + vertex -824.508 449.471 -0.000198573 + endloop + endfacet + facet normal 0.000142216 -5.59383e-05 -1 + outer loop + vertex -832.572 451.757 -0.00115243 + vertex -828.589 450.561 -0.000518993 + vertex -834.592 443.409 -0.000972676 + endloop + endfacet + facet normal 0.000190862 -6.77071e-05 -1 + outer loop + vertex -838.501 444.619 -0.00180082 + vertex -832.572 451.757 -0.00115243 + vertex -834.592 443.409 -0.000972676 + endloop + endfacet + facet normal 0.000250694 -8.9751e-05 -1 + outer loop + vertex -842.433 445.797 -0.00289226 + vertex -838.501 444.619 -0.00180082 + vertex -844.443 437.321 -0.00263521 + endloop + endfacet + facet normal 0.000229025 -8.46149e-05 -1 + outer loop + vertex -848.425 438.388 -0.0036375 + vertex -842.433 445.797 -0.00289226 + vertex -844.443 437.321 -0.00263521 + endloop + endfacet + facet normal 0.000153962 -7.28519e-05 -1 + outer loop + vertex -852.453 439.419 -0.00433288 + vertex -848.425 438.388 -0.0036375 + vertex -854.469 430.813 -0.00401613 + endloop + endfacet + facet normal -9.60563e-05 -1.43131e-05 -1 + outer loop + vertex -858.566 431.781 -0.00363639 + vertex -852.453 439.419 -0.00433288 + vertex -854.469 430.813 -0.00401613 + endloop + endfacet + facet normal -0.000322315 3.81932e-05 -1 + outer loop + vertex -862.734 432.735 -0.00225672 + vertex -858.566 431.781 -0.00363639 + vertex -864.787 424.008 -0.00192838 + endloop + endfacet + facet normal -0.000241672 1.92244e-05 -1 + outer loop + vertex -869.079 424.846 -0.000874878 + vertex -862.734 432.735 -0.00225672 + vertex -864.787 424.008 -0.00192838 + endloop + endfacet + facet normal 1.31639e-05 -6.72784e-05 -1 + outer loop + vertex -873.408 425.55 -0.000979222 + vertex -869.079 424.846 -0.000874878 + vertex -875.588 416.667 -0.000410306 + endloop + endfacet + facet normal -0.00192955 0.000409465 -0.999998 + outer loop + vertex -880.016 417.112 0.00831606 + vertex -873.408 425.55 -0.000979222 + vertex -875.588 416.667 -0.000410306 + endloop + endfacet + facet normal -0.0109487 0.00286425 -0.999936 + outer loop + vertex -884.394 417.427 0.0571574 + vertex -880.016 417.112 0.00831606 + vertex -886.784 408.353 0.0573326 + endloop + endfacet + facet normal -0.0316454 0.00831519 -0.999465 + outer loop + vertex -891.276 408.68 0.202262 + vertex -884.394 417.427 0.0571574 + vertex -886.784 408.353 0.0573326 + endloop + endfacet + facet normal -0.0641001 0.0188268 -0.997766 + outer loop + vertex -895.731 409.332 0.500761 + vertex -891.276 408.68 0.202262 + vertex -898.421 400.044 0.498376 + endloop + endfacet + facet normal -0.0987679 0.0298553 -0.994663 + outer loop + vertex -903.08 401.014 0.990029 + vertex -898.421 400.044 0.498376 + vertex -905.887 391.592 0.986024 + endloop + endfacet + facet normal -0.0588436 0.0149619 -0.998155 + outer loop + vertex -900.985 390.672 0.495809 + vertex -893.751 399.466 0.201116 + vertex -896.111 390.165 0.200819 + endloop + endfacet + facet normal -0.0301359 0.00767812 -0.999516 + outer loop + vertex -893.751 399.466 0.201116 + vertex -889.086 399.212 0.0585258 + vertex -896.111 390.165 0.200819 + endloop + endfacet + facet normal -0.0103658 0.00237128 -0.999943 + outer loop + vertex -889.086 399.212 0.0585258 + vertex -882.258 408.111 0.00884213 + vertex -884.419 399.039 0.00973596 + endloop + endfacet + facet normal -0.00194498 0.000364894 -0.999998 + outer loop + vertex -882.258 408.111 0.00884213 + vertex -877.71 407.735 -0.000139566 + vertex -884.419 399.039 0.00973596 + endloop + endfacet + facet normal -0.000111525 2.47018e-05 -1 + outer loop + vertex -877.71 407.735 -0.000139566 + vertex -871.163 416.029 -0.000664913 + vertex -873.193 407.166 -0.000657469 + endloop + endfacet + facet normal -0.000260019 5.87105e-05 -1 + outer loop + vertex -871.163 416.029 -0.000664913 + vertex -866.802 415.254 -0.00184418 + vertex -873.193 407.166 -0.000657469 + endloop + endfacet + facet normal -0.000352288 7.4375e-05 -1 + outer loop + vertex -866.802 415.254 -0.00184418 + vertex -860.578 423.108 -0.0034529 + vertex -862.555 414.407 -0.00340325 + endloop + endfacet + facet normal -0.00011015 1.93327e-05 -1 + outer loop + vertex -860.578 423.108 -0.0034529 + vertex -856.462 422.189 -0.00392403 + vertex -862.555 414.407 -0.00340325 + endloop + endfacet + facet normal 0.000117325 -3.29154e-05 -1 + outer loop + vertex -856.462 422.189 -0.00392403 + vertex -850.433 429.831 -0.00346821 + vertex -852.424 421.254 -0.00341952 + endloop + endfacet + facet normal 0.000215557 -5.57206e-05 -1 + outer loop + vertex -850.433 429.831 -0.00346821 + vertex -846.449 428.819 -0.0025531 + vertex -852.424 421.254 -0.00341952 + endloop + endfacet + facet normal 0.000215989 -5.53474e-05 -1 + outer loop + vertex -846.449 428.819 -0.0025531 + vertex -840.505 436.207 -0.00167817 + vertex -842.509 427.769 -0.00164413 + endloop + endfacet + facet normal 0.000180666 -4.69557e-05 -1 + outer loop + vertex -840.505 436.207 -0.00167817 + vertex -836.603 435.056 -0.000919155 + vertex -842.509 427.769 -0.00164413 + endloop + endfacet + facet normal 0.000116711 -3.05436e-05 -1 + outer loop + vertex -836.603 435.056 -0.000919155 + vertex -830.67 442.212 -0.000445262 + vertex -832.719 433.887 -0.000430212 + endloop + endfacet + facet normal 6.41759e-05 -1.76088e-05 -1 + outer loop + vertex -830.67 442.212 -0.000445262 + vertex -826.704 441.065 -0.000170577 + vertex -832.719 433.887 -0.000430212 + endloop + endfacet + facet normal 2.64205e-05 -7.98058e-06 -1 + outer loop + vertex -826.704 441.065 -0.000170577 + vertex -820.353 448.459 -6.1792e-05 + vertex -822.687 439.973 -5.57222e-05 + endloop + endfacet + facet normal 9.39666e-06 -2.85403e-06 -1 + outer loop + vertex -822.687 439.973 -5.57222e-05 + vertex -816.214 447.471 -1.63004e-05 + vertex -818.679 438.917 -1.50443e-05 + endloop + endfacet + facet normal 2.92935e-06 -9.02999e-07 -1 + outer loop + vertex -818.679 438.917 -1.50443e-05 + vertex -812.468 446.432 -3.6356e-06 + vertex -814.966 437.93 -3.2786e-06 + endloop + endfacet + facet normal 1.0498e-06 -2.9446e-07 -1 + outer loop + vertex -814.966 437.93 -3.2786e-06 + vertex -809.77 445.321 -2.08073e-13 + vertex -811.99 437.406 -2.28185e-13 + endloop + endfacet + facet normal 2.86867e-06 -7.89422e-07 -1 + outer loop + vertex -823.28 422.192 -1.43141e-05 + vertex -817.389 429.526 -3.20522e-06 + vertex -819.678 421.231 -3.22326e-06 + endloop + endfacet + facet normal 9.73747e-06 -2.6006e-06 -1 + outer loop + vertex -827.08 423.307 -5.4222e-05 + vertex -821.054 430.473 -1.41807e-05 + vertex -823.28 422.192 -1.43141e-05 + endloop + endfacet + facet normal 2.70408e-05 -7.01389e-06 -1 + outer loop + vertex -830.909 424.441 -0.000165709 + vertex -824.937 431.584 -5.43274e-05 + vertex -827.08 423.307 -5.4222e-05 + endloop + endfacet + facet normal 6.28512e-05 -1.5943e-05 -1 + outer loop + vertex -834.748 425.57 -0.000424985 + vertex -828.836 432.725 -0.000167521 + vertex -830.909 424.441 -0.000165709 + endloop + endfacet + facet normal 0.000117684 -2.85263e-05 -1 + outer loop + vertex -838.611 426.683 -0.00091138 + vertex -834.748 425.57 -0.000424985 + vertex -840.615 418.287 -0.000907686 + endloop + endfacet + facet normal 0.000176066 -4.24597e-05 -1 + outer loop + vertex -844.508 419.306 -0.0016365 + vertex -838.611 426.683 -0.00091138 + vertex -840.615 418.287 -0.000907686 + endloop + endfacet + facet normal 0.000215244 -4.98939e-05 -1 + outer loop + vertex -848.444 420.295 -0.0025329 + vertex -844.508 419.306 -0.0016365 + vertex -850.411 411.743 -0.00252962 + endloop + endfacet + facet normal 0.000210617 -4.88294e-05 -1 + outer loop + vertex -854.383 412.654 -0.00341075 + vertex -848.444 420.295 -0.0025329 + vertex -850.411 411.743 -0.00252962 + endloop + endfacet + facet normal 0.000113455 -2.33975e-05 -1 + outer loop + vertex -858.423 413.539 -0.00388976 + vertex -854.383 412.654 -0.00341075 + vertex -860.332 404.854 -0.00390317 + endloop + endfacet + facet normal -0.000109082 2.55239e-05 -1 + outer loop + vertex -864.482 405.667 -0.00342976 + vertex -858.423 413.539 -0.00388976 + vertex -860.332 404.854 -0.00390317 + endloop + endfacet + facet normal -0.000342399 8.2128e-05 -1 + outer loop + vertex -868.769 406.451 -0.00189736 + vertex -864.482 405.667 -0.00342976 + vertex -870.665 397.592 -0.00197564 + endloop + endfacet + facet normal -0.000266916 6.59704e-05 -1 + outer loop + vertex -875.151 398.239 -0.000735543 + vertex -868.769 406.451 -0.00189736 + vertex -870.665 397.592 -0.00197564 + endloop + endfacet + facet normal -0.000151262 1.67152e-05 -1 + outer loop + vertex -879.758 398.739 -3.04423e-05 + vertex -875.151 398.239 -0.000735543 + vertex -881.713 389.661 0.000113579 + endloop + endfacet + facet normal -0.00214324 0.000445773 -0.999998 + outer loop + vertex -886.482 389.889 0.0104362 + vertex -879.758 398.739 -3.04423e-05 + vertex -881.713 389.661 0.000113579 + endloop + endfacet + facet normal -0.0101932 0.00198557 -0.999946 + outer loop + vertex -891.282 389.986 0.0595581 + vertex -886.482 389.889 0.0104362 + vertex -893.35 380.677 0.0621508 + endloop + endfacet + facet normal -0.0281281 0.00596927 -0.999587 + outer loop + vertex -898.334 380.771 0.202981 + vertex -891.282 389.986 0.0595581 + vertex -893.35 380.677 0.0621508 + endloop + endfacet + facet normal -0.056479 0.0136827 -0.99831 + outer loop + vertex -903.406 381.184 0.495559 + vertex -898.334 380.771 0.202981 + vertex -905.644 371.597 0.490786 + endloop + endfacet + facet normal -0.0877969 0.0212308 -0.995912 + outer loop + vertex -911.021 372.278 0.979355 + vertex -905.644 371.597 0.490786 + vertex -913.244 362.502 0.966903 + endloop + endfacet + facet normal -0.051957 0.00973376 -0.998602 + outer loop + vertex -907.665 361.972 0.49175 + vertex -900.39 371.301 0.204182 + vertex -902.247 361.799 0.20816 + endloop + endfacet + facet normal -0.027331 0.00492171 -0.999614 + outer loop + vertex -900.39 371.301 0.204182 + vertex -895.262 371.305 0.0639983 + vertex -902.247 361.799 0.20816 + endloop + endfacet + facet normal -0.0103708 0.00194843 -0.999944 + outer loop + vertex -895.262 371.305 0.0639983 + vertex -888.425 380.661 0.0113127 + vertex -890.224 371.377 0.0118798 + endloop + endfacet + facet normal -0.00229714 0.000384027 -0.999997 + outer loop + vertex -888.425 380.661 0.0113127 + vertex -883.555 380.515 6.98469e-05 + vertex -890.224 371.377 0.0118798 + endloop + endfacet + facet normal -0.000225612 6.22715e-05 -1 + outer loop + vertex -883.555 380.515 6.98469e-05 + vertex -877.022 389.238 -0.000860822 + vertex -878.786 380.165 -0.00102773 + endloop + endfacet + facet normal -0.000255342 6.80533e-05 -1 + outer loop + vertex -877.022 389.238 -0.000860822 + vertex -872.476 388.662 -0.00206093 + vertex -878.786 380.165 -0.00102773 + endloop + endfacet + facet normal -0.000317885 6.63523e-05 -1 + outer loop + vertex -872.476 388.662 -0.00206093 + vertex -866.34 396.87 -0.0034667 + vertex -868.115 388.001 -0.00349094 + endloop + endfacet + facet normal -0.000100943 2.29353e-05 -1 + outer loop + vertex -866.34 396.87 -0.0034667 + vertex -862.174 396.111 -0.00390464 + vertex -868.115 388.001 -0.00349094 + endloop + endfacet + facet normal 0.000118312 -2.47639e-05 -1 + outer loop + vertex -862.174 396.111 -0.00390464 + vertex -856.293 404.016 -0.00340454 + vertex -858.133 395.327 -0.00340706 + endloop + endfacet + facet normal 0.000211489 -4.44951e-05 -1 + outer loop + vertex -856.293 404.016 -0.00340454 + vertex -852.33 403.156 -0.00252827 + vertex -858.133 395.327 -0.00340706 + endloop + endfacet + facet normal 0.000217505 -4.93818e-05 -1 + outer loop + vertex -852.33 403.156 -0.00252827 + vertex -846.487 410.81 -0.00163531 + vertex -848.423 402.271 -0.00163467 + endloop + endfacet + facet normal 0.000177069 -4.02155e-05 -1 + outer loop + vertex -846.487 410.81 -0.00163531 + vertex -842.604 409.851 -0.000909288 + vertex -848.423 402.271 -0.00163467 + endloop + endfacet + facet normal 0.000118494 -2.82155e-05 -1 + outer loop + vertex -842.604 409.851 -0.000909288 + vertex -836.761 417.242 -0.000425362 + vertex -838.762 408.873 -0.000426327 + endloop + endfacet + facet normal 6.42267e-05 -1.56546e-05 -1 + outer loop + vertex -838.762 408.873 -0.000426327 + vertex -832.941 416.174 -0.000166784 + vertex -834.955 407.875 -0.000166247 + endloop + endfacet + facet normal 2.79093e-05 -6.92712e-06 -1 + outer loop + vertex -834.955 407.875 -0.000166247 + vertex -829.146 415.09 -5.40942e-05 + vertex -831.179 406.86 -5.38151e-05 + endloop + endfacet + facet normal 9.83778e-06 -2.49674e-06 -1 + outer loop + vertex -831.179 406.86 -5.38151e-05 + vertex -825.391 414.017 -1.47449e-05 + vertex -827.45 405.852 -1.46171e-05 + endloop + endfacet + facet normal 3.04796e-06 -7.94122e-07 -1 + outer loop + vertex -827.45 405.852 -1.46171e-05 + vertex -821.851 413.088 -3.29641e-06 + vertex -823.95 405.001 -3.27161e-06 + endloop + endfacet + facet normal 1.11827e-06 -3.06822e-07 -1 + outer loop + vertex -823.95 405.001 -3.27161e-06 + vertex -818.936 412.61 -2.42478e-13 + vertex -821.094 404.747 -2.38096e-13 + endloop + endfacet + facet normal 3.16794e-06 -7.68817e-07 -1 + outer loop + vertex -831.496 389.283 -1.46843e-05 + vertex -826.04 396.779 -3.16116e-06 + vertex -828.096 388.472 -3.28837e-06 + endloop + endfacet + facet normal 1.01136e-05 -2.44695e-06 -1 + outer loop + vertex -835.168 390.173 -5.39962e-05 + vertex -829.494 397.616 -1.48227e-05 + vertex -831.496 389.283 -1.46843e-05 + endloop + endfacet + facet normal 2.84208e-05 -6.72646e-06 -1 + outer loop + vertex -838.895 391.067 -0.00016593 + vertex -833.194 398.558 -5.42935e-05 + vertex -835.168 390.173 -5.39962e-05 + endloop + endfacet + facet normal 6.49631e-05 -1.4978e-05 -1 + outer loop + vertex -842.654 391.952 -0.000423371 + vertex -836.95 399.508 -0.000165992 + vertex -838.895 391.067 -0.00016593 + endloop + endfacet + facet normal 0.000121606 -2.76879e-05 -1 + outer loop + vertex -846.449 392.823 -0.000909069 + vertex -840.736 400.445 -0.000425283 + vertex -842.654 391.952 -0.000423371 + endloop + endfacet + facet normal 0.000180384 -3.98573e-05 -1 + outer loop + vertex -850.29 393.679 -0.00163597 + vertex -844.559 401.366 -0.000908529 + vertex -846.449 392.823 -0.000909069 + endloop + endfacet + facet normal 0.000219919 -4.44772e-05 -1 + outer loop + vertex -854.18 394.516 -0.00252867 + vertex -850.29 393.679 -0.00163597 + vertex -855.941 385.817 -0.00252905 + endloop + endfacet + facet normal 0.000214879 -4.34568e-05 -1 + outer loop + vertex -859.886 386.576 -0.00340969 + vertex -854.18 394.516 -0.00252867 + vertex -855.941 385.817 -0.00252905 + endloop + endfacet + facet normal 0.000121842 -2.28662e-05 -1 + outer loop + vertex -863.93 387.305 -0.00391911 + vertex -859.886 386.576 -0.00340969 + vertex -865.583 378.437 -0.00391769 + endloop + endfacet + facet normal -9.12046e-05 1.68347e-05 -1 + outer loop + vertex -869.785 379.073 -0.00352371 + vertex -863.93 387.305 -0.00391911 + vertex -865.583 378.437 -0.00391769 + endloop + endfacet + facet normal -0.000304338 5.98122e-05 -1 + outer loop + vertex -874.183 379.663 -0.00214994 + vertex -869.785 379.073 -0.00352371 + vertex -875.764 370.622 -0.00220954 + endloop + endfacet + facet normal -0.000219737 4.5018e-05 -1 + outer loop + vertex -880.419 371.05 -0.00116725 + vertex -874.183 379.663 -0.00214994 + vertex -875.764 370.622 -0.00220954 + endloop + endfacet + facet normal -0.000239626 6.35813e-05 -1 + outer loop + vertex -885.262 371.314 9.90328e-06 + vertex -880.419 371.05 -0.00116725 + vertex -886.808 362.098 -0.000205639 + endloop + endfacet + facet normal -0.00241469 0.000428414 -0.999997 + outer loop + vertex -891.852 362.069 0.0119616 + vertex -885.262 371.314 9.90328e-06 + vertex -886.808 362.098 -0.000205639 + endloop + endfacet + facet normal -0.0104373 0.00155497 -0.999944 + outer loop + vertex -896.991 361.903 0.0653464 + vertex -891.852 362.069 0.0119616 + vertex -898.502 352.494 0.0664911 + endloop + endfacet + facet normal -0.0268704 0.00419479 -0.99963 + outer loop + vertex -903.866 352.285 0.209797 + vertex -896.991 361.903 0.0653464 + vertex -898.502 352.494 0.0664911 + endloop + endfacet + facet normal -0.0507052 0.00729682 -0.998687 + outer loop + vertex -909.427 352.34 0.492553 + vertex -903.866 352.285 0.209797 + vertex -910.892 342.708 0.496512 + endloop + endfacet + facet normal -0.0773594 0.00958102 -0.996957 + outer loop + vertex -916.814 342.972 0.958591 + vertex -910.892 342.708 0.496512 + vertex -918.066 333.189 0.961726 + endloop + endfacet + facet normal -0.0494394 0.00534772 -0.998763 + outer loop + vertex -912.01 333.04 0.496552 + vertex -905.211 342.765 0.212087 + vertex -906.237 333.226 0.211788 + endloop + endfacet + facet normal -0.0267774 0.0029108 -0.999637 + outer loop + vertex -905.211 342.765 0.212087 + vertex -899.76 343.082 0.0669975 + vertex -906.237 333.226 0.211788 + endloop + endfacet + facet normal -0.0104683 0.00133979 -0.999944 + outer loop + vertex -899.76 343.082 0.0669975 + vertex -893.278 352.758 0.0121019 + vertex -894.47 343.45 0.0121021 + endloop + endfacet + facet normal -0.00242452 0.000310288 -0.999997 + outer loop + vertex -893.278 352.758 0.0121019 + vertex -888.164 352.88 -0.000259262 + vertex -894.47 343.45 0.0121021 + endloop + endfacet + facet normal -0.000214184 3.71365e-05 -1 + outer loop + vertex -888.164 352.88 -0.000259262 + vertex -881.899 361.919 -0.00126546 + vertex -883.199 352.792 -0.00132609 + endloop + endfacet + facet normal -0.000204233 3.57197e-05 -1 + outer loop + vertex -881.899 361.919 -0.00126546 + vertex -877.194 361.571 -0.00223884 + vertex -883.199 352.792 -0.00132609 + endloop + endfacet + facet normal -0.000288042 4.68707e-05 -1 + outer loop + vertex -877.194 361.571 -0.00223884 + vertex -871.332 370.102 -0.00352756 + vertex -872.73 361.125 -0.00354568 + endloop + endfacet + facet normal -9.33716e-05 1.65578e-05 -1 + outer loop + vertex -871.332 370.102 -0.00352756 + vertex -867.11 369.534 -0.00393116 + vertex -872.73 361.125 -0.00354568 + endloop + endfacet + facet normal 0.000125158 -2.13132e-05 -1 + outer loop + vertex -867.11 369.534 -0.00393116 + vertex -861.533 377.767 -0.0034086 + vertex -863.055 368.924 -0.00341057 + endloop + endfacet + facet normal 0.000216039 -3.69511e-05 -1 + outer loop + vertex -861.533 377.767 -0.0034086 + vertex -857.594 377.065 -0.00253169 + vertex -863.055 368.924 -0.00341057 + endloop + endfacet + facet normal 0.000224069 -4.29502e-05 -1 + outer loop + vertex -857.594 377.065 -0.00253169 + vertex -852.067 385.03 -0.00163549 + vertex -853.733 376.331 -0.00163514 + endloop + endfacet + facet normal 0.000183914 -3.55652e-05 -1 + outer loop + vertex -853.733 376.331 -0.00163514 + vertex -848.25 384.222 -0.000907325 + vertex -849.934 375.572 -0.000909367 + endloop + endfacet + facet normal 0.000123687 -2.4328e-05 -1 + outer loop + vertex -849.934 375.572 -0.000909367 + vertex -844.48 383.397 -0.0004252 + vertex -846.187 374.796 -0.00042711 + endloop + endfacet + facet normal 6.80083e-05 -1.38728e-05 -1 + outer loop + vertex -846.187 374.796 -0.00042711 + vertex -840.753 382.561 -0.000165246 + vertex -842.49 374.009 -0.000164745 + endloop + endfacet + facet normal 2.89965e-05 -6.04676e-06 -1 + outer loop + vertex -842.49 374.009 -0.000164745 + vertex -837.059 381.716 -5.38582e-05 + vertex -838.828 373.209 -5.37187e-05 + endloop + endfacet + facet normal 1.03682e-05 -2.2162e-06 -1 + outer loop + vertex -838.828 373.209 -5.37187e-05 + vertex -833.422 380.873 -1.46559e-05 + vertex -835.225 372.413 -1.45972e-05 + endloop + endfacet + facet normal 3.243e-06 -7.0522e-07 -1 + outer loop + vertex -835.225 372.413 -1.45972e-05 + vertex -830.046 380.126 -3.24053e-06 + vertex -831.881 371.728 -3.26843e-06 + endloop + endfacet + facet normal 1.21641e-06 -2.70183e-07 -1 + outer loop + vertex -831.881 371.728 -3.26843e-06 + vertex -827.439 379.627 -2.11934e-13 + vertex -829.242 371.51 -2.01137e-13 + endloop + endfacet + facet normal 3.43963e-06 -6.32079e-07 -1 + outer loop + vertex -838.336 355.463 -1.47805e-05 + vertex -833.557 363.3 -3.29376e-06 + vertex -835.042 354.853 -3.06385e-06 + endloop + endfacet + facet normal 1.06814e-05 -1.83911e-06 -1 + outer loop + vertex -841.883 356.158 -5.3947e-05 + vertex -836.872 363.933 -1.47134e-05 + vertex -838.336 355.463 -1.47805e-05 + endloop + endfacet + facet normal 2.99862e-05 -5.10998e-06 -1 + outer loop + vertex -845.498 356.86 -0.000165924 + vertex -840.444 364.68 -5.43134e-05 + vertex -841.883 356.158 -5.3947e-05 + endloop + endfacet + facet normal 6.82106e-05 -1.13546e-05 -1 + outer loop + vertex -849.159 357.549 -0.000423458 + vertex -844.079 365.432 -0.000166443 + vertex -845.498 356.86 -0.000165924 + endloop + endfacet + facet normal 0.000127297 -2.09199e-05 -1 + outer loop + vertex -852.87 358.219 -0.000909881 + vertex -847.756 366.172 -0.000425228 + vertex -849.159 357.549 -0.000423458 + endloop + endfacet + facet normal 0.000187117 -2.95928e-05 -1 + outer loop + vertex -856.645 358.869 -0.00163543 + vertex -851.483 366.896 -0.000907116 + vertex -852.87 358.219 -0.000909881 + endloop + endfacet + facet normal 0.000226607 -3.59841e-05 -1 + outer loop + vertex -860.49 359.49 -0.0025292 + vertex -855.266 367.6 -0.0016371 + vertex -856.645 358.869 -0.00163543 + endloop + endfacet + facet normal 0.000218495 -3.44005e-05 -1 + outer loop + vertex -864.427 360.076 -0.00340959 + vertex -859.119 368.28 -0.00253183 + vertex -860.49 359.49 -0.0025292 + endloop + endfacet + facet normal 0.000124471 -1.7379e-05 -1 + outer loop + vertex -868.491 360.622 -0.00392486 + vertex -864.427 360.076 -0.00340959 + vertex -869.698 351.725 -0.00392044 + endloop + endfacet + facet normal -8.82979e-05 1.14795e-05 -1 + outer loop + vertex -873.955 352.157 -0.00353957 + vertex -868.491 360.622 -0.00392486 + vertex -869.698 351.725 -0.00392044 + endloop + endfacet + facet normal -0.000282346 3.26407e-05 -1 + outer loop + vertex -878.45 352.527 -0.00225846 + vertex -873.955 352.157 -0.00353957 + vertex -879.499 343.502 -0.00225676 + endloop + endfacet + facet normal -0.000185801 2.14153e-05 -1 + outer loop + vertex -884.287 343.678 -0.00136344 + vertex -878.45 352.527 -0.00225846 + vertex -879.499 343.502 -0.00225676 + endloop + endfacet + facet normal -0.000196179 3.31101e-05 -1 + outer loop + vertex -889.3 343.674 -0.00038006 + vertex -884.287 343.678 -0.00136344 + vertex -890.18 334.483 -0.000511741 + endloop + endfacet + facet normal -0.00238084 0.000242279 -0.999997 + outer loop + vertex -895.389 334.151 0.0118092 + vertex -889.3 343.674 -0.00038006 + vertex -890.18 334.483 -0.000511741 + endloop + endfacet + facet normal -0.0102517 0.000616557 -0.999947 + outer loop + vertex -900.725 333.668 0.0662244 + vertex -895.389 334.151 0.0118092 + vertex -901.346 324.278 0.0667943 + endloop + endfacet + facet normal -0.0263006 0.00167682 -0.999653 + outer loop + vertex -906.892 323.697 0.211732 + vertex -900.725 333.668 0.0662244 + vertex -901.346 324.278 0.0667943 + endloop + endfacet + facet normal -0.0489629 0.00113831 -0.9988 + outer loop + vertex -912.725 323.348 0.497315 + vertex -906.892 323.697 0.211732 + vertex -912.972 313.715 0.498445 + endloop + endfacet + facet normal -0.0740542 -0.00217821 -0.997252 + outer loop + vertex -919.201 313.453 0.961553 + vertex -912.972 313.715 0.498445 + vertex -918.935 303.754 0.962977 + endloop + endfacet + facet normal -0.0484592 -0.00157244 -0.998824 + outer loop + vertex -912.691 304.219 0.496725 + vertex -907.118 314.241 0.210546 + vertex -906.848 304.917 0.21213 + endloop + endfacet + facet normal -0.0258121 -0.000917024 -0.999666 + outer loop + vertex -907.118 314.241 0.210546 + vertex -901.568 314.972 0.0665892 + vertex -906.848 304.917 0.21213 + endloop + endfacet + facet normal -0.010375 0.000240777 -0.999946 + outer loop + vertex -901.568 314.972 0.0665892 + vertex -895.991 324.888 0.0111069 + vertex -896.219 315.716 0.011263 + endloop + endfacet + facet normal -0.00222574 3.82816e-05 -0.999998 + outer loop + vertex -895.991 324.888 0.0111069 + vertex -890.759 325.334 -0.000521252 + vertex -896.219 315.716 0.011263 + endloop + endfacet + facet normal -0.000166335 9.95775e-06 -1 + outer loop + vertex -890.759 325.334 -0.000521252 + vertex -885.129 334.588 -0.00136552 + vertex -885.685 325.547 -0.00136309 + endloop + endfacet + facet normal -0.000185592 1.11417e-05 -1 + outer loop + vertex -885.129 334.588 -0.00136552 + vertex -880.31 334.503 -0.00226085 + vertex -885.685 325.547 -0.00136309 + endloop + endfacet + facet normal -0.000282038 2.56422e-05 -1 + outer loop + vertex -880.31 334.503 -0.00226085 + vertex -874.977 343.212 -0.00354176 + vertex -875.764 334.295 -0.00354836 + endloop + endfacet + facet normal -8.88984e-05 8.58944e-06 -1 + outer loop + vertex -874.977 343.212 -0.00354176 + vertex -870.702 342.851 -0.0039249 + vertex -875.764 334.295 -0.00354836 + endloop + endfacet + facet normal 0.000124686 -1.39907e-05 -1 + outer loop + vertex -870.702 342.851 -0.0039249 + vertex -865.625 351.244 -0.00340935 + vertex -866.619 342.436 -0.00340999 + endloop + endfacet + facet normal 0.000220424 -2.49066e-05 -1 + outer loop + vertex -866.619 342.436 -0.00340999 + vertex -861.685 350.719 -0.00252889 + vertex -862.674 341.974 -0.0025289 + endloop + endfacet + facet normal 0.000229107 -2.60765e-05 -1 + outer loop + vertex -862.674 341.974 -0.0025289 + vertex -857.842 350.156 -0.00163527 + vertex -858.828 341.471 -0.00163463 + endloop + endfacet + facet normal 0.00018938 -2.1376e-05 -1 + outer loop + vertex -858.828 341.471 -0.00163463 + vertex -854.074 349.564 -0.000907337 + vertex -855.058 340.936 -0.000909231 + endloop + endfacet + facet normal 0.000128112 -1.45606e-05 -1 + outer loop + vertex -855.058 340.936 -0.000909231 + vertex -850.368 348.947 -0.000425127 + vertex -851.354 340.375 -0.00042653 + endloop + endfacet + facet normal 7.00538e-05 -7.91641e-06 -1 + outer loop + vertex -851.354 340.375 -0.00042653 + vertex -846.72 348.313 -0.000164761 + vertex -847.708 339.795 -0.00016653 + endloop + endfacet + facet normal 3.06101e-05 -3.52163e-06 -1 + outer loop + vertex -847.708 339.795 -0.00016653 + vertex -843.118 347.664 -5.37466e-05 + vertex -844.112 339.199 -5.437e-05 + endloop + endfacet + facet normal 1.11352e-05 -1.3701e-06 -1 + outer loop + vertex -844.112 339.199 -5.437e-05 + vertex -839.587 347.018 -1.46927e-05 + vertex -840.592 338.599 -1.43561e-05 + endloop + endfacet + facet normal 3.33963e-06 -4.06461e-07 -1 + outer loop + vertex -840.592 338.599 -1.43561e-05 + vertex -836.312 346.465 -3.25937e-06 + vertex -837.328 338.089 -3.24869e-06 + endloop + endfacet + facet normal 1.27018e-06 -1.57019e-07 -1 + outer loop + vertex -837.328 338.089 -3.24869e-06 + vertex -833.761 346.261 -1.64318e-13 + vertex -834.806 337.802 -1.51602e-13 + endloop + endfacet + facet normal 3.46085e-06 -1.63444e-07 -1 + outer loop + vertex -841.716 321.914 -1.46249e-05 + vertex -838.057 329.773 -3.24493e-06 + vertex -838.453 321.526 -3.26742e-06 + endloop + endfacet + facet normal 1.08776e-05 -5.32116e-07 -1 + outer loop + vertex -845.24 322.412 -5.32229e-05 + vertex -841.317 330.22 -1.4697e-05 + vertex -841.716 321.914 -1.46249e-05 + endloop + endfacet + facet normal 3.13085e-05 -1.61294e-06 -1 + outer loop + vertex -848.841 322.907 -0.000166764 + vertex -844.835 330.771 -5.40118e-05 + vertex -845.24 322.412 -5.32229e-05 + endloop + endfacet + facet normal 7.03163e-05 -3.2836e-06 -1 + outer loop + vertex -852.506 323.378 -0.000425987 + vertex -848.432 331.317 -0.000165594 + vertex -848.841 322.907 -0.000166764 + endloop + endfacet + facet normal 0.000129242 -6.1607e-06 -1 + outer loop + vertex -856.228 323.824 -0.000909781 + vertex -852.084 331.842 -0.000423583 + vertex -852.506 323.378 -0.000425987 + endloop + endfacet + facet normal 0.000190093 -9.45304e-06 -1 + outer loop + vertex -860.019 324.241 -0.00163428 + vertex -855.792 332.345 -0.000907447 + vertex -856.228 323.824 -0.000909781 + endloop + endfacet + facet normal 0.000230008 -1.23255e-05 -1 + outer loop + vertex -863.884 324.622 -0.00252809 + vertex -859.565 332.822 -0.00163575 + vertex -860.019 324.241 -0.00163428 + endloop + endfacet + facet normal 0.000220573 -1.19527e-05 -1 + outer loop + vertex -867.853 324.955 -0.0034075 + vertex -863.419 333.264 -0.00252874 + vertex -863.884 324.622 -0.00252809 + endloop + endfacet + facet normal 0.000124224 -7.18831e-06 -1 + outer loop + vertex -871.965 325.231 -0.0039203 + vertex -867.375 333.663 -0.00341074 + vertex -867.853 324.955 -0.0034075 + endloop + endfacet + facet normal -8.82214e-05 4.06674e-06 -1 + outer loop + vertex -876.276 325.439 -0.00353913 + vertex -871.471 334.009 -0.00392818 + vertex -871.965 325.231 -0.0039203 + endloop + endfacet + facet normal -0.000280062 5.52598e-06 -1 + outer loop + vertex -880.843 325.56 -0.0022595 + vertex -876.276 325.439 -0.00353913 + vertex -881.049 316.726 -0.00225067 + endloop + endfacet + facet normal -0.000184367 3.29645e-06 -1 + outer loop + vertex -885.903 316.61 -0.00135611 + vertex -880.843 325.56 -0.0022595 + vertex -881.049 316.726 -0.00225067 + endloop + endfacet + facet normal -0.000184217 -3.26192e-06 -1 + outer loop + vertex -890.984 316.284 -0.000419039 + vertex -885.903 316.61 -0.00135611 + vertex -890.802 307.379 -0.000423453 + endloop + endfacet + facet normal -0.00236597 -4.7765e-05 -0.999997 + outer loop + vertex -896.011 306.68 0.0119328 + vertex -890.984 316.284 -0.000419039 + vertex -890.802 307.379 -0.000423453 + endloop + endfacet + facet normal -0.0100277 -0.000918615 -0.999949 + outer loop + vertex -901.335 305.8 0.0661369 + vertex -896.011 306.68 0.0119328 + vertex -900.584 296.777 0.0668949 + endloop + endfacet + facet normal -0.0261359 -0.00225926 -0.999656 + outer loop + vertex -906.034 295.731 0.211738 + vertex -901.335 305.8 0.0661369 + vertex -900.584 296.777 0.0668949 + endloop + endfacet + facet normal -0.0482771 -0.00765211 -0.998805 + outer loop + vertex -911.818 294.862 0.497967 + vertex -906.034 295.731 0.211738 + vertex -910.328 285.615 0.496784 + endloop + endfacet + facet normal -0.0734635 -0.0175063 -0.997144 + outer loop + vertex -916.456 284.785 0.962889 + vertex -910.328 285.615 0.496784 + vertex -914.206 275.407 0.961696 + endloop + endfacet + facet normal -0.0495535 -0.0107162 -0.998714 + outer loop + vertex -908.236 276.551 0.498494 + vertex -904.65 286.697 0.211705 + vertex -902.722 277.878 0.210705 + endloop + endfacet + facet normal -0.0259838 -0.00556517 -0.999647 + outer loop + vertex -904.65 286.697 0.211705 + vertex -899.313 287.929 0.0661333 + vertex -902.722 277.878 0.210705 + endloop + endfacet + facet normal -0.0101475 -0.00145089 -0.999947 + outer loop + vertex -899.313 287.929 0.0661333 + vertex -895.331 297.808 0.0113898 + vertex -894.147 289.118 0.0119778 + endloop + endfacet + facet normal -0.00222314 -0.000370709 -0.999997 + outer loop + vertex -895.331 297.808 0.0113898 + vertex -890.167 298.642 -0.000401164 + vertex -894.147 289.118 0.0119778 + endloop + endfacet + facet normal -0.000168686 -1.9455e-05 -1 + outer loop + vertex -890.167 298.642 -0.000401164 + vertex -885.731 307.824 -0.00132804 + vertex -885.119 299.21 -0.00126363 + endloop + endfacet + facet normal -0.000185033 -2.06158e-05 -1 + outer loop + vertex -885.731 307.824 -0.00132804 + vertex -880.872 308.045 -0.00223169 + vertex -885.119 299.21 -0.00126363 + endloop + endfacet + facet normal -0.000277279 -1.00859e-05 -1 + outer loop + vertex -880.872 308.045 -0.00223169 + vertex -876.466 316.696 -0.00354064 + vertex -876.277 308.11 -0.00350644 + endloop + endfacet + facet normal -9.22153e-05 -4.09851e-06 -1 + outer loop + vertex -876.277 308.11 -0.00350644 + vertex -872.138 316.568 -0.0039228 + vertex -871.935 308.065 -0.00390666 + endloop + endfacet + facet normal 0.000123361 1.97438e-06 -1 + outer loop + vertex -871.935 308.065 -0.00390666 + vertex -868.008 316.364 -0.00340581 + vertex -867.785 307.935 -0.00339498 + endloop + endfacet + facet normal 0.000218907 5.49483e-06 -1 + outer loop + vertex -867.785 307.935 -0.00339498 + vertex -864.019 316.098 -0.00252583 + vertex -863.772 307.737 -0.00251754 + endloop + endfacet + facet normal 0.000227681 6.82119e-06 -1 + outer loop + vertex -863.772 307.737 -0.00251754 + vertex -860.132 315.78 -0.00163397 + vertex -859.858 307.483 -0.0016282 + endloop + endfacet + facet normal 0.000189054 6.63108e-06 -1 + outer loop + vertex -859.858 307.483 -0.0016282 + vertex -856.323 315.422 -0.000907308 + vertex -856.018 307.185 -0.000904261 + endloop + endfacet + facet normal 0.000127537 5.31478e-06 -1 + outer loop + vertex -856.018 307.185 -0.000904261 + vertex -852.579 315.033 -0.000423916 + vertex -852.239 306.853 -0.000424 + endloop + endfacet + facet normal 6.97685e-05 3.25189e-06 -1 + outer loop + vertex -852.239 306.853 -0.000424 + vertex -848.893 314.617 -0.000165338 + vertex -848.52 306.493 -0.000165746 + endloop + endfacet + facet normal 3.09168e-05 1.42677e-06 -1 + outer loop + vertex -848.52 306.493 -0.000165746 + vertex -845.267 314.177 -5.41982e-05 + vertex -844.87 306.106 -5.34282e-05 + endloop + endfacet + facet normal 1.09875e-05 6.01601e-07 -1 + outer loop + vertex -844.87 306.106 -5.34282e-05 + vertex -841.733 313.731 -1.43726e-05 + vertex -841.3 305.707 -1.4452e-05 + endloop + endfacet + facet normal 3.39132e-06 2.03942e-07 -1 + outer loop + vertex -841.3 305.707 -1.4452e-05 + vertex -838.445 313.366 -3.20658e-06 + vertex -837.976 305.364 -3.24787e-06 + endloop + endfacet + facet normal 1.2538e-06 8.09162e-08 -1 + outer loop + vertex -837.976 305.364 -3.24787e-06 + vertex -835.896 313.271 -1.16476e-13 + vertex -835.365 305.049 -1.06159e-13 + endloop + endfacet + facet normal 3.25095e-06 6.23197e-07 -1 + outer loop + vertex -838.939 290.23 -1.39533e-05 + vertex -837.002 297.579 -3.07686e-06 + vertex -835.513 290.035 -2.93856e-06 + endloop + endfacet + facet normal 1.04893e-05 1.90199e-06 -1 + outer loop + vertex -842.611 290.539 -5.18894e-05 + vertex -840.373 297.866 -1.4473e-05 + vertex -838.939 290.23 -1.39533e-05 + endloop + endfacet + facet normal 2.94482e-05 5.08953e-06 -1 + outer loop + vertex -846.365 290.829 -0.000160962 + vertex -843.987 298.221 -5.33042e-05 + vertex -842.611 290.539 -5.18894e-05 + endloop + endfacet + facet normal 6.63691e-05 1.10728e-05 -1 + outer loop + vertex -850.185 291.079 -0.000411717 + vertex -847.687 298.556 -0.000163115 + vertex -846.365 290.829 -0.000160962 + endloop + endfacet + facet normal 0.000122522 1.88566e-05 -1 + outer loop + vertex -854.058 291.296 -0.000882144 + vertex -851.448 298.861 -0.000419655 + vertex -850.185 291.079 -0.000411717 + endloop + endfacet + facet normal 0.000180607 2.61114e-05 -1 + outer loop + vertex -857.986 291.474 -0.00158691 + vertex -855.27 299.135 -0.000896355 + vertex -854.058 291.296 -0.000882144 + endloop + endfacet + facet normal 0.000216676 2.8342e-05 -1 + outer loop + vertex -861.975 291.601 -0.00244769 + vertex -859.148 299.373 -0.00161486 + vertex -857.986 291.474 -0.00158691 + endloop + endfacet + facet normal 0.000205756 2.30247e-05 -1 + outer loop + vertex -866.052 291.661 -0.00328503 + vertex -863.098 299.563 -0.00249527 + vertex -861.975 291.601 -0.00244769 + endloop + endfacet + facet normal 0.000111521 5.84765e-06 -1 + outer loop + vertex -870.252 291.638 -0.00375361 + vertex -867.138 299.693 -0.00335925 + vertex -866.052 291.661 -0.00328503 + endloop + endfacet + facet normal -9.39505e-05 -2.54538e-05 -1 + outer loop + vertex -874.628 291.511 -0.00333926 + vertex -871.313 299.747 -0.00386034 + vertex -870.252 291.638 -0.00375361 + endloop + endfacet + facet normal -0.00028203 -5.06607e-05 -1 + outer loop + vertex -879.227 291.246 -0.00202886 + vertex -875.672 299.708 -0.00345999 + vertex -874.628 291.511 -0.00333926 + endloop + endfacet + facet normal -0.000183794 -3.96943e-05 -1 + outer loop + vertex -884.053 290.794 -0.00112391 + vertex -880.27 299.545 -0.00216642 + vertex -879.227 291.246 -0.00202886 + endloop + endfacet + facet normal -0.000186492 -5.12697e-05 -1 + outer loop + vertex -889.053 290.094 -0.000155509 + vertex -884.053 290.794 -0.00112391 + vertex -887.491 281.798 -2.14173e-05 + endloop + endfacet + facet normal -0.00236471 -0.00046131 -0.999997 + outer loop + vertex -892.487 280.668 0.0123124 + vertex -889.053 290.094 -0.000155509 + vertex -887.491 281.798 -2.14173e-05 + endloop + endfacet + facet normal -0.0101326 -0.00263944 -0.999945 + outer loop + vertex -897.527 279.31 0.0669738 + vertex -892.487 280.668 0.0123124 + vertex -895.29 271.009 0.066213 + endloop + endfacet + facet normal -0.0269041 -0.00715995 -0.999612 + outer loop + vertex -900.299 269.374 0.212736 + vertex -897.527 279.31 0.0669738 + vertex -895.29 271.009 0.066213 + endloop + endfacet + facet normal -0.0480475 -0.0177826 -0.998687 + outer loop + vertex -905.62 267.793 0.49691 + vertex -900.299 269.374 0.212736 + vertex -902.537 259.429 0.497499 + endloop + endfacet + facet normal -0.0734431 -0.0336846 -0.99673 + outer loop + vertex -908.043 257.696 0.96182 + vertex -902.537 259.429 0.497499 + vertex -904.267 249.461 0.961884 + endloop + endfacet + facet normal -0.0499865 -0.0210859 -0.998527 + outer loop + vertex -898.998 251.412 0.497717 + vertex -897.438 261.241 0.212066 + vertex -894.129 253.446 0.211047 + endloop + endfacet + facet normal -0.0263755 -0.0110643 -0.999591 + outer loop + vertex -897.438 261.241 0.212066 + vertex -892.631 263.084 0.0648305 + vertex -894.129 253.446 0.211047 + endloop + endfacet + facet normal -0.0101745 -0.00318249 -0.999943 + outer loop + vertex -892.631 263.084 0.0648305 + vertex -890.399 272.547 0.0120048 + vertex -887.904 264.804 0.011255 + endloop + endfacet + facet normal -0.00230954 -0.000647552 -0.999997 + outer loop + vertex -890.399 272.547 0.0120048 + vertex -885.516 273.836 -0.000108742 + vertex -887.904 264.804 0.011255 + endloop + endfacet + facet normal -0.000172599 -3.66709e-05 -1 + outer loop + vertex -885.516 273.836 -0.000108742 + vertex -882.553 282.636 -0.000942726 + vertex -880.649 274.815 -0.000984687 + endloop + endfacet + facet normal -0.000159934 -4.83221e-05 -1 + outer loop + vertex -880.649 274.815 -0.000984687 + vertex -877.754 283.208 -0.00185317 + vertex -875.892 275.511 -0.00177904 + endloop + endfacet + facet normal -0.000262746 -8.2478e-05 -1 + outer loop + vertex -875.892 275.511 -0.00177904 + vertex -873.162 283.575 -0.00316163 + vertex -871.307 275.983 -0.00302277 + endloop + endfacet + facet normal -9.05474e-05 -4.47901e-05 -1 + outer loop + vertex -871.307 275.983 -0.00302277 + vertex -868.772 283.791 -0.00360204 + vertex -866.902 276.288 -0.00343527 + endloop + endfacet + facet normal 9.86101e-05 4.47465e-06 -1 + outer loop + vertex -866.902 276.288 -0.00343527 + vertex -864.543 283.89 -0.00316866 + vertex -862.639 276.466 -0.00301408 + endloop + endfacet + facet normal 0.000181618 3.28241e-05 -1 + outer loop + vertex -862.639 276.466 -0.00301408 + vertex -860.428 283.898 -0.00236858 + vertex -858.48 276.543 -0.00225626 + endloop + endfacet + facet normal 0.000192042 4.33635e-05 -1 + outer loop + vertex -858.48 276.543 -0.00225626 + vertex -856.388 283.837 -0.00153823 + vertex -854.387 276.543 -0.00147024 + endloop + endfacet + facet normal 0.00016238 4.0592e-05 -1 + outer loop + vertex -854.387 276.543 -0.00147024 + vertex -852.403 283.721 -0.000856669 + vertex -850.346 276.478 -0.000816676 + endloop + endfacet + facet normal 0.000109792 2.96655e-05 -1 + outer loop + vertex -850.346 276.478 -0.000816676 + vertex -848.467 283.559 -0.000400333 + vertex -846.341 276.37 -0.000380117 + endloop + endfacet + facet normal 5.9711e-05 1.72226e-05 -1 + outer loop + vertex -846.341 276.37 -0.000380117 + vertex -844.585 283.357 -0.00015493 + vertex -842.383 276.217 -0.000146457 + endloop + endfacet + facet normal 2.60049e-05 7.91024e-06 -1 + outer loop + vertex -842.383 276.217 -0.000146457 + vertex -840.761 283.114 -4.97246e-05 + vertex -838.487 276.024 -4.66493e-05 + endloop + endfacet + facet normal 9.1544e-06 2.92426e-06 -1 + outer loop + vertex -838.487 276.024 -4.66493e-05 + vertex -837.021 282.854 -1.3257e-05 + vertex -834.671 275.815 -1.23294e-05 + endloop + endfacet + facet normal 3.00236e-06 8.70511e-07 -1 + outer loop + vertex -837.021 282.854 -1.3257e-05 + vertex -833.522 282.687 -2.89781e-06 + vertex -834.671 275.815 -1.23294e-05 + endloop + endfacet + facet normal 1.02465e-06 2.92276e-07 -1 + outer loop + vertex -833.522 282.687 -2.89781e-06 + vertex -832.843 290.221 -9.05812e-14 + vertex -830.662 282.575 -8.41863e-14 + endloop + endfacet + facet normal 2.45149e-06 1.02071e-06 -1 + outer loop + vertex -831.908 269.131 -1.1381e-05 + vertex -831.072 275.658 -2.6701e-06 + vertex -828.191 268.977 -2.42559e-06 + endloop + endfacet + facet normal 8.37346e-06 3.35478e-06 -1 + outer loop + vertex -835.813 269.304 -4.35028e-05 + vertex -831.908 269.131 -1.1381e-05 + vertex -832.725 262.861 -3.92602e-05 + endloop + endfacet + facet normal 2.15309e-05 9.66092e-06 -1 + outer loop + vertex -836.786 262.965 -0.000125694 + vertex -835.813 269.304 -4.35028e-05 + vertex -832.725 262.861 -3.92602e-05 + endloop + endfacet + facet normal 5.02919e-05 2.14912e-05 -1 + outer loop + vertex -840.892 263.018 -0.000331028 + vertex -839.787 269.446 -0.000137298 + vertex -836.786 262.965 -0.000125694 + endloop + endfacet + facet normal 9.38459e-05 3.7944e-05 -1 + outer loop + vertex -845.038 263.029 -0.0007197 + vertex -843.819 269.55 -0.000357859 + vertex -840.892 263.018 -0.000331028 + endloop + endfacet + facet normal 0.000138603 5.25556e-05 -1 + outer loop + vertex -849.219 262.988 -0.00130137 + vertex -847.898 269.61 -0.000770202 + vertex -845.038 263.029 -0.0007197 + endloop + endfacet + facet normal 0.000168682 5.81277e-05 -1 + outer loop + vertex -853.422 262.879 -0.0020166 + vertex -852.01 269.618 -0.00138672 + vertex -849.219 262.988 -0.00130137 + endloop + endfacet + facet normal 0.000172259 5.30953e-05 -1 + outer loop + vertex -857.678 262.674 -0.00276058 + vertex -856.159 269.562 -0.00213322 + vertex -853.422 262.879 -0.0020166 + endloop + endfacet + facet normal 0.000133502 3.69546e-05 -1 + outer loop + vertex -862 262.35 -0.00334956 + vertex -860.363 269.42 -0.00286973 + vertex -857.678 262.674 -0.00276058 + endloop + endfacet + facet normal 1.14522e-05 7.39764e-06 -1 + outer loop + vertex -866.425 261.869 -0.00340379 + vertex -864.653 269.169 -0.00332951 + vertex -862 262.35 -0.00334956 + endloop + endfacet + facet normal -0.000123597 4.21367e-07 -1 + outer loop + vertex -870.974 261.183 -0.00284185 + vertex -869.071 268.776 -0.00307381 + vertex -866.425 261.869 -0.00340379 + endloop + endfacet + facet normal -6.29958e-05 8.59365e-05 -1 + outer loop + vertex -875.635 260.237 -0.00262951 + vertex -873.647 268.198 -0.00207063 + vertex -870.974 261.183 -0.00284185 + endloop + endfacet + facet normal -0.000119148 0.000108968 -1 + outer loop + vertex -880.329 258.975 -0.00220771 + vertex -878.359 267.375 -0.00152719 + vertex -875.635 260.237 -0.00262951 + endloop + endfacet + facet normal -0.00245485 -0.000772617 -0.999997 + outer loop + vertex -884.952 257.37 0.0103808 + vertex -883.144 266.253 -0.000921577 + vertex -880.329 258.975 -0.00220771 + endloop + endfacet + facet normal -0.0100644 -0.00474797 -0.999938 + outer loop + vertex -889.517 255.485 0.0652731 + vertex -884.952 257.37 0.0103808 + vertex -885.903 248.056 0.0641783 + endloop + endfacet + facet normal -0.0264979 -0.0127412 -0.999568 + outer loop + vertex -890.322 245.85 0.209431 + vertex -889.517 255.485 0.0652731 + vertex -885.903 248.056 0.0641783 + endloop + endfacet + facet normal -0.0479785 -0.028222 -0.99845 + outer loop + vertex -894.965 243.613 0.49575 + vertex -890.322 245.85 0.209431 + vertex -890.402 235.912 0.494201 + endloop + endfacet + facet normal -0.0727611 -0.0492144 -0.996134 + outer loop + vertex -895.164 233.516 0.960365 + vertex -890.402 235.912 0.494201 + vertex -889.848 225.699 0.958303 + endloop + endfacet + facet normal -0.0482913 -0.031745 -0.998329 + outer loop + vertex -885.392 228.329 0.499002 + vertex -885.991 238.326 0.210101 + vertex -881.291 230.973 0.216573 + endloop + endfacet + facet normal -0.0247796 -0.0167181 -0.999553 + outer loop + vertex -885.991 238.326 0.210101 + vertex -881.782 240.682 0.0663541 + vertex -881.291 230.973 0.216573 + endloop + endfacet + facet normal -0.0100659 -0.00576934 -0.999933 + outer loop + vertex -881.782 240.682 0.0663541 + vertex -881.509 250.089 0.00932606 + vertex -877.569 242.85 0.0114333 + endloop + endfacet + facet normal -0.00252266 -0.0014562 -0.999996 + outer loop + vertex -877.569 242.85 0.0114333 + vertex -877.012 251.83 -0.00305032 + vertex -873.226 244.723 -0.00225004 + endloop + endfacet + facet normal -0.000401464 -0.000142355 -1 + outer loop + vertex -873.226 244.723 -0.00225004 + vertex -872.424 253.227 -0.00378291 + vertex -868.758 246.245 -0.00426038 + endloop + endfacet + facet normal -9.98573e-05 6.76233e-05 -1 + outer loop + vertex -868.758 246.245 -0.00426038 + vertex -867.833 254.294 -0.00380855 + vertex -864.246 247.423 -0.00463138 + endloop + endfacet + facet normal 3.68963e-05 9.03657e-05 -1 + outer loop + vertex -864.246 247.423 -0.00463138 + vertex -863.311 255.08 -0.00390502 + vertex -859.757 248.303 -0.00438624 + endloop + endfacet + facet normal 0.000175114 0.000106577 -1 + outer loop + vertex -859.757 248.303 -0.00438624 + vertex -858.888 255.649 -0.0034511 + vertex -855.321 248.951 -0.00354036 + endloop + endfacet + facet normal 0.000202047 9.82804e-05 -1 + outer loop + vertex -855.321 248.951 -0.00354036 + vertex -854.533 256.045 -0.00268395 + vertex -850.94 249.429 -0.00260836 + endloop + endfacet + facet normal 0.000175303 8.30841e-05 -1 + outer loop + vertex -850.94 249.429 -0.00260836 + vertex -850.234 256.312 -0.00191251 + vertex -846.606 249.782 -0.0018191 + endloop + endfacet + facet normal 0.000152065 7.47092e-05 -1 + outer loop + vertex -846.606 249.782 -0.0018191 + vertex -845.971 256.483 -0.00122195 + vertex -842.309 250.031 -0.0011472 + endloop + endfacet + facet normal 0.000120264 6.26683e-05 -1 + outer loop + vertex -842.309 250.031 -0.0011472 + vertex -841.739 256.583 -0.000667959 + vertex -838.024 250.199 -0.00062128 + endloop + endfacet + facet normal 7.90423e-05 4.31447e-05 -1 + outer loop + vertex -838.024 250.199 -0.00062128 + vertex -837.526 256.628 -0.000304575 + vertex -833.737 250.288 -0.000278546 + endloop + endfacet + facet normal 4.05811e-05 2.34169e-05 -1 + outer loop + vertex -833.737 250.288 -0.000278546 + vertex -833.337 256.615 -0.00011416 + vertex -829.432 250.299 -0.000103619 + endloop + endfacet + facet normal 1.44111e-05 9.38815e-06 -1 + outer loop + vertex -825.183 244.135 -8.97115e-05 + vertex -825.128 250.228 -3.17159e-05 + vertex -820.795 244.13 -2.65211e-05 + endloop + endfacet + facet normal 1.90089e-05 1.00818e-05 -1 + outer loop + vertex -833.337 256.615 -0.00011416 + vertex -829.16 256.529 -3.56326e-05 + vertex -829.432 250.299 -0.000103619 + endloop + endfacet + facet normal 6.55687e-06 3.61251e-06 -1 + outer loop + vertex -829.16 256.529 -3.56326e-05 + vertex -828.705 262.703 -1.03445e-05 + vertex -825.02 256.381 -9.02341e-06 + endloop + endfacet + facet normal 2.16672e-06 1.05384e-06 -1 + outer loop + vertex -828.705 262.703 -1.03445e-05 + vertex -824.89 262.584 -2.20485e-06 + vertex -825.02 256.381 -9.02341e-06 + endloop + endfacet + facet normal 6.94508e-07 3.69614e-07 -1 + outer loop + vertex -824.89 262.584 -2.20485e-06 + vertex -825.048 268.845 -7.56606e-14 + vertex -821.893 262.917 -7.31705e-14 + endloop + endfacet + facet normal 1.63866e-06 1.04628e-06 -1 + outer loop + vertex -820.904 250.147 -8.02221e-06 + vertex -821.138 256.341 -1.92442e-06 + vertex -816.997 250.231 -1.53242e-06 + endloop + endfacet + facet normal 5.66986e-06 3.17688e-06 -1 + outer loop + vertex -825.128 250.228 -3.17159e-05 + vertex -820.904 250.147 -8.02221e-06 + vertex -820.795 244.13 -2.65211e-05 + endloop + endfacet + facet normal 1.441e-05 8.39817e-06 -1 + outer loop + vertex -825.183 244.135 -8.97115e-05 + vertex -820.795 244.13 -2.65211e-05 + vertex -820.812 238.492 -7.41122e-05 + endloop + endfacet + facet normal 3.18748e-05 2.19267e-05 -1 + outer loop + vertex -825.288 238.434 -0.000218081 + vertex -825.183 244.135 -8.97115e-05 + vertex -820.812 238.492 -7.41122e-05 + endloop + endfacet + facet normal 6.62478e-05 4.43882e-05 -1 + outer loop + vertex -829.782 238.319 -0.000520871 + vertex -829.61 244.118 -0.000252058 + vertex -825.288 238.434 -0.000218081 + endloop + endfacet + facet normal 0.000106021 6.95179e-05 -1 + outer loop + vertex -834.252 238.106 -0.00100956 + vertex -834.008 244.01 -0.000573303 + vertex -829.782 238.319 -0.000520871 + endloop + endfacet + facet normal 0.000137672 8.70674e-05 -1 + outer loop + vertex -838.655 237.763 -0.00164559 + vertex -838.36 243.801 -0.00107932 + vertex -834.252 238.106 -0.00100956 + endloop + endfacet + facet normal 0.000164762 0.00010171 -1 + outer loop + vertex -843.018 237.22 -0.00241975 + vertex -842.69 243.47 -0.00172999 + vertex -838.655 237.763 -0.00164559 + endloop + endfacet + facet normal 0.0002184 0.000134401 -1 + outer loop + vertex -847.418 236.527 -0.00347373 + vertex -847.038 243.014 -0.00251891 + vertex -843.018 237.22 -0.00241975 + endloop + endfacet + facet normal 0.000277899 0.000176519 -1 + outer loop + vertex -851.844 235.715 -0.00484718 + vertex -851.433 242.434 -0.00354677 + vertex -847.418 236.527 -0.00347373 + endloop + endfacet + facet normal 0.000154556 0.000127795 -1 + outer loop + vertex -856.273 234.671 -0.00566517 + vertex -855.873 241.694 -0.00470579 + vertex -851.844 235.715 -0.00484718 + endloop + endfacet + facet normal -0.000346873 -0.000156228 -1 + outer loop + vertex -860.709 233.324 -0.00391609 + vertex -860.344 240.732 -0.00520011 + vertex -856.273 234.671 -0.00566517 + endloop + endfacet + facet normal -0.00123324 -0.000836882 -0.999999 + outer loop + vertex -865.046 231.606 0.00287056 + vertex -864.803 239.469 -0.00400922 + vertex -860.709 233.324 -0.00391609 + endloop + endfacet + facet normal -0.00324264 -0.00255562 -0.999991 + outer loop + vertex -869.143 229.479 0.02159 + vertex -869.171 237.84 0.000314864 + vertex -865.046 231.606 0.00287056 + endloop + endfacet + facet normal -0.00985488 -0.00732726 -0.999925 + outer loop + vertex -872.946 226.995 0.0772785 + vertex -873.357 235.836 0.0165357 + vertex -869.143 229.479 0.02159 + endloop + endfacet + facet normal -0.025285 -0.0179262 -0.99952 + outer loop + vertex -876.578 224.22 0.218912 + vertex -877.355 233.512 0.0719312 + vertex -872.946 226.995 0.0772785 + endloop + endfacet + facet normal -0.0483431 -0.0361061 -0.998178 + outer loop + vertex -880.261 221.232 0.505398 + vertex -876.578 224.22 0.218912 + vertex -875.374 215.191 0.487184 + endloop + endfacet + facet normal -0.0757439 -0.0613552 -0.995238 + outer loop + vertex -878.774 211.495 0.973875 + vertex -875.374 215.191 0.487184 + vertex -873.719 206.263 0.911617 + endloop + endfacet + facet normal -0.0639554 -0.0591272 -0.9962 + outer loop + vertex -868.144 202.272 0.727818 + vertex -865.443 205.865 0.341112 + vertex -861.863 197.168 0.627502 + endloop + endfacet + facet normal -0.0958544 -0.0984947 -0.99051 + outer loop + vertex -861.863 197.168 0.627502 + vertex -864.38 193.692 1.21666 + vertex -868.144 202.272 0.727818 + endloop + endfacet + facet normal -0.0967351 -0.0988742 -0.990387 + outer loop + vertex -870.893 198.696 1.35327 + vertex -868.144 202.272 0.727818 + vertex -864.38 193.692 1.21666 + endloop + endfacet + facet normal -0.101058 -0.095533 -0.990283 + outer loop + vertex -868.144 202.272 0.727818 + vertex -870.893 198.696 1.35327 + vertex -873.719 206.263 0.911617 + endloop + endfacet + facet normal -0.0944127 -0.0995445 -0.990544 + outer loop + vertex -864.38 193.692 1.21666 + vertex -861.863 197.168 0.627502 + vertex -856.908 187.364 1.14041 + endloop + endfacet + facet normal -0.0898253 -0.09726 -0.991197 + outer loop + vertex -856.908 187.364 1.14041 + vertex -861.863 197.168 0.627502 + vertex -854.618 190.978 0.578276 + endloop + endfacet + facet normal -0.0872353 -0.0989114 -0.991265 + outer loop + vertex -856.908 187.364 1.14041 + vertex -854.618 190.978 0.578276 + vertex -848.636 180.286 1.11878 + endloop + endfacet + facet normal -0.0858745 -0.09816 -0.991459 + outer loop + vertex -848.636 180.286 1.11878 + vertex -854.618 190.978 0.578276 + vertex -846.477 183.98 0.566067 + endloop + endfacet + facet normal -0.0829735 -0.099867 -0.991535 + outer loop + vertex -848.636 180.286 1.11878 + vertex -846.477 183.98 0.566067 + vertex -839.806 172.97 1.11673 + endloop + endfacet + facet normal -0.0822054 -0.0994071 -0.991645 + outer loop + vertex -839.806 172.97 1.11673 + vertex -846.477 183.98 0.566067 + vertex -837.7 176.676 0.570672 + endloop + endfacet + facet normal -0.0785775 -0.101481 -0.991729 + outer loop + vertex -839.806 172.97 1.11673 + vertex -837.7 176.676 0.570672 + vertex -830.559 165.769 1.12097 + endloop + endfacet + facet normal -0.0794513 -0.102046 -0.991602 + outer loop + vertex -830.559 165.769 1.12097 + vertex -837.7 176.676 0.570672 + vertex -828.518 169.501 0.573329 + endloop + endfacet + facet normal -0.0751313 -0.104423 -0.991691 + outer loop + vertex -830.559 165.769 1.12097 + vertex -828.518 169.501 0.573329 + vertex -820.998 158.881 1.1218 + endloop + endfacet + facet normal -0.0754827 -0.104669 -0.991638 + outer loop + vertex -820.998 158.881 1.1218 + vertex -828.518 169.501 0.573329 + vertex -819.033 162.667 0.572595 + endloop + endfacet + facet normal -0.0709324 -0.107042 -0.991721 + outer loop + vertex -820.998 158.881 1.1218 + vertex -819.033 162.667 0.572595 + vertex -811.193 152.35 1.12548 + endloop + endfacet + facet normal -0.0706895 -0.106859 -0.991758 + outer loop + vertex -811.193 152.35 1.12548 + vertex -819.033 162.667 0.572595 + vertex -809.285 156.194 0.575333 + endloop + endfacet + facet normal -0.0678467 -0.108277 -0.991803 + outer loop + vertex -811.193 152.35 1.12548 + vertex -809.285 156.194 0.575333 + vertex -801.205 146.115 1.12289 + endloop + endfacet + facet normal -0.0672713 -0.107821 -0.991892 + outer loop + vertex -801.205 146.115 1.12289 + vertex -809.285 156.194 0.575333 + vertex -799.315 149.995 0.572995 + endloop + endfacet + facet normal -0.0646863 -0.109085 -0.991925 + outer loop + vertex -801.205 146.115 1.12289 + vertex -799.315 149.995 0.572995 + vertex -791.071 140.121 1.12115 + endloop + endfacet + facet normal -0.0635678 -0.108161 -0.992099 + outer loop + vertex -791.071 140.121 1.12115 + vertex -799.315 149.995 0.572995 + vertex -789.183 144.021 0.575069 + endloop + endfacet + facet normal -0.0382552 -0.0611509 -0.997395 + outer loop + vertex -809.285 156.194 0.575333 + vertex -807.563 159.986 0.276808 + vertex -799.315 149.995 0.572995 + endloop + endfacet + facet normal -0.037503 -0.0605318 -0.997461 + outer loop + vertex -799.315 149.995 0.572995 + vertex -807.563 159.986 0.276808 + vertex -797.617 153.809 0.277659 + endloop + endfacet + facet normal -0.0189223 -0.0306099 -0.999352 + outer loop + vertex -807.563 159.986 0.276808 + vertex -805.725 163.605 0.131146 + vertex -797.617 153.809 0.277659 + endloop + endfacet + facet normal -0.0199341 -0.0300958 -0.999348 + outer loop + vertex -807.563 159.986 0.276808 + vertex -815.376 170.018 0.130504 + vertex -805.725 163.605 0.131146 + endloop + endfacet + facet normal -0.0099018 -0.0149998 -0.999838 + outer loop + vertex -815.376 170.018 0.130504 + vertex -813.115 173.316 0.0586362 + vertex -805.725 163.605 0.131146 + endloop + endfacet + facet normal -0.0100427 -0.015107 -0.999835 + outer loop + vertex -805.725 163.605 0.131146 + vertex -813.115 173.316 0.0586362 + vertex -803.514 166.931 0.0586786 + endloop + endfacet + facet normal -0.0054763 -0.00824088 -0.999951 + outer loop + vertex -813.115 173.316 0.0586362 + vertex -810.395 176.248 0.0195749 + vertex -803.514 166.931 0.0586786 + endloop + endfacet + facet normal -0.00576224 -0.00797556 -0.999952 + outer loop + vertex -813.115 173.316 0.0586362 + vertex -819.582 182.905 0.0194272 + vertex -810.395 176.248 0.0195749 + endloop + endfacet + facet normal -0.00306803 -0.00425686 -0.999986 + outer loop + vertex -819.582 182.905 0.0194272 + vertex -816.395 185.398 -0.00096578 + vertex -810.395 176.248 0.0195749 + endloop + endfacet + facet normal -0.00309944 -0.00427745 -0.999986 + outer loop + vertex -810.395 176.248 0.0195749 + vertex -816.395 185.398 -0.00096578 + vertex -807.266 178.793 -0.00100761 + endloop + endfacet + facet normal -0.00116347 -0.00160171 -0.999998 + outer loop + vertex -816.395 185.398 -0.00096578 + vertex -812.908 187.518 -0.00841686 + vertex -807.266 178.793 -0.00100761 + endloop + endfacet + facet normal -0.00120197 -0.00153835 -0.999998 + outer loop + vertex -816.395 185.398 -0.00096578 + vertex -821.555 194.351 -0.00853548 + vertex -812.908 187.518 -0.00841686 + endloop + endfacet + facet normal 3.81845e-05 3.09586e-05 -1 + outer loop + vertex -821.555 194.351 -0.00853548 + vertex -817.8 196.066 -0.00833897 + vertex -812.908 187.518 -0.00841686 + endloop + endfacet + facet normal 2.903e-05 2.57207e-05 -1 + outer loop + vertex -812.908 187.518 -0.00841686 + vertex -817.8 196.066 -0.00833897 + vertex -809.196 189.273 -0.00826392 + endloop + endfacet + facet normal 0.000434481 0.000539258 -1 + outer loop + vertex -817.8 196.066 -0.00833897 + vertex -813.893 197.449 -0.00589596 + vertex -809.196 189.273 -0.00826392 + endloop + endfacet + facet normal 0.000444599 0.000510666 -1 + outer loop + vertex -817.8 196.066 -0.00833897 + vertex -821.945 204.246 -0.00600513 + vertex -813.893 197.449 -0.00589596 + endloop + endfacet + facet normal 0.000380545 0.00043478 -1 + outer loop + vertex -821.945 204.246 -0.00600513 + vertex -817.917 205.288 -0.00401887 + vertex -813.893 197.449 -0.00589596 + endloop + endfacet + facet normal 0.000381844 0.000435447 -1 + outer loop + vertex -813.893 197.449 -0.00589596 + vertex -817.917 205.288 -0.00401887 + vertex -809.904 198.542 -0.00389696 + endloop + endfacet + facet normal 0.00024077 0.000267892 -1 + outer loop + vertex -817.917 205.288 -0.00401887 + vertex -813.924 206.132 -0.00283148 + vertex -809.904 198.542 -0.00389696 + endloop + endfacet + facet normal 0.000241708 0.000263452 -1 + outer loop + vertex -817.917 205.288 -0.00401887 + vertex -821.3 212.353 -0.00297544 + vertex -813.924 206.132 -0.00283148 + endloop + endfacet + facet normal 0.000174764 0.000184077 -1 + outer loop + vertex -821.3 212.353 -0.00297544 + vertex -817.483 213.114 -0.0021682 + vertex -813.924 206.132 -0.00283148 + endloop + endfacet + facet normal 0.000177587 0.000185516 -1 + outer loop + vertex -813.924 206.132 -0.00283148 + vertex -817.483 213.114 -0.0021682 + vertex -809.868 206.774 -0.00199197 + endloop + endfacet + facet normal 0.000163626 0.000168746 -1 + outer loop + vertex -817.483 213.114 -0.0021682 + vertex -813.439 213.662 -0.00141408 + vertex -809.868 206.774 -0.00199197 + endloop + endfacet + facet normal 0.00016289 0.000174183 -1 + outer loop + vertex -817.483 213.114 -0.0021682 + vertex -820.521 219.116 -0.00161772 + vertex -813.439 213.662 -0.00141408 + endloop + endfacet + facet normal 0.000148406 0.000155375 -1 + outer loop + vertex -820.521 219.116 -0.00161772 + vertex -816.603 219.807 -0.000928817 + vertex -813.439 213.662 -0.00141408 + endloop + endfacet + facet normal 0.000135631 0.000148797 -1 + outer loop + vertex -813.439 213.662 -0.00141408 + vertex -816.603 219.807 -0.000928817 + vertex -809.221 214.16 -0.000767808 + endloop + endfacet + facet normal 0.000136508 0.000141373 -1 + outer loop + vertex -813.439 213.662 -0.00141408 + vertex -809.221 214.16 -0.000767808 + vertex -805.702 207.271 -0.00126145 + endloop + endfacet + facet normal 0.000101456 0.00010412 -1 + outer loop + vertex -816.603 219.807 -0.000928817 + vertex -812.406 220.911 -0.000388018 + vertex -809.221 214.16 -0.000767808 + endloop + endfacet + facet normal 8.83574e-05 9.79407e-05 -1 + outer loop + vertex -809.221 214.16 -0.000767808 + vertex -812.406 220.911 -0.000388018 + vertex -804.715 214.49 -0.000337373 + endloop + endfacet + facet normal 8.8726e-05 9.2912e-05 -1 + outer loop + vertex -809.221 214.16 -0.000767808 + vertex -804.715 214.49 -0.000337373 + vertex -801.436 207.695 -0.000677861 + endloop + endfacet + facet normal 4.97476e-05 5.16966e-05 -1 + outer loop + vertex -812.406 220.911 -0.000388018 + vertex -806.835 220.421 -0.000136231 + vertex -804.715 214.49 -0.000337373 + endloop + endfacet + facet normal 4.48485e-05 4.99455e-05 -1 + outer loop + vertex -804.715 214.49 -0.000337373 + vertex -806.835 220.421 -0.000136231 + vertex -800.187 214.707 -0.000123478 + endloop + endfacet + facet normal 4.49444e-05 4.79384e-05 -1 + outer loop + vertex -804.715 214.49 -0.000337373 + vertex -800.187 214.707 -0.000123478 + vertex -797.125 208.093 -0.00030293 + endloop + endfacet + facet normal 4.0474e-05 4.58688e-05 -1 + outer loop + vertex -797.125 208.093 -0.00030293 + vertex -800.187 214.707 -0.000123478 + vertex -792.867 208.492 -0.000112289 + endloop + endfacet + facet normal 1.88167e-05 2.03614e-05 -1 + outer loop + vertex -800.187 214.707 -0.000123478 + vertex -795.906 214.966 -3.76597e-05 + vertex -792.867 208.492 -0.000112289 + endloop + endfacet + facet normal 1.87919e-05 2.07705e-05 -1 + outer loop + vertex -800.187 214.707 -0.000123478 + vertex -802.26 220.512 -4.18581e-05 + vertex -795.906 214.966 -3.76597e-05 + endloop + endfacet + facet normal 7.17057e-06 7.45743e-06 -1 + outer loop + vertex -802.26 220.512 -4.18581e-05 + vertex -797.808 220.441 -1.04671e-05 + vertex -795.906 214.966 -3.76597e-05 + endloop + endfacet + facet normal 6.64616e-06 7.27529e-06 -1 + outer loop + vertex -795.906 214.966 -3.76597e-05 + vertex -797.808 220.441 -1.04671e-05 + vertex -791.739 215.006 -9.67449e-06 + endloop + endfacet + facet normal 6.64496e-06 7.401e-06 -1 + outer loop + vertex -795.906 214.966 -3.76597e-05 + vertex -791.739 215.006 -9.67449e-06 + vertex -788.679 208.822 -3.51048e-05 + endloop + endfacet + facet normal 2.34666e-06 2.47445e-06 -1 + outer loop + vertex -797.808 220.441 -1.04671e-05 + vertex -793.578 219.577 -2.67928e-06 + vertex -791.739 215.006 -9.67449e-06 + endloop + endfacet + facet normal 1.84313e-06 2.27188e-06 -1 + outer loop + vertex -791.739 215.006 -9.67449e-06 + vertex -793.578 219.577 -2.67928e-06 + vertex -787.768 215.075 -2.1959e-06 + endloop + endfacet + facet normal 1.84506e-06 2.16168e-06 -1 + outer loop + vertex -791.739 215.006 -9.67449e-06 + vertex -787.768 215.075 -2.1959e-06 + vertex -784.527 209.021 -9.30332e-06 + endloop + endfacet + facet normal 2.22592e-06 1.88334e-06 -1 + outer loop + vertex -793.578 219.577 -2.67928e-06 + vertex -797.808 220.441 -1.04671e-05 + vertex -797.636 224.639 -2.177e-06 + endloop + endfacet + facet normal 5.55336e-07 5.44327e-07 -1 + outer loop + vertex -790.838 220.555 -6.25173e-07 + vertex -793.578 219.577 -2.67928e-06 + vertex -797.636 224.639 -2.177e-06 + endloop + endfacet + facet normal 1.91972e-06 1.89588e-06 -1 + outer loop + vertex -803.149 225.362 -1.13902e-05 + vertex -797.636 224.639 -2.177e-06 + vertex -797.808 220.441 -1.04671e-05 + endloop + endfacet + facet normal 1.94055e-06 2.05485e-06 -1 + outer loop + vertex -797.636 224.639 -2.177e-06 + vertex -803.149 225.362 -1.13902e-05 + vertex -803.362 229.708 -2.87403e-06 + endloop + endfacet + facet normal 5.35508e-07 4.6748e-07 -1 + outer loop + vertex -803.362 229.708 -2.87403e-06 + vertex -798.59 229.304 -5.07226e-07 + vertex -797.636 224.639 -2.177e-06 + endloop + endfacet + facet normal 2.22377e-06 2.06877e-06 -1 + outer loop + vertex -807.958 229.702 -1.31061e-05 + vertex -803.362 229.708 -2.87403e-06 + vertex -803.149 225.362 -1.13902e-05 + endloop + endfacet + facet normal 7.17282e-06 7.59707e-06 -1 + outer loop + vertex -797.808 220.441 -1.04671e-05 + vertex -802.26 220.512 -4.18581e-05 + vertex -803.149 225.362 -1.13902e-05 + endloop + endfacet + facet normal 7.04186e-06 7.57307e-06 -1 + outer loop + vertex -807.706 225.299 -4.39604e-05 + vertex -803.149 225.362 -1.13902e-05 + vertex -802.26 220.512 -4.18581e-05 + endloop + endfacet + facet normal 2.01805e-05 2.25223e-05 -1 + outer loop + vertex -802.26 220.512 -4.18581e-05 + vertex -806.835 220.421 -0.000136231 + vertex -807.706 225.299 -4.39604e-05 + endloop + endfacet + facet normal 2.02053e-05 2.12753e-05 -1 + outer loop + vertex -806.835 220.421 -0.000136231 + vertex -802.26 220.512 -4.18581e-05 + vertex -800.187 214.707 -0.000123478 + endloop + endfacet + facet normal 5.02181e-05 5.70451e-05 -1 + outer loop + vertex -806.835 220.421 -0.000136231 + vertex -812.406 220.911 -0.000388018 + vertex -812.245 225.32 -0.000128475 + endloop + endfacet + facet normal 9.78793e-05 0.000117714 -1 + outer loop + vertex -812.406 220.911 -0.000388018 + vertex -816.603 219.807 -0.000928817 + vertex -819.291 224.974 -0.00058368 + endloop + endfacet + facet normal 0.000146862 0.000164134 -1 + outer loop + vertex -816.603 219.807 -0.000928817 + vertex -820.521 219.116 -0.00161772 + vertex -823.156 224.192 -0.00117147 + endloop + endfacet + facet normal 0.000162667 0.00017407 -1 + outer loop + vertex -824.402 218.434 -0.00236775 + vertex -820.521 219.116 -0.00161772 + vertex -817.483 213.114 -0.0021682 + endloop + endfacet + facet normal 0.00016167 0.000179739 -1 + outer loop + vertex -820.521 219.116 -0.00161772 + vertex -824.402 218.434 -0.00236775 + vertex -826.22 222.935 -0.00185259 + endloop + endfacet + facet normal 0.000173857 0.000188626 -1 + outer loop + vertex -821.3 212.353 -0.00297544 + vertex -824.402 218.434 -0.00236775 + vertex -817.483 213.114 -0.0021682 + endloop + endfacet + facet normal 0.000181058 0.000192299 -1 + outer loop + vertex -827.196 217.031 -0.0031432 + vertex -824.402 218.434 -0.00236775 + vertex -821.3 212.353 -0.00297544 + endloop + endfacet + facet normal 0.000242929 0.000270266 -1 + outer loop + vertex -825.217 211.567 -0.00413929 + vertex -827.196 217.031 -0.0031432 + vertex -821.3 212.353 -0.00297544 + endloop + endfacet + facet normal 0.000290035 0.000287323 -1 + outer loop + vertex -831.688 217.203 -0.00439695 + vertex -827.196 217.031 -0.0031432 + vertex -825.217 211.567 -0.00413929 + endloop + endfacet + facet normal 0.000418585 0.000434935 -1 + outer loop + vertex -829.411 210.61 -0.00631159 + vertex -831.688 217.203 -0.00439695 + vertex -825.217 211.567 -0.00413929 + endloop + endfacet + facet normal 0.000417143 0.000441247 -1 + outer loop + vertex -829.411 210.61 -0.00631159 + vertex -825.217 211.567 -0.00413929 + vertex -821.945 204.246 -0.00600513 + endloop + endfacet + facet normal 0.00046884 0.0005019 -1 + outer loop + vertex -825.903 202.881 -0.00854554 + vertex -829.411 210.61 -0.00631159 + vertex -821.945 204.246 -0.00600513 + endloop + endfacet + facet normal 0.000505785 0.000518671 -1 + outer loop + vertex -833.343 209.119 -0.0090731 + vertex -829.411 210.61 -0.00631159 + vertex -825.903 202.881 -0.00854554 + endloop + endfacet + facet normal 7.73444e-05 7.67011e-06 -1 + outer loop + vertex -829.693 201.199 -0.00885158 + vertex -833.343 209.119 -0.0090731 + vertex -825.903 202.881 -0.00854554 + endloop + endfacet + facet normal 6.62794e-05 3.26039e-05 -1 + outer loop + vertex -829.693 201.199 -0.00885158 + vertex -825.903 202.881 -0.00854554 + vertex -821.555 194.351 -0.00853548 + endloop + endfacet + facet normal -0.00120124 -0.00147355 -0.999998 + outer loop + vertex -825.102 192.295 -0.00124493 + vertex -829.693 201.199 -0.00885158 + vertex -821.555 194.351 -0.00853548 + endloop + endfacet + facet normal -0.00124668 -0.00149697 -0.999998 + outer loop + vertex -833.352 199.262 -0.00138943 + vertex -829.693 201.199 -0.00885158 + vertex -825.102 192.295 -0.00124493 + endloop + endfacet + facet normal -0.0033665 -0.00400713 -0.999986 + outer loop + vertex -828.366 189.876 0.0194351 + vertex -833.352 199.262 -0.00138943 + vertex -825.102 192.295 -0.00124493 + endloop + endfacet + facet normal -0.00327698 -0.00412793 -0.999986 + outer loop + vertex -828.366 189.876 0.0194351 + vertex -825.102 192.295 -0.00124493 + vertex -819.582 182.905 0.0194272 + endloop + endfacet + facet normal -0.00611672 -0.00770607 -0.999952 + outer loop + vertex -822.364 180.024 0.0586479 + vertex -828.366 189.876 0.0194351 + vertex -819.582 182.905 0.0194272 + endloop + endfacet + facet normal -0.00616163 -0.00773342 -0.999951 + outer loop + vertex -831.251 187.061 0.0589864 + vertex -828.366 189.876 0.0194351 + vertex -822.364 180.024 0.0586479 + endloop + endfacet + facet normal -0.011386 -0.0143313 -0.999832 + outer loop + vertex -824.691 176.77 0.131789 + vertex -831.251 187.061 0.0589864 + vertex -822.364 180.024 0.0586479 + endloop + endfacet + facet normal -0.0108186 -0.0147371 -0.999833 + outer loop + vertex -824.691 176.77 0.131789 + vertex -822.364 180.024 0.0586479 + vertex -815.376 170.018 0.130504 + endloop + endfacet + facet normal -0.0217426 -0.0298099 -0.999319 + outer loop + vertex -817.254 166.428 0.278475 + vertex -824.691 176.77 0.131789 + vertex -815.376 170.018 0.130504 + endloop + endfacet + facet normal -0.0210543 -0.0293152 -0.999348 + outer loop + vertex -826.663 173.216 0.277565 + vertex -824.691 176.77 0.131789 + vertex -817.254 166.428 0.278475 + endloop + endfacet + facet normal -0.041892 -0.0581963 -0.997426 + outer loop + vertex -819.033 162.667 0.572595 + vertex -826.663 173.216 0.277565 + vertex -817.254 166.428 0.278475 + endloop + endfacet + facet normal -0.0224161 -0.0285595 -0.999341 + outer loop + vertex -826.663 173.216 0.277565 + vertex -833.69 183.856 0.131111 + vertex -824.691 176.77 0.131789 + endloop + endfacet + facet normal -0.0218971 -0.028217 -0.999362 + outer loop + vertex -835.756 180.347 0.27547 + vertex -833.69 183.856 0.131111 + vertex -826.663 173.216 0.277565 + endloop + endfacet + facet normal -0.0445753 -0.0571359 -0.997371 + outer loop + vertex -828.518 169.501 0.573329 + vertex -835.756 180.347 0.27547 + vertex -826.663 173.216 0.277565 + endloop + endfacet + facet normal -0.0229529 -0.0275953 -0.999356 + outer loop + vertex -835.756 180.347 0.27547 + vertex -842.247 190.983 0.130841 + vertex -833.69 183.856 0.131111 + endloop + endfacet + facet normal -0.0112489 -0.0135434 -0.999845 + outer loop + vertex -842.247 190.983 0.130841 + vertex -839.749 194.141 0.0599771 + vertex -833.69 183.856 0.131111 + endloop + endfacet + facet normal -0.0115458 -0.0137183 -0.999839 + outer loop + vertex -833.69 183.856 0.131111 + vertex -839.749 194.141 0.0599771 + vertex -831.251 187.061 0.0589864 + endloop + endfacet + facet normal -0.00643585 -0.0075849 -0.999951 + outer loop + vertex -839.749 194.141 0.0599771 + vertex -836.787 196.946 0.0196284 + vertex -831.251 187.061 0.0589864 + endloop + endfacet + facet normal -0.00657735 -0.00743551 -0.999951 + outer loop + vertex -839.749 194.141 0.0599771 + vertex -844.673 203.474 0.0229581 + vertex -836.787 196.946 0.0196284 + endloop + endfacet + facet normal -0.00378136 -0.00405788 -0.999985 + outer loop + vertex -844.673 203.474 0.0229581 + vertex -841.088 205.842 -0.000205078 + vertex -836.787 196.946 0.0196284 + endloop + endfacet + facet normal -0.0034815 -0.00391289 -0.999986 + outer loop + vertex -836.787 196.946 0.0196284 + vertex -841.088 205.842 -0.000205078 + vertex -833.352 199.262 -0.00138943 + endloop + endfacet + facet normal -0.00154708 -0.00163878 -0.999997 + outer loop + vertex -841.088 205.842 -0.000205078 + vertex -837.161 207.566 -0.00910492 + vertex -833.352 199.262 -0.00138943 + endloop + endfacet + facet normal -0.00157947 -0.00156497 -0.999998 + outer loop + vertex -841.088 205.842 -0.000205078 + vertex -843.836 213.361 -0.00763196 + vertex -837.161 207.566 -0.00910492 + endloop + endfacet + facet normal -0.000388636 -0.00019344 -1 + outer loop + vertex -843.836 213.361 -0.00763196 + vertex -839.395 213.754 -0.00943399 + vertex -837.161 207.566 -0.00910492 + endloop + endfacet + facet normal 2.61295e-05 -4.37453e-05 -1 + outer loop + vertex -837.161 207.566 -0.00910492 + vertex -839.395 213.754 -0.00943399 + vertex -833.343 209.119 -0.0090731 + endloop + endfacet + facet normal 0.000439121 0.000495491 -1 + outer loop + vertex -839.395 213.754 -0.00943399 + vertex -836.396 215.963 -0.00702252 + vertex -833.343 209.119 -0.0090731 + endloop + endfacet + facet normal 0.000375569 0.000581744 -1 + outer loop + vertex -836.396 215.963 -0.00702252 + vertex -839.395 213.754 -0.00943399 + vertex -844.234 220.263 -0.00746506 + endloop + endfacet + facet normal -0.000405825 7.71811e-07 -1 + outer loop + vertex -839.395 213.754 -0.00943399 + vertex -843.836 213.361 -0.00763196 + vertex -844.234 220.263 -0.00746506 + endloop + endfacet + facet normal -0.00191925 -0.00168913 -0.999997 + outer loop + vertex -848.249 211.473 0.00402674 + vertex -843.836 213.361 -0.00763196 + vertex -841.088 205.842 -0.000205078 + endloop + endfacet + facet normal -0.00189721 -0.00174063 -0.999997 + outer loop + vertex -843.836 213.361 -0.00763196 + vertex -848.249 211.473 0.00402674 + vertex -850.209 218.205 -0.00397295 + endloop + endfacet + facet normal -0.00378161 -0.00405751 -0.999985 + outer loop + vertex -844.673 203.474 0.0229581 + vertex -848.249 211.473 0.00402674 + vertex -841.088 205.842 -0.000205078 + endloop + endfacet + facet normal -0.00433243 -0.00430376 -0.999981 + outer loop + vertex -851.735 208.635 0.0313458 + vertex -848.249 211.473 0.00402674 + vertex -844.673 203.474 0.0229581 + endloop + endfacet + facet normal -0.00649903 -0.00726883 -0.999952 + outer loop + vertex -847.528 200.556 0.0627281 + vertex -851.735 208.635 0.0313458 + vertex -844.673 203.474 0.0229581 + endloop + endfacet + facet normal -0.00693143 -0.00749399 -0.999948 + outer loop + vertex -853.47 205.091 0.0699293 + vertex -851.735 208.635 0.0313458 + vertex -847.528 200.556 0.0627281 + endloop + endfacet + facet normal -0.0115019 -0.0134827 -0.999843 + outer loop + vertex -849.985 197.582 0.131096 + vertex -853.47 205.091 0.0699293 + vertex -847.528 200.556 0.0627281 + endloop + endfacet + facet normal -0.0115185 -0.013469 -0.999843 + outer loop + vertex -849.985 197.582 0.131096 + vertex -847.528 200.556 0.0627281 + vertex -842.247 190.983 0.130841 + endloop + endfacet + facet normal -0.0230706 -0.0270161 -0.999369 + outer loop + vertex -844.414 187.575 0.273003 + vertex -849.985 197.582 0.131096 + vertex -842.247 190.983 0.130841 + endloop + endfacet + facet normal -0.0240656 -0.0275694 -0.99933 + outer loop + vertex -852.382 194.496 0.27398 + vertex -849.985 197.582 0.131096 + vertex -844.414 187.575 0.273003 + endloop + endfacet + facet normal -0.0472007 -0.0542088 -0.997413 + outer loop + vertex -846.477 183.98 0.566067 + vertex -852.382 194.496 0.27398 + vertex -844.414 187.575 0.273003 + endloop + endfacet + facet normal -0.0250163 -0.0268307 -0.999327 + outer loop + vertex -852.382 194.496 0.27398 + vertex -856.62 203.693 0.133129 + vertex -849.985 197.582 0.131096 + endloop + endfacet + facet normal -0.0266754 -0.0275942 -0.999263 + outer loop + vertex -859.423 200.684 0.291063 + vertex -856.62 203.693 0.133129 + vertex -852.382 194.496 0.27398 + endloop + endfacet + facet normal -0.0502003 -0.0543678 -0.997258 + outer loop + vertex -854.618 190.978 0.578276 + vertex -859.423 200.684 0.291063 + vertex -852.382 194.496 0.27398 + endloop + endfacet + facet normal -0.0274948 -0.0268309 -0.999262 + outer loop + vertex -856.62 203.693 0.133129 + vertex -859.423 200.684 0.291063 + vertex -862.443 209.139 0.147096 + endloop + endfacet + facet normal -0.0136347 -0.0144722 -0.999802 + outer loop + vertex -856.62 203.693 0.133129 + vertex -853.47 205.091 0.0699293 + vertex -849.985 197.582 0.131096 + endloop + endfacet + facet normal -0.0145386 -0.0124357 -0.999817 + outer loop + vertex -853.47 205.091 0.0699293 + vertex -856.62 203.693 0.133129 + vertex -858.238 211.748 0.056468 + endloop + endfacet + facet normal -0.00735206 -0.00728816 -0.999946 + outer loop + vertex -851.735 208.635 0.0313458 + vertex -853.47 205.091 0.0699293 + vertex -858.238 211.748 0.056468 + endloop + endfacet + facet normal -0.00431655 -0.00432327 -0.999981 + outer loop + vertex -848.249 211.473 0.00402674 + vertex -851.735 208.635 0.0313458 + vertex -854.649 215.735 0.0132274 + endloop + endfacet + facet normal -0.00641579 -0.00735029 -0.999952 + outer loop + vertex -847.528 200.556 0.0627281 + vertex -844.673 203.474 0.0229581 + vertex -839.749 194.141 0.0599771 + endloop + endfacet + facet normal -0.0114151 -0.013412 -0.999845 + outer loop + vertex -842.247 190.983 0.130841 + vertex -847.528 200.556 0.0627281 + vertex -839.749 194.141 0.0599771 + endloop + endfacet + facet normal -0.0225481 -0.0273484 -0.999372 + outer loop + vertex -844.414 187.575 0.273003 + vertex -842.247 190.983 0.130841 + vertex -835.756 180.347 0.27547 + endloop + endfacet + facet normal -0.0462301 -0.0557133 -0.997376 + outer loop + vertex -837.7 176.676 0.570672 + vertex -844.414 187.575 0.273003 + vertex -835.756 180.347 0.27547 + endloop + endfacet + facet normal -0.0110346 -0.0141073 -0.99984 + outer loop + vertex -833.69 183.856 0.131111 + vertex -831.251 187.061 0.0589864 + vertex -824.691 176.77 0.131789 + endloop + endfacet + facet normal -0.00635223 -0.00753808 -0.999951 + outer loop + vertex -831.251 187.061 0.0589864 + vertex -836.787 196.946 0.0196284 + vertex -828.366 189.876 0.0194351 + endloop + endfacet + facet normal -0.0034044 -0.00402726 -0.999986 + outer loop + vertex -836.787 196.946 0.0196284 + vertex -833.352 199.262 -0.00138943 + vertex -828.366 189.876 0.0194351 + endloop + endfacet + facet normal -0.00124496 -0.0015002 -0.999998 + outer loop + vertex -833.352 199.262 -0.00138943 + vertex -837.161 207.566 -0.00910492 + vertex -829.693 201.199 -0.00885158 + endloop + endfacet + facet normal 1.66007e-05 -2.03212e-05 -1 + outer loop + vertex -837.161 207.566 -0.00910492 + vertex -833.343 209.119 -0.0090731 + vertex -829.693 201.199 -0.00885158 + endloop + endfacet + facet normal 0.000503657 0.000524281 -1 + outer loop + vertex -833.343 209.119 -0.0090731 + vertex -836.396 215.963 -0.00702252 + vertex -829.411 210.61 -0.00631159 + endloop + endfacet + facet normal 0.000441144 0.000442725 -1 + outer loop + vertex -836.396 215.963 -0.00702252 + vertex -831.688 217.203 -0.00439695 + vertex -829.411 210.61 -0.00631159 + endloop + endfacet + facet normal 0.000434286 0.000468772 -1 + outer loop + vertex -831.688 217.203 -0.00439695 + vertex -836.396 215.963 -0.00702252 + vertex -838.031 222.004 -0.00490085 + endloop + endfacet + facet normal 0.00028934 0.000269093 -1 + outer loop + vertex -827.196 217.031 -0.0031432 + vertex -831.688 217.203 -0.00439695 + vertex -831.653 223.039 -0.00281623 + endloop + endfacet + facet normal 0.000182353 0.000189718 -1 + outer loop + vertex -824.402 218.434 -0.00236775 + vertex -827.196 217.031 -0.0031432 + vertex -831.653 223.039 -0.00281623 + endloop + endfacet + facet normal 0.000244069 0.000264583 -1 + outer loop + vertex -825.217 211.567 -0.00413929 + vertex -821.3 212.353 -0.00297544 + vertex -817.917 205.288 -0.00401887 + endloop + endfacet + facet normal 0.000382838 0.000425917 -1 + outer loop + vertex -821.945 204.246 -0.00600513 + vertex -825.217 211.567 -0.00413929 + vertex -817.917 205.288 -0.00401887 + endloop + endfacet + facet normal 0.000462662 0.000519821 -1 + outer loop + vertex -825.903 202.881 -0.00854554 + vertex -821.945 204.246 -0.00600513 + vertex -817.8 196.066 -0.00833897 + endloop + endfacet + facet normal 4.28815e-05 2.0678e-05 -1 + outer loop + vertex -821.555 194.351 -0.00853548 + vertex -825.903 202.881 -0.00854554 + vertex -817.8 196.066 -0.00833897 + endloop + endfacet + facet normal -0.00117327 -0.00152181 -0.999998 + outer loop + vertex -825.102 192.295 -0.00124493 + vertex -821.555 194.351 -0.00853548 + vertex -816.395 185.398 -0.00096578 + endloop + endfacet + facet normal -0.00320297 -0.00408442 -0.999987 + outer loop + vertex -819.582 182.905 0.0194272 + vertex -825.102 192.295 -0.00124493 + vertex -816.395 185.398 -0.00096578 + endloop + endfacet + facet normal -0.00580663 -0.00800549 -0.999951 + outer loop + vertex -822.364 180.024 0.0586479 + vertex -819.582 182.905 0.0194272 + vertex -813.115 173.316 0.0586362 + endloop + endfacet + facet normal -0.0105543 -0.0145525 -0.999838 + outer loop + vertex -815.376 170.018 0.130504 + vertex -822.364 180.024 0.0586479 + vertex -813.115 173.316 0.0586362 + endloop + endfacet + facet normal -0.0204417 -0.0304908 -0.999326 + outer loop + vertex -817.254 166.428 0.278475 + vertex -815.376 170.018 0.130504 + vertex -807.563 159.986 0.276808 + endloop + endfacet + facet normal -0.0402272 -0.0602535 -0.997372 + outer loop + vertex -809.285 156.194 0.575333 + vertex -817.254 166.428 0.278475 + vertex -807.563 159.986 0.276808 + endloop + endfacet + facet normal -0.0392128 -0.0594661 -0.99746 + outer loop + vertex -819.033 162.667 0.572595 + vertex -817.254 166.428 0.278475 + vertex -809.285 156.194 0.575333 + endloop + endfacet + facet normal -0.0421235 -0.0583631 -0.997406 + outer loop + vertex -828.518 169.501 0.573329 + vertex -826.663 173.216 0.277565 + vertex -819.033 162.667 0.572595 + endloop + endfacet + facet normal -0.0441205 -0.0568334 -0.997408 + outer loop + vertex -837.7 176.676 0.570672 + vertex -835.756 180.347 0.27547 + vertex -828.518 169.501 0.573329 + endloop + endfacet + facet normal -0.0454343 -0.0552248 -0.99744 + outer loop + vertex -846.477 183.98 0.566067 + vertex -844.414 187.575 0.273003 + vertex -837.7 176.676 0.570672 + endloop + endfacet + facet normal -0.0489306 -0.0551765 -0.997277 + outer loop + vertex -854.618 190.978 0.578276 + vertex -852.382 194.496 0.27398 + vertex -846.477 183.98 0.566067 + endloop + endfacet + facet normal -0.0554158 -0.0569378 -0.996839 + outer loop + vertex -861.863 197.168 0.627502 + vertex -859.423 200.684 0.291063 + vertex -854.618 190.978 0.578276 + endloop + endfacet + facet normal -0.0565948 -0.0561179 -0.996819 + outer loop + vertex -859.423 200.684 0.291063 + vertex -861.863 197.168 0.627502 + vertex -865.443 205.865 0.341112 + endloop + endfacet + facet normal -0.0422332 -0.0340173 -0.998529 + outer loop + vertex -870.612 210.352 0.421352 + vertex -872.085 218.524 0.205253 + vertex -867.576 213.784 0.17602 + endloop + endfacet + facet normal -0.0331323 -0.0288401 -0.999035 + outer loop + vertex -865.443 205.865 0.341112 + vertex -862.443 209.139 0.147096 + vertex -859.423 200.684 0.291063 + endloop + endfacet + facet normal -0.0177388 -0.0156481 -0.99972 + outer loop + vertex -867.576 213.784 0.17602 + vertex -868.677 221.494 0.0748844 + vertex -864.113 216.798 0.0674032 + endloop + endfacet + facet normal -0.0139134 -0.0123102 -0.999827 + outer loop + vertex -862.443 209.139 0.147096 + vertex -858.238 211.748 0.056468 + vertex -856.62 203.693 0.133129 + endloop + endfacet + facet normal -0.00693465 -0.0066909 -0.999954 + outer loop + vertex -864.113 216.798 0.0674032 + vertex -864.916 224.131 0.023903 + vertex -860.221 219.643 0.0213712 + endloop + endfacet + facet normal -0.00632784 -0.00514859 -0.999967 + outer loop + vertex -858.238 211.748 0.056468 + vertex -854.649 215.735 0.0132274 + vertex -851.735 208.635 0.0313458 + endloop + endfacet + facet normal -0.00320117 -0.00296169 -0.99999 + outer loop + vertex -860.221 219.643 0.0213712 + vertex -860.794 226.386 0.00323414 + vertex -856.012 222.144 0.000491262 + endloop + endfacet + facet normal -0.00276491 -0.00199324 -0.999994 + outer loop + vertex -854.649 215.735 0.0132274 + vertex -850.209 218.205 -0.00397295 + vertex -848.249 211.473 0.00402674 + endloop + endfacet + facet normal -0.00110316 -0.000945118 -0.999999 + outer loop + vertex -856.012 222.144 0.000491262 + vertex -856.409 228.208 -0.00480247 + vertex -851.46 224.111 -0.00638992 + endloop + endfacet + facet normal -0.00058126 -9.34814e-06 -1 + outer loop + vertex -850.209 218.205 -0.00397295 + vertex -844.234 220.263 -0.00746506 + vertex -843.836 213.361 -0.00763196 + endloop + endfacet + facet normal -4.76402e-05 3.24137e-05 -1 + outer loop + vertex -851.46 224.111 -0.00638992 + vertex -852.097 229.691 -0.00617868 + vertex -848.04 226.141 -0.00648702 + endloop + endfacet + facet normal 0.000300419 0.000329482 -1 + outer loop + vertex -848.04 226.141 -0.00648702 + vertex -847.803 230.743 -0.00489929 + vertex -843.557 226.332 -0.00507708 + endloop + endfacet + facet normal 0.000292557 0.00043041 -1 + outer loop + vertex -844.234 220.263 -0.00746506 + vertex -838.031 222.004 -0.00490085 + vertex -836.396 215.963 -0.00702252 + endloop + endfacet + facet normal 0.000297356 0.00030546 -1 + outer loop + vertex -843.557 226.332 -0.00507708 + vertex -843.308 231.557 -0.00340706 + vertex -838.613 227.385 -0.0032853 + endloop + endfacet + facet normal 0.000283164 0.00026913 -1 + outer loop + vertex -838.031 222.004 -0.00490085 + vertex -831.653 223.039 -0.00281623 + vertex -831.688 217.203 -0.00439695 + endloop + endfacet + facet normal 0.000211964 0.000204372 -1 + outer loop + vertex -838.613 227.385 -0.0032853 + vertex -838.926 232.414 -0.00232392 + vertex -834.873 228.735 -0.00221666 + endloop + endfacet + facet normal 0.000149745 0.000144203 -1 + outer loop + vertex -834.873 228.735 -0.00221666 + vertex -834.494 232.849 -0.00156674 + vertex -829.587 227.806 -0.00155914 + endloop + endfacet + facet normal 0.000180965 0.000187532 -1 + outer loop + vertex -831.653 223.039 -0.00281623 + vertex -826.22 222.935 -0.00185259 + vertex -824.402 218.434 -0.00236775 + endloop + endfacet + facet normal 0.000153532 0.000167596 -1 + outer loop + vertex -826.22 222.935 -0.00185259 + vertex -823.156 224.192 -0.00117147 + vertex -820.521 219.116 -0.00161772 + endloop + endfacet + facet normal 0.000138454 0.000126113 -1 + outer loop + vertex -829.587 227.806 -0.00155914 + vertex -829.869 233.083 -0.000932658 + vertex -824.898 228.814 -0.000782857 + endloop + endfacet + facet normal 0.000125369 0.000132016 -1 + outer loop + vertex -823.156 224.192 -0.00117147 + vertex -819.291 224.974 -0.00058368 + vertex -816.603 219.807 -0.000928817 + endloop + endfacet + facet normal 9.63951e-05 8.41755e-05 -1 + outer loop + vertex -824.898 228.814 -0.000782857 + vertex -825.354 233.382 -0.00044234 + vertex -820.743 229.269 -0.000343977 + endloop + endfacet + facet normal 8.11595e-05 8.93802e-05 -1 + outer loop + vertex -819.291 224.974 -0.00058368 + vertex -816.452 226.007 -0.000260966 + vertex -812.406 220.911 -0.000388018 + endloop + endfacet + facet normal 5.05196e-05 4.25253e-05 -1 + outer loop + vertex -820.743 229.269 -0.000343977 + vertex -820.922 233.526 -0.000172022 + vertex -816.631 229.408 -0.000130315 + endloop + endfacet + facet normal 4.08688e-05 5.73861e-05 -1 + outer loop + vertex -816.452 226.007 -0.000260966 + vertex -812.245 225.32 -0.000128475 + vertex -812.406 220.911 -0.000388018 + endloop + endfacet + facet normal 1.92529e-05 1.70906e-05 -1 + outer loop + vertex -816.631 229.408 -0.000130315 + vertex -816.533 233.65 -5.5954e-05 + vertex -812.314 229.476 -4.60417e-05 + endloop + endfacet + facet normal 1.87236e-05 2.22621e-05 -1 + outer loop + vertex -812.245 225.32 -0.000128475 + vertex -807.706 225.299 -4.39604e-05 + vertex -806.835 220.421 -0.000136231 + endloop + endfacet + facet normal 7.04411e-06 7.4101e-06 -1 + outer loop + vertex -803.149 225.362 -1.13902e-05 + vertex -807.706 225.299 -4.39604e-05 + vertex -807.958 229.702 -1.31061e-05 + endloop + endfacet + facet normal 9.02867e-06 6.75346e-06 -1 + outer loop + vertex -816.533 233.65 -5.5954e-05 + vertex -812.232 233.891 -1.54892e-05 + vertex -812.314 229.476 -4.60417e-05 + endloop + endfacet + facet normal 2.22367e-06 2.14675e-06 -1 + outer loop + vertex -807.958 229.702 -1.31061e-05 + vertex -807.957 234.153 -3.54662e-06 + vertex -803.362 229.708 -2.87403e-06 + endloop + endfacet + facet normal 6.58368e-07 5.29094e-07 -1 + outer loop + vertex -807.957 234.153 -3.54662e-06 + vertex -803.569 234.128 -6.71064e-07 + vertex -803.362 229.708 -2.87403e-06 + endloop + endfacet + facet normal 3.62732e-06 2.14962e-06 -1 + outer loop + vertex -816.438 238.607 -2.06102e-05 + vertex -812.23 238.845 -4.83331e-06 + vertex -812.232 233.891 -1.54892e-05 + endloop + endfacet + facet normal 1.27346e-06 7.29163e-07 -1 + outer loop + vertex -816.559 244.199 -6.4419e-06 + vertex -812.632 244.429 -1.27378e-06 + vertex -812.23 238.845 -4.83331e-06 + endloop + endfacet + facet normal 3.5033e-07 2.73681e-07 -1 + outer loop + vertex -812.632 244.429 -1.27378e-06 + vertex -813.924 250.736 -7.02221e-14 + vertex -809.093 244.552 -6.97309e-14 + endloop + endfacet + facet normal 6.58554e-07 5.61728e-07 -1 + outer loop + vertex -807.957 234.153 -3.54662e-06 + vertex -808.169 239.074 -9.22701e-07 + vertex -803.569 234.128 -6.71064e-07 + endloop + endfacet + facet normal 5.40254e-07 5.23576e-07 -1 + outer loop + vertex -803.362 229.708 -2.87403e-06 + vertex -803.569 234.128 -6.71064e-07 + vertex -798.59 229.304 -5.07226e-07 + endloop + endfacet + facet normal 4.22959e-07 4.44461e-07 -1 + outer loop + vertex -793.678 225.063 -3.14643e-07 + vertex -797.636 224.639 -2.177e-06 + vertex -798.59 229.304 -5.07226e-07 + endloop + endfacet + facet normal 4.33904e-07 3.42216e-07 -1 + outer loop + vertex -797.636 224.639 -2.177e-06 + vertex -793.678 225.063 -3.14643e-07 + vertex -790.838 220.555 -6.25173e-07 + endloop + endfacet + facet normal 5.39409e-07 5.88927e-07 -1 + outer loop + vertex -793.578 219.577 -2.67928e-06 + vertex -790.838 220.555 -6.25173e-07 + vertex -787.768 215.075 -2.1959e-06 + endloop + endfacet + facet normal 9.28601e-08 1.05056e-07 -1 + outer loop + vertex -783.802 215.379 -3.70537e-07 + vertex -787.3 221.998 -7.12059e-14 + vertex -779.909 215.465 -7.18505e-14 + endloop + endfacet + facet normal 3.94494e-07 4.94304e-07 -1 + outer loop + vertex -780.364 209.149 -2.0585e-06 + vertex -776.227 209.237 -3.83037e-07 + vertex -772.346 202.813 -2.02726e-06 + endloop + endfacet + facet normal 1.6768e-06 2.0716e-06 -1 + outer loop + vertex -784.527 209.021 -9.30332e-06 + vertex -787.768 215.075 -2.1959e-06 + vertex -780.364 209.149 -2.0585e-06 + endloop + endfacet + facet normal 5.87689e-06 7.0209e-06 -1 + outer loop + vertex -788.679 208.822 -3.51048e-05 + vertex -791.739 215.006 -9.67449e-06 + vertex -784.527 209.021 -9.30332e-06 + endloop + endfacet + facet normal 1.68958e-05 1.94597e-05 -1 + outer loop + vertex -792.867 208.492 -0.000112289 + vertex -795.906 214.966 -3.76597e-05 + vertex -788.679 208.822 -3.51048e-05 + endloop + endfacet + facet normal 4.03341e-05 4.73593e-05 -1 + outer loop + vertex -797.125 208.093 -0.00030293 + vertex -792.867 208.492 -0.000112289 + vertex -789.179 201.607 -0.000289586 + endloop + endfacet + facet normal 7.88257e-05 8.81352e-05 -1 + outer loop + vertex -801.436 207.695 -0.000677861 + vertex -804.715 214.49 -0.000337373 + vertex -797.125 208.093 -0.00030293 + endloop + endfacet + facet normal 0.000123428 0.000134692 -1 + outer loop + vertex -805.702 207.271 -0.00126145 + vertex -809.221 214.16 -0.000767808 + vertex -801.436 207.695 -0.000677861 + endloop + endfacet + facet normal 0.000155745 0.00016466 -1 + outer loop + vertex -809.868 206.774 -0.00199197 + vertex -813.439 213.662 -0.00141408 + vertex -805.702 207.271 -0.00126145 + endloop + endfacet + facet normal 0.000176877 0.000189998 -1 + outer loop + vertex -813.924 206.132 -0.00283148 + vertex -809.868 206.774 -0.00199197 + vertex -805.87 199.397 -0.00268653 + endloop + endfacet + facet normal 0.000243001 0.000269074 -1 + outer loop + vertex -809.904 198.542 -0.00389696 + vertex -813.924 206.132 -0.00283148 + vertex -805.87 199.397 -0.00268653 + endloop + endfacet + facet normal 0.00037503 0.000460308 -1 + outer loop + vertex -813.893 197.449 -0.00589596 + vertex -809.904 198.542 -0.00389696 + vertex -805.331 190.697 -0.00579308 + endloop + endfacet + facet normal 0.00043962 0.000542211 -1 + outer loop + vertex -809.196 189.273 -0.00826392 + vertex -813.893 197.449 -0.00589596 + vertex -805.331 190.697 -0.00579308 + endloop + endfacet + facet normal 2.78717e-05 2.81699e-05 -1 + outer loop + vertex -812.908 187.518 -0.00841686 + vertex -809.196 189.273 -0.00826392 + vertex -803.813 180.952 -0.00834832 + endloop + endfacet + facet normal -0.00113585 -0.00158385 -0.999998 + outer loop + vertex -807.266 178.793 -0.00100761 + vertex -812.908 187.518 -0.00841686 + vertex -803.813 180.952 -0.00834832 + endloop + endfacet + facet normal -0.00297032 -0.00443618 -0.999986 + outer loop + vertex -810.395 176.248 0.0195749 + vertex -807.266 178.793 -0.00100761 + vertex -800.846 169.896 0.0193918 + endloop + endfacet + facet normal -0.00552557 -0.00827727 -0.99995 + outer loop + vertex -803.514 166.931 0.0586786 + vertex -810.395 176.248 0.0195749 + vertex -800.846 169.896 0.0193918 + endloop + endfacet + facet normal -0.00967015 -0.0153546 -0.999835 + outer loop + vertex -805.725 163.605 0.131146 + vertex -803.514 166.931 0.0586786 + vertex -795.823 157.445 0.129972 + endloop + endfacet + facet normal -0.019412 -0.0310149 -0.99933 + outer loop + vertex -797.617 153.809 0.277659 + vertex -805.725 163.605 0.131146 + vertex -795.823 157.445 0.129972 + endloop + endfacet + facet normal -0.0359052 -0.0612445 -0.997477 + outer loop + vertex -799.315 149.995 0.572995 + vertex -797.617 153.809 0.277659 + vertex -789.183 144.021 0.575069 + endloop + endfacet + facet normal -0.0613749 -0.109225 -0.99212 + outer loop + vertex -791.071 140.121 1.12115 + vertex -789.183 144.021 0.575069 + vertex -780.809 134.334 1.12347 + endloop + endfacet + facet normal -0.0346356 -0.0618743 -0.997483 + outer loop + vertex -778.938 138.253 0.572921 + vertex -787.512 147.848 0.275473 + vertex -777.29 142.093 0.277493 + endloop + endfacet + facet normal -0.0173471 -0.0311649 -0.999364 + outer loop + vertex -787.512 147.848 0.275473 + vertex -785.741 151.494 0.131032 + vertex -777.29 142.093 0.277493 + endloop + endfacet + facet normal -0.00920563 -0.015645 -0.999835 + outer loop + vertex -785.741 151.494 0.131032 + vertex -793.651 160.79 0.0584057 + vertex -783.601 154.849 0.0588284 + endloop + endfacet + facet normal -0.00504496 -0.00860608 -0.99995 + outer loop + vertex -793.651 160.79 0.0584057 + vertex -791.012 163.773 0.0194128 + vertex -783.601 154.849 0.0588284 + endloop + endfacet + facet normal -0.00278999 -0.00449158 -0.999986 + outer loop + vertex -791.012 163.773 0.0194128 + vertex -797.743 172.469 -0.000865558 + vertex -787.949 166.37 -0.000795884 + endloop + endfacet + facet normal -0.0010645 -0.00172079 -0.999998 + outer loop + vertex -797.743 172.469 -0.000865558 + vertex -794.335 174.661 -0.00826478 + vertex -787.949 166.37 -0.000795884 + endloop + endfacet + facet normal 3.96398e-05 4.30871e-05 -1 + outer loop + vertex -794.335 174.661 -0.00826478 + vertex -800.141 182.747 -0.00814651 + vertex -790.711 176.49 -0.00804231 + endloop + endfacet + facet normal 0.000415715 0.000609875 -1 + outer loop + vertex -800.141 182.747 -0.00814651 + vertex -796.337 184.217 -0.0056686 + vertex -790.711 176.49 -0.00804231 + endloop + endfacet + facet normal 0.000364879 0.000492346 -1 + outer loop + vertex -796.337 184.217 -0.0056686 + vertex -801.394 191.841 -0.00375987 + vertex -792.451 185.412 -0.00366272 + endloop + endfacet + facet normal 0.000230587 0.000305579 -1 + outer loop + vertex -801.394 191.841 -0.00375987 + vertex -797.403 192.759 -0.0025594 + vertex -792.451 185.412 -0.00366272 + endloop + endfacet + facet normal 0.000158761 0.000191187 -1 + outer loop + vertex -797.403 192.759 -0.0025594 + vertex -801.783 200.073 -0.00185623 + vertex -793.356 193.508 -0.00177368 + endloop + endfacet + facet normal 0.000131555 0.000163747 -1 + outer loop + vertex -793.356 193.508 -0.00177368 + vertex -797.634 200.63 -0.00117017 + vertex -789.244 194.143 -0.00112869 + endloop + endfacet + facet normal 0.000103761 0.000132861 -1 + outer loop + vertex -789.244 194.143 -0.00112869 + vertex -793.423 201.13 -0.000634054 + vertex -785.054 194.706 -0.000619067 + endloop + endfacet + facet normal 6.76526e-05 9.4479e-05 -1 + outer loop + vertex -785.054 194.706 -0.000619067 + vertex -780.805 195.21 -0.000283969 + vertex -776.265 188.473 -0.000613436 + endloop + endfacet + facet normal 3.67576e-05 4.7775e-05 -1 + outer loop + vertex -780.805 195.21 -0.000283969 + vertex -784.943 202.046 -0.000109537 + vertex -776.542 195.646 -0.000106463 + endloop + endfacet + facet normal 1.53025e-05 2.01708e-05 -1 + outer loop + vertex -776.542 195.646 -0.000106463 + vertex -780.728 202.396 -3.43618e-05 + vertex -772.3 196.007 -3.42698e-05 + endloop + endfacet + facet normal 5.51312e-06 7.3167e-06 -1 + outer loop + vertex -772.3 196.007 -3.42698e-05 + vertex -776.533 202.644 -9.05105e-06 + vertex -768.114 196.294 -9.08965e-06 + endloop + endfacet + facet normal 1.57865e-06 2.22858e-06 -1 + outer loop + vertex -768.114 196.294 -9.08965e-06 + vertex -763.978 196.542 -2.00851e-06 + vertex -759.391 190.145 -9.02166e-06 + endloop + endfacet + facet normal 3.73068e-07 5.03194e-07 -1 + outer loop + vertex -763.978 196.542 -2.00851e-06 + vertex -768.326 203.015 -3.73457e-07 + vertex -760.049 196.864 -3.8074e-07 + endloop + endfacet + facet normal 9.59577e-08 1.2989e-07 -1 + outer loop + vertex -760.049 196.864 -3.8074e-07 + vertex -765.143 203.558 -7.30252e-14 + vertex -756.831 197.418 -7.36311e-14 + endloop + endfacet + facet normal 3.65437e-07 5.53897e-07 -1 + outer loop + vertex -746.316 184.529 -2.00573e-06 + vertex -751.384 190.812 -3.77211e-07 + vertex -742.405 184.897 -3.72636e-07 + endloop + endfacet + facet normal 1.54257e-06 2.33311e-06 -1 + outer loop + vertex -750.388 184.198 -9.05839e-06 + vertex -755.29 190.449 -2.03668e-06 + vertex -746.316 184.529 -2.00573e-06 + endloop + endfacet + facet normal 5.34347e-06 8.6053e-06 -1 + outer loop + vertex -754.496 183.837 -3.41182e-05 + vertex -750.388 184.198 -9.05839e-06 + vertex -745.232 178.052 -3.43973e-05 + endloop + endfacet + facet normal 1.53489e-05 2.3299e-05 -1 + outer loop + vertex -758.661 183.424 -0.000107659 + vertex -763.54 189.815 -3.36469e-05 + vertex -754.496 183.837 -3.41182e-05 + endloop + endfacet + facet normal 3.52464e-05 5.32188e-05 -1 + outer loop + vertex -762.88 182.953 -0.000281436 + vertex -767.747 189.433 -0.000108129 + vertex -758.661 183.424 -0.000107659 + endloop + endfacet + facet normal 6.56211e-05 9.91201e-05 -1 + outer loop + vertex -767.1 182.416 -0.000611603 + vertex -772.011 188.988 -0.00028247 + vertex -762.88 182.953 -0.000281436 + endloop + endfacet + facet normal 9.68785e-05 0.000155099 -1 + outer loop + vertex -771.254 181.799 -0.00110968 + vertex -767.1 182.416 -0.000611603 + vertex -761.78 175.888 -0.00110874 + endloop + endfacet + facet normal 0.000120525 0.00018157 -1 + outer loop + vertex -775.297 181.084 -0.00172689 + vertex -780.448 187.88 -0.00111374 + vertex -771.254 181.799 -0.00110968 + endloop + endfacet + facet normal 0.000141444 0.000212209 -1 + outer loop + vertex -779.252 180.239 -0.00246553 + vertex -784.531 187.194 -0.00173643 + vertex -775.297 181.084 -0.00172689 + endloop + endfacet + facet normal 0.000211114 0.000313198 -1 + outer loop + vertex -783.133 179.228 -0.00360156 + vertex -788.519 186.386 -0.00249667 + vertex -779.252 180.239 -0.00246553 + endloop + endfacet + facet normal 0.000342873 0.000542883 -1 + outer loop + vertex -786.959 177.996 -0.00558203 + vertex -783.133 179.228 -0.00360156 + vertex -777.299 171.978 -0.0055372 + endloop + endfacet + facet normal 0.000401976 0.000637747 -1 + outer loop + vertex -781.006 170.446 -0.00800414 + vertex -786.959 177.996 -0.00558203 + vertex -777.299 171.978 -0.0055372 + endloop + endfacet + facet normal 1.67571e-05 2.80155e-05 -1 + outer loop + vertex -784.577 168.586 -0.00811609 + vertex -781.006 170.446 -0.00800414 + vertex -774.658 162.711 -0.00811446 + endloop + endfacet + facet normal -0.0010347 -0.00174734 -0.999998 + outer loop + vertex -777.984 160.47 -0.000756052 + vertex -784.577 168.586 -0.00811609 + vertex -774.658 162.711 -0.00811446 + endloop + endfacet + facet normal -0.00268292 -0.00473516 -0.999985 + outer loop + vertex -780.999 157.849 0.0197426 + vertex -777.984 160.47 -0.000756052 + vertex -770.882 152.131 0.0196757 + endloop + endfacet + facet normal -0.0049392 -0.00872717 -0.99995 + outer loop + vertex -773.446 149.114 0.0586741 + vertex -780.999 157.849 0.0197426 + vertex -770.882 152.131 0.0196757 + endloop + endfacet + facet normal -0.00870368 -0.0160242 -0.999834 + outer loop + vertex -775.551 145.747 0.130952 + vertex -773.446 149.114 0.0586741 + vertex -765.25 140.198 0.130223 + endloop + endfacet + facet normal -0.0172591 -0.0319046 -0.999342 + outer loop + vertex -766.962 136.537 0.276669 + vertex -775.551 145.747 0.130952 + vertex -765.25 140.198 0.130223 + endloop + endfacet + facet normal -0.0326817 -0.0634632 -0.997449 + outer loop + vertex -768.59 132.689 0.574847 + vertex -766.962 136.537 0.276669 + vertex -758.124 127.31 0.574138 + endloop + endfacet + facet normal -0.0553359 -0.112171 -0.992147 + outer loop + vertex -759.972 123.358 1.12401 + vertex -758.124 127.31 0.574138 + vertex -749.382 118.146 1.12267 + endloop + endfacet + facet normal -0.0314766 -0.0637593 -0.997469 + outer loop + vertex -747.555 122.116 0.57371 + vertex -756.513 131.167 0.277859 + vertex -745.973 125.985 0.276508 + endloop + endfacet + facet normal -0.016121 -0.0325276 -0.999341 + outer loop + vertex -756.513 131.167 0.277859 + vertex -754.828 134.835 0.131263 + vertex -745.973 125.985 0.276508 + endloop + endfacet + facet normal -0.00840603 -0.0163292 -0.999831 + outer loop + vertex -754.828 134.835 0.131263 + vertex -763.176 143.575 0.0587118 + vertex -752.79 138.225 0.0587756 + endloop + endfacet + facet normal -0.0046163 -0.00897279 -0.999949 + outer loop + vertex -763.176 143.575 0.0587118 + vertex -760.644 146.607 0.0198175 + vertex -752.79 138.225 0.0587756 + endloop + endfacet + facet normal -0.00260508 -0.00482012 -0.999985 + outer loop + vertex -760.644 146.607 0.0198175 + vertex -767.9 154.77 -0.000625074 + vertex -757.708 149.268 -0.000659758 + endloop + endfacet + facet normal -0.000992292 -0.00183211 -0.999998 + outer loop + vertex -767.9 154.77 -0.000625074 + vertex -764.616 157.034 -0.00803175 + vertex -757.708 149.268 -0.000659758 + endloop + endfacet + facet normal 4.43347e-06 1.6711e-05 -1 + outer loop + vertex -764.616 157.034 -0.00803175 + vertex -771.123 164.592 -0.00793429 + vertex -761.133 158.942 -0.00798442 + endloop + endfacet + facet normal 0.000373822 0.000669852 -1 + outer loop + vertex -771.123 164.592 -0.00793429 + vertex -767.464 166.149 -0.00552375 + vertex -761.133 158.942 -0.00798442 + endloop + endfacet + facet normal 0.000330111 0.000557039 -1 + outer loop + vertex -767.464 166.149 -0.00552375 + vertex -773.521 173.235 -0.00357601 + vertex -763.73 167.429 -0.00357806 + endloop + endfacet + facet normal 0.000201144 0.000339621 -1 + outer loop + vertex -763.73 167.429 -0.00357806 + vertex -769.688 174.272 -0.00245233 + vertex -759.946 168.492 -0.00245599 + endloop + endfacet + facet normal 0.000136679 0.000230206 -1 + outer loop + vertex -759.946 168.492 -0.00245599 + vertex -765.783 175.143 -0.00172262 + vertex -756.092 169.39 -0.00172231 + endloop + endfacet + facet normal 0.000115312 0.000203484 -1 + outer loop + vertex -756.092 169.39 -0.00172231 + vertex -752.145 170.168 -0.00110899 + vertex -746.297 163.844 -0.00172147 + endloop + endfacet + facet normal 9.58e-05 0.000161111 -1 + outer loop + vertex -752.145 170.168 -0.00110899 + vertex -757.675 176.537 -0.000612643 + vertex -748.1 170.851 -0.000611508 + endloop + endfacet + facet normal 6.44304e-05 0.000108315 -1 + outer loop + vertex -748.1 170.851 -0.000611508 + vertex -753.512 177.107 -0.000282458 + vertex -743.994 171.456 -0.000281399 + endloop + endfacet + facet normal 3.45675e-05 5.83673e-05 -1 + outer loop + vertex -743.994 171.456 -0.000281399 + vertex -749.35 177.61 -0.000107338 + vertex -739.885 171.991 -0.000108075 + endloop + endfacet + facet normal 1.50971e-05 2.66092e-05 -1 + outer loop + vertex -739.885 171.991 -0.000108075 + vertex -735.819 172.461 -3.4205e-05 + vertex -730.307 166.571 -0.000107727 + endloop + endfacet + facet normal 5.3294e-06 9.01356e-06 -1 + outer loop + vertex -735.819 172.461 -3.4205e-05 + vertex -741.167 178.437 -8.83888e-06 + vertex -731.798 172.874 -9.04889e-06 + endloop + endfacet + facet normal 1.51096e-06 2.5549e-06 -1 + outer loop + vertex -731.798 172.874 -9.04889e-06 + vertex -737.13 178.791 -1.98874e-06 + vertex -727.81 173.257 -2.04407e-06 + endloop + endfacet + facet normal 3.64704e-07 6.4107e-07 -1 + outer loop + vertex -727.81 173.257 -2.04407e-06 + vertex -723.982 173.676 -3.79758e-07 + vertex -718.383 167.922 -2.02628e-06 + endloop + endfacet + facet normal 9.0776e-08 1.53002e-07 -1 + outer loop + vertex -723.982 173.676 -3.79758e-07 + vertex -729.981 179.717 -7.53775e-14 + vertex -720.665 174.19 -7.59228e-14 + endloop + endfacet + facet normal 3.57004e-07 6.63444e-07 -1 + outer loop + vertex -708.846 162.774 -2.01251e-06 + vertex -714.614 168.375 -3.55943e-07 + vertex -705.132 163.259 -3.65135e-07 + endloop + endfacet + facet normal 1.47176e-06 2.87682e-06 -1 + outer loop + vertex -712.741 162.337 -9.00162e-06 + vertex -708.846 162.774 -2.01251e-06 + vertex -703.05 157.341 -9.11288e-06 + endloop + endfacet + facet normal 5.21759e-06 9.64092e-06 -1 + outer loop + vertex -716.661 161.867 -3.39852e-05 + vertex -722.322 167.512 -9.10536e-06 + vertex -712.741 162.337 -9.00162e-06 + endloop + endfacet + facet normal 1.48377e-05 2.7446e-05 -1 + outer loop + vertex -720.62 161.339 -0.00010724 + vertex -726.294 167.07 -3.41349e-05 + vertex -716.661 161.867 -3.39852e-05 + endloop + endfacet + facet normal 3.39095e-05 6.55746e-05 -1 + outer loop + vertex -724.619 160.744 -0.000281863 + vertex -720.62 161.339 -0.00010724 + vertex -714.767 155.66 -0.000281119 + endloop + endfacet + facet normal 6.29996e-05 0.000116516 -1 + outer loop + vertex -728.617 160.077 -0.000611431 + vertex -734.361 166.005 -0.000282542 + vertex -724.619 160.744 -0.000281863 + endloop + endfacet + facet normal 9.35363e-05 0.000172926 -1 + outer loop + vertex -732.554 159.332 -0.0011085 + vertex -738.412 165.368 -0.000612639 + vertex -728.617 160.077 -0.000611431 + endloop + endfacet + facet normal 0.000113814 0.000210508 -1 + outer loop + vertex -736.395 158.495 -0.00172184 + vertex -742.402 164.653 -0.00110933 + vertex -732.554 159.332 -0.0011085 + endloop + endfacet + facet normal 0.000129542 0.000252037 -1 + outer loop + vertex -740.147 157.54 -0.00244857 + vertex -736.395 158.495 -0.00172184 + vertex -730.08 152.347 -0.00245325 + endloop + endfacet + facet normal 0.000195507 0.000362175 -1 + outer loop + vertex -743.828 156.424 -0.00357252 + vertex -750.1 162.917 -0.00244725 + vertex -740.147 157.54 -0.00244857 + endloop + endfacet + facet normal 0.000319157 0.000590762 -1 + outer loop + vertex -747.462 155.092 -0.00551937 + vertex -753.833 161.827 -0.00357355 + vertex -743.828 156.424 -0.00357252 + endloop + endfacet + facet normal 0.000374125 0.000692602 -1 + outer loop + vertex -751.03 153.488 -0.00796524 + vertex -757.518 160.522 -0.00552058 + vertex -747.462 155.092 -0.00551937 + endloop + endfacet + facet normal 1.12979e-05 2.73255e-05 -1 + outer loop + vertex -754.467 151.555 -0.00805688 + vertex -751.03 153.488 -0.00796524 + vertex -744.208 146.265 -0.00808552 + endloop + endfacet + facet normal -0.000963148 -0.00186246 -0.999998 + outer loop + vertex -747.402 143.955 -0.000706493 + vertex -754.467 151.555 -0.00805688 + vertex -744.208 146.265 -0.00808552 + endloop + endfacet + facet normal -0.00243981 -0.00497479 -0.999985 + outer loop + vertex -750.299 141.274 0.0196984 + vertex -747.402 143.955 -0.000706493 + vertex -739.857 136.127 0.0198255 + endloop + endfacet + facet normal -0.00447554 -0.00910507 -0.999949 + outer loop + vertex -742.314 133.064 0.0587179 + vertex -750.299 141.274 0.0196984 + vertex -739.857 136.127 0.0198255 + endloop + endfacet + facet normal -0.00787523 -0.016618 -0.999831 + outer loop + vertex -744.318 129.663 0.131031 + vertex -742.314 133.064 0.0587179 + vertex -733.751 124.686 0.130521 + endloop + endfacet + facet normal -0.0156164 -0.0330539 -0.999332 + outer loop + vertex -735.371 120.998 0.277823 + vertex -744.318 129.663 0.131031 + vertex -733.751 124.686 0.130521 + endloop + endfacet + facet normal -0.0285718 -0.064106 -0.997534 + outer loop + vertex -736.925 117.117 0.571752 + vertex -735.371 120.998 0.277823 + vertex -726.263 112.315 0.574966 + endloop + endfacet + facet normal -0.0495932 -0.114072 -0.992234 + outer loop + vertex -728.046 108.307 1.12478 + vertex -726.263 112.315 0.574966 + vertex -717.308 103.667 1.12158 + endloop + endfacet + facet normal -0.0283321 -0.0653891 -0.997458 + outer loop + vertex -715.527 107.683 0.574422 + vertex -724.731 116.204 0.277226 + vertex -714.015 111.581 0.275939 + endloop + endfacet + facet normal -0.0145053 -0.0333416 -0.999339 + outer loop + vertex -724.731 116.204 0.277226 + vertex -723.139 119.901 0.130808 + vertex -714.015 111.581 0.275939 + endloop + endfacet + facet normal -0.00749773 -0.0167066 -0.999832 + outer loop + vertex -723.139 119.901 0.130808 + vertex -731.782 128.098 0.0586454 + vertex -721.199 123.322 0.0590938 + endloop + endfacet + facet normal -0.00416766 -0.00932817 -0.999948 + outer loop + vertex -731.782 128.098 0.0586454 + vertex -729.363 131.177 0.019843 + vertex -721.199 123.322 0.0590938 + endloop + endfacet + facet normal -0.00237885 -0.00504578 -0.999984 + outer loop + vertex -729.363 131.177 0.019843 + vertex -737.002 138.827 -0.000587174 + vertex -726.55 133.895 -0.00056541 + endloop + endfacet + facet normal -0.000915889 -0.00194541 -0.999998 + outer loop + vertex -737.002 138.827 -0.000587174 + vertex -733.853 141.159 -0.00800691 + vertex -726.55 133.895 -0.00056541 + endloop + endfacet + facet normal 1.52704e-05 2.83352e-05 -1 + outer loop + vertex -733.853 141.159 -0.00800691 + vertex -740.812 148.218 -0.00791316 + vertex -730.51 143.136 -0.00789981 + endloop + endfacet + facet normal 0.000352489 0.00071293 -1 + outer loop + vertex -730.51 143.136 -0.00789981 + vertex -737.299 149.849 -0.00550708 + vertex -727.044 144.79 -0.00549887 + endloop + endfacet + facet normal 0.000306121 0.000619814 -1 + outer loop + vertex -727.044 144.79 -0.00549887 + vertex -733.715 151.206 -0.00356473 + vertex -723.51 146.172 -0.00356122 + endloop + endfacet + facet normal 0.0001861 0.000385989 -1 + outer loop + vertex -723.51 146.172 -0.00356122 + vertex -719.929 147.338 -0.00244444 + vertex -713.252 141.328 -0.00352187 + endloop + endfacet + facet normal 0.000128294 0.000258942 -1 + outer loop + vertex -719.929 147.338 -0.00244444 + vertex -726.382 153.329 -0.00172101 + vertex -716.281 148.345 -0.00171579 + endloop + endfacet + facet normal 0.000110167 0.000222694 -1 + outer loop + vertex -716.281 148.345 -0.00171579 + vertex -722.591 154.193 -0.00110854 + vertex -712.543 149.234 -0.00110591 + endloop + endfacet + facet normal 9.10977e-05 0.000184116 -1 + outer loop + vertex -712.543 149.234 -0.00110591 + vertex -718.708 154.966 -0.000612212 + vertex -708.714 150.033 -0.000609992 + endloop + endfacet + facet normal 6.07167e-05 0.000128243 -1 + outer loop + vertex -708.714 150.033 -0.000609992 + vertex -704.828 150.756 -0.000281285 + vertex -698.664 145.287 -0.000608391 + endloop + endfacet + facet normal 3.35981e-05 6.78006e-05 -1 + outer loop + vertex -704.828 150.756 -0.000281285 + vertex -710.823 156.285 -0.000107844 + vertex -700.941 151.407 -0.000106546 + endloop + endfacet + facet normal 1.44394e-05 2.9184e-05 -1 + outer loop + vertex -700.941 151.407 -0.000106546 + vertex -706.919 156.843 -3.42448e-05 + vertex -697.091 151.992 -3.38908e-05 + endloop + endfacet + facet normal 5.03608e-06 1.07119e-05 -1 + outer loop + vertex -697.091 151.992 -3.38908e-05 + vertex -693.275 152.518 -9.04255e-06 + vertex -687.207 147.324 -3.41186e-05 + endloop + endfacet + facet normal 1.46365e-06 2.9971e-06 -1 + outer loop + vertex -693.275 152.518 -9.04255e-06 + vertex -699.205 157.802 -1.88591e-06 + vertex -689.485 153.01 -2.02031e-06 + endloop + endfacet + facet normal 3.47167e-07 7.31559e-07 -1 + outer loop + vertex -689.485 153.01 -2.02031e-06 + vertex -685.88 153.547 -3.75486e-07 + vertex -679.716 148.397 -2.00386e-06 + endloop + endfacet + facet normal 8.5891e-08 1.74147e-07 -1 + outer loop + vertex -685.88 153.547 -3.75486e-07 + vertex -692.219 158.83 -7.74382e-14 + vertex -683.154 154.359 -7.78793e-14 + endloop + endfacet + facet normal 3.36334e-07 7.42197e-07 -1 + outer loop + vertex -669.89 143.953 -1.97951e-06 + vertex -676.161 148.961 -3.72233e-07 + vertex -666.33 144.516 -3.64239e-07 + endloop + endfacet + facet normal 1.41486e-06 3.20869e-06 -1 + outer loop + vertex -673.57 143.408 -8.93518e-06 + vertex -669.89 143.953 -1.97951e-06 + vertex -663.614 139.094 -8.69129e-06 + endloop + endfacet + facet normal 4.95279e-06 1.09496e-05 -1 + outer loop + vertex -677.275 142.831 -3.36056e-05 + vertex -683.447 147.875 -8.94598e-06 + vertex -673.57 143.408 -8.93518e-06 + endloop + endfacet + facet normal 1.39647e-05 3.18061e-05 -1 + outer loop + vertex -681.016 142.197 -0.000106024 + vertex -677.275 142.831 -3.36056e-05 + vertex -670.951 137.836 -0.000104168 + endloop + endfacet + facet normal 3.2101e-05 7.06752e-05 -1 + outer loop + vertex -684.794 141.494 -0.000276926 + vertex -691.002 146.714 -0.000107329 + vertex -681.016 142.197 -0.000106024 + endloop + endfacet + facet normal 5.9107e-05 0.000129754 -1 + outer loop + vertex -688.57 140.721 -0.000600489 + vertex -694.834 146.036 -0.000280999 + vertex -684.794 141.494 -0.000276926 + endloop + endfacet + facet normal 8.65492e-05 0.000193369 -1 + outer loop + vertex -692.287 139.872 -0.00108634 + vertex -688.57 140.721 -0.000600489 + vertex -682.058 135.44 -0.00105808 + endloop + endfacet + facet normal 0.000103851 0.000226834 -1 + outer loop + vertex -695.919 138.933 -0.00167644 + vertex -702.44 144.462 -0.00109958 + vertex -692.287 139.872 -0.00108634 + endloop + endfacet + facet normal 0.000119655 0.000258733 -1 + outer loop + vertex -699.463 137.879 -0.0023733 + vertex -706.125 143.548 -0.00170379 + vertex -695.919 138.933 -0.00167644 + endloop + endfacet + facet normal 0.000175128 0.000375929 -1 + outer loop + vertex -702.944 136.667 -0.00343863 + vertex -709.718 142.517 -0.00242552 + vertex -699.463 137.879 -0.0023733 + endloop + endfacet + facet normal 0.000291485 0.000621183 -1 + outer loop + vertex -706.375 135.24 -0.00532514 + vertex -702.944 136.667 -0.00343863 + vertex -695.934 130.718 -0.00509065 + endloop + endfacet + facet normal 0.000335389 0.000714976 -1 + outer loop + vertex -709.739 133.54 -0.00766849 + vertex -716.733 139.923 -0.0054511 + vertex -706.375 135.24 -0.00532514 + endloop + endfacet + facet normal 2.05637e-05 7.60071e-06 -1 + outer loop + vertex -712.988 131.521 -0.00775065 + vertex -720.15 138.246 -0.0078468 + vertex -709.739 133.54 -0.00766849 + endloop + endfacet + facet normal -0.000874963 -0.00198715 -0.999998 + outer loop + vertex -716.048 129.151 -0.000362539 + vertex -723.447 136.248 -0.00799256 + vertex -712.988 131.521 -0.00775065 + endloop + endfacet + facet normal -0.0022061 -0.00520642 -0.999984 + outer loop + vertex -718.823 126.416 0.0199951 + vertex -716.048 129.151 -0.000362539 + vertex -708.198 121.819 0.0204907 + endloop + endfacet + facet normal -0.00405505 -0.0094796 -0.999947 + outer loop + vertex -710.542 118.713 0.0594363 + vertex -718.823 126.416 0.0199951 + vertex -708.198 121.819 0.0204907 + endloop + endfacet + facet normal -0.00706674 -0.0171498 -0.999828 + outer loop + vertex -712.445 115.282 0.131744 + vertex -710.542 118.713 0.0594363 + vertex -701.633 110.804 0.132129 + endloop + endfacet + facet normal -0.0138986 -0.0336464 -0.999337 + outer loop + vertex -703.174 107.096 0.278403 + vertex -712.445 115.282 0.131744 + vertex -701.633 110.804 0.132129 + endloop + endfacet + facet normal -0.0258681 -0.0654939 -0.997518 + outer loop + vertex -704.67 103.193 0.573508 + vertex -703.174 107.096 0.278403 + vertex -693.665 98.8229 0.575026 + endloop + endfacet + facet normal -0.0443281 -0.115557 -0.992311 + outer loop + vertex -695.422 94.7807 1.12424 + vertex -693.665 98.8229 0.575026 + vertex -684.275 90.5201 1.12243 + endloop + endfacet + facet normal -0.0258068 -0.0669606 -0.997422 + outer loop + vertex -682.559 94.5859 0.576189 + vertex -692.195 102.737 0.278264 + vertex -681.131 98.5204 0.275102 + endloop + endfacet + facet normal -0.0132436 -0.0339974 -0.999334 + outer loop + vertex -692.195 102.737 0.278264 + vertex -690.687 106.456 0.131798 + vertex -681.131 98.5204 0.275102 + endloop + endfacet + facet normal -0.00680654 -0.0171656 -0.999829 + outer loop + vertex -690.687 106.456 0.131798 + vertex -699.761 114.244 0.0598488 + vertex -688.851 109.907 0.0600416 + endloop + endfacet + facet normal -0.00379911 -0.00960072 -0.999947 + outer loop + vertex -699.761 114.244 0.0598488 + vertex -697.448 117.36 0.0211464 + vertex -688.851 109.907 0.0600416 + endloop + endfacet + facet normal -0.00214445 -0.00532022 -0.999984 + outer loop + vertex -697.448 117.36 0.0211464 + vertex -705.469 124.572 -2.13548e-05 + vertex -694.759 120.128 0.000654732 + endloop + endfacet + facet normal -0.000826793 -0.00211152 -0.999997 + outer loop + vertex -694.759 120.128 0.000654732 + vertex -702.452 126.96 -0.00741182 + vertex -691.79 122.535 -0.0068834 + endloop + endfacet + facet normal 1.91512e-05 -5.26929e-05 -1 + outer loop + vertex -691.79 122.535 -0.0068834 + vertex -699.25 128.999 -0.00736689 + vertex -688.635 124.592 -0.00693136 + endloop + endfacet + facet normal 0.000299046 0.000682499 -1 + outer loop + vertex -688.635 124.592 -0.00693136 + vertex -685.374 126.334 -0.00476713 + vertex -677.917 120.325 -0.00663814 + endloop + endfacet + facet normal 0.000261813 0.000576248 -1 + outer loop + vertex -685.374 126.334 -0.00476713 + vertex -692.553 132.166 -0.00328594 + vertex -682.044 127.802 -0.00304939 + endloop + endfacet + facet normal 0.000150151 0.000328559 -1 + outer loop + vertex -682.044 127.802 -0.00304939 + vertex -689.127 133.401 -0.00227304 + vertex -678.667 129.058 -0.00212975 + endloop + endfacet + facet normal 0.000100535 0.000222914 -1 + outer loop + vertex -678.667 129.058 -0.00212975 + vertex -685.635 134.478 -0.00162197 + vertex -675.23 130.157 -0.00153924 + endloop + endfacet + facet normal 9.12807e-05 0.000205083 -1 + outer loop + vertex -675.23 130.157 -0.00153924 + vertex -671.708 131.141 -0.00101579 + vertex -664.715 125.967 -0.00143867 + endloop + endfacet + facet normal 7.81498e-05 0.000183477 -1 + outer loop + vertex -671.708 131.141 -0.00101579 + vertex -678.392 136.313 -0.000589239 + vertex -668.098 132.038 -0.000569226 + endloop + endfacet + facet normal 5.43698e-05 0.00012888 -1 + outer loop + vertex -668.098 132.038 -0.000569226 + vertex -674.673 137.11 -0.000272898 + vertex -664.434 132.858 -0.00026428 + endloop + endfacet + facet normal 2.96729e-05 7.24564e-05 -1 + outer loop + vertex -664.434 132.858 -0.00026428 + vertex -660.768 133.607 -0.000101244 + vertex -654.086 128.735 -0.000255923 + endloop + endfacet + facet normal 1.30676e-05 3.13664e-05 -1 + outer loop + vertex -660.768 133.607 -0.000101244 + vertex -667.266 138.494 -3.28666e-05 + vertex -657.136 134.288 -3.24178e-05 + endloop + endfacet + facet normal 4.63851e-06 1.14004e-05 -1 + outer loop + vertex -657.136 134.288 -3.24178e-05 + vertex -653.532 134.909 -8.61437e-06 + vertex -646.896 130.208 -3.14324e-05 + endloop + endfacet + facet normal 1.34332e-06 3.22583e-06 -1 + outer loop + vertex -653.532 134.909 -8.61437e-06 + vertex -659.976 139.66 -1.94594e-06 + vertex -649.944 135.497 -1.89905e-06 + endloop + endfacet + facet normal 3.07912e-07 7.81307e-07 -1 + outer loop + vertex -649.944 135.497 -1.89905e-06 + vertex -646.568 136.14 -3.57353e-07 + vertex -639.821 131.466 -1.93142e-06 + endloop + endfacet + facet normal 7.71348e-08 1.85554e-07 -1 + outer loop + vertex -646.568 136.14 -3.57353e-07 + vertex -653.741 141.047 -7.91927e-14 + vertex -643.948 136.976 -7.95944e-14 + endloop + endfacet + facet normal 3.17727e-07 8.39697e-07 -1 + outer loop + vertex -629.722 127.595 -2.0297e-06 + vertex -636.529 132.136 -3.79589e-07 + vertex -626.521 128.293 -4.27515e-07 + endloop + endfacet + facet normal 1.23921e-06 3.50371e-06 -1 + outer loop + vertex -633.126 126.942 -8.53885e-06 + vertex -629.722 127.595 -2.0297e-06 + vertex -622.983 123.201 -9.07665e-06 + endloop + endfacet + facet normal 4.27201e-06 1.12129e-05 -1 + outer loop + vertex -636.619 126.275 -3.09312e-05 + vertex -643.34 130.849 -8.35414e-06 + vertex -633.126 126.942 -8.53885e-06 + endloop + endfacet + facet normal 1.1753e-05 3.17605e-05 -1 + outer loop + vertex -640.151 125.554 -9.53503e-05 + vertex -636.619 126.275 -3.09312e-05 + vertex -629.845 121.759 -9.47717e-05 + endloop + endfacet + facet normal 2.70463e-05 6.97811e-05 -1 + outer loop + vertex -643.708 124.763 -0.000246752 + vertex -650.476 129.506 -9.88097e-05 + vertex -640.151 125.554 -9.53503e-05 + endloop + endfacet + facet normal 4.74222e-05 0.000124025 -1 + outer loop + vertex -647.258 123.899 -0.000522339 + vertex -643.708 124.763 -0.000246752 + vertex -636.85 120.064 -0.000504399 + endloop + endfacet + facet normal 6.62816e-05 0.00016733 -1 + outer loop + vertex -650.756 122.958 -0.000911556 + vertex -657.693 127.892 -0.000545744 + vertex -647.258 123.899 -0.000522339 + endloop + endfacet + facet normal 7.31761e-05 0.0001783 -1 + outer loop + vertex -654.17 121.93 -0.00134465 + vertex -661.247 126.973 -0.000963364 + vertex -650.756 122.958 -0.000911556 + endloop + endfacet + facet normal 7.67936e-05 0.000186642 -1 + outer loop + vertex -657.502 120.79 -0.00181326 + vertex -654.17 121.93 -0.00134465 + vertex -646.926 116.897 -0.0017278 + endloop + endfacet + facet normal 0.000130048 0.000303766 -1 + outer loop + vertex -660.773 119.495 -0.00263199 + vertex -668.1 124.846 -0.00195942 + vertex -657.502 120.79 -0.00181326 + endloop + endfacet + facet normal 0.000241707 0.000588896 -1 + outer loop + vertex -664 117.991 -0.00429801 + vertex -671.423 123.57 -0.00280693 + vertex -660.773 119.495 -0.00263199 + endloop + endfacet + facet normal 0.000305175 0.0007593 -1 + outer loop + vertex -667.165 116.217 -0.00661044 + vertex -674.701 122.081 -0.00445767 + vertex -664 117.991 -0.00429801 + endloop + endfacet + facet normal -9.00078e-06 0.000173689 -1 + outer loop + vertex -670.219 114.126 -0.00694629 + vertex -667.165 116.217 -0.00661044 + vertex -659.438 110.17 -0.00773031 + endloop + endfacet + facet normal -0.000766607 -0.00192512 -0.999998 + outer loop + vertex -673.092 111.684 -4.43638e-05 + vertex -681.019 118.247 -0.00660212 + vertex -670.219 114.126 -0.00694629 + endloop + endfacet + facet normal -0.00207353 -0.00524171 -0.999984 + outer loop + vertex -675.681 108.88 0.0200259 + vertex -683.943 115.825 0.000754535 + vertex -673.092 111.684 -4.43638e-05 + endloop + endfacet + facet normal -0.00372568 -0.00952931 -0.999948 + outer loop + vertex -677.898 105.729 0.0583069 + vertex -686.59 113.042 0.021011 + vertex -675.681 108.88 0.0200259 + endloop + endfacet + facet normal -0.00659041 -0.0175091 -0.999825 + outer loop + vertex -679.674 102.257 0.130834 + vertex -677.898 105.729 0.0583069 + vertex -668.665 98.221 0.128936 + endloop + endfacet + facet normal -0.0127119 -0.0342095 -0.999334 + outer loop + vertex -670.071 94.4664 0.275362 + vertex -679.674 102.257 0.130834 + vertex -668.665 98.221 0.128936 + endloop + endfacet + facet normal -0.0241827 -0.0667697 -0.997475 + outer loop + vertex -671.445 90.5095 0.57352 + vertex -670.071 94.4664 0.275362 + vertex -660.34 86.5802 0.567327 + endloop + endfacet + facet normal -0.0406567 -0.117688 -0.992218 + outer loop + vertex -661.983 82.4708 1.12206 + vertex -660.34 86.5802 0.567327 + vertex -650.828 78.6382 1.11958 + endloop + endfacet + facet normal -0.0232628 -0.0675412 -0.997445 + outer loop + vertex -649.099 82.7025 0.573304 + vertex -658.981 90.5364 0.273327 + vertex -647.675 86.6202 0.274823 + endloop + endfacet + facet normal -0.0118153 -0.0344927 -0.999335 + outer loop + vertex -658.981 90.5364 0.273327 + vertex -657.599 94.2917 0.127368 + vertex -647.675 86.6202 0.274823 + endloop + endfacet + facet normal -0.00635045 -0.0175485 -0.999826 + outer loop + vertex -657.599 94.2917 0.127368 + vertex -666.942 101.712 0.0564716 + vertex -655.913 97.7891 0.0552738 + endloop + endfacet + facet normal -0.00357352 -0.00972397 -0.999946 + outer loop + vertex -655.913 97.7891 0.0552738 + vertex -664.79 104.886 0.0179893 + vertex -653.809 100.978 0.0167436 + endloop + endfacet + facet normal -0.00190421 -0.00509123 -0.999985 + outer loop + vertex -653.809 100.978 0.0167436 + vertex -662.256 107.71 -0.00144437 + vertex -651.329 103.823 -0.00246585 + endloop + endfacet + facet normal -0.000590155 -0.00170145 -0.999998 + outer loop + vertex -651.329 103.823 -0.00246585 + vertex -648.568 106.306 -0.00831957 + vertex -640.09 99.9116 -0.00244271 + endloop + endfacet + facet normal 0.000115951 0.000388871 -1 + outer loop + vertex -648.568 106.306 -0.00831957 + vertex -656.439 112.28 -0.00690903 + vertex -645.625 108.437 -0.00714957 + endloop + endfacet + facet normal 0.000337296 0.000965818 -0.999999 + outer loop + vertex -645.625 108.437 -0.00714957 + vertex -653.326 114.069 -0.00430804 + vertex -642.566 110.245 -0.00437252 + endloop + endfacet + facet normal 0.000247962 0.000694796 -1 + outer loop + vertex -642.566 110.245 -0.00437252 + vertex -650.148 115.587 -0.00254079 + vertex -639.442 111.78 -0.00253135 + endloop + endfacet + facet normal 0.000122321 0.000348185 -1 + outer loop + vertex -639.442 111.78 -0.00253135 + vertex -636.282 113.11 -0.00168169 + vertex -628.447 107.975 -0.00251101 + endloop + endfacet + facet normal 6.90502e-05 0.000184848 -1 + outer loop + vertex -636.282 113.11 -0.00168169 + vertex -643.65 118.056 -0.00127615 + vertex -633.058 114.284 -0.00124195 + endloop + endfacet + facet normal 6.26358e-05 0.000170772 -1 + outer loop + vertex -633.058 114.284 -0.00124195 + vertex -640.293 119.103 -0.000872149 + vertex -629.759 115.35 -0.000853249 + endloop + endfacet + facet normal 5.70828e-05 0.000165394 -1 + outer loop + vertex -629.759 115.35 -0.000853249 + vertex -626.377 116.331 -0.000497982 + vertex -618.943 111.6 -0.000856216 + endloop + endfacet + facet normal 4.28411e-05 0.00012045 -1 + outer loop + vertex -626.377 116.331 -0.000497982 + vertex -633.353 120.948 -0.000240727 + vertex -622.929 117.235 -0.000241415 + endloop + endfacet + facet normal 2.39691e-05 7.23535e-05 -1 + outer loop + vertex -622.929 117.235 -0.000241415 + vertex -619.475 118.067 -9.84294e-05 + vertex -612.218 113.524 -0.000253165 + endloop + endfacet + facet normal 1.14227e-05 3.28266e-05 -1 + outer loop + vertex -619.475 118.067 -9.84294e-05 + vertex -626.371 122.501 -3.16355e-05 + vertex -616.093 118.839 -3.4428e-05 + endloop + endfacet + facet normal 4.09152e-06 1.37097e-05 -1 + outer loop + vertex -616.093 118.839 -3.4428e-05 + vertex -612.837 119.579 -1.09705e-05 + vertex -605.592 115.199 -4.13779e-05 + endloop + endfacet + facet normal 1.44968e-06 4.30141e-06 -1 + outer loop + vertex -612.837 119.579 -1.09705e-05 + vertex -619.712 123.894 -2.37451e-06 + vertex -609.625 120.288 -3.26363e-06 + endloop + endfacet + facet normal 3.13886e-07 1.12451e-06 -1 + outer loop + vertex -619.712 123.894 -2.37451e-06 + vertex -616.514 124.59 -5.88605e-07 + vertex -609.625 120.288 -3.26363e-06 + endloop + endfacet + facet normal 1.19518e-07 3.24107e-07 -1 + outer loop + vertex -616.514 124.59 -5.88605e-07 + vertex -623.751 129.075 -8.0374e-14 + vertex -613.228 125.194 -8.07568e-14 + endloop + endfacet + facet normal 6.07838e-07 1.94406e-06 -1 + outer loop + vertex -599.114 116.651 -4.89268e-06 + vertex -606.281 120.939 -9.1335e-07 + vertex -595.608 117.275 -1.54829e-06 + endloop + endfacet + facet normal 1.56061e-06 6.47367e-06 -1 + outer loop + vertex -602.432 115.967 -1.44979e-05 + vertex -599.114 116.651 -4.89268e-06 + vertex -591.601 112.324 -2.11782e-05 + endloop + endfacet + facet normal 5.64406e-06 1.86144e-05 -1 + outer loop + vertex -594.812 111.561 -5.35164e-05 + vertex -602.432 115.967 -1.44979e-05 + vertex -591.601 112.324 -2.11782e-05 + endloop + endfacet + facet normal 1.13082e-05 4.43919e-05 -1 + outer loop + vertex -597.946 110.708 -0.000126816 + vertex -594.812 111.561 -5.35164e-05 + vertex -587.329 107.264 -0.00015962 + endloop + endfacet + facet normal 2.49365e-05 7.88465e-05 -1 + outer loop + vertex -601.208 109.813 -0.000278744 + vertex -608.845 114.385 -0.00010865 + vertex -597.946 110.708 -0.000126816 + endloop + endfacet + facet normal 3.88471e-05 0.000133111 -1 + outer loop + vertex -604.527 108.862 -0.000534267 + vertex -601.208 109.813 -0.000278744 + vertex -593.695 105.361 -0.000579429 + endloop + endfacet + facet normal 5.38751e-05 0.000166993 -1 + outer loop + vertex -607.803 107.843 -0.000880783 + vertex -615.611 112.598 -0.000507387 + vertex -604.527 108.862 -0.000534267 + endloop + endfacet + facet normal 5.49492e-05 0.00018244 -1 + outer loop + vertex -610.981 106.738 -0.0012571 + vertex -607.803 107.843 -0.000880783 + vertex -600.027 103.214 -0.00129816 + endloop + endfacet + facet normal 6.22848e-05 0.000189947 -1 + outer loop + vertex -614.082 105.523 -0.00168104 + vertex -622.182 110.515 -0.00123739 + vertex -610.981 106.738 -0.0012571 + endloop + endfacet + facet normal 0.00011328 0.000336688 -1 + outer loop + vertex -617.137 104.161 -0.00248577 + vertex -625.34 109.32 -0.00167799 + vertex -614.082 105.523 -0.00168104 + endloop + endfacet + facet normal 0.000232264 0.000680127 -1 + outer loop + vertex -620.142 102.587 -0.00425394 + vertex -617.137 104.161 -0.00248577 + vertex -609.078 99.0067 -0.00411934 + endloop + endfacet + facet normal 0.000331536 0.000955746 -0.999999 + outer loop + vertex -623.09 100.731 -0.00700521 + vertex -631.514 106.421 -0.00435983 + vertex -620.142 102.587 -0.00425394 + endloop + endfacet + facet normal 0.000155323 0.000411459 -1 + outer loop + vertex -625.917 98.5381 -0.00834659 + vertex -634.518 104.592 -0.00719143 + vertex -623.09 100.731 -0.00700521 + endloop + endfacet + facet normal -0.00059012 -0.0017924 -0.999998 + outer loop + vertex -628.55 95.9881 -0.00222225 + vertex -637.404 102.434 -0.00855055 + vertex -625.917 98.5381 -0.00834659 + endloop + endfacet + facet normal -0.00192221 -0.0057806 -0.999981 + outer loop + vertex -630.915 93.0882 0.0190883 + vertex -628.55 95.9881 -0.00222225 + vertex -619.653 89.437 0.018545 + endloop + endfacet + facet normal -0.0036063 -0.0110388 -0.999933 + outer loop + vertex -632.954 89.8686 0.0619849 + vertex -642.52 97.0413 0.0173002 + vertex -630.915 93.0882 0.0190883 + endloop + endfacet + facet normal -0.00608994 -0.0189987 -0.999801 + outer loop + vertex -634.661 86.3882 0.138515 + vertex -644.59 93.8383 0.0574279 + vertex -632.954 89.8686 0.0619849 + endloop + endfacet + facet normal -0.0114719 -0.0355281 -0.999303 + outer loop + vertex -636.117 82.6928 0.28661 + vertex -646.272 90.3484 0.131009 + vertex -634.661 86.3882 0.138515 + endloop + endfacet + facet normal -0.021601 -0.0676548 -0.997475 + outer loop + vertex -637.601 78.8222 0.581281 + vertex -636.117 82.6928 0.28661 + vertex -626.324 75.1774 0.584281 + endloop + endfacet + facet normal -0.0378251 -0.1181 -0.992281 + outer loop + vertex -628.028 71.1151 1.13273 + vertex -626.324 75.1774 0.584281 + vertex -617.869 68.1713 1.09582 + endloop + endfacet + facet normal -0.0192994 -0.0635766 -0.99779 + outer loop + vertex -616.511 72.3793 0.553282 + vertex -624.85 79.0464 0.289763 + vertex -615.121 76.3353 0.274326 + endloop + endfacet + facet normal -0.010075 -0.0336706 -0.999382 + outer loop + vertex -615.121 76.3353 0.274326 + vertex -623.343 82.7374 0.141525 + vertex -613.592 80.095 0.132243 + endloop + endfacet + facet normal -0.0060128 -0.0192459 -0.999797 + outer loop + vertex -613.592 80.095 0.132243 + vertex -621.633 86.2242 0.0626142 + vertex -611.974 83.5556 0.0558987 + endloop + endfacet + facet normal -0.00381792 -0.0108943 -0.999933 + outer loop + vertex -611.974 83.5556 0.0558987 + vertex -610.016 86.5936 0.0153226 + vertex -605.691 82.4307 0.0441653 + endloop + endfacet + facet normal -0.00163732 -0.00518575 -0.999985 + outer loop + vertex -610.016 86.5936 0.0153226 + vertex -617.326 92.3224 -0.00241722 + vertex -607.586 89.3965 -0.00319154 + endloop + endfacet + facet normal -0.000431131 -0.00146336 -0.999999 + outer loop + vertex -607.586 89.3965 -0.00319154 + vertex -614.708 94.8935 -0.0081649 + vertex -604.96 92.0475 -0.0082032 + endloop + endfacet + facet normal 0.000177706 0.000525965 -1 + outer loop + vertex -604.96 92.0475 -0.0082032 + vertex -611.936 97.1286 -0.00677035 + vertex -602.361 94.3359 -0.00653785 + endloop + endfacet + facet normal 0.000255371 0.000982364 -0.999999 + outer loop + vertex -602.361 94.3359 -0.00653785 + vertex -599.561 96.149 -0.0040417 + vertex -596.004 92.9025 -0.00632248 + endloop + endfacet + facet normal 0.00017501 0.000616481 -1 + outer loop + vertex -599.561 96.149 -0.0040417 + vertex -606.087 100.58 -0.00245224 + vertex -596.475 97.7212 -0.00253233 + endloop + endfacet + facet normal 9.22161e-05 0.000335163 -1 + outer loop + vertex -596.475 97.7212 -0.00253233 + vertex -603.078 101.974 -0.00171576 + vertex -593.498 99.1909 -0.00176516 + endloop + endfacet + facet normal 4.60389e-05 0.000225492 -1 + outer loop + vertex -593.498 99.1909 -0.00176516 + vertex -590.514 100.427 -0.00134901 + vertex -587.027 97.7987 -0.00178119 + endloop + endfacet + facet normal 4.99115e-05 0.000190627 -1 + outer loop + vertex -590.514 100.427 -0.00134901 + vertex -596.894 104.325 -0.000924487 + vertex -587.459 101.541 -0.000984211 + endloop + endfacet + facet normal 3.96514e-05 0.000208411 -1 + outer loop + vertex -587.459 101.541 -0.000984211 + vertex -584.304 102.567 -0.000645393 + vertex -581.037 100.059 -0.0010384 + endloop + endfacet + facet normal 3.79186e-05 0.000148615 -1 + outer loop + vertex -584.304 102.567 -0.000645393 + vertex -590.459 106.33 -0.000319436 + vertex -581.179 103.553 -0.000380247 + endloop + endfacet + facet normal 2.07082e-05 0.000122217 -1 + outer loop + vertex -581.179 103.553 -0.000380247 + vertex -578.076 104.479 -0.000202919 + vertex -574.856 102.037 -0.000434577 + endloop + endfacet + facet normal 1.53542e-05 6.15352e-05 -1 + outer loop + vertex -578.076 104.479 -0.000202919 + vertex -584.2 108.12 -7.28562e-05 + vertex -574.881 105.314 -0.00010243 + endloop + endfacet + facet normal 6.7698e-06 4.54247e-05 -1 + outer loop + vertex -574.881 105.314 -0.00010243 + vertex -571.341 106 -4.73401e-05 + vertex -568.458 103.719 -0.0001314 + endloop + endfacet + facet normal 7.74112e-06 3.45281e-05 -1 + outer loop + vertex -564.605 104.205 -7.78898e-05 + vertex -567.356 106.477 -2.07193e-05 + vertex -561.847 105.026 -2.81737e-05 + endloop + endfacet + facet normal 4.11415e-06 4.67028e-05 -1 + outer loop + vertex -564.605 104.205 -7.78898e-05 + vertex -561.847 105.026 -2.81737e-05 + vertex -559.381 103.913 -7.00412e-05 + endloop + endfacet + facet normal 2.22976e-06 1.36032e-05 -1 + outer loop + vertex -567.356 106.477 -2.07193e-05 + vertex -563.688 106.724 -9.17726e-06 + vertex -561.847 105.026 -2.81737e-05 + endloop + endfacet + facet normal 2.73356e-06 1.46401e-05 -1 + outer loop + vertex -580.785 108.841 -3.15548e-05 + vertex -576.779 109.384 -1.2657e-05 + vertex -571.341 106 -4.73401e-05 + endloop + endfacet + facet normal 8.11702e-07 3.86905e-06 -1 + outer loop + vertex -588 112.951 -7.96299e-06 + vertex -584.337 113.574 -2.57903e-06 + vertex -576.779 109.384 -1.2657e-05 + endloop + endfacet + facet normal 5.12878e-07 1.54201e-06 -1 + outer loop + vertex -584.337 113.574 -2.57903e-06 + vertex -593.093 118.159 -8.14509e-14 + vertex -583.066 114.824 -8.178e-14 + endloop + endfacet + facet normal 2.56889e-06 8.57104e-06 -1 + outer loop + vertex -567.356 106.477 -2.07193e-05 + vertex -572.144 109.845 -4.15409e-06 + vertex -563.688 106.724 -9.17726e-06 + endloop + endfacet + facet normal 1.88799e-06 1.32327e-05 -1 + outer loop + vertex -561.847 105.026 -2.81737e-05 + vertex -563.688 106.724 -9.17726e-06 + vertex -559.422 105.645 -1.54023e-05 + endloop + endfacet + facet normal -2.76815e-06 3.14656e-05 -1 + outer loop + vertex -561.847 105.026 -2.81737e-05 + vertex -559.422 105.645 -1.54023e-05 + vertex -559.381 103.913 -7.00412e-05 + endloop + endfacet + facet normal 1.15196e-05 4.87503e-05 -1 + outer loop + vertex -559.876 102.44 -0.000161103 + vertex -555.465 103.652 -5.1242e-05 + vertex -555.998 101.856 -0.000144923 + endloop + endfacet + facet normal 7.28727e-06 0.000103448 -1 + outer loop + vertex -559.381 103.913 -7.00412e-05 + vertex -565.056 102.226 -0.000285875 + vertex -564.605 104.205 -7.78898e-05 + endloop + endfacet + facet normal 3.01284e-05 0.00010797 -1 + outer loop + vertex -563.109 101.401 -0.000370725 + vertex -559.876 102.44 -0.000161103 + vertex -559.977 101.268 -0.00029069 + endloop + endfacet + facet normal 4.21182e-05 0.000208808 -1 + outer loop + vertex -566.916 100.381 -0.000744124 + vertex -563.109 101.401 -0.000370725 + vertex -562.611 100.065 -0.000628778 + endloop + endfacet + facet normal 1.56975e-05 0.000208952 -1 + outer loop + vertex -565.056 102.226 -0.000285875 + vertex -571.438 100.591 -0.000727614 + vertex -571.218 102.708 -0.000281846 + endloop + endfacet + facet normal 4.07563e-05 0.000273881 -1 + outer loop + vertex -571.764 99.0137 -0.00131609 + vertex -566.916 100.381 -0.000744124 + vertex -566.596 98.4201 -0.00126801 + endloop + endfacet + facet normal 1.58442e-05 0.000288164 -1 + outer loop + vertex -571.438 100.591 -0.000727614 + vertex -577.321 98.5442 -0.00141074 + vertex -577.378 100.836 -0.000751126 + endloop + endfacet + facet normal 1.58738e-05 0.000320307 -1 + outer loop + vertex -575.283 97.7161 -0.00178756 + vertex -571.764 99.0137 -0.00131609 + vertex -571.79 97.6722 -0.0017462 + endloop + endfacet + facet normal 1.65494e-05 0.000191732 -1 + outer loop + vertex -579.059 96.4341 -0.00209586 + vertex -575.283 97.7161 -0.00178756 + vertex -574.569 95.8383 -0.00213579 + endloop + endfacet + facet normal 1.45143e-05 0.000336978 -1 + outer loop + vertex -577.321 98.5442 -0.00141074 + vertex -583.302 96.3577 -0.00223434 + vertex -583.474 98.7391 -0.00143436 + endloop + endfacet + facet normal 0.000108157 0.000295276 -1 + outer loop + vertex -583.193 94.4818 -0.00311952 + vertex -579.059 96.4341 -0.00209586 + vertex -579.324 94.649 -0.00265164 + endloop + endfacet + facet normal 3.66316e-05 0.000755935 -1 + outer loop + vertex -583.302 96.3577 -0.00223434 + vertex -587.776 93.5699 -0.00450561 + vertex -589.211 96.1533 -0.00260531 + endloop + endfacet + facet normal 0.000217445 0.000713167 -1 + outer loop + vertex -586.241 92.4985 -0.00519661 + vertex -583.193 94.4818 -0.00311952 + vertex -581.75 92.1609 -0.00446087 + endloop + endfacet + facet normal 0.000310282 0.000972678 -0.999999 + outer loop + vertex -589.64 90.8089 -0.00789463 + vertex -586.241 92.4985 -0.00519661 + vertex -586.43 90.0831 -0.00760482 + endloop + endfacet + facet normal 0.000110989 0.000974426 -1 + outer loop + vertex -587.776 93.5699 -0.00450561 + vertex -592.69 90.9615 -0.00759267 + vertex -592.714 94.2617 -0.00437945 + endloop + endfacet + facet normal -0.000348929 0.000632772 -1 + outer loop + vertex -592.79 88.135 -0.00848738 + vertex -589.64 90.8089 -0.00789463 + vertex -589.918 88.4038 -0.00931934 + endloop + endfacet + facet normal 0.000182137 -0.000651224 -1 + outer loop + vertex -592.69 90.9615 -0.00759267 + vertex -595.839 87.5791 -0.00596367 + vertex -597.779 90.5964 -0.00828188 + endloop + endfacet + facet normal -0.00149686 -0.00256749 -0.999996 + outer loop + vertex -595.361 84.6927 0.0042001 + vertex -592.79 88.135 -0.00848738 + vertex -591.538 85.3459 -0.0031994 + endloop + endfacet + facet normal -0.000603975 -0.00481839 -0.999988 + outer loop + vertex -595.839 87.5791 -0.00596367 + vertex -598.637 84.1836 0.0120873 + vertex -600.448 87.7592 -0.00404786 + endloop + endfacet + facet normal -0.0030245 -0.00781533 -0.999965 + outer loop + vertex -598.105 80.9645 0.0416374 + vertex -595.361 84.6927 0.0042001 + vertex -593.457 80.9773 0.0274787 + endloop + endfacet + facet normal -0.00215014 -0.0115804 -0.999931 + outer loop + vertex -598.637 84.1836 0.0120873 + vertex -601.797 80.4221 0.0624451 + vertex -603.131 84.7507 0.0151828 + endloop + endfacet + facet normal -0.00568038 -0.0141987 -0.999883 + outer loop + vertex -600.706 77.2904 0.108588 + vertex -598.105 80.9645 0.0416374 + vertex -596.999 77.3782 0.0862832 + endloop + endfacet + facet normal -0.00324452 -0.022068 -0.999751 + outer loop + vertex -601.797 80.4221 0.0624451 + vertex -603.664 75.9401 0.167437 + vertex -606.541 79.1553 0.105803 + endloop + endfacet + facet normal -0.0137098 -0.0234897 -0.99963 + outer loop + vertex -602.327 73.5647 0.218361 + vertex -600.706 77.2904 0.108588 + vertex -599.625 74.6912 0.15484 + endloop + endfacet + facet normal -0.00777839 -0.0430062 -0.999045 + outer loop + vertex -603.664 75.9401 0.167437 + vertex -604.995 71.2177 0.381081 + vertex -608.053 75.2137 0.232881 + endloop + endfacet + facet normal -0.0169273 -0.046666 -0.998767 + outer loop + vertex -602.73 70.0509 0.389379 + vertex -602.327 73.5647 0.218361 + vertex -599.667 71.0495 0.290799 + endloop + endfacet + facet normal -0.0377717 -0.0794824 -0.99612 + outer loop + vertex -606.462 66.649 0.80127 + vertex -604.995 71.2177 0.381081 + vertex -603.911 66.8305 0.690053 + endloop + endfacet + facet normal -0.0491173 -0.134481 -0.989698 + outer loop + vertex -604.973 62.6766 1.30718 + vertex -603.911 66.8305 0.690053 + vertex -602.368 63.0885 1.12195 + endloop + endfacet + facet normal -0.033294 -0.13854 -0.989797 + outer loop + vertex -603.911 66.8305 0.690053 + vertex -604.973 62.6766 1.30718 + vertex -606.462 66.649 0.80127 + endloop + endfacet + facet normal -0.0507167 -0.144863 -0.988151 + outer loop + vertex -607.26 62.3015 1.47955 + vertex -606.462 66.649 0.80127 + vertex -604.973 62.6766 1.30718 + endloop + endfacet + facet normal -0.0478371 -0.15406 -0.986903 + outer loop + vertex -596.706 59.8171 1.41601 + vertex -593.502 62.8055 0.794206 + vertex -586.964 57.3236 1.33304 + endloop + endfacet + facet normal -0.0369424 -0.1413 -0.989277 + outer loop + vertex -586.964 57.3236 1.33304 + vertex -593.502 62.8055 0.794206 + vertex -585.637 61.3066 0.714564 + endloop + endfacet + facet normal -0.0396514 -0.1404 -0.989301 + outer loop + vertex -586.964 57.3236 1.33304 + vertex -585.637 61.3066 0.714564 + vertex -576.081 54.4531 1.3042 + endloop + endfacet + facet normal -0.0373828 -0.137282 -0.989826 + outer loop + vertex -576.081 54.4531 1.3042 + vertex -585.637 61.3066 0.714564 + vertex -574.83 58.5762 0.68511 + endloop + endfacet + facet normal -0.0385783 -0.13692 -0.989831 + outer loop + vertex -576.081 54.4531 1.3042 + vertex -574.83 58.5762 0.68511 + vertex -564.271 51.171 1.29792 + endloop + endfacet + facet normal -0.0376694 -0.135642 -0.990042 + outer loop + vertex -564.271 51.171 1.29792 + vertex -574.83 58.5762 0.68511 + vertex -562.869 55.2114 0.691031 + endloop + endfacet + facet normal -0.0371468 -0.135822 -0.990037 + outer loop + vertex -564.271 51.171 1.29792 + vertex -562.869 55.2114 0.691031 + vertex -552.223 47.7745 1.31184 + endloop + endfacet + facet normal -0.0378229 -0.136777 -0.98988 + outer loop + vertex -552.223 47.7745 1.31184 + vertex -562.869 55.2114 0.691031 + vertex -550.671 51.7316 0.705744 + endloop + endfacet + facet normal -0.0215365 -0.0783075 -0.996697 + outer loop + vertex -574.83 58.5762 0.68511 + vertex -573.806 62.6327 0.344276 + vertex -562.869 55.2114 0.691031 + endloop + endfacet + facet normal -0.02215 -0.0792076 -0.996612 + outer loop + vertex -562.869 55.2114 0.691031 + vertex -573.806 62.6327 0.344276 + vertex -561.762 59.1749 0.351405 + endloop + endfacet + facet normal -0.0114688 -0.0420078 -0.999051 + outer loop + vertex -573.806 62.6327 0.344276 + vertex -572.642 66.51 0.167882 + vertex -561.762 59.1749 0.351405 + endloop + endfacet + facet normal -0.0120949 -0.0418199 -0.999052 + outer loop + vertex -573.806 62.6327 0.344276 + vertex -583.791 69.6549 0.171216 + vertex -572.642 66.51 0.167882 + endloop + endfacet + facet normal -0.00669594 -0.0226787 -0.99972 + outer loop + vertex -583.791 69.6549 0.171216 + vertex -581.886 73.1595 0.0789544 + vertex -572.642 66.51 0.167882 + endloop + endfacet + facet normal -0.00628268 -0.0221043 -0.999736 + outer loop + vertex -572.642 66.51 0.167882 + vertex -581.886 73.1595 0.0789544 + vertex -571.185 70.1843 0.0774869 + endloop + endfacet + facet normal -0.00371181 -0.0128574 -0.99991 + outer loop + vertex -581.886 73.1595 0.0789544 + vertex -580.12 76.5272 0.0290962 + vertex -571.185 70.1843 0.0774869 + endloop + endfacet + facet normal -0.00350753 -0.0129645 -0.99991 + outer loop + vertex -581.886 73.1595 0.0789544 + vertex -587.735 78.0842 0.03562 + vertex -580.12 76.5272 0.0290962 + endloop + endfacet + facet normal -0.00690041 -0.0225675 -0.999722 + outer loop + vertex -583.791 69.6549 0.171216 + vertex -590.734 75.7278 0.0820466 + vertex -581.886 73.1595 0.0789544 + endloop + endfacet + facet normal -0.0118377 -0.0414545 -0.99907 + outer loop + vertex -585.031 65.5912 0.354526 + vertex -583.791 69.6549 0.171216 + vertex -573.806 62.6327 0.344276 + endloop + endfacet + facet normal -0.0117055 -0.0414948 -0.99907 + outer loop + vertex -585.031 65.5912 0.354526 + vertex -593.899 72.0924 0.188406 + vertex -583.791 69.6549 0.171216 + endloop + endfacet + facet normal -0.0215474 -0.0783047 -0.996697 + outer loop + vertex -574.83 58.5762 0.68511 + vertex -585.031 65.5912 0.354526 + vertex -573.806 62.6327 0.344276 + endloop + endfacet + facet normal -0.0230493 -0.0804789 -0.99649 + outer loop + vertex -585.637 61.3066 0.714564 + vertex -585.031 65.5912 0.354526 + vertex -574.83 58.5762 0.68511 + endloop + endfacet + facet normal -0.0206641 -0.0808182 -0.996515 + outer loop + vertex -585.637 61.3066 0.714564 + vertex -593.917 67.0095 0.423758 + vertex -585.031 65.5912 0.354526 + endloop + endfacet + facet normal -0.0273095 -0.0904166 -0.99553 + outer loop + vertex -593.502 62.8055 0.794206 + vertex -593.917 67.0095 0.423758 + vertex -585.637 61.3066 0.714564 + endloop + endfacet + facet normal -0.00825457 -0.0731284 -0.997288 + outer loop + vertex -599.856 66.2373 0.645224 + vertex -602.73 70.0509 0.389379 + vertex -599.667 71.0495 0.290799 + endloop + endfacet + facet normal -0.0151555 -0.0461943 -0.998818 + outer loop + vertex -593.917 67.0095 0.423758 + vertex -593.899 72.0924 0.188406 + vertex -585.031 65.5912 0.354526 + endloop + endfacet + facet normal -0.00797774 -0.0372161 -0.999275 + outer loop + vertex -599.667 71.0495 0.290799 + vertex -602.327 73.5647 0.218361 + vertex -599.625 74.6912 0.15484 + endloop + endfacet + facet normal -0.00554014 -0.0200949 -0.999783 + outer loop + vertex -599.625 74.6912 0.15484 + vertex -600.706 77.2904 0.108588 + vertex -596.999 77.3782 0.0862832 + endloop + endfacet + facet normal -0.00723434 -0.0229491 -0.99971 + outer loop + vertex -593.899 72.0924 0.188406 + vertex -590.734 75.7278 0.0820466 + vertex -583.791 69.6549 0.171216 + endloop + endfacet + facet normal -0.003009 -0.0133753 -0.999906 + outer loop + vertex -596.999 77.3782 0.0862832 + vertex -598.105 80.9645 0.0416374 + vertex -593.457 80.9773 0.0274787 + endloop + endfacet + facet normal -0.00443126 -0.0140614 -0.999891 + outer loop + vertex -590.734 75.7278 0.0820466 + vertex -587.735 78.0842 0.03562 + vertex -581.886 73.1595 0.0789544 + endloop + endfacet + facet normal -0.00242879 -0.00768845 -0.999967 + outer loop + vertex -587.735 78.0842 0.03562 + vertex -587.133 81.6205 0.00696929 + vertex -580.12 76.5272 0.0290962 + endloop + endfacet + facet normal -0.00175674 -0.00676311 -0.999976 + outer loop + vertex -580.12 76.5272 0.0290962 + vertex -587.133 81.6205 0.00696929 + vertex -578.179 80.0389 0.001935 + endloop + endfacet + facet normal -0.000795422 -0.00667293 -0.999977 + outer loop + vertex -593.457 80.9773 0.0274787 + vertex -595.361 84.6927 0.0042001 + vertex -591.538 85.3459 -0.0031994 + endloop + endfacet + facet normal -0.00107799 -0.0029202 -0.999995 + outer loop + vertex -587.133 81.6205 0.00696929 + vertex -585.154 85.7514 -0.00722734 + vertex -578.179 80.0389 0.001935 + endloop + endfacet + facet normal -0.000107752 -0.00194427 -0.999998 + outer loop + vertex -591.538 85.3459 -0.0031994 + vertex -592.79 88.135 -0.00848738 + vertex -589.918 88.4038 -0.00931934 + endloop + endfacet + facet normal 0.000218551 0.000567074 -1 + outer loop + vertex -589.918 88.4038 -0.00931934 + vertex -589.64 90.8089 -0.00789463 + vertex -586.43 90.0831 -0.00760482 + endloop + endfacet + facet normal -4.92066e-05 7.18867e-05 -1 + outer loop + vertex -585.154 85.7514 -0.00722734 + vertex -580.38 88.2308 -0.00728403 + vertex -575.233 83.1976 -0.00789911 + endloop + endfacet + facet normal 0.000237382 0.000978398 -0.999999 + outer loop + vertex -586.43 90.0831 -0.00760482 + vertex -586.241 92.4985 -0.00519661 + vertex -581.75 92.1609 -0.00446087 + endloop + endfacet + facet normal 0.000246189 0.000887722 -1 + outer loop + vertex -580.38 88.2308 -0.00728403 + vertex -576.226 89.7323 -0.00492838 + vertex -571.646 85.6837 -0.00739494 + endloop + endfacet + facet normal 0.00019272 0.000609943 -1 + outer loop + vertex -576.226 89.7323 -0.00492838 + vertex -574.435 92.4279 -0.00293896 + vertex -568.369 87.9361 -0.00450985 + endloop + endfacet + facet normal 9.34278e-05 0.000636044 -1 + outer loop + vertex -581.75 92.1609 -0.00446087 + vertex -583.193 94.4818 -0.00311952 + vertex -579.324 94.649 -0.00265164 + endloop + endfacet + facet normal 3.17964e-05 0.000306629 -1 + outer loop + vertex -579.324 94.649 -0.00265164 + vertex -579.059 96.4341 -0.00209586 + vertex -574.569 95.8383 -0.00213579 + endloop + endfacet + facet normal 9.32276e-05 0.000244052 -1 + outer loop + vertex -574.435 92.4279 -0.00293896 + vertex -569.315 93.5041 -0.00219909 + vertex -564.912 89.9197 -0.0026633 + endloop + endfacet + facet normal 5.13705e-05 0.000113814 -1 + outer loop + vertex -569.315 93.5041 -0.00219909 + vertex -566.963 95.5811 -0.00184184 + vertex -561.287 91.6162 -0.00200151 + endloop + endfacet + facet normal 1.4245e-05 0.000190856 -1 + outer loop + vertex -574.569 95.8383 -0.00213579 + vertex -575.283 97.7161 -0.00178756 + vertex -571.79 97.6722 -0.0017462 + endloop + endfacet + facet normal 4.60223e-05 0.000319732 -1 + outer loop + vertex -571.79 97.6722 -0.0017462 + vertex -571.764 99.0137 -0.00131609 + vertex -566.596 98.4201 -0.00126801 + endloop + endfacet + facet normal 5.66373e-05 0.00014895 -1 + outer loop + vertex -566.963 95.5811 -0.00184184 + vertex -561.682 96.1909 -0.00145189 + vertex -557.555 93.0583 -0.00168477 + endloop + endfacet + facet normal 6.15071e-05 0.000155365 -1 + outer loop + vertex -557.555 93.0583 -0.00168477 + vertex -561.682 96.1909 -0.00145189 + vertex -553.821 94.3201 -0.00125905 + endloop + endfacet + facet normal 7.53937e-05 0.000213715 -1 + outer loop + vertex -561.682 96.1909 -0.00145189 + vertex -559.259 97.6954 -0.00094773 + vertex -553.821 94.3201 -0.00125905 + endloop + endfacet + facet normal 4.69686e-05 0.000274895 -1 + outer loop + vertex -566.596 98.4201 -0.00126801 + vertex -566.916 100.381 -0.000744124 + vertex -562.611 100.065 -0.000628778 + endloop + endfacet + facet normal 6.26642e-05 0.000181045 -1 + outer loop + vertex -559.259 97.6954 -0.00094773 + vertex -555.685 99.4053 -0.000414203 + vertex -550.294 95.6826 -0.000750355 + endloop + endfacet + facet normal 3.42792e-05 0.000205883 -1 + outer loop + vertex -562.611 100.065 -0.000628778 + vertex -563.109 101.401 -0.000370725 + vertex -559.977 101.268 -0.00029069 + endloop + endfacet + facet normal 2.05685e-05 0.000108793 -1 + outer loop + vertex -559.977 101.268 -0.00029069 + vertex -559.876 102.44 -0.000161103 + vertex -555.998 101.856 -0.000144923 + endloop + endfacet + facet normal 3.34746e-05 9.88109e-05 -1 + outer loop + vertex -555.685 99.4053 -0.000414203 + vertex -550.331 100.279 -0.00014869 + vertex -546.28 96.8979 -0.000347132 + endloop + endfacet + facet normal 2.9041e-05 9.34982e-05 -1 + outer loop + vertex -546.28 96.8979 -0.000347132 + vertex -550.331 100.279 -0.00014869 + vertex -542.181 97.9458 -0.000130102 + endloop + endfacet + facet normal 1.1828e-05 4.86588e-05 -1 + outer loop + vertex -555.998 101.856 -0.000144923 + vertex -555.465 103.652 -5.1242e-05 + vertex -552.078 102.925 -4.6514e-05 + endloop + endfacet + facet normal 1.51275e-05 4.48862e-05 -1 + outer loop + vertex -550.331 100.279 -0.00014869 + vertex -546.603 101.37 -4.3286e-05 + vertex -542.181 97.9458 -0.000130102 + endloop + endfacet + facet normal 6.48056e-06 2.14603e-05 -1 + outer loop + vertex -552.078 102.925 -4.6514e-05 + vertex -552.205 105.131 -8.27363e-14 + vertex -551.859 105.027 -8.27466e-14 + endloop + endfacet + facet normal 1.30776e-05 4.22389e-05 -1 + outer loop + vertex -542.181 97.9458 -0.000130102 + vertex -546.603 101.37 -4.3286e-05 + vertex -538.533 99.0128 -3.73283e-05 + endloop + endfacet + facet normal 3.02424e-05 8.87975e-05 -1 + outer loop + vertex -546.28 96.8979 -0.000347132 + vertex -542.181 97.9458 -0.000130102 + vertex -536.05 93.9903 -0.000295917 + endloop + endfacet + facet normal 5.08291e-05 0.000163906 -1 + outer loop + vertex -550.294 95.6826 -0.000750355 + vertex -555.685 99.4053 -0.000414203 + vertex -546.28 96.8979 -0.000347132 + endloop + endfacet + facet normal 6.69412e-05 0.000200095 -1 + outer loop + vertex -553.821 94.3201 -0.00125905 + vertex -559.259 97.6954 -0.00094773 + vertex -550.294 95.6826 -0.000750355 + endloop + endfacet + facet normal 6.25661e-05 0.000152231 -1 + outer loop + vertex -557.555 93.0583 -0.00168477 + vertex -553.821 94.3201 -0.00125905 + vertex -547.066 90.1554 -0.00147045 + endloop + endfacet + facet normal 4.46264e-05 0.000104159 -1 + outer loop + vertex -561.287 91.6162 -0.00200151 + vertex -566.963 95.5811 -0.00184184 + vertex -557.555 93.0583 -0.00168477 + endloop + endfacet + facet normal 7.7431e-05 0.000224644 -1 + outer loop + vertex -564.912 89.9197 -0.0026633 + vertex -569.315 93.5041 -0.00219909 + vertex -561.287 91.6162 -0.00200151 + endloop + endfacet + facet normal 0.000187877 0.000603404 -1 + outer loop + vertex -568.369 87.9361 -0.00450985 + vertex -574.435 92.4279 -0.00293896 + vertex -564.912 89.9197 -0.0026633 + endloop + endfacet + facet normal 0.000259729 0.000903039 -1 + outer loop + vertex -571.646 85.6837 -0.00739494 + vertex -576.226 89.7323 -0.00492838 + vertex -568.369 87.9361 -0.00450985 + endloop + endfacet + facet normal 3.26908e-05 0.000155637 -1 + outer loop + vertex -575.233 83.1976 -0.00789911 + vertex -580.38 88.2308 -0.00728403 + vertex -571.646 85.6837 -0.00739494 + endloop + endfacet + facet normal -0.00070084 -0.00245967 -0.999997 + outer loop + vertex -578.179 80.0389 0.001935 + vertex -585.154 85.7514 -0.00722734 + vertex -575.233 83.1976 -0.00789911 + endloop + endfacet + facet normal -0.0020279 -0.00661323 -0.999976 + outer loop + vertex -580.12 76.5272 0.0290962 + vertex -578.179 80.0389 0.001935 + vertex -569.441 73.7619 0.0257265 + endloop + endfacet + facet normal -0.00360616 -0.0127086 -0.999913 + outer loop + vertex -571.185 70.1843 0.0774869 + vertex -580.12 76.5272 0.0290962 + vertex -569.441 73.7619 0.0257265 + endloop + endfacet + facet normal -0.0059676 -0.0222292 -0.999735 + outer loop + vertex -572.642 66.51 0.167882 + vertex -571.185 70.1843 0.0774869 + vertex -560.676 63.0542 0.173299 + endloop + endfacet + facet normal -0.0118386 -0.0425557 -0.999024 + outer loop + vertex -561.762 59.1749 0.351405 + vertex -572.642 66.51 0.167882 + vertex -560.676 63.0542 0.173299 + endloop + endfacet + facet normal -0.0214485 -0.0794036 -0.996612 + outer loop + vertex -562.869 55.2114 0.691031 + vertex -561.762 59.1749 0.351405 + vertex -550.671 51.7316 0.705744 + endloop + endfacet + facet normal -0.0370862 -0.137064 -0.989868 + outer loop + vertex -552.223 47.7745 1.31184 + vertex -550.671 51.7316 0.705744 + vertex -540.184 44.4479 1.32141 + endloop + endfacet + facet normal -0.0214353 -0.0807369 -0.996505 + outer loop + vertex -538.534 48.3668 0.718001 + vertex -549.488 55.6567 0.362987 + vertex -537.273 52.269 0.374705 + endloop + endfacet + facet normal -0.0110917 -0.0434492 -0.998994 + outer loop + vertex -549.488 55.6567 0.362987 + vertex -548.371 59.5446 0.181487 + vertex -537.273 52.269 0.374705 + endloop + endfacet + facet normal -0.00648957 -0.0239636 -0.999692 + outer loop + vertex -548.371 59.5446 0.181487 + vertex -559.325 66.8282 0.078 + vertex -546.998 63.347 0.0814305 + endloop + endfacet + facet normal -0.0034225 -0.0131039 -0.999908 + outer loop + vertex -559.325 66.8282 0.078 + vertex -557.511 70.435 0.0245236 + vertex -546.998 63.347 0.0814305 + endloop + endfacet + facet normal -0.0019663 -0.00656854 -0.999976 + outer loop + vertex -557.511 70.435 0.0245236 + vertex -567.123 77.127 -0.000533707 + vertex -555.19 73.7762 -0.00198594 + endloop + endfacet + facet normal -0.000684385 -0.00206181 -0.999998 + outer loop + vertex -555.19 73.7762 -0.00198594 + vertex -564.225 80.1114 -0.00886458 + vertex -552.474 76.7886 -0.0100557 + endloop + endfacet + facet normal 0.000128355 0.000580101 -1 + outer loop + vertex -552.474 76.7886 -0.0100557 + vertex -561.061 82.7182 -0.00771809 + vertex -549.453 79.4374 -0.00813134 + endloop + endfacet + facet normal 0.000321313 0.00113913 -0.999999 + outer loop + vertex -549.453 79.4374 -0.00813134 + vertex -557.791 85.0215 -0.00444941 + vertex -546.214 81.7452 -0.00446186 + endloop + endfacet + facet normal 0.000213074 0.000708065 -1 + outer loop + vertex -546.214 81.7452 -0.00446186 + vertex -554.325 86.9975 -0.00247099 + vertex -542.797 83.7284 -0.00232946 + endloop + endfacet + facet normal 8.75487e-05 0.000249322 -1 + outer loop + vertex -542.797 83.7284 -0.00232946 + vertex -550.728 88.6884 -0.00178714 + vertex -539.279 85.4438 -0.00159378 + endloop + endfacet + facet normal 3.79351e-05 0.000104667 -1 + outer loop + vertex -539.279 85.4438 -0.00159378 + vertex -535.702 86.9505 -0.00130038 + vertex -527.476 82.1229 -0.00149364 + endloop + endfacet + facet normal 4.8536e-05 0.00013209 -1 + outer loop + vertex -535.702 86.9505 -0.00130038 + vertex -543.429 91.5095 -0.00107322 + vertex -532.114 88.3286 -0.00094422 + endloop + endfacet + facet normal 5.17558e-05 0.000158705 -1 + outer loop + vertex -532.114 88.3286 -0.00094422 + vertex -539.761 92.7939 -0.000631331 + vertex -528.539 89.6192 -0.000554336 + endloop + endfacet + facet normal 3.96644e-05 0.000124928 -1 + outer loop + vertex -528.539 89.6192 -0.000554336 + vertex -525.042 90.8581 -0.000260867 + vertex -517.012 86.3979 -0.000499567 + endloop + endfacet + facet normal 2.20629e-05 7.30322e-05 -1 + outer loop + vertex -525.042 90.8581 -0.000260867 + vertex -532.435 95.1311 -0.000111914 + vertex -521.535 92.0314 -9.77935e-05 + endloop + endfacet + facet normal 1.1369e-05 3.54254e-05 -1 + outer loop + vertex -532.435 95.1311 -0.000111914 + vertex -528.718 96.1771 -3.25992e-05 + vertex -521.535 92.0314 -9.77935e-05 + endloop + endfacet + facet normal 4.57443e-06 1.5915e-05 -1 + outer loop + vertex -528.718 96.1771 -3.25992e-05 + vertex -534.878 99.9961 -8.32429e-14 + vertex -524.469 97.0041 -8.35381e-14 + endloop + endfacet + facet normal 8.24731e-06 2.90663e-05 -1 + outer loop + vertex -509.83 88.7777 -8.8799e-05 + vertex -517.69 93.0587 -2.91892e-05 + vertex -505.98 89.8235 -2.66509e-05 + endloop + endfacet + facet normal 1.923e-05 6.47348e-05 -1 + outer loop + vertex -513.539 87.6481 -0.000233251 + vertex -509.83 88.7777 -8.8799e-05 + vertex -501.861 84.4626 -0.0002149 + endloop + endfacet + facet normal 3.12246e-05 0.000108706 -1 + outer loop + vertex -505.486 83.2449 -0.000460444 + vertex -513.539 87.6481 -0.000233251 + vertex -501.861 84.4626 -0.0002149 + endloop + endfacet + facet normal 4.27065e-05 0.000149099 -1 + outer loop + vertex -508.906 81.903 -0.000806566 + vertex -505.486 83.2449 -0.000460444 + vertex -498.169 79.0541 -0.000772844 + endloop + endfacet + facet normal 4.30046e-05 0.000139906 -1 + outer loop + vertex -512.301 80.4578 -0.00115479 + vertex -520.476 85.0725 -0.000860716 + vertex -508.906 81.903 -0.000806566 + endloop + endfacet + facet normal 3.57335e-05 0.000115785 -1 + outer loop + vertex -515.707 78.8864 -0.00145844 + vertex -523.984 83.6651 -0.00120091 + vertex -512.301 80.4578 -0.00115479 + endloop + endfacet + facet normal 6.9976e-05 0.000240295 -1 + outer loop + vertex -519.055 77.122 -0.00211672 + vertex -515.707 78.8864 -0.00145844 + vertex -508.028 74.2155 -0.00204347 + endloop + endfacet + facet normal 0.000193617 0.000679484 -1 + outer loop + vertex -522.307 75.0976 -0.0041219 + vertex -530.915 80.3856 -0.00219537 + vertex -519.055 77.122 -0.00211672 + endloop + endfacet + facet normal 0.000337906 0.00115792 -0.999999 + outer loop + vertex -525.42 72.761 -0.0078794 + vertex -534.258 78.386 -0.00435249 + vertex -522.307 75.0976 -0.0041219 + endloop + endfacet + facet normal 0.000198149 0.000617327 -1 + outer loop + vertex -528.277 70.0631 -0.0101109 + vertex -537.435 76.0669 -0.00821937 + vertex -525.42 72.761 -0.0078794 + endloop + endfacet + facet normal -0.000553776 -0.00211137 -0.999998 + outer loop + vertex -530.799 66.9952 -0.00223643 + vertex -540.357 73.3896 -0.0104447 + vertex -528.277 70.0631 -0.0101109 + endloop + endfacet + facet normal -0.00199133 -0.00737451 -0.999971 + outer loop + vertex -532.952 63.5932 0.0271396 + vertex -542.971 70.3521 -0.00275374 + vertex -530.799 66.9952 -0.00223643 + endloop + endfacet + facet normal -0.00393635 -0.0147375 -0.999884 + outer loop + vertex -534.722 59.9483 0.0878296 + vertex -545.197 66.9779 0.025456 + vertex -532.952 63.5932 0.0271396 + endloop + endfacet + facet normal -0.00624136 -0.0249232 -0.99967 + outer loop + vertex -536.114 56.149 0.191241 + vertex -534.722 59.9483 0.0878296 + vertex -524.792 53.1648 0.194953 + endloop + endfacet + facet normal -0.0112241 -0.0438272 -0.998976 + outer loop + vertex -525.941 49.3375 0.37578 + vertex -536.114 56.149 0.191241 + vertex -524.792 53.1648 0.194953 + endloop + endfacet + facet normal -0.022917 -0.0794084 -0.996579 + outer loop + vertex -527.137 45.4304 0.714604 + vertex -525.941 49.3375 0.37578 + vertex -517.818 43.4724 0.656316 + endloop + endfacet + facet normal -0.0402628 -0.130347 -0.990651 + outer loop + vertex -518.781 39.2568 1.25013 + vertex -517.818 43.4724 0.656316 + vertex -512.393 38.7322 1.05952 + endloop + endfacet + facet normal -0.0155553 -0.0650366 -0.997762 + outer loop + vertex -511.851 43.0955 0.549726 + vertex -516.95 47.3787 0.350031 + vertex -511.677 46.7995 0.305573 + endloop + endfacet + facet normal -0.0128896 -0.0406649 -0.99909 + outer loop + vertex -516.95 47.3787 0.350031 + vertex -515.856 51.0221 0.187625 + vertex -511.677 46.7995 0.305573 + endloop + endfacet + facet normal -0.0063399 -0.0245174 -0.999679 + outer loop + vertex -515.856 51.0221 0.187625 + vertex -523.407 56.9192 0.0908859 + vertex -514.391 54.6798 0.0886296 + endloop + endfacet + facet normal -0.00382345 -0.014948 -0.999881 + outer loop + vertex -514.391 54.6798 0.0886296 + vertex -521.641 60.5618 0.0284169 + vertex -512.628 58.3792 0.0265814 + endloop + endfacet + facet normal -0.00182457 -0.0072557 -0.999972 + outer loop + vertex -512.628 58.3792 0.0265814 + vertex -519.543 63.997 -0.0015637 + vertex -510.461 61.8307 -0.00241539 + endloop + endfacet + facet normal -0.000331905 -0.00175934 -0.999998 + outer loop + vertex -510.461 61.8307 -0.00241539 + vertex -517.045 67.0903 -0.00948373 + vertex -507.983 64.9699 -0.00876114 + endloop + endfacet + facet normal 0.000238315 0.000629831 -1 + outer loop + vertex -507.983 64.9699 -0.00876114 + vertex -514.232 69.8193 -0.00719625 + vertex -505.168 67.7493 -0.00633985 + endloop + endfacet + facet normal 0.000260956 0.00093271 -1 + outer loop + vertex -505.168 67.7493 -0.00633985 + vertex -511.205 72.1885 -0.00377482 + vertex -502.243 70.1244 -0.00336127 + endloop + endfacet + facet normal 0.000132853 0.000476342 -1 + outer loop + vertex -502.243 70.1244 -0.00336127 + vertex -499.215 72.0847 -0.00202528 + vertex -496.658 69.2851 -0.00301913 + endloop + endfacet + facet normal 4.47434e-05 0.000205513 -1 + outer loop + vertex -499.215 72.0847 -0.00202528 + vertex -504.776 75.988 -0.0014719 + vertex -495.912 73.822 -0.00152045 + endloop + endfacet + facet normal 3.85811e-05 0.000158139 -1 + outer loop + vertex -495.912 73.822 -0.00152045 + vertex -501.474 77.5883 -0.0011394 + vertex -492.717 75.4654 -0.00113729 + endloop + endfacet + facet normal 3.40679e-05 0.000184925 -1 + outer loop + vertex -492.717 75.4654 -0.00113729 + vertex -489.492 76.8938 -0.000763264 + vertex -487.299 74.5053 -0.00113023 + endloop + endfacet + facet normal 3.66269e-05 0.000147819 -1 + outer loop + vertex -489.492 76.8938 -0.000763264 + vertex -494.71 80.385 -0.000438314 + vertex -485.82 78.1928 -0.000436746 + endloop + endfacet + facet normal 2.70791e-05 0.000109099 -1 + outer loop + vertex -494.71 80.385 -0.000438314 + vertex -490.853 81.5609 -0.000205576 + vertex -485.82 78.1928 -0.000436746 + endloop + endfacet + facet normal 1.53797e-05 5.79345e-05 -1 + outer loop + vertex -490.853 81.5609 -0.000205576 + vertex -497.916 85.5452 -8.33771e-05 + vertex -486.923 82.6644 -8.12096e-05 + endloop + endfacet + facet normal 7.36459e-06 2.735e-05 -1 + outer loop + vertex -497.916 85.5452 -8.33771e-05 + vertex -494.34 86.6836 -2.59106e-05 + vertex -486.923 82.6644 -8.12096e-05 + endloop + endfacet + facet normal 3.42674e-06 1.27535e-05 -1 + outer loop + vertex -494.34 86.6836 -2.59106e-05 + vertex -503.331 91.131 -8.41176e-14 + vertex -492.652 88.2617 -8.44007e-14 + endloop + endfacet + facet normal 6.26355e-06 2.69166e-05 -1 + outer loop + vertex -478.407 80.5674 -8.28019e-05 + vertex -483.855 83.9352 -2.62794e-05 + vertex -475.738 81.887 -3.05653e-05 + endloop + endfacet + facet normal 3.53454e-06 3.24358e-05 -1 + outer loop + vertex -478.407 80.5674 -8.28019e-05 + vertex -475.738 81.887 -3.05653e-05 + vertex -473.272 79.384 -0.000103036 + endloop + endfacet + facet normal 7.1507e-06 3.8052e-05 -1 + outer loop + vertex -469.625 79.0713 -0.00010651 + vertex -463.204 80.6637 -8.51503e-14 + vertex -465.647 78.8718 -8.56564e-05 + endloop + endfacet + facet normal 7.22e-06 3.60671e-05 -1 + outer loop + vertex -473.272 79.384 -0.000103036 + vertex -475.738 81.887 -3.05653e-05 + vertex -470.547 80.6958 -3.60481e-05 + endloop + endfacet + facet normal 1.51514e-05 8.7472e-05 -1 + outer loop + vertex -474.22 77.3524 -0.000326486 + vertex -469.625 79.0713 -0.00010651 + vertex -469.485 77.3218 -0.00025741 + endloop + endfacet + facet normal 9.95191e-06 6.02829e-05 -1 + outer loop + vertex -476.382 78.4092 -0.000192754 + vertex -478.407 80.5674 -8.28019e-05 + vertex -473.272 79.384 -0.000103036 + endloop + endfacet + facet normal 2.4429e-05 0.000124613 -1 + outer loop + vertex -479.47 77.0869 -0.000432971 + vertex -481.932 79.4125 -0.000203308 + vertex -476.382 78.4092 -0.000192754 + endloop + endfacet + facet normal 1.04484e-05 0.000226732 -1 + outer loop + vertex -483.693 75.5904 -0.000816404 + vertex -479.47 77.0869 -0.000432971 + vertex -479.081 75.1713 -0.000863239 + endloop + endfacet + facet normal 2.98341e-05 0.000249935 -1 + outer loop + vertex -479.807 72.9177 -0.00151611 + vertex -475.951 74.1773 -0.00108627 + vertex -471.685 71.8262 -0.0015466 + endloop + endfacet + facet normal 1.25052e-05 0.000249367 -1 + outer loop + vertex -479.081 75.1713 -0.000863239 + vertex -484.755 73.1952 -0.00142696 + vertex -483.693 75.5904 -0.000816404 + endloop + endfacet + facet normal 2.0385e-05 0.000223207 -1 + outer loop + vertex -483.921 70.9943 -0.00202931 + vertex -479.807 72.9177 -0.00151611 + vertex -475.337 70.1471 -0.0020434 + endloop + endfacet + facet normal 3.72464e-06 0.000301663 -1 + outer loop + vertex -484.755 73.1952 -0.00142696 + vertex -489.079 70.734 -0.00218554 + vertex -489.815 72.831 -0.00155569 + endloop + endfacet + facet normal 4.41316e-05 0.000267419 -1 + outer loop + vertex -487.753 68.7948 -0.0027866 + vertex -483.921 70.9943 -0.00202931 + vertex -478.969 68.2085 -0.00255574 + endloop + endfacet + facet normal 1.50536e-05 0.000606973 -1 + outer loop + vertex -489.079 70.734 -0.00218554 + vertex -493.647 67.803 -0.00403331 + vertex -493.361 70.8396 -0.00218588 + endloop + endfacet + facet normal 0.000114061 0.000581844 -1 + outer loop + vertex -490.055 66.6556 -0.00429381 + vertex -487.753 68.7948 -0.0027866 + vertex -482.262 66.0928 -0.00373242 + endloop + endfacet + facet normal 0.000179653 0.00105814 -0.999999 + outer loop + vertex -493.28 64.5746 -0.00707534 + vertex -490.055 66.6556 -0.00429381 + vertex -485.262 63.7733 -0.00648273 + endloop + endfacet + facet normal 0.000116889 0.000913198 -1 + outer loop + vertex -493.647 67.803 -0.00403331 + vertex -497.702 64.3565 -0.0076547 + vertex -498.898 66.99 -0.00538957 + endloop + endfacet + facet normal -3.76903e-05 0.000650734 -1 + outer loop + vertex -496.17 61.5159 -0.00895678 + vertex -493.28 64.5746 -0.00707534 + vertex -487.997 61.0084 -0.0095951 + endloop + endfacet + facet normal 0.000151701 -0.000344434 -1 + outer loop + vertex -497.702 64.3565 -0.0076547 + vertex -500.549 61.094 -0.00696282 + vertex -501.873 64.1088 -0.00820209 + endloop + endfacet + facet normal -0.000867279 -0.00221376 -0.999997 + outer loop + vertex -498.548 58.1407 0.000577288 + vertex -496.17 61.5159 -0.00895678 + vertex -490.46 57.8147 -0.00571577 + endloop + endfacet + facet normal -0.00047791 -0.00462318 -0.999989 + outer loop + vertex -500.549 61.094 -0.00696282 + vertex -502.881 57.6426 0.0101082 + vertex -504.446 60.9171 -0.00428303 + endloop + endfacet + facet normal -0.00231735 -0.00785186 -0.999966 + outer loop + vertex -500.72 54.577 0.0335942 + vertex -498.548 58.1407 0.000577288 + vertex -492.696 54.3796 0.0165481 + endloop + endfacet + facet normal -0.00188672 -0.0116241 -0.999931 + outer loop + vertex -502.881 57.6426 0.0101082 + vertex -504.913 53.9433 0.0569463 + vertex -506.648 57.4365 0.019612 + endloop + endfacet + facet normal -0.00442236 -0.0154115 -0.999871 + outer loop + vertex -502.602 50.8254 0.0997427 + vertex -500.72 54.577 0.0335942 + vertex -494.554 50.7477 0.0653434 + endloop + endfacet + facet normal -0.00445973 -0.0221076 -0.999746 + outer loop + vertex -504.913 53.9433 0.0569463 + vertex -506.652 49.9215 0.153641 + vertex -508.578 53.7058 0.0785475 + endloop + endfacet + facet normal -0.00823674 -0.0257338 -0.999635 + outer loop + vertex -503.997 46.8866 0.212629 + vertex -502.602 50.8254 0.0997427 + vertex -496.165 47.0489 0.143917 + endloop + endfacet + facet normal -0.00730221 -0.0424502 -0.999072 + outer loop + vertex -506.652 49.9215 0.153641 + vertex -508.009 44.828 0.379981 + vertex -510.179 49.8079 0.184243 + endloop + endfacet + facet normal -0.0143626 -0.0455117 -0.998861 + outer loop + vertex -503.912 43.2489 0.377162 + vertex -503.997 46.8866 0.212629 + vertex -497.038 43.2843 0.276714 + endloop + endfacet + facet normal -0.0283432 -0.0822583 -0.996208 + outer loop + vertex -508.783 39.4702 0.84439 + vertex -508.009 44.828 0.379981 + vertex -504.733 39.7548 0.705673 + endloop + endfacet + facet normal -0.0316584 -0.135271 -0.990303 + outer loop + vertex -505.881 35.4469 1.3308 + vertex -504.733 39.7548 0.705673 + vertex -496.639 34.1271 1.21564 + endloop + endfacet + facet normal -0.0242753 -0.137229 -0.990242 + outer loop + vertex -504.733 39.7548 0.705673 + vertex -505.881 35.4469 1.3308 + vertex -508.783 39.4702 0.84439 + endloop + endfacet + facet normal -0.023912 -0.0978797 -0.994911 + outer loop + vertex -484.028 33.5131 0.82932 + vertex -484.259 37.7755 0.415536 + vertex -466.694 30.5675 0.70251 + endloop + endfacet + facet normal -0.0142238 -0.0686842 -0.997537 + outer loop + vertex -497.183 39.2701 0.555169 + vertex -503.912 43.2489 0.377162 + vertex -497.038 43.2843 0.276714 + endloop + endfacet + facet normal -0.0122957 -0.0507411 -0.998636 + outer loop + vertex -484.259 37.7755 0.415536 + vertex -483.749 41.6757 0.211087 + vertex -466.04 34.5352 0.355858 + endloop + endfacet + facet normal -0.00807634 -0.0333792 -0.99941 + outer loop + vertex -497.038 43.2843 0.276714 + vertex -503.997 46.8866 0.212629 + vertex -496.165 47.0489 0.143917 + endloop + endfacet + facet normal -0.00611841 -0.0257887 -0.999649 + outer loop + vertex -483.749 41.6757 0.211087 + vertex -482.607 45.3991 0.108045 + vertex -465.209 38.3408 0.183643 + endloop + endfacet + facet normal -0.00445959 -0.0192971 -0.999804 + outer loop + vertex -496.165 47.0489 0.143917 + vertex -502.602 50.8254 0.0997427 + vertex -494.554 50.7477 0.0653434 + endloop + endfacet + facet normal -0.00375836 -0.0157782 -0.999868 + outer loop + vertex -482.607 45.3991 0.108045 + vertex -481.104 49.0729 0.0444176 + vertex -464.131 42.0816 0.0909461 + endloop + endfacet + facet normal -0.0024241 -0.012194 -0.999923 + outer loop + vertex -494.554 50.7477 0.0653434 + vertex -500.72 54.577 0.0335942 + vertex -492.696 54.3796 0.0165481 + endloop + endfacet + facet normal -0.00223481 -0.00946903 -0.999953 + outer loop + vertex -481.104 49.0729 0.0444176 + vertex -479.124 52.5876 0.00671191 + vertex -462.617 45.7156 0.0348934 + endloop + endfacet + facet normal -0.0010127 -0.00582191 -0.999983 + outer loop + vertex -492.696 54.3796 0.0165481 + vertex -498.548 58.1407 0.000577288 + vertex -490.46 57.8147 -0.00571577 + endloop + endfacet + facet normal -0.000965972 -0.00400012 -0.999992 + outer loop + vertex -479.124 52.5876 0.00671191 + vertex -476.965 55.9457 -0.00880626 + vertex -460.759 49.2197 0.00244411 + endloop + endfacet + facet normal -0.000146524 -0.00110173 -0.999999 + outer loop + vertex -490.46 57.8147 -0.00571577 + vertex -496.17 61.5159 -0.00895678 + vertex -487.997 61.0084 -0.0095951 + endloop + endfacet + facet normal -5.6617e-05 -0.000173729 -1 + outer loop + vertex -476.965 55.9457 -0.00880626 + vertex -474.436 58.9836 -0.00947722 + vertex -458.519 52.4866 -0.0092497 + endloop + endfacet + facet normal 0.000169633 0.000957868 -1 + outer loop + vertex -487.997 61.0084 -0.0095951 + vertex -493.28 64.5746 -0.00707534 + vertex -485.262 63.7733 -0.00648273 + endloop + endfacet + facet normal 0.000232609 0.00107257 -0.999999 + outer loop + vertex -474.436 58.9836 -0.00947722 + vertex -471.565 61.631 -0.00596982 + vertex -455.937 55.44 -0.00897496 + endloop + endfacet + facet normal 0.000144201 0.000999187 -0.999999 + outer loop + vertex -485.262 63.7733 -0.00648273 + vertex -490.055 66.6556 -0.00429381 + vertex -482.262 66.0928 -0.00373242 + endloop + endfacet + facet normal 0.000176335 0.000827345 -1 + outer loop + vertex -471.565 61.631 -0.00596982 + vertex -468.503 63.9599 -0.00350301 + vertex -453.124 58.0609 -0.00567163 + endloop + endfacet + facet normal 5.74379e-05 0.000466778 -1 + outer loop + vertex -482.262 66.0928 -0.00373242 + vertex -487.753 68.7948 -0.0027866 + vertex -478.969 68.2085 -0.00255574 + endloop + endfacet + facet normal 7.35453e-05 0.000358376 -1 + outer loop + vertex -468.503 63.9599 -0.00350301 + vertex -465.191 66.0135 -0.00252349 + vertex -450.073 60.348 -0.003442 + endloop + endfacet + facet normal 2.06245e-05 0.000225635 -1 + outer loop + vertex -478.969 68.2085 -0.00255574 + vertex -483.921 70.9943 -0.00202931 + vertex -475.337 70.1471 -0.0020434 + endloop + endfacet + facet normal 3.96393e-05 0.000192978 -1 + outer loop + vertex -465.191 66.0135 -0.00252349 + vertex -461.711 67.8329 -0.00203445 + vertex -446.805 62.3431 -0.00250301 + endloop + endfacet + facet normal 4.59468e-05 0.000210104 -1 + outer loop + vertex -446.805 62.3431 -0.00250301 + vertex -461.711 67.8329 -0.00203445 + vertex -443.526 64.1624 -0.00197006 + endloop + endfacet + facet normal 2.78638e-05 0.000235274 -1 + outer loop + vertex -475.337 70.1471 -0.0020434 + vertex -479.807 72.9177 -0.00151611 + vertex -471.685 71.8262 -0.0015466 + endloop + endfacet + facet normal 4.97834e-05 0.000229113 -1 + outer loop + vertex -461.711 67.8329 -0.00203445 + vertex -458.253 69.4989 -0.00148061 + vertex -443.526 64.1624 -0.00197006 + endloop + endfacet + facet normal 4.23994e-05 0.000272735 -1 + outer loop + vertex -471.685 71.8262 -0.0015466 + vertex -475.951 74.1773 -0.00108627 + vertex -468.238 73.3554 -0.000983408 + endloop + endfacet + facet normal 3.92397e-05 0.000243083 -1 + outer loop + vertex -475.951 74.1773 -0.00108627 + vertex -473.162 75.6644 -0.000615351 + vertex -468.238 73.3554 -0.000983408 + endloop + endfacet + facet normal 1.57552e-05 0.000181 -1 + outer loop + vertex -469.485 77.3218 -0.00025741 + vertex -473.162 75.6644 -0.000615351 + vertex -474.22 77.3524 -0.000326486 + endloop + endfacet + facet normal 9.60661e-06 8.70271e-05 -1 + outer loop + vertex -465.647 78.8718 -8.56564e-05 + vertex -469.485 77.3218 -0.00025741 + vertex -469.625 79.0713 -0.00010651 + endloop + endfacet + facet normal 8.92515e-06 3.56327e-05 -1 + outer loop + vertex -463.204 80.6637 -8.51503e-14 + vertex -462.852 80.5755 -8.5159e-14 + vertex -465.647 78.8718 -8.56564e-05 + endloop + endfacet + facet normal 9.52481e-06 8.13614e-05 -1 + outer loop + vertex -463.864 76.7707 -0.000211199 + vertex -459.643 77.5703 -0.00010593 + vertex -452.849 73.4245 -0.000378524 + endloop + endfacet + facet normal 3.38329e-05 0.000191933 -1 + outer loop + vertex -452.849 73.4245 -0.000378524 + vertex -455.071 71.1967 -0.00088133 + vertex -465.241 75.0098 -0.000493535 + endloop + endfacet + facet normal 5.51247e-05 0.000249666 -1 + outer loop + vertex -458.253 69.4989 -0.00148061 + vertex -455.071 71.1967 -0.00088133 + vertex -440.201 65.8457 -0.00139756 + endloop + endfacet + facet normal 5.24609e-05 0.000236503 -1 + outer loop + vertex -443.526 64.1624 -0.00197006 + vertex -458.253 69.4989 -0.00148061 + vertex -440.201 65.8457 -0.00139756 + endloop + endfacet + facet normal 4.79158e-05 0.000206555 -1 + outer loop + vertex -446.805 62.3431 -0.00250301 + vertex -443.526 64.1624 -0.00197006 + vertex -426.18 57.9039 -0.00243168 + endloop + endfacet + facet normal 7.9767e-05 0.000354539 -1 + outer loop + vertex -429.272 55.8875 -0.00339314 + vertex -446.805 62.3431 -0.00250301 + vertex -426.18 57.9039 -0.00243168 + endloop + endfacet + facet normal 0.000164216 0.000737863 -1 + outer loop + vertex -432.196 53.6022 -0.00555969 + vertex -429.272 55.8875 -0.00339314 + vertex -410.918 48.954 -0.00549512 + endloop + endfacet + facet normal 0.000207828 0.000937511 -1 + outer loop + vertex -413.499 46.3238 -0.00849743 + vertex -432.196 53.6022 -0.00555969 + vertex -410.918 48.954 -0.00549512 + endloop + endfacet + facet normal 1.2399e-06 -1.19146e-05 -1 + outer loop + vertex -415.873 43.3656 -0.00846512 + vertex -413.499 46.3238 -0.00849743 + vertex -394.901 38.909 -0.00838602 + endloop + endfacet + facet normal -0.000616112 -0.00291705 -0.999996 + outer loop + vertex -396.907 35.6261 0.00242638 + vertex -415.873 43.3656 -0.00846512 + vertex -394.901 38.909 -0.00838602 + endloop + endfacet + facet normal -0.00154545 -0.00763294 -0.99997 + outer loop + vertex -398.592 32.1028 0.0319247 + vertex -396.907 35.6261 0.00242638 + vertex -377.97 27.9577 0.0316942 + endloop + endfacet + facet normal -0.00277292 -0.0137396 -0.999902 + outer loop + vertex -379.127 24.2388 0.0860028 + vertex -398.592 32.1028 0.0319247 + vertex -377.97 27.9577 0.0316942 + endloop + endfacet + facet normal -0.00441024 -0.0233275 -0.999718 + outer loop + vertex -379.814 20.3999 0.178609 + vertex -379.127 24.2388 0.0860028 + vertex -359.291 16.5504 0.1779 + endloop + endfacet + facet normal -0.00818958 -0.0434759 -0.999021 + outer loop + vertex -359.69 12.6463 0.351064 + vertex -379.814 20.3999 0.178609 + vertex -359.291 16.5504 0.1779 + endloop + endfacet + facet normal -0.0146042 -0.0825705 -0.996478 + outer loop + vertex -360.386 8.71791 0.686779 + vertex -359.69 12.6463 0.351064 + vertex -339.784 5.08787 0.68564 + endloop + endfacet + facet normal -0.0236585 -0.140278 -0.989829 + outer loop + vertex -341.308 1.13885 1.28171 + vertex -339.784 5.08787 0.68564 + vertex -320.607 -2.33218 1.27885 + endloop + endfacet + facet normal -0.0138151 -0.0823043 -0.996511 + outer loop + vertex -319.056 1.62476 0.684338 + vertex -339.11 9.02149 0.351441 + vertex -318.393 5.55748 0.350332 + endloop + endfacet + facet normal -0.00734994 -0.0436374 -0.99902 + outer loop + vertex -339.11 9.02149 0.351441 + vertex -338.739 12.9237 0.178262 + vertex -318.393 5.55748 0.350332 + endloop + endfacet + facet normal -0.00419178 -0.0235761 -0.999713 + outer loop + vertex -338.739 12.9237 0.178262 + vertex -358.654 20.3923 0.0856329 + vertex -338.162 16.7662 0.085226 + endloop + endfacet + facet normal -0.00244008 -0.013677 -0.999903 + outer loop + vertex -358.654 20.3923 0.0856329 + vertex -357.563 24.1245 0.0319212 + vertex -338.162 16.7662 0.085226 + endloop + endfacet + facet normal -0.0014381 -0.0076383 -0.99997 + outer loop + vertex -357.563 24.1245 0.0319212 + vertex -376.378 31.5047 0.00260651 + vertex -356.066 27.6873 0.00255405 + endloop + endfacet + facet normal -0.000559067 -0.00296103 -0.999995 + outer loop + vertex -376.378 31.5047 0.00260651 + vertex -374.488 34.8131 -0.00824657 + vertex -356.066 27.6873 0.00255405 + endloop + endfacet + facet normal -8.03881e-07 -2.87256e-05 -1 + outer loop + vertex -374.488 34.8131 -0.00824657 + vertex -392.665 41.8969 -0.00843545 + vertex -372.378 37.8287 -0.0083349 + endloop + endfacet + facet normal 0.000196682 0.00095609 -1 + outer loop + vertex -392.665 41.8969 -0.00843545 + vertex -390.229 44.5615 -0.00540864 + vertex -372.378 37.8287 -0.0083349 + endloop + endfacet + facet normal 0.000161146 0.000742444 -1 + outer loop + vertex -390.229 44.5615 -0.00540864 + vertex -408.144 51.2712 -0.00331393 + vertex -387.601 46.915 -0.00323786 + endloop + endfacet + facet normal 7.90499e-05 0.000355307 -1 + outer loop + vertex -408.144 51.2712 -0.00331393 + vertex -405.201 53.3214 -0.00235289 + vertex -387.601 46.915 -0.00323786 + endloop + endfacet + facet normal 4.78155e-05 0.000205295 -1 + outer loop + vertex -405.201 53.3214 -0.00235289 + vertex -422.994 59.7236 -0.00188934 + vertex -402.172 55.1804 -0.00182641 + endloop + endfacet + facet normal 5.25157e-05 0.000226838 -1 + outer loop + vertex -422.994 59.7236 -0.00188934 + vertex -419.862 61.4388 -0.00133576 + vertex -402.172 55.1804 -0.00182641 + endloop + endfacet + facet normal 5.30048e-05 0.000233819 -1 + outer loop + vertex -419.862 61.4388 -0.00133576 + vertex -437.127 67.5668 -0.000818038 + vertex -416.771 63.0696 -0.000790606 + endloop + endfacet + facet normal 4.17988e-05 0.000183096 -1 + outer loop + vertex -437.127 67.5668 -0.000818038 + vertex -433.61 69.1212 -0.000386453 + vertex -416.771 63.0696 -0.000790606 + endloop + endfacet + facet normal 2.54053e-05 0.000110137 -1 + outer loop + vertex -433.61 69.1212 -0.000386453 + vertex -447.428 74.5919 -0.000134971 + vertex -429.618 70.423 -0.000141659 + endloop + endfacet + facet normal 1.58317e-05 6.69239e-05 -1 + outer loop + vertex -429.618 70.423 -0.000141659 + vertex -444.124 75.9713 -8.56133e-14 + vertex -424.982 71.4429 -8.60601e-14 + endloop + endfacet + facet normal 2.47024e-05 0.000111913 -1 + outer loop + vertex -413.615 64.5949 -0.000382043 + vertex -410.171 65.9846 -0.000141442 + vertex -393.303 60.1203 -0.000381065 + endloop + endfacet + facet normal 3.97781e-05 0.000180347 -1 + outer loop + vertex -396.21 58.5506 -0.000779787 + vertex -413.615 64.5949 -0.000382043 + vertex -393.303 60.1203 -0.000381065 + endloop + endfacet + facet normal 4.9118e-05 0.000229429 -1 + outer loop + vertex -399.16 56.9117 -0.00130072 + vertex -396.21 58.5506 -0.000779787 + vertex -379.01 52.6653 -0.00128521 + endloop + endfacet + facet normal 4.52672e-05 0.000211156 -1 + outer loop + vertex -381.926 50.9079 -0.00178829 + vertex -399.16 56.9117 -0.00130072 + vertex -379.01 52.6653 -0.00128521 + endloop + endfacet + facet normal 4.19753e-05 0.000199363 -1 + outer loop + vertex -384.809 49.008 -0.00228808 + vertex -381.926 50.9079 -0.00178829 + vertex -364.951 45.0424 -0.00224514 + endloop + endfacet + facet normal 7.20438e-05 0.000349929 -1 + outer loop + vertex -367.589 42.9118 -0.00318076 + vertex -384.809 49.008 -0.00228808 + vertex -364.951 45.0424 -0.00224514 + endloop + endfacet + facet normal 0.000144641 0.000751464 -1 + outer loop + vertex -370.074 40.5236 -0.00533481 + vertex -367.589 42.9118 -0.00318076 + vertex -350.108 36.7711 -0.00526676 + endloop + endfacet + facet normal 0.000182635 0.000953617 -1 + outer loop + vertex -352.283 34.0526 -0.00825643 + vertex -370.074 40.5236 -0.00533481 + vertex -350.108 36.7711 -0.00526676 + endloop + endfacet + facet normal 5.6554e-06 -1.37549e-05 -1 + outer loop + vertex -354.28 31.0159 -0.00822595 + vertex -352.283 34.0526 -0.00825643 + vertex -334.035 27.4268 -0.00806209 + endloop + endfacet + facet normal -0.000520917 -0.00298386 -0.999995 + outer loop + vertex -335.722 24.0827 0.00279461 + vertex -354.28 31.0159 -0.00822595 + vertex -334.035 27.4268 -0.00806209 + endloop + endfacet + facet normal -0.00126396 -0.00763251 -0.99997 + outer loop + vertex -337.14 20.5069 0.0318798 + vertex -335.722 24.0827 0.00279461 + vertex -316.573 17.0531 0.0322466 + endloop + endfacet + facet normal -0.00228765 -0.013728 -0.999903 + outer loop + vertex -317.527 13.3052 0.0858828 + vertex -337.14 20.5069 0.0318798 + vertex -316.573 17.0531 0.0322466 + endloop + endfacet + facet normal -0.00366625 -0.0233583 -0.99972 + outer loop + vertex -318.062 9.45836 0.177729 + vertex -317.527 13.3052 0.0858828 + vertex -297.171 6.14463 0.178539 + endloop + endfacet + facet normal -0.00690849 -0.0437989 -0.999016 + outer loop + vertex -297.468 2.24285 0.351656 + vertex -318.062 9.45836 0.177729 + vertex -297.171 6.14463 0.178539 + endloop + endfacet + facet normal -0.0123687 -0.0827309 -0.996495 + outer loop + vertex -298.109 -1.69243 0.686329 + vertex -297.468 2.24285 0.351656 + vertex -276.918 -4.85227 0.68564 + endloop + endfacet + facet normal -0.0194735 -0.140148 -0.989939 + outer loop + vertex -278.411 -8.83541 1.27891 + vertex -276.918 -4.85227 0.68564 + vertex -257.057 -11.8204 1.28143 + endloop + endfacet + facet normal -0.0114667 -0.0827005 -0.996508 + outer loop + vertex -255.61 -7.82125 0.685757 + vertex -276.319 -0.912128 0.350672 + vertex -255.047 -3.87514 0.351789 + endloop + endfacet + facet normal -0.00604951 -0.0438088 -0.999022 + outer loop + vertex -276.319 -0.912128 0.350672 + vertex -276.074 2.9916 0.177999 + vertex -255.047 -3.87514 0.351789 + endloop + endfacet + facet normal -0.00350635 -0.0235138 -0.999717 + outer loop + vertex -276.074 2.9916 0.177999 + vertex -296.7 9.99403 0.085642 + vertex -275.656 6.84692 0.0858541 + endloop + endfacet + facet normal -0.00204595 -0.0137483 -0.999903 + outer loop + vertex -296.7 9.99403 0.085642 + vertex -295.818 13.7517 0.0321708 + vertex -275.656 6.84692 0.0858541 + endloop + endfacet + facet normal -0.00121826 -0.00771535 -0.999969 + outer loop + vertex -295.818 13.7517 0.0321708 + vertex -315.252 20.6421 0.00268411 + vertex -294.575 17.3529 0.00287101 + endloop + endfacet + facet normal -0.000464198 -0.00297498 -0.999995 + outer loop + vertex -315.252 20.6421 0.00268411 + vertex -313.662 24.001 -0.00804682 + vertex -294.575 17.3529 0.00287101 + endloop + endfacet + facet normal -4.73205e-06 -3.57361e-05 -1 + outer loop + vertex -313.662 24.001 -0.00804682 + vertex -332.155 30.4815 -0.0081909 + vertex -311.895 27.072 -0.00816493 + endloop + endfacet + facet normal 0.0001628 0.000959756 -1 + outer loop + vertex -332.155 30.4815 -0.0081909 + vertex -330.107 33.2192 -0.00523013 + vertex -311.895 27.072 -0.00816493 + endloop + endfacet + facet normal 0.000133826 0.000746988 -1 + outer loop + vertex -330.107 33.2192 -0.00523013 + vertex -347.768 39.1862 -0.00313627 + vertex -327.912 35.6571 -0.00311528 + endloop + endfacet + facet normal 6.26913e-05 0.000346769 -1 + outer loop + vertex -347.768 39.1862 -0.00313627 + vertex -345.287 41.3484 -0.00223093 + vertex -327.912 35.6571 -0.00311528 + endloop + endfacet + facet normal 3.58577e-05 0.000189341 -1 + outer loop + vertex -345.287 41.3484 -0.00223093 + vertex -362.203 46.9774 -0.00177169 + vertex -342.686 43.3153 -0.00176526 + endloop + endfacet + facet normal 4.01814e-05 0.000212384 -1 + outer loop + vertex -362.203 46.9774 -0.00177169 + vertex -359.382 48.7649 -0.00127873 + vertex -342.686 43.3153 -0.00176526 + endloop + endfacet + facet normal 4.50513e-05 0.000226454 -1 + outer loop + vertex -359.382 48.7649 -0.00127873 + vertex -376.117 54.3239 -0.000773797 + vertex -356.512 50.4327 -0.000771756 + endloop + endfacet + facet normal 3.64584e-05 0.000183161 -1 + outer loop + vertex -376.117 54.3239 -0.000773797 + vertex -373.243 55.9085 -0.000378775 + vertex -356.512 50.4327 -0.000771756 + endloop + endfacet + facet normal 2.33443e-05 0.000111346 -1 + outer loop + vertex -373.243 55.9085 -0.000378775 + vertex -390.364 61.6332 -0.000141022 + vertex -370.499 57.4758 -0.00014022 + endloop + endfacet + facet normal 1.39323e-05 6.69306e-05 -1 + outer loop + vertex -370.499 57.4758 -0.00014022 + vertex -388.407 63.2985 -8.68636e-14 + vertex -367.645 58.9767 -8.729e-14 + endloop + endfacet + facet normal 2.18021e-05 0.00011568 -1 + outer loop + vertex -353.649 52.022 -0.00038035 + vertex -350.93 53.5884 -0.000139872 + vertex -334.458 48.4164 -0.000379036 + endloop + endfacet + facet normal 3.49083e-05 0.000185439 -1 + outer loop + vertex -337.23 46.8176 -0.000772319 + vertex -353.649 52.022 -0.00038035 + vertex -334.458 48.4164 -0.000379036 + endloop + endfacet + facet normal 4.118e-05 0.000231474 -1 + outer loop + vertex -339.993 45.1288 -0.00127698 + vertex -337.23 46.8176 -0.000772319 + vertex -320.642 41.687 -0.0012768 + endloop + endfacet + facet normal 3.76716e-05 0.000211749 -1 + outer loop + vertex -323.159 39.8419 -0.00176233 + vertex -339.993 45.1288 -0.00127698 + vertex -320.642 41.687 -0.0012768 + endloop + endfacet + facet normal 3.30144e-05 0.00019293 -1 + outer loop + vertex -325.584 37.8448 -0.00222766 + vertex -323.159 39.8419 -0.00176233 + vertex -305.754 34.499 -0.00221851 + endloop + endfacet + facet normal 5.94504e-05 0.000349607 -1 + outer loop + vertex -307.916 32.2853 -0.00312098 + vertex -325.584 37.8448 -0.00222766 + vertex -305.754 34.499 -0.00221851 + endloop + endfacet + facet normal 0.000119298 0.000751555 -1 + outer loop + vertex -309.977 29.8283 -0.00521336 + vertex -307.916 32.2853 -0.00312098 + vertex -289.644 26.5891 -0.00522215 + endloop + endfacet + facet normal 0.000152603 0.000960611 -1 + outer loop + vertex -291.441 23.8162 -0.00816001 + vertex -309.977 29.8283 -0.00521336 + vertex -289.644 26.5891 -0.00522215 + endloop + endfacet + facet normal -1.46655e-06 -3.62474e-05 -1 + outer loop + vertex -293.092 20.7281 -0.00804565 + vertex -291.441 23.8162 -0.00816001 + vertex -272.309 17.6179 -0.0079634 + endloop + endfacet + facet normal -0.000450365 -0.00303593 -0.999995 + outer loop + vertex -273.689 14.2279 0.00295034 + vertex -293.092 20.7281 -0.00804565 + vertex -272.309 17.6179 -0.0079634 + endloop + endfacet + facet normal -0.00109427 -0.00775146 -0.999969 + outer loop + vertex -274.846 10.6138 0.0322308 + vertex -273.689 14.2279 0.00295034 + vertex -253.753 7.66463 0.0320105 + endloop + endfacet + facet normal -0.00196531 -0.0139811 -0.9999 + outer loop + vertex -254.482 3.89078 0.0862112 + vertex -274.846 10.6138 0.0322308 + vertex -253.753 7.66463 0.0320105 + endloop + endfacet + facet normal -0.00306321 -0.0236423 -0.999716 + outer loop + vertex -254.843 0.030964 0.178598 + vertex -254.482 3.89078 0.0862112 + vertex -233.628 -2.71114 0.178443 + endloop + endfacet + facet normal -0.00566767 -0.0437921 -0.999025 + outer loop + vertex -233.782 -6.62047 0.350678 + vertex -254.843 0.030964 0.178598 + vertex -233.628 -2.71114 0.178443 + endloop + endfacet + facet normal -0.00988422 -0.0831415 -0.996489 + outer loop + vertex -234.316 -10.5699 0.685503 + vertex -233.782 -6.62047 0.350678 + vertex -213.099 -13.0818 0.684626 + endloop + endfacet + facet normal -0.0151272 -0.140822 -0.989919 + outer loop + vertex -214.536 -17.1035 1.27868 + vertex -213.099 -13.0818 0.684626 + vertex -193.338 -19.3908 1.28014 + endloop + endfacet + facet normal -0.008954 -0.0833255 -0.996482 + outer loop + vertex -191.922 -15.3532 0.686793 + vertex -212.605 -9.12532 0.351863 + vertex -191.451 -11.3934 0.351435 + endloop + endfacet + facet normal -0.00476832 -0.0442855 -0.999008 + outer loop + vertex -212.605 -9.12532 0.351863 + vertex -212.495 -5.21705 0.17809 + vertex -191.451 -11.3934 0.351435 + endloop + endfacet + facet normal -0.00278347 -0.0236308 -0.999717 + outer loop + vertex -212.495 -5.21705 0.17809 + vertex -233.332 1.15073 0.0855855 + vertex -212.249 -1.34982 0.0859941 + endloop + endfacet + facet normal -0.00161755 -0.0138009 -0.999903 + outer loop + vertex -233.332 1.15073 0.0855855 + vertex -232.665 4.93525 0.0322717 + vertex -212.249 -1.34982 0.0859941 + endloop + endfacet + facet normal -0.00100754 -0.00780513 -0.999969 + outer loop + vertex -232.665 4.93525 0.0322717 + vertex -252.685 11.2922 0.00282502 + vertex -231.686 8.57321 0.00288992 + endloop + endfacet + facet normal -0.00038983 -0.00303453 -0.999995 + outer loop + vertex -252.685 11.2922 0.00282502 + vertex -251.407 14.6972 -0.00800576 + vertex -231.686 8.57321 0.00288992 + endloop + endfacet + facet normal -6.66948e-06 -4.30254e-05 -1 + outer loop + vertex -251.407 14.6972 -0.00800576 + vertex -270.775 20.7229 -0.00813585 + vertex -249.991 17.8188 -0.00814951 + endloop + endfacet + facet normal 0.00013444 0.000966822 -1 + outer loop + vertex -270.775 20.7229 -0.00813585 + vertex -269.112 23.5164 -0.00521157 + vertex -249.991 17.8188 -0.00814951 + endloop + endfacet + facet normal 0.000112687 0.000757232 -1 + outer loop + vertex -269.112 23.5164 -0.00521157 + vertex -287.733 29.0694 -0.00310496 + vertex -267.328 26.0142 -0.00311913 + endloop + endfacet + facet normal 5.12964e-05 0.000347227 -1 + outer loop + vertex -287.733 29.0694 -0.00310496 + vertex -285.708 31.3032 -0.00222543 + vertex -267.328 26.0142 -0.00311913 + endloop + endfacet + facet normal 3.09448e-05 0.000194027 -1 + outer loop + vertex -285.708 31.3032 -0.00222543 + vertex -303.493 36.5229 -0.00176302 + vertex -283.61 33.3534 -0.00176273 + endloop + endfacet + facet normal 3.44266e-05 0.000215869 -1 + outer loop + vertex -303.493 36.5229 -0.00176302 + vertex -301.166 38.4015 -0.00127741 + vertex -283.61 33.3534 -0.00176273 + endloop + endfacet + facet normal 3.95759e-05 0.000234568 -1 + outer loop + vertex -301.166 38.4015 -0.00127741 + vertex -318.067 43.408 -0.00077188 + vertex -298.805 40.1596 -0.000771564 + endloop + endfacet + facet normal 3.21068e-05 0.00019028 -1 + outer loop + vertex -318.067 43.408 -0.00077188 + vertex -315.476 45.039 -0.000378346 + vertex -298.805 40.1596 -0.000771564 + endloop + endfacet + facet normal 2.07966e-05 0.000116388 -1 + outer loop + vertex -315.476 45.039 -0.000378346 + vertex -331.875 50.0082 -0.000141049 + vertex -312.983 46.6429 -0.000139834 + endloop + endfacet + facet normal 1.23858e-05 6.93266e-05 -1 + outer loop + vertex -312.983 46.6429 -0.000139834 + vertex -329.464 51.6044 -8.80174e-14 + vertex -310.935 48.2941 -8.8344e-14 + endloop + endfacet + facet normal 1.90399e-05 0.000119357 -1 + outer loop + vertex -296.401 41.8275 -0.000379938 + vertex -294.055 43.4562 -0.000140878 + vertex -277.05 38.7479 -0.000379067 + endloop + endfacet + facet normal 3.05343e-05 0.000191584 -1 + outer loop + vertex -279.276 37.0502 -0.000772295 + vertex -296.401 41.8275 -0.000379938 + vertex -277.05 38.7479 -0.000379067 + endloop + endfacet + facet normal 3.57359e-05 0.000238455 -1 + outer loop + vertex -281.471 35.2607 -0.00127745 + vertex -279.276 37.0502 -0.000772295 + vertex -261.517 32.2734 -0.00127671 + endloop + endfacet + facet normal 3.26902e-05 0.000218111 -1 + outer loop + vertex -263.508 30.3428 -0.0017629 + vertex -281.471 35.2607 -0.00127745 + vertex -261.517 32.2734 -0.00127671 + endloop + endfacet + facet normal 2.71016e-05 0.00019506 -1 + outer loop + vertex -265.455 28.2706 -0.00221987 + vertex -263.508 30.3428 -0.0017629 + vertex -245.077 25.421 -0.00222344 + endloop + endfacet + facet normal 4.90271e-05 0.000351851 -1 + outer loop + vertex -246.811 23.1459 -0.00310893 + vertex -265.455 28.2706 -0.00221987 + vertex -245.077 25.421 -0.00222344 + endloop + endfacet + facet normal 9.97952e-05 0.000770416 -1 + outer loop + vertex -248.456 20.6292 -0.00521201 + vertex -246.811 23.1459 -0.00310893 + vertex -227.808 17.9551 -0.0052116 + endloop + endfacet + facet normal 0.000126486 0.000976508 -1 + outer loop + vertex -229.215 15.1285 -0.00814967 + vertex -248.456 20.6292 -0.00521201 + vertex -227.808 17.9551 -0.0052116 + endloop + endfacet + facet normal -2.23177e-06 -3.46654e-05 -1 + outer loop + vertex -230.513 11.9922 -0.00803805 + vertex -229.215 15.1285 -0.00814967 + vertex -209.689 9.51933 -0.00799881 + endloop + endfacet + facet normal -0.000363813 -0.00307961 -0.999995 + outer loop + vertex -210.759 6.08835 0.00295668 + vertex -230.513 11.9922 -0.00803805 + vertex -209.689 9.51933 -0.00799881 + endloop + endfacet + facet normal -0.000826418 -0.00776824 -0.999969 + outer loop + vertex -211.657 2.4392 0.032047 + vertex -210.759 6.08835 0.00295668 + vertex -190.665 0.180399 0.0322457 + endloop + endfacet + facet normal -0.00149775 -0.0140071 -0.999901 + outer loop + vertex -191.189 -3.61428 0.0861881 + vertex -211.657 2.4392 0.032047 + vertex -190.665 0.180399 0.0322457 + endloop + endfacet + facet normal -0.00232964 -0.0237623 -0.999715 + outer loop + vertex -191.382 -7.48272 0.178588 + vertex -191.189 -3.61428 0.0861881 + vertex -170.209 -9.5198 0.177667 + endloop + endfacet + facet normal -0.0043141 -0.044389 -0.999005 + outer loop + vertex -170.233 -13.428 0.351426 + vertex -191.382 -7.48272 0.178588 + vertex -170.209 -9.5198 0.177667 + endloop + endfacet + facet normal -0.00710332 -0.0832542 -0.996503 + outer loop + vertex -170.666 -17.3934 0.685806 + vertex -170.233 -13.428 0.351426 + vertex -149.32 -19.1997 0.684556 + endloop + endfacet + facet normal -0.0104604 -0.141418 -0.989895 + outer loop + vertex -150.66 -23.2693 1.2801 + vertex -149.32 -19.1997 0.684556 + vertex -129.258 -24.8449 1.27904 + endloop + endfacet + facet normal -0.00599741 -0.0831903 -0.996516 + outer loop + vertex -127.943 -20.7585 0.685728 + vertex -148.928 -15.2308 0.350571 + vertex -127.568 -16.785 0.351761 + endloop + endfacet + facet normal -0.00315514 -0.0441284 -0.999021 + outer loop + vertex -148.928 -15.2308 0.350571 + vertex -148.947 -11.3222 0.177977 + vertex -127.568 -16.785 0.351761 + endloop + endfacet + facet normal -0.00199043 -0.0236537 -0.999718 + outer loop + vertex -148.947 -11.3222 0.177977 + vertex -170.074 -5.65038 0.0858444 + vertex -148.859 -7.45035 0.086193 + endloop + endfacet + facet normal -0.00116577 -0.0139339 -0.999902 + outer loop + vertex -170.074 -5.65038 0.0858444 + vertex -169.613 -1.84887 0.0323316 + vertex -148.859 -7.45035 0.086193 + endloop + endfacet + facet normal -0.000752484 -0.00786232 -0.999969 + outer loop + vertex -169.613 -1.84887 0.0323316 + vertex -189.857 3.83788 0.00285277 + vertex -168.889 1.81649 0.00296784 + endloop + endfacet + facet normal -0.00028931 -0.00305789 -0.999995 + outer loop + vertex -189.857 3.83788 0.00285277 + vertex -188.885 7.27947 -0.00795246 + vertex -168.889 1.81649 0.00296784 + endloop + endfacet + facet normal -1.05127e-05 -7.43215e-05 -1 + outer loop + vertex -188.885 7.27947 -0.00795246 + vertex -208.508 12.6696 -0.00814677 + vertex -187.824 10.4432 -0.00819874 + endloop + endfacet + facet normal 0.000103672 0.000986479 -1 + outer loop + vertex -208.508 12.6696 -0.00814677 + vertex -207.232 15.5114 -0.00521116 + vertex -187.824 10.4432 -0.00819874 + endloop + endfacet + facet normal 9.24061e-05 0.000774474 -1 + outer loop + vertex -207.232 15.5114 -0.00521116 + vertex -226.3 20.4889 -0.00311821 + vertex -205.862 18.0609 -0.00310998 + endloop + endfacet + facet normal 4.30996e-05 0.000359418 -1 + outer loop + vertex -226.3 20.4889 -0.00311821 + vertex -224.71 22.7823 -0.00222539 + vertex -205.862 18.0609 -0.00310998 + endloop + endfacet + facet normal 2.56891e-05 0.000198446 -1 + outer loop + vertex -224.71 22.7823 -0.00222539 + vertex -243.279 27.5136 -0.0017635 + vertex -223.059 24.8932 -0.00176408 + endloop + endfacet + facet normal 2.87537e-05 0.000222093 -1 + outer loop + vertex -243.279 27.5136 -0.0017635 + vertex -241.434 29.4652 -0.00127701 + vertex -223.059 24.8932 -0.00176408 + endloop + endfacet + facet normal 3.37599e-05 0.000241181 -1 + outer loop + vertex -241.434 29.4652 -0.00127701 + vertex -259.484 34.087 -0.000771695 + vertex -239.555 31.298 -0.000771552 + endloop + endfacet + facet normal 2.73743e-05 0.000195552 -1 + outer loop + vertex -259.484 34.087 -0.000771695 + vertex -257.424 35.8101 -0.00037836 + vertex -239.555 31.298 -0.000771552 + endloop + endfacet + facet normal 1.80083e-05 0.000120009 -1 + outer loop + vertex -257.424 35.8101 -0.00037836 + vertex -274.897 40.4084 -0.000141184 + vertex -255.491 37.5022 -0.00014047 + endloop + endfacet + facet normal 1.09123e-05 7.27362e-05 -1 + outer loop + vertex -255.491 37.5022 -0.00014047 + vertex -273.387 42.1184 -8.89533e-14 + vertex -254.02 39.2128 -8.924e-14 + endloop + endfacet + facet normal 1.59505e-05 0.000122787 -1 + outer loop + vertex -237.657 33.0453 -0.00037955 + vertex -235.793 34.7468 -0.000140899 + vertex -217.895 30.4823 -0.000379043 + endloop + endfacet + facet normal 2.56003e-05 0.000197191 -1 + outer loop + vertex -219.639 28.717 -0.000771784 + vertex -237.657 33.0453 -0.00037955 + vertex -217.895 30.4823 -0.000379043 + endloop + endfacet + facet normal 2.92035e-05 0.00024548 -1 + outer loop + vertex -221.364 26.8636 -0.00127712 + vertex -219.639 28.717 -0.000771784 + vertex -201.366 24.4863 -0.0012767 + endloop + endfacet + facet normal 2.66727e-05 0.000224191 -1 + outer loop + vertex -202.909 22.4991 -0.00176335 + vertex -221.364 26.8636 -0.00127712 + vertex -201.366 24.4863 -0.0012767 + endloop + endfacet + facet normal 2.19097e-05 0.000202298 -1 + outer loop + vertex -204.413 20.3709 -0.00222685 + vertex -202.909 22.4991 -0.00176335 + vertex -184.138 18.1868 -0.00222447 + endloop + endfacet + facet normal 3.91851e-05 0.000362669 -1 + outer loop + vertex -185.441 15.8615 -0.00311882 + vertex -204.413 20.3709 -0.00222685 + vertex -184.138 18.1868 -0.00222447 + endloop + endfacet + facet normal 7.56781e-05 0.000783244 -1 + outer loop + vertex -186.673 13.2972 -0.0052206 + vertex -185.441 15.8615 -0.00311882 + vertex -166.054 11.309 -0.00521736 + endloop + endfacet + facet normal 9.52696e-05 0.000986431 -1 + outer loop + vertex -167.074 8.44202 -0.00814265 + vertex -186.673 13.2972 -0.0052206 + vertex -166.054 11.309 -0.00521736 + endloop + endfacet + facet normal -6.98023e-08 -3.40765e-05 -1 + outer loop + vertex -168.023 5.26883 -0.00803445 + vertex -167.074 8.44202 -0.00814265 + vertex -147.064 3.48728 -0.00797521 + endloop + endfacet + facet normal -0.000259307 -0.00308384 -0.999995 + outer loop + vertex -147.832 0.0264346 0.00289662 + vertex -168.023 5.26883 -0.00803445 + vertex -147.064 3.48728 -0.00797521 + endloop + endfacet + facet normal -0.00055794 -0.00784099 -0.999969 + outer loop + vertex -148.474 -3.64752 0.0320634 + vertex -147.832 0.0264346 0.00289662 + vertex -127.26 -5.19879 0.0323907 + endloop + endfacet + facet normal -0.00100809 -0.0139969 -0.999902 + outer loop + vertex -127.586 -9.00746 0.0860338 + vertex -148.474 -3.64752 0.0320634 + vertex -127.26 -5.19879 0.0323907 + endloop + endfacet + facet normal -0.00143261 -0.0237885 -0.999716 + outer loop + vertex -127.618 -12.8777 0.178175 + vertex -127.586 -9.00746 0.0860338 + vertex -106.258 -14.1748 0.17843 + endloop + endfacet + facet normal -0.00263666 -0.0436161 -0.999045 + outer loop + vertex -106.163 -18.0839 0.34884 + vertex -127.618 -12.8777 0.178175 + vertex -106.258 -14.1748 0.17843 + endloop + endfacet + facet normal -0.00415125 -0.0844701 -0.996417 + outer loop + vertex -106.537 -22.0582 0.68732 + vertex -106.163 -18.0839 0.34884 + vertex -85.0824 -23.098 0.686082 + endloop + endfacet + facet normal -0.00531057 -0.141204 -0.989966 + outer loop + vertex -86.4097 -27.2136 1.28022 + vertex -85.0824 -23.098 0.686082 + vertex -64.8959 -28.0134 1.2789 + endloop + endfacet + facet normal -0.00307781 -0.0832929 -0.99652 + outer loop + vertex -63.6248 -23.8824 0.684695 + vertex -84.7544 -19.1166 0.351614 + vertex -63.3331 -19.897 0.350679 + endloop + endfacet + facet normal -0.00166337 -0.0444633 -0.99901 + outer loop + vertex -84.7544 -19.1166 0.351614 + vertex -84.8792 -15.212 0.178039 + vertex -63.3331 -19.897 0.350679 + endloop + endfacet + facet normal -0.00116517 -0.0238329 -0.999715 + outer loop + vertex -84.8792 -15.212 0.178039 + vertex -106.275 -10.3058 0.0860128 + vertex -84.944 -11.3429 0.0858767 + endloop + endfacet + facet normal -0.000690061 -0.0140612 -0.999901 + outer loop + vertex -106.275 -10.3058 0.0860128 + vertex -106.016 -6.49478 0.0322411 + vertex -84.944 -11.3429 0.0858767 + endloop + endfacet + facet normal -0.000470639 -0.00788494 -0.999969 + outer loop + vertex -106.016 -6.49478 0.0322411 + vertex -126.707 -1.52062 0.00275725 + vertex -105.541 -2.80999 0.00296205 + endloop + endfacet + facet normal -0.000177865 -0.00307871 -0.999995 + outer loop + vertex -126.707 -1.52062 0.00275725 + vertex -126.04 1.94883 -0.00804295 + vertex -105.541 -2.80999 0.00296205 + endloop + endfacet + facet normal -1.12503e-06 -2.91231e-05 -1 + outer loop + vertex -126.04 1.94883 -0.00804295 + vertex -146.235 6.6712 -0.00815776 + vertex -125.324 5.14044 -0.0081367 + endloop + endfacet + facet normal 7.41725e-05 0.000999469 -0.999999 + outer loop + vertex -146.235 6.6712 -0.00815776 + vertex -145.342 9.54836 -0.00521595 + vertex -125.324 5.14044 -0.0081367 + endloop + endfacet + facet normal 6.59241e-05 0.00078589 -1 + outer loop + vertex -145.342 9.54836 -0.00521595 + vertex -164.964 13.8869 -0.00309987 + vertex -144.386 12.1372 -0.0031184 + endloop + endfacet + facet normal 2.96963e-05 0.000359833 -1 + outer loop + vertex -164.964 13.8869 -0.00309987 + vertex -163.803 16.2253 -0.00222394 + vertex -144.386 12.1372 -0.0031184 + endloop + endfacet + facet normal 1.95675e-05 0.000202654 -1 + outer loop + vertex -163.803 16.2253 -0.00222394 + vertex -182.781 20.3309 -0.00176329 + vertex -162.596 18.3841 -0.00176284 + endloop + endfacet + facet normal 2.1959e-05 0.00022745 -1 + outer loop + vertex -182.781 20.3309 -0.00176329 + vertex -181.392 22.3335 -0.00127731 + vertex -162.596 18.3841 -0.00176284 + endloop + endfacet + facet normal 2.67684e-05 0.000247914 -1 + outer loop + vertex -181.392 22.3335 -0.00127731 + vertex -199.795 26.3581 -0.00077216 + vertex -179.969 24.2205 -0.000771394 + endloop + endfacet + facet normal 2.17686e-05 0.000201542 -1 + outer loop + vertex -199.795 26.3581 -0.00077216 + vertex -198.205 28.1401 -0.00037841 + vertex -179.969 24.2205 -0.000771394 + endloop + endfacet + facet normal 1.46779e-05 0.000123283 -1 + outer loop + vertex -198.205 28.1401 -0.00037841 + vertex -216.094 32.1938 -0.000141217 + vertex -196.702 29.8881 -0.000140852 + endloop + endfacet + facet normal 8.85373e-06 7.4523e-05 -1 + outer loop + vertex -196.702 29.8881 -0.000140852 + vertex -214.067 33.8412 -8.97699e-14 + vertex -196.286 31.7287 -8.99784e-14 + endloop + endfacet + facet normal 1.22234e-05 0.00012624 -1 + outer loop + vertex -178.531 26.0199 -0.000379573 + vertex -177.186 27.7833 -0.000140526 + vertex -158.795 24.1131 -0.000379046 + endloop + endfacet + facet normal 1.96556e-05 0.000203165 -1 + outer loop + vertex -160.084 22.3026 -0.000772227 + vertex -178.531 26.0199 -0.000379573 + vertex -158.795 24.1131 -0.000379046 + endloop + endfacet + facet normal 2.1344e-05 0.000251193 -1 + outer loop + vertex -161.359 20.4008 -0.00127714 + vertex -160.084 22.3026 -0.000772227 + vertex -141.236 18.6914 -0.00127703 + endloop + endfacet + facet normal 1.94451e-05 0.000228838 -1 + outer loop + vertex -142.323 16.6597 -0.0017631 + vertex -161.359 20.4008 -0.00127714 + vertex -141.236 18.6914 -0.00127703 + endloop + endfacet + facet normal 1.46881e-05 0.000203193 -1 + outer loop + vertex -143.377 14.4884 -0.00221977 + vertex -142.323 16.6597 -0.0017631 + vertex -122.883 12.9876 -0.00222369 + endloop + endfacet + facet normal 2.65379e-05 0.000365012 -1 + outer loop + vertex -123.748 10.6258 -0.00310874 + vertex -143.377 14.4884 -0.00221977 + vertex -122.883 12.9876 -0.00222369 + endloop + endfacet + facet normal 4.78267e-05 0.000792222 -1 + outer loop + vertex -124.564 8.02741 -0.00520629 + vertex -123.748 10.6258 -0.00310874 + vertex -103.743 6.75842 -0.00521583 + endloop + endfacet + facet normal 6.04342e-05 0.000999077 -0.999999 + outer loop + vertex -104.376 3.86426 -0.00814558 + vertex -124.564 8.02741 -0.00520629 + vertex -103.743 6.75842 -0.00521583 + endloop + endfacet + facet normal -4.6324e-06 -5.92279e-05 -1 + outer loop + vertex -104.974 0.665124 -0.00795333 + vertex -104.376 3.86426 -0.00814558 + vertex -83.8857 -0.359462 -0.00799034 + endloop + endfacet + facet normal -0.000152976 -0.00311249 -0.999995 + outer loop + vertex -84.3534 -3.83994 0.00291421 + vertex -104.974 0.665124 -0.00795333 + vertex -83.8857 -0.359462 -0.00799034 + endloop + endfacet + facet normal -0.000281486 -0.00789676 -0.999969 + outer loop + vertex -84.7478 -7.52944 0.0321612 + vertex -84.3534 -3.83994 0.00291421 + vertex -63.4767 -8.30904 0.03233 + endloop + endfacet + facet normal -0.000506665 -0.0140407 -0.999901 + outer loop + vertex -63.6092 -12.1241 0.0859691 + vertex -84.7478 -7.52944 0.0321612 + vertex -63.4767 -8.30904 0.03233 + endloop + endfacet + facet normal -0.00066264 -0.0239485 -0.999713 + outer loop + vertex -63.4967 -15.9914 0.178536 + vertex -63.6092 -12.1241 0.0859691 + vertex -42.1547 -16.5338 0.177382 + endloop + endfacet + facet normal -0.00119281 -0.0448123 -0.998995 + outer loop + vertex -41.959 -20.4337 0.352089 + vertex -63.4967 -15.9914 0.178536 + vertex -42.1547 -16.5338 0.177382 + endloop + endfacet + facet normal -0.0011612 -0.0832677 -0.996527 + outer loop + vertex -42.2243 -24.4233 0.685759 + vertex -41.959 -20.4337 0.352089 + vertex -20.9001 -24.7378 0.687191 + endloop + endfacet + facet normal -0.000602274 -0.140849 -0.990031 + outer loop + vertex -22.1314 -28.8945 1.27931 + vertex -20.9001 -24.7378 0.687191 + vertex -0.85661 -29.0069 1.28236 + endloop + endfacet + facet normal -0.000285015 -0.0828373 -0.996563 + outer loop + vertex 0.392157 -24.8386 0.683598 + vertex -20.6471 -20.7484 0.349622 + vertex 0.604051 -20.8456 0.35163 + endloop + endfacet + facet normal -0.000106297 -0.0438487 -0.999038 + outer loop + vertex -20.6471 -20.7484 0.349622 + vertex -20.889 -16.8475 0.178436 + vertex 0.604051 -20.8456 0.35163 + endloop + endfacet + facet normal -0.000373781 -0.0239726 -0.999713 + outer loop + vertex -20.889 -16.8475 0.178436 + vertex -42.3174 -12.6654 0.086163 + vertex -21.1012 -12.9845 0.0858827 + endloop + endfacet + facet normal -0.000226634 -0.0141894 -0.999899 + outer loop + vertex -42.3174 -12.6654 0.086163 + vertex -42.2523 -8.8518 0.0320301 + vertex -21.1012 -12.9845 0.0858827 + endloop + endfacet + facet normal -0.000204531 -0.00789057 -0.999969 + outer loop + vertex -42.2523 -8.8518 0.0320301 + vertex -63.1651 -4.61699 0.00289141 + vertex -42.0188 -5.15555 0.00281585 + endloop + endfacet + facet normal -8.30188e-05 -0.00311941 -0.999995 + outer loop + vertex -63.1651 -4.61699 0.00289141 + vertex -62.7964 -1.132 -0.00801039 + vertex -42.0188 -5.15555 0.00281585 + endloop + endfacet + facet normal 5.97255e-07 -4.46242e-05 -1 + outer loop + vertex -62.7964 -1.132 -0.00801039 + vertex -83.4034 2.84585 -0.0082002 + vertex -62.4271 2.07713 -0.00815337 + endloop + endfacet + facet normal 3.96167e-05 0.00102011 -0.999999 + outer loop + vertex -83.4034 2.84585 -0.0082002 + vertex -82.8972 5.74552 -0.00522216 + vertex -62.4271 2.07713 -0.00815337 + endloop + endfacet + facet normal 3.90132e-05 0.000798128 -1 + outer loop + vertex -82.8972 5.74552 -0.00522216 + vertex -103.065 9.36525 -0.00311995 + vertex -82.3582 8.35903 -0.00311521 + endloop + endfacet + facet normal 1.82552e-05 0.000370954 -1 + outer loop + vertex -103.065 9.36525 -0.00311995 + vertex -102.346 11.7364 -0.00222723 + vertex -82.3582 8.35903 -0.00311521 + endloop + endfacet + facet normal 1.26599e-05 0.000207315 -1 + outer loop + vertex -102.346 11.7364 -0.00222723 + vertex -121.981 15.1702 -0.00176395 + vertex -101.598 13.9284 -0.00176333 + endloop + endfacet + facet normal 1.41673e-05 0.00023206 -1 + outer loop + vertex -121.981 15.1702 -0.00176395 + vertex -121.055 17.2126 -0.00127685 + vertex -101.598 13.9284 -0.00176333 + endloop + endfacet + facet normal 1.84127e-05 0.00025259 -1 + outer loop + vertex -121.055 17.2126 -0.00127685 + vertex -140.127 20.6035 -0.000771502 + vertex -120.106 19.1394 -0.000772703 + endloop + endfacet + facet normal 1.49959e-05 0.000205871 -1 + outer loop + vertex -140.127 20.6035 -0.000771502 + vertex -139.001 22.4282 -0.000378981 + vertex -120.106 19.1394 -0.000772703 + endloop + endfacet + facet normal 1.08245e-05 0.000126862 -1 + outer loop + vertex -139.001 22.4282 -0.000378981 + vertex -157.527 25.883 -0.000141231 + vertex -137.984 24.219 -0.000140783 + endloop + endfacet + facet normal 6.50766e-06 7.61779e-05 -1 + outer loop + vertex -137.984 24.219 -0.000140783 + vertex -156.643 27.6611 -9.44466e-14 + vertex -137.542 26.0293 -1.07888e-13 + endloop + endfacet + facet normal 7.73073e-06 0.00012783 -1 + outer loop + vertex -119.151 20.9735 -0.00037791 + vertex -118.187 22.7708 -0.000140707 + vertex -99.2313 19.761 -0.000378909 + endloop + endfacet + facet normal 1.25629e-05 0.000207217 -1 + outer loop + vertex -100.045 17.915 -0.000771653 + vertex -119.151 20.9735 -0.00037791 + vertex -99.2313 19.761 -0.000378909 + endloop + endfacet + facet normal 1.24326e-05 0.000255937 -1 + outer loop + vertex -100.831 15.9801 -0.00127663 + vertex -100.045 17.915 -0.000771653 + vertex -80.5754 14.9959 -0.0012767 + endloop + endfacet + facet normal 1.13e-05 0.000232628 -1 + outer loop + vertex -81.1891 12.9359 -0.00176284 + vertex -100.831 15.9801 -0.00127663 + vertex -80.5754 14.9959 -0.0012767 + endloop + endfacet + facet normal 7.91451e-06 0.000207832 -1 + outer loop + vertex -81.7851 10.7369 -0.00222459 + vertex -81.1891 12.9359 -0.00176284 + vertex -61.2222 9.98298 -0.00221853 + endloop + endfacet + facet normal 1.39134e-05 0.000371446 -1 + outer loop + vertex -61.6492 7.60005 -0.0031096 + vertex -81.7851 10.7369 -0.00222459 + vertex -61.2222 9.98298 -0.00221853 + endloop + endfacet + facet normal 2.0431e-05 0.000802434 -1 + outer loop + vertex -62.0509 4.98227 -0.00521841 + vertex -61.6492 7.60005 -0.0031096 + vertex -41.2433 4.45233 -0.00521853 + endloop + endfacet + facet normal 2.56332e-05 0.00100669 -0.999999 + outer loop + vertex -41.4924 1.54426 -0.00815245 + vertex -62.0509 4.98227 -0.00521841 + vertex -41.2433 4.45233 -0.00521853 + endloop + endfacet + facet normal -4.88886e-06 -4.24476e-05 -1 + outer loop + vertex -41.7478 -1.66736 -0.00801487 + vertex -41.4924 1.54426 -0.00815245 + vertex -20.7687 -1.97996 -0.00810417 + endloop + endfacet + facet normal -5.12159e-05 -0.00315145 -0.999995 + outer loop + vertex -20.9415 -5.47044 0.00290482 + vertex -41.7478 -1.66736 -0.00801487 + vertex -20.7687 -1.97996 -0.00810417 + endloop + endfacet + facet normal -3.53632e-05 -0.00793063 -0.999969 + outer loop + vertex -21.0944 -9.16786 0.032234 + vertex -20.9415 -5.47044 0.00290482 + vertex 0.0252995 -9.27115 0.0323063 + endloop + endfacet + facet normal -6.55346e-05 -0.0140996 -0.999901 + outer loop + vertex 0.0807233 -13.0868 0.0861066 + vertex -21.0944 -9.16786 0.032234 + vertex 0.0252995 -9.27115 0.0323063 + endloop + endfacet + facet normal 0.000153194 -0.0237869 -0.999717 + outer loop + vertex 0.335185 -16.9498 0.17806 + vertex 0.0807233 -13.0868 0.0861066 + vertex 21.6044 -16.838 0.178661 + endloop + endfacet + facet normal 0.000259981 -0.0441199 -0.999026 + outer loop + vertex 21.9042 -20.7333 0.350764 + vertex 0.335185 -16.9498 0.17806 + vertex 21.6044 -16.838 0.178661 + endloop + endfacet + facet normal 0.00123583 -0.0838333 -0.996479 + outer loop + vertex 21.6982 -24.7272 0.686517 + vertex 21.9042 -20.7333 0.350764 + vertex 43.1247 -24.3998 0.685547 + endloop + endfacet + facet normal 0.00350633 -0.141331 -0.989956 + outer loop + vertex 41.9121 -28.594 1.28004 + vertex 43.1247 -24.3998 0.685547 + vertex 63.4548 -28.0525 1.27903 + endloop + endfacet + facet normal 0.00218046 -0.0830559 -0.996543 + outer loop + vertex 64.6271 -23.8461 0.68478 + vertex 43.3007 -20.4041 0.351243 + vertex 64.7679 -19.8487 0.351929 + endloop + endfacet + facet normal 0.00117689 -0.0442595 -0.999019 + outer loop + vertex 43.3007 -20.4041 0.351243 + vertex 42.9667 -16.5137 0.178494 + vertex 64.7679 -19.8487 0.351929 + endloop + endfacet + facet normal 0.000399139 -0.0239196 -0.999714 + outer loop + vertex 42.9667 -16.5137 0.178494 + vertex 21.2994 -12.9825 0.0853539 + vertex 42.6187 -12.6585 0.086114 + endloop + endfacet + facet normal 0.000247053 -0.0139112 -0.999903 + outer loop + vertex 21.2994 -12.9825 0.0853539 + vertex 21.185 -9.16542 0.0322208 + vertex 42.6187 -12.6585 0.086114 + endloop + endfacet + facet normal 3.62655e-05 -0.00791457 -0.999969 + outer loop + vertex 21.185 -9.16542 0.0322208 + vertex 0.0988668 -5.57306 0.00302325 + vertex 21.1802 -5.46643 0.00294388 + endloop + endfacet + facet normal 1.21414e-05 -0.00314497 -0.999995 + outer loop + vertex 0.0988668 -5.57306 0.00302325 + vertex 0.175319 -2.08171 -0.00795607 + vertex 21.1802 -5.46643 0.00294388 + endloop + endfacet + facet normal -2.70984e-06 -7.75903e-05 -1 + outer loop + vertex 0.175319 -2.08171 -0.00795607 + vertex -20.627 1.23385 -0.00815696 + vertex 0.201599 1.13445 -0.00820569 + endloop + endfacet + facet normal 2.48048e-06 0.00101001 -0.999999 + outer loop + vertex -20.627 1.23385 -0.00815696 + vertex -20.5046 4.14354 -0.00521784 + vertex 0.201599 1.13445 -0.00820569 + endloop + endfacet + facet normal 1.22548e-05 0.000801141 -1 + outer loop + vertex -20.5046 4.14354 -0.00521784 + vertex -40.979 7.07433 -0.00312077 + vertex -20.3781 6.76703 -0.00311451 + endloop + endfacet + facet normal 5.88663e-06 0.000374234 -1 + outer loop + vertex -40.979 7.07433 -0.00312077 + vertex -40.6972 9.46145 -0.00222577 + vertex -20.3781 6.76703 -0.00311451 + endloop + endfacet + facet normal 5.31606e-06 0.000209522 -1 + outer loop + vertex -40.6972 9.46145 -0.00222577 + vertex -60.777 12.1871 -0.00176143 + vertex -40.4042 11.6683 -0.00176183 + endloop + endfacet + facet normal 5.93081e-06 0.000233662 -1 + outer loop + vertex -60.777 12.1871 -0.00176143 + vertex -60.3163 14.2515 -0.00127633 + vertex -40.4042 11.6683 -0.00176183 + endloop + endfacet + facet normal 9.38487e-06 0.000256624 -1 + outer loop + vertex -60.3163 14.2515 -0.00127633 + vertex -79.9436 16.9367 -0.000771431 + vertex -59.8327 16.2 -0.000771751 + endloop + endfacet + facet normal 7.59763e-06 0.000207836 -1 + outer loop + vertex -79.9436 16.9367 -0.000771431 + vertex -79.2862 18.7946 -0.000380317 + vertex -59.8327 16.2 -0.000771751 + endloop + endfacet + facet normal 6.32399e-06 0.00013033 -1 + outer loop + vertex -79.2862 18.7946 -0.000380317 + vertex -98.3714 21.5627 -0.000140238 + vertex -78.7566 20.6109 -0.000140247 + endloop + endfacet + facet normal 3.78741e-06 7.74955e-05 -1 + outer loop + vertex -78.7566 20.6109 -0.000140247 + vertex -97.7837 23.3505 -1.91469e-13 + vertex -79.1304 22.4389 -2.66476e-13 + endloop + endfacet + facet normal 3.3366e-06 0.00012991 -1 + outer loop + vertex -59.342 18.0614 -0.000379007 + vertex -58.9179 19.8849 -0.000140705 + vertex -39.4345 17.5551 -0.000378362 + endloop + endfacet + facet normal 5.37651e-06 0.000210112 -1 + outer loop + vertex -39.7692 15.6899 -0.000772057 + vertex -59.342 18.0614 -0.000379007 + vertex -39.4345 17.5551 -0.000378362 + endloop + endfacet + facet normal 3.84622e-06 0.0002576 -1 + outer loop + vertex -40.0957 13.7366 -0.00127648 + vertex -39.7692 15.6899 -0.000772057 + vertex -19.9449 13.4358 -0.00127647 + endloop + endfacet + facet normal 3.50584e-06 0.000234799 -1 + outer loop + vertex -20.0972 11.3653 -0.00176316 + vertex -40.0957 13.7366 -0.00127648 + vertex -19.9449 13.4358 -0.00127647 + endloop + endfacet + facet normal 8.79025e-07 0.000208226 -1 + outer loop + vertex -20.2422 9.15542 -0.00222344 + vertex -20.0972 11.3653 -0.00176316 + vertex 0.181599 9.05728 -0.00222592 + endloop + endfacet + facet normal 1.65419e-06 0.000369545 -1 + outer loop + vertex 0.187211 6.66808 -0.00310883 + vertex -20.2422 9.15542 -0.00222344 + vertex 0.181599 9.05728 -0.00222592 + endloop + endfacet + facet normal -3.76763e-06 0.000802855 -1 + outer loop + vertex 0.198304 4.04405 -0.00521559 + vertex 0.187211 6.66808 -0.00310883 + vertex 20.9422 4.15049 -0.00520828 + endloop + endfacet + facet normal -4.83172e-06 0.00101023 -0.999999 + outer loop + vertex 21.0739 1.24045 -0.00814872 + vertex 0.198304 4.04405 -0.00521559 + vertex 20.9422 4.15049 -0.00520828 + endloop + endfacet + facet normal 5.97582e-06 -1.14861e-05 -1 + outer loop + vertex 21.1582 -1.97378 -0.00811129 + vertex 21.0739 1.24045 -0.00814872 + vertex 42.235 -1.65506 -0.007989 + endloop + endfacet + facet normal 5.28936e-05 -0.00311412 -0.999995 + outer loop + vertex 42.3528 -5.14649 0.00289001 + vertex 21.1582 -1.97378 -0.00811129 + vertex 42.235 -1.65506 -0.007989 + endloop + endfacet + facet normal 0.000211354 -0.00791266 -0.999969 + outer loop + vertex 42.4377 -8.84577 0.03218 + vertex 42.3528 -5.14649 0.00289001 + vertex 63.7582 -8.30041 0.0323709 + endloop + endfacet + facet normal 0.00036814 -0.0140421 -0.999901 + outer loop + vertex 64.0008 -12.1124 0.0859942 + vertex 42.4377 -8.84577 0.03218 + vertex 63.7582 -8.30041 0.0323709 + endloop + endfacet + facet normal 0.00086562 -0.0238936 -0.999714 + outer loop + vertex 64.3982 -15.9635 0.178381 + vertex 64.0008 -12.1124 0.0859942 + vertex 85.8256 -15.1734 0.17805 + endloop + endfacet + facet normal 0.00162368 -0.044451 -0.99901 + outer loop + vertex 86.2338 -19.0541 0.351385 + vertex 64.3982 -15.9635 0.178381 + vertex 85.8256 -15.1734 0.17805 + endloop + endfacet + facet normal 0.00403869 -0.0836874 -0.996484 + outer loop + vertex 86.1085 -23.0527 0.686696 + vertex 86.2338 -19.0541 0.351385 + vertex 107.549 -22.0058 0.685673 + endloop + endfacet + facet normal 0.00867618 -0.141074 -0.989961 + outer loop + vertex 106.398 -26.2413 1.27915 + vertex 107.549 -22.0058 0.685673 + vertex 127.803 -24.9465 1.28224 + endloop + endfacet + facet normal 0.005087 -0.082822 -0.996551 + outer loop + vertex 128.966 -20.6951 0.683553 + vertex 107.649 -18.0045 0.35113 + vertex 129.031 -16.6914 0.35115 + endloop + endfacet + facet normal 0.00270701 -0.0440659 -0.999025 + outer loop + vertex 107.649 -18.0045 0.35113 + vertex 107.204 -14.1248 0.178796 + vertex 129.031 -16.6914 0.35115 + endloop + endfacet + facet normal 0.00117041 -0.0241252 -0.999708 + outer loop + vertex 107.204 -14.1248 0.178796 + vertex 85.3778 -11.3269 0.0857214 + vertex 106.705 -10.2874 0.0856056 + endloop + endfacet + facet normal 0.000675729 -0.0139757 -0.999902 + outer loop + vertex 85.3778 -11.3269 0.0857214 + vertex 85.0695 -7.51737 0.0322676 + vertex 106.705 -10.2874 0.0856056 + endloop + endfacet + facet normal 0.000305479 -0.00790787 -0.999969 + outer loop + vertex 85.0695 -7.51737 0.0322676 + vertex 63.5904 -4.60417 0.00266815 + vertex 84.8216 -3.82135 0.00296341 + endloop + endfacet + facet normal 0.000126811 -0.00306211 -0.999995 + outer loop + vertex 63.5904 -4.60417 0.00266815 + vertex 63.3744 -1.11277 -0.00805036 + vertex 84.8216 -3.82135 0.00296341 + endloop + endfacet + facet normal 1.69831e-06 -2.71216e-05 -1 + outer loop + vertex 63.3744 -1.11277 -0.00805036 + vertex 42.0351 1.55888 -0.00815906 + vertex 63.0605 2.09779 -0.00813796 + endloop + endfacet + facet normal -2.48435e-05 0.0010084 -0.999999 + outer loop + vertex 42.0351 1.55888 -0.00815906 + vertex 41.7787 4.46588 -0.00522126 + vertex 63.0605 2.09779 -0.00813796 + endloop + endfacet + facet normal -1.15636e-05 0.000806218 -1 + outer loop + vertex 41.7787 4.46588 -0.00522126 + vertex 20.7966 6.77327 -0.00311837 + vertex 41.492 7.08734 -0.00310448 + endloop + endfacet + facet normal -5.01062e-06 0.000374409 -1 + outer loop + vertex 20.7966 6.77327 -0.00311837 + vertex 20.6453 9.16189 -0.00222329 + vertex 41.492 7.08734 -0.00310448 + endloop + endfacet + facet normal -1.10951e-06 0.000209101 -1 + outer loop + vertex 20.6453 9.16189 -0.00222329 + vertex 0.17308 11.2673 -0.00176034 + vertex 20.4858 11.371 -0.0017612 + endloop + endfacet + facet normal -1.23495e-06 0.000233672 -1 + outer loop + vertex 0.17308 11.2673 -0.00176034 + vertex 0.171201 13.3397 -0.00127608 + vertex 20.4858 11.371 -0.0017612 + endloop + endfacet + facet normal 1.17013e-06 0.00025734 -1 + outer loop + vertex 0.171201 13.3397 -0.00127608 + vertex -19.781 15.392 -0.00077127 + vertex 0.174475 15.2978 -0.000772173 + endloop + endfacet + facet normal 9.40939e-07 0.000208812 -1 + outer loop + vertex -19.781 15.392 -0.00077127 + vertex -19.6061 17.2638 -0.000380261 + vertex 0.174475 15.2978 -0.000772173 + endloop + endfacet + facet normal 1.95627e-06 0.00013151 -1 + outer loop + vertex -19.6061 17.2638 -0.000380261 + vertex -39.0555 19.3788 -0.000140159 + vertex -19.4523 19.0894 -0.000139869 + endloop + endfacet + facet normal 1.11442e-06 7.7001e-05 -1 + outer loop + vertex -19.4523 19.0894 -0.000139869 + vertex -38.6566 21.1838 -4.53707e-13 + vertex -19.5314 20.907 -5.14874e-13 + endloop + endfacet + facet normal -6.20706e-07 0.000130378 -1 + outer loop + vertex 20.0381 17.2709 -0.000378917 + vertex 0.164981 19 -0.000141147 + vertex 19.9148 19.0995 -0.000140441 + endloop + endfacet + facet normal -1.07473e-06 0.000209884 -1 + outer loop + vertex 20.1747 15.4003 -0.000771689 + vertex 0.185054 17.1686 -0.000379056 + vertex 20.0381 17.2709 -0.000378917 + endloop + endfacet + facet normal -3.90553e-06 0.000257559 -1 + outer loop + vertex 20.3262 13.4423 -0.00127658 + vertex 20.1747 15.4003 -0.000771689 + vertex 40.573 13.7499 -0.00127642 + endloop + endfacet + facet normal -3.55727e-06 0.000234639 -1 + outer loop + vertex 40.8861 11.6799 -0.00176325 + vertex 20.3262 13.4423 -0.00127658 + vertex 40.573 13.7499 -0.00127642 + endloop + endfacet + facet normal -5.66614e-06 0.000205234 -1 + outer loop + vertex 41.1946 9.47262 -0.002218 + vertex 40.8861 11.6799 -0.00176325 + vertex 61.8086 10.0018 -0.0022262 + endloop + endfacet + facet normal -9.97678e-06 0.000373156 -1 + outer loop + vertex 62.2529 7.61983 -0.00311947 + vertex 41.1946 9.47262 -0.002218 + vertex 61.8086 10.0018 -0.0022262 + endloop + endfacet + facet normal -2.93711e-05 0.000794452 -1 + outer loop + vertex 62.6742 5.00244 -0.00521124 + vertex 62.2529 7.61983 -0.00311947 + vertex 83.5616 5.7731 -0.00521247 + endloop + endfacet + facet normal -3.711e-05 0.0010042 -0.999999 + outer loop + vertex 84.0758 2.87335 -0.00814348 + vertex 62.6742 5.00244 -0.00521124 + vertex 83.5616 5.7731 -0.00521247 + endloop + endfacet + facet normal 5.91712e-07 -5.89046e-05 -1 + outer loop + vertex 84.5053 -0.333963 -0.0079543 + vertex 84.0758 2.87335 -0.00814348 + vertex 105.587 0.696333 -0.00800251 + endloop + endfacet + facet normal 0.000149996 -0.00311605 -0.999995 + outer loop + vertex 106.003 -2.78752 0.0029158 + vertex 84.5053 -0.333963 -0.0079543 + vertex 105.587 0.696333 -0.00800251 + endloop + endfacet + facet normal 0.000484207 -0.00789383 -0.999969 + outer loop + vertex 106.333 -6.48058 0.0322288 + vertex 106.003 -2.78752 0.0029158 + vertex 127.568 -5.18122 0.0322539 + endloop + endfacet + facet normal 0.000859961 -0.0140346 -0.999901 + outer loop + vertex 128.005 -8.98222 0.0859804 + vertex 106.333 -6.48058 0.0322288 + vertex 127.568 -5.18122 0.0322539 + endloop + endfacet + facet normal 0.00174156 -0.0237995 -0.999715 + outer loop + vertex 128.55 -12.8185 0.178259 + vertex 128.005 -8.98222 0.0859804 + vertex 149.907 -11.2468 0.178046 + endloop + endfacet + facet normal 0.00323919 -0.0441489 -0.99902 + outer loop + vertex 150.425 -15.1148 0.350662 + vertex 128.55 -12.8185 0.178259 + vertex 149.907 -11.2468 0.178046 + endloop + endfacet + facet normal 0.00706759 -0.0835928 -0.996475 + outer loop + vertex 150.376 -19.1202 0.686323 + vertex 150.425 -15.1148 0.350662 + vertex 171.81 -17.2899 0.684801 + endloop + endfacet + facet normal 0.0136504 -0.140922 -0.989927 + outer loop + vertex 170.73 -21.5675 1.27886 + vertex 171.81 -17.2899 0.684801 + vertex 192.123 -19.5115 1.28117 + endloop + endfacet + facet normal 0.00801404 -0.0841202 -0.996423 + outer loop + vertex 193.161 -15.2229 0.687137 + vertex 171.816 -13.2831 0.351701 + vertex 193.151 -11.2165 0.348825 + endloop + endfacet + facet normal 0.00414825 -0.0442149 -0.999013 + outer loop + vertex 171.816 -13.2831 0.351701 + vertex 171.26 -9.4202 0.178426 + vertex 193.151 -11.2165 0.348825 + endloop + endfacet + facet normal 0.00202236 -0.0238283 -0.999714 + outer loop + vertex 171.26 -9.4202 0.178426 + vertex 149.313 -7.41434 0.0862187 + vertex 170.612 -5.59765 0.0860046 + endloop + endfacet + facet normal 0.00119424 -0.0141192 -0.9999 + outer loop + vertex 149.313 -7.41434 0.0862187 + vertex 148.808 -3.62118 0.032054 + vertex 170.612 -5.59765 0.0860046 + endloop + endfacet + facet normal 0.000574729 -0.00783662 -0.999969 + outer loop + vertex 148.808 -3.62118 0.032054 + vertex 127.155 -1.49234 0.00292557 + vertex 148.313 0.0641408 0.00288804 + endloop + endfacet + facet normal 0.000229172 -0.00313933 -0.999995 + outer loop + vertex 127.155 -1.49234 0.00292557 + vertex 126.64 1.98667 -0.00811439 + vertex 148.313 0.0641408 0.00288804 + endloop + endfacet + facet normal -3.08539e-07 -2.69713e-05 -1 + outer loop + vertex 126.64 1.98667 -0.00811439 + vertex 105.042 3.89846 -0.00815929 + vertex 125.979 5.18253 -0.00820038 + endloop + endfacet + facet normal -6.3568e-05 0.00100445 -0.999999 + outer loop + vertex 105.042 3.89846 -0.00815929 + vertex 104.399 6.79215 -0.00521184 + vertex 125.979 5.18253 -0.00820038 + endloop + endfacet + facet normal -3.86822e-05 0.000796591 -1 + outer loop + vertex 104.399 6.79215 -0.00521184 + vertex 83.0008 8.38548 -0.00311486 + vertex 103.7 9.3974 -0.00310945 + endloop + endfacet + facet normal -1.7968e-05 0.000372877 -1 + outer loop + vertex 83.0008 8.38548 -0.00311486 + vertex 82.41 10.7615 -0.00221829 + vertex 103.7 9.3974 -0.00310945 + endloop + endfacet + facet normal -7.5807e-06 0.000204881 -1 + outer loop + vertex 82.41 10.7615 -0.00221829 + vertex 61.3479 12.2055 -0.00176276 + vertex 81.7979 12.9596 -0.0017633 + endloop + endfacet + facet normal -8.62611e-06 0.000233234 -1 + outer loop + vertex 61.3479 12.2055 -0.00176276 + vertex 60.8781 14.271 -0.00127697 + vertex 81.7979 12.9596 -0.0017633 + endloop + endfacet + facet normal -6.58501e-06 0.000257792 -1 + outer loop + vertex 60.8781 14.271 -0.00127697 + vertex 40.2656 15.7048 -0.000771612 + vertex 60.4115 16.2203 -0.000771377 + endloop + endfacet + facet normal -5.42276e-06 0.000208786 -1 + outer loop + vertex 60.4115 16.2203 -0.000771377 + vertex 39.9718 17.572 -0.000378337 + vertex 59.9504 18.0847 -0.000379616 + endloop + endfacet + facet normal -3.313e-06 0.000130334 -1 + outer loop + vertex 59.9504 18.0847 -0.000379616 + vertex 39.6235 19.3971 -0.000141227 + vertex 59.4689 19.9043 -0.000140872 + endloop + endfacet + facet normal -1.9735e-06 7.79492e-05 -1 + outer loop + vertex 59.4689 19.9043 -0.000140872 + vertex 38.5271 21.1813 -4.14108e-13 + vertex 59.6337 21.7157 -2.99726e-13 + endloop + endfacet + facet normal -6.34572e-06 0.000128362 -1 + outer loop + vertex 99.8448 19.7913 -0.000377896 + vertex 79.3431 20.6332 -0.00013973 + vertex 99.0906 21.6015 -0.00014075 + endloop + endfacet + facet normal -1.01456e-05 0.000209691 -1 + outer loop + vertex 100.63 17.946 -0.000772805 + vertex 79.9197 18.8203 -0.000379351 + vertex 99.8448 19.7913 -0.000377896 + endloop + endfacet + facet normal -1.25342e-05 0.000255219 -1 + outer loop + vertex 101.418 16.0084 -0.00127719 + vertex 80.5444 16.9633 -0.00077185 + vertex 100.63 17.946 -0.000772805 + endloop + endfacet + facet normal -1.14023e-05 0.000232794 -1 + outer loop + vertex 102.202 13.9588 -0.00176326 + vertex 81.1724 15.0192 -0.00127663 + vertex 101.418 16.0084 -0.00127719 + endloop + endfacet + facet normal -1.27676e-05 0.000206238 -1 + outer loop + vertex 102.964 11.7672 -0.002225 + vertex 102.202 13.9588 -0.00176326 + vertex 123.488 13.0268 -0.00222726 + endloop + endfacet + facet normal -2.27971e-05 0.000369651 -1 + outer loop + vertex 124.369 10.6656 -0.00312017 + vertex 102.964 11.7672 -0.002225 + vertex 123.488 13.0268 -0.00222726 + endloop + endfacet + facet normal -5.79054e-05 0.000791669 -1 + outer loop + vertex 125.207 8.06828 -0.0052249 + vertex 124.369 10.6656 -0.00312017 + vertex 146.018 9.60154 -0.00521613 + endloop + endfacet + facet normal -7.43226e-05 0.0010145 -0.999999 + outer loop + vertex 146.919 6.72517 -0.00820118 + vertex 125.207 8.06828 -0.0052249 + vertex 146.018 9.60154 -0.00521613 + endloop + endfacet + facet normal 4.06404e-06 -7.26203e-05 -1 + outer loop + vertex 147.696 3.53655 -0.00796646 + vertex 146.919 6.72517 -0.00820118 + vertex 168.742 5.33591 -0.0080116 + endloop + endfacet + facet normal 0.000258858 -0.00305276 -0.999995 + outer loop + vertex 169.462 1.87003 0.00275527 + vertex 147.696 3.53655 -0.00796646 + vertex 168.742 5.33591 -0.0080116 + endloop + endfacet + facet normal 0.000761258 -0.00793596 -0.999968 + outer loop + vertex 170.041 -1.80721 0.0323798 + vertex 169.462 1.87003 0.00275527 + vertex 191.197 0.238572 0.0322495 + endloop + endfacet + facet normal 0.00134281 -0.0139498 -0.999902 + outer loop + vertex 191.836 -3.54554 0.0859007 + vertex 170.041 -1.80721 0.0323798 + vertex 191.197 0.238572 0.0322495 + endloop + endfacet + facet normal 0.00258534 -0.0236261 -0.999718 + outer loop + vertex 192.539 -7.36165 0.177905 + vertex 191.836 -3.54554 0.0859007 + vertex 213.684 -5.07883 0.178636 + endloop + endfacet + facet normal 0.00479767 -0.0441177 -0.999015 + outer loop + vertex 214.325 -8.92927 0.351757 + vertex 192.539 -7.36165 0.177905 + vertex 213.684 -5.07883 0.178636 + endloop + endfacet + facet normal 0.00983001 -0.0830588 -0.996496 + outer loop + vertex 214.386 -12.9354 0.68627 + vertex 214.325 -8.92927 0.351757 + vertex 235.48 -10.4332 0.68579 + endloop + endfacet + facet normal 0.0180583 -0.140893 -0.98986 + outer loop + vertex 234.476 -14.7465 1.28142 + vertex 235.48 -10.4332 0.68579 + vertex 255.538 -12.0384 1.28018 + endloop + endfacet + facet normal 0.0106944 -0.0825841 -0.996527 + outer loop + vertex 256.535 -7.71091 0.68467 + vertex 235.395 -6.42549 0.351276 + vertex 256.413 -3.70421 0.35132 + endloop + endfacet + facet normal 0.00568943 -0.0439274 -0.999019 + outer loop + vertex 235.395 -6.42549 0.351276 + vertex 234.714 -2.58121 0.178363 + vertex 256.413 -3.70421 0.35132 + endloop + endfacet + facet normal 0.00280361 -0.0237169 -0.999715 + outer loop + vertex 234.714 -2.58121 0.178363 + vertex 212.93 -1.26995 0.0861626 + vertex 233.908 1.21955 0.0859343 + endloop + endfacet + facet normal 0.0016489 -0.0139865 -0.999901 + outer loop + vertex 212.93 -1.26995 0.0861626 + vertex 212.223 2.5054 0.0321872 + vertex 233.908 1.21955 0.0859343 + endloop + endfacet + facet normal 0.000845874 -0.00778903 -0.999969 + outer loop + vertex 212.223 2.5054 0.0321872 + vertex 190.531 3.91001 0.00289749 + vertex 211.47 6.16941 0.00301071 + endloop + endfacet + facet normal 0.000336947 -0.00307255 -0.999995 + outer loop + vertex 190.531 3.91001 0.00289749 + vertex 189.71 7.36692 -0.00800089 + vertex 211.47 6.16941 0.00301071 + endloop + endfacet + facet normal 3.8002e-06 -5.07345e-05 -1 + outer loop + vertex 189.71 7.36692 -0.00800089 + vertex 167.847 8.51425 -0.00814219 + vertex 188.698 10.5351 -0.00816548 + endloop + endfacet + facet normal -9.6964e-05 0.000988916 -1 + outer loop + vertex 167.847 8.51425 -0.00814219 + vertex 166.817 11.3806 -0.00520769 + vertex 188.698 10.5351 -0.00816548 + endloop + endfacet + facet normal -6.69877e-05 0.000785874 -1 + outer loop + vertex 166.817 11.3806 -0.00520769 + vertex 145.041 12.1887 -0.00311395 + vertex 165.701 13.9559 -0.00310909 + endloop + endfacet + facet normal -3.09568e-05 0.000364652 -1 + outer loop + vertex 145.041 12.1887 -0.00311395 + vertex 144.014 14.539 -0.00222509 + vertex 165.701 13.9559 -0.00310909 + endloop + endfacet + facet normal -1.51151e-05 0.000205192 -1 + outer loop + vertex 144.014 14.539 -0.00222509 + vertex 122.573 15.208 -0.00176375 + vertex 142.946 16.7093 -0.00176363 + endloop + endfacet + facet normal -1.69736e-05 0.000230748 -1 + outer loop + vertex 142.946 16.7093 -0.00176363 + vertex 121.635 17.2503 -0.00127706 + vertex 141.853 18.739 -0.00127673 + endloop + endfacet + facet normal -1.86812e-05 0.000252809 -1 + outer loop + vertex 141.853 18.739 -0.00127673 + vertex 120.688 19.1736 -0.000771455 + vertex 140.756 20.6537 -0.000772184 + endloop + endfacet + facet normal -1.51516e-05 0.000206512 -1 + outer loop + vertex 140.756 20.6537 -0.000772184 + vertex 119.755 21.0142 -0.000379537 + vertex 139.67 22.4804 -0.000378484 + endloop + endfacet + facet normal -9.35242e-06 0.000127248 -1 + outer loop + vertex 139.67 22.4804 -0.000378484 + vertex 118.828 22.8129 -0.000141258 + vertex 138.562 24.2661 -0.00014089 + endloop + endfacet + facet normal -5.63755e-06 7.66466e-05 -1 + outer loop + vertex 138.562 24.2661 -0.00014089 + vertex 117.55 24.5589 -4.50522e-14 + vertex 137.543 26.0294 -1.02639e-14 + endloop + endfacet + facet normal -1.22001e-05 0.000125774 -1 + outer loop + vertex 179.365 26.1047 -0.000378941 + vertex 158.33 25.957 -0.000140895 + vertex 177.991 27.8653 -0.000140755 + endloop + endfacet + facet normal -1.96493e-05 0.000202937 -1 + outer loop + vertex 180.775 24.3058 -0.000771707 + vertex 159.562 24.1841 -0.000379589 + vertex 179.365 26.1047 -0.000378941 + endloop + endfacet + facet normal -2.41963e-05 0.000249491 -1 + outer loop + vertex 182.186 22.42 -0.00127636 + vertex 160.807 22.3692 -0.00077174 + vertex 180.775 24.3058 -0.000771707 + endloop + endfacet + facet normal -2.20411e-05 0.000227562 -1 + outer loop + vertex 183.588 20.4183 -0.00176278 + vertex 162.058 20.4672 -0.0012771 + vertex 182.186 22.42 -0.00127636 + endloop + endfacet + facet normal -1.95645e-05 0.000202191 -1 + outer loop + vertex 184.96 18.2746 -0.00222305 + vertex 163.306 18.4508 -0.00176377 + vertex 183.588 20.4183 -0.00176278 + endloop + endfacet + facet normal -3.52881e-05 0.000365119 -1 + outer loop + vertex 186.282 15.9508 -0.00311817 + vertex 164.526 16.2938 -0.0022252 + vertex 184.96 18.2746 -0.00222305 + endloop + endfacet + facet normal -8.38047e-05 0.000778283 -1 + outer loop + vertex 187.537 13.3884 -0.00521763 + vertex 186.282 15.9508 -0.00311817 + vertex 208.129 15.6133 -0.00521172 + endloop + endfacet + facet normal -0.000106285 0.000986347 -1 + outer loop + vertex 209.418 12.7731 -0.0081502 + vertex 187.537 13.3884 -0.00521763 + vertex 208.129 15.6133 -0.00521172 + endloop + endfacet + facet normal 8.76932e-06 -8.3464e-06 -1 + outer loop + vertex 210.55 9.61722 -0.00811394 + vertex 209.418 12.7731 -0.0081502 + vertex 231.273 12.0813 -0.00795278 + endloop + endfacet + facet normal 0.000365517 -0.00300864 -0.999995 + outer loop + vertex 232.299 8.64421 0.00276331 + vertex 210.55 9.61722 -0.00811394 + vertex 231.273 12.0813 -0.00795278 + endloop + endfacet + facet normal 0.00100545 -0.00788452 -0.999968 + outer loop + vertex 233.133 4.98956 0.0324181 + vertex 232.299 8.64421 0.00276331 + vertex 253.99 7.68655 0.0321245 + endloop + endfacet + facet normal 0.00179724 -0.0140078 -0.9999 + outer loop + vertex 254.833 3.92778 0.086296 + vertex 233.133 4.98956 0.0324181 + vertex 253.99 7.68655 0.0321245 + endloop + endfacet + facet normal 0.00328871 -0.0235211 -0.999718 + outer loop + vertex 255.691 0.133416 0.178393 + vertex 254.833 3.92778 0.086296 + vertex 276.65 3.05875 0.178513 + endloop + endfacet + facet normal 0.00613202 -0.0438922 -0.999017 + outer loop + vertex 277.417 -0.771201 0.35149 + vertex 255.691 0.133416 0.178393 + vertex 276.65 3.05875 0.178513 + endloop + endfacet + facet normal 0.0123446 -0.0829264 -0.996479 + outer loop + vertex 277.578 -4.77542 0.686721 + vertex 277.417 -0.771201 0.35149 + vertex 298.582 -1.64038 0.686028 + endloop + endfacet + facet normal 0.0221783 -0.140452 -0.989839 + outer loop + vertex 297.717 -5.97456 1.28163 + vertex 298.582 -1.64038 0.686028 + vertex 318.636 -2.66404 1.28059 + endloop + endfacet + facet normal 0.0131081 -0.0821968 -0.99653 + outer loop + vertex 319.507 1.68498 0.6853 + vertex 298.38 2.36129 0.351611 + vertex 319.282 5.68674 0.352258 + endloop + endfacet + facet normal 0.00698889 -0.0437342 -0.999019 + outer loop + vertex 298.38 2.36129 0.351611 + vertex 297.573 6.18333 0.178646 + vertex 319.282 5.68674 0.352258 + endloop + endfacet + facet normal 0.00352894 -0.0233834 -0.99972 + outer loop + vertex 297.573 6.18333 0.178646 + vertex 275.738 6.84275 0.0861456 + vertex 296.608 9.96038 0.0868962 + endloop + endfacet + facet normal 0.00209216 -0.013765 -0.999903 + outer loop + vertex 275.738 6.84275 0.0861456 + vertex 274.828 10.5957 0.0325784 + vertex 296.608 9.96038 0.0868962 + endloop + endfacet + facet normal 0.0010973 -0.00773411 -0.999969 + outer loop + vertex 274.828 10.5957 0.0325784 + vertex 253.07 11.334 0.00299278 + vertex 273.823 14.232 0.00335141 + endloop + endfacet + facet normal 0.00044088 -0.00303343 -0.999995 + outer loop + vertex 253.07 11.334 0.00299278 + vertex 251.944 14.7595 -0.00789502 + vertex 273.823 14.232 0.00335141 + endloop + endfacet + facet normal 8.73535e-06 -5.39018e-05 -1 + outer loop + vertex 251.944 14.7595 -0.00789502 + vertex 230.026 15.2244 -0.00811154 + vertex 250.582 17.8891 -0.00807561 + endloop + endfacet + facet normal -0.000124264 0.000972059 -1 + outer loop + vertex 230.026 15.2244 -0.00811154 + vertex 228.609 18.0505 -0.00518826 + vertex 250.582 17.8891 -0.00807561 + endloop + endfacet + facet normal -9.15397e-05 0.000768122 -1 + outer loop + vertex 228.609 18.0505 -0.00518826 + vertex 206.735 18.1612 -0.00310094 + vertex 227.076 20.5816 -0.00310382 + endloop + endfacet + facet normal -4.21899e-05 0.000357943 -1 + outer loop + vertex 227.076 20.5816 -0.00310382 + vertex 205.268 20.4695 -0.00222382 + vertex 225.465 22.873 -0.00221562 + endloop + endfacet + facet normal -2.34108e-05 0.000198485 -1 + outer loop + vertex 225.465 22.873 -0.00221562 + vertex 203.745 22.5964 -0.00176205 + vertex 223.793 24.9824 -0.00175779 + endloop + endfacet + facet normal -2.64093e-05 0.000222702 -1 + outer loop + vertex 223.793 24.9824 -0.00175779 + vertex 202.187 24.5807 -0.00127667 + vertex 222.078 26.9477 -0.00127483 + endloop + endfacet + facet normal -2.91306e-05 0.000245095 -1 + outer loop + vertex 222.078 26.9477 -0.00127483 + vertex 200.614 26.4505 -0.000771444 + vertex 220.35 28.7999 -0.00077055 + endloop + endfacet + facet normal -2.36966e-05 0.000198509 -1 + outer loop + vertex 220.35 28.7999 -0.00077055 + vertex 199.043 28.2329 -0.000378188 + vertex 218.633 30.568 -0.00037888 + endloop + endfacet + facet normal -1.57613e-05 0.000122315 -1 + outer loop + vertex 218.633 30.568 -0.00037888 + vertex 216.975 32.2996 -0.000140942 + vertex 238.181 33.1039 -0.000376789 + endloop + endfacet + facet normal -8.85829e-06 7.43384e-05 -1 + outer loop + vertex 216.975 32.2996 -0.000140942 + vertex 196.004 31.6966 9.62153e-15 + vertex 215.646 34.0371 9.62153e-15 + endloop + endfacet + facet normal -1.6642e-05 0.000119148 -1 + outer loop + vertex 257.702 35.8364 -0.000372878 + vertex 236.335 34.8101 -0.000139564 + vertex 255.658 37.5167 -0.000138656 + endloop + endfacet + facet normal -2.77105e-05 0.000191076 -1 + outer loop + vertex 259.724 34.1084 -0.000759085 + vertex 257.702 35.8364 -0.000372878 + vertex 279.371 37.0504 -0.000741364 + endloop + endfacet + facet normal -3.24582e-05 0.000234726 -1 + outer loop + vertex 261.75 32.295 -0.00125049 + vertex 240.043 31.3537 -0.000766866 + vertex 259.724 34.1084 -0.000759085 + endloop + endfacet + facet normal -2.86011e-05 0.00021081 -1 + outer loop + vertex 263.765 30.3681 -0.00171433 + vertex 241.922 29.5226 -0.00126785 + vertex 261.75 32.295 -0.00125049 + endloop + endfacet + facet normal -2.35686e-05 0.000179523 -1 + outer loop + vertex 265.737 28.2999 -0.0021321 + vertex 243.787 27.5744 -0.001745 + vertex 263.765 30.3681 -0.00171433 + endloop + endfacet + facet normal -4.4235e-05 0.000337939 -1 + outer loop + vertex 267.638 26.0473 -0.00297743 + vertex 245.609 25.4848 -0.00219306 + vertex 265.737 28.2999 -0.0021321 + endloop + endfacet + facet normal -0.0001004 0.000746108 -1 + outer loop + vertex 269.445 23.5525 -0.00502022 + vertex 247.365 23.2124 -0.00305713 + vertex 267.638 26.0473 -0.00297743 + endloop + endfacet + facet normal -0.000126201 0.000948429 -1 + outer loop + vertex 271.119 20.7591 -0.00788078 + vertex 249.035 20.6978 -0.00515189 + vertex 269.445 23.5525 -0.00502022 + endloop + endfacet + facet normal 3.08384e-05 -1.07791e-05 -1 + outer loop + vertex 272.599 17.6459 -0.00780158 + vertex 271.119 20.7591 -0.00788078 + vertex 293.219 20.7283 -0.00719892 + endloop + endfacet + facet normal 0.000472881 -0.0029678 -0.999995 + outer loop + vertex 294.548 17.3284 0.00351979 + vertex 272.599 17.6459 -0.00780158 + vertex 293.219 20.7283 -0.00719892 + endloop + endfacet + facet normal 0.00127213 -0.00781979 -0.999969 + outer loop + vertex 295.631 13.7031 0.0332488 + vertex 294.548 17.3284 0.00351979 + vertex 316.37 17.0002 0.0338486 + endloop + endfacet + facet normal 0.00220989 -0.0137184 -0.999903 + outer loop + vertex 317.416 13.2672 0.0873746 + vertex 295.631 13.7031 0.0332488 + vertex 316.37 17.0002 0.0338486 + endloop + endfacet + facet normal 0.00395806 -0.0234853 -0.999716 + outer loop + vertex 318.434 9.50248 0.179848 + vertex 317.416 13.2672 0.0873746 + vertex 339.232 13.0118 0.179749 + endloop + endfacet + facet normal 0.00736944 -0.0437025 -0.999017 + outer loop + vertex 340.137 9.20805 0.352823 + vertex 318.434 9.50248 0.179848 + vertex 339.232 13.0118 0.179749 + endloop + endfacet + facet normal 0.0146578 -0.0824708 -0.996486 + outer loop + vertex 340.393 5.20771 0.68766 + vertex 340.137 9.20805 0.352823 + vertex 361.299 8.93906 0.68637 + endloop + endfacet + facet normal 0.0263077 -0.139553 -0.989865 + outer loop + vertex 360.494 4.57401 1.28036 + vertex 361.299 8.93906 0.68637 + vertex 381.484 8.51044 1.28324 + endloop + endfacet + facet normal 0.0155361 -0.0824088 -0.996478 + outer loop + vertex 382.177 12.8711 0.687668 + vertex 360.955 12.9282 0.352068 + vertex 381.751 16.8511 0.351861 + endloop + endfacet + facet normal 0.00816445 -0.0433322 -0.999027 + outer loop + vertex 360.955 12.9282 0.352068 + vertex 359.961 16.7173 0.179596 + vertex 381.751 16.8511 0.351861 + endloop + endfacet + facet normal 0.00414497 -0.0235185 -0.999715 + outer loop + vertex 359.961 16.7173 0.179596 + vertex 338.142 16.7657 0.087988 + vertex 358.779 20.4512 0.086853 + endloop + endfacet + facet normal 0.00241281 -0.0138189 -0.999902 + outer loop + vertex 338.142 16.7657 0.087988 + vertex 337.016 20.4823 0.0339083 + vertex 358.779 20.4512 0.086853 + endloop + endfacet + facet normal 0.00130294 -0.00763399 -0.99997 + outer loop + vertex 337.016 20.4823 0.0339083 + vertex 315.2 20.6142 0.00447487 + vertex 335.754 24.0825 0.00477862 + endloop + endfacet + facet normal 0.000528576 -0.00304492 -0.999995 + outer loop + vertex 315.2 20.6142 0.00447487 + vertex 313.775 24.0002 -0.00658824 + vertex 335.754 24.0825 0.00477862 + endloop + endfacet + facet normal 4.43687e-05 -9.23146e-05 -1 + outer loop + vertex 313.775 24.0002 -0.00658824 + vertex 291.629 23.8284 -0.00755498 + vertex 312.069 27.0815 -0.00694838 + endloop + endfacet + facet normal -0.000118758 0.000878221 -1 + outer loop + vertex 312.069 27.0815 -0.00694838 + vertex 289.826 26.602 -0.00472797 + vertex 310.141 29.8359 -0.00430041 + endloop + endfacet + facet normal -9.09903e-05 0.000661907 -1 + outer loop + vertex 310.141 29.8359 -0.00430041 + vertex 287.883 29.0773 -0.00277726 + vertex 308.062 32.291 -0.00248624 + endloop + endfacet + facet normal -3.25195e-05 0.000263883 -1 + outer loop + vertex 308.062 32.291 -0.00248624 + vertex 285.837 31.3084 -0.00202277 + vertex 305.875 34.5009 -0.00183196 + endloop + endfacet + facet normal -1.48864e-05 0.000127604 -1 + outer loop + vertex 305.875 34.5009 -0.00183196 + vertex 283.717 33.3552 -0.0016483 + vertex 303.608 36.5247 -0.00153997 + endloop + endfacet + facet normal -2.46095e-05 0.000173081 -1 + outer loop + vertex 303.608 36.5247 -0.00153997 + vertex 281.552 35.2598 -0.00121611 + vertex 301.291 38.406 -0.00115733 + endloop + endfacet + facet normal -3.12282e-05 0.000210849 -1 + outer loop + vertex 301.291 38.406 -0.00115733 + vertex 298.954 40.1741 -0.000711555 + vertex 320.924 41.7258 -0.00107047 + endloop + endfacet + facet normal -2.7417e-05 0.000176069 -1 + outer loop + vertex 298.954 40.1741 -0.000711555 + vertex 277.188 38.7562 -0.000364441 + vertex 296.613 41.8567 -0.000351123 + endloop + endfacet + facet normal -1.73894e-05 0.000110842 -1 + outer loop + vertex 296.613 41.8567 -0.000351123 + vertex 275.027 40.419 -0.0001351 + vertex 294.354 43.5033 -0.000129328 + endloop + endfacet + facet normal -1.05046e-05 6.57397e-05 -1 + outer loop + vertex 294.354 43.5033 -0.000129328 + vertex 273.01 42.06 9.62153e-15 + vertex 292.762 45.2161 9.62153e-15 + endloop + endfacet + facet normal -1.61162e-05 9.35135e-05 -1 + outer loop + vertex 335.033 48.5357 -0.000299254 + vertex 313.413 46.724 -0.000120236 + vertex 332.266 50.0923 -0.0001091 + endloop + endfacet + facet normal -2.50815e-05 0.000149019 -1 + outer loop + vertex 337.751 46.9223 -0.000607862 + vertex 315.914 45.1203 -0.000328691 + vertex 335.033 48.5357 -0.000299254 + endloop + endfacet + facet normal -2.69931e-05 0.000167769 -1 + outer loop + vertex 340.416 45.2111 -0.000966882 + vertex 318.429 43.4669 -0.000666007 + vertex 337.751 46.9223 -0.000607862 + endloop + endfacet + facet normal -1.34412e-05 0.000115616 -1 + outer loop + vertex 343.039 43.3821 -0.00121358 + vertex 340.416 45.2111 -0.000966882 + vertex 362.624 47.082 -0.00104907 + endloop + endfacet + facet normal 2.02439e-08 4.89191e-05 -1 + outer loop + vertex 345.602 41.4091 -0.00131005 + vertex 323.392 39.8692 -0.00138583 + vertex 343.039 43.3821 -0.00121358 + endloop + endfacet + facet normal -1.71506e-05 0.000172036 -1 + outer loop + vertex 348.077 39.2489 -0.00172414 + vertex 325.807 37.8696 -0.00157948 + vertex 345.602 41.4091 -0.00131005 + endloop + endfacet + facet normal -8.83122e-05 0.000599359 -1 + outer loop + vertex 350.43 36.8406 -0.00337536 + vertex 328.137 35.683 -0.00210045 + vertex 348.077 39.2489 -0.00172414 + endloop + endfacet + facet normal -0.000137995 0.000886718 -1 + outer loop + vertex 352.61 34.1281 -0.00608152 + vertex 330.352 33.2499 -0.00378863 + vertex 350.43 36.8406 -0.00337536 + endloop + endfacet + facet normal 1.10922e-05 1.87258e-05 -1 + outer loop + vertex 354.548 31.0852 -0.00611701 + vertex 332.404 30.5144 -0.00637332 + vertex 352.61 34.1281 -0.00608152 + endloop + endfacet + facet normal 0.000515095 -0.00289686 -0.999996 + outer loop + vertex 356.185 27.734 0.00443432 + vertex 334.225 27.4518 -0.00605992 + vertex 354.548 31.0852 -0.00611701 + endloop + endfacet + facet normal 0.00132837 -0.00755859 -0.999971 + outer loop + vertex 357.553 24.1525 0.0333237 + vertex 356.185 27.734 0.00443432 + vertex 378.072 28.03 0.0312719 + endloop + endfacet + facet normal 0.00246682 -0.013583 -0.999905 + outer loop + vertex 379.403 24.344 0.0846257 + vertex 357.553 24.1525 0.0333237 + vertex 378.072 28.03 0.0312719 + endloop + endfacet + facet normal 0.00457016 -0.0233739 -0.999716 + outer loop + vertex 380.677 20.6247 0.177412 + vertex 379.403 24.344 0.0846257 + vertex 401.605 24.7769 0.176004 + endloop + endfacet + facet normal 0.00861482 -0.04376 -0.999005 + outer loop + vertex 402.691 21.0019 0.350721 + vertex 380.677 20.6247 0.177412 + vertex 401.605 24.7769 0.176004 + endloop + endfacet + facet normal 0.0170188 -0.0819137 -0.996494 + outer loop + vertex 403.116 17.0163 0.685601 + vertex 402.691 21.0019 0.350721 + vertex 424.327 21.4051 0.687087 + endloop + endfacet + facet normal 0.029807 -0.138646 -0.989893 + outer loop + vertex 423.498 16.9964 1.27961 + vertex 424.327 21.4051 0.687087 + vertex 444.831 21.5871 1.27901 + endloop + endfacet + facet normal 0.0178126 -0.0800969 -0.996628 + outer loop + vertex 445.88 26.0392 0.694956 + vertex 424.054 25.4222 0.354468 + vertex 445.751 30.0848 0.367524 + endloop + endfacet + facet normal 0.0101342 -0.0436166 -0.998997 + outer loop + vertex 466.579 34.7669 0.374539 + vertex 444.862 33.9048 0.191877 + vertex 465.669 38.5405 0.200552 + endloop + endfacet + facet normal 0.00987607 -0.0431591 -0.999019 + outer loop + vertex 424.054 25.4222 0.354468 + vertex 423.065 29.2234 0.18047 + vertex 445.751 30.0848 0.367524 + endloop + endfacet + facet normal 0.00502547 -0.02359 -0.999709 + outer loop + vertex 423.065 29.2234 0.18047 + vertex 400.281 28.4951 0.0831192 + vertex 421.742 32.955 0.0857676 + endloop + endfacet + facet normal 0.00293186 -0.013515 -0.999904 + outer loop + vertex 400.281 28.4951 0.0831192 + vertex 398.859 32.1737 0.0292317 + vertex 421.742 32.955 0.0857676 + endloop + endfacet + facet normal 0.00137896 -0.00727039 -0.999973 + outer loop + vertex 398.859 32.1737 0.0292317 + vertex 376.588 31.5937 0.00273644 + vertex 397.259 35.7206 0.00123576 + endloop + endfacet + facet normal 0.0004458 -0.00246391 -0.999997 + outer loop + vertex 397.259 35.7206 0.00123576 + vertex 374.829 34.924 -0.00680035 + vertex 395.369 39.0223 -0.00774147 + endloop + endfacet + facet normal -8.4181e-05 0.000342862 -1 + outer loop + vertex 395.369 39.0223 -0.00774147 + vertex 372.767 37.942 -0.00620917 + vertex 393.168 42.0083 -0.00653233 + endloop + endfacet + facet normal -0.000215721 0.00110235 -0.999999 + outer loop + vertex 393.168 42.0083 -0.00653233 + vertex 370.454 40.6265 -0.00315582 + vertex 390.733 44.6619 -0.00308202 + endloop + endfacet + facet normal -0.000117829 0.000638886 -1 + outer loop + vertex 390.733 44.6619 -0.00308202 + vertex 367.966 43.0063 -0.00145713 + vertex 388.109 47.014 -0.00127001 + endloop + endfacet + facet normal -1.99866e-05 0.000142143 -1 + outer loop + vertex 388.109 47.014 -0.00127001 + vertex 365.345 45.1387 -0.00108162 + vertex 385.344 49.1198 -0.000915432 + endloop + endfacet + facet normal 3.54489e-06 7.97066e-06 -1 + outer loop + vertex 385.344 49.1198 -0.000915432 + vertex 382.464 51.0352 -0.000910373 + vertex 405.966 53.4198 -0.000808055 + endloop + endfacet + facet normal -9.36098e-06 7.35024e-05 -1 + outer loop + vertex 382.464 51.0352 -0.000910373 + vertex 359.836 48.88 -0.000856966 + vertex 379.486 52.7948 -0.00075316 + endloop + endfacet + facet normal -2.23789e-05 0.000130242 -1 + outer loop + vertex 379.486 52.7948 -0.00075316 + vertex 356.985 50.5535 -0.000541534 + vertex 376.469 54.4325 -0.000472357 + endloop + endfacet + facet normal -2.12425e-05 0.000116642 -1 + outer loop + vertex 376.469 54.4325 -0.000472357 + vertex 354.104 52.1333 -0.000265449 + vertex 373.52 55.9938 -0.000227604 + endloop + endfacet + facet normal -1.46703e-05 8.35872e-05 -1 + outer loop + vertex 354.104 52.1333 -0.000265449 + vertex 351.428 53.7034 -9.49564e-05 + vertex 373.52 55.9938 -0.000227604 + endloop + endfacet + facet normal -8.76454e-06 4.64761e-05 -1 + outer loop + vertex 351.428 53.7034 -9.49564e-05 + vertex 329.465 51.6046 9.62153e-15 + vertex 349.99 55.4752 9.62153e-15 + endloop + endfacet + facet normal -1.16644e-05 5.95118e-05 -1 + outer loop + vertex 393.675 60.1968 -0.000189128 + vertex 370.917 57.5747 -7.97152e-05 + vertex 390.807 61.7237 -6.4812e-05 + endloop + endfacet + facet normal -1.8691e-05 0.000101579 -1 + outer loop + vertex 396.654 58.6445 -0.000402496 + vertex 393.675 60.1968 -0.000189128 + vertex 417.392 63.1417 -0.000333293 + endloop + endfacet + facet normal -1.93733e-05 0.000104725 -1 + outer loop + vertex 420.579 61.5415 -0.00056262 + vertex 396.654 58.6445 -0.000402496 + vertex 417.392 63.1417 -0.000333293 + endloop + endfacet + facet normal -1.07299e-05 7.03899e-05 -1 + outer loop + vertex 423.834 59.8339 -0.000717742 + vertex 399.779 57.0316 -0.000656875 + vertex 420.579 61.5415 -0.00056262 + endloop + endfacet + facet normal 1.77072e-06 1.14916e-05 -1 + outer loop + vertex 427.041 57.9808 -0.000733359 + vertex 402.914 55.3032 -0.000806851 + vertex 423.834 59.8339 -0.000717742 + endloop + endfacet + facet normal -1.60748e-05 0.000104525 -1 + outer loop + vertex 430.102 55.9293 -0.000997001 + vertex 427.041 57.9808 -0.000733359 + vertex 450.328 60.4771 -0.000846779 + endloop + endfacet + facet normal -0.000111253 0.00054679 -1 + outer loop + vertex 432.973 53.6152 -0.00258165 + vertex 408.883 51.3387 -0.00114636 + vertex 430.102 55.9293 -0.000997001 + endloop + endfacet + facet normal -0.000218903 0.00108826 -0.999999 + outer loop + vertex 435.62 50.9916 -0.00601632 + vertex 411.625 49.0058 -0.00292492 + vertex 432.973 53.6152 -0.00258165 + endloop + endfacet + facet normal -0.000109953 0.000614864 -1 + outer loop + vertex 438.027 48.047 -0.00809154 + vertex 414.176 46.3743 -0.00649751 + vertex 435.62 50.9916 -0.00601632 + endloop + endfacet + facet normal 0.000523064 -0.00238616 -0.999997 + outer loop + vertex 440.15 44.7935 0.000782135 + vertex 416.489 43.418 -0.00831198 + vertex 438.027 48.047 -0.00809154 + endloop + endfacet + facet normal 0.00170101 -0.00780661 -0.999968 + outer loop + vertex 442.004 41.2956 0.0312441 + vertex 418.517 40.1492 0.000241414 + vertex 440.15 44.7935 0.000782135 + endloop + endfacet + facet normal 0.00331753 -0.0150684 -0.999881 + outer loop + vertex 443.568 37.6378 0.091558 + vertex 420.246 36.6268 0.0294109 + vertex 442.004 41.2956 0.0312441 + endloop + endfacet + facet normal 0.00594323 -0.0248047 -0.999675 + outer loop + vertex 444.862 33.9048 0.191877 + vertex 443.568 37.6378 0.091558 + vertex 465.669 38.5405 0.200552 + endloop + endfacet + facet normal 0.00990697 -0.0436714 -0.998997 + outer loop + vertex 466.579 34.7669 0.374539 + vertex 465.669 38.5405 0.200552 + vertex 484.089 39.0723 0.359975 + endloop + endfacet + facet normal 0.00611617 -0.0258943 -0.999646 + outer loop + vertex 483.123 42.6789 0.199759 + vertex 464.46 42.2531 0.0966054 + vertex 482.078 46.3977 0.0970375 + endloop + endfacet + facet normal 0.00374383 -0.0161889 -0.999862 + outer loop + vertex 482.078 46.3977 0.0970375 + vertex 462.825 45.9039 0.032942 + vertex 480.463 50.1221 0.0306868 + endloop + endfacet + facet normal 0.00177825 -0.0075572 -0.99997 + outer loop + vertex 480.463 50.1221 0.0306868 + vertex 460.869 49.405 0.00126101 + vertex 478.461 53.6618 0.000375578 + endloop + endfacet + facet normal 0.000459697 -0.00167261 -0.999998 + outer loop + vertex 478.461 53.6618 0.000375578 + vertex 458.662 52.6636 -0.0070566 + vertex 476.117 56.9316 -0.00617119 + endloop + endfacet + facet normal -9.86915e-05 0.00065696 -1 + outer loop + vertex 476.117 56.9316 -0.00617119 + vertex 456.143 55.6129 -0.0050663 + vertex 473.437 59.8799 -0.00396979 + endloop + endfacet + facet normal -0.00015891 0.00078559 -1 + outer loop + vertex 473.437 59.8799 -0.00396979 + vertex 453.345 58.2157 -0.00208435 + vertex 470.221 62.3455 -0.00152189 + endloop + endfacet + facet normal -5.13266e-05 0.000309563 -1 + outer loop + vertex 470.221 62.3455 -0.00152189 + vertex 467.221 64.4801 -0.000707079 + vertex 480.521 65.3709 -0.00111395 + endloop + endfacet + facet normal -5.36656e-06 3.6256e-05 -1 + outer loop + vertex 467.221 64.4801 -0.000707079 + vertex 447.184 62.4893 -0.000671729 + vertex 464.201 66.5016 -0.000617582 + endloop + endfacet + facet normal -2.85149e-06 3.41758e-05 -1 + outer loop + vertex 464.201 66.5016 -0.000617582 + vertex 443.888 64.3347 -0.000633714 + vertex 460.653 68.3737 -0.000543482 + endloop + endfacet + facet normal -1.23749e-05 7.48423e-05 -1 + outer loop + vertex 460.653 68.3737 -0.000543482 + vertex 440.528 66.0342 -0.000469531 + vertex 456.918 69.9872 -0.000376505 + endloop + endfacet + facet normal -1.47794e-05 8.07791e-05 -1 + outer loop + vertex 456.918 69.9872 -0.000376505 + vertex 453.524 71.4601 -0.000207362 + vertex 466.682 72.7664 -0.000296308 + endloop + endfacet + facet normal -9.21753e-06 4.13639e-05 -1 + outer loop + vertex 465.252 74.4377 -0.000168208 + vertex 449.973 72.8947 -9.11986e-05 + vertex 461.159 75.9693 -6.71287e-05 + endloop + endfacet + facet normal -8.62851e-06 4.29379e-05 -1 + outer loop + vertex 465.252 74.4377 -0.000168208 + vertex 461.159 75.9693 -6.71287e-05 + vertex 472.612 77.0867 -0.000117973 + endloop + endfacet + facet normal -5.72317e-06 2.86506e-05 -1 + outer loop + vertex 449.973 72.8947 -9.11986e-05 + vertex 445.785 74.208 -2.96051e-05 + vertex 461.159 75.9693 -6.71287e-05 + endloop + endfacet + facet normal -1.31138e-05 7.04668e-05 -1 + outer loop + vertex 437.211 67.5974 -0.000265625 + vertex 433.772 69.0507 -0.000118125 + vertex 453.524 71.4601 -0.000207362 + endloop + endfacet + facet normal -9.21707e-06 4.85331e-05 -1 + outer loop + vertex 414.289 64.6665 -0.000151331 + vertex 410.905 66.0926 -5.0929e-05 + vertex 433.772 69.0507 -0.000118125 + endloop + endfacet + facet normal -5.25119e-06 2.40981e-05 -1 + outer loop + vertex 410.905 66.0926 -5.0929e-05 + vertex 387.362 63.0757 9.62153e-15 + vertex 407.043 67.3643 9.62153e-15 + endloop + endfacet + facet normal -6.04421e-06 2.76269e-05 -1 + outer loop + vertex 449.973 72.8947 -9.11986e-05 + vertex 429.811 70.373 -3.90026e-05 + vertex 445.785 74.208 -2.96051e-05 + endloop + endfacet + facet normal -4.85621e-06 2.10834e-05 -1 + outer loop + vertex 461.159 75.9693 -6.71287e-05 + vertex 445.785 74.208 -2.96051e-05 + vertex 457.044 77.1858 -2.14988e-05 + endloop + endfacet + facet normal -4.59064e-06 2.19818e-05 -1 + outer loop + vertex 461.159 75.9693 -6.71287e-05 + vertex 457.044 77.1858 -2.14988e-05 + vertex 467.143 78.5781 -3.72542e-05 + endloop + endfacet + facet normal -3.40461e-06 1.50555e-05 -1 + outer loop + vertex 470.833 80.7297 -1.5309e-05 + vertex 477.448 82.2531 -1.48955e-05 + vertex 474.599 79.6605 -4.42277e-05 + endloop + endfacet + facet normal -7.15871e-06 2.78726e-05 -1 + outer loop + vertex 467.143 78.5781 -3.72542e-05 + vertex 472.612 77.0867 -0.000117973 + vertex 461.159 75.9693 -6.71287e-05 + endloop + endfacet + facet normal -5.94958e-06 2.63016e-05 -1 + outer loop + vertex 474.599 79.6605 -4.42277e-05 + vertex 480.627 81.0487 -4.35821e-05 + vertex 478.087 78.7559 -8.87765e-05 + endloop + endfacet + facet normal -1.29852e-05 5.01297e-05 -1 + outer loop + vertex 478.087 78.7559 -8.87765e-05 + vertex 483.349 79.696 -0.000109978 + vertex 480.104 77.1986 -0.000193036 + endloop + endfacet + facet normal -1.29363e-05 5.49069e-05 -1 + outer loop + vertex 472.612 77.0867 -0.000117973 + vertex 475.942 74.6234 -0.000296295 + vertex 465.252 74.4377 -0.000168208 + endloop + endfacet + facet normal -1.81481e-05 6.28717e-05 -1 + outer loop + vertex 480.104 77.1986 -0.000193036 + vertex 486.549 78.3062 -0.000240353 + vertex 483.926 75.5988 -0.000362971 + endloop + endfacet + facet normal -1.16263e-05 6.64791e-05 -1 + outer loop + vertex 475.942 74.6234 -0.000296295 + vertex 482.637 72.7985 -0.000495455 + vertex 471.73 71.6834 -0.000442774 + endloop + endfacet + facet normal -2.20712e-05 5.7149e-05 -1 + outer loop + vertex 483.926 75.5988 -0.000362971 + vertex 490.203 77.0038 -0.000421218 + vertex 487.912 74.5677 -0.000509883 + endloop + endfacet + facet normal -1.70734e-05 2.51234e-05 -1 + outer loop + vertex 487.912 74.5677 -0.000509883 + vertex 493.581 75.61 -0.000580487 + vertex 490.188 72.8465 -0.000591988 + endloop + endfacet + facet normal -1.26657e-05 5.16702e-05 -1 + outer loop + vertex 482.637 72.7985 -0.000495455 + vertex 486.467 70.2601 -0.000675126 + vertex 476.036 69.8033 -0.000566609 + endloop + endfacet + facet normal -1.44826e-05 4.16716e-05 -1 + outer loop + vertex 490.188 72.8465 -0.000591988 + vertex 496.821 73.9729 -0.000641101 + vertex 493.666 70.8552 -0.000725335 + endloop + endfacet + facet normal -6.63024e-05 0.000187188 -1 + outer loop + vertex 486.467 70.2601 -0.000675126 + vertex 490.703 67.312 -0.00150783 + vertex 479.37 67.5661 -0.000708875 + endloop + endfacet + facet normal -3.74617e-05 0.00016966 -1 + outer loop + vertex 493.666 70.8552 -0.000725335 + vertex 500.162 72.2389 -0.000733923 + vertex 497.289 69.3526 -0.00111599 + endloop + endfacet + facet normal -0.000165711 0.000586264 -1 + outer loop + vertex 497.289 69.3526 -0.00111599 + vertex 503.232 70.2824 -0.00155571 + vertex 499.269 67.0107 -0.00281699 + endloop + endfacet + facet normal -0.000168242 0.00059202 -1 + outer loop + vertex 490.703 67.312 -0.00150783 + vertex 495.153 63.9526 -0.00424526 + vertex 485.028 63.5343 -0.00278942 + endloop + endfacet + facet normal -0.000260753 0.00064029 -1 + outer loop + vertex 499.269 67.0107 -0.00281699 + vertex 506.167 67.8961 -0.0040488 + vertex 502.318 64.1366 -0.00545239 + endloop + endfacet + facet normal 4.92453e-05 0.000241003 -1 + outer loop + vertex 495.153 63.9526 -0.00424526 + vertex 498.195 60.7548 -0.00486613 + vertex 488.334 60.6405 -0.0053793 + endloop + endfacet + facet normal -1.37543e-05 -0.000950367 -1 + outer loop + vertex 502.318 64.1366 -0.00545239 + vertex 509.059 65.1298 -0.00648902 + vertex 504.979 60.968 -0.0024776 + endloop + endfacet + facet normal 0.00103884 -0.00303715 -0.999995 + outer loop + vertex 498.195 60.7548 -0.00486613 + vertex 500.571 57.3225 0.00802684 + vertex 490.916 57.3862 -0.00219656 + endloop + endfacet + facet normal 0.00117646 -0.00584874 -0.999982 + outer loop + vertex 504.979 60.968 -0.0024776 + vertex 511.543 61.9921 -0.000745221 + vertex 507.164 57.4791 0.020499 + endloop + endfacet + facet normal 0.00310386 -0.010509 -0.99994 + outer loop + vertex 500.571 57.3225 0.00802684 + vertex 502.518 53.5924 0.0532711 + vertex 493.1 53.8538 0.0212914 + endloop + endfacet + facet normal 0.00351286 -0.0144764 -0.999889 + outer loop + vertex 507.164 57.4791 0.020499 + vertex 513.617 58.5193 0.0281119 + vertex 508.919 53.6845 0.0816009 + endloop + endfacet + facet normal 0.00632723 -0.0221442 -0.999735 + outer loop + vertex 502.518 53.5924 0.0532711 + vertex 504.043 49.4915 0.153757 + vertex 494.867 50.0538 0.0832301 + endloop + endfacet + facet normal 0.00637107 -0.0257475 -0.999648 + outer loop + vertex 508.919 53.6845 0.0816009 + vertex 515.32 54.8094 0.0934255 + vertex 510.4 49.7361 0.192737 + endloop + endfacet + facet normal 0.0118143 -0.0393397 -0.999156 + outer loop + vertex 504.043 49.4915 0.153757 + vertex 505.257 44.4048 0.368389 + vertex 495.989 46.0398 0.194434 + endloop + endfacet + facet normal 0.00903347 -0.0378478 -0.999243 + outer loop + vertex 510.4 49.7361 0.192737 + vertex 516.774 51.137 0.197301 + vertex 512.258 46.7952 0.320928 + endloop + endfacet + facet normal 0.0149763 -0.0647006 -0.997792 + outer loop + vertex 512.258 46.7952 0.320928 + vertex 517.852 47.465 0.361468 + vertex 512.185 43.0549 0.562369 + endloop + endfacet + facet normal 0.0248885 -0.111182 -0.993488 + outer loop + vertex 512.185 43.0549 0.562369 + vertex 518.747 43.571 0.669013 + vertex 512.75 38.6877 1.06526 + endloop + endfacet + facet normal 0.0243051 -0.0755454 -0.996846 + outer loop + vertex 505.257 44.4048 0.368389 + vertex 506.446 39.1921 0.792429 + vertex 497.455 39.3847 0.558603 + endloop + endfacet + facet normal 0.0165813 -0.075474 -0.99701 + outer loop + vertex 484.784 35.2426 0.661441 + vertex 484.089 39.0723 0.359975 + vertex 497.455 39.3847 0.558603 + endloop + endfacet + facet normal 0.0312716 -0.133972 -0.990492 + outer loop + vertex 484.813 30.935 1.24497 + vertex 466.781 30.7516 0.700488 + vertex 484.784 35.2426 0.661441 + endloop + endfacet +endsolid diff --git a/noether_examples/meshes/outputs/output_8.stl b/noether_examples/meshes/outputs/output_8.stl new file mode 100644 index 00000000..3a6fef3b --- /dev/null +++ b/noether_examples/meshes/outputs/output_8.stl @@ -0,0 +1,4678 @@ +solid ascii + facet normal 0.0512103 -0.212644 0.975787 + outer loop + vertex 604.456 80.0321 22.3738 + vertex 606.179 79.6722 22.2049 + vertex 604.599 81.0834 22.5954 + endloop + endfacet + facet normal 0.266354 -0.233247 0.935228 + outer loop + vertex 604.456 80.0321 22.3738 + vertex 604.599 81.0834 22.5954 + vertex 604.173 81.3065 22.7723 + endloop + endfacet + facet normal 0.381166 0.352115 -0.854826 + outer loop + vertex 604.173 81.3065 22.7723 + vertex 605.253 78.4326 22.0703 + vertex 604.456 80.0321 22.3738 + endloop + endfacet + facet normal 0.053215 -0.210498 0.976145 + outer loop + vertex 604.599 81.0834 22.5954 + vertex 606.179 79.6722 22.2049 + vertex 606.508 81.839 22.6542 + endloop + endfacet + facet normal 0.0662034 -0.212226 0.974975 + outer loop + vertex 606.179 79.6722 22.2049 + vertex 610.189 80.453 22.1026 + vertex 606.508 81.839 22.6542 + endloop + endfacet + facet normal 0.0692282 -0.204746 0.976364 + outer loop + vertex 606.508 81.839 22.6542 + vertex 610.189 80.453 22.1026 + vertex 610.036 83.0725 22.6628 + endloop + endfacet + facet normal 0.0845037 -0.20365 0.97539 + outer loop + vertex 610.189 80.453 22.1026 + vertex 614.165 82.1882 22.1204 + vertex 610.036 83.0725 22.6628 + endloop + endfacet + facet normal 0.0824911 -0.212053 0.97377 + outer loop + vertex 610.036 83.0725 22.6628 + vertex 614.165 82.1882 22.1204 + vertex 614.81 84.5535 22.5808 + endloop + endfacet + facet normal 0.0726118 -0.209613 0.975085 + outer loop + vertex 614.165 82.1882 22.1204 + vertex 620.044 83.5325 21.9716 + vertex 614.81 84.5535 22.5808 + endloop + endfacet + facet normal 0.0774765 -0.187172 0.979267 + outer loop + vertex 614.81 84.5535 22.5808 + vertex 620.044 83.5325 21.9716 + vertex 620.39 86.2182 22.4576 + endloop + endfacet + facet normal 0.0743426 -0.186824 0.979576 + outer loop + vertex 620.044 83.5325 21.9716 + vertex 625.383 85.587 21.9583 + vertex 620.39 86.2182 22.4576 + endloop + endfacet + facet normal 0.074003 -0.189174 0.979151 + outer loop + vertex 620.39 86.2182 22.4576 + vertex 625.383 85.587 21.9583 + vertex 626.187 87.988 22.3614 + endloop + endfacet + facet normal 0.0602278 -0.184858 0.980918 + outer loop + vertex 625.383 85.587 21.9583 + vertex 631.574 87.0645 21.8566 + vertex 626.187 87.988 22.3614 + endloop + endfacet + facet normal 0.0641091 -0.164096 0.984359 + outer loop + vertex 626.187 87.988 22.3614 + vertex 631.574 87.0645 21.8566 + vertex 631.882 89.7648 22.2866 + endloop + endfacet + facet normal 0.0606166 -0.163743 0.984639 + outer loop + vertex 631.574 87.0645 21.8566 + vertex 636.897 89.1333 21.8729 + vertex 631.882 89.7648 22.2866 + endloop + endfacet + facet normal 0.060995 -0.161017 0.985065 + outer loop + vertex 631.882 89.7648 22.2866 + vertex 636.897 89.1333 21.8729 + vertex 637.609 91.5553 22.2247 + endloop + endfacet + facet normal 0.0517516 -0.158436 0.986012 + outer loop + vertex 636.897 89.1333 21.8729 + vertex 643.435 90.6402 21.7719 + vertex 637.609 91.5553 22.2247 + endloop + endfacet + facet normal 0.0549102 -0.139649 0.988677 + outer loop + vertex 637.609 91.5553 22.2247 + vertex 643.435 90.6402 21.7719 + vertex 643.814 93.5999 22.1689 + endloop + endfacet + facet normal 0.0501592 -0.139083 0.98901 + outer loop + vertex 643.435 90.6402 21.7719 + vertex 651.587 93.5142 21.7626 + vertex 643.814 93.5999 22.1689 + endloop + endfacet + facet normal 0.0503098 -0.130763 0.990136 + outer loop + vertex 643.814 93.5999 22.1689 + vertex 651.587 93.5142 21.7626 + vertex 649.941 96.2703 22.2103 + endloop + endfacet + facet normal 0.0490307 -0.131521 0.9901 + outer loop + vertex 651.587 93.5142 21.7626 + vertex 660.496 98.1159 21.9327 + vertex 649.941 96.2703 22.2103 + endloop + endfacet + facet normal 0.055507 -0.169484 0.983969 + outer loop + vertex 653.353 99.0957 22.5044 + vertex 649.941 96.2703 22.2103 + vertex 660.496 98.1159 21.9327 + endloop + endfacet + facet normal 0.0592709 -0.144254 0.987764 + outer loop + vertex 658.544 100.944 22.4629 + vertex 653.353 99.0957 22.5044 + vertex 660.496 98.1159 21.9327 + endloop + endfacet + facet normal 0.0606397 -0.143319 0.987817 + outer loop + vertex 658.544 100.944 22.4629 + vertex 660.496 98.1159 21.9327 + vertex 664.481 102.5 22.3242 + endloop + endfacet + facet normal 0.050971 -0.134689 0.989576 + outer loop + vertex 660.496 98.1159 21.9327 + vertex 672.899 102.441 21.8826 + vertex 664.481 102.5 22.3242 + endloop + endfacet + facet normal 0.0510652 -0.127919 0.990469 + outer loop + vertex 669.788 104.816 22.3497 + vertex 664.481 102.5 22.3242 + vertex 672.899 102.441 21.8826 + endloop + endfacet + facet normal 0.0520157 -0.126695 0.990577 + outer loop + vertex 669.788 104.816 22.3497 + vertex 672.899 102.441 21.8826 + vertex 675.668 106.486 22.2545 + endloop + endfacet + facet normal 0.0477147 -0.123804 0.991159 + outer loop + vertex 672.899 102.441 21.8826 + vertex 684.21 106.444 21.838 + vertex 675.668 106.486 22.2545 + endloop + endfacet + facet normal 0.0477597 -0.119665 0.991665 + outer loop + vertex 680.827 108.77 22.2817 + vertex 675.668 106.486 22.2545 + vertex 684.21 106.444 21.838 + endloop + endfacet + facet normal 0.0465846 -0.121346 0.991517 + outer loop + vertex 680.827 108.77 22.2817 + vertex 684.21 106.444 21.838 + vertex 687.289 110.569 22.1981 + endloop + endfacet + facet normal 0.0451594 -0.120298 0.99171 + outer loop + vertex 684.21 106.444 21.838 + vertex 695.205 109.99 21.7675 + vertex 687.289 110.569 22.1981 + endloop + endfacet + facet normal 0.0445098 -0.128448 0.990717 + outer loop + vertex 695.31 113.825 22.26 + vertex 687.289 110.569 22.1981 + vertex 695.205 109.99 21.7675 + endloop + endfacet + facet normal 0.0480976 -0.128523 0.990539 + outer loop + vertex 695.205 109.99 21.7675 + vertex 705.155 114.15 21.8242 + vertex 695.31 113.825 22.26 + endloop + endfacet + facet normal 0.0486469 -0.149056 0.987631 + outer loop + vertex 695.31 113.825 22.26 + vertex 705.155 114.15 21.8242 + vertex 703.948 118.756 22.5787 + endloop + endfacet + facet normal 0.0587114 -0.146394 0.987483 + outer loop + vertex 705.155 114.15 21.8242 + vertex 715.675 118.799 21.8879 + vertex 703.948 118.756 22.5787 + endloop + endfacet + facet normal 0.0586938 -0.149834 0.986967 + outer loop + vertex 703.948 118.756 22.5787 + vertex 715.675 118.799 21.8879 + vertex 715.91 123.662 22.6122 + endloop + endfacet + facet normal 0.064964 -0.150074 0.986538 + outer loop + vertex 715.675 118.799 21.8879 + vertex 726.576 123.552 21.893 + vertex 715.91 123.662 22.6122 + endloop + endfacet + facet normal 0.0649186 -0.152278 0.986203 + outer loop + vertex 715.91 123.662 22.6122 + vertex 726.576 123.552 21.893 + vertex 726.694 128.372 22.6295 + endloop + endfacet + facet normal 0.0714972 -0.152367 0.985734 + outer loop + vertex 726.576 123.552 21.893 + vertex 737.219 128.387 21.8684 + vertex 726.694 128.372 22.6295 + endloop + endfacet + facet normal 0.0715086 -0.151188 0.985915 + outer loop + vertex 726.694 128.372 22.6295 + vertex 737.219 128.387 21.8684 + vertex 737.252 133.211 22.6057 + endloop + endfacet + facet normal 0.0778195 -0.151158 0.985442 + outer loop + vertex 737.219 128.387 21.8684 + vertex 747.681 133.375 21.8073 + vertex 737.252 133.211 22.6057 + endloop + endfacet + facet normal 0.0778004 -0.146549 0.986139 + outer loop + vertex 737.252 133.211 22.6057 + vertex 747.681 133.375 21.8073 + vertex 747.694 138.2 22.5234 + endloop + endfacet + facet normal 0.0825282 -0.146506 0.985761 + outer loop + vertex 747.681 133.375 21.8073 + vertex 757.963 138.532 21.713 + vertex 747.694 138.2 22.5234 + endloop + endfacet + facet normal 0.0824423 -0.142335 0.986379 + outer loop + vertex 747.694 138.2 22.5234 + vertex 757.963 138.532 21.713 + vertex 757.839 143.313 22.4133 + endloop + endfacet + facet normal 0.0875961 -0.142142 0.985963 + outer loop + vertex 757.963 138.532 21.713 + vertex 768.063 143.889 21.5879 + vertex 757.839 143.313 22.4133 + endloop + endfacet + facet normal 0.0875911 -0.14203 0.985979 + outer loop + vertex 757.839 143.313 22.4133 + vertex 768.063 143.889 21.5879 + vertex 767.864 148.707 22.2998 + endloop + endfacet + facet normal 0.0961848 -0.141565 0.985245 + outer loop + vertex 768.063 143.889 21.5879 + vertex 778.082 149.554 21.4238 + vertex 767.864 148.707 22.2998 + endloop + endfacet + facet normal 0.0960548 -0.139709 0.985523 + outer loop + vertex 767.864 148.707 22.2998 + vertex 778.082 149.554 21.4238 + vertex 777.958 154.509 22.1384 + endloop + endfacet + facet normal 0.106961 -0.139282 0.984459 + outer loop + vertex 778.082 149.554 21.4238 + vertex 788.058 155.625 21.199 + vertex 777.958 154.509 22.1384 + endloop + endfacet + facet normal 0.106088 -0.130264 0.985787 + outer loop + vertex 777.958 154.509 22.1384 + vertex 788.058 155.625 21.199 + vertex 788.237 160.799 21.8634 + endloop + endfacet + facet normal 0.116724 -0.130475 0.984557 + outer loop + vertex 788.058 155.625 21.199 + vertex 797.722 162.114 20.9132 + vertex 788.237 160.799 21.8634 + endloop + endfacet + facet normal 0.112636 -0.097918 0.9888 + outer loop + vertex 788.237 160.799 21.8634 + vertex 797.722 162.114 20.9132 + vertex 794.976 163.733 21.3863 + endloop + endfacet + facet normal 0.108118 -0.1055 0.988524 + outer loop + vertex 794.976 163.733 21.3863 + vertex 797.722 162.114 20.9132 + vertex 799.591 166.523 21.1793 + endloop + endfacet + facet normal 0.107997 -0.10545 0.988543 + outer loop + vertex 797.722 162.114 20.9132 + vertex 807.337 168.553 20.5496 + vertex 799.591 166.523 21.1793 + endloop + endfacet + facet normal 0.109276 -0.110545 0.987845 + outer loop + vertex 803.82 170.022 21.1031 + vertex 799.591 166.523 21.1793 + vertex 807.337 168.553 20.5496 + endloop + endfacet + facet normal 0.111281 -0.105856 0.988135 + outer loop + vertex 803.82 170.022 21.1031 + vertex 807.337 168.553 20.5496 + vertex 808.837 173.138 20.8718 + endloop + endfacet + facet normal 0.113321 -0.106503 0.987834 + outer loop + vertex 807.337 168.553 20.5496 + vertex 816.469 175.184 20.2169 + vertex 808.837 173.138 20.8718 + endloop + endfacet + facet normal 0.113784 -0.108308 0.987584 + outer loop + vertex 812.886 176.621 20.7874 + vertex 808.837 173.138 20.8718 + vertex 816.469 175.184 20.2169 + endloop + endfacet + facet normal 0.116352 -0.102053 0.987951 + outer loop + vertex 812.886 176.621 20.7874 + vertex 816.469 175.184 20.2169 + vertex 817.737 179.755 20.5398 + endloop + endfacet + facet normal 0.115554 -0.10184 0.988067 + outer loop + vertex 816.469 175.184 20.2169 + vertex 825.244 181.9 19.8828 + vertex 817.737 179.755 20.5398 + endloop + endfacet + facet normal 0.115209 -0.100582 0.988236 + outer loop + vertex 821.619 183.289 20.4468 + vertex 817.737 179.755 20.5398 + vertex 825.244 181.9 19.8828 + endloop + endfacet + facet normal 0.116911 -0.0962382 0.988469 + outer loop + vertex 821.619 183.289 20.4468 + vertex 825.244 181.9 19.8828 + vertex 826.289 186.465 20.2038 + endloop + endfacet + facet normal 0.113296 -0.0954461 0.988966 + outer loop + vertex 825.244 181.9 19.8828 + vertex 833.661 188.73 19.5778 + vertex 826.289 186.465 20.2038 + endloop + endfacet + facet normal 0.112824 -0.0938552 0.989172 + outer loop + vertex 829.943 189.99 20.1213 + vertex 826.289 186.465 20.2038 + vertex 833.661 188.73 19.5778 + endloop + endfacet + facet normal 0.113593 -0.0916366 0.989292 + outer loop + vertex 829.943 189.99 20.1213 + vertex 833.661 188.73 19.5778 + vertex 834.414 193.194 19.9049 + endloop + endfacet + facet normal 0.110045 -0.0910714 0.989746 + outer loop + vertex 833.661 188.73 19.5778 + vertex 841.652 195.733 19.3337 + vertex 834.414 193.194 19.9049 + endloop + endfacet + facet normal 0.111652 -0.0957969 0.989119 + outer loop + vertex 837.872 196.736 19.8575 + vertex 834.414 193.194 19.9049 + vertex 841.652 195.733 19.3337 + endloop + endfacet + facet normal 0.112672 -0.0920794 0.989357 + outer loop + vertex 837.872 196.736 19.8575 + vertex 841.652 195.733 19.3337 + vertex 842.228 200.104 19.6749 + endloop + endfacet + facet normal 0.110806 -0.0918517 0.989588 + outer loop + vertex 841.652 195.733 19.3337 + vertex 848.973 202.891 19.1784 + vertex 842.228 200.104 19.6749 + endloop + endfacet + facet normal 0.11419 -0.100255 0.988387 + outer loop + vertex 845.609 203.807 19.6599 + vertex 842.228 200.104 19.6749 + vertex 848.973 202.891 19.1784 + endloop + endfacet + facet normal 0.11503 -0.0972797 0.988587 + outer loop + vertex 845.609 203.807 19.6599 + vertex 848.973 202.891 19.1784 + vertex 849.68 207.275 19.5275 + endloop + endfacet + facet normal 0.115346 -0.0973275 0.988546 + outer loop + vertex 848.973 202.891 19.1784 + vertex 854.637 209.278 19.1462 + vertex 849.68 207.275 19.5275 + endloop + endfacet + facet normal 0.12059 -0.110696 0.986511 + outer loop + vertex 852.898 211.004 19.5525 + vertex 849.68 207.275 19.5275 + vertex 854.637 209.278 19.1462 + endloop + endfacet + facet normal 0.119618 -0.111677 0.986519 + outer loop + vertex 852.898 211.004 19.5525 + vertex 854.637 209.278 19.1462 + vertex 856.478 213.937 19.4504 + endloop + endfacet + facet normal 0.103914 -0.105631 0.988961 + outer loop + vertex 860.538 213.636 18.9917 + vertex 856.478 213.937 19.4504 + vertex 854.637 209.278 19.1462 + endloop + endfacet + facet normal 0.104568 -0.0979064 0.989687 + outer loop + vertex 860.538 213.636 18.9917 + vertex 859.334 217.3 19.4814 + vertex 856.478 213.937 19.4504 + endloop + endfacet + facet normal 0.0902505 -0.0744641 0.993131 + outer loop + vertex 807.337 168.553 20.5496 + vertex 817.032 170.073 19.7825 + vertex 816.469 175.184 20.2169 + endloop + endfacet + facet normal 0.0904238 -0.0744438 0.993117 + outer loop + vertex 817.032 170.073 19.7825 + vertex 825.991 176.813 19.472 + vertex 816.469 175.184 20.2169 + endloop + endfacet + facet normal 0.0892255 -0.0671515 0.993745 + outer loop + vertex 816.469 175.184 20.2169 + vertex 825.991 176.813 19.472 + vertex 825.244 181.9 19.8828 + endloop + endfacet + facet normal 0.0869367 -0.0675019 0.993924 + outer loop + vertex 825.991 176.813 19.472 + vertex 834.649 183.722 19.184 + vertex 825.244 181.9 19.8828 + endloop + endfacet + facet normal 0.0857698 -0.0612869 0.994428 + outer loop + vertex 825.244 181.9 19.8828 + vertex 834.649 183.722 19.184 + vertex 833.661 188.73 19.5778 + endloop + endfacet + facet normal 0.0827536 -0.0618986 0.994646 + outer loop + vertex 834.649 183.722 19.184 + vertex 842.9 190.858 18.9416 + vertex 833.661 188.73 19.5778 + endloop + endfacet + facet normal 0.0821034 -0.0590074 0.994875 + outer loop + vertex 833.661 188.73 19.5778 + vertex 842.9 190.858 18.9416 + vertex 841.652 195.733 19.3337 + endloop + endfacet + facet normal 0.0794899 -0.0596901 0.995047 + outer loop + vertex 842.9 190.858 18.9416 + vertex 850.38 198.236 18.7866 + vertex 841.652 195.733 19.3337 + endloop + endfacet + facet normal 0.0794961 -0.059712 0.995045 + outer loop + vertex 841.652 195.733 19.3337 + vertex 850.38 198.236 18.7866 + vertex 848.973 202.891 19.1784 + endloop + endfacet + facet normal 0.0772446 -0.060404 0.995181 + outer loop + vertex 850.38 198.236 18.7866 + vertex 856.449 205.716 18.7695 + vertex 848.973 202.891 19.1784 + endloop + endfacet + facet normal 0.0789709 -0.0650353 0.994753 + outer loop + vertex 848.973 202.891 19.1784 + vertex 856.449 205.716 18.7695 + vertex 854.637 209.278 19.1462 + endloop + endfacet + facet normal 0.0754292 -0.0668535 0.994908 + outer loop + vertex 854.637 209.278 19.1462 + vertex 856.449 205.716 18.7695 + vertex 860.538 213.636 18.9917 + endloop + endfacet + facet normal 0.0613372 -0.059619 0.996335 + outer loop + vertex 863.378 208.737 18.5237 + vertex 860.538 213.636 18.9917 + vertex 856.449 205.716 18.7695 + endloop + endfacet + facet normal 0.057613 -0.0510208 0.997034 + outer loop + vertex 856.449 205.716 18.7695 + vertex 858.596 201.109 18.4097 + vertex 863.378 208.737 18.5237 + endloop + endfacet + facet normal 0.0603195 -0.0527137 0.996786 + outer loop + vertex 866.924 204.024 18.0599 + vertex 863.378 208.737 18.5237 + vertex 858.596 201.109 18.4097 + endloop + endfacet + facet normal 0.062457 -0.0588774 0.996309 + outer loop + vertex 858.596 201.109 18.4097 + vertex 860.76 196.256 17.9873 + vertex 866.924 204.024 18.0599 + endloop + endfacet + facet normal 0.0868047 -0.0781694 0.993154 + outer loop + vertex 869.356 198.16 17.3858 + vertex 866.924 204.024 18.0599 + vertex 860.76 196.256 17.9873 + endloop + endfacet + facet normal 0.0887967 -0.0874645 0.992202 + outer loop + vertex 860.76 196.256 17.9873 + vertex 862.578 191.376 17.3943 + vertex 869.356 198.16 17.3858 + endloop + endfacet + facet normal 0.0958847 -0.084772 0.991776 + outer loop + vertex 853.443 188.768 18.0546 + vertex 862.578 191.376 17.3943 + vertex 860.76 196.256 17.9873 + endloop + endfacet + facet normal 0.0720908 -0.0614907 0.995501 + outer loop + vertex 853.443 188.768 18.0546 + vertex 860.76 196.256 17.9873 + vertex 851.96 193.518 18.4554 + endloop + endfacet + facet normal 0.0769975 -0.0599352 0.995228 + outer loop + vertex 844.114 186.101 18.6158 + vertex 853.443 188.768 18.0546 + vertex 851.96 193.518 18.4554 + endloop + endfacet + facet normal 0.0683766 -0.0507913 0.996366 + outer loop + vertex 844.114 186.101 18.6158 + vertex 851.96 193.518 18.4554 + vertex 842.9 190.858 18.9416 + endloop + endfacet + facet normal 0.0790912 -0.0673951 0.994587 + outer loop + vertex 845.165 181.334 18.2091 + vertex 853.443 188.768 18.0546 + vertex 844.114 186.101 18.6158 + endloop + endfacet + facet normal 0.0827552 -0.0665663 0.994344 + outer loop + vertex 835.616 178.936 18.8433 + vertex 845.165 181.334 18.2091 + vertex 844.114 186.101 18.6158 + endloop + endfacet + facet normal 0.0738337 -0.0559432 0.9957 + outer loop + vertex 835.616 178.936 18.8433 + vertex 844.114 186.101 18.6158 + vertex 834.649 183.722 19.184 + endloop + endfacet + facet normal 0.0848688 -0.0751914 0.993551 + outer loop + vertex 836.501 174.178 18.4077 + vertex 845.165 181.334 18.2091 + vertex 835.616 178.936 18.8433 + endloop + endfacet + facet normal 0.087896 -0.0746084 0.993332 + outer loop + vertex 826.816 172.015 19.1022 + vertex 836.501 174.178 18.4077 + vertex 835.616 178.936 18.8433 + endloop + endfacet + facet normal 0.0789042 -0.0631157 0.994882 + outer loop + vertex 826.816 172.015 19.1022 + vertex 835.616 178.936 18.8433 + vertex 825.991 176.813 19.472 + endloop + endfacet + facet normal 0.090162 -0.0850923 0.992285 + outer loop + vertex 827.62 167.265 18.6218 + vertex 836.501 174.178 18.4077 + vertex 826.816 172.015 19.1022 + endloop + endfacet + facet normal 0.0930117 -0.0845881 0.992065 + outer loop + vertex 817.754 165.265 19.3763 + vertex 827.62 167.265 18.6218 + vertex 826.816 172.015 19.1022 + endloop + endfacet + facet normal 0.0832999 -0.071473 0.993958 + outer loop + vertex 817.754 165.265 19.3763 + vertex 826.816 172.015 19.1022 + vertex 817.032 170.073 19.7825 + endloop + endfacet + facet normal 0.0846321 -0.0712647 0.993861 + outer loop + vertex 807.749 163.46 20.0988 + vertex 817.754 165.265 19.3763 + vertex 817.032 170.073 19.7825 + endloop + endfacet + facet normal 0.08634 -0.081091 0.99296 + outer loop + vertex 808.409 158.686 19.6516 + vertex 817.754 165.265 19.3763 + vertex 807.749 163.46 20.0988 + endloop + endfacet + facet normal 0.0860518 -0.0811329 0.992982 + outer loop + vertex 798.206 156.995 20.3976 + vertex 808.409 158.686 19.6516 + vertex 807.749 163.46 20.0988 + endloop + endfacet + facet normal 0.0927509 -0.0910885 0.991514 + outer loop + vertex 798.206 156.995 20.3976 + vertex 807.749 163.46 20.0988 + vertex 797.722 162.114 20.9132 + endloop + endfacet + facet normal 0.0877461 -0.0918291 0.991901 + outer loop + vertex 798.847 152.336 19.9095 + vertex 808.409 158.686 19.6516 + vertex 798.206 156.995 20.3976 + endloop + endfacet + facet normal 0.0848309 -0.0922531 0.992115 + outer loop + vertex 788.479 150.78 20.6514 + vertex 798.847 152.336 19.9095 + vertex 798.206 156.995 20.3976 + endloop + endfacet + facet normal 0.0922254 -0.103901 0.990302 + outer loop + vertex 788.479 150.78 20.6514 + vertex 798.206 156.995 20.3976 + vertex 788.058 155.625 21.199 + endloop + endfacet + facet normal 0.086164 -0.10163 0.991084 + outer loop + vertex 789.127 146.286 20.1342 + vertex 798.847 152.336 19.9095 + vertex 788.479 150.78 20.6514 + endloop + endfacet + facet normal 0.0813028 -0.102369 0.991418 + outer loop + vertex 778.599 144.913 20.8558 + vertex 789.127 146.286 20.1342 + vertex 788.479 150.78 20.6514 + endloop + endfacet + facet normal 0.0867034 -0.111514 0.989973 + outer loop + vertex 778.599 144.913 20.8558 + vertex 788.479 150.78 20.6514 + vertex 778.082 149.554 21.4238 + endloop + endfacet + facet normal 0.0821336 -0.109159 0.990625 + outer loop + vertex 779.25 140.529 20.3187 + vertex 789.127 146.286 20.1342 + vertex 778.599 144.913 20.8558 + endloop + endfacet + facet normal 0.0768457 -0.109984 0.990958 + outer loop + vertex 768.588 139.344 21.014 + vertex 779.25 140.529 20.3187 + vertex 778.599 144.913 20.8558 + endloop + endfacet + facet normal 0.0800538 -0.115777 0.990044 + outer loop + vertex 768.588 139.344 21.014 + vertex 778.599 144.913 20.8558 + vertex 768.063 143.889 21.5879 + endloop + endfacet + facet normal 0.0773662 -0.115027 0.990345 + outer loop + vertex 769.182 134.985 20.4613 + vertex 779.25 140.529 20.3187 + vertex 768.588 139.344 21.014 + endloop + endfacet + facet normal 0.0722673 -0.115759 0.990645 + outer loop + vertex 758.405 133.989 21.1311 + vertex 769.182 134.985 20.4613 + vertex 768.588 139.344 21.014 + endloop + endfacet + facet normal 0.0742701 -0.119581 0.990043 + outer loop + vertex 758.405 133.989 21.1311 + vertex 768.588 139.344 21.014 + vertex 757.963 138.532 21.713 + endloop + endfacet + facet normal 0.0725799 -0.119451 0.990184 + outer loop + vertex 758.918 129.613 20.5657 + vertex 769.182 134.985 20.4613 + vertex 758.405 133.989 21.1311 + endloop + endfacet + facet normal 0.0678888 -0.120035 0.990446 + outer loop + vertex 748.047 128.813 21.2139 + vertex 758.918 129.613 20.5657 + vertex 758.405 133.989 21.1311 + endloop + endfacet + facet normal 0.0694794 -0.123227 0.989943 + outer loop + vertex 748.047 128.813 21.2139 + vertex 758.405 133.989 21.1311 + vertex 747.681 133.375 21.8073 + endloop + endfacet + facet normal 0.0681311 -0.123707 0.989977 + outer loop + vertex 748.484 124.426 20.6355 + vertex 758.918 129.613 20.5657 + vertex 748.047 128.813 21.2139 + endloop + endfacet + facet normal 0.0639639 -0.124151 0.9902 + outer loop + vertex 737.526 123.821 21.2676 + vertex 748.484 124.426 20.6355 + vertex 748.047 128.813 21.2139 + endloop + endfacet + facet normal 0.0648015 -0.125919 0.989922 + outer loop + vertex 737.526 123.821 21.2676 + vertex 748.047 128.813 21.2139 + vertex 737.219 128.387 21.8684 + endloop + endfacet + facet normal 0.0639929 -0.12476 0.990121 + outer loop + vertex 737.927 119.436 20.6891 + vertex 748.484 124.426 20.6355 + vertex 737.526 123.821 21.2676 + endloop + endfacet + facet normal 0.0595508 -0.125195 0.990343 + outer loop + vertex 726.85 118.996 21.2996 + vertex 737.927 119.436 20.6891 + vertex 737.526 123.821 21.2676 + endloop + endfacet + facet normal 0.0596498 -0.125415 0.99031 + outer loop + vertex 726.85 118.996 21.2996 + vertex 737.526 123.821 21.2676 + vertex 726.576 123.552 21.893 + endloop + endfacet + facet normal 0.0595516 -0.12522 0.99034 + outer loop + vertex 727.249 114.629 20.7234 + vertex 737.927 119.436 20.6891 + vertex 726.85 118.996 21.2996 + endloop + endfacet + facet normal 0.0557212 -0.125593 0.990516 + outer loop + vertex 716.133 114.325 21.3102 + vertex 727.249 114.629 20.7234 + vertex 726.85 118.996 21.2996 + endloop + endfacet + facet normal 0.0543282 -0.122396 0.990993 + outer loop + vertex 716.133 114.325 21.3102 + vertex 726.85 118.996 21.2996 + vertex 715.675 118.799 21.8879 + endloop + endfacet + facet normal 0.0556952 -0.12433 0.990677 + outer loop + vertex 716.516 110.002 20.7461 + vertex 727.249 114.629 20.7234 + vertex 716.133 114.325 21.3102 + endloop + endfacet + facet normal 0.0518587 -0.124691 0.990839 + outer loop + vertex 705.524 109.883 21.3064 + vertex 716.516 110.002 20.7461 + vertex 716.133 114.325 21.3102 + endloop + endfacet + facet normal 0.0482961 -0.116185 0.992053 + outer loop + vertex 705.524 109.883 21.3064 + vertex 716.133 114.325 21.3102 + vertex 705.155 114.15 21.8242 + endloop + endfacet + facet normal 0.051849 -0.122555 0.991106 + outer loop + vertex 705.718 105.556 20.7612 + vertex 716.516 110.002 20.7461 + vertex 705.524 109.883 21.3064 + endloop + endfacet + facet normal 0.0487282 -0.122712 0.991245 + outer loop + vertex 694.789 105.727 21.3196 + vertex 705.718 105.556 20.7612 + vertex 705.524 109.883 21.3064 + endloop + endfacet + facet normal 0.0432505 -0.108557 0.993149 + outer loop + vertex 694.789 105.727 21.3196 + vertex 705.524 109.883 21.3064 + vertex 695.205 109.99 21.7675 + endloop + endfacet + facet normal 0.0487579 -0.121357 0.991411 + outer loop + vertex 694.761 101.252 20.7733 + vertex 705.718 105.556 20.7612 + vertex 694.789 105.727 21.3196 + endloop + endfacet + facet normal 0.0469356 -0.121356 0.991499 + outer loop + vertex 683.724 101.662 21.3459 + vertex 694.761 101.252 20.7733 + vertex 694.789 105.727 21.3196 + endloop + endfacet + facet normal 0.041466 -0.106453 0.993453 + outer loop + vertex 683.724 101.662 21.3459 + vertex 694.789 105.727 21.3196 + vertex 684.21 106.444 21.838 + endloop + endfacet + facet normal 0.0469225 -0.121658 0.991462 + outer loop + vertex 683.607 97.0168 20.7815 + vertex 694.761 101.252 20.7733 + vertex 683.724 101.662 21.3459 + endloop + endfacet + facet normal 0.0459762 -0.12164 0.991509 + outer loop + vertex 672.384 97.5006 21.3612 + vertex 683.607 97.0168 20.7815 + vertex 683.724 101.662 21.3459 + endloop + endfacet + facet normal 0.041383 -0.109117 0.993167 + outer loop + vertex 672.384 97.5006 21.3612 + vertex 683.724 101.662 21.3459 + vertex 672.899 102.441 21.8826 + endloop + endfacet + facet normal 0.0459196 -0.122786 0.99137 + outer loop + vertex 672.457 92.8698 20.7843 + vertex 683.607 97.0168 20.7815 + vertex 672.384 97.5006 21.3612 + endloop + endfacet + facet normal 0.0456075 -0.122793 0.991384 + outer loop + vertex 661.522 93.3599 21.348 + vertex 672.457 92.8698 20.7843 + vertex 672.384 97.5006 21.3612 + endloop + endfacet + facet normal 0.0418739 -0.113004 0.992712 + outer loop + vertex 661.522 93.3599 21.348 + vertex 672.384 97.5006 21.3612 + vertex 660.496 98.1159 21.9327 + endloop + endfacet + facet normal 0.0455131 -0.124639 0.991158 + outer loop + vertex 661.539 88.9522 20.793 + vertex 672.457 92.8698 20.7843 + vertex 661.522 93.3599 21.348 + endloop + endfacet + facet normal 0.0450096 -0.124644 0.99118 + outer loop + vertex 651.37 89.6968 21.3484 + vertex 661.539 88.9522 20.793 + vertex 661.522 93.3599 21.348 + endloop + endfacet + facet normal 0.0397347 -0.110025 0.993134 + outer loop + vertex 651.37 89.6968 21.3484 + vertex 661.522 93.3599 21.348 + vertex 651.587 93.5142 21.7626 + endloop + endfacet + facet normal 0.0447322 -0.128112 0.99075 + outer loop + vertex 650.582 85.3405 20.8207 + vertex 661.539 88.9522 20.793 + vertex 651.37 89.6968 21.3484 + endloop + endfacet + facet normal 0.0433658 -0.127875 0.990842 + outer loop + vertex 640.232 86.6883 21.4476 + vertex 650.582 85.3405 20.8207 + vertex 651.37 89.6968 21.3484 + endloop + endfacet + facet normal 0.0394934 -0.113476 0.992755 + outer loop + vertex 640.232 86.6883 21.4476 + vertex 651.37 89.6968 21.3484 + vertex 643.435 90.6402 21.7719 + endloop + endfacet + facet normal 0.0433041 -0.128323 0.990787 + outer loop + vertex 639.29 81.8066 20.8565 + vertex 650.582 85.3405 20.8207 + vertex 640.232 86.6883 21.4476 + endloop + endfacet + facet normal 0.0447338 -0.128587 0.990689 + outer loop + vertex 628.815 83.2133 21.5121 + vertex 639.29 81.8066 20.8565 + vertex 640.232 86.6883 21.4476 + endloop + endfacet + facet normal 0.0417075 -0.118618 0.992064 + outer loop + vertex 628.815 83.2133 21.5121 + vertex 640.232 86.6883 21.4476 + vertex 631.574 87.0645 21.8566 + endloop + endfacet + facet normal 0.0451799 -0.121066 0.991616 + outer loop + vertex 625.383 85.587 21.9583 + vertex 628.815 83.2133 21.5121 + vertex 631.574 87.0645 21.8566 + endloop + endfacet + facet normal 0.0476926 -0.117493 0.991928 + outer loop + vertex 625.383 85.587 21.9583 + vertex 620.044 83.5325 21.9716 + vertex 628.815 83.2133 21.5121 + endloop + endfacet + facet normal 0.0472331 -0.128233 0.990619 + outer loop + vertex 617.997 79.7822 21.5837 + vertex 628.815 83.2133 21.5121 + vertex 620.044 83.5325 21.9716 + endloop + endfacet + facet normal 0.0553642 -0.132567 0.989627 + outer loop + vertex 614.165 82.1882 22.1204 + vertex 617.997 79.7822 21.5837 + vertex 620.044 83.5325 21.9716 + endloop + endfacet + facet normal 0.0542075 -0.13437 0.989447 + outer loop + vertex 614.165 82.1882 22.1204 + vertex 610.189 80.453 22.1026 + vertex 617.997 79.7822 21.5837 + endloop + endfacet + facet normal 0.0530295 -0.146769 0.987748 + outer loop + vertex 610.049 76.8287 21.5716 + vertex 617.997 79.7822 21.5837 + vertex 610.189 80.453 22.1026 + endloop + endfacet + facet normal 0.0537847 -0.146792 0.987704 + outer loop + vertex 606.179 79.6722 22.2049 + vertex 610.049 76.8287 21.5716 + vertex 610.189 80.453 22.1026 + endloop + endfacet + facet normal 0.0534645 -0.147217 0.987658 + outer loop + vertex 610.049 76.8287 21.5716 + vertex 606.179 79.6722 22.2049 + vertex 605.253 78.4326 22.0703 + endloop + endfacet + facet normal 0.0508512 -0.154717 0.986649 + outer loop + vertex 605.253 78.4326 22.0703 + vertex 606.365 74.1372 21.3394 + vertex 610.049 76.8287 21.5716 + endloop + endfacet + facet normal 0.0482211 -0.151176 0.98733 + outer loop + vertex 610.947 71.6581 20.736 + vertex 610.049 76.8287 21.5716 + vertex 606.365 74.1372 21.3394 + endloop + endfacet + facet normal 0.0445809 -0.157698 0.986481 + outer loop + vertex 606.365 74.1372 21.3394 + vertex 607.043 68.9257 20.4756 + vertex 610.947 71.6581 20.736 + endloop + endfacet + facet normal 0.0480304 -0.15121 0.987334 + outer loop + vertex 610.947 71.6581 20.736 + vertex 618.006 74.7497 20.8661 + vertex 610.049 76.8287 21.5716 + endloop + endfacet + facet normal 0.0586742 -0.17532 0.982762 + outer loop + vertex 610.947 71.6581 20.736 + vertex 617.68 69.7346 19.9909 + vertex 618.006 74.7497 20.8661 + endloop + endfacet + facet normal 0.0567034 -0.175216 0.982896 + outer loop + vertex 617.68 69.7346 19.9909 + vertex 627.357 73.1718 20.0454 + vertex 618.006 74.7497 20.8661 + endloop + endfacet + facet normal 0.0574434 -0.171177 0.983564 + outer loop + vertex 618.006 74.7497 20.8661 + vertex 627.357 73.1718 20.0454 + vertex 628.019 78.2052 20.8827 + endloop + endfacet + facet normal 0.0469975 -0.140932 0.988903 + outer loop + vertex 618.006 74.7497 20.8661 + vertex 628.019 78.2052 20.8827 + vertex 617.997 79.7822 21.5837 + endloop + endfacet + facet normal 0.0553827 -0.170933 0.983725 + outer loop + vertex 627.357 73.1718 20.0454 + vertex 638.489 76.8354 20.0552 + vertex 628.019 78.2052 20.8827 + endloop + endfacet + facet normal 0.0558555 -0.167645 0.984264 + outer loop + vertex 628.019 78.2052 20.8827 + vertex 638.489 76.8354 20.0552 + vertex 639.29 81.8066 20.8565 + endloop + endfacet + facet normal 0.0557049 -0.167623 0.984276 + outer loop + vertex 638.489 76.8354 20.0552 + vertex 649.91 80.5502 20.0415 + vertex 639.29 81.8066 20.8565 + endloop + endfacet + facet normal 0.0566802 -0.181884 0.981685 + outer loop + vertex 610.923 66.8025 19.8378 + vertex 617.68 69.7346 19.9909 + vertex 610.947 71.6581 20.736 + endloop + endfacet + facet normal 0.0618289 -0.181852 0.98138 + outer loop + vertex 610.923 66.8025 19.8378 + vertex 610.947 71.6581 20.736 + vertex 607.043 68.9257 20.4756 + endloop + endfacet + facet normal 0.0508471 -0.140899 0.988717 + outer loop + vertex 610.049 76.8287 21.5716 + vertex 618.006 74.7497 20.8661 + vertex 617.997 79.7822 21.5837 + endloop + endfacet + facet normal 0.0484636 -0.132124 0.990048 + outer loop + vertex 617.997 79.7822 21.5837 + vertex 628.019 78.2052 20.8827 + vertex 628.815 83.2133 21.5121 + endloop + endfacet + facet normal 0.0418582 -0.115537 0.992421 + outer loop + vertex 636.897 89.1333 21.8729 + vertex 631.574 87.0645 21.8566 + vertex 640.232 86.6883 21.4476 + endloop + endfacet + facet normal 0.0443197 -0.131501 0.990325 + outer loop + vertex 628.019 78.2052 20.8827 + vertex 639.29 81.8066 20.8565 + vertex 628.815 83.2133 21.5121 + endloop + endfacet + facet normal 0.0556689 -0.167898 0.984231 + outer loop + vertex 639.29 81.8066 20.8565 + vertex 649.91 80.5502 20.0415 + vertex 650.582 85.3405 20.8207 + endloop + endfacet + facet normal 0.0574773 -0.168129 0.984088 + outer loop + vertex 649.91 80.5502 20.0415 + vertex 661.14 84.3055 20.0272 + vertex 650.582 85.3405 20.8207 + endloop + endfacet + facet normal 0.0575847 -0.167155 0.984247 + outer loop + vertex 650.582 85.3405 20.8207 + vertex 661.14 84.3055 20.0272 + vertex 661.539 88.9522 20.793 + endloop + endfacet + facet normal 0.059475 -0.167295 0.984111 + outer loop + vertex 661.14 84.3055 20.0272 + vertex 672.258 88.2065 20.0184 + vertex 661.539 88.9522 20.793 + endloop + endfacet + facet normal 0.0597227 -0.164253 0.984609 + outer loop + vertex 661.539 88.9522 20.793 + vertex 672.258 88.2065 20.0184 + vertex 672.457 92.8698 20.7843 + endloop + endfacet + facet normal 0.0607821 -0.164286 0.984538 + outer loop + vertex 672.258 88.2065 20.0184 + vertex 683.426 92.3097 20.0136 + vertex 672.457 92.8698 20.7843 + endloop + endfacet + facet normal 0.0608642 -0.162972 0.984752 + outer loop + vertex 672.457 92.8698 20.7843 + vertex 683.426 92.3097 20.0136 + vertex 683.607 97.0168 20.7815 + endloop + endfacet + facet normal 0.0624589 -0.163016 0.984644 + outer loop + vertex 683.426 92.3097 20.0136 + vertex 694.612 96.5768 20.0105 + vertex 683.607 97.0168 20.7815 + endloop + endfacet + facet normal 0.0624784 -0.162636 0.984706 + outer loop + vertex 683.607 97.0168 20.7815 + vertex 694.612 96.5768 20.0105 + vertex 694.761 101.252 20.7733 + endloop + endfacet + facet normal 0.0646281 -0.162681 0.98456 + outer loop + vertex 694.612 96.5768 20.0105 + vertex 705.669 100.955 20.0081 + vertex 694.761 101.252 20.7733 + endloop + endfacet + facet normal 0.0646598 -0.161862 0.984693 + outer loop + vertex 694.761 101.252 20.7733 + vertex 705.669 100.955 20.0081 + vertex 705.718 105.556 20.7612 + endloop + endfacet + facet normal 0.0676697 -0.161861 0.984491 + outer loop + vertex 705.669 100.955 20.0081 + vertex 716.54 105.437 19.9978 + vertex 705.718 105.556 20.7612 + endloop + endfacet + facet normal 0.0676881 -0.161043 0.984624 + outer loop + vertex 705.718 105.556 20.7612 + vertex 716.54 105.437 19.9978 + vertex 716.516 110.002 20.7461 + endloop + endfacet + facet normal 0.070467 -0.160998 0.984436 + outer loop + vertex 716.54 105.437 19.9978 + vertex 727.317 110.072 19.9844 + vertex 716.516 110.002 20.7461 + endloop + endfacet + facet normal 0.0704787 -0.158652 0.984816 + outer loop + vertex 716.516 110.002 20.7461 + vertex 727.317 110.072 19.9844 + vertex 727.249 114.629 20.7234 + endloop + endfacet + facet normal 0.0739274 -0.158562 0.984577 + outer loop + vertex 727.317 110.072 19.9844 + vertex 738.017 114.877 19.9548 + vertex 727.249 114.629 20.7234 + endloop + endfacet + facet normal 0.0739113 -0.157156 0.984804 + outer loop + vertex 727.249 114.629 20.7234 + vertex 738.017 114.877 19.9548 + vertex 737.927 119.436 20.6891 + endloop + endfacet + facet normal 0.0777146 -0.157037 0.98453 + outer loop + vertex 738.017 114.877 19.9548 + vertex 748.614 119.861 19.9133 + vertex 737.927 119.436 20.6891 + endloop + endfacet + facet normal 0.0776191 -0.153645 0.985073 + outer loop + vertex 737.927 119.436 20.6891 + vertex 748.614 119.861 19.9133 + vertex 748.484 124.426 20.6355 + endloop + endfacet + facet normal 0.0815957 -0.153484 0.984777 + outer loop + vertex 748.614 119.861 19.9133 + vertex 759.093 125.045 19.853 + vertex 748.484 124.426 20.6355 + endloop + endfacet + facet normal 0.08146 -0.15058 0.985236 + outer loop + vertex 748.484 124.426 20.6355 + vertex 759.093 125.045 19.853 + vertex 758.918 129.613 20.5657 + endloop + endfacet + facet normal 0.0865364 -0.150323 0.984842 + outer loop + vertex 759.093 125.045 19.853 + vertex 769.44 130.429 19.7656 + vertex 758.918 129.613 20.5657 + endloop + endfacet + facet normal 0.0862278 -0.14562 0.985576 + outer loop + vertex 758.918 129.613 20.5657 + vertex 769.44 130.429 19.7656 + vertex 769.182 134.985 20.4613 + endloop + endfacet + facet normal 0.0908558 -0.145301 0.985207 + outer loop + vertex 769.44 130.429 19.7656 + vertex 779.603 135.984 19.6477 + vertex 769.182 134.985 20.4613 + endloop + endfacet + facet normal 0.0902929 -0.138607 0.986223 + outer loop + vertex 769.182 134.985 20.4613 + vertex 779.603 135.984 19.6477 + vertex 779.25 140.529 20.3187 + endloop + endfacet + facet normal 0.0949591 -0.138189 0.985843 + outer loop + vertex 779.603 135.984 19.6477 + vertex 789.551 141.714 19.4926 + vertex 779.25 140.529 20.3187 + endloop + endfacet + facet normal 0.116375 -0.1756 0.977559 + outer loop + vertex 779.603 135.984 19.6477 + vertex 789.516 136.703 18.5968 + vertex 789.551 141.714 19.4926 + endloop + endfacet + facet normal 0.119899 -0.17555 0.977142 + outer loop + vertex 789.516 136.703 18.5968 + vertex 799.382 142.63 18.4509 + vertex 789.551 141.714 19.4926 + endloop + endfacet + facet normal 0.119033 -0.163831 0.979281 + outer loop + vertex 789.551 141.714 19.4926 + vertex 799.382 142.63 18.4509 + vertex 799.329 147.681 19.3024 + endloop + endfacet + facet normal 0.0981425 -0.129364 0.986728 + outer loop + vertex 789.551 141.714 19.4926 + vertex 799.329 147.681 19.3024 + vertex 789.127 146.286 20.1342 + endloop + endfacet + facet normal 0.121386 -0.163759 0.979004 + outer loop + vertex 799.382 142.63 18.4509 + vertex 809.154 148.855 18.2806 + vertex 799.329 147.681 19.3024 + endloop + endfacet + facet normal 0.120025 -0.150356 0.981319 + outer loop + vertex 799.329 147.681 19.3024 + vertex 809.154 148.855 18.2806 + vertex 808.972 153.95 19.0835 + endloop + endfacet + facet normal 0.0995049 -0.118559 0.987949 + outer loop + vertex 799.329 147.681 19.3024 + vertex 808.972 153.95 19.0835 + vertex 798.847 152.336 19.9095 + endloop + endfacet + facet normal 0.120901 -0.150309 0.981219 + outer loop + vertex 809.154 148.855 18.2806 + vertex 818.823 155.417 18.0944 + vertex 808.972 153.95 19.0835 + endloop + endfacet + facet normal 0.119173 -0.137282 0.983337 + outer loop + vertex 808.972 153.95 19.0835 + vertex 818.823 155.417 18.0944 + vertex 818.438 160.507 18.8517 + endloop + endfacet + facet normal 0.0983348 -0.106986 0.989386 + outer loop + vertex 808.972 153.95 19.0835 + vertex 818.438 160.507 18.8517 + vertex 808.409 158.686 19.6516 + endloop + endfacet + facet normal 0.118454 -0.137348 0.983414 + outer loop + vertex 818.823 155.417 18.0944 + vertex 828.244 162.238 17.9123 + vertex 818.438 160.507 18.8517 + endloop + endfacet + facet normal 0.116395 -0.124628 0.985353 + outer loop + vertex 818.438 160.507 18.8517 + vertex 828.244 162.238 17.9123 + vertex 827.62 167.265 18.6218 + endloop + endfacet + facet normal 0.11375 -0.124993 0.985615 + outer loop + vertex 828.244 162.238 17.9123 + vertex 837.247 169.177 17.7532 + vertex 827.62 167.265 18.6218 + endloop + endfacet + facet normal 0.116874 -0.185153 0.975735 + outer loop + vertex 779.467 130.981 18.7146 + vertex 789.516 136.703 18.5968 + vertex 779.603 135.984 19.6477 + endloop + endfacet + facet normal 0.112526 -0.185131 0.97625 + outer loop + vertex 769.44 130.429 19.7656 + vertex 779.467 130.981 18.7146 + vertex 779.603 135.984 19.6477 + endloop + endfacet + facet normal 0.112773 -0.192316 0.974832 + outer loop + vertex 769.186 125.413 18.8055 + vertex 779.467 130.981 18.7146 + vertex 769.44 130.429 19.7656 + endloop + endfacet + facet normal 0.10824 -0.192189 0.975371 + outer loop + vertex 759.093 125.045 19.853 + vertex 769.186 125.413 18.8055 + vertex 769.44 130.429 19.7656 + endloop + endfacet + facet normal 0.108342 -0.198808 0.974032 + outer loop + vertex 758.752 120.033 18.8679 + vertex 769.186 125.413 18.8055 + vertex 759.093 125.045 19.853 + endloop + endfacet + facet normal 0.103858 -0.198607 0.974561 + outer loop + vertex 748.614 119.861 19.9133 + vertex 758.752 120.033 18.8679 + vertex 759.093 125.045 19.853 + endloop + endfacet + facet normal 0.103839 -0.20309 0.973639 + outer loop + vertex 748.25 114.879 18.9129 + vertex 758.752 120.033 18.8679 + vertex 748.614 119.861 19.9133 + endloop + endfacet + facet normal 0.0992266 -0.202858 0.974168 + outer loop + vertex 738.017 114.877 19.9548 + vertex 748.25 114.879 18.9129 + vertex 748.614 119.861 19.9133 + endloop + endfacet + facet normal 0.0991382 -0.207066 0.973291 + outer loop + vertex 737.598 109.896 18.9379 + vertex 748.25 114.879 18.9129 + vertex 738.017 114.877 19.9548 + endloop + endfacet + facet normal 0.0955807 -0.206848 0.973693 + outer loop + vertex 727.317 110.072 19.9844 + vertex 737.598 109.896 18.9379 + vertex 738.017 114.877 19.9548 + endloop + endfacet + facet normal 0.0954809 -0.209444 0.973148 + outer loop + vertex 726.858 105.088 18.9567 + vertex 737.598 109.896 18.9379 + vertex 727.317 110.072 19.9844 + endloop + endfacet + facet normal 0.0911609 -0.209146 0.973626 + outer loop + vertex 716.54 105.437 19.9978 + vertex 726.858 105.088 18.9567 + vertex 727.317 110.072 19.9844 + endloop + endfacet + facet normal 0.0910883 -0.210464 0.973349 + outer loop + vertex 716.126 100.484 18.9656 + vertex 726.858 105.088 18.9567 + vertex 716.54 105.437 19.9978 + endloop + endfacet + facet normal 0.0876103 -0.21025 0.973714 + outer loop + vertex 705.669 100.955 20.0081 + vertex 716.126 100.484 18.9656 + vertex 716.54 105.437 19.9978 + endloop + endfacet + facet normal 0.0874189 -0.213146 0.973102 + outer loop + vertex 705.232 96.0043 18.963 + vertex 716.126 100.484 18.9656 + vertex 705.669 100.955 20.0081 + endloop + endfacet + facet normal 0.0845305 -0.212954 0.973399 + outer loop + vertex 694.612 96.5768 20.0105 + vertex 705.232 96.0043 18.963 + vertex 705.669 100.955 20.0081 + endloop + endfacet + facet normal 0.0844972 -0.213398 0.973304 + outer loop + vertex 694.107 91.612 18.9658 + vertex 705.232 96.0043 18.963 + vertex 694.612 96.5768 20.0105 + endloop + endfacet + facet normal 0.0815858 -0.213165 0.973604 + outer loop + vertex 683.426 92.3097 20.0136 + vertex 694.107 91.612 18.9658 + vertex 694.612 96.5768 20.0105 + endloop + endfacet + facet normal 0.0814525 -0.214712 0.973275 + outer loop + vertex 682.884 87.3557 18.9661 + vertex 694.107 91.612 18.9658 + vertex 683.426 92.3097 20.0136 + endloop + endfacet + facet normal 0.0792343 -0.214518 0.973501 + outer loop + vertex 672.258 88.2065 20.0184 + vertex 682.884 87.3557 18.9661 + vertex 683.426 92.3097 20.0136 + endloop + endfacet + facet normal 0.0789933 -0.2169 0.972993 + outer loop + vertex 671.665 83.2627 18.9645 + vertex 682.884 87.3557 18.9661 + vertex 672.258 88.2065 20.0184 + endloop + endfacet + facet normal 0.0767937 -0.216683 0.973217 + outer loop + vertex 661.14 84.3055 20.0272 + vertex 671.665 83.2627 18.9645 + vertex 672.258 88.2065 20.0184 + endloop + endfacet + facet normal 0.0766957 -0.217496 0.973043 + outer loop + vertex 660.458 79.3265 18.968 + vertex 671.665 83.2627 18.9645 + vertex 661.14 84.3055 20.0272 + endloop + endfacet + facet normal 0.0738631 -0.21717 0.973335 + outer loop + vertex 649.91 80.5502 20.0415 + vertex 660.458 79.3265 18.968 + vertex 661.14 84.3055 20.0272 + endloop + endfacet + facet normal 0.0738523 -0.217249 0.973318 + outer loop + vertex 649.189 75.5185 18.9731 + vertex 660.458 79.3265 18.968 + vertex 649.91 80.5502 20.0415 + endloop + endfacet + facet normal 0.0717515 -0.216993 0.973533 + outer loop + vertex 638.489 76.8354 20.0552 + vertex 649.189 75.5185 18.9731 + vertex 649.91 80.5502 20.0415 + endloop + endfacet + facet normal 0.0715948 -0.218077 0.973302 + outer loop + vertex 637.781 71.7835 18.9754 + vertex 649.189 75.5185 18.9731 + vertex 638.489 76.8354 20.0552 + endloop + endfacet + facet normal 0.0708788 -0.217991 0.973373 + outer loop + vertex 627.357 73.1718 20.0454 + vertex 637.781 71.7835 18.9754 + vertex 638.489 76.8354 20.0552 + endloop + endfacet + facet normal 0.0706633 -0.219381 0.973077 + outer loop + vertex 626.552 68.133 18.9678 + vertex 637.781 71.7835 18.9754 + vertex 627.357 73.1718 20.0454 + endloop + endfacet + facet normal 0.0725383 -0.219638 0.972881 + outer loop + vertex 617.68 69.7346 19.9909 + vertex 626.552 68.133 18.9678 + vertex 627.357 73.1718 20.0454 + endloop + endfacet + facet normal 0.0716594 -0.223924 0.971969 + outer loop + vertex 616.662 64.8274 18.9354 + vertex 626.552 68.133 18.9678 + vertex 617.68 69.7346 19.9909 + endloop + endfacet + facet normal 0.0754537 -0.224616 0.971522 + outer loop + vertex 610.923 66.8025 19.8378 + vertex 616.662 64.8274 18.9354 + vertex 617.68 69.7346 19.9909 + endloop + endfacet + facet normal 0.073548 -0.229678 0.970484 + outer loop + vertex 610.157 62.5215 18.8827 + vertex 616.662 64.8274 18.9354 + vertex 610.923 66.8025 19.8378 + endloop + endfacet + facet normal 0.0753972 -0.229963 0.970274 + outer loop + vertex 610.157 62.5215 18.8827 + vertex 610.923 66.8025 19.8378 + vertex 607.219 64.2499 19.5206 + endloop + endfacet + facet normal 0.0940909 -0.129788 0.987067 + outer loop + vertex 779.25 140.529 20.3187 + vertex 789.551 141.714 19.4926 + vertex 789.127 146.286 20.1342 + endloop + endfacet + facet normal 0.0968246 -0.118866 0.988178 + outer loop + vertex 789.127 146.286 20.1342 + vertex 799.329 147.681 19.3024 + vertex 798.847 152.336 19.9095 + endloop + endfacet + facet normal 0.097792 -0.107056 0.989432 + outer loop + vertex 798.847 152.336 19.9095 + vertex 808.972 153.95 19.0835 + vertex 808.409 158.686 19.6516 + endloop + endfacet + facet normal 0.0963387 -0.0953846 0.990768 + outer loop + vertex 808.409 158.686 19.6516 + vertex 818.438 160.507 18.8517 + vertex 817.754 165.265 19.3763 + endloop + endfacet + facet normal 0.0951449 -0.095567 0.990865 + outer loop + vertex 818.438 160.507 18.8517 + vertex 827.62 167.265 18.6218 + vertex 817.754 165.265 19.3763 + endloop + endfacet + facet normal 0.111445 -0.112585 0.987373 + outer loop + vertex 827.62 167.265 18.6218 + vertex 837.247 169.177 17.7532 + vertex 836.501 174.178 18.4077 + endloop + endfacet + facet normal 0.108736 -0.113022 0.987625 + outer loop + vertex 837.247 169.177 17.7532 + vertex 845.933 176.252 17.6065 + vertex 836.501 174.178 18.4077 + endloop + endfacet + facet normal 0.106275 -0.101232 0.98917 + outer loop + vertex 836.501 174.178 18.4077 + vertex 845.933 176.252 17.6065 + vertex 845.165 181.334 18.2091 + endloop + endfacet + facet normal 0.10512 -0.101419 0.989274 + outer loop + vertex 845.933 176.252 17.6065 + vertex 854.596 183.749 17.4546 + vertex 845.165 181.334 18.2091 + endloop + endfacet + facet normal 0.103444 -0.094606 0.990126 + outer loop + vertex 845.165 181.334 18.2091 + vertex 854.596 183.749 17.4546 + vertex 853.443 188.768 18.0546 + endloop + endfacet + facet normal 0.0989084 -0.0956904 0.990485 + outer loop + vertex 854.596 183.749 17.4546 + vertex 862.578 191.376 17.3943 + vertex 853.443 188.768 18.0546 + endloop + endfacet + facet normal 0.0702189 -0.0553901 0.995993 + outer loop + vertex 851.96 193.518 18.4554 + vertex 860.76 196.256 17.9873 + vertex 858.596 201.109 18.4097 + endloop + endfacet + facet normal 0.0628364 -0.0489306 0.996824 + outer loop + vertex 851.96 193.518 18.4554 + vertex 858.596 201.109 18.4097 + vertex 850.38 198.236 18.7866 + endloop + endfacet + facet normal 0.0539122 -0.0575452 0.996886 + outer loop + vertex 863.378 208.737 18.5237 + vertex 866.924 204.024 18.0599 + vertex 869.886 211.349 18.3225 + endloop + endfacet + facet normal 0.0528348 -0.0548445 0.997096 + outer loop + vertex 869.886 211.349 18.3225 + vertex 866.78 216.193 18.7536 + vertex 863.378 208.737 18.5237 + endloop + endfacet + facet normal 0.0529246 -0.0547868 0.997094 + outer loop + vertex 869.886 211.349 18.3225 + vertex 873.878 217.789 18.4645 + vertex 866.78 216.193 18.7536 + endloop + endfacet + facet normal 0.0539491 -0.0594025 0.996775 + outer loop + vertex 866.78 216.193 18.7536 + vertex 873.878 217.789 18.4645 + vertex 871.172 222.446 18.8885 + endloop + endfacet + facet normal 0.072798 -0.0725972 0.994701 + outer loop + vertex 866.78 216.193 18.7536 + vertex 871.172 222.446 18.8885 + vertex 865.627 220.865 19.179 + endloop + endfacet + facet normal 0.0647639 -0.0746168 0.995107 + outer loop + vertex 863.069 218.414 19.1616 + vertex 866.78 216.193 18.7536 + vertex 865.627 220.865 19.179 + endloop + endfacet + facet normal 0.0670097 -0.0708864 0.995231 + outer loop + vertex 866.78 216.193 18.7536 + vertex 863.069 218.414 19.1616 + vertex 860.538 213.636 18.9917 + endloop + endfacet + facet normal 0.0754845 -0.0821919 0.993754 + outer loop + vertex 867.2 223.603 19.2859 + vertex 865.627 220.865 19.179 + vertex 871.172 222.446 18.8885 + endloop + endfacet + facet normal 0.0770564 -0.0768968 0.994057 + outer loop + vertex 867.2 223.603 19.2859 + vertex 871.172 222.446 18.8885 + vertex 870.322 226.363 19.2574 + endloop + endfacet + facet normal 0.0744451 -0.0774782 0.994211 + outer loop + vertex 871.172 222.446 18.8885 + vertex 876.664 228.898 18.98 + vertex 870.322 226.363 19.2574 + endloop + endfacet + facet normal 0.0753342 -0.0797292 0.993966 + outer loop + vertex 872.813 229.693 19.3357 + vertex 870.322 226.363 19.2574 + vertex 876.664 228.898 18.98 + endloop + endfacet + facet normal 0.0753614 -0.0796012 0.993974 + outer loop + vertex 872.813 229.693 19.3357 + vertex 876.664 228.898 18.98 + vertex 876.36 233.01 19.3324 + endloop + endfacet + facet normal 0.0730245 -0.0797878 0.994133 + outer loop + vertex 876.664 228.898 18.98 + vertex 882.592 235.897 19.1063 + vertex 876.36 233.01 19.3324 + endloop + endfacet + facet normal 0.0753842 -0.0849282 0.993531 + outer loop + vertex 878.872 236.575 19.4466 + vertex 876.36 233.01 19.3324 + vertex 882.592 235.897 19.1063 + endloop + endfacet + facet normal 0.0755456 -0.0840734 0.993592 + outer loop + vertex 878.872 236.575 19.4466 + vertex 882.592 235.897 19.1063 + vertex 882.166 239.99 19.4851 + endloop + endfacet + facet normal 0.078514 -0.0837451 0.993389 + outer loop + vertex 882.592 235.897 19.1063 + vertex 888.216 243.131 19.2717 + vertex 882.166 239.99 19.4851 + endloop + endfacet + facet normal 0.0815359 -0.0896171 0.992633 + outer loop + vertex 884.437 243.605 19.6249 + vertex 882.166 239.99 19.4851 + vertex 888.216 243.131 19.2717 + endloop + endfacet + facet normal 0.0821661 -0.0848692 0.992998 + outer loop + vertex 884.437 243.605 19.6249 + vertex 888.216 243.131 19.2717 + vertex 887.561 247.142 19.6687 + endloop + endfacet + facet normal 0.0848044 -0.0844202 0.992815 + outer loop + vertex 888.216 243.131 19.2717 + vertex 893.4 250.508 19.4562 + vertex 887.561 247.142 19.6687 + endloop + endfacet + facet normal 0.0874244 -0.0890041 0.992187 + outer loop + vertex 889.65 250.82 19.8145 + vertex 887.561 247.142 19.6687 + vertex 893.4 250.508 19.4562 + endloop + endfacet + facet normal 0.0878394 -0.0844292 0.99255 + outer loop + vertex 889.65 250.82 19.8145 + vertex 893.4 250.508 19.4562 + vertex 892.545 254.419 19.8645 + endloop + endfacet + facet normal 0.091328 -0.0836405 0.992302 + outer loop + vertex 893.4 250.508 19.4562 + vertex 898.103 257.995 19.6544 + vertex 892.545 254.419 19.8645 + endloop + endfacet + facet normal 0.0941192 -0.0880153 0.991663 + outer loop + vertex 894.392 258.1 20.0159 + vertex 892.545 254.419 19.8645 + vertex 898.103 257.995 19.6544 + endloop + endfacet + facet normal 0.0942929 -0.083223 0.99206 + outer loop + vertex 894.392 258.1 20.0159 + vertex 898.103 257.995 19.6544 + vertex 897.036 261.77 20.0725 + endloop + endfacet + facet normal 0.0992613 -0.0817792 0.991695 + outer loop + vertex 898.103 257.995 19.6544 + vertex 902.342 265.674 19.8634 + vertex 897.036 261.77 20.0725 + endloop + endfacet + facet normal 0.103226 -0.0872142 0.990827 + outer loop + vertex 898.657 265.512 20.233 + vertex 897.036 261.77 20.0725 + vertex 902.342 265.674 19.8634 + endloop + endfacet + facet normal 0.103007 -0.0809514 0.991381 + outer loop + vertex 898.657 265.512 20.233 + vertex 902.342 265.674 19.8634 + vertex 901.099 269.383 20.2954 + endloop + endfacet + facet normal 0.109934 -0.0785654 0.990829 + outer loop + vertex 902.342 265.674 19.8634 + vertex 906.173 273.736 20.0776 + vertex 901.099 269.383 20.2954 + endloop + endfacet + facet normal 0.11439 -0.0838064 0.989895 + outer loop + vertex 902.539 273.321 20.4624 + vertex 901.099 269.383 20.2954 + vertex 906.173 273.736 20.0776 + endloop + endfacet + facet normal 0.113632 -0.0765268 0.990571 + outer loop + vertex 902.539 273.321 20.4624 + vertex 906.173 273.736 20.0776 + vertex 904.785 277.494 20.527 + endloop + endfacet + facet normal 0.121987 -0.0733524 0.989817 + outer loop + vertex 906.173 273.736 20.0776 + vertex 909.543 282.266 20.2943 + vertex 904.785 277.494 20.527 + endloop + endfacet + facet normal 0.126243 -0.077637 0.988957 + outer loop + vertex 906.028 281.672 20.6964 + vertex 904.785 277.494 20.527 + vertex 909.543 282.266 20.2943 + endloop + endfacet + facet normal 0.125019 -0.0699009 0.989689 + outer loop + vertex 906.028 281.672 20.6964 + vertex 909.543 282.266 20.2943 + vertex 907.995 286.079 20.7591 + endloop + endfacet + facet normal 0.13399 -0.0661488 0.988772 + outer loop + vertex 909.543 282.266 20.2943 + vertex 912.288 291.072 20.5114 + vertex 907.995 286.079 20.7591 + endloop + endfacet + facet normal 0.136887 -0.0686675 0.988204 + outer loop + vertex 908.965 290.387 20.9242 + vertex 907.995 286.079 20.7591 + vertex 912.288 291.072 20.5114 + endloop + endfacet + facet normal 0.135296 -0.0604895 0.988957 + outer loop + vertex 908.965 290.387 20.9242 + vertex 912.288 291.072 20.5114 + vertex 910.577 294.846 20.9764 + endloop + endfacet + facet normal 0.144125 -0.0563636 0.987953 + outer loop + vertex 912.288 291.072 20.5114 + vertex 914.34 299.895 20.7155 + vertex 910.577 294.846 20.9764 + endloop + endfacet + facet normal 0.145883 -0.0576918 0.987618 + outer loop + vertex 911.209 299.118 21.1325 + vertex 910.577 294.846 20.9764 + vertex 914.34 299.895 20.7155 + endloop + endfacet + facet normal 0.143687 -0.0484013 0.988439 + outer loop + vertex 911.209 299.118 21.1325 + vertex 914.34 299.895 20.7155 + vertex 912.443 303.559 21.1706 + endloop + endfacet + facet normal 0.15266 -0.0436174 0.987316 + outer loop + vertex 914.34 299.895 20.7155 + vertex 915.777 308.83 20.888 + vertex 912.443 303.559 21.1706 + endloop + endfacet + facet normal 0.154537 -0.0448233 0.98697 + outer loop + vertex 912.727 307.819 21.3196 + vertex 912.443 303.559 21.1706 + vertex 915.777 308.83 20.888 + endloop + endfacet + facet normal 0.15147 -0.0352007 0.987835 + outer loop + vertex 912.727 307.819 21.3196 + vertex 915.777 308.83 20.888 + vertex 913.596 312.401 21.3496 + endloop + endfacet + facet normal 0.160557 -0.029492 0.986586 + outer loop + vertex 915.777 308.83 20.888 + vertex 916.507 318.065 21.0452 + vertex 913.596 312.401 21.3496 + endloop + endfacet + facet normal 0.16417 -0.0313839 0.985933 + outer loop + vertex 913.57 316.757 21.4927 + vertex 913.596 312.401 21.3496 + vertex 916.507 318.065 21.0452 + endloop + endfacet + facet normal 0.160564 -0.0230003 0.986757 + outer loop + vertex 913.57 316.757 21.4927 + vertex 916.507 318.065 21.0452 + vertex 914.145 321.469 21.5089 + endloop + endfacet + facet normal 0.169554 -0.0165767 0.985381 + outer loop + vertex 916.507 318.065 21.0452 + vertex 916.67 327.484 21.1757 + vertex 914.145 321.469 21.5089 + endloop + endfacet + facet normal 0.170539 -0.0169998 0.985204 + outer loop + vertex 913.923 325.94 21.6245 + vertex 914.145 321.469 21.5089 + vertex 916.67 327.484 21.1757 + endloop + endfacet + facet normal 0.166811 -0.0101538 0.985937 + outer loop + vertex 913.923 325.94 21.6245 + vertex 916.67 327.484 21.1757 + vertex 914.313 331.216 21.6129 + endloop + endfacet + facet normal 0.173414 -0.00585341 0.984832 + outer loop + vertex 916.67 327.484 21.1757 + vertex 916.752 336.723 21.2162 + vertex 914.313 331.216 21.6129 + endloop + endfacet + facet normal 0.171992 -0.00520493 0.985085 + outer loop + vertex 913.822 338.136 21.7352 + vertex 914.313 331.216 21.6129 + vertex 916.752 336.723 21.2162 + endloop + endfacet + facet normal 0.176551 0.00454124 0.984281 + outer loop + vertex 916.752 336.723 21.2162 + vertex 915.845 345.398 21.3389 + vertex 913.822 338.136 21.7352 + endloop + endfacet + facet normal 0.194697 -0.00070056 0.980863 + outer loop + vertex 913.822 338.136 21.7352 + vertex 915.845 345.398 21.3389 + vertex 912.004 345.983 22.1015 + endloop + endfacet + facet normal 0.197288 0.0171817 0.980195 + outer loop + vertex 915.845 345.398 21.3389 + vertex 914.471 354.633 21.4535 + vertex 912.004 345.983 22.1015 + endloop + endfacet + facet normal 0.202815 0.0155235 0.979094 + outer loop + vertex 912.004 345.983 22.1015 + vertex 914.471 354.633 21.4535 + vertex 910.806 356.251 22.1869 + endloop + endfacet + facet normal 0.207807 0.0274191 0.977785 + outer loop + vertex 914.471 354.633 21.4535 + vertex 912.92 364.216 21.5143 + vertex 910.806 356.251 22.1869 + endloop + endfacet + facet normal 0.208637 0.0271845 0.977615 + outer loop + vertex 910.806 356.251 22.1869 + vertex 912.92 364.216 21.5143 + vertex 909.303 365.682 22.2455 + endloop + endfacet + facet normal 0.212037 0.0360819 0.976595 + outer loop + vertex 912.92 364.216 21.5143 + vertex 911.077 373.679 21.5649 + vertex 909.303 365.682 22.2455 + endloop + endfacet + facet normal 0.211724 0.0361567 0.97666 + outer loop + vertex 909.303 365.682 22.2455 + vertex 911.077 373.679 21.5649 + vertex 907.519 374.952 22.289 + endloop + endfacet + facet normal 0.214308 0.0438753 0.97578 + outer loop + vertex 911.077 373.679 21.5649 + vertex 908.979 383.043 21.6046 + vertex 907.519 374.952 22.289 + endloop + endfacet + facet normal 0.213929 0.0439503 0.97586 + outer loop + vertex 907.519 374.952 22.289 + vertex 908.979 383.043 21.6046 + vertex 905.477 384.196 22.3203 + endloop + endfacet + facet normal 0.216189 0.0513423 0.975001 + outer loop + vertex 908.979 383.043 21.6046 + vertex 906.651 392.328 21.6318 + vertex 905.477 384.196 22.3203 + endloop + endfacet + facet normal 0.216893 0.051228 0.97485 + outer loop + vertex 905.477 384.196 22.3203 + vertex 906.651 392.328 21.6318 + vertex 903.23 393.374 22.3381 + endloop + endfacet + facet normal 0.218912 0.0584122 0.973995 + outer loop + vertex 906.651 392.328 21.6318 + vertex 904.136 401.53 21.6454 + vertex 903.23 393.374 22.3381 + endloop + endfacet + facet normal 0.221787 0.0580396 0.973366 + outer loop + vertex 903.23 393.374 22.3381 + vertex 904.136 401.53 21.6454 + vertex 900.808 402.483 22.3467 + endloop + endfacet + facet normal 0.223659 0.0652255 0.972482 + outer loop + vertex 904.136 401.53 21.6454 + vertex 901.449 410.673 21.6499 + vertex 900.808 402.483 22.3467 + endloop + endfacet + facet normal 0.229995 0.0646074 0.971045 + outer loop + vertex 900.808 402.483 22.3467 + vertex 901.449 410.673 21.6499 + vertex 898.213 411.584 22.3558 + endloop + endfacet + facet normal 0.231837 0.07189 0.970094 + outer loop + vertex 901.449 410.673 21.6499 + vertex 898.618 419.782 21.6515 + vertex 898.213 411.584 22.3558 + endloop + endfacet + facet normal 0.239206 0.0713753 0.968342 + outer loop + vertex 898.213 411.584 22.3558 + vertex 898.618 419.782 21.6515 + vertex 895.478 420.675 22.3613 + endloop + endfacet + facet normal 0.241052 0.0786799 0.967318 + outer loop + vertex 898.618 419.782 21.6515 + vertex 895.669 428.849 21.6489 + vertex 895.478 420.675 22.3613 + endloop + endfacet + facet normal 0.248654 0.0783368 0.965419 + outer loop + vertex 895.478 420.675 22.3613 + vertex 895.669 428.849 21.6489 + vertex 892.659 429.671 22.3575 + endloop + endfacet + facet normal 0.250267 0.0850924 0.96443 + outer loop + vertex 895.669 428.849 21.6489 + vertex 892.633 437.872 21.6407 + vertex 892.659 429.671 22.3575 + endloop + endfacet + facet normal 0.260069 0.0848978 0.961851 + outer loop + vertex 892.659 429.671 22.3575 + vertex 892.633 437.872 21.6407 + vertex 889.771 438.607 22.3496 + endloop + endfacet + facet normal 0.261653 0.0921197 0.960756 + outer loop + vertex 892.633 437.872 21.6407 + vertex 889.491 446.897 21.6311 + vertex 889.771 438.607 22.3496 + endloop + endfacet + facet normal 0.275699 0.0922524 0.956807 + outer loop + vertex 889.771 438.607 22.3496 + vertex 889.491 446.897 21.6311 + vertex 886.788 447.624 22.3397 + endloop + endfacet + facet normal 0.277609 0.100728 0.955399 + outer loop + vertex 889.491 446.897 21.6311 + vertex 886.211 455.945 21.6302 + vertex 886.788 447.624 22.3397 + endloop + endfacet + facet normal 0.2978 0.101601 0.949206 + outer loop + vertex 886.788 447.624 22.3397 + vertex 886.211 455.945 21.6302 + vertex 883.69 456.68 22.3424 + endloop + endfacet + facet normal 0.300519 0.112997 0.947059 + outer loop + vertex 886.211 455.945 21.6302 + vertex 882.708 465.011 21.66 + vertex 883.69 456.68 22.3424 + endloop + endfacet + facet normal 0.328889 0.115538 0.937274 + outer loop + vertex 883.69 456.68 22.3424 + vertex 882.708 465.011 21.66 + vertex 880.455 465.663 22.3702 + endloop + endfacet + facet normal 0.332132 0.130068 0.934222 + outer loop + vertex 882.708 465.011 21.66 + vertex 878.97 474.126 21.7198 + vertex 880.455 465.663 22.3702 + endloop + endfacet + facet normal 0.369938 0.135539 0.919116 + outer loop + vertex 880.455 465.663 22.3702 + vertex 878.97 474.126 21.7198 + vertex 877.069 474.641 22.4091 + endloop + endfacet + facet normal 0.371415 0.143389 0.917328 + outer loop + vertex 878.97 474.126 21.7198 + vertex 875.358 483.349 21.7407 + vertex 877.069 474.641 22.4091 + endloop + endfacet + facet normal 0.26201 0.0922439 0.960647 + outer loop + vertex 892.633 437.872 21.6407 + vertex 891.671 446.602 21.0648 + vertex 889.491 446.897 21.6311 + endloop + endfacet + facet normal 0.262775 0.0997459 0.959687 + outer loop + vertex 891.671 446.602 21.0648 + vertex 888.237 455.65 21.0647 + vertex 889.491 446.897 21.6311 + endloop + endfacet + facet normal 0.281205 0.102032 0.954208 + outer loop + vertex 889.491 446.897 21.6311 + vertex 888.237 455.65 21.0647 + vertex 886.211 455.945 21.6302 + endloop + endfacet + facet normal 0.282385 0.113265 0.952591 + outer loop + vertex 888.237 455.65 21.0647 + vertex 884.561 464.707 21.0774 + vertex 886.211 455.945 21.6302 + endloop + endfacet + facet normal 0.315477 0.118794 0.941468 + outer loop + vertex 886.211 455.945 21.6302 + vertex 884.561 464.707 21.0774 + vertex 882.708 465.011 21.66 + endloop + endfacet + facet normal 0.317007 0.132623 0.939105 + outer loop + vertex 884.561 464.707 21.0774 + vertex 880.606 473.844 21.1222 + vertex 882.708 465.011 21.66 + endloop + endfacet + facet normal 0.361222 0.14208 0.921592 + outer loop + vertex 882.708 465.011 21.66 + vertex 880.606 473.844 21.1222 + vertex 878.97 474.126 21.7198 + endloop + endfacet + facet normal 0.36198 0.149631 0.920098 + outer loop + vertex 880.606 473.844 21.1222 + vertex 876.634 483.189 21.165 + vertex 878.97 474.126 21.7198 + endloop + endfacet + facet normal 0.25321 0.0914344 0.963081 + outer loop + vertex 894.97 437.523 21.0592 + vertex 891.671 446.602 21.0648 + vertex 892.633 437.872 21.6407 + endloop + endfacet + facet normal 0.252551 0.0858605 0.963767 + outer loop + vertex 895.669 428.849 21.6489 + vertex 894.97 437.523 21.0592 + vertex 892.633 437.872 21.6407 + endloop + endfacet + facet normal 0.245349 0.0854094 0.965665 + outer loop + vertex 898.178 428.411 21.0501 + vertex 894.97 437.523 21.0592 + vertex 895.669 428.849 21.6489 + endloop + endfacet + facet normal 0.244536 0.0798128 0.96635 + outer loop + vertex 898.618 419.782 21.6515 + vertex 898.178 428.411 21.0501 + vertex 895.669 428.849 21.6489 + endloop + endfacet + facet normal 0.235711 0.0795173 0.968565 + outer loop + vertex 901.277 419.283 21.0455 + vertex 898.178 428.411 21.0501 + vertex 898.618 419.782 21.6515 + endloop + endfacet + facet normal 0.234623 0.0727558 0.96936 + outer loop + vertex 901.449 410.673 21.6499 + vertex 901.277 419.283 21.0455 + vertex 898.618 419.782 21.6515 + endloop + endfacet + facet normal 0.224983 0.0727231 0.971645 + outer loop + vertex 904.237 410.135 21.0446 + vertex 901.277 419.283 21.0455 + vertex 901.449 410.673 21.6499 + endloop + endfacet + facet normal 0.223717 0.0652424 0.972468 + outer loop + vertex 904.136 401.53 21.6454 + vertex 904.237 410.135 21.0446 + vertex 901.449 410.673 21.6499 + endloop + endfacet + facet normal 0.21619 0.0654493 0.974155 + outer loop + vertex 907.037 400.937 21.0412 + vertex 904.237 410.135 21.0446 + vertex 904.136 401.53 21.6454 + endloop + endfacet + facet normal 0.214693 0.0572573 0.975002 + outer loop + vertex 906.651 392.328 21.6318 + vertex 907.037 400.937 21.0412 + vertex 904.136 401.53 21.6454 + endloop + endfacet + facet normal 0.210189 0.0575256 0.975967 + outer loop + vertex 909.677 391.635 21.0209 + vertex 907.037 400.937 21.0412 + vertex 906.651 392.328 21.6318 + endloop + endfacet + facet normal 0.208494 0.0494077 0.976775 + outer loop + vertex 908.979 383.043 21.6046 + vertex 909.677 391.635 21.0209 + vertex 906.651 392.328 21.6318 + endloop + endfacet + facet normal 0.206996 0.0495506 0.977086 + outer loop + vertex 912.138 382.201 20.978 + vertex 909.677 391.635 21.0209 + vertex 908.979 383.043 21.6046 + endloop + endfacet + facet normal 0.205083 0.0418001 0.977851 + outer loop + vertex 911.077 373.679 21.5649 + vertex 912.138 382.201 20.978 + vertex 908.979 383.043 21.6046 + endloop + endfacet + facet normal 0.204246 0.0419161 0.978022 + outer loop + vertex 914.373 372.642 20.921 + vertex 912.138 382.201 20.978 + vertex 911.077 373.679 21.5649 + endloop + endfacet + facet normal 0.201941 0.0341032 0.978804 + outer loop + vertex 912.92 364.216 21.5143 + vertex 914.373 372.642 20.921 + vertex 911.077 373.679 21.5649 + endloop + endfacet + facet normal 0.199354 0.0345852 0.979317 + outer loop + vertex 916.32 363.013 20.8647 + vertex 914.373 372.642 20.921 + vertex 912.92 364.216 21.5143 + endloop + endfacet + facet normal 0.196326 0.0255464 0.980206 + outer loop + vertex 914.471 354.633 21.4535 + vertex 916.32 363.013 20.8647 + vertex 912.92 364.216 21.5143 + endloop + endfacet + facet normal 0.191002 0.0267929 0.981224 + outer loop + vertex 917.954 353.465 20.8073 + vertex 916.32 363.013 20.8647 + vertex 914.471 354.633 21.4535 + endloop + endfacet + facet normal 0.187451 0.0156939 0.982149 + outer loop + vertex 915.845 345.398 21.3389 + vertex 917.954 353.465 20.8073 + vertex 914.471 354.633 21.4535 + endloop + endfacet + facet normal 0.183542 0.0167637 0.982869 + outer loop + vertex 919.208 344.098 20.7329 + vertex 917.954 353.465 20.8073 + vertex 915.845 345.398 21.3389 + endloop + endfacet + facet normal 0.179094 0.00481371 0.98382 + outer loop + vertex 916.752 336.723 21.2162 + vertex 919.208 344.098 20.7329 + vertex 915.845 345.398 21.3389 + endloop + endfacet + facet normal 0.175012 0.00622135 0.984547 + outer loop + vertex 920.001 334.67 20.6515 + vertex 919.208 344.098 20.7329 + vertex 916.752 336.723 21.2162 + endloop + endfacet + facet normal 0.167637 -0.00580657 0.985832 + outer loop + vertex 916.67 327.484 21.1757 + vertex 920.001 334.67 20.6515 + vertex 916.752 336.723 21.2162 + endloop + endfacet + facet normal 0.16378 -0.00397022 0.986489 + outer loop + vertex 920.424 324.923 20.5421 + vertex 920.001 334.67 20.6515 + vertex 916.67 327.484 21.1757 + endloop + endfacet + facet normal 0.195936 -0.00251022 0.980613 + outer loop + vertex 920.424 324.923 20.5421 + vertex 923.62 332.46 19.9227 + vertex 920.001 334.67 20.6515 + endloop + endfacet + facet normal 0.204045 0.0113361 0.978896 + outer loop + vertex 923.62 332.46 19.9227 + vertex 922.647 342.36 20.011 + vertex 920.001 334.67 20.6515 + endloop + endfacet + facet normal 0.209913 0.00921624 0.977677 + outer loop + vertex 920.001 334.67 20.6515 + vertex 922.647 342.36 20.011 + vertex 919.208 344.098 20.7329 + endloop + endfacet + facet normal 0.21682 0.0236122 0.975926 + outer loop + vertex 922.647 342.36 20.011 + vertex 921.321 352.022 20.0717 + vertex 919.208 344.098 20.7329 + endloop + endfacet + facet normal 0.222381 0.022028 0.974711 + outer loop + vertex 919.208 344.098 20.7329 + vertex 921.321 352.022 20.0717 + vertex 917.954 353.465 20.8073 + endloop + endfacet + facet normal 0.227562 0.0349235 0.973137 + outer loop + vertex 921.321 352.022 20.0717 + vertex 919.614 361.702 20.1235 + vertex 917.954 353.465 20.8073 + endloop + endfacet + facet normal 0.232202 0.0339005 0.972077 + outer loop + vertex 917.954 353.465 20.8073 + vertex 919.614 361.702 20.1235 + vertex 916.32 363.013 20.8647 + endloop + endfacet + facet normal 0.236371 0.0452075 0.970611 + outer loop + vertex 919.614 361.702 20.1235 + vertex 917.529 371.508 20.1747 + vertex 916.32 363.013 20.8647 + endloop + endfacet + facet normal 0.244816 0.0438406 0.968578 + outer loop + vertex 916.32 363.013 20.8647 + vertex 917.529 371.508 20.1747 + vertex 914.373 372.642 20.921 + endloop + endfacet + facet normal 0.248681 0.055639 0.966986 + outer loop + vertex 917.529 371.508 20.1747 + vertex 915.089 381.311 20.238 + vertex 914.373 372.642 20.921 + endloop + endfacet + facet normal 0.258352 0.0546442 0.964504 + outer loop + vertex 914.373 372.642 20.921 + vertex 915.089 381.311 20.238 + vertex 912.138 382.201 20.978 + endloop + endfacet + facet normal 0.261397 0.0660075 0.962972 + outer loop + vertex 915.089 381.311 20.238 + vertex 912.405 390.974 20.3044 + vertex 912.138 382.201 20.978 + endloop + endfacet + facet normal 0.268422 0.0656475 0.961062 + outer loop + vertex 912.138 382.201 20.978 + vertex 912.405 390.974 20.3044 + vertex 909.677 391.635 21.0209 + endloop + endfacet + facet normal 0.27077 0.0769513 0.959564 + outer loop + vertex 912.405 390.974 20.3044 + vertex 909.572 400.454 20.3435 + vertex 909.677 391.635 21.0209 + endloop + endfacet + facet normal 0.278228 0.0768769 0.957433 + outer loop + vertex 909.677 391.635 21.0209 + vertex 909.572 400.454 20.3435 + vertex 907.037 400.937 21.0412 + endloop + endfacet + facet normal 0.280008 0.0883889 0.95592 + outer loop + vertex 909.572 400.454 20.3435 + vertex 906.606 409.753 20.3523 + vertex 907.037 400.937 21.0412 + endloop + endfacet + facet normal 0.29256 0.0887061 0.952124 + outer loop + vertex 907.037 400.937 21.0412 + vertex 906.606 409.753 20.3523 + vertex 904.237 410.135 21.0446 + endloop + endfacet + facet normal 0.293824 0.0991411 0.950704 + outer loop + vertex 906.606 409.753 20.3523 + vertex 903.496 418.959 20.3535 + vertex 904.237 410.135 21.0446 + endloop + endfacet + facet normal 0.309431 0.100056 0.945643 + outer loop + vertex 904.237 410.135 21.0446 + vertex 903.496 418.959 20.3535 + vertex 901.277 419.283 21.0455 + endloop + endfacet + facet normal 0.310309 0.108742 0.944396 + outer loop + vertex 903.496 418.959 20.3535 + vertex 900.229 428.166 20.367 + vertex 901.277 419.283 21.0455 + endloop + endfacet + facet normal 0.325989 0.110174 0.938932 + outer loop + vertex 901.277 419.283 21.0455 + vertex 900.229 428.166 20.367 + vertex 898.178 428.411 21.0501 + endloop + endfacet + facet normal 0.326464 0.116829 0.937962 + outer loop + vertex 900.229 428.166 20.367 + vertex 896.828 437.402 20.4002 + vertex 898.178 428.411 21.0501 + endloop + endfacet + facet normal 0.338836 0.118355 0.933371 + outer loop + vertex 898.178 428.411 21.0501 + vertex 896.828 437.402 20.4002 + vertex 894.97 437.523 21.0592 + endloop + endfacet + facet normal 0.338963 0.125923 0.932334 + outer loop + vertex 896.828 437.402 20.4002 + vertex 893.302 446.619 20.4371 + vertex 894.97 437.523 21.0592 + endloop + endfacet + facet normal 0.354887 0.128413 0.926048 + outer loop + vertex 894.97 437.523 21.0592 + vertex 893.302 446.619 20.4371 + vertex 891.671 446.602 21.0648 + endloop + endfacet + facet normal 0.354338 0.138029 0.924875 + outer loop + vertex 893.302 446.619 20.4371 + vertex 889.68 455.75 20.4623 + vertex 891.671 446.602 21.0648 + endloop + endfacet + facet normal 0.372955 0.141561 0.916987 + outer loop + vertex 891.671 446.602 21.0648 + vertex 889.68 455.75 20.4623 + vertex 888.237 455.65 21.0647 + endloop + endfacet + facet normal 0.371373 0.155081 0.915441 + outer loop + vertex 889.68 455.75 20.4623 + vertex 885.881 464.807 20.4691 + vertex 888.237 455.65 21.0647 + endloop + endfacet + facet normal 0.402821 0.162218 0.900789 + outer loop + vertex 888.237 455.65 21.0647 + vertex 885.881 464.807 20.4691 + vertex 884.561 464.707 21.0774 + endloop + endfacet + facet normal 0.400537 0.179046 0.898617 + outer loop + vertex 885.881 464.807 20.4691 + vertex 881.807 473.905 20.4722 + vertex 884.561 464.707 21.0774 + endloop + endfacet + facet normal 0.182778 0.0032788 0.983149 + outer loop + vertex 924.31 321.898 19.8297 + vertex 923.62 332.46 19.9227 + vertex 920.424 324.923 20.5421 + endloop + endfacet + facet normal 0.171456 -0.011728 0.985122 + outer loop + vertex 920.581 315.001 20.3966 + vertex 924.31 321.898 19.8297 + vertex 920.424 324.923 20.5421 + endloop + endfacet + facet normal 0.148295 -0.0121498 0.988869 + outer loop + vertex 920.581 315.001 20.3966 + vertex 920.424 324.923 20.5421 + vertex 916.507 318.065 21.0452 + endloop + endfacet + facet normal 0.132781 0.0096764 0.991098 + outer loop + vertex 923.52 315.554 19.9975 + vertex 924.31 321.898 19.8297 + vertex 920.581 315.001 20.3966 + endloop + endfacet + facet normal 0.137913 -0.0182261 0.990277 + outer loop + vertex 923.52 315.554 19.9975 + vertex 920.581 315.001 20.3966 + vertex 922.899 310.334 19.988 + endloop + endfacet + facet normal 0.183685 -0.0236591 0.9827 + outer loop + vertex 922.899 310.334 19.988 + vertex 925.367 314.845 19.6352 + vertex 923.52 315.554 19.9975 + endloop + endfacet + facet normal 0.175141 -0.0188542 0.984363 + outer loop + vertex 925.093 308.251 19.5576 + vertex 925.367 314.845 19.6352 + vertex 922.899 310.334 19.988 + endloop + endfacet + facet normal 0.158914 -0.0364184 0.98662 + outer loop + vertex 922.066 302.722 19.8411 + vertex 925.093 308.251 19.5576 + vertex 922.899 310.334 19.988 + endloop + endfacet + facet normal 0.134562 -0.0338265 0.990328 + outer loop + vertex 922.066 302.722 19.8411 + vertex 922.899 310.334 19.988 + vertex 919.14 305.54 20.3349 + endloop + endfacet + facet normal 0.126973 -0.0418285 0.991024 + outer loop + vertex 917.694 296.807 20.1516 + vertex 922.066 302.722 19.8411 + vertex 919.14 305.54 20.3349 + endloop + endfacet + facet normal 0.127933 -0.0419847 0.990894 + outer loop + vertex 917.694 296.807 20.1516 + vertex 919.14 305.54 20.3349 + vertex 914.34 299.895 20.7155 + endloop + endfacet + facet normal 0.134161 -0.0472038 0.989835 + outer loop + vertex 921.112 294.315 19.5695 + vertex 922.066 302.722 19.8411 + vertex 917.694 296.807 20.1516 + endloop + endfacet + facet normal 0.129667 -0.0534337 0.990117 + outer loop + vertex 915.707 287.872 19.9296 + vertex 921.112 294.315 19.5695 + vertex 917.694 296.807 20.1516 + endloop + endfacet + facet normal 0.120564 -0.0514404 0.991372 + outer loop + vertex 915.707 287.872 19.9296 + vertex 917.694 296.807 20.1516 + vertex 912.288 291.072 20.5114 + endloop + endfacet + facet normal 0.125607 -0.0499882 0.99082 + outer loop + vertex 919.414 284.784 19.3039 + vertex 921.112 294.315 19.5695 + vertex 915.707 287.872 19.9296 + endloop + endfacet + facet normal 0.118067 -0.0591243 0.991244 + outer loop + vertex 912.838 278.856 19.7336 + vertex 919.414 284.784 19.3039 + vertex 915.707 287.872 19.9296 + endloop + endfacet + facet normal 0.110236 -0.0566547 0.992289 + outer loop + vertex 912.838 278.856 19.7336 + vertex 915.707 287.872 19.9296 + vertex 909.543 282.266 20.2943 + endloop + endfacet + facet normal 0.112155 -0.0524887 0.992303 + outer loop + vertex 915.726 275.372 19.2229 + vertex 919.414 284.784 19.3039 + vertex 912.838 278.856 19.7336 + endloop + endfacet + facet normal 0.100447 -0.0622948 0.99299 + outer loop + vertex 909.308 270.26 19.5514 + vertex 915.726 275.372 19.2229 + vertex 912.838 278.856 19.7336 + endloop + endfacet + facet normal 0.0984997 -0.0615003 0.993235 + outer loop + vertex 909.308 270.26 19.5514 + vertex 912.838 278.856 19.7336 + vertex 906.173 273.736 20.0776 + endloop + endfacet + facet normal 0.101249 -0.0633109 0.992845 + outer loop + vertex 912.467 267.045 19.0243 + vertex 915.726 275.372 19.2229 + vertex 909.308 270.26 19.5514 + endloop + endfacet + facet normal 0.0950594 -0.0694263 0.993048 + outer loop + vertex 905.42 262.114 19.3541 + vertex 912.467 267.045 19.0243 + vertex 909.308 270.26 19.5514 + endloop + endfacet + facet normal 0.0880132 -0.0660842 0.993925 + outer loop + vertex 905.42 262.114 19.3541 + vertex 909.308 270.26 19.5514 + vertex 902.342 265.674 19.8634 + endloop + endfacet + facet normal 0.0937673 -0.0675628 0.993299 + outer loop + vertex 908.616 258.655 18.8171 + vertex 912.467 267.045 19.0243 + vertex 905.42 262.114 19.3541 + endloop + endfacet + facet normal 0.0881093 -0.0728129 0.993446 + outer loop + vertex 901.032 254.195 19.1628 + vertex 908.616 258.655 18.8171 + vertex 905.42 262.114 19.3541 + endloop + endfacet + facet normal 0.0789761 -0.06778 0.99457 + outer loop + vertex 901.032 254.195 19.1628 + vertex 905.42 262.114 19.3541 + vertex 898.103 257.995 19.6544 + endloop + endfacet + facet normal 0.0849893 -0.0674566 0.994096 + outer loop + vertex 903.971 250.354 18.6509 + vertex 908.616 258.655 18.8171 + vertex 901.032 254.195 19.1628 + endloop + endfacet + facet normal 0.0784549 -0.0724797 0.994279 + outer loop + vertex 896.125 246.451 18.9855 + vertex 903.971 250.354 18.6509 + vertex 901.032 254.195 19.1628 + endloop + endfacet + facet normal 0.0709866 -0.0677675 0.995173 + outer loop + vertex 896.125 246.451 18.9855 + vertex 901.032 254.195 19.1628 + vertex 893.4 250.508 19.4562 + endloop + endfacet + facet normal 0.0759575 -0.0674115 0.99483 + outer loop + vertex 898.866 242.378 18.5003 + vertex 903.971 250.354 18.6509 + vertex 896.125 246.451 18.9855 + endloop + endfacet + facet normal 0.0699968 -0.0714407 0.994986 + outer loop + vertex 890.718 238.865 18.8212 + vertex 898.866 242.378 18.5003 + vertex 896.125 246.451 18.9855 + endloop + endfacet + facet normal 0.0643229 -0.0674108 0.99565 + outer loop + vertex 890.718 238.865 18.8212 + vertex 896.125 246.451 18.9855 + vertex 888.216 243.131 19.2717 + endloop + endfacet + facet normal 0.0677948 -0.0662875 0.995495 + outer loop + vertex 893.249 234.572 18.363 + vertex 898.866 242.378 18.5003 + vertex 890.718 238.865 18.8212 + endloop + endfacet + facet normal 0.0634678 -0.0688509 0.995606 + outer loop + vertex 884.888 231.453 18.6803 + vertex 893.249 234.572 18.363 + vertex 890.718 238.865 18.8212 + endloop + endfacet + facet normal 0.0587478 -0.0651484 0.996145 + outer loop + vertex 884.888 231.453 18.6803 + vertex 890.718 238.865 18.8212 + vertex 882.592 235.897 19.1063 + endloop + endfacet + facet normal 0.0615741 -0.0637283 0.996066 + outer loop + vertex 887.26 226.972 18.2469 + vertex 893.249 234.572 18.363 + vertex 884.888 231.453 18.6803 + endloop + endfacet + facet normal 0.0594117 -0.0648786 0.996123 + outer loop + vertex 879.037 224.386 18.569 + vertex 887.26 226.972 18.2469 + vertex 884.888 231.453 18.6803 + endloop + endfacet + facet normal 0.0554678 -0.06162 0.996557 + outer loop + vertex 879.037 224.386 18.569 + vertex 884.888 231.453 18.6803 + vertex 876.664 228.898 18.98 + endloop + endfacet + facet normal 0.0580695 -0.0605655 0.996474 + outer loop + vertex 881.389 219.798 18.1531 + vertex 887.26 226.972 18.2469 + vertex 879.037 224.386 18.569 + endloop + endfacet + facet normal 0.0575862 -0.0608144 0.996487 + outer loop + vertex 873.878 217.789 18.4645 + vertex 881.389 219.798 18.1531 + vertex 879.037 224.386 18.569 + endloop + endfacet + facet normal 0.0566138 -0.0571371 0.99676 + outer loop + vertex 876.29 213.328 18.0718 + vertex 881.389 219.798 18.1531 + vertex 873.878 217.789 18.4645 + endloop + endfacet + facet normal 0.0771484 -0.0732896 0.994322 + outer loop + vertex 876.29 213.328 18.0718 + vertex 883.499 214.984 17.6345 + vertex 881.389 219.798 18.1531 + endloop + endfacet + facet normal 0.0770428 -0.0733364 0.994327 + outer loop + vertex 883.499 214.984 17.6345 + vertex 889.651 222.328 17.6996 + vertex 881.389 219.798 18.1531 + endloop + endfacet + facet normal 0.0770554 -0.0728745 0.99436 + outer loop + vertex 877.98 208.674 17.5997 + vertex 883.499 214.984 17.6345 + vertex 876.29 213.328 18.0718 + endloop + endfacet + facet normal 0.0781018 -0.0724893 0.994306 + outer loop + vertex 872.686 208.214 17.982 + vertex 877.98 208.674 17.5997 + vertex 876.29 213.328 18.0718 + endloop + endfacet + facet normal 0.0568036 -0.0575232 0.996727 + outer loop + vertex 872.686 208.214 17.982 + vertex 876.29 213.328 18.0718 + vertex 869.886 211.349 18.3225 + endloop + endfacet + facet normal 0.0784814 -0.0771793 0.993924 + outer loop + vertex 873.155 203.971 17.6155 + vertex 877.98 208.674 17.5997 + vertex 872.686 208.214 17.982 + endloop + endfacet + facet normal 0.0702528 -0.0781351 0.994464 + outer loop + vertex 873.155 203.971 17.6155 + vertex 872.686 208.214 17.982 + vertex 866.924 204.024 18.0599 + endloop + endfacet + facet normal 0.0701522 -0.0851588 0.993895 + outer loop + vertex 866.924 204.024 18.0599 + vertex 869.356 198.16 17.3858 + vertex 873.155 203.971 17.6155 + endloop + endfacet + facet normal 0.0781301 -0.0769507 0.993969 + outer loop + vertex 881.389 219.798 18.1531 + vertex 889.651 222.328 17.6996 + vertex 887.26 226.972 18.2469 + endloop + endfacet + facet normal 0.0809943 -0.0754627 0.993854 + outer loop + vertex 889.651 222.328 17.6996 + vertex 895.856 230.178 17.7898 + vertex 887.26 226.972 18.2469 + endloop + endfacet + facet normal 0.0828149 -0.0804209 0.993315 + outer loop + vertex 887.26 226.972 18.2469 + vertex 895.856 230.178 17.7898 + vertex 893.249 234.572 18.363 + endloop + endfacet + facet normal 0.0882659 -0.0771591 0.993104 + outer loop + vertex 895.856 230.178 17.7898 + vertex 901.674 238.231 17.8985 + vertex 893.249 234.572 18.363 + endloop + endfacet + facet normal 0.0906174 -0.0826577 0.99245 + outer loop + vertex 893.249 234.572 18.363 + vertex 901.674 238.231 17.8985 + vertex 898.866 242.378 18.5003 + endloop + endfacet + facet normal 0.0973396 -0.0780683 0.992185 + outer loop + vertex 901.674 238.231 17.8985 + vertex 906.93 246.36 18.0224 + vertex 898.866 242.378 18.5003 + endloop + endfacet + facet normal 0.0994355 -0.0823796 0.991628 + outer loop + vertex 898.866 242.378 18.5003 + vertex 906.93 246.36 18.0224 + vertex 903.971 250.354 18.6509 + endloop + endfacet + facet normal 0.108236 -0.075797 0.991231 + outer loop + vertex 906.93 246.36 18.0224 + vertex 911.724 254.828 18.1465 + vertex 903.971 250.354 18.6509 + endloop + endfacet + facet normal 0.112057 -0.0825267 0.990269 + outer loop + vertex 903.971 250.354 18.6509 + vertex 911.724 254.828 18.1465 + vertex 908.616 258.655 18.8171 + endloop + endfacet + facet normal 0.121361 -0.0748841 0.98978 + outer loop + vertex 911.724 254.828 18.1465 + vertex 916.499 264.472 18.2906 + vertex 908.616 258.655 18.8171 + endloop + endfacet + facet normal 0.127054 -0.0827191 0.988441 + outer loop + vertex 908.616 258.655 18.8171 + vertex 916.499 264.472 18.2906 + vertex 912.467 267.045 19.0243 + endloop + endfacet + facet normal 0.128841 -0.0799165 0.98844 + outer loop + vertex 916.499 264.472 18.2906 + vertex 918.424 272.606 18.6974 + vertex 912.467 267.045 19.0243 + endloop + endfacet + facet normal 0.120359 -0.0707267 0.990208 + outer loop + vertex 912.467 267.045 19.0243 + vertex 918.424 272.606 18.6974 + vertex 915.726 275.372 19.2229 + endloop + endfacet + facet normal 0.127253 -0.063927 0.989808 + outer loop + vertex 918.424 272.606 18.6974 + vertex 920.764 279.869 18.8656 + vertex 915.726 275.372 19.2229 + endloop + endfacet + facet normal 0.119818 -0.0554823 0.991244 + outer loop + vertex 919.414 284.784 19.3039 + vertex 915.726 275.372 19.2229 + vertex 920.764 279.869 18.8656 + endloop + endfacet + facet normal 0.134214 -0.0513813 0.989619 + outer loop + vertex 922.7 285.337 18.887 + vertex 919.414 284.784 19.3039 + vertex 920.764 279.869 18.8656 + endloop + endfacet + facet normal 0.130117 -0.0258815 0.991161 + outer loop + vertex 922.7 285.337 18.887 + vertex 925.481 293.044 18.7231 + vertex 919.414 284.784 19.3039 + endloop + endfacet + facet normal 0.173487 -0.0583059 0.983109 + outer loop + vertex 919.414 284.784 19.3039 + vertex 925.481 293.044 18.7231 + vertex 921.112 294.315 19.5695 + endloop + endfacet + facet normal 0.173597 -0.057929 0.983112 + outer loop + vertex 921.112 294.315 19.5695 + vertex 925.481 293.044 18.7231 + vertex 924.839 301.251 19.32 + endloop + endfacet + facet normal 0.207801 -0.0547842 0.976636 + outer loop + vertex 927.039 301.907 18.8888 + vertex 924.839 301.251 19.32 + vertex 925.481 293.044 18.7231 + endloop + endfacet + facet normal 0.260413 -0.0637844 0.963388 + outer loop + vertex 927.039 301.907 18.8888 + vertex 925.481 293.044 18.7231 + vertex 928.587 301.18 18.4223 + endloop + endfacet + facet normal 0.270798 -0.0406232 0.961779 + outer loop + vertex 928.587 301.18 18.4223 + vertex 928.757 306.807 18.6119 + vertex 927.039 301.907 18.8888 + endloop + endfacet + facet normal 0.267851 -0.0395405 0.962649 + outer loop + vertex 927.039 301.907 18.8888 + vertex 928.757 306.807 18.6119 + vertex 927.044 307.317 19.1096 + endloop + endfacet + facet normal 0.272988 -0.0214188 0.961779 + outer loop + vertex 928.757 306.807 18.6119 + vertex 928.716 312.638 18.7535 + vertex 927.044 307.317 19.1096 + endloop + endfacet + facet normal 0.276705 -0.0226595 0.960688 + outer loop + vertex 927.044 307.317 19.1096 + vertex 928.716 312.638 18.7535 + vertex 927.016 312.684 19.2442 + endloop + endfacet + facet normal 0.277347 0.000496643 0.96077 + outer loop + vertex 927.016 312.684 19.2442 + vertex 928.716 312.638 18.7535 + vertex 928.074 319.916 18.9352 + endloop + endfacet + facet normal 0.238818 0.00656892 0.971042 + outer loop + vertex 927.016 312.684 19.2442 + vertex 928.074 319.916 18.9352 + vertex 925.367 314.845 19.6352 + endloop + endfacet + facet normal 0.235453 0.00847634 0.971849 + outer loop + vertex 928.074 319.916 18.9352 + vertex 924.31 321.898 19.8297 + vertex 925.367 314.845 19.6352 + endloop + endfacet + facet normal 0.235756 0.00908742 0.97177 + outer loop + vertex 928.074 319.916 18.9352 + vertex 927.369 330.22 19.0098 + vertex 924.31 321.898 19.8297 + endloop + endfacet + facet normal 0.240656 0.00716951 0.970584 + outer loop + vertex 924.31 321.898 19.8297 + vertex 927.369 330.22 19.0098 + vertex 923.62 332.46 19.9227 + endloop + endfacet + facet normal 0.248035 0.0203553 0.968537 + outer loop + vertex 927.369 330.22 19.0098 + vertex 926.275 340.31 19.0778 + vertex 923.62 332.46 19.9227 + endloop + endfacet + facet normal 0.257902 0.016748 0.966026 + outer loop + vertex 923.62 332.46 19.9227 + vertex 926.275 340.31 19.0778 + vertex 922.647 342.36 20.011 + endloop + endfacet + facet normal 0.266893 0.0339831 0.963127 + outer loop + vertex 926.275 340.31 19.0778 + vertex 924.826 350.169 19.1315 + vertex 922.647 342.36 20.011 + endloop + endfacet + facet normal 0.274524 0.0316203 0.96106 + outer loop + vertex 922.647 342.36 20.011 + vertex 924.826 350.169 19.1315 + vertex 921.321 352.022 20.0717 + endloop + endfacet + facet normal 0.283227 0.049758 0.957761 + outer loop + vertex 924.826 350.169 19.1315 + vertex 923.001 359.947 19.1633 + vertex 921.321 352.022 20.0717 + endloop + endfacet + facet normal 0.294897 0.0468969 0.954378 + outer loop + vertex 921.321 352.022 20.0717 + vertex 923.001 359.947 19.1633 + vertex 919.614 361.702 20.1235 + endloop + endfacet + facet normal 0.302595 0.0635958 0.950995 + outer loop + vertex 923.001 359.947 19.1633 + vertex 920.767 369.874 19.2101 + vertex 919.614 361.702 20.1235 + endloop + endfacet + facet normal 0.313351 0.0617024 0.947631 + outer loop + vertex 919.614 361.702 20.1235 + vertex 920.767 369.874 19.2101 + vertex 917.529 371.508 20.1747 + endloop + endfacet + facet normal 0.322609 0.0828539 0.942899 + outer loop + vertex 920.767 369.874 19.2101 + vertex 918.18 379.975 19.2077 + vertex 917.529 371.508 20.1747 + endloop + endfacet + facet normal 0.346184 0.0801086 0.93474 + outer loop + vertex 917.529 371.508 20.1747 + vertex 918.18 379.975 19.2077 + vertex 915.089 381.311 20.238 + endloop + endfacet + facet normal 0.353935 0.101931 0.929699 + outer loop + vertex 918.18 379.975 19.2077 + vertex 915.15 389.834 19.2804 + vertex 915.089 381.311 20.238 + endloop + endfacet + facet normal 0.384021 0.100387 0.917851 + outer loop + vertex 915.089 381.311 20.238 + vertex 915.15 389.834 19.2804 + vertex 912.405 390.974 20.3044 + endloop + endfacet + facet normal 0.389945 0.118903 0.913129 + outer loop + vertex 915.15 389.834 19.2804 + vertex 912.053 399.583 19.3334 + vertex 912.405 390.974 20.3044 + endloop + endfacet + facet normal 0.409825 0.11873 0.904404 + outer loop + vertex 912.405 390.974 20.3044 + vertex 912.053 399.583 19.3334 + vertex 909.572 400.454 20.3435 + endloop + endfacet + facet normal 0.414198 0.136404 0.899908 + outer loop + vertex 912.053 399.583 19.3334 + vertex 908.874 409.071 19.3588 + vertex 909.572 400.454 20.3435 + endloop + endfacet + facet normal 0.431855 0.136874 0.891497 + outer loop + vertex 909.572 400.454 20.3435 + vertex 908.874 409.071 19.3588 + vertex 906.606 409.753 20.3523 + endloop + endfacet + facet normal 0.435071 0.153883 0.887149 + outer loop + vertex 908.874 409.071 19.3588 + vertex 905.582 418.37 19.3601 + vertex 906.606 409.753 20.3523 + endloop + endfacet + facet normal 0.460229 0.155372 0.874099 + outer loop + vertex 906.606 409.753 20.3523 + vertex 905.582 418.37 19.3601 + vertex 903.496 418.959 20.3535 + endloop + endfacet + facet normal 0.462636 0.170975 0.869905 + outer loop + vertex 905.582 418.37 19.3601 + vertex 902.138 427.638 19.37 + vertex 903.496 418.959 20.3535 + endloop + endfacet + facet normal 0.493163 0.173769 0.852405 + outer loop + vertex 903.496 418.959 20.3535 + vertex 902.138 427.638 19.37 + vertex 900.229 428.166 20.367 + endloop + endfacet + facet normal 0.495019 0.188434 0.848204 + outer loop + vertex 902.138 427.638 19.37 + vertex 898.516 437.018 19.3998 + vertex 900.229 428.166 20.367 + endloop + endfacet + facet normal 0.53232 0.193031 0.824242 + outer loop + vertex 900.229 428.166 20.367 + vertex 898.516 437.018 19.3998 + vertex 896.828 437.402 20.4002 + endloop + endfacet + facet normal 0.533297 0.209504 0.819574 + outer loop + vertex 898.516 437.018 19.3998 + vertex 894.743 446.437 19.4475 + vertex 896.828 437.402 20.4002 + endloop + endfacet + facet normal 0.571349 0.215372 0.791944 + outer loop + vertex 896.828 437.402 20.4002 + vertex 894.743 446.437 19.4475 + vertex 893.302 446.619 20.4371 + endloop + endfacet + facet normal 0.570585 0.232187 0.787732 + outer loop + vertex 894.743 446.437 19.4475 + vertex 890.872 455.754 19.5048 + vertex 893.302 446.619 20.4371 + endloop + endfacet + facet normal 0.318723 0.00447163 0.947838 + outer loop + vertex 928.716 312.638 18.7535 + vertex 930.413 317.215 18.1613 + vertex 928.074 319.916 18.9352 + endloop + endfacet + facet normal 0.319934 0.00563973 0.947423 + outer loop + vertex 930.536 322.281 18.0896 + vertex 928.074 319.916 18.9352 + vertex 930.413 317.215 18.1613 + endloop + endfacet + facet normal 0.315801 0.010423 0.948768 + outer loop + vertex 930.536 322.281 18.0896 + vertex 929.898 327.043 18.2496 + vertex 928.074 319.916 18.9352 + endloop + endfacet + facet normal 0.303769 0.0138762 0.952645 + outer loop + vertex 927.369 330.22 19.0098 + vertex 928.074 319.916 18.9352 + vertex 929.898 327.043 18.2496 + endloop + endfacet + facet normal 0.312719 0.0217294 0.949597 + outer loop + vertex 929.742 332.38 18.179 + vertex 927.369 330.22 19.0098 + vertex 929.898 327.043 18.2496 + endloop + endfacet + facet normal 0.308409 0.0269558 0.950872 + outer loop + vertex 929.742 332.38 18.179 + vertex 928.883 337.135 18.3228 + vertex 927.369 330.22 19.0098 + endloop + endfacet + facet normal 0.308236 0.0269991 0.950927 + outer loop + vertex 926.275 340.31 19.0778 + vertex 927.369 330.22 19.0098 + vertex 928.883 337.135 18.3228 + endloop + endfacet + facet normal 0.324158 0.0414598 0.945094 + outer loop + vertex 928.491 342.373 18.2274 + vertex 926.275 340.31 19.0778 + vertex 928.883 337.135 18.3228 + endloop + endfacet + facet normal 0.320612 0.0456859 0.946108 + outer loop + vertex 928.491 342.373 18.2274 + vertex 927.438 347.061 18.3577 + vertex 926.275 340.31 19.0778 + endloop + endfacet + facet normal 0.33102 0.043521 0.942619 + outer loop + vertex 924.826 350.169 19.1315 + vertex 926.275 340.31 19.0778 + vertex 927.438 347.061 18.3577 + endloop + endfacet + facet normal 0.351072 0.0624535 0.934264 + outer loop + vertex 926.812 352.235 18.2472 + vertex 924.826 350.169 19.1315 + vertex 927.438 347.061 18.3577 + endloop + endfacet + facet normal 0.34939 0.0642863 0.934769 + outer loop + vertex 926.812 352.235 18.2472 + vertex 925.607 356.871 18.3788 + vertex 924.826 350.169 19.1315 + endloop + endfacet + facet normal 0.355472 0.0633272 0.932539 + outer loop + vertex 923.001 359.947 19.1633 + vertex 924.826 350.169 19.1315 + vertex 925.607 356.871 18.3788 + endloop + endfacet + facet normal 0.373959 0.0811967 0.923884 + outer loop + vertex 924.781 362.012 18.2613 + vertex 923.001 359.947 19.1633 + vertex 925.607 356.871 18.3788 + endloop + endfacet + facet normal 0.371893 0.0832624 0.924534 + outer loop + vertex 924.781 362.012 18.2613 + vertex 923.395 366.714 18.3955 + vertex 923.001 359.947 19.1633 + endloop + endfacet + facet normal 0.383847 0.0820236 0.919746 + outer loop + vertex 920.767 369.874 19.2101 + vertex 923.001 359.947 19.1633 + vertex 923.395 366.714 18.3955 + endloop + endfacet + facet normal 0.401304 0.0988941 0.910591 + outer loop + vertex 922.292 372.023 18.3046 + vertex 920.767 369.874 19.2101 + vertex 923.395 366.714 18.3955 + endloop + endfacet + facet normal 0.400283 0.0997675 0.910944 + outer loop + vertex 922.292 372.023 18.3046 + vertex 920.678 376.856 18.4845 + vertex 920.767 369.874 19.2101 + endloop + endfacet + facet normal 0.389955 0.100097 0.915378 + outer loop + vertex 918.18 379.975 19.2077 + vertex 920.767 369.874 19.2101 + vertex 920.678 376.856 18.4845 + endloop + endfacet + facet normal 0.410097 0.118806 0.904271 + outer loop + vertex 919.448 381.622 18.4163 + vertex 918.18 379.975 19.2077 + vertex 920.678 376.856 18.4845 + endloop + endfacet + facet normal 0.367298 0.157699 0.916637 + outer loop + vertex 919.448 381.622 18.4163 + vertex 918.111 387.923 17.8683 + vertex 918.18 379.975 19.2077 + endloop + endfacet + facet normal 0.501974 0.148005 0.852125 + outer loop + vertex 918.18 379.975 19.2077 + vertex 918.111 387.923 17.8683 + vertex 915.15 389.834 19.2804 + endloop + endfacet + facet normal 0.511382 0.169739 0.842424 + outer loop + vertex 918.111 387.923 17.8683 + vertex 914.722 398.112 17.8722 + vertex 915.15 389.834 19.2804 + endloop + endfacet + facet normal 0.543033 0.168023 0.822729 + outer loop + vertex 915.15 389.834 19.2804 + vertex 914.722 398.112 17.8722 + vertex 912.053 399.583 19.3334 + endloop + endfacet + facet normal 0.550339 0.191184 0.812758 + outer loop + vertex 914.722 398.112 17.8722 + vertex 911.305 407.827 17.9006 + vertex 912.053 399.583 19.3334 + endloop + endfacet + facet normal 0.574674 0.190464 0.79591 + outer loop + vertex 912.053 399.583 19.3334 + vertex 911.305 407.827 17.9006 + vertex 908.874 409.071 19.3588 + endloop + endfacet + facet normal 0.580575 0.21417 0.785534 + outer loop + vertex 911.305 407.827 17.9006 + vertex 907.8 417.289 17.9113 + vertex 908.874 409.071 19.3588 + endloop + endfacet + facet normal 0.605069 0.214078 0.766852 + outer loop + vertex 908.874 409.071 19.3588 + vertex 907.8 417.289 17.9113 + vertex 905.582 418.37 19.3601 + endloop + endfacet + facet normal 0.609479 0.236872 0.756589 + outer loop + vertex 907.8 417.289 17.9113 + vertex 904.196 426.572 17.9087 + vertex 905.582 418.37 19.3601 + endloop + endfacet + facet normal 0.641197 0.237473 0.729707 + outer loop + vertex 905.582 418.37 19.3601 + vertex 904.196 426.572 17.9087 + vertex 902.138 427.638 19.37 + endloop + endfacet + facet normal 0.644545 0.25725 0.719989 + outer loop + vertex 904.196 426.572 17.9087 + vertex 900.397 435.99 17.9448 + vertex 902.138 427.638 19.37 + endloop + endfacet + facet normal 0.347135 -0.00736399 0.937786 + outer loop + vertex 930.467 311.523 18.0966 + vertex 930.413 317.215 18.1613 + vertex 928.716 312.638 18.7535 + endloop + endfacet + facet normal 0.339757 -0.0204224 0.940292 + outer loop + vertex 928.757 306.807 18.6119 + vertex 930.467 311.523 18.0966 + vertex 928.716 312.638 18.7535 + endloop + endfacet + facet normal 0.343394 -0.0218891 0.938936 + outer loop + vertex 930.383 306.208 18.0033 + vertex 930.467 311.523 18.0966 + vertex 928.757 306.807 18.6119 + endloop + endfacet + facet normal 0.336669 -0.041911 0.94069 + outer loop + vertex 928.587 301.18 18.4223 + vertex 930.383 306.208 18.0033 + vertex 928.757 306.807 18.6119 + endloop + endfacet + facet normal 0.318447 -0.0348487 0.9473 + outer loop + vertex 930.348 302.085 17.8635 + vertex 930.383 306.208 18.0033 + vertex 928.587 301.18 18.4223 + endloop + endfacet + facet normal 0.326712 -0.0532068 0.943625 + outer loop + vertex 930.348 302.085 17.8635 + vertex 928.587 301.18 18.4223 + vertex 929.29 297.478 17.97 + endloop + endfacet + facet normal 0.267568 -0.0665951 0.961235 + outer loop + vertex 929.29 297.478 17.97 + vertex 928.587 301.18 18.4223 + vertex 925.481 293.044 18.7231 + endloop + endfacet + facet normal 0.252184 -0.0525288 0.966253 + outer loop + vertex 928.703 292.944 17.8767 + vertex 929.29 297.478 17.97 + vertex 925.481 293.044 18.7231 + endloop + endfacet + facet normal 0.25213 -0.0538008 0.966197 + outer loop + vertex 928.703 292.944 17.8767 + vertex 925.481 293.044 18.7231 + vertex 927.419 288.112 17.9427 + endloop + endfacet + facet normal 0.246412 -0.0562589 0.967531 + outer loop + vertex 924.378 284.264 18.4934 + vertex 927.419 288.112 17.9427 + vertex 925.481 293.044 18.7231 + endloop + endfacet + facet normal 0.197339 -0.0503979 0.979039 + outer loop + vertex 922.7 285.337 18.887 + vertex 924.378 284.264 18.4934 + vertex 925.481 293.044 18.7231 + endloop + endfacet + facet normal 0.185417 -0.0694717 0.980201 + outer loop + vertex 920.764 279.869 18.8656 + vertex 924.378 284.264 18.4934 + vertex 922.7 285.337 18.887 + endloop + endfacet + facet normal 0.180546 -0.0653647 0.981392 + outer loop + vertex 922.801 277.854 18.3567 + vertex 924.378 284.264 18.4934 + vertex 920.764 279.869 18.8656 + endloop + endfacet + facet normal 0.169087 -0.0772397 0.98257 + outer loop + vertex 918.424 272.606 18.6974 + vertex 922.801 277.854 18.3567 + vertex 920.764 279.869 18.8656 + endloop + endfacet + facet normal 0.171558 -0.0793392 0.981974 + outer loop + vertex 921.418 272.069 18.1309 + vertex 922.801 277.854 18.3567 + vertex 918.424 272.606 18.6974 + endloop + endfacet + facet normal 0.169686 -0.0892303 0.98145 + outer loop + vertex 918.424 272.606 18.6974 + vertex 916.499 264.472 18.2906 + vertex 921.418 272.069 18.1309 + endloop + endfacet + facet normal 0.200925 -0.109624 0.973454 + outer loop + vertex 921.623 268.441 17.6801 + vertex 921.418 272.069 18.1309 + vertex 916.499 264.472 18.2906 + endloop + endfacet + facet normal 0.188176 -0.0925024 0.977769 + outer loop + vertex 919.901 264.027 17.5937 + vertex 921.623 268.441 17.6801 + vertex 916.499 264.472 18.2906 + endloop + endfacet + facet normal 0.187952 -0.0940506 0.977665 + outer loop + vertex 919.901 264.027 17.5937 + vertex 916.499 264.472 18.2906 + vertex 917.295 259.424 17.652 + endloop + endfacet + facet normal 0.167648 -0.0976719 0.980997 + outer loop + vertex 916.499 264.472 18.2906 + vertex 911.724 254.828 18.1465 + vertex 917.295 259.424 17.652 + endloop + endfacet + facet normal 0.166424 -0.0961497 0.981355 + outer loop + vertex 915.538 254.885 17.5052 + vertex 917.295 259.424 17.652 + vertex 911.724 254.828 18.1465 + endloop + endfacet + facet normal 0.166423 -0.0963698 0.981334 + outer loop + vertex 915.538 254.885 17.5052 + vertex 911.724 254.828 18.1465 + vertex 912.792 250.574 17.5475 + endloop + endfacet + facet normal 0.151772 -0.100328 0.98331 + outer loop + vertex 911.724 254.828 18.1465 + vertex 906.93 246.36 18.0224 + vertex 912.792 250.574 17.5475 + endloop + endfacet + facet normal 0.152154 -0.100872 0.983196 + outer loop + vertex 910.933 246.406 17.4077 + vertex 912.792 250.574 17.5475 + vertex 906.93 246.36 18.0224 + endloop + endfacet + facet normal 0.152149 -0.101978 0.983082 + outer loop + vertex 910.933 246.406 17.4077 + vertex 906.93 246.36 18.0224 + vertex 907.934 242.281 17.4439 + endloop + endfacet + facet normal 0.139604 -0.105281 0.984595 + outer loop + vertex 906.93 246.36 18.0224 + vertex 901.674 238.231 17.8985 + vertex 907.934 242.281 17.4439 + endloop + endfacet + facet normal 0.137545 -0.102027 0.985227 + outer loop + vertex 905.815 238.155 17.3125 + vertex 907.934 242.281 17.4439 + vertex 901.674 238.231 17.8985 + endloop + endfacet + facet normal 0.137522 -0.102739 0.985156 + outer loop + vertex 905.815 238.155 17.3125 + vertex 901.674 238.231 17.8985 + vertex 902.479 234.026 17.3476 + endloop + endfacet + facet normal 0.126849 -0.104941 0.986355 + outer loop + vertex 901.674 238.231 17.8985 + vertex 895.856 230.178 17.7898 + vertex 902.479 234.026 17.3476 + endloop + endfacet + facet normal 0.125868 -0.103217 0.986663 + outer loop + vertex 900.045 229.857 17.2218 + vertex 902.479 234.026 17.3476 + vertex 895.856 230.178 17.7898 + endloop + endfacet + facet normal 0.125778 -0.104225 0.986568 + outer loop + vertex 900.045 229.857 17.2218 + vertex 895.856 230.178 17.7898 + vertex 896.41 225.797 17.2564 + endloop + endfacet + facet normal 0.118716 -0.105211 0.987338 + outer loop + vertex 895.856 230.178 17.7898 + vertex 889.651 222.328 17.6996 + vertex 896.41 225.797 17.2564 + endloop + endfacet + facet normal 0.118275 -0.104332 0.987485 + outer loop + vertex 893.724 221.669 17.142 + vertex 896.41 225.797 17.2564 + vertex 889.651 222.328 17.6996 + endloop + endfacet + facet normal 0.118409 -0.103561 0.98755 + outer loop + vertex 893.724 221.669 17.142 + vertex 889.651 222.328 17.6996 + vertex 889.945 217.796 17.1889 + endloop + endfacet + facet normal 0.113638 -0.10393 0.988071 + outer loop + vertex 889.651 222.328 17.6996 + vertex 883.499 214.984 17.6345 + vertex 889.945 217.796 17.1889 + endloop + endfacet + facet normal 0.116145 -0.109826 0.987142 + outer loop + vertex 887.143 213.831 17.0775 + vertex 889.945 217.796 17.1889 + vertex 883.499 214.984 17.6345 + endloop + endfacet + facet normal 0.11751 -0.105652 0.987436 + outer loop + vertex 887.143 213.831 17.0775 + vertex 883.499 214.984 17.6345 + vertex 883.487 210.379 17.1433 + endloop + endfacet + facet normal 0.114602 -0.10568 0.987774 + outer loop + vertex 883.499 214.984 17.6345 + vertex 877.98 208.674 17.5997 + vertex 883.487 210.379 17.1433 + endloop + endfacet + facet normal 0.115618 -0.10909 0.987285 + outer loop + vertex 880.806 206.835 17.0657 + vertex 883.487 210.379 17.1433 + vertex 877.98 208.674 17.5997 + endloop + endfacet + facet normal 0.117162 -0.106739 0.98736 + outer loop + vertex 880.806 206.835 17.0657 + vertex 877.98 208.674 17.5997 + vertex 877.613 204.157 17.1551 + endloop + endfacet + facet normal 0.106559 -0.106003 0.98864 + outer loop + vertex 877.98 208.674 17.5997 + vertex 873.155 203.971 17.6155 + vertex 877.613 204.157 17.1551 + endloop + endfacet + facet normal 0.106702 -0.110759 0.988103 + outer loop + vertex 874.858 200.732 17.0686 + vertex 877.613 204.157 17.1551 + vertex 873.155 203.971 17.6155 + endloop + endfacet + facet normal 0.108332 -0.109889 0.988023 + outer loop + vertex 874.858 200.732 17.0686 + vertex 873.155 203.971 17.6155 + vertex 869.356 198.16 17.3858 + endloop + endfacet + facet normal 0.119893 -0.135171 0.983542 + outer loop + vertex 873.86 198.067 16.824 + vertex 874.858 200.732 17.0686 + vertex 869.356 198.16 17.3858 + endloop + endfacet + facet normal 0.243558 -0.106056 0.96407 + outer loop + vertex 923.891 272.869 17.5941 + vertex 921.418 272.069 18.1309 + vertex 921.623 268.441 17.6801 + endloop + endfacet + facet normal 0.239547 -0.0920092 0.966515 + outer loop + vertex 923.891 272.869 17.5941 + vertex 924.846 276.904 17.7414 + vertex 921.418 272.069 18.1309 + endloop + endfacet + facet normal 0.245406 -0.0963163 0.964624 + outer loop + vertex 921.418 272.069 18.1309 + vertex 924.846 276.904 17.7414 + vertex 922.801 277.854 18.3567 + endloop + endfacet + facet normal 0.251658 -0.0826364 0.964282 + outer loop + vertex 924.846 276.904 17.7414 + vertex 926.165 282.228 17.8535 + vertex 922.801 277.854 18.3567 + endloop + endfacet + facet normal 0.251419 -0.082444 0.964361 + outer loop + vertex 922.801 277.854 18.3567 + vertex 926.165 282.228 17.8535 + vertex 924.378 284.264 18.4934 + endloop + endfacet + facet normal 0.263819 -0.0708099 0.96197 + outer loop + vertex 926.165 282.228 17.8535 + vertex 927.419 288.112 17.9427 + vertex 924.378 284.264 18.4934 + endloop + endfacet + facet normal 0.203736 -0.0401138 0.978204 + outer loop + vertex 927.039 301.907 18.8888 + vertex 927.044 307.317 19.1096 + vertex 924.839 301.251 19.32 + endloop + endfacet + facet normal 0.205128 -0.0406304 0.977892 + outer loop + vertex 924.839 301.251 19.32 + vertex 927.044 307.317 19.1096 + vertex 925.093 308.251 19.5576 + endloop + endfacet + facet normal 0.21312 -0.023392 0.976746 + outer loop + vertex 927.044 307.317 19.1096 + vertex 927.016 312.684 19.2442 + vertex 925.093 308.251 19.5576 + endloop + endfacet + facet normal 0.158812 -0.0498786 0.986048 + outer loop + vertex 922.066 302.722 19.8411 + vertex 921.112 294.315 19.5695 + vertex 924.839 301.251 19.32 + endloop + endfacet + facet normal 0.164286 -0.0394107 0.985625 + outer loop + vertex 924.839 301.251 19.32 + vertex 925.093 308.251 19.5576 + vertex 922.066 302.722 19.8411 + endloop + endfacet + facet normal 0.20569 -0.0200513 0.978412 + outer loop + vertex 925.093 308.251 19.5576 + vertex 927.016 312.684 19.2442 + vertex 925.367 314.845 19.6352 + endloop + endfacet + facet normal 0.123888 -0.0253385 0.991973 + outer loop + vertex 920.581 315.001 20.3966 + vertex 919.14 305.54 20.3349 + vertex 922.899 310.334 19.988 + endloop + endfacet + facet normal 0.136242 -0.027209 0.990302 + outer loop + vertex 919.14 305.54 20.3349 + vertex 920.581 315.001 20.3966 + vertex 915.777 308.83 20.888 + endloop + endfacet + facet normal 0.19319 0.00188769 0.98116 + outer loop + vertex 923.52 315.554 19.9975 + vertex 925.367 314.845 19.6352 + vertex 924.31 321.898 19.8297 + endloop + endfacet + facet normal 0.155528 -0.0163663 0.987696 + outer loop + vertex 916.507 318.065 21.0452 + vertex 920.424 324.923 20.5421 + vertex 916.67 327.484 21.1757 + endloop + endfacet + facet normal 0.136834 -0.0276772 0.990207 + outer loop + vertex 915.777 308.83 20.888 + vertex 920.581 315.001 20.3966 + vertex 916.507 318.065 21.0452 + endloop + endfacet + facet normal 0.1247 -0.0392001 0.99142 + outer loop + vertex 914.34 299.895 20.7155 + vertex 919.14 305.54 20.3349 + vertex 915.777 308.83 20.888 + endloop + endfacet + facet normal 0.119906 -0.0508137 0.991484 + outer loop + vertex 912.288 291.072 20.5114 + vertex 917.694 296.807 20.1516 + vertex 914.34 299.895 20.7155 + endloop + endfacet + facet normal 0.112943 -0.0596628 0.991809 + outer loop + vertex 909.543 282.266 20.2943 + vertex 915.707 287.872 19.9296 + vertex 912.288 291.072 20.5114 + endloop + endfacet + facet normal 0.101378 -0.0652826 0.992704 + outer loop + vertex 906.173 273.736 20.0776 + vertex 912.838 278.856 19.7336 + vertex 909.543 282.266 20.2943 + endloop + endfacet + facet normal 0.0900341 -0.069181 0.993533 + outer loop + vertex 902.342 265.674 19.8634 + vertex 909.308 270.26 19.5514 + vertex 906.173 273.736 20.0776 + endloop + endfacet + facet normal 0.0812884 -0.0719225 0.994092 + outer loop + vertex 898.103 257.995 19.6544 + vertex 905.42 262.114 19.3541 + vertex 902.342 265.674 19.8634 + endloop + endfacet + facet normal 0.0731515 -0.072287 0.994698 + outer loop + vertex 893.4 250.508 19.4562 + vertex 901.032 254.195 19.1628 + vertex 898.103 257.995 19.6544 + endloop + endfacet + facet normal 0.0658995 -0.0711977 0.995283 + outer loop + vertex 888.216 243.131 19.2717 + vertex 896.125 246.451 18.9855 + vertex 893.4 250.508 19.4562 + endloop + endfacet + facet normal 0.0604028 -0.0697189 0.995736 + outer loop + vertex 882.592 235.897 19.1063 + vertex 890.718 238.865 18.8212 + vertex 888.216 243.131 19.2717 + endloop + endfacet + facet normal 0.0568557 -0.0661301 0.99619 + outer loop + vertex 876.664 228.898 18.98 + vertex 884.888 231.453 18.6803 + vertex 882.592 235.897 19.1063 + endloop + endfacet + facet normal 0.0556597 -0.0615187 0.996553 + outer loop + vertex 871.172 222.446 18.8885 + vertex 879.037 224.386 18.569 + vertex 876.664 228.898 18.98 + endloop + endfacet + facet normal 0.0549955 -0.0587928 0.996754 + outer loop + vertex 873.878 217.789 18.4645 + vertex 879.037 224.386 18.569 + vertex 871.172 222.446 18.8885 + endloop + endfacet + facet normal 0.0566752 -0.0571038 0.996758 + outer loop + vertex 869.886 211.349 18.3225 + vertex 876.29 213.328 18.0718 + vertex 873.878 217.789 18.4645 + endloop + endfacet + facet normal 0.0558902 -0.0583395 0.996731 + outer loop + vertex 872.686 208.214 17.982 + vertex 869.886 211.349 18.3225 + vertex 866.924 204.024 18.0599 + endloop + endfacet + facet normal 0.0622232 -0.0591031 0.996311 + outer loop + vertex 860.538 213.636 18.9917 + vertex 863.378 208.737 18.5237 + vertex 866.78 216.193 18.7536 + endloop + endfacet + facet normal 0.0627293 -0.0486213 0.996846 + outer loop + vertex 850.38 198.236 18.7866 + vertex 858.596 201.109 18.4097 + vertex 856.449 205.716 18.7695 + endloop + endfacet + facet normal 0.0673907 -0.04739 0.996601 + outer loop + vertex 842.9 190.858 18.9416 + vertex 851.96 193.518 18.4554 + vertex 850.38 198.236 18.7866 + endloop + endfacet + facet normal 0.072309 -0.0497723 0.99614 + outer loop + vertex 834.649 183.722 19.184 + vertex 844.114 186.101 18.6158 + vertex 842.9 190.858 18.9416 + endloop + endfacet + facet normal 0.077208 -0.0552455 0.995483 + outer loop + vertex 825.991 176.813 19.472 + vertex 835.616 178.936 18.8433 + vertex 834.649 183.722 19.184 + endloop + endfacet + facet normal 0.0815975 -0.0626381 0.994695 + outer loop + vertex 817.032 170.073 19.7825 + vertex 826.816 172.015 19.1022 + vertex 825.991 176.813 19.472 + endloop + endfacet + facet normal 0.0911493 -0.0804741 0.99258 + outer loop + vertex 807.749 163.46 20.0988 + vertex 817.032 170.073 19.7825 + vertex 807.337 168.553 20.5496 + endloop + endfacet + facet normal 0.0914078 -0.0804512 0.992558 + outer loop + vertex 797.722 162.114 20.9132 + vertex 807.749 163.46 20.0988 + vertex 807.337 168.553 20.5496 + endloop + endfacet + facet normal 0.0906352 -0.0913062 0.99169 + outer loop + vertex 788.058 155.625 21.199 + vertex 798.206 156.995 20.3976 + vertex 797.722 162.114 20.9132 + endloop + endfacet + facet normal 0.0859384 -0.104504 0.990804 + outer loop + vertex 778.082 149.554 21.4238 + vertex 788.479 150.78 20.6514 + vertex 788.058 155.625 21.199 + endloop + endfacet + facet normal 0.0797496 -0.112348 0.990463 + outer loop + vertex 768.063 143.889 21.5879 + vertex 778.599 144.913 20.8558 + vertex 778.082 149.554 21.4238 + endloop + endfacet + facet normal 0.074061 -0.116516 0.990424 + outer loop + vertex 757.963 138.532 21.713 + vertex 768.588 139.344 21.014 + vertex 768.063 143.889 21.5879 + endloop + endfacet + facet normal 0.0693254 -0.1201 0.990338 + outer loop + vertex 747.681 133.375 21.8073 + vertex 758.405 133.989 21.1311 + vertex 757.963 138.532 21.713 + endloop + endfacet + facet normal 0.0647295 -0.123642 0.990213 + outer loop + vertex 737.219 128.387 21.8684 + vertex 748.047 128.813 21.2139 + vertex 747.681 133.375 21.8073 + endloop + endfacet + facet normal 0.0596652 -0.126301 0.990196 + outer loop + vertex 726.576 123.552 21.893 + vertex 737.526 123.821 21.2676 + vertex 737.219 128.387 21.8684 + endloop + endfacet + facet normal 0.0543653 -0.125767 0.990569 + outer loop + vertex 715.675 118.799 21.8879 + vertex 726.85 118.996 21.2996 + vertex 726.576 123.552 21.893 + endloop + endfacet + facet normal 0.0483665 -0.123037 0.991223 + outer loop + vertex 705.155 114.15 21.8242 + vertex 716.133 114.325 21.3102 + vertex 715.675 118.799 21.8879 + endloop + endfacet + facet normal 0.0431254 -0.116654 0.992236 + outer loop + vertex 695.205 109.99 21.7675 + vertex 705.524 109.883 21.3064 + vertex 705.155 114.15 21.8242 + endloop + endfacet + facet normal 0.0413254 -0.108381 0.99325 + outer loop + vertex 684.21 106.444 21.838 + vertex 694.789 105.727 21.3196 + vertex 695.205 109.99 21.7675 + endloop + endfacet + facet normal 0.0415877 -0.106465 0.993446 + outer loop + vertex 672.899 102.441 21.8826 + vertex 683.724 101.662 21.3459 + vertex 684.21 106.444 21.838 + endloop + endfacet + facet normal 0.0420916 -0.109187 0.99313 + outer loop + vertex 660.496 98.1159 21.9327 + vertex 672.384 97.5006 21.3612 + vertex 672.899 102.441 21.8826 + endloop + endfacet + facet normal 0.0799986 -0.198323 0.976867 + outer loop + vertex 647.844 97.8864 22.71 + vertex 649.941 96.2703 22.2103 + vertex 653.353 99.0957 22.5044 + endloop + endfacet + facet normal 0.0827266 -0.194926 0.977323 + outer loop + vertex 643.503 96.0539 22.712 + vertex 649.941 96.2703 22.2103 + vertex 647.844 97.8864 22.71 + endloop + endfacet + facet normal 0.0829086 -0.205314 0.975178 + outer loop + vertex 643.814 93.5999 22.1689 + vertex 649.941 96.2703 22.2103 + vertex 643.503 96.0539 22.712 + endloop + endfacet + facet normal 0.0899166 -0.204332 0.974763 + outer loop + vertex 638.027 94.1228 22.8123 + vertex 643.814 93.5999 22.1689 + vertex 643.503 96.0539 22.712 + endloop + endfacet + facet normal 0.0863404 -0.235596 0.968008 + outer loop + vertex 637.609 91.5553 22.2247 + vertex 643.814 93.5999 22.1689 + vertex 638.027 94.1228 22.8123 + endloop + endfacet + facet normal 0.100513 -0.237482 0.966178 + outer loop + vertex 632.45 92.35 22.9568 + vertex 637.609 91.5553 22.2247 + vertex 638.027 94.1228 22.8123 + endloop + endfacet + facet normal 0.0945283 -0.269203 0.958433 + outer loop + vertex 631.882 89.7648 22.2866 + vertex 637.609 91.5553 22.2247 + vertex 632.45 92.35 22.9568 + endloop + endfacet + facet normal 0.109889 -0.27195 0.956017 + outer loop + vertex 626.855 90.6056 23.1037 + vertex 631.882 89.7648 22.2866 + vertex 632.45 92.35 22.9568 + endloop + endfacet + facet normal 0.104797 -0.295987 0.949426 + outer loop + vertex 626.187 87.988 22.3614 + vertex 631.882 89.7648 22.2866 + vertex 626.855 90.6056 23.1037 + endloop + endfacet + facet normal 0.118119 -0.298703 0.947008 + outer loop + vertex 621.147 88.8474 23.261 + vertex 626.187 87.988 22.3614 + vertex 626.855 90.6056 23.1037 + endloop + endfacet + facet normal 0.113328 -0.320079 0.940588 + outer loop + vertex 620.39 86.2182 22.4576 + vertex 626.187 87.988 22.3614 + vertex 621.147 88.8474 23.261 + endloop + endfacet + facet normal 0.128044 -0.323392 0.937562 + outer loop + vertex 615.573 87.1794 23.447 + vertex 620.39 86.2182 22.4576 + vertex 621.147 88.8474 23.261 + endloop + endfacet + facet normal 0.122873 -0.342875 0.93131 + outer loop + vertex 614.81 84.5535 22.5808 + vertex 620.39 86.2182 22.4576 + vertex 615.573 87.1794 23.447 + endloop + endfacet + facet normal 0.135023 -0.345524 0.928645 + outer loop + vertex 610.72 85.69 23.5985 + vertex 614.81 84.5535 22.5808 + vertex 615.573 87.1794 23.447 + endloop + endfacet + facet normal 0.128572 -0.363428 0.922708 + outer loop + vertex 610.036 83.0725 22.6628 + vertex 614.81 84.5535 22.5808 + vertex 610.72 85.69 23.5985 + endloop + endfacet + facet normal 0.121044 -0.362023 0.924277 + outer loop + vertex 607.043 84.316 23.5418 + vertex 610.036 83.0725 22.6628 + vertex 610.72 85.69 23.5985 + endloop + endfacet + facet normal 0.122999 -0.358188 0.925512 + outer loop + vertex 606.508 81.839 22.6542 + vertex 610.036 83.0725 22.6628 + vertex 607.043 84.316 23.5418 + endloop + endfacet + facet normal 0.0951895 -0.353938 0.930412 + outer loop + vertex 604.873 82.9957 23.2616 + vertex 606.508 81.839 22.6542 + vertex 607.043 84.316 23.5418 + endloop + endfacet + facet normal 0.106011 -0.340629 0.934202 + outer loop + vertex 604.599 81.0834 22.5954 + vertex 606.508 81.839 22.6542 + vertex 604.873 82.9957 23.2616 + endloop + endfacet + facet normal 0.198554 -0.347667 0.916354 + outer loop + vertex 604.599 81.0834 22.5954 + vertex 604.873 82.9957 23.2616 + vertex 604.173 81.3065 22.7723 + endloop + endfacet + facet normal 0.0396648 -0.113485 0.992748 + outer loop + vertex 651.587 93.5142 21.7626 + vertex 661.522 93.3599 21.348 + vertex 660.496 98.1159 21.9327 + endloop + endfacet + facet normal 0.0399224 -0.110034 0.993126 + outer loop + vertex 651.587 93.5142 21.7626 + vertex 643.435 90.6402 21.7719 + vertex 651.37 89.6968 21.3484 + endloop + endfacet + facet normal 0.0419377 -0.11543 0.99243 + outer loop + vertex 636.897 89.1333 21.8729 + vertex 640.232 86.6883 21.4476 + vertex 643.435 90.6402 21.7719 + endloop + endfacet +endsolid diff --git a/noether_examples/meshes/outputs/output_9.stl b/noether_examples/meshes/outputs/output_9.stl new file mode 100644 index 00000000..ab498d69 --- /dev/null +++ b/noether_examples/meshes/outputs/output_9.stl @@ -0,0 +1,52950 @@ +solid ascii + facet normal 0.139948 -0.441674 0.886193 + outer loop + vertex 381.335 85.9999 363.76 + vertex 384.016 86.0274 363.35 + vertex 391.968 88.9581 363.555 + endloop + endfacet + facet normal 0.150124 -0.479757 0.864463 + outer loop + vertex 381.335 85.9999 363.76 + vertex 391.968 88.9581 363.555 + vertex 389.155 88.5455 363.815 + endloop + endfacet + facet normal 0.116427 -0.380057 0.917606 + outer loop + vertex 391.968 88.9581 363.555 + vertex 384.016 86.0274 363.35 + vertex 391.533 88.417 363.386 + endloop + endfacet + facet normal 0.135518 -0.392891 0.909545 + outer loop + vertex 391.533 88.417 363.386 + vertex 395.904 89.6568 363.271 + vertex 391.968 88.9581 363.555 + endloop + endfacet + facet normal 0.150127 -0.446975 0.881859 + outer loop + vertex 391.533 88.417 363.386 + vertex 391.58 87.8201 363.076 + vertex 395.904 89.6568 363.271 + endloop + endfacet + facet normal 0.146946 -0.43992 0.885933 + outer loop + vertex 395.904 89.6568 363.271 + vertex 391.58 87.8201 363.076 + vertex 396.99 89.2223 362.875 + endloop + endfacet + facet normal 0.152754 -0.429256 0.890172 + outer loop + vertex 395.904 89.6568 363.271 + vertex 396.99 89.2223 362.875 + vertex 399.557 90.4747 363.038 + endloop + endfacet + facet normal 0.147306 -0.400936 0.904185 + outer loop + vertex 399.557 90.4747 363.038 + vertex 399.092 90.9337 363.317 + vertex 395.904 89.6568 363.271 + endloop + endfacet + facet normal 0.157384 -0.392056 0.906379 + outer loop + vertex 399.092 90.9337 363.317 + vertex 399.557 90.4747 363.038 + vertex 401.571 90.9404 362.89 + endloop + endfacet + facet normal 0.157561 -0.389505 0.907447 + outer loop + vertex 403.337 92.4562 363.234 + vertex 399.092 90.9337 363.317 + vertex 401.571 90.9404 362.89 + endloop + endfacet + facet normal 0.183985 -0.41642 0.890362 + outer loop + vertex 401.571 90.9404 362.89 + vertex 402.35 89.4453 362.03 + vertex 403.337 92.4562 363.234 + endloop + endfacet + facet normal 0.188713 -0.417392 0.888916 + outer loop + vertex 404.037 87.388 360.705 + vertex 403.337 92.4562 363.234 + vertex 402.35 89.4453 362.03 + endloop + endfacet + facet normal 0.16582 -0.425476 0.889648 + outer loop + vertex 402.35 89.4453 362.03 + vertex 401.571 90.9404 362.89 + vertex 400.401 89.858 362.59 + endloop + endfacet + facet normal 0.163014 -0.433896 0.886093 + outer loop + vertex 400.257 88.7844 362.091 + vertex 402.35 89.4453 362.03 + vertex 400.401 89.858 362.59 + endloop + endfacet + facet normal 0.152031 -0.433432 0.88827 + outer loop + vertex 400.401 89.858 362.59 + vertex 397.266 88.3152 362.374 + vertex 400.257 88.7844 362.091 + endloop + endfacet + facet normal 0.152979 -0.442184 0.883782 + outer loop + vertex 397.266 88.3152 362.374 + vertex 397.325 87.2071 361.809 + vertex 400.257 88.7844 362.091 + endloop + endfacet + facet normal 0.151027 -0.438907 0.885749 + outer loop + vertex 400.257 88.7844 362.091 + vertex 397.325 87.2071 361.809 + vertex 400.671 87.7325 361.499 + endloop + endfacet + facet normal 0.152056 -0.44837 0.88082 + outer loop + vertex 397.325 87.2071 361.809 + vertex 397.368 85.9597 361.167 + vertex 400.671 87.7325 361.499 + endloop + endfacet + facet normal 0.148092 -0.441738 0.884837 + outer loop + vertex 400.671 87.7325 361.499 + vertex 397.368 85.9597 361.167 + vertex 400.503 86.3613 360.843 + endloop + endfacet + facet normal 0.156213 -0.441999 0.883309 + outer loop + vertex 400.503 86.3613 360.843 + vertex 402.439 87.0295 360.835 + vertex 400.671 87.7325 361.499 + endloop + endfacet + facet normal 0.161265 -0.432754 0.886971 + outer loop + vertex 402.439 87.0295 360.835 + vertex 402.35 89.4453 362.03 + vertex 400.671 87.7325 361.499 + endloop + endfacet + facet normal 0.168608 -0.431991 0.885977 + outer loop + vertex 402.35 89.4453 362.03 + vertex 402.439 87.0295 360.835 + vertex 404.037 87.388 360.705 + endloop + endfacet + facet normal 0.171383 -0.447312 0.877804 + outer loop + vertex 402.439 87.0295 360.835 + vertex 402.67 84.5053 359.503 + vertex 404.037 87.388 360.705 + endloop + endfacet + facet normal 0.167956 -0.446198 0.879032 + outer loop + vertex 404.689 83.2934 358.502 + vertex 404.037 87.388 360.705 + vertex 402.67 84.5053 359.503 + endloop + endfacet + facet normal 0.159082 -0.449159 0.879175 + outer loop + vertex 402.67 84.5053 359.503 + vertex 402.439 87.0295 360.835 + vertex 401.089 85.1574 360.123 + endloop + endfacet + facet normal 0.154785 -0.456638 0.876084 + outer loop + vertex 401.014 83.8265 359.442 + vertex 402.67 84.5053 359.503 + vertex 401.089 85.1574 360.123 + endloop + endfacet + facet normal 0.14336 -0.456908 0.877885 + outer loop + vertex 401.089 85.1574 360.123 + vertex 397.996 83.0423 359.527 + vertex 401.014 83.8265 359.442 + endloop + endfacet + facet normal 0.146134 -0.46828 0.871412 + outer loop + vertex 401.014 83.8265 359.442 + vertex 397.996 83.0423 359.527 + vertex 399.133 81.5812 358.551 + endloop + endfacet + facet normal 0.14059 -0.471899 0.870371 + outer loop + vertex 392.617 80.0365 358.766 + vertex 399.133 81.5812 358.551 + vertex 397.996 83.0423 359.527 + endloop + endfacet + facet normal 0.144968 -0.478621 0.865971 + outer loop + vertex 392.178 81.8143 359.822 + vertex 392.617 80.0365 358.766 + vertex 397.996 83.0423 359.527 + endloop + endfacet + facet normal 0.142515 -0.465148 0.873686 + outer loop + vertex 397.471 84.5251 360.402 + vertex 392.178 81.8143 359.822 + vertex 397.996 83.0423 359.527 + endloop + endfacet + facet normal 0.145303 -0.469943 0.870655 + outer loop + vertex 391.859 83.4919 360.781 + vertex 392.178 81.8143 359.822 + vertex 397.471 84.5251 360.402 + endloop + endfacet + facet normal 0.143499 -0.457643 0.87748 + outer loop + vertex 397.368 85.9597 361.167 + vertex 391.859 83.4919 360.781 + vertex 397.471 84.5251 360.402 + endloop + endfacet + facet normal 0.147615 -0.466032 0.872367 + outer loop + vertex 393.044 85.1895 361.487 + vertex 391.859 83.4919 360.781 + vertex 397.368 85.9597 361.167 + endloop + endfacet + facet normal 0.136711 -0.460403 0.87712 + outer loop + vertex 393.044 85.1895 361.487 + vertex 384.586 82.5459 361.418 + vertex 391.859 83.4919 360.781 + endloop + endfacet + facet normal 0.137997 -0.476091 0.868501 + outer loop + vertex 384.586 82.5459 361.418 + vertex 384.018 80.0917 360.163 + vertex 391.859 83.4919 360.781 + endloop + endfacet + facet normal 0.125911 -0.474636 0.87113 + outer loop + vertex 384.586 82.5459 361.418 + vertex 372.47 77.6405 360.496 + vertex 384.018 80.0917 360.163 + endloop + endfacet + facet normal 0.131013 -0.500783 0.8556 + outer loop + vertex 372.47 77.6405 360.496 + vertex 375.531 75.7961 358.948 + vertex 384.018 80.0917 360.163 + endloop + endfacet + facet normal 0.126307 -0.492966 0.860832 + outer loop + vertex 384.018 80.0917 360.163 + vertex 375.531 75.7961 358.948 + vertex 385.995 78.8628 359.169 + endloop + endfacet + facet normal 0.137449 -0.479704 0.866598 + outer loop + vertex 384.018 80.0917 360.163 + vertex 385.995 78.8628 359.169 + vertex 392.178 81.8143 359.822 + endloop + endfacet + facet normal 0.129554 -0.503566 0.854188 + outer loop + vertex 385.995 78.8628 359.169 + vertex 375.531 75.7961 358.948 + vertex 383.451 76.1551 357.959 + endloop + endfacet + facet normal 0.142341 -0.512327 0.846912 + outer loop + vertex 385.995 78.8628 359.169 + vertex 383.451 76.1551 357.959 + vertex 392.617 80.0365 358.766 + endloop + endfacet + facet normal 0.130117 -0.486952 0.863683 + outer loop + vertex 392.617 80.0365 358.766 + vertex 383.451 76.1551 357.959 + vertex 392.645 77.8125 357.508 + endloop + endfacet + facet normal 0.133339 -0.508336 0.850774 + outer loop + vertex 383.451 76.1551 357.959 + vertex 383.99 74.0551 356.619 + vertex 392.645 77.8125 357.508 + endloop + endfacet + facet normal 0.131056 -0.503798 0.853822 + outer loop + vertex 392.645 77.8125 357.508 + vertex 383.99 74.0551 356.619 + vertex 392.357 75.1242 355.966 + endloop + endfacet + facet normal 0.14035 -0.503909 0.852278 + outer loop + vertex 392.645 77.8125 357.508 + vertex 392.357 75.1242 355.966 + vertex 399.106 78.7346 356.989 + endloop + endfacet + facet normal 0.137819 -0.477449 0.867783 + outer loop + vertex 399.133 81.5812 358.551 + vertex 392.645 77.8125 357.508 + vertex 399.106 78.7346 356.989 + endloop + endfacet + facet normal 0.144321 -0.477051 0.866945 + outer loop + vertex 402.452 81.6219 358.021 + vertex 399.133 81.5812 358.551 + vertex 399.106 78.7346 356.989 + endloop + endfacet + facet normal 0.152163 -0.48423 0.861608 + outer loop + vertex 404.011 79.0232 356.285 + vertex 402.452 81.6219 358.021 + vertex 399.106 78.7346 356.989 + endloop + endfacet + facet normal 0.151832 -0.498695 0.853376 + outer loop + vertex 399.106 78.7346 356.989 + vertex 399.337 75.8838 355.282 + vertex 404.011 79.0232 356.285 + endloop + endfacet + facet normal 0.153573 -0.500794 0.851834 + outer loop + vertex 403.555 75.5159 354.305 + vertex 404.011 79.0232 356.285 + vertex 399.337 75.8838 355.282 + endloop + endfacet + facet normal 0.146204 -0.53422 0.832606 + outer loop + vertex 399.337 75.8838 355.282 + vertex 399.728 72.9528 353.333 + vertex 403.555 75.5159 354.305 + endloop + endfacet + facet normal 0.155887 -0.545274 0.823636 + outer loop + vertex 404.384 72.7732 352.333 + vertex 403.555 75.5159 354.305 + vertex 399.728 72.9528 353.333 + endloop + endfacet + facet normal 0.151479 -0.570006 0.807556 + outer loop + vertex 399.728 72.9528 353.333 + vertex 400.531 70.3677 351.358 + vertex 404.384 72.7732 352.333 + endloop + endfacet + facet normal 0.160378 -0.580509 0.798303 + outer loop + vertex 403.912 69.3812 349.961 + vertex 404.384 72.7732 352.333 + vertex 400.531 70.3677 351.358 + endloop + endfacet + facet normal 0.164184 -0.580501 0.797535 + outer loop + vertex 404.384 72.7732 352.333 + vertex 403.912 69.3812 349.961 + vertex 408.888 71.3492 350.369 + endloop + endfacet + facet normal 0.140039 -0.573337 0.807263 + outer loop + vertex 399.728 72.9528 353.333 + vertex 393.486 68.8551 351.505 + vertex 400.531 70.3677 351.358 + endloop + endfacet + facet normal 0.146846 -0.607652 0.78051 + outer loop + vertex 400.531 70.3677 351.358 + vertex 393.486 68.8551 351.505 + vertex 397.818 66.11 348.553 + endloop + endfacet + facet normal 0.145606 -0.608852 0.779807 + outer loop + vertex 383.821 62.7985 348.581 + vertex 397.818 66.11 348.553 + vertex 393.486 68.8551 351.505 + endloop + endfacet + facet normal 0.14069 -0.603459 0.784884 + outer loop + vertex 380.688 66.4547 351.954 + vertex 383.821 62.7985 348.581 + vertex 393.486 68.8551 351.505 + endloop + endfacet + facet normal 0.136196 -0.575479 0.806396 + outer loop + vertex 392.125 72.0103 353.987 + vertex 380.688 66.4547 351.954 + vertex 393.486 68.8551 351.505 + endloop + endfacet + facet normal 0.134679 -0.573075 0.80836 + outer loop + vertex 380.75 70.452 354.777 + vertex 380.688 66.4547 351.954 + vertex 392.125 72.0103 353.987 + endloop + endfacet + facet normal 0.131621 -0.538673 0.83217 + outer loop + vertex 392.357 75.1242 355.966 + vertex 380.75 70.452 354.777 + vertex 392.125 72.0103 353.987 + endloop + endfacet + facet normal 0.140004 -0.538498 0.830915 + outer loop + vertex 392.357 75.1242 355.966 + vertex 392.125 72.0103 353.987 + vertex 399.337 75.8838 355.282 + endloop + endfacet + facet normal 0.127222 -0.573566 0.809219 + outer loop + vertex 380.688 66.4547 351.954 + vertex 380.75 70.452 354.777 + vertex 363.691 63.7454 352.706 + endloop + endfacet + facet normal 0.130591 -0.600299 0.789042 + outer loop + vertex 363.691 63.7454 352.706 + vertex 364.956 59.046 348.921 + vertex 380.688 66.4547 351.954 + endloop + endfacet + facet normal 0.12108 -0.602641 0.788773 + outer loop + vertex 363.691 63.7454 352.706 + vertex 344.006 55.6479 349.541 + vertex 364.956 59.046 348.921 + endloop + endfacet + facet normal 0.122226 -0.60473 0.786996 + outer loop + vertex 342.942 60.3711 353.335 + vertex 344.006 55.6479 349.541 + vertex 363.691 63.7454 352.706 + endloop + endfacet + facet normal 0.112438 -0.606818 0.786848 + outer loop + vertex 342.942 60.3711 353.335 + vertex 321.83 51.9677 349.872 + vertex 344.006 55.6479 349.541 + endloop + endfacet + facet normal 0.114035 -0.609788 0.784318 + outer loop + vertex 320.614 56.5228 353.59 + vertex 321.83 51.9677 349.872 + vertex 342.942 60.3711 353.335 + endloop + endfacet + facet normal 0.108222 -0.57427 0.811481 + outer loop + vertex 341.609 64.7309 356.599 + vertex 320.614 56.5228 353.59 + vertex 342.942 60.3711 353.335 + endloop + endfacet + facet normal 0.120668 -0.57092 0.812089 + outer loop + vertex 341.609 64.7309 356.599 + vertex 342.942 60.3711 353.335 + vertex 366.692 69.7485 356.399 + endloop + endfacet + facet normal 0.116838 -0.551212 0.826144 + outer loop + vertex 359.268 71.9857 358.942 + vertex 341.609 64.7309 356.599 + vertex 366.692 69.7485 356.399 + endloop + endfacet + facet normal 0.124991 -0.534916 0.835609 + outer loop + vertex 359.268 71.9857 358.942 + vertex 366.692 69.7485 356.399 + vertex 375.531 75.7961 358.948 + endloop + endfacet + facet normal 0.111654 -0.540995 0.833581 + outer loop + vertex 340.62 68.6532 359.277 + vertex 341.609 64.7309 356.599 + vertex 359.268 71.9857 358.942 + endloop + endfacet + facet normal 0.108279 -0.520781 0.846796 + outer loop + vertex 359.268 71.9857 358.942 + vertex 358.32 75.0042 360.919 + vertex 340.62 68.6532 359.277 + endloop + endfacet + facet normal 0.10493 -0.512812 0.852064 + outer loop + vertex 343.232 73.0964 361.629 + vertex 340.62 68.6532 359.277 + vertex 358.32 75.0042 360.919 + endloop + endfacet + facet normal 0.102995 -0.493131 0.863837 + outer loop + vertex 361.148 77.9069 362.239 + vertex 343.232 73.0964 361.629 + vertex 358.32 75.0042 360.919 + endloop + endfacet + facet normal 0.123631 -0.508045 0.852412 + outer loop + vertex 361.148 77.9069 362.239 + vertex 358.32 75.0042 360.919 + vertex 372.407 80.0547 361.886 + endloop + endfacet + facet normal 0.11871 -0.479444 0.869506 + outer loop + vertex 372.27 81.8693 362.906 + vertex 361.148 77.9069 362.239 + vertex 372.407 80.0547 361.886 + endloop + endfacet + facet normal 0.133413 -0.477676 0.868347 + outer loop + vertex 372.27 81.8693 362.906 + vertex 372.407 80.0547 361.886 + vertex 384.631 84.6966 362.562 + endloop + endfacet + facet normal 0.129759 -0.460512 0.878118 + outer loop + vertex 384.016 86.0274 363.35 + vertex 372.27 81.8693 362.906 + vertex 384.631 84.6966 362.562 + endloop + endfacet + facet normal 0.140021 -0.456181 0.878802 + outer loop + vertex 384.016 86.0274 363.35 + vertex 384.631 84.6966 362.562 + vertex 391.58 87.8201 363.076 + endloop + endfacet + facet normal 0.140282 -0.456709 0.878486 + outer loop + vertex 393.04 87.4266 362.638 + vertex 391.58 87.8201 363.076 + vertex 384.631 84.6966 362.562 + endloop + endfacet + facet normal 0.137896 -0.449474 0.882586 + outer loop + vertex 393.04 87.4266 362.638 + vertex 384.631 84.6966 362.562 + vertex 392.063 86.0433 362.086 + endloop + endfacet + facet normal 0.150732 -0.456295 0.876969 + outer loop + vertex 393.04 87.4266 362.638 + vertex 392.063 86.0433 362.086 + vertex 397.266 88.3152 362.374 + endloop + endfacet + facet normal 0.148367 -0.442896 0.884212 + outer loop + vertex 396.99 89.2223 362.875 + vertex 393.04 87.4266 362.638 + vertex 397.266 88.3152 362.374 + endloop + endfacet + facet normal 0.140481 -0.467145 0.87295 + outer loop + vertex 384.631 84.6966 362.562 + vertex 384.586 82.5459 361.418 + vertex 392.063 86.0433 362.086 + endloop + endfacet + facet normal 0.134799 -0.473904 0.870198 + outer loop + vertex 371.42 82.8442 363.568 + vertex 372.27 81.8693 362.906 + vertex 384.016 86.0274 363.35 + endloop + endfacet + facet normal 0.118638 -0.485314 0.866254 + outer loop + vertex 371.42 82.8442 363.568 + vertex 358.459 78.7654 363.058 + vertex 372.27 81.8693 362.906 + endloop + endfacet + facet normal 0.129068 -0.516025 0.846794 + outer loop + vertex 360.214 80.4026 363.788 + vertex 358.459 78.7654 363.058 + vertex 371.42 82.8442 363.568 + endloop + endfacet + facet normal 0.133168 -0.536024 0.833634 + outer loop + vertex 370.61 83.2129 363.935 + vertex 360.214 80.4026 363.788 + vertex 371.42 82.8442 363.568 + endloop + endfacet + facet normal 0.147572 -0.515047 0.844363 + outer loop + vertex 370.61 83.2129 363.935 + vertex 371.42 82.8442 363.568 + vertex 381.335 85.9999 363.76 + endloop + endfacet + facet normal 0.158466 -0.625958 0.763587 + outer loop + vertex 363.594 81.5995 364.068 + vertex 360.214 80.4026 363.788 + vertex 370.61 83.2129 363.935 + endloop + endfacet + facet normal 0.112601 -0.516382 0.848923 + outer loop + vertex 360.214 80.4026 363.788 + vertex 363.594 81.5995 364.068 + vertex 355.211 80.1705 364.311 + endloop + endfacet + facet normal 0.10455 -0.496413 0.861767 + outer loop + vertex 360.214 80.4026 363.788 + vertex 340.788 75.646 363.405 + vertex 358.459 78.7654 363.058 + endloop + endfacet + facet normal 0.10493 -0.498718 0.86039 + outer loop + vertex 340.788 75.646 363.405 + vertex 343.232 73.0964 361.629 + vertex 358.459 78.7654 363.058 + endloop + endfacet + facet normal 0.0939807 -0.506802 0.856924 + outer loop + vertex 340.788 75.646 363.405 + vertex 320.459 69.0566 361.737 + vertex 343.232 73.0964 361.629 + endloop + endfacet + facet normal 0.0950432 -0.512892 0.853176 + outer loop + vertex 320.459 69.0566 361.737 + vertex 320.779 65.4585 359.539 + vertex 343.232 73.0964 361.629 + endloop + endfacet + facet normal 0.085127 -0.514006 0.853552 + outer loop + vertex 320.459 69.0566 361.737 + vertex 299.692 62.141 359.644 + vertex 320.779 65.4585 359.539 + endloop + endfacet + facet normal 0.0881812 -0.533819 0.840989 + outer loop + vertex 299.692 62.141 359.644 + vertex 299.236 57.7491 356.904 + vertex 320.779 65.4585 359.539 + endloop + endfacet + facet normal 0.0875644 -0.53242 0.841939 + outer loop + vertex 320.779 65.4585 359.539 + vertex 299.236 57.7491 356.904 + vertex 320.183 61.048 356.812 + endloop + endfacet + facet normal 0.0969068 -0.532873 0.840628 + outer loop + vertex 320.779 65.4585 359.539 + vertex 320.183 61.048 356.812 + vertex 340.62 68.6532 359.277 + endloop + endfacet + facet normal 0.0926076 -0.565062 0.819834 + outer loop + vertex 299.236 57.7491 356.904 + vertex 299.116 53.0497 353.679 + vertex 320.183 61.048 356.812 + endloop + endfacet + facet normal 0.095658 -0.57127 0.815169 + outer loop + vertex 320.183 61.048 356.812 + vertex 299.116 53.0497 353.679 + vertex 320.614 56.5228 353.59 + endloop + endfacet + facet normal 0.101497 -0.608125 0.787326 + outer loop + vertex 299.116 53.0497 353.679 + vertex 300.052 48.514 350.055 + vertex 320.614 56.5228 353.59 + endloop + endfacet + facet normal 0.0917674 -0.609957 0.787103 + outer loop + vertex 299.116 53.0497 353.679 + vertex 278.94 45.2845 350.013 + vertex 300.052 48.514 350.055 + endloop + endfacet + facet normal 0.0910886 -0.608692 0.78816 + outer loop + vertex 277.941 49.8507 353.655 + vertex 278.94 45.2845 350.013 + vertex 299.116 53.0497 353.679 + endloop + endfacet + facet normal 0.0843592 -0.609973 0.787919 + outer loop + vertex 277.941 49.8507 353.655 + vertex 257.716 42.1737 349.877 + vertex 278.94 45.2845 350.013 + endloop + endfacet + facet normal 0.0854935 -0.612091 0.786152 + outer loop + vertex 256.641 46.852 353.637 + vertex 257.716 42.1737 349.877 + vertex 277.941 49.8507 353.655 + endloop + endfacet + facet normal 0.0790948 -0.566847 0.820017 + outer loop + vertex 278.095 54.6142 356.933 + vertex 256.641 46.852 353.637 + vertex 277.941 49.8507 353.655 + endloop + endfacet + facet normal 0.0851634 -0.566697 0.819513 + outer loop + vertex 278.095 54.6142 356.933 + vertex 277.941 49.8507 353.655 + vertex 299.236 57.7491 356.904 + endloop + endfacet + facet normal 0.0799293 -0.568603 0.81872 + outer loop + vertex 256.774 51.639 356.948 + vertex 256.641 46.852 353.637 + vertex 278.095 54.6142 356.933 + endloop + endfacet + facet normal 0.075278 -0.535153 0.841394 + outer loop + vertex 278.506 58.988 359.678 + vertex 256.774 51.639 356.948 + vertex 278.095 54.6142 356.933 + endloop + endfacet + facet normal 0.0810273 -0.535299 0.840767 + outer loop + vertex 278.506 58.988 359.678 + vertex 278.095 54.6142 356.933 + vertex 299.692 62.141 359.644 + endloop + endfacet + facet normal 0.078306 -0.516887 0.852465 + outer loop + vertex 298.682 65.4762 361.759 + vertex 278.506 58.988 359.678 + vertex 299.692 62.141 359.644 + endloop + endfacet + facet normal 0.0784352 -0.51722 0.852251 + outer loop + vertex 277.77 62.3567 361.79 + vertex 278.506 58.988 359.678 + vertex 298.682 65.4762 361.759 + endloop + endfacet + facet normal 0.0783231 -0.516464 0.852719 + outer loop + vertex 294.599 67.2984 363.238 + vertex 277.77 62.3567 361.79 + vertex 298.682 65.4762 361.759 + endloop + endfacet + facet normal 0.0830299 -0.509129 0.856676 + outer loop + vertex 294.599 67.2984 363.238 + vertex 298.682 65.4762 361.759 + vertex 315.739 70.9838 363.379 + endloop + endfacet + facet normal 0.0842708 -0.516082 0.852383 + outer loop + vertex 294.599 67.2984 363.238 + vertex 315.739 70.9838 363.379 + vertex 302.982 70.5315 364.366 + endloop + endfacet + facet normal 0.0793206 -0.505598 0.859115 + outer loop + vertex 302.982 70.5315 364.366 + vertex 289.207 68.0574 364.182 + vertex 294.599 67.2984 363.238 + endloop + endfacet + facet normal 0.0769044 -0.515609 0.853366 + outer loop + vertex 274.887 64.6476 363.413 + vertex 294.599 67.2984 363.238 + vertex 289.207 68.0574 364.182 + endloop + endfacet + facet normal 0.0747281 -0.507594 0.85835 + outer loop + vertex 289.207 68.0574 364.182 + vertex 278.36 67.1114 364.567 + vertex 274.887 64.6476 363.413 + endloop + endfacet + facet normal 0.0725615 -0.505268 0.859906 + outer loop + vertex 278.36 67.1114 364.567 + vertex 264.518 64.8955 364.433 + vertex 274.887 64.6476 363.413 + endloop + endfacet + facet normal 0.0718597 -0.513856 0.854861 + outer loop + vertex 252.552 61.5333 363.418 + vertex 274.887 64.6476 363.413 + vertex 264.518 64.8955 364.433 + endloop + endfacet + facet normal 0.0723134 -0.515213 0.854006 + outer loop + vertex 264.518 64.8955 364.433 + vertex 253.812 63.3116 364.384 + vertex 252.552 61.5333 363.418 + endloop + endfacet + facet normal 0.0670126 -0.512557 0.856034 + outer loop + vertex 253.812 63.3116 364.384 + vertex 241.897 61.7872 364.404 + vertex 252.552 61.5333 363.418 + endloop + endfacet + facet normal 0.0668617 -0.514472 0.854897 + outer loop + vertex 231.304 58.5623 363.292 + vertex 252.552 61.5333 363.418 + vertex 241.897 61.7872 364.404 + endloop + endfacet + facet normal 0.0634807 -0.505328 0.860589 + outer loop + vertex 241.897 61.7872 364.404 + vertex 224.66 59.6418 364.416 + vertex 231.304 58.5623 363.292 + endloop + endfacet + facet normal 0.0613444 -0.513553 0.855862 + outer loop + vertex 211.28 56.3973 363.428 + vertex 231.304 58.5623 363.292 + vertex 224.66 59.6418 364.416 + endloop + endfacet + facet normal 0.0632844 -0.520273 0.851652 + outer loop + vertex 224.66 59.6418 364.416 + vertex 214.01 58.3198 364.4 + vertex 211.28 56.3973 363.428 + endloop + endfacet + facet normal 0.0568058 -0.513404 0.856265 + outer loop + vertex 214.01 58.3198 364.4 + vertex 202.931 57.1159 364.413 + vertex 211.28 56.3973 363.428 + endloop + endfacet + facet normal 0.0560289 -0.518382 0.853312 + outer loop + vertex 189.912 54.0865 363.427 + vertex 211.28 56.3973 363.428 + vertex 202.931 57.1159 364.413 + endloop + endfacet + facet normal 0.0563217 -0.519427 0.852657 + outer loop + vertex 202.931 57.1159 364.413 + vertex 192.453 55.958 364.4 + vertex 189.912 54.0865 363.427 + endloop + endfacet + facet normal 0.0502672 -0.513321 0.856723 + outer loop + vertex 192.453 55.958 364.4 + vertex 180.562 54.8129 364.411 + vertex 189.912 54.0865 363.427 + endloop + endfacet + facet normal 0.0498364 -0.516395 0.854899 + outer loop + vertex 168.65 51.7956 363.283 + vertex 189.912 54.0865 363.427 + vertex 180.562 54.8129 364.411 + endloop + endfacet + facet normal 0.0473031 -0.508264 0.859901 + outer loop + vertex 180.562 54.8129 364.411 + vertex 163.392 53.1935 364.398 + vertex 168.65 51.7956 363.283 + endloop + endfacet + facet normal 0.0441549 -0.516374 0.855224 + outer loop + vertex 148.618 50.2993 363.414 + vertex 168.65 51.7956 363.283 + vertex 163.392 53.1935 364.398 + endloop + endfacet + facet normal 0.0465241 -0.526349 0.848995 + outer loop + vertex 163.392 53.1935 364.398 + vertex 152.591 52.2064 364.378 + vertex 148.618 50.2993 363.414 + endloop + endfacet + facet normal 0.0391633 -0.514777 0.856429 + outer loop + vertex 152.591 52.2064 364.378 + vertex 141.053 51.4307 364.44 + vertex 148.618 50.2993 363.414 + endloop + endfacet + facet normal 0.037981 -0.519912 0.853375 + outer loop + vertex 126.156 48.6599 363.415 + vertex 148.618 50.2993 363.414 + vertex 141.053 51.4307 364.44 + endloop + endfacet + facet normal 0.0366368 -0.514023 0.856994 + outer loop + vertex 141.053 51.4307 364.44 + vertex 127.161 50.6737 364.58 + vertex 126.156 48.6599 363.415 + endloop + endfacet + facet normal 0.0336685 -0.512974 0.857743 + outer loop + vertex 127.161 50.6737 364.58 + vertex 116.005 49.3165 364.206 + vertex 126.156 48.6599 363.415 + endloop + endfacet + facet normal 0.0320571 -0.52738 0.849024 + outer loop + vertex 104.759 47.0983 363.253 + vertex 126.156 48.6599 363.415 + vertex 116.005 49.3165 364.206 + endloop + endfacet + facet normal 0.0281506 -0.511728 0.858686 + outer loop + vertex 116.005 49.3165 364.206 + vertex 101.279 48.8108 364.387 + vertex 104.759 47.0983 363.253 + endloop + endfacet + facet normal 0.0249788 -0.516387 0.855991 + outer loop + vertex 84.4248 46.3616 363.402 + vertex 104.759 47.0983 363.253 + vertex 101.279 48.8108 364.387 + endloop + endfacet + facet normal 0.0250976 -0.517043 0.855591 + outer loop + vertex 101.279 48.8108 364.387 + vertex 87.3479 48.4099 364.554 + vertex 84.4248 46.3616 363.402 + endloop + endfacet + facet normal 0.0218312 -0.513598 0.857753 + outer loop + vertex 87.3479 48.4099 364.554 + vertex 76.0279 47.3777 364.224 + vertex 84.4248 46.3616 363.402 + endloop + endfacet + facet normal 0.0190326 -0.52911 0.84834 + outer loop + vertex 61.5707 45.5508 363.409 + vertex 84.4248 46.3616 363.402 + vertex 76.0279 47.3777 364.224 + endloop + endfacet + facet normal 0.0166897 -0.514563 0.85729 + outer loop + vertex 76.0279 47.3777 364.224 + vertex 65.0033 47.566 364.551 + vertex 61.5707 45.5508 363.409 + endloop + endfacet + facet normal 0.0140902 -0.511276 0.859301 + outer loop + vertex 65.0033 47.566 364.551 + vertex 50.8 46.9457 364.415 + vertex 61.5707 45.5508 363.409 + endloop + endfacet + facet normal 0.0125664 -0.519492 0.854383 + outer loop + vertex 38.5283 44.9808 363.401 + vertex 61.5707 45.5508 363.409 + vertex 50.8 46.9457 364.415 + endloop + endfacet + facet normal 0.0123326 -0.518382 0.85506 + outer loop + vertex 50.8 46.9457 364.415 + vertex 39.8685 46.6075 364.368 + vertex 38.5283 44.9808 363.401 + endloop + endfacet + facet normal 0.00720794 -0.515301 0.856979 + outer loop + vertex 39.8685 46.6075 364.368 + vertex 28.0731 46.4904 364.397 + vertex 38.5283 44.9808 363.401 + endloop + endfacet + facet normal 0.00681204 -0.517264 0.855799 + outer loop + vertex 17.2225 44.5106 363.286 + vertex 38.5283 44.9808 363.401 + vertex 28.0731 46.4904 364.397 + endloop + endfacet + facet normal 0.00459922 -0.508185 0.861236 + outer loop + vertex 28.0731 46.4904 364.397 + vertex 10.9637 46.3688 364.416 + vertex 17.2225 44.5106 363.286 + endloop + endfacet + facet normal 0.00186752 -0.514945 0.857221 + outer loop + vertex -2.6198 44.6615 363.42 + vertex 17.2225 44.5106 363.286 + vertex 10.9637 46.3688 364.416 + endloop + endfacet + facet normal 0.00239463 -0.518047 0.855349 + outer loop + vertex 10.9637 46.3688 364.416 + vertex 0.0830764 46.3066 364.409 + vertex -2.6198 44.6615 363.42 + endloop + endfacet + facet normal -0.00253431 -0.512097 0.858924 + outer loop + vertex 0.0830764 46.3066 364.409 + vertex -11.7794 46.3865 364.422 + vertex -2.6198 44.6615 363.42 + endloop + endfacet + facet normal -0.00330636 -0.515138 0.857101 + outer loop + vertex -23.6014 44.5812 363.291 + vertex -2.6198 44.6615 363.42 + vertex -11.7794 46.3865 364.422 + endloop + endfacet + facet normal -0.0047517 -0.508242 0.861201 + outer loop + vertex -11.7794 46.3865 364.422 + vertex -28.8864 46.5039 364.396 + vertex -23.6014 44.5812 363.291 + endloop + endfacet + facet normal -0.00823035 -0.515352 0.856939 + outer loop + vertex -43.7802 45.0861 363.401 + vertex -23.6014 44.5812 363.291 + vertex -28.8864 46.5039 364.396 + endloop + endfacet + facet normal -0.00695173 -0.524766 0.851218 + outer loop + vertex -28.8864 46.5039 364.396 + vertex -39.7696 46.5967 364.365 + vertex -43.7802 45.0861 363.401 + endloop + endfacet + facet normal -0.0122697 -0.514568 0.857362 + outer loop + vertex -39.7696 46.5967 364.365 + vertex -51.539 46.9593 364.414 + vertex -43.7802 45.0861 363.401 + endloop + endfacet + facet normal -0.0137786 -0.51927 0.854499 + outer loop + vertex -66.6263 45.7013 363.406 + vertex -43.7802 45.0861 363.401 + vertex -51.539 46.9593 364.414 + endloop + endfacet + facet normal -0.0142615 -0.515364 0.856853 + outer loop + vertex -51.539 46.9593 364.414 + vertex -65.4449 47.559 364.543 + vertex -66.6263 45.7013 363.406 + endloop + endfacet + facet normal -0.0169477 -0.514092 0.857567 + outer loop + vertex -65.4449 47.559 364.543 + vertex -76.3437 47.3859 364.224 + vertex -66.6263 45.7013 363.406 + endloop + endfacet + facet normal -0.0204871 -0.529803 0.847873 + outer loop + vertex -89.6435 46.577 363.397 + vertex -66.6263 45.7013 363.406 + vertex -76.3437 47.3859 364.224 + endloop + endfacet + facet normal -0.0220842 -0.513621 0.857733 + outer loop + vertex -76.3437 47.3859 364.224 + vertex -87.8516 48.44 364.559 + vertex -89.6435 46.577 363.397 + endloop + endfacet + facet normal -0.0252079 -0.511393 0.858977 + outer loop + vertex -87.8516 48.44 364.559 + vertex -102.22 48.8666 364.391 + vertex -89.6435 46.577 363.397 + endloop + endfacet + facet normal -0.0266254 -0.517554 0.855236 + outer loop + vertex -111.118 47.4428 363.253 + vertex -89.6435 46.577 363.397 + vertex -102.22 48.8666 364.391 + endloop + endfacet + facet normal -0.0282174 -0.510803 0.859235 + outer loop + vertex -102.22 48.8666 364.391 + vertex -116.411 49.3404 364.207 + vertex -111.118 47.4428 363.253 + endloop + endfacet + facet normal -0.0334774 -0.521986 0.852297 + outer loop + vertex -131.039 48.9969 363.422 + vertex -111.118 47.4428 363.253 + vertex -116.411 49.3404 364.207 + endloop + endfacet + facet normal -0.0339878 -0.512846 0.857808 + outer loop + vertex -116.411 49.3404 364.207 + vertex -127.466 50.7009 364.582 + vertex -131.039 48.9969 363.422 + endloop + endfacet + facet normal -0.0366076 -0.508884 0.860056 + outer loop + vertex -127.466 50.7009 364.582 + vertex -141.568 51.4791 364.442 + vertex -131.039 48.9969 363.422 + endloop + endfacet + facet normal -0.0394922 -0.518659 0.854068 + outer loop + vertex -153.451 50.6934 363.416 + vertex -131.039 48.9969 363.422 + vertex -141.568 51.4791 364.442 + endloop + endfacet + facet normal -0.0394552 -0.518973 0.85388 + outer loop + vertex -141.568 51.4791 364.442 + vertex -152.296 52.1933 364.381 + vertex -153.451 50.6934 363.416 + endloop + endfacet + facet normal -0.045152 -0.515683 0.855589 + outer loop + vertex -152.296 52.1933 364.381 + vertex -164.165 53.2497 364.391 + vertex -153.451 50.6934 363.416 + endloop + endfacet + facet normal -0.0455741 -0.517114 0.854702 + outer loop + vertex -174.625 52.3386 363.282 + vertex -153.451 50.6934 363.416 + vertex -164.165 53.2497 364.391 + endloop + endfacet + facet normal -0.0471287 -0.506717 0.860823 + outer loop + vertex -164.165 53.2497 364.391 + vertex -181.287 54.8394 364.39 + vertex -174.625 52.3386 363.282 + endloop + endfacet + facet normal -0.0514816 -0.515804 0.855158 + outer loop + vertex -194.845 54.5903 363.423 + vertex -174.625 52.3386 363.282 + vertex -181.287 54.8394 364.39 + endloop + endfacet + facet normal -0.0511775 -0.520757 0.85217 + outer loop + vertex -181.287 54.8394 364.39 + vertex -192.121 55.8871 364.379 + vertex -194.845 54.5903 363.423 + endloop + endfacet + facet normal -0.0563508 -0.513078 0.85649 + outer loop + vertex -192.121 55.8871 364.379 + vertex -203.695 57.262 364.441 + vertex -194.845 54.5903 363.423 + endloop + endfacet + facet normal -0.057936 -0.517315 0.853831 + outer loop + vertex -217.342 57.1272 363.434 + vertex -194.845 54.5903 363.423 + vertex -203.695 57.262 364.441 + endloop + endfacet + facet normal -0.0583672 -0.509313 0.8586 + outer loop + vertex -203.695 57.262 364.441 + vertex -217.767 59.1145 364.584 + vertex -217.342 57.1272 363.434 + endloop + endfacet + facet normal -0.0608759 -0.509637 0.858233 + outer loop + vertex -217.767 59.1145 364.584 + vertex -228.344 59.7629 364.218 + vertex -217.342 57.1272 363.434 + endloop + endfacet + facet normal -0.0629785 -0.517045 0.853638 + outer loop + vertex -238.12 59.4083 363.282 + vertex -217.342 57.1272 363.434 + vertex -228.344 59.7629 364.218 + endloop + endfacet + facet normal -0.0640924 -0.505028 0.86072 + outer loop + vertex -228.344 59.7629 364.218 + vertex -242.725 61.8363 364.364 + vertex -238.12 59.4083 363.282 + endloop + endfacet + facet normal -0.0668987 -0.509167 0.858064 + outer loop + vertex -257.535 62.21 363.431 + vertex -238.12 59.4083 363.282 + vertex -242.725 61.8363 364.364 + endloop + endfacet + facet normal -0.066865 -0.511922 0.856426 + outer loop + vertex -242.725 61.8363 364.364 + vertex -253.524 63.3095 364.402 + vertex -257.535 62.21 363.431 + endloop + endfacet + facet normal -0.0698831 -0.504551 0.860549 + outer loop + vertex -253.524 63.3095 364.402 + vertex -264.878 65.0051 364.474 + vertex -257.535 62.21 363.431 + endloop + endfacet + facet normal -0.0714671 -0.507924 0.858432 + outer loop + vertex -279.535 65.3051 363.431 + vertex -257.535 62.21 363.431 + vertex -264.878 65.0051 364.474 + endloop + endfacet + facet normal -0.0715893 -0.502153 0.86181 + outer loop + vertex -264.878 65.0051 364.474 + vertex -278.574 67.198 364.614 + vertex -279.535 65.3051 363.431 + endloop + endfacet + facet normal -0.0741631 -0.501095 0.862208 + outer loop + vertex -278.574 67.198 364.614 + vertex -289.644 68.1802 364.232 + vertex -279.535 65.3051 363.431 + endloop + endfacet + facet normal -0.0791315 -0.51598 0.852938 + outer loop + vertex -300.78 68.3003 363.272 + vertex -279.535 65.3051 363.431 + vertex -289.644 68.1802 364.232 + endloop + endfacet + facet normal -0.0797304 -0.501028 0.86175 + outer loop + vertex -289.644 68.1802 364.232 + vertex -304.209 70.8338 364.428 + vertex -300.78 68.3003 363.272 + endloop + endfacet + facet normal -0.0857942 -0.507292 0.857493 + outer loop + vertex -321.206 72.1359 363.497 + vertex -300.78 68.3003 363.272 + vertex -304.209 70.8338 364.428 + endloop + endfacet + facet normal -0.0861368 -0.515141 0.852766 + outer loop + vertex -304.209 70.8338 364.428 + vertex -317.921 73.416 364.602 + vertex -321.206 72.1359 363.497 + endloop + endfacet + facet normal -0.08911 -0.509942 0.855581 + outer loop + vertex -317.921 73.416 364.602 + vertex -328.975 74.8591 364.311 + vertex -321.206 72.1359 363.497 + endloop + endfacet + facet normal -0.0852872 -0.476762 0.874885 + outer loop + vertex -328.975 74.8591 364.311 + vertex -317.921 73.416 364.602 + vertex -330.01 77.1868 365.479 + endloop + endfacet + facet normal -0.0905655 -0.478395 0.873462 + outer loop + vertex -339.945 77.4483 364.592 + vertex -328.975 74.8591 364.311 + vertex -330.01 77.1868 365.479 + endloop + endfacet + facet normal -0.0909202 -0.461727 0.88235 + outer loop + vertex -330.01 77.1868 365.479 + vertex -349.308 81.1655 365.572 + vertex -339.945 77.4483 364.592 + endloop + endfacet + facet normal -0.0960405 -0.486237 0.868533 + outer loop + vertex -330.01 77.1868 365.479 + vertex -342.534 82.5783 367.112 + vertex -349.308 81.1655 365.572 + endloop + endfacet + facet normal -0.100064 -0.473877 0.874888 + outer loop + vertex -342.534 82.5783 367.112 + vertex -356.347 85.6977 367.222 + vertex -349.308 81.1655 365.572 + endloop + endfacet + facet normal -0.114301 -0.491739 0.863208 + outer loop + vertex -356.347 85.6977 367.222 + vertex -363.321 85.5956 366.241 + vertex -349.308 81.1655 365.572 + endloop + endfacet + facet normal -0.107813 -0.472915 0.874487 + outer loop + vertex -363.915 83.3285 364.941 + vertex -349.308 81.1655 365.572 + vertex -363.321 85.5956 366.241 + endloop + endfacet + facet normal -0.12807 -0.467659 0.874582 + outer loop + vertex -363.321 85.5956 366.241 + vertex -373.337 87.4806 365.782 + vertex -363.915 83.3285 364.941 + endloop + endfacet + facet normal -0.122594 -0.456573 0.881199 + outer loop + vertex -363.915 83.3285 364.941 + vertex -373.337 87.4806 365.782 + vertex -374.646 85.8831 364.772 + endloop + endfacet + facet normal -0.111723 -0.409293 0.905537 + outer loop + vertex -363.915 83.3285 364.941 + vertex -374.646 85.8831 364.772 + vertex -369.786 83.8415 364.449 + endloop + endfacet + facet normal -0.114981 -0.482102 0.868537 + outer loop + vertex -363.915 83.3285 364.941 + vertex -369.786 83.8415 364.449 + vertex -368.029 83.001 364.215 + endloop + endfacet + facet normal -0.114069 -0.487338 0.865731 + outer loop + vertex -368.029 83.001 364.215 + vertex -354.593 80.0527 364.326 + vertex -363.915 83.3285 364.941 + endloop + endfacet + facet normal -0.10917 -0.46452 0.878808 + outer loop + vertex -354.593 80.0527 364.326 + vertex -368.029 83.001 364.215 + vertex -365.136 81.8031 363.941 + endloop + endfacet + facet normal -0.148703 -0.541218 0.827629 + outer loop + vertex -369.786 83.8415 364.449 + vertex -376.046 85.2555 364.249 + vertex -368.029 83.001 364.215 + endloop + endfacet + facet normal -0.14161 -0.516253 0.844647 + outer loop + vertex -378.599 85.5373 363.993 + vertex -368.029 83.001 364.215 + vertex -376.046 85.2555 364.249 + endloop + endfacet + facet normal -0.129543 -0.448371 0.884411 + outer loop + vertex -369.786 83.8415 364.449 + vertex -374.646 85.8831 364.772 + vertex -376.046 85.2555 364.249 + endloop + endfacet + facet normal -0.135268 -0.43886 0.888316 + outer loop + vertex -374.646 85.8831 364.772 + vertex -384.584 88.3278 364.466 + vertex -376.046 85.2555 364.249 + endloop + endfacet + facet normal -0.13559 -0.43972 0.887841 + outer loop + vertex -376.046 85.2555 364.249 + vertex -384.584 88.3278 364.466 + vertex -384.79 87.5175 364.034 + endloop + endfacet + facet normal -0.138058 -0.449778 0.882406 + outer loop + vertex -376.046 85.2555 364.249 + vertex -384.79 87.5175 364.034 + vertex -378.599 85.5373 363.993 + endloop + endfacet + facet normal -0.143938 -0.437488 0.88763 + outer loop + vertex -384.79 87.5175 364.034 + vertex -384.584 88.3278 364.466 + vertex -391.219 89.7045 364.069 + endloop + endfacet + facet normal -0.148303 -0.450204 0.880524 + outer loop + vertex -392.318 89.5971 363.829 + vertex -384.79 87.5175 364.034 + vertex -391.219 89.7045 364.069 + endloop + endfacet + facet normal -0.15197 -0.431787 0.889081 + outer loop + vertex -391.219 89.7045 364.069 + vertex -396.548 91.2518 363.91 + vertex -392.318 89.5971 363.829 + endloop + endfacet + facet normal -0.159443 -0.450372 0.878489 + outer loop + vertex -392.318 89.5971 363.829 + vertex -396.548 91.2518 363.91 + vertex -398.157 91.3594 363.673 + endloop + endfacet + facet normal -0.15122 -0.42175 0.894013 + outer loop + vertex -392.318 89.5971 363.829 + vertex -398.157 91.3594 363.673 + vertex -394.906 90.0554 363.607 + endloop + endfacet + facet normal -0.172563 -0.47345 0.863752 + outer loop + vertex -402.439 92.2161 363.287 + vertex -394.906 90.0554 363.607 + vertex -398.157 91.3594 363.673 + endloop + endfacet + facet normal -0.168567 -0.446779 0.878621 + outer loop + vertex -398.157 91.3594 363.673 + vertex -400.847 92.3591 363.665 + vertex -402.439 92.2161 363.287 + endloop + endfacet + facet normal -0.17546 -0.411574 0.894327 + outer loop + vertex -400.847 92.3591 363.665 + vertex -401.451 93.2324 363.948 + vertex -402.439 92.2161 363.287 + endloop + endfacet + facet normal -0.184402 -0.403963 0.895997 + outer loop + vertex -401.451 93.2324 363.948 + vertex -401.842 93.5256 364 + vertex -402.439 92.2161 363.287 + endloop + endfacet + facet normal 0.0374922 0.464735 -0.884656 + outer loop + vertex -401.398 94.2241 364.386 + vertex -402.439 92.2161 363.287 + vertex -401.842 93.5256 364 + endloop + endfacet + facet normal -0.323282 -0.291493 0.900289 + outer loop + vertex -401.842 93.5256 364 + vertex -401.144 94.5369 364.578 + vertex -401.398 94.2241 364.386 + endloop + endfacet + facet normal -0.415382 -0.207727 0.885611 + outer loop + vertex -401.144 94.5369 364.578 + vertex -400.194 95.8886 365.341 + vertex -401.398 94.2241 364.386 + endloop + endfacet + facet normal 0.138862 0.415422 -0.898967 + outer loop + vertex -401.398 94.2241 364.386 + vertex -400.194 95.8886 365.341 + vertex -400.521 95.2929 365.015 + endloop + endfacet + facet normal 0.147587 0.410984 -0.899617 + outer loop + vertex -399.014 97.2386 366.151 + vertex -400.521 95.2929 365.015 + vertex -400.194 95.8886 365.341 + endloop + endfacet + facet normal 0.148838 0.410029 -0.899846 + outer loop + vertex -400.194 95.8886 365.341 + vertex -398.412 98.2116 366.694 + vertex -399.014 97.2386 366.151 + endloop + endfacet + facet normal 0.157542 0.405069 -0.900611 + outer loop + vertex -397.228 99.6171 367.533 + vertex -399.014 97.2386 366.151 + vertex -398.412 98.2116 366.694 + endloop + endfacet + facet normal 0.149713 0.410888 -0.899309 + outer loop + vertex -398.412 98.2116 366.694 + vertex -396.106 101.381 368.526 + vertex -397.228 99.6171 367.533 + endloop + endfacet + facet normal 0.159216 0.405343 -0.900193 + outer loop + vertex -395.738 101.697 368.734 + vertex -397.228 99.6171 367.533 + vertex -396.106 101.381 368.526 + endloop + endfacet + facet normal 0.156739 0.407793 -0.899521 + outer loop + vertex -394.308 104.064 370.056 + vertex -395.738 101.697 368.734 + vertex -396.106 101.381 368.526 + endloop + endfacet + facet normal 0.176174 0.395773 -0.901291 + outer loop + vertex -396.106 101.381 368.526 + vertex -394.012 104.708 370.396 + vertex -394.308 104.064 370.056 + endloop + endfacet + facet normal 0.191594 0.388667 -0.901238 + outer loop + vertex -392.765 106.628 371.49 + vertex -394.308 104.064 370.056 + vertex -394.012 104.708 370.396 + endloop + endfacet + facet normal 0.177811 0.397129 -0.900373 + outer loop + vertex -394.012 104.708 370.396 + vertex -392.24 107.837 372.126 + vertex -392.765 106.628 371.49 + endloop + endfacet + facet normal 0.196435 0.388903 -0.900093 + outer loop + vertex -391.909 108.201 372.356 + vertex -392.765 106.628 371.49 + vertex -392.24 107.837 372.126 + endloop + endfacet + facet normal 0.190018 0.394177 -0.899176 + outer loop + vertex -391.146 110.069 373.336 + vertex -391.909 108.201 372.356 + vertex -392.24 107.837 372.126 + endloop + endfacet + facet normal 0.226643 0.375866 -0.898531 + outer loop + vertex -392.24 107.837 372.126 + vertex -391.144 110.26 373.417 + vertex -391.146 110.069 373.336 + endloop + endfacet + facet normal 0.236656 0.374855 -0.896369 + outer loop + vertex -390.306 112.206 374.452 + vertex -391.146 110.069 373.336 + vertex -391.144 110.26 373.417 + endloop + endfacet + facet normal 0.1485 0.413762 -0.898192 + outer loop + vertex -391.144 110.26 373.417 + vertex -390.537 111.977 374.308 + vertex -390.306 112.206 374.452 + endloop + endfacet + facet normal 0.152511 0.410292 -0.899111 + outer loop + vertex -389.41 114.962 375.861 + vertex -390.306 112.206 374.452 + vertex -390.537 111.977 374.308 + endloop + endfacet + facet normal 0.116505 0.423501 -0.898373 + outer loop + vertex -390.537 111.977 374.308 + vertex -389.293 115.598 376.176 + vertex -389.41 114.962 375.861 + endloop + endfacet + facet normal 0.113774 0.42405 -0.898464 + outer loop + vertex -388.546 117.654 377.241 + vertex -389.41 114.962 375.861 + vertex -389.293 115.598 376.176 + endloop + endfacet + facet normal 0.01958 0.454232 -0.890668 + outer loop + vertex -389.293 115.598 376.176 + vertex -387.899 119.98 378.442 + vertex -388.546 117.654 377.241 + endloop + endfacet + facet normal 0.0166873 0.454893 -0.89039 + outer loop + vertex -388.015 119.279 378.081 + vertex -388.546 117.654 377.241 + vertex -387.899 119.98 378.442 + endloop + endfacet + facet normal -0.0844374 0.466552 -0.880454 + outer loop + vertex -387.54 121.134 379.019 + vertex -388.015 119.279 378.081 + vertex -387.899 119.98 378.442 + endloop + endfacet + facet normal -0.139365 0.477208 -0.867669 + outer loop + vertex -386.919 123.612 380.282 + vertex -387.54 121.134 379.019 + vertex -387.899 119.98 378.442 + endloop + endfacet + facet normal -0.32362 -0.356781 0.876343 + outer loop + vertex -387.899 119.98 378.442 + vertex -385.711 126.248 381.801 + vertex -386.919 123.612 380.282 + endloop + endfacet + facet normal -0.284854 -0.377339 0.881177 + outer loop + vertex -386.251 126.542 381.753 + vertex -386.919 123.612 380.282 + vertex -385.711 126.248 381.801 + endloop + endfacet + facet normal -0.286788 -0.381274 0.878853 + outer loop + vertex -385.852 128.36 382.672 + vertex -386.251 126.542 381.753 + vertex -385.711 126.248 381.801 + endloop + endfacet + facet normal -0.297563 -0.380629 0.875544 + outer loop + vertex -385.354 130.55 383.793 + vertex -385.852 128.36 382.672 + vertex -385.711 126.248 381.801 + endloop + endfacet + facet normal -0.294846 -0.381171 0.876228 + outer loop + vertex -385.711 126.248 381.801 + vertex -383.969 134.734 386.079 + vertex -385.354 130.55 383.793 + endloop + endfacet + facet normal -0.304709 -0.377037 0.87464 + outer loop + vertex -384.862 133.233 385.121 + vertex -385.354 130.55 383.793 + vertex -383.969 134.734 386.079 + endloop + endfacet + facet normal -0.293808 -0.383978 0.87535 + outer loop + vertex -384.457 135.165 386.105 + vertex -384.862 133.233 385.121 + vertex -383.969 134.734 386.079 + endloop + endfacet + facet normal -0.298154 -0.388682 0.871797 + outer loop + vertex -384.16 137.222 387.123 + vertex -384.457 135.165 386.105 + vertex -383.969 134.734 386.079 + endloop + endfacet + facet normal -0.315111 -0.387667 0.866267 + outer loop + vertex -383.779 139.46 388.263 + vertex -384.16 137.222 387.123 + vertex -383.969 134.734 386.079 + endloop + endfacet + facet normal -0.298688 -0.390433 0.870831 + outer loop + vertex -383.969 134.734 386.079 + vertex -382.843 142.481 389.939 + vertex -383.779 139.46 388.263 + endloop + endfacet + facet normal -0.297804 -0.390787 0.870975 + outer loop + vertex -383.517 141.71 389.362 + vertex -383.779 139.46 388.263 + vertex -382.843 142.481 389.939 + endloop + endfacet + facet normal -0.291366 -0.396209 0.870703 + outer loop + vertex -383.271 143.798 390.394 + vertex -383.517 141.71 389.362 + vertex -382.843 142.481 389.939 + endloop + endfacet + facet normal -0.300574 -0.397856 0.866813 + outer loop + vertex -382.917 146.302 391.667 + vertex -383.271 143.798 390.394 + vertex -382.843 142.481 389.939 + endloop + endfacet + facet normal -0.301777 -0.397719 0.866458 + outer loop + vertex -382.843 142.481 389.939 + vertex -382.088 149.579 393.46 + vertex -382.917 146.302 391.667 + endloop + endfacet + facet normal -0.311446 -0.394263 0.864614 + outer loop + vertex -382.742 148.261 392.623 + vertex -382.917 146.302 391.667 + vertex -382.088 149.579 393.46 + endloop + endfacet + facet normal -0.300144 -0.400568 0.865713 + outer loop + vertex -382.595 149.909 393.437 + vertex -382.742 148.261 392.623 + vertex -382.088 149.579 393.46 + endloop + endfacet + facet normal -0.302224 -0.403917 0.86343 + outer loop + vertex -382.426 151.448 394.215 + vertex -382.595 149.909 393.437 + vertex -382.088 149.579 393.46 + endloop + endfacet + facet normal -0.313314 -0.404258 0.859307 + outer loop + vertex -382.186 153.433 395.237 + vertex -382.426 151.448 394.215 + vertex -382.088 149.579 393.46 + endloop + endfacet + facet normal -0.298339 -0.405959 0.863823 + outer loop + vertex -382.088 149.579 393.46 + vertex -381.2 157.187 397.342 + vertex -382.186 153.433 395.237 + endloop + endfacet + facet normal -0.290012 -0.408946 0.865249 + outer loop + vertex -382.001 156.12 396.569 + vertex -382.186 153.433 395.237 + vertex -381.2 157.187 397.342 + endloop + endfacet + facet normal -0.282261 -0.414654 0.865096 + outer loop + vertex -381.789 158.348 397.706 + vertex -382.001 156.12 396.569 + vertex -381.2 157.187 397.342 + endloop + endfacet + facet normal -0.28841 -0.416814 0.862024 + outer loop + vertex -381.559 161.619 399.365 + vertex -381.789 158.348 397.706 + vertex -381.2 157.187 397.342 + endloop + endfacet + facet normal -0.285492 -0.416983 0.862913 + outer loop + vertex -381.2 157.187 397.342 + vertex -380.801 165.448 401.466 + vertex -381.559 161.619 399.365 + endloop + endfacet + facet normal -0.277124 -0.419472 0.864434 + outer loop + vertex -381.392 164.865 400.993 + vertex -381.559 161.619 399.365 + vertex -380.801 165.448 401.466 + endloop + endfacet + facet normal -0.273651 -0.422637 0.863998 + outer loop + vertex -381.286 167.406 402.27 + vertex -381.392 164.865 400.993 + vertex -380.801 165.448 401.466 + endloop + endfacet + facet normal -0.281137 -0.423357 0.861238 + outer loop + vertex -381.086 169.993 403.607 + vertex -381.286 167.406 402.27 + vertex -380.801 165.448 401.466 + endloop + endfacet + facet normal -0.255252 -0.425112 0.868405 + outer loop + vertex -380.801 165.448 401.466 + vertex -380.374 171.739 404.671 + vertex -381.086 169.993 403.607 + endloop + endfacet + facet normal -0.250372 -0.427311 0.868745 + outer loop + vertex -380.961 172.87 405.058 + vertex -381.086 169.993 403.607 + vertex -380.374 171.739 404.671 + endloop + endfacet + facet normal -0.252768 -0.428173 0.867627 + outer loop + vertex -380.704 174.191 405.785 + vertex -380.961 172.87 405.058 + vertex -380.374 171.739 404.671 + endloop + endfacet + facet normal -0.229698 -0.428001 0.874102 + outer loop + vertex -379.966 174.862 406.307 + vertex -380.704 174.191 405.785 + vertex -380.374 171.739 404.671 + endloop + endfacet + facet normal -0.223765 -0.429257 0.875024 + outer loop + vertex -380.374 171.739 404.671 + vertex -377.884 172.723 405.79 + vertex -379.966 174.862 406.307 + endloop + endfacet + facet normal -0.224993 -0.427033 0.875798 + outer loop + vertex -377.884 172.723 405.79 + vertex -380.374 171.739 404.671 + vertex -378.856 168.108 403.29 + endloop + endfacet + facet normal -0.213774 -0.430103 0.877104 + outer loop + vertex -377.884 172.723 405.79 + vertex -378.856 168.108 403.29 + vertex -375.387 167.506 403.841 + endloop + endfacet + facet normal -0.208114 -0.428242 0.879373 + outer loop + vertex -375.387 167.506 403.841 + vertex -374.185 170.514 405.59 + vertex -377.884 172.723 405.79 + endloop + endfacet + facet normal -0.2027 -0.419662 0.884758 + outer loop + vertex -374.185 170.514 405.59 + vertex -374.154 173.98 407.241 + vertex -377.884 172.723 405.79 + endloop + endfacet + facet normal -0.202767 -0.419522 0.884809 + outer loop + vertex -378.776 177.36 407.784 + vertex -377.884 172.723 405.79 + vertex -374.154 173.98 407.241 + endloop + endfacet + facet normal -0.189323 -0.402853 0.89547 + outer loop + vertex -372.482 176.987 408.947 + vertex -378.776 177.36 407.784 + vertex -374.154 173.98 407.241 + endloop + endfacet + facet normal -0.172466 -0.411835 0.894789 + outer loop + vertex -374.154 173.98 407.241 + vertex -368.267 172.748 407.809 + vertex -372.482 176.987 408.947 + endloop + endfacet + facet normal -0.156172 -0.398096 0.903952 + outer loop + vertex -363.823 174.234 409.231 + vertex -372.482 176.987 408.947 + vertex -368.267 172.748 407.809 + endloop + endfacet + facet normal -0.146409 -0.419538 0.895853 + outer loop + vertex -368.267 172.748 407.809 + vertex -361.072 170.469 407.917 + vertex -363.823 174.234 409.231 + endloop + endfacet + facet normal -0.12547 -0.407302 0.904634 + outer loop + vertex -354.799 171.5 409.252 + vertex -363.823 174.234 409.231 + vertex -361.072 170.469 407.917 + endloop + endfacet + facet normal -0.122535 -0.418842 0.899754 + outer loop + vertex -361.072 170.469 407.917 + vertex -354.251 168.166 407.774 + vertex -354.799 171.5 409.252 + endloop + endfacet + facet normal -0.104914 -0.417255 0.902713 + outer loop + vertex -354.251 168.166 407.774 + vertex -346.739 167.484 408.332 + vertex -354.799 171.5 409.252 + endloop + endfacet + facet normal -0.104623 -0.416734 0.902987 + outer loop + vertex -344.306 169.962 409.757 + vertex -354.799 171.5 409.252 + vertex -346.739 167.484 408.332 + endloop + endfacet + facet normal -0.0945625 -0.425026 0.900228 + outer loop + vertex -346.739 167.484 408.332 + vertex -336.284 165.838 408.653 + vertex -344.306 169.962 409.757 + endloop + endfacet + facet normal -0.0955401 -0.426689 0.899338 + outer loop + vertex -335.635 167.974 409.736 + vertex -344.306 169.962 409.757 + vertex -336.284 165.838 408.653 + endloop + endfacet + facet normal -0.0868788 -0.429167 0.899037 + outer loop + vertex -327.247 165.354 409.295 + vertex -335.635 167.974 409.736 + vertex -336.284 165.838 408.653 + endloop + endfacet + facet normal -0.0869231 -0.431452 0.897938 + outer loop + vertex -327.247 165.354 409.295 + vertex -336.284 165.838 408.653 + vertex -322.975 158.961 406.637 + endloop + endfacet + facet normal -0.0842627 -0.430058 0.89886 + outer loop + vertex -319.482 163.016 408.905 + vertex -327.247 165.354 409.295 + vertex -322.975 158.961 406.637 + endloop + endfacet + facet normal -0.0785664 -0.434151 0.897407 + outer loop + vertex -312.883 161.342 408.673 + vertex -319.482 163.016 408.905 + vertex -322.975 158.961 406.637 + endloop + endfacet + facet normal -0.0772378 -0.438197 0.895554 + outer loop + vertex -322.975 158.961 406.637 + vertex -301.021 156.07 407.116 + vertex -312.883 161.342 408.673 + endloop + endfacet + facet normal -0.0734758 -0.430873 0.899416 + outer loop + vertex -305.237 161.494 409.37 + vertex -312.883 161.342 408.673 + vertex -301.021 156.07 407.116 + endloop + endfacet + facet normal -0.0725366 -0.430291 0.899771 + outer loop + vertex -299.303 160.307 409.281 + vertex -305.237 161.494 409.37 + vertex -301.021 156.07 407.116 + endloop + endfacet + facet normal -0.0679778 -0.431922 0.899345 + outer loop + vertex -291.79 158.921 409.183 + vertex -299.303 160.307 409.281 + vertex -301.021 156.07 407.116 + endloop + endfacet + facet normal -0.0683407 -0.431035 0.899743 + outer loop + vertex -301.021 156.07 407.116 + vertex -282.04 153.387 407.272 + vertex -291.79 158.921 409.183 + endloop + endfacet + facet normal -0.067125 -0.429224 0.9007 + outer loop + vertex -285.275 158.047 409.252 + vertex -291.79 158.921 409.183 + vertex -282.04 153.387 407.272 + endloop + endfacet + facet normal -0.0651144 -0.428115 0.901375 + outer loop + vertex -281.84 157.514 409.247 + vertex -285.275 158.047 409.252 + vertex -282.04 153.387 407.272 + endloop + endfacet + facet normal -0.0637413 -0.428208 0.901429 + outer loop + vertex -274.582 156.243 409.157 + vertex -281.84 157.514 409.247 + vertex -282.04 153.387 407.272 + endloop + endfacet + facet normal -0.0634337 -0.42883 0.901155 + outer loop + vertex -282.04 153.387 407.272 + vertex -263.764 150.639 407.251 + vertex -274.582 156.243 409.157 + endloop + endfacet + facet normal -0.0640955 -0.429916 0.900591 + outer loop + vertex -267.75 155.37 409.226 + vertex -274.582 156.243 409.157 + vertex -263.764 150.639 407.251 + endloop + endfacet + facet normal -0.0627114 -0.428977 0.901136 + outer loop + vertex -264.133 154.833 409.222 + vertex -267.75 155.37 409.226 + vertex -263.764 150.639 407.251 + endloop + endfacet + facet normal -0.0608429 -0.428892 0.901305 + outer loop + vertex -256.717 153.583 409.128 + vertex -264.133 154.833 409.222 + vertex -263.764 150.639 407.251 + endloop + endfacet + facet normal -0.0602502 -0.429999 0.900817 + outer loop + vertex -263.764 150.639 407.251 + vertex -245.377 147.988 407.215 + vertex -256.717 153.583 409.128 + endloop + endfacet + facet normal -0.0612751 -0.431764 0.899903 + outer loop + vertex -249.612 152.667 409.172 + vertex -256.717 153.583 409.128 + vertex -245.377 147.988 407.215 + endloop + endfacet + facet normal -0.0593328 -0.430345 0.900712 + outer loop + vertex -246.046 152.179 409.174 + vertex -249.612 152.667 409.172 + vertex -245.377 147.988 407.215 + endloop + endfacet + facet normal -0.0566935 -0.430065 0.901016 + outer loop + vertex -238.773 151.114 409.123 + vertex -246.046 152.179 409.174 + vertex -245.377 147.988 407.215 + endloop + endfacet + facet normal -0.0561553 -0.430961 0.900621 + outer loop + vertex -245.377 147.988 407.215 + vertex -226.566 145.484 407.19 + vertex -238.773 151.114 409.123 + endloop + endfacet + facet normal -0.056614 -0.431807 0.900188 + outer loop + vertex -231.222 150.367 409.24 + vertex -238.773 151.114 409.123 + vertex -226.566 145.484 407.19 + endloop + endfacet + facet normal -0.0534614 -0.429371 0.901545 + outer loop + vertex -225.271 149.957 409.397 + vertex -231.222 150.367 409.24 + vertex -226.566 145.484 407.19 + endloop + endfacet + facet normal -0.0531838 -0.429442 0.901527 + outer loop + vertex -218.508 147.986 408.857 + vertex -225.271 149.957 409.397 + vertex -226.566 145.484 407.19 + endloop + endfacet + facet normal -0.0519273 -0.432548 0.900114 + outer loop + vertex -226.566 145.484 407.19 + vertex -208.168 143.211 407.159 + vertex -218.508 147.986 408.857 + endloop + endfacet + facet normal -0.0513683 -0.431524 0.900638 + outer loop + vertex -213.242 147.969 409.15 + vertex -218.508 147.986 408.857 + vertex -208.168 143.211 407.159 + endloop + endfacet + facet normal -0.0488155 -0.429305 0.901839 + outer loop + vertex -207.73 147.822 409.378 + vertex -213.242 147.969 409.15 + vertex -208.168 143.211 407.159 + endloop + endfacet + facet normal -0.0486575 -0.429321 0.901841 + outer loop + vertex -200.509 145.924 408.864 + vertex -207.73 147.822 409.378 + vertex -208.168 143.211 407.159 + endloop + endfacet + facet normal -0.0472753 -0.432357 0.900462 + outer loop + vertex -208.168 143.211 407.159 + vertex -189.635 141.247 407.189 + vertex -200.509 145.924 408.864 + endloop + endfacet + facet normal -0.0471476 -0.432106 0.90059 + outer loop + vertex -195.238 146.022 409.187 + vertex -200.509 145.924 408.864 + vertex -189.635 141.247 407.189 + endloop + endfacet + facet normal -0.0446753 -0.429732 0.90185 + outer loop + vertex -189.823 145.966 409.429 + vertex -195.238 146.022 409.187 + vertex -189.635 141.247 407.189 + endloop + endfacet + facet normal -0.0442205 -0.429726 0.901876 + outer loop + vertex -181.823 144.163 408.962 + vertex -189.823 145.966 409.429 + vertex -189.635 141.247 407.189 + endloop + endfacet + facet normal -0.0428597 -0.432581 0.900576 + outer loop + vertex -189.635 141.247 407.189 + vertex -170.239 139.342 407.197 + vertex -181.823 144.163 408.962 + endloop + endfacet + facet normal -0.0422392 -0.431322 0.901209 + outer loop + vertex -174.333 144.448 409.449 + vertex -181.823 144.163 408.962 + vertex -170.239 139.342 407.197 + endloop + endfacet + facet normal -0.0420128 -0.431176 0.901289 + outer loop + vertex -169.111 143.409 409.196 + vertex -174.333 144.448 409.449 + vertex -170.239 139.342 407.197 + endloop + endfacet + facet normal -0.0393539 -0.43182 0.901101 + outer loop + vertex -163.35 142.251 408.892 + vertex -169.111 143.409 409.196 + vertex -170.239 139.342 407.197 + endloop + endfacet + facet normal -0.0384369 -0.433535 0.900317 + outer loop + vertex -170.239 139.342 407.197 + vertex -151.541 137.651 407.181 + vertex -163.35 142.251 408.892 + endloop + endfacet + facet normal -0.0374884 -0.431482 0.901342 + outer loop + vertex -156.662 142.715 409.393 + vertex -163.35 142.251 408.892 + vertex -151.541 137.651 407.181 + endloop + endfacet + facet normal -0.0378447 -0.431774 0.901188 + outer loop + vertex -151.136 141.78 409.176 + vertex -156.662 142.715 409.393 + vertex -151.541 137.651 407.181 + endloop + endfacet + facet normal -0.034923 -0.432053 0.901172 + outer loop + vertex -145.204 140.676 408.877 + vertex -151.136 141.78 409.176 + vertex -151.541 137.651 407.181 + endloop + endfacet + facet normal -0.0337183 -0.434061 0.900252 + outer loop + vertex -151.541 137.651 407.181 + vertex -132.691 136.222 407.198 + vertex -145.204 140.676 408.877 + endloop + endfacet + facet normal -0.0329493 -0.432241 0.901156 + outer loop + vertex -138.873 141.326 409.42 + vertex -145.204 140.676 408.877 + vertex -132.691 136.222 407.198 + endloop + endfacet + facet normal -0.0329267 -0.432219 0.901167 + outer loop + vertex -132.754 140.507 409.251 + vertex -138.873 141.326 409.42 + vertex -132.691 136.222 407.198 + endloop + endfacet + facet normal -0.0295978 -0.432225 0.90128 + outer loop + vertex -124.738 139.676 409.116 + vertex -132.754 140.507 409.251 + vertex -132.691 136.222 407.198 + endloop + endfacet + facet normal -0.0289857 -0.433346 0.900761 + outer loop + vertex -132.691 136.222 407.198 + vertex -113.713 134.956 407.2 + vertex -124.738 139.676 409.116 + endloop + endfacet + facet normal -0.0296355 -0.434608 0.900132 + outer loop + vertex -117.83 139.295 409.16 + vertex -124.738 139.676 409.116 + vertex -113.713 134.956 407.2 + endloop + endfacet + facet normal -0.0269527 -0.43255 0.901207 + outer loop + vertex -114.248 139.061 409.154 + vertex -117.83 139.295 409.16 + vertex -113.713 134.956 407.2 + endloop + endfacet + facet normal -0.0242795 -0.432295 0.901405 + outer loop + vertex -106.76 138.505 409.089 + vertex -114.248 139.061 409.154 + vertex -113.713 134.956 407.2 + endloop + endfacet + facet normal -0.0237854 -0.433072 0.901046 + outer loop + vertex -113.713 134.956 407.2 + vertex -95.1637 133.955 407.209 + vertex -106.76 138.505 409.089 + endloop + endfacet + facet normal -0.0245771 -0.434747 0.900217 + outer loop + vertex -99.7925 138.269 409.165 + vertex -106.76 138.505 409.089 + vertex -95.1637 133.955 407.209 + endloop + endfacet + facet normal -0.0222269 -0.4327 0.901264 + outer loop + vertex -96.1415 138.099 409.174 + vertex -99.7925 138.269 409.165 + vertex -95.1637 133.955 407.209 + endloop + endfacet + facet normal -0.0195403 -0.432208 0.901562 + outer loop + vertex -88.4937 137.679 409.138 + vertex -96.1415 138.099 409.174 + vertex -95.1637 133.955 407.209 + endloop + endfacet + facet normal -0.0188649 -0.433182 0.901109 + outer loop + vertex -95.1637 133.955 407.209 + vertex -75.6646 133.122 407.216 + vertex -88.4937 137.679 409.138 + endloop + endfacet + facet normal -0.0193954 -0.43442 0.900502 + outer loop + vertex -80.7965 137.617 409.274 + vertex -88.4937 137.679 409.138 + vertex -75.6646 133.122 407.216 + endloop + endfacet + facet normal -0.0164839 -0.431716 0.901859 + outer loop + vertex -74.7263 137.695 409.423 + vertex -80.7965 137.617 409.274 + vertex -75.6646 133.122 407.216 + endloop + endfacet + facet normal -0.0158275 -0.43183 0.901816 + outer loop + vertex -67.6355 136.293 408.876 + vertex -74.7263 137.695 409.423 + vertex -75.6646 133.122 407.216 + endloop + endfacet + facet normal -0.0142508 -0.435031 0.900303 + outer loop + vertex -75.6646 133.122 407.216 + vertex -56.204 132.478 407.213 + vertex -67.6355 136.293 408.876 + endloop + endfacet + facet normal -0.0138818 -0.434119 0.900748 + outer loop + vertex -62.1883 136.705 409.158 + vertex -67.6355 136.293 408.876 + vertex -56.204 132.478 407.213 + endloop + endfacet + facet normal -0.0115499 -0.431427 0.902074 + outer loop + vertex -56.666 137.022 409.38 + vertex -62.1883 136.705 409.158 + vertex -56.204 132.478 407.213 + endloop + endfacet + facet normal -0.011165 -0.431397 0.902093 + outer loop + vertex -48.7544 135.912 408.947 + vertex -56.666 137.022 409.38 + vertex -56.204 132.478 407.213 + endloop + endfacet + facet normal -0.00944966 -0.4344 0.90067 + outer loop + vertex -56.204 132.478 407.213 + vertex -35.933 132.64 407.504 + vertex -48.7544 135.912 408.947 + endloop + endfacet + facet normal -0.00943598 -0.434356 0.900692 + outer loop + vertex -43.5012 136.504 409.288 + vertex -48.7544 135.912 408.947 + vertex -35.933 132.64 407.504 + endloop + endfacet + facet normal -0.00769052 -0.431564 0.902049 + outer loop + vertex -39.0309 137.014 409.57 + vertex -43.5012 136.504 409.288 + vertex -35.933 132.64 407.504 + endloop + endfacet + facet normal -0.00778506 -0.431619 0.902023 + outer loop + vertex -33.5449 136.477 409.361 + vertex -39.0309 137.014 409.57 + vertex -35.933 132.64 407.504 + endloop + endfacet + facet normal -0.00569869 -0.432679 0.90153 + outer loop + vertex -25.4623 135.982 409.174 + vertex -33.5449 136.477 409.361 + vertex -35.933 132.64 407.504 + endloop + endfacet + facet normal -0.00542411 -0.433374 0.901198 + outer loop + vertex -35.933 132.64 407.504 + vertex -14.7786 131.795 407.225 + vertex -25.4623 135.982 409.174 + endloop + endfacet + facet normal -0.00557872 -0.433695 0.901042 + outer loop + vertex -18.1079 135.839 409.151 + vertex -25.4623 135.982 409.174 + vertex -14.7786 131.795 407.225 + endloop + endfacet + facet normal -0.00342188 -0.432255 0.901745 + outer loop + vertex -14.4436 135.775 409.134 + vertex -18.1079 135.839 409.151 + vertex -14.7786 131.795 407.225 + endloop + endfacet + facet normal -0.00132596 -0.4324 0.901681 + outer loop + vertex -7.14643 135.682 409.1 + vertex -14.4436 135.775 409.134 + vertex -14.7786 131.795 407.225 + endloop + endfacet + facet normal -0.00111151 -0.432742 0.901517 + outer loop + vertex -14.7786 131.795 407.225 + vertex 4.68664 131.7 407.203 + vertex -7.14643 135.682 409.1 + endloop + endfacet + facet normal -0.00103013 -0.432546 0.901611 + outer loop + vertex 0.436751 135.936 409.231 + vertex -7.14643 135.682 409.1 + vertex 4.68664 131.7 407.203 + endloop + endfacet + facet normal 0.00108749 -0.430817 0.902439 + outer loop + vertex 6.36578 136.345 409.419 + vertex 0.436751 135.936 409.231 + vertex 4.68664 131.7 407.203 + endloop + endfacet + facet normal 0.00149187 -0.430936 0.902381 + outer loop + vertex 13.1755 135.237 408.878 + vertex 6.36578 136.345 409.419 + vertex 4.68664 131.7 407.203 + endloop + endfacet + facet normal 0.00273367 -0.433364 0.901215 + outer loop + vertex 4.68664 131.7 407.203 + vertex 23.4656 131.737 407.164 + vertex 13.1755 135.237 408.878 + endloop + endfacet + facet normal 0.00307718 -0.432546 0.901607 + outer loop + vertex 18.5829 135.883 409.17 + vertex 13.1755 135.237 408.878 + vertex 23.4656 131.737 407.164 + endloop + endfacet + facet normal 0.00521133 -0.430501 0.902575 + outer loop + vertex 24.2746 136.396 409.382 + vertex 18.5829 135.883 409.17 + vertex 23.4656 131.737 407.164 + endloop + endfacet + facet normal 0.00515268 -0.430493 0.902579 + outer loop + vertex 31.5222 135.398 408.864 + vertex 24.2746 136.396 409.382 + vertex 23.4656 131.737 407.164 + endloop + endfacet + facet normal 0.00676188 -0.433386 0.901183 + outer loop + vertex 23.4656 131.737 407.164 + vertex 42.2262 132.047 407.172 + vertex 31.5222 135.398 408.864 + endloop + endfacet + facet normal 0.00691968 -0.43298 0.901377 + outer loop + vertex 36.9536 136.129 409.173 + vertex 31.5222 135.398 408.864 + vertex 42.2262 132.047 407.172 + endloop + endfacet + facet normal 0.00923272 -0.430552 0.902519 + outer loop + vertex 42.6314 136.746 409.41 + vertex 36.9536 136.129 409.173 + vertex 42.2262 132.047 407.172 + endloop + endfacet + facet normal 0.00949511 -0.430569 0.902508 + outer loop + vertex 50.6366 135.923 408.933 + vertex 42.6314 136.746 409.41 + vertex 42.2262 132.047 407.172 + endloop + endfacet + facet normal 0.011074 -0.433376 0.901145 + outer loop + vertex 42.2262 132.047 407.172 + vertex 61.8628 132.543 407.17 + vertex 50.6366 135.923 408.933 + endloop + endfacet + facet normal 0.0117373 -0.43161 0.901984 + outer loop + vertex 58.5061 137.121 409.404 + vertex 50.6366 135.923 408.933 + vertex 61.8628 132.543 407.17 + endloop + endfacet + facet normal 0.0117284 -0.431616 0.901981 + outer loop + vertex 63.5808 136.755 409.163 + vertex 58.5061 137.121 409.404 + vertex 61.8628 132.543 407.17 + endloop + endfacet + facet normal 0.0146505 -0.432571 0.901481 + outer loop + vertex 69.3186 136.343 408.872 + vertex 63.5808 136.755 409.163 + vertex 61.8628 132.543 407.17 + endloop + endfacet + facet normal 0.0157706 -0.434372 0.900595 + outer loop + vertex 61.8628 132.543 407.17 + vertex 81.1147 133.323 407.209 + vertex 69.3186 136.343 408.872 + endloop + endfacet + facet normal 0.0164957 -0.432127 0.901662 + outer loop + vertex 76.1161 137.757 409.425 + vertex 69.3186 136.343 408.872 + vertex 81.1147 133.323 407.209 + endloop + endfacet + facet normal 0.0167364 -0.431906 0.901763 + outer loop + vertex 81.9991 137.672 409.276 + vertex 76.1161 137.757 409.425 + vertex 81.1147 133.323 407.209 + endloop + endfacet + facet normal 0.01972 -0.432377 0.901477 + outer loop + vertex 89.9938 137.759 409.142 + vertex 81.9991 137.672 409.276 + vertex 81.1147 133.323 407.209 + endloop + endfacet + facet normal 0.0202701 -0.433283 0.90103 + outer loop + vertex 81.1147 133.323 407.209 + vertex 100.509 134.263 407.224 + vertex 89.9938 137.759 409.142 + endloop + endfacet + facet normal 0.0200397 -0.433834 0.90077 + outer loop + vertex 97.0499 138.174 409.185 + vertex 89.9938 137.759 409.142 + vertex 100.509 134.263 407.224 + endloop + endfacet + facet normal 0.0222714 -0.432222 0.901492 + outer loop + vertex 100.677 138.367 409.188 + vertex 97.0499 138.174 409.185 + vertex 100.509 134.263 407.224 + endloop + endfacet + facet normal 0.0248807 -0.432283 0.901395 + outer loop + vertex 108.149 138.67 409.127 + vertex 100.677 138.367 409.188 + vertex 100.509 134.263 407.224 + endloop + endfacet + facet normal 0.0253033 -0.432885 0.901094 + outer loop + vertex 100.509 134.263 407.224 + vertex 119.282 135.363 407.226 + vertex 108.149 138.67 409.127 + endloop + endfacet + facet normal 0.0249889 -0.433718 0.900702 + outer loop + vertex 115.327 139.224 409.195 + vertex 108.149 138.67 409.127 + vertex 119.282 135.363 407.226 + endloop + endfacet + facet normal 0.0269502 -0.432081 0.901432 + outer loop + vertex 118.982 139.47 409.203 + vertex 115.327 139.224 409.195 + vertex 119.282 135.363 407.226 + endloop + endfacet + facet normal 0.0296456 -0.431888 0.90144 + outer loop + vertex 126.497 139.795 409.112 + vertex 118.982 139.47 409.203 + vertex 119.282 135.363 407.226 + endloop + endfacet + facet normal 0.0301248 -0.43253 0.901116 + outer loop + vertex 119.282 135.363 407.226 + vertex 138.011 136.638 407.211 + vertex 126.497 139.795 409.112 + endloop + endfacet + facet normal 0.0296063 -0.434005 0.900424 + outer loop + vertex 133.669 140.428 409.181 + vertex 126.497 139.795 409.112 + vertex 138.011 136.638 407.211 + endloop + endfacet + facet normal 0.0318794 -0.431889 0.901363 + outer loop + vertex 137.338 140.68 409.172 + vertex 133.669 140.428 409.181 + vertex 138.011 136.638 407.211 + endloop + endfacet + facet normal 0.0343171 -0.431524 0.901449 + outer loop + vertex 144.715 141.168 409.125 + vertex 137.338 140.68 409.172 + vertex 138.011 136.638 407.211 + endloop + endfacet + facet normal 0.0349644 -0.432312 0.901046 + outer loop + vertex 138.011 136.638 407.211 + vertex 157.228 138.158 407.195 + vertex 144.715 141.168 409.125 + endloop + endfacet + facet normal 0.0346819 -0.433215 0.900623 + outer loop + vertex 152.359 142.043 409.251 + vertex 144.715 141.168 409.125 + vertex 157.228 138.158 407.195 + endloop + endfacet + facet normal 0.0372123 -0.430643 0.901755 + outer loop + vertex 158.174 142.866 409.405 + vertex 152.359 142.043 409.251 + vertex 157.228 138.158 407.195 + endloop + endfacet + facet normal 0.0379108 -0.430746 0.901676 + outer loop + vertex 165.228 142.313 408.844 + vertex 158.174 142.866 409.405 + vertex 157.228 138.158 407.195 + endloop + endfacet + facet normal 0.039778 -0.43374 0.90016 + outer loop + vertex 157.228 138.158 407.195 + vertex 175.994 139.795 407.155 + vertex 165.228 142.313 408.844 + endloop + endfacet + facet normal 0.039996 -0.43303 0.900492 + outer loop + vertex 170.38 143.414 409.144 + vertex 165.228 142.313 408.844 + vertex 175.994 139.795 407.155 + endloop + endfacet + facet normal 0.0421927 -0.43029 0.901704 + outer loop + vertex 175.514 144.441 409.394 + vertex 170.38 143.414 409.144 + vertex 175.994 139.795 407.155 + endloop + endfacet + facet normal 0.0426511 -0.430243 0.901705 + outer loop + vertex 183.525 144.257 408.928 + vertex 175.514 144.441 409.394 + vertex 175.994 139.795 407.155 + endloop + endfacet + facet normal 0.0443824 -0.432671 0.900459 + outer loop + vertex 175.994 139.795 407.155 + vertex 195.08 141.815 407.185 + vertex 183.525 144.257 408.928 + endloop + endfacet + facet normal 0.0449221 -0.430754 0.901351 + outer loop + vertex 190.952 146.051 409.414 + vertex 183.525 144.257 408.928 + vertex 195.08 141.815 407.185 + endloop + endfacet + facet normal 0.0448956 -0.430775 0.901342 + outer loop + vertex 196.208 146.13 409.191 + vertex 190.952 146.051 409.414 + vertex 195.08 141.815 407.185 + endloop + endfacet + facet normal 0.0478707 -0.431353 0.900913 + outer loop + vertex 201.952 146.143 408.892 + vertex 196.208 146.13 409.191 + vertex 195.08 141.815 407.185 + endloop + endfacet + facet normal 0.0488504 -0.432643 0.900241 + outer loop + vertex 195.08 141.815 407.185 + vertex 213.54 143.923 407.196 + vertex 201.952 146.143 408.892 + endloop + endfacet + facet normal 0.0494699 -0.430256 0.90135 + outer loop + vertex 208.653 148.016 409.418 + vertex 201.952 146.143 408.892 + vertex 213.54 143.923 407.196 + endloop + endfacet + facet normal 0.0492854 -0.430436 0.901275 + outer loop + vertex 214.179 148.219 409.213 + vertex 208.653 148.016 409.418 + vertex 213.54 143.923 407.196 + endloop + endfacet + facet normal 0.0519574 -0.430703 0.900997 + outer loop + vertex 220.047 148.284 408.905 + vertex 214.179 148.219 409.213 + vertex 213.54 143.923 407.196 + endloop + endfacet + facet normal 0.0529491 -0.431929 0.900352 + outer loop + vertex 213.54 143.923 407.196 + vertex 231.902 146.158 407.188 + vertex 220.047 148.284 408.905 + endloop + endfacet + facet normal 0.0535475 -0.429502 0.901477 + outer loop + vertex 226.624 150.162 409.41 + vertex 220.047 148.284 408.905 + vertex 231.902 146.158 407.188 + endloop + endfacet + facet normal 0.0533699 -0.429691 0.901397 + outer loop + vertex 232.245 150.401 409.191 + vertex 226.624 150.162 409.41 + vertex 231.902 146.158 407.188 + endloop + endfacet + facet normal 0.0561014 -0.429807 0.901176 + outer loop + vertex 238.147 150.533 408.886 + vertex 232.245 150.401 409.191 + vertex 231.902 146.158 407.188 + endloop + endfacet + facet normal 0.0572078 -0.431117 0.900481 + outer loop + vertex 231.902 146.158 407.188 + vertex 250.502 148.626 407.188 + vertex 238.147 150.533 408.886 + endloop + endfacet + facet normal 0.0577952 -0.428421 0.901729 + outer loop + vertex 244.447 152.508 409.421 + vertex 238.147 150.533 408.886 + vertex 250.502 148.626 407.188 + endloop + endfacet + facet normal 0.0578541 -0.428348 0.90176 + outer loop + vertex 250.522 152.99 409.26 + vertex 244.447 152.508 409.421 + vertex 250.502 148.626 407.188 + endloop + endfacet + facet normal 0.0604493 -0.428291 0.901617 + outer loop + vertex 258.416 153.787 409.109 + vertex 250.522 152.99 409.26 + vertex 250.502 148.626 407.188 + endloop + endfacet + facet normal 0.060938 -0.428918 0.901286 + outer loop + vertex 250.502 148.626 407.188 + vertex 269.235 151.269 407.18 + vertex 258.416 153.787 409.109 + endloop + endfacet + facet normal 0.0607105 -0.429642 0.900956 + outer loop + vertex 265.233 154.842 409.153 + vertex 258.416 153.787 409.109 + vertex 269.235 151.269 407.18 + endloop + endfacet + facet normal 0.0623509 -0.428138 0.90156 + outer loop + vertex 268.734 155.319 409.137 + vertex 265.233 154.842 409.153 + vertex 269.235 151.269 407.18 + endloop + endfacet + facet normal 0.0640054 -0.427926 0.901545 + outer loop + vertex 275.806 156.254 409.079 + vertex 268.734 155.319 409.137 + vertex 269.235 151.269 407.18 + endloop + endfacet + facet normal 0.0652372 -0.429273 0.900816 + outer loop + vertex 269.235 151.269 407.18 + vertex 287.26 154.089 407.218 + vertex 275.806 156.254 409.079 + endloop + endfacet + facet normal 0.0645776 -0.431775 0.899667 + outer loop + vertex 282.513 157.385 409.14 + vertex 275.806 156.254 409.079 + vertex 287.26 154.089 407.218 + endloop + endfacet + facet normal 0.0657803 -0.430381 0.900247 + outer loop + vertex 285.918 157.937 409.155 + vertex 282.513 157.385 409.14 + vertex 287.26 154.089 407.218 + endloop + endfacet + facet normal 0.0684517 -0.429549 0.900446 + outer loop + vertex 293.194 159.052 409.134 + vertex 285.918 157.937 409.155 + vertex 287.26 154.089 407.218 + endloop + endfacet + facet normal 0.0706184 -0.43168 0.899258 + outer loop + vertex 287.26 154.089 407.218 + vertex 306.239 157.319 407.278 + vertex 293.194 159.052 409.134 + endloop + endfacet + facet normal 0.0699262 -0.435153 0.897637 + outer loop + vertex 300.671 160.507 409.257 + vertex 293.194 159.052 409.134 + vertex 306.239 157.319 407.278 + endloop + endfacet + facet normal 0.0729416 -0.430985 0.899406 + outer loop + vertex 306.802 161.852 409.404 + vertex 300.671 160.507 409.257 + vertex 306.239 157.319 407.278 + endloop + endfacet + facet normal 0.0742455 -0.431076 0.899256 + outer loop + vertex 314.126 161.937 408.841 + vertex 306.802 161.852 409.404 + vertex 306.239 157.319 407.278 + endloop + endfacet + facet normal 0.0782039 -0.436788 0.896159 + outer loop + vertex 306.239 157.319 407.278 + vertex 325.295 160.509 407.17 + vertex 314.126 161.937 408.841 + endloop + endfacet + facet normal 0.0782844 -0.436381 0.89635 + outer loop + vertex 320.073 163.588 409.125 + vertex 314.126 161.937 408.841 + vertex 325.295 160.509 407.17 + endloop + endfacet + facet normal 0.0823349 -0.430948 0.898613 + outer loop + vertex 327.643 165.536 409.366 + vertex 320.073 163.588 409.125 + vertex 325.295 160.509 407.17 + endloop + endfacet + facet normal 0.0872046 -0.432662 0.897329 + outer loop + vertex 327.643 165.536 409.366 + vertex 325.295 160.509 407.17 + vertex 337.958 165.391 408.293 + endloop + endfacet + facet normal 0.0869835 -0.436128 0.895671 + outer loop + vertex 335.397 167.706 409.669 + vertex 327.643 165.536 409.366 + vertex 337.958 165.391 408.293 + endloop + endfacet + facet normal 0.095779 -0.428149 0.898618 + outer loop + vertex 344.24 169.802 409.725 + vertex 335.397 167.706 409.669 + vertex 337.958 165.391 408.293 + endloop + endfacet + facet normal 0.0993692 -0.432462 0.89616 + outer loop + vertex 337.958 165.391 408.293 + vertex 349.904 167.893 408.176 + vertex 344.24 169.802 409.725 + endloop + endfacet + facet normal 0.108098 -0.41312 0.904238 + outer loop + vertex 355.857 171.812 409.255 + vertex 344.24 169.802 409.725 + vertex 349.904 167.893 408.176 + endloop + endfacet + facet normal 0.115202 -0.422477 0.899022 + outer loop + vertex 349.904 167.893 408.176 + vertex 358.075 169.268 407.775 + vertex 355.857 171.812 409.255 + endloop + endfacet + facet normal 0.135049 -0.407569 0.903133 + outer loop + vertex 358.075 169.268 407.775 + vertex 363.942 171.493 407.902 + vertex 355.857 171.812 409.255 + endloop + endfacet + facet normal 0.134368 -0.413604 0.900487 + outer loop + vertex 365.276 174.667 409.161 + vertex 355.857 171.812 409.255 + vertex 363.942 171.493 407.902 + endloop + endfacet + facet normal 0.159661 -0.42119 0.892809 + outer loop + vertex 363.942 171.493 407.902 + vertex 370.723 173.656 407.71 + vertex 365.276 174.667 409.161 + endloop + endfacet + facet normal 0.162338 -0.412132 0.896545 + outer loop + vertex 374.142 177.503 408.859 + vertex 365.276 174.667 409.161 + vertex 370.723 173.656 407.71 + endloop + endfacet + facet normal 0.178166 -0.423678 0.888118 + outer loop + vertex 370.723 173.656 407.71 + vertex 375.488 174.859 407.327 + vertex 374.142 177.503 408.859 + endloop + endfacet + facet normal 0.193746 -0.415967 0.888501 + outer loop + vertex 375.488 174.859 407.327 + vertex 378.001 176.242 407.427 + vertex 374.142 177.503 408.859 + endloop + endfacet + facet normal 0.19762 -0.407563 0.891537 + outer loop + vertex 379.276 178.101 407.994 + vertex 374.142 177.503 408.859 + vertex 378.001 176.242 407.427 + endloop + endfacet + facet normal 0.207654 -0.412983 0.886749 + outer loop + vertex 379.669 176.424 407.121 + vertex 379.276 178.101 407.994 + vertex 378.001 176.242 407.427 + endloop + endfacet + facet normal 0.20786 -0.42249 0.882211 + outer loop + vertex 379.77 175.02 406.425 + vertex 379.669 176.424 407.121 + vertex 378.001 176.242 407.427 + endloop + endfacet + facet normal 0.207645 -0.422743 0.88214 + outer loop + vertex 378.001 176.242 407.427 + vertex 378.416 173.604 406.065 + vertex 379.77 175.02 406.425 + endloop + endfacet + facet normal 0.215115 -0.428693 0.877467 + outer loop + vertex 380.449 172.516 405.035 + vertex 379.77 175.02 406.425 + vertex 378.416 173.604 406.065 + endloop + endfacet + facet normal 0.216605 -0.42655 0.878144 + outer loop + vertex 378.416 173.604 406.065 + vertex 379.16 169.819 404.043 + vertex 380.449 172.516 405.035 + endloop + endfacet + facet normal 0.223006 -0.428645 0.875518 + outer loop + vertex 380.892 170.104 403.742 + vertex 380.449 172.516 405.035 + vertex 379.16 169.819 404.043 + endloop + endfacet + facet normal 0.223114 -0.430078 0.874787 + outer loop + vertex 380.961 167.37 402.38 + vertex 380.892 170.104 403.742 + vertex 379.16 169.819 404.043 + endloop + endfacet + facet normal 0.229965 -0.425391 0.875305 + outer loop + vertex 379.16 169.819 404.043 + vertex 379.221 165.475 401.916 + vertex 380.961 167.37 402.38 + endloop + endfacet + facet normal 0.233085 -0.427769 0.873319 + outer loop + vertex 380.931 163.754 400.617 + vertex 380.961 167.37 402.38 + vertex 379.221 165.475 401.916 + endloop + endfacet + facet normal 0.234752 -0.426312 0.873584 + outer loop + vertex 379.221 165.475 401.916 + vertex 379.453 161.492 399.91 + vertex 380.931 163.754 400.617 + endloop + endfacet + facet normal 0.240777 -0.429282 0.870484 + outer loop + vertex 381.271 160.555 398.945 + vertex 380.931 163.754 400.617 + vertex 379.453 161.492 399.91 + endloop + endfacet + facet normal 0.243973 -0.424554 0.871912 + outer loop + vertex 379.453 161.492 399.91 + vertex 380.045 157.475 397.788 + vertex 381.271 160.555 398.945 + endloop + endfacet + facet normal 0.24938 -0.425886 0.86973 + outer loop + vertex 381.533 157.917 397.578 + vertex 381.271 160.555 398.945 + vertex 380.045 157.475 397.788 + endloop + endfacet + facet normal 0.248511 -0.421928 0.871905 + outer loop + vertex 381.65 155.555 396.402 + vertex 381.533 157.917 397.578 + vertex 380.045 157.475 397.788 + endloop + endfacet + facet normal 0.251017 -0.419991 0.872123 + outer loop + vertex 380.045 157.475 397.788 + vertex 380.347 153.418 395.747 + vertex 381.65 155.555 396.402 + endloop + endfacet + facet normal 0.249417 -0.419264 0.872931 + outer loop + vertex 381.838 153.363 395.295 + vertex 381.65 155.555 396.402 + vertex 380.347 153.418 395.747 + endloop + endfacet + facet normal 0.250261 -0.414214 0.875098 + outer loop + vertex 381.834 151.787 394.55 + vertex 381.838 153.363 395.295 + vertex 380.347 153.418 395.747 + endloop + endfacet + facet normal 0.249736 -0.414651 0.875041 + outer loop + vertex 380.347 153.418 395.747 + vertex 380.67 149.623 393.857 + vertex 381.834 151.787 394.55 + endloop + endfacet + facet normal 0.248333 -0.414106 0.875698 + outer loop + vertex 382.336 149.864 393.498 + vertex 381.834 151.787 394.55 + vertex 380.67 149.623 393.857 + endloop + endfacet + facet normal 0.248158 -0.409804 0.877769 + outer loop + vertex 382.28 147.692 392.501 + vertex 382.336 149.864 393.498 + vertex 380.67 149.623 393.857 + endloop + endfacet + facet normal 0.247344 -0.410436 0.877703 + outer loop + vertex 380.67 149.623 393.857 + vertex 381.043 145.784 391.957 + vertex 382.28 147.692 392.501 + endloop + endfacet + facet normal 0.246709 -0.410118 0.87803 + outer loop + vertex 382.632 146.116 391.666 + vertex 382.28 147.692 392.501 + vertex 381.043 145.784 391.957 + endloop + endfacet + facet normal 0.246411 -0.407577 0.879297 + outer loop + vertex 382.787 143.867 390.579 + vertex 382.632 146.116 391.666 + vertex 381.043 145.784 391.957 + endloop + endfacet + facet normal 0.246218 -0.407738 0.879276 + outer loop + vertex 381.043 145.784 391.957 + vertex 381.198 142.048 390.181 + vertex 382.787 143.867 390.579 + endloop + endfacet + facet normal 0.24443 -0.406418 0.880385 + outer loop + vertex 383 140.921 389.16 + vertex 382.787 143.867 390.579 + vertex 381.198 142.048 390.181 + endloop + endfacet + facet normal 0.244421 -0.40643 0.880382 + outer loop + vertex 381.198 142.048 390.181 + vertex 381.955 138.43 388.301 + vertex 383 140.921 389.16 + endloop + endfacet + facet normal 0.245598 -0.406759 0.879903 + outer loop + vertex 383.48 139.373 388.311 + vertex 383 140.921 389.16 + vertex 381.955 138.43 388.301 + endloop + endfacet + facet normal 0.243942 -0.4041 0.881587 + outer loop + vertex 383.79 137.247 387.25 + vertex 383.48 139.373 388.311 + vertex 381.955 138.43 388.301 + endloop + endfacet + facet normal 0.2449 -0.402876 0.881882 + outer loop + vertex 381.955 138.43 388.301 + vertex 382.656 134.315 386.226 + vertex 383.79 137.247 387.25 + endloop + endfacet + facet normal 0.243269 -0.402468 0.882519 + outer loop + vertex 384.226 134.858 386.041 + vertex 383.79 137.247 387.25 + vertex 382.656 134.315 386.226 + endloop + endfacet + facet normal 0.242261 -0.398913 0.884408 + outer loop + vertex 384.594 132.503 384.878 + vertex 384.226 134.858 386.041 + vertex 382.656 134.315 386.226 + endloop + endfacet + facet normal 0.241508 -0.39963 0.884291 + outer loop + vertex 382.656 134.315 386.226 + vertex 383.324 130.203 384.185 + vertex 384.594 132.503 384.878 + endloop + endfacet + facet normal 0.238033 -0.39819 0.885881 + outer loop + vertex 385.056 130.254 383.743 + vertex 384.594 132.503 384.878 + vertex 383.324 130.203 384.185 + endloop + endfacet + facet normal 0.238267 -0.395257 0.887131 + outer loop + vertex 385.133 128.558 382.967 + vertex 385.056 130.254 383.743 + vertex 383.324 130.203 384.185 + endloop + endfacet + facet normal 0.235703 -0.397756 0.886699 + outer loop + vertex 383.324 130.203 384.185 + vertex 383.773 126.58 382.441 + vertex 385.133 128.558 382.967 + endloop + endfacet + facet normal 0.23367 -0.396635 0.887738 + outer loop + vertex 385.893 126.01 381.628 + vertex 385.133 128.558 382.967 + vertex 383.773 126.58 382.441 + endloop + endfacet + facet normal 0.234187 -0.395341 0.888179 + outer loop + vertex 383.773 126.58 382.441 + vertex 384.957 122.928 380.503 + vertex 385.893 126.01 381.628 + endloop + endfacet + facet normal 0.232034 -0.394956 0.888915 + outer loop + vertex 386.619 123.628 380.38 + vertex 385.893 126.01 381.628 + vertex 384.957 122.928 380.503 + endloop + endfacet + facet normal 0.230775 -0.391656 0.890701 + outer loop + vertex 387.16 121.286 379.21 + vertex 386.619 123.628 380.38 + vertex 384.957 122.928 380.503 + endloop + endfacet + facet normal 0.22992 -0.392637 0.89049 + outer loop + vertex 384.957 122.928 380.503 + vertex 385.991 118.855 378.44 + vertex 387.16 121.286 379.21 + endloop + endfacet + facet normal 0.22624 -0.391345 0.892 + outer loop + vertex 387.76 119.055 378.079 + vertex 387.16 121.286 379.21 + vertex 385.991 118.855 378.44 + endloop + endfacet + facet normal 0.226175 -0.38844 0.893286 + outer loop + vertex 388.03 117.293 377.245 + vertex 387.76 119.055 378.079 + vertex 385.991 118.855 378.44 + endloop + endfacet + facet normal 0.223669 -0.391253 0.892689 + outer loop + vertex 385.991 118.855 378.44 + vertex 386.906 114.856 376.458 + vertex 388.03 117.293 377.245 + endloop + endfacet + facet normal 0.22105 -0.39038 0.893723 + outer loop + vertex 389.201 114.883 375.902 + vertex 388.03 117.293 377.245 + vertex 386.906 114.856 376.458 + endloop + endfacet + facet normal 0.221542 -0.384778 0.896027 + outer loop + vertex 386.906 114.856 376.458 + vertex 389.462 112.372 374.76 + vertex 389.201 114.883 375.902 + endloop + endfacet + facet normal 0.230135 -0.383206 0.894534 + outer loop + vertex 390.454 112.314 374.479 + vertex 389.201 114.883 375.902 + vertex 389.462 112.372 374.76 + endloop + endfacet + facet normal 0.230956 -0.378277 0.896418 + outer loop + vertex 389.462 112.372 374.76 + vertex 390.864 110.648 373.671 + vertex 390.454 112.314 374.479 + endloop + endfacet + facet normal 0.230926 -0.378287 0.896422 + outer loop + vertex 391.527 110.16 373.294 + vertex 390.454 112.314 374.479 + vertex 390.864 110.648 373.671 + endloop + endfacet + facet normal 0.234359 -0.374247 0.897226 + outer loop + vertex 390.864 110.648 373.671 + vertex 391.805 108.24 372.421 + vertex 391.527 110.16 373.294 + endloop + endfacet + facet normal 0.234635 -0.374185 0.89718 + outer loop + vertex 392.349 108.268 372.29 + vertex 391.527 110.16 373.294 + vertex 391.805 108.24 372.421 + endloop + endfacet + facet normal 0.234953 -0.367076 0.900029 + outer loop + vertex 393.044 106.758 371.493 + vertex 392.349 108.268 372.29 + vertex 391.805 108.24 372.421 + endloop + endfacet + facet normal 0.228922 -0.371861 0.899619 + outer loop + vertex 391.805 108.24 372.421 + vertex 393.236 105.108 370.762 + vertex 393.044 106.758 371.493 + endloop + endfacet + facet normal 0.215288 -0.374455 0.901906 + outer loop + vertex 394.558 104.208 370.073 + vertex 393.044 106.758 371.493 + vertex 393.236 105.108 370.762 + endloop + endfacet + facet normal 0.21521 -0.374553 0.901884 + outer loop + vertex 393.236 105.108 370.762 + vertex 395.298 101.791 368.892 + vertex 394.558 104.208 370.073 + endloop + endfacet + facet normal 0.207608 -0.377209 0.902559 + outer loop + vertex 396.025 101.883 368.764 + vertex 394.558 104.208 370.073 + vertex 395.298 101.791 368.892 + endloop + endfacet + facet normal 0.207372 -0.372551 0.904546 + outer loop + vertex 397.391 99.888 367.629 + vertex 396.025 101.883 368.764 + vertex 395.298 101.791 368.892 + endloop + endfacet + facet normal 0.197436 -0.382265 0.902714 + outer loop + vertex 395.298 101.791 368.892 + vertex 397.285 98.6298 367.119 + vertex 397.391 99.888 367.629 + endloop + endfacet + facet normal 0.190285 -0.38228 0.904242 + outer loop + vertex 399.086 97.5381 366.279 + vertex 397.391 99.888 367.629 + vertex 397.285 98.6298 367.119 + endloop + endfacet + facet normal 0.186376 -0.387608 0.902787 + outer loop + vertex 397.285 98.6298 367.119 + vertex 399.2 96.0452 365.614 + vertex 399.086 97.5381 366.279 + endloop + endfacet + facet normal 0.18007 -0.388491 0.903687 + outer loop + vertex 400.826 95.4702 365.043 + vertex 399.086 97.5381 366.279 + vertex 399.2 96.0452 365.614 + endloop + endfacet + facet normal 0.180022 -0.388593 0.903652 + outer loop + vertex 399.2 96.0452 365.614 + vertex 400.937 93.9263 364.357 + vertex 400.826 95.4702 365.043 + endloop + endfacet + facet normal 0.184815 -0.387944 0.902963 + outer loop + vertex 403.337 92.4562 363.234 + vertex 400.826 95.4702 365.043 + vertex 400.937 93.9263 364.357 + endloop + endfacet + facet normal 0.175901 -0.399878 0.899531 + outer loop + vertex 400.937 93.9263 364.357 + vertex 401.014 92.6217 363.762 + vertex 403.337 92.4562 363.234 + endloop + endfacet + facet normal 0.168237 -0.444549 0.879814 + outer loop + vertex 397.798 91.1067 363.611 + vertex 403.337 92.4562 363.234 + vertex 401.014 92.6217 363.762 + endloop + endfacet + facet normal 0.219694 -0.546664 0.808018 + outer loop + vertex 401.014 92.6217 363.762 + vertex 399.201 91.8941 363.762 + vertex 397.798 91.1067 363.611 + endloop + endfacet + facet normal 0.17061 -0.470318 0.865848 + outer loop + vertex 399.201 91.8941 363.762 + vertex 395.234 90.5026 363.788 + vertex 397.798 91.1067 363.611 + endloop + endfacet + facet normal 0.167787 -0.462181 0.870768 + outer loop + vertex 399.201 91.8941 363.762 + vertex 397.017 91.3816 363.911 + vertex 395.234 90.5026 363.788 + endloop + endfacet + facet normal 0.154051 -0.436506 0.886414 + outer loop + vertex 397.017 91.3816 363.911 + vertex 391.826 89.7591 364.014 + vertex 395.234 90.5026 363.788 + endloop + endfacet + facet normal 0.158825 -0.462735 0.872153 + outer loop + vertex 395.234 90.5026 363.788 + vertex 391.826 89.7591 364.014 + vertex 390.85 89.1829 363.886 + endloop + endfacet + facet normal 0.140315 -0.435209 0.889328 + outer loop + vertex 390.85 89.1829 363.886 + vertex 391.826 89.7591 364.014 + vertex 383.932 87.4585 364.134 + endloop + endfacet + facet normal 0.159112 -0.517611 0.840692 + outer loop + vertex 390.85 89.1829 363.886 + vertex 383.932 87.4585 364.134 + vertex 389.155 88.5455 363.815 + endloop + endfacet + facet normal 0.147715 -0.461354 0.874833 + outer loop + vertex 385.747 89.0459 364.665 + vertex 383.932 87.4585 364.134 + vertex 391.826 89.7591 364.014 + endloop + endfacet + facet normal 0.145911 -0.432288 0.889852 + outer loop + vertex 393.466 90.6883 364.197 + vertex 385.747 89.0459 364.665 + vertex 391.826 89.7591 364.014 + endloop + endfacet + facet normal 0.147298 -0.439943 0.885863 + outer loop + vertex 393.466 90.6883 364.197 + vertex 392.179 91.2802 364.705 + vertex 385.747 89.0459 364.665 + endloop + endfacet + facet normal 0.150224 -0.448282 0.881179 + outer loop + vertex 385.351 91.1125 365.784 + vertex 385.747 89.0459 364.665 + vertex 392.179 91.2802 364.705 + endloop + endfacet + facet normal 0.151153 -0.430567 0.889812 + outer loop + vertex 392.333 92.4598 365.249 + vertex 385.351 91.1125 365.784 + vertex 392.179 91.2802 364.705 + endloop + endfacet + facet normal 0.160962 -0.43097 0.887894 + outer loop + vertex 396.34 92.8651 364.72 + vertex 392.333 92.4598 365.249 + vertex 392.179 91.2802 364.705 + endloop + endfacet + facet normal 0.155218 -0.415965 0.896036 + outer loop + vertex 396.34 92.8651 364.72 + vertex 392.179 91.2802 364.705 + vertex 397.095 92.0519 364.212 + endloop + endfacet + facet normal 0.162218 -0.410319 0.897398 + outer loop + vertex 399.289 93.2341 364.356 + vertex 396.34 92.8651 364.72 + vertex 397.095 92.0519 364.212 + endloop + endfacet + facet normal 0.15907 -0.404848 0.900441 + outer loop + vertex 399.289 93.2341 364.356 + vertex 397.095 92.0519 364.212 + vertex 399.944 92.6687 363.986 + endloop + endfacet + facet normal 0.166328 -0.397669 0.902327 + outer loop + vertex 399.289 93.2341 364.356 + vertex 399.944 92.6687 363.986 + vertex 400.937 93.9263 364.357 + endloop + endfacet + facet normal 0.16728 -0.399934 0.901149 + outer loop + vertex 399.289 93.2341 364.356 + vertex 400.937 93.9263 364.357 + vertex 398.645 94.2863 364.942 + endloop + endfacet + facet normal 0.161587 -0.41903 0.893478 + outer loop + vertex 399.944 92.6687 363.986 + vertex 397.095 92.0519 364.212 + vertex 397.017 91.3816 363.911 + endloop + endfacet + facet normal 0.15376 -0.418793 0.89497 + outer loop + vertex 397.095 92.0519 364.212 + vertex 393.466 90.6883 364.197 + vertex 397.017 91.3816 363.911 + endloop + endfacet + facet normal 0.161729 -0.403109 0.900748 + outer loop + vertex 398.645 94.2863 364.942 + vertex 396.34 92.8651 364.72 + vertex 399.289 93.2341 364.356 + endloop + endfacet + facet normal 0.166854 -0.410732 0.896359 + outer loop + vertex 398.645 94.2863 364.942 + vertex 395.395 93.9628 365.399 + vertex 396.34 92.8651 364.72 + endloop + endfacet + facet normal 0.166669 -0.405409 0.898813 + outer loop + vertex 397.382 95.3437 365.653 + vertex 395.395 93.9628 365.399 + vertex 398.645 94.2863 364.942 + endloop + endfacet + facet normal 0.173252 -0.398724 0.900557 + outer loop + vertex 397.382 95.3437 365.653 + vertex 398.645 94.2863 364.942 + vertex 399.2 96.0452 365.614 + endloop + endfacet + facet normal 0.174128 -0.40106 0.89935 + outer loop + vertex 397.382 95.3437 365.653 + vertex 399.2 96.0452 365.614 + vertex 396.73 96.8033 366.43 + endloop + endfacet + facet normal 0.170431 -0.402699 0.899326 + outer loop + vertex 396.73 96.8033 366.43 + vertex 394.466 95.2988 366.186 + vertex 397.382 95.3437 365.653 + endloop + endfacet + facet normal 0.174062 -0.407685 0.896379 + outer loop + vertex 396.73 96.8033 366.43 + vertex 393.58 96.7785 367.031 + vertex 394.466 95.2988 366.186 + endloop + endfacet + facet normal 0.167092 -0.411598 0.895917 + outer loop + vertex 393.58 96.7785 367.031 + vertex 390.697 95.1753 366.832 + vertex 394.466 95.2988 366.186 + endloop + endfacet + facet normal 0.166564 -0.423103 0.890641 + outer loop + vertex 394.466 95.2988 366.186 + vertex 390.697 95.1753 366.832 + vertex 390.677 93.5612 366.069 + endloop + endfacet + facet normal 0.162451 -0.414457 0.895452 + outer loop + vertex 394.466 95.2988 366.186 + vertex 390.677 93.5612 366.069 + vertex 395.395 93.9628 365.399 + endloop + endfacet + facet normal 0.16255 -0.419807 0.892939 + outer loop + vertex 395.395 93.9628 365.399 + vertex 390.677 93.5612 366.069 + vertex 392.333 92.4598 365.249 + endloop + endfacet + facet normal 0.156286 -0.423719 0.892209 + outer loop + vertex 390.697 95.1753 366.832 + vertex 384.256 93.8684 367.339 + vertex 390.677 93.5612 366.069 + endloop + endfacet + facet normal 0.154223 -0.438552 0.885374 + outer loop + vertex 384.256 93.8684 367.339 + vertex 385.351 91.1125 365.784 + vertex 390.677 93.5612 366.069 + endloop + endfacet + facet normal 0.14377 -0.44257 0.885134 + outer loop + vertex 384.256 93.8684 367.339 + vertex 375.111 90.7121 367.247 + vertex 385.351 91.1125 365.784 + endloop + endfacet + facet normal 0.143141 -0.461377 0.875581 + outer loop + vertex 385.351 91.1125 365.784 + vertex 375.111 90.7121 367.247 + vertex 375.25 87.9894 365.789 + endloop + endfacet + facet normal 0.129259 -0.462829 0.876973 + outer loop + vertex 375.111 90.7121 367.247 + vertex 364.879 87.6492 367.138 + vertex 375.25 87.9894 365.789 + endloop + endfacet + facet normal 0.128636 -0.479779 0.867908 + outer loop + vertex 375.25 87.9894 365.789 + vertex 364.879 87.6492 367.138 + vertex 363.732 84.8022 365.735 + endloop + endfacet + facet normal 0.12413 -0.463654 0.877278 + outer loop + vertex 375.25 87.9894 365.789 + vertex 363.732 84.8022 365.735 + vertex 374.766 85.9223 364.765 + endloop + endfacet + facet normal 0.14047 -0.465716 0.873714 + outer loop + vertex 385.747 89.0459 364.665 + vertex 375.25 87.9894 365.789 + vertex 374.766 85.9223 364.765 + endloop + endfacet + facet normal 0.124065 -0.462474 0.87791 + outer loop + vertex 374.766 85.9223 364.765 + vertex 363.732 84.8022 365.735 + vertex 364.642 82.9981 364.656 + endloop + endfacet + facet normal 0.117647 -0.440702 0.889911 + outer loop + vertex 374.766 85.9223 364.765 + vertex 364.642 82.9981 364.656 + vertex 373.231 84.4972 364.262 + endloop + endfacet + facet normal 0.1372 -0.457719 0.878447 + outer loop + vertex 383.932 87.4585 364.134 + vertex 374.766 85.9223 364.765 + vertex 373.231 84.4972 364.262 + endloop + endfacet + facet normal 0.136353 -0.454581 0.880207 + outer loop + vertex 383.932 87.4585 364.134 + vertex 373.231 84.4972 364.262 + vertex 378.052 85.4362 364.001 + endloop + endfacet + facet normal 0.106621 -0.368749 0.923394 + outer loop + vertex 373.231 84.4972 364.262 + vertex 364.642 82.9981 364.656 + vertex 368.713 83.2447 364.284 + endloop + endfacet + facet normal 0.183848 -0.65051 0.73691 + outer loop + vertex 373.231 84.4972 364.262 + vertex 368.713 83.2447 364.284 + vertex 367.866 82.8852 364.178 + endloop + endfacet + facet normal 0.151146 -0.546248 0.823874 + outer loop + vertex 367.866 82.8852 364.178 + vertex 378.052 85.4362 364.001 + vertex 373.231 84.4972 364.262 + endloop + endfacet + facet normal 0.108765 -0.508325 0.854269 + outer loop + vertex 368.713 83.2447 364.284 + vertex 364.642 82.9981 364.656 + vertex 367.866 82.8852 364.178 + endloop + endfacet + facet normal 0.112098 -0.480009 0.870072 + outer loop + vertex 355.211 80.1705 364.311 + vertex 367.866 82.8852 364.178 + vertex 364.642 82.9981 364.656 + endloop + endfacet + facet normal 0.105411 -0.45917 0.882072 + outer loop + vertex 364.642 82.9981 364.656 + vertex 347.491 81.1704 365.754 + vertex 355.211 80.1705 364.311 + endloop + endfacet + facet normal 0.0921875 -0.384827 0.918373 + outer loop + vertex 367.866 82.8852 364.178 + vertex 355.211 80.1705 364.311 + vertex 363.594 81.5995 364.068 + endloop + endfacet + facet normal 0.106219 -0.470365 0.876056 + outer loop + vertex 364.642 82.9981 364.656 + vertex 363.732 84.8022 365.735 + vertex 347.491 81.1704 365.754 + endloop + endfacet + facet normal 0.112985 -0.500716 0.858206 + outer loop + vertex 363.732 84.8022 365.735 + vertex 353.375 84.7186 367.049 + vertex 347.491 81.1704 365.754 + endloop + endfacet + facet normal 0.103559 -0.488148 0.866595 + outer loop + vertex 343.883 82.9407 367.182 + vertex 347.491 81.1704 365.754 + vertex 353.375 84.7186 367.049 + endloop + endfacet + facet normal 0.100681 -0.472095 0.87578 + outer loop + vertex 353.375 84.7186 367.049 + vertex 343.212 85.4284 368.6 + vertex 343.883 82.9407 367.182 + endloop + endfacet + facet normal 0.0888006 -0.475104 0.875438 + outer loop + vertex 343.883 82.9407 367.182 + vertex 343.212 85.4284 368.6 + vertex 330.092 81.8572 367.993 + endloop + endfacet + facet normal 0.0874811 -0.470684 0.877954 + outer loop + vertex 329.944 87.9506 371.274 + vertex 330.092 81.8572 367.993 + vertex 343.212 85.4284 368.6 + endloop + endfacet + facet normal 0.0883847 -0.467588 0.879517 + outer loop + vertex 345.417 88.8564 370.201 + vertex 329.944 87.9506 371.274 + vertex 343.212 85.4284 368.6 + endloop + endfacet + facet normal 0.10063 -0.473393 0.875084 + outer loop + vertex 354.794 87.9989 368.659 + vertex 345.417 88.8564 370.201 + vertex 343.212 85.4284 368.6 + endloop + endfacet + facet normal 0.101951 -0.465894 0.878947 + outer loop + vertex 354.812 91.4643 370.494 + vertex 345.417 88.8564 370.201 + vertex 354.794 87.9989 368.659 + endloop + endfacet + facet normal 0.115024 -0.46528 0.877658 + outer loop + vertex 365.055 90.8592 368.83 + vertex 354.812 91.4643 370.494 + vertex 354.794 87.9989 368.659 + endloop + endfacet + facet normal 0.115852 -0.46815 0.876022 + outer loop + vertex 365.055 90.8592 368.83 + vertex 354.794 87.9989 368.659 + vertex 364.879 87.6492 367.138 + endloop + endfacet + facet normal 0.11482 -0.477202 0.871261 + outer loop + vertex 364.879 87.6492 367.138 + vertex 354.794 87.9989 368.659 + vertex 353.375 84.7186 367.049 + endloop + endfacet + facet normal 0.116108 -0.457611 0.881539 + outer loop + vertex 364.575 94.273 370.666 + vertex 354.812 91.4643 370.494 + vertex 365.055 90.8592 368.83 + endloop + endfacet + facet normal 0.132546 -0.454825 0.880662 + outer loop + vertex 374.459 93.8475 368.958 + vertex 364.575 94.273 370.666 + vertex 365.055 90.8592 368.83 + endloop + endfacet + facet normal 0.132171 -0.453673 0.881313 + outer loop + vertex 374.459 93.8475 368.958 + vertex 365.055 90.8592 368.83 + vertex 375.111 90.7121 367.247 + endloop + endfacet + facet normal 0.133913 -0.444109 0.885909 + outer loop + vertex 373.616 97.1955 370.764 + vertex 364.575 94.273 370.666 + vertex 374.459 93.8475 368.958 + endloop + endfacet + facet normal 0.150239 -0.439759 0.88546 + outer loop + vertex 383.07 97.034 369.08 + vertex 373.616 97.1955 370.764 + vertex 374.459 93.8475 368.958 + endloop + endfacet + facet normal 0.147837 -0.433402 0.888992 + outer loop + vertex 383.07 97.034 369.08 + vertex 374.459 93.8475 368.958 + vertex 384.256 93.8684 367.339 + endloop + endfacet + facet normal 0.159065 -0.429241 0.889073 + outer loop + vertex 383.07 97.034 369.08 + vertex 384.256 93.8684 367.339 + vertex 389.166 96.5533 367.757 + endloop + endfacet + facet normal 0.161122 -0.417491 0.894282 + outer loop + vertex 389.195 98.3278 368.58 + vertex 383.07 97.034 369.08 + vertex 389.166 96.5533 367.757 + endloop + endfacet + facet normal 0.172267 -0.416851 0.892502 + outer loop + vertex 392.728 98.3349 367.902 + vertex 389.195 98.3278 368.58 + vertex 389.166 96.5533 367.757 + endloop + endfacet + facet normal 0.168475 -0.409598 0.896574 + outer loop + vertex 392.728 98.3349 367.902 + vertex 389.166 96.5533 367.757 + vertex 393.58 96.7785 367.031 + endloop + endfacet + facet normal 0.17678 -0.405261 0.896946 + outer loop + vertex 395.495 98.1794 367.286 + vertex 392.728 98.3349 367.902 + vertex 393.58 96.7785 367.031 + endloop + endfacet + facet normal 0.177932 -0.397531 0.900172 + outer loop + vertex 394.814 99.8159 368.144 + vertex 392.728 98.3349 367.902 + vertex 395.495 98.1794 367.286 + endloop + endfacet + facet normal 0.183509 -0.395167 0.900093 + outer loop + vertex 395.495 98.1794 367.286 + vertex 397.285 98.6298 367.119 + vertex 394.814 99.8159 368.144 + endloop + endfacet + facet normal 0.183508 -0.395162 0.900096 + outer loop + vertex 395.495 98.1794 367.286 + vertex 396.73 96.8033 366.43 + vertex 397.285 98.6298 367.119 + endloop + endfacet + facet normal 0.181586 -0.402218 0.897356 + outer loop + vertex 394.814 99.8159 368.144 + vertex 391.888 99.9514 368.796 + vertex 392.728 98.3349 367.902 + endloop + endfacet + facet normal 0.18228 -0.39723 0.899434 + outer loop + vertex 393.588 101.365 369.076 + vertex 391.888 99.9514 368.796 + vertex 394.814 99.8159 368.144 + endloop + endfacet + facet normal 0.193745 -0.388907 0.900674 + outer loop + vertex 393.588 101.365 369.076 + vertex 394.814 99.8159 368.144 + vertex 395.298 101.791 368.892 + endloop + endfacet + facet normal 0.194074 -0.390568 0.899884 + outer loop + vertex 393.588 101.365 369.076 + vertex 395.298 101.791 368.892 + vertex 392.917 103.093 369.971 + endloop + endfacet + facet normal 0.186233 -0.393753 0.900153 + outer loop + vertex 392.917 103.093 369.971 + vertex 391.063 101.604 369.703 + vertex 393.588 101.365 369.076 + endloop + endfacet + facet normal 0.190425 -0.398445 0.897207 + outer loop + vertex 392.917 103.093 369.971 + vertex 390.298 103.278 370.609 + vertex 391.063 101.604 369.703 + endloop + endfacet + facet normal 0.17964 -0.403382 0.897225 + outer loop + vertex 390.298 103.278 370.609 + vertex 387.771 101.64 370.378 + vertex 391.063 101.604 369.703 + endloop + endfacet + facet normal 0.178742 -0.412354 0.893317 + outer loop + vertex 391.063 101.604 369.703 + vertex 387.771 101.64 370.378 + vertex 387.742 99.8003 369.535 + endloop + endfacet + facet normal 0.174642 -0.405189 0.897397 + outer loop + vertex 391.063 101.604 369.703 + vertex 387.742 99.8003 369.535 + vertex 391.888 99.9514 368.796 + endloop + endfacet + facet normal 0.174497 -0.408576 0.895888 + outer loop + vertex 391.888 99.9514 368.796 + vertex 387.742 99.8003 369.535 + vertex 389.195 98.3278 368.58 + endloop + endfacet + facet normal 0.166463 -0.413091 0.895347 + outer loop + vertex 387.771 101.64 370.378 + vertex 381.933 100.361 370.874 + vertex 387.742 99.8003 369.535 + endloop + endfacet + facet normal 0.16432 -0.424015 0.890624 + outer loop + vertex 381.933 100.361 370.874 + vertex 383.07 97.034 369.08 + vertex 387.742 99.8003 369.535 + endloop + endfacet + facet normal 0.167091 -0.416642 0.893583 + outer loop + vertex 387.771 101.64 370.378 + vertex 386.418 103.157 371.339 + vertex 381.933 100.361 370.874 + endloop + endfacet + facet normal 0.170079 -0.421001 0.890972 + outer loop + vertex 380.723 103.76 372.711 + vertex 381.933 100.361 370.874 + vertex 386.418 103.157 371.339 + endloop + endfacet + facet normal 0.172062 -0.411491 0.895025 + outer loop + vertex 386.447 105.057 372.207 + vertex 380.723 103.76 372.711 + vertex 386.418 103.157 371.339 + endloop + endfacet + facet normal 0.186241 -0.410596 0.892595 + outer loop + vertex 389.561 104.963 371.514 + vertex 386.447 105.057 372.207 + vertex 386.418 103.157 371.339 + endloop + endfacet + facet normal 0.181332 -0.40251 0.897276 + outer loop + vertex 389.561 104.963 371.514 + vertex 386.418 103.157 371.339 + vertex 390.298 103.278 370.609 + endloop + endfacet + facet normal 0.193753 -0.396998 0.897136 + outer loop + vertex 391.849 104.703 370.904 + vertex 389.561 104.963 371.514 + vertex 390.298 103.278 370.609 + endloop + endfacet + facet normal 0.195152 -0.39057 0.89965 + outer loop + vertex 391.297 106.419 371.769 + vertex 389.561 104.963 371.514 + vertex 391.849 104.703 370.904 + endloop + endfacet + facet normal 0.205429 -0.386908 0.898944 + outer loop + vertex 391.849 104.703 370.904 + vertex 393.236 105.108 370.762 + vertex 391.297 106.419 371.769 + endloop + endfacet + facet normal 0.205114 -0.385605 0.899576 + outer loop + vertex 391.849 104.703 370.904 + vertex 392.917 103.093 369.971 + vertex 393.236 105.108 370.762 + endloop + endfacet + facet normal 0.1997 -0.395442 0.896519 + outer loop + vertex 391.297 106.419 371.769 + vertex 388.822 106.737 372.461 + vertex 389.561 104.963 371.514 + endloop + endfacet + facet normal 0.20064 -0.391458 0.898056 + outer loop + vertex 390.371 108.125 372.72 + vertex 388.822 106.737 372.461 + vertex 391.297 106.419 371.769 + endloop + endfacet + facet normal 0.217973 -0.382052 0.898067 + outer loop + vertex 390.371 108.125 372.72 + vertex 391.297 106.419 371.769 + vertex 391.805 108.24 372.421 + endloop + endfacet + facet normal 0.217957 -0.384061 0.897213 + outer loop + vertex 390.371 108.125 372.72 + vertex 391.805 108.24 372.421 + vertex 390.015 109.997 373.607 + endloop + endfacet + facet normal 0.205222 -0.387253 0.898843 + outer loop + vertex 390.015 109.997 373.607 + vertex 387.965 108.781 373.552 + vertex 390.371 108.125 372.72 + endloop + endfacet + facet normal 0.208416 -0.3925 0.895827 + outer loop + vertex 390.015 109.997 373.607 + vertex 387.326 111.395 374.846 + vertex 387.965 108.781 373.552 + endloop + endfacet + facet normal 0.19441 -0.396589 0.897174 + outer loop + vertex 387.326 111.395 374.846 + vertex 383.735 109.459 374.768 + vertex 387.965 108.781 373.552 + endloop + endfacet + facet normal 0.192236 -0.40458 0.89407 + outer loop + vertex 387.965 108.781 373.552 + vertex 383.735 109.459 374.768 + vertex 384.817 106.747 373.308 + endloop + endfacet + facet normal 0.188793 -0.399606 0.897035 + outer loop + vertex 387.965 108.781 373.552 + vertex 384.817 106.747 373.308 + vertex 388.822 106.737 372.461 + endloop + endfacet + facet normal 0.188562 -0.402089 0.895974 + outer loop + vertex 388.822 106.737 372.461 + vertex 384.817 106.747 373.308 + vertex 386.447 105.057 372.207 + endloop + endfacet + facet normal 0.175842 -0.411292 0.894381 + outer loop + vertex 383.735 109.459 374.768 + vertex 378.7 106.938 374.599 + vertex 384.817 106.747 373.308 + endloop + endfacet + facet normal 0.174996 -0.418117 0.891378 + outer loop + vertex 378.7 106.938 374.599 + vertex 380.723 103.76 372.711 + vertex 384.817 106.747 373.308 + endloop + endfacet + facet normal 0.15778 -0.428149 0.889828 + outer loop + vertex 378.7 106.938 374.599 + vertex 371.863 104.139 374.464 + vertex 380.723 103.76 372.711 + endloop + endfacet + facet normal 0.157242 -0.432173 0.887976 + outer loop + vertex 380.723 103.76 372.711 + vertex 371.863 104.139 374.464 + vertex 372.784 100.639 372.597 + endloop + endfacet + facet normal 0.137648 -0.437634 0.888555 + outer loop + vertex 371.863 104.139 374.464 + vertex 363.352 101.351 374.41 + vertex 372.784 100.639 372.597 + endloop + endfacet + facet normal 0.1369 -0.442148 0.886433 + outer loop + vertex 372.784 100.639 372.597 + vertex 363.352 101.351 374.41 + vertex 363.946 97.7697 372.531 + endloop + endfacet + facet normal 0.136114 -0.439758 0.887742 + outer loop + vertex 372.784 100.639 372.597 + vertex 363.946 97.7697 372.531 + vertex 373.616 97.1955 370.764 + endloop + endfacet + facet normal 0.153938 -0.435117 0.887117 + outer loop + vertex 381.933 100.361 370.874 + vertex 372.784 100.639 372.597 + vertex 373.616 97.1955 370.764 + endloop + endfacet + facet normal 0.117938 -0.44577 0.887344 + outer loop + vertex 363.352 101.351 374.41 + vertex 353.855 98.6331 374.306 + vertex 363.946 97.7697 372.531 + endloop + endfacet + facet normal 0.117022 -0.45114 0.884748 + outer loop + vertex 363.946 97.7697 372.531 + vertex 353.855 98.6331 374.306 + vertex 354.355 95.0208 372.398 + endloop + endfacet + facet normal 0.116985 -0.451015 0.884816 + outer loop + vertex 363.946 97.7697 372.531 + vertex 354.355 95.0208 372.398 + vertex 364.575 94.273 370.666 + endloop + endfacet + facet normal 0.102373 -0.453491 0.885362 + outer loop + vertex 353.855 98.6331 374.306 + vertex 344.695 96.0344 374.034 + vertex 354.355 95.0208 372.398 + endloop + endfacet + facet normal 0.100621 -0.462756 0.880757 + outer loop + vertex 354.355 95.0208 372.398 + vertex 344.695 96.0344 374.034 + vertex 343.196 92.2774 372.232 + endloop + endfacet + facet normal 0.0998494 -0.459719 0.882433 + outer loop + vertex 354.355 95.0208 372.398 + vertex 343.196 92.2774 372.232 + vertex 354.812 91.4643 370.494 + endloop + endfacet + facet normal 0.0875285 -0.459115 0.884055 + outer loop + vertex 344.695 96.0344 374.034 + vertex 329.31 95.0913 375.068 + vertex 343.196 92.2774 372.232 + endloop + endfacet + facet normal 0.0868527 -0.461346 0.882959 + outer loop + vertex 329.31 95.0913 375.068 + vertex 329.944 87.9506 371.274 + vertex 343.196 92.2774 372.232 + endloop + endfacet + facet normal 0.0814278 -0.461938 0.883167 + outer loop + vertex 329.31 95.0913 375.068 + vertex 308.762 90.6556 374.642 + vertex 329.944 87.9506 371.274 + endloop + endfacet + facet normal 0.0810339 -0.463831 0.88221 + outer loop + vertex 329.944 87.9506 371.274 + vertex 308.762 90.6556 374.642 + vertex 309.294 83.7568 370.966 + endloop + endfacet + facet normal 0.075605 -0.464358 0.882414 + outer loop + vertex 308.762 90.6556 374.642 + vertex 288.871 86.9522 374.398 + vertex 309.294 83.7568 370.966 + endloop + endfacet + facet normal 0.0754015 -0.465201 0.881988 + outer loop + vertex 309.294 83.7568 370.966 + vertex 288.871 86.9522 374.398 + vertex 289.42 80.2041 370.791 + endloop + endfacet + facet normal 0.0763261 -0.470237 0.879233 + outer loop + vertex 309.294 83.7568 370.966 + vertex 289.42 80.2041 370.791 + vertex 308.784 77.9498 367.905 + endloop + endfacet + facet normal 0.0826333 -0.470434 0.878557 + outer loop + vertex 330.092 81.8572 367.993 + vertex 309.294 83.7568 370.966 + vertex 308.784 77.9498 367.905 + endloop + endfacet + facet normal 0.0829552 -0.472168 0.877597 + outer loop + vertex 330.092 81.8572 367.993 + vertex 308.784 77.9498 367.905 + vertex 326.094 76.7992 365.65 + endloop + endfacet + facet normal 0.0934869 -0.478425 0.873138 + outer loop + vertex 347.491 81.1704 365.754 + vertex 330.092 81.8572 367.993 + vertex 326.094 76.7992 365.65 + endloop + endfacet + facet normal 0.0900067 -0.461613 0.882504 + outer loop + vertex 347.491 81.1704 365.754 + vertex 326.094 76.7992 365.65 + vertex 340.155 77.5085 364.586 + endloop + endfacet + facet normal 0.0901356 -0.474354 0.875708 + outer loop + vertex 328.732 74.7232 364.254 + vertex 340.155 77.5085 364.586 + vertex 326.094 76.7992 365.65 + endloop + endfacet + facet normal 0.0859226 -0.47848 0.873885 + outer loop + vertex 316.919 73.1798 364.57 + vertex 328.732 74.7232 364.254 + vertex 326.094 76.7992 365.65 + endloop + endfacet + facet normal 0.0810742 -0.468011 0.879996 + outer loop + vertex 326.094 76.7992 365.65 + vertex 306.146 73.5633 365.766 + vertex 316.919 73.1798 364.57 + endloop + endfacet + facet normal 0.0794549 -0.485041 0.870874 + outer loop + vertex 302.982 70.5315 364.366 + vertex 316.919 73.1798 364.57 + vertex 306.146 73.5633 365.766 + endloop + endfacet + facet normal 0.0758786 -0.482187 0.872776 + outer loop + vertex 306.146 73.5633 365.766 + vertex 287.584 70.2474 365.548 + vertex 302.982 70.5315 364.366 + endloop + endfacet + facet normal 0.075355 -0.479361 0.874377 + outer loop + vertex 306.146 73.5633 365.766 + vertex 289.322 74.6647 367.82 + vertex 287.584 70.2474 365.548 + endloop + endfacet + facet normal 0.0709196 -0.478148 0.875411 + outer loop + vertex 289.322 74.6647 367.82 + vertex 270.38 71.825 367.804 + vertex 287.584 70.2474 365.548 + endloop + endfacet + facet normal 0.0705769 -0.480266 0.874279 + outer loop + vertex 287.584 70.2474 365.548 + vertex 270.38 71.825 367.804 + vertex 268.284 67.7727 365.747 + endloop + endfacet + facet normal 0.0707008 -0.481277 0.873713 + outer loop + vertex 287.584 70.2474 365.548 + vertex 268.284 67.7727 365.747 + vertex 278.36 67.1114 364.567 + endloop + endfacet + facet normal 0.0664644 -0.47873 0.875443 + outer loop + vertex 270.38 71.825 367.804 + vertex 251.481 69.236 367.823 + vertex 268.284 67.7727 365.747 + endloop + endfacet + facet normal 0.0661818 -0.480572 0.874455 + outer loop + vertex 268.284 67.7727 365.747 + vertex 251.481 69.236 367.823 + vertex 250.115 64.9732 365.583 + endloop + endfacet + facet normal 0.066985 -0.485618 0.871601 + outer loop + vertex 268.284 67.7727 365.747 + vertex 250.115 64.9732 365.583 + vertex 264.518 64.8955 364.433 + endloop + endfacet + facet normal 0.0623248 -0.479728 0.875201 + outer loop + vertex 251.481 69.236 367.823 + vertex 232.389 66.7832 367.838 + vertex 250.115 64.9732 365.583 + endloop + endfacet + facet normal 0.0620701 -0.481222 0.874399 + outer loop + vertex 250.115 64.9732 365.583 + vertex 232.389 66.7832 367.838 + vertex 230.008 62.6955 365.757 + endloop + endfacet + facet normal 0.062365 -0.483941 0.872875 + outer loop + vertex 250.115 64.9732 365.583 + vertex 230.008 62.6955 365.757 + vertex 241.897 61.7872 364.404 + endloop + endfacet + facet normal 0.0576392 -0.479325 0.875743 + outer loop + vertex 232.389 66.7832 367.838 + vertex 213.087 64.4845 367.85 + vertex 230.008 62.6955 365.757 + endloop + endfacet + facet normal 0.0573954 -0.480741 0.874982 + outer loop + vertex 230.008 62.6955 365.757 + vertex 213.087 64.4845 367.85 + vertex 211.106 60.1029 365.573 + endloop + endfacet + facet normal 0.0579824 -0.484857 0.872669 + outer loop + vertex 230.008 62.6955 365.757 + vertex 211.106 60.1029 365.573 + vertex 224.66 59.6418 364.416 + endloop + endfacet + facet normal 0.0526684 -0.479198 0.876125 + outer loop + vertex 213.087 64.4845 367.85 + vertex 193.664 62.3117 367.829 + vertex 211.106 60.1029 365.573 + endloop + endfacet + facet normal 0.0521382 -0.481901 0.874673 + outer loop + vertex 211.106 60.1029 365.573 + vertex 193.664 62.3117 367.829 + vertex 190.493 57.8864 365.58 + endloop + endfacet + facet normal 0.0521872 -0.482358 0.874418 + outer loop + vertex 211.106 60.1029 365.573 + vertex 190.493 57.8864 365.58 + vertex 202.931 57.1159 364.413 + endloop + endfacet + facet normal 0.0477316 -0.479532 0.876225 + outer loop + vertex 193.664 62.3117 367.829 + vertex 174.05 60.3871 367.844 + vertex 190.493 57.8864 365.58 + endloop + endfacet + facet normal 0.0470648 -0.482481 0.874641 + outer loop + vertex 190.493 57.8864 365.58 + vertex 174.05 60.3871 367.844 + vertex 170.295 56.2225 365.749 + endloop + endfacet + facet normal 0.0472485 -0.484844 0.873323 + outer loop + vertex 190.493 57.8864 365.58 + vertex 170.295 56.2225 365.749 + vertex 180.562 54.8129 364.411 + endloop + endfacet + facet normal 0.0426005 -0.479418 0.876552 + outer loop + vertex 174.05 60.3871 367.844 + vertex 154.698 58.6551 367.838 + vertex 170.295 56.2225 365.749 + endloop + endfacet + facet normal 0.0419526 -0.48226 0.875023 + outer loop + vertex 170.295 56.2225 365.749 + vertex 154.698 58.6551 367.838 + vertex 151.246 54.2627 365.582 + endloop + endfacet + facet normal 0.0423328 -0.485787 0.873051 + outer loop + vertex 170.295 56.2225 365.749 + vertex 151.246 54.2627 365.582 + vertex 163.392 53.1935 364.398 + endloop + endfacet + facet normal 0.0373993 -0.479551 0.876717 + outer loop + vertex 154.698 58.6551 367.838 + vertex 135.593 57.1378 367.823 + vertex 151.246 54.2627 365.582 + endloop + endfacet + facet normal 0.0367083 -0.482201 0.875291 + outer loop + vertex 151.246 54.2627 365.582 + vertex 135.593 57.1378 367.823 + vertex 132.132 53.1259 365.758 + endloop + endfacet + facet normal 0.0368702 -0.485178 0.873638 + outer loop + vertex 151.246 54.2627 365.582 + vertex 132.132 53.1259 365.758 + vertex 141.053 51.4307 364.44 + endloop + endfacet + facet normal 0.0318778 -0.479028 0.877221 + outer loop + vertex 135.593 57.1378 367.823 + vertex 116.427 55.8634 367.823 + vertex 132.132 53.1259 365.758 + endloop + endfacet + facet normal 0.0309466 -0.482823 0.875171 + outer loop + vertex 132.132 53.1259 365.758 + vertex 116.427 55.8634 367.823 + vertex 113.221 51.5775 365.572 + endloop + endfacet + facet normal 0.0309756 -0.483155 0.874987 + outer loop + vertex 132.132 53.1259 365.758 + vertex 113.221 51.5775 365.572 + vertex 127.161 50.6737 364.58 + endloop + endfacet + facet normal 0.0265539 -0.480332 0.876685 + outer loop + vertex 116.427 55.8634 367.823 + vertex 97.0224 54.7905 367.823 + vertex 113.221 51.5775 365.572 + endloop + endfacet + facet normal 0.0259 -0.482722 0.87539 + outer loop + vertex 113.221 51.5775 365.572 + vertex 97.0224 54.7905 367.823 + vertex 93.1248 50.8119 365.745 + endloop + endfacet + facet normal 0.0260215 -0.486366 0.873368 + outer loop + vertex 113.221 51.5775 365.572 + vertex 93.1248 50.8119 365.745 + vertex 101.279 48.8108 364.387 + endloop + endfacet + facet normal 0.0211709 -0.479173 0.877465 + outer loop + vertex 97.0224 54.7905 367.823 + vertex 77.5934 53.9295 367.822 + vertex 93.1248 50.8119 365.745 + endloop + endfacet + facet normal 0.0203098 -0.482325 0.875757 + outer loop + vertex 93.1248 50.8119 365.745 + vertex 77.5934 53.9295 367.822 + vertex 74.5295 49.7069 365.567 + endloop + endfacet + facet normal 0.0203524 -0.482983 0.875393 + outer loop + vertex 93.1248 50.8119 365.745 + vertex 74.5295 49.7069 365.567 + vertex 87.3479 48.4099 364.554 + endloop + endfacet + facet normal 0.0160024 -0.479944 0.877153 + outer loop + vertex 77.5934 53.9295 367.822 + vertex 58.2963 53.2781 367.817 + vertex 74.5295 49.7069 365.567 + endloop + endfacet + facet normal 0.015226 -0.482573 0.875723 + outer loop + vertex 74.5295 49.7069 365.567 + vertex 58.2963 53.2781 367.817 + vertex 55.2526 49.4075 365.737 + endloop + endfacet + facet normal 0.0152324 -0.483173 0.875392 + outer loop + vertex 74.5295 49.7069 365.567 + vertex 55.2526 49.4075 365.737 + vertex 65.0033 47.566 364.551 + endloop + endfacet + facet normal 0.0112877 -0.480207 0.877083 + outer loop + vertex 58.2963 53.2781 367.817 + vertex 39.0729 52.8164 367.812 + vertex 55.2526 49.4075 365.737 + endloop + endfacet + facet normal 0.0104716 -0.483114 0.875495 + outer loop + vertex 55.2526 49.4075 365.737 + vertex 39.0729 52.8164 367.812 + vertex 36.8233 48.6922 365.563 + endloop + endfacet + facet normal 0.0106909 -0.48809 0.872728 + outer loop + vertex 55.2526 49.4075 365.737 + vertex 36.8233 48.6922 365.563 + vertex 50.8 46.9457 364.415 + endloop + endfacet + facet normal 0.00661023 -0.48151 0.876416 + outer loop + vertex 39.0729 52.8164 367.812 + vertex 19.7394 52.5894 367.833 + vertex 36.8233 48.6922 365.563 + endloop + endfacet + facet normal 0.00606907 -0.483308 0.87543 + outer loop + vertex 36.8233 48.6922 365.563 + vertex 19.7394 52.5894 367.833 + vertex 16.766 48.7779 365.749 + endloop + endfacet + facet normal 0.0060363 -0.486783 0.873502 + outer loop + vertex 36.8233 48.6922 365.563 + vertex 16.766 48.7779 365.749 + vertex 28.0731 46.4904 364.397 + endloop + endfacet + facet normal 0.00230993 -0.481061 0.876684 + outer loop + vertex 19.7394 52.5894 367.833 + vertex 0.390189 52.5252 367.849 + vertex 16.766 48.7779 365.749 + endloop + endfacet + facet normal 0.00171554 -0.483047 0.875593 + outer loop + vertex 16.766 48.7779 365.749 + vertex 0.390189 52.5252 367.849 + vertex -2.21693 48.4338 365.597 + endloop + endfacet + facet normal 0.00181784 -0.487575 0.873079 + outer loop + vertex 16.766 48.7779 365.749 + vertex -2.21693 48.4338 365.597 + vertex 10.9637 46.3688 364.416 + endloop + endfacet + facet normal -0.00205378 -0.481203 0.876607 + outer loop + vertex 0.390189 52.5252 367.849 + vertex -18.9322 52.5998 367.845 + vertex -2.21693 48.4338 365.597 + endloop + endfacet + facet normal -0.00282411 -0.483585 0.875293 + outer loop + vertex -2.21693 48.4338 365.597 + vertex -18.9322 52.5998 367.845 + vertex -22.2687 48.8264 365.749 + endloop + endfacet + facet normal -0.00291855 -0.487554 0.873088 + outer loop + vertex -2.21693 48.4338 365.597 + vertex -22.2687 48.8264 365.749 + vertex -11.7794 46.3865 364.422 + endloop + endfacet + facet normal -0.0065154 -0.481077 0.876654 + outer loop + vertex -18.9322 52.5998 367.845 + vertex -38.3504 52.8394 367.832 + vertex -22.2687 48.8264 365.749 + endloop + endfacet + facet normal -0.00725702 -0.483386 0.875377 + outer loop + vertex -22.2687 48.8264 365.749 + vertex -38.3504 52.8394 367.832 + vertex -41.4373 48.7902 365.57 + endloop + endfacet + facet normal -0.00722599 -0.487778 0.872938 + outer loop + vertex -22.2687 48.8264 365.749 + vertex -41.4373 48.7902 365.57 + vertex -28.8864 46.5039 364.396 + endloop + endfacet + facet normal -0.0110749 -0.481143 0.876572 + outer loop + vertex -38.3504 52.8394 367.832 + vertex -57.7171 53.2547 367.815 + vertex -41.4373 48.7902 365.57 + endloop + endfacet + facet normal -0.0115972 -0.482633 0.875746 + outer loop + vertex -41.4373 48.7902 365.57 + vertex -57.7171 53.2547 367.815 + vertex -60.8032 49.5466 365.731 + endloop + endfacet + facet normal -0.011772 -0.486636 0.873525 + outer loop + vertex -41.4373 48.7902 365.57 + vertex -60.8032 49.5466 365.731 + vertex -51.539 46.9593 364.414 + endloop + endfacet + facet normal -0.0159103 -0.479861 0.877201 + outer loop + vertex -57.7171 53.2547 367.815 + vertex -77.0031 53.8925 367.814 + vertex -60.8032 49.5466 365.731 + endloop + endfacet + facet normal -0.0166376 -0.482002 0.876012 + outer loop + vertex -60.8032 49.5466 365.731 + vertex -77.0031 53.8925 367.814 + vertex -79.16 49.8863 365.569 + endloop + endfacet + facet normal -0.0166619 -0.483782 0.87503 + outer loop + vertex -60.8032 49.5466 365.731 + vertex -79.16 49.8863 365.569 + vertex -65.4449 47.559 364.543 + endloop + endfacet + facet normal -0.0210773 -0.480133 0.876943 + outer loop + vertex -77.0031 53.8925 367.814 + vertex -96.2885 54.7497 367.82 + vertex -79.16 49.8863 365.569 + endloop + endfacet + facet normal -0.0217092 -0.481902 0.875956 + outer loop + vertex -79.16 49.8863 365.569 + vertex -96.2885 54.7497 367.82 + vertex -98.6705 51.078 365.741 + endloop + endfacet + facet normal -0.0216803 -0.481463 0.876198 + outer loop + vertex -79.16 49.8863 365.569 + vertex -98.6705 51.078 365.741 + vertex -87.8516 48.44 364.559 + endloop + endfacet + facet normal -0.0264387 -0.479504 0.877141 + outer loop + vertex -96.2885 54.7497 367.82 + vertex -115.681 55.8307 367.826 + vertex -98.6705 51.078 365.741 + endloop + endfacet + facet normal -0.0274233 -0.482334 0.875558 + outer loop + vertex -98.6705 51.078 365.741 + vertex -115.681 55.8307 367.826 + vertex -117.83 51.8668 365.575 + endloop + endfacet + facet normal -0.0276307 -0.488039 0.872385 + outer loop + vertex -98.6705 51.078 365.741 + vertex -117.83 51.8668 365.575 + vertex -102.22 48.8666 364.391 + endloop + endfacet + facet normal -0.0319754 -0.480386 0.876474 + outer loop + vertex -115.681 55.8307 367.826 + vertex -135.142 57.1389 367.833 + vertex -117.83 51.8668 365.575 + endloop + endfacet + facet normal -0.0325559 -0.481922 0.875609 + outer loop + vertex -117.83 51.8668 365.575 + vertex -135.142 57.1389 367.833 + vertex -137.649 53.5602 365.77 + endloop + endfacet + facet normal -0.0323416 -0.479564 0.876911 + outer loop + vertex -117.83 51.8668 365.575 + vertex -137.649 53.5602 365.77 + vertex -127.466 50.7009 364.582 + endloop + endfacet + facet normal -0.0372001 -0.479368 0.876825 + outer loop + vertex -135.142 57.1389 367.833 + vertex -154.456 58.6434 367.836 + vertex -137.649 53.5602 365.77 + endloop + endfacet + facet normal -0.0379614 -0.481416 0.87567 + outer loop + vertex -137.649 53.5602 365.77 + vertex -154.456 58.6434 367.836 + vertex -155.963 54.6454 365.573 + endloop + endfacet + facet normal -0.0381757 -0.485437 0.873438 + outer loop + vertex -137.649 53.5602 365.77 + vertex -155.963 54.6454 365.573 + vertex -141.568 51.4791 364.442 + endloop + endfacet + facet normal -0.0424429 -0.480038 0.87622 + outer loop + vertex -154.456 58.6434 367.836 + vertex -173.7 60.3205 367.823 + vertex -155.963 54.6454 365.573 + endloop + endfacet + facet normal -0.0431841 -0.481929 0.875146 + outer loop + vertex -155.963 54.6454 365.573 + vertex -173.7 60.3205 367.823 + vertex -176.048 56.7305 365.73 + endloop + endfacet + facet normal -0.0434591 -0.48447 0.873728 + outer loop + vertex -155.963 54.6454 365.573 + vertex -176.048 56.7305 365.73 + vertex -164.165 53.2497 364.391 + endloop + endfacet + facet normal -0.0475215 -0.47968 0.876156 + outer loop + vertex -173.7 60.3205 367.823 + vertex -192.91 62.2123 367.817 + vertex -176.048 56.7305 365.73 + endloop + endfacet + facet normal -0.0481978 -0.481389 0.875181 + outer loop + vertex -176.048 56.7305 365.73 + vertex -192.91 62.2123 367.817 + vertex -194.845 58.331 365.575 + endloop + endfacet + facet normal -0.0484724 -0.484799 0.873281 + outer loop + vertex -176.048 56.7305 365.73 + vertex -194.845 58.331 365.575 + vertex -181.287 54.8394 364.39 + endloop + endfacet + facet normal -0.0525365 -0.479637 0.875893 + outer loop + vertex -192.91 62.2123 367.817 + vertex -211.914 64.2889 367.814 + vertex -194.845 58.331 365.575 + endloop + endfacet + facet normal -0.0532939 -0.481422 0.874867 + outer loop + vertex -194.845 58.331 365.575 + vertex -211.914 64.2889 367.814 + vertex -214.173 60.8029 365.758 + endloop + endfacet + facet normal -0.0535645 -0.483454 0.87373 + outer loop + vertex -194.845 58.331 365.575 + vertex -214.173 60.8029 365.758 + vertex -203.695 57.262 364.441 + endloop + endfacet + facet normal -0.0573282 -0.479333 0.875759 + outer loop + vertex -211.914 64.2889 367.814 + vertex -230.918 66.5894 367.829 + vertex -214.173 60.8029 365.758 + endloop + endfacet + facet normal -0.0586413 -0.482482 0.873941 + outer loop + vertex -214.173 60.8029 365.758 + vertex -230.918 66.5894 367.829 + vertex -232.901 62.7333 365.567 + endloop + endfacet + facet normal -0.0586836 -0.482916 0.873698 + outer loop + vertex -214.173 60.8029 365.758 + vertex -232.901 62.7333 365.567 + vertex -217.767 59.1145 364.584 + endloop + endfacet + facet normal -0.0621637 -0.481005 0.874511 + outer loop + vertex -230.918 66.5894 367.829 + vertex -250.269 69.1197 367.845 + vertex -232.901 62.7333 365.567 + endloop + endfacet + facet normal -0.0626861 -0.482181 0.873826 + outer loop + vertex -232.901 62.7333 365.567 + vertex -250.269 69.1197 367.845 + vertex -254.189 65.5397 365.589 + endloop + endfacet + facet normal -0.0628263 -0.48324 0.873231 + outer loop + vertex -232.901 62.7333 365.567 + vertex -254.189 65.5397 365.589 + vertex -242.725 61.8363 364.364 + endloop + endfacet + facet normal -0.0664762 -0.478968 0.875312 + outer loop + vertex -250.269 69.1197 367.845 + vertex -269.842 71.9462 367.906 + vertex -254.189 65.5397 365.589 + endloop + endfacet + facet normal -0.0670224 -0.480069 0.874667 + outer loop + vertex -254.189 65.5397 365.589 + vertex -269.842 71.9462 367.906 + vertex -273.631 68.6795 365.822 + endloop + endfacet + facet normal -0.0671506 -0.480831 0.874238 + outer loop + vertex -254.189 65.5397 365.589 + vertex -273.631 68.6795 365.822 + vertex -264.878 65.0051 364.474 + endloop + endfacet + facet normal -0.0713425 -0.476191 0.876443 + outer loop + vertex -269.842 71.9462 367.906 + vertex -289.242 74.8139 367.884 + vertex -273.631 68.6795 365.822 + endloop + endfacet + facet normal -0.0716805 -0.47691 0.876024 + outer loop + vertex -273.631 68.6795 365.822 + vertex -289.242 74.8139 367.884 + vertex -292.392 71.1159 365.614 + endloop + endfacet + facet normal -0.071585 -0.476138 0.876452 + outer loop + vertex -273.631 68.6795 365.822 + vertex -292.392 71.1159 365.614 + vertex -278.574 67.198 364.614 + endloop + endfacet + facet normal -0.0761058 -0.47391 0.877278 + outer loop + vertex -289.242 74.8139 367.884 + vertex -308.642 77.6264 367.721 + vertex -292.392 71.1159 365.614 + endloop + endfacet + facet normal -0.0763975 -0.474523 0.876922 + outer loop + vertex -292.392 71.1159 365.614 + vertex -308.642 77.6264 367.721 + vertex -312.068 74.4711 365.715 + endloop + endfacet + facet normal -0.0765899 -0.475633 0.876303 + outer loop + vertex -292.392 71.1159 365.614 + vertex -312.068 74.4711 365.715 + vertex -304.209 70.8338 364.428 + endloop + endfacet + facet normal -0.0809521 -0.470645 0.878601 + outer loop + vertex -308.642 77.6264 367.721 + vertex -326.605 80.0953 367.388 + vertex -312.068 74.4711 365.715 + endloop + endfacet + facet normal -0.0836552 -0.4766 0.875131 + outer loop + vertex -312.068 74.4711 365.715 + vertex -326.605 80.0953 367.388 + vertex -330.01 77.1868 365.479 + endloop + endfacet + facet normal -0.0807669 -0.469191 0.879395 + outer loop + vertex -308.642 77.6264 367.721 + vertex -328.509 85.751 370.231 + vertex -326.605 80.0953 367.388 + endloop + endfacet + facet normal -0.087462 -0.470714 0.87794 + outer loop + vertex -326.605 80.0953 367.388 + vertex -328.509 85.751 370.231 + vertex -341.59 86.0698 369.099 + endloop + endfacet + facet normal -0.0890977 -0.474228 0.875882 + outer loop + vertex -342.534 82.5783 367.112 + vertex -326.605 80.0953 367.388 + vertex -341.59 86.0698 369.099 + endloop + endfacet + facet normal -0.0986677 -0.471801 0.876167 + outer loop + vertex -341.59 86.0698 369.099 + vertex -353.792 88.1183 368.828 + vertex -342.534 82.5783 367.112 + endloop + endfacet + facet normal -0.0979631 -0.467273 0.878669 + outer loop + vertex -341.59 86.0698 369.099 + vertex -353.694 91.6531 370.718 + vertex -353.792 88.1183 368.828 + endloop + endfacet + facet normal -0.116713 -0.465916 0.877098 + outer loop + vertex -353.694 91.6531 370.718 + vertex -363.552 93.8616 370.58 + vertex -353.792 88.1183 368.828 + endloop + endfacet + facet normal -0.111744 -0.458807 0.881481 + outer loop + vertex -353.792 88.1183 368.828 + vertex -363.552 93.8616 370.58 + vertex -364.404 90.6985 368.825 + endloop + endfacet + facet normal -0.112933 -0.463699 0.878766 + outer loop + vertex -353.792 88.1183 368.828 + vertex -364.404 90.6985 368.825 + vertex -356.347 85.6977 367.222 + endloop + endfacet + facet normal -0.114131 -0.465307 0.87776 + outer loop + vertex -356.347 85.6977 367.222 + vertex -364.404 90.6985 368.825 + vertex -366.091 88.6821 367.537 + endloop + endfacet + facet normal -0.132231 -0.452737 0.881785 + outer loop + vertex -364.404 90.6985 368.825 + vertex -373.452 93.1931 368.749 + vertex -366.091 88.6821 367.537 + endloop + endfacet + facet normal -0.134793 -0.456317 0.879548 + outer loop + vertex -366.091 88.6821 367.537 + vertex -373.452 93.1931 368.749 + vertex -373.483 90.1735 367.178 + endloop + endfacet + facet normal -0.140286 -0.487868 0.861571 + outer loop + vertex -366.091 88.6821 367.537 + vertex -373.483 90.1735 367.178 + vertex -363.321 85.5956 366.241 + endloop + endfacet + facet normal -0.151657 -0.455054 0.877454 + outer loop + vertex -373.452 93.1931 368.749 + vertex -382.309 95.6797 368.508 + vertex -373.483 90.1735 367.178 + endloop + endfacet + facet normal -0.142774 -0.442695 0.885233 + outer loop + vertex -373.483 90.1735 367.178 + vertex -382.309 95.6797 368.508 + vertex -383.045 92.5928 366.846 + endloop + endfacet + facet normal -0.147193 -0.461596 0.874794 + outer loop + vertex -373.483 90.1735 367.178 + vertex -383.045 92.5928 366.846 + vertex -373.337 87.4806 365.782 + endloop + endfacet + facet normal -0.137527 -0.445312 0.884751 + outer loop + vertex -373.337 87.4806 365.782 + vertex -383.045 92.5928 366.846 + vertex -383.817 90.0337 365.438 + endloop + endfacet + facet normal -0.150508 -0.441331 0.884632 + outer loop + vertex -383.817 90.0337 365.438 + vertex -383.045 92.5928 366.846 + vertex -389.544 93.7796 366.332 + endloop + endfacet + facet normal -0.146515 -0.436015 0.887933 + outer loop + vertex -391.023 92.7731 365.594 + vertex -383.817 90.0337 365.438 + vertex -389.544 93.7796 366.332 + endloop + endfacet + facet normal -0.157613 -0.422943 0.892344 + outer loop + vertex -389.544 93.7796 366.332 + vertex -394.206 95.2487 366.205 + vertex -391.023 92.7731 365.594 + endloop + endfacet + facet normal -0.156192 -0.421361 0.893341 + outer loop + vertex -391.023 92.7731 365.594 + vertex -394.206 95.2487 366.205 + vertex -394.94 93.8559 365.42 + endloop + endfacet + facet normal -0.159457 -0.434266 0.886559 + outer loop + vertex -391.023 92.7731 365.594 + vertex -394.94 93.8559 365.42 + vertex -390.616 91.2563 364.924 + endloop + endfacet + facet normal -0.152063 -0.423227 0.893172 + outer loop + vertex -390.616 91.2563 364.924 + vertex -394.94 93.8559 365.42 + vertex -395.527 92.6435 364.745 + endloop + endfacet + facet normal -0.15231 -0.424164 0.892685 + outer loop + vertex -390.616 91.2563 364.924 + vertex -395.527 92.6435 364.745 + vertex -391.929 90.6095 364.393 + endloop + endfacet + facet normal -0.144457 -0.436347 0.888106 + outer loop + vertex -391.929 90.6095 364.393 + vertex -384.584 88.3278 364.466 + vertex -390.616 91.2563 364.924 + endloop + endfacet + facet normal -0.145939 -0.439145 0.886484 + outer loop + vertex -384.584 88.3278 364.466 + vertex -383.817 90.0337 365.438 + vertex -390.616 91.2563 364.924 + endloop + endfacet + facet normal -0.151967 -0.423613 0.893005 + outer loop + vertex -391.929 90.6095 364.393 + vertex -395.527 92.6435 364.745 + vertex -395.983 91.7475 364.243 + endloop + endfacet + facet normal -0.155957 -0.438895 0.8849 + outer loop + vertex -391.929 90.6095 364.393 + vertex -395.983 91.7475 364.243 + vertex -391.219 89.7045 364.069 + endloop + endfacet + facet normal -0.162025 -0.41878 0.893516 + outer loop + vertex -395.527 92.6435 364.745 + vertex -398.554 93.7592 364.719 + vertex -395.983 91.7475 364.243 + endloop + endfacet + facet normal -0.155467 -0.411475 0.898064 + outer loop + vertex -395.983 91.7475 364.243 + vertex -398.554 93.7592 364.719 + vertex -398.879 92.7122 364.183 + endloop + endfacet + facet normal -0.158248 -0.4201 0.893574 + outer loop + vertex -395.983 91.7475 364.243 + vertex -398.879 92.7122 364.183 + vertex -396.548 91.2518 363.91 + endloop + endfacet + facet normal -0.158717 -0.420774 0.893173 + outer loop + vertex -396.548 91.2518 363.91 + vertex -398.879 92.7122 364.183 + vertex -399.894 92.5355 363.92 + endloop + endfacet + facet normal -0.163368 -0.404193 0.899966 + outer loop + vertex -398.879 92.7122 364.183 + vertex -400.325 94.2259 364.601 + vertex -399.894 92.5355 363.92 + endloop + endfacet + facet normal -0.164444 -0.404358 0.899696 + outer loop + vertex -400.325 94.2259 364.601 + vertex -401.451 93.2324 363.948 + vertex -399.894 92.5355 363.92 + endloop + endfacet + facet normal -0.174574 -0.394502 0.90216 + outer loop + vertex -400.325 94.2259 364.601 + vertex -401.144 94.5369 364.578 + vertex -401.451 93.2324 363.948 + endloop + endfacet + facet normal -0.17396 -0.392822 0.903011 + outer loop + vertex -400.325 94.2259 364.601 + vertex -399.769 96.3691 365.64 + vertex -401.144 94.5369 364.578 + endloop + endfacet + facet normal -0.18522 -0.389508 0.902207 + outer loop + vertex -398.824 96.3141 365.81 + vertex -399.769 96.3691 365.64 + vertex -400.325 94.2259 364.601 + endloop + endfacet + facet normal -0.166268 -0.402075 0.900384 + outer loop + vertex -398.824 96.3141 365.81 + vertex -400.325 94.2259 364.601 + vertex -398.554 93.7592 364.719 + endloop + endfacet + facet normal -0.175244 -0.40226 0.898597 + outer loop + vertex -397.659 94.6605 365.297 + vertex -398.824 96.3141 365.81 + vertex -398.554 93.7592 364.719 + endloop + endfacet + facet normal -0.176304 -0.40286 0.898121 + outer loop + vertex -397.659 94.6605 365.297 + vertex -397.032 96.2824 366.148 + vertex -398.824 96.3141 365.81 + endloop + endfacet + facet normal -0.176755 -0.395773 0.901178 + outer loop + vertex -396.892 99.1933 367.454 + vertex -398.824 96.3141 365.81 + vertex -397.032 96.2824 366.148 + endloop + endfacet + facet normal -0.185485 -0.394762 0.899866 + outer loop + vertex -395.892 97.538 366.934 + vertex -396.892 99.1933 367.454 + vertex -397.032 96.2824 366.148 + endloop + endfacet + facet normal -0.167741 -0.409055 0.89696 + outer loop + vertex -394.206 95.2487 366.205 + vertex -395.892 97.538 366.934 + vertex -397.032 96.2824 366.148 + endloop + endfacet + facet normal -0.171356 -0.411189 0.895299 + outer loop + vertex -393.372 96.7488 367.053 + vertex -395.892 97.538 366.934 + vertex -394.206 95.2487 366.205 + endloop + endfacet + facet normal -0.168711 -0.402038 0.899946 + outer loop + vertex -393.372 96.7488 367.053 + vertex -395.081 99.3376 367.89 + vertex -395.892 97.538 366.934 + endloop + endfacet + facet normal -0.176786 -0.406252 0.896496 + outer loop + vertex -392.496 98.3053 367.932 + vertex -395.081 99.3376 367.89 + vertex -393.372 96.7488 367.053 + endloop + endfacet + facet normal -0.161287 -0.414495 0.895645 + outer loop + vertex -389.74 95.637 367.193 + vertex -392.496 98.3053 367.932 + vertex -393.372 96.7488 367.053 + endloop + endfacet + facet normal -0.165454 -0.429072 0.887988 + outer loop + vertex -389.74 95.637 367.193 + vertex -393.372 96.7488 367.053 + vertex -389.544 93.7796 366.332 + endloop + endfacet + facet normal -0.164268 -0.41709 0.893897 + outer loop + vertex -388.273 96.8096 368.01 + vertex -392.496 98.3053 367.932 + vertex -389.74 95.637 367.193 + endloop + endfacet + facet normal -0.150135 -0.431671 0.889449 + outer loop + vertex -389.74 95.637 367.193 + vertex -383.045 92.5928 366.846 + vertex -388.273 96.8096 368.01 + endloop + endfacet + facet normal -0.162671 -0.412454 0.896337 + outer loop + vertex -388.273 96.8096 368.01 + vertex -391.633 99.9268 368.835 + vertex -392.496 98.3053 367.932 + endloop + endfacet + facet normal -0.17935 -0.403953 0.897026 + outer loop + vertex -391.633 99.9268 368.835 + vertex -393.932 100.705 368.725 + vertex -392.496 98.3053 367.932 + endloop + endfacet + facet normal -0.17702 -0.396547 0.900785 + outer loop + vertex -391.633 99.9268 368.835 + vertex -393.154 102.6 369.712 + vertex -393.932 100.705 368.725 + endloop + endfacet + facet normal -0.193682 -0.389516 0.900425 + outer loop + vertex -393.932 100.705 368.725 + vertex -393.154 102.6 369.712 + vertex -394.848 102.395 369.259 + endloop + endfacet + facet normal -0.19229 -0.388935 0.900974 + outer loop + vertex -393.932 100.705 368.725 + vertex -394.848 102.395 369.259 + vertex -395.081 99.3376 367.89 + endloop + endfacet + facet normal -0.18604 -0.389826 0.901901 + outer loop + vertex -394.848 102.395 369.259 + vertex -396.892 99.1933 367.454 + vertex -395.081 99.3376 367.89 + endloop + endfacet + facet normal -0.21552 -0.371643 0.903013 + outer loop + vertex -394.848 102.395 369.259 + vertex -395.689 102.192 368.975 + vertex -396.892 99.1933 367.454 + endloop + endfacet + facet normal -0.201674 -0.377568 0.903753 + outer loop + vertex -396.892 99.1933 367.454 + vertex -395.689 102.192 368.975 + vertex -397.845 99.0312 367.173 + endloop + endfacet + facet normal 0.0877021 0.447456 -0.889995 + outer loop + vertex -395.689 102.192 368.975 + vertex -396.106 101.381 368.526 + vertex -397.845 99.0312 367.173 + endloop + endfacet + facet normal -0.215112 -0.372798 0.902634 + outer loop + vertex -394.848 102.395 369.259 + vertex -393.706 105.445 370.791 + vertex -395.689 102.192 368.975 + endloop + endfacet + facet normal 0.10455 0.435457 -0.894118 + outer loop + vertex -393.706 105.445 370.791 + vertex -394.012 104.708 370.396 + vertex -395.689 102.192 368.975 + endloop + endfacet + facet normal -0.227181 -0.367819 0.90172 + outer loop + vertex -392.955 105.674 371.074 + vertex -393.706 105.445 370.791 + vertex -394.848 102.395 369.259 + endloop + endfacet + facet normal -0.225571 -0.371651 0.900552 + outer loop + vertex -392.955 105.674 371.074 + vertex -392.044 108.576 372.499 + vertex -393.706 105.445 370.791 + endloop + endfacet + facet normal 0.13795 0.416981 -0.898386 + outer loop + vertex -392.044 108.576 372.499 + vertex -392.24 107.837 372.126 + vertex -393.706 105.445 370.791 + endloop + endfacet + facet normal -0.240408 -0.366203 0.898944 + outer loop + vertex -391.303 108.976 372.861 + vertex -392.044 108.576 372.499 + vertex -392.955 105.674 371.074 + endloop + endfacet + facet normal -0.203462 -0.385306 0.900079 + outer loop + vertex -391.303 108.976 372.861 + vertex -392.955 105.674 371.074 + vertex -391.349 105.933 371.548 + endloop + endfacet + facet normal -0.209207 -0.384753 0.898998 + outer loop + vertex -390.4 107.372 372.384 + vertex -391.303 108.976 372.861 + vertex -391.349 105.933 371.548 + endloop + endfacet + facet normal -0.193622 -0.39458 0.89823 + outer loop + vertex -389.116 104.982 371.611 + vertex -390.4 107.372 372.384 + vertex -391.349 105.933 371.548 + endloop + endfacet + facet normal -0.19427 -0.396154 0.897397 + outer loop + vertex -389.116 104.982 371.611 + vertex -391.349 105.933 371.548 + vertex -389.935 103.297 370.69 + endloop + endfacet + facet normal -0.177912 -0.404036 0.897275 + outer loop + vertex -386.887 102.245 370.821 + vertex -389.116 104.982 371.611 + vertex -389.935 103.297 370.69 + endloop + endfacet + facet normal -0.181862 -0.416265 0.89087 + outer loop + vertex -386.887 102.245 370.821 + vertex -389.935 103.297 370.69 + vertex -386.906 100.128 369.827 + endloop + endfacet + facet normal -0.160173 -0.418032 0.8942 + outer loop + vertex -386.887 102.245 370.821 + vertex -386.906 100.128 369.827 + vertex -381.348 99.0137 370.302 + endloop + endfacet + facet normal -0.161659 -0.420361 0.89284 + outer loop + vertex -386.887 102.245 370.821 + vertex -381.348 99.0137 370.302 + vertex -385.538 103.542 371.676 + endloop + endfacet + facet normal -0.167531 -0.424824 0.889639 + outer loop + vertex -381.348 99.0137 370.302 + vertex -380.327 102.48 372.15 + vertex -385.538 103.542 371.676 + endloop + endfacet + facet normal -0.165626 -0.412798 0.895637 + outer loop + vertex -385.555 105.663 372.65 + vertex -385.538 103.542 371.676 + vertex -380.327 102.48 372.15 + endloop + endfacet + facet normal -0.167768 -0.416019 0.893746 + outer loop + vertex -385.555 105.663 372.65 + vertex -380.327 102.48 372.15 + vertex -384.361 107.076 373.532 + endloop + endfacet + facet normal -0.186544 -0.401869 0.896495 + outer loop + vertex -384.361 107.076 373.532 + vertex -387.744 108.394 373.419 + vertex -385.555 105.663 372.65 + endloop + endfacet + facet normal -0.185144 -0.400945 0.897198 + outer loop + vertex -385.555 105.663 372.65 + vertex -387.744 108.394 373.419 + vertex -388.392 106.662 372.511 + endloop + endfacet + facet normal -0.202263 -0.394172 0.896503 + outer loop + vertex -387.744 108.394 373.419 + vertex -389.836 109.285 373.339 + vertex -388.392 106.662 372.511 + endloop + endfacet + facet normal -0.195069 -0.391134 0.899423 + outer loop + vertex -388.392 106.662 372.511 + vertex -389.836 109.285 373.339 + vertex -390.4 107.372 372.384 + endloop + endfacet + facet normal -0.201991 -0.393503 0.896858 + outer loop + vertex -387.744 108.394 373.419 + vertex -389.034 110.861 374.211 + vertex -389.836 109.285 373.339 + endloop + endfacet + facet normal -0.216809 -0.385877 0.896712 + outer loop + vertex -389.034 110.861 374.211 + vertex -389.917 112.472 374.69 + vertex -389.836 109.285 373.339 + endloop + endfacet + facet normal -0.211145 -0.38624 0.897906 + outer loop + vertex -389.917 112.472 374.69 + vertex -391.303 108.976 372.861 + vertex -389.836 109.285 373.339 + endloop + endfacet + facet normal -0.260502 -0.364614 0.893977 + outer loop + vertex -389.917 112.472 374.69 + vertex -390.537 111.977 374.308 + vertex -391.303 108.976 372.861 + endloop + endfacet + facet normal -0.222596 -0.388314 0.894239 + outer loop + vertex -389.034 110.861 374.211 + vertex -388.526 113.225 375.364 + vertex -389.917 112.472 374.69 + endloop + endfacet + facet normal -0.223012 -0.387695 0.894404 + outer loop + vertex -388.724 116.37 376.678 + vertex -389.917 112.472 374.69 + vertex -388.526 113.225 375.364 + endloop + endfacet + facet normal -0.229642 -0.387454 0.892829 + outer loop + vertex -387.299 116.017 376.891 + vertex -388.724 116.37 376.678 + vertex -388.526 113.225 375.364 + endloop + endfacet + facet normal -0.211752 -0.395749 0.893613 + outer loop + vertex -386.303 112.498 375.569 + vertex -387.299 116.017 376.891 + vertex -388.526 113.225 375.364 + endloop + endfacet + facet normal -0.211573 -0.395108 0.893939 + outer loop + vertex -386.303 112.498 375.569 + vertex -388.526 113.225 375.364 + vertex -387.131 110.311 374.406 + endloop + endfacet + facet normal -0.193781 -0.402284 0.894772 + outer loop + vertex -384.358 109.422 374.607 + vertex -386.303 112.498 375.569 + vertex -387.131 110.311 374.406 + endloop + endfacet + facet normal -0.195476 -0.408273 0.891685 + outer loop + vertex -384.358 109.422 374.607 + vertex -387.131 110.311 374.406 + vertex -384.361 107.076 373.532 + endloop + endfacet + facet normal -0.171591 -0.410153 0.895729 + outer loop + vertex -384.358 109.422 374.607 + vertex -384.361 107.076 373.532 + vertex -379.339 106.192 374.09 + endloop + endfacet + facet normal -0.176454 -0.417049 0.891591 + outer loop + vertex -384.358 109.422 374.607 + vertex -379.339 106.192 374.09 + vertex -382.971 110.963 375.602 + endloop + endfacet + facet normal -0.174915 -0.416112 0.892332 + outer loop + vertex -379.339 106.192 374.09 + vertex -378.192 110.052 376.114 + vertex -382.971 110.963 375.602 + endloop + endfacet + facet normal -0.174734 -0.414802 0.892977 + outer loop + vertex -382.408 112.765 376.549 + vertex -382.971 110.963 375.602 + vertex -378.192 110.052 376.114 + endloop + endfacet + facet normal -0.16858 -0.406069 0.898159 + outer loop + vertex -378.192 110.052 376.114 + vertex -381.961 115.06 377.671 + vertex -382.408 112.765 376.549 + endloop + endfacet + facet normal -0.193143 -0.400161 0.895861 + outer loop + vertex -382.408 112.765 376.549 + vertex -381.961 115.06 377.671 + vertex -384.866 114.451 376.772 + endloop + endfacet + facet normal -0.194128 -0.397134 0.896994 + outer loop + vertex -384.866 114.451 376.772 + vertex -381.961 115.06 377.671 + vertex -385.19 118.235 378.377 + endloop + endfacet + facet normal -0.212034 -0.396975 0.893002 + outer loop + vertex -387.299 116.017 376.891 + vertex -384.866 114.451 376.772 + vertex -385.19 118.235 378.377 + endloop + endfacet + facet normal -0.217156 -0.392581 0.893713 + outer loop + vertex -385.19 118.235 378.377 + vertex -387.126 120.095 378.724 + vertex -387.299 116.017 376.891 + endloop + endfacet + facet normal -0.221651 -0.396712 0.890781 + outer loop + vertex -385.19 118.235 378.377 + vertex -385.03 122.219 380.192 + vertex -387.126 120.095 378.724 + endloop + endfacet + facet normal -0.224695 -0.394009 0.891217 + outer loop + vertex -387.126 120.095 378.724 + vertex -385.03 122.219 380.192 + vertex -385.711 126.248 381.801 + endloop + endfacet + facet normal -0.267126 -0.381175 0.88507 + outer loop + vertex -387.899 119.98 378.442 + vertex -387.126 120.095 378.724 + vertex -385.711 126.248 381.801 + endloop + endfacet + facet normal -0.269555 -0.372326 0.888095 + outer loop + vertex -387.126 120.095 378.724 + vertex -387.899 119.98 378.442 + vertex -388.724 116.37 376.678 + endloop + endfacet + facet normal -0.227001 -0.394142 0.890574 + outer loop + vertex -382.864 124.934 381.946 + vertex -385.711 126.248 381.801 + vertex -385.03 122.219 380.192 + endloop + endfacet + facet normal -0.209431 -0.407158 0.889023 + outer loop + vertex -382.864 124.934 381.946 + vertex -385.03 122.219 380.192 + vertex -381.507 119.596 379.82 + endloop + endfacet + facet normal -0.205323 -0.406597 0.890237 + outer loop + vertex -381.507 119.596 379.82 + vertex -379.413 122.438 381.602 + vertex -382.864 124.934 381.946 + endloop + endfacet + facet normal -0.2068 -0.408473 0.889035 + outer loop + vertex -379.413 122.438 381.602 + vertex -379.393 126.168 383.32 + vertex -382.864 124.934 381.946 + endloop + endfacet + facet normal -0.208722 -0.404557 0.890375 + outer loop + vertex -382.616 129.839 384.232 + vertex -382.864 124.934 381.946 + vertex -379.393 126.168 383.32 + endloop + endfacet + facet normal -0.212945 -0.407664 0.887955 + outer loop + vertex -379.393 126.168 383.32 + vertex -378.899 130.196 385.287 + vertex -382.616 129.839 384.232 + endloop + endfacet + facet normal -0.212825 -0.408229 0.887725 + outer loop + vertex -381.574 133.863 386.332 + vertex -382.616 129.839 384.232 + vertex -378.899 130.196 385.287 + endloop + endfacet + facet normal -0.214174 -0.409017 0.887037 + outer loop + vertex -378.899 130.196 385.287 + vertex -378.368 134.199 387.262 + vertex -381.574 133.863 386.332 + endloop + endfacet + facet normal -0.214541 -0.407369 0.887706 + outer loop + vertex -381.408 138.013 388.277 + vertex -381.574 133.863 386.332 + vertex -378.368 134.199 387.262 + endloop + endfacet + facet normal -0.218828 -0.410164 0.88537 + outer loop + vertex -378.368 134.199 387.262 + vertex -377.997 138.376 389.288 + vertex -381.408 138.013 388.277 + endloop + endfacet + facet normal -0.218494 -0.411636 0.884769 + outer loop + vertex -380.781 141.948 390.263 + vertex -381.408 138.013 388.277 + vertex -377.997 138.376 389.288 + endloop + endfacet + facet normal -0.220629 -0.412984 0.88361 + outer loop + vertex -377.997 138.376 389.288 + vertex -378.048 143.295 391.575 + vertex -380.781 141.948 390.263 + endloop + endfacet + facet normal -0.222243 -0.410462 0.884381 + outer loop + vertex -381.241 145.46 391.777 + vertex -380.781 141.948 390.263 + vertex -378.048 143.295 391.575 + endloop + endfacet + facet normal -0.227542 -0.41783 0.87957 + outer loop + vertex -380.141 148.018 393.277 + vertex -381.241 145.46 391.777 + vertex -378.048 143.295 391.575 + endloop + endfacet + facet normal -0.221896 -0.416136 0.881813 + outer loop + vertex -378.048 143.295 391.575 + vertex -376.997 147.379 393.766 + vertex -380.141 148.018 393.277 + endloop + endfacet + facet normal -0.222248 -0.418961 0.880385 + outer loop + vertex -379.725 152.005 395.279 + vertex -380.141 148.018 393.277 + vertex -376.997 147.379 393.766 + endloop + endfacet + facet normal -0.222448 -0.419049 0.880293 + outer loop + vertex -376.997 147.379 393.766 + vertex -376.28 151.191 395.762 + vertex -379.725 152.005 395.279 + endloop + endfacet + facet normal -0.223055 -0.422763 0.878361 + outer loop + vertex -378.503 156.03 397.527 + vertex -379.725 152.005 395.279 + vertex -376.28 151.191 395.762 + endloop + endfacet + facet normal -0.214832 -0.420182 0.881643 + outer loop + vertex -376.28 151.191 395.762 + vertex -375.292 153.935 397.311 + vertex -378.503 156.03 397.527 + endloop + endfacet + facet normal -0.215492 -0.421131 0.881029 + outer loop + vertex -375.292 153.935 397.311 + vertex -375.93 157.871 399.036 + vertex -378.503 156.03 397.527 + endloop + endfacet + facet normal -0.214797 -0.421928 0.880817 + outer loop + vertex -379.241 161.189 399.818 + vertex -378.503 156.03 397.527 + vertex -375.93 157.871 399.036 + endloop + endfacet + facet normal -0.218047 -0.424673 0.878697 + outer loop + vertex -375.93 157.871 399.036 + vertex -376.454 163.118 401.442 + vertex -379.241 161.189 399.818 + endloop + endfacet + facet normal -0.216101 -0.426958 0.87807 + outer loop + vertex -379.353 164.928 401.608 + vertex -379.241 161.189 399.818 + vertex -376.454 163.118 401.442 + endloop + endfacet + facet normal -0.217767 -0.429477 0.876429 + outer loop + vertex -378.856 168.108 403.29 + vertex -379.353 164.928 401.608 + vertex -376.454 163.118 401.442 + endloop + endfacet + facet normal -0.238676 -0.424588 0.87336 + outer loop + vertex -379.353 164.928 401.608 + vertex -378.856 168.108 403.29 + vertex -380.801 165.448 401.466 + endloop + endfacet + facet normal -0.238866 -0.425213 0.873005 + outer loop + vertex -379.353 164.928 401.608 + vertex -380.801 165.448 401.466 + vertex -379.241 161.189 399.818 + endloop + endfacet + facet normal -0.236804 -0.42476 0.873786 + outer loop + vertex -380.801 165.448 401.466 + vertex -381.2 157.187 397.342 + vertex -379.241 161.189 399.818 + endloop + endfacet + facet normal -0.192969 -0.424817 0.884474 + outer loop + vertex -371.302 157.165 399.707 + vertex -376.454 163.118 401.442 + vertex -375.93 157.871 399.036 + endloop + endfacet + facet normal -0.192714 -0.421656 0.88604 + outer loop + vertex -371.302 157.165 399.707 + vertex -375.93 157.871 399.036 + vertex -371.291 152.958 397.707 + endloop + endfacet + facet normal -0.168844 -0.423489 0.890027 + outer loop + vertex -365.177 150.826 397.852 + vertex -371.302 157.165 399.707 + vertex -371.291 152.958 397.707 + endloop + endfacet + facet normal -0.168399 -0.422162 0.890742 + outer loop + vertex -365.177 150.826 397.852 + vertex -371.291 152.958 397.707 + vertex -365.431 146.854 395.922 + endloop + endfacet + facet normal -0.144597 -0.425048 0.893547 + outer loop + vertex -357.927 144.321 395.931 + vertex -365.177 150.826 397.852 + vertex -365.431 146.854 395.922 + endloop + endfacet + facet normal -0.144293 -0.424145 0.894025 + outer loop + vertex -357.927 144.321 395.931 + vertex -365.431 146.854 395.922 + vertex -358.25 140.321 393.981 + endloop + endfacet + facet normal -0.120865 -0.427052 0.896113 + outer loop + vertex -349.561 138.052 394.072 + vertex -357.927 144.321 395.931 + vertex -358.25 140.321 393.981 + endloop + endfacet + facet normal -0.120673 -0.426301 0.896496 + outer loop + vertex -349.561 138.052 394.072 + vertex -358.25 140.321 393.981 + vertex -349.887 133.974 392.089 + endloop + endfacet + facet normal -0.0995439 -0.428699 0.897947 + outer loop + vertex -339.328 131.848 392.245 + vertex -349.561 138.052 394.072 + vertex -349.887 133.974 392.089 + endloop + endfacet + facet normal -0.0989283 -0.425526 0.899522 + outer loop + vertex -339.328 131.848 392.245 + vertex -349.887 133.974 392.089 + vertex -341.435 128.411 390.387 + endloop + endfacet + facet normal -0.0861479 -0.43232 0.897596 + outer loop + vertex -341.435 128.411 390.387 + vertex -326.828 123.367 389.36 + vertex -339.328 131.848 392.245 + endloop + endfacet + facet normal -0.0853785 -0.431367 0.898128 + outer loop + vertex -326.828 123.367 389.36 + vertex -326.338 131.398 393.263 + vertex -339.328 131.848 392.245 + endloop + endfacet + facet normal -0.0853841 -0.429399 0.89907 + outer loop + vertex -340.843 136.517 394.331 + vertex -339.328 131.848 392.245 + vertex -326.338 131.398 393.263 + endloop + endfacet + facet normal -0.0857018 -0.430212 0.898651 + outer loop + vertex -340.843 136.517 394.331 + vertex -326.338 131.398 393.263 + vertex -338.782 139.857 396.126 + endloop + endfacet + facet normal -0.0982394 -0.423497 0.900555 + outer loop + vertex -338.782 139.857 396.126 + vertex -349.24 142.029 396.007 + vertex -340.843 136.517 394.331 + endloop + endfacet + facet normal -0.102067 -0.428481 0.897767 + outer loop + vertex -340.843 136.517 394.331 + vertex -349.24 142.029 396.007 + vertex -349.561 138.052 394.072 + endloop + endfacet + facet normal -0.09902 -0.427361 0.898642 + outer loop + vertex -338.782 139.857 396.126 + vertex -348.996 146.013 397.928 + vertex -349.24 142.029 396.007 + endloop + endfacet + facet normal -0.119321 -0.42538 0.897114 + outer loop + vertex -348.996 146.013 397.928 + vertex -357.624 148.302 397.866 + vertex -349.24 142.029 396.007 + endloop + endfacet + facet normal -0.120316 -0.426512 0.896444 + outer loop + vertex -349.24 142.029 396.007 + vertex -357.624 148.302 397.866 + vertex -357.927 144.321 395.931 + endloop + endfacet + facet normal -0.119709 -0.426861 0.896359 + outer loop + vertex -348.996 146.013 397.928 + vertex -357.458 152.41 399.845 + vertex -357.624 148.302 397.866 + endloop + endfacet + facet normal -0.142338 -0.424819 0.894018 + outer loop + vertex -357.458 152.41 399.845 + vertex -364.967 154.945 399.854 + vertex -357.624 148.302 397.866 + endloop + endfacet + facet normal -0.144128 -0.426476 0.892942 + outer loop + vertex -357.624 148.302 397.866 + vertex -364.967 154.945 399.854 + vertex -365.177 150.826 397.852 + endloop + endfacet + facet normal -0.144009 -0.429759 0.891386 + outer loop + vertex -357.458 152.41 399.845 + vertex -364.806 159.213 401.937 + vertex -364.967 154.945 399.854 + endloop + endfacet + facet normal -0.168656 -0.427299 0.88824 + outer loop + vertex -364.806 159.213 401.937 + vertex -371.059 161.566 401.882 + vertex -364.967 154.945 399.854 + endloop + endfacet + facet normal -0.170902 -0.428985 0.886997 + outer loop + vertex -364.967 154.945 399.854 + vertex -371.059 161.566 401.882 + vertex -371.302 157.165 399.707 + endloop + endfacet + facet normal -0.171115 -0.43392 0.884553 + outer loop + vertex -364.806 159.213 401.937 + vertex -370.566 165.705 404.008 + vertex -371.059 161.566 401.882 + endloop + endfacet + facet normal -0.191329 -0.430292 0.88218 + outer loop + vertex -370.566 165.705 404.008 + vertex -375.387 167.506 403.841 + vertex -371.059 161.566 401.882 + endloop + endfacet + facet normal -0.196357 -0.433132 0.879682 + outer loop + vertex -371.059 161.566 401.882 + vertex -375.387 167.506 403.841 + vertex -376.454 163.118 401.442 + endloop + endfacet + facet normal -0.16343 -0.428418 0.888678 + outer loop + vertex -364.58 163.526 404.058 + vertex -370.566 165.705 404.008 + vertex -364.806 159.213 401.937 + endloop + endfacet + facet normal -0.142274 -0.430761 0.891181 + outer loop + vertex -357.5 156.76 401.918 + vertex -364.58 163.526 404.058 + vertex -364.806 159.213 401.937 + endloop + endfacet + facet normal -0.136585 -0.425836 0.894432 + outer loop + vertex -357.356 161.272 404.088 + vertex -364.58 163.526 404.058 + vertex -357.5 156.76 401.918 + endloop + endfacet + facet normal -0.116563 -0.427466 0.896485 + outer loop + vertex -349.066 154.735 402.049 + vertex -357.356 161.272 404.088 + vertex -357.5 156.76 401.918 + endloop + endfacet + facet normal -0.115939 -0.42478 0.897842 + outer loop + vertex -349.066 154.735 402.049 + vertex -357.5 156.76 401.918 + vertex -348.963 150.206 399.92 + endloop + endfacet + facet normal -0.0973358 -0.425283 0.899811 + outer loop + vertex -338.624 148.349 400.161 + vertex -349.066 154.735 402.049 + vertex -348.963 150.206 399.92 + endloop + endfacet + facet normal -0.0966117 -0.420979 0.901911 + outer loop + vertex -338.624 148.349 400.161 + vertex -348.963 150.206 399.92 + vertex -340.441 144.56 398.197 + endloop + endfacet + facet normal -0.0842628 -0.426258 0.900669 + outer loop + vertex -340.441 144.56 398.197 + vertex -325.999 139.655 397.227 + vertex -338.624 148.349 400.161 + endloop + endfacet + facet normal -0.0839127 -0.425829 0.900904 + outer loop + vertex -325.999 139.655 397.227 + vertex -325.46 148.83 401.614 + vertex -338.624 148.349 400.161 + endloop + endfacet + facet normal -0.0841346 -0.423294 0.902077 + outer loop + vertex -340.383 153.689 402.502 + vertex -338.624 148.349 400.161 + vertex -325.46 148.83 401.614 + endloop + endfacet + facet normal -0.0851936 -0.426272 0.900575 + outer loop + vertex -340.383 153.689 402.502 + vertex -325.46 148.83 401.614 + vertex -337.941 158.004 404.776 + endloop + endfacet + facet normal -0.0950961 -0.421363 0.901893 + outer loop + vertex -337.941 158.004 404.776 + vertex -348.842 159.451 404.302 + vertex -340.383 153.689 402.502 + endloop + endfacet + facet normal -0.0981635 -0.4252 0.899761 + outer loop + vertex -340.383 153.689 402.502 + vertex -348.842 159.451 404.302 + vertex -349.066 154.735 402.049 + endloop + endfacet + facet normal -0.095673 -0.426524 0.899402 + outer loop + vertex -337.941 158.004 404.776 + vertex -347.936 163.816 406.469 + vertex -348.842 159.451 404.302 + endloop + endfacet + facet normal -0.109679 -0.423526 0.89922 + outer loop + vertex -347.936 163.816 406.469 + vertex -356.363 165.373 406.174 + vertex -348.842 159.451 404.302 + endloop + endfacet + facet normal -0.114132 -0.428291 0.896404 + outer loop + vertex -348.842 159.451 404.302 + vertex -356.363 165.373 406.174 + vertex -357.356 161.272 404.088 + endloop + endfacet + facet normal -0.130783 -0.424115 0.896115 + outer loop + vertex -356.363 165.373 406.174 + vertex -363.746 167.548 406.126 + vertex -357.356 161.272 404.088 + endloop + endfacet + facet normal -0.131836 -0.427732 0.89424 + outer loop + vertex -356.363 165.373 406.174 + vertex -361.072 170.469 407.917 + vertex -363.746 167.548 406.126 + endloop + endfacet + facet normal -0.110713 -0.429704 0.896157 + outer loop + vertex -347.936 163.816 406.469 + vertex -354.251 168.166 407.774 + vertex -356.363 165.373 406.174 + endloop + endfacet + facet normal -0.095652 -0.426493 0.899419 + outer loop + vertex -338.902 163.079 407.08 + vertex -347.936 163.816 406.469 + vertex -337.941 158.004 404.776 + endloop + endfacet + facet normal -0.0848947 -0.425218 0.901101 + outer loop + vertex -338.902 163.079 407.08 + vertex -337.941 158.004 404.776 + vertex -322.975 158.961 406.637 + endloop + endfacet + facet normal -0.0956218 -0.425879 0.899713 + outer loop + vertex -338.902 163.079 407.08 + vertex -346.739 167.484 408.332 + vertex -347.936 163.816 406.469 + endloop + endfacet + facet normal -0.0848189 -0.425844 0.900812 + outer loop + vertex -325.46 148.83 401.614 + vertex -322.975 158.961 406.637 + vertex -337.941 158.004 404.776 + endloop + endfacet + facet normal -0.0766612 -0.427758 0.900637 + outer loop + vertex -304.764 146.683 402.355 + vertex -322.975 158.961 406.637 + vertex -325.46 148.83 401.614 + endloop + endfacet + facet normal -0.0765566 -0.426548 0.901219 + outer loop + vertex -304.764 146.683 402.355 + vertex -325.46 148.83 401.614 + vertex -305.914 137.23 397.784 + endloop + endfacet + facet normal -0.070067 -0.427398 0.901344 + outer loop + vertex -286.398 134.641 398.073 + vertex -304.764 146.683 402.355 + vertex -305.914 137.23 397.784 + endloop + endfacet + facet normal -0.0702067 -0.428512 0.900804 + outer loop + vertex -286.398 134.641 398.073 + vertex -305.914 137.23 397.784 + vertex -286.64 125.857 393.876 + endloop + endfacet + facet normal -0.0644209 -0.42881 0.901095 + outer loop + vertex -267.662 123.037 393.891 + vertex -286.398 134.641 398.073 + vertex -286.64 125.857 393.876 + endloop + endfacet + facet normal -0.0648686 -0.431829 0.89962 + outer loop + vertex -267.662 123.037 393.891 + vertex -286.64 125.857 393.876 + vertex -267.686 114.895 389.981 + endloop + endfacet + facet normal -0.0599058 -0.431975 0.899894 + outer loop + vertex -248.891 112.13 389.904 + vertex -267.662 123.037 393.891 + vertex -267.686 114.895 389.981 + endloop + endfacet + facet normal -0.0606059 -0.436669 0.897578 + outer loop + vertex -248.891 112.13 389.904 + vertex -267.686 114.895 389.981 + vertex -249.108 104.359 386.109 + endloop + endfacet + facet normal -0.0563652 -0.436874 0.897755 + outer loop + vertex -230.293 101.815 386.053 + vertex -248.891 112.13 389.904 + vertex -249.108 104.359 386.109 + endloop + endfacet + facet normal -0.0572236 -0.443151 0.894619 + outer loop + vertex -230.293 101.815 386.053 + vertex -249.108 104.359 386.109 + vertex -230.702 94.1041 382.207 + endloop + endfacet + facet normal -0.053313 -0.443414 0.89473 + outer loop + vertex -211.778 91.8084 382.197 + vertex -230.293 101.815 386.053 + vertex -230.702 94.1041 382.207 + endloop + endfacet + facet normal -0.0542712 -0.451294 0.890723 + outer loop + vertex -211.778 91.8084 382.197 + vertex -230.702 94.1041 382.207 + vertex -212.1 84.0644 378.254 + endloop + endfacet + facet normal -0.049905 -0.451542 0.890853 + outer loop + vertex -193.045 81.9849 378.267 + vertex -211.778 91.8084 382.197 + vertex -212.1 84.0644 378.254 + endloop + endfacet + facet normal -0.0508382 -0.460122 0.886399 + outer loop + vertex -193.045 81.9849 378.267 + vertex -212.1 84.0644 378.254 + vertex -193.024 74.4516 374.358 + endloop + endfacet + facet normal -0.0458422 -0.460222 0.886619 + outer loop + vertex -173.821 72.5645 374.371 + vertex -193.045 81.9849 378.267 + vertex -193.024 74.4516 374.358 + endloop + endfacet + facet normal -0.046647 -0.468442 0.882262 + outer loop + vertex -173.821 72.5645 374.371 + vertex -193.024 74.4516 374.358 + vertex -173.559 65.7775 370.781 + endloop + endfacet + facet normal -0.0414014 -0.468391 0.88255 + outer loop + vertex -154.238 64.0806 370.787 + vertex -173.821 72.5645 374.371 + vertex -173.559 65.7775 370.781 + endloop + endfacet + facet normal -0.0420041 -0.475266 0.878839 + outer loop + vertex -154.238 64.0806 370.787 + vertex -173.559 65.7775 370.781 + vertex -154.456 58.6434 367.836 + endloop + endfacet + facet normal -0.0417068 -0.468962 0.882233 + outer loop + vertex -154.486 70.8478 374.373 + vertex -173.821 72.5645 374.371 + vertex -154.238 64.0806 370.787 + endloop + endfacet + facet normal -0.0363839 -0.468908 0.882497 + outer loop + vertex -134.807 62.5673 370.784 + vertex -154.486 70.8478 374.373 + vertex -154.238 64.0806 370.787 + endloop + endfacet + facet normal -0.0368992 -0.475518 0.878932 + outer loop + vertex -134.807 62.5673 370.784 + vertex -154.238 64.0806 370.787 + vertex -135.142 57.1389 367.833 + endloop + endfacet + facet normal -0.0363501 -0.468843 0.882533 + outer loop + vertex -135.055 69.348 374.376 + vertex -154.486 70.8478 374.373 + vertex -134.807 62.5673 370.784 + endloop + endfacet + facet normal -0.0311074 -0.468776 0.882769 + outer loop + vertex -115.34 61.2667 370.78 + vertex -135.055 69.348 374.376 + vertex -134.807 62.5673 370.784 + endloop + endfacet + facet normal -0.0315651 -0.475614 0.879088 + outer loop + vertex -115.34 61.2667 370.78 + vertex -134.807 62.5673 370.784 + vertex -115.681 55.8307 367.826 + endloop + endfacet + facet normal -0.0313125 -0.469179 0.882548 + outer loop + vertex -115.615 68.043 374.372 + vertex -135.055 69.348 374.376 + vertex -115.34 61.2667 370.78 + endloop + endfacet + facet normal -0.0257542 -0.469077 0.882782 + outer loop + vertex -95.913 60.1923 370.775 + vertex -115.615 68.043 374.372 + vertex -115.34 61.2667 370.78 + endloop + endfacet + facet normal -0.0261192 -0.475664 0.879239 + outer loop + vertex -95.913 60.1923 370.775 + vertex -115.34 61.2667 370.78 + vertex -96.2885 54.7497 367.82 + endloop + endfacet + facet normal -0.0259134 -0.469397 0.882607 + outer loop + vertex -96.2021 66.9622 374.367 + vertex -115.615 68.043 374.372 + vertex -95.913 60.1923 370.775 + endloop + endfacet + facet normal -0.0205468 -0.469277 0.882812 + outer loop + vertex -76.5106 59.3342 370.771 + vertex -96.2021 66.9622 374.367 + vertex -95.913 60.1923 370.775 + endloop + endfacet + facet normal -0.0208394 -0.475873 0.879267 + outer loop + vertex -76.5106 59.3342 370.771 + vertex -95.913 60.1923 370.775 + vertex -77.0031 53.8925 367.814 + endloop + endfacet + facet normal -0.0206049 -0.469396 0.882747 + outer loop + vertex -76.8283 66.1148 374.369 + vertex -96.2021 66.9622 374.367 + vertex -76.5106 59.3342 370.771 + endloop + endfacet + facet normal -0.015393 -0.469249 0.882931 + outer loop + vertex -57.1216 58.7158 370.78 + vertex -76.8283 66.1148 374.369 + vertex -76.5106 59.3342 370.771 + endloop + endfacet + facet normal -0.0156003 -0.475803 0.879413 + outer loop + vertex -57.1216 58.7158 370.78 + vertex -76.5106 59.3342 370.771 + vertex -57.7171 53.2547 367.815 + endloop + endfacet + facet normal -0.0155682 -0.469619 0.882732 + outer loop + vertex -57.4609 65.4659 374.365 + vertex -76.8283 66.1148 374.369 + vertex -57.1216 58.7158 370.78 + endloop + endfacet + facet normal -0.0106851 -0.469458 0.88289 + outer loop + vertex -37.7389 58.29 370.788 + vertex -57.4609 65.4659 374.365 + vertex -57.1216 58.7158 370.78 + endloop + endfacet + facet normal -0.0108242 -0.475853 0.879458 + outer loop + vertex -37.7389 58.29 370.788 + vertex -57.1216 58.7158 370.78 + vertex -38.3504 52.8394 367.832 + endloop + endfacet + facet normal -0.0107499 -0.469598 0.882815 + outer loop + vertex -38.1191 65.0286 374.368 + vertex -57.4609 65.4659 374.365 + vertex -37.7389 58.29 370.788 + endloop + endfacet + facet normal -0.00629383 -0.46942 0.882953 + outer loop + vertex -18.4082 58.0325 370.789 + vertex -38.1191 65.0286 374.368 + vertex -37.7389 58.29 370.788 + endloop + endfacet + facet normal -0.00638205 -0.476055 0.879392 + outer loop + vertex -18.4082 58.0325 370.789 + vertex -37.7389 58.29 370.788 + vertex -18.9322 52.5998 367.845 + endloop + endfacet + facet normal -0.0062916 -0.469415 0.882955 + outer loop + vertex -18.7895 64.7721 374.37 + vertex -38.1191 65.0286 374.368 + vertex -18.4082 58.0325 370.789 + endloop + endfacet + facet normal -0.00191474 -0.46923 0.883074 + outer loop + vertex 0.903917 57.9425 370.783 + vertex -18.7895 64.7721 374.37 + vertex -18.4082 58.0325 370.789 + endloop + endfacet + facet normal -0.00194813 -0.476156 0.879359 + outer loop + vertex 0.903917 57.9425 370.783 + vertex -18.4082 58.0325 370.789 + vertex 0.390189 52.5252 367.849 + endloop + endfacet + facet normal -0.00192443 -0.469252 0.883062 + outer loop + vertex 0.554547 64.6961 374.371 + vertex -18.7895 64.7721 374.37 + vertex 0.903917 57.9425 370.783 + endloop + endfacet + facet normal 0.00235771 -0.469079 0.883153 + outer loop + vertex 20.2376 58.0256 370.776 + vertex 0.554547 64.6961 374.371 + vertex 0.903917 57.9425 370.783 + endloop + endfacet + facet normal 0.00238693 -0.476222 0.879322 + outer loop + vertex 20.2376 58.0256 370.776 + vertex 0.903917 57.9425 370.783 + vertex 19.7394 52.5894 367.833 + endloop + endfacet + facet normal 0.00223417 -0.469363 0.883003 + outer loop + vertex 19.9257 64.7855 374.37 + vertex 0.554547 64.6961 374.371 + vertex 20.2376 58.0256 370.776 + endloop + endfacet + facet normal 0.00666468 -0.469194 0.88307 + outer loop + vertex 39.6061 58.2964 370.774 + vertex 19.9257 64.7855 374.37 + vertex 20.2376 58.0256 370.776 + endloop + endfacet + facet normal 0.0067586 -0.475944 0.87945 + outer loop + vertex 39.6061 58.2964 370.774 + vertex 20.2376 58.0256 370.776 + vertex 39.0729 52.8164 367.812 + endloop + endfacet + facet normal 0.00652227 -0.469528 0.882893 + outer loop + vertex 39.3226 65.0546 374.37 + vertex 19.9257 64.7855 374.37 + vertex 39.6061 58.2964 370.774 + endloop + endfacet + facet normal 0.0111568 -0.469357 0.882938 + outer loop + vertex 59.0244 58.7551 370.772 + vertex 39.3226 65.0546 374.37 + vertex 39.6061 58.2964 370.774 + endloop + endfacet + facet normal 0.0113116 -0.475921 0.879415 + outer loop + vertex 59.0244 58.7551 370.772 + vertex 39.6061 58.2964 370.774 + vertex 58.2963 53.2781 367.817 + endloop + endfacet + facet normal 0.0110619 -0.469585 0.882818 + outer loop + vertex 58.7383 65.5086 374.368 + vertex 39.3226 65.0546 374.37 + vertex 59.0244 58.7551 370.772 + endloop + endfacet + facet normal 0.0159358 -0.469394 0.882845 + outer loop + vertex 78.4561 59.42 370.775 + vertex 58.7383 65.5086 374.368 + vertex 59.0244 58.7551 370.772 + endloop + endfacet + facet normal 0.0161482 -0.475587 0.879521 + outer loop + vertex 78.4561 59.42 370.775 + vertex 59.0244 58.7551 370.772 + vertex 77.5934 53.9295 367.822 + endloop + endfacet + facet normal 0.0159035 -0.469473 0.882803 + outer loop + vertex 78.1398 66.1653 374.368 + vertex 58.7383 65.5086 374.368 + vertex 78.4561 59.42 370.775 + endloop + endfacet + facet normal 0.0210307 -0.469242 0.882819 + outer loop + vertex 97.8513 60.2964 370.779 + vertex 78.1398 66.1653 374.368 + vertex 78.4561 59.42 370.775 + endloop + endfacet + facet normal 0.0213064 -0.47533 0.87955 + outer loop + vertex 97.8513 60.2964 370.779 + vertex 78.4561 59.42 370.775 + vertex 97.0224 54.7905 367.823 + endloop + endfacet + facet normal 0.0209538 -0.469437 0.882717 + outer loop + vertex 97.4994 67.0239 374.365 + vertex 78.1398 66.1653 374.368 + vertex 97.8513 60.2964 370.779 + endloop + endfacet + facet normal 0.026202 -0.469165 0.882722 + outer loop + vertex 117.154 61.3713 370.777 + vertex 97.4994 67.0239 374.365 + vertex 97.8513 60.2964 370.779 + endloop + endfacet + facet normal 0.026535 -0.47515 0.879505 + outer loop + vertex 117.154 61.3713 370.777 + vertex 97.8513 60.2964 370.779 + vertex 116.427 55.8634 367.823 + endloop + endfacet + facet normal 0.0263192 -0.468859 0.882881 + outer loop + vertex 116.783 68.1128 374.368 + vertex 97.4994 67.0239 374.365 + vertex 117.154 61.3713 370.777 + endloop + endfacet + facet normal 0.0314722 -0.468568 0.882867 + outer loop + vertex 136.344 62.6679 370.781 + vertex 116.783 68.1128 374.368 + vertex 117.154 61.3713 370.777 + endloop + endfacet + facet normal 0.0318955 -0.474822 0.879504 + outer loop + vertex 136.344 62.6679 370.781 + vertex 117.154 61.3713 370.777 + vertex 135.593 57.1378 367.823 + endloop + endfacet + facet normal 0.0313009 -0.469027 0.882629 + outer loop + vertex 135.993 69.391 374.366 + vertex 116.783 68.1128 374.368 + vertex 136.344 62.6679 370.781 + endloop + endfacet + facet normal 0.0366001 -0.468726 0.882585 + outer loop + vertex 155.531 64.1666 370.781 + vertex 135.993 69.391 374.366 + vertex 136.344 62.6679 370.781 + endloop + endfacet + facet normal 0.0371012 -0.475141 0.879127 + outer loop + vertex 155.531 64.1666 370.781 + vertex 136.344 62.6679 370.781 + vertex 154.698 58.6551 367.838 + endloop + endfacet + facet normal 0.036637 -0.468624 0.882638 + outer loop + vertex 155.151 70.8985 374.371 + vertex 135.993 69.391 374.366 + vertex 155.531 64.1666 370.781 + endloop + endfacet + facet normal 0.0417646 -0.468304 0.88258 + outer loop + vertex 174.759 65.8885 370.785 + vertex 155.151 70.8985 374.371 + vertex 155.531 64.1666 370.781 + endloop + endfacet + facet normal 0.042385 -0.475223 0.878844 + outer loop + vertex 174.759 65.8885 370.785 + vertex 155.531 64.1666 370.781 + vertex 174.05 60.3871 367.844 + endloop + endfacet + facet normal 0.041738 -0.46838 0.882541 + outer loop + vertex 174.295 72.61 374.374 + vertex 155.151 70.8985 374.371 + vertex 174.759 65.8885 370.785 + endloop + endfacet + facet normal 0.046712 -0.468009 0.882488 + outer loop + vertex 193.993 67.8137 370.788 + vertex 174.295 72.61 374.374 + vertex 174.759 65.8885 370.785 + endloop + endfacet + facet normal 0.0474402 -0.475278 0.878556 + outer loop + vertex 193.993 67.8137 370.788 + vertex 174.759 65.8885 370.785 + vertex 193.664 62.3117 367.829 + endloop + endfacet + facet normal 0.0467172 -0.467993 0.882496 + outer loop + vertex 193.425 74.5251 374.377 + vertex 174.295 72.61 374.374 + vertex 193.993 67.8137 370.788 + endloop + endfacet + facet normal 0.0515801 -0.46756 0.882455 + outer loop + vertex 213.168 69.9308 370.789 + vertex 193.425 74.5251 374.377 + vertex 193.993 67.8137 370.788 + endloop + endfacet + facet normal 0.0523828 -0.474827 0.878519 + outer loop + vertex 213.168 69.9308 370.789 + vertex 193.993 67.8137 370.788 + vertex 213.087 64.4845 367.85 + endloop + endfacet + facet normal 0.0515396 -0.467684 0.882392 + outer loop + vertex 212.543 76.6339 374.378 + vertex 193.425 74.5251 374.377 + vertex 213.168 69.9308 370.789 + endloop + endfacet + facet normal 0.0563856 -0.467209 0.882347 + outer loop + vertex 232.282 72.2315 370.786 + vertex 212.543 76.6339 374.378 + vertex 213.168 69.9308 370.789 + endloop + endfacet + facet normal 0.0572288 -0.474219 0.878545 + outer loop + vertex 232.282 72.2315 370.786 + vertex 213.168 69.9308 370.789 + vertex 232.389 66.7832 367.838 + endloop + endfacet + facet normal 0.0562906 -0.467509 0.882194 + outer loop + vertex 231.634 78.9121 374.367 + vertex 212.543 76.6339 374.378 + vertex 232.282 72.2315 370.786 + endloop + endfacet + facet normal 0.0606569 -0.467058 0.882143 + outer loop + vertex 251.318 74.6584 370.762 + vertex 231.634 78.9121 374.367 + vertex 232.282 72.2315 370.786 + endloop + endfacet + facet normal 0.0615598 -0.474179 0.878274 + outer loop + vertex 251.318 74.6584 370.762 + vertex 232.282 72.2315 370.786 + vertex 251.481 69.236 367.823 + endloop + endfacet + facet normal 0.0605659 -0.467353 0.881994 + outer loop + vertex 250.643 81.3234 374.34 + vertex 231.634 78.9121 374.367 + vertex 251.318 74.6584 370.762 + endloop + endfacet + facet normal 0.0648719 -0.466885 0.881935 + outer loop + vertex 270.277 77.2658 370.747 + vertex 250.643 81.3234 374.34 + vertex 251.318 74.6584 370.762 + endloop + endfacet + facet normal 0.06583 -0.473873 0.878129 + outer loop + vertex 270.277 77.2658 370.747 + vertex 251.318 74.6584 370.762 + vertex 270.38 71.825 367.804 + endloop + endfacet + facet normal 0.0648 -0.467126 0.881813 + outer loop + vertex 269.621 83.9218 374.322 + vertex 250.643 81.3234 374.34 + vertex 270.277 77.2658 370.747 + endloop + endfacet + facet normal 0.0695918 -0.466605 0.881724 + outer loop + vertex 289.42 80.2041 370.791 + vertex 269.621 83.9218 374.322 + vertex 270.277 77.2658 370.747 + endloop + endfacet + facet normal 0.0705014 -0.472483 0.878515 + outer loop + vertex 289.42 80.2041 370.791 + vertex 270.277 77.2658 370.747 + vertex 289.322 74.6647 367.82 + endloop + endfacet + facet normal 0.063712 -0.45915 0.886071 + outer loop + vertex 269.621 83.9218 374.322 + vertex 250.151 88.7784 378.238 + vertex 250.643 81.3234 374.34 + endloop + endfacet + facet normal 0.0594789 -0.459491 0.886189 + outer loop + vertex 250.151 88.7784 378.238 + vertex 231.196 86.3944 378.274 + vertex 250.643 81.3234 374.34 + endloop + endfacet + facet normal 0.0583944 -0.4508 0.890713 + outer loop + vertex 250.151 88.7784 378.238 + vertex 231.074 94.1772 382.221 + vertex 231.196 86.3944 378.274 + endloop + endfacet + facet normal 0.0541901 -0.450959 0.890898 + outer loop + vertex 231.074 94.1772 382.221 + vertex 212.057 91.9232 382.237 + vertex 231.196 86.3944 378.274 + endloop + endfacet + facet normal 0.0541435 -0.451079 0.89084 + outer loop + vertex 231.196 86.3944 378.274 + vertex 212.057 91.9232 382.237 + vertex 212.133 84.1368 378.29 + endloop + endfacet + facet normal 0.0551506 -0.459614 0.886405 + outer loop + vertex 231.196 86.3944 378.274 + vertex 212.133 84.1368 378.29 + vertex 231.634 78.9121 374.367 + endloop + endfacet + facet normal 0.0500268 -0.451208 0.891015 + outer loop + vertex 212.057 91.9232 382.237 + vertex 192.944 89.7975 382.234 + vertex 212.133 84.1368 378.29 + endloop + endfacet + facet normal 0.0499435 -0.451419 0.890913 + outer loop + vertex 212.133 84.1368 378.29 + vertex 192.944 89.7975 382.234 + vertex 193.003 82.0128 378.286 + endloop + endfacet + facet normal 0.050842 -0.459504 0.886719 + outer loop + vertex 212.133 84.1368 378.29 + vertex 193.003 82.0128 378.286 + vertex 212.543 76.6339 374.378 + endloop + endfacet + facet normal 0.0451507 -0.451552 0.891102 + outer loop + vertex 192.944 89.7975 382.234 + vertex 173.8 87.8662 382.225 + vertex 193.003 82.0128 378.286 + endloop + endfacet + facet normal 0.0450928 -0.451695 0.891032 + outer loop + vertex 193.003 82.0128 378.286 + vertex 173.8 87.8662 382.225 + vertex 173.871 80.09 378.279 + endloop + endfacet + facet normal 0.0459533 -0.460242 0.886603 + outer loop + vertex 193.003 82.0128 378.286 + vertex 173.871 80.09 378.279 + vertex 193.425 74.5251 374.377 + endloop + endfacet + facet normal 0.040329 -0.451821 0.891196 + outer loop + vertex 173.8 87.8662 382.225 + vertex 154.651 86.15 382.221 + vertex 173.871 80.09 378.279 + endloop + endfacet + facet normal 0.0401995 -0.452133 0.891044 + outer loop + vertex 173.871 80.09 378.279 + vertex 154.651 86.15 382.221 + vertex 154.736 78.3884 378.279 + endloop + endfacet + facet normal 0.0409516 -0.460591 0.886667 + outer loop + vertex 173.871 80.09 378.279 + vertex 154.736 78.3884 378.279 + vertex 174.295 72.61 374.374 + endloop + endfacet + facet normal 0.0354173 -0.452257 0.891184 + outer loop + vertex 154.651 86.15 382.221 + vertex 135.48 84.6482 382.221 + vertex 154.736 78.3884 378.279 + endloop + endfacet + facet normal 0.0352761 -0.452589 0.891021 + outer loop + vertex 154.736 78.3884 378.279 + vertex 135.48 84.6482 382.221 + vertex 135.574 76.892 378.278 + endloop + endfacet + facet normal 0.0359115 -0.460721 0.886818 + outer loop + vertex 154.736 78.3884 378.279 + vertex 135.574 76.892 378.278 + vertex 155.151 70.8985 374.371 + endloop + endfacet + facet normal 0.0302799 -0.452711 0.891143 + outer loop + vertex 135.48 84.6482 382.221 + vertex 116.262 83.3638 382.222 + vertex 135.574 76.892 378.278 + endloop + endfacet + facet normal 0.0303953 -0.452446 0.891274 + outer loop + vertex 135.574 76.892 378.278 + vertex 116.262 83.3638 382.222 + vertex 116.354 75.5991 378.277 + endloop + endfacet + facet normal 0.0309581 -0.460809 0.886959 + outer loop + vertex 135.574 76.892 378.278 + vertex 116.354 75.5991 378.277 + vertex 135.993 69.391 374.366 + endloop + endfacet + facet normal 0.025234 -0.452559 0.891377 + outer loop + vertex 116.262 83.3638 382.222 + vertex 96.977 82.2919 382.223 + vertex 116.354 75.5991 378.277 + endloop + endfacet + facet normal 0.0251715 -0.4527 0.891308 + outer loop + vertex 116.354 75.5991 378.277 + vertex 96.977 82.2919 382.223 + vertex 97.0681 74.53 378.279 + endloop + endfacet + facet normal 0.0256605 -0.461528 0.886754 + outer loop + vertex 116.354 75.5991 378.277 + vertex 97.0681 74.53 378.279 + vertex 116.783 68.1128 374.368 + endloop + endfacet + facet normal 0.0201545 -0.452798 0.891385 + outer loop + vertex 96.977 82.2919 382.223 + vertex 77.6398 81.4354 382.226 + vertex 97.0681 74.53 378.279 + endloop + endfacet + facet normal 0.0201363 -0.452838 0.891365 + outer loop + vertex 97.0681 74.53 378.279 + vertex 77.6398 81.4354 382.226 + vertex 77.7271 73.677 378.282 + endloop + endfacet + facet normal 0.0205097 -0.461323 0.886995 + outer loop + vertex 97.0681 74.53 378.279 + vertex 77.7271 73.677 378.282 + vertex 97.4994 67.0239 374.365 + endloop + endfacet + facet normal 0.0152842 -0.45292 0.89142 + outer loop + vertex 77.6398 81.4354 382.226 + vertex 58.2882 80.7855 382.227 + vertex 77.7271 73.677 378.282 + endloop + endfacet + facet normal 0.015237 -0.453021 0.891369 + outer loop + vertex 77.7271 73.677 378.282 + vertex 58.2882 80.7855 382.227 + vertex 58.3647 73.0291 378.284 + endloop + endfacet + facet normal 0.0155172 -0.461408 0.887052 + outer loop + vertex 77.7271 73.677 378.282 + vertex 58.3647 73.0291 378.284 + vertex 78.1398 66.1653 374.368 + endloop + endfacet + facet normal 0.0105249 -0.453086 0.891405 + outer loop + vertex 58.2882 80.7855 382.227 + vertex 38.9563 80.3367 382.227 + vertex 58.3647 73.0291 378.284 + endloop + endfacet + facet normal 0.0106106 -0.452907 0.891495 + outer loop + vertex 58.3647 73.0291 378.284 + vertex 38.9563 80.3367 382.227 + vertex 39.0007 72.5775 378.285 + endloop + endfacet + facet normal 0.0108082 -0.461391 0.887131 + outer loop + vertex 58.3647 73.0291 378.284 + vertex 39.0007 72.5775 378.285 + vertex 58.7383 65.5086 374.368 + endloop + endfacet + facet normal 0.00630385 -0.452943 0.891517 + outer loop + vertex 38.9563 80.3367 382.227 + vertex 19.6347 80.0699 382.228 + vertex 39.0007 72.5775 378.285 + endloop + endfacet + facet normal 0.00631309 -0.452924 0.891527 + outer loop + vertex 39.0007 72.5775 378.285 + vertex 19.6347 80.0699 382.228 + vertex 19.6343 72.304 378.283 + endloop + endfacet + facet normal 0.00643359 -0.461428 0.887154 + outer loop + vertex 39.0007 72.5775 378.285 + vertex 19.6343 72.304 378.283 + vertex 39.3226 65.0546 374.37 + endloop + endfacet + facet normal 0.00205341 -0.452932 0.891543 + outer loop + vertex 19.6347 80.0699 382.228 + vertex 0.29989 79.9798 382.227 + vertex 19.6343 72.304 378.283 + endloop + endfacet + facet normal 0.00196551 -0.453107 0.891454 + outer loop + vertex 19.6343 72.304 378.283 + vertex 0.29989 79.9798 382.227 + vertex 0.268516 72.2183 378.282 + endloop + endfacet + facet normal 0.0020034 -0.46162 0.887075 + outer loop + vertex 19.6343 72.304 378.283 + vertex 0.268516 72.2183 378.282 + vertex 19.9257 64.7855 374.37 + endloop + endfacet + facet normal -0.0020792 -0.453094 0.89146 + outer loop + vertex 0.29989 79.9798 382.227 + vertex -19.0616 80.0651 382.225 + vertex 0.268516 72.2183 378.282 + endloop + endfacet + facet normal -0.00199049 -0.45292 0.891549 + outer loop + vertex 0.268516 72.2183 378.282 + vertex -19.0616 80.0651 382.225 + vertex -19.1033 72.3005 378.281 + endloop + endfacet + facet normal -0.0020259 -0.461345 0.887219 + outer loop + vertex 0.268516 72.2183 378.282 + vertex -19.1033 72.3005 378.281 + vertex 0.554547 64.6961 374.371 + endloop + endfacet + facet normal -0.00610844 -0.452895 0.891543 + outer loop + vertex -19.0616 80.0651 382.225 + vertex -38.4371 80.3234 382.224 + vertex -19.1033 72.3005 378.281 + endloop + endfacet + facet normal -0.00612501 -0.452927 0.891527 + outer loop + vertex -19.1033 72.3005 378.281 + vertex -38.4371 80.3234 382.224 + vertex -38.4657 72.5594 378.279 + endloop + endfacet + facet normal -0.00623543 -0.461207 0.88727 + outer loop + vertex -19.1033 72.3005 378.281 + vertex -38.4657 72.5594 378.279 + vertex -18.7895 64.7721 374.37 + endloop + endfacet + facet normal -0.0104502 -0.452898 0.891501 + outer loop + vertex -38.4371 80.3234 382.224 + vertex -57.7919 80.7677 382.223 + vertex -38.4657 72.5594 378.279 + endloop + endfacet + facet normal -0.0104351 -0.45287 0.891516 + outer loop + vertex -38.4657 72.5594 378.279 + vertex -57.7919 80.7677 382.223 + vertex -57.806 73.0049 378.279 + endloop + endfacet + facet normal -0.010628 -0.461244 0.88721 + outer loop + vertex -38.4657 72.5594 378.279 + vertex -57.806 73.0049 378.279 + vertex -38.1191 65.0286 374.368 + endloop + endfacet + facet normal -0.0149858 -0.452837 0.891467 + outer loop + vertex -57.7919 80.7677 382.223 + vertex -77.1037 81.4076 382.223 + vertex -57.806 73.0049 378.279 + endloop + endfacet + facet normal -0.0150979 -0.453044 0.89136 + outer loop + vertex -57.806 73.0049 378.279 + vertex -77.1037 81.4076 382.223 + vertex -77.1227 73.6506 378.28 + endloop + endfacet + facet normal -0.0153725 -0.461252 0.887136 + outer loop + vertex -57.806 73.0049 378.279 + vertex -77.1227 73.6506 378.28 + vertex -57.4609 65.4659 374.365 + endloop + endfacet + facet normal -0.0200162 -0.452995 0.891288 + outer loop + vertex -77.1037 81.4076 382.223 + vertex -96.3884 82.2621 382.224 + vertex -77.1227 73.6506 378.28 + endloop + endfacet + facet normal -0.0198318 -0.452662 0.891461 + outer loop + vertex -77.1227 73.6506 378.28 + vertex -96.3884 82.2621 382.224 + vertex -96.4459 74.4992 378.281 + endloop + endfacet + facet normal -0.0202065 -0.461188 0.887072 + outer loop + vertex -77.1227 73.6506 378.28 + vertex -96.4459 74.4992 378.281 + vertex -76.8283 66.1148 374.369 + endloop + endfacet + facet normal -0.0251849 -0.452576 0.89137 + outer loop + vertex -96.3884 82.2621 382.224 + vertex -115.695 83.3389 382.225 + vertex -96.4459 74.4992 378.281 + endloop + endfacet + facet normal -0.0251706 -0.452551 0.891383 + outer loop + vertex -96.4459 74.4992 378.281 + vertex -115.695 83.3389 382.225 + vertex -115.794 75.5818 378.284 + endloop + endfacet + facet normal -0.0256637 -0.46135 0.886847 + outer loop + vertex -96.4459 74.4992 378.281 + vertex -115.794 75.5818 378.284 + vertex -96.2021 66.9622 374.367 + endloop + endfacet + facet normal -0.0301907 -0.452437 0.891285 + outer loop + vertex -115.695 83.3389 382.225 + vertex -135.039 84.6365 382.229 + vertex -115.794 75.5818 378.284 + endloop + endfacet + facet normal -0.0301395 -0.452348 0.891332 + outer loop + vertex -115.794 75.5818 378.284 + vertex -135.039 84.6365 382.229 + vertex -135.188 76.8769 378.286 + endloop + endfacet + facet normal -0.0307159 -0.460975 0.886881 + outer loop + vertex -115.794 75.5818 378.284 + vertex -135.188 76.8769 378.286 + vertex -115.615 68.043 374.372 + endloop + endfacet + facet normal -0.0353339 -0.452192 0.89122 + outer loop + vertex -135.039 84.6365 382.229 + vertex -154.374 86.1486 382.23 + vertex -135.188 76.8769 378.286 + endloop + endfacet + facet normal -0.0353378 -0.452199 0.891217 + outer loop + vertex -135.188 76.8769 378.286 + vertex -154.374 86.1486 382.23 + vertex -154.568 78.3944 378.287 + endloop + endfacet + facet normal -0.036032 -0.461059 0.886638 + outer loop + vertex -135.188 76.8769 378.286 + vertex -154.568 78.3944 378.287 + vertex -135.055 69.348 374.376 + endloop + endfacet + facet normal -0.0402723 -0.452016 0.8911 + outer loop + vertex -154.374 86.1486 382.23 + vertex -173.625 87.8534 382.224 + vertex -154.568 78.3944 378.287 + endloop + endfacet + facet normal -0.0401693 -0.451846 0.891191 + outer loop + vertex -154.568 78.3944 378.287 + vertex -173.625 87.8534 382.224 + vertex -173.869 80.0976 378.281 + endloop + endfacet + facet normal -0.0409264 -0.460442 0.886746 + outer loop + vertex -154.568 78.3944 378.287 + vertex -173.869 80.0976 378.281 + vertex -154.486 70.8478 374.373 + endloop + endfacet + facet normal -0.0450394 -0.451631 0.891067 + outer loop + vertex -173.625 87.8534 382.224 + vertex -192.757 89.7359 382.211 + vertex -173.869 80.0976 378.281 + endloop + endfacet + facet normal -0.0451082 -0.451741 0.891008 + outer loop + vertex -173.869 80.0976 378.281 + vertex -192.757 89.7359 382.211 + vertex -193.045 81.9849 378.267 + endloop + endfacet + facet normal -0.0442955 -0.444043 0.89491 + outer loop + vertex -173.625 87.8534 382.224 + vertex -192.414 97.4417 386.052 + vertex -192.757 89.7359 382.211 + endloop + endfacet + facet normal -0.0489555 -0.44378 0.894797 + outer loop + vertex -192.414 97.4417 386.052 + vertex -211.398 99.5104 386.039 + vertex -192.757 89.7359 382.211 + endloop + endfacet + facet normal -0.0490558 -0.443939 0.894713 + outer loop + vertex -192.757 89.7359 382.211 + vertex -211.398 99.5104 386.039 + vertex -211.778 91.8084 382.197 + endloop + endfacet + facet normal -0.0483169 -0.437902 0.897723 + outer loop + vertex -192.414 97.4417 386.052 + vertex -211.218 107.262 389.83 + vertex -211.398 99.5104 386.039 + endloop + endfacet + facet normal -0.0527991 -0.437718 0.897561 + outer loop + vertex -211.218 107.262 389.83 + vertex -230.098 109.567 389.844 + vertex -211.398 99.5104 386.039 + endloop + endfacet + facet normal -0.0527363 -0.437621 0.897612 + outer loop + vertex -211.398 99.5104 386.039 + vertex -230.098 109.567 389.844 + vertex -230.293 101.815 386.053 + endloop + endfacet + facet normal -0.0521993 -0.43282 0.899968 + outer loop + vertex -211.218 107.262 389.83 + vertex -230.108 117.738 393.772 + vertex -230.098 109.567 389.844 + endloop + endfacet + facet normal -0.0562433 -0.432729 0.899768 + outer loop + vertex -230.108 117.738 393.772 + vertex -248.907 120.284 393.822 + vertex -230.098 109.567 389.844 + endloop + endfacet + facet normal -0.0560544 -0.432451 0.899913 + outer loop + vertex -230.098 109.567 389.844 + vertex -248.907 120.284 393.822 + vertex -248.891 112.13 389.904 + endloop + endfacet + facet normal -0.0557714 -0.429278 0.901449 + outer loop + vertex -230.108 117.738 393.772 + vertex -248.737 129.182 398.07 + vertex -248.907 120.284 393.822 + endloop + endfacet + facet normal -0.0598581 -0.429113 0.901265 + outer loop + vertex -248.737 129.182 398.07 + vertex -267.477 131.898 398.118 + vertex -248.907 120.284 393.822 + endloop + endfacet + facet normal -0.0596441 -0.428826 0.901416 + outer loop + vertex -248.907 120.284 393.822 + vertex -267.477 131.898 398.118 + vertex -267.662 123.037 393.891 + endloop + endfacet + facet normal -0.0596245 -0.427515 0.90204 + outer loop + vertex -248.737 129.182 398.07 + vertex -266.39 141.381 402.685 + vertex -267.477 131.898 398.118 + endloop + endfacet + facet normal -0.0638054 -0.427013 0.901992 + outer loop + vertex -266.39 141.381 402.685 + vertex -285.142 144.098 402.644 + vertex -267.477 131.898 398.118 + endloop + endfacet + facet normal -0.0641036 -0.427373 0.9018 + outer loop + vertex -267.477 131.898 398.118 + vertex -285.142 144.098 402.644 + vertex -286.398 134.641 398.073 + endloop + endfacet + facet normal -0.0639241 -0.427837 0.901592 + outer loop + vertex -266.39 141.381 402.685 + vertex -282.04 153.387 407.272 + vertex -285.142 144.098 402.644 + endloop + endfacet + facet normal -0.0598043 -0.427732 0.901925 + outer loop + vertex -247.727 138.683 402.642 + vertex -266.39 141.381 402.685 + vertex -248.737 129.182 398.07 + endloop + endfacet + facet normal -0.0559856 -0.428158 0.901968 + outer loop + vertex -229.961 126.64 398.028 + vertex -247.727 138.683 402.642 + vertex -248.737 129.182 398.07 + endloop + endfacet + facet normal -0.0561119 -0.428314 0.901886 + outer loop + vertex -229.041 136.176 402.615 + vertex -247.727 138.683 402.642 + vertex -229.961 126.64 398.028 + endloop + endfacet + facet normal -0.0519785 -0.428735 0.901934 + outer loop + vertex -211.173 124.351 398.023 + vertex -229.041 136.176 402.615 + vertex -229.961 126.64 398.028 + endloop + endfacet + facet normal -0.0521685 -0.430293 0.901181 + outer loop + vertex -211.173 124.351 398.023 + vertex -229.961 126.64 398.028 + vertex -211.241 115.439 393.764 + endloop + endfacet + facet normal -0.0477992 -0.430414 0.901365 + outer loop + vertex -192.333 113.354 393.771 + vertex -211.173 124.351 398.023 + vertex -211.241 115.439 393.764 + endloop + endfacet + facet normal -0.0481559 -0.433655 0.899791 + outer loop + vertex -192.333 113.354 393.771 + vertex -211.241 115.439 393.764 + vertex -192.258 105.196 389.844 + endloop + endfacet + facet normal -0.043368 -0.433715 0.900006 + outer loop + vertex -173.191 103.315 389.856 + vertex -192.333 113.354 393.771 + vertex -192.258 105.196 389.844 + endloop + endfacet + facet normal -0.0438003 -0.438108 0.897855 + outer loop + vertex -173.191 103.315 389.856 + vertex -192.258 105.196 389.844 + vertex -173.32 95.5578 386.064 + endloop + endfacet + facet normal -0.0390048 -0.43826 0.898002 + outer loop + vertex -154.1 93.8564 386.069 + vertex -173.191 103.315 389.856 + vertex -173.32 95.5578 386.064 + endloop + endfacet + facet normal -0.0395454 -0.444374 0.894968 + outer loop + vertex -154.1 93.8564 386.069 + vertex -173.32 95.5578 386.064 + vertex -154.374 86.1486 382.23 + endloop + endfacet + facet normal -0.0391807 -0.438554 0.89785 + outer loop + vertex -153.987 101.601 389.857 + vertex -173.191 103.315 389.856 + vertex -154.1 93.8564 386.069 + endloop + endfacet + facet normal -0.0342358 -0.438692 0.897985 + outer loop + vertex -134.791 92.3475 386.068 + vertex -153.987 101.601 389.857 + vertex -154.1 93.8564 386.069 + endloop + endfacet + facet normal -0.0346904 -0.444507 0.895103 + outer loop + vertex -134.791 92.3475 386.068 + vertex -154.1 93.8564 386.069 + vertex -135.039 84.6365 382.229 + endloop + endfacet + facet normal -0.0342634 -0.438739 0.897961 + outer loop + vertex -134.677 100.091 389.856 + vertex -153.987 101.601 389.857 + vertex -134.791 92.3475 386.068 + endloop + endfacet + facet normal -0.0294323 -0.438864 0.898071 + outer loop + vertex -115.465 91.0469 386.066 + vertex -134.677 100.091 389.856 + vertex -134.791 92.3475 386.068 + endloop + endfacet + facet normal -0.0298464 -0.445013 0.895027 + outer loop + vertex -115.465 91.0469 386.066 + vertex -134.791 92.3475 386.068 + vertex -115.695 83.3389 382.225 + endloop + endfacet + facet normal -0.0294312 -0.438863 0.898072 + outer loop + vertex -115.338 98.7882 389.853 + vertex -134.677 100.091 389.856 + vertex -115.465 91.0469 386.066 + endloop + endfacet + facet normal -0.024344 -0.43899 0.898162 + outer loop + vertex -96.1663 89.9736 386.064 + vertex -115.338 98.7882 389.853 + vertex -115.465 91.0469 386.066 + endloop + endfacet + facet normal -0.0246802 -0.445031 0.895175 + outer loop + vertex -96.1663 89.9736 386.064 + vertex -115.465 91.0469 386.066 + vertex -96.3884 82.2621 382.224 + endloop + endfacet + facet normal -0.0243737 -0.439043 0.898135 + outer loop + vertex -96.0211 97.7159 389.853 + vertex -115.338 98.7882 389.853 + vertex -96.1663 89.9736 386.064 + endloop + endfacet + facet normal -0.0193868 -0.439167 0.898196 + outer loop + vertex -76.8738 89.1215 386.064 + vertex -96.0211 97.7159 389.853 + vertex -96.1663 89.9736 386.064 + endloop + endfacet + facet normal -0.0196517 -0.445162 0.895234 + outer loop + vertex -76.8738 89.1215 386.064 + vertex -96.1663 89.9736 386.064 + vertex -77.1037 81.4076 382.223 + endloop + endfacet + facet normal -0.0193186 -0.439042 0.898259 + outer loop + vertex -76.7175 96.8696 389.854 + vertex -96.0211 97.7159 389.853 + vertex -76.8738 89.1215 386.064 + endloop + endfacet + facet normal -0.0145899 -0.439154 0.898293 + outer loop + vertex -57.552 88.482 386.065 + vertex -76.7175 96.8696 389.854 + vertex -76.8738 89.1215 386.064 + endloop + endfacet + facet normal -0.0147975 -0.44543 0.895194 + outer loop + vertex -57.552 88.482 386.065 + vertex -76.8738 89.1215 386.064 + vertex -57.7919 80.7677 382.223 + endloop + endfacet + facet normal -0.0145946 -0.439163 0.898289 + outer loop + vertex -57.4016 96.2251 389.853 + vertex -76.7175 96.8696 389.854 + vertex -57.552 88.482 386.065 + endloop + endfacet + facet normal -0.0100648 -0.439259 0.898304 + outer loop + vertex -38.1948 88.0385 386.065 + vertex -57.4016 96.2251 389.853 + vertex -57.552 88.482 386.065 + endloop + endfacet + facet normal -0.0102061 -0.445424 0.895262 + outer loop + vertex -38.1948 88.0385 386.065 + vertex -57.552 88.482 386.065 + vertex -38.4371 80.3234 382.224 + endloop + endfacet + facet normal -0.0101271 -0.439378 0.898245 + outer loop + vertex -38.0802 95.7715 389.849 + vertex -57.4016 96.2251 389.853 + vertex -38.1948 88.0385 386.065 + endloop + endfacet + facet normal -0.00591307 -0.439443 0.898251 + outer loop + vertex -18.8433 87.7794 386.066 + vertex -38.0802 95.7715 389.849 + vertex -38.1948 88.0385 386.065 + endloop + endfacet + facet normal -0.00599421 -0.445513 0.895256 + outer loop + vertex -18.8433 87.7794 386.066 + vertex -38.1948 88.0385 386.065 + vertex -19.0616 80.0651 382.225 + endloop + endfacet + facet normal -0.00591748 -0.439452 0.898247 + outer loop + vertex -18.7849 95.5066 389.846 + vertex -38.0802 95.7715 389.849 + vertex -18.8433 87.7794 386.066 + endloop + endfacet + facet normal -0.0018805 -0.439483 0.898249 + outer loop + vertex 0.475082 87.6952 386.065 + vertex -18.7849 95.5066 389.846 + vertex -18.8433 87.7794 386.066 + endloop + endfacet + facet normal -0.00190612 -0.445332 0.895363 + outer loop + vertex 0.475082 87.6952 386.065 + vertex -18.8433 87.7794 386.066 + vertex 0.29989 79.9798 382.227 + endloop + endfacet + facet normal -0.00186721 -0.439457 0.898262 + outer loop + vertex 0.468963 95.4229 389.846 + vertex -18.7849 95.5066 389.846 + vertex 0.475082 87.6952 386.065 + endloop + endfacet + facet normal 0.00203757 -0.439454 0.898263 + outer loop + vertex 19.7602 87.7839 386.065 + vertex 0.468963 95.4229 389.846 + vertex 0.475082 87.6952 386.065 + endloop + endfacet + facet normal 0.00206444 -0.44531 0.895374 + outer loop + vertex 19.7602 87.7839 386.065 + vertex 0.475082 87.6952 386.065 + vertex 19.6347 80.0699 382.228 + endloop + endfacet + facet normal 0.00213853 -0.439249 0.898363 + outer loop + vertex 19.7023 95.5229 389.849 + vertex 0.468963 95.4229 389.846 + vertex 19.7602 87.7839 386.065 + endloop + endfacet + facet normal 0.00606337 -0.439218 0.89836 + outer loop + vertex 39.0449 88.053 386.066 + vertex 19.7023 95.5229 389.849 + vertex 19.7602 87.7839 386.065 + endloop + endfacet + facet normal 0.00615067 -0.445457 0.895282 + outer loop + vertex 39.0449 88.053 386.066 + vertex 19.7602 87.7839 386.065 + vertex 38.9563 80.3367 382.227 + endloop + endfacet + facet normal 0.00612651 -0.439087 0.898424 + outer loop + vertex 38.9587 95.8002 389.853 + vertex 19.7023 95.5229 389.849 + vertex 39.0449 88.053 386.066 + endloop + endfacet + facet normal 0.010371 -0.439033 0.898411 + outer loop + vertex 58.3652 88.5115 386.067 + vertex 38.9587 95.8002 389.853 + vertex 39.0449 88.053 386.066 + endloop + endfacet + facet normal 0.0105158 -0.445128 0.895405 + outer loop + vertex 58.3652 88.5115 386.067 + vertex 39.0449 88.053 386.066 + vertex 58.2882 80.7855 382.227 + endloop + endfacet + facet normal 0.010284 -0.439218 0.898322 + outer loop + vertex 58.2649 96.2576 389.856 + vertex 38.9587 95.8002 389.853 + vertex 58.3652 88.5115 386.067 + endloop + endfacet + facet normal 0.0147858 -0.439146 0.898294 + outer loop + vertex 77.7138 89.1626 386.067 + vertex 58.2649 96.2576 389.856 + vertex 58.3652 88.5115 386.067 + endloop + endfacet + facet normal 0.0149899 -0.44521 0.895301 + outer loop + vertex 77.7138 89.1626 386.067 + vertex 58.3652 88.5115 386.067 + vertex 77.6398 81.4354 382.226 + endloop + endfacet + facet normal 0.0149111 -0.438873 0.898425 + outer loop + vertex 77.5919 96.92 389.858 + vertex 58.2649 96.2576 389.856 + vertex 77.7138 89.1626 386.067 + endloop + endfacet + facet normal 0.0196133 -0.438778 0.898382 + outer loop + vertex 97.0403 90.023 386.065 + vertex 77.5919 96.92 389.858 + vertex 77.7138 89.1626 386.067 + endloop + endfacet + facet normal 0.0198921 -0.445048 0.895286 + outer loop + vertex 97.0403 90.023 386.065 + vertex 77.7138 89.1626 386.067 + vertex 96.977 82.2919 382.223 + endloop + endfacet + facet normal 0.0195224 -0.43898 0.898284 + outer loop + vertex 96.8945 97.7724 389.855 + vertex 77.5919 96.92 389.858 + vertex 97.0403 90.023 386.065 + endloop + endfacet + facet normal 0.0244228 -0.438859 0.898224 + outer loop + vertex 116.31 91.0923 386.064 + vertex 96.8945 97.7724 389.855 + vertex 97.0403 90.023 386.065 + endloop + endfacet + facet normal 0.0247708 -0.445133 0.895122 + outer loop + vertex 116.31 91.0923 386.064 + vertex 97.0403 90.023 386.065 + vertex 116.262 83.3638 382.222 + endloop + endfacet + facet normal 0.0244455 -0.438807 0.898249 + outer loop + vertex 116.134 98.8343 389.851 + vertex 96.8945 97.7724 389.855 + vertex 116.31 91.0923 386.064 + endloop + endfacet + facet normal 0.0295168 -0.438654 0.898171 + outer loop + vertex 135.512 92.3811 386.062 + vertex 116.134 98.8343 389.851 + vertex 116.31 91.0923 386.064 + endloop + endfacet + facet normal 0.0299252 -0.444742 0.895159 + outer loop + vertex 135.512 92.3811 386.062 + vertex 116.31 91.0923 386.064 + vertex 135.48 84.6482 382.221 + endloop + endfacet + facet normal 0.0294714 -0.438761 0.898121 + outer loop + vertex 135.316 100.121 389.849 + vertex 116.134 98.8343 389.851 + vertex 135.512 92.3811 386.062 + endloop + endfacet + facet normal 0.03441 -0.43859 0.898028 + outer loop + vertex 154.673 93.8847 386.062 + vertex 135.316 100.121 389.849 + vertex 135.512 92.3811 386.062 + endloop + endfacet + facet normal 0.0348784 -0.444559 0.89507 + outer loop + vertex 154.673 93.8847 386.062 + vertex 135.512 92.3811 386.062 + vertex 154.651 86.15 382.221 + endloop + endfacet + facet normal 0.0344003 -0.438614 0.898017 + outer loop + vertex 154.463 101.621 389.849 + vertex 135.316 100.121 389.849 + vertex 154.673 93.8847 386.062 + endloop + endfacet + facet normal 0.039232 -0.43843 0.897909 + outer loop + vertex 173.819 95.6081 386.067 + vertex 154.463 101.621 389.849 + vertex 154.673 93.8847 386.062 + endloop + endfacet + facet normal 0.0397591 -0.444277 0.895007 + outer loop + vertex 173.819 95.6081 386.067 + vertex 154.673 93.8847 386.062 + vertex 173.8 87.8662 382.225 + endloop + endfacet + facet normal 0.0392801 -0.43831 0.897965 + outer loop + vertex 173.595 103.352 389.857 + vertex 154.463 101.621 389.849 + vertex 173.819 95.6081 386.067 + endloop + endfacet + facet normal 0.0439035 -0.438118 0.897845 + outer loop + vertex 192.954 97.5478 386.078 + vertex 173.595 103.352 389.857 + vertex 173.819 95.6081 386.067 + endloop + endfacet + facet normal 0.0444985 -0.44397 0.894936 + outer loop + vertex 192.954 97.5478 386.078 + vertex 173.819 95.6081 386.067 + vertex 192.944 89.7975 382.234 + endloop + endfacet + facet normal 0.0439984 -0.437875 0.897959 + outer loop + vertex 192.705 105.3 389.871 + vertex 173.595 103.352 389.857 + vertex 192.954 97.5478 386.078 + endloop + endfacet + facet normal 0.0484896 -0.437667 0.897828 + outer loop + vertex 212.035 99.6767 386.085 + vertex 192.705 105.3 389.871 + vertex 192.954 97.5478 386.078 + endloop + endfacet + facet normal 0.0491896 -0.443931 0.89471 + outer loop + vertex 212.035 99.6767 386.085 + vertex 192.954 97.5478 386.078 + vertex 212.057 91.9232 382.237 + endloop + endfacet + facet normal 0.0485199 -0.437588 0.897866 + outer loop + vertex 211.755 107.435 389.881 + vertex 192.705 105.3 389.871 + vertex 212.035 99.6767 386.085 + endloop + endfacet + facet normal 0.0527748 -0.437369 0.897732 + outer loop + vertex 230.996 101.928 386.067 + vertex 211.755 107.435 389.881 + vertex 212.035 99.6767 386.085 + endloop + endfacet + facet normal 0.0534936 -0.443448 0.894702 + outer loop + vertex 230.996 101.928 386.067 + vertex 212.035 99.6767 386.085 + vertex 231.074 94.1772 382.221 + endloop + endfacet + facet normal 0.0574406 -0.443319 0.894522 + outer loop + vertex 249.953 96.5269 382.173 + vertex 230.996 101.928 386.067 + vertex 231.074 94.1772 382.221 + endloop + endfacet + facet normal 0.0574542 -0.443283 0.894539 + outer loop + vertex 249.818 104.255 386.012 + vertex 230.996 101.928 386.067 + vertex 249.953 96.5269 382.173 + endloop + endfacet + facet normal 0.0617361 -0.443109 0.894339 + outer loop + vertex 268.827 99.0648 382.128 + vertex 249.818 104.255 386.012 + vertex 249.953 96.5269 382.173 + endloop + endfacet + facet normal 0.0627146 -0.450453 0.890595 + outer loop + vertex 268.827 99.0648 382.128 + vertex 249.953 96.5269 382.173 + vertex 269.089 91.3578 378.211 + endloop + endfacet + facet normal 0.0675911 -0.450177 0.890378 + outer loop + vertex 288.333 94.3833 378.28 + vertex 268.827 99.0648 382.128 + vertex 269.089 91.3578 378.211 + endloop + endfacet + facet normal 0.0688452 -0.45806 0.886251 + outer loop + vertex 288.333 94.3833 378.28 + vertex 269.089 91.3578 378.211 + vertex 288.871 86.9522 374.398 + endloop + endfacet + facet normal 0.068685 -0.458564 0.886003 + outer loop + vertex 288.871 86.9522 374.398 + vertex 269.089 91.3578 378.211 + vertex 269.621 83.9218 374.322 + endloop + endfacet + facet normal 0.0676438 -0.450019 0.890453 + outer loop + vertex 288.008 102.029 382.169 + vertex 268.827 99.0648 382.128 + vertex 288.333 94.3833 378.28 + endloop + endfacet + facet normal 0.0734085 -0.44964 0.890188 + outer loop + vertex 308.212 98.1159 378.526 + vertex 288.008 102.029 382.169 + vertex 288.333 94.3833 378.28 + endloop + endfacet + facet normal 0.0746757 -0.456162 0.886758 + outer loop + vertex 308.212 98.1159 378.526 + vertex 288.333 94.3833 378.28 + vertex 308.762 90.6556 374.642 + endloop + endfacet + facet normal 0.0737223 -0.448521 0.890727 + outer loop + vertex 307.822 105.709 382.382 + vertex 288.008 102.029 382.169 + vertex 308.212 98.1159 378.526 + endloop + endfacet + facet normal 0.0794547 -0.448087 0.890452 + outer loop + vertex 328.695 102.571 378.94 + vertex 307.822 105.709 382.382 + vertex 308.212 98.1159 378.526 + endloop + endfacet + facet normal 0.0805874 -0.453052 0.887834 + outer loop + vertex 328.695 102.571 378.94 + vertex 308.212 98.1159 378.526 + vertex 329.31 95.0913 375.068 + endloop + endfacet + facet normal 0.0864956 -0.452439 0.887591 + outer loop + vertex 328.695 102.571 378.94 + vertex 329.31 95.0913 375.068 + vertex 342.366 99.5914 376.089 + endloop + endfacet + facet normal 0.0876188 -0.448898 0.889277 + outer loop + vertex 343.958 103.47 377.891 + vertex 328.695 102.571 378.94 + vertex 342.366 99.5914 376.089 + endloop + endfacet + facet normal 0.101396 -0.452921 0.885766 + outer loop + vertex 353.436 102.322 376.219 + vertex 343.958 103.47 377.891 + vertex 342.366 99.5914 376.089 + endloop + endfacet + facet normal 0.10037 -0.448865 0.887945 + outer loop + vertex 353.436 102.322 376.219 + vertex 342.366 99.5914 376.089 + vertex 353.855 98.6331 374.306 + endloop + endfacet + facet normal 0.103095 -0.444678 0.889737 + outer loop + vertex 353.061 106.092 378.146 + vertex 343.958 103.47 377.891 + vertex 353.436 102.322 376.219 + endloop + endfacet + facet normal 0.119084 -0.442597 0.888778 + outer loop + vertex 362.805 105.031 376.312 + vertex 353.061 106.092 378.146 + vertex 353.436 102.322 376.219 + endloop + endfacet + facet normal 0.118916 -0.442026 0.889085 + outer loop + vertex 362.805 105.031 376.312 + vertex 353.436 102.322 376.219 + vertex 363.352 101.351 374.41 + endloop + endfacet + facet normal 0.119704 -0.439458 0.890252 + outer loop + vertex 362.311 108.803 378.24 + vertex 353.061 106.092 378.146 + vertex 362.805 105.031 376.312 + endloop + endfacet + facet normal 0.138971 -0.436299 0.889005 + outer loop + vertex 371.03 107.722 376.347 + vertex 362.311 108.803 378.24 + vertex 362.805 105.031 376.312 + endloop + endfacet + facet normal 0.138629 -0.435261 0.889567 + outer loop + vertex 371.03 107.722 376.347 + vertex 362.805 105.031 376.312 + vertex 371.863 104.139 374.464 + endloop + endfacet + facet normal 0.140351 -0.430082 0.891813 + outer loop + vertex 370.388 111.455 378.248 + vertex 362.311 108.803 378.24 + vertex 371.03 107.722 376.347 + endloop + endfacet + facet normal 0.161716 -0.425648 0.890321 + outer loop + vertex 377.77 110.341 376.375 + vertex 370.388 111.455 378.248 + vertex 371.03 107.722 376.347 + endloop + endfacet + facet normal 0.160284 -0.421984 0.892322 + outer loop + vertex 377.77 110.341 376.375 + vertex 371.03 107.722 376.347 + vertex 378.7 106.938 374.599 + endloop + endfacet + facet normal 0.163825 -0.417501 0.893787 + outer loop + vertex 377.06 114.015 378.221 + vertex 370.388 111.455 378.248 + vertex 377.77 110.341 376.375 + endloop + endfacet + facet normal 0.18381 -0.412785 0.892089 + outer loop + vertex 383.025 112.745 376.405 + vertex 377.06 114.015 378.221 + vertex 377.77 110.341 376.375 + endloop + endfacet + facet normal 0.181062 -0.40682 0.895385 + outer loop + vertex 383.025 112.745 376.405 + vertex 377.77 110.341 376.375 + vertex 383.735 109.459 374.768 + endloop + endfacet + facet normal 0.1863 -0.405272 0.895012 + outer loop + vertex 382.309 116.449 378.231 + vertex 377.06 114.015 378.221 + vertex 383.025 112.745 376.405 + endloop + endfacet + facet normal 0.205526 -0.400536 0.892934 + outer loop + vertex 386.906 114.856 376.458 + vertex 382.309 116.449 378.231 + vertex 383.025 112.745 376.405 + endloop + endfacet + facet normal 0.201616 -0.393445 0.896968 + outer loop + vertex 386.906 114.856 376.458 + vertex 383.025 112.745 376.405 + vertex 387.326 111.395 374.846 + endloop + endfacet + facet normal 0.189331 -0.411797 0.89139 + outer loop + vertex 382.309 116.449 378.231 + vertex 376.363 117.837 380.135 + vertex 377.06 114.015 378.221 + endloop + endfacet + facet normal 0.167008 -0.416913 0.893472 + outer loop + vertex 376.363 117.837 380.135 + vertex 369.757 115.282 380.178 + vertex 377.06 114.015 378.221 + endloop + endfacet + facet normal 0.168558 -0.420957 0.891282 + outer loop + vertex 376.363 117.837 380.135 + vertex 369.12 119.135 382.118 + vertex 369.757 115.282 380.178 + endloop + endfacet + facet normal 0.144761 -0.425827 0.893149 + outer loop + vertex 369.12 119.135 382.118 + vertex 361.296 116.487 382.123 + vertex 369.757 115.282 380.178 + endloop + endfacet + facet normal 0.143556 -0.430771 0.89097 + outer loop + vertex 369.757 115.282 380.178 + vertex 361.296 116.487 382.123 + vertex 361.797 112.634 380.18 + endloop + endfacet + facet normal 0.142224 -0.426766 0.893109 + outer loop + vertex 369.757 115.282 380.178 + vertex 361.797 112.634 380.18 + vertex 370.388 111.455 378.248 + endloop + endfacet + facet normal 0.121759 -0.434363 0.892471 + outer loop + vertex 361.296 116.487 382.123 + vertex 352.281 113.746 382.019 + vertex 361.797 112.634 380.18 + endloop + endfacet + facet normal 0.121102 -0.437554 0.891 + outer loop + vertex 361.797 112.634 380.18 + vertex 352.281 113.746 382.019 + vertex 352.671 109.911 380.083 + endloop + endfacet + facet normal 0.120458 -0.435434 0.892125 + outer loop + vertex 361.797 112.634 380.18 + vertex 352.671 109.911 380.083 + vertex 362.311 108.803 378.24 + endloop + endfacet + facet normal 0.103733 -0.439856 0.892057 + outer loop + vertex 352.281 113.746 382.019 + vertex 343.336 111.085 381.747 + vertex 352.671 109.911 380.083 + endloop + endfacet + facet normal 0.102456 -0.445938 0.889181 + outer loop + vertex 352.671 109.911 380.083 + vertex 343.336 111.085 381.747 + vertex 341.744 107.134 379.949 + endloop + endfacet + facet normal 0.101363 -0.441744 0.891396 + outer loop + vertex 352.671 109.911 380.083 + vertex 341.744 107.134 379.949 + vertex 353.061 106.092 378.146 + endloop + endfacet + facet normal 0.0878178 -0.441711 0.892849 + outer loop + vertex 343.336 111.085 381.747 + vertex 328.215 110.168 382.781 + vertex 341.744 107.134 379.949 + endloop + endfacet + facet normal 0.0867307 -0.445091 0.891276 + outer loop + vertex 328.215 110.168 382.781 + vertex 328.695 102.571 378.94 + vertex 341.744 107.134 379.949 + endloop + endfacet + facet normal 0.0878289 -0.442126 0.892643 + outer loop + vertex 343.336 111.085 381.747 + vertex 341.139 114.782 383.795 + vertex 328.215 110.168 382.781 + endloop + endfacet + facet normal 0.0866709 -0.439222 0.894188 + outer loop + vertex 327.751 117.85 386.6 + vertex 328.215 110.168 382.781 + vertex 341.139 114.782 383.795 + endloop + endfacet + facet normal 0.0874109 -0.436946 0.895231 + outer loop + vertex 342.72 118.785 385.594 + vertex 327.751 117.85 386.6 + vertex 341.139 114.782 383.795 + endloop + endfacet + facet normal 0.102906 -0.441351 0.891414 + outer loop + vertex 351.871 117.601 383.951 + vertex 342.72 118.785 385.594 + vertex 341.139 114.782 383.795 + endloop + endfacet + facet normal 0.101754 -0.437088 0.893644 + outer loop + vertex 351.871 117.601 383.951 + vertex 341.139 114.782 383.795 + vertex 352.281 113.746 382.019 + endloop + endfacet + facet normal 0.104217 -0.435201 0.894281 + outer loop + vertex 351.506 121.503 385.893 + vertex 342.72 118.785 385.594 + vertex 351.871 117.601 383.951 + endloop + endfacet + facet normal 0.122539 -0.432891 0.893079 + outer loop + vertex 360.782 120.356 384.064 + vertex 351.506 121.503 385.893 + vertex 351.871 117.601 383.951 + endloop + endfacet + facet normal 0.122254 -0.431989 0.893554 + outer loop + vertex 360.782 120.356 384.064 + vertex 351.871 117.601 383.951 + vertex 361.296 116.487 382.123 + endloop + endfacet + facet normal 0.122996 -0.430746 0.894052 + outer loop + vertex 360.321 124.273 386.015 + vertex 351.506 121.503 385.893 + vertex 360.782 120.356 384.064 + endloop + endfacet + facet normal 0.146351 -0.427115 0.892274 + outer loop + vertex 368.531 122.999 384.058 + vertex 360.321 124.273 386.015 + vertex 360.782 120.356 384.064 + endloop + endfacet + facet normal 0.146014 -0.426124 0.892804 + outer loop + vertex 368.531 122.999 384.058 + vertex 360.782 120.356 384.064 + vertex 369.12 119.135 382.118 + endloop + endfacet + facet normal 0.171147 -0.42122 0.890664 + outer loop + vertex 375.638 121.684 382.071 + vertex 368.531 122.999 384.058 + vertex 369.12 119.135 382.118 + endloop + endfacet + facet normal 0.172353 -0.417206 0.892319 + outer loop + vertex 374.911 125.516 384.003 + vertex 368.531 122.999 384.058 + vertex 375.638 121.684 382.071 + endloop + endfacet + facet normal 0.196699 -0.411407 0.889974 + outer loop + vertex 380.578 124.16 382.124 + vertex 374.911 125.516 384.003 + vertex 375.638 121.684 382.071 + endloop + endfacet + facet normal 0.195083 -0.408222 0.891794 + outer loop + vertex 380.578 124.16 382.124 + vertex 375.638 121.684 382.071 + vertex 381.478 120.329 380.173 + endloop + endfacet + facet normal 0.216097 -0.40221 0.889679 + outer loop + vertex 384.957 122.928 380.503 + vertex 380.578 124.16 382.124 + vertex 381.478 120.329 380.173 + endloop + endfacet + facet normal 0.193889 -0.411576 0.890512 + outer loop + vertex 381.478 120.329 380.173 + vertex 375.638 121.684 382.071 + vertex 376.363 117.837 380.135 + endloop + endfacet + facet normal 0.19736 -0.409598 0.890662 + outer loop + vertex 379.836 127.924 384.019 + vertex 374.911 125.516 384.003 + vertex 380.578 124.16 382.124 + endloop + endfacet + facet normal 0.218056 -0.404303 0.888251 + outer loop + vertex 383.773 126.58 382.441 + vertex 379.836 127.924 384.019 + vertex 380.578 124.16 382.124 + endloop + endfacet + facet normal 0.199162 -0.413269 0.888562 + outer loop + vertex 379.836 127.924 384.019 + vertex 374.322 129.395 385.939 + vertex 374.911 125.516 384.003 + endloop + endfacet + facet normal 0.174025 -0.418498 0.891389 + outer loop + vertex 374.322 129.395 385.939 + vertex 367.983 126.904 386.007 + vertex 374.911 125.516 384.003 + endloop + endfacet + facet normal 0.174524 -0.419787 0.890685 + outer loop + vertex 374.322 129.395 385.939 + vertex 367.496 130.893 387.983 + vertex 367.983 126.904 386.007 + endloop + endfacet + facet normal 0.1478 -0.424371 0.893344 + outer loop + vertex 367.496 130.893 387.983 + vertex 359.919 128.266 387.988 + vertex 367.983 126.904 386.007 + endloop + endfacet + facet normal 0.147277 -0.426278 0.892522 + outer loop + vertex 367.983 126.904 386.007 + vertex 359.919 128.266 387.988 + vertex 360.321 124.273 386.015 + endloop + endfacet + facet normal 0.123034 -0.429717 0.894542 + outer loop + vertex 359.919 128.266 387.988 + vertex 351.165 125.476 387.852 + vertex 360.321 124.273 386.015 + endloop + endfacet + facet normal 0.122963 -0.429498 0.894657 + outer loop + vertex 359.919 128.266 387.988 + vertex 350.867 129.512 389.831 + vertex 351.165 125.476 387.852 + endloop + endfacet + facet normal 0.104185 -0.431566 0.896045 + outer loop + vertex 350.867 129.512 389.831 + vertex 342.174 126.711 389.492 + vertex 351.165 125.476 387.852 + endloop + endfacet + facet normal 0.102865 -0.437535 0.893298 + outer loop + vertex 351.165 125.476 387.852 + vertex 342.174 126.711 389.492 + vertex 340.569 122.584 387.656 + endloop + endfacet + facet normal 0.101567 -0.43294 0.895682 + outer loop + vertex 351.165 125.476 387.852 + vertex 340.569 122.584 387.656 + vertex 351.506 121.503 385.893 + endloop + endfacet + facet normal 0.0866563 -0.43298 0.897228 + outer loop + vertex 342.174 126.711 389.492 + vertex 327.239 125.76 390.476 + vertex 340.569 122.584 387.656 + endloop + endfacet + facet normal 0.0863468 -0.433908 0.89681 + outer loop + vertex 327.239 125.76 390.476 + vertex 327.751 117.85 386.6 + vertex 340.569 122.584 387.656 + endloop + endfacet + facet normal 0.078505 -0.434603 0.897194 + outer loop + vertex 327.239 125.76 390.476 + vertex 307.017 121.117 389.996 + vertex 327.751 117.85 386.6 + endloop + endfacet + facet normal 0.0782578 -0.43566 0.896703 + outer loop + vertex 327.751 117.85 386.6 + vertex 307.017 121.117 389.996 + vertex 307.484 113.341 386.177 + endloop + endfacet + facet normal 0.0718963 -0.43618 0.896983 + outer loop + vertex 307.017 121.117 389.996 + vertex 287.351 117.388 389.759 + vertex 307.484 113.341 386.177 + endloop + endfacet + facet normal 0.0718025 -0.436511 0.896829 + outer loop + vertex 307.484 113.341 386.177 + vertex 287.351 117.388 389.759 + vertex 287.758 109.671 385.97 + endloop + endfacet + facet normal 0.0727595 -0.441513 0.8943 + outer loop + vertex 307.484 113.341 386.177 + vertex 287.758 109.671 385.97 + vertex 307.822 105.709 382.382 + endloop + endfacet + facet normal 0.0789545 -0.441082 0.893987 + outer loop + vertex 328.215 110.168 382.781 + vertex 307.484 113.341 386.177 + vertex 307.822 105.709 382.382 + endloop + endfacet + facet normal 0.0659053 -0.436941 0.897072 + outer loop + vertex 287.351 117.388 389.759 + vertex 268.266 114.456 389.733 + vertex 287.758 109.671 385.97 + endloop + endfacet + facet normal 0.0658223 -0.437189 0.896958 + outer loop + vertex 287.758 109.671 385.97 + vertex 268.266 114.456 389.733 + vertex 268.633 106.751 385.951 + endloop + endfacet + facet normal 0.0666584 -0.442648 0.894215 + outer loop + vertex 287.758 109.671 385.97 + vertex 268.633 106.751 385.951 + vertex 288.008 102.029 382.169 + endloop + endfacet + facet normal 0.0607356 -0.437527 0.897152 + outer loop + vertex 268.266 114.456 389.733 + vertex 249.48 111.995 389.805 + vertex 268.633 106.751 385.951 + endloop + endfacet + facet normal 0.0608949 -0.437093 0.897353 + outer loop + vertex 268.633 106.751 385.951 + vertex 249.48 111.995 389.805 + vertex 249.818 104.255 386.012 + endloop + endfacet + facet normal 0.0567325 -0.437347 0.897502 + outer loop + vertex 249.48 111.995 389.805 + vertex 230.689 109.679 389.864 + vertex 249.818 104.255 386.012 + endloop + endfacet + facet normal 0.0561554 -0.432605 0.899833 + outer loop + vertex 249.48 111.995 389.805 + vertex 230.137 117.787 393.796 + vertex 230.689 109.679 389.864 + endloop + endfacet + facet normal 0.0521502 -0.432921 0.899922 + outer loop + vertex 230.137 117.787 393.796 + vertex 211.22 115.543 393.813 + vertex 230.689 109.679 389.864 + endloop + endfacet + facet normal 0.0521459 -0.432932 0.899917 + outer loop + vertex 230.689 109.679 389.864 + vertex 211.22 115.543 393.813 + vertex 211.755 107.435 389.881 + endloop + endfacet + facet normal 0.0480193 -0.433243 0.899997 + outer loop + vertex 211.22 115.543 393.813 + vertex 192.194 113.404 393.799 + vertex 211.755 107.435 389.881 + endloop + endfacet + facet normal 0.0476746 -0.430185 0.901481 + outer loop + vertex 211.22 115.543 393.813 + vertex 191.892 122.296 398.058 + vertex 192.194 113.404 393.799 + endloop + endfacet + facet normal 0.0432568 -0.430394 0.901604 + outer loop + vertex 191.892 122.296 398.058 + vertex 172.854 120.349 398.042 + vertex 192.194 113.404 393.799 + endloop + endfacet + facet normal 0.0432091 -0.430498 0.901557 + outer loop + vertex 192.194 113.404 393.799 + vertex 172.854 120.349 398.042 + vertex 173.113 111.455 393.782 + endloop + endfacet + facet normal 0.0435211 -0.433539 0.900083 + outer loop + vertex 192.194 113.404 393.799 + vertex 173.113 111.455 393.782 + vertex 192.705 105.3 389.871 + endloop + endfacet + facet normal 0.0385475 -0.430691 0.901676 + outer loop + vertex 172.854 120.349 398.042 + vertex 153.79 118.632 398.037 + vertex 173.113 111.455 393.782 + endloop + endfacet + facet normal 0.0385154 -0.430759 0.901645 + outer loop + vertex 173.113 111.455 393.782 + vertex 153.79 118.632 398.037 + vertex 154 109.73 393.775 + endloop + endfacet + facet normal 0.0387892 -0.433788 0.90018 + outer loop + vertex 173.113 111.455 393.782 + vertex 154 109.73 393.775 + vertex 173.595 103.352 389.857 + endloop + endfacet + facet normal 0.0337946 -0.430923 0.901756 + outer loop + vertex 153.79 118.632 398.037 + vertex 134.676 117.132 398.036 + vertex 154 109.73 393.775 + endloop + endfacet + facet normal 0.0337893 -0.430934 0.901751 + outer loop + vertex 154 109.73 393.775 + vertex 134.676 117.132 398.036 + vertex 134.862 108.225 393.772 + endloop + endfacet + facet normal 0.034025 -0.433929 0.900304 + outer loop + vertex 154 109.73 393.775 + vertex 134.862 108.225 393.772 + vertex 154.463 101.621 389.849 + endloop + endfacet + facet normal 0.0289249 -0.431083 0.901849 + outer loop + vertex 134.676 117.132 398.036 + vertex 115.513 115.843 398.035 + vertex 134.862 108.225 393.772 + endloop + endfacet + facet normal 0.0288872 -0.431159 0.901813 + outer loop + vertex 134.862 108.225 393.772 + vertex 115.513 115.843 398.035 + vertex 115.687 106.943 393.774 + endloop + endfacet + facet normal 0.0290906 -0.434205 0.900344 + outer loop + vertex 134.862 108.225 393.772 + vertex 115.687 106.943 393.774 + vertex 135.316 100.121 389.849 + endloop + endfacet + facet normal 0.0240243 -0.431292 0.901892 + outer loop + vertex 115.513 115.843 398.035 + vertex 96.2766 114.77 398.034 + vertex 115.687 106.943 393.774 + endloop + endfacet + facet normal 0.0240245 -0.431292 0.901893 + outer loop + vertex 115.687 106.943 393.774 + vertex 96.2766 114.77 398.034 + vertex 96.4642 105.88 393.778 + endloop + endfacet + facet normal 0.0241927 -0.434336 0.900426 + outer loop + vertex 115.687 106.943 393.774 + vertex 96.4642 105.88 393.778 + vertex 116.134 98.8343 389.851 + endloop + endfacet + facet normal 0.0191812 -0.43142 0.901947 + outer loop + vertex 96.2766 114.77 398.034 + vertex 76.9916 113.918 398.036 + vertex 96.4642 105.88 393.778 + endloop + endfacet + facet normal 0.0191529 -0.431475 0.901922 + outer loop + vertex 96.4642 105.88 393.778 + vertex 76.9916 113.918 398.036 + vertex 77.1908 105.034 393.782 + endloop + endfacet + facet normal 0.0192888 -0.434581 0.900426 + outer loop + vertex 96.4642 105.88 393.778 + vertex 77.1908 105.034 393.782 + vertex 96.8945 97.7724 389.855 + endloop + endfacet + facet normal 0.0145372 -0.431593 0.901951 + outer loop + vertex 76.9916 113.918 398.036 + vertex 57.7222 113.274 398.039 + vertex 77.1908 105.034 393.782 + endloop + endfacet + facet normal 0.0144705 -0.431719 0.901892 + outer loop + vertex 77.1908 105.034 393.782 + vertex 57.7222 113.274 398.039 + vertex 57.9037 104.394 393.785 + endloop + endfacet + facet normal 0.0145703 -0.434729 0.900444 + outer loop + vertex 77.1908 105.034 393.782 + vertex 57.9037 104.394 393.785 + vertex 77.5919 96.92 389.858 + endloop + endfacet + facet normal 0.0100869 -0.431816 0.901906 + outer loop + vertex 57.7222 113.274 398.039 + vertex 38.5381 112.827 398.039 + vertex 57.9037 104.394 393.785 + endloop + endfacet + facet normal 0.0101628 -0.431675 0.901972 + outer loop + vertex 57.9037 104.394 393.785 + vertex 38.5381 112.827 398.039 + vertex 38.6376 103.927 393.779 + endloop + endfacet + facet normal 0.0102323 -0.434526 0.900601 + outer loop + vertex 57.9037 104.394 393.785 + vertex 38.6376 103.927 393.779 + vertex 58.2649 96.2576 389.856 + endloop + endfacet + facet normal 0.00596748 -0.431728 0.901984 + outer loop + vertex 38.5381 112.827 398.039 + vertex 19.3912 112.551 398.034 + vertex 38.6376 103.927 393.779 + endloop + endfacet + facet normal 0.00598485 -0.431696 0.901999 + outer loop + vertex 38.6376 103.927 393.779 + vertex 19.3912 112.551 398.034 + vertex 19.4131 103.645 393.772 + endloop + endfacet + facet normal 0.00603067 -0.434791 0.900511 + outer loop + vertex 38.6376 103.927 393.779 + vertex 19.4131 103.645 393.772 + vertex 38.9587 95.8002 389.853 + endloop + endfacet + facet normal 0.00198645 -0.431711 0.90201 + outer loop + vertex 19.3912 112.551 398.034 + vertex 0.152117 112.463 398.034 + vertex 19.4131 103.645 393.772 + endloop + endfacet + facet normal 0.00200004 -0.431687 0.902021 + outer loop + vertex 19.4131 103.645 393.772 + vertex 0.152117 112.463 398.034 + vertex 0.194862 103.548 393.767 + endloop + endfacet + facet normal 0.00201647 -0.434849 0.900501 + outer loop + vertex 19.4131 103.645 393.772 + vertex 0.194862 103.548 393.767 + vertex 19.7023 95.5229 389.849 + endloop + endfacet + facet normal -0.00198251 -0.431703 0.902014 + outer loop + vertex 0.152117 112.463 398.034 + vertex -19.2201 112.557 398.037 + vertex 0.194862 103.548 393.767 + endloop + endfacet + facet normal -0.00188598 -0.431533 0.902095 + outer loop + vertex 0.194862 103.548 393.767 + vertex -19.2201 112.557 398.037 + vertex -19.0463 103.629 393.766 + endloop + endfacet + facet normal -0.00189945 -0.434766 0.900541 + outer loop + vertex 0.194862 103.548 393.767 + vertex -19.0463 103.629 393.766 + vertex 0.468963 95.4229 389.846 + endloop + endfacet + facet normal -0.00596121 -0.431591 0.90205 + outer loop + vertex -19.2201 112.557 398.037 + vertex -38.6323 112.812 398.03 + vertex -19.0463 103.629 393.766 + endloop + endfacet + facet normal -0.0058807 -0.43145 0.902117 + outer loop + vertex -19.0463 103.629 393.766 + vertex -38.6323 112.812 398.03 + vertex -38.3123 103.897 393.769 + endloop + endfacet + facet normal -0.00592711 -0.434763 0.900525 + outer loop + vertex -19.0463 103.629 393.766 + vertex -38.3123 103.897 393.769 + vertex -18.7849 95.5066 389.846 + endloop + endfacet + facet normal -0.0101118 -0.431559 0.902028 + outer loop + vertex -38.6323 112.812 398.03 + vertex -57.9704 113.26 398.028 + vertex -38.3123 103.897 393.769 + endloop + endfacet + facet normal -0.00993787 -0.43126 0.902173 + outer loop + vertex -38.3123 103.897 393.769 + vertex -57.9704 113.26 398.028 + vertex -57.5812 104.346 393.771 + endloop + endfacet + facet normal -0.0100183 -0.434701 0.900519 + outer loop + vertex -38.3123 103.897 393.769 + vertex -57.5812 104.346 393.771 + vertex -38.0802 95.7715 389.849 + endloop + endfacet + facet normal -0.0145432 -0.4314 0.902044 + outer loop + vertex -57.9704 113.26 398.028 + vertex -77.1992 113.922 398.035 + vertex -57.5812 104.346 393.771 + endloop + endfacet + facet normal -0.0144423 -0.43123 0.902127 + outer loop + vertex -57.5812 104.346 393.771 + vertex -77.1992 113.922 398.035 + vertex -76.8451 105.006 393.778 + endloop + endfacet + facet normal -0.0145635 -0.434755 0.900431 + outer loop + vertex -57.5812 104.346 393.771 + vertex -76.8451 105.006 393.778 + vertex -57.4016 96.2251 389.853 + endloop + endfacet + facet normal -0.019264 -0.431351 0.901979 + outer loop + vertex -77.1992 113.922 398.035 + vertex -96.3505 114.79 398.04 + vertex -76.8451 105.006 393.778 + endloop + endfacet + facet normal -0.0191725 -0.4312 0.902052 + outer loop + vertex -76.8451 105.006 393.778 + vertex -96.3505 114.79 398.04 + vertex -96.1115 105.872 393.783 + endloop + endfacet + facet normal -0.0193238 -0.434557 0.900437 + outer loop + vertex -76.8451 105.006 393.778 + vertex -96.1115 105.872 393.783 + vertex -76.7175 96.8696 389.854 + endloop + endfacet + facet normal -0.0240308 -0.431261 0.901907 + outer loop + vertex -96.3505 114.79 398.04 + vertex -115.539 115.851 398.037 + vertex -96.1115 105.872 393.783 + endloop + endfacet + facet normal -0.0239323 -0.431103 0.901985 + outer loop + vertex -96.1115 105.872 393.783 + vertex -115.539 115.851 398.037 + vertex -115.416 106.935 393.779 + endloop + endfacet + facet normal -0.0241009 -0.434168 0.90051 + outer loop + vertex -96.1115 105.872 393.783 + vertex -115.416 106.935 393.779 + vertex -96.0211 97.7159 389.853 + endloop + endfacet + facet normal -0.0290719 -0.431102 0.901835 + outer loop + vertex -115.539 115.851 398.037 + vertex -134.809 117.157 398.04 + vertex -115.416 106.935 393.779 + endloop + endfacet + facet normal -0.0289368 -0.43089 0.901941 + outer loop + vertex -115.416 106.935 393.779 + vertex -134.809 117.157 398.04 + vertex -134.766 108.239 393.781 + endloop + endfacet + facet normal -0.0291569 -0.434153 0.900367 + outer loop + vertex -115.416 106.935 393.779 + vertex -134.766 108.239 393.781 + vertex -115.338 98.7882 389.853 + endloop + endfacet + facet normal -0.0338564 -0.430842 0.901792 + outer loop + vertex -134.809 117.157 398.04 + vertex -154.131 118.68 398.042 + vertex -134.766 108.239 393.781 + endloop + endfacet + facet normal -0.0337857 -0.430734 0.901847 + outer loop + vertex -134.766 108.239 393.781 + vertex -154.131 118.68 398.042 + vertex -154.1 109.76 393.783 + endloop + endfacet + facet normal -0.0340465 -0.434046 0.900247 + outer loop + vertex -134.766 108.239 393.781 + vertex -154.1 109.76 393.783 + vertex -134.677 100.091 389.856 + endloop + endfacet + facet normal -0.0384985 -0.430674 0.901686 + outer loop + vertex -154.131 118.68 398.042 + vertex -173.365 120.395 398.04 + vertex -154.1 109.76 393.783 + endloop + endfacet + facet normal -0.0384464 -0.430595 0.901726 + outer loop + vertex -154.1 109.76 393.783 + vertex -173.365 120.395 398.04 + vertex -173.302 111.473 393.782 + endloop + endfacet + facet normal -0.0387265 -0.433736 0.900207 + outer loop + vertex -154.1 109.76 393.783 + vertex -173.302 111.473 393.782 + vertex -153.987 101.601 389.857 + endloop + endfacet + facet normal -0.0431752 -0.430539 0.901539 + outer loop + vertex -173.365 120.395 398.04 + vertex -192.353 122.286 398.033 + vertex -173.302 111.473 393.782 + endloop + endfacet + facet normal -0.043057 -0.430366 0.901627 + outer loop + vertex -173.302 111.473 393.782 + vertex -192.353 122.286 398.033 + vertex -192.333 113.354 393.771 + endloop + endfacet + facet normal -0.043044 -0.429219 0.902174 + outer loop + vertex -173.365 120.395 398.04 + vertex -191.728 131.847 402.612 + vertex -192.353 122.286 398.033 + endloop + endfacet + facet normal -0.0474113 -0.428901 0.902106 + outer loop + vertex -191.728 131.847 402.612 + vertex -210.42 133.896 402.604 + vertex -192.353 122.286 398.033 + endloop + endfacet + facet normal -0.04758 -0.429119 0.901994 + outer loop + vertex -192.353 122.286 398.033 + vertex -210.42 133.896 402.604 + vertex -211.173 124.351 398.023 + endloop + endfacet + facet normal -0.0474792 -0.429522 0.901807 + outer loop + vertex -191.728 131.847 402.612 + vertex -208.168 143.211 407.159 + vertex -210.42 133.896 402.604 + endloop + endfacet + facet normal -0.0427996 -0.428894 0.902341 + outer loop + vertex -172.667 129.969 402.623 + vertex -191.728 131.847 402.612 + vertex -173.365 120.395 398.04 + endloop + endfacet + facet normal -0.0428731 -0.429642 0.901981 + outer loop + vertex -172.667 129.969 402.623 + vertex -189.635 141.247 407.189 + vertex -191.728 131.847 402.612 + endloop + endfacet + facet normal -0.0383703 -0.429234 0.902378 + outer loop + vertex -154.131 118.68 398.042 + vertex -172.667 129.969 402.623 + vertex -173.365 120.395 398.04 + endloop + endfacet + facet normal -0.0383546 -0.429213 0.902389 + outer loop + vertex -153.445 128.245 402.621 + vertex -172.667 129.969 402.623 + vertex -154.131 118.68 398.042 + endloop + endfacet + facet normal -0.0384385 -0.430148 0.90194 + outer loop + vertex -153.445 128.245 402.621 + vertex -170.239 139.342 407.197 + vertex -172.667 129.969 402.623 + endloop + endfacet + facet normal -0.0337547 -0.429553 0.90241 + outer loop + vertex -134.809 117.157 398.04 + vertex -153.445 128.245 402.621 + vertex -154.131 118.68 398.042 + endloop + endfacet + facet normal -0.0337406 -0.429534 0.90242 + outer loop + vertex -134.321 126.741 402.62 + vertex -153.445 128.245 402.621 + vertex -134.809 117.157 398.04 + endloop + endfacet + facet normal -0.0338152 -0.430481 0.901966 + outer loop + vertex -134.321 126.741 402.62 + vertex -151.541 137.651 407.181 + vertex -153.445 128.245 402.621 + endloop + endfacet + facet normal -0.0289833 -0.429796 0.902461 + outer loop + vertex -115.539 115.851 398.037 + vertex -134.321 126.741 402.62 + vertex -134.809 117.157 398.04 + endloop + endfacet + facet normal -0.0288963 -0.429672 0.902523 + outer loop + vertex -115.248 125.46 402.621 + vertex -134.321 126.741 402.62 + vertex -115.539 115.851 398.037 + endloop + endfacet + facet normal -0.0289609 -0.430633 0.902062 + outer loop + vertex -115.248 125.46 402.621 + vertex -132.691 136.222 407.198 + vertex -134.321 126.741 402.62 + endloop + endfacet + facet normal -0.0239529 -0.42985 0.902583 + outer loop + vertex -96.3505 114.79 398.04 + vertex -115.248 125.46 402.621 + vertex -115.539 115.851 398.037 + endloop + endfacet + facet normal -0.0240982 -0.430062 0.902478 + outer loop + vertex -96.3083 124.402 402.622 + vertex -115.248 125.46 402.621 + vertex -96.3505 114.79 398.04 + endloop + endfacet + facet normal -0.0241543 -0.431066 0.901997 + outer loop + vertex -96.3083 124.402 402.622 + vertex -113.713 134.956 407.2 + vertex -115.248 125.46 402.621 + endloop + endfacet + facet normal -0.0192083 -0.430125 0.902565 + outer loop + vertex -77.1992 113.922 398.035 + vertex -96.3083 124.402 402.622 + vertex -96.3505 114.79 398.04 + endloop + endfacet + facet normal -0.0190858 -0.429941 0.902655 + outer loop + vertex -77.2047 123.552 402.621 + vertex -96.3083 124.402 402.622 + vertex -77.1992 113.922 398.035 + endloop + endfacet + facet normal -0.0191263 -0.430851 0.902221 + outer loop + vertex -77.2047 123.552 402.621 + vertex -95.1637 133.955 407.209 + vertex -96.3083 124.402 402.622 + endloop + endfacet + facet normal -0.0144938 -0.429972 0.902726 + outer loop + vertex -57.9704 113.26 398.028 + vertex -77.2047 123.552 402.621 + vertex -77.1992 113.922 398.035 + endloop + endfacet + facet normal -0.0144841 -0.429957 0.902733 + outer loop + vertex -57.8346 122.896 402.62 + vertex -77.2047 123.552 402.621 + vertex -57.9704 113.26 398.028 + endloop + endfacet + facet normal -0.0145157 -0.43089 0.902288 + outer loop + vertex -57.8346 122.896 402.62 + vertex -75.6646 133.122 407.216 + vertex -77.2047 123.552 402.621 + endloop + endfacet + facet normal -0.0100765 -0.430031 0.902758 + outer loop + vertex -38.6323 112.812 398.03 + vertex -57.8346 122.896 402.62 + vertex -57.9704 113.26 398.028 + endloop + endfacet + facet normal -0.01005 -0.42999 0.902778 + outer loop + vertex -38.2006 122.533 402.665 + vertex -57.8346 122.896 402.62 + vertex -38.6323 112.812 398.03 + endloop + endfacet + facet normal -0.0100652 -0.430865 0.90236 + outer loop + vertex -38.2006 122.533 402.665 + vertex -56.204 132.478 407.213 + vertex -57.8346 122.896 402.62 + endloop + endfacet + facet normal -0.00594258 -0.430153 0.902737 + outer loop + vertex -19.2201 112.557 398.037 + vertex -38.2006 122.533 402.665 + vertex -38.6323 112.812 398.03 + endloop + endfacet + facet normal -0.00586311 -0.430029 0.902796 + outer loop + vertex -18.2975 122.268 402.668 + vertex -38.2006 122.533 402.665 + vertex -19.2201 112.557 398.037 + endloop + endfacet + facet normal -0.00587236 -0.430726 0.902463 + outer loop + vertex -18.2975 122.268 402.668 + vertex -35.933 132.64 407.504 + vertex -38.2006 122.533 402.665 + endloop + endfacet + facet normal -0.00197582 -0.430336 0.902666 + outer loop + vertex 0.152117 112.463 398.034 + vertex -18.2975 122.268 402.668 + vertex -19.2201 112.557 398.037 + endloop + endfacet + facet normal -0.00180447 -0.430073 0.902792 + outer loop + vertex 1.35935 122.095 402.625 + vertex -18.2975 122.268 402.668 + vertex 0.152117 112.463 398.034 + endloop + endfacet + facet normal -0.00181281 -0.430922 0.902387 + outer loop + vertex 1.35935 122.095 402.625 + vertex -14.7786 131.795 407.225 + vertex -18.2975 122.268 402.668 + endloop + endfacet + facet normal 0.00198074 -0.43046 0.902608 + outer loop + vertex 19.3912 112.551 398.034 + vertex 1.35935 122.095 402.625 + vertex 0.152117 112.463 398.034 + endloop + endfacet + facet normal 0.00211752 -0.430249 0.902708 + outer loop + vertex 20.4783 122.169 402.615 + vertex 1.35935 122.095 402.625 + vertex 19.3912 112.551 398.034 + endloop + endfacet + facet normal 0.00211972 -0.430857 0.902418 + outer loop + vertex 20.4783 122.169 402.615 + vertex 4.68664 131.7 407.203 + vertex 1.35935 122.095 402.625 + endloop + endfacet + facet normal 0.00595107 -0.430596 0.902525 + outer loop + vertex 38.5381 112.827 398.039 + vertex 20.4783 122.169 402.615 + vertex 19.3912 112.551 398.034 + endloop + endfacet + facet normal 0.00614857 -0.430286 0.902672 + outer loop + vertex 39.4732 122.43 402.611 + vertex 20.4783 122.169 402.615 + vertex 38.5381 112.827 398.039 + endloop + endfacet + facet normal 0.00615695 -0.4309 0.902379 + outer loop + vertex 39.4732 122.43 402.611 + vertex 23.4656 131.737 407.164 + vertex 20.4783 122.169 402.615 + endloop + endfacet + facet normal 0.0100582 -0.430583 0.902495 + outer loop + vertex 57.7222 113.274 398.039 + vertex 39.4732 122.43 402.611 + vertex 38.5381 112.827 398.039 + endloop + endfacet + facet normal 0.0103349 -0.430136 0.902705 + outer loop + vertex 58.6545 122.893 402.612 + vertex 39.4732 122.43 402.611 + vertex 57.7222 113.274 398.039 + endloop + endfacet + facet normal 0.010355 -0.430968 0.902308 + outer loop + vertex 58.6545 122.893 402.612 + vertex 42.2262 132.047 407.172 + vertex 39.4732 122.43 402.611 + endloop + endfacet + facet normal 0.0144988 -0.430443 0.902501 + outer loop + vertex 76.9916 113.918 398.036 + vertex 58.6545 122.893 402.612 + vertex 57.7222 113.274 398.039 + endloop + endfacet + facet normal 0.0147647 -0.430004 0.902706 + outer loop + vertex 77.9975 123.564 402.615 + vertex 58.6545 122.893 402.612 + vertex 76.9916 113.918 398.036 + endloop + endfacet + facet normal 0.0148014 -0.431058 0.902203 + outer loop + vertex 77.9975 123.564 402.615 + vertex 61.8628 132.543 407.17 + vertex 58.6545 122.893 402.612 + endloop + endfacet + facet normal 0.0191337 -0.430344 0.902462 + outer loop + vertex 96.2766 114.77 398.034 + vertex 77.9975 123.564 402.615 + vertex 76.9916 113.918 398.036 + endloop + endfacet + facet normal 0.0194287 -0.42985 0.902691 + outer loop + vertex 97.3294 124.454 402.623 + vertex 77.9975 123.564 402.615 + vertex 96.2766 114.77 398.034 + endloop + endfacet + facet normal 0.0194774 -0.430903 0.902188 + outer loop + vertex 97.3294 124.454 402.623 + vertex 81.1147 133.323 407.209 + vertex 77.9975 123.564 402.615 + endloop + endfacet + facet normal 0.0239639 -0.43021 0.902411 + outer loop + vertex 115.513 115.843 398.035 + vertex 97.3294 124.454 402.623 + vertex 96.2766 114.77 398.034 + endloop + endfacet + facet normal 0.0242321 -0.429755 0.90262 + outer loop + vertex 116.52 125.554 402.631 + vertex 97.3294 124.454 402.623 + vertex 115.513 115.843 398.035 + endloop + endfacet + facet normal 0.0243062 -0.431044 0.902003 + outer loop + vertex 116.52 125.554 402.631 + vertex 100.509 134.263 407.224 + vertex 97.3294 124.454 402.623 + endloop + endfacet + facet normal 0.0288583 -0.430094 0.902323 + outer loop + vertex 134.676 117.132 398.036 + vertex 116.52 125.554 402.631 + vertex 115.513 115.843 398.035 + endloop + endfacet + facet normal 0.0291466 -0.429597 0.90255 + outer loop + vertex 135.562 126.843 402.63 + vertex 116.52 125.554 402.631 + vertex 134.676 117.132 398.036 + endloop + endfacet + facet normal 0.0292232 -0.43073 0.902008 + outer loop + vertex 135.562 126.843 402.63 + vertex 119.282 135.363 407.226 + vertex 116.52 125.554 402.631 + endloop + endfacet + facet normal 0.0337123 -0.429876 0.902258 + outer loop + vertex 153.79 118.632 398.037 + vertex 135.562 126.843 402.63 + vertex 134.676 117.132 398.036 + endloop + endfacet + facet normal 0.0339468 -0.429461 0.902447 + outer loop + vertex 154.599 128.327 402.62 + vertex 135.562 126.843 402.63 + vertex 153.79 118.632 398.037 + endloop + endfacet + facet normal 0.0340219 -0.430427 0.901984 + outer loop + vertex 154.599 128.327 402.62 + vertex 138.011 136.638 407.211 + vertex 135.562 126.843 402.63 + endloop + endfacet + facet normal 0.038458 -0.429698 0.902153 + outer loop + vertex 172.854 120.349 398.042 + vertex 154.599 128.327 402.62 + vertex 153.79 118.632 398.037 + endloop + endfacet + facet normal 0.038753 -0.429162 0.902396 + outer loop + vertex 173.616 130.037 402.617 + vertex 154.599 128.327 402.62 + vertex 172.854 120.349 398.042 + endloop + endfacet + facet normal 0.0388406 -0.430137 0.901928 + outer loop + vertex 173.616 130.037 402.617 + vertex 157.228 138.158 407.195 + vertex 154.599 128.327 402.62 + endloop + endfacet + facet normal 0.0431514 -0.429368 0.902098 + outer loop + vertex 191.892 122.296 398.058 + vertex 173.616 130.037 402.617 + vertex 172.854 120.349 398.042 + endloop + endfacet + facet normal 0.0433446 -0.429007 0.902261 + outer loop + vertex 192.563 131.975 402.628 + vertex 173.616 130.037 402.617 + vertex 191.892 122.296 398.058 + endloop + endfacet + facet normal 0.0475773 -0.429165 0.901972 + outer loop + vertex 210.87 124.431 398.072 + vertex 192.563 131.975 402.628 + vertex 191.892 122.296 398.058 + endloop + endfacet + facet normal 0.0477731 -0.428791 0.90214 + outer loop + vertex 211.453 134.116 402.645 + vertex 192.563 131.975 402.628 + vertex 210.87 124.431 398.072 + endloop + endfacet + facet normal 0.0516459 -0.428899 0.901875 + outer loop + vertex 229.749 126.666 398.054 + vertex 211.453 134.116 402.645 + vertex 210.87 124.431 398.072 + endloop + endfacet + facet normal 0.051774 -0.429985 0.90135 + outer loop + vertex 229.749 126.666 398.054 + vertex 210.87 124.431 398.072 + vertex 230.137 117.787 393.796 + endloop + endfacet + facet normal 0.0556653 -0.429756 0.901228 + outer loop + vertex 248.928 120.096 393.737 + vertex 229.749 126.666 398.054 + vertex 230.137 117.787 393.796 + endloop + endfacet + facet normal 0.0556092 -0.429882 0.901171 + outer loop + vertex 248.503 128.962 397.992 + vertex 229.749 126.666 398.054 + vertex 248.928 120.096 393.737 + endloop + endfacet + facet normal 0.0596305 -0.429625 0.901036 + outer loop + vertex 267.699 122.556 393.668 + vertex 248.503 128.962 397.992 + vertex 248.928 120.096 393.737 + endloop + endfacet + facet normal 0.0600309 -0.432722 0.899526 + outer loop + vertex 267.699 122.556 393.668 + vertex 248.928 120.096 393.737 + vertex 268.266 114.456 389.733 + endloop + endfacet + facet normal 0.0597648 -0.429316 0.901175 + outer loop + vertex 267.247 131.478 397.948 + vertex 248.503 128.962 397.992 + vertex 267.699 122.556 393.668 + endloop + endfacet + facet normal 0.064743 -0.428976 0.900993 + outer loop + vertex 286.78 125.561 393.727 + vertex 267.247 131.478 397.948 + vertex 267.699 122.556 393.668 + endloop + endfacet + facet normal 0.0652442 -0.432128 0.899449 + outer loop + vertex 286.78 125.561 393.727 + vertex 267.699 122.556 393.668 + vertex 287.351 117.388 389.759 + endloop + endfacet + facet normal 0.0648423 -0.428728 0.901104 + outer loop + vertex 286.281 134.538 398.034 + vertex 267.247 131.478 397.948 + vertex 286.78 125.561 393.727 + endloop + endfacet + facet normal 0.0705218 -0.428304 0.900879 + outer loop + vertex 306.428 129.376 394.003 + vertex 286.281 134.538 398.034 + vertex 286.78 125.561 393.727 + endloop + endfacet + facet normal 0.0711169 -0.431264 0.899419 + outer loop + vertex 306.428 129.376 394.003 + vertex 286.78 125.561 393.727 + vertex 307.017 121.117 389.996 + endloop + endfacet + facet normal 0.0706613 -0.427901 0.901059 + outer loop + vertex 305.87 138.353 398.31 + vertex 286.281 134.538 398.034 + vertex 306.428 129.376 394.003 + endloop + endfacet + facet normal 0.0768981 -0.427386 0.900793 + outer loop + vertex 326.661 134.029 394.483 + vertex 305.87 138.353 398.31 + vertex 306.428 129.376 394.003 + endloop + endfacet + facet normal 0.0776279 -0.430404 0.899292 + outer loop + vertex 326.661 134.029 394.483 + vertex 306.428 129.376 394.003 + vertex 327.239 125.76 390.476 + endloop + endfacet + facet normal 0.0854242 -0.429683 0.89893 + outer loop + vertex 326.661 134.029 394.483 + vertex 327.239 125.76 390.476 + vertex 340.035 130.622 391.584 + endloop + endfacet + facet normal 0.0856598 -0.429012 0.899228 + outer loop + vertex 341.64 134.837 393.442 + vertex 326.661 134.029 394.483 + vertex 340.035 130.622 391.584 + endloop + endfacet + facet normal 0.102249 -0.433592 0.895289 + outer loop + vertex 350.577 133.583 391.814 + vertex 341.64 134.837 393.442 + vertex 340.035 130.622 391.584 + endloop + endfacet + facet normal 0.101166 -0.429885 0.897198 + outer loop + vertex 350.577 133.583 391.814 + vertex 340.035 130.622 391.584 + vertex 350.867 129.512 389.831 + endloop + endfacet + facet normal 0.122734 -0.427576 0.895609 + outer loop + vertex 359.569 132.328 389.983 + vertex 350.577 133.583 391.814 + vertex 350.867 129.512 389.831 + endloop + endfacet + facet normal 0.122787 -0.427347 0.895711 + outer loop + vertex 359.232 136.415 391.979 + vertex 350.577 133.583 391.814 + vertex 359.569 132.328 389.983 + endloop + endfacet + facet normal 0.148577 -0.424073 0.893357 + outer loop + vertex 367.063 134.962 389.986 + vertex 359.232 136.415 391.979 + vertex 359.569 132.328 389.983 + endloop + endfacet + facet normal 0.148593 -0.424119 0.893333 + outer loop + vertex 367.063 134.962 389.986 + vertex 359.569 132.328 389.983 + vertex 367.496 130.893 387.983 + endloop + endfacet + facet normal 0.175567 -0.419835 0.890457 + outer loop + vertex 373.775 133.382 387.918 + vertex 367.063 134.962 389.986 + vertex 367.496 130.893 387.983 + endloop + endfacet + facet normal 0.175736 -0.419365 0.890646 + outer loop + vertex 373.273 137.446 389.931 + vertex 367.063 134.962 389.986 + vertex 373.775 133.382 387.918 + endloop + endfacet + facet normal 0.203168 -0.414266 0.88719 + outer loop + vertex 378.621 135.832 387.952 + vertex 373.273 137.446 389.931 + vertex 373.775 133.382 387.918 + endloop + endfacet + facet normal 0.202082 -0.412133 0.888431 + outer loop + vertex 378.621 135.832 387.952 + vertex 373.775 133.382 387.918 + vertex 379.233 131.803 385.944 + endloop + endfacet + facet normal 0.225718 -0.406903 0.885145 + outer loop + vertex 382.656 134.315 386.226 + vertex 378.621 135.832 387.952 + vertex 379.233 131.803 385.944 + endloop + endfacet + facet normal 0.201654 -0.413146 0.888058 + outer loop + vertex 379.233 131.803 385.944 + vertex 373.775 133.382 387.918 + vertex 374.322 129.395 385.939 + endloop + endfacet + facet normal 0.202886 -0.41491 0.886954 + outer loop + vertex 378.049 139.83 389.953 + vertex 373.273 137.446 389.931 + vertex 378.621 135.832 387.952 + endloop + endfacet + facet normal 0.226998 -0.409734 0.88351 + outer loop + vertex 381.955 138.43 388.301 + vertex 378.049 139.83 389.953 + vertex 378.621 135.832 387.952 + endloop + endfacet + facet normal 0.203443 -0.416019 0.886307 + outer loop + vertex 378.049 139.83 389.953 + vertex 372.849 141.503 391.932 + vertex 373.273 137.446 389.931 + endloop + endfacet + facet normal 0.176332 -0.420638 0.889928 + outer loop + vertex 372.849 141.503 391.932 + vertex 366.695 139.057 391.995 + vertex 373.273 137.446 389.931 + endloop + endfacet + facet normal 0.176736 -0.42167 0.889359 + outer loop + vertex 372.849 141.503 391.932 + vertex 366.391 143.107 393.976 + vertex 366.695 139.057 391.995 + endloop + endfacet + facet normal 0.147743 -0.425528 0.892803 + outer loop + vertex 366.391 143.107 393.976 + vertex 358.946 140.473 393.953 + vertex 366.695 139.057 391.995 + endloop + endfacet + facet normal 0.148132 -0.42419 0.893375 + outer loop + vertex 366.695 139.057 391.995 + vertex 358.946 140.473 393.953 + vertex 359.232 136.415 391.979 + endloop + endfacet + facet normal 0.122449 -0.427197 0.895829 + outer loop + vertex 358.946 140.473 393.953 + vertex 350.31 137.647 393.786 + vertex 359.232 136.415 391.979 + endloop + endfacet + facet normal 0.122177 -0.426389 0.896251 + outer loop + vertex 358.946 140.473 393.953 + vertex 350.079 141.688 395.74 + vertex 350.31 137.647 393.786 + endloop + endfacet + facet normal 0.0998604 -0.428507 0.898003 + outer loop + vertex 350.079 141.688 395.74 + vertex 339.487 138.837 395.557 + vertex 350.31 137.647 393.786 + endloop + endfacet + facet normal 0.101055 -0.422016 0.900938 + outer loop + vertex 350.31 137.647 393.786 + vertex 339.487 138.837 395.557 + vertex 341.64 134.837 393.442 + endloop + endfacet + facet normal 0.100536 -0.430938 0.896764 + outer loop + vertex 350.079 141.688 395.74 + vertex 341.101 143.09 397.42 + vertex 339.487 138.837 395.557 + endloop + endfacet + facet normal 0.0847058 -0.426562 0.900483 + outer loop + vertex 341.101 143.09 397.42 + vertex 326.039 142.746 398.674 + vertex 339.487 138.837 395.557 + endloop + endfacet + facet normal 0.0846137 -0.426797 0.900381 + outer loop + vertex 326.039 142.746 398.674 + vertex 326.661 134.029 394.483 + vertex 339.487 138.837 395.557 + endloop + endfacet + facet normal 0.0846971 -0.42709 0.900233 + outer loop + vertex 341.101 143.09 397.42 + vertex 338.862 147.333 399.643 + vertex 326.039 142.746 398.674 + endloop + endfacet + facet normal 0.0842446 -0.425949 0.900817 + outer loop + vertex 325.412 151.86 403.042 + vertex 326.039 142.746 398.674 + vertex 338.862 147.333 399.643 + endloop + endfacet + facet normal 0.0846769 -0.424978 0.901234 + outer loop + vertex 340.317 151.817 401.621 + vertex 325.412 151.86 403.042 + vertex 338.862 147.333 399.643 + endloop + endfacet + facet normal 0.0983671 -0.428145 0.898341 + outer loop + vertex 349.53 149.945 399.72 + vertex 340.317 151.817 401.621 + vertex 338.862 147.333 399.643 + endloop + endfacet + facet normal 0.0979084 -0.426299 0.899268 + outer loop + vertex 349.53 149.945 399.72 + vertex 338.862 147.333 399.643 + vertex 349.841 145.759 397.702 + endloop + endfacet + facet normal 0.119835 -0.423933 0.897731 + outer loop + vertex 358.491 148.484 397.834 + vertex 349.53 149.945 399.72 + vertex 349.841 145.759 397.702 + endloop + endfacet + facet normal 0.120677 -0.426539 0.896383 + outer loop + vertex 358.491 148.484 397.834 + vertex 349.841 145.759 397.702 + vertex 358.724 144.481 395.898 + endloop + endfacet + facet normal 0.146754 -0.42377 0.893802 + outer loop + vertex 366.128 147.079 395.914 + vertex 358.491 148.484 397.834 + vertex 358.724 144.481 395.898 + endloop + endfacet + facet normal 0.147461 -0.425777 0.892731 + outer loop + vertex 366.128 147.079 395.914 + vertex 358.724 144.481 395.898 + vertex 366.391 143.107 393.976 + endloop + endfacet + facet normal 0.176524 -0.422124 0.889186 + outer loop + vertex 372.522 145.5 393.895 + vertex 366.128 147.079 395.914 + vertex 366.391 143.107 393.976 + endloop + endfacet + facet normal 0.176016 -0.423481 0.888641 + outer loop + vertex 372.235 149.412 395.816 + vertex 366.128 147.079 395.914 + vertex 372.522 145.5 393.895 + endloop + endfacet + facet normal 0.205289 -0.41923 0.884366 + outer loop + vertex 377.288 147.639 393.802 + vertex 372.235 149.412 395.816 + vertex 372.522 145.5 393.895 + endloop + endfacet + facet normal 0.20453 -0.417497 0.885361 + outer loop + vertex 377.288 147.639 393.802 + vertex 372.522 145.5 393.895 + vertex 377.611 143.748 391.893 + endloop + endfacet + facet normal 0.22895 -0.413463 0.881266 + outer loop + vertex 381.043 145.784 391.957 + vertex 377.288 147.639 393.802 + vertex 377.611 143.748 391.893 + endloop + endfacet + facet normal 0.204304 -0.417963 0.885193 + outer loop + vertex 377.611 143.748 391.893 + vertex 372.522 145.5 393.895 + vertex 372.849 141.503 391.932 + endloop + endfacet + facet normal 0.204603 -0.420617 0.883866 + outer loop + vertex 376.976 151.481 395.703 + vertex 372.235 149.412 395.816 + vertex 377.288 147.639 393.802 + endloop + endfacet + facet normal 0.230119 -0.416418 0.879569 + outer loop + vertex 380.67 149.623 393.857 + vertex 376.976 151.481 395.703 + vertex 377.288 147.639 393.802 + endloop + endfacet + facet normal 0.204756 -0.420979 0.883658 + outer loop + vertex 376.976 151.481 395.703 + vertex 371.993 153.301 397.725 + vertex 372.235 149.412 395.816 + endloop + endfacet + facet normal 0.175538 -0.424945 0.888036 + outer loop + vertex 371.993 153.301 397.725 + vertex 365.927 151.029 397.837 + vertex 372.235 149.412 395.816 + endloop + endfacet + facet normal 0.174723 -0.42271 0.889262 + outer loop + vertex 371.993 153.301 397.725 + vertex 365.67 155.076 399.811 + vertex 365.927 151.029 397.837 + endloop + endfacet + facet normal 0.1438 -0.426492 0.892987 + outer loop + vertex 365.67 155.076 399.811 + vertex 358.22 152.603 399.829 + vertex 365.927 151.029 397.837 + endloop + endfacet + facet normal 0.144678 -0.423696 0.894176 + outer loop + vertex 365.927 151.029 397.837 + vertex 358.22 152.603 399.829 + vertex 358.491 148.484 397.834 + endloop + endfacet + facet normal 0.142544 -0.422693 0.894993 + outer loop + vertex 365.67 155.076 399.811 + vertex 357.807 156.947 401.947 + vertex 358.22 152.603 399.829 + endloop + endfacet + facet normal 0.117196 -0.426105 0.897051 + outer loop + vertex 357.807 156.947 401.947 + vertex 349.075 154.361 401.86 + vertex 358.22 152.603 399.829 + endloop + endfacet + facet normal 0.118078 -0.423052 0.898379 + outer loop + vertex 358.22 152.603 399.829 + vertex 349.075 154.361 401.86 + vertex 349.53 149.945 399.72 + endloop + endfacet + facet normal 0.116238 -0.422924 0.898679 + outer loop + vertex 357.807 156.947 401.947 + vertex 348.498 159.002 404.118 + vertex 349.075 154.361 401.86 + endloop + endfacet + facet normal 0.0965421 -0.425837 0.899634 + outer loop + vertex 348.498 159.002 404.118 + vertex 337.912 156.395 404.02 + vertex 349.075 154.361 401.86 + endloop + endfacet + facet normal 0.0977958 -0.421152 0.901702 + outer loop + vertex 349.075 154.361 401.86 + vertex 337.912 156.395 404.02 + vertex 340.317 151.817 401.621 + endloop + endfacet + facet normal 0.0973196 -0.428936 0.898077 + outer loop + vertex 348.498 159.002 404.118 + vertex 339.337 161.094 406.11 + vertex 337.912 156.395 404.02 + endloop + endfacet + facet normal 0.0857245 -0.426467 0.900432 + outer loop + vertex 339.337 161.094 406.11 + vertex 325.295 160.509 407.17 + vertex 337.912 156.395 404.02 + endloop + endfacet + facet normal 0.0849521 -0.428245 0.899661 + outer loop + vertex 325.295 160.509 407.17 + vertex 325.412 151.86 403.042 + vertex 337.912 156.395 404.02 + endloop + endfacet + facet normal 0.097918 -0.427091 0.898891 + outer loop + vertex 348.306 163.62 406.333 + vertex 339.337 161.094 406.11 + vertex 348.498 159.002 404.118 + endloop + endfacet + facet normal 0.114636 -0.425752 0.897549 + outer loop + vertex 357.328 161.475 404.164 + vertex 348.306 163.62 406.333 + vertex 348.498 159.002 404.118 + endloop + endfacet + facet normal 0.113786 -0.428241 0.896472 + outer loop + vertex 357.217 165.846 406.266 + vertex 348.306 163.62 406.333 + vertex 357.328 161.475 404.164 + endloop + endfacet + facet normal 0.138397 -0.426376 0.893896 + outer loop + vertex 364.786 163.711 404.075 + vertex 357.217 165.846 406.266 + vertex 357.328 161.475 404.164 + endloop + endfacet + facet normal 0.138723 -0.427487 0.893314 + outer loop + vertex 364.786 163.711 404.075 + vertex 357.328 161.475 404.164 + vertex 365.27 159.329 401.903 + endloop + endfacet + facet normal 0.167355 -0.42296 0.89056 + outer loop + vertex 371.356 161.474 401.778 + vertex 364.786 163.711 404.075 + vertex 365.27 159.329 401.903 + endloop + endfacet + facet normal 0.168719 -0.426957 0.888393 + outer loop + vertex 371.356 161.474 401.778 + vertex 365.27 159.329 401.903 + vertex 371.761 157.291 399.691 + endloop + endfacet + facet normal 0.198099 -0.422216 0.884585 + outer loop + vertex 376.411 159.338 399.627 + vertex 371.356 161.474 401.778 + vertex 371.761 157.291 399.691 + endloop + endfacet + facet normal 0.200326 -0.427368 0.881604 + outer loop + vertex 376.411 159.338 399.627 + vertex 371.761 157.291 399.691 + vertex 376.725 155.347 397.621 + endloop + endfacet + facet normal 0.226873 -0.423083 0.877228 + outer loop + vertex 380.045 157.475 397.788 + vertex 376.411 159.338 399.627 + vertex 376.725 155.347 397.621 + endloop + endfacet + facet normal 0.202504 -0.423344 0.883047 + outer loop + vertex 376.725 155.347 397.621 + vertex 371.761 157.291 399.691 + vertex 371.993 153.301 397.725 + endloop + endfacet + facet normal 0.194581 -0.428353 0.882412 + outer loop + vertex 376.019 163.483 401.725 + vertex 371.356 161.474 401.778 + vertex 376.411 159.338 399.627 + endloop + endfacet + facet normal 0.218571 -0.424241 0.878775 + outer loop + vertex 379.453 161.492 399.91 + vertex 376.019 163.483 401.725 + vertex 376.411 159.338 399.627 + endloop + endfacet + facet normal 0.1921 -0.422507 0.885768 + outer loop + vertex 376.019 163.483 401.725 + vertex 370.856 165.777 403.939 + vertex 371.356 161.474 401.778 + endloop + endfacet + facet normal 0.18944 -0.426979 0.884196 + outer loop + vertex 375.622 167.753 403.872 + vertex 370.856 165.777 403.939 + vertex 376.019 163.483 401.725 + endloop + endfacet + facet normal 0.210915 -0.423401 0.881048 + outer loop + vertex 379.221 165.475 401.916 + vertex 375.622 167.753 403.872 + vertex 376.019 163.483 401.725 + endloop + endfacet + facet normal 0.187006 -0.420998 0.887575 + outer loop + vertex 375.622 167.753 403.872 + vertex 370.365 169.934 406.014 + vertex 370.856 165.777 403.939 + endloop + endfacet + facet normal 0.163102 -0.425181 0.890292 + outer loop + vertex 370.365 169.934 406.014 + vertex 364.353 167.874 406.132 + vertex 370.856 165.777 403.939 + endloop + endfacet + facet normal 0.164016 -0.423173 0.89108 + outer loop + vertex 370.856 165.777 403.939 + vertex 364.353 167.874 406.132 + vertex 364.786 163.711 404.075 + endloop + endfacet + facet normal 0.160976 -0.418779 0.893706 + outer loop + vertex 370.365 169.934 406.014 + vertex 363.942 171.493 407.902 + vertex 364.353 167.874 406.132 + endloop + endfacet + facet normal 0.183446 -0.427337 0.885286 + outer loop + vertex 375.301 171.804 405.894 + vertex 370.365 169.934 406.014 + vertex 375.622 167.753 403.872 + endloop + endfacet + facet normal 0.205014 -0.42405 0.882129 + outer loop + vertex 379.16 169.819 404.043 + vertex 375.301 171.804 405.894 + vertex 375.622 167.753 403.872 + endloop + endfacet + facet normal 0.1815 -0.422013 0.888236 + outer loop + vertex 375.301 171.804 405.894 + vertex 370.723 173.656 407.71 + vertex 370.365 169.934 406.014 + endloop + endfacet + facet normal 0.170976 -0.421912 0.890369 + outer loop + vertex 371.761 157.291 399.691 + vertex 365.27 159.329 401.903 + vertex 365.67 155.076 399.811 + endloop + endfacet + facet normal 0.165336 -0.427198 0.888913 + outer loop + vertex 370.856 165.777 403.939 + vertex 364.786 163.711 404.075 + vertex 371.356 161.474 401.778 + endloop + endfacet + facet normal 0.140357 -0.423283 0.89506 + outer loop + vertex 365.27 159.329 401.903 + vertex 357.328 161.475 404.164 + vertex 357.807 156.947 401.947 + endloop + endfacet + facet normal 0.138104 -0.427104 0.893593 + outer loop + vertex 364.353 167.874 406.132 + vertex 357.217 165.846 406.266 + vertex 364.786 163.711 404.075 + endloop + endfacet + facet normal 0.138506 -0.42857 0.892829 + outer loop + vertex 364.353 167.874 406.132 + vertex 358.075 169.268 407.775 + vertex 357.217 165.846 406.266 + endloop + endfacet + facet normal 0.113985 -0.429051 0.89606 + outer loop + vertex 357.217 165.846 406.266 + vertex 349.904 167.893 408.176 + vertex 348.306 163.62 406.333 + endloop + endfacet + facet normal 0.0975196 -0.425737 0.899577 + outer loop + vertex 348.306 163.62 406.333 + vertex 337.958 165.391 408.293 + vertex 339.337 161.094 406.11 + endloop + endfacet + facet normal 0.11496 -0.426899 0.896962 + outer loop + vertex 357.328 161.475 404.164 + vertex 348.498 159.002 404.118 + vertex 357.807 156.947 401.947 + endloop + endfacet + facet normal 0.141293 -0.426248 0.893504 + outer loop + vertex 365.27 159.329 401.903 + vertex 357.807 156.947 401.947 + vertex 365.67 155.076 399.811 + endloop + endfacet + facet normal 0.172856 -0.427241 0.88746 + outer loop + vertex 371.761 157.291 399.691 + vertex 365.67 155.076 399.811 + vertex 371.993 153.301 397.725 + endloop + endfacet + facet normal 0.202974 -0.424464 0.882401 + outer loop + vertex 376.725 155.347 397.621 + vertex 371.993 153.301 397.725 + vertex 376.976 151.481 395.703 + endloop + endfacet + facet normal 0.229992 -0.420381 0.877715 + outer loop + vertex 380.347 153.418 395.747 + vertex 376.725 155.347 397.621 + vertex 376.976 151.481 395.703 + endloop + endfacet + facet normal 0.176058 -0.423593 0.888579 + outer loop + vertex 372.235 149.412 395.816 + vertex 365.927 151.029 397.837 + vertex 366.128 147.079 395.914 + endloop + endfacet + facet normal 0.145811 -0.427003 0.892417 + outer loop + vertex 365.927 151.029 397.837 + vertex 358.491 148.484 397.834 + vertex 366.128 147.079 395.914 + endloop + endfacet + facet normal 0.120971 -0.425281 0.89694 + outer loop + vertex 358.724 144.481 395.898 + vertex 349.841 145.759 397.702 + vertex 350.079 141.688 395.74 + endloop + endfacet + facet normal 0.119168 -0.426542 0.896583 + outer loop + vertex 358.22 152.603 399.829 + vertex 349.53 149.945 399.72 + vertex 358.491 148.484 397.834 + endloop + endfacet + facet normal 0.0991325 -0.425546 0.899491 + outer loop + vertex 349.075 154.361 401.86 + vertex 340.317 151.817 401.621 + vertex 349.53 149.945 399.72 + endloop + endfacet + facet normal 0.0845671 -0.42729 0.900151 + outer loop + vertex 340.317 151.817 401.621 + vertex 337.912 156.395 404.02 + vertex 325.412 151.86 403.042 + endloop + endfacet + facet normal 0.0764536 -0.426657 0.901176 + outer loop + vertex 325.412 151.86 403.042 + vertex 305.61 147.9 402.847 + vertex 326.039 142.746 398.674 + endloop + endfacet + facet normal 0.0765804 -0.426288 0.90134 + outer loop + vertex 326.039 142.746 398.674 + vertex 305.61 147.9 402.847 + vertex 305.87 138.353 398.31 + endloop + endfacet + facet normal 0.0703234 -0.426625 0.901691 + outer loop + vertex 305.61 147.9 402.847 + vertex 286.336 144.326 402.659 + vertex 305.87 138.353 398.31 + endloop + endfacet + facet normal 0.070491 -0.427506 0.90126 + outer loop + vertex 305.61 147.9 402.847 + vertex 287.26 154.089 407.218 + vertex 286.336 144.326 402.659 + endloop + endfacet + facet normal 0.0768565 -0.428624 0.900208 + outer loop + vertex 325.412 151.86 403.042 + vertex 306.239 157.319 407.278 + vertex 305.61 147.9 402.847 + endloop + endfacet + facet normal 0.0992387 -0.42031 0.901937 + outer loop + vertex 349.841 145.759 397.702 + vertex 338.862 147.333 399.643 + vertex 341.101 143.09 397.42 + endloop + endfacet + facet normal 0.101444 -0.427163 0.898466 + outer loop + vertex 349.841 145.759 397.702 + vertex 341.101 143.09 397.42 + vertex 350.079 141.688 395.74 + endloop + endfacet + facet normal 0.121837 -0.427886 0.895583 + outer loop + vertex 358.724 144.481 395.898 + vertex 350.079 141.688 395.74 + vertex 358.946 140.473 393.953 + endloop + endfacet + facet normal 0.147626 -0.425199 0.89298 + outer loop + vertex 366.391 143.107 393.976 + vertex 358.724 144.481 395.898 + vertex 358.946 140.473 393.953 + endloop + endfacet + facet normal 0.176545 -0.42218 0.889155 + outer loop + vertex 372.522 145.5 393.895 + vertex 366.391 143.107 393.976 + vertex 372.849 141.503 391.932 + endloop + endfacet + facet normal 0.20342 -0.416068 0.886289 + outer loop + vertex 377.611 143.748 391.893 + vertex 372.849 141.503 391.932 + vertex 378.049 139.83 389.953 + endloop + endfacet + facet normal 0.226234 -0.411773 0.882758 + outer loop + vertex 381.198 142.048 390.181 + vertex 377.611 143.748 391.893 + vertex 378.049 139.83 389.953 + endloop + endfacet + facet normal 0.176286 -0.42076 0.889879 + outer loop + vertex 373.273 137.446 389.931 + vertex 366.695 139.057 391.995 + vertex 367.063 134.962 389.986 + endloop + endfacet + facet normal 0.148356 -0.424822 0.893038 + outer loop + vertex 366.695 139.057 391.995 + vertex 359.232 136.415 391.979 + vertex 367.063 134.962 389.986 + endloop + endfacet + facet normal 0.122565 -0.42669 0.896054 + outer loop + vertex 359.232 136.415 391.979 + vertex 350.31 137.647 393.786 + vertex 350.577 133.583 391.814 + endloop + endfacet + facet normal 0.103347 -0.428671 0.89753 + outer loop + vertex 350.31 137.647 393.786 + vertex 341.64 134.837 393.442 + vertex 350.577 133.583 391.814 + endloop + endfacet + facet normal 0.085666 -0.429314 0.899083 + outer loop + vertex 341.64 134.837 393.442 + vertex 339.487 138.837 395.557 + vertex 326.661 134.029 394.483 + endloop + endfacet + facet normal 0.0768595 -0.427519 0.900733 + outer loop + vertex 326.039 142.746 398.674 + vertex 305.87 138.353 398.31 + vertex 326.661 134.029 394.483 + endloop + endfacet + facet normal 0.0703772 -0.426492 0.901749 + outer loop + vertex 305.87 138.353 398.31 + vertex 286.336 144.326 402.659 + vertex 286.281 134.538 398.034 + endloop + endfacet + facet normal 0.0647982 -0.426628 0.902103 + outer loop + vertex 286.336 144.326 402.659 + vertex 267.504 141.278 402.57 + vertex 286.281 134.538 398.034 + endloop + endfacet + facet normal 0.0649021 -0.427261 0.901796 + outer loop + vertex 286.336 144.326 402.659 + vertex 269.235 151.269 407.18 + vertex 267.504 141.278 402.57 + endloop + endfacet + facet normal 0.0645774 -0.427102 0.901894 + outer loop + vertex 286.281 134.538 398.034 + vertex 267.504 141.278 402.57 + vertex 267.247 131.478 397.948 + endloop + endfacet + facet normal 0.0600191 -0.427126 0.902198 + outer loop + vertex 267.504 141.278 402.57 + vertex 248.807 138.673 402.581 + vertex 267.247 131.478 397.948 + endloop + endfacet + facet normal 0.0601034 -0.427732 0.901905 + outer loop + vertex 267.504 141.278 402.57 + vertex 250.502 148.626 407.188 + vertex 248.807 138.673 402.581 + endloop + endfacet + facet normal 0.0595879 -0.427987 0.901818 + outer loop + vertex 267.247 131.478 397.948 + vertex 248.807 138.673 402.581 + vertex 248.503 128.962 397.992 + endloop + endfacet + facet normal 0.0557635 -0.427983 0.902065 + outer loop + vertex 248.807 138.673 402.581 + vertex 230.169 136.341 402.626 + vertex 248.503 128.962 397.992 + endloop + endfacet + facet normal 0.0558685 -0.428831 0.901656 + outer loop + vertex 248.807 138.673 402.581 + vertex 231.902 146.158 407.188 + vertex 230.169 136.341 402.626 + endloop + endfacet + facet normal 0.0554528 -0.428587 0.901797 + outer loop + vertex 248.503 128.962 397.992 + vertex 230.169 136.341 402.626 + vertex 229.749 126.666 398.054 + endloop + endfacet + facet normal 0.0518311 -0.428542 0.902034 + outer loop + vertex 230.169 136.341 402.626 + vertex 211.453 134.116 402.645 + vertex 229.749 126.666 398.054 + endloop + endfacet + facet normal 0.0519371 -0.429438 0.901602 + outer loop + vertex 230.169 136.341 402.626 + vertex 213.54 143.923 407.196 + vertex 211.453 134.116 402.645 + endloop + endfacet + facet normal 0.0478878 -0.4298 0.901654 + outer loop + vertex 211.453 134.116 402.645 + vertex 195.08 141.815 407.185 + vertex 192.563 131.975 402.628 + endloop + endfacet + facet normal 0.0434453 -0.429989 0.901788 + outer loop + vertex 192.563 131.975 402.628 + vertex 175.994 139.795 407.155 + vertex 173.616 130.037 402.617 + endloop + endfacet + facet normal 0.0476889 -0.430153 0.901495 + outer loop + vertex 210.87 124.431 398.072 + vertex 191.892 122.296 398.058 + vertex 211.22 115.543 393.813 + endloop + endfacet + facet normal 0.0517971 -0.429933 0.901374 + outer loop + vertex 230.137 117.787 393.796 + vertex 210.87 124.431 398.072 + vertex 211.22 115.543 393.813 + endloop + endfacet + facet normal 0.056045 -0.432885 0.899705 + outer loop + vertex 248.928 120.096 393.737 + vertex 230.137 117.787 393.796 + vertex 249.48 111.995 389.805 + endloop + endfacet + facet normal 0.060094 -0.432559 0.899601 + outer loop + vertex 268.266 114.456 389.733 + vertex 248.928 120.096 393.737 + vertex 249.48 111.995 389.805 + endloop + endfacet + facet normal 0.0651874 -0.432289 0.899376 + outer loop + vertex 287.351 117.388 389.759 + vertex 267.699 122.556 393.668 + vertex 268.266 114.456 389.733 + endloop + endfacet + facet normal 0.0710061 -0.431629 0.899252 + outer loop + vertex 307.017 121.117 389.996 + vertex 286.78 125.561 393.727 + vertex 287.351 117.388 389.759 + endloop + endfacet + facet normal 0.0775581 -0.430682 0.899165 + outer loop + vertex 327.239 125.76 390.476 + vertex 306.428 129.376 394.003 + vertex 307.017 121.117 389.996 + endloop + endfacet + facet normal 0.0866426 -0.432549 0.897438 + outer loop + vertex 342.174 126.711 389.492 + vertex 340.035 130.622 391.584 + vertex 327.239 125.76 390.476 + endloop + endfacet + facet normal 0.101997 -0.425174 0.899346 + outer loop + vertex 350.867 129.512 389.831 + vertex 340.035 130.622 391.584 + vertex 342.174 126.711 389.492 + endloop + endfacet + facet normal 0.12313 -0.428767 0.894985 + outer loop + vertex 359.569 132.328 389.983 + vertex 350.867 129.512 389.831 + vertex 359.919 128.266 387.988 + endloop + endfacet + facet normal 0.148193 -0.425504 0.89274 + outer loop + vertex 367.496 130.893 387.983 + vertex 359.569 132.328 389.983 + vertex 359.919 128.266 387.988 + endloop + endfacet + facet normal 0.175 -0.418386 0.891251 + outer loop + vertex 373.775 133.382 387.918 + vertex 367.496 130.893 387.983 + vertex 374.322 129.395 385.939 + endloop + endfacet + facet normal 0.200303 -0.410394 0.889638 + outer loop + vertex 379.233 131.803 385.944 + vertex 374.322 129.395 385.939 + vertex 379.836 127.924 384.019 + endloop + endfacet + facet normal 0.222619 -0.405421 0.886609 + outer loop + vertex 383.324 130.203 384.185 + vertex 379.233 131.803 385.944 + vertex 379.836 127.924 384.019 + endloop + endfacet + facet normal 0.173499 -0.420147 0.890716 + outer loop + vertex 374.911 125.516 384.003 + vertex 367.983 126.904 386.007 + vertex 368.531 122.999 384.058 + endloop + endfacet + facet normal 0.146873 -0.425101 0.89315 + outer loop + vertex 367.983 126.904 386.007 + vertex 360.321 124.273 386.015 + vertex 368.531 122.999 384.058 + endloop + endfacet + facet normal 0.122884 -0.430396 0.894236 + outer loop + vertex 360.321 124.273 386.015 + vertex 351.165 125.476 387.852 + vertex 351.506 121.503 385.893 + endloop + endfacet + facet normal 0.102228 -0.429122 0.897443 + outer loop + vertex 351.506 121.503 385.893 + vertex 340.569 122.584 387.656 + vertex 342.72 118.785 385.594 + endloop + endfacet + facet normal 0.0873963 -0.436451 0.895473 + outer loop + vertex 342.72 118.785 385.594 + vertex 340.569 122.584 387.656 + vertex 327.751 117.85 386.6 + endloop + endfacet + facet normal 0.0792365 -0.439859 0.894565 + outer loop + vertex 327.751 117.85 386.6 + vertex 307.484 113.341 386.177 + vertex 328.215 110.168 382.781 + endloop + endfacet + facet normal 0.102141 -0.434777 0.894727 + outer loop + vertex 352.281 113.746 382.019 + vertex 341.139 114.782 383.795 + vertex 343.336 111.085 381.747 + endloop + endfacet + facet normal 0.121762 -0.434371 0.892466 + outer loop + vertex 361.296 116.487 382.123 + vertex 351.871 117.601 383.951 + vertex 352.281 113.746 382.019 + endloop + endfacet + facet normal 0.145525 -0.428087 0.891944 + outer loop + vertex 369.12 119.135 382.118 + vertex 360.782 120.356 384.064 + vertex 361.296 116.487 382.123 + endloop + endfacet + facet normal 0.169629 -0.417298 0.892798 + outer loop + vertex 375.638 121.684 382.071 + vertex 369.12 119.135 382.118 + vertex 376.363 117.837 380.135 + endloop + endfacet + facet normal 0.191291 -0.406289 0.893497 + outer loop + vertex 381.478 120.329 380.173 + vertex 376.363 117.837 380.135 + vertex 382.309 116.449 378.231 + endloop + endfacet + facet normal 0.211322 -0.400947 0.891395 + outer loop + vertex 385.991 118.855 378.44 + vertex 381.478 120.329 380.173 + vertex 382.309 116.449 378.231 + endloop + endfacet + facet normal 0.165551 -0.422025 0.891341 + outer loop + vertex 377.06 114.015 378.221 + vertex 369.757 115.282 380.178 + vertex 370.388 111.455 378.248 + endloop + endfacet + facet normal 0.140983 -0.432003 0.890784 + outer loop + vertex 370.388 111.455 378.248 + vertex 361.797 112.634 380.18 + vertex 362.311 108.803 378.24 + endloop + endfacet + facet normal 0.119665 -0.439329 0.89032 + outer loop + vertex 362.311 108.803 378.24 + vertex 352.671 109.911 380.083 + vertex 353.061 106.092 378.146 + endloop + endfacet + facet normal 0.101664 -0.439953 0.892248 + outer loop + vertex 353.061 106.092 378.146 + vertex 341.744 107.134 379.949 + vertex 343.958 103.47 377.891 + endloop + endfacet + facet normal 0.0875792 -0.447259 0.890107 + outer loop + vertex 343.958 103.47 377.891 + vertex 341.744 107.134 379.949 + vertex 328.695 102.571 378.94 + endloop + endfacet + facet normal 0.0800068 -0.445683 0.891608 + outer loop + vertex 328.215 110.168 382.781 + vertex 307.822 105.709 382.382 + vertex 328.695 102.571 378.94 + endloop + endfacet + facet normal 0.0725345 -0.442311 0.893924 + outer loop + vertex 307.822 105.709 382.382 + vertex 287.758 109.671 385.97 + vertex 288.008 102.029 382.169 + endloop + endfacet + facet normal 0.0665479 -0.442977 0.89406 + outer loop + vertex 288.008 102.029 382.169 + vertex 268.633 106.751 385.951 + vertex 268.827 99.0648 382.128 + endloop + endfacet + facet normal 0.0626383 -0.45066 0.890496 + outer loop + vertex 269.089 91.3578 378.211 + vertex 249.953 96.5269 382.173 + vertex 250.151 88.7784 378.238 + endloop + endfacet + facet normal 0.0616972 -0.443214 0.89429 + outer loop + vertex 268.633 106.751 385.951 + vertex 249.818 104.255 386.012 + vertex 268.827 99.0648 382.128 + endloop + endfacet + facet normal 0.0567298 -0.437354 0.897498 + outer loop + vertex 249.818 104.255 386.012 + vertex 230.689 109.679 389.864 + vertex 230.996 101.928 386.067 + endloop + endfacet + facet normal 0.0526949 -0.43758 0.897634 + outer loop + vertex 230.689 109.679 389.864 + vertex 211.755 107.435 389.881 + vertex 230.996 101.928 386.067 + endloop + endfacet + facet normal 0.0480291 -0.433218 0.900008 + outer loop + vertex 211.755 107.435 389.881 + vertex 192.194 113.404 393.799 + vertex 192.705 105.3 389.871 + endloop + endfacet + facet normal 0.043548 -0.433473 0.900114 + outer loop + vertex 192.705 105.3 389.871 + vertex 173.113 111.455 393.782 + vertex 173.595 103.352 389.857 + endloop + endfacet + facet normal 0.0388557 -0.433629 0.900253 + outer loop + vertex 173.595 103.352 389.857 + vertex 154 109.73 393.775 + vertex 154.463 101.621 389.849 + endloop + endfacet + facet normal 0.034032 -0.433913 0.900312 + outer loop + vertex 154.463 101.621 389.849 + vertex 134.862 108.225 393.772 + vertex 135.316 100.121 389.849 + endloop + endfacet + facet normal 0.0291561 -0.434057 0.900413 + outer loop + vertex 135.316 100.121 389.849 + vertex 115.687 106.943 393.774 + vertex 116.134 98.8343 389.851 + endloop + endfacet + facet normal 0.0241986 -0.434323 0.900432 + outer loop + vertex 116.134 98.8343 389.851 + vertex 96.4642 105.88 393.778 + vertex 96.8945 97.7724 389.855 + endloop + endfacet + facet normal 0.019325 -0.434503 0.900463 + outer loop + vertex 96.8945 97.7724 389.855 + vertex 77.1908 105.034 393.782 + vertex 77.5919 96.92 389.858 + endloop + endfacet + facet normal 0.0147554 -0.434338 0.900629 + outer loop + vertex 77.5919 96.92 389.858 + vertex 57.9037 104.394 393.785 + vertex 58.2649 96.2576 389.856 + endloop + endfacet + facet normal 0.0101753 -0.434643 0.900545 + outer loop + vertex 58.2649 96.2576 389.856 + vertex 38.6376 103.927 393.779 + vertex 38.9587 95.8002 389.853 + endloop + endfacet + facet normal 0.00606324 -0.434725 0.900543 + outer loop + vertex 38.9587 95.8002 389.853 + vertex 19.4131 103.645 393.772 + vertex 19.7023 95.5229 389.849 + endloop + endfacet + facet normal 0.00211429 -0.434656 0.900594 + outer loop + vertex 19.7023 95.5229 389.849 + vertex 0.194862 103.548 393.767 + vertex 0.468963 95.4229 389.846 + endloop + endfacet + facet normal -0.00184627 -0.434664 0.900591 + outer loop + vertex 0.468963 95.4229 389.846 + vertex -19.0463 103.629 393.766 + vertex -18.7849 95.5066 389.846 + endloop + endfacet + facet normal -0.00585082 -0.434619 0.900596 + outer loop + vertex -18.7849 95.5066 389.846 + vertex -38.3123 103.897 393.769 + vertex -38.0802 95.7715 389.849 + endloop + endfacet + facet normal -0.0100167 -0.434698 0.900521 + outer loop + vertex -38.0802 95.7715 389.849 + vertex -57.5812 104.346 393.771 + vertex -57.4016 96.2251 389.853 + endloop + endfacet + facet normal -0.0144399 -0.434531 0.900541 + outer loop + vertex -57.4016 96.2251 389.853 + vertex -76.8451 105.006 393.778 + vertex -76.7175 96.8696 389.854 + endloop + endfacet + facet normal -0.0191052 -0.43417 0.900628 + outer loop + vertex -76.7175 96.8696 389.854 + vertex -96.1115 105.872 393.783 + vertex -96.0211 97.7159 389.853 + endloop + endfacet + facet normal -0.0241032 -0.434172 0.900507 + outer loop + vertex -96.0211 97.7159 389.853 + vertex -115.416 106.935 393.779 + vertex -115.338 98.7882 389.853 + endloop + endfacet + facet normal -0.0291079 -0.434069 0.900409 + outer loop + vertex -115.338 98.7882 389.853 + vertex -134.766 108.239 393.781 + vertex -134.677 100.091 389.856 + endloop + endfacet + facet normal -0.0338739 -0.433758 0.900393 + outer loop + vertex -134.677 100.091 389.856 + vertex -154.1 109.76 393.783 + vertex -153.987 101.601 389.857 + endloop + endfacet + facet normal -0.0387551 -0.433783 0.900184 + outer loop + vertex -153.987 101.601 389.857 + vertex -173.302 111.473 393.782 + vertex -173.191 103.315 389.856 + endloop + endfacet + facet normal -0.0438105 -0.438125 0.897846 + outer loop + vertex -173.32 95.5578 386.064 + vertex -192.258 105.196 389.844 + vertex -192.414 97.4417 386.052 + endloop + endfacet + facet normal -0.0433908 -0.433751 0.899987 + outer loop + vertex -173.302 111.473 393.782 + vertex -192.333 113.354 393.771 + vertex -173.191 103.315 389.856 + endloop + endfacet + facet normal -0.0478305 -0.433152 0.900051 + outer loop + vertex -192.258 105.196 389.844 + vertex -211.241 115.439 393.764 + vertex -211.218 107.262 389.83 + endloop + endfacet + facet normal -0.0477074 -0.430283 0.901432 + outer loop + vertex -192.353 122.286 398.033 + vertex -211.173 124.351 398.023 + vertex -192.333 113.354 393.771 + endloop + endfacet + facet normal -0.0519927 -0.430048 0.901308 + outer loop + vertex -211.241 115.439 393.764 + vertex -229.961 126.64 398.028 + vertex -230.108 117.738 393.772 + endloop + endfacet + facet normal -0.0519836 -0.428741 0.90193 + outer loop + vertex -210.42 133.896 402.604 + vertex -229.041 136.176 402.615 + vertex -211.173 124.351 398.023 + endloop + endfacet + facet normal -0.0520608 -0.429371 0.901627 + outer loop + vertex -210.42 133.896 402.604 + vertex -226.566 145.484 407.19 + vertex -229.041 136.176 402.615 + endloop + endfacet + facet normal -0.05619 -0.428892 0.901606 + outer loop + vertex -229.041 136.176 402.615 + vertex -245.377 147.988 407.215 + vertex -247.727 138.683 402.642 + endloop + endfacet + facet normal -0.0598242 -0.427868 0.901859 + outer loop + vertex -247.727 138.683 402.642 + vertex -263.764 150.639 407.251 + vertex -266.39 141.381 402.685 + endloop + endfacet + facet normal -0.0562221 -0.429892 0.901128 + outer loop + vertex -229.961 126.64 398.028 + vertex -248.737 129.182 398.07 + vertex -230.108 117.738 393.772 + endloop + endfacet + facet normal -0.0523609 -0.433064 0.899841 + outer loop + vertex -211.241 115.439 393.764 + vertex -230.108 117.738 393.772 + vertex -211.218 107.262 389.83 + endloop + endfacet + facet normal -0.0483524 -0.437959 0.897694 + outer loop + vertex -192.258 105.196 389.844 + vertex -211.218 107.262 389.83 + vertex -192.414 97.4417 386.052 + endloop + endfacet + facet normal -0.0444108 -0.44423 0.894811 + outer loop + vertex -173.32 95.5578 386.064 + vertex -192.414 97.4417 386.052 + vertex -173.625 87.8534 382.224 + endloop + endfacet + facet normal -0.0396053 -0.444473 0.894916 + outer loop + vertex -154.374 86.1486 382.23 + vertex -173.32 95.5578 386.064 + vertex -173.625 87.8534 382.224 + endloop + endfacet + facet normal -0.0347393 -0.44459 0.89506 + outer loop + vertex -135.039 84.6365 382.229 + vertex -154.1 93.8564 386.069 + vertex -154.374 86.1486 382.23 + endloop + endfacet + facet normal -0.0296716 -0.444709 0.895184 + outer loop + vertex -115.695 83.3389 382.225 + vertex -134.791 92.3475 386.068 + vertex -135.039 84.6365 382.229 + endloop + endfacet + facet normal -0.0247731 -0.445196 0.895091 + outer loop + vertex -96.3884 82.2621 382.224 + vertex -115.465 91.0469 386.066 + vertex -115.695 83.3389 382.225 + endloop + endfacet + facet normal -0.0196703 -0.445196 0.895217 + outer loop + vertex -77.1037 81.4076 382.223 + vertex -96.1663 89.9736 386.064 + vertex -96.3884 82.2621 382.224 + endloop + endfacet + facet normal -0.0147366 -0.445317 0.895252 + outer loop + vertex -57.7919 80.7677 382.223 + vertex -76.8738 89.1215 386.064 + vertex -77.1037 81.4076 382.223 + endloop + endfacet + facet normal -0.0102822 -0.445568 0.895189 + outer loop + vertex -38.4371 80.3234 382.224 + vertex -57.552 88.482 386.065 + vertex -57.7919 80.7677 382.223 + endloop + endfacet + facet normal -0.00601073 -0.445544 0.89524 + outer loop + vertex -19.0616 80.0651 382.225 + vertex -38.1948 88.0385 386.065 + vertex -38.4371 80.3234 382.224 + endloop + endfacet + facet normal -0.00204654 -0.445609 0.895225 + outer loop + vertex 0.29989 79.9798 382.227 + vertex -18.8433 87.7794 386.066 + vertex -19.0616 80.0651 382.225 + endloop + endfacet + facet normal 0.00201805 -0.445404 0.895328 + outer loop + vertex 19.6347 80.0699 382.228 + vertex 0.475082 87.6952 386.065 + vertex 0.29989 79.9798 382.227 + endloop + endfacet + facet normal 0.00619933 -0.445357 0.895332 + outer loop + vertex 38.9563 80.3367 382.227 + vertex 19.7602 87.7839 386.065 + vertex 19.6347 80.0699 382.228 + endloop + endfacet + facet normal 0.0103484 -0.44548 0.895232 + outer loop + vertex 58.2882 80.7855 382.227 + vertex 39.0449 88.053 386.066 + vertex 38.9563 80.3367 382.227 + endloop + endfacet + facet normal 0.0150231 -0.445139 0.895336 + outer loop + vertex 77.6398 81.4354 382.226 + vertex 58.3652 88.5115 386.067 + vertex 58.2882 80.7855 382.227 + endloop + endfacet + facet normal 0.0198188 -0.44521 0.895207 + outer loop + vertex 96.977 82.2919 382.223 + vertex 77.7138 89.1626 386.067 + vertex 77.6398 81.4354 382.226 + endloop + endfacet + facet normal 0.024816 -0.445032 0.895171 + outer loop + vertex 116.262 83.3638 382.222 + vertex 97.0403 90.023 386.065 + vertex 96.977 82.2919 382.223 + endloop + endfacet + facet normal 0.0297712 -0.445098 0.894987 + outer loop + vertex 135.48 84.6482 382.221 + vertex 116.31 91.0923 386.064 + vertex 116.262 83.3638 382.222 + endloop + endfacet + facet normal 0.0348243 -0.444687 0.895009 + outer loop + vertex 154.651 86.15 382.221 + vertex 135.512 92.3811 386.062 + vertex 135.48 84.6482 382.221 + endloop + endfacet + facet normal 0.0396712 -0.444491 0.894905 + outer loop + vertex 173.8 87.8662 382.225 + vertex 154.673 93.8847 386.062 + vertex 154.651 86.15 382.221 + endloop + endfacet + facet normal 0.0444072 -0.444199 0.894827 + outer loop + vertex 192.944 89.7975 382.234 + vertex 173.819 95.6081 386.067 + vertex 173.8 87.8662 382.225 + endloop + endfacet + facet normal 0.0492109 -0.443877 0.894735 + outer loop + vertex 212.057 91.9232 382.237 + vertex 192.954 97.5478 386.078 + vertex 192.944 89.7975 382.234 + endloop + endfacet + facet normal 0.0533478 -0.443827 0.894523 + outer loop + vertex 231.074 94.1772 382.221 + vertex 212.035 99.6767 386.085 + vertex 212.057 91.9232 382.237 + endloop + endfacet + facet normal 0.05837 -0.450863 0.890682 + outer loop + vertex 249.953 96.5269 382.173 + vertex 231.074 94.1772 382.221 + vertex 250.151 88.7784 378.238 + endloop + endfacet + facet normal 0.0637671 -0.458992 0.886149 + outer loop + vertex 269.089 91.3578 378.211 + vertex 250.151 88.7784 378.238 + vertex 269.621 83.9218 374.322 + endloop + endfacet + facet normal 0.05955 -0.459294 0.886286 + outer loop + vertex 250.643 81.3234 374.34 + vertex 231.196 86.3944 378.274 + vertex 231.634 78.9121 374.367 + endloop + endfacet + facet normal 0.0553018 -0.459202 0.886609 + outer loop + vertex 231.634 78.9121 374.367 + vertex 212.133 84.1368 378.29 + vertex 212.543 76.6339 374.378 + endloop + endfacet + facet normal 0.0506837 -0.459926 0.886509 + outer loop + vertex 212.543 76.6339 374.378 + vertex 193.003 82.0128 378.286 + vertex 193.425 74.5251 374.377 + endloop + endfacet + facet normal 0.0459432 -0.460268 0.88659 + outer loop + vertex 193.425 74.5251 374.377 + vertex 173.871 80.09 378.279 + vertex 174.295 72.61 374.374 + endloop + endfacet + facet normal 0.0410245 -0.460407 0.88676 + outer loop + vertex 174.295 72.61 374.374 + vertex 154.736 78.3884 378.279 + vertex 155.151 70.8985 374.371 + endloop + endfacet + facet normal 0.0359973 -0.46051 0.886924 + outer loop + vertex 155.151 70.8985 374.371 + vertex 135.574 76.892 378.278 + vertex 135.993 69.391 374.366 + endloop + endfacet + facet normal 0.0307826 -0.46123 0.886746 + outer loop + vertex 135.993 69.391 374.366 + vertex 116.354 75.5991 378.277 + vertex 116.783 68.1128 374.368 + endloop + endfacet + facet normal 0.025876 -0.461023 0.887011 + outer loop + vertex 116.783 68.1128 374.368 + vertex 97.0681 74.53 378.279 + vertex 97.4994 67.0239 374.365 + endloop + endfacet + facet normal 0.0205867 -0.461147 0.887085 + outer loop + vertex 97.4994 67.0239 374.365 + vertex 77.7271 73.677 378.282 + vertex 78.1398 66.1653 374.368 + endloop + endfacet + facet normal 0.0156226 -0.461173 0.887173 + outer loop + vertex 78.1398 66.1653 374.368 + vertex 58.3647 73.0291 378.284 + vertex 58.7383 65.5086 374.368 + endloop + endfacet + facet normal 0.0108677 -0.461261 0.887198 + outer loop + vertex 58.7383 65.5086 374.368 + vertex 39.0007 72.5775 378.285 + vertex 39.3226 65.0546 374.37 + endloop + endfacet + facet normal 0.00641059 -0.461477 0.887129 + outer loop + vertex 39.3226 65.0546 374.37 + vertex 19.6343 72.304 378.283 + vertex 19.9257 64.7855 374.37 + endloop + endfacet + facet normal 0.00219691 -0.461218 0.887284 + outer loop + vertex 19.9257 64.7855 374.37 + vertex 0.268516 72.2183 378.282 + vertex 0.554547 64.6961 374.371 + endloop + endfacet + facet normal -0.00189265 -0.461073 0.88736 + outer loop + vertex 0.554547 64.6961 374.371 + vertex -19.1033 72.3005 378.281 + vertex -18.7895 64.7721 374.37 + endloop + endfacet + facet normal -0.00618157 -0.4611 0.887327 + outer loop + vertex -18.7895 64.7721 374.37 + vertex -38.4657 72.5594 378.279 + vertex -38.1191 65.0286 374.368 + endloop + endfacet + facet normal -0.0105586 -0.461107 0.887281 + outer loop + vertex -38.1191 65.0286 374.368 + vertex -57.806 73.0049 378.279 + vertex -57.4609 65.4659 374.365 + endloop + endfacet + facet normal -0.0152811 -0.461077 0.887229 + outer loop + vertex -57.4609 65.4659 374.365 + vertex -77.1227 73.6506 378.28 + vertex -76.8283 66.1148 374.369 + endloop + endfacet + facet normal -0.0202498 -0.461269 0.887029 + outer loop + vertex -76.8283 66.1148 374.369 + vertex -96.4459 74.4992 378.281 + vertex -96.2021 66.9622 374.367 + endloop + endfacet + facet normal -0.0254417 -0.460944 0.887064 + outer loop + vertex -96.2021 66.9622 374.367 + vertex -115.794 75.5818 378.284 + vertex -115.615 68.043 374.372 + endloop + endfacet + facet normal -0.0307671 -0.461066 0.886832 + outer loop + vertex -115.615 68.043 374.372 + vertex -135.188 76.8769 378.286 + vertex -135.055 69.348 374.376 + endloop + endfacet + facet normal -0.0357062 -0.46049 0.886947 + outer loop + vertex -135.055 69.348 374.376 + vertex -154.568 78.3944 378.287 + vertex -154.486 70.8478 374.373 + endloop + endfacet + facet normal -0.0409551 -0.460491 0.886719 + outer loop + vertex -154.486 70.8478 374.373 + vertex -173.869 80.0976 378.281 + vertex -173.821 72.5645 374.371 + endloop + endfacet + facet normal -0.0464337 -0.468053 0.88248 + outer loop + vertex -173.559 65.7775 370.781 + vertex -193.024 74.4516 374.358 + vertex -192.746 67.6574 370.769 + endloop + endfacet + facet normal -0.0471238 -0.475122 0.878657 + outer loop + vertex -173.559 65.7775 370.781 + vertex -192.746 67.6574 370.769 + vertex -173.7 60.3205 367.823 + endloop + endfacet + facet normal -0.0514774 -0.468098 0.882176 + outer loop + vertex -193.024 74.4516 374.358 + vertex -212.091 76.525 374.345 + vertex -192.746 67.6574 370.769 + endloop + endfacet + facet normal -0.0512617 -0.467715 0.882392 + outer loop + vertex -192.746 67.6574 370.769 + vertex -212.091 76.525 374.345 + vertex -211.788 69.7283 370.76 + endloop + endfacet + facet normal -0.0520256 -0.474755 0.878579 + outer loop + vertex -192.746 67.6574 370.769 + vertex -211.788 69.7283 370.76 + vertex -192.91 62.2123 367.817 + endloop + endfacet + facet normal -0.0559991 -0.467761 0.882079 + outer loop + vertex -212.091 76.525 374.345 + vertex -231.012 78.8133 374.358 + vertex -211.788 69.7283 370.76 + endloop + endfacet + facet normal -0.0557448 -0.467322 0.882328 + outer loop + vertex -211.788 69.7283 370.76 + vertex -231.012 78.8133 374.358 + vertex -230.7 72.0155 370.777 + endloop + endfacet + facet normal -0.0566155 -0.474493 0.878437 + outer loop + vertex -211.788 69.7283 370.76 + vertex -230.7 72.0155 370.777 + vertex -211.914 64.2889 367.814 + endloop + endfacet + facet normal -0.0601473 -0.46736 0.882019 + outer loop + vertex -231.012 78.8133 374.358 + vertex -249.815 81.3209 374.404 + vertex -230.7 72.0155 370.777 + endloop + endfacet + facet normal -0.0600722 -0.467234 0.882091 + outer loop + vertex -230.7 72.0155 370.777 + vertex -249.815 81.3209 374.404 + vertex -249.602 74.5292 370.821 + endloop + endfacet + facet normal -0.0610569 -0.474568 0.878098 + outer loop + vertex -230.7 72.0155 370.777 + vertex -249.602 74.5292 370.821 + vertex -230.918 66.5894 367.829 + endloop + endfacet + facet normal -0.0646354 -0.467213 0.881779 + outer loop + vertex -249.815 81.3209 374.404 + vertex -268.667 83.9997 374.442 + vertex -249.602 74.5292 370.821 + endloop + endfacet + facet normal -0.0648553 -0.467576 0.881571 + outer loop + vertex -249.602 74.5292 370.821 + vertex -268.667 83.9997 374.442 + vertex -268.674 77.25 370.861 + endloop + endfacet + facet normal -0.0658777 -0.474685 0.877687 + outer loop + vertex -249.602 74.5292 370.821 + vertex -268.674 77.25 370.861 + vertex -250.269 69.1197 367.845 + endloop + endfacet + facet normal -0.0701239 -0.467404 0.881258 + outer loop + vertex -268.667 83.9997 374.442 + vertex -287.924 86.784 374.386 + vertex -268.674 77.25 370.861 + endloop + endfacet + facet normal -0.0700714 -0.467317 0.881309 + outer loop + vertex -268.674 77.25 370.861 + vertex -287.924 86.784 374.386 + vertex -288.1 80.0867 370.821 + endloop + endfacet + facet normal -0.0709781 -0.473575 0.877889 + outer loop + vertex -268.674 77.25 370.861 + vertex -288.1 80.0867 370.821 + vertex -269.842 71.9462 367.906 + endloop + endfacet + facet normal -0.0760272 -0.466989 0.880988 + outer loop + vertex -287.924 86.784 374.386 + vertex -307.964 89.6472 374.174 + vertex -288.1 80.0867 370.821 + endloop + endfacet + facet normal -0.0755716 -0.466203 0.881444 + outer loop + vertex -288.1 80.0867 370.821 + vertex -307.964 89.6472 374.174 + vertex -308.104 82.9812 370.637 + endloop + endfacet + facet normal -0.0764386 -0.47241 0.878058 + outer loop + vertex -288.1 80.0867 370.821 + vertex -308.104 82.9812 370.637 + vertex -289.242 74.8139 367.884 + endloop + endfacet + facet normal -0.081134 -0.465906 0.881106 + outer loop + vertex -307.964 89.6472 374.174 + vertex -328.811 92.5566 373.793 + vertex -308.104 82.9812 370.637 + endloop + endfacet + facet normal -0.0806507 -0.465029 0.881614 + outer loop + vertex -308.104 82.9812 370.637 + vertex -328.811 92.5566 373.793 + vertex -328.509 85.751 370.231 + endloop + endfacet + facet normal -0.0866522 -0.465003 0.881058 + outer loop + vertex -328.509 85.751 370.231 + vertex -328.811 92.5566 373.793 + vertex -342.437 93.2031 372.794 + endloop + endfacet + facet normal -0.0864782 -0.464733 0.881218 + outer loop + vertex -344.285 90.1782 371.018 + vertex -328.509 85.751 370.231 + vertex -342.437 93.2031 372.794 + endloop + endfacet + facet normal -0.0985432 -0.458526 0.8832 + outer loop + vertex -342.437 93.2031 372.794 + vertex -353.721 95.3309 372.64 + vertex -344.285 90.1782 371.018 + endloop + endfacet + facet normal -0.100338 -0.461296 0.881555 + outer loop + vertex -344.285 90.1782 371.018 + vertex -353.721 95.3309 372.64 + vertex -353.694 91.6531 370.718 + endloop + endfacet + facet normal -0.11862 -0.460468 0.879715 + outer loop + vertex -353.721 95.3309 372.64 + vertex -363.194 97.4927 372.494 + vertex -353.694 91.6531 370.718 + endloop + endfacet + facet normal -0.115706 -0.447214 0.886912 + outer loop + vertex -353.721 95.3309 372.64 + vertex -362.731 101.253 374.451 + vertex -363.194 97.4927 372.494 + endloop + endfacet + facet normal -0.14049 -0.443313 0.885289 + outer loop + vertex -362.731 101.253 374.451 + vertex -371.269 103.676 374.309 + vertex -363.194 97.4927 372.494 + endloop + endfacet + facet normal -0.134922 -0.437188 0.889192 + outer loop + vertex -363.194 97.4927 372.494 + vertex -371.269 103.676 374.309 + vertex -371.976 99.9051 372.348 + endloop + endfacet + facet normal -0.138623 -0.451117 0.881633 + outer loop + vertex -363.194 97.4927 372.494 + vertex -371.976 99.9051 372.348 + vertex -363.552 93.8616 370.58 + endloop + endfacet + facet normal -0.132305 -0.443693 0.886359 + outer loop + vertex -363.552 93.8616 370.58 + vertex -371.976 99.9051 372.348 + vertex -372.677 96.3684 370.473 + endloop + endfacet + facet normal -0.156121 -0.438333 0.88515 + outer loop + vertex -371.976 99.9051 372.348 + vertex -380.327 102.48 372.15 + vertex -372.677 96.3684 370.473 + endloop + endfacet + facet normal -0.152329 -0.425507 0.892042 + outer loop + vertex -371.976 99.9051 372.348 + vertex -379.339 106.192 374.09 + vertex -380.327 102.48 372.15 + endloop + endfacet + facet normal -0.158856 -0.431971 0.887787 + outer loop + vertex -371.269 103.676 374.309 + vertex -379.339 106.192 374.09 + vertex -371.976 99.9051 372.348 + endloop + endfacet + facet normal -0.137739 -0.433305 0.89066 + outer loop + vertex -362.731 101.253 374.451 + vertex -370.416 107.516 376.309 + vertex -371.269 103.676 374.309 + endloop + endfacet + facet normal -0.16169 -0.427377 0.889497 + outer loop + vertex -370.416 107.516 376.309 + vertex -378.192 110.052 376.114 + vertex -371.269 103.676 374.309 + endloop + endfacet + facet normal -0.159503 -0.420387 0.893215 + outer loop + vertex -370.416 107.516 376.309 + vertex -376.627 113.733 378.126 + vertex -378.192 110.052 376.114 + endloop + endfacet + facet normal -0.163721 -0.423892 0.890792 + outer loop + vertex -369.537 111.379 378.309 + vertex -376.627 113.733 378.126 + vertex -370.416 107.516 376.309 + endloop + endfacet + facet normal -0.139831 -0.429934 0.891966 + outer loop + vertex -362.122 105.037 376.414 + vertex -369.537 111.379 378.309 + vertex -370.416 107.516 376.309 + endloop + endfacet + facet normal -0.143025 -0.433064 0.889944 + outer loop + vertex -361.478 108.838 378.367 + vertex -369.537 111.379 378.309 + vertex -362.122 105.037 376.414 + endloop + endfacet + facet normal -0.118448 -0.437874 0.8912 + outer loop + vertex -352.932 102.753 376.514 + vertex -361.478 108.838 378.367 + vertex -362.122 105.037 376.414 + endloop + endfacet + facet normal -0.120631 -0.446868 0.886429 + outer loop + vertex -352.932 102.753 376.514 + vertex -362.122 105.037 376.414 + vertex -353.404 99.0423 374.579 + endloop + endfacet + facet normal -0.10098 -0.449858 0.887373 + outer loop + vertex -344.182 97.4623 374.827 + vertex -352.932 102.753 376.514 + vertex -353.404 99.0423 374.579 + endloop + endfacet + facet normal -0.102966 -0.462511 0.880615 + outer loop + vertex -344.182 97.4623 374.827 + vertex -353.404 99.0423 374.579 + vertex -342.437 93.2031 372.794 + endloop + endfacet + facet normal -0.0994817 -0.44777 0.888598 + outer loop + vertex -341.911 100.524 376.624 + vertex -352.932 102.753 376.514 + vertex -344.182 97.4623 374.827 + endloop + endfacet + facet normal -0.0859836 -0.456116 0.885757 + outer loop + vertex -344.182 97.4623 374.827 + vertex -328.811 92.5566 373.793 + vertex -341.911 100.524 376.624 + endloop + endfacet + facet normal -0.0863088 -0.456558 0.885497 + outer loop + vertex -328.811 92.5566 373.793 + vertex -328.447 99.915 377.623 + vertex -341.911 100.524 376.624 + endloop + endfacet + facet normal -0.0862501 -0.448591 0.889565 + outer loop + vertex -343.39 104.899 378.687 + vertex -341.911 100.524 376.624 + vertex -328.447 99.915 377.623 + endloop + endfacet + facet normal -0.0856782 -0.447054 0.890394 + outer loop + vertex -343.39 104.899 378.687 + vertex -328.447 99.915 377.623 + vertex -341.161 108.054 380.486 + endloop + endfacet + facet normal -0.0999406 -0.438543 0.893136 + outer loop + vertex -341.161 108.054 380.486 + vertex -351.95 110.258 380.361 + vertex -343.39 104.899 378.687 + endloop + endfacet + facet normal -0.102573 -0.442105 0.891079 + outer loop + vertex -343.39 104.899 378.687 + vertex -351.95 110.258 380.361 + vertex -352.401 106.499 378.444 + endloop + endfacet + facet normal -0.122239 -0.43921 0.89003 + outer loop + vertex -351.95 110.258 380.361 + vertex -360.939 112.623 380.293 + vertex -352.401 106.499 378.444 + endloop + endfacet + facet normal -0.119962 -0.436527 0.891658 + outer loop + vertex -352.401 106.499 378.444 + vertex -360.939 112.623 380.293 + vertex -361.478 108.838 378.367 + endloop + endfacet + facet normal -0.144921 -0.432166 0.890073 + outer loop + vertex -360.939 112.623 380.293 + vertex -368.84 115.229 380.272 + vertex -361.478 108.838 378.367 + endloop + endfacet + facet normal -0.143535 -0.427945 0.892334 + outer loop + vertex -360.939 112.623 380.293 + vertex -368.289 119.031 382.184 + vertex -368.84 115.229 380.272 + endloop + endfacet + facet normal -0.168254 -0.4233 0.890229 + outer loop + vertex -368.289 119.031 382.184 + vertex -374.799 121.287 382.027 + vertex -368.84 115.229 380.272 + endloop + endfacet + facet normal -0.165874 -0.421356 0.891597 + outer loop + vertex -368.84 115.229 380.272 + vertex -374.799 121.287 382.027 + vertex -375.588 117.59 380.132 + endloop + endfacet + facet normal -0.166695 -0.423779 0.890294 + outer loop + vertex -368.84 115.229 380.272 + vertex -375.588 117.59 380.132 + vertex -369.537 111.379 378.309 + endloop + endfacet + facet normal -0.185806 -0.416301 0.890039 + outer loop + vertex -374.799 121.287 382.027 + vertex -379.413 122.438 381.602 + vertex -375.588 117.59 380.132 + endloop + endfacet + facet normal -0.166873 -0.41916 0.892445 + outer loop + vertex -368.289 119.031 382.184 + vertex -374.346 125.122 383.912 + vertex -374.799 121.287 382.027 + endloop + endfacet + facet normal -0.190432 -0.415012 0.889663 + outer loop + vertex -374.346 125.122 383.912 + vertex -379.393 126.168 383.32 + vertex -374.799 121.287 382.027 + endloop + endfacet + facet normal -0.170427 -0.422109 0.890381 + outer loop + vertex -367.783 122.822 384.078 + vertex -374.346 125.122 383.912 + vertex -368.289 119.031 382.184 + endloop + endfacet + facet normal -0.144642 -0.426728 0.892738 + outer loop + vertex -360.45 116.4 382.196 + vertex -367.783 122.822 384.078 + vertex -368.289 119.031 382.184 + endloop + endfacet + facet normal -0.147064 -0.429051 0.891228 + outer loop + vertex -359.987 120.184 384.094 + vertex -367.783 122.822 384.078 + vertex -360.45 116.4 382.196 + endloop + endfacet + facet normal -0.12212 -0.433031 0.893068 + outer loop + vertex -351.537 114.029 382.266 + vertex -359.987 120.184 384.094 + vertex -360.45 116.4 382.196 + endloop + endfacet + facet normal -0.123079 -0.436693 0.891151 + outer loop + vertex -351.537 114.029 382.266 + vertex -360.45 116.4 382.196 + vertex -351.95 110.258 380.361 + endloop + endfacet + facet normal -0.123172 -0.434256 0.892328 + outer loop + vertex -351.142 117.844 384.176 + vertex -359.987 120.184 384.094 + vertex -351.537 114.029 382.266 + endloop + endfacet + facet normal -0.103002 -0.436962 0.893563 + outer loop + vertex -342.663 112.487 382.535 + vertex -351.142 117.844 384.176 + vertex -351.537 114.029 382.266 + endloop + endfacet + facet normal -0.104459 -0.446171 0.888831 + outer loop + vertex -342.663 112.487 382.535 + vertex -351.537 114.029 382.266 + vertex -341.161 108.054 380.486 + endloop + endfacet + facet normal -0.0864283 -0.441931 0.892876 + outer loop + vertex -342.663 112.487 382.535 + vertex -341.161 108.054 380.486 + vertex -327.934 107.56 381.521 + endloop + endfacet + facet normal -0.0858569 -0.440391 0.893691 + outer loop + vertex -342.663 112.487 382.535 + vertex -327.934 107.56 381.521 + vertex -340.49 115.736 384.344 + endloop + endfacet + facet normal -0.0860842 -0.440683 0.893526 + outer loop + vertex -327.934 107.56 381.521 + vertex -327.379 115.384 385.434 + vertex -340.49 115.736 384.344 + endloop + endfacet + facet normal -0.0861497 -0.435926 0.89585 + outer loop + vertex -342.011 120.284 386.411 + vertex -340.49 115.736 384.344 + vertex -327.379 115.384 385.434 + endloop + endfacet + facet normal -0.08597 -0.43544 0.896103 + outer loop + vertex -342.011 120.284 386.411 + vertex -327.379 115.384 385.434 + vertex -339.898 123.688 388.268 + endloop + endfacet + facet normal -0.0992676 -0.428311 0.898162 + outer loop + vertex -339.898 123.688 388.268 + vertex -350.465 125.734 388.076 + vertex -342.011 120.284 386.411 + endloop + endfacet + facet normal -0.102613 -0.432737 0.895661 + outer loop + vertex -342.011 120.284 386.411 + vertex -350.465 125.734 388.076 + vertex -350.776 121.736 386.108 + endloop + endfacet + facet normal -0.122364 -0.430508 0.894254 + outer loop + vertex -350.465 125.734 388.076 + vertex -359.189 127.997 387.972 + vertex -350.776 121.736 386.108 + endloop + endfacet + facet normal -0.122127 -0.430238 0.894416 + outer loop + vertex -350.776 121.736 386.108 + vertex -359.189 127.997 387.972 + vertex -359.559 124.029 386.012 + endloop + endfacet + facet normal -0.122566 -0.431959 0.893526 + outer loop + vertex -350.776 121.736 386.108 + vertex -359.559 124.029 386.012 + vertex -351.142 117.844 384.176 + endloop + endfacet + facet normal -0.100119 -0.434778 0.894955 + outer loop + vertex -340.49 115.736 384.344 + vertex -350.776 121.736 386.108 + vertex -351.142 117.844 384.176 + endloop + endfacet + facet normal -0.148197 -0.426698 0.89217 + outer loop + vertex -359.189 127.997 387.972 + vertex -366.848 130.609 387.948 + vertex -359.559 124.029 386.012 + endloop + endfacet + facet normal -0.147243 -0.425811 0.892751 + outer loop + vertex -359.559 124.029 386.012 + vertex -366.848 130.609 387.948 + vertex -367.28 126.65 385.989 + endloop + endfacet + facet normal -0.148029 -0.428139 0.891507 + outer loop + vertex -359.559 124.029 386.012 + vertex -367.28 126.65 385.989 + vertex -359.987 120.184 384.094 + endloop + endfacet + facet normal -0.174125 -0.421494 0.889957 + outer loop + vertex -366.848 130.609 387.948 + vertex -373.33 132.945 387.786 + vertex -367.28 126.65 385.989 + endloop + endfacet + facet normal -0.171798 -0.419637 0.891286 + outer loop + vertex -367.28 126.65 385.989 + vertex -373.33 132.945 387.786 + vertex -373.813 128.979 385.826 + endloop + endfacet + facet normal -0.172497 -0.421674 0.890189 + outer loop + vertex -367.28 126.65 385.989 + vertex -373.813 128.979 385.826 + vertex -367.783 122.822 384.078 + endloop + endfacet + facet normal -0.195914 -0.415253 0.888359 + outer loop + vertex -373.33 132.945 387.786 + vertex -378.368 134.199 387.262 + vertex -373.813 128.979 385.826 + endloop + endfacet + facet normal -0.173491 -0.419667 0.890944 + outer loop + vertex -366.848 130.609 387.948 + vertex -372.995 137.171 389.842 + vertex -373.33 132.945 387.786 + endloop + endfacet + facet normal -0.19849 -0.415985 0.887445 + outer loop + vertex -372.995 137.171 389.842 + vertex -377.997 138.376 389.288 + vertex -373.33 132.945 387.786 + endloop + endfacet + facet normal -0.174872 -0.420736 0.890169 + outer loop + vertex -366.474 134.722 389.966 + vertex -372.995 137.171 389.842 + vertex -366.848 130.609 387.948 + endloop + endfacet + facet normal -0.175082 -0.421313 0.889855 + outer loop + vertex -366.474 134.722 389.966 + vertex -372.573 141.446 391.949 + vertex -372.995 137.171 389.842 + endloop + endfacet + facet normal -0.201479 -0.416964 0.886311 + outer loop + vertex -372.573 141.446 391.949 + vertex -378.048 143.295 391.575 + vertex -372.995 137.171 389.842 + endloop + endfacet + facet normal -0.175699 -0.421772 0.889516 + outer loop + vertex -366.13 138.871 392.001 + vertex -372.573 141.446 391.949 + vertex -366.474 134.722 389.966 + endloop + endfacet + facet normal -0.148123 -0.42562 0.892697 + outer loop + vertex -358.868 132.093 389.974 + vertex -366.13 138.871 392.001 + vertex -366.474 134.722 389.966 + endloop + endfacet + facet normal -0.147942 -0.425097 0.892976 + outer loop + vertex -358.868 132.093 389.974 + vertex -366.474 134.722 389.966 + vertex -359.189 127.997 387.972 + endloop + endfacet + facet normal -0.146864 -0.424493 0.893441 + outer loop + vertex -358.567 136.231 391.99 + vertex -366.13 138.871 392.001 + vertex -358.868 132.093 389.974 + endloop + endfacet + facet normal -0.121433 -0.427498 0.895823 + outer loop + vertex -350.171 129.845 390.081 + vertex -358.567 136.231 391.99 + vertex -358.868 132.093 389.974 + endloop + endfacet + facet normal -0.121574 -0.428057 0.895537 + outer loop + vertex -350.171 129.845 390.081 + vertex -358.868 132.093 389.974 + vertex -350.465 125.734 388.076 + endloop + endfacet + facet normal -0.121384 -0.427442 0.895857 + outer loop + vertex -349.887 133.974 392.089 + vertex -358.567 136.231 391.99 + vertex -350.171 129.845 390.081 + endloop + endfacet + facet normal -0.147548 -0.426451 0.892395 + outer loop + vertex -358.567 136.231 391.99 + vertex -365.786 142.918 393.992 + vertex -366.13 138.871 392.001 + endloop + endfacet + facet normal -0.173655 -0.422777 0.88944 + outer loop + vertex -365.786 142.918 393.992 + vertex -372.068 145.502 393.994 + vertex -366.13 138.871 392.001 + endloop + endfacet + facet normal -0.174806 -0.425574 0.887879 + outer loop + vertex -365.786 142.918 393.992 + vertex -371.553 149.229 395.881 + vertex -372.068 145.502 393.994 + endloop + endfacet + facet normal -0.197138 -0.421177 0.885295 + outer loop + vertex -371.553 149.229 395.881 + vertex -376.28 151.191 395.762 + vertex -372.068 145.502 393.994 + endloop + endfacet + facet normal -0.169434 -0.42155 0.890836 + outer loop + vertex -365.431 146.854 395.922 + vertex -371.553 149.229 395.881 + vertex -365.786 142.918 393.992 + endloop + endfacet + facet normal -0.144914 -0.424075 0.893958 + outer loop + vertex -358.25 140.321 393.981 + vertex -365.786 142.918 393.992 + vertex -358.567 136.231 391.99 + endloop + endfacet + facet normal -0.177088 -0.425288 0.887564 + outer loop + vertex -366.13 138.871 392.001 + vertex -372.068 145.502 393.994 + vertex -372.573 141.446 391.949 + endloop + endfacet + facet normal -0.201028 -0.420811 0.884594 + outer loop + vertex -372.068 145.502 393.994 + vertex -376.997 147.379 393.766 + vertex -372.573 141.446 391.949 + endloop + endfacet + facet normal -0.147526 -0.424719 0.893224 + outer loop + vertex -359.189 127.997 387.972 + vertex -366.474 134.722 389.966 + vertex -366.848 130.609 387.948 + endloop + endfacet + facet normal -0.12181 -0.428321 0.895379 + outer loop + vertex -350.465 125.734 388.076 + vertex -358.868 132.093 389.974 + vertex -359.189 127.997 387.972 + endloop + endfacet + facet normal -0.0996529 -0.430399 0.897121 + outer loop + vertex -339.898 123.688 388.268 + vertex -350.171 129.845 390.081 + vertex -350.465 125.734 388.076 + endloop + endfacet + facet normal -0.102765 -0.434854 0.894618 + outer loop + vertex -341.435 128.411 390.387 + vertex -350.171 129.845 390.081 + vertex -339.898 123.688 388.268 + endloop + endfacet + facet normal -0.085556 -0.434917 0.896397 + outer loop + vertex -327.379 115.384 385.434 + vertex -326.828 123.367 389.36 + vertex -339.898 123.688 388.268 + endloop + endfacet + facet normal -0.0781707 -0.435595 0.896742 + outer loop + vertex -306.967 112.716 385.917 + vertex -326.828 123.367 389.36 + vertex -327.379 115.384 385.434 + endloop + endfacet + facet normal -0.0788815 -0.441576 0.89375 + outer loop + vertex -306.967 112.716 385.917 + vertex -327.379 115.384 385.434 + vertex -307.456 104.852 381.988 + endloop + endfacet + facet normal -0.0725896 -0.442103 0.894022 + outer loop + vertex -287.615 102.128 382.253 + vertex -306.967 112.716 385.917 + vertex -307.456 104.852 381.988 + endloop + endfacet + facet normal -0.0735241 -0.449265 0.890368 + outer loop + vertex -287.615 102.128 382.253 + vertex -307.456 104.852 381.988 + vertex -287.893 94.316 378.288 + endloop + endfacet + facet normal -0.067463 -0.449631 0.890663 + outer loop + vertex -268.71 91.5602 378.349 + vertex -287.615 102.128 382.253 + vertex -287.893 94.316 378.288 + endloop + endfacet + facet normal -0.0687072 -0.458394 0.88609 + outer loop + vertex -268.71 91.5602 378.349 + vertex -287.893 94.316 378.288 + vertex -268.667 83.9997 374.442 + endloop + endfacet + facet normal -0.0674926 -0.449675 0.890639 + outer loop + vertex -268.417 99.3525 382.306 + vertex -287.615 102.128 382.253 + vertex -268.71 91.5602 378.349 + endloop + endfacet + facet normal -0.062372 -0.449979 0.890858 + outer loop + vertex -249.874 88.8637 378.306 + vertex -268.417 99.3525 382.306 + vertex -268.71 91.5602 378.349 + endloop + endfacet + facet normal -0.0636664 -0.458946 0.88618 + outer loop + vertex -249.874 88.8637 378.306 + vertex -268.71 91.5602 378.349 + vertex -249.815 81.3209 374.404 + endloop + endfacet + facet normal -0.0623905 -0.450006 0.890843 + outer loop + vertex -249.542 96.6374 382.256 + vertex -268.417 99.3525 382.306 + vertex -249.874 88.8637 378.306 + endloop + endfacet + facet normal -0.057877 -0.450283 0.891008 + outer loop + vertex -231.04 86.3575 378.263 + vertex -249.542 96.6374 382.256 + vertex -249.874 88.8637 378.306 + endloop + endfacet + facet normal -0.0590606 -0.459099 0.88642 + outer loop + vertex -231.04 86.3575 378.263 + vertex -249.874 88.8637 378.306 + vertex -231.012 78.8133 374.358 + endloop + endfacet + facet normal -0.0582953 -0.450903 0.890667 + outer loop + vertex -230.702 94.1041 382.207 + vertex -249.542 96.6374 382.256 + vertex -231.04 86.3575 378.263 + endloop + endfacet + facet normal -0.0613333 -0.442725 0.894557 + outer loop + vertex -249.542 96.6374 382.256 + vertex -267.962 107.113 386.178 + vertex -268.417 99.3525 382.306 + endloop + endfacet + facet normal -0.0663923 -0.442342 0.894386 + outer loop + vertex -267.962 107.113 386.178 + vertex -287.147 109.945 386.154 + vertex -268.417 99.3525 382.306 + endloop + endfacet + facet normal -0.0654873 -0.436187 0.89747 + outer loop + vertex -267.962 107.113 386.178 + vertex -286.779 117.76 389.979 + vertex -287.147 109.945 386.154 + endloop + endfacet + facet normal -0.0715455 -0.435774 0.897208 + outer loop + vertex -286.779 117.76 389.979 + vertex -306.498 120.598 389.785 + vertex -287.147 109.945 386.154 + endloop + endfacet + facet normal -0.0716999 -0.436011 0.897081 + outer loop + vertex -287.147 109.945 386.154 + vertex -306.498 120.598 389.785 + vertex -306.967 112.716 385.917 + endloop + endfacet + facet normal -0.071009 -0.431916 0.899114 + outer loop + vertex -286.779 117.76 389.979 + vertex -306.196 128.628 393.667 + vertex -306.498 120.598 389.785 + endloop + endfacet + facet normal -0.0773457 -0.431518 0.898782 + outer loop + vertex -306.196 128.628 393.667 + vertex -326.338 131.398 393.263 + vertex -306.498 120.598 389.785 + endloop + endfacet + facet normal -0.0770101 -0.42889 0.900068 + outer loop + vertex -306.196 128.628 393.667 + vertex -325.999 139.655 397.227 + vertex -326.338 131.398 393.263 + endloop + endfacet + facet normal -0.0766936 -0.428405 0.900326 + outer loop + vertex -305.914 137.23 397.784 + vertex -325.999 139.655 397.227 + vertex -306.196 128.628 393.667 + endloop + endfacet + facet normal -0.0707687 -0.431553 0.899308 + outer loop + vertex -286.64 125.857 393.876 + vertex -306.196 128.628 393.667 + vertex -286.779 117.76 389.979 + endloop + endfacet + facet normal -0.0655183 -0.436233 0.897445 + outer loop + vertex -267.686 114.895 389.981 + vertex -286.779 117.76 389.979 + vertex -267.962 107.113 386.178 + endloop + endfacet + facet normal -0.061444 -0.442886 0.89447 + outer loop + vertex -249.108 104.359 386.109 + vertex -267.962 107.113 386.178 + vertex -249.542 96.6374 382.256 + endloop + endfacet + facet normal -0.0664565 -0.442437 0.894334 + outer loop + vertex -268.417 99.3525 382.306 + vertex -287.147 109.945 386.154 + vertex -287.615 102.128 382.253 + endloop + endfacet + facet normal -0.0737046 -0.449546 0.890211 + outer loop + vertex -287.893 94.316 378.288 + vertex -307.456 104.852 381.988 + vertex -307.791 97.0821 378.037 + endloop + endfacet + facet normal -0.0748809 -0.458427 0.885572 + outer loop + vertex -287.893 94.316 378.288 + vertex -307.791 97.0821 378.037 + vertex -287.924 86.784 374.386 + endloop + endfacet + facet normal -0.0796902 -0.449131 0.889905 + outer loop + vertex -307.456 104.852 381.988 + vertex -327.934 107.56 381.521 + vertex -307.791 97.0821 378.037 + endloop + endfacet + facet normal -0.0793961 -0.448655 0.890171 + outer loop + vertex -307.791 97.0821 378.037 + vertex -327.934 107.56 381.521 + vertex -328.447 99.915 377.623 + endloop + endfacet + facet normal -0.080587 -0.458057 0.885263 + outer loop + vertex -307.791 97.0821 378.037 + vertex -328.447 99.915 377.623 + vertex -307.964 89.6472 374.174 + endloop + endfacet + facet normal -0.0724957 -0.441959 0.894101 + outer loop + vertex -287.147 109.945 386.154 + vertex -306.967 112.716 385.917 + vertex -287.615 102.128 382.253 + endloop + endfacet + facet normal -0.0781052 -0.435491 0.896798 + outer loop + vertex -306.498 120.598 389.785 + vertex -326.828 123.367 389.36 + vertex -306.967 112.716 385.917 + endloop + endfacet + facet normal -0.103694 -0.440031 0.891975 + outer loop + vertex -342.011 120.284 386.411 + vertex -350.776 121.736 386.108 + vertex -340.49 115.736 384.344 + endloop + endfacet + facet normal -0.0787542 -0.441372 0.893862 + outer loop + vertex -307.456 104.852 381.988 + vertex -327.379 115.384 385.434 + vertex -327.934 107.56 381.521 + endloop + endfacet + facet normal -0.0996842 -0.432491 0.896111 + outer loop + vertex -340.49 115.736 384.344 + vertex -351.142 117.844 384.176 + vertex -342.663 112.487 382.535 + endloop + endfacet + facet normal -0.122579 -0.431974 0.893517 + outer loop + vertex -351.142 117.844 384.176 + vertex -359.559 124.029 386.012 + vertex -359.987 120.184 384.094 + endloop + endfacet + facet normal -0.146159 -0.426368 0.892663 + outer loop + vertex -359.987 120.184 384.094 + vertex -367.28 126.65 385.989 + vertex -367.783 122.822 384.078 + endloop + endfacet + facet normal -0.16944 -0.419181 0.891951 + outer loop + vertex -367.783 122.822 384.078 + vertex -373.813 128.979 385.826 + vertex -374.346 125.122 383.912 + endloop + endfacet + facet normal -0.193347 -0.414537 0.889256 + outer loop + vertex -373.813 128.979 385.826 + vertex -378.899 130.196 385.287 + vertex -374.346 125.122 383.912 + endloop + endfacet + facet normal -0.145769 -0.430095 0.890937 + outer loop + vertex -360.45 116.4 382.196 + vertex -368.289 119.031 382.184 + vertex -360.939 112.623 380.293 + endloop + endfacet + facet normal -0.120935 -0.434181 0.892671 + outer loop + vertex -351.95 110.258 380.361 + vertex -360.45 116.4 382.196 + vertex -360.939 112.623 380.293 + endloop + endfacet + facet normal -0.100202 -0.439859 0.892459 + outer loop + vertex -341.161 108.054 380.486 + vertex -351.537 114.029 382.266 + vertex -351.95 110.258 380.361 + endloop + endfacet + facet normal -0.086418 -0.448014 0.88984 + outer loop + vertex -328.447 99.915 377.623 + vertex -327.934 107.56 381.521 + vertex -341.161 108.054 380.486 + endloop + endfacet + facet normal -0.104319 -0.452781 0.885498 + outer loop + vertex -343.39 104.899 378.687 + vertex -352.401 106.499 378.444 + vertex -341.911 100.524 376.624 + endloop + endfacet + facet normal -0.0988679 -0.444654 0.890229 + outer loop + vertex -341.911 100.524 376.624 + vertex -352.401 106.499 378.444 + vertex -352.932 102.753 376.514 + endloop + endfacet + facet normal -0.117109 -0.442552 0.889063 + outer loop + vertex -353.404 99.0423 374.579 + vertex -362.122 105.037 376.414 + vertex -362.731 101.253 374.451 + endloop + endfacet + facet normal -0.121098 -0.441015 0.889292 + outer loop + vertex -352.401 106.499 378.444 + vertex -361.478 108.838 378.367 + vertex -352.932 102.753 376.514 + endloop + endfacet + facet normal -0.141811 -0.429165 0.892024 + outer loop + vertex -361.478 108.838 378.367 + vertex -368.84 115.229 380.272 + vertex -369.537 111.379 378.309 + endloop + endfacet + facet normal -0.162644 -0.420507 0.892592 + outer loop + vertex -369.537 111.379 378.309 + vertex -375.588 117.59 380.132 + vertex -376.627 113.733 378.126 + endloop + endfacet + facet normal -0.187015 -0.413227 0.891218 + outer loop + vertex -375.588 117.59 380.132 + vertex -381.507 119.596 379.82 + vertex -376.627 113.733 378.126 + endloop + endfacet + facet normal -0.177677 -0.40685 0.896049 + outer loop + vertex -376.627 113.733 378.126 + vertex -381.507 119.596 379.82 + vertex -381.961 115.06 377.671 + endloop + endfacet + facet normal -0.142141 -0.437843 0.887744 + outer loop + vertex -362.122 105.037 376.414 + vertex -370.416 107.516 376.309 + vertex -362.731 101.253 374.451 + endloop + endfacet + facet normal -0.119212 -0.451707 0.884166 + outer loop + vertex -353.404 99.0423 374.579 + vertex -362.731 101.253 374.451 + vertex -353.721 95.3309 372.64 + endloop + endfacet + facet normal -0.0977658 -0.454237 0.8855 + outer loop + vertex -342.437 93.2031 372.794 + vertex -353.404 99.0423 374.579 + vertex -353.721 95.3309 372.64 + endloop + endfacet + facet normal -0.0865869 -0.457809 0.884824 + outer loop + vertex -344.182 97.4623 374.827 + vertex -342.437 93.2031 372.794 + vertex -328.811 92.5566 373.793 + endloop + endfacet + facet normal -0.0799843 -0.457048 0.885839 + outer loop + vertex -307.964 89.6472 374.174 + vertex -328.447 99.915 377.623 + vertex -328.811 92.5566 373.793 + endloop + endfacet + facet normal -0.0748441 -0.458368 0.885605 + outer loop + vertex -287.924 86.784 374.386 + vertex -307.791 97.0821 378.037 + vertex -307.964 89.6472 374.174 + endloop + endfacet + facet normal -0.0688712 -0.458646 0.885946 + outer loop + vertex -268.667 83.9997 374.442 + vertex -287.893 94.316 378.288 + vertex -287.924 86.784 374.386 + endloop + endfacet + facet normal -0.0633926 -0.458531 0.886415 + outer loop + vertex -249.815 81.3209 374.404 + vertex -268.71 91.5602 378.349 + vertex -268.667 83.9997 374.442 + endloop + endfacet + facet normal -0.0590279 -0.459048 0.886448 + outer loop + vertex -231.012 78.8133 374.358 + vertex -249.874 88.8637 378.306 + vertex -249.815 81.3209 374.404 + endloop + endfacet + facet normal -0.05496 -0.459194 0.886634 + outer loop + vertex -212.091 76.525 374.345 + vertex -231.04 86.3575 378.263 + vertex -231.012 78.8133 374.358 + endloop + endfacet + facet normal -0.0551988 -0.459571 0.886424 + outer loop + vertex -212.1 84.0644 378.254 + vertex -231.04 86.3575 378.263 + vertex -212.091 76.525 374.345 + endloop + endfacet + facet normal -0.0459586 -0.460416 0.886513 + outer loop + vertex -173.869 80.0976 378.281 + vertex -193.045 81.9849 378.267 + vertex -173.821 72.5645 374.371 + endloop + endfacet + facet normal -0.0505648 -0.459679 0.886645 + outer loop + vertex -193.024 74.4516 374.358 + vertex -212.1 84.0644 378.254 + vertex -212.091 76.525 374.345 + endloop + endfacet + facet normal -0.0498764 -0.451498 0.890877 + outer loop + vertex -192.757 89.7359 382.211 + vertex -211.778 91.8084 382.197 + vertex -193.045 81.9849 378.267 + endloop + endfacet + facet normal -0.0541772 -0.451151 0.890802 + outer loop + vertex -212.1 84.0644 378.254 + vertex -230.702 94.1041 382.207 + vertex -231.04 86.3575 378.263 + endloop + endfacet + facet normal -0.0534752 -0.443663 0.894597 + outer loop + vertex -211.398 99.5104 386.039 + vertex -230.293 101.815 386.053 + vertex -211.778 91.8084 382.197 + endloop + endfacet + facet normal -0.0572475 -0.443187 0.894599 + outer loop + vertex -230.702 94.1041 382.207 + vertex -249.108 104.359 386.109 + vertex -249.542 96.6374 382.256 + endloop + endfacet + facet normal -0.0567429 -0.437443 0.897454 + outer loop + vertex -230.098 109.567 389.844 + vertex -248.891 112.13 389.904 + vertex -230.293 101.815 386.053 + endloop + endfacet + facet normal -0.0605022 -0.436516 0.89766 + outer loop + vertex -249.108 104.359 386.109 + vertex -267.686 114.895 389.981 + vertex -267.962 107.113 386.178 + endloop + endfacet + facet normal -0.060168 -0.432354 0.899694 + outer loop + vertex -248.907 120.284 393.822 + vertex -267.662 123.037 393.891 + vertex -248.891 112.13 389.904 + endloop + endfacet + facet normal -0.0648547 -0.431809 0.89963 + outer loop + vertex -267.686 114.895 389.981 + vertex -286.64 125.857 393.876 + vertex -286.779 117.76 389.979 + endloop + endfacet + facet normal -0.0642834 -0.428623 0.901193 + outer loop + vertex -267.477 131.898 398.118 + vertex -286.398 134.641 398.073 + vertex -267.662 123.037 393.891 + endloop + endfacet + facet normal -0.0703895 -0.428774 0.900665 + outer loop + vertex -286.64 125.857 393.876 + vertex -305.914 137.23 397.784 + vertex -306.196 128.628 393.667 + endloop + endfacet + facet normal -0.0694727 -0.426637 0.901751 + outer loop + vertex -285.142 144.098 402.644 + vertex -304.764 146.683 402.355 + vertex -286.398 134.641 398.073 + endloop + endfacet + facet normal -0.069756 -0.428911 0.90065 + outer loop + vertex -285.142 144.098 402.644 + vertex -301.021 156.07 407.116 + vertex -304.764 146.683 402.355 + endloop + endfacet + facet normal -0.0764829 -0.426443 0.901275 + outer loop + vertex -305.914 137.23 397.784 + vertex -325.46 148.83 401.614 + vertex -325.999 139.655 397.227 + endloop + endfacet + facet normal -0.0842882 -0.426326 0.900634 + outer loop + vertex -340.441 144.56 398.197 + vertex -338.782 139.857 396.126 + vertex -325.999 139.655 397.227 + endloop + endfacet + facet normal -0.100636 -0.426173 0.899027 + outer loop + vertex -340.441 144.56 398.197 + vertex -348.963 150.206 399.92 + vertex -348.996 146.013 397.928 + endloop + endfacet + facet normal -0.0983008 -0.42664 0.899063 + outer loop + vertex -340.383 153.689 402.502 + vertex -349.066 154.735 402.049 + vertex -338.624 148.349 400.161 + endloop + endfacet + facet normal -0.119002 -0.428158 0.895834 + outer loop + vertex -348.963 150.206 399.92 + vertex -357.5 156.76 401.918 + vertex -357.458 152.41 399.845 + endloop + endfacet + facet normal -0.113253 -0.423925 0.898589 + outer loop + vertex -348.842 159.451 404.302 + vertex -357.356 161.272 404.088 + vertex -349.066 154.735 402.049 + endloop + endfacet + facet normal -0.137902 -0.43009 0.892191 + outer loop + vertex -357.356 161.272 404.088 + vertex -363.746 167.548 406.126 + vertex -364.58 163.526 404.058 + endloop + endfacet + facet normal -0.156337 -0.425769 0.891223 + outer loop + vertex -363.746 167.548 406.126 + vertex -369.963 169.552 405.993 + vertex -364.58 163.526 404.058 + endloop + endfacet + facet normal -0.155843 -0.42418 0.892067 + outer loop + vertex -363.746 167.548 406.126 + vertex -368.267 172.748 407.809 + vertex -369.963 169.552 405.993 + endloop + endfacet + facet normal -0.164636 -0.431773 0.88683 + outer loop + vertex -364.58 163.526 404.058 + vertex -369.963 169.552 405.993 + vertex -370.566 165.705 404.008 + endloop + endfacet + facet normal -0.182005 -0.428195 0.885169 + outer loop + vertex -369.963 169.552 405.993 + vertex -374.185 170.514 405.59 + vertex -370.566 165.705 404.008 + endloop + endfacet + facet normal -0.141036 -0.427089 0.893143 + outer loop + vertex -357.5 156.76 401.918 + vertex -364.806 159.213 401.937 + vertex -357.458 152.41 399.845 + endloop + endfacet + facet normal -0.118255 -0.425229 0.897327 + outer loop + vertex -348.963 150.206 399.92 + vertex -357.458 152.41 399.845 + vertex -348.996 146.013 397.928 + endloop + endfacet + facet normal -0.101328 -0.430654 0.896811 + outer loop + vertex -340.441 144.56 398.197 + vertex -348.996 146.013 397.928 + vertex -338.782 139.857 396.126 + endloop + endfacet + facet normal -0.0842366 -0.428396 0.899656 + outer loop + vertex -326.338 131.398 393.263 + vertex -325.999 139.655 397.227 + vertex -338.782 139.857 396.126 + endloop + endfacet + facet normal -0.0776689 -0.432025 0.898511 + outer loop + vertex -306.498 120.598 389.785 + vertex -326.338 131.398 393.263 + vertex -326.828 123.367 389.36 + endloop + endfacet + facet normal -0.0856181 -0.430932 0.898314 + outer loop + vertex -341.435 128.411 390.387 + vertex -339.898 123.688 388.268 + vertex -326.828 123.367 389.36 + endloop + endfacet + facet normal -0.101976 -0.429477 0.897302 + outer loop + vertex -341.435 128.411 390.387 + vertex -349.887 133.974 392.089 + vertex -350.171 129.845 390.081 + endloop + endfacet + facet normal -0.102859 -0.433392 0.895317 + outer loop + vertex -340.843 136.517 394.331 + vertex -349.561 138.052 394.072 + vertex -339.328 131.848 392.245 + endloop + endfacet + facet normal -0.121261 -0.426958 0.896104 + outer loop + vertex -349.887 133.974 392.089 + vertex -358.25 140.321 393.981 + vertex -358.567 136.231 391.99 + endloop + endfacet + facet normal -0.120286 -0.426395 0.896503 + outer loop + vertex -349.24 142.029 396.007 + vertex -357.927 144.321 395.931 + vertex -349.561 138.052 394.072 + endloop + endfacet + facet normal -0.14524 -0.425018 0.893457 + outer loop + vertex -358.25 140.321 393.981 + vertex -365.431 146.854 395.922 + vertex -365.786 142.918 393.992 + endloop + endfacet + facet normal -0.143225 -0.423764 0.894377 + outer loop + vertex -357.624 148.302 397.866 + vertex -365.177 150.826 397.852 + vertex -357.927 144.321 395.931 + endloop + endfacet + facet normal -0.170227 -0.423615 0.889704 + outer loop + vertex -365.431 146.854 395.922 + vertex -371.291 152.958 397.707 + vertex -371.553 149.229 395.881 + endloop + endfacet + facet normal -0.190603 -0.420811 0.886898 + outer loop + vertex -371.291 152.958 397.707 + vertex -375.292 153.935 397.311 + vertex -371.553 149.229 395.881 + endloop + endfacet + facet normal -0.16912 -0.423709 0.88987 + outer loop + vertex -364.967 154.945 399.854 + vertex -371.302 157.165 399.707 + vertex -365.177 150.826 397.852 + endloop + endfacet + facet normal -0.194615 -0.425973 0.883556 + outer loop + vertex -371.059 161.566 401.882 + vertex -376.454 163.118 401.442 + vertex -371.302 157.165 399.707 + endloop + endfacet + facet normal -0.241204 -0.422531 0.873664 + outer loop + vertex -378.503 156.03 397.527 + vertex -379.241 161.189 399.818 + vertex -381.2 157.187 397.342 + endloop + endfacet + facet normal -0.190419 -0.419855 0.887391 + outer loop + vertex -371.291 152.958 397.707 + vertex -375.93 157.871 399.036 + vertex -375.292 153.935 397.311 + endloop + endfacet + facet normal -0.199172 -0.426253 0.882405 + outer loop + vertex -371.553 149.229 395.881 + vertex -375.292 153.935 397.311 + vertex -376.28 151.191 395.762 + endloop + endfacet + facet normal -0.239078 -0.417064 0.876869 + outer loop + vertex -378.503 156.03 397.527 + vertex -381.2 157.187 397.342 + vertex -379.725 152.005 395.279 + endloop + endfacet + facet normal -0.24468 -0.417887 0.87493 + outer loop + vertex -381.2 157.187 397.342 + vertex -382.088 149.579 393.46 + vertex -379.725 152.005 395.279 + endloop + endfacet + facet normal -0.202208 -0.424135 0.882735 + outer loop + vertex -372.068 145.502 393.994 + vertex -376.28 151.191 395.762 + vertex -376.997 147.379 393.766 + endloop + endfacet + facet normal -0.249469 -0.413701 0.875567 + outer loop + vertex -380.141 148.018 393.277 + vertex -379.725 152.005 395.279 + vertex -382.088 149.579 393.46 + endloop + endfacet + facet normal -0.202981 -0.421962 0.883599 + outer loop + vertex -372.573 141.446 391.949 + vertex -376.997 147.379 393.766 + vertex -378.048 143.295 391.575 + endloop + endfacet + facet normal -0.245761 -0.409433 0.878616 + outer loop + vertex -380.141 148.018 393.277 + vertex -382.088 149.579 393.46 + vertex -381.241 145.46 391.777 + endloop + endfacet + facet normal -0.246578 -0.409496 0.878358 + outer loop + vertex -382.088 149.579 393.46 + vertex -382.843 142.481 389.939 + vertex -381.241 145.46 391.777 + endloop + endfacet + facet normal -0.244256 -0.410776 0.878409 + outer loop + vertex -380.781 141.948 390.263 + vertex -381.241 145.46 391.777 + vertex -382.843 142.481 389.939 + endloop + endfacet + facet normal -0.198274 -0.41481 0.888043 + outer loop + vertex -372.995 137.171 389.842 + vertex -378.048 143.295 391.575 + vertex -377.997 138.376 389.288 + endloop + endfacet + facet normal -0.243364 -0.405761 0.880983 + outer loop + vertex -380.781 141.948 390.263 + vertex -382.843 142.481 389.939 + vertex -381.408 138.013 388.277 + endloop + endfacet + facet normal -0.239001 -0.404944 0.882553 + outer loop + vertex -382.843 142.481 389.939 + vertex -383.969 134.734 386.079 + vertex -381.408 138.013 388.277 + endloop + endfacet + facet normal -0.195666 -0.413989 0.889004 + outer loop + vertex -373.33 132.945 387.786 + vertex -377.997 138.376 389.288 + vertex -378.368 134.199 387.262 + endloop + endfacet + facet normal -0.240334 -0.403962 0.882641 + outer loop + vertex -381.574 133.863 386.332 + vertex -381.408 138.013 388.277 + vertex -383.969 134.734 386.079 + endloop + endfacet + facet normal -0.193104 -0.41323 0.889917 + outer loop + vertex -373.813 128.979 385.826 + vertex -378.368 134.199 387.262 + vertex -378.899 130.196 385.287 + endloop + endfacet + facet normal -0.239091 -0.39991 0.884821 + outer loop + vertex -381.574 133.863 386.332 + vertex -383.969 134.734 386.079 + vertex -382.616 129.839 384.232 + endloop + endfacet + facet normal -0.233446 -0.399062 0.886709 + outer loop + vertex -383.969 134.734 386.079 + vertex -385.711 126.248 381.801 + vertex -382.616 129.839 384.232 + endloop + endfacet + facet normal -0.189988 -0.412033 0.891142 + outer loop + vertex -374.346 125.122 383.912 + vertex -378.899 130.196 385.287 + vertex -379.393 126.168 383.32 + endloop + endfacet + facet normal -0.184614 -0.410424 0.893012 + outer loop + vertex -374.799 121.287 382.027 + vertex -379.393 126.168 383.32 + vertex -379.413 122.438 381.602 + endloop + endfacet + facet normal -0.188503 -0.418013 0.888668 + outer loop + vertex -375.588 117.59 380.132 + vertex -379.413 122.438 381.602 + vertex -381.507 119.596 379.82 + endloop + endfacet + facet normal -0.230237 -0.401615 0.886395 + outer loop + vertex -382.864 124.934 381.946 + vertex -382.616 129.839 384.232 + vertex -385.711 126.248 381.801 + endloop + endfacet + facet normal -0.202835 -0.399032 0.894221 + outer loop + vertex -385.03 122.219 380.192 + vertex -385.19 118.235 378.377 + vertex -381.507 119.596 379.82 + endloop + endfacet + facet normal -0.200829 -0.403034 0.892878 + outer loop + vertex -381.961 115.06 377.671 + vertex -381.507 119.596 379.82 + vertex -385.19 118.235 378.377 + endloop + endfacet + facet normal -0.178792 -0.41226 0.893351 + outer loop + vertex -376.627 113.733 378.126 + vertex -381.961 115.06 377.671 + vertex -378.192 110.052 376.114 + endloop + endfacet + facet normal -0.198106 -0.406852 0.891754 + outer loop + vertex -382.408 112.765 376.549 + vertex -384.866 114.451 376.772 + vertex -382.971 110.963 375.602 + endloop + endfacet + facet normal -0.196042 -0.406012 0.892593 + outer loop + vertex -382.971 110.963 375.602 + vertex -384.866 114.451 376.772 + vertex -386.303 112.498 375.569 + endloop + endfacet + facet normal -0.155926 -0.422119 0.89303 + outer loop + vertex -371.269 103.676 374.309 + vertex -378.192 110.052 376.114 + vertex -379.339 106.192 374.09 + endloop + endfacet + facet normal -0.194508 -0.402643 0.894453 + outer loop + vertex -382.971 110.963 375.602 + vertex -386.303 112.498 375.569 + vertex -384.358 109.422 374.607 + endloop + endfacet + facet normal -0.21114 -0.395647 0.893803 + outer loop + vertex -384.866 114.451 376.772 + vertex -387.299 116.017 376.891 + vertex -386.303 112.498 375.569 + endloop + endfacet + facet normal -0.230245 -0.390886 0.891176 + outer loop + vertex -387.299 116.017 376.891 + vertex -387.126 120.095 378.724 + vertex -388.724 116.37 376.678 + endloop + endfacet + facet normal -0.287415 -0.36374 0.886051 + outer loop + vertex -388.724 116.37 376.678 + vertex -389.293 115.598 376.176 + vertex -389.917 112.472 374.69 + endloop + endfacet + facet normal -0.205516 -0.392979 0.896287 + outer loop + vertex -387.131 110.311 374.406 + vertex -388.526 113.225 375.364 + vertex -389.034 110.861 374.211 + endloop + endfacet + facet normal -0.206019 -0.39509 0.895243 + outer loop + vertex -387.131 110.311 374.406 + vertex -389.034 110.861 374.211 + vertex -387.744 108.394 373.419 + endloop + endfacet + facet normal -0.18657 -0.401938 0.896458 + outer loop + vertex -384.361 107.076 373.532 + vertex -387.131 110.311 374.406 + vertex -387.744 108.394 373.419 + endloop + endfacet + facet normal -0.17274 -0.419595 0.891123 + outer loop + vertex -380.327 102.48 372.15 + vertex -379.339 106.192 374.09 + vertex -384.361 107.076 373.532 + endloop + endfacet + facet normal -0.188504 -0.411228 0.891828 + outer loop + vertex -385.555 105.663 372.65 + vertex -388.392 106.662 372.511 + vertex -385.538 103.542 371.676 + endloop + endfacet + facet normal -0.178612 -0.403648 0.89731 + outer loop + vertex -385.538 103.542 371.676 + vertex -388.392 106.662 372.511 + vertex -389.116 104.982 371.611 + endloop + endfacet + facet normal -0.148853 -0.430616 0.890176 + outer loop + vertex -372.677 96.3684 370.473 + vertex -380.327 102.48 372.15 + vertex -381.348 99.0137 370.302 + endloop + endfacet + facet normal -0.15233 -0.442426 0.883773 + outer loop + vertex -372.677 96.3684 370.473 + vertex -381.348 99.0137 370.302 + vertex -373.452 93.1931 368.749 + endloop + endfacet + facet normal -0.162202 -0.430938 0.887684 + outer loop + vertex -382.309 95.6797 368.508 + vertex -381.348 99.0137 370.302 + vertex -386.906 100.128 369.827 + endloop + endfacet + facet normal -0.156017 -0.42563 0.891346 + outer loop + vertex -388.347 98.8456 368.963 + vertex -382.309 95.6797 368.508 + vertex -386.906 100.128 369.827 + endloop + endfacet + facet normal -0.171946 -0.410527 0.89549 + outer loop + vertex -386.906 100.128 369.827 + vertex -390.781 101.599 369.758 + vertex -388.347 98.8456 368.963 + endloop + endfacet + facet normal -0.169628 -0.40883 0.896707 + outer loop + vertex -388.347 98.8456 368.963 + vertex -390.781 101.599 369.758 + vertex -391.633 99.9268 368.835 + endloop + endfacet + facet normal -0.154824 -0.423528 0.892555 + outer loop + vertex -388.347 98.8456 368.963 + vertex -388.273 96.8096 368.01 + vertex -382.309 95.6797 368.508 + endloop + endfacet + facet normal -0.170784 -0.40739 0.897143 + outer loop + vertex -386.906 100.128 369.827 + vertex -389.935 103.297 370.69 + vertex -390.781 101.599 369.758 + endloop + endfacet + facet normal -0.188829 -0.398583 0.897483 + outer loop + vertex -389.935 103.297 370.69 + vertex -392.064 104.03 370.568 + vertex -390.781 101.599 369.758 + endloop + endfacet + facet normal -0.184747 -0.396952 0.899054 + outer loop + vertex -390.781 101.599 369.758 + vertex -392.064 104.03 370.568 + vertex -393.154 102.6 369.712 + endloop + endfacet + facet normal -0.200471 -0.385843 0.90052 + outer loop + vertex -392.064 104.03 370.568 + vertex -392.955 105.674 371.074 + vertex -393.154 102.6 369.712 + endloop + endfacet + facet normal -0.179069 -0.404811 0.896695 + outer loop + vertex -385.538 103.542 371.676 + vertex -389.116 104.982 371.611 + vertex -386.887 102.245 370.821 + endloop + endfacet + facet normal -0.187147 -0.39324 0.900188 + outer loop + vertex -389.935 103.297 370.69 + vertex -391.349 105.933 371.548 + vertex -392.064 104.03 370.568 + endloop + endfacet + facet normal -0.196562 -0.395781 0.897062 + outer loop + vertex -388.392 106.662 372.511 + vertex -390.4 107.372 372.384 + vertex -389.116 104.982 371.611 + endloop + endfacet + facet normal -0.211328 -0.385681 0.898104 + outer loop + vertex -390.4 107.372 372.384 + vertex -389.836 109.285 373.339 + vertex -391.303 108.976 372.861 + endloop + endfacet + facet normal -0.203029 -0.386911 0.899488 + outer loop + vertex -392.064 104.03 370.568 + vertex -391.349 105.933 371.548 + vertex -392.955 105.674 371.074 + endloop + endfacet + facet normal -0.2363 -0.372468 0.897458 + outer loop + vertex -391.303 108.976 372.861 + vertex -390.537 111.977 374.308 + vertex -392.044 108.576 372.499 + endloop + endfacet + facet normal -0.194314 -0.38668 0.90151 + outer loop + vertex -392.955 105.674 371.074 + vertex -394.848 102.395 369.259 + vertex -393.154 102.6 369.712 + endloop + endfacet + facet normal -0.186247 -0.400597 0.897125 + outer loop + vertex -390.781 101.599 369.758 + vertex -393.154 102.6 369.712 + vertex -391.633 99.9268 368.835 + endloop + endfacet + facet normal -0.173921 -0.422744 0.889404 + outer loop + vertex -388.347 98.8456 368.963 + vertex -391.633 99.9268 368.835 + vertex -388.273 96.8096 368.01 + endloop + endfacet + facet normal -0.17512 -0.401991 0.898742 + outer loop + vertex -392.496 98.3053 367.932 + vertex -393.932 100.705 368.725 + vertex -395.081 99.3376 367.89 + endloop + endfacet + facet normal -0.185196 -0.394625 0.899985 + outer loop + vertex -395.892 97.538 366.934 + vertex -395.081 99.3376 367.89 + vertex -396.892 99.1933 367.454 + endloop + endfacet + facet normal -0.200878 -0.380458 0.902718 + outer loop + vertex -396.892 99.1933 367.454 + vertex -397.845 99.0312 367.173 + vertex -398.824 96.3141 365.81 + endloop + endfacet + facet normal -0.161382 -0.408711 0.898282 + outer loop + vertex -394.94 93.8559 365.42 + vertex -397.032 96.2824 366.148 + vertex -397.659 94.6605 365.297 + endloop + endfacet + facet normal -0.185277 -0.386472 0.9035 + outer loop + vertex -398.824 96.3141 365.81 + vertex -397.845 99.0312 367.173 + vertex -399.769 96.3691 365.64 + endloop + endfacet + facet normal -0.215343 0.599531 -0.770837 + outer loop + vertex -397.845 99.0312 367.173 + vertex -398.412 98.2116 366.694 + vertex -399.769 96.3691 365.64 + endloop + endfacet + facet normal -0.167528 -0.407539 0.897689 + outer loop + vertex -398.879 92.7122 364.183 + vertex -398.554 93.7592 364.719 + vertex -400.325 94.2259 364.601 + endloop + endfacet + facet normal -0.160603 -0.414873 0.895593 + outer loop + vertex -395.527 92.6435 364.745 + vertex -397.659 94.6605 365.297 + vertex -398.554 93.7592 364.719 + endloop + endfacet + facet normal -0.163857 -0.41778 0.89365 + outer loop + vertex -394.94 93.8559 365.42 + vertex -397.659 94.6605 365.297 + vertex -395.527 92.6435 364.745 + endloop + endfacet + facet normal -0.169719 -0.414623 0.894026 + outer loop + vertex -394.206 95.2487 366.205 + vertex -397.032 96.2824 366.148 + vertex -394.94 93.8559 365.42 + endloop + endfacet + facet normal -0.156424 -0.41899 0.894415 + outer loop + vertex -389.544 93.7796 366.332 + vertex -393.372 96.7488 367.053 + vertex -394.206 95.2487 366.205 + endloop + endfacet + facet normal -0.144926 -0.431961 0.890172 + outer loop + vertex -391.023 92.7731 365.594 + vertex -390.616 91.2563 364.924 + vertex -383.817 90.0337 365.438 + endloop + endfacet + facet normal -0.148722 -0.42875 0.891098 + outer loop + vertex -389.74 95.637 367.193 + vertex -389.544 93.7796 366.332 + vertex -383.045 92.5928 366.846 + endloop + endfacet + facet normal -0.15709 -0.438972 0.884662 + outer loop + vertex -383.045 92.5928 366.846 + vertex -382.309 95.6797 368.508 + vertex -388.273 96.8096 368.01 + endloop + endfacet + facet normal -0.146508 -0.435681 0.888098 + outer loop + vertex -373.452 93.1931 368.749 + vertex -381.348 99.0137 370.302 + vertex -382.309 95.6797 368.508 + endloop + endfacet + facet normal -0.130944 -0.447989 0.884398 + outer loop + vertex -364.404 90.6985 368.825 + vertex -372.677 96.3684 370.473 + vertex -373.452 93.1931 368.749 + endloop + endfacet + facet normal -0.134699 -0.452618 0.881472 + outer loop + vertex -363.552 93.8616 370.58 + vertex -372.677 96.3684 370.473 + vertex -364.404 90.6985 368.825 + endloop + endfacet + facet normal -0.114235 -0.454459 0.883413 + outer loop + vertex -353.694 91.6531 370.718 + vertex -363.194 97.4927 372.494 + vertex -363.552 93.8616 370.58 + endloop + endfacet + facet normal -0.102282 -0.475248 0.873887 + outer loop + vertex -344.285 90.1782 371.018 + vertex -353.694 91.6531 370.718 + vertex -341.59 86.0698 369.099 + endloop + endfacet + facet normal -0.0875186 -0.468105 0.879328 + outer loop + vertex -344.285 90.1782 371.018 + vertex -341.59 86.0698 369.099 + vertex -328.509 85.751 370.231 + endloop + endfacet + facet normal -0.0813121 -0.470322 0.878741 + outer loop + vertex -308.104 82.9812 370.637 + vertex -328.509 85.751 370.231 + vertex -308.642 77.6264 367.721 + endloop + endfacet + facet normal -0.0756933 -0.470971 0.878895 + outer loop + vertex -289.242 74.8139 367.884 + vertex -308.104 82.9812 370.637 + vertex -308.642 77.6264 367.721 + endloop + endfacet + facet normal -0.0709496 -0.473522 0.87792 + outer loop + vertex -269.842 71.9462 367.906 + vertex -288.1 80.0867 370.821 + vertex -289.242 74.8139 367.884 + endloop + endfacet + facet normal -0.0658402 -0.474615 0.877727 + outer loop + vertex -250.269 69.1197 367.845 + vertex -268.674 77.25 370.861 + vertex -269.842 71.9462 367.906 + endloop + endfacet + facet normal -0.0614082 -0.475247 0.877707 + outer loop + vertex -230.918 66.5894 367.829 + vertex -249.602 74.5292 370.821 + vertex -250.269 69.1197 367.845 + endloop + endfacet + facet normal -0.05678 -0.474821 0.878249 + outer loop + vertex -211.914 64.2889 367.814 + vertex -230.7 72.0155 370.777 + vertex -230.918 66.5894 367.829 + endloop + endfacet + facet normal -0.051997 -0.474696 0.878613 + outer loop + vertex -192.91 62.2123 367.817 + vertex -211.788 69.7283 370.76 + vertex -211.914 64.2889 367.814 + endloop + endfacet + facet normal -0.0470602 -0.474987 0.878733 + outer loop + vertex -173.7 60.3205 367.823 + vertex -192.746 67.6574 370.769 + vertex -192.91 62.2123 367.817 + endloop + endfacet + facet normal -0.0420345 -0.475332 0.878802 + outer loop + vertex -154.456 58.6434 367.836 + vertex -173.559 65.7775 370.781 + vertex -173.7 60.3205 367.823 + endloop + endfacet + facet normal -0.0369 -0.47552 0.878931 + outer loop + vertex -135.142 57.1389 367.833 + vertex -154.238 64.0806 370.787 + vertex -154.456 58.6434 367.836 + endloop + endfacet + facet normal -0.0316698 -0.475853 0.878955 + outer loop + vertex -115.681 55.8307 367.826 + vertex -134.807 62.5673 370.784 + vertex -135.142 57.1389 367.833 + endloop + endfacet + facet normal -0.0262396 -0.475945 0.879083 + outer loop + vertex -96.2885 54.7497 367.82 + vertex -115.34 61.2667 370.78 + vertex -115.681 55.8307 367.826 + endloop + endfacet + facet normal -0.020893 -0.476001 0.879196 + outer loop + vertex -77.0031 53.8925 367.814 + vertex -95.913 60.1923 370.775 + vertex -96.2885 54.7497 367.82 + endloop + endfacet + facet normal -0.0157917 -0.47627 0.879157 + outer loop + vertex -57.7171 53.2547 367.815 + vertex -76.5106 59.3342 370.771 + vertex -77.0031 53.8925 367.814 + endloop + endfacet + facet normal -0.0109717 -0.476223 0.879256 + outer loop + vertex -38.3504 52.8394 367.832 + vertex -57.1216 58.7158 370.78 + vertex -57.7171 53.2547 367.815 + endloop + endfacet + facet normal -0.00645756 -0.47625 0.879286 + outer loop + vertex -18.9322 52.5998 367.845 + vertex -37.7389 58.29 370.788 + vertex -38.3504 52.8394 367.832 + endloop + endfacet + facet normal -0.00203578 -0.476388 0.879233 + outer loop + vertex 0.390189 52.5252 367.849 + vertex -18.4082 58.0325 370.789 + vertex -18.9322 52.5998 367.845 + endloop + endfacet + facet normal 0.00229673 -0.476467 0.87919 + outer loop + vertex 19.7394 52.5894 367.833 + vertex 0.903917 57.9425 370.783 + vertex 0.390189 52.5252 367.849 + endloop + endfacet + facet normal 0.0065545 -0.476508 0.879145 + outer loop + vertex 39.0729 52.8164 367.812 + vertex 20.2376 58.0256 370.776 + vertex 19.7394 52.5894 367.833 + endloop + endfacet + facet normal 0.0111923 -0.476258 0.879234 + outer loop + vertex 58.2963 53.2781 367.817 + vertex 39.6061 58.2964 370.774 + vertex 39.0729 52.8164 367.812 + endloop + endfacet + facet normal 0.015881 -0.476361 0.879106 + outer loop + vertex 77.5934 53.9295 367.822 + vertex 59.0244 58.7551 370.772 + vertex 58.2963 53.2781 367.817 + endloop + endfacet + facet normal 0.0210363 -0.476139 0.879119 + outer loop + vertex 97.0224 54.7905 367.823 + vertex 78.4561 59.42 370.775 + vertex 77.5934 53.9295 367.822 + endloop + endfacet + facet normal 0.0263065 -0.475857 0.879129 + outer loop + vertex 116.427 55.8634 367.823 + vertex 97.8513 60.2964 370.779 + vertex 97.0224 54.7905 367.823 + endloop + endfacet + facet normal 0.0316501 -0.475602 0.879091 + outer loop + vertex 135.593 57.1378 367.823 + vertex 117.154 61.3713 370.777 + vertex 116.427 55.8634 367.823 + endloop + endfacet + facet normal 0.0370584 -0.475282 0.879053 + outer loop + vertex 154.698 58.6551 367.838 + vertex 136.344 62.6679 370.781 + vertex 135.593 57.1378 367.823 + endloop + endfacet + facet normal 0.0422624 -0.475649 0.878619 + outer loop + vertex 174.05 60.3871 367.844 + vertex 155.531 64.1666 370.781 + vertex 154.698 58.6551 367.838 + endloop + endfacet + facet normal 0.0473489 -0.475615 0.878379 + outer loop + vertex 193.664 62.3117 367.829 + vertex 174.759 65.8885 370.785 + vertex 174.05 60.3871 367.844 + endloop + endfacet + facet normal 0.0522398 -0.475387 0.878224 + outer loop + vertex 213.087 64.4845 367.85 + vertex 193.993 67.8137 370.788 + vertex 193.664 62.3117 367.829 + endloop + endfacet + facet normal 0.057097 -0.474759 0.878262 + outer loop + vertex 232.389 66.7832 367.838 + vertex 213.168 69.9308 370.789 + vertex 213.087 64.4845 367.85 + endloop + endfacet + facet normal 0.0615952 -0.474029 0.878352 + outer loop + vertex 251.481 69.236 367.823 + vertex 232.282 72.2315 370.786 + vertex 232.389 66.7832 367.838 + endloop + endfacet + facet normal 0.0658123 -0.47395 0.878089 + outer loop + vertex 270.38 71.825 367.804 + vertex 251.318 74.6584 370.762 + vertex 251.481 69.236 367.823 + endloop + endfacet + facet normal 0.0702454 -0.473665 0.877899 + outer loop + vertex 289.322 74.6647 367.82 + vertex 270.277 77.2658 370.747 + vertex 270.38 71.825 367.804 + endloop + endfacet + facet normal 0.0761138 -0.473545 0.877474 + outer loop + vertex 308.784 77.9498 367.905 + vertex 289.322 74.6647 367.82 + vertex 306.146 73.5633 365.766 + endloop + endfacet + facet normal 0.0897306 -0.511594 0.854529 + outer loop + vertex 328.732 74.7232 364.254 + vertex 316.919 73.1798 364.57 + vertex 315.739 70.9838 363.379 + endloop + endfacet + facet normal 0.0991304 -0.50879 0.855165 + outer loop + vertex 340.155 77.5085 364.586 + vertex 328.732 74.7232 364.254 + vertex 340.788 75.646 363.405 + endloop + endfacet + facet normal 0.105303 -0.506927 0.855533 + outer loop + vertex 355.211 80.1705 364.311 + vertex 340.155 77.5085 364.586 + vertex 340.788 75.646 363.405 + endloop + endfacet + facet normal 0.10079 -0.479739 0.871603 + outer loop + vertex 340.155 77.5085 364.586 + vertex 355.211 80.1705 364.311 + vertex 347.491 81.1704 365.754 + endloop + endfacet + facet normal 0.0823942 -0.476314 0.875406 + outer loop + vertex 326.094 76.7992 365.65 + vertex 308.784 77.9498 367.905 + vertex 306.146 73.5633 365.766 + endloop + endfacet + facet normal 0.0759126 -0.47237 0.878125 + outer loop + vertex 308.784 77.9498 367.905 + vertex 289.42 80.2041 370.791 + vertex 289.322 74.6647 367.82 + endloop + endfacet + facet normal 0.0698308 -0.465746 0.882159 + outer loop + vertex 288.871 86.9522 374.398 + vertex 269.621 83.9218 374.322 + vertex 289.42 80.2041 370.791 + endloop + endfacet + facet normal 0.0742958 -0.457568 0.886065 + outer loop + vertex 308.762 90.6556 374.642 + vertex 288.333 94.3833 378.28 + vertex 288.871 86.9522 374.398 + endloop + endfacet + facet normal 0.0800029 -0.455661 0.886551 + outer loop + vertex 329.31 95.0913 375.068 + vertex 308.212 98.1159 378.526 + vertex 308.762 90.6556 374.642 + endloop + endfacet + facet normal 0.0874147 -0.45481 0.886288 + outer loop + vertex 344.695 96.0344 374.034 + vertex 342.366 99.5914 376.089 + vertex 329.31 95.0913 375.068 + endloop + endfacet + facet normal 0.100584 -0.447521 0.888599 + outer loop + vertex 353.855 98.6331 374.306 + vertex 342.366 99.5914 376.089 + vertex 344.695 96.0344 374.034 + endloop + endfacet + facet normal 0.118114 -0.446371 0.887019 + outer loop + vertex 363.352 101.351 374.41 + vertex 353.436 102.322 376.219 + vertex 353.855 98.6331 374.306 + endloop + endfacet + facet normal 0.137979 -0.438633 0.888011 + outer loop + vertex 371.863 104.139 374.464 + vertex 362.805 105.031 376.312 + vertex 363.352 101.351 374.41 + endloop + endfacet + facet normal 0.158625 -0.430158 0.888708 + outer loop + vertex 378.7 106.938 374.599 + vertex 371.03 107.722 376.347 + vertex 371.863 104.139 374.464 + endloop + endfacet + facet normal 0.178559 -0.416519 0.891419 + outer loop + vertex 383.735 109.459 374.768 + vertex 377.77 110.341 376.375 + vertex 378.7 106.938 374.599 + endloop + endfacet + facet normal 0.197651 -0.402466 0.893843 + outer loop + vertex 383.735 109.459 374.768 + vertex 387.326 111.395 374.846 + vertex 383.025 112.745 376.405 + endloop + endfacet + facet normal 0.212704 -0.385898 0.897686 + outer loop + vertex 389.462 112.372 374.76 + vertex 387.326 111.395 374.846 + vertex 390.015 109.997 373.607 + endloop + endfacet + facet normal 0.202751 -0.393554 0.896665 + outer loop + vertex 390.371 108.125 372.72 + vertex 387.965 108.781 373.552 + vertex 388.822 106.737 372.461 + endloop + endfacet + facet normal 0.187482 -0.400691 0.896826 + outer loop + vertex 388.822 106.737 372.461 + vertex 386.447 105.057 372.207 + vertex 389.561 104.963 371.514 + endloop + endfacet + facet normal 0.172779 -0.415417 0.893071 + outer loop + vertex 386.447 105.057 372.207 + vertex 384.817 106.747 373.308 + vertex 380.723 103.76 372.711 + endloop + endfacet + facet normal 0.154956 -0.426473 0.891128 + outer loop + vertex 380.723 103.76 372.711 + vertex 372.784 100.639 372.597 + vertex 381.933 100.361 370.874 + endloop + endfacet + facet normal 0.181175 -0.405566 0.895931 + outer loop + vertex 390.298 103.278 370.609 + vertex 386.418 103.157 371.339 + vertex 387.771 101.64 370.378 + endloop + endfacet + facet normal 0.1911 -0.39446 0.898823 + outer loop + vertex 391.849 104.703 370.904 + vertex 390.298 103.278 370.609 + vertex 392.917 103.093 369.971 + endloop + endfacet + facet normal 0.184994 -0.400129 0.897593 + outer loop + vertex 393.588 101.365 369.076 + vertex 391.063 101.604 369.703 + vertex 391.888 99.9514 368.796 + endloop + endfacet + facet normal 0.173131 -0.406474 0.897109 + outer loop + vertex 391.888 99.9514 368.796 + vertex 389.195 98.3278 368.58 + vertex 392.728 98.3349 367.902 + endloop + endfacet + facet normal 0.161493 -0.419663 0.893198 + outer loop + vertex 389.195 98.3278 368.58 + vertex 387.742 99.8003 369.535 + vertex 383.07 97.034 369.08 + endloop + endfacet + facet normal 0.151376 -0.428513 0.890765 + outer loop + vertex 381.933 100.361 370.874 + vertex 373.616 97.1955 370.764 + vertex 383.07 97.034 369.08 + endloop + endfacet + facet normal 0.134994 -0.447391 0.884091 + outer loop + vertex 373.616 97.1955 370.764 + vertex 363.946 97.7697 372.531 + vertex 364.575 94.273 370.666 + endloop + endfacet + facet normal 0.116005 -0.457266 0.881732 + outer loop + vertex 364.575 94.273 370.666 + vertex 354.355 95.0208 372.398 + vertex 354.812 91.4643 370.494 + endloop + endfacet + facet normal 0.0999418 -0.459084 0.882754 + outer loop + vertex 354.812 91.4643 370.494 + vertex 343.196 92.2774 372.232 + vertex 345.417 88.8564 370.201 + endloop + endfacet + facet normal 0.0883372 -0.46539 0.880687 + outer loop + vertex 345.417 88.8564 370.201 + vertex 343.196 92.2774 372.232 + vertex 329.944 87.9506 371.274 + endloop + endfacet + facet normal 0.0825436 -0.470976 0.878276 + outer loop + vertex 329.944 87.9506 371.274 + vertex 309.294 83.7568 370.966 + vertex 330.092 81.8572 367.993 + endloop + endfacet + facet normal 0.100544 -0.473011 0.875301 + outer loop + vertex 354.794 87.9989 368.659 + vertex 343.212 85.4284 368.6 + vertex 353.375 84.7186 367.049 + endloop + endfacet + facet normal 0.0902548 -0.507465 0.856932 + outer loop + vertex 343.883 82.9407 367.182 + vertex 330.092 81.8572 367.993 + vertex 347.491 81.1704 365.754 + endloop + endfacet + facet normal 0.114527 -0.47607 0.871918 + outer loop + vertex 364.879 87.6492 367.138 + vertex 353.375 84.7186 367.049 + vertex 363.732 84.8022 365.735 + endloop + endfacet + facet normal 0.130816 -0.467924 0.874033 + outer loop + vertex 375.111 90.7121 367.247 + vertex 365.055 90.8592 368.83 + vertex 364.879 87.6492 367.138 + endloop + endfacet + facet normal 0.146509 -0.450375 0.880737 + outer loop + vertex 384.256 93.8684 367.339 + vertex 374.459 93.8475 368.958 + vertex 375.111 90.7121 367.247 + endloop + endfacet + facet normal 0.156479 -0.424907 0.89161 + outer loop + vertex 390.697 95.1753 366.832 + vertex 389.166 96.5533 367.757 + vertex 384.256 93.8684 367.339 + endloop + endfacet + facet normal 0.168375 -0.413753 0.894683 + outer loop + vertex 393.58 96.7785 367.031 + vertex 389.166 96.5533 367.757 + vertex 390.697 95.1753 366.832 + endloop + endfacet + facet normal 0.17446 -0.402406 0.898684 + outer loop + vertex 395.495 98.1794 367.286 + vertex 393.58 96.7785 367.031 + vertex 396.73 96.8033 366.43 + endloop + endfacet + facet normal 0.169976 -0.409695 0.896247 + outer loop + vertex 397.382 95.3437 365.653 + vertex 394.466 95.2988 366.186 + vertex 395.395 93.9628 365.399 + endloop + endfacet + facet normal 0.160387 -0.415634 0.895279 + outer loop + vertex 395.395 93.9628 365.399 + vertex 392.333 92.4598 365.249 + vertex 396.34 92.8651 364.72 + endloop + endfacet + facet normal 0.151539 -0.433081 0.888525 + outer loop + vertex 392.333 92.4598 365.249 + vertex 390.677 93.5612 366.069 + vertex 385.351 91.1125 365.784 + endloop + endfacet + facet normal 0.139804 -0.450573 0.881725 + outer loop + vertex 385.351 91.1125 365.784 + vertex 375.25 87.9894 365.789 + vertex 385.747 89.0459 364.665 + endloop + endfacet + facet normal 0.156227 -0.425322 0.891456 + outer loop + vertex 397.095 92.0519 364.212 + vertex 392.179 91.2802 364.705 + vertex 393.466 90.6883 364.197 + endloop + endfacet + facet normal 0.13629 -0.450749 0.882185 + outer loop + vertex 385.747 89.0459 364.665 + vertex 374.766 85.9223 364.765 + vertex 383.932 87.4585 364.134 + endloop + endfacet + facet normal 0.158997 -0.452916 0.877261 + outer loop + vertex 397.017 91.3816 363.911 + vertex 393.466 90.6883 364.197 + vertex 391.826 89.7591 364.014 + endloop + endfacet + facet normal 0.157365 -0.40972 0.898535 + outer loop + vertex 399.944 92.6687 363.986 + vertex 397.017 91.3816 363.911 + vertex 399.201 91.8941 363.762 + endloop + endfacet + facet normal 0.168302 -0.418475 0.892498 + outer loop + vertex 399.201 91.8941 363.762 + vertex 401.014 92.6217 363.762 + vertex 399.944 92.6687 363.986 + endloop + endfacet + facet normal 0.170711 -0.400514 0.900248 + outer loop + vertex 401.014 92.6217 363.762 + vertex 400.937 93.9263 364.357 + vertex 399.944 92.6687 363.986 + endloop + endfacet + facet normal 0.174047 -0.396079 0.90157 + outer loop + vertex 400.826 95.4702 365.043 + vertex 403.337 92.4562 363.234 + vertex 401.67 94.751 364.564 + endloop + endfacet + facet normal 0.19838 -0.371207 0.907111 + outer loop + vertex 401.67 94.751 364.564 + vertex 400.415 96.1698 365.419 + vertex 400.826 95.4702 365.043 + endloop + endfacet + facet normal 0.226958 -0.354436 0.907119 + outer loop + vertex 400.415 96.1698 365.419 + vertex 399.013 97.9871 366.48 + vertex 400.826 95.4702 365.043 + endloop + endfacet + facet normal 0.260889 -0.328601 0.907721 + outer loop + vertex 400.415 96.1698 365.419 + vertex 399.015 98.0975 366.519 + vertex 399.013 97.9871 366.48 + endloop + endfacet + facet normal 0.274331 -0.327596 0.904115 + outer loop + vertex 399.013 97.9871 366.48 + vertex 399.015 98.0975 366.519 + vertex 396.318 102.094 368.786 + endloop + endfacet + facet normal 0.196819 -0.378621 0.904383 + outer loop + vertex 399.013 97.9871 366.48 + vertex 396.318 102.094 368.786 + vertex 397.391 99.888 367.629 + endloop + endfacet + facet normal 0.196145 -0.374728 0.906149 + outer loop + vertex 400.829 95.9629 365.244 + vertex 399.015 98.0975 366.519 + vertex 400.415 96.1698 365.419 + endloop + endfacet + facet normal 0.205724 -0.367168 0.907119 + outer loop + vertex 400.829 95.9629 365.244 + vertex 399.715 97.9312 366.293 + vertex 399.015 98.0975 366.519 + endloop + endfacet + facet normal 0.204338 -0.371193 0.905793 + outer loop + vertex 399.715 97.9312 366.293 + vertex 397.629 100.555 367.839 + vertex 399.015 98.0975 366.519 + endloop + endfacet + facet normal 0.211371 -0.365918 0.906326 + outer loop + vertex 399.715 97.9312 366.293 + vertex 398.617 100.648 367.646 + vertex 397.629 100.555 367.839 + endloop + endfacet + facet normal 0.211415 -0.368984 0.905071 + outer loop + vertex 398.617 100.648 367.646 + vertex 396.596 103.661 369.346 + vertex 397.629 100.555 367.839 + endloop + endfacet + facet normal 0.221056 -0.36537 0.904234 + outer loop + vertex 397.629 100.555 367.839 + vertex 396.596 103.661 369.346 + vertex 396.069 103.063 369.233 + endloop + endfacet + facet normal 0.232198 -0.35843 0.904219 + outer loop + vertex 396.069 103.063 369.233 + vertex 396.318 102.094 368.786 + vertex 397.629 100.555 367.839 + endloop + endfacet + facet normal 0.245531 -0.347516 0.904957 + outer loop + vertex 399.015 98.0975 366.519 + vertex 397.629 100.555 367.839 + vertex 396.318 102.094 368.786 + endloop + endfacet + facet normal 0.296593 -0.337017 0.893561 + outer loop + vertex 396.069 103.063 369.233 + vertex 394.44 107.284 371.366 + vertex 396.318 102.094 368.786 + endloop + endfacet + facet normal 0.234278 -0.363567 0.901628 + outer loop + vertex 396.318 102.094 368.786 + vertex 394.44 107.284 371.366 + vertex 392.951 108.078 372.074 + endloop + endfacet + facet normal 0.198251 -0.38394 0.901824 + outer loop + vertex 396.318 102.094 368.786 + vertex 392.951 108.078 372.074 + vertex 394.558 104.208 370.073 + endloop + endfacet + facet normal 0.227152 -0.374543 0.898955 + outer loop + vertex 394.44 107.284 371.366 + vertex 391.627 113.39 374.621 + vertex 392.951 108.078 372.074 + endloop + endfacet + facet normal 0.24721 -0.368249 0.896259 + outer loop + vertex 392.951 108.078 372.074 + vertex 391.627 113.39 374.621 + vertex 390.5 113.691 375.056 + endloop + endfacet + facet normal 0.199673 -0.39034 0.898758 + outer loop + vertex 392.951 108.078 372.074 + vertex 390.5 113.691 375.056 + vertex 391.527 110.16 373.294 + endloop + endfacet + facet normal 0.244262 -0.375882 0.893895 + outer loop + vertex 391.627 113.39 374.621 + vertex 389.548 119.004 377.55 + vertex 390.5 113.691 375.056 + endloop + endfacet + facet normal 0.265598 -0.370294 0.890135 + outer loop + vertex 390.5 113.691 375.056 + vertex 389.548 119.004 377.55 + vertex 388.52 119.148 377.917 + endloop + endfacet + facet normal 0.228652 -0.385649 0.893864 + outer loop + vertex 390.5 113.691 375.056 + vertex 388.52 119.148 377.917 + vertex 389.201 114.883 375.902 + endloop + endfacet + facet normal 0.263727 -0.37742 0.887695 + outer loop + vertex 389.548 119.004 377.55 + vertex 387.976 124.543 380.372 + vertex 388.52 119.148 377.917 + endloop + endfacet + facet normal 0.281177 -0.373898 0.883821 + outer loop + vertex 388.52 119.148 377.917 + vertex 387.976 124.543 380.372 + vertex 387.086 124.798 380.763 + endloop + endfacet + facet normal 0.235854 -0.388823 0.890612 + outer loop + vertex 388.52 119.148 377.917 + vertex 387.086 124.798 380.763 + vertex 387.16 121.286 379.21 + endloop + endfacet + facet normal 0.278569 -0.380168 0.88197 + outer loop + vertex 387.976 124.543 380.372 + vertex 386.683 130.124 383.186 + vertex 387.086 124.798 380.763 + endloop + endfacet + facet normal 0.286357 -0.378725 0.880095 + outer loop + vertex 387.086 124.798 380.763 + vertex 386.683 130.124 383.186 + vertex 385.754 130.298 383.563 + endloop + endfacet + facet normal 0.244424 -0.392281 0.886776 + outer loop + vertex 387.086 124.798 380.763 + vertex 385.754 130.298 383.563 + vertex 385.893 126.01 381.628 + endloop + endfacet + facet normal 0.284271 -0.385209 0.877954 + outer loop + vertex 386.683 130.124 383.186 + vertex 385.578 135.749 386.012 + vertex 385.754 130.298 383.563 + endloop + endfacet + facet normal 0.295836 -0.38346 0.874894 + outer loop + vertex 385.754 130.298 383.563 + vertex 385.578 135.749 386.012 + vertex 384.745 136.002 386.404 + endloop + endfacet + facet normal 0.248304 -0.39635 0.883884 + outer loop + vertex 385.754 130.298 383.563 + vertex 384.745 136.002 386.404 + vertex 384.594 132.503 384.878 + endloop + endfacet + facet normal 0.293073 -0.389707 0.873061 + outer loop + vertex 385.578 135.749 386.012 + vertex 384.669 141.406 388.842 + vertex 384.745 136.002 386.404 + endloop + endfacet + facet normal 0.303401 -0.38826 0.870173 + outer loop + vertex 384.745 136.002 386.404 + vertex 384.669 141.406 388.842 + vertex 383.832 141.482 389.168 + endloop + endfacet + facet normal 0.256807 -0.400711 0.879478 + outer loop + vertex 384.745 136.002 386.404 + vertex 383.832 141.482 389.168 + vertex 383.79 137.247 387.25 + endloop + endfacet + facet normal 0.301867 -0.394822 0.867751 + outer loop + vertex 384.669 141.406 388.842 + vertex 383.925 147.173 391.725 + vertex 383.832 141.482 389.168 + endloop + endfacet + facet normal 0.306214 -0.394312 0.866459 + outer loop + vertex 383.832 141.482 389.168 + vertex 383.925 147.173 391.725 + vertex 383.085 147.607 392.22 + endloop + endfacet + facet normal 0.259798 -0.405036 0.876613 + outer loop + vertex 383.832 141.482 389.168 + vertex 383.085 147.607 392.22 + vertex 382.787 143.867 390.579 + endloop + endfacet + facet normal 0.301139 -0.402077 0.864667 + outer loop + vertex 383.925 147.173 391.725 + vertex 383.301 153.034 394.668 + vertex 383.085 147.607 392.22 + endloop + endfacet + facet normal 0.300732 -0.402116 0.864791 + outer loop + vertex 383.085 147.607 392.22 + vertex 383.301 153.034 394.668 + vertex 382.483 153.411 395.127 + endloop + endfacet + facet normal 0.252522 -0.412383 0.875313 + outer loop + vertex 383.085 147.607 392.22 + vertex 382.483 153.411 395.127 + vertex 382.336 149.864 393.498 + endloop + endfacet + facet normal 0.295642 -0.410492 0.862608 + outer loop + vertex 383.301 153.034 394.668 + vertex 382.811 158.95 397.651 + vertex 382.483 153.411 395.127 + endloop + endfacet + facet normal 0.307615 -0.409504 0.858883 + outer loop + vertex 382.483 153.411 395.127 + vertex 382.811 158.95 397.651 + vertex 382.098 159.183 398.017 + endloop + endfacet + facet normal 0.253808 -0.419452 0.871574 + outer loop + vertex 382.483 153.411 395.127 + vertex 382.098 159.183 398.017 + vertex 381.65 155.555 396.402 + endloop + endfacet + facet normal 0.305151 -0.414585 0.857323 + outer loop + vertex 382.811 158.95 397.651 + vertex 382.434 164.956 400.689 + vertex 382.098 159.183 398.017 + endloop + endfacet + facet normal 0.320972 -0.413147 0.852225 + outer loop + vertex 382.098 159.183 398.017 + vertex 382.434 164.956 400.689 + vertex 381.755 165.135 401.032 + endloop + endfacet + facet normal 0.269333 -0.422743 0.865302 + outer loop + vertex 382.098 159.183 398.017 + vertex 381.755 165.135 401.032 + vertex 381.271 160.555 398.945 + endloop + endfacet + facet normal 0.320878 -0.413367 0.852153 + outer loop + vertex 382.434 164.956 400.689 + vertex 382.018 170.807 403.684 + vertex 381.755 165.135 401.032 + endloop + endfacet + facet normal 0.319482 -0.413514 0.852606 + outer loop + vertex 381.755 165.135 401.032 + vertex 382.018 170.807 403.684 + vertex 381.358 170.899 403.977 + endloop + endfacet + facet normal 0.278121 -0.421693 0.863032 + outer loop + vertex 381.755 165.135 401.032 + vertex 381.358 170.899 403.977 + vertex 380.961 167.37 402.38 + endloop + endfacet + facet normal 0.322009 -0.405141 0.85567 + outer loop + vertex 382.018 170.807 403.684 + vertex 381.139 175.46 406.218 + vertex 381.358 170.899 403.977 + endloop + endfacet + facet normal 0.288299 -0.411216 0.864745 + outer loop + vertex 381.358 170.899 403.977 + vertex 381.139 175.46 406.218 + vertex 380.531 174.958 406.182 + endloop + endfacet + facet normal 0.270036 -0.416707 0.868007 + outer loop + vertex 381.358 170.899 403.977 + vertex 380.531 174.958 406.182 + vertex 380.449 172.516 405.035 + endloop + endfacet + facet normal 0.274725 -0.395598 0.876372 + outer loop + vertex 380.531 174.958 406.182 + vertex 381.139 175.46 406.218 + vertex 379.276 178.101 407.994 + endloop + endfacet + facet normal 0.235117 -0.422759 0.875211 + outer loop + vertex 379.276 178.101 407.994 + vertex 381.139 175.46 406.218 + vertex 380.884 179.713 408.341 + endloop + endfacet + facet normal 0.24276 -0.429255 0.869947 + outer loop + vertex 380.884 179.713 408.341 + vertex 379.863 180.729 409.127 + vertex 379.276 178.101 407.994 + endloop + endfacet + facet normal 0.126704 -0.416428 0.900296 + outer loop + vertex 379.603 181.16 409.363 + vertex 379.276 178.101 407.994 + vertex 379.863 180.729 409.127 + endloop + endfacet + facet normal 0.0438124 -0.459309 0.887196 + outer loop + vertex 379.863 180.729 409.127 + vertex 379.768 181.435 409.497 + vertex 379.603 181.16 409.363 + endloop + endfacet + facet normal -0.205818 0.526466 -0.824908 + outer loop + vertex 379.768 181.435 409.497 + vertex 380.191 181.347 409.336 + vertex 379.603 181.16 409.363 + endloop + endfacet + facet normal -0.0451659 0.282114 0.958317 + outer loop + vertex 380.191 181.347 409.336 + vertex 381.344 181.86 409.239 + vertex 379.603 181.16 409.363 + endloop + endfacet + facet normal 0.259637 -0.419483 0.86984 + outer loop + vertex 380.884 179.713 408.341 + vertex 381.344 181.86 409.239 + vertex 380.191 181.347 409.336 + endloop + endfacet + facet normal 0.266744 -0.419999 0.867438 + outer loop + vertex 382.315 180.93 408.491 + vertex 381.344 181.86 409.239 + vertex 380.884 179.713 408.341 + endloop + endfacet + facet normal 0.268859 -0.422266 0.865683 + outer loop + vertex 382.315 180.93 408.491 + vertex 380.884 179.713 408.341 + vertex 382.443 176.97 406.519 + endloop + endfacet + facet normal 0.302718 -0.416878 0.857073 + outer loop + vertex 383.995 181.067 407.964 + vertex 382.315 180.93 408.491 + vertex 382.443 176.97 406.519 + endloop + endfacet + facet normal 0.308809 -0.418192 0.854255 + outer loop + vertex 382.443 176.97 406.519 + vertex 384.288 177.177 405.953 + vertex 383.995 181.067 407.964 + endloop + endfacet + facet normal 0.338294 -0.411791 0.846159 + outer loop + vertex 386.322 181.851 407.415 + vertex 383.995 181.067 407.964 + vertex 384.288 177.177 405.953 + endloop + endfacet + facet normal 0.336384 -0.411276 0.847171 + outer loop + vertex 384.288 177.177 405.953 + vertex 385.86 177.384 405.43 + vertex 386.322 181.851 407.415 + endloop + endfacet + facet normal 0.336314 -0.413855 0.845941 + outer loop + vertex 384.574 172.182 403.396 + vertex 385.86 177.384 405.43 + vertex 384.288 177.177 405.953 + endloop + endfacet + facet normal 0.323998 -0.416383 0.8495 + outer loop + vertex 384.574 172.182 403.396 + vertex 384.288 177.177 405.953 + vertex 383.049 171.361 403.575 + endloop + endfacet + facet normal 0.32302 -0.414257 0.850911 + outer loop + vertex 383.44 165.496 400.571 + vertex 384.574 172.182 403.396 + vertex 383.049 171.361 403.575 + endloop + endfacet + facet normal 0.322352 -0.414397 0.851096 + outer loop + vertex 383.44 165.496 400.571 + vertex 383.049 171.361 403.575 + vertex 382.434 164.956 400.689 + endloop + endfacet + facet normal 0.336934 -0.414317 0.845468 + outer loop + vertex 385.032 166.72 400.537 + vertex 384.574 172.182 403.396 + vertex 383.44 165.496 400.571 + endloop + endfacet + facet normal 0.333134 -0.409265 0.849426 + outer loop + vertex 383.876 159.52 397.521 + vertex 385.032 166.72 400.537 + vertex 383.44 165.496 400.571 + endloop + endfacet + facet normal 0.323974 -0.41125 0.852006 + outer loop + vertex 383.876 159.52 397.521 + vertex 383.44 165.496 400.571 + vertex 382.811 158.95 397.651 + endloop + endfacet + facet normal 0.344741 -0.409198 0.844814 + outer loop + vertex 385.527 160.883 397.507 + vertex 385.032 166.72 400.537 + vertex 383.876 159.52 397.521 + endloop + endfacet + facet normal 0.338795 -0.401935 0.850686 + outer loop + vertex 384.39 153.588 394.513 + vertex 385.527 160.883 397.507 + vertex 383.876 159.52 397.521 + endloop + endfacet + facet normal 0.326735 -0.404704 0.854084 + outer loop + vertex 384.39 153.588 394.513 + vertex 383.876 159.52 397.521 + vertex 383.301 153.034 394.668 + endloop + endfacet + facet normal 0.348865 -0.401847 0.846648 + outer loop + vertex 386.046 155.028 394.515 + vertex 385.527 160.883 397.507 + vertex 384.39 153.588 394.513 + endloop + endfacet + facet normal 0.341469 -0.39335 0.853624 + outer loop + vertex 384.995 147.777 391.594 + vertex 386.046 155.028 394.515 + vertex 384.39 153.588 394.513 + endloop + endfacet + facet normal 0.328791 -0.396447 0.857161 + outer loop + vertex 384.995 147.777 391.594 + vertex 384.39 153.588 394.513 + vertex 383.925 147.173 391.725 + endloop + endfacet + facet normal 0.347488 -0.39326 0.851234 + outer loop + vertex 386.643 149.286 391.618 + vertex 386.046 155.028 394.515 + vertex 384.995 147.777 391.594 + endloop + endfacet + facet normal 0.339673 -0.384845 0.858205 + outer loop + vertex 385.738 142.07 388.741 + vertex 386.643 149.286 391.618 + vertex 384.995 147.777 391.594 + endloop + endfacet + facet normal 0.323631 -0.389074 0.862487 + outer loop + vertex 385.738 142.07 388.741 + vertex 384.995 147.777 391.594 + vertex 384.669 141.406 388.842 + endloop + endfacet + facet normal 0.341686 -0.384789 0.857431 + outer loop + vertex 387.394 143.625 388.779 + vertex 386.643 149.286 391.618 + vertex 385.738 142.07 388.741 + endloop + endfacet + facet normal 0.334574 -0.377367 0.863513 + outer loop + vertex 386.677 136.427 385.911 + vertex 387.394 143.625 388.779 + vertex 385.738 142.07 388.741 + endloop + endfacet + facet normal 0.316059 -0.382749 0.868107 + outer loop + vertex 386.677 136.427 385.911 + vertex 385.738 142.07 388.741 + vertex 385.578 135.749 386.012 + endloop + endfacet + facet normal 0.335465 -0.377325 0.863185 + outer loop + vertex 388.328 137.991 385.953 + vertex 387.394 143.625 388.779 + vertex 386.677 136.427 385.911 + endloop + endfacet + facet normal 0.329162 -0.370814 0.868418 + outer loop + vertex 387.789 130.799 383.086 + vertex 388.328 137.991 385.953 + vertex 386.677 136.427 385.911 + endloop + endfacet + facet normal 0.309135 -0.377101 0.873058 + outer loop + vertex 387.789 130.799 383.086 + vertex 386.677 136.427 385.911 + vertex 386.683 130.124 383.186 + endloop + endfacet + facet normal 0.327332 -0.370933 0.869059 + outer loop + vertex 389.457 132.397 383.14 + vertex 388.328 137.991 385.953 + vertex 387.789 130.799 383.086 + endloop + endfacet + facet normal 0.321021 -0.364514 0.874114 + outer loop + vertex 389.126 125.242 380.278 + vertex 389.457 132.397 383.14 + vertex 387.789 130.799 383.086 + endloop + endfacet + facet normal 0.298412 -0.372331 0.878817 + outer loop + vertex 389.126 125.242 380.278 + vertex 387.789 130.799 383.086 + vertex 387.976 124.543 380.372 + endloop + endfacet + facet normal 0.31539 -0.364993 0.875962 + outer loop + vertex 390.858 126.892 380.341 + vertex 389.457 132.397 383.14 + vertex 389.126 125.242 380.278 + endloop + endfacet + facet normal 0.30816 -0.357615 0.88156 + outer loop + vertex 390.84 119.733 377.443 + vertex 390.858 126.892 380.341 + vertex 389.126 125.242 380.278 + endloop + endfacet + facet normal 0.280799 -0.368516 0.886199 + outer loop + vertex 390.84 119.733 377.443 + vertex 389.126 125.242 380.278 + vertex 389.548 119.004 377.55 + endloop + endfacet + facet normal 0.298487 -0.358749 0.884423 + outer loop + vertex 392.688 121.457 377.519 + vertex 390.858 126.892 380.341 + vertex 390.84 119.733 377.443 + endloop + endfacet + facet normal 0.291128 -0.351104 0.889927 + outer loop + vertex 393.148 114.16 374.49 + vertex 392.688 121.457 377.519 + vertex 390.84 119.733 377.443 + endloop + endfacet + facet normal 0.261884 -0.365053 0.893394 + outer loop + vertex 393.148 114.16 374.49 + vertex 390.84 119.733 377.443 + vertex 391.627 113.39 374.621 + endloop + endfacet + facet normal 0.281007 -0.352811 0.892502 + outer loop + vertex 395.164 116.123 374.631 + vertex 392.688 121.457 377.519 + vertex 393.148 114.16 374.49 + endloop + endfacet + facet normal 0.274199 -0.346159 0.897211 + outer loop + vertex 396.086 108.534 371.421 + vertex 395.164 116.123 374.631 + vertex 393.148 114.16 374.49 + endloop + endfacet + facet normal 0.245137 -0.362421 0.899199 + outer loop + vertex 396.086 108.534 371.421 + vertex 393.148 114.16 374.49 + vertex 394.44 107.284 371.366 + endloop + endfacet + facet normal 0.242125 -0.358559 0.90156 + outer loop + vertex 396.086 108.534 371.421 + vertex 394.44 107.284 371.366 + vertex 396.596 103.661 369.346 + endloop + endfacet + facet normal 0.222485 -0.362153 0.905177 + outer loop + vertex 397.815 103.701 369.063 + vertex 396.086 108.534 371.421 + vertex 396.596 103.661 369.346 + endloop + endfacet + facet normal 0.232972 -0.357934 0.904216 + outer loop + vertex 397.815 103.701 369.063 + vertex 398.745 105.456 369.518 + vertex 396.086 108.534 371.421 + endloop + endfacet + facet normal 0.251825 -0.342274 0.905225 + outer loop + vertex 398.334 110.924 371.7 + vertex 396.086 108.534 371.421 + vertex 398.745 105.456 369.518 + endloop + endfacet + facet normal 0.233904 -0.345107 0.90895 + outer loop + vertex 400.219 106.252 369.441 + vertex 398.334 110.924 371.7 + vertex 398.745 105.456 369.518 + endloop + endfacet + facet normal 0.233814 -0.344934 0.909039 + outer loop + vertex 400.933 102.842 367.963 + vertex 400.219 106.252 369.441 + vertex 398.745 105.456 369.518 + endloop + endfacet + facet normal 0.219112 -0.356715 0.908154 + outer loop + vertex 400.933 102.842 367.963 + vertex 398.745 105.456 369.518 + vertex 399.725 101.541 367.744 + endloop + endfacet + facet normal 0.215396 -0.353617 0.910252 + outer loop + vertex 401.739 99.587 366.508 + vertex 400.933 102.842 367.963 + vertex 399.725 101.541 367.744 + endloop + endfacet + facet normal 0.204469 -0.363913 0.908713 + outer loop + vertex 401.739 99.587 366.508 + vertex 399.725 101.541 367.744 + vertex 400.647 98.4946 366.316 + endloop + endfacet + facet normal 0.201066 -0.360857 0.910689 + outer loop + vertex 402.398 97.0414 365.354 + vertex 401.739 99.587 366.508 + vertex 400.647 98.4946 366.316 + endloop + endfacet + facet normal 0.192133 -0.370369 0.908797 + outer loop + vertex 402.398 97.0414 365.354 + vertex 400.647 98.4946 366.316 + vertex 401.52 96.2001 365.197 + endloop + endfacet + facet normal 0.191783 -0.370043 0.909003 + outer loop + vertex 402.98 95.176 364.472 + vertex 402.398 97.0414 365.354 + vertex 401.52 96.2001 365.197 + endloop + endfacet + facet normal 0.185801 -0.377328 0.907249 + outer loop + vertex 402.98 95.176 364.472 + vertex 401.52 96.2001 365.197 + vertex 402.166 94.6746 364.43 + endloop + endfacet + facet normal 0.191193 -0.385684 0.902603 + outer loop + vertex 402.98 95.176 364.472 + vertex 402.166 94.6746 364.43 + vertex 403.337 92.4562 363.234 + endloop + endfacet + facet normal 0.190234 -0.385867 0.902728 + outer loop + vertex 403.337 92.4562 363.234 + vertex 404.468 95.5716 364.327 + vertex 402.98 95.176 364.472 + endloop + endfacet + facet normal 0.187342 -0.372756 0.908821 + outer loop + vertex 403.634 96.459 364.863 + vertex 402.98 95.176 364.472 + vertex 404.468 95.5716 364.327 + endloop + endfacet + facet normal 0.197347 -0.364173 0.910182 + outer loop + vertex 404.669 97.5996 365.095 + vertex 403.634 96.459 364.863 + vertex 404.468 95.5716 364.327 + endloop + endfacet + facet normal 0.203423 -0.364254 0.908811 + outer loop + vertex 404.468 95.5716 364.327 + vertex 406.037 98.1051 364.991 + vertex 404.669 97.5996 365.095 + endloop + endfacet + facet normal 0.198919 -0.350776 0.915089 + outer loop + vertex 405.641 99.1601 365.482 + vertex 404.669 97.5996 365.095 + vertex 406.037 98.1051 364.991 + endloop + endfacet + facet normal 0.217248 -0.343277 0.913764 + outer loop + vertex 406.81 100.546 365.725 + vertex 405.641 99.1601 365.482 + vertex 406.037 98.1051 364.991 + endloop + endfacet + facet normal 0.206282 -0.340842 0.91721 + outer loop + vertex 406.037 98.1051 364.991 + vertex 407.772 100.545 365.508 + vertex 406.81 100.546 365.725 + endloop + endfacet + facet normal 0.207905 -0.320101 0.92429 + outer loop + vertex 408.228 102.65 366.134 + vertex 406.81 100.546 365.725 + vertex 407.772 100.545 365.508 + endloop + endfacet + facet normal 0.207314 -0.32002 0.92445 + outer loop + vertex 407.772 100.545 365.508 + vertex 409.255 102.856 365.975 + vertex 408.228 102.65 366.134 + endloop + endfacet + facet normal 0.204014 -0.297229 0.932756 + outer loop + vertex 409.619 104.763 366.503 + vertex 408.228 102.65 366.134 + vertex 409.255 102.856 365.975 + endloop + endfacet + facet normal 0.192323 -0.295804 0.935688 + outer loop + vertex 409.255 102.856 365.975 + vertex 410.13 104.331 366.262 + vertex 409.619 104.763 366.503 + endloop + endfacet + facet normal 0.209152 -0.27711 0.937798 + outer loop + vertex 410.13 104.331 366.262 + vertex 410.928 106 366.577 + vertex 409.619 104.763 366.503 + endloop + endfacet + facet normal 0.207977 -0.275903 0.938415 + outer loop + vertex 410.263 108.397 367.429 + vertex 409.619 104.763 366.503 + vertex 410.928 106 366.577 + endloop + endfacet + facet normal 0.225911 -0.270054 0.935968 + outer loop + vertex 410.928 106 366.577 + vertex 411.747 107.781 366.893 + vertex 410.263 108.397 367.429 + endloop + endfacet + facet normal 0.239398 -0.241407 0.940431 + outer loop + vertex 411.747 107.781 366.893 + vertex 412.682 110.056 367.239 + vertex 410.263 108.397 367.429 + endloop + endfacet + facet normal 0.236512 -0.236987 0.942284 + outer loop + vertex 411.858 112.945 368.173 + vertex 410.263 108.397 367.429 + vertex 412.682 110.056 367.239 + endloop + endfacet + facet normal 0.244948 -0.243393 0.938488 + outer loop + vertex 412.682 110.056 367.239 + vertex 411.747 107.781 366.893 + vertex 413.092 107.244 366.403 + endloop + endfacet + facet normal 0.241481 -0.24411 0.9392 + outer loop + vertex 413.092 107.244 366.403 + vertex 415.1 111.295 366.939 + vertex 412.682 110.056 367.239 + endloop + endfacet + facet normal 0.226109 -0.211276 0.950914 + outer loop + vertex 414.112 113.742 367.718 + vertex 412.682 110.056 367.239 + vertex 415.1 111.295 366.939 + endloop + endfacet + facet normal 0.245284 -0.202612 0.948042 + outer loop + vertex 415.1 111.295 366.939 + vertex 416.388 114.858 367.368 + vertex 414.112 113.742 367.718 + endloop + endfacet + facet normal 0.235463 -0.180396 0.954994 + outer loop + vertex 415.369 117.279 368.076 + vertex 414.112 113.742 367.718 + vertex 416.388 114.858 367.368 + endloop + endfacet + facet normal 0.257849 -0.169844 0.95114 + outer loop + vertex 416.388 114.858 367.368 + vertex 417.383 118.303 367.713 + vertex 415.369 117.279 368.076 + endloop + endfacet + facet normal 0.252567 -0.158253 0.95455 + outer loop + vertex 416.2 120.65 368.415 + vertex 415.369 117.279 368.076 + vertex 417.383 118.303 367.713 + endloop + endfacet + facet normal 0.276981 -0.144558 0.949939 + outer loop + vertex 417.383 118.303 367.713 + vertex 418.06 121.737 368.038 + vertex 416.2 120.65 368.415 + endloop + endfacet + facet normal 0.275435 -0.141603 0.950833 + outer loop + vertex 416.443 124.192 368.873 + vertex 416.2 120.65 368.415 + vertex 418.06 121.737 368.038 + endloop + endfacet + facet normal 0.303115 -0.121447 0.945183 + outer loop + vertex 418.06 121.737 368.038 + vertex 418.443 125.256 368.368 + vertex 416.443 124.192 368.873 + endloop + endfacet + facet normal 0.300931 -0.116727 0.946475 + outer loop + vertex 416.419 128.192 369.373 + vertex 416.443 124.192 368.873 + vertex 418.443 125.256 368.368 + endloop + endfacet + facet normal 0.325443 -0.0977824 0.940492 + outer loop + vertex 418.443 125.256 368.368 + vertex 418.798 128.743 368.607 + vertex 416.419 128.192 369.373 + endloop + endfacet + facet normal 0.3219 -0.0782551 0.943534 + outer loop + vertex 417.321 131.112 369.308 + vertex 416.419 128.192 369.373 + vertex 418.798 128.743 368.607 + endloop + endfacet + facet normal 0.323318 -0.0772524 0.943132 + outer loop + vertex 418.798 128.743 368.607 + vertex 419.122 132.22 368.781 + vertex 417.321 131.112 369.308 + endloop + endfacet + facet normal 0.321917 -0.0746479 0.943821 + outer loop + vertex 417.329 134.62 369.583 + vertex 417.321 131.112 369.308 + vertex 419.122 132.22 368.781 + endloop + endfacet + facet normal 0.333419 -0.06496 0.940538 + outer loop + vertex 419.122 132.22 368.781 + vertex 419.382 135.784 368.935 + vertex 417.329 134.62 369.583 + endloop + endfacet + facet normal 0.330683 -0.0593958 0.941871 + outer loop + vertex 417.846 137.933 369.61 + vertex 417.329 134.62 369.583 + vertex 419.382 135.784 368.935 + endloop + endfacet + facet normal 0.336216 -0.0549133 0.940183 + outer loop + vertex 419.382 135.784 368.935 + vertex 419.649 139.339 369.047 + vertex 417.846 137.933 369.61 + endloop + endfacet + facet normal 0.336948 -0.0559824 0.939857 + outer loop + vertex 417.891 141.556 369.81 + vertex 417.846 137.933 369.61 + vertex 419.649 139.339 369.047 + endloop + endfacet + facet normal 0.344495 -0.0491874 0.937499 + outer loop + vertex 419.649 139.339 369.047 + vertex 419.919 142.762 369.128 + vertex 417.891 141.556 369.81 + endloop + endfacet + facet normal 0.342348 -0.0450174 0.938494 + outer loop + vertex 418.44 144.525 369.752 + vertex 417.891 141.556 369.81 + vertex 419.919 142.762 369.128 + endloop + endfacet + facet normal 0.338421 -0.0487505 0.939731 + outer loop + vertex 419.919 142.762 369.128 + vertex 419.952 145.969 369.282 + vertex 418.44 144.525 369.752 + endloop + endfacet + facet normal 0.335917 -0.0457861 0.940778 + outer loop + vertex 418.309 146.048 369.873 + vertex 418.44 144.525 369.752 + vertex 419.952 145.969 369.282 + endloop + endfacet + facet normal 0.335437 -0.0538635 0.940522 + outer loop + vertex 418.559 147.397 369.861 + vertex 418.309 146.048 369.873 + vertex 419.952 145.969 369.282 + endloop + endfacet + facet normal 0.306172 -0.0854834 0.94813 + outer loop + vertex 419.952 145.969 369.282 + vertex 420.203 148.966 369.471 + vertex 418.559 147.397 369.861 + endloop + endfacet + facet normal 0.330644 -0.113913 0.936855 + outer loop + vertex 418.229 149.86 370.277 + vertex 418.559 147.397 369.861 + vertex 420.203 148.966 369.471 + endloop + endfacet + facet normal 0.319138 -0.139754 0.937347 + outer loop + vertex 419.55 151.67 370.097 + vertex 418.229 149.86 370.277 + vertex 420.203 148.966 369.471 + endloop + endfacet + facet normal 0.187465 -0.178133 0.965984 + outer loop + vertex 419.55 151.67 370.097 + vertex 420.203 148.966 369.471 + vertex 423.358 151.531 369.332 + endloop + endfacet + facet normal 0.177155 -0.301128 0.936984 + outer loop + vertex 420.298 153.148 370.43 + vertex 419.55 151.67 370.097 + vertex 423.358 151.531 369.332 + endloop + endfacet + facet normal 0.206805 -0.202394 0.957219 + outer loop + vertex 420.203 148.966 369.471 + vertex 422.754 147.84 368.682 + vertex 423.358 151.531 369.332 + endloop + endfacet + facet normal 0.207214 -0.202443 0.95712 + outer loop + vertex 426.186 150.37 368.474 + vertex 423.358 151.531 369.332 + vertex 422.754 147.84 368.682 + endloop + endfacet + facet normal 0.194218 -0.184281 0.963493 + outer loop + vertex 422.754 147.84 368.682 + vertex 425.822 146.549 367.817 + vertex 426.186 150.37 368.474 + endloop + endfacet + facet normal 0.188792 -0.18396 0.964633 + outer loop + vertex 425.822 146.549 367.817 + vertex 430.13 149.162 367.472 + vertex 426.186 150.37 368.474 + endloop + endfacet + facet normal 0.180761 -0.170187 0.968691 + outer loop + vertex 429.507 145.448 366.936 + vertex 430.13 149.162 367.472 + vertex 425.822 146.549 367.817 + endloop + endfacet + facet normal 0.208325 -0.0826304 0.974563 + outer loop + vertex 425.398 142.972 367.604 + vertex 429.507 145.448 366.936 + vertex 425.822 146.549 367.817 + endloop + endfacet + facet normal 0.233561 -0.0852702 0.968596 + outer loop + vertex 425.398 142.972 367.604 + vertex 425.822 146.549 367.817 + vertex 422.424 144.404 368.447 + endloop + endfacet + facet normal 0.251599 -0.0467187 0.966703 + outer loop + vertex 422.137 140.951 368.355 + vertex 425.398 142.972 367.604 + vertex 422.424 144.404 368.447 + endloop + endfacet + facet normal 0.292008 -0.049772 0.95512 + outer loop + vertex 422.137 140.951 368.355 + vertex 422.424 144.404 368.447 + vertex 419.919 142.762 369.128 + endloop + endfacet + facet normal 0.251568 -0.0466646 0.966714 + outer loop + vertex 425.093 139.439 367.513 + vertex 425.398 142.972 367.604 + vertex 422.137 140.951 368.355 + endloop + endfacet + facet normal 0.253048 -0.0436334 0.966469 + outer loop + vertex 421.863 137.414 368.267 + vertex 425.093 139.439 367.513 + vertex 422.137 140.951 368.355 + endloop + endfacet + facet normal 0.295645 -0.046626 0.954159 + outer loop + vertex 421.863 137.414 368.267 + vertex 422.137 140.951 368.355 + vertex 419.649 139.339 369.047 + endloop + endfacet + facet normal 0.253192 -0.0438802 0.96642 + outer loop + vertex 424.859 135.893 367.413 + vertex 425.093 139.439 367.513 + vertex 421.863 137.414 368.267 + endloop + endfacet + facet normal 0.249904 -0.0506508 0.966945 + outer loop + vertex 421.617 133.835 368.143 + vertex 424.859 135.893 367.413 + vertex 421.863 137.414 368.267 + endloop + endfacet + facet normal 0.291984 -0.0531278 0.954946 + outer loop + vertex 421.617 133.835 368.143 + vertex 421.863 137.414 368.267 + vertex 419.382 135.784 368.935 + endloop + endfacet + facet normal 0.249643 -0.0502064 0.967036 + outer loop + vertex 424.629 132.352 367.289 + vertex 424.859 135.893 367.413 + vertex 421.617 133.835 368.143 + endloop + endfacet + facet normal 0.244564 -0.0609098 0.967718 + outer loop + vertex 421.349 130.278 367.987 + vertex 424.629 132.352 367.289 + vertex 421.617 133.835 368.143 + endloop + endfacet + facet normal 0.285559 -0.0634973 0.956255 + outer loop + vertex 421.349 130.278 367.987 + vertex 421.617 133.835 368.143 + vertex 419.122 132.22 368.781 + endloop + endfacet + facet normal 0.244599 -0.0609699 0.967705 + outer loop + vertex 424.341 128.836 367.14 + vertex 424.629 132.352 367.289 + vertex 421.349 130.278 367.987 + endloop + endfacet + facet normal 0.238003 -0.0750392 0.968361 + outer loop + vertex 421.016 126.768 367.797 + vertex 424.341 128.836 367.14 + vertex 421.349 130.278 367.987 + endloop + endfacet + facet normal 0.279813 -0.0783835 0.956849 + outer loop + vertex 421.016 126.768 367.797 + vertex 421.349 130.278 367.987 + vertex 418.798 128.743 368.607 + endloop + endfacet + facet normal 0.237923 -0.0749008 0.968392 + outer loop + vertex 423.993 125.37 366.957 + vertex 424.341 128.836 367.14 + vertex 421.016 126.768 367.797 + endloop + endfacet + facet normal 0.229338 -0.0934631 0.968849 + outer loop + vertex 420.587 123.292 367.563 + vertex 423.993 125.37 366.957 + vertex 421.016 126.768 367.797 + endloop + endfacet + facet normal 0.269904 -0.0977307 0.957915 + outer loop + vertex 420.587 123.292 367.563 + vertex 421.016 126.768 367.797 + vertex 418.443 125.256 368.368 + endloop + endfacet + facet normal 0.229598 -0.0939196 0.968743 + outer loop + vertex 423.516 121.919 366.736 + vertex 423.993 125.37 366.957 + vertex 420.587 123.292 367.563 + endloop + endfacet + facet normal 0.220222 -0.113938 0.968772 + outer loop + vertex 420 119.856 367.293 + vertex 423.516 121.919 366.736 + vertex 420.587 123.292 367.563 + endloop + endfacet + facet normal 0.253678 -0.118955 0.959947 + outer loop + vertex 420 119.856 367.293 + vertex 420.587 123.292 367.563 + vertex 418.06 121.737 368.038 + endloop + endfacet + facet normal 0.221307 -0.115917 0.96829 + outer loop + vertex 422.949 118.521 366.459 + vertex 423.516 121.919 366.736 + vertex 420 119.856 367.293 + endloop + endfacet + facet normal 0.211409 -0.137407 0.967691 + outer loop + vertex 419.237 116.463 366.978 + vertex 422.949 118.521 366.459 + vertex 420 119.856 367.293 + endloop + endfacet + facet normal 0.239194 -0.14298 0.960387 + outer loop + vertex 419.237 116.463 366.978 + vertex 420 119.856 367.293 + vertex 417.383 118.303 367.713 + endloop + endfacet + facet normal 0.214163 -0.14272 0.966315 + outer loop + vertex 422.247 115.16 366.118 + vertex 422.949 118.521 366.459 + vertex 419.237 116.463 366.978 + endloop + endfacet + facet normal 0.203612 -0.166141 0.964852 + outer loop + vertex 418.281 113.068 366.595 + vertex 422.247 115.16 366.118 + vertex 419.237 116.463 366.978 + endloop + endfacet + facet normal 0.22835 -0.172359 0.958201 + outer loop + vertex 418.281 113.068 366.595 + vertex 419.237 116.463 366.978 + vertex 416.388 114.858 367.368 + endloop + endfacet + facet normal 0.207099 -0.173205 0.962866 + outer loop + vertex 421.421 111.843 365.699 + vertex 422.247 115.16 366.118 + vertex 418.281 113.068 366.595 + endloop + endfacet + facet normal 0.195912 -0.19983 0.960045 + outer loop + vertex 417.113 109.618 366.115 + vertex 421.421 111.843 365.699 + vertex 418.281 113.068 366.595 + endloop + endfacet + facet normal 0.218552 -0.20661 0.953702 + outer loop + vertex 417.113 109.618 366.115 + vertex 418.281 113.068 366.595 + vertex 415.1 111.295 366.939 + endloop + endfacet + facet normal 0.198095 -0.204317 0.958652 + outer loop + vertex 420.491 108.567 365.193 + vertex 421.421 111.843 365.699 + vertex 417.113 109.618 366.115 + endloop + endfacet + facet normal 0.188369 -0.231796 0.954352 + outer loop + vertex 415.872 106.197 365.529 + vertex 420.491 108.567 365.193 + vertex 417.113 109.618 366.115 + endloop + endfacet + facet normal 0.208527 -0.23812 0.948586 + outer loop + vertex 415.872 106.197 365.529 + vertex 417.113 109.618 366.115 + vertex 413.092 107.244 366.403 + endloop + endfacet + facet normal 0.19571 -0.267808 0.943386 + outer loop + vertex 411.859 103.537 365.606 + vertex 415.872 106.197 365.529 + vertex 413.092 107.244 366.403 + endloop + endfacet + facet normal 0.218884 -0.274031 0.936481 + outer loop + vertex 410.638 104.167 366.076 + vertex 411.859 103.537 365.606 + vertex 413.092 107.244 366.403 + endloop + endfacet + facet normal 0.241897 -0.291217 0.925569 + outer loop + vertex 410.928 106 366.577 + vertex 410.638 104.167 366.076 + vertex 413.092 107.244 366.403 + endloop + endfacet + facet normal 0.202923 -0.301397 0.931655 + outer loop + vertex 409.225 101.525 365.529 + vertex 411.859 103.537 365.606 + vertex 410.638 104.167 366.076 + endloop + endfacet + facet normal 0.230504 -0.313948 0.921034 + outer loop + vertex 409.225 101.525 365.529 + vertex 410.638 104.167 366.076 + vertex 409.255 102.856 365.975 + endloop + endfacet + facet normal 0.18803 -0.282258 0.940731 + outer loop + vertex 410.017 101.53 365.372 + vertex 411.859 103.537 365.606 + vertex 409.225 101.525 365.529 + endloop + endfacet + facet normal 0.186748 -0.306287 0.933442 + outer loop + vertex 410.017 101.53 365.372 + vertex 409.225 101.525 365.529 + vertex 409.121 100.02 365.056 + endloop + endfacet + facet normal 0.18765 -0.306753 0.933108 + outer loop + vertex 409.121 100.02 365.056 + vertex 411.336 101.279 365.025 + vertex 410.017 101.53 365.372 + endloop + endfacet + facet normal 0.186312 -0.304373 0.934155 + outer loop + vertex 410.482 99.2479 364.533 + vertex 411.336 101.279 365.025 + vertex 409.121 100.02 365.056 + endloop + endfacet + facet normal 0.178316 -0.316747 0.931598 + outer loop + vertex 408.434 98.3863 364.632 + vertex 410.482 99.2479 364.533 + vertex 409.121 100.02 365.056 + endloop + endfacet + facet normal 0.173872 -0.315229 0.932952 + outer loop + vertex 408.434 98.3863 364.632 + vertex 409.121 100.02 365.056 + vertex 407.444 98.681 364.916 + endloop + endfacet + facet normal 0.168048 -0.330658 0.928669 + outer loop + vertex 408.434 98.3863 364.632 + vertex 407.444 98.681 364.916 + vertex 407.462 96.993 364.312 + endloop + endfacet + facet normal 0.171921 -0.333003 0.92712 + outer loop + vertex 407.462 96.993 364.312 + vertex 409.548 97.5354 364.12 + vertex 408.434 98.3863 364.632 + endloop + endfacet + facet normal 0.173375 -0.339528 0.924479 + outer loop + vertex 408.773 96.1576 363.759 + vertex 409.548 97.5354 364.12 + vertex 407.462 96.993 364.312 + endloop + endfacet + facet normal 0.168164 -0.346605 0.922814 + outer loop + vertex 406.921 95.721 363.933 + vertex 408.773 96.1576 363.759 + vertex 407.462 96.993 364.312 + endloop + endfacet + facet normal 0.167441 -0.346364 0.923036 + outer loop + vertex 406.921 95.721 363.933 + vertex 407.462 96.993 364.312 + vertex 405.941 96.1672 364.278 + endloop + endfacet + facet normal 0.160925 -0.358098 0.919711 + outer loop + vertex 406.921 95.721 363.933 + vertex 405.941 96.1672 364.278 + vertex 406.247 94.7463 363.671 + endloop + endfacet + facet normal 0.166049 -0.361086 0.91763 + outer loop + vertex 406.247 94.7463 363.671 + vertex 408.137 95.007 363.432 + vertex 406.921 95.721 363.933 + endloop + endfacet + facet normal 0.166415 -0.365351 0.915874 + outer loop + vertex 407.796 94.0394 363.108 + vertex 408.137 95.007 363.432 + vertex 406.247 94.7463 363.671 + endloop + endfacet + facet normal 0.164702 -0.368382 0.914969 + outer loop + vertex 406.226 93.8124 363.299 + vertex 407.796 94.0394 363.108 + vertex 406.247 94.7463 363.671 + endloop + endfacet + facet normal 0.163758 -0.368423 0.915122 + outer loop + vertex 406.226 93.8124 363.299 + vertex 406.247 94.7463 363.671 + vertex 405.131 94.2553 363.673 + endloop + endfacet + facet normal 0.160158 -0.37545 0.9129 + outer loop + vertex 406.35 93.1314 362.997 + vertex 406.226 93.8124 363.299 + vertex 405.131 94.2553 363.673 + endloop + endfacet + facet normal 0.156569 -0.378868 0.91211 + outer loop + vertex 403.337 92.4562 363.234 + vertex 406.35 93.1314 362.997 + vertex 405.131 94.2553 363.673 + endloop + endfacet + facet normal 0.157244 -0.382445 0.9105 + outer loop + vertex 403.337 92.4562 363.234 + vertex 407.508 92.4572 362.514 + vertex 406.35 93.1314 362.997 + endloop + endfacet + facet normal 0.159948 -0.378611 0.91163 + outer loop + vertex 410.232 92.6737 362.126 + vertex 406.35 93.1314 362.997 + vertex 407.508 92.4572 362.514 + endloop + endfacet + facet normal 0.159992 -0.380852 0.910689 + outer loop + vertex 407.508 92.4572 362.514 + vertex 409.795 92.3426 362.064 + vertex 410.232 92.6737 362.126 + endloop + endfacet + facet normal 0.156768 -0.377003 0.912849 + outer loop + vertex 409.795 92.3426 362.064 + vertex 412.987 92.1912 361.454 + vertex 410.232 92.6737 362.126 + endloop + endfacet + facet normal 0.155134 -0.383152 0.910565 + outer loop + vertex 416.117 92.4381 361.024 + vertex 410.232 92.6737 362.126 + vertex 412.987 92.1912 361.454 + endloop + endfacet + facet normal 0.154647 -0.361547 0.919439 + outer loop + vertex 412.987 92.1912 361.454 + vertex 418.28 92.0921 360.524 + vertex 416.117 92.4381 361.024 + endloop + endfacet + facet normal 0.150116 -0.380105 0.91268 + outer loop + vertex 422.128 92.4282 360.031 + vertex 416.117 92.4381 361.024 + vertex 418.28 92.0921 360.524 + endloop + endfacet + facet normal 0.148935 -0.347218 0.925882 + outer loop + vertex 418.28 92.0921 360.524 + vertex 423.765 92.1931 359.68 + vertex 422.128 92.4282 360.031 + endloop + endfacet + facet normal 0.143696 -0.371046 0.917429 + outer loop + vertex 428.167 92.6758 359.186 + vertex 422.128 92.4282 360.031 + vertex 423.765 92.1931 359.68 + endloop + endfacet + facet normal 0.142123 -0.346769 0.927121 + outer loop + vertex 423.765 92.1931 359.68 + vertex 429.672 92.2994 358.814 + vertex 428.167 92.6758 359.186 + endloop + endfacet + facet normal 0.136803 -0.362769 0.921783 + outer loop + vertex 433.956 93.0971 358.492 + vertex 428.167 92.6758 359.186 + vertex 429.672 92.2994 358.814 + endloop + endfacet + facet normal 0.137036 -0.364276 0.921154 + outer loop + vertex 429.672 92.2994 358.814 + vertex 435.466 92.7559 358.133 + vertex 433.956 93.0971 358.492 + endloop + endfacet + facet normal 0.133371 -0.376063 0.916945 + outer loop + vertex 437.455 93.3269 358.078 + vertex 433.956 93.0971 358.492 + vertex 435.466 92.7559 358.133 + endloop + endfacet + facet normal 0.132743 -0.37378 0.917969 + outer loop + vertex 435.466 92.7559 358.133 + vertex 440.645 93.2621 357.59 + vertex 437.455 93.3269 358.078 + endloop + endfacet + facet normal 0.13227 -0.379607 0.915644 + outer loop + vertex 440.46 94.1799 357.997 + vertex 437.455 93.3269 358.078 + vertex 440.645 93.2621 357.59 + endloop + endfacet + facet normal 0.129187 -0.380297 0.915798 + outer loop + vertex 440.645 93.2621 357.59 + vertex 446.544 94.4321 357.244 + vertex 440.46 94.1799 357.997 + endloop + endfacet + facet normal 0.129174 -0.381602 0.915256 + outer loop + vertex 451.69 96.7711 357.493 + vertex 440.46 94.1799 357.997 + vertex 446.544 94.4321 357.244 + endloop + endfacet + facet normal 0.128173 -0.379507 0.916267 + outer loop + vertex 446.544 94.4321 357.244 + vertex 452.754 95.0925 356.648 + vertex 451.69 96.7711 357.493 + endloop + endfacet + facet normal 0.122091 -0.383039 0.915628 + outer loop + vertex 452.754 95.0925 356.648 + vertex 458.606 96.5201 356.465 + vertex 451.69 96.7711 357.493 + endloop + endfacet + facet normal 0.121533 -0.388791 0.913275 + outer loop + vertex 465.82 99.2971 356.688 + vertex 451.69 96.7711 357.493 + vertex 458.606 96.5201 356.465 + endloop + endfacet + facet normal 0.125828 -0.39953 0.908044 + outer loop + vertex 458.606 96.5201 356.465 + vertex 465.064 97.2727 355.902 + vertex 465.82 99.2971 356.688 + endloop + endfacet + facet normal 0.120259 -0.398003 0.909468 + outer loop + vertex 465.064 97.2727 355.902 + vertex 471.321 98.9622 355.814 + vertex 465.82 99.2971 356.688 + endloop + endfacet + facet normal 0.119773 -0.401792 0.907864 + outer loop + vertex 479.045 102.053 356.162 + vertex 465.82 99.2971 356.688 + vertex 471.321 98.9622 355.814 + endloop + endfacet + facet normal 0.127145 -0.41921 0.898942 + outer loop + vertex 471.321 98.9622 355.814 + vertex 477.59 99.8963 355.363 + vertex 479.045 102.053 356.162 + endloop + endfacet + facet normal 0.121788 -0.41636 0.901006 + outer loop + vertex 477.59 99.8963 355.363 + vertex 484.954 101.958 355.32 + vertex 479.045 102.053 356.162 + endloop + endfacet + facet normal 0.121422 -0.420888 0.898949 + outer loop + vertex 491.569 105.025 355.862 + vertex 479.045 102.053 356.162 + vertex 484.954 101.958 355.32 + endloop + endfacet + facet normal 0.119865 -0.417818 0.900589 + outer loop + vertex 484.954 101.958 355.32 + vertex 490.359 103.377 355.259 + vertex 491.569 105.025 355.862 + endloop + endfacet + facet normal 0.124918 -0.420774 0.898523 + outer loop + vertex 490.359 103.377 355.259 + vertex 495.419 104.393 355.031 + vertex 491.569 105.025 355.862 + endloop + endfacet + facet normal 0.122646 -0.429551 0.894675 + outer loop + vertex 503.091 107.58 355.509 + vertex 491.569 105.025 355.862 + vertex 495.419 104.393 355.031 + endloop + endfacet + facet normal 0.13017 -0.446268 0.885382 + outer loop + vertex 495.419 104.393 355.031 + vertex 500.92 104.947 354.502 + vertex 503.091 107.58 355.509 + endloop + endfacet + facet normal 0.13232 -0.44765 0.884365 + outer loop + vertex 500.92 104.947 354.502 + vertex 507.81 106.318 354.165 + vertex 503.091 107.58 355.509 + endloop + endfacet + facet normal 0.128145 -0.458169 0.879579 + outer loop + vertex 514.861 110.339 355.232 + vertex 503.091 107.58 355.509 + vertex 507.81 106.318 354.165 + endloop + endfacet + facet normal 0.125154 -0.453657 0.882345 + outer loop + vertex 507.81 106.318 354.165 + vertex 513.828 108.054 354.204 + vertex 514.861 110.339 355.232 + endloop + endfacet + facet normal 0.129229 -0.454939 0.881096 + outer loop + vertex 513.828 108.054 354.204 + vertex 520.535 109.846 354.145 + vertex 514.861 110.339 355.232 + endloop + endfacet + facet normal 0.128442 -0.459282 0.878956 + outer loop + vertex 526.781 113.458 355.12 + vertex 514.861 110.339 355.232 + vertex 520.535 109.846 354.145 + endloop + endfacet + facet normal 0.125498 -0.454919 0.881646 + outer loop + vertex 520.535 109.846 354.145 + vertex 526.376 111.461 354.147 + vertex 526.781 113.458 355.12 + endloop + endfacet + facet normal 0.12667 -0.455043 0.881414 + outer loop + vertex 526.376 111.461 354.147 + vertex 531.265 112.985 354.231 + vertex 526.781 113.458 355.12 + endloop + endfacet + facet normal 0.127611 -0.450377 0.883672 + outer loop + vertex 538.908 116.682 355.012 + vertex 526.781 113.458 355.12 + vertex 531.265 112.985 354.231 + endloop + endfacet + facet normal 0.135284 -0.464448 0.875206 + outer loop + vertex 531.265 112.985 354.231 + vertex 538.174 114.245 353.832 + vertex 538.908 116.682 355.012 + endloop + endfacet + facet normal 0.127065 -0.462953 0.877228 + outer loop + vertex 538.174 114.245 353.832 + vertex 544.538 116.529 354.115 + vertex 538.908 116.682 355.012 + endloop + endfacet + facet normal 0.128646 -0.448199 0.884629 + outer loop + vertex 551.424 120.172 354.96 + vertex 538.908 116.682 355.012 + vertex 544.538 116.529 354.115 + endloop + endfacet + facet normal 0.130912 -0.45196 0.88238 + outer loop + vertex 544.538 116.529 354.115 + vertex 549.625 117.685 353.953 + vertex 551.424 120.172 354.96 + endloop + endfacet + facet normal 0.132995 -0.453103 0.881482 + outer loop + vertex 549.625 117.685 353.953 + vertex 556.942 119.76 353.916 + vertex 551.424 120.172 354.96 + endloop + endfacet + facet normal 0.132055 -0.4587 0.878724 + outer loop + vertex 564.181 123.855 354.965 + vertex 551.424 120.172 354.96 + vertex 556.942 119.76 353.916 + endloop + endfacet + facet normal 0.12857 -0.453378 0.881997 + outer loop + vertex 556.942 119.76 353.916 + vertex 563.78 121.812 353.974 + vertex 564.181 123.855 354.965 + endloop + endfacet + facet normal 0.130181 -0.453539 0.881677 + outer loop + vertex 563.78 121.812 353.974 + vertex 569.048 123.637 354.135 + vertex 564.181 123.855 354.965 + endloop + endfacet + facet normal 0.130264 -0.4529 0.881994 + outer loop + vertex 576.277 127.307 354.951 + vertex 564.181 123.855 354.965 + vertex 569.048 123.637 354.135 + endloop + endfacet + facet normal 0.140484 -0.470605 0.871089 + outer loop + vertex 569.048 123.637 354.135 + vertex 575.674 124.978 353.79 + vertex 576.277 127.307 354.951 + endloop + endfacet + facet normal 0.133144 -0.469561 0.872803 + outer loop + vertex 575.674 124.978 353.79 + vertex 581.69 127.292 354.118 + vertex 576.277 127.307 354.951 + endloop + endfacet + facet normal 0.133811 -0.461485 0.876998 + outer loop + vertex 585.655 129.78 354.822 + vertex 576.277 127.307 354.951 + vertex 581.69 127.292 354.118 + endloop + endfacet + facet normal 0.137744 -0.466787 0.873577 + outer loop + vertex 581.69 127.292 354.118 + vertex 586.084 128.267 353.946 + vertex 585.655 129.78 354.822 + endloop + endfacet + facet normal 0.145115 -0.464663 0.873516 + outer loop + vertex 586.084 128.267 353.946 + vertex 591.417 129.66 353.801 + vertex 585.655 129.78 354.822 + endloop + endfacet + facet normal 0.146398 -0.45304 0.879388 + outer loop + vertex 591.417 129.66 353.801 + vertex 592.277 133.261 355.513 + vertex 585.655 129.78 354.822 + endloop + endfacet + facet normal 0.124214 -0.415185 0.901217 + outer loop + vertex 584.554 132.17 356.075 + vertex 585.655 129.78 354.822 + vertex 592.277 133.261 355.513 + endloop + endfacet + facet normal 0.13454 -0.451486 0.882077 + outer loop + vertex 591.417 129.66 353.801 + vertex 596.974 132.805 354.563 + vertex 592.277 133.261 355.513 + endloop + endfacet + facet normal 0.141594 -0.414266 0.899075 + outer loop + vertex 592.277 133.261 355.513 + vertex 596.974 132.805 354.563 + vertex 599.968 137.659 356.328 + endloop + endfacet + facet normal 0.148271 -0.417455 0.89652 + outer loop + vertex 601.978 133.784 354.191 + vertex 599.968 137.659 356.328 + vertex 596.974 132.805 354.563 + endloop + endfacet + facet normal 0.161349 -0.531173 0.831759 + outer loop + vertex 591.417 129.66 353.801 + vertex 586.084 128.267 353.946 + vertex 584.034 125.596 352.638 + endloop + endfacet + facet normal 0.150216 -0.514514 0.844222 + outer loop + vertex 591.417 129.66 353.801 + vertex 584.034 125.596 352.638 + vertex 593.923 127.254 351.888 + endloop + endfacet + facet normal 0.148648 -0.515763 0.843737 + outer loop + vertex 597.89 129.695 352.682 + vertex 591.417 129.66 353.801 + vertex 593.923 127.254 351.888 + endloop + endfacet + facet normal 0.145307 -0.511386 0.846977 + outer loop + vertex 593.923 127.254 351.888 + vertex 597.57 127.674 351.516 + vertex 597.89 129.695 352.682 + endloop + endfacet + facet normal 0.148264 -0.573962 0.805348 + outer loop + vertex 593.923 127.254 351.888 + vertex 597.193 125.887 350.312 + vertex 597.57 127.674 351.516 + endloop + endfacet + facet normal 0.152518 -0.567853 0.808877 + outer loop + vertex 591.516 124.013 350.067 + vertex 597.193 125.887 350.312 + vertex 593.923 127.254 351.888 + endloop + endfacet + facet normal 0.156633 -0.569725 0.806771 + outer loop + vertex 591.516 124.013 350.067 + vertex 593.923 127.254 351.888 + vertex 584.034 125.596 352.638 + endloop + endfacet + facet normal 0.1607 -0.560106 0.812685 + outer loop + vertex 584.034 125.596 352.638 + vertex 580.451 121.016 350.19 + vertex 591.516 124.013 350.067 + endloop + endfacet + facet normal 0.163057 -0.56127 0.811412 + outer loop + vertex 567.913 121.083 352.756 + vertex 580.451 121.016 350.19 + vertex 584.034 125.596 352.638 + endloop + endfacet + facet normal 0.163187 -0.560344 0.812025 + outer loop + vertex 565.409 116.818 350.316 + vertex 580.451 121.016 350.19 + vertex 567.913 121.083 352.756 + endloop + endfacet + facet normal 0.161288 -0.5597 0.812848 + outer loop + vertex 549.595 115.854 352.789 + vertex 565.409 116.818 350.316 + vertex 567.913 121.083 352.756 + endloop + endfacet + facet normal 0.161097 -0.563864 0.810004 + outer loop + vertex 548.24 111.954 350.344 + vertex 565.409 116.818 350.316 + vertex 549.595 115.854 352.789 + endloop + endfacet + facet normal 0.158934 -0.563527 0.810665 + outer loop + vertex 531.645 110.959 352.906 + vertex 548.24 111.954 350.344 + vertex 549.595 115.854 352.789 + endloop + endfacet + facet normal 0.159165 -0.558422 0.814145 + outer loop + vertex 530.986 107.197 350.455 + vertex 548.24 111.954 350.344 + vertex 531.645 110.959 352.906 + endloop + endfacet + facet normal 0.157798 -0.558376 0.814442 + outer loop + vertex 517.126 106.727 352.818 + vertex 530.986 107.197 350.455 + vertex 531.645 110.959 352.906 + endloop + endfacet + facet normal 0.158412 -0.550609 0.819594 + outer loop + vertex 516.872 103.167 350.476 + vertex 530.986 107.197 350.455 + vertex 517.126 106.727 352.818 + endloop + endfacet + facet normal 0.160292 -0.550536 0.819278 + outer loop + vertex 508.097 103.443 352.377 + vertex 516.872 103.167 350.476 + vertex 517.126 106.727 352.818 + endloop + endfacet + facet normal 0.160024 -0.552111 0.81827 + outer loop + vertex 507.646 100.146 350.241 + vertex 516.872 103.167 350.476 + vertex 508.097 103.443 352.377 + endloop + endfacet + facet normal 0.16298 -0.552129 0.817674 + outer loop + vertex 507.646 100.146 350.241 + vertex 508.097 103.443 352.377 + vertex 503.141 101.172 351.832 + endloop + endfacet + facet normal 0.1521 -0.478351 0.864896 + outer loop + vertex 596.974 132.805 354.563 + vertex 591.417 129.66 353.801 + vertex 597.89 129.695 352.682 + endloop + endfacet + facet normal 0.157512 -0.476717 0.86483 + outer loop + vertex 596.974 132.805 354.563 + vertex 597.89 129.695 352.682 + vertex 601.978 133.784 354.191 + endloop + endfacet + facet normal 0.149247 -0.524924 0.837962 + outer loop + vertex 586.084 128.267 353.946 + vertex 581.69 127.292 354.118 + vertex 584.034 125.596 352.638 + endloop + endfacet + facet normal 0.122167 -0.416062 0.901092 + outer loop + vertex 585.655 129.78 354.822 + vertex 584.554 132.17 356.075 + vertex 576.277 127.307 354.951 + endloop + endfacet + facet normal 0.114589 -0.404596 0.907288 + outer loop + vertex 576.277 127.307 354.951 + vertex 584.554 132.17 356.075 + vertex 574.191 129.705 356.284 + endloop + endfacet + facet normal 0.154283 -0.519898 0.84018 + outer loop + vertex 581.69 127.292 354.118 + vertex 575.674 124.978 353.79 + vertex 584.034 125.596 352.638 + endloop + endfacet + facet normal 0.154174 -0.528932 0.834543 + outer loop + vertex 567.913 121.083 352.756 + vertex 584.034 125.596 352.638 + vertex 575.674 124.978 353.79 + endloop + endfacet + facet normal 0.148962 -0.520242 0.840927 + outer loop + vertex 575.674 124.978 353.79 + vertex 569.048 123.637 354.135 + vertex 567.913 121.083 352.756 + endloop + endfacet + facet normal 0.11617 -0.403404 0.907618 + outer loop + vertex 576.277 127.307 354.951 + vertex 574.191 129.705 356.284 + vertex 564.181 123.855 354.965 + endloop + endfacet + facet normal 0.112987 -0.398532 0.910168 + outer loop + vertex 564.181 123.855 354.965 + vertex 574.191 129.705 356.284 + vertex 562.079 126.444 356.36 + endloop + endfacet + facet normal 0.155156 -0.521851 0.838808 + outer loop + vertex 569.048 123.637 354.135 + vertex 563.78 121.812 353.974 + vertex 567.913 121.083 352.756 + endloop + endfacet + facet normal 0.152152 -0.530603 0.833853 + outer loop + vertex 563.78 121.812 353.974 + vertex 556.942 119.76 353.916 + vertex 567.913 121.083 352.756 + endloop + endfacet + facet normal 0.151955 -0.52686 0.836258 + outer loop + vertex 549.595 115.854 352.789 + vertex 567.913 121.083 352.756 + vertex 556.942 119.76 353.916 + endloop + endfacet + facet normal 0.114383 -0.397539 0.910428 + outer loop + vertex 564.181 123.855 354.965 + vertex 562.079 126.444 356.36 + vertex 551.424 120.172 354.96 + endloop + endfacet + facet normal 0.114563 -0.397813 0.910286 + outer loop + vertex 551.424 120.172 354.96 + vertex 562.079 126.444 356.36 + vertex 549.475 122.889 356.393 + endloop + endfacet + facet normal 0.15501 -0.531581 0.832703 + outer loop + vertex 556.942 119.76 353.916 + vertex 549.625 117.685 353.953 + vertex 549.595 115.854 352.789 + endloop + endfacet + facet normal 0.147571 -0.532105 0.833719 + outer loop + vertex 549.625 117.685 353.953 + vertex 544.538 116.529 354.115 + vertex 549.595 115.854 352.789 + endloop + endfacet + facet normal 0.114684 -0.397737 0.910304 + outer loop + vertex 551.424 120.172 354.96 + vertex 549.475 122.889 356.393 + vertex 538.908 116.682 355.012 + endloop + endfacet + facet normal 0.115524 -0.399018 0.909636 + outer loop + vertex 538.908 116.682 355.012 + vertex 549.475 122.889 356.393 + vertex 537.044 119.399 356.441 + endloop + endfacet + facet normal 0.150232 -0.522785 0.839122 + outer loop + vertex 544.538 116.529 354.115 + vertex 538.174 114.245 353.832 + vertex 549.595 115.854 352.789 + endloop + endfacet + facet normal 0.151203 -0.534678 0.831419 + outer loop + vertex 531.645 110.959 352.906 + vertex 549.595 115.854 352.789 + vertex 538.174 114.245 353.832 + endloop + endfacet + facet normal 0.143886 -0.522644 0.840322 + outer loop + vertex 538.174 114.245 353.832 + vertex 531.265 112.985 354.231 + vertex 531.645 110.959 352.906 + endloop + endfacet + facet normal 0.114373 -0.399722 0.909473 + outer loop + vertex 538.908 116.682 355.012 + vertex 537.044 119.399 356.441 + vertex 526.781 113.458 355.12 + endloop + endfacet + facet normal 0.113444 -0.398282 0.910221 + outer loop + vertex 526.781 113.458 355.12 + vertex 537.044 119.399 356.441 + vertex 524.961 116.132 356.517 + endloop + endfacet + facet normal 0.148165 -0.521728 0.840147 + outer loop + vertex 531.265 112.985 354.231 + vertex 526.376 111.461 354.147 + vertex 531.645 110.959 352.906 + endloop + endfacet + facet normal 0.14625 -0.529937 0.835331 + outer loop + vertex 526.376 111.461 354.147 + vertex 520.535 109.846 354.145 + vertex 531.645 110.959 352.906 + endloop + endfacet + facet normal 0.145897 -0.518149 0.842755 + outer loop + vertex 517.126 106.727 352.818 + vertex 531.645 110.959 352.906 + vertex 520.535 109.846 354.145 + endloop + endfacet + facet normal 0.112861 -0.398636 0.910138 + outer loop + vertex 526.781 113.458 355.12 + vertex 524.961 116.132 356.517 + vertex 514.861 110.339 355.232 + endloop + endfacet + facet normal 0.111453 -0.396434 0.911273 + outer loop + vertex 514.861 110.339 355.232 + vertex 524.961 116.132 356.517 + vertex 513.149 113.069 356.629 + endloop + endfacet + facet normal 0.145748 -0.518028 0.842855 + outer loop + vertex 520.535 109.846 354.145 + vertex 513.828 108.054 354.204 + vertex 517.126 106.727 352.818 + endloop + endfacet + facet normal 0.144545 -0.519978 0.841861 + outer loop + vertex 513.828 108.054 354.204 + vertex 507.81 106.318 354.165 + vertex 517.126 106.727 352.818 + endloop + endfacet + facet normal 0.144897 -0.511889 0.846744 + outer loop + vertex 508.097 103.443 352.377 + vertex 517.126 106.727 352.818 + vertex 507.81 106.318 354.165 + endloop + endfacet + facet normal 0.152581 -0.510722 0.846098 + outer loop + vertex 503.045 103.809 353.509 + vertex 508.097 103.443 352.377 + vertex 507.81 106.318 354.165 + endloop + endfacet + facet normal 0.14931 -0.526875 0.836725 + outer loop + vertex 503.045 103.809 353.509 + vertex 503.141 101.172 351.832 + vertex 508.097 103.443 352.377 + endloop + endfacet + facet normal 0.114082 -0.394949 0.911592 + outer loop + vertex 514.861 110.339 355.232 + vertex 513.149 113.069 356.629 + vertex 503.091 107.58 355.509 + endloop + endfacet + facet normal 0.107528 -0.384049 0.91703 + outer loop + vertex 503.091 107.58 355.509 + vertex 513.149 113.069 356.629 + vertex 501.445 110.16 356.783 + endloop + endfacet + facet normal 0.139541 -0.489755 0.860621 + outer loop + vertex 500.92 104.947 354.502 + vertex 503.045 103.809 353.509 + vertex 507.81 106.318 354.165 + endloop + endfacet + facet normal 0.144249 -0.48341 0.863428 + outer loop + vertex 503.045 103.809 353.509 + vertex 500.92 104.947 354.502 + vertex 500.44 103.782 353.93 + endloop + endfacet + facet normal 0.127048 -0.478879 0.868639 + outer loop + vertex 496.968 102.845 353.921 + vertex 500.44 103.782 353.93 + vertex 500.92 104.947 354.502 + endloop + endfacet + facet normal 0.137462 -0.517235 0.844732 + outer loop + vertex 496.968 102.845 353.921 + vertex 500.466 102.207 352.961 + vertex 500.44 103.782 353.93 + endloop + endfacet + facet normal 0.134751 -0.525279 0.840193 + outer loop + vertex 497.629 100.499 352.348 + vertex 500.466 102.207 352.961 + vertex 496.968 102.845 353.921 + endloop + endfacet + facet normal 0.147177 -0.521823 0.840262 + outer loop + vertex 497.629 100.499 352.348 + vertex 496.968 102.845 353.921 + vertex 491.122 99.6262 352.946 + endloop + endfacet + facet normal 0.13916 -0.509883 0.848913 + outer loop + vertex 490.356 102.146 354.585 + vertex 491.122 99.6262 352.946 + vertex 496.968 102.845 353.921 + endloop + endfacet + facet normal 0.137879 -0.482473 0.864991 + outer loop + vertex 495.419 104.393 355.031 + vertex 490.356 102.146 354.585 + vertex 496.968 102.845 353.921 + endloop + endfacet + facet normal 0.146727 -0.507631 0.848989 + outer loop + vertex 482.878 99.7555 354.448 + vertex 491.122 99.6262 352.946 + vertex 490.356 102.146 354.585 + endloop + endfacet + facet normal 0.14739 -0.502101 0.852157 + outer loop + vertex 481.402 97.0382 353.102 + vertex 491.122 99.6262 352.946 + vertex 482.878 99.7555 354.448 + endloop + endfacet + facet normal 0.144334 -0.501016 0.853318 + outer loop + vertex 472.346 97.4382 354.869 + vertex 481.402 97.0382 353.102 + vertex 482.878 99.7555 354.448 + endloop + endfacet + facet normal 0.145444 -0.493738 0.857362 + outer loop + vertex 470.713 94.4511 353.426 + vertex 481.402 97.0382 353.102 + vertex 472.346 97.4382 354.869 + endloop + endfacet + facet normal 0.142072 -0.492509 0.858633 + outer loop + vertex 460.571 95.085 355.467 + vertex 470.713 94.4511 353.426 + vertex 472.346 97.4382 354.869 + endloop + endfacet + facet normal 0.144461 -0.478468 0.86614 + outer loop + vertex 459.24 92.0818 354.03 + vertex 470.713 94.4511 353.426 + vertex 460.571 95.085 355.467 + endloop + endfacet + facet normal 0.140585 -0.477349 0.867395 + outer loop + vertex 448.788 93.1156 356.293 + vertex 459.24 92.0818 354.03 + vertex 460.571 95.085 355.467 + endloop + endfacet + facet normal 0.144269 -0.45963 0.876315 + outer loop + vertex 447.787 90.082 354.867 + vertex 459.24 92.0818 354.03 + vertex 448.788 93.1156 356.293 + endloop + endfacet + facet normal 0.140195 -0.4588 0.87741 + outer loop + vertex 436.54 91.5349 357.424 + vertex 447.787 90.082 354.867 + vertex 448.788 93.1156 356.293 + endloop + endfacet + facet normal 0.144186 -0.441935 0.885383 + outer loop + vertex 437.248 88.3685 355.728 + vertex 447.787 90.082 354.867 + vertex 436.54 91.5349 357.424 + endloop + endfacet + facet normal 0.146053 -0.441477 0.885306 + outer loop + vertex 437.248 88.3685 355.728 + vertex 436.54 91.5349 357.424 + vertex 427.981 89.9445 358.043 + endloop + endfacet + facet normal 0.145694 -0.442745 0.884732 + outer loop + vertex 427.786 87.0348 356.619 + vertex 437.248 88.3685 355.728 + vertex 427.981 89.9445 358.043 + endloop + endfacet + facet normal 0.145489 -0.442747 0.884764 + outer loop + vertex 420.366 89.1597 358.902 + vertex 427.786 87.0348 356.619 + vertex 427.981 89.9445 358.043 + endloop + endfacet + facet normal 0.144035 -0.412489 0.899503 + outer loop + vertex 420.366 89.1597 358.902 + vertex 427.981 89.9445 358.043 + vertex 420.824 91.0325 359.688 + endloop + endfacet + facet normal 0.147499 -0.413002 0.898706 + outer loop + vertex 414.786 90.7623 360.554 + vertex 420.366 89.1597 358.902 + vertex 420.824 91.0325 359.688 + endloop + endfacet + facet normal 0.148025 -0.383774 0.911486 + outer loop + vertex 414.786 90.7623 360.554 + vertex 420.824 91.0325 359.688 + vertex 416.018 91.7484 360.77 + endloop + endfacet + facet normal 0.152877 -0.38916 0.908396 + outer loop + vertex 410.648 91.8611 361.722 + vertex 414.786 90.7623 360.554 + vertex 416.018 91.7484 360.77 + endloop + endfacet + facet normal 0.155844 -0.35638 0.921252 + outer loop + vertex 410.648 91.8611 361.722 + vertex 416.018 91.7484 360.77 + vertex 412.987 92.1912 361.454 + endloop + endfacet + facet normal 0.149871 -0.397276 0.905378 + outer loop + vertex 409.843 90.6422 361.32 + vertex 414.786 90.7623 360.554 + vertex 410.648 91.8611 361.722 + endloop + endfacet + facet normal 0.155158 -0.400069 0.903256 + outer loop + vertex 407.201 91.804 362.288 + vertex 409.843 90.6422 361.32 + vertex 410.648 91.8611 361.722 + endloop + endfacet + facet normal 0.155849 -0.38713 0.908758 + outer loop + vertex 407.201 91.804 362.288 + vertex 410.648 91.8611 361.722 + vertex 407.508 92.4572 362.514 + endloop + endfacet + facet normal 0.148762 -0.4113 0.899279 + outer loop + vertex 406.687 90.5912 361.819 + vertex 409.843 90.6422 361.32 + vertex 407.201 91.804 362.288 + endloop + endfacet + facet normal 0.150423 -0.411807 0.89877 + outer loop + vertex 406.687 90.5912 361.819 + vertex 407.201 91.804 362.288 + vertex 403.337 92.4562 363.234 + endloop + endfacet + facet normal 0.138583 -0.428562 0.892821 + outer loop + vertex 405.996 88.441 360.894 + vertex 406.687 90.5912 361.819 + vertex 403.337 92.4562 363.234 + endloop + endfacet + facet normal 0.14305 -0.425928 0.893377 + outer loop + vertex 403.337 92.4562 363.234 + vertex 404.037 87.388 360.705 + vertex 405.996 88.441 360.894 + endloop + endfacet + facet normal 0.153427 -0.443388 0.883101 + outer loop + vertex 406.135 85.2568 359.271 + vertex 405.996 88.441 360.894 + vertex 404.037 87.388 360.705 + endloop + endfacet + facet normal 0.144192 -0.450947 0.880827 + outer loop + vertex 404.037 87.388 360.705 + vertex 404.689 83.2934 358.502 + vertex 406.135 85.2568 359.271 + endloop + endfacet + facet normal 0.147088 -0.444046 0.883849 + outer loop + vertex 406.135 85.2568 359.271 + vertex 409.201 85.4976 358.882 + vertex 405.996 88.441 360.894 + endloop + endfacet + facet normal 0.142152 -0.448451 0.882431 + outer loop + vertex 405.996 88.441 360.894 + vertex 409.201 85.4976 358.882 + vertex 409.104 88.5876 360.468 + endloop + endfacet + facet normal 0.14102 -0.448553 0.882561 + outer loop + vertex 409.201 85.4976 358.882 + vertex 412.872 86.4562 358.782 + vertex 409.104 88.5876 360.468 + endloop + endfacet + facet normal 0.145222 -0.442859 0.884752 + outer loop + vertex 409.104 88.5876 360.468 + vertex 412.872 86.4562 358.782 + vertex 413.808 88.8389 359.821 + endloop + endfacet + facet normal 0.14548 -0.423274 0.894245 + outer loop + vertex 409.104 88.5876 360.468 + vertex 413.808 88.8389 359.821 + vertex 409.843 90.6422 361.32 + endloop + endfacet + facet normal 0.146335 -0.443152 0.884422 + outer loop + vertex 412.872 86.4562 358.782 + vertex 419.145 86.3079 357.67 + vertex 413.808 88.8389 359.821 + endloop + endfacet + facet normal 0.145638 -0.444251 0.883986 + outer loop + vertex 413.808 88.8389 359.821 + vertex 419.145 86.3079 357.67 + vertex 420.366 89.1597 358.902 + endloop + endfacet + facet normal 0.142626 -0.475885 0.867866 + outer loop + vertex 412.872 86.4562 358.782 + vertex 416.302 82.712 356.166 + vertex 419.145 86.3079 357.67 + endloop + endfacet + facet normal 0.14672 -0.478284 0.865863 + outer loop + vertex 416.302 82.712 356.166 + vertex 426.674 83.3291 354.749 + vertex 419.145 86.3079 357.67 + endloop + endfacet + facet normal 0.145646 -0.480157 0.865006 + outer loop + vertex 427.786 87.0348 356.619 + vertex 419.145 86.3079 357.67 + vertex 426.674 83.3291 354.749 + endloop + endfacet + facet normal 0.149998 -0.480884 0.863858 + outer loop + vertex 426.674 83.3291 354.749 + vertex 437.005 84.7008 353.719 + vertex 427.786 87.0348 356.619 + endloop + endfacet + facet normal 0.149274 -0.482665 0.86299 + outer loop + vertex 427.786 87.0348 356.619 + vertex 437.005 84.7008 353.719 + vertex 437.248 88.3685 355.728 + endloop + endfacet + facet normal 0.153816 -0.482561 0.86225 + outer loop + vertex 437.005 84.7008 353.719 + vertex 447.685 86.4989 352.82 + vertex 437.248 88.3685 355.728 + endloop + endfacet + facet normal 0.150244 -0.493671 0.856572 + outer loop + vertex 437.248 88.3685 355.728 + vertex 447.685 86.4989 352.82 + vertex 447.787 90.082 354.867 + endloop + endfacet + facet normal 0.155754 -0.493365 0.855764 + outer loop + vertex 447.685 86.4989 352.82 + vertex 458.924 88.6263 352.001 + vertex 447.787 90.082 354.867 + endloop + endfacet + facet normal 0.151024 -0.510882 0.846281 + outer loop + vertex 447.787 90.082 354.867 + vertex 458.924 88.6263 352.001 + vertex 459.24 92.0818 354.03 + endloop + endfacet + facet normal 0.156297 -0.510822 0.845359 + outer loop + vertex 458.924 88.6263 352.001 + vertex 470.42 91.1098 351.376 + vertex 459.24 92.0818 354.03 + endloop + endfacet + facet normal 0.152801 -0.526459 0.836357 + outer loop + vertex 459.24 92.0818 354.03 + vertex 470.42 91.1098 351.376 + vertex 470.713 94.4511 353.426 + endloop + endfacet + facet normal 0.155083 -0.526418 0.835963 + outer loop + vertex 470.42 91.1098 351.376 + vertex 481.048 93.8652 351.139 + vertex 470.713 94.4511 353.426 + endloop + endfacet + facet normal 0.153994 -0.53217 0.832515 + outer loop + vertex 470.713 94.4511 353.426 + vertex 481.048 93.8652 351.139 + vertex 481.402 97.0382 353.102 + endloop + endfacet + facet normal 0.15448 -0.532169 0.832426 + outer loop + vertex 481.048 93.8652 351.139 + vertex 488.785 96.3758 351.309 + vertex 481.402 97.0382 353.102 + endloop + endfacet + facet normal 0.154766 -0.530949 0.833151 + outer loop + vertex 481.402 97.0382 353.102 + vertex 488.785 96.3758 351.309 + vertex 491.122 99.6262 352.946 + endloop + endfacet + facet normal 0.167164 -0.536768 0.827004 + outer loop + vertex 491.122 99.6262 352.946 + vertex 488.785 96.3758 351.309 + vertex 495.94 96.9465 350.233 + endloop + endfacet + facet normal 0.149782 -0.557463 0.816578 + outer loop + vertex 495.94 96.9465 350.233 + vertex 497.629 100.499 352.348 + vertex 491.122 99.6262 352.946 + endloop + endfacet + facet normal 0.142652 -0.555591 0.819127 + outer loop + vertex 495.94 96.9465 350.233 + vertex 500.327 99.1747 350.98 + vertex 497.629 100.499 352.348 + endloop + endfacet + facet normal 0.150324 -0.545517 0.824508 + outer loop + vertex 497.629 100.499 352.348 + vertex 500.327 99.1747 350.98 + vertex 500.466 102.207 352.961 + endloop + endfacet + facet normal 0.146945 -0.472657 0.868909 + outer loop + vertex 412.872 86.4562 358.782 + vertex 409.201 85.4976 358.882 + vertex 416.302 82.712 356.166 + endloop + endfacet + facet normal 0.147034 -0.472498 0.86898 + outer loop + vertex 408.813 81.2937 356.662 + vertex 416.302 82.712 356.166 + vertex 409.201 85.4976 358.882 + endloop + endfacet + facet normal 0.147427 -0.472499 0.868913 + outer loop + vertex 406.135 85.2568 359.271 + vertex 408.813 81.2937 356.662 + vertex 409.201 85.4976 358.882 + endloop + endfacet + facet normal 0.164749 -0.46234 0.871263 + outer loop + vertex 408.813 81.2937 356.662 + vertex 406.135 85.2568 359.271 + vertex 404.689 83.2934 358.502 + endloop + endfacet + facet normal 0.142538 -0.429394 0.891798 + outer loop + vertex 405.996 88.441 360.894 + vertex 409.104 88.5876 360.468 + vertex 406.687 90.5912 361.819 + endloop + endfacet + facet normal 0.148056 -0.423901 0.893525 + outer loop + vertex 406.687 90.5912 361.819 + vertex 409.104 88.5876 360.468 + vertex 409.843 90.6422 361.32 + endloop + endfacet + facet normal 0.148973 -0.417405 0.896426 + outer loop + vertex 409.843 90.6422 361.32 + vertex 413.808 88.8389 359.821 + vertex 414.786 90.7623 360.554 + endloop + endfacet + facet normal 0.150191 -0.374512 0.914977 + outer loop + vertex 416.018 91.7484 360.77 + vertex 420.824 91.0325 359.688 + vertex 421.369 91.8641 359.939 + endloop + endfacet + facet normal 0.15167 -0.334679 0.930046 + outer loop + vertex 416.018 91.7484 360.77 + vertex 421.369 91.8641 359.939 + vertex 418.28 92.0921 360.524 + endloop + endfacet + facet normal 0.144336 -0.371349 0.917206 + outer loop + vertex 420.824 91.0325 359.688 + vertex 426.616 91.5894 359.002 + vertex 421.369 91.8641 359.939 + endloop + endfacet + facet normal 0.146409 -0.353985 0.92372 + outer loop + vertex 421.369 91.8641 359.939 + vertex 426.616 91.5894 359.002 + vertex 425.031 92.0476 359.428 + endloop + endfacet + facet normal 0.146439 -0.334671 0.930887 + outer loop + vertex 421.369 91.8641 359.939 + vertex 425.031 92.0476 359.428 + vertex 423.765 92.1931 359.68 + endloop + endfacet + facet normal 0.141601 -0.366685 0.919506 + outer loop + vertex 425.031 92.0476 359.428 + vertex 426.616 91.5894 359.002 + vertex 429.672 92.2994 358.814 + endloop + endfacet + facet normal 0.143496 -0.375904 0.915481 + outer loop + vertex 426.616 91.5894 359.002 + vertex 436.54 91.5349 357.424 + vertex 429.672 92.2994 358.814 + endloop + endfacet + facet normal 0.146151 -0.416335 0.897388 + outer loop + vertex 413.808 88.8389 359.821 + vertex 420.366 89.1597 358.902 + vertex 414.786 90.7623 360.554 + endloop + endfacet + facet normal 0.145849 -0.405148 0.902543 + outer loop + vertex 420.824 91.0325 359.688 + vertex 427.981 89.9445 358.043 + vertex 426.616 91.5894 359.002 + endloop + endfacet + facet normal 0.144944 -0.444048 0.884202 + outer loop + vertex 419.145 86.3079 357.67 + vertex 427.786 87.0348 356.619 + vertex 420.366 89.1597 358.902 + endloop + endfacet + facet normal 0.141132 -0.408595 0.901738 + outer loop + vertex 426.616 91.5894 359.002 + vertex 427.981 89.9445 358.043 + vertex 436.54 91.5349 357.424 + endloop + endfacet + facet normal 0.132154 -0.487015 0.863338 + outer loop + vertex 500.92 104.947 354.502 + vertex 495.419 104.393 355.031 + vertex 496.968 102.845 353.921 + endloop + endfacet + facet normal 0.112607 -0.381112 0.917645 + outer loop + vertex 503.091 107.58 355.509 + vertex 501.445 110.16 356.783 + vertex 491.569 105.025 355.862 + endloop + endfacet + facet normal 0.105 -0.367628 0.924027 + outer loop + vertex 491.569 105.025 355.862 + vertex 501.445 110.16 356.783 + vertex 489.336 107.207 356.984 + endloop + endfacet + facet normal 0.134699 -0.476103 0.869012 + outer loop + vertex 495.419 104.393 355.031 + vertex 490.359 103.377 355.259 + vertex 490.356 102.146 354.585 + endloop + endfacet + facet normal 0.134803 -0.476097 0.869 + outer loop + vertex 490.359 103.377 355.259 + vertex 484.954 101.958 355.32 + vertex 490.356 102.146 354.585 + endloop + endfacet + facet normal 0.134957 -0.472089 0.871159 + outer loop + vertex 482.878 99.7555 354.448 + vertex 490.356 102.146 354.585 + vertex 484.954 101.958 355.32 + endloop + endfacet + facet normal 0.108631 -0.364361 0.9249 + outer loop + vertex 491.569 105.025 355.862 + vertex 489.336 107.207 356.984 + vertex 479.045 102.053 356.162 + endloop + endfacet + facet normal 0.104701 -0.357042 0.928202 + outer loop + vertex 479.045 102.053 356.162 + vertex 489.336 107.207 356.984 + vertex 476.538 104.353 357.33 + endloop + endfacet + facet normal 0.137782 -0.474136 0.869604 + outer loop + vertex 484.954 101.958 355.32 + vertex 477.59 99.8963 355.363 + vertex 482.878 99.7555 354.448 + endloop + endfacet + facet normal 0.138259 -0.470065 0.871736 + outer loop + vertex 472.346 97.4382 354.869 + vertex 482.878 99.7555 354.448 + vertex 477.59 99.8963 355.363 + endloop + endfacet + facet normal 0.131395 -0.457021 0.879697 + outer loop + vertex 477.59 99.8963 355.363 + vertex 471.321 98.9622 355.814 + vertex 472.346 97.4382 354.869 + endloop + endfacet + facet normal 0.110207 -0.351743 0.929587 + outer loop + vertex 479.045 102.053 356.162 + vertex 476.538 104.353 357.33 + vertex 465.82 99.2971 356.688 + endloop + endfacet + facet normal 0.106385 -0.344061 0.932901 + outer loop + vertex 465.82 99.2971 356.688 + vertex 476.538 104.353 357.33 + vertex 462.578 101.59 357.903 + endloop + endfacet + facet normal 0.13519 -0.45482 0.880263 + outer loop + vertex 471.321 98.9622 355.814 + vertex 465.064 97.2727 355.902 + vertex 472.346 97.4382 354.869 + endloop + endfacet + facet normal 0.135289 -0.452808 0.881284 + outer loop + vertex 460.571 95.085 355.467 + vertex 472.346 97.4382 354.869 + vertex 465.064 97.2727 355.902 + endloop + endfacet + facet normal 0.128937 -0.441123 0.888136 + outer loop + vertex 465.064 97.2727 355.902 + vertex 458.606 96.5201 356.465 + vertex 460.571 95.085 355.467 + endloop + endfacet + facet normal 0.113263 -0.335546 0.93519 + outer loop + vertex 465.82 99.2971 356.688 + vertex 462.578 101.59 357.903 + vertex 451.69 96.7711 357.493 + endloop + endfacet + facet normal 0.113495 -0.336054 0.93498 + outer loop + vertex 451.69 96.7711 357.493 + vertex 462.578 101.59 357.903 + vertex 453.625 98.8587 358.008 + endloop + endfacet + facet normal 0.115692 -0.337861 0.934058 + outer loop + vertex 453.625 98.8587 358.008 + vertex 447.517 97.7854 358.376 + vertex 451.69 96.7711 357.493 + endloop + endfacet + facet normal 0.119571 -0.325337 0.938008 + outer loop + vertex 447.517 97.7854 358.376 + vertex 440.915 95.4409 358.405 + vertex 451.69 96.7711 357.493 + endloop + endfacet + facet normal 0.11999 -0.326522 0.937542 + outer loop + vertex 440.124 96.9712 359.039 + vertex 440.915 95.4409 358.405 + vertex 447.517 97.7854 358.376 + endloop + endfacet + facet normal 0.118888 -0.31253 0.942439 + outer loop + vertex 447.517 97.7854 358.376 + vertex 446.56 99.6868 359.128 + vertex 440.124 96.9712 359.039 + endloop + endfacet + facet normal 0.117993 -0.310436 0.943243 + outer loop + vertex 440.124 96.9712 359.039 + vertex 446.56 99.6868 359.128 + vertex 439.994 99.1494 359.772 + endloop + endfacet + facet normal 0.127994 -0.309503 0.942245 + outer loop + vertex 440.124 96.9712 359.039 + vertex 439.994 99.1494 359.772 + vertex 433.591 96.4801 359.765 + endloop + endfacet + facet normal 0.128651 -0.327311 0.936118 + outer loop + vertex 433.617 94.7514 359.157 + vertex 440.124 96.9712 359.039 + vertex 433.591 96.4801 359.765 + endloop + endfacet + facet normal 0.138371 -0.326748 0.934927 + outer loop + vertex 433.617 94.7514 359.157 + vertex 433.591 96.4801 359.765 + vertex 427.214 94.3908 359.979 + endloop + endfacet + facet normal 0.13857 -0.347158 0.927513 + outer loop + vertex 427.424 93.2347 359.515 + vertex 433.617 94.7514 359.157 + vertex 427.214 94.3908 359.979 + endloop + endfacet + facet normal 0.14643 -0.345497 0.926925 + outer loop + vertex 427.424 93.2347 359.515 + vertex 427.214 94.3908 359.979 + vertex 421.119 93.057 360.444 + endloop + endfacet + facet normal 0.145766 -0.368983 0.917935 + outer loop + vertex 422.128 92.4282 360.031 + vertex 427.424 93.2347 359.515 + vertex 421.119 93.057 360.444 + endloop + endfacet + facet normal 0.147638 -0.35193 0.92431 + outer loop + vertex 421.119 93.057 360.444 + vertex 427.214 94.3908 359.979 + vertex 420.995 94.3976 360.975 + endloop + endfacet + facet normal 0.15407 -0.35105 0.923594 + outer loop + vertex 421.119 93.057 360.444 + vertex 420.995 94.3976 360.975 + vertex 414.527 93.1833 361.592 + endloop + endfacet + facet normal 0.152224 -0.372714 0.915375 + outer loop + vertex 416.117 92.4381 361.024 + vertex 421.119 93.057 360.444 + vertex 414.527 93.1833 361.592 + endloop + endfacet + facet normal 0.154558 -0.354325 0.922261 + outer loop + vertex 414.527 93.1833 361.592 + vertex 420.995 94.3976 360.975 + vertex 414.782 94.7266 362.142 + endloop + endfacet + facet normal 0.159838 -0.35481 0.921174 + outer loop + vertex 414.527 93.1833 361.592 + vertex 414.782 94.7266 362.142 + vertex 410.566 93.6066 362.442 + endloop + endfacet + facet normal 0.157394 -0.36806 0.916384 + outer loop + vertex 410.383 93.0144 362.236 + vertex 414.527 93.1833 361.592 + vertex 410.566 93.6066 362.442 + endloop + endfacet + facet normal 0.161494 -0.36895 0.915312 + outer loop + vertex 410.383 93.0144 362.236 + vertex 410.566 93.6066 362.442 + vertex 408.071 93.2631 362.744 + endloop + endfacet + facet normal 0.161789 -0.367389 0.915887 + outer loop + vertex 410.383 93.0144 362.236 + vertex 408.071 93.2631 362.744 + vertex 410.232 92.6737 362.126 + endloop + endfacet + facet normal 0.16168 -0.371079 0.914418 + outer loop + vertex 408.071 93.2631 362.744 + vertex 410.566 93.6066 362.442 + vertex 407.796 94.0394 363.108 + endloop + endfacet + facet normal 0.163532 -0.363433 0.917155 + outer loop + vertex 410.566 93.6066 362.442 + vertex 410.169 94.4406 362.844 + vertex 407.796 94.0394 363.108 + endloop + endfacet + facet normal 0.15744 -0.365892 0.917244 + outer loop + vertex 410.232 92.6737 362.126 + vertex 414.527 93.1833 361.592 + vertex 410.383 93.0144 362.236 + endloop + endfacet + facet normal 0.16203 -0.364141 0.917141 + outer loop + vertex 410.169 94.4406 362.844 + vertex 410.566 93.6066 362.442 + vertex 414.782 94.7266 362.142 + endloop + endfacet + facet normal 0.161997 -0.352059 0.921852 + outer loop + vertex 410.169 94.4406 362.844 + vertex 414.782 94.7266 362.142 + vertex 411.244 95.5422 363.075 + endloop + endfacet + facet normal 0.166814 -0.356242 0.919383 + outer loop + vertex 410.169 94.4406 362.844 + vertex 411.244 95.5422 363.075 + vertex 408.137 95.007 363.432 + endloop + endfacet + facet normal 0.166533 -0.353996 0.920301 + outer loop + vertex 408.137 95.007 363.432 + vertex 411.244 95.5422 363.075 + vertex 408.773 96.1576 363.759 + endloop + endfacet + facet normal 0.170289 -0.34284 0.92383 + outer loop + vertex 411.244 95.5422 363.075 + vertex 411.379 96.7783 363.509 + vertex 408.773 96.1576 363.759 + endloop + endfacet + facet normal 0.168295 -0.342761 0.924225 + outer loop + vertex 411.379 96.7783 363.509 + vertex 411.244 95.5422 363.075 + vertex 415.842 97.0097 362.782 + endloop + endfacet + facet normal 0.168433 -0.32048 0.932161 + outer loop + vertex 411.379 96.7783 363.509 + vertex 415.842 97.0097 362.782 + vertex 412.856 98.3266 363.775 + endloop + endfacet + facet normal 0.17497 -0.326174 0.928976 + outer loop + vertex 411.379 96.7783 363.509 + vertex 412.856 98.3266 363.775 + vertex 409.548 97.5354 364.12 + endloop + endfacet + facet normal 0.17363 -0.319438 0.931564 + outer loop + vertex 409.548 97.5354 364.12 + vertex 412.856 98.3266 363.775 + vertex 410.482 99.2479 364.533 + endloop + endfacet + facet normal 0.180268 -0.305215 0.935065 + outer loop + vertex 412.856 98.3266 363.775 + vertex 413.967 100.568 364.292 + vertex 410.482 99.2479 364.533 + endloop + endfacet + facet normal 0.170288 -0.301014 0.938292 + outer loop + vertex 413.967 100.568 364.292 + vertex 412.856 98.3266 363.775 + vertex 417.684 99.6735 363.331 + endloop + endfacet + facet normal 0.175988 -0.282399 0.943016 + outer loop + vertex 417.684 99.6735 363.331 + vertex 418.691 102.424 363.966 + vertex 413.967 100.568 364.292 + endloop + endfacet + facet normal 0.175137 -0.280084 0.943864 + outer loop + vertex 413.967 100.568 364.292 + vertex 418.691 102.424 363.966 + vertex 414.869 103.162 364.895 + endloop + endfacet + facet normal 0.185481 -0.283016 0.941009 + outer loop + vertex 413.967 100.568 364.292 + vertex 414.869 103.162 364.895 + vertex 411.336 101.279 365.025 + endloop + endfacet + facet normal 0.186743 -0.285451 0.940024 + outer loop + vertex 414.869 103.162 364.895 + vertex 411.859 103.537 365.606 + vertex 411.336 101.279 365.025 + endloop + endfacet + facet normal 0.180889 -0.257139 0.949294 + outer loop + vertex 418.691 102.424 363.966 + vertex 419.554 105.393 364.606 + vertex 414.869 103.162 364.895 + endloop + endfacet + facet normal 0.181421 -0.25831 0.948874 + outer loop + vertex 414.869 103.162 364.895 + vertex 419.554 105.393 364.606 + vertex 415.872 106.197 365.529 + endloop + endfacet + facet normal 0.168267 -0.254147 0.952416 + outer loop + vertex 418.691 102.424 363.966 + vertex 424.139 104.732 363.62 + vertex 419.554 105.393 364.606 + endloop + endfacet + facet normal 0.173471 -0.226877 0.95835 + outer loop + vertex 424.139 104.732 363.62 + vertex 424.891 107.843 364.22 + vertex 419.554 105.393 364.606 + endloop + endfacet + facet normal 0.17418 -0.228503 0.957835 + outer loop + vertex 419.554 105.393 364.606 + vertex 424.891 107.843 364.22 + vertex 420.491 108.567 365.193 + endloop + endfacet + facet normal 0.180129 -0.199549 0.963189 + outer loop + vertex 424.891 107.843 364.22 + vertex 425.655 111.04 364.74 + vertex 420.491 108.567 365.193 + endloop + endfacet + facet normal 0.161611 -0.195783 0.967239 + outer loop + vertex 424.891 107.843 364.22 + vertex 430.578 110.585 363.825 + vertex 425.655 111.04 364.74 + endloop + endfacet + facet normal 0.165267 -0.166142 0.972154 + outer loop + vertex 430.578 110.585 363.825 + vertex 431.187 113.813 364.273 + vertex 425.655 111.04 364.74 + endloop + endfacet + facet normal 0.165595 -0.166826 0.971981 + outer loop + vertex 425.655 111.04 364.74 + vertex 431.187 113.813 364.273 + vertex 426.354 114.302 365.18 + endloop + endfacet + facet normal 0.186837 -0.170766 0.967435 + outer loop + vertex 425.655 111.04 364.74 + vertex 426.354 114.302 365.18 + vertex 421.421 111.843 365.699 + endloop + endfacet + facet normal 0.169158 -0.138663 0.975786 + outer loop + vertex 431.187 113.813 364.273 + vertex 431.707 117.109 364.651 + vertex 426.354 114.302 365.18 + endloop + endfacet + facet normal 0.168734 -0.137818 0.975979 + outer loop + vertex 426.354 114.302 365.18 + vertex 431.707 117.109 364.651 + vertex 426.953 117.625 365.546 + endloop + endfacet + facet normal 0.192153 -0.141503 0.97111 + outer loop + vertex 426.354 114.302 365.18 + vertex 426.953 117.625 365.546 + vertex 422.247 115.16 366.118 + endloop + endfacet + facet normal 0.171931 -0.1129 0.978618 + outer loop + vertex 431.707 117.109 364.651 + vertex 432.133 120.469 364.964 + vertex 426.953 117.625 365.546 + endloop + endfacet + facet normal 0.171073 -0.11127 0.978955 + outer loop + vertex 426.953 117.625 365.546 + vertex 432.133 120.469 364.964 + vertex 427.454 121.008 365.843 + endloop + endfacet + facet normal 0.196372 -0.114562 0.973814 + outer loop + vertex 426.953 117.625 365.546 + vertex 427.454 121.008 365.843 + vertex 422.949 118.521 366.459 + endloop + endfacet + facet normal 0.173881 -0.0896697 0.980676 + outer loop + vertex 432.133 120.469 364.964 + vertex 432.469 123.862 365.215 + vertex 427.454 121.008 365.843 + endloop + endfacet + facet normal 0.173086 -0.0882132 0.980948 + outer loop + vertex 427.454 121.008 365.843 + vertex 432.469 123.862 365.215 + vertex 427.869 124.431 366.077 + endloop + endfacet + facet normal 0.200148 -0.0911267 0.975519 + outer loop + vertex 427.454 121.008 365.843 + vertex 427.869 124.431 366.077 + vertex 423.516 121.919 366.736 + endloop + endfacet + facet normal 0.1756 -0.0695072 0.982005 + outer loop + vertex 432.469 123.862 365.215 + vertex 432.735 127.269 365.408 + vertex 427.869 124.431 366.077 + endloop + endfacet + facet normal 0.17535 -0.0690607 0.982081 + outer loop + vertex 427.869 124.431 366.077 + vertex 432.735 127.269 365.408 + vertex 428.197 127.871 366.261 + endloop + endfacet + facet normal 0.204319 -0.0715115 0.976289 + outer loop + vertex 427.869 124.431 366.077 + vertex 428.197 127.871 366.261 + vertex 423.993 125.37 366.957 + endloop + endfacet + facet normal 0.177537 -0.0534196 0.982663 + outer loop + vertex 432.735 127.269 365.408 + vertex 432.944 130.694 365.557 + vertex 428.197 127.871 366.261 + endloop + endfacet + facet normal 0.178041 -0.0543025 0.982524 + outer loop + vertex 428.197 127.871 366.261 + vertex 432.944 130.694 365.557 + vertex 428.45 131.331 366.406 + endloop + endfacet + facet normal 0.208547 -0.0562719 0.976392 + outer loop + vertex 428.197 127.871 366.261 + vertex 428.45 131.331 366.406 + vertex 424.341 128.836 367.14 + endloop + endfacet + facet normal 0.179831 -0.0420523 0.982798 + outer loop + vertex 432.944 130.694 365.557 + vertex 433.109 134.148 365.674 + vertex 428.45 131.331 366.406 + endloop + endfacet + facet normal 0.181178 -0.0443707 0.982449 + outer loop + vertex 428.45 131.331 366.406 + vertex 433.109 134.148 365.674 + vertex 428.651 134.822 366.527 + endloop + endfacet + facet normal 0.213132 -0.0459899 0.97594 + outer loop + vertex 428.45 131.331 366.406 + vertex 428.651 134.822 366.527 + vertex 424.629 132.352 367.289 + endloop + endfacet + facet normal 0.18256 -0.0353685 0.982558 + outer loop + vertex 433.109 134.148 365.674 + vertex 433.24 137.625 365.775 + vertex 428.651 134.822 366.527 + endloop + endfacet + facet normal 0.184775 -0.0391451 0.982001 + outer loop + vertex 428.651 134.822 366.527 + vertex 433.24 137.625 365.775 + vertex 428.838 138.339 366.632 + endloop + endfacet + facet normal 0.216539 -0.0406314 0.975428 + outer loop + vertex 428.651 134.822 366.527 + vertex 428.838 138.339 366.632 + vertex 424.859 135.893 367.413 + endloop + endfacet + facet normal 0.184545 -0.0405496 0.981987 + outer loop + vertex 433.24 137.625 365.775 + vertex 433.401 141.125 365.889 + vertex 428.838 138.339 366.632 + endloop + endfacet + facet normal 0.185357 -0.0419359 0.981776 + outer loop + vertex 428.838 138.339 366.632 + vertex 433.401 141.125 365.889 + vertex 429.084 141.87 366.736 + endloop + endfacet + facet normal 0.216562 -0.0439245 0.97528 + outer loop + vertex 428.838 138.339 366.632 + vertex 429.084 141.87 366.736 + vertex 425.093 139.439 367.513 + endloop + endfacet + facet normal 0.179457 -0.0751046 0.980895 + outer loop + vertex 433.401 141.125 365.889 + vertex 433.739 144.663 366.099 + vertex 429.084 141.87 366.736 + endloop + endfacet + facet normal 0.179948 -0.0759582 0.980739 + outer loop + vertex 429.084 141.87 366.736 + vertex 433.739 144.663 366.099 + vertex 429.507 145.448 366.936 + endloop + endfacet + facet normal 0.162724 -0.161018 0.973444 + outer loop + vertex 433.739 144.663 366.099 + vertex 434.352 148.288 366.596 + vertex 429.507 145.448 366.936 + endloop + endfacet + facet normal 0.144837 -0.158437 0.976688 + outer loop + vertex 433.739 144.663 366.099 + vertex 438.984 147.719 365.816 + vertex 434.352 148.288 366.596 + endloop + endfacet + facet normal 0.146376 -0.16114 0.976016 + outer loop + vertex 438.323 144.156 365.327 + vertex 438.984 147.719 365.816 + vertex 433.739 144.663 366.099 + endloop + endfacet + facet normal 0.123942 -0.157487 0.979712 + outer loop + vertex 438.323 144.156 365.327 + vertex 443.881 147.47 365.157 + vertex 438.984 147.719 365.816 + endloop + endfacet + facet normal 0.125998 -0.160978 0.978882 + outer loop + vertex 443.089 143.916 364.674 + vertex 443.881 147.47 365.157 + vertex 438.323 144.156 365.327 + endloop + endfacet + facet normal 0.132016 -0.0686951 0.988864 + outer loop + vertex 438.068 140.663 365.119 + vertex 443.089 143.916 364.674 + vertex 438.323 144.156 365.327 + endloop + endfacet + facet normal 0.155765 -0.0702186 0.985295 + outer loop + vertex 438.068 140.663 365.119 + vertex 438.323 144.156 365.327 + vertex 433.401 141.125 365.889 + endloop + endfacet + facet normal 0.130218 -0.0658603 0.989296 + outer loop + vertex 442.872 140.461 364.473 + vertex 443.089 143.916 364.674 + vertex 438.068 140.663 365.119 + endloop + endfacet + facet normal 0.131767 -0.0335025 0.990714 + outer loop + vertex 437.991 137.207 365.012 + vertex 442.872 140.461 364.473 + vertex 438.068 140.663 365.119 + endloop + endfacet + facet normal 0.155581 -0.0339257 0.98724 + outer loop + vertex 437.991 137.207 365.012 + vertex 438.068 140.663 365.119 + vertex 433.24 137.625 365.775 + endloop + endfacet + facet normal 0.1275 -0.0269778 0.991472 + outer loop + vertex 442.866 137.065 364.381 + vertex 442.872 140.461 364.473 + vertex 437.991 137.207 365.012 + endloop + endfacet + facet normal 0.127416 -0.0295732 0.991408 + outer loop + vertex 437.916 133.773 364.919 + vertex 442.866 137.065 364.381 + vertex 437.991 137.207 365.012 + endloop + endfacet + facet normal 0.152819 -0.0300323 0.987798 + outer loop + vertex 437.916 133.773 364.919 + vertex 437.991 137.207 365.012 + vertex 433.109 134.148 365.674 + endloop + endfacet + facet normal 0.124734 -0.0254646 0.991863 + outer loop + vertex 442.854 133.686 364.296 + vertex 442.866 137.065 364.381 + vertex 437.916 133.773 364.919 + endloop + endfacet + facet normal 0.124469 -0.0378753 0.9915 + outer loop + vertex 437.799 130.361 364.804 + vertex 442.854 133.686 364.296 + vertex 437.916 133.773 364.919 + endloop + endfacet + facet normal 0.150581 -0.0386415 0.987842 + outer loop + vertex 437.799 130.361 364.804 + vertex 437.916 133.773 364.919 + vertex 432.944 130.694 365.557 + endloop + endfacet + facet normal 0.122842 -0.035356 0.991796 + outer loop + vertex 442.794 130.329 364.184 + vertex 442.854 133.686 364.296 + vertex 437.799 130.361 364.804 + endloop + endfacet + facet normal 0.122664 -0.0505824 0.991158 + outer loop + vertex 437.64 126.978 364.651 + vertex 442.794 130.329 364.184 + vertex 437.799 130.361 364.804 + endloop + endfacet + facet normal 0.149457 -0.0516761 0.987417 + outer loop + vertex 437.64 126.978 364.651 + vertex 437.799 130.361 364.804 + vertex 432.735 127.269 365.408 + endloop + endfacet + facet normal 0.121855 -0.049315 0.991322 + outer loop + vertex 442.708 126.982 364.028 + vertex 442.794 130.329 364.184 + vertex 437.64 126.978 364.651 + endloop + endfacet + facet normal 0.121748 -0.0665977 0.990324 + outer loop + vertex 437.441 123.61 364.449 + vertex 442.708 126.982 364.028 + vertex 437.64 126.978 364.651 + endloop + endfacet + facet normal 0.148569 -0.0679541 0.986565 + outer loop + vertex 437.441 123.61 364.449 + vertex 437.64 126.978 364.651 + vertex 432.469 123.862 365.215 + endloop + endfacet + facet normal 0.120773 -0.0650476 0.990547 + outer loop + vertex 442.617 123.629 363.819 + vertex 442.708 126.982 364.028 + vertex 437.441 123.61 364.449 + endloop + endfacet + facet normal 0.120661 -0.0855396 0.989001 + outer loop + vertex 437.186 120.25 364.189 + vertex 442.617 123.629 363.819 + vertex 437.441 123.61 364.449 + endloop + endfacet + facet normal 0.147317 -0.087278 0.985231 + outer loop + vertex 437.186 120.25 364.189 + vertex 437.441 123.61 364.449 + vertex 432.133 120.469 364.964 + endloop + endfacet + facet normal 0.119814 -0.0841537 0.989223 + outer loop + vertex 442.467 120.274 363.551 + vertex 442.617 123.629 363.819 + vertex 437.186 120.25 364.189 + endloop + endfacet + facet normal 0.11965 -0.10727 0.987004 + outer loop + vertex 436.843 116.919 363.869 + vertex 442.467 120.274 363.551 + vertex 437.186 120.25 364.189 + endloop + endfacet + facet normal 0.145761 -0.109594 0.983231 + outer loop + vertex 436.843 116.919 363.869 + vertex 437.186 120.25 364.189 + vertex 431.707 117.109 364.651 + endloop + endfacet + facet normal 0.118869 -0.105938 0.987242 + outer loop + vertex 442.233 116.966 363.225 + vertex 442.467 120.274 363.551 + vertex 436.843 116.919 363.869 + endloop + endfacet + facet normal 0.118724 -0.131415 0.984192 + outer loop + vertex 436.401 113.647 363.485 + vertex 442.233 116.966 363.225 + vertex 436.843 116.919 363.869 + endloop + endfacet + facet normal 0.143885 -0.134372 0.980429 + outer loop + vertex 436.401 113.647 363.485 + vertex 436.843 116.919 363.869 + vertex 431.187 113.813 364.273 + endloop + endfacet + facet normal 0.118334 -0.130717 0.984332 + outer loop + vertex 441.908 113.728 362.834 + vertex 442.233 116.966 363.225 + vertex 436.401 113.647 363.485 + endloop + endfacet + facet normal 0.11826 -0.157765 0.98037 + outer loop + vertex 435.887 110.454 363.033 + vertex 441.908 113.728 362.834 + vertex 436.401 113.647 363.485 + endloop + endfacet + facet normal 0.141671 -0.161018 0.976731 + outer loop + vertex 435.887 110.454 363.033 + vertex 436.401 113.647 363.485 + vertex 430.578 110.585 363.825 + endloop + endfacet + facet normal 0.140179 -0.190549 0.971618 + outer loop + vertex 429.935 107.426 363.298 + vertex 435.887 110.454 363.033 + vertex 430.578 110.585 363.825 + endloop + endfacet + facet normal 0.139352 -0.188885 0.972062 + outer loop + vertex 435.37 107.363 362.507 + vertex 435.887 110.454 363.033 + vertex 429.935 107.426 363.298 + endloop + endfacet + facet normal 0.138096 -0.21922 0.965853 + outer loop + vertex 429.339 104.377 362.691 + vertex 435.37 107.363 362.507 + vertex 429.935 107.426 363.298 + endloop + endfacet + facet normal 0.156649 -0.222149 0.962347 + outer loop + vertex 429.339 104.377 362.691 + vertex 429.935 107.426 363.298 + vertex 424.139 104.732 363.62 + endloop + endfacet + facet normal 0.153513 -0.250839 0.955779 + outer loop + vertex 423.402 101.761 362.958 + vertex 429.339 104.377 362.691 + vertex 424.139 104.732 363.62 + endloop + endfacet + facet normal 0.153782 -0.251473 0.955569 + outer loop + vertex 428.75 101.451 362.016 + vertex 429.339 104.377 362.691 + vertex 423.402 101.761 362.958 + endloop + endfacet + facet normal 0.151001 -0.27822 0.948574 + outer loop + vertex 422.513 98.9633 362.279 + vertex 428.75 101.451 362.016 + vertex 423.402 101.761 362.958 + endloop + endfacet + facet normal 0.164378 -0.281682 0.945323 + outer loop + vertex 422.513 98.9633 362.279 + vertex 423.402 101.761 362.958 + vertex 417.684 99.6735 363.331 + endloop + endfacet + facet normal 0.159803 -0.303787 0.939243 + outer loop + vertex 415.842 97.0097 362.782 + vertex 422.513 98.9633 362.279 + vertex 417.684 99.6735 363.331 + endloop + endfacet + facet normal 0.161295 -0.30942 0.937146 + outer loop + vertex 421.588 96.435 361.604 + vertex 422.513 98.9633 362.279 + vertex 415.842 97.0097 362.782 + endloop + endfacet + facet normal 0.157298 -0.333658 0.929478 + outer loop + vertex 414.782 94.7266 362.142 + vertex 421.588 96.435 361.604 + vertex 415.842 97.0097 362.782 + endloop + endfacet + facet normal 0.149855 -0.30604 0.94015 + outer loop + vertex 421.588 96.435 361.604 + vertex 428.12 98.7097 361.303 + vertex 422.513 98.9633 362.279 + endloop + endfacet + facet normal 0.150776 -0.308823 0.939093 + outer loop + vertex 427.528 96.2838 360.6 + vertex 428.12 98.7097 361.303 + vertex 421.588 96.435 361.604 + endloop + endfacet + facet normal 0.148973 -0.33106 0.931776 + outer loop + vertex 420.995 94.3976 360.975 + vertex 427.528 96.2838 360.6 + vertex 421.588 96.435 361.604 + endloop + endfacet + facet normal 0.138711 -0.306625 0.941669 + outer loop + vertex 427.528 96.2838 360.6 + vertex 433.926 98.8145 360.482 + vertex 428.12 98.7097 361.303 + endloop + endfacet + facet normal 0.139313 -0.283027 0.94894 + outer loop + vertex 433.926 98.8145 360.482 + vertex 434.404 101.506 361.214 + vertex 428.12 98.7097 361.303 + endloop + endfacet + facet normal 0.137467 -0.27883 0.950451 + outer loop + vertex 428.12 98.7097 361.303 + vertex 434.404 101.506 361.214 + vertex 428.75 101.451 362.016 + endloop + endfacet + facet normal 0.138267 -0.251503 0.957929 + outer loop + vertex 434.404 101.506 361.214 + vertex 434.884 104.379 361.899 + vertex 428.75 101.451 362.016 + endloop + endfacet + facet normal 0.120641 -0.249261 0.960893 + outer loop + vertex 434.404 101.506 361.214 + vertex 440.698 104.636 361.236 + vertex 434.884 104.379 361.899 + endloop + endfacet + facet normal 0.120166 -0.219765 0.968124 + outer loop + vertex 440.698 104.636 361.236 + vertex 441.107 107.563 361.85 + vertex 434.884 104.379 361.899 + endloop + endfacet + facet normal 0.118511 -0.216514 0.96906 + outer loop + vertex 434.884 104.379 361.899 + vertex 441.107 107.563 361.85 + vertex 435.37 107.363 362.507 + endloop + endfacet + facet normal 0.118179 -0.186417 0.975337 + outer loop + vertex 441.107 107.563 361.85 + vertex 441.519 110.591 362.379 + vertex 435.37 107.363 362.507 + endloop + endfacet + facet normal 0.0996353 -0.184327 0.977802 + outer loop + vertex 441.107 107.563 361.85 + vertex 447.534 110.904 361.825 + vertex 441.519 110.591 362.379 + endloop + endfacet + facet normal 0.0986669 -0.157167 0.982631 + outer loop + vertex 447.534 110.904 361.825 + vertex 447.809 114.004 362.293 + vertex 441.519 110.591 362.379 + endloop + endfacet + facet normal 0.0973468 -0.154721 0.983151 + outer loop + vertex 441.519 110.591 362.379 + vertex 447.809 114.004 362.293 + vertex 441.908 113.728 362.834 + endloop + endfacet + facet normal 0.0965208 -0.129876 0.986821 + outer loop + vertex 447.809 114.004 362.293 + vertex 447.994 117.196 362.695 + vertex 441.908 113.728 362.834 + endloop + endfacet + facet normal 0.0804401 -0.129139 0.988358 + outer loop + vertex 447.809 114.004 362.293 + vertex 454.795 117.851 362.227 + vertex 447.994 117.196 362.695 + endloop + endfacet + facet normal 0.0785031 -0.107046 0.99115 + outer loop + vertex 454.795 117.851 362.227 + vertex 453.584 120.649 362.625 + vertex 447.994 117.196 362.695 + endloop + endfacet + facet normal 0.0771105 -0.104785 0.991501 + outer loop + vertex 447.994 117.196 362.695 + vertex 453.584 120.649 362.625 + vertex 448.059 120.431 363.032 + endloop + endfacet + facet normal 0.0952239 -0.104982 0.989905 + outer loop + vertex 447.994 117.196 362.695 + vertex 448.059 120.431 363.032 + vertex 442.233 116.966 363.225 + endloop + endfacet + facet normal 0.0765385 -0.0870439 0.99326 + outer loop + vertex 453.584 120.649 362.625 + vertex 454.441 124.019 362.854 + vertex 448.059 120.431 363.032 + endloop + endfacet + facet normal 0.0736474 -0.0818699 0.993918 + outer loop + vertex 448.059 120.431 363.032 + vertex 454.441 124.019 362.854 + vertex 448.141 123.799 363.303 + endloop + endfacet + facet normal 0.0945204 -0.0822301 0.992121 + outer loop + vertex 448.059 120.431 363.032 + vertex 448.141 123.799 363.303 + vertex 442.467 120.274 363.551 + endloop + endfacet + facet normal 0.0730244 -0.060888 0.99547 + outer loop + vertex 454.441 124.019 362.854 + vertex 453.921 127.503 363.106 + vertex 448.141 123.799 363.303 + endloop + endfacet + facet normal 0.0740728 -0.0625338 0.99529 + outer loop + vertex 448.141 123.799 363.303 + vertex 453.921 127.503 363.106 + vertex 448.023 127.19 363.525 + endloop + endfacet + facet normal 0.0946537 -0.0617077 0.993596 + outer loop + vertex 448.141 123.799 363.303 + vertex 448.023 127.19 363.525 + vertex 442.617 123.629 363.819 + endloop + endfacet + facet normal 0.0731823 -0.0443407 0.996332 + outer loop + vertex 453.921 127.503 363.106 + vertex 453.527 130.912 363.286 + vertex 448.023 127.19 363.525 + endloop + endfacet + facet normal 0.0748788 -0.046865 0.996091 + outer loop + vertex 448.023 127.19 363.525 + vertex 453.527 130.912 363.286 + vertex 447.95 130.546 363.688 + endloop + endfacet + facet normal 0.0958998 -0.0463216 0.994313 + outer loop + vertex 448.023 127.19 363.525 + vertex 447.95 130.546 363.688 + vertex 442.708 126.982 364.028 + endloop + endfacet + facet normal 0.0738792 -0.030857 0.99679 + outer loop + vertex 453.527 130.912 363.286 + vertex 453.314 134.261 363.406 + vertex 447.95 130.546 363.688 + endloop + endfacet + facet normal 0.0753262 -0.0329596 0.996614 + outer loop + vertex 447.95 130.546 363.688 + vertex 453.314 134.261 363.406 + vertex 447.914 133.876 363.801 + endloop + endfacet + facet normal 0.0969658 -0.0326634 0.994752 + outer loop + vertex 447.95 130.546 363.688 + vertex 447.914 133.876 363.801 + vertex 442.794 130.329 364.184 + endloop + endfacet + facet normal 0.0743322 -0.0185902 0.99706 + outer loop + vertex 453.314 134.261 363.406 + vertex 453.16 137.561 363.479 + vertex 447.914 133.876 363.801 + endloop + endfacet + facet normal 0.0764454 -0.0216172 0.996839 + outer loop + vertex 447.914 133.876 363.801 + vertex 453.16 137.561 363.479 + vertex 447.857 137.196 363.878 + endloop + endfacet + facet normal 0.0981002 -0.0212016 0.994951 + outer loop + vertex 447.914 133.876 363.801 + vertex 447.857 137.196 363.878 + vertex 442.854 133.686 364.296 + endloop + endfacet + facet normal 0.0761832 -0.0177024 0.996937 + outer loop + vertex 453.16 137.561 363.479 + vertex 453.09 140.87 363.543 + vertex 447.857 137.196 363.878 + endloop + endfacet + facet normal 0.0788503 -0.0215268 0.996654 + outer loop + vertex 447.857 137.196 363.878 + vertex 453.09 140.87 363.543 + vertex 447.802 140.53 363.954 + endloop + endfacet + facet normal 0.100942 -0.0211197 0.994668 + outer loop + vertex 447.857 137.196 363.878 + vertex 447.802 140.53 363.954 + vertex 442.866 137.065 364.381 + endloop + endfacet + facet normal 0.0806474 -0.0509126 0.995442 + outer loop + vertex 453.09 140.87 363.543 + vertex 453.228 144.251 363.705 + vertex 447.802 140.53 363.954 + endloop + endfacet + facet normal 0.0849622 -0.057251 0.994738 + outer loop + vertex 447.802 140.53 363.954 + vertex 453.228 144.251 363.705 + vertex 447.981 143.935 364.135 + endloop + endfacet + facet normal 0.105321 -0.0582145 0.992733 + outer loop + vertex 447.802 140.53 363.954 + vertex 447.981 143.935 364.135 + vertex 442.872 140.461 364.473 + endloop + endfacet + facet normal 0.0899685 -0.155336 0.983756 + outer loop + vertex 453.228 144.251 363.705 + vertex 454.125 147.84 364.189 + vertex 447.981 143.935 364.135 + endloop + endfacet + facet normal 0.0910968 -0.157106 0.983371 + outer loop + vertex 447.981 143.935 364.135 + vertex 454.125 147.84 364.189 + vertex 448.893 147.519 364.623 + endloop + endfacet + facet normal 0.108858 -0.161284 0.980886 + outer loop + vertex 447.981 143.935 364.135 + vertex 448.893 147.519 364.623 + vertex 443.089 143.916 364.674 + endloop + endfacet + facet normal 0.0775657 -0.152438 0.985265 + outer loop + vertex 453.228 144.251 363.705 + vertex 459.691 148.432 363.843 + vertex 454.125 147.84 364.189 + endloop + endfacet + facet normal 0.0695798 -0.140174 0.987679 + outer loop + vertex 459.162 144.846 363.371 + vertex 459.691 148.432 363.843 + vertex 453.228 144.251 363.705 + endloop + endfacet + facet normal 0.0646912 -0.139509 0.988105 + outer loop + vertex 459.162 144.846 363.371 + vertex 465.446 149.263 363.583 + vertex 459.691 148.432 363.843 + endloop + endfacet + facet normal 0.0482443 -0.1163 0.992042 + outer loop + vertex 466.477 145.592 363.103 + vertex 465.446 149.263 363.583 + vertex 459.162 144.846 363.371 + endloop + endfacet + facet normal 0.041275 -0.0458373 0.998096 + outer loop + vertex 458.944 141.376 363.221 + vertex 466.477 145.592 363.103 + vertex 459.162 144.846 363.371 + endloop + endfacet + facet normal 0.058946 -0.0469083 0.997158 + outer loop + vertex 458.944 141.376 363.221 + vertex 459.162 144.846 363.371 + vertex 453.09 140.87 363.543 + endloop + endfacet + facet normal 0.0411468 -0.0456077 0.998112 + outer loop + vertex 464.727 141.779 363.001 + vertex 466.477 145.592 363.103 + vertex 458.944 141.376 363.221 + endloop + endfacet + facet normal 0.0391172 -0.015959 0.999107 + outer loop + vertex 459.015 138.073 363.165 + vertex 464.727 141.779 363.001 + vertex 458.944 141.376 363.221 + endloop + endfacet + facet normal 0.0548566 -0.0156065 0.998372 + outer loop + vertex 459.015 138.073 363.165 + vertex 458.944 141.376 363.221 + vertex 453.16 137.561 363.479 + endloop + endfacet + facet normal 0.0373303 -0.0132 0.999216 + outer loop + vertex 466.073 138.915 362.913 + vertex 464.727 141.779 363.001 + vertex 459.015 138.073 363.165 + endloop + endfacet + facet normal 0.0382238 -0.0207402 0.999054 + outer loop + vertex 459.286 134.755 363.086 + vertex 466.073 138.915 362.913 + vertex 459.015 138.073 363.165 + endloop + endfacet + facet normal 0.0550829 -0.0193464 0.998294 + outer loop + vertex 459.286 134.755 363.086 + vertex 459.015 138.073 363.165 + vertex 453.314 134.261 363.406 + endloop + endfacet + facet normal 0.0418236 -0.0266246 0.99877 + outer loop + vertex 465.194 135.152 362.849 + vertex 466.073 138.915 362.913 + vertex 459.286 134.755 363.086 + endloop + endfacet + facet normal 0.0422789 -0.0335231 0.998543 + outer loop + vertex 459.739 131.374 362.953 + vertex 465.194 135.152 362.849 + vertex 459.286 134.755 363.086 + endloop + endfacet + facet normal 0.0558746 -0.0316753 0.997935 + outer loop + vertex 459.739 131.374 362.953 + vertex 459.286 134.755 363.086 + vertex 453.527 130.912 363.286 + endloop + endfacet + facet normal 0.0423004 -0.0335543 0.998541 + outer loop + vertex 466.85 132.262 362.682 + vertex 465.194 135.152 362.849 + vertex 459.739 131.374 362.953 + endloop + endfacet + facet normal 0.0443631 -0.0503234 0.997747 + outer loop + vertex 460.606 127.957 362.742 + vertex 466.85 132.262 362.682 + vertex 459.739 131.374 362.953 + endloop + endfacet + facet normal 0.0574009 -0.0469848 0.997245 + outer loop + vertex 460.606 127.957 362.742 + vertex 459.739 131.374 362.953 + vertex 453.921 127.503 363.106 + endloop + endfacet + facet normal 0.0450616 -0.0513378 0.997664 + outer loop + vertex 466.319 128.961 362.536 + vertex 466.85 132.262 362.682 + vertex 460.606 127.957 362.742 + endloop + endfacet + facet normal 0.0488138 -0.0729979 0.996137 + outer loop + vertex 466.319 128.961 362.536 + vertex 460.606 127.957 362.742 + vertex 462.967 124.177 362.35 + endloop + endfacet + facet normal 0.0415377 -0.0679259 0.996825 + outer loop + vertex 462.967 124.177 362.35 + vertex 474.843 131.986 362.387 + vertex 466.319 128.961 362.536 + endloop + endfacet + facet normal 0.0461907 -0.0749999 0.996113 + outer loop + vertex 475.915 125.634 361.859 + vertex 474.843 131.986 362.387 + vertex 462.967 124.177 362.35 + endloop + endfacet + facet normal 0.0502995 -0.112798 0.992344 + outer loop + vertex 463.046 117.543 361.591 + vertex 475.915 125.634 361.859 + vertex 462.967 124.177 362.35 + endloop + endfacet + facet normal 0.072143 -0.112389 0.991042 + outer loop + vertex 463.046 117.543 361.591 + vertex 462.967 124.177 362.35 + vertex 454.795 117.851 362.227 + endloop + endfacet + facet normal 0.0713076 -0.130349 0.988901 + outer loop + vertex 453.517 114.258 361.846 + vertex 463.046 117.543 361.591 + vertex 454.795 117.851 362.227 + endloop + endfacet + facet normal 0.0832083 -0.165348 0.982719 + outer loop + vertex 453.517 114.258 361.846 + vertex 454.516 111.572 361.309 + vertex 463.046 117.543 361.591 + endloop + endfacet + facet normal 0.0873779 -0.17124 0.981347 + outer loop + vertex 462.816 111.402 360.54 + vertex 463.046 117.543 361.591 + vertex 454.516 111.572 361.309 + endloop + endfacet + facet normal 0.0865055 -0.194551 0.97707 + outer loop + vertex 453.033 108.206 360.77 + vertex 462.816 111.402 360.54 + vertex 454.516 111.572 361.309 + endloop + endfacet + facet normal 0.0950008 -0.198056 0.975576 + outer loop + vertex 453.033 108.206 360.77 + vertex 454.516 111.572 361.309 + vertex 447.204 107.918 361.279 + endloop + endfacet + facet normal 0.095813 -0.225025 0.969631 + outer loop + vertex 446.851 105.008 360.639 + vertex 453.033 108.206 360.77 + vertex 447.204 107.918 361.279 + endloop + endfacet + facet normal 0.107662 -0.22613 0.968129 + outer loop + vertex 446.851 105.008 360.639 + vertex 447.204 107.918 361.279 + vertex 440.698 104.636 361.236 + endloop + endfacet + facet normal 0.108654 -0.25369 0.961164 + outer loop + vertex 440.292 101.799 360.533 + vertex 446.851 105.008 360.639 + vertex 440.698 104.636 361.236 + endloop + endfacet + facet normal 0.11336 -0.263205 0.958057 + outer loop + vertex 446.544 102.197 359.903 + vertex 446.851 105.008 360.639 + vertex 440.292 101.799 360.533 + endloop + endfacet + facet normal 0.114147 -0.286152 0.951361 + outer loop + vertex 439.994 99.1494 359.772 + vertex 446.544 102.197 359.903 + vertex 440.292 101.799 360.533 + endloop + endfacet + facet normal 0.126905 -0.287047 0.949473 + outer loop + vertex 439.994 99.1494 359.772 + vertex 440.292 101.799 360.533 + vertex 433.926 98.8145 360.482 + endloop + endfacet + facet normal 0.104072 -0.262515 0.959299 + outer loop + vertex 446.544 102.197 359.903 + vertex 453.979 105.715 360.059 + vertex 446.851 105.008 360.639 + endloop + endfacet + facet normal 0.107441 -0.269533 0.956979 + outer loop + vertex 452.552 102.605 359.343 + vertex 453.979 105.715 360.059 + vertex 446.544 102.197 359.903 + endloop + endfacet + facet normal 0.108369 -0.292729 0.950035 + outer loop + vertex 446.56 99.6868 359.128 + vertex 452.552 102.605 359.343 + vertex 446.544 102.197 359.903 + endloop + endfacet + facet normal 0.110379 -0.296748 0.948555 + outer loop + vertex 454 100.747 358.593 + vertex 452.552 102.605 359.343 + vertex 446.56 99.6868 359.128 + endloop + endfacet + facet normal 0.109601 -0.297318 0.948467 + outer loop + vertex 452.552 102.605 359.343 + vertex 454 100.747 358.593 + vertex 462.479 105.871 359.22 + endloop + endfacet + facet normal 0.105096 -0.290196 0.951179 + outer loop + vertex 462.578 101.59 357.903 + vertex 462.479 105.871 359.22 + vertex 454 100.747 358.593 + endloop + endfacet + facet normal 0.0938059 -0.290765 0.952185 + outer loop + vertex 462.578 101.59 357.903 + vertex 475.765 108.119 358.597 + vertex 462.479 105.871 359.22 + endloop + endfacet + facet normal 0.0981876 -0.299286 0.949098 + outer loop + vertex 476.538 104.353 357.33 + vertex 475.765 108.119 358.597 + vertex 462.578 101.59 357.903 + endloop + endfacet + facet normal 0.0900837 -0.301035 0.949349 + outer loop + vertex 476.538 104.353 357.33 + vertex 488.566 110.76 358.22 + vertex 475.765 108.119 358.597 + endloop + endfacet + facet normal 0.0944313 -0.308791 0.946431 + outer loop + vertex 489.336 107.207 356.984 + vertex 488.566 110.76 358.22 + vertex 476.538 104.353 357.33 + endloop + endfacet + facet normal 0.0883786 -0.310152 0.94657 + outer loop + vertex 489.336 107.207 356.984 + vertex 500.791 113.677 358.035 + vertex 488.566 110.76 358.22 + endloop + endfacet + facet normal 0.0933077 -0.318359 0.943367 + outer loop + vertex 501.445 110.16 356.783 + vertex 500.791 113.677 358.035 + vertex 489.336 107.207 356.984 + endloop + endfacet + facet normal 0.0890438 -0.319198 0.943496 + outer loop + vertex 501.445 110.16 356.783 + vertex 512.719 116.76 357.952 + vertex 500.791 113.677 358.035 + endloop + endfacet + facet normal 0.0934703 -0.326255 0.940649 + outer loop + vertex 513.149 113.069 356.629 + vertex 512.719 116.76 357.952 + vertex 501.445 110.16 356.783 + endloop + endfacet + facet normal 0.0909374 -0.326596 0.940779 + outer loop + vertex 513.149 113.069 356.629 + vertex 524.603 119.92 357.9 + vertex 512.719 116.76 357.952 + endloop + endfacet + facet normal 0.095391 -0.33351 0.937908 + outer loop + vertex 524.961 116.132 356.517 + vertex 524.603 119.92 357.9 + vertex 513.149 113.069 356.629 + endloop + endfacet + facet normal 0.0947464 -0.333585 0.937947 + outer loop + vertex 524.961 116.132 356.517 + vertex 536.661 123.236 357.862 + vertex 524.603 119.92 357.9 + endloop + endfacet + facet normal 0.0970754 -0.337135 0.936438 + outer loop + vertex 537.044 119.399 356.441 + vertex 536.661 123.236 357.862 + vertex 524.961 116.132 356.517 + endloop + endfacet + facet normal 0.0977208 -0.337056 0.936399 + outer loop + vertex 537.044 119.399 356.441 + vertex 549.021 126.739 357.832 + vertex 536.661 123.236 357.862 + endloop + endfacet + facet normal 0.0986044 -0.338389 0.935826 + outer loop + vertex 549.475 122.889 356.393 + vertex 549.021 126.739 357.832 + vertex 537.044 119.399 356.441 + endloop + endfacet + facet normal 0.0980338 -0.338468 0.935857 + outer loop + vertex 549.475 122.889 356.393 + vertex 561.635 130.272 357.789 + vertex 549.021 126.739 357.832 + endloop + endfacet + facet normal 0.0977867 -0.338092 0.936019 + outer loop + vertex 562.079 126.444 356.36 + vertex 561.635 130.272 357.789 + vertex 549.475 122.889 356.393 + endloop + endfacet + facet normal 0.0948416 -0.338492 0.936177 + outer loop + vertex 562.079 126.444 356.36 + vertex 573.956 133.426 357.681 + vertex 561.635 130.272 357.789 + endloop + endfacet + facet normal 0.0985285 -0.344291 0.933679 + outer loop + vertex 574.191 129.705 356.284 + vertex 573.956 133.426 357.681 + vertex 562.079 126.444 356.36 + endloop + endfacet + facet normal 0.094391 -0.344661 0.933969 + outer loop + vertex 574.191 129.705 356.284 + vertex 584.387 135.572 357.419 + vertex 573.956 133.426 357.681 + endloop + endfacet + facet normal 0.104619 -0.361027 0.926668 + outer loop + vertex 584.554 132.17 356.075 + vertex 584.387 135.572 357.419 + vertex 574.191 129.705 356.284 + endloop + endfacet + facet normal 0.105034 -0.360993 0.926635 + outer loop + vertex 584.387 135.572 357.419 + vertex 584.554 132.17 356.075 + vertex 592.657 137.039 357.053 + endloop + endfacet + facet normal 0.101726 -0.34032 0.934791 + outer loop + vertex 592.657 137.039 357.053 + vertex 592.151 140.123 358.231 + vertex 584.387 135.572 357.419 + endloop + endfacet + facet normal 0.0762253 -0.299712 0.95098 + outer loop + vertex 586.134 140.616 358.868 + vertex 584.387 135.572 357.419 + vertex 592.151 140.123 358.231 + endloop + endfacet + facet normal 0.0778561 -0.285322 0.955264 + outer loop + vertex 592.151 140.123 358.231 + vertex 594.779 143.803 359.116 + vertex 586.134 140.616 358.868 + endloop + endfacet + facet normal 0.0660787 -0.254124 0.964912 + outer loop + vertex 594.779 143.803 359.116 + vertex 593.004 145.956 359.805 + vertex 586.134 140.616 358.868 + endloop + endfacet + facet normal 0.0488743 -0.2331 0.971224 + outer loop + vertex 586.497 146.415 360.242 + vertex 586.134 140.616 358.868 + vertex 593.004 145.956 359.805 + endloop + endfacet + facet normal 0.0510546 -0.207591 0.976883 + outer loop + vertex 593.004 145.956 359.805 + vertex 595.103 149.696 360.49 + vertex 586.497 146.415 360.242 + endloop + endfacet + facet normal 0.0374066 -0.172353 0.984325 + outer loop + vertex 595.103 149.696 360.49 + vertex 593.762 152.965 361.113 + vertex 586.497 146.415 360.242 + endloop + endfacet + facet normal 0.0332182 -0.167831 0.985256 + outer loop + vertex 586.195 152.661 361.316 + vertex 586.497 146.415 360.242 + vertex 593.762 152.965 361.113 + endloop + endfacet + facet normal 0.0324168 -0.145538 0.988821 + outer loop + vertex 593.762 152.965 361.113 + vertex 593.417 155.912 361.558 + vertex 586.195 152.661 361.316 + endloop + endfacet + facet normal 0.00923253 -0.0945281 0.995479 + outer loop + vertex 593.417 155.912 361.558 + vertex 593.498 159.13 361.863 + vertex 586.195 152.661 361.316 + endloop + endfacet + facet normal 0.0174783 -0.103749 0.99445 + outer loop + vertex 586.05 159.246 362.006 + vertex 586.195 152.661 361.316 + vertex 593.498 159.13 361.863 + endloop + endfacet + facet normal 0.0179701 -0.0752437 0.997003 + outer loop + vertex 593.498 159.13 361.863 + vertex 594.558 163.589 362.18 + vertex 586.05 159.246 362.006 + endloop + endfacet + facet normal 0.00952564 -0.0587482 0.998227 + outer loop + vertex 594.558 163.589 362.18 + vertex 592.369 165.633 362.321 + vertex 586.05 159.246 362.006 + endloop + endfacet + facet normal 0.00824018 -0.0574806 0.998313 + outer loop + vertex 585.941 165.764 362.382 + vertex 586.05 159.246 362.006 + vertex 592.369 165.633 362.321 + endloop + endfacet + facet normal 0.00868566 -0.0360185 0.999313 + outer loop + vertex 592.369 165.633 362.321 + vertex 594.323 169.612 362.448 + vertex 585.941 165.764 362.382 + endloop + endfacet + facet normal 0.004328 -0.0265332 0.999639 + outer loop + vertex 594.323 169.612 362.448 + vertex 592.609 171.889 362.516 + vertex 585.941 165.764 362.382 + endloop + endfacet + facet normal 0.0102207 -0.0329423 0.999405 + outer loop + vertex 586.319 172.554 362.602 + vertex 585.941 165.764 362.382 + vertex 592.609 171.889 362.516 + endloop + endfacet + facet normal 0.0113413 -0.0223738 0.999685 + outer loop + vertex 592.609 171.889 362.516 + vertex 595.203 175.833 362.574 + vertex 586.319 172.554 362.602 + endloop + endfacet + facet normal 0.0211764 -0.0490303 0.998573 + outer loop + vertex 595.203 175.833 362.574 + vertex 595.436 179.782 362.763 + vertex 586.319 172.554 362.602 + endloop + endfacet + facet normal 0.0370626 -0.0690333 0.996926 + outer loop + vertex 585.973 180.276 363.149 + vertex 586.319 172.554 362.602 + vertex 595.436 179.782 362.763 + endloop + endfacet + facet normal 0.0345063 -0.11474 0.992796 + outer loop + vertex 595.436 179.782 362.763 + vertex 598.068 183.913 363.149 + vertex 585.973 180.276 363.149 + endloop + endfacet + facet normal 0.0354401 -0.115326 0.992695 + outer loop + vertex 598.068 183.913 363.149 + vertex 595.436 179.782 362.763 + vertex 606.421 186.48 363.149 + endloop + endfacet + facet normal 0.0162362 -0.0840429 0.99633 + outer loop + vertex 595.436 179.782 362.763 + vertex 600.577 179.448 362.651 + vertex 606.421 186.48 363.149 + endloop + endfacet + facet normal 0.0162019 -0.0840146 0.996333 + outer loop + vertex 600.577 179.448 362.651 + vertex 605.402 180.124 362.63 + vertex 606.421 186.48 363.149 + endloop + endfacet + facet normal 0.0314426 -0.0864095 0.995763 + outer loop + vertex 605.402 180.124 362.63 + vertex 613.381 183.971 362.712 + vertex 606.421 186.48 363.149 + endloop + endfacet + facet normal 0.029092 -0.0928425 0.995256 + outer loop + vertex 615.191 189.228 363.149 + vertex 606.421 186.48 363.149 + vertex 613.381 183.971 362.712 + endloop + endfacet + facet normal 0.0297914 -0.0930799 0.995213 + outer loop + vertex 613.381 183.971 362.712 + vertex 623.718 191.957 363.149 + vertex 615.191 189.228 363.149 + endloop + endfacet + facet normal 0.0253769 -0.0874006 0.99585 + outer loop + vertex 622.67 186.31 362.68 + vertex 623.718 191.957 363.149 + vertex 613.381 183.971 362.712 + endloop + endfacet + facet normal 0.01364 -0.0407376 0.999077 + outer loop + vertex 614.26 178.283 362.468 + vertex 622.67 186.31 362.68 + vertex 613.381 183.971 362.712 + endloop + endfacet + facet normal 0.0132448 -0.0407988 0.99908 + outer loop + vertex 614.26 178.283 362.468 + vertex 613.381 183.971 362.712 + vertex 606.558 176.113 362.482 + endloop + endfacet + facet normal 0.0113388 -0.03403 0.999356 + outer loop + vertex 606.906 170.875 362.299 + vertex 614.26 178.283 362.468 + vertex 606.558 176.113 362.482 + endloop + endfacet + facet normal 0.0153219 -0.0337637 0.999312 + outer loop + vertex 606.906 170.875 362.299 + vertex 606.558 176.113 362.482 + vertex 599.418 169.274 362.36 + endloop + endfacet + facet normal 0.0191109 -0.0515221 0.998489 + outer loop + vertex 600.195 164.422 362.095 + vertex 606.906 170.875 362.299 + vertex 599.418 169.274 362.36 + endloop + endfacet + facet normal 0.0226708 -0.0509497 0.998444 + outer loop + vertex 600.195 164.422 362.095 + vertex 599.418 169.274 362.36 + vertex 594.558 163.589 362.18 + endloop + endfacet + facet normal 0.0243481 -0.0569556 0.99808 + outer loop + vertex 606.881 165.532 361.995 + vertex 606.906 170.875 362.299 + vertex 600.195 164.422 362.095 + endloop + endfacet + facet normal 0.0290406 -0.0854118 0.995922 + outer loop + vertex 599.375 158.805 361.637 + vertex 606.881 165.532 361.995 + vertex 600.195 164.422 362.095 + endloop + endfacet + facet normal 0.0335124 -0.086049 0.995727 + outer loop + vertex 599.375 158.805 361.637 + vertex 600.195 164.422 362.095 + vertex 593.498 159.13 361.863 + endloop + endfacet + facet normal 0.0367776 -0.0939912 0.994893 + outer loop + vertex 606.963 160.327 361.5 + vertex 606.881 165.532 361.995 + vertex 599.375 158.805 361.637 + endloop + endfacet + facet normal 0.0303739 -0.0941109 0.995098 + outer loop + vertex 606.963 160.327 361.5 + vertex 614.329 167.462 361.95 + vertex 606.881 165.532 361.995 + endloop + endfacet + facet normal 0.0215555 -0.0600264 0.997964 + outer loop + vertex 614.329 167.462 361.95 + vertex 614.338 172.797 362.271 + vertex 606.881 165.532 361.995 + endloop + endfacet + facet normal 0.0178903 -0.0600245 0.998037 + outer loop + vertex 614.329 167.462 361.95 + vertex 622.39 175.315 362.278 + vertex 614.338 172.797 362.271 + endloop + endfacet + facet normal 0.0103632 -0.0359594 0.9993 + outer loop + vertex 622.39 175.315 362.278 + vertex 622.434 180.715 362.472 + vertex 614.338 172.797 362.271 + endloop + endfacet + facet normal 0.010181 -0.0357733 0.999308 + outer loop + vertex 614.338 172.797 362.271 + vertex 622.434 180.715 362.472 + vertex 614.26 178.283 362.468 + endloop + endfacet + facet normal 0.0100844 -0.0359572 0.999302 + outer loop + vertex 622.39 175.315 362.278 + vertex 630.934 183.542 362.488 + vertex 622.434 180.715 362.472 + endloop + endfacet + facet normal 0.0104521 -0.0370625 0.999258 + outer loop + vertex 630.934 183.542 362.488 + vertex 631.235 189.024 362.688 + vertex 622.434 180.715 362.472 + endloop + endfacet + facet normal 0.0110931 -0.0377406 0.999226 + outer loop + vertex 622.434 180.715 362.472 + vertex 631.235 189.024 362.688 + vertex 622.67 186.31 362.68 + endloop + endfacet + facet normal 0.0260277 -0.0848657 0.996052 + outer loop + vertex 631.235 189.024 362.688 + vertex 632.327 194.776 363.149 + vertex 622.67 186.31 362.68 + endloop + endfacet + facet normal 0.0286136 -0.0853476 0.99594 + outer loop + vertex 631.235 189.024 362.688 + vertex 640.827 197.625 363.149 + vertex 632.327 194.776 363.149 + endloop + endfacet + facet normal 0.027921 -0.0845798 0.996025 + outer loop + vertex 639.933 191.976 362.695 + vertex 640.827 197.625 363.149 + vertex 631.235 189.024 362.688 + endloop + endfacet + facet normal 0.0291655 -0.0847726 0.995973 + outer loop + vertex 639.933 191.976 362.695 + vertex 649.819 200.719 363.149 + vertex 640.827 197.625 363.149 + endloop + endfacet + facet normal 0.0293433 -0.0849725 0.995951 + outer loop + vertex 648.766 195.049 362.697 + vertex 649.819 200.719 363.149 + vertex 639.933 191.976 362.695 + endloop + endfacet + facet normal 0.0126139 -0.0369016 0.999239 + outer loop + vertex 639.699 186.566 362.498 + vertex 648.766 195.049 362.697 + vertex 639.933 191.976 362.695 + endloop + endfacet + facet normal 0.0115565 -0.0368563 0.999254 + outer loop + vertex 639.699 186.566 362.498 + vertex 639.933 191.976 362.695 + vertex 630.934 183.542 362.488 + endloop + endfacet + facet normal 0.0110784 -0.0354706 0.999309 + outer loop + vertex 630.962 178.234 362.299 + vertex 639.699 186.566 362.498 + vertex 630.934 183.542 362.488 + endloop + endfacet + facet normal 0.0106189 -0.0349893 0.999331 + outer loop + vertex 639.733 181.268 362.312 + vertex 639.699 186.566 362.498 + vertex 630.962 178.234 362.299 + endloop + endfacet + facet normal 0.0193076 -0.0601008 0.998006 + outer loop + vertex 631.069 172.986 361.981 + vertex 639.733 181.268 362.312 + vertex 630.962 178.234 362.299 + endloop + endfacet + facet normal 0.0173295 -0.060143 0.998039 + outer loop + vertex 631.069 172.986 361.981 + vertex 630.962 178.234 362.299 + vertex 622.454 170.049 361.953 + endloop + endfacet + facet normal 0.0307911 -0.0995959 0.994551 + outer loop + vertex 622.599 164.846 361.428 + vertex 631.069 172.986 361.981 + vertex 622.454 170.049 361.953 + endloop + endfacet + facet normal 0.0313237 -0.0995795 0.994536 + outer loop + vertex 622.599 164.846 361.428 + vertex 622.454 170.049 361.953 + vertex 614.461 162.272 361.427 + endloop + endfacet + facet normal 0.0312745 -0.0995294 0.994543 + outer loop + vertex 614.461 162.272 361.427 + vertex 622.454 170.049 361.953 + vertex 614.329 167.462 361.95 + endloop + endfacet + facet normal 0.0298742 -0.0986501 0.994674 + outer loop + vertex 631.209 167.761 361.458 + vertex 631.069 172.986 361.981 + vertex 622.599 164.846 361.428 + endloop + endfacet + facet normal 0.0320628 -0.0985853 0.994612 + outer loop + vertex 631.209 167.761 361.458 + vertex 639.802 175.995 361.998 + vertex 631.069 172.986 361.981 + endloop + endfacet + facet normal 0.0307092 -0.0971843 0.994793 + outer loop + vertex 639.906 170.739 361.481 + vertex 639.802 175.995 361.998 + vertex 631.209 167.761 361.458 + endloop + endfacet + facet normal 0.0341068 -0.0971074 0.994689 + outer loop + vertex 639.906 170.739 361.481 + vertex 648.458 179.025 361.997 + vertex 639.802 175.995 361.998 + endloop + endfacet + facet normal 0.0210302 -0.0597563 0.997991 + outer loop + vertex 648.458 179.025 361.997 + vertex 648.469 184.325 362.314 + vertex 639.802 175.995 361.998 + endloop + endfacet + facet normal 0.0205367 -0.0592444 0.998032 + outer loop + vertex 639.802 175.995 361.998 + vertex 648.469 184.325 362.314 + vertex 639.733 181.268 362.312 + endloop + endfacet + facet normal 0.0119481 -0.0346937 0.999327 + outer loop + vertex 648.469 184.325 362.314 + vertex 648.525 189.651 362.498 + vertex 639.733 181.268 362.312 + endloop + endfacet + facet normal 0.0130809 -0.0347051 0.999312 + outer loop + vertex 648.469 184.325 362.314 + vertex 657.338 192.822 362.493 + vertex 648.525 189.651 362.498 + endloop + endfacet + facet normal 0.0141061 -0.0375543 0.999195 + outer loop + vertex 657.338 192.822 362.493 + vertex 657.523 198.174 362.691 + vertex 648.525 189.651 362.498 + endloop + endfacet + facet normal 0.0139743 -0.0374153 0.999202 + outer loop + vertex 648.525 189.651 362.498 + vertex 657.523 198.174 362.691 + vertex 648.766 195.049 362.697 + endloop + endfacet + facet normal 0.0315672 -0.0867243 0.995732 + outer loop + vertex 657.523 198.174 362.691 + vertex 658.261 203.703 363.149 + vertex 648.766 195.049 362.697 + endloop + endfacet + facet normal 0.0314786 -0.0867128 0.995736 + outer loop + vertex 657.523 198.174 362.691 + vertex 666.163 206.572 363.149 + vertex 658.261 203.703 363.149 + endloop + endfacet + facet normal 0.0323037 -0.0875562 0.995636 + outer loop + vertex 666.206 201.359 362.69 + vertex 666.163 206.572 363.149 + vertex 657.523 198.174 362.691 + endloop + endfacet + facet normal 0.0326834 -0.0875521 0.995624 + outer loop + vertex 666.206 201.359 362.69 + vertex 674.734 209.772 363.149 + vertex 666.163 206.572 363.149 + endloop + endfacet + facet normal 0.0316238 -0.0864848 0.995751 + outer loop + vertex 674.608 204.38 362.685 + vertex 674.734 209.772 363.149 + vertex 666.206 201.359 362.69 + endloop + endfacet + facet normal 0.0142305 -0.038099 0.999173 + outer loop + vertex 666.116 196.059 362.489 + vertex 674.608 204.38 362.685 + vertex 666.206 201.359 362.69 + endloop + endfacet + facet normal 0.0144944 -0.0381034 0.999169 + outer loop + vertex 666.116 196.059 362.489 + vertex 666.206 201.359 362.69 + vertex 657.338 192.822 362.493 + endloop + endfacet + facet normal 0.013372 -0.0350592 0.999296 + outer loop + vertex 657.205 187.494 362.308 + vertex 666.116 196.059 362.489 + vertex 657.338 192.822 362.493 + endloop + endfacet + facet normal 0.0138546 -0.0355609 0.999271 + outer loop + vertex 666.029 190.761 362.301 + vertex 666.116 196.059 362.489 + vertex 657.205 187.494 362.308 + endloop + endfacet + facet normal 0.0226438 -0.059301 0.997983 + outer loop + vertex 657.134 182.184 361.994 + vertex 666.029 190.761 362.301 + vertex 657.205 187.494 362.308 + endloop + endfacet + facet normal 0.0219292 -0.0592924 0.998 + outer loop + vertex 657.134 182.184 361.994 + vertex 657.205 187.494 362.308 + vertex 648.458 179.025 361.997 + endloop + endfacet + facet normal 0.0357001 -0.0971106 0.994633 + outer loop + vertex 648.516 173.748 361.479 + vertex 657.134 182.184 361.994 + vertex 648.458 179.025 361.997 + endloop + endfacet + facet normal 0.0357672 -0.0971786 0.994624 + outer loop + vertex 657.154 176.894 361.476 + vertex 657.134 182.184 361.994 + vertex 648.516 173.748 361.479 + endloop + endfacet + facet normal 0.036938 -0.0971699 0.994582 + outer loop + vertex 657.154 176.894 361.476 + vertex 665.949 185.447 361.985 + vertex 657.134 182.184 361.994 + endloop + endfacet + facet normal 0.0371812 -0.097418 0.994549 + outer loop + vertex 665.927 180.141 361.466 + vertex 665.949 185.447 361.985 + vertex 657.154 176.894 361.476 + endloop + endfacet + facet normal 0.035056 -0.0974166 0.994626 + outer loop + vertex 665.927 180.141 361.466 + vertex 674.543 188.376 361.969 + vertex 665.949 185.447 361.985 + endloop + endfacet + facet normal 0.0224898 -0.0605244 0.997913 + outer loop + vertex 674.543 188.376 361.969 + vertex 674.747 193.78 362.292 + vertex 665.949 185.447 361.985 + endloop + endfacet + facet normal 0.0217564 -0.0597524 0.997976 + outer loop + vertex 665.949 185.447 361.985 + vertex 674.747 193.78 362.292 + vertex 666.029 190.761 362.301 + endloop + endfacet + facet normal 0.0134277 -0.0356963 0.999272 + outer loop + vertex 674.747 193.78 362.292 + vertex 674.662 199.043 362.481 + vertex 666.029 190.761 362.301 + endloop + endfacet + facet normal 0.011986 -0.0357201 0.99929 + outer loop + vertex 674.747 193.78 362.292 + vertex 682.789 201.45 362.47 + vertex 674.662 199.043 362.481 + endloop + endfacet + facet normal 0.0104492 -0.03053 0.999479 + outer loop + vertex 682.789 201.45 362.47 + vertex 681.894 206.286 362.627 + vertex 674.662 199.043 362.481 + endloop + endfacet + facet normal 0.0179141 -0.0379764 0.999118 + outer loop + vertex 674.662 199.043 362.481 + vertex 681.894 206.286 362.627 + vertex 674.608 204.38 362.685 + endloop + endfacet + facet normal 0.0296545 -0.0829535 0.996112 + outer loop + vertex 681.894 206.286 362.627 + vertex 683.148 213.008 363.149 + vertex 674.608 204.38 362.685 + endloop + endfacet + facet normal 0.0578531 -0.0880851 0.994432 + outer loop + vertex 683.148 213.008 363.149 + vertex 681.894 206.286 362.627 + vertex 687.586 211.573 362.764 + endloop + endfacet + facet normal 0.0474365 -0.119557 0.991693 + outer loop + vertex 687.586 211.573 362.764 + vertex 691.72 216.409 363.149 + vertex 683.148 213.008 363.149 + endloop + endfacet + facet normal 0.0486334 -0.120566 0.991513 + outer loop + vertex 691.72 216.409 363.149 + vertex 687.586 211.573 362.764 + vertex 692.078 216.553 363.149 + endloop + endfacet + facet normal 0.00857216 -0.0848073 0.99636 + outer loop + vertex 691.076 210.472 362.64 + vertex 692.078 216.553 363.149 + vertex 687.586 211.573 362.764 + endloop + endfacet + facet normal 0.0212632 -0.0448344 0.998768 + outer loop + vertex 687.586 211.573 362.764 + vertex 687.169 206.846 362.561 + vertex 691.076 210.472 362.64 + endloop + endfacet + facet normal 0.00606355 -0.0284728 0.999576 + outer loop + vertex 690.551 205.425 362.5 + vertex 691.076 210.472 362.64 + vertex 687.169 206.846 362.561 + endloop + endfacet + facet normal 0.0099648 -0.0191898 0.999766 + outer loop + vertex 687.169 206.846 362.561 + vertex 687.472 204.181 362.507 + vertex 690.551 205.425 362.5 + endloop + endfacet + facet normal 0.0133148 -0.0274803 0.999534 + outer loop + vertex 687.472 204.181 362.507 + vertex 687.517 201.339 362.428 + vertex 690.551 205.425 362.5 + endloop + endfacet + facet normal 0.017305 -0.0304406 0.999387 + outer loop + vertex 691.16 200.85 362.35 + vertex 690.551 205.425 362.5 + vertex 687.517 201.339 362.428 + endloop + endfacet + facet normal 0.0119798 -0.0311517 0.999443 + outer loop + vertex 694.842 204.38 362.416 + vertex 690.551 205.425 362.5 + vertex 691.16 200.85 362.35 + endloop + endfacet + facet normal 0.0251802 -0.0449067 0.998674 + outer loop + vertex 694.842 204.38 362.416 + vertex 691.16 200.85 362.35 + vertex 695.285 199.307 362.177 + endloop + endfacet + facet normal 0.0159894 -0.0457166 0.998826 + outer loop + vertex 694.842 204.38 362.416 + vertex 695.285 199.307 362.177 + vertex 700.592 203.394 362.279 + endloop + endfacet + facet normal 0.0179111 -0.0345757 0.999242 + outer loop + vertex 700.592 203.394 362.279 + vertex 699.939 209.135 362.489 + vertex 694.842 204.38 362.416 + endloop + endfacet + facet normal 0.0110838 -0.0272631 0.999567 + outer loop + vertex 694.093 208.553 362.538 + vertex 694.842 204.38 362.416 + vertex 699.939 209.135 362.489 + endloop + endfacet + facet normal 0.0123957 -0.0404825 0.999103 + outer loop + vertex 695.822 213.672 362.724 + vertex 694.093 208.553 362.538 + vertex 699.939 209.135 362.489 + endloop + endfacet + facet normal 0.0176364 -0.0357326 0.999206 + outer loop + vertex 699.939 209.135 362.489 + vertex 702.208 214.659 362.646 + vertex 695.822 213.672 362.724 + endloop + endfacet + facet normal 0.0251225 -0.0844282 0.996113 + outer loop + vertex 702.208 214.659 362.646 + vertex 701.132 220.272 363.149 + vertex 695.822 213.672 362.724 + endloop + endfacet + facet normal 0.0393771 -0.0958 0.994621 + outer loop + vertex 701.132 220.272 363.149 + vertex 692.436 216.698 363.149 + vertex 695.822 213.672 362.724 + endloop + endfacet + facet normal 0.0389107 -0.0963175 0.99459 + outer loop + vertex 692.436 216.698 363.149 + vertex 692.078 216.553 363.149 + vertex 695.822 213.672 362.724 + endloop + endfacet + facet normal 0.0387025 -0.0818077 0.995896 + outer loop + vertex 708.774 218.33 362.693 + vertex 701.132 220.272 363.149 + vertex 702.208 214.659 362.646 + endloop + endfacet + facet normal 0.0135937 -0.0369391 0.999225 + outer loop + vertex 708.774 218.33 362.693 + vertex 702.208 214.659 362.646 + vertex 708.3 212.961 362.501 + endloop + endfacet + facet normal 0.0165273 -0.0371964 0.999171 + outer loop + vertex 717.109 217.101 362.509 + vertex 708.774 218.33 362.693 + vertex 708.3 212.961 362.501 + endloop + endfacet + facet normal 0.0145016 -0.0328868 0.999354 + outer loop + vertex 717.109 217.101 362.509 + vertex 708.3 212.961 362.501 + vertex 717.058 212.019 362.343 + endloop + endfacet + facet normal 0.0151506 -0.0328929 0.999344 + outer loop + vertex 726.448 216.341 362.343 + vertex 717.109 217.101 362.509 + vertex 717.058 212.019 362.343 + endloop + endfacet + facet normal 0.0253186 -0.0549875 0.998166 + outer loop + vertex 726.448 216.341 362.343 + vertex 717.058 212.019 362.343 + vertex 726.526 211.352 362.066 + endloop + endfacet + facet normal 0.0260437 -0.0549751 0.998148 + outer loop + vertex 735.71 215.618 362.061 + vertex 726.448 216.341 362.343 + vertex 726.526 211.352 362.066 + endloop + endfacet + facet normal 0.0417719 -0.0888386 0.99517 + outer loop + vertex 735.71 215.618 362.061 + vertex 726.526 211.352 362.066 + vertex 735.786 210.627 361.612 + endloop + endfacet + facet normal 0.043594 -0.0888041 0.995095 + outer loop + vertex 744.551 214.863 361.606 + vertex 735.71 215.618 362.061 + vertex 735.786 210.627 361.612 + endloop + endfacet + facet normal 0.0648593 -0.132813 0.989017 + outer loop + vertex 744.551 214.863 361.606 + vertex 735.786 210.627 361.612 + vertex 744.643 209.882 360.932 + endloop + endfacet + facet normal 0.0678396 -0.132733 0.988827 + outer loop + vertex 753.165 214.224 360.93 + vertex 744.551 214.863 361.606 + vertex 744.643 209.882 360.932 + endloop + endfacet + facet normal 0.0678492 -0.13262 0.988842 + outer loop + vertex 753.068 219.208 361.605 + vertex 744.551 214.863 361.606 + vertex 753.165 214.224 360.93 + endloop + endfacet + facet normal 0.070685 -0.132539 0.988654 + outer loop + vertex 761.638 218.747 360.93 + vertex 753.068 219.208 361.605 + vertex 753.165 214.224 360.93 + endloop + endfacet + facet normal 0.0706721 -0.13274 0.988628 + outer loop + vertex 761.535 223.728 361.606 + vertex 753.068 219.208 361.605 + vertex 761.638 218.747 360.93 + endloop + endfacet + facet normal 0.0737588 -0.132648 0.988415 + outer loop + vertex 770.137 223.458 360.928 + vertex 761.535 223.728 361.606 + vertex 761.638 218.747 360.93 + endloop + endfacet + facet normal 0.0737479 -0.132909 0.988381 + outer loop + vertex 770.026 228.432 361.605 + vertex 761.535 223.728 361.606 + vertex 770.137 223.458 360.928 + endloop + endfacet + facet normal 0.0765012 -0.13282 0.988183 + outer loop + vertex 778.635 228.338 360.926 + vertex 770.026 228.432 361.605 + vertex 770.137 223.458 360.928 + endloop + endfacet + facet normal 0.076505 -0.132644 0.988207 + outer loop + vertex 778.517 233.309 361.603 + vertex 770.026 228.432 361.605 + vertex 778.635 228.338 360.926 + endloop + endfacet + facet normal 0.0801775 -0.132519 0.987932 + outer loop + vertex 787.079 233.386 360.918 + vertex 778.517 233.309 361.603 + vertex 778.635 228.338 360.926 + endloop + endfacet + facet normal 0.0801775 -0.132536 0.98793 + outer loop + vertex 786.956 238.356 361.595 + vertex 778.517 233.309 361.603 + vertex 787.079 233.386 360.918 + endloop + endfacet + facet normal 0.0827127 -0.132446 0.987733 + outer loop + vertex 795.408 238.58 360.917 + vertex 786.956 238.356 361.595 + vertex 787.079 233.386 360.918 + endloop + endfacet + facet normal 0.0827123 -0.13242 0.987737 + outer loop + vertex 795.283 243.552 361.594 + vertex 786.956 238.356 361.595 + vertex 795.408 238.58 360.917 + endloop + endfacet + facet normal 0.0859943 -0.132302 0.987472 + outer loop + vertex 803.565 243.915 360.922 + vertex 795.283 243.552 361.594 + vertex 795.408 238.58 360.917 + endloop + endfacet + facet normal 0.0859853 -0.132027 0.98751 + outer loop + vertex 803.434 248.89 361.598 + vertex 795.283 243.552 361.594 + vertex 803.565 243.915 360.922 + endloop + endfacet + facet normal 0.0891689 -0.131908 0.987243 + outer loop + vertex 811.542 249.42 360.937 + vertex 803.434 248.89 361.598 + vertex 803.565 243.915 360.922 + endloop + endfacet + facet normal 0.0891095 -0.13081 0.987395 + outer loop + vertex 811.404 254.403 361.609 + vertex 803.434 248.89 361.598 + vertex 811.542 249.42 360.937 + endloop + endfacet + facet normal 0.0941004 -0.130613 0.986958 + outer loop + vertex 819.423 255.196 360.95 + vertex 811.404 254.403 361.609 + vertex 811.542 249.42 360.937 + endloop + endfacet + facet normal 0.0940633 -0.130188 0.987017 + outer loop + vertex 819.271 260.179 361.621 + vertex 811.404 254.403 361.609 + vertex 819.423 255.196 360.95 + endloop + endfacet + facet normal 0.101467 -0.129869 0.986326 + outer loop + vertex 827.282 261.295 360.944 + vertex 819.271 260.179 361.621 + vertex 819.423 255.196 360.95 + endloop + endfacet + facet normal 0.101474 -0.129925 0.986318 + outer loop + vertex 827.092 266.255 361.617 + vertex 819.271 260.179 361.621 + vertex 827.282 261.295 360.944 + endloop + endfacet + facet normal 0.109848 -0.129491 0.985477 + outer loop + vertex 834.967 267.565 360.911 + vertex 827.092 266.255 361.617 + vertex 827.282 261.295 360.944 + endloop + endfacet + facet normal 0.110007 -0.130528 0.985323 + outer loop + vertex 834.7 272.488 361.593 + vertex 827.092 266.255 361.617 + vertex 834.967 267.565 360.911 + endloop + endfacet + facet normal 0.117068 -0.130041 0.984573 + outer loop + vertex 842.001 273.661 360.88 + vertex 834.7 272.488 361.593 + vertex 834.967 267.565 360.911 + endloop + endfacet + facet normal 0.116974 -0.129395 0.984669 + outer loop + vertex 841.618 278.59 361.573 + vertex 834.7 272.488 361.593 + vertex 842.001 273.661 360.88 + endloop + endfacet + facet normal 0.119576 -0.129154 0.984389 + outer loop + vertex 847.862 279.373 360.918 + vertex 841.618 278.59 361.573 + vertex 842.001 273.661 360.88 + endloop + endfacet + facet normal 0.119202 -0.125766 0.984873 + outer loop + vertex 847.419 284.411 361.615 + vertex 841.618 278.59 361.573 + vertex 847.862 279.373 360.918 + endloop + endfacet + facet normal 0.114952 -0.126202 0.985322 + outer loop + vertex 852.507 285.068 361.105 + vertex 847.419 284.411 361.615 + vertex 847.862 279.373 360.918 + endloop + endfacet + facet normal 0.113537 -0.113962 0.986976 + outer loop + vertex 851.996 290.044 361.739 + vertex 847.419 284.411 361.615 + vertex 852.507 285.068 361.105 + endloop + endfacet + facet normal 0.0967428 -0.115884 0.98854 + outer loop + vertex 851.996 290.044 361.739 + vertex 852.507 285.068 361.105 + vertex 855.448 290.8 361.489 + endloop + endfacet + facet normal 0.0908183 -0.0876798 0.992 + outer loop + vertex 855.448 290.8 361.489 + vertex 856.089 295.708 361.864 + vertex 851.996 290.044 361.739 + endloop + endfacet + facet normal 0.0811666 -0.0864899 0.992941 + outer loop + vertex 856.089 295.708 361.864 + vertex 855.448 290.8 361.489 + vertex 858.131 294.906 361.628 + endloop + endfacet + facet normal 0.0862997 -0.0735892 0.993548 + outer loop + vertex 856.089 295.708 361.864 + vertex 858.131 294.906 361.628 + vertex 860.254 299.423 361.778 + endloop + endfacet + facet normal 0.0713674 -0.0568004 0.995832 + outer loop + vertex 858.645 303.155 362.106 + vertex 856.089 295.708 361.864 + vertex 860.254 299.423 361.778 + endloop + endfacet + facet normal 0.0717082 -0.056652 0.995815 + outer loop + vertex 860.254 299.423 361.778 + vertex 864.24 305.913 361.86 + vertex 858.645 303.155 362.106 + endloop + endfacet + facet normal 0.0659978 -0.0449771 0.996806 + outer loop + vertex 863.558 311.444 362.155 + vertex 858.645 303.155 362.106 + vertex 864.24 305.913 361.86 + endloop + endfacet + facet normal 0.0615783 -0.0455352 0.997063 + outer loop + vertex 864.24 305.913 361.86 + vertex 869.177 313.819 361.916 + vertex 863.558 311.444 362.155 + endloop + endfacet + facet normal 0.0598447 -0.0414041 0.997349 + outer loop + vertex 867.017 317.769 362.21 + vertex 863.558 311.444 362.155 + vertex 869.177 313.819 361.916 + endloop + endfacet + facet normal 0.0605251 -0.0410301 0.997323 + outer loop + vertex 870.932 322.083 362.15 + vertex 867.017 317.769 362.21 + vertex 869.177 313.819 361.916 + endloop + endfacet + facet normal 0.0630118 -0.0415532 0.997147 + outer loop + vertex 869.177 313.819 361.916 + vertex 874.415 320.572 361.867 + vertex 870.932 322.083 362.15 + endloop + endfacet + facet normal 0.0641375 -0.038966 0.99718 + outer loop + vertex 875.06 328.142 362.121 + vertex 870.932 322.083 362.15 + vertex 874.415 320.572 361.867 + endloop + endfacet + facet normal 0.0680251 -0.0392881 0.99691 + outer loop + vertex 874.415 320.572 361.867 + vertex 878.553 327.19 361.845 + vertex 875.06 328.142 362.121 + endloop + endfacet + facet normal 0.0687868 -0.0365091 0.996963 + outer loop + vertex 878.935 334.76 362.096 + vertex 875.06 328.142 362.121 + vertex 878.553 327.19 361.845 + endloop + endfacet + facet normal 0.0722633 -0.0366762 0.996711 + outer loop + vertex 878.553 327.19 361.845 + vertex 882.284 333.833 361.819 + vertex 878.935 334.76 362.096 + endloop + endfacet + facet normal 0.0729795 -0.0341007 0.99675 + outer loop + vertex 882.974 342.167 362.054 + vertex 878.935 334.76 362.096 + vertex 882.284 333.833 361.819 + endloop + endfacet + facet normal 0.0768237 -0.0344105 0.996451 + outer loop + vertex 882.284 333.833 361.819 + vertex 885.271 339.146 361.772 + vertex 882.974 342.167 362.054 + endloop + endfacet + facet normal 0.079259 -0.0325466 0.996323 + outer loop + vertex 885.271 339.146 361.772 + vertex 887.127 345.602 361.835 + vertex 882.974 342.167 362.054 + endloop + endfacet + facet normal 0.0779911 -0.0310041 0.996472 + outer loop + vertex 885.586 350.98 362.123 + vertex 882.974 342.167 362.054 + vertex 887.127 345.602 361.835 + endloop + endfacet + facet normal 0.0874725 -0.0282496 0.995766 + outer loop + vertex 887.127 345.602 361.835 + vertex 889.416 354.355 361.883 + vertex 885.586 350.98 362.123 + endloop + endfacet + facet normal 0.0866852 -0.0273493 0.99586 + outer loop + vertex 887.136 357.863 362.177 + vertex 885.586 350.98 362.123 + vertex 889.416 354.355 361.883 + endloop + endfacet + facet normal 0.0944139 -0.0222785 0.995284 + outer loop + vertex 889.609 363.779 362.075 + vertex 887.136 357.863 362.177 + vertex 889.416 354.355 361.883 + endloop + endfacet + facet normal 0.0981457 -0.0223476 0.994921 + outer loop + vertex 889.416 354.355 361.883 + vertex 891.849 360.854 361.789 + vertex 889.609 363.779 362.075 + endloop + endfacet + facet normal 0.105434 -0.016704 0.994286 + outer loop + vertex 891.849 360.854 361.789 + vertex 892.551 367.859 361.832 + vertex 889.609 363.779 362.075 + endloop + endfacet + facet normal 0.105342 -0.0166375 0.994297 + outer loop + vertex 890.613 372.716 362.119 + vertex 889.609 363.779 362.075 + vertex 892.551 367.859 361.832 + endloop + endfacet + facet normal 0.120509 -0.010487 0.992657 + outer loop + vertex 892.551 367.859 361.832 + vertex 892.936 376.984 361.882 + vertex 890.613 372.716 362.119 + endloop + endfacet + facet normal 0.121177 -0.010855 0.992572 + outer loop + vertex 890.77 379.741 362.176 + vertex 890.613 372.716 362.119 + vertex 892.936 376.984 361.882 + endloop + endfacet + facet normal 0.130853 -0.00312633 0.991397 + outer loop + vertex 891.521 386.136 362.097 + vertex 890.77 379.741 362.176 + vertex 892.936 376.984 361.882 + endloop + endfacet + facet normal 0.141456 -0.00145257 0.989943 + outer loop + vertex 892.936 376.984 361.882 + vertex 893.492 384.194 361.813 + vertex 891.521 386.136 362.097 + endloop + endfacet + facet normal 0.149898 0.00730355 0.988674 + outer loop + vertex 893.492 384.194 361.813 + vertex 892.569 392.154 361.894 + vertex 891.521 386.136 362.097 + endloop + endfacet + facet normal 0.157668 0.00590934 0.987475 + outer loop + vertex 890.681 393.764 362.186 + vertex 891.521 386.136 362.097 + vertex 892.569 392.154 361.894 + endloop + endfacet + facet normal 0.164908 0.0146348 0.9862 + outer loop + vertex 890.456 399.499 362.138 + vertex 890.681 393.764 362.186 + vertex 892.569 392.154 361.894 + endloop + endfacet + facet normal 0.186043 0.0208451 0.98232 + outer loop + vertex 892.569 392.154 361.894 + vertex 891.79 400.615 361.862 + vertex 890.456 399.499 362.138 + endloop + endfacet + facet normal 0.181903 0.0259587 0.982974 + outer loop + vertex 889.602 406.49 362.112 + vertex 890.456 399.499 362.138 + vertex 891.79 400.615 361.862 + endloop + endfacet + facet normal 0.203479 0.0341841 0.978482 + outer loop + vertex 891.79 400.615 361.862 + vertex 890.604 408.226 361.843 + vertex 889.602 406.49 362.112 + endloop + endfacet + facet normal 0.197964 0.0375223 0.979491 + outer loop + vertex 888.36 413.671 362.087 + vertex 889.602 406.49 362.112 + vertex 890.604 408.226 361.843 + endloop + endfacet + facet normal 0.214717 0.0445979 0.975658 + outer loop + vertex 890.604 408.226 361.843 + vertex 889.204 415.523 361.817 + vertex 888.36 413.671 362.087 + endloop + endfacet + facet normal 0.210182 0.0467919 0.976542 + outer loop + vertex 886.77 421.581 362.051 + vertex 888.36 413.671 362.087 + vertex 889.204 415.523 361.817 + endloop + endfacet + facet normal 0.223625 0.0523184 0.97327 + outer loop + vertex 889.204 415.523 361.817 + vertex 887.957 421.608 361.777 + vertex 886.77 421.581 362.051 + endloop + endfacet + facet normal 0.223549 0.0545895 0.973163 + outer loop + vertex 887.957 421.608 361.777 + vertex 885.951 428.419 361.855 + vertex 886.77 421.581 362.051 + endloop + endfacet + facet normal 0.227082 0.0549888 0.972322 + outer loop + vertex 884.648 428.554 362.152 + vertex 886.77 421.581 362.051 + vertex 885.951 428.419 361.855 + endloop + endfacet + facet normal 0.227135 0.0555974 0.972275 + outer loop + vertex 883.187 435.679 362.086 + vertex 884.648 428.554 362.152 + vertex 885.951 428.419 361.855 + endloop + endfacet + facet normal 0.246379 0.0630894 0.967118 + outer loop + vertex 885.951 428.419 361.855 + vertex 884.319 435.698 361.796 + vertex 883.187 435.679 362.086 + endloop + endfacet + facet normal 0.246388 0.0628159 0.967134 + outer loop + vertex 884.319 435.698 361.796 + vertex 882.418 442.483 361.84 + vertex 883.187 435.679 362.086 + endloop + endfacet + facet normal 0.262702 0.0645005 0.962719 + outer loop + vertex 880.805 444.447 362.148 + vertex 883.187 435.679 362.086 + vertex 882.418 442.483 361.84 + endloop + endfacet + facet normal 0.266018 0.0673952 0.961609 + outer loop + vertex 882.418 442.483 361.84 + vertex 880.372 450.863 361.819 + vertex 880.805 444.447 362.148 + endloop + endfacet + facet normal 0.297672 0.0690498 0.952168 + outer loop + vertex 878.911 452.535 362.154 + vertex 880.805 444.447 362.148 + vertex 880.372 450.863 361.819 + endloop + endfacet + facet normal 0.29796 0.0693232 0.952058 + outer loop + vertex 878.911 452.535 362.154 + vertex 880.372 450.863 361.819 + vertex 879.139 455.777 361.846 + endloop + endfacet + facet normal 0.317579 0.067353 0.945837 + outer loop + vertex 878.394 457.545 361.971 + vertex 878.911 452.535 362.154 + vertex 879.139 455.777 361.846 + endloop + endfacet + facet normal 0.400057 0.104627 0.910498 + outer loop + vertex 879.139 455.777 361.846 + vertex 878.382 460.566 361.629 + vertex 878.394 457.545 361.971 + endloop + endfacet + facet normal 0.411099 0.104118 0.905625 + outer loop + vertex 878.394 457.545 361.971 + vertex 878.382 460.566 361.629 + vertex 877.751 460.604 361.911 + endloop + endfacet + facet normal 0.0848745 -0.0498268 0.995145 + outer loop + vertex 874.415 320.572 361.867 + vertex 877.535 321.347 361.639 + vertex 878.553 327.19 361.845 + endloop + endfacet + facet normal 0.0931457 -0.0512388 0.994333 + outer loop + vertex 877.535 321.347 361.639 + vertex 881.334 328.168 361.635 + vertex 878.553 327.19 361.845 + endloop + endfacet + facet normal 0.0919362 -0.0477349 0.99462 + outer loop + vertex 878.553 327.19 361.845 + vertex 881.334 328.168 361.635 + vertex 882.284 333.833 361.819 + endloop + endfacet + facet normal 0.102218 -0.0494232 0.993533 + outer loop + vertex 881.334 328.168 361.635 + vertex 884.822 335.185 361.625 + vertex 882.284 333.833 361.819 + endloop + endfacet + facet normal 0.10169 -0.0484173 0.993637 + outer loop + vertex 882.284 333.833 361.819 + vertex 884.822 335.185 361.625 + vertex 885.271 339.146 361.772 + endloop + endfacet + facet normal 0.11808 -0.0502045 0.991734 + outer loop + vertex 884.822 335.185 361.625 + vertex 887.522 341.792 361.638 + vertex 885.271 339.146 361.772 + endloop + endfacet + facet normal 0.106653 -0.0403933 0.993476 + outer loop + vertex 885.271 339.146 361.772 + vertex 887.522 341.792 361.638 + vertex 887.127 345.602 361.835 + endloop + endfacet + facet normal 0.113711 -0.0396221 0.992724 + outer loop + vertex 887.522 341.792 361.638 + vertex 889.684 348.895 361.674 + vertex 887.127 345.602 361.835 + endloop + endfacet + facet normal 0.105049 -0.0328362 0.993925 + outer loop + vertex 887.127 345.602 361.835 + vertex 889.684 348.895 361.674 + vertex 889.416 354.355 361.883 + endloop + endfacet + facet normal 0.121499 -0.0319572 0.992077 + outer loop + vertex 889.684 348.895 361.674 + vertex 891.913 356.788 361.655 + vertex 889.416 354.355 361.883 + endloop + endfacet + facet normal 0.120256 -0.0306637 0.992269 + outer loop + vertex 889.416 354.355 361.883 + vertex 891.913 356.788 361.655 + vertex 891.849 360.854 361.789 + endloop + endfacet + facet normal 0.156944 -0.0299266 0.987154 + outer loop + vertex 891.913 356.788 361.655 + vertex 893.358 364.248 361.652 + vertex 891.849 360.854 361.789 + endloop + endfacet + facet normal 0.133895 -0.0195335 0.990803 + outer loop + vertex 891.849 360.854 361.789 + vertex 893.358 364.248 361.652 + vertex 892.551 367.859 361.832 + endloop + endfacet + facet normal 0.152123 -0.0153322 0.988243 + outer loop + vertex 893.358 364.248 361.652 + vertex 894.084 371.882 361.658 + vertex 892.551 367.859 361.832 + endloop + endfacet + facet normal 0.141911 -0.0113742 0.989814 + outer loop + vertex 892.551 367.859 361.832 + vertex 894.084 371.882 361.658 + vertex 892.936 376.984 361.882 + endloop + endfacet + facet normal 0.109346 -0.0602641 0.992175 + outer loop + vertex 881.334 328.168 361.635 + vertex 877.535 321.347 361.639 + vertex 879.705 324.051 361.564 + endloop + endfacet + facet normal 0.110865 -0.0608615 0.99197 + outer loop + vertex 879.705 324.051 361.564 + vertex 881.206 326.787 361.565 + vertex 881.334 328.168 361.635 + endloop + endfacet + facet normal 0.119389 -0.0616017 0.990935 + outer loop + vertex 881.206 326.787 361.565 + vertex 881.915 328.181 361.566 + vertex 881.334 328.168 361.635 + endloop + endfacet + facet normal 0.119328 -0.0576333 0.991181 + outer loop + vertex 881.915 328.181 361.566 + vertex 883.256 330.96 361.566 + vertex 881.334 328.168 361.635 + endloop + endfacet + facet normal 0.120854 -0.0586896 0.990934 + outer loop + vertex 884.822 335.185 361.625 + vertex 881.334 328.168 361.635 + vertex 883.256 330.96 361.566 + endloop + endfacet + facet normal 0.130065 -0.062085 0.98956 + outer loop + vertex 883.256 330.96 361.566 + vertex 884.734 334.009 361.563 + vertex 884.822 335.185 361.625 + endloop + endfacet + facet normal 0.145062 -0.0630967 0.987409 + outer loop + vertex 884.734 334.009 361.563 + vertex 885.818 336.387 361.556 + vertex 884.822 335.185 361.625 + endloop + endfacet + facet normal 0.148412 -0.0659126 0.986727 + outer loop + vertex 885.818 336.387 361.556 + vertex 886.872 338.958 361.569 + vertex 884.822 335.185 361.625 + endloop + endfacet + facet normal 0.124253 -0.0527258 0.990849 + outer loop + vertex 887.522 341.792 361.638 + vertex 884.822 335.185 361.625 + vertex 886.872 338.958 361.569 + endloop + endfacet + facet normal 0.275482 -0.12264 0.953451 + outer loop + vertex 885.818 336.387 361.556 + vertex 884.734 334.009 361.563 + vertex 884.655 333.283 361.493 + endloop + endfacet + facet normal 0.25072 -0.120617 0.960516 + outer loop + vertex 884.734 334.009 361.563 + vertex 883.256 330.96 361.566 + vertex 884.655 333.283 361.493 + endloop + endfacet + facet normal 0.228918 -0.117298 0.966353 + outer loop + vertex 881.915 328.181 361.566 + vertex 881.206 326.787 361.565 + vertex 881.498 326.828 361.5 + endloop + endfacet + facet normal 0.229834 -0.126099 0.965026 + outer loop + vertex 881.206 326.787 361.565 + vertex 879.705 324.051 361.564 + vertex 881.498 326.828 361.5 + endloop + endfacet + facet normal 0.109008 -0.0599914 0.992229 + outer loop + vertex 878.23 321.303 361.56 + vertex 879.705 324.051 361.564 + vertex 877.535 321.347 361.639 + endloop + endfacet + facet normal 0.108809 -0.0628653 0.992073 + outer loop + vertex 877.457 319.956 361.56 + vertex 878.23 321.303 361.56 + vertex 877.535 321.347 361.639 + endloop + endfacet + facet normal 0.102856 -0.0625692 0.992726 + outer loop + vertex 875.824 317.353 361.565 + vertex 877.457 319.956 361.56 + vertex 877.535 321.347 361.639 + endloop + endfacet + facet normal 0.0961713 -0.0597208 0.993572 + outer loop + vertex 877.535 321.347 361.639 + vertex 873.313 314.755 361.652 + vertex 875.824 317.353 361.565 + endloop + endfacet + facet normal 0.0933052 -0.0569363 0.994008 + outer loop + vertex 874.219 314.741 361.566 + vertex 875.824 317.353 361.565 + vertex 873.313 314.755 361.652 + endloop + endfacet + facet normal 0.0932484 -0.0596842 0.993852 + outer loop + vertex 873.374 313.468 361.569 + vertex 874.219 314.741 361.566 + vertex 873.313 314.755 361.652 + endloop + endfacet + facet normal 0.0855385 -0.0600978 0.994521 + outer loop + vertex 871.476 310.904 361.577 + vertex 873.374 313.468 361.569 + vertex 873.313 314.755 361.652 + endloop + endfacet + facet normal 0.0838652 -0.0593037 0.994711 + outer loop + vertex 873.313 314.755 361.652 + vertex 868.588 308.361 361.669 + vertex 871.476 310.904 361.577 + endloop + endfacet + facet normal 0.0860338 -0.0617787 0.994375 + outer loop + vertex 869.29 307.9 361.58 + vertex 871.476 310.904 361.577 + vertex 868.588 308.361 361.669 + endloop + endfacet + facet normal 0.0831846 -0.066105 0.994339 + outer loop + vertex 866.911 304.841 361.575 + vertex 869.29 307.9 361.58 + vertex 868.588 308.361 361.669 + endloop + endfacet + facet normal 0.0862603 -0.0675607 0.993979 + outer loop + vertex 868.588 308.361 361.669 + vertex 863.991 302.031 361.638 + vertex 866.911 304.841 361.575 + endloop + endfacet + facet normal 0.0947349 -0.0763981 0.992567 + outer loop + vertex 864.896 302.235 361.567 + vertex 866.911 304.841 361.575 + vertex 863.991 302.031 361.638 + endloop + endfacet + facet normal 0.0953896 -0.0794007 0.992268 + outer loop + vertex 863.852 300.962 361.565 + vertex 864.896 302.235 361.567 + vertex 863.991 302.031 361.638 + endloop + endfacet + facet normal 0.0941703 -0.0792502 0.992397 + outer loop + vertex 861.951 298.695 361.565 + vertex 863.852 300.962 361.565 + vertex 863.991 302.031 361.638 + endloop + endfacet + facet normal 0.105884 -0.0863771 0.99062 + outer loop + vertex 863.991 302.031 361.638 + vertex 860.435 297.458 361.619 + vertex 861.951 298.695 361.565 + endloop + endfacet + facet normal 0.110223 -0.0917355 0.989664 + outer loop + vertex 860.062 296.451 361.567 + vertex 861.951 298.695 361.565 + vertex 860.435 297.458 361.619 + endloop + endfacet + facet normal 0.110259 -0.0917487 0.989659 + outer loop + vertex 859.277 295.657 361.581 + vertex 860.062 296.451 361.567 + vertex 860.435 297.458 361.619 + endloop + endfacet + facet normal 0.0935118 -0.0810365 0.992315 + outer loop + vertex 858.131 294.906 361.628 + vertex 859.277 295.657 361.581 + vertex 860.435 297.458 361.619 + endloop + endfacet + facet normal 0.127473 -0.13349 0.982818 + outer loop + vertex 859.277 295.657 361.581 + vertex 858.131 294.906 361.628 + vertex 859.672 295.428 361.499 + endloop + endfacet + facet normal 0.115948 -0.0980213 0.988407 + outer loop + vertex 857.372 292.789 361.507 + vertex 859.672 295.428 361.499 + vertex 858.131 294.906 361.628 + endloop + endfacet + facet normal 0.151755 -0.129272 0.979928 + outer loop + vertex 857.504 291.419 361.306 + vertex 859.672 295.428 361.499 + vertex 857.372 292.789 361.507 + endloop + endfacet + facet normal 0.127604 -0.132047 0.982996 + outer loop + vertex 857.504 291.419 361.306 + vertex 857.372 292.789 361.507 + vertex 855.448 290.8 361.489 + endloop + endfacet + facet normal 0.125553 -0.124874 0.984197 + outer loop + vertex 855.448 290.8 361.489 + vertex 855.55 287.78 361.093 + vertex 857.504 291.419 361.306 + endloop + endfacet + facet normal 0.165347 -0.136472 0.976748 + outer loop + vertex 861.111 294.63 361.144 + vertex 859.672 295.428 361.499 + vertex 857.504 291.419 361.306 + endloop + endfacet + facet normal 0.175776 -0.148366 0.973186 + outer loop + vertex 861.111 294.63 361.144 + vertex 857.504 291.419 361.306 + vertex 857.671 288.487 360.828 + endloop + endfacet + facet normal 0.193892 -0.158253 0.968175 + outer loop + vertex 857.671 288.487 360.828 + vertex 860.054 289.734 360.555 + vertex 861.111 294.63 361.144 + endloop + endfacet + facet normal 0.192465 -0.157984 0.968503 + outer loop + vertex 860.054 289.734 360.555 + vertex 863.632 294.577 360.634 + vertex 861.111 294.63 361.144 + endloop + endfacet + facet normal 0.19256 -0.156145 0.968783 + outer loop + vertex 866.347 301.513 361.212 + vertex 861.111 294.63 361.144 + vertex 863.632 294.577 360.634 + endloop + endfacet + facet normal 0.195954 -0.157399 0.967898 + outer loop + vertex 863.632 294.577 360.634 + vertex 868.42 300.924 360.697 + vertex 866.347 301.513 361.212 + endloop + endfacet + facet normal 0.197889 -0.151124 0.968505 + outer loop + vertex 871.279 308.218 361.251 + vertex 866.347 301.513 361.212 + vertex 868.42 300.924 360.697 + endloop + endfacet + facet normal 0.200769 -0.152195 0.967744 + outer loop + vertex 868.42 300.924 360.697 + vertex 873.258 307.598 360.743 + vertex 871.279 308.218 361.251 + endloop + endfacet + facet normal 0.204651 -0.140588 0.968686 + outer loop + vertex 875.75 314.805 361.262 + vertex 871.279 308.218 361.251 + vertex 873.258 307.598 360.743 + endloop + endfacet + facet normal 0.211764 -0.142913 0.966815 + outer loop + vertex 873.258 307.598 360.743 + vertex 877.664 314.15 360.746 + vertex 875.75 314.805 361.262 + endloop + endfacet + facet normal 0.21647 -0.129789 0.967624 + outer loop + vertex 879.694 321.312 361.253 + vertex 875.75 314.805 361.262 + vertex 877.664 314.15 360.746 + endloop + endfacet + facet normal 0.225885 -0.132282 0.965131 + outer loop + vertex 877.664 314.15 360.746 + vertex 881.538 320.676 360.734 + vertex 879.694 321.312 361.253 + endloop + endfacet + facet normal 0.230059 -0.120629 0.965672 + outer loop + vertex 883.179 327.942 361.251 + vertex 879.694 321.312 361.253 + vertex 881.538 320.676 360.734 + endloop + endfacet + facet normal 0.246417 -0.124003 0.961198 + outer loop + vertex 881.538 320.676 360.734 + vertex 885.002 327.563 360.734 + vertex 883.179 327.942 361.251 + endloop + endfacet + facet normal 0.248742 -0.11374 0.961868 + outer loop + vertex 886.261 334.843 361.27 + vertex 883.179 327.942 361.251 + vertex 885.002 327.563 360.734 + endloop + endfacet + facet normal 0.274319 -0.117615 0.954419 + outer loop + vertex 885.002 327.563 360.734 + vertex 888.354 335.875 360.795 + vertex 886.261 334.843 361.27 + endloop + endfacet + facet normal 0.269585 -0.106812 0.957035 + outer loop + vertex 888.589 341.354 361.341 + vertex 886.261 334.843 361.27 + vertex 888.354 335.875 360.795 + endloop + endfacet + facet normal 0.315941 -0.10737 0.942684 + outer loop + vertex 890.695 346.522 361.223 + vertex 888.589 341.354 361.341 + vertex 888.354 335.875 360.795 + endloop + endfacet + facet normal 0.263564 -0.0965408 0.959799 + outer loop + vertex 888.354 335.875 360.795 + vertex 890.862 340.889 360.611 + vertex 890.695 346.522 361.223 + endloop + endfacet + facet normal 0.323441 -0.0927966 0.941687 + outer loop + vertex 890.862 340.889 360.611 + vertex 892.722 349.411 360.812 + vertex 890.695 346.522 361.223 + endloop + endfacet + facet normal 0.313506 -0.0852463 0.945752 + outer loop + vertex 892.381 354.169 361.354 + vertex 890.695 346.522 361.223 + vertex 892.722 349.411 360.812 + endloop + endfacet + facet normal 0.377162 -0.0780683 0.922851 + outer loop + vertex 893.572 359.227 361.295 + vertex 892.381 354.169 361.354 + vertex 892.722 349.411 360.812 + endloop + endfacet + facet normal 0.340397 -0.0755955 0.937238 + outer loop + vertex 892.722 349.411 360.812 + vertex 894.484 356.6 360.752 + vertex 893.572 359.227 361.295 + endloop + endfacet + facet normal 0.386608 -0.0560893 0.920537 + outer loop + vertex 894.588 365.611 361.257 + vertex 893.572 359.227 361.295 + vertex 894.484 356.6 360.752 + endloop + endfacet + facet normal 0.367516 -0.0563056 0.928311 + outer loop + vertex 894.484 356.6 360.752 + vertex 895.573 362.881 360.701 + vertex 894.588 365.611 361.257 + endloop + endfacet + facet normal 0.417711 -0.0340418 0.907942 + outer loop + vertex 895.269 372.241 361.192 + vertex 894.588 365.611 361.257 + vertex 895.573 362.881 360.701 + endloop + endfacet + facet normal 0.374605 -0.036413 0.926469 + outer loop + vertex 895.573 362.881 360.701 + vertex 896.28 367.212 360.586 + vertex 895.269 372.241 361.192 + endloop + endfacet + facet normal 0.455676 -0.0157286 0.890007 + outer loop + vertex 896.28 367.212 360.586 + vertex 896.264 373.356 360.703 + vertex 895.269 372.241 361.192 + endloop + endfacet + facet normal 0.445779 -0.00465338 0.895131 + outer loop + vertex 895.208 379.943 361.263 + vertex 895.269 372.241 361.192 + vertex 896.264 373.356 360.703 + endloop + endfacet + facet normal 0.505851 0.00774111 0.862586 + outer loop + vertex 896.264 373.356 360.703 + vertex 896.106 379.847 360.737 + vertex 895.208 379.943 361.263 + endloop + endfacet + facet normal 0.507012 0.0239649 0.861606 + outer loop + vertex 894.905 386.129 361.269 + vertex 895.208 379.943 361.263 + vertex 896.106 379.847 360.737 + endloop + endfacet + facet normal 0.55325 0.0352915 0.832267 + outer loop + vertex 896.106 379.847 360.737 + vertex 895.727 385.961 360.73 + vertex 894.905 386.129 361.269 + endloop + endfacet + facet normal 0.555212 0.0518761 0.830089 + outer loop + vertex 894.372 391.925 361.263 + vertex 894.905 386.129 361.269 + vertex 895.727 385.961 360.73 + endloop + endfacet + facet normal 0.590862 0.0622797 0.804365 + outer loop + vertex 895.727 385.961 360.73 + vertex 895.038 392.242 360.75 + vertex 894.372 391.925 361.263 + endloop + endfacet + facet normal 0.586084 0.0760194 0.806676 + outer loop + vertex 893.563 397.823 361.295 + vertex 894.372 391.925 361.263 + vertex 895.038 392.242 360.75 + endloop + endfacet + facet normal 0.628515 0.0905712 0.772506 + outer loop + vertex 895.038 392.242 360.75 + vertex 893.876 399.546 360.839 + vertex 893.563 397.823 361.295 + endloop + endfacet + facet normal 0.612944 0.0964903 0.784212 + outer loop + vertex 892.661 402.915 361.374 + vertex 893.563 397.823 361.295 + vertex 893.876 399.546 360.839 + endloop + endfacet + facet normal 0.644789 0.11244 0.756045 + outer loop + vertex 892.053 406.975 361.288 + vertex 892.661 402.915 361.374 + vertex 893.876 399.546 360.839 + endloop + endfacet + facet normal 0.610117 0.102141 0.7857 + outer loop + vertex 893.876 399.546 360.839 + vertex 893.052 405.382 360.72 + vertex 892.053 406.975 361.288 + endloop + endfacet + facet normal 0.632867 0.124061 0.764256 + outer loop + vertex 891.045 412.739 361.187 + vertex 892.053 406.975 361.288 + vertex 893.052 405.382 360.72 + endloop + endfacet + facet normal 0.608721 0.116169 0.784833 + outer loop + vertex 893.052 405.382 360.72 + vertex 892.452 409.466 360.58 + vertex 891.045 412.739 361.187 + endloop + endfacet + facet normal 0.647126 0.139211 0.749565 + outer loop + vertex 892.452 409.466 360.58 + vertex 891.164 414.806 360.701 + vertex 891.045 412.739 361.187 + endloop + endfacet + facet normal 0.633771 0.142495 0.760283 + outer loop + vertex 889.419 419.611 361.255 + vertex 891.045 412.739 361.187 + vertex 891.164 414.806 360.701 + endloop + endfacet + facet normal 0.665011 0.157318 0.730077 + outer loop + vertex 891.164 414.806 360.701 + vertex 889.753 420.616 360.735 + vertex 889.419 419.611 361.255 + endloop + endfacet + facet normal 0.658176 0.162225 0.735179 + outer loop + vertex 887.944 425.494 361.277 + vertex 889.419 419.611 361.255 + vertex 889.753 420.616 360.735 + endloop + endfacet + facet normal 0.675376 0.17057 0.717477 + outer loop + vertex 889.753 420.616 360.735 + vertex 888.347 426.182 360.735 + vertex 887.944 425.494 361.277 + endloop + endfacet + facet normal 0.671412 0.174988 0.720128 + outer loop + vertex 886.55 430.857 361.273 + vertex 887.944 425.494 361.277 + vertex 888.347 426.182 360.735 + endloop + endfacet + facet normal 0.676944 0.177793 0.714238 + outer loop + vertex 888.347 426.182 360.735 + vertex 886.937 431.573 360.729 + vertex 886.55 430.857 361.273 + endloop + endfacet + facet normal 0.675365 0.179467 0.715314 + outer loop + vertex 885.195 435.974 361.269 + vertex 886.55 430.857 361.273 + vertex 886.937 431.573 360.729 + endloop + endfacet + facet normal 0.67984 0.181834 0.71046 + outer loop + vertex 886.937 431.573 360.729 + vertex 885.524 436.907 360.716 + vertex 885.195 435.974 361.269 + endloop + endfacet + facet normal 0.681964 0.180134 0.708856 + outer loop + vertex 883.822 441.176 361.268 + vertex 885.195 435.974 361.269 + vertex 885.524 436.907 360.716 + endloop + endfacet + facet normal 0.684773 0.181655 0.705753 + outer loop + vertex 885.524 436.907 360.716 + vertex 884.085 442.372 360.705 + vertex 883.822 441.176 361.268 + endloop + endfacet + facet normal 0.690623 0.178101 0.700942 + outer loop + vertex 882.428 446.589 361.266 + vertex 883.822 441.176 361.268 + vertex 884.085 442.372 360.705 + endloop + endfacet + facet normal 0.69131 0.178474 0.70017 + outer loop + vertex 884.085 442.372 360.705 + vertex 882.597 448.134 360.706 + vertex 882.428 446.589 361.266 + endloop + endfacet + facet normal 0.698865 0.175212 0.693461 + outer loop + vertex 881.088 451.991 361.252 + vertex 882.428 446.589 361.266 + vertex 882.597 448.134 360.706 + endloop + endfacet + facet normal 0.697588 0.174505 0.694924 + outer loop + vertex 882.597 448.134 360.706 + vertex 881.003 454.44 360.723 + vertex 881.088 451.991 361.252 + endloop + endfacet + facet normal 0.706551 0.172931 0.686207 + outer loop + vertex 880.045 456.266 361.249 + vertex 881.088 451.991 361.252 + vertex 881.003 454.44 360.723 + endloop + endfacet + facet normal 0.701361 0.168354 0.69264 + outer loop + vertex 879.427 459.733 361.032 + vertex 880.045 456.266 361.249 + vertex 881.003 454.44 360.723 + endloop + endfacet + facet normal 0.733108 0.179952 0.655873 + outer loop + vertex 881.003 454.44 360.723 + vertex 880.199 458.608 360.478 + vertex 879.427 459.733 361.032 + endloop + endfacet + facet normal 0.735313 0.183118 0.65252 + outer loop + vertex 880.199 458.608 360.478 + vertex 879.296 462.027 360.535 + vertex 879.427 459.733 361.032 + endloop + endfacet + facet normal 0.741995 0.181927 0.645248 + outer loop + vertex 879.296 462.027 360.535 + vertex 878.581 463.286 361.003 + vertex 879.427 459.733 361.032 + endloop + endfacet + facet normal 0.702225 0.172817 0.690663 + outer loop + vertex 878.772 461.528 361.248 + vertex 879.427 459.733 361.032 + vertex 878.581 463.286 361.003 + endloop + endfacet + facet normal 0.752286 0.193517 0.629775 + outer loop + vertex 879.296 462.027 360.535 + vertex 878.7 464.37 360.528 + vertex 878.581 463.286 361.003 + endloop + endfacet + facet normal 0.763173 0.187353 0.618438 + outer loop + vertex 878.329 464.393 360.978 + vertex 878.581 463.286 361.003 + vertex 878.7 464.37 360.528 + endloop + endfacet + facet normal 0.680087 0.165911 0.714112 + outer loop + vertex 879.427 459.733 361.032 + vertex 879.433 458.398 361.337 + vertex 880.045 456.266 361.249 + endloop + endfacet + facet normal 0.660121 0.159357 0.734061 + outer loop + vertex 880.045 456.266 361.249 + vertex 879.433 458.398 361.337 + vertex 880.168 454.801 361.456 + endloop + endfacet + facet normal 0.652058 0.159679 0.741163 + outer loop + vertex 880.045 456.266 361.249 + vertex 880.168 454.801 361.456 + vertex 881.088 451.991 361.252 + endloop + endfacet + facet normal 0.656274 0.161355 0.737068 + outer loop + vertex 881.088 451.991 361.252 + vertex 880.168 454.801 361.456 + vertex 881.32 449.915 361.5 + endloop + endfacet + facet normal 0.642004 0.161253 0.749552 + outer loop + vertex 881.088 451.991 361.252 + vertex 881.32 449.915 361.5 + vertex 882.428 446.589 361.266 + endloop + endfacet + facet normal 0.647446 0.16343 0.744382 + outer loop + vertex 882.428 446.589 361.266 + vertex 881.32 449.915 361.5 + vertex 882.638 444.573 361.527 + endloop + endfacet + facet normal 0.6339 0.163511 0.755933 + outer loop + vertex 882.428 446.589 361.266 + vertex 882.638 444.573 361.527 + vertex 883.822 441.176 361.268 + endloop + endfacet + facet normal 0.640649 0.166345 0.749599 + outer loop + vertex 883.822 441.176 361.268 + vertex 882.638 444.573 361.527 + vertex 884.035 439.219 361.521 + endloop + endfacet + facet normal 0.629666 0.166342 0.758848 + outer loop + vertex 883.822 441.176 361.268 + vertex 884.035 439.219 361.521 + vertex 885.195 435.974 361.269 + endloop + endfacet + facet normal 0.631809 0.167262 0.756863 + outer loop + vertex 885.195 435.974 361.269 + vertex 884.035 439.219 361.521 + vertex 885.324 434.356 361.519 + endloop + endfacet + facet normal 0.629564 0.167368 0.758707 + outer loop + vertex 885.195 435.974 361.269 + vertex 885.324 434.356 361.519 + vertex 886.55 430.857 361.273 + endloop + endfacet + facet normal 0.623033 0.164659 0.764668 + outer loop + vertex 886.55 430.857 361.273 + vertex 885.324 434.356 361.519 + vertex 886.65 429.364 361.514 + endloop + endfacet + facet normal 0.62987 0.164223 0.759141 + outer loop + vertex 886.55 430.857 361.273 + vertex 886.65 429.364 361.514 + vertex 887.944 425.494 361.277 + endloop + endfacet + facet normal 0.607191 0.15541 0.779209 + outer loop + vertex 887.944 425.494 361.277 + vertex 886.65 429.364 361.514 + vertex 888.144 423.517 361.516 + endloop + endfacet + facet normal 0.631758 0.155508 0.759407 + outer loop + vertex 887.944 425.494 361.277 + vertex 888.144 423.517 361.516 + vertex 889.419 419.611 361.255 + endloop + endfacet + facet normal 0.596052 0.141784 0.790328 + outer loop + vertex 889.419 419.611 361.255 + vertex 888.144 423.517 361.516 + vertex 889.638 417.367 361.492 + endloop + endfacet + facet normal 0.632918 0.142286 0.761032 + outer loop + vertex 889.419 419.611 361.255 + vertex 889.638 417.367 361.492 + vertex 891.045 412.739 361.187 + endloop + endfacet + facet normal 0.596803 0.129269 0.791907 + outer loop + vertex 891.045 412.739 361.187 + vertex 889.638 417.367 361.492 + vertex 890.88 411.578 361.501 + endloop + endfacet + facet normal 0.618885 0.121822 0.775977 + outer loop + vertex 891.045 412.739 361.187 + vertex 890.88 411.578 361.501 + vertex 892.053 406.975 361.288 + endloop + endfacet + facet normal 0.599649 0.116189 0.791783 + outer loop + vertex 892.053 406.975 361.288 + vertex 890.88 411.578 361.501 + vertex 891.864 406.347 361.524 + endloop + endfacet + facet normal 0.613633 0.108323 0.782126 + outer loop + vertex 892.053 406.975 361.288 + vertex 891.864 406.347 361.524 + vertex 892.661 402.915 361.374 + endloop + endfacet + facet normal 0.574515 0.0978943 0.812619 + outer loop + vertex 892.661 402.915 361.374 + vertex 891.864 406.347 361.524 + vertex 892.72 401.369 361.518 + endloop + endfacet + facet normal 0.613929 0.096677 0.783419 + outer loop + vertex 892.661 402.915 361.374 + vertex 892.72 401.369 361.518 + vertex 893.563 397.823 361.295 + endloop + endfacet + facet normal 0.56302 0.0821314 0.822352 + outer loop + vertex 893.563 397.823 361.295 + vertex 892.72 401.369 361.518 + vertex 893.535 395.942 361.502 + endloop + endfacet + facet normal 0.60297 0.0784031 0.793902 + outer loop + vertex 893.563 397.823 361.295 + vertex 893.535 395.942 361.502 + vertex 894.372 391.925 361.263 + endloop + endfacet + facet normal 0.5386 0.0622405 0.840259 + outer loop + vertex 894.372 391.925 361.263 + vertex 893.535 395.942 361.502 + vertex 894.173 390.411 361.503 + endloop + endfacet + facet normal 0.575003 0.0536812 0.816388 + outer loop + vertex 894.372 391.925 361.263 + vertex 894.173 390.411 361.503 + vertex 894.905 386.129 361.269 + endloop + endfacet + facet normal 0.500436 0.0382951 0.864926 + outer loop + vertex 894.905 386.129 361.269 + vertex 894.173 390.411 361.503 + vertex 894.577 384.924 361.512 + endloop + endfacet + facet normal 0.533666 0.0252907 0.845317 + outer loop + vertex 894.905 386.129 361.269 + vertex 894.577 384.924 361.512 + vertex 895.208 379.943 361.263 + endloop + endfacet + facet normal 0.451969 0.0125914 0.891945 + outer loop + vertex 895.208 379.943 361.263 + vertex 894.577 384.924 361.512 + vertex 894.772 378.758 361.5 + endloop + endfacet + facet normal 0.487194 -0.00412498 0.873284 + outer loop + vertex 895.208 379.943 361.263 + vertex 894.772 378.758 361.5 + vertex 895.269 372.241 361.192 + endloop + endfacet + facet normal 0.424669 -0.0104088 0.905289 + outer loop + vertex 895.269 372.241 361.192 + vertex 894.772 378.758 361.5 + vertex 894.632 372.342 361.492 + endloop + endfacet + facet normal 0.421314 -0.0344287 0.906261 + outer loop + vertex 895.269 372.241 361.192 + vertex 894.632 372.342 361.492 + vertex 894.588 365.611 361.257 + endloop + endfacet + facet normal 0.40814 -0.0345512 0.912265 + outer loop + vertex 894.588 365.611 361.257 + vertex 894.632 372.342 361.492 + vertex 894.043 365.866 361.511 + endloop + endfacet + facet normal 0.398569 -0.0580241 0.915301 + outer loop + vertex 894.588 365.611 361.257 + vertex 894.043 365.866 361.511 + vertex 893.572 359.227 361.295 + endloop + endfacet + facet normal 0.361795 -0.0559105 0.93058 + outer loop + vertex 893.572 359.227 361.295 + vertex 894.043 365.866 361.511 + vertex 892.994 359.121 361.513 + endloop + endfacet + facet normal 0.714288 0.170944 0.678654 + outer loop + vertex 889.638 417.367 361.492 + vertex 888.144 423.517 361.516 + vertex 889.019 419.627 361.575 + endloop + endfacet + facet normal 0.624739 0.15989 0.764288 + outer loop + vertex 888.144 423.517 361.516 + vertex 886.65 429.364 361.514 + vertex 886.966 427.763 361.59 + endloop + endfacet + facet normal 0.608619 0.155177 0.778141 + outer loop + vertex 886.966 427.763 361.59 + vertex 888.172 423.032 361.59 + vertex 888.144 423.517 361.516 + endloop + endfacet + facet normal 0.632086 0.153689 0.759504 + outer loop + vertex 888.172 423.032 361.59 + vertex 889.019 419.627 361.575 + vertex 888.144 423.517 361.516 + endloop + endfacet + facet normal 0.615248 0.162584 0.771386 + outer loop + vertex 886.65 429.364 361.514 + vertex 885.324 434.356 361.519 + vertex 885.78 432.296 361.59 + endloop + endfacet + facet normal 0.608135 0.161212 0.777292 + outer loop + vertex 884.586 436.751 361.6 + vertex 885.78 432.296 361.59 + vertex 885.324 434.356 361.519 + endloop + endfacet + facet normal 0.402819 0.105888 0.909134 + outer loop + vertex 885.78 432.296 361.59 + vertex 884.586 436.751 361.6 + vertex 885.609 432.341 361.661 + endloop + endfacet + facet normal 0.402743 0.105471 0.909216 + outer loop + vertex 886.966 427.763 361.59 + vertex 885.78 432.296 361.59 + vertex 885.609 432.341 361.661 + endloop + endfacet + facet normal 0.588786 0.154163 0.793451 + outer loop + vertex 885.78 432.296 361.59 + vertex 886.966 427.763 361.59 + vertex 886.65 429.364 361.514 + endloop + endfacet + facet normal 0.422495 0.11032 0.899626 + outer loop + vertex 883.538 440.278 361.66 + vertex 885.609 432.341 361.661 + vertex 884.586 436.751 361.6 + endloop + endfacet + facet normal 0.444424 0.117031 0.888139 + outer loop + vertex 884.586 436.751 361.6 + vertex 883.418 441.217 361.596 + vertex 883.538 440.278 361.66 + endloop + endfacet + facet normal 0.462605 0.118702 0.878582 + outer loop + vertex 883.418 441.217 361.596 + vertex 882.521 444.667 361.602 + vertex 883.538 440.278 361.66 + endloop + endfacet + facet normal 0.6237 0.16081 0.764943 + outer loop + vertex 882.521 444.667 361.602 + vertex 883.418 441.217 361.596 + vertex 882.638 444.573 361.527 + endloop + endfacet + facet normal 0.622643 0.158396 0.766307 + outer loop + vertex 881.661 448.138 361.583 + vertex 882.521 444.667 361.602 + vertex 882.638 444.573 361.527 + endloop + endfacet + facet normal 0.600226 0.155757 0.784518 + outer loop + vertex 884.035 439.219 361.521 + vertex 882.638 444.573 361.527 + vertex 883.418 441.217 361.596 + endloop + endfacet + facet normal 0.624035 0.163882 0.764018 + outer loop + vertex 883.418 441.217 361.596 + vertex 884.586 436.751 361.6 + vertex 884.035 439.219 361.521 + endloop + endfacet + facet normal 0.311283 0.0813102 0.946833 + outer loop + vertex 885.609 432.341 361.661 + vertex 883.538 440.278 361.66 + vertex 884.319 435.698 361.796 + endloop + endfacet + facet normal 0.289597 0.0726758 0.954386 + outer loop + vertex 885.951 428.419 361.855 + vertex 885.609 432.341 361.661 + vertex 884.319 435.698 361.796 + endloop + endfacet + facet normal 0.278302 0.0718588 0.957802 + outer loop + vertex 887.452 425.21 361.66 + vertex 885.609 432.341 361.661 + vertex 885.951 428.419 361.855 + endloop + endfacet + facet normal 0.273167 0.0693571 0.959463 + outer loop + vertex 887.957 421.608 361.777 + vertex 887.452 425.21 361.66 + vertex 885.951 428.419 361.855 + endloop + endfacet + facet normal 0.301307 0.073019 0.950727 + outer loop + vertex 889.091 418.633 361.646 + vertex 887.452 425.21 361.66 + vertex 887.957 421.608 361.777 + endloop + endfacet + facet normal 0.275787 0.062917 0.959157 + outer loop + vertex 889.204 415.523 361.817 + vertex 889.091 418.633 361.646 + vertex 887.957 421.608 361.777 + endloop + endfacet + facet normal 0.28679 0.0631376 0.95591 + outer loop + vertex 890.591 411.452 361.67 + vertex 889.091 418.633 361.646 + vertex 889.204 415.523 361.817 + endloop + endfacet + facet normal 0.257058 0.0526848 0.964959 + outer loop + vertex 890.604 408.226 361.843 + vertex 890.591 411.452 361.67 + vertex 889.204 415.523 361.817 + endloop + endfacet + facet normal 0.281506 0.0524221 0.958127 + outer loop + vertex 892.021 403.836 361.666 + vertex 890.591 411.452 361.67 + vertex 890.604 408.226 361.843 + endloop + endfacet + facet normal 0.247338 0.0409922 0.968062 + outer loop + vertex 891.79 400.615 361.862 + vertex 892.021 403.836 361.666 + vertex 890.604 408.226 361.843 + endloop + endfacet + facet normal 0.26586 0.0393687 0.963207 + outer loop + vertex 893.14 395.86 361.684 + vertex 892.021 403.836 361.666 + vertex 891.79 400.615 361.862 + endloop + endfacet + facet normal 0.210297 0.0230603 0.977366 + outer loop + vertex 892.569 392.154 361.894 + vertex 893.14 395.86 361.684 + vertex 891.79 400.615 361.862 + endloop + endfacet + facet normal 0.220039 0.0214399 0.975256 + outer loop + vertex 893.991 387.866 361.667 + vertex 893.14 395.86 361.684 + vertex 892.569 392.154 361.894 + endloop + endfacet + facet normal 0.31271 0.0815392 0.946342 + outer loop + vertex 884.319 435.698 361.796 + vertex 883.538 440.278 361.66 + vertex 882.418 442.483 361.84 + endloop + endfacet + facet normal 0.314056 0.0822646 0.945834 + outer loop + vertex 883.538 440.278 361.66 + vertex 881.445 448.643 361.627 + vertex 882.418 442.483 361.84 + endloop + endfacet + facet normal 0.346548 0.0869861 0.93399 + outer loop + vertex 882.418 442.483 361.84 + vertex 881.445 448.643 361.627 + vertex 880.372 450.863 361.819 + endloop + endfacet + facet normal 0.359968 0.0939721 0.92822 + outer loop + vertex 880.372 450.863 361.819 + vertex 881.445 448.643 361.627 + vertex 880.015 454.948 361.543 + endloop + endfacet + facet normal 0.604936 0.160135 0.780006 + outer loop + vertex 885.324 434.356 361.519 + vertex 884.035 439.219 361.521 + vertex 884.586 436.751 361.6 + endloop + endfacet + facet normal 0.619454 0.15298 0.769983 + outer loop + vertex 881.32 449.915 361.5 + vertex 880.168 454.801 361.456 + vertex 880.715 452.124 361.548 + endloop + endfacet + facet normal 0.633811 0.157181 0.757349 + outer loop + vertex 880.715 452.124 361.548 + vertex 881.661 448.138 361.583 + vertex 881.32 449.915 361.5 + endloop + endfacet + facet normal 0.64349 0.157171 0.749145 + outer loop + vertex 880.045 455.099 361.499 + vertex 880.715 452.124 361.548 + vertex 880.168 454.801 361.456 + endloop + endfacet + facet normal 0.637374 0.153777 0.755054 + outer loop + vertex 879.564 457.463 361.424 + vertex 880.045 455.099 361.499 + vertex 880.168 454.801 361.456 + endloop + endfacet + facet normal 0.685967 0.164708 0.708746 + outer loop + vertex 879.433 458.398 361.337 + vertex 879.427 459.733 361.032 + vertex 878.772 461.528 361.248 + endloop + endfacet + facet normal 0.364397 -0.0750008 0.928218 + outer loop + vertex 893.572 359.227 361.295 + vertex 892.994 359.121 361.513 + vertex 892.381 354.169 361.354 + endloop + endfacet + facet normal 0.30881 -0.0687778 0.948634 + outer loop + vertex 892.381 354.169 361.354 + vertex 892.994 359.121 361.513 + vertex 891.66 353.036 361.506 + endloop + endfacet + facet normal 0.341292 -0.0911958 0.935523 + outer loop + vertex 892.381 354.169 361.354 + vertex 891.66 353.036 361.506 + vertex 890.695 346.522 361.223 + endloop + endfacet + facet normal 0.296558 -0.08525 0.951202 + outer loop + vertex 890.695 346.522 361.223 + vertex 891.66 353.036 361.506 + vertex 889.864 346.69 361.498 + endloop + endfacet + facet normal 0.293816 -0.0981687 0.950807 + outer loop + vertex 890.695 346.522 361.223 + vertex 889.864 346.69 361.498 + vertex 888.589 341.354 361.341 + endloop + endfacet + facet normal 0.251585 -0.0884645 0.963784 + outer loop + vertex 888.589 341.354 361.341 + vertex 889.864 346.69 361.498 + vertex 887.485 340.054 361.51 + endloop + endfacet + facet normal 0.273623 -0.108242 0.955727 + outer loop + vertex 888.589 341.354 361.341 + vertex 887.485 340.054 361.51 + vertex 886.261 334.843 361.27 + endloop + endfacet + facet normal 0.230051 -0.0985805 0.968173 + outer loop + vertex 886.261 334.843 361.27 + vertex 887.485 340.054 361.51 + vertex 884.655 333.283 361.493 + endloop + endfacet + facet normal 0.240797 -0.110199 0.964299 + outer loop + vertex 886.261 334.843 361.27 + vertex 884.655 333.283 361.493 + vertex 883.179 327.942 361.251 + endloop + endfacet + facet normal 0.212374 -0.102685 0.971778 + outer loop + vertex 883.179 327.942 361.251 + vertex 884.655 333.283 361.493 + vertex 881.498 326.828 361.5 + endloop + endfacet + facet normal 0.220436 -0.11557 0.968531 + outer loop + vertex 883.179 327.942 361.251 + vertex 881.498 326.828 361.5 + vertex 879.694 321.312 361.253 + endloop + endfacet + facet normal 0.198538 -0.108658 0.974051 + outer loop + vertex 879.694 321.312 361.253 + vertex 881.498 326.828 361.5 + vertex 877.837 320.131 361.499 + endloop + endfacet + facet normal 0.208291 -0.124828 0.970068 + outer loop + vertex 879.694 321.312 361.253 + vertex 877.837 320.131 361.499 + vertex 875.75 314.805 361.262 + endloop + endfacet + facet normal 0.190893 -0.118208 0.974467 + outer loop + vertex 875.75 314.805 361.262 + vertex 877.837 320.131 361.499 + vertex 873.779 313.623 361.505 + endloop + endfacet + facet normal 0.202985 -0.139458 0.9692 + outer loop + vertex 875.75 314.805 361.262 + vertex 873.779 313.623 361.505 + vertex 871.279 308.218 361.251 + endloop + endfacet + facet normal 0.181312 -0.129697 0.974836 + outer loop + vertex 871.279 308.218 361.251 + vertex 873.779 313.623 361.505 + vertex 869.218 307.171 361.495 + endloop + endfacet + facet normal 0.188192 -0.144009 0.971517 + outer loop + vertex 871.279 308.218 361.251 + vertex 869.218 307.171 361.495 + vertex 866.347 301.513 361.212 + endloop + endfacet + facet normal 0.171565 -0.135783 0.975771 + outer loop + vertex 866.347 301.513 361.212 + vertex 869.218 307.171 361.495 + vertex 864.264 300.839 361.485 + endloop + endfacet + facet normal 0.17328 -0.141539 0.974649 + outer loop + vertex 866.347 301.513 361.212 + vertex 864.264 300.839 361.485 + vertex 861.111 294.63 361.144 + endloop + endfacet + facet normal 0.171132 -0.148757 0.973953 + outer loop + vertex 855.55 287.78 361.093 + vertex 857.671 288.487 360.828 + vertex 857.504 291.419 361.306 + endloop + endfacet + facet normal 0.164841 -0.137368 0.976708 + outer loop + vertex 861.111 294.63 361.144 + vertex 864.264 300.839 361.485 + vertex 859.672 295.428 361.499 + endloop + endfacet + facet normal 0.136656 -0.117933 0.983573 + outer loop + vertex 860.062 296.451 361.567 + vertex 859.277 295.657 361.581 + vertex 859.672 295.428 361.499 + endloop + endfacet + facet normal 0.144967 -0.120991 0.982011 + outer loop + vertex 861.951 298.695 361.565 + vertex 860.062 296.451 361.567 + vertex 859.672 295.428 361.499 + endloop + endfacet + facet normal 0.148138 -0.123187 0.981265 + outer loop + vertex 859.672 295.428 361.499 + vertex 864.264 300.839 361.485 + vertex 861.951 298.695 361.565 + endloop + endfacet + facet normal 0.0877023 -0.0722491 0.993523 + outer loop + vertex 860.435 297.458 361.619 + vertex 863.991 302.031 361.638 + vertex 860.254 299.423 361.778 + endloop + endfacet + facet normal 0.153385 -0.128903 0.979723 + outer loop + vertex 863.852 300.962 361.565 + vertex 861.951 298.695 361.565 + vertex 864.264 300.839 361.485 + endloop + endfacet + facet normal 0.153871 -0.127351 0.97985 + outer loop + vertex 864.896 302.235 361.567 + vertex 863.852 300.962 361.565 + vertex 864.264 300.839 361.485 + endloop + endfacet + facet normal 0.169658 -0.134295 0.97631 + outer loop + vertex 866.911 304.841 361.575 + vertex 864.896 302.235 361.567 + vertex 864.264 300.839 361.485 + endloop + endfacet + facet normal 0.169684 -0.134312 0.976303 + outer loop + vertex 864.264 300.839 361.485 + vertex 869.218 307.171 361.495 + vertex 866.911 304.841 361.575 + endloop + endfacet + facet normal 0.0786723 -0.0620549 0.994967 + outer loop + vertex 863.991 302.031 361.638 + vertex 868.588 308.361 361.669 + vertex 864.24 305.913 361.86 + endloop + endfacet + facet normal 0.165344 -0.12997 0.977635 + outer loop + vertex 869.29 307.9 361.58 + vertex 866.911 304.841 361.575 + vertex 869.218 307.171 361.495 + endloop + endfacet + facet normal 0.181406 -0.131209 0.974616 + outer loop + vertex 871.476 310.904 361.577 + vertex 869.29 307.9 361.58 + vertex 869.218 307.171 361.495 + endloop + endfacet + facet normal 0.0757202 -0.0532827 0.995704 + outer loop + vertex 868.588 308.361 361.669 + vertex 873.313 314.755 361.652 + vertex 869.177 313.819 361.916 + endloop + endfacet + facet normal 0.203963 -0.133232 0.96987 + outer loop + vertex 874.219 314.741 361.566 + vertex 873.374 313.468 361.569 + vertex 873.779 313.623 361.505 + endloop + endfacet + facet normal 0.23925 -0.146588 0.959829 + outer loop + vertex 875.824 317.353 361.565 + vertex 874.219 314.741 361.566 + vertex 873.779 313.623 361.505 + endloop + endfacet + facet normal 0.20964 -0.120695 0.970301 + outer loop + vertex 878.23 321.303 361.56 + vertex 877.457 319.956 361.56 + vertex 877.837 320.131 361.499 + endloop + endfacet + facet normal 0.214831 -0.13289 0.967568 + outer loop + vertex 877.457 319.956 361.56 + vertex 875.824 317.353 361.565 + vertex 877.837 320.131 361.499 + endloop + endfacet + facet normal 0.240799 -0.130704 0.961734 + outer loop + vertex 879.705 324.051 361.564 + vertex 878.23 321.303 361.56 + vertex 877.837 320.131 361.499 + endloop + endfacet + facet normal 0.0856399 -0.0529729 0.994917 + outer loop + vertex 873.313 314.755 361.652 + vertex 877.535 321.347 361.639 + vertex 874.415 320.572 361.867 + endloop + endfacet + facet normal 0.0752211 -0.051033 0.99586 + outer loop + vertex 869.177 313.819 361.916 + vertex 873.313 314.755 361.652 + vertex 874.415 320.572 361.867 + endloop + endfacet + facet normal 0.073652 -0.0530672 0.995871 + outer loop + vertex 864.24 305.913 361.86 + vertex 868.588 308.361 361.669 + vertex 869.177 313.819 361.916 + endloop + endfacet + facet normal 0.0807231 -0.0621763 0.994795 + outer loop + vertex 860.254 299.423 361.778 + vertex 863.991 302.031 361.638 + vertex 864.24 305.913 361.86 + endloop + endfacet + facet normal 0.106286 -0.0686577 0.991962 + outer loop + vertex 855.658 298.44 362.1 + vertex 856.089 295.708 361.864 + vertex 858.645 303.155 362.106 + endloop + endfacet + facet normal 0.0705174 -0.04601 0.996449 + outer loop + vertex 854.932 300.352 362.239 + vertex 855.658 298.44 362.1 + vertex 858.645 303.155 362.106 + endloop + endfacet + facet normal 0.0630748 -0.0361104 0.997355 + outer loop + vertex 855.226 304.855 362.384 + vertex 854.932 300.352 362.239 + vertex 858.645 303.155 362.106 + endloop + endfacet + facet normal 0.0621376 -0.0379939 0.997344 + outer loop + vertex 858.645 303.155 362.106 + vertex 857.9 311.566 362.473 + vertex 855.226 304.855 362.384 + endloop + endfacet + facet normal 0.0456788 -0.0314514 0.998461 + outer loop + vertex 855.011 308.077 362.495 + vertex 855.226 304.855 362.384 + vertex 857.9 311.566 362.473 + endloop + endfacet + facet normal 0.0333214 -0.0212134 0.99922 + outer loop + vertex 854.131 309.746 362.56 + vertex 855.011 308.077 362.495 + vertex 857.9 311.566 362.473 + endloop + endfacet + facet normal 0.0450653 -0.0455998 0.997943 + outer loop + vertex 853.942 313.644 362.747 + vertex 854.131 309.746 362.56 + vertex 857.9 311.566 362.473 + endloop + endfacet + facet normal 0.0369512 -0.060989 0.997454 + outer loop + vertex 857.9 311.566 362.473 + vertex 858.663 323.092 363.149 + vertex 853.942 313.644 362.747 + endloop + endfacet + facet normal 0.135079 -0.109475 0.984768 + outer loop + vertex 854.138 317.509 363.149 + vertex 853.942 313.644 362.747 + vertex 858.663 323.092 363.149 + endloop + endfacet + facet normal 0.122093 -0.108999 0.986515 + outer loop + vertex 853.942 313.644 362.747 + vertex 854.138 317.509 363.149 + vertex 848.347 311.023 363.149 + endloop + endfacet + facet normal 0.112131 -0.0872193 0.989858 + outer loop + vertex 853.942 313.644 362.747 + vertex 848.347 311.023 363.149 + vertex 851.06 309.085 362.671 + endloop + endfacet + facet normal 0.104388 -0.0980154 0.989695 + outer loop + vertex 846.833 304.91 362.704 + vertex 851.06 309.085 362.671 + vertex 848.347 311.023 363.149 + endloop + endfacet + facet normal 0.0979313 -0.0964752 0.990506 + outer loop + vertex 848.347 311.023 363.149 + vertex 841.865 304.443 363.149 + vertex 846.833 304.91 362.704 + endloop + endfacet + facet normal 0.098085 -0.0982972 0.990312 + outer loop + vertex 846.833 304.91 362.704 + vertex 841.865 304.443 363.149 + vertex 840.95 298.997 362.7 + endloop + endfacet + facet normal 0.036527 -0.0370482 0.998646 + outer loop + vertex 846.833 304.91 362.704 + vertex 840.95 298.997 362.7 + vertex 846.795 299.875 362.518 + endloop + endfacet + facet normal 0.0392434 -0.0370651 0.998542 + outer loop + vertex 851.785 305.476 362.53 + vertex 846.833 304.91 362.704 + vertex 846.795 299.875 362.518 + endloop + endfacet + facet normal 0.0307195 -0.0294717 0.999093 + outer loop + vertex 851.785 305.476 362.53 + vertex 846.795 299.875 362.518 + vertex 851.639 300.246 362.38 + endloop + endfacet + facet normal 0.0371053 -0.0296441 0.998872 + outer loop + vertex 851.785 305.476 362.53 + vertex 851.639 300.246 362.38 + vertex 855.226 304.855 362.384 + endloop + endfacet + facet normal 0.0309162 -0.0320743 0.999007 + outer loop + vertex 851.639 300.246 362.38 + vertex 846.795 299.875 362.518 + vertex 847.004 294.732 362.347 + endloop + endfacet + facet normal 0.0473826 -0.0459052 0.997821 + outer loop + vertex 851.639 300.246 362.38 + vertex 847.004 294.732 362.347 + vertex 852.322 295.509 362.13 + endloop + endfacet + facet normal 0.044192 -0.0463722 0.997946 + outer loop + vertex 851.639 300.246 362.38 + vertex 852.322 295.509 362.13 + vertex 854.932 300.352 362.239 + endloop + endfacet + facet normal 0.0482783 -0.0521262 0.997473 + outer loop + vertex 852.322 295.509 362.13 + vertex 847.004 294.732 362.347 + vertex 847.184 289.54 362.067 + endloop + endfacet + facet normal 0.0757219 -0.0757142 0.99425 + outer loop + vertex 852.322 295.509 362.13 + vertex 847.184 289.54 362.067 + vertex 851.996 290.044 361.739 + endloop + endfacet + facet normal 0.0740646 -0.0756249 0.994382 + outer loop + vertex 852.322 295.509 362.13 + vertex 851.996 290.044 361.739 + vertex 856.089 295.708 361.864 + endloop + endfacet + facet normal 0.0765462 -0.0840488 0.993517 + outer loop + vertex 851.996 290.044 361.739 + vertex 847.184 289.54 362.067 + vertex 847.419 284.411 361.615 + endloop + endfacet + facet normal 0.0802095 -0.0838569 0.993244 + outer loop + vertex 847.184 289.54 362.067 + vertex 841.314 283.592 362.039 + vertex 847.419 284.411 361.615 + endloop + endfacet + facet normal 0.0806632 -0.0874189 0.9929 + outer loop + vertex 847.419 284.411 361.615 + vertex 841.314 283.592 362.039 + vertex 841.618 278.59 361.573 + endloop + endfacet + facet normal 0.0797314 -0.0874821 0.99297 + outer loop + vertex 841.314 283.592 362.039 + vertex 834.459 277.449 362.048 + vertex 841.618 278.59 361.573 + endloop + endfacet + facet normal 0.0796689 -0.087073 0.993011 + outer loop + vertex 841.618 278.59 361.573 + vertex 834.459 277.449 362.048 + vertex 834.7 272.488 361.593 + endloop + endfacet + facet normal 0.0741437 -0.0873781 0.993412 + outer loop + vertex 834.459 277.449 362.048 + vertex 826.932 271.241 362.064 + vertex 834.7 272.488 361.593 + endloop + endfacet + facet normal 0.0740186 -0.0865687 0.993492 + outer loop + vertex 834.7 272.488 361.593 + vertex 826.932 271.241 362.064 + vertex 827.092 266.255 361.617 + endloop + endfacet + facet normal 0.0679933 -0.0867993 0.993903 + outer loop + vertex 826.932 271.241 362.064 + vertex 819.155 265.194 362.067 + vertex 827.092 266.255 361.617 + endloop + endfacet + facet normal 0.0679974 -0.0868314 0.9939 + outer loop + vertex 827.092 266.255 361.617 + vertex 819.155 265.194 362.067 + vertex 819.271 260.179 361.621 + endloop + endfacet + facet normal 0.0628391 -0.0869793 0.994226 + outer loop + vertex 819.155 265.194 362.067 + vertex 811.305 259.424 362.059 + vertex 819.271 260.179 361.621 + endloop + endfacet + facet normal 0.0629099 -0.0877691 0.994152 + outer loop + vertex 819.271 260.179 361.621 + vertex 811.305 259.424 362.059 + vertex 811.404 254.403 361.609 + endloop + endfacet + facet normal 0.0599395 -0.0878436 0.994329 + outer loop + vertex 811.305 259.424 362.059 + vertex 803.342 253.903 362.051 + vertex 811.404 254.403 361.609 + endloop + endfacet + facet normal 0.0599901 -0.088731 0.994247 + outer loop + vertex 811.404 254.403 361.609 + vertex 803.342 253.903 362.051 + vertex 803.434 248.89 361.598 + endloop + endfacet + facet normal 0.0578993 -0.0887802 0.994367 + outer loop + vertex 803.342 253.903 362.051 + vertex 795.194 248.559 362.048 + vertex 803.434 248.89 361.598 + endloop + endfacet + facet normal 0.0579127 -0.0891639 0.994332 + outer loop + vertex 803.434 248.89 361.598 + vertex 795.194 248.559 362.048 + vertex 795.283 243.552 361.594 + endloop + endfacet + facet normal 0.0559854 -0.0892077 0.994438 + outer loop + vertex 795.194 248.559 362.048 + vertex 786.87 243.36 362.051 + vertex 795.283 243.552 361.594 + endloop + endfacet + facet normal 0.0559924 -0.0895985 0.994403 + outer loop + vertex 795.283 243.552 361.594 + vertex 786.87 243.36 362.051 + vertex 786.956 238.356 361.595 + endloop + endfacet + facet normal 0.0538723 -0.0896452 0.994516 + outer loop + vertex 786.87 243.36 362.051 + vertex 778.436 238.318 362.053 + vertex 786.956 238.356 361.595 + endloop + endfacet + facet normal 0.0538728 -0.0885412 0.994615 + outer loop + vertex 786.956 238.356 361.595 + vertex 778.436 238.318 362.053 + vertex 778.517 233.309 361.603 + endloop + endfacet + facet normal 0.0514086 -0.0885922 0.99474 + outer loop + vertex 778.436 238.318 362.053 + vertex 769.958 233.446 362.057 + vertex 778.517 233.309 361.603 + endloop + endfacet + facet normal 0.0514016 -0.0889293 0.994711 + outer loop + vertex 778.517 233.309 361.603 + vertex 769.958 233.446 362.057 + vertex 770.026 228.432 361.605 + endloop + endfacet + facet normal 0.049353 -0.0889661 0.994811 + outer loop + vertex 769.958 233.446 362.057 + vertex 761.482 228.752 362.058 + vertex 770.026 228.432 361.605 + endloop + endfacet + facet normal 0.0493566 -0.0888815 0.994819 + outer loop + vertex 770.026 228.432 361.605 + vertex 761.482 228.752 362.058 + vertex 761.535 223.728 361.606 + endloop + endfacet + facet normal 0.0475045 -0.088909 0.994906 + outer loop + vertex 761.482 228.752 362.058 + vertex 753.018 224.232 362.058 + vertex 761.535 223.728 361.606 + endloop + endfacet + facet normal 0.0474796 -0.0892993 0.994873 + outer loop + vertex 761.535 223.728 361.606 + vertex 753.018 224.232 362.058 + vertex 753.068 219.208 361.605 + endloop + endfacet + facet normal 0.0456324 -0.0893254 0.994957 + outer loop + vertex 753.018 224.232 362.058 + vertex 744.489 219.874 362.058 + vertex 753.068 219.208 361.605 + endloop + endfacet + facet normal 0.0281645 -0.0551401 0.998081 + outer loop + vertex 753.018 224.232 362.058 + vertex 744.452 224.912 362.337 + vertex 744.489 219.874 362.058 + endloop + endfacet + facet normal 0.0269848 -0.0551505 0.998113 + outer loop + vertex 744.452 224.912 362.337 + vertex 735.633 220.62 362.339 + vertex 744.489 219.874 362.058 + endloop + endfacet + facet normal 0.0270002 -0.0549705 0.998123 + outer loop + vertex 744.489 219.874 362.058 + vertex 735.633 220.62 362.339 + vertex 735.71 215.618 362.061 + endloop + endfacet + facet normal 0.0162244 -0.0330397 0.999322 + outer loop + vertex 744.452 224.912 362.337 + vertex 735.593 225.658 362.506 + vertex 735.633 220.62 362.339 + endloop + endfacet + facet normal 0.0157107 -0.0330441 0.99933 + outer loop + vertex 735.593 225.658 362.506 + vertex 726.398 221.361 362.508 + vertex 735.633 220.62 362.339 + endloop + endfacet + facet normal 0.0157269 -0.0328438 0.999337 + outer loop + vertex 735.633 220.62 362.339 + vertex 726.398 221.361 362.508 + vertex 726.448 216.341 362.343 + endloop + endfacet + facet normal 0.0176558 -0.0372055 0.999152 + outer loop + vertex 735.593 225.658 362.506 + vertex 726.661 226.531 362.696 + vertex 726.398 221.361 362.508 + endloop + endfacet + facet normal 0.0170209 -0.0371736 0.999164 + outer loop + vertex 726.661 226.531 362.696 + vertex 717.449 222.332 362.697 + vertex 726.398 221.361 362.508 + endloop + endfacet + facet normal 0.0170431 -0.0369697 0.999171 + outer loop + vertex 726.398 221.361 362.508 + vertex 717.449 222.332 362.697 + vertex 717.109 217.101 362.509 + endloop + endfacet + facet normal 0.0413665 -0.0905737 0.99503 + outer loop + vertex 726.661 226.531 362.696 + vertex 718.858 227.945 363.149 + vertex 717.449 222.332 362.697 + endloop + endfacet + facet normal 0.0397076 -0.0901658 0.995135 + outer loop + vertex 718.858 227.945 363.149 + vertex 709.882 223.992 363.149 + vertex 717.449 222.332 362.697 + endloop + endfacet + facet normal 0.0401699 -0.0881042 0.995301 + outer loop + vertex 717.449 222.332 362.697 + vertex 709.882 223.992 363.149 + vertex 708.774 218.33 362.693 + endloop + endfacet + facet normal 0.0413661 -0.0905757 0.99503 + outer loop + vertex 727.81 232.034 363.149 + vertex 718.858 227.945 363.149 + vertex 726.661 226.531 362.696 + endloop + endfacet + facet normal 0.0427416 -0.0908562 0.994946 + outer loop + vertex 735.823 230.835 362.696 + vertex 727.81 232.034 363.149 + vertex 726.661 226.531 362.696 + endloop + endfacet + facet normal 0.0428225 -0.0903325 0.994991 + outer loop + vertex 736.812 236.301 363.149 + vertex 727.81 232.034 363.149 + vertex 735.823 230.835 362.696 + endloop + endfacet + facet normal 0.0443842 -0.0906073 0.994897 + outer loop + vertex 744.699 235.184 362.696 + vertex 736.812 236.301 363.149 + vertex 735.823 230.835 362.696 + endloop + endfacet + facet normal 0.01825 -0.0372686 0.999139 + outer loop + vertex 744.699 235.184 362.696 + vertex 735.823 230.835 362.696 + vertex 744.467 229.994 362.506 + endloop + endfacet + facet normal 0.0190922 -0.0373055 0.999122 + outer loop + vertex 753.064 234.394 362.507 + vertex 744.699 235.184 362.696 + vertex 744.467 229.994 362.506 + endloop + endfacet + facet normal 0.0169637 -0.0331472 0.999307 + outer loop + vertex 753.064 234.394 362.507 + vertex 744.467 229.994 362.506 + vertex 753.012 229.291 362.338 + endloop + endfacet + facet normal 0.0178072 -0.0331553 0.999292 + outer loop + vertex 761.474 233.809 362.337 + vertex 753.064 234.394 362.507 + vertex 753.012 229.291 362.338 + endloop + endfacet + facet normal 0.0295041 -0.0550627 0.998047 + outer loop + vertex 761.474 233.809 362.337 + vertex 753.012 229.291 362.338 + vertex 761.482 228.752 362.058 + endloop + endfacet + facet normal 0.0178171 -0.033015 0.999296 + outer loop + vertex 761.524 238.908 362.505 + vertex 753.064 234.394 362.507 + vertex 761.474 233.809 362.337 + endloop + endfacet + facet normal 0.0184483 -0.0330209 0.999284 + outer loop + vertex 769.93 238.493 362.336 + vertex 761.524 238.908 362.505 + vertex 761.474 233.809 362.337 + endloop + endfacet + facet normal 0.030581 -0.0549262 0.998022 + outer loop + vertex 769.93 238.493 362.336 + vertex 761.474 233.809 362.337 + vertex 769.958 233.446 362.057 + endloop + endfacet + facet normal 0.0184353 -0.0332804 0.999276 + outer loop + vertex 769.964 243.58 362.505 + vertex 761.524 238.908 362.505 + vertex 769.93 238.493 362.336 + endloop + endfacet + facet normal 0.0194049 -0.0332864 0.999257 + outer loop + vertex 778.391 243.356 362.334 + vertex 769.964 243.58 362.505 + vertex 769.93 238.493 362.336 + endloop + endfacet + facet normal 0.0320504 -0.055289 0.997956 + outer loop + vertex 778.391 243.356 362.334 + vertex 769.93 238.493 362.336 + vertex 778.436 238.318 362.053 + endloop + endfacet + facet normal 0.0194043 -0.0333096 0.999257 + outer loop + vertex 778.409 248.436 362.503 + vertex 769.964 243.58 362.505 + vertex 778.391 243.356 362.334 + endloop + endfacet + facet normal 0.0202742 -0.033312 0.999239 + outer loop + vertex 786.818 248.396 362.331 + vertex 778.409 248.436 362.503 + vertex 778.391 243.356 362.334 + endloop + endfacet + facet normal 0.0333293 -0.0551373 0.997922 + outer loop + vertex 786.818 248.396 362.331 + vertex 778.391 243.356 362.334 + vertex 786.87 243.36 362.051 + endloop + endfacet + facet normal 0.0202731 -0.0335142 0.999233 + outer loop + vertex 786.829 253.476 362.501 + vertex 778.409 248.436 362.503 + vertex 786.818 248.396 362.331 + endloop + endfacet + facet normal 0.0211891 -0.0335156 0.999214 + outer loop + vertex 795.139 253.6 362.329 + vertex 786.829 253.476 362.501 + vertex 786.818 248.396 362.331 + endloop + endfacet + facet normal 0.0346939 -0.0551124 0.997877 + outer loop + vertex 795.139 253.6 362.329 + vertex 786.818 248.396 362.331 + vertex 795.194 248.559 362.048 + endloop + endfacet + facet normal 0.0211896 -0.0335535 0.999212 + outer loop + vertex 795.149 258.681 362.499 + vertex 786.829 253.476 362.501 + vertex 795.139 253.6 362.329 + endloop + endfacet + facet normal 0.0217739 -0.0335542 0.9992 + outer loop + vertex 803.284 258.949 362.331 + vertex 795.149 258.681 362.499 + vertex 795.139 253.6 362.329 + endloop + endfacet + facet normal 0.0357997 -0.0549144 0.997849 + outer loop + vertex 803.284 258.949 362.331 + vertex 795.139 253.6 362.329 + vertex 803.342 253.903 362.051 + endloop + endfacet + facet normal 0.0217717 -0.0334865 0.999202 + outer loop + vertex 803.291 264.029 362.501 + vertex 795.149 258.681 362.499 + vertex 803.284 258.949 362.331 + endloop + endfacet + facet normal 0.0223336 -0.0334868 0.99919 + outer loop + vertex 811.243 264.467 362.338 + vertex 803.291 264.029 362.501 + vertex 803.284 258.949 362.331 + endloop + endfacet + facet normal 0.0370841 -0.0547552 0.997811 + outer loop + vertex 811.243 264.467 362.338 + vertex 803.284 258.949 362.331 + vertex 811.305 259.424 362.059 + endloop + endfacet + facet normal 0.0223 -0.0328701 0.999211 + outer loop + vertex 811.251 269.552 362.505 + vertex 803.291 264.029 362.501 + vertex 811.243 264.467 362.338 + endloop + endfacet + facet normal 0.0235588 -0.0328712 0.999182 + outer loop + vertex 819.078 270.228 362.343 + vertex 811.251 269.552 362.505 + vertex 811.243 264.467 362.338 + endloop + endfacet + facet normal 0.0390631 -0.0539594 0.997779 + outer loop + vertex 819.078 270.228 362.343 + vertex 811.243 264.467 362.338 + vertex 819.155 265.194 362.067 + endloop + endfacet + facet normal 0.0235504 -0.0327724 0.999185 + outer loop + vertex 819.087 275.311 362.509 + vertex 811.251 269.552 362.505 + vertex 819.078 270.228 362.343 + endloop + endfacet + facet normal 0.0259269 -0.0327747 0.999126 + outer loop + vertex 826.816 276.257 362.34 + vertex 819.087 275.311 362.509 + vertex 819.078 270.228 362.343 + endloop + endfacet + facet normal 0.0424152 -0.053937 0.997643 + outer loop + vertex 826.816 276.257 362.34 + vertex 819.078 270.228 362.343 + vertex 826.932 271.241 362.064 + endloop + endfacet + facet normal 0.0259229 -0.0327416 0.999128 + outer loop + vertex 826.788 281.341 362.507 + vertex 819.087 275.311 362.509 + vertex 826.816 276.257 362.34 + endloop + endfacet + facet normal 0.0285524 -0.0327246 0.999056 + outer loop + vertex 834.279 282.473 362.33 + vertex 826.788 281.341 362.507 + vertex 826.816 276.257 362.34 + endloop + endfacet + facet normal 0.0465696 -0.0543581 0.997435 + outer loop + vertex 834.279 282.473 362.33 + vertex 826.816 276.257 362.34 + vertex 834.459 277.449 362.048 + endloop + endfacet + facet normal 0.0286076 -0.0330915 0.999043 + outer loop + vertex 834.178 287.577 362.502 + vertex 826.788 281.341 362.507 + vertex 834.279 282.473 362.33 + endloop + endfacet + facet normal 0.0302497 -0.0330575 0.998996 + outer loop + vertex 841.116 288.694 362.329 + vertex 834.178 287.577 362.502 + vertex 834.279 282.473 362.33 + endloop + endfacet + facet normal 0.0500212 -0.0547863 0.997244 + outer loop + vertex 841.116 288.694 362.329 + vertex 834.279 282.473 362.33 + vertex 841.314 283.592 362.039 + endloop + endfacet + facet normal 0.0302386 -0.0329885 0.998998 + outer loop + vertex 840.939 293.846 362.504 + vertex 834.178 287.577 362.502 + vertex 841.116 288.694 362.329 + endloop + endfacet + facet normal 0.0307692 -0.0329697 0.998983 + outer loop + vertex 847.004 294.732 362.347 + vertex 840.939 293.846 362.504 + vertex 841.116 288.694 362.329 + endloop + endfacet + facet normal 0.034692 -0.0377908 0.998683 + outer loop + vertex 840.939 293.846 362.504 + vertex 834.236 292.743 362.695 + vertex 834.178 287.577 362.502 + endloop + endfacet + facet normal 0.0323364 -0.0377674 0.998763 + outer loop + vertex 834.236 292.743 362.695 + vertex 826.991 286.553 362.696 + vertex 834.178 287.577 362.502 + endloop + endfacet + facet normal 0.0819273 -0.0958086 0.992022 + outer loop + vertex 834.236 292.743 362.695 + vertex 827.643 291.806 363.149 + vertex 826.991 286.553 362.696 + endloop + endfacet + facet normal 0.0752861 -0.0950361 0.992623 + outer loop + vertex 827.643 291.806 363.149 + vertex 820.504 286.151 363.149 + vertex 826.991 286.553 362.696 + endloop + endfacet + facet normal 0.0752971 -0.0952366 0.992603 + outer loop + vertex 826.991 286.553 362.696 + vertex 820.504 286.151 363.149 + vertex 819.375 280.544 362.697 + endloop + endfacet + facet normal 0.0296345 -0.0373585 0.998862 + outer loop + vertex 826.991 286.553 362.696 + vertex 819.375 280.544 362.697 + vertex 826.788 281.341 362.507 + endloop + endfacet + facet normal 0.0697348 -0.0941579 0.993112 + outer loop + vertex 820.504 286.151 363.149 + vertex 812.508 280.229 363.149 + vertex 819.375 280.544 362.697 + endloop + endfacet + facet normal 0.0697618 -0.0948422 0.993045 + outer loop + vertex 819.375 280.544 362.697 + vertex 812.508 280.229 363.149 + vertex 811.548 274.775 362.696 + endloop + endfacet + facet normal 0.0274105 -0.0373809 0.998925 + outer loop + vertex 819.375 280.544 362.697 + vertex 811.548 274.775 362.696 + vertex 819.087 275.311 362.509 + endloop + endfacet + facet normal 0.0655235 -0.094126 0.993402 + outer loop + vertex 812.508 280.229 363.149 + vertex 804.719 274.807 363.149 + vertex 811.548 274.775 362.696 + endloop + endfacet + facet normal 0.0655154 -0.094869 0.993332 + outer loop + vertex 811.548 274.775 362.696 + vertex 804.719 274.807 363.149 + vertex 803.557 269.232 362.694 + endloop + endfacet + facet normal 0.0260734 -0.0380146 0.998937 + outer loop + vertex 811.548 274.775 362.696 + vertex 803.557 269.232 362.694 + vertex 811.251 269.552 362.505 + endloop + endfacet + facet normal 0.0619473 -0.0941495 0.993629 + outer loop + vertex 804.719 274.807 363.149 + vertex 796.196 269.199 363.149 + vertex 803.557 269.232 362.694 + endloop + endfacet + facet normal 0.0619468 -0.0945269 0.993593 + outer loop + vertex 803.557 269.232 362.694 + vertex 796.196 269.199 363.149 + vertex 795.42 263.885 362.692 + endloop + endfacet + facet normal 0.0249793 -0.0382705 0.998955 + outer loop + vertex 803.557 269.232 362.694 + vertex 795.42 263.885 362.692 + vertex 803.291 264.029 362.501 + endloop + endfacet + facet normal 0.0588868 -0.0940995 0.99382 + outer loop + vertex 796.196 269.199 363.149 + vertex 788.344 264.285 363.149 + vertex 795.42 263.885 362.692 + endloop + endfacet + facet normal 0.0588867 -0.0941016 0.99382 + outer loop + vertex 795.42 263.885 362.692 + vertex 788.344 264.285 363.149 + vertex 787.095 258.679 362.693 + endloop + endfacet + facet normal 0.0240079 -0.0383231 0.998977 + outer loop + vertex 795.42 263.885 362.692 + vertex 787.095 258.679 362.693 + vertex 795.149 258.681 362.499 + endloop + endfacet + facet normal 0.0558885 -0.0934528 0.994054 + outer loop + vertex 788.344 264.285 363.149 + vertex 779.345 258.903 363.149 + vertex 787.095 258.679 362.693 + endloop + endfacet + facet normal 0.0558999 -0.0931203 0.994084 + outer loop + vertex 787.095 258.679 362.693 + vertex 779.345 258.903 363.149 + vertex 778.664 253.631 362.694 + endloop + endfacet + facet normal 0.0228967 -0.0380028 0.999015 + outer loop + vertex 787.095 258.679 362.693 + vertex 778.664 253.631 362.694 + vertex 786.829 253.476 362.501 + endloop + endfacet + facet normal 0.0532506 -0.0927934 0.99426 + outer loop + vertex 779.345 258.903 363.149 + vertex 771.285 254.278 363.149 + vertex 778.664 253.631 362.694 + endloop + endfacet + facet normal 0.0532835 -0.0924402 0.994292 + outer loop + vertex 778.664 253.631 362.694 + vertex 771.285 254.278 363.149 + vertex 770.267 248.802 362.695 + endloop + endfacet + facet normal 0.0218896 -0.0378525 0.999044 + outer loop + vertex 778.664 253.631 362.694 + vertex 770.267 248.802 362.695 + vertex 778.409 248.436 362.503 + endloop + endfacet + facet normal 0.0508055 -0.0919937 0.994463 + outer loop + vertex 771.285 254.278 363.149 + vertex 762.839 249.614 363.149 + vertex 770.267 248.802 362.695 + endloop + endfacet + facet normal 0.0508328 -0.0917554 0.994483 + outer loop + vertex 770.267 248.802 362.695 + vertex 762.839 249.614 363.149 + vertex 761.775 244.103 362.695 + endloop + endfacet + facet normal 0.0208602 -0.0375884 0.999076 + outer loop + vertex 770.267 248.802 362.695 + vertex 761.775 244.103 362.695 + vertex 769.964 243.58 362.505 + endloop + endfacet + facet normal 0.0484561 -0.0913097 0.994643 + outer loop + vertex 762.839 249.614 363.149 + vertex 753.736 244.783 363.149 + vertex 761.775 244.103 362.695 + endloop + endfacet + facet normal 0.048491 -0.09092 0.994677 + outer loop + vertex 761.775 244.103 362.695 + vertex 753.736 244.783 363.149 + vertex 753.272 239.571 362.696 + endloop + endfacet + facet normal 0.0200876 -0.0376165 0.99909 + outer loop + vertex 761.775 244.103 362.695 + vertex 753.272 239.571 362.696 + vertex 761.524 238.908 362.505 + endloop + endfacet + facet normal 0.046327 -0.0907377 0.994797 + outer loop + vertex 753.736 244.783 363.149 + vertex 745.437 240.546 363.149 + vertex 753.272 239.571 362.696 + endloop + endfacet + facet normal 0.0463526 -0.0905389 0.994814 + outer loop + vertex 753.272 239.571 362.696 + vertex 745.437 240.546 363.149 + vertex 744.699 235.184 362.696 + endloop + endfacet + facet normal 0.0819794 -0.0961961 0.991981 + outer loop + vertex 834.874 297.968 363.149 + vertex 827.643 291.806 363.149 + vertex 834.236 292.743 362.695 + endloop + endfacet + facet normal 0.0898301 -0.0970871 0.991214 + outer loop + vertex 840.95 298.997 362.7 + vertex 834.874 297.968 363.149 + vertex 834.236 292.743 362.695 + endloop + endfacet + facet normal 0.0347143 -0.0379272 0.998677 + outer loop + vertex 840.95 298.997 362.7 + vertex 834.236 292.743 362.695 + vertex 840.939 293.846 362.504 + endloop + endfacet + facet normal 0.0322928 -0.0374591 0.998776 + outer loop + vertex 834.178 287.577 362.502 + vertex 826.991 286.553 362.696 + vertex 826.788 281.341 362.507 + endloop + endfacet + facet normal 0.0296498 -0.037502 0.998857 + outer loop + vertex 826.788 281.341 362.507 + vertex 819.375 280.544 362.697 + vertex 819.087 275.311 362.509 + endloop + endfacet + facet normal 0.0274604 -0.038092 0.998897 + outer loop + vertex 819.087 275.311 362.509 + vertex 811.548 274.775 362.696 + vertex 811.251 269.552 362.505 + endloop + endfacet + facet normal 0.0260861 -0.0383258 0.998925 + outer loop + vertex 811.251 269.552 362.505 + vertex 803.557 269.232 362.694 + vertex 803.291 264.029 362.501 + endloop + endfacet + facet normal 0.024981 -0.0383729 0.998951 + outer loop + vertex 803.291 264.029 362.501 + vertex 795.42 263.885 362.692 + vertex 795.149 258.681 362.499 + endloop + endfacet + facet normal 0.0240081 -0.0380587 0.998987 + outer loop + vertex 795.149 258.681 362.499 + vertex 787.095 258.679 362.693 + vertex 786.829 253.476 362.501 + endloop + endfacet + facet normal 0.0228988 -0.0379012 0.999019 + outer loop + vertex 786.829 253.476 362.501 + vertex 778.664 253.631 362.694 + vertex 778.409 248.436 362.503 + endloop + endfacet + facet normal 0.021899 -0.0376478 0.999051 + outer loop + vertex 778.409 248.436 362.503 + vertex 770.267 248.802 362.695 + vertex 769.964 243.58 362.505 + endloop + endfacet + facet normal 0.0208561 -0.037653 0.999073 + outer loop + vertex 769.964 243.58 362.505 + vertex 761.775 244.103 362.695 + vertex 761.524 238.908 362.505 + endloop + endfacet + facet normal 0.0201119 -0.0373171 0.999101 + outer loop + vertex 761.524 238.908 362.505 + vertex 753.272 239.571 362.696 + vertex 753.064 234.394 362.507 + endloop + endfacet + facet normal 0.0169525 -0.0332827 0.999302 + outer loop + vertex 753.012 229.291 362.338 + vertex 744.467 229.994 362.506 + vertex 744.452 224.912 362.337 + endloop + endfacet + facet normal 0.0190949 -0.0372769 0.999123 + outer loop + vertex 753.272 239.571 362.696 + vertex 744.699 235.184 362.696 + vertex 753.064 234.394 362.507 + endloop + endfacet + facet normal 0.0182336 -0.0374353 0.999133 + outer loop + vertex 744.467 229.994 362.506 + vertex 735.823 230.835 362.696 + vertex 735.593 225.658 362.506 + endloop + endfacet + facet normal 0.0444316 -0.0902838 0.994924 + outer loop + vertex 745.437 240.546 363.149 + vertex 736.812 236.301 363.149 + vertex 744.699 235.184 362.696 + endloop + endfacet + facet normal 0.0176357 -0.0374091 0.999144 + outer loop + vertex 735.823 230.835 362.696 + vertex 726.661 226.531 362.696 + vertex 735.593 225.658 362.506 + endloop + endfacet + facet normal 0.016204 -0.0332808 0.999315 + outer loop + vertex 744.467 229.994 362.506 + vertex 735.593 225.658 362.506 + vertex 744.452 224.912 362.337 + endloop + endfacet + facet normal 0.0281604 -0.0551904 0.998079 + outer loop + vertex 753.012 229.291 362.338 + vertex 744.452 224.912 362.337 + vertex 753.018 224.232 362.058 + endloop + endfacet + facet normal 0.029496 -0.0551865 0.99804 + outer loop + vertex 761.482 228.752 362.058 + vertex 753.012 229.291 362.338 + vertex 753.018 224.232 362.058 + endloop + endfacet + facet normal 0.0305751 -0.0550591 0.998015 + outer loop + vertex 769.958 233.446 362.057 + vertex 761.474 233.809 362.337 + vertex 761.482 228.752 362.058 + endloop + endfacet + facet normal 0.0320587 -0.0549155 0.997976 + outer loop + vertex 778.436 238.318 362.053 + vertex 769.93 238.493 362.336 + vertex 769.958 233.446 362.057 + endloop + endfacet + facet normal 0.0333291 -0.0552753 0.997915 + outer loop + vertex 786.87 243.36 362.051 + vertex 778.391 243.356 362.334 + vertex 778.436 238.318 362.053 + endloop + endfacet + facet normal 0.034694 -0.0551205 0.997877 + outer loop + vertex 795.194 248.559 362.048 + vertex 786.818 248.396 362.331 + vertex 786.87 243.36 362.051 + endloop + endfacet + facet normal 0.0358061 -0.0550982 0.997839 + outer loop + vertex 803.342 253.903 362.051 + vertex 795.139 253.6 362.329 + vertex 795.194 248.559 362.048 + endloop + endfacet + facet normal 0.0370922 -0.054897 0.997803 + outer loop + vertex 811.305 259.424 362.059 + vertex 803.284 258.949 362.331 + vertex 803.342 253.903 362.051 + endloop + endfacet + facet normal 0.0391319 -0.0547255 0.997734 + outer loop + vertex 819.155 265.194 362.067 + vertex 811.243 264.467 362.338 + vertex 811.305 259.424 362.059 + endloop + endfacet + facet normal 0.0424106 -0.0539006 0.997645 + outer loop + vertex 826.932 271.241 362.064 + vertex 819.078 270.228 362.343 + vertex 819.155 265.194 362.067 + endloop + endfacet + facet normal 0.0464889 -0.0538332 0.997467 + outer loop + vertex 834.459 277.449 362.048 + vertex 826.816 276.257 362.34 + vertex 826.932 271.241 362.064 + endloop + endfacet + facet normal 0.0499339 -0.0542285 0.997279 + outer loop + vertex 841.314 283.592 362.039 + vertex 834.279 282.473 362.33 + vertex 834.459 277.449 362.048 + endloop + endfacet + facet normal 0.0507067 -0.0547578 0.997211 + outer loop + vertex 847.184 289.54 362.067 + vertex 841.116 288.694 362.329 + vertex 841.314 283.592 362.039 + endloop + endfacet + facet normal 0.0503366 -0.0520499 0.997375 + outer loop + vertex 847.004 294.732 362.347 + vertex 841.116 288.694 362.329 + vertex 847.184 289.54 362.067 + endloop + endfacet + facet normal 0.030641 -0.0320858 0.999015 + outer loop + vertex 846.795 299.875 362.518 + vertex 840.939 293.846 362.504 + vertex 847.004 294.732 362.347 + endloop + endfacet + facet normal 0.036658 -0.0379287 0.998608 + outer loop + vertex 846.795 299.875 362.518 + vertex 840.95 298.997 362.7 + vertex 840.939 293.846 362.504 + endloop + endfacet + facet normal 0.0898133 -0.0969827 0.991225 + outer loop + vertex 841.865 304.443 363.149 + vertex 834.874 297.968 363.149 + vertex 840.95 298.997 362.7 + endloop + endfacet + facet normal 0.0385959 -0.0313365 0.998763 + outer loop + vertex 851.06 309.085 362.671 + vertex 846.833 304.91 362.704 + vertex 851.785 305.476 362.53 + endloop + endfacet + facet normal 0.0427865 -0.0304893 0.998619 + outer loop + vertex 851.06 309.085 362.671 + vertex 851.785 305.476 362.53 + vertex 854.131 309.746 362.56 + endloop + endfacet + facet normal 0.0903058 -0.0643071 0.993836 + outer loop + vertex 857.9 311.566 362.473 + vertex 862.942 319.331 362.517 + vertex 858.663 323.092 363.149 + endloop + endfacet + facet normal 0.0890892 -0.0656943 0.993855 + outer loop + vertex 858.663 323.092 363.149 + vertex 862.942 319.331 362.517 + vertex 863.052 329.044 363.149 + endloop + endfacet + facet normal 0.0954754 -0.0657277 0.993259 + outer loop + vertex 862.942 319.331 362.517 + vertex 867.09 325.281 362.512 + vertex 863.052 329.044 363.149 + endloop + endfacet + facet normal 0.0967378 -0.0643675 0.993226 + outer loop + vertex 863.052 329.044 363.149 + vertex 867.09 325.281 362.512 + vertex 867.19 335.264 363.149 + endloop + endfacet + facet normal 0.0988246 -0.0643753 0.99302 + outer loop + vertex 867.09 325.281 362.512 + vertex 871.042 331.079 362.495 + vertex 867.19 335.264 363.149 + endloop + endfacet + facet normal 0.102465 -0.0610011 0.992864 + outer loop + vertex 867.19 335.264 363.149 + vertex 871.042 331.079 362.495 + vertex 870.922 341.532 363.149 + endloop + endfacet + facet normal 0.106202 -0.0609339 0.992476 + outer loop + vertex 871.042 331.079 362.495 + vertex 874.782 337.394 362.482 + vertex 870.922 341.532 363.149 + endloop + endfacet + facet normal 0.10961 -0.0577265 0.992297 + outer loop + vertex 870.922 341.532 363.149 + vertex 874.782 337.394 362.482 + vertex 874.318 347.981 363.149 + endloop + endfacet + facet normal 0.114275 -0.05749 0.991784 + outer loop + vertex 874.782 337.394 362.482 + vertex 878.283 344.163 362.471 + vertex 874.318 347.981 363.149 + endloop + endfacet + facet normal 0.117687 -0.0539114 0.991586 + outer loop + vertex 874.318 347.981 363.149 + vertex 878.283 344.163 362.471 + vertex 877.309 354.51 363.149 + endloop + endfacet + facet normal 0.12415 -0.0532538 0.990833 + outer loop + vertex 878.283 344.163 362.471 + vertex 881.317 351.376 362.479 + vertex 877.309 354.51 363.149 + endloop + endfacet + facet normal 0.127052 -0.0495047 0.99066 + outer loop + vertex 877.309 354.51 363.149 + vertex 881.317 351.376 362.479 + vertex 879.899 361.158 363.149 + endloop + endfacet + facet normal 0.136904 -0.0479922 0.989421 + outer loop + vertex 881.317 351.376 362.479 + vertex 883.656 358.532 362.502 + vertex 879.899 361.158 363.149 + endloop + endfacet + facet normal 0.139017 -0.0449306 0.98927 + outer loop + vertex 879.899 361.158 363.149 + vertex 883.656 358.532 362.502 + vertex 882.015 367.705 363.149 + endloop + endfacet + facet normal 0.149149 -0.04302 0.987878 + outer loop + vertex 883.656 358.532 362.502 + vertex 885.659 365.232 362.492 + vertex 882.015 367.705 363.149 + endloop + endfacet + facet normal 0.151794 -0.0390596 0.98764 + outer loop + vertex 882.015 367.705 363.149 + vertex 885.659 365.232 362.492 + vertex 883.773 374.538 363.149 + endloop + endfacet + facet normal 0.166152 -0.0359952 0.985443 + outer loop + vertex 885.659 365.232 362.492 + vertex 887.241 372.272 362.482 + vertex 883.773 374.538 363.149 + endloop + endfacet + facet normal 0.168465 -0.0323756 0.985176 + outer loop + vertex 883.773 374.538 363.149 + vertex 887.241 372.272 362.482 + vertex 885.029 381.068 363.149 + endloop + endfacet + facet normal 0.193066 -0.025859 0.980845 + outer loop + vertex 887.241 372.272 362.482 + vertex 888.134 379.502 362.497 + vertex 885.029 381.068 363.149 + endloop + endfacet + facet normal 0.193638 -0.0246912 0.980762 + outer loop + vertex 885.029 381.068 363.149 + vertex 888.134 379.502 362.497 + vertex 885.881 387.756 363.149 + endloop + endfacet + facet normal 0.222105 -0.016459 0.974884 + outer loop + vertex 888.134 379.502 362.497 + vertex 888.645 386.366 362.496 + vertex 885.881 387.756 363.149 + endloop + endfacet + facet normal 0.223359 -0.0138499 0.974638 + outer loop + vertex 885.881 387.756 363.149 + vertex 888.645 386.366 362.496 + vertex 886.287 394.297 363.149 + endloop + endfacet + facet normal 0.258548 -0.00267566 0.965995 + outer loop + vertex 888.645 386.366 362.496 + vertex 888.705 393.264 362.499 + vertex 886.287 394.297 363.149 + endloop + endfacet + facet normal 0.259846 0.000579755 0.96565 + outer loop + vertex 886.287 394.297 363.149 + vertex 888.705 393.264 362.499 + vertex 886.271 401.273 363.149 + endloop + endfacet + facet normal 0.3044 0.015194 0.952423 + outer loop + vertex 888.705 393.264 362.499 + vertex 888.356 399.921 362.505 + vertex 886.271 401.273 363.149 + endloop + endfacet + facet normal 0.30604 0.0179973 0.951848 + outer loop + vertex 886.271 401.273 363.149 + vertex 888.356 399.921 362.505 + vertex 885.917 407.302 363.149 + endloop + endfacet + facet normal 0.351618 0.0344831 0.935508 + outer loop + vertex 888.356 399.921 362.505 + vertex 887.768 406.319 362.49 + vertex 885.917 407.302 363.149 + endloop + endfacet + facet normal 0.353188 0.0379298 0.934783 + outer loop + vertex 885.917 407.302 363.149 + vertex 887.768 406.319 362.49 + vertex 885.243 413.58 363.149 + endloop + endfacet + facet normal 0.41385 0.0614388 0.90827 + outer loop + vertex 887.768 406.319 362.49 + vertex 886.834 412.847 362.474 + vertex 885.243 413.58 363.149 + endloop + endfacet + facet normal 0.414069 0.0620439 0.908129 + outer loop + vertex 885.243 413.58 363.149 + vertex 886.834 412.847 362.474 + vertex 884.4 419.202 363.149 + endloop + endfacet + facet normal 0.479406 0.0908107 0.872882 + outer loop + vertex 886.834 412.847 362.474 + vertex 885.589 419.529 362.462 + vertex 884.4 419.202 363.149 + endloop + endfacet + facet normal 0.479602 0.0900406 0.872854 + outer loop + vertex 884.4 419.202 363.149 + vertex 885.589 419.529 362.462 + vertex 883.19 425.646 363.149 + endloop + endfacet + facet normal 0.56192 0.128577 0.817138 + outer loop + vertex 885.589 419.529 362.462 + vertex 884.065 426.119 362.474 + vertex 883.19 425.646 363.149 + endloop + endfacet + facet normal 0.564275 0.123108 0.816357 + outer loop + vertex 883.19 425.646 363.149 + vertex 884.065 426.119 362.474 + vertex 882.033 430.951 363.149 + endloop + endfacet + facet normal 0.614665 0.150168 0.774362 + outer loop + vertex 884.065 426.119 362.474 + vertex 882.453 432.601 362.496 + vertex 882.033 430.951 363.149 + endloop + endfacet + facet normal 0.620487 0.147079 0.770301 + outer loop + vertex 882.033 430.951 363.149 + vertex 882.453 432.601 362.496 + vertex 880.639 436.832 363.149 + endloop + endfacet + facet normal 0.637184 0.156657 0.754623 + outer loop + vertex 882.453 432.601 362.496 + vertex 880.705 439.596 362.52 + vertex 880.639 436.832 363.149 + endloop + endfacet + facet normal 0.641468 0.155769 0.751169 + outer loop + vertex 880.639 436.832 363.149 + vertex 880.705 439.596 362.52 + vertex 879.119 443.093 363.149 + endloop + endfacet + facet normal 0.639629 0.15461 0.752974 + outer loop + vertex 880.705 439.596 362.52 + vertex 878.882 447.007 362.547 + vertex 879.119 443.093 363.149 + endloop + endfacet + facet normal 0.6633 0.152897 0.732568 + outer loop + vertex 879.119 443.093 363.149 + vertex 878.882 447.007 362.547 + vertex 877.742 449.065 363.149 + endloop + endfacet + facet normal 0.657198 0.147595 0.739125 + outer loop + vertex 878.882 447.007 362.547 + vertex 877.202 454.725 362.5 + vertex 877.742 449.065 363.149 + endloop + endfacet + facet normal 0.748586 0.145727 0.646825 + outer loop + vertex 877.742 449.065 363.149 + vertex 877.202 454.725 362.5 + vertex 876.486 455.541 363.145 + endloop + endfacet + facet normal 0.765597 0.184882 0.616182 + outer loop + vertex 876.486 455.541 363.145 + vertex 877.202 454.725 362.5 + vertex 875.838 460.581 362.437 + endloop + endfacet + facet normal 0.98919 0.135147 0.0569117 + outer loop + vertex 875.566 462.325 363.022 + vertex 876.486 455.541 363.145 + vertex 875.838 460.581 362.437 + endloop + endfacet + facet normal 0.323417 0.0853702 0.942398 + outer loop + vertex 876.545 460.284 362.221 + vertex 875.838 460.581 362.437 + vertex 877.202 454.725 362.5 + endloop + endfacet + facet normal 0.0881611 -0.024776 0.995798 + outer loop + vertex 883.656 358.532 362.502 + vertex 887.136 357.863 362.177 + vertex 885.659 365.232 362.492 + endloop + endfacet + facet normal 0.0963697 -0.0230995 0.995078 + outer loop + vertex 887.136 357.863 362.177 + vertex 889.609 363.779 362.075 + vertex 885.659 365.232 362.492 + endloop + endfacet + facet normal 0.0973175 -0.0205123 0.995042 + outer loop + vertex 885.659 365.232 362.492 + vertex 889.609 363.779 362.075 + vertex 887.241 372.272 362.482 + endloop + endfacet + facet normal 0.109388 -0.0170895 0.993852 + outer loop + vertex 889.609 363.779 362.075 + vertex 890.613 372.716 362.119 + vertex 887.241 372.272 362.482 + endloop + endfacet + facet normal 0.109188 -0.0155311 0.9939 + outer loop + vertex 887.241 372.272 362.482 + vertex 890.613 372.716 362.119 + vertex 888.134 379.502 362.497 + endloop + endfacet + facet normal 0.121743 -0.0108671 0.992502 + outer loop + vertex 890.613 372.716 362.119 + vertex 890.77 379.741 362.176 + vertex 888.134 379.502 362.497 + endloop + endfacet + facet normal 0.121576 -0.00896847 0.992542 + outer loop + vertex 888.134 379.502 362.497 + vertex 890.77 379.741 362.176 + vertex 888.645 386.366 362.496 + endloop + endfacet + facet normal 0.13715 -0.00387657 0.990543 + outer loop + vertex 890.77 379.741 362.176 + vertex 891.521 386.136 362.097 + vertex 888.645 386.366 362.496 + endloop + endfacet + facet normal 0.137328 -0.00162187 0.990524 + outer loop + vertex 888.645 386.366 362.496 + vertex 891.521 386.136 362.097 + vertex 888.705 393.264 362.499 + endloop + endfacet + facet normal 0.155357 0.00565066 0.987842 + outer loop + vertex 891.521 386.136 362.097 + vertex 890.681 393.764 362.186 + vertex 888.705 393.264 362.499 + endloop + endfacet + facet normal 0.154946 0.0073097 0.987896 + outer loop + vertex 888.705 393.264 362.499 + vertex 890.681 393.764 362.186 + vertex 888.356 399.921 362.505 + endloop + endfacet + facet normal 0.174867 0.0150113 0.984478 + outer loop + vertex 890.681 393.764 362.186 + vertex 890.456 399.499 362.138 + vertex 888.356 399.921 362.505 + endloop + endfacet + facet normal 0.175523 0.0184324 0.984303 + outer loop + vertex 888.356 399.921 362.505 + vertex 890.456 399.499 362.138 + vertex 887.768 406.319 362.49 + endloop + endfacet + facet normal 0.199374 0.0280789 0.979521 + outer loop + vertex 890.456 399.499 362.138 + vertex 889.602 406.49 362.112 + vertex 887.768 406.319 362.49 + endloop + endfacet + facet normal 0.199108 0.0308729 0.979491 + outer loop + vertex 887.768 406.319 362.49 + vertex 889.602 406.49 362.112 + vertex 886.834 412.847 362.474 + endloop + endfacet + facet normal 0.223859 0.0419815 0.973717 + outer loop + vertex 889.602 406.49 362.112 + vertex 888.36 413.671 362.087 + vertex 886.834 412.847 362.474 + endloop + endfacet + facet normal 0.223197 0.0432531 0.973813 + outer loop + vertex 886.834 412.847 362.474 + vertex 888.36 413.671 362.087 + vertex 885.589 419.529 362.462 + endloop + endfacet + facet normal 0.244356 0.0536224 0.968202 + outer loop + vertex 888.36 413.671 362.087 + vertex 886.77 421.581 362.051 + vertex 885.589 419.529 362.462 + endloop + endfacet + facet normal 0.242888 0.0545313 0.96852 + outer loop + vertex 885.589 419.529 362.462 + vertex 886.77 421.581 362.051 + vertex 884.065 426.119 362.474 + endloop + endfacet + facet normal 0.259763 0.0650632 0.963478 + outer loop + vertex 886.77 421.581 362.051 + vertex 884.648 428.554 362.152 + vertex 884.065 426.119 362.474 + endloop + endfacet + facet normal 0.267051 0.0630705 0.961616 + outer loop + vertex 884.065 426.119 362.474 + vertex 884.648 428.554 362.152 + vertex 882.453 432.601 362.496 + endloop + endfacet + facet normal 0.268732 0.0640278 0.961085 + outer loop + vertex 884.648 428.554 362.152 + vertex 883.187 435.679 362.086 + vertex 882.453 432.601 362.496 + endloop + endfacet + facet normal 0.269052 0.0639402 0.961001 + outer loop + vertex 882.453 432.601 362.496 + vertex 883.187 435.679 362.086 + vertex 880.705 439.596 362.52 + endloop + endfacet + facet normal 0.274849 0.0678251 0.959092 + outer loop + vertex 883.187 435.679 362.086 + vertex 880.805 444.447 362.148 + vertex 880.705 439.596 362.52 + endloop + endfacet + facet normal 0.287402 0.067285 0.955444 + outer loop + vertex 880.705 439.596 362.52 + vertex 880.805 444.447 362.148 + vertex 878.882 447.007 362.547 + endloop + endfacet + facet normal 0.286279 0.0663791 0.955844 + outer loop + vertex 880.805 444.447 362.148 + vertex 878.911 452.535 362.154 + vertex 878.882 447.007 362.547 + endloop + endfacet + facet normal 0.279024 0.0665685 0.957974 + outer loop + vertex 878.882 447.007 362.547 + vertex 878.911 452.535 362.154 + vertex 877.202 454.725 362.5 + endloop + endfacet + facet normal 0.278395 0.0660432 0.958193 + outer loop + vertex 877.202 454.725 362.5 + vertex 878.911 452.535 362.154 + vertex 877.591 458.079 362.156 + endloop + endfacet + facet normal 0.218483 0.0745104 0.972992 + outer loop + vertex 876.545 460.284 362.221 + vertex 877.202 454.725 362.5 + vertex 877.591 458.079 362.156 + endloop + endfacet + facet normal 0.0876229 -0.0275599 0.995772 + outer loop + vertex 885.586 350.98 362.123 + vertex 887.136 357.863 362.177 + vertex 883.656 358.532 362.502 + endloop + endfacet + facet normal 0.0802048 -0.0294843 0.996342 + outer loop + vertex 881.317 351.376 362.479 + vertex 885.586 350.98 362.123 + vertex 883.656 358.532 362.502 + endloop + endfacet + facet normal 0.0800047 -0.0315996 0.996293 + outer loop + vertex 882.974 342.167 362.054 + vertex 885.586 350.98 362.123 + vertex 881.317 351.376 362.479 + endloop + endfacet + facet normal 0.0748887 -0.032537 0.996661 + outer loop + vertex 878.283 344.163 362.471 + vertex 882.974 342.167 362.054 + vertex 881.317 351.376 362.479 + endloop + endfacet + facet normal 0.0739886 -0.0346515 0.996657 + outer loop + vertex 878.935 334.76 362.096 + vertex 882.974 342.167 362.054 + vertex 878.283 344.163 362.471 + endloop + endfacet + facet normal 0.0706084 -0.0348953 0.996894 + outer loop + vertex 874.782 337.394 362.482 + vertex 878.935 334.76 362.096 + vertex 878.283 344.163 362.471 + endloop + endfacet + facet normal 0.0693699 -0.0368507 0.99691 + outer loop + vertex 875.06 328.142 362.121 + vertex 878.935 334.76 362.096 + vertex 874.782 337.394 362.482 + endloop + endfacet + facet normal 0.0657518 -0.0369689 0.997151 + outer loop + vertex 871.042 331.079 362.495 + vertex 875.06 328.142 362.121 + vertex 874.782 337.394 362.482 + endloop + endfacet + facet normal 0.0642421 -0.0390373 0.997171 + outer loop + vertex 870.932 322.083 362.15 + vertex 875.06 328.142 362.121 + vertex 871.042 331.079 362.495 + endloop + endfacet + facet normal 0.0616266 -0.0390119 0.997337 + outer loop + vertex 867.09 325.281 362.512 + vertex 870.932 322.083 362.15 + vertex 871.042 331.079 362.495 + endloop + endfacet + facet normal 0.0601971 -0.0407319 0.997355 + outer loop + vertex 867.017 317.769 362.21 + vertex 870.932 322.083 362.15 + vertex 867.09 325.281 362.512 + endloop + endfacet + facet normal 0.0596243 -0.0407277 0.99739 + outer loop + vertex 862.942 319.331 362.517 + vertex 867.017 317.769 362.21 + vertex 867.09 325.281 362.512 + endloop + endfacet + facet normal 0.0594476 -0.0411872 0.997381 + outer loop + vertex 863.558 311.444 362.155 + vertex 867.017 317.769 362.21 + vertex 862.942 319.331 362.517 + endloop + endfacet + facet normal 0.0551936 -0.0415303 0.997612 + outer loop + vertex 857.9 311.566 362.473 + vertex 863.558 311.444 362.155 + vertex 862.942 319.331 362.517 + endloop + endfacet + facet normal 0.0460049 -0.0455524 0.997902 + outer loop + vertex 854.131 309.746 362.56 + vertex 853.942 313.644 362.747 + vertex 851.06 309.085 362.671 + endloop + endfacet + facet normal 0.029533 -0.023214 0.999294 + outer loop + vertex 855.011 308.077 362.495 + vertex 854.131 309.746 362.56 + vertex 851.785 305.476 362.53 + endloop + endfacet + facet normal 0.0366655 -0.0320662 0.998813 + outer loop + vertex 855.226 304.855 362.384 + vertex 855.011 308.077 362.495 + vertex 851.785 305.476 362.53 + endloop + endfacet + facet normal 0.0552627 -0.0386194 0.997725 + outer loop + vertex 858.645 303.155 362.106 + vertex 863.558 311.444 362.155 + vertex 857.9 311.566 362.473 + endloop + endfacet + facet normal 0.0438436 -0.034889 0.998429 + outer loop + vertex 854.932 300.352 362.239 + vertex 855.226 304.855 362.384 + vertex 851.639 300.246 362.38 + endloop + endfacet + facet normal 0.0547556 -0.0520478 0.997142 + outer loop + vertex 855.658 298.44 362.1 + vertex 854.932 300.352 362.239 + vertex 852.322 295.509 362.13 + endloop + endfacet + facet normal 0.0739866 -0.073969 0.994512 + outer loop + vertex 856.089 295.708 361.864 + vertex 855.658 298.44 362.1 + vertex 852.322 295.509 362.13 + endloop + endfacet + facet normal 0.0841726 -0.072598 0.993803 + outer loop + vertex 860.435 297.458 361.619 + vertex 860.254 299.423 361.778 + vertex 858.131 294.906 361.628 + endloop + endfacet + facet normal 0.078886 -0.0850101 0.993252 + outer loop + vertex 858.131 294.906 361.628 + vertex 855.448 290.8 361.489 + vertex 857.372 292.789 361.507 + endloop + endfacet + facet normal 0.115631 -0.12536 0.98535 + outer loop + vertex 855.55 287.78 361.093 + vertex 855.448 290.8 361.489 + vertex 852.507 285.068 361.105 + endloop + endfacet + facet normal 0.0456506 -0.0891046 0.994976 + outer loop + vertex 753.068 219.208 361.605 + vertex 744.489 219.874 362.058 + vertex 744.551 214.863 361.606 + endloop + endfacet + facet normal 0.0648615 -0.132789 0.98902 + outer loop + vertex 744.643 209.882 360.932 + vertex 735.786 210.627 361.612 + vertex 735.867 205.646 360.938 + endloop + endfacet + facet normal 0.062275 -0.132853 0.989177 + outer loop + vertex 735.786 210.627 361.612 + vertex 726.605 206.366 361.618 + vertex 735.867 205.646 360.938 + endloop + endfacet + facet normal 0.0623001 -0.132565 0.989214 + outer loop + vertex 735.867 205.646 360.938 + vertex 726.605 206.366 361.618 + vertex 726.688 201.384 360.945 + endloop + endfacet + facet normal 0.061279 -0.13259 0.989275 + outer loop + vertex 726.605 206.366 361.618 + vertex 717.25 202.004 361.613 + vertex 726.688 201.384 360.945 + endloop + endfacet + facet normal 0.0613058 -0.132232 0.989321 + outer loop + vertex 726.688 201.384 360.945 + vertex 717.25 202.004 361.613 + vertex 717.346 197.061 360.946 + endloop + endfacet + facet normal 0.0615176 -0.132226 0.989309 + outer loop + vertex 717.25 202.004 361.613 + vertex 708.592 197.723 361.579 + vertex 717.346 197.061 360.946 + endloop + endfacet + facet normal 0.0609742 -0.138612 0.988468 + outer loop + vertex 717.346 197.061 360.946 + vertex 708.592 197.723 361.579 + vertex 708.622 192.923 360.904 + endloop + endfacet + facet normal 0.0625441 -0.138589 0.988373 + outer loop + vertex 708.592 197.723 361.579 + vertex 702.256 194.176 361.483 + vertex 708.622 192.923 360.904 + endloop + endfacet + facet normal 0.0601217 -0.150177 0.986829 + outer loop + vertex 708.622 192.923 360.904 + vertex 702.256 194.176 361.483 + vertex 700.614 189.202 360.826 + endloop + endfacet + facet normal 0.0458951 -0.145669 0.988268 + outer loop + vertex 700.614 189.202 360.826 + vertex 702.256 194.176 361.483 + vertex 696 193.607 361.69 + endloop + endfacet + facet normal 0.0651877 -0.125785 0.989914 + outer loop + vertex 696 193.607 361.69 + vertex 694.536 188.492 361.136 + vertex 700.614 189.202 360.826 + endloop + endfacet + facet normal 0.0627444 -0.125112 0.990157 + outer loop + vertex 696 193.607 361.69 + vertex 691.201 190.57 361.61 + vertex 694.536 188.492 361.136 + endloop + endfacet + facet normal 0.0553817 -0.136677 0.989066 + outer loop + vertex 694.536 188.492 361.136 + vertex 691.201 190.57 361.61 + vertex 690.801 185.424 360.921 + endloop + endfacet + facet normal 0.0392497 -0.0881304 0.995335 + outer loop + vertex 696 193.607 361.69 + vertex 690.784 195.653 362.076 + vertex 691.201 190.57 361.61 + endloop + endfacet + facet normal 0.0425744 -0.0797605 0.995904 + outer loop + vertex 695.285 199.307 362.177 + vertex 690.784 195.653 362.076 + vertex 696 193.607 361.69 + endloop + endfacet + facet normal 0.0255975 -0.0819226 0.99631 + outer loop + vertex 695.285 199.307 362.177 + vertex 696 193.607 361.69 + vertex 701.154 198.307 361.944 + endloop + endfacet + facet normal 0.0419087 -0.0996953 0.994135 + outer loop + vertex 702.256 194.176 361.483 + vertex 701.154 198.307 361.944 + vertex 696 193.607 361.69 + endloop + endfacet + facet normal 0.0408472 -0.0999803 0.994151 + outer loop + vertex 708.592 197.723 361.579 + vertex 701.154 198.307 361.944 + vertex 702.256 194.176 361.483 + endloop + endfacet + facet normal 0.0416053 -0.0908479 0.994995 + outer loop + vertex 708.277 202.574 362.035 + vertex 701.154 198.307 361.944 + vertex 708.592 197.723 361.579 + endloop + endfacet + facet normal 0.0248739 -0.0629788 0.997705 + outer loop + vertex 708.277 202.574 362.035 + vertex 700.592 203.394 362.279 + vertex 701.154 198.307 361.944 + endloop + endfacet + facet normal 0.025662 -0.0557097 0.998117 + outer loop + vertex 708.05 207.706 362.328 + vertex 700.592 203.394 362.279 + vertex 708.277 202.574 362.035 + endloop + endfacet + facet normal 0.0245308 -0.0557613 0.998143 + outer loop + vertex 717.117 206.986 362.065 + vertex 708.05 207.706 362.328 + vertex 708.277 202.574 362.035 + endloop + endfacet + facet normal 0.0411724 -0.0890831 0.995173 + outer loop + vertex 717.117 206.986 362.065 + vertex 708.277 202.574 362.035 + vertex 717.25 202.004 361.613 + endloop + endfacet + facet normal 0.0246011 -0.0548928 0.998189 + outer loop + vertex 717.058 212.019 362.343 + vertex 708.05 207.706 362.328 + vertex 717.117 206.986 362.065 + endloop + endfacet + facet normal 0.0410505 -0.0908858 0.995015 + outer loop + vertex 717.25 202.004 361.613 + vertex 708.277 202.574 362.035 + vertex 708.592 197.723 361.579 + endloop + endfacet + facet normal 0.040994 -0.0890885 0.99518 + outer loop + vertex 726.605 206.366 361.618 + vertex 717.117 206.986 362.065 + vertex 717.25 202.004 361.613 + endloop + endfacet + facet normal 0.0410204 -0.0887072 0.995213 + outer loop + vertex 726.526 211.352 362.066 + vertex 717.117 206.986 362.065 + vertex 726.605 206.366 361.618 + endloop + endfacet + facet normal 0.043564 -0.0891387 0.995066 + outer loop + vertex 744.489 219.874 362.058 + vertex 735.71 215.618 362.061 + vertex 744.551 214.863 361.606 + endloop + endfacet + facet normal 0.041784 -0.0886924 0.995182 + outer loop + vertex 735.786 210.627 361.612 + vertex 726.526 211.352 362.066 + vertex 726.605 206.366 361.618 + endloop + endfacet + facet normal 0.0260428 -0.0549867 0.998147 + outer loop + vertex 735.633 220.62 362.339 + vertex 726.448 216.341 362.343 + vertex 735.71 215.618 362.061 + endloop + endfacet + facet normal 0.0253261 -0.0548834 0.998172 + outer loop + vertex 726.526 211.352 362.066 + vertex 717.058 212.019 362.343 + vertex 717.117 206.986 362.065 + endloop + endfacet + facet normal 0.0151541 -0.0328498 0.999345 + outer loop + vertex 726.398 221.361 362.508 + vertex 717.109 217.101 362.509 + vertex 726.448 216.341 362.343 + endloop + endfacet + facet normal 0.0144208 -0.033634 0.99933 + outer loop + vertex 717.058 212.019 362.343 + vertex 708.3 212.961 362.501 + vertex 708.05 207.706 362.328 + endloop + endfacet + facet normal 0.013965 -0.0336125 0.999337 + outer loop + vertex 708.3 212.961 362.501 + vertex 699.939 209.135 362.489 + vertex 708.05 207.706 362.328 + endloop + endfacet + facet normal 0.0165654 -0.0369389 0.99918 + outer loop + vertex 717.449 222.332 362.697 + vertex 708.774 218.33 362.693 + vertex 717.109 217.101 362.509 + endloop + endfacet + facet normal 0.0372196 -0.0875406 0.995465 + outer loop + vertex 709.882 223.992 363.149 + vertex 701.132 220.272 363.149 + vertex 708.774 218.33 362.693 + endloop + endfacet + facet normal 0.0143115 -0.0343696 0.999307 + outer loop + vertex 708.3 212.961 362.501 + vertex 702.208 214.659 362.646 + vertex 699.939 209.135 362.489 + endloop + endfacet + facet normal 0.00892922 -0.0393144 0.999187 + outer loop + vertex 695.822 213.672 362.724 + vertex 691.076 210.472 362.64 + vertex 694.093 208.553 362.538 + endloop + endfacet + facet normal 0.0137098 -0.0350557 0.999291 + outer loop + vertex 708.05 207.706 362.328 + vertex 699.939 209.135 362.489 + vertex 700.592 203.394 362.279 + endloop + endfacet + facet normal 0.028956 -0.0625229 0.997623 + outer loop + vertex 701.154 198.307 361.944 + vertex 700.592 203.394 362.279 + vertex 695.285 199.307 362.177 + endloop + endfacet + facet normal 0.0217131 -0.0541284 0.998298 + outer loop + vertex 695.285 199.307 362.177 + vertex 691.16 200.85 362.35 + vertex 690.784 195.653 362.076 + endloop + endfacet + facet normal 0.032617 -0.0548991 0.997959 + outer loop + vertex 690.784 195.653 362.076 + vertex 691.16 200.85 362.35 + vertex 688.059 198.006 362.295 + endloop + endfacet + facet normal 0.0295172 -0.0584798 0.997852 + outer loop + vertex 688.059 198.006 362.295 + vertex 686.513 194.574 362.139 + vertex 690.784 195.653 362.076 + endloop + endfacet + facet normal 0.0343864 -0.0778471 0.996372 + outer loop + vertex 686.513 194.574 362.139 + vertex 687.156 191.099 361.846 + vertex 690.784 195.653 362.076 + endloop + endfacet + facet normal 0.0275692 -0.0791179 0.996484 + outer loop + vertex 687.156 191.099 361.846 + vertex 686.513 194.574 362.139 + vertex 681.788 190.177 361.921 + endloop + endfacet + facet normal 0.0318398 -0.104175 0.994049 + outer loop + vertex 681.788 190.177 361.921 + vertex 682.568 185.421 361.398 + vertex 687.156 191.099 361.846 + endloop + endfacet + facet normal 0.0327283 -0.104885 0.993946 + outer loop + vertex 688.013 187.814 361.471 + vertex 687.156 191.099 361.846 + vertex 682.568 185.421 361.398 + endloop + endfacet + facet normal 0.0452282 -0.133201 0.990056 + outer loop + vertex 686.602 184.455 361.083 + vertex 688.013 187.814 361.471 + vertex 682.568 185.421 361.398 + endloop + endfacet + facet normal 0.040019 -0.154043 0.987253 + outer loop + vertex 682.568 185.421 361.398 + vertex 682.002 180.046 360.582 + vertex 686.602 184.455 361.083 + endloop + endfacet + facet normal 0.063406 -0.177845 0.982014 + outer loop + vertex 687.348 181.14 360.435 + vertex 686.602 184.455 361.083 + vertex 682.002 180.046 360.582 + endloop + endfacet + facet normal 0.0720283 -0.22128 0.972547 + outer loop + vertex 682.002 180.046 360.582 + vertex 683.124 175.594 359.486 + vertex 687.348 181.14 360.435 + endloop + endfacet + facet normal 0.0539418 -0.208197 0.976598 + outer loop + vertex 687.839 178.553 359.856 + vertex 687.348 181.14 360.435 + vertex 683.124 175.594 359.486 + endloop + endfacet + facet normal 0.0880399 -0.260643 0.961413 + outer loop + vertex 688.033 175.726 359.072 + vertex 687.839 178.553 359.856 + vertex 683.124 175.594 359.486 + endloop + endfacet + facet normal 0.0881156 -0.290251 0.952885 + outer loop + vertex 683.124 175.594 359.486 + vertex 683.531 170.131 357.784 + vertex 688.033 175.726 359.072 + endloop + endfacet + facet normal 0.0890307 -0.29092 0.952596 + outer loop + vertex 688.764 172.602 358.05 + vertex 688.033 175.726 359.072 + vertex 683.531 170.131 357.784 + endloop + endfacet + facet normal 0.115272 -0.284494 0.951722 + outer loop + vertex 688.033 175.726 359.072 + vertex 688.764 172.602 358.05 + vertex 691.601 175.241 358.495 + endloop + endfacet + facet normal 0.106595 -0.288456 0.951541 + outer loop + vertex 683.531 170.131 357.784 + vertex 683.124 175.594 359.486 + vertex 675.24 167.774 357.998 + endloop + endfacet + facet normal 0.10052 -0.282781 0.953903 + outer loop + vertex 675.24 167.774 357.998 + vertex 683.124 175.594 359.486 + vertex 674.847 172.867 359.55 + endloop + endfacet + facet normal 0.107134 -0.282111 0.953381 + outer loop + vertex 675.24 167.774 357.998 + vertex 674.847 172.867 359.55 + vertex 666.396 164.571 358.045 + endloop + endfacet + facet normal 0.102767 -0.277971 0.955077 + outer loop + vertex 666.396 164.571 358.045 + vertex 674.847 172.867 359.55 + vertex 666.171 169.698 359.561 + endloop + endfacet + facet normal 0.103995 -0.277885 0.954969 + outer loop + vertex 666.396 164.571 358.045 + vertex 666.171 169.698 359.561 + vertex 657.624 161.255 358.035 + endloop + endfacet + facet normal 0.104671 -0.278522 0.954709 + outer loop + vertex 657.624 161.255 358.035 + vertex 666.171 169.698 359.561 + vertex 657.425 166.403 359.558 + endloop + endfacet + facet normal 0.101358 -0.278737 0.955004 + outer loop + vertex 657.624 161.255 358.035 + vertex 657.425 166.403 359.558 + vertex 649.073 158.134 358.032 + endloop + endfacet + facet normal 0.103122 -0.280394 0.95433 + outer loop + vertex 649.073 158.134 358.032 + vertex 657.425 166.403 359.558 + vertex 648.844 163.273 359.566 + endloop + endfacet + facet normal 0.0974634 -0.280789 0.954808 + outer loop + vertex 649.073 158.134 358.032 + vertex 648.844 163.273 359.566 + vertex 640.499 155.167 358.034 + endloop + endfacet + facet normal 0.0963518 -0.279724 0.955233 + outer loop + vertex 640.499 155.167 358.034 + vertex 648.844 163.273 359.566 + vertex 640.256 160.298 359.561 + endloop + endfacet + facet normal 0.091765 -0.280047 0.95559 + outer loop + vertex 640.499 155.167 358.034 + vertex 640.256 160.298 359.561 + vertex 631.707 152.206 358.011 + endloop + endfacet + facet normal 0.0928105 -0.281075 0.955187 + outer loop + vertex 631.707 152.206 358.011 + vertex 640.256 160.298 359.561 + vertex 631.524 157.34 359.539 + endloop + endfacet + facet normal 0.0886078 -0.281321 0.955514 + outer loop + vertex 631.707 152.206 358.011 + vertex 631.524 157.34 359.539 + vertex 622.956 149.287 357.963 + endloop + endfacet + facet normal 0.0895648 -0.282267 0.955146 + outer loop + vertex 622.956 149.287 357.963 + vertex 631.524 157.34 359.539 + vertex 622.886 154.444 359.493 + endloop + endfacet + facet normal 0.0883998 -0.282312 0.955241 + outer loop + vertex 622.956 149.287 357.963 + vertex 622.886 154.444 359.493 + vertex 614.799 146.684 357.948 + endloop + endfacet + facet normal 0.0878279 -0.281759 0.955457 + outer loop + vertex 614.799 146.684 357.948 + vertex 622.886 154.444 359.493 + vertex 614.774 151.88 359.483 + endloop + endfacet + facet normal 0.0908904 -0.281668 0.955198 + outer loop + vertex 614.799 146.684 357.948 + vertex 614.774 151.88 359.483 + vertex 607.29 144.614 358.052 + endloop + endfacet + facet normal 0.087733 -0.278648 0.956378 + outer loop + vertex 607.29 144.614 358.052 + vertex 614.774 151.88 359.483 + vertex 607.257 149.943 359.608 + endloop + endfacet + facet normal 0.0963788 -0.278375 0.955625 + outer loop + vertex 607.29 144.614 358.052 + vertex 607.257 149.943 359.608 + vertex 599.559 143.111 358.394 + endloop + endfacet + facet normal 0.0849383 -0.266287 0.960144 + outer loop + vertex 599.559 143.111 358.394 + vertex 607.257 149.943 359.608 + vertex 599.939 148.799 359.938 + endloop + endfacet + facet normal 0.100325 -0.198992 0.974852 + outer loop + vertex 687.348 181.14 360.435 + vertex 687.839 178.553 359.856 + vertex 691.136 179.894 359.791 + endloop + endfacet + facet normal 0.079742 -0.219298 0.972394 + outer loop + vertex 683.124 175.594 359.486 + vertex 682.002 180.046 360.582 + vertex 674.847 172.867 359.55 + endloop + endfacet + facet normal 0.0707175 -0.210678 0.974994 + outer loop + vertex 674.847 172.867 359.55 + vertex 682.002 180.046 360.582 + vertex 674.618 177.954 360.665 + endloop + endfacet + facet normal 0.0780559 -0.210245 0.974528 + outer loop + vertex 674.847 172.867 359.55 + vertex 674.618 177.954 360.665 + vertex 666.171 169.698 359.561 + endloop + endfacet + facet normal 0.0764514 -0.208665 0.974994 + outer loop + vertex 666.171 169.698 359.561 + vertex 674.618 177.954 360.665 + vertex 666.015 174.895 360.685 + endloop + endfacet + facet normal 0.0783124 -0.208582 0.974865 + outer loop + vertex 666.171 169.698 359.561 + vertex 666.015 174.895 360.685 + vertex 657.425 166.403 359.558 + endloop + endfacet + facet normal 0.0772202 -0.207519 0.975178 + outer loop + vertex 657.425 166.403 359.558 + vertex 666.015 174.895 360.685 + vertex 657.264 171.629 360.683 + endloop + endfacet + facet normal 0.0765709 -0.207548 0.975223 + outer loop + vertex 657.425 166.403 359.558 + vertex 657.264 171.629 360.683 + vertex 648.844 163.273 359.566 + endloop + endfacet + facet normal 0.0766702 -0.207645 0.975195 + outer loop + vertex 648.844 163.273 359.566 + vertex 657.264 171.629 360.683 + vertex 648.651 168.494 360.693 + endloop + endfacet + facet normal 0.0714631 -0.20791 0.975534 + outer loop + vertex 648.844 163.273 359.566 + vertex 648.651 168.494 360.693 + vertex 640.256 160.298 359.561 + endloop + endfacet + facet normal 0.0723702 -0.208803 0.975276 + outer loop + vertex 640.256 160.298 359.561 + vertex 648.651 168.494 360.693 + vertex 640.059 165.503 360.69 + endloop + endfacet + facet normal 0.0683499 -0.209009 0.975522 + outer loop + vertex 640.256 160.298 359.561 + vertex 640.059 165.503 360.69 + vertex 631.524 157.34 359.539 + endloop + endfacet + facet normal 0.0689254 -0.209588 0.975358 + outer loop + vertex 631.524 157.34 359.539 + vertex 640.059 165.503 360.69 + vertex 631.365 162.542 360.668 + endloop + endfacet + facet normal 0.0651431 -0.209752 0.975582 + outer loop + vertex 631.524 157.34 359.539 + vertex 631.365 162.542 360.668 + vertex 622.886 154.444 359.493 + endloop + endfacet + facet normal 0.0670952 -0.211715 0.975026 + outer loop + vertex 622.886 154.444 359.493 + vertex 631.365 162.542 360.668 + vertex 622.764 159.646 360.631 + endloop + endfacet + facet normal 0.0656781 -0.211767 0.975111 + outer loop + vertex 622.886 154.444 359.493 + vertex 622.764 159.646 360.631 + vertex 614.774 151.88 359.483 + endloop + endfacet + facet normal 0.0671949 -0.213264 0.974681 + outer loop + vertex 614.774 151.88 359.483 + vertex 622.764 159.646 360.631 + vertex 614.645 157.091 360.632 + endloop + endfacet + facet normal 0.0711486 -0.213112 0.974434 + outer loop + vertex 614.774 151.88 359.483 + vertex 614.645 157.091 360.632 + vertex 607.257 149.943 359.608 + endloop + endfacet + facet normal 0.0665965 -0.208593 0.975732 + outer loop + vertex 607.257 149.943 359.608 + vertex 614.645 157.091 360.632 + vertex 607.21 155.217 360.739 + endloop + endfacet + facet normal 0.0765512 -0.208358 0.975052 + outer loop + vertex 607.257 149.943 359.608 + vertex 607.21 155.217 360.739 + vertex 599.939 148.799 359.938 + endloop + endfacet + facet normal 0.0617279 -0.192113 0.97943 + outer loop + vertex 599.939 148.799 359.938 + vertex 607.21 155.217 360.739 + vertex 600.49 154.188 360.96 + endloop + endfacet + facet normal 0.0756622 -0.193307 0.978216 + outer loop + vertex 599.939 148.799 359.938 + vertex 600.49 154.188 360.96 + vertex 595.103 149.696 360.49 + endloop + endfacet + facet normal 0.0781929 -0.174428 0.98156 + outer loop + vertex 686.602 184.455 361.083 + vertex 687.348 181.14 360.435 + vertex 690.801 185.424 360.921 + endloop + endfacet + facet normal 0.0552081 -0.155497 0.986292 + outer loop + vertex 682.002 180.046 360.582 + vertex 682.568 185.421 361.398 + vertex 674.618 177.954 360.665 + endloop + endfacet + facet normal 0.0490228 -0.149041 0.987615 + outer loop + vertex 674.618 177.954 360.665 + vertex 682.568 185.421 361.398 + vertex 674.506 183.116 361.45 + endloop + endfacet + facet normal 0.0552192 -0.148861 0.987315 + outer loop + vertex 674.618 177.954 360.665 + vertex 674.506 183.116 361.45 + vertex 666.015 174.895 360.685 + endloop + endfacet + facet normal 0.0525309 -0.146136 0.987869 + outer loop + vertex 666.015 174.895 360.685 + vertex 674.506 183.116 361.45 + vertex 665.927 180.141 361.466 + endloop + endfacet + facet normal 0.0542917 -0.146093 0.98778 + outer loop + vertex 666.015 174.895 360.685 + vertex 665.927 180.141 361.466 + vertex 657.264 171.629 360.683 + endloop + endfacet + facet normal 0.0557212 -0.147521 0.987488 + outer loop + vertex 657.264 171.629 360.683 + vertex 665.927 180.141 361.466 + vertex 657.154 176.894 361.476 + endloop + endfacet + facet normal 0.0548058 -0.147547 0.987535 + outer loop + vertex 657.264 171.629 360.683 + vertex 657.154 176.894 361.476 + vertex 648.651 168.494 360.693 + endloop + endfacet + facet normal 0.053713 -0.146462 0.987757 + outer loop + vertex 648.651 168.494 360.693 + vertex 657.154 176.894 361.476 + vertex 648.516 173.748 361.479 + endloop + endfacet + facet normal 0.0507047 -0.146561 0.987901 + outer loop + vertex 648.651 168.494 360.693 + vertex 648.516 173.748 361.479 + vertex 640.059 165.503 360.69 + endloop + endfacet + facet normal 0.0517837 -0.147647 0.987684 + outer loop + vertex 640.059 165.503 360.69 + vertex 648.516 173.748 361.479 + vertex 639.906 170.739 361.481 + endloop + endfacet + facet normal 0.0478457 -0.147789 0.987861 + outer loop + vertex 640.059 165.503 360.69 + vertex 639.906 170.739 361.481 + vertex 631.365 162.542 360.668 + endloop + endfacet + facet normal 0.0481658 -0.148116 0.987796 + outer loop + vertex 631.365 162.542 360.668 + vertex 639.906 170.739 361.481 + vertex 631.209 167.761 361.458 + endloop + endfacet + facet normal 0.0456555 -0.148207 0.987902 + outer loop + vertex 631.365 162.542 360.668 + vertex 631.209 167.761 361.458 + vertex 622.764 159.646 360.631 + endloop + endfacet + facet normal 0.0472226 -0.149806 0.987587 + outer loop + vertex 622.764 159.646 360.631 + vertex 631.209 167.761 361.458 + vertex 622.599 164.846 361.428 + endloop + endfacet + facet normal 0.0472221 -0.149806 0.987587 + outer loop + vertex 622.764 159.646 360.631 + vertex 622.599 164.846 361.428 + vertex 614.645 157.091 360.632 + endloop + endfacet + facet normal 0.0471996 -0.149783 0.987592 + outer loop + vertex 614.645 157.091 360.632 + vertex 622.599 164.846 361.428 + vertex 614.461 162.272 361.427 + endloop + endfacet + facet normal 0.0518945 -0.149584 0.987386 + outer loop + vertex 614.645 157.091 360.632 + vertex 614.461 162.272 361.427 + vertex 607.21 155.217 360.739 + endloop + endfacet + facet normal 0.0473054 -0.144958 0.988306 + outer loop + vertex 607.21 155.217 360.739 + vertex 614.461 162.272 361.427 + vertex 606.963 160.327 361.5 + endloop + endfacet + facet normal 0.0547224 -0.144551 0.987983 + outer loop + vertex 607.21 155.217 360.739 + vertex 606.963 160.327 361.5 + vertex 600.49 154.188 360.96 + endloop + endfacet + facet normal 0.0447542 -0.134213 0.989941 + outer loop + vertex 600.49 154.188 360.96 + vertex 606.963 160.327 361.5 + vertex 599.375 158.805 361.637 + endloop + endfacet + facet normal 0.0713399 -0.143822 0.987029 + outer loop + vertex 688.013 187.814 361.471 + vertex 686.602 184.455 361.083 + vertex 690.801 185.424 360.921 + endloop + endfacet + facet normal 0.0763359 -0.138094 0.987473 + outer loop + vertex 690.801 185.424 360.921 + vertex 691.201 190.57 361.61 + vertex 688.013 187.814 361.471 + endloop + endfacet + facet normal 0.0446519 -0.101758 0.993807 + outer loop + vertex 687.156 191.099 361.846 + vertex 688.013 187.814 361.471 + vertex 691.201 190.57 361.61 + endloop + endfacet + facet normal 0.0360409 -0.103478 0.993979 + outer loop + vertex 682.568 185.421 361.398 + vertex 681.788 190.177 361.921 + vertex 674.506 183.116 361.45 + endloop + endfacet + facet normal 0.0310359 -0.0983617 0.994667 + outer loop + vertex 674.506 183.116 361.45 + vertex 681.788 190.177 361.921 + vertex 674.543 188.376 361.969 + endloop + endfacet + facet normal 0.0227065 -0.064767 0.997642 + outer loop + vertex 681.788 190.177 361.921 + vertex 682.744 195.824 362.266 + vertex 674.543 188.376 361.969 + endloop + endfacet + facet normal 0.0125645 -0.063068 0.99793 + outer loop + vertex 682.744 195.824 362.266 + vertex 681.788 190.177 361.921 + vertex 686.513 194.574 362.139 + endloop + endfacet + facet normal 0.0161004 -0.052462 0.998493 + outer loop + vertex 686.513 194.574 362.139 + vertex 688.059 198.006 362.295 + vertex 682.744 195.824 362.266 + endloop + endfacet + facet normal 0.010256 -0.0382339 0.999216 + outer loop + vertex 688.059 198.006 362.295 + vertex 687.517 201.339 362.428 + vertex 682.744 195.824 362.266 + endloop + endfacet + facet normal 0.008018 -0.0362999 0.999309 + outer loop + vertex 682.789 201.45 362.47 + vertex 682.744 195.824 362.266 + vertex 687.517 201.339 362.428 + endloop + endfacet + facet normal 0.0163898 -0.0372337 0.999172 + outer loop + vertex 687.517 201.339 362.428 + vertex 688.059 198.006 362.295 + vertex 691.16 200.85 362.35 + endloop + endfacet + facet normal 0.0130136 -0.0269162 0.999553 + outer loop + vertex 694.093 208.553 362.538 + vertex 690.551 205.425 362.5 + vertex 694.842 204.38 362.416 + endloop + endfacet + facet normal 0.00822571 -0.0275623 0.999586 + outer loop + vertex 687.517 201.339 362.428 + vertex 687.472 204.181 362.507 + vertex 682.789 201.45 362.47 + endloop + endfacet + facet normal 0.00375295 -0.0198968 0.999795 + outer loop + vertex 687.472 204.181 362.507 + vertex 687.169 206.846 362.561 + vertex 682.789 201.45 362.47 + endloop + endfacet + facet normal 0.0152287 -0.0294233 0.999451 + outer loop + vertex 694.093 208.553 362.538 + vertex 691.076 210.472 362.64 + vertex 690.551 205.425 362.5 + endloop + endfacet + facet normal 0.0434752 -0.0904397 0.994953 + outer loop + vertex 695.822 213.672 362.724 + vertex 692.078 216.553 363.149 + vertex 691.076 210.472 362.64 + endloop + endfacet + facet normal 0.0172465 -0.0444838 0.998861 + outer loop + vertex 687.169 206.846 362.561 + vertex 687.586 211.573 362.764 + vertex 681.894 206.286 362.627 + endloop + endfacet + facet normal 0.0156696 -0.0295621 0.99944 + outer loop + vertex 681.894 206.286 362.627 + vertex 682.789 201.45 362.47 + vertex 687.169 206.846 362.561 + endloop + endfacet + facet normal 0.0125732 -0.0363351 0.999261 + outer loop + vertex 682.744 195.824 362.266 + vertex 682.789 201.45 362.47 + vertex 674.747 193.78 362.292 + endloop + endfacet + facet normal 0.018716 -0.0603873 0.998 + outer loop + vertex 674.543 188.376 361.969 + vertex 682.744 195.824 362.266 + vertex 674.747 193.78 362.292 + endloop + endfacet + facet normal 0.0359841 -0.09838 0.994498 + outer loop + vertex 674.506 183.116 361.45 + vertex 674.543 188.376 361.969 + vertex 665.927 180.141 361.466 + endloop + endfacet + facet normal 0.0230982 -0.0597708 0.997945 + outer loop + vertex 665.949 185.447 361.985 + vertex 666.029 190.761 362.301 + vertex 657.134 182.184 361.994 + endloop + endfacet + facet normal 0.013289 -0.0355519 0.999279 + outer loop + vertex 666.029 190.761 362.301 + vertex 674.662 199.043 362.481 + vertex 666.116 196.059 362.489 + endloop + endfacet + facet normal 0.0141496 -0.0380167 0.999177 + outer loop + vertex 674.662 199.043 362.481 + vertex 674.608 204.38 362.685 + vertex 666.116 196.059 362.489 + endloop + endfacet + facet normal 0.033279 -0.0865186 0.995694 + outer loop + vertex 674.608 204.38 362.685 + vertex 683.148 213.008 363.149 + vertex 674.734 209.772 363.149 + endloop + endfacet + facet normal 0.0139603 -0.0375493 0.999197 + outer loop + vertex 657.338 192.822 362.493 + vertex 666.206 201.359 362.69 + vertex 657.523 198.174 362.691 + endloop + endfacet + facet normal 0.0134217 -0.0350605 0.999295 + outer loop + vertex 657.205 187.494 362.308 + vertex 657.338 192.822 362.493 + vertex 648.469 184.325 362.314 + endloop + endfacet + facet normal 0.0223809 -0.0597575 0.997962 + outer loop + vertex 648.458 179.025 361.997 + vertex 657.205 187.494 362.308 + vertex 648.469 184.325 362.314 + endloop + endfacet + facet normal 0.034132 -0.0971332 0.994686 + outer loop + vertex 648.516 173.748 361.479 + vertex 648.458 179.025 361.997 + vertex 639.906 170.739 361.481 + endloop + endfacet + facet normal 0.0184047 -0.061257 0.997952 + outer loop + vertex 622.454 170.049 361.953 + vertex 630.962 178.234 362.299 + vertex 622.39 175.315 362.278 + endloop + endfacet + facet normal 0.0185142 -0.0592734 0.99807 + outer loop + vertex 639.802 175.995 361.998 + vertex 639.733 181.268 362.312 + vertex 631.069 172.986 361.981 + endloop + endfacet + facet normal 0.0122198 -0.0349784 0.999313 + outer loop + vertex 639.733 181.268 362.312 + vertex 648.525 189.651 362.498 + vertex 639.699 186.566 362.498 + endloop + endfacet + facet normal 0.0130573 -0.0373749 0.999216 + outer loop + vertex 648.525 189.651 362.498 + vertex 648.766 195.049 362.697 + vertex 639.699 186.566 362.498 + endloop + endfacet + facet normal 0.0300849 -0.0851075 0.995917 + outer loop + vertex 648.766 195.049 362.697 + vertex 658.261 203.703 363.149 + vertex 649.819 200.719 363.149 + endloop + endfacet + facet normal 0.0118198 -0.0371369 0.99924 + outer loop + vertex 630.934 183.542 362.488 + vertex 639.933 191.976 362.695 + vertex 631.235 189.024 362.688 + endloop + endfacet + facet normal 0.00962325 -0.0354789 0.999324 + outer loop + vertex 630.962 178.234 362.299 + vertex 630.934 183.542 362.488 + vertex 622.39 175.315 362.278 + endloop + endfacet + facet normal 0.0190861 -0.0612479 0.99794 + outer loop + vertex 622.454 170.049 361.953 + vertex 622.39 175.315 362.278 + vertex 614.329 167.462 361.95 + endloop + endfacet + facet normal 0.0355467 -0.0994074 0.994412 + outer loop + vertex 614.461 162.272 361.427 + vertex 614.329 167.462 361.95 + vertex 606.963 160.327 361.5 + endloop + endfacet + facet normal 0.0185356 -0.0569362 0.998206 + outer loop + vertex 606.881 165.532 361.995 + vertex 614.338 172.797 362.271 + vertex 606.906 170.875 362.299 + endloop + endfacet + facet normal 0.0105991 -0.0288375 0.999528 + outer loop + vertex 599.418 169.274 362.36 + vertex 606.558 176.113 362.482 + vertex 599.456 174.699 362.516 + endloop + endfacet + facet normal 0.0153205 -0.0288686 0.999466 + outer loop + vertex 599.418 169.274 362.36 + vertex 599.456 174.699 362.516 + vertex 594.323 169.612 362.448 + endloop + endfacet + facet normal 0.0115617 -0.0336729 0.999366 + outer loop + vertex 606.558 176.113 362.482 + vertex 605.402 180.124 362.63 + vertex 599.456 174.699 362.516 + endloop + endfacet + facet normal 0.0130547 -0.0357317 0.999276 + outer loop + vertex 614.338 172.797 362.271 + vertex 614.26 178.283 362.468 + vertex 606.906 170.875 362.299 + endloop + endfacet + facet normal 0.0107623 -0.0377268 0.99923 + outer loop + vertex 622.434 180.715 362.472 + vertex 622.67 186.31 362.68 + vertex 614.26 178.283 362.468 + endloop + endfacet + facet normal 0.0288153 -0.088026 0.995701 + outer loop + vertex 622.67 186.31 362.68 + vertex 632.327 194.776 363.149 + vertex 623.718 191.957 363.149 + endloop + endfacet + facet normal 0.00665574 -0.0350859 0.999362 + outer loop + vertex 606.558 176.113 362.482 + vertex 613.381 183.971 362.712 + vertex 605.402 180.124 362.63 + endloop + endfacet + facet normal 0.0087271 -0.0305688 0.999495 + outer loop + vertex 599.456 174.699 362.516 + vertex 605.402 180.124 362.63 + vertex 600.577 179.448 362.651 + endloop + endfacet + facet normal 0.00577161 -0.0298723 0.999537 + outer loop + vertex 599.456 174.699 362.516 + vertex 600.577 179.448 362.651 + vertex 595.203 175.833 362.574 + endloop + endfacet + facet normal 0.0204223 -0.0698073 0.997351 + outer loop + vertex 586.319 172.554 362.602 + vertex 585.973 180.276 363.149 + vertex 573.765 169.979 362.679 + endloop + endfacet + facet normal 0.0141795 -0.0393163 0.999126 + outer loop + vertex 573.917 163.266 362.412 + vertex 586.319 172.554 362.602 + vertex 573.765 169.979 362.679 + endloop + endfacet + facet normal 0.0121759 -0.0393627 0.999151 + outer loop + vertex 573.917 163.266 362.412 + vertex 573.765 169.979 362.679 + vertex 561.348 160.088 362.44 + endloop + endfacet + facet normal 0.0157757 -0.0536045 0.998438 + outer loop + vertex 561.442 153.545 362.088 + vertex 573.917 163.266 362.412 + vertex 561.348 160.088 362.44 + endloop + endfacet + facet normal 0.0163251 -0.0535962 0.998429 + outer loop + vertex 561.442 153.545 362.088 + vertex 561.348 160.088 362.44 + vertex 548.905 150.09 362.107 + endloop + endfacet + facet normal 0.0284184 -0.0975003 0.99483 + outer loop + vertex 549.03 143.613 361.469 + vertex 561.442 153.545 362.088 + vertex 548.905 150.09 362.107 + endloop + endfacet + facet normal 0.0284512 -0.0974996 0.994829 + outer loop + vertex 549.03 143.613 361.469 + vertex 548.905 150.09 362.107 + vertex 536.717 140.141 361.481 + endloop + endfacet + facet normal 0.0276989 -0.0965849 0.994939 + outer loop + vertex 536.717 140.141 361.481 + vertex 548.905 150.09 362.107 + vertex 536.615 146.639 362.114 + endloop + endfacet + facet normal 0.0266265 -0.0966043 0.994967 + outer loop + vertex 536.717 140.141 361.481 + vertex 536.615 146.639 362.114 + vertex 524.673 136.796 361.478 + endloop + endfacet + facet normal 0.0257371 -0.0955335 0.995093 + outer loop + vertex 524.673 136.796 361.478 + vertex 536.615 146.639 362.114 + vertex 524.638 143.307 362.104 + endloop + endfacet + facet normal 0.0251135 -0.0955384 0.995109 + outer loop + vertex 524.673 136.796 361.478 + vertex 524.638 143.307 362.104 + vertex 512.856 133.579 361.467 + endloop + endfacet + facet normal 0.023456 -0.0935463 0.995339 + outer loop + vertex 512.856 133.579 361.467 + vertex 524.638 143.307 362.104 + vertex 512.869 140.088 362.079 + endloop + endfacet + facet normal 0.0252739 -0.0935455 0.995294 + outer loop + vertex 512.856 133.579 361.467 + vertex 512.869 140.088 362.079 + vertex 501.046 130.527 361.481 + endloop + endfacet + facet normal 0.0226232 -0.0902906 0.995658 + outer loop + vertex 501.046 130.527 361.481 + vertex 512.869 140.088 362.079 + vertex 500.965 137.043 362.073 + endloop + endfacet + facet normal 0.0284804 -0.0902048 0.995516 + outer loop + vertex 501.046 130.527 361.481 + vertex 500.965 137.043 362.073 + vertex 488.816 127.816 361.585 + endloop + endfacet + facet normal 0.0246625 -0.0852068 0.996058 + outer loop + vertex 488.816 127.816 361.585 + vertex 500.965 137.043 362.073 + vertex 488.428 134.334 362.152 + endloop + endfacet + facet normal 0.035451 -0.0845421 0.995789 + outer loop + vertex 488.816 127.816 361.585 + vertex 488.428 134.334 362.152 + vertex 475.915 125.634 361.859 + endloop + endfacet + facet normal 0.0168629 -0.0490453 0.998654 + outer loop + vertex 500.965 137.043 362.073 + vertex 500.718 143.659 362.402 + vertex 488.428 134.334 362.152 + endloop + endfacet + facet normal 0.0155084 -0.0472632 0.998762 + outer loop + vertex 488.428 134.334 362.152 + vertex 500.718 143.659 362.402 + vertex 487.925 140.961 362.473 + endloop + endfacet + facet normal 0.025299 -0.0465117 0.998597 + outer loop + vertex 488.428 134.334 362.152 + vertex 487.925 140.961 362.473 + vertex 474.843 131.986 362.387 + endloop + endfacet + facet normal 0.0214736 -0.0409391 0.998931 + outer loop + vertex 474.843 131.986 362.387 + vertex 487.925 140.961 362.473 + vertex 474.704 138.77 362.668 + endloop + endfacet + facet normal 0.0354452 -0.0406373 0.998545 + outer loop + vertex 474.843 131.986 362.387 + vertex 474.704 138.77 362.668 + vertex 466.85 132.262 362.682 + endloop + endfacet + facet normal 0.0209837 -0.0379711 0.999058 + outer loop + vertex 487.925 140.961 362.473 + vertex 487.855 147.642 362.729 + vertex 474.704 138.77 362.668 + endloop + endfacet + facet normal 0.0176325 -0.0330051 0.9993 + outer loop + vertex 474.704 138.77 362.668 + vertex 487.855 147.642 362.729 + vertex 474.861 145.358 362.883 + endloop + endfacet + facet normal 0.0277674 -0.0332382 0.999062 + outer loop + vertex 474.704 138.77 362.668 + vertex 474.861 145.358 362.883 + vertex 466.073 138.915 362.913 + endloop + endfacet + facet normal 0.0243972 -0.0716379 0.997132 + outer loop + vertex 487.855 147.642 362.729 + vertex 488.898 154.106 363.168 + vertex 474.861 145.358 362.883 + endloop + endfacet + facet normal 0.0259122 -0.0740619 0.996917 + outer loop + vertex 474.861 145.358 362.883 + vertex 488.898 154.106 363.168 + vertex 477.745 151.58 363.27 + endloop + endfacet + facet normal 0.0241292 -0.073242 0.997022 + outer loop + vertex 474.861 145.358 362.883 + vertex 477.745 151.58 363.27 + vertex 466.477 145.592 363.103 + endloop + endfacet + facet normal 0.0188871 -0.0707614 0.997314 + outer loop + vertex 487.855 147.642 362.729 + vertex 501.811 157.295 363.149 + vertex 488.898 154.106 363.168 + endloop + endfacet + facet normal 0.0206898 -0.0733578 0.997091 + outer loop + vertex 500.568 150.363 362.665 + vertex 501.811 157.295 363.149 + vertex 487.855 147.642 362.729 + endloop + endfacet + facet normal 0.0185902 -0.0729861 0.99716 + outer loop + vertex 500.568 150.363 362.665 + vertex 513.11 160.173 363.149 + vertex 501.811 157.295 363.149 + endloop + endfacet + facet normal 0.0180606 -0.072312 0.997219 + outer loop + vertex 512.844 153.356 362.66 + vertex 513.11 160.173 363.149 + vertex 500.568 150.363 362.665 + endloop + endfacet + facet normal 0.00992361 -0.0389414 0.999192 + outer loop + vertex 500.718 143.659 362.402 + vertex 512.844 153.356 362.66 + vertex 500.568 150.363 362.665 + endloop + endfacet + facet normal 0.00848162 -0.0371404 0.999274 + outer loop + vertex 512.865 146.687 362.412 + vertex 512.844 153.356 362.66 + vertex 500.718 143.659 362.402 + endloop + endfacet + facet normal 0.00797823 -0.0371421 0.999278 + outer loop + vertex 512.865 146.687 362.412 + vertex 524.907 156.547 362.682 + vertex 512.844 153.356 362.66 + endloop + endfacet + facet normal 0.0165533 -0.0695502 0.997441 + outer loop + vertex 524.907 156.547 362.682 + vertex 525.318 163.345 363.149 + vertex 512.844 153.356 362.66 + endloop + endfacet + facet normal 0.0185058 -0.0696653 0.997399 + outer loop + vertex 524.907 156.547 362.682 + vertex 537.373 166.548 363.149 + vertex 525.318 163.345 363.149 + endloop + endfacet + facet normal 0.0171764 -0.0680145 0.997536 + outer loop + vertex 536.988 159.853 362.7 + vertex 537.373 166.548 363.149 + vertex 524.907 156.547 362.682 + endloop + endfacet + facet normal 0.00851744 -0.0363822 0.999302 + outer loop + vertex 524.716 149.897 362.442 + vertex 536.988 159.853 362.7 + vertex 524.907 156.547 362.682 + endloop + endfacet + facet normal 0.00900908 -0.0369876 0.999275 + outer loop + vertex 536.663 153.215 362.457 + vertex 536.988 159.853 362.7 + vertex 524.716 149.897 362.442 + endloop + endfacet + facet normal 0.0129862 -0.0513047 0.998599 + outer loop + vertex 524.638 143.307 362.104 + vertex 536.663 153.215 362.457 + vertex 524.716 149.897 362.442 + endloop + endfacet + facet normal 0.0101867 -0.0370446 0.999262 + outer loop + vertex 536.663 153.215 362.457 + vertex 549.202 163.248 362.701 + vertex 536.988 159.853 362.7 + endloop + endfacet + facet normal 0.0189762 -0.0686664 0.997459 + outer loop + vertex 549.202 163.248 362.701 + vertex 550.186 170.035 363.149 + vertex 536.988 159.853 362.7 + endloop + endfacet + facet normal 0.0191793 -0.0686955 0.997453 + outer loop + vertex 549.202 163.248 362.701 + vertex 562.366 173.435 363.149 + vertex 550.186 170.035 363.149 + endloop + endfacet + facet normal 0.0202204 -0.0700358 0.99734 + outer loop + vertex 561.407 166.664 362.693 + vertex 562.366 173.435 363.149 + vertex 549.202 163.248 362.701 + endloop + endfacet + facet normal 0.0112393 -0.037943 0.999217 + outer loop + vertex 548.878 156.635 362.453 + vertex 561.407 166.664 362.693 + vertex 549.202 163.248 362.701 + endloop + endfacet + facet normal 0.0117258 -0.0385501 0.999188 + outer loop + vertex 561.348 160.088 362.44 + vertex 561.407 166.664 362.693 + vertex 548.878 156.635 362.453 + endloop + endfacet + facet normal 0.020023 -0.0700083 0.997345 + outer loop + vertex 561.407 166.664 362.693 + vertex 573.466 176.61 363.149 + vertex 562.366 173.435 363.149 + endloop + endfacet + facet normal 0.0199367 -0.069904 0.997354 + outer loop + vertex 573.765 169.979 362.679 + vertex 573.466 176.61 363.149 + vertex 561.407 166.664 362.693 + endloop + endfacet + facet normal 0.0108929 -0.0379262 0.999221 + outer loop + vertex 548.878 156.635 362.453 + vertex 549.202 163.248 362.701 + vertex 536.663 153.215 362.457 + endloop + endfacet + facet normal 0.014867 -0.0521215 0.99853 + outer loop + vertex 536.615 146.639 362.114 + vertex 548.878 156.635 362.453 + vertex 536.663 153.215 362.457 + endloop + endfacet + facet normal 0.0185303 -0.0680905 0.997507 + outer loop + vertex 536.988 159.853 362.7 + vertex 550.186 170.035 363.149 + vertex 537.373 166.548 363.149 + endloop + endfacet + facet normal 0.00732764 -0.0363484 0.999312 + outer loop + vertex 524.716 149.897 362.442 + vertex 524.907 156.547 362.682 + vertex 512.865 146.687 362.412 + endloop + endfacet + facet normal 0.0111267 -0.0503697 0.998669 + outer loop + vertex 512.869 140.088 362.079 + vertex 524.716 149.897 362.442 + vertex 512.865 146.687 362.412 + endloop + endfacet + facet normal 0.0187965 -0.0723396 0.997203 + outer loop + vertex 512.844 153.356 362.66 + vertex 525.318 163.345 363.149 + vertex 513.11 160.173 363.149 + endloop + endfacet + facet normal 0.0131448 -0.0380589 0.999189 + outer loop + vertex 487.925 140.961 362.473 + vertex 500.568 150.363 362.665 + vertex 487.855 147.642 362.729 + endloop + endfacet + facet normal 0.013737 -0.0388545 0.99915 + outer loop + vertex 500.718 143.659 362.402 + vertex 500.568 150.363 362.665 + vertex 487.925 140.961 362.473 + endloop + endfacet + facet normal 0.0115009 -0.0492488 0.99872 + outer loop + vertex 500.965 137.043 362.073 + vertex 512.865 146.687 362.412 + vertex 500.718 143.659 362.402 + endloop + endfacet + facet normal 0.01241 -0.0503682 0.998654 + outer loop + vertex 512.869 140.088 362.079 + vertex 512.865 146.687 362.412 + vertex 500.965 137.043 362.073 + endloop + endfacet + facet normal 0.0118925 -0.0512925 0.998613 + outer loop + vertex 524.638 143.307 362.104 + vertex 524.716 149.897 362.442 + vertex 512.869 140.088 362.079 + endloop + endfacet + facet normal 0.0136541 -0.0521136 0.998548 + outer loop + vertex 536.615 146.639 362.114 + vertex 536.663 153.215 362.457 + vertex 524.638 143.307 362.104 + endloop + endfacet + facet normal 0.0154019 -0.0527763 0.998488 + outer loop + vertex 548.905 150.09 362.107 + vertex 548.878 156.635 362.453 + vertex 536.615 146.639 362.114 + endloop + endfacet + facet normal 0.0287256 -0.0978814 0.994783 + outer loop + vertex 561.558 147.075 361.448 + vertex 561.442 153.545 362.088 + vertex 549.03 143.613 361.469 + endloop + endfacet + facet normal 0.0275871 -0.0979048 0.994813 + outer loop + vertex 561.558 147.075 361.448 + vertex 573.968 156.687 362.049 + vertex 561.442 153.545 362.088 + endloop + endfacet + facet normal 0.0292061 -0.0999796 0.994561 + outer loop + vertex 574.095 150.206 361.394 + vertex 573.968 156.687 362.049 + vertex 561.558 147.075 361.448 + endloop + endfacet + facet normal 0.0247967 -0.100077 0.994671 + outer loop + vertex 574.095 150.206 361.394 + vertex 586.05 159.246 362.006 + vertex 573.968 156.687 362.049 + endloop + endfacet + facet normal 0.0156638 -0.052775 0.998484 + outer loop + vertex 548.905 150.09 362.107 + vertex 561.348 160.088 362.44 + vertex 548.878 156.635 362.453 + endloop + endfacet + facet normal 0.0168219 -0.0549441 0.998348 + outer loop + vertex 573.968 156.687 362.049 + vertex 573.917 163.266 362.412 + vertex 561.442 153.545 362.088 + endloop + endfacet + facet normal 0.0139481 -0.0549689 0.998391 + outer loop + vertex 573.968 156.687 362.049 + vertex 585.941 165.764 362.382 + vertex 573.917 163.266 362.412 + endloop + endfacet + facet normal 0.0115265 -0.0385484 0.99919 + outer loop + vertex 561.348 160.088 362.44 + vertex 573.765 169.979 362.679 + vertex 561.407 166.664 362.693 + endloop + endfacet + facet normal 0.0204827 -0.0698787 0.997345 + outer loop + vertex 573.765 169.979 362.679 + vertex 585.973 180.276 363.149 + vertex 573.466 176.61 363.149 + endloop + endfacet + facet normal 0.0185698 -0.0488796 0.998632 + outer loop + vertex 595.436 179.782 362.763 + vertex 595.203 175.833 362.574 + vertex 600.577 179.448 362.651 + endloop + endfacet + facet normal 0.00830795 -0.0203796 0.999758 + outer loop + vertex 595.203 175.833 362.574 + vertex 592.609 171.889 362.516 + vertex 599.456 174.699 362.516 + endloop + endfacet + facet normal 0.00936612 -0.0328952 0.999415 + outer loop + vertex 585.941 165.764 362.382 + vertex 586.319 172.554 362.602 + vertex 573.917 163.266 362.412 + endloop + endfacet + facet normal 0.00929898 -0.0227951 0.999697 + outer loop + vertex 592.609 171.889 362.516 + vertex 594.323 169.612 362.448 + vertex 599.456 174.699 362.516 + endloop + endfacet + facet normal 0.0146474 -0.0389396 0.999134 + outer loop + vertex 594.323 169.612 362.448 + vertex 592.369 165.633 362.321 + vertex 599.418 169.274 362.36 + endloop + endfacet + facet normal 0.0157579 -0.0573501 0.99823 + outer loop + vertex 586.05 159.246 362.006 + vertex 585.941 165.764 362.382 + vertex 573.968 156.687 362.049 + endloop + endfacet + facet normal 0.0194235 -0.0481805 0.99865 + outer loop + vertex 592.369 165.633 362.321 + vertex 594.558 163.589 362.18 + vertex 599.418 169.274 362.36 + endloop + endfacet + facet normal 0.0265315 -0.0772545 0.996658 + outer loop + vertex 594.558 163.589 362.18 + vertex 593.498 159.13 361.863 + vertex 600.195 164.422 362.095 + endloop + endfacet + facet normal 0.0274138 -0.103509 0.994251 + outer loop + vertex 586.195 152.661 361.316 + vertex 586.05 159.246 362.006 + vertex 574.095 150.206 361.394 + endloop + endfacet + facet normal 0.0329819 -0.0950758 0.994924 + outer loop + vertex 593.498 159.13 361.863 + vertex 593.417 155.912 361.558 + vertex 599.375 158.805 361.637 + endloop + endfacet + facet normal 0.0561797 -0.142655 0.988177 + outer loop + vertex 593.417 155.912 361.558 + vertex 593.762 152.965 361.113 + vertex 599.375 158.805 361.637 + endloop + endfacet + facet normal 0.0451502 -0.167192 0.98489 + outer loop + vertex 586.497 146.415 360.242 + vertex 586.195 152.661 361.316 + vertex 574.266 143.991 360.391 + endloop + endfacet + facet normal 0.0384554 -0.15817 0.986663 + outer loop + vertex 574.266 143.991 360.391 + vertex 586.195 152.661 361.316 + vertex 574.095 150.206 361.394 + endloop + endfacet + facet normal 0.0452422 -0.157942 0.986411 + outer loop + vertex 574.266 143.991 360.391 + vertex 574.095 150.206 361.394 + vertex 561.66 140.854 360.467 + endloop + endfacet + facet normal 0.0428761 -0.154855 0.987006 + outer loop + vertex 561.66 140.854 360.467 + vertex 574.095 150.206 361.394 + vertex 561.558 147.075 361.448 + endloop + endfacet + facet normal 0.0455563 -0.154793 0.986896 + outer loop + vertex 561.66 140.854 360.467 + vertex 561.558 147.075 361.448 + vertex 549.107 137.365 360.499 + endloop + endfacet + facet normal 0.043847 -0.152642 0.987308 + outer loop + vertex 549.107 137.365 360.499 + vertex 561.558 147.075 361.448 + vertex 549.03 143.613 361.469 + endloop + endfacet + facet normal 0.0438223 -0.152642 0.987309 + outer loop + vertex 549.107 137.365 360.499 + vertex 549.03 143.613 361.469 + vertex 536.794 133.873 360.506 + endloop + endfacet + facet normal 0.0440854 -0.152967 0.987248 + outer loop + vertex 536.794 133.873 360.506 + vertex 549.03 143.613 361.469 + vertex 536.717 140.141 361.481 + endloop + endfacet + facet normal 0.0427696 -0.152991 0.987302 + outer loop + vertex 536.794 133.873 360.506 + vertex 536.717 140.141 361.481 + vertex 524.716 130.516 360.509 + endloop + endfacet + facet normal 0.0420393 -0.152098 0.987471 + outer loop + vertex 524.716 130.516 360.509 + vertex 536.717 140.141 361.481 + vertex 524.673 136.796 361.478 + endloop + endfacet + facet normal 0.0415473 -0.152104 0.987491 + outer loop + vertex 524.716 130.516 360.509 + vertex 524.673 136.796 361.478 + vertex 512.822 127.294 360.513 + endloop + endfacet + facet normal 0.0400089 -0.150221 0.987843 + outer loop + vertex 512.822 127.294 360.513 + vertex 524.673 136.796 361.478 + vertex 512.856 133.579 361.467 + endloop + endfacet + facet normal 0.0418049 -0.15022 0.987768 + outer loop + vertex 512.822 127.294 360.513 + vertex 512.856 133.579 361.467 + vertex 500.963 124.245 360.551 + endloop + endfacet + facet normal 0.0390041 -0.146713 0.98841 + outer loop + vertex 500.963 124.245 360.551 + vertex 512.856 133.579 361.467 + vertex 501.046 130.527 361.481 + endloop + endfacet + facet normal 0.0450988 -0.146755 0.988144 + outer loop + vertex 500.963 124.245 360.551 + vertex 501.046 130.527 361.481 + vertex 488.824 121.5 360.698 + endloop + endfacet + facet normal 0.0392311 -0.13893 0.989525 + outer loop + vertex 488.824 121.5 360.698 + vertex 501.046 130.527 361.481 + vertex 488.816 127.816 361.585 + endloop + endfacet + facet normal 0.0506708 -0.138845 0.989017 + outer loop + vertex 488.824 121.5 360.698 + vertex 488.816 127.816 361.585 + vertex 476.134 119.246 361.031 + endloop + endfacet + facet normal 0.0425131 -0.1269 0.991004 + outer loop + vertex 476.134 119.246 361.031 + vertex 488.816 127.816 361.585 + vertex 475.915 125.634 361.859 + endloop + endfacet + facet normal 0.0525167 -0.166225 0.984688 + outer loop + vertex 593.762 152.965 361.113 + vertex 595.103 149.696 360.49 + vertex 600.49 154.188 360.96 + endloop + endfacet + facet normal 0.07055 -0.2179 0.973418 + outer loop + vertex 595.103 149.696 360.49 + vertex 593.004 145.956 359.805 + vertex 599.939 148.799 359.938 + endloop + endfacet + facet normal 0.064462 -0.23382 0.970141 + outer loop + vertex 586.134 140.616 358.868 + vertex 586.497 146.415 360.242 + vertex 574.277 138.311 359.101 + endloop + endfacet + facet normal 0.0557009 -0.221106 0.973658 + outer loop + vertex 574.277 138.311 359.101 + vertex 586.497 146.415 360.242 + vertex 574.266 143.991 360.391 + endloop + endfacet + facet normal 0.0633474 -0.220991 0.973216 + outer loop + vertex 574.277 138.311 359.101 + vertex 574.266 143.991 360.391 + vertex 561.674 135.153 359.204 + endloop + endfacet + facet normal 0.0595676 -0.215794 0.97462 + outer loop + vertex 561.674 135.153 359.204 + vertex 574.266 143.991 360.391 + vertex 561.66 140.854 360.467 + endloop + endfacet + facet normal 0.0629257 -0.215742 0.974421 + outer loop + vertex 561.674 135.153 359.204 + vertex 561.66 140.854 360.467 + vertex 549.068 131.642 359.241 + endloop + endfacet + facet normal 0.0621918 -0.214773 0.974682 + outer loop + vertex 549.068 131.642 359.241 + vertex 561.66 140.854 360.467 + vertex 549.107 137.365 360.499 + endloop + endfacet + facet normal 0.062472 -0.214772 0.974664 + outer loop + vertex 549.068 131.642 359.241 + vertex 549.107 137.365 360.499 + vertex 536.74 128.124 359.256 + endloop + endfacet + facet normal 0.0608379 -0.212661 0.97523 + outer loop + vertex 536.74 128.124 359.256 + vertex 549.107 137.365 360.499 + vertex 536.794 133.873 360.506 + endloop + endfacet + facet normal 0.0598156 -0.212665 0.975293 + outer loop + vertex 536.74 128.124 359.256 + vertex 536.794 133.873 360.506 + vertex 524.664 124.776 359.266 + endloop + endfacet + facet normal 0.0590992 -0.211743 0.975537 + outer loop + vertex 524.664 124.776 359.266 + vertex 536.794 133.873 360.506 + vertex 524.716 130.516 360.509 + endloop + endfacet + facet normal 0.0587227 -0.211744 0.975559 + outer loop + vertex 524.664 124.776 359.266 + vertex 524.716 130.516 360.509 + vertex 512.727 121.552 359.285 + endloop + endfacet + facet normal 0.0571466 -0.209709 0.976092 + outer loop + vertex 512.727 121.552 359.285 + vertex 524.716 130.516 360.509 + vertex 512.822 127.294 360.513 + endloop + endfacet + facet normal 0.0586714 -0.209715 0.976001 + outer loop + vertex 512.727 121.552 359.285 + vertex 512.822 127.294 360.513 + vertex 500.792 118.491 359.345 + endloop + endfacet + facet normal 0.0562404 -0.206502 0.976828 + outer loop + vertex 500.792 118.491 359.345 + vertex 512.822 127.294 360.513 + vertex 500.963 124.245 360.551 + endloop + endfacet + facet normal 0.0622018 -0.206599 0.976447 + outer loop + vertex 500.792 118.491 359.345 + vertex 500.963 124.245 360.551 + vertex 488.614 115.66 359.522 + endloop + endfacet + facet normal 0.0568142 -0.199076 0.978336 + outer loop + vertex 488.614 115.66 359.522 + vertex 500.963 124.245 360.551 + vertex 488.824 121.5 360.698 + endloop + endfacet + facet normal 0.0668741 -0.199301 0.977654 + outer loop + vertex 488.614 115.66 359.522 + vertex 488.824 121.5 360.698 + vertex 475.944 113.268 359.901 + endloop + endfacet + facet normal 0.0590599 -0.187351 0.980516 + outer loop + vertex 475.944 113.268 359.901 + vertex 488.824 121.5 360.698 + vertex 476.134 119.246 361.031 + endloop + endfacet + facet normal 0.0743954 -0.18763 0.979418 + outer loop + vertex 475.944 113.268 359.901 + vertex 476.134 119.246 361.031 + vertex 462.816 111.402 360.54 + endloop + endfacet + facet normal 0.0807952 -0.242587 0.966759 + outer loop + vertex 593.004 145.956 359.805 + vertex 594.779 143.803 359.116 + vertex 599.939 148.799 359.938 + endloop + endfacet + facet normal 0.099864 -0.299498 0.948856 + outer loop + vertex 594.779 143.803 359.116 + vertex 592.151 140.123 358.231 + vertex 599.559 143.111 358.394 + endloop + endfacet + facet normal 0.0861294 -0.302632 0.949208 + outer loop + vertex 584.387 135.572 357.419 + vertex 586.134 140.616 358.868 + vertex 573.956 133.426 357.681 + endloop + endfacet + facet normal 0.0737088 -0.282773 0.956351 + outer loop + vertex 573.956 133.426 357.681 + vertex 586.134 140.616 358.868 + vertex 574.277 138.311 359.101 + endloop + endfacet + facet normal 0.0808213 -0.28305 0.955694 + outer loop + vertex 573.956 133.426 357.681 + vertex 574.277 138.311 359.101 + vertex 561.635 130.272 357.789 + endloop + endfacet + facet normal 0.0775468 -0.278178 0.957394 + outer loop + vertex 561.635 130.272 357.789 + vertex 574.277 138.311 359.101 + vertex 561.674 135.153 359.204 + endloop + endfacet + facet normal 0.0812009 -0.278123 0.957107 + outer loop + vertex 561.635 130.272 357.789 + vertex 561.674 135.153 359.204 + vertex 549.021 126.739 357.832 + endloop + endfacet + facet normal 0.0796311 -0.27589 0.957885 + outer loop + vertex 549.021 126.739 357.832 + vertex 561.674 135.153 359.204 + vertex 549.068 131.642 359.241 + endloop + endfacet + facet normal 0.0804368 -0.275879 0.957821 + outer loop + vertex 549.021 126.739 357.832 + vertex 549.068 131.642 359.241 + vertex 536.661 123.236 357.862 + endloop + endfacet + facet normal 0.0795202 -0.274599 0.958265 + outer loop + vertex 536.661 123.236 357.862 + vertex 549.068 131.642 359.241 + vertex 536.74 128.124 359.256 + endloop + endfacet + facet normal 0.078592 -0.274605 0.95834 + outer loop + vertex 536.661 123.236 357.862 + vertex 536.74 128.124 359.256 + vertex 524.603 119.92 357.9 + endloop + endfacet + facet normal 0.0759482 -0.270903 0.959606 + outer loop + vertex 524.603 119.92 357.9 + vertex 536.74 128.124 359.256 + vertex 524.664 124.776 359.266 + endloop + endfacet + facet normal 0.0762098 -0.270901 0.959586 + outer loop + vertex 524.603 119.92 357.9 + vertex 524.664 124.776 359.266 + vertex 512.719 116.76 357.952 + endloop + endfacet + facet normal 0.0737301 -0.267399 0.960761 + outer loop + vertex 512.719 116.76 357.952 + vertex 524.664 124.776 359.266 + vertex 512.727 121.552 359.285 + endloop + endfacet + facet normal 0.0757629 -0.267361 0.960614 + outer loop + vertex 512.719 116.76 357.952 + vertex 512.727 121.552 359.285 + vertex 500.791 113.677 358.035 + endloop + endfacet + facet normal 0.0720012 -0.261942 0.962394 + outer loop + vertex 500.791 113.677 358.035 + vertex 512.727 121.552 359.285 + vertex 500.792 118.491 359.345 + endloop + endfacet + facet normal 0.0770858 -0.261844 0.962027 + outer loop + vertex 500.791 113.677 358.035 + vertex 500.792 118.491 359.345 + vertex 488.566 110.76 358.22 + endloop + endfacet + facet normal 0.0736518 -0.256655 0.963693 + outer loop + vertex 488.566 110.76 358.22 + vertex 500.792 118.491 359.345 + vertex 488.614 115.66 359.522 + endloop + endfacet + facet normal 0.0813154 -0.256572 0.963098 + outer loop + vertex 488.566 110.76 358.22 + vertex 488.614 115.66 359.522 + vertex 475.765 108.119 358.597 + endloop + endfacet + facet normal 0.0755543 -0.247117 0.966036 + outer loop + vertex 475.765 108.119 358.597 + vertex 488.614 115.66 359.522 + vertex 475.944 113.268 359.901 + endloop + endfacet + facet normal 0.0870481 -0.247263 0.96503 + outer loop + vertex 475.765 108.119 358.597 + vertex 475.944 113.268 359.901 + vertex 462.479 105.871 359.22 + endloop + endfacet + facet normal 0.080744 -0.236094 0.96837 + outer loop + vertex 462.479 105.871 359.22 + vertex 475.944 113.268 359.901 + vertex 462.816 111.402 360.54 + endloop + endfacet + facet normal 0.0997407 -0.236786 0.966429 + outer loop + vertex 462.479 105.871 359.22 + vertex 462.816 111.402 360.54 + vertex 453.979 105.715 360.059 + endloop + endfacet + facet normal 0.115625 -0.337775 0.934098 + outer loop + vertex 592.151 140.123 358.231 + vertex 592.657 137.039 357.053 + vertex 599.559 143.111 358.394 + endloop + endfacet + facet normal 0.120964 -0.385145 0.914894 + outer loop + vertex 592.277 133.261 355.513 + vertex 592.657 137.039 357.053 + vertex 584.554 132.17 356.075 + endloop + endfacet + facet normal 0.123359 -0.38524 0.914534 + outer loop + vertex 592.657 137.039 357.053 + vertex 592.277 133.261 355.513 + vertex 599.968 137.659 356.328 + endloop + endfacet + facet normal 0.0995248 -0.266307 0.958736 + outer loop + vertex 452.552 102.605 359.343 + vertex 462.479 105.871 359.22 + vertex 453.979 105.715 360.059 + endloop + endfacet + facet normal 0.1021 -0.237032 0.966122 + outer loop + vertex 453.979 105.715 360.059 + vertex 453.033 108.206 360.77 + vertex 446.851 105.008 360.639 + endloop + endfacet + facet normal 0.0902733 -0.188613 0.977894 + outer loop + vertex 447.204 107.918 361.279 + vertex 454.516 111.572 361.309 + vertex 447.534 110.904 361.825 + endloop + endfacet + facet normal 0.100346 -0.237703 0.966141 + outer loop + vertex 453.033 108.206 360.77 + vertex 453.979 105.715 360.059 + vertex 462.816 111.402 360.54 + endloop + endfacet + facet normal 0.0642811 -0.170695 0.983225 + outer loop + vertex 462.816 111.402 360.54 + vertex 476.134 119.246 361.031 + vertex 463.046 117.543 361.591 + endloop + endfacet + facet normal 0.088214 -0.163463 0.982598 + outer loop + vertex 454.516 111.572 361.309 + vertex 453.517 114.258 361.846 + vertex 447.534 110.904 361.825 + endloop + endfacet + facet normal 0.058797 -0.126245 0.990255 + outer loop + vertex 476.134 119.246 361.031 + vertex 475.915 125.634 361.859 + vertex 463.046 117.543 361.591 + endloop + endfacet + facet normal 0.0306462 -0.0776553 0.996509 + outer loop + vertex 475.915 125.634 361.859 + vertex 488.428 134.334 362.152 + vertex 474.843 131.986 362.387 + endloop + endfacet + facet normal 0.0601993 -0.0658737 0.99601 + outer loop + vertex 460.606 127.957 362.742 + vertex 454.441 124.019 362.854 + vertex 462.967 124.177 362.35 + endloop + endfacet + facet normal 0.0351152 -0.0497598 0.998144 + outer loop + vertex 466.319 128.961 362.536 + vertex 474.843 131.986 362.387 + vertex 466.85 132.262 362.682 + endloop + endfacet + facet normal 0.0336761 -0.0385019 0.998691 + outer loop + vertex 465.194 135.152 362.849 + vertex 466.85 132.262 362.682 + vertex 474.704 138.77 362.668 + endloop + endfacet + facet normal 0.0279405 -0.023392 0.999336 + outer loop + vertex 465.194 135.152 362.849 + vertex 474.704 138.77 362.668 + vertex 466.073 138.915 362.913 + endloop + endfacet + facet normal 0.0193014 -0.0216878 0.999578 + outer loop + vertex 464.727 141.779 363.001 + vertex 466.073 138.915 362.913 + vertex 474.861 145.358 362.883 + endloop + endfacet + facet normal 0.0251569 -0.0382901 0.99895 + outer loop + vertex 464.727 141.779 363.001 + vertex 474.861 145.358 362.883 + vertex 466.477 145.592 363.103 + endloop + endfacet + facet normal 0.0472356 -0.116585 0.992057 + outer loop + vertex 465.446 149.263 363.583 + vertex 466.477 145.592 363.103 + vertex 477.745 151.58 363.27 + endloop + endfacet + facet normal 0.0610818 -0.0501832 0.99687 + outer loop + vertex 453.09 140.87 363.543 + vertex 459.162 144.846 363.371 + vertex 453.228 144.251 363.705 + endloop + endfacet + facet normal 0.0565224 -0.0181417 0.998236 + outer loop + vertex 453.16 137.561 363.479 + vertex 458.944 141.376 363.221 + vertex 453.09 140.87 363.543 + endloop + endfacet + facet normal 0.0551935 -0.0195124 0.998285 + outer loop + vertex 453.314 134.261 363.406 + vertex 459.015 138.073 363.165 + vertex 453.16 137.561 363.479 + endloop + endfacet + facet normal 0.0561099 -0.0320292 0.997911 + outer loop + vertex 453.527 130.912 363.286 + vertex 459.286 134.755 363.086 + vertex 453.314 134.261 363.406 + endloop + endfacet + facet normal 0.0569271 -0.0462704 0.997306 + outer loop + vertex 453.921 127.503 363.106 + vertex 459.739 131.374 362.953 + vertex 453.527 130.912 363.286 + endloop + endfacet + facet normal 0.0584459 -0.0631202 0.996293 + outer loop + vertex 453.921 127.503 363.106 + vertex 454.441 124.019 362.854 + vertex 460.606 127.957 362.742 + endloop + endfacet + facet normal 0.0604416 -0.083049 0.994711 + outer loop + vertex 453.584 120.649 362.625 + vertex 462.967 124.177 362.35 + vertex 454.441 124.019 362.854 + endloop + endfacet + facet normal 0.0706556 -0.110474 0.991364 + outer loop + vertex 453.584 120.649 362.625 + vertex 454.795 117.851 362.227 + vertex 462.967 124.177 362.35 + endloop + endfacet + facet normal 0.0833732 -0.134481 0.987403 + outer loop + vertex 453.517 114.258 361.846 + vertex 454.795 117.851 362.227 + vertex 447.809 114.004 362.293 + endloop + endfacet + facet normal 0.0840821 -0.156103 0.984156 + outer loop + vertex 447.534 110.904 361.825 + vertex 453.517 114.258 361.846 + vertex 447.809 114.004 362.293 + endloop + endfacet + facet normal 0.102423 -0.1897 0.976485 + outer loop + vertex 447.204 107.918 361.279 + vertex 447.534 110.904 361.825 + vertex 441.107 107.563 361.85 + endloop + endfacet + facet normal 0.103506 -0.217924 0.970462 + outer loop + vertex 440.698 104.636 361.236 + vertex 447.204 107.918 361.279 + vertex 441.107 107.563 361.85 + endloop + endfacet + facet normal 0.12364 -0.255277 0.95893 + outer loop + vertex 440.292 101.799 360.533 + vertex 440.698 104.636 361.236 + vertex 434.404 101.506 361.214 + endloop + endfacet + facet normal 0.12408 -0.281057 0.951636 + outer loop + vertex 433.926 98.8145 360.482 + vertex 440.292 101.799 360.533 + vertex 434.404 101.506 361.214 + endloop + endfacet + facet normal 0.139601 -0.308915 0.940789 + outer loop + vertex 433.591 96.4801 359.765 + vertex 433.926 98.8145 360.482 + vertex 427.528 96.2838 360.6 + endloop + endfacet + facet normal 0.152235 -0.281435 0.947427 + outer loop + vertex 428.12 98.7097 361.303 + vertex 428.75 101.451 362.016 + vertex 422.513 98.9633 362.279 + endloop + endfacet + facet normal 0.137013 -0.248842 0.958804 + outer loop + vertex 428.75 101.451 362.016 + vertex 434.884 104.379 361.899 + vertex 429.339 104.377 362.691 + endloop + endfacet + facet normal 0.138012 -0.219049 0.965904 + outer loop + vertex 434.884 104.379 361.899 + vertex 435.37 107.363 362.507 + vertex 429.339 104.377 362.691 + endloop + endfacet + facet normal 0.117901 -0.185881 0.975473 + outer loop + vertex 435.37 107.363 362.507 + vertex 441.519 110.591 362.379 + vertex 435.887 110.454 363.033 + endloop + endfacet + facet normal 0.117788 -0.156884 0.980568 + outer loop + vertex 441.519 110.591 362.379 + vertex 441.908 113.728 362.834 + vertex 435.887 110.454 363.033 + endloop + endfacet + facet normal 0.0959091 -0.128795 0.987022 + outer loop + vertex 441.908 113.728 362.834 + vertex 447.994 117.196 362.695 + vertex 442.233 116.966 363.225 + endloop + endfacet + facet normal 0.0949462 -0.104511 0.989981 + outer loop + vertex 442.233 116.966 363.225 + vertex 448.059 120.431 363.032 + vertex 442.467 120.274 363.551 + endloop + endfacet + facet normal 0.0951638 -0.0832762 0.991972 + outer loop + vertex 442.467 120.274 363.551 + vertex 448.141 123.799 363.303 + vertex 442.617 123.629 363.819 + endloop + endfacet + facet normal 0.09651 -0.0645559 0.993236 + outer loop + vertex 442.617 123.629 363.819 + vertex 448.023 127.19 363.525 + vertex 442.708 126.982 364.028 + endloop + endfacet + facet normal 0.0975772 -0.0488159 0.99403 + outer loop + vertex 442.708 126.982 364.028 + vertex 447.95 130.546 363.688 + vertex 442.794 130.329 364.184 + endloop + endfacet + facet normal 0.098576 -0.0350136 0.994513 + outer loop + vertex 442.794 130.329 364.184 + vertex 447.914 133.876 363.801 + vertex 442.854 133.686 364.296 + endloop + endfacet + facet normal 0.101045 -0.0254448 0.994556 + outer loop + vertex 442.854 133.686 364.296 + vertex 447.857 137.196 363.878 + vertex 442.866 137.065 364.381 + endloop + endfacet + facet normal 0.10503 -0.0270118 0.994102 + outer loop + vertex 442.866 137.065 364.381 + vertex 447.802 140.53 363.954 + vertex 442.872 140.461 364.473 + endloop + endfacet + facet normal 0.109688 -0.0647226 0.991857 + outer loop + vertex 442.872 140.461 364.473 + vertex 447.981 143.935 364.135 + vertex 443.089 143.916 364.674 + endloop + endfacet + facet normal 0.106188 -0.156968 0.981878 + outer loop + vertex 443.089 143.916 364.674 + vertex 448.893 147.519 364.623 + vertex 443.881 147.47 365.157 + endloop + endfacet + facet normal 0.157572 -0.0732472 0.984787 + outer loop + vertex 433.401 141.125 365.889 + vertex 438.323 144.156 365.327 + vertex 433.739 144.663 366.099 + endloop + endfacet + facet normal 0.159 -0.0395209 0.986487 + outer loop + vertex 433.24 137.625 365.775 + vertex 438.068 140.663 365.119 + vertex 433.401 141.125 365.889 + endloop + endfacet + facet normal 0.155531 -0.0344827 0.987229 + outer loop + vertex 433.109 134.148 365.674 + vertex 437.991 137.207 365.012 + vertex 433.24 137.625 365.775 + endloop + endfacet + facet normal 0.151932 -0.0408849 0.987545 + outer loop + vertex 432.944 130.694 365.557 + vertex 437.916 133.773 364.919 + vertex 433.109 134.148 365.674 + endloop + endfacet + facet normal 0.1496 -0.0519169 0.987383 + outer loop + vertex 432.735 127.269 365.408 + vertex 437.799 130.361 364.804 + vertex 432.944 130.694 365.557 + endloop + endfacet + facet normal 0.148387 -0.0676432 0.986613 + outer loop + vertex 432.469 123.862 365.215 + vertex 437.64 126.978 364.651 + vertex 432.735 127.269 365.408 + endloop + endfacet + facet normal 0.147376 -0.0873818 0.985213 + outer loop + vertex 432.133 120.469 364.964 + vertex 437.441 123.61 364.449 + vertex 432.469 123.862 365.215 + endloop + endfacet + facet normal 0.146009 -0.110039 0.983144 + outer loop + vertex 431.707 117.109 364.651 + vertex 437.186 120.25 364.189 + vertex 432.133 120.469 364.964 + endloop + endfacet + facet normal 0.144356 -0.135255 0.980239 + outer loop + vertex 431.187 113.813 364.273 + vertex 436.843 116.919 363.869 + vertex 431.707 117.109 364.651 + endloop + endfacet + facet normal 0.142386 -0.162414 0.976395 + outer loop + vertex 430.578 110.585 363.825 + vertex 436.401 113.647 363.485 + vertex 431.187 113.813 364.273 + endloop + endfacet + facet normal 0.16083 -0.194096 0.967709 + outer loop + vertex 429.935 107.426 363.298 + vertex 430.578 110.585 363.825 + vertex 424.891 107.843 364.22 + endloop + endfacet + facet normal 0.157323 -0.223654 0.961888 + outer loop + vertex 424.139 104.732 363.62 + vertex 429.935 107.426 363.298 + vertex 424.891 107.843 364.22 + endloop + endfacet + facet normal 0.168103 -0.25374 0.952553 + outer loop + vertex 423.402 101.761 362.958 + vertex 424.139 104.732 363.62 + vertex 418.691 102.424 363.966 + endloop + endfacet + facet normal 0.163306 -0.278547 0.946437 + outer loop + vertex 417.684 99.6735 363.331 + vertex 423.402 101.761 362.958 + vertex 418.691 102.424 363.966 + endloop + endfacet + facet normal 0.172939 -0.311845 0.934262 + outer loop + vertex 415.842 97.0097 362.782 + vertex 417.684 99.6735 363.331 + vertex 412.856 98.3266 363.775 + endloop + endfacet + facet normal 0.166667 -0.337192 0.926566 + outer loop + vertex 414.782 94.7266 362.142 + vertex 415.842 97.0097 362.782 + vertex 411.244 95.5422 363.075 + endloop + endfacet + facet normal 0.157115 -0.332825 0.929808 + outer loop + vertex 420.995 94.3976 360.975 + vertex 421.588 96.435 361.604 + vertex 414.782 94.7266 362.142 + endloop + endfacet + facet normal 0.148879 -0.330705 0.931917 + outer loop + vertex 427.214 94.3908 359.979 + vertex 427.528 96.2838 360.6 + vertex 420.995 94.3976 360.975 + endloop + endfacet + facet normal 0.136988 -0.340022 0.930387 + outer loop + vertex 433.833 93.6873 358.736 + vertex 433.617 94.7514 359.157 + vertex 427.424 93.2347 359.515 + endloop + endfacet + facet normal 0.13748 -0.360276 0.922659 + outer loop + vertex 428.167 92.6758 359.186 + vertex 433.833 93.6873 358.736 + vertex 427.424 93.2347 359.515 + endloop + endfacet + facet normal 0.128274 -0.341997 0.930905 + outer loop + vertex 433.833 93.6873 358.736 + vertex 440.915 95.4409 358.405 + vertex 433.617 94.7514 359.157 + endloop + endfacet + facet normal 0.129404 -0.346936 0.928919 + outer loop + vertex 440.46 94.1799 357.997 + vertex 440.915 95.4409 358.405 + vertex 433.833 93.6873 358.736 + endloop + endfacet + facet normal 0.129681 -0.355717 0.925553 + outer loop + vertex 433.956 93.0971 358.492 + vertex 440.46 94.1799 357.997 + vertex 433.833 93.6873 358.736 + endloop + endfacet + facet normal 0.139304 -0.329717 0.933746 + outer loop + vertex 427.214 94.3908 359.979 + vertex 433.591 96.4801 359.765 + vertex 427.528 96.2838 360.6 + endloop + endfacet + facet normal 0.127281 -0.307795 0.942901 + outer loop + vertex 433.591 96.4801 359.765 + vertex 439.994 99.1494 359.772 + vertex 433.926 98.8145 360.482 + endloop + endfacet + facet normal 0.117091 -0.292385 0.949105 + outer loop + vertex 446.56 99.6868 359.128 + vertex 446.544 102.197 359.903 + vertex 439.994 99.1494 359.772 + endloop + endfacet + facet normal 0.112606 -0.315592 0.94219 + outer loop + vertex 447.517 97.7854 358.376 + vertex 454 100.747 358.593 + vertex 446.56 99.6868 359.128 + endloop + endfacet + facet normal 0.127187 -0.322927 0.937839 + outer loop + vertex 440.915 95.4409 358.405 + vertex 440.124 96.9712 359.039 + vertex 433.617 94.7514 359.157 + endloop + endfacet + facet normal 0.112107 -0.314529 0.942605 + outer loop + vertex 453.625 98.8587 358.008 + vertex 454 100.747 358.593 + vertex 447.517 97.7854 358.376 + endloop + endfacet + facet normal 0.10679 -0.313744 0.943483 + outer loop + vertex 453.625 98.8587 358.008 + vertex 462.578 101.59 357.903 + vertex 454 100.747 358.593 + endloop + endfacet + facet normal 0.134086 -0.435477 0.890158 + outer loop + vertex 458.606 96.5201 356.465 + vertex 452.754 95.0925 356.648 + vertex 460.571 95.085 355.467 + endloop + endfacet + facet normal 0.134472 -0.43017 0.892676 + outer loop + vertex 448.788 93.1156 356.293 + vertex 460.571 95.085 355.467 + vertex 452.754 95.0925 356.648 + endloop + endfacet + facet normal 0.130964 -0.423774 0.89625 + outer loop + vertex 452.754 95.0925 356.648 + vertex 446.544 94.4321 357.244 + vertex 448.788 93.1156 356.293 + endloop + endfacet + facet normal 0.12135 -0.344655 0.930853 + outer loop + vertex 440.46 94.1799 357.997 + vertex 451.69 96.7711 357.493 + vertex 440.915 95.4409 358.405 + endloop + endfacet + facet normal 0.135559 -0.417554 0.898483 + outer loop + vertex 446.544 94.4321 357.244 + vertex 440.645 93.2621 357.59 + vertex 448.788 93.1156 356.293 + endloop + endfacet + facet normal 0.136192 -0.41045 0.901655 + outer loop + vertex 436.54 91.5349 357.424 + vertex 448.788 93.1156 356.293 + vertex 440.645 93.2621 357.59 + endloop + endfacet + facet normal 0.134447 -0.406501 0.903704 + outer loop + vertex 440.645 93.2621 357.59 + vertex 435.466 92.7559 358.133 + vertex 436.54 91.5349 357.424 + endloop + endfacet + facet normal 0.133502 -0.384143 0.913571 + outer loop + vertex 437.455 93.3269 358.078 + vertex 440.46 94.1799 357.997 + vertex 433.956 93.0971 358.492 + endloop + endfacet + facet normal 0.13817 -0.403643 0.904423 + outer loop + vertex 435.466 92.7559 358.133 + vertex 429.672 92.2994 358.814 + vertex 436.54 91.5349 357.424 + endloop + endfacet + facet normal 0.13658 -0.354116 0.925175 + outer loop + vertex 433.956 93.0971 358.492 + vertex 433.833 93.6873 358.736 + vertex 428.167 92.6758 359.186 + endloop + endfacet + facet normal 0.14159 -0.361055 0.921733 + outer loop + vertex 429.672 92.2994 358.814 + vertex 423.765 92.1931 359.68 + vertex 425.031 92.0476 359.428 + endloop + endfacet + facet normal 0.143947 -0.352795 0.924562 + outer loop + vertex 428.167 92.6758 359.186 + vertex 427.424 93.2347 359.515 + vertex 422.128 92.4282 360.031 + endloop + endfacet + facet normal 0.148557 -0.356866 0.922268 + outer loop + vertex 423.765 92.1931 359.68 + vertex 418.28 92.0921 360.524 + vertex 421.369 91.8641 359.939 + endloop + endfacet + facet normal 0.151364 -0.361386 0.920049 + outer loop + vertex 422.128 92.4282 360.031 + vertex 421.119 93.057 360.444 + vertex 416.117 92.4381 361.024 + endloop + endfacet + facet normal 0.154628 -0.361773 0.919354 + outer loop + vertex 418.28 92.0921 360.524 + vertex 412.987 92.1912 361.454 + vertex 416.018 91.7484 360.77 + endloop + endfacet + facet normal 0.157306 -0.363915 0.918053 + outer loop + vertex 416.117 92.4381 361.024 + vertex 414.527 93.1833 361.592 + vertex 410.232 92.6737 362.126 + endloop + endfacet + facet normal 0.157339 -0.372314 0.914673 + outer loop + vertex 412.987 92.1912 361.454 + vertex 409.795 92.3426 362.064 + vertex 410.648 91.8611 361.722 + endloop + endfacet + facet normal 0.161919 -0.365567 0.916593 + outer loop + vertex 409.795 92.3426 362.064 + vertex 407.508 92.4572 362.514 + vertex 410.648 91.8611 361.722 + endloop + endfacet + facet normal 0.162708 -0.364895 0.916721 + outer loop + vertex 406.35 93.1314 362.997 + vertex 410.232 92.6737 362.126 + vertex 408.071 93.2631 362.744 + endloop + endfacet + facet normal 0.156887 -0.387501 0.908421 + outer loop + vertex 407.508 92.4572 362.514 + vertex 403.337 92.4562 363.234 + vertex 407.201 91.804 362.288 + endloop + endfacet + facet normal 0.162874 -0.374854 0.912665 + outer loop + vertex 406.226 93.8124 363.299 + vertex 406.35 93.1314 362.997 + vertex 408.071 93.2631 362.744 + endloop + endfacet + facet normal 0.164845 -0.369911 0.914326 + outer loop + vertex 408.071 93.2631 362.744 + vertex 407.796 94.0394 363.108 + vertex 406.226 93.8124 363.299 + endloop + endfacet + facet normal 0.16368 -0.364645 0.916648 + outer loop + vertex 407.796 94.0394 363.108 + vertex 410.169 94.4406 362.844 + vertex 408.137 95.007 363.432 + endloop + endfacet + facet normal 0.159391 -0.358479 0.91983 + outer loop + vertex 405.941 96.1672 364.278 + vertex 405.131 94.2553 363.673 + vertex 406.247 94.7463 363.671 + endloop + endfacet + facet normal 0.177922 -0.364505 0.914046 + outer loop + vertex 405.131 94.2553 363.673 + vertex 405.941 96.1672 364.278 + vertex 404.468 95.5716 364.327 + endloop + endfacet + facet normal 0.169918 -0.355525 0.919092 + outer loop + vertex 408.137 95.007 363.432 + vertex 408.773 96.1576 363.759 + vertex 406.921 95.721 363.933 + endloop + endfacet + facet normal 0.169241 -0.337591 0.925954 + outer loop + vertex 408.773 96.1576 363.759 + vertex 411.379 96.7783 363.509 + vertex 409.548 97.5354 364.12 + endloop + endfacet + facet normal 0.159075 -0.331245 0.930039 + outer loop + vertex 407.444 98.681 364.916 + vertex 405.941 96.1672 364.278 + vertex 407.462 96.993 364.312 + endloop + endfacet + facet normal 0.191286 -0.347438 0.917985 + outer loop + vertex 405.941 96.1672 364.278 + vertex 407.444 98.681 364.916 + vertex 406.037 98.1051 364.991 + endloop + endfacet + facet normal 0.180698 -0.3227 0.929093 + outer loop + vertex 409.548 97.5354 364.12 + vertex 410.482 99.2479 364.533 + vertex 408.434 98.3863 364.632 + endloop + endfacet + facet normal 0.179093 -0.301877 0.936374 + outer loop + vertex 410.482 99.2479 364.533 + vertex 413.967 100.568 364.292 + vertex 411.336 101.279 365.025 + endloop + endfacet + facet normal 0.166212 -0.306096 0.937379 + outer loop + vertex 409.225 101.525 365.529 + vertex 407.444 98.681 364.916 + vertex 409.121 100.02 365.056 + endloop + endfacet + facet normal 0.192918 -0.28648 0.938463 + outer loop + vertex 410.017 101.53 365.372 + vertex 411.336 101.279 365.025 + vertex 411.859 103.537 365.606 + endloop + endfacet + facet normal 0.191253 -0.261002 0.946203 + outer loop + vertex 414.869 103.162 364.895 + vertex 415.872 106.197 365.529 + vertex 411.859 103.537 365.606 + endloop + endfacet + facet normal 0.188504 -0.232072 0.954258 + outer loop + vertex 419.554 105.393 364.606 + vertex 420.491 108.567 365.193 + vertex 415.872 106.197 365.529 + endloop + endfacet + facet normal 0.180312 -0.199952 0.963072 + outer loop + vertex 420.491 108.567 365.193 + vertex 425.655 111.04 364.74 + vertex 421.421 111.843 365.699 + endloop + endfacet + facet normal 0.185794 -0.16855 0.968024 + outer loop + vertex 421.421 111.843 365.699 + vertex 426.354 114.302 365.18 + vertex 422.247 115.16 366.118 + endloop + endfacet + facet normal 0.190601 -0.138363 0.971868 + outer loop + vertex 422.247 115.16 366.118 + vertex 426.953 117.625 365.546 + vertex 422.949 118.521 366.459 + endloop + endfacet + facet normal 0.195051 -0.112031 0.974374 + outer loop + vertex 422.949 118.521 366.459 + vertex 427.454 121.008 365.843 + vertex 423.516 121.919 366.736 + endloop + endfacet + facet normal 0.199655 -0.0902243 0.975704 + outer loop + vertex 423.516 121.919 366.736 + vertex 427.869 124.431 366.077 + vertex 423.993 125.37 366.957 + endloop + endfacet + facet normal 0.204577 -0.0719705 0.976201 + outer loop + vertex 423.993 125.37 366.957 + vertex 428.197 127.871 366.261 + vertex 424.341 128.836 367.14 + endloop + endfacet + facet normal 0.20981 -0.05847 0.975992 + outer loop + vertex 424.341 128.836 367.14 + vertex 428.45 131.331 366.406 + vertex 424.629 132.352 367.289 + endloop + endfacet + facet normal 0.214426 -0.0482177 0.975549 + outer loop + vertex 424.629 132.352 367.289 + vertex 428.651 134.822 366.527 + vertex 424.859 135.893 367.413 + endloop + endfacet + facet normal 0.21719 -0.0417519 0.975236 + outer loop + vertex 424.859 135.893 367.413 + vertex 428.838 138.339 366.632 + vertex 425.093 139.439 367.513 + endloop + endfacet + facet normal 0.216526 -0.043862 0.975291 + outer loop + vertex 425.093 139.439 367.513 + vertex 429.084 141.87 366.736 + vertex 425.398 142.972 367.604 + endloop + endfacet + facet normal 0.206117 -0.078753 0.975353 + outer loop + vertex 429.084 141.87 366.736 + vertex 429.507 145.448 366.936 + vertex 425.398 142.972 367.604 + endloop + endfacet + facet normal 0.166836 -0.168262 0.971521 + outer loop + vertex 429.507 145.448 366.936 + vertex 434.352 148.288 366.596 + vertex 430.13 149.162 367.472 + endloop + endfacet + facet normal 0.235623 -0.088777 0.967781 + outer loop + vertex 422.424 144.404 368.447 + vertex 425.822 146.549 367.817 + vertex 422.754 147.84 368.682 + endloop + endfacet + facet normal 0.266335 -0.0911621 0.95956 + outer loop + vertex 422.424 144.404 368.447 + vertex 422.754 147.84 368.682 + vertex 419.952 145.969 369.282 + endloop + endfacet + facet normal 0.370351 -0.179718 0.91134 + outer loop + vertex 418.229 149.86 370.277 + vertex 419.55 151.67 370.097 + vertex 417.043 155.4 371.851 + endloop + endfacet + facet normal 0.514105 -0.130858 0.847687 + outer loop + vertex 417.043 155.4 371.851 + vertex 416.593 146.194 370.703 + vertex 418.229 149.86 370.277 + endloop + endfacet + facet normal 0.193428 -0.30812 0.931476 + outer loop + vertex 419.55 151.67 370.097 + vertex 420.298 153.148 370.43 + vertex 417.043 155.4 371.851 + endloop + endfacet + facet normal 0.439148 -0.0920694 0.893685 + outer loop + vertex 418.559 147.397 369.861 + vertex 418.229 149.86 370.277 + vertex 416.593 146.194 370.703 + endloop + endfacet + facet normal 0.261071 -0.0825679 0.961782 + outer loop + vertex 419.952 145.969 369.282 + vertex 422.754 147.84 368.682 + vertex 420.203 148.966 369.471 + endloop + endfacet + facet normal 0.429469 -0.0716652 0.900234 + outer loop + vertex 418.309 146.048 369.873 + vertex 418.559 147.397 369.861 + vertex 416.593 146.194 370.703 + endloop + endfacet + facet normal 0.432915 -0.0342988 0.900782 + outer loop + vertex 418.44 144.525 369.752 + vertex 418.309 146.048 369.873 + vertex 416.593 146.194 370.703 + endloop + endfacet + facet normal 0.291563 -0.0490216 0.955295 + outer loop + vertex 419.919 142.762 369.128 + vertex 422.424 144.404 368.447 + vertex 419.952 145.969 369.282 + endloop + endfacet + facet normal 0.414459 -0.0589257 0.908158 + outer loop + vertex 417.891 141.556 369.81 + vertex 418.44 144.525 369.752 + vertex 416.593 146.194 370.703 + endloop + endfacet + facet normal 0.39612 -0.0655392 0.915857 + outer loop + vertex 416.593 146.194 370.703 + vertex 415.646 138.695 370.576 + vertex 417.891 141.556 369.81 + endloop + endfacet + facet normal 0.295092 -0.0456788 0.954376 + outer loop + vertex 419.649 139.339 369.047 + vertex 422.137 140.951 368.355 + vertex 419.919 142.762 369.128 + endloop + endfacet + facet normal 0.385204 -0.055552 0.921158 + outer loop + vertex 417.846 137.933 369.61 + vertex 417.891 141.556 369.81 + vertex 415.646 138.695 370.576 + endloop + endfacet + facet normal 0.291326 -0.0520176 0.955209 + outer loop + vertex 419.382 135.784 368.935 + vertex 421.863 137.414 368.267 + vertex 419.649 139.339 369.047 + endloop + endfacet + facet normal 0.381519 -0.067164 0.921918 + outer loop + vertex 417.329 134.62 369.583 + vertex 417.846 137.933 369.61 + vertex 415.646 138.695 370.576 + endloop + endfacet + facet normal 0.372057 -0.0719257 0.925419 + outer loop + vertex 415.646 138.695 370.576 + vertex 415.374 132.883 370.234 + vertex 417.329 134.62 369.583 + endloop + endfacet + facet normal 0.284742 -0.0621042 0.95659 + outer loop + vertex 419.122 132.22 368.781 + vertex 421.617 133.835 368.143 + vertex 419.382 135.784 368.935 + endloop + endfacet + facet normal 0.373084 -0.0732772 0.924899 + outer loop + vertex 417.321 131.112 369.308 + vertex 417.329 134.62 369.583 + vertex 415.374 132.883 370.234 + endloop + endfacet + facet normal 0.277268 -0.0737041 0.957962 + outer loop + vertex 418.798 128.743 368.607 + vertex 421.349 130.278 367.987 + vertex 419.122 132.22 368.781 + endloop + endfacet + facet normal 0.35952 -0.0902184 0.928766 + outer loop + vertex 416.419 128.192 369.373 + vertex 417.321 131.112 369.308 + vertex 415.374 132.883 370.234 + endloop + endfacet + facet normal 0.390237 -0.081239 0.917123 + outer loop + vertex 416.419 128.192 369.373 + vertex 415.374 132.883 370.234 + vertex 413.575 130.291 370.769 + endloop + endfacet + facet normal 0.366488 -0.117325 0.922996 + outer loop + vertex 414.946 126.712 369.77 + vertex 416.419 128.192 369.373 + vertex 413.575 130.291 370.769 + endloop + endfacet + facet normal 0.382685 -0.109547 0.917361 + outer loop + vertex 413.575 130.291 370.769 + vertex 413.51 128.056 370.529 + vertex 414.946 126.712 369.77 + endloop + endfacet + facet normal 0.368285 -0.126984 0.921 + outer loop + vertex 414.044 126.959 370.165 + vertex 414.946 126.712 369.77 + vertex 413.51 128.056 370.529 + endloop + endfacet + facet normal 0.371041 -0.117215 0.921189 + outer loop + vertex 414.946 126.712 369.77 + vertex 414.044 126.959 370.165 + vertex 414.02 126.138 370.07 + endloop + endfacet + facet normal 0.267466 -0.0931489 0.959054 + outer loop + vertex 418.443 125.256 368.368 + vertex 421.016 126.768 367.797 + vertex 418.798 128.743 368.607 + endloop + endfacet + facet normal 0.363248 -0.113635 0.924737 + outer loop + vertex 416.443 124.192 368.873 + vertex 416.419 128.192 369.373 + vertex 414.946 126.712 369.77 + endloop + endfacet + facet normal 0.339024 -0.130495 0.931683 + outer loop + vertex 416.443 124.192 368.873 + vertex 414.946 126.712 369.77 + vertex 415.335 124.924 369.378 + endloop + endfacet + facet normal 0.331115 -0.14315 0.932669 + outer loop + vertex 415.335 124.924 369.378 + vertex 414.843 123.269 369.299 + vertex 416.443 124.192 368.873 + endloop + endfacet + facet normal 0.349781 -0.148331 0.925014 + outer loop + vertex 415.335 124.924 369.378 + vertex 414.02 126.138 370.07 + vertex 414.843 123.269 369.299 + endloop + endfacet + facet normal 0.366449 -0.142081 0.919526 + outer loop + vertex 414.843 123.269 369.299 + vertex 414.02 126.138 370.07 + vertex 412.855 125.53 370.44 + endloop + endfacet + facet normal 0.336677 -0.171454 0.925879 + outer loop + vertex 414.843 123.269 369.299 + vertex 412.855 125.53 370.44 + vertex 412.663 121.987 369.854 + endloop + endfacet + facet normal 0.332734 -0.163506 0.928738 + outer loop + vertex 412.663 121.987 369.854 + vertex 414.672 119.96 368.778 + vertex 414.843 123.269 369.299 + endloop + endfacet + facet normal 0.296851 -0.163554 0.940813 + outer loop + vertex 416.2 120.65 368.415 + vertex 414.843 123.269 369.299 + vertex 414.672 119.96 368.778 + endloop + endfacet + facet normal 0.309761 -0.188028 0.932037 + outer loop + vertex 414.672 119.96 368.778 + vertex 412.663 121.987 369.854 + vertex 413.394 117.131 368.631 + endloop + endfacet + facet normal 0.316464 -0.186527 0.930085 + outer loop + vertex 413.394 117.131 368.631 + vertex 412.663 121.987 369.854 + vertex 412.384 118.758 369.302 + endloop + endfacet + facet normal 0.305367 -0.194294 0.932202 + outer loop + vertex 412.384 118.758 369.302 + vertex 411.641 116.577 369.09 + vertex 413.394 117.131 368.631 + endloop + endfacet + facet normal 0.310383 -0.215392 0.925888 + outer loop + vertex 411.858 112.945 368.173 + vertex 413.394 117.131 368.631 + vertex 411.641 116.577 369.09 + endloop + endfacet + facet normal 0.316172 -0.214597 0.924112 + outer loop + vertex 410.45 114.565 369.031 + vertex 411.858 112.945 368.173 + vertex 411.641 116.577 369.09 + endloop + endfacet + facet normal 0.316513 -0.214794 0.92395 + outer loop + vertex 411.641 116.577 369.09 + vertex 409.768 117.725 369.999 + vertex 410.45 114.565 369.031 + endloop + endfacet + facet normal 0.313334 -0.215744 0.924811 + outer loop + vertex 410.45 114.565 369.031 + vertex 409.768 117.725 369.999 + vertex 408.717 115.236 369.774 + endloop + endfacet + facet normal 0.303521 -0.238511 0.92249 + outer loop + vertex 410.45 114.565 369.031 + vertex 408.717 115.236 369.774 + vertex 409.718 112.099 368.634 + endloop + endfacet + facet normal 0.297664 -0.240852 0.923789 + outer loop + vertex 409.718 112.099 368.634 + vertex 408.717 115.236 369.774 + vertex 407.769 113.113 369.526 + endloop + endfacet + facet normal 0.28573 -0.262019 0.921794 + outer loop + vertex 409.718 112.099 368.634 + vertex 407.769 113.113 369.526 + vertex 408.598 110.349 368.483 + endloop + endfacet + facet normal 0.281147 -0.259272 0.923977 + outer loop + vertex 408.598 110.349 368.483 + vertex 410.263 108.397 367.429 + vertex 409.718 112.099 368.634 + endloop + endfacet + facet normal 0.299036 -0.25518 0.919489 + outer loop + vertex 410.263 108.397 367.429 + vertex 411.858 112.945 368.173 + vertex 409.718 112.099 368.634 + endloop + endfacet + facet normal 0.255253 -0.281844 0.924884 + outer loop + vertex 408.598 110.349 368.483 + vertex 407.875 108.251 368.044 + vertex 410.263 108.397 367.429 + endloop + endfacet + facet normal 0.255064 -0.292496 0.921623 + outer loop + vertex 407.875 108.251 368.044 + vertex 408.408 105.334 366.97 + vertex 410.263 108.397 367.429 + endloop + endfacet + facet normal 0.241322 -0.295962 0.924213 + outer loop + vertex 406.63 106.134 367.691 + vertex 408.408 105.334 366.97 + vertex 407.875 108.251 368.044 + endloop + endfacet + facet normal 0.252109 -0.301522 0.919525 + outer loop + vertex 407.875 108.251 368.044 + vertex 405.788 109.413 368.997 + vertex 406.63 106.134 367.691 + endloop + endfacet + facet normal 0.253745 -0.300992 0.919248 + outer loop + vertex 406.63 106.134 367.691 + vertex 405.788 109.413 368.997 + vertex 404.621 107.617 368.731 + endloop + endfacet + facet normal 0.242044 -0.315611 0.917499 + outer loop + vertex 406.63 106.134 367.691 + vertex 404.621 107.617 368.731 + vertex 405.373 104.239 367.371 + endloop + endfacet + facet normal 0.233414 -0.310554 0.921452 + outer loop + vertex 407.004 103.12 366.58 + vertex 406.63 106.134 367.691 + vertex 405.373 104.239 367.371 + endloop + endfacet + facet normal 0.222077 -0.325442 0.919113 + outer loop + vertex 407.004 103.12 366.58 + vertex 405.373 104.239 367.371 + vertex 405.719 101.296 366.245 + endloop + endfacet + facet normal 0.217538 -0.322624 0.92119 + outer loop + vertex 406.81 100.546 365.725 + vertex 407.004 103.12 366.58 + vertex 405.719 101.296 366.245 + endloop + endfacet + facet normal 0.224066 -0.325073 0.918761 + outer loop + vertex 405.719 101.296 366.245 + vertex 405.373 104.239 367.371 + vertex 404.134 102.547 367.074 + endloop + endfacet + facet normal 0.211545 -0.339452 0.916527 + outer loop + vertex 405.719 101.296 366.245 + vertex 404.134 102.547 367.074 + vertex 404.541 99.6998 365.926 + endloop + endfacet + facet normal 0.205985 -0.335866 0.919111 + outer loop + vertex 405.641 99.1601 365.482 + vertex 405.719 101.296 366.245 + vertex 404.541 99.6998 365.926 + endloop + endfacet + facet normal 0.213833 -0.338981 0.91617 + outer loop + vertex 404.541 99.6998 365.926 + vertex 404.134 102.547 367.074 + vertex 402.92 100.988 366.781 + endloop + endfacet + facet normal 0.202248 -0.35203 0.913877 + outer loop + vertex 404.541 99.6998 365.926 + vertex 402.92 100.988 366.781 + vertex 403.416 98.2646 365.622 + endloop + endfacet + facet normal 0.199123 -0.349899 0.91538 + outer loop + vertex 404.669 97.5996 365.095 + vertex 404.541 99.6998 365.926 + vertex 403.416 98.2646 365.622 + endloop + endfacet + facet normal 0.205771 -0.351192 0.913413 + outer loop + vertex 403.416 98.2646 365.622 + vertex 402.92 100.988 366.781 + vertex 401.739 99.587 366.508 + endloop + endfacet + facet normal 0.220091 -0.343276 0.913084 + outer loop + vertex 404.134 102.547 367.074 + vertex 402.176 104.33 368.216 + vertex 402.92 100.988 366.781 + endloop + endfacet + facet normal 0.223831 -0.342222 0.91257 + outer loop + vertex 402.92 100.988 366.781 + vertex 402.176 104.33 368.216 + vertex 400.933 102.842 367.963 + endloop + endfacet + facet normal 0.23398 -0.329138 0.914834 + outer loop + vertex 404.134 102.547 367.074 + vertex 403.406 105.932 368.478 + vertex 402.176 104.33 368.216 + endloop + endfacet + facet normal 0.2401 -0.333333 0.911724 + outer loop + vertex 403.406 105.932 368.478 + vertex 401.192 108.343 369.943 + vertex 402.176 104.33 368.216 + endloop + endfacet + facet normal 0.243859 -0.332166 0.911152 + outer loop + vertex 402.176 104.33 368.216 + vertex 401.192 108.343 369.943 + vertex 400.219 106.252 369.441 + endloop + endfacet + facet normal 0.25703 -0.318255 0.912496 + outer loop + vertex 403.406 105.932 368.478 + vertex 402.661 109.364 369.885 + vertex 401.192 108.343 369.943 + endloop + endfacet + facet normal 0.257676 -0.319214 0.911979 + outer loop + vertex 402.661 109.364 369.885 + vertex 400.692 113.931 372.04 + vertex 401.192 108.343 369.943 + endloop + endfacet + facet normal 0.272648 -0.316583 0.908536 + outer loop + vertex 400.692 113.931 372.04 + vertex 398.334 110.924 371.7 + vertex 401.192 108.343 369.943 + endloop + endfacet + facet normal 0.287115 -0.327005 0.900351 + outer loop + vertex 400.692 113.931 372.04 + vertex 397.442 118.856 374.865 + vertex 398.334 110.924 371.7 + endloop + endfacet + facet normal 0.297515 -0.324805 0.897768 + outer loop + vertex 398.334 110.924 371.7 + vertex 397.442 118.856 374.865 + vertex 395.164 116.123 374.631 + endloop + endfacet + facet normal 0.309781 -0.334368 0.890075 + outer loop + vertex 397.442 118.856 374.865 + vertex 394.904 124.002 377.682 + vertex 395.164 116.123 374.631 + endloop + endfacet + facet normal 0.281375 -0.307577 0.908969 + outer loop + vertex 402.661 109.364 369.885 + vertex 403.549 111.579 370.36 + vertex 400.692 113.931 372.04 + endloop + endfacet + facet normal 0.300889 -0.284723 0.910164 + outer loop + vertex 402.871 117.303 372.374 + vertex 400.692 113.931 372.04 + vertex 403.549 111.579 370.36 + endloop + endfacet + facet normal 0.280181 -0.289018 0.915405 + outer loop + vertex 404.908 112.742 370.311 + vertex 402.871 117.303 372.374 + vertex 403.549 111.579 370.36 + endloop + endfacet + facet normal 0.279161 -0.287796 0.916102 + outer loop + vertex 405.788 109.413 368.997 + vertex 404.908 112.742 370.311 + vertex 403.549 111.579 370.36 + endloop + endfacet + facet normal 0.27224 -0.290153 0.91744 + outer loop + vertex 406.814 111.263 369.278 + vertex 404.908 112.742 370.311 + vertex 405.788 109.413 368.997 + endloop + endfacet + facet normal 0.288986 -0.269413 0.918642 + outer loop + vertex 406.814 111.263 369.278 + vertex 405.623 115.103 370.778 + vertex 404.908 112.742 370.311 + endloop + endfacet + facet normal 0.285356 -0.27082 0.919363 + outer loop + vertex 407.769 113.113 369.526 + vertex 405.623 115.103 370.778 + vertex 406.814 111.263 369.278 + endloop + endfacet + facet normal 0.307676 -0.246518 0.919002 + outer loop + vertex 407.769 113.113 369.526 + vertex 406.842 116.521 370.751 + vertex 405.623 115.103 370.778 + endloop + endfacet + facet normal 0.313631 -0.251701 0.915577 + outer loop + vertex 406.842 116.521 370.751 + vertex 404.744 121.142 372.74 + vertex 405.623 115.103 370.778 + endloop + endfacet + facet normal 0.330179 -0.247749 0.910825 + outer loop + vertex 404.744 121.142 372.74 + vertex 402.871 117.303 372.374 + vertex 405.623 115.103 370.778 + endloop + endfacet + facet normal 0.363403 -0.262344 0.893932 + outer loop + vertex 404.744 121.142 372.74 + vertex 401.637 125.732 375.35 + vertex 402.871 117.303 372.374 + endloop + endfacet + facet normal 0.370524 -0.260462 0.891556 + outer loop + vertex 402.871 117.303 372.374 + vertex 401.637 125.732 375.35 + vertex 399.67 122.097 375.105 + endloop + endfacet + facet normal 0.400503 -0.275501 0.873897 + outer loop + vertex 401.637 125.732 375.35 + vertex 399.152 130.601 378.024 + vertex 399.67 122.097 375.105 + endloop + endfacet + facet normal 0.404111 -0.274788 0.87246 + outer loop + vertex 399.67 122.097 375.105 + vertex 399.152 130.601 378.024 + vertex 397.13 127.093 377.855 + endloop + endfacet + facet normal 0.432193 -0.290078 0.853853 + outer loop + vertex 399.152 130.601 378.024 + vertex 397.265 135.662 380.698 + vertex 397.13 127.093 377.855 + endloop + endfacet + facet normal 0.434106 -0.289815 0.852971 + outer loop + vertex 397.13 127.093 377.855 + vertex 397.265 135.662 380.698 + vertex 395.232 132.309 380.594 + endloop + endfacet + facet normal 0.457905 -0.303698 0.835518 + outer loop + vertex 397.265 135.662 380.698 + vertex 395.838 140.92 383.391 + vertex 395.232 132.309 380.594 + endloop + endfacet + facet normal 0.459502 -0.303544 0.834697 + outer loop + vertex 395.232 132.309 380.594 + vertex 395.838 140.92 383.391 + vertex 393.792 137.7 383.347 + endloop + endfacet + facet normal 0.477807 -0.314968 0.820058 + outer loop + vertex 395.838 140.92 383.391 + vertex 394.697 146.329 386.134 + vertex 393.792 137.7 383.347 + endloop + endfacet + facet normal 0.478267 -0.314934 0.819804 + outer loop + vertex 393.792 137.7 383.347 + vertex 394.697 146.329 386.134 + vertex 392.645 143.197 386.128 + endloop + endfacet + facet normal 0.493739 -0.325044 0.806578 + outer loop + vertex 394.697 146.329 386.134 + vertex 393.742 151.735 388.897 + vertex 392.645 143.197 386.128 + endloop + endfacet + facet normal 0.4912 -0.3252 0.808064 + outer loop + vertex 392.645 143.197 386.128 + vertex 393.742 151.735 388.897 + vertex 391.697 148.719 388.926 + endloop + endfacet + facet normal 0.506921 -0.33599 0.793815 + outer loop + vertex 393.742 151.735 388.897 + vertex 392.958 157.124 391.678 + vertex 391.697 148.719 388.926 + endloop + endfacet + facet normal 0.502048 -0.336237 0.796802 + outer loop + vertex 391.697 148.719 388.926 + vertex 392.958 157.124 391.678 + vertex 390.926 154.232 391.739 + endloop + endfacet + facet normal 0.519732 -0.349023 0.779783 + outer loop + vertex 392.958 157.124 391.678 + vertex 392.333 162.555 394.526 + vertex 390.926 154.232 391.739 + endloop + endfacet + facet normal 0.510617 -0.349431 0.785601 + outer loop + vertex 390.926 154.232 391.739 + vertex 392.333 162.555 394.526 + vertex 390.314 159.758 394.594 + endloop + endfacet + facet normal 0.529138 -0.363253 0.766851 + outer loop + vertex 392.333 162.555 394.526 + vertex 391.801 167.946 397.447 + vertex 390.314 159.758 394.594 + endloop + endfacet + facet normal 0.509693 -0.364131 0.779501 + outer loop + vertex 390.314 159.758 394.594 + vertex 391.801 167.946 397.447 + vertex 389.802 165.323 397.529 + endloop + endfacet + facet normal 0.52495 -0.376259 0.76345 + outer loop + vertex 391.801 167.946 397.447 + vertex 391.292 173.225 400.398 + vertex 389.802 165.323 397.529 + endloop + endfacet + facet normal 0.493906 -0.377594 0.783249 + outer loop + vertex 389.802 165.323 397.529 + vertex 391.292 173.225 400.398 + vertex 389.285 170.861 400.524 + endloop + endfacet + facet normal 0.503872 -0.386634 0.772416 + outer loop + vertex 391.292 173.225 400.398 + vertex 390.721 178.235 403.278 + vertex 389.285 170.861 400.524 + endloop + endfacet + facet normal 0.469182 -0.387727 0.793433 + outer loop + vertex 389.285 170.861 400.524 + vertex 390.721 178.235 403.278 + vertex 388.65 176.02 403.421 + endloop + endfacet + facet normal 0.424785 -0.402886 0.810704 + outer loop + vertex 389.285 170.861 400.524 + vertex 388.65 176.02 403.421 + vertex 387.093 168.597 400.548 + endloop + endfacet + facet normal 0.416692 -0.394967 0.81876 + outer loop + vertex 387.619 162.896 397.53 + vertex 389.285 170.861 400.524 + vertex 387.093 168.597 400.548 + endloop + endfacet + facet normal 0.38074 -0.404926 0.831307 + outer loop + vertex 387.619 162.896 397.53 + vertex 387.093 168.597 400.548 + vertex 385.527 160.883 397.507 + endloop + endfacet + facet normal 0.439876 -0.395183 0.806436 + outer loop + vertex 389.802 165.323 397.529 + vertex 389.285 170.861 400.524 + vertex 387.619 162.896 397.53 + endloop + endfacet + facet normal 0.428198 -0.384675 0.817723 + outer loop + vertex 388.13 157.158 394.563 + vertex 389.802 165.323 397.529 + vertex 387.619 162.896 397.53 + endloop + endfacet + facet normal 0.446635 -0.384822 0.807731 + outer loop + vertex 390.314 159.758 394.594 + vertex 389.802 165.323 397.529 + vertex 388.13 157.158 394.563 + endloop + endfacet + facet normal 0.431677 -0.372415 0.82156 + outer loop + vertex 388.728 151.512 391.69 + vertex 390.314 159.758 394.594 + vertex 388.13 157.158 394.563 + endloop + endfacet + facet normal 0.442744 -0.372456 0.815631 + outer loop + vertex 390.926 154.232 391.739 + vertex 390.314 159.758 394.594 + vertex 388.728 151.512 391.69 + endloop + endfacet + facet normal 0.427664 -0.360511 0.828936 + outer loop + vertex 389.486 145.914 388.864 + vertex 390.926 154.232 391.739 + vertex 388.728 151.512 391.69 + endloop + endfacet + facet normal 0.434021 -0.360473 0.825643 + outer loop + vertex 391.697 148.719 388.926 + vertex 390.926 154.232 391.739 + vertex 389.486 145.914 388.864 + endloop + endfacet + facet normal 0.420967 -0.350426 0.836653 + outer loop + vertex 390.425 140.323 386.05 + vertex 391.697 148.719 388.926 + vertex 389.486 145.914 388.864 + endloop + endfacet + facet normal 0.424219 -0.350364 0.835035 + outer loop + vertex 392.645 143.197 386.128 + vertex 391.697 148.719 388.926 + vertex 390.425 140.323 386.05 + endloop + endfacet + facet normal 0.412263 -0.341387 0.844686 + outer loop + vertex 391.572 134.782 383.25 + vertex 392.645 143.197 386.128 + vertex 390.425 140.323 386.05 + endloop + endfacet + facet normal 0.412046 -0.341395 0.844789 + outer loop + vertex 393.792 137.7 383.347 + vertex 392.645 143.197 386.128 + vertex 391.572 134.782 383.25 + endloop + endfacet + facet normal 0.39823 -0.331235 0.855392 + outer loop + vertex 392.997 129.313 380.469 + vertex 393.792 137.7 383.347 + vertex 391.572 134.782 383.25 + endloop + endfacet + facet normal 0.396478 -0.331335 0.856167 + outer loop + vertex 395.232 132.309 380.594 + vertex 393.792 137.7 383.347 + vertex 392.997 129.313 380.469 + endloop + endfacet + facet normal 0.379742 -0.319352 0.868222 + outer loop + vertex 394.904 124.002 377.682 + vertex 395.232 132.309 380.594 + vertex 392.997 129.313 380.469 + endloop + endfacet + facet normal 0.376056 -0.319721 0.86969 + outer loop + vertex 397.13 127.093 377.855 + vertex 395.232 132.309 380.594 + vertex 394.904 124.002 377.682 + endloop + endfacet + facet normal 0.35709 -0.306758 0.882262 + outer loop + vertex 397.442 118.856 374.865 + vertex 397.13 127.093 377.855 + vertex 394.904 124.002 377.682 + endloop + endfacet + facet normal 0.352102 -0.307571 0.883982 + outer loop + vertex 399.67 122.097 375.105 + vertex 397.13 127.093 377.855 + vertex 397.442 118.856 374.865 + endloop + endfacet + facet normal 0.332175 -0.29476 0.895978 + outer loop + vertex 400.692 113.931 372.04 + vertex 399.67 122.097 375.105 + vertex 397.442 118.856 374.865 + endloop + endfacet + facet normal 0.399661 -0.40258 0.823529 + outer loop + vertex 387.093 168.597 400.548 + vertex 388.65 176.02 403.421 + vertex 386.485 173.745 403.359 + endloop + endfacet + facet normal 0.370081 -0.41125 0.833014 + outer loop + vertex 387.093 168.597 400.548 + vertex 386.485 173.745 403.359 + vertex 385.032 166.72 400.537 + endloop + endfacet + facet normal 0.405885 -0.408344 0.817626 + outer loop + vertex 388.65 176.02 403.421 + vertex 387.74 179.849 405.785 + vertex 386.485 173.745 403.359 + endloop + endfacet + facet normal 0.377791 -0.407952 0.831173 + outer loop + vertex 386.485 173.745 403.359 + vertex 387.74 179.849 405.785 + vertex 385.86 177.384 405.43 + endloop + endfacet + facet normal 0.378349 -0.408315 0.830741 + outer loop + vertex 385.86 177.384 405.43 + vertex 387.74 179.849 405.785 + vertex 386.322 181.851 407.415 + endloop + endfacet + facet normal 0.383876 -0.404037 0.830297 + outer loop + vertex 388.717 184.378 407.537 + vertex 386.322 181.851 407.415 + vertex 387.74 179.849 405.785 + endloop + endfacet + facet normal 0.384892 -0.404956 0.829378 + outer loop + vertex 388.717 184.378 407.537 + vertex 387.965 185.509 408.438 + vertex 386.322 181.851 407.415 + endloop + endfacet + facet normal 0.365641 -0.399468 0.840674 + outer loop + vertex 386.322 181.851 407.415 + vertex 387.965 185.509 408.438 + vertex 385.644 183.982 408.722 + endloop + endfacet + facet normal 0.435301 -0.395791 0.808617 + outer loop + vertex 388.65 176.02 403.421 + vertex 390.016 182.787 405.998 + vertex 387.74 179.849 405.785 + endloop + endfacet + facet normal 0.448303 -0.40501 0.796864 + outer loop + vertex 387.74 179.849 405.785 + vertex 390.016 182.787 405.998 + vertex 388.717 184.378 407.537 + endloop + endfacet + facet normal 0.452629 -0.401052 0.79642 + outer loop + vertex 390.222 186.354 407.677 + vertex 388.717 184.378 407.537 + vertex 390.016 182.787 405.998 + endloop + endfacet + facet normal 0.44764 -0.397576 0.800969 + outer loop + vertex 390.222 186.354 407.677 + vertex 389.577 186.828 408.272 + vertex 388.717 184.378 407.537 + endloop + endfacet + facet normal 0.404356 -0.390246 0.827167 + outer loop + vertex 388.717 184.378 407.537 + vertex 389.577 186.828 408.272 + vertex 387.965 185.509 408.438 + endloop + endfacet + facet normal 0.476641 -0.395231 0.785242 + outer loop + vertex 390.721 178.235 403.278 + vertex 390.016 182.787 405.998 + vertex 388.65 176.02 403.421 + endloop + endfacet + facet normal 0.354411 -0.229295 0.906541 + outer loop + vertex 406.842 116.521 370.751 + vertex 407.473 119.49 371.255 + vertex 404.744 121.142 372.74 + endloop + endfacet + facet normal 0.361903 -0.216981 0.906612 + outer loop + vertex 406.101 125.522 373.247 + vertex 404.744 121.142 372.74 + vertex 407.473 119.49 371.255 + endloop + endfacet + facet normal 0.369893 -0.214307 0.90402 + outer loop + vertex 408.779 122.278 371.382 + vertex 406.101 125.522 373.247 + vertex 407.473 119.49 371.255 + endloop + endfacet + facet normal 0.345187 -0.203286 0.916254 + outer loop + vertex 409.768 117.725 369.999 + vertex 408.779 122.278 371.382 + vertex 407.473 119.49 371.255 + endloop + endfacet + facet normal 0.340915 -0.204611 0.917557 + outer loop + vertex 411.055 120.046 370.038 + vertex 408.779 122.278 371.382 + vertex 409.768 117.725 369.999 + endloop + endfacet + facet normal 0.354864 -0.189188 0.915576 + outer loop + vertex 408.779 122.278 371.382 + vertex 411.055 120.046 370.038 + vertex 410.207 123.925 371.168 + endloop + endfacet + facet normal 0.368087 -0.20168 0.907655 + outer loop + vertex 410.207 123.925 371.168 + vertex 407.824 127.635 372.959 + vertex 408.779 122.278 371.382 + endloop + endfacet + facet normal 0.339492 -0.193955 0.920395 + outer loop + vertex 412.663 121.987 369.854 + vertex 410.207 123.925 371.168 + vertex 411.055 120.046 370.038 + endloop + endfacet + facet normal 0.389775 -0.195533 0.899912 + outer loop + vertex 408.779 122.278 371.382 + vertex 407.824 127.635 372.959 + vertex 406.101 125.522 373.247 + endloop + endfacet + facet normal 0.407209 -0.228432 0.884308 + outer loop + vertex 406.101 125.522 373.247 + vertex 403.292 129.62 375.598 + vertex 404.744 121.142 372.74 + endloop + endfacet + facet normal 0.405159 -0.229047 0.88509 + outer loop + vertex 404.744 121.142 372.74 + vertex 403.292 129.62 375.598 + vertex 401.637 125.732 375.35 + endloop + endfacet + facet normal 0.445669 -0.244753 0.86109 + outer loop + vertex 403.292 129.62 375.598 + vertex 400.837 134.287 378.196 + vertex 401.637 125.732 375.35 + endloop + endfacet + facet normal 0.446976 -0.244435 0.860502 + outer loop + vertex 401.637 125.732 375.35 + vertex 400.837 134.287 378.196 + vertex 399.152 130.601 378.024 + endloop + endfacet + facet normal 0.484241 -0.260286 0.835321 + outer loop + vertex 400.837 134.287 378.196 + vertex 398.947 139.187 380.818 + vertex 399.152 130.601 378.024 + endloop + endfacet + facet normal 0.485528 -0.260037 0.834652 + outer loop + vertex 399.152 130.601 378.024 + vertex 398.947 139.187 380.818 + vertex 397.265 135.662 380.698 + endloop + endfacet + facet normal 0.516992 -0.27424 0.810871 + outer loop + vertex 398.947 139.187 380.818 + vertex 397.517 144.095 383.39 + vertex 397.265 135.662 380.698 + endloop + endfacet + facet normal 0.51893 -0.273935 0.809735 + outer loop + vertex 397.265 135.662 380.698 + vertex 397.517 144.095 383.39 + vertex 395.838 140.92 383.391 + endloop + endfacet + facet normal 0.541042 -0.285636 0.791003 + outer loop + vertex 397.517 144.095 383.39 + vertex 396.405 149.328 386.04 + vertex 395.838 140.92 383.391 + endloop + endfacet + facet normal 0.544175 -0.285218 0.789002 + outer loop + vertex 395.838 140.92 383.391 + vertex 396.405 149.328 386.04 + vertex 394.697 146.329 386.134 + endloop + endfacet + facet normal 0.561233 -0.295434 0.773134 + outer loop + vertex 396.405 149.328 386.04 + vertex 395.447 154.6 388.749 + vertex 394.697 146.329 386.134 + endloop + endfacet + facet normal 0.562702 -0.295251 0.772135 + outer loop + vertex 394.697 146.329 386.134 + vertex 395.447 154.6 388.749 + vertex 393.742 151.735 388.897 + endloop + endfacet + facet normal 0.579776 -0.306304 0.755009 + outer loop + vertex 395.447 154.6 388.749 + vertex 394.65 159.676 391.421 + vertex 393.742 151.735 388.897 + endloop + endfacet + facet normal 0.577466 -0.306568 0.75667 + outer loop + vertex 393.742 151.735 388.897 + vertex 394.65 159.676 391.421 + vertex 392.958 157.124 391.678 + endloop + endfacet + facet normal 0.593681 -0.319122 0.738718 + outer loop + vertex 394.65 159.676 391.421 + vertex 394.032 165 394.217 + vertex 392.958 157.124 391.678 + endloop + endfacet + facet normal 0.593305 -0.319162 0.739002 + outer loop + vertex 392.958 157.124 391.678 + vertex 394.032 165 394.217 + vertex 392.333 162.555 394.526 + endloop + endfacet + facet normal 0.610255 -0.333518 0.718578 + outer loop + vertex 394.032 165 394.217 + vertex 393.494 170.436 397.197 + vertex 392.333 162.555 394.526 + endloop + endfacet + facet normal 0.599324 -0.334805 0.727129 + outer loop + vertex 392.333 162.555 394.526 + vertex 393.494 170.436 397.197 + vertex 391.801 167.946 397.447 + endloop + endfacet + facet normal 0.615184 -0.347545 0.707645 + outer loop + vertex 393.494 170.436 397.197 + vertex 392.951 175.464 400.139 + vertex 391.801 167.946 397.447 + endloop + endfacet + facet normal 0.587615 -0.350993 0.729049 + outer loop + vertex 391.801 167.946 397.447 + vertex 392.951 175.464 400.139 + vertex 391.292 173.225 400.398 + endloop + endfacet + facet normal 0.598328 -0.360486 0.715579 + outer loop + vertex 392.951 175.464 400.139 + vertex 392.412 180.056 402.903 + vertex 391.292 173.225 400.398 + endloop + endfacet + facet normal 0.558271 -0.364768 0.74517 + outer loop + vertex 391.292 173.225 400.398 + vertex 392.412 180.056 402.903 + vertex 390.721 178.235 403.278 + endloop + endfacet + facet normal 0.564425 -0.372204 0.73681 + outer loop + vertex 392.412 180.056 402.903 + vertex 391.857 184.12 405.381 + vertex 390.721 178.235 403.278 + endloop + endfacet + facet normal 0.5266 -0.374352 0.763252 + outer loop + vertex 390.721 178.235 403.278 + vertex 391.857 184.12 405.381 + vertex 390.016 182.787 405.998 + endloop + endfacet + facet normal 0.531643 -0.38554 0.754132 + outer loop + vertex 390.016 182.787 405.998 + vertex 391.857 184.12 405.381 + vertex 391.406 186.969 407.156 + endloop + endfacet + facet normal 0.532056 -0.385589 0.753815 + outer loop + vertex 391.406 186.969 407.156 + vertex 390.222 186.354 407.677 + vertex 390.016 182.787 405.998 + endloop + endfacet + facet normal 0.527265 -0.364919 0.767349 + outer loop + vertex 391.406 186.969 407.156 + vertex 390.884 188.076 408.04 + vertex 390.222 186.354 407.677 + endloop + endfacet + facet normal 0.480567 -0.354299 0.802202 + outer loop + vertex 390.222 186.354 407.677 + vertex 390.884 188.076 408.04 + vertex 389.577 186.828 408.272 + endloop + endfacet + facet normal 0.324314 -0.224983 0.918805 + outer loop + vertex 408.717 115.236 369.774 + vertex 407.473 119.49 371.255 + vertex 406.842 116.521 370.751 + endloop + endfacet + facet normal 0.309157 -0.273949 0.910699 + outer loop + vertex 404.908 112.742 370.311 + vertex 405.623 115.103 370.778 + vertex 402.871 117.303 372.374 + endloop + endfacet + facet normal 0.321863 -0.297164 0.898943 + outer loop + vertex 402.871 117.303 372.374 + vertex 399.67 122.097 375.105 + vertex 400.692 113.931 372.04 + endloop + endfacet + facet normal 0.26799 -0.303379 0.914408 + outer loop + vertex 404.621 107.617 368.731 + vertex 403.549 111.579 370.36 + vertex 402.661 109.364 369.885 + endloop + endfacet + facet normal 0.252978 -0.319431 0.913217 + outer loop + vertex 404.621 107.617 368.731 + vertex 402.661 109.364 369.885 + vertex 403.406 105.932 368.478 + endloop + endfacet + facet normal 0.231435 -0.329848 0.915226 + outer loop + vertex 405.373 104.239 367.371 + vertex 403.406 105.932 368.478 + vertex 404.134 102.547 367.074 + endloop + endfacet + facet normal 0.245513 -0.314607 0.916922 + outer loop + vertex 405.373 104.239 367.371 + vertex 404.621 107.617 368.731 + vertex 403.406 105.932 368.478 + endloop + endfacet + facet normal 0.261625 -0.30556 0.915525 + outer loop + vertex 405.788 109.413 368.997 + vertex 403.549 111.579 370.36 + vertex 404.621 107.617 368.731 + endloop + endfacet + facet normal 0.262235 -0.285273 0.921874 + outer loop + vertex 407.875 108.251 368.044 + vertex 406.814 111.263 369.278 + vertex 405.788 109.413 368.997 + endloop + endfacet + facet normal 0.233642 -0.31051 0.921409 + outer loop + vertex 408.408 105.334 366.97 + vertex 406.63 106.134 367.691 + vertex 407.004 103.12 366.58 + endloop + endfacet + facet normal 0.221138 -0.30353 0.926805 + outer loop + vertex 408.228 102.65 366.134 + vertex 408.408 105.334 366.97 + vertex 407.004 103.12 366.58 + endloop + endfacet + facet normal 0.264504 -0.284328 0.921518 + outer loop + vertex 408.598 110.349 368.483 + vertex 406.814 111.263 369.278 + vertex 407.875 108.251 368.044 + endloop + endfacet + facet normal 0.274937 -0.266058 0.923917 + outer loop + vertex 408.598 110.349 368.483 + vertex 407.769 113.113 369.526 + vertex 406.814 111.263 369.278 + endloop + endfacet + facet normal 0.309929 -0.245711 0.918461 + outer loop + vertex 408.717 115.236 369.774 + vertex 406.842 116.521 370.751 + vertex 407.769 113.113 369.526 + endloop + endfacet + facet normal 0.330886 -0.222458 0.917075 + outer loop + vertex 409.768 117.725 369.999 + vertex 407.473 119.49 371.255 + vertex 408.717 115.236 369.774 + endloop + endfacet + facet normal 0.327362 -0.197208 0.924091 + outer loop + vertex 411.641 116.577 369.09 + vertex 411.055 120.046 370.038 + vertex 409.768 117.725 369.999 + endloop + endfacet + facet normal 0.292974 -0.236033 0.926528 + outer loop + vertex 410.45 114.565 369.031 + vertex 409.718 112.099 368.634 + vertex 411.858 112.945 368.173 + endloop + endfacet + facet normal 0.320609 -0.198895 0.926095 + outer loop + vertex 412.384 118.758 369.302 + vertex 411.055 120.046 370.038 + vertex 411.641 116.577 369.09 + endloop + endfacet + facet normal 0.331489 -0.186913 0.924759 + outer loop + vertex 412.384 118.758 369.302 + vertex 412.663 121.987 369.854 + vertex 411.055 120.046 370.038 + endloop + endfacet + facet normal 0.252803 -0.117404 0.960368 + outer loop + vertex 418.06 121.737 368.038 + vertex 420.587 123.292 367.563 + vertex 418.443 125.256 368.368 + endloop + endfacet + facet normal 0.331079 -0.143078 0.932692 + outer loop + vertex 416.2 120.65 368.415 + vertex 416.443 124.192 368.873 + vertex 414.843 123.269 369.299 + endloop + endfacet + facet normal 0.236281 -0.137663 0.961884 + outer loop + vertex 417.383 118.303 367.713 + vertex 420 119.856 367.293 + vertex 418.06 121.737 368.038 + endloop + endfacet + facet normal 0.298573 -0.168076 0.93947 + outer loop + vertex 415.369 117.279 368.076 + vertex 416.2 120.65 368.415 + vertex 414.672 119.96 368.778 + endloop + endfacet + facet normal 0.222205 -0.160605 0.961681 + outer loop + vertex 416.388 114.858 367.368 + vertex 419.237 116.463 366.978 + vertex 417.383 118.303 367.713 + endloop + endfacet + facet normal 0.210583 -0.19135 0.958666 + outer loop + vertex 415.1 111.295 366.939 + vertex 418.281 113.068 366.595 + vertex 416.388 114.858 367.368 + endloop + endfacet + facet normal 0.201846 -0.226277 0.95292 + outer loop + vertex 413.092 107.244 366.403 + vertex 417.113 109.618 366.115 + vertex 415.1 111.295 366.939 + endloop + endfacet + facet normal 0.231713 -0.27235 0.933881 + outer loop + vertex 411.747 107.781 366.893 + vertex 410.928 106 366.577 + vertex 413.092 107.244 366.403 + endloop + endfacet + facet normal 0.228588 -0.278158 0.932939 + outer loop + vertex 409.619 104.763 366.503 + vertex 410.263 108.397 367.429 + vertex 408.408 105.334 366.97 + endloop + endfacet + facet normal 0.244087 -0.291392 0.924939 + outer loop + vertex 410.928 106 366.577 + vertex 410.13 104.331 366.262 + vertex 410.638 104.167 366.076 + endloop + endfacet + facet normal 0.233649 -0.317124 0.919152 + outer loop + vertex 410.13 104.331 366.262 + vertex 409.255 102.856 365.975 + vertex 410.638 104.167 366.076 + endloop + endfacet + facet normal 0.214831 -0.303566 0.928276 + outer loop + vertex 409.619 104.763 366.503 + vertex 408.408 105.334 366.97 + vertex 408.228 102.65 366.134 + endloop + endfacet + facet normal 0.199262 -0.315523 0.927761 + outer loop + vertex 409.255 102.856 365.975 + vertex 407.772 100.545 365.508 + vertex 409.225 101.525 365.529 + endloop + endfacet + facet normal 0.212196 -0.322633 0.922432 + outer loop + vertex 408.228 102.65 366.134 + vertex 407.004 103.12 366.58 + vertex 406.81 100.546 365.725 + endloop + endfacet + facet normal 0.183244 -0.326586 0.927234 + outer loop + vertex 407.772 100.545 365.508 + vertex 406.037 98.1051 364.991 + vertex 407.444 98.681 364.916 + endloop + endfacet + facet normal 0.207344 -0.335813 0.918824 + outer loop + vertex 406.81 100.546 365.725 + vertex 405.719 101.296 366.245 + vertex 405.641 99.1601 365.482 + endloop + endfacet + facet normal 0.197604 -0.350093 0.915635 + outer loop + vertex 405.641 99.1601 365.482 + vertex 404.541 99.6998 365.926 + vertex 404.669 97.5996 365.095 + endloop + endfacet + facet normal 0.171442 -0.347843 0.921745 + outer loop + vertex 406.037 98.1051 364.991 + vertex 404.468 95.5716 364.327 + vertex 405.941 96.1672 364.278 + endloop + endfacet + facet normal 0.192501 -0.360301 0.912758 + outer loop + vertex 404.669 97.5996 365.095 + vertex 403.416 98.2646 365.622 + vertex 403.634 96.459 364.863 + endloop + endfacet + facet normal 0.192645 -0.360275 0.912738 + outer loop + vertex 403.634 96.459 364.863 + vertex 403.416 98.2646 365.622 + vertex 402.398 97.0414 365.354 + endloop + endfacet + facet normal 0.153768 -0.376437 0.913592 + outer loop + vertex 404.468 95.5716 364.327 + vertex 403.337 92.4562 363.234 + vertex 405.131 94.2553 363.673 + endloop + endfacet + facet normal 0.190663 -0.375204 0.907122 + outer loop + vertex 402.166 94.6746 364.43 + vertex 401.52 96.2001 365.197 + vertex 400.829 95.9629 365.244 + endloop + endfacet + facet normal 0.186479 -0.379079 0.90638 + outer loop + vertex 402.166 94.6746 364.43 + vertex 400.829 95.9629 365.244 + vertex 401.67 94.751 364.564 + endloop + endfacet + facet normal 0.185742 -0.372119 0.90941 + outer loop + vertex 403.634 96.459 364.863 + vertex 402.398 97.0414 365.354 + vertex 402.98 95.176 364.472 + endloop + endfacet + facet normal 0.199484 -0.367388 0.908423 + outer loop + vertex 401.52 96.2001 365.197 + vertex 400.647 98.4946 366.316 + vertex 399.715 97.9312 366.293 + endloop + endfacet + facet normal 0.1957 -0.362482 0.911212 + outer loop + vertex 403.416 98.2646 365.622 + vertex 401.739 99.587 366.508 + vertex 402.398 97.0414 365.354 + endloop + endfacet + facet normal 0.211323 -0.361546 0.90809 + outer loop + vertex 400.647 98.4946 366.316 + vertex 399.725 101.541 367.744 + vertex 398.617 100.648 367.646 + endloop + endfacet + facet normal 0.213812 -0.364446 0.906346 + outer loop + vertex 399.725 101.541 367.744 + vertex 397.815 103.701 369.063 + vertex 398.617 100.648 367.646 + endloop + endfacet + facet normal 0.210869 -0.354976 0.910783 + outer loop + vertex 402.92 100.988 366.781 + vertex 400.933 102.842 367.963 + vertex 401.739 99.587 366.508 + endloop + endfacet + facet normal 0.229182 -0.346206 0.909735 + outer loop + vertex 402.176 104.33 368.216 + vertex 400.219 106.252 369.441 + vertex 400.933 102.842 367.963 + endloop + endfacet + facet normal 0.254172 -0.335955 0.906935 + outer loop + vertex 400.219 106.252 369.441 + vertex 401.192 108.343 369.943 + vertex 398.334 110.924 371.7 + endloop + endfacet + facet normal 0.22546 -0.354769 0.907363 + outer loop + vertex 399.725 101.541 367.744 + vertex 398.745 105.456 369.518 + vertex 397.815 103.701 369.063 + endloop + endfacet + facet normal 0.259814 -0.349215 0.900303 + outer loop + vertex 398.334 110.924 371.7 + vertex 395.164 116.123 374.631 + vertex 396.086 108.534 371.421 + endloop + endfacet + facet normal 0.317679 -0.333198 0.887727 + outer loop + vertex 395.164 116.123 374.631 + vertex 394.904 124.002 377.682 + vertex 392.688 121.457 377.519 + endloop + endfacet + facet normal 0.32977 -0.343192 0.879472 + outer loop + vertex 394.904 124.002 377.682 + vertex 392.997 129.313 380.469 + vertex 392.688 121.457 377.519 + endloop + endfacet + facet normal 0.335543 -0.342675 0.877488 + outer loop + vertex 392.688 121.457 377.519 + vertex 392.997 129.313 380.469 + vertex 390.858 126.892 380.341 + endloop + endfacet + facet normal 0.34648 -0.351916 0.869544 + outer loop + vertex 392.997 129.313 380.469 + vertex 391.572 134.782 383.25 + vertex 390.858 126.892 380.341 + endloop + endfacet + facet normal 0.351251 -0.351677 0.867725 + outer loop + vertex 390.858 126.892 380.341 + vertex 391.572 134.782 383.25 + vertex 389.457 132.397 383.14 + endloop + endfacet + facet normal 0.360933 -0.359927 0.860337 + outer loop + vertex 391.572 134.782 383.25 + vertex 390.425 140.323 386.05 + vertex 389.457 132.397 383.14 + endloop + endfacet + facet normal 0.360504 -0.359938 0.860512 + outer loop + vertex 389.457 132.397 383.14 + vertex 390.425 140.323 386.05 + vertex 388.328 137.991 385.953 + endloop + endfacet + facet normal 0.369325 -0.367578 0.853513 + outer loop + vertex 390.425 140.323 386.05 + vertex 389.486 145.914 388.864 + vertex 388.328 137.991 385.953 + endloop + endfacet + facet normal 0.367381 -0.367599 0.854343 + outer loop + vertex 388.328 137.991 385.953 + vertex 389.486 145.914 388.864 + vertex 387.394 143.625 388.779 + endloop + endfacet + facet normal 0.377068 -0.37616 0.846359 + outer loop + vertex 389.486 145.914 388.864 + vertex 388.728 151.512 391.69 + vertex 387.394 143.625 388.779 + endloop + endfacet + facet normal 0.372586 -0.376137 0.848352 + outer loop + vertex 387.394 143.625 388.779 + vertex 388.728 151.512 391.69 + vertex 386.643 149.286 391.618 + endloop + endfacet + facet normal 0.383721 -0.386262 0.838785 + outer loop + vertex 388.728 151.512 391.69 + vertex 388.13 157.158 394.563 + vertex 386.643 149.286 391.618 + endloop + endfacet + facet normal 0.375079 -0.386114 0.842752 + outer loop + vertex 386.643 149.286 391.618 + vertex 388.13 157.158 394.563 + vertex 386.046 155.028 394.515 + endloop + endfacet + facet normal 0.385811 -0.396391 0.833081 + outer loop + vertex 388.13 157.158 394.563 + vertex 387.619 162.896 397.53 + vertex 386.046 155.028 394.515 + endloop + endfacet + facet normal 0.372146 -0.396088 0.839417 + outer loop + vertex 386.046 155.028 394.515 + vertex 387.619 162.896 397.53 + vertex 385.527 160.883 397.507 + endloop + endfacet + facet normal 0.36394 -0.404543 0.838983 + outer loop + vertex 385.527 160.883 397.507 + vertex 387.093 168.597 400.548 + vertex 385.032 166.72 400.537 + endloop + endfacet + facet normal 0.352007 -0.410745 0.841059 + outer loop + vertex 385.032 166.72 400.537 + vertex 386.485 173.745 403.359 + vertex 384.574 172.182 403.396 + endloop + endfacet + facet normal 0.355626 -0.415254 0.837314 + outer loop + vertex 386.485 173.745 403.359 + vertex 385.86 177.384 405.43 + vertex 384.574 172.182 403.396 + endloop + endfacet + facet normal 0.338256 -0.411604 0.846266 + outer loop + vertex 386.322 181.851 407.415 + vertex 385.644 183.982 408.722 + vertex 383.995 181.067 407.964 + endloop + endfacet + facet normal 0.325824 -0.406475 0.853591 + outer loop + vertex 383.995 181.067 407.964 + vertex 385.644 183.982 408.722 + vertex 383.333 182.88 409.08 + endloop + endfacet + facet normal 0.308895 -0.415612 0.855483 + outer loop + vertex 383.049 171.361 403.575 + vertex 384.288 177.177 405.953 + vertex 382.443 176.97 406.519 + endloop + endfacet + facet normal 0.313283 -0.414567 0.854393 + outer loop + vertex 383.049 171.361 403.575 + vertex 382.443 176.97 406.519 + vertex 382.018 170.807 403.684 + endloop + endfacet + facet normal 0.302709 -0.417022 0.857007 + outer loop + vertex 383.995 181.067 407.964 + vertex 383.333 182.88 409.08 + vertex 382.315 180.93 408.491 + endloop + endfacet + facet normal 0.27915 -0.408364 0.869088 + outer loop + vertex 382.315 180.93 408.491 + vertex 383.333 182.88 409.08 + vertex 381.344 181.86 409.239 + endloop + endfacet + facet normal 0.245005 -0.424312 0.871741 + outer loop + vertex 379.863 180.729 409.127 + vertex 380.191 181.347 409.336 + vertex 379.768 181.435 409.497 + endloop + endfacet + facet normal 0.247347 -0.425189 0.870651 + outer loop + vertex 380.884 179.713 408.341 + vertex 380.191 181.347 409.336 + vertex 379.863 180.729 409.127 + endloop + endfacet + facet normal 0.281094 -0.415049 0.865286 + outer loop + vertex 381.139 175.46 406.218 + vertex 382.443 176.97 406.519 + vertex 380.884 179.713 408.341 + endloop + endfacet + facet normal 0.283466 -0.416778 0.86368 + outer loop + vertex 382.018 170.807 403.684 + vertex 382.443 176.97 406.519 + vertex 381.139 175.46 406.218 + endloop + endfacet + facet normal 0.313449 -0.414923 0.85416 + outer loop + vertex 382.434 164.956 400.689 + vertex 383.049 171.361 403.575 + vertex 382.018 170.807 403.684 + endloop + endfacet + facet normal 0.320988 -0.411428 0.853049 + outer loop + vertex 382.811 158.95 397.651 + vertex 383.44 165.496 400.571 + vertex 382.434 164.956 400.689 + endloop + endfacet + facet normal 0.321152 -0.405064 0.856028 + outer loop + vertex 383.301 153.034 394.668 + vertex 383.876 159.52 397.521 + vertex 382.811 158.95 397.651 + endloop + endfacet + facet normal 0.323439 -0.39686 0.859005 + outer loop + vertex 383.925 147.173 391.725 + vertex 384.39 153.588 394.513 + vertex 383.301 153.034 394.668 + endloop + endfacet + facet normal 0.325143 -0.388933 0.861982 + outer loop + vertex 384.669 141.406 388.842 + vertex 384.995 147.777 391.594 + vertex 383.925 147.173 391.725 + endloop + endfacet + facet normal 0.319857 -0.382325 0.866902 + outer loop + vertex 385.578 135.749 386.012 + vertex 385.738 142.07 388.741 + vertex 384.669 141.406 388.842 + endloop + endfacet + facet normal 0.312651 -0.376641 0.872004 + outer loop + vertex 386.683 130.124 383.186 + vertex 386.677 136.427 385.911 + vertex 385.578 135.749 386.012 + endloop + endfacet + facet normal 0.305859 -0.371203 0.876732 + outer loop + vertex 387.976 124.543 380.372 + vertex 387.789 130.799 383.086 + vertex 386.683 130.124 383.186 + endloop + endfacet + facet normal 0.294883 -0.366013 0.882654 + outer loop + vertex 389.548 119.004 377.55 + vertex 389.126 125.242 380.278 + vertex 387.976 124.543 380.372 + endloop + endfacet + facet normal 0.277273 -0.361685 0.890114 + outer loop + vertex 391.627 113.39 374.621 + vertex 390.84 119.733 377.443 + vertex 389.548 119.004 377.55 + endloop + endfacet + facet normal 0.258976 -0.358729 0.896797 + outer loop + vertex 394.44 107.284 371.366 + vertex 393.148 114.16 374.49 + vertex 391.627 113.39 374.621 + endloop + endfacet + facet normal 0.225343 -0.368691 0.901825 + outer loop + vertex 396.069 103.063 369.233 + vertex 396.596 103.661 369.346 + vertex 394.44 107.284 371.366 + endloop + endfacet + facet normal 0.222511 -0.361699 0.905353 + outer loop + vertex 398.617 100.648 367.646 + vertex 397.815 103.701 369.063 + vertex 396.596 103.661 369.346 + endloop + endfacet + facet normal 0.201263 -0.370268 0.90686 + outer loop + vertex 400.647 98.4946 366.316 + vertex 398.617 100.648 367.646 + vertex 399.715 97.9312 366.293 + endloop + endfacet + facet normal 0.19077 -0.375548 0.906957 + outer loop + vertex 401.52 96.2001 365.197 + vertex 399.715 97.9312 366.293 + vertex 400.829 95.9629 365.244 + endloop + endfacet + facet normal 0.198256 -0.371308 0.907097 + outer loop + vertex 401.67 94.751 364.564 + vertex 400.829 95.9629 365.244 + vertex 400.415 96.1698 365.419 + endloop + endfacet + facet normal 0.183821 -0.389513 0.902491 + outer loop + vertex 402.166 94.6746 364.43 + vertex 401.67 94.751 364.564 + vertex 403.337 92.4562 363.234 + endloop + endfacet + facet normal 0.16788 -0.397605 0.902068 + outer loop + vertex 400.937 93.9263 364.357 + vertex 399.2 96.0452 365.614 + vertex 398.645 94.2863 364.942 + endloop + endfacet + facet normal 0.199013 -0.37386 0.905882 + outer loop + vertex 399.086 97.5381 366.279 + vertex 400.826 95.4702 365.043 + vertex 399.013 97.9871 366.48 + endloop + endfacet + facet normal 0.177166 -0.393919 0.901909 + outer loop + vertex 399.2 96.0452 365.614 + vertex 397.285 98.6298 367.119 + vertex 396.73 96.8033 366.43 + endloop + endfacet + facet normal 0.204346 -0.372682 0.90518 + outer loop + vertex 397.391 99.888 367.629 + vertex 399.086 97.5381 366.279 + vertex 399.013 97.9871 366.48 + endloop + endfacet + facet normal 0.187826 -0.388069 0.902288 + outer loop + vertex 397.285 98.6298 367.119 + vertex 395.298 101.791 368.892 + vertex 394.814 99.8159 368.144 + endloop + endfacet + facet normal 0.202182 -0.37597 0.904306 + outer loop + vertex 396.025 101.883 368.764 + vertex 397.391 99.888 367.629 + vertex 396.318 102.094 368.786 + endloop + endfacet + facet normal 0.204561 -0.379082 0.90247 + outer loop + vertex 394.558 104.208 370.073 + vertex 396.025 101.883 368.764 + vertex 396.318 102.094 368.786 + endloop + endfacet + facet normal 0.197727 -0.38516 0.901419 + outer loop + vertex 395.298 101.791 368.892 + vertex 393.236 105.108 370.762 + vertex 392.917 103.093 369.971 + endloop + endfacet + facet normal 0.201482 -0.382537 0.901704 + outer loop + vertex 393.044 106.758 371.493 + vertex 394.558 104.208 370.073 + vertex 392.951 108.078 372.074 + endloop + endfacet + facet normal 0.210352 -0.380769 0.900426 + outer loop + vertex 393.236 105.108 370.762 + vertex 391.805 108.24 372.421 + vertex 391.297 106.419 371.769 + endloop + endfacet + facet normal 0.203555 -0.382241 0.901364 + outer loop + vertex 392.349 108.268 372.29 + vertex 393.044 106.758 371.493 + vertex 392.951 108.078 372.074 + endloop + endfacet + facet normal 0.20018 -0.390011 0.898788 + outer loop + vertex 391.527 110.16 373.294 + vertex 392.349 108.268 372.29 + vertex 392.951 108.078 372.074 + endloop + endfacet + facet normal 0.223595 -0.378871 0.898032 + outer loop + vertex 391.805 108.24 372.421 + vertex 390.864 110.648 373.671 + vertex 390.015 109.997 373.607 + endloop + endfacet + facet normal 0.222319 -0.382731 0.896711 + outer loop + vertex 390.454 112.314 374.479 + vertex 391.527 110.16 373.294 + vertex 390.5 113.691 375.056 + endloop + endfacet + facet normal 0.226129 -0.381988 0.896075 + outer loop + vertex 389.462 112.372 374.76 + vertex 390.015 109.997 373.607 + vertex 390.864 110.648 373.671 + endloop + endfacet + facet normal 0.232277 -0.382113 0.894448 + outer loop + vertex 389.201 114.883 375.902 + vertex 390.454 112.314 374.479 + vertex 390.5 113.691 375.056 + endloop + endfacet + facet normal 0.214889 -0.390914 0.894991 + outer loop + vertex 389.462 112.372 374.76 + vertex 386.906 114.856 376.458 + vertex 387.326 111.395 374.846 + endloop + endfacet + facet normal 0.23194 -0.38488 0.893348 + outer loop + vertex 388.03 117.293 377.245 + vertex 389.201 114.883 375.902 + vertex 388.52 119.148 377.917 + endloop + endfacet + facet normal 0.20778 -0.3958 0.894522 + outer loop + vertex 385.991 118.855 378.44 + vertex 382.309 116.449 378.231 + vertex 386.906 114.856 376.458 + endloop + endfacet + facet normal 0.237893 -0.38575 0.891406 + outer loop + vertex 387.76 119.055 378.079 + vertex 388.03 117.293 377.245 + vertex 388.52 119.148 377.917 + endloop + endfacet + facet normal 0.237943 -0.387505 0.890631 + outer loop + vertex 387.16 121.286 379.21 + vertex 387.76 119.055 378.079 + vertex 388.52 119.148 377.917 + endloop + endfacet + facet normal 0.212677 -0.397979 0.892402 + outer loop + vertex 384.957 122.928 380.503 + vertex 381.478 120.329 380.173 + vertex 385.991 118.855 378.44 + endloop + endfacet + facet normal 0.243117 -0.387972 0.889029 + outer loop + vertex 386.619 123.628 380.38 + vertex 387.16 121.286 379.21 + vertex 387.086 124.798 380.763 + endloop + endfacet + facet normal 0.247804 -0.38924 0.887178 + outer loop + vertex 385.893 126.01 381.628 + vertex 386.619 123.628 380.38 + vertex 387.086 124.798 380.763 + endloop + endfacet + facet normal 0.216176 -0.402017 0.889747 + outer loop + vertex 383.773 126.58 382.441 + vertex 380.578 124.16 382.124 + vertex 384.957 122.928 380.503 + endloop + endfacet + facet normal 0.246689 -0.391984 0.88628 + outer loop + vertex 385.133 128.558 382.967 + vertex 385.893 126.01 381.628 + vertex 385.754 130.298 383.563 + endloop + endfacet + facet normal 0.219617 -0.401026 0.889352 + outer loop + vertex 383.324 130.203 384.185 + vertex 379.836 127.924 384.019 + vertex 383.773 126.58 382.441 + endloop + endfacet + facet normal 0.252284 -0.39325 0.884142 + outer loop + vertex 385.056 130.254 383.743 + vertex 385.133 128.558 382.967 + vertex 385.754 130.298 383.563 + endloop + endfacet + facet normal 0.252239 -0.394191 0.883736 + outer loop + vertex 384.594 132.503 384.878 + vertex 385.056 130.254 383.743 + vertex 385.754 130.298 383.563 + endloop + endfacet + facet normal 0.223396 -0.403955 0.887082 + outer loop + vertex 382.656 134.315 386.226 + vertex 379.233 131.803 385.944 + vertex 383.324 130.203 384.185 + endloop + endfacet + facet normal 0.254657 -0.39592 0.882268 + outer loop + vertex 384.226 134.858 386.041 + vertex 384.594 132.503 384.878 + vertex 384.745 136.002 386.404 + endloop + endfacet + facet normal 0.260707 -0.39783 0.879638 + outer loop + vertex 383.79 137.247 387.25 + vertex 384.226 134.858 386.041 + vertex 384.745 136.002 386.404 + endloop + endfacet + facet normal 0.225292 -0.407728 0.884873 + outer loop + vertex 381.955 138.43 388.301 + vertex 378.621 135.832 387.952 + vertex 382.656 134.315 386.226 + endloop + endfacet + facet normal 0.259536 -0.400432 0.878803 + outer loop + vertex 383.48 139.373 388.311 + vertex 383.79 137.247 387.25 + vertex 383.832 141.482 389.168 + endloop + endfacet + facet normal 0.262235 -0.400539 0.877953 + outer loop + vertex 383 140.921 389.16 + vertex 383.48 139.373 388.311 + vertex 383.832 141.482 389.168 + endloop + endfacet + facet normal 0.22608 -0.411568 0.882893 + outer loop + vertex 381.198 142.048 390.181 + vertex 378.049 139.83 389.953 + vertex 381.955 138.43 388.301 + endloop + endfacet + facet normal 0.263934 -0.403038 0.876298 + outer loop + vertex 382.787 143.867 390.579 + vertex 383 140.921 389.16 + vertex 383.832 141.482 389.168 + endloop + endfacet + facet normal 0.227092 -0.41039 0.883182 + outer loop + vertex 381.043 145.784 391.957 + vertex 377.611 143.748 391.893 + vertex 381.198 142.048 390.181 + endloop + endfacet + facet normal 0.261766 -0.404953 0.876066 + outer loop + vertex 382.632 146.116 391.666 + vertex 382.787 143.867 390.579 + vertex 383.085 147.607 392.22 + endloop + endfacet + facet normal 0.263067 -0.405167 0.875577 + outer loop + vertex 382.28 147.692 392.501 + vertex 382.632 146.116 391.666 + vertex 383.085 147.607 392.22 + endloop + endfacet + facet normal 0.228641 -0.413944 0.881121 + outer loop + vertex 380.67 149.623 393.857 + vertex 377.288 147.639 393.802 + vertex 381.043 145.784 391.957 + endloop + endfacet + facet normal 0.262247 -0.408552 0.874249 + outer loop + vertex 382.336 149.864 393.498 + vertex 382.28 147.692 392.501 + vertex 383.085 147.607 392.22 + endloop + endfacet + facet normal 0.253816 -0.412286 0.874985 + outer loop + vertex 381.834 151.787 394.55 + vertex 382.336 149.864 393.498 + vertex 382.483 153.411 395.127 + endloop + endfacet + facet normal 0.22883 -0.418387 0.878971 + outer loop + vertex 380.347 153.418 395.747 + vertex 376.976 151.481 395.703 + vertex 380.67 149.623 393.857 + endloop + endfacet + facet normal 0.258039 -0.413355 0.873243 + outer loop + vertex 381.838 153.363 395.295 + vertex 381.834 151.787 394.55 + vertex 382.483 153.411 395.127 + endloop + endfacet + facet normal 0.257837 -0.417686 0.87124 + outer loop + vertex 381.65 155.555 396.402 + vertex 381.838 153.363 395.295 + vertex 382.483 153.411 395.127 + endloop + endfacet + facet normal 0.227496 -0.424007 0.876621 + outer loop + vertex 380.045 157.475 397.788 + vertex 376.725 155.347 397.621 + vertex 380.347 153.418 395.747 + endloop + endfacet + facet normal 0.264681 -0.41937 0.868373 + outer loop + vertex 381.533 157.917 397.578 + vertex 381.65 155.555 396.402 + vertex 382.098 159.183 398.017 + endloop + endfacet + facet normal 0.271574 -0.42137 0.865271 + outer loop + vertex 381.271 160.555 398.945 + vertex 381.533 157.917 397.578 + vertex 382.098 159.183 398.017 + endloop + endfacet + facet normal 0.222593 -0.429455 0.875226 + outer loop + vertex 379.453 161.492 399.91 + vertex 376.411 159.338 399.627 + vertex 380.045 157.475 397.788 + endloop + endfacet + facet normal 0.272797 -0.422638 0.864268 + outer loop + vertex 380.931 163.754 400.617 + vertex 381.271 160.555 398.945 + vertex 381.755 165.135 401.032 + endloop + endfacet + facet normal 0.214818 -0.429312 0.877237 + outer loop + vertex 379.221 165.475 401.916 + vertex 376.019 163.483 401.725 + vertex 379.453 161.492 399.91 + endloop + endfacet + facet normal 0.274317 -0.423303 0.863461 + outer loop + vertex 380.961 167.37 402.38 + vertex 380.931 163.754 400.617 + vertex 381.755 165.135 401.032 + endloop + endfacet + facet normal 0.207364 -0.427877 0.879728 + outer loop + vertex 379.16 169.819 404.043 + vertex 375.622 167.753 403.872 + vertex 379.221 165.475 401.916 + endloop + endfacet + facet normal 0.285566 -0.421476 0.860703 + outer loop + vertex 380.892 170.104 403.742 + vertex 380.961 167.37 402.38 + vertex 381.358 170.899 403.977 + endloop + endfacet + facet normal 0.271909 -0.415615 0.867946 + outer loop + vertex 380.449 172.516 405.035 + vertex 380.892 170.104 403.742 + vertex 381.358 170.899 403.977 + endloop + endfacet + facet normal 0.200564 -0.430663 0.879945 + outer loop + vertex 378.416 173.604 406.065 + vertex 375.301 171.804 405.894 + vertex 379.16 169.819 404.043 + endloop + endfacet + facet normal 0.197868 -0.426258 0.882696 + outer loop + vertex 378.416 173.604 406.065 + vertex 375.488 174.859 407.327 + vertex 375.301 171.804 405.894 + endloop + endfacet + facet normal 0.245009 -0.418859 0.874373 + outer loop + vertex 379.77 175.02 406.425 + vertex 380.449 172.516 405.035 + vertex 380.531 174.958 406.182 + endloop + endfacet + facet normal 0.245533 -0.416407 0.875396 + outer loop + vertex 379.669 176.424 407.121 + vertex 379.77 175.02 406.425 + vertex 380.531 174.958 406.182 + endloop + endfacet + facet normal 0.198003 -0.417928 0.88664 + outer loop + vertex 379.603 181.16 409.363 + vertex 374.142 177.503 408.859 + vertex 379.276 178.101 407.994 + endloop + endfacet + facet normal 0.198766 -0.42471 0.88324 + outer loop + vertex 378.001 176.242 407.427 + vertex 375.488 174.859 407.327 + vertex 378.416 173.604 406.065 + endloop + endfacet + facet normal 0.178835 -0.426859 0.886459 + outer loop + vertex 375.488 174.859 407.327 + vertex 370.723 173.656 407.71 + vertex 375.301 171.804 405.894 + endloop + endfacet + facet normal 0.17575 -0.456658 0.87211 + outer loop + vertex 365.276 174.667 409.161 + vertex 374.142 177.503 408.859 + vertex 368.705 177.217 409.805 + endloop + endfacet + facet normal 0.146438 -0.422841 0.894294 + outer loop + vertex 368.705 177.217 409.805 + vertex 360.682 174.892 410.019 + vertex 365.276 174.667 409.161 + endloop + endfacet + facet normal 0.151493 -0.441185 0.884537 + outer loop + vertex 367.27 177.283 410.084 + vertex 360.682 174.892 410.019 + vertex 368.705 177.217 409.805 + endloop + endfacet + facet normal 0.156871 -0.40082 0.902627 + outer loop + vertex 367.27 177.283 410.084 + vertex 368.705 177.217 409.805 + vertex 373.062 179.09 409.879 + endloop + endfacet + facet normal -0.187099 0.68004 0.7089 + outer loop + vertex 373.675 179.293 409.846 + vertex 367.27 177.283 410.084 + vertex 373.062 179.09 409.879 + endloop + endfacet + facet normal -0.0281874 -0.0785762 -0.99651 + outer loop + vertex 373.675 179.293 409.846 + vertex 373.062 179.09 409.879 + vertex 377.907 180.874 409.601 + endloop + endfacet + facet normal -0.212122 0.432139 -0.876504 + outer loop + vertex 378.07 180.847 409.548 + vertex 373.675 179.293 409.846 + vertex 377.907 180.874 409.601 + endloop + endfacet + facet normal -0.233722 0.357251 -0.904293 + outer loop + vertex 378.07 180.847 409.548 + vertex 377.907 180.874 409.601 + vertex 382.516 182.877 409.201 + endloop + endfacet + facet normal -0.0608431 -0.0372867 -0.997451 + outer loop + vertex 382.688 182.928 409.189 + vertex 378.07 180.847 409.548 + vertex 382.516 182.877 409.201 + endloop + endfacet + facet normal -0.187289 0.251624 -0.94953 + outer loop + vertex 378.27 180.857 409.512 + vertex 378.07 180.847 409.548 + vertex 382.688 182.928 409.189 + endloop + endfacet + facet normal 0.294719 -0.502063 0.813064 + outer loop + vertex 382.755 183.054 409.243 + vertex 378.27 180.857 409.512 + vertex 382.688 182.928 409.189 + endloop + endfacet + facet normal 0.298297 -0.510142 0.806705 + outer loop + vertex 378.372 180.995 409.561 + vertex 378.27 180.857 409.512 + vertex 382.755 183.054 409.243 + endloop + endfacet + facet normal 0.252992 -0.402433 0.879797 + outer loop + vertex 382.722 183.379 409.401 + vertex 378.372 180.995 409.561 + vertex 382.755 183.054 409.243 + endloop + endfacet + facet normal 0.266469 -0.428112 0.863548 + outer loop + vertex 378.395 181.357 409.733 + vertex 378.372 180.995 409.561 + vertex 382.722 183.379 409.401 + endloop + endfacet + facet normal 0.249294 -0.387422 0.887557 + outer loop + vertex 382.65 183.954 409.672 + vertex 378.395 181.357 409.733 + vertex 382.722 183.379 409.401 + endloop + endfacet + facet normal 0.259251 -0.403975 0.877264 + outer loop + vertex 378.365 181.98 410.029 + vertex 378.395 181.357 409.733 + vertex 382.65 183.954 409.672 + endloop + endfacet + facet normal 0.251828 -0.386023 0.887451 + outer loop + vertex 382.556 184.735 410.038 + vertex 378.365 181.98 410.029 + vertex 382.65 183.954 409.672 + endloop + endfacet + facet normal 0.253438 -0.388468 0.885924 + outer loop + vertex 378.29 182.824 410.42 + vertex 378.365 181.98 410.029 + vertex 382.556 184.735 410.038 + endloop + endfacet + facet normal 0.2479 -0.374604 0.89343 + outer loop + vertex 382.442 185.636 410.447 + vertex 378.29 182.824 410.42 + vertex 382.556 184.735 410.038 + endloop + endfacet + facet normal 0.255322 -0.385497 0.886681 + outer loop + vertex 378.211 183.768 410.854 + vertex 378.29 182.824 410.42 + vertex 382.442 185.636 410.447 + endloop + endfacet + facet normal 0.249394 -0.3703 0.894807 + outer loop + vertex 382.352 186.574 410.861 + vertex 378.211 183.768 410.854 + vertex 382.442 185.636 410.447 + endloop + endfacet + facet normal 0.250832 -0.372419 0.893525 + outer loop + vertex 378.119 184.751 411.289 + vertex 378.211 183.768 410.854 + vertex 382.352 186.574 410.861 + endloop + endfacet + facet normal 0.245434 -0.358171 0.900819 + outer loop + vertex 382.286 187.518 411.254 + vertex 378.119 184.751 411.289 + vertex 382.352 186.574 410.861 + endloop + endfacet + facet normal 0.253148 -0.36988 0.893927 + outer loop + vertex 378.042 185.723 411.713 + vertex 378.119 184.751 411.289 + vertex 382.286 187.518 411.254 + endloop + endfacet + facet normal 0.241156 -0.33743 0.909937 + outer loop + vertex 382.219 188.459 411.621 + vertex 378.042 185.723 411.713 + vertex 382.286 187.518 411.254 + endloop + endfacet + facet normal 0.251574 -0.353634 0.900918 + outer loop + vertex 377.956 186.692 412.118 + vertex 378.042 185.723 411.713 + vertex 382.219 188.459 411.621 + endloop + endfacet + facet normal 0.245446 -0.336549 0.909115 + outer loop + vertex 382.156 189.408 411.989 + vertex 377.956 186.692 412.118 + vertex 382.219 188.459 411.621 + endloop + endfacet + facet normal 0.254106 -0.350297 0.901511 + outer loop + vertex 377.874 187.664 412.519 + vertex 377.956 186.692 412.118 + vertex 382.156 189.408 411.989 + endloop + endfacet + facet normal 0.246054 -0.327235 0.912346 + outer loop + vertex 382.095 190.385 412.356 + vertex 377.874 187.664 412.519 + vertex 382.156 189.408 411.989 + endloop + endfacet + facet normal 0.253491 -0.339154 0.905934 + outer loop + vertex 377.777 188.652 412.916 + vertex 377.874 187.664 412.519 + vertex 382.095 190.385 412.356 + endloop + endfacet + facet normal 0.245466 -0.315735 0.916547 + outer loop + vertex 382.021 191.394 412.724 + vertex 377.777 188.652 412.916 + vertex 382.095 190.385 412.356 + endloop + endfacet + facet normal 0.25467 -0.330525 0.908788 + outer loop + vertex 377.655 189.662 413.317 + vertex 377.777 188.652 412.916 + vertex 382.021 191.394 412.724 + endloop + endfacet + facet normal 0.242969 -0.295884 0.923807 + outer loop + vertex 381.896 192.428 413.088 + vertex 377.655 189.662 413.317 + vertex 382.021 191.394 412.724 + endloop + endfacet + facet normal 0.25532 -0.315641 0.913883 + outer loop + vertex 377.488 190.688 413.718 + vertex 377.655 189.662 413.317 + vertex 381.896 192.428 413.088 + endloop + endfacet + facet normal 0.247533 -0.292355 0.923718 + outer loop + vertex 381.737 193.475 413.462 + vertex 377.488 190.688 413.718 + vertex 381.896 192.428 413.088 + endloop + endfacet + facet normal 0.253314 -0.301588 0.919172 + outer loop + vertex 377.28 191.73 414.117 + vertex 377.488 190.688 413.718 + vertex 381.737 193.475 413.462 + endloop + endfacet + facet normal 0.242928 -0.270391 0.931598 + outer loop + vertex 381.522 194.541 413.827 + vertex 377.28 191.73 414.117 + vertex 381.737 193.475 413.462 + endloop + endfacet + facet normal 0.255568 -0.290449 0.92213 + outer loop + vertex 377.058 192.79 414.513 + vertex 377.28 191.73 414.117 + vertex 381.522 194.541 413.827 + endloop + endfacet + facet normal 0.24492 -0.25847 0.934456 + outer loop + vertex 381.303 195.638 414.188 + vertex 377.058 192.79 414.513 + vertex 381.522 194.541 413.827 + endloop + endfacet + facet normal 0.261193 -0.284086 0.922537 + outer loop + vertex 376.893 193.903 414.902 + vertex 377.058 192.79 414.513 + vertex 381.303 195.638 414.188 + endloop + endfacet + facet normal 0.253414 -0.260585 0.931599 + outer loop + vertex 381.149 196.806 414.556 + vertex 376.893 193.903 414.902 + vertex 381.303 195.638 414.188 + endloop + endfacet + facet normal 0.279874 -0.30178 0.911372 + outer loop + vertex 376.845 195.085 415.308 + vertex 376.893 193.903 414.902 + vertex 381.149 196.806 414.556 + endloop + endfacet + facet normal 0.296476 -0.353936 0.887035 + outer loop + vertex 381.107 198.043 415.064 + vertex 376.845 195.085 415.308 + vertex 381.149 196.806 414.556 + endloop + endfacet + facet normal 0.312411 -0.378181 0.871423 + outer loop + vertex 376.866 196.305 415.83 + vertex 376.845 195.085 415.308 + vertex 381.107 198.043 415.064 + endloop + endfacet + facet normal 0.364102 -0.560595 0.743749 + outer loop + vertex 380.841 199.141 416.022 + vertex 376.866 196.305 415.83 + vertex 381.107 198.043 415.064 + endloop + endfacet + facet normal 0.345613 -0.536451 0.769917 + outer loop + vertex 377.196 197.62 416.599 + vertex 376.866 196.305 415.83 + vertex 380.841 199.141 416.022 + endloop + endfacet + facet normal 0.2852 -0.535778 0.794735 + outer loop + vertex 377.196 197.62 416.599 + vertex 371.772 194.6 416.509 + vertex 376.866 196.305 415.83 + endloop + endfacet + facet normal 0.2486 -0.389909 0.886662 + outer loop + vertex 371.772 194.6 416.509 + vertex 372.797 193.783 415.862 + vertex 376.866 196.305 415.83 + endloop + endfacet + facet normal 0.309457 -0.578155 0.754966 + outer loop + vertex 373.139 196.114 417.109 + vertex 371.772 194.6 416.509 + vertex 377.196 197.62 416.599 + endloop + endfacet + facet normal 0.240218 -0.536956 0.808686 + outer loop + vertex 373.139 196.114 417.109 + vertex 363.779 193.167 417.932 + vertex 371.772 194.6 416.509 + endloop + endfacet + facet normal 0.245515 -0.384896 0.889706 + outer loop + vertex 376.866 196.305 415.83 + vertex 372.797 193.783 415.862 + vertex 376.845 195.085 415.308 + endloop + endfacet + facet normal 0.243918 -0.378598 0.892842 + outer loop + vertex 372.797 193.783 415.862 + vertex 371.95 192.277 415.455 + vertex 376.845 195.085 415.308 + endloop + endfacet + facet normal 0.178925 -0.349281 0.919776 + outer loop + vertex 372.797 193.783 415.862 + vertex 365.874 191.157 416.211 + vertex 371.95 192.277 415.455 + endloop + endfacet + facet normal 0.183866 -0.387033 0.903548 + outer loop + vertex 365.874 191.157 416.211 + vertex 366.052 188.908 415.212 + vertex 371.95 192.277 415.455 + endloop + endfacet + facet normal 0.162472 -0.350934 0.922197 + outer loop + vertex 372.841 191.477 414.993 + vertex 371.95 192.277 415.455 + vertex 366.052 188.908 415.212 + endloop + endfacet + facet normal 0.156492 -0.334528 0.929301 + outer loop + vertex 372.841 191.477 414.993 + vertex 366.052 188.908 415.212 + vertex 372.135 190.068 414.605 + endloop + endfacet + facet normal 0.215112 -0.358186 0.908532 + outer loop + vertex 372.841 191.477 414.993 + vertex 372.135 190.068 414.605 + vertex 377.058 192.79 414.513 + endloop + endfacet + facet normal 0.161665 -0.368966 0.915275 + outer loop + vertex 366.052 188.908 415.212 + vertex 366.18 186.727 414.31 + vertex 372.135 190.068 414.605 + endloop + endfacet + facet normal 0.151303 -0.351267 0.923969 + outer loop + vertex 373.181 189.347 414.16 + vertex 372.135 190.068 414.605 + vertex 366.18 186.727 414.31 + endloop + endfacet + facet normal 0.149195 -0.345491 0.926486 + outer loop + vertex 373.181 189.347 414.16 + vertex 366.18 186.727 414.31 + vertex 372.49 187.97 413.757 + endloop + endfacet + facet normal 0.207761 -0.368885 0.905958 + outer loop + vertex 373.181 189.347 414.16 + vertex 372.49 187.97 413.757 + vertex 377.488 190.688 413.718 + endloop + endfacet + facet normal 0.153859 -0.374577 0.914341 + outer loop + vertex 366.18 186.727 414.31 + vertex 366.444 184.611 413.399 + vertex 372.49 187.97 413.757 + endloop + endfacet + facet normal 0.151571 -0.370667 0.916314 + outer loop + vertex 373.526 187.286 413.31 + vertex 372.49 187.97 413.757 + vertex 366.444 184.611 413.399 + endloop + endfacet + facet normal 0.149251 -0.364433 0.919191 + outer loop + vertex 373.526 187.286 413.31 + vertex 366.444 184.611 413.399 + vertex 372.781 185.929 412.893 + endloop + endfacet + facet normal 0.208481 -0.390107 0.896857 + outer loop + vertex 373.526 187.286 413.31 + vertex 372.781 185.929 412.893 + vertex 377.777 188.652 412.916 + endloop + endfacet + facet normal 0.152586 -0.383691 0.910768 + outer loop + vertex 366.444 184.611 413.399 + vertex 366.706 182.541 412.483 + vertex 372.781 185.929 412.893 + endloop + endfacet + facet normal 0.151755 -0.382289 0.911496 + outer loop + vertex 373.775 185.277 412.454 + vertex 372.781 185.929 412.893 + vertex 366.706 182.541 412.483 + endloop + endfacet + facet normal 0.150466 -0.378942 0.913106 + outer loop + vertex 373.775 185.277 412.454 + vertex 366.706 182.541 412.483 + vertex 372.999 183.93 412.022 + endloop + endfacet + facet normal 0.20857 -0.405044 0.89019 + outer loop + vertex 373.775 185.277 412.454 + vertex 372.999 183.93 412.022 + vertex 377.956 186.692 412.118 + endloop + endfacet + facet normal 0.153951 -0.39757 0.904565 + outer loop + vertex 366.706 182.541 412.483 + vertex 366.86 180.571 411.591 + vertex 372.999 183.93 412.022 + endloop + endfacet + facet normal 0.152842 -0.395673 0.905584 + outer loop + vertex 373.966 183.292 411.58 + vertex 372.999 183.93 412.022 + vertex 366.86 180.571 411.591 + endloop + endfacet + facet normal 0.150118 -0.388545 0.909119 + outer loop + vertex 373.966 183.292 411.58 + vertex 366.86 180.571 411.591 + vertex 373.157 181.954 411.142 + endloop + endfacet + facet normal 0.208138 -0.415838 0.885301 + outer loop + vertex 373.966 183.292 411.58 + vertex 373.157 181.954 411.142 + vertex 378.119 184.751 411.289 + endloop + endfacet + facet normal 0.153176 -0.40497 0.901408 + outer loop + vertex 366.86 180.571 411.591 + vertex 366.855 178.818 410.804 + vertex 373.157 181.954 411.142 + endloop + endfacet + facet normal 0.155594 -0.409561 0.898916 + outer loop + vertex 374.093 181.345 410.703 + vertex 373.157 181.954 411.142 + vertex 366.855 178.818 410.804 + endloop + endfacet + facet normal 0.152635 -0.400911 0.903312 + outer loop + vertex 374.093 181.345 410.703 + vertex 366.855 178.818 410.804 + vertex 373.201 180.183 410.338 + endloop + endfacet + facet normal 0.212959 -0.437812 0.873481 + outer loop + vertex 374.093 181.345 410.703 + vertex 373.201 180.183 410.338 + vertex 378.29 182.824 410.42 + endloop + endfacet + facet normal 0.154413 -0.410809 0.89855 + outer loop + vertex 366.855 178.818 410.804 + vertex 366.724 177.605 410.272 + vertex 373.201 180.183 410.338 + endloop + endfacet + facet normal 0.161131 -0.427458 0.88956 + outer loop + vertex 374.085 179.824 410.005 + vertex 373.201 180.183 410.338 + vertex 366.724 177.605 410.272 + endloop + endfacet + facet normal 0.152244 -0.396062 0.905514 + outer loop + vertex 374.085 179.824 410.005 + vertex 366.724 177.605 410.272 + vertex 373.116 179.124 409.862 + endloop + endfacet + facet normal 0.225925 -0.485535 0.84452 + outer loop + vertex 374.085 179.824 410.005 + vertex 373.116 179.124 409.862 + vertex 378.395 181.357 409.733 + endloop + endfacet + facet normal 0.14929 -0.381855 0.912085 + outer loop + vertex 366.724 177.605 410.272 + vertex 366.74 177.181 410.092 + vertex 373.116 179.124 409.862 + endloop + endfacet + facet normal 0.175358 -0.473169 0.863343 + outer loop + vertex 373.93 179.22 409.749 + vertex 373.116 179.124 409.862 + vertex 366.74 177.181 410.092 + endloop + endfacet + facet normal -0.217463 0.643356 -0.734032 + outer loop + vertex 373.93 179.22 409.749 + vertex 366.74 177.181 410.092 + vertex 372.915 178.961 409.823 + endloop + endfacet + facet normal -0.109011 0.146304 -0.983215 + outer loop + vertex 373.93 179.22 409.749 + vertex 372.915 178.961 409.823 + vertex 378.27 180.857 409.512 + endloop + endfacet + facet normal -0.0390649 0.280214 0.959142 + outer loop + vertex 366.74 177.181 410.092 + vertex 367.27 177.283 410.084 + vertex 372.915 178.961 409.823 + endloop + endfacet + facet normal -0.0137909 0.151669 0.988335 + outer loop + vertex 366.74 177.181 410.092 + vertex 358.086 174.815 410.334 + vertex 367.27 177.283 410.084 + endloop + endfacet + facet normal 0.086442 -0.216678 0.972409 + outer loop + vertex 356.631 174.717 410.442 + vertex 358.086 174.815 410.334 + vertex 366.74 177.181 410.092 + endloop + endfacet + facet normal 0.0915542 -0.327223 0.940501 + outer loop + vertex 356.631 174.717 410.442 + vertex 348.112 172.284 410.424 + vertex 358.086 174.815 410.334 + endloop + endfacet + facet normal 0.093186 -0.33374 0.938048 + outer loop + vertex 348.112 172.284 410.424 + vertex 352.663 172.84 410.17 + vertex 358.086 174.815 410.334 + endloop + endfacet + facet normal 0.121751 -0.409351 0.904217 + outer loop + vertex 358.086 174.815 410.334 + vertex 352.663 172.84 410.17 + vertex 360.682 174.892 410.019 + endloop + endfacet + facet normal 0.100983 -0.412537 0.905326 + outer loop + vertex 352.663 172.84 410.17 + vertex 348.112 172.284 410.424 + vertex 344.24 169.802 409.725 + endloop + endfacet + facet normal 0.0960126 -0.342792 0.934492 + outer loop + vertex 345.874 172.431 410.708 + vertex 348.112 172.284 410.424 + vertex 356.631 174.717 410.442 + endloop + endfacet + facet normal 0.107036 -0.397352 0.911403 + outer loop + vertex 356.588 175.282 410.693 + vertex 345.874 172.431 410.708 + vertex 356.631 174.717 410.442 + endloop + endfacet + facet normal 0.128282 -0.394966 0.909695 + outer loop + vertex 356.588 175.282 410.693 + vertex 356.631 174.717 410.442 + vertex 366.724 177.605 410.272 + endloop + endfacet + facet normal 0.115457 -0.429074 0.89586 + outer loop + vertex 347.6 173.578 411.035 + vertex 345.874 172.431 410.708 + vertex 356.588 175.282 410.693 + endloop + endfacet + facet normal 0.112619 -0.412475 0.903981 + outer loop + vertex 356.768 176.504 411.228 + vertex 347.6 173.578 411.035 + vertex 356.588 175.282 410.693 + endloop + endfacet + facet normal 0.132802 -0.413952 0.90056 + outer loop + vertex 356.768 176.504 411.228 + vertex 356.588 175.282 410.693 + vertex 366.855 178.818 410.804 + endloop + endfacet + facet normal 0.109121 -0.401858 0.909177 + outer loop + vertex 345.958 174.517 411.647 + vertex 347.6 173.578 411.035 + vertex 356.768 176.504 411.228 + endloop + endfacet + facet normal 0.110798 -0.411982 0.904431 + outer loop + vertex 356.804 178.223 412.007 + vertex 345.958 174.517 411.647 + vertex 356.768 176.504 411.228 + endloop + endfacet + facet normal 0.133299 -0.411227 0.901734 + outer loop + vertex 356.804 178.223 412.007 + vertex 356.768 176.504 411.228 + vertex 366.86 180.571 411.591 + endloop + endfacet + facet normal 0.117372 -0.430307 0.895019 + outer loop + vertex 347.729 176.59 412.412 + vertex 345.958 174.517 411.647 + vertex 356.804 178.223 412.007 + endloop + endfacet + facet normal 0.113677 -0.406965 0.906343 + outer loop + vertex 356.664 180.201 412.912 + vertex 347.729 176.59 412.412 + vertex 356.804 178.223 412.007 + endloop + endfacet + facet normal 0.133022 -0.404834 0.904663 + outer loop + vertex 356.664 180.201 412.912 + vertex 356.804 178.223 412.007 + vertex 366.706 182.541 412.483 + endloop + endfacet + facet normal 0.111002 -0.400772 0.909429 + outer loop + vertex 345.919 178.108 413.301 + vertex 347.729 176.59 412.412 + vertex 356.664 180.201 412.912 + endloop + endfacet + facet normal 0.111048 -0.40103 0.909309 + outer loop + vertex 356.482 182.32 413.869 + vertex 345.919 178.108 413.301 + vertex 356.664 180.201 412.912 + endloop + endfacet + facet normal 0.134398 -0.398164 0.907415 + outer loop + vertex 356.482 182.32 413.869 + vertex 356.664 180.201 412.912 + vertex 366.444 184.611 413.399 + endloop + endfacet + facet normal 0.119371 -0.42056 0.899377 + outer loop + vertex 347.662 180.667 414.267 + vertex 345.919 178.108 413.301 + vertex 356.482 182.32 413.869 + endloop + endfacet + facet normal 0.115067 -0.394659 0.911594 + outer loop + vertex 356.461 184.516 414.822 + vertex 347.662 180.667 414.267 + vertex 356.482 182.32 413.869 + endloop + endfacet + facet normal 0.137401 -0.393346 0.909066 + outer loop + vertex 356.461 184.516 414.822 + vertex 356.482 182.32 413.869 + vertex 366.18 186.727 414.31 + endloop + endfacet + facet normal 0.115489 -0.395558 0.911151 + outer loop + vertex 346.104 182.381 415.208 + vertex 347.662 180.667 414.267 + vertex 356.461 184.516 414.822 + endloop + endfacet + facet normal 0.115874 -0.397597 0.910214 + outer loop + vertex 356.614 186.772 415.789 + vertex 346.104 182.381 415.208 + vertex 356.461 184.516 414.822 + endloop + endfacet + facet normal 0.14535 -0.397752 0.905907 + outer loop + vertex 356.614 186.772 415.789 + vertex 356.461 184.516 414.822 + vertex 366.052 188.908 415.212 + endloop + endfacet + facet normal 0.12766 -0.424007 0.896616 + outer loop + vertex 347.993 185.136 416.242 + vertex 346.104 182.381 415.208 + vertex 356.614 186.772 415.789 + endloop + endfacet + facet normal 0.129597 -0.435874 0.890628 + outer loop + vertex 356.422 188.997 416.906 + vertex 347.993 185.136 416.242 + vertex 356.614 186.772 415.789 + endloop + endfacet + facet normal 0.163667 -0.431244 0.887266 + outer loop + vertex 356.422 188.997 416.906 + vertex 356.614 186.772 415.789 + vertex 365.874 191.157 416.211 + endloop + endfacet + facet normal 0.180796 -0.523861 0.832396 + outer loop + vertex 363.779 193.167 417.932 + vertex 356.422 188.997 416.906 + vertex 365.874 191.157 416.211 + endloop + endfacet + facet normal 0.236277 -0.477779 0.846109 + outer loop + vertex 363.779 193.167 417.932 + vertex 365.874 191.157 416.211 + vertex 371.772 194.6 416.509 + endloop + endfacet + facet normal 0.189018 -0.536004 0.822783 + outer loop + vertex 356.301 191.174 418.352 + vertex 356.422 188.997 416.906 + vertex 363.779 193.167 417.932 + endloop + endfacet + facet normal 0.150361 -0.541178 0.827356 + outer loop + vertex 356.301 191.174 418.352 + vertex 345.862 186.815 417.397 + vertex 356.422 188.997 416.906 + endloop + endfacet + facet normal 0.165959 -0.573085 0.802515 + outer loop + vertex 348.104 189.23 418.658 + vertex 345.862 186.815 417.397 + vertex 356.301 191.174 418.352 + endloop + endfacet + facet normal 0.130037 -0.551098 0.824246 + outer loop + vertex 348.104 189.23 418.658 + vertex 331.454 185.782 418.98 + vertex 345.862 186.815 417.397 + endloop + endfacet + facet normal 0.129753 -0.484405 0.865168 + outer loop + vertex 331.454 185.782 418.98 + vertex 334.058 181.164 416.003 + vertex 345.862 186.815 417.397 + endloop + endfacet + facet normal 0.115729 -0.458983 0.880876 + outer loop + vertex 347.993 185.136 416.242 + vertex 345.862 186.815 417.397 + vertex 334.058 181.164 416.003 + endloop + endfacet + facet normal 0.100254 -0.498427 0.861115 + outer loop + vertex 331.454 185.782 418.98 + vertex 316.112 178.211 416.384 + vertex 334.058 181.164 416.003 + endloop + endfacet + facet normal 0.0915591 -0.441519 0.892568 + outer loop + vertex 316.112 178.211 416.384 + vertex 316.722 174.236 414.355 + vertex 334.058 181.164 416.003 + endloop + endfacet + facet normal 0.0848912 -0.426697 0.900402 + outer loop + vertex 334.058 181.164 416.003 + vertex 316.722 174.236 414.355 + vertex 334.096 176.971 414.013 + endloop + endfacet + facet normal 0.102355 -0.425865 0.898979 + outer loop + vertex 334.058 181.164 416.003 + vertex 334.096 176.971 414.013 + vertex 346.104 182.381 415.208 + endloop + endfacet + facet normal 0.0849406 -0.427032 0.900238 + outer loop + vertex 316.722 174.236 414.355 + vertex 316.038 170.812 412.795 + vertex 334.096 176.971 414.013 + endloop + endfacet + facet normal 0.0817689 -0.418573 0.904495 + outer loop + vertex 334.096 176.971 414.013 + vertex 316.038 170.812 412.795 + vertex 333.864 173.377 412.37 + endloop + endfacet + facet normal 0.0946054 -0.418783 0.903145 + outer loop + vertex 334.096 176.971 414.013 + vertex 333.864 173.377 412.37 + vertex 345.919 178.108 413.301 + endloop + endfacet + facet normal 0.082397 -0.423315 0.902228 + outer loop + vertex 333.864 173.377 412.37 + vertex 316.038 170.812 412.795 + vertex 315.914 167.989 411.482 + endloop + endfacet + facet normal 0.0810423 -0.419142 0.904296 + outer loop + vertex 315.914 167.989 411.482 + vertex 334.091 170.767 411.141 + vertex 333.864 173.377 412.37 + endloop + endfacet + facet normal 0.0934327 -0.417796 0.903724 + outer loop + vertex 345.958 174.517 411.647 + vertex 333.864 173.377 412.37 + vertex 334.091 170.767 411.141 + endloop + endfacet + facet normal 0.0797497 -0.410169 0.908516 + outer loop + vertex 315.914 167.989 411.482 + vertex 318.239 165.585 410.192 + vertex 334.091 170.767 411.141 + endloop + endfacet + facet normal 0.0778255 -0.404758 0.911106 + outer loop + vertex 334.091 170.767 411.141 + vertex 318.239 165.585 410.192 + vertex 335.317 169.217 410.347 + endloop + endfacet + facet normal 0.089545 -0.39674 0.913553 + outer loop + vertex 334.091 170.767 411.141 + vertex 335.317 169.217 410.347 + vertex 345.874 172.431 410.708 + endloop + endfacet + facet normal 0.0725387 -0.416038 0.906449 + outer loop + vertex 315.914 167.989 411.482 + vertex 301.166 163.012 410.378 + vertex 318.239 165.585 410.192 + endloop + endfacet + facet normal 0.0717257 -0.413864 0.907509 + outer loop + vertex 296.763 165.248 411.746 + vertex 301.166 163.012 410.378 + vertex 315.914 167.989 411.482 + endloop + endfacet + facet normal 0.0672197 -0.420949 0.90459 + outer loop + vertex 296.763 165.248 411.746 + vertex 284.345 159.974 410.214 + vertex 301.166 163.012 410.378 + endloop + endfacet + facet normal 0.0668441 -0.418922 0.905558 + outer loop + vertex 301.166 163.012 410.378 + vertex 284.345 159.974 410.214 + vertex 293.194 159.052 409.134 + endloop + endfacet + facet normal 0.0654718 -0.417355 0.906382 + outer loop + vertex 278.672 161.613 411.379 + vertex 284.345 159.974 410.214 + vertex 296.763 165.248 411.746 + endloop + endfacet + facet normal 0.0677828 -0.428323 0.90108 + outer loop + vertex 278.672 161.613 411.379 + vertex 296.763 165.248 411.746 + vertex 284.274 165.372 412.744 + endloop + endfacet + facet normal 0.0621991 -0.42134 0.904767 + outer loop + vertex 263.849 160.211 411.745 + vertex 278.672 161.613 411.379 + vertex 284.274 165.372 412.744 + endloop + endfacet + facet normal 0.065033 -0.431578 0.899728 + outer loop + vertex 284.274 165.372 412.744 + vertex 270.05 163.929 413.08 + vertex 263.849 160.211 411.745 + endloop + endfacet + facet normal 0.060617 -0.425382 0.902982 + outer loop + vertex 270.05 163.929 413.08 + vertex 255.128 161.352 412.868 + vertex 263.849 160.211 411.745 + endloop + endfacet + facet normal 0.0599589 -0.428842 0.901387 + outer loop + vertex 244.45 157.242 411.623 + vertex 263.849 160.211 411.745 + vertex 255.128 161.352 412.868 + endloop + endfacet + facet normal 0.0572842 -0.422807 0.904407 + outer loop + vertex 255.128 161.352 412.868 + vertex 238.259 158.946 412.811 + vertex 244.45 157.242 411.623 + endloop + endfacet + facet normal 0.0558145 -0.426876 0.902586 + outer loop + vertex 227.104 154.905 411.59 + vertex 244.45 157.242 411.623 + vertex 238.259 158.946 412.811 + endloop + endfacet + facet normal 0.0537854 -0.422003 0.904998 + outer loop + vertex 238.259 158.946 412.811 + vertex 221.459 156.813 412.815 + vertex 227.104 154.905 411.59 + endloop + endfacet + facet normal 0.05185 -0.426459 0.90302 + outer loop + vertex 210.023 152.843 411.597 + vertex 227.104 154.905 411.59 + vertex 221.459 156.813 412.815 + endloop + endfacet + facet normal 0.0501342 -0.422164 0.905132 + outer loop + vertex 221.459 156.813 412.815 + vertex 204.744 154.839 412.82 + vertex 210.023 152.843 411.597 + endloop + endfacet + facet normal 0.0478416 -0.426933 0.903017 + outer loop + vertex 193.345 150.992 411.605 + vertex 210.023 152.843 411.597 + vertex 204.744 154.839 412.82 + endloop + endfacet + facet normal 0.0461884 -0.42269 0.905097 + outer loop + vertex 204.744 154.839 412.82 + vertex 188.258 153.039 412.821 + vertex 193.345 150.992 411.605 + endloop + endfacet + facet normal 0.0438355 -0.427317 0.903039 + outer loop + vertex 177.035 149.291 411.592 + vertex 193.345 150.992 411.605 + vertex 188.258 153.039 412.821 + endloop + endfacet + facet normal 0.0422309 -0.423175 0.905063 + outer loop + vertex 188.258 153.039 412.821 + vertex 171.898 151.399 412.817 + vertex 177.035 149.291 411.592 + endloop + endfacet + facet normal 0.0399082 -0.427669 0.903054 + outer loop + vertex 160.832 147.775 411.59 + vertex 177.035 149.291 411.592 + vertex 171.898 151.399 412.817 + endloop + endfacet + facet normal 0.0383221 -0.423511 0.90508 + outer loop + vertex 171.898 151.399 412.817 + vertex 155.532 149.921 412.819 + vertex 160.832 147.775 411.59 + endloop + endfacet + facet normal 0.0358564 -0.428353 0.9029 + outer loop + vertex 144.529 146.426 411.597 + vertex 160.832 147.775 411.59 + vertex 155.532 149.921 412.819 + endloop + endfacet + facet normal 0.0342923 -0.424145 0.904945 + outer loop + vertex 155.532 149.921 412.819 + vertex 139.106 148.629 412.836 + vertex 144.529 146.426 411.597 + endloop + endfacet + facet normal 0.0318435 -0.428949 0.902767 + outer loop + vertex 127.746 145.172 411.594 + vertex 144.529 146.426 411.597 + vertex 139.106 148.629 412.836 + endloop + endfacet + facet normal 0.030158 -0.424231 0.905052 + outer loop + vertex 139.106 148.629 412.836 + vertex 122.41 147.46 412.844 + vertex 127.746 145.172 411.594 + endloop + endfacet + facet normal 0.0274924 -0.429208 0.902787 + outer loop + vertex 110.631 144.067 411.59 + vertex 127.746 145.172 411.594 + vertex 122.41 147.46 412.844 + endloop + endfacet + facet normal 0.0256642 -0.423822 0.905382 + outer loop + vertex 122.41 147.46 412.844 + vertex 105.04 146.324 412.805 + vertex 110.631 144.067 411.59 + endloop + endfacet + facet normal 0.023221 -0.428677 0.903159 + outer loop + vertex 93.5781 143.05 411.545 + vertex 110.631 144.067 411.59 + vertex 105.04 146.324 412.805 + endloop + endfacet + facet normal 0.020422 -0.420398 0.90711 + outer loop + vertex 105.04 146.324 412.805 + vertex 85.0082 144.926 412.608 + vertex 93.5781 143.05 411.545 + endloop + endfacet + facet normal 0.0190596 -0.425333 0.904836 + outer loop + vertex 79.0914 141.963 411.34 + vertex 93.5781 143.05 411.545 + vertex 85.0082 144.926 412.608 + endloop + endfacet + facet normal 0.0150494 -0.418683 0.908008 + outer loop + vertex 66.5665 141.949 411.541 + vertex 79.0914 141.963 411.34 + vertex 85.0082 144.926 412.608 + endloop + endfacet + facet normal 0.0163738 -0.425705 0.904714 + outer loop + vertex 85.0082 144.926 412.608 + vertex 66.7674 144.617 412.793 + vertex 66.5665 141.949 411.541 + endloop + endfacet + facet normal 0.0119713 -0.42546 0.904898 + outer loop + vertex 49.8989 141.658 411.624 + vertex 66.5665 141.949 411.541 + vertex 66.7674 144.617 412.793 + endloop + endfacet + facet normal 0.0124956 -0.427977 0.903703 + outer loop + vertex 66.7674 144.617 412.793 + vertex 49.9878 144.319 412.883 + vertex 49.8989 141.658 411.624 + endloop + endfacet + facet normal 0.00828412 -0.42788 0.903797 + outer loop + vertex 31.0624 141.618 411.778 + vertex 49.8989 141.658 411.624 + vertex 49.9878 144.319 412.883 + endloop + endfacet + facet normal 0.00932223 -0.433962 0.900883 + outer loop + vertex 49.9878 144.319 412.883 + vertex 37.0748 144.507 413.107 + vertex 31.0624 141.618 411.778 + endloop + endfacet + facet normal 0.00561154 -0.427642 0.903931 + outer loop + vertex 37.0748 144.507 413.107 + vertex 21.5361 143.741 412.842 + vertex 31.0624 141.618 411.778 + endloop + endfacet + facet normal 0.00463633 -0.431178 0.902255 + outer loop + vertex 10.5629 140.914 411.547 + vertex 31.0624 141.618 411.778 + vertex 21.5361 143.741 412.842 + endloop + endfacet + facet normal 0.00220274 -0.423417 0.905932 + outer loop + vertex 21.5361 143.741 412.842 + vertex 1.50638 143.206 412.64 + vertex 10.5629 140.914 411.547 + endloop + endfacet + facet normal 0.000984696 -0.427349 0.904086 + outer loop + vertex -4.8529 140.424 411.332 + vertex 10.5629 140.914 411.547 + vertex 1.50638 143.206 412.64 + endloop + endfacet + facet normal -0.00229345 -0.421207 0.906962 + outer loop + vertex -18.8738 141.326 411.716 + vertex -4.8529 140.424 411.332 + vertex 1.50638 143.206 412.64 + endloop + endfacet + facet normal -0.000953881 -0.43299 0.901398 + outer loop + vertex 1.50638 143.206 412.64 + vertex -12.4018 144.119 413.064 + vertex -18.8738 141.326 411.716 + endloop + endfacet + facet normal -0.00429394 -0.426695 0.904386 + outer loop + vertex -12.4018 144.119 413.064 + vertex -27.8344 143.813 412.846 + vertex -18.8738 141.326 411.716 + endloop + endfacet + facet normal -0.00567589 -0.430787 0.902436 + outer loop + vertex -38.3494 141.245 411.555 + vertex -18.8738 141.326 411.716 + vertex -27.8344 143.813 412.846 + endloop + endfacet + facet normal -0.00818298 -0.422482 0.906334 + outer loop + vertex -27.8344 143.813 412.846 + vertex -48.0108 143.692 412.608 + vertex -38.3494 141.245 411.555 + endloop + endfacet + facet normal -0.00925691 -0.426007 0.904672 + outer loop + vertex -53.5032 141.057 411.311 + vertex -38.3494 141.245 411.555 + vertex -48.0108 143.692 412.608 + endloop + endfacet + facet normal -0.0126572 -0.420226 0.907331 + outer loop + vertex -66.4778 141.93 411.535 + vertex -53.5032 141.057 411.311 + vertex -48.0108 143.692 412.608 + endloop + endfacet + facet normal -0.0121006 -0.424775 0.905218 + outer loop + vertex -48.0108 143.692 412.608 + vertex -66.4604 144.596 412.786 + vertex -66.4778 141.93 411.535 + endloop + endfacet + facet normal -0.0163668 -0.424726 0.905174 + outer loop + vertex -82.9165 142.67 411.584 + vertex -66.4778 141.93 411.535 + vertex -66.4604 144.596 412.786 + endloop + endfacet + facet normal -0.016331 -0.424964 0.905063 + outer loop + vertex -66.4604 144.596 412.786 + vertex -83.6741 145.327 412.818 + vertex -82.9165 142.67 411.584 + endloop + endfacet + facet normal -0.0204106 -0.425887 0.904546 + outer loop + vertex -100.215 143.519 411.593 + vertex -82.9165 142.67 411.584 + vertex -83.6741 145.327 412.818 + endloop + endfacet + facet normal -0.0202518 -0.426989 0.90403 + outer loop + vertex -83.6741 145.327 412.818 + vertex -100.247 146.24 412.878 + vertex -100.215 143.519 411.593 + endloop + endfacet + facet normal -0.024644 -0.426988 0.903921 + outer loop + vertex -118.715 144.989 411.783 + vertex -100.215 143.519 411.593 + vertex -100.247 146.24 412.878 + endloop + endfacet + facet normal -0.0239061 -0.434684 0.900266 + outer loop + vertex -100.247 146.24 412.878 + vertex -112.873 147.404 413.105 + vertex -118.715 144.989 411.783 + endloop + endfacet + facet normal -0.0276313 -0.427494 0.903596 + outer loop + vertex -112.873 147.404 413.105 + vertex -127.58 147.878 412.879 + vertex -118.715 144.989 411.783 + endloop + endfacet + facet normal -0.0297501 -0.432977 0.900914 + outer loop + vertex -138.539 146.008 411.619 + vertex -118.715 144.989 411.783 + vertex -127.58 147.878 412.879 + endloop + endfacet + facet normal -0.0317291 -0.424157 0.905032 + outer loop + vertex -127.58 147.878 412.879 + vertex -145.063 148.987 412.786 + vertex -138.539 146.008 411.619 + endloop + endfacet + facet normal -0.0345546 -0.429344 0.90248 + outer loop + vertex -156.046 147.23 411.53 + vertex -138.539 146.008 411.619 + vertex -145.063 148.987 412.786 + endloop + endfacet + facet normal -0.0364788 -0.420297 0.906653 + outer loop + vertex -145.063 148.987 412.786 + vertex -165.127 150.327 412.6 + vertex -156.046 147.23 411.53 + endloop + endfacet + facet normal -0.038187 -0.424591 0.90458 + outer loop + vertex -170.695 148.17 411.353 + vertex -156.046 147.23 411.53 + vertex -165.127 150.327 412.6 + endloop + endfacet + facet normal -0.0414227 -0.417944 0.907528 + outer loop + vertex -183.409 149.854 411.548 + vertex -170.695 148.17 411.353 + vertex -165.127 150.327 412.6 + endloop + endfacet + facet normal -0.0411005 -0.424082 0.904691 + outer loop + vertex -165.127 150.327 412.6 + vertex -183.399 152.504 412.79 + vertex -183.409 149.854 411.548 + endloop + endfacet + facet normal -0.0452738 -0.423992 0.904534 + outer loop + vertex -200.1 151.765 411.608 + vertex -183.409 149.854 411.548 + vertex -183.399 152.504 412.79 + endloop + endfacet + facet normal -0.0450706 -0.42662 0.903307 + outer loop + vertex -183.399 152.504 412.79 + vertex -200.062 154.457 412.881 + vertex -200.1 151.765 411.608 + endloop + endfacet + facet normal -0.0492049 -0.426489 0.903153 + outer loop + vertex -218.444 154.287 411.8 + vertex -200.1 151.765 411.608 + vertex -200.062 154.457 412.881 + endloop + endfacet + facet normal -0.048976 -0.432648 0.900232 + outer loop + vertex -200.062 154.457 412.881 + vertex -212.662 156.371 413.116 + vertex -218.444 154.287 411.8 + endloop + endfacet + facet normal -0.0520333 -0.426045 0.903204 + outer loop + vertex -212.662 156.371 413.116 + vertex -227.359 157.679 412.886 + vertex -218.444 154.287 411.8 + endloop + endfacet + facet normal -0.0539874 -0.43047 0.900989 + outer loop + vertex -238.258 156.386 411.615 + vertex -218.444 154.287 411.8 + vertex -227.359 157.679 412.886 + endloop + endfacet + facet normal -0.0553569 -0.422531 0.904656 + outer loop + vertex -227.359 157.679 412.886 + vertex -244.842 159.761 412.789 + vertex -238.258 156.386 411.615 + endloop + endfacet + facet normal -0.0579726 -0.426868 0.902454 + outer loop + vertex -255.888 158.58 411.521 + vertex -238.258 156.386 411.615 + vertex -244.842 159.761 412.789 + endloop + endfacet + facet normal -0.0590337 -0.420216 0.905502 + outer loop + vertex -244.842 159.761 412.789 + vertex -264.74 162.159 412.604 + vertex -255.888 158.58 411.521 + endloop + endfacet + facet normal -0.0610289 -0.424504 0.903367 + outer loop + vertex -270.656 160.289 411.326 + vertex -255.888 158.58 411.521 + vertex -264.74 162.159 412.604 + endloop + endfacet + facet normal -0.0632467 -0.419105 0.905732 + outer loop + vertex -282.904 162.629 411.553 + vertex -270.656 160.289 411.326 + vertex -264.74 162.159 412.604 + endloop + endfacet + facet normal -0.0632418 -0.423694 0.903595 + outer loop + vertex -264.74 162.159 412.604 + vertex -282.332 165.213 412.805 + vertex -282.904 162.629 411.553 + endloop + endfacet + facet normal -0.0680304 -0.422693 0.903716 + outer loop + vertex -299.016 165.342 411.609 + vertex -282.904 162.629 411.553 + vertex -282.332 165.213 412.805 + endloop + endfacet + facet normal -0.0680356 -0.422492 0.90381 + outer loop + vertex -282.332 165.213 412.805 + vertex -298.741 168.05 412.896 + vertex -299.016 165.342 411.609 + endloop + endfacet + facet normal -0.0746874 -0.421735 0.903638 + outer loop + vertex -318.339 168.942 411.693 + vertex -299.016 165.342 411.609 + vertex -298.741 168.05 412.896 + endloop + endfacet + facet normal -0.0747866 -0.427735 0.900805 + outer loop + vertex -298.741 168.05 412.896 + vertex -312.529 170.896 413.103 + vertex -318.339 168.942 411.693 + endloop + endfacet + facet normal -0.0800964 -0.415679 0.905978 + outer loop + vertex -312.529 170.896 413.103 + vertex -332.222 173.51 412.561 + vertex -318.339 168.942 411.693 + endloop + endfacet + facet normal -0.0812593 -0.418911 0.904384 + outer loop + vertex -337.752 171.625 411.191 + vertex -318.339 168.942 411.693 + vertex -332.222 173.51 412.561 + endloop + endfacet + facet normal -0.0878011 -0.404138 0.910474 + outer loop + vertex -332.222 173.51 412.561 + vertex -346.442 173.719 411.282 + vertex -337.752 171.625 411.191 + endloop + endfacet + facet normal -0.0907538 -0.416147 0.904757 + outer loop + vertex -346.442 173.719 411.282 + vertex -348.776 173.106 410.767 + vertex -337.752 171.625 411.191 + endloop + endfacet + facet normal -0.0933414 -0.438537 0.893853 + outer loop + vertex -348.776 173.106 410.767 + vertex -347.096 172.482 410.636 + vertex -337.752 171.625 411.191 + endloop + endfacet + facet normal -0.0926623 -0.427692 0.899162 + outer loop + vertex -334.183 169.356 410.48 + vertex -337.752 171.625 411.191 + vertex -347.096 172.482 410.636 + endloop + endfacet + facet normal -0.100664 -0.459899 0.882247 + outer loop + vertex -348.712 172.379 410.398 + vertex -334.183 169.356 410.48 + vertex -347.096 172.482 410.636 + endloop + endfacet + facet normal -0.107907 -0.405299 0.907793 + outer loop + vertex -347.096 172.482 410.636 + vertex -356.888 174.508 410.376 + vertex -348.712 172.379 410.398 + endloop + endfacet + facet normal -0.110497 -0.415297 0.90295 + outer loop + vertex -356.888 174.508 410.376 + vertex -357.246 173.976 410.088 + vertex -348.712 172.379 410.398 + endloop + endfacet + facet normal -0.0996769 -0.352108 0.930637 + outer loop + vertex -348.712 172.379 410.398 + vertex -357.246 173.976 410.088 + vertex -351.655 172.433 410.103 + endloop + endfacet + facet normal -0.0981227 -0.418102 0.903085 + outer loop + vertex -348.712 172.379 410.398 + vertex -351.655 172.433 410.103 + vertex -344.306 169.962 409.757 + endloop + endfacet + facet normal -0.133871 -0.401277 0.906121 + outer loop + vertex -356.888 174.508 410.376 + vertex -365.389 176.308 409.918 + vertex -357.246 173.976 410.088 + endloop + endfacet + facet normal -0.133824 -0.401107 0.906203 + outer loop + vertex -357.246 173.976 410.088 + vertex -365.389 176.308 409.918 + vertex -363.823 174.234 409.231 + endloop + endfacet + facet normal -0.133732 -0.400534 0.90647 + outer loop + vertex -365.671 176.82 410.102 + vertex -365.389 176.308 409.918 + vertex -356.888 174.508 410.376 + endloop + endfacet + facet normal -0.18123 -0.595667 0.782519 + outer loop + vertex -356.671 174.521 410.437 + vertex -365.671 176.82 410.102 + vertex -356.888 174.508 410.376 + endloop + endfacet + facet normal -0.21336 -0.743034 0.634333 + outer loop + vertex -365.597 176.854 410.167 + vertex -365.671 176.82 410.102 + vertex -356.671 174.521 410.437 + endloop + endfacet + facet normal -0.1418 -0.440089 0.886687 + outer loop + vertex -356.471 174.862 410.638 + vertex -365.597 176.854 410.167 + vertex -356.671 174.521 410.437 + endloop + endfacet + facet normal -0.118021 -0.452432 0.883955 + outer loop + vertex -356.471 174.862 410.638 + vertex -356.671 174.521 410.437 + vertex -348.776 173.106 410.767 + endloop + endfacet + facet normal -0.139518 -0.428181 0.892858 + outer loop + vertex -365.524 177.425 410.453 + vertex -365.597 176.854 410.167 + vertex -356.471 174.862 410.638 + endloop + endfacet + facet normal -0.133402 -0.405767 0.904189 + outer loop + vertex -356.263 175.954 411.159 + vertex -365.524 177.425 410.453 + vertex -356.471 174.862 410.638 + endloop + endfacet + facet normal -0.105114 -0.411669 0.905251 + outer loop + vertex -356.263 175.954 411.159 + vertex -356.471 174.862 410.638 + vertex -346.442 173.719 411.282 + endloop + endfacet + facet normal -0.105522 -0.413507 0.904366 + outer loop + vertex -347.424 175.366 411.921 + vertex -356.263 175.954 411.159 + vertex -346.442 173.719 411.282 + endloop + endfacet + facet normal -0.105307 -0.405634 0.907949 + outer loop + vertex -356.162 177.763 411.979 + vertex -356.263 175.954 411.159 + vertex -347.424 175.366 411.921 + endloop + endfacet + facet normal -0.104287 -0.40196 0.909699 + outer loop + vertex -345.771 177.271 412.952 + vertex -356.162 177.763 411.979 + vertex -347.424 175.366 411.921 + endloop + endfacet + facet normal -0.088647 -0.413607 0.906129 + outer loop + vertex -347.424 175.366 411.921 + vertex -332.222 173.51 412.561 + vertex -345.771 177.271 412.952 + endloop + endfacet + facet normal -0.0907749 -0.420902 0.902553 + outer loop + vertex -332.222 173.51 412.561 + vertex -334.16 178.164 414.537 + vertex -345.771 177.271 412.952 + endloop + endfacet + facet normal -0.0922283 -0.41035 0.907252 + outer loop + vertex -347.852 179.825 413.896 + vertex -345.771 177.271 412.952 + vertex -334.16 178.164 414.537 + endloop + endfacet + facet normal -0.0928137 -0.416234 0.904508 + outer loop + vertex -347.852 179.825 413.896 + vertex -334.16 178.164 414.537 + vertex -346.27 181.84 414.986 + endloop + endfacet + facet normal -0.109652 -0.404797 0.907808 + outer loop + vertex -346.27 181.84 414.986 + vertex -356.218 182.198 413.943 + vertex -347.852 179.825 413.896 + endloop + endfacet + facet normal -0.109042 -0.402666 0.908829 + outer loop + vertex -356.218 182.198 413.943 + vertex -356.188 179.96 412.955 + vertex -347.852 179.825 413.896 + endloop + endfacet + facet normal -0.133689 -0.401727 0.905948 + outer loop + vertex -356.218 182.198 413.943 + vertex -365.263 182.733 412.846 + vertex -356.188 179.96 412.955 + endloop + endfacet + facet normal -0.132525 -0.397844 0.907831 + outer loop + vertex -365.263 182.733 412.846 + vertex -365.391 180.635 411.908 + vertex -356.188 179.96 412.955 + endloop + endfacet + facet normal -0.132667 -0.40409 0.905047 + outer loop + vertex -356.188 179.96 412.955 + vertex -365.391 180.635 411.908 + vertex -356.162 177.763 411.979 + endloop + endfacet + facet normal -0.132306 -0.402918 0.905623 + outer loop + vertex -365.391 180.635 411.908 + vertex -365.474 178.749 411.057 + vertex -356.162 177.763 411.979 + endloop + endfacet + facet normal -0.169043 -0.399267 0.901116 + outer loop + vertex -365.391 180.635 411.908 + vertex -374.638 181.973 410.766 + vertex -365.474 178.749 411.057 + endloop + endfacet + facet normal -0.168964 -0.399031 0.901236 + outer loop + vertex -374.638 181.973 410.766 + vertex -374.737 180.537 410.112 + vertex -365.474 178.749 411.057 + endloop + endfacet + facet normal -0.169671 -0.403917 0.898923 + outer loop + vertex -365.474 178.749 411.057 + vertex -374.737 180.537 410.112 + vertex -365.524 177.425 410.453 + endloop + endfacet + facet normal -0.17508 -0.420906 0.890048 + outer loop + vertex -374.737 180.537 410.112 + vertex -374.78 179.848 409.777 + vertex -365.524 177.425 410.453 + endloop + endfacet + facet normal -0.168781 -0.396294 0.902477 + outer loop + vertex -374.442 183.835 411.62 + vertex -374.638 181.973 410.766 + vertex -365.391 180.635 411.908 + endloop + endfacet + facet normal -0.167955 -0.393848 0.903701 + outer loop + vertex -365.263 182.733 412.846 + vertex -374.442 183.835 411.62 + vertex -365.391 180.635 411.908 + endloop + endfacet + facet normal -0.167113 -0.380163 0.909697 + outer loop + vertex -374.224 185.802 412.482 + vertex -374.442 183.835 411.62 + vertex -365.263 182.733 412.846 + endloop + endfacet + facet normal -0.169414 -0.387289 0.906259 + outer loop + vertex -365.141 184.826 413.763 + vertex -374.224 185.802 412.482 + vertex -365.263 182.733 412.846 + endloop + endfacet + facet normal -0.168274 -0.363603 0.91623 + outer loop + vertex -374.028 187.791 413.308 + vertex -374.224 185.802 412.482 + vertex -365.141 184.826 413.763 + endloop + endfacet + facet normal -0.174208 -0.38276 0.907274 + outer loop + vertex -365.081 186.907 414.653 + vertex -374.028 187.791 413.308 + vertex -365.141 184.826 413.763 + endloop + endfacet + facet normal -0.137362 -0.385949 0.912236 + outer loop + vertex -365.081 186.907 414.653 + vertex -365.141 184.826 413.763 + vertex -356.231 184.344 414.901 + endloop + endfacet + facet normal -0.142939 -0.40614 0.902562 + outer loop + vertex -356.181 186.458 415.86 + vertex -365.081 186.907 414.653 + vertex -356.231 184.344 414.901 + endloop + endfacet + facet normal -0.115771 -0.408138 0.90555 + outer loop + vertex -356.181 186.458 415.86 + vertex -356.231 184.344 414.901 + vertex -347.943 184.204 415.898 + endloop + endfacet + facet normal -0.12219 -0.431796 0.893657 + outer loop + vertex -345.779 186.056 417.088 + vertex -356.181 186.458 415.86 + vertex -347.943 184.204 415.898 + endloop + endfacet + facet normal -0.104593 -0.448494 0.887645 + outer loop + vertex -347.943 184.204 415.898 + vertex -334.206 182.478 416.644 + vertex -345.779 186.056 417.088 + endloop + endfacet + facet normal -0.122646 -0.50291 0.855593 + outer loop + vertex -334.206 182.478 416.644 + vertex -331.508 185.793 418.979 + vertex -345.779 186.056 417.088 + endloop + endfacet + facet normal -0.122229 -0.509975 0.851461 + outer loop + vertex -348.225 189.258 418.655 + vertex -345.779 186.056 417.088 + vertex -331.508 185.793 418.979 + endloop + endfacet + facet normal -0.14535 -0.522199 0.840346 + outer loop + vertex -348.225 189.258 418.655 + vertex -356.155 188.731 416.956 + vertex -345.779 186.056 417.088 + endloop + endfacet + facet normal -0.150115 -0.496883 0.854735 + outer loop + vertex -356.357 191.188 418.349 + vertex -356.155 188.731 416.956 + vertex -348.225 189.258 418.655 + endloop + endfacet + facet normal -0.178259 -0.496312 0.849646 + outer loop + vertex -356.357 191.188 418.349 + vertex -365.026 191.264 416.574 + vertex -356.155 188.731 416.956 + endloop + endfacet + facet normal -0.154559 -0.405598 0.900889 + outer loop + vertex -365.026 191.264 416.574 + vertex -365.098 189.047 415.564 + vertex -356.155 188.731 416.956 + endloop + endfacet + facet normal -0.153766 -0.427618 0.890785 + outer loop + vertex -356.155 188.731 416.956 + vertex -365.098 189.047 415.564 + vertex -356.181 186.458 415.86 + endloop + endfacet + facet normal -0.196825 -0.401331 0.894535 + outer loop + vertex -365.026 191.264 416.574 + vertex -373.812 192.009 414.975 + vertex -365.098 189.047 415.564 + endloop + endfacet + facet normal -0.181304 -0.35086 0.918709 + outer loop + vertex -373.812 192.009 414.975 + vertex -373.879 189.843 414.135 + vertex -365.098 189.047 415.564 + endloop + endfacet + facet normal -0.182158 -0.386382 0.904172 + outer loop + vertex -365.098 189.047 415.564 + vertex -373.879 189.843 414.135 + vertex -365.081 186.907 414.653 + endloop + endfacet + facet normal -0.196514 -0.361065 0.9116 + outer loop + vertex -373.535 194.176 415.893 + vertex -373.812 192.009 414.975 + vertex -365.026 191.264 416.574 + endloop + endfacet + facet normal -0.226908 -0.462627 0.857023 + outer loop + vertex -363.779 193.167 417.932 + vertex -373.535 194.176 415.893 + vertex -365.026 191.264 416.574 + endloop + endfacet + facet normal -0.226454 -0.495362 0.838651 + outer loop + vertex -372.309 195.826 417.199 + vertex -373.535 194.176 415.893 + vertex -363.779 193.167 417.932 + endloop + endfacet + facet normal -0.178821 -0.490979 0.852621 + outer loop + vertex -363.779 193.167 417.932 + vertex -365.026 191.264 416.574 + vertex -356.357 191.188 418.349 + endloop + endfacet + facet normal -0.099948 -0.517378 0.8499 + outer loop + vertex -331.508 185.793 418.979 + vertex -334.206 182.478 416.644 + vertex -315.75 182.912 419.079 + endloop + endfacet + facet normal -0.101414 -0.502832 0.858415 + outer loop + vertex -315.75 182.912 419.079 + vertex -334.206 182.478 416.644 + vertex -316.385 178.783 416.585 + endloop + endfacet + facet normal -0.0858319 -0.505358 0.85863 + outer loop + vertex -315.75 182.912 419.079 + vertex -316.385 178.783 416.585 + vertex -298.851 180.068 419.094 + endloop + endfacet + facet normal -0.0880578 -0.490874 0.866769 + outer loop + vertex -298.851 180.068 419.094 + vertex -316.385 178.783 416.585 + vertex -298.892 175.533 416.522 + endloop + endfacet + facet normal -0.0780605 -0.491353 0.867455 + outer loop + vertex -298.851 180.068 419.094 + vertex -298.892 175.533 416.522 + vertex -281.866 177.369 419.094 + endloop + endfacet + facet normal -0.0794075 -0.484264 0.871311 + outer loop + vertex -281.866 177.369 419.094 + vertex -298.892 175.533 416.522 + vertex -282.216 172.697 416.465 + endloop + endfacet + facet normal -0.0730961 -0.48486 0.871532 + outer loop + vertex -281.866 177.369 419.094 + vertex -282.216 172.697 416.465 + vertex -266.922 175.116 419.094 + endloop + endfacet + facet normal -0.0732744 -0.484147 0.871913 + outer loop + vertex -266.922 175.116 419.094 + vertex -282.216 172.697 416.465 + vertex -265.773 170.151 416.433 + endloop + endfacet + facet normal -0.0687703 -0.483496 0.872641 + outer loop + vertex -266.922 175.116 419.094 + vertex -265.773 170.151 416.433 + vertex -248.914 172.555 419.094 + endloop + endfacet + facet normal -0.0684522 -0.484894 0.87189 + outer loop + vertex -248.914 172.555 419.094 + vertex -265.773 170.151 416.433 + vertex -249.167 167.774 416.415 + endloop + endfacet + facet normal -0.0646546 -0.485171 0.872026 + outer loop + vertex -248.914 172.555 419.094 + vertex -249.167 167.774 416.415 + vertex -232.808 170.409 419.094 + endloop + endfacet + facet normal -0.0644749 -0.485893 0.871637 + outer loop + vertex -232.808 170.409 419.094 + vertex -249.167 167.774 416.415 + vertex -232.697 165.585 416.413 + endloop + endfacet + facet normal -0.0606149 -0.485943 0.871886 + outer loop + vertex -232.808 170.409 419.094 + vertex -232.697 165.585 416.413 + vertex -217.034 168.441 419.094 + endloop + endfacet + facet normal -0.0605055 -0.486341 0.871672 + outer loop + vertex -217.034 168.441 419.094 + vertex -232.697 165.585 416.413 + vertex -216.144 163.544 416.423 + endloop + endfacet + facet normal -0.0561876 -0.485861 0.872228 + outer loop + vertex -217.034 168.441 419.094 + vertex -216.144 163.544 416.423 + vertex -199.346 166.396 419.094 + endloop + endfacet + facet normal -0.0561516 -0.486001 0.872152 + outer loop + vertex -199.346 166.396 419.094 + vertex -216.144 163.544 416.423 + vertex -199.673 161.654 416.431 + endloop + endfacet + facet normal -0.0516537 -0.486356 0.872233 + outer loop + vertex -199.346 166.396 419.094 + vertex -199.673 161.654 416.431 + vertex -182.866 164.645 419.094 + endloop + endfacet + facet normal -0.0516687 -0.486299 0.872263 + outer loop + vertex -182.866 164.645 419.094 + vertex -199.673 161.654 416.431 + vertex -183.313 159.904 416.424 + endloop + endfacet + facet normal -0.0472031 -0.486728 0.872277 + outer loop + vertex -182.866 164.645 419.094 + vertex -183.313 159.904 416.424 + vertex -166.607 163.068 419.094 + endloop + endfacet + facet normal -0.0472724 -0.486477 0.872414 + outer loop + vertex -166.607 163.068 419.094 + vertex -183.313 159.904 416.424 + vertex -166.657 158.27 416.416 + endloop + endfacet + facet normal -0.0425786 -0.486617 0.872577 + outer loop + vertex -166.607 163.068 419.094 + vertex -166.657 158.27 416.416 + vertex -149.866 161.604 419.094 + endloop + endfacet + facet normal -0.042747 -0.486026 0.872898 + outer loop + vertex -149.866 161.604 419.094 + vertex -166.657 158.27 416.416 + vertex -149.702 156.787 416.42 + endloop + endfacet + facet normal -0.0376908 -0.485994 0.873149 + outer loop + vertex -149.866 161.604 419.094 + vertex -149.702 156.787 416.42 + vertex -132.648 160.268 419.094 + endloop + endfacet + facet normal -0.037794 -0.485637 0.873343 + outer loop + vertex -132.648 160.268 419.094 + vertex -149.702 156.787 416.42 + vertex -132.967 155.48 416.417 + endloop + endfacet + facet normal -0.0330157 -0.485963 0.873356 + outer loop + vertex -132.648 160.268 419.094 + vertex -132.967 155.48 416.417 + vertex -117.606 159.246 419.094 + endloop + endfacet + facet normal -0.0326874 -0.486928 0.87283 + outer loop + vertex -117.606 159.246 419.094 + vertex -132.967 155.48 416.417 + vertex -116.359 154.367 416.419 + endloop + endfacet + facet normal -0.0281483 -0.486106 0.873447 + outer loop + vertex -117.606 159.246 419.094 + vertex -116.359 154.367 416.419 + vertex -99.5825 158.203 419.094 + endloop + endfacet + facet normal -0.0278079 -0.487183 0.872857 + outer loop + vertex -99.5825 158.203 419.094 + vertex -116.359 154.367 416.419 + vertex -99.7398 153.431 416.426 + endloop + endfacet + facet normal -0.0230615 -0.487361 0.872896 + outer loop + vertex -99.5825 158.203 419.094 + vertex -99.7398 153.431 416.426 + vertex -82.7924 157.408 419.094 + endloop + endfacet + facet normal -0.0229711 -0.487643 0.872741 + outer loop + vertex -82.7924 157.408 419.094 + vertex -99.7398 153.431 416.426 + vertex -83.2171 152.643 416.42 + endloop + endfacet + facet normal -0.0183579 -0.488002 0.872649 + outer loop + vertex -82.7924 157.408 419.094 + vertex -83.2171 152.643 416.42 + vertex -66.2399 156.785 419.094 + endloop + endfacet + facet normal -0.0185139 -0.487531 0.872909 + outer loop + vertex -66.2399 156.785 419.094 + vertex -83.2171 152.643 416.42 + vertex -66.4758 152.009 416.421 + endloop + endfacet + facet normal -0.0138602 -0.487743 0.872877 + outer loop + vertex -66.2399 156.785 419.094 + vertex -66.4758 152.009 416.421 + vertex -49.4535 156.308 419.094 + endloop + endfacet + facet normal -0.0141071 -0.487016 0.873279 + outer loop + vertex -49.4535 156.308 419.094 + vertex -66.4758 152.009 416.421 + vertex -49.623 151.524 416.423 + endloop + endfacet + facet normal -0.0095765 -0.487164 0.873258 + outer loop + vertex -49.4535 156.308 419.094 + vertex -49.623 151.524 416.423 + vertex -32.7864 155.981 419.094 + endloop + endfacet + facet normal -0.00990582 -0.48623 0.873775 + outer loop + vertex -32.7864 155.981 419.094 + vertex -49.623 151.524 416.423 + vertex -32.8692 151.198 416.432 + endloop + endfacet + facet normal -0.00557878 -0.486303 0.873772 + outer loop + vertex -32.7864 155.981 419.094 + vertex -32.8692 151.198 416.432 + vertex -16.4978 155.794 419.094 + endloop + endfacet + facet normal -0.00556351 -0.486345 0.873749 + outer loop + vertex -16.4978 155.794 419.094 + vertex -32.8692 151.198 416.432 + vertex -16.318 151.016 416.435 + endloop + endfacet + facet normal -0.00182319 -0.486244 0.873821 + outer loop + vertex -16.4978 155.794 419.094 + vertex -16.318 151.016 416.435 + vertex -2.2005e-14 155.732 419.094 + endloop + endfacet + facet normal -0.00186941 -0.486122 0.873889 + outer loop + vertex -2.2005e-14 155.732 419.094 + vertex -16.318 151.016 416.435 + vertex -0.0377764 150.956 416.437 + endloop + endfacet + facet normal 0.00175413 -0.486144 0.873877 + outer loop + vertex -2.2005e-14 155.732 419.094 + vertex -0.0377764 150.956 416.437 + vertex 15.8878 155.789 419.094 + endloop + endfacet + facet normal 0.00200935 -0.486788 0.873518 + outer loop + vertex 15.8878 155.789 419.094 + vertex -0.0377764 150.956 416.437 + vertex 16.426 150.983 416.414 + endloop + endfacet + facet normal 0.00557837 -0.486476 0.873676 + outer loop + vertex 15.8878 155.789 419.094 + vertex 16.426 150.983 416.414 + vertex 33.3624 155.99 419.094 + endloop + endfacet + facet normal 0.00566112 -0.486692 0.873556 + outer loop + vertex 33.3624 155.99 419.094 + vertex 16.426 150.983 416.414 + vertex 33.3024 151.185 416.418 + endloop + endfacet + facet normal 0.00973479 -0.486715 0.873506 + outer loop + vertex 33.3624 155.99 419.094 + vertex 33.3024 151.185 416.418 + vertex 50.2209 156.327 419.094 + endloop + endfacet + facet normal 0.0098269 -0.48695 0.873375 + outer loop + vertex 50.2209 156.327 419.094 + vertex 33.3024 151.185 416.418 + vertex 50.0673 151.532 416.422 + endloop + endfacet + facet normal 0.0140642 -0.487029 0.873273 + outer loop + vertex 50.2209 156.327 419.094 + vertex 50.0673 151.532 416.422 + vertex 67.1835 156.817 419.094 + endloop + endfacet + facet normal 0.013932 -0.486696 0.873461 + outer loop + vertex 67.1835 156.817 419.094 + vertex 50.0673 151.532 416.422 + vertex 66.7039 152.012 416.424 + endloop + endfacet + facet normal 0.018621 -0.487016 0.873195 + outer loop + vertex 67.1835 156.817 419.094 + vertex 66.7039 152.012 416.424 + vertex 84.0159 157.46 419.094 + endloop + endfacet + facet normal 0.018401 -0.486468 0.873504 + outer loop + vertex 84.0159 157.46 419.094 + vertex 66.7039 152.012 416.424 + vertex 83.3394 152.638 416.422 + endloop + endfacet + facet normal 0.0231923 -0.486934 0.873131 + outer loop + vertex 84.0159 157.46 419.094 + vertex 83.3394 152.638 416.422 + vertex 99.4092 158.194 419.094 + endloop + endfacet + facet normal 0.0234093 -0.487427 0.87285 + outer loop + vertex 99.4092 158.194 419.094 + vertex 83.3394 152.638 416.422 + vertex 100.258 153.448 416.421 + endloop + endfacet + facet normal 0.0280693 -0.486733 0.873099 + outer loop + vertex 99.4092 158.194 419.094 + vertex 100.258 153.448 416.421 + vertex 117.004 159.208 419.094 + endloop + endfacet + facet normal 0.0282253 -0.487092 0.872895 + outer loop + vertex 117.004 159.208 419.094 + vertex 100.258 153.448 416.421 + vertex 117.355 154.468 416.437 + endloop + endfacet + facet normal 0.0332133 -0.486735 0.872918 + outer loop + vertex 117.004 159.208 419.094 + vertex 117.355 154.468 416.437 + vertex 134.251 160.385 419.094 + endloop + endfacet + facet normal 0.0332832 -0.486894 0.872827 + outer loop + vertex 134.251 160.385 419.094 + vertex 117.355 154.468 416.437 + vertex 134.107 155.621 416.442 + endloop + endfacet + facet normal 0.0381367 -0.486921 0.872613 + outer loop + vertex 134.251 160.385 419.094 + vertex 134.107 155.621 416.442 + vertex 150.855 161.686 419.094 + endloop + endfacet + facet normal 0.0379458 -0.4865 0.872856 + outer loop + vertex 150.855 161.686 419.094 + vertex 134.107 155.621 416.442 + vertex 150.451 156.884 416.435 + endloop + endfacet + facet normal 0.0426672 -0.486712 0.87252 + outer loop + vertex 150.855 161.686 419.094 + vertex 150.451 156.884 416.435 + vertex 166.182 163.029 419.094 + endloop + endfacet + facet normal 0.0427503 -0.486882 0.872421 + outer loop + vertex 166.182 163.029 419.094 + vertex 150.451 156.884 416.435 + vertex 166.882 158.315 416.429 + endloop + endfacet + facet normal 0.0472652 -0.486272 0.872528 + outer loop + vertex 166.182 163.029 419.094 + vertex 166.882 158.315 416.429 + vertex 184.067 164.768 419.094 + endloop + endfacet + facet normal 0.0472956 -0.486338 0.87249 + outer loop + vertex 184.067 164.768 419.094 + vertex 166.882 158.315 416.429 + vertex 183.315 159.907 416.425 + endloop + endfacet + facet normal 0.0518378 -0.486767 0.871993 + outer loop + vertex 184.067 164.768 419.094 + vertex 183.315 159.907 416.425 + vertex 199.176 166.377 419.094 + endloop + endfacet + facet normal 0.0520553 -0.487196 0.87174 + outer loop + vertex 199.176 166.377 419.094 + vertex 183.315 159.907 416.425 + vertex 199.736 161.66 416.424 + endloop + endfacet + facet normal 0.0561846 -0.486713 0.871753 + outer loop + vertex 199.176 166.377 419.094 + vertex 199.736 161.66 416.424 + vertex 216.442 168.37 419.094 + endloop + endfacet + facet normal 0.0565658 -0.487482 0.871299 + outer loop + vertex 216.442 168.37 419.094 + vertex 199.736 161.66 416.424 + vertex 216.385 163.589 416.423 + endloop + endfacet + facet normal 0.0607914 -0.487399 0.871061 + outer loop + vertex 216.442 168.37 419.094 + vertex 216.385 163.589 416.423 + vertex 233.365 170.481 419.094 + endloop + endfacet + facet normal 0.0607497 -0.487315 0.87111 + outer loop + vertex 233.365 170.481 419.094 + vertex 216.385 163.589 416.423 + vertex 232.964 165.647 416.418 + endloop + endfacet + facet normal 0.0651274 -0.487459 0.870714 + outer loop + vertex 233.365 170.481 419.094 + vertex 232.964 165.647 416.418 + vertex 249.654 172.657 419.094 + endloop + endfacet + facet normal 0.0645967 -0.48643 0.871328 + outer loop + vertex 249.654 172.657 419.094 + vertex 232.964 165.647 416.418 + vertex 249.534 167.83 416.408 + endloop + endfacet + facet normal 0.0692337 -0.486367 0.871007 + outer loop + vertex 249.654 172.657 419.094 + vertex 249.534 167.83 416.408 + vertex 266.612 175.071 419.094 + endloop + endfacet + facet normal 0.0680298 -0.484043 0.872396 + outer loop + vertex 266.612 175.071 419.094 + vertex 249.534 167.83 416.408 + vertex 266.142 170.192 416.424 + endloop + endfacet + facet normal 0.0731166 -0.484246 0.871871 + outer loop + vertex 266.612 175.071 419.094 + vertex 266.142 170.192 416.424 + vertex 283.092 177.559 419.094 + endloop + endfacet + facet normal 0.0720084 -0.48215 0.873124 + outer loop + vertex 283.092 177.559 419.094 + vertex 266.142 170.192 416.424 + vertex 282.591 172.672 416.437 + endloop + endfacet + facet normal 0.0767805 -0.482356 0.872604 + outer loop + vertex 283.092 177.559 419.094 + vertex 282.591 172.672 416.437 + vertex 298.851 180.068 419.094 + endloop + endfacet + facet normal 0.0773432 -0.483373 0.871991 + outer loop + vertex 298.851 180.068 419.094 + vertex 282.591 172.672 416.437 + vertex 299.234 175.358 416.449 + endloop + endfacet + facet normal 0.0821139 -0.482891 0.871822 + outer loop + vertex 298.851 180.068 419.094 + vertex 299.234 175.358 416.449 + vertex 315.944 182.946 419.078 + endloop + endfacet + facet normal 0.0862799 -0.490458 0.867183 + outer loop + vertex 315.944 182.946 419.078 + vertex 299.234 175.358 416.449 + vertex 316.112 178.211 416.384 + endloop + endfacet + facet normal 0.0784666 -0.443652 0.892757 + outer loop + vertex 299.234 175.358 416.449 + vertex 299.83 171.378 414.419 + vertex 316.112 178.211 416.384 + endloop + endfacet + facet normal 0.0714674 -0.444726 0.892811 + outer loop + vertex 299.234 175.358 416.449 + vertex 283.292 168.703 414.41 + vertex 299.83 171.378 414.419 + endloop + endfacet + facet normal 0.0690792 -0.42999 0.900187 + outer loop + vertex 283.292 168.703 414.41 + vertex 284.274 165.372 412.744 + vertex 299.83 171.378 414.419 + endloop + endfacet + facet normal 0.0692759 -0.430436 0.899959 + outer loop + vertex 299.83 171.378 414.419 + vertex 284.274 165.372 412.744 + vertex 302.143 169.019 413.113 + endloop + endfacet + facet normal 0.0754159 -0.425453 0.901833 + outer loop + vertex 299.83 171.378 414.419 + vertex 302.143 169.019 413.113 + vertex 316.722 174.236 414.355 + endloop + endfacet + facet normal 0.0709035 -0.443566 0.893432 + outer loop + vertex 282.591 172.672 416.437 + vertex 283.292 168.703 414.41 + vertex 299.234 175.358 416.449 + endloop + endfacet + facet normal 0.0663878 -0.444344 0.893393 + outer loop + vertex 282.591 172.672 416.437 + vertex 267.332 166.299 414.401 + vertex 283.292 168.703 414.41 + endloop + endfacet + facet normal 0.0640399 -0.428781 0.901136 + outer loop + vertex 267.332 166.299 414.401 + vertex 270.05 163.929 413.08 + vertex 283.292 168.703 414.41 + endloop + endfacet + facet normal 0.0662478 -0.444057 0.893546 + outer loop + vertex 266.142 170.192 416.424 + vertex 267.332 166.299 414.401 + vertex 282.591 172.672 416.437 + endloop + endfacet + facet normal 0.0627861 -0.445001 0.893326 + outer loop + vertex 266.142 170.192 416.424 + vertex 251.055 163.906 414.353 + vertex 267.332 166.299 414.401 + endloop + endfacet + facet normal 0.0602855 -0.428165 0.901688 + outer loop + vertex 251.055 163.906 414.353 + vertex 255.128 161.352 412.868 + vertex 267.332 166.299 414.401 + endloop + endfacet + facet normal 0.0623214 -0.444052 0.893831 + outer loop + vertex 249.534 167.83 416.408 + vertex 251.055 163.906 414.353 + vertex 266.142 170.192 416.424 + endloop + endfacet + facet normal 0.0593294 -0.445057 0.893535 + outer loop + vertex 249.534 167.83 416.408 + vertex 234.452 161.68 414.346 + vertex 251.055 163.906 414.353 + endloop + endfacet + facet normal 0.0569482 -0.427324 0.902303 + outer loop + vertex 234.452 161.68 414.346 + vertex 238.259 158.946 412.811 + vertex 251.055 163.906 414.353 + endloop + endfacet + facet normal 0.0590941 -0.444567 0.893794 + outer loop + vertex 232.964 165.647 416.418 + vertex 234.452 161.68 414.346 + vertex 249.534 167.83 416.408 + endloop + endfacet + facet normal 0.0558539 -0.445618 0.893479 + outer loop + vertex 232.964 165.647 416.418 + vertex 217.832 159.614 414.355 + vertex 234.452 161.68 414.346 + endloop + endfacet + facet normal 0.053536 -0.426928 0.9027 + outer loop + vertex 217.832 159.614 414.355 + vertex 221.459 156.813 412.815 + vertex 234.452 161.68 414.346 + endloop + endfacet + facet normal 0.0554861 -0.444836 0.893892 + outer loop + vertex 216.385 163.589 416.423 + vertex 217.832 159.614 414.355 + vertex 232.964 165.647 416.418 + endloop + endfacet + facet normal 0.0521664 -0.445879 0.893572 + outer loop + vertex 216.385 163.589 416.423 + vertex 201.291 157.706 414.369 + vertex 217.832 159.614 414.355 + endloop + endfacet + facet normal 0.0500273 -0.427265 0.902741 + outer loop + vertex 201.291 157.706 414.369 + vertex 204.744 154.839 412.82 + vertex 217.832 159.614 414.355 + endloop + endfacet + facet normal 0.0516041 -0.444659 0.894212 + outer loop + vertex 199.736 161.66 416.424 + vertex 201.291 157.706 414.369 + vertex 216.385 163.589 416.423 + endloop + endfacet + facet normal 0.0479872 -0.445873 0.893809 + outer loop + vertex 199.736 161.66 416.424 + vertex 184.783 155.919 414.363 + vertex 201.291 157.706 414.369 + endloop + endfacet + facet normal 0.0460379 -0.427893 0.902656 + outer loop + vertex 184.783 155.919 414.363 + vertex 188.258 153.039 412.821 + vertex 201.291 157.706 414.369 + endloop + endfacet + facet normal 0.0475409 -0.444894 0.894321 + outer loop + vertex 183.315 159.907 416.425 + vertex 184.783 155.919 414.363 + vertex 199.736 161.66 416.424 + endloop + endfacet + facet normal 0.0437392 -0.446086 0.893921 + outer loop + vertex 183.315 159.907 416.425 + vertex 168.391 154.324 414.369 + vertex 184.783 155.919 414.363 + endloop + endfacet + facet normal 0.0420313 -0.428504 0.902562 + outer loop + vertex 168.391 154.324 414.369 + vertex 171.898 151.399 412.817 + vertex 184.783 155.919 414.363 + endloop + endfacet + facet normal 0.0433073 -0.445117 0.894424 + outer loop + vertex 166.882 158.315 416.429 + vertex 168.391 154.324 414.369 + vertex 183.315 159.907 416.425 + endloop + endfacet + facet normal 0.0395403 -0.446321 0.893999 + outer loop + vertex 166.882 158.315 416.429 + vertex 151.991 152.884 414.376 + vertex 168.391 154.324 414.369 + endloop + endfacet + facet normal 0.0380117 -0.428878 0.902562 + outer loop + vertex 151.991 152.884 414.376 + vertex 155.532 149.921 412.819 + vertex 168.391 154.324 414.369 + endloop + endfacet + facet normal 0.0391481 -0.445422 0.894464 + outer loop + vertex 150.451 156.884 416.435 + vertex 151.991 152.884 414.376 + vertex 166.882 158.315 416.429 + endloop + endfacet + facet normal 0.0352144 -0.446694 0.893993 + outer loop + vertex 150.451 156.884 416.435 + vertex 135.557 151.605 414.384 + vertex 151.991 152.884 414.376 + endloop + endfacet + facet normal 0.0338611 -0.429237 0.902557 + outer loop + vertex 135.557 151.605 414.384 + vertex 139.106 148.629 412.836 + vertex 151.991 152.884 414.376 + endloop + endfacet + facet normal 0.0348057 -0.445734 0.894489 + outer loop + vertex 134.107 155.621 416.442 + vertex 135.557 151.605 414.384 + vertex 150.451 156.884 416.435 + endloop + endfacet + facet normal 0.0308973 -0.446916 0.894042 + outer loop + vertex 134.107 155.621 416.442 + vertex 118.881 150.457 414.387 + vertex 135.557 151.605 414.384 + endloop + endfacet + facet normal 0.0297025 -0.429555 0.902552 + outer loop + vertex 118.881 150.457 414.387 + vertex 122.41 147.46 412.844 + vertex 135.557 151.605 414.384 + endloop + endfacet + facet normal 0.0304496 -0.44582 0.894605 + outer loop + vertex 117.355 154.468 416.437 + vertex 118.881 150.457 414.387 + vertex 134.107 155.621 416.442 + endloop + endfacet + facet normal 0.026181 -0.447168 0.894067 + outer loop + vertex 117.355 154.468 416.437 + vertex 101.457 149.36 414.348 + vertex 118.881 150.457 414.387 + endloop + endfacet + facet normal 0.0250431 -0.429401 0.902766 + outer loop + vertex 101.457 149.36 414.348 + vertex 105.04 146.324 412.805 + vertex 118.881 150.457 414.387 + endloop + endfacet + facet normal 0.0257594 -0.446083 0.894621 + outer loop + vertex 100.258 153.448 416.421 + vertex 101.457 149.36 414.348 + vertex 117.355 154.468 416.437 + endloop + endfacet + facet normal 0.0215093 -0.447123 0.894214 + outer loop + vertex 100.258 153.448 416.421 + vertex 83.7379 148.483 414.336 + vertex 101.457 149.36 414.348 + endloop + endfacet + facet normal 0.0207009 -0.430903 0.902161 + outer loop + vertex 83.7379 148.483 414.336 + vertex 85.0082 144.926 412.608 + vertex 101.457 149.36 414.348 + endloop + endfacet + facet normal 0.0214755 -0.44703 0.894261 + outer loop + vertex 83.3394 152.638 416.422 + vertex 83.7379 148.483 414.336 + vertex 100.258 153.448 416.421 + endloop + endfacet + facet normal 0.017027 -0.44741 0.894167 + outer loop + vertex 83.3394 152.638 416.422 + vertex 66.6066 147.894 414.367 + vertex 83.7379 148.483 414.336 + endloop + endfacet + facet normal 0.016526 -0.43244 0.901511 + outer loop + vertex 66.6066 147.894 414.367 + vertex 66.7674 144.617 412.793 + vertex 83.7379 148.483 414.336 + endloop + endfacet + facet normal 0.0169222 -0.447106 0.894321 + outer loop + vertex 66.7039 152.012 416.424 + vertex 66.6066 147.894 414.367 + vertex 83.3394 152.638 416.422 + endloop + endfacet + facet normal 0.0129911 -0.447058 0.89441 + outer loop + vertex 66.7039 152.012 416.424 + vertex 50.4632 147.505 414.407 + vertex 66.6066 147.894 414.367 + endloop + endfacet + facet normal 0.0126694 -0.433022 0.901294 + outer loop + vertex 50.4632 147.505 414.407 + vertex 49.9878 144.319 412.883 + vertex 66.6066 147.894 414.367 + endloop + endfacet + facet normal 0.0127683 -0.446404 0.894741 + outer loop + vertex 50.0673 151.532 416.422 + vertex 50.4632 147.505 414.407 + vertex 66.7039 152.012 416.424 + endloop + endfacet + facet normal 0.00910862 -0.446709 0.894633 + outer loop + vertex 50.0673 151.532 416.422 + vertex 34.5129 147.162 414.399 + vertex 50.4632 147.505 414.407 + endloop + endfacet + facet normal 0.00875479 -0.430426 0.902583 + outer loop + vertex 34.5129 147.162 414.399 + vertex 37.0748 144.507 413.107 + vertex 50.4632 147.505 414.407 + endloop + endfacet + facet normal 0.00897969 -0.446337 0.89482 + outer loop + vertex 33.3024 151.185 416.418 + vertex 34.5129 147.162 414.399 + vertex 50.0673 151.532 416.422 + endloop + endfacet + facet normal 0.0055077 -0.447184 0.894425 + outer loop + vertex 33.3024 151.185 416.418 + vertex 17.4626 146.819 414.332 + vertex 34.5129 147.162 414.399 + endloop + endfacet + facet normal 0.00513517 -0.430288 0.902677 + outer loop + vertex 17.4626 146.819 414.332 + vertex 21.5361 143.741 412.842 + vertex 34.5129 147.162 414.399 + endloop + endfacet + facet normal 0.00517106 -0.446198 0.894919 + outer loop + vertex 16.426 150.983 416.414 + vertex 17.4626 146.819 414.332 + vertex 33.3024 151.185 416.418 + endloop + endfacet + facet normal 0.0020813 -0.446819 0.894622 + outer loop + vertex 16.426 150.983 416.414 + vertex 0.775451 146.826 414.374 + vertex 17.4626 146.819 414.332 + endloop + endfacet + facet normal 0.00210626 -0.431666 0.902031 + outer loop + vertex 0.775451 146.826 414.374 + vertex 1.50638 143.206 412.64 + vertex 17.4626 146.819 414.332 + endloop + endfacet + facet normal 0.00197224 -0.446489 0.894787 + outer loop + vertex -0.0377764 150.956 416.437 + vertex 0.775451 146.826 414.374 + vertex 16.426 150.983 416.414 + endloop + endfacet + facet normal -0.00141043 -0.447023 0.894521 + outer loop + vertex -0.0377764 150.956 416.437 + vertex -15.0684 146.958 414.415 + vertex 0.775451 146.826 414.374 + endloop + endfacet + facet normal -0.00125366 -0.430709 0.90249 + outer loop + vertex -15.0684 146.958 414.415 + vertex -12.4018 144.119 413.064 + vertex 0.775451 146.826 414.374 + endloop + endfacet + facet normal -0.00172364 -0.446082 0.89499 + outer loop + vertex -16.318 151.016 416.435 + vertex -15.0684 146.958 414.415 + vertex -0.0377764 150.956 416.437 + endloop + endfacet + facet normal -0.00498966 -0.446883 0.894578 + outer loop + vertex -16.318 151.016 416.435 + vertex -31.8808 147.023 414.354 + vertex -15.0684 146.958 414.415 + endloop + endfacet + facet normal -0.00495448 -0.430198 0.902721 + outer loop + vertex -31.8808 147.023 414.354 + vertex -27.8344 143.813 412.846 + vertex -15.0684 146.958 414.415 + endloop + endfacet + facet normal -0.00512887 -0.446452 0.894793 + outer loop + vertex -32.8692 151.198 416.432 + vertex -31.8808 147.023 414.354 + vertex -16.318 151.016 416.435 + endloop + endfacet + facet normal -0.00897711 -0.44717 0.894404 + outer loop + vertex -32.8692 151.198 416.432 + vertex -49.3823 147.352 414.343 + vertex -31.8808 147.023 414.354 + endloop + endfacet + facet normal -0.0086782 -0.430974 0.902322 + outer loop + vertex -49.3823 147.352 414.343 + vertex -48.0108 143.692 412.608 + vertex -31.8808 147.023 414.354 + endloop + endfacet + facet normal -0.00914451 -0.446604 0.894685 + outer loop + vertex -49.623 151.524 416.423 + vertex -49.3823 147.352 414.343 + vertex -32.8692 151.198 416.432 + endloop + endfacet + facet normal -0.0131082 -0.446767 0.894554 + outer loop + vertex -49.623 151.524 416.423 + vertex -66.6237 147.894 414.361 + vertex -49.3823 147.352 414.343 + endloop + endfacet + facet normal -0.0126205 -0.431508 0.902021 + outer loop + vertex -66.6237 147.894 414.361 + vertex -66.4604 144.596 412.786 + vertex -49.3823 147.352 414.343 + endloop + endfacet + facet normal -0.0129684 -0.447278 0.894301 + outer loop + vertex -66.4758 152.009 416.421 + vertex -66.6237 147.894 414.361 + vertex -49.623 151.524 416.423 + endloop + endfacet + facet normal -0.0171348 -0.44713 0.894305 + outer loop + vertex -66.4758 152.009 416.421 + vertex -83.5334 148.551 414.365 + vertex -66.6237 147.894 414.361 + endloop + endfacet + facet normal -0.0165463 -0.432027 0.901709 + outer loop + vertex -83.5334 148.551 414.365 + vertex -83.6741 145.327 412.818 + vertex -66.6237 147.894 414.361 + endloop + endfacet + facet normal -0.0170026 -0.447634 0.894055 + outer loop + vertex -83.2171 152.643 416.42 + vertex -83.5334 148.551 414.365 + vertex -66.4758 152.009 416.421 + endloop + endfacet + facet normal -0.021009 -0.447352 0.894111 + outer loop + vertex -83.2171 152.643 416.42 + vertex -99.5608 149.381 414.404 + vertex -83.5334 148.551 414.365 + endloop + endfacet + facet normal -0.0202649 -0.433311 0.901017 + outer loop + vertex -99.5608 149.381 414.404 + vertex -100.247 146.24 412.878 + vertex -83.5334 148.551 414.365 + endloop + endfacet + facet normal -0.0210368 -0.447245 0.894164 + outer loop + vertex -99.7398 153.431 416.426 + vertex -99.5608 149.381 414.404 + vertex -83.2171 152.643 416.42 + endloop + endfacet + facet normal -0.0250718 -0.447347 0.894009 + outer loop + vertex -99.7398 153.431 416.426 + vertex -115.151 150.249 414.401 + vertex -99.5608 149.381 414.404 + endloop + endfacet + facet normal -0.0241328 -0.430462 0.902286 + outer loop + vertex -115.151 150.249 414.401 + vertex -112.873 147.404 413.105 + vertex -99.5608 149.381 414.404 + endloop + endfacet + facet normal -0.0254876 -0.445812 0.894763 + outer loop + vertex -116.359 154.367 416.419 + vertex -115.151 150.249 414.401 + vertex -99.7398 153.431 416.426 + endloop + endfacet + facet normal -0.029574 -0.446726 0.894182 + outer loop + vertex -116.359 154.367 416.419 + vertex -131.458 151.25 414.362 + vertex -115.151 150.249 414.401 + endloop + endfacet + facet normal -0.0285465 -0.429659 0.90254 + outer loop + vertex -131.458 151.25 414.362 + vertex -127.58 147.878 412.879 + vertex -115.151 150.249 414.401 + endloop + endfacet + facet normal -0.0299125 -0.445486 0.894789 + outer loop + vertex -132.967 155.48 416.417 + vertex -131.458 151.25 414.362 + vertex -116.359 154.367 416.419 + endloop + endfacet + facet normal -0.0344451 -0.446724 0.894008 + outer loop + vertex -132.967 155.48 416.417 + vertex -148.761 152.518 414.329 + vertex -131.458 151.25 414.362 + endloop + endfacet + facet normal -0.0331713 -0.429108 0.902644 + outer loop + vertex -148.761 152.518 414.329 + vertex -145.063 148.987 412.786 + vertex -131.458 151.25 414.362 + endloop + endfacet + facet normal -0.0346796 -0.445795 0.894463 + outer loop + vertex -149.702 156.787 416.42 + vertex -148.761 152.518 414.329 + vertex -132.967 155.48 416.417 + endloop + endfacet + facet normal -0.0392039 -0.446523 0.893913 + outer loop + vertex -149.702 156.787 416.42 + vertex -166.397 154.055 414.323 + vertex -148.761 152.518 414.329 + endloop + endfacet + facet normal -0.0377507 -0.429826 0.902122 + outer loop + vertex -166.397 154.055 414.323 + vertex -165.127 150.327 412.6 + vertex -148.761 152.518 414.329 + endloop + endfacet + facet normal -0.0392701 -0.446229 0.894057 + outer loop + vertex -166.657 158.27 416.416 + vertex -166.397 154.055 414.323 + vertex -149.702 156.787 416.42 + endloop + endfacet + facet normal -0.0434132 -0.446357 0.893801 + outer loop + vertex -166.657 158.27 416.416 + vertex -183.481 155.799 414.364 + vertex -166.397 154.055 414.323 + endloop + endfacet + facet normal -0.0418768 -0.431476 0.901152 + outer loop + vertex -183.481 155.799 414.364 + vertex -183.399 152.504 412.79 + vertex -166.397 154.055 414.323 + endloop + endfacet + facet normal -0.0433532 -0.446648 0.893659 + outer loop + vertex -183.313 159.904 416.424 + vertex -183.481 155.799 414.364 + vertex -166.657 158.27 416.416 + endloop + endfacet + facet normal -0.0472145 -0.446442 0.893566 + outer loop + vertex -183.313 159.904 416.424 + vertex -199.475 157.581 414.41 + vertex -183.481 155.799 414.364 + endloop + endfacet + facet normal -0.045587 -0.432019 0.900712 + outer loop + vertex -199.475 157.581 414.41 + vertex -200.062 154.457 412.881 + vertex -183.481 155.799 414.364 + endloop + endfacet + facet normal -0.047335 -0.445854 0.893853 + outer loop + vertex -199.673 161.654 416.431 + vertex -199.475 157.581 414.41 + vertex -183.313 159.904 416.424 + endloop + endfacet + facet normal -0.0510899 -0.445917 0.893615 + outer loop + vertex -199.673 161.654 416.431 + vertex -214.996 159.361 414.41 + vertex -199.475 157.581 414.41 + endloop + endfacet + facet normal -0.0491389 -0.428904 0.902013 + outer loop + vertex -214.996 159.361 414.41 + vertex -212.662 156.371 413.116 + vertex -199.475 157.581 414.41 + endloop + endfacet + facet normal -0.0513978 -0.444476 0.894315 + outer loop + vertex -216.144 163.544 416.423 + vertex -214.996 159.361 414.41 + vertex -199.673 161.654 416.431 + endloop + endfacet + facet normal -0.055083 -0.445207 0.893732 + outer loop + vertex -216.144 163.544 416.423 + vertex -231.272 161.287 414.367 + vertex -214.996 159.361 414.41 + endloop + endfacet + facet normal -0.0530466 -0.427804 0.902313 + outer loop + vertex -231.272 161.287 414.367 + vertex -227.359 157.679 412.886 + vertex -214.996 159.361 414.41 + endloop + endfacet + facet normal -0.0553142 -0.444132 0.894252 + outer loop + vertex -232.697 165.585 416.413 + vertex -231.272 161.287 414.367 + vertex -216.144 163.544 416.423 + endloop + endfacet + facet normal -0.0589829 -0.445025 0.893574 + outer loop + vertex -232.697 165.585 416.413 + vertex -248.44 163.484 414.328 + vertex -231.272 161.287 414.367 + endloop + endfacet + facet normal -0.0567939 -0.427773 0.9021 + outer loop + vertex -248.44 163.484 414.328 + vertex -244.842 159.761 412.789 + vertex -231.272 161.287 414.367 + endloop + endfacet + facet normal -0.059017 -0.444852 0.893657 + outer loop + vertex -249.167 167.774 416.415 + vertex -248.44 163.484 414.328 + vertex -232.697 165.585 416.413 + endloop + endfacet + facet normal -0.0626668 -0.445253 0.893209 + outer loop + vertex -249.167 167.774 416.415 + vertex -265.613 165.916 414.335 + vertex -248.44 163.484 414.328 + endloop + endfacet + facet normal -0.0603897 -0.429195 0.901191 + outer loop + vertex -265.613 165.916 414.335 + vertex -264.74 162.159 412.604 + vertex -248.44 163.484 414.328 + endloop + endfacet + facet normal -0.0627156 -0.444973 0.893345 + outer loop + vertex -265.773 170.151 416.433 + vertex -265.613 165.916 414.335 + vertex -249.167 167.774 416.415 + endloop + endfacet + facet normal -0.0668096 -0.444979 0.893045 + outer loop + vertex -265.773 170.151 416.433 + vertex -282.149 168.526 414.399 + vertex -265.613 165.916 414.335 + endloop + endfacet + facet normal -0.0643604 -0.42965 0.900699 + outer loop + vertex -282.149 168.526 414.399 + vertex -282.332 165.213 412.805 + vertex -265.613 165.916 414.335 + endloop + endfacet + facet normal -0.0669902 -0.443847 0.893595 + outer loop + vertex -282.216 172.697 416.465 + vertex -282.149 168.526 414.399 + vertex -265.773 170.151 416.433 + endloop + endfacet + facet normal -0.072009 -0.443755 0.89325 + outer loop + vertex -282.216 172.697 416.465 + vertex -298.264 171.296 414.475 + vertex -282.149 168.526 414.399 + endloop + endfacet + facet normal -0.0693046 -0.428234 0.901006 + outer loop + vertex -298.264 171.296 414.475 + vertex -298.741 168.05 412.896 + vertex -282.149 168.526 414.399 + endloop + endfacet + facet normal -0.0722104 -0.442389 0.893912 + outer loop + vertex -298.892 175.533 416.522 + vertex -298.264 171.296 414.475 + vertex -282.216 172.697 416.465 + endloop + endfacet + facet normal -0.0788488 -0.442964 0.893065 + outer loop + vertex -298.892 175.533 416.522 + vertex -315.424 174.403 414.502 + vertex -298.264 171.296 414.475 + endloop + endfacet + facet normal -0.0750908 -0.422298 0.903341 + outer loop + vertex -315.424 174.403 414.502 + vertex -312.529 170.896 413.103 + vertex -298.264 171.296 414.475 + endloop + endfacet + facet normal -0.0789352 -0.442286 0.893393 + outer loop + vertex -316.385 178.783 416.585 + vertex -315.424 174.403 414.502 + vertex -298.892 175.533 416.522 + endloop + endfacet + facet normal -0.0873587 -0.44348 0.892017 + outer loop + vertex -316.385 178.783 416.585 + vertex -334.16 178.164 414.537 + vertex -315.424 174.403 414.502 + endloop + endfacet + facet normal -0.0878547 -0.438008 0.894668 + outer loop + vertex -334.206 182.478 416.644 + vertex -334.16 178.164 414.537 + vertex -316.385 178.783 416.585 + endloop + endfacet + facet normal -0.101773 -0.419936 0.901829 + outer loop + vertex -347.943 184.204 415.898 + vertex -346.27 181.84 414.986 + vertex -334.206 182.478 416.644 + endloop + endfacet + facet normal -0.122225 -0.429821 0.894603 + outer loop + vertex -356.155 188.731 416.956 + vertex -356.181 186.458 415.86 + vertex -345.779 186.056 417.088 + endloop + endfacet + facet normal -0.115034 -0.427354 0.896736 + outer loop + vertex -347.943 184.204 415.898 + vertex -356.231 184.344 414.901 + vertex -346.27 181.84 414.986 + endloop + endfacet + facet normal -0.143095 -0.388642 0.91021 + outer loop + vertex -365.098 189.047 415.564 + vertex -365.081 186.907 414.653 + vertex -356.181 186.458 415.86 + endloop + endfacet + facet normal -0.137336 -0.404281 0.904265 + outer loop + vertex -356.231 184.344 414.901 + vertex -365.141 184.826 413.763 + vertex -356.218 182.198 413.943 + endloop + endfacet + facet normal -0.173274 -0.357366 0.91775 + outer loop + vertex -373.879 189.843 414.135 + vertex -374.028 187.791 413.308 + vertex -365.081 186.907 414.653 + endloop + endfacet + facet normal -0.133625 -0.391251 0.910531 + outer loop + vertex -365.141 184.826 413.763 + vertex -365.263 182.733 412.846 + vertex -356.218 182.198 413.943 + endloop + endfacet + facet normal -0.109644 -0.405547 0.907474 + outer loop + vertex -356.231 184.344 414.901 + vertex -356.218 182.198 413.943 + vertex -346.27 181.84 414.986 + endloop + endfacet + facet normal -0.0997089 -0.43762 0.893614 + outer loop + vertex -334.16 178.164 414.537 + vertex -334.206 182.478 416.644 + vertex -346.27 181.84 414.986 + endloop + endfacet + facet normal -0.108403 -0.421047 0.900538 + outer loop + vertex -347.852 179.825 413.896 + vertex -356.188 179.96 412.955 + vertex -345.771 177.271 412.952 + endloop + endfacet + facet normal -0.0822665 -0.41823 0.904608 + outer loop + vertex -334.16 178.164 414.537 + vertex -332.222 173.51 412.561 + vertex -315.424 174.403 414.502 + endloop + endfacet + facet normal -0.104306 -0.405184 0.908266 + outer loop + vertex -356.188 179.96 412.955 + vertex -356.162 177.763 411.979 + vertex -345.771 177.271 412.952 + endloop + endfacet + facet normal -0.132314 -0.403044 0.905565 + outer loop + vertex -356.162 177.763 411.979 + vertex -365.474 178.749 411.057 + vertex -356.263 175.954 411.159 + endloop + endfacet + facet normal -0.133596 -0.407348 0.903449 + outer loop + vertex -365.474 178.749 411.057 + vertex -365.524 177.425 410.453 + vertex -356.263 175.954 411.159 + endloop + endfacet + facet normal -0.175305 -0.42191 0.889528 + outer loop + vertex -365.524 177.425 410.453 + vertex -374.78 179.848 409.777 + vertex -365.597 176.854 410.167 + endloop + endfacet + facet normal -0.231314 -0.610947 0.757124 + outer loop + vertex -374.78 179.848 409.777 + vertex -374.813 179.736 409.677 + vertex -365.597 176.854 410.167 + endloop + endfacet + facet normal -0.255558 -0.704671 0.661913 + outer loop + vertex -365.597 176.854 410.167 + vertex -374.813 179.736 409.677 + vertex -365.671 176.82 410.102 + endloop + endfacet + facet normal -0.149665 -0.333505 0.930792 + outer loop + vertex -374.813 179.736 409.677 + vertex -374.452 179.494 409.648 + vertex -365.671 176.82 410.102 + endloop + endfacet + facet normal -0.173131 -0.417106 0.892216 + outer loop + vertex -365.671 176.82 410.102 + vertex -374.452 179.494 409.648 + vertex -365.389 176.308 409.918 + endloop + endfacet + facet normal -0.158856 -0.675695 0.719862 + outer loop + vertex -356.671 174.521 410.437 + vertex -356.888 174.508 410.376 + vertex -347.096 172.482 410.636 + endloop + endfacet + facet normal -0.129077 -0.523912 0.841936 + outer loop + vertex -348.776 173.106 410.767 + vertex -356.671 174.521 410.437 + vertex -347.096 172.482 410.636 + endloop + endfacet + facet normal -0.102613 -0.382361 0.918298 + outer loop + vertex -346.442 173.719 411.282 + vertex -356.471 174.862 410.638 + vertex -348.776 173.106 410.767 + endloop + endfacet + facet normal -0.0877762 -0.405131 0.910035 + outer loop + vertex -332.222 173.51 412.561 + vertex -347.424 175.366 411.921 + vertex -346.442 173.719 411.282 + endloop + endfacet + facet normal -0.08026 -0.410986 0.908102 + outer loop + vertex -337.752 171.625 411.191 + vertex -334.183 169.356 410.48 + vertex -318.339 168.942 411.693 + endloop + endfacet + facet normal -0.0802179 -0.415836 0.905895 + outer loop + vertex -318.339 168.942 411.693 + vertex -334.183 169.356 410.48 + vertex -314.271 164.927 410.21 + endloop + endfacet + facet normal -0.0813897 -0.426492 0.900822 + outer loop + vertex -315.424 174.403 414.502 + vertex -332.222 173.51 412.561 + vertex -312.529 170.896 413.103 + endloop + endfacet + facet normal -0.0747185 -0.427416 0.900962 + outer loop + vertex -298.264 171.296 414.475 + vertex -312.529 170.896 413.103 + vertex -298.741 168.05 412.896 + endloop + endfacet + facet normal -0.0723262 -0.409199 0.909574 + outer loop + vertex -318.339 168.942 411.693 + vertex -314.271 164.927 410.21 + vertex -299.016 165.342 411.609 + endloop + endfacet + facet normal -0.0718062 -0.4168 0.906158 + outer loop + vertex -299.016 165.342 411.609 + vertex -314.271 164.927 410.21 + vertex -296.779 162.329 410.401 + endloop + endfacet + facet normal -0.0692292 -0.429291 0.900509 + outer loop + vertex -282.149 168.526 414.399 + vertex -298.741 168.05 412.896 + vertex -282.332 165.213 412.805 + endloop + endfacet + facet normal -0.0664839 -0.413597 0.908029 + outer loop + vertex -299.016 165.342 411.609 + vertex -296.779 162.329 410.401 + vertex -282.904 162.629 411.553 + endloop + endfacet + facet normal -0.0660417 -0.42103 0.904639 + outer loop + vertex -282.904 162.629 411.553 + vertex -296.779 162.329 410.401 + vertex -281.875 159.696 410.264 + endloop + endfacet + facet normal -0.0658377 -0.419904 0.905178 + outer loop + vertex -281.875 159.696 410.264 + vertex -296.779 162.329 410.401 + vertex -291.79 158.921 409.183 + endloop + endfacet + facet normal -0.0643438 -0.429845 0.900607 + outer loop + vertex -265.613 165.916 414.335 + vertex -282.332 165.213 412.805 + vertex -264.74 162.159 412.604 + endloop + endfacet + facet normal -0.0634966 -0.420355 0.905135 + outer loop + vertex -282.904 162.629 411.553 + vertex -281.875 159.696 410.264 + vertex -270.656 160.289 411.326 + endloop + endfacet + facet normal -0.063095 -0.42452 0.903218 + outer loop + vertex -270.656 160.289 411.326 + vertex -281.875 159.696 410.264 + vertex -265.588 157.194 410.225 + endloop + endfacet + facet normal -0.0627871 -0.422531 0.904171 + outer loop + vertex -265.588 157.194 410.225 + vertex -281.875 159.696 410.264 + vertex -274.582 156.243 409.157 + endloop + endfacet + facet normal -0.0606624 -0.421156 0.904957 + outer loop + vertex -270.656 160.289 411.326 + vertex -265.588 157.194 410.225 + vertex -255.888 158.58 411.521 + endloop + endfacet + facet normal -0.0600179 -0.424323 0.90352 + outer loop + vertex -255.888 158.58 411.521 + vertex -265.588 157.194 410.225 + vertex -248.296 154.756 410.229 + endloop + endfacet + facet normal -0.0596221 -0.421513 0.90486 + outer loop + vertex -248.296 154.756 410.229 + vertex -265.588 157.194 410.225 + vertex -256.717 153.583 409.128 + endloop + endfacet + facet normal -0.0602236 -0.430465 0.900596 + outer loop + vertex -248.44 163.484 414.328 + vertex -264.74 162.159 412.604 + vertex -244.842 159.761 412.789 + endloop + endfacet + facet normal -0.0570485 -0.419285 0.90606 + outer loop + vertex -255.888 158.58 411.521 + vertex -248.296 154.756 410.229 + vertex -238.258 156.386 411.615 + endloop + endfacet + facet normal -0.056075 -0.423616 0.904105 + outer loop + vertex -238.258 156.386 411.615 + vertex -248.296 154.756 410.229 + vertex -231.392 152.874 410.396 + endloop + endfacet + facet normal -0.0557733 -0.420787 0.905443 + outer loop + vertex -231.392 152.874 410.396 + vertex -248.296 154.756 410.229 + vertex -238.773 151.114 409.123 + endloop + endfacet + facet normal -0.0563069 -0.430695 0.900739 + outer loop + vertex -231.272 161.287 414.367 + vertex -244.842 159.761 412.789 + vertex -227.359 157.679 412.886 + endloop + endfacet + facet normal -0.0527248 -0.418036 0.906899 + outer loop + vertex -238.258 156.386 411.615 + vertex -231.392 152.874 410.396 + vertex -218.444 154.287 411.8 + endloop + endfacet + facet normal -0.0520026 -0.422595 0.904825 + outer loop + vertex -218.444 154.287 411.8 + vertex -231.392 152.874 410.396 + vertex -214.802 150.583 410.279 + endloop + endfacet + facet normal -0.051384 -0.418222 0.90689 + outer loop + vertex -214.802 150.583 410.279 + vertex -231.392 152.874 410.396 + vertex -225.271 149.957 409.397 + endloop + endfacet + facet normal -0.0524347 -0.43097 0.900842 + outer loop + vertex -214.996 159.361 414.41 + vertex -227.359 157.679 412.886 + vertex -212.662 156.371 413.116 + endloop + endfacet + facet normal -0.0487857 -0.431466 0.900809 + outer loop + vertex -199.475 157.581 414.41 + vertex -212.662 156.371 413.116 + vertex -200.062 154.457 412.881 + endloop + endfacet + facet normal -0.048215 -0.41954 0.906456 + outer loop + vertex -218.444 154.287 411.8 + vertex -214.802 150.583 410.279 + vertex -200.1 151.765 411.608 + endloop + endfacet + facet normal -0.0479734 -0.421524 0.905547 + outer loop + vertex -200.1 151.765 411.608 + vertex -214.802 150.583 410.279 + vertex -197.361 148.6 410.28 + endloop + endfacet + facet normal -0.0475678 -0.417957 0.907221 + outer loop + vertex -197.361 148.6 410.28 + vertex -214.802 150.583 410.279 + vertex -207.73 147.822 409.378 + endloop + endfacet + facet normal -0.0456532 -0.431482 0.900966 + outer loop + vertex -183.481 155.799 414.364 + vertex -200.062 154.457 412.881 + vertex -183.399 152.504 412.79 + endloop + endfacet + facet normal -0.0447201 -0.419227 0.90678 + outer loop + vertex -200.1 151.765 411.608 + vertex -197.361 148.6 410.28 + vertex -183.409 149.854 411.548 + endloop + endfacet + facet normal -0.0443307 -0.422187 0.905424 + outer loop + vertex -183.409 149.854 411.548 + vertex -197.361 148.6 410.28 + vertex -181.076 147.104 410.38 + endloop + endfacet + facet normal -0.0440707 -0.419264 0.906794 + outer loop + vertex -181.076 147.104 410.38 + vertex -197.361 148.6 410.28 + vertex -189.823 145.966 409.429 + endloop + endfacet + facet normal -0.0419502 -0.430927 0.901411 + outer loop + vertex -166.397 154.055 414.323 + vertex -183.399 152.504 412.79 + vertex -165.127 150.327 412.6 + endloop + endfacet + facet normal -0.0417676 -0.420414 0.90637 + outer loop + vertex -183.409 149.854 411.548 + vertex -181.076 147.104 410.38 + vertex -170.695 148.17 411.353 + endloop + endfacet + facet normal -0.0409969 -0.425699 0.903936 + outer loop + vertex -170.695 148.17 411.353 + vertex -181.076 147.104 410.38 + vertex -165.596 145.375 410.267 + endloop + endfacet + facet normal -0.0403539 -0.420114 0.906574 + outer loop + vertex -165.596 145.375 410.267 + vertex -181.076 147.104 410.38 + vertex -174.333 144.448 409.449 + endloop + endfacet + facet normal -0.0379823 -0.421089 0.906224 + outer loop + vertex -170.695 148.17 411.353 + vertex -165.596 145.375 410.267 + vertex -156.046 147.23 411.53 + endloop + endfacet + facet normal -0.0367998 -0.425731 0.904101 + outer loop + vertex -156.046 147.23 411.53 + vertex -165.596 145.375 410.267 + vertex -148.564 143.909 410.27 + endloop + endfacet + facet normal -0.0363352 -0.420328 0.906644 + outer loop + vertex -148.564 143.909 410.27 + vertex -165.596 145.375 410.267 + vertex -156.662 142.715 409.393 + endloop + endfacet + facet normal -0.037245 -0.432581 0.900825 + outer loop + vertex -148.761 152.518 414.329 + vertex -165.127 150.327 412.6 + vertex -145.063 148.987 412.786 + endloop + endfacet + facet normal -0.0339449 -0.420304 0.906748 + outer loop + vertex -156.046 147.23 411.53 + vertex -148.564 143.909 410.27 + vertex -138.539 146.008 411.619 + endloop + endfacet + facet normal -0.0325099 -0.425602 0.904326 + outer loop + vertex -138.539 146.008 411.619 + vertex -148.564 143.909 410.27 + vertex -131.721 142.89 410.397 + endloop + endfacet + facet normal -0.0321476 -0.419242 0.907305 + outer loop + vertex -131.721 142.89 410.397 + vertex -148.564 143.909 410.27 + vertex -138.873 141.326 409.42 + endloop + endfacet + facet normal -0.0322772 -0.433158 0.90074 + outer loop + vertex -131.458 151.25 414.362 + vertex -145.063 148.987 412.786 + vertex -127.58 147.878 412.879 + endloop + endfacet + facet normal -0.0291027 -0.419341 0.907362 + outer loop + vertex -138.539 146.008 411.619 + vertex -131.721 142.89 410.397 + vertex -118.715 144.989 411.783 + endloop + endfacet + facet normal -0.0281351 -0.423944 0.905251 + outer loop + vertex -118.715 144.989 411.783 + vertex -131.721 142.89 410.397 + vertex -114.782 141.418 410.234 + endloop + endfacet + facet normal -0.0279389 -0.421798 0.906259 + outer loop + vertex -114.782 141.418 410.234 + vertex -131.721 142.89 410.397 + vertex -124.738 139.676 409.116 + endloop + endfacet + facet normal -0.0277638 -0.43281 0.901058 + outer loop + vertex -115.151 150.249 414.401 + vertex -127.58 147.878 412.879 + vertex -112.873 147.404 413.105 + endloop + endfacet + facet normal -0.0237029 -0.432669 0.901241 + outer loop + vertex -99.5608 149.381 414.404 + vertex -112.873 147.404 413.105 + vertex -100.247 146.24 412.878 + endloop + endfacet + facet normal -0.0240776 -0.420268 0.90708 + outer loop + vertex -118.715 144.989 411.783 + vertex -114.782 141.418 410.234 + vertex -100.215 143.519 411.593 + endloop + endfacet + facet normal -0.0237109 -0.422228 0.906179 + outer loop + vertex -100.215 143.519 411.593 + vertex -114.782 141.418 410.234 + vertex -97.1158 140.44 410.24 + endloop + endfacet + facet normal -0.020528 -0.431854 0.90171 + outer loop + vertex -83.5334 148.551 414.365 + vertex -100.247 146.24 412.878 + vertex -83.6741 145.327 412.818 + endloop + endfacet + facet normal -0.020082 -0.419226 0.90766 + outer loop + vertex -100.215 143.519 411.593 + vertex -97.1158 140.44 410.24 + vertex -82.9165 142.67 411.584 + endloop + endfacet + facet normal -0.0194172 -0.42254 0.906136 + outer loop + vertex -82.9165 142.67 411.584 + vertex -97.1158 140.44 410.24 + vertex -80.1465 139.965 410.382 + endloop + endfacet + facet normal -0.0194109 -0.42228 0.906258 + outer loop + vertex -80.1465 139.965 410.382 + vertex -97.1158 140.44 410.24 + vertex -88.4937 137.679 409.138 + endloop + endfacet + facet normal -0.0166205 -0.431644 0.901891 + outer loop + vertex -66.6237 147.894 414.361 + vertex -83.6741 145.327 412.818 + vertex -66.4604 144.596 412.786 + endloop + endfacet + facet normal -0.0161374 -0.41978 0.907482 + outer loop + vertex -82.9165 142.67 411.584 + vertex -80.1465 139.965 410.382 + vertex -66.4778 141.93 411.535 + endloop + endfacet + facet normal -0.0155026 -0.423254 0.905878 + outer loop + vertex -66.4778 141.93 411.535 + vertex -80.1465 139.965 410.382 + vertex -64.4393 139.071 410.233 + endloop + endfacet + facet normal -0.015315 -0.420194 0.907305 + outer loop + vertex -64.4393 139.071 410.233 + vertex -80.1465 139.965 410.382 + vertex -74.7263 137.695 409.423 + endloop + endfacet + facet normal -0.0124945 -0.432123 0.901728 + outer loop + vertex -49.3823 147.352 414.343 + vertex -66.4604 144.596 412.786 + vertex -48.0108 143.692 412.608 + endloop + endfacet + facet normal -0.0127652 -0.42166 0.906664 + outer loop + vertex -66.4778 141.93 411.535 + vertex -64.4393 139.071 410.233 + vertex -53.5032 141.057 411.311 + endloop + endfacet + facet normal -0.0116567 -0.426532 0.904397 + outer loop + vertex -53.5032 141.057 411.311 + vertex -64.4393 139.071 410.233 + vertex -47.6223 138.682 410.267 + endloop + endfacet + facet normal -0.0115402 -0.42129 0.906853 + outer loop + vertex -47.6223 138.682 410.267 + vertex -64.4393 139.071 410.233 + vertex -56.666 137.022 409.38 + endloop + endfacet + facet normal -0.00934087 -0.421789 0.906646 + outer loop + vertex -53.5032 141.057 411.311 + vertex -47.6223 138.682 410.267 + vertex -38.3494 141.245 411.555 + endloop + endfacet + facet normal -0.00794345 -0.425887 0.904742 + outer loop + vertex -38.3494 141.245 411.555 + vertex -47.6223 138.682 410.267 + vertex -31.6677 138.694 410.412 + endloop + endfacet + facet normal -0.00797294 -0.420012 0.907484 + outer loop + vertex -31.6677 138.694 410.412 + vertex -47.6223 138.682 410.267 + vertex -39.0309 137.014 409.57 + endloop + endfacet + facet normal -0.00805661 -0.433382 0.901174 + outer loop + vertex -31.8808 147.023 414.354 + vertex -48.0108 143.692 412.608 + vertex -27.8344 143.813 412.846 + endloop + endfacet + facet normal -0.00575329 -0.42115 0.906973 + outer loop + vertex -38.3494 141.245 411.555 + vertex -31.6677 138.694 410.412 + vertex -18.8738 141.326 411.716 + endloop + endfacet + facet normal -0.00480494 -0.424896 0.905229 + outer loop + vertex -18.8738 141.326 411.716 + vertex -31.6677 138.694 410.412 + vertex -15.4914 138.067 410.204 + endloop + endfacet + facet normal -0.00478244 -0.424394 0.905465 + outer loop + vertex -15.4914 138.067 410.204 + vertex -31.6677 138.694 410.412 + vertex -25.4623 135.982 409.174 + endloop + endfacet + facet normal -0.00412881 -0.432906 0.90143 + outer loop + vertex -15.0684 146.958 414.415 + vertex -27.8344 143.813 412.846 + vertex -12.4018 144.119 413.064 + endloop + endfacet + facet normal -0.000887116 -0.432159 0.901797 + outer loop + vertex 0.775451 146.826 414.374 + vertex -12.4018 144.119 413.064 + vertex 1.50638 143.206 412.64 + endloop + endfacet + facet normal -0.00242137 -0.422867 0.906188 + outer loop + vertex -18.8738 141.326 411.716 + vertex -15.4914 138.067 410.204 + vertex -4.8529 140.424 411.332 + endloop + endfacet + facet normal -0.00147928 -0.42634 0.904562 + outer loop + vertex -4.8529 140.424 411.332 + vertex -15.4914 138.067 410.204 + vertex 0.382309 138.283 410.332 + endloop + endfacet + facet normal -0.00151342 -0.424376 0.905485 + outer loop + vertex 0.382309 138.283 410.332 + vertex -15.4914 138.067 410.204 + vertex -7.14643 135.682 409.1 + endloop + endfacet + facet normal 0.00077307 -0.421823 0.906678 + outer loop + vertex -4.8529 140.424 411.332 + vertex 0.382309 138.283 410.332 + vertex 10.5629 140.914 411.547 + endloop + endfacet + facet normal 0.00188309 -0.425354 0.905025 + outer loop + vertex 10.5629 140.914 411.547 + vertex 0.382309 138.283 410.332 + vertex 16.7696 138.24 410.278 + endloop + endfacet + facet normal 0.00189952 -0.421365 0.906889 + outer loop + vertex 16.7696 138.24 410.278 + vertex 0.382309 138.283 410.332 + vertex 6.36578 136.345 409.419 + endloop + endfacet + facet normal 0.00250805 -0.433115 0.901335 + outer loop + vertex 17.4626 146.819 414.332 + vertex 1.50638 143.206 412.64 + vertex 21.5361 143.741 412.842 + endloop + endfacet + facet normal 0.00422861 -0.420894 0.9071 + outer loop + vertex 10.5629 140.914 411.547 + vertex 16.7696 138.24 410.278 + vertex 31.0624 141.618 411.778 + endloop + endfacet + facet normal 0.00519817 -0.424291 0.905511 + outer loop + vertex 31.0624 141.618 411.778 + vertex 16.7696 138.24 410.278 + vertex 34.9749 138.501 410.295 + endloop + endfacet + facet normal 0.00513422 -0.41996 0.907528 + outer loop + vertex 34.9749 138.501 410.295 + vertex 16.7696 138.24 410.278 + vertex 24.2746 136.396 409.382 + endloop + endfacet + facet normal 0.00590025 -0.432669 0.901533 + outer loop + vertex 34.5129 147.162 414.399 + vertex 21.5361 143.741 412.842 + vertex 37.0748 144.507 413.107 + endloop + endfacet + facet normal 0.00935263 -0.432635 0.901521 + outer loop + vertex 50.4632 147.505 414.407 + vertex 37.0748 144.507 413.107 + vertex 49.9878 144.319 412.883 + endloop + endfacet + facet normal 0.00829558 -0.4211 0.906976 + outer loop + vertex 31.0624 141.618 411.778 + vertex 34.9749 138.501 410.295 + vertex 49.8989 141.658 411.624 + endloop + endfacet + facet normal 0.00893713 -0.423634 0.90579 + outer loop + vertex 49.8989 141.658 411.624 + vertex 34.9749 138.501 410.295 + vertex 52.4254 139.044 410.377 + endloop + endfacet + facet normal 0.00879865 -0.419475 0.907724 + outer loop + vertex 52.4254 139.044 410.377 + vertex 34.9749 138.501 410.295 + vertex 42.6314 136.746 409.41 + endloop + endfacet + facet normal 0.0125663 -0.432622 0.901488 + outer loop + vertex 66.6066 147.894 414.367 + vertex 49.9878 144.319 412.883 + vertex 66.7674 144.617 412.793 + endloop + endfacet + facet normal 0.011908 -0.421271 0.906857 + outer loop + vertex 49.8989 141.658 411.624 + vertex 52.4254 139.044 410.377 + vertex 66.5665 141.949 411.541 + endloop + endfacet + facet normal 0.0122914 -0.422843 0.90612 + outer loop + vertex 66.5665 141.949 411.541 + vertex 52.4254 139.044 410.377 + vertex 68.0661 139.23 410.251 + endloop + endfacet + facet normal 0.0122707 -0.420289 0.907307 + outer loop + vertex 68.0661 139.23 410.251 + vertex 52.4254 139.044 410.377 + vertex 58.5061 137.121 409.404 + endloop + endfacet + facet normal 0.0164523 -0.432168 0.901643 + outer loop + vertex 83.7379 148.483 414.336 + vertex 66.7674 144.617 412.793 + vertex 85.0082 144.926 412.608 + endloop + endfacet + facet normal 0.0150311 -0.421589 0.906662 + outer loop + vertex 66.5665 141.949 411.541 + vertex 68.0661 139.23 410.251 + vertex 79.0914 141.963 411.34 + endloop + endfacet + facet normal 0.0163434 -0.426042 0.904556 + outer loop + vertex 79.0914 141.963 411.34 + vertex 68.0661 139.23 410.251 + vertex 83.5838 140.071 410.367 + endloop + endfacet + facet normal 0.0160554 -0.421056 0.906893 + outer loop + vertex 83.5838 140.071 410.367 + vertex 68.0661 139.23 410.251 + vertex 76.1161 137.757 409.425 + endloop + endfacet + facet normal 0.0187411 -0.421434 0.906665 + outer loop + vertex 79.0914 141.963 411.34 + vertex 83.5838 140.071 410.367 + vertex 93.5781 143.05 411.545 + endloop + endfacet + facet normal 0.020292 -0.425814 0.904583 + outer loop + vertex 93.5781 143.05 411.545 + vertex 83.5838 140.071 410.367 + vertex 99.6012 140.599 410.257 + endloop + endfacet + facet normal 0.0202317 -0.423783 0.905538 + outer loop + vertex 99.6012 140.599 410.257 + vertex 83.5838 140.071 410.367 + vertex 89.9938 137.759 409.142 + endloop + endfacet + facet normal 0.0213555 -0.432942 0.901169 + outer loop + vertex 101.457 149.36 414.348 + vertex 85.0082 144.926 412.608 + vertex 105.04 146.324 412.805 + endloop + endfacet + facet normal 0.0227501 -0.42094 0.906803 + outer loop + vertex 93.5781 143.05 411.545 + vertex 99.6012 140.599 410.257 + vertex 110.631 144.067 411.59 + endloop + endfacet + facet normal 0.0246883 -0.426149 0.904316 + outer loop + vertex 110.631 144.067 411.59 + vertex 99.6012 140.599 410.257 + vertex 117.269 141.588 410.24 + endloop + endfacet + facet normal 0.0262645 -0.432848 0.901084 + outer loop + vertex 118.881 150.457 414.387 + vertex 105.04 146.324 412.805 + vertex 122.41 147.46 412.844 + endloop + endfacet + facet normal 0.0269769 -0.421237 0.906549 + outer loop + vertex 110.631 144.067 411.59 + vertex 117.269 141.588 410.24 + vertex 127.746 145.172 411.594 + endloop + endfacet + facet normal 0.0290916 -0.42647 0.904034 + outer loop + vertex 127.746 145.172 411.594 + vertex 117.269 141.588 410.24 + vertex 134.97 142.789 410.237 + endloop + endfacet + facet normal 0.0307195 -0.432283 0.901215 + outer loop + vertex 135.557 151.605 414.384 + vertex 122.41 147.46 412.844 + vertex 139.106 148.629 412.836 + endloop + endfacet + facet normal 0.0312662 -0.421232 0.906414 + outer loop + vertex 127.746 145.172 411.594 + vertex 134.97 142.789 410.237 + vertex 144.529 146.426 411.597 + endloop + endfacet + facet normal 0.033305 -0.425769 0.904219 + outer loop + vertex 144.529 146.426 411.597 + vertex 134.97 142.789 410.237 + vertex 151.407 144.372 410.377 + endloop + endfacet + facet normal 0.0330183 -0.422911 0.905569 + outer loop + vertex 151.407 144.372 410.377 + vertex 134.97 142.789 410.237 + vertex 144.715 141.168 409.125 + endloop + endfacet + facet normal 0.0348992 -0.431905 0.901244 + outer loop + vertex 151.991 152.884 414.376 + vertex 139.106 148.629 412.836 + vertex 155.532 149.921 412.819 + endloop + endfacet + facet normal 0.0352247 -0.420705 0.906514 + outer loop + vertex 144.529 146.426 411.597 + vertex 151.407 144.372 410.377 + vertex 160.832 147.775 411.59 + endloop + endfacet + facet normal 0.0372549 -0.425499 0.904192 + outer loop + vertex 160.832 147.775 411.59 + vertex 151.407 144.372 410.377 + vertex 167.282 145.509 410.258 + endloop + endfacet + facet normal 0.0368785 -0.419974 0.906787 + outer loop + vertex 167.282 145.509 410.258 + vertex 151.407 144.372 410.377 + vertex 158.174 142.866 409.405 + endloop + endfacet + facet normal 0.0390362 -0.431427 0.901303 + outer loop + vertex 168.391 154.324 414.369 + vertex 155.532 149.921 412.819 + vertex 171.898 151.399 412.817 + endloop + endfacet + facet normal 0.0392785 -0.420943 0.906236 + outer loop + vertex 160.832 147.775 411.59 + vertex 167.282 145.509 410.258 + vertex 177.035 149.291 411.592 + endloop + endfacet + facet normal 0.0413405 -0.425479 0.904024 + outer loop + vertex 177.035 149.291 411.592 + vertex 167.282 145.509 410.258 + vertex 183.389 147.326 410.377 + endloop + endfacet + facet normal 0.0430034 -0.430873 0.901387 + outer loop + vertex 184.783 155.919 414.363 + vertex 171.898 151.399 412.817 + vertex 188.258 153.039 412.821 + endloop + endfacet + facet normal 0.0431609 -0.420873 0.906092 + outer loop + vertex 177.035 149.291 411.592 + vertex 183.389 147.326 410.377 + vertex 193.345 150.992 411.605 + endloop + endfacet + facet normal 0.0450189 -0.425209 0.903975 + outer loop + vertex 193.345 150.992 411.605 + vertex 183.389 147.326 410.377 + vertex 199.637 148.858 410.288 + endloop + endfacet + facet normal 0.0445304 -0.41988 0.906487 + outer loop + vertex 199.637 148.858 410.288 + vertex 183.389 147.326 410.377 + vertex 190.952 146.051 409.414 + endloop + endfacet + facet normal 0.0470111 -0.430225 0.901497 + outer loop + vertex 201.291 157.706 414.369 + vertex 188.258 153.039 412.821 + vertex 204.744 154.839 412.82 + endloop + endfacet + facet normal 0.0471141 -0.420364 0.906132 + outer loop + vertex 193.345 150.992 411.605 + vertex 199.637 148.858 410.288 + vertex 210.023 152.843 411.597 + endloop + endfacet + facet normal 0.0491225 -0.424871 0.90392 + outer loop + vertex 210.023 152.843 411.597 + vertex 199.637 148.858 410.288 + vertex 217.078 150.861 410.282 + endloop + endfacet + facet normal 0.048422 -0.418763 0.906804 + outer loop + vertex 217.078 150.861 410.282 + vertex 199.637 148.858 410.288 + vertex 208.653 148.016 409.418 + endloop + endfacet + facet normal 0.0510098 -0.429586 0.901584 + outer loop + vertex 217.832 159.614 414.355 + vertex 204.744 154.839 412.82 + vertex 221.459 156.813 412.815 + endloop + endfacet + facet normal 0.0510281 -0.41964 0.906255 + outer loop + vertex 210.023 152.843 411.597 + vertex 217.078 150.861 410.282 + vertex 227.104 154.905 411.59 + endloop + endfacet + facet normal 0.0530074 -0.423871 0.90417 + outer loop + vertex 227.104 154.905 411.59 + vertex 217.078 150.861 410.282 + vertex 234.624 153.07 410.289 + endloop + endfacet + facet normal 0.0522723 -0.418041 0.906923 + outer loop + vertex 234.624 153.07 410.289 + vertex 217.078 150.861 410.282 + vertex 226.624 150.162 409.41 + endloop + endfacet + facet normal 0.0547714 -0.429777 0.901272 + outer loop + vertex 234.452 161.68 414.346 + vertex 221.459 156.813 412.815 + vertex 238.259 158.946 412.811 + endloop + endfacet + facet normal 0.0546949 -0.41862 0.906513 + outer loop + vertex 227.104 154.905 411.59 + vertex 234.624 153.07 410.289 + vertex 244.45 157.242 411.623 + endloop + endfacet + facet normal 0.0569446 -0.423194 0.904248 + outer loop + vertex 244.45 157.242 411.623 + vertex 234.624 153.07 410.289 + vertex 251.383 155.556 410.397 + endloop + endfacet + facet normal 0.0561932 -0.418232 0.9066 + outer loop + vertex 251.383 155.556 410.397 + vertex 234.624 153.07 410.289 + vertex 244.447 152.508 409.421 + endloop + endfacet + facet normal 0.0584042 -0.430571 0.900665 + outer loop + vertex 251.055 163.906 414.353 + vertex 238.259 158.946 412.811 + vertex 255.128 161.352 412.868 + endloop + endfacet + facet normal 0.058381 -0.418729 0.906232 + outer loop + vertex 244.45 157.242 411.623 + vertex 251.383 155.556 410.397 + vertex 263.849 160.211 411.745 + endloop + endfacet + facet normal 0.0599718 -0.422458 0.904396 + outer loop + vertex 263.849 160.211 411.745 + vertex 251.383 155.556 410.397 + vertex 267.589 157.458 410.211 + endloop + endfacet + facet normal 0.0598107 -0.421019 0.905078 + outer loop + vertex 267.589 157.458 410.211 + vertex 251.383 155.556 410.397 + vertex 258.416 153.787 409.109 + endloop + endfacet + facet normal 0.0616325 -0.431035 0.900228 + outer loop + vertex 267.332 166.299 414.401 + vertex 255.128 161.352 412.868 + vertex 270.05 163.929 413.08 + endloop + endfacet + facet normal 0.0649888 -0.431087 0.899967 + outer loop + vertex 283.292 168.703 414.41 + vertex 270.05 163.929 413.08 + vertex 284.274 165.372 412.744 + endloop + endfacet + facet normal 0.0620965 -0.420103 0.905349 + outer loop + vertex 263.849 160.211 411.745 + vertex 267.589 157.458 410.211 + vertex 278.672 161.613 411.379 + endloop + endfacet + facet normal 0.0679715 -0.424346 0.902945 + outer loop + vertex 302.143 169.019 413.113 + vertex 284.274 165.372 412.744 + vertex 296.763 165.248 411.746 + endloop + endfacet + facet normal 0.0765959 -0.434622 0.89735 + outer loop + vertex 316.038 170.812 412.795 + vertex 302.143 169.019 413.113 + vertex 296.763 165.248 411.746 + endloop + endfacet + facet normal 0.0633334 -0.422999 0.903914 + outer loop + vertex 278.672 161.613 411.379 + vertex 267.589 157.458 410.211 + vertex 284.345 159.974 410.214 + endloop + endfacet + facet normal 0.0629892 -0.420707 0.905007 + outer loop + vertex 284.345 159.974 410.214 + vertex 267.589 157.458 410.211 + vertex 275.806 156.254 409.079 + endloop + endfacet + facet normal 0.0730125 -0.423284 0.90305 + outer loop + vertex 296.763 165.248 411.746 + vertex 315.914 167.989 411.482 + vertex 316.038 170.812 412.795 + endloop + endfacet + facet normal 0.0755561 -0.425803 0.901656 + outer loop + vertex 316.722 174.236 414.355 + vertex 302.143 169.019 413.113 + vertex 316.038 170.812 412.795 + endloop + endfacet + facet normal 0.0784567 -0.443632 0.892768 + outer loop + vertex 316.112 178.211 416.384 + vertex 299.83 171.378 414.419 + vertex 316.722 174.236 414.355 + endloop + endfacet + facet normal 0.0950777 -0.489825 0.866621 + outer loop + vertex 315.944 182.946 419.078 + vertex 316.112 178.211 416.384 + vertex 331.454 185.782 418.98 + endloop + endfacet + facet normal 0.132624 -0.441892 0.88721 + outer loop + vertex 345.862 186.815 417.397 + vertex 347.993 185.136 416.242 + vertex 356.422 188.997 416.906 + endloop + endfacet + facet normal 0.101218 -0.409624 0.906622 + outer loop + vertex 347.993 185.136 416.242 + vertex 334.058 181.164 416.003 + vertex 346.104 182.381 415.208 + endloop + endfacet + facet normal 0.0951336 -0.411485 0.906438 + outer loop + vertex 347.662 180.667 414.267 + vertex 346.104 182.381 415.208 + vertex 334.096 176.971 414.013 + endloop + endfacet + facet normal 0.0937777 -0.406668 0.90875 + outer loop + vertex 347.662 180.667 414.267 + vertex 334.096 176.971 414.013 + vertex 345.919 178.108 413.301 + endloop + endfacet + facet normal 0.0940941 -0.417599 0.903746 + outer loop + vertex 347.729 176.59 412.412 + vertex 345.919 178.108 413.301 + vertex 333.864 173.377 412.37 + endloop + endfacet + facet normal 0.0931512 -0.413555 0.905701 + outer loop + vertex 347.729 176.59 412.412 + vertex 333.864 173.377 412.37 + vertex 345.958 174.517 411.647 + endloop + endfacet + facet normal 0.0948333 -0.421949 0.901646 + outer loop + vertex 347.6 173.578 411.035 + vertex 345.958 174.517 411.647 + vertex 334.091 170.767 411.141 + endloop + endfacet + facet normal 0.0893313 -0.395028 0.914316 + outer loop + vertex 347.6 173.578 411.035 + vertex 334.091 170.767 411.141 + vertex 345.874 172.431 410.708 + endloop + endfacet + facet normal 0.0897426 -0.397357 0.913265 + outer loop + vertex 348.112 172.284 410.424 + vertex 345.874 172.431 410.708 + vertex 335.317 169.217 410.347 + endloop + endfacet + facet normal 0.166725 -0.31837 0.93319 + outer loop + vertex 373.116 179.124 409.862 + vertex 373.93 179.22 409.749 + vertex 378.372 180.995 409.561 + endloop + endfacet + facet normal 0.12522 -0.383964 0.914818 + outer loop + vertex 366.724 177.605 410.272 + vertex 356.631 174.717 410.442 + vertex 366.74 177.181 410.092 + endloop + endfacet + facet normal 0.186438 -0.380211 0.905914 + outer loop + vertex 373.201 180.183 410.338 + vertex 374.085 179.824 410.005 + vertex 378.365 181.98 410.029 + endloop + endfacet + facet normal 0.131447 -0.410078 0.902529 + outer loop + vertex 366.855 178.818 410.804 + vertex 356.588 175.282 410.693 + vertex 366.724 177.605 410.272 + endloop + endfacet + facet normal 0.185305 -0.371693 0.909674 + outer loop + vertex 373.157 181.954 411.142 + vertex 374.093 181.345 410.703 + vertex 378.211 183.768 410.854 + endloop + endfacet + facet normal 0.131184 -0.406211 0.904314 + outer loop + vertex 366.86 180.571 411.591 + vertex 356.768 176.504 411.228 + vertex 366.855 178.818 410.804 + endloop + endfacet + facet normal 0.183083 -0.357041 0.91597 + outer loop + vertex 372.999 183.93 412.022 + vertex 373.966 183.292 411.58 + vertex 378.042 185.723 411.713 + endloop + endfacet + facet normal 0.13099 -0.400422 0.90692 + outer loop + vertex 366.706 182.541 412.483 + vertex 356.804 178.223 412.007 + vertex 366.86 180.571 411.591 + endloop + endfacet + facet normal 0.183737 -0.340639 0.922066 + outer loop + vertex 372.781 185.929 412.893 + vertex 373.775 185.277 412.454 + vertex 377.874 187.664 412.519 + endloop + endfacet + facet normal 0.12933 -0.387514 0.912747 + outer loop + vertex 366.444 184.611 413.399 + vertex 356.664 180.201 412.912 + vertex 366.706 182.541 412.483 + endloop + endfacet + facet normal 0.185778 -0.325802 0.927006 + outer loop + vertex 372.49 187.97 413.757 + vertex 373.526 187.286 413.31 + vertex 377.655 189.662 413.317 + endloop + endfacet + facet normal 0.130282 -0.378414 0.916422 + outer loop + vertex 366.18 186.727 414.31 + vertex 356.482 182.32 413.869 + vertex 366.444 184.611 413.399 + endloop + endfacet + facet normal 0.187149 -0.305285 0.93369 + outer loop + vertex 372.135 190.068 414.605 + vertex 373.181 189.347 414.16 + vertex 377.28 191.73 414.117 + endloop + endfacet + facet normal 0.133057 -0.372034 0.918633 + outer loop + vertex 366.052 188.908 415.212 + vertex 356.461 184.516 414.822 + vertex 366.18 186.727 414.31 + endloop + endfacet + facet normal 0.144279 -0.392335 0.908437 + outer loop + vertex 365.874 191.157 416.211 + vertex 356.614 186.772 415.789 + vertex 366.052 188.908 415.212 + endloop + endfacet + facet normal 0.208431 -0.432756 0.877085 + outer loop + vertex 372.797 193.783 415.862 + vertex 371.772 194.6 416.509 + vertex 365.874 191.157 416.211 + endloop + endfacet + facet normal 0.205906 -0.31049 0.928008 + outer loop + vertex 376.845 195.085 415.308 + vertex 371.95 192.277 415.455 + vertex 376.893 193.903 414.902 + endloop + endfacet + facet normal 0.205055 -0.307499 0.929192 + outer loop + vertex 371.95 192.277 415.455 + vertex 372.841 191.477 414.993 + vertex 376.893 193.903 414.902 + endloop + endfacet + facet normal 0.199024 -0.297251 0.933826 + outer loop + vertex 376.893 193.903 414.902 + vertex 372.841 191.477 414.993 + vertex 377.058 192.79 414.513 + endloop + endfacet + facet normal 0.188044 -0.308408 0.932483 + outer loop + vertex 377.058 192.79 414.513 + vertex 372.135 190.068 414.605 + vertex 377.28 191.73 414.117 + endloop + endfacet + facet normal 0.193902 -0.316992 0.928395 + outer loop + vertex 377.28 191.73 414.117 + vertex 373.181 189.347 414.16 + vertex 377.488 190.688 413.718 + endloop + endfacet + facet normal 0.187294 -0.330987 0.924861 + outer loop + vertex 377.488 190.688 413.718 + vertex 372.49 187.97 413.757 + vertex 377.655 189.662 413.317 + endloop + endfacet + facet normal 0.195077 -0.341939 0.919251 + outer loop + vertex 377.655 189.662 413.317 + vertex 373.526 187.286 413.31 + vertex 377.777 188.652 412.916 + endloop + endfacet + facet normal 0.186752 -0.350412 0.917788 + outer loop + vertex 377.777 188.652 412.916 + vertex 372.781 185.929 412.893 + vertex 377.874 187.664 412.519 + endloop + endfacet + facet normal 0.195059 -0.359819 0.912405 + outer loop + vertex 377.874 187.664 412.519 + vertex 373.775 185.277 412.454 + vertex 377.956 186.692 412.118 + endloop + endfacet + facet normal 0.185484 -0.364377 0.912593 + outer loop + vertex 377.956 186.692 412.118 + vertex 372.999 183.93 412.022 + vertex 378.042 185.723 411.713 + endloop + endfacet + facet normal 0.19649 -0.378889 0.904342 + outer loop + vertex 378.042 185.723 411.713 + vertex 373.966 183.292 411.58 + vertex 378.119 184.751 411.289 + endloop + endfacet + facet normal 0.189024 -0.382922 0.904235 + outer loop + vertex 378.119 184.751 411.289 + vertex 373.157 181.954 411.142 + vertex 378.211 183.768 410.854 + endloop + endfacet + facet normal 0.199411 -0.394873 0.896834 + outer loop + vertex 378.211 183.768 410.854 + vertex 374.093 181.345 410.703 + vertex 378.29 182.824 410.42 + endloop + endfacet + facet normal 0.19237 -0.398856 0.896609 + outer loop + vertex 378.29 182.824 410.42 + vertex 373.201 180.183 410.338 + vertex 378.365 181.98 410.029 + endloop + endfacet + facet normal 0.202529 -0.411963 0.888408 + outer loop + vertex 378.365 181.98 410.029 + vertex 374.085 179.824 410.005 + vertex 378.395 181.357 409.733 + endloop + endfacet + facet normal 0.203837 -0.431348 0.878857 + outer loop + vertex 378.395 181.357 409.733 + vertex 373.116 179.124 409.862 + vertex 378.372 180.995 409.561 + endloop + endfacet + facet normal 0.224813 -0.472307 0.852282 + outer loop + vertex 378.372 180.995 409.561 + vertex 373.93 179.22 409.749 + vertex 378.27 180.857 409.512 + endloop + endfacet + facet normal -0.185729 0.375372 -0.908075 + outer loop + vertex 378.27 180.857 409.512 + vertex 372.915 178.961 409.823 + vertex 378.07 180.847 409.548 + endloop + endfacet + facet normal -0.203369 0.280657 -0.938015 + outer loop + vertex 382.516 182.877 409.201 + vertex 377.907 180.874 409.601 + vertex 382.337 182.831 409.226 + endloop + endfacet + facet normal -0.387399 0.907861 0.160342 + outer loop + vertex 377.907 180.874 409.601 + vertex 378.043 180.931 409.61 + vertex 382.337 182.831 409.226 + endloop + endfacet + facet normal -0.291187 0.492408 -0.82021 + outer loop + vertex 382.337 182.831 409.226 + vertex 378.043 180.931 409.61 + vertex 382.391 182.866 409.228 + endloop + endfacet + facet normal -0.108499 0.421725 0.900209 + outer loop + vertex 378.043 180.931 409.61 + vertex 378.962 181.269 409.563 + vertex 382.391 182.866 409.228 + endloop + endfacet + facet normal -0.355155 0.614912 -0.704093 + outer loop + vertex 382.391 182.866 409.228 + vertex 378.962 181.269 409.563 + vertex 382.774 183.093 409.233 + endloop + endfacet + facet normal -0.317185 0.76432 0.561434 + outer loop + vertex 378.962 181.269 409.563 + vertex 380.132 181.795 409.508 + vertex 382.774 183.093 409.233 + endloop + endfacet + facet normal -0.324233 0.488408 -0.810142 + outer loop + vertex 382.774 183.093 409.233 + vertex 380.132 181.795 409.508 + vertex 383.188 183.438 409.275 + endloop + endfacet + facet normal 0.215922 -0.386614 0.896609 + outer loop + vertex 378.962 181.269 409.563 + vertex 377.225 180.248 409.541 + vertex 380.132 181.795 409.508 + endloop + endfacet + facet normal 0.1505 -0.276385 0.94919 + outer loop + vertex 374.665 179.362 409.689 + vertex 377.225 180.248 409.541 + vertex 378.962 181.269 409.563 + endloop + endfacet + facet normal 0.204785 -0.446407 0.871082 + outer loop + vertex 377.225 180.248 409.541 + vertex 374.665 179.362 409.689 + vertex 374.142 177.503 408.859 + endloop + endfacet + facet normal 0.150066 -0.275384 0.949549 + outer loop + vertex 378.043 180.931 409.61 + vertex 374.665 179.362 409.689 + vertex 378.962 181.269 409.563 + endloop + endfacet + facet normal 0.163152 -0.304119 0.938559 + outer loop + vertex 373.062 179.09 409.879 + vertex 374.665 179.362 409.689 + vertex 378.043 180.931 409.61 + endloop + endfacet + facet normal -0.298814 0.726659 -0.618609 + outer loop + vertex 372.915 178.961 409.823 + vertex 373.675 179.293 409.846 + vertex 378.07 180.847 409.548 + endloop + endfacet + facet normal -0.342069 0.875214 -0.342037 + outer loop + vertex 377.907 180.874 409.601 + vertex 373.062 179.09 409.879 + vertex 378.043 180.931 409.61 + endloop + endfacet + facet normal -0.179867 0.470998 -0.863602 + outer loop + vertex 373.675 179.293 409.846 + vertex 372.915 178.961 409.823 + vertex 367.27 177.283 410.084 + endloop + endfacet + facet normal 0.181015 -0.455749 0.871508 + outer loop + vertex 374.665 179.362 409.689 + vertex 373.062 179.09 409.879 + vertex 368.705 177.217 409.805 + endloop + endfacet + facet normal 0.122747 -0.363047 0.923651 + outer loop + vertex 358.086 174.815 410.334 + vertex 360.682 174.892 410.019 + vertex 367.27 177.283 410.084 + endloop + endfacet + facet normal 0.159863 -0.421854 0.892459 + outer loop + vertex 370.723 173.656 407.71 + vertex 363.942 171.493 407.902 + vertex 370.365 169.934 406.014 + endloop + endfacet + facet normal 0.140689 -0.422013 0.895607 + outer loop + vertex 363.942 171.493 407.902 + vertex 358.075 169.268 407.775 + vertex 364.353 167.874 406.132 + endloop + endfacet + facet normal 0.115567 -0.425007 0.897783 + outer loop + vertex 358.075 169.268 407.775 + vertex 349.904 167.893 408.176 + vertex 357.217 165.846 406.266 + endloop + endfacet + facet normal 0.0977826 -0.424707 0.900035 + outer loop + vertex 349.904 167.893 408.176 + vertex 337.958 165.391 408.293 + vertex 348.306 163.62 406.333 + endloop + endfacet + facet normal 0.0857405 -0.429271 0.899097 + outer loop + vertex 339.337 161.094 406.11 + vertex 337.958 165.391 408.293 + vertex 325.295 160.509 407.17 + endloop + endfacet + facet normal 0.0776136 -0.413655 0.907119 + outer loop + vertex 320.073 163.588 409.125 + vertex 327.643 165.536 409.366 + vertex 318.239 165.585 410.192 + endloop + endfacet + facet normal 0.0726022 -0.417528 0.905759 + outer loop + vertex 314.126 161.937 408.841 + vertex 320.073 163.588 409.125 + vertex 318.239 165.585 410.192 + endloop + endfacet + facet normal 0.0768591 -0.428618 0.900211 + outer loop + vertex 325.295 160.509 407.17 + vertex 306.239 157.319 407.278 + vertex 325.412 151.86 403.042 + endloop + endfacet + facet normal 0.0701397 -0.418862 0.905337 + outer loop + vertex 300.671 160.507 409.257 + vertex 306.802 161.852 409.404 + vertex 301.166 163.012 410.378 + endloop + endfacet + facet normal 0.0665274 -0.418372 0.905836 + outer loop + vertex 293.194 159.052 409.134 + vertex 300.671 160.507 409.257 + vertex 301.166 163.012 410.378 + endloop + endfacet + facet normal 0.0700664 -0.428466 0.900837 + outer loop + vertex 306.239 157.319 407.278 + vertex 287.26 154.089 407.218 + vertex 305.61 147.9 402.847 + endloop + endfacet + facet normal 0.0668404 -0.418946 0.905548 + outer loop + vertex 285.918 157.937 409.155 + vertex 293.194 159.052 409.134 + vertex 284.345 159.974 410.214 + endloop + endfacet + facet normal 0.0641875 -0.420677 0.904937 + outer loop + vertex 282.513 157.385 409.14 + vertex 285.918 157.937 409.155 + vertex 284.345 159.974 410.214 + endloop + endfacet + facet normal 0.0624891 -0.419711 0.905504 + outer loop + vertex 275.806 156.254 409.079 + vertex 282.513 157.385 409.14 + vertex 284.345 159.974 410.214 + endloop + endfacet + facet normal 0.0649163 -0.427234 0.901808 + outer loop + vertex 287.26 154.089 407.218 + vertex 269.235 151.269 407.18 + vertex 286.336 144.326 402.659 + endloop + endfacet + facet normal 0.0630455 -0.420437 0.905129 + outer loop + vertex 268.734 155.319 409.137 + vertex 275.806 156.254 409.079 + vertex 267.589 157.458 410.211 + endloop + endfacet + facet normal 0.0614187 -0.421189 0.904891 + outer loop + vertex 265.233 154.842 409.153 + vertex 268.734 155.319 409.137 + vertex 267.589 157.458 410.211 + endloop + endfacet + facet normal 0.0591074 -0.419488 0.905834 + outer loop + vertex 258.416 153.787 409.109 + vertex 265.233 154.842 409.153 + vertex 267.589 157.458 410.211 + endloop + endfacet + facet normal 0.060635 -0.426767 0.902327 + outer loop + vertex 269.235 151.269 407.18 + vertex 250.502 148.626 407.188 + vertex 267.504 141.278 402.57 + endloop + endfacet + facet normal 0.0597875 -0.421088 0.905047 + outer loop + vertex 250.522 152.99 409.26 + vertex 258.416 153.787 409.109 + vertex 251.383 155.556 410.397 + endloop + endfacet + facet normal 0.0573285 -0.420463 0.905497 + outer loop + vertex 244.447 152.508 409.421 + vertex 250.522 152.99 409.26 + vertex 251.383 155.556 410.397 + endloop + endfacet + facet normal 0.055758 -0.422691 0.904557 + outer loop + vertex 238.147 150.533 408.886 + vertex 244.447 152.508 409.421 + vertex 234.624 153.07 410.289 + endloop + endfacet + facet normal 0.0567066 -0.427341 0.90231 + outer loop + vertex 250.502 148.626 407.188 + vertex 231.902 146.158 407.188 + vertex 248.807 138.673 402.581 + endloop + endfacet + facet normal 0.0561166 -0.422286 0.904724 + outer loop + vertex 232.245 150.401 409.191 + vertex 238.147 150.533 408.886 + vertex 234.624 153.07 410.289 + endloop + endfacet + facet normal 0.0531391 -0.42012 0.905911 + outer loop + vertex 226.624 150.162 409.41 + vertex 232.245 150.401 409.191 + vertex 234.624 153.07 410.289 + endloop + endfacet + facet normal 0.0516347 -0.423584 0.904384 + outer loop + vertex 220.047 148.284 408.905 + vertex 226.624 150.162 409.41 + vertex 217.078 150.861 410.282 + endloop + endfacet + facet normal 0.0525232 -0.428423 0.90205 + outer loop + vertex 231.902 146.158 407.188 + vertex 213.54 143.923 407.196 + vertex 230.169 136.341 402.626 + endloop + endfacet + facet normal 0.052061 -0.423181 0.904548 + outer loop + vertex 214.179 148.219 409.213 + vertex 220.047 148.284 408.905 + vertex 217.078 150.861 410.282 + endloop + endfacet + facet normal 0.0490936 -0.420497 0.905965 + outer loop + vertex 208.653 148.016 409.418 + vertex 214.179 148.219 409.213 + vertex 217.078 150.861 410.282 + endloop + endfacet + facet normal 0.0476348 -0.424486 0.904181 + outer loop + vertex 201.952 146.143 408.892 + vertex 208.653 148.016 409.418 + vertex 199.637 148.858 410.288 + endloop + endfacet + facet normal 0.0484218 -0.4289 0.902053 + outer loop + vertex 213.54 143.923 407.196 + vertex 195.08 141.815 407.185 + vertex 211.453 134.116 402.645 + endloop + endfacet + facet normal 0.0480301 -0.424205 0.904291 + outer loop + vertex 196.208 146.13 409.191 + vertex 201.952 146.143 408.892 + vertex 199.637 148.858 410.288 + endloop + endfacet + facet normal 0.0449444 -0.420993 0.90595 + outer loop + vertex 190.952 146.051 409.414 + vertex 196.208 146.13 409.191 + vertex 199.637 148.858 410.288 + endloop + endfacet + facet normal 0.0433605 -0.425042 0.904135 + outer loop + vertex 183.525 144.257 408.928 + vertex 190.952 146.051 409.414 + vertex 183.389 147.326 410.377 + endloop + endfacet + facet normal 0.0439974 -0.429059 0.902204 + outer loop + vertex 195.08 141.815 407.185 + vertex 175.994 139.795 407.155 + vertex 192.563 131.975 402.628 + endloop + endfacet + facet normal 0.042912 -0.425066 0.904144 + outer loop + vertex 175.514 144.441 409.394 + vertex 183.525 144.257 408.928 + vertex 183.389 147.326 410.377 + endloop + endfacet + facet normal 0.0406862 -0.419854 0.906679 + outer loop + vertex 183.389 147.326 410.377 + vertex 167.282 145.509 410.258 + vertex 175.514 144.441 409.394 + endloop + endfacet + facet normal 0.0403205 -0.421914 0.905739 + outer loop + vertex 170.38 143.414 409.144 + vertex 175.514 144.441 409.394 + vertex 167.282 145.509 410.258 + endloop + endfacet + facet normal 0.0379853 -0.424724 0.904526 + outer loop + vertex 165.228 142.313 408.844 + vertex 170.38 143.414 409.144 + vertex 167.282 145.509 410.258 + endloop + endfacet + facet normal 0.0393911 -0.429251 0.902326 + outer loop + vertex 175.994 139.795 407.155 + vertex 157.228 138.158 407.195 + vertex 173.616 130.037 402.617 + endloop + endfacet + facet normal 0.0385724 -0.425027 0.904358 + outer loop + vertex 158.174 142.866 409.405 + vertex 165.228 142.313 408.844 + vertex 167.282 145.509 410.258 + endloop + endfacet + facet normal 0.036025 -0.422941 0.905441 + outer loop + vertex 152.359 142.043 409.251 + vertex 158.174 142.866 409.405 + vertex 151.407 144.372 410.377 + endloop + endfacet + facet normal 0.0335311 -0.42381 0.90513 + outer loop + vertex 144.715 141.168 409.125 + vertex 152.359 142.043 409.251 + vertex 151.407 144.372 410.377 + endloop + endfacet + facet normal 0.0347274 -0.429301 0.902494 + outer loop + vertex 157.228 138.158 407.195 + vertex 138.011 136.638 407.211 + vertex 154.599 128.327 402.62 + endloop + endfacet + facet normal 0.033604 -0.420231 0.906795 + outer loop + vertex 137.338 140.68 409.172 + vertex 144.715 141.168 409.125 + vertex 134.97 142.789 410.237 + endloop + endfacet + facet normal 0.0312391 -0.422416 0.905864 + outer loop + vertex 133.669 140.428 409.181 + vertex 137.338 140.68 409.172 + vertex 134.97 142.789 410.237 + endloop + endfacet + facet normal 0.0284152 -0.421162 0.90654 + outer loop + vertex 126.497 139.795 409.112 + vertex 133.669 140.428 409.181 + vertex 134.97 142.789 410.237 + endloop + endfacet + facet normal 0.0287935 -0.42207 0.906106 + outer loop + vertex 134.97 142.789 410.237 + vertex 117.269 141.588 410.24 + vertex 126.497 139.795 409.112 + endloop + endfacet + facet normal 0.0299296 -0.429646 0.902501 + outer loop + vertex 138.011 136.638 407.211 + vertex 119.282 135.363 407.226 + vertex 135.562 126.843 402.63 + endloop + endfacet + facet normal 0.0292133 -0.420391 0.906872 + outer loop + vertex 118.982 139.47 409.203 + vertex 126.497 139.795 409.112 + vertex 117.269 141.588 410.24 + endloop + endfacet + facet normal 0.026285 -0.422357 0.906048 + outer loop + vertex 115.327 139.224 409.195 + vertex 118.982 139.47 409.203 + vertex 117.269 141.588 410.24 + endloop + endfacet + facet normal 0.0239327 -0.420778 0.906848 + outer loop + vertex 108.149 138.67 409.127 + vertex 115.327 139.224 409.195 + vertex 117.269 141.588 410.24 + endloop + endfacet + facet normal 0.0244688 -0.422197 0.906174 + outer loop + vertex 117.269 141.588 410.24 + vertex 99.6012 140.599 410.257 + vertex 108.149 138.67 409.127 + endloop + endfacet + facet normal 0.0251243 -0.429833 0.902559 + outer loop + vertex 119.282 135.363 407.226 + vertex 100.509 134.263 407.224 + vertex 116.52 125.554 402.631 + endloop + endfacet + facet normal 0.024506 -0.422067 0.906233 + outer loop + vertex 100.677 138.367 409.188 + vertex 108.149 138.67 409.127 + vertex 99.6012 140.599 410.257 + endloop + endfacet + facet normal 0.021787 -0.423165 0.90579 + outer loop + vertex 97.0499 138.174 409.185 + vertex 100.677 138.367 409.188 + vertex 99.6012 140.599 410.257 + endloop + endfacet + facet normal 0.0192451 -0.420968 0.906871 + outer loop + vertex 89.9938 137.759 409.142 + vertex 97.0499 138.174 409.185 + vertex 99.6012 140.599 410.257 + endloop + endfacet + facet normal 0.0201085 -0.429972 0.902618 + outer loop + vertex 100.509 134.263 407.224 + vertex 81.1147 133.323 407.209 + vertex 97.3294 124.454 402.623 + endloop + endfacet + facet normal 0.0196984 -0.424972 0.904992 + outer loop + vertex 81.9991 137.672 409.276 + vertex 89.9938 137.759 409.142 + vertex 83.5838 140.071 410.367 + endloop + endfacet + facet normal 0.0169589 -0.423501 0.905737 + outer loop + vertex 76.1161 137.757 409.425 + vertex 81.9991 137.672 409.276 + vertex 83.5838 140.071 410.367 + endloop + endfacet + facet normal 0.0149477 -0.425863 0.904664 + outer loop + vertex 69.3186 136.343 408.872 + vertex 76.1161 137.757 409.425 + vertex 68.0661 139.23 410.251 + endloop + endfacet + facet normal 0.0155858 -0.429917 0.902734 + outer loop + vertex 81.1147 133.323 407.209 + vertex 61.8628 132.543 407.17 + vertex 77.9975 123.564 402.615 + endloop + endfacet + facet normal 0.0153061 -0.425734 0.904719 + outer loop + vertex 63.5808 136.755 409.163 + vertex 69.3186 136.343 408.872 + vertex 68.0661 139.23 410.251 + endloop + endfacet + facet normal 0.0126583 -0.421768 0.906615 + outer loop + vertex 58.5061 137.121 409.404 + vertex 63.5808 136.755 409.163 + vertex 68.0661 139.23 410.251 + endloop + endfacet + facet normal 0.0105083 -0.424807 0.905223 + outer loop + vertex 50.6366 135.923 408.933 + vertex 58.5061 137.121 409.404 + vertex 52.4254 139.044 410.377 + endloop + endfacet + facet normal 0.0109901 -0.430045 0.902741 + outer loop + vertex 61.8628 132.543 407.17 + vertex 42.2262 132.047 407.172 + vertex 58.6545 122.893 402.612 + endloop + endfacet + facet normal 0.0102642 -0.424693 0.905279 + outer loop + vertex 42.6314 136.746 409.41 + vertex 50.6366 135.923 408.933 + vertex 52.4254 139.044 410.377 + endloop + endfacet + facet normal 0.00811869 -0.421882 0.906614 + outer loop + vertex 36.9536 136.129 409.173 + vertex 42.6314 136.746 409.41 + vertex 34.9749 138.501 410.295 + endloop + endfacet + facet normal 0.00542567 -0.42373 0.905772 + outer loop + vertex 31.5222 135.398 408.864 + vertex 36.9536 136.129 409.173 + vertex 34.9749 138.501 410.295 + endloop + endfacet + facet normal 0.00670743 -0.43013 0.902742 + outer loop + vertex 42.2262 132.047 407.172 + vertex 23.4656 131.737 407.164 + vertex 39.4732 122.43 402.611 + endloop + endfacet + facet normal 0.00619164 -0.424429 0.90544 + outer loop + vertex 24.2746 136.396 409.382 + vertex 31.5222 135.398 408.864 + vertex 34.9749 138.501 410.295 + endloop + endfacet + facet normal 0.00435568 -0.422547 0.906331 + outer loop + vertex 18.5829 135.883 409.17 + vertex 24.2746 136.396 409.382 + vertex 16.7696 138.24 410.278 + endloop + endfacet + facet normal 0.00185447 -0.424128 0.9056 + outer loop + vertex 13.1755 135.237 408.878 + vertex 18.5829 135.883 409.17 + vertex 16.7696 138.24 410.278 + endloop + endfacet + facet normal 0.00273034 -0.430034 0.902809 + outer loop + vertex 23.4656 131.737 407.164 + vertex 4.68664 131.7 407.203 + vertex 20.4783 122.169 402.615 + endloop + endfacet + facet normal 0.00269088 -0.424948 0.905214 + outer loop + vertex 6.36578 136.345 409.419 + vertex 13.1755 135.237 408.878 + vertex 16.7696 138.24 410.278 + endloop + endfacet + facet normal 0.000575953 -0.424715 0.905327 + outer loop + vertex 0.436751 135.936 409.231 + vertex 6.36578 136.345 409.419 + vertex 0.382309 138.283 410.332 + endloop + endfacet + facet normal -0.00135501 -0.424751 0.905309 + outer loop + vertex -7.14643 135.682 409.1 + vertex 0.436751 135.936 409.231 + vertex 0.382309 138.283 410.332 + endloop + endfacet + facet normal -0.00109643 -0.42995 0.902852 + outer loop + vertex 4.68664 131.7 407.203 + vertex -14.7786 131.795 407.225 + vertex 1.35935 122.095 402.625 + endloop + endfacet + facet normal -0.00119213 -0.423452 0.905918 + outer loop + vertex -14.4436 135.775 409.134 + vertex -7.14643 135.682 409.1 + vertex -15.4914 138.067 410.204 + endloop + endfacet + facet normal -0.00326403 -0.424228 0.90555 + outer loop + vertex -18.1079 135.839 409.151 + vertex -14.4436 135.775 409.134 + vertex -15.4914 138.067 410.204 + endloop + endfacet + facet normal -0.00534023 -0.422226 0.906475 + outer loop + vertex -25.4623 135.982 409.174 + vertex -18.1079 135.839 409.151 + vertex -15.4914 138.067 410.204 + endloop + endfacet + facet normal -0.00526235 -0.429879 0.902871 + outer loop + vertex -14.7786 131.795 407.225 + vertex -35.933 132.64 407.504 + vertex -18.2975 122.268 402.668 + endloop + endfacet + facet normal -0.00514961 -0.425085 0.905139 + outer loop + vertex -33.5449 136.477 409.361 + vertex -25.4623 135.982 409.174 + vertex -31.6677 138.694 410.412 + endloop + endfacet + facet normal -0.00688654 -0.423878 0.905693 + outer loop + vertex -39.0309 137.014 409.57 + vertex -33.5449 136.477 409.361 + vertex -31.6677 138.694 410.412 + endloop + endfacet + facet normal -0.00882454 -0.423683 0.905767 + outer loop + vertex -43.5012 136.504 409.288 + vertex -39.0309 137.014 409.57 + vertex -47.6223 138.682 410.267 + endloop + endfacet + facet normal -0.0105764 -0.426414 0.904466 + outer loop + vertex -48.7544 135.912 408.947 + vertex -43.5012 136.504 409.288 + vertex -47.6223 138.682 410.267 + endloop + endfacet + facet normal -0.00951431 -0.430049 0.902755 + outer loop + vertex -35.933 132.64 407.504 + vertex -56.204 132.478 407.213 + vertex -38.2006 122.533 402.665 + endloop + endfacet + facet normal -0.0103485 -0.426491 0.904432 + outer loop + vertex -56.666 137.022 409.38 + vertex -48.7544 135.912 408.947 + vertex -47.6223 138.682 410.267 + endloop + endfacet + facet normal -0.0121716 -0.423293 0.905911 + outer loop + vertex -62.1883 136.705 409.158 + vertex -56.666 137.022 409.38 + vertex -64.4393 139.071 410.233 + endloop + endfacet + facet normal -0.0147636 -0.425312 0.904926 + outer loop + vertex -67.6355 136.293 408.876 + vertex -62.1883 136.705 409.158 + vertex -64.4393 139.071 410.233 + endloop + endfacet + facet normal -0.0140934 -0.430287 0.902582 + outer loop + vertex -56.204 132.478 407.213 + vertex -75.6646 133.122 407.216 + vertex -57.8346 122.896 402.62 + endloop + endfacet + facet normal -0.0143824 -0.425671 0.904764 + outer loop + vertex -74.7263 137.695 409.423 + vertex -67.6355 136.293 408.876 + vertex -64.4393 139.071 410.233 + endloop + endfacet + facet normal -0.0166993 -0.422949 0.906 + outer loop + vertex -80.7965 137.617 409.274 + vertex -74.7263 137.695 409.423 + vertex -80.1465 139.965 410.382 + endloop + endfacet + facet normal -0.0193988 -0.422315 0.906241 + outer loop + vertex -88.4937 137.679 409.138 + vertex -80.7965 137.617 409.274 + vertex -80.1465 139.965 410.382 + endloop + endfacet + facet normal -0.0187426 -0.430306 0.902488 + outer loop + vertex -75.6646 133.122 407.216 + vertex -95.1637 133.955 407.209 + vertex -77.2047 123.552 402.621 + endloop + endfacet + facet normal -0.0188954 -0.420926 0.906898 + outer loop + vertex -96.1415 138.099 409.174 + vertex -88.4937 137.679 409.138 + vertex -97.1158 140.44 410.24 + endloop + endfacet + facet normal -0.0217364 -0.421878 0.906392 + outer loop + vertex -99.7925 138.269 409.165 + vertex -96.1415 138.099 409.174 + vertex -97.1158 140.44 410.24 + endloop + endfacet + facet normal -0.024136 -0.419447 0.907459 + outer loop + vertex -106.76 138.505 409.089 + vertex -99.7925 138.269 409.165 + vertex -97.1158 140.44 410.24 + endloop + endfacet + facet normal -0.0236603 -0.421312 0.906607 + outer loop + vertex -97.1158 140.44 410.24 + vertex -114.782 141.418 410.234 + vertex -106.76 138.505 409.089 + endloop + endfacet + facet normal -0.0236402 -0.430369 0.902344 + outer loop + vertex -95.1637 133.955 407.209 + vertex -113.713 134.956 407.2 + vertex -96.3083 124.402 402.622 + endloop + endfacet + facet normal -0.023366 -0.420629 0.906932 + outer loop + vertex -114.248 139.061 409.154 + vertex -106.76 138.505 409.089 + vertex -114.782 141.418 410.234 + endloop + endfacet + facet normal -0.0261968 -0.421129 0.906622 + outer loop + vertex -117.83 139.295 409.16 + vertex -114.248 139.061 409.154 + vertex -114.782 141.418 410.234 + endloop + endfacet + facet normal -0.0287765 -0.418096 0.907947 + outer loop + vertex -124.738 139.676 409.116 + vertex -117.83 139.295 409.16 + vertex -114.782 141.418 410.234 + endloop + endfacet + facet normal -0.0287894 -0.430404 0.902177 + outer loop + vertex -113.713 134.956 407.2 + vertex -132.691 136.222 407.198 + vertex -115.248 125.46 402.621 + endloop + endfacet + facet normal -0.0285594 -0.422928 0.905713 + outer loop + vertex -132.754 140.507 409.251 + vertex -124.738 139.676 409.116 + vertex -131.721 142.89 410.397 + endloop + endfacet + facet normal -0.0314062 -0.421884 0.906106 + outer loop + vertex -138.873 141.326 409.42 + vertex -132.754 140.507 409.251 + vertex -131.721 142.89 410.397 + endloop + endfacet + facet normal -0.0339651 -0.425135 0.904492 + outer loop + vertex -145.204 140.676 408.877 + vertex -138.873 141.326 409.42 + vertex -148.564 143.909 410.27 + endloop + endfacet + facet normal -0.0334085 -0.429951 0.902234 + outer loop + vertex -132.691 136.222 407.198 + vertex -151.541 137.651 407.181 + vertex -134.321 126.741 402.62 + endloop + endfacet + facet normal -0.0333584 -0.424619 0.904757 + outer loop + vertex -151.136 141.78 409.176 + vertex -145.204 140.676 408.877 + vertex -148.564 143.909 410.27 + endloop + endfacet + facet normal -0.0360063 -0.421998 0.905881 + outer loop + vertex -156.662 142.715 409.393 + vertex -151.136 141.78 409.176 + vertex -148.564 143.909 410.27 + endloop + endfacet + facet normal -0.0381153 -0.425491 0.90416 + outer loop + vertex -163.35 142.251 408.892 + vertex -156.662 142.715 409.393 + vertex -165.596 145.375 410.267 + endloop + endfacet + facet normal -0.0380896 -0.429711 0.902163 + outer loop + vertex -151.541 137.651 407.181 + vertex -170.239 139.342 407.197 + vertex -153.445 128.245 402.621 + endloop + endfacet + facet normal -0.0378895 -0.42536 0.904231 + outer loop + vertex -169.111 143.409 409.196 + vertex -163.35 142.251 408.892 + vertex -165.596 145.375 410.267 + endloop + endfacet + facet normal -0.0400331 -0.422266 0.905587 + outer loop + vertex -174.333 144.448 409.449 + vertex -169.111 143.409 409.196 + vertex -165.596 145.375 410.267 + endloop + endfacet + facet normal -0.0426647 -0.425124 0.904129 + outer loop + vertex -181.823 144.163 408.962 + vertex -174.333 144.448 409.449 + vertex -181.076 147.104 410.38 + endloop + endfacet + facet normal -0.0425298 -0.429215 0.902201 + outer loop + vertex -170.239 139.342 407.197 + vertex -189.635 141.247 407.189 + vertex -172.667 129.969 402.623 + endloop + endfacet + facet normal -0.0430317 -0.425041 0.904151 + outer loop + vertex -189.823 145.966 409.429 + vertex -181.823 144.163 408.962 + vertex -181.076 147.104 410.38 + endloop + endfacet + facet normal -0.0447681 -0.42099 0.90596 + outer loop + vertex -195.238 146.022 409.187 + vertex -189.823 145.966 409.429 + vertex -197.361 148.6 410.28 + endloop + endfacet + facet normal -0.0475857 -0.422878 0.904936 + outer loop + vertex -200.509 145.924 408.864 + vertex -195.238 146.022 409.187 + vertex -197.361 148.6 410.28 + endloop + endfacet + facet normal -0.0469046 -0.428834 0.902165 + outer loop + vertex -189.635 141.247 407.189 + vertex -208.168 143.211 407.159 + vertex -191.728 131.847 402.612 + endloop + endfacet + facet normal -0.0469295 -0.423511 0.904675 + outer loop + vertex -207.73 147.822 409.378 + vertex -200.509 145.924 408.864 + vertex -197.361 148.6 410.28 + endloop + endfacet + facet normal -0.048751 -0.420572 0.905948 + outer loop + vertex -213.242 147.969 409.15 + vertex -207.73 147.822 409.378 + vertex -214.802 150.583 410.279 + endloop + endfacet + facet normal -0.0515903 -0.421927 0.905161 + outer loop + vertex -218.508 147.986 408.857 + vertex -213.242 147.969 409.15 + vertex -214.802 150.583 410.279 + endloop + endfacet + facet normal -0.0514435 -0.428659 0.902001 + outer loop + vertex -208.168 143.211 407.159 + vertex -226.566 145.484 407.19 + vertex -210.42 133.896 402.604 + endloop + endfacet + facet normal -0.0509458 -0.422675 0.904848 + outer loop + vertex -225.271 149.957 409.397 + vertex -218.508 147.986 408.857 + vertex -214.802 150.583 410.279 + endloop + endfacet + facet normal -0.0529952 -0.421113 0.905459 + outer loop + vertex -231.222 150.367 409.24 + vertex -225.271 149.957 409.397 + vertex -231.392 152.874 410.396 + endloop + endfacet + facet normal -0.0556433 -0.4212 0.905259 + outer loop + vertex -238.773 151.114 409.123 + vertex -231.222 150.367 409.24 + vertex -231.392 152.874 410.396 + endloop + endfacet + facet normal -0.0558222 -0.428471 0.90183 + outer loop + vertex -226.566 145.484 407.19 + vertex -245.377 147.988 407.215 + vertex -229.041 136.176 402.615 + endloop + endfacet + facet normal -0.055062 -0.419168 0.906237 + outer loop + vertex -246.046 152.179 409.174 + vertex -238.773 151.114 409.123 + vertex -248.296 154.756 410.229 + endloop + endfacet + facet normal -0.0581033 -0.421334 0.905042 + outer loop + vertex -249.612 152.667 409.172 + vertex -246.046 152.179 409.174 + vertex -248.296 154.756 410.229 + endloop + endfacet + facet normal -0.0598425 -0.420401 0.905363 + outer loop + vertex -256.717 153.583 409.128 + vertex -249.612 152.667 409.172 + vertex -248.296 154.756 410.229 + endloop + endfacet + facet normal -0.0599634 -0.428023 0.901776 + outer loop + vertex -245.377 147.988 407.215 + vertex -263.764 150.639 407.251 + vertex -247.727 138.683 402.642 + endloop + endfacet + facet normal -0.0595142 -0.421283 0.904975 + outer loop + vertex -264.133 154.833 409.222 + vertex -256.717 153.583 409.128 + vertex -265.588 157.194 410.225 + endloop + endfacet + facet normal -0.0617258 -0.422368 0.90432 + outer loop + vertex -267.75 155.37 409.226 + vertex -264.133 154.833 409.222 + vertex -265.588 157.194 410.225 + endloop + endfacet + facet normal -0.0630136 -0.421113 0.904817 + outer loop + vertex -274.582 156.243 409.157 + vertex -267.75 155.37 409.226 + vertex -265.588 157.194 410.225 + endloop + endfacet + facet normal -0.0631591 -0.42701 0.902038 + outer loop + vertex -263.764 150.639 407.251 + vertex -282.04 153.387 407.272 + vertex -266.39 141.381 402.685 + endloop + endfacet + facet normal -0.0626765 -0.42233 0.904273 + outer loop + vertex -281.84 157.514 409.247 + vertex -274.582 156.243 409.157 + vertex -281.875 159.696 410.264 + endloop + endfacet + facet normal -0.0642111 -0.422308 0.904175 + outer loop + vertex -285.275 158.047 409.252 + vertex -281.84 157.514 409.247 + vertex -281.875 159.696 410.264 + endloop + endfacet + facet normal -0.0658796 -0.419576 0.905326 + outer loop + vertex -291.79 158.921 409.183 + vertex -285.275 158.047 409.252 + vertex -281.875 159.696 410.264 + endloop + endfacet + facet normal -0.0677442 -0.426693 0.901856 + outer loop + vertex -282.04 153.387 407.272 + vertex -301.021 156.07 407.116 + vertex -285.142 144.098 402.644 + endloop + endfacet + facet normal -0.0656368 -0.419656 0.905307 + outer loop + vertex -299.303 160.307 409.281 + vertex -291.79 158.921 409.183 + vertex -296.779 162.329 410.401 + endloop + endfacet + facet normal -0.0695081 -0.415678 0.906852 + outer loop + vertex -305.237 161.494 409.37 + vertex -299.303 160.307 409.281 + vertex -296.779 162.329 410.401 + endloop + endfacet + facet normal -0.0758534 -0.42675 0.901183 + outer loop + vertex -301.021 156.07 407.116 + vertex -322.975 158.961 406.637 + vertex -304.764 146.683 402.355 + endloop + endfacet + facet normal -0.0739388 -0.41708 0.905857 + outer loop + vertex -319.482 163.016 408.905 + vertex -312.883 161.342 408.673 + vertex -314.271 164.927 410.21 + endloop + endfacet + facet normal -0.0775402 -0.409433 0.909039 + outer loop + vertex -327.247 165.354 409.295 + vertex -319.482 163.016 408.905 + vertex -314.271 164.927 410.21 + endloop + endfacet + facet normal -0.0863182 -0.430441 0.898482 + outer loop + vertex -338.902 163.079 407.08 + vertex -322.975 158.961 406.637 + vertex -336.284 165.838 408.653 + endloop + endfacet + facet normal -0.0944198 -0.424025 0.900715 + outer loop + vertex -336.284 165.838 408.653 + vertex -346.739 167.484 408.332 + vertex -338.902 163.079 407.08 + endloop + endfacet + facet normal -0.105229 -0.422909 0.900042 + outer loop + vertex -346.739 167.484 408.332 + vertex -354.251 168.166 407.774 + vertex -347.936 163.816 406.469 + endloop + endfacet + facet normal -0.123425 -0.421395 0.898439 + outer loop + vertex -354.251 168.166 407.774 + vertex -361.072 170.469 407.917 + vertex -356.363 165.373 406.174 + endloop + endfacet + facet normal -0.145606 -0.416939 0.897196 + outer loop + vertex -361.072 170.469 407.917 + vertex -368.267 172.748 407.809 + vertex -363.746 167.548 406.126 + endloop + endfacet + facet normal -0.162304 -0.418446 0.893622 + outer loop + vertex -372.482 176.987 408.947 + vertex -363.823 174.234 409.231 + vertex -365.389 176.308 409.918 + endloop + endfacet + facet normal -0.173065 -0.415545 0.892956 + outer loop + vertex -368.267 172.748 407.809 + vertex -374.154 173.98 407.241 + vertex -369.963 169.552 405.993 + endloop + endfacet + facet normal -0.189202 -0.40797 0.893176 + outer loop + vertex -379.621 181.232 409.374 + vertex -378.776 177.36 407.784 + vertex -372.482 176.987 408.947 + endloop + endfacet + facet normal -0.1027 -0.396867 0.912112 + outer loop + vertex -378.776 177.36 407.784 + vertex -379.621 181.232 409.374 + vertex -380.101 180.822 409.142 + endloop + endfacet + facet normal -0.245818 -0.433867 0.866795 + outer loop + vertex -380.101 180.822 409.142 + vertex -381.011 179.763 408.353 + vertex -378.776 177.36 407.784 + endloop + endfacet + facet normal -0.233154 -0.424056 0.875109 + outer loop + vertex -380.938 175.506 406.31 + vertex -378.776 177.36 407.784 + vertex -381.011 179.763 408.353 + endloop + endfacet + facet normal -0.285567 -0.41869 0.862062 + outer loop + vertex -382.36 176.717 406.427 + vertex -380.938 175.506 406.31 + vertex -381.011 179.763 408.353 + endloop + endfacet + facet normal -0.28434 -0.419302 0.86217 + outer loop + vertex -381.011 179.763 408.353 + vertex -382.585 180.883 408.379 + vertex -382.36 176.717 406.427 + endloop + endfacet + facet normal -0.312373 -0.416817 0.853632 + outer loop + vertex -382.585 180.883 408.379 + vertex -384.361 180.735 407.657 + vertex -382.36 176.717 406.427 + endloop + endfacet + facet normal -0.307112 -0.415045 0.8564 + outer loop + vertex -383.819 176.049 405.58 + vertex -382.36 176.717 406.427 + vertex -384.361 180.735 407.657 + endloop + endfacet + facet normal -0.335333 -0.413844 0.846336 + outer loop + vertex -385.66 178.203 405.904 + vertex -383.819 176.049 405.58 + vertex -384.361 180.735 407.657 + endloop + endfacet + facet normal -0.341854 -0.409989 0.845603 + outer loop + vertex -384.361 180.735 407.657 + vertex -386.825 182.971 407.745 + vertex -385.66 178.203 405.904 + endloop + endfacet + facet normal -0.345778 -0.414172 0.841962 + outer loop + vertex -384.361 180.735 407.657 + vertex -385.892 184.181 408.723 + vertex -386.825 182.971 407.745 + endloop + endfacet + facet normal -0.364913 -0.398869 0.841274 + outer loop + vertex -385.892 184.181 408.723 + vertex -388.037 185.809 408.565 + vertex -386.825 182.971 407.745 + endloop + endfacet + facet normal -0.385591 -0.404264 0.829391 + outer loop + vertex -386.825 182.971 407.745 + vertex -388.037 185.809 408.565 + vertex -388.658 184.908 407.837 + endloop + endfacet + facet normal -0.388939 -0.407287 0.826344 + outer loop + vertex -386.825 182.971 407.745 + vertex -388.658 184.908 407.837 + vertex -388.151 180.901 406.1 + endloop + endfacet + facet normal -0.381649 -0.412573 0.82712 + outer loop + vertex -388.151 180.901 406.1 + vertex -385.66 178.203 405.904 + vertex -386.825 182.971 407.745 + endloop + endfacet + facet normal -0.373357 -0.405446 0.834397 + outer loop + vertex -385.66 178.203 405.904 + vertex -388.151 180.901 406.1 + vertex -386.539 174.031 403.484 + endloop + endfacet + facet normal -0.352043 -0.413114 0.839882 + outer loop + vertex -384.43 172.033 403.385 + vertex -385.66 178.203 405.904 + vertex -386.539 174.031 403.484 + endloop + endfacet + facet normal -0.348591 -0.409627 0.843024 + outer loop + vertex -384.43 172.033 403.385 + vertex -386.539 174.031 403.484 + vertex -385.061 166.673 400.519 + endloop + endfacet + facet normal -0.330366 -0.414434 0.847999 + outer loop + vertex -383.315 165.289 400.523 + vertex -384.43 172.033 403.385 + vertex -385.061 166.673 400.519 + endloop + endfacet + facet normal -0.326783 -0.409902 0.851583 + outer loop + vertex -383.315 165.289 400.523 + vertex -385.061 166.673 400.519 + vertex -383.831 159.366 397.474 + endloop + endfacet + facet normal -0.311804 -0.413259 0.855567 + outer loop + vertex -382.628 158.822 397.65 + vertex -383.315 165.289 400.523 + vertex -383.831 159.366 397.474 + endloop + endfacet + facet normal -0.309728 -0.40755 0.859052 + outer loop + vertex -382.628 158.822 397.65 + vertex -383.831 159.366 397.474 + vertex -383.138 152.89 394.652 + endloop + endfacet + facet normal -0.292845 -0.411127 0.863259 + outer loop + vertex -382.451 153.405 395.13 + vertex -382.628 158.822 397.65 + vertex -383.138 152.89 394.652 + endloop + endfacet + facet normal -0.299499 -0.403483 0.864582 + outer loop + vertex -382.451 153.405 395.13 + vertex -383.138 152.89 394.652 + vertex -383.016 147.621 392.235 + endloop + endfacet + facet normal -0.24924 -0.413876 0.875549 + outer loop + vertex -382.451 153.405 395.13 + vertex -383.016 147.621 392.235 + vertex -382.595 149.909 393.437 + endloop + endfacet + facet normal -0.294964 -0.403985 0.865906 + outer loop + vertex -383.016 147.621 392.235 + vertex -383.138 152.89 394.652 + vertex -383.723 147.037 391.722 + endloop + endfacet + facet normal -0.302852 -0.395493 0.867102 + outer loop + vertex -383.016 147.621 392.235 + vertex -383.723 147.037 391.722 + vertex -383.753 141.525 389.197 + endloop + endfacet + facet normal -0.272583 -0.40253 0.873881 + outer loop + vertex -383.016 147.621 392.235 + vertex -383.753 141.525 389.197 + vertex -383.271 143.798 390.394 + endloop + endfacet + facet normal -0.297718 -0.396189 0.868561 + outer loop + vertex -383.753 141.525 389.197 + vertex -383.723 147.037 391.722 + vertex -384.445 141.306 388.86 + endloop + endfacet + facet normal -0.300611 -0.389887 0.870414 + outer loop + vertex -383.753 141.525 389.197 + vertex -384.445 141.306 388.86 + vertex -384.576 136.077 386.473 + endloop + endfacet + facet normal -0.27945 -0.395369 0.874981 + outer loop + vertex -383.753 141.525 389.197 + vertex -384.576 136.077 386.473 + vertex -384.16 137.222 387.123 + endloop + endfacet + facet normal -0.284656 -0.392248 0.874707 + outer loop + vertex -384.576 136.077 386.473 + vertex -384.445 141.306 388.86 + vertex -385.331 135.669 386.044 + endloop + endfacet + facet normal -0.289405 -0.385148 0.876302 + outer loop + vertex -384.576 136.077 386.473 + vertex -385.331 135.669 386.044 + vertex -385.627 130.411 383.635 + endloop + endfacet + facet normal -0.264012 -0.392282 0.881143 + outer loop + vertex -384.576 136.077 386.473 + vertex -385.627 130.411 383.635 + vertex -384.862 133.233 385.121 + endloop + endfacet + facet normal -0.280565 -0.386658 0.878509 + outer loop + vertex -385.627 130.411 383.635 + vertex -385.331 135.669 386.044 + vertex -386.405 130.028 383.218 + endloop + endfacet + facet normal -0.284062 -0.381015 0.87985 + outer loop + vertex -385.627 130.411 383.635 + vertex -386.405 130.028 383.218 + vertex -386.84 124.761 380.797 + endloop + endfacet + facet normal -0.260725 -0.388094 0.883971 + outer loop + vertex -385.627 130.411 383.635 + vertex -386.84 124.761 380.797 + vertex -386.251 126.542 381.753 + endloop + endfacet + facet normal -0.265836 -0.384447 0.884043 + outer loop + vertex -386.84 124.761 380.797 + vertex -386.405 130.028 383.218 + vertex -387.684 124.443 380.405 + endloop + endfacet + facet normal -0.268637 -0.378903 0.885588 + outer loop + vertex -386.84 124.761 380.797 + vertex -387.684 124.443 380.405 + vertex -388.262 119.113 377.949 + endloop + endfacet + facet normal -0.212294 -0.396827 0.893006 + outer loop + vertex -386.84 124.761 380.797 + vertex -388.262 119.113 377.949 + vertex -387.54 121.134 379.019 + endloop + endfacet + facet normal -0.24617 -0.383441 0.890154 + outer loop + vertex -388.262 119.113 377.949 + vertex -387.684 124.443 380.405 + vertex -389.277 118.954 377.6 + endloop + endfacet + facet normal -0.247924 -0.3771 0.892373 + outer loop + vertex -388.262 119.113 377.949 + vertex -389.277 118.954 377.6 + vertex -390.09 113.68 375.145 + endloop + endfacet + facet normal -0.195562 -0.396977 0.896753 + outer loop + vertex -388.262 119.113 377.949 + vertex -390.09 113.68 375.145 + vertex -389.41 114.962 375.861 + endloop + endfacet + facet normal -0.23256 -0.380682 0.894985 + outer loop + vertex -390.09 113.68 375.145 + vertex -389.277 118.954 377.6 + vertex -391.407 113.415 374.69 + endloop + endfacet + facet normal -0.234525 -0.374491 0.897081 + outer loop + vertex -390.09 113.68 375.145 + vertex -391.407 113.415 374.69 + vertex -392.481 108.082 372.183 + endloop + endfacet + facet normal -0.187512 -0.395627 0.899065 + outer loop + vertex -390.09 113.68 375.145 + vertex -392.481 108.082 372.183 + vertex -391.146 110.069 373.336 + endloop + endfacet + facet normal -0.220292 -0.3783 0.899088 + outer loop + vertex -392.481 108.082 372.183 + vertex -391.407 113.415 374.69 + vertex -394.325 107.339 371.419 + endloop + endfacet + facet normal -0.224887 -0.369494 0.90161 + outer loop + vertex -392.481 108.082 372.183 + vertex -394.325 107.339 371.419 + vertex -396.001 102.076 368.844 + endloop + endfacet + facet normal -0.181644 -0.394392 0.900811 + outer loop + vertex -392.481 108.082 372.183 + vertex -396.001 102.076 368.844 + vertex -394.308 104.064 370.056 + endloop + endfacet + facet normal -0.216816 -0.372439 0.902375 + outer loop + vertex -396.001 102.076 368.844 + vertex -394.325 107.339 371.419 + vertex -396.012 103.138 369.28 + endloop + endfacet + facet normal -0.208373 -0.37306 0.904106 + outer loop + vertex -396.012 103.138 369.28 + vertex -397.634 100.631 367.872 + vertex -396.001 102.076 368.844 + endloop + endfacet + facet normal -0.212748 -0.368646 0.904897 + outer loop + vertex -397.634 100.631 367.872 + vertex -398.853 98.1146 366.56 + vertex -396.001 102.076 368.844 + endloop + endfacet + facet normal -0.219149 -0.366224 0.904353 + outer loop + vertex -396.012 103.138 369.28 + vertex -396.67 103.723 369.357 + vertex -397.634 100.631 367.872 + endloop + endfacet + facet normal -0.210703 -0.369234 0.905136 + outer loop + vertex -397.634 100.631 367.872 + vertex -396.67 103.723 369.357 + vertex -398.751 100.697 367.638 + endloop + endfacet + facet normal -0.210782 -0.366092 0.906393 + outer loop + vertex -397.634 100.631 367.872 + vertex -398.751 100.697 367.638 + vertex -399.796 97.9883 366.301 + endloop + endfacet + facet normal -0.197678 -0.376124 0.905237 + outer loop + vertex -399.796 97.9883 366.301 + vertex -398.853 98.1146 366.56 + vertex -397.634 100.631 367.872 + endloop + endfacet + facet normal -0.198138 -0.374153 0.905953 + outer loop + vertex -398.853 98.1146 366.56 + vertex -399.796 97.9883 366.301 + vertex -400.713 95.9496 365.259 + endloop + endfacet + facet normal -0.183888 -0.385372 0.904253 + outer loop + vertex -400.097 96.1006 365.448 + vertex -398.853 98.1146 366.56 + vertex -400.713 95.9496 365.259 + endloop + endfacet + facet normal -0.183544 -0.386344 0.903908 + outer loop + vertex -400.097 96.1006 365.448 + vertex -400.713 95.9496 365.259 + vertex -401.255 94.6252 364.583 + endloop + endfacet + facet normal -0.175301 -0.392276 0.902989 + outer loop + vertex -400.097 96.1006 365.448 + vertex -401.255 94.6252 364.583 + vertex -400.521 95.2929 365.015 + endloop + endfacet + facet normal -0.174542 -0.392663 0.902968 + outer loop + vertex -398.624 97.8505 366.494 + vertex -400.097 96.1006 365.448 + vertex -400.521 95.2929 365.015 + endloop + endfacet + facet normal -0.162852 -0.404093 0.900104 + outer loop + vertex -402.439 92.2161 363.287 + vertex -400.521 95.2929 365.015 + vertex -401.255 94.6252 364.583 + endloop + endfacet + facet normal -0.181166 -0.395308 0.900506 + outer loop + vertex -401.255 94.6252 364.583 + vertex -401.878 94.5982 364.445 + vertex -402.439 92.2161 363.287 + endloop + endfacet + facet normal -0.191827 -0.392352 0.89959 + outer loop + vertex -401.878 94.5982 364.445 + vertex -402.792 95.1077 364.473 + vertex -402.439 92.2161 363.287 + endloop + endfacet + facet normal -0.190968 -0.392327 0.899784 + outer loop + vertex -404.275 95.5057 364.331 + vertex -402.439 92.2161 363.287 + vertex -402.792 95.1077 364.473 + endloop + endfacet + facet normal -0.187533 -0.37695 0.90705 + outer loop + vertex -402.792 95.1077 364.473 + vertex -403.609 96.4448 364.86 + vertex -404.275 95.5057 364.331 + endloop + endfacet + facet normal -0.200414 -0.368265 0.907863 + outer loop + vertex -403.609 96.4448 364.86 + vertex -404.665 97.5996 365.095 + vertex -404.275 95.5057 364.331 + endloop + endfacet + facet normal -0.20507 -0.36869 0.90665 + outer loop + vertex -406.026 98.1048 364.992 + vertex -404.275 95.5057 364.331 + vertex -404.665 97.5996 365.095 + endloop + endfacet + facet normal -0.199439 -0.351929 0.914533 + outer loop + vertex -404.665 97.5996 365.095 + vertex -405.652 99.1763 365.486 + vertex -406.026 98.1048 364.992 + endloop + endfacet + facet normal -0.219488 -0.344172 0.912891 + outer loop + vertex -405.652 99.1763 365.486 + vertex -406.812 100.567 365.732 + vertex -406.026 98.1048 364.992 + endloop + endfacet + facet normal -0.204985 -0.340917 0.917473 + outer loop + vertex -407.775 100.542 365.507 + vertex -406.026 98.1048 364.992 + vertex -406.812 100.567 365.732 + endloop + endfacet + facet normal -0.207208 -0.319459 0.924668 + outer loop + vertex -406.812 100.567 365.732 + vertex -408.226 102.653 366.136 + vertex -407.775 100.542 365.507 + endloop + endfacet + facet normal -0.20714 -0.31945 0.924686 + outer loop + vertex -409.252 102.86 365.977 + vertex -407.775 100.542 365.507 + vertex -408.226 102.653 366.136 + endloop + endfacet + facet normal -0.203906 -0.297298 0.932757 + outer loop + vertex -408.226 102.653 366.136 + vertex -409.615 104.751 366.5 + vertex -409.252 102.86 365.977 + endloop + endfacet + facet normal -0.193617 -0.296037 0.935347 + outer loop + vertex -410.122 104.335 366.264 + vertex -409.252 102.86 365.977 + vertex -409.615 104.751 366.5 + endloop + endfacet + facet normal -0.20981 -0.277552 0.93752 + outer loop + vertex -410.922 105.995 366.576 + vertex -410.122 104.335 366.264 + vertex -409.615 104.751 366.5 + endloop + endfacet + facet normal -0.207855 -0.275561 0.938543 + outer loop + vertex -409.615 104.751 366.5 + vertex -410.256 108.386 367.426 + vertex -410.922 105.995 366.576 + endloop + endfacet + facet normal -0.2255 -0.269796 0.936141 + outer loop + vertex -411.741 107.778 366.893 + vertex -410.922 105.995 366.576 + vertex -410.256 108.386 367.426 + endloop + endfacet + facet normal -0.238798 -0.241235 0.940628 + outer loop + vertex -412.68 110.05 367.237 + vertex -411.741 107.778 366.893 + vertex -410.256 108.386 367.426 + endloop + endfacet + facet normal -0.235981 -0.236931 0.942431 + outer loop + vertex -410.256 108.386 367.426 + vertex -411.856 112.921 368.165 + vertex -412.68 110.05 367.237 + endloop + endfacet + facet normal -0.244316 -0.243222 0.938697 + outer loop + vertex -411.741 107.778 366.893 + vertex -412.68 110.05 367.237 + vertex -413.088 107.24 366.403 + endloop + endfacet + facet normal -0.241093 -0.243887 0.939358 + outer loop + vertex -415.105 111.294 366.938 + vertex -413.088 107.24 366.403 + vertex -412.68 110.05 367.237 + endloop + endfacet + facet normal -0.225576 -0.210789 0.951149 + outer loop + vertex -412.68 110.05 367.237 + vertex -414.105 113.744 367.718 + vertex -415.105 111.294 366.938 + endloop + endfacet + facet normal -0.244988 -0.201948 0.948261 + outer loop + vertex -416.389 114.891 367.372 + vertex -415.105 111.294 366.938 + vertex -414.105 113.744 367.718 + endloop + endfacet + facet normal -0.234978 -0.179928 0.955202 + outer loop + vertex -414.105 113.744 367.718 + vertex -415.325 117.444 368.115 + vertex -416.389 114.891 367.372 + endloop + endfacet + facet normal -0.25801 -0.169176 0.951215 + outer loop + vertex -417.379 118.382 367.724 + vertex -416.389 114.891 367.372 + vertex -415.325 117.444 368.115 + endloop + endfacet + facet normal -0.253395 -0.157736 0.954416 + outer loop + vertex -415.325 117.444 368.115 + vertex -416.186 120.883 368.454 + vertex -417.379 118.382 367.724 + endloop + endfacet + facet normal -0.278113 -0.144541 0.949611 + outer loop + vertex -418.048 121.793 368.048 + vertex -417.379 118.382 367.724 + vertex -416.186 120.883 368.454 + endloop + endfacet + facet normal -0.277076 -0.142123 0.950279 + outer loop + vertex -416.186 120.883 368.454 + vertex -416.43 124.259 368.888 + vertex -418.048 121.793 368.048 + endloop + endfacet + facet normal -0.304397 -0.12228 0.944664 + outer loop + vertex -418.405 125.24 368.379 + vertex -418.048 121.793 368.048 + vertex -416.43 124.259 368.888 + endloop + endfacet + facet normal -0.30329 -0.119694 0.945351 + outer loop + vertex -416.43 124.259 368.888 + vertex -416.291 128.068 369.415 + vertex -418.405 125.24 368.379 + endloop + endfacet + facet normal -0.328484 -0.098654 0.939343 + outer loop + vertex -418.729 128.677 368.627 + vertex -418.405 125.24 368.379 + vertex -416.291 128.068 369.415 + endloop + endfacet + facet normal -0.32526 -0.0822728 0.942039 + outer loop + vertex -416.291 128.068 369.415 + vertex -417.109 131.051 369.393 + vertex -418.729 128.677 368.627 + endloop + endfacet + facet normal -0.330311 -0.0783651 0.940613 + outer loop + vertex -419.062 132.156 368.8 + vertex -418.729 128.677 368.627 + vertex -417.109 131.051 369.393 + endloop + endfacet + facet normal -0.328425 -0.0745084 0.941587 + outer loop + vertex -417.109 131.051 369.393 + vertex -417.17 134.619 369.654 + vertex -419.062 132.156 368.8 + endloop + endfacet + facet normal -0.339407 -0.06497 0.938393 + outer loop + vertex -419.366 135.726 368.937 + vertex -419.062 132.156 368.8 + vertex -417.17 134.619 369.654 + endloop + endfacet + facet normal -0.336185 -0.0575116 0.940038 + outer loop + vertex -417.17 134.619 369.654 + vertex -417.819 137.937 369.625 + vertex -419.366 135.726 368.937 + endloop + endfacet + facet normal -0.338228 -0.0558858 0.939403 + outer loop + vertex -419.696 139.319 369.032 + vertex -419.366 135.726 368.937 + vertex -417.819 137.937 369.625 + endloop + endfacet + facet normal -0.339186 -0.0573742 0.938968 + outer loop + vertex -417.819 137.937 369.625 + vertex -417.928 141.597 369.809 + vertex -419.696 139.319 369.032 + endloop + endfacet + facet normal -0.347942 -0.0496369 0.936201 + outer loop + vertex -419.957 142.789 369.119 + vertex -419.696 139.319 369.032 + vertex -417.928 141.597 369.809 + endloop + endfacet + facet normal -0.345419 -0.0446589 0.937385 + outer loop + vertex -417.928 141.597 369.809 + vertex -418.478 144.564 369.748 + vertex -419.957 142.789 369.119 + endloop + endfacet + facet normal -0.343737 -0.0462516 0.937926 + outer loop + vertex -419.86 145.983 369.312 + vertex -419.957 142.789 369.119 + vertex -418.478 144.564 369.748 + endloop + endfacet + facet normal -0.346142 -0.0489069 0.936906 + outer loop + vertex -418.478 144.564 369.748 + vertex -418.337 146.069 369.879 + vertex -419.86 145.983 369.312 + endloop + endfacet + facet normal -0.346214 -0.0478255 0.936936 + outer loop + vertex -418.337 146.069 369.879 + vertex -418.505 147.292 369.879 + vertex -419.86 145.983 369.312 + endloop + endfacet + facet normal -0.334263 -0.0617269 0.940456 + outer loop + vertex -419.659 148.395 369.542 + vertex -419.86 145.983 369.312 + vertex -418.505 147.292 369.879 + endloop + endfacet + facet normal -0.369418 -0.103689 0.92346 + outer loop + vertex -418.505 147.292 369.879 + vertex -418.226 149.621 370.252 + vertex -419.659 148.395 369.542 + endloop + endfacet + facet normal -0.329971 -0.154311 0.931293 + outer loop + vertex -418.226 149.621 370.252 + vertex -419.906 150.963 369.879 + vertex -419.659 148.395 369.542 + endloop + endfacet + facet normal -0.246408 -0.149715 0.957533 + outer loop + vertex -422.253 148.237 368.849 + vertex -419.659 148.395 369.542 + vertex -419.906 150.963 369.879 + endloop + endfacet + facet normal -0.185862 -0.203283 0.961318 + outer loop + vertex -423.358 151.531 369.332 + vertex -422.253 148.237 368.849 + vertex -419.906 150.963 369.879 + endloop + endfacet + facet normal -0.194248 -0.272436 0.942362 + outer loop + vertex -419.906 150.963 369.879 + vertex -420.298 153.148 370.43 + vertex -423.358 151.531 369.332 + endloop + endfacet + facet normal -0.204386 -0.208772 0.956368 + outer loop + vertex -423.358 151.531 369.332 + vertex -426.186 150.37 368.474 + vertex -422.253 148.237 368.849 + endloop + endfacet + facet normal -0.193246 -0.187032 0.963159 + outer loop + vertex -422.253 148.237 368.849 + vertex -426.186 150.37 368.474 + vertex -425.752 146.637 367.836 + endloop + endfacet + facet normal -0.237911 -0.0917282 0.966946 + outer loop + vertex -422.253 148.237 368.849 + vertex -425.752 146.637 367.836 + vertex -422.37 144.5 368.466 + endloop + endfacet + facet normal -0.269938 -0.0898798 0.958674 + outer loop + vertex -419.86 145.983 369.312 + vertex -422.253 148.237 368.849 + vertex -422.37 144.5 368.466 + endloop + endfacet + facet normal -0.234158 -0.0853464 0.968445 + outer loop + vertex -422.37 144.5 368.466 + vertex -425.752 146.637 367.836 + vertex -425.418 142.998 367.597 + endloop + endfacet + facet normal -0.25197 -0.0480913 0.966539 + outer loop + vertex -422.37 144.5 368.466 + vertex -425.418 142.998 367.597 + vertex -422.189 140.956 368.337 + endloop + endfacet + facet normal -0.293536 -0.0497792 0.954651 + outer loop + vertex -419.957 142.789 369.119 + vertex -422.37 144.5 368.466 + vertex -422.189 140.956 368.337 + endloop + endfacet + facet normal -0.251637 -0.0475226 0.966654 + outer loop + vertex -422.189 140.956 368.337 + vertex -425.418 142.998 367.597 + vertex -425.128 139.424 367.496 + endloop + endfacet + facet normal -0.253262 -0.0442586 0.966385 + outer loop + vertex -422.189 140.956 368.337 + vertex -425.128 139.424 367.496 + vertex -421.91 137.377 368.246 + endloop + endfacet + facet normal -0.296933 -0.0473434 0.953724 + outer loop + vertex -419.696 139.319 369.032 + vertex -422.189 140.956 368.337 + vertex -421.91 137.377 368.246 + endloop + endfacet + facet normal -0.253202 -0.0441571 0.966405 + outer loop + vertex -421.91 137.377 368.246 + vertex -425.128 139.424 367.496 + vertex -424.878 135.869 367.399 + endloop + endfacet + facet normal -0.250089 -0.0505615 0.966902 + outer loop + vertex -421.91 137.377 368.246 + vertex -424.878 135.869 367.399 + vertex -421.628 133.787 368.131 + endloop + endfacet + facet normal -0.293912 -0.0535911 0.954329 + outer loop + vertex -419.366 135.726 368.937 + vertex -421.91 137.377 368.246 + vertex -421.628 133.787 368.131 + endloop + endfacet + facet normal -0.249529 -0.0496198 0.967095 + outer loop + vertex -421.628 133.787 368.131 + vertex -424.878 135.869 367.399 + vertex -424.646 132.344 367.278 + endloop + endfacet + facet normal -0.244581 -0.0603532 0.967749 + outer loop + vertex -421.628 133.787 368.131 + vertex -424.646 132.344 367.278 + vertex -421.351 130.247 367.98 + endloop + endfacet + facet normal -0.289028 -0.0633059 0.955225 + outer loop + vertex -419.062 132.156 368.8 + vertex -421.628 133.787 368.131 + vertex -421.351 130.247 367.98 + endloop + endfacet + facet normal -0.244422 -0.0600844 0.967806 + outer loop + vertex -421.351 130.247 367.98 + vertex -424.646 132.344 367.278 + vertex -424.37 128.847 367.131 + endloop + endfacet + facet normal -0.237685 -0.0750006 0.968442 + outer loop + vertex -421.351 130.247 367.98 + vertex -424.37 128.847 367.131 + vertex -421.01 126.75 367.793 + endloop + endfacet + facet normal -0.282737 -0.0787287 0.955961 + outer loop + vertex -418.729 128.677 368.627 + vertex -421.351 130.247 367.98 + vertex -421.01 126.75 367.793 + endloop + endfacet + facet normal -0.237794 -0.0751887 0.968401 + outer loop + vertex -421.01 126.75 367.793 + vertex -424.37 128.847 367.131 + vertex -424.001 125.369 366.952 + endloop + endfacet + facet normal -0.229544 -0.0933086 0.968815 + outer loop + vertex -421.01 126.75 367.793 + vertex -424.001 125.369 366.952 + vertex -420.593 123.3 367.56 + endloop + endfacet + facet normal -0.271834 -0.0976447 0.957378 + outer loop + vertex -418.405 125.24 368.379 + vertex -421.01 126.75 367.793 + vertex -420.593 123.3 367.56 + endloop + endfacet + facet normal -0.229697 -0.0935787 0.968753 + outer loop + vertex -420.593 123.3 367.56 + vertex -424.001 125.369 366.952 + vertex -423.523 121.911 366.731 + endloop + endfacet + facet normal -0.220143 -0.113767 0.968811 + outer loop + vertex -420.593 123.3 367.56 + vertex -423.523 121.911 366.731 + vertex -420.006 119.867 367.29 + endloop + endfacet + facet normal -0.254435 -0.118912 0.959751 + outer loop + vertex -418.048 121.793 368.048 + vertex -420.593 123.3 367.56 + vertex -420.006 119.867 367.29 + endloop + endfacet + facet normal -0.221197 -0.115711 0.96834 + outer loop + vertex -420.006 119.867 367.29 + vertex -423.523 121.911 366.731 + vertex -422.95 118.501 366.454 + endloop + endfacet + facet normal -0.211229 -0.136865 0.967807 + outer loop + vertex -420.006 119.867 367.29 + vertex -422.95 118.501 366.454 + vertex -419.244 116.462 366.975 + endloop + endfacet + facet normal -0.239377 -0.142487 0.960415 + outer loop + vertex -417.379 118.382 367.724 + vertex -420.006 119.867 367.29 + vertex -419.244 116.462 366.975 + endloop + endfacet + facet normal -0.21402 -0.142294 0.96641 + outer loop + vertex -419.244 116.462 366.975 + vertex -422.95 118.501 366.454 + vertex -422.241 115.135 366.116 + endloop + endfacet + facet normal -0.203244 -0.16572 0.965002 + outer loop + vertex -419.244 116.462 366.975 + vertex -422.241 115.135 366.116 + vertex -418.29 113.059 366.591 + endloop + endfacet + facet normal -0.227974 -0.171904 0.958372 + outer loop + vertex -416.389 114.891 367.372 + vertex -419.244 116.462 366.975 + vertex -418.29 113.059 366.591 + endloop + endfacet + facet normal -0.206978 -0.173314 0.962872 + outer loop + vertex -418.29 113.059 366.591 + vertex -422.241 115.135 366.116 + vertex -421.43 111.833 365.696 + endloop + endfacet + facet normal -0.195901 -0.199648 0.960085 + outer loop + vertex -418.29 113.059 366.591 + vertex -421.43 111.833 365.696 + vertex -417.11 109.607 366.114 + endloop + endfacet + facet normal -0.218133 -0.206384 0.953847 + outer loop + vertex -415.105 111.294 366.938 + vertex -418.29 113.059 366.591 + vertex -417.11 109.607 366.114 + endloop + endfacet + facet normal -0.198201 -0.204388 0.958615 + outer loop + vertex -417.11 109.607 366.114 + vertex -421.43 111.833 365.696 + vertex -420.484 108.561 365.194 + endloop + endfacet + facet normal -0.188423 -0.2321 0.954267 + outer loop + vertex -417.11 109.607 366.114 + vertex -420.484 108.561 365.194 + vertex -415.861 106.193 365.53 + endloop + endfacet + facet normal -0.20839 -0.238426 0.948539 + outer loop + vertex -413.088 107.24 366.403 + vertex -417.11 109.607 366.114 + vertex -415.861 106.193 365.53 + endloop + endfacet + facet normal -0.195596 -0.267979 0.943361 + outer loop + vertex -413.088 107.24 366.403 + vertex -415.861 106.193 365.53 + vertex -411.855 103.537 365.607 + endloop + endfacet + facet normal -0.218806 -0.274219 0.936444 + outer loop + vertex -411.855 103.537 365.607 + vertex -410.638 104.168 366.076 + vertex -413.088 107.24 366.403 + endloop + endfacet + facet normal -0.241446 -0.291135 0.925713 + outer loop + vertex -410.922 105.995 366.576 + vertex -413.088 107.24 366.403 + vertex -410.638 104.168 366.076 + endloop + endfacet + facet normal -0.202956 -0.301257 0.931694 + outer loop + vertex -410.638 104.168 366.076 + vertex -411.855 103.537 365.607 + vertex -409.226 101.53 365.53 + endloop + endfacet + facet normal -0.230673 -0.31388 0.921015 + outer loop + vertex -410.638 104.168 366.076 + vertex -409.226 101.53 365.53 + vertex -409.252 102.86 365.977 + endloop + endfacet + facet normal -0.18858 -0.282762 0.94047 + outer loop + vertex -409.226 101.53 365.53 + vertex -411.855 103.537 365.607 + vertex -410.011 101.531 365.373 + endloop + endfacet + facet normal -0.187187 -0.306558 0.933265 + outer loop + vertex -410.011 101.531 365.373 + vertex -409.125 100.024 365.056 + vertex -409.226 101.53 365.53 + endloop + endfacet + facet normal -0.167031 -0.30642 0.937127 + outer loop + vertex -407.439 98.6828 364.918 + vertex -409.226 101.53 365.53 + vertex -409.125 100.024 365.056 + endloop + endfacet + facet normal -0.174277 -0.315095 0.932921 + outer loop + vertex -408.429 98.3881 364.633 + vertex -407.439 98.6828 364.918 + vertex -409.125 100.024 365.056 + endloop + endfacet + facet normal -0.178643 -0.316607 0.931583 + outer loop + vertex -409.125 100.024 365.056 + vertex -410.479 99.2473 364.532 + vertex -408.429 98.3881 364.633 + endloop + endfacet + facet normal -0.181022 -0.322579 0.929071 + outer loop + vertex -408.429 98.3881 364.633 + vertex -410.479 99.2473 364.532 + vertex -409.539 97.5318 364.12 + endloop + endfacet + facet normal -0.171827 -0.333283 0.927037 + outer loop + vertex -408.429 98.3881 364.633 + vertex -409.539 97.5318 364.12 + vertex -407.493 97.0037 364.309 + endloop + endfacet + facet normal -0.173183 -0.33943 0.924551 + outer loop + vertex -407.493 97.0037 364.309 + vertex -409.539 97.5318 364.12 + vertex -408.798 96.1647 363.757 + endloop + endfacet + facet normal -0.168174 -0.346185 0.92297 + outer loop + vertex -407.493 97.0037 364.309 + vertex -408.798 96.1647 363.757 + vertex -406.932 95.7266 363.932 + endloop + endfacet + facet normal -0.166192 -0.345496 0.923587 + outer loop + vertex -406.932 95.7266 363.932 + vertex -405.907 96.1591 364.279 + vertex -407.493 97.0037 364.309 + endloop + endfacet + facet normal -0.158861 -0.331963 0.929819 + outer loop + vertex -405.907 96.1591 364.279 + vertex -407.439 98.6828 364.918 + vertex -407.493 97.0037 364.309 + endloop + endfacet + facet normal -0.190848 -0.348313 0.917745 + outer loop + vertex -407.439 98.6828 364.918 + vertex -405.907 96.1591 364.279 + vertex -406.026 98.1048 364.992 + endloop + endfacet + facet normal -0.159611 -0.35815 0.91992 + outer loop + vertex -406.932 95.7266 363.932 + vertex -406.222 94.7445 363.673 + vertex -405.907 96.1591 364.279 + endloop + endfacet + facet normal -0.157769 -0.358618 0.920055 + outer loop + vertex -404.872 94.1829 363.686 + vertex -405.907 96.1591 364.279 + vertex -406.222 94.7445 363.673 + endloop + endfacet + facet normal -0.162095 -0.369132 0.915132 + outer loop + vertex -406.143 93.7989 363.306 + vertex -404.872 94.1829 363.686 + vertex -406.222 94.7445 363.673 + endloop + endfacet + facet normal -0.163871 -0.369154 0.914807 + outer loop + vertex -406.222 94.7445 363.673 + vertex -407.792 94.0524 363.113 + vertex -406.143 93.7989 363.306 + endloop + endfacet + facet normal -0.164047 -0.370843 0.914092 + outer loop + vertex -406.143 93.7989 363.306 + vertex -407.792 94.0524 363.113 + vertex -408.008 93.2711 362.757 + endloop + endfacet + facet normal -0.161873 -0.376514 0.912159 + outer loop + vertex -406.143 93.7989 363.306 + vertex -408.008 93.2711 362.757 + vertex -406.046 93.063 363.019 + endloop + endfacet + facet normal -0.161478 -0.368661 0.915431 + outer loop + vertex -410.112 92.6786 362.147 + vertex -406.046 93.063 363.019 + vertex -408.008 93.2711 362.757 + endloop + endfacet + facet normal -0.161255 -0.36925 0.915233 + outer loop + vertex -410.346 93.0353 362.25 + vertex -410.112 92.6786 362.147 + vertex -408.008 93.2711 362.757 + endloop + endfacet + facet normal -0.161313 -0.368929 0.915352 + outer loop + vertex -408.008 93.2711 362.757 + vertex -410.554 93.6219 362.45 + vertex -410.346 93.0353 362.25 + endloop + endfacet + facet normal -0.157407 -0.367913 0.916441 + outer loop + vertex -410.346 93.0353 362.25 + vertex -410.554 93.6219 362.45 + vertex -414.516 93.2067 361.603 + endloop + endfacet + facet normal -0.159822 -0.354657 0.921236 + outer loop + vertex -414.786 94.7303 362.142 + vertex -414.516 93.2067 361.603 + vertex -410.554 93.6219 362.45 + endloop + endfacet + facet normal -0.162052 -0.364325 0.917064 + outer loop + vertex -410.184 94.4477 362.843 + vertex -414.786 94.7303 362.142 + vertex -410.554 93.6219 362.45 + endloop + endfacet + facet normal -0.163458 -0.363695 0.917065 + outer loop + vertex -407.792 94.0524 363.113 + vertex -410.184 94.4477 362.843 + vertex -410.554 93.6219 362.45 + endloop + endfacet + facet normal -0.163568 -0.364629 0.916674 + outer loop + vertex -408.171 95.0202 363.43 + vertex -410.184 94.4477 362.843 + vertex -407.792 94.0524 363.113 + endloop + endfacet + facet normal -0.166792 -0.35612 0.919434 + outer loop + vertex -408.171 95.0202 363.43 + vertex -411.266 95.5468 363.073 + vertex -410.184 94.4477 362.843 + endloop + endfacet + facet normal -0.166521 -0.353912 0.920335 + outer loop + vertex -408.798 96.1647 363.757 + vertex -411.266 95.5468 363.073 + vertex -408.171 95.0202 363.43 + endloop + endfacet + facet normal -0.170424 -0.342365 0.923982 + outer loop + vertex -408.798 96.1647 363.757 + vertex -411.391 96.7807 363.507 + vertex -411.266 95.5468 363.073 + endloop + endfacet + facet normal -0.168277 -0.342294 0.924401 + outer loop + vertex -411.391 96.7807 363.507 + vertex -415.842 97.0094 362.781 + vertex -411.266 95.5468 363.073 + endloop + endfacet + facet normal -0.166734 -0.337028 0.926613 + outer loop + vertex -415.842 97.0094 362.781 + vertex -414.786 94.7303 362.142 + vertex -411.266 95.5468 363.073 + endloop + endfacet + facet normal -0.157316 -0.333481 0.929539 + outer loop + vertex -415.842 97.0094 362.781 + vertex -421.581 96.4273 361.601 + vertex -414.786 94.7303 362.142 + endloop + endfacet + facet normal -0.157163 -0.33278 0.929816 + outer loop + vertex -414.786 94.7303 362.142 + vertex -421.581 96.4273 361.601 + vertex -420.988 94.4015 360.976 + endloop + endfacet + facet normal -0.148989 -0.331 0.931795 + outer loop + vertex -421.581 96.4273 361.601 + vertex -427.52 96.2768 360.598 + vertex -420.988 94.4015 360.976 + endloop + endfacet + facet normal -0.148908 -0.330696 0.931915 + outer loop + vertex -420.988 94.4015 360.976 + vertex -427.52 96.2768 360.598 + vertex -427.211 94.3888 359.977 + endloop + endfacet + facet normal -0.147655 -0.351753 0.924374 + outer loop + vertex -420.988 94.4015 360.976 + vertex -427.211 94.3888 359.977 + vertex -421.105 93.0627 360.448 + endloop + endfacet + facet normal -0.154154 -0.350894 0.923639 + outer loop + vertex -414.516 93.2067 361.603 + vertex -420.988 94.4015 360.976 + vertex -421.105 93.0627 360.448 + endloop + endfacet + facet normal -0.152228 -0.372728 0.915369 + outer loop + vertex -414.516 93.2067 361.603 + vertex -421.105 93.0627 360.448 + vertex -416.084 92.4573 361.037 + endloop + endfacet + facet normal -0.15722 -0.364229 0.917943 + outer loop + vertex -410.112 92.6786 362.147 + vertex -414.516 93.2067 361.603 + vertex -416.084 92.4573 361.037 + endloop + endfacet + facet normal -0.155102 -0.383543 0.910405 + outer loop + vertex -410.112 92.6786 362.147 + vertex -416.084 92.4573 361.037 + vertex -412.927 92.2177 361.474 + endloop + endfacet + facet normal -0.15676 -0.376996 0.912853 + outer loop + vertex -412.927 92.2177 361.474 + vertex -409.638 92.3568 362.096 + vertex -410.112 92.6786 362.147 + endloop + endfacet + facet normal -0.159769 -0.381066 0.910638 + outer loop + vertex -409.638 92.3568 362.096 + vertex -407.189 92.3995 362.543 + vertex -410.112 92.6786 362.147 + endloop + endfacet + facet normal -0.161259 -0.364335 0.9172 + outer loop + vertex -407.189 92.3995 362.543 + vertex -409.638 92.3568 362.096 + vertex -410.554 91.8766 361.744 + endloop + endfacet + facet normal -0.155964 -0.386131 0.909163 + outer loop + vertex -410.554 91.8766 361.744 + vertex -406.89 91.7192 362.306 + vertex -407.189 92.3995 362.543 + endloop + endfacet + facet normal -0.157175 -0.386531 0.908785 + outer loop + vertex -402.439 92.2161 363.287 + vertex -407.189 92.3995 362.543 + vertex -406.89 91.7192 362.306 + endloop + endfacet + facet normal -0.152251 -0.410991 0.898836 + outer loop + vertex -406.89 91.7192 362.306 + vertex -406.316 90.4838 361.838 + vertex -402.439 92.2161 363.287 + endloop + endfacet + facet normal -0.141659 -0.42906 0.892099 + outer loop + vertex -406.316 90.4838 361.838 + vertex -405.448 88.2829 360.917 + vertex -402.439 92.2161 363.287 + endloop + endfacet + facet normal -0.142215 -0.428689 0.892189 + outer loop + vertex -403.562 87.4412 360.813 + vertex -402.439 92.2161 363.287 + vertex -405.448 88.2829 360.917 + endloop + endfacet + facet normal -0.150338 -0.445686 0.882475 + outer loop + vertex -405.448 88.2829 360.917 + vertex -405.459 85.0516 359.284 + vertex -403.562 87.4412 360.813 + endloop + endfacet + facet normal -0.137095 -0.454649 0.880056 + outer loop + vertex -404.337 83.2084 358.506 + vertex -403.562 87.4412 360.813 + vertex -405.459 85.0516 359.284 + endloop + endfacet + facet normal -0.146349 -0.445968 0.883003 + outer loop + vertex -405.448 88.2829 360.917 + vertex -408.819 85.3656 358.885 + vertex -405.459 85.0516 359.284 + endloop + endfacet + facet normal -0.147221 -0.474503 0.867855 + outer loop + vertex -405.459 85.0516 359.284 + vertex -408.819 85.3656 358.885 + vertex -408.287 81.0381 356.609 + endloop + endfacet + facet normal -0.161976 -0.465576 0.870059 + outer loop + vertex -405.459 85.0516 359.284 + vertex -408.287 81.0381 356.609 + vertex -404.337 83.2084 358.506 + endloop + endfacet + facet normal -0.146911 -0.474495 0.867912 + outer loop + vertex -416.134 82.6529 356.164 + vertex -408.287 81.0381 356.609 + vertex -408.819 85.3656 358.885 + endloop + endfacet + facet normal -0.148071 -0.472345 0.868887 + outer loop + vertex -412.84 86.4708 358.801 + vertex -416.134 82.6529 356.164 + vertex -408.819 85.3656 358.885 + endloop + endfacet + facet normal -0.141699 -0.448109 0.882677 + outer loop + vertex -408.97 88.5513 360.478 + vertex -412.84 86.4708 358.801 + vertex -408.819 85.3656 358.885 + endloop + endfacet + facet normal -0.14642 -0.441422 0.885273 + outer loop + vertex -413.931 88.8888 359.826 + vertex -412.84 86.4708 358.801 + vertex -408.97 88.5513 360.478 + endloop + endfacet + facet normal -0.146342 -0.4225 0.894471 + outer loop + vertex -409.774 90.6556 361.341 + vertex -413.931 88.8888 359.826 + vertex -408.97 88.5513 360.478 + endloop + endfacet + facet normal -0.149549 -0.423344 0.893541 + outer loop + vertex -409.774 90.6556 361.341 + vertex -408.97 88.5513 360.478 + vertex -406.316 90.4838 361.838 + endloop + endfacet + facet normal -0.149564 -0.416767 0.896625 + outer loop + vertex -414.847 90.8151 360.569 + vertex -413.931 88.8888 359.826 + vertex -409.774 90.6556 361.341 + endloop + endfacet + facet normal -0.150339 -0.395351 0.906143 + outer loop + vertex -410.554 91.8766 361.744 + vertex -414.847 90.8151 360.569 + vertex -409.774 90.6556 361.341 + endloop + endfacet + facet normal -0.153247 -0.387024 0.909246 + outer loop + vertex -416.016 91.7795 360.782 + vertex -414.847 90.8151 360.569 + vertex -410.554 91.8766 361.744 + endloop + endfacet + facet normal -0.156048 -0.354657 0.921882 + outer loop + vertex -416.016 91.7795 360.782 + vertex -410.554 91.8766 361.744 + vertex -412.927 92.2177 361.474 + endloop + endfacet + facet normal -0.15497 -0.359548 0.920168 + outer loop + vertex -412.927 92.2177 361.474 + vertex -418.244 92.1067 360.535 + vertex -416.016 91.7795 360.782 + endloop + endfacet + facet normal -0.152102 -0.331833 0.930995 + outer loop + vertex -421.351 91.8696 359.943 + vertex -416.016 91.7795 360.782 + vertex -418.244 92.1067 360.535 + endloop + endfacet + facet normal -0.148692 -0.35575 0.922677 + outer loop + vertex -418.244 92.1067 360.535 + vertex -423.738 92.1847 359.679 + vertex -421.351 91.8696 359.943 + endloop + endfacet + facet normal -0.146694 -0.333418 0.931297 + outer loop + vertex -425.006 92.0338 359.426 + vertex -421.351 91.8696 359.943 + vertex -423.738 92.1847 359.679 + endloop + endfacet + facet normal -0.141505 -0.361007 0.921765 + outer loop + vertex -423.738 92.1847 359.679 + vertex -429.653 92.2851 358.811 + vertex -425.006 92.0338 359.426 + endloop + endfacet + facet normal -0.141515 -0.366811 0.919469 + outer loop + vertex -426.614 91.5831 358.998 + vertex -425.006 92.0338 359.426 + vertex -429.653 92.2851 358.811 + endloop + endfacet + facet normal -0.143589 -0.376981 0.915023 + outer loop + vertex -436.542 91.5298 357.418 + vertex -426.614 91.5831 358.998 + vertex -429.653 92.2851 358.811 + endloop + endfacet + facet normal -0.138103 -0.405753 0.903489 + outer loop + vertex -429.653 92.2851 358.811 + vertex -435.448 92.7418 358.13 + vertex -436.542 91.5298 357.418 + endloop + endfacet + facet normal -0.13442 -0.408639 0.902743 + outer loop + vertex -435.448 92.7418 358.13 + vertex -440.629 93.2573 357.592 + vertex -436.542 91.5298 357.418 + endloop + endfacet + facet normal -0.136372 -0.413028 0.90045 + outer loop + vertex -448.793 93.1319 356.298 + vertex -436.542 91.5298 357.418 + vertex -440.629 93.2573 357.592 + endloop + endfacet + facet normal -0.135781 -0.419842 0.897383 + outer loop + vertex -440.629 93.2573 357.592 + vertex -446.531 94.4376 357.251 + vertex -448.793 93.1319 356.298 + endloop + endfacet + facet normal -0.131085 -0.426273 0.895046 + outer loop + vertex -446.531 94.4376 357.251 + vertex -452.761 95.1232 356.665 + vertex -448.793 93.1319 356.298 + endloop + endfacet + facet normal -0.134548 -0.432524 0.891527 + outer loop + vertex -460.551 95.118 355.487 + vertex -448.793 93.1319 356.298 + vertex -452.761 95.1232 356.665 + endloop + endfacet + facet normal -0.134106 -0.438584 0.888628 + outer loop + vertex -452.761 95.1232 356.665 + vertex -458.563 96.5551 356.496 + vertex -460.551 95.118 355.487 + endloop + endfacet + facet normal -0.128653 -0.444595 0.886445 + outer loop + vertex -458.563 96.5551 356.496 + vertex -464.985 97.3096 355.943 + vertex -460.551 95.118 355.487 + endloop + endfacet + facet normal -0.135985 -0.457795 0.878596 + outer loop + vertex -472.29 97.4096 354.864 + vertex -460.551 95.118 355.487 + vertex -464.985 97.3096 355.943 + endloop + endfacet + facet normal -0.135889 -0.459353 0.877798 + outer loop + vertex -464.985 97.3096 355.943 + vertex -471.228 98.9785 355.85 + vertex -472.29 97.4096 354.864 + endloop + endfacet + facet normal -0.131419 -0.46195 0.877115 + outer loop + vertex -471.228 98.9785 355.85 + vertex -477.541 99.8436 355.359 + vertex -472.29 97.4096 354.864 + endloop + endfacet + facet normal -0.139678 -0.477773 0.867308 + outer loop + vertex -482.91 99.5553 354.336 + vertex -472.29 97.4096 354.864 + vertex -477.541 99.8436 355.359 + endloop + endfacet + facet normal -0.139514 -0.478834 0.866749 + outer loop + vertex -477.541 99.8436 355.359 + vertex -485.27 101.882 355.241 + vertex -482.91 99.5553 354.336 + endloop + endfacet + facet normal -0.138701 -0.478196 0.867232 + outer loop + vertex -491.742 102.011 354.277 + vertex -482.91 99.5553 354.336 + vertex -485.27 101.882 355.241 + endloop + endfacet + facet normal -0.138245 -0.485601 0.86318 + outer loop + vertex -485.27 101.882 355.241 + vertex -490.999 103.354 355.152 + vertex -491.742 102.011 354.277 + endloop + endfacet + facet normal -0.138498 -0.48548 0.863208 + outer loop + vertex -490.999 103.354 355.152 + vertex -496.186 104.621 355.032 + vertex -491.742 102.011 354.277 + endloop + endfacet + facet normal -0.137757 -0.484424 0.863919 + outer loop + vertex -496.186 104.621 355.032 + vertex -498.801 103.794 354.152 + vertex -491.742 102.011 354.277 + endloop + endfacet + facet normal -0.146145 -0.519177 0.842079 + outer loop + vertex -498.801 103.794 354.152 + vertex -496.877 100.928 352.718 + vertex -491.742 102.011 354.277 + endloop + endfacet + facet normal -0.14816 -0.513831 0.845001 + outer loop + vertex -490.094 98.9344 352.695 + vertex -491.742 102.011 354.277 + vertex -496.877 100.928 352.718 + endloop + endfacet + facet normal -0.148495 -0.513945 0.844873 + outer loop + vertex -491.742 102.011 354.277 + vertex -490.094 98.9344 352.695 + vertex -482.91 99.5553 354.336 + endloop + endfacet + facet normal -0.14969 -0.508399 0.848011 + outer loop + vertex -482.91 99.5553 354.336 + vertex -490.094 98.9344 352.695 + vertex -481.18 96.8323 353.009 + endloop + endfacet + facet normal -0.144574 -0.506217 0.850202 + outer loop + vertex -482.91 99.5553 354.336 + vertex -481.18 96.8323 353.009 + vertex -472.29 97.4096 354.864 + endloop + endfacet + facet normal -0.146028 -0.4982 0.854677 + outer loop + vertex -472.29 97.4096 354.864 + vertex -481.18 96.8323 353.009 + vertex -470.692 94.4305 353.4 + endloop + endfacet + facet normal -0.142428 -0.496931 0.856022 + outer loop + vertex -472.29 97.4096 354.864 + vertex -470.692 94.4305 353.4 + vertex -460.551 95.118 355.487 + endloop + endfacet + facet normal -0.14495 -0.482831 0.863634 + outer loop + vertex -460.551 95.118 355.487 + vertex -470.692 94.4305 353.4 + vertex -459.269 92.0964 354.013 + endloop + endfacet + facet normal -0.141028 -0.481772 0.864874 + outer loop + vertex -460.551 95.118 355.487 + vertex -459.269 92.0964 354.013 + vertex -448.793 93.1319 356.298 + endloop + endfacet + facet normal -0.144889 -0.463377 0.874236 + outer loop + vertex -448.793 93.1319 356.298 + vertex -459.269 92.0964 354.013 + vertex -447.81 90.0813 354.844 + endloop + endfacet + facet normal -0.140554 -0.462531 0.875391 + outer loop + vertex -448.793 93.1319 356.298 + vertex -447.81 90.0813 354.844 + vertex -436.542 91.5298 357.418 + endloop + endfacet + facet normal -0.145021 -0.443712 0.884358 + outer loop + vertex -436.542 91.5298 357.418 + vertex -447.81 90.0813 354.844 + vertex -437.288 88.373 355.712 + endloop + endfacet + facet normal -0.146424 -0.443353 0.884307 + outer loop + vertex -436.542 91.5298 357.418 + vertex -437.288 88.373 355.712 + vertex -428.025 89.967 358.045 + endloop + endfacet + facet normal -0.146282 -0.443845 0.884083 + outer loop + vertex -427.899 87.0727 356.613 + vertex -428.025 89.967 358.045 + vertex -437.288 88.373 355.712 + endloop + endfacet + facet normal -0.145615 -0.443866 0.884183 + outer loop + vertex -428.025 89.967 358.045 + vertex -427.899 87.0727 356.613 + vertex -420.483 89.2172 358.911 + endloop + endfacet + facet normal -0.144214 -0.411717 0.899828 + outer loop + vertex -420.87 91.0595 359.692 + vertex -428.025 89.967 358.045 + vertex -420.483 89.2172 358.911 + endloop + endfacet + facet normal -0.147612 -0.41212 0.899093 + outer loop + vertex -420.87 91.0595 359.692 + vertex -420.483 89.2172 358.911 + vertex -414.847 90.8151 360.569 + endloop + endfacet + facet normal -0.145881 -0.404988 0.902609 + outer loop + vertex -426.614 91.5831 358.998 + vertex -428.025 89.967 358.045 + vertex -420.87 91.0595 359.692 + endloop + endfacet + facet normal -0.144514 -0.369942 0.917747 + outer loop + vertex -421.351 91.8696 359.943 + vertex -426.614 91.5831 358.998 + vertex -420.87 91.0595 359.692 + endloop + endfacet + facet normal -0.145273 -0.444673 0.883834 + outer loop + vertex -420.483 89.2172 358.911 + vertex -427.899 87.0727 356.613 + vertex -419.278 86.3568 357.67 + endloop + endfacet + facet normal -0.145726 -0.444803 0.883694 + outer loop + vertex -420.483 89.2172 358.911 + vertex -419.278 86.3568 357.67 + vertex -413.931 88.8888 359.826 + endloop + endfacet + facet normal -0.145908 -0.480241 0.864916 + outer loop + vertex -427.899 87.0727 356.613 + vertex -426.748 83.3652 354.749 + vertex -419.278 86.3568 357.67 + endloop + endfacet + facet normal -0.147547 -0.477407 0.866206 + outer loop + vertex -426.748 83.3652 354.749 + vertex -416.134 82.6529 356.164 + vertex -419.278 86.3568 357.67 + endloop + endfacet + facet normal -0.150892 -0.481114 0.863574 + outer loop + vertex -427.899 87.0727 356.613 + vertex -437.076 84.7158 353.696 + vertex -426.748 83.3652 354.749 + endloop + endfacet + facet normal -0.149735 -0.483925 0.862204 + outer loop + vertex -437.288 88.373 355.712 + vertex -437.076 84.7158 353.696 + vertex -427.899 87.0727 356.613 + endloop + endfacet + facet normal -0.154557 -0.48378 0.861434 + outer loop + vertex -437.288 88.373 355.712 + vertex -447.7 86.4844 352.784 + vertex -437.076 84.7158 353.696 + endloop + endfacet + facet normal -0.150961 -0.494831 0.855776 + outer loop + vertex -447.81 90.0813 354.844 + vertex -447.7 86.4844 352.784 + vertex -437.288 88.373 355.712 + endloop + endfacet + facet normal -0.156384 -0.494537 0.854972 + outer loop + vertex -447.81 90.0813 354.844 + vertex -458.938 88.6157 351.961 + vertex -447.7 86.4844 352.784 + endloop + endfacet + facet normal -0.151446 -0.512665 0.845127 + outer loop + vertex -459.269 92.0964 354.013 + vertex -458.938 88.6157 351.961 + vertex -447.81 90.0813 354.844 + endloop + endfacet + facet normal -0.156219 -0.512621 0.844284 + outer loop + vertex -459.269 92.0964 354.013 + vertex -470.442 91.0963 351.338 + vertex -458.938 88.6157 351.961 + endloop + endfacet + facet normal -0.152687 -0.528126 0.835326 + outer loop + vertex -470.692 94.4305 353.4 + vertex -470.442 91.0963 351.338 + vertex -459.269 92.0964 354.013 + endloop + endfacet + facet normal -0.155573 -0.528045 0.834844 + outer loop + vertex -470.692 94.4305 353.4 + vertex -480.976 93.7721 351.068 + vertex -470.442 91.0963 351.338 + endloop + endfacet + facet normal -0.153872 -0.536523 0.829739 + outer loop + vertex -481.18 96.8323 353.009 + vertex -480.976 93.7721 351.068 + vertex -470.692 94.4305 353.4 + endloop + endfacet + facet normal -0.154684 -0.536493 0.829607 + outer loop + vertex -481.18 96.8323 353.009 + vertex -488.489 96.1217 351.186 + vertex -480.976 93.7721 351.068 + endloop + endfacet + facet normal -0.15521 -0.534356 0.830887 + outer loop + vertex -490.094 98.9344 352.695 + vertex -488.489 96.1217 351.186 + vertex -481.18 96.8323 353.009 + endloop + endfacet + facet normal -0.167571 -0.53863 0.82571 + outer loop + vertex -488.489 96.1217 351.186 + vertex -490.094 98.9344 352.695 + vertex -495.66 96.8442 350.202 + endloop + endfacet + facet normal -0.159416 -0.551835 0.818575 + outer loop + vertex -496.877 100.928 352.718 + vertex -495.66 96.8442 350.202 + vertex -490.094 98.9344 352.695 + endloop + endfacet + facet normal -0.146009 -0.550098 0.822237 + outer loop + vertex -496.877 100.928 352.718 + vertex -500.194 99.4862 351.165 + vertex -495.66 96.8442 350.202 + endloop + endfacet + facet normal -0.153265 -0.539511 0.827911 + outer loop + vertex -500.567 102.824 353.271 + vertex -500.194 99.4862 351.165 + vertex -496.877 100.928 352.718 + endloop + endfacet + facet normal -0.138381 -0.515689 0.845527 + outer loop + vertex -498.801 103.794 354.152 + vertex -500.567 102.824 353.271 + vertex -496.877 100.928 352.718 + endloop + endfacet + facet normal -0.138735 -0.51524 0.845742 + outer loop + vertex -500.785 104.082 354.001 + vertex -500.567 102.824 353.271 + vertex -498.801 103.794 354.152 + endloop + endfacet + facet normal -0.13657 -0.493395 0.859017 + outer loop + vertex -500.785 104.082 354.001 + vertex -498.801 103.794 354.152 + vertex -501.339 104.481 354.143 + endloop + endfacet + facet normal -0.135469 -0.489298 0.861531 + outer loop + vertex -501.306 105.604 354.785 + vertex -501.339 104.481 354.143 + vertex -498.801 103.794 354.152 + endloop + endfacet + facet normal -0.122129 -0.490447 0.862871 + outer loop + vertex -501.339 104.481 354.143 + vertex -501.306 105.604 354.785 + vertex -502.376 105.533 354.594 + endloop + endfacet + facet normal 0.146884 0.508646 -0.848354 + outer loop + vertex -502.376 105.533 354.594 + vertex -501.654 105.096 354.457 + vertex -501.339 104.481 354.143 + endloop + endfacet + facet normal -0.0995988 -0.492631 0.86452 + outer loop + vertex -501.654 105.096 354.457 + vertex -501.567 104.351 354.042 + vertex -501.339 104.481 354.143 + endloop + endfacet + facet normal -0.025751 -0.488313 0.872288 + outer loop + vertex -501.654 105.096 354.457 + vertex -501.765 104.935 354.363 + vertex -501.567 104.351 354.042 + endloop + endfacet + facet normal -0.0177053 -0.486314 0.873605 + outer loop + vertex -501.765 104.935 354.363 + vertex -501.666 103.955 353.82 + vertex -501.567 104.351 354.042 + endloop + endfacet + facet normal -0.128558 -0.490901 0.861678 + outer loop + vertex -501.765 104.935 354.363 + vertex -502.726 104.348 353.886 + vertex -501.666 103.955 353.82 + endloop + endfacet + facet normal -0.133047 -0.50183 0.854673 + outer loop + vertex -502.726 104.348 353.886 + vertex -502.499 103.453 353.395 + vertex -501.666 103.955 353.82 + endloop + endfacet + facet normal -0.155555 -0.504578 0.849237 + outer loop + vertex -502.726 104.348 353.886 + vertex -506.391 103.361 352.628 + vertex -502.499 103.453 353.395 + endloop + endfacet + facet normal -0.148885 -0.551202 0.820981 + outer loop + vertex -502.499 103.453 353.395 + vertex -506.391 103.361 352.628 + vertex -502.386 102.293 352.637 + endloop + endfacet + facet normal -0.14942 -0.518236 0.842084 + outer loop + vertex -505.871 105.129 353.808 + vertex -506.391 103.361 352.628 + vertex -502.726 104.348 353.886 + endloop + endfacet + facet normal -0.142506 -0.488533 0.86083 + outer loop + vertex -505.871 105.129 353.808 + vertex -502.726 104.348 353.886 + vertex -503.218 105.364 354.381 + endloop + endfacet + facet normal -0.143178 -0.485226 0.862587 + outer loop + vertex -505.871 105.129 353.808 + vertex -503.218 105.364 354.381 + vertex -506.654 106.684 354.553 + endloop + endfacet + facet normal -0.146598 -0.486365 0.86137 + outer loop + vertex -506.654 106.684 354.553 + vertex -515.219 106.451 352.964 + vertex -505.871 105.129 353.808 + endloop + endfacet + facet normal -0.142328 -0.518622 0.843074 + outer loop + vertex -506.654 106.684 354.553 + vertex -513.225 108.064 354.293 + vertex -515.219 106.451 352.964 + endloop + endfacet + facet normal -0.14423 -0.516883 0.843818 + outer loop + vertex -513.225 108.064 354.293 + vertex -520.29 109.777 354.134 + vertex -515.219 106.451 352.964 + endloop + endfacet + facet normal -0.146595 -0.519729 0.84166 + outer loop + vertex -531.497 110.856 352.848 + vertex -515.219 106.451 352.964 + vertex -520.29 109.777 354.134 + endloop + endfacet + facet normal -0.146993 -0.536835 0.830784 + outer loop + vertex -520.29 109.777 354.134 + vertex -526.401 111.389 354.095 + vertex -531.497 110.856 352.848 + endloop + endfacet + facet normal -0.149647 -0.526209 0.837084 + outer loop + vertex -526.401 111.389 354.095 + vertex -531.302 112.92 354.181 + vertex -531.497 110.856 352.848 + endloop + endfacet + facet normal -0.14524 -0.52686 0.837451 + outer loop + vertex -531.302 112.92 354.181 + vertex -538.131 114.166 353.78 + vertex -531.497 110.856 352.848 + endloop + endfacet + facet normal -0.151866 -0.537836 0.829258 + outer loop + vertex -549.666 115.847 352.758 + vertex -531.497 110.856 352.848 + vertex -538.131 114.166 353.78 + endloop + endfacet + facet normal -0.150487 -0.522159 0.839466 + outer loop + vertex -538.131 114.166 353.78 + vertex -544.562 116.476 354.064 + vertex -549.666 115.847 352.758 + endloop + endfacet + facet normal -0.147893 -0.531697 0.833922 + outer loop + vertex -544.562 116.476 354.064 + vertex -549.653 117.615 353.888 + vertex -549.666 115.847 352.758 + endloop + endfacet + facet normal -0.153508 -0.531205 0.83322 + outer loop + vertex -549.653 117.615 353.888 + vertex -557.011 119.688 353.854 + vertex -549.666 115.847 352.758 + endloop + endfacet + facet normal -0.149914 -0.525543 0.837455 + outer loop + vertex -567.968 121.272 352.886 + vertex -549.666 115.847 352.758 + vertex -557.011 119.688 353.854 + endloop + endfacet + facet normal -0.149717 -0.5233 0.838893 + outer loop + vertex -557.011 119.688 353.854 + vertex -563.998 121.765 353.903 + vertex -567.968 121.272 352.886 + endloop + endfacet + facet normal -0.151677 -0.516045 0.843025 + outer loop + vertex -563.998 121.765 353.903 + vertex -569.203 123.594 354.086 + vertex -567.968 121.272 352.886 + endloop + endfacet + facet normal -0.146532 -0.514321 0.844987 + outer loop + vertex -569.203 123.594 354.086 + vertex -575.479 125.058 353.888 + vertex -567.968 121.272 352.886 + endloop + endfacet + facet normal -0.15217 -0.52371 0.838195 + outer loop + vertex -582.375 125.995 353.221 + vertex -567.968 121.272 352.886 + vertex -575.479 125.058 353.888 + endloop + endfacet + facet normal -0.151017 -0.508388 0.847783 + outer loop + vertex -575.479 125.058 353.888 + vertex -581.314 127.483 354.303 + vertex -582.375 125.995 353.221 + endloop + endfacet + facet normal -0.1502 -0.508867 0.84764 + outer loop + vertex -581.314 127.483 354.303 + vertex -585.288 128.545 354.236 + vertex -582.375 125.995 353.221 + endloop + endfacet + facet normal -0.180446 -0.534634 0.825594 + outer loop + vertex -585.288 128.545 354.236 + vertex -589.601 129.849 354.138 + vertex -582.375 125.995 353.221 + endloop + endfacet + facet normal -0.160822 -0.5034 0.848955 + outer loop + vertex -589.601 129.849 354.138 + vertex -591.689 126.668 351.856 + vertex -582.375 125.995 353.221 + endloop + endfacet + facet normal -0.161504 -0.503021 0.84905 + outer loop + vertex -589.601 129.849 354.138 + vertex -596.799 131.307 353.633 + vertex -591.689 126.668 351.856 + endloop + endfacet + facet normal -0.14814 -0.491747 0.858044 + outer loop + vertex -597.038 127.851 351.611 + vertex -591.689 126.668 351.856 + vertex -596.799 131.307 353.633 + endloop + endfacet + facet normal -0.151702 -0.434876 0.88762 + outer loop + vertex -589.601 129.849 354.138 + vertex -585.288 128.545 354.236 + vertex -585.032 130.15 355.067 + endloop + endfacet + facet normal -0.132126 -0.438647 0.888893 + outer loop + vertex -585.288 128.545 354.236 + vertex -581.314 127.483 354.303 + vertex -585.032 130.15 355.067 + endloop + endfacet + facet normal -0.129286 -0.43528 0.890964 + outer loop + vertex -576.062 127.275 354.964 + vertex -585.032 130.15 355.067 + vertex -581.314 127.483 354.303 + endloop + endfacet + facet normal -0.12126 -0.410694 0.903674 + outer loop + vertex -576.062 127.275 354.964 + vertex -582.546 131.662 356.087 + vertex -585.032 130.15 355.067 + endloop + endfacet + facet normal -0.131967 -0.396381 0.908552 + outer loop + vertex -585.032 130.15 355.067 + vertex -582.546 131.662 356.087 + vertex -592.089 135.324 356.299 + endloop + endfacet + facet normal -0.153683 -0.422369 0.893301 + outer loop + vertex -589.601 129.849 354.138 + vertex -585.032 130.15 355.067 + vertex -592.089 135.324 356.299 + endloop + endfacet + facet normal -0.148018 -0.420517 0.895129 + outer loop + vertex -596.799 131.307 353.633 + vertex -589.601 129.849 354.138 + vertex -592.089 135.324 356.299 + endloop + endfacet + facet normal -0.116117 -0.404034 0.907344 + outer loop + vertex -573.818 129.628 356.298 + vertex -582.546 131.662 356.087 + vertex -576.062 127.275 354.964 + endloop + endfacet + facet normal -0.115335 -0.404675 0.907158 + outer loop + vertex -564.325 123.789 354.9 + vertex -573.818 129.628 356.298 + vertex -576.062 127.275 354.964 + endloop + endfacet + facet normal -0.129457 -0.451767 0.882693 + outer loop + vertex -564.325 123.789 354.9 + vertex -576.062 127.275 354.964 + vertex -569.203 123.594 354.086 + endloop + endfacet + facet normal -0.115833 -0.405392 0.906775 + outer loop + vertex -562.169 126.446 356.364 + vertex -573.818 129.628 356.298 + vertex -564.325 123.789 354.9 + endloop + endfacet + facet normal -0.116891 -0.404642 0.906974 + outer loop + vertex -551.516 120.115 354.912 + vertex -562.169 126.446 356.364 + vertex -564.325 123.789 354.9 + endloop + endfacet + facet normal -0.133138 -0.461384 0.877154 + outer loop + vertex -551.516 120.115 354.912 + vertex -564.325 123.789 354.9 + vertex -557.011 119.688 353.854 + endloop + endfacet + facet normal -0.117537 -0.405611 0.906457 + outer loop + vertex -549.667 122.88 356.389 + vertex -562.169 126.446 356.364 + vertex -551.516 120.115 354.912 + endloop + endfacet + facet normal -0.117199 -0.405812 0.906411 + outer loop + vertex -538.994 116.649 354.98 + vertex -549.667 122.88 356.389 + vertex -551.516 120.115 354.912 + endloop + endfacet + facet normal -0.130677 -0.455004 0.880849 + outer loop + vertex -538.994 116.649 354.98 + vertex -551.516 120.115 354.912 + vertex -544.562 116.476 354.064 + endloop + endfacet + facet normal -0.115554 -0.403296 0.907744 + outer loop + vertex -537.227 119.398 356.426 + vertex -549.667 122.88 356.389 + vertex -538.994 116.649 354.98 + endloop + endfacet + facet normal -0.115314 -0.403435 0.907713 + outer loop + vertex -526.857 113.431 355.091 + vertex -537.227 119.398 356.426 + vertex -538.994 116.649 354.98 + endloop + endfacet + facet normal -0.128435 -0.453827 0.881785 + outer loop + vertex -526.857 113.431 355.091 + vertex -538.994 116.649 354.98 + vertex -531.302 112.92 354.181 + endloop + endfacet + facet normal -0.113035 -0.39989 0.909567 + outer loop + vertex -525.026 116.113 356.498 + vertex -537.227 119.398 356.426 + vertex -526.857 113.431 355.091 + endloop + endfacet + facet normal -0.113766 -0.399445 0.909671 + outer loop + vertex -514.714 110.378 355.269 + vertex -525.026 116.113 356.498 + vertex -526.857 113.431 355.091 + endloop + endfacet + facet normal -0.128922 -0.461594 0.877673 + outer loop + vertex -514.714 110.378 355.269 + vertex -526.857 113.431 355.091 + vertex -520.29 109.777 354.134 + endloop + endfacet + facet normal -0.110134 -0.393559 0.912678 + outer loop + vertex -513.129 113.069 356.621 + vertex -525.026 116.113 356.498 + vertex -514.714 110.378 355.269 + endloop + endfacet + facet normal -0.113523 -0.391745 0.913043 + outer loop + vertex -503.161 107.735 355.572 + vertex -513.129 113.069 356.621 + vertex -514.714 110.378 355.269 + endloop + endfacet + facet normal -0.124943 -0.444648 0.886948 + outer loop + vertex -503.161 107.735 355.572 + vertex -514.714 110.378 355.269 + vertex -506.654 106.684 354.553 + endloop + endfacet + facet normal -0.127355 -0.439019 0.889406 + outer loop + vertex -506.654 106.684 354.553 + vertex -501.306 105.604 354.785 + vertex -503.161 107.735 355.572 + endloop + endfacet + facet normal -0.127101 -0.438843 0.889529 + outer loop + vertex -501.306 105.604 354.785 + vertex -496.186 104.621 355.032 + vertex -503.161 107.735 355.572 + endloop + endfacet + facet normal -0.123352 -0.431185 0.893792 + outer loop + vertex -491.749 105.032 355.843 + vertex -503.161 107.735 355.572 + vertex -496.186 104.621 355.032 + endloop + endfacet + facet normal -0.111578 -0.378976 0.918655 + outer loop + vertex -491.749 105.032 355.843 + vertex -501.375 110.13 356.777 + vertex -503.161 107.735 355.572 + endloop + endfacet + facet normal -0.105825 -0.36898 0.923393 + outer loop + vertex -489.237 107.173 356.986 + vertex -501.375 110.13 356.777 + vertex -491.749 105.032 355.843 + endloop + endfacet + facet normal -0.109672 -0.365058 0.924502 + outer loop + vertex -479.004 102.042 356.174 + vertex -489.237 107.173 356.986 + vertex -491.749 105.032 355.843 + endloop + endfacet + facet normal -0.122757 -0.423841 0.897379 + outer loop + vertex -479.004 102.042 356.174 + vertex -491.749 105.032 355.843 + vertex -485.27 101.882 355.241 + endloop + endfacet + facet normal -0.104696 -0.355794 0.928681 + outer loop + vertex -476.439 104.345 357.346 + vertex -489.237 107.173 356.986 + vertex -479.004 102.042 356.174 + endloop + endfacet + facet normal -0.110065 -0.350518 0.930066 + outer loop + vertex -465.772 99.3375 356.721 + vertex -476.439 104.345 357.346 + vertex -479.004 102.042 356.174 + endloop + endfacet + facet normal -0.119004 -0.398405 0.909457 + outer loop + vertex -465.772 99.3375 356.721 + vertex -479.004 102.042 356.174 + vertex -471.228 98.9785 355.85 + endloop + endfacet + facet normal -0.105699 -0.341689 0.93385 + outer loop + vertex -462.543 101.594 357.912 + vertex -476.439 104.345 357.346 + vertex -465.772 99.3375 356.721 + endloop + endfacet + facet normal -0.112319 -0.333389 0.936075 + outer loop + vertex -451.69 96.7919 357.504 + vertex -462.543 101.594 357.912 + vertex -465.772 99.3375 356.721 + endloop + endfacet + facet normal -0.120715 -0.386522 0.914346 + outer loop + vertex -451.69 96.7919 357.504 + vertex -465.772 99.3375 356.721 + vertex -458.563 96.5551 356.496 + endloop + endfacet + facet normal -0.112311 -0.333373 0.936082 + outer loop + vertex -453.632 98.8717 358.011 + vertex -462.543 101.594 357.912 + vertex -451.69 96.7919 357.504 + endloop + endfacet + facet normal -0.115259 -0.335824 0.934846 + outer loop + vertex -453.632 98.8717 358.011 + vertex -451.69 96.7919 357.504 + vertex -447.518 97.7796 358.373 + endloop + endfacet + facet normal -0.111841 -0.314059 0.942793 + outer loop + vertex -447.518 97.7796 358.373 + vertex -453.999 100.736 358.589 + vertex -453.632 98.8717 358.011 + endloop + endfacet + facet normal -0.112532 -0.315531 0.942219 + outer loop + vertex -446.566 99.6801 359.123 + vertex -453.999 100.736 358.589 + vertex -447.518 97.7796 358.373 + endloop + endfacet + facet normal -0.118739 -0.312519 0.942461 + outer loop + vertex -440.116 96.9526 359.031 + vertex -446.566 99.6801 359.123 + vertex -447.518 97.7796 358.373 + endloop + endfacet + facet normal -0.119831 -0.326057 0.937725 + outer loop + vertex -440.116 96.9526 359.031 + vertex -447.518 97.7796 358.373 + vertex -440.915 95.4376 358.402 + endloop + endfacet + facet normal -0.127104 -0.322357 0.938046 + outer loop + vertex -433.62 94.7485 359.154 + vertex -440.116 96.9526 359.031 + vertex -440.915 95.4376 358.402 + endloop + endfacet + facet normal -0.128231 -0.342134 0.930861 + outer loop + vertex -433.62 94.7485 359.154 + vertex -440.915 95.4376 358.402 + vertex -433.824 93.6775 358.732 + endloop + endfacet + facet normal -0.136915 -0.340263 0.930309 + outer loop + vertex -427.401 93.2136 359.508 + vertex -433.62 94.7485 359.154 + vertex -433.824 93.6775 358.732 + endloop + endfacet + facet normal -0.137408 -0.359081 0.923136 + outer loop + vertex -427.401 93.2136 359.508 + vertex -433.824 93.6775 358.732 + vertex -428.155 92.6702 359.184 + endloop + endfacet + facet normal -0.143875 -0.351295 0.925144 + outer loop + vertex -422.093 92.4204 360.032 + vertex -427.401 93.2136 359.508 + vertex -428.155 92.6702 359.184 + endloop + endfacet + facet normal -0.143611 -0.371022 0.917452 + outer loop + vertex -422.093 92.4204 360.032 + vertex -428.155 92.6702 359.184 + vertex -423.738 92.1847 359.679 + endloop + endfacet + facet normal -0.145891 -0.369775 0.917596 + outer loop + vertex -421.105 93.0627 360.448 + vertex -427.401 93.2136 359.508 + vertex -422.093 92.4204 360.032 + endloop + endfacet + facet normal -0.136468 -0.352614 0.925764 + outer loop + vertex -428.155 92.6702 359.184 + vertex -433.824 93.6775 358.732 + vertex -433.947 93.0864 358.489 + endloop + endfacet + facet normal -0.136718 -0.36263 0.92185 + outer loop + vertex -428.155 92.6702 359.184 + vertex -433.947 93.0864 358.489 + vertex -429.653 92.2851 358.811 + endloop + endfacet + facet normal -0.129373 -0.354249 0.926159 + outer loop + vertex -433.824 93.6775 358.732 + vertex -440.454 94.1758 357.997 + vertex -433.947 93.0864 358.489 + endloop + endfacet + facet normal -0.133259 -0.382897 0.914129 + outer loop + vertex -433.947 93.0864 358.489 + vertex -440.454 94.1758 357.997 + vertex -437.439 93.3147 358.076 + endloop + endfacet + facet normal -0.133143 -0.37569 0.917132 + outer loop + vertex -433.947 93.0864 358.489 + vertex -437.439 93.3147 358.076 + vertex -435.448 92.7418 358.13 + endloop + endfacet + facet normal -0.132102 -0.37867 0.916056 + outer loop + vertex -437.439 93.3147 358.076 + vertex -440.454 94.1758 357.997 + vertex -440.629 93.2573 357.592 + endloop + endfacet + facet normal -0.138645 -0.347989 0.92719 + outer loop + vertex -427.211 94.3888 359.977 + vertex -433.62 94.7485 359.154 + vertex -427.401 93.2136 359.508 + endloop + endfacet + facet normal -0.138447 -0.326969 0.934839 + outer loop + vertex -427.211 94.3888 359.977 + vertex -433.591 96.4791 359.764 + vertex -433.62 94.7485 359.154 + endloop + endfacet + facet normal -0.1291 -0.345917 0.929341 + outer loop + vertex -433.824 93.6775 358.732 + vertex -440.915 95.4376 358.402 + vertex -440.454 94.1758 357.997 + endloop + endfacet + facet normal -0.120852 -0.343542 0.931329 + outer loop + vertex -440.454 94.1758 357.997 + vertex -440.915 95.4376 358.402 + vertex -451.69 96.7919 357.504 + endloop + endfacet + facet normal -0.12877 -0.380481 0.91578 + outer loop + vertex -440.454 94.1758 357.997 + vertex -451.69 96.7919 357.504 + vertex -446.531 94.4376 357.251 + endloop + endfacet + facet normal -0.128824 -0.327541 0.936014 + outer loop + vertex -433.591 96.4791 359.764 + vertex -440.116 96.9526 359.031 + vertex -433.62 94.7485 359.154 + endloop + endfacet + facet normal -0.128236 -0.310192 0.941985 + outer loop + vertex -433.591 96.4791 359.764 + vertex -440.003 99.1542 359.772 + vertex -440.116 96.9526 359.031 + endloop + endfacet + facet normal -0.12732 -0.307999 0.942829 + outer loop + vertex -433.923 98.815 360.482 + vertex -440.003 99.1542 359.772 + vertex -433.591 96.4791 359.764 + endloop + endfacet + facet normal -0.139586 -0.309094 0.940732 + outer loop + vertex -427.52 96.2768 360.598 + vertex -433.923 98.815 360.482 + vertex -433.591 96.4791 359.764 + endloop + endfacet + facet normal -0.138674 -0.306751 0.941633 + outer loop + vertex -428.112 98.7009 361.3 + vertex -433.923 98.815 360.482 + vertex -427.52 96.2768 360.598 + endloop + endfacet + facet normal -0.139236 -0.283119 0.948924 + outer loop + vertex -428.112 98.7009 361.3 + vertex -434.403 101.511 361.216 + vertex -433.923 98.815 360.482 + endloop + endfacet + facet normal -0.124101 -0.281154 0.951605 + outer loop + vertex -434.403 101.511 361.216 + vertex -440.289 101.792 360.531 + vertex -433.923 98.815 360.482 + endloop + endfacet + facet normal -0.123718 -0.255469 0.958869 + outer loop + vertex -434.403 101.511 361.216 + vertex -440.698 104.635 361.236 + vertex -440.289 101.792 360.531 + endloop + endfacet + facet normal -0.108688 -0.253866 0.961113 + outer loop + vertex -440.698 104.635 361.236 + vertex -446.855 105.005 360.637 + vertex -440.289 101.792 360.531 + endloop + endfacet + facet normal -0.113455 -0.263504 0.957963 + outer loop + vertex -440.289 101.792 360.531 + vertex -446.855 105.005 360.637 + vertex -446.556 102.198 359.901 + endloop + endfacet + facet normal -0.114259 -0.286328 0.951295 + outer loop + vertex -440.289 101.792 360.531 + vertex -446.556 102.198 359.901 + vertex -440.003 99.1542 359.772 + endloop + endfacet + facet normal -0.11723 -0.292627 0.949013 + outer loop + vertex -440.003 99.1542 359.772 + vertex -446.556 102.198 359.901 + vertex -446.566 99.6801 359.123 + endloop + endfacet + facet normal -0.108619 -0.292947 0.949939 + outer loop + vertex -446.556 102.198 359.901 + vertex -452.574 102.618 359.342 + vertex -446.566 99.6801 359.123 + endloop + endfacet + facet normal -0.10766 -0.270129 0.956786 + outer loop + vertex -446.556 102.198 359.901 + vertex -453.99 105.709 360.056 + vertex -452.574 102.618 359.342 + endloop + endfacet + facet normal -0.09948 -0.266802 0.958603 + outer loop + vertex -452.574 102.618 359.342 + vertex -453.99 105.709 360.056 + vertex -462.482 105.87 359.219 + endloop + endfacet + facet normal -0.109244 -0.296925 0.948631 + outer loop + vertex -452.574 102.618 359.342 + vertex -462.482 105.87 359.219 + vertex -453.999 100.736 358.589 + endloop + endfacet + facet normal -0.104469 -0.289388 0.951494 + outer loop + vertex -462.482 105.87 359.219 + vertex -462.543 101.594 357.912 + vertex -453.999 100.736 358.589 + endloop + endfacet + facet normal -0.0934413 -0.289854 0.952498 + outer loop + vertex -462.482 105.87 359.219 + vertex -475.722 108.11 358.602 + vertex -462.543 101.594 357.912 + endloop + endfacet + facet normal -0.0977241 -0.298197 0.949489 + outer loop + vertex -462.543 101.594 357.912 + vertex -475.722 108.11 358.602 + vertex -476.439 104.345 357.346 + endloop + endfacet + facet normal -0.089955 -0.299768 0.949762 + outer loop + vertex -475.722 108.11 358.602 + vertex -488.466 110.743 358.226 + vertex -476.439 104.345 357.346 + endloop + endfacet + facet normal -0.0946857 -0.308224 0.94659 + outer loop + vertex -476.439 104.345 357.346 + vertex -488.466 110.743 358.226 + vertex -489.237 107.173 356.986 + endloop + endfacet + facet normal -0.0888381 -0.309534 0.946729 + outer loop + vertex -488.466 110.743 358.226 + vertex -500.662 113.658 358.034 + vertex -489.237 107.173 356.986 + endloop + endfacet + facet normal -0.0936273 -0.317472 0.943634 + outer loop + vertex -489.237 107.173 356.986 + vertex -500.662 113.658 358.034 + vertex -501.375 110.13 356.777 + endloop + endfacet + facet normal -0.0892533 -0.318397 0.943746 + outer loop + vertex -500.662 113.658 358.034 + vertex -512.605 116.725 357.94 + vertex -501.375 110.13 356.777 + endloop + endfacet + facet normal -0.0939418 -0.32585 0.940743 + outer loop + vertex -501.375 110.13 356.777 + vertex -512.605 116.725 357.94 + vertex -513.129 113.069 356.621 + endloop + endfacet + facet normal -0.0906002 -0.326381 0.940886 + outer loop + vertex -512.605 116.725 357.94 + vertex -524.594 119.881 357.88 + vertex -513.129 113.069 356.621 + endloop + endfacet + facet normal -0.0949442 -0.333172 0.938073 + outer loop + vertex -513.129 113.069 356.621 + vertex -524.594 119.881 357.88 + vertex -525.026 116.113 356.498 + endloop + endfacet + facet normal -0.0932226 -0.333403 0.938164 + outer loop + vertex -524.594 119.881 357.88 + vertex -536.831 123.205 357.845 + vertex -525.026 116.113 356.498 + endloop + endfacet + facet normal -0.0967599 -0.338852 0.935851 + outer loop + vertex -525.026 116.113 356.498 + vertex -536.831 123.205 357.845 + vertex -537.227 119.398 356.426 + endloop + endfacet + facet normal -0.0967093 -0.338858 0.935854 + outer loop + vertex -536.831 123.205 357.845 + vertex -549.322 126.754 357.839 + vertex -537.227 119.398 356.426 + endloop + endfacet + facet normal -0.0982523 -0.341201 0.934841 + outer loop + vertex -537.227 119.398 356.426 + vertex -549.322 126.754 357.839 + vertex -549.667 122.88 356.389 + endloop + endfacet + facet normal -0.0983068 -0.341194 0.934838 + outer loop + vertex -549.322 126.754 357.839 + vertex -561.754 130.336 357.839 + vertex -549.667 122.88 356.389 + endloop + endfacet + facet normal -0.0998961 -0.343569 0.933799 + outer loop + vertex -549.667 122.88 356.389 + vertex -561.754 130.336 357.839 + vertex -562.169 126.446 356.364 + endloop + endfacet + facet normal -0.098358 -0.343767 0.93389 + outer loop + vertex -561.754 130.336 357.839 + vertex -573.487 133.513 357.773 + vertex -562.169 126.446 356.364 + endloop + endfacet + facet normal -0.0996813 -0.345715 0.93303 + outer loop + vertex -562.169 126.446 356.364 + vertex -573.487 133.513 357.773 + vertex -573.818 129.628 356.298 + endloop + endfacet + facet normal -0.0997442 -0.345708 0.933026 + outer loop + vertex -573.487 133.513 357.773 + vertex -583.606 135.586 357.46 + vertex -573.818 129.628 356.298 + endloop + endfacet + facet normal -0.104856 -0.353431 0.929565 + outer loop + vertex -573.818 129.628 356.298 + vertex -583.606 135.586 357.46 + vertex -582.546 131.662 356.087 + endloop + endfacet + facet normal -0.115928 -0.355663 0.927397 + outer loop + vertex -582.546 131.662 356.087 + vertex -583.606 135.586 357.46 + vertex -592.089 135.324 356.299 + endloop + endfacet + facet normal -0.0996817 -0.23698 0.966387 + outer loop + vertex -462.828 111.396 360.539 + vertex -462.482 105.87 359.219 + vertex -453.99 105.709 360.056 + endloop + endfacet + facet normal -0.100126 -0.237653 0.966176 + outer loop + vertex -453.041 108.209 360.769 + vertex -462.828 111.396 360.539 + vertex -453.99 105.709 360.056 + endloop + endfacet + facet normal -0.102168 -0.236871 0.966154 + outer loop + vertex -446.855 105.005 360.637 + vertex -453.041 108.209 360.769 + vertex -453.99 105.709 360.056 + endloop + endfacet + facet normal -0.0961222 -0.225338 0.969527 + outer loop + vertex -447.205 107.915 361.279 + vertex -453.041 108.209 360.769 + vertex -446.855 105.005 360.637 + endloop + endfacet + facet normal -0.0952822 -0.198233 0.975513 + outer loop + vertex -447.205 107.915 361.279 + vertex -454.523 111.576 361.308 + vertex -453.041 108.209 360.769 + endloop + endfacet + facet normal -0.0904092 -0.18851 0.977901 + outer loop + vertex -447.536 110.903 361.824 + vertex -454.523 111.576 361.308 + vertex -447.205 107.915 361.279 + endloop + endfacet + facet normal -0.10238 -0.189582 0.976513 + outer loop + vertex -441.109 107.564 361.85 + vertex -447.536 110.903 361.824 + vertex -447.205 107.915 361.279 + endloop + endfacet + facet normal -0.103448 -0.217973 0.970457 + outer loop + vertex -441.109 107.564 361.85 + vertex -447.205 107.915 361.279 + vertex -440.698 104.635 361.236 + endloop + endfacet + facet normal -0.12014 -0.219827 0.968113 + outer loop + vertex -434.883 104.378 361.899 + vertex -441.109 107.564 361.85 + vertex -440.698 104.635 361.236 + endloop + endfacet + facet normal -0.11848 -0.216569 0.969051 + outer loop + vertex -435.371 107.365 362.507 + vertex -441.109 107.564 361.85 + vertex -434.883 104.378 361.899 + endloop + endfacet + facet normal -0.137994 -0.219116 0.965891 + outer loop + vertex -429.336 104.376 362.691 + vertex -435.371 107.365 362.507 + vertex -434.883 104.378 361.899 + endloop + endfacet + facet normal -0.13699 -0.248951 0.958779 + outer loop + vertex -429.336 104.376 362.691 + vertex -434.883 104.378 361.899 + vertex -428.744 101.444 362.015 + endloop + endfacet + facet normal -0.153744 -0.251593 0.955544 + outer loop + vertex -423.398 101.763 362.959 + vertex -429.336 104.376 362.691 + vertex -428.744 101.444 362.015 + endloop + endfacet + facet normal -0.150918 -0.278263 0.948575 + outer loop + vertex -423.398 101.763 362.959 + vertex -428.744 101.444 362.015 + vertex -422.503 98.9581 362.278 + endloop + endfacet + facet normal -0.164341 -0.281753 0.945308 + outer loop + vertex -417.675 99.6709 363.33 + vertex -423.398 101.763 362.959 + vertex -422.503 98.9581 362.278 + endloop + endfacet + facet normal -0.159778 -0.303739 0.939262 + outer loop + vertex -417.675 99.6709 363.33 + vertex -422.503 98.9581 362.278 + vertex -415.842 97.0094 362.781 + endloop + endfacet + facet normal -0.17291 -0.311758 0.934296 + outer loop + vertex -417.675 99.6709 363.33 + vertex -415.842 97.0094 362.781 + vertex -412.848 98.3227 363.773 + endloop + endfacet + facet normal -0.170274 -0.301004 0.938298 + outer loop + vertex -413.965 100.568 364.291 + vertex -417.675 99.6709 363.33 + vertex -412.848 98.3227 363.773 + endloop + endfacet + facet normal -0.180369 -0.305269 0.935028 + outer loop + vertex -410.479 99.2473 364.532 + vertex -413.965 100.568 364.291 + vertex -412.848 98.3227 363.773 + endloop + endfacet + facet normal -0.179292 -0.302208 0.936229 + outer loop + vertex -411.314 101.275 365.027 + vertex -413.965 100.568 364.291 + vertex -410.479 99.2473 364.532 + endloop + endfacet + facet normal -0.185652 -0.283246 0.940906 + outer loop + vertex -413.965 100.568 364.291 + vertex -411.314 101.275 365.027 + vertex -414.862 103.161 364.895 + endloop + endfacet + facet normal -0.175031 -0.280252 0.943834 + outer loop + vertex -414.862 103.161 364.895 + vertex -418.674 102.416 363.967 + vertex -413.965 100.568 364.291 + endloop + endfacet + facet normal -0.180859 -0.257202 0.949282 + outer loop + vertex -414.862 103.161 364.895 + vertex -419.557 105.395 364.605 + vertex -418.674 102.416 363.967 + endloop + endfacet + facet normal -0.168228 -0.254133 0.952426 + outer loop + vertex -419.557 105.395 364.605 + vertex -424.137 104.732 363.62 + vertex -418.674 102.416 363.967 + endloop + endfacet + facet normal -0.168126 -0.25388 0.952512 + outer loop + vertex -418.674 102.416 363.967 + vertex -424.137 104.732 363.62 + vertex -423.398 101.763 362.959 + endloop + endfacet + facet normal -0.173426 -0.226996 0.95833 + outer loop + vertex -419.557 105.395 364.605 + vertex -424.891 107.844 364.22 + vertex -424.137 104.732 363.62 + endloop + endfacet + facet normal -0.157302 -0.223768 0.961865 + outer loop + vertex -424.891 107.844 364.22 + vertex -429.941 107.435 363.299 + vertex -424.137 104.732 363.62 + endloop + endfacet + facet normal -0.156616 -0.22224 0.962331 + outer loop + vertex -424.137 104.732 363.62 + vertex -429.941 107.435 363.299 + vertex -429.336 104.376 362.691 + endloop + endfacet + facet normal -0.160784 -0.194025 0.967731 + outer loop + vertex -424.891 107.844 364.22 + vertex -430.577 110.588 363.826 + vertex -429.941 107.435 363.299 + endloop + endfacet + facet normal -0.14025 -0.19053 0.971611 + outer loop + vertex -430.577 110.588 363.826 + vertex -435.885 110.453 363.033 + vertex -429.941 107.435 363.299 + endloop + endfacet + facet normal -0.139375 -0.188765 0.972082 + outer loop + vertex -429.941 107.435 363.299 + vertex -435.885 110.453 363.033 + vertex -435.371 107.365 362.507 + endloop + endfacet + facet normal -0.117894 -0.185771 0.975495 + outer loop + vertex -435.885 110.453 363.033 + vertex -441.517 110.588 362.378 + vertex -435.371 107.365 362.507 + endloop + endfacet + facet normal -0.11779 -0.157074 0.980537 + outer loop + vertex -435.885 110.453 363.033 + vertex -441.91 113.731 362.834 + vertex -441.517 110.588 362.378 + endloop + endfacet + facet normal -0.097412 -0.154897 0.983116 + outer loop + vertex -441.91 113.731 362.834 + vertex -447.81 114.003 362.293 + vertex -441.517 110.588 362.378 + endloop + endfacet + facet normal -0.0986147 -0.157126 0.982643 + outer loop + vertex -441.517 110.588 362.378 + vertex -447.81 114.003 362.293 + vertex -447.536 110.903 361.824 + endloop + endfacet + facet normal -0.0839381 -0.156058 0.984175 + outer loop + vertex -447.81 114.003 362.293 + vertex -453.519 114.249 361.845 + vertex -447.536 110.903 361.824 + endloop + endfacet + facet normal -0.0832532 -0.134241 0.987445 + outer loop + vertex -447.81 114.003 362.293 + vertex -454.798 117.852 362.227 + vertex -453.519 114.249 361.845 + endloop + endfacet + facet normal -0.071274 -0.130144 0.98893 + outer loop + vertex -453.519 114.249 361.845 + vertex -454.798 117.852 362.227 + vertex -463.054 117.539 361.591 + endloop + endfacet + facet normal -0.0834373 -0.165886 0.982609 + outer loop + vertex -453.519 114.249 361.845 + vertex -463.054 117.539 361.591 + vertex -454.523 111.576 361.308 + endloop + endfacet + facet normal -0.0872437 -0.171272 0.981353 + outer loop + vertex -463.054 117.539 361.591 + vertex -462.828 111.396 360.539 + vertex -454.523 111.576 361.308 + endloop + endfacet + facet normal -0.064395 -0.170748 0.983208 + outer loop + vertex -463.054 117.539 361.591 + vertex -476.137 119.248 361.03 + vertex -462.828 111.396 360.539 + endloop + endfacet + facet normal -0.0743962 -0.187465 0.97945 + outer loop + vertex -462.828 111.396 360.539 + vertex -476.137 119.248 361.03 + vertex -475.943 113.269 359.901 + endloop + endfacet + facet normal -0.058875 -0.187171 0.980561 + outer loop + vertex -476.137 119.248 361.03 + vertex -488.814 121.497 360.699 + vertex -475.943 113.269 359.901 + endloop + endfacet + facet normal -0.0667884 -0.199269 0.977666 + outer loop + vertex -475.943 113.269 359.901 + vertex -488.814 121.497 360.699 + vertex -488.571 115.651 359.524 + endloop + endfacet + facet normal -0.0568815 -0.198994 0.978349 + outer loop + vertex -488.814 121.497 360.699 + vertex -500.907 124.245 360.554 + vertex -488.571 115.651 359.524 + endloop + endfacet + facet normal -0.0624955 -0.206817 0.976382 + outer loop + vertex -488.571 115.651 359.524 + vertex -500.907 124.245 360.554 + vertex -500.689 118.484 359.348 + endloop + endfacet + facet normal -0.0568053 -0.20668 0.976758 + outer loop + vertex -500.907 124.245 360.554 + vertex -512.732 127.304 360.514 + vertex -500.689 118.484 359.348 + endloop + endfacet + facet normal -0.059079 -0.209682 0.975983 + outer loop + vertex -500.689 118.484 359.348 + vertex -512.732 127.304 360.514 + vertex -512.595 121.534 359.283 + endloop + endfacet + facet normal -0.0569313 -0.209659 0.976116 + outer loop + vertex -512.732 127.304 360.514 + vertex -524.683 130.506 360.505 + vertex -512.595 121.534 359.283 + endloop + endfacet + facet normal -0.0587277 -0.211996 0.975504 + outer loop + vertex -512.595 121.534 359.283 + vertex -524.683 130.506 360.505 + vertex -524.61 124.734 359.255 + endloop + endfacet + facet normal -0.0583141 -0.211996 0.975529 + outer loop + vertex -524.683 130.506 360.505 + vertex -536.954 133.842 360.496 + vertex -524.61 124.734 359.255 + endloop + endfacet + facet normal -0.0597332 -0.213853 0.975038 + outer loop + vertex -524.61 124.734 359.255 + vertex -536.954 133.842 360.496 + vertex -536.901 128.09 359.238 + endloop + endfacet + facet normal -0.060627 -0.213849 0.974984 + outer loop + vertex -536.954 133.842 360.496 + vertex -549.481 137.358 360.488 + vertex -536.901 128.09 359.238 + endloop + endfacet + facet normal -0.0609465 -0.214268 0.974872 + outer loop + vertex -536.901 128.09 359.238 + vertex -549.481 137.358 360.488 + vertex -549.42 131.642 359.236 + endloop + endfacet + facet normal -0.0615446 -0.214266 0.974834 + outer loop + vertex -549.481 137.358 360.488 + vertex -561.909 140.934 360.49 + vertex -549.42 131.642 359.236 + endloop + endfacet + facet normal -0.0602964 -0.212647 0.975267 + outer loop + vertex -549.42 131.642 359.236 + vertex -561.909 140.934 360.49 + vertex -561.864 135.233 359.249 + endloop + endfacet + facet normal -0.060252 -0.212647 0.97527 + outer loop + vertex -561.909 140.934 360.49 + vertex -573.66 144.211 360.478 + vertex -561.864 135.233 359.249 + endloop + endfacet + facet normal -0.0611842 -0.213828 0.974953 + outer loop + vertex -561.864 135.233 359.249 + vertex -573.66 144.211 360.478 + vertex -573.627 138.486 359.225 + endloop + endfacet + facet normal -0.0592023 -0.213843 0.975072 + outer loop + vertex -573.66 144.211 360.478 + vertex -584.235 146.776 360.399 + vertex -573.627 138.486 359.225 + endloop + endfacet + facet normal -0.0651831 -0.221209 0.973046 + outer loop + vertex -573.627 138.486 359.225 + vertex -584.235 146.776 360.399 + vertex -584.021 140.848 359.065 + endloop + endfacet + facet normal -0.0568116 -0.221034 0.97361 + outer loop + vertex -584.021 140.848 359.065 + vertex -584.235 146.776 360.399 + vertex -593.217 148.147 360.186 + endloop + endfacet + facet normal -0.0794513 -0.248298 0.96542 + outer loop + vertex -593.217 148.147 360.186 + vertex -592.865 142.086 358.656 + vertex -584.021 140.848 359.065 + endloop + endfacet + facet normal -0.0721144 -0.112308 0.991053 + outer loop + vertex -462.967 124.178 362.349 + vertex -463.054 117.539 361.591 + vertex -454.798 117.852 362.227 + endloop + endfacet + facet normal -0.0707574 -0.110562 0.991347 + outer loop + vertex -453.585 120.645 362.625 + vertex -462.967 124.178 362.349 + vertex -454.798 117.852 362.227 + endloop + endfacet + facet normal -0.0785273 -0.107156 0.991136 + outer loop + vertex -447.995 117.196 362.695 + vertex -453.585 120.645 362.625 + vertex -454.798 117.852 362.227 + endloop + endfacet + facet normal -0.0770558 -0.104764 0.991507 + outer loop + vertex -448.059 120.429 363.031 + vertex -453.585 120.645 362.625 + vertex -447.995 117.196 362.695 + endloop + endfacet + facet normal -0.0952776 -0.104956 0.989902 + outer loop + vertex -442.233 116.968 363.225 + vertex -448.059 120.429 363.031 + vertex -447.995 117.196 362.695 + endloop + endfacet + facet normal -0.0959528 -0.128747 0.987024 + outer loop + vertex -442.233 116.968 363.225 + vertex -447.995 117.196 362.695 + vertex -441.91 113.731 362.834 + endloop + endfacet + facet normal -0.118307 -0.130654 0.984344 + outer loop + vertex -436.4 113.65 363.486 + vertex -442.233 116.968 363.225 + vertex -441.91 113.731 362.834 + endloop + endfacet + facet normal -0.118724 -0.131398 0.984195 + outer loop + vertex -436.842 116.921 363.869 + vertex -442.233 116.968 363.225 + vertex -436.4 113.65 363.486 + endloop + endfacet + facet normal -0.143892 -0.134357 0.98043 + outer loop + vertex -431.184 113.812 364.274 + vertex -436.842 116.921 363.869 + vertex -436.4 113.65 363.486 + endloop + endfacet + facet normal -0.142412 -0.162459 0.976384 + outer loop + vertex -431.184 113.812 364.274 + vertex -436.4 113.65 363.486 + vertex -430.577 110.588 363.826 + endloop + endfacet + facet normal -0.165318 -0.166179 0.972139 + outer loop + vertex -425.654 111.038 364.74 + vertex -431.184 113.812 364.274 + vertex -430.577 110.588 363.826 + endloop + endfacet + facet normal -0.165609 -0.166786 0.971986 + outer loop + vertex -426.36 114.294 365.178 + vertex -431.184 113.812 364.274 + vertex -425.654 111.038 364.74 + endloop + endfacet + facet normal -0.186785 -0.170765 0.967445 + outer loop + vertex -421.43 111.833 365.696 + vertex -426.36 114.294 365.178 + vertex -425.654 111.038 364.74 + endloop + endfacet + facet normal -0.169103 -0.138941 0.975756 + outer loop + vertex -426.36 114.294 365.178 + vertex -431.712 117.114 364.652 + vertex -431.184 113.812 364.274 + endloop + endfacet + facet normal -0.168509 -0.137764 0.976026 + outer loop + vertex -426.956 117.611 365.544 + vertex -431.712 117.114 364.652 + vertex -426.36 114.294 365.178 + endloop + endfacet + facet normal -0.192134 -0.141467 0.971119 + outer loop + vertex -422.241 115.135 366.116 + vertex -426.956 117.611 365.544 + vertex -426.36 114.294 365.178 + endloop + endfacet + facet normal -0.171652 -0.112542 0.978708 + outer loop + vertex -426.956 117.611 365.544 + vertex -432.128 120.462 364.964 + vertex -431.712 117.114 364.652 + endloop + endfacet + facet normal -0.145977 -0.109766 0.98318 + outer loop + vertex -432.128 120.462 364.964 + vertex -437.184 120.252 364.19 + vertex -431.712 117.114 364.652 + endloop + endfacet + facet normal -0.145941 -0.109701 0.983192 + outer loop + vertex -431.712 117.114 364.652 + vertex -437.184 120.252 364.19 + vertex -436.842 116.921 363.869 + endloop + endfacet + facet normal -0.119815 -0.107378 0.986972 + outer loop + vertex -437.184 120.252 364.19 + vertex -442.466 120.274 363.551 + vertex -436.842 116.921 363.869 + endloop + endfacet + facet normal -0.119987 -0.0842725 0.989192 + outer loop + vertex -437.184 120.252 364.19 + vertex -442.614 123.631 363.819 + vertex -442.466 120.274 363.551 + endloop + endfacet + facet normal -0.0951544 -0.0834027 0.991963 + outer loop + vertex -442.614 123.631 363.819 + vertex -448.141 123.799 363.303 + vertex -442.466 120.274 363.551 + endloop + endfacet + facet normal -0.0945002 -0.0823389 0.992114 + outer loop + vertex -442.466 120.274 363.551 + vertex -448.141 123.799 363.303 + vertex -448.059 120.429 363.031 + endloop + endfacet + facet normal -0.0736766 -0.0819759 0.993907 + outer loop + vertex -448.141 123.799 363.303 + vertex -454.441 124.015 362.854 + vertex -448.059 120.429 363.031 + endloop + endfacet + facet normal -0.0730606 -0.0607735 0.995474 + outer loop + vertex -448.141 123.799 363.303 + vertex -453.917 127.5 363.105 + vertex -454.441 124.015 362.854 + endloop + endfacet + facet normal -0.0583538 -0.063046 0.996303 + outer loop + vertex -453.917 127.5 363.105 + vertex -460.61 127.955 362.742 + vertex -454.441 124.015 362.854 + endloop + endfacet + facet normal -0.0602474 -0.0660199 0.995998 + outer loop + vertex -454.441 124.015 362.854 + vertex -460.61 127.955 362.742 + vertex -462.967 124.178 362.349 + endloop + endfacet + facet normal -0.0488609 -0.0731411 0.996124 + outer loop + vertex -466.317 128.956 362.536 + vertex -462.967 124.178 362.349 + vertex -460.61 127.955 362.742 + endloop + endfacet + facet normal -0.0451097 -0.0514404 0.997657 + outer loop + vertex -460.61 127.955 362.742 + vertex -466.847 132.258 362.682 + vertex -466.317 128.956 362.536 + endloop + endfacet + facet normal -0.0352036 -0.049872 0.998135 + outer loop + vertex -466.317 128.956 362.536 + vertex -466.847 132.258 362.682 + vertex -474.833 131.985 362.387 + endloop + endfacet + facet normal -0.0355318 -0.0406961 0.99854 + outer loop + vertex -474.696 138.761 362.668 + vertex -474.833 131.985 362.387 + vertex -466.847 132.258 362.682 + endloop + endfacet + facet normal -0.033523 -0.0382712 0.998705 + outer loop + vertex -465.186 135.145 362.848 + vertex -474.696 138.761 362.668 + vertex -466.847 132.258 362.682 + endloop + endfacet + facet normal -0.0421751 -0.0332846 0.998556 + outer loop + vertex -459.734 131.371 362.953 + vertex -465.186 135.145 362.848 + vertex -466.847 132.258 362.682 + endloop + endfacet + facet normal -0.0422722 -0.0334252 0.998547 + outer loop + vertex -459.279 134.752 363.085 + vertex -465.186 135.145 362.848 + vertex -459.734 131.371 362.953 + endloop + endfacet + facet normal -0.0560337 -0.0315497 0.99793 + outer loop + vertex -453.535 130.913 363.286 + vertex -459.279 134.752 363.085 + vertex -459.734 131.371 362.953 + endloop + endfacet + facet normal -0.0571062 -0.0465261 0.997283 + outer loop + vertex -453.535 130.913 363.286 + vertex -459.734 131.371 362.953 + vertex -453.917 127.5 363.105 + endloop + endfacet + facet normal -0.0734013 -0.0446479 0.996303 + outer loop + vertex -448.025 127.192 363.526 + vertex -453.535 130.913 363.286 + vertex -453.917 127.5 363.105 + endloop + endfacet + facet normal -0.0747416 -0.0466448 0.996111 + outer loop + vertex -447.948 130.546 363.688 + vertex -453.535 130.913 363.286 + vertex -448.025 127.192 363.526 + endloop + endfacet + facet normal -0.0957377 -0.0460807 0.994339 + outer loop + vertex -442.705 126.983 364.028 + vertex -447.948 130.546 363.688 + vertex -448.025 127.192 363.526 + endloop + endfacet + facet normal -0.0963592 -0.0644885 0.993255 + outer loop + vertex -442.705 126.983 364.028 + vertex -448.025 127.192 363.526 + vertex -442.614 123.631 363.819 + endloop + endfacet + facet normal -0.120946 -0.0649894 0.990529 + outer loop + vertex -437.44 123.612 364.45 + vertex -442.705 126.983 364.028 + vertex -442.614 123.631 363.819 + endloop + endfacet + facet normal -0.122138 -0.0668857 0.990257 + outer loop + vertex -437.64 126.983 364.653 + vertex -442.705 126.983 364.028 + vertex -437.44 123.612 364.45 + endloop + endfacet + facet normal -0.148409 -0.06822 0.98657 + outer loop + vertex -432.468 123.86 365.215 + vertex -437.64 126.983 364.653 + vertex -437.44 123.612 364.45 + endloop + endfacet + facet normal -0.147247 -0.087422 0.985229 + outer loop + vertex -432.468 123.86 365.215 + vertex -437.44 123.612 364.45 + vertex -432.128 120.462 364.964 + endloop + endfacet + facet normal -0.17378 -0.0897459 0.980687 + outer loop + vertex -427.462 121.001 365.84 + vertex -432.468 123.86 365.215 + vertex -432.128 120.462 364.964 + endloop + endfacet + facet normal -0.172826 -0.0880033 0.981013 + outer loop + vertex -427.874 124.431 366.076 + vertex -432.468 123.86 365.215 + vertex -427.462 121.001 365.84 + endloop + endfacet + facet normal -0.199568 -0.0908454 0.975664 + outer loop + vertex -423.523 121.911 366.731 + vertex -427.874 124.431 366.076 + vertex -427.462 121.001 365.84 + endloop + endfacet + facet normal -0.175281 -0.0697899 0.982042 + outer loop + vertex -427.874 124.431 366.076 + vertex -432.735 127.275 365.41 + vertex -432.468 123.86 365.215 + endloop + endfacet + facet normal -0.17471 -0.0687725 0.982215 + outer loop + vertex -428.199 127.879 366.259 + vertex -432.735 127.275 365.41 + vertex -427.874 124.431 366.076 + endloop + endfacet + facet normal -0.203626 -0.0711941 0.976457 + outer loop + vertex -424.001 125.369 366.952 + vertex -428.199 127.879 366.259 + vertex -427.874 124.431 366.076 + endloop + endfacet + facet normal -0.176895 -0.0531697 0.982792 + outer loop + vertex -428.199 127.879 366.259 + vertex -432.941 130.701 365.558 + vertex -432.735 127.275 365.41 + endloop + endfacet + facet normal -0.149499 -0.0517262 0.987408 + outer loop + vertex -432.941 130.701 365.558 + vertex -437.796 130.364 364.805 + vertex -432.735 127.275 365.41 + endloop + endfacet + facet normal -0.149352 -0.0514792 0.987443 + outer loop + vertex -432.735 127.275 365.41 + vertex -437.796 130.364 364.805 + vertex -437.64 126.983 364.653 + endloop + endfacet + facet normal -0.122896 -0.0504232 0.991138 + outer loop + vertex -437.796 130.364 364.805 + vertex -442.792 130.329 364.184 + vertex -437.64 126.983 364.653 + endloop + endfacet + facet normal -0.123075 -0.0357293 0.991754 + outer loop + vertex -437.796 130.364 364.805 + vertex -442.851 133.688 364.298 + vertex -442.792 130.329 364.184 + endloop + endfacet + facet normal -0.0988696 -0.0353921 0.994471 + outer loop + vertex -442.851 133.688 364.298 + vertex -447.914 133.875 363.801 + vertex -442.792 130.329 364.184 + endloop + endfacet + facet normal -0.097037 -0.0327162 0.994743 + outer loop + vertex -442.792 130.329 364.184 + vertex -447.914 133.875 363.801 + vertex -447.948 130.546 363.688 + endloop + endfacet + facet normal -0.0756621 -0.0330017 0.996587 + outer loop + vertex -447.914 133.875 363.801 + vertex -453.305 134.259 363.405 + vertex -447.948 130.546 363.688 + endloop + endfacet + facet normal -0.0747152 -0.0192257 0.99702 + outer loop + vertex -447.914 133.875 363.801 + vertex -453.161 137.562 363.479 + vertex -453.305 134.259 363.405 + endloop + endfacet + facet normal -0.0555905 -0.020088 0.998252 + outer loop + vertex -453.161 137.562 363.479 + vertex -459.004 138.07 363.164 + vertex -453.305 134.259 363.405 + endloop + endfacet + facet normal -0.0549585 -0.0191394 0.998305 + outer loop + vertex -453.305 134.259 363.405 + vertex -459.004 138.07 363.164 + vertex -459.279 134.752 363.085 + endloop + endfacet + facet normal -0.0381602 -0.020548 0.99906 + outer loop + vertex -459.004 138.07 363.164 + vertex -466.064 138.909 362.912 + vertex -459.279 134.752 363.085 + endloop + endfacet + facet normal -0.0373665 -0.0138274 0.999206 + outer loop + vertex -459.004 138.07 363.164 + vertex -464.727 141.777 363.001 + vertex -466.064 138.909 362.912 + endloop + endfacet + facet normal -0.0197803 -0.0220373 0.999561 + outer loop + vertex -464.727 141.777 363.001 + vertex -474.841 145.349 362.88 + vertex -466.064 138.909 362.912 + endloop + endfacet + facet normal -0.0276669 -0.0327882 0.999079 + outer loop + vertex -474.841 145.349 362.88 + vertex -474.696 138.761 362.668 + vertex -466.064 138.909 362.912 + endloop + endfacet + facet normal -0.0171651 -0.0325643 0.999322 + outer loop + vertex -474.841 145.349 362.88 + vertex -487.849 147.64 362.731 + vertex -474.696 138.761 362.668 + endloop + endfacet + facet normal -0.0210467 -0.0383128 0.999044 + outer loop + vertex -474.696 138.761 362.668 + vertex -487.849 147.64 362.731 + vertex -487.912 140.955 362.473 + endloop + endfacet + facet normal -0.0136042 -0.0383878 0.99917 + outer loop + vertex -487.849 147.64 362.731 + vertex -500.563 150.358 362.662 + vertex -487.912 140.955 362.473 + endloop + endfacet + facet normal -0.0135865 -0.0383641 0.999171 + outer loop + vertex -487.912 140.955 362.473 + vertex -500.563 150.358 362.662 + vertex -500.717 143.654 362.403 + endloop + endfacet + facet normal -0.0154796 -0.0473598 0.998758 + outer loop + vertex -487.912 140.955 362.473 + vertex -500.717 143.654 362.403 + vertex -488.415 134.329 362.151 + endloop + endfacet + facet normal -0.0253383 -0.0466036 0.998592 + outer loop + vertex -474.833 131.985 362.387 + vertex -487.912 140.955 362.473 + vertex -488.415 134.329 362.151 + endloop + endfacet + facet normal -0.0306302 -0.0774822 0.996523 + outer loop + vertex -474.833 131.985 362.387 + vertex -488.415 134.329 362.151 + vertex -475.92 125.621 361.858 + endloop + endfacet + facet normal -0.0460744 -0.0748122 0.996133 + outer loop + vertex -462.967 124.178 362.349 + vertex -474.833 131.985 362.387 + vertex -475.92 125.621 361.858 + endloop + endfacet + facet normal -0.035501 -0.0844464 0.995795 + outer loop + vertex -475.92 125.621 361.858 + vertex -488.415 134.329 362.151 + vertex -488.807 127.813 361.585 + endloop + endfacet + facet normal -0.0245887 -0.0851266 0.996067 + outer loop + vertex -488.415 134.329 362.151 + vertex -500.95 137.043 362.074 + vertex -488.807 127.813 361.585 + endloop + endfacet + facet normal -0.0286902 -0.090492 0.995484 + outer loop + vertex -488.807 127.813 361.585 + vertex -500.95 137.043 362.074 + vertex -501.014 130.534 361.48 + endloop + endfacet + facet normal -0.0227077 -0.0905642 0.995632 + outer loop + vertex -500.95 137.043 362.074 + vertex -512.853 140.098 362.08 + vertex -501.014 130.534 361.48 + endloop + endfacet + facet normal -0.0250181 -0.0934045 0.995314 + outer loop + vertex -501.014 130.534 361.48 + vertex -512.853 140.098 362.08 + vertex -512.813 133.586 361.47 + endloop + endfacet + facet normal -0.0235006 -0.0933986 0.995351 + outer loop + vertex -512.853 140.098 362.08 + vertex -524.657 143.318 362.104 + vertex -512.813 133.586 361.47 + endloop + endfacet + facet normal -0.0252386 -0.0954982 0.99511 + outer loop + vertex -512.813 133.586 361.47 + vertex -524.657 143.318 362.104 + vertex -524.673 136.8 361.478 + endloop + endfacet + facet normal -0.0257798 -0.0954956 0.995096 + outer loop + vertex -524.657 143.318 362.104 + vertex -536.743 146.636 362.109 + vertex -524.673 136.8 361.478 + endloop + endfacet + facet normal -0.0266256 -0.0965257 0.994974 + outer loop + vertex -524.673 136.8 361.478 + vertex -536.743 146.636 362.109 + vertex -536.873 140.128 361.474 + endloop + endfacet + facet normal -0.0275748 -0.0965044 0.994951 + outer loop + vertex -536.743 146.636 362.109 + vertex -549.15 150.075 362.099 + vertex -536.873 140.128 361.474 + endloop + endfacet + facet normal -0.0278855 -0.096885 0.994905 + outer loop + vertex -536.873 140.128 361.474 + vertex -549.15 150.075 362.099 + vertex -549.366 143.606 361.463 + endloop + endfacet + facet normal -0.0281903 -0.0968741 0.994897 + outer loop + vertex -549.15 150.075 362.099 + vertex -561.545 153.571 362.088 + vertex -549.366 143.606 361.463 + endloop + endfacet + facet normal -0.028232 -0.0969247 0.994891 + outer loop + vertex -549.366 143.606 361.463 + vertex -561.545 153.571 362.088 + vertex -561.777 147.136 361.455 + endloop + endfacet + facet normal -0.0277645 -0.0969426 0.994903 + outer loop + vertex -561.545 153.571 362.088 + vertex -573.271 156.809 362.076 + vertex -561.777 147.136 361.455 + endloop + endfacet + facet normal -0.0282096 -0.0974674 0.994839 + outer loop + vertex -561.777 147.136 361.455 + vertex -573.271 156.809 362.076 + vertex -573.485 150.397 361.442 + endloop + endfacet + facet normal -0.0272564 -0.0975015 0.994862 + outer loop + vertex -573.271 156.809 362.076 + vertex -583.688 159.424 362.047 + vertex -573.485 150.397 361.442 + endloop + endfacet + facet normal -0.0289671 -0.0994192 0.994624 + outer loop + vertex -573.485 150.397 361.442 + vertex -583.688 159.424 362.047 + vertex -584.059 153.078 361.402 + endloop + endfacet + facet normal -0.0273041 -0.0995203 0.994661 + outer loop + vertex -584.059 153.078 361.402 + vertex -583.688 159.424 362.047 + vertex -592.81 161.497 362.004 + endloop + endfacet + facet normal -0.0288714 -0.101134 0.994454 + outer loop + vertex -592.81 161.497 362.004 + vertex -594.219 155.384 361.342 + vertex -584.059 153.078 361.402 + endloop + endfacet + facet normal -0.0277646 -0.10139 0.994459 + outer loop + vertex -594.219 155.384 361.342 + vertex -592.81 161.497 362.004 + vertex -601.05 163.778 362.007 + endloop + endfacet + facet normal -0.0109511 -0.0878352 0.996075 + outer loop + vertex -601.05 163.778 362.007 + vertex -602.563 159.981 361.655 + vertex -594.219 155.384 361.342 + endloop + endfacet + facet normal -0.0245581 -0.0824343 0.996294 + outer loop + vertex -601.05 163.778 362.007 + vertex -609.099 166.194 362.008 + vertex -602.563 159.981 361.655 + endloop + endfacet + facet normal -0.0329043 -0.0911577 0.995293 + outer loop + vertex -602.563 159.981 361.655 + vertex -609.099 166.194 362.008 + vertex -609.272 161.207 361.546 + endloop + endfacet + facet normal -0.0309136 -0.0912319 0.99535 + outer loop + vertex -609.099 166.194 362.008 + vertex -618.181 168.789 361.964 + vertex -609.272 161.207 361.546 + endloop + endfacet + facet normal -0.0339513 -0.0947774 0.994919 + outer loop + vertex -609.272 161.207 361.546 + vertex -618.181 168.789 361.964 + vertex -618.347 163.608 361.465 + endloop + endfacet + facet normal -0.0314742 -0.094864 0.994993 + outer loop + vertex -618.181 168.789 361.964 + vertex -628.631 172.112 361.95 + vertex -618.347 163.608 361.465 + endloop + endfacet + facet normal -0.0335875 -0.0974014 0.994678 + outer loop + vertex -618.347 163.608 361.465 + vertex -628.631 172.112 361.95 + vertex -628.828 166.923 361.435 + endloop + endfacet + facet normal -0.032297 -0.0974541 0.994716 + outer loop + vertex -628.631 172.112 361.95 + vertex -639.722 175.901 361.961 + vertex -628.828 166.923 361.435 + endloop + endfacet + facet normal -0.031695 -0.096729 0.994806 + outer loop + vertex -628.828 166.923 361.435 + vertex -639.722 175.901 361.961 + vertex -639.849 170.675 361.449 + endloop + endfacet + facet normal -0.0325466 -0.0967057 0.994781 + outer loop + vertex -639.722 175.901 361.961 + vertex -650.734 179.782 361.978 + vertex -639.849 170.675 361.449 + endloop + endfacet + facet normal -0.0326549 -0.0968342 0.994765 + outer loop + vertex -639.849 170.675 361.449 + vertex -650.734 179.782 361.978 + vertex -650.818 174.53 361.464 + endloop + endfacet + facet normal -0.0341087 -0.0968066 0.994719 + outer loop + vertex -650.734 179.782 361.978 + vertex -661.452 183.633 361.986 + vertex -650.818 174.53 361.464 + endloop + endfacet + facet normal -0.0345735 -0.0973458 0.99465 + outer loop + vertex -650.818 174.53 361.464 + vertex -661.452 183.633 361.986 + vertex -661.518 178.368 361.468 + endloop + endfacet + facet normal -0.0359536 -0.0973238 0.994603 + outer loop + vertex -661.452 183.633 361.986 + vertex -671.977 187.517 361.985 + vertex -661.518 178.368 361.468 + endloop + endfacet + facet normal -0.0367881 -0.0982708 0.99448 + outer loop + vertex -661.518 178.368 361.468 + vertex -671.977 187.517 361.985 + vertex -672.042 182.252 361.463 + endloop + endfacet + facet normal -0.0379744 -0.098252 0.994437 + outer loop + vertex -671.977 187.517 361.985 + vertex -682.448 191.524 361.981 + vertex -672.042 182.252 361.463 + endloop + endfacet + facet normal -0.0375319 -0.0977591 0.994502 + outer loop + vertex -672.042 182.252 361.463 + vertex -682.448 191.524 361.981 + vertex -682.514 186.259 361.461 + endloop + endfacet + facet normal -0.0389333 -0.0977363 0.994451 + outer loop + vertex -682.448 191.524 361.981 + vertex -692.899 195.687 361.981 + vertex -682.514 186.259 361.461 + endloop + endfacet + facet normal -0.0388617 -0.097658 0.994461 + outer loop + vertex -682.514 186.259 361.461 + vertex -692.899 195.687 361.981 + vertex -692.969 190.424 361.462 + endloop + endfacet + facet normal -0.0404395 -0.0976311 0.994401 + outer loop + vertex -692.899 195.687 361.981 + vertex -703.314 200.01 361.982 + vertex -692.969 190.424 361.462 + endloop + endfacet + facet normal -0.0401584 -0.09733 0.994442 + outer loop + vertex -692.969 190.424 361.462 + vertex -703.314 200.01 361.982 + vertex -703.388 194.748 361.464 + endloop + endfacet + facet normal -0.0419926 -0.0972971 0.994369 + outer loop + vertex -703.314 200.01 361.982 + vertex -713.704 204.505 361.983 + vertex -703.388 194.748 361.464 + endloop + endfacet + facet normal -0.0419275 -0.0972288 0.994379 + outer loop + vertex -703.388 194.748 361.464 + vertex -713.704 204.505 361.983 + vertex -713.781 199.243 361.465 + endloop + endfacet + facet normal -0.0434407 -0.0972006 0.994316 + outer loop + vertex -713.704 204.505 361.983 + vertex -724.098 209.192 361.987 + vertex -713.781 199.243 361.465 + endloop + endfacet + facet normal -0.0441574 -0.0979383 0.994212 + outer loop + vertex -713.781 199.243 361.465 + vertex -724.098 209.192 361.987 + vertex -724.177 203.934 361.466 + endloop + endfacet + facet normal -0.0461787 -0.0978995 0.994124 + outer loop + vertex -724.098 209.192 361.987 + vertex -734.487 214.085 361.987 + vertex -724.177 203.934 361.466 + endloop + endfacet + facet normal -0.0463744 -0.0980968 0.994096 + outer loop + vertex -724.177 203.934 361.466 + vertex -734.487 214.085 361.987 + vertex -734.563 208.826 361.464 + endloop + endfacet + facet normal -0.0482433 -0.0980614 0.99401 + outer loop + vertex -734.487 214.085 361.987 + vertex -744.801 219.158 361.986 + vertex -734.563 208.826 361.464 + endloop + endfacet + facet normal -0.0475689 -0.0973981 0.994108 + outer loop + vertex -734.563 208.826 361.464 + vertex -744.801 219.158 361.986 + vertex -744.879 213.895 361.467 + endloop + endfacet + facet normal -0.0501582 -0.0973478 0.993986 + outer loop + vertex -744.801 219.158 361.986 + vertex -754.961 224.382 361.985 + vertex -744.879 213.895 361.467 + endloop + endfacet + facet normal -0.0501464 -0.0973366 0.993987 + outer loop + vertex -744.879 213.895 361.467 + vertex -754.961 224.382 361.985 + vertex -755.042 219.121 361.466 + endloop + endfacet + facet normal -0.0523413 -0.0972921 0.993879 + outer loop + vertex -754.961 224.382 361.985 + vertex -764.924 229.742 361.985 + vertex -755.042 219.121 361.466 + endloop + endfacet + facet normal -0.052133 -0.0970997 0.993908 + outer loop + vertex -755.042 219.121 361.466 + vertex -764.924 229.742 361.985 + vertex -765.01 224.482 361.467 + endloop + endfacet + facet normal -0.0546742 -0.0970453 0.993777 + outer loop + vertex -764.924 229.742 361.985 + vertex -774.699 235.244 361.985 + vertex -765.01 224.482 361.467 + endloop + endfacet + facet normal -0.0548381 -0.0971917 0.993754 + outer loop + vertex -765.01 224.482 361.467 + vertex -774.699 235.244 361.985 + vertex -774.791 229.988 361.466 + endloop + endfacet + facet normal -0.057264 -0.0971363 0.993622 + outer loop + vertex -774.699 235.244 361.985 + vertex -784.327 240.911 361.984 + vertex -774.791 229.988 361.466 + endloop + endfacet + facet normal -0.0568442 -0.0967726 0.993682 + outer loop + vertex -774.791 229.988 361.466 + vertex -784.327 240.911 361.984 + vertex -784.426 235.654 361.466 + endloop + endfacet + facet normal -0.0596198 -0.096705 0.993526 + outer loop + vertex -784.327 240.911 361.984 + vertex -793.837 246.765 361.983 + vertex -784.426 235.654 361.466 + endloop + endfacet + facet normal -0.059777 -0.0968371 0.993504 + outer loop + vertex -784.426 235.654 361.466 + vertex -793.837 246.765 361.983 + vertex -793.942 241.504 361.464 + endloop + endfacet + facet normal -0.0629437 -0.0967557 0.993316 + outer loop + vertex -793.837 246.765 361.983 + vertex -803.224 252.861 361.982 + vertex -793.942 241.504 361.464 + endloop + endfacet + facet normal -0.0633392 -0.0970765 0.993259 + outer loop + vertex -793.942 241.504 361.464 + vertex -803.224 252.861 361.982 + vertex -803.333 247.603 361.461 + endloop + endfacet + facet normal -0.0678248 -0.0969554 0.992975 + outer loop + vertex -803.224 252.861 361.982 + vertex -812.465 259.326 361.982 + vertex -803.333 247.603 361.461 + endloop + endfacet + facet normal -0.0666702 -0.0960634 0.99314 + outer loop + vertex -803.333 247.603 361.461 + vertex -812.465 259.326 361.982 + vertex -812.585 254.064 361.465 + endloop + endfacet + facet normal -0.0724034 -0.0958947 0.992755 + outer loop + vertex -812.465 259.326 361.982 + vertex -821.559 266.281 361.991 + vertex -812.585 254.064 361.465 + endloop + endfacet + facet normal -0.0712534 -0.0950569 0.992918 + outer loop + vertex -812.585 254.064 361.465 + vertex -821.559 266.281 361.991 + vertex -821.69 260.983 361.474 + endloop + endfacet + facet normal -0.0770173 -0.0948741 0.992506 + outer loop + vertex -821.559 266.281 361.991 + vertex -830.507 273.637 362 + vertex -821.69 260.983 361.474 + endloop + endfacet + facet normal -0.0748342 -0.093366 0.992816 + outer loop + vertex -821.69 260.983 361.474 + vertex -830.507 273.637 362 + vertex -830.622 268.22 361.481 + endloop + endfacet + facet normal -0.0800164 -0.0932186 0.992425 + outer loop + vertex -830.507 273.637 362 + vertex -839.161 280.861 361.98 + vertex -830.622 268.22 361.481 + endloop + endfacet + facet normal -0.0820844 -0.0946038 0.992125 + outer loop + vertex -830.622 268.22 361.481 + vertex -839.161 280.861 361.98 + vertex -839.262 275.384 361.45 + endloop + endfacet + facet normal -0.0848632 -0.0945306 0.991898 + outer loop + vertex -839.161 280.861 361.98 + vertex -846.963 286.987 361.897 + vertex -839.262 275.384 361.45 + endloop + endfacet + facet normal -0.0921268 -0.0993083 0.990783 + outer loop + vertex -839.262 275.384 361.45 + vertex -846.963 286.987 361.897 + vertex -847.851 282.531 361.367 + endloop + endfacet + facet normal -0.0953995 -0.0986269 0.990541 + outer loop + vertex -847.851 282.531 361.367 + vertex -846.963 286.987 361.897 + vertex -854.547 293.071 361.772 + endloop + endfacet + facet normal -0.0667329 -0.0805688 0.994513 + outer loop + vertex -854.547 293.071 361.772 + vertex -854.183 289.606 361.516 + vertex -847.851 282.531 361.367 + endloop + endfacet + facet normal -0.117262 -0.125597 0.985127 + outer loop + vertex -854.183 289.606 361.516 + vertex -852.69 285.078 361.116 + vertex -847.851 282.531 361.367 + endloop + endfacet + facet normal -0.127029 -0.144532 0.981312 + outer loop + vertex -847.007 276.201 360.544 + vertex -847.851 282.531 361.367 + vertex -852.69 285.078 361.116 + endloop + endfacet + facet normal -0.151288 -0.159687 0.975506 + outer loop + vertex -852.69 285.078 361.116 + vertex -852.709 280.903 360.43 + vertex -847.007 276.201 360.544 + endloop + endfacet + facet normal -0.166685 -0.159217 0.97307 + outer loop + vertex -852.709 280.903 360.43 + vertex -852.69 285.078 361.116 + vertex -856.941 288.325 360.919 + endloop + endfacet + facet normal -0.132228 -0.145124 0.980538 + outer loop + vertex -839.478 270.088 360.655 + vertex -847.851 282.531 361.367 + vertex -847.007 276.201 360.544 + endloop + endfacet + facet normal -0.127652 -0.142105 0.981586 + outer loop + vertex -839.262 275.384 361.45 + vertex -847.851 282.531 361.367 + vertex -839.478 270.088 360.655 + endloop + endfacet + facet normal -0.12276 -0.142391 0.982168 + outer loop + vertex -830.854 262.928 360.695 + vertex -839.262 275.384 361.45 + vertex -839.478 270.088 360.655 + endloop + endfacet + facet normal -0.120354 -0.140799 0.982695 + outer loop + vertex -830.622 268.22 361.481 + vertex -839.262 275.384 361.45 + vertex -830.854 262.928 360.695 + endloop + endfacet + facet normal -0.113158 -0.141233 0.983488 + outer loop + vertex -821.904 255.726 360.69 + vertex -830.622 268.22 361.481 + vertex -830.854 262.928 360.695 + endloop + endfacet + facet normal -0.114207 -0.14195 0.983263 + outer loop + vertex -821.69 260.983 361.474 + vertex -830.622 268.22 361.481 + vertex -821.904 255.726 360.69 + endloop + endfacet + facet normal -0.105798 -0.142422 0.984136 + outer loop + vertex -812.773 248.838 360.675 + vertex -821.69 260.983 361.474 + vertex -821.904 255.726 360.69 + endloop + endfacet + facet normal -0.109018 -0.144741 0.983446 + outer loop + vertex -812.585 254.064 361.465 + vertex -821.69 260.983 361.474 + vertex -812.773 248.838 360.675 + endloop + endfacet + facet normal -0.100532 -0.145174 0.984285 + outer loop + vertex -803.499 242.375 360.669 + vertex -812.585 254.064 361.465 + vertex -812.773 248.838 360.675 + endloop + endfacet + facet normal -0.10147 -0.145889 0.984084 + outer loop + vertex -803.333 247.603 361.461 + vertex -812.585 254.064 361.465 + vertex -803.499 242.375 360.669 + endloop + endfacet + facet normal -0.0950023 -0.146185 0.984685 + outer loop + vertex -794.092 236.271 360.67 + vertex -803.333 247.603 361.461 + vertex -803.499 242.375 360.669 + endloop + endfacet + facet normal -0.095466 -0.146556 0.984585 + outer loop + vertex -793.942 241.504 361.464 + vertex -803.333 247.603 361.461 + vertex -794.092 236.271 360.67 + endloop + endfacet + facet normal -0.0906856 -0.146758 0.985007 + outer loop + vertex -784.567 230.416 360.675 + vertex -793.942 241.504 361.464 + vertex -794.092 236.271 360.67 + endloop + endfacet + facet normal -0.0902472 -0.146394 0.985101 + outer loop + vertex -784.426 235.654 361.466 + vertex -793.942 241.504 361.464 + vertex -784.567 230.416 360.675 + endloop + endfacet + facet normal -0.0863912 -0.146547 0.985424 + outer loop + vertex -774.926 224.748 360.677 + vertex -784.426 235.654 361.466 + vertex -784.567 230.416 360.675 + endloop + endfacet + facet normal -0.0858273 -0.146064 0.985545 + outer loop + vertex -774.791 229.988 361.466 + vertex -784.426 235.654 361.466 + vertex -774.926 224.748 360.677 + endloop + endfacet + facet normal -0.0820157 -0.146208 0.985848 + outer loop + vertex -765.14 219.243 360.675 + vertex -774.791 229.988 361.466 + vertex -774.926 224.748 360.677 + endloop + endfacet + facet normal -0.0828377 -0.146933 0.985672 + outer loop + vertex -765.01 224.482 361.467 + vertex -774.791 229.988 361.466 + vertex -765.14 219.243 360.675 + endloop + endfacet + facet normal -0.0793655 -0.14706 0.985938 + outer loop + vertex -755.17 213.879 360.678 + vertex -765.01 224.482 361.467 + vertex -765.14 219.243 360.675 + endloop + endfacet + facet normal -0.0786598 -0.146416 0.986091 + outer loop + vertex -755.042 219.121 361.466 + vertex -765.01 224.482 361.467 + vertex -755.17 213.879 360.678 + endloop + endfacet + facet normal -0.0752416 -0.146537 0.98634 + outer loop + vertex -745.003 208.654 360.677 + vertex -755.042 219.121 361.466 + vertex -755.17 213.879 360.678 + endloop + endfacet + facet normal -0.0756299 -0.146903 0.986255 + outer loop + vertex -744.879 213.895 361.467 + vertex -755.042 219.121 361.466 + vertex -745.003 208.654 360.677 + endloop + endfacet + facet normal -0.0724605 -0.147012 0.986477 + outer loop + vertex -734.685 203.581 360.679 + vertex -744.879 213.895 361.467 + vertex -745.003 208.654 360.677 + endloop + endfacet + facet normal -0.0714874 -0.146066 0.986689 + outer loop + vertex -734.563 208.826 361.464 + vertex -744.879 213.895 361.467 + vertex -734.685 203.581 360.679 + endloop + endfacet + facet normal -0.0686444 -0.14616 0.986876 + outer loop + vertex -724.296 198.691 360.677 + vertex -734.563 208.826 361.464 + vertex -734.685 203.581 360.679 + endloop + endfacet + facet normal -0.0693366 -0.14685 0.986726 + outer loop + vertex -724.177 203.934 361.466 + vertex -734.563 208.826 361.464 + vertex -724.296 198.691 360.677 + endloop + endfacet + facet normal -0.0664107 -0.146945 0.986913 + outer loop + vertex -713.899 194 360.678 + vertex -724.177 203.934 361.466 + vertex -724.296 198.691 360.677 + endloop + endfacet + facet normal -0.0661517 -0.146681 0.986969 + outer loop + vertex -713.781 199.243 361.465 + vertex -724.177 203.934 361.466 + vertex -713.899 194 360.678 + endloop + endfacet + facet normal -0.0627271 -0.146789 0.987177 + outer loop + vertex -703.503 189.507 360.671 + vertex -713.781 199.243 361.465 + vertex -713.899 194 360.678 + endloop + endfacet + facet normal -0.0638857 -0.147991 0.986923 + outer loop + vertex -703.388 194.748 361.464 + vertex -713.781 199.243 361.465 + vertex -703.503 189.507 360.671 + endloop + endfacet + facet normal -0.0612151 -0.148074 0.98708 + outer loop + vertex -693.08 185.181 360.668 + vertex -703.388 194.748 361.464 + vertex -703.503 189.507 360.671 + endloop + endfacet + facet normal -0.0612185 -0.148077 0.987079 + outer loop + vertex -692.969 190.424 361.462 + vertex -703.388 194.748 361.464 + vertex -693.08 185.181 360.668 + endloop + endfacet + facet normal -0.0591005 -0.14814 0.987199 + outer loop + vertex -682.623 181.014 360.669 + vertex -692.969 190.424 361.462 + vertex -693.08 185.181 360.668 + endloop + endfacet + facet normal -0.0588796 -0.147901 0.987248 + outer loop + vertex -682.514 186.259 361.461 + vertex -692.969 190.424 361.462 + vertex -682.623 181.014 360.669 + endloop + endfacet + facet normal -0.0571831 -0.14795 0.98734 + outer loop + vertex -672.155 177.007 360.675 + vertex -682.514 186.259 361.461 + vertex -682.623 181.014 360.669 + endloop + endfacet + facet normal -0.0564091 -0.147098 0.987512 + outer loop + vertex -672.042 182.252 361.463 + vertex -682.514 186.259 361.461 + vertex -672.155 177.007 360.675 + endloop + endfacet + facet normal -0.0549327 -0.147142 0.987589 + outer loop + vertex -661.639 173.13 360.682 + vertex -672.042 182.252 361.463 + vertex -672.155 177.007 360.675 + endloop + endfacet + facet normal -0.0547378 -0.146923 0.987632 + outer loop + vertex -661.518 178.368 361.468 + vertex -672.042 182.252 361.463 + vertex -661.639 173.13 360.682 + endloop + endfacet + facet normal -0.0523524 -0.146996 0.987751 + outer loop + vertex -650.937 169.303 360.68 + vertex -661.518 178.368 361.468 + vertex -661.639 173.13 360.682 + endloop + endfacet + facet normal -0.0524075 -0.147059 0.987738 + outer loop + vertex -650.818 174.53 361.464 + vertex -661.518 178.368 361.468 + vertex -650.937 169.303 360.68 + endloop + endfacet + facet normal -0.0502599 -0.147123 0.98784 + outer loop + vertex -639.977 165.471 360.667 + vertex -650.818 174.53 361.464 + vertex -650.937 169.303 360.68 + endloop + endfacet + facet normal -0.0503949 -0.147282 0.98781 + outer loop + vertex -639.849 170.675 361.449 + vertex -650.818 174.53 361.464 + vertex -639.977 165.471 360.667 + endloop + endfacet + facet normal -0.0495371 -0.147309 0.987849 + outer loop + vertex -628.988 161.738 360.661 + vertex -639.849 170.675 361.449 + vertex -639.977 165.471 360.667 + endloop + endfacet + facet normal -0.0485074 -0.146078 0.988083 + outer loop + vertex -628.828 166.923 361.435 + vertex -639.849 170.675 361.449 + vertex -628.988 161.738 360.661 + endloop + endfacet + facet normal -0.0491565 -0.146054 0.988055 + outer loop + vertex -618.555 158.44 360.693 + vertex -628.828 166.923 361.435 + vertex -628.988 161.738 360.661 + endloop + endfacet + facet normal -0.0488372 -0.145674 0.988127 + outer loop + vertex -618.347 163.608 361.465 + vertex -628.828 166.923 361.435 + vertex -618.555 158.44 360.693 + endloop + endfacet + facet normal -0.0502508 -0.145608 0.988065 + outer loop + vertex -609.262 155.987 360.804 + vertex -618.347 163.608 361.465 + vertex -618.555 158.44 360.693 + endloop + endfacet + facet normal -0.0460368 -0.140664 0.988986 + outer loop + vertex -609.272 161.207 361.546 + vertex -618.347 163.608 361.465 + vertex -609.262 155.987 360.804 + endloop + endfacet + facet normal -0.0472202 -0.140658 0.988931 + outer loop + vertex -601.357 154.74 361.004 + vertex -609.272 161.207 361.546 + vertex -609.262 155.987 360.804 + endloop + endfacet + facet normal -0.0403582 -0.132382 0.990377 + outer loop + vertex -602.563 159.981 361.655 + vertex -609.272 161.207 361.546 + vertex -601.357 154.74 361.004 + endloop + endfacet + facet normal -0.0350478 -0.131205 0.990736 + outer loop + vertex -602.563 159.981 361.655 + vertex -601.357 154.74 361.004 + vertex -594.219 155.384 361.342 + endloop + endfacet + facet normal -0.032063 -0.161952 0.986278 + outer loop + vertex -593.217 148.147 360.186 + vertex -594.219 155.384 361.342 + vertex -601.357 154.74 361.004 + endloop + endfacet + facet normal -0.0483889 -0.164051 0.985264 + outer loop + vertex -594.219 155.384 361.342 + vertex -593.217 148.147 360.186 + vertex -584.235 146.776 360.399 + endloop + endfacet + facet normal -0.0412738 -0.155977 0.986898 + outer loop + vertex -584.235 146.776 360.399 + vertex -584.059 153.078 361.402 + vertex -594.219 155.384 361.342 + endloop + endfacet + facet normal -0.0452223 -0.155842 0.986746 + outer loop + vertex -573.66 144.211 360.478 + vertex -584.059 153.078 361.402 + vertex -584.235 146.776 360.399 + endloop + endfacet + facet normal -0.0424276 -0.15263 0.987372 + outer loop + vertex -573.485 150.397 361.442 + vertex -584.059 153.078 361.402 + vertex -573.66 144.211 360.478 + endloop + endfacet + facet normal -0.0435137 -0.152592 0.987331 + outer loop + vertex -561.909 140.934 360.49 + vertex -573.485 150.397 361.442 + vertex -573.66 144.211 360.478 + endloop + endfacet + facet normal -0.0435756 -0.152667 0.987317 + outer loop + vertex -561.777 147.136 361.455 + vertex -573.485 150.397 361.442 + vertex -561.909 140.934 360.49 + endloop + endfacet + facet normal -0.0438154 -0.15266 0.987307 + outer loop + vertex -549.481 137.358 360.488 + vertex -561.777 147.136 361.455 + vertex -561.909 140.934 360.49 + endloop + endfacet + facet normal -0.0442278 -0.153169 0.98721 + outer loop + vertex -549.366 143.606 361.463 + vertex -561.777 147.136 361.455 + vertex -549.481 137.358 360.488 + endloop + endfacet + facet normal -0.0436091 -0.153184 0.987235 + outer loop + vertex -536.954 133.842 360.496 + vertex -549.366 143.606 361.463 + vertex -549.481 137.358 360.488 + endloop + endfacet + facet normal -0.0435166 -0.153069 0.987257 + outer loop + vertex -536.873 140.128 361.474 + vertex -549.366 143.606 361.463 + vertex -536.954 133.842 360.496 + endloop + endfacet + facet normal -0.042311 -0.153092 0.987306 + outer loop + vertex -524.683 130.506 360.505 + vertex -536.873 140.128 361.474 + vertex -536.954 133.842 360.496 + endloop + endfacet + facet normal -0.0419206 -0.152607 0.987397 + outer loop + vertex -524.673 136.8 361.478 + vertex -536.873 140.128 361.474 + vertex -524.683 130.506 360.505 + endloop + endfacet + facet normal -0.0416561 -0.152609 0.987408 + outer loop + vertex -512.732 127.304 360.514 + vertex -524.673 136.8 361.478 + vertex -524.683 130.506 360.505 + endloop + endfacet + facet normal -0.0402513 -0.150875 0.987733 + outer loop + vertex -512.813 133.586 361.47 + vertex -524.673 136.8 361.478 + vertex -512.732 127.304 360.514 + endloop + endfacet + facet normal -0.0424089 -0.150889 0.987641 + outer loop + vertex -500.907 124.245 360.554 + vertex -512.813 133.586 361.47 + vertex -512.732 127.304 360.514 + endloop + endfacet + facet normal -0.0386711 -0.146209 0.988498 + outer loop + vertex -501.014 130.534 361.48 + vertex -512.813 133.586 361.47 + vertex -500.907 124.245 360.554 + endloop + endfacet + facet normal -0.045019 -0.146276 0.988219 + outer loop + vertex -488.814 121.497 360.699 + vertex -501.014 130.534 361.48 + vertex -500.907 124.245 360.554 + endloop + endfacet + facet normal -0.0394118 -0.13882 0.989533 + outer loop + vertex -488.807 127.813 361.585 + vertex -501.014 130.534 361.48 + vertex -488.814 121.497 360.699 + endloop + endfacet + facet normal -0.0505052 -0.138739 0.98904 + outer loop + vertex -476.137 119.248 361.03 + vertex -488.807 127.813 361.585 + vertex -488.814 121.497 360.699 + endloop + endfacet + facet normal -0.0426887 -0.127299 0.990945 + outer loop + vertex -475.92 125.621 361.858 + vertex -488.807 127.813 361.585 + vertex -476.137 119.248 361.03 + endloop + endfacet + facet normal -0.0589333 -0.126649 0.990195 + outer loop + vertex -463.054 117.539 361.591 + vertex -475.92 125.621 361.858 + vertex -476.137 119.248 361.03 + endloop + endfacet + facet normal -0.131743 -0.130159 0.982702 + outer loop + vertex -852.69 285.078 361.116 + vertex -854.183 289.606 361.516 + vertex -856.884 291.269 361.374 + endloop + endfacet + facet normal -0.130472 -0.128057 0.983147 + outer loop + vertex -856.917 292.593 361.542 + vertex -856.884 291.269 361.374 + vertex -854.183 289.606 361.516 + endloop + endfacet + facet normal -0.105543 -0.105289 0.988825 + outer loop + vertex -854.183 289.606 361.516 + vertex -856.093 292.377 361.607 + vertex -856.917 292.593 361.542 + endloop + endfacet + facet normal -0.101626 -0.0897489 0.990766 + outer loop + vertex -856.093 292.377 361.607 + vertex -857.903 293.892 361.559 + vertex -856.917 292.593 361.542 + endloop + endfacet + facet normal -0.123153 -0.106027 0.986707 + outer loop + vertex -859.842 295.619 361.502 + vertex -856.917 292.593 361.542 + vertex -857.903 293.892 361.559 + endloop + endfacet + facet normal -0.129754 -0.113497 0.985029 + outer loop + vertex -857.903 293.892 361.559 + vertex -859.931 296.15 361.551 + vertex -859.842 295.619 361.502 + endloop + endfacet + facet normal -0.132997 -0.113994 0.984539 + outer loop + vertex -859.931 296.15 361.551 + vertex -862.345 299.023 361.558 + vertex -859.842 295.619 361.502 + endloop + endfacet + facet normal -0.151042 -0.127195 0.98031 + outer loop + vertex -864.272 300.795 361.491 + vertex -859.842 295.619 361.502 + vertex -862.345 299.023 361.558 + endloop + endfacet + facet normal -0.158722 -0.135632 0.977963 + outer loop + vertex -862.345 299.023 361.558 + vertex -864.236 301.284 361.565 + vertex -864.272 300.795 361.491 + endloop + endfacet + facet normal -0.162845 -0.135228 0.977341 + outer loop + vertex -864.236 301.284 361.565 + vertex -865.197 302.473 361.569 + vertex -864.272 300.795 361.491 + endloop + endfacet + facet normal -0.202832 -0.156767 0.966583 + outer loop + vertex -865.197 302.473 361.569 + vertex -867.035 304.893 361.576 + vertex -864.272 300.795 361.491 + endloop + endfacet + facet normal -0.184683 -0.144645 0.972096 + outer loop + vertex -868.807 306.517 361.481 + vertex -864.272 300.795 361.491 + vertex -867.035 304.893 361.576 + endloop + endfacet + facet normal -0.0852926 -0.0725958 0.993708 + outer loop + vertex -865.197 302.473 361.569 + vertex -864.236 301.284 361.565 + vertex -864.434 302.617 361.645 + endloop + endfacet + facet normal -0.0861421 -0.0682258 0.993944 + outer loop + vertex -867.035 304.893 361.576 + vertex -865.197 302.473 361.569 + vertex -864.434 302.617 361.645 + endloop + endfacet + facet normal -0.0848448 -0.0667373 0.994157 + outer loop + vertex -864.434 302.617 361.645 + vertex -868.976 308.835 361.675 + vertex -867.035 304.893 361.576 + endloop + endfacet + facet normal -0.0846423 -0.0666382 0.994181 + outer loop + vertex -869.267 307.794 361.58 + vertex -867.035 304.893 361.576 + vertex -868.976 308.835 361.675 + endloop + endfacet + facet normal -0.0914105 -0.0647022 0.993709 + outer loop + vertex -871.391 310.782 361.58 + vertex -869.267 307.794 361.58 + vertex -868.976 308.835 361.675 + endloop + endfacet + facet normal -0.090237 -0.063237 0.993911 + outer loop + vertex -868.976 308.835 361.675 + vertex -873.556 314.906 361.645 + vertex -871.391 310.782 361.58 + endloop + endfacet + facet normal -0.0890965 -0.0626407 0.994051 + outer loop + vertex -873.275 313.384 361.575 + vertex -871.391 310.782 361.58 + vertex -873.556 314.906 361.645 + endloop + endfacet + facet normal -0.100807 -0.064742 0.992797 + outer loop + vertex -874.15 314.695 361.571 + vertex -873.275 313.384 361.575 + vertex -873.556 314.906 361.645 + endloop + endfacet + facet normal -0.101922 -0.0616344 0.992881 + outer loop + vertex -875.775 317.351 361.569 + vertex -874.15 314.695 361.571 + vertex -873.556 314.906 361.645 + endloop + endfacet + facet normal -0.104956 -0.0644037 0.992389 + outer loop + vertex -873.556 314.906 361.645 + vertex -877.667 321.327 361.627 + vertex -875.775 317.351 361.569 + endloop + endfacet + facet normal -0.10845 -0.0660597 0.991905 + outer loop + vertex -877.47 320.039 361.563 + vertex -875.775 317.351 361.569 + vertex -877.667 321.327 361.627 + endloop + endfacet + facet normal -0.115298 -0.0670692 0.991064 + outer loop + vertex -878.281 321.423 361.562 + vertex -877.47 320.039 361.563 + vertex -877.667 321.327 361.627 + endloop + endfacet + facet normal -0.114853 -0.0640409 0.991316 + outer loop + vertex -879.765 324.131 361.565 + vertex -878.281 321.423 361.562 + vertex -877.667 321.327 361.627 + endloop + endfacet + facet normal -0.112449 -0.062234 0.991707 + outer loop + vertex -877.667 321.327 361.627 + vertex -881.359 328.15 361.637 + vertex -879.765 324.131 361.565 + endloop + endfacet + facet normal -0.110813 -0.0615889 0.991931 + outer loop + vertex -881.325 326.924 361.564 + vertex -879.765 324.131 361.565 + vertex -881.359 328.15 361.637 + endloop + endfacet + facet normal -0.115931 -0.0616946 0.991339 + outer loop + vertex -882.055 328.333 361.567 + vertex -881.325 326.924 361.564 + vertex -881.359 328.15 361.637 + endloop + endfacet + facet normal -0.114648 -0.0566398 0.99179 + outer loop + vertex -883.36 331.072 361.572 + vertex -882.055 328.333 361.567 + vertex -881.359 328.15 361.637 + endloop + endfacet + facet normal -0.110381 -0.0537028 0.992437 + outer loop + vertex -881.359 328.15 361.637 + vertex -884.843 335.578 361.651 + vertex -883.36 331.072 361.572 + endloop + endfacet + facet normal -0.11077 -0.0538297 0.992387 + outer loop + vertex -884.855 334.147 361.572 + vertex -883.36 331.072 361.572 + vertex -884.843 335.578 361.651 + endloop + endfacet + facet normal -0.125645 -0.0536081 0.990626 + outer loop + vertex -885.907 336.446 361.563 + vertex -884.855 334.147 361.572 + vertex -884.843 335.578 361.651 + endloop + endfacet + facet normal -0.127758 -0.0562406 0.990209 + outer loop + vertex -887.016 339.215 361.577 + vertex -885.907 336.446 361.563 + vertex -884.843 335.578 361.651 + endloop + endfacet + facet normal -0.11135 -0.0463859 0.992698 + outer loop + vertex -884.843 335.578 361.651 + vertex -887.756 342.594 361.652 + vertex -887.016 339.215 361.577 + endloop + endfacet + facet normal -0.283522 -0.126035 0.950647 + outer loop + vertex -884.855 334.147 361.572 + vertex -885.907 336.446 361.563 + vertex -884.452 332.694 361.5 + endloop + endfacet + facet normal -0.231136 -0.112323 0.966416 + outer loop + vertex -883.36 331.072 361.572 + vertex -884.855 334.147 361.572 + vertex -884.452 332.694 361.5 + endloop + endfacet + facet normal -0.26086 -0.136668 0.955654 + outer loop + vertex -881.325 326.924 361.564 + vertex -882.055 328.333 361.567 + vertex -881.25 326.403 361.51 + endloop + endfacet + facet normal -0.241173 -0.134422 0.961128 + outer loop + vertex -879.765 324.131 361.565 + vertex -881.325 326.924 361.564 + vertex -881.25 326.403 361.51 + endloop + endfacet + facet normal -0.0999705 -0.0554851 0.993442 + outer loop + vertex -878.55 325.852 361.791 + vertex -881.359 328.15 361.637 + vertex -877.667 321.327 361.627 + endloop + endfacet + facet normal -0.0877122 -0.0531394 0.994727 + outer loop + vertex -878.55 325.852 361.791 + vertex -877.667 321.327 361.627 + vertex -874.922 320.593 361.83 + endloop + endfacet + facet normal -0.0685217 -0.0398832 0.996852 + outer loop + vertex -878.55 325.852 361.791 + vertex -874.922 320.593 361.83 + vertex -876.128 328.864 362.078 + endloop + endfacet + facet normal -0.0701511 -0.0385676 0.996791 + outer loop + vertex -881.242 333.332 361.891 + vertex -878.55 325.852 361.791 + vertex -876.128 328.864 362.078 + endloop + endfacet + facet normal -0.0692129 -0.0374892 0.996897 + outer loop + vertex -876.128 328.864 362.078 + vertex -878.658 336.491 362.189 + vertex -881.242 333.332 361.891 + endloop + endfacet + facet normal -0.0726823 -0.0346385 0.996753 + outer loop + vertex -878.658 336.491 362.189 + vertex -881.759 341.751 362.146 + vertex -881.242 333.332 361.891 + endloop + endfacet + facet normal -0.0768021 -0.0348819 0.996436 + outer loop + vertex -885.126 341.001 361.86 + vertex -881.242 333.332 361.891 + vertex -881.759 341.751 362.146 + endloop + endfacet + facet normal -0.0778352 -0.0302684 0.996507 + outer loop + vertex -881.759 341.751 362.146 + vertex -884.908 348.527 362.106 + vertex -885.126 341.001 361.86 + endloop + endfacet + facet normal -0.0835259 -0.0300885 0.996051 + outer loop + vertex -888.046 347.899 361.824 + vertex -885.126 341.001 361.86 + vertex -884.908 348.527 362.106 + endloop + endfacet + facet normal -0.0844079 -0.0257004 0.9961 + outer loop + vertex -884.908 348.527 362.106 + vertex -887.985 356.173 362.042 + vertex -888.046 347.899 361.824 + endloop + endfacet + facet normal -0.0898143 -0.0256481 0.995628 + outer loop + vertex -890.243 353.469 361.769 + vertex -888.046 347.899 361.824 + vertex -887.985 356.173 362.042 + endloop + endfacet + facet normal -0.0939196 -0.0221893 0.995332 + outer loop + vertex -891.296 360.05 361.816 + vertex -890.243 353.469 361.769 + vertex -887.985 356.173 362.042 + endloop + endfacet + facet normal -0.0938902 -0.022164 0.995336 + outer loop + vertex -887.985 356.173 362.042 + vertex -889.608 365.081 362.088 + vertex -891.296 360.05 361.816 + endloop + endfacet + facet normal -0.105096 -0.0183486 0.994293 + outer loop + vertex -892.433 367.756 361.838 + vertex -891.296 360.05 361.816 + vertex -889.608 365.081 362.088 + endloop + endfacet + facet normal -0.103517 -0.0166633 0.994488 + outer loop + vertex -889.608 365.081 362.088 + vertex -890.691 372.854 362.105 + vertex -892.433 367.756 361.838 + endloop + endfacet + facet normal -0.118479 -0.0114665 0.99289 + outer loop + vertex -893.091 375.481 361.849 + vertex -892.433 367.756 361.838 + vertex -890.691 372.854 362.105 + endloop + endfacet + facet normal -0.116632 -0.00975526 0.993127 + outer loop + vertex -890.691 372.854 362.105 + vertex -891.29 380.295 362.108 + vertex -893.091 375.481 361.849 + endloop + endfacet + facet normal -0.134228 -0.00305439 0.990946 + outer loop + vertex -893.242 383.188 361.852 + vertex -893.091 375.481 361.849 + vertex -891.29 380.295 362.108 + endloop + endfacet + facet normal -0.132231 -0.00168353 0.991217 + outer loop + vertex -891.29 380.295 362.108 + vertex -891.341 387.709 362.114 + vertex -893.242 383.188 361.852 + endloop + endfacet + facet normal -0.152378 0.00695633 0.988298 + outer loop + vertex -892.817 391.057 361.862 + vertex -893.242 383.188 361.852 + vertex -891.341 387.709 362.114 + endloop + endfacet + facet normal -0.151776 0.00722856 0.988389 + outer loop + vertex -891.341 387.709 362.114 + vertex -890.851 395.104 362.135 + vertex -892.817 391.057 361.862 + endloop + endfacet + facet normal -0.173679 0.0181218 0.984636 + outer loop + vertex -891.75 399.778 361.89 + vertex -892.817 391.057 361.862 + vertex -890.851 395.104 362.135 + endloop + endfacet + facet normal -0.175509 0.0177534 0.984318 + outer loop + vertex -890.851 395.104 362.135 + vertex -889.953 401.448 362.181 + vertex -891.75 399.778 361.89 + endloop + endfacet + facet normal -0.183967 0.0271644 0.982557 + outer loop + vertex -889.953 401.448 362.181 + vertex -889.469 407.811 362.095 + vertex -891.75 399.778 361.89 + endloop + endfacet + facet normal -0.19953 0.0316641 0.97938 + outer loop + vertex -890.995 407.018 361.81 + vertex -891.75 399.778 361.89 + vertex -889.469 407.811 362.095 + endloop + endfacet + facet normal -0.203536 0.0397796 0.978259 + outer loop + vertex -889.212 414.392 361.881 + vertex -890.995 407.018 361.81 + vertex -889.469 407.811 362.095 + endloop + endfacet + facet normal -0.210941 0.0400177 0.976679 + outer loop + vertex -889.469 407.811 362.095 + vertex -887.793 414.792 362.171 + vertex -889.212 414.392 361.881 + endloop + endfacet + facet normal -0.212565 0.0462407 0.976052 + outer loop + vertex -887.793 414.792 362.171 + vertex -886.786 420.521 362.119 + vertex -889.212 414.392 361.881 + endloop + endfacet + facet normal -0.228182 0.0525718 0.972198 + outer loop + vertex -887.484 422.639 361.841 + vertex -889.212 414.392 361.881 + vertex -886.786 420.521 362.119 + endloop + endfacet + facet normal -0.223743 0.0541574 0.973142 + outer loop + vertex -886.786 420.521 362.119 + vertex -885.185 427.543 362.096 + vertex -887.484 422.639 361.841 + endloop + endfacet + facet normal -0.232716 0.0584872 0.970785 + outer loop + vertex -885.699 429.977 361.827 + vertex -887.484 422.639 361.841 + vertex -885.185 427.543 362.096 + endloop + endfacet + facet normal -0.23492 0.0579663 0.970285 + outer loop + vertex -885.185 427.543 362.096 + vertex -883.175 435.737 362.094 + vertex -885.699 429.977 361.827 + endloop + endfacet + facet normal -0.247979 0.063857 0.966658 + outer loop + vertex -884.126 436.455 361.802 + vertex -885.699 429.977 361.827 + vertex -883.175 435.737 362.094 + endloop + endfacet + facet normal -0.248921 0.0625466 0.966502 + outer loop + vertex -881.926 443.892 361.887 + vertex -884.126 436.455 361.802 + vertex -883.175 435.737 362.094 + endloop + endfacet + facet normal -0.256387 0.0636384 0.964477 + outer loop + vertex -883.175 435.737 362.094 + vertex -880.893 442.987 362.222 + vertex -881.926 443.892 361.887 + endloop + endfacet + facet normal -0.258033 0.0616464 0.964167 + outer loop + vertex -880.893 442.987 362.222 + vertex -879.334 451.413 362.1 + vertex -881.926 443.892 361.887 + endloop + endfacet + facet normal -0.301315 0.0769541 0.950414 + outer loop + vertex -880.275 452.15 361.742 + vertex -881.926 443.892 361.887 + vertex -879.334 451.413 362.1 + endloop + endfacet + facet normal -0.302103 0.0758694 0.950251 + outer loop + vertex -879.334 451.413 362.1 + vertex -879.155 456.562 361.746 + vertex -880.275 452.15 361.742 + endloop + endfacet + facet normal -0.346455 0.0763625 0.934953 + outer loop + vertex -879.334 451.413 362.1 + vertex -878.423 457.712 361.923 + vertex -879.155 456.562 361.746 + endloop + endfacet + facet normal -0.384027 0.102954 0.917564 + outer loop + vertex -878.423 457.712 361.923 + vertex -878.223 461.169 361.619 + vertex -879.155 456.562 361.746 + endloop + endfacet + facet normal -0.392071 0.103117 0.914138 + outer loop + vertex -877.654 461.059 361.876 + vertex -878.223 461.169 361.619 + vertex -878.423 457.712 361.923 + endloop + endfacet + facet normal -0.0640314 -0.0392381 0.997176 + outer loop + vertex -871.443 322.049 362.111 + vertex -876.128 328.864 362.078 + vertex -874.922 320.593 361.83 + endloop + endfacet + facet normal -0.0634549 -0.0406124 0.997158 + outer loop + vertex -874.922 320.593 361.83 + vertex -870.43 314.513 361.868 + vertex -871.443 322.049 362.111 + endloop + endfacet + facet normal -0.0605738 -0.0402314 0.997353 + outer loop + vertex -866.81 316.213 362.157 + vertex -871.443 322.049 362.111 + vertex -870.43 314.513 361.868 + endloop + endfacet + facet normal -0.0595609 -0.0423835 0.997324 + outer loop + vertex -870.43 314.513 361.868 + vertex -864.771 307.717 361.917 + vertex -866.81 316.213 362.157 + endloop + endfacet + facet normal -0.0612933 -0.0427959 0.997202 + outer loop + vertex -862.143 311.219 362.229 + vertex -866.81 316.213 362.157 + vertex -864.771 307.717 361.917 + endloop + endfacet + facet normal -0.0609355 -0.0430653 0.997212 + outer loop + vertex -857.478 302.566 362.141 + vertex -862.143 311.219 362.229 + vertex -864.771 307.717 361.917 + endloop + endfacet + facet normal -0.0699893 -0.0559359 0.995978 + outer loop + vertex -864.771 307.717 361.917 + vertex -860.272 299.705 361.784 + vertex -857.478 302.566 362.141 + endloop + endfacet + facet normal -0.0666157 -0.0592364 0.996019 + outer loop + vertex -854.547 293.071 361.772 + vertex -857.478 302.566 362.141 + vertex -860.272 299.705 361.784 + endloop + endfacet + facet normal -0.074333 -0.0658949 0.995054 + outer loop + vertex -860.272 299.705 361.784 + vertex -858.124 295.174 361.644 + vertex -854.547 293.071 361.772 + endloop + endfacet + facet normal -0.0748192 -0.0667276 0.994962 + outer loop + vertex -858.124 295.174 361.644 + vertex -856.505 293.034 361.622 + vertex -854.547 293.071 361.772 + endloop + endfacet + facet normal -0.0747348 -0.0701735 0.994731 + outer loop + vertex -856.093 292.377 361.607 + vertex -854.547 293.071 361.772 + vertex -856.505 293.034 361.622 + endloop + endfacet + facet normal -0.087615 -0.0782056 0.99308 + outer loop + vertex -856.505 293.034 361.622 + vertex -856.334 292.497 361.595 + vertex -856.093 292.377 361.607 + endloop + endfacet + facet normal 0.0745693 0.0518282 -0.995868 + outer loop + vertex -856.334 292.497 361.595 + vertex -856.754 292.835 361.581 + vertex -856.093 292.377 361.607 + endloop + endfacet + facet normal -0.098342 -0.0815613 0.991805 + outer loop + vertex -856.505 293.034 361.622 + vertex -856.754 292.835 361.581 + vertex -856.334 292.497 361.595 + endloop + endfacet + facet normal -0.0967968 -0.0834991 0.991795 + outer loop + vertex -857.543 293.705 361.577 + vertex -856.754 292.835 361.581 + vertex -856.505 293.034 361.622 + endloop + endfacet + facet normal -0.0947232 -0.0816172 0.992152 + outer loop + vertex -856.754 292.835 361.581 + vertex -857.543 293.705 361.577 + vertex -857.903 293.892 361.559 + endloop + endfacet + facet normal -0.0958552 -0.0838259 0.991859 + outer loop + vertex -857.543 293.705 361.577 + vertex -858.83 295.082 361.57 + vertex -857.903 293.892 361.559 + endloop + endfacet + facet normal -0.0941003 -0.0821848 0.992165 + outer loop + vertex -858.124 295.174 361.644 + vertex -858.83 295.082 361.57 + vertex -857.543 293.705 361.577 + endloop + endfacet + facet normal -0.0941361 -0.0819244 0.992183 + outer loop + vertex -860.757 297.775 361.609 + vertex -858.83 295.082 361.57 + vertex -858.124 295.174 361.644 + endloop + endfacet + facet normal -0.0990851 -0.0854551 0.991403 + outer loop + vertex -858.83 295.082 361.57 + vertex -860.757 297.775 361.609 + vertex -859.931 296.15 361.551 + endloop + endfacet + facet normal -0.096571 -0.0831466 0.991847 + outer loop + vertex -858.124 295.174 361.644 + vertex -857.543 293.705 361.577 + vertex -856.505 293.034 361.622 + endloop + endfacet + facet normal -0.0818023 -0.0694106 0.994229 + outer loop + vertex -860.272 299.705 361.784 + vertex -860.757 297.775 361.609 + vertex -858.124 295.174 361.644 + endloop + endfacet + facet normal -0.0816774 -0.0694427 0.994237 + outer loop + vertex -860.272 299.705 361.784 + vertex -864.434 302.617 361.645 + vertex -860.757 297.775 361.609 + endloop + endfacet + facet normal -0.093455 -0.0783753 0.992534 + outer loop + vertex -860.757 297.775 361.609 + vertex -864.434 302.617 361.645 + vertex -862.345 299.023 361.558 + endloop + endfacet + facet normal -0.0860163 -0.0651534 0.994161 + outer loop + vertex -854.547 293.071 361.772 + vertex -852.241 295.304 362.118 + vertex -857.478 302.566 362.141 + endloop + endfacet + facet normal -0.0800194 -0.0608307 0.994935 + outer loop + vertex -852.241 295.304 362.118 + vertex -852.986 298.846 362.275 + vertex -857.478 302.566 362.141 + endloop + endfacet + facet normal -0.058824 -0.0351361 0.99765 + outer loop + vertex -852.986 298.846 362.275 + vertex -852.942 302.24 362.397 + vertex -857.478 302.566 362.141 + endloop + endfacet + facet normal -0.0590743 -0.0387441 0.997501 + outer loop + vertex -856.669 310.634 362.502 + vertex -857.478 302.566 362.141 + vertex -852.942 302.24 362.397 + endloop + endfacet + facet normal -0.0430197 -0.0316295 0.998573 + outer loop + vertex -852.942 302.24 362.397 + vertex -852.624 305.342 362.509 + vertex -856.669 310.634 362.502 + endloop + endfacet + facet normal -0.0286366 -0.0206339 0.999377 + outer loop + vertex -852.624 305.342 362.509 + vertex -851.473 306.613 362.568 + vertex -856.669 310.634 362.502 + endloop + endfacet + facet normal -0.0457014 -0.0427056 0.998042 + outer loop + vertex -851.473 306.613 362.568 + vertex -852.404 311.953 362.754 + vertex -856.669 310.634 362.502 + endloop + endfacet + facet normal -0.0408209 -0.0583717 0.99746 + outer loop + vertex -858.663 323.092 363.149 + vertex -856.669 310.634 362.502 + vertex -852.404 311.953 362.754 + endloop + endfacet + facet normal -0.140563 -0.113919 0.983496 + outer loop + vertex -852.404 311.953 362.754 + vertex -854.138 317.509 363.149 + vertex -858.663 323.092 363.149 + endloop + endfacet + facet normal -0.119001 -0.107443 0.987064 + outer loop + vertex -854.138 317.509 363.149 + vertex -852.404 311.953 362.754 + vertex -846.979 309.581 363.149 + endloop + endfacet + facet normal -0.111214 -0.0891845 0.989787 + outer loop + vertex -846.184 302.981 362.644 + vertex -846.979 309.581 363.149 + vertex -852.404 311.953 362.754 + endloop + endfacet + facet normal -0.0782583 -0.0854764 0.993262 + outer loop + vertex -838.741 296.758 362.695 + vertex -846.979 309.581 363.149 + vertex -846.184 302.981 362.644 + endloop + endfacet + facet normal -0.0373691 -0.0365376 0.998633 + outer loop + vertex -838.741 296.758 362.695 + vertex -846.184 302.981 362.644 + vertex -838.904 291.682 362.503 + endloop + endfacet + facet normal -0.0313925 -0.0367372 0.998832 + outer loop + vertex -830.329 284.193 362.497 + vertex -838.741 296.758 362.695 + vertex -838.904 291.682 362.503 + endloop + endfacet + facet normal -0.029513 -0.0345854 0.998966 + outer loop + vertex -830.329 284.193 362.497 + vertex -838.904 291.682 362.503 + vertex -830.419 278.994 362.315 + endloop + endfacet + facet normal -0.0275744 -0.0346208 0.99902 + outer loop + vertex -821.491 271.564 362.304 + vertex -830.329 284.193 362.497 + vertex -830.419 278.994 362.315 + endloop + endfacet + facet normal -0.0474005 -0.0584424 0.997165 + outer loop + vertex -821.491 271.564 362.304 + vertex -830.419 278.994 362.315 + vertex -821.559 266.281 361.991 + endloop + endfacet + facet normal -0.0285009 -0.0352685 0.998971 + outer loop + vertex -821.505 276.84 362.489 + vertex -830.329 284.193 362.497 + vertex -821.491 271.564 362.304 + endloop + endfacet + facet normal -0.0264058 -0.0352652 0.999029 + outer loop + vertex -812.413 264.616 362.298 + vertex -821.505 276.84 362.489 + vertex -821.491 271.564 362.304 + endloop + endfacet + facet normal -0.0446863 -0.0591491 0.997248 + outer loop + vertex -812.413 264.616 362.298 + vertex -821.491 271.564 362.304 + vertex -812.465 259.326 361.982 + endloop + endfacet + facet normal -0.0271446 -0.0358141 0.99899 + outer loop + vertex -812.448 269.947 362.488 + vertex -821.505 276.84 362.489 + vertex -812.413 264.616 362.298 + endloop + endfacet + facet normal -0.0251296 -0.0358028 0.999043 + outer loop + vertex -803.168 258.153 362.299 + vertex -812.448 269.947 362.488 + vertex -812.413 264.616 362.298 + endloop + endfacet + facet normal -0.0415713 -0.0593206 0.997373 + outer loop + vertex -803.168 258.153 362.299 + vertex -812.413 264.616 362.298 + vertex -803.224 252.861 361.982 + endloop + endfacet + facet normal -0.0248973 -0.0356203 0.999055 + outer loop + vertex -803.184 263.48 362.489 + vertex -812.448 269.947 362.488 + vertex -803.168 258.153 362.299 + endloop + endfacet + facet normal -0.0235364 -0.0356173 0.999088 + outer loop + vertex -793.777 252.04 362.302 + vertex -803.184 263.48 362.489 + vertex -803.168 258.153 362.299 + endloop + endfacet + facet normal -0.0393663 -0.059939 0.997425 + outer loop + vertex -793.777 252.04 362.302 + vertex -803.168 258.153 362.299 + vertex -793.837 246.765 361.983 + endloop + endfacet + facet normal -0.0229992 -0.035176 0.999116 + outer loop + vertex -793.784 257.354 362.489 + vertex -803.184 263.48 362.489 + vertex -793.777 252.04 362.302 + endloop + endfacet + facet normal -0.021702 -0.0351752 0.999145 + outer loop + vertex -784.271 246.181 362.303 + vertex -793.784 257.354 362.489 + vertex -793.777 252.04 362.302 + endloop + endfacet + facet normal -0.0369572 -0.0599268 0.997518 + outer loop + vertex -784.271 246.181 362.303 + vertex -793.777 252.04 362.302 + vertex -784.327 240.911 361.984 + endloop + endfacet + facet normal -0.0219431 -0.0353803 0.999133 + outer loop + vertex -784.287 251.489 362.49 + vertex -793.784 257.354 362.489 + vertex -784.271 246.181 362.303 + endloop + endfacet + facet normal -0.0208453 -0.0353777 0.999157 + outer loop + vertex -774.652 240.519 362.303 + vertex -784.287 251.489 362.49 + vertex -784.271 246.181 362.303 + endloop + endfacet + facet normal -0.0352374 -0.0598256 0.997587 + outer loop + vertex -774.652 240.519 362.303 + vertex -784.271 246.181 362.303 + vertex -774.699 235.244 361.985 + endloop + endfacet + facet normal -0.0209183 -0.0354417 0.999153 + outer loop + vertex -774.681 245.839 362.491 + vertex -784.287 251.489 362.49 + vertex -774.652 240.519 362.303 + endloop + endfacet + facet normal -0.0198602 -0.0354367 0.999175 + outer loop + vertex -764.884 235.024 362.302 + vertex -774.681 245.839 362.491 + vertex -774.652 240.519 362.303 + endloop + endfacet + facet normal -0.0334446 -0.0595842 0.997663 + outer loop + vertex -764.884 235.024 362.302 + vertex -774.652 240.519 362.303 + vertex -764.924 229.742 361.985 + endloop + endfacet + facet normal -0.0199804 -0.0355455 0.999168 + outer loop + vertex -764.913 240.345 362.491 + vertex -774.681 245.839 362.491 + vertex -764.884 235.024 362.302 + endloop + endfacet + facet normal -0.019105 -0.0355414 0.999186 + outer loop + vertex -754.924 229.668 362.302 + vertex -764.913 240.345 362.491 + vertex -764.884 235.024 362.302 + endloop + endfacet + facet normal -0.0320158 -0.0595519 0.997712 + outer loop + vertex -754.924 229.668 362.302 + vertex -764.884 235.024 362.302 + vertex -754.961 224.382 361.985 + endloop + endfacet + facet normal -0.0189695 -0.0354147 0.999193 + outer loop + vertex -754.949 234.988 362.49 + vertex -764.913 240.345 362.491 + vertex -754.924 229.668 362.302 + endloop + endfacet + facet normal -0.0182774 -0.035412 0.999206 + outer loop + vertex -744.764 224.443 362.303 + vertex -754.949 234.988 362.49 + vertex -754.924 229.668 362.302 + endloop + endfacet + facet normal -0.0306663 -0.0595024 0.997757 + outer loop + vertex -744.764 224.443 362.303 + vertex -754.924 229.668 362.302 + vertex -744.801 219.158 361.986 + endloop + endfacet + facet normal -0.0182723 -0.0354072 0.999206 + outer loop + vertex -744.787 229.766 362.491 + vertex -754.949 234.988 362.49 + vertex -744.764 224.443 362.303 + endloop + endfacet + facet normal -0.0173291 -0.0354037 0.999223 + outer loop + vertex -734.447 219.371 362.302 + vertex -744.787 229.766 362.491 + vertex -744.764 224.443 362.303 + endloop + endfacet + facet normal -0.0290864 -0.0593178 0.997815 + outer loop + vertex -734.447 219.371 362.302 + vertex -744.764 224.443 362.303 + vertex -734.487 214.085 361.987 + endloop + endfacet + facet normal -0.0175831 -0.0356561 0.999209 + outer loop + vertex -734.469 224.69 362.491 + vertex -744.787 229.766 362.491 + vertex -734.447 219.371 362.302 + endloop + endfacet + facet normal -0.0168986 -0.0356538 0.999221 + outer loop + vertex -724.057 214.475 362.303 + vertex -734.469 224.69 362.491 + vertex -734.447 219.371 362.302 + endloop + endfacet + facet normal -0.0280945 -0.0594121 0.997838 + outer loop + vertex -724.057 214.475 362.303 + vertex -734.447 219.371 362.302 + vertex -724.098 209.192 361.987 + endloop + endfacet + facet normal -0.0164013 -0.0351475 0.999248 + outer loop + vertex -724.08 219.796 362.49 + vertex -734.469 224.69 362.491 + vertex -724.057 214.475 362.303 + endloop + endfacet + facet normal -0.0158581 -0.0351455 0.999256 + outer loop + vertex -713.665 209.784 362.303 + vertex -724.08 219.796 362.49 + vertex -724.057 214.475 362.303 + endloop + endfacet + facet normal -0.0271799 -0.0602282 0.997815 + outer loop + vertex -713.665 209.784 362.303 + vertex -724.057 214.475 362.303 + vertex -713.704 204.505 361.983 + endloop + endfacet + facet normal -0.0160085 -0.0353018 0.999248 + outer loop + vertex -713.694 215.109 362.491 + vertex -724.08 219.796 362.49 + vertex -713.665 209.784 362.303 + endloop + endfacet + facet normal -0.0150907 -0.0352974 0.999263 + outer loop + vertex -703.279 205.292 362.301 + vertex -713.694 215.109 362.491 + vertex -713.665 209.784 362.303 + endloop + endfacet + facet normal -0.025811 -0.0600824 0.99786 + outer loop + vertex -703.279 205.292 362.301 + vertex -713.665 209.784 362.303 + vertex -703.314 200.01 361.982 + endloop + endfacet + facet normal -0.0152489 -0.0354651 0.999255 + outer loop + vertex -703.309 210.617 362.49 + vertex -713.694 215.109 362.491 + vertex -703.279 205.292 362.301 + endloop + endfacet + facet normal -0.0145217 -0.0354614 0.999266 + outer loop + vertex -692.868 200.973 362.299 + vertex -703.309 210.617 362.49 + vertex -703.279 205.292 362.301 + endloop + endfacet + facet normal -0.0246415 -0.0598579 0.997903 + outer loop + vertex -692.868 200.973 362.299 + vertex -703.279 205.292 362.301 + vertex -692.899 195.687 361.981 + endloop + endfacet + facet normal -0.0147253 -0.0356817 0.999255 + outer loop + vertex -692.898 206.299 362.489 + vertex -703.309 210.617 362.49 + vertex -692.868 200.973 362.299 + endloop + endfacet + facet normal -0.0142599 -0.0356793 0.999262 + outer loop + vertex -682.421 196.814 362.3 + vertex -692.898 206.299 362.489 + vertex -692.868 200.973 362.299 + endloop + endfacet + facet normal -0.0239183 -0.05994 0.997915 + outer loop + vertex -682.421 196.814 362.3 + vertex -692.868 200.973 362.299 + vertex -682.448 191.524 361.981 + endloop + endfacet + facet normal -0.0141274 -0.035533 0.999269 + outer loop + vertex -682.457 202.144 362.489 + vertex -692.898 206.299 362.489 + vertex -682.421 196.814 362.3 + endloop + endfacet + facet normal -0.0138663 -0.0355314 0.999272 + outer loop + vertex -671.958 192.813 362.303 + vertex -682.457 202.144 362.489 + vertex -682.421 196.814 362.3 + endloop + endfacet + facet normal -0.0231182 -0.059723 0.997947 + outer loop + vertex -671.958 192.813 362.303 + vertex -682.421 196.814 362.3 + vertex -671.977 187.517 361.985 + endloop + endfacet + facet normal -0.0140565 -0.0357452 0.999262 + outer loop + vertex -671.993 198.143 362.493 + vertex -682.457 202.144 362.489 + vertex -671.958 192.813 362.303 + endloop + endfacet + facet normal -0.0133637 -0.035741 0.999272 + outer loop + vertex -661.427 188.925 362.304 + vertex -671.993 198.143 362.493 + vertex -671.958 192.813 362.303 + endloop + endfacet + facet normal -0.0223174 -0.0599984 0.997949 + outer loop + vertex -661.427 188.925 362.304 + vertex -671.958 192.813 362.303 + vertex -661.452 183.633 361.986 + endloop + endfacet + facet normal -0.0132572 -0.0356191 0.999278 + outer loop + vertex -661.419 194.239 362.494 + vertex -671.993 198.143 362.493 + vertex -661.427 188.925 362.304 + endloop + endfacet + facet normal -0.0121449 -0.0356211 0.999292 + outer loop + vertex -650.668 185.057 362.297 + vertex -661.419 194.239 362.494 + vertex -661.427 188.925 362.304 + endloop + endfacet + facet normal -0.0209381 -0.0600736 0.997974 + outer loop + vertex -650.668 185.057 362.297 + vertex -661.427 188.925 362.304 + vertex -650.734 179.782 361.978 + endloop + endfacet + facet normal -0.012439 -0.0359651 0.999276 + outer loop + vertex -650.605 190.353 362.489 + vertex -661.419 194.239 362.494 + vertex -650.668 185.057 362.297 + endloop + endfacet + facet normal -0.0112595 -0.0359795 0.999289 + outer loop + vertex -639.598 181.159 362.282 + vertex -650.605 190.353 362.489 + vertex -650.668 185.057 362.297 + endloop + endfacet + facet normal -0.0198329 -0.0603205 0.997982 + outer loop + vertex -639.598 181.159 362.282 + vertex -650.668 185.057 362.297 + vertex -639.722 175.901 361.961 + endloop + endfacet + facet normal -0.0119804 -0.0368417 0.999249 + outer loop + vertex -639.558 186.478 362.478 + vertex -650.605 190.353 362.489 + vertex -639.598 181.159 362.282 + endloop + endfacet + facet normal -0.0115903 -0.0368449 0.999254 + outer loop + vertex -628.515 177.383 362.271 + vertex -639.558 186.478 362.478 + vertex -639.598 181.159 362.282 + endloop + endfacet + facet normal -0.0195799 -0.0602914 0.997989 + outer loop + vertex -628.515 177.383 362.271 + vertex -639.598 181.159 362.282 + vertex -628.631 172.112 361.95 + endloop + endfacet + facet normal -0.0118737 -0.0371886 0.999238 + outer loop + vertex -628.612 182.782 362.471 + vertex -639.558 186.478 362.478 + vertex -628.515 177.383 362.271 + endloop + endfacet + facet normal -0.0127385 -0.0372037 0.999227 + outer loop + vertex -618.105 174.056 362.28 + vertex -628.612 182.782 362.471 + vertex -628.515 177.383 362.271 + endloop + endfacet + facet normal -0.0198805 -0.0595561 0.998027 + outer loop + vertex -618.105 174.056 362.28 + vertex -628.515 177.383 362.271 + vertex -618.181 168.789 361.964 + endloop + endfacet + facet normal -0.0123594 -0.0367477 0.999248 + outer loop + vertex -618.364 179.557 362.479 + vertex -628.612 182.782 362.471 + vertex -618.105 174.056 362.28 + endloop + endfacet + facet normal -0.0134215 -0.0367972 0.999233 + outer loop + vertex -608.899 171.381 362.305 + vertex -618.364 179.557 362.479 + vertex -618.105 174.056 362.28 + endloop + endfacet + facet normal -0.0191063 -0.056371 0.998227 + outer loop + vertex -608.899 171.381 362.305 + vertex -618.105 174.056 362.28 + vertex -609.099 166.194 362.008 + endloop + endfacet + facet normal -0.012157 -0.0353347 0.999302 + outer loop + vertex -609.204 177.006 362.5 + vertex -618.364 179.557 362.479 + vertex -608.899 171.381 362.305 + endloop + endfacet + facet normal -0.0126838 -0.035363 0.999294 + outer loop + vertex -600.729 169.339 362.336 + vertex -609.204 177.006 362.5 + vertex -608.899 171.381 362.305 + endloop + endfacet + facet normal -0.0183666 -0.058116 0.998141 + outer loop + vertex -600.729 169.339 362.336 + vertex -608.899 171.381 362.305 + vertex -601.05 163.778 362.007 + endloop + endfacet + facet normal -0.0158303 -0.0582646 0.998176 + outer loop + vertex -600.729 169.339 362.336 + vertex -601.05 163.778 362.007 + vertex -592.81 161.497 362.004 + endloop + endfacet + facet normal -0.0123297 -0.0349719 0.999312 + outer loop + vertex -601.135 175.213 362.537 + vertex -609.204 177.006 362.5 + vertex -600.729 169.339 362.336 + endloop + endfacet + facet normal -0.0122262 -0.0349648 0.999314 + outer loop + vertex -601.135 175.213 362.537 + vertex -600.729 169.339 362.336 + vertex -592.728 167.737 362.378 + endloop + endfacet + facet normal -0.0141759 -0.0371552 0.999209 + outer loop + vertex -592.728 167.737 362.378 + vertex -593.684 174.439 362.614 + vertex -601.135 175.213 362.537 + endloop + endfacet + facet normal -0.0143095 -0.0384466 0.999158 + outer loop + vertex -601.963 180.565 362.731 + vertex -601.135 175.213 362.537 + vertex -593.684 174.439 362.614 + endloop + endfacet + facet normal -0.0419233 -0.075715 0.996248 + outer loop + vertex -593.684 174.439 362.614 + vertex -598.068 183.913 363.149 + vertex -601.963 180.565 362.731 + endloop + endfacet + facet normal -0.0282067 -0.0915633 0.9954 + outer loop + vertex -598.068 183.913 363.149 + vertex -608.608 187.16 363.149 + vertex -601.963 180.565 362.731 + endloop + endfacet + facet normal -0.0263086 -0.0896653 0.995624 + outer loop + vertex -609.566 182.488 362.703 + vertex -601.963 180.565 362.731 + vertex -608.608 187.16 363.149 + endloop + endfacet + facet normal -0.0281874 -0.0892787 0.995608 + outer loop + vertex -608.608 187.16 363.149 + vertex -619.278 190.529 363.149 + vertex -609.566 182.488 362.703 + endloop + endfacet + facet normal -0.0267422 -0.0875439 0.995802 + outer loop + vertex -609.566 182.488 362.703 + vertex -619.278 190.529 363.149 + vertex -618.901 185.156 362.687 + endloop + endfacet + facet normal -0.0125506 -0.0378679 0.999204 + outer loop + vertex -609.566 182.488 362.703 + vertex -618.901 185.156 362.687 + vertex -609.204 177.006 362.5 + endloop + endfacet + facet normal -0.0284358 -0.0876578 0.995745 + outer loop + vertex -619.278 190.529 363.149 + vertex -629.959 193.994 363.149 + vertex -618.901 185.156 362.687 + endloop + endfacet + facet normal -0.0275817 -0.0865952 0.995862 + outer loop + vertex -618.901 185.156 362.687 + vertex -629.959 193.994 363.149 + vertex -629.177 188.376 362.683 + endloop + endfacet + facet normal -0.0124713 -0.0383693 0.999186 + outer loop + vertex -618.901 185.156 362.687 + vertex -629.177 188.376 362.683 + vertex -618.364 179.557 362.479 + endloop + endfacet + facet normal -0.0290293 -0.086792 0.995803 + outer loop + vertex -629.959 193.994 363.149 + vertex -641.493 197.852 363.149 + vertex -629.177 188.376 362.683 + endloop + endfacet + facet normal -0.0285773 -0.0862076 0.995867 + outer loop + vertex -629.177 188.376 362.683 + vertex -641.493 197.852 363.149 + vertex -639.908 191.956 362.685 + endloop + endfacet + facet normal -0.012873 -0.0391383 0.999151 + outer loop + vertex -629.177 188.376 362.683 + vertex -639.908 191.956 362.685 + vertex -628.612 182.782 362.471 + endloop + endfacet + facet normal -0.0298834 -0.0865533 0.995799 + outer loop + vertex -641.493 197.852 363.149 + vertex -651.469 201.296 363.149 + vertex -639.908 191.956 362.685 + endloop + endfacet + facet normal -0.0294702 -0.0860446 0.995855 + outer loop + vertex -639.908 191.956 362.685 + vertex -651.469 201.296 363.149 + vertex -650.727 195.722 362.69 + endloop + endfacet + facet normal -0.012907 -0.0384603 0.999177 + outer loop + vertex -639.908 191.956 362.685 + vertex -650.727 195.722 362.69 + vertex -639.558 186.478 362.478 + endloop + endfacet + facet normal -0.0307448 -0.0862098 0.995803 + outer loop + vertex -651.469 201.296 363.149 + vertex -662.086 205.082 363.149 + vertex -650.727 195.722 362.69 + endloop + endfacet + facet normal -0.0305575 -0.0859838 0.995828 + outer loop + vertex -650.727 195.722 362.69 + vertex -662.086 205.082 363.149 + vertex -661.523 199.595 362.693 + endloop + endfacet + facet normal -0.0132453 -0.0377307 0.9992 + outer loop + vertex -650.727 195.722 362.69 + vertex -661.523 199.595 362.693 + vertex -650.605 190.353 362.489 + endloop + endfacet + facet normal -0.0318127 -0.0861082 0.995778 + outer loop + vertex -662.086 205.082 363.149 + vertex -672.739 209.018 363.149 + vertex -661.523 199.595 362.693 + endloop + endfacet + facet normal -0.0319286 -0.0862453 0.995762 + outer loop + vertex -661.523 199.595 362.693 + vertex -672.739 209.018 363.149 + vertex -672.203 203.543 362.692 + endloop + endfacet + facet normal -0.0138703 -0.0373964 0.999204 + outer loop + vertex -661.523 199.595 362.693 + vertex -672.203 203.543 362.692 + vertex -661.419 194.239 362.494 + endloop + endfacet + facet normal -0.0331401 -0.0863599 0.995713 + outer loop + vertex -672.739 209.018 363.149 + vertex -683.801 213.263 363.149 + vertex -672.203 203.543 362.692 + endloop + endfacet + facet normal -0.0333563 -0.0866165 0.995683 + outer loop + vertex -672.203 203.543 362.692 + vertex -683.801 213.263 363.149 + vertex -682.741 207.577 362.69 + endloop + endfacet + facet normal -0.0145575 -0.0375069 0.99919 + outer loop + vertex -672.203 203.543 362.692 + vertex -682.741 207.577 362.69 + vertex -671.993 198.143 362.493 + endloop + endfacet + facet normal -0.0346575 -0.0868537 0.995618 + outer loop + vertex -683.801 213.263 363.149 + vertex -694.102 217.374 363.149 + vertex -682.741 207.577 362.69 + endloop + endfacet + facet normal -0.0346672 -0.0868649 0.995617 + outer loop + vertex -682.741 207.577 362.69 + vertex -694.102 217.374 363.149 + vertex -693.141 211.716 362.689 + endloop + endfacet + facet normal -0.0151701 -0.0378702 0.999168 + outer loop + vertex -682.741 207.577 362.69 + vertex -693.141 211.716 362.689 + vertex -682.457 202.144 362.489 + endloop + endfacet + facet normal -0.0361344 -0.0871082 0.995543 + outer loop + vertex -694.102 217.374 363.149 + vertex -704.223 221.572 363.149 + vertex -693.141 211.716 362.689 + endloop + endfacet + facet normal -0.0360777 -0.0870447 0.995551 + outer loop + vertex -693.141 211.716 362.689 + vertex -704.223 221.572 363.149 + vertex -703.549 216.032 362.689 + endloop + endfacet + facet normal -0.0156026 -0.0376726 0.999168 + outer loop + vertex -693.141 211.716 362.689 + vertex -703.549 216.032 362.689 + vertex -692.898 206.299 362.489 + endloop + endfacet + facet normal -0.0376868 -0.0872344 0.995475 + outer loop + vertex -704.223 221.572 363.149 + vertex -714.875 226.174 363.149 + vertex -703.549 216.032 362.689 + endloop + endfacet + facet normal -0.0376429 -0.0871856 0.995481 + outer loop + vertex -703.549 216.032 362.689 + vertex -714.875 226.174 363.149 + vertex -713.933 220.522 362.69 + endloop + endfacet + facet normal -0.0162055 -0.0376 0.999161 + outer loop + vertex -703.549 216.032 362.689 + vertex -713.933 220.522 362.69 + vertex -703.309 210.617 362.49 + endloop + endfacet + facet normal -0.0393937 -0.0874698 0.995388 + outer loop + vertex -714.875 226.174 363.149 + vertex -724.952 230.712 363.149 + vertex -713.933 220.522 362.69 + endloop + endfacet + facet normal -0.0393166 -0.0873869 0.995398 + outer loop + vertex -713.933 220.522 362.69 + vertex -724.952 230.712 363.149 + vertex -724.325 225.212 362.691 + endloop + endfacet + facet normal -0.0168282 -0.0375635 0.999153 + outer loop + vertex -713.933 220.522 362.69 + vertex -724.325 225.212 362.691 + vertex -713.694 215.109 362.491 + endloop + endfacet + facet normal -0.0411786 -0.0875916 0.995305 + outer loop + vertex -724.952 230.712 363.149 + vertex -735.674 235.753 363.149 + vertex -724.325 225.212 362.691 + endloop + endfacet + facet normal -0.0417534 -0.0882072 0.995227 + outer loop + vertex -724.325 225.212 362.691 + vertex -735.674 235.753 363.149 + vertex -734.729 230.111 362.689 + endloop + endfacet + facet normal -0.0181157 -0.0380057 0.999113 + outer loop + vertex -724.325 225.212 362.691 + vertex -734.729 230.111 362.689 + vertex -724.08 219.796 362.49 + endloop + endfacet + facet normal -0.0434966 -0.0884909 0.995127 + outer loop + vertex -735.674 235.753 363.149 + vertex -745.993 240.825 363.149 + vertex -734.729 230.111 362.689 + endloop + endfacet + facet normal -0.0433208 -0.0883072 0.995151 + outer loop + vertex -734.729 230.111 362.689 + vertex -745.993 240.825 363.149 + vertex -745.048 235.187 362.69 + endloop + endfacet + facet normal -0.0182316 -0.0373072 0.999138 + outer loop + vertex -734.729 230.111 362.689 + vertex -745.048 235.187 362.69 + vertex -734.469 224.69 362.491 + endloop + endfacet + facet normal -0.045577 -0.0886745 0.995017 + outer loop + vertex -745.993 240.825 363.149 + vertex -756.199 246.07 363.149 + vertex -745.048 235.187 362.69 + endloop + endfacet + facet normal -0.0455971 -0.088695 0.995015 + outer loop + vertex -745.048 235.187 362.69 + vertex -756.199 246.07 363.149 + vertex -755.212 240.412 362.69 + endloop + endfacet + facet normal -0.0193704 -0.0376724 0.999102 + outer loop + vertex -745.048 235.187 362.69 + vertex -755.212 240.412 362.69 + vertex -744.787 229.766 362.491 + endloop + endfacet + facet normal -0.0478936 -0.0890838 0.994872 + outer loop + vertex -756.199 246.07 363.149 + vertex -766.128 251.409 363.149 + vertex -755.212 240.412 362.69 + endloop + endfacet + facet normal -0.0477832 -0.0889748 0.994887 + outer loop + vertex -755.212 240.412 362.69 + vertex -766.128 251.409 363.149 + vertex -765.144 245.747 362.69 + endloop + endfacet + facet normal -0.0203187 -0.0378411 0.999077 + outer loop + vertex -755.212 240.412 362.69 + vertex -765.144 245.747 362.69 + vertex -754.949 234.988 362.49 + endloop + endfacet + facet normal -0.0502373 -0.0893882 0.994729 + outer loop + vertex -766.128 251.409 363.149 + vertex -775.557 256.708 363.149 + vertex -765.144 245.747 362.69 + endloop + endfacet + facet normal -0.0502524 -0.0894024 0.994727 + outer loop + vertex -765.144 245.747 362.69 + vertex -775.557 256.708 363.149 + vertex -774.958 251.264 362.69 + endloop + endfacet + facet normal -0.0212403 -0.0377975 0.99906 + outer loop + vertex -765.144 245.747 362.69 + vertex -774.958 251.264 362.69 + vertex -764.913 240.345 362.491 + endloop + endfacet + facet normal -0.052812 -0.0896712 0.99457 + outer loop + vertex -775.557 256.708 363.149 + vertex -785.918 262.81 363.149 + vertex -774.958 251.264 362.69 + endloop + endfacet + facet normal -0.0527281 -0.0895919 0.994582 + outer loop + vertex -774.958 251.264 362.69 + vertex -785.918 262.81 363.149 + vertex -784.584 256.928 362.69 + endloop + endfacet + facet normal -0.0222867 -0.0378617 0.999034 + outer loop + vertex -774.958 251.264 362.69 + vertex -784.584 256.928 362.69 + vertex -774.681 245.839 362.491 + endloop + endfacet + facet normal -0.0559026 -0.0902937 0.994345 + outer loop + vertex -785.918 262.81 363.149 + vertex -794.808 268.314 363.149 + vertex -784.584 256.928 362.69 + endloop + endfacet + facet normal -0.0558195 -0.0902195 0.994356 + outer loop + vertex -784.584 256.928 362.69 + vertex -794.808 268.314 363.149 + vertex -794.043 262.778 362.69 + endloop + endfacet + facet normal -0.0235402 -0.0380263 0.998999 + outer loop + vertex -784.584 256.928 362.69 + vertex -794.043 262.778 362.69 + vertex -784.287 251.489 362.49 + endloop + endfacet + facet normal -0.0593663 -0.0906888 0.994108 + outer loop + vertex -794.808 268.314 363.149 + vertex -804.488 274.651 363.149 + vertex -794.043 262.778 362.69 + endloop + endfacet + facet normal -0.0592463 -0.0905839 0.994125 + outer loop + vertex -794.043 262.778 362.69 + vertex -804.488 274.651 363.149 + vertex -803.439 268.919 362.69 + endloop + endfacet + facet normal -0.0249819 -0.0381584 0.998959 + outer loop + vertex -794.043 262.778 362.69 + vertex -803.439 268.919 362.69 + vertex -793.784 257.354 362.489 + endloop + endfacet + facet normal -0.0638001 -0.091389 0.993769 + outer loop + vertex -804.488 274.651 363.149 + vertex -813.474 280.924 363.149 + vertex -803.439 268.919 362.69 + endloop + endfacet + facet normal -0.0640544 -0.0916002 0.993734 + outer loop + vertex -803.439 268.919 362.69 + vertex -813.474 280.924 363.149 + vertex -812.734 275.411 362.689 + endloop + endfacet + facet normal -0.0267385 -0.0381712 0.998913 + outer loop + vertex -803.439 268.919 362.69 + vertex -812.734 275.411 362.689 + vertex -803.184 263.48 362.489 + endloop + endfacet + facet normal -0.0693981 -0.0922819 0.993312 + outer loop + vertex -813.474 280.924 363.149 + vertex -823.083 288.15 363.149 + vertex -812.734 275.411 362.689 + endloop + endfacet + facet normal -0.0704374 -0.0931207 0.99316 + outer loop + vertex -812.734 275.411 362.689 + vertex -823.083 288.15 363.149 + vertex -821.793 282.262 362.689 + endloop + endfacet + facet normal -0.0288869 -0.038179 0.998853 + outer loop + vertex -812.734 275.411 362.689 + vertex -821.793 282.262 362.689 + vertex -812.448 269.947 362.488 + endloop + endfacet + facet normal -0.0772517 -0.0945631 0.992517 + outer loop + vertex -823.083 288.15 363.149 + vertex -831.315 294.875 363.149 + vertex -821.793 282.262 362.689 + endloop + endfacet + facet normal -0.0787636 -0.0956963 0.99229 + outer loop + vertex -821.793 282.262 362.689 + vertex -831.315 294.875 363.149 + vertex -830.467 289.432 362.692 + endloop + endfacet + facet normal -0.0314079 -0.0384064 0.998768 + outer loop + vertex -821.793 282.262 362.689 + vertex -830.467 289.432 362.692 + vertex -821.505 276.84 362.489 + endloop + endfacet + facet normal -0.0864952 -0.0968373 0.991535 + outer loop + vertex -831.315 294.875 363.149 + vertex -839.452 302.143 363.149 + vertex -830.467 289.432 362.692 + endloop + endfacet + facet normal -0.0834794 -0.0947223 0.991997 + outer loop + vertex -830.467 289.432 362.692 + vertex -839.452 302.143 363.149 + vertex -838.741 296.758 362.695 + endloop + endfacet + facet normal -0.0172841 -0.0643993 0.997775 + outer loop + vertex -598.068 183.913 363.149 + vertex -593.684 174.439 362.614 + vertex -584.676 173.037 362.679 + endloop + endfacet + facet normal -0.0205852 -0.0684499 0.997442 + outer loop + vertex -585.973 180.276 363.149 + vertex -598.068 183.913 363.149 + vertex -584.676 173.037 362.679 + endloop + endfacet + facet normal -0.0188818 -0.068148 0.997497 + outer loop + vertex -573.344 170.019 362.688 + vertex -585.973 180.276 363.149 + vertex -584.676 173.037 362.679 + endloop + endfacet + facet normal -0.0110351 -0.0386874 0.99919 + outer loop + vertex -573.344 170.019 362.688 + vertex -584.676 173.037 362.679 + vertex -573.206 163.365 362.432 + endloop + endfacet + facet normal -0.0114384 -0.0386956 0.999186 + outer loop + vertex -561.336 160.076 362.44 + vertex -573.344 170.019 362.688 + vertex -573.206 163.365 362.432 + endloop + endfacet + facet normal -0.0155518 -0.0535429 0.998444 + outer loop + vertex -561.336 160.076 362.44 + vertex -573.206 163.365 362.432 + vertex -561.545 153.571 362.088 + endloop + endfacet + facet normal -0.0114062 -0.0386567 0.999187 + outer loop + vertex -561.359 166.632 362.693 + vertex -573.344 170.019 362.688 + vertex -561.336 160.076 362.44 + endloop + endfacet + facet normal -0.0117035 -0.0386576 0.999184 + outer loop + vertex -549 156.611 362.451 + vertex -561.359 166.632 362.693 + vertex -561.336 160.076 362.44 + endloop + endfacet + facet normal -0.0158333 -0.0533627 0.99845 + outer loop + vertex -549 156.611 362.451 + vertex -561.336 160.076 362.44 + vertex -549.15 150.075 362.099 + endloop + endfacet + facet normal -0.0111131 -0.0379302 0.999219 + outer loop + vertex -549.234 163.231 362.699 + vertex -561.359 166.632 362.693 + vertex -549 156.611 362.451 + endloop + endfacet + facet normal -0.0109372 -0.0379241 0.999221 + outer loop + vertex -536.74 153.215 362.456 + vertex -549.234 163.231 362.699 + vertex -549 156.611 362.451 + endloop + endfacet + facet normal -0.0150068 -0.0526179 0.998502 + outer loop + vertex -536.74 153.215 362.456 + vertex -549 156.611 362.451 + vertex -536.743 146.636 362.109 + endloop + endfacet + facet normal -0.0100525 -0.0368218 0.999271 + outer loop + vertex -537.025 159.858 362.698 + vertex -549.234 163.231 362.699 + vertex -536.74 153.215 362.456 + endloop + endfacet + facet normal -0.00898034 -0.036776 0.999283 + outer loop + vertex -524.746 149.911 362.442 + vertex -537.025 159.858 362.698 + vertex -536.74 153.215 362.456 + endloop + endfacet + facet normal -0.0130122 -0.0514073 0.998593 + outer loop + vertex -524.746 149.911 362.442 + vertex -536.74 153.215 362.456 + vertex -524.657 143.318 362.104 + endloop + endfacet + facet normal -0.00859543 -0.0363014 0.999304 + outer loop + vertex -524.941 156.56 362.682 + vertex -537.025 159.858 362.698 + vertex -524.746 149.911 362.442 + endloop + endfacet + facet normal -0.00731986 -0.0362643 0.999315 + outer loop + vertex -512.872 146.693 362.412 + vertex -524.941 156.56 362.682 + vertex -524.746 149.911 362.442 + endloop + endfacet + facet normal -0.0111224 -0.0502909 0.998673 + outer loop + vertex -512.872 146.693 362.412 + vertex -524.746 149.911 362.442 + vertex -512.853 140.098 362.08 + endloop + endfacet + facet normal -0.00808075 -0.0371939 0.999275 + outer loop + vertex -512.865 153.366 362.661 + vertex -524.941 156.56 362.682 + vertex -512.872 146.693 362.412 + endloop + endfacet + facet normal -0.00853399 -0.0371932 0.999272 + outer loop + vertex -500.717 143.654 362.403 + vertex -512.865 153.366 362.661 + vertex -512.872 146.693 362.412 + endloop + endfacet + facet normal -0.0115613 -0.0492963 0.998717 + outer loop + vertex -500.717 143.654 362.403 + vertex -512.872 146.693 362.412 + vertex -500.95 137.043 362.074 + endloop + endfacet + facet normal -0.0166685 -0.069648 0.997432 + outer loop + vertex -512.865 153.366 362.661 + vertex -525.318 163.345 363.149 + vertex -524.941 156.56 362.682 + endloop + endfacet + facet normal -0.0185279 -0.0697484 0.997393 + outer loop + vertex -525.318 163.345 363.149 + vertex -537.373 166.548 363.149 + vertex -524.941 156.56 362.682 + endloop + endfacet + facet normal -0.0187783 -0.0722697 0.997208 + outer loop + vertex -513.11 160.173 363.149 + vertex -525.318 163.345 363.149 + vertex -512.865 153.366 362.661 + endloop + endfacet + facet normal -0.0178055 -0.072236 0.997229 + outer loop + vertex -500.563 150.358 362.662 + vertex -513.11 160.173 363.149 + vertex -512.865 153.366 362.661 + endloop + endfacet + facet normal -0.0186839 -0.0733541 0.997131 + outer loop + vertex -501.811 157.295 363.149 + vertex -513.11 160.173 363.149 + vertex -500.563 150.358 362.662 + endloop + endfacet + facet normal -0.0173165 -0.0682464 0.997518 + outer loop + vertex -524.941 156.56 362.682 + vertex -537.373 166.548 363.149 + vertex -537.025 159.858 362.698 + endloop + endfacet + facet normal -0.0185902 -0.0683107 0.997491 + outer loop + vertex -537.373 166.548 363.149 + vertex -550.186 170.035 363.149 + vertex -537.025 159.858 362.698 + endloop + endfacet + facet normal -0.0188412 -0.0686341 0.997464 + outer loop + vertex -537.025 159.858 362.698 + vertex -550.186 170.035 363.149 + vertex -549.234 163.231 362.699 + endloop + endfacet + facet normal -0.0191751 -0.0686802 0.997454 + outer loop + vertex -550.186 170.035 363.149 + vertex -562.366 173.435 363.149 + vertex -549.234 163.231 362.699 + endloop + endfacet + facet normal -0.0200515 -0.0698039 0.997359 + outer loop + vertex -549.234 163.231 362.699 + vertex -562.366 173.435 363.149 + vertex -561.359 166.632 362.693 + endloop + endfacet + facet normal -0.0199608 -0.0697907 0.997362 + outer loop + vertex -562.366 173.435 363.149 + vertex -573.466 176.61 363.149 + vertex -561.359 166.632 362.693 + endloop + endfacet + facet normal -0.020331 -0.0702381 0.997323 + outer loop + vertex -561.359 166.632 362.693 + vertex -573.466 176.61 363.149 + vertex -573.344 170.019 362.688 + endloop + endfacet + facet normal -0.0111151 -0.0387821 0.999186 + outer loop + vertex -573.206 163.365 362.432 + vertex -584.676 173.037 362.679 + vertex -583.788 165.964 362.415 + endloop + endfacet + facet normal -0.0148418 -0.0539616 0.998433 + outer loop + vertex -573.206 163.365 362.432 + vertex -583.788 165.964 362.415 + vertex -573.271 156.809 362.076 + endloop + endfacet + facet normal -0.0205894 -0.0702424 0.997317 + outer loop + vertex -573.466 176.61 363.149 + vertex -585.973 180.276 363.149 + vertex -573.344 170.019 362.688 + endloop + endfacet + facet normal -0.0133518 -0.0390615 0.999148 + outer loop + vertex -583.788 165.964 362.415 + vertex -584.676 173.037 362.679 + vertex -593.684 174.439 362.614 + endloop + endfacet + facet normal -0.0133235 -0.0382947 0.999178 + outer loop + vertex -601.963 180.565 362.731 + vertex -609.566 182.488 362.703 + vertex -601.135 175.213 362.537 + endloop + endfacet + facet normal -0.0113765 -0.0367577 0.999259 + outer loop + vertex -593.684 174.439 362.614 + vertex -592.728 167.737 362.378 + vertex -583.788 165.964 362.415 + endloop + endfacet + facet normal -0.0152569 -0.0563431 0.998295 + outer loop + vertex -583.688 159.424 362.047 + vertex -583.788 165.964 362.415 + vertex -592.728 167.737 362.378 + endloop + endfacet + facet normal -0.0129789 -0.0378959 0.999197 + outer loop + vertex -601.135 175.213 362.537 + vertex -609.566 182.488 362.703 + vertex -609.204 177.006 362.5 + endloop + endfacet + facet normal -0.0130162 -0.0384212 0.999177 + outer loop + vertex -609.204 177.006 362.5 + vertex -618.901 185.156 362.687 + vertex -618.364 179.557 362.479 + endloop + endfacet + facet normal -0.0131195 -0.0391631 0.999147 + outer loop + vertex -618.364 179.557 362.479 + vertex -629.177 188.376 362.683 + vertex -628.612 182.782 362.471 + endloop + endfacet + facet normal -0.0122899 -0.0384212 0.999186 + outer loop + vertex -628.612 182.782 362.471 + vertex -639.908 191.956 362.685 + vertex -639.558 186.478 362.478 + endloop + endfacet + facet normal -0.0122848 -0.0377094 0.999213 + outer loop + vertex -639.558 186.478 362.478 + vertex -650.727 195.722 362.69 + vertex -650.605 190.353 362.489 + endloop + endfacet + facet normal -0.0129472 -0.037379 0.999217 + outer loop + vertex -650.605 190.353 362.489 + vertex -661.523 199.595 362.693 + vertex -661.419 194.239 362.494 + endloop + endfacet + facet normal -0.0139455 -0.0374835 0.9992 + outer loop + vertex -661.419 194.239 362.494 + vertex -672.203 203.543 362.692 + vertex -671.993 198.143 362.493 + endloop + endfacet + facet normal -0.0148628 -0.0378543 0.999173 + outer loop + vertex -671.993 198.143 362.493 + vertex -682.741 207.577 362.69 + vertex -682.457 202.144 362.489 + endloop + endfacet + facet normal -0.0149677 -0.0376445 0.999179 + outer loop + vertex -682.457 202.144 362.489 + vertex -693.141 211.716 362.689 + vertex -692.898 206.299 362.489 + endloop + endfacet + facet normal -0.0155083 -0.0375695 0.999174 + outer loop + vertex -692.898 206.299 362.489 + vertex -703.549 216.032 362.689 + vertex -703.309 210.617 362.49 + endloop + endfacet + facet normal -0.0161436 -0.0375336 0.999165 + outer loop + vertex -703.309 210.617 362.49 + vertex -713.933 220.522 362.69 + vertex -713.694 215.109 362.491 + endloop + endfacet + facet normal -0.0172106 -0.0379655 0.999131 + outer loop + vertex -713.694 215.109 362.491 + vertex -724.325 225.212 362.691 + vertex -724.08 219.796 362.49 + endloop + endfacet + facet normal -0.0174002 -0.0372678 0.999154 + outer loop + vertex -724.08 219.796 362.49 + vertex -734.729 230.111 362.689 + vertex -734.469 224.69 362.491 + endloop + endfacet + facet normal -0.0185561 -0.0376339 0.999119 + outer loop + vertex -734.469 224.69 362.491 + vertex -745.048 235.187 362.69 + vertex -744.787 229.766 362.491 + endloop + endfacet + facet normal -0.019503 -0.0378021 0.999095 + outer loop + vertex -744.787 229.766 362.491 + vertex -755.212 240.412 362.69 + vertex -754.949 234.988 362.49 + endloop + endfacet + facet normal -0.0202276 -0.0377549 0.999082 + outer loop + vertex -754.949 234.988 362.49 + vertex -765.144 245.747 362.69 + vertex -764.913 240.345 362.491 + endloop + endfacet + facet normal -0.0212539 -0.03781 0.999059 + outer loop + vertex -764.913 240.345 362.491 + vertex -774.958 251.264 362.69 + vertex -774.681 245.839 362.491 + endloop + endfacet + facet normal -0.0224028 -0.0379653 0.999028 + outer loop + vertex -774.681 245.839 362.491 + vertex -784.584 256.928 362.69 + vertex -784.287 251.489 362.49 + endloop + endfacet + facet normal -0.0236194 -0.0380946 0.998995 + outer loop + vertex -784.287 251.489 362.49 + vertex -794.043 262.778 362.69 + vertex -793.784 257.354 362.489 + endloop + endfacet + facet normal -0.0248963 -0.0380869 0.998964 + outer loop + vertex -793.784 257.354 362.489 + vertex -803.439 268.919 362.69 + vertex -803.184 263.48 362.489 + endloop + endfacet + facet normal -0.0266015 -0.0380616 0.998921 + outer loop + vertex -803.184 263.48 362.489 + vertex -812.734 275.411 362.689 + vertex -812.448 269.947 362.488 + endloop + endfacet + facet normal -0.0290232 -0.0382823 0.998845 + outer loop + vertex -812.448 269.947 362.488 + vertex -821.793 282.262 362.689 + vertex -821.505 276.84 362.489 + endloop + endfacet + facet normal -0.0306908 -0.0378967 0.99881 + outer loop + vertex -821.505 276.84 362.489 + vertex -830.467 289.432 362.692 + vertex -830.329 284.193 362.497 + endloop + endfacet + facet normal -0.0303078 -0.0351163 0.998924 + outer loop + vertex -830.419 278.994 362.315 + vertex -838.904 291.682 362.503 + vertex -839.186 286.523 362.313 + endloop + endfacet + facet normal -0.0498134 -0.0578289 0.997083 + outer loop + vertex -830.419 278.994 362.315 + vertex -839.186 286.523 362.313 + vertex -830.507 273.637 362 + endloop + endfacet + facet normal -0.0320819 -0.0350177 0.998872 + outer loop + vertex -838.904 291.682 362.503 + vertex -847.383 299.003 362.487 + vertex -839.186 286.523 362.313 + endloop + endfacet + facet normal -0.0352513 -0.037097 0.99869 + outer loop + vertex -839.186 286.523 362.313 + vertex -847.383 299.003 362.487 + vertex -847.597 293.307 362.268 + endloop + endfacet + facet normal -0.0527962 -0.0588616 0.996869 + outer loop + vertex -839.186 286.523 362.313 + vertex -847.597 293.307 362.268 + vertex -839.161 280.861 361.98 + endloop + endfacet + facet normal -0.0615302 -0.064761 0.996002 + outer loop + vertex -839.161 280.861 361.98 + vertex -847.597 293.307 362.268 + vertex -846.963 286.987 361.897 + endloop + endfacet + facet normal -0.0600733 -0.0646206 0.9961 + outer loop + vertex -846.963 286.987 361.897 + vertex -847.597 293.307 362.268 + vertex -852.241 295.304 362.118 + endloop + endfacet + facet normal -0.0378691 -0.0369954 0.998598 + outer loop + vertex -847.597 293.307 362.268 + vertex -847.383 299.003 362.487 + vertex -852.942 302.24 362.397 + endloop + endfacet + facet normal -0.0332219 -0.0379604 0.998727 + outer loop + vertex -830.467 289.432 362.692 + vertex -838.741 296.758 362.695 + vertex -830.329 284.193 362.497 + endloop + endfacet + facet normal -0.028425 -0.0307817 0.999122 + outer loop + vertex -838.904 291.682 362.503 + vertex -846.184 302.981 362.644 + vertex -847.383 299.003 362.487 + endloop + endfacet + facet normal -0.034334 -0.0289947 0.99899 + outer loop + vertex -847.383 299.003 362.487 + vertex -846.184 302.981 362.644 + vertex -851.473 306.613 362.568 + endloop + endfacet + facet normal -0.0949958 -0.0961429 0.990824 + outer loop + vertex -839.452 302.143 363.149 + vertex -846.979 309.581 363.149 + vertex -838.741 296.758 362.695 + endloop + endfacet + facet normal -0.0898638 -0.0660293 0.993763 + outer loop + vertex -858.663 323.092 363.149 + vertex -862.642 319.104 362.525 + vertex -856.669 310.634 362.502 + endloop + endfacet + facet normal -0.0540529 -0.0407844 0.997705 + outer loop + vertex -862.642 319.104 362.525 + vertex -862.143 311.219 362.229 + vertex -856.669 310.634 362.502 + endloop + endfacet + facet normal -0.0595001 -0.0411171 0.997381 + outer loop + vertex -862.642 319.104 362.525 + vertex -866.81 316.213 362.157 + vertex -862.143 311.219 362.229 + endloop + endfacet + facet normal -0.059907 -0.0405304 0.997381 + outer loop + vertex -867.197 325.088 362.494 + vertex -866.81 316.213 362.157 + vertex -862.642 319.104 362.525 + endloop + endfacet + facet normal -0.0937434 -0.0663069 0.993386 + outer loop + vertex -863.052 329.044 363.149 + vertex -867.197 325.088 362.494 + vertex -862.642 319.104 362.525 + endloop + endfacet + facet normal -0.0960321 -0.063898 0.993325 + outer loop + vertex -867.19 335.264 363.149 + vertex -867.197 325.088 362.494 + vertex -863.052 329.044 363.149 + endloop + endfacet + facet normal -0.0983402 -0.0638819 0.9931 + outer loop + vertex -867.19 335.264 363.149 + vertex -871.334 331.234 362.48 + vertex -867.197 325.088 362.494 + endloop + endfacet + facet normal -0.0618909 -0.039341 0.997307 + outer loop + vertex -871.334 331.234 362.48 + vertex -871.443 322.049 362.111 + vertex -867.197 325.088 362.494 + endloop + endfacet + facet normal -0.0641342 -0.0393087 0.997167 + outer loop + vertex -871.334 331.234 362.48 + vertex -876.128 328.864 362.078 + vertex -871.443 322.049 362.111 + endloop + endfacet + facet normal -0.065146 -0.0372637 0.99718 + outer loop + vertex -874.893 337.829 362.494 + vertex -876.128 328.864 362.078 + vertex -871.334 331.234 362.48 + endloop + endfacet + facet normal -0.107685 -0.060212 0.99236 + outer loop + vertex -870.922 341.532 363.149 + vertex -874.893 337.829 362.494 + vertex -871.334 331.234 362.48 + endloop + endfacet + facet normal -0.109862 -0.0578594 0.992261 + outer loop + vertex -874.318 347.981 363.149 + vertex -874.893 337.829 362.494 + vertex -870.922 341.532 363.149 + endloop + endfacet + facet normal -0.115937 -0.0574722 0.991592 + outer loop + vertex -874.318 347.981 363.149 + vertex -877.989 344.345 362.509 + vertex -874.893 337.829 362.494 + endloop + endfacet + facet normal -0.0682671 -0.034834 0.997059 + outer loop + vertex -877.989 344.345 362.509 + vertex -878.658 336.491 362.189 + vertex -874.893 337.829 362.494 + endloop + endfacet + facet normal -0.072398 -0.0344707 0.99678 + outer loop + vertex -877.989 344.345 362.509 + vertex -881.759 341.751 362.146 + vertex -878.658 336.491 362.189 + endloop + endfacet + facet normal -0.0742509 -0.0317714 0.996733 + outer loop + vertex -880.948 350.805 362.495 + vertex -881.759 341.751 362.146 + vertex -877.989 344.345 362.509 + endloop + endfacet + facet normal -0.123076 -0.0541504 0.990919 + outer loop + vertex -877.309 354.51 363.149 + vertex -880.948 350.805 362.495 + vertex -877.989 344.345 362.509 + endloop + endfacet + facet normal -0.127549 -0.0496983 0.990586 + outer loop + vertex -879.899 361.158 363.149 + vertex -880.948 350.805 362.495 + vertex -877.309 354.51 363.149 + endloop + endfacet + facet normal -0.134695 -0.0489169 0.989679 + outer loop + vertex -879.899 361.158 363.149 + vertex -883.642 357.707 362.469 + vertex -880.948 350.805 362.495 + endloop + endfacet + facet normal -0.0816826 -0.0282021 0.996259 + outer loop + vertex -883.642 357.707 362.469 + vertex -884.908 348.527 362.106 + vertex -880.948 350.805 362.495 + endloop + endfacet + facet normal -0.0882969 -0.0272689 0.995721 + outer loop + vertex -883.642 357.707 362.469 + vertex -887.985 356.173 362.042 + vertex -884.908 348.527 362.106 + endloop + endfacet + facet normal -0.088969 -0.0253634 0.995711 + outer loop + vertex -885.783 365.101 362.466 + vertex -887.985 356.173 362.042 + vertex -883.642 357.707 362.469 + endloop + endfacet + facet normal -0.149421 -0.0428711 0.987844 + outer loop + vertex -882.015 367.705 363.149 + vertex -885.783 365.101 362.466 + vertex -883.642 357.707 362.469 + endloop + endfacet + facet normal -0.151979 -0.0391072 0.98761 + outer loop + vertex -883.773 374.538 363.149 + vertex -885.783 365.101 362.466 + vertex -882.015 367.705 363.149 + endloop + endfacet + facet normal -0.169899 -0.0350899 0.984837 + outer loop + vertex -883.773 374.538 363.149 + vertex -887.267 372.531 362.475 + vertex -885.783 365.101 362.466 + endloop + endfacet + facet normal -0.171137 -0.032889 0.984698 + outer loop + vertex -885.029 381.068 363.149 + vertex -887.267 372.531 362.475 + vertex -883.773 374.538 363.149 + endloop + endfacet + facet normal -0.192653 -0.0269482 0.980897 + outer loop + vertex -885.029 381.068 363.149 + vertex -888.231 379.713 362.483 + vertex -887.267 372.531 362.475 + endloop + endfacet + facet normal -0.193585 -0.0246844 0.980773 + outer loop + vertex -885.881 387.756 363.149 + vertex -888.231 379.713 362.483 + vertex -885.029 381.068 363.149 + endloop + endfacet + facet normal -0.223585 -0.0154073 0.974563 + outer loop + vertex -885.881 387.756 363.149 + vertex -888.718 386.742 362.483 + vertex -888.231 379.713 362.483 + endloop + endfacet + facet normal -0.224103 -0.013896 0.974466 + outer loop + vertex -886.287 394.297 363.149 + vertex -888.718 386.742 362.483 + vertex -885.881 387.756 363.149 + endloop + endfacet + facet normal -0.261876 -0.000914526 0.965101 + outer loop + vertex -886.287 394.297 363.149 + vertex -888.713 393.764 362.491 + vertex -888.718 386.742 362.483 + endloop + endfacet + facet normal -0.262183 0.000584969 0.965018 + outer loop + vertex -886.271 401.273 363.149 + vertex -888.713 393.764 362.491 + vertex -886.287 394.297 363.149 + endloop + endfacet + facet normal -0.310011 0.0174051 0.950574 + outer loop + vertex -886.271 401.273 363.149 + vertex -888.3 400.491 362.502 + vertex -888.713 393.764 362.491 + endloop + endfacet + facet normal -0.310301 0.0182478 0.950463 + outer loop + vertex -885.917 407.302 363.149 + vertex -888.3 400.491 362.502 + vertex -886.271 401.273 363.149 + endloop + endfacet + facet normal -0.359873 0.0373219 0.932255 + outer loop + vertex -885.917 407.302 363.149 + vertex -887.643 406.944 362.497 + vertex -888.3 400.491 362.502 + endloop + endfacet + facet normal -0.360099 0.038672 0.932112 + outer loop + vertex -885.243 413.58 363.149 + vertex -887.643 406.944 362.497 + vertex -885.917 407.302 363.149 + endloop + endfacet + facet normal -0.422153 0.0638509 0.904273 + outer loop + vertex -885.243 413.58 363.149 + vertex -886.691 413.348 362.49 + vertex -887.643 406.944 362.497 + endloop + endfacet + facet normal -0.422089 0.0632457 0.904345 + outer loop + vertex -884.4 419.202 363.149 + vertex -886.691 413.348 362.49 + vertex -885.243 413.58 363.149 + endloop + endfacet + facet normal -0.488643 0.0934405 0.867466 + outer loop + vertex -884.4 419.202 363.149 + vertex -885.49 419.609 362.492 + vertex -886.691 413.348 362.49 + endloop + endfacet + facet normal -0.489239 0.0916175 0.867324 + outer loop + vertex -883.225 425.478 363.149 + vertex -885.49 419.609 362.492 + vertex -884.4 419.202 363.149 + endloop + endfacet + facet normal -0.550604 0.119916 0.826108 + outer loop + vertex -883.225 425.478 363.149 + vertex -884.151 425.852 362.478 + vertex -885.49 419.609 362.492 + endloop + endfacet + facet normal -0.550388 0.120547 0.826161 + outer loop + vertex -881.919 431.438 363.149 + vertex -884.151 425.852 362.478 + vertex -883.225 425.478 363.149 + endloop + endfacet + facet normal -0.597638 0.143922 0.788743 + outer loop + vertex -881.919 431.438 363.149 + vertex -882.54 432.472 362.491 + vertex -884.151 425.852 362.478 + endloop + endfacet + facet normal -0.598345 0.143235 0.788332 + outer loop + vertex -880.522 437.276 363.149 + vertex -882.54 432.472 362.491 + vertex -881.919 431.438 363.149 + endloop + endfacet + facet normal -0.637849 0.164765 0.75233 + outer loop + vertex -880.522 437.276 363.149 + vertex -880.74 439.244 362.533 + vertex -882.54 432.472 362.491 + endloop + endfacet + facet normal -0.65071 0.160179 0.742239 + outer loop + vertex -879.149 442.852 363.149 + vertex -880.74 439.244 362.533 + vertex -880.522 437.276 363.149 + endloop + endfacet + facet normal -0.641193 0.154367 0.751693 + outer loop + vertex -879.149 442.852 363.149 + vertex -878.978 446.465 362.554 + vertex -880.74 439.244 362.533 + endloop + endfacet + facet normal -0.654013 0.153184 0.740812 + outer loop + vertex -877.646 449.271 363.149 + vertex -878.978 446.465 362.554 + vertex -879.149 442.852 363.149 + endloop + endfacet + facet normal -0.640759 0.144075 0.754102 + outer loop + vertex -877.646 449.271 363.149 + vertex -877.231 454.531 362.497 + vertex -878.978 446.465 362.554 + endloop + endfacet + facet normal -0.726531 0.140739 0.672566 + outer loop + vertex -876.423 455.607 363.145 + vertex -877.231 454.531 362.497 + vertex -877.646 449.271 363.149 + endloop + endfacet + facet normal -0.754877 0.188749 0.628119 + outer loop + vertex -877.231 454.531 362.497 + vertex -876.423 455.607 363.145 + vertex -875.757 460.532 362.465 + endloop + endfacet + facet normal -0.336389 0.0876357 0.937637 + outer loop + vertex -876.435 460.391 362.235 + vertex -877.231 454.531 362.497 + vertex -875.757 460.532 362.465 + endloop + endfacet + facet normal -0.990905 0.128546 -0.0397974 + outer loop + vertex -875.544 462.349 363.022 + vertex -875.757 460.532 362.465 + vertex -876.423 455.607 363.145 + endloop + endfacet + facet normal -0.0984342 -0.0229898 0.994878 + outer loop + vertex -885.783 365.101 362.466 + vertex -889.608 365.081 362.088 + vertex -887.985 356.173 362.042 + endloop + endfacet + facet normal -0.0984505 -0.0208335 0.994924 + outer loop + vertex -887.267 372.531 362.475 + vertex -889.608 365.081 362.088 + vertex -885.783 365.101 362.466 + endloop + endfacet + facet normal -0.109084 -0.0174371 0.99388 + outer loop + vertex -887.267 372.531 362.475 + vertex -890.691 372.854 362.105 + vertex -889.608 365.081 362.088 + endloop + endfacet + facet normal -0.108928 -0.0157259 0.993925 + outer loop + vertex -888.231 379.713 362.483 + vertex -890.691 372.854 362.105 + vertex -887.267 372.531 362.475 + endloop + endfacet + facet normal -0.123728 -0.0103264 0.992262 + outer loop + vertex -888.231 379.713 362.483 + vertex -891.29 380.295 362.108 + vertex -890.691 372.854 362.105 + endloop + endfacet + facet normal -0.12338 -0.00846074 0.992323 + outer loop + vertex -888.718 386.742 362.483 + vertex -891.29 380.295 362.108 + vertex -888.231 379.713 362.483 + endloop + endfacet + facet normal -0.139923 -0.00173602 0.990161 + outer loop + vertex -888.718 386.742 362.483 + vertex -891.341 387.709 362.114 + vertex -891.29 380.295 362.108 + endloop + endfacet + facet normal -0.139667 -0.00102914 0.990198 + outer loop + vertex -888.713 393.764 362.491 + vertex -891.341 387.709 362.114 + vertex -888.718 386.742 362.483 + endloop + endfacet + facet normal -0.159436 0.00773972 0.987178 + outer loop + vertex -888.713 393.764 362.491 + vertex -890.851 395.104 362.135 + vertex -891.341 387.709 362.114 + endloop + endfacet + facet normal -0.159229 0.00807724 0.987209 + outer loop + vertex -888.3 400.491 362.502 + vertex -890.851 395.104 362.135 + vertex -888.713 393.764 362.491 + endloop + endfacet + facet normal -0.180662 0.01849 0.983371 + outer loop + vertex -888.3 400.491 362.502 + vertex -889.953 401.448 362.181 + vertex -890.851 395.104 362.135 + endloop + endfacet + facet normal -0.18033 0.0190802 0.983421 + outer loop + vertex -887.643 406.944 362.497 + vertex -889.953 401.448 362.181 + vertex -888.3 400.491 362.502 + endloop + endfacet + facet normal -0.202117 0.0284955 0.978947 + outer loop + vertex -887.643 406.944 362.497 + vertex -889.469 407.811 362.095 + vertex -889.953 401.448 362.181 + endloop + endfacet + facet normal -0.200942 0.0310489 0.979111 + outer loop + vertex -886.691 413.348 362.49 + vertex -889.469 407.811 362.095 + vertex -887.643 406.944 362.497 + endloop + endfacet + facet normal -0.224636 0.0433403 0.973479 + outer loop + vertex -886.691 413.348 362.49 + vertex -887.793 414.792 362.171 + vertex -889.469 407.811 362.095 + endloop + endfacet + facet normal -0.225203 0.0428826 0.973368 + outer loop + vertex -885.49 419.609 362.492 + vertex -887.793 414.792 362.171 + vertex -886.691 413.348 362.49 + endloop + endfacet + facet normal -0.24243 0.051424 0.968805 + outer loop + vertex -885.49 419.609 362.492 + vertex -886.786 420.521 362.119 + vertex -887.793 414.792 362.171 + endloop + endfacet + facet normal -0.240824 0.0538185 0.969076 + outer loop + vertex -884.151 425.852 362.478 + vertex -886.786 420.521 362.119 + vertex -885.49 419.609 362.492 + endloop + endfacet + facet normal -0.255559 0.0613874 0.964843 + outer loop + vertex -884.151 425.852 362.478 + vertex -885.185 427.543 362.096 + vertex -886.786 420.521 362.119 + endloop + endfacet + facet normal -0.256736 0.0606091 0.964579 + outer loop + vertex -882.54 432.472 362.491 + vertex -885.185 427.543 362.096 + vertex -884.151 425.852 362.478 + endloop + endfacet + facet normal -0.265299 0.0654146 0.961945 + outer loop + vertex -882.54 432.472 362.491 + vertex -883.175 435.737 362.094 + vertex -885.185 427.543 362.096 + endloop + endfacet + facet normal -0.267246 0.0649742 0.961435 + outer loop + vertex -880.74 439.244 362.533 + vertex -883.175 435.737 362.094 + vertex -882.54 432.472 362.491 + endloop + endfacet + facet normal -0.272389 0.0687581 0.959727 + outer loop + vertex -880.74 439.244 362.533 + vertex -880.893 442.987 362.222 + vertex -883.175 435.737 362.094 + endloop + endfacet + facet normal -0.288639 0.0677046 0.955041 + outer loop + vertex -878.978 446.465 362.554 + vertex -880.893 442.987 362.222 + vertex -880.74 439.244 362.533 + endloop + endfacet + facet normal -0.287335 0.0669436 0.955488 + outer loop + vertex -878.978 446.465 362.554 + vertex -879.334 451.413 362.1 + vertex -880.893 442.987 362.222 + endloop + endfacet + facet normal -0.28093 0.0675754 0.957346 + outer loop + vertex -877.231 454.531 362.497 + vertex -879.334 451.413 362.1 + vertex -878.978 446.465 362.554 + endloop + endfacet + facet normal -0.282832 0.0689424 0.956688 + outer loop + vertex -879.334 451.413 362.1 + vertex -877.231 454.531 362.497 + vertex -877.595 458.141 362.13 + endloop + endfacet + facet normal -0.233995 0.0751552 0.969329 + outer loop + vertex -876.435 460.391 362.235 + vertex -877.595 458.141 362.13 + vertex -877.231 454.531 362.497 + endloop + endfacet + facet normal -0.138474 -0.044755 0.989354 + outer loop + vertex -882.015 367.705 363.149 + vertex -883.642 357.707 362.469 + vertex -879.899 361.158 363.149 + endloop + endfacet + facet normal -0.0799366 -0.0312459 0.99631 + outer loop + vertex -880.948 350.805 362.495 + vertex -884.908 348.527 362.106 + vertex -881.759 341.751 362.146 + endloop + endfacet + facet normal -0.118889 -0.0544617 0.991413 + outer loop + vertex -877.309 354.51 363.149 + vertex -877.989 344.345 362.509 + vertex -874.318 347.981 363.149 + endloop + endfacet + facet normal -0.0675203 -0.0369298 0.997034 + outer loop + vertex -874.893 337.829 362.494 + vertex -878.658 336.491 362.189 + vertex -876.128 328.864 362.078 + endloop + endfacet + facet normal -0.101616 -0.0604953 0.992983 + outer loop + vertex -870.922 341.532 363.149 + vertex -871.334 331.234 362.48 + vertex -867.19 335.264 363.149 + endloop + endfacet + facet normal -0.0610073 -0.0405758 0.997312 + outer loop + vertex -867.197 325.088 362.494 + vertex -871.443 322.049 362.111 + vertex -866.81 316.213 362.157 + endloop + endfacet + facet normal -0.089728 -0.0661654 0.993766 + outer loop + vertex -863.052 329.044 363.149 + vertex -862.642 319.104 362.525 + vertex -858.663 323.092 363.149 + endloop + endfacet + facet normal -0.0434716 -0.042321 0.998158 + outer loop + vertex -852.404 311.953 362.754 + vertex -851.473 306.613 362.568 + vertex -846.184 302.981 362.644 + endloop + endfacet + facet normal -0.0249618 -0.0239625 0.999401 + outer loop + vertex -851.473 306.613 362.568 + vertex -852.624 305.342 362.509 + vertex -847.383 299.003 362.487 + endloop + endfacet + facet normal -0.03522 -0.0324401 0.998853 + outer loop + vertex -852.624 305.342 362.509 + vertex -852.942 302.24 362.397 + vertex -847.383 299.003 362.487 + endloop + endfacet + facet normal -0.053895 -0.0392756 0.997774 + outer loop + vertex -856.669 310.634 362.502 + vertex -862.143 311.219 362.229 + vertex -857.478 302.566 362.141 + endloop + endfacet + facet normal -0.0353331 -0.0354801 0.998746 + outer loop + vertex -852.942 302.24 362.397 + vertex -852.986 298.846 362.275 + vertex -847.597 293.307 362.268 + endloop + endfacet + facet normal -0.0563623 -0.0559365 0.996842 + outer loop + vertex -852.986 298.846 362.275 + vertex -852.241 295.304 362.118 + vertex -847.597 293.307 362.268 + endloop + endfacet + facet normal -0.0737449 -0.0580383 0.995587 + outer loop + vertex -864.771 307.717 361.917 + vertex -864.434 302.617 361.645 + vertex -860.272 299.705 361.784 + endloop + endfacet + facet normal -0.0713371 -0.052199 0.996085 + outer loop + vertex -870.43 314.513 361.868 + vertex -868.976 308.835 361.675 + vertex -864.771 307.717 361.917 + endloop + endfacet + facet normal -0.0774232 -0.0509421 0.995696 + outer loop + vertex -874.922 320.593 361.83 + vertex -873.556 314.906 361.645 + vertex -870.43 314.513 361.868 + endloop + endfacet + facet normal -0.092848 -0.046706 0.994584 + outer loop + vertex -881.242 333.332 361.891 + vertex -881.359 328.15 361.637 + vertex -878.55 325.852 361.791 + endloop + endfacet + facet normal -0.095314 -0.0466392 0.994354 + outer loop + vertex -881.242 333.332 361.891 + vertex -884.843 335.578 361.651 + vertex -881.359 328.15 361.637 + endloop + endfacet + facet normal -0.0931817 -0.0431829 0.994712 + outer loop + vertex -885.126 341.001 361.86 + vertex -884.843 335.578 361.651 + vertex -881.242 333.332 361.891 + endloop + endfacet + facet normal -0.105013 -0.0437542 0.993508 + outer loop + vertex -885.126 341.001 361.86 + vertex -887.756 342.594 361.652 + vertex -884.843 335.578 361.651 + endloop + endfacet + facet normal -0.101367 -0.0376514 0.994136 + outer loop + vertex -888.046 347.899 361.824 + vertex -887.756 342.594 361.652 + vertex -885.126 341.001 361.86 + endloop + endfacet + facet normal -0.114646 -0.0383283 0.992667 + outer loop + vertex -888.046 347.899 361.824 + vertex -890 349.326 361.653 + vertex -887.756 342.594 361.652 + endloop + endfacet + facet normal -0.111771 -0.0343355 0.993141 + outer loop + vertex -890.243 353.469 361.769 + vertex -890 349.326 361.653 + vertex -888.046 347.899 361.824 + endloop + endfacet + facet normal -0.140728 -0.0359331 0.989396 + outer loop + vertex -890.243 353.469 361.769 + vertex -891.941 356.67 361.644 + vertex -890 349.326 361.653 + endloop + endfacet + facet normal -0.124042 -0.0269824 0.99191 + outer loop + vertex -891.296 360.05 361.816 + vertex -891.941 356.67 361.644 + vertex -890.243 353.469 361.769 + endloop + endfacet + facet normal -0.134337 -0.0249508 0.990621 + outer loop + vertex -891.296 360.05 361.816 + vertex -893.194 364.183 361.663 + vertex -891.941 356.67 361.644 + endloop + endfacet + facet normal -0.127096 -0.0215869 0.991655 + outer loop + vertex -892.433 367.756 361.838 + vertex -893.194 364.183 361.663 + vertex -891.296 360.05 361.816 + endloop + endfacet + facet normal -0.150196 -0.0165113 0.988518 + outer loop + vertex -892.433 367.756 361.838 + vertex -894.053 371.797 361.66 + vertex -893.194 364.183 361.663 + endloop + endfacet + facet normal -0.142922 -0.0135452 0.989641 + outer loop + vertex -893.091 375.481 361.849 + vertex -894.053 371.797 361.66 + vertex -892.433 367.756 361.838 + endloop + endfacet + facet normal -0.393205 -0.21643 0.893615 + outer loop + vertex -878.281 321.423 361.562 + vertex -879.765 324.131 361.565 + vertex -877.506 319.83 361.518 + endloop + endfacet + facet normal -0.271935 -0.158981 0.949092 + outer loop + vertex -877.47 320.039 361.563 + vertex -878.281 321.423 361.562 + vertex -877.506 319.83 361.518 + endloop + endfacet + facet normal -0.260012 -0.1617 0.95197 + outer loop + vertex -875.775 317.351 361.569 + vertex -877.47 320.039 361.563 + vertex -877.506 319.83 361.518 + endloop + endfacet + facet normal -0.08778 -0.0533985 0.994708 + outer loop + vertex -874.922 320.593 361.83 + vertex -877.667 321.327 361.627 + vertex -873.556 314.906 361.645 + endloop + endfacet + facet normal -0.362799 -0.221356 0.905195 + outer loop + vertex -874.15 314.695 361.571 + vertex -875.775 317.351 361.569 + vertex -873.366 313.151 361.508 + endloop + endfacet + facet normal -0.260212 -0.171171 0.950258 + outer loop + vertex -873.275 313.384 361.575 + vertex -874.15 314.695 361.571 + vertex -873.366 313.151 361.508 + endloop + endfacet + facet normal -0.0777738 -0.053828 0.995517 + outer loop + vertex -870.43 314.513 361.868 + vertex -873.556 314.906 361.645 + vertex -868.976 308.835 361.675 + endloop + endfacet + facet normal -0.214837 -0.152458 0.964677 + outer loop + vertex -869.267 307.794 361.58 + vertex -871.391 310.782 361.58 + vertex -868.807 306.517 361.481 + endloop + endfacet + facet normal -0.181523 -0.141131 0.973207 + outer loop + vertex -867.035 304.893 361.576 + vertex -869.267 307.794 361.58 + vertex -868.807 306.517 361.481 + endloop + endfacet + facet normal -0.072849 -0.0579828 0.995656 + outer loop + vertex -864.771 307.717 361.917 + vertex -868.976 308.835 361.675 + vertex -864.434 302.617 361.645 + endloop + endfacet + facet normal -0.0828502 -0.072246 0.99394 + outer loop + vertex -864.236 301.284 361.565 + vertex -862.345 299.023 361.558 + vertex -864.434 302.617 361.645 + endloop + endfacet + facet normal -0.0989108 -0.0853674 0.991428 + outer loop + vertex -862.345 299.023 361.558 + vertex -859.931 296.15 361.551 + vertex -860.757 297.775 361.609 + endloop + endfacet + facet normal -0.102497 -0.0889877 0.990745 + outer loop + vertex -859.931 296.15 361.551 + vertex -857.903 293.892 361.559 + vertex -858.83 295.082 361.57 + endloop + endfacet + facet normal -0.145973 -0.128162 0.980952 + outer loop + vertex -856.917 292.593 361.542 + vertex -859.842 295.619 361.502 + vertex -856.884 291.269 361.374 + endloop + endfacet + facet normal -0.159579 -0.137315 0.977588 + outer loop + vertex -856.884 291.269 361.374 + vertex -859.842 295.619 361.502 + vertex -860.739 295.014 361.271 + endloop + endfacet + facet normal -0.169127 -0.147228 0.974536 + outer loop + vertex -856.884 291.269 361.374 + vertex -860.739 295.014 361.271 + vertex -856.941 288.325 360.919 + endloop + endfacet + facet normal -0.158052 -0.147717 0.976319 + outer loop + vertex -852.69 285.078 361.116 + vertex -856.884 291.269 361.374 + vertex -856.941 288.325 360.919 + endloop + endfacet + facet normal -0.183042 -0.154933 0.97082 + outer loop + vertex -861.236 292.315 360.746 + vertex -856.941 288.325 360.919 + vertex -860.739 295.014 361.271 + endloop + endfacet + facet normal -0.187231 -0.154034 0.970164 + outer loop + vertex -860.739 295.014 361.271 + vertex -865.182 300.047 361.212 + vertex -861.236 292.315 360.746 + endloop + endfacet + facet normal -0.192818 -0.156792 0.968627 + outer loop + vertex -865.624 297.076 360.643 + vertex -861.236 292.315 360.746 + vertex -865.182 300.047 361.212 + endloop + endfacet + facet normal -0.203002 -0.154933 0.966843 + outer loop + vertex -865.182 300.047 361.212 + vertex -870.194 306.338 361.168 + vertex -865.624 297.076 360.643 + endloop + endfacet + facet normal -0.192614 -0.149973 0.969746 + outer loop + vertex -869.278 301.111 360.542 + vertex -865.624 297.076 360.643 + vertex -870.194 306.338 361.168 + endloop + endfacet + facet normal -0.214112 -0.153136 0.964731 + outer loop + vertex -873.922 309.224 360.799 + vertex -869.278 301.111 360.542 + vertex -870.194 306.338 361.168 + endloop + endfacet + facet normal -0.206063 -0.142304 0.968136 + outer loop + vertex -870.194 306.338 361.168 + vertex -874.744 314.105 361.341 + vertex -873.922 309.224 360.799 + endloop + endfacet + facet normal -0.231342 -0.145865 0.961876 + outer loop + vertex -874.744 314.105 361.341 + vertex -878.162 319.245 361.299 + vertex -873.922 309.224 360.799 + endloop + endfacet + facet normal -0.207994 -0.136322 0.968584 + outer loop + vertex -878.727 316.32 360.766 + vertex -873.922 309.224 360.799 + vertex -878.162 319.245 361.299 + endloop + endfacet + facet normal -0.230278 -0.131223 0.964237 + outer loop + vertex -878.162 319.245 361.299 + vertex -881.905 325.636 361.275 + vertex -878.727 316.32 360.766 + endloop + endfacet + facet normal -0.22057 -0.128059 0.966928 + outer loop + vertex -882.665 322.941 360.744 + vertex -878.727 316.32 360.766 + vertex -881.905 325.636 361.275 + endloop + endfacet + facet normal -0.244484 -0.12037 0.962153 + outer loop + vertex -881.905 325.636 361.275 + vertex -885.262 332.22 361.245 + vertex -882.665 322.941 360.744 + endloop + endfacet + facet normal -0.234501 -0.117728 0.964961 + outer loop + vertex -886.012 329.298 360.706 + vertex -882.665 322.941 360.744 + vertex -885.262 332.22 361.245 + endloop + endfacet + facet normal -0.263774 -0.109006 0.958405 + outer loop + vertex -885.262 332.22 361.245 + vertex -888.436 339.532 361.203 + vertex -886.012 329.298 360.706 + endloop + endfacet + facet normal -0.247959 -0.105484 0.963011 + outer loop + vertex -888.488 334.144 360.6 + vertex -886.012 329.298 360.706 + vertex -888.436 339.532 361.203 + endloop + endfacet + facet normal -0.296431 -0.103488 0.949431 + outer loop + vertex -890.778 342.661 360.813 + vertex -888.488 334.144 360.6 + vertex -888.436 339.532 361.203 + endloop + endfacet + facet normal -0.287184 -0.0961165 0.953041 + outer loop + vertex -888.436 339.532 361.203 + vertex -890.636 347.641 361.358 + vertex -890.778 342.661 360.813 + endloop + endfacet + facet normal -0.338465 -0.0928384 0.936388 + outer loop + vertex -890.636 347.641 361.358 + vertex -892.172 352.613 361.296 + vertex -890.778 342.661 360.813 + endloop + endfacet + facet normal -0.30994 -0.0893365 0.94655 + outer loop + vertex -893.049 349.866 360.75 + vertex -890.778 342.661 360.813 + vertex -892.172 352.613 361.296 + endloop + endfacet + facet normal -0.34819 -0.0747122 0.934442 + outer loop + vertex -892.172 352.613 361.296 + vertex -893.619 358.986 361.266 + vertex -893.049 349.866 360.75 + endloop + endfacet + facet normal -0.338534 -0.0743115 0.938015 + outer loop + vertex -894.568 356.558 360.732 + vertex -893.049 349.866 360.75 + vertex -893.619 358.986 361.266 + endloop + endfacet + facet normal -0.378675 -0.0555094 0.923863 + outer loop + vertex -893.619 358.986 361.266 + vertex -894.597 365.544 361.259 + vertex -894.568 356.558 360.732 + endloop + endfacet + facet normal -0.382563 -0.0554283 0.922265 + outer loop + vertex -895.524 363.077 360.726 + vertex -894.568 356.558 360.732 + vertex -894.597 365.544 361.259 + endloop + endfacet + facet normal -0.42976 -0.0333865 0.902326 + outer loop + vertex -894.597 365.544 361.259 + vertex -895.087 371.877 361.26 + vertex -895.524 363.077 360.726 + endloop + endfacet + facet normal -0.421062 -0.0340653 0.906392 + outer loop + vertex -896.02 369.502 360.738 + vertex -895.524 363.077 360.726 + vertex -895.087 371.877 361.26 + endloop + endfacet + facet normal -0.471185 -0.0089962 0.881989 + outer loop + vertex -895.087 371.877 361.26 + vertex -895.187 378.065 361.27 + vertex -896.02 369.502 360.738 + endloop + endfacet + facet normal -0.475465 -0.0084374 0.879694 + outer loop + vertex -896.141 375.752 360.732 + vertex -896.02 369.502 360.738 + vertex -895.187 378.065 361.27 + endloop + endfacet + facet normal -0.342415 -0.0733908 0.936678 + outer loop + vertex -892.172 352.613 361.296 + vertex -892.952 358.912 361.504 + vertex -893.619 358.986 361.266 + endloop + endfacet + facet normal -0.340902 -0.0535728 0.938571 + outer loop + vertex -892.952 358.912 361.504 + vertex -894.053 365.911 361.504 + vertex -893.619 358.986 361.266 + endloop + endfacet + facet normal -0.377952 -0.0554012 0.924166 + outer loop + vertex -893.619 358.986 361.266 + vertex -894.053 365.911 361.504 + vertex -894.597 365.544 361.259 + endloop + endfacet + facet normal -0.390512 -0.0339729 0.919971 + outer loop + vertex -894.053 365.911 361.504 + vertex -894.633 372.356 361.496 + vertex -894.597 365.544 361.259 + endloop + endfacet + facet normal -0.431796 -0.0335439 0.901347 + outer loop + vertex -894.597 365.544 361.259 + vertex -894.633 372.356 361.496 + vertex -895.087 371.877 361.26 + endloop + endfacet + facet normal -0.450942 -0.0110569 0.892485 + outer loop + vertex -894.633 372.356 361.496 + vertex -894.766 378.453 361.504 + vertex -895.087 371.877 361.26 + endloop + endfacet + facet normal -0.479309 -0.00912106 0.877599 + outer loop + vertex -895.087 371.877 361.26 + vertex -894.766 378.453 361.504 + vertex -895.187 378.065 361.27 + endloop + endfacet + facet normal -0.495174 0.0135159 0.868689 + outer loop + vertex -894.766 378.453 361.504 + vertex -894.604 384.31 361.505 + vertex -895.187 378.065 361.27 + endloop + endfacet + facet normal -0.525202 0.0169925 0.850808 + outer loop + vertex -895.187 378.065 361.27 + vertex -894.604 384.31 361.505 + vertex -894.998 384.008 361.268 + endloop + endfacet + facet normal -0.536236 0.0372808 0.843244 + outer loop + vertex -894.604 384.31 361.505 + vertex -894.213 389.878 361.508 + vertex -894.998 384.008 361.268 + endloop + endfacet + facet normal -0.568499 0.042478 0.821587 + outer loop + vertex -894.998 384.008 361.268 + vertex -894.213 389.878 361.508 + vertex -894.558 389.848 361.27 + endloop + endfacet + facet normal -0.569079 0.0621049 0.819935 + outer loop + vertex -894.213 389.878 361.508 + vertex -893.613 395.406 361.506 + vertex -894.558 389.848 361.27 + endloop + endfacet + facet normal -0.590413 0.0663936 0.804366 + outer loop + vertex -894.558 389.848 361.27 + vertex -893.613 395.406 361.506 + vertex -893.909 395.591 361.273 + endloop + endfacet + facet normal -0.583396 0.0822317 0.808015 + outer loop + vertex -893.613 395.406 361.506 + vertex -892.83 400.933 361.509 + vertex -893.909 395.591 361.273 + endloop + endfacet + facet normal -0.607607 0.0879468 0.789354 + outer loop + vertex -893.909 395.591 361.273 + vertex -892.83 400.933 361.509 + vertex -893.092 401.219 361.275 + endloop + endfacet + facet normal -0.597914 0.101504 0.795107 + outer loop + vertex -892.83 400.933 361.509 + vertex -891.935 406.214 361.507 + vertex -893.092 401.219 361.275 + endloop + endfacet + facet normal -0.621209 0.107782 0.776198 + outer loop + vertex -893.092 401.219 361.275 + vertex -891.935 406.214 361.507 + vertex -892.136 406.818 361.262 + endloop + endfacet + facet normal -0.60365 0.11858 0.788382 + outer loop + vertex -891.935 406.214 361.507 + vertex -890.875 411.697 361.494 + vertex -892.136 406.818 361.262 + endloop + endfacet + facet normal -0.637295 0.128641 0.759807 + outer loop + vertex -892.136 406.818 361.262 + vertex -890.875 411.697 361.494 + vertex -890.971 412.906 361.209 + endloop + endfacet + facet normal -0.614445 0.13459 0.777395 + outer loop + vertex -890.875 411.697 361.494 + vertex -889.604 417.448 361.503 + vertex -890.971 412.906 361.209 + endloop + endfacet + facet normal -0.654427 0.148947 0.741309 + outer loop + vertex -890.971 412.906 361.209 + vertex -889.604 417.448 361.503 + vertex -889.357 419.26 361.357 + endloop + endfacet + facet normal -0.612521 0.146093 0.776837 + outer loop + vertex -889.604 417.448 361.503 + vertex -888.197 423.273 361.517 + vertex -889.357 419.26 361.357 + endloop + endfacet + facet normal -0.647366 0.157402 0.745749 + outer loop + vertex -889.357 419.26 361.357 + vertex -888.197 423.273 361.517 + vertex -888.363 423.632 361.297 + endloop + endfacet + facet normal -0.640549 0.163349 0.750343 + outer loop + vertex -888.197 423.273 361.517 + vertex -886.832 428.682 361.504 + vertex -888.363 423.632 361.297 + endloop + endfacet + facet normal -0.630551 0.159945 0.759489 + outer loop + vertex -888.363 423.632 361.297 + vertex -886.832 428.682 361.504 + vertex -887.067 428.848 361.275 + endloop + endfacet + facet normal -0.628092 0.164803 0.760487 + outer loop + vertex -886.832 428.682 361.504 + vertex -885.531 433.625 361.508 + vertex -887.067 428.848 361.275 + endloop + endfacet + facet normal -0.619457 0.161649 0.768207 + outer loop + vertex -887.067 428.848 361.275 + vertex -885.531 433.625 361.508 + vertex -885.714 434.104 361.259 + endloop + endfacet + facet normal -0.617114 0.163342 0.769733 + outer loop + vertex -885.531 433.625 361.508 + vertex -884.2 438.666 361.506 + vertex -885.714 434.104 361.259 + endloop + endfacet + facet normal -0.614803 0.162464 0.771766 + outer loop + vertex -885.714 434.104 361.259 + vertex -884.2 438.666 361.506 + vertex -884.222 439.958 361.216 + endloop + endfacet + facet normal -0.618598 0.16175 0.768878 + outer loop + vertex -884.2 438.666 361.506 + vertex -882.689 444.324 361.531 + vertex -884.222 439.958 361.216 + endloop + endfacet + facet normal -0.600941 0.154443 0.78423 + outer loop + vertex -884.222 439.958 361.216 + vertex -882.689 444.324 361.531 + vertex -882.508 445.854 361.368 + endloop + endfacet + facet normal -0.611145 0.154799 0.776234 + outer loop + vertex -882.689 444.324 361.531 + vertex -881.391 449.517 361.517 + vertex -882.508 445.854 361.368 + endloop + endfacet + facet normal -0.609374 0.154197 0.777745 + outer loop + vertex -882.508 445.854 361.368 + vertex -881.391 449.517 361.517 + vertex -881.559 450.04 361.282 + endloop + endfacet + facet normal -0.614507 0.151018 0.774322 + outer loop + vertex -881.391 449.517 361.517 + vertex -880.283 454.337 361.456 + vertex -881.559 450.04 361.282 + endloop + endfacet + facet normal -0.632281 0.156927 0.75868 + outer loop + vertex -881.559 450.04 361.282 + vertex -880.283 454.337 361.456 + vertex -880.496 454.778 361.188 + endloop + endfacet + facet normal -0.682427 0.167243 0.711564 + outer loop + vertex -881.559 450.04 361.282 + vertex -880.496 454.778 361.188 + vertex -882.215 449.715 360.729 + endloop + endfacet + facet normal -0.683722 0.175269 0.708382 + outer loop + vertex -882.215 449.715 360.729 + vertex -883.648 443.742 360.824 + vertex -881.559 450.04 361.282 + endloop + endfacet + facet normal -0.655612 0.163852 0.737106 + outer loop + vertex -882.508 445.854 361.368 + vertex -881.559 450.04 361.282 + vertex -883.648 443.742 360.824 + endloop + endfacet + facet normal -0.670863 0.17642 0.720291 + outer loop + vertex -884.222 439.958 361.216 + vertex -882.508 445.854 361.368 + vertex -883.648 443.742 360.824 + endloop + endfacet + facet normal -0.672915 0.17653 0.718347 + outer loop + vertex -883.648 443.742 360.824 + vertex -885.504 437.552 360.607 + vertex -884.222 439.958 361.216 + endloop + endfacet + facet normal -0.676254 0.179276 0.714521 + outer loop + vertex -885.504 437.552 360.607 + vertex -886.537 433.28 360.7 + vertex -884.222 439.958 361.216 + endloop + endfacet + facet normal -0.667513 0.175545 0.72361 + outer loop + vertex -885.714 434.104 361.259 + vertex -884.222 439.958 361.216 + vertex -886.537 433.28 360.7 + endloop + endfacet + facet normal -0.666549 0.173675 0.724948 + outer loop + vertex -886.537 433.28 360.7 + vertex -887.877 427.989 360.736 + vertex -885.714 434.104 361.259 + endloop + endfacet + facet normal -0.666354 0.173589 0.725148 + outer loop + vertex -887.067 428.848 361.275 + vertex -885.714 434.104 361.259 + vertex -887.877 427.989 360.736 + endloop + endfacet + facet normal -0.662203 0.166226 0.730654 + outer loop + vertex -887.877 427.989 360.736 + vertex -889.249 422.444 360.754 + vertex -887.067 428.848 361.275 + endloop + endfacet + facet normal -0.670339 0.169669 0.722398 + outer loop + vertex -888.363 423.632 361.297 + vertex -887.067 428.848 361.275 + vertex -889.249 422.444 360.754 + endloop + endfacet + facet normal -0.66196 0.15879 0.732526 + outer loop + vertex -889.249 422.444 360.754 + vertex -890.626 416.383 360.823 + vertex -888.363 423.632 361.297 + endloop + endfacet + facet normal -0.672661 0.162832 0.721812 + outer loop + vertex -889.357 419.26 361.357 + vertex -888.363 423.632 361.297 + vertex -890.626 416.383 360.823 + endloop + endfacet + facet normal -0.64783 0.14713 0.747441 + outer loop + vertex -890.971 412.906 361.209 + vertex -889.357 419.26 361.357 + vertex -890.626 416.383 360.823 + endloop + endfacet + facet normal -0.662079 0.147145 0.734846 + outer loop + vertex -890.626 416.383 360.823 + vertex -892.362 409.671 360.603 + vertex -890.971 412.906 361.209 + endloop + endfacet + facet normal -0.621883 0.122619 0.773451 + outer loop + vertex -892.362 409.671 360.603 + vertex -893.089 405.345 360.704 + vertex -890.971 412.906 361.209 + endloop + endfacet + facet normal -0.642421 0.129584 0.755317 + outer loop + vertex -892.136 406.818 361.262 + vertex -890.971 412.906 361.209 + vertex -893.089 405.345 360.704 + endloop + endfacet + facet normal -0.619439 0.106209 0.777827 + outer loop + vertex -893.089 405.345 360.704 + vertex -894.005 399.781 360.735 + vertex -892.136 406.818 361.262 + endloop + endfacet + facet normal -0.627377 0.108823 0.771075 + outer loop + vertex -893.092 401.219 361.275 + vertex -892.136 406.818 361.262 + vertex -894.005 399.781 360.735 + endloop + endfacet + facet normal -0.605148 0.0870958 0.791335 + outer loop + vertex -894.005 399.781 360.735 + vertex -894.829 393.986 360.742 + vertex -893.092 401.219 361.275 + endloop + endfacet + facet normal -0.608356 0.0880557 0.788764 + outer loop + vertex -893.909 395.591 361.273 + vertex -893.092 401.219 361.275 + vertex -894.829 393.986 360.742 + endloop + endfacet + facet normal -0.580095 0.0641589 0.812018 + outer loop + vertex -894.829 393.986 360.742 + vertex -895.504 387.997 360.733 + vertex -893.909 395.591 361.273 + endloop + endfacet + facet normal -0.587223 0.0660319 0.806727 + outer loop + vertex -894.558 389.848 361.27 + vertex -893.909 395.591 361.273 + vertex -895.504 387.997 360.733 + endloop + endfacet + facet normal -0.553387 0.0414371 0.831893 + outer loop + vertex -895.504 387.997 360.733 + vertex -895.951 381.948 360.738 + vertex -894.558 389.848 361.27 + endloop + endfacet + facet normal -0.552702 0.0412852 0.832356 + outer loop + vertex -894.998 384.008 361.268 + vertex -894.558 389.848 361.27 + vertex -895.951 381.948 360.738 + endloop + endfacet + facet normal -0.705123 0.177219 0.686582 + outer loop + vertex -880.966 455.003 360.647 + vertex -882.215 449.715 360.729 + vertex -880.496 454.778 361.188 + endloop + endfacet + facet normal -0.706795 0.172486 0.686069 + outer loop + vertex -880.496 454.778 361.188 + vertex -879.564 459.049 361.074 + vertex -880.966 455.003 360.647 + endloop + endfacet + facet normal -0.729609 0.183262 0.658851 + outer loop + vertex -879.867 459.757 360.541 + vertex -880.966 455.003 360.647 + vertex -879.564 459.049 361.074 + endloop + endfacet + facet normal -0.732558 0.180174 0.656427 + outer loop + vertex -879.867 459.757 360.541 + vertex -879.564 459.049 361.074 + vertex -878.753 462.816 360.945 + endloop + endfacet + facet normal -0.742422 0.18544 0.643756 + outer loop + vertex -879.096 463.242 360.426 + vertex -879.867 459.757 360.541 + vertex -878.753 462.816 360.945 + endloop + endfacet + facet normal -0.734658 0.19797 0.648911 + outer loop + vertex -878.617 464.889 360.467 + vertex -879.096 463.242 360.426 + vertex -878.753 462.816 360.945 + endloop + endfacet + facet normal -0.714158 0.191392 0.673311 + outer loop + vertex -878.826 464.8 360.27 + vertex -879.096 463.242 360.426 + vertex -878.617 464.889 360.467 + endloop + endfacet + facet normal -0.677741 0.170397 0.715285 + outer loop + vertex -879.564 459.049 361.074 + vertex -878.808 461.315 361.25 + vertex -878.753 462.816 360.945 + endloop + endfacet + facet normal -0.664522 0.164407 0.728959 + outer loop + vertex -880.496 454.778 361.188 + vertex -879.566 457.881 361.336 + vertex -879.564 459.049 361.074 + endloop + endfacet + facet normal -0.66364 0.164577 0.729724 + outer loop + vertex -879.564 459.049 361.074 + vertex -879.566 457.881 361.336 + vertex -878.808 461.315 361.25 + endloop + endfacet + facet normal -0.635243 0.154317 0.756738 + outer loop + vertex -880.283 454.337 361.456 + vertex -879.566 457.881 361.336 + vertex -880.496 454.778 361.188 + endloop + endfacet + facet normal -0.58599 0.144752 0.797285 + outer loop + vertex -880.283 454.337 361.456 + vertex -881.391 449.517 361.517 + vertex -880.675 452.234 361.55 + endloop + endfacet + facet normal -0.603762 0.147444 0.783411 + outer loop + vertex -880.675 452.234 361.55 + vertex -880.017 455.179 361.503 + vertex -880.283 454.337 361.456 + endloop + endfacet + facet normal -0.601626 0.146668 0.785198 + outer loop + vertex -880.017 455.179 361.503 + vertex -879.569 457.409 361.43 + vertex -880.283 454.337 361.456 + endloop + endfacet + facet normal -0.597582 0.147921 0.788045 + outer loop + vertex -881.615 448.257 361.584 + vertex -880.675 452.234 361.55 + vertex -881.391 449.517 361.517 + endloop + endfacet + facet normal -0.568529 0.148205 0.809203 + outer loop + vertex -882.689 444.324 361.531 + vertex -884.2 438.666 361.506 + vertex -883.394 441.272 361.594 + endloop + endfacet + facet normal -0.594912 0.153878 0.788924 + outer loop + vertex -883.394 441.272 361.594 + vertex -882.441 444.902 361.605 + vertex -882.689 444.324 361.531 + endloop + endfacet + facet normal -0.586838 0.149528 0.795778 + outer loop + vertex -882.441 444.902 361.605 + vertex -881.615 448.257 361.584 + vertex -882.689 444.324 361.531 + endloop + endfacet + facet normal -0.469469 0.120673 0.874664 + outer loop + vertex -882.441 444.902 361.605 + vertex -883.394 441.272 361.594 + vertex -883.387 440.769 361.667 + endloop + endfacet + facet normal -0.459216 0.121584 0.879965 + outer loop + vertex -883.394 441.272 361.594 + vertex -884.583 436.793 361.593 + vertex -883.387 440.769 361.667 + endloop + endfacet + facet normal -0.454498 0.120115 0.882612 + outer loop + vertex -885.502 432.895 361.65 + vertex -883.387 440.769 361.667 + vertex -884.583 436.793 361.593 + endloop + endfacet + facet normal -0.457994 0.120911 0.880694 + outer loop + vertex -884.583 436.793 361.593 + vertex -885.809 432.266 361.577 + vertex -885.502 432.895 361.65 + endloop + endfacet + facet normal -0.456506 0.12008 0.88158 + outer loop + vertex -885.809 432.266 361.577 + vertex -886.943 427.951 361.577 + vertex -885.502 432.895 361.65 + endloop + endfacet + facet normal -0.65656 0.172627 0.734253 + outer loop + vertex -886.943 427.951 361.577 + vertex -885.809 432.266 361.577 + vertex -886.832 428.682 361.504 + endloop + endfacet + facet normal -0.624087 0.166323 0.763447 + outer loop + vertex -885.809 432.266 361.577 + vertex -884.583 436.793 361.593 + vertex -885.531 433.625 361.508 + endloop + endfacet + facet normal -0.323695 0.0848558 0.942349 + outer loop + vertex -884.126 436.455 361.802 + vertex -883.387 440.769 361.667 + vertex -885.502 432.895 361.65 + endloop + endfacet + facet normal -0.30685 0.0780814 0.948549 + outer loop + vertex -884.126 436.455 361.802 + vertex -885.502 432.895 361.65 + vertex -885.699 429.977 361.827 + endloop + endfacet + facet normal -0.300055 0.0777559 0.950748 + outer loop + vertex -885.699 429.977 361.827 + vertex -885.502 432.895 361.65 + vertex -887.287 425.917 361.658 + endloop + endfacet + facet normal -0.282039 0.0704584 0.956812 + outer loop + vertex -885.699 429.977 361.827 + vertex -887.287 425.917 361.658 + vertex -887.484 422.639 361.841 + endloop + endfacet + facet normal -0.292915 0.0709276 0.953504 + outer loop + vertex -887.484 422.639 361.841 + vertex -887.287 425.917 361.658 + vertex -888.994 418.868 361.657 + endloop + endfacet + facet normal -0.269461 0.061168 0.961067 + outer loop + vertex -887.484 422.639 361.841 + vertex -888.994 418.868 361.657 + vertex -889.212 414.392 361.881 + endloop + endfacet + facet normal -0.274239 0.0613328 0.959704 + outer loop + vertex -889.212 414.392 361.881 + vertex -888.994 418.868 361.657 + vertex -890.653 411.22 361.672 + endloop + endfacet + facet normal -0.255582 0.0524871 0.965362 + outer loop + vertex -889.212 414.392 361.881 + vertex -890.653 411.22 361.672 + vertex -890.995 407.018 361.81 + endloop + endfacet + facet normal -0.299254 0.0556224 0.952551 + outer loop + vertex -890.995 407.018 361.81 + vertex -890.653 411.22 361.672 + vertex -892.07 403.681 361.667 + endloop + endfacet + facet normal -0.240046 0.0357861 0.970102 + outer loop + vertex -890.995 407.018 361.81 + vertex -892.07 403.681 361.667 + vertex -891.75 399.778 361.89 + endloop + endfacet + facet normal -0.243357 0.0354676 0.969288 + outer loop + vertex -891.75 399.778 361.89 + vertex -892.07 403.681 361.667 + vertex -893.156 395.677 361.687 + endloop + endfacet + facet normal -0.20549 0.022035 0.978411 + outer loop + vertex -891.75 399.778 361.89 + vertex -893.156 395.677 361.687 + vertex -892.817 391.057 361.862 + endloop + endfacet + facet normal -0.220536 0.0208085 0.975157 + outer loop + vertex -892.817 391.057 361.862 + vertex -893.156 395.677 361.687 + vertex -893.984 387.704 361.67 + endloop + endfacet + facet normal -0.323097 0.0847601 0.942563 + outer loop + vertex -881.926 443.892 361.887 + vertex -883.387 440.769 361.667 + vertex -884.126 436.455 361.802 + endloop + endfacet + facet normal -0.321932 0.0841834 0.943013 + outer loop + vertex -881.926 443.892 361.887 + vertex -881.312 449.152 361.628 + vertex -883.387 440.769 361.667 + endloop + endfacet + facet normal -0.356001 0.0875405 0.930376 + outer loop + vertex -880.275 452.15 361.742 + vertex -881.312 449.152 361.628 + vertex -881.926 443.892 361.887 + endloop + endfacet + facet normal -0.389222 0.0995919 0.915744 + outer loop + vertex -881.312 449.152 361.628 + vertex -880.275 452.15 361.742 + vertex -879.993 455.15 361.536 + endloop + endfacet + facet normal -0.602838 0.159742 0.781709 + outer loop + vertex -884.583 436.793 361.593 + vertex -883.394 441.272 361.594 + vertex -884.2 438.666 361.506 + endloop + endfacet + facet normal -0.604542 0.160027 0.780333 + outer loop + vertex -884.2 438.666 361.506 + vertex -885.531 433.625 361.508 + vertex -884.583 436.793 361.593 + endloop + endfacet + facet normal -0.64905 0.170339 0.741431 + outer loop + vertex -885.531 433.625 361.508 + vertex -886.832 428.682 361.504 + vertex -885.809 432.266 361.577 + endloop + endfacet + facet normal -0.683937 0.174203 0.708438 + outer loop + vertex -886.832 428.682 361.504 + vertex -888.197 423.273 361.517 + vertex -886.943 427.951 361.577 + endloop + endfacet + facet normal -0.686268 0.174859 0.706017 + outer loop + vertex -888.116 423.331 361.581 + vertex -886.943 427.951 361.577 + vertex -888.197 423.273 361.517 + endloop + endfacet + facet normal -0.683841 0.166588 0.710359 + outer loop + vertex -888.984 419.823 361.569 + vertex -888.116 423.331 361.581 + vertex -888.197 423.273 361.517 + endloop + endfacet + facet normal -0.376142 0.0897118 0.922209 + outer loop + vertex -888.116 423.331 361.581 + vertex -888.984 419.823 361.569 + vertex -888.994 418.868 361.657 + endloop + endfacet + facet normal -0.38769 0.089389 0.917446 + outer loop + vertex -888.984 419.823 361.569 + vertex -890.081 414.915 361.583 + vertex -888.994 418.868 361.657 + endloop + endfacet + facet normal -0.775441 0.185861 0.603446 + outer loop + vertex -888.197 423.273 361.517 + vertex -889.604 417.448 361.503 + vertex -888.984 419.823 361.569 + endloop + endfacet + facet normal -0.319405 -0.0708131 0.944969 + outer loop + vertex -891.599 353.015 361.52 + vertex -892.952 358.912 361.504 + vertex -892.172 352.613 361.296 + endloop + endfacet + facet normal -0.310738 -0.0841474 0.946763 + outer loop + vertex -890.636 347.641 361.358 + vertex -891.599 353.015 361.52 + vertex -892.172 352.613 361.296 + endloop + endfacet + facet normal -0.268995 -0.0770681 0.960053 + outer loop + vertex -889.837 346.634 361.501 + vertex -891.599 353.015 361.52 + vertex -890.636 347.641 361.358 + endloop + endfacet + facet normal -0.293436 -0.0977735 0.950966 + outer loop + vertex -888.436 339.532 361.203 + vertex -889.837 346.634 361.501 + vertex -890.636 347.641 361.358 + endloop + endfacet + facet normal -0.271028 -0.0936489 0.958005 + outer loop + vertex -887.421 339.607 361.498 + vertex -889.837 346.634 361.501 + vertex -888.436 339.532 361.203 + endloop + endfacet + facet normal -0.269307 -0.111419 0.956588 + outer loop + vertex -885.262 332.22 361.245 + vertex -887.421 339.607 361.498 + vertex -888.436 339.532 361.203 + endloop + endfacet + facet normal -0.242365 -0.103818 0.964615 + outer loop + vertex -884.452 332.694 361.5 + vertex -887.421 339.607 361.498 + vertex -885.262 332.22 361.245 + endloop + endfacet + facet normal -0.235488 -0.11577 0.964957 + outer loop + vertex -881.905 325.636 361.275 + vertex -884.452 332.694 361.5 + vertex -885.262 332.22 361.245 + endloop + endfacet + facet normal -0.219966 -0.110305 0.969251 + outer loop + vertex -881.25 326.403 361.51 + vertex -884.452 332.694 361.5 + vertex -881.905 325.636 361.275 + endloop + endfacet + facet normal -0.209891 -0.11926 0.970424 + outer loop + vertex -878.162 319.245 361.299 + vertex -881.25 326.403 361.51 + vertex -881.905 325.636 361.275 + endloop + endfacet + facet normal -0.215085 -0.121459 0.969013 + outer loop + vertex -877.506 319.83 361.518 + vertex -881.25 326.403 361.51 + vertex -878.162 319.245 361.299 + endloop + endfacet + facet normal -0.207612 -0.130024 0.969531 + outer loop + vertex -874.744 314.105 361.341 + vertex -877.506 319.83 361.518 + vertex -878.162 319.245 361.299 + endloop + endfacet + facet normal -0.206941 -0.129706 0.969718 + outer loop + vertex -873.366 313.151 361.508 + vertex -877.506 319.83 361.518 + vertex -874.744 314.105 361.341 + endloop + endfacet + facet normal -0.220845 -0.150861 0.963571 + outer loop + vertex -870.194 306.338 361.168 + vertex -873.366 313.151 361.508 + vertex -874.744 314.105 361.341 + endloop + endfacet + facet normal -0.200393 -0.14163 0.969424 + outer loop + vertex -868.807 306.517 361.481 + vertex -873.366 313.151 361.508 + vertex -870.194 306.338 361.168 + endloop + endfacet + facet normal -0.198833 -0.151602 0.968237 + outer loop + vertex -865.182 300.047 361.212 + vertex -868.807 306.517 361.481 + vertex -870.194 306.338 361.168 + endloop + endfacet + facet normal -0.181372 -0.142019 0.973106 + outer loop + vertex -864.272 300.795 361.491 + vertex -868.807 306.517 361.481 + vertex -865.182 300.047 361.212 + endloop + endfacet + facet normal -0.178129 -0.145966 0.973121 + outer loop + vertex -860.739 295.014 361.271 + vertex -864.272 300.795 361.491 + vertex -865.182 300.047 361.212 + endloop + endfacet + facet normal -0.160787 -0.13554 0.977638 + outer loop + vertex -859.842 295.619 361.502 + vertex -864.272 300.795 361.491 + vertex -860.739 295.014 361.271 + endloop + endfacet + facet normal -0.0698766 -0.0808807 0.994271 + outer loop + vertex -854.183 289.606 361.516 + vertex -854.547 293.071 361.772 + vertex -856.093 292.377 361.607 + endloop + endfacet + facet normal -0.0765004 -0.0749952 0.994245 + outer loop + vertex -852.241 295.304 362.118 + vertex -854.547 293.071 361.772 + vertex -846.963 286.987 361.897 + endloop + endfacet + facet normal -0.051349 -0.0588598 0.996945 + outer loop + vertex -830.507 273.637 362 + vertex -839.186 286.523 362.313 + vertex -839.161 280.861 361.98 + endloop + endfacet + facet normal -0.0466059 -0.0578905 0.997234 + outer loop + vertex -821.559 266.281 361.991 + vertex -830.419 278.994 362.315 + vertex -830.507 273.637 362 + endloop + endfacet + facet normal -0.0438014 -0.0584985 0.997326 + outer loop + vertex -812.465 259.326 361.982 + vertex -821.491 271.564 362.304 + vertex -821.559 266.281 361.991 + endloop + endfacet + facet normal -0.0414034 -0.0591898 0.997388 + outer loop + vertex -803.224 252.861 361.982 + vertex -812.413 264.616 362.298 + vertex -812.465 259.326 361.982 + endloop + endfacet + facet normal -0.0386554 -0.0593583 0.997488 + outer loop + vertex -793.837 246.765 361.983 + vertex -803.168 258.153 362.299 + vertex -803.224 252.861 361.982 + endloop + endfacet + facet normal -0.0370098 -0.0599714 0.997514 + outer loop + vertex -784.327 240.911 361.984 + vertex -793.777 252.04 362.302 + vertex -793.837 246.765 361.983 + endloop + endfacet + facet normal -0.0353767 -0.0599471 0.997574 + outer loop + vertex -774.699 235.244 361.985 + vertex -784.271 246.181 362.303 + vertex -784.327 240.911 361.984 + endloop + endfacet + facet normal -0.0337312 -0.0598422 0.997638 + outer loop + vertex -764.924 229.742 361.985 + vertex -774.652 240.519 362.303 + vertex -774.699 235.244 361.985 + endloop + endfacet + facet normal -0.0320646 -0.0595973 0.997707 + outer loop + vertex -754.961 224.382 361.985 + vertex -764.884 235.024 362.302 + vertex -764.924 229.742 361.985 + endloop + endfacet + facet normal -0.0307296 -0.0595633 0.997751 + outer loop + vertex -744.801 219.158 361.986 + vertex -754.924 229.668 362.302 + vertex -754.961 224.382 361.985 + endloop + endfacet + facet normal -0.0292852 -0.0595145 0.997798 + outer loop + vertex -734.487 214.085 361.987 + vertex -744.764 224.443 362.303 + vertex -744.801 219.158 361.986 + endloop + endfacet + facet normal -0.0280113 -0.0593278 0.997845 + outer loop + vertex -724.098 209.192 361.987 + vertex -734.447 219.371 362.302 + vertex -734.487 214.085 361.987 + endloop + endfacet + facet normal -0.0264071 -0.0594279 0.997883 + outer loop + vertex -713.704 204.505 361.983 + vertex -724.057 214.475 362.303 + vertex -724.098 209.192 361.987 + endloop + endfacet + facet normal -0.0259594 -0.0602392 0.997846 + outer loop + vertex -703.314 200.01 361.982 + vertex -713.665 209.784 362.303 + vertex -713.704 204.505 361.983 + endloop + endfacet + facet normal -0.024857 -0.0600902 0.997883 + outer loop + vertex -692.899 195.687 361.981 + vertex -703.279 205.292 362.301 + vertex -703.314 200.01 361.982 + endloop + endfacet + facet normal -0.0238491 -0.0598638 0.997922 + outer loop + vertex -682.448 191.524 361.981 + vertex -692.868 200.973 362.299 + vertex -692.899 195.687 361.981 + endloop + endfacet + facet normal -0.0233154 -0.0599438 0.997929 + outer loop + vertex -671.977 187.517 361.985 + vertex -682.421 196.814 362.3 + vertex -682.448 191.524 361.981 + endloop + endfacet + facet normal -0.0220806 -0.0597281 0.99797 + outer loop + vertex -661.452 183.633 361.986 + vertex -671.958 192.813 362.303 + vertex -671.977 187.517 361.985 + endloop + endfacet + facet normal -0.0208811 -0.0600071 0.99798 + outer loop + vertex -650.734 179.782 361.978 + vertex -661.427 188.925 362.304 + vertex -661.452 183.633 361.986 + endloop + endfacet + facet normal -0.0196407 -0.0600914 0.998 + outer loop + vertex -639.722 175.901 361.961 + vertex -650.668 185.057 362.297 + vertex -650.734 179.782 361.978 + endloop + endfacet + facet normal -0.0196086 -0.060326 0.997986 + outer loop + vertex -628.631 172.112 361.95 + vertex -639.598 181.159 362.282 + vertex -639.722 175.901 361.961 + endloop + endfacet + facet normal -0.0204764 -0.0602707 0.997972 + outer loop + vertex -618.181 168.789 361.964 + vertex -628.515 177.383 362.271 + vertex -628.631 172.112 361.95 + endloop + endfacet + facet normal -0.0218672 -0.0595251 0.997987 + outer loop + vertex -609.099 166.194 362.008 + vertex -618.105 174.056 362.28 + vertex -618.181 168.789 361.964 + endloop + endfacet + facet normal -0.0167614 -0.0564638 0.998264 + outer loop + vertex -601.05 163.778 362.007 + vertex -608.899 171.381 362.305 + vertex -609.099 166.194 362.008 + endloop + endfacet + facet normal -0.0182408 -0.0595784 0.998057 + outer loop + vertex -592.728 167.737 362.378 + vertex -592.81 161.497 362.004 + vertex -583.688 159.424 362.047 + endloop + endfacet + facet normal -0.0171508 -0.0595939 0.998075 + outer loop + vertex -592.81 161.497 362.004 + vertex -592.728 167.737 362.378 + vertex -600.729 169.339 362.336 + endloop + endfacet + facet normal -0.0169412 -0.0563672 0.998266 + outer loop + vertex -573.271 156.809 362.076 + vertex -583.788 165.964 362.415 + vertex -583.688 159.424 362.047 + endloop + endfacet + facet normal -0.0158947 -0.0539503 0.998417 + outer loop + vertex -561.545 153.571 362.088 + vertex -573.206 163.365 362.432 + vertex -573.271 156.809 362.076 + endloop + endfacet + facet normal -0.0159702 -0.0535292 0.998439 + outer loop + vertex -549.15 150.075 362.099 + vertex -561.336 160.076 362.44 + vertex -561.545 153.571 362.088 + endloop + endfacet + facet normal -0.0156184 -0.0533678 0.998453 + outer loop + vertex -536.743 146.636 362.109 + vertex -549 156.611 362.451 + vertex -549.15 150.075 362.099 + endloop + endfacet + facet normal -0.0140071 -0.0526191 0.998516 + outer loop + vertex -524.657 143.318 362.104 + vertex -536.74 153.215 362.456 + vertex -536.743 146.636 362.109 + endloop + endfacet + facet normal -0.0120354 -0.0513949 0.998606 + outer loop + vertex -512.853 140.098 362.08 + vertex -524.746 149.911 362.442 + vertex -524.657 143.318 362.104 + endloop + endfacet + facet normal -0.0123704 -0.0502938 0.998658 + outer loop + vertex -500.95 137.043 362.074 + vertex -512.872 146.693 362.412 + vertex -512.853 140.098 362.08 + endloop + endfacet + facet normal -0.016807 -0.0491081 0.998652 + outer loop + vertex -488.415 134.329 362.151 + vertex -500.717 143.654 362.403 + vertex -500.95 137.043 362.074 + endloop + endfacet + facet normal -0.00954714 -0.0384589 0.999215 + outer loop + vertex -500.563 150.358 362.662 + vertex -512.865 153.366 362.661 + vertex -500.717 143.654 362.403 + endloop + endfacet + facet normal -0.021163 -0.0737945 0.997049 + outer loop + vertex -487.849 147.64 362.731 + vertex -501.811 157.295 363.149 + vertex -500.563 150.358 362.662 + endloop + endfacet + facet normal -0.018793 -0.0703802 0.997343 + outer loop + vertex -488.898 154.106 363.168 + vertex -501.811 157.295 363.149 + vertex -487.849 147.64 362.731 + endloop + endfacet + facet normal -0.0239433 -0.0712039 0.997174 + outer loop + vertex -474.841 145.349 362.88 + vertex -488.898 154.106 363.168 + vertex -487.849 147.64 362.731 + endloop + endfacet + facet normal -0.0260159 -0.0745212 0.99688 + outer loop + vertex -477.745 151.58 363.27 + vertex -488.898 154.106 363.168 + vertex -474.841 145.349 362.88 + endloop + endfacet + facet normal -0.024555 -0.0738458 0.996967 + outer loop + vertex -477.745 151.58 363.27 + vertex -474.841 145.349 362.88 + vertex -466.472 145.59 363.104 + endloop + endfacet + facet normal -0.0471819 -0.116296 0.992093 + outer loop + vertex -465.446 149.263 363.583 + vertex -477.745 151.58 363.27 + vertex -466.472 145.59 363.104 + endloop + endfacet + facet normal -0.0480192 -0.11606 0.992081 + outer loop + vertex -459.155 144.843 363.371 + vertex -465.446 149.263 363.583 + vertex -466.472 145.59 363.104 + endloop + endfacet + facet normal -0.0410732 -0.0458769 0.998102 + outer loop + vertex -459.155 144.843 363.371 + vertex -466.472 145.59 363.104 + vertex -458.935 141.373 363.22 + endloop + endfacet + facet normal -0.0594116 -0.046994 0.997127 + outer loop + vertex -453.092 140.871 363.545 + vertex -459.155 144.843 363.371 + vertex -458.935 141.373 363.22 + endloop + endfacet + facet normal -0.057031 -0.0185741 0.9982 + outer loop + vertex -453.092 140.871 363.545 + vertex -458.935 141.373 363.22 + vertex -453.161 137.562 363.479 + endloop + endfacet + facet normal -0.0761116 -0.0181518 0.996934 + outer loop + vertex -447.853 137.195 363.878 + vertex -453.092 140.871 363.545 + vertex -453.161 137.562 363.479 + endloop + endfacet + facet normal -0.0782741 -0.0212546 0.996705 + outer loop + vertex -447.795 140.528 363.953 + vertex -453.092 140.871 363.545 + vertex -447.853 137.195 363.878 + endloop + endfacet + facet normal -0.100968 -0.0208143 0.994672 + outer loop + vertex -442.861 137.062 364.382 + vertex -447.795 140.528 363.953 + vertex -447.853 137.195 363.878 + endloop + endfacet + facet normal -0.101069 -0.024978 0.994566 + outer loop + vertex -442.861 137.062 364.382 + vertex -447.853 137.195 363.878 + vertex -442.851 133.688 364.298 + endloop + endfacet + facet normal -0.124954 -0.024979 0.991848 + outer loop + vertex -437.911 133.778 364.923 + vertex -442.861 137.062 364.382 + vertex -442.851 133.688 364.298 + endloop + endfacet + facet normal -0.12797 -0.029608 0.991336 + outer loop + vertex -437.984 137.21 365.016 + vertex -442.861 137.062 364.382 + vertex -437.911 133.778 364.923 + endloop + endfacet + facet normal -0.152562 -0.0300372 0.987837 + outer loop + vertex -433.105 134.155 365.676 + vertex -437.984 137.21 365.016 + vertex -437.911 133.778 364.923 + endloop + endfacet + facet normal -0.151665 -0.0409417 0.987584 + outer loop + vertex -433.105 134.155 365.676 + vertex -437.911 133.778 364.923 + vertex -432.941 130.701 365.558 + endloop + endfacet + facet normal -0.179315 -0.0420943 0.982891 + outer loop + vertex -428.455 131.342 366.404 + vertex -433.105 134.155 365.676 + vertex -432.941 130.701 365.558 + endloop + endfacet + facet normal -0.180717 -0.0445055 0.982528 + outer loop + vertex -428.667 134.83 366.523 + vertex -433.105 134.155 365.676 + vertex -428.455 131.342 366.404 + endloop + endfacet + facet normal -0.211911 -0.0461909 0.976197 + outer loop + vertex -424.646 132.344 367.278 + vertex -428.667 134.83 366.523 + vertex -428.455 131.342 366.404 + endloop + endfacet + facet normal -0.18212 -0.0354184 0.982638 + outer loop + vertex -428.667 134.83 366.523 + vertex -433.237 137.627 365.777 + vertex -433.105 134.155 365.676 + endloop + endfacet + facet normal -0.184094 -0.0387769 0.982143 + outer loop + vertex -428.858 138.336 366.626 + vertex -433.237 137.627 365.777 + vertex -428.667 134.83 366.523 + endloop + endfacet + facet normal -0.214641 -0.0402559 0.975863 + outer loop + vertex -424.878 135.869 367.399 + vertex -428.858 138.336 366.626 + vertex -428.667 134.83 366.523 + endloop + endfacet + facet normal -0.183992 -0.0393984 0.982138 + outer loop + vertex -428.858 138.336 366.626 + vertex -433.401 141.118 365.886 + vertex -433.237 137.627 365.777 + endloop + endfacet + facet normal -0.158145 -0.0383315 0.986672 + outer loop + vertex -433.401 141.118 365.886 + vertex -438.063 140.662 365.121 + vertex -433.237 137.627 365.777 + endloop + endfacet + facet normal -0.155364 -0.0337785 0.98728 + outer loop + vertex -433.237 137.627 365.777 + vertex -438.063 140.662 365.121 + vertex -437.984 137.21 365.016 + endloop + endfacet + facet normal -0.132263 -0.0333551 0.990653 + outer loop + vertex -438.063 140.662 365.121 + vertex -442.863 140.459 364.474 + vertex -437.984 137.21 365.016 + endloop + endfacet + facet normal -0.130727 -0.0652465 0.989269 + outer loop + vertex -438.063 140.662 365.121 + vertex -443.079 143.912 364.673 + vertex -442.863 140.459 364.474 + endloop + endfacet + facet normal -0.109106 -0.064046 0.991965 + outer loop + vertex -443.079 143.912 364.673 + vertex -447.977 143.935 364.136 + vertex -442.863 140.459 364.474 + endloop + endfacet + facet normal -0.105546 -0.0587385 0.992678 + outer loop + vertex -442.863 140.459 364.474 + vertex -447.977 143.935 364.136 + vertex -447.795 140.528 363.953 + endloop + endfacet + facet normal -0.0845848 -0.0577288 0.994743 + outer loop + vertex -447.977 143.935 364.136 + vertex -453.232 144.254 363.707 + vertex -447.795 140.528 363.953 + endloop + endfacet + facet normal -0.0895721 -0.154543 0.983917 + outer loop + vertex -447.977 143.935 364.136 + vertex -454.125 147.84 364.189 + vertex -453.232 144.254 363.707 + endloop + endfacet + facet normal -0.0774979 -0.151734 0.985379 + outer loop + vertex -454.125 147.84 364.189 + vertex -459.691 148.432 363.843 + vertex -453.232 144.254 363.707 + endloop + endfacet + facet normal -0.0700958 -0.140366 0.987615 + outer loop + vertex -453.232 144.254 363.707 + vertex -459.691 148.432 363.843 + vertex -459.155 144.843 363.371 + endloop + endfacet + facet normal -0.0910881 -0.156923 0.983401 + outer loop + vertex -448.893 147.519 364.623 + vertex -454.125 147.84 364.189 + vertex -447.977 143.935 364.136 + endloop + endfacet + facet normal -0.108368 -0.161009 0.980985 + outer loop + vertex -443.079 143.912 364.673 + vertex -448.893 147.519 364.623 + vertex -447.977 143.935 364.136 + endloop + endfacet + facet normal -0.106184 -0.157479 0.981797 + outer loop + vertex -443.881 147.47 365.157 + vertex -448.893 147.519 364.623 + vertex -443.079 143.912 364.673 + endloop + endfacet + facet normal -0.126637 -0.161664 0.978687 + outer loop + vertex -438.323 144.154 365.328 + vertex -443.881 147.47 365.157 + vertex -443.079 143.912 364.673 + endloop + endfacet + facet normal -0.123967 -0.157132 0.979766 + outer loop + vertex -438.984 147.719 365.816 + vertex -443.881 147.47 365.157 + vertex -438.323 144.154 365.328 + endloop + endfacet + facet normal -0.14604 -0.16073 0.976134 + outer loop + vertex -433.744 144.661 366.097 + vertex -438.984 147.719 365.816 + vertex -438.323 144.154 365.328 + endloop + endfacet + facet normal -0.157137 -0.0737348 0.98482 + outer loop + vertex -433.744 144.661 366.097 + vertex -438.323 144.154 365.328 + vertex -433.401 141.118 365.886 + endloop + endfacet + facet normal -0.17922 -0.0756425 0.980897 + outer loop + vertex -429.105 141.868 366.729 + vertex -433.744 144.661 366.097 + vertex -433.401 141.118 365.886 + endloop + endfacet + facet normal -0.179944 -0.076896 0.980667 + outer loop + vertex -429.516 145.466 366.936 + vertex -433.744 144.661 366.097 + vertex -429.105 141.868 366.729 + endloop + endfacet + facet normal -0.205163 -0.0794842 0.975495 + outer loop + vertex -425.418 142.998 367.597 + vertex -429.516 145.466 366.936 + vertex -429.105 141.868 366.729 + endloop + endfacet + facet normal -0.162489 -0.161105 0.973469 + outer loop + vertex -429.516 145.466 366.936 + vertex -434.352 148.288 366.596 + vertex -433.744 144.661 366.097 + endloop + endfacet + facet normal -0.166747 -0.168641 0.971471 + outer loop + vertex -430.13 149.162 367.472 + vertex -434.352 148.288 366.596 + vertex -429.516 145.466 366.936 + endloop + endfacet + facet normal -0.178885 -0.1703 0.969019 + outer loop + vertex -425.752 146.637 367.836 + vertex -430.13 149.162 367.472 + vertex -429.516 145.466 366.936 + endloop + endfacet + facet normal -0.144816 -0.158583 0.976668 + outer loop + vertex -434.352 148.288 366.596 + vertex -438.984 147.719 365.816 + vertex -433.744 144.661 366.097 + endloop + endfacet + facet normal -0.132772 -0.0684702 0.988779 + outer loop + vertex -438.323 144.154 365.328 + vertex -443.079 143.912 364.673 + vertex -438.063 140.662 365.121 + endloop + endfacet + facet normal -0.154855 -0.0699177 0.98546 + outer loop + vertex -433.401 141.118 365.886 + vertex -438.323 144.154 365.328 + vertex -438.063 140.662 365.121 + endloop + endfacet + facet normal -0.185326 -0.0416665 0.981793 + outer loop + vertex -429.105 141.868 366.729 + vertex -433.401 141.118 365.886 + vertex -428.858 138.336 366.626 + endloop + endfacet + facet normal -0.215008 -0.0435572 0.975641 + outer loop + vertex -425.128 139.424 367.496 + vertex -429.105 141.868 366.729 + vertex -428.858 138.336 366.626 + endloop + endfacet + facet normal -0.155296 -0.034527 0.987264 + outer loop + vertex -433.237 137.627 365.777 + vertex -437.984 137.21 365.016 + vertex -433.105 134.155 365.676 + endloop + endfacet + facet normal -0.12806 -0.026919 0.991401 + outer loop + vertex -437.984 137.21 365.016 + vertex -442.863 140.459 364.474 + vertex -442.861 137.062 364.382 + endloop + endfacet + facet normal -0.105247 -0.0269786 0.99408 + outer loop + vertex -442.863 140.459 364.474 + vertex -447.795 140.528 363.953 + vertex -442.861 137.062 364.382 + endloop + endfacet + facet normal -0.0801134 -0.0511543 0.995472 + outer loop + vertex -447.795 140.528 363.953 + vertex -453.232 144.254 363.707 + vertex -453.092 140.871 363.545 + endloop + endfacet + facet normal -0.0616687 -0.0504526 0.996821 + outer loop + vertex -453.232 144.254 363.707 + vertex -459.155 144.843 363.371 + vertex -453.092 140.871 363.545 + endloop + endfacet + facet normal -0.0409019 -0.0455703 0.998123 + outer loop + vertex -458.935 141.373 363.22 + vertex -466.472 145.59 363.104 + vertex -464.727 141.777 363.001 + endloop + endfacet + facet normal -0.0647069 -0.139623 0.988088 + outer loop + vertex -459.691 148.432 363.843 + vertex -465.446 149.263 363.583 + vertex -459.155 144.843 363.371 + endloop + endfacet + facet normal -0.0256216 -0.0385969 0.998926 + outer loop + vertex -464.727 141.777 363.001 + vertex -466.472 145.59 363.104 + vertex -474.841 145.349 362.88 + endloop + endfacet + facet normal -0.0388893 -0.0161821 0.999112 + outer loop + vertex -458.935 141.373 363.22 + vertex -464.727 141.777 363.001 + vertex -459.004 138.07 363.164 + endloop + endfacet + facet normal -0.0552253 -0.0158283 0.998348 + outer loop + vertex -453.161 137.562 363.479 + vertex -458.935 141.373 363.22 + vertex -459.004 138.07 363.164 + endloop + endfacet + facet normal -0.0763398 -0.0215533 0.996849 + outer loop + vertex -447.853 137.195 363.878 + vertex -453.161 137.562 363.479 + vertex -447.914 133.875 363.801 + endloop + endfacet + facet normal -0.098384 -0.0211072 0.994925 + outer loop + vertex -442.851 133.688 364.298 + vertex -447.853 137.195 363.878 + vertex -447.914 133.875 363.801 + endloop + endfacet + facet normal -0.124665 -0.0381919 0.991464 + outer loop + vertex -437.911 133.778 364.923 + vertex -442.851 133.688 364.298 + vertex -437.796 130.364 364.805 + endloop + endfacet + facet normal -0.150457 -0.0389339 0.98785 + outer loop + vertex -432.941 130.701 365.558 + vertex -437.911 133.778 364.923 + vertex -437.796 130.364 364.805 + endloop + endfacet + facet normal -0.177524 -0.0542686 0.982619 + outer loop + vertex -428.455 131.342 366.404 + vertex -432.941 130.701 365.558 + vertex -428.199 127.879 366.259 + endloop + endfacet + facet normal -0.208121 -0.0562708 0.976483 + outer loop + vertex -424.37 128.847 367.131 + vertex -428.455 131.342 366.404 + vertex -428.199 127.879 366.259 + endloop + endfacet + facet normal -0.148245 -0.0679402 0.986614 + outer loop + vertex -432.735 127.275 365.41 + vertex -437.64 126.983 364.653 + vertex -432.468 123.86 365.215 + endloop + endfacet + facet normal -0.122264 -0.0494325 0.991266 + outer loop + vertex -437.64 126.983 364.653 + vertex -442.792 130.329 364.184 + vertex -442.705 126.983 364.028 + endloop + endfacet + facet normal -0.0976506 -0.0489257 0.994017 + outer loop + vertex -442.792 130.329 364.184 + vertex -447.948 130.546 363.688 + vertex -442.705 126.983 364.028 + endloop + endfacet + facet normal -0.0737122 -0.0301701 0.996823 + outer loop + vertex -447.948 130.546 363.688 + vertex -453.305 134.259 363.405 + vertex -453.535 130.913 363.286 + endloop + endfacet + facet normal -0.0559532 -0.0314288 0.997939 + outer loop + vertex -453.305 134.259 363.405 + vertex -459.279 134.752 363.085 + vertex -453.535 130.913 363.286 + endloop + endfacet + facet normal -0.041822 -0.0265361 0.998773 + outer loop + vertex -459.279 134.752 363.085 + vertex -466.064 138.909 362.912 + vertex -465.186 135.145 362.848 + endloop + endfacet + facet normal -0.0278368 -0.0232837 0.999341 + outer loop + vertex -465.186 135.145 362.848 + vertex -466.064 138.909 362.912 + vertex -474.696 138.761 362.668 + endloop + endfacet + facet normal -0.0214906 -0.0409966 0.998928 + outer loop + vertex -474.696 138.761 362.668 + vertex -487.912 140.955 362.473 + vertex -474.833 131.985 362.387 + endloop + endfacet + facet normal -0.0442538 -0.0501985 0.997758 + outer loop + vertex -459.734 131.371 362.953 + vertex -466.847 132.258 362.682 + vertex -460.61 127.955 362.742 + endloop + endfacet + facet normal -0.0416751 -0.0681287 0.996806 + outer loop + vertex -466.317 128.956 362.536 + vertex -474.833 131.985 362.387 + vertex -462.967 124.178 362.349 + endloop + endfacet + facet normal -0.0573027 -0.0468223 0.997258 + outer loop + vertex -453.917 127.5 363.105 + vertex -459.734 131.371 362.953 + vertex -460.61 127.955 362.742 + endloop + endfacet + facet normal -0.0742696 -0.0626718 0.995267 + outer loop + vertex -448.025 127.192 363.526 + vertex -453.917 127.5 363.105 + vertex -448.141 123.799 363.303 + endloop + endfacet + facet normal -0.0946502 -0.0618643 0.993587 + outer loop + vertex -442.614 123.631 363.819 + vertex -448.025 127.192 363.526 + vertex -448.141 123.799 363.303 + endloop + endfacet + facet normal -0.12083 -0.0856516 0.988971 + outer loop + vertex -437.44 123.612 364.45 + vertex -442.614 123.631 363.819 + vertex -437.184 120.252 364.19 + endloop + endfacet + facet normal -0.147219 -0.0873742 0.985237 + outer loop + vertex -432.128 120.462 364.964 + vertex -437.44 123.612 364.45 + vertex -437.184 120.252 364.19 + endloop + endfacet + facet normal -0.170971 -0.111252 0.978975 + outer loop + vertex -427.462 121.001 365.84 + vertex -432.128 120.462 364.964 + vertex -426.956 117.611 365.544 + endloop + endfacet + facet normal -0.195966 -0.114541 0.973898 + outer loop + vertex -422.95 118.501 366.454 + vertex -427.462 121.001 365.84 + vertex -426.956 117.611 365.544 + endloop + endfacet + facet normal -0.144511 -0.135515 0.98018 + outer loop + vertex -431.712 117.114 364.652 + vertex -436.842 116.921 363.869 + vertex -431.184 113.812 364.274 + endloop + endfacet + facet normal -0.118866 -0.105759 0.987262 + outer loop + vertex -436.842 116.921 363.869 + vertex -442.466 120.274 363.551 + vertex -442.233 116.968 363.225 + endloop + endfacet + facet normal -0.0949151 -0.10434 0.990002 + outer loop + vertex -442.466 120.274 363.551 + vertex -448.059 120.429 363.031 + vertex -442.233 116.968 363.225 + endloop + endfacet + facet normal -0.0764919 -0.0870184 0.993266 + outer loop + vertex -448.059 120.429 363.031 + vertex -454.441 124.015 362.854 + vertex -453.585 120.645 362.625 + endloop + endfacet + facet normal -0.0604964 -0.0830521 0.994707 + outer loop + vertex -453.585 120.645 362.625 + vertex -454.441 124.015 362.854 + vertex -462.967 124.178 362.349 + endloop + endfacet + facet normal -0.0501551 -0.112745 0.992357 + outer loop + vertex -462.967 124.178 362.349 + vertex -475.92 125.621 361.858 + vertex -463.054 117.539 361.591 + endloop + endfacet + facet normal -0.0804599 -0.129154 0.988355 + outer loop + vertex -447.995 117.196 362.695 + vertex -454.798 117.852 362.227 + vertex -447.81 114.003 362.293 + endloop + endfacet + facet normal -0.0966003 -0.129893 0.986811 + outer loop + vertex -441.91 113.731 362.834 + vertex -447.995 117.196 362.695 + vertex -447.81 114.003 362.293 + endloop + endfacet + facet normal -0.118237 -0.157907 0.98035 + outer loop + vertex -436.4 113.65 363.486 + vertex -441.91 113.731 362.834 + vertex -435.885 110.453 363.033 + endloop + endfacet + facet normal -0.141755 -0.161176 0.976692 + outer loop + vertex -430.577 110.588 363.826 + vertex -436.4 113.65 363.486 + vertex -435.885 110.453 363.033 + endloop + endfacet + facet normal -0.161678 -0.195955 0.967193 + outer loop + vertex -425.654 111.038 364.74 + vertex -430.577 110.588 363.826 + vertex -424.891 107.844 364.22 + endloop + endfacet + facet normal -0.180234 -0.199727 0.963133 + outer loop + vertex -420.484 108.561 365.194 + vertex -425.654 111.038 364.74 + vertex -424.891 107.844 364.22 + endloop + endfacet + facet normal -0.174284 -0.228962 0.957706 + outer loop + vertex -420.484 108.561 365.194 + vertex -424.891 107.844 364.22 + vertex -419.557 105.395 364.605 + endloop + endfacet + facet normal -0.181582 -0.258795 0.948711 + outer loop + vertex -415.861 106.193 365.53 + vertex -419.557 105.395 364.605 + vertex -414.862 103.161 364.895 + endloop + endfacet + facet normal -0.186854 -0.285573 0.939965 + outer loop + vertex -411.855 103.537 365.607 + vertex -414.862 103.161 364.895 + vertex -411.314 101.275 365.027 + endloop + endfacet + facet normal -0.175915 -0.282659 0.942952 + outer loop + vertex -413.965 100.568 364.291 + vertex -418.674 102.416 363.967 + vertex -417.675 99.6709 363.33 + endloop + endfacet + facet normal -0.163353 -0.27887 0.946334 + outer loop + vertex -418.674 102.416 363.967 + vertex -423.398 101.763 362.959 + vertex -417.675 99.6709 363.33 + endloop + endfacet + facet normal -0.152224 -0.28167 0.947359 + outer loop + vertex -422.503 98.9581 362.278 + vertex -428.744 101.444 362.015 + vertex -428.112 98.7009 361.3 + endloop + endfacet + facet normal -0.14984 -0.306136 0.940122 + outer loop + vertex -422.503 98.9581 362.278 + vertex -428.112 98.7009 361.3 + vertex -421.581 96.4273 361.601 + endloop + endfacet + facet normal -0.153474 -0.250958 0.955754 + outer loop + vertex -424.137 104.732 363.62 + vertex -429.336 104.376 362.691 + vertex -423.398 101.763 362.959 + endloop + endfacet + facet normal -0.138179 -0.251472 0.95795 + outer loop + vertex -428.744 101.444 362.015 + vertex -434.883 104.378 361.899 + vertex -434.403 101.511 361.216 + endloop + endfacet + facet normal -0.138071 -0.219275 0.965844 + outer loop + vertex -429.941 107.435 363.299 + vertex -435.371 107.365 362.507 + vertex -429.336 104.376 362.691 + endloop + endfacet + facet normal -0.11815 -0.186263 0.97537 + outer loop + vertex -435.371 107.365 362.507 + vertex -441.517 110.588 362.378 + vertex -441.109 107.564 361.85 + endloop + endfacet + facet normal -0.0995855 -0.184192 0.977832 + outer loop + vertex -441.517 110.588 362.378 + vertex -447.536 110.903 361.824 + vertex -441.109 107.564 361.85 + endloop + endfacet + facet normal -0.088388 -0.164004 0.982492 + outer loop + vertex -447.536 110.903 361.824 + vertex -453.519 114.249 361.845 + vertex -454.523 111.576 361.308 + endloop + endfacet + facet normal -0.0863451 -0.19455 0.977085 + outer loop + vertex -453.041 108.209 360.769 + vertex -454.523 111.576 361.308 + vertex -462.828 111.396 360.539 + endloop + endfacet + facet normal -0.0808238 -0.236261 0.968322 + outer loop + vertex -462.828 111.396 360.539 + vertex -475.943 113.269 359.901 + vertex -462.482 105.87 359.219 + endloop + endfacet + facet normal -0.0867381 -0.246733 0.965194 + outer loop + vertex -462.482 105.87 359.219 + vertex -475.943 113.269 359.901 + vertex -475.722 108.11 358.602 + endloop + endfacet + facet normal -0.0753548 -0.246501 0.966209 + outer loop + vertex -475.943 113.269 359.901 + vertex -488.571 115.651 359.524 + vertex -475.722 108.11 358.602 + endloop + endfacet + facet normal -0.0813919 -0.256412 0.963135 + outer loop + vertex -475.722 108.11 358.602 + vertex -488.571 115.651 359.524 + vertex -488.466 110.743 358.226 + endloop + endfacet + facet normal -0.0739049 -0.256412 0.963738 + outer loop + vertex -488.571 115.651 359.524 + vertex -500.689 118.484 359.348 + vertex -488.466 110.743 358.226 + endloop + endfacet + facet normal -0.0777754 -0.262252 0.96186 + outer loop + vertex -488.466 110.743 358.226 + vertex -500.689 118.484 359.348 + vertex -500.662 113.658 358.034 + endloop + endfacet + facet normal -0.0724931 -0.262329 0.962252 + outer loop + vertex -500.689 118.484 359.348 + vertex -512.595 121.534 359.283 + vertex -500.662 113.658 358.034 + endloop + endfacet + facet normal -0.0764462 -0.268021 0.960375 + outer loop + vertex -500.662 113.658 358.034 + vertex -512.595 121.534 359.283 + vertex -512.605 116.725 357.94 + endloop + endfacet + facet normal -0.0736269 -0.268083 0.960578 + outer loop + vertex -512.595 121.534 359.283 + vertex -524.61 124.734 359.255 + vertex -512.605 116.725 357.94 + endloop + endfacet + facet normal -0.0763733 -0.271985 0.959266 + outer loop + vertex -512.605 116.725 357.94 + vertex -524.61 124.734 359.255 + vertex -524.594 119.881 357.88 + endloop + endfacet + facet normal -0.0755888 -0.271999 0.959324 + outer loop + vertex -524.61 124.734 359.255 + vertex -536.901 128.09 359.238 + vertex -524.594 119.881 357.88 + endloop + endfacet + facet normal -0.0772367 -0.274337 0.958527 + outer loop + vertex -524.594 119.881 357.88 + vertex -536.901 128.09 359.238 + vertex -536.831 123.205 357.845 + endloop + endfacet + facet normal -0.0779858 -0.274331 0.958468 + outer loop + vertex -536.901 128.09 359.238 + vertex -549.42 131.642 359.236 + vertex -536.831 123.205 357.845 + endloop + endfacet + facet normal -0.0786582 -0.275281 0.958141 + outer loop + vertex -536.831 123.205 357.845 + vertex -549.42 131.642 359.236 + vertex -549.322 126.754 357.839 + endloop + endfacet + facet normal -0.0783902 -0.275281 0.958162 + outer loop + vertex -549.42 131.642 359.236 + vertex -561.864 135.233 359.249 + vertex -549.322 126.754 357.839 + endloop + endfacet + facet normal -0.07994 -0.277448 0.957409 + outer loop + vertex -549.322 126.754 357.839 + vertex -561.864 135.233 359.249 + vertex -561.754 130.336 357.839 + endloop + endfacet + facet normal -0.0787432 -0.27745 0.957508 + outer loop + vertex -561.864 135.233 359.249 + vertex -573.627 138.486 359.225 + vertex -561.754 130.336 357.839 + endloop + endfacet + facet normal -0.0815747 -0.281341 0.956134 + outer loop + vertex -561.754 130.336 357.839 + vertex -573.627 138.486 359.225 + vertex -573.487 133.513 357.773 + endloop + endfacet + facet normal -0.0785873 -0.281331 0.956387 + outer loop + vertex -573.627 138.486 359.225 + vertex -584.021 140.848 359.065 + vertex -573.487 133.513 357.773 + endloop + endfacet + facet normal -0.0903538 -0.2972 0.950531 + outer loop + vertex -573.487 133.513 357.773 + vertex -584.021 140.848 359.065 + vertex -583.606 135.586 357.46 + endloop + endfacet + facet normal -0.0855994 -0.29698 0.951039 + outer loop + vertex -583.606 135.586 357.46 + vertex -584.021 140.848 359.065 + vertex -592.865 142.086 358.656 + endloop + endfacet + facet normal -0.11728 -0.338881 0.933491 + outer loop + vertex -592.865 142.086 358.656 + vertex -592.089 135.324 356.299 + vertex -583.606 135.586 357.46 + endloop + endfacet + facet normal -0.104167 -0.262842 0.959199 + outer loop + vertex -446.855 105.005 360.637 + vertex -453.99 105.709 360.056 + vertex -446.556 102.198 359.901 + endloop + endfacet + facet normal -0.107716 -0.226409 0.968058 + outer loop + vertex -440.698 104.635 361.236 + vertex -447.205 107.915 361.279 + vertex -446.855 105.005 360.637 + endloop + endfacet + facet normal -0.120618 -0.249235 0.960902 + outer loop + vertex -434.883 104.378 361.899 + vertex -440.698 104.635 361.236 + vertex -434.403 101.511 361.216 + endloop + endfacet + facet normal -0.137441 -0.279057 0.950388 + outer loop + vertex -428.744 101.444 362.015 + vertex -434.403 101.511 361.216 + vertex -428.112 98.7009 361.3 + endloop + endfacet + facet normal -0.126929 -0.287167 0.949434 + outer loop + vertex -433.923 98.815 360.482 + vertex -440.289 101.792 360.531 + vertex -440.003 99.1542 359.772 + endloop + endfacet + facet normal -0.118115 -0.311061 0.943022 + outer loop + vertex -440.003 99.1542 359.772 + vertex -446.566 99.6801 359.123 + vertex -440.116 96.9526 359.031 + endloop + endfacet + facet normal -0.110255 -0.296203 0.94874 + outer loop + vertex -446.566 99.6801 359.123 + vertex -452.574 102.618 359.342 + vertex -453.999 100.736 358.589 + endloop + endfacet + facet normal -0.118958 -0.323584 0.938692 + outer loop + vertex -440.915 95.4376 358.402 + vertex -447.518 97.7796 358.373 + vertex -451.69 96.7919 357.504 + endloop + endfacet + facet normal -0.106247 -0.313243 0.943711 + outer loop + vertex -453.632 98.8717 358.011 + vertex -453.999 100.736 358.589 + vertex -462.543 101.594 357.912 + endloop + endfacet + facet normal -0.107588 -0.381636 0.91803 + outer loop + vertex -501.375 110.13 356.777 + vertex -513.129 113.069 356.621 + vertex -503.161 107.735 355.572 + endloop + endfacet + facet normal -0.128701 -0.459948 0.878569 + outer loop + vertex -581.314 127.483 354.303 + vertex -575.479 125.058 353.888 + vertex -576.062 127.275 354.964 + endloop + endfacet + facet normal -0.135082 -0.460916 0.877103 + outer loop + vertex -575.479 125.058 353.888 + vertex -569.203 123.594 354.086 + vertex -576.062 127.275 354.964 + endloop + endfacet + facet normal -0.129018 -0.455341 0.880919 + outer loop + vertex -569.203 123.594 354.086 + vertex -563.998 121.765 353.903 + vertex -564.325 123.789 354.9 + endloop + endfacet + facet normal -0.129225 -0.455356 0.880881 + outer loop + vertex -563.998 121.765 353.903 + vertex -557.011 119.688 353.854 + vertex -564.325 123.789 354.9 + endloop + endfacet + facet normal -0.133483 -0.459395 0.878145 + outer loop + vertex -557.011 119.688 353.854 + vertex -549.653 117.615 353.888 + vertex -551.516 120.115 354.912 + endloop + endfacet + facet normal -0.133209 -0.459241 0.878267 + outer loop + vertex -549.653 117.615 353.888 + vertex -544.562 116.476 354.064 + vertex -551.516 120.115 354.912 + endloop + endfacet + facet normal -0.129259 -0.467369 0.874562 + outer loop + vertex -544.562 116.476 354.064 + vertex -538.131 114.166 353.78 + vertex -538.994 116.649 354.98 + endloop + endfacet + facet normal -0.136748 -0.468998 0.872548 + outer loop + vertex -538.131 114.166 353.78 + vertex -531.302 112.92 354.181 + vertex -538.994 116.649 354.98 + endloop + endfacet + facet normal -0.12756 -0.457907 0.879801 + outer loop + vertex -531.302 112.92 354.181 + vertex -526.401 111.389 354.095 + vertex -526.857 113.431 355.091 + endloop + endfacet + facet normal -0.126451 -0.457771 0.880032 + outer loop + vertex -526.401 111.389 354.095 + vertex -520.29 109.777 354.134 + vertex -526.857 113.431 355.091 + endloop + endfacet + facet normal -0.13018 -0.455537 0.880647 + outer loop + vertex -520.29 109.777 354.134 + vertex -513.225 108.064 354.293 + vertex -514.714 110.378 355.269 + endloop + endfacet + facet normal -0.130601 -0.455738 0.880481 + outer loop + vertex -513.225 108.064 354.293 + vertex -506.654 106.684 354.553 + vertex -514.714 110.378 355.269 + endloop + endfacet + facet normal -0.131166 -0.456249 0.880132 + outer loop + vertex -502.376 105.533 354.594 + vertex -506.654 106.684 354.553 + vertex -503.218 105.364 354.381 + endloop + endfacet + facet normal -0.127565 -0.467433 0.874776 + outer loop + vertex -503.218 105.364 354.381 + vertex -501.765 104.935 354.363 + vertex -502.376 105.533 354.594 + endloop + endfacet + facet normal -0.149366 -0.518252 0.842084 + outer loop + vertex -506.391 103.361 352.628 + vertex -505.871 105.129 353.808 + vertex -515.219 106.451 352.964 + endloop + endfacet + facet normal -0.133024 -0.485514 0.864049 + outer loop + vertex -503.218 105.364 354.381 + vertex -502.726 104.348 353.886 + vertex -501.765 104.935 354.363 + endloop + endfacet + facet normal -0.101231 -0.446065 0.889257 + outer loop + vertex -502.376 105.533 354.594 + vertex -501.765 104.935 354.363 + vertex -501.654 105.096 354.457 + endloop + endfacet + facet normal -0.128908 -0.44769 0.884848 + outer loop + vertex -501.306 105.604 354.785 + vertex -506.654 106.684 354.553 + vertex -502.376 105.533 354.594 + endloop + endfacet + facet normal -0.157434 -0.516235 0.841853 + outer loop + vertex -500.567 102.824 353.271 + vertex -500.785 104.082 354.001 + vertex -501.339 104.481 354.143 + endloop + endfacet + facet normal -0.135434 -0.489259 0.861559 + outer loop + vertex -496.186 104.621 355.032 + vertex -501.306 105.604 354.785 + vertex -498.801 103.794 354.152 + endloop + endfacet + facet normal -0.124463 -0.42486 0.896662 + outer loop + vertex -496.186 104.621 355.032 + vertex -490.999 103.354 355.152 + vertex -491.749 105.032 355.843 + endloop + endfacet + facet normal -0.123058 -0.424401 0.897073 + outer loop + vertex -490.999 103.354 355.152 + vertex -485.27 101.882 355.241 + vertex -491.749 105.032 355.843 + endloop + endfacet + facet normal -0.123481 -0.416071 0.900909 + outer loop + vertex -485.27 101.882 355.241 + vertex -477.541 99.8436 355.359 + vertex -479.004 102.042 356.174 + endloop + endfacet + facet normal -0.127134 -0.417985 0.899514 + outer loop + vertex -477.541 99.8436 355.359 + vertex -471.228 98.9785 355.85 + vertex -479.004 102.042 356.174 + endloop + endfacet + facet normal -0.119362 -0.395705 0.910588 + outer loop + vertex -471.228 98.9785 355.85 + vertex -464.985 97.3096 355.943 + vertex -465.772 99.3375 356.721 + endloop + endfacet + facet normal -0.125056 -0.397347 0.909107 + outer loop + vertex -464.985 97.3096 355.943 + vertex -458.563 96.5551 356.496 + vertex -465.772 99.3375 356.721 + endloop + endfacet + facet normal -0.121084 -0.382604 0.915943 + outer loop + vertex -458.563 96.5551 356.496 + vertex -452.761 95.1232 356.665 + vertex -451.69 96.7919 357.504 + endloop + endfacet + facet normal -0.127875 -0.378615 0.916678 + outer loop + vertex -452.761 95.1232 356.665 + vertex -446.531 94.4376 357.251 + vertex -451.69 96.7919 357.504 + endloop + endfacet + facet normal -0.128779 -0.379382 0.916234 + outer loop + vertex -446.531 94.4376 357.251 + vertex -440.629 93.2573 357.592 + vertex -440.454 94.1758 357.997 + endloop + endfacet + facet normal -0.132515 -0.37341 0.918153 + outer loop + vertex -440.629 93.2573 357.592 + vertex -435.448 92.7418 358.13 + vertex -437.439 93.3147 358.076 + endloop + endfacet + facet normal -0.136895 -0.363765 0.921377 + outer loop + vertex -435.448 92.7418 358.13 + vertex -429.653 92.2851 358.811 + vertex -433.947 93.0864 358.489 + endloop + endfacet + facet normal -0.141309 -0.408481 0.901762 + outer loop + vertex -426.614 91.5831 358.998 + vertex -436.542 91.5298 357.418 + vertex -428.025 89.967 358.045 + endloop + endfacet + facet normal -0.142044 -0.346964 0.92706 + outer loop + vertex -429.653 92.2851 358.811 + vertex -423.738 92.1847 359.679 + vertex -428.155 92.6702 359.184 + endloop + endfacet + facet normal -0.146552 -0.353158 0.924014 + outer loop + vertex -425.006 92.0338 359.426 + vertex -426.614 91.5831 358.998 + vertex -421.351 91.8696 359.943 + endloop + endfacet + facet normal -0.149124 -0.345876 0.926354 + outer loop + vertex -423.738 92.1847 359.679 + vertex -418.244 92.1067 360.535 + vertex -422.093 92.4204 360.032 + endloop + endfacet + facet normal -0.150153 -0.381006 0.912298 + outer loop + vertex -416.084 92.4573 361.037 + vertex -422.093 92.4204 360.032 + vertex -418.244 92.1067 360.535 + endloop + endfacet + facet normal -0.15038 -0.372772 0.915657 + outer loop + vertex -421.351 91.8696 359.943 + vertex -420.87 91.0595 359.692 + vertex -416.016 91.7795 360.782 + endloop + endfacet + facet normal -0.148302 -0.381711 0.912307 + outer loop + vertex -416.016 91.7795 360.782 + vertex -420.87 91.0595 359.692 + vertex -414.847 90.8151 360.569 + endloop + endfacet + facet normal -0.146222 -0.415598 0.897718 + outer loop + vertex -414.847 90.8151 360.569 + vertex -420.483 89.2172 358.911 + vertex -413.931 88.8888 359.826 + endloop + endfacet + facet normal -0.147627 -0.441801 0.884883 + outer loop + vertex -413.931 88.8888 359.826 + vertex -419.278 86.3568 357.67 + vertex -412.84 86.4708 358.801 + endloop + endfacet + facet normal -0.144072 -0.475189 0.868008 + outer loop + vertex -412.84 86.4708 358.801 + vertex -419.278 86.3568 357.67 + vertex -416.134 82.6529 356.164 + endloop + endfacet + facet normal -0.144138 -0.448044 0.882316 + outer loop + vertex -408.97 88.5513 360.478 + vertex -408.819 85.3656 358.885 + vertex -405.448 88.2829 360.917 + endloop + endfacet + facet normal -0.143876 -0.429665 0.891453 + outer loop + vertex -406.316 90.4838 361.838 + vertex -408.97 88.5513 360.478 + vertex -405.448 88.2829 360.917 + endloop + endfacet + facet normal -0.14977 -0.410142 0.89964 + outer loop + vertex -406.89 91.7192 362.306 + vertex -409.774 90.6556 361.341 + vertex -406.316 90.4838 361.838 + endloop + endfacet + facet normal -0.157289 -0.382273 0.910564 + outer loop + vertex -407.189 92.3995 362.543 + vertex -402.439 92.2161 363.287 + vertex -406.046 93.063 363.019 + endloop + endfacet + facet normal -0.156583 -0.378766 0.91215 + outer loop + vertex -406.046 93.063 363.019 + vertex -402.439 92.2161 363.287 + vertex -404.872 94.1829 363.686 + endloop + endfacet + facet normal -0.155692 -0.398079 0.904043 + outer loop + vertex -410.554 91.8766 361.744 + vertex -409.774 90.6556 361.341 + vertex -406.89 91.7192 362.306 + endloop + endfacet + facet normal -0.157551 -0.370167 0.915508 + outer loop + vertex -409.638 92.3568 362.096 + vertex -412.927 92.2177 361.474 + vertex -410.554 91.8766 361.744 + endloop + endfacet + facet normal -0.154704 -0.362587 0.91902 + outer loop + vertex -418.244 92.1067 360.535 + vertex -412.927 92.2177 361.474 + vertex -416.084 92.4573 361.037 + endloop + endfacet + facet normal -0.151487 -0.362467 0.919603 + outer loop + vertex -416.084 92.4573 361.037 + vertex -421.105 93.0627 360.448 + vertex -422.093 92.4204 360.032 + endloop + endfacet + facet normal -0.146667 -0.346434 0.926538 + outer loop + vertex -421.105 93.0627 360.448 + vertex -427.211 94.3888 359.977 + vertex -427.401 93.2136 359.508 + endloop + endfacet + facet normal -0.139313 -0.329723 0.933742 + outer loop + vertex -427.52 96.2768 360.598 + vertex -433.591 96.4791 359.764 + vertex -427.211 94.3888 359.977 + endloop + endfacet + facet normal -0.150772 -0.308957 0.939049 + outer loop + vertex -421.581 96.4273 361.601 + vertex -428.112 98.7009 361.3 + vertex -427.52 96.2768 360.598 + endloop + endfacet + facet normal -0.161305 -0.309512 0.937114 + outer loop + vertex -415.842 97.0094 362.781 + vertex -422.503 98.9581 362.278 + vertex -421.581 96.4273 361.601 + endloop + endfacet + facet normal -0.168421 -0.320399 0.93219 + outer loop + vertex -411.391 96.7807 363.507 + vertex -412.848 98.3227 363.773 + vertex -415.842 97.0094 362.781 + endloop + endfacet + facet normal -0.17521 -0.326245 0.928906 + outer loop + vertex -409.539 97.5318 364.12 + vertex -412.848 98.3227 363.773 + vertex -411.391 96.7807 363.507 + endloop + endfacet + facet normal -0.162027 -0.351941 0.921892 + outer loop + vertex -410.184 94.4477 362.843 + vertex -411.266 95.5468 363.073 + vertex -414.786 94.7303 362.142 + endloop + endfacet + facet normal -0.154624 -0.354123 0.922328 + outer loop + vertex -414.786 94.7303 362.142 + vertex -420.988 94.4015 360.976 + vertex -414.516 93.2067 361.603 + endloop + endfacet + facet normal -0.157423 -0.367164 0.916738 + outer loop + vertex -410.346 93.0353 362.25 + vertex -414.516 93.2067 361.603 + vertex -410.112 92.6786 362.147 + endloop + endfacet + facet normal -0.159685 -0.378868 0.91157 + outer loop + vertex -406.046 93.063 363.019 + vertex -410.112 92.6786 362.147 + vertex -407.189 92.3995 362.543 + endloop + endfacet + facet normal -0.161546 -0.371598 0.914231 + outer loop + vertex -407.792 94.0524 363.113 + vertex -410.554 93.6219 362.45 + vertex -408.008 93.2711 362.757 + endloop + endfacet + facet normal -0.165967 -0.365334 0.915962 + outer loop + vertex -406.222 94.7445 363.673 + vertex -408.171 95.0202 363.43 + vertex -407.792 94.0524 363.113 + endloop + endfacet + facet normal -0.159182 -0.376365 0.912694 + outer loop + vertex -404.872 94.1829 363.686 + vertex -406.143 93.7989 363.306 + vertex -406.046 93.063 363.019 + endloop + endfacet + facet normal -0.176261 -0.366379 0.913618 + outer loop + vertex -405.907 96.1591 364.279 + vertex -404.872 94.1829 363.686 + vertex -404.275 95.5057 364.331 + endloop + endfacet + facet normal -0.165654 -0.361851 0.9174 + outer loop + vertex -406.932 95.7266 363.932 + vertex -408.171 95.0202 363.43 + vertex -406.222 94.7445 363.673 + endloop + endfacet + facet normal -0.169987 -0.355463 0.919103 + outer loop + vertex -406.932 95.7266 363.932 + vertex -408.798 96.1647 363.757 + vertex -408.171 95.0202 363.43 + endloop + endfacet + facet normal -0.169514 -0.337782 0.925834 + outer loop + vertex -409.539 97.5318 364.12 + vertex -411.391 96.7807 363.507 + vertex -408.798 96.1647 363.757 + endloop + endfacet + facet normal -0.173818 -0.319241 0.931597 + outer loop + vertex -410.479 99.2473 364.532 + vertex -412.848 98.3227 363.773 + vertex -409.539 97.5318 364.12 + endloop + endfacet + facet normal -0.186468 -0.304629 0.93404 + outer loop + vertex -409.125 100.024 365.056 + vertex -411.314 101.275 365.027 + vertex -410.479 99.2473 364.532 + endloop + endfacet + facet normal -0.16821 -0.33117 0.928457 + outer loop + vertex -408.429 98.3881 364.633 + vertex -407.493 97.0037 364.309 + vertex -407.439 98.6828 364.918 + endloop + endfacet + facet normal -0.187709 -0.306824 0.933073 + outer loop + vertex -410.011 101.531 365.373 + vertex -411.314 101.275 365.027 + vertex -409.125 100.024 365.056 + endloop + endfacet + facet normal -0.193078 -0.286656 0.938376 + outer loop + vertex -410.011 101.531 365.373 + vertex -411.855 103.537 365.607 + vertex -411.314 101.275 365.027 + endloop + endfacet + facet normal -0.191318 -0.261449 0.946067 + outer loop + vertex -411.855 103.537 365.607 + vertex -415.861 106.193 365.53 + vertex -414.862 103.161 364.895 + endloop + endfacet + facet normal -0.188616 -0.232496 0.954133 + outer loop + vertex -415.861 106.193 365.53 + vertex -420.484 108.561 365.194 + vertex -419.557 105.395 364.605 + endloop + endfacet + facet normal -0.180315 -0.199905 0.963081 + outer loop + vertex -421.43 111.833 365.696 + vertex -425.654 111.038 364.74 + vertex -420.484 108.561 365.194 + endloop + endfacet + facet normal -0.185846 -0.168773 0.967976 + outer loop + vertex -422.241 115.135 366.116 + vertex -426.36 114.294 365.178 + vertex -421.43 111.833 365.696 + endloop + endfacet + facet normal -0.19035 -0.137869 0.971987 + outer loop + vertex -422.95 118.501 366.454 + vertex -426.956 117.611 365.544 + vertex -422.241 115.135 366.116 + endloop + endfacet + facet normal -0.194488 -0.11172 0.974522 + outer loop + vertex -423.523 121.911 366.731 + vertex -427.462 121.001 365.84 + vertex -422.95 118.501 366.454 + endloop + endfacet + facet normal -0.198989 -0.0897905 0.97588 + outer loop + vertex -424.001 125.369 366.952 + vertex -427.874 124.431 366.076 + vertex -423.523 121.911 366.731 + endloop + endfacet + facet normal -0.204095 -0.0720223 0.976298 + outer loop + vertex -424.37 128.847 367.131 + vertex -428.199 127.879 366.259 + vertex -424.001 125.369 366.952 + endloop + endfacet + facet normal -0.20891 -0.0576347 0.976235 + outer loop + vertex -424.646 132.344 367.278 + vertex -428.455 131.342 366.404 + vertex -424.37 128.847 367.131 + endloop + endfacet + facet normal -0.212679 -0.0475031 0.975967 + outer loop + vertex -424.878 135.869 367.399 + vertex -428.667 134.83 366.523 + vertex -424.646 132.344 367.278 + endloop + endfacet + facet normal -0.215524 -0.0417604 0.975605 + outer loop + vertex -425.128 139.424 367.496 + vertex -428.858 138.336 366.626 + vertex -424.878 135.869 367.399 + endloop + endfacet + facet normal -0.215761 -0.0448534 0.975416 + outer loop + vertex -425.418 142.998 367.597 + vertex -429.105 141.868 366.729 + vertex -425.128 139.424 367.496 + endloop + endfacet + facet normal -0.207332 -0.0832955 0.974718 + outer loop + vertex -425.752 146.637 367.836 + vertex -429.516 145.466 366.936 + vertex -425.418 142.998 367.597 + endloop + endfacet + facet normal -0.187898 -0.186605 0.964299 + outer loop + vertex -426.186 150.37 368.474 + vertex -430.13 149.162 367.472 + vertex -425.752 146.637 367.836 + endloop + endfacet + facet normal -0.349819 -0.182619 0.918846 + outer loop + vertex -419.906 150.963 369.879 + vertex -418.226 149.621 370.252 + vertex -417.043 155.4 371.851 + endloop + endfacet + facet normal -0.218281 -0.275218 0.936274 + outer loop + vertex -420.298 153.148 370.43 + vertex -419.906 150.963 369.879 + vertex -417.043 155.4 371.851 + endloop + endfacet + facet normal -0.514697 -0.129146 0.84759 + outer loop + vertex -416.626 146.22 370.706 + vertex -417.043 155.4 371.851 + vertex -418.226 149.621 370.252 + endloop + endfacet + facet normal -0.443504 -0.0897651 0.891766 + outer loop + vertex -418.226 149.621 370.252 + vertex -418.505 147.292 369.879 + vertex -416.626 146.22 370.706 + endloop + endfacet + facet normal -0.253169 -0.0708119 0.964827 + outer loop + vertex -419.659 148.395 369.542 + vertex -422.253 148.237 368.849 + vertex -419.86 145.983 369.312 + endloop + endfacet + facet normal -0.430107 -0.0592896 0.900829 + outer loop + vertex -418.505 147.292 369.879 + vertex -418.337 146.069 369.879 + vertex -416.626 146.22 370.706 + endloop + endfacet + facet normal -0.432113 -0.0377378 0.901029 + outer loop + vertex -418.337 146.069 369.879 + vertex -418.478 144.564 369.748 + vertex -416.626 146.22 370.706 + endloop + endfacet + facet normal -0.292922 -0.0488215 0.954889 + outer loop + vertex -419.86 145.983 369.312 + vertex -422.37 144.5 368.466 + vertex -419.957 142.789 369.119 + endloop + endfacet + facet normal -0.416712 -0.0584961 0.907154 + outer loop + vertex -418.478 144.564 369.748 + vertex -417.928 141.597 369.809 + vertex -416.626 146.22 370.706 + endloop + endfacet + facet normal -0.39371 -0.0668424 0.916801 + outer loop + vertex -415.611 138.906 370.608 + vertex -416.626 146.22 370.706 + vertex -417.928 141.597 369.809 + endloop + endfacet + facet normal -0.296252 -0.0461916 0.953992 + outer loop + vertex -419.957 142.789 369.119 + vertex -422.189 140.956 368.337 + vertex -419.696 139.319 369.032 + endloop + endfacet + facet normal -0.384775 -0.0578391 0.921196 + outer loop + vertex -417.928 141.597 369.809 + vertex -417.819 137.937 369.625 + vertex -415.611 138.906 370.608 + endloop + endfacet + facet normal -0.293063 -0.0521412 0.95467 + outer loop + vertex -419.696 139.319 369.032 + vertex -421.91 137.377 368.246 + vertex -419.366 135.726 368.937 + endloop + endfacet + facet normal -0.381345 -0.066502 0.922038 + outer loop + vertex -417.819 137.937 369.625 + vertex -417.17 134.619 369.654 + vertex -415.611 138.906 370.608 + endloop + endfacet + facet normal -0.377258 -0.0683327 0.923584 + outer loop + vertex -414.773 133.013 370.515 + vertex -415.611 138.906 370.608 + vertex -417.17 134.619 369.654 + endloop + endfacet + facet normal -0.287847 -0.0612461 0.955716 + outer loop + vertex -419.366 135.726 368.937 + vertex -421.628 133.787 368.131 + vertex -419.062 132.156 368.8 + endloop + endfacet + facet normal -0.380404 -0.0739526 0.921859 + outer loop + vertex -417.17 134.619 369.654 + vertex -417.109 131.051 369.393 + vertex -414.773 133.013 370.515 + endloop + endfacet + facet normal -0.280405 -0.0744084 0.956993 + outer loop + vertex -419.062 132.156 368.8 + vertex -421.351 130.247 367.98 + vertex -418.729 128.677 368.627 + endloop + endfacet + facet normal -0.365907 -0.0935441 0.925938 + outer loop + vertex -417.109 131.051 369.393 + vertex -416.291 128.068 369.415 + vertex -414.773 133.013 370.515 + endloop + endfacet + facet normal -0.38361 -0.0866617 0.91942 + outer loop + vertex -414.773 133.013 370.515 + vertex -416.291 128.068 369.415 + vertex -413.726 129.539 370.624 + endloop + endfacet + facet normal -0.365776 -0.120581 0.922859 + outer loop + vertex -416.291 128.068 369.415 + vertex -414.905 126.579 369.77 + vertex -413.726 129.539 370.624 + endloop + endfacet + facet normal -0.378875 -0.114071 0.918391 + outer loop + vertex -413.482 127.899 370.521 + vertex -413.726 129.539 370.624 + vertex -414.905 126.579 369.77 + endloop + endfacet + facet normal -0.361927 -0.134648 0.922431 + outer loop + vertex -414.905 126.579 369.77 + vertex -413.957 126.908 370.19 + vertex -413.482 127.899 370.521 + endloop + endfacet + facet normal -0.389609 -0.118334 0.913347 + outer loop + vertex -413.957 126.908 370.19 + vertex -412.735 127.907 370.84 + vertex -413.482 127.899 370.521 + endloop + endfacet + facet normal -0.389418 -0.118598 0.913394 + outer loop + vertex -412.735 127.907 370.84 + vertex -413.957 126.908 370.19 + vertex -413.967 126.075 370.077 + endloop + endfacet + facet normal -0.366983 -0.120102 0.922442 + outer loop + vertex -413.957 126.908 370.19 + vertex -414.905 126.579 369.77 + vertex -413.967 126.075 370.077 + endloop + endfacet + facet normal -0.403635 -0.117064 0.9074 + outer loop + vertex -413.482 127.899 370.521 + vertex -411.597 129.982 371.628 + vertex -413.726 129.539 370.624 + endloop + endfacet + facet normal -0.40496 -0.111063 0.907564 + outer loop + vertex -413.726 129.539 370.624 + vertex -411.597 129.982 371.628 + vertex -411.328 133.769 372.212 + endloop + endfacet + facet normal -0.422192 -0.0988704 0.901099 + outer loop + vertex -413.726 129.539 370.624 + vertex -411.328 133.769 372.212 + vertex -414.773 133.013 370.515 + endloop + endfacet + facet normal -0.428136 -0.0713245 0.900895 + outer loop + vertex -412.843 137.261 371.768 + vertex -414.773 133.013 370.515 + vertex -411.328 133.769 372.212 + endloop + endfacet + facet normal -0.422709 -0.0744701 0.903201 + outer loop + vertex -414.773 133.013 370.515 + vertex -412.843 137.261 371.768 + vertex -415.611 138.906 370.608 + endloop + endfacet + facet normal -0.42288 -0.0748362 0.90309 + outer loop + vertex -415.611 138.906 370.608 + vertex -412.843 137.261 371.768 + vertex -413.004 142.73 372.146 + endloop + endfacet + facet normal -0.427103 -0.0712742 0.90139 + outer loop + vertex -415.611 138.906 370.608 + vertex -413.004 142.73 372.146 + vertex -416.626 146.22 370.706 + endloop + endfacet + facet normal -0.437348 -0.0844109 0.895322 + outer loop + vertex -416.626 146.22 370.706 + vertex -413.004 142.73 372.146 + vertex -413.436 150.029 372.623 + endloop + endfacet + facet normal -0.390685 -0.131441 0.911092 + outer loop + vertex -416.626 146.22 370.706 + vertex -413.436 150.029 372.623 + vertex -417.043 155.4 371.851 + endloop + endfacet + facet normal -0.378307 -0.122194 0.91758 + outer loop + vertex -417.043 155.4 371.851 + vertex -413.436 150.029 372.623 + vertex -414.271 157.851 373.32 + endloop + endfacet + facet normal -0.270196 -0.0945198 0.958155 + outer loop + vertex -418.729 128.677 368.627 + vertex -421.01 126.75 367.793 + vertex -418.405 125.24 368.379 + endloop + endfacet + facet normal -0.360387 -0.114887 0.925701 + outer loop + vertex -416.291 128.068 369.415 + vertex -416.43 124.259 368.888 + vertex -414.905 126.579 369.77 + endloop + endfacet + facet normal -0.336387 -0.133153 0.932263 + outer loop + vertex -414.905 126.579 369.77 + vertex -416.43 124.259 368.888 + vertex -415.343 124.982 369.384 + endloop + endfacet + facet normal -0.330724 -0.142141 0.932962 + outer loop + vertex -415.091 123.531 369.252 + vertex -415.343 124.982 369.384 + vertex -416.43 124.259 368.888 + endloop + endfacet + facet normal -0.351173 -0.144973 0.925019 + outer loop + vertex -415.091 123.531 369.252 + vertex -413.967 126.075 370.077 + vertex -415.343 124.982 369.384 + endloop + endfacet + facet normal -0.356285 -0.142219 0.923491 + outer loop + vertex -412.741 124.714 370.341 + vertex -413.967 126.075 370.077 + vertex -415.091 123.531 369.252 + endloop + endfacet + facet normal -0.344178 -0.166727 0.923983 + outer loop + vertex -412.741 124.714 370.341 + vertex -415.091 123.531 369.252 + vertex -414.421 120.659 368.984 + endloop + endfacet + facet normal -0.321434 -0.17817 0.930019 + outer loop + vertex -414.421 120.659 368.984 + vertex -412.666 120.773 369.612 + vertex -412.741 124.714 370.341 + endloop + endfacet + facet normal -0.320344 -0.187229 0.928614 + outer loop + vertex -413.36 117.016 368.615 + vertex -412.666 120.773 369.612 + vertex -414.421 120.659 368.984 + endloop + endfacet + facet normal -0.321263 -0.186988 0.928345 + outer loop + vertex -412.418 118.363 369.212 + vertex -412.666 120.773 369.612 + vertex -413.36 117.016 368.615 + endloop + endfacet + facet normal -0.308308 -0.197079 0.930648 + outer loop + vertex -412.418 118.363 369.212 + vertex -413.36 117.016 368.615 + vertex -411.668 116.489 369.064 + endloop + endfacet + facet normal -0.318596 -0.200858 0.926365 + outer loop + vertex -411.668 116.489 369.064 + vertex -411.14 119.928 369.991 + vertex -412.418 118.363 369.212 + endloop + endfacet + facet normal -0.328243 -0.1986 0.923479 + outer loop + vertex -409.794 117.814 370.015 + vertex -411.14 119.928 369.991 + vertex -411.668 116.489 369.064 + endloop + endfacet + facet normal -0.315961 -0.216206 0.923809 + outer loop + vertex -410.47 114.562 369.022 + vertex -409.794 117.814 370.015 + vertex -411.668 116.489 369.064 + endloop + endfacet + facet normal -0.31568 -0.216035 0.923945 + outer loop + vertex -410.47 114.562 369.022 + vertex -411.668 116.489 369.064 + vertex -411.856 112.921 368.165 + endloop + endfacet + facet normal -0.292552 -0.23687 0.926448 + outer loop + vertex -410.47 114.562 369.022 + vertex -411.856 112.921 368.165 + vertex -409.72 112.109 368.632 + endloop + endfacet + facet normal -0.303226 -0.239482 0.922335 + outer loop + vertex -409.72 112.109 368.632 + vertex -408.721 115.304 369.79 + vertex -410.47 114.562 369.022 + endloop + endfacet + facet normal -0.298534 -0.241329 0.923384 + outer loop + vertex -407.763 113.154 369.538 + vertex -408.721 115.304 369.79 + vertex -409.72 112.109 368.632 + endloop + endfacet + facet normal -0.286565 -0.262102 0.921511 + outer loop + vertex -408.599 110.337 368.477 + vertex -407.763 113.154 369.538 + vertex -409.72 112.109 368.632 + endloop + endfacet + facet normal -0.28121 -0.258937 0.924052 + outer loop + vertex -408.599 110.337 368.477 + vertex -409.72 112.109 368.632 + vertex -410.256 108.386 367.426 + endloop + endfacet + facet normal -0.254865 -0.281826 0.924996 + outer loop + vertex -408.599 110.337 368.477 + vertex -410.256 108.386 367.426 + vertex -407.864 108.242 368.041 + endloop + endfacet + facet normal -0.264984 -0.284607 0.921294 + outer loop + vertex -407.864 108.242 368.041 + vertex -406.807 111.271 369.281 + vertex -408.599 110.337 368.477 + endloop + endfacet + facet normal -0.262138 -0.285784 0.921743 + outer loop + vertex -405.774 109.411 368.998 + vertex -406.807 111.271 369.281 + vertex -407.864 108.242 368.041 + endloop + endfacet + facet normal -0.252262 -0.301573 0.919466 + outer loop + vertex -406.618 106.111 367.684 + vertex -405.774 109.411 368.998 + vertex -407.864 108.242 368.041 + endloop + endfacet + facet normal -0.240808 -0.295712 0.924427 + outer loop + vertex -406.618 106.111 367.684 + vertex -407.864 108.242 368.041 + vertex -408.403 105.315 366.964 + endloop + endfacet + facet normal -0.23319 -0.310241 0.921614 + outer loop + vertex -406.995 103.116 366.58 + vertex -406.618 106.111 367.684 + vertex -408.403 105.315 366.964 + endloop + endfacet + facet normal -0.22091 -0.303309 0.926932 + outer loop + vertex -406.995 103.116 366.58 + vertex -408.403 105.315 366.964 + vertex -408.226 102.653 366.136 + endloop + endfacet + facet normal -0.232845 -0.310308 0.921679 + outer loop + vertex -405.356 104.22 367.366 + vertex -406.618 106.111 367.684 + vertex -406.995 103.116 366.58 + endloop + endfacet + facet normal -0.221941 -0.32484 0.919359 + outer loop + vertex -405.719 101.294 366.245 + vertex -405.356 104.22 367.366 + vertex -406.995 103.116 366.58 + endloop + endfacet + facet normal -0.217917 -0.32236 0.921193 + outer loop + vertex -405.719 101.294 366.245 + vertex -406.995 103.116 366.58 + vertex -406.812 100.567 365.732 + endloop + endfacet + facet normal -0.223484 -0.324545 0.919089 + outer loop + vertex -404.119 102.537 367.073 + vertex -405.356 104.22 367.366 + vertex -405.719 101.294 366.245 + endloop + endfacet + facet normal -0.211152 -0.338912 0.916817 + outer loop + vertex -404.554 99.7066 365.926 + vertex -404.119 102.537 367.073 + vertex -405.719 101.294 366.245 + endloop + endfacet + facet normal -0.206098 -0.335671 0.919156 + outer loop + vertex -404.554 99.7066 365.926 + vertex -405.719 101.294 366.245 + vertex -405.652 99.1763 365.486 + endloop + endfacet + facet normal -0.213647 -0.338375 0.916437 + outer loop + vertex -402.93 100.989 366.778 + vertex -404.119 102.537 367.073 + vertex -404.554 99.7066 365.926 + endloop + endfacet + facet normal -0.201877 -0.351714 0.914081 + outer loop + vertex -403.453 98.2784 365.62 + vertex -402.93 100.989 366.778 + vertex -404.554 99.7066 365.926 + endloop + endfacet + facet normal -0.20003 -0.350479 0.91496 + outer loop + vertex -403.453 98.2784 365.62 + vertex -404.554 99.7066 365.926 + vertex -404.665 97.5996 365.095 + endloop + endfacet + facet normal -0.206222 -0.350637 0.913524 + outer loop + vertex -401.812 99.5894 366.493 + vertex -402.93 100.989 366.778 + vertex -403.453 98.2784 365.62 + endloop + endfacet + facet normal -0.195197 -0.362871 0.911166 + outer loop + vertex -402.449 97.0544 365.347 + vertex -401.812 99.5894 366.493 + vertex -403.453 98.2784 365.62 + endloop + endfacet + facet normal -0.193533 -0.361688 0.91199 + outer loop + vertex -402.449 97.0544 365.347 + vertex -403.453 98.2784 365.62 + vertex -403.609 96.4448 364.86 + endloop + endfacet + facet normal -0.202548 -0.360689 0.910427 + outer loop + vertex -400.777 98.5193 366.3 + vertex -401.812 99.5894 366.493 + vertex -402.449 97.0544 365.347 + endloop + endfacet + facet normal -0.192008 -0.371403 0.908401 + outer loop + vertex -401.538 96.2144 365.196 + vertex -400.777 98.5193 366.3 + vertex -402.449 97.0544 365.347 + endloop + endfacet + facet normal -0.194058 -0.373399 0.907147 + outer loop + vertex -401.538 96.2144 365.196 + vertex -402.449 97.0544 365.347 + vertex -402.792 95.1077 364.473 + endloop + endfacet + facet normal -0.200717 -0.368241 0.907806 + outer loop + vertex -399.796 97.9883 366.301 + vertex -400.777 98.5193 366.3 + vertex -401.538 96.2144 365.196 + endloop + endfacet + facet normal -0.205081 -0.362878 0.908989 + outer loop + vertex -400.777 98.5193 366.3 + vertex -399.821 101.544 367.723 + vertex -401.812 99.5894 366.493 + endloop + endfacet + facet normal -0.216406 -0.352309 0.91052 + outer loop + vertex -399.821 101.544 367.723 + vertex -400.953 102.829 367.951 + vertex -401.812 99.5894 366.493 + endloop + endfacet + facet normal -0.220471 -0.355498 0.908303 + outer loop + vertex -399.821 101.544 367.723 + vertex -398.792 105.444 369.499 + vertex -400.953 102.829 367.951 + endloop + endfacet + facet normal -0.23513 -0.34386 0.909106 + outer loop + vertex -398.792 105.444 369.499 + vertex -400.208 106.233 369.431 + vertex -400.953 102.829 367.951 + endloop + endfacet + facet normal -0.229639 -0.345416 0.90992 + outer loop + vertex -400.953 102.829 367.951 + vertex -400.208 106.233 369.431 + vertex -402.147 104.321 368.216 + endloop + endfacet + facet normal -0.223877 -0.341336 0.91289 + outer loop + vertex -400.953 102.829 367.951 + vertex -402.147 104.321 368.216 + vertex -402.93 100.989 366.778 + endloop + endfacet + facet normal -0.243612 -0.332088 0.911247 + outer loop + vertex -400.208 106.233 369.431 + vertex -401.163 108.339 369.943 + vertex -402.147 104.321 368.216 + endloop + endfacet + facet normal -0.239783 -0.333276 0.911829 + outer loop + vertex -402.147 104.321 368.216 + vertex -401.163 108.339 369.943 + vertex -403.373 105.917 368.477 + endloop + endfacet + facet normal -0.233232 -0.328788 0.915151 + outer loop + vertex -402.147 104.321 368.216 + vertex -403.373 105.917 368.477 + vertex -404.119 102.537 367.073 + endloop + endfacet + facet normal -0.256292 -0.318662 0.912562 + outer loop + vertex -401.163 108.339 369.943 + vertex -402.627 109.362 369.889 + vertex -403.373 105.917 368.477 + endloop + endfacet + facet normal -0.252486 -0.319762 0.913238 + outer loop + vertex -403.373 105.917 368.477 + vertex -402.627 109.362 369.889 + vertex -404.595 107.61 368.732 + endloop + endfacet + facet normal -0.244572 -0.314637 0.917163 + outer loop + vertex -403.373 105.917 368.477 + vertex -404.595 107.61 368.732 + vertex -405.356 104.22 367.366 + endloop + endfacet + facet normal -0.267071 -0.304156 0.914419 + outer loop + vertex -402.627 109.362 369.889 + vertex -403.524 111.608 370.375 + vertex -404.595 107.61 368.732 + endloop + endfacet + facet normal -0.261216 -0.306148 0.915445 + outer loop + vertex -404.595 107.61 368.732 + vertex -403.524 111.608 370.375 + vertex -405.774 109.411 368.998 + endloop + endfacet + facet normal -0.278447 -0.288837 0.915991 + outer loop + vertex -403.524 111.608 370.375 + vertex -404.889 112.769 370.326 + vertex -405.774 109.411 368.998 + endloop + endfacet + facet normal -0.279514 -0.290123 0.91526 + outer loop + vertex -404.889 112.769 370.326 + vertex -403.524 111.608 370.375 + vertex -402.834 117.362 372.409 + endloop + endfacet + facet normal -0.309047 -0.274749 0.910496 + outer loop + vertex -404.889 112.769 370.326 + vertex -402.834 117.362 372.409 + vertex -405.602 115.155 370.804 + endloop + endfacet + facet normal -0.289165 -0.27037 0.918305 + outer loop + vertex -404.889 112.769 370.326 + vertex -405.602 115.155 370.804 + vertex -406.807 111.271 369.281 + endloop + endfacet + facet normal -0.286976 -0.27122 0.918741 + outer loop + vertex -406.807 111.271 369.281 + vertex -405.602 115.155 370.804 + vertex -407.763 113.154 369.538 + endloop + endfacet + facet normal -0.309021 -0.247178 0.918373 + outer loop + vertex -405.602 115.155 370.804 + vertex -406.825 116.608 370.783 + vertex -407.763 113.154 369.538 + endloop + endfacet + facet normal -0.31475 -0.252049 0.915098 + outer loop + vertex -406.825 116.608 370.783 + vertex -405.602 115.155 370.804 + vertex -404.716 121.152 372.761 + endloop + endfacet + facet normal -0.354566 -0.229765 0.906362 + outer loop + vertex -406.825 116.608 370.783 + vertex -404.716 121.152 372.761 + vertex -407.455 119.622 371.301 + endloop + endfacet + facet normal -0.325634 -0.225749 0.91815 + outer loop + vertex -406.825 116.608 370.783 + vertex -407.455 119.622 371.301 + vertex -408.721 115.304 369.79 + endloop + endfacet + facet normal -0.331179 -0.223611 0.916689 + outer loop + vertex -408.721 115.304 369.79 + vertex -407.455 119.622 371.301 + vertex -409.794 117.814 370.015 + endloop + endfacet + facet normal -0.345567 -0.204407 0.915861 + outer loop + vertex -407.455 119.622 371.301 + vertex -408.78 122.621 371.47 + vertex -409.794 117.814 370.015 + endloop + endfacet + facet normal -0.369231 -0.214214 0.904312 + outer loop + vertex -408.78 122.621 371.47 + vertex -407.455 119.622 371.301 + vertex -406.02 125.464 373.271 + endloop + endfacet + facet normal -0.384111 -0.198158 0.901771 + outer loop + vertex -406.02 125.464 373.271 + vertex -407.388 128.895 373.442 + vertex -408.78 122.621 371.47 + endloop + endfacet + facet normal -0.370398 -0.202685 0.90649 + outer loop + vertex -408.78 122.621 371.47 + vertex -407.388 128.895 373.442 + vertex -410.547 124.355 371.136 + endloop + endfacet + facet normal -0.358037 -0.188547 0.914472 + outer loop + vertex -408.78 122.621 371.47 + vertex -410.547 124.355 371.136 + vertex -411.14 119.928 369.991 + endloop + endfacet + facet normal -0.336154 -0.193361 0.921744 + outer loop + vertex -410.547 124.355 371.136 + vertex -412.666 120.773 369.612 + vertex -411.14 119.928 369.991 + endloop + endfacet + facet normal -0.361965 -0.216782 0.906635 + outer loop + vertex -404.716 121.152 372.761 + vertex -406.02 125.464 373.271 + vertex -407.455 119.622 371.301 + endloop + endfacet + facet normal -0.405822 -0.227507 0.885183 + outer loop + vertex -404.716 121.152 372.761 + vertex -403.36 129.016 375.403 + vertex -406.02 125.464 373.271 + endloop + endfacet + facet normal -0.406245 -0.22738 0.885022 + outer loop + vertex -401.628 125.681 375.341 + vertex -403.36 129.016 375.403 + vertex -404.716 121.152 372.761 + endloop + endfacet + facet normal -0.439515 -0.244284 0.864379 + outer loop + vertex -401.628 125.681 375.341 + vertex -400.97 133.964 378.016 + vertex -403.36 129.016 375.403 + endloop + endfacet + facet normal -0.448271 -0.242313 0.860429 + outer loop + vertex -399.129 130.618 378.033 + vertex -400.97 133.964 378.016 + vertex -401.628 125.681 375.341 + endloop + endfacet + facet normal -0.479858 -0.259808 0.837996 + outer loop + vertex -399.129 130.618 378.033 + vertex -398.993 139.165 380.761 + vertex -400.97 133.964 378.016 + endloop + endfacet + facet normal -0.48718 -0.258472 0.834175 + outer loop + vertex -397.229 135.673 380.71 + vertex -398.993 139.165 380.761 + vertex -399.129 130.618 378.033 + endloop + endfacet + facet normal -0.51775 -0.273569 0.810614 + outer loop + vertex -397.229 135.673 380.71 + vertex -397.492 144.058 383.371 + vertex -398.993 139.165 380.761 + endloop + endfacet + facet normal -0.520347 -0.273165 0.809086 + outer loop + vertex -395.803 140.87 383.382 + vertex -397.492 144.058 383.371 + vertex -397.229 135.673 380.71 + endloop + endfacet + facet normal -0.542919 -0.28519 0.789877 + outer loop + vertex -395.803 140.87 383.382 + vertex -396.377 149.324 386.039 + vertex -397.492 144.058 383.371 + endloop + endfacet + facet normal -0.546351 -0.28473 0.787673 + outer loop + vertex -394.678 146.306 386.127 + vertex -396.377 149.324 386.039 + vertex -395.803 140.87 383.382 + endloop + endfacet + facet normal -0.564584 -0.295486 0.770671 + outer loop + vertex -394.678 146.306 386.127 + vertex -395.423 154.919 388.883 + vertex -396.377 149.324 386.039 + endloop + endfacet + facet normal -0.563595 -0.295616 0.771345 + outer loop + vertex -393.725 151.788 388.924 + vertex -395.423 154.919 388.883 + vertex -394.678 146.306 386.127 + endloop + endfacet + facet normal -0.584115 -0.307008 0.751369 + outer loop + vertex -393.725 151.788 388.924 + vertex -394.588 160.032 391.621 + vertex -395.423 154.919 388.883 + endloop + endfacet + facet normal -0.576629 -0.307979 0.756735 + outer loop + vertex -392.944 157.2 391.721 + vertex -394.588 160.032 391.621 + vertex -393.725 151.788 388.924 + endloop + endfacet + facet normal -0.595582 -0.319686 0.736942 + outer loop + vertex -392.944 157.2 391.721 + vertex -393.974 165.02 394.282 + vertex -394.588 160.032 391.621 + endloop + endfacet + facet normal -0.590628 -0.320255 0.740672 + outer loop + vertex -392.331 162.613 394.551 + vertex -393.974 165.02 394.282 + vertex -392.944 157.2 391.721 + endloop + endfacet + facet normal -0.606302 -0.333022 0.722145 + outer loop + vertex -392.331 162.613 394.551 + vertex -393.486 170.23 397.094 + vertex -393.974 165.02 394.282 + endloop + endfacet + facet normal -0.599445 -0.333772 0.727504 + outer loop + vertex -391.814 168.025 397.459 + vertex -393.486 170.23 397.094 + vertex -392.331 162.613 394.551 + endloop + endfacet + facet normal -0.612225 -0.346218 0.710854 + outer loop + vertex -391.814 168.025 397.459 + vertex -392.974 175.338 400.022 + vertex -393.486 170.23 397.094 + endloop + endfacet + facet normal -0.594166 -0.348317 0.725012 + outer loop + vertex -391.287 173.266 400.409 + vertex -392.974 175.338 400.022 + vertex -391.814 168.025 397.459 + endloop + endfacet + facet normal -0.603537 -0.358321 0.712285 + outer loop + vertex -391.287 173.266 400.409 + vertex -392.347 179.973 402.885 + vertex -392.974 175.338 400.022 + endloop + endfacet + facet normal -0.567055 -0.362623 0.739563 + outer loop + vertex -390.651 177.914 403.176 + vertex -392.347 179.973 402.885 + vertex -391.287 173.266 400.409 + endloop + endfacet + facet normal -0.574711 -0.370314 0.729777 + outer loop + vertex -390.651 177.914 403.176 + vertex -391.502 183.426 405.303 + vertex -392.347 179.973 402.885 + endloop + endfacet + facet normal -0.525404 -0.375689 0.763419 + outer loop + vertex -389.97 181.262 405.292 + vertex -391.502 183.426 405.303 + vertex -390.651 177.914 403.176 + endloop + endfacet + facet normal -0.52824 -0.377682 0.760472 + outer loop + vertex -391.502 183.426 405.303 + vertex -389.97 181.262 405.292 + vertex -390.248 185.263 407.087 + endloop + endfacet + facet normal -0.536638 -0.369938 0.758397 + outer loop + vertex -390.248 185.263 407.087 + vertex -392.013 187.251 406.807 + vertex -391.502 183.426 405.303 + endloop + endfacet + facet normal -0.544402 -0.378189 0.748732 + outer loop + vertex -390.248 185.263 407.087 + vertex -391.035 187.987 407.89 + vertex -392.013 187.251 406.807 + endloop + endfacet + facet normal -0.503894 -0.375136 0.778051 + outer loop + vertex -389.617 186.795 408.234 + vertex -391.035 187.987 407.89 + vertex -390.248 185.263 407.087 + endloop + endfacet + facet normal -0.330212 -0.248314 0.910659 + outer loop + vertex -402.834 117.362 372.409 + vertex -404.716 121.152 372.761 + vertex -405.602 115.155 370.804 + endloop + endfacet + facet normal -0.362221 -0.26269 0.89431 + outer loop + vertex -402.834 117.362 372.409 + vertex -401.628 125.681 375.341 + vertex -404.716 121.152 372.761 + endloop + endfacet + facet normal -0.37083 -0.260429 0.891438 + outer loop + vertex -399.63 122.175 375.148 + vertex -401.628 125.681 375.341 + vertex -402.834 117.362 372.409 + endloop + endfacet + facet normal -0.398574 -0.275319 0.874836 + outer loop + vertex -399.63 122.175 375.148 + vertex -399.129 130.618 378.033 + vertex -401.628 125.681 375.341 + endloop + endfacet + facet normal -0.405953 -0.273875 0.871892 + outer loop + vertex -397.102 127.158 377.89 + vertex -399.129 130.618 378.033 + vertex -399.63 122.175 375.148 + endloop + endfacet + facet normal -0.433206 -0.289088 0.853674 + outer loop + vertex -397.102 127.158 377.89 + vertex -397.229 135.673 380.71 + vertex -399.129 130.618 378.033 + endloop + endfacet + facet normal -0.437004 -0.288562 0.851915 + outer loop + vertex -395.222 132.309 380.599 + vertex -397.229 135.673 380.71 + vertex -397.102 127.158 377.89 + endloop + endfacet + facet normal -0.461103 -0.302357 0.834245 + outer loop + vertex -395.222 132.309 380.599 + vertex -395.803 140.87 383.382 + vertex -397.229 135.673 380.71 + endloop + endfacet + facet normal -0.462777 -0.302189 0.833378 + outer loop + vertex -393.807 137.647 383.321 + vertex -395.803 140.87 383.382 + vertex -395.222 132.309 380.599 + endloop + endfacet + facet normal -0.481657 -0.313601 0.818328 + outer loop + vertex -393.807 137.647 383.321 + vertex -394.678 146.306 386.127 + vertex -395.803 140.87 383.382 + endloop + endfacet + facet normal -0.481131 -0.313643 0.818621 + outer loop + vertex -392.676 143.149 386.094 + vertex -394.678 146.306 386.127 + vertex -393.807 137.647 383.321 + endloop + endfacet + facet normal -0.49771 -0.324009 0.804551 + outer loop + vertex -392.676 143.149 386.094 + vertex -393.725 151.788 388.924 + vertex -394.678 146.306 386.127 + endloop + endfacet + facet normal -0.494308 -0.32425 0.806549 + outer loop + vertex -391.731 148.712 388.909 + vertex -393.725 151.788 388.924 + vertex -392.676 143.149 386.094 + endloop + endfacet + facet normal -0.511387 -0.335243 0.791262 + outer loop + vertex -391.731 148.712 388.909 + vertex -392.944 157.2 391.721 + vertex -393.725 151.788 388.924 + endloop + endfacet + facet normal -0.504755 -0.335647 0.795339 + outer loop + vertex -390.962 154.285 391.749 + vertex -392.944 157.2 391.721 + vertex -391.731 148.712 388.909 + endloop + endfacet + facet normal -0.52237 -0.347785 0.778572 + outer loop + vertex -390.962 154.285 391.749 + vertex -392.331 162.613 394.551 + vertex -392.944 157.2 391.721 + endloop + endfacet + facet normal -0.513831 -0.34822 0.784041 + outer loop + vertex -390.355 159.873 394.629 + vertex -392.331 162.613 394.551 + vertex -390.962 154.285 391.749 + endloop + endfacet + facet normal -0.531157 -0.361212 0.766419 + outer loop + vertex -390.355 159.873 394.629 + vertex -391.814 168.025 397.459 + vertex -392.331 162.613 394.551 + endloop + endfacet + facet normal -0.516738 -0.361918 0.775885 + outer loop + vertex -389.844 165.458 397.574 + vertex -391.814 168.025 397.459 + vertex -390.355 159.873 394.629 + endloop + endfacet + facet normal -0.531746 -0.374161 0.759769 + outer loop + vertex -389.844 165.458 397.574 + vertex -391.287 173.266 400.409 + vertex -391.814 168.025 397.459 + endloop + endfacet + facet normal -0.502812 -0.37562 0.778518 + outer loop + vertex -389.317 170.906 400.543 + vertex -391.287 173.266 400.409 + vertex -389.844 165.458 397.574 + endloop + endfacet + facet normal -0.514045 -0.3857 0.766155 + outer loop + vertex -389.317 170.906 400.543 + vertex -390.651 177.914 403.176 + vertex -391.287 173.266 400.409 + endloop + endfacet + facet normal -0.47403 -0.387319 0.790746 + outer loop + vertex -388.723 175.99 403.39 + vertex -390.651 177.914 403.176 + vertex -389.317 170.906 400.543 + endloop + endfacet + facet normal -0.429392 -0.402463 0.808483 + outer loop + vertex -387.173 168.669 400.569 + vertex -388.723 175.99 403.39 + vertex -389.317 170.906 400.543 + endloop + endfacet + facet normal -0.420728 -0.394057 0.817133 + outer loop + vertex -387.173 168.669 400.569 + vertex -389.317 170.906 400.543 + vertex -387.703 162.981 397.552 + endloop + endfacet + facet normal -0.382507 -0.40475 0.830582 + outer loop + vertex -385.6 160.86 397.487 + vertex -387.173 168.669 400.569 + vertex -387.703 162.981 397.552 + endloop + endfacet + facet normal -0.373565 -0.396139 0.838763 + outer loop + vertex -385.6 160.86 397.487 + vertex -387.703 162.981 397.552 + vertex -386.115 155.031 394.505 + endloop + endfacet + facet normal -0.344787 -0.403231 0.84766 + outer loop + vertex -384.349 153.473 394.482 + vertex -385.6 160.86 397.487 + vertex -386.115 155.031 394.505 + endloop + endfacet + facet normal -0.337255 -0.394793 0.854633 + outer loop + vertex -384.349 153.473 394.482 + vertex -386.115 155.031 394.505 + vertex -384.93 147.681 391.578 + endloop + endfacet + facet normal -0.316178 -0.399776 0.860355 + outer loop + vertex -383.723 147.037 391.722 + vertex -384.349 153.473 394.482 + vertex -384.93 147.681 391.578 + endloop + endfacet + facet normal -0.342536 -0.394805 0.852525 + outer loop + vertex -384.93 147.681 391.578 + vertex -386.115 155.031 394.505 + vertex -386.698 149.282 391.609 + endloop + endfacet + facet normal -0.334763 -0.386352 0.859457 + outer loop + vertex -384.93 147.681 391.578 + vertex -386.698 149.282 391.609 + vertex -385.674 142.003 388.735 + endloop + endfacet + facet normal -0.310648 -0.392614 0.865651 + outer loop + vertex -384.445 141.306 388.86 + vertex -384.93 147.681 391.578 + vertex -385.674 142.003 388.735 + endloop + endfacet + facet normal -0.336664 -0.38633 0.858724 + outer loop + vertex -385.674 142.003 388.735 + vertex -386.698 149.282 391.609 + vertex -387.455 143.613 388.761 + endloop + endfacet + facet normal -0.329932 -0.378979 0.864592 + outer loop + vertex -385.674 142.003 388.735 + vertex -387.455 143.613 388.761 + vertex -386.594 136.346 385.905 + endloop + endfacet + facet normal -0.303358 -0.386493 0.870975 + outer loop + vertex -385.331 135.669 386.044 + vertex -385.674 142.003 388.735 + vertex -386.594 136.346 385.905 + endloop + endfacet + facet normal -0.329702 -0.378985 0.864677 + outer loop + vertex -386.594 136.346 385.905 + vertex -387.455 143.613 388.761 + vertex -388.395 137.964 385.927 + endloop + endfacet + facet normal -0.323813 -0.372497 0.869707 + outer loop + vertex -386.594 136.346 385.905 + vertex -388.395 137.964 385.927 + vertex -387.713 130.729 383.082 + endloop + endfacet + facet normal -0.295507 -0.381279 0.875958 + outer loop + vertex -386.405 130.028 383.218 + vertex -386.594 136.346 385.905 + vertex -387.713 130.729 383.082 + endloop + endfacet + facet normal -0.321654 -0.372593 0.870467 + outer loop + vertex -387.713 130.729 383.082 + vertex -388.395 137.964 385.927 + vertex -389.538 132.372 383.111 + endloop + endfacet + facet normal -0.315617 -0.365977 0.875469 + outer loop + vertex -387.713 130.729 383.082 + vertex -389.538 132.372 383.111 + vertex -389.078 125.199 380.278 + endloop + endfacet + facet normal -0.284408 -0.376773 0.881563 + outer loop + vertex -387.684 124.443 380.405 + vertex -387.713 130.729 383.082 + vertex -389.078 125.199 380.278 + endloop + endfacet + facet normal -0.310417 -0.366321 0.877183 + outer loop + vertex -389.078 125.199 380.278 + vertex -389.538 132.372 383.111 + vertex -390.943 126.875 380.318 + endloop + endfacet + facet normal -0.303609 -0.358872 0.882628 + outer loop + vertex -389.078 125.199 380.278 + vertex -390.943 126.875 380.318 + vertex -390.832 119.734 377.453 + endloop + endfacet + facet normal -0.270616 -0.372155 0.887845 + outer loop + vertex -389.277 118.954 377.6 + vertex -389.078 125.199 380.278 + vertex -390.832 119.734 377.453 + endloop + endfacet + facet normal -0.296658 -0.359594 0.884696 + outer loop + vertex -390.832 119.734 377.453 + vertex -390.943 126.875 380.318 + vertex -392.776 121.473 377.508 + endloop + endfacet + facet normal -0.289527 -0.351797 0.890176 + outer loop + vertex -390.832 119.734 377.453 + vertex -392.776 121.473 377.508 + vertex -393.176 114.192 374.5 + endloop + endfacet + facet normal -0.257396 -0.367309 0.893774 + outer loop + vertex -391.407 113.415 374.69 + vertex -390.832 119.734 377.453 + vertex -393.176 114.192 374.5 + endloop + endfacet + facet normal -0.281785 -0.353045 0.892164 + outer loop + vertex -393.176 114.192 374.5 + vertex -392.776 121.473 377.508 + vertex -395.229 116.153 374.628 + endloop + endfacet + facet normal -0.274815 -0.346065 0.897059 + outer loop + vertex -393.176 114.192 374.5 + vertex -395.229 116.153 374.628 + vertex -396.145 108.551 371.415 + endloop + endfacet + facet normal -0.244095 -0.36335 0.899108 + outer loop + vertex -394.325 107.339 371.419 + vertex -393.176 114.192 374.5 + vertex -396.145 108.551 371.415 + endloop + endfacet + facet normal -0.2407 -0.358245 0.902067 + outer loop + vertex -394.325 107.339 371.419 + vertex -396.145 108.551 371.415 + vertex -396.67 103.723 369.357 + endloop + endfacet + facet normal -0.224349 -0.3613 0.905058 + outer loop + vertex -397.925 103.717 369.044 + vertex -396.67 103.723 369.357 + vertex -396.145 108.551 371.415 + endloop + endfacet + facet normal -0.235552 -0.356677 0.904045 + outer loop + vertex -397.925 103.717 369.044 + vertex -396.145 108.551 371.415 + vertex -398.792 105.444 369.499 + endloop + endfacet + facet normal -0.253672 -0.341766 0.904901 + outer loop + vertex -396.145 108.551 371.415 + vertex -398.349 110.934 371.697 + vertex -398.792 105.444 369.499 + endloop + endfacet + facet normal -0.261918 -0.3488 0.899854 + outer loop + vertex -396.145 108.551 371.415 + vertex -395.229 116.153 374.628 + vertex -398.349 110.934 371.697 + endloop + endfacet + facet normal -0.299757 -0.324621 0.897088 + outer loop + vertex -395.229 116.153 374.628 + vertex -397.447 118.92 374.888 + vertex -398.349 110.934 371.697 + endloop + endfacet + facet normal -0.287715 -0.327183 0.900095 + outer loop + vertex -398.349 110.934 371.697 + vertex -397.447 118.92 374.888 + vertex -400.661 113.971 372.062 + endloop + endfacet + facet normal -0.273312 -0.317188 0.908126 + outer loop + vertex -398.349 110.934 371.697 + vertex -400.661 113.971 372.062 + vertex -401.163 108.339 369.943 + endloop + endfacet + facet normal -0.3123 -0.333949 0.889352 + outer loop + vertex -395.229 116.153 374.628 + vertex -394.937 124.034 377.69 + vertex -397.447 118.92 374.888 + endloop + endfacet + facet normal -0.319755 -0.332809 0.887127 + outer loop + vertex -392.776 121.473 377.508 + vertex -394.937 124.034 377.69 + vertex -395.229 116.153 374.628 + endloop + endfacet + facet normal -0.331954 -0.342517 0.878913 + outer loop + vertex -392.776 121.473 377.508 + vertex -393.067 129.308 380.451 + vertex -394.937 124.034 377.69 + endloop + endfacet + facet normal -0.336864 -0.342063 0.87722 + outer loop + vertex -390.943 126.875 380.318 + vertex -393.067 129.308 380.451 + vertex -392.776 121.473 377.508 + endloop + endfacet + facet normal -0.347966 -0.351314 0.869194 + outer loop + vertex -390.943 126.875 380.318 + vertex -391.653 134.743 383.214 + vertex -393.067 129.308 380.451 + endloop + endfacet + facet normal -0.351354 -0.351143 0.867899 + outer loop + vertex -389.538 132.372 383.111 + vertex -391.653 134.743 383.214 + vertex -390.943 126.875 380.318 + endloop + endfacet + facet normal -0.360947 -0.359384 0.860558 + outer loop + vertex -389.538 132.372 383.111 + vertex -390.513 140.299 386.012 + vertex -391.653 134.743 383.214 + endloop + endfacet + facet normal -0.361442 -0.359371 0.860356 + outer loop + vertex -388.395 137.964 385.927 + vertex -390.513 140.299 386.012 + vertex -389.538 132.372 383.111 + endloop + endfacet + facet normal -0.370445 -0.367271 0.85316 + outer loop + vertex -388.395 137.964 385.927 + vertex -389.567 145.92 388.843 + vertex -390.513 140.299 386.012 + endloop + endfacet + facet normal -0.368159 -0.367293 0.85414 + outer loop + vertex -387.455 143.613 388.761 + vertex -389.567 145.92 388.843 + vertex -388.395 137.964 385.927 + endloop + endfacet + facet normal -0.378049 -0.376062 0.845965 + outer loop + vertex -387.455 143.613 388.761 + vertex -388.805 151.567 391.694 + vertex -389.567 145.92 388.843 + endloop + endfacet + facet normal -0.373457 -0.376037 0.848013 + outer loop + vertex -386.698 149.282 391.609 + vertex -388.805 151.567 391.694 + vertex -387.455 143.613 388.761 + endloop + endfacet + facet normal -0.38479 -0.386131 0.838355 + outer loop + vertex -386.698 149.282 391.609 + vertex -388.21 157.252 394.585 + vertex -388.805 151.567 391.694 + endloop + endfacet + facet normal -0.376967 -0.385994 0.841965 + outer loop + vertex -386.115 155.031 394.505 + vertex -388.21 157.252 394.585 + vertex -386.698 149.282 391.609 + endloop + endfacet + facet normal -0.334144 -0.403169 0.85194 + outer loop + vertex -383.831 159.366 397.474 + vertex -385.6 160.86 397.487 + vertex -384.349 153.473 394.482 + endloop + endfacet + facet normal -0.388439 -0.396453 0.831829 + outer loop + vertex -386.115 155.031 394.505 + vertex -387.703 162.981 397.552 + vertex -388.21 157.252 394.585 + endloop + endfacet + facet normal -0.362618 -0.404327 0.839659 + outer loop + vertex -385.061 166.673 400.519 + vertex -387.173 168.669 400.569 + vertex -385.6 160.86 397.487 + endloop + endfacet + facet normal -0.447753 -0.394087 0.802629 + outer loop + vertex -387.703 162.981 397.552 + vertex -389.317 170.906 400.543 + vertex -389.844 165.458 397.574 + endloop + endfacet + facet normal -0.435251 -0.383386 0.814599 + outer loop + vertex -387.703 162.981 397.552 + vertex -389.844 165.458 397.574 + vertex -388.21 157.252 394.585 + endloop + endfacet + facet normal -0.45212 -0.38338 0.805362 + outer loop + vertex -388.21 157.252 394.585 + vertex -389.844 165.458 397.574 + vertex -390.355 159.873 394.629 + endloop + endfacet + facet normal -0.436797 -0.371074 0.819459 + outer loop + vertex -388.21 157.252 394.585 + vertex -390.355 159.873 394.629 + vertex -388.805 151.567 391.694 + endloop + endfacet + facet normal -0.446635 -0.371035 0.814156 + outer loop + vertex -388.805 151.567 391.694 + vertex -390.355 159.873 394.629 + vertex -390.962 154.285 391.749 + endloop + endfacet + facet normal -0.431663 -0.359427 0.827333 + outer loop + vertex -388.805 151.567 391.694 + vertex -390.962 154.285 391.749 + vertex -389.567 145.92 388.843 + endloop + endfacet + facet normal -0.438388 -0.359331 0.823831 + outer loop + vertex -389.567 145.92 388.843 + vertex -390.962 154.285 391.749 + vertex -391.731 148.712 388.909 + endloop + endfacet + facet normal -0.424835 -0.349097 0.835252 + outer loop + vertex -389.567 145.92 388.843 + vertex -391.731 148.712 388.909 + vertex -390.513 140.299 386.012 + endloop + endfacet + facet normal -0.428549 -0.348996 0.833395 + outer loop + vertex -390.513 140.299 386.012 + vertex -391.731 148.712 388.909 + vertex -392.676 143.149 386.094 + endloop + endfacet + facet normal -0.4158 -0.339616 0.843666 + outer loop + vertex -390.513 140.299 386.012 + vertex -392.676 143.149 386.094 + vertex -391.653 134.743 383.214 + endloop + endfacet + facet normal -0.415991 -0.339608 0.843575 + outer loop + vertex -391.653 134.743 383.214 + vertex -392.676 143.149 386.094 + vertex -393.807 137.647 383.321 + endloop + endfacet + facet normal -0.402026 -0.329647 0.854229 + outer loop + vertex -391.653 134.743 383.214 + vertex -393.807 137.647 383.321 + vertex -393.067 129.308 380.451 + endloop + endfacet + facet normal -0.400349 -0.329755 0.854975 + outer loop + vertex -393.067 129.308 380.451 + vertex -393.807 137.647 383.321 + vertex -395.222 132.309 380.599 + endloop + endfacet + facet normal -0.383319 -0.318122 0.867101 + outer loop + vertex -393.067 129.308 380.451 + vertex -395.222 132.309 380.599 + vertex -394.937 124.034 377.69 + endloop + endfacet + facet normal -0.379112 -0.318569 0.868785 + outer loop + vertex -394.937 124.034 377.69 + vertex -395.222 132.309 380.599 + vertex -397.102 127.158 377.89 + endloop + endfacet + facet normal -0.360003 -0.306125 0.881298 + outer loop + vertex -394.937 124.034 377.69 + vertex -397.102 127.158 377.89 + vertex -397.447 118.92 374.888 + endloop + endfacet + facet normal -0.352887 -0.307319 0.883757 + outer loop + vertex -397.447 118.92 374.888 + vertex -397.102 127.158 377.89 + vertex -399.63 122.175 375.148 + endloop + endfacet + facet normal -0.333176 -0.295038 0.895515 + outer loop + vertex -397.447 118.92 374.888 + vertex -399.63 122.175 375.148 + vertex -400.661 113.971 372.062 + endloop + endfacet + facet normal -0.321046 -0.297873 0.899 + outer loop + vertex -400.661 113.971 372.062 + vertex -399.63 122.175 375.148 + vertex -402.834 117.362 372.409 + endloop + endfacet + facet normal -0.396056 -0.401985 0.825559 + outer loop + vertex -386.539 174.031 403.484 + vertex -388.723 175.99 403.39 + vertex -387.173 168.669 400.569 + endloop + endfacet + facet normal -0.481785 -0.396101 0.781657 + outer loop + vertex -388.723 175.99 403.39 + vertex -389.97 181.262 405.292 + vertex -390.651 177.914 403.176 + endloop + endfacet + facet normal -0.437242 -0.395049 0.807933 + outer loop + vertex -388.151 180.901 406.1 + vertex -389.97 181.262 405.292 + vertex -388.723 175.99 403.39 + endloop + endfacet + facet normal -0.43727 -0.393064 0.808885 + outer loop + vertex -389.97 181.262 405.292 + vertex -388.151 180.901 406.1 + vertex -390.248 185.263 407.087 + endloop + endfacet + facet normal -0.462646 -0.401127 0.790605 + outer loop + vertex -388.658 184.908 407.837 + vertex -390.248 185.263 407.087 + vertex -388.151 180.901 406.1 + endloop + endfacet + facet normal -0.462642 -0.401414 0.790461 + outer loop + vertex -388.658 184.908 407.837 + vertex -389.617 186.795 408.234 + vertex -390.248 185.263 407.087 + endloop + endfacet + facet normal -0.412342 -0.383411 0.82642 + outer loop + vertex -388.037 185.809 408.565 + vertex -389.617 186.795 408.234 + vertex -388.658 184.908 407.837 + endloop + endfacet + facet normal -0.300389 -0.285762 0.910004 + outer loop + vertex -400.661 113.971 372.062 + vertex -402.834 117.362 372.409 + vertex -403.524 111.608 370.375 + endloop + endfacet + facet normal -0.280927 -0.308474 0.908803 + outer loop + vertex -402.627 109.362 369.889 + vertex -400.661 113.971 372.062 + vertex -403.524 111.608 370.375 + endloop + endfacet + facet normal -0.257212 -0.320017 0.911829 + outer loop + vertex -402.627 109.362 369.889 + vertex -401.163 108.339 369.943 + vertex -400.661 113.971 372.062 + endloop + endfacet + facet normal -0.254948 -0.336112 0.906659 + outer loop + vertex -400.208 106.233 369.431 + vertex -398.349 110.934 371.697 + vertex -401.163 108.339 369.943 + endloop + endfacet + facet normal -0.235593 -0.344729 0.908657 + outer loop + vertex -400.208 106.233 369.431 + vertex -398.792 105.444 369.499 + vertex -398.349 110.934 371.697 + endloop + endfacet + facet normal -0.227151 -0.353365 0.907489 + outer loop + vertex -397.925 103.717 369.044 + vertex -398.792 105.444 369.499 + vertex -399.821 101.544 367.723 + endloop + endfacet + facet normal -0.215576 -0.362897 0.90655 + outer loop + vertex -398.751 100.697 367.638 + vertex -397.925 103.717 369.044 + vertex -399.821 101.544 367.723 + endloop + endfacet + facet normal -0.213143 -0.359998 0.90828 + outer loop + vertex -398.751 100.697 367.638 + vertex -399.821 101.544 367.723 + vertex -400.777 98.5193 366.3 + endloop + endfacet + facet normal -0.21104 -0.354001 0.911123 + outer loop + vertex -401.812 99.5894 366.493 + vertex -400.953 102.829 367.951 + vertex -402.93 100.989 366.778 + endloop + endfacet + facet normal -0.219803 -0.342528 0.913434 + outer loop + vertex -402.93 100.989 366.778 + vertex -402.147 104.321 368.216 + vertex -404.119 102.537 367.073 + endloop + endfacet + facet normal -0.23098 -0.329426 0.915492 + outer loop + vertex -404.119 102.537 367.073 + vertex -403.373 105.917 368.477 + vertex -405.356 104.22 367.366 + endloop + endfacet + facet normal -0.241621 -0.315495 0.91765 + outer loop + vertex -405.356 104.22 367.366 + vertex -404.595 107.61 368.732 + vertex -406.618 106.111 367.684 + endloop + endfacet + facet normal -0.25299 -0.301337 0.919343 + outer loop + vertex -404.595 107.61 368.732 + vertex -405.774 109.411 368.998 + vertex -406.618 106.111 367.684 + endloop + endfacet + facet normal -0.272529 -0.290849 0.917134 + outer loop + vertex -405.774 109.411 368.998 + vertex -404.889 112.769 370.326 + vertex -406.807 111.271 369.281 + endloop + endfacet + facet normal -0.254674 -0.292199 0.921825 + outer loop + vertex -408.403 105.315 366.964 + vertex -407.864 108.242 368.041 + vertex -410.256 108.386 367.426 + endloop + endfacet + facet normal -0.275665 -0.266148 0.923674 + outer loop + vertex -406.807 111.271 369.281 + vertex -407.763 113.154 369.538 + vertex -408.599 110.337 368.477 + endloop + endfacet + facet normal -0.311296 -0.246362 0.917824 + outer loop + vertex -407.763 113.154 369.538 + vertex -406.825 116.608 370.783 + vertex -408.721 115.304 369.79 + endloop + endfacet + facet normal -0.298046 -0.255139 0.919822 + outer loop + vertex -411.856 112.921 368.165 + vertex -410.256 108.386 367.426 + vertex -409.72 112.109 368.632 + endloop + endfacet + facet normal -0.313744 -0.216852 0.924414 + outer loop + vertex -408.721 115.304 369.79 + vertex -409.794 117.814 370.015 + vertex -410.47 114.562 369.022 + endloop + endfacet + facet normal -0.33994 -0.206114 0.917582 + outer loop + vertex -409.794 117.814 370.015 + vertex -408.78 122.621 371.47 + vertex -411.14 119.928 369.991 + endloop + endfacet + facet normal -0.312788 -0.216413 0.92484 + outer loop + vertex -413.36 117.016 368.615 + vertex -411.856 112.921 368.165 + vertex -411.668 116.489 369.064 + endloop + endfacet + facet normal -0.33346 -0.187513 0.923928 + outer loop + vertex -412.418 118.363 369.212 + vertex -411.14 119.928 369.991 + vertex -412.666 120.773 369.612 + endloop + endfacet + facet normal -0.301797 -0.158339 0.940132 + outer loop + vertex -416.186 120.883 368.454 + vertex -414.421 120.659 368.984 + vertex -415.091 123.531 369.252 + endloop + endfacet + facet normal -0.254235 -0.118541 0.95985 + outer loop + vertex -418.405 125.24 368.379 + vertex -420.593 123.3 367.56 + vertex -418.048 121.793 368.048 + endloop + endfacet + facet normal -0.331465 -0.143759 0.932451 + outer loop + vertex -416.43 124.259 368.888 + vertex -416.186 120.883 368.454 + vertex -415.091 123.531 369.252 + endloop + endfacet + facet normal -0.236835 -0.137597 0.961757 + outer loop + vertex -418.048 121.793 368.048 + vertex -420.006 119.867 367.29 + vertex -417.379 118.382 367.724 + endloop + endfacet + facet normal -0.30248 -0.168428 0.938157 + outer loop + vertex -416.186 120.883 368.454 + vertex -415.325 117.444 368.115 + vertex -414.421 120.659 368.984 + endloop + endfacet + facet normal -0.221911 -0.160006 0.961849 + outer loop + vertex -417.379 118.382 367.724 + vertex -419.244 116.462 366.975 + vertex -416.389 114.891 367.372 + endloop + endfacet + facet normal -0.210026 -0.190756 0.958906 + outer loop + vertex -416.389 114.891 367.372 + vertex -418.29 113.059 366.591 + vertex -415.105 111.294 366.938 + endloop + endfacet + facet normal -0.20137 -0.225941 0.953101 + outer loop + vertex -415.105 111.294 366.938 + vertex -417.11 109.607 366.114 + vertex -413.088 107.24 366.403 + endloop + endfacet + facet normal -0.231141 -0.272028 0.934117 + outer loop + vertex -410.922 105.995 366.576 + vertex -411.741 107.778 366.893 + vertex -413.088 107.24 366.403 + endloop + endfacet + facet normal -0.227886 -0.277746 0.933234 + outer loop + vertex -409.615 104.751 366.5 + vertex -408.403 105.315 366.964 + vertex -410.256 108.386 367.426 + endloop + endfacet + facet normal -0.243045 -0.291258 0.925256 + outer loop + vertex -410.122 104.335 366.264 + vertex -410.922 105.995 366.576 + vertex -410.638 104.168 366.076 + endloop + endfacet + facet normal -0.232971 -0.316212 0.919638 + outer loop + vertex -409.252 102.86 365.977 + vertex -410.122 104.335 366.264 + vertex -410.638 104.168 366.076 + endloop + endfacet + facet normal -0.21416 -0.303349 0.928502 + outer loop + vertex -408.226 102.653 366.136 + vertex -408.403 105.315 366.964 + vertex -409.615 104.751 366.5 + endloop + endfacet + facet normal -0.200027 -0.31551 0.9276 + outer loop + vertex -407.775 100.542 365.507 + vertex -409.252 102.86 365.977 + vertex -409.226 101.53 365.53 + endloop + endfacet + facet normal -0.212144 -0.322389 0.922529 + outer loop + vertex -406.812 100.567 365.732 + vertex -406.995 103.116 366.58 + vertex -408.226 102.653 366.136 + endloop + endfacet + facet normal -0.182592 -0.326911 0.927248 + outer loop + vertex -406.026 98.1048 364.992 + vertex -407.775 100.542 365.507 + vertex -407.439 98.6828 364.918 + endloop + endfacet + facet normal -0.207964 -0.335591 0.918765 + outer loop + vertex -405.652 99.1763 365.486 + vertex -405.719 101.294 366.245 + vertex -406.812 100.567 365.732 + endloop + endfacet + facet normal -0.197292 -0.350808 0.915429 + outer loop + vertex -404.665 97.5996 365.095 + vertex -404.554 99.7066 365.926 + vertex -405.652 99.1763 365.486 + endloop + endfacet + facet normal -0.16938 -0.34852 0.92187 + outer loop + vertex -404.275 95.5057 364.331 + vertex -406.026 98.1048 364.992 + vertex -405.907 96.1591 364.279 + endloop + endfacet + facet normal -0.192446 -0.361849 0.912157 + outer loop + vertex -403.609 96.4448 364.86 + vertex -403.453 98.2784 365.62 + vertex -404.665 97.5996 365.095 + endloop + endfacet + facet normal -0.184669 -0.375539 0.908222 + outer loop + vertex -402.792 95.1077 364.473 + vertex -402.449 97.0544 365.347 + vertex -403.609 96.4448 364.86 + endloop + endfacet + facet normal -0.154318 -0.376254 0.913575 + outer loop + vertex -402.439 92.2161 363.287 + vertex -404.275 95.5057 364.331 + vertex -404.872 94.1829 363.686 + endloop + endfacet + facet normal -0.185723 -0.381719 0.905427 + outer loop + vertex -401.878 94.5982 364.445 + vertex -401.538 96.2144 365.196 + vertex -402.792 95.1077 364.473 + endloop + endfacet + facet normal -0.190364 -0.380527 0.904964 + outer loop + vertex -400.713 95.9496 365.259 + vertex -401.538 96.2144 365.196 + vertex -401.878 94.5982 364.445 + endloop + endfacet + facet normal -0.182288 -0.386872 0.903936 + outer loop + vertex -401.255 94.6252 364.583 + vertex -400.713 95.9496 365.259 + vertex -401.878 94.5982 364.445 + endloop + endfacet + facet normal -0.184765 -0.384854 0.904295 + outer loop + vertex -398.624 97.8505 366.494 + vertex -398.853 98.1146 366.56 + vertex -400.097 96.1006 365.448 + endloop + endfacet + facet normal -0.186809 -0.386362 0.903231 + outer loop + vertex -398.624 97.8505 366.494 + vertex -396.001 102.076 368.844 + vertex -398.853 98.1146 366.56 + endloop + endfacet + facet normal -0.171649 -0.395297 0.902373 + outer loop + vertex -396.001 102.076 368.844 + vertex -398.624 97.8505 366.494 + vertex -397.228 99.6171 367.533 + endloop + endfacet + facet normal -0.189662 -0.378063 0.906144 + outer loop + vertex -400.713 95.9496 365.259 + vertex -399.796 97.9883 366.301 + vertex -401.538 96.2144 365.196 + endloop + endfacet + facet normal -0.201612 -0.369896 0.906934 + outer loop + vertex -399.796 97.9883 366.301 + vertex -398.751 100.697 367.638 + vertex -400.777 98.5193 366.3 + endloop + endfacet + facet normal -0.224477 -0.359994 0.905546 + outer loop + vertex -396.67 103.723 369.357 + vertex -397.925 103.717 369.044 + vertex -398.751 100.697 367.638 + endloop + endfacet + facet normal -0.222683 -0.369889 0.901995 + outer loop + vertex -396.012 103.138 369.28 + vertex -394.325 107.339 371.419 + vertex -396.67 103.723 369.357 + endloop + endfacet + facet normal -0.254854 -0.360686 0.897193 + outer loop + vertex -391.407 113.415 374.69 + vertex -393.176 114.192 374.5 + vertex -394.325 107.339 371.419 + endloop + endfacet + facet normal -0.267585 -0.365411 0.891557 + outer loop + vertex -389.277 118.954 377.6 + vertex -390.832 119.734 377.453 + vertex -391.407 113.415 374.69 + endloop + endfacet + facet normal -0.281407 -0.370641 0.885119 + outer loop + vertex -387.684 124.443 380.405 + vertex -389.078 125.199 380.278 + vertex -389.277 118.954 377.6 + endloop + endfacet + facet normal -0.29291 -0.375801 0.879191 + outer loop + vertex -386.405 130.028 383.218 + vertex -387.713 130.729 383.082 + vertex -387.684 124.443 380.405 + endloop + endfacet + facet normal -0.300676 -0.380777 0.874416 + outer loop + vertex -385.331 135.669 386.044 + vertex -386.594 136.346 385.905 + vertex -386.405 130.028 383.218 + endloop + endfacet + facet normal -0.307407 -0.38617 0.869698 + outer loop + vertex -384.445 141.306 388.86 + vertex -385.674 142.003 388.735 + vertex -385.331 135.669 386.044 + endloop + endfacet + facet normal -0.312824 -0.392473 0.864931 + outer loop + vertex -383.723 147.037 391.722 + vertex -384.93 147.681 391.578 + vertex -384.445 141.306 388.86 + endloop + endfacet + facet normal -0.313073 -0.39993 0.861418 + outer loop + vertex -383.138 152.89 394.652 + vertex -384.349 153.473 394.482 + vertex -383.723 147.037 391.722 + endloop + endfacet + facet normal -0.297989 -0.410594 0.861751 + outer loop + vertex -381.969 159.469 398.186 + vertex -382.628 158.822 397.65 + vertex -382.451 153.405 395.13 + endloop + endfacet + facet normal -0.262264 -0.417576 0.86997 + outer loop + vertex -381.969 159.469 398.186 + vertex -382.451 153.405 395.13 + vertex -382.001 156.12 396.569 + endloop + endfacet + facet normal -0.291973 -0.4162 0.861121 + outer loop + vertex -381.969 159.469 398.186 + vertex -382.161 164.899 400.745 + vertex -382.628 158.822 397.65 + endloop + endfacet + facet normal -0.298172 -0.415563 0.859303 + outer loop + vertex -381.559 165.548 401.268 + vertex -382.161 164.899 400.745 + vertex -381.969 159.469 398.186 + endloop + endfacet + facet normal -0.287748 -0.417572 0.861878 + outer loop + vertex -381.559 165.548 401.268 + vertex -381.969 159.469 398.186 + vertex -381.559 161.619 399.365 + endloop + endfacet + facet normal -0.295398 -0.417969 0.859094 + outer loop + vertex -381.559 165.548 401.268 + vertex -381.713 170.847 403.793 + vertex -382.161 164.899 400.745 + endloop + endfacet + facet normal -0.299181 -0.417203 0.858156 + outer loop + vertex -381.713 170.847 403.793 + vertex -382.807 171.019 403.495 + vertex -382.161 164.899 400.745 + endloop + endfacet + facet normal -0.305686 -0.41692 0.855999 + outer loop + vertex -382.161 164.899 400.745 + vertex -382.807 171.019 403.495 + vertex -383.315 165.289 400.523 + endloop + endfacet + facet normal -0.299197 -0.417882 0.85782 + outer loop + vertex -381.713 170.847 403.793 + vertex -382.36 176.717 406.427 + vertex -382.807 171.019 403.495 + endloop + endfacet + facet normal -0.306036 -0.416778 0.855943 + outer loop + vertex -381.183 171.179 404.144 + vertex -381.713 170.847 403.793 + vertex -381.559 165.548 401.268 + endloop + endfacet + facet normal -0.302697 -0.417441 0.856806 + outer loop + vertex -381.183 171.179 404.144 + vertex -381.559 165.548 401.268 + vertex -381.286 167.406 402.27 + endloop + endfacet + facet normal -0.310154 -0.411391 0.857066 + outer loop + vertex -381.183 171.179 404.144 + vertex -380.938 175.506 406.31 + vertex -381.713 170.847 403.793 + endloop + endfacet + facet normal -0.306818 -0.412027 0.857961 + outer loop + vertex -380.575 174.86 406.129 + vertex -380.938 175.506 406.31 + vertex -381.183 171.179 404.144 + endloop + endfacet + facet normal -0.0223784 0.477428 -0.878386 + outer loop + vertex -380.575 174.86 406.129 + vertex -381.183 171.179 404.144 + vertex -380.961 172.87 405.058 + endloop + endfacet + facet normal -0.315979 -0.407282 0.856901 + outer loop + vertex -383.138 152.89 394.652 + vertex -383.831 159.366 397.474 + vertex -384.349 153.473 394.482 + endloop + endfacet + facet normal -0.304917 -0.413564 0.857899 + outer loop + vertex -382.161 164.899 400.745 + vertex -383.315 165.289 400.523 + vertex -382.628 158.822 397.65 + endloop + endfacet + facet normal -0.339912 -0.409953 0.846403 + outer loop + vertex -383.831 159.366 397.474 + vertex -385.061 166.673 400.519 + vertex -385.6 160.86 397.487 + endloop + endfacet + facet normal -0.31709 -0.414392 0.853073 + outer loop + vertex -382.807 171.019 403.495 + vertex -384.43 172.033 403.385 + vertex -383.315 165.289 400.523 + endloop + endfacet + facet normal -0.318544 -0.416914 0.8513 + outer loop + vertex -382.807 171.019 403.495 + vertex -383.819 176.049 405.58 + vertex -384.43 172.033 403.385 + endloop + endfacet + facet normal -0.368196 -0.410097 0.834417 + outer loop + vertex -385.061 166.673 400.519 + vertex -386.539 174.031 403.484 + vertex -387.173 168.669 400.569 + endloop + endfacet + facet normal -0.400125 -0.406728 0.821263 + outer loop + vertex -386.539 174.031 403.484 + vertex -388.151 180.901 406.1 + vertex -388.723 175.99 403.39 + endloop + endfacet + facet normal -0.329745 -0.4097 0.850537 + outer loop + vertex -383.749 182.945 408.958 + vertex -385.892 184.181 408.723 + vertex -384.361 180.735 407.657 + endloop + endfacet + facet normal -0.333654 -0.4126 0.847606 + outer loop + vertex -383.819 176.049 405.58 + vertex -385.66 178.203 405.904 + vertex -384.43 172.033 403.385 + endloop + endfacet + facet normal -0.306277 -0.416409 0.856037 + outer loop + vertex -382.36 176.717 406.427 + vertex -383.819 176.049 405.58 + vertex -382.807 171.019 403.495 + endloop + endfacet + facet normal -0.312475 -0.416399 0.853798 + outer loop + vertex -382.585 180.883 408.379 + vertex -383.749 182.945 408.958 + vertex -384.361 180.735 407.657 + endloop + endfacet + facet normal -0.292284 -0.408111 0.864879 + outer loop + vertex -381.751 182.027 409.201 + vertex -383.749 182.945 408.958 + vertex -382.585 180.883 408.379 + endloop + endfacet + facet normal -0.281742 -0.415711 0.864758 + outer loop + vertex -381.011 179.763 408.353 + vertex -381.751 182.027 409.201 + vertex -382.585 180.883 408.379 + endloop + endfacet + facet normal -0.2844 -0.41617 0.863666 + outer loop + vertex -380.561 181.586 409.38 + vertex -381.751 182.027 409.201 + vertex -381.011 179.763 408.353 + endloop + endfacet + facet normal 0.352014 0.935355 -0.0345927 + outer loop + vertex -381.751 182.027 409.201 + vertex -380.561 181.586 409.38 + vertex -379.621 181.232 409.374 + endloop + endfacet + facet normal 0.200837 0.547121 -0.812603 + outer loop + vertex -380.561 181.586 409.38 + vertex -380.156 181.686 409.548 + vertex -379.621 181.232 409.374 + endloop + endfacet + facet normal -0.25453 -0.424492 0.86892 + outer loop + vertex -380.156 181.686 409.548 + vertex -380.561 181.586 409.38 + vertex -380.101 180.822 409.142 + endloop + endfacet + facet normal -0.28527 -0.418366 0.862317 + outer loop + vertex -380.938 175.506 406.31 + vertex -382.36 176.717 406.427 + vertex -381.713 170.847 403.793 + endloop + endfacet + facet normal -0.262992 -0.393764 0.880787 + outer loop + vertex -380.938 175.506 406.31 + vertex -380.575 174.86 406.129 + vertex -378.776 177.36 407.784 + endloop + endfacet + facet normal -0.25659 -0.425404 0.867867 + outer loop + vertex -380.101 180.822 409.142 + vertex -380.561 181.586 409.38 + vertex -381.011 179.763 408.353 + endloop + endfacet + facet normal -0.0708442 -0.427873 0.901058 + outer loop + vertex -380.156 181.686 409.548 + vertex -380.101 180.822 409.142 + vertex -379.621 181.232 409.374 + endloop + endfacet + facet normal -0.180836 -0.421656 0.888541 + outer loop + vertex -369.963 169.552 405.993 + vertex -374.154 173.98 407.241 + vertex -374.185 170.514 405.59 + endloop + endfacet + facet normal -0.192842 -0.434568 0.879751 + outer loop + vertex -370.566 165.705 404.008 + vertex -374.185 170.514 405.59 + vertex -375.387 167.506 403.841 + endloop + endfacet + facet normal -0.213589 -0.428095 0.878131 + outer loop + vertex -376.454 163.118 401.442 + vertex -375.387 167.506 403.841 + vertex -378.856 168.108 403.29 + endloop + endfacet + facet normal -0.254833 -0.403842 0.878619 + outer loop + vertex -380.704 174.191 405.785 + vertex -379.966 174.862 406.307 + vertex -380.575 174.86 406.129 + endloop + endfacet + facet normal -0.982232 0.187587 0.00564956 + outer loop + vertex -380.961 172.87 405.058 + vertex -380.704 174.191 405.785 + vertex -380.575 174.86 406.129 + endloop + endfacet + facet normal -0.34427 -0.410848 0.844205 + outer loop + vertex -381.086 169.993 403.607 + vertex -380.961 172.87 405.058 + vertex -381.183 171.179 404.144 + endloop + endfacet + facet normal -0.232269 -0.428986 0.872939 + outer loop + vertex -380.374 171.739 404.671 + vertex -380.801 165.448 401.466 + vertex -378.856 168.108 403.29 + endloop + endfacet + facet normal -0.337807 -0.411384 0.846551 + outer loop + vertex -381.286 167.406 402.27 + vertex -381.086 169.993 403.607 + vertex -381.183 171.179 404.144 + endloop + endfacet + facet normal -0.29943 -0.418311 0.85753 + outer loop + vertex -381.392 164.865 400.993 + vertex -381.286 167.406 402.27 + vertex -381.559 165.548 401.268 + endloop + endfacet + facet normal -0.289073 -0.417398 0.861519 + outer loop + vertex -381.559 161.619 399.365 + vertex -381.392 164.865 400.993 + vertex -381.559 165.548 401.268 + endloop + endfacet + facet normal -0.29387 -0.415752 0.860692 + outer loop + vertex -381.789 158.348 397.706 + vertex -381.559 161.619 399.365 + vertex -381.969 159.469 398.186 + endloop + endfacet + facet normal -0.278163 -0.415512 0.866011 + outer loop + vertex -382.001 156.12 396.569 + vertex -381.789 158.348 397.706 + vertex -381.969 159.469 398.186 + endloop + endfacet + facet normal -0.304492 -0.406137 0.86159 + outer loop + vertex -382.186 153.433 395.237 + vertex -382.001 156.12 396.569 + vertex -382.451 153.405 395.13 + endloop + endfacet + facet normal -0.304411 -0.406449 0.861471 + outer loop + vertex -382.426 151.448 394.215 + vertex -382.186 153.433 395.237 + vertex -382.451 153.405 395.13 + endloop + endfacet + facet normal -0.276185 -0.409777 0.86937 + outer loop + vertex -382.595 149.909 393.437 + vertex -382.426 151.448 394.215 + vertex -382.451 153.405 395.13 + endloop + endfacet + facet normal -0.288241 -0.403054 0.868599 + outer loop + vertex -382.742 148.261 392.623 + vertex -382.595 149.909 393.437 + vertex -383.016 147.621 392.235 + endloop + endfacet + facet normal -0.301793 -0.396335 0.867087 + outer loop + vertex -382.917 146.302 391.667 + vertex -382.742 148.261 392.623 + vertex -383.016 147.621 392.235 + endloop + endfacet + facet normal -0.307977 -0.395937 0.865092 + outer loop + vertex -383.271 143.798 390.394 + vertex -382.917 146.302 391.667 + vertex -383.016 147.621 392.235 + endloop + endfacet + facet normal -0.297911 -0.394684 0.86918 + outer loop + vertex -383.517 141.71 389.362 + vertex -383.271 143.798 390.394 + vertex -383.753 141.525 389.197 + endloop + endfacet + facet normal -0.302293 -0.389738 0.869898 + outer loop + vertex -383.779 139.46 388.263 + vertex -383.517 141.71 389.362 + vertex -383.753 141.525 389.197 + endloop + endfacet + facet normal -0.313569 -0.388113 0.866627 + outer loop + vertex -384.16 137.222 387.123 + vertex -383.779 139.46 388.263 + vertex -383.753 141.525 389.197 + endloop + endfacet + facet normal -0.289998 -0.39076 0.873617 + outer loop + vertex -384.457 135.165 386.105 + vertex -384.16 137.222 387.123 + vertex -384.576 136.077 386.473 + endloop + endfacet + facet normal -0.271656 -0.390736 0.879505 + outer loop + vertex -384.862 133.233 385.121 + vertex -384.457 135.165 386.105 + vertex -384.576 136.077 386.473 + endloop + endfacet + facet normal -0.312961 -0.374599 0.872772 + outer loop + vertex -385.354 130.55 383.793 + vertex -384.862 133.233 385.121 + vertex -385.627 130.411 383.635 + endloop + endfacet + facet normal -0.312237 -0.375752 0.872535 + outer loop + vertex -385.852 128.36 382.672 + vertex -385.354 130.55 383.793 + vertex -385.627 130.411 383.635 + endloop + endfacet + facet normal -0.284799 -0.381901 0.879228 + outer loop + vertex -386.251 126.542 381.753 + vertex -385.852 128.36 382.672 + vertex -385.627 130.411 383.635 + endloop + endfacet + facet normal -0.296659 -0.37351 0.87891 + outer loop + vertex -386.919 123.612 380.282 + vertex -386.251 126.542 381.753 + vertex -386.84 124.761 380.797 + endloop + endfacet + facet normal -0.297495 -0.373355 0.878694 + outer loop + vertex -387.54 121.134 379.019 + vertex -386.919 123.612 380.282 + vertex -386.84 124.761 380.797 + endloop + endfacet + facet normal -0.210609 -0.397485 0.893112 + outer loop + vertex -388.015 119.279 378.081 + vertex -387.54 121.134 379.019 + vertex -388.262 119.113 377.949 + endloop + endfacet + facet normal -0.21487 -0.392204 0.894431 + outer loop + vertex -388.546 117.654 377.241 + vertex -388.015 119.279 378.081 + vertex -388.262 119.113 377.949 + endloop + endfacet + facet normal -0.280535 -0.368858 0.88614 + outer loop + vertex -388.724 116.37 376.678 + vertex -387.899 119.98 378.442 + vertex -389.293 115.598 376.176 + endloop + endfacet + facet normal -0.194179 -0.397413 0.89686 + outer loop + vertex -389.41 114.962 375.861 + vertex -388.546 117.654 377.241 + vertex -388.262 119.113 377.949 + endloop + endfacet + facet normal -0.252262 -0.373835 0.892531 + outer loop + vertex -389.917 112.472 374.69 + vertex -389.293 115.598 376.176 + vertex -390.537 111.977 374.308 + endloop + endfacet + facet normal -0.204805 -0.39212 0.896826 + outer loop + vertex -390.306 112.206 374.452 + vertex -389.41 114.962 375.861 + vertex -390.09 113.68 375.145 + endloop + endfacet + facet normal 0.126182 0.42154 -0.897988 + outer loop + vertex -390.537 111.977 374.308 + vertex -391.144 110.26 373.417 + vertex -392.044 108.576 372.499 + endloop + endfacet + facet normal -0.186909 -0.395823 0.899105 + outer loop + vertex -391.146 110.069 373.336 + vertex -390.306 112.206 374.452 + vertex -390.09 113.68 375.145 + endloop + endfacet + facet normal 0.132338 0.418532 -0.898509 + outer loop + vertex -392.044 108.576 372.499 + vertex -391.144 110.26 373.417 + vertex -392.24 107.837 372.126 + endloop + endfacet + facet normal -0.189376 -0.394448 0.899193 + outer loop + vertex -391.909 108.201 372.356 + vertex -391.146 110.069 373.336 + vertex -392.481 108.082 372.183 + endloop + endfacet + facet normal -0.190056 -0.392314 0.899982 + outer loop + vertex -392.765 106.628 371.49 + vertex -391.909 108.201 372.356 + vertex -392.481 108.082 372.183 + endloop + endfacet + facet normal 0.102551 0.436214 -0.89398 + outer loop + vertex -393.706 105.445 370.791 + vertex -392.24 107.837 372.126 + vertex -394.012 104.708 370.396 + endloop + endfacet + facet normal -0.181808 -0.394317 0.900811 + outer loop + vertex -394.308 104.064 370.056 + vertex -392.765 106.628 371.49 + vertex -392.481 108.082 372.183 + endloop + endfacet + facet normal 0.0672155 0.456445 -0.887209 + outer loop + vertex -395.689 102.192 368.975 + vertex -394.012 104.708 370.396 + vertex -396.106 101.381 368.526 + endloop + endfacet + facet normal -0.185487 -0.39143 0.90132 + outer loop + vertex -395.738 101.697 368.734 + vertex -394.308 104.064 370.056 + vertex -396.001 102.076 368.844 + endloop + endfacet + facet normal -0.182722 -0.389871 0.902559 + outer loop + vertex -397.228 99.6171 367.533 + vertex -395.738 101.697 368.734 + vertex -396.001 102.076 368.844 + endloop + endfacet + facet normal -0.148264 0.573513 -0.805668 + outer loop + vertex -397.845 99.0312 367.173 + vertex -396.106 101.381 368.526 + vertex -398.412 98.2116 366.694 + endloop + endfacet + facet normal -0.166403 -0.399049 0.901704 + outer loop + vertex -399.014 97.2386 366.151 + vertex -397.228 99.6171 367.533 + vertex -398.624 97.8505 366.494 + endloop + endfacet + facet normal -0.309429 -0.290174 0.905567 + outer loop + vertex -399.769 96.3691 365.64 + vertex -398.412 98.2116 366.694 + vertex -400.194 95.8886 365.341 + endloop + endfacet + facet normal -0.155916 -0.405235 0.900819 + outer loop + vertex -400.521 95.2929 365.015 + vertex -399.014 97.2386 366.151 + vertex -398.624 97.8505 366.494 + endloop + endfacet + facet normal -0.29148 -0.30643 0.906168 + outer loop + vertex -399.769 96.3691 365.64 + vertex -400.194 95.8886 365.341 + vertex -401.144 94.5369 364.578 + endloop + endfacet + facet normal 0.123293 0.42648 -0.896054 + outer loop + vertex -400.521 95.2929 365.015 + vertex -402.439 92.2161 363.287 + vertex -401.398 94.2241 364.386 + endloop + endfacet + facet normal -0.176198 -0.394061 0.902037 + outer loop + vertex -401.451 93.2324 363.948 + vertex -401.144 94.5369 364.578 + vertex -401.842 93.5256 364 + endloop + endfacet + facet normal -0.165159 -0.405921 0.898861 + outer loop + vertex -400.847 92.3591 363.665 + vertex -399.894 92.5355 363.92 + vertex -401.451 93.2324 363.948 + endloop + endfacet + facet normal -0.159965 -0.423539 0.891642 + outer loop + vertex -398.157 91.3594 363.673 + vertex -399.894 92.5355 363.92 + vertex -400.847 92.3591 363.665 + endloop + endfacet + facet normal -0.150681 -0.390566 0.90816 + outer loop + vertex -394.906 90.0554 363.607 + vertex -402.439 92.2161 363.287 + vertex -397.062 90.0897 363.264 + endloop + endfacet + facet normal -0.148826 -0.424511 0.893108 + outer loop + vertex -394.906 90.0554 363.607 + vertex -397.062 90.0897 363.264 + vertex -390.934 88.6951 363.623 + endloop + endfacet + facet normal -0.133803 -0.380393 0.915094 + outer loop + vertex -387.47 87.9726 363.829 + vertex -394.906 90.0554 363.607 + vertex -390.934 88.6951 363.623 + endloop + endfacet + facet normal -0.153072 -0.446071 0.88181 + outer loop + vertex -390.687 88.1285 363.379 + vertex -390.934 88.6951 363.623 + vertex -397.062 90.0897 363.264 + endloop + endfacet + facet normal -0.144074 -0.41588 0.897935 + outer loop + vertex -397.062 90.0897 363.264 + vertex -396.671 89.0984 362.868 + vertex -390.687 88.1285 363.379 + endloop + endfacet + facet normal -0.147314 -0.443056 0.884308 + outer loop + vertex -390.687 88.1285 363.379 + vertex -396.671 89.0984 362.868 + vertex -391.163 87.3721 362.921 + endloop + endfacet + facet normal -0.140038 -0.447116 0.883446 + outer loop + vertex -390.687 88.1285 363.379 + vertex -391.163 87.3721 362.921 + vertex -382.824 85.8005 363.447 + endloop + endfacet + facet normal -0.148974 -0.477819 0.865734 + outer loop + vertex -383.983 86.7119 363.751 + vertex -390.687 88.1285 363.379 + vertex -382.824 85.8005 363.447 + endloop + endfacet + facet normal -0.136973 -0.465446 0.874413 + outer loop + vertex -383.983 86.7119 363.751 + vertex -382.824 85.8005 363.447 + vertex -374.621 84.1612 363.86 + endloop + endfacet + facet normal -0.146139 -0.519488 0.841888 + outer loop + vertex -374.621 84.1612 363.86 + vertex -382.824 85.8005 363.447 + vertex -372.706 83.0351 363.497 + endloop + endfacet + facet normal -0.13147 -0.499228 0.856438 + outer loop + vertex -374.621 84.1612 363.86 + vertex -372.706 83.0351 363.497 + vertex -365.136 81.8031 363.941 + endloop + endfacet + facet normal -0.13994 -0.567497 0.811396 + outer loop + vertex -365.136 81.8031 363.941 + vertex -372.706 83.0351 363.497 + vertex -360.078 80.0328 363.575 + endloop + endfacet + facet normal -0.115125 -0.505613 0.855045 + outer loop + vertex -365.136 81.8031 363.941 + vertex -360.078 80.0328 363.575 + vertex -354.593 80.0527 364.326 + endloop + endfacet + facet normal -0.123186 -0.495773 0.859671 + outer loop + vertex -372.706 83.0351 363.497 + vertex -371.87 81.6243 362.803 + vertex -360.078 80.0328 363.575 + endloop + endfacet + facet normal -0.124959 -0.514368 0.848417 + outer loop + vertex -360.078 80.0328 363.575 + vertex -371.87 81.6243 362.803 + vertex -357.895 78.1271 362.741 + endloop + endfacet + facet normal -0.107319 -0.499157 0.85984 + outer loop + vertex -360.078 80.0328 363.575 + vertex -357.895 78.1271 362.741 + vertex -342.569 76.3826 363.642 + endloop + endfacet + facet normal -0.108318 -0.511874 0.852204 + outer loop + vertex -342.919 73.909 362.111 + vertex -342.569 76.3826 363.642 + vertex -357.895 78.1271 362.741 + endloop + endfacet + facet normal -0.104923 -0.500858 0.859146 + outer loop + vertex -360.611 76.9055 361.698 + vertex -342.919 73.909 362.111 + vertex -357.895 78.1271 362.741 + endloop + endfacet + facet normal -0.117304 -0.481417 0.868607 + outer loop + vertex -357.895 78.1271 362.741 + vertex -372.292 79.8831 361.77 + vertex -360.611 76.9055 361.698 + endloop + endfacet + facet normal -0.118619 -0.486504 0.865588 + outer loop + vertex -372.292 79.8831 361.77 + vertex -372.395 77.6712 360.513 + vertex -360.611 76.9055 361.698 + endloop + endfacet + facet normal -0.118756 -0.506458 0.854047 + outer loop + vertex -360.611 76.9055 361.698 + vertex -372.395 77.6712 360.513 + vertex -358.613 74.5099 360.555 + endloop + endfacet + facet normal -0.117439 -0.500667 0.857637 + outer loop + vertex -372.395 77.6712 360.513 + vertex -371.576 74.9707 359.049 + vertex -358.613 74.5099 360.555 + endloop + endfacet + facet normal -0.117168 -0.508973 0.852771 + outer loop + vertex -358.613 74.5099 360.555 + vertex -371.576 74.9707 359.049 + vertex -360.587 72.7796 359.251 + endloop + endfacet + facet normal -0.104443 -0.519808 0.847875 + outer loop + vertex -360.587 72.7796 359.251 + vertex -344.407 70.3954 359.782 + vertex -358.613 74.5099 360.555 + endloop + endfacet + facet normal -0.104029 -0.518535 0.848705 + outer loop + vertex -344.407 70.3954 359.782 + vertex -342.919 73.909 362.111 + vertex -358.613 74.5099 360.555 + endloop + endfacet + facet normal -0.097469 -0.520879 0.848048 + outer loop + vertex -342.919 73.909 362.111 + vertex -344.407 70.3954 359.782 + vertex -320.245 69.2275 361.842 + endloop + endfacet + facet normal -0.0964819 -0.516266 0.850976 + outer loop + vertex -321.206 72.1359 363.497 + vertex -342.919 73.909 362.111 + vertex -320.245 69.2275 361.842 + endloop + endfacet + facet normal -0.0974659 -0.521653 0.847572 + outer loop + vertex -320.245 69.2275 361.842 + vertex -344.407 70.3954 359.782 + vertex -320.079 65.6124 359.636 + endloop + endfacet + facet normal -0.088229 -0.521794 0.848497 + outer loop + vertex -320.245 69.2275 361.842 + vertex -320.079 65.6124 359.636 + vertex -298.162 65.3979 361.783 + endloop + endfacet + facet normal -0.0871831 -0.51582 0.852249 + outer loop + vertex -300.78 68.3003 363.272 + vertex -320.245 69.2275 361.842 + vertex -298.162 65.3979 361.783 + endloop + endfacet + facet normal -0.0883138 -0.520091 0.849533 + outer loop + vertex -298.162 65.3979 361.783 + vertex -320.079 65.6124 359.636 + vertex -297.804 61.8248 359.633 + endloop + endfacet + facet normal -0.0790446 -0.519814 0.850615 + outer loop + vertex -298.162 65.3979 361.783 + vertex -297.804 61.8248 359.633 + vertex -276.688 62.169 361.805 + endloop + endfacet + facet normal -0.0781436 -0.513796 0.854346 + outer loop + vertex -279.535 65.3051 363.431 + vertex -298.162 65.3979 361.783 + vertex -276.688 62.169 361.805 + endloop + endfacet + facet normal -0.0789714 -0.520747 0.850051 + outer loop + vertex -276.688 62.169 361.805 + vertex -297.804 61.8248 359.633 + vertex -276.594 58.6316 359.647 + endloop + endfacet + facet normal -0.0726874 -0.520874 0.850533 + outer loop + vertex -276.688 62.169 361.805 + vertex -276.594 58.6316 359.647 + vertex -255.737 59.2472 361.807 + endloop + endfacet + facet normal -0.0715356 -0.512613 0.855634 + outer loop + vertex -257.535 62.21 363.431 + vertex -276.688 62.169 361.805 + vertex -255.737 59.2472 361.807 + endloop + endfacet + facet normal -0.0727014 -0.520722 0.850625 + outer loop + vertex -255.737 59.2472 361.807 + vertex -276.594 58.6316 359.647 + vertex -255.569 55.7338 359.67 + endloop + endfacet + facet normal -0.0674883 -0.52073 0.851049 + outer loop + vertex -255.737 59.2472 361.807 + vertex -255.569 55.7338 359.67 + vertex -234.839 56.5494 361.813 + endloop + endfacet + facet normal -0.0668415 -0.515713 0.85415 + outer loop + vertex -238.12 59.4083 363.282 + vertex -255.737 59.2472 361.807 + vertex -234.839 56.5494 361.813 + endloop + endfacet + facet normal -0.0675363 -0.520258 0.851334 + outer loop + vertex -234.839 56.5494 361.813 + vertex -255.569 55.7338 359.67 + vertex -234.275 52.9865 359.68 + endloop + endfacet + facet normal -0.0625059 -0.519843 0.851972 + outer loop + vertex -234.839 56.5494 361.813 + vertex -234.275 52.9865 359.68 + vertex -213.339 53.9848 361.826 + endloop + endfacet + facet normal -0.0620738 -0.51621 0.85421 + outer loop + vertex -217.342 57.1272 363.434 + vertex -234.839 56.5494 361.813 + vertex -213.339 53.9848 361.826 + endloop + endfacet + facet normal -0.0625393 -0.519537 0.852156 + outer loop + vertex -213.339 53.9848 361.826 + vertex -234.275 52.9865 359.68 + vertex -212.812 50.4078 359.683 + endloop + endfacet + facet normal -0.0569388 -0.519104 0.852813 + outer loop + vertex -213.339 53.9848 361.826 + vertex -212.812 50.4078 359.683 + vertex -191.981 51.5913 361.795 + endloop + endfacet + facet normal -0.0567879 -0.517769 0.853634 + outer loop + vertex -194.845 54.5903 363.423 + vertex -213.339 53.9848 361.826 + vertex -191.981 51.5913 361.795 + endloop + endfacet + facet normal -0.0568097 -0.520199 0.852153 + outer loop + vertex -191.981 51.5913 361.795 + vertex -212.812 50.4078 359.683 + vertex -191.458 48.0672 359.678 + endloop + endfacet + facet normal -0.0509417 -0.519725 0.852814 + outer loop + vertex -191.981 51.5913 361.795 + vertex -191.458 48.0672 359.678 + vertex -170.797 49.5181 361.797 + endloop + endfacet + facet normal -0.0508291 -0.518573 0.853521 + outer loop + vertex -174.625 52.3386 363.282 + vertex -191.981 51.5913 361.795 + vertex -170.797 49.5181 361.797 + endloop + endfacet + facet normal -0.0507986 -0.52081 0.85216 + outer loop + vertex -170.797 49.5181 361.797 + vertex -191.458 48.0672 359.678 + vertex -170.156 46.002 359.686 + endloop + endfacet + facet normal -0.0446828 -0.520144 0.852909 + outer loop + vertex -170.797 49.5181 361.797 + vertex -170.156 46.002 359.686 + vertex -149.398 47.7091 361.814 + endloop + endfacet + facet normal -0.0445612 -0.518696 0.853797 + outer loop + vertex -153.451 50.6934 363.416 + vertex -170.797 49.5181 361.797 + vertex -149.398 47.7091 361.814 + endloop + endfacet + facet normal -0.0446409 -0.520434 0.852734 + outer loop + vertex -149.398 47.7091 361.814 + vertex -170.156 46.002 359.686 + vertex -148.898 44.1889 359.692 + endloop + endfacet + facet normal -0.0385322 -0.519931 0.853339 + outer loop + vertex -149.398 47.7091 361.814 + vertex -148.898 44.1889 359.692 + vertex -128.25 46.1042 361.791 + endloop + endfacet + facet normal -0.0384242 -0.51852 0.854202 + outer loop + vertex -131.039 48.9969 363.422 + vertex -149.398 47.7091 361.814 + vertex -128.25 46.1042 361.791 + endloop + endfacet + facet normal -0.0383534 -0.521091 0.852639 + outer loop + vertex -128.25 46.1042 361.791 + vertex -148.898 44.1889 359.692 + vertex -127.78 42.6156 359.681 + endloop + endfacet + facet normal -0.0322473 -0.520602 0.853191 + outer loop + vertex -128.25 46.1042 361.791 + vertex -127.78 42.6156 359.681 + vertex -107.196 44.7938 361.788 + endloop + endfacet + facet normal -0.0321965 -0.519786 0.85369 + outer loop + vertex -111.118 47.4428 363.253 + vertex -128.25 46.1042 361.791 + vertex -107.196 44.7938 361.788 + endloop + endfacet + facet normal -0.0320679 -0.521671 0.852544 + outer loop + vertex -107.196 44.7938 361.788 + vertex -127.78 42.6156 359.681 + vertex -106.571 41.3069 359.678 + endloop + endfacet + facet normal -0.0255512 -0.520916 0.853225 + outer loop + vertex -107.196 44.7938 361.788 + vertex -106.571 41.3069 359.678 + vertex -85.5638 43.7528 361.8 + endloop + endfacet + facet normal -0.0254975 -0.519793 0.853911 + outer loop + vertex -89.6435 46.577 363.397 + vertex -107.196 44.7938 361.788 + vertex -85.5638 43.7528 361.8 + endloop + endfacet + facet normal -0.0254658 -0.521397 0.852934 + outer loop + vertex -85.5638 43.7528 361.8 + vertex -106.571 41.3069 359.678 + vertex -85.1425 40.2546 359.674 + endloop + endfacet + facet normal -0.019122 -0.520913 0.853396 + outer loop + vertex -85.5638 43.7528 361.8 + vertex -85.1425 40.2546 359.674 + vertex -63.5953 42.9382 361.795 + endloop + endfacet + facet normal -0.0190573 -0.519176 0.854455 + outer loop + vertex -66.6263 45.7013 363.406 + vertex -85.5638 43.7528 361.8 + vertex -63.5953 42.9382 361.795 + endloop + endfacet + facet normal -0.0191869 -0.52056 0.853609 + outer loop + vertex -63.5953 42.9382 361.795 + vertex -85.1425 40.2546 359.674 + vertex -63.6081 39.4652 359.677 + endloop + endfacet + facet normal -0.0133501 -0.520626 0.853681 + outer loop + vertex -63.5953 42.9382 361.795 + vertex -63.6081 39.4652 359.677 + vertex -42.058 42.379 361.791 + endloop + endfacet + facet normal -0.0132647 -0.51735 0.855671 + outer loop + vertex -43.7802 45.0861 363.401 + vertex -63.5953 42.9382 361.795 + vertex -42.058 42.379 361.791 + endloop + endfacet + facet normal -0.0132599 -0.521089 0.853399 + outer loop + vertex -42.058 42.379 361.791 + vertex -63.6081 39.4652 359.677 + vertex -42.1599 38.9248 359.68 + endloop + endfacet + facet normal -0.0077873 -0.521236 0.853377 + outer loop + vertex -42.058 42.379 361.791 + vertex -42.1599 38.9248 359.68 + vertex -21.0046 42.0723 361.796 + endloop + endfacet + facet normal -0.00773889 -0.517881 0.855418 + outer loop + vertex -23.6014 44.5812 363.291 + vertex -42.058 42.379 361.791 + vertex -21.0046 42.0723 361.796 + endloop + endfacet + facet normal -0.00778741 -0.521236 0.853377 + outer loop + vertex -21.0046 42.0723 361.796 + vertex -42.1599 38.9248 359.68 + vertex -20.8377 38.6087 359.682 + endloop + endfacet + facet normal -0.00271082 -0.521072 0.853509 + outer loop + vertex -21.0046 42.0723 361.796 + vertex -20.8377 38.6087 359.682 + vertex -0.0646938 41.9684 361.799 + endloop + endfacet + facet normal -0.00269438 -0.5177 0.855558 + outer loop + vertex -2.6198 44.6615 363.42 + vertex -21.0046 42.0723 361.796 + vertex -0.0646938 41.9684 361.799 + endloop + endfacet + facet normal -0.00265417 -0.521325 0.853354 + outer loop + vertex -0.0646938 41.9684 361.799 + vertex -20.8377 38.6087 359.682 + vertex 0.416727 38.5025 359.683 + endloop + endfacet + facet normal 0.00252645 -0.520801 0.853675 + outer loop + vertex -0.0646938 41.9684 361.799 + vertex 0.416727 38.5025 359.683 + vertex 20.9703 42.059 361.792 + endloop + endfacet + facet normal 0.0025139 -0.517745 0.855531 + outer loop + vertex 17.2225 44.5106 363.286 + vertex -0.0646938 41.9684 361.799 + vertex 20.9703 42.059 361.792 + endloop + endfacet + facet normal 0.00277177 -0.521841 0.853038 + outer loop + vertex 20.9703 42.059 361.792 + vertex 0.416727 38.5025 359.683 + vertex 21.7207 38.5986 359.672 + endloop + endfacet + facet normal 0.00801799 -0.520998 0.85352 + outer loop + vertex 20.9703 42.059 361.792 + vertex 21.7207 38.5986 359.672 + vertex 42.59 42.3967 361.795 + endloop + endfacet + facet normal 0.00798364 -0.518811 0.854852 + outer loop + vertex 38.5283 44.9808 363.401 + vertex 20.9703 42.059 361.792 + vertex 42.59 42.3967 361.795 + endloop + endfacet + facet normal 0.00807752 -0.521242 0.853371 + outer loop + vertex 42.59 42.3967 361.795 + vertex 21.7207 38.5986 359.672 + vertex 43.1936 38.9321 359.673 + endloop + endfacet + facet normal 0.0135212 -0.520521 0.853742 + outer loop + vertex 42.59 42.3967 361.795 + vertex 43.1936 38.9321 359.673 + vertex 64.5847 42.9774 361.8 + endloop + endfacet + facet normal 0.013468 -0.518515 0.854962 + outer loop + vertex 61.5707 45.5508 363.409 + vertex 42.59 42.3967 361.795 + vertex 64.5847 42.9774 361.8 + endloop + endfacet + facet normal 0.013521 -0.52052 0.853743 + outer loop + vertex 64.5847 42.9774 361.8 + vertex 43.1936 38.9321 359.673 + vertex 64.6873 39.5033 359.681 + endloop + endfacet + facet normal 0.01949 -0.52034 0.853737 + outer loop + vertex 64.5847 42.9774 361.8 + vertex 64.6873 39.5033 359.681 + vertex 86.1146 43.7598 361.786 + endloop + endfacet + facet normal 0.0194181 -0.518341 0.854954 + outer loop + vertex 84.4248 46.3616 363.402 + vertex 64.5847 42.9774 361.8 + vertex 86.1146 43.7598 361.786 + endloop + endfacet + facet normal 0.0197422 -0.521313 0.853137 + outer loop + vertex 86.1146 43.7598 361.786 + vertex 64.6873 39.5033 359.681 + vertex 86.1331 40.3103 359.677 + endloop + endfacet + facet normal 0.0258331 -0.521217 0.853033 + outer loop + vertex 86.1146 43.7598 361.786 + vertex 86.1331 40.3103 359.677 + vertex 107.446 44.8303 361.794 + endloop + endfacet + facet normal 0.0257233 -0.519039 0.854363 + outer loop + vertex 104.759 47.0983 363.253 + vertex 86.1146 43.7598 361.786 + vertex 107.446 44.8303 361.794 + endloop + endfacet + facet normal 0.025872 -0.521359 0.852945 + outer loop + vertex 107.446 44.8303 361.794 + vertex 86.1331 40.3103 359.677 + vertex 107.653 41.3841 359.681 + endloop + endfacet + facet normal 0.03233 -0.520979 0.852957 + outer loop + vertex 107.446 44.8303 361.794 + vertex 107.653 41.3841 359.681 + vertex 129.073 46.2008 361.811 + endloop + endfacet + facet normal 0.0321939 -0.518847 0.854261 + outer loop + vertex 126.156 48.6599 363.415 + vertex 107.446 44.8303 361.794 + vertex 129.073 46.2008 361.811 + endloop + endfacet + facet normal 0.0322973 -0.520865 0.853028 + outer loop + vertex 129.073 46.2008 361.811 + vertex 107.653 41.3841 359.681 + vertex 129.199 42.7123 359.676 + endloop + endfacet + facet normal 0.0386866 -0.520579 0.852937 + outer loop + vertex 129.073 46.2008 361.811 + vertex 129.199 42.7123 359.676 + vertex 150.45 47.7543 361.79 + endloop + endfacet + facet normal 0.038479 -0.517699 0.854697 + outer loop + vertex 148.618 50.2993 363.414 + vertex 129.073 46.2008 361.811 + vertex 150.45 47.7543 361.79 + endloop + endfacet + facet normal 0.038766 -0.520844 0.852771 + outer loop + vertex 150.45 47.7543 361.79 + vertex 129.199 42.7123 359.676 + vertex 150.643 44.2981 359.67 + endloop + endfacet + facet normal 0.0450424 -0.520452 0.852702 + outer loop + vertex 150.45 47.7543 361.79 + vertex 150.643 44.2981 359.67 + vertex 171.599 49.5837 361.789 + endloop + endfacet + facet normal 0.0447799 -0.517417 0.854561 + outer loop + vertex 168.65 51.7956 363.283 + vertex 150.45 47.7543 361.79 + vertex 171.599 49.5837 361.789 + endloop + endfacet + facet normal 0.0447796 -0.519619 0.853224 + outer loop + vertex 171.599 49.5837 361.789 + vertex 150.643 44.2981 359.67 + vertex 172.013 46.1537 359.679 + endloop + endfacet + facet normal 0.0508521 -0.518932 0.853301 + outer loop + vertex 171.599 49.5837 361.789 + vertex 172.013 46.1537 359.679 + vertex 192.922 51.7163 361.815 + endloop + endfacet + facet normal 0.0506433 -0.51686 0.85457 + outer loop + vertex 189.912 54.0865 363.427 + vertex 171.599 49.5837 361.789 + vertex 192.922 51.7163 361.815 + endloop + endfacet + facet normal 0.0510561 -0.51955 0.852913 + outer loop + vertex 192.922 51.7163 361.815 + vertex 172.013 46.1537 359.679 + vertex 193.289 48.2467 359.68 + endloop + endfacet + facet normal 0.0569271 -0.518932 0.852918 + outer loop + vertex 192.922 51.7163 361.815 + vertex 193.289 48.2467 359.68 + vertex 213.983 53.9935 361.795 + endloop + endfacet + facet normal 0.056678 -0.516615 0.85434 + outer loop + vertex 211.28 56.3973 363.428 + vertex 192.922 51.7163 361.815 + vertex 213.983 53.9935 361.795 + endloop + endfacet + facet normal 0.0572758 -0.51995 0.852274 + outer loop + vertex 213.983 53.9935 361.795 + vertex 193.289 48.2467 359.68 + vertex 214.512 50.5788 359.676 + endloop + endfacet + facet normal 0.0628584 -0.519146 0.852371 + outer loop + vertex 213.983 53.9935 361.795 + vertex 214.512 50.5788 359.676 + vertex 235.088 56.5469 361.794 + endloop + endfacet + facet normal 0.0625976 -0.51699 0.8537 + outer loop + vertex 231.304 58.5623 363.292 + vertex 213.983 53.9935 361.795 + vertex 235.088 56.5469 361.794 + endloop + endfacet + facet normal 0.0629589 -0.519429 0.852191 + outer loop + vertex 235.088 56.5469 361.794 + vertex 214.512 50.5788 359.676 + vertex 235.863 53.1896 359.69 + endloop + endfacet + facet normal 0.0681747 -0.518376 0.852431 + outer loop + vertex 235.088 56.5469 361.794 + vertex 235.863 53.1896 359.69 + vertex 256.609 59.4175 361.818 + endloop + endfacet + facet normal 0.0678139 -0.515685 0.85409 + outer loop + vertex 252.552 61.5333 363.418 + vertex 235.088 56.5469 361.794 + vertex 256.609 59.4175 361.818 + endloop + endfacet + facet normal 0.0683816 -0.518942 0.85207 + outer loop + vertex 256.609 59.4175 361.818 + vertex 235.863 53.1896 359.69 + vertex 257.25 56.0084 359.691 + endloop + endfacet + facet normal 0.0730909 -0.518124 0.852177 + outer loop + vertex 256.609 59.4175 361.818 + vertex 257.25 56.0084 359.691 + vertex 277.77 62.3567 361.79 + endloop + endfacet + facet normal 0.0725143 -0.513947 0.854751 + outer loop + vertex 274.887 64.6476 363.413 + vertex 256.609 59.4175 361.818 + vertex 277.77 62.3567 361.79 + endloop + endfacet + facet normal 0.0707491 -0.536903 0.840672 + outer loop + vertex 235.863 53.1896 359.69 + vertex 235.362 48.8323 356.95 + vertex 257.25 56.0084 359.691 + endloop + endfacet + facet normal 0.0702743 -0.535751 0.841447 + outer loop + vertex 257.25 56.0084 359.691 + vertex 235.362 48.8323 356.95 + vertex 256.774 51.639 356.948 + endloop + endfacet + facet normal 0.0747371 -0.569804 0.818375 + outer loop + vertex 235.362 48.8323 356.95 + vertex 235.24 44.0638 353.641 + vertex 256.774 51.639 356.948 + endloop + endfacet + facet normal 0.0688493 -0.569944 0.818794 + outer loop + vertex 235.362 48.8323 356.95 + vertex 213.867 41.4916 353.647 + vertex 235.24 44.0638 353.641 + endloop + endfacet + facet normal 0.0743219 -0.615507 0.78462 + outer loop + vertex 213.867 41.4916 353.647 + vertex 215.034 36.8176 349.87 + vertex 235.24 44.0638 353.641 + endloop + endfacet + facet normal 0.0744517 -0.615759 0.784409 + outer loop + vertex 235.24 44.0638 353.641 + vertex 215.034 36.8176 349.87 + vertex 236.394 39.377 349.852 + endloop + endfacet + facet normal 0.0802142 -0.61461 0.784742 + outer loop + vertex 235.24 44.0638 353.641 + vertex 236.394 39.377 349.852 + vertex 256.641 46.852 353.637 + endloop + endfacet + facet normal 0.0674981 -0.616853 0.784178 + outer loop + vertex 213.867 41.4916 353.647 + vertex 193.774 34.4983 349.876 + vertex 215.034 36.8176 349.87 + endloop + endfacet + facet normal 0.0674624 -0.616783 0.784237 + outer loop + vertex 192.606 39.1626 353.645 + vertex 193.774 34.4983 349.876 + vertex 213.867 41.4916 353.647 + endloop + endfacet + facet normal 0.0623939 -0.570554 0.818886 + outer loop + vertex 213.997 46.2384 356.945 + vertex 192.606 39.1626 353.645 + vertex 213.867 41.4916 353.647 + endloop + endfacet + facet normal 0.0627393 -0.571333 0.818317 + outer loop + vertex 192.729 43.8957 356.94 + vertex 192.606 39.1626 353.645 + vertex 213.997 46.2384 356.945 + endloop + endfacet + facet normal 0.0589199 -0.53671 0.841707 + outer loop + vertex 214.512 50.5788 359.676 + vertex 192.729 43.8957 356.94 + vertex 213.997 46.2384 356.945 + endloop + endfacet + facet normal 0.0561324 -0.571443 0.81872 + outer loop + vertex 192.729 43.8957 356.94 + vertex 171.356 37.0775 353.646 + vertex 192.606 39.1626 353.645 + endloop + endfacet + facet normal 0.0606217 -0.617224 0.784449 + outer loop + vertex 171.356 37.0775 353.646 + vertex 172.532 32.4068 349.88 + vertex 192.606 39.1626 353.645 + endloop + endfacet + facet normal 0.0531074 -0.61865 0.78387 + outer loop + vertex 171.356 37.0775 353.646 + vertex 151.231 30.5685 349.873 + vertex 172.532 32.4068 349.88 + endloop + endfacet + facet normal 0.0528107 -0.618028 0.78438 + outer loop + vertex 150.045 35.2486 353.64 + vertex 151.231 30.5685 349.873 + vertex 171.356 37.0775 353.646 + endloop + endfacet + facet normal 0.0487615 -0.570967 0.819524 + outer loop + vertex 171.47 41.8094 356.936 + vertex 150.045 35.2486 353.64 + vertex 171.356 37.0775 353.646 + endloop + endfacet + facet normal 0.0493937 -0.572481 0.818429 + outer loop + vertex 150.112 39.974 356.941 + vertex 150.045 35.2486 353.64 + vertex 171.47 41.8094 356.936 + endloop + endfacet + facet normal 0.0463815 -0.537361 0.842076 + outer loop + vertex 172.013 46.1537 359.679 + vertex 150.112 39.974 356.941 + vertex 171.47 41.8094 356.936 + endloop + endfacet + facet normal 0.0425209 -0.572597 0.818734 + outer loop + vertex 150.112 39.974 356.941 + vertex 128.578 33.6609 353.644 + vertex 150.045 35.2486 353.64 + endloop + endfacet + facet normal 0.0459021 -0.618409 0.784515 + outer loop + vertex 128.578 33.6609 353.644 + vertex 129.766 28.9663 349.874 + vertex 150.045 35.2486 353.64 + endloop + endfacet + facet normal 0.0384277 -0.619764 0.783847 + outer loop + vertex 128.578 33.6609 353.644 + vertex 108.252 27.6275 349.871 + vertex 129.766 28.9663 349.874 + endloop + endfacet + facet normal 0.0380026 -0.618814 0.784618 + outer loop + vertex 107.034 32.3365 353.643 + vertex 108.252 27.6275 349.871 + vertex 128.578 33.6609 353.644 + endloop + endfacet + facet normal 0.0351268 -0.572058 0.819461 + outer loop + vertex 128.639 38.3896 356.943 + vertex 107.034 32.3365 353.643 + vertex 128.578 33.6609 353.644 + endloop + endfacet + facet normal 0.0352164 -0.572288 0.819296 + outer loop + vertex 107.074 37.0642 356.944 + vertex 107.034 32.3365 353.643 + vertex 128.639 38.3896 356.943 + endloop + endfacet + facet normal 0.0330613 -0.537204 0.842804 + outer loop + vertex 129.199 42.7123 359.676 + vertex 107.074 37.0642 356.944 + vertex 128.639 38.3896 356.943 + endloop + endfacet + facet normal 0.0281673 -0.572376 0.819507 + outer loop + vertex 107.074 37.0642 356.944 + vertex 85.4436 31.276 353.645 + vertex 107.034 32.3365 353.643 + endloop + endfacet + facet normal 0.0304519 -0.61893 0.784856 + outer loop + vertex 85.4436 31.276 353.645 + vertex 86.696 26.5513 349.87 + vertex 107.034 32.3365 353.643 + endloop + endfacet + facet normal 0.0233788 -0.620198 0.784097 + outer loop + vertex 85.4436 31.276 353.645 + vertex 65.1265 25.7376 349.87 + vertex 86.696 26.5513 349.87 + endloop + endfacet + facet normal 0.0230141 -0.619334 0.784791 + outer loop + vertex 63.8865 30.4757 353.645 + vertex 65.1265 25.7376 349.87 + vertex 85.4436 31.276 353.645 + endloop + endfacet + facet normal 0.0212763 -0.572498 0.81963 + outer loop + vertex 85.4979 36.0047 356.946 + vertex 63.8865 30.4757 353.645 + vertex 85.4436 31.276 353.645 + endloop + endfacet + facet normal 0.0212499 -0.572425 0.819681 + outer loop + vertex 63.9938 35.1995 356.941 + vertex 63.8865 30.4757 353.645 + vertex 85.4979 36.0047 356.946 + endloop + endfacet + facet normal 0.0199419 -0.537632 0.842944 + outer loop + vertex 86.1331 40.3103 359.677 + vertex 63.9938 35.1995 356.941 + vertex 85.4979 36.0047 356.946 + endloop + endfacet + facet normal 0.014681 -0.572393 0.819848 + outer loop + vertex 63.9938 35.1995 356.941 + vertex 42.4385 29.9229 353.644 + vertex 63.8865 30.4757 353.645 + endloop + endfacet + facet normal 0.0158878 -0.619099 0.785152 + outer loop + vertex 42.4385 29.9229 353.644 + vertex 43.6208 25.1702 349.872 + vertex 63.8865 30.4757 353.645 + endloop + endfacet + facet normal 0.00975829 -0.620085 0.784474 + outer loop + vertex 42.4385 29.9229 353.644 + vertex 22.2497 24.8362 349.874 + vertex 43.6208 25.1702 349.872 + endloop + endfacet + facet normal 0.00944756 -0.619309 0.78509 + outer loop + vertex 21.0931 29.5997 353.645 + vertex 22.2497 24.8362 349.874 + vertex 42.4385 29.9229 353.644 + endloop + endfacet + facet normal 0.00875073 -0.573081 0.819452 + outer loop + vertex 42.5816 34.6448 356.944 + vertex 21.0931 29.5997 353.645 + vertex 42.4385 29.9229 353.644 + endloop + endfacet + facet normal 0.00849947 -0.572348 0.819967 + outer loop + vertex 21.2386 34.3163 356.936 + vertex 21.0931 29.5997 353.645 + vertex 42.5816 34.6448 356.944 + endloop + endfacet + facet normal 0.00795724 -0.537692 0.843104 + outer loop + vertex 43.1936 38.9321 359.673 + vertex 21.2386 34.3163 356.936 + vertex 42.5816 34.6448 356.944 + endloop + endfacet + facet normal 0.00255629 -0.572243 0.82008 + outer loop + vertex 21.2386 34.3163 356.936 + vertex -0.189077 29.4994 353.642 + vertex 21.0931 29.5997 353.645 + endloop + endfacet + facet normal 0.00278303 -0.619106 0.785303 + outer loop + vertex -0.189077 29.4994 353.642 + vertex 0.979474 24.7231 349.872 + vertex 21.0931 29.5997 353.645 + endloop + endfacet + facet normal -0.00299361 -0.619976 0.784615 + outer loop + vertex -0.189077 29.4994 353.642 + vertex -20.3363 24.8238 349.87 + vertex 0.979474 24.7231 349.872 + endloop + endfacet + facet normal -0.00311692 -0.619651 0.784871 + outer loop + vertex -21.5611 29.6126 353.646 + vertex -20.3363 24.8238 349.87 + vertex -0.189077 29.4994 353.642 + endloop + endfacet + facet normal -0.00286329 -0.573105 0.819477 + outer loop + vertex -0.0835181 34.2182 356.942 + vertex -21.5611 29.6126 353.646 + vertex -0.189077 29.4994 353.642 + endloop + endfacet + facet normal -0.00305207 -0.572518 0.819887 + outer loop + vertex -21.4478 34.3337 356.943 + vertex -21.5611 29.6126 353.646 + vertex -0.0835181 34.2182 356.942 + endloop + endfacet + facet normal -0.00286749 -0.538599 0.842557 + outer loop + vertex 0.416727 38.5025 359.683 + vertex -21.4478 34.3337 356.943 + vertex -0.0835181 34.2182 356.942 + endloop + endfacet + facet normal -0.0089836 -0.572402 0.819924 + outer loop + vertex -21.4478 34.3337 356.943 + vertex -43.0361 29.9456 353.643 + vertex -21.5611 29.6126 353.646 + endloop + endfacet + facet normal -0.009694 -0.61851 0.785717 + outer loop + vertex -43.0361 29.9456 353.643 + vertex -41.8219 25.1385 349.874 + vertex -21.5611 29.6126 353.646 + endloop + endfacet + facet normal -0.0158849 -0.619427 0.784893 + outer loop + vertex -43.0361 29.9456 353.643 + vertex -63.3485 25.6855 349.87 + vertex -41.8219 25.1385 349.874 + endloop + endfacet + facet normal -0.0159914 -0.619128 0.785128 + outer loop + vertex -64.5809 30.5018 353.643 + vertex -63.3485 25.6855 349.87 + vertex -43.0361 29.9456 353.643 + endloop + endfacet + facet normal -0.0147935 -0.572719 0.819618 + outer loop + vertex -42.9054 34.6612 356.941 + vertex -64.5809 30.5018 353.643 + vertex -43.0361 29.9456 353.643 + endloop + endfacet + facet normal -0.0146877 -0.573074 0.819372 + outer loop + vertex -64.4225 35.2137 356.942 + vertex -64.5809 30.5018 353.643 + vertex -42.9054 34.6612 356.941 + endloop + endfacet + facet normal -0.0138052 -0.538741 0.842358 + outer loop + vertex -42.1599 38.9248 359.68 + vertex -64.4225 35.2137 356.942 + vertex -42.9054 34.6612 356.941 + endloop + endfacet + facet normal -0.0214005 -0.572853 0.819378 + outer loop + vertex -64.4225 35.2137 356.942 + vertex -86.0633 31.2999 353.64 + vertex -64.5809 30.5018 353.643 + endloop + endfacet + facet normal -0.023118 -0.619216 0.78488 + outer loop + vertex -86.0633 31.2999 353.64 + vertex -84.8144 26.472 349.868 + vertex -64.5809 30.5018 353.643 + endloop + endfacet + facet normal -0.0300235 -0.620207 0.783863 + outer loop + vertex -86.0633 31.2999 353.64 + vertex -106.199 27.5094 349.87 + vertex -84.8144 26.472 349.868 + endloop + endfacet + facet normal -0.0303963 -0.619091 0.784731 + outer loop + vertex -107.434 32.3518 353.642 + vertex -106.199 27.5094 349.87 + vertex -86.0633 31.2999 353.64 + endloop + endfacet + facet normal -0.0281068 -0.572642 0.819323 + outer loop + vertex -85.8876 36.0061 356.935 + vertex -107.434 32.3518 353.642 + vertex -86.0633 31.2999 353.64 + endloop + endfacet + facet normal -0.0280877 -0.572712 0.819276 + outer loop + vertex -107.24 37.0609 356.941 + vertex -107.434 32.3518 353.642 + vertex -85.8876 36.0061 356.935 + endloop + endfacet + facet normal -0.0263838 -0.538335 0.842318 + outer loop + vertex -85.1425 40.2546 359.674 + vertex -107.24 37.0609 356.941 + vertex -85.8876 36.0061 356.935 + endloop + endfacet + facet normal -0.0352409 -0.572384 0.819228 + outer loop + vertex -107.24 37.0609 356.941 + vertex -128.691 33.6664 353.646 + vertex -107.434 32.3518 353.642 + endloop + endfacet + facet normal -0.0381264 -0.618931 0.784519 + outer loop + vertex -128.691 33.6664 353.646 + vertex -127.483 28.8074 349.872 + vertex -107.434 32.3518 353.642 + endloop + endfacet + facet normal -0.0453035 -0.619853 0.783409 + outer loop + vertex -128.691 33.6664 353.646 + vertex -148.739 30.3663 349.876 + vertex -127.483 28.8074 349.872 + endloop + endfacet + facet normal -0.045896 -0.61794 0.784884 + outer loop + vertex -149.907 35.2444 353.648 + vertex -148.739 30.3663 349.876 + vertex -128.691 33.6664 353.646 + endloop + endfacet + facet normal -0.0424234 -0.571288 0.819652 + outer loop + vertex -128.457 38.3766 356.941 + vertex -149.907 35.2444 353.648 + vertex -128.691 33.6664 353.646 + endloop + endfacet + facet normal -0.0422758 -0.571876 0.81925 + outer loop + vertex -149.638 39.954 356.949 + vertex -149.907 35.2444 353.648 + vertex -128.457 38.3766 356.941 + endloop + endfacet + facet normal -0.039731 -0.537823 0.842121 + outer loop + vertex -127.78 42.6156 359.681 + vertex -149.638 39.954 356.949 + vertex -128.457 38.3766 356.941 + endloop + endfacet + facet normal -0.0491896 -0.571429 0.819176 + outer loop + vertex -149.638 39.954 356.949 + vertex -171.152 37.0748 353.649 + vertex -149.907 35.2444 353.648 + endloop + endfacet + facet normal -0.0531693 -0.617596 0.784696 + outer loop + vertex -171.152 37.0748 353.649 + vertex -170.03 32.1854 349.877 + vertex -149.907 35.2444 353.648 + endloop + endfacet + facet normal -0.0593009 -0.61826 0.783733 + outer loop + vertex -171.152 37.0748 353.649 + vertex -191.36 34.24 349.884 + vertex -170.03 32.1854 349.877 + endloop + endfacet + facet normal -0.0600674 -0.615549 0.785806 + outer loop + vertex -192.416 39.1428 353.644 + vertex -191.36 34.24 349.884 + vertex -171.152 37.0748 353.649 + endloop + endfacet + facet normal -0.05574 -0.570965 0.81908 + outer loop + vertex -170.854 41.7778 356.948 + vertex -192.416 39.1428 353.644 + vertex -171.152 37.0748 353.649 + endloop + endfacet + facet normal -0.0557731 -0.570819 0.81918 + outer loop + vertex -192.127 43.8449 356.94 + vertex -192.416 39.1428 353.644 + vertex -170.854 41.7778 356.948 + endloop + endfacet + facet normal -0.0524994 -0.53704 0.841922 + outer loop + vertex -170.156 46.002 359.686 + vertex -192.127 43.8449 356.94 + vertex -170.854 41.7778 356.948 + endloop + endfacet + facet normal -0.0619861 -0.570352 0.819058 + outer loop + vertex -192.127 43.8449 356.94 + vertex -213.765 41.4511 353.635 + vertex -192.416 39.1428 353.644 + endloop + endfacet + facet normal -0.0668796 -0.615733 0.785111 + outer loop + vertex -213.765 41.4511 353.635 + vertex -212.663 36.5289 349.869 + vertex -192.416 39.1428 353.644 + endloop + endfacet + facet normal -0.0732899 -0.616356 0.78405 + outer loop + vertex -213.765 41.4511 353.635 + vertex -234.246 39.0802 349.857 + vertex -212.663 36.5289 349.869 + endloop + endfacet + facet normal -0.0739797 -0.61366 0.786097 + outer loop + vertex -235.268 44.0216 353.618 + vertex -234.246 39.0802 349.857 + vertex -213.765 41.4511 353.635 + endloop + endfacet + facet normal -0.0686588 -0.568928 0.819516 + outer loop + vertex -213.479 46.1673 356.933 + vertex -235.268 44.0216 353.618 + vertex -213.765 41.4511 353.635 + endloop + endfacet + facet normal -0.068755 -0.568451 0.819839 + outer loop + vertex -234.93 48.7387 356.917 + vertex -235.268 44.0216 353.618 + vertex -213.479 46.1673 356.933 + endloop + endfacet + facet normal -0.0648526 -0.53576 0.841876 + outer loop + vertex -212.812 50.4078 359.683 + vertex -234.93 48.7387 356.917 + vertex -213.479 46.1673 356.933 + endloop + endfacet + facet normal -0.0743306 -0.567953 0.819698 + outer loop + vertex -234.93 48.7387 356.917 + vertex -256.827 46.8367 353.614 + vertex -235.268 44.0216 353.618 + endloop + endfacet + facet normal -0.0801433 -0.612522 0.78638 + outer loop + vertex -256.827 46.8367 353.614 + vertex -256.171 41.9452 349.871 + vertex -235.268 44.0216 353.618 + endloop + endfacet + facet normal -0.0847769 -0.612678 0.785773 + outer loop + vertex -256.827 46.8367 353.614 + vertex -277.772 45.0519 349.963 + vertex -256.171 41.9452 349.871 + endloop + endfacet + facet normal -0.0856319 -0.608726 0.788746 + outer loop + vertex -278.1 49.8166 353.604 + vertex -277.772 45.0519 349.963 + vertex -256.827 46.8367 353.614 + endloop + endfacet + facet normal -0.0798932 -0.567658 0.819379 + outer loop + vertex -256.334 51.5166 356.904 + vertex -278.1 49.8166 353.604 + vertex -256.827 46.8367 353.614 + endloop + endfacet + facet normal -0.0795981 -0.569291 0.818274 + outer loop + vertex -277.441 54.4444 356.888 + vertex -278.1 49.8166 353.604 + vertex -256.334 51.5166 356.904 + endloop + endfacet + facet normal -0.0751784 -0.537308 0.840029 + outer loop + vertex -255.569 55.7338 359.67 + vertex -277.441 54.4444 356.888 + vertex -256.334 51.5166 356.904 + endloop + endfacet + facet normal -0.0854597 -0.568451 0.818266 + outer loop + vertex -277.441 54.4444 356.888 + vertex -298.911 52.9357 353.598 + vertex -278.1 49.8166 353.604 + endloop + endfacet + facet normal -0.0915863 -0.609394 0.78756 + outer loop + vertex -298.911 52.9357 353.598 + vertex -298.861 48.2144 349.95 + vertex -278.1 49.8166 353.604 + endloop + endfacet + facet normal -0.0973573 -0.609098 0.787097 + outer loop + vertex -298.911 52.9357 353.598 + vertex -319.044 51.5442 350.03 + vertex -298.861 48.2144 349.95 + endloop + endfacet + facet normal -0.0992451 -0.599666 0.794072 + outer loop + vertex -319.59 56.3258 353.573 + vertex -319.044 51.5442 350.03 + vertex -298.911 52.9357 353.598 + endloop + endfacet + facet normal -0.0936389 -0.565287 0.819563 + outer loop + vertex -298.372 57.5776 356.861 + vertex -319.59 56.3258 353.573 + vertex -298.911 52.9357 353.598 + endloop + endfacet + facet normal -0.0945799 -0.559485 0.823426 + outer loop + vertex -319.966 61.1693 356.821 + vertex -319.59 56.3258 353.573 + vertex -298.372 57.5776 356.861 + endloop + endfacet + facet normal -0.0906651 -0.535771 0.839482 + outer loop + vertex -297.804 61.8248 359.633 + vertex -319.966 61.1693 356.821 + vertex -298.372 57.5776 356.861 + endloop + endfacet + facet normal -0.105282 -0.559457 0.822146 + outer loop + vertex -319.966 61.1693 356.821 + vertex -341.592 60.2276 353.411 + vertex -319.59 56.3258 353.573 + endloop + endfacet + facet normal -0.109549 -0.584269 0.804133 + outer loop + vertex -341.592 60.2276 353.411 + vertex -338.583 55.0546 350.062 + vertex -319.59 56.3258 353.573 + endloop + endfacet + facet normal -0.120858 -0.588021 0.799766 + outer loop + vertex -341.592 60.2276 353.411 + vertex -360.808 58.6076 349.316 + vertex -338.583 55.0546 350.062 + endloop + endfacet + facet normal -0.121212 -0.586501 0.800827 + outer loop + vertex -366.202 65.053 353.22 + vertex -360.808 58.6076 349.316 + vertex -341.592 60.2276 353.411 + endloop + endfacet + facet normal -0.115836 -0.55826 0.82154 + outer loop + vertex -343.293 65.5791 356.807 + vertex -366.202 65.053 353.22 + vertex -341.592 60.2276 353.411 + endloop + endfacet + facet normal -0.115722 -0.559157 0.820946 + outer loop + vertex -367.607 70.9277 357.023 + vertex -366.202 65.053 353.22 + vertex -343.293 65.5791 356.807 + endloop + endfacet + facet normal -0.111563 -0.540767 0.833741 + outer loop + vertex -344.407 70.3954 359.782 + vertex -367.607 70.9277 357.023 + vertex -343.293 65.5791 356.807 + endloop + endfacet + facet normal -0.119506 -0.559541 0.820141 + outer loop + vertex -366.202 65.053 353.22 + vertex -367.607 70.9277 357.023 + vertex -381.806 69.5439 354.01 + endloop + endfacet + facet normal -0.123167 -0.570794 0.811803 + outer loop + vertex -381.388 66.7048 352.077 + vertex -366.202 65.053 353.22 + vertex -381.806 69.5439 354.01 + endloop + endfacet + facet normal -0.140068 -0.571213 0.808762 + outer loop + vertex -381.806 69.5439 354.01 + vertex -390.245 68.0848 351.518 + vertex -381.388 66.7048 352.077 + endloop + endfacet + facet normal -0.144278 -0.61034 0.778889 + outer loop + vertex -381.388 66.7048 352.077 + vertex -390.245 68.0848 351.518 + vertex -382.348 63.1373 349.104 + endloop + endfacet + facet normal -0.149701 -0.616225 0.773212 + outer loop + vertex -382.348 63.1373 349.104 + vertex -390.245 68.0848 351.518 + vertex -396.275 65.2498 348.091 + endloop + endfacet + facet normal -0.15498 -0.609843 0.777221 + outer loop + vertex -398.479 70.113 351.467 + vertex -396.275 65.2498 348.091 + vertex -390.245 68.0848 351.518 + endloop + endfacet + facet normal -0.147696 -0.579667 0.801357 + outer loop + vertex -390.245 68.0848 351.518 + vertex -392.967 72.0068 353.853 + vertex -398.479 70.113 351.467 + endloop + endfacet + facet normal -0.155706 -0.566369 0.809309 + outer loop + vertex -399.387 74.3205 354.237 + vertex -398.479 70.113 351.467 + vertex -392.967 72.0068 353.853 + endloop + endfacet + facet normal -0.14519 -0.540418 0.828775 + outer loop + vertex -392.967 72.0068 353.853 + vertex -393.62 75.1318 355.776 + vertex -399.387 74.3205 354.237 + endloop + endfacet + facet normal -0.149165 -0.527068 0.83663 + outer loop + vertex -398.909 77.1058 356.077 + vertex -399.387 74.3205 354.237 + vertex -393.62 75.1318 355.776 + endloop + endfacet + facet normal -0.13993 -0.504656 0.851905 + outer loop + vertex -393.62 75.1318 355.776 + vertex -393.557 77.8102 357.373 + vertex -398.909 77.1058 356.077 + endloop + endfacet + facet normal -0.143726 -0.490164 0.859699 + outer loop + vertex -399.507 79.5843 357.39 + vertex -398.909 77.1058 356.077 + vertex -393.557 77.8102 357.373 + endloop + endfacet + facet normal -0.141996 -0.484397 0.863248 + outer loop + vertex -393.557 77.8102 357.373 + vertex -394.202 80.6333 358.852 + vertex -399.507 79.5843 357.39 + endloop + endfacet + facet normal -0.143839 -0.478909 0.866001 + outer loop + vertex -399.715 81.8051 358.584 + vertex -399.507 79.5843 357.39 + vertex -394.202 80.6333 358.852 + endloop + endfacet + facet normal -0.143634 -0.477797 0.866648 + outer loop + vertex -397.3 82.8803 359.577 + vertex -399.715 81.8051 358.584 + vertex -394.202 80.6333 358.852 + endloop + endfacet + facet normal -0.144766 -0.479069 0.865757 + outer loop + vertex -393.216 82.1429 359.852 + vertex -397.3 82.8803 359.577 + vertex -394.202 80.6333 358.852 + endloop + endfacet + facet normal -0.136164 -0.483851 0.864493 + outer loop + vertex -393.216 82.1429 359.852 + vertex -394.202 80.6333 358.852 + vertex -385.465 80.8945 360.374 + endloop + endfacet + facet normal -0.134609 -0.471186 0.871702 + outer loop + vertex -393.216 82.1429 359.852 + vertex -385.465 80.8945 360.374 + vertex -392.758 83.3039 360.55 + endloop + endfacet + facet normal -0.135621 -0.474121 0.869952 + outer loop + vertex -385.465 80.8945 360.374 + vertex -385.04 83.2225 361.709 + vertex -392.758 83.3039 360.55 + endloop + endfacet + facet normal -0.136439 -0.462164 0.876236 + outer loop + vertex -393.734 84.7795 361.176 + vertex -392.758 83.3039 360.55 + vertex -385.04 83.2225 361.709 + endloop + endfacet + facet normal -0.136373 -0.461712 0.876484 + outer loop + vertex -393.734 84.7795 361.176 + vertex -385.04 83.2225 361.709 + vertex -392.389 85.7145 361.878 + endloop + endfacet + facet normal -0.144433 -0.45268 0.879898 + outer loop + vertex -392.389 85.7145 361.878 + vertex -397.807 85.9941 361.133 + vertex -393.734 84.7795 361.176 + endloop + endfacet + facet normal -0.145725 -0.457103 0.877395 + outer loop + vertex -397.807 85.9941 361.133 + vertex -397.935 84.5576 360.363 + vertex -393.734 84.7795 361.176 + endloop + endfacet + facet normal -0.151596 -0.456277 0.87683 + outer loop + vertex -397.807 85.9941 361.133 + vertex -400.945 85.5169 360.342 + vertex -397.935 84.5576 360.363 + endloop + endfacet + facet normal -0.15246 -0.459022 0.875246 + outer loop + vertex -400.945 85.5169 360.342 + vertex -400.832 83.5723 359.342 + vertex -397.935 84.5576 360.363 + endloop + endfacet + facet normal -0.149292 -0.465405 0.872416 + outer loop + vertex -397.935 84.5576 360.363 + vertex -400.832 83.5723 359.342 + vertex -397.3 82.8803 359.577 + endloop + endfacet + facet normal -0.14397 -0.464128 0.873989 + outer loop + vertex -397.935 84.5576 360.363 + vertex -397.3 82.8803 359.577 + vertex -392.758 83.3039 360.55 + endloop + endfacet + facet normal -0.155684 -0.458938 0.874722 + outer loop + vertex -400.832 83.5723 359.342 + vertex -400.945 85.5169 360.342 + vertex -402.588 84.1889 359.353 + endloop + endfacet + facet normal -0.15863 -0.467238 0.869784 + outer loop + vertex -402.588 84.1889 359.353 + vertex -402.121 81.547 358.019 + vertex -400.832 83.5723 359.342 + endloop + endfacet + facet normal -0.153805 -0.469927 0.869202 + outer loop + vertex -400.832 83.5723 359.342 + vertex -402.121 81.547 358.019 + vertex -399.715 81.8051 358.584 + endloop + endfacet + facet normal -0.159716 -0.467311 0.869547 + outer loop + vertex -402.588 84.1889 359.353 + vertex -403.348 81.814 357.937 + vertex -402.121 81.547 358.019 + endloop + endfacet + facet normal -0.163664 -0.489457 0.856531 + outer loop + vertex -403.348 81.814 357.937 + vertex -402.436 77.7108 355.766 + vertex -402.121 81.547 358.019 + endloop + endfacet + facet normal -0.182596 -0.459717 0.869091 + outer loop + vertex -403.221 85.2672 359.79 + vertex -403.348 81.814 357.937 + vertex -402.588 84.1889 359.353 + endloop + endfacet + facet normal -0.162473 -0.451303 0.877455 + outer loop + vertex -402.302 86.8634 360.781 + vertex -403.221 85.2672 359.79 + vertex -402.588 84.1889 359.353 + endloop + endfacet + facet normal -0.178551 -0.442801 0.878662 + outer loop + vertex -402.958 87.8396 361.14 + vertex -403.221 85.2672 359.79 + vertex -402.302 86.8634 360.781 + endloop + endfacet + facet normal -0.165949 -0.436415 0.88431 + outer loop + vertex -402.111 89.1777 361.959 + vertex -402.958 87.8396 361.14 + vertex -402.302 86.8634 360.781 + endloop + endfacet + facet normal -0.165382 -0.436495 0.884376 + outer loop + vertex -402.111 89.1777 361.959 + vertex -402.302 86.8634 360.781 + vertex -400.618 88.1384 361.725 + endloop + endfacet + facet normal -0.161196 -0.431233 0.887724 + outer loop + vertex -400.05 89.1877 362.338 + vertex -402.111 89.1777 361.959 + vertex -400.618 88.1384 361.725 + endloop + endfacet + facet normal -0.152675 -0.43551 0.887142 + outer loop + vertex -400.05 89.1877 362.338 + vertex -400.618 88.1384 361.725 + vertex -397.162 88.2077 362.354 + endloop + endfacet + facet normal -0.150923 -0.430301 0.889979 + outer loop + vertex -396.671 89.0984 362.868 + vertex -400.05 89.1877 362.338 + vertex -397.162 88.2077 362.354 + endloop + endfacet + facet normal -0.151336 -0.421555 0.894085 + outer loop + vertex -400.388 90.1304 362.725 + vertex -400.05 89.1877 362.338 + vertex -396.671 89.0984 362.868 + endloop + endfacet + facet normal -0.152352 -0.438545 0.885701 + outer loop + vertex -397.162 88.2077 362.354 + vertex -400.618 88.1384 361.725 + vertex -397.559 87.1929 361.783 + endloop + endfacet + facet normal -0.145742 -0.441058 0.885566 + outer loop + vertex -397.162 88.2077 362.354 + vertex -397.559 87.1929 361.783 + vertex -393.014 86.8921 362.382 + endloop + endfacet + facet normal -0.14481 -0.438085 0.887193 + outer loop + vertex -391.163 87.3721 362.921 + vertex -397.162 88.2077 362.354 + vertex -393.014 86.8921 362.382 + endloop + endfacet + facet normal -0.138429 -0.454514 0.879917 + outer loop + vertex -393.014 86.8921 362.382 + vertex -384.312 84.9618 362.754 + vertex -391.163 87.3721 362.921 + endloop + endfacet + facet normal -0.137568 -0.450177 0.882279 + outer loop + vertex -393.014 86.8921 362.382 + vertex -392.389 85.7145 361.878 + vertex -384.312 84.9618 362.754 + endloop + endfacet + facet normal -0.145736 -0.453274 0.879377 + outer loop + vertex -393.014 86.8921 362.382 + vertex -397.559 87.1929 361.783 + vertex -392.389 85.7145 361.878 + endloop + endfacet + facet normal -0.152793 -0.440022 0.884893 + outer loop + vertex -400.618 88.1384 361.725 + vertex -400.473 86.9249 361.147 + vertex -397.559 87.1929 361.783 + endloop + endfacet + facet normal -0.151398 -0.447198 0.881529 + outer loop + vertex -397.559 87.1929 361.783 + vertex -400.473 86.9249 361.147 + vertex -397.807 85.9941 361.133 + endloop + endfacet + facet normal -0.161842 -0.424079 0.891047 + outer loop + vertex -400.05 89.1877 362.338 + vertex -400.388 90.1304 362.725 + vertex -402.111 89.1777 361.959 + endloop + endfacet + facet normal -0.163488 -0.421748 0.891852 + outer loop + vertex -402.229 90.7728 362.692 + vertex -402.111 89.1777 361.959 + vertex -400.388 90.1304 362.725 + endloop + endfacet + facet normal -0.160365 -0.412542 0.896712 + outer loop + vertex -400.905 90.9965 363.032 + vertex -402.229 90.7728 362.692 + vertex -400.388 90.1304 362.725 + endloop + endfacet + facet normal -0.150889 -0.408175 0.900348 + outer loop + vertex -400.905 90.9965 363.032 + vertex -400.388 90.1304 362.725 + vertex -397.062 90.0897 363.264 + endloop + endfacet + facet normal -0.164772 -0.396316 0.903207 + outer loop + vertex -402.229 90.7728 362.692 + vertex -400.905 90.9965 363.032 + vertex -402.439 92.2161 363.287 + endloop + endfacet + facet normal -0.160045 -0.39603 0.904182 + outer loop + vertex -402.693 91.1073 362.756 + vertex -402.229 90.7728 362.692 + vertex -402.439 92.2161 363.287 + endloop + endfacet + facet normal -0.108824 0.449307 -0.886725 + outer loop + vertex -402.818 89.8927 362.156 + vertex -402.693 91.1073 362.756 + vertex -402.439 92.2161 363.287 + endloop + endfacet + facet normal -0.372299 -0.356341 0.85698 + outer loop + vertex -402.439 92.2161 363.287 + vertex -403.562 87.4412 360.813 + vertex -402.818 89.8927 362.156 + endloop + endfacet + facet normal -0.179981 -0.420798 0.889121 + outer loop + vertex -402.693 91.1073 362.756 + vertex -402.818 89.8927 362.156 + vertex -402.229 90.7728 362.692 + endloop + endfacet + facet normal -0.17873 -0.421568 0.889009 + outer loop + vertex -402.229 90.7728 362.692 + vertex -402.818 89.8927 362.156 + vertex -402.111 89.1777 361.959 + endloop + endfacet + facet normal -0.161837 -0.440276 0.883157 + outer loop + vertex -400.473 86.9249 361.147 + vertex -400.618 88.1384 361.725 + vertex -402.302 86.8634 360.781 + endloop + endfacet + facet normal -0.160728 -0.448814 0.879052 + outer loop + vertex -400.473 86.9249 361.147 + vertex -402.302 86.8634 360.781 + vertex -400.945 85.5169 360.342 + endloop + endfacet + facet normal -0.184017 -0.425925 0.885848 + outer loop + vertex -402.818 89.8927 362.156 + vertex -402.958 87.8396 361.14 + vertex -402.111 89.1777 361.959 + endloop + endfacet + facet normal -0.197831 -0.423974 0.883804 + outer loop + vertex -402.958 87.8396 361.14 + vertex -402.818 89.8927 362.156 + vertex -403.562 87.4412 360.813 + endloop + endfacet + facet normal -0.182827 -0.44209 0.878141 + outer loop + vertex -403.221 85.2672 359.79 + vertex -402.958 87.8396 361.14 + vertex -403.562 87.4412 360.813 + endloop + endfacet + facet normal -0.19162 -0.442491 0.876061 + outer loop + vertex -403.562 87.4412 360.813 + vertex -404.337 83.2084 358.506 + vertex -403.221 85.2672 359.79 + endloop + endfacet + facet normal -0.150319 -0.463221 0.873402 + outer loop + vertex -403.348 81.814 357.937 + vertex -403.221 85.2672 359.79 + vertex -404.337 83.2084 358.506 + endloop + endfacet + facet normal -0.173691 -0.475338 0.862488 + outer loop + vertex -404.337 83.2084 358.506 + vertex -404.744 78.9861 356.097 + vertex -403.348 81.814 357.937 + endloop + endfacet + facet normal -0.152207 -0.47867 0.864701 + outer loop + vertex -404.744 78.9861 356.097 + vertex -404.337 83.2084 358.506 + vertex -408.287 81.0381 356.609 + endloop + endfacet + facet normal -0.163573 -0.451125 0.877342 + outer loop + vertex -402.302 86.8634 360.781 + vertex -402.588 84.1889 359.353 + vertex -400.945 85.5169 360.342 + endloop + endfacet + facet normal -0.1529 -0.45146 0.879094 + outer loop + vertex -400.473 86.9249 361.147 + vertex -400.945 85.5169 360.342 + vertex -397.807 85.9941 361.133 + endloop + endfacet + facet normal -0.144504 -0.448807 0.881868 + outer loop + vertex -397.559 87.1929 361.783 + vertex -397.807 85.9941 361.133 + vertex -392.389 85.7145 361.878 + endloop + endfacet + facet normal -0.138166 -0.466797 0.873505 + outer loop + vertex -385.04 83.2225 361.709 + vertex -384.312 84.9618 362.754 + vertex -392.389 85.7145 361.878 + endloop + endfacet + facet normal -0.129596 -0.470106 0.873043 + outer loop + vertex -384.312 84.9618 362.754 + vertex -385.04 83.2225 361.709 + vertex -371.87 81.6243 362.803 + endloop + endfacet + facet normal -0.130508 -0.48227 0.866247 + outer loop + vertex -371.87 81.6243 362.803 + vertex -385.04 83.2225 361.709 + vertex -372.292 79.8831 361.77 + endloop + endfacet + facet normal -0.144388 -0.466012 0.872918 + outer loop + vertex -393.734 84.7795 361.176 + vertex -397.935 84.5576 360.363 + vertex -392.758 83.3039 360.55 + endloop + endfacet + facet normal -0.128761 -0.47553 0.870225 + outer loop + vertex -385.04 83.2225 361.709 + vertex -385.465 80.8945 360.374 + vertex -372.292 79.8831 361.77 + endloop + endfacet + facet normal -0.136034 -0.484892 0.863929 + outer loop + vertex -385.465 80.8945 360.374 + vertex -394.202 80.6333 358.852 + vertex -384.272 78.0353 358.957 + endloop + endfacet + facet normal -0.128294 -0.482824 0.866269 + outer loop + vertex -385.465 80.8945 360.374 + vertex -384.272 78.0353 358.957 + vertex -372.395 77.6712 360.513 + endloop + endfacet + facet normal -0.143192 -0.468008 0.872046 + outer loop + vertex -392.758 83.3039 360.55 + vertex -397.3 82.8803 359.577 + vertex -393.216 82.1429 359.852 + endloop + endfacet + facet normal -0.149715 -0.468076 0.870913 + outer loop + vertex -397.3 82.8803 359.577 + vertex -400.832 83.5723 359.342 + vertex -399.715 81.8051 358.584 + endloop + endfacet + facet normal -0.151767 -0.478922 0.864639 + outer loop + vertex -399.715 81.8051 358.584 + vertex -402.121 81.547 358.019 + vertex -399.507 79.5843 357.39 + endloop + endfacet + facet normal -0.135729 -0.483698 0.864647 + outer loop + vertex -394.202 80.6333 358.852 + vertex -393.557 77.8102 357.373 + vertex -384.272 78.0353 358.957 + endloop + endfacet + facet normal -0.133372 -0.503501 0.853639 + outer loop + vertex -384.272 78.0353 358.957 + vertex -393.557 77.8102 357.373 + vertex -383.643 75.1553 357.357 + endloop + endfacet + facet normal -0.12757 -0.502916 0.854869 + outer loop + vertex -384.272 78.0353 358.957 + vertex -383.643 75.1553 357.357 + vertex -371.576 74.9707 359.049 + endloop + endfacet + facet normal -0.124993 -0.53979 0.832468 + outer loop + vertex -371.576 74.9707 359.049 + vertex -383.643 75.1553 357.357 + vertex -367.607 70.9277 357.023 + endloop + endfacet + facet normal -0.121166 -0.526008 0.841804 + outer loop + vertex -385.195 72.8341 355.683 + vertex -367.607 70.9277 357.023 + vertex -383.643 75.1553 357.357 + endloop + endfacet + facet normal -0.132414 -0.51997 0.843859 + outer loop + vertex -383.643 75.1553 357.357 + vertex -393.62 75.1318 355.776 + vertex -385.195 72.8341 355.683 + endloop + endfacet + facet normal -0.159827 -0.491986 0.855807 + outer loop + vertex -398.909 77.1058 356.077 + vertex -399.507 79.5843 357.39 + vertex -402.436 77.7108 355.766 + endloop + endfacet + facet normal -0.133827 -0.505194 0.852566 + outer loop + vertex -393.557 77.8102 357.373 + vertex -393.62 75.1318 355.776 + vertex -383.643 75.1553 357.357 + endloop + endfacet + facet normal -0.163567 -0.524063 0.835825 + outer loop + vertex -398.909 77.1058 356.077 + vertex -402.436 77.7108 355.766 + vertex -399.387 74.3205 354.237 + endloop + endfacet + facet normal -0.137994 -0.539883 0.830351 + outer loop + vertex -393.62 75.1318 355.776 + vertex -392.967 72.0068 353.853 + vertex -385.195 72.8341 355.683 + endloop + endfacet + facet normal -0.13408 -0.55537 0.820724 + outer loop + vertex -385.195 72.8341 355.683 + vertex -392.967 72.0068 353.853 + vertex -381.806 69.5439 354.01 + endloop + endfacet + facet normal -0.145244 -0.565699 0.81172 + outer loop + vertex -398.479 70.113 351.467 + vertex -399.387 74.3205 354.237 + vertex -402.67 72.4442 352.342 + endloop + endfacet + facet normal -0.166698 -0.594777 0.786417 + outer loop + vertex -402.67 72.4442 352.342 + vertex -401.945 66.9786 348.362 + vertex -398.479 70.113 351.467 + endloop + endfacet + facet normal -0.148239 -0.608454 0.779621 + outer loop + vertex -398.479 70.113 351.467 + vertex -401.945 66.9786 348.362 + vertex -396.275 65.2498 348.091 + endloop + endfacet + facet normal -0.138386 -0.575833 0.80577 + outer loop + vertex -392.967 72.0068 353.853 + vertex -390.245 68.0848 351.518 + vertex -381.806 69.5439 354.01 + endloop + endfacet + facet normal -0.125469 -0.615038 0.778451 + outer loop + vertex -381.388 66.7048 352.077 + vertex -382.348 63.1373 349.104 + vertex -366.202 65.053 353.22 + endloop + endfacet + facet normal -0.122404 -0.547085 0.828079 + outer loop + vertex -385.195 72.8341 355.683 + vertex -381.806 69.5439 354.01 + vertex -367.607 70.9277 357.023 + endloop + endfacet + facet normal -0.132358 -0.592203 0.794844 + outer loop + vertex -366.202 65.053 353.22 + vertex -382.348 63.1373 349.104 + vertex -360.808 58.6076 349.316 + endloop + endfacet + facet normal -0.105701 -0.556612 0.824021 + outer loop + vertex -343.293 65.5791 356.807 + vertex -341.592 60.2276 353.411 + vertex -319.966 61.1693 356.821 + endloop + endfacet + facet normal -0.101488 -0.53428 0.839193 + outer loop + vertex -320.079 65.6124 359.636 + vertex -343.293 65.5791 356.807 + vertex -319.966 61.1693 356.821 + endloop + endfacet + facet normal -0.106468 -0.599751 0.793072 + outer loop + vertex -319.59 56.3258 353.573 + vertex -338.583 55.0546 350.062 + vertex -319.044 51.5442 350.03 + endloop + endfacet + facet normal -0.085833 -0.566301 0.819717 + outer loop + vertex -298.372 57.5776 356.861 + vertex -298.911 52.9357 353.598 + vertex -277.441 54.4444 356.888 + endloop + endfacet + facet normal -0.0814516 -0.53686 0.839731 + outer loop + vertex -276.594 58.6316 359.647 + vertex -298.372 57.5776 356.861 + vertex -277.441 54.4444 356.888 + endloop + endfacet + facet normal -0.0917395 -0.608661 0.788109 + outer loop + vertex -278.1 49.8166 353.604 + vertex -298.861 48.2144 349.95 + vertex -277.772 45.0519 349.963 + endloop + endfacet + facet normal -0.0742639 -0.568306 0.819459 + outer loop + vertex -256.334 51.5166 356.904 + vertex -256.827 46.8367 353.614 + vertex -234.93 48.7387 356.917 + endloop + endfacet + facet normal -0.0701232 -0.536297 0.841111 + outer loop + vertex -234.275 52.9865 359.68 + vertex -256.334 51.5166 356.904 + vertex -234.93 48.7387 356.917 + endloop + endfacet + facet normal -0.0797633 -0.614139 0.785156 + outer loop + vertex -235.268 44.0216 353.618 + vertex -256.171 41.9452 349.871 + vertex -234.246 39.0802 349.857 + endloop + endfacet + facet normal -0.0621828 -0.569435 0.819681 + outer loop + vertex -213.479 46.1673 356.933 + vertex -213.765 41.4511 353.635 + vertex -192.127 43.8449 356.94 + endloop + endfacet + facet normal -0.0586218 -0.536636 0.841775 + outer loop + vertex -191.458 48.0672 359.678 + vertex -213.479 46.1673 356.933 + vertex -192.127 43.8449 356.94 + endloop + endfacet + facet normal -0.0667557 -0.61619 0.784763 + outer loop + vertex -192.416 39.1428 353.644 + vertex -212.663 36.5289 349.869 + vertex -191.36 34.24 349.884 + endloop + endfacet + facet normal -0.0491868 -0.571441 0.819168 + outer loop + vertex -170.854 41.7778 356.948 + vertex -171.152 37.0748 353.649 + vertex -149.638 39.954 356.949 + endloop + endfacet + facet normal -0.0462543 -0.537306 0.842118 + outer loop + vertex -148.898 44.1889 359.692 + vertex -170.854 41.7778 356.948 + vertex -149.638 39.954 356.949 + endloop + endfacet + facet normal -0.0528244 -0.618761 0.783801 + outer loop + vertex -149.907 35.2444 353.648 + vertex -170.03 32.1854 349.877 + vertex -148.739 30.3663 349.876 + endloop + endfacet + facet normal -0.0354269 -0.571678 0.819713 + outer loop + vertex -128.457 38.3766 356.941 + vertex -128.691 33.6664 353.646 + vertex -107.24 37.0609 356.941 + endloop + endfacet + facet normal -0.0333224 -0.537751 0.842445 + outer loop + vertex -106.571 41.3069 359.678 + vertex -128.457 38.3766 356.941 + vertex -107.24 37.0609 356.941 + endloop + endfacet + facet normal -0.0377504 -0.620098 0.783616 + outer loop + vertex -107.434 32.3518 353.642 + vertex -127.483 28.8074 349.872 + vertex -106.199 27.5094 349.87 + endloop + endfacet + facet normal -0.0213853 -0.572906 0.819342 + outer loop + vertex -85.8876 36.0061 356.935 + vertex -86.0633 31.2999 353.64 + vertex -64.4225 35.2137 356.942 + endloop + endfacet + facet normal -0.0201106 -0.538193 0.842582 + outer loop + vertex -63.6081 39.4652 359.677 + vertex -85.8876 36.0061 356.935 + vertex -64.4225 35.2137 356.942 + endloop + endfacet + facet normal -0.0228053 -0.620123 0.784173 + outer loop + vertex -64.5809 30.5018 353.643 + vertex -84.8144 26.472 349.868 + vertex -63.3485 25.6855 349.87 + endloop + endfacet + facet normal -0.0088387 -0.57287 0.819599 + outer loop + vertex -42.9054 34.6612 356.941 + vertex -43.0361 29.9456 353.643 + vertex -21.4478 34.3337 356.943 + endloop + endfacet + facet normal -0.00831664 -0.538481 0.842596 + outer loop + vertex -20.8377 38.6087 359.682 + vertex -42.9054 34.6612 356.941 + vertex -21.4478 34.3337 356.943 + endloop + endfacet + facet normal -0.00894614 -0.620548 0.784118 + outer loop + vertex -21.5611 29.6126 353.646 + vertex -41.8219 25.1385 349.874 + vertex -20.3363 24.8238 349.87 + endloop + endfacet + facet normal 0.00287139 -0.573191 0.819417 + outer loop + vertex -0.0835181 34.2182 356.942 + vertex -0.189077 29.4994 353.642 + vertex 21.2386 34.3163 356.936 + endloop + endfacet + facet normal 0.00271901 -0.538627 0.84254 + outer loop + vertex 21.7207 38.5986 359.672 + vertex -0.0835181 34.2182 356.942 + vertex 21.2386 34.3163 356.936 + endloop + endfacet + facet normal 0.00323493 -0.620262 0.784388 + outer loop + vertex 21.0931 29.5997 353.645 + vertex 0.979474 24.7231 349.872 + vertex 22.2497 24.8362 349.874 + endloop + endfacet + facet normal 0.0149536 -0.573165 0.819303 + outer loop + vertex 42.5816 34.6448 356.944 + vertex 42.4385 29.9229 353.644 + vertex 63.9938 35.1995 356.941 + endloop + endfacet + facet normal 0.014058 -0.538474 0.842525 + outer loop + vertex 64.6873 39.5033 359.681 + vertex 42.5816 34.6448 356.944 + vertex 63.9938 35.1995 356.941 + endloop + endfacet + facet normal 0.0164499 -0.620469 0.784059 + outer loop + vertex 63.8865 30.4757 353.645 + vertex 43.6208 25.1702 349.872 + vertex 65.1265 25.7376 349.87 + endloop + endfacet + facet normal 0.0281963 -0.572453 0.819452 + outer loop + vertex 85.4979 36.0047 356.946 + vertex 85.4436 31.276 353.645 + vertex 107.074 37.0642 356.944 + endloop + endfacet + facet normal 0.0264841 -0.537537 0.842824 + outer loop + vertex 107.653 41.3841 359.681 + vertex 85.4979 36.0047 356.946 + vertex 107.074 37.0642 356.944 + endloop + endfacet + facet normal 0.0309525 -0.620083 0.783925 + outer loop + vertex 107.034 32.3365 353.643 + vertex 86.696 26.5513 349.87 + vertex 108.252 27.6275 349.871 + endloop + endfacet + facet normal 0.0422646 -0.571962 0.819191 + outer loop + vertex 128.639 38.3896 356.943 + vertex 128.578 33.6609 353.644 + vertex 150.112 39.974 356.941 + endloop + endfacet + facet normal 0.0396665 -0.536727 0.842823 + outer loop + vertex 150.643 44.2981 359.67 + vertex 128.639 38.3896 356.943 + vertex 150.112 39.974 356.941 + endloop + endfacet + facet normal 0.0462868 -0.619243 0.783834 + outer loop + vertex 150.045 35.2486 353.64 + vertex 129.766 28.9663 349.874 + vertex 151.231 30.5685 349.873 + endloop + endfacet + facet normal 0.0558858 -0.57087 0.819136 + outer loop + vertex 171.47 41.8094 356.936 + vertex 171.356 37.0775 353.646 + vertex 192.729 43.8957 356.94 + endloop + endfacet + facet normal 0.0525575 -0.536996 0.841946 + outer loop + vertex 193.289 48.2467 359.68 + vertex 171.47 41.8094 356.936 + vertex 192.729 43.8957 356.94 + endloop + endfacet + facet normal 0.0610177 -0.61803 0.783783 + outer loop + vertex 192.606 39.1626 353.645 + vertex 172.532 32.4068 349.88 + vertex 193.774 34.4983 349.876 + endloop + endfacet + facet normal 0.0690683 -0.570426 0.81844 + outer loop + vertex 213.997 46.2384 356.945 + vertex 213.867 41.4916 353.647 + vertex 235.362 48.8323 356.95 + endloop + endfacet + facet normal 0.0649612 -0.536638 0.841308 + outer loop + vertex 235.863 53.1896 359.69 + vertex 213.997 46.2384 356.945 + vertex 235.362 48.8323 356.95 + endloop + endfacet + facet normal 0.0651184 -0.537029 0.841046 + outer loop + vertex 214.512 50.5788 359.676 + vertex 213.997 46.2384 356.945 + vertex 235.863 53.1896 359.69 + endloop + endfacet + facet normal 0.0591923 -0.537407 0.841243 + outer loop + vertex 193.289 48.2467 359.68 + vertex 192.729 43.8957 356.94 + vertex 214.512 50.5788 359.676 + endloop + endfacet + facet normal 0.0528488 -0.537766 0.841436 + outer loop + vertex 172.013 46.1537 359.679 + vertex 171.47 41.8094 356.936 + vertex 193.289 48.2467 359.68 + endloop + endfacet + facet normal 0.0463069 -0.537157 0.84221 + outer loop + vertex 150.643 44.2981 359.67 + vertex 150.112 39.974 356.941 + vertex 172.013 46.1537 359.679 + endloop + endfacet + facet normal 0.04001 -0.537709 0.84218 + outer loop + vertex 129.199 42.7123 359.676 + vertex 128.639 38.3896 356.943 + vertex 150.643 44.2981 359.67 + endloop + endfacet + facet normal 0.0333564 -0.538083 0.842232 + outer loop + vertex 107.653 41.3841 359.681 + vertex 107.074 37.0642 356.944 + vertex 129.199 42.7123 359.676 + endloop + endfacet + facet normal 0.026717 -0.538259 0.842356 + outer loop + vertex 86.1331 40.3103 359.677 + vertex 85.4979 36.0047 356.946 + vertex 107.653 41.3841 359.681 + endloop + endfacet + facet normal 0.0204115 -0.539143 0.841967 + outer loop + vertex 64.6873 39.5033 359.681 + vertex 63.9938 35.1995 356.941 + vertex 86.1331 40.3103 359.677 + endloop + endfacet + facet normal 0.0139966 -0.538269 0.842657 + outer loop + vertex 43.1936 38.9321 359.673 + vertex 42.5816 34.6448 356.944 + vertex 64.6873 39.5033 359.681 + endloop + endfacet + facet normal 0.00835451 -0.539061 0.842225 + outer loop + vertex 21.7207 38.5986 359.672 + vertex 21.2386 34.3163 356.936 + vertex 43.1936 38.9321 359.673 + endloop + endfacet + facet normal 0.00284427 -0.539073 0.842254 + outer loop + vertex 0.416727 38.5025 359.683 + vertex -0.0835181 34.2182 356.942 + vertex 21.7207 38.5986 359.672 + endloop + endfacet + facet normal -0.00274223 -0.539062 0.842261 + outer loop + vertex -20.8377 38.6087 359.682 + vertex -21.4478 34.3337 356.943 + vertex 0.416727 38.5025 359.683 + endloop + endfacet + facet normal -0.00805713 -0.539487 0.841955 + outer loop + vertex -42.1599 38.9248 359.68 + vertex -42.9054 34.6612 356.941 + vertex -20.8377 38.6087 359.682 + endloop + endfacet + facet normal -0.0137125 -0.539119 0.842118 + outer loop + vertex -63.6081 39.4652 359.677 + vertex -64.4225 35.2137 356.942 + vertex -42.1599 38.9248 359.68 + endloop + endfacet + facet normal -0.0198696 -0.539225 0.841927 + outer loop + vertex -85.1425 40.2546 359.674 + vertex -85.8876 36.0061 356.935 + vertex -63.6081 39.4652 359.677 + endloop + endfacet + facet normal -0.0263146 -0.538646 0.842121 + outer loop + vertex -106.571 41.3069 359.678 + vertex -107.24 37.0609 356.941 + vertex -85.1425 40.2546 359.674 + endloop + endfacet + facet normal -0.0331203 -0.538701 0.841846 + outer loop + vertex -127.78 42.6156 359.681 + vertex -128.457 38.3766 356.941 + vertex -106.571 41.3069 359.678 + endloop + endfacet + facet normal -0.0396398 -0.538278 0.841835 + outer loop + vertex -148.898 44.1889 359.692 + vertex -149.638 39.954 356.949 + vertex -127.78 42.6156 359.681 + endloop + endfacet + facet normal -0.046132 -0.537956 0.84171 + outer loop + vertex -170.156 46.002 359.686 + vertex -170.854 41.7778 356.948 + vertex -148.898 44.1889 359.692 + endloop + endfacet + facet normal -0.0524147 -0.537519 0.841621 + outer loop + vertex -191.458 48.0672 359.678 + vertex -192.127 43.8449 356.94 + vertex -170.156 46.002 359.686 + endloop + endfacet + facet normal -0.0586171 -0.536665 0.841757 + outer loop + vertex -212.812 50.4078 359.683 + vertex -213.479 46.1673 356.933 + vertex -191.458 48.0672 359.678 + endloop + endfacet + facet normal -0.0646473 -0.537095 0.841041 + outer loop + vertex -234.275 52.9865 359.68 + vertex -234.93 48.7387 356.917 + vertex -212.812 50.4078 359.683 + endloop + endfacet + facet normal -0.0698458 -0.538202 0.839917 + outer loop + vertex -255.569 55.7338 359.67 + vertex -256.334 51.5166 356.904 + vertex -234.275 52.9865 359.68 + endloop + endfacet + facet normal -0.0750764 -0.538042 0.839568 + outer loop + vertex -276.594 58.6316 359.647 + vertex -277.441 54.4444 356.888 + vertex -255.569 55.7338 359.67 + endloop + endfacet + facet normal -0.0814233 -0.537079 0.839593 + outer loop + vertex -297.804 61.8248 359.633 + vertex -298.372 57.5776 356.861 + vertex -276.594 58.6316 359.647 + endloop + endfacet + facet normal -0.0907886 -0.534638 0.84019 + outer loop + vertex -320.079 65.6124 359.636 + vertex -319.966 61.1693 356.821 + vertex -297.804 61.8248 359.633 + endloop + endfacet + facet normal -0.101069 -0.539623 0.835818 + outer loop + vertex -344.407 70.3954 359.782 + vertex -343.293 65.5791 356.807 + vertex -320.079 65.6124 359.636 + endloop + endfacet + facet normal -0.110179 -0.565542 0.817327 + outer loop + vertex -360.587 72.7796 359.251 + vertex -367.607 70.9277 357.023 + vertex -344.407 70.3954 359.782 + endloop + endfacet + facet normal -0.122645 -0.538181 0.833858 + outer loop + vertex -360.587 72.7796 359.251 + vertex -371.576 74.9707 359.049 + vertex -367.607 70.9277 357.023 + endloop + endfacet + facet normal -0.127444 -0.502381 0.855202 + outer loop + vertex -372.395 77.6712 360.513 + vertex -384.272 78.0353 358.957 + vertex -371.576 74.9707 359.049 + endloop + endfacet + facet normal -0.128939 -0.485505 0.864673 + outer loop + vertex -372.292 79.8831 361.77 + vertex -385.465 80.8945 360.374 + vertex -372.395 77.6712 360.513 + endloop + endfacet + facet normal -0.104452 -0.497826 0.860964 + outer loop + vertex -360.611 76.9055 361.698 + vertex -358.613 74.5099 360.555 + vertex -342.919 73.909 362.111 + endloop + endfacet + facet normal -0.0963744 -0.513752 0.852508 + outer loop + vertex -342.569 76.3826 363.642 + vertex -342.919 73.909 362.111 + vertex -321.206 72.1359 363.497 + endloop + endfacet + facet normal -0.11764 -0.485435 0.866322 + outer loop + vertex -371.87 81.6243 362.803 + vertex -372.292 79.8831 361.77 + vertex -357.895 78.1271 362.741 + endloop + endfacet + facet normal -0.138005 -0.501741 0.853938 + outer loop + vertex -372.706 83.0351 363.497 + vertex -384.312 84.9618 362.754 + vertex -371.87 81.6243 362.803 + endloop + endfacet + facet normal -0.134991 -0.478237 0.867794 + outer loop + vertex -382.824 85.8005 363.447 + vertex -384.312 84.9618 362.754 + vertex -372.706 83.0351 363.497 + endloop + endfacet + facet normal -0.143173 -0.467474 0.872336 + outer loop + vertex -384.312 84.9618 362.754 + vertex -382.824 85.8005 363.447 + vertex -391.163 87.3721 362.921 + endloop + endfacet + facet normal -0.144399 -0.433596 0.889463 + outer loop + vertex -396.671 89.0984 362.868 + vertex -397.162 88.2077 362.354 + vertex -391.163 87.3721 362.921 + endloop + endfacet + facet normal -0.150318 -0.41761 0.896107 + outer loop + vertex -397.062 90.0897 363.264 + vertex -400.388 90.1304 362.725 + vertex -396.671 89.0984 362.868 + endloop + endfacet + facet normal -0.142685 -0.44297 0.885109 + outer loop + vertex -390.934 88.6951 363.623 + vertex -390.687 88.1285 363.379 + vertex -383.983 86.7119 363.751 + endloop + endfacet + facet normal -0.143441 -0.372349 0.916941 + outer loop + vertex -400.905 90.9965 363.032 + vertex -397.062 90.0897 363.264 + vertex -402.439 92.2161 363.287 + endloop + endfacet + facet normal -0.159597 -0.423056 0.891937 + outer loop + vertex -396.548 91.2518 363.91 + vertex -399.894 92.5355 363.92 + vertex -398.157 91.3594 363.673 + endloop + endfacet + facet normal -0.150726 -0.427254 0.891479 + outer loop + vertex -391.219 89.7045 364.069 + vertex -395.983 91.7475 364.243 + vertex -396.548 91.2518 363.91 + endloop + endfacet + facet normal -0.13921 -0.415484 0.898884 + outer loop + vertex -384.79 87.5175 364.034 + vertex -392.318 89.5971 363.829 + vertex -387.47 87.9726 363.829 + endloop + endfacet + facet normal -0.142746 -0.430742 0.891114 + outer loop + vertex -391.929 90.6095 364.393 + vertex -391.219 89.7045 364.069 + vertex -384.584 88.3278 364.466 + endloop + endfacet + facet normal -0.136269 -0.443218 0.885996 + outer loop + vertex -374.646 85.8831 364.772 + vertex -383.817 90.0337 365.438 + vertex -384.584 88.3278 364.466 + endloop + endfacet + facet normal -0.137715 -0.446141 0.884304 + outer loop + vertex -373.337 87.4806 365.782 + vertex -383.817 90.0337 365.438 + vertex -374.646 85.8831 364.772 + endloop + endfacet + facet normal -0.127151 -0.462015 0.87771 + outer loop + vertex -363.321 85.5956 366.241 + vertex -373.483 90.1735 367.178 + vertex -373.337 87.4806 365.782 + endloop + endfacet + facet normal -0.116143 -0.471498 0.874186 + outer loop + vertex -366.091 88.6821 367.537 + vertex -363.321 85.5956 366.241 + vertex -356.347 85.6977 367.222 + endloop + endfacet + facet normal -0.100182 -0.474392 0.874595 + outer loop + vertex -342.534 82.5783 367.112 + vertex -353.792 88.1183 368.828 + vertex -356.347 85.6977 367.222 + endloop + endfacet + facet normal -0.0887637 -0.471944 0.877149 + outer loop + vertex -326.605 80.0953 367.388 + vertex -342.534 82.5783 367.112 + vertex -330.01 77.1868 365.479 + endloop + endfacet + facet normal -0.0996116 -0.514371 0.851763 + outer loop + vertex -328.975 74.8591 364.311 + vertex -339.945 77.4483 364.592 + vertex -342.569 76.3826 363.642 + endloop + endfacet + facet normal -0.105335 -0.504773 0.856801 + outer loop + vertex -339.945 77.4483 364.592 + vertex -354.593 80.0527 364.326 + vertex -342.569 76.3826 363.642 + endloop + endfacet + facet normal -0.102279 -0.486469 0.867691 + outer loop + vertex -354.593 80.0527 364.326 + vertex -339.945 77.4483 364.592 + vertex -349.308 81.1655 365.572 + endloop + endfacet + facet normal -0.0825716 -0.469079 0.879288 + outer loop + vertex -312.068 74.4711 365.715 + vertex -330.01 77.1868 365.479 + vertex -317.921 73.416 364.602 + endloop + endfacet + facet normal -0.0793675 -0.480588 0.873347 + outer loop + vertex -317.921 73.416 364.602 + vertex -304.209 70.8338 364.428 + vertex -312.068 74.4711 365.715 + endloop + endfacet + facet normal -0.0871785 -0.514406 0.853104 + outer loop + vertex -321.206 72.1359 363.497 + vertex -320.245 69.2275 361.842 + vertex -300.78 68.3003 363.272 + endloop + endfacet + facet normal -0.0760989 -0.481917 0.872906 + outer loop + vertex -304.209 70.8338 364.428 + vertex -289.644 68.1802 364.232 + vertex -292.392 71.1159 365.614 + endloop + endfacet + facet normal -0.078322 -0.510045 0.856574 + outer loop + vertex -300.78 68.3003 363.272 + vertex -298.162 65.3979 361.783 + vertex -279.535 65.3051 363.431 + endloop + endfacet + facet normal -0.0726695 -0.479475 0.874541 + outer loop + vertex -289.644 68.1802 364.232 + vertex -278.574 67.198 364.614 + vertex -292.392 71.1159 365.614 + endloop + endfacet + facet normal -0.0684806 -0.483433 0.872698 + outer loop + vertex -278.574 67.198 364.614 + vertex -264.878 65.0051 364.474 + vertex -273.631 68.6795 365.822 + endloop + endfacet + facet normal -0.0716961 -0.509551 0.857448 + outer loop + vertex -279.535 65.3051 363.431 + vertex -276.688 62.169 361.805 + vertex -257.535 62.21 363.431 + endloop + endfacet + facet normal -0.0667816 -0.484285 0.872358 + outer loop + vertex -264.878 65.0051 364.474 + vertex -253.524 63.3095 364.402 + vertex -254.189 65.5397 365.589 + endloop + endfacet + facet normal -0.0629327 -0.483517 0.87307 + outer loop + vertex -253.524 63.3095 364.402 + vertex -242.725 61.8363 364.364 + vertex -254.189 65.5397 365.589 + endloop + endfacet + facet normal -0.0671344 -0.510749 0.857105 + outer loop + vertex -257.535 62.21 363.431 + vertex -255.737 59.2472 361.807 + vertex -238.12 59.4083 363.282 + endloop + endfacet + facet normal -0.0617974 -0.48974 0.869676 + outer loop + vertex -242.725 61.8363 364.364 + vertex -228.344 59.7629 364.218 + vertex -232.901 62.7333 365.567 + endloop + endfacet + facet normal -0.0624457 -0.511988 0.85672 + outer loop + vertex -238.12 59.4083 363.282 + vertex -234.839 56.5494 361.813 + vertex -217.342 57.1272 363.434 + endloop + endfacet + facet normal -0.0599634 -0.487544 0.871037 + outer loop + vertex -228.344 59.7629 364.218 + vertex -217.767 59.1145 364.584 + vertex -232.901 62.7333 365.567 + endloop + endfacet + facet normal -0.0554361 -0.488006 0.871078 + outer loop + vertex -217.767 59.1145 364.584 + vertex -203.695 57.262 364.441 + vertex -214.173 60.8029 365.758 + endloop + endfacet + facet normal -0.0573 -0.511689 0.857258 + outer loop + vertex -217.342 57.1272 363.434 + vertex -213.339 53.9848 361.826 + vertex -194.845 54.5903 363.423 + endloop + endfacet + facet normal -0.0530611 -0.486097 0.872293 + outer loop + vertex -203.695 57.262 364.441 + vertex -192.121 55.8871 364.379 + vertex -194.845 58.331 365.575 + endloop + endfacet + facet normal -0.0473785 -0.481239 0.875308 + outer loop + vertex -192.121 55.8871 364.379 + vertex -181.287 54.8394 364.39 + vertex -194.845 58.331 365.575 + endloop + endfacet + facet normal -0.0512662 -0.51394 0.856293 + outer loop + vertex -194.845 54.5903 363.423 + vertex -191.981 51.5913 361.795 + vertex -174.625 52.3386 363.282 + endloop + endfacet + facet normal -0.045626 -0.490523 0.870233 + outer loop + vertex -181.287 54.8394 364.39 + vertex -164.165 53.2497 364.391 + vertex -176.048 56.7305 365.73 + endloop + endfacet + facet normal -0.045268 -0.512971 0.857212 + outer loop + vertex -174.625 52.3386 363.282 + vertex -170.797 49.5181 361.797 + vertex -153.451 50.6934 363.416 + endloop + endfacet + facet normal -0.0426494 -0.487727 0.871954 + outer loop + vertex -164.165 53.2497 364.391 + vertex -152.296 52.1933 364.381 + vertex -155.963 54.6454 365.573 + endloop + endfacet + facet normal -0.0370699 -0.481253 0.875798 + outer loop + vertex -152.296 52.1933 364.381 + vertex -141.568 51.4791 364.442 + vertex -155.963 54.6454 365.573 + endloop + endfacet + facet normal -0.0390783 -0.513179 0.857392 + outer loop + vertex -153.451 50.6934 363.416 + vertex -149.398 47.7091 361.814 + vertex -131.039 48.9969 363.422 + endloop + endfacet + facet normal -0.0356258 -0.489028 0.87154 + outer loop + vertex -141.568 51.4791 364.442 + vertex -127.466 50.7009 364.582 + vertex -137.649 53.5602 365.77 + endloop + endfacet + facet normal -0.0306188 -0.489273 0.871593 + outer loop + vertex -127.466 50.7009 364.582 + vertex -116.411 49.3404 364.207 + vertex -117.83 51.8668 365.575 + endloop + endfacet + facet normal -0.0328645 -0.514619 0.856789 + outer loop + vertex -131.039 48.9969 363.422 + vertex -128.25 46.1042 361.791 + vertex -111.118 47.4428 363.253 + endloop + endfacet + facet normal -0.0276278 -0.488026 0.872392 + outer loop + vertex -116.411 49.3404 364.207 + vertex -102.22 48.8666 364.391 + vertex -117.83 51.8668 365.575 + endloop + endfacet + facet normal -0.0264792 -0.513522 0.857668 + outer loop + vertex -111.118 47.4428 363.253 + vertex -107.196 44.7938 361.788 + vertex -89.6435 46.577 363.397 + endloop + endfacet + facet normal -0.0247525 -0.491517 0.870516 + outer loop + vertex -102.22 48.8666 364.391 + vertex -87.8516 48.44 364.559 + vertex -98.6705 51.078 365.741 + endloop + endfacet + facet normal -0.0195815 -0.490573 0.87118 + outer loop + vertex -87.8516 48.44 364.559 + vertex -76.3437 47.3859 364.224 + vertex -79.16 49.8863 365.569 + endloop + endfacet + facet normal -0.0198825 -0.51381 0.857674 + outer loop + vertex -89.6435 46.577 363.397 + vertex -85.5638 43.7528 361.8 + vertex -66.6263 45.7013 363.406 + endloop + endfacet + facet normal -0.0177711 -0.489023 0.87209 + outer loop + vertex -76.3437 47.3859 364.224 + vertex -65.4449 47.559 364.543 + vertex -79.16 49.8863 365.569 + endloop + endfacet + facet normal -0.013038 -0.490157 0.871536 + outer loop + vertex -65.4449 47.559 364.543 + vertex -51.539 46.9593 364.414 + vertex -60.8032 49.5466 365.731 + endloop + endfacet + facet normal -0.0136587 -0.514841 0.857177 + outer loop + vertex -66.6263 45.7013 363.406 + vertex -63.5953 42.9382 361.795 + vertex -43.7802 45.0861 363.401 + endloop + endfacet + facet normal -0.011393 -0.488185 0.872666 + outer loop + vertex -51.539 46.9593 364.414 + vertex -39.7696 46.5967 364.365 + vertex -41.4373 48.7902 365.57 + endloop + endfacet + facet normal -0.00668362 -0.485464 0.874231 + outer loop + vertex -39.7696 46.5967 364.365 + vertex -28.8864 46.5039 364.396 + vertex -41.4373 48.7902 365.57 + endloop + endfacet + facet normal -0.00822082 -0.515016 0.857141 + outer loop + vertex -43.7802 45.0861 363.401 + vertex -42.058 42.379 361.791 + vertex -23.6014 44.5812 363.291 + endloop + endfacet + facet normal -0.00466174 -0.493288 0.869854 + outer loop + vertex -28.8864 46.5039 364.396 + vertex -11.7794 46.3865 364.422 + vertex -22.2687 48.8264 365.749 + endloop + endfacet + facet normal -0.003311 -0.514521 0.857471 + outer loop + vertex -23.6014 44.5812 363.291 + vertex -21.0046 42.0723 361.796 + vertex -2.6198 44.6615 363.42 + endloop + endfacet + facet normal -0.00236805 -0.4895 0.872 + outer loop + vertex -11.7794 46.3865 364.422 + vertex 0.0830764 46.3066 364.409 + vertex -2.21693 48.4338 365.597 + endloop + endfacet + facet normal 0.00219736 -0.485738 0.874102 + outer loop + vertex 0.0830764 46.3066 364.409 + vertex 10.9637 46.3688 364.416 + vertex -2.21693 48.4338 365.597 + endloop + endfacet + facet normal 0.00187246 -0.514521 0.857476 + outer loop + vertex -2.6198 44.6615 363.42 + vertex -0.0646938 41.9684 361.799 + vertex 17.2225 44.5106 363.286 + endloop + endfacet + facet normal 0.00449811 -0.492495 0.870304 + outer loop + vertex 10.9637 46.3688 364.416 + vertex 28.0731 46.4904 364.397 + vertex 16.766 48.7779 365.749 + endloop + endfacet + facet normal 0.00670532 -0.513047 0.858334 + outer loop + vertex 17.2225 44.5106 363.286 + vertex 20.9703 42.059 361.792 + vertex 38.5283 44.9808 363.401 + endloop + endfacet + facet normal 0.00699022 -0.489705 0.87186 + outer loop + vertex 28.0731 46.4904 364.397 + vertex 39.8685 46.6075 364.368 + vertex 36.8233 48.6922 365.563 + endloop + endfacet + facet normal 0.0112162 -0.485009 0.874437 + outer loop + vertex 39.8685 46.6075 364.368 + vertex 50.8 46.9457 364.415 + vertex 36.8233 48.6922 365.563 + endloop + endfacet + facet normal 0.0124223 -0.513712 0.857873 + outer loop + vertex 38.5283 44.9808 363.401 + vertex 42.59 42.3967 361.795 + vertex 61.5707 45.5508 363.409 + endloop + endfacet + facet normal 0.0131135 -0.491442 0.870811 + outer loop + vertex 50.8 46.9457 364.415 + vertex 65.0033 47.566 364.551 + vertex 55.2526 49.4075 365.737 + endloop + endfacet + facet normal 0.0174953 -0.491119 0.870917 + outer loop + vertex 65.0033 47.566 364.551 + vertex 76.0279 47.3777 364.224 + vertex 74.5295 49.7069 365.567 + endloop + endfacet + facet normal 0.0185059 -0.514187 0.857478 + outer loop + vertex 61.5707 45.5508 363.409 + vertex 64.5847 42.9774 361.8 + vertex 84.4248 46.3616 363.402 + endloop + endfacet + facet normal 0.0193026 -0.490224 0.871382 + outer loop + vertex 76.0279 47.3777 364.224 + vertex 87.3479 48.4099 364.554 + vertex 74.5295 49.7069 365.567 + endloop + endfacet + facet normal 0.0245256 -0.490804 0.870925 + outer loop + vertex 87.3479 48.4099 364.554 + vertex 101.279 48.8108 364.387 + vertex 93.1248 50.8119 365.745 + endloop + endfacet + facet normal 0.0249557 -0.51566 0.856429 + outer loop + vertex 84.4248 46.3616 363.402 + vertex 86.1146 43.7598 361.786 + vertex 104.759 47.0983 363.253 + endloop + endfacet + facet normal 0.0276111 -0.491881 0.870225 + outer loop + vertex 101.279 48.8108 364.387 + vertex 116.005 49.3165 364.206 + vertex 113.221 51.5775 365.572 + endloop + endfacet + facet normal 0.0310504 -0.514412 0.856981 + outer loop + vertex 104.759 47.0983 363.253 + vertex 107.446 44.8303 361.794 + vertex 126.156 48.6599 363.415 + endloop + endfacet + facet normal 0.0303307 -0.489342 0.871564 + outer loop + vertex 116.005 49.3165 364.206 + vertex 127.161 50.6737 364.58 + vertex 113.221 51.5775 365.572 + endloop + endfacet + facet normal 0.0354832 -0.490297 0.870833 + outer loop + vertex 127.161 50.6737 364.58 + vertex 141.053 51.4307 364.44 + vertex 132.132 53.1259 365.758 + endloop + endfacet + facet normal 0.0375624 -0.514174 0.856863 + outer loop + vertex 126.156 48.6599 363.415 + vertex 129.073 46.2008 361.811 + vertex 148.618 50.2993 363.414 + endloop + endfacet + facet normal 0.0373561 -0.486599 0.872826 + outer loop + vertex 141.053 51.4307 364.44 + vertex 152.591 52.2064 364.378 + vertex 151.246 54.2627 365.582 + endloop + endfacet + facet normal 0.0425989 -0.483906 0.874083 + outer loop + vertex 152.591 52.2064 364.378 + vertex 163.392 53.1935 364.398 + vertex 151.246 54.2627 365.582 + endloop + endfacet + facet normal 0.0440355 -0.514687 0.856247 + outer loop + vertex 148.618 50.2993 363.414 + vertex 150.45 47.7543 361.79 + vertex 168.65 51.7956 363.283 + endloop + endfacet + facet normal 0.0457594 -0.491972 0.869408 + outer loop + vertex 163.392 53.1935 364.398 + vertex 180.562 54.8129 364.411 + vertex 170.295 56.2225 365.749 + endloop + endfacet + facet normal 0.0494425 -0.512874 0.857039 + outer loop + vertex 168.65 51.7956 363.283 + vertex 171.599 49.5837 361.789 + vertex 189.912 54.0865 363.427 + endloop + endfacet + facet normal 0.0476408 -0.485884 0.872724 + outer loop + vertex 180.562 54.8129 364.411 + vertex 192.453 55.958 364.4 + vertex 190.493 57.8864 365.58 + endloop + endfacet + facet normal 0.0521926 -0.482311 0.874444 + outer loop + vertex 192.453 55.958 364.4 + vertex 202.931 57.1159 364.413 + vertex 190.493 57.8864 365.58 + endloop + endfacet + facet normal 0.0553866 -0.512444 0.856933 + outer loop + vertex 189.912 54.0865 363.427 + vertex 192.922 51.7163 361.815 + vertex 211.28 56.3973 363.428 + endloop + endfacet + facet normal 0.0538559 -0.486083 0.872252 + outer loop + vertex 202.931 57.1159 364.413 + vertex 214.01 58.3198 364.4 + vertex 211.106 60.1029 365.573 + endloop + endfacet + facet normal 0.0583254 -0.480608 0.874994 + outer loop + vertex 214.01 58.3198 364.4 + vertex 224.66 59.6418 364.416 + vertex 211.106 60.1029 365.573 + endloop + endfacet + facet normal 0.0612661 -0.5128 0.856319 + outer loop + vertex 211.28 56.3973 363.428 + vertex 213.983 53.9935 361.795 + vertex 231.304 58.5623 363.292 + endloop + endfacet + facet normal 0.0615529 -0.48979 0.869665 + outer loop + vertex 224.66 59.6418 364.416 + vertex 241.897 61.7872 364.404 + vertex 230.008 62.6955 365.757 + endloop + endfacet + facet normal 0.0664789 -0.511803 0.856527 + outer loop + vertex 231.304 58.5623 363.292 + vertex 235.088 56.5469 361.794 + vertex 252.552 61.5333 363.418 + endloop + endfacet + facet normal 0.0637526 -0.486878 0.87114 + outer loop + vertex 241.897 61.7872 364.404 + vertex 253.812 63.3116 364.384 + vertex 250.115 64.9732 365.583 + endloop + endfacet + facet normal 0.0671996 -0.481267 0.873994 + outer loop + vertex 253.812 63.3116 364.384 + vertex 264.518 64.8955 364.433 + vertex 250.115 64.9732 365.583 + endloop + endfacet + facet normal 0.0714288 -0.510763 0.856749 + outer loop + vertex 252.552 61.5333 363.418 + vertex 256.609 59.4175 361.818 + vertex 274.887 64.6476 363.413 + endloop + endfacet + facet normal 0.0697725 -0.488444 0.869801 + outer loop + vertex 264.518 64.8955 364.433 + vertex 278.36 67.1114 364.567 + vertex 268.284 67.7727 365.747 + endloop + endfacet + facet normal 0.073427 -0.488048 0.869723 + outer loop + vertex 278.36 67.1114 364.567 + vertex 289.207 68.0574 364.182 + vertex 287.584 70.2474 365.548 + endloop + endfacet + facet normal 0.0757708 -0.486668 0.870295 + outer loop + vertex 289.207 68.0574 364.182 + vertex 302.982 70.5315 364.366 + vertex 287.584 70.2474 365.548 + endloop + endfacet + facet normal 0.0843413 -0.509632 0.856249 + outer loop + vertex 316.919 73.1798 364.57 + vertex 302.982 70.5315 364.366 + vertex 315.739 70.9838 363.379 + endloop + endfacet + facet normal 0.0856989 -0.516089 0.852237 + outer loop + vertex 315.739 70.9838 363.379 + vertex 298.682 65.4762 361.759 + vertex 320.459 69.0566 361.737 + endloop + endfacet + facet normal 0.0762437 -0.510489 0.856497 + outer loop + vertex 274.887 64.6476 363.413 + vertex 277.77 62.3567 361.79 + vertex 294.599 67.2984 363.238 + endloop + endfacet + facet normal 0.0731459 -0.51827 0.852083 + outer loop + vertex 277.77 62.3567 361.79 + vertex 257.25 56.0084 359.691 + vertex 278.506 58.988 359.678 + endloop + endfacet + facet normal 0.075619 -0.535959 0.84085 + outer loop + vertex 257.25 56.0084 359.691 + vertex 256.774 51.639 356.948 + vertex 278.506 58.988 359.678 + endloop + endfacet + facet normal 0.0742449 -0.568746 0.819155 + outer loop + vertex 256.774 51.639 356.948 + vertex 235.24 44.0638 353.641 + vertex 256.641 46.852 353.637 + endloop + endfacet + facet normal 0.0794994 -0.613249 0.785879 + outer loop + vertex 256.641 46.852 353.637 + vertex 236.394 39.377 349.852 + vertex 257.716 42.1737 349.877 + endloop + endfacet + facet normal 0.0845018 -0.56533 0.820525 + outer loop + vertex 299.236 57.7491 356.904 + vertex 277.941 49.8507 353.655 + vertex 299.116 53.0497 353.679 + endloop + endfacet + facet normal 0.0802842 -0.533585 0.841927 + outer loop + vertex 299.692 62.141 359.644 + vertex 278.095 54.6142 356.933 + vertex 299.236 57.7491 356.904 + endloop + endfacet + facet normal 0.0855193 -0.514992 0.852918 + outer loop + vertex 298.682 65.4762 361.759 + vertex 299.692 62.141 359.644 + vertex 320.459 69.0566 361.737 + endloop + endfacet + facet normal 0.0929099 -0.503953 0.85872 + outer loop + vertex 315.739 70.9838 363.379 + vertex 320.459 69.0566 361.737 + vertex 340.788 75.646 363.405 + endloop + endfacet + facet normal 0.129283 -0.467681 0.874392 + outer loop + vertex 384.631 84.6966 362.562 + vertex 372.407 80.0547 361.886 + vertex 384.586 82.5459 361.418 + endloop + endfacet + facet normal 0.115655 -0.471652 0.874167 + outer loop + vertex 358.459 78.7654 363.058 + vertex 361.148 77.9069 362.239 + vertex 372.27 81.8693 362.906 + endloop + endfacet + facet normal 0.117627 -0.493129 0.861967 + outer loop + vertex 372.407 80.0547 361.886 + vertex 358.32 75.0042 360.919 + vertex 372.47 77.6405 360.496 + endloop + endfacet + facet normal 0.103964 -0.49648 0.8618 + outer loop + vertex 361.148 77.9069 362.239 + vertex 358.459 78.7654 363.058 + vertex 343.232 73.0964 361.629 + endloop + endfacet + facet normal 0.0931229 -0.50809 0.856255 + outer loop + vertex 343.232 73.0964 361.629 + vertex 320.779 65.4585 359.539 + vertex 340.62 68.6532 359.277 + endloop + endfacet + facet normal 0.121627 -0.51694 0.847337 + outer loop + vertex 358.32 75.0042 360.919 + vertex 359.268 71.9857 358.942 + vertex 372.47 77.6405 360.496 + endloop + endfacet + facet normal 0.101681 -0.543339 0.833333 + outer loop + vertex 340.62 68.6532 359.277 + vertex 320.183 61.048 356.812 + vertex 341.609 64.7309 356.599 + endloop + endfacet + facet normal 0.116239 -0.561948 0.818965 + outer loop + vertex 366.692 69.7485 356.399 + vertex 342.942 60.3711 353.335 + vertex 363.691 63.7454 352.706 + endloop + endfacet + facet normal 0.106079 -0.569993 0.814773 + outer loop + vertex 320.183 61.048 356.812 + vertex 320.614 56.5228 353.59 + vertex 341.609 64.7309 356.599 + endloop + endfacet + facet normal 0.103674 -0.612195 0.783881 + outer loop + vertex 320.614 56.5228 353.59 + vertex 300.052 48.514 350.055 + vertex 321.83 51.9677 349.872 + endloop + endfacet + facet normal 0.122431 -0.563731 0.816834 + outer loop + vertex 366.692 69.7485 356.399 + vertex 363.691 63.7454 352.706 + vertex 380.75 70.452 354.777 + endloop + endfacet + facet normal 0.123129 -0.537271 0.834373 + outer loop + vertex 383.99 74.0551 356.619 + vertex 366.692 69.7485 356.399 + vertex 380.75 70.452 354.777 + endloop + endfacet + facet normal 0.13484 -0.606941 0.783225 + outer loop + vertex 380.688 66.4547 351.954 + vertex 364.956 59.046 348.921 + vertex 383.821 62.7985 348.581 + endloop + endfacet + facet normal 0.140551 -0.573899 0.806775 + outer loop + vertex 392.125 72.0103 353.987 + vertex 393.486 68.8551 351.505 + vertex 399.728 72.9528 353.333 + endloop + endfacet + facet normal 0.170723 -0.540796 0.823646 + outer loop + vertex 403.555 75.5159 354.305 + vertex 404.384 72.7732 352.333 + vertex 408.492 75.8224 353.483 + endloop + endfacet + facet normal 0.13807 -0.535626 0.833092 + outer loop + vertex 399.337 75.8838 355.282 + vertex 392.125 72.0103 353.987 + vertex 399.728 72.9528 353.333 + endloop + endfacet + facet normal 0.172323 -0.501102 0.848058 + outer loop + vertex 404.011 79.0232 356.285 + vertex 403.555 75.5159 354.305 + vertex 408.492 75.8224 353.483 + endloop + endfacet + facet normal 0.171098 -0.502375 0.847552 + outer loop + vertex 408.492 75.8224 353.483 + vertex 408.813 81.2937 356.662 + vertex 404.011 79.0232 356.285 + endloop + endfacet + facet normal 0.155228 -0.503 0.850233 + outer loop + vertex 408.492 75.8224 353.483 + vertex 416.063 77.6543 353.185 + vertex 408.813 81.2937 356.662 + endloop + endfacet + facet normal 0.152227 -0.507143 0.848312 + outer loop + vertex 408.813 81.2937 356.662 + vertex 416.063 77.6543 353.185 + vertex 416.302 82.712 356.166 + endloop + endfacet + facet normal 0.152852 -0.507116 0.848216 + outer loop + vertex 416.063 77.6543 353.185 + vertex 425.621 79.137 352.349 + vertex 416.302 82.712 356.166 + endloop + endfacet + facet normal 0.145917 -0.518881 0.842301 + outer loop + vertex 416.302 82.712 356.166 + vertex 425.621 79.137 352.349 + vertex 426.674 83.3291 354.749 + endloop + endfacet + facet normal 0.156781 -0.52007 0.839611 + outer loop + vertex 425.621 79.137 352.349 + vertex 436.414 80.7306 351.321 + vertex 426.674 83.3291 354.749 + endloop + endfacet + facet normal 0.153371 -0.527528 0.835578 + outer loop + vertex 426.674 83.3291 354.749 + vertex 436.414 80.7306 351.321 + vertex 437.005 84.7008 353.719 + endloop + endfacet + facet normal 0.164405 -0.527799 0.833306 + outer loop + vertex 436.414 80.7306 351.321 + vertex 447.497 82.6676 350.361 + vertex 437.005 84.7008 353.719 + endloop + endfacet + facet normal 0.160309 -0.538698 0.827107 + outer loop + vertex 437.005 84.7008 353.719 + vertex 447.497 82.6676 350.361 + vertex 447.685 86.4989 352.82 + endloop + endfacet + facet normal 0.170095 -0.538152 0.825506 + outer loop + vertex 447.497 82.6676 350.361 + vertex 458.885 84.9113 349.477 + vertex 447.685 86.4989 352.82 + endloop + endfacet + facet normal 0.164542 -0.555442 0.815113 + outer loop + vertex 447.685 86.4989 352.82 + vertex 458.885 84.9113 349.477 + vertex 458.924 88.6263 352.001 + endloop + endfacet + facet normal 0.171635 -0.554813 0.814078 + outer loop + vertex 458.885 84.9113 349.477 + vertex 470.544 87.4833 348.772 + vertex 458.924 88.6263 352.001 + endloop + endfacet + facet normal 0.16709 -0.571298 0.803555 + outer loop + vertex 458.924 88.6263 352.001 + vertex 470.544 87.4833 348.772 + vertex 470.42 91.1098 351.376 + endloop + endfacet + facet normal 0.170588 -0.570869 0.803124 + outer loop + vertex 470.544 87.4833 348.772 + vertex 481.541 90.3881 348.501 + vertex 470.42 91.1098 351.376 + endloop + endfacet + facet normal 0.168264 -0.580634 0.796587 + outer loop + vertex 470.42 91.1098 351.376 + vertex 481.541 90.3881 348.501 + vertex 481.048 93.8652 351.139 + endloop + endfacet + facet normal 0.167947 -0.580696 0.796609 + outer loop + vertex 481.541 90.3881 348.501 + vertex 490.257 93.4671 348.908 + vertex 481.048 93.8652 351.139 + endloop + endfacet + facet normal 0.169111 -0.575101 0.800412 + outer loop + vertex 481.048 93.8652 351.139 + vertex 490.257 93.4671 348.908 + vertex 488.785 96.3758 351.309 + endloop + endfacet + facet normal 0.166278 -0.576308 0.800138 + outer loop + vertex 488.785 96.3758 351.309 + vertex 490.257 93.4671 348.908 + vertex 495.94 96.9465 350.233 + endloop + endfacet + facet normal 0.188323 -0.602859 0.775304 + outer loop + vertex 496.893 92.7656 346.75 + vertex 495.94 96.9465 350.233 + vertex 490.257 93.4671 348.908 + endloop + endfacet + facet normal 0.152909 -0.611674 0.776192 + outer loop + vertex 496.893 92.7656 346.75 + vertex 500.407 95.1439 347.932 + vertex 495.94 96.9465 350.233 + endloop + endfacet + facet normal 0.16673 -0.592581 0.788066 + outer loop + vertex 495.94 96.9465 350.233 + vertex 500.407 95.1439 347.932 + vertex 500.327 99.1747 350.98 + endloop + endfacet + facet normal 0.169212 -0.475223 0.863441 + outer loop + vertex 404.011 79.0232 356.285 + vertex 404.689 83.2934 358.502 + vertex 402.452 81.6219 358.021 + endloop + endfacet + facet normal 0.15638 -0.460951 0.873538 + outer loop + vertex 402.67 84.5053 359.503 + vertex 402.452 81.6219 358.021 + vertex 404.689 83.2934 358.502 + endloop + endfacet + facet normal 0.156518 -0.47462 0.866163 + outer loop + vertex 404.689 83.2934 358.502 + vertex 404.011 79.0232 356.285 + vertex 408.813 81.2937 356.662 + endloop + endfacet + facet normal 0.14547 -0.461063 0.875362 + outer loop + vertex 402.67 84.5053 359.503 + vertex 399.133 81.5812 358.551 + vertex 402.452 81.6219 358.021 + endloop + endfacet + facet normal 0.138195 -0.500542 0.854611 + outer loop + vertex 399.106 78.7346 356.989 + vertex 392.357 75.1242 355.966 + vertex 399.337 75.8838 355.282 + endloop + endfacet + facet normal 0.134206 -0.544089 0.828225 + outer loop + vertex 383.99 74.0551 356.619 + vertex 380.75 70.452 354.777 + vertex 392.357 75.1242 355.966 + endloop + endfacet + facet normal 0.116763 -0.512535 0.85069 + outer loop + vertex 383.99 74.0551 356.619 + vertex 383.451 76.1551 357.959 + vertex 366.692 69.7485 356.399 + endloop + endfacet + facet normal 0.128455 -0.538724 0.832632 + outer loop + vertex 383.451 76.1551 357.959 + vertex 375.531 75.7961 358.948 + vertex 366.692 69.7485 356.399 + endloop + endfacet + facet normal 0.120044 -0.513827 0.849453 + outer loop + vertex 372.47 77.6405 360.496 + vertex 359.268 71.9857 358.942 + vertex 375.531 75.7961 358.948 + endloop + endfacet + facet normal 0.133678 -0.491803 0.860384 + outer loop + vertex 372.407 80.0547 361.886 + vertex 372.47 77.6405 360.496 + vertex 384.586 82.5459 361.418 + endloop + endfacet + facet normal 0.136328 -0.459195 0.877813 + outer loop + vertex 393.044 85.1895 361.487 + vertex 392.063 86.0433 362.086 + vertex 384.586 82.5459 361.418 + endloop + endfacet + facet normal 0.145935 -0.450307 0.880867 + outer loop + vertex 392.063 86.0433 362.086 + vertex 393.044 85.1895 361.487 + vertex 397.325 87.2071 361.809 + endloop + endfacet + facet normal 0.135999 -0.471951 0.871072 + outer loop + vertex 392.178 81.8143 359.822 + vertex 391.859 83.4919 360.781 + vertex 384.018 80.0917 360.163 + endloop + endfacet + facet normal 0.13786 -0.480458 0.866115 + outer loop + vertex 392.178 81.8143 359.822 + vertex 385.995 78.8628 359.169 + vertex 392.617 80.0365 358.766 + endloop + endfacet + facet normal 0.143637 -0.4859 0.862131 + outer loop + vertex 392.617 80.0365 358.766 + vertex 392.645 77.8125 357.508 + vertex 399.133 81.5812 358.551 + endloop + endfacet + facet normal 0.148399 -0.463123 0.873782 + outer loop + vertex 397.471 84.5251 360.402 + vertex 397.996 83.0423 359.527 + vertex 401.089 85.1574 360.123 + endloop + endfacet + facet normal 0.147193 -0.454025 0.878747 + outer loop + vertex 400.503 86.3613 360.843 + vertex 397.471 84.5251 360.402 + vertex 401.089 85.1574 360.123 + endloop + endfacet + facet normal 0.16495 -0.48013 0.861549 + outer loop + vertex 401.014 83.8265 359.442 + vertex 399.133 81.5812 358.551 + vertex 402.67 84.5053 359.503 + endloop + endfacet + facet normal 0.158572 -0.448881 0.87941 + outer loop + vertex 400.503 86.3613 360.843 + vertex 401.089 85.1574 360.123 + vertex 402.439 87.0295 360.835 + endloop + endfacet + facet normal 0.149217 -0.456923 0.876901 + outer loop + vertex 397.368 85.9597 361.167 + vertex 397.471 84.5251 360.402 + vertex 400.503 86.3613 360.843 + endloop + endfacet + facet normal 0.145272 -0.449022 0.881632 + outer loop + vertex 397.325 87.2071 361.809 + vertex 393.044 85.1895 361.487 + vertex 397.368 85.9597 361.167 + endloop + endfacet + facet normal 0.14455 -0.443122 0.884731 + outer loop + vertex 397.266 88.3152 362.374 + vertex 392.063 86.0433 362.086 + vertex 397.325 87.2071 361.809 + endloop + endfacet + facet normal 0.155829 -0.440566 0.884092 + outer loop + vertex 396.99 89.2223 362.875 + vertex 397.266 88.3152 362.374 + vertex 400.401 89.858 362.59 + endloop + endfacet + facet normal 0.163117 -0.434239 0.885906 + outer loop + vertex 400.257 88.7844 362.091 + vertex 400.671 87.7325 361.499 + vertex 402.35 89.4453 362.03 + endloop + endfacet + facet normal 0.155414 -0.383353 0.910432 + outer loop + vertex 403.337 92.4562 363.234 + vertex 397.798 91.1067 363.611 + vertex 399.092 90.9337 363.317 + endloop + endfacet + facet normal 0.146773 -0.421549 0.894849 + outer loop + vertex 391.968 88.9581 363.555 + vertex 399.092 90.9337 363.317 + vertex 397.798 91.1067 363.611 + endloop + endfacet + facet normal 0.143536 -0.412882 0.899403 + outer loop + vertex 397.798 91.1067 363.611 + vertex 389.155 88.5455 363.815 + vertex 391.968 88.9581 363.555 + endloop + endfacet + facet normal 0.163499 -0.423366 0.891083 + outer loop + vertex 399.557 90.4747 363.038 + vertex 400.401 89.858 362.59 + vertex 401.571 90.9404 362.89 + endloop + endfacet + facet normal 0.154756 -0.433073 0.887974 + outer loop + vertex 399.557 90.4747 363.038 + vertex 396.99 89.2223 362.875 + vertex 400.401 89.858 362.59 + endloop + endfacet + facet normal 0.146979 -0.44006 0.885858 + outer loop + vertex 391.58 87.8201 363.076 + vertex 393.04 87.4266 362.638 + vertex 396.99 89.2223 362.875 + endloop + endfacet + facet normal 0.138354 -0.448505 0.883007 + outer loop + vertex 391.533 88.417 363.386 + vertex 384.016 86.0274 363.35 + vertex 391.58 87.8201 363.076 + endloop + endfacet + facet normal 0.137083 -0.483321 0.864644 + outer loop + vertex 381.335 85.9999 363.76 + vertex 371.42 82.8442 363.568 + vertex 384.016 86.0274 363.35 + endloop + endfacet +endsolid diff --git a/noether_examples/meshes/outputsBackDoor/output_0.stl b/noether_examples/meshes/outputsBackDoor/output_0.stl new file mode 100644 index 00000000..892b1db9 --- /dev/null +++ b/noether_examples/meshes/outputsBackDoor/output_0.stl @@ -0,0 +1,57647 @@ +solid ascii + facet normal -0.84059 -0.0617856 0.538137 + outer loop + vertex 0.794666 1.38656 2.55282 + vertex 0.794836 1.38149 2.5525 + vertex 0.796677 1.38375 2.55564 + endloop + endfacet + facet normal -0.842509 -0.0667677 0.534528 + outer loop + vertex 0.796453 1.38887 2.55592 + vertex 0.794666 1.38656 2.55282 + vertex 0.796677 1.38375 2.55564 + endloop + endfacet + facet normal -0.784521 -0.0688279 0.616271 + outer loop + vertex 0.796677 1.38375 2.55564 + vertex 0.798735 1.38645 2.55856 + vertex 0.796453 1.38887 2.55592 + endloop + endfacet + facet normal -0.785404 -0.0711704 0.614878 + outer loop + vertex 0.798735 1.38645 2.55856 + vertex 0.798474 1.39147 2.5588 + vertex 0.796453 1.38887 2.55592 + endloop + endfacet + facet normal -0.790563 -0.0609993 0.609335 + outer loop + vertex 0.796453 1.38887 2.55592 + vertex 0.798474 1.39147 2.5588 + vertex 0.796214 1.39386 2.55611 + endloop + endfacet + facet normal -0.846585 -0.0606525 0.528787 + outer loop + vertex 0.796214 1.39386 2.55611 + vertex 0.79443 1.39154 2.55299 + vertex 0.796453 1.38887 2.55592 + endloop + endfacet + facet normal -0.849122 -0.0541441 0.525414 + outer loop + vertex 0.794206 1.39648 2.55314 + vertex 0.79443 1.39154 2.55299 + vertex 0.796214 1.39386 2.55611 + endloop + endfacet + facet normal -0.84936 -0.0548451 0.524957 + outer loop + vertex 0.796024 1.39881 2.55632 + vertex 0.794206 1.39648 2.55314 + vertex 0.796214 1.39386 2.55611 + endloop + endfacet + facet normal -0.795605 -0.0561023 0.603212 + outer loop + vertex 0.796214 1.39386 2.55611 + vertex 0.798261 1.39641 2.55905 + vertex 0.796024 1.39881 2.55632 + endloop + endfacet + facet normal -0.79623 -0.0578086 0.602226 + outer loop + vertex 0.798261 1.39641 2.55905 + vertex 0.798166 1.40135 2.5594 + vertex 0.796024 1.39881 2.55632 + endloop + endfacet + facet normal -0.749971 -0.0609053 0.65866 + outer loop + vertex 0.798166 1.40135 2.5594 + vertex 0.798261 1.39641 2.55905 + vertex 0.800579 1.39892 2.56192 + endloop + endfacet + facet normal -0.75026 -0.061601 0.658267 + outer loop + vertex 0.800828 1.40409 2.56269 + vertex 0.798166 1.40135 2.5594 + vertex 0.800579 1.39892 2.56192 + endloop + endfacet + facet normal -0.725958 -0.0666698 0.684499 + outer loop + vertex 0.800579 1.39892 2.56192 + vertex 0.802974 1.40075 2.56464 + vertex 0.800828 1.40409 2.56269 + endloop + endfacet + facet normal -0.72325 -0.0630584 0.687702 + outer loop + vertex 0.80389 1.40404 2.5659 + vertex 0.800828 1.40409 2.56269 + vertex 0.802974 1.40075 2.56464 + endloop + endfacet + facet normal -0.716266 -0.0676385 0.694542 + outer loop + vertex 0.802974 1.40075 2.56464 + vertex 0.804685 1.40154 2.56648 + vertex 0.80389 1.40404 2.5659 + endloop + endfacet + facet normal -0.708798 -0.0634105 0.702556 + outer loop + vertex 0.806805 1.4021 2.56867 + vertex 0.80389 1.40404 2.5659 + vertex 0.804685 1.40154 2.56648 + endloop + endfacet + facet normal -0.707676 -0.069744 0.703086 + outer loop + vertex 0.805133 1.39872 2.56665 + vertex 0.806805 1.4021 2.56867 + vertex 0.804685 1.40154 2.56648 + endloop + endfacet + facet normal -0.708105 -0.0693003 0.702698 + outer loop + vertex 0.807759 1.39669 2.5691 + vertex 0.806805 1.4021 2.56867 + vertex 0.805133 1.39872 2.56665 + endloop + endfacet + facet normal -0.708361 -0.0700294 0.702368 + outer loop + vertex 0.805558 1.3941 2.56662 + vertex 0.807759 1.39669 2.5691 + vertex 0.805133 1.39872 2.56665 + endloop + endfacet + facet normal -0.714523 -0.0705545 0.696045 + outer loop + vertex 0.805133 1.39872 2.56665 + vertex 0.803004 1.39647 2.56424 + vertex 0.805558 1.3941 2.56662 + endloop + endfacet + facet normal -0.714684 -0.0709333 0.695841 + outer loop + vertex 0.803004 1.39647 2.56424 + vertex 0.803256 1.39165 2.564 + vertex 0.805558 1.3941 2.56662 + endloop + endfacet + facet normal -0.714303 -0.0716324 0.696161 + outer loop + vertex 0.805558 1.3941 2.56662 + vertex 0.803256 1.39165 2.564 + vertex 0.805887 1.38912 2.56645 + endloop + endfacet + facet normal -0.709149 -0.071476 0.701427 + outer loop + vertex 0.805887 1.38912 2.56645 + vertex 0.808233 1.39159 2.56907 + vertex 0.805558 1.3941 2.56662 + endloop + endfacet + facet normal -0.709067 -0.0716246 0.701494 + outer loop + vertex 0.808522 1.38652 2.56884 + vertex 0.808233 1.39159 2.56907 + vertex 0.805887 1.38912 2.56645 + endloop + endfacet + facet normal -0.71029 -0.0742644 0.69998 + outer loop + vertex 0.806144 1.38408 2.56617 + vertex 0.808522 1.38652 2.56884 + vertex 0.805887 1.38912 2.56645 + endloop + endfacet + facet normal -0.715128 -0.0742409 0.695039 + outer loop + vertex 0.805887 1.38912 2.56645 + vertex 0.803537 1.38665 2.56376 + vertex 0.806144 1.38408 2.56617 + endloop + endfacet + facet normal -0.716618 -0.0775299 0.693143 + outer loop + vertex 0.803537 1.38665 2.56376 + vertex 0.803785 1.3816 2.56345 + vertex 0.806144 1.38408 2.56617 + endloop + endfacet + facet normal -0.716658 -0.0774561 0.693111 + outer loop + vertex 0.806144 1.38408 2.56617 + vertex 0.803785 1.3816 2.56345 + vertex 0.806346 1.37903 2.56582 + endloop + endfacet + facet normal -0.711025 -0.0776344 0.698868 + outer loop + vertex 0.806346 1.37903 2.56582 + vertex 0.808728 1.38148 2.56851 + vertex 0.806144 1.38408 2.56617 + endloop + endfacet + facet normal -0.710447 -0.0787103 0.699335 + outer loop + vertex 0.808912 1.37647 2.56813 + vertex 0.808728 1.38148 2.56851 + vertex 0.806346 1.37903 2.56582 + endloop + endfacet + facet normal -0.711076 -0.0800584 0.698542 + outer loop + vertex 0.806546 1.37401 2.56544 + vertex 0.808912 1.37647 2.56813 + vertex 0.806346 1.37903 2.56582 + endloop + endfacet + facet normal -0.718189 -0.0798029 0.691257 + outer loop + vertex 0.806346 1.37903 2.56582 + vertex 0.803979 1.37652 2.56307 + vertex 0.806546 1.37401 2.56544 + endloop + endfacet + facet normal -0.719005 -0.0816503 0.690192 + outer loop + vertex 0.803979 1.37652 2.56307 + vertex 0.80418 1.3714 2.56267 + vertex 0.806546 1.37401 2.56544 + endloop + endfacet + facet normal -0.718793 -0.0820285 0.690368 + outer loop + vertex 0.806546 1.37401 2.56544 + vertex 0.80418 1.3714 2.56267 + vertex 0.806919 1.36911 2.56525 + endloop + endfacet + facet normal -0.71035 -0.081733 0.699087 + outer loop + vertex 0.806919 1.36911 2.56525 + vertex 0.80919 1.37155 2.56784 + vertex 0.806546 1.37401 2.56544 + endloop + endfacet + facet normal -0.708816 -0.0844679 0.700318 + outer loop + vertex 0.809744 1.3668 2.56783 + vertex 0.80919 1.37155 2.56784 + vertex 0.806919 1.36911 2.56525 + endloop + endfacet + facet normal -0.708642 -0.0839931 0.700551 + outer loop + vertex 0.807656 1.36445 2.56544 + vertex 0.809744 1.3668 2.56783 + vertex 0.806919 1.36911 2.56525 + endloop + endfacet + facet normal -0.717756 -0.0858138 0.690987 + outer loop + vertex 0.806919 1.36911 2.56525 + vertex 0.804716 1.36645 2.56263 + vertex 0.807656 1.36445 2.56544 + endloop + endfacet + facet normal -0.717509 -0.0849431 0.69135 + outer loop + vertex 0.804716 1.36645 2.56263 + vertex 0.805712 1.36185 2.5631 + vertex 0.807656 1.36445 2.56544 + endloop + endfacet + facet normal -0.714608 -0.0893252 0.693798 + outer loop + vertex 0.808703 1.36005 2.56595 + vertex 0.807656 1.36445 2.56544 + vertex 0.805712 1.36185 2.5631 + endloop + endfacet + facet normal -0.714236 -0.0877915 0.694377 + outer loop + vertex 0.806975 1.35702 2.56379 + vertex 0.808703 1.36005 2.56595 + vertex 0.805712 1.36185 2.5631 + endloop + endfacet + facet normal -0.725137 -0.0923406 0.682385 + outer loop + vertex 0.806975 1.35702 2.56379 + vertex 0.805712 1.36185 2.5631 + vertex 0.803976 1.35919 2.56089 + endloop + endfacet + facet normal -0.721116 -0.0788791 0.688309 + outer loop + vertex 0.806975 1.35702 2.56379 + vertex 0.803976 1.35919 2.56089 + vertex 0.804795 1.35674 2.56147 + endloop + endfacet + facet normal -0.719367 -0.0930944 0.688364 + outer loop + vertex 0.805301 1.35393 2.56162 + vertex 0.806975 1.35702 2.56379 + vertex 0.804795 1.35674 2.56147 + endloop + endfacet + facet normal -0.737955 -0.0975232 0.667767 + outer loop + vertex 0.804795 1.35674 2.56147 + vertex 0.803128 1.35598 2.55952 + vertex 0.805301 1.35393 2.56162 + endloop + endfacet + facet normal -0.73716 -0.0954891 0.668937 + outer loop + vertex 0.803128 1.35598 2.55952 + vertex 0.803268 1.35163 2.55905 + vertex 0.805301 1.35393 2.56162 + endloop + endfacet + facet normal -0.73746 -0.0949398 0.668685 + outer loop + vertex 0.805301 1.35393 2.56162 + vertex 0.803268 1.35163 2.55905 + vertex 0.805805 1.34924 2.56151 + endloop + endfacet + facet normal -0.720172 -0.0935221 0.687463 + outer loop + vertex 0.805805 1.34924 2.56151 + vertex 0.807933 1.35184 2.56409 + vertex 0.805301 1.35393 2.56162 + endloop + endfacet + facet normal -0.737021 -0.0938152 0.669328 + outer loop + vertex 0.803268 1.35163 2.55905 + vertex 0.803608 1.34662 2.55872 + vertex 0.805805 1.34924 2.56151 + endloop + endfacet + facet normal -0.719842 -0.0925403 0.687941 + outer loop + vertex 0.807933 1.35184 2.56409 + vertex 0.806975 1.35702 2.56379 + vertex 0.805301 1.35393 2.56162 + endloop + endfacet + facet normal -0.710286 -0.0901724 0.698114 + outer loop + vertex 0.806975 1.35702 2.56379 + vertex 0.807933 1.35184 2.56409 + vertex 0.810059 1.35412 2.56655 + endloop + endfacet + facet normal -0.711855 -0.0938254 0.696031 + outer loop + vertex 0.809443 1.35718 2.56633 + vertex 0.806975 1.35702 2.56379 + vertex 0.810059 1.35412 2.56655 + endloop + endfacet + facet normal -0.700919 -0.090816 0.707436 + outer loop + vertex 0.810059 1.35412 2.56655 + vertex 0.811944 1.35711 2.5688 + vertex 0.809443 1.35718 2.56633 + endloop + endfacet + facet normal -0.701157 -0.085788 0.707828 + outer loop + vertex 0.811944 1.35711 2.5688 + vertex 0.808703 1.36005 2.56595 + vertex 0.809443 1.35718 2.56633 + endloop + endfacet + facet normal -0.703125 -0.0904027 0.705296 + outer loop + vertex 0.811944 1.35711 2.5688 + vertex 0.810688 1.36218 2.5682 + vertex 0.808703 1.36005 2.56595 + endloop + endfacet + facet normal -0.697019 -0.0881453 0.711614 + outer loop + vertex 0.811944 1.35711 2.5688 + vertex 0.813719 1.36009 2.57091 + vertex 0.810688 1.36218 2.5682 + endloop + endfacet + facet normal -0.697304 -0.0890691 0.71122 + outer loop + vertex 0.813719 1.36009 2.57091 + vertex 0.812666 1.36453 2.57043 + vertex 0.810688 1.36218 2.5682 + endloop + endfacet + facet normal -0.699214 -0.0860272 0.709718 + outer loop + vertex 0.809744 1.3668 2.56783 + vertex 0.810688 1.36218 2.5682 + vertex 0.812666 1.36453 2.57043 + endloop + endfacet + facet normal -0.699324 -0.0863367 0.709571 + outer loop + vertex 0.811933 1.36915 2.57027 + vertex 0.809744 1.3668 2.56783 + vertex 0.812666 1.36453 2.57043 + endloop + endfacet + facet normal -0.692287 -0.0849767 0.716601 + outer loop + vertex 0.812666 1.36453 2.57043 + vertex 0.814776 1.36683 2.57274 + vertex 0.811933 1.36915 2.57027 + endloop + endfacet + facet normal -0.691972 -0.0841661 0.717001 + outer loop + vertex 0.814776 1.36683 2.57274 + vertex 0.814254 1.37156 2.5728 + vertex 0.811933 1.36915 2.57027 + endloop + endfacet + facet normal -0.69263 -0.0830053 0.716501 + outer loop + vertex 0.811933 1.36915 2.57027 + vertex 0.814254 1.37156 2.5728 + vertex 0.811531 1.37397 2.57044 + endloop + endfacet + facet normal -0.700849 -0.0834063 0.708417 + outer loop + vertex 0.811531 1.37397 2.57044 + vertex 0.80919 1.37155 2.56784 + vertex 0.811933 1.36915 2.57027 + endloop + endfacet + facet normal -0.701866 -0.0815701 0.707623 + outer loop + vertex 0.808912 1.37647 2.56813 + vertex 0.80919 1.37155 2.56784 + vertex 0.811531 1.37397 2.57044 + endloop + endfacet + facet normal -0.701387 -0.0805196 0.708218 + outer loop + vertex 0.811312 1.37893 2.57079 + vertex 0.808912 1.37647 2.56813 + vertex 0.811531 1.37397 2.57044 + endloop + endfacet + facet normal -0.692922 -0.0807246 0.716479 + outer loop + vertex 0.811531 1.37397 2.57044 + vertex 0.813945 1.37646 2.57306 + vertex 0.811312 1.37893 2.57079 + endloop + endfacet + facet normal -0.691844 -0.0783831 0.71778 + outer loop + vertex 0.813945 1.37646 2.57306 + vertex 0.813744 1.38144 2.57341 + vertex 0.811312 1.37893 2.57079 + endloop + endfacet + facet normal -0.692463 -0.0772833 0.717302 + outer loop + vertex 0.811312 1.37893 2.57079 + vertex 0.813744 1.38144 2.57341 + vertex 0.811131 1.38395 2.57116 + endloop + endfacet + facet normal -0.701233 -0.0769766 0.708764 + outer loop + vertex 0.811131 1.38395 2.57116 + vertex 0.808728 1.38148 2.56851 + vertex 0.811312 1.37893 2.57079 + endloop + endfacet + facet normal -0.702148 -0.0753036 0.708038 + outer loop + vertex 0.808522 1.38652 2.56884 + vertex 0.808728 1.38148 2.56851 + vertex 0.811131 1.38395 2.57116 + endloop + endfacet + facet normal -0.700867 -0.0726178 0.709586 + outer loop + vertex 0.810915 1.38899 2.57146 + vertex 0.808522 1.38652 2.56884 + vertex 0.811131 1.38395 2.57116 + endloop + endfacet + facet normal -0.691681 -0.0727605 0.718528 + outer loop + vertex 0.811131 1.38395 2.57116 + vertex 0.813556 1.38645 2.57374 + vertex 0.810915 1.38899 2.57146 + endloop + endfacet + facet normal -0.690195 -0.0696677 0.720262 + outer loop + vertex 0.813556 1.38645 2.57374 + vertex 0.813323 1.39149 2.57401 + vertex 0.810915 1.38899 2.57146 + endloop + endfacet + facet normal -0.690641 -0.0688807 0.71991 + outer loop + vertex 0.810915 1.38899 2.57146 + vertex 0.813323 1.39149 2.57401 + vertex 0.81058 1.3941 2.57163 + endloop + endfacet + facet normal -0.700376 -0.0692091 0.710411 + outer loop + vertex 0.81058 1.3941 2.57163 + vertex 0.808233 1.39159 2.56907 + vertex 0.810915 1.38899 2.57146 + endloop + endfacet + facet normal -0.700395 -0.0691767 0.710396 + outer loop + vertex 0.807759 1.39669 2.5691 + vertex 0.808233 1.39159 2.56907 + vertex 0.81058 1.3941 2.57163 + endloop + endfacet + facet normal -0.699763 -0.0677454 0.711156 + outer loop + vertex 0.81001 1.3992 2.57155 + vertex 0.807759 1.39669 2.5691 + vertex 0.81058 1.3941 2.57163 + endloop + endfacet + facet normal -0.690053 -0.0665203 0.720695 + outer loop + vertex 0.81058 1.3941 2.57163 + vertex 0.812942 1.39667 2.57412 + vertex 0.81001 1.3992 2.57155 + endloop + endfacet + facet normal -0.689953 -0.0662847 0.720813 + outer loop + vertex 0.812942 1.39667 2.57412 + vertex 0.812226 1.40226 2.57395 + vertex 0.81001 1.3992 2.57155 + endloop + endfacet + facet normal -0.689366 -0.0670917 0.7213 + outer loop + vertex 0.81001 1.3992 2.57155 + vertex 0.812226 1.40226 2.57395 + vertex 0.809417 1.4032 2.57136 + endloop + endfacet + facet normal -0.700992 -0.0693719 0.709788 + outer loop + vertex 0.809417 1.4032 2.57136 + vertex 0.806805 1.4021 2.56867 + vertex 0.81001 1.3992 2.57155 + endloop + endfacet + facet normal -0.700806 -0.0700861 0.7099 + outer loop + vertex 0.806805 1.4021 2.56867 + vertex 0.809417 1.4032 2.57136 + vertex 0.807874 1.40568 2.57008 + endloop + endfacet + facet normal -0.706192 -0.0665106 0.704889 + outer loop + vertex 0.806805 1.4021 2.56867 + vertex 0.807874 1.40568 2.57008 + vertex 0.805579 1.40688 2.56789 + endloop + endfacet + facet normal -0.705231 -0.0621933 0.706245 + outer loop + vertex 0.807874 1.40568 2.57008 + vertex 0.807585 1.40933 2.57011 + vertex 0.805579 1.40688 2.56789 + endloop + endfacet + facet normal -0.705954 -0.0610365 0.705622 + outer loop + vertex 0.804812 1.41138 2.56751 + vertex 0.805579 1.40688 2.56789 + vertex 0.807585 1.40933 2.57011 + endloop + endfacet + facet normal -0.705301 -0.0591209 0.706439 + outer loop + vertex 0.807208 1.414 2.57013 + vertex 0.804812 1.41138 2.56751 + vertex 0.807585 1.40933 2.57011 + endloop + endfacet + facet normal -0.696045 -0.0583998 0.715619 + outer loop + vertex 0.807585 1.40933 2.57011 + vertex 0.810286 1.41111 2.57288 + vertex 0.807208 1.414 2.57013 + endloop + endfacet + facet normal -0.696296 -0.0589415 0.715331 + outer loop + vertex 0.810286 1.41111 2.57288 + vertex 0.809645 1.41645 2.5727 + vertex 0.807208 1.414 2.57013 + endloop + endfacet + facet normal -0.69791 -0.055943 0.713997 + outer loop + vertex 0.807208 1.414 2.57013 + vertex 0.809645 1.41645 2.5727 + vertex 0.806875 1.41901 2.57019 + endloop + endfacet + facet normal -0.705068 -0.0563234 0.7069 + outer loop + vertex 0.806875 1.41901 2.57019 + vertex 0.804399 1.41636 2.56751 + vertex 0.807208 1.414 2.57013 + endloop + endfacet + facet normal -0.706158 -0.054362 0.705964 + outer loop + vertex 0.804259 1.42148 2.56777 + vertex 0.804399 1.41636 2.56751 + vertex 0.806875 1.41901 2.57019 + endloop + endfacet + facet normal -0.705116 -0.0520678 0.707178 + outer loop + vertex 0.806696 1.42403 2.57038 + vertex 0.804259 1.42148 2.56777 + vertex 0.806875 1.41901 2.57019 + endloop + endfacet + facet normal -0.698622 -0.0520798 0.713593 + outer loop + vertex 0.806875 1.41901 2.57019 + vertex 0.809327 1.42149 2.57277 + vertex 0.806696 1.42403 2.57038 + endloop + endfacet + facet normal -0.698136 -0.0510568 0.714142 + outer loop + vertex 0.809327 1.42149 2.57277 + vertex 0.809141 1.42648 2.57295 + vertex 0.806696 1.42403 2.57038 + endloop + endfacet + facet normal -0.699395 -0.0486865 0.713075 + outer loop + vertex 0.806696 1.42403 2.57038 + vertex 0.809141 1.42648 2.57295 + vertex 0.806558 1.429 2.57059 + endloop + endfacet + facet normal -0.705708 -0.0486034 0.706834 + outer loop + vertex 0.806558 1.429 2.57059 + vertex 0.804143 1.42653 2.56801 + vertex 0.806696 1.42403 2.57038 + endloop + endfacet + facet normal -0.706733 -0.0466687 0.705939 + outer loop + vertex 0.804 1.43151 2.56819 + vertex 0.804143 1.42653 2.56801 + vertex 0.806558 1.429 2.57059 + endloop + endfacet + facet normal -0.706527 -0.0462335 0.706174 + outer loop + vertex 0.806408 1.43396 2.57076 + vertex 0.804 1.43151 2.56819 + vertex 0.806558 1.429 2.57059 + endloop + endfacet + facet normal -0.699998 -0.0462627 0.712645 + outer loop + vertex 0.806558 1.429 2.57059 + vertex 0.808998 1.43144 2.57314 + vertex 0.806408 1.43396 2.57076 + endloop + endfacet + facet normal -0.699721 -0.0456865 0.712954 + outer loop + vertex 0.808998 1.43144 2.57314 + vertex 0.808847 1.43641 2.57331 + vertex 0.806408 1.43396 2.57076 + endloop + endfacet + facet normal -0.700671 -0.0438895 0.712133 + outer loop + vertex 0.806408 1.43396 2.57076 + vertex 0.808847 1.43641 2.57331 + vertex 0.806246 1.43893 2.57091 + endloop + endfacet + facet normal -0.707417 -0.0439122 0.705431 + outer loop + vertex 0.806246 1.43893 2.57091 + vertex 0.803836 1.43647 2.56834 + vertex 0.806408 1.43396 2.57076 + endloop + endfacet + facet normal -0.708448 -0.0419492 0.704516 + outer loop + vertex 0.803675 1.44143 2.56847 + vertex 0.803836 1.43647 2.56834 + vertex 0.806246 1.43893 2.57091 + endloop + endfacet + facet normal -0.708108 -0.0412255 0.7049 + outer loop + vertex 0.80609 1.44392 2.57104 + vertex 0.803675 1.44143 2.56847 + vertex 0.806246 1.43893 2.57091 + endloop + endfacet + facet normal -0.700877 -0.0411941 0.712091 + outer loop + vertex 0.806246 1.43893 2.57091 + vertex 0.808689 1.44141 2.57346 + vertex 0.80609 1.44392 2.57104 + endloop + endfacet + facet normal -0.700123 -0.0396149 0.712923 + outer loop + vertex 0.808689 1.44141 2.57346 + vertex 0.808538 1.44642 2.57359 + vertex 0.80609 1.44392 2.57104 + endloop + endfacet + facet normal -0.70025 -0.0393747 0.712811 + outer loop + vertex 0.80609 1.44392 2.57104 + vertex 0.808538 1.44642 2.57359 + vertex 0.805946 1.44893 2.57118 + endloop + endfacet + facet normal -0.708115 -0.0393895 0.704997 + outer loop + vertex 0.805946 1.44893 2.57118 + vertex 0.80353 1.44642 2.56861 + vertex 0.80609 1.44392 2.57104 + endloop + endfacet + facet normal -0.707465 -0.040614 0.70558 + outer loop + vertex 0.803394 1.45142 2.56876 + vertex 0.80353 1.44642 2.56861 + vertex 0.805946 1.44893 2.57118 + endloop + endfacet + facet normal -0.706746 -0.0390983 0.706386 + outer loop + vertex 0.805808 1.45392 2.57132 + vertex 0.803394 1.45142 2.56876 + vertex 0.805946 1.44893 2.57118 + endloop + endfacet + facet normal -0.698545 -0.0390958 0.714497 + outer loop + vertex 0.805946 1.44893 2.57118 + vertex 0.808398 1.45142 2.57371 + vertex 0.805808 1.45392 2.57132 + endloop + endfacet + facet normal -0.69759 -0.0371134 0.715536 + outer loop + vertex 0.808398 1.45142 2.57371 + vertex 0.808261 1.45641 2.57384 + vertex 0.805808 1.45392 2.57132 + endloop + endfacet + facet normal -0.696909 -0.0383888 0.716132 + outer loop + vertex 0.805808 1.45392 2.57132 + vertex 0.808261 1.45641 2.57384 + vertex 0.805671 1.45891 2.57145 + endloop + endfacet + facet normal -0.704422 -0.0383941 0.708743 + outer loop + vertex 0.805671 1.45891 2.57145 + vertex 0.803257 1.45642 2.56892 + vertex 0.805808 1.45392 2.57132 + endloop + endfacet + facet normal -0.704194 -0.0388199 0.708945 + outer loop + vertex 0.803124 1.4614 2.56906 + vertex 0.803257 1.45642 2.56892 + vertex 0.805671 1.45891 2.57145 + endloop + endfacet + facet normal -0.702617 -0.0355365 0.71068 + outer loop + vertex 0.805544 1.4639 2.57158 + vertex 0.803124 1.4614 2.56906 + vertex 0.805671 1.45891 2.57145 + endloop + endfacet + facet normal -0.695985 -0.035527 0.717176 + outer loop + vertex 0.805671 1.45891 2.57145 + vertex 0.808129 1.4614 2.57396 + vertex 0.805544 1.4639 2.57158 + endloop + endfacet + facet normal -0.694736 -0.0329629 0.71851 + outer loop + vertex 0.808129 1.4614 2.57396 + vertex 0.808007 1.46638 2.57407 + vertex 0.805544 1.4639 2.57158 + endloop + endfacet + facet normal -0.695971 -0.0306403 0.717416 + outer loop + vertex 0.805544 1.4639 2.57158 + vertex 0.808007 1.46638 2.57407 + vertex 0.805432 1.46888 2.57168 + endloop + endfacet + facet normal -0.702752 -0.0306538 0.710774 + outer loop + vertex 0.805432 1.46888 2.57168 + vertex 0.803005 1.46639 2.56917 + vertex 0.805544 1.4639 2.57158 + endloop + endfacet + facet normal -0.704422 -0.0274967 0.709249 + outer loop + vertex 0.802903 1.47138 2.56927 + vertex 0.803005 1.46639 2.56917 + vertex 0.805432 1.46888 2.57168 + endloop + endfacet + facet normal -0.703623 -0.0258582 0.710103 + outer loop + vertex 0.805337 1.47387 2.57177 + vertex 0.802903 1.47138 2.56927 + vertex 0.805432 1.46888 2.57168 + endloop + endfacet + facet normal -0.696573 -0.0258448 0.71702 + outer loop + vertex 0.805432 1.46888 2.57168 + vertex 0.807901 1.47137 2.57417 + vertex 0.805337 1.47387 2.57177 + endloop + endfacet + facet normal -0.696212 -0.0251127 0.717397 + outer loop + vertex 0.807901 1.47137 2.57417 + vertex 0.807808 1.47636 2.57425 + vertex 0.805337 1.47387 2.57177 + endloop + endfacet + facet normal -0.697035 -0.023551 0.71665 + outer loop + vertex 0.805337 1.47387 2.57177 + vertex 0.807808 1.47636 2.57425 + vertex 0.805251 1.47885 2.57185 + endloop + endfacet + facet normal -0.704933 -0.023561 0.708882 + outer loop + vertex 0.805251 1.47885 2.57185 + vertex 0.802816 1.47637 2.56934 + vertex 0.805337 1.47387 2.57177 + endloop + endfacet + facet normal -0.705346 -0.0227701 0.708498 + outer loop + vertex 0.802735 1.48136 2.56942 + vertex 0.802816 1.47637 2.56934 + vertex 0.805251 1.47885 2.57185 + endloop + endfacet + facet normal -0.705055 -0.0221819 0.708805 + outer loop + vertex 0.805173 1.48383 2.57193 + vertex 0.802735 1.48136 2.56942 + vertex 0.805251 1.47885 2.57185 + endloop + endfacet + facet normal -0.697603 -0.0221795 0.716141 + outer loop + vertex 0.805251 1.47885 2.57185 + vertex 0.807723 1.48134 2.57433 + vertex 0.805173 1.48383 2.57193 + endloop + endfacet + facet normal -0.696976 -0.0209107 0.71679 + outer loop + vertex 0.807723 1.48134 2.57433 + vertex 0.807651 1.48632 2.57441 + vertex 0.805173 1.48383 2.57193 + endloop + endfacet + facet normal -0.697977 -0.0189906 0.715868 + outer loop + vertex 0.805173 1.48383 2.57193 + vertex 0.807651 1.48632 2.57441 + vertex 0.805105 1.48881 2.57199 + endloop + endfacet + facet normal -0.704968 -0.0189945 0.708985 + outer loop + vertex 0.805105 1.48881 2.57199 + vertex 0.802661 1.48635 2.5695 + vertex 0.805173 1.48383 2.57193 + endloop + endfacet + facet normal -0.706226 -0.0165434 0.707793 + outer loop + vertex 0.802598 1.49133 2.56955 + vertex 0.802661 1.48635 2.5695 + vertex 0.805105 1.48881 2.57199 + endloop + endfacet + facet normal -0.70501 -0.0141036 0.709057 + outer loop + vertex 0.805043 1.49381 2.57203 + vertex 0.802598 1.49133 2.56955 + vertex 0.805105 1.48881 2.57199 + endloop + endfacet + facet normal -0.698016 -0.014068 0.715944 + outer loop + vertex 0.805105 1.48881 2.57199 + vertex 0.807588 1.4913 2.57446 + vertex 0.805043 1.49381 2.57203 + endloop + endfacet + facet normal -0.696754 -0.0115476 0.717218 + outer loop + vertex 0.807588 1.4913 2.57446 + vertex 0.807518 1.49634 2.57447 + vertex 0.805043 1.49381 2.57203 + endloop + endfacet + facet normal -0.69802 -0.00914992 0.71602 + outer loop + vertex 0.805043 1.49381 2.57203 + vertex 0.807518 1.49634 2.57447 + vertex 0.804969 1.49883 2.57202 + endloop + endfacet + facet normal -0.705393 -0.00926982 0.708756 + outer loop + vertex 0.804969 1.49883 2.57202 + vertex 0.802547 1.49631 2.56958 + vertex 0.805043 1.49381 2.57203 + endloop + endfacet + facet normal -0.706112 -0.00789776 0.708056 + outer loop + vertex 0.802513 1.50126 2.5696 + vertex 0.802547 1.49631 2.56958 + vertex 0.804969 1.49883 2.57202 + endloop + endfacet + facet normal -0.696951 -0.00700779 0.717084 + outer loop + vertex 0.807518 1.49634 2.57447 + vertex 0.807409 1.5015 2.57442 + vertex 0.804969 1.49883 2.57202 + endloop + endfacet + facet normal -0.697367 -0.00627032 0.716687 + outer loop + vertex 0.804969 1.49883 2.57202 + vertex 0.807409 1.5015 2.57442 + vertex 0.804847 1.50376 2.57195 + endloop + endfacet + facet normal -0.696895 -0.00522505 0.717154 + outer loop + vertex 0.807409 1.5015 2.57442 + vertex 0.807158 1.50713 2.57422 + vertex 0.804847 1.50376 2.57195 + endloop + endfacet + facet normal -0.697005 -0.00507883 0.717049 + outer loop + vertex 0.804847 1.50376 2.57195 + vertex 0.807158 1.50713 2.57422 + vertex 0.804554 1.50776 2.57169 + endloop + endfacet + facet normal -0.6969 -0.00421622 0.717156 + outer loop + vertex 0.804554 1.50776 2.57169 + vertex 0.807158 1.50713 2.57422 + vertex 0.805306 1.51195 2.57245 + endloop + endfacet + facet normal -0.69574 -0.00335637 0.718286 + outer loop + vertex 0.807158 1.50713 2.57422 + vertex 0.808026 1.51161 2.57508 + vertex 0.805306 1.51195 2.57245 + endloop + endfacet + facet normal -0.69566 -0.00209742 0.718368 + outer loop + vertex 0.808026 1.51161 2.57508 + vertex 0.807527 1.51577 2.57461 + vertex 0.805306 1.51195 2.57245 + endloop + endfacet + facet normal -0.696325 -0.00134587 0.717725 + outer loop + vertex 0.805306 1.51195 2.57245 + vertex 0.807527 1.51577 2.57461 + vertex 0.804802 1.51719 2.57197 + endloop + endfacet + facet normal -0.695817 0.000547064 0.718219 + outer loop + vertex 0.804802 1.51719 2.57197 + vertex 0.807527 1.51577 2.57461 + vertex 0.806982 1.52102 2.57408 + endloop + endfacet + facet normal -0.695634 0.000345317 0.718396 + outer loop + vertex 0.804407 1.52091 2.57158 + vertex 0.804802 1.51719 2.57197 + vertex 0.806982 1.52102 2.57408 + endloop + endfacet + facet normal -0.695694 0.00309656 0.718332 + outer loop + vertex 0.804407 1.52091 2.57158 + vertex 0.806982 1.52102 2.57408 + vertex 0.80488 1.52437 2.57202 + endloop + endfacet + facet normal -0.694369 0.00470462 0.719604 + outer loop + vertex 0.806982 1.52102 2.57408 + vertex 0.807378 1.52635 2.57442 + vertex 0.80488 1.52437 2.57202 + endloop + endfacet + facet normal -0.696006 0.00874194 0.717983 + outer loop + vertex 0.80488 1.52437 2.57202 + vertex 0.807378 1.52635 2.57442 + vertex 0.804974 1.52889 2.57206 + endloop + endfacet + facet normal -0.707189 0.00906111 0.706966 + outer loop + vertex 0.804974 1.52889 2.57206 + vertex 0.802649 1.52647 2.56977 + vertex 0.80488 1.52437 2.57202 + endloop + endfacet + facet normal -0.708748 0.0120908 0.705358 + outer loop + vertex 0.802557 1.53127 2.56959 + vertex 0.802649 1.52647 2.56977 + vertex 0.804974 1.52889 2.57206 + endloop + endfacet + facet normal -0.708256 0.0130851 0.705834 + outer loop + vertex 0.805007 1.53375 2.572 + vertex 0.802557 1.53127 2.56959 + vertex 0.804974 1.52889 2.57206 + endloop + endfacet + facet normal -0.696978 0.0131376 0.716972 + outer loop + vertex 0.804974 1.52889 2.57206 + vertex 0.807492 1.53128 2.57447 + vertex 0.805007 1.53375 2.572 + endloop + endfacet + facet normal -0.696031 0.0149698 0.717855 + outer loop + vertex 0.807492 1.53128 2.57447 + vertex 0.80755 1.53624 2.57442 + vertex 0.805007 1.53375 2.572 + endloop + endfacet + facet normal -0.697108 0.0171345 0.716761 + outer loop + vertex 0.805007 1.53375 2.572 + vertex 0.80755 1.53624 2.57442 + vertex 0.805057 1.53873 2.57193 + endloop + endfacet + facet normal -0.708111 0.0170917 0.705894 + outer loop + vertex 0.805057 1.53873 2.57193 + vertex 0.802568 1.53624 2.5695 + vertex 0.805007 1.53375 2.572 + endloop + endfacet + facet normal -0.708714 0.018317 0.705258 + outer loop + vertex 0.802632 1.54125 2.56943 + vertex 0.802568 1.53624 2.5695 + vertex 0.805057 1.53873 2.57193 + endloop + endfacet + facet normal -0.707223 0.0211559 0.706674 + outer loop + vertex 0.805132 1.54374 2.57186 + vertex 0.802632 1.54125 2.56943 + vertex 0.805057 1.53873 2.57193 + endloop + endfacet + facet normal -0.697057 0.0211555 0.716704 + outer loop + vertex 0.805057 1.53873 2.57193 + vertex 0.807611 1.54123 2.57434 + vertex 0.805132 1.54374 2.57186 + endloop + endfacet + facet normal -0.696045 0.0230713 0.717627 + outer loop + vertex 0.807611 1.54123 2.57434 + vertex 0.807692 1.54624 2.57426 + vertex 0.805132 1.54374 2.57186 + endloop + endfacet + facet normal -0.696553 0.0241009 0.7171 + outer loop + vertex 0.805132 1.54374 2.57186 + vertex 0.807692 1.54624 2.57426 + vertex 0.805219 1.54874 2.57177 + endloop + endfacet + facet normal -0.705622 0.0241112 0.708178 + outer loop + vertex 0.805219 1.54874 2.57177 + vertex 0.802713 1.54626 2.56936 + vertex 0.805132 1.54374 2.57186 + endloop + endfacet + facet normal -0.705684 0.0242387 0.708112 + outer loop + vertex 0.802798 1.55126 2.56928 + vertex 0.802713 1.54626 2.56936 + vertex 0.805219 1.54874 2.57177 + endloop + endfacet + facet normal -0.705025 0.0254833 0.708724 + outer loop + vertex 0.80531 1.55374 2.57169 + vertex 0.802798 1.55126 2.56928 + vertex 0.805219 1.54874 2.57177 + endloop + endfacet + facet normal -0.696222 0.0254773 0.717374 + outer loop + vertex 0.805219 1.54874 2.57177 + vertex 0.807783 1.55124 2.57418 + vertex 0.80531 1.55374 2.57169 + endloop + endfacet + facet normal -0.69605 0.0258014 0.717529 + outer loop + vertex 0.807783 1.55124 2.57418 + vertex 0.807878 1.55624 2.57409 + vertex 0.80531 1.55374 2.57169 + endloop + endfacet + facet normal -0.69583 0.0253541 0.717758 + outer loop + vertex 0.80531 1.55374 2.57169 + vertex 0.807878 1.55624 2.57409 + vertex 0.805401 1.55874 2.5716 + endloop + endfacet + facet normal -0.704719 0.0253628 0.709033 + outer loop + vertex 0.805401 1.55874 2.5716 + vertex 0.802883 1.55625 2.56918 + vertex 0.80531 1.55374 2.57169 + endloop + endfacet + facet normal -0.704784 0.0254972 0.708963 + outer loop + vertex 0.80297 1.56124 2.56909 + vertex 0.802883 1.55625 2.56918 + vertex 0.805401 1.55874 2.5716 + endloop + endfacet + facet normal -0.70465 0.0257531 0.709088 + outer loop + vertex 0.805495 1.56374 2.57151 + vertex 0.80297 1.56124 2.56909 + vertex 0.805401 1.55874 2.5716 + endloop + endfacet + facet normal -0.695168 0.02574 0.718386 + outer loop + vertex 0.805401 1.55874 2.5716 + vertex 0.807974 1.56124 2.574 + vertex 0.805495 1.56374 2.57151 + endloop + endfacet + facet normal -0.694145 0.0276692 0.719304 + outer loop + vertex 0.807974 1.56124 2.574 + vertex 0.808074 1.56624 2.5739 + vertex 0.805495 1.56374 2.57151 + endloop + endfacet + facet normal -0.694607 0.0286083 0.71882 + outer loop + vertex 0.805495 1.56374 2.57151 + vertex 0.808074 1.56624 2.5739 + vertex 0.805598 1.56874 2.57141 + endloop + endfacet + facet normal -0.704145 0.0286182 0.709479 + outer loop + vertex 0.805598 1.56874 2.57141 + vertex 0.803062 1.56623 2.56899 + vertex 0.805495 1.56374 2.57151 + endloop + endfacet + facet normal -0.705097 0.0305748 0.708451 + outer loop + vertex 0.803167 1.57123 2.56888 + vertex 0.803062 1.56623 2.56899 + vertex 0.805598 1.56874 2.57141 + endloop + endfacet + facet normal -0.703428 0.0337346 0.709966 + outer loop + vertex 0.805718 1.57374 2.57129 + vertex 0.803167 1.57123 2.56888 + vertex 0.805598 1.56874 2.57141 + endloop + endfacet + facet normal -0.694683 0.0337287 0.718525 + outer loop + vertex 0.805598 1.56874 2.57141 + vertex 0.808186 1.57124 2.57379 + vertex 0.805718 1.57374 2.57129 + endloop + endfacet + facet normal -0.693245 0.0364093 0.719782 + outer loop + vertex 0.808186 1.57124 2.57379 + vertex 0.808319 1.57624 2.57367 + vertex 0.805718 1.57374 2.57129 + endloop + endfacet + facet normal -0.694708 0.0394232 0.718211 + outer loop + vertex 0.805718 1.57374 2.57129 + vertex 0.808319 1.57624 2.57367 + vertex 0.805857 1.57874 2.57115 + endloop + endfacet + facet normal -0.703618 0.0394264 0.709484 + outer loop + vertex 0.805857 1.57874 2.57115 + vertex 0.80329 1.57623 2.56874 + vertex 0.805718 1.57374 2.57129 + endloop + endfacet + facet normal -0.704796 0.0418865 0.708173 + outer loop + vertex 0.803429 1.58124 2.56859 + vertex 0.80329 1.57623 2.56874 + vertex 0.805857 1.57874 2.57115 + endloop + endfacet + facet normal -0.703991 0.0433993 0.708882 + outer loop + vertex 0.806006 1.58375 2.57099 + vertex 0.803429 1.58124 2.56859 + vertex 0.805857 1.57874 2.57115 + endloop + endfacet + facet normal -0.694961 0.0434106 0.717736 + outer loop + vertex 0.805857 1.57874 2.57115 + vertex 0.808467 1.58124 2.57353 + vertex 0.806006 1.58375 2.57099 + endloop + endfacet + facet normal -0.694529 0.0442061 0.718105 + outer loop + vertex 0.808467 1.58124 2.57353 + vertex 0.808614 1.58622 2.57336 + vertex 0.806006 1.58375 2.57099 + endloop + endfacet + facet normal -0.695202 0.0456261 0.717365 + outer loop + vertex 0.806006 1.58375 2.57099 + vertex 0.808614 1.58622 2.57336 + vertex 0.806155 1.58874 2.57082 + endloop + endfacet + facet normal -0.704561 0.0455894 0.708178 + outer loop + vertex 0.806155 1.58874 2.57082 + vertex 0.803577 1.58624 2.56842 + vertex 0.806006 1.58375 2.57099 + endloop + endfacet + facet normal -0.705071 0.0466712 0.707599 + outer loop + vertex 0.803738 1.59122 2.56825 + vertex 0.803577 1.58624 2.56842 + vertex 0.806155 1.58874 2.57082 + endloop + endfacet + facet normal -0.704613 0.0475298 0.707998 + outer loop + vertex 0.806319 1.59372 2.57065 + vertex 0.803738 1.59122 2.56825 + vertex 0.806155 1.58874 2.57082 + endloop + endfacet + facet normal -0.695824 0.0475402 0.716637 + outer loop + vertex 0.806155 1.58874 2.57082 + vertex 0.808755 1.59119 2.57318 + vertex 0.806319 1.59372 2.57065 + endloop + endfacet + facet normal -0.695528 0.0480774 0.716888 + outer loop + vertex 0.808755 1.59119 2.57318 + vertex 0.80892 1.59616 2.57301 + vertex 0.806319 1.59372 2.57065 + endloop + endfacet + facet normal -0.696593 0.0503589 0.715697 + outer loop + vertex 0.806319 1.59372 2.57065 + vertex 0.80892 1.59616 2.57301 + vertex 0.806525 1.59869 2.5705 + endloop + endfacet + facet normal -0.704883 0.0504592 0.707526 + outer loop + vertex 0.806525 1.59869 2.5705 + vertex 0.80393 1.5962 2.56809 + vertex 0.806319 1.59372 2.57065 + endloop + endfacet + facet normal -0.705976 0.0528127 0.706264 + outer loop + vertex 0.804155 1.60118 2.56794 + vertex 0.80393 1.5962 2.56809 + vertex 0.806525 1.59869 2.5705 + endloop + endfacet + facet normal -0.705318 0.0540217 0.70683 + outer loop + vertex 0.806767 1.60366 2.57036 + vertex 0.804155 1.60118 2.56794 + vertex 0.806525 1.59869 2.5705 + endloop + endfacet + facet normal -0.697401 0.0538568 0.714654 + outer loop + vertex 0.806525 1.59869 2.5705 + vertex 0.809147 1.60115 2.57287 + vertex 0.806767 1.60366 2.57036 + endloop + endfacet + facet normal -0.696935 0.0546892 0.715046 + outer loop + vertex 0.809147 1.60115 2.57287 + vertex 0.809399 1.60612 2.57274 + vertex 0.806767 1.60366 2.57036 + endloop + endfacet + facet normal -0.69821 0.0574754 0.713582 + outer loop + vertex 0.806767 1.60366 2.57036 + vertex 0.809399 1.60612 2.57274 + vertex 0.806936 1.60858 2.57013 + endloop + endfacet + facet normal -0.705473 0.0573913 0.706409 + outer loop + vertex 0.806936 1.60858 2.57013 + vertex 0.804352 1.60617 2.56775 + vertex 0.806767 1.60366 2.57036 + endloop + endfacet + facet normal -0.706272 0.0591861 0.705462 + outer loop + vertex 0.804403 1.61114 2.56738 + vertex 0.804352 1.60617 2.56775 + vertex 0.806936 1.60858 2.57013 + endloop + endfacet + facet normal -0.705849 0.0599871 0.705818 + outer loop + vertex 0.806903 1.61332 2.56969 + vertex 0.804403 1.61114 2.56738 + vertex 0.806936 1.60858 2.57013 + endloop + endfacet + facet normal -0.699191 0.0606346 0.712359 + outer loop + vertex 0.806936 1.60858 2.57013 + vertex 0.809499 1.61096 2.57244 + vertex 0.806903 1.61332 2.56969 + endloop + endfacet + facet normal -0.698813 0.0614057 0.712664 + outer loop + vertex 0.809499 1.61096 2.57244 + vertex 0.80926 1.61558 2.57181 + vertex 0.806903 1.61332 2.56969 + endloop + endfacet + facet normal -0.70009 0.0641403 0.711168 + outer loop + vertex 0.806903 1.61332 2.56969 + vertex 0.80926 1.61558 2.57181 + vertex 0.806596 1.61782 2.56899 + endloop + endfacet + facet normal -0.70539 0.0629663 0.706017 + outer loop + vertex 0.806596 1.61782 2.56899 + vertex 0.804402 1.61581 2.56697 + vertex 0.806903 1.61332 2.56969 + endloop + endfacet + facet normal -0.705582 0.063408 0.705786 + outer loop + vertex 0.804426 1.6195 2.56667 + vertex 0.804402 1.61581 2.56697 + vertex 0.806596 1.61782 2.56899 + endloop + endfacet + facet normal -0.704067 0.0670019 0.706966 + outer loop + vertex 0.805862 1.62283 2.56778 + vertex 0.804426 1.6195 2.56667 + vertex 0.806596 1.61782 2.56899 + endloop + endfacet + facet normal -0.70151 0.0679658 0.709411 + outer loop + vertex 0.805862 1.62283 2.56778 + vertex 0.806596 1.61782 2.56899 + vertex 0.808702 1.61997 2.57086 + endloop + endfacet + facet normal -0.702839 0.0654788 0.708329 + outer loop + vertex 0.805862 1.62283 2.56778 + vertex 0.808702 1.61997 2.57086 + vertex 0.808277 1.62288 2.57017 + endloop + endfacet + facet normal -0.702724 0.0686204 0.708146 + outer loop + vertex 0.808277 1.62288 2.57017 + vertex 0.808021 1.62603 2.56961 + vertex 0.805862 1.62283 2.56778 + endloop + endfacet + facet normal -0.703412 0.0695262 0.707374 + outer loop + vertex 0.805862 1.62283 2.56778 + vertex 0.808021 1.62603 2.56961 + vertex 0.805404 1.62845 2.56677 + endloop + endfacet + facet normal -0.709074 0.0680746 0.701841 + outer loop + vertex 0.805404 1.62845 2.56677 + vertex 0.802943 1.62605 2.56452 + vertex 0.805862 1.62283 2.56778 + endloop + endfacet + facet normal -0.707647 0.0705707 0.703033 + outer loop + vertex 0.802943 1.62605 2.56452 + vertex 0.803141 1.62208 2.56512 + vertex 0.805862 1.62283 2.56778 + endloop + endfacet + facet normal -0.722162 0.0676429 0.688408 + outer loop + vertex 0.803141 1.62208 2.56512 + vertex 0.802943 1.62605 2.56452 + vertex 0.800573 1.62299 2.56233 + endloop + endfacet + facet normal -0.721843 0.0691145 0.688597 + outer loop + vertex 0.803141 1.62208 2.56512 + vertex 0.800573 1.62299 2.56233 + vertex 0.802311 1.61882 2.56457 + endloop + endfacet + facet normal -0.71221 0.0649399 0.698956 + outer loop + vertex 0.803141 1.62208 2.56512 + vertex 0.802311 1.61882 2.56457 + vertex 0.804426 1.6195 2.56667 + endloop + endfacet + facet normal -0.724417 0.0667164 0.686126 + outer loop + vertex 0.800573 1.62299 2.56233 + vertex 0.799909 1.61816 2.5621 + vertex 0.802311 1.61882 2.56457 + endloop + endfacet + facet normal -0.724053 0.0623949 0.686916 + outer loop + vertex 0.799909 1.61816 2.5621 + vertex 0.801668 1.6141 2.56432 + vertex 0.802311 1.61882 2.56457 + endloop + endfacet + facet normal -0.713753 0.0604163 0.697787 + outer loop + vertex 0.801668 1.6141 2.56432 + vertex 0.804402 1.61581 2.56697 + vertex 0.802311 1.61882 2.56457 + endloop + endfacet + facet normal -0.713777 0.0605078 0.697754 + outer loop + vertex 0.804403 1.61114 2.56738 + vertex 0.804402 1.61581 2.56697 + vertex 0.801668 1.6141 2.56432 + endloop + endfacet + facet normal -0.714738 0.0587599 0.696919 + outer loop + vertex 0.801867 1.60872 2.56498 + vertex 0.804403 1.61114 2.56738 + vertex 0.801668 1.6141 2.56432 + endloop + endfacet + facet normal -0.728178 0.0565695 0.683049 + outer loop + vertex 0.801668 1.6141 2.56432 + vertex 0.799472 1.6111 2.56223 + vertex 0.801867 1.60872 2.56498 + endloop + endfacet + facet normal -0.730015 0.0528048 0.681388 + outer loop + vertex 0.799472 1.6111 2.56223 + vertex 0.799362 1.60625 2.56249 + vertex 0.801867 1.60872 2.56498 + endloop + endfacet + facet normal -0.731247 0.0556045 0.679843 + outer loop + vertex 0.801867 1.60872 2.56498 + vertex 0.799362 1.60625 2.56249 + vertex 0.801766 1.60366 2.56529 + endloop + endfacet + facet normal -0.715932 0.0562692 0.695899 + outer loop + vertex 0.801766 1.60366 2.56529 + vertex 0.804352 1.60617 2.56775 + vertex 0.801867 1.60872 2.56498 + endloop + endfacet + facet normal -0.715807 0.0559919 0.69605 + outer loop + vertex 0.804155 1.60118 2.56794 + vertex 0.804352 1.60617 2.56775 + vertex 0.801766 1.60366 2.56529 + endloop + endfacet + facet normal -0.717126 0.0534815 0.694889 + outer loop + vertex 0.801571 1.59864 2.56547 + vertex 0.804155 1.60118 2.56794 + vertex 0.801766 1.60366 2.56529 + endloop + endfacet + facet normal -0.734048 0.0534739 0.676989 + outer loop + vertex 0.801766 1.60366 2.56529 + vertex 0.799194 1.60114 2.5627 + vertex 0.801571 1.59864 2.56547 + endloop + endfacet + facet normal -0.735191 0.051206 0.675923 + outer loop + vertex 0.799194 1.60114 2.5627 + vertex 0.79906 1.59607 2.56294 + vertex 0.801571 1.59864 2.56547 + endloop + endfacet + facet normal -0.734971 0.050718 0.676199 + outer loop + vertex 0.801571 1.59864 2.56547 + vertex 0.79906 1.59607 2.56294 + vertex 0.801374 1.59365 2.56563 + endloop + endfacet + facet normal -0.718121 0.0506245 0.694075 + outer loop + vertex 0.801374 1.59365 2.56563 + vertex 0.80393 1.5962 2.56809 + vertex 0.801571 1.59864 2.56547 + endloop + endfacet + facet normal -0.717575 0.049448 0.694724 + outer loop + vertex 0.803738 1.59122 2.56825 + vertex 0.80393 1.5962 2.56809 + vertex 0.801374 1.59365 2.56563 + endloop + endfacet + facet normal -0.718286 0.0480691 0.694086 + outer loop + vertex 0.801197 1.58868 2.56579 + vertex 0.803738 1.59122 2.56825 + vertex 0.801374 1.59365 2.56563 + endloop + endfacet + facet normal -0.73588 0.0480951 0.675401 + outer loop + vertex 0.801374 1.59365 2.56563 + vertex 0.798888 1.59109 2.56311 + vertex 0.801197 1.58868 2.56579 + endloop + endfacet + facet normal -0.73624 0.0473695 0.67506 + outer loop + vertex 0.798888 1.59109 2.56311 + vertex 0.798716 1.58612 2.56327 + vertex 0.801197 1.58868 2.56579 + endloop + endfacet + facet normal -0.735831 0.0464716 0.675569 + outer loop + vertex 0.801197 1.58868 2.56579 + vertex 0.798716 1.58612 2.56327 + vertex 0.801039 1.58369 2.56597 + endloop + endfacet + facet normal -0.71766 0.0465634 0.694835 + outer loop + vertex 0.801039 1.58369 2.56597 + vertex 0.803577 1.58624 2.56842 + vertex 0.801197 1.58868 2.56579 + endloop + endfacet + facet normal -0.716955 0.0450635 0.695662 + outer loop + vertex 0.803429 1.58124 2.56859 + vertex 0.803577 1.58624 2.56842 + vertex 0.801039 1.58369 2.56597 + endloop + endfacet + facet normal -0.717429 0.0441421 0.695231 + outer loop + vertex 0.800898 1.5787 2.56614 + vertex 0.803429 1.58124 2.56859 + vertex 0.801039 1.58369 2.56597 + endloop + endfacet + facet normal -0.734829 0.0440029 0.676824 + outer loop + vertex 0.801039 1.58369 2.56597 + vertex 0.79856 1.58113 2.56344 + vertex 0.800898 1.5787 2.56614 + endloop + endfacet + facet normal -0.735128 0.0433978 0.676538 + outer loop + vertex 0.79856 1.58113 2.56344 + vertex 0.798422 1.57613 2.56361 + vertex 0.800898 1.5787 2.56614 + endloop + endfacet + facet normal -0.733524 0.0399242 0.67849 + outer loop + vertex 0.800898 1.5787 2.56614 + vertex 0.798422 1.57613 2.56361 + vertex 0.800772 1.5737 2.56629 + endloop + endfacet + facet normal -0.717258 0.0400541 0.695655 + outer loop + vertex 0.800772 1.5737 2.56629 + vertex 0.80329 1.57623 2.56874 + vertex 0.800898 1.5787 2.56614 + endloop + endfacet + facet normal -0.715739 0.0368679 0.697394 + outer loop + vertex 0.803167 1.57123 2.56888 + vertex 0.80329 1.57623 2.56874 + vertex 0.800772 1.5737 2.56629 + endloop + endfacet + facet normal -0.716973 0.0344649 0.696249 + outer loop + vertex 0.800662 1.5687 2.56643 + vertex 0.803167 1.57123 2.56888 + vertex 0.800772 1.5737 2.56629 + endloop + endfacet + facet normal -0.731739 0.0343723 0.680718 + outer loop + vertex 0.800772 1.5737 2.56629 + vertex 0.7983 1.57114 2.56377 + vertex 0.800662 1.5687 2.56643 + endloop + endfacet + facet normal -0.732178 0.0334803 0.68029 + outer loop + vertex 0.7983 1.57114 2.56377 + vertex 0.798198 1.56615 2.5639 + vertex 0.800662 1.5687 2.56643 + endloop + endfacet + facet normal -0.730017 0.0288766 0.682818 + outer loop + vertex 0.800662 1.5687 2.56643 + vertex 0.798198 1.56615 2.5639 + vertex 0.800569 1.56371 2.56654 + endloop + endfacet + facet normal -0.715917 0.0289479 0.697585 + outer loop + vertex 0.800569 1.56371 2.56654 + vertex 0.803062 1.56623 2.56899 + vertex 0.800662 1.5687 2.56643 + endloop + endfacet + facet normal -0.714843 0.0267318 0.698774 + outer loop + vertex 0.80297 1.56124 2.56909 + vertex 0.803062 1.56623 2.56899 + vertex 0.800569 1.56371 2.56654 + endloop + endfacet + facet normal -0.715133 0.0261652 0.698499 + outer loop + vertex 0.800488 1.55872 2.56664 + vertex 0.80297 1.56124 2.56909 + vertex 0.800569 1.56371 2.56654 + endloop + endfacet + facet normal -0.728939 0.026091 0.684081 + outer loop + vertex 0.800569 1.56371 2.56654 + vertex 0.798115 1.56118 2.56402 + vertex 0.800488 1.55872 2.56664 + endloop + endfacet + facet normal -0.729541 0.0248735 0.683485 + outer loop + vertex 0.798115 1.56118 2.56402 + vertex 0.798047 1.5562 2.56413 + vertex 0.800488 1.55872 2.56664 + endloop + endfacet + facet normal -0.729527 0.0248456 0.6835 + outer loop + vertex 0.800488 1.55872 2.56664 + vertex 0.798047 1.5562 2.56413 + vertex 0.800413 1.55374 2.56675 + endloop + endfacet + facet normal -0.715082 0.0249361 0.698595 + outer loop + vertex 0.800413 1.55374 2.56675 + vertex 0.802883 1.55625 2.56918 + vertex 0.800488 1.55872 2.56664 + endloop + endfacet + facet normal -0.715162 0.0251008 0.698507 + outer loop + vertex 0.802798 1.55126 2.56928 + vertex 0.802883 1.55625 2.56918 + vertex 0.800413 1.55374 2.56675 + endloop + endfacet + facet normal -0.716143 0.0232043 0.697568 + outer loop + vertex 0.800341 1.54876 2.56684 + vertex 0.802798 1.55126 2.56928 + vertex 0.800413 1.55374 2.56675 + endloop + endfacet + facet normal -0.731664 0.0231328 0.681273 + outer loop + vertex 0.800413 1.55374 2.56675 + vertex 0.797987 1.55123 2.56422 + vertex 0.800341 1.54876 2.56684 + endloop + endfacet + facet normal -0.733856 0.018685 0.679048 + outer loop + vertex 0.797987 1.55123 2.56422 + vertex 0.797929 1.54626 2.5643 + vertex 0.800341 1.54876 2.56684 + endloop + endfacet + facet normal -0.734684 0.0204453 0.678101 + outer loop + vertex 0.800341 1.54876 2.56684 + vertex 0.797929 1.54626 2.5643 + vertex 0.800265 1.54378 2.5669 + endloop + endfacet + facet normal -0.718617 0.0204321 0.695106 + outer loop + vertex 0.800265 1.54378 2.5669 + vertex 0.802713 1.54626 2.56936 + vertex 0.800341 1.54876 2.56684 + endloop + endfacet + facet normal -0.718961 0.0211459 0.694729 + outer loop + vertex 0.802632 1.54125 2.56943 + vertex 0.802713 1.54626 2.56936 + vertex 0.800265 1.54378 2.5669 + endloop + endfacet + facet normal -0.720613 0.0179696 0.693104 + outer loop + vertex 0.800188 1.53878 2.56695 + vertex 0.802632 1.54125 2.56943 + vertex 0.800265 1.54378 2.5669 + endloop + endfacet + facet normal -0.737814 0.0180491 0.674762 + outer loop + vertex 0.800265 1.54378 2.5669 + vertex 0.79786 1.54131 2.56434 + vertex 0.800188 1.53878 2.56695 + endloop + endfacet + facet normal -0.739012 0.0156498 0.673511 + outer loop + vertex 0.79786 1.54131 2.56434 + vertex 0.797786 1.53632 2.56438 + vertex 0.800188 1.53878 2.56695 + endloop + endfacet + facet normal -0.738973 0.0155644 0.673555 + outer loop + vertex 0.800188 1.53878 2.56695 + vertex 0.797786 1.53632 2.56438 + vertex 0.800142 1.53375 2.56702 + endloop + endfacet + facet normal -0.722155 0.0156401 0.691554 + outer loop + vertex 0.800142 1.53375 2.56702 + vertex 0.802568 1.53624 2.5695 + vertex 0.800188 1.53878 2.56695 + endloop + endfacet + facet normal -0.721725 0.014756 0.692022 + outer loop + vertex 0.802557 1.53127 2.56959 + vertex 0.802568 1.53624 2.5695 + vertex 0.800142 1.53375 2.56702 + endloop + endfacet + facet normal -0.722066 0.0140724 0.691681 + outer loop + vertex 0.800188 1.52865 2.56717 + vertex 0.802557 1.53127 2.56959 + vertex 0.800142 1.53375 2.56702 + endloop + endfacet + facet normal -0.73719 0.0134545 0.675552 + outer loop + vertex 0.800142 1.53375 2.56702 + vertex 0.797742 1.53128 2.56445 + vertex 0.800188 1.52865 2.56717 + endloop + endfacet + facet normal -0.735627 0.0165996 0.677183 + outer loop + vertex 0.797742 1.53128 2.56445 + vertex 0.797753 1.52611 2.56459 + vertex 0.800188 1.52865 2.56717 + endloop + endfacet + facet normal -0.732431 0.00988772 0.680769 + outer loop + vertex 0.800188 1.52865 2.56717 + vertex 0.797753 1.52611 2.56459 + vertex 0.800487 1.52313 2.56757 + endloop + endfacet + facet normal -0.720667 0.0114293 0.693187 + outer loop + vertex 0.800487 1.52313 2.56757 + vertex 0.802649 1.52647 2.56977 + vertex 0.800188 1.52865 2.56717 + endloop + endfacet + facet normal -0.717965 0.00781804 0.696035 + outer loop + vertex 0.802958 1.52279 2.57013 + vertex 0.802649 1.52647 2.56977 + vertex 0.800487 1.52313 2.56757 + endloop + endfacet + facet normal -0.718171 0.00491794 0.69585 + outer loop + vertex 0.802958 1.52279 2.57013 + vertex 0.800487 1.52313 2.56757 + vertex 0.802448 1.5193 2.56962 + endloop + endfacet + facet normal -0.716261 0.0069401 0.697798 + outer loop + vertex 0.800487 1.52313 2.56757 + vertex 0.799936 1.51785 2.56706 + vertex 0.802448 1.5193 2.56962 + endloop + endfacet + facet normal -0.71437 0.000151756 0.699768 + outer loop + vertex 0.799936 1.51785 2.56706 + vertex 0.802174 1.51415 2.56935 + vertex 0.802448 1.5193 2.56962 + endloop + endfacet + facet normal -0.705552 -0.000797529 0.708658 + outer loop + vertex 0.802174 1.51415 2.56935 + vertex 0.804802 1.51719 2.57197 + vertex 0.802448 1.5193 2.56962 + endloop + endfacet + facet normal -0.713622 0.00107497 0.70053 + outer loop + vertex 0.799482 1.51373 2.5666 + vertex 0.802174 1.51415 2.56935 + vertex 0.799936 1.51785 2.56706 + endloop + endfacet + facet normal -0.727834 0.00427078 0.68574 + outer loop + vertex 0.799936 1.51785 2.56706 + vertex 0.797483 1.51606 2.56447 + vertex 0.799482 1.51373 2.5666 + endloop + endfacet + facet normal -0.73178 -0.00295104 0.681535 + outer loop + vertex 0.797483 1.51606 2.56447 + vertex 0.797555 1.51136 2.56452 + vertex 0.799482 1.51373 2.5666 + endloop + endfacet + facet normal -0.728025 -0.00948517 0.685485 + outer loop + vertex 0.799482 1.51373 2.5666 + vertex 0.797555 1.51136 2.56452 + vertex 0.800351 1.50933 2.56747 + endloop + endfacet + facet normal -0.727771 -0.00873176 0.685765 + outer loop + vertex 0.797555 1.51136 2.56452 + vertex 0.797692 1.50644 2.56461 + vertex 0.800351 1.50933 2.56747 + endloop + endfacet + facet normal -0.729308 -0.00572569 0.684162 + outer loop + vertex 0.800351 1.50933 2.56747 + vertex 0.797692 1.50644 2.56461 + vertex 0.800134 1.50387 2.56719 + endloop + endfacet + facet normal -0.71492 -0.00705888 0.69917 + outer loop + vertex 0.800134 1.50387 2.56719 + vertex 0.80255 1.50598 2.56968 + vertex 0.800351 1.50933 2.56747 + endloop + endfacet + facet normal -0.712689 -0.00407267 0.701469 + outer loop + vertex 0.802976 1.50985 2.57014 + vertex 0.800351 1.50933 2.56747 + vertex 0.80255 1.50598 2.56968 + endloop + endfacet + facet normal -0.705336 -0.00574985 0.70885 + outer loop + vertex 0.80255 1.50598 2.56968 + vertex 0.804554 1.50776 2.57169 + vertex 0.802976 1.50985 2.57014 + endloop + endfacet + facet normal -0.705139 -0.00618662 0.709042 + outer loop + vertex 0.804554 1.50776 2.57169 + vertex 0.80255 1.50598 2.56968 + vertex 0.804847 1.50376 2.57195 + endloop + endfacet + facet normal -0.705396 -0.00671876 0.708781 + outer loop + vertex 0.80255 1.50598 2.56968 + vertex 0.802513 1.50126 2.5696 + vertex 0.804847 1.50376 2.57195 + endloop + endfacet + facet normal -0.705465 -0.00659123 0.708714 + outer loop + vertex 0.804847 1.50376 2.57195 + vertex 0.802513 1.50126 2.5696 + vertex 0.804969 1.49883 2.57202 + endloop + endfacet + facet normal -0.712698 -0.00398331 0.70146 + outer loop + vertex 0.802976 1.50985 2.57014 + vertex 0.802174 1.51415 2.56935 + vertex 0.800351 1.50933 2.56747 + endloop + endfacet + facet normal -0.715173 -0.00647147 0.698918 + outer loop + vertex 0.802513 1.50126 2.5696 + vertex 0.80255 1.50598 2.56968 + vertex 0.800134 1.50387 2.56719 + endloop + endfacet + facet normal -0.715652 -0.00737188 0.698418 + outer loop + vertex 0.800104 1.49884 2.56711 + vertex 0.802513 1.50126 2.5696 + vertex 0.800134 1.50387 2.56719 + endloop + endfacet + facet normal -0.731341 -0.00700141 0.681976 + outer loop + vertex 0.800134 1.50387 2.56719 + vertex 0.79769 1.50139 2.56454 + vertex 0.800104 1.49884 2.56711 + endloop + endfacet + facet normal -0.73186 -0.00806588 0.681407 + outer loop + vertex 0.79769 1.50139 2.56454 + vertex 0.797707 1.49641 2.5645 + vertex 0.800104 1.49884 2.56711 + endloop + endfacet + facet normal -0.731271 -0.00930502 0.682023 + outer loop + vertex 0.800104 1.49884 2.56711 + vertex 0.797707 1.49641 2.5645 + vertex 0.800131 1.49386 2.56707 + endloop + endfacet + facet normal -0.716094 -0.00934232 0.697942 + outer loop + vertex 0.800131 1.49386 2.56707 + vertex 0.802547 1.49631 2.56958 + vertex 0.800104 1.49884 2.56711 + endloop + endfacet + facet normal -0.715078 -0.0113809 0.698952 + outer loop + vertex 0.802598 1.49133 2.56955 + vertex 0.802547 1.49631 2.56958 + vertex 0.800131 1.49386 2.56707 + endloop + endfacet + facet normal -0.716303 -0.0138441 0.697652 + outer loop + vertex 0.800184 1.48889 2.56702 + vertex 0.802598 1.49133 2.56955 + vertex 0.800131 1.49386 2.56707 + endloop + endfacet + facet normal -0.730147 -0.0138624 0.68315 + outer loop + vertex 0.800131 1.49386 2.56707 + vertex 0.797746 1.49143 2.56447 + vertex 0.800184 1.48889 2.56702 + endloop + endfacet + facet normal -0.731744 -0.0171836 0.681362 + outer loop + vertex 0.797746 1.49143 2.56447 + vertex 0.797807 1.48644 2.56441 + vertex 0.800184 1.48889 2.56702 + endloop + endfacet + facet normal -0.730656 -0.0194222 0.68247 + outer loop + vertex 0.800184 1.48889 2.56702 + vertex 0.797807 1.48644 2.56441 + vertex 0.800254 1.48389 2.56696 + endloop + endfacet + facet normal -0.716364 -0.0194239 0.697457 + outer loop + vertex 0.800254 1.48389 2.56696 + vertex 0.802661 1.48635 2.5695 + vertex 0.800184 1.48889 2.56702 + endloop + endfacet + facet normal -0.715716 -0.0207094 0.698085 + outer loop + vertex 0.802735 1.48136 2.56942 + vertex 0.802661 1.48635 2.5695 + vertex 0.800254 1.48389 2.56696 + endloop + endfacet + facet normal -0.716724 -0.02277 0.696985 + outer loop + vertex 0.800334 1.47888 2.56687 + vertex 0.802735 1.48136 2.56942 + vertex 0.800254 1.48389 2.56696 + endloop + endfacet + facet normal -0.733209 -0.022747 0.679623 + outer loop + vertex 0.800254 1.48389 2.56696 + vertex 0.797887 1.48141 2.56432 + vertex 0.800334 1.47888 2.56687 + endloop + endfacet + facet normal -0.734206 -0.0248748 0.678471 + outer loop + vertex 0.797887 1.48141 2.56432 + vertex 0.797972 1.47638 2.56423 + vertex 0.800334 1.47888 2.56687 + endloop + endfacet + facet normal -0.73511 -0.0230554 0.677556 + outer loop + vertex 0.800334 1.47888 2.56687 + vertex 0.797972 1.47638 2.56423 + vertex 0.800417 1.47387 2.56679 + endloop + endfacet + facet normal -0.716862 -0.0230595 0.696834 + outer loop + vertex 0.800417 1.47387 2.56679 + vertex 0.802816 1.47637 2.56934 + vertex 0.800334 1.47888 2.56687 + endloop + endfacet + facet normal -0.716649 -0.0234734 0.697039 + outer loop + vertex 0.802903 1.47138 2.56927 + vertex 0.802816 1.47637 2.56934 + vertex 0.800417 1.47387 2.56679 + endloop + endfacet + facet normal -0.716949 -0.0241011 0.696709 + outer loop + vertex 0.80051 1.46886 2.56672 + vertex 0.802903 1.47138 2.56927 + vertex 0.800417 1.47387 2.56679 + endloop + endfacet + facet normal -0.735934 -0.0241361 0.676623 + outer loop + vertex 0.800417 1.47387 2.56679 + vertex 0.798061 1.47134 2.56414 + vertex 0.80051 1.46886 2.56672 + endloop + endfacet + facet normal -0.736553 -0.0254943 0.6759 + outer loop + vertex 0.798061 1.47134 2.56414 + vertex 0.798165 1.46632 2.56406 + vertex 0.80051 1.46886 2.56672 + endloop + endfacet + facet normal -0.734506 -0.0295344 0.677959 + outer loop + vertex 0.80051 1.46886 2.56672 + vertex 0.798165 1.46632 2.56406 + vertex 0.800621 1.46386 2.56662 + endloop + endfacet + facet normal -0.716105 -0.0294978 0.697369 + outer loop + vertex 0.800621 1.46386 2.56662 + vertex 0.803005 1.46639 2.56917 + vertex 0.80051 1.46886 2.56672 + endloop + endfacet + facet normal -0.714207 -0.0330881 0.699152 + outer loop + vertex 0.803124 1.4614 2.56906 + vertex 0.803005 1.46639 2.56917 + vertex 0.800621 1.46386 2.56662 + endloop + endfacet + facet normal -0.715811 -0.0365256 0.697339 + outer loop + vertex 0.800751 1.45887 2.56649 + vertex 0.803124 1.4614 2.56906 + vertex 0.800621 1.46386 2.56662 + endloop + endfacet + facet normal -0.733213 -0.0365068 0.679018 + outer loop + vertex 0.800621 1.46386 2.56662 + vertex 0.798293 1.46131 2.56397 + vertex 0.800751 1.45887 2.56649 + endloop + endfacet + facet normal -0.734547 -0.0395188 0.677407 + outer loop + vertex 0.798293 1.46131 2.56397 + vertex 0.798433 1.45631 2.56383 + vertex 0.800751 1.45887 2.56649 + endloop + endfacet + facet normal -0.733653 -0.04123 0.678272 + outer loop + vertex 0.800751 1.45887 2.56649 + vertex 0.798433 1.45631 2.56383 + vertex 0.800886 1.45388 2.56633 + endloop + endfacet + facet normal -0.715769 -0.04134 0.697113 + outer loop + vertex 0.800886 1.45388 2.56633 + vertex 0.803257 1.45642 2.56892 + vertex 0.800751 1.45887 2.56649 + endloop + endfacet + facet normal -0.715937 -0.0410258 0.696959 + outer loop + vertex 0.803394 1.45142 2.56876 + vertex 0.803257 1.45642 2.56892 + vertex 0.800886 1.45388 2.56633 + endloop + endfacet + facet normal -0.71647 -0.0421809 0.696342 + outer loop + vertex 0.801018 1.44888 2.56617 + vertex 0.803394 1.45142 2.56876 + vertex 0.800886 1.45388 2.56633 + endloop + endfacet + facet normal -0.733684 -0.0420292 0.678189 + outer loop + vertex 0.800886 1.45388 2.56633 + vertex 0.798566 1.45132 2.56366 + vertex 0.801018 1.44888 2.56617 + endloop + endfacet + facet normal -0.73316 -0.0408447 0.678828 + outer loop + vertex 0.798566 1.45132 2.56366 + vertex 0.798693 1.44633 2.5635 + vertex 0.801018 1.44888 2.56617 + endloop + endfacet + facet normal -0.733499 -0.0401931 0.678501 + outer loop + vertex 0.801018 1.44888 2.56617 + vertex 0.798693 1.44633 2.5635 + vertex 0.80115 1.44389 2.56601 + endloop + endfacet + facet normal -0.71719 -0.0402878 0.695712 + outer loop + vertex 0.80115 1.44389 2.56601 + vertex 0.80353 1.44642 2.56861 + vertex 0.801018 1.44888 2.56617 + endloop + endfacet + facet normal -0.717155 -0.040355 0.695745 + outer loop + vertex 0.803675 1.44143 2.56847 + vertex 0.80353 1.44642 2.56861 + vertex 0.80115 1.44389 2.56601 + endloop + endfacet + facet normal -0.716892 -0.0397823 0.696048 + outer loop + vertex 0.801296 1.43893 2.56588 + vertex 0.803675 1.44143 2.56847 + vertex 0.80115 1.44389 2.56601 + endloop + endfacet + facet normal -0.732302 -0.0398014 0.679816 + outer loop + vertex 0.80115 1.44389 2.56601 + vertex 0.798827 1.44137 2.56336 + vertex 0.801296 1.43893 2.56588 + endloop + endfacet + facet normal -0.732242 -0.0396659 0.679888 + outer loop + vertex 0.798827 1.44137 2.56336 + vertex 0.798978 1.43642 2.56324 + vertex 0.801296 1.43893 2.56588 + endloop + endfacet + facet normal -0.731169 -0.0417396 0.680918 + outer loop + vertex 0.801296 1.43893 2.56588 + vertex 0.798978 1.43642 2.56324 + vertex 0.801459 1.43398 2.56575 + endloop + endfacet + facet normal -0.71558 -0.0416553 0.697287 + outer loop + vertex 0.801459 1.43398 2.56575 + vertex 0.803836 1.43647 2.56834 + vertex 0.801296 1.43893 2.56588 + endloop + endfacet + facet normal -0.714207 -0.044263 0.698534 + outer loop + vertex 0.804 1.43151 2.56819 + vertex 0.803836 1.43647 2.56834 + vertex 0.801459 1.43398 2.56575 + endloop + endfacet + facet normal -0.714497 -0.0448952 0.698197 + outer loop + vertex 0.801616 1.42897 2.56559 + vertex 0.804 1.43151 2.56819 + vertex 0.801459 1.43398 2.56575 + endloop + endfacet + facet normal -0.73022 -0.0448622 0.681738 + outer loop + vertex 0.801459 1.43398 2.56575 + vertex 0.79913 1.43141 2.56309 + vertex 0.801616 1.42897 2.56559 + endloop + endfacet + facet normal -0.731061 -0.0467859 0.680706 + outer loop + vertex 0.79913 1.43141 2.56309 + vertex 0.799258 1.42623 2.56287 + vertex 0.801616 1.42897 2.56559 + endloop + endfacet + facet normal -0.730924 -0.047033 0.680836 + outer loop + vertex 0.801616 1.42897 2.56559 + vertex 0.799258 1.42623 2.56287 + vertex 0.801748 1.42391 2.56538 + endloop + endfacet + facet normal -0.713906 -0.0473261 0.69864 + outer loop + vertex 0.801748 1.42391 2.56538 + vertex 0.804143 1.42653 2.56801 + vertex 0.801616 1.42897 2.56559 + endloop + endfacet + facet normal -0.712588 -0.0497106 0.699819 + outer loop + vertex 0.804259 1.42148 2.56777 + vertex 0.804143 1.42653 2.56801 + vertex 0.801748 1.42391 2.56538 + endloop + endfacet + facet normal -0.713681 -0.0521136 0.698529 + outer loop + vertex 0.801812 1.41876 2.56506 + vertex 0.804259 1.42148 2.56777 + vertex 0.801748 1.42391 2.56538 + endloop + endfacet + facet normal -0.727388 -0.051407 0.684299 + outer loop + vertex 0.801748 1.42391 2.56538 + vertex 0.799441 1.42112 2.56272 + vertex 0.801812 1.41876 2.56506 + endloop + endfacet + facet normal -0.72779 -0.0523035 0.683803 + outer loop + vertex 0.799441 1.42112 2.56272 + vertex 0.799461 1.41627 2.56237 + vertex 0.801812 1.41876 2.56506 + endloop + endfacet + facet normal -0.725575 -0.0565733 0.685813 + outer loop + vertex 0.801812 1.41876 2.56506 + vertex 0.799461 1.41627 2.56237 + vertex 0.801717 1.4132 2.5645 + endloop + endfacet + facet normal -0.714115 -0.0579578 0.697625 + outer loop + vertex 0.801717 1.4132 2.5645 + vertex 0.804399 1.41636 2.56751 + vertex 0.801812 1.41876 2.56506 + endloop + endfacet + facet normal -0.71358 -0.0588602 0.698096 + outer loop + vertex 0.804812 1.41138 2.56751 + vertex 0.804399 1.41636 2.56751 + vertex 0.801717 1.4132 2.5645 + endloop + endfacet + facet normal -0.714206 -0.0613483 0.697242 + outer loop + vertex 0.802734 1.40815 2.5651 + vertex 0.804812 1.41138 2.56751 + vertex 0.801717 1.4132 2.5645 + endloop + endfacet + facet normal -0.724482 -0.0647239 0.686248 + outer loop + vertex 0.801717 1.4132 2.5645 + vertex 0.800001 1.40897 2.56229 + vertex 0.802734 1.40815 2.5651 + endloop + endfacet + facet normal -0.724739 -0.0673781 0.685721 + outer loop + vertex 0.802734 1.40815 2.5651 + vertex 0.800001 1.40897 2.56229 + vertex 0.800828 1.40409 2.56269 + endloop + endfacet + facet normal -0.751038 -0.074237 0.656072 + outer loop + vertex 0.800001 1.40897 2.56229 + vertex 0.798027 1.40617 2.55972 + vertex 0.800828 1.40409 2.56269 + endloop + endfacet + facet normal -0.750491 -0.0751073 0.656599 + outer loop + vertex 0.798027 1.40617 2.55972 + vertex 0.800001 1.40897 2.56229 + vertex 0.797977 1.41002 2.5601 + endloop + endfacet + facet normal -0.749787 -0.0711462 0.657844 + outer loop + vertex 0.799206 1.4124 2.56176 + vertex 0.797977 1.41002 2.5601 + vertex 0.800001 1.40897 2.56229 + endloop + endfacet + facet normal -0.727454 -0.0619979 0.683349 + outer loop + vertex 0.799206 1.4124 2.56176 + vertex 0.800001 1.40897 2.56229 + vertex 0.801717 1.4132 2.5645 + endloop + endfacet + facet normal -0.713059 -0.0628613 0.698281 + outer loop + vertex 0.805579 1.40688 2.56789 + vertex 0.804812 1.41138 2.56751 + vertex 0.802734 1.40815 2.5651 + endloop + endfacet + facet normal -0.713334 -0.0644075 0.697858 + outer loop + vertex 0.80389 1.40404 2.5659 + vertex 0.805579 1.40688 2.56789 + vertex 0.802734 1.40815 2.5651 + endloop + endfacet + facet normal -0.72782 -0.0600832 0.683131 + outer loop + vertex 0.799461 1.41627 2.56237 + vertex 0.799206 1.4124 2.56176 + vertex 0.801717 1.4132 2.5645 + endloop + endfacet + facet normal -0.730504 -0.0460219 0.681356 + outer loop + vertex 0.799258 1.42623 2.56287 + vertex 0.799441 1.42112 2.56272 + vertex 0.801748 1.42391 2.56538 + endloop + endfacet + facet normal -0.731488 -0.0424621 0.680531 + outer loop + vertex 0.798978 1.43642 2.56324 + vertex 0.79913 1.43141 2.56309 + vertex 0.801459 1.43398 2.56575 + endloop + endfacet + facet normal -0.732853 -0.0387356 0.679284 + outer loop + vertex 0.798693 1.44633 2.5635 + vertex 0.798827 1.44137 2.56336 + vertex 0.80115 1.44389 2.56601 + endloop + endfacet + facet normal -0.760731 -0.0386093 0.647918 + outer loop + vertex 0.798827 1.44137 2.56336 + vertex 0.798693 1.44633 2.5635 + vertex 0.796462 1.44386 2.56074 + endloop + endfacet + facet normal -0.760821 -0.0388185 0.6478 + outer loop + vertex 0.796606 1.43891 2.56061 + vertex 0.798827 1.44137 2.56336 + vertex 0.796462 1.44386 2.56074 + endloop + endfacet + facet normal -0.797608 -0.0387037 0.601933 + outer loop + vertex 0.796462 1.44386 2.56074 + vertex 0.794383 1.44155 2.55783 + vertex 0.796606 1.43891 2.56061 + endloop + endfacet + facet normal -0.799826 -0.0440579 0.598612 + outer loop + vertex 0.794383 1.44155 2.55783 + vertex 0.794537 1.43656 2.55767 + vertex 0.796606 1.43891 2.56061 + endloop + endfacet + facet normal -0.800617 -0.0422072 0.597688 + outer loop + vertex 0.796606 1.43891 2.56061 + vertex 0.794537 1.43656 2.55767 + vertex 0.796757 1.43391 2.56046 + endloop + endfacet + facet normal -0.761579 -0.0425086 0.646676 + outer loop + vertex 0.796757 1.43391 2.56046 + vertex 0.798978 1.43642 2.56324 + vertex 0.796606 1.43891 2.56061 + endloop + endfacet + facet normal -0.761649 -0.0423671 0.646604 + outer loop + vertex 0.79913 1.43141 2.56309 + vertex 0.798978 1.43642 2.56324 + vertex 0.796757 1.43391 2.56046 + endloop + endfacet + facet normal -0.763108 -0.0458024 0.644646 + outer loop + vertex 0.796867 1.42875 2.56022 + vertex 0.79913 1.43141 2.56309 + vertex 0.796757 1.43391 2.56046 + endloop + endfacet + facet normal -0.804279 -0.044302 0.592598 + outer loop + vertex 0.796757 1.43391 2.56046 + vertex 0.794679 1.43149 2.55746 + vertex 0.796867 1.42875 2.56022 + endloop + endfacet + facet normal -0.806064 -0.0485019 0.589837 + outer loop + vertex 0.794679 1.43149 2.55746 + vertex 0.794739 1.42642 2.55712 + vertex 0.796867 1.42875 2.56022 + endloop + endfacet + facet normal -0.808148 -0.0433321 0.587383 + outer loop + vertex 0.796867 1.42875 2.56022 + vertex 0.794739 1.42642 2.55712 + vertex 0.796836 1.42301 2.55975 + endloop + endfacet + facet normal -0.763852 -0.048138 0.643594 + outer loop + vertex 0.796836 1.42301 2.55975 + vertex 0.799258 1.42623 2.56287 + vertex 0.796867 1.42875 2.56022 + endloop + endfacet + facet normal -0.764988 -0.0461221 0.64239 + outer loop + vertex 0.799441 1.42112 2.56272 + vertex 0.799258 1.42623 2.56287 + vertex 0.796836 1.42301 2.55975 + endloop + endfacet + facet normal -0.762025 -0.0354699 0.646575 + outer loop + vertex 0.797643 1.41842 2.56045 + vertex 0.799441 1.42112 2.56272 + vertex 0.796836 1.42301 2.55975 + endloop + endfacet + facet normal -0.80024 -0.0496405 0.597621 + outer loop + vertex 0.796836 1.42301 2.55975 + vertex 0.795452 1.41806 2.55749 + vertex 0.797643 1.41842 2.56045 + endloop + endfacet + facet normal -0.800311 -0.0489153 0.597587 + outer loop + vertex 0.795452 1.41806 2.55749 + vertex 0.797185 1.41389 2.55947 + vertex 0.797643 1.41842 2.56045 + endloop + endfacet + facet normal -0.759035 -0.0640124 0.647895 + outer loop + vertex 0.797185 1.41389 2.55947 + vertex 0.799461 1.41627 2.56237 + vertex 0.797643 1.41842 2.56045 + endloop + endfacet + facet normal -0.764996 -0.0511213 0.642003 + outer loop + vertex 0.799206 1.4124 2.56176 + vertex 0.799461 1.41627 2.56237 + vertex 0.797185 1.41389 2.55947 + endloop + endfacet + facet normal -0.809538 -0.0591486 0.58408 + outer loop + vertex 0.79506 1.41359 2.55649 + vertex 0.797185 1.41389 2.55947 + vertex 0.795452 1.41806 2.55749 + endloop + endfacet + facet normal -0.846585 -0.0439639 0.530435 + outer loop + vertex 0.795452 1.41806 2.55749 + vertex 0.793476 1.41606 2.55417 + vertex 0.79506 1.41359 2.55649 + endloop + endfacet + facet normal -0.85374 -0.0610698 0.517106 + outer loop + vertex 0.793476 1.41606 2.55417 + vertex 0.793581 1.41136 2.55379 + vertex 0.79506 1.41359 2.55649 + endloop + endfacet + facet normal -0.847669 -0.0749387 0.525206 + outer loop + vertex 0.79506 1.41359 2.55649 + vertex 0.793581 1.41136 2.55379 + vertex 0.795862 1.4092 2.55716 + endloop + endfacet + facet normal -0.844977 -0.0629044 0.53109 + outer loop + vertex 0.793581 1.41136 2.55379 + vertex 0.793822 1.40642 2.55359 + vertex 0.795862 1.4092 2.55716 + endloop + endfacet + facet normal -0.847346 -0.057144 0.527958 + outer loop + vertex 0.795862 1.4092 2.55716 + vertex 0.793822 1.40642 2.55359 + vertex 0.79589 1.4038 2.55662 + endloop + endfacet + facet normal -0.847476 -0.0575391 0.527706 + outer loop + vertex 0.793822 1.40642 2.55359 + vertex 0.794003 1.4014 2.55333 + vertex 0.79589 1.4038 2.55662 + endloop + endfacet + facet normal -0.84867 -0.0544208 0.526115 + outer loop + vertex 0.79589 1.4038 2.55662 + vertex 0.794003 1.4014 2.55333 + vertex 0.796024 1.39881 2.55632 + endloop + endfacet + facet normal -0.841631 -0.0593616 0.53678 + outer loop + vertex 0.793476 1.41606 2.55417 + vertex 0.795452 1.41806 2.55749 + vertex 0.793584 1.41994 2.55477 + endloop + endfacet + facet normal -0.841348 -0.0582557 0.537346 + outer loop + vertex 0.794648 1.42222 2.55668 + vertex 0.793584 1.41994 2.55477 + vertex 0.795452 1.41806 2.55749 + endloop + endfacet + facet normal -0.809551 -0.0590075 0.584076 + outer loop + vertex 0.797185 1.41389 2.55947 + vertex 0.79506 1.41359 2.55649 + vertex 0.795862 1.4092 2.55716 + endloop + endfacet + facet normal -0.800905 -0.0668427 0.595049 + outer loop + vertex 0.797977 1.41002 2.5601 + vertex 0.797185 1.41389 2.55947 + vertex 0.795862 1.4092 2.55716 + endloop + endfacet + facet normal -0.80036 -0.0696837 0.595456 + outer loop + vertex 0.797977 1.41002 2.5601 + vertex 0.795862 1.4092 2.55716 + vertex 0.798027 1.40617 2.55972 + endloop + endfacet + facet normal -0.7976 -0.0640555 0.599775 + outer loop + vertex 0.79589 1.4038 2.55662 + vertex 0.798027 1.40617 2.55972 + vertex 0.795862 1.4092 2.55716 + endloop + endfacet + facet normal -0.798182 -0.0627085 0.599144 + outer loop + vertex 0.798166 1.40135 2.5594 + vertex 0.798027 1.40617 2.55972 + vertex 0.79589 1.4038 2.55662 + endloop + endfacet + facet normal -0.796323 -0.0576039 0.602122 + outer loop + vertex 0.796024 1.39881 2.55632 + vertex 0.798166 1.40135 2.5594 + vertex 0.79589 1.4038 2.55662 + endloop + endfacet + facet normal -0.765212 -0.0519119 0.641681 + outer loop + vertex 0.797977 1.41002 2.5601 + vertex 0.799206 1.4124 2.56176 + vertex 0.797185 1.41389 2.55947 + endloop + endfacet + facet normal -0.808653 -0.0423116 0.586762 + outer loop + vertex 0.794648 1.42222 2.55668 + vertex 0.795452 1.41806 2.55749 + vertex 0.796836 1.42301 2.55975 + endloop + endfacet + facet normal -0.752394 -0.0504635 0.656777 + outer loop + vertex 0.799461 1.41627 2.56237 + vertex 0.799441 1.42112 2.56272 + vertex 0.797643 1.41842 2.56045 + endloop + endfacet + facet normal -0.762978 -0.0460584 0.644781 + outer loop + vertex 0.799258 1.42623 2.56287 + vertex 0.79913 1.43141 2.56309 + vertex 0.796867 1.42875 2.56022 + endloop + endfacet + facet normal -0.802837 -0.0476451 0.594292 + outer loop + vertex 0.794537 1.43656 2.55767 + vertex 0.794679 1.43149 2.55746 + vertex 0.796757 1.43391 2.56046 + endloop + endfacet + facet normal -0.797273 -0.0395 0.602325 + outer loop + vertex 0.794239 1.44651 2.55797 + vertex 0.794383 1.44155 2.55783 + vertex 0.796462 1.44386 2.56074 + endloop + endfacet + facet normal -0.797009 -0.0388715 0.602715 + outer loop + vertex 0.796329 1.44882 2.56088 + vertex 0.794239 1.44651 2.55797 + vertex 0.796462 1.44386 2.56074 + endloop + endfacet + facet normal -0.79625 -0.0406719 0.603599 + outer loop + vertex 0.794096 1.45147 2.55811 + vertex 0.794239 1.44651 2.55797 + vertex 0.796329 1.44882 2.56088 + endloop + endfacet + facet normal -0.795967 -0.0399979 0.604017 + outer loop + vertex 0.796196 1.45381 2.56103 + vertex 0.794096 1.45147 2.55811 + vertex 0.796329 1.44882 2.56088 + endloop + endfacet + facet normal -0.761073 -0.0404224 0.647406 + outer loop + vertex 0.796329 1.44882 2.56088 + vertex 0.798566 1.45132 2.56366 + vertex 0.796196 1.45381 2.56103 + endloop + endfacet + facet normal -0.761493 -0.0414097 0.646848 + outer loop + vertex 0.798566 1.45132 2.56366 + vertex 0.798433 1.45631 2.56383 + vertex 0.796196 1.45381 2.56103 + endloop + endfacet + facet normal -0.761939 -0.0404912 0.646382 + outer loop + vertex 0.796196 1.45381 2.56103 + vertex 0.798433 1.45631 2.56383 + vertex 0.796049 1.45881 2.56117 + endloop + endfacet + facet normal -0.795408 -0.0403093 0.604732 + outer loop + vertex 0.796049 1.45881 2.56117 + vertex 0.793946 1.45647 2.55825 + vertex 0.796196 1.45381 2.56103 + endloop + endfacet + facet normal -0.796327 -0.0381507 0.603662 + outer loop + vertex 0.793783 1.46148 2.55835 + vertex 0.793946 1.45647 2.55825 + vertex 0.796049 1.45881 2.56117 + endloop + endfacet + facet normal -0.795072 -0.0351431 0.605496 + outer loop + vertex 0.795902 1.46382 2.56127 + vertex 0.793783 1.46148 2.55835 + vertex 0.796049 1.45881 2.56117 + endloop + endfacet + facet normal -0.763622 -0.0349753 0.644715 + outer loop + vertex 0.796049 1.45881 2.56117 + vertex 0.798293 1.46131 2.56397 + vertex 0.795902 1.46382 2.56127 + endloop + endfacet + facet normal -0.762363 -0.0320206 0.646357 + outer loop + vertex 0.798293 1.46131 2.56397 + vertex 0.798165 1.46632 2.56406 + vertex 0.795902 1.46382 2.56127 + endloop + endfacet + facet normal -0.764019 -0.0285059 0.644563 + outer loop + vertex 0.795902 1.46382 2.56127 + vertex 0.798165 1.46632 2.56406 + vertex 0.795778 1.46886 2.56135 + endloop + endfacet + facet normal -0.794907 -0.0286885 0.606053 + outer loop + vertex 0.795778 1.46886 2.56135 + vertex 0.793636 1.4665 2.55843 + vertex 0.795902 1.46382 2.56127 + endloop + endfacet + facet normal -0.79635 -0.0321105 0.603983 + outer loop + vertex 0.793636 1.4665 2.55843 + vertex 0.793783 1.46148 2.55835 + vertex 0.795902 1.46382 2.56127 + endloop + endfacet + facet normal -0.794636 -0.0293365 0.606377 + outer loop + vertex 0.793541 1.47151 2.55854 + vertex 0.793636 1.4665 2.55843 + vertex 0.795778 1.46886 2.56135 + endloop + endfacet + facet normal -0.793538 -0.0267745 0.607931 + outer loop + vertex 0.795684 1.47388 2.56145 + vertex 0.793541 1.47151 2.55854 + vertex 0.795778 1.46886 2.56135 + endloop + endfacet + facet normal -0.762113 -0.0269555 0.646882 + outer loop + vertex 0.795778 1.46886 2.56135 + vertex 0.798061 1.47134 2.56414 + vertex 0.795684 1.47388 2.56145 + endloop + endfacet + facet normal -0.761009 -0.0244351 0.64828 + outer loop + vertex 0.798061 1.47134 2.56414 + vertex 0.797972 1.47638 2.56423 + vertex 0.795684 1.47388 2.56145 + endloop + endfacet + facet normal -0.759582 -0.0274664 0.649831 + outer loop + vertex 0.795684 1.47388 2.56145 + vertex 0.797972 1.47638 2.56423 + vertex 0.795595 1.47888 2.56155 + endloop + endfacet + facet normal -0.791351 -0.0319405 0.610527 + outer loop + vertex 0.793501 1.47638 2.55875 + vertex 0.793541 1.47151 2.55854 + vertex 0.795684 1.47388 2.56145 + endloop + endfacet + facet normal -0.789371 -0.0272089 0.613314 + outer loop + vertex 0.795595 1.47888 2.56155 + vertex 0.793501 1.47638 2.55875 + vertex 0.795684 1.47388 2.56145 + endloop + endfacet + facet normal -0.788839 -0.0283649 0.613944 + outer loop + vertex 0.793361 1.48116 2.55879 + vertex 0.793501 1.47638 2.55875 + vertex 0.795595 1.47888 2.56155 + endloop + endfacet + facet normal -0.78824 -0.0267586 0.614785 + outer loop + vertex 0.795495 1.48388 2.56164 + vertex 0.793361 1.48116 2.55879 + vertex 0.795595 1.47888 2.56155 + endloop + endfacet + facet normal -0.757437 -0.0268189 0.652358 + outer loop + vertex 0.795595 1.47888 2.56155 + vertex 0.797887 1.48141 2.56432 + vertex 0.795495 1.48388 2.56164 + endloop + endfacet + facet normal -0.756078 -0.0236649 0.654053 + outer loop + vertex 0.797887 1.48141 2.56432 + vertex 0.797807 1.48644 2.56441 + vertex 0.795495 1.48388 2.56164 + endloop + endfacet + facet normal -0.756757 -0.0222541 0.653317 + outer loop + vertex 0.795495 1.48388 2.56164 + vertex 0.797807 1.48644 2.56441 + vertex 0.795421 1.48892 2.56173 + endloop + endfacet + facet normal -0.788979 -0.022065 0.614024 + outer loop + vertex 0.795421 1.48892 2.56173 + vertex 0.793216 1.48617 2.5588 + vertex 0.795495 1.48388 2.56164 + endloop + endfacet + facet normal -0.789647 -0.0238857 0.613096 + outer loop + vertex 0.793216 1.48617 2.5588 + vertex 0.793361 1.48116 2.55879 + vertex 0.795495 1.48388 2.56164 + endloop + endfacet + facet normal -0.762754 -0.0255828 0.646183 + outer loop + vertex 0.798165 1.46632 2.56406 + vertex 0.798061 1.47134 2.56414 + vertex 0.795778 1.46886 2.56135 + endloop + endfacet + facet normal -0.761487 -0.0394254 0.64698 + outer loop + vertex 0.798433 1.45631 2.56383 + vertex 0.798293 1.46131 2.56397 + vertex 0.796049 1.45881 2.56117 + endloop + endfacet + facet normal -0.795619 -0.040815 0.60442 + outer loop + vertex 0.793946 1.45647 2.55825 + vertex 0.794096 1.45147 2.55811 + vertex 0.796196 1.45381 2.56103 + endloop + endfacet + facet normal -0.76039 -0.039714 0.648252 + outer loop + vertex 0.798978 1.43642 2.56324 + vertex 0.798827 1.44137 2.56336 + vertex 0.796606 1.43891 2.56061 + endloop + endfacet + facet normal -0.760445 -0.0392049 0.648218 + outer loop + vertex 0.796462 1.44386 2.56074 + vertex 0.798693 1.44633 2.5635 + vertex 0.796329 1.44882 2.56088 + endloop + endfacet + facet normal -0.761016 -0.0405398 0.647465 + outer loop + vertex 0.798693 1.44633 2.5635 + vertex 0.798566 1.45132 2.56366 + vertex 0.796329 1.44882 2.56088 + endloop + endfacet + facet normal -0.733859 -0.041696 0.678021 + outer loop + vertex 0.798433 1.45631 2.56383 + vertex 0.798566 1.45132 2.56366 + vertex 0.800886 1.45388 2.56633 + endloop + endfacet + facet normal -0.735577 -0.0319256 0.676688 + outer loop + vertex 0.798165 1.46632 2.56406 + vertex 0.798293 1.46131 2.56397 + vertex 0.800621 1.46386 2.56662 + endloop + endfacet + facet normal -0.735766 -0.0244723 0.676794 + outer loop + vertex 0.797972 1.47638 2.56423 + vertex 0.798061 1.47134 2.56414 + vertex 0.800417 1.47387 2.56679 + endloop + endfacet + facet normal -0.758416 -0.0247821 0.6513 + outer loop + vertex 0.797972 1.47638 2.56423 + vertex 0.797887 1.48141 2.56432 + vertex 0.795595 1.47888 2.56155 + endloop + endfacet + facet normal -0.732713 -0.0237529 0.680123 + outer loop + vertex 0.797807 1.48644 2.56441 + vertex 0.797887 1.48141 2.56432 + vertex 0.800254 1.48389 2.56696 + endloop + endfacet + facet normal -0.754518 -0.0171525 0.656055 + outer loop + vertex 0.797807 1.48644 2.56441 + vertex 0.797746 1.49143 2.56447 + vertex 0.795421 1.48892 2.56173 + endloop + endfacet + facet normal -0.756094 -0.0138001 0.654318 + outer loop + vertex 0.795421 1.48892 2.56173 + vertex 0.797746 1.49143 2.56447 + vertex 0.795379 1.49393 2.56179 + endloop + endfacet + facet normal -0.787846 -0.0136224 0.615722 + outer loop + vertex 0.795379 1.49393 2.56179 + vertex 0.793193 1.49132 2.55893 + vertex 0.795421 1.48892 2.56173 + endloop + endfacet + facet normal -0.790195 -0.0195126 0.612544 + outer loop + vertex 0.793193 1.49132 2.55893 + vertex 0.793216 1.48617 2.5588 + vertex 0.795421 1.48892 2.56173 + endloop + endfacet + facet normal -0.790772 -0.0071903 0.612068 + outer loop + vertex 0.793179 1.49634 2.55897 + vertex 0.793193 1.49132 2.55893 + vertex 0.795379 1.49393 2.56179 + endloop + endfacet + facet normal -0.790879 -0.00745265 0.611927 + outer loop + vertex 0.795348 1.49891 2.56181 + vertex 0.793179 1.49634 2.55897 + vertex 0.795379 1.49393 2.56179 + endloop + endfacet + facet normal -0.755955 -0.00740754 0.654581 + outer loop + vertex 0.795379 1.49393 2.56179 + vertex 0.797707 1.49641 2.5645 + vertex 0.795348 1.49891 2.56181 + endloop + endfacet + facet normal -0.792197 -0.00448444 0.610249 + outer loop + vertex 0.793152 1.50131 2.55897 + vertex 0.793179 1.49634 2.55897 + vertex 0.795348 1.49891 2.56181 + endloop + endfacet + facet normal -0.793647 -0.00807926 0.608325 + outer loop + vertex 0.795319 1.50388 2.56184 + vertex 0.793152 1.50131 2.55897 + vertex 0.795348 1.49891 2.56181 + endloop + endfacet + facet normal -0.756096 -0.00813098 0.65441 + outer loop + vertex 0.795348 1.49891 2.56181 + vertex 0.79769 1.50139 2.56454 + vertex 0.795319 1.50388 2.56184 + endloop + endfacet + facet normal -0.756074 -0.00808119 0.654436 + outer loop + vertex 0.79769 1.50139 2.56454 + vertex 0.797692 1.50644 2.56461 + vertex 0.795319 1.50388 2.56184 + endloop + endfacet + facet normal -0.754435 -0.0115871 0.656272 + outer loop + vertex 0.795319 1.50388 2.56184 + vertex 0.797692 1.50644 2.56461 + vertex 0.795269 1.50886 2.56186 + endloop + endfacet + facet normal -0.792317 -0.0116979 0.609998 + outer loop + vertex 0.795269 1.50886 2.56186 + vertex 0.793109 1.50628 2.55901 + vertex 0.795319 1.50388 2.56184 + endloop + endfacet + facet normal -0.791583 -0.0133308 0.610916 + outer loop + vertex 0.793072 1.51127 2.55907 + vertex 0.793109 1.50628 2.55901 + vertex 0.795269 1.50886 2.56186 + endloop + endfacet + facet normal -0.789862 -0.00909348 0.613218 + outer loop + vertex 0.795218 1.51378 2.56187 + vertex 0.793072 1.51127 2.55907 + vertex 0.795269 1.50886 2.56186 + endloop + endfacet + facet normal -0.754281 -0.00880393 0.656492 + outer loop + vertex 0.795269 1.50886 2.56186 + vertex 0.797555 1.51136 2.56452 + vertex 0.795218 1.51378 2.56187 + endloop + endfacet + facet normal -0.751927 -0.00352579 0.659237 + outer loop + vertex 0.797555 1.51136 2.56452 + vertex 0.797483 1.51606 2.56447 + vertex 0.795218 1.51378 2.56187 + endloop + endfacet + facet normal -0.753942 0.0010901 0.656941 + outer loop + vertex 0.795218 1.51378 2.56187 + vertex 0.797483 1.51606 2.56447 + vertex 0.795236 1.51872 2.56189 + endloop + endfacet + facet normal -0.785202 0.00129837 0.619238 + outer loop + vertex 0.795236 1.51872 2.56189 + vertex 0.793051 1.51626 2.55912 + vertex 0.795218 1.51378 2.56187 + endloop + endfacet + facet normal -0.78754 0.00675922 0.616226 + outer loop + vertex 0.793081 1.52127 2.5591 + vertex 0.793051 1.51626 2.55912 + vertex 0.795236 1.51872 2.56189 + endloop + endfacet + facet normal -0.784068 0.0143759 0.620508 + outer loop + vertex 0.795309 1.52374 2.56186 + vertex 0.793081 1.52127 2.5591 + vertex 0.795236 1.51872 2.56189 + endloop + endfacet + facet normal -0.751291 0.0141001 0.65982 + outer loop + vertex 0.795236 1.51872 2.56189 + vertex 0.797664 1.52094 2.5646 + vertex 0.795309 1.52374 2.56186 + endloop + endfacet + facet normal -0.751021 0.0146162 0.660116 + outer loop + vertex 0.797664 1.52094 2.5646 + vertex 0.797753 1.52611 2.56459 + vertex 0.795309 1.52374 2.56186 + endloop + endfacet + facet normal -0.749531 0.0096395 0.661899 + outer loop + vertex 0.797483 1.51606 2.56447 + vertex 0.797664 1.52094 2.5646 + vertex 0.795236 1.51872 2.56189 + endloop + endfacet + facet normal -0.789777 -0.00928445 0.613324 + outer loop + vertex 0.793051 1.51626 2.55912 + vertex 0.793072 1.51127 2.55907 + vertex 0.795218 1.51378 2.56187 + endloop + endfacet + facet normal -0.753738 -0.00994498 0.6571 + outer loop + vertex 0.797692 1.50644 2.56461 + vertex 0.797555 1.51136 2.56452 + vertex 0.795269 1.50886 2.56186 + endloop + endfacet + facet normal -0.792185 -0.0113671 0.610176 + outer loop + vertex 0.793109 1.50628 2.55901 + vertex 0.793152 1.50131 2.55897 + vertex 0.795319 1.50388 2.56184 + endloop + endfacet + facet normal -0.754573 -0.0104127 0.656134 + outer loop + vertex 0.797746 1.49143 2.56447 + vertex 0.797707 1.49641 2.5645 + vertex 0.795379 1.49393 2.56179 + endloop + endfacet + facet normal -0.731804 -0.0104054 0.681436 + outer loop + vertex 0.797707 1.49641 2.5645 + vertex 0.797746 1.49143 2.56447 + vertex 0.800131 1.49386 2.56707 + endloop + endfacet + facet normal -0.756189 -0.00792715 0.654305 + outer loop + vertex 0.797707 1.49641 2.5645 + vertex 0.79769 1.50139 2.56454 + vertex 0.795348 1.49891 2.56181 + endloop + endfacet + facet normal -0.730649 -0.00845967 0.6827 + outer loop + vertex 0.797692 1.50644 2.56461 + vertex 0.79769 1.50139 2.56454 + vertex 0.800134 1.50387 2.56719 + endloop + endfacet + facet normal -0.715381 -0.00792234 0.69869 + outer loop + vertex 0.802547 1.49631 2.56958 + vertex 0.802513 1.50126 2.5696 + vertex 0.800104 1.49884 2.56711 + endloop + endfacet + facet normal -0.729193 0.00827876 0.684258 + outer loop + vertex 0.797664 1.52094 2.5646 + vertex 0.797483 1.51606 2.56447 + vertex 0.799936 1.51785 2.56706 + endloop + endfacet + facet normal -0.713257 -0.00355171 0.700894 + outer loop + vertex 0.802174 1.51415 2.56935 + vertex 0.799482 1.51373 2.5666 + vertex 0.800351 1.50933 2.56747 + endloop + endfacet + facet normal -0.728442 0.00945489 0.685042 + outer loop + vertex 0.800487 1.52313 2.56757 + vertex 0.797664 1.52094 2.5646 + vertex 0.799936 1.51785 2.56706 + endloop + endfacet + facet normal -0.730168 0.0143095 0.683118 + outer loop + vertex 0.797753 1.52611 2.56459 + vertex 0.797664 1.52094 2.5646 + vertex 0.800487 1.52313 2.56757 + endloop + endfacet + facet normal -0.720671 0.0114201 0.693183 + outer loop + vertex 0.802649 1.52647 2.56977 + vertex 0.802557 1.53127 2.56959 + vertex 0.800188 1.52865 2.56717 + endloop + endfacet + facet normal -0.738556 0.0163951 0.673992 + outer loop + vertex 0.797786 1.53632 2.56438 + vertex 0.797742 1.53128 2.56445 + vertex 0.800142 1.53375 2.56702 + endloop + endfacet + facet normal -0.736874 0.0160176 0.67584 + outer loop + vertex 0.797929 1.54626 2.5643 + vertex 0.79786 1.54131 2.56434 + vertex 0.800265 1.54378 2.5669 + endloop + endfacet + facet normal -0.731032 0.0217983 0.681995 + outer loop + vertex 0.798047 1.5562 2.56413 + vertex 0.797987 1.55123 2.56422 + vertex 0.800413 1.55374 2.56675 + endloop + endfacet + facet normal -0.751159 0.0246555 0.659661 + outer loop + vertex 0.798047 1.5562 2.56413 + vertex 0.798115 1.56118 2.56402 + vertex 0.795715 1.5587 2.56138 + endloop + endfacet + facet normal -0.753511 0.0196928 0.65714 + outer loop + vertex 0.795648 1.55371 2.56145 + vertex 0.798047 1.5562 2.56413 + vertex 0.795715 1.5587 2.56138 + endloop + endfacet + facet normal -0.783285 0.0195813 0.621354 + outer loop + vertex 0.795715 1.5587 2.56138 + vertex 0.793419 1.55634 2.55856 + vertex 0.795648 1.55371 2.56145 + endloop + endfacet + facet normal -0.787603 0.0101476 0.616099 + outer loop + vertex 0.793419 1.55634 2.55856 + vertex 0.793295 1.55118 2.55849 + vertex 0.795648 1.55371 2.56145 + endloop + endfacet + facet normal -0.789824 0.0157009 0.613133 + outer loop + vertex 0.795648 1.55371 2.56145 + vertex 0.793295 1.55118 2.55849 + vertex 0.7956 1.5487 2.56152 + endloop + endfacet + facet normal -0.756961 0.0159236 0.653266 + outer loop + vertex 0.7956 1.5487 2.56152 + vertex 0.797987 1.55123 2.56422 + vertex 0.795648 1.55371 2.56145 + endloop + endfacet + facet normal -0.754347 0.0215873 0.656121 + outer loop + vertex 0.797987 1.55123 2.56422 + vertex 0.798047 1.5562 2.56413 + vertex 0.795648 1.55371 2.56145 + endloop + endfacet + facet normal -0.758133 0.0185614 0.651836 + outer loop + vertex 0.797929 1.54626 2.5643 + vertex 0.797987 1.55123 2.56422 + vertex 0.7956 1.5487 2.56152 + endloop + endfacet + facet normal -0.759984 0.0144552 0.649781 + outer loop + vertex 0.795563 1.54376 2.56159 + vertex 0.797929 1.54626 2.5643 + vertex 0.7956 1.5487 2.56152 + endloop + endfacet + facet normal -0.791169 0.0141705 0.611434 + outer loop + vertex 0.7956 1.5487 2.56152 + vertex 0.793309 1.54611 2.55862 + vertex 0.795563 1.54376 2.56159 + endloop + endfacet + facet normal -0.791534 0.0132499 0.610982 + outer loop + vertex 0.793309 1.54611 2.55862 + vertex 0.793309 1.54128 2.55872 + vertex 0.795563 1.54376 2.56159 + endloop + endfacet + facet normal -0.792058 0.0145453 0.610272 + outer loop + vertex 0.795563 1.54376 2.56159 + vertex 0.793309 1.54128 2.55872 + vertex 0.795495 1.53884 2.56162 + endloop + endfacet + facet normal -0.761522 0.0143406 0.647981 + outer loop + vertex 0.795495 1.53884 2.56162 + vertex 0.79786 1.54131 2.56434 + vertex 0.795563 1.54376 2.56159 + endloop + endfacet + facet normal -0.762156 0.0158133 0.6472 + outer loop + vertex 0.797786 1.53632 2.56438 + vertex 0.79786 1.54131 2.56434 + vertex 0.795495 1.53884 2.56162 + endloop + endfacet + facet normal -0.761267 0.0177156 0.648196 + outer loop + vertex 0.795419 1.53386 2.56166 + vertex 0.797786 1.53632 2.56438 + vertex 0.795495 1.53884 2.56162 + endloop + endfacet + facet normal -0.793095 0.0178355 0.608836 + outer loop + vertex 0.795495 1.53884 2.56162 + vertex 0.793203 1.53635 2.5587 + vertex 0.795419 1.53386 2.56166 + endloop + endfacet + facet normal -0.790536 0.0238119 0.611953 + outer loop + vertex 0.793203 1.53635 2.5587 + vertex 0.793173 1.53132 2.55886 + vertex 0.795419 1.53386 2.56166 + endloop + endfacet + facet normal -0.789313 0.0208804 0.613636 + outer loop + vertex 0.795419 1.53386 2.56166 + vertex 0.793173 1.53132 2.55886 + vertex 0.795366 1.52882 2.56177 + endloop + endfacet + facet normal -0.75817 0.0213429 0.651708 + outer loop + vertex 0.795366 1.52882 2.56177 + vertex 0.797742 1.53128 2.56445 + vertex 0.795419 1.53386 2.56166 + endloop + endfacet + facet normal -0.755831 0.0159523 0.654572 + outer loop + vertex 0.797753 1.52611 2.56459 + vertex 0.797742 1.53128 2.56445 + vertex 0.795366 1.52882 2.56177 + endloop + endfacet + facet normal -0.787493 0.02501 0.615815 + outer loop + vertex 0.793173 1.53132 2.55886 + vertex 0.79313 1.52629 2.55901 + vertex 0.795366 1.52882 2.56177 + endloop + endfacet + facet normal -0.760622 0.0162156 0.648993 + outer loop + vertex 0.797742 1.53128 2.56445 + vertex 0.797786 1.53632 2.56438 + vertex 0.795419 1.53386 2.56166 + endloop + endfacet + facet normal -0.791921 0.0148706 0.610442 + outer loop + vertex 0.793309 1.54128 2.55872 + vertex 0.793203 1.53635 2.5587 + vertex 0.795495 1.53884 2.56162 + endloop + endfacet + facet normal -0.760714 0.0161133 0.648887 + outer loop + vertex 0.79786 1.54131 2.56434 + vertex 0.797929 1.54626 2.5643 + vertex 0.795563 1.54376 2.56159 + endloop + endfacet + facet normal -0.790807 0.0133039 0.611921 + outer loop + vertex 0.793295 1.55118 2.55849 + vertex 0.793309 1.54611 2.55862 + vertex 0.7956 1.5487 2.56152 + endloop + endfacet + facet normal -0.783394 0.0198612 0.621208 + outer loop + vertex 0.793506 1.56134 2.55851 + vertex 0.793419 1.55634 2.55856 + vertex 0.795715 1.5587 2.56138 + endloop + endfacet + facet normal -0.780422 0.026161 0.624706 + outer loop + vertex 0.795791 1.56367 2.56127 + vertex 0.793506 1.56134 2.55851 + vertex 0.795715 1.5587 2.56138 + endloop + endfacet + facet normal -0.781711 0.029509 0.622943 + outer loop + vertex 0.793595 1.5663 2.55839 + vertex 0.793506 1.56134 2.55851 + vertex 0.795791 1.56367 2.56127 + endloop + endfacet + facet normal -0.780374 0.0323133 0.624477 + outer loop + vertex 0.795887 1.56864 2.56113 + vertex 0.793595 1.5663 2.55839 + vertex 0.795791 1.56367 2.56127 + endloop + endfacet + facet normal -0.752911 0.0326868 0.65731 + outer loop + vertex 0.795791 1.56367 2.56127 + vertex 0.798198 1.56615 2.5639 + vertex 0.795887 1.56864 2.56113 + endloop + endfacet + facet normal -0.751052 0.0284209 0.659631 + outer loop + vertex 0.798115 1.56118 2.56402 + vertex 0.798198 1.56615 2.5639 + vertex 0.795791 1.56367 2.56127 + endloop + endfacet + facet normal -0.782573 0.0380752 0.621394 + outer loop + vertex 0.79372 1.57126 2.55824 + vertex 0.793595 1.5663 2.55839 + vertex 0.795887 1.56864 2.56113 + endloop + endfacet + facet normal -0.782222 0.0388012 0.62179 + outer loop + vertex 0.796012 1.57362 2.56098 + vertex 0.79372 1.57126 2.55824 + vertex 0.795887 1.56864 2.56113 + endloop + endfacet + facet normal -0.783827 0.0430387 0.619486 + outer loop + vertex 0.793872 1.57624 2.55809 + vertex 0.79372 1.57126 2.55824 + vertex 0.796012 1.57362 2.56098 + endloop + endfacet + facet normal -0.783574 0.0435581 0.61977 + outer loop + vertex 0.796158 1.57861 2.56081 + vertex 0.793872 1.57624 2.55809 + vertex 0.796012 1.57362 2.56098 + endloop + endfacet + facet normal -0.75743 0.0438407 0.651442 + outer loop + vertex 0.796012 1.57362 2.56098 + vertex 0.798422 1.57613 2.56361 + vertex 0.796158 1.57861 2.56081 + endloop + endfacet + facet normal -0.755291 0.038868 0.654236 + outer loop + vertex 0.7983 1.57114 2.56377 + vertex 0.798422 1.57613 2.56361 + vertex 0.796012 1.57362 2.56098 + endloop + endfacet + facet normal -0.755163 0.0391348 0.654368 + outer loop + vertex 0.795887 1.56864 2.56113 + vertex 0.7983 1.57114 2.56377 + vertex 0.796012 1.57362 2.56098 + endloop + endfacet + facet normal -0.784165 0.0451232 0.61891 + outer loop + vertex 0.794037 1.58124 2.55793 + vertex 0.793872 1.57624 2.55809 + vertex 0.796158 1.57861 2.56081 + endloop + endfacet + facet normal -0.783592 0.0462847 0.619549 + outer loop + vertex 0.796321 1.5836 2.56064 + vertex 0.794037 1.58124 2.55793 + vertex 0.796158 1.57861 2.56081 + endloop + endfacet + facet normal -0.759182 0.0464803 0.649217 + outer loop + vertex 0.796158 1.57861 2.56081 + vertex 0.79856 1.58113 2.56344 + vertex 0.796321 1.5836 2.56064 + endloop + endfacet + facet normal -0.759337 0.0461599 0.649058 + outer loop + vertex 0.79856 1.58113 2.56344 + vertex 0.798716 1.58612 2.56327 + vertex 0.796321 1.5836 2.56064 + endloop + endfacet + facet normal -0.75958 0.046729 0.648734 + outer loop + vertex 0.796321 1.5836 2.56064 + vertex 0.798716 1.58612 2.56327 + vertex 0.796496 1.58857 2.56049 + endloop + endfacet + facet normal -0.7837 0.0465714 0.619391 + outer loop + vertex 0.794216 1.58623 2.55778 + vertex 0.794037 1.58124 2.55793 + vertex 0.796321 1.5836 2.56064 + endloop + endfacet + facet normal -0.783651 0.0466699 0.619445 + outer loop + vertex 0.796496 1.58857 2.56049 + vertex 0.794216 1.58623 2.55778 + vertex 0.796321 1.5836 2.56064 + endloop + endfacet + facet normal -0.783882 0.0472865 0.619106 + outer loop + vertex 0.794401 1.5912 2.55764 + vertex 0.794216 1.58623 2.55778 + vertex 0.796496 1.58857 2.56049 + endloop + endfacet + facet normal -0.783855 0.047341 0.619137 + outer loop + vertex 0.79667 1.59354 2.56033 + vertex 0.794401 1.5912 2.55764 + vertex 0.796496 1.58857 2.56049 + endloop + endfacet + facet normal -0.784182 0.048215 0.618655 + outer loop + vertex 0.79456 1.59612 2.55746 + vertex 0.794401 1.5912 2.55764 + vertex 0.79667 1.59354 2.56033 + endloop + endfacet + facet normal -0.784606 0.0473428 0.618184 + outer loop + vertex 0.796778 1.59854 2.56009 + vertex 0.79456 1.59612 2.55746 + vertex 0.79667 1.59354 2.56033 + endloop + endfacet + facet normal -0.758824 0.0483302 0.6495 + outer loop + vertex 0.79667 1.59354 2.56033 + vertex 0.79906 1.59607 2.56294 + vertex 0.796778 1.59854 2.56009 + endloop + endfacet + facet normal -0.75773 0.0506096 0.650603 + outer loop + vertex 0.79906 1.59607 2.56294 + vertex 0.799194 1.60114 2.5627 + vertex 0.796778 1.59854 2.56009 + endloop + endfacet + facet normal -0.75824 0.0517745 0.649917 + outer loop + vertex 0.796778 1.59854 2.56009 + vertex 0.799194 1.60114 2.5627 + vertex 0.796641 1.60398 2.55949 + endloop + endfacet + facet normal -0.785955 0.047423 0.616462 + outer loop + vertex 0.796641 1.60398 2.55949 + vertex 0.794615 1.60085 2.55715 + vertex 0.796778 1.59854 2.56009 + endloop + endfacet + facet normal -0.788028 0.0509673 0.613526 + outer loop + vertex 0.794431 1.60453 2.55661 + vertex 0.794615 1.60085 2.55715 + vertex 0.796641 1.60398 2.55949 + endloop + endfacet + facet normal -0.787568 0.0543414 0.613827 + outer loop + vertex 0.794431 1.60453 2.55661 + vertex 0.796641 1.60398 2.55949 + vertex 0.794968 1.6079 2.557 + endloop + endfacet + facet normal -0.818869 0.0644088 0.570355 + outer loop + vertex 0.794968 1.6079 2.557 + vertex 0.79325 1.60688 2.55465 + vertex 0.794431 1.60453 2.55661 + endloop + endfacet + facet normal -0.819952 0.0719229 0.567896 + outer loop + vertex 0.793177 1.61077 2.55405 + vertex 0.79325 1.60688 2.55465 + vertex 0.794968 1.6079 2.557 + endloop + endfacet + facet normal -0.824776 0.0628222 0.561959 + outer loop + vertex 0.795295 1.61248 2.55697 + vertex 0.793177 1.61077 2.55405 + vertex 0.794968 1.6079 2.557 + endloop + endfacet + facet normal -0.789516 0.0606443 0.610727 + outer loop + vertex 0.794968 1.6079 2.557 + vertex 0.797184 1.60918 2.55974 + vertex 0.795295 1.61248 2.55697 + endloop + endfacet + facet normal -0.793319 0.0547844 0.606337 + outer loop + vertex 0.795295 1.61248 2.55697 + vertex 0.797184 1.60918 2.55974 + vertex 0.797476 1.61372 2.55971 + endloop + endfacet + facet normal -0.794235 0.0601764 0.604624 + outer loop + vertex 0.795862 1.61777 2.55719 + vertex 0.795295 1.61248 2.55697 + vertex 0.797476 1.61372 2.55971 + endloop + endfacet + facet normal -0.791396 0.0634112 0.608006 + outer loop + vertex 0.798028 1.61709 2.56008 + vertex 0.795862 1.61777 2.55719 + vertex 0.797476 1.61372 2.55971 + endloop + endfacet + facet normal -0.791323 0.063853 0.608055 + outer loop + vertex 0.798028 1.61709 2.56008 + vertex 0.797933 1.62094 2.55955 + vertex 0.795862 1.61777 2.55719 + endloop + endfacet + facet normal -0.790914 0.063131 0.608662 + outer loop + vertex 0.795862 1.61777 2.55719 + vertex 0.797933 1.62094 2.55955 + vertex 0.795779 1.62342 2.55649 + endloop + endfacet + facet normal -0.829102 0.0561286 0.556274 + outer loop + vertex 0.795779 1.62342 2.55649 + vertex 0.793659 1.62102 2.55357 + vertex 0.795862 1.61777 2.55719 + endloop + endfacet + facet normal -0.826132 0.0623053 0.560022 + outer loop + vertex 0.793659 1.62102 2.55357 + vertex 0.793429 1.61579 2.55382 + vertex 0.795862 1.61777 2.55719 + endloop + endfacet + facet normal -0.830389 0.0601201 0.553931 + outer loop + vertex 0.793853 1.62619 2.5533 + vertex 0.793659 1.62102 2.55357 + vertex 0.795779 1.62342 2.55649 + endloop + endfacet + facet normal -0.830439 0.0600127 0.553868 + outer loop + vertex 0.795932 1.62856 2.55616 + vertex 0.793853 1.62619 2.5533 + vertex 0.795779 1.62342 2.55649 + endloop + endfacet + facet normal -0.790024 0.0623595 0.609896 + outer loop + vertex 0.795779 1.62342 2.55649 + vertex 0.798028 1.62597 2.55914 + vertex 0.795932 1.62856 2.55616 + endloop + endfacet + facet normal -0.78934 0.0637643 0.610636 + outer loop + vertex 0.798028 1.62597 2.55914 + vertex 0.79817 1.63109 2.55879 + vertex 0.795932 1.62856 2.55616 + endloop + endfacet + facet normal -0.789604 0.0644231 0.610225 + outer loop + vertex 0.795932 1.62856 2.55616 + vertex 0.79817 1.63109 2.55879 + vertex 0.796181 1.63352 2.55596 + endloop + endfacet + facet normal -0.830832 0.0641389 0.552814 + outer loop + vertex 0.796181 1.63352 2.55596 + vertex 0.794113 1.63117 2.55313 + vertex 0.795932 1.62856 2.55616 + endloop + endfacet + facet normal -0.83199 0.0677729 0.550636 + outer loop + vertex 0.794387 1.63604 2.55294 + vertex 0.794113 1.63117 2.55313 + vertex 0.796181 1.63352 2.55596 + endloop + endfacet + facet normal -0.787876 0.0679822 0.61207 + outer loop + vertex 0.79817 1.63109 2.55879 + vertex 0.798423 1.63606 2.55857 + vertex 0.796181 1.63352 2.55596 + endloop + endfacet + facet normal -0.787537 0.0671384 0.612599 + outer loop + vertex 0.796181 1.63352 2.55596 + vertex 0.798423 1.63606 2.55857 + vertex 0.796441 1.63839 2.55576 + endloop + endfacet + facet normal -0.785055 0.0723532 0.615186 + outer loop + vertex 0.798423 1.63606 2.55857 + vertex 0.798696 1.64096 2.55834 + vertex 0.796441 1.63839 2.55576 + endloop + endfacet + facet normal -0.78399 0.0697574 0.616842 + outer loop + vertex 0.796441 1.63839 2.55576 + vertex 0.798696 1.64096 2.55834 + vertex 0.796615 1.6433 2.55543 + endloop + endfacet + facet normal -0.83486 0.0667733 0.546397 + outer loop + vertex 0.796615 1.6433 2.55543 + vertex 0.794621 1.64088 2.55268 + vertex 0.796441 1.63839 2.55576 + endloop + endfacet + facet normal -0.833357 0.070189 0.54826 + outer loop + vertex 0.794621 1.64088 2.55268 + vertex 0.794387 1.63604 2.55294 + vertex 0.796441 1.63839 2.55576 + endloop + endfacet + facet normal -0.832347 0.0669858 0.550192 + outer loop + vertex 0.796441 1.63839 2.55576 + vertex 0.794387 1.63604 2.55294 + vertex 0.796181 1.63352 2.55596 + endloop + endfacet + facet normal -0.834078 0.0644656 0.547866 + outer loop + vertex 0.794753 1.64554 2.55233 + vertex 0.794621 1.64088 2.55268 + vertex 0.796615 1.6433 2.55543 + endloop + endfacet + facet normal -0.833843 0.0650591 0.548154 + outer loop + vertex 0.796559 1.64869 2.55471 + vertex 0.794753 1.64554 2.55233 + vertex 0.796615 1.6433 2.55543 + endloop + endfacet + facet normal -0.782398 0.0750243 0.618243 + outer loop + vertex 0.796615 1.6433 2.55543 + vertex 0.798901 1.64596 2.558 + vertex 0.796559 1.64869 2.55471 + endloop + endfacet + facet normal -0.780333 0.079299 0.620316 + outer loop + vertex 0.798901 1.64596 2.558 + vertex 0.799135 1.65105 2.55764 + vertex 0.796559 1.64869 2.55471 + endloop + endfacet + facet normal -0.778247 0.0727757 0.623727 + outer loop + vertex 0.796559 1.64869 2.55471 + vertex 0.799135 1.65105 2.55764 + vertex 0.797127 1.65394 2.5548 + endloop + endfacet + facet normal -0.824527 0.0789281 0.56029 + outer loop + vertex 0.795175 1.65259 2.55212 + vertex 0.796559 1.64869 2.55471 + vertex 0.797127 1.65394 2.5548 + endloop + endfacet + facet normal -0.826087 0.0886136 0.556532 + outer loop + vertex 0.795175 1.65259 2.55212 + vertex 0.797127 1.65394 2.5548 + vertex 0.795566 1.65724 2.55196 + endloop + endfacet + facet normal -0.884046 0.0901016 0.458634 + outer loop + vertex 0.795566 1.65724 2.55196 + vertex 0.793864 1.65554 2.54901 + vertex 0.795175 1.65259 2.55212 + endloop + endfacet + facet normal -0.772539 0.0824942 0.629586 + outer loop + vertex 0.799135 1.65105 2.55764 + vertex 0.799332 1.65593 2.55725 + vertex 0.797127 1.65394 2.5548 + endloop + endfacet + facet normal -0.773135 0.0843556 0.628607 + outer loop + vertex 0.797127 1.65394 2.5548 + vertex 0.799332 1.65593 2.55725 + vertex 0.797499 1.65854 2.55464 + endloop + endfacet + facet normal -0.827665 0.0861728 0.554567 + outer loop + vertex 0.795566 1.65724 2.55196 + vertex 0.797127 1.65394 2.5548 + vertex 0.797499 1.65854 2.55464 + endloop + endfacet + facet normal -0.833251 0.0639396 0.549185 + outer loop + vertex 0.794662 1.6492 2.55177 + vertex 0.794753 1.64554 2.55233 + vertex 0.796559 1.64869 2.55471 + endloop + endfacet + facet normal -0.832561 0.0689994 0.549619 + outer loop + vertex 0.794662 1.6492 2.55177 + vertex 0.796559 1.64869 2.55471 + vertex 0.795175 1.65259 2.55212 + endloop + endfacet + facet normal -0.880217 0.084818 0.46693 + outer loop + vertex 0.795175 1.65259 2.55212 + vertex 0.79381 1.65161 2.54972 + vertex 0.794662 1.6492 2.55177 + endloop + endfacet + facet normal -0.78199 0.0740599 0.618875 + outer loop + vertex 0.798696 1.64096 2.55834 + vertex 0.798901 1.64596 2.558 + vertex 0.796615 1.6433 2.55543 + endloop + endfacet + facet normal -0.74426 0.0755302 0.663606 + outer loop + vertex 0.798901 1.64596 2.558 + vertex 0.798696 1.64096 2.55834 + vertex 0.801175 1.64355 2.56082 + endloop + endfacet + facet normal -0.742433 0.0791619 0.665227 + outer loop + vertex 0.801456 1.64853 2.56055 + vertex 0.798901 1.64596 2.558 + vertex 0.801175 1.64355 2.56082 + endloop + endfacet + facet normal -0.724202 0.0792368 0.68502 + outer loop + vertex 0.801175 1.64355 2.56082 + vertex 0.803791 1.64611 2.56329 + vertex 0.801456 1.64853 2.56055 + endloop + endfacet + facet normal -0.723404 0.0807642 0.685685 + outer loop + vertex 0.803791 1.64611 2.56329 + vertex 0.804082 1.65109 2.56301 + vertex 0.801456 1.64853 2.56055 + endloop + endfacet + facet normal -0.725131 0.084761 0.683374 + outer loop + vertex 0.801456 1.64853 2.56055 + vertex 0.804082 1.65109 2.56301 + vertex 0.801647 1.65358 2.56012 + endloop + endfacet + facet normal -0.74139 0.0839043 0.665809 + outer loop + vertex 0.801647 1.65358 2.56012 + vertex 0.799135 1.65105 2.55764 + vertex 0.801456 1.64853 2.56055 + endloop + endfacet + facet normal -0.741507 0.0841834 0.665643 + outer loop + vertex 0.799332 1.65593 2.55725 + vertex 0.799135 1.65105 2.55764 + vertex 0.801647 1.65358 2.56012 + endloop + endfacet + facet normal -0.739711 0.0878214 0.66717 + outer loop + vertex 0.80158 1.65898 2.55934 + vertex 0.799332 1.65593 2.55725 + vertex 0.801647 1.65358 2.56012 + endloop + endfacet + facet normal -0.726613 0.0900153 0.681125 + outer loop + vertex 0.801647 1.65358 2.56012 + vertex 0.804228 1.65608 2.56254 + vertex 0.80158 1.65898 2.55934 + endloop + endfacet + facet normal -0.727679 0.0880604 0.680241 + outer loop + vertex 0.804228 1.65608 2.56254 + vertex 0.804335 1.6608 2.56205 + vertex 0.80158 1.65898 2.55934 + endloop + endfacet + facet normal -0.728339 0.0905982 0.679202 + outer loop + vertex 0.80158 1.65898 2.55934 + vertex 0.804335 1.6608 2.56205 + vertex 0.802346 1.66374 2.55952 + endloop + endfacet + facet normal -0.739727 0.0929295 0.666459 + outer loop + vertex 0.799957 1.66303 2.55697 + vertex 0.80158 1.65898 2.55934 + vertex 0.802346 1.66374 2.55952 + endloop + endfacet + facet normal -0.740009 0.0972203 0.665533 + outer loop + vertex 0.800737 1.66788 2.55713 + vertex 0.799957 1.66303 2.55697 + vertex 0.802346 1.66374 2.55952 + endloop + endfacet + facet normal -0.739959 0.0972678 0.665582 + outer loop + vertex 0.803236 1.66706 2.56003 + vertex 0.800737 1.66788 2.55713 + vertex 0.802346 1.66374 2.55952 + endloop + endfacet + facet normal -0.729204 0.0925074 0.678014 + outer loop + vertex 0.803236 1.66706 2.56003 + vertex 0.802346 1.66374 2.55952 + vertex 0.804439 1.66453 2.56167 + endloop + endfacet + facet normal -0.724269 0.0977922 0.682547 + outer loop + vertex 0.805888 1.66796 2.56271 + vertex 0.803236 1.66706 2.56003 + vertex 0.804439 1.66453 2.56167 + endloop + endfacet + facet normal -0.71786 0.092817 0.689972 + outer loop + vertex 0.805888 1.66796 2.56271 + vertex 0.804439 1.66453 2.56167 + vertex 0.806528 1.66295 2.56405 + endloop + endfacet + facet normal -0.710685 0.0956088 0.696983 + outer loop + vertex 0.805888 1.66796 2.56271 + vertex 0.806528 1.66295 2.56405 + vertex 0.808614 1.66512 2.56588 + endloop + endfacet + facet normal -0.71458 0.0884764 0.693936 + outer loop + vertex 0.805888 1.66796 2.56271 + vertex 0.808614 1.66512 2.56588 + vertex 0.808228 1.66807 2.56511 + endloop + endfacet + facet normal -0.71439 0.0930362 0.693535 + outer loop + vertex 0.808228 1.66807 2.56511 + vertex 0.808023 1.67118 2.56448 + vertex 0.805888 1.66796 2.56271 + endloop + endfacet + facet normal -0.715894 0.0950354 0.691711 + outer loop + vertex 0.805888 1.66796 2.56271 + vertex 0.808023 1.67118 2.56448 + vertex 0.805544 1.67352 2.56159 + endloop + endfacet + facet normal -0.727852 0.0918491 0.679555 + outer loop + vertex 0.805544 1.67352 2.56159 + vertex 0.803122 1.67102 2.55934 + vertex 0.805888 1.66796 2.56271 + endloop + endfacet + facet normal -0.730273 0.0972265 0.676201 + outer loop + vertex 0.803188 1.67606 2.55868 + vertex 0.803122 1.67102 2.55934 + vertex 0.805544 1.67352 2.56159 + endloop + endfacet + facet normal -0.730791 0.0962627 0.67578 + outer loop + vertex 0.805728 1.67862 2.56106 + vertex 0.803188 1.67606 2.55868 + vertex 0.805544 1.67352 2.56159 + endloop + endfacet + facet normal -0.717866 0.0972029 0.689362 + outer loop + vertex 0.805544 1.67352 2.56159 + vertex 0.808004 1.67609 2.56379 + vertex 0.805728 1.67862 2.56106 + endloop + endfacet + facet normal -0.717134 0.0984844 0.689941 + outer loop + vertex 0.808004 1.67609 2.56379 + vertex 0.808355 1.68114 2.56344 + vertex 0.805728 1.67862 2.56106 + endloop + endfacet + facet normal -0.718059 0.100643 0.688667 + outer loop + vertex 0.805728 1.67862 2.56106 + vertex 0.808355 1.68114 2.56344 + vertex 0.806173 1.68362 2.5608 + endloop + endfacet + facet normal -0.732232 0.101098 0.67351 + outer loop + vertex 0.806173 1.68362 2.5608 + vertex 0.803551 1.68106 2.55833 + vertex 0.805728 1.67862 2.56106 + endloop + endfacet + facet normal -0.732699 0.102232 0.67283 + outer loop + vertex 0.803983 1.68598 2.55805 + vertex 0.803551 1.68106 2.55833 + vertex 0.806173 1.68362 2.5608 + endloop + endfacet + facet normal -0.731796 0.103913 0.673556 + outer loop + vertex 0.806576 1.6885 2.56048 + vertex 0.803983 1.68598 2.55805 + vertex 0.806173 1.68362 2.5608 + endloop + endfacet + facet normal -0.716395 0.1037 0.689945 + outer loop + vertex 0.806173 1.68362 2.5608 + vertex 0.808846 1.68612 2.5632 + vertex 0.806576 1.6885 2.56048 + endloop + endfacet + facet normal -0.714928 0.106371 0.691059 + outer loop + vertex 0.808846 1.68612 2.5632 + vertex 0.809146 1.69091 2.56277 + vertex 0.806576 1.6885 2.56048 + endloop + endfacet + facet normal -0.714522 0.105399 0.691628 + outer loop + vertex 0.806576 1.6885 2.56048 + vertex 0.809146 1.69091 2.56277 + vertex 0.806719 1.6932 2.55991 + endloop + endfacet + facet normal -0.731545 0.103768 0.67385 + outer loop + vertex 0.806719 1.6932 2.55991 + vertex 0.804244 1.69084 2.55759 + vertex 0.806576 1.6885 2.56048 + endloop + endfacet + facet normal -0.730743 0.101771 0.675024 + outer loop + vertex 0.804392 1.69546 2.55705 + vertex 0.804244 1.69084 2.55759 + vertex 0.806719 1.6932 2.55991 + endloop + endfacet + facet normal -0.730071 0.103124 0.675546 + outer loop + vertex 0.806542 1.6977 2.55904 + vertex 0.804392 1.69546 2.55705 + vertex 0.806719 1.6932 2.55991 + endloop + endfacet + facet normal -0.714049 0.106945 0.691879 + outer loop + vertex 0.806719 1.6932 2.55991 + vertex 0.809062 1.69552 2.56197 + vertex 0.806542 1.6977 2.55904 + endloop + endfacet + facet normal -0.729432 0.101712 0.676449 + outer loop + vertex 0.80451 1.69918 2.55662 + vertex 0.804392 1.69546 2.55705 + vertex 0.806542 1.6977 2.55904 + endloop + endfacet + facet normal -0.727878 0.1056 0.677526 + outer loop + vertex 0.805963 1.70273 2.55763 + vertex 0.80451 1.69918 2.55662 + vertex 0.806542 1.6977 2.55904 + endloop + endfacet + facet normal -0.716303 0.110149 0.689041 + outer loop + vertex 0.805963 1.70273 2.55763 + vertex 0.806542 1.6977 2.55904 + vertex 0.808632 1.69996 2.56085 + endloop + endfacet + facet normal -0.720609 0.102205 0.685767 + outer loop + vertex 0.805963 1.70273 2.55763 + vertex 0.808632 1.69996 2.56085 + vertex 0.80828 1.70293 2.56003 + endloop + endfacet + facet normal -0.720591 0.102771 0.685702 + outer loop + vertex 0.80828 1.70293 2.56003 + vertex 0.808107 1.70608 2.55938 + vertex 0.805963 1.70273 2.55763 + endloop + endfacet + facet normal -0.721248 0.103621 0.684882 + outer loop + vertex 0.805963 1.70273 2.55763 + vertex 0.808107 1.70608 2.55938 + vertex 0.805677 1.70838 2.55648 + endloop + endfacet + facet normal -0.744235 0.0975213 0.660761 + outer loop + vertex 0.805677 1.70838 2.55648 + vertex 0.803323 1.70575 2.55421 + vertex 0.805963 1.70273 2.55763 + endloop + endfacet + facet normal -0.738652 0.107681 0.665431 + outer loop + vertex 0.803323 1.70575 2.55421 + vertex 0.803385 1.7017 2.55493 + vertex 0.805963 1.70273 2.55763 + endloop + endfacet + facet normal -0.743319 0.0955634 0.662076 + outer loop + vertex 0.803406 1.71088 2.55356 + vertex 0.803323 1.70575 2.55421 + vertex 0.805677 1.70838 2.55648 + endloop + endfacet + facet normal -0.723022 0.100049 0.683542 + outer loop + vertex 0.808107 1.70608 2.55938 + vertex 0.808125 1.71103 2.55868 + vertex 0.805677 1.70838 2.55648 + endloop + endfacet + facet normal -0.721393 0.0967308 0.685737 + outer loop + vertex 0.805677 1.70838 2.55648 + vertex 0.808125 1.71103 2.55868 + vertex 0.805851 1.71353 2.55593 + endloop + endfacet + facet normal -0.743641 0.0949539 0.661802 + outer loop + vertex 0.805851 1.71353 2.55593 + vertex 0.803406 1.71088 2.55356 + vertex 0.805677 1.70838 2.55648 + endloop + endfacet + facet normal -0.740936 0.0890278 0.665649 + outer loop + vertex 0.803678 1.71594 2.55319 + vertex 0.803406 1.71088 2.55356 + vertex 0.805851 1.71353 2.55593 + endloop + endfacet + facet normal -0.737214 0.095994 0.668806 + outer loop + vertex 0.806223 1.71855 2.55562 + vertex 0.803678 1.71594 2.55319 + vertex 0.805851 1.71353 2.55593 + endloop + endfacet + facet normal -0.718937 0.0958587 0.688434 + outer loop + vertex 0.805851 1.71353 2.55593 + vertex 0.808465 1.71609 2.5583 + vertex 0.806223 1.71855 2.55562 + endloop + endfacet + facet normal -0.715955 0.101139 0.690782 + outer loop + vertex 0.808465 1.71609 2.5583 + vertex 0.808901 1.72104 2.55803 + vertex 0.806223 1.71855 2.55562 + endloop + endfacet + facet normal -0.717714 0.105434 0.688309 + outer loop + vertex 0.806223 1.71855 2.55562 + vertex 0.808901 1.72104 2.55803 + vertex 0.806546 1.7235 2.5552 + endloop + endfacet + facet normal -0.731416 0.105095 0.673784 + outer loop + vertex 0.806546 1.7235 2.5552 + vertex 0.80396 1.72093 2.55279 + vertex 0.806223 1.71855 2.55562 + endloop + endfacet + facet normal -0.733287 0.109543 0.671037 + outer loop + vertex 0.804212 1.72576 2.55228 + vertex 0.80396 1.72093 2.55279 + vertex 0.806546 1.7235 2.5552 + endloop + endfacet + facet normal -0.726281 0.123513 0.67621 + outer loop + vertex 0.806628 1.72873 2.55433 + vertex 0.804212 1.72576 2.55228 + vertex 0.806546 1.7235 2.5552 + endloop + endfacet + facet normal -0.720365 0.124438 0.682341 + outer loop + vertex 0.806546 1.7235 2.5552 + vertex 0.809202 1.72585 2.55757 + vertex 0.806628 1.72873 2.55433 + endloop + endfacet + facet normal -0.720546 0.124125 0.682207 + outer loop + vertex 0.809202 1.72585 2.55757 + vertex 0.809433 1.73035 2.557 + vertex 0.806628 1.72873 2.55433 + endloop + endfacet + facet normal -0.724013 0.142025 0.675007 + outer loop + vertex 0.806628 1.72873 2.55433 + vertex 0.809433 1.73035 2.557 + vertex 0.807554 1.73331 2.55436 + endloop + endfacet + facet normal -0.736113 0.14456 0.661241 + outer loop + vertex 0.805126 1.73276 2.55178 + vertex 0.806628 1.72873 2.55433 + vertex 0.807554 1.73331 2.55436 + endloop + endfacet + facet normal -0.735972 0.161151 0.657552 + outer loop + vertex 0.806092 1.73755 2.55169 + vertex 0.805126 1.73276 2.55178 + vertex 0.807554 1.73331 2.55436 + endloop + endfacet + facet normal -0.741515 0.15607 0.652532 + outer loop + vertex 0.808555 1.73652 2.55473 + vertex 0.806092 1.73755 2.55169 + vertex 0.807554 1.73331 2.55436 + endloop + endfacet + facet normal -0.728129 0.150009 0.668825 + outer loop + vertex 0.808555 1.73652 2.55473 + vertex 0.807554 1.73331 2.55436 + vertex 0.809652 1.73394 2.55651 + endloop + endfacet + facet normal -0.724143 0.154037 0.672227 + outer loop + vertex 0.811222 1.73731 2.55742 + vertex 0.808555 1.73652 2.55473 + vertex 0.809652 1.73394 2.55651 + endloop + endfacet + facet normal -0.713252 0.145301 0.685682 + outer loop + vertex 0.811222 1.73731 2.55742 + vertex 0.809652 1.73394 2.55651 + vertex 0.811666 1.73231 2.55895 + endloop + endfacet + facet normal -0.712261 0.145678 0.686632 + outer loop + vertex 0.811222 1.73731 2.55742 + vertex 0.811666 1.73231 2.55895 + vertex 0.813811 1.73448 2.56071 + endloop + endfacet + facet normal -0.717371 0.136895 0.68311 + outer loop + vertex 0.811222 1.73731 2.55742 + vertex 0.813811 1.73448 2.56071 + vertex 0.813548 1.73741 2.55985 + endloop + endfacet + facet normal -0.716439 0.148232 0.68172 + outer loop + vertex 0.813548 1.73741 2.55985 + vertex 0.813519 1.74071 2.5591 + vertex 0.811222 1.73731 2.55742 + endloop + endfacet + facet normal -0.702748 0.151394 0.695144 + outer loop + vertex 0.813519 1.74071 2.5591 + vertex 0.813548 1.73741 2.55985 + vertex 0.816045 1.73774 2.5623 + endloop + endfacet + facet normal -0.705686 0.146755 0.693159 + outer loop + vertex 0.816072 1.74325 2.56116 + vertex 0.813519 1.74071 2.5591 + vertex 0.816045 1.73774 2.5623 + endloop + endfacet + facet normal -0.699148 0.148032 0.699485 + outer loop + vertex 0.816045 1.73774 2.5623 + vertex 0.818345 1.74107 2.56389 + vertex 0.816072 1.74325 2.56116 + endloop + endfacet + facet normal -0.697547 0.150927 0.700463 + outer loop + vertex 0.818345 1.74107 2.56389 + vertex 0.818678 1.74587 2.56319 + vertex 0.816072 1.74325 2.56116 + endloop + endfacet + facet normal -0.696242 0.148171 0.702348 + outer loop + vertex 0.816072 1.74325 2.56116 + vertex 0.818678 1.74587 2.56319 + vertex 0.816534 1.74841 2.56053 + endloop + endfacet + facet normal -0.707443 0.147806 0.691142 + outer loop + vertex 0.816534 1.74841 2.56053 + vertex 0.813795 1.74599 2.55824 + vertex 0.816072 1.74325 2.56116 + endloop + endfacet + facet normal -0.705484 0.142685 0.694214 + outer loop + vertex 0.814607 1.75178 2.55788 + vertex 0.813795 1.74599 2.55824 + vertex 0.816534 1.74841 2.56053 + endloop + endfacet + facet normal -0.703796 0.144675 0.695514 + outer loop + vertex 0.817287 1.7523 2.56048 + vertex 0.814607 1.75178 2.55788 + vertex 0.816534 1.74841 2.56053 + endloop + endfacet + facet normal -0.694019 0.142909 0.705631 + outer loop + vertex 0.816534 1.74841 2.56053 + vertex 0.81903 1.75051 2.56256 + vertex 0.817287 1.7523 2.56048 + endloop + endfacet + facet normal -0.69367 0.143505 0.705853 + outer loop + vertex 0.819094 1.75403 2.56191 + vertex 0.817287 1.7523 2.56048 + vertex 0.81903 1.75051 2.56256 + endloop + endfacet + facet normal -0.685527 0.144776 0.713507 + outer loop + vertex 0.819094 1.75403 2.56191 + vertex 0.81903 1.75051 2.56256 + vertex 0.821259 1.7529 2.56421 + endloop + endfacet + facet normal -0.686106 0.143189 0.713271 + outer loop + vertex 0.820636 1.75765 2.56266 + vertex 0.819094 1.75403 2.56191 + vertex 0.821259 1.7529 2.56421 + endloop + endfacet + facet normal -0.677788 0.146637 0.720487 + outer loop + vertex 0.820636 1.75765 2.56266 + vertex 0.821259 1.7529 2.56421 + vertex 0.82353 1.75516 2.56589 + endloop + endfacet + facet normal -0.679323 0.143736 0.719625 + outer loop + vertex 0.820636 1.75765 2.56266 + vertex 0.82353 1.75516 2.56589 + vertex 0.823254 1.75799 2.56507 + endloop + endfacet + facet normal -0.679394 0.14126 0.720048 + outer loop + vertex 0.823254 1.75799 2.56507 + vertex 0.823141 1.76098 2.56437 + vertex 0.820636 1.75765 2.56266 + endloop + endfacet + facet normal -0.678688 0.140289 0.720903 + outer loop + vertex 0.820636 1.75765 2.56266 + vertex 0.823141 1.76098 2.56437 + vertex 0.820491 1.7632 2.56145 + endloop + endfacet + facet normal -0.689043 0.13795 0.71147 + outer loop + vertex 0.820491 1.7632 2.56145 + vertex 0.817252 1.76047 2.55884 + vertex 0.820636 1.75765 2.56266 + endloop + endfacet + facet normal -0.689341 0.138725 0.711031 + outer loop + vertex 0.818079 1.7658 2.5586 + vertex 0.817252 1.76047 2.55884 + vertex 0.820491 1.7632 2.56145 + endloop + endfacet + facet normal -0.693143 0.132462 0.708524 + outer loop + vertex 0.820903 1.76832 2.56089 + vertex 0.818079 1.7658 2.5586 + vertex 0.820491 1.7632 2.56145 + endloop + endfacet + facet normal -0.68065 0.132754 0.72048 + outer loop + vertex 0.820491 1.7632 2.56145 + vertex 0.823261 1.76579 2.56359 + vertex 0.820903 1.76832 2.56089 + endloop + endfacet + facet normal -0.68884 0.119322 0.715025 + outer loop + vertex 0.823261 1.76579 2.56359 + vertex 0.823682 1.77086 2.56314 + vertex 0.820903 1.76832 2.56089 + endloop + endfacet + facet normal -0.686982 0.115102 0.7175 + outer loop + vertex 0.820903 1.76832 2.56089 + vertex 0.823682 1.77086 2.56314 + vertex 0.821414 1.77337 2.56057 + endloop + endfacet + facet normal -0.704121 0.11576 0.700581 + outer loop + vertex 0.821414 1.77337 2.56057 + vertex 0.81867 1.77081 2.55823 + vertex 0.820903 1.76832 2.56089 + endloop + endfacet + facet normal -0.7023 0.111509 0.703094 + outer loop + vertex 0.819128 1.77582 2.5579 + vertex 0.81867 1.77081 2.55823 + vertex 0.821414 1.77337 2.56057 + endloop + endfacet + facet normal -0.715355 0.0884577 0.69314 + outer loop + vertex 0.821757 1.77835 2.56029 + vertex 0.819128 1.77582 2.5579 + vertex 0.821414 1.77337 2.56057 + endloop + endfacet + facet normal -0.69632 0.0882208 0.712289 + outer loop + vertex 0.821414 1.77337 2.56057 + vertex 0.824133 1.77595 2.56291 + vertex 0.821757 1.77835 2.56029 + endloop + endfacet + facet normal -0.705549 0.0711776 0.705078 + outer loop + vertex 0.824133 1.77595 2.56291 + vertex 0.824315 1.78087 2.56259 + vertex 0.821757 1.77835 2.56029 + endloop + endfacet + facet normal -0.699289 0.0947557 0.708531 + outer loop + vertex 0.823682 1.77086 2.56314 + vertex 0.824133 1.77595 2.56291 + vertex 0.821414 1.77337 2.56057 + endloop + endfacet + facet normal -0.722829 0.111968 0.681896 + outer loop + vertex 0.81867 1.77081 2.55823 + vertex 0.819128 1.77582 2.5579 + vertex 0.816452 1.7733 2.55548 + endloop + endfacet + facet normal -0.710207 0.133593 0.691201 + outer loop + vertex 0.815958 1.76833 2.55593 + vertex 0.81867 1.77081 2.55823 + vertex 0.816452 1.7733 2.55548 + endloop + endfacet + facet normal -0.728565 0.133648 0.671812 + outer loop + vertex 0.816452 1.7733 2.55548 + vertex 0.813745 1.77084 2.55303 + vertex 0.815958 1.76833 2.55593 + endloop + endfacet + facet normal -0.720457 0.147504 0.677631 + outer loop + vertex 0.813745 1.77084 2.55303 + vertex 0.813421 1.76585 2.55377 + vertex 0.815958 1.76833 2.55593 + endloop + endfacet + facet normal -0.720135 0.14673 0.678141 + outer loop + vertex 0.815958 1.76833 2.55593 + vertex 0.813421 1.76585 2.55377 + vertex 0.815407 1.76373 2.55634 + endloop + endfacet + facet normal -0.702597 0.14626 0.696395 + outer loop + vertex 0.815407 1.76373 2.55634 + vertex 0.818079 1.7658 2.5586 + vertex 0.815958 1.76833 2.55593 + endloop + endfacet + facet normal -0.716371 0.153311 0.680667 + outer loop + vertex 0.813421 1.76585 2.55377 + vertex 0.813359 1.76211 2.55455 + vertex 0.815407 1.76373 2.55634 + endloop + endfacet + facet normal -0.714186 0.146287 0.684499 + outer loop + vertex 0.815407 1.76373 2.55634 + vertex 0.813359 1.76211 2.55455 + vertex 0.81459 1.7603 2.55622 + endloop + endfacet + facet normal -0.698761 0.142022 0.701115 + outer loop + vertex 0.81459 1.7603 2.55622 + vertex 0.817252 1.76047 2.55884 + vertex 0.815407 1.76373 2.55634 + endloop + endfacet + facet normal -0.699303 0.13368 0.702215 + outer loop + vertex 0.81459 1.7603 2.55622 + vertex 0.814606 1.75684 2.55689 + vertex 0.817252 1.76047 2.55884 + endloop + endfacet + facet normal -0.70121 0.136367 0.699792 + outer loop + vertex 0.814606 1.75684 2.55689 + vertex 0.817228 1.75566 2.55975 + vertex 0.817252 1.76047 2.55884 + endloop + endfacet + facet normal -0.701357 0.135905 0.699735 + outer loop + vertex 0.814607 1.75178 2.55788 + vertex 0.817228 1.75566 2.55975 + vertex 0.814606 1.75684 2.55689 + endloop + endfacet + facet normal -0.726231 0.12735 0.675552 + outer loop + vertex 0.814165 1.77594 2.55252 + vertex 0.813745 1.77084 2.55303 + vertex 0.816452 1.7733 2.55548 + endloop + endfacet + facet normal -0.739238 0.1046 0.665271 + outer loop + vertex 0.816764 1.77832 2.55503 + vertex 0.814165 1.77594 2.55252 + vertex 0.816452 1.7733 2.55548 + endloop + endfacet + facet normal -0.735713 0.0951477 0.670577 + outer loop + vertex 0.814449 1.78071 2.55216 + vertex 0.814165 1.77594 2.55252 + vertex 0.816764 1.77832 2.55503 + endloop + endfacet + facet normal -0.747767 0.0708902 0.660166 + outer loop + vertex 0.816654 1.78366 2.55434 + vertex 0.814449 1.78071 2.55216 + vertex 0.816764 1.77832 2.55503 + endloop + endfacet + facet normal -0.730187 0.0737536 0.679256 + outer loop + vertex 0.816764 1.77832 2.55503 + vertex 0.819304 1.7808 2.5575 + vertex 0.816654 1.78366 2.55434 + endloop + endfacet + facet normal -0.733136 0.0807357 0.675273 + outer loop + vertex 0.819128 1.77582 2.5579 + vertex 0.819304 1.7808 2.5575 + vertex 0.816764 1.77832 2.55503 + endloop + endfacet + facet normal -0.712413 0.0817631 0.696981 + outer loop + vertex 0.819304 1.7808 2.5575 + vertex 0.819128 1.77582 2.5579 + vertex 0.821757 1.77835 2.56029 + endloop + endfacet + facet normal -0.746571 0.0688379 0.661735 + outer loop + vertex 0.814326 1.78436 2.55164 + vertex 0.814449 1.78071 2.55216 + vertex 0.816654 1.78366 2.55434 + endloop + endfacet + facet normal -0.748248 0.0594911 0.660747 + outer loop + vertex 0.814326 1.78436 2.55164 + vertex 0.816654 1.78366 2.55434 + vertex 0.814949 1.7877 2.55204 + endloop + endfacet + facet normal -0.74907 0.0597602 0.65979 + outer loop + vertex 0.814949 1.7877 2.55204 + vertex 0.813054 1.78667 2.54998 + vertex 0.814326 1.78436 2.55164 + endloop + endfacet + facet normal -0.748604 0.0603578 0.660264 + outer loop + vertex 0.813054 1.78667 2.54998 + vertex 0.812453 1.78338 2.5496 + vertex 0.814326 1.78436 2.55164 + endloop + endfacet + facet normal -0.750063 0.068168 0.657844 + outer loop + vertex 0.814326 1.78436 2.55164 + vertex 0.812453 1.78338 2.5496 + vertex 0.814449 1.78071 2.55216 + endloop + endfacet + facet normal -0.743392 0.07917 0.664154 + outer loop + vertex 0.812033 1.77899 2.54966 + vertex 0.814449 1.78071 2.55216 + vertex 0.812453 1.78338 2.5496 + endloop + endfacet + facet normal -0.747553 0.0948454 0.657396 + outer loop + vertex 0.814165 1.77594 2.55252 + vertex 0.814449 1.78071 2.55216 + vertex 0.812033 1.77899 2.54966 + endloop + endfacet + facet normal -0.738151 0.109258 0.66573 + outer loop + vertex 0.81123 1.77386 2.54961 + vertex 0.814165 1.77594 2.55252 + vertex 0.812033 1.77899 2.54966 + endloop + endfacet + facet normal -0.753497 0.111829 0.647871 + outer loop + vertex 0.809649 1.7779 2.54707 + vertex 0.81123 1.77386 2.54961 + vertex 0.812033 1.77899 2.54966 + endloop + endfacet + facet normal -0.749879 0.0842188 0.656193 + outer loop + vertex 0.809649 1.7779 2.54707 + vertex 0.812033 1.77899 2.54966 + vertex 0.8101 1.78231 2.54702 + endloop + endfacet + facet normal -0.771142 0.0860981 0.630815 + outer loop + vertex 0.8101 1.78231 2.54702 + vertex 0.807852 1.78054 2.54451 + vertex 0.809649 1.7779 2.54707 + endloop + endfacet + facet normal -0.753016 0.0799584 0.653126 + outer loop + vertex 0.8101 1.78231 2.54702 + vertex 0.812033 1.77899 2.54966 + vertex 0.812453 1.78338 2.5496 + endloop + endfacet + facet normal -0.742596 0.126907 0.657606 + outer loop + vertex 0.813745 1.77084 2.55303 + vertex 0.814165 1.77594 2.55252 + vertex 0.81123 1.77386 2.54961 + endloop + endfacet + facet normal -0.735366 0.139274 0.663204 + outer loop + vertex 0.811142 1.76817 2.55071 + vertex 0.813745 1.77084 2.55303 + vertex 0.81123 1.77386 2.54961 + endloop + endfacet + facet normal -0.757767 0.134843 0.638441 + outer loop + vertex 0.81123 1.77386 2.54961 + vertex 0.808877 1.7707 2.54748 + vertex 0.811142 1.76817 2.55071 + endloop + endfacet + facet normal -0.754831 0.140367 0.640724 + outer loop + vertex 0.808877 1.7707 2.54748 + vertex 0.808627 1.76552 2.54832 + vertex 0.811142 1.76817 2.55071 + endloop + endfacet + facet normal -0.75652 0.144635 0.637776 + outer loop + vertex 0.811142 1.76817 2.55071 + vertex 0.808627 1.76552 2.54832 + vertex 0.811046 1.76255 2.55186 + endloop + endfacet + facet normal -0.736538 0.148839 0.659817 + outer loop + vertex 0.811046 1.76255 2.55186 + vertex 0.813421 1.76585 2.55377 + vertex 0.811142 1.76817 2.55071 + endloop + endfacet + facet normal -0.736791 0.149235 0.659446 + outer loop + vertex 0.813359 1.76211 2.55455 + vertex 0.813421 1.76585 2.55377 + vertex 0.811046 1.76255 2.55186 + endloop + endfacet + facet normal -0.73808 0.142599 0.659472 + outer loop + vertex 0.813359 1.76211 2.55455 + vertex 0.811046 1.76255 2.55186 + vertex 0.812527 1.75881 2.55433 + endloop + endfacet + facet normal -0.720928 0.136952 0.679343 + outer loop + vertex 0.813359 1.76211 2.55455 + vertex 0.812527 1.75881 2.55433 + vertex 0.81459 1.7603 2.55622 + endloop + endfacet + facet normal -0.718963 0.129803 0.68282 + outer loop + vertex 0.81459 1.7603 2.55622 + vertex 0.812527 1.75881 2.55433 + vertex 0.814606 1.75684 2.55689 + endloop + endfacet + facet normal -0.719123 0.129492 0.682711 + outer loop + vertex 0.811641 1.75408 2.55429 + vertex 0.814606 1.75684 2.55689 + vertex 0.812527 1.75881 2.55433 + endloop + endfacet + facet normal -0.73717 0.133023 0.662484 + outer loop + vertex 0.810144 1.75772 2.5519 + vertex 0.811641 1.75408 2.55429 + vertex 0.812527 1.75881 2.55433 + endloop + endfacet + facet normal -0.736769 0.133428 0.662849 + outer loop + vertex 0.80927 1.75444 2.55159 + vertex 0.811641 1.75408 2.55429 + vertex 0.810144 1.75772 2.5519 + endloop + endfacet + facet normal -0.753355 0.139766 0.642589 + outer loop + vertex 0.810144 1.75772 2.5519 + vertex 0.808209 1.75661 2.54987 + vertex 0.80927 1.75444 2.55159 + endloop + endfacet + facet normal -0.758993 0.132906 0.63739 + outer loop + vertex 0.808209 1.75661 2.54987 + vertex 0.807344 1.7534 2.54951 + vertex 0.80927 1.75444 2.55159 + endloop + endfacet + facet normal -0.758545 0.129687 0.638585 + outer loop + vertex 0.80927 1.75444 2.55159 + vertex 0.807344 1.7534 2.54951 + vertex 0.809116 1.75079 2.55215 + endloop + endfacet + facet normal -0.754341 0.13619 0.642201 + outer loop + vertex 0.806392 1.74871 2.54939 + vertex 0.809116 1.75079 2.55215 + vertex 0.807344 1.7534 2.54951 + endloop + endfacet + facet normal -0.773297 0.140664 0.618244 + outer loop + vertex 0.805104 1.75269 2.54687 + vertex 0.806392 1.74871 2.54939 + vertex 0.807344 1.7534 2.54951 + endloop + endfacet + facet normal -0.773364 0.144497 0.617275 + outer loop + vertex 0.806047 1.75742 2.54694 + vertex 0.805104 1.75269 2.54687 + vertex 0.807344 1.7534 2.54951 + endloop + endfacet + facet normal -0.792794 0.148787 0.59105 + outer loop + vertex 0.806047 1.75742 2.54694 + vertex 0.803426 1.75552 2.54391 + vertex 0.805104 1.75269 2.54687 + endloop + endfacet + facet normal -0.786804 0.158156 0.596596 + outer loop + vertex 0.803426 1.75552 2.54391 + vertex 0.803261 1.7517 2.5447 + vertex 0.805104 1.75269 2.54687 + endloop + endfacet + facet normal -0.786112 0.150633 0.599447 + outer loop + vertex 0.805104 1.75269 2.54687 + vertex 0.803261 1.7517 2.5447 + vertex 0.804243 1.74946 2.54655 + endloop + endfacet + facet normal -0.794192 0.1572 0.586982 + outer loop + vertex 0.803858 1.76056 2.54314 + vertex 0.803426 1.75552 2.54391 + vertex 0.806047 1.75742 2.54694 + endloop + endfacet + facet normal -0.769763 0.14409 0.621854 + outer loop + vertex 0.804243 1.74946 2.54655 + vertex 0.806392 1.74871 2.54939 + vertex 0.805104 1.75269 2.54687 + endloop + endfacet + facet normal -0.769161 0.146508 0.622034 + outer loop + vertex 0.804243 1.74946 2.54655 + vertex 0.804107 1.74575 2.54726 + vertex 0.806392 1.74871 2.54939 + endloop + endfacet + facet normal -0.768509 0.145203 0.623145 + outer loop + vertex 0.806392 1.74871 2.54939 + vertex 0.804107 1.74575 2.54726 + vertex 0.806224 1.74319 2.55046 + endloop + endfacet + facet normal -0.749696 0.148866 0.644822 + outer loop + vertex 0.806224 1.74319 2.55046 + vertex 0.808758 1.7458 2.55281 + vertex 0.806392 1.74871 2.54939 + endloop + endfacet + facet normal -0.74939 0.148089 0.645356 + outer loop + vertex 0.808585 1.74056 2.55381 + vertex 0.808758 1.7458 2.55281 + vertex 0.806224 1.74319 2.55046 + endloop + endfacet + facet normal -0.743976 0.157929 0.649275 + outer loop + vertex 0.806092 1.73755 2.55169 + vertex 0.808585 1.74056 2.55381 + vertex 0.806224 1.74319 2.55046 + endloop + endfacet + facet normal -0.765557 0.153152 0.624873 + outer loop + vertex 0.806224 1.74319 2.55046 + vertex 0.803711 1.74079 2.54798 + vertex 0.806092 1.73755 2.55169 + endloop + endfacet + facet normal -0.75976 0.162733 0.62951 + outer loop + vertex 0.803711 1.74079 2.54798 + vertex 0.803312 1.73566 2.54882 + vertex 0.806092 1.73755 2.55169 + endloop + endfacet + facet normal -0.755144 0.13942 0.640562 + outer loop + vertex 0.808758 1.7458 2.55281 + vertex 0.809116 1.75079 2.55215 + vertex 0.806392 1.74871 2.54939 + endloop + endfacet + facet normal -0.735277 0.140975 0.662944 + outer loop + vertex 0.809116 1.75079 2.55215 + vertex 0.808758 1.7458 2.55281 + vertex 0.811445 1.74858 2.5552 + endloop + endfacet + facet normal -0.738311 0.134862 0.660839 + outer loop + vertex 0.811641 1.75408 2.55429 + vertex 0.809116 1.75079 2.55215 + vertex 0.811445 1.74858 2.5552 + endloop + endfacet + facet normal -0.717797 0.13769 0.682502 + outer loop + vertex 0.811445 1.74858 2.5552 + vertex 0.814607 1.75178 2.55788 + vertex 0.811641 1.75408 2.55429 + endloop + endfacet + facet normal -0.720484 0.143792 0.6784 + outer loop + vertex 0.813795 1.74599 2.55824 + vertex 0.814607 1.75178 2.55788 + vertex 0.811445 1.74858 2.5552 + endloop + endfacet + facet normal -0.719366 0.145716 0.679175 + outer loop + vertex 0.811125 1.74312 2.55603 + vertex 0.813795 1.74599 2.55824 + vertex 0.811445 1.74858 2.5552 + endloop + endfacet + facet normal -0.720197 0.147462 0.677917 + outer loop + vertex 0.813519 1.74071 2.5591 + vertex 0.813795 1.74599 2.55824 + vertex 0.811125 1.74312 2.55603 + endloop + endfacet + facet normal -0.736531 0.143935 0.660912 + outer loop + vertex 0.811445 1.74858 2.5552 + vertex 0.808758 1.7458 2.55281 + vertex 0.811125 1.74312 2.55603 + endloop + endfacet + facet normal -0.732458 0.151059 0.663842 + outer loop + vertex 0.808758 1.7458 2.55281 + vertex 0.808585 1.74056 2.55381 + vertex 0.811125 1.74312 2.55603 + endloop + endfacet + facet normal -0.730992 0.147515 0.666251 + outer loop + vertex 0.811125 1.74312 2.55603 + vertex 0.808585 1.74056 2.55381 + vertex 0.811222 1.73731 2.55742 + endloop + endfacet + facet normal -0.718364 0.15081 0.679125 + outer loop + vertex 0.811222 1.73731 2.55742 + vertex 0.813519 1.74071 2.5591 + vertex 0.811125 1.74312 2.55603 + endloop + endfacet + facet normal -0.777361 0.140577 0.613147 + outer loop + vertex 0.808209 1.75661 2.54987 + vertex 0.806047 1.75742 2.54694 + vertex 0.807344 1.7534 2.54951 + endloop + endfacet + facet normal -0.776835 0.142652 0.613334 + outer loop + vertex 0.808209 1.75661 2.54987 + vertex 0.808349 1.76041 2.54916 + vertex 0.806047 1.75742 2.54694 + endloop + endfacet + facet normal -0.754412 0.146749 0.639786 + outer loop + vertex 0.808349 1.76041 2.54916 + vertex 0.808209 1.75661 2.54987 + vertex 0.810144 1.75772 2.5519 + endloop + endfacet + facet normal -0.755267 0.145455 0.639074 + outer loop + vertex 0.811046 1.76255 2.55186 + vertex 0.808349 1.76041 2.54916 + vertex 0.810144 1.75772 2.5519 + endloop + endfacet + facet normal -0.736927 0.13248 0.662863 + outer loop + vertex 0.80927 1.75444 2.55159 + vertex 0.809116 1.75079 2.55215 + vertex 0.811641 1.75408 2.55429 + endloop + endfacet + facet normal -0.720221 0.132265 0.681019 + outer loop + vertex 0.814607 1.75178 2.55788 + vertex 0.814606 1.75684 2.55689 + vertex 0.811641 1.75408 2.55429 + endloop + endfacet + facet normal -0.738255 0.142425 0.659314 + outer loop + vertex 0.811046 1.76255 2.55186 + vertex 0.810144 1.75772 2.5519 + vertex 0.812527 1.75881 2.55433 + endloop + endfacet + facet normal -0.755511 0.146401 0.638568 + outer loop + vertex 0.808627 1.76552 2.54832 + vertex 0.808349 1.76041 2.54916 + vertex 0.811046 1.76255 2.55186 + endloop + endfacet + facet normal -0.781273 0.142711 0.607657 + outer loop + vertex 0.808349 1.76041 2.54916 + vertex 0.808627 1.76552 2.54832 + vertex 0.806215 1.76297 2.54582 + endloop + endfacet + facet normal -0.778976 0.147111 0.609553 + outer loop + vertex 0.806047 1.75742 2.54694 + vertex 0.808349 1.76041 2.54916 + vertex 0.806215 1.76297 2.54582 + endloop + endfacet + facet normal -0.802812 0.141674 0.579155 + outer loop + vertex 0.806215 1.76297 2.54582 + vertex 0.803858 1.76056 2.54314 + vertex 0.806047 1.75742 2.54694 + endloop + endfacet + facet normal -0.781155 0.142374 0.607887 + outer loop + vertex 0.806215 1.76297 2.54582 + vertex 0.808627 1.76552 2.54832 + vertex 0.806346 1.76854 2.54468 + endloop + endfacet + facet normal -0.784689 0.135975 0.604792 + outer loop + vertex 0.808627 1.76552 2.54832 + vertex 0.808877 1.7707 2.54748 + vertex 0.806346 1.76854 2.54468 + endloop + endfacet + facet normal -0.780253 0.118712 0.614096 + outer loop + vertex 0.806346 1.76854 2.54468 + vertex 0.808877 1.7707 2.54748 + vertex 0.807131 1.77348 2.54473 + endloop + endfacet + facet normal -0.778004 0.122259 0.616249 + outer loop + vertex 0.808926 1.7746 2.54677 + vertex 0.807131 1.77348 2.54473 + vertex 0.808877 1.7707 2.54748 + endloop + endfacet + facet normal -0.753483 0.127203 0.645045 + outer loop + vertex 0.808926 1.7746 2.54677 + vertex 0.808877 1.7707 2.54748 + vertex 0.81123 1.77386 2.54961 + endloop + endfacet + facet normal -0.757918 0.107327 0.64346 + outer loop + vertex 0.808926 1.7746 2.54677 + vertex 0.81123 1.77386 2.54961 + vertex 0.809649 1.7779 2.54707 + endloop + endfacet + facet normal -0.738115 0.14584 0.658723 + outer loop + vertex 0.813421 1.76585 2.55377 + vertex 0.813745 1.77084 2.55303 + vertex 0.811142 1.76817 2.55071 + endloop + endfacet + facet normal -0.710368 0.133994 0.690958 + outer loop + vertex 0.818079 1.7658 2.5586 + vertex 0.81867 1.77081 2.55823 + vertex 0.815958 1.76833 2.55593 + endloop + endfacet + facet normal -0.720073 0.105222 0.685874 + outer loop + vertex 0.816452 1.7733 2.55548 + vertex 0.819128 1.77582 2.5579 + vertex 0.816764 1.77832 2.55503 + endloop + endfacet + facet normal -0.675084 0.119313 0.728028 + outer loop + vertex 0.823682 1.77086 2.56314 + vertex 0.823261 1.76579 2.56359 + vertex 0.826014 1.76828 2.56573 + endloop + endfacet + facet normal -0.68637 0.101247 0.72017 + outer loop + vertex 0.826475 1.77348 2.56544 + vertex 0.823682 1.77086 2.56314 + vertex 0.826014 1.76828 2.56573 + endloop + endfacet + facet normal -0.669505 0.100634 0.735959 + outer loop + vertex 0.826014 1.76828 2.56573 + vertex 0.828851 1.77095 2.56795 + vertex 0.826475 1.77348 2.56544 + endloop + endfacet + facet normal -0.681197 0.0813354 0.727568 + outer loop + vertex 0.828851 1.77095 2.56795 + vertex 0.829332 1.77621 2.56781 + vertex 0.826475 1.77348 2.56544 + endloop + endfacet + facet normal -0.661465 0.0800039 0.745696 + outer loop + vertex 0.829332 1.77621 2.56781 + vertex 0.828851 1.77095 2.56795 + vertex 0.831733 1.77372 2.57021 + endloop + endfacet + facet normal -0.666498 0.089841 0.740073 + outer loop + vertex 0.831733 1.77372 2.57021 + vertex 0.828851 1.77095 2.56795 + vertex 0.831363 1.76849 2.57051 + endloop + endfacet + facet normal -0.644696 0.0894041 0.759193 + outer loop + vertex 0.831363 1.76849 2.57051 + vertex 0.834684 1.77172 2.57295 + vertex 0.831733 1.77372 2.57021 + endloop + endfacet + facet normal -0.652323 0.103558 0.750833 + outer loop + vertex 0.833895 1.76589 2.57306 + vertex 0.834684 1.77172 2.57295 + vertex 0.831363 1.76849 2.57051 + endloop + endfacet + facet normal -0.641989 0.120009 0.757264 + outer loop + vertex 0.830799 1.76328 2.57085 + vertex 0.833895 1.76589 2.57306 + vertex 0.831363 1.76849 2.57051 + endloop + endfacet + facet normal -0.660892 0.120953 0.74067 + outer loop + vertex 0.831363 1.76849 2.57051 + vertex 0.828416 1.76575 2.56832 + vertex 0.830799 1.76328 2.57085 + endloop + endfacet + facet normal -0.653049 0.133443 0.745467 + outer loop + vertex 0.828416 1.76575 2.56832 + vertex 0.828125 1.76107 2.56891 + vertex 0.830799 1.76328 2.57085 + endloop + endfacet + facet normal -0.657061 0.14298 0.740153 + outer loop + vertex 0.830799 1.76328 2.57085 + vertex 0.828125 1.76107 2.56891 + vertex 0.830133 1.75886 2.57112 + endloop + endfacet + facet normal -0.644975 0.141802 0.750932 + outer loop + vertex 0.830133 1.75886 2.57112 + vertex 0.833153 1.76061 2.57338 + vertex 0.830799 1.76328 2.57085 + endloop + endfacet + facet normal -0.648534 0.155386 0.745157 + outer loop + vertex 0.832125 1.75526 2.5736 + vertex 0.833153 1.76061 2.57338 + vertex 0.830133 1.75886 2.57112 + endloop + endfacet + facet normal -0.653293 0.150563 0.741983 + outer loop + vertex 0.828635 1.75577 2.57042 + vertex 0.832125 1.75526 2.5736 + vertex 0.830133 1.75886 2.57112 + endloop + endfacet + facet normal -0.655497 0.152143 0.739714 + outer loop + vertex 0.830133 1.75886 2.57112 + vertex 0.828151 1.75826 2.56948 + vertex 0.828635 1.75577 2.57042 + endloop + endfacet + facet normal -0.663023 0.148426 0.733737 + outer loop + vertex 0.825831 1.75812 2.56742 + vertex 0.828635 1.75577 2.57042 + vertex 0.828151 1.75826 2.56948 + endloop + endfacet + facet normal -0.663273 0.144506 0.734294 + outer loop + vertex 0.828151 1.75826 2.56948 + vertex 0.828125 1.76107 2.56891 + vertex 0.825831 1.75812 2.56742 + endloop + endfacet + facet normal -0.661639 0.142274 0.736201 + outer loop + vertex 0.825831 1.75812 2.56742 + vertex 0.828125 1.76107 2.56891 + vertex 0.825728 1.76322 2.56634 + endloop + endfacet + facet normal -0.672902 0.139967 0.726369 + outer loop + vertex 0.825728 1.76322 2.56634 + vertex 0.823141 1.76098 2.56437 + vertex 0.825831 1.75812 2.56742 + endloop + endfacet + facet normal -0.671215 0.135998 0.728681 + outer loop + vertex 0.823261 1.76579 2.56359 + vertex 0.823141 1.76098 2.56437 + vertex 0.825728 1.76322 2.56634 + endloop + endfacet + facet normal -0.660976 0.152235 0.734802 + outer loop + vertex 0.825831 1.75812 2.56742 + vertex 0.826304 1.75331 2.56884 + vertex 0.828635 1.75577 2.57042 + endloop + endfacet + facet normal -0.66309 0.155978 0.732108 + outer loop + vertex 0.828635 1.75577 2.57042 + vertex 0.826304 1.75331 2.56884 + vertex 0.829267 1.75163 2.57188 + endloop + endfacet + facet normal -0.67174 0.1485 0.72575 + outer loop + vertex 0.825831 1.75812 2.56742 + vertex 0.82353 1.75516 2.56589 + vertex 0.826304 1.75331 2.56884 + endloop + endfacet + facet normal -0.670358 0.151591 0.726388 + outer loop + vertex 0.82353 1.75516 2.56589 + vertex 0.823826 1.75077 2.56708 + vertex 0.826304 1.75331 2.56884 + endloop + endfacet + facet normal -0.672082 0.154849 0.724105 + outer loop + vertex 0.826304 1.75331 2.56884 + vertex 0.823826 1.75077 2.56708 + vertex 0.826546 1.74866 2.57006 + endloop + endfacet + facet normal -0.662464 0.15751 0.732347 + outer loop + vertex 0.826546 1.74866 2.57006 + vertex 0.829267 1.75163 2.57188 + vertex 0.826304 1.75331 2.56884 + endloop + endfacet + facet normal -0.664617 0.161176 0.729593 + outer loop + vertex 0.82958 1.7466 2.57328 + vertex 0.829267 1.75163 2.57188 + vertex 0.826546 1.74866 2.57006 + endloop + endfacet + facet normal -0.666929 0.156171 0.728572 + outer loop + vertex 0.826248 1.74364 2.57086 + vertex 0.82958 1.7466 2.57328 + vertex 0.826546 1.74866 2.57006 + endloop + endfacet + facet normal -0.672981 0.155653 0.723097 + outer loop + vertex 0.826546 1.74866 2.57006 + vertex 0.82372 1.74595 2.56801 + vertex 0.826248 1.74364 2.57086 + endloop + endfacet + facet normal -0.675251 0.151621 0.721836 + outer loop + vertex 0.82372 1.74595 2.56801 + vertex 0.823173 1.74092 2.56856 + vertex 0.826248 1.74364 2.57086 + endloop + endfacet + facet normal -0.672893 0.146139 0.725161 + outer loop + vertex 0.826248 1.74364 2.57086 + vertex 0.823173 1.74092 2.56856 + vertex 0.825535 1.73849 2.57124 + endloop + endfacet + facet normal -0.670523 0.145973 0.727387 + outer loop + vertex 0.825535 1.73849 2.57124 + vertex 0.828645 1.74119 2.57356 + vertex 0.826248 1.74364 2.57086 + endloop + endfacet + facet normal -0.665828 0.135047 0.733782 + outer loop + vertex 0.827912 1.7361 2.57383 + vertex 0.828645 1.74119 2.57356 + vertex 0.825535 1.73849 2.57124 + endloop + endfacet + facet normal -0.66911 0.129604 0.731775 + outer loop + vertex 0.824911 1.73365 2.57152 + vertex 0.827912 1.7361 2.57383 + vertex 0.825535 1.73849 2.57124 + endloop + endfacet + facet normal -0.673133 0.129899 0.728023 + outer loop + vertex 0.825535 1.73849 2.57124 + vertex 0.822089 1.73559 2.56857 + vertex 0.824911 1.73365 2.57152 + endloop + endfacet + facet normal -0.675397 0.124773 0.726823 + outer loop + vertex 0.822089 1.73559 2.56857 + vertex 0.822276 1.73084 2.56956 + vertex 0.824911 1.73365 2.57152 + endloop + endfacet + facet normal -0.67079 0.116528 0.732436 + outer loop + vertex 0.824911 1.73365 2.57152 + vertex 0.822276 1.73084 2.56956 + vertex 0.824361 1.73001 2.5716 + endloop + endfacet + facet normal -0.662699 0.115461 0.739932 + outer loop + vertex 0.824361 1.73001 2.5716 + vertex 0.827045 1.7308 2.57388 + vertex 0.824911 1.73365 2.57152 + endloop + endfacet + facet normal -0.661673 0.104839 0.742426 + outer loop + vertex 0.824361 1.73001 2.5716 + vertex 0.824703 1.72681 2.57235 + vertex 0.827045 1.7308 2.57388 + endloop + endfacet + facet normal -0.660508 0.103698 0.743624 + outer loop + vertex 0.824703 1.72681 2.57235 + vertex 0.827181 1.72615 2.57465 + vertex 0.827045 1.7308 2.57388 + endloop + endfacet + facet normal -0.658056 0.104119 0.745735 + outer loop + vertex 0.827045 1.7308 2.57388 + vertex 0.827181 1.72615 2.57465 + vertex 0.829767 1.72883 2.57656 + endloop + endfacet + facet normal -0.657095 0.106199 0.74629 + outer loop + vertex 0.830299 1.73363 2.57634 + vertex 0.827045 1.7308 2.57388 + vertex 0.829767 1.72883 2.57656 + endloop + endfacet + facet normal -0.649636 0.105666 0.752866 + outer loop + vertex 0.829767 1.72883 2.57656 + vertex 0.832781 1.73111 2.57884 + vertex 0.830299 1.73363 2.57634 + endloop + endfacet + facet normal -0.64613 0.111301 0.755068 + outer loop + vertex 0.832781 1.73111 2.57884 + vertex 0.83334 1.73615 2.57857 + vertex 0.830299 1.73363 2.57634 + endloop + endfacet + facet normal -0.650212 0.120631 0.750115 + outer loop + vertex 0.830299 1.73363 2.57634 + vertex 0.83334 1.73615 2.57857 + vertex 0.830916 1.73862 2.57607 + endloop + endfacet + facet normal -0.656785 0.121132 0.744285 + outer loop + vertex 0.830916 1.73862 2.57607 + vertex 0.827912 1.7361 2.57383 + vertex 0.830299 1.73363 2.57634 + endloop + endfacet + facet normal -0.645207 0.128556 0.753114 + outer loop + vertex 0.83334 1.73615 2.57857 + vertex 0.833799 1.74103 2.57813 + vertex 0.830916 1.73862 2.57607 + endloop + endfacet + facet normal -0.650199 0.14 0.746754 + outer loop + vertex 0.830916 1.73862 2.57607 + vertex 0.833799 1.74103 2.57813 + vertex 0.831568 1.74338 2.57575 + endloop + endfacet + facet normal -0.658622 0.140638 0.739215 + outer loop + vertex 0.831568 1.74338 2.57575 + vertex 0.828645 1.74119 2.57356 + vertex 0.830916 1.73862 2.57607 + endloop + endfacet + facet normal -0.663166 0.153304 0.732604 + outer loop + vertex 0.82958 1.7466 2.57328 + vertex 0.828645 1.74119 2.57356 + vertex 0.831568 1.74338 2.57575 + endloop + endfacet + facet normal -0.659701 0.157211 0.734901 + outer loop + vertex 0.83235 1.74696 2.57569 + vertex 0.82958 1.7466 2.57328 + vertex 0.831568 1.74338 2.57575 + endloop + endfacet + facet normal -0.648183 0.154882 0.745567 + outer loop + vertex 0.831568 1.74338 2.57575 + vertex 0.834148 1.74533 2.57759 + vertex 0.83235 1.74696 2.57569 + endloop + endfacet + facet normal -0.645349 0.147401 0.749532 + outer loop + vertex 0.833799 1.74103 2.57813 + vertex 0.834148 1.74533 2.57759 + vertex 0.831568 1.74338 2.57575 + endloop + endfacet + facet normal -0.633811 0.147701 0.759255 + outer loop + vertex 0.834148 1.74533 2.57759 + vertex 0.833799 1.74103 2.57813 + vertex 0.836568 1.74363 2.57994 + endloop + endfacet + facet normal -0.628163 0.159014 0.76166 + outer loop + vertex 0.83646 1.7479 2.57896 + vertex 0.834148 1.74533 2.57759 + vertex 0.836568 1.74363 2.57994 + endloop + endfacet + facet normal -0.621458 0.160377 0.766856 + outer loop + vertex 0.836568 1.74363 2.57994 + vertex 0.839321 1.74668 2.58153 + vertex 0.83646 1.7479 2.57896 + endloop + endfacet + facet normal -0.619218 0.166658 0.767329 + outer loop + vertex 0.8388 1.75075 2.58023 + vertex 0.83646 1.7479 2.57896 + vertex 0.839321 1.74668 2.58153 + endloop + endfacet + facet normal -0.614202 0.168462 0.770958 + outer loop + vertex 0.8388 1.75075 2.58023 + vertex 0.839321 1.74668 2.58153 + vertex 0.84246 1.7508 2.58313 + endloop + endfacet + facet normal -0.614342 0.167028 0.771159 + outer loop + vertex 0.8388 1.75075 2.58023 + vertex 0.84246 1.7508 2.58313 + vertex 0.840566 1.75424 2.58088 + endloop + endfacet + facet normal -0.620946 0.171544 0.764853 + outer loop + vertex 0.840566 1.75424 2.58088 + vertex 0.838343 1.7532 2.57931 + vertex 0.8388 1.75075 2.58023 + endloop + endfacet + facet normal -0.628688 0.16801 0.759292 + outer loop + vertex 0.835769 1.75243 2.57734 + vertex 0.8388 1.75075 2.58023 + vertex 0.838343 1.7532 2.57931 + endloop + endfacet + facet normal -0.628759 0.16889 0.759038 + outer loop + vertex 0.838343 1.7532 2.57931 + vertex 0.838408 1.75609 2.57872 + vertex 0.835769 1.75243 2.57734 + endloop + endfacet + facet normal -0.627612 0.167602 0.760271 + outer loop + vertex 0.835769 1.75243 2.57734 + vertex 0.838408 1.75609 2.57872 + vertex 0.835758 1.75795 2.57612 + endloop + endfacet + facet normal -0.632273 0.158346 0.758391 + outer loop + vertex 0.838408 1.75609 2.57872 + vertex 0.838942 1.7609 2.57816 + vertex 0.835758 1.75795 2.57612 + endloop + endfacet + facet normal -0.62724 0.14869 0.764501 + outer loop + vertex 0.835758 1.75795 2.57612 + vertex 0.838942 1.7609 2.57816 + vertex 0.836429 1.7633 2.57563 + endloop + endfacet + facet normal -0.636258 0.134173 0.759719 + outer loop + vertex 0.838942 1.7609 2.57816 + vertex 0.839922 1.76653 2.57798 + vertex 0.836429 1.7633 2.57563 + endloop + endfacet + facet normal -0.630322 0.122794 0.766561 + outer loop + vertex 0.836429 1.7633 2.57563 + vertex 0.839922 1.76653 2.57798 + vertex 0.837075 1.76857 2.57532 + endloop + endfacet + facet normal -0.640575 0.123533 0.757894 + outer loop + vertex 0.837075 1.76857 2.57532 + vertex 0.833895 1.76589 2.57306 + vertex 0.836429 1.7633 2.57563 + endloop + endfacet + facet normal -0.633491 0.134473 0.761975 + outer loop + vertex 0.833895 1.76589 2.57306 + vertex 0.833153 1.76061 2.57338 + vertex 0.836429 1.7633 2.57563 + endloop + endfacet + facet normal -0.63999 0.149307 0.753737 + outer loop + vertex 0.836429 1.7633 2.57563 + vertex 0.833153 1.76061 2.57338 + vertex 0.835758 1.75795 2.57612 + endloop + endfacet + facet normal -0.63718 0.153619 0.75525 + outer loop + vertex 0.833153 1.76061 2.57338 + vertex 0.832125 1.75526 2.5736 + vertex 0.835758 1.75795 2.57612 + endloop + endfacet + facet normal -0.641479 0.165108 0.749162 + outer loop + vertex 0.835758 1.75795 2.57612 + vertex 0.832125 1.75526 2.5736 + vertex 0.835769 1.75243 2.57734 + endloop + endfacet + facet normal -0.639479 0.168845 0.750039 + outer loop + vertex 0.832125 1.75526 2.5736 + vertex 0.832227 1.75029 2.57481 + vertex 0.835769 1.75243 2.57734 + endloop + endfacet + facet normal -0.630068 0.100929 0.769953 + outer loop + vertex 0.834684 1.77172 2.57295 + vertex 0.833895 1.76589 2.57306 + vertex 0.837075 1.76857 2.57532 + endloop + endfacet + facet normal -0.637789 0.0911664 0.764796 + outer loop + vertex 0.837593 1.77267 2.57526 + vertex 0.834684 1.77172 2.57295 + vertex 0.837075 1.76857 2.57532 + endloop + endfacet + facet normal -0.632315 0.0551517 0.772745 + outer loop + vertex 0.837593 1.77267 2.57526 + vertex 0.836855 1.77631 2.5744 + vertex 0.834684 1.77172 2.57295 + endloop + endfacet + facet normal -0.646866 0.0661236 0.759731 + outer loop + vertex 0.834684 1.77172 2.57295 + vertex 0.836855 1.77631 2.5744 + vertex 0.834103 1.7762 2.57206 + endloop + endfacet + facet normal -0.639567 0.0523123 0.766953 + outer loop + vertex 0.837593 1.77267 2.57526 + vertex 0.839164 1.77498 2.57641 + vertex 0.836855 1.77631 2.5744 + endloop + endfacet + facet normal -0.64534 0.0364336 0.763026 + outer loop + vertex 0.839218 1.77783 2.57632 + vertex 0.836855 1.77631 2.5744 + vertex 0.839164 1.77498 2.57641 + endloop + endfacet + facet normal -0.643536 0.0951009 0.759485 + outer loop + vertex 0.839922 1.76653 2.57798 + vertex 0.839745 1.77162 2.5772 + vertex 0.837075 1.76857 2.57532 + endloop + endfacet + facet normal -0.641188 0.0915561 0.761903 + outer loop + vertex 0.837075 1.76857 2.57532 + vertex 0.839745 1.77162 2.5772 + vertex 0.837593 1.77267 2.57526 + endloop + endfacet + facet normal -0.650082 0.0643787 0.757132 + outer loop + vertex 0.839164 1.77498 2.57641 + vertex 0.837593 1.77267 2.57526 + vertex 0.839745 1.77162 2.5772 + endloop + endfacet + facet normal -0.659982 0.0607183 0.748824 + outer loop + vertex 0.839164 1.77498 2.57641 + vertex 0.839745 1.77162 2.5772 + vertex 0.841817 1.77622 2.57865 + endloop + endfacet + facet normal -0.654192 0.036365 0.755454 + outer loop + vertex 0.839164 1.77498 2.57641 + vertex 0.841817 1.77622 2.57865 + vertex 0.839218 1.77783 2.57632 + endloop + endfacet + facet normal -0.639709 0.0957215 0.762633 + outer loop + vertex 0.839922 1.76653 2.57798 + vertex 0.842356 1.77084 2.57948 + vertex 0.839745 1.77162 2.5772 + endloop + endfacet + facet normal -0.6258 0.0833712 0.775515 + outer loop + vertex 0.842754 1.7674 2.58018 + vertex 0.842356 1.77084 2.57948 + vertex 0.839922 1.76653 2.57798 + endloop + endfacet + facet normal -0.630475 0.120713 0.766766 + outer loop + vertex 0.842754 1.7674 2.58018 + vertex 0.839922 1.76653 2.57798 + vertex 0.842035 1.7636 2.58018 + endloop + endfacet + facet normal -0.632644 0.12112 0.764912 + outer loop + vertex 0.842035 1.7636 2.58018 + vertex 0.844774 1.76643 2.582 + vertex 0.842754 1.7674 2.58018 + endloop + endfacet + facet normal -0.643597 0.0893955 0.760126 + outer loop + vertex 0.844482 1.76975 2.58136 + vertex 0.842754 1.7674 2.58018 + vertex 0.844774 1.76643 2.582 + endloop + endfacet + facet normal -0.6496 0.0879175 0.755176 + outer loop + vertex 0.844482 1.76975 2.58136 + vertex 0.844774 1.76643 2.582 + vertex 0.847242 1.77042 2.58366 + endloop + endfacet + facet normal -0.646168 0.0526358 0.761378 + outer loop + vertex 0.844482 1.76975 2.58136 + vertex 0.847242 1.77042 2.58366 + vertex 0.844915 1.7736 2.58146 + endloop + endfacet + facet normal -0.64579 0.0525848 0.761702 + outer loop + vertex 0.844915 1.7736 2.58146 + vertex 0.842356 1.77084 2.57948 + vertex 0.844482 1.76975 2.58136 + endloop + endfacet + facet normal -0.636879 0.075023 0.767304 + outer loop + vertex 0.844774 1.76643 2.582 + vertex 0.847393 1.76538 2.58428 + vertex 0.847242 1.77042 2.58366 + endloop + endfacet + facet normal -0.623622 0.0767244 0.777952 + outer loop + vertex 0.847242 1.77042 2.58366 + vertex 0.847393 1.76538 2.58428 + vertex 0.850314 1.76835 2.58633 + endloop + endfacet + facet normal -0.636974 0.0461079 0.769505 + outer loop + vertex 0.850504 1.77331 2.58618 + vertex 0.847242 1.77042 2.58366 + vertex 0.850314 1.76835 2.58633 + endloop + endfacet + facet normal -0.624179 0.0459133 0.779931 + outer loop + vertex 0.850314 1.76835 2.58633 + vertex 0.853302 1.7709 2.58857 + vertex 0.850504 1.77331 2.58618 + endloop + endfacet + facet normal -0.624337 0.0779045 0.777261 + outer loop + vertex 0.850314 1.76835 2.58633 + vertex 0.847393 1.76538 2.58428 + vertex 0.849982 1.76369 2.58652 + endloop + endfacet + facet normal -0.612719 0.0774717 0.786495 + outer loop + vertex 0.849982 1.76369 2.58652 + vertex 0.853012 1.76599 2.58866 + vertex 0.850314 1.76835 2.58633 + endloop + endfacet + facet normal -0.622002 0.0987848 0.77676 + outer loop + vertex 0.852194 1.76074 2.58867 + vertex 0.853012 1.76599 2.58866 + vertex 0.849982 1.76369 2.58652 + endloop + endfacet + facet normal -0.607306 0.116451 0.785887 + outer loop + vertex 0.849303 1.76008 2.58654 + vertex 0.852194 1.76074 2.58867 + vertex 0.849982 1.76369 2.58652 + endloop + endfacet + facet normal -0.609033 0.116772 0.784502 + outer loop + vertex 0.849982 1.76369 2.58652 + vertex 0.847166 1.761 2.58474 + vertex 0.849303 1.76008 2.58654 + endloop + endfacet + facet normal -0.599638 0.14395 0.787218 + outer loop + vertex 0.847357 1.75773 2.58548 + vertex 0.849303 1.76008 2.58654 + vertex 0.847166 1.761 2.58474 + endloop + endfacet + facet normal -0.603154 0.143167 0.784671 + outer loop + vertex 0.847357 1.75773 2.58548 + vertex 0.847166 1.761 2.58474 + vertex 0.844253 1.75684 2.58326 + endloop + endfacet + facet normal -0.604962 0.162293 0.779539 + outer loop + vertex 0.847357 1.75773 2.58548 + vertex 0.844253 1.75684 2.58326 + vertex 0.846442 1.75375 2.5856 + endloop + endfacet + facet normal -0.599882 0.161247 0.783672 + outer loop + vertex 0.846442 1.75375 2.5856 + vertex 0.849524 1.75676 2.58734 + vertex 0.847357 1.75773 2.58548 + endloop + endfacet + facet normal -0.599263 0.160218 0.784355 + outer loop + vertex 0.849453 1.75185 2.58829 + vertex 0.849524 1.75676 2.58734 + vertex 0.846442 1.75375 2.5856 + endloop + endfacet + facet normal -0.598224 0.162363 0.784708 + outer loop + vertex 0.845639 1.7486 2.58606 + vertex 0.849453 1.75185 2.58829 + vertex 0.846442 1.75375 2.5856 + endloop + endfacet + facet normal -0.604445 0.162902 0.779813 + outer loop + vertex 0.846442 1.75375 2.5856 + vertex 0.84246 1.7508 2.58313 + vertex 0.845639 1.7486 2.58606 + endloop + endfacet + facet normal -0.604788 0.162238 0.779686 + outer loop + vertex 0.84246 1.7508 2.58313 + vertex 0.842307 1.7454 2.58414 + vertex 0.845639 1.7486 2.58606 + endloop + endfacet + facet normal -0.598315 0.151172 0.786871 + outer loop + vertex 0.845639 1.7486 2.58606 + vertex 0.842307 1.7454 2.58414 + vertex 0.844956 1.74365 2.58649 + endloop + endfacet + facet normal -0.596178 0.15102 0.788521 + outer loop + vertex 0.844956 1.74365 2.58649 + vertex 0.848284 1.74623 2.58851 + vertex 0.845639 1.7486 2.58606 + endloop + endfacet + facet normal -0.588034 0.13324 0.797786 + outer loop + vertex 0.847189 1.74068 2.58863 + vertex 0.848284 1.74623 2.58851 + vertex 0.844956 1.74365 2.58649 + endloop + endfacet + facet normal -0.587673 0.133653 0.797984 + outer loop + vertex 0.84423 1.73998 2.58657 + vertex 0.847189 1.74068 2.58863 + vertex 0.844956 1.74365 2.58649 + endloop + endfacet + facet normal -0.59626 0.135198 0.791325 + outer loop + vertex 0.844956 1.74365 2.58649 + vertex 0.842121 1.74093 2.58481 + vertex 0.84423 1.73998 2.58657 + endloop + endfacet + facet normal -0.599601 0.125965 0.790323 + outer loop + vertex 0.842407 1.7377 2.58555 + vertex 0.84423 1.73998 2.58657 + vertex 0.842121 1.74093 2.58481 + endloop + endfacet + facet normal -0.606697 0.124169 0.785176 + outer loop + vertex 0.842407 1.7377 2.58555 + vertex 0.842121 1.74093 2.58481 + vertex 0.839494 1.73688 2.58343 + endloop + endfacet + facet normal -0.605276 0.111335 0.788191 + outer loop + vertex 0.842407 1.7377 2.58555 + vertex 0.839494 1.73688 2.58343 + vertex 0.841748 1.73396 2.58557 + endloop + endfacet + facet normal -0.605097 0.111552 0.788298 + outer loop + vertex 0.839494 1.73688 2.58343 + vertex 0.838605 1.73133 2.58353 + vertex 0.841748 1.73396 2.58557 + endloop + endfacet + facet normal -0.603511 0.108369 0.789956 + outer loop + vertex 0.841748 1.73396 2.58557 + vertex 0.838605 1.73133 2.58353 + vertex 0.841255 1.72905 2.58587 + endloop + endfacet + facet normal -0.604558 0.106577 0.789399 + outer loop + vertex 0.838605 1.73133 2.58353 + vertex 0.83794 1.7262 2.58371 + vertex 0.841255 1.72905 2.58587 + endloop + endfacet + facet normal -0.607348 0.111998 0.786501 + outer loop + vertex 0.841255 1.72905 2.58587 + vertex 0.83794 1.7262 2.58371 + vertex 0.840636 1.72386 2.58613 + endloop + endfacet + facet normal -0.592473 0.110801 0.797934 + outer loop + vertex 0.840636 1.72386 2.58613 + vertex 0.844369 1.72703 2.58846 + vertex 0.841255 1.72905 2.58587 + endloop + endfacet + facet normal -0.593156 0.109358 0.797625 + outer loop + vertex 0.844369 1.72703 2.58846 + vertex 0.844343 1.73225 2.58772 + vertex 0.841255 1.72905 2.58587 + endloop + endfacet + facet normal -0.592096 0.107746 0.798632 + outer loop + vertex 0.841255 1.72905 2.58587 + vertex 0.844343 1.73225 2.58772 + vertex 0.841748 1.73396 2.58557 + endloop + endfacet + facet normal -0.591846 0.108268 0.798746 + outer loop + vertex 0.844343 1.73225 2.58772 + vertex 0.84451 1.73672 2.58724 + vertex 0.841748 1.73396 2.58557 + endloop + endfacet + facet normal -0.592387 0.109121 0.798229 + outer loop + vertex 0.841748 1.73396 2.58557 + vertex 0.84451 1.73672 2.58724 + vertex 0.842407 1.7377 2.58555 + endloop + endfacet + facet normal -0.586864 0.108475 0.802386 + outer loop + vertex 0.844343 1.73225 2.58772 + vertex 0.847204 1.73556 2.58937 + vertex 0.84451 1.73672 2.58724 + endloop + endfacet + facet normal -0.584833 0.114383 0.803049 + outer loop + vertex 0.84451 1.73672 2.58724 + vertex 0.847204 1.73556 2.58937 + vertex 0.847189 1.74068 2.58863 + endloop + endfacet + facet normal -0.588688 0.113972 0.800285 + outer loop + vertex 0.847189 1.74068 2.58863 + vertex 0.847204 1.73556 2.58937 + vertex 0.850295 1.73855 2.59122 + endloop + endfacet + facet normal -0.585736 0.11987 0.801589 + outer loop + vertex 0.850919 1.74371 2.5909 + vertex 0.847189 1.74068 2.58863 + vertex 0.850295 1.73855 2.59122 + endloop + endfacet + facet normal -0.587564 0.120008 0.800229 + outer loop + vertex 0.850295 1.73855 2.59122 + vertex 0.853645 1.74129 2.59327 + vertex 0.850919 1.74371 2.5909 + endloop + endfacet + facet normal -0.583109 0.127132 0.802385 + outer loop + vertex 0.853645 1.74129 2.59327 + vertex 0.854612 1.74671 2.59311 + vertex 0.850919 1.74371 2.5909 + endloop + endfacet + facet normal -0.589674 0.140402 0.795344 + outer loop + vertex 0.850919 1.74371 2.5909 + vertex 0.854612 1.74671 2.59311 + vertex 0.851688 1.74879 2.59058 + endloop + endfacet + facet normal -0.588632 0.140295 0.796134 + outer loop + vertex 0.851688 1.74879 2.59058 + vertex 0.848284 1.74623 2.58851 + vertex 0.850919 1.74371 2.5909 + endloop + endfacet + facet normal -0.594819 0.154409 0.788891 + outer loop + vertex 0.849453 1.75185 2.58829 + vertex 0.848284 1.74623 2.58851 + vertex 0.851688 1.74879 2.59058 + endloop + endfacet + facet normal -0.593003 0.156453 0.789854 + outer loop + vertex 0.852457 1.75264 2.59039 + vertex 0.849453 1.75185 2.58829 + vertex 0.851688 1.74879 2.59058 + endloop + endfacet + facet normal -0.588509 0.155727 0.793351 + outer loop + vertex 0.851688 1.74879 2.59058 + vertex 0.854617 1.75156 2.5922 + vertex 0.852457 1.75264 2.59039 + endloop + endfacet + facet normal -0.58483 0.149546 0.797252 + outer loop + vertex 0.854612 1.74671 2.59311 + vertex 0.854617 1.75156 2.5922 + vertex 0.851688 1.74879 2.59058 + endloop + endfacet + facet normal -0.584138 0.149637 0.797741 + outer loop + vertex 0.854612 1.74671 2.59311 + vertex 0.857329 1.75074 2.59434 + vertex 0.854617 1.75156 2.5922 + endloop + endfacet + facet normal -0.58309 0.15331 0.797811 + outer loop + vertex 0.854617 1.75156 2.5922 + vertex 0.857329 1.75074 2.59434 + vertex 0.857359 1.75561 2.59343 + endloop + endfacet + facet normal -0.589012 0.158973 0.792334 + outer loop + vertex 0.854369 1.75491 2.59135 + vertex 0.854617 1.75156 2.5922 + vertex 0.857359 1.75561 2.59343 + endloop + endfacet + facet normal -0.588114 0.145268 0.795625 + outer loop + vertex 0.854369 1.75491 2.59135 + vertex 0.857359 1.75561 2.59343 + vertex 0.855095 1.75866 2.5912 + endloop + endfacet + facet normal -0.59361 0.146168 0.791367 + outer loop + vertex 0.855095 1.75866 2.5912 + vertex 0.852214 1.75598 2.58953 + vertex 0.854369 1.75491 2.59135 + endloop + endfacet + facet normal -0.587784 0.160537 0.79293 + outer loop + vertex 0.852457 1.75264 2.59039 + vertex 0.854369 1.75491 2.59135 + vertex 0.852214 1.75598 2.58953 + endloop + endfacet + facet normal -0.593226 0.15917 0.789144 + outer loop + vertex 0.852457 1.75264 2.59039 + vertex 0.852214 1.75598 2.58953 + vertex 0.849453 1.75185 2.58829 + endloop + endfacet + facet normal -0.586955 0.159489 0.793755 + outer loop + vertex 0.854369 1.75491 2.59135 + vertex 0.852457 1.75264 2.59039 + vertex 0.854617 1.75156 2.5922 + endloop + endfacet + facet normal -0.572409 0.154639 0.805254 + outer loop + vertex 0.857359 1.75561 2.59343 + vertex 0.857329 1.75074 2.59434 + vertex 0.86042 1.75367 2.59598 + endloop + endfacet + facet normal -0.582398 0.134253 0.801741 + outer loop + vertex 0.861124 1.75879 2.59563 + vertex 0.857359 1.75561 2.59343 + vertex 0.86042 1.75367 2.59598 + endloop + endfacet + facet normal -0.583981 0.149487 0.797884 + outer loop + vertex 0.85757 1.74741 2.59514 + vertex 0.857329 1.75074 2.59434 + vertex 0.854612 1.74671 2.59311 + endloop + endfacet + facet normal -0.582356 0.128941 0.802643 + outer loop + vertex 0.85757 1.74741 2.59514 + vertex 0.854612 1.74671 2.59311 + vertex 0.856858 1.74375 2.59521 + endloop + endfacet + facet normal -0.565736 0.125955 0.81491 + outer loop + vertex 0.856858 1.74375 2.59521 + vertex 0.859768 1.74643 2.59682 + vertex 0.85757 1.74741 2.59514 + endloop + endfacet + facet normal -0.561178 0.138131 0.816088 + outer loop + vertex 0.859536 1.74973 2.5961 + vertex 0.85757 1.74741 2.59514 + vertex 0.859768 1.74643 2.59682 + endloop + endfacet + facet normal -0.55255 0.139948 0.821647 + outer loop + vertex 0.859536 1.74973 2.5961 + vertex 0.859768 1.74643 2.59682 + vertex 0.862763 1.75061 2.59812 + endloop + endfacet + facet normal -0.553715 0.150195 0.819049 + outer loop + vertex 0.859536 1.74973 2.5961 + vertex 0.862763 1.75061 2.59812 + vertex 0.86042 1.75367 2.59598 + endloop + endfacet + facet normal -0.571925 0.153852 0.805749 + outer loop + vertex 0.86042 1.75367 2.59598 + vertex 0.857329 1.75074 2.59434 + vertex 0.859536 1.74973 2.5961 + endloop + endfacet + facet normal -0.563648 0.139204 0.814201 + outer loop + vertex 0.862763 1.75061 2.59812 + vertex 0.864354 1.75672 2.59818 + vertex 0.86042 1.75367 2.59598 + endloop + endfacet + facet normal -0.542946 0.133683 0.829059 + outer loop + vertex 0.864354 1.75672 2.59818 + vertex 0.862763 1.75061 2.59812 + vertex 0.866677 1.75369 2.60019 + endloop + endfacet + facet normal -0.546633 0.12967 0.827271 + outer loop + vertex 0.867571 1.75751 2.60018 + vertex 0.864354 1.75672 2.59818 + vertex 0.866677 1.75369 2.60019 + endloop + endfacet + facet normal -0.542797 0.128776 0.829933 + outer loop + vertex 0.866677 1.75369 2.60019 + vertex 0.869804 1.7565 2.6018 + vertex 0.867571 1.75751 2.60018 + endloop + endfacet + facet normal -0.550514 0.108263 0.827776 + outer loop + vertex 0.869545 1.75979 2.6012 + vertex 0.867571 1.75751 2.60018 + vertex 0.869804 1.7565 2.6018 + endloop + endfacet + facet normal -0.55325 0.107726 0.82602 + outer loop + vertex 0.869545 1.75979 2.6012 + vertex 0.869804 1.7565 2.6018 + vertex 0.872645 1.76058 2.60317 + endloop + endfacet + facet normal -0.548562 0.0717602 0.833025 + outer loop + vertex 0.869545 1.75979 2.6012 + vertex 0.872645 1.76058 2.60317 + vertex 0.870207 1.76354 2.60131 + endloop + endfacet + facet normal -0.550978 0.0722364 0.831387 + outer loop + vertex 0.870207 1.76354 2.60131 + vertex 0.867298 1.76083 2.59962 + vertex 0.869545 1.75979 2.6012 + endloop + endfacet + facet normal -0.543339 0.0982283 0.833747 + outer loop + vertex 0.869804 1.7565 2.6018 + vertex 0.872734 1.75539 2.60384 + vertex 0.872645 1.76058 2.60317 + endloop + endfacet + facet normal -0.524807 0.100039 0.845322 + outer loop + vertex 0.872645 1.76058 2.60317 + vertex 0.872734 1.75539 2.60384 + vertex 0.876092 1.75881 2.60552 + endloop + endfacet + facet normal -0.536104 0.0723153 0.841049 + outer loop + vertex 0.876397 1.76389 2.60528 + vertex 0.872645 1.76058 2.60317 + vertex 0.876092 1.75881 2.60552 + endloop + endfacet + facet normal -0.512446 0.0715955 0.85573 + outer loop + vertex 0.876092 1.75881 2.60552 + vertex 0.879501 1.76209 2.60729 + vertex 0.876397 1.76389 2.60528 + endloop + endfacet + facet normal -0.515496 0.0759562 0.853519 + outer loop + vertex 0.879237 1.75717 2.60756 + vertex 0.879501 1.76209 2.60729 + vertex 0.876092 1.75881 2.60552 + endloop + endfacet + facet normal -0.489277 0.0754205 0.868861 + outer loop + vertex 0.879237 1.75717 2.60756 + vertex 0.882637 1.76048 2.60919 + vertex 0.879501 1.76209 2.60729 + endloop + endfacet + facet normal -0.491576 0.0785622 0.867283 + outer loop + vertex 0.882319 1.75566 2.60945 + vertex 0.882637 1.76048 2.60919 + vertex 0.879237 1.75717 2.60756 + endloop + endfacet + facet normal -0.482941 0.0994702 0.869985 + outer loop + vertex 0.878845 1.7522 2.60791 + vertex 0.882319 1.75566 2.60945 + vertex 0.879237 1.75717 2.60756 + endloop + endfacet + facet normal -0.505669 0.100338 0.856873 + outer loop + vertex 0.878845 1.7522 2.60791 + vertex 0.879237 1.75717 2.60756 + vertex 0.875803 1.75385 2.60593 + endloop + endfacet + facet normal -0.499138 0.114752 0.858891 + outer loop + vertex 0.875339 1.74904 2.6063 + vertex 0.878845 1.7522 2.60791 + vertex 0.875803 1.75385 2.60593 + endloop + endfacet + facet normal -0.513929 0.11549 0.850023 + outer loop + vertex 0.875803 1.75385 2.60593 + vertex 0.872425 1.75059 2.60433 + vertex 0.875339 1.74904 2.6063 + endloop + endfacet + facet normal -0.511415 0.121134 0.850753 + outer loop + vertex 0.872425 1.75059 2.60433 + vertex 0.872115 1.74609 2.60478 + vertex 0.875339 1.74904 2.6063 + endloop + endfacet + facet normal -0.508498 0.11673 0.853114 + outer loop + vertex 0.875339 1.74904 2.6063 + vertex 0.872115 1.74609 2.60478 + vertex 0.874565 1.74518 2.60637 + endloop + endfacet + facet normal -0.49228 0.113649 0.862986 + outer loop + vertex 0.874565 1.74518 2.60637 + vertex 0.878358 1.7464 2.60837 + vertex 0.875339 1.74904 2.6063 + endloop + endfacet + facet normal -0.490486 0.104567 0.865153 + outer loop + vertex 0.874565 1.74518 2.60637 + vertex 0.874829 1.74177 2.60693 + vertex 0.878358 1.7464 2.60837 + endloop + endfacet + facet normal -0.488924 0.103046 0.866219 + outer loop + vertex 0.874829 1.74177 2.60693 + vertex 0.877917 1.74055 2.60882 + vertex 0.878358 1.7464 2.60837 + endloop + endfacet + facet normal -0.478854 0.102718 0.871865 + outer loop + vertex 0.878358 1.7464 2.60837 + vertex 0.877917 1.74055 2.60882 + vertex 0.88148 1.74378 2.61039 + endloop + endfacet + facet normal -0.478643 0.10303 0.871944 + outer loop + vertex 0.882207 1.74772 2.61033 + vertex 0.878358 1.7464 2.60837 + vertex 0.88148 1.74378 2.61039 + endloop + endfacet + facet normal -0.451526 0.0982715 0.88683 + outer loop + vertex 0.88148 1.74378 2.61039 + vertex 0.884933 1.74696 2.6118 + vertex 0.882207 1.74772 2.61033 + endloop + endfacet + facet normal -0.45097 0.100367 0.886878 + outer loop + vertex 0.884489 1.7503 2.61119 + vertex 0.882207 1.74772 2.61033 + vertex 0.884933 1.74696 2.6118 + endloop + endfacet + facet normal -0.459711 0.109988 0.881231 + outer loop + vertex 0.882207 1.74772 2.61033 + vertex 0.884489 1.7503 2.61119 + vertex 0.881922 1.75108 2.60976 + endloop + endfacet + facet normal -0.45303 0.100346 0.88583 + outer loop + vertex 0.88469 1.74224 2.61221 + vertex 0.884933 1.74696 2.6118 + vertex 0.88148 1.74378 2.61039 + endloop + endfacet + facet normal -0.454262 0.0974201 0.885525 + outer loop + vertex 0.88105 1.73885 2.61071 + vertex 0.88469 1.74224 2.61221 + vertex 0.88148 1.74378 2.61039 + endloop + endfacet + facet normal -0.456907 0.101042 0.883757 + outer loop + vertex 0.884219 1.73721 2.61254 + vertex 0.88469 1.74224 2.61221 + vertex 0.88105 1.73885 2.61071 + endloop + endfacet + facet normal -0.458463 0.0975838 0.88334 + outer loop + vertex 0.880659 1.73393 2.61105 + vertex 0.884219 1.73721 2.61254 + vertex 0.88105 1.73885 2.61071 + endloop + endfacet + facet normal -0.477967 0.0984088 0.872848 + outer loop + vertex 0.88105 1.73885 2.61071 + vertex 0.877549 1.73555 2.60917 + vertex 0.880659 1.73393 2.61105 + endloop + endfacet + facet normal -0.47719 0.100163 0.873073 + outer loop + vertex 0.877549 1.73555 2.60917 + vertex 0.877186 1.73074 2.60952 + vertex 0.880659 1.73393 2.61105 + endloop + endfacet + facet normal -0.479655 0.103691 0.871309 + outer loop + vertex 0.880659 1.73393 2.61105 + vertex 0.877186 1.73074 2.60952 + vertex 0.88021 1.72915 2.61138 + endloop + endfacet + facet normal -0.462861 0.102729 0.880458 + outer loop + vertex 0.88021 1.72915 2.61138 + vertex 0.883782 1.7322 2.6129 + vertex 0.880659 1.73393 2.61105 + endloop + endfacet + facet normal -0.466234 0.107876 0.87806 + outer loop + vertex 0.883335 1.72647 2.61336 + vertex 0.883782 1.7322 2.6129 + vertex 0.88021 1.72915 2.61138 + endloop + endfacet + facet normal -0.466297 0.107786 0.878037 + outer loop + vertex 0.879439 1.72535 2.61143 + vertex 0.883335 1.72647 2.61336 + vertex 0.88021 1.72915 2.61138 + endloop + endfacet + facet normal -0.480872 0.110616 0.869785 + outer loop + vertex 0.88021 1.72915 2.61138 + vertex 0.876828 1.7262 2.60988 + vertex 0.879439 1.72535 2.61143 + endloop + endfacet + facet normal -0.480574 0.111603 0.869824 + outer loop + vertex 0.87711 1.72284 2.61047 + vertex 0.879439 1.72535 2.61143 + vertex 0.876828 1.7262 2.60988 + endloop + endfacet + facet normal -0.489566 0.110005 0.864999 + outer loop + vertex 0.87711 1.72284 2.61047 + vertex 0.876828 1.7262 2.60988 + vertex 0.873275 1.72161 2.60846 + endloop + endfacet + facet normal -0.489527 0.10981 0.865046 + outer loop + vertex 0.87711 1.72284 2.61047 + vertex 0.873275 1.72161 2.60846 + vertex 0.876329 1.71891 2.61053 + endloop + endfacet + facet normal -0.479745 0.10795 0.870742 + outer loop + vertex 0.876329 1.71891 2.61053 + vertex 0.879721 1.72194 2.61202 + vertex 0.87711 1.72284 2.61047 + endloop + endfacet + facet normal -0.480515 0.109094 0.870175 + outer loop + vertex 0.879329 1.71719 2.6124 + vertex 0.879721 1.72194 2.61202 + vertex 0.876329 1.71891 2.61053 + endloop + endfacet + facet normal -0.481715 0.106614 0.869819 + outer loop + vertex 0.875842 1.71394 2.61087 + vertex 0.879329 1.71719 2.6124 + vertex 0.876329 1.71891 2.61053 + endloop + endfacet + facet normal -0.490103 0.10711 0.865059 + outer loop + vertex 0.876329 1.71891 2.61053 + vertex 0.872805 1.71574 2.60892 + vertex 0.875842 1.71394 2.61087 + endloop + endfacet + facet normal -0.49132 0.104631 0.864671 + outer loop + vertex 0.872805 1.71574 2.60892 + vertex 0.872419 1.7107 2.60931 + vertex 0.875842 1.71394 2.61087 + endloop + endfacet + facet normal -0.491275 0.104567 0.864705 + outer loop + vertex 0.875842 1.71394 2.61087 + vertex 0.872419 1.7107 2.60931 + vertex 0.875389 1.709 2.6112 + endloop + endfacet + facet normal -0.481822 0.104068 0.870068 + outer loop + vertex 0.875389 1.709 2.6112 + vertex 0.878884 1.71205 2.61278 + vertex 0.875842 1.71394 2.61087 + endloop + endfacet + facet normal -0.480979 0.102781 0.870687 + outer loop + vertex 0.878394 1.70622 2.61319 + vertex 0.878884 1.71205 2.61278 + vertex 0.875389 1.709 2.6112 + endloop + endfacet + facet normal -0.481076 0.102648 0.870649 + outer loop + vertex 0.874676 1.70512 2.61127 + vertex 0.878394 1.70622 2.61319 + vertex 0.875389 1.709 2.6112 + endloop + endfacet + facet normal -0.492267 0.104595 0.864137 + outer loop + vertex 0.875389 1.709 2.6112 + vertex 0.872173 1.70609 2.60972 + vertex 0.874676 1.70512 2.61127 + endloop + endfacet + facet normal -0.492689 0.103358 0.864046 + outer loop + vertex 0.872497 1.70272 2.61031 + vertex 0.874676 1.70512 2.61127 + vertex 0.872173 1.70609 2.60972 + endloop + endfacet + facet normal -0.502178 0.101528 0.858784 + outer loop + vertex 0.872497 1.70272 2.61031 + vertex 0.872173 1.70609 2.60972 + vertex 0.869105 1.70192 2.60842 + endloop + endfacet + facet normal -0.501849 0.0989741 0.859274 + outer loop + vertex 0.872497 1.70272 2.61031 + vertex 0.869105 1.70192 2.60842 + vertex 0.871649 1.69887 2.61026 + endloop + endfacet + facet normal -0.489838 0.0962336 0.866486 + outer loop + vertex 0.871649 1.69887 2.61026 + vertex 0.874981 1.70175 2.61183 + vertex 0.872497 1.70272 2.61031 + endloop + endfacet + facet normal -0.489983 0.0964603 0.866379 + outer loop + vertex 0.874634 1.69714 2.61214 + vertex 0.874981 1.70175 2.61183 + vertex 0.871649 1.69887 2.61026 + endloop + endfacet + facet normal -0.490695 0.0949774 0.86614 + outer loop + vertex 0.87111 1.69392 2.6105 + vertex 0.874634 1.69714 2.61214 + vertex 0.871649 1.69887 2.61026 + endloop + endfacet + facet normal -0.501314 0.0958395 0.859941 + outer loop + vertex 0.871649 1.69887 2.61026 + vertex 0.867669 1.69586 2.60828 + vertex 0.87111 1.69392 2.6105 + endloop + endfacet + facet normal -0.501884 0.0946042 0.859746 + outer loop + vertex 0.867669 1.69586 2.60828 + vertex 0.867693 1.69052 2.60888 + vertex 0.87111 1.69392 2.6105 + endloop + endfacet + facet normal -0.500616 0.0928882 0.860672 + outer loop + vertex 0.87111 1.69392 2.6105 + vertex 0.867693 1.69052 2.60888 + vertex 0.870783 1.68892 2.61085 + endloop + endfacet + facet normal -0.489666 0.0926158 0.866978 + outer loop + vertex 0.870783 1.68892 2.61085 + vertex 0.874254 1.69223 2.61245 + vertex 0.87111 1.69392 2.6105 + endloop + endfacet + facet normal -0.487931 0.0902041 0.868209 + outer loop + vertex 0.873808 1.68721 2.61273 + vertex 0.874254 1.69223 2.61245 + vertex 0.870783 1.68892 2.61085 + endloop + endfacet + facet normal -0.487738 0.0906178 0.868274 + outer loop + vertex 0.870336 1.68406 2.6111 + vertex 0.873808 1.68721 2.61273 + vertex 0.870783 1.68892 2.61085 + endloop + endfacet + facet normal -0.501789 0.0914815 0.860139 + outer loop + vertex 0.870783 1.68892 2.61085 + vertex 0.867462 1.68559 2.60926 + vertex 0.870336 1.68406 2.6111 + endloop + endfacet + facet normal -0.502024 0.0909464 0.860058 + outer loop + vertex 0.867462 1.68559 2.60926 + vertex 0.867269 1.681 2.60964 + vertex 0.870336 1.68406 2.6111 + endloop + endfacet + facet normal -0.502991 0.0922564 0.859354 + outer loop + vertex 0.870336 1.68406 2.6111 + vertex 0.867269 1.681 2.60964 + vertex 0.869657 1.6802 2.61112 + endloop + endfacet + facet normal -0.485418 0.0892103 0.869719 + outer loop + vertex 0.869657 1.6802 2.61112 + vertex 0.873051 1.68166 2.61287 + vertex 0.870336 1.68406 2.6111 + endloop + endfacet + facet normal -0.48426 0.0852945 0.870757 + outer loop + vertex 0.869657 1.6802 2.61112 + vertex 0.870117 1.67697 2.61169 + vertex 0.873051 1.68166 2.61287 + endloop + endfacet + facet normal -0.482211 0.0836893 0.872048 + outer loop + vertex 0.870117 1.67697 2.61169 + vertex 0.873766 1.6764 2.61377 + vertex 0.873051 1.68166 2.61287 + endloop + endfacet + facet normal -0.475748 0.0851502 0.87545 + outer loop + vertex 0.873766 1.6764 2.61377 + vertex 0.876765 1.68111 2.61494 + vertex 0.873051 1.68166 2.61287 + endloop + endfacet + facet normal -0.475569 0.0862962 0.875435 + outer loop + vertex 0.876765 1.68111 2.61494 + vertex 0.876965 1.68567 2.6146 + vertex 0.873051 1.68166 2.61287 + endloop + endfacet + facet normal -0.476126 0.0869993 0.875063 + outer loop + vertex 0.873051 1.68166 2.61287 + vertex 0.876965 1.68567 2.6146 + vertex 0.873808 1.68721 2.61273 + endloop + endfacet + facet normal -0.475785 0.0878269 0.875166 + outer loop + vertex 0.876965 1.68567 2.6146 + vertex 0.877391 1.69061 2.61433 + vertex 0.873808 1.68721 2.61273 + endloop + endfacet + facet normal -0.464973 0.0872078 0.881019 + outer loop + vertex 0.877391 1.69061 2.61433 + vertex 0.876965 1.68567 2.6146 + vertex 0.880568 1.689 2.61617 + endloop + endfacet + facet normal -0.46393 0.0896092 0.881328 + outer loop + vertex 0.880957 1.69394 2.61587 + vertex 0.877391 1.69061 2.61433 + vertex 0.880568 1.689 2.61617 + endloop + endfacet + facet normal -0.446737 0.0887932 0.890248 + outer loop + vertex 0.880568 1.689 2.61617 + vertex 0.884182 1.69227 2.61766 + vertex 0.880957 1.69394 2.61587 + endloop + endfacet + facet normal -0.444531 0.0936985 0.890849 + outer loop + vertex 0.884182 1.69227 2.61766 + vertex 0.884643 1.69742 2.61734 + vertex 0.880957 1.69394 2.61587 + endloop + endfacet + facet normal -0.442656 0.0912089 0.892041 + outer loop + vertex 0.880957 1.69394 2.61587 + vertex 0.884643 1.69742 2.61734 + vertex 0.881292 1.69896 2.61552 + endloop + endfacet + facet normal -0.462973 0.0918425 0.881601 + outer loop + vertex 0.881292 1.69896 2.61552 + vertex 0.877763 1.69556 2.61403 + vertex 0.880957 1.69394 2.61587 + endloop + endfacet + facet normal -0.464496 0.0938669 0.880586 + outer loop + vertex 0.87809 1.70055 2.61367 + vertex 0.877763 1.69556 2.61403 + vertex 0.881292 1.69896 2.61552 + endloop + endfacet + facet normal -0.464279 0.0943728 0.880647 + outer loop + vertex 0.881505 1.7039 2.61511 + vertex 0.87809 1.70055 2.61367 + vertex 0.881292 1.69896 2.61552 + endloop + endfacet + facet normal -0.441772 0.0943699 0.89215 + outer loop + vertex 0.881292 1.69896 2.61552 + vertex 0.884901 1.70269 2.61692 + vertex 0.881505 1.7039 2.61511 + endloop + endfacet + facet normal -0.477959 0.0942226 0.873314 + outer loop + vertex 0.877763 1.69556 2.61403 + vertex 0.87809 1.70055 2.61367 + vertex 0.874634 1.69714 2.61214 + endloop + endfacet + facet normal -0.478622 0.0926739 0.873117 + outer loop + vertex 0.874254 1.69223 2.61245 + vertex 0.877763 1.69556 2.61403 + vertex 0.874634 1.69714 2.61214 + endloop + endfacet + facet normal -0.476799 0.0901547 0.874377 + outer loop + vertex 0.877391 1.69061 2.61433 + vertex 0.877763 1.69556 2.61403 + vertex 0.874254 1.69223 2.61245 + endloop + endfacet + facet normal -0.441503 0.0940468 0.892317 + outer loop + vertex 0.884643 1.69742 2.61734 + vertex 0.884901 1.70269 2.61692 + vertex 0.881292 1.69896 2.61552 + endloop + endfacet + facet normal -0.417591 0.0938046 0.90378 + outer loop + vertex 0.884643 1.69742 2.61734 + vertex 0.888824 1.70138 2.61887 + vertex 0.884901 1.70269 2.61692 + endloop + endfacet + facet normal -0.417387 0.0944516 0.903807 + outer loop + vertex 0.888824 1.70138 2.61887 + vertex 0.888572 1.70676 2.61819 + vertex 0.884901 1.70269 2.61692 + endloop + endfacet + facet normal -0.41979 0.0970492 0.902418 + outer loop + vertex 0.884901 1.70269 2.61692 + vertex 0.888572 1.70676 2.61819 + vertex 0.884711 1.70806 2.61625 + endloop + endfacet + facet normal -0.441564 0.0950096 0.892185 + outer loop + vertex 0.884901 1.70269 2.61692 + vertex 0.884711 1.70806 2.61625 + vertex 0.881505 1.7039 2.61511 + endloop + endfacet + facet normal -0.41953 0.0978677 0.90245 + outer loop + vertex 0.884711 1.70806 2.61625 + vertex 0.888572 1.70676 2.61819 + vertex 0.888881 1.71206 2.61776 + endloop + endfacet + facet normal -0.41976 0.0981602 0.902311 + outer loop + vertex 0.884711 1.70806 2.61625 + vertex 0.888881 1.71206 2.61776 + vertex 0.88557 1.71372 2.61603 + endloop + endfacet + facet normal -0.443867 0.101363 0.890341 + outer loop + vertex 0.88557 1.71372 2.61603 + vertex 0.881942 1.71044 2.6146 + vertex 0.884711 1.70806 2.61625 + endloop + endfacet + facet normal -0.44549 0.103621 0.88927 + outer loop + vertex 0.882432 1.7155 2.61425 + vertex 0.881942 1.71044 2.6146 + vertex 0.88557 1.71372 2.61603 + endloop + endfacet + facet normal -0.444932 0.104753 0.889417 + outer loop + vertex 0.886094 1.71895 2.61568 + vertex 0.882432 1.7155 2.61425 + vertex 0.88557 1.71372 2.61603 + endloop + endfacet + facet normal -0.418725 0.102994 0.902254 + outer loop + vertex 0.88557 1.71372 2.61603 + vertex 0.88948 1.71744 2.61743 + vertex 0.886094 1.71895 2.61568 + endloop + endfacet + facet normal -0.417803 0.105253 0.90242 + outer loop + vertex 0.88948 1.71744 2.61743 + vertex 0.889875 1.72256 2.61701 + vertex 0.886094 1.71895 2.61568 + endloop + endfacet + facet normal -0.419191 0.107018 0.901569 + outer loop + vertex 0.886094 1.71895 2.61568 + vertex 0.889875 1.72256 2.61701 + vertex 0.886541 1.72388 2.6153 + endloop + endfacet + facet normal -0.445976 0.108441 0.888452 + outer loop + vertex 0.886541 1.72388 2.6153 + vertex 0.882881 1.72066 2.61386 + vertex 0.886094 1.71895 2.61568 + endloop + endfacet + facet normal -0.447383 0.11047 0.887493 + outer loop + vertex 0.883335 1.72647 2.61336 + vertex 0.882881 1.72066 2.61386 + vertex 0.886541 1.72388 2.6153 + endloop + endfacet + facet normal -0.447573 0.11019 0.887432 + outer loop + vertex 0.887256 1.72769 2.61519 + vertex 0.883335 1.72647 2.61336 + vertex 0.886541 1.72388 2.6153 + endloop + endfacet + facet normal -0.418221 0.10513 0.902241 + outer loop + vertex 0.886541 1.72388 2.6153 + vertex 0.889977 1.72707 2.61653 + vertex 0.887256 1.72769 2.61519 + endloop + endfacet + facet normal -0.417707 0.107315 0.902222 + outer loop + vertex 0.88955 1.73024 2.61595 + vertex 0.887256 1.72769 2.61519 + vertex 0.889977 1.72707 2.61653 + endloop + endfacet + facet normal -0.423695 0.113776 0.898631 + outer loop + vertex 0.887256 1.72769 2.61519 + vertex 0.88955 1.73024 2.61595 + vertex 0.88694 1.731 2.61462 + endloop + endfacet + facet normal -0.447454 0.109608 0.887565 + outer loop + vertex 0.887256 1.72769 2.61519 + vertex 0.88694 1.731 2.61462 + vertex 0.883335 1.72647 2.61336 + endloop + endfacet + facet normal -0.466187 0.111101 0.877682 + outer loop + vertex 0.879721 1.72194 2.61202 + vertex 0.882881 1.72066 2.61386 + vertex 0.883335 1.72647 2.61336 + endloop + endfacet + facet normal -0.419343 0.106605 0.901547 + outer loop + vertex 0.889875 1.72256 2.61701 + vertex 0.889977 1.72707 2.61653 + vertex 0.886541 1.72388 2.6153 + endloop + endfacet + facet normal -0.446636 0.107029 0.888291 + outer loop + vertex 0.882881 1.72066 2.61386 + vertex 0.882432 1.7155 2.61425 + vertex 0.886094 1.71895 2.61568 + endloop + endfacet + facet normal -0.466655 0.107973 0.877824 + outer loop + vertex 0.882432 1.7155 2.61425 + vertex 0.882881 1.72066 2.61386 + vertex 0.879329 1.71719 2.6124 + endloop + endfacet + facet normal -0.468034 0.105023 0.877447 + outer loop + vertex 0.878884 1.71205 2.61278 + vertex 0.882432 1.7155 2.61425 + vertex 0.879329 1.71719 2.6124 + endloop + endfacet + facet normal -0.468011 0.104993 0.877463 + outer loop + vertex 0.881942 1.71044 2.6146 + vertex 0.882432 1.7155 2.61425 + vertex 0.878884 1.71205 2.61278 + endloop + endfacet + facet normal -0.417998 0.102064 0.902696 + outer loop + vertex 0.888881 1.71206 2.61776 + vertex 0.88948 1.71744 2.61743 + vertex 0.88557 1.71372 2.61603 + endloop + endfacet + facet normal -0.420623 0.0977131 0.901958 + outer loop + vertex 0.887908 1.69568 2.61906 + vertex 0.888824 1.70138 2.61887 + vertex 0.884643 1.69742 2.61734 + endloop + endfacet + facet normal -0.423127 0.0924151 0.901345 + outer loop + vertex 0.884182 1.69227 2.61766 + vertex 0.887908 1.69568 2.61906 + vertex 0.884643 1.69742 2.61734 + endloop + endfacet + facet normal -0.425769 0.0959678 0.899728 + outer loop + vertex 0.887374 1.69065 2.61934 + vertex 0.887908 1.69568 2.61906 + vertex 0.884182 1.69227 2.61766 + endloop + endfacet + facet normal -0.428618 0.0896421 0.899028 + outer loop + vertex 0.88377 1.68725 2.61796 + vertex 0.887374 1.69065 2.61934 + vertex 0.884182 1.69227 2.61766 + endloop + endfacet + facet normal -0.432014 0.0940865 0.896946 + outer loop + vertex 0.886996 1.68601 2.61964 + vertex 0.887374 1.69065 2.61934 + vertex 0.88377 1.68725 2.61796 + endloop + endfacet + facet normal -0.434618 0.0866121 0.896441 + outer loop + vertex 0.883381 1.68151 2.61833 + vertex 0.886996 1.68601 2.61964 + vertex 0.88377 1.68725 2.61796 + endloop + endfacet + facet normal -0.450577 0.0871838 0.88847 + outer loop + vertex 0.883381 1.68151 2.61833 + vertex 0.88377 1.68725 2.61796 + vertex 0.880152 1.6842 2.61642 + endloop + endfacet + facet normal -0.451978 0.0851421 0.887957 + outer loop + vertex 0.879456 1.68041 2.61643 + vertex 0.883381 1.68151 2.61833 + vertex 0.880152 1.6842 2.61642 + endloop + endfacet + facet normal -0.466523 0.087795 0.880141 + outer loop + vertex 0.880152 1.6842 2.61642 + vertex 0.876765 1.68111 2.61494 + vertex 0.879456 1.68041 2.61643 + endloop + endfacet + facet normal -0.466925 0.0861279 0.880093 + outer loop + vertex 0.877236 1.67786 2.61551 + vertex 0.879456 1.68041 2.61643 + vertex 0.876765 1.68111 2.61494 + endloop + endfacet + facet normal -0.463962 0.0828743 0.88197 + outer loop + vertex 0.879456 1.68041 2.61643 + vertex 0.877236 1.67786 2.61551 + vertex 0.879811 1.677 2.61694 + endloop + endfacet + facet normal -0.464532 0.0809551 0.881848 + outer loop + vertex 0.876518 1.67394 2.61549 + vertex 0.879811 1.677 2.61694 + vertex 0.877236 1.67786 2.61551 + endloop + endfacet + facet normal -0.474231 0.0827552 0.876503 + outer loop + vertex 0.877236 1.67786 2.61551 + vertex 0.873766 1.6764 2.61377 + vertex 0.876518 1.67394 2.61549 + endloop + endfacet + facet normal -0.475452 0.0810417 0.876001 + outer loop + vertex 0.873766 1.6764 2.61377 + vertex 0.873017 1.67078 2.61388 + vertex 0.876518 1.67394 2.61549 + endloop + endfacet + facet normal -0.473794 0.0786325 0.877118 + outer loop + vertex 0.876518 1.67394 2.61549 + vertex 0.873017 1.67078 2.61388 + vertex 0.876069 1.669 2.61569 + endloop + endfacet + facet normal -0.465888 0.0780858 0.881391 + outer loop + vertex 0.876069 1.669 2.61569 + vertex 0.879495 1.67227 2.61721 + vertex 0.876518 1.67394 2.61549 + endloop + endfacet + facet normal -0.463878 0.0753797 0.882686 + outer loop + vertex 0.879211 1.66728 2.61749 + vertex 0.879495 1.67227 2.61721 + vertex 0.876069 1.669 2.61569 + endloop + endfacet + facet normal -0.464819 0.0733261 0.882364 + outer loop + vertex 0.875794 1.66399 2.61596 + vertex 0.879211 1.66728 2.61749 + vertex 0.876069 1.669 2.61569 + endloop + endfacet + facet normal -0.472742 0.0735305 0.878128 + outer loop + vertex 0.876069 1.669 2.61569 + vertex 0.872639 1.66567 2.61412 + vertex 0.875794 1.66399 2.61596 + endloop + endfacet + facet normal -0.473476 0.0718725 0.877869 + outer loop + vertex 0.872639 1.66567 2.61412 + vertex 0.872396 1.66068 2.6144 + vertex 0.875794 1.66399 2.61596 + endloop + endfacet + facet normal -0.471139 0.0687534 0.879376 + outer loop + vertex 0.875794 1.66399 2.61596 + vertex 0.872396 1.66068 2.6144 + vertex 0.875566 1.65903 2.61622 + endloop + endfacet + facet normal -0.463167 0.0686124 0.883611 + outer loop + vertex 0.875566 1.65903 2.61622 + vertex 0.878995 1.66228 2.61777 + vertex 0.875794 1.66399 2.61596 + endloop + endfacet + facet normal -0.461612 0.0665049 0.884586 + outer loop + vertex 0.878766 1.65725 2.61803 + vertex 0.878995 1.66228 2.61777 + vertex 0.875566 1.65903 2.61622 + endloop + endfacet + facet normal -0.461746 0.0662128 0.884537 + outer loop + vertex 0.87525 1.65419 2.61642 + vertex 0.878766 1.65725 2.61803 + vertex 0.875566 1.65903 2.61622 + endloop + endfacet + facet normal -0.470514 0.0665956 0.879876 + outer loop + vertex 0.875566 1.65903 2.61622 + vertex 0.872151 1.6558 2.61464 + vertex 0.87525 1.65419 2.61642 + endloop + endfacet + facet normal -0.470712 0.066137 0.879805 + outer loop + vertex 0.872151 1.6558 2.61464 + vertex 0.871903 1.65118 2.61486 + vertex 0.87525 1.65419 2.61642 + endloop + endfacet + facet normal -0.471543 0.0673397 0.879268 + outer loop + vertex 0.87525 1.65419 2.61642 + vertex 0.871903 1.65118 2.61486 + vertex 0.87457 1.65035 2.61635 + endloop + endfacet + facet normal -0.461094 0.0653904 0.884939 + outer loop + vertex 0.87457 1.65035 2.61635 + vertex 0.878485 1.65149 2.61831 + vertex 0.87525 1.65419 2.61642 + endloop + endfacet + facet normal -0.461294 0.0663849 0.88476 + outer loop + vertex 0.87457 1.65035 2.61635 + vertex 0.874951 1.64694 2.61681 + vertex 0.878485 1.65149 2.61831 + endloop + endfacet + facet normal -0.460965 0.0660646 0.884956 + outer loop + vertex 0.874951 1.64694 2.61681 + vertex 0.878174 1.64569 2.61858 + vertex 0.878485 1.65149 2.61831 + endloop + endfacet + facet normal -0.451001 0.0657686 0.890097 + outer loop + vertex 0.878485 1.65149 2.61831 + vertex 0.878174 1.64569 2.61858 + vertex 0.881767 1.6489 2.62016 + endloop + endfacet + facet normal -0.451465 0.0650513 0.889915 + outer loop + vertex 0.882407 1.65271 2.62021 + vertex 0.878485 1.65149 2.61831 + vertex 0.881767 1.6489 2.62016 + endloop + endfacet + facet normal -0.451461 0.0650362 0.889917 + outer loop + vertex 0.882407 1.65271 2.62021 + vertex 0.881989 1.65603 2.61975 + vertex 0.878485 1.65149 2.61831 + endloop + endfacet + facet normal -0.451518 0.06509 0.889885 + outer loop + vertex 0.878485 1.65149 2.61831 + vertex 0.881989 1.65603 2.61975 + vertex 0.878766 1.65725 2.61803 + endloop + endfacet + facet normal -0.450995 0.0666777 0.890033 + outer loop + vertex 0.881989 1.65603 2.61975 + vertex 0.882209 1.66066 2.61952 + vertex 0.878766 1.65725 2.61803 + endloop + endfacet + facet normal -0.435936 0.0663427 0.897529 + outer loop + vertex 0.882209 1.66066 2.61952 + vertex 0.881989 1.65603 2.61975 + vertex 0.885289 1.6591 2.62113 + endloop + endfacet + facet normal -0.434818 0.0689219 0.897877 + outer loop + vertex 0.885684 1.66395 2.62095 + vertex 0.882209 1.66066 2.61952 + vertex 0.885289 1.6591 2.62113 + endloop + endfacet + facet normal -0.422387 0.0681315 0.903851 + outer loop + vertex 0.885289 1.6591 2.62113 + vertex 0.888894 1.66222 2.62258 + vertex 0.885684 1.66395 2.62095 + endloop + endfacet + facet normal -0.420439 0.0722992 0.904436 + outer loop + vertex 0.888894 1.66222 2.62258 + vertex 0.889306 1.66737 2.62236 + vertex 0.885684 1.66395 2.62095 + endloop + endfacet + facet normal -0.419309 0.0708378 0.905076 + outer loop + vertex 0.885684 1.66395 2.62095 + vertex 0.889306 1.66737 2.62236 + vertex 0.885978 1.66897 2.62069 + endloop + endfacet + facet normal -0.43265 0.0712929 0.898739 + outer loop + vertex 0.885978 1.66897 2.62069 + vertex 0.882438 1.66559 2.61926 + vertex 0.885684 1.66395 2.62095 + endloop + endfacet + facet normal -0.433098 0.0718725 0.898477 + outer loop + vertex 0.88268 1.67061 2.61897 + vertex 0.882438 1.66559 2.61926 + vertex 0.885978 1.66897 2.62069 + endloop + endfacet + facet normal -0.431638 0.0752602 0.898902 + outer loop + vertex 0.886289 1.674 2.62042 + vertex 0.88268 1.67061 2.61897 + vertex 0.885978 1.66897 2.62069 + endloop + endfacet + facet normal -0.416561 0.0747118 0.906033 + outer loop + vertex 0.885978 1.66897 2.62069 + vertex 0.889725 1.67255 2.62212 + vertex 0.886289 1.674 2.62042 + endloop + endfacet + facet normal -0.415174 0.0783835 0.906359 + outer loop + vertex 0.889725 1.67255 2.62212 + vertex 0.890025 1.6776 2.62182 + vertex 0.886289 1.674 2.62042 + endloop + endfacet + facet normal -0.415215 0.0784347 0.906336 + outer loop + vertex 0.886289 1.674 2.62042 + vertex 0.890025 1.6776 2.62182 + vertex 0.886658 1.67887 2.62017 + endloop + endfacet + facet normal -0.433088 0.0793458 0.897853 + outer loop + vertex 0.886658 1.67887 2.62017 + vertex 0.883002 1.6757 2.61868 + vertex 0.886289 1.674 2.62042 + endloop + endfacet + facet normal -0.436017 0.0835627 0.89605 + outer loop + vertex 0.883381 1.68151 2.61833 + vertex 0.883002 1.6757 2.61868 + vertex 0.886658 1.67887 2.62017 + endloop + endfacet + facet normal -0.435771 0.0839282 0.896136 + outer loop + vertex 0.887352 1.68268 2.62015 + vertex 0.883381 1.68151 2.61833 + vertex 0.886658 1.67887 2.62017 + endloop + endfacet + facet normal -0.414068 0.0800148 0.906722 + outer loop + vertex 0.886658 1.67887 2.62017 + vertex 0.890093 1.68207 2.62145 + vertex 0.887352 1.68268 2.62015 + endloop + endfacet + facet normal -0.413014 0.0848903 0.906759 + outer loop + vertex 0.889644 1.68524 2.62095 + vertex 0.887352 1.68268 2.62015 + vertex 0.890093 1.68207 2.62145 + endloop + endfacet + facet normal -0.413949 0.0846933 0.906352 + outer loop + vertex 0.889644 1.68524 2.62095 + vertex 0.890093 1.68207 2.62145 + vertex 0.893218 1.68664 2.62245 + endloop + endfacet + facet normal -0.417264 0.0960366 0.903697 + outer loop + vertex 0.889644 1.68524 2.62095 + vertex 0.893218 1.68664 2.62245 + vertex 0.890419 1.68909 2.6209 + endloop + endfacet + facet normal -0.418174 0.0962146 0.903257 + outer loop + vertex 0.890419 1.68909 2.6209 + vertex 0.886996 1.68601 2.61964 + vertex 0.889644 1.68524 2.62095 + endloop + endfacet + facet normal -0.419389 0.0931722 0.903013 + outer loop + vertex 0.893218 1.68664 2.62245 + vertex 0.894093 1.69221 2.62228 + vertex 0.890419 1.68909 2.6209 + endloop + endfacet + facet normal -0.422913 0.0982795 0.900825 + outer loop + vertex 0.890419 1.68909 2.6209 + vertex 0.894093 1.69221 2.62228 + vertex 0.891008 1.69393 2.62065 + endloop + endfacet + facet normal -0.414114 0.097427 0.904996 + outer loop + vertex 0.891008 1.69393 2.62065 + vertex 0.887374 1.69065 2.61934 + vertex 0.890419 1.68909 2.6209 + endloop + endfacet + facet normal -0.412231 0.0948913 0.906124 + outer loop + vertex 0.887908 1.69568 2.61906 + vertex 0.887374 1.69065 2.61934 + vertex 0.891008 1.69393 2.62065 + endloop + endfacet + facet normal -0.410561 0.0982137 0.906528 + outer loop + vertex 0.891601 1.69879 2.62039 + vertex 0.887908 1.69568 2.61906 + vertex 0.891008 1.69393 2.62065 + endloop + endfacet + facet normal -0.424099 0.099526 0.90013 + outer loop + vertex 0.891008 1.69393 2.62065 + vertex 0.894605 1.69724 2.62198 + vertex 0.891601 1.69879 2.62039 + endloop + endfacet + facet normal -0.423843 0.100084 0.900189 + outer loop + vertex 0.894605 1.69724 2.62198 + vertex 0.89498 1.70191 2.62164 + vertex 0.891601 1.69879 2.62039 + endloop + endfacet + facet normal -0.426563 0.103708 0.898493 + outer loop + vertex 0.891601 1.69879 2.62039 + vertex 0.89498 1.70191 2.62164 + vertex 0.892388 1.70267 2.62032 + endloop + endfacet + facet normal -0.406116 0.099743 0.908362 + outer loop + vertex 0.892388 1.70267 2.62032 + vertex 0.888824 1.70138 2.61887 + vertex 0.891601 1.69879 2.62039 + endloop + endfacet + facet normal -0.405226 0.096436 0.909116 + outer loop + vertex 0.892388 1.70267 2.62032 + vertex 0.891997 1.70598 2.61979 + vertex 0.888824 1.70138 2.61887 + endloop + endfacet + facet normal -0.404405 0.0957836 0.90955 + outer loop + vertex 0.888824 1.70138 2.61887 + vertex 0.891997 1.70598 2.61979 + vertex 0.888572 1.70676 2.61819 + endloop + endfacet + facet normal -0.404153 0.0968853 0.909546 + outer loop + vertex 0.891997 1.70598 2.61979 + vertex 0.892257 1.71067 2.61941 + vertex 0.888572 1.70676 2.61819 + endloop + endfacet + facet normal -0.404749 0.0975525 0.909209 + outer loop + vertex 0.888572 1.70676 2.61819 + vertex 0.892257 1.71067 2.61941 + vertex 0.888881 1.71206 2.61776 + endloop + endfacet + facet normal -0.40349 0.100846 0.90941 + outer loop + vertex 0.892257 1.71067 2.61941 + vertex 0.892809 1.71583 2.61908 + vertex 0.888881 1.71206 2.61776 + endloop + endfacet + facet normal -0.403503 0.100862 0.909402 + outer loop + vertex 0.888881 1.71206 2.61776 + vertex 0.892809 1.71583 2.61908 + vertex 0.88948 1.71744 2.61743 + endloop + endfacet + facet normal -0.401643 0.105079 0.909748 + outer loop + vertex 0.892809 1.71583 2.61908 + vertex 0.893792 1.72151 2.61886 + vertex 0.88948 1.71744 2.61743 + endloop + endfacet + facet normal -0.401257 0.10459 0.909975 + outer loop + vertex 0.88948 1.71744 2.61743 + vertex 0.893792 1.72151 2.61886 + vertex 0.889875 1.72256 2.61701 + endloop + endfacet + facet normal -0.40068 0.106737 0.909979 + outer loop + vertex 0.893792 1.72151 2.61886 + vertex 0.893494 1.72655 2.61814 + vertex 0.889875 1.72256 2.61701 + endloop + endfacet + facet normal -0.401 0.107078 0.909799 + outer loop + vertex 0.889875 1.72256 2.61701 + vertex 0.893494 1.72655 2.61814 + vertex 0.889977 1.72707 2.61653 + endloop + endfacet + facet normal -0.400712 0.108808 0.90972 + outer loop + vertex 0.889977 1.72707 2.61653 + vertex 0.893494 1.72655 2.61814 + vertex 0.893191 1.73157 2.6174 + endloop + endfacet + facet normal -0.402756 0.110484 0.908615 + outer loop + vertex 0.88955 1.73024 2.61595 + vertex 0.889977 1.72707 2.61653 + vertex 0.893191 1.73157 2.6174 + endloop + endfacet + facet normal -0.403054 0.1116 0.908346 + outer loop + vertex 0.88955 1.73024 2.61595 + vertex 0.893191 1.73157 2.6174 + vertex 0.890384 1.73404 2.61585 + endloop + endfacet + facet normal -0.423125 0.11576 0.898646 + outer loop + vertex 0.890384 1.73404 2.61585 + vertex 0.88694 1.731 2.61462 + vertex 0.88955 1.73024 2.61595 + endloop + endfacet + facet normal -0.417722 0.108229 0.902106 + outer loop + vertex 0.887367 1.73561 2.61427 + vertex 0.88694 1.731 2.61462 + vertex 0.890384 1.73404 2.61585 + endloop + endfacet + facet normal -0.417306 0.109115 0.902192 + outer loop + vertex 0.891059 1.73885 2.61558 + vertex 0.887367 1.73561 2.61427 + vertex 0.890384 1.73404 2.61585 + endloop + endfacet + facet normal -0.402249 0.107391 0.90921 + outer loop + vertex 0.890384 1.73404 2.61585 + vertex 0.894214 1.73713 2.61718 + vertex 0.891059 1.73885 2.61558 + endloop + endfacet + facet normal -0.404237 0.103362 0.908795 + outer loop + vertex 0.894214 1.73713 2.61718 + vertex 0.894905 1.74221 2.61691 + vertex 0.891059 1.73885 2.61558 + endloop + endfacet + facet normal -0.404086 0.103153 0.908886 + outer loop + vertex 0.891059 1.73885 2.61558 + vertex 0.894905 1.74221 2.61691 + vertex 0.891702 1.74366 2.61532 + endloop + endfacet + facet normal -0.412789 0.104098 0.904859 + outer loop + vertex 0.891702 1.74366 2.61532 + vertex 0.887933 1.74059 2.61396 + vertex 0.891059 1.73885 2.61558 + endloop + endfacet + facet normal -0.413166 0.103341 0.904773 + outer loop + vertex 0.887933 1.74059 2.61396 + vertex 0.887367 1.73561 2.61427 + vertex 0.891059 1.73885 2.61558 + endloop + endfacet + facet normal -0.436753 0.105313 0.893396 + outer loop + vertex 0.887367 1.73561 2.61427 + vertex 0.887933 1.74059 2.61396 + vertex 0.884219 1.73721 2.61254 + endloop + endfacet + facet normal -0.438201 0.102094 0.89306 + outer loop + vertex 0.883782 1.7322 2.6129 + vertex 0.887367 1.73561 2.61427 + vertex 0.884219 1.73721 2.61254 + endloop + endfacet + facet normal -0.432559 0.0995761 0.89609 + outer loop + vertex 0.884219 1.73721 2.61254 + vertex 0.887933 1.74059 2.61396 + vertex 0.88469 1.74224 2.61221 + endloop + endfacet + facet normal -0.411155 0.101639 0.905881 + outer loop + vertex 0.888807 1.74616 2.61373 + vertex 0.887933 1.74059 2.61396 + vertex 0.891702 1.74366 2.61532 + endloop + endfacet + facet normal -0.411452 0.101238 0.905791 + outer loop + vertex 0.89248 1.74748 2.61525 + vertex 0.888807 1.74616 2.61373 + vertex 0.891702 1.74366 2.61532 + endloop + endfacet + facet normal -0.410532 0.101059 0.906229 + outer loop + vertex 0.891702 1.74366 2.61532 + vertex 0.895213 1.74685 2.61656 + vertex 0.89248 1.74748 2.61525 + endloop + endfacet + facet normal -0.412278 0.0934894 0.906249 + outer loop + vertex 0.894725 1.7501 2.616 + vertex 0.89248 1.74748 2.61525 + vertex 0.895213 1.74685 2.61656 + endloop + endfacet + facet normal -0.411225 0.0924205 0.906837 + outer loop + vertex 0.89248 1.74748 2.61525 + vertex 0.894725 1.7501 2.616 + vertex 0.891988 1.75077 2.61469 + endloop + endfacet + facet normal -0.409229 0.0928646 0.907694 + outer loop + vertex 0.89248 1.74748 2.61525 + vertex 0.891988 1.75077 2.61469 + vertex 0.888807 1.74616 2.61373 + endloop + endfacet + facet normal -0.416646 0.09882 0.903682 + outer loop + vertex 0.888807 1.74616 2.61373 + vertex 0.891988 1.75077 2.61469 + vertex 0.88811 1.75155 2.61282 + endloop + endfacet + facet normal -0.427978 0.0964989 0.898623 + outer loop + vertex 0.884933 1.74696 2.6118 + vertex 0.888807 1.74616 2.61373 + vertex 0.88811 1.75155 2.61282 + endloop + endfacet + facet normal -0.436538 0.103522 0.89371 + outer loop + vertex 0.884489 1.7503 2.61119 + vertex 0.884933 1.74696 2.6118 + vertex 0.88811 1.75155 2.61282 + endloop + endfacet + facet normal -0.43529 0.098344 0.894903 + outer loop + vertex 0.884489 1.7503 2.61119 + vertex 0.88811 1.75155 2.61282 + vertex 0.885288 1.7541 2.61116 + endloop + endfacet + facet normal -0.42721 0.100124 0.898592 + outer loop + vertex 0.88469 1.74224 2.61221 + vertex 0.888807 1.74616 2.61373 + vertex 0.884933 1.74696 2.6118 + endloop + endfacet + facet normal -0.420312 0.0808395 0.903771 + outer loop + vertex 0.891988 1.75077 2.61469 + vertex 0.892209 1.75546 2.61438 + vertex 0.88811 1.75155 2.61282 + endloop + endfacet + facet normal -0.422145 0.0831849 0.902704 + outer loop + vertex 0.88811 1.75155 2.61282 + vertex 0.892209 1.75546 2.61438 + vertex 0.888925 1.7571 2.61269 + endloop + endfacet + facet normal -0.444402 0.0861921 0.891671 + outer loop + vertex 0.88811 1.75155 2.61282 + vertex 0.888925 1.7571 2.61269 + vertex 0.885288 1.7541 2.61116 + endloop + endfacet + facet normal -0.440126 0.079622 0.894399 + outer loop + vertex 0.885288 1.7541 2.61116 + vertex 0.888925 1.7571 2.61269 + vertex 0.885782 1.75888 2.61098 + endloop + endfacet + facet normal -0.466555 0.0818374 0.880698 + outer loop + vertex 0.885782 1.75888 2.61098 + vertex 0.882319 1.75566 2.60945 + vertex 0.885288 1.7541 2.61116 + endloop + endfacet + facet normal -0.458618 0.0996122 0.883033 + outer loop + vertex 0.882319 1.75566 2.60945 + vertex 0.881922 1.75108 2.60976 + vertex 0.885288 1.7541 2.61116 + endloop + endfacet + facet normal -0.430356 0.0643781 0.900361 + outer loop + vertex 0.892209 1.75546 2.61438 + vertex 0.892602 1.76053 2.6142 + vertex 0.888925 1.7571 2.61269 + endloop + endfacet + facet normal -0.425537 0.0640838 0.902669 + outer loop + vertex 0.892602 1.76053 2.6142 + vertex 0.892209 1.75546 2.61438 + vertex 0.89586 1.75891 2.61585 + endloop + endfacet + facet normal -0.428891 0.0562491 0.901603 + outer loop + vertex 0.896154 1.76395 2.61568 + vertex 0.892602 1.76053 2.6142 + vertex 0.89586 1.75891 2.61585 + endloop + endfacet + facet normal -0.425516 0.0640563 0.902681 + outer loop + vertex 0.89586 1.75891 2.61585 + vertex 0.892209 1.75546 2.61438 + vertex 0.895429 1.75399 2.616 + endloop + endfacet + facet normal -0.445968 0.0655522 0.892645 + outer loop + vertex 0.895429 1.75399 2.616 + vertex 0.899013 1.75715 2.61756 + vertex 0.89586 1.75891 2.61585 + endloop + endfacet + facet normal -0.445324 0.0646314 0.893034 + outer loop + vertex 0.898317 1.75152 2.61762 + vertex 0.899013 1.75715 2.61756 + vertex 0.895429 1.75399 2.616 + endloop + endfacet + facet normal -0.434781 0.079599 0.897011 + outer loop + vertex 0.894725 1.7501 2.616 + vertex 0.898317 1.75152 2.61762 + vertex 0.895429 1.75399 2.616 + endloop + endfacet + facet normal -0.415084 0.0760391 0.9066 + outer loop + vertex 0.895429 1.75399 2.616 + vertex 0.891988 1.75077 2.61469 + vertex 0.894725 1.7501 2.616 + endloop + endfacet + facet normal -0.437165 0.0878425 0.895081 + outer loop + vertex 0.894725 1.7501 2.616 + vertex 0.895213 1.74685 2.61656 + vertex 0.898317 1.75152 2.61762 + endloop + endfacet + facet normal -0.427944 0.0805505 0.900209 + outer loop + vertex 0.895213 1.74685 2.61656 + vertex 0.899074 1.7462 2.61845 + vertex 0.898317 1.75152 2.61762 + endloop + endfacet + facet normal -0.470148 0.0713231 0.879701 + outer loop + vertex 0.899074 1.7462 2.61845 + vertex 0.902036 1.75075 2.61967 + vertex 0.898317 1.75152 2.61762 + endloop + endfacet + facet normal -0.474282 0.0494193 0.878985 + outer loop + vertex 0.902036 1.75075 2.61967 + vertex 0.902113 1.7554 2.61945 + vertex 0.898317 1.75152 2.61762 + endloop + endfacet + facet normal -0.464006 0.0663509 0.883344 + outer loop + vertex 0.902568 1.74751 2.62019 + vertex 0.902036 1.75075 2.61967 + vertex 0.899074 1.7462 2.61845 + endloop + endfacet + facet normal -0.545827 0.0454096 0.836667 + outer loop + vertex 0.902568 1.74751 2.62019 + vertex 0.904468 1.74988 2.6213 + vertex 0.902036 1.75075 2.61967 + endloop + endfacet + facet normal -0.425087 0.096842 0.899957 + outer loop + vertex 0.894905 1.74221 2.61691 + vertex 0.899074 1.7462 2.61845 + vertex 0.895213 1.74685 2.61656 + endloop + endfacet + facet normal -0.422908 0.0940538 0.901279 + outer loop + vertex 0.898184 1.74062 2.61862 + vertex 0.899074 1.7462 2.61845 + vertex 0.894905 1.74221 2.61691 + endloop + endfacet + facet normal -0.41817 0.104907 0.902291 + outer loop + vertex 0.894214 1.73713 2.61718 + vertex 0.898184 1.74062 2.61862 + vertex 0.894905 1.74221 2.61691 + endloop + endfacet + facet normal -0.418927 0.105961 0.901816 + outer loop + vertex 0.897509 1.73543 2.61891 + vertex 0.898184 1.74062 2.61862 + vertex 0.894214 1.73713 2.61718 + endloop + endfacet + facet normal -0.469809 0.111096 0.875749 + outer loop + vertex 0.898184 1.74062 2.61862 + vertex 0.897509 1.73543 2.61891 + vertex 0.901338 1.73884 2.62053 + endloop + endfacet + facet normal -0.470686 0.109282 0.875507 + outer loop + vertex 0.901859 1.74373 2.6202 + vertex 0.898184 1.74062 2.61862 + vertex 0.901338 1.73884 2.62053 + endloop + endfacet + facet normal -0.548662 0.114413 0.828179 + outer loop + vertex 0.901338 1.73884 2.62053 + vertex 0.904672 1.74218 2.62228 + vertex 0.901859 1.74373 2.6202 + endloop + endfacet + facet normal -0.557278 0.0943659 0.824946 + outer loop + vertex 0.904672 1.74218 2.62228 + vertex 0.904833 1.74662 2.62188 + vertex 0.901859 1.74373 2.6202 + endloop + endfacet + facet normal -0.551571 0.118644 0.825647 + outer loop + vertex 0.904634 1.73701 2.623 + vertex 0.904672 1.74218 2.62228 + vertex 0.901338 1.73884 2.62053 + endloop + endfacet + facet normal -0.552693 0.116108 0.825257 + outer loop + vertex 0.900768 1.73372 2.62087 + vertex 0.904634 1.73701 2.623 + vertex 0.901338 1.73884 2.62053 + endloop + endfacet + facet normal -0.469206 0.110213 0.876184 + outer loop + vertex 0.901338 1.73884 2.62053 + vertex 0.897509 1.73543 2.61891 + vertex 0.900768 1.73372 2.62087 + endloop + endfacet + facet normal -0.468984 0.110702 0.876242 + outer loop + vertex 0.897509 1.73543 2.61891 + vertex 0.89706 1.73041 2.61931 + vertex 0.900768 1.73372 2.62087 + endloop + endfacet + facet normal -0.463407 0.10257 0.880189 + outer loop + vertex 0.900768 1.73372 2.62087 + vertex 0.89706 1.73041 2.61931 + vertex 0.900096 1.72881 2.62109 + endloop + endfacet + facet normal -0.553046 0.112418 0.825532 + outer loop + vertex 0.900096 1.72881 2.62109 + vertex 0.903505 1.73133 2.62303 + vertex 0.900768 1.73372 2.62087 + endloop + endfacet + facet normal -0.553123 0.112579 0.825458 + outer loop + vertex 0.902405 1.72568 2.62307 + vertex 0.903505 1.73133 2.62303 + vertex 0.900096 1.72881 2.62109 + endloop + endfacet + facet normal -0.553595 0.112075 0.82521 + outer loop + vertex 0.899366 1.72514 2.6211 + vertex 0.902405 1.72568 2.62307 + vertex 0.900096 1.72881 2.62109 + endloop + endfacet + facet normal -0.457854 0.0931507 0.884134 + outer loop + vertex 0.900096 1.72881 2.62109 + vertex 0.896924 1.72597 2.61975 + vertex 0.899366 1.72514 2.6211 + endloop + endfacet + facet normal -0.553307 0.107581 0.826001 + outer loop + vertex 0.899366 1.72514 2.6211 + vertex 0.899643 1.72183 2.62172 + vertex 0.902405 1.72568 2.62307 + endloop + endfacet + facet normal -0.565293 0.119605 0.816173 + outer loop + vertex 0.899643 1.72183 2.62172 + vertex 0.902426 1.7203 2.62387 + vertex 0.902405 1.72568 2.62307 + endloop + endfacet + facet normal -0.463799 0.101709 0.880083 + outer loop + vertex 0.89706 1.73041 2.61931 + vertex 0.896924 1.72597 2.61975 + vertex 0.900096 1.72881 2.62109 + endloop + endfacet + facet normal -0.551749 0.114439 0.826122 + outer loop + vertex 0.903505 1.73133 2.62303 + vertex 0.904634 1.73701 2.623 + vertex 0.900768 1.73372 2.62087 + endloop + endfacet + facet normal -0.464762 0.100089 0.87976 + outer loop + vertex 0.899074 1.7462 2.61845 + vertex 0.898184 1.74062 2.61862 + vertex 0.901859 1.74373 2.6202 + endloop + endfacet + facet normal -0.470652 0.0918857 0.877521 + outer loop + vertex 0.902568 1.74751 2.62019 + vertex 0.899074 1.7462 2.61845 + vertex 0.901859 1.74373 2.6202 + endloop + endfacet + facet normal -0.490288 0.0699269 0.868751 + outer loop + vertex 0.898317 1.75152 2.61762 + vertex 0.902113 1.7554 2.61945 + vertex 0.899013 1.75715 2.61756 + endloop + endfacet + facet normal -0.418752 0.0808147 0.904497 + outer loop + vertex 0.892209 1.75546 2.61438 + vertex 0.891988 1.75077 2.61469 + vertex 0.895429 1.75399 2.616 + endloop + endfacet + facet normal -0.430425 0.104285 0.896582 + outer loop + vertex 0.887933 1.74059 2.61396 + vertex 0.888807 1.74616 2.61373 + vertex 0.88469 1.74224 2.61221 + endloop + endfacet + facet normal -0.406939 0.0962761 0.908368 + outer loop + vertex 0.894905 1.74221 2.61691 + vertex 0.895213 1.74685 2.61656 + vertex 0.891702 1.74366 2.61532 + endloop + endfacet + facet normal -0.443977 0.109677 0.889301 + outer loop + vertex 0.88694 1.731 2.61462 + vertex 0.887367 1.73561 2.61427 + vertex 0.883782 1.7322 2.6129 + endloop + endfacet + facet normal -0.404114 0.110207 0.908045 + outer loop + vertex 0.893191 1.73157 2.6174 + vertex 0.894214 1.73713 2.61718 + vertex 0.890384 1.73404 2.61585 + endloop + endfacet + facet normal -0.416038 0.112176 0.902402 + outer loop + vertex 0.893191 1.73157 2.6174 + vertex 0.897509 1.73543 2.61891 + vertex 0.894214 1.73713 2.61718 + endloop + endfacet + facet normal -0.412888 0.107891 0.904369 + outer loop + vertex 0.89706 1.73041 2.61931 + vertex 0.897509 1.73543 2.61891 + vertex 0.893191 1.73157 2.6174 + endloop + endfacet + facet normal -0.413066 0.107279 0.90436 + outer loop + vertex 0.893494 1.72655 2.61814 + vertex 0.89706 1.73041 2.61931 + vertex 0.893191 1.73157 2.6174 + endloop + endfacet + facet normal -0.408891 0.102684 0.906788 + outer loop + vertex 0.896924 1.72597 2.61975 + vertex 0.89706 1.73041 2.61931 + vertex 0.893494 1.72655 2.61814 + endloop + endfacet + facet normal -0.408313 0.105813 0.906688 + outer loop + vertex 0.893792 1.72151 2.61886 + vertex 0.896924 1.72597 2.61975 + vertex 0.893494 1.72655 2.61814 + endloop + endfacet + facet normal -0.411652 0.10852 0.904857 + outer loop + vertex 0.897316 1.7228 2.62031 + vertex 0.896924 1.72597 2.61975 + vertex 0.893792 1.72151 2.61886 + endloop + endfacet + facet normal -0.412408 0.11134 0.90417 + outer loop + vertex 0.897316 1.7228 2.62031 + vertex 0.893792 1.72151 2.61886 + vertex 0.896518 1.719 2.62041 + endloop + endfacet + facet normal -0.476038 0.123753 0.870674 + outer loop + vertex 0.896518 1.719 2.62041 + vertex 0.899643 1.72183 2.62172 + vertex 0.897316 1.7228 2.62031 + endloop + endfacet + facet normal -0.476584 0.122315 0.870578 + outer loop + vertex 0.899366 1.72514 2.6211 + vertex 0.897316 1.7228 2.62031 + vertex 0.899643 1.72183 2.62172 + endloop + endfacet + facet normal -0.473498 0.120071 0.872573 + outer loop + vertex 0.899352 1.71726 2.62219 + vertex 0.899643 1.72183 2.62172 + vertex 0.896518 1.719 2.62041 + endloop + endfacet + facet normal -0.477056 0.113216 0.87155 + outer loop + vertex 0.895914 1.71413 2.62071 + vertex 0.899352 1.71726 2.62219 + vertex 0.896518 1.719 2.62041 + endloop + endfacet + facet normal -0.415854 0.107578 0.903046 + outer loop + vertex 0.896518 1.719 2.62041 + vertex 0.892809 1.71583 2.61908 + vertex 0.895914 1.71413 2.62071 + endloop + endfacet + facet normal -0.474373 0.109354 0.873505 + outer loop + vertex 0.898959 1.71228 2.6226 + vertex 0.899352 1.71726 2.62219 + vertex 0.895914 1.71413 2.62071 + endloop + endfacet + facet normal -0.475727 0.1067 0.873097 + outer loop + vertex 0.895397 1.7092 2.62103 + vertex 0.898959 1.71228 2.6226 + vertex 0.895914 1.71413 2.62071 + endloop + endfacet + facet normal -0.419078 0.102649 0.902129 + outer loop + vertex 0.895914 1.71413 2.62071 + vertex 0.892257 1.71067 2.61941 + vertex 0.895397 1.7092 2.62103 + endloop + endfacet + facet normal -0.42139 0.0971932 0.901656 + outer loop + vertex 0.892257 1.71067 2.61941 + vertex 0.891997 1.70598 2.61979 + vertex 0.895397 1.7092 2.62103 + endloop + endfacet + facet normal -0.4184 0.0933347 0.903454 + outer loop + vertex 0.895397 1.7092 2.62103 + vertex 0.891997 1.70598 2.61979 + vertex 0.894655 1.70529 2.62109 + endloop + endfacet + facet normal -0.476542 0.103917 0.872989 + outer loop + vertex 0.894655 1.70529 2.62109 + vertex 0.898484 1.70643 2.62305 + vertex 0.895397 1.7092 2.62103 + endloop + endfacet + facet normal -0.474773 0.0944993 0.87502 + outer loop + vertex 0.894655 1.70529 2.62109 + vertex 0.89498 1.70191 2.62164 + vertex 0.898484 1.70643 2.62305 + endloop + endfacet + facet normal -0.477396 0.0970674 0.87331 + outer loop + vertex 0.89498 1.70191 2.62164 + vertex 0.898069 1.70064 2.62347 + vertex 0.898484 1.70643 2.62305 + endloop + endfacet + facet normal -0.475161 0.105836 0.873511 + outer loop + vertex 0.898484 1.70643 2.62305 + vertex 0.898959 1.71228 2.6226 + vertex 0.895397 1.7092 2.62103 + endloop + endfacet + facet normal -0.415623 0.107246 0.903192 + outer loop + vertex 0.893792 1.72151 2.61886 + vertex 0.892809 1.71583 2.61908 + vertex 0.896518 1.719 2.62041 + endloop + endfacet + facet normal -0.455892 0.099446 0.884462 + outer loop + vertex 0.897316 1.7228 2.62031 + vertex 0.899366 1.72514 2.6211 + vertex 0.896924 1.72597 2.61975 + endloop + endfacet + facet normal -0.418588 0.102017 0.902428 + outer loop + vertex 0.892809 1.71583 2.61908 + vertex 0.892257 1.71067 2.61941 + vertex 0.895914 1.71413 2.62071 + endloop + endfacet + facet normal -0.418229 0.0940078 0.903464 + outer loop + vertex 0.892388 1.70267 2.62032 + vertex 0.894655 1.70529 2.62109 + vertex 0.891997 1.70598 2.61979 + endloop + endfacet + facet normal -0.426794 0.102888 0.898477 + outer loop + vertex 0.894655 1.70529 2.62109 + vertex 0.892388 1.70267 2.62032 + vertex 0.89498 1.70191 2.62164 + endloop + endfacet + facet normal -0.475502 0.102298 0.873746 + outer loop + vertex 0.894605 1.69724 2.62198 + vertex 0.898069 1.70064 2.62347 + vertex 0.89498 1.70191 2.62164 + endloop + endfacet + facet normal -0.473496 0.0996417 0.875142 + outer loop + vertex 0.897674 1.69556 2.62383 + vertex 0.898069 1.70064 2.62347 + vertex 0.894605 1.69724 2.62198 + endloop + endfacet + facet normal -0.472596 0.101576 0.875406 + outer loop + vertex 0.894093 1.69221 2.62228 + vertex 0.897674 1.69556 2.62383 + vertex 0.894605 1.69724 2.62198 + endloop + endfacet + facet normal -0.46774 0.0948293 0.878764 + outer loop + vertex 0.897237 1.69047 2.62415 + vertex 0.897674 1.69556 2.62383 + vertex 0.894093 1.69221 2.62228 + endloop + endfacet + facet normal -0.409059 0.0960371 0.90744 + outer loop + vertex 0.888824 1.70138 2.61887 + vertex 0.887908 1.69568 2.61906 + vertex 0.891601 1.69879 2.62039 + endloop + endfacet + facet normal -0.423013 0.0980763 0.9008 + outer loop + vertex 0.894093 1.69221 2.62228 + vertex 0.894605 1.69724 2.62198 + vertex 0.891008 1.69393 2.62065 + endloop + endfacet + facet normal -0.46544 0.0996919 0.879447 + outer loop + vertex 0.893218 1.68664 2.62245 + vertex 0.897237 1.69047 2.62415 + vertex 0.894093 1.69221 2.62228 + endloop + endfacet + facet normal -0.455866 0.0868172 0.885804 + outer loop + vertex 0.896941 1.68551 2.62448 + vertex 0.897237 1.69047 2.62415 + vertex 0.893218 1.68664 2.62245 + endloop + endfacet + facet normal -0.457762 0.0799716 0.885471 + outer loop + vertex 0.89357 1.68164 2.62309 + vertex 0.896941 1.68551 2.62448 + vertex 0.893218 1.68664 2.62245 + endloop + endfacet + facet normal -0.45402 0.0758923 0.887753 + outer loop + vertex 0.896899 1.68112 2.62483 + vertex 0.896941 1.68551 2.62448 + vertex 0.89357 1.68164 2.62309 + endloop + endfacet + facet normal -0.453327 0.0802276 0.887727 + outer loop + vertex 0.893918 1.6766 2.62372 + vertex 0.896899 1.68112 2.62483 + vertex 0.89357 1.68164 2.62309 + endloop + endfacet + facet normal -0.419568 0.0845723 0.903775 + outer loop + vertex 0.893918 1.6766 2.62372 + vertex 0.89357 1.68164 2.62309 + vertex 0.890025 1.6776 2.62182 + endloop + endfacet + facet normal -0.421037 0.0785709 0.903634 + outer loop + vertex 0.889725 1.67255 2.62212 + vertex 0.893918 1.6766 2.62372 + vertex 0.890025 1.6776 2.62182 + endloop + endfacet + facet normal -0.424111 0.0824627 0.901848 + outer loop + vertex 0.893054 1.67089 2.62384 + vertex 0.893918 1.6766 2.62372 + vertex 0.889725 1.67255 2.62212 + endloop + endfacet + facet normal -0.426867 0.0761909 0.901099 + outer loop + vertex 0.889306 1.66737 2.62236 + vertex 0.893054 1.67089 2.62384 + vertex 0.889725 1.67255 2.62212 + endloop + endfacet + facet normal -0.428745 0.0786552 0.899995 + outer loop + vertex 0.892572 1.66564 2.62407 + vertex 0.893054 1.67089 2.62384 + vertex 0.889306 1.66737 2.62236 + endloop + endfacet + facet normal -0.482572 0.0823797 0.871973 + outer loop + vertex 0.893054 1.67089 2.62384 + vertex 0.892572 1.66564 2.62407 + vertex 0.896137 1.66884 2.62574 + endloop + endfacet + facet normal -0.478006 0.0908316 0.873648 + outer loop + vertex 0.896665 1.67398 2.62549 + vertex 0.893054 1.67089 2.62384 + vertex 0.896137 1.66884 2.62574 + endloop + endfacet + facet normal -0.57393 0.0978027 0.813043 + outer loop + vertex 0.896137 1.66884 2.62574 + vertex 0.899723 1.67192 2.6279 + vertex 0.896665 1.67398 2.62549 + endloop + endfacet + facet normal -0.567663 0.110345 0.815833 + outer loop + vertex 0.899723 1.67192 2.6279 + vertex 0.899619 1.67691 2.62715 + vertex 0.896665 1.67398 2.62549 + endloop + endfacet + facet normal -0.571598 0.116348 0.812243 + outer loop + vertex 0.896665 1.67398 2.62549 + vertex 0.899619 1.67691 2.62715 + vertex 0.897337 1.67794 2.6254 + endloop + endfacet + facet normal -0.469405 0.100539 0.877241 + outer loop + vertex 0.897337 1.67794 2.6254 + vertex 0.893918 1.6766 2.62372 + vertex 0.896665 1.67398 2.62549 + endloop + endfacet + facet normal -0.573136 0.112101 0.811756 + outer loop + vertex 0.899249 1.68027 2.62642 + vertex 0.897337 1.67794 2.6254 + vertex 0.899619 1.67691 2.62715 + endloop + endfacet + facet normal -0.540467 0.0737676 0.838125 + outer loop + vertex 0.897337 1.67794 2.6254 + vertex 0.899249 1.68027 2.62642 + vertex 0.896899 1.68112 2.62483 + endloop + endfacet + facet normal -0.563848 0.0797206 0.822022 + outer loop + vertex 0.898912 1.66638 2.62788 + vertex 0.899723 1.67192 2.6279 + vertex 0.896137 1.66884 2.62574 + endloop + endfacet + facet normal -0.562053 0.0825663 0.822969 + outer loop + vertex 0.895678 1.66365 2.62594 + vertex 0.898912 1.66638 2.62788 + vertex 0.896137 1.66884 2.62574 + endloop + endfacet + facet normal -0.560173 0.079201 0.824581 + outer loop + vertex 0.898478 1.66125 2.62808 + vertex 0.898912 1.66638 2.62788 + vertex 0.895678 1.66365 2.62594 + endloop + endfacet + facet normal -0.56141 0.0771765 0.823931 + outer loop + vertex 0.895337 1.65867 2.62618 + vertex 0.898478 1.66125 2.62808 + vertex 0.895678 1.66365 2.62594 + endloop + endfacet + facet normal -0.477706 0.0738729 0.875408 + outer loop + vertex 0.895678 1.66365 2.62594 + vertex 0.892171 1.66049 2.6243 + vertex 0.895337 1.65867 2.62618 + endloop + endfacet + facet normal -0.47869 0.0717909 0.875044 + outer loop + vertex 0.892171 1.66049 2.6243 + vertex 0.891947 1.65557 2.62458 + vertex 0.895337 1.65867 2.62618 + endloop + endfacet + facet normal -0.476879 0.0691865 0.876242 + outer loop + vertex 0.895337 1.65867 2.62618 + vertex 0.891947 1.65557 2.62458 + vertex 0.894962 1.654 2.62634 + endloop + endfacet + facet normal -0.562144 0.0741835 0.823706 + outer loop + vertex 0.894962 1.654 2.62634 + vertex 0.898068 1.65624 2.62826 + vertex 0.895337 1.65867 2.62618 + endloop + endfacet + facet normal -0.559169 0.0678804 0.82627 + outer loop + vertex 0.897349 1.65091 2.62821 + vertex 0.898068 1.65624 2.62826 + vertex 0.894962 1.654 2.62634 + endloop + endfacet + facet normal -0.558599 0.0685224 0.826603 + outer loop + vertex 0.894393 1.65043 2.62625 + vertex 0.897349 1.65091 2.62821 + vertex 0.894962 1.654 2.62634 + endloop + endfacet + facet normal -0.473407 0.0536189 0.87921 + outer loop + vertex 0.894962 1.654 2.62634 + vertex 0.891957 1.65121 2.62489 + vertex 0.894393 1.65043 2.62625 + endloop + endfacet + facet normal -0.472636 0.0564492 0.879448 + outer loop + vertex 0.892423 1.64805 2.62535 + vertex 0.894393 1.65043 2.62625 + vertex 0.891957 1.65121 2.62489 + endloop + endfacet + facet normal -0.436682 0.0643245 0.897313 + outer loop + vertex 0.892423 1.64805 2.62535 + vertex 0.891957 1.65121 2.62489 + vertex 0.888976 1.64666 2.62377 + endloop + endfacet + facet normal -0.436341 0.0632048 0.897559 + outer loop + vertex 0.892423 1.64805 2.62535 + vertex 0.888976 1.64666 2.62377 + vertex 0.891727 1.64416 2.62528 + endloop + endfacet + facet normal -0.490624 0.0734087 0.868274 + outer loop + vertex 0.891727 1.64416 2.62528 + vertex 0.894746 1.64709 2.62674 + vertex 0.892423 1.64805 2.62535 + endloop + endfacet + facet normal -0.485206 0.0660258 0.871904 + outer loop + vertex 0.894573 1.64249 2.62699 + vertex 0.894746 1.64709 2.62674 + vertex 0.891727 1.64416 2.62528 + endloop + endfacet + facet normal -0.486939 0.0623709 0.871206 + outer loop + vertex 0.891296 1.63922 2.6254 + vertex 0.894573 1.64249 2.62699 + vertex 0.891727 1.64416 2.62528 + endloop + endfacet + facet normal -0.435821 0.0585347 0.898128 + outer loop + vertex 0.891727 1.64416 2.62528 + vertex 0.888165 1.64095 2.62376 + vertex 0.891296 1.63922 2.6254 + endloop + endfacet + facet normal -0.437143 0.0557107 0.897665 + outer loop + vertex 0.888165 1.64095 2.62376 + vertex 0.887801 1.63578 2.62391 + vertex 0.891296 1.63922 2.6254 + endloop + endfacet + facet normal -0.436287 0.0546327 0.898147 + outer loop + vertex 0.891296 1.63922 2.6254 + vertex 0.887801 1.63578 2.62391 + vertex 0.89106 1.63418 2.62559 + endloop + endfacet + facet normal -0.487344 0.0560085 0.871412 + outer loop + vertex 0.89106 1.63418 2.62559 + vertex 0.894367 1.6375 2.62722 + vertex 0.891296 1.63922 2.6254 + endloop + endfacet + facet normal -0.487562 0.056295 0.871272 + outer loop + vertex 0.894229 1.63245 2.62747 + vertex 0.894367 1.6375 2.62722 + vertex 0.89106 1.63418 2.62559 + endloop + endfacet + facet normal -0.488715 0.0536646 0.870792 + outer loop + vertex 0.890932 1.62916 2.62583 + vertex 0.894229 1.63245 2.62747 + vertex 0.89106 1.63418 2.62559 + endloop + endfacet + facet normal -0.437834 0.0536221 0.897456 + outer loop + vertex 0.89106 1.63418 2.62559 + vertex 0.887614 1.63076 2.62411 + vertex 0.890932 1.62916 2.62583 + endloop + endfacet + facet normal -0.438417 0.0521945 0.897255 + outer loop + vertex 0.887614 1.63076 2.62411 + vertex 0.887446 1.62574 2.62432 + vertex 0.890932 1.62916 2.62583 + endloop + endfacet + facet normal -0.439869 0.0540354 0.896435 + outer loop + vertex 0.890932 1.62916 2.62583 + vertex 0.887446 1.62574 2.62432 + vertex 0.890842 1.62406 2.62609 + endloop + endfacet + facet normal -0.485743 0.0536056 0.872457 + outer loop + vertex 0.890842 1.62406 2.62609 + vertex 0.894182 1.62742 2.62774 + vertex 0.890932 1.62916 2.62583 + endloop + endfacet + facet normal -0.488474 0.0571818 0.870703 + outer loop + vertex 0.894439 1.62205 2.62824 + vertex 0.894182 1.62742 2.62774 + vertex 0.890842 1.62406 2.62609 + endloop + endfacet + facet normal -0.49042 0.0528186 0.869884 + outer loop + vertex 0.890575 1.61889 2.62625 + vertex 0.894439 1.62205 2.62824 + vertex 0.890842 1.62406 2.62609 + endloop + endfacet + facet normal -0.440917 0.0511012 0.896092 + outer loop + vertex 0.890842 1.62406 2.62609 + vertex 0.887167 1.62061 2.62448 + vertex 0.890575 1.61889 2.62625 + endloop + endfacet + facet normal -0.442426 0.0475411 0.895544 + outer loop + vertex 0.887167 1.62061 2.62448 + vertex 0.886957 1.61556 2.62464 + vertex 0.890575 1.61889 2.62625 + endloop + endfacet + facet normal -0.440881 0.0454385 0.896415 + outer loop + vertex 0.890575 1.61889 2.62625 + vertex 0.886957 1.61556 2.62464 + vertex 0.890108 1.61396 2.62627 + endloop + endfacet + facet normal -0.489301 0.0499298 0.870684 + outer loop + vertex 0.890108 1.61396 2.62627 + vertex 0.893576 1.61646 2.62808 + vertex 0.890575 1.61889 2.62625 + endloop + endfacet + facet normal -0.487884 0.0472825 0.871627 + outer loop + vertex 0.892723 1.61091 2.6279 + vertex 0.893576 1.61646 2.62808 + vertex 0.890108 1.61396 2.62627 + endloop + endfacet + facet normal -0.488851 0.0461969 0.871143 + outer loop + vertex 0.889502 1.61026 2.62613 + vertex 0.892723 1.61091 2.6279 + vertex 0.890108 1.61396 2.62627 + endloop + endfacet + facet normal -0.439375 0.037093 0.897537 + outer loop + vertex 0.890108 1.61396 2.62627 + vertex 0.88698 1.61106 2.62486 + vertex 0.889502 1.61026 2.62613 + endloop + endfacet + facet normal -0.439635 0.0361426 0.897449 + outer loop + vertex 0.887506 1.60786 2.62525 + vertex 0.889502 1.61026 2.62613 + vertex 0.88698 1.61106 2.62486 + endloop + endfacet + facet normal -0.429612 0.0383605 0.902199 + outer loop + vertex 0.887506 1.60786 2.62525 + vertex 0.88698 1.61106 2.62486 + vertex 0.884084 1.60658 2.62367 + endloop + endfacet + facet normal -0.429277 0.0372112 0.902406 + outer loop + vertex 0.887506 1.60786 2.62525 + vertex 0.884084 1.60658 2.62367 + vertex 0.886914 1.60404 2.62512 + endloop + endfacet + facet normal -0.448193 0.0404476 0.893021 + outer loop + vertex 0.886914 1.60404 2.62512 + vertex 0.889971 1.60696 2.62653 + vertex 0.887506 1.60786 2.62525 + endloop + endfacet + facet normal -0.447283 0.0392472 0.893531 + outer loop + vertex 0.889913 1.60244 2.62669 + vertex 0.889971 1.60696 2.62653 + vertex 0.886914 1.60404 2.62512 + endloop + endfacet + facet normal -0.448943 0.0354802 0.892856 + outer loop + vertex 0.886596 1.59918 2.62516 + vertex 0.889913 1.60244 2.62669 + vertex 0.886914 1.60404 2.62512 + endloop + endfacet + facet normal -0.431259 0.0343838 0.901573 + outer loop + vertex 0.886914 1.60404 2.62512 + vertex 0.883415 1.60094 2.62357 + vertex 0.886596 1.59918 2.62516 + endloop + endfacet + facet normal -0.432782 0.0310816 0.900963 + outer loop + vertex 0.883415 1.60094 2.62357 + vertex 0.883151 1.59579 2.62362 + vertex 0.886596 1.59918 2.62516 + endloop + endfacet + facet normal -0.432809 0.0311147 0.900949 + outer loop + vertex 0.886596 1.59918 2.62516 + vertex 0.883151 1.59579 2.62362 + vertex 0.886435 1.59417 2.62525 + endloop + endfacet + facet normal -0.451001 0.0315297 0.891966 + outer loop + vertex 0.886435 1.59417 2.62525 + vertex 0.88978 1.59755 2.62682 + vertex 0.886596 1.59918 2.62516 + endloop + endfacet + facet normal -0.451142 0.031705 0.891889 + outer loop + vertex 0.889675 1.59257 2.62695 + vertex 0.88978 1.59755 2.62682 + vertex 0.886435 1.59417 2.62525 + endloop + endfacet + facet normal -0.45297 0.0271833 0.891111 + outer loop + vertex 0.886351 1.58917 2.62536 + vertex 0.889675 1.59257 2.62695 + vertex 0.886435 1.59417 2.62525 + endloop + endfacet + facet normal -0.433798 0.0270688 0.900603 + outer loop + vertex 0.886435 1.59417 2.62525 + vertex 0.883039 1.59075 2.62372 + vertex 0.886351 1.58917 2.62536 + endloop + endfacet + facet normal -0.435211 0.0235026 0.900022 + outer loop + vertex 0.883039 1.59075 2.62372 + vertex 0.882976 1.58575 2.62382 + vertex 0.886351 1.58917 2.62536 + endloop + endfacet + facet normal -0.434902 0.0231259 0.900181 + outer loop + vertex 0.886351 1.58917 2.62536 + vertex 0.882976 1.58575 2.62382 + vertex 0.886289 1.58417 2.62546 + endloop + endfacet + facet normal -0.454634 0.0231768 0.890377 + outer loop + vertex 0.886289 1.58417 2.62546 + vertex 0.889598 1.58757 2.62706 + vertex 0.886351 1.58917 2.62536 + endloop + endfacet + facet normal -0.454827 0.0234137 0.890272 + outer loop + vertex 0.889531 1.58258 2.62716 + vertex 0.889598 1.58757 2.62706 + vertex 0.886289 1.58417 2.62546 + endloop + endfacet + facet normal -0.455863 0.0208113 0.889806 + outer loop + vertex 0.886221 1.57918 2.62554 + vertex 0.889531 1.58258 2.62716 + vertex 0.886289 1.58417 2.62546 + endloop + endfacet + facet normal -0.436079 0.0207051 0.89967 + outer loop + vertex 0.886289 1.58417 2.62546 + vertex 0.882913 1.58076 2.6239 + vertex 0.886221 1.57918 2.62554 + endloop + endfacet + facet normal -0.436492 0.0196565 0.899493 + outer loop + vertex 0.882913 1.58076 2.6239 + vertex 0.882836 1.57578 2.62397 + vertex 0.886221 1.57918 2.62554 + endloop + endfacet + facet normal -0.437231 0.0205656 0.899114 + outer loop + vertex 0.886221 1.57918 2.62554 + vertex 0.882836 1.57578 2.62397 + vertex 0.886142 1.57419 2.62562 + endloop + endfacet + facet normal -0.456802 0.0207257 0.889327 + outer loop + vertex 0.886142 1.57419 2.62562 + vertex 0.889462 1.57758 2.62724 + vertex 0.886221 1.57918 2.62554 + endloop + endfacet + facet normal -0.457719 0.0218622 0.888828 + outer loop + vertex 0.889389 1.57259 2.62733 + vertex 0.889462 1.57758 2.62724 + vertex 0.886142 1.57419 2.62562 + endloop + endfacet + facet normal -0.457661 0.0220063 0.888854 + outer loop + vertex 0.88606 1.5692 2.6257 + vertex 0.889389 1.57259 2.62733 + vertex 0.886142 1.57419 2.62562 + endloop + endfacet + facet normal -0.438109 0.0218419 0.898657 + outer loop + vertex 0.886142 1.57419 2.62562 + vertex 0.882749 1.57079 2.62405 + vertex 0.88606 1.5692 2.6257 + endloop + endfacet + facet normal -0.438155 0.0217251 0.898637 + outer loop + vertex 0.882749 1.57079 2.62405 + vertex 0.882664 1.56579 2.62413 + vertex 0.88606 1.5692 2.6257 + endloop + endfacet + facet normal -0.438792 0.0225125 0.898306 + outer loop + vertex 0.88606 1.5692 2.6257 + vertex 0.882664 1.56579 2.62413 + vertex 0.885983 1.56421 2.62579 + endloop + endfacet + facet normal -0.458527 0.0226437 0.888392 + outer loop + vertex 0.885983 1.56421 2.62579 + vertex 0.889318 1.5676 2.62742 + vertex 0.88606 1.5692 2.6257 + endloop + endfacet + facet normal -0.458238 0.0222834 0.88855 + outer loop + vertex 0.889254 1.56261 2.62751 + vertex 0.889318 1.5676 2.62742 + vertex 0.885983 1.56421 2.62579 + endloop + endfacet + facet normal -0.458873 0.0206701 0.888261 + outer loop + vertex 0.88592 1.55921 2.62587 + vertex 0.889254 1.56261 2.62751 + vertex 0.885983 1.56421 2.62579 + endloop + endfacet + facet normal -0.439076 0.0205893 0.898214 + outer loop + vertex 0.885983 1.56421 2.62579 + vertex 0.88259 1.5608 2.62421 + vertex 0.88592 1.55921 2.62587 + endloop + endfacet + facet normal -0.440209 0.0176958 0.897721 + outer loop + vertex 0.88259 1.5608 2.62421 + vertex 0.882534 1.5558 2.62428 + vertex 0.88592 1.55921 2.62587 + endloop + endfacet + facet normal -0.439094 0.0163215 0.898293 + outer loop + vertex 0.88592 1.55921 2.62587 + vertex 0.882534 1.5558 2.62428 + vertex 0.885874 1.55422 2.62594 + endloop + endfacet + facet normal -0.459697 0.0163698 0.887925 + outer loop + vertex 0.885874 1.55422 2.62594 + vertex 0.889199 1.55762 2.6276 + vertex 0.88592 1.55921 2.62587 + endloop + endfacet + facet normal -0.458056 0.0143343 0.888808 + outer loop + vertex 0.889159 1.55265 2.62766 + vertex 0.889199 1.55762 2.6276 + vertex 0.885874 1.55422 2.62594 + endloop + endfacet + facet normal -0.459044 0.0117467 0.888336 + outer loop + vertex 0.885841 1.54924 2.62599 + vertex 0.889159 1.55265 2.62766 + vertex 0.885874 1.55422 2.62594 + endloop + endfacet + facet normal -0.43914 0.0117156 0.898342 + outer loop + vertex 0.885874 1.55422 2.62594 + vertex 0.882494 1.5508 2.62433 + vertex 0.885841 1.54924 2.62599 + endloop + endfacet + facet normal -0.440297 0.00868413 0.89781 + outer loop + vertex 0.882494 1.5508 2.62433 + vertex 0.882468 1.54581 2.62437 + vertex 0.885841 1.54924 2.62599 + endloop + endfacet + facet normal -0.439807 0.0080852 0.898056 + outer loop + vertex 0.885841 1.54924 2.62599 + vertex 0.882468 1.54581 2.62437 + vertex 0.885819 1.54426 2.62602 + endloop + endfacet + facet normal -0.459139 0.00810839 0.888327 + outer loop + vertex 0.885819 1.54426 2.62602 + vertex 0.889128 1.54769 2.6277 + vertex 0.885841 1.54924 2.62599 + endloop + endfacet + facet normal -0.45892 0.00784092 0.888443 + outer loop + vertex 0.889106 1.54273 2.62773 + vertex 0.889128 1.54769 2.6277 + vertex 0.885819 1.54426 2.62602 + endloop + endfacet + facet normal -0.459935 0.00509445 0.887938 + outer loop + vertex 0.885805 1.53928 2.62604 + vertex 0.889106 1.54273 2.62773 + vertex 0.885819 1.54426 2.62602 + endloop + endfacet + facet normal -0.440575 0.00508554 0.897701 + outer loop + vertex 0.885819 1.54426 2.62602 + vertex 0.882453 1.54082 2.62439 + vertex 0.885805 1.53928 2.62604 + endloop + endfacet + facet normal -0.441249 0.00326917 0.897379 + outer loop + vertex 0.882453 1.54082 2.62439 + vertex 0.882443 1.53582 2.6244 + vertex 0.885805 1.53928 2.62604 + endloop + endfacet + facet normal -0.441623 0.00372117 0.897193 + outer loop + vertex 0.885805 1.53928 2.62604 + vertex 0.882443 1.53582 2.6244 + vertex 0.885798 1.5343 2.62606 + endloop + endfacet + facet normal -0.461763 0.00371712 0.886996 + outer loop + vertex 0.885798 1.5343 2.62606 + vertex 0.889095 1.53776 2.62776 + vertex 0.885805 1.53928 2.62604 + endloop + endfacet + facet normal -0.463155 0.00540338 0.886261 + outer loop + vertex 0.889088 1.53279 2.62779 + vertex 0.889095 1.53776 2.62776 + vertex 0.885798 1.5343 2.62606 + endloop + endfacet + facet normal -0.464103 0.00278827 0.885777 + outer loop + vertex 0.885792 1.52931 2.62607 + vertex 0.889088 1.53279 2.62779 + vertex 0.885798 1.5343 2.62606 + endloop + endfacet + facet normal -0.442503 0.00279081 0.896763 + outer loop + vertex 0.885798 1.5343 2.62606 + vertex 0.882435 1.53083 2.62441 + vertex 0.885792 1.52931 2.62607 + endloop + endfacet + facet normal -0.442558 0.00264077 0.896736 + outer loop + vertex 0.882435 1.53083 2.62441 + vertex 0.882423 1.52584 2.62442 + vertex 0.885792 1.52931 2.62607 + endloop + endfacet + facet normal -0.442784 0.0029128 0.896624 + outer loop + vertex 0.885792 1.52931 2.62607 + vertex 0.882423 1.52584 2.62442 + vertex 0.885782 1.52432 2.62608 + endloop + endfacet + facet normal -0.464857 0.00292972 0.885381 + outer loop + vertex 0.885782 1.52432 2.62608 + vertex 0.889086 1.52781 2.62781 + vertex 0.885792 1.52931 2.62607 + endloop + endfacet + facet normal -0.464806 0.00286869 0.885408 + outer loop + vertex 0.88908 1.52282 2.62782 + vertex 0.889086 1.52781 2.62781 + vertex 0.885782 1.52432 2.62608 + endloop + endfacet + facet normal -0.465011 0.00230021 0.885302 + outer loop + vertex 0.885773 1.51933 2.62609 + vertex 0.88908 1.52282 2.62782 + vertex 0.885782 1.52432 2.62608 + endloop + endfacet + facet normal -0.441892 0.00227376 0.897065 + outer loop + vertex 0.885782 1.52432 2.62608 + vertex 0.882409 1.52084 2.62443 + vertex 0.885773 1.51933 2.62609 + endloop + endfacet + facet normal -0.44157 0.00316382 0.897221 + outer loop + vertex 0.882409 1.52084 2.62443 + vertex 0.882397 1.51585 2.62444 + vertex 0.885773 1.51933 2.62609 + endloop + endfacet + facet normal -0.440632 0.00203485 0.897686 + outer loop + vertex 0.885773 1.51933 2.62609 + vertex 0.882397 1.51585 2.62444 + vertex 0.885765 1.51434 2.6261 + endloop + endfacet + facet normal -0.464271 0.00205492 0.885691 + outer loop + vertex 0.885765 1.51434 2.6261 + vertex 0.889072 1.51782 2.62783 + vertex 0.885773 1.51933 2.62609 + endloop + endfacet + facet normal -0.462504 -8.29909e-05 0.886617 + outer loop + vertex 0.889071 1.51284 2.62782 + vertex 0.889072 1.51782 2.62783 + vertex 0.885765 1.51434 2.6261 + endloop + endfacet + facet normal -0.462535 -0.000171404 0.886601 + outer loop + vertex 0.885766 1.50935 2.6261 + vertex 0.889071 1.51284 2.62782 + vertex 0.885765 1.51434 2.6261 + endloop + endfacet + facet normal -0.439443 -0.000162846 0.89827 + outer loop + vertex 0.885765 1.51434 2.6261 + vertex 0.882394 1.51086 2.62445 + vertex 0.885766 1.50935 2.6261 + endloop + endfacet + facet normal -0.43976 -0.00104324 0.898115 + outer loop + vertex 0.882394 1.51086 2.62445 + vertex 0.882402 1.50587 2.62445 + vertex 0.885766 1.50935 2.6261 + endloop + endfacet + facet normal -0.439354 -0.00152931 0.898313 + outer loop + vertex 0.885766 1.50935 2.6261 + vertex 0.882402 1.50587 2.62445 + vertex 0.885775 1.50437 2.6261 + endloop + endfacet + facet normal -0.463125 -0.00155988 0.886292 + outer loop + vertex 0.885775 1.50437 2.6261 + vertex 0.889073 1.50785 2.62782 + vertex 0.885766 1.50935 2.6261 + endloop + endfacet + facet normal -0.463082 -0.00161196 0.886314 + outer loop + vertex 0.889085 1.50285 2.62782 + vertex 0.889073 1.50785 2.62782 + vertex 0.885775 1.50437 2.6261 + endloop + endfacet + facet normal -0.463256 -0.00209769 0.886222 + outer loop + vertex 0.885785 1.49938 2.62609 + vertex 0.889085 1.50285 2.62782 + vertex 0.885775 1.50437 2.6261 + endloop + endfacet + facet normal -0.440379 -0.00206812 0.89781 + outer loop + vertex 0.885775 1.50437 2.6261 + vertex 0.882413 1.50089 2.62444 + vertex 0.885785 1.49938 2.62609 + endloop + endfacet + facet normal -0.44069 -0.00293133 0.897655 + outer loop + vertex 0.882413 1.50089 2.62444 + vertex 0.882422 1.4959 2.62443 + vertex 0.885785 1.49938 2.62609 + endloop + endfacet + facet normal -0.44099 -0.00257085 0.897508 + outer loop + vertex 0.885785 1.49938 2.62609 + vertex 0.882422 1.4959 2.62443 + vertex 0.885794 1.49438 2.62608 + endloop + endfacet + facet normal -0.463301 -0.0025873 0.886197 + outer loop + vertex 0.885794 1.49438 2.62608 + vertex 0.889099 1.49784 2.62782 + vertex 0.885785 1.49938 2.62609 + endloop + endfacet + facet normal -0.462709 -0.00330639 0.886504 + outer loop + vertex 0.88911 1.49281 2.6278 + vertex 0.889099 1.49784 2.62782 + vertex 0.885794 1.49438 2.62608 + endloop + endfacet + facet normal -0.462687 -0.00324461 0.886516 + outer loop + vertex 0.885802 1.48937 2.62606 + vertex 0.88911 1.49281 2.6278 + vertex 0.885794 1.49438 2.62608 + endloop + endfacet + facet normal -0.440539 -0.00323999 0.897728 + outer loop + vertex 0.885794 1.49438 2.62608 + vertex 0.88243 1.49091 2.62442 + vertex 0.885802 1.48937 2.62606 + endloop + endfacet + facet normal -0.440865 -0.00412781 0.897564 + outer loop + vertex 0.88243 1.49091 2.62442 + vertex 0.882446 1.48592 2.6244 + vertex 0.885802 1.48937 2.62606 + endloop + endfacet + facet normal -0.43933 -0.00597933 0.898306 + outer loop + vertex 0.885802 1.48937 2.62606 + vertex 0.882446 1.48592 2.6244 + vertex 0.885819 1.48436 2.62604 + endloop + endfacet + facet normal -0.46057 -0.0060004 0.887603 + outer loop + vertex 0.885819 1.48436 2.62604 + vertex 0.889121 1.48778 2.62778 + vertex 0.885802 1.48937 2.62606 + endloop + endfacet + facet normal -0.457894 -0.00927016 0.888958 + outer loop + vertex 0.88914 1.48276 2.62773 + vertex 0.889121 1.48778 2.62778 + vertex 0.885819 1.48436 2.62604 + endloop + endfacet + facet normal -0.458179 -0.0100255 0.888804 + outer loop + vertex 0.885852 1.47936 2.626 + vertex 0.88914 1.48276 2.62773 + vertex 0.885819 1.48436 2.62604 + endloop + endfacet + facet normal -0.438188 -0.00997187 0.898828 + outer loop + vertex 0.885819 1.48436 2.62604 + vertex 0.882479 1.48093 2.62437 + vertex 0.885852 1.47936 2.626 + endloop + endfacet + facet normal -0.438977 -0.0120929 0.898417 + outer loop + vertex 0.882479 1.48093 2.62437 + vertex 0.88253 1.47594 2.62433 + vertex 0.885852 1.47936 2.626 + endloop + endfacet + facet normal -0.438078 -0.0131714 0.89884 + outer loop + vertex 0.885852 1.47936 2.626 + vertex 0.88253 1.47594 2.62433 + vertex 0.8859 1.47436 2.62595 + endloop + endfacet + facet normal -0.457385 -0.0132604 0.88917 + outer loop + vertex 0.8859 1.47436 2.62595 + vertex 0.889169 1.47776 2.62768 + vertex 0.885852 1.47936 2.626 + endloop + endfacet + facet normal -0.456128 -0.0147873 0.889791 + outer loop + vertex 0.889214 1.47276 2.62762 + vertex 0.889169 1.47776 2.62768 + vertex 0.8859 1.47436 2.62595 + endloop + endfacet + facet normal -0.456407 -0.0155291 0.889635 + outer loop + vertex 0.885959 1.46937 2.62589 + vertex 0.889214 1.47276 2.62762 + vertex 0.8859 1.47436 2.62595 + endloop + endfacet + facet normal -0.438838 -0.0154225 0.898434 + outer loop + vertex 0.8859 1.47436 2.62595 + vertex 0.882593 1.47095 2.62428 + vertex 0.885959 1.46937 2.62589 + endloop + endfacet + facet normal -0.439552 -0.0173416 0.89805 + outer loop + vertex 0.882593 1.47095 2.62428 + vertex 0.882662 1.46595 2.62421 + vertex 0.885959 1.46937 2.62589 + endloop + endfacet + facet normal -0.439842 -0.0169949 0.897914 + outer loop + vertex 0.885959 1.46937 2.62589 + vertex 0.882662 1.46595 2.62421 + vertex 0.886024 1.46438 2.62583 + endloop + endfacet + facet normal -0.456668 -0.0171076 0.889473 + outer loop + vertex 0.886024 1.46438 2.62583 + vertex 0.889269 1.46777 2.62756 + vertex 0.885959 1.46937 2.62589 + endloop + endfacet + facet normal -0.456667 -0.0171093 0.889473 + outer loop + vertex 0.88933 1.46278 2.6275 + vertex 0.889269 1.46777 2.62756 + vertex 0.886024 1.46438 2.62583 + endloop + endfacet + facet normal -0.457146 -0.0183861 0.889202 + outer loop + vertex 0.886092 1.45938 2.62576 + vertex 0.88933 1.46278 2.6275 + vertex 0.886024 1.46438 2.62583 + endloop + endfacet + facet normal -0.439766 -0.0182681 0.897927 + outer loop + vertex 0.886024 1.46438 2.62583 + vertex 0.882731 1.46096 2.62415 + vertex 0.886092 1.45938 2.62576 + endloop + endfacet + facet normal -0.439461 -0.0174504 0.898092 + outer loop + vertex 0.882731 1.46096 2.62415 + vertex 0.882799 1.45598 2.62409 + vertex 0.886092 1.45938 2.62576 + endloop + endfacet + facet normal -0.438869 -0.0181578 0.898368 + outer loop + vertex 0.886092 1.45938 2.62576 + vertex 0.882799 1.45598 2.62409 + vertex 0.886162 1.45439 2.6257 + endloop + endfacet + facet normal -0.457627 -0.0182922 0.888956 + outer loop + vertex 0.886162 1.45439 2.6257 + vertex 0.889392 1.45779 2.62743 + vertex 0.886092 1.45938 2.62576 + endloop + endfacet + facet normal -0.456009 -0.0202353 0.889745 + outer loop + vertex 0.889465 1.45279 2.62735 + vertex 0.889392 1.45779 2.62743 + vertex 0.886162 1.45439 2.6257 + endloop + endfacet + facet normal -0.455427 -0.0186881 0.890077 + outer loop + vertex 0.886243 1.4494 2.62563 + vertex 0.889465 1.45279 2.62735 + vertex 0.886162 1.45439 2.6257 + endloop + endfacet + facet normal -0.43714 -0.0185059 0.899203 + outer loop + vertex 0.886162 1.45439 2.6257 + vertex 0.882875 1.45099 2.62403 + vertex 0.886243 1.4494 2.62563 + endloop + endfacet + facet normal -0.436653 -0.0172045 0.899466 + outer loop + vertex 0.882875 1.45099 2.62403 + vertex 0.882962 1.446 2.62397 + vertex 0.886243 1.4494 2.62563 + endloop + endfacet + facet normal -0.434826 -0.0193765 0.900306 + outer loop + vertex 0.886243 1.4494 2.62563 + vertex 0.882962 1.446 2.62397 + vertex 0.886334 1.44442 2.62557 + endloop + endfacet + facet normal -0.453235 -0.0195959 0.891176 + outer loop + vertex 0.886334 1.44442 2.62557 + vertex 0.889549 1.4478 2.62728 + vertex 0.886243 1.4494 2.62563 + endloop + endfacet + facet normal -0.451005 -0.0222541 0.892244 + outer loop + vertex 0.889638 1.44282 2.6272 + vertex 0.889549 1.4478 2.62728 + vertex 0.886334 1.44442 2.62557 + endloop + endfacet + facet normal -0.450826 -0.0217817 0.892346 + outer loop + vertex 0.886407 1.43943 2.62548 + vertex 0.889638 1.44282 2.6272 + vertex 0.886334 1.44442 2.62557 + endloop + endfacet + facet normal -0.43295 -0.0216684 0.901157 + outer loop + vertex 0.886334 1.44442 2.62557 + vertex 0.883045 1.44102 2.62391 + vertex 0.886407 1.43943 2.62548 + endloop + endfacet + facet normal -0.433491 -0.0231117 0.900862 + outer loop + vertex 0.883045 1.44102 2.62391 + vertex 0.883091 1.43603 2.6238 + vertex 0.886407 1.43943 2.62548 + endloop + endfacet + facet normal -0.431761 -0.0251779 0.901636 + outer loop + vertex 0.886407 1.43943 2.62548 + vertex 0.883091 1.43603 2.6238 + vertex 0.88644 1.43445 2.62536 + endloop + endfacet + facet normal -0.449109 -0.025083 0.893125 + outer loop + vertex 0.88644 1.43445 2.62536 + vertex 0.889699 1.43783 2.62709 + vertex 0.886407 1.43943 2.62548 + endloop + endfacet + facet normal -0.446271 -0.0284958 0.894444 + outer loop + vertex 0.889734 1.43284 2.62695 + vertex 0.889699 1.43783 2.62709 + vertex 0.88644 1.43445 2.62536 + endloop + endfacet + facet normal -0.446329 -0.0286476 0.894411 + outer loop + vertex 0.886483 1.42946 2.62522 + vertex 0.889734 1.43284 2.62695 + vertex 0.88644 1.43445 2.62536 + endloop + endfacet + facet normal -0.430991 -0.0287221 0.901899 + outer loop + vertex 0.88644 1.43445 2.62536 + vertex 0.88312 1.43104 2.62367 + vertex 0.886483 1.42946 2.62522 + endloop + endfacet + facet normal -0.431254 -0.0294285 0.90175 + outer loop + vertex 0.88312 1.43104 2.62367 + vertex 0.883251 1.42604 2.62357 + vertex 0.886483 1.42946 2.62522 + endloop + endfacet + facet normal -0.430066 -0.0308051 0.902272 + outer loop + vertex 0.886483 1.42946 2.62522 + vertex 0.883251 1.42604 2.62357 + vertex 0.886682 1.42446 2.62515 + endloop + endfacet + facet normal -0.444177 -0.0312623 0.895393 + outer loop + vertex 0.886682 1.42446 2.62515 + vertex 0.889815 1.42782 2.62682 + vertex 0.886483 1.42946 2.62522 + endloop + endfacet + facet normal -0.442459 -0.0332498 0.896172 + outer loop + vertex 0.890091 1.42275 2.62677 + vertex 0.889815 1.42782 2.62682 + vertex 0.886682 1.42446 2.62515 + endloop + endfacet + facet normal -0.44247 -0.0332797 0.896165 + outer loop + vertex 0.887166 1.41957 2.6252 + vertex 0.890091 1.42275 2.62677 + vertex 0.886682 1.42446 2.62515 + endloop + endfacet + facet normal -0.429191 -0.0318885 0.902651 + outer loop + vertex 0.886682 1.42446 2.62515 + vertex 0.883678 1.42103 2.6236 + vertex 0.887166 1.41957 2.6252 + endloop + endfacet + facet normal -0.429295 -0.0322054 0.90259 + outer loop + vertex 0.883678 1.42103 2.6236 + vertex 0.884633 1.41624 2.62388 + vertex 0.887166 1.41957 2.6252 + endloop + endfacet + facet normal -0.427688 -0.033708 0.903298 + outer loop + vertex 0.887666 1.41556 2.62529 + vertex 0.887166 1.41957 2.6252 + vertex 0.884633 1.41624 2.62388 + endloop + endfacet + facet normal -0.427994 -0.0355313 0.903083 + outer loop + vertex 0.887666 1.41556 2.62529 + vertex 0.884633 1.41624 2.62388 + vertex 0.886452 1.41148 2.62456 + endloop + endfacet + facet normal -0.434998 -0.0328642 0.899831 + outer loop + vertex 0.886452 1.41148 2.62456 + vertex 0.889613 1.41315 2.62614 + vertex 0.887666 1.41556 2.62529 + endloop + endfacet + facet normal -0.441916 -0.0397306 0.896176 + outer loop + vertex 0.889613 1.41315 2.62614 + vertex 0.890693 1.41734 2.62686 + vertex 0.887666 1.41556 2.62529 + endloop + endfacet + facet normal -0.473008 -0.0290622 0.880579 + outer loop + vertex 0.889613 1.41315 2.62614 + vertex 0.8931 1.41237 2.62799 + vertex 0.890693 1.41734 2.62686 + endloop + endfacet + facet normal -0.490297 -0.0396805 0.870652 + outer loop + vertex 0.8931 1.41237 2.62799 + vertex 0.894036 1.41682 2.62872 + vertex 0.890693 1.41734 2.62686 + endloop + endfacet + facet normal -0.490026 -0.0369529 0.870924 + outer loop + vertex 0.894036 1.41682 2.62872 + vertex 0.893398 1.42104 2.62854 + vertex 0.890693 1.41734 2.62686 + endloop + endfacet + facet normal -0.488137 -0.0387799 0.871905 + outer loop + vertex 0.890693 1.41734 2.62686 + vertex 0.893398 1.42104 2.62854 + vertex 0.890091 1.42275 2.62677 + endloop + endfacet + facet normal -0.48754 -0.0372109 0.872307 + outer loop + vertex 0.893398 1.42104 2.62854 + vertex 0.893065 1.42602 2.62857 + vertex 0.890091 1.42275 2.62677 + endloop + endfacet + facet normal -0.474943 -0.0413411 0.879045 + outer loop + vertex 0.890177 1.40895 2.62625 + vertex 0.8931 1.41237 2.62799 + vertex 0.889613 1.41315 2.62614 + endloop + endfacet + facet normal -0.473061 -0.0434178 0.879959 + outer loop + vertex 0.893779 1.40675 2.62808 + vertex 0.8931 1.41237 2.62799 + vertex 0.890177 1.40895 2.62625 + endloop + endfacet + facet normal -0.474433 -0.0464067 0.879068 + outer loop + vertex 0.890732 1.40386 2.62628 + vertex 0.893779 1.40675 2.62808 + vertex 0.890177 1.40895 2.62625 + endloop + endfacet + facet normal -0.435247 -0.0420037 0.899331 + outer loop + vertex 0.890177 1.40895 2.62625 + vertex 0.887107 1.40601 2.62463 + vertex 0.890732 1.40386 2.62628 + endloop + endfacet + facet normal -0.436773 -0.0452679 0.898432 + outer loop + vertex 0.887107 1.40601 2.62463 + vertex 0.8875 1.40097 2.62457 + vertex 0.890732 1.40386 2.62628 + endloop + endfacet + facet normal -0.433184 -0.0501578 0.899909 + outer loop + vertex 0.890732 1.40386 2.62628 + vertex 0.8875 1.40097 2.62457 + vertex 0.890888 1.39895 2.62608 + endloop + endfacet + facet normal -0.477835 -0.0506398 0.876989 + outer loop + vertex 0.890888 1.39895 2.62608 + vertex 0.894469 1.40133 2.62817 + vertex 0.890732 1.40386 2.62628 + endloop + endfacet + facet normal -0.471153 -0.0631388 0.879789 + outer loop + vertex 0.893554 1.39691 2.62737 + vertex 0.894469 1.40133 2.62817 + vertex 0.890888 1.39895 2.62608 + endloop + endfacet + facet normal -0.465682 -0.0537866 0.883316 + outer loop + vertex 0.890922 1.39429 2.62582 + vertex 0.893554 1.39691 2.62737 + vertex 0.890888 1.39895 2.62608 + endloop + endfacet + facet normal -0.429437 -0.0545482 0.901448 + outer loop + vertex 0.890888 1.39895 2.62608 + vertex 0.887658 1.39605 2.62437 + vertex 0.890922 1.39429 2.62582 + endloop + endfacet + facet normal -0.429311 -0.0542512 0.901526 + outer loop + vertex 0.887658 1.39605 2.62437 + vertex 0.88777 1.39114 2.62413 + vertex 0.890922 1.39429 2.62582 + endloop + endfacet + facet normal -0.427927 -0.0559381 0.902081 + outer loop + vertex 0.890922 1.39429 2.62582 + vertex 0.88777 1.39114 2.62413 + vertex 0.89115 1.38953 2.62563 + endloop + endfacet + facet normal -0.474468 -0.0572309 0.87841 + outer loop + vertex 0.89115 1.38953 2.62563 + vertex 0.894127 1.39286 2.62746 + vertex 0.890922 1.39429 2.62582 + endloop + endfacet + facet normal -0.474009 -0.0577582 0.878624 + outer loop + vertex 0.894448 1.38793 2.62731 + vertex 0.894127 1.39286 2.62746 + vertex 0.89115 1.38953 2.62563 + endloop + endfacet + facet normal -0.475502 -0.0619842 0.877528 + outer loop + vertex 0.89145 1.38457 2.62544 + vertex 0.894448 1.38793 2.62731 + vertex 0.89115 1.38953 2.62563 + endloop + endfacet + facet normal -0.426814 -0.0599739 0.902349 + outer loop + vertex 0.89115 1.38953 2.62563 + vertex 0.887964 1.38618 2.6239 + vertex 0.89145 1.38457 2.62544 + endloop + endfacet + facet normal -0.426672 -0.0595764 0.902442 + outer loop + vertex 0.887964 1.38618 2.6239 + vertex 0.88835 1.38112 2.62375 + vertex 0.89145 1.38457 2.62544 + endloop + endfacet + facet normal -0.42647 -0.0597976 0.902523 + outer loop + vertex 0.89145 1.38457 2.62544 + vertex 0.88835 1.38112 2.62375 + vertex 0.891949 1.3796 2.62535 + endloop + endfacet + facet normal -0.476631 -0.0643379 0.876746 + outer loop + vertex 0.891949 1.3796 2.62535 + vertex 0.894815 1.38284 2.62715 + vertex 0.89145 1.38457 2.62544 + endloop + endfacet + facet normal -0.481273 -0.0590389 0.87458 + outer loop + vertex 0.895459 1.37743 2.62713 + vertex 0.894815 1.38284 2.62715 + vertex 0.891949 1.3796 2.62535 + endloop + endfacet + facet normal -0.485738 -0.0688994 0.871385 + outer loop + vertex 0.892529 1.37557 2.62535 + vertex 0.895459 1.37743 2.62713 + vertex 0.891949 1.3796 2.62535 + endloop + endfacet + facet normal -0.425948 -0.0602463 0.902739 + outer loop + vertex 0.892529 1.37557 2.62535 + vertex 0.891949 1.3796 2.62535 + vertex 0.889109 1.37577 2.62375 + endloop + endfacet + facet normal -0.425939 -0.0598503 0.90277 + outer loop + vertex 0.892529 1.37557 2.62535 + vertex 0.889109 1.37577 2.62375 + vertex 0.891495 1.37152 2.6246 + endloop + endfacet + facet normal -0.419105 -0.0553232 0.906251 + outer loop + vertex 0.891495 1.37152 2.6246 + vertex 0.889109 1.37577 2.62375 + vertex 0.888645 1.37208 2.62331 + endloop + endfacet + facet normal -0.419628 -0.0591058 0.90577 + outer loop + vertex 0.888191 1.36835 2.62286 + vertex 0.891495 1.37152 2.6246 + vertex 0.888645 1.37208 2.62331 + endloop + endfacet + facet normal -0.411205 -0.0605902 0.909527 + outer loop + vertex 0.888191 1.36835 2.62286 + vertex 0.888645 1.37208 2.62331 + vertex 0.885779 1.37252 2.62205 + endloop + endfacet + facet normal -0.411829 -0.0610105 0.909217 + outer loop + vertex 0.884732 1.36851 2.6213 + vertex 0.888191 1.36835 2.62286 + vertex 0.885779 1.37252 2.62205 + endloop + endfacet + facet normal -0.419694 -0.0583219 0.90579 + outer loop + vertex 0.884732 1.36851 2.6213 + vertex 0.885779 1.37252 2.62205 + vertex 0.882743 1.37066 2.62052 + endloop + endfacet + facet normal -0.429593 -0.0694428 0.900349 + outer loop + vertex 0.881599 1.3666 2.61966 + vertex 0.884732 1.36851 2.6213 + vertex 0.882743 1.37066 2.62052 + endloop + endfacet + facet normal -0.442466 -0.0645723 0.894457 + outer loop + vertex 0.882743 1.37066 2.62052 + vertex 0.879692 1.37126 2.61906 + vertex 0.881599 1.3666 2.61966 + endloop + endfacet + facet normal -0.449866 -0.0681222 0.890494 + outer loop + vertex 0.881599 1.3666 2.61966 + vertex 0.879692 1.37126 2.61906 + vertex 0.877621 1.36758 2.61773 + endloop + endfacet + facet normal -0.449708 -0.0671727 0.890646 + outer loop + vertex 0.878669 1.36277 2.61789 + vertex 0.881599 1.3666 2.61966 + vertex 0.877621 1.36758 2.61773 + endloop + endfacet + facet normal -0.464355 -0.0706403 0.882827 + outer loop + vertex 0.878669 1.36277 2.61789 + vertex 0.877621 1.36758 2.61773 + vertex 0.875203 1.36429 2.61619 + endloop + endfacet + facet normal -0.464506 -0.0711183 0.88271 + outer loop + vertex 0.875773 1.35939 2.6161 + vertex 0.878669 1.36277 2.61789 + vertex 0.875203 1.36429 2.61619 + endloop + endfacet + facet normal -0.478338 -0.0725842 0.875171 + outer loop + vertex 0.875203 1.36429 2.61619 + vertex 0.872389 1.36114 2.61439 + vertex 0.875773 1.35939 2.6161 + endloop + endfacet + facet normal -0.478474 -0.0729476 0.875066 + outer loop + vertex 0.872389 1.36114 2.61439 + vertex 0.872819 1.35609 2.61421 + vertex 0.875773 1.35939 2.6161 + endloop + endfacet + facet normal -0.47786 -0.0736553 0.875343 + outer loop + vertex 0.875773 1.35939 2.6161 + vertex 0.872819 1.35609 2.61421 + vertex 0.876159 1.35441 2.61589 + endloop + endfacet + facet normal -0.463308 -0.0728562 0.883198 + outer loop + vertex 0.876159 1.35441 2.61589 + vertex 0.879189 1.35773 2.61775 + vertex 0.875773 1.35939 2.6161 + endloop + endfacet + facet normal -0.461947 -0.0744231 0.883779 + outer loop + vertex 0.879517 1.35274 2.6175 + vertex 0.879189 1.35773 2.61775 + vertex 0.876159 1.35441 2.61589 + endloop + endfacet + facet normal -0.462202 -0.0751243 0.883587 + outer loop + vertex 0.876589 1.3496 2.61571 + vertex 0.879517 1.35274 2.6175 + vertex 0.876159 1.35441 2.61589 + endloop + endfacet + facet normal -0.476794 -0.0761293 0.875712 + outer loop + vertex 0.876159 1.35441 2.61589 + vertex 0.873313 1.35114 2.61406 + vertex 0.876589 1.3496 2.61571 + endloop + endfacet + facet normal -0.477118 -0.0771006 0.875451 + outer loop + vertex 0.873313 1.35114 2.61406 + vertex 0.87417 1.34693 2.61415 + vertex 0.876589 1.3496 2.61571 + endloop + endfacet + facet normal -0.473936 -0.0807974 0.876844 + outer loop + vertex 0.876589 1.3496 2.61571 + vertex 0.87417 1.34693 2.61415 + vertex 0.877008 1.34488 2.6155 + endloop + endfacet + facet normal -0.46056 -0.0799253 0.884023 + outer loop + vertex 0.877008 1.34488 2.6155 + vertex 0.87995 1.34778 2.61729 + vertex 0.876589 1.3496 2.61571 + endloop + endfacet + facet normal -0.458465 -0.0825718 0.884868 + outer loop + vertex 0.880666 1.34243 2.61716 + vertex 0.87995 1.34778 2.61729 + vertex 0.877008 1.34488 2.6155 + endloop + endfacet + facet normal -0.45836 -0.0823654 0.884942 + outer loop + vertex 0.877483 1.34082 2.61537 + vertex 0.880666 1.34243 2.61716 + vertex 0.877008 1.34488 2.6155 + endloop + endfacet + facet normal -0.477574 -0.08427 0.874541 + outer loop + vertex 0.877483 1.34082 2.61537 + vertex 0.877008 1.34488 2.6155 + vertex 0.873642 1.34192 2.61337 + endloop + endfacet + facet normal -0.477755 -0.0852522 0.874347 + outer loop + vertex 0.877483 1.34082 2.61537 + vertex 0.873642 1.34192 2.61337 + vertex 0.876547 1.3366 2.61444 + endloop + endfacet + facet normal -0.466708 -0.0889176 0.87993 + outer loop + vertex 0.876547 1.3366 2.61444 + vertex 0.879551 1.33836 2.61621 + vertex 0.877483 1.34082 2.61537 + endloop + endfacet + facet normal -0.46565 -0.0910671 0.880271 + outer loop + vertex 0.879551 1.33836 2.61621 + vertex 0.876547 1.3366 2.61444 + vertex 0.880208 1.33434 2.61615 + endloop + endfacet + facet normal -0.446992 -0.0881897 0.89018 + outer loop + vertex 0.880208 1.33434 2.61615 + vertex 0.882642 1.33768 2.6177 + vertex 0.879551 1.33836 2.61621 + endloop + endfacet + facet normal -0.446627 -0.0855866 0.890617 + outer loop + vertex 0.879551 1.33836 2.61621 + vertex 0.882642 1.33768 2.6177 + vertex 0.880666 1.34243 2.61716 + endloop + endfacet + facet normal -0.438288 -0.0816108 0.895122 + outer loop + vertex 0.882642 1.33768 2.6177 + vertex 0.884722 1.34143 2.61906 + vertex 0.880666 1.34243 2.61716 + endloop + endfacet + facet normal -0.438444 -0.0825566 0.894959 + outer loop + vertex 0.884722 1.34143 2.61906 + vertex 0.883562 1.34617 2.61893 + vertex 0.880666 1.34243 2.61716 + endloop + endfacet + facet normal -0.428639 -0.088415 0.899139 + outer loop + vertex 0.886681 1.33673 2.61953 + vertex 0.884722 1.34143 2.61906 + vertex 0.882642 1.33768 2.6177 + endloop + endfacet + facet normal -0.428361 -0.0866422 0.899444 + outer loop + vertex 0.883774 1.33287 2.61777 + vertex 0.886681 1.33673 2.61953 + vertex 0.882642 1.33768 2.6177 + endloop + endfacet + facet normal -0.424566 -0.0901589 0.900897 + outer loop + vertex 0.88742 1.33129 2.61933 + vertex 0.886681 1.33673 2.61953 + vertex 0.883774 1.33287 2.61777 + endloop + endfacet + facet normal -0.424169 -0.0889398 0.901205 + outer loop + vertex 0.884425 1.32784 2.61758 + vertex 0.88742 1.33129 2.61933 + vertex 0.883774 1.33287 2.61777 + endloop + endfacet + facet normal -0.42124 -0.0920221 0.902269 + outer loop + vertex 0.887992 1.32624 2.61909 + vertex 0.88742 1.33129 2.61933 + vertex 0.884425 1.32784 2.61758 + endloop + endfacet + facet normal -0.420746 -0.0905592 0.902647 + outer loop + vertex 0.884988 1.32281 2.61734 + vertex 0.887992 1.32624 2.61909 + vertex 0.884425 1.32784 2.61758 + endloop + endfacet + facet normal -0.418285 -0.0931626 0.903525 + outer loop + vertex 0.888635 1.32129 2.61887 + vertex 0.887992 1.32624 2.61909 + vertex 0.884988 1.32281 2.61734 + endloop + endfacet + facet normal -0.41802 -0.0923187 0.903735 + outer loop + vertex 0.885691 1.31745 2.61712 + vertex 0.888635 1.32129 2.61887 + vertex 0.884988 1.32281 2.61734 + endloop + endfacet + facet normal -0.415709 -0.094479 0.904577 + outer loop + vertex 0.889737 1.31657 2.61889 + vertex 0.888635 1.32129 2.61887 + vertex 0.885691 1.31745 2.61712 + endloop + endfacet + facet normal -0.415847 -0.0954459 0.904412 + outer loop + vertex 0.887618 1.31278 2.61751 + vertex 0.889737 1.31657 2.61889 + vertex 0.885691 1.31745 2.61712 + endloop + endfacet + facet normal -0.422883 -0.0986544 0.900798 + outer loop + vertex 0.884532 1.31339 2.61613 + vertex 0.887618 1.31278 2.61751 + vertex 0.885691 1.31745 2.61712 + endloop + endfacet + facet normal -0.432126 -0.0950393 0.896791 + outer loop + vertex 0.884532 1.31339 2.61613 + vertex 0.885691 1.31745 2.61712 + vertex 0.882662 1.31571 2.61548 + endloop + endfacet + facet normal -0.44449 -0.107135 0.889354 + outer loop + vertex 0.881591 1.31168 2.61446 + vertex 0.884532 1.31339 2.61613 + vertex 0.882662 1.31571 2.61548 + endloop + endfacet + facet normal -0.456823 -0.102408 0.883643 + outer loop + vertex 0.882662 1.31571 2.61548 + vertex 0.879683 1.31641 2.61402 + vertex 0.881591 1.31168 2.61446 + endloop + endfacet + facet normal -0.46452 -0.105927 0.879205 + outer loop + vertex 0.881591 1.31168 2.61446 + vertex 0.879683 1.31641 2.61402 + vertex 0.877684 1.31275 2.61252 + endloop + endfacet + facet normal -0.464236 -0.104249 0.879555 + outer loop + vertex 0.878928 1.30795 2.61261 + vertex 0.881591 1.31168 2.61446 + vertex 0.877684 1.31275 2.61252 + endloop + endfacet + facet normal -0.479155 -0.108277 0.871026 + outer loop + vertex 0.878928 1.30795 2.61261 + vertex 0.877684 1.31275 2.61252 + vertex 0.87548 1.30949 2.6109 + endloop + endfacet + facet normal -0.478328 -0.105551 0.871815 + outer loop + vertex 0.876439 1.30478 2.61086 + vertex 0.878928 1.30795 2.61261 + vertex 0.87548 1.30949 2.6109 + endloop + endfacet + facet normal -0.49391 -0.108634 0.8627 + outer loop + vertex 0.87548 1.30949 2.6109 + vertex 0.873101 1.3064 2.60915 + vertex 0.876439 1.30478 2.61086 + endloop + endfacet + facet normal -0.492658 -0.104796 0.86389 + outer loop + vertex 0.873101 1.3064 2.60915 + vertex 0.874234 1.30211 2.60928 + vertex 0.876439 1.30478 2.61086 + endloop + endfacet + facet normal -0.488094 -0.109733 0.865865 + outer loop + vertex 0.876439 1.30478 2.61086 + vertex 0.874234 1.30211 2.60928 + vertex 0.877092 1.29998 2.61062 + endloop + endfacet + facet normal -0.472423 -0.108042 0.874725 + outer loop + vertex 0.877092 1.29998 2.61062 + vertex 0.879862 1.3029 2.61247 + vertex 0.876439 1.30478 2.61086 + endloop + endfacet + facet normal -0.469479 -0.111561 0.875867 + outer loop + vertex 0.880721 1.29747 2.61224 + vertex 0.879862 1.3029 2.61247 + vertex 0.877092 1.29998 2.61062 + endloop + endfacet + facet normal -0.467795 -0.108285 0.877179 + outer loop + vertex 0.877583 1.29586 2.61037 + vertex 0.880721 1.29747 2.61224 + vertex 0.877092 1.29998 2.61062 + endloop + endfacet + facet normal -0.490856 -0.110251 0.864237 + outer loop + vertex 0.877583 1.29586 2.61037 + vertex 0.877092 1.29998 2.61062 + vertex 0.873787 1.29702 2.60836 + endloop + endfacet + facet normal -0.49116 -0.111917 0.86385 + outer loop + vertex 0.877583 1.29586 2.61037 + vertex 0.873787 1.29702 2.60836 + vertex 0.876679 1.29166 2.60931 + endloop + endfacet + facet normal -0.476206 -0.117064 0.871507 + outer loop + vertex 0.876679 1.29166 2.60931 + vertex 0.879614 1.29339 2.61115 + vertex 0.877583 1.29586 2.61037 + endloop + endfacet + facet normal -0.46777 -0.108341 0.877185 + outer loop + vertex 0.879614 1.29339 2.61115 + vertex 0.880721 1.29747 2.61224 + vertex 0.877583 1.29586 2.61037 + endloop + endfacet + facet normal -0.454291 -0.11371 0.883566 + outer loop + vertex 0.879614 1.29339 2.61115 + vertex 0.882674 1.29273 2.61264 + vertex 0.880721 1.29747 2.61224 + endloop + endfacet + facet normal -0.448708 -0.111144 0.88674 + outer loop + vertex 0.882674 1.29273 2.61264 + vertex 0.884741 1.29645 2.61415 + vertex 0.880721 1.29747 2.61224 + endloop + endfacet + facet normal -0.448982 -0.112904 0.886379 + outer loop + vertex 0.884741 1.29645 2.61415 + vertex 0.883522 1.30121 2.61414 + vertex 0.880721 1.29747 2.61224 + endloop + endfacet + facet normal -0.436832 -0.109774 0.89282 + outer loop + vertex 0.883522 1.30121 2.61414 + vertex 0.884741 1.29645 2.61415 + vertex 0.887139 1.29975 2.61573 + endloop + endfacet + facet normal -0.43723 -0.111169 0.892452 + outer loop + vertex 0.886202 1.30458 2.61587 + vertex 0.883522 1.30121 2.61414 + vertex 0.887139 1.29975 2.61573 + endloop + endfacet + facet normal -0.424751 -0.108926 0.898733 + outer loop + vertex 0.887139 1.29975 2.61573 + vertex 0.889886 1.30295 2.61741 + vertex 0.886202 1.30458 2.61587 + endloop + endfacet + facet normal -0.42446 -0.108033 0.898978 + outer loop + vertex 0.889886 1.30295 2.61741 + vertex 0.888896 1.308 2.61755 + vertex 0.886202 1.30458 2.61587 + endloop + endfacet + facet normal -0.424527 -0.107969 0.898955 + outer loop + vertex 0.886202 1.30458 2.61587 + vertex 0.888896 1.308 2.61755 + vertex 0.885231 1.30943 2.61599 + endloop + endfacet + facet normal -0.439553 -0.110785 0.891358 + outer loop + vertex 0.885231 1.30943 2.61599 + vertex 0.882549 1.30626 2.61428 + vertex 0.886202 1.30458 2.61587 + endloop + endfacet + facet normal -0.442921 -0.107261 0.890121 + outer loop + vertex 0.881591 1.31168 2.61446 + vertex 0.882549 1.30626 2.61428 + vertex 0.885231 1.30943 2.61599 + endloop + endfacet + facet normal -0.423846 -0.105543 0.899564 + outer loop + vertex 0.888896 1.308 2.61755 + vertex 0.887618 1.31278 2.61751 + vertex 0.885231 1.30943 2.61599 + endloop + endfacet + facet normal -0.414053 -0.102883 0.90442 + outer loop + vertex 0.888896 1.308 2.61755 + vertex 0.891704 1.31191 2.61928 + vertex 0.887618 1.31278 2.61751 + endloop + endfacet + facet normal -0.415873 -0.101284 0.903765 + outer loop + vertex 0.892662 1.30647 2.61912 + vertex 0.891704 1.31191 2.61928 + vertex 0.888896 1.308 2.61755 + endloop + endfacet + facet normal -0.423944 -0.102582 0.89986 + outer loop + vertex 0.891704 1.31191 2.61928 + vertex 0.892662 1.30647 2.61912 + vertex 0.895412 1.30971 2.62078 + endloop + endfacet + facet normal -0.419805 -0.0936532 0.90277 + outer loop + vertex 0.894737 1.31371 2.62088 + vertex 0.891704 1.31191 2.61928 + vertex 0.895412 1.30971 2.62078 + endloop + endfacet + facet normal -0.453174 -0.0988508 0.885924 + outer loop + vertex 0.895412 1.30971 2.62078 + vertex 0.897824 1.31295 2.62238 + vertex 0.894737 1.31371 2.62088 + endloop + endfacet + facet normal -0.451984 -0.0912844 0.887343 + outer loop + vertex 0.894737 1.31371 2.62088 + vertex 0.897824 1.31295 2.62238 + vertex 0.89588 1.31769 2.62187 + endloop + endfacet + facet normal -0.427927 -0.100896 0.898164 + outer loop + vertex 0.894737 1.31371 2.62088 + vertex 0.89588 1.31769 2.62187 + vertex 0.892824 1.31601 2.62023 + endloop + endfacet + facet normal -0.430328 -0.0959396 0.89756 + outer loop + vertex 0.892824 1.31601 2.62023 + vertex 0.89588 1.31769 2.62187 + vertex 0.89223 1.31992 2.62036 + endloop + endfacet + facet normal -0.410982 -0.093314 0.906855 + outer loop + vertex 0.892824 1.31601 2.62023 + vertex 0.89223 1.31992 2.62036 + vertex 0.889737 1.31657 2.61889 + endloop + endfacet + facet normal -0.411329 -0.0963387 0.906381 + outer loop + vertex 0.892824 1.31601 2.62023 + vertex 0.889737 1.31657 2.61889 + vertex 0.891704 1.31191 2.61928 + endloop + endfacet + facet normal -0.410935 -0.0933561 0.906872 + outer loop + vertex 0.888635 1.32129 2.61887 + vertex 0.889737 1.31657 2.61889 + vertex 0.89223 1.31992 2.62036 + endloop + endfacet + facet normal -0.41052 -0.0918995 0.907209 + outer loop + vertex 0.891554 1.3247 2.62054 + vertex 0.888635 1.32129 2.61887 + vertex 0.89223 1.31992 2.62036 + endloop + endfacet + facet normal -0.423342 -0.0934874 0.901134 + outer loop + vertex 0.89223 1.31992 2.62036 + vertex 0.895103 1.32301 2.62203 + vertex 0.891554 1.3247 2.62054 + endloop + endfacet + facet normal -0.42247 -0.091069 0.90179 + outer loop + vertex 0.895103 1.32301 2.62203 + vertex 0.89452 1.32801 2.62226 + vertex 0.891554 1.3247 2.62054 + endloop + endfacet + facet normal -0.420045 -0.0936908 0.902654 + outer loop + vertex 0.891554 1.3247 2.62054 + vertex 0.89452 1.32801 2.62226 + vertex 0.891 1.32963 2.62079 + endloop + endfacet + facet normal -0.410344 -0.0928356 0.907193 + outer loop + vertex 0.891 1.32963 2.62079 + vertex 0.887992 1.32624 2.61909 + vertex 0.891554 1.3247 2.62054 + endloop + endfacet + facet normal -0.419291 -0.0915383 0.903225 + outer loop + vertex 0.89452 1.32801 2.62226 + vertex 0.893897 1.33307 2.62249 + vertex 0.891 1.32963 2.62079 + endloop + endfacet + facet normal -0.418966 -0.0918694 0.903342 + outer loop + vertex 0.891 1.32963 2.62079 + vertex 0.893897 1.33307 2.62249 + vertex 0.890331 1.33453 2.62098 + endloop + endfacet + facet normal -0.411851 -0.0910268 0.906694 + outer loop + vertex 0.890331 1.33453 2.62098 + vertex 0.88742 1.33129 2.61933 + vertex 0.891 1.32963 2.62079 + endloop + endfacet + facet normal -0.416828 -0.0849237 0.90501 + outer loop + vertex 0.893897 1.33307 2.62249 + vertex 0.892804 1.33795 2.62244 + vertex 0.890331 1.33453 2.62098 + endloop + endfacet + facet normal -0.414028 -0.0873963 0.906059 + outer loop + vertex 0.890331 1.33453 2.62098 + vertex 0.892804 1.33795 2.62244 + vertex 0.889733 1.33855 2.6211 + endloop + endfacet + facet normal -0.413069 -0.0872666 0.906509 + outer loop + vertex 0.889733 1.33855 2.6211 + vertex 0.886681 1.33673 2.61953 + vertex 0.890331 1.33453 2.62098 + endloop + endfacet + facet normal -0.41325 -0.0869217 0.90646 + outer loop + vertex 0.886681 1.33673 2.61953 + vertex 0.889733 1.33855 2.6211 + vertex 0.887811 1.34085 2.62044 + endloop + endfacet + facet normal -0.4076 -0.0812997 0.909534 + outer loop + vertex 0.889733 1.33855 2.6211 + vertex 0.890853 1.34268 2.62197 + vertex 0.887811 1.34085 2.62044 + endloop + endfacet + facet normal -0.409566 -0.0775674 0.908977 + outer loop + vertex 0.887811 1.34085 2.62044 + vertex 0.890853 1.34268 2.62197 + vertex 0.887166 1.3448 2.62049 + endloop + endfacet + facet normal -0.419426 -0.0791169 0.904335 + outer loop + vertex 0.887811 1.34085 2.62044 + vertex 0.887166 1.3448 2.62049 + vertex 0.884722 1.34143 2.61906 + endloop + endfacet + facet normal -0.420712 -0.0779742 0.903837 + outer loop + vertex 0.883562 1.34617 2.61893 + vertex 0.884722 1.34143 2.61906 + vertex 0.887166 1.3448 2.62049 + endloop + endfacet + facet normal -0.420608 -0.0776091 0.903917 + outer loop + vertex 0.886486 1.34961 2.62058 + vertex 0.883562 1.34617 2.61893 + vertex 0.887166 1.3448 2.62049 + endloop + endfacet + facet normal -0.409829 -0.0761834 0.908975 + outer loop + vertex 0.887166 1.3448 2.62049 + vertex 0.890075 1.34803 2.62207 + vertex 0.886486 1.34961 2.62058 + endloop + endfacet + facet normal -0.409865 -0.0762867 0.908951 + outer loop + vertex 0.890075 1.34803 2.62207 + vertex 0.889617 1.35297 2.62228 + vertex 0.886486 1.34961 2.62058 + endloop + endfacet + facet normal -0.410305 -0.075797 0.908793 + outer loop + vertex 0.886486 1.34961 2.62058 + vertex 0.889617 1.35297 2.62228 + vertex 0.886121 1.35453 2.62083 + endloop + endfacet + facet normal -0.42143 -0.0763652 0.90364 + outer loop + vertex 0.886121 1.35453 2.62083 + vertex 0.882965 1.35112 2.61907 + vertex 0.886486 1.34961 2.62058 + endloop + endfacet + facet normal -0.422414 -0.075263 0.903273 + outer loop + vertex 0.882643 1.3561 2.61933 + vertex 0.882965 1.35112 2.61907 + vertex 0.886121 1.35453 2.62083 + endloop + endfacet + facet normal -0.422365 -0.075119 0.903308 + outer loop + vertex 0.88583 1.35951 2.62111 + vertex 0.882643 1.3561 2.61933 + vertex 0.886121 1.35453 2.62083 + endloop + endfacet + facet normal -0.411497 -0.0747651 0.908339 + outer loop + vertex 0.886121 1.35453 2.62083 + vertex 0.889358 1.3579 2.62257 + vertex 0.88583 1.35951 2.62111 + endloop + endfacet + facet normal -0.411171 -0.0738484 0.908562 + outer loop + vertex 0.889358 1.3579 2.62257 + vertex 0.888973 1.36295 2.62281 + vertex 0.88583 1.35951 2.62111 + endloop + endfacet + facet normal -0.413123 -0.0717107 0.907847 + outer loop + vertex 0.88583 1.35951 2.62111 + vertex 0.888973 1.36295 2.62281 + vertex 0.885323 1.3645 2.62127 + endloop + endfacet + facet normal -0.424895 -0.0727276 0.902316 + outer loop + vertex 0.885323 1.3645 2.62127 + vertex 0.882261 1.36117 2.61956 + vertex 0.88583 1.35951 2.62111 + endloop + endfacet + facet normal -0.428096 -0.0691504 0.901084 + outer loop + vertex 0.881599 1.3666 2.61966 + vertex 0.882261 1.36117 2.61956 + vertex 0.885323 1.3645 2.62127 + endloop + endfacet + facet normal -0.412019 -0.0683559 0.908608 + outer loop + vertex 0.888973 1.36295 2.62281 + vertex 0.888191 1.36835 2.62286 + vertex 0.885323 1.3645 2.62127 + endloop + endfacet + facet normal -0.422658 -0.0698494 0.903593 + outer loop + vertex 0.888973 1.36295 2.62281 + vertex 0.892069 1.36621 2.62451 + vertex 0.888191 1.36835 2.62286 + endloop + endfacet + facet normal -0.421974 -0.0706354 0.903852 + outer loop + vertex 0.892543 1.36109 2.62433 + vertex 0.892069 1.36621 2.62451 + vertex 0.888973 1.36295 2.62281 + endloop + endfacet + facet normal -0.42355 -0.0745251 0.902802 + outer loop + vertex 0.889358 1.3579 2.62257 + vertex 0.892543 1.36109 2.62433 + vertex 0.888973 1.36295 2.62281 + endloop + endfacet + facet normal -0.423493 -0.0745943 0.902823 + outer loop + vertex 0.892823 1.35614 2.62405 + vertex 0.892543 1.36109 2.62433 + vertex 0.889358 1.3579 2.62257 + endloop + endfacet + facet normal -0.424194 -0.0763773 0.902345 + outer loop + vertex 0.889617 1.35297 2.62228 + vertex 0.892823 1.35614 2.62405 + vertex 0.889358 1.3579 2.62257 + endloop + endfacet + facet normal -0.424294 -0.0762562 0.902308 + outer loop + vertex 0.893122 1.35128 2.62378 + vertex 0.892823 1.35614 2.62405 + vertex 0.889617 1.35297 2.62228 + endloop + endfacet + facet normal -0.47366 -0.076004 0.877422 + outer loop + vertex 0.892543 1.36109 2.62433 + vertex 0.892823 1.35614 2.62405 + vertex 0.895907 1.35899 2.62596 + endloop + endfacet + facet normal -0.471715 -0.0717974 0.878823 + outer loop + vertex 0.895546 1.36399 2.62618 + vertex 0.892543 1.36109 2.62433 + vertex 0.895907 1.35899 2.62596 + endloop + endfacet + facet normal -0.55229 -0.0755387 0.830222 + outer loop + vertex 0.895907 1.35899 2.62596 + vertex 0.898714 1.3616 2.62807 + vertex 0.895546 1.36399 2.62618 + endloop + endfacet + facet normal -0.550649 -0.0722645 0.831603 + outer loop + vertex 0.898714 1.3616 2.62807 + vertex 0.898302 1.36673 2.62824 + vertex 0.895546 1.36399 2.62618 + endloop + endfacet + facet normal -0.549957 -0.0732399 0.831975 + outer loop + vertex 0.895546 1.36399 2.62618 + vertex 0.898302 1.36673 2.62824 + vertex 0.895044 1.36906 2.62629 + endloop + endfacet + facet normal -0.465966 -0.0660683 0.882333 + outer loop + vertex 0.895044 1.36906 2.62629 + vertex 0.892069 1.36621 2.62451 + vertex 0.895546 1.36399 2.62618 + endloop + endfacet + facet normal -0.46661 -0.0652218 0.882055 + outer loop + vertex 0.891495 1.37152 2.6246 + vertex 0.892069 1.36621 2.62451 + vertex 0.895044 1.36906 2.62629 + endloop + endfacet + facet normal -0.45942 -0.0516428 0.886717 + outer loop + vertex 0.894513 1.37325 2.62626 + vertex 0.891495 1.37152 2.6246 + vertex 0.895044 1.36906 2.62629 + endloop + endfacet + facet normal -0.545741 -0.0629563 0.835585 + outer loop + vertex 0.895044 1.36906 2.62629 + vertex 0.897731 1.37243 2.6283 + vertex 0.894513 1.37325 2.62626 + endloop + endfacet + facet normal -0.544044 -0.0516591 0.837465 + outer loop + vertex 0.894513 1.37325 2.62626 + vertex 0.897731 1.37243 2.6283 + vertex 0.895459 1.37743 2.62713 + endloop + endfacet + facet normal -0.483902 -0.0724891 0.872115 + outer loop + vertex 0.894513 1.37325 2.62626 + vertex 0.895459 1.37743 2.62713 + vertex 0.892529 1.37557 2.62535 + endloop + endfacet + facet normal -0.567879 -0.0664604 0.820425 + outer loop + vertex 0.897731 1.37243 2.6283 + vertex 0.898553 1.37689 2.62923 + vertex 0.895459 1.37743 2.62713 + endloop + endfacet + facet normal -0.567192 -0.0581774 0.821528 + outer loop + vertex 0.898553 1.37689 2.62923 + vertex 0.897928 1.38111 2.6291 + vertex 0.895459 1.37743 2.62713 + endloop + endfacet + facet normal -0.557318 -0.0679921 0.827511 + outer loop + vertex 0.895459 1.37743 2.62713 + vertex 0.897928 1.38111 2.6291 + vertex 0.894815 1.38284 2.62715 + endloop + endfacet + facet normal -0.556187 -0.0648111 0.828526 + outer loop + vertex 0.897928 1.38111 2.6291 + vertex 0.89756 1.38612 2.62925 + vertex 0.894815 1.38284 2.62715 + endloop + endfacet + facet normal -0.461272 -0.0476986 0.885976 + outer loop + vertex 0.891495 1.37152 2.6246 + vertex 0.894513 1.37325 2.62626 + vertex 0.892529 1.37557 2.62535 + endloop + endfacet + facet normal -0.545291 -0.0634671 0.83584 + outer loop + vertex 0.898302 1.36673 2.62824 + vertex 0.897731 1.37243 2.6283 + vertex 0.895044 1.36906 2.62629 + endloop + endfacet + facet normal -0.556062 -0.0698573 0.8282 + outer loop + vertex 0.899136 1.35661 2.62793 + vertex 0.898714 1.3616 2.62807 + vertex 0.895907 1.35899 2.62596 + endloop + endfacet + facet normal -0.558962 -0.0758284 0.825719 + outer loop + vertex 0.896239 1.35405 2.62574 + vertex 0.899136 1.35661 2.62793 + vertex 0.895907 1.35899 2.62596 + endloop + endfacet + facet normal -0.560756 -0.0729654 0.82476 + outer loop + vertex 0.899866 1.35118 2.62795 + vertex 0.899136 1.35661 2.62793 + vertex 0.896239 1.35405 2.62574 + endloop + endfacet + facet normal -0.568172 -0.0873162 0.818265 + outer loop + vertex 0.896529 1.34933 2.62543 + vertex 0.899866 1.35118 2.62795 + vertex 0.896239 1.35405 2.62574 + endloop + endfacet + facet normal -0.473501 -0.085239 0.876659 + outer loop + vertex 0.896239 1.35405 2.62574 + vertex 0.893122 1.35128 2.62378 + vertex 0.896529 1.34933 2.62543 + endloop + endfacet + facet normal -0.473248 -0.0846317 0.876854 + outer loop + vertex 0.893122 1.35128 2.62378 + vertex 0.893714 1.34646 2.62364 + vertex 0.896529 1.34933 2.62543 + endloop + endfacet + facet normal -0.470921 -0.0875164 0.877824 + outer loop + vertex 0.896529 1.34933 2.62543 + vertex 0.893714 1.34646 2.62364 + vertex 0.897109 1.34489 2.6253 + endloop + endfacet + facet normal -0.542266 -0.0955394 0.834757 + outer loop + vertex 0.897109 1.34489 2.6253 + vertex 0.899243 1.34705 2.62694 + vertex 0.896529 1.34933 2.62543 + endloop + endfacet + facet normal -0.554549 -0.0786282 0.828428 + outer loop + vertex 0.900361 1.34263 2.62726 + vertex 0.899243 1.34705 2.62694 + vertex 0.897109 1.34489 2.6253 + endloop + endfacet + facet normal -0.565147 -0.102388 0.818612 + outer loop + vertex 0.897836 1.34109 2.62533 + vertex 0.900361 1.34263 2.62726 + vertex 0.897109 1.34489 2.6253 + endloop + endfacet + facet normal -0.476713 -0.0850345 0.874936 + outer loop + vertex 0.897836 1.34109 2.62533 + vertex 0.897109 1.34489 2.6253 + vertex 0.894874 1.34177 2.62378 + endloop + endfacet + facet normal -0.476672 -0.0847361 0.874988 + outer loop + vertex 0.897836 1.34109 2.62533 + vertex 0.894874 1.34177 2.62378 + vertex 0.896772 1.33692 2.62435 + endloop + endfacet + facet normal -0.446322 -0.0708636 0.892062 + outer loop + vertex 0.896772 1.33692 2.62435 + vertex 0.894874 1.34177 2.62378 + vertex 0.892804 1.33795 2.62244 + endloop + endfacet + facet normal -0.425585 -0.0852072 0.900898 + outer loop + vertex 0.892804 1.33795 2.62244 + vertex 0.894874 1.34177 2.62378 + vertex 0.890853 1.34268 2.62197 + endloop + endfacet + facet normal -0.424376 -0.0772895 0.902181 + outer loop + vertex 0.894874 1.34177 2.62378 + vertex 0.893714 1.34646 2.62364 + vertex 0.890853 1.34268 2.62197 + endloop + endfacet + facet normal -0.422864 -0.078694 0.90277 + outer loop + vertex 0.890853 1.34268 2.62197 + vertex 0.893714 1.34646 2.62364 + vertex 0.890075 1.34803 2.62207 + endloop + endfacet + facet normal -0.471653 -0.0897613 0.877204 + outer loop + vertex 0.893714 1.34646 2.62364 + vertex 0.894874 1.34177 2.62378 + vertex 0.897109 1.34489 2.6253 + endloop + endfacet + facet normal -0.423046 -0.0792476 0.902636 + outer loop + vertex 0.893714 1.34646 2.62364 + vertex 0.893122 1.35128 2.62378 + vertex 0.890075 1.34803 2.62207 + endloop + endfacet + facet normal -0.478584 -0.0780573 0.874565 + outer loop + vertex 0.892823 1.35614 2.62405 + vertex 0.893122 1.35128 2.62378 + vertex 0.896239 1.35405 2.62574 + endloop + endfacet + facet normal -0.554987 -0.118138 0.823427 + outer loop + vertex 0.899243 1.34705 2.62694 + vertex 0.899866 1.35118 2.62795 + vertex 0.896529 1.34933 2.62543 + endloop + endfacet + facet normal -0.469861 -0.074224 0.879614 + outer loop + vertex 0.892069 1.36621 2.62451 + vertex 0.892543 1.36109 2.62433 + vertex 0.895546 1.36399 2.62618 + endloop + endfacet + facet normal -0.476143 -0.0726068 0.876365 + outer loop + vertex 0.895907 1.35899 2.62596 + vertex 0.892823 1.35614 2.62405 + vertex 0.896239 1.35405 2.62574 + endloop + endfacet + facet normal -0.424776 -0.0723938 0.902399 + outer loop + vertex 0.882261 1.36117 2.61956 + vertex 0.882643 1.3561 2.61933 + vertex 0.88583 1.35951 2.62111 + endloop + endfacet + facet normal -0.443388 -0.0733856 0.89332 + outer loop + vertex 0.882643 1.3561 2.61933 + vertex 0.882261 1.36117 2.61956 + vertex 0.879189 1.35773 2.61775 + endloop + endfacet + facet normal -0.443493 -0.0736812 0.893244 + outer loop + vertex 0.879517 1.35274 2.6175 + vertex 0.882643 1.3561 2.61933 + vertex 0.879189 1.35773 2.61775 + endloop + endfacet + facet normal -0.44556 -0.0709815 0.892434 + outer loop + vertex 0.879189 1.35773 2.61775 + vertex 0.882261 1.36117 2.61956 + vertex 0.878669 1.36277 2.61789 + endloop + endfacet + facet normal -0.441469 -0.0760069 0.894051 + outer loop + vertex 0.882965 1.35112 2.61907 + vertex 0.882643 1.3561 2.61933 + vertex 0.879517 1.35274 2.6175 + endloop + endfacet + facet normal -0.441745 -0.076789 0.893848 + outer loop + vertex 0.87995 1.34778 2.61729 + vertex 0.882965 1.35112 2.61907 + vertex 0.879517 1.35274 2.6175 + endloop + endfacet + facet normal -0.440084 -0.0786383 0.894507 + outer loop + vertex 0.883562 1.34617 2.61893 + vertex 0.882965 1.35112 2.61907 + vertex 0.87995 1.34778 2.61729 + endloop + endfacet + facet normal -0.410388 -0.0760359 0.908736 + outer loop + vertex 0.889617 1.35297 2.62228 + vertex 0.889358 1.3579 2.62257 + vertex 0.886121 1.35453 2.62083 + endloop + endfacet + facet normal -0.424705 -0.0773685 0.90202 + outer loop + vertex 0.890075 1.34803 2.62207 + vertex 0.893122 1.35128 2.62378 + vertex 0.889617 1.35297 2.62228 + endloop + endfacet + facet normal -0.421527 -0.0766587 0.90357 + outer loop + vertex 0.882965 1.35112 2.61907 + vertex 0.883562 1.34617 2.61893 + vertex 0.886486 1.34961 2.62058 + endloop + endfacet + facet normal -0.409228 -0.0768326 0.909192 + outer loop + vertex 0.890853 1.34268 2.62197 + vertex 0.890075 1.34803 2.62207 + vertex 0.887166 1.3448 2.62049 + endloop + endfacet + facet normal -0.41298 -0.079361 0.907276 + outer loop + vertex 0.889733 1.33855 2.6211 + vertex 0.892804 1.33795 2.62244 + vertex 0.890853 1.34268 2.62197 + endloop + endfacet + facet normal -0.450083 -0.0925299 0.88818 + outer loop + vertex 0.893897 1.33307 2.62249 + vertex 0.896772 1.33692 2.62435 + vertex 0.892804 1.33795 2.62244 + endloop + endfacet + facet normal -0.456574 -0.0863805 0.885482 + outer loop + vertex 0.897424 1.33129 2.62413 + vertex 0.896772 1.33692 2.62435 + vertex 0.893897 1.33307 2.62249 + endloop + endfacet + facet normal -0.459983 -0.0956379 0.882762 + outer loop + vertex 0.89452 1.32801 2.62226 + vertex 0.897424 1.33129 2.62413 + vertex 0.893897 1.33307 2.62249 + endloop + endfacet + facet normal -0.462669 -0.0926449 0.881677 + outer loop + vertex 0.897959 1.32618 2.62388 + vertex 0.897424 1.33129 2.62413 + vertex 0.89452 1.32801 2.62226 + endloop + endfacet + facet normal -0.463535 -0.094895 0.880983 + outer loop + vertex 0.895103 1.32301 2.62203 + vertex 0.897959 1.32618 2.62388 + vertex 0.89452 1.32801 2.62226 + endloop + endfacet + facet normal -0.469323 -0.0883043 0.8786 + outer loop + vertex 0.898689 1.32123 2.62377 + vertex 0.897959 1.32618 2.62388 + vertex 0.895103 1.32301 2.62203 + endloop + endfacet + facet normal -0.471699 -0.0950356 0.876623 + outer loop + vertex 0.89588 1.31769 2.62187 + vertex 0.898689 1.32123 2.62377 + vertex 0.895103 1.32301 2.62203 + endloop + endfacet + facet normal -0.48185 -0.0846047 0.87216 + outer loop + vertex 0.899962 1.31641 2.624 + vertex 0.898689 1.32123 2.62377 + vertex 0.89588 1.31769 2.62187 + endloop + endfacet + facet normal -0.427144 -0.0892208 0.899771 + outer loop + vertex 0.89588 1.31769 2.62187 + vertex 0.895103 1.32301 2.62203 + vertex 0.89223 1.31992 2.62036 + endloop + endfacet + facet normal -0.486411 -0.107536 0.867087 + outer loop + vertex 0.897824 1.31295 2.62238 + vertex 0.899962 1.31641 2.624 + vertex 0.89588 1.31769 2.62187 + endloop + endfacet + facet normal -0.457601 -0.0946596 0.884105 + outer loop + vertex 0.898984 1.30812 2.62246 + vertex 0.897824 1.31295 2.62238 + vertex 0.895412 1.30971 2.62078 + endloop + endfacet + facet normal -0.46179 -0.107982 0.880392 + outer loop + vertex 0.896314 1.30481 2.62065 + vertex 0.898984 1.30812 2.62246 + vertex 0.895412 1.30971 2.62078 + endloop + endfacet + facet normal -0.463468 -0.106258 0.87972 + outer loop + vertex 0.899809 1.30305 2.62228 + vertex 0.898984 1.30812 2.62246 + vertex 0.896314 1.30481 2.62065 + endloop + endfacet + facet normal -0.46632 -0.114257 0.877207 + outer loop + vertex 0.897178 1.29994 2.62048 + vertex 0.899809 1.30305 2.62228 + vertex 0.896314 1.30481 2.62065 + endloop + endfacet + facet normal -0.427558 -0.108104 0.897501 + outer loop + vertex 0.896314 1.30481 2.62065 + vertex 0.893612 1.3014 2.61895 + vertex 0.897178 1.29994 2.62048 + endloop + endfacet + facet normal -0.42868 -0.111892 0.896501 + outer loop + vertex 0.893612 1.3014 2.61895 + vertex 0.894803 1.29663 2.61893 + vertex 0.897178 1.29994 2.62048 + endloop + endfacet + facet normal -0.42889 -0.111706 0.896424 + outer loop + vertex 0.89783 1.29595 2.62029 + vertex 0.897178 1.29994 2.62048 + vertex 0.894803 1.29663 2.61893 + endloop + endfacet + facet normal -0.428569 -0.109373 0.896865 + outer loop + vertex 0.89783 1.29595 2.62029 + vertex 0.894803 1.29663 2.61893 + vertex 0.896759 1.29187 2.61928 + endloop + endfacet + facet normal -0.45846 -0.0981716 0.883276 + outer loop + vertex 0.896759 1.29187 2.61928 + vertex 0.899797 1.2935 2.62104 + vertex 0.89783 1.29595 2.62029 + endloop + endfacet + facet normal -0.478291 -0.11804 0.870232 + outer loop + vertex 0.899797 1.2935 2.62104 + vertex 0.900667 1.29764 2.62208 + vertex 0.89783 1.29595 2.62029 + endloop + endfacet + facet normal -0.532949 -0.0990597 0.840329 + outer loop + vertex 0.899797 1.2935 2.62104 + vertex 0.903202 1.29253 2.62309 + vertex 0.900667 1.29764 2.62208 + endloop + endfacet + facet normal -0.548367 -0.108906 0.829116 + outer loop + vertex 0.903202 1.29253 2.62309 + vertex 0.903809 1.29701 2.62408 + vertex 0.900667 1.29764 2.62208 + endloop + endfacet + facet normal -0.54806 -0.105251 0.829791 + outer loop + vertex 0.903809 1.29701 2.62408 + vertex 0.903054 1.30124 2.62411 + vertex 0.900667 1.29764 2.62208 + endloop + endfacet + facet normal -0.536763 -0.116095 0.835708 + outer loop + vertex 0.900667 1.29764 2.62208 + vertex 0.903054 1.30124 2.62411 + vertex 0.899809 1.30305 2.62228 + endloop + endfacet + facet normal -0.533364 -0.106541 0.839149 + outer loop + vertex 0.903054 1.30124 2.62411 + vertex 0.90241 1.30623 2.62434 + vertex 0.899809 1.30305 2.62228 + endloop + endfacet + facet normal -0.525761 -0.115131 0.842805 + outer loop + vertex 0.899809 1.30305 2.62228 + vertex 0.90241 1.30623 2.62434 + vertex 0.898984 1.30812 2.62246 + endloop + endfacet + facet normal -0.521179 -0.102318 0.847292 + outer loop + vertex 0.90241 1.30623 2.62434 + vertex 0.901759 1.31149 2.62457 + vertex 0.898984 1.30812 2.62246 + endloop + endfacet + facet normal -0.515143 -0.109062 0.850137 + outer loop + vertex 0.898984 1.30812 2.62246 + vertex 0.901759 1.31149 2.62457 + vertex 0.897824 1.31295 2.62238 + endloop + endfacet + facet normal -0.510198 -0.0874349 0.855601 + outer loop + vertex 0.901759 1.31149 2.62457 + vertex 0.899962 1.31641 2.624 + vertex 0.897824 1.31295 2.62238 + endloop + endfacet + facet normal -0.535053 -0.113068 0.837218 + outer loop + vertex 0.900567 1.28925 2.62096 + vertex 0.903202 1.29253 2.62309 + vertex 0.899797 1.2935 2.62104 + endloop + endfacet + facet normal -0.538946 -0.108703 0.835297 + outer loop + vertex 0.904558 1.28629 2.62315 + vertex 0.903202 1.29253 2.62309 + vertex 0.900567 1.28925 2.62096 + endloop + endfacet + facet normal -0.550135 -0.131754 0.824617 + outer loop + vertex 0.901335 1.28437 2.62069 + vertex 0.904558 1.28629 2.62315 + vertex 0.900567 1.28925 2.62096 + endloop + endfacet + facet normal -0.461152 -0.12071 0.879072 + outer loop + vertex 0.900567 1.28925 2.62096 + vertex 0.897702 1.28643 2.61907 + vertex 0.901335 1.28437 2.62069 + endloop + endfacet + facet normal -0.460771 -0.119778 0.8794 + outer loop + vertex 0.897702 1.28643 2.61907 + vertex 0.898645 1.28148 2.61889 + vertex 0.901335 1.28437 2.62069 + endloop + endfacet + facet normal -0.456933 -0.124213 0.880785 + outer loop + vertex 0.901335 1.28437 2.62069 + vertex 0.898645 1.28148 2.61889 + vertex 0.902109 1.27993 2.62047 + endloop + endfacet + facet normal -0.522909 -0.133733 0.841832 + outer loop + vertex 0.902109 1.27993 2.62047 + vertex 0.904203 1.28207 2.62211 + vertex 0.901335 1.28437 2.62069 + endloop + endfacet + facet normal -0.539626 -0.111687 0.834464 + outer loop + vertex 0.905404 1.2777 2.6223 + vertex 0.904203 1.28207 2.62211 + vertex 0.902109 1.27993 2.62047 + endloop + endfacet + facet normal -0.546871 -0.128236 0.827337 + outer loop + vertex 0.902833 1.27619 2.62037 + vertex 0.905404 1.2777 2.6223 + vertex 0.902109 1.27993 2.62047 + endloop + endfacet + facet normal -0.45903 -0.112678 0.881246 + outer loop + vertex 0.902833 1.27619 2.62037 + vertex 0.902109 1.27993 2.62047 + vertex 0.899851 1.27682 2.61889 + endloop + endfacet + facet normal -0.457584 -0.10074 0.883441 + outer loop + vertex 0.902833 1.27619 2.62037 + vertex 0.899851 1.27682 2.61889 + vertex 0.901726 1.27204 2.61932 + endloop + endfacet + facet normal -0.435426 -0.0909632 0.895617 + outer loop + vertex 0.901726 1.27204 2.61932 + vertex 0.899851 1.27682 2.61889 + vertex 0.89772 1.27301 2.61747 + endloop + endfacet + facet normal -0.43763 -0.105178 0.892983 + outer loop + vertex 0.898873 1.26816 2.61746 + vertex 0.901726 1.27204 2.61932 + vertex 0.89772 1.27301 2.61747 + endloop + endfacet + facet normal -0.417652 -0.100439 0.903039 + outer loop + vertex 0.898873 1.26816 2.61746 + vertex 0.89772 1.27301 2.61747 + vertex 0.895263 1.26958 2.61595 + endloop + endfacet + facet normal -0.419546 -0.106984 0.901408 + outer loop + vertex 0.89615 1.26472 2.61579 + vertex 0.898873 1.26816 2.61746 + vertex 0.895263 1.26958 2.61595 + endloop + endfacet + facet normal -0.424595 -0.107823 0.89894 + outer loop + vertex 0.895263 1.26958 2.61595 + vertex 0.892523 1.26635 2.61427 + vertex 0.89615 1.26472 2.61579 + endloop + endfacet + facet normal -0.426596 -0.113846 0.897249 + outer loop + vertex 0.892523 1.26635 2.61427 + vertex 0.893479 1.26133 2.61409 + vertex 0.89615 1.26472 2.61579 + endloop + endfacet + facet normal -0.423772 -0.116565 0.898237 + outer loop + vertex 0.89615 1.26472 2.61579 + vertex 0.893479 1.26133 2.61409 + vertex 0.897078 1.2599 2.6156 + endloop + endfacet + facet normal -0.424809 -0.116744 0.897724 + outer loop + vertex 0.897078 1.2599 2.6156 + vertex 0.899784 1.26304 2.61729 + vertex 0.89615 1.26472 2.61579 + endloop + endfacet + facet normal -0.424948 -0.116599 0.897677 + outer loop + vertex 0.900757 1.25763 2.61705 + vertex 0.899784 1.26304 2.61729 + vertex 0.897078 1.2599 2.6156 + endloop + endfacet + facet normal -0.466527 -0.123101 0.875899 + outer loop + vertex 0.900757 1.25763 2.61705 + vertex 0.903467 1.26122 2.619 + vertex 0.899784 1.26304 2.61729 + endloop + endfacet + facet normal -0.459888 -0.104102 0.881853 + outer loop + vertex 0.903467 1.26122 2.619 + vertex 0.902526 1.2664 2.61912 + vertex 0.899784 1.26304 2.61729 + endloop + endfacet + facet normal -0.453356 -0.11081 0.884415 + outer loop + vertex 0.899784 1.26304 2.61729 + vertex 0.902526 1.2664 2.61912 + vertex 0.898873 1.26816 2.61746 + endloop + endfacet + facet normal -0.473254 -0.116546 0.873183 + outer loop + vertex 0.904865 1.2563 2.6191 + vertex 0.903467 1.26122 2.619 + vertex 0.900757 1.25763 2.61705 + endloop + endfacet + facet normal -0.479655 -0.149553 0.864618 + outer loop + vertex 0.90285 1.2529 2.61739 + vertex 0.904865 1.2563 2.6191 + vertex 0.900757 1.25763 2.61705 + endloop + endfacet + facet normal -0.446078 -0.133198 0.885027 + outer loop + vertex 0.899748 1.2537 2.61595 + vertex 0.90285 1.2529 2.61739 + vertex 0.900757 1.25763 2.61705 + endloop + endfacet + facet normal -0.425394 -0.141015 0.893955 + outer loop + vertex 0.899748 1.2537 2.61595 + vertex 0.900757 1.25763 2.61705 + vertex 0.897794 1.25599 2.61538 + endloop + endfacet + facet normal -0.424633 -0.140245 0.894437 + outer loop + vertex 0.896877 1.25196 2.61431 + vertex 0.899748 1.2537 2.61595 + vertex 0.897794 1.25599 2.61538 + endloop + endfacet + facet normal -0.42557 -0.139927 0.894042 + outer loop + vertex 0.897794 1.25599 2.61538 + vertex 0.894759 1.25661 2.61403 + vertex 0.896877 1.25196 2.61431 + endloop + endfacet + facet normal -0.431535 -0.142849 0.890714 + outer loop + vertex 0.896877 1.25196 2.61431 + vertex 0.894759 1.25661 2.61403 + vertex 0.892839 1.25289 2.6125 + endloop + endfacet + facet normal -0.431582 -0.143217 0.890632 + outer loop + vertex 0.894355 1.24808 2.61247 + vertex 0.896877 1.25196 2.61431 + vertex 0.892839 1.25289 2.6125 + endloop + endfacet + facet normal -0.448755 -0.14856 0.88122 + outer loop + vertex 0.894355 1.24808 2.61247 + vertex 0.892839 1.25289 2.6125 + vertex 0.890679 1.24959 2.61085 + endloop + endfacet + facet normal -0.447545 -0.14418 0.882562 + outer loop + vertex 0.891934 1.24486 2.61071 + vertex 0.894355 1.24808 2.61247 + vertex 0.890679 1.24959 2.61085 + endloop + endfacet + facet normal -0.466835 -0.148981 0.871705 + outer loop + vertex 0.890679 1.24959 2.61085 + vertex 0.888308 1.24642 2.60904 + vertex 0.891934 1.24486 2.61071 + endloop + endfacet + facet normal -0.465472 -0.144188 0.873238 + outer loop + vertex 0.888308 1.24642 2.60904 + vertex 0.889802 1.2416 2.60904 + vertex 0.891934 1.24486 2.61071 + endloop + endfacet + facet normal -0.464488 -0.145031 0.873623 + outer loop + vertex 0.892812 1.24089 2.61052 + vertex 0.891934 1.24486 2.61071 + vertex 0.889802 1.2416 2.60904 + endloop + endfacet + facet normal -0.464752 -0.14719 0.873121 + outer loop + vertex 0.892812 1.24089 2.61052 + vertex 0.889802 1.2416 2.60904 + vertex 0.891951 1.23687 2.60938 + endloop + endfacet + facet normal -0.454035 -0.150899 0.878112 + outer loop + vertex 0.891951 1.23687 2.60938 + vertex 0.894765 1.23858 2.61113 + vertex 0.892812 1.24089 2.61052 + endloop + endfacet + facet normal -0.442946 -0.139501 0.885629 + outer loop + vertex 0.894765 1.23858 2.61113 + vertex 0.895656 1.24266 2.61222 + vertex 0.892812 1.24089 2.61052 + endloop + endfacet + facet normal -0.428542 -0.144326 0.89192 + outer loop + vertex 0.894765 1.23858 2.61113 + vertex 0.897844 1.23798 2.61251 + vertex 0.895656 1.24266 2.61222 + endloop + endfacet + facet normal -0.422177 -0.141129 0.89546 + outer loop + vertex 0.897844 1.23798 2.61251 + vertex 0.899749 1.24176 2.61401 + vertex 0.895656 1.24266 2.61222 + endloop + endfacet + facet normal -0.422801 -0.146198 0.894352 + outer loop + vertex 0.899749 1.24176 2.61401 + vertex 0.898195 1.24657 2.61406 + vertex 0.895656 1.24266 2.61222 + endloop + endfacet + facet normal -0.426975 -0.142813 0.892915 + outer loop + vertex 0.895656 1.24266 2.61222 + vertex 0.898195 1.24657 2.61406 + vertex 0.894355 1.24808 2.61247 + endloop + endfacet + facet normal -0.424712 -0.146805 0.893346 + outer loop + vertex 0.898195 1.24657 2.61406 + vertex 0.899749 1.24176 2.61401 + vertex 0.90194 1.24509 2.6156 + endloop + endfacet + facet normal -0.424576 -0.146311 0.893492 + outer loop + vertex 0.900646 1.24978 2.61575 + vertex 0.898195 1.24657 2.61406 + vertex 0.90194 1.24509 2.6156 + endloop + endfacet + facet normal -0.453109 -0.153673 0.87811 + outer loop + vertex 0.90194 1.24509 2.6156 + vertex 0.904345 1.24814 2.61737 + vertex 0.900646 1.24978 2.61575 + endloop + endfacet + facet normal -0.450458 -0.144851 0.880969 + outer loop + vertex 0.904345 1.24814 2.61737 + vertex 0.90285 1.2529 2.61739 + vertex 0.900646 1.24978 2.61575 + endloop + endfacet + facet normal -0.456169 -0.150649 0.877049 + outer loop + vertex 0.905781 1.24279 2.6172 + vertex 0.904345 1.24814 2.61737 + vertex 0.90194 1.24509 2.6156 + endloop + endfacet + facet normal -0.458583 -0.156258 0.874806 + outer loop + vertex 0.902912 1.24113 2.6154 + vertex 0.905781 1.24279 2.6172 + vertex 0.90194 1.24509 2.6156 + endloop + endfacet + facet normal -0.457145 -0.159022 0.87506 + outer loop + vertex 0.905092 1.23867 2.61609 + vertex 0.905781 1.24279 2.6172 + vertex 0.902912 1.24113 2.6154 + endloop + endfacet + facet normal -0.439867 -0.140413 0.887018 + outer loop + vertex 0.901993 1.23704 2.6143 + vertex 0.905092 1.23867 2.61609 + vertex 0.902912 1.24113 2.6154 + endloop + endfacet + facet normal -0.422545 -0.146307 0.894455 + outer loop + vertex 0.902912 1.24113 2.6154 + vertex 0.899749 1.24176 2.61401 + vertex 0.901993 1.23704 2.6143 + endloop + endfacet + facet normal -0.435013 -0.150483 0.88776 + outer loop + vertex 0.905092 1.23867 2.61609 + vertex 0.901993 1.23704 2.6143 + vertex 0.905828 1.2346 2.61576 + endloop + endfacet + facet normal -0.493536 -0.158441 0.855172 + outer loop + vertex 0.905828 1.2346 2.61576 + vertex 0.908924 1.23734 2.61806 + vertex 0.905092 1.23867 2.61609 + endloop + endfacet + facet normal -0.480229 -0.176798 0.859141 + outer loop + vertex 0.908859 1.23242 2.61701 + vertex 0.908924 1.23734 2.61806 + vertex 0.905828 1.2346 2.61576 + endloop + endfacet + facet normal -0.47664 -0.16988 0.862528 + outer loop + vertex 0.906866 1.22998 2.61543 + vertex 0.908859 1.23242 2.61701 + vertex 0.905828 1.2346 2.61576 + endloop + endfacet + facet normal -0.432607 -0.161762 0.886952 + outer loop + vertex 0.905828 1.2346 2.61576 + vertex 0.903248 1.23163 2.61396 + vertex 0.906866 1.22998 2.61543 + endloop + endfacet + facet normal -0.435386 -0.170528 0.883945 + outer loop + vertex 0.903248 1.23163 2.61396 + vertex 0.904847 1.22682 2.61382 + vertex 0.906866 1.22998 2.61543 + endloop + endfacet + facet normal -0.43611 -0.16994 0.883702 + outer loop + vertex 0.907951 1.22613 2.61522 + vertex 0.906866 1.22998 2.61543 + vertex 0.904847 1.22682 2.61382 + endloop + endfacet + facet normal -0.435619 -0.165557 0.884775 + outer loop + vertex 0.907951 1.22613 2.61522 + vertex 0.904847 1.22682 2.61382 + vertex 0.907328 1.22201 2.61414 + endloop + endfacet + facet normal -0.426844 -0.160698 0.889933 + outer loop + vertex 0.907328 1.22201 2.61414 + vertex 0.904847 1.22682 2.61382 + vertex 0.903045 1.2231 2.61229 + endloop + endfacet + facet normal -0.426952 -0.161439 0.889747 + outer loop + vertex 0.904655 1.21822 2.61217 + vertex 0.907328 1.22201 2.61414 + vertex 0.903045 1.2231 2.61229 + endloop + endfacet + facet normal -0.419241 -0.158983 0.893846 + outer loop + vertex 0.904655 1.21822 2.61217 + vertex 0.903045 1.2231 2.61229 + vertex 0.900835 1.21981 2.61066 + endloop + endfacet + facet normal -0.41268 -0.136747 0.900553 + outer loop + vertex 0.901964 1.21516 2.61048 + vertex 0.904655 1.21822 2.61217 + vertex 0.900835 1.21981 2.61066 + endloop + endfacet + facet normal -0.425392 -0.139573 0.894182 + outer loop + vertex 0.900835 1.21981 2.61066 + vertex 0.898291 1.21662 2.60896 + vertex 0.901964 1.21516 2.61048 + endloop + endfacet + facet normal -0.411725 -0.0923229 0.90662 + outer loop + vertex 0.898291 1.21662 2.60896 + vertex 0.899565 1.21181 2.60905 + vertex 0.901964 1.21516 2.61048 + endloop + endfacet + facet normal -0.415857 -0.0887045 0.905093 + outer loop + vertex 0.902642 1.21138 2.61042 + vertex 0.901964 1.21516 2.61048 + vertex 0.899565 1.21181 2.60905 + endloop + endfacet + facet normal -0.410545 -0.0309813 0.911314 + outer loop + vertex 0.902642 1.21138 2.61042 + vertex 0.899565 1.21181 2.60905 + vertex 0.901577 1.20752 2.60981 + endloop + endfacet + facet normal -0.437915 -0.0461942 0.897829 + outer loop + vertex 0.901577 1.20752 2.60981 + vertex 0.899565 1.21181 2.60905 + vertex 0.897258 1.20742 2.60769 + endloop + endfacet + facet normal -0.44348 -0.0424841 0.895277 + outer loop + vertex 0.897258 1.20742 2.60769 + vertex 0.899565 1.21181 2.60905 + vertex 0.895549 1.21283 2.6071 + endloop + endfacet + facet normal -0.491816 -0.0606935 0.868581 + outer loop + vertex 0.89429 1.20903 2.60613 + vertex 0.897258 1.20742 2.60769 + vertex 0.895549 1.21283 2.6071 + endloop + endfacet + facet normal -0.499919 -0.0568776 0.864203 + outer loop + vertex 0.89429 1.20903 2.60613 + vertex 0.895549 1.21283 2.6071 + vertex 0.892538 1.21141 2.60527 + endloop + endfacet + facet normal -0.49407 -0.051241 0.867911 + outer loop + vertex 0.891643 1.20744 2.60453 + vertex 0.89429 1.20903 2.60613 + vertex 0.892538 1.21141 2.60527 + endloop + endfacet + facet normal -0.491594 -0.0520536 0.869267 + outer loop + vertex 0.892538 1.21141 2.60527 + vertex 0.888878 1.21244 2.60326 + vertex 0.891643 1.20744 2.60453 + endloop + endfacet + facet normal -0.527325 -0.0776995 0.846104 + outer loop + vertex 0.891643 1.20744 2.60453 + vertex 0.888878 1.21244 2.60326 + vertex 0.888517 1.20724 2.60256 + endloop + endfacet + facet normal -0.54534 -0.074929 0.834859 + outer loop + vertex 0.888517 1.20724 2.60256 + vertex 0.888878 1.21244 2.60326 + vertex 0.885823 1.20951 2.601 + endloop + endfacet + facet normal -0.534703 -0.0566396 0.84314 + outer loop + vertex 0.886093 1.2047 2.60085 + vertex 0.888517 1.20724 2.60256 + vertex 0.885823 1.20951 2.601 + endloop + endfacet + facet normal -0.55081 -0.0572112 0.832668 + outer loop + vertex 0.885823 1.20951 2.601 + vertex 0.883443 1.20726 2.59927 + vertex 0.886093 1.2047 2.60085 + endloop + endfacet + facet normal -0.542331 -0.0445741 0.838982 + outer loop + vertex 0.883443 1.20726 2.59927 + vertex 0.882394 1.20235 2.59834 + vertex 0.886093 1.2047 2.60085 + endloop + endfacet + facet normal -0.541061 -0.0449978 0.839779 + outer loop + vertex 0.882394 1.20235 2.59834 + vertex 0.883443 1.20726 2.59927 + vertex 0.880206 1.2078 2.59722 + endloop + endfacet + facet normal -0.568614 -0.0600407 0.82041 + outer loop + vertex 0.879268 1.20398 2.59629 + vertex 0.882394 1.20235 2.59834 + vertex 0.880206 1.2078 2.59722 + endloop + endfacet + facet normal -0.555714 -0.0652564 0.828808 + outer loop + vertex 0.879268 1.20398 2.59629 + vertex 0.880206 1.2078 2.59722 + vertex 0.877472 1.20638 2.59527 + endloop + endfacet + facet normal -0.536983 -0.0454622 0.842367 + outer loop + vertex 0.876643 1.20241 2.59453 + vertex 0.879268 1.20398 2.59629 + vertex 0.877472 1.20638 2.59527 + endloop + endfacet + facet normal -0.517102 -0.0518602 0.854351 + outer loop + vertex 0.877472 1.20638 2.59527 + vertex 0.873898 1.20747 2.59318 + vertex 0.876643 1.20241 2.59453 + endloop + endfacet + facet normal -0.549187 -0.0751727 0.832312 + outer loop + vertex 0.876643 1.20241 2.59453 + vertex 0.873898 1.20747 2.59318 + vertex 0.873514 1.20225 2.59245 + endloop + endfacet + facet normal -0.563542 -0.0728046 0.822873 + outer loop + vertex 0.873514 1.20225 2.59245 + vertex 0.873898 1.20747 2.59318 + vertex 0.870804 1.20469 2.59081 + endloop + endfacet + facet normal -0.540829 -0.107809 0.834195 + outer loop + vertex 0.870804 1.20469 2.59081 + vertex 0.873898 1.20747 2.59318 + vertex 0.870381 1.20872 2.59106 + endloop + endfacet + facet normal -0.555087 -0.108725 0.824656 + outer loop + vertex 0.870381 1.20872 2.59106 + vertex 0.867908 1.20762 2.58925 + vertex 0.870804 1.20469 2.59081 + endloop + endfacet + facet normal -0.550993 -0.102805 0.828153 + outer loop + vertex 0.867908 1.20762 2.58925 + vertex 0.867634 1.20265 2.58845 + vertex 0.870804 1.20469 2.59081 + endloop + endfacet + facet normal -0.577945 -0.0984179 0.81012 + outer loop + vertex 0.867634 1.20265 2.58845 + vertex 0.867908 1.20762 2.58925 + vertex 0.865107 1.20683 2.58715 + endloop + endfacet + facet normal -0.596528 -0.114535 0.794378 + outer loop + vertex 0.864732 1.20343 2.58638 + vertex 0.867634 1.20265 2.58845 + vertex 0.865107 1.20683 2.58715 + endloop + endfacet + facet normal -0.562002 -0.159058 0.811699 + outer loop + vertex 0.867908 1.20762 2.58925 + vertex 0.864982 1.21186 2.58805 + vertex 0.865107 1.20683 2.58715 + endloop + endfacet + facet normal -0.549856 -0.14776 0.822086 + outer loop + vertex 0.868253 1.21119 2.59012 + vertex 0.864982 1.21186 2.58805 + vertex 0.867908 1.20762 2.58925 + endloop + endfacet + facet normal -0.551856 -0.183677 0.81346 + outer loop + vertex 0.868253 1.21119 2.59012 + vertex 0.867136 1.21511 2.59025 + vertex 0.864982 1.21186 2.58805 + endloop + endfacet + facet normal -0.553865 -0.181717 0.812535 + outer loop + vertex 0.863352 1.21788 2.58829 + vertex 0.864982 1.21186 2.58805 + vertex 0.867136 1.21511 2.59025 + endloop + endfacet + facet normal -0.557296 -0.189276 0.808453 + outer loop + vertex 0.866369 1.21976 2.59081 + vertex 0.863352 1.21788 2.58829 + vertex 0.867136 1.21511 2.59025 + endloop + endfacet + facet normal -0.538016 -0.187701 0.821771 + outer loop + vertex 0.867136 1.21511 2.59025 + vertex 0.869245 1.21725 2.59212 + vertex 0.866369 1.21976 2.59081 + endloop + endfacet + facet normal -0.535071 -0.182732 0.824808 + outer loop + vertex 0.869245 1.21725 2.59212 + vertex 0.869477 1.22171 2.59326 + vertex 0.866369 1.21976 2.59081 + endloop + endfacet + facet normal -0.537724 -0.177718 0.824178 + outer loop + vertex 0.866369 1.21976 2.59081 + vertex 0.869477 1.22171 2.59326 + vertex 0.865687 1.22433 2.59135 + endloop + endfacet + facet normal -0.554373 -0.178854 0.812823 + outer loop + vertex 0.865687 1.22433 2.59135 + vertex 0.86359 1.22224 2.58946 + vertex 0.866369 1.21976 2.59081 + endloop + endfacet + facet normal -0.563327 -0.166644 0.809255 + outer loop + vertex 0.862223 1.2266 2.5894 + vertex 0.86359 1.22224 2.58946 + vertex 0.865687 1.22433 2.59135 + endloop + endfacet + facet normal -0.566085 -0.173794 0.805819 + outer loop + vertex 0.864675 1.22811 2.59145 + vertex 0.862223 1.2266 2.5894 + vertex 0.865687 1.22433 2.59135 + endloop + endfacet + facet normal -0.546875 -0.169036 0.819972 + outer loop + vertex 0.865687 1.22433 2.59135 + vertex 0.867892 1.22758 2.59349 + vertex 0.864675 1.22811 2.59145 + endloop + endfacet + facet normal -0.546786 -0.165603 0.820732 + outer loop + vertex 0.864675 1.22811 2.59145 + vertex 0.867892 1.22758 2.59349 + vertex 0.864925 1.23164 2.59233 + endloop + endfacet + facet normal -0.56496 -0.161439 0.809171 + outer loop + vertex 0.864675 1.22811 2.59145 + vertex 0.864925 1.23164 2.59233 + vertex 0.862604 1.23046 2.59048 + endloop + endfacet + facet normal -0.567184 -0.156217 0.80864 + outer loop + vertex 0.862604 1.23046 2.59048 + vertex 0.864925 1.23164 2.59233 + vertex 0.861752 1.23457 2.59067 + endloop + endfacet + facet normal -0.582723 -0.158891 0.796987 + outer loop + vertex 0.862604 1.23046 2.59048 + vertex 0.861752 1.23457 2.59067 + vertex 0.859381 1.23147 2.58832 + endloop + endfacet + facet normal -0.583234 -0.163226 0.795736 + outer loop + vertex 0.862604 1.23046 2.59048 + vertex 0.859381 1.23147 2.58832 + vertex 0.862223 1.2266 2.5894 + endloop + endfacet + facet normal -0.584022 -0.163844 0.79503 + outer loop + vertex 0.862223 1.2266 2.5894 + vertex 0.859381 1.23147 2.58832 + vertex 0.859133 1.22702 2.58722 + endloop + endfacet + facet normal -0.583992 -0.167331 0.794326 + outer loop + vertex 0.860509 1.22264 2.58731 + vertex 0.862223 1.2266 2.5894 + vertex 0.859133 1.22702 2.58722 + endloop + endfacet + facet normal -0.593587 -0.170507 0.7865 + outer loop + vertex 0.860509 1.22264 2.58731 + vertex 0.859133 1.22702 2.58722 + vertex 0.857198 1.22485 2.58529 + endloop + endfacet + facet normal -0.592764 -0.168266 0.787602 + outer loop + vertex 0.858158 1.22112 2.58521 + vertex 0.860509 1.22264 2.58731 + vertex 0.857198 1.22485 2.58529 + endloop + endfacet + facet normal -0.605031 -0.171221 0.777574 + outer loop + vertex 0.858158 1.22112 2.58521 + vertex 0.857198 1.22485 2.58529 + vertex 0.855177 1.2217 2.58302 + endloop + endfacet + facet normal -0.605187 -0.180105 0.775442 + outer loop + vertex 0.858158 1.22112 2.58521 + vertex 0.855177 1.2217 2.58302 + vertex 0.857959 1.21766 2.58426 + endloop + endfacet + facet normal -0.595291 -0.182621 0.782482 + outer loop + vertex 0.857959 1.21766 2.58426 + vertex 0.860154 1.21881 2.58619 + vertex 0.858158 1.22112 2.58521 + endloop + endfacet + facet normal -0.591759 -0.190635 0.78325 + outer loop + vertex 0.860154 1.21881 2.58619 + vertex 0.857959 1.21766 2.58426 + vertex 0.861083 1.21478 2.58591 + endloop + endfacet + facet normal -0.575469 -0.18777 0.795976 + outer loop + vertex 0.861083 1.21478 2.58591 + vertex 0.863352 1.21788 2.58829 + vertex 0.860154 1.21881 2.58619 + endloop + endfacet + facet normal -0.574653 -0.179164 0.798545 + outer loop + vertex 0.860154 1.21881 2.58619 + vertex 0.863352 1.21788 2.58829 + vertex 0.860509 1.22264 2.58731 + endloop + endfacet + facet normal -0.578159 -0.181908 0.795388 + outer loop + vertex 0.863352 1.21788 2.58829 + vertex 0.86359 1.22224 2.58946 + vertex 0.860509 1.22264 2.58731 + endloop + endfacet + facet normal -0.5761 -0.187084 0.795681 + outer loop + vertex 0.864982 1.21186 2.58805 + vertex 0.863352 1.21788 2.58829 + vertex 0.861083 1.21478 2.58591 + endloop + endfacet + facet normal -0.573396 -0.180998 0.799035 + outer loop + vertex 0.862061 1.20977 2.58548 + vertex 0.864982 1.21186 2.58805 + vertex 0.861083 1.21478 2.58591 + endloop + endfacet + facet normal -0.594346 -0.183712 0.782945 + outer loop + vertex 0.861083 1.21478 2.58591 + vertex 0.858183 1.2127 2.58323 + vertex 0.862061 1.20977 2.58548 + endloop + endfacet + facet normal -0.587889 -0.168825 0.791129 + outer loop + vertex 0.858183 1.2127 2.58323 + vertex 0.859864 1.2067 2.58319 + vertex 0.862061 1.20977 2.58548 + endloop + endfacet + facet normal -0.599451 -0.156036 0.785055 + outer loop + vertex 0.862928 1.20583 2.58536 + vertex 0.862061 1.20977 2.58548 + vertex 0.859864 1.2067 2.58319 + endloop + endfacet + facet normal -0.59353 -0.102617 0.798243 + outer loop + vertex 0.862928 1.20583 2.58536 + vertex 0.859864 1.2067 2.58319 + vertex 0.862448 1.20243 2.58457 + endloop + endfacet + facet normal -0.590372 -0.103582 0.800457 + outer loop + vertex 0.862448 1.20243 2.58457 + vertex 0.864732 1.20343 2.58638 + vertex 0.862928 1.20583 2.58536 + endloop + endfacet + facet normal -0.615515 -0.122243 0.778587 + outer loop + vertex 0.862448 1.20243 2.58457 + vertex 0.859864 1.2067 2.58319 + vertex 0.859723 1.20182 2.58232 + endloop + endfacet + facet normal -0.584709 -0.153158 0.796654 + outer loop + vertex 0.862928 1.20583 2.58536 + vertex 0.865107 1.20683 2.58715 + vertex 0.862061 1.20977 2.58548 + endloop + endfacet + facet normal -0.615546 -0.17646 0.768092 + outer loop + vertex 0.859864 1.2067 2.58319 + vertex 0.858183 1.2127 2.58323 + vertex 0.856057 1.20954 2.5808 + endloop + endfacet + facet normal -0.611182 -0.165672 0.773957 + outer loop + vertex 0.85706 1.20464 2.58054 + vertex 0.859864 1.2067 2.58319 + vertex 0.856057 1.20954 2.5808 + endloop + endfacet + facet normal -0.623711 -0.167682 0.763457 + outer loop + vertex 0.856057 1.20954 2.5808 + vertex 0.853746 1.20704 2.57836 + vertex 0.85706 1.20464 2.58054 + endloop + endfacet + facet normal -0.61358 -0.141447 0.776861 + outer loop + vertex 0.853746 1.20704 2.57836 + vertex 0.854755 1.20157 2.57816 + vertex 0.85706 1.20464 2.58054 + endloop + endfacet + facet normal -0.633713 -0.116922 0.764681 + outer loop + vertex 0.85758 1.20087 2.58039 + vertex 0.85706 1.20464 2.58054 + vertex 0.854755 1.20157 2.57816 + endloop + endfacet + facet normal -0.627883 -0.0569603 0.776221 + outer loop + vertex 0.85758 1.20087 2.58039 + vertex 0.854755 1.20157 2.57816 + vertex 0.856877 1.1972 2.57956 + endloop + endfacet + facet normal -0.654905 -0.0779094 0.751684 + outer loop + vertex 0.856877 1.1972 2.57956 + vertex 0.854755 1.20157 2.57816 + vertex 0.854217 1.19699 2.57722 + endloop + endfacet + facet normal -0.657231 -0.0772319 0.749722 + outer loop + vertex 0.854217 1.19699 2.57722 + vertex 0.854755 1.20157 2.57816 + vertex 0.85184 1.19941 2.57538 + endloop + endfacet + facet normal -0.632637 -0.128347 0.763739 + outer loop + vertex 0.85184 1.19941 2.57538 + vertex 0.854755 1.20157 2.57816 + vertex 0.851361 1.20447 2.57584 + endloop + endfacet + facet normal -0.649254 -0.128649 0.749612 + outer loop + vertex 0.851361 1.20447 2.57584 + vertex 0.848845 1.20198 2.57323 + vertex 0.85184 1.19941 2.57538 + endloop + endfacet + facet normal -0.639763 -0.108188 0.76092 + outer loop + vertex 0.848845 1.20198 2.57323 + vertex 0.849312 1.19687 2.5729 + vertex 0.85184 1.19941 2.57538 + endloop + endfacet + facet normal -0.661697 -0.108943 0.741814 + outer loop + vertex 0.849312 1.19687 2.5729 + vertex 0.848845 1.20198 2.57323 + vertex 0.846432 1.19936 2.57069 + endloop + endfacet + facet normal -0.652532 -0.0888805 0.752531 + outer loop + vertex 0.846781 1.19431 2.5704 + vertex 0.849312 1.19687 2.5729 + vertex 0.846432 1.19936 2.57069 + endloop + endfacet + facet normal -0.672077 -0.089213 0.735087 + outer loop + vertex 0.846432 1.19936 2.57069 + vertex 0.843992 1.19685 2.56816 + vertex 0.846781 1.19431 2.5704 + endloop + endfacet + facet normal -0.664879 -0.0741433 0.743262 + outer loop + vertex 0.843992 1.19685 2.56816 + vertex 0.844258 1.19186 2.5679 + vertex 0.846781 1.19431 2.5704 + endloop + endfacet + facet normal -0.648951 -0.126967 0.750161 + outer loop + vertex 0.843391 1.20195 2.5685 + vertex 0.843992 1.19685 2.56816 + vertex 0.846432 1.19936 2.57069 + endloop + endfacet + facet normal -0.657546 -0.146517 0.739031 + outer loop + vertex 0.845657 1.20441 2.571 + vertex 0.843391 1.20195 2.5685 + vertex 0.846432 1.19936 2.57069 + endloop + endfacet + facet normal -0.639224 -0.173689 0.749149 + outer loop + vertex 0.842047 1.20744 2.56863 + vertex 0.843391 1.20195 2.5685 + vertex 0.845657 1.20441 2.571 + endloop + endfacet + facet normal -0.643758 -0.184093 0.742755 + outer loop + vertex 0.844765 1.20835 2.57121 + vertex 0.842047 1.20744 2.56863 + vertex 0.845657 1.20441 2.571 + endloop + endfacet + facet normal -0.634645 -0.182461 0.750955 + outer loop + vertex 0.845657 1.20441 2.571 + vertex 0.847814 1.20744 2.57356 + vertex 0.844765 1.20835 2.57121 + endloop + endfacet + facet normal -0.635535 -0.196794 0.74657 + outer loop + vertex 0.844765 1.20835 2.57121 + vertex 0.847814 1.20744 2.57356 + vertex 0.845131 1.2116 2.57238 + endloop + endfacet + facet normal -0.637323 -0.196109 0.745225 + outer loop + vertex 0.844765 1.20835 2.57121 + vertex 0.845131 1.2116 2.57238 + vertex 0.84291 1.21089 2.57029 + endloop + endfacet + facet normal -0.638712 -0.191646 0.745197 + outer loop + vertex 0.84291 1.21089 2.57029 + vertex 0.845131 1.2116 2.57238 + vertex 0.842264 1.21465 2.5707 + endloop + endfacet + facet normal -0.645741 -0.192174 0.738978 + outer loop + vertex 0.84291 1.21089 2.57029 + vertex 0.842264 1.21465 2.5707 + vertex 0.840317 1.21246 2.56843 + endloop + endfacet + facet normal -0.646243 -0.19414 0.738024 + outer loop + vertex 0.842047 1.20744 2.56863 + vertex 0.84291 1.21089 2.57029 + vertex 0.840317 1.21246 2.56843 + endloop + endfacet + facet normal -0.650277 -0.195684 0.734062 + outer loop + vertex 0.842047 1.20744 2.56863 + vertex 0.840317 1.21246 2.56843 + vertex 0.838712 1.21001 2.56636 + endloop + endfacet + facet normal -0.649485 -0.193539 0.735331 + outer loop + vertex 0.842047 1.20744 2.56863 + vertex 0.838712 1.21001 2.56636 + vertex 0.839801 1.2072 2.56658 + endloop + endfacet + facet normal -0.65097 -0.1857 0.736039 + outer loop + vertex 0.840417 1.20428 2.56639 + vertex 0.842047 1.20744 2.56863 + vertex 0.839801 1.2072 2.56658 + endloop + endfacet + facet normal -0.654404 -0.186214 0.732857 + outer loop + vertex 0.839801 1.2072 2.56658 + vertex 0.837881 1.20703 2.56482 + vertex 0.840417 1.20428 2.56639 + endloop + endfacet + facet normal -0.654039 -0.185606 0.733337 + outer loop + vertex 0.837881 1.20703 2.56482 + vertex 0.837788 1.20254 2.5636 + vertex 0.840417 1.20428 2.56639 + endloop + endfacet + facet normal -0.666219 -0.159458 0.728509 + outer loop + vertex 0.840417 1.20428 2.56639 + vertex 0.837788 1.20254 2.5636 + vertex 0.841087 1.19949 2.56595 + endloop + endfacet + facet normal -0.651395 -0.158608 0.741976 + outer loop + vertex 0.841087 1.19949 2.56595 + vertex 0.843391 1.20195 2.5685 + vertex 0.840417 1.20428 2.56639 + endloop + endfacet + facet normal -0.660232 -0.146754 0.736584 + outer loop + vertex 0.837788 1.20254 2.5636 + vertex 0.838713 1.19702 2.56333 + vertex 0.841087 1.19949 2.56595 + endloop + endfacet + facet normal -0.682536 -0.110332 0.722476 + outer loop + vertex 0.841087 1.19949 2.56595 + vertex 0.838713 1.19702 2.56333 + vertex 0.841541 1.19439 2.5656 + endloop + endfacet + facet normal -0.662358 -0.109812 0.741096 + outer loop + vertex 0.841541 1.19439 2.5656 + vertex 0.843992 1.19685 2.56816 + vertex 0.841087 1.19949 2.56595 + endloop + endfacet + facet normal -0.683019 -0.0742389 0.726618 + outer loop + vertex 0.844258 1.19186 2.5679 + vertex 0.843992 1.19685 2.56816 + vertex 0.841541 1.19439 2.5656 + endloop + endfacet + facet normal -0.675096 -0.0944111 0.731664 + outer loop + vertex 0.838713 1.19702 2.56333 + vertex 0.839122 1.19184 2.56304 + vertex 0.841541 1.19439 2.5656 + endloop + endfacet + facet normal -0.697694 -0.0949826 0.710072 + outer loop + vertex 0.839122 1.19184 2.56304 + vertex 0.838713 1.19702 2.56333 + vertex 0.836422 1.19432 2.56072 + endloop + endfacet + facet normal -0.675327 -0.129425 0.726073 + outer loop + vertex 0.836422 1.19432 2.56072 + vertex 0.838713 1.19702 2.56333 + vertex 0.835711 1.19952 2.56098 + endloop + endfacet + facet normal -0.694638 -0.131109 0.707311 + outer loop + vertex 0.835711 1.19952 2.56098 + vertex 0.833561 1.19688 2.55838 + vertex 0.836422 1.19432 2.56072 + endloop + endfacet + facet normal -0.688965 -0.117546 0.715199 + outer loop + vertex 0.833561 1.19688 2.55838 + vertex 0.834101 1.1915 2.55802 + vertex 0.836422 1.19432 2.56072 + endloop + endfacet + facet normal -0.713177 -0.118346 0.690922 + outer loop + vertex 0.834101 1.1915 2.55802 + vertex 0.833561 1.19688 2.55838 + vertex 0.831432 1.19404 2.5557 + endloop + endfacet + facet normal -0.672275 -0.163762 0.721961 + outer loop + vertex 0.832199 1.20264 2.55842 + vertex 0.833561 1.19688 2.55838 + vertex 0.835711 1.19952 2.56098 + endloop + endfacet + facet normal -0.675181 -0.170541 0.717667 + outer loop + vertex 0.834858 1.20354 2.56114 + vertex 0.832199 1.20264 2.55842 + vertex 0.835711 1.19952 2.56098 + endloop + endfacet + facet normal -0.667568 -0.169208 0.725066 + outer loop + vertex 0.835711 1.19952 2.56098 + vertex 0.837788 1.20254 2.5636 + vertex 0.834858 1.20354 2.56114 + endloop + endfacet + facet normal -0.693752 -0.168677 0.700183 + outer loop + vertex 0.833561 1.19688 2.55838 + vertex 0.832199 1.20264 2.55842 + vertex 0.830619 1.19925 2.55604 + endloop + endfacet + facet normal -0.688512 -0.153738 0.708742 + outer loop + vertex 0.831432 1.19404 2.5557 + vertex 0.833561 1.19688 2.55838 + vertex 0.830619 1.19925 2.55604 + endloop + endfacet + facet normal -0.703332 -0.15507 0.693742 + outer loop + vertex 0.830619 1.19925 2.55604 + vertex 0.828602 1.19685 2.55346 + vertex 0.831432 1.19404 2.5557 + endloop + endfacet + facet normal -0.703995 -0.156538 0.692739 + outer loop + vertex 0.828602 1.19685 2.55346 + vertex 0.829216 1.19173 2.55293 + vertex 0.831432 1.19404 2.5557 + endloop + endfacet + facet normal -0.713926 -0.156659 0.682472 + outer loop + vertex 0.829216 1.19173 2.55293 + vertex 0.828602 1.19685 2.55346 + vertex 0.826571 1.19431 2.55075 + endloop + endfacet + facet normal -0.697015 -0.182018 0.69357 + outer loop + vertex 0.826571 1.19431 2.55075 + vertex 0.828602 1.19685 2.55346 + vertex 0.825607 1.19934 2.5511 + endloop + endfacet + facet normal -0.707895 -0.183308 0.682116 + outer loop + vertex 0.825607 1.19934 2.5511 + vertex 0.823586 1.1968 2.54832 + vertex 0.826571 1.19431 2.55075 + endloop + endfacet + facet normal -0.705129 -0.175114 0.687116 + outer loop + vertex 0.823586 1.1968 2.54832 + vertex 0.824511 1.19163 2.54795 + vertex 0.826571 1.19431 2.55075 + endloop + endfacet + facet normal -0.718662 -0.15505 0.677853 + outer loop + vertex 0.826571 1.19431 2.55075 + vertex 0.824511 1.19163 2.54795 + vertex 0.827165 1.18971 2.55033 + endloop + endfacet + facet normal -0.71317 -0.154878 0.683667 + outer loop + vertex 0.827165 1.18971 2.55033 + vertex 0.829216 1.19173 2.55293 + vertex 0.826571 1.19431 2.55075 + endloop + endfacet + facet normal -0.732198 -0.118851 0.670641 + outer loop + vertex 0.829121 1.18791 2.55215 + vertex 0.829216 1.19173 2.55293 + vertex 0.827165 1.18971 2.55033 + endloop + endfacet + facet normal -0.726416 -0.103677 0.67939 + outer loop + vertex 0.827627 1.18649 2.55033 + vertex 0.829121 1.18791 2.55215 + vertex 0.827165 1.18971 2.55033 + endloop + endfacet + facet normal -0.727884 -0.103889 0.677784 + outer loop + vertex 0.827627 1.18649 2.55033 + vertex 0.827165 1.18971 2.55033 + vertex 0.825422 1.18734 2.54809 + endloop + endfacet + facet normal -0.721388 -0.053846 0.690434 + outer loop + vertex 0.826698 1.18419 2.54918 + vertex 0.827627 1.18649 2.55033 + vertex 0.825422 1.18734 2.54809 + endloop + endfacet + facet normal -0.734291 -0.0641421 0.675798 + outer loop + vertex 0.826698 1.18419 2.54918 + vertex 0.825422 1.18734 2.54809 + vertex 0.823989 1.1846 2.54628 + endloop + endfacet + facet normal -0.732337 -0.0152551 0.680772 + outer loop + vertex 0.826698 1.18419 2.54918 + vertex 0.823989 1.1846 2.54628 + vertex 0.825544 1.1819 2.54789 + endloop + endfacet + facet normal -0.74345 -0.0292073 0.668154 + outer loop + vertex 0.823376 1.18202 2.54548 + vertex 0.825544 1.1819 2.54789 + vertex 0.823989 1.1846 2.54628 + endloop + endfacet + facet normal -0.722134 -0.0781384 0.687325 + outer loop + vertex 0.823989 1.1846 2.54628 + vertex 0.825422 1.18734 2.54809 + vertex 0.82266 1.18836 2.54531 + endloop + endfacet + facet normal -0.738998 -0.0377972 0.672647 + outer loop + vertex 0.826698 1.18419 2.54918 + vertex 0.829676 1.18448 2.55247 + vertex 0.827627 1.18649 2.55033 + endloop + endfacet + facet normal -0.747699 -0.0586082 0.661446 + outer loop + vertex 0.829121 1.18791 2.55215 + vertex 0.827627 1.18649 2.55033 + vertex 0.829676 1.18448 2.55247 + endloop + endfacet + facet normal -0.747581 -0.0585762 0.661583 + outer loop + vertex 0.829121 1.18791 2.55215 + vertex 0.829676 1.18448 2.55247 + vertex 0.831546 1.18846 2.55493 + endloop + endfacet + facet normal -0.737888 -0.117479 0.664621 + outer loop + vertex 0.829216 1.19173 2.55293 + vertex 0.829121 1.18791 2.55215 + vertex 0.831546 1.18846 2.55493 + endloop + endfacet + facet normal -0.731307 -0.107315 0.673553 + outer loop + vertex 0.831432 1.19404 2.5557 + vertex 0.829216 1.19173 2.55293 + vertex 0.831546 1.18846 2.55493 + endloop + endfacet + facet normal -0.709587 -0.109947 0.695987 + outer loop + vertex 0.831546 1.18846 2.55493 + vertex 0.834101 1.1915 2.55802 + vertex 0.831432 1.19404 2.5557 + endloop + endfacet + facet normal -0.732845 -0.0708676 0.676695 + outer loop + vertex 0.834399 1.18651 2.55782 + vertex 0.834101 1.1915 2.55802 + vertex 0.831546 1.18846 2.55493 + endloop + endfacet + facet normal -0.708837 -0.0704396 0.701847 + outer loop + vertex 0.834101 1.1915 2.55802 + vertex 0.834399 1.18651 2.55782 + vertex 0.836744 1.18917 2.56046 + endloop + endfacet + facet normal -0.712799 -0.0802643 0.69676 + outer loop + vertex 0.836422 1.19432 2.56072 + vertex 0.834101 1.1915 2.55802 + vertex 0.836744 1.18917 2.56046 + endloop + endfacet + facet normal -0.691072 -0.0800122 0.718344 + outer loop + vertex 0.836744 1.18917 2.56046 + vertex 0.839122 1.19184 2.56304 + vertex 0.836422 1.19432 2.56072 + endloop + endfacet + facet normal -0.703006 -0.059987 0.70865 + outer loop + vertex 0.839461 1.18676 2.56295 + vertex 0.839122 1.19184 2.56304 + vertex 0.836744 1.18917 2.56046 + endloop + endfacet + facet normal -0.69085 -0.0593942 0.720555 + outer loop + vertex 0.839122 1.19184 2.56304 + vertex 0.839461 1.18676 2.56295 + vertex 0.841814 1.1894 2.56542 + endloop + endfacet + facet normal -0.711286 -0.128589 0.691041 + outer loop + vertex 0.824511 1.19163 2.54795 + vertex 0.825422 1.18734 2.54809 + vertex 0.827165 1.18971 2.55033 + endloop + endfacet + facet normal -0.727728 -0.132665 0.672913 + outer loop + vertex 0.825422 1.18734 2.54809 + vertex 0.824511 1.19163 2.54795 + vertex 0.82266 1.18836 2.54531 + endloop + endfacet + facet normal -0.718942 -0.143452 0.680106 + outer loop + vertex 0.82266 1.18836 2.54531 + vertex 0.824511 1.19163 2.54795 + vertex 0.821358 1.19357 2.54503 + endloop + endfacet + facet normal -0.725587 -0.177195 0.664925 + outer loop + vertex 0.824511 1.19163 2.54795 + vertex 0.823586 1.1968 2.54832 + vertex 0.821358 1.19357 2.54503 + endloop + endfacet + facet normal -0.714616 -0.192476 0.672516 + outer loop + vertex 0.821358 1.19357 2.54503 + vertex 0.823586 1.1968 2.54832 + vertex 0.820806 1.19896 2.54599 + endloop + endfacet + facet normal -0.744466 -0.189783 0.640119 + outer loop + vertex 0.820806 1.19896 2.54599 + vertex 0.818847 1.19663 2.54302 + vertex 0.821358 1.19357 2.54503 + endloop + endfacet + facet normal -0.745371 -0.191572 0.638531 + outer loop + vertex 0.818847 1.19663 2.54302 + vertex 0.81907 1.19278 2.54212 + vertex 0.821358 1.19357 2.54503 + endloop + endfacet + facet normal -0.769198 -0.186604 0.611158 + outer loop + vertex 0.81907 1.19278 2.54212 + vertex 0.818847 1.19663 2.54302 + vertex 0.817186 1.19379 2.54006 + endloop + endfacet + facet normal -0.755964 -0.20523 0.62161 + outer loop + vertex 0.817186 1.19379 2.54006 + vertex 0.818847 1.19663 2.54302 + vertex 0.81617 1.19867 2.54044 + endloop + endfacet + facet normal -0.755453 -0.202757 0.623042 + outer loop + vertex 0.818847 1.19663 2.54302 + vertex 0.818518 1.20113 2.54408 + vertex 0.81617 1.19867 2.54044 + endloop + endfacet + facet normal -0.749005 -0.21457 0.626858 + outer loop + vertex 0.81617 1.19867 2.54044 + vertex 0.818518 1.20113 2.54408 + vertex 0.816022 1.20467 2.54231 + endloop + endfacet + facet normal -0.751892 -0.213656 0.623707 + outer loop + vertex 0.816022 1.20467 2.54231 + vertex 0.813604 1.20167 2.53837 + vertex 0.81617 1.19867 2.54044 + endloop + endfacet + facet normal -0.734171 -0.206808 0.646702 + outer loop + vertex 0.818518 1.20113 2.54408 + vertex 0.818847 1.19663 2.54302 + vertex 0.820806 1.19896 2.54599 + endloop + endfacet + facet normal -0.733619 -0.205242 0.647826 + outer loop + vertex 0.820193 1.20201 2.54626 + vertex 0.818518 1.20113 2.54408 + vertex 0.820806 1.19896 2.54599 + endloop + endfacet + facet normal -0.709083 -0.202743 0.675349 + outer loop + vertex 0.820806 1.19896 2.54599 + vertex 0.822348 1.20233 2.54862 + vertex 0.820193 1.20201 2.54626 + endloop + endfacet + facet normal -0.713043 -0.18441 0.676434 + outer loop + vertex 0.822348 1.20233 2.54862 + vertex 0.819221 1.20455 2.54593 + vertex 0.820193 1.20201 2.54626 + endloop + endfacet + facet normal -0.715637 -0.195022 0.670694 + outer loop + vertex 0.822348 1.20233 2.54862 + vertex 0.820802 1.20725 2.5484 + vertex 0.819221 1.20455 2.54593 + endloop + endfacet + facet normal -0.717161 -0.193139 0.66961 + outer loop + vertex 0.819221 1.20455 2.54593 + vertex 0.820802 1.20725 2.5484 + vertex 0.817705 1.20873 2.54551 + endloop + endfacet + facet normal -0.717285 -0.194335 0.669131 + outer loop + vertex 0.820802 1.20725 2.5484 + vertex 0.819459 1.21182 2.54829 + vertex 0.817705 1.20873 2.54551 + endloop + endfacet + facet normal -0.712909 -0.19962 0.672245 + outer loop + vertex 0.817705 1.20873 2.54551 + vertex 0.819459 1.21182 2.54829 + vertex 0.81614 1.21379 2.54535 + endloop + endfacet + facet normal -0.712518 -0.197329 0.673335 + outer loop + vertex 0.819459 1.21182 2.54829 + vertex 0.818312 1.21674 2.54851 + vertex 0.81614 1.21379 2.54535 + endloop + endfacet + facet normal -0.70866 -0.202786 0.67578 + outer loop + vertex 0.81614 1.21379 2.54535 + vertex 0.818312 1.21674 2.54851 + vertex 0.815342 1.21905 2.54609 + endloop + endfacet + facet normal -0.701182 -0.195255 0.685725 + outer loop + vertex 0.818312 1.21674 2.54851 + vertex 0.819459 1.21182 2.54829 + vertex 0.821397 1.21443 2.55101 + endloop + endfacet + facet normal -0.699945 -0.190923 0.688204 + outer loop + vertex 0.820331 1.2191 2.55122 + vertex 0.818312 1.21674 2.54851 + vertex 0.821397 1.21443 2.55101 + endloop + endfacet + facet normal -0.695373 -0.1901 0.69305 + outer loop + vertex 0.821397 1.21443 2.55101 + vertex 0.82334 1.21689 2.55363 + vertex 0.820331 1.2191 2.55122 + endloop + endfacet + facet normal -0.694256 -0.186232 0.695217 + outer loop + vertex 0.82334 1.21689 2.55363 + vertex 0.822046 1.22211 2.55374 + vertex 0.820331 1.2191 2.55122 + endloop + endfacet + facet normal -0.690588 -0.190433 0.697728 + outer loop + vertex 0.820331 1.2191 2.55122 + vertex 0.822046 1.22211 2.55374 + vertex 0.819567 1.22217 2.5513 + endloop + endfacet + facet normal -0.696678 -0.191786 0.691273 + outer loop + vertex 0.819567 1.22217 2.5513 + vertex 0.817024 1.22217 2.54874 + vertex 0.820331 1.2191 2.55122 + endloop + endfacet + facet normal -0.696972 -0.189624 0.691572 + outer loop + vertex 0.817024 1.22217 2.54874 + vertex 0.819567 1.22217 2.5513 + vertex 0.818644 1.22515 2.55119 + endloop + endfacet + facet normal -0.690946 -0.18751 0.698165 + outer loop + vertex 0.822046 1.22211 2.55374 + vertex 0.818644 1.22515 2.55119 + vertex 0.819567 1.22217 2.5513 + endloop + endfacet + facet normal -0.690949 -0.187517 0.69816 + outer loop + vertex 0.822046 1.22211 2.55374 + vertex 0.820487 1.22727 2.55358 + vertex 0.818644 1.22515 2.55119 + endloop + endfacet + facet normal -0.692942 -0.184473 0.696994 + outer loop + vertex 0.818644 1.22515 2.55119 + vertex 0.820487 1.22727 2.55358 + vertex 0.817273 1.2297 2.55103 + endloop + endfacet + facet normal -0.69414 -0.188438 0.694738 + outer loop + vertex 0.820487 1.22727 2.55358 + vertex 0.819159 1.23199 2.55354 + vertex 0.817273 1.2297 2.55103 + endloop + endfacet + facet normal -0.699237 -0.180859 0.691634 + outer loop + vertex 0.817273 1.2297 2.55103 + vertex 0.819159 1.23199 2.55354 + vertex 0.816238 1.23443 2.55122 + endloop + endfacet + facet normal -0.700813 -0.185421 0.688825 + outer loop + vertex 0.819159 1.23199 2.55354 + vertex 0.818307 1.23646 2.55387 + vertex 0.816238 1.23443 2.55122 + endloop + endfacet + facet normal -0.707992 -0.172797 0.684754 + outer loop + vertex 0.816238 1.23443 2.55122 + vertex 0.818307 1.23646 2.55387 + vertex 0.815878 1.23959 2.55215 + endloop + endfacet + facet normal -0.708508 -0.173603 0.684016 + outer loop + vertex 0.818311 1.23991 2.55475 + vertex 0.815878 1.23959 2.55215 + vertex 0.818307 1.23646 2.55387 + endloop + endfacet + facet normal -0.711186 -0.15926 0.684727 + outer loop + vertex 0.818311 1.23991 2.55475 + vertex 0.817668 1.24342 2.5549 + vertex 0.815878 1.23959 2.55215 + endloop + endfacet + facet normal -0.710411 -0.160064 0.685344 + outer loop + vertex 0.817668 1.24342 2.5549 + vertex 0.814979 1.24433 2.55233 + vertex 0.815878 1.23959 2.55215 + endloop + endfacet + facet normal -0.710153 -0.155604 0.686637 + outer loop + vertex 0.816633 1.24853 2.55499 + vertex 0.814979 1.24433 2.55233 + vertex 0.817668 1.24342 2.5549 + endloop + endfacet + facet normal -0.689403 -0.151769 0.7083 + outer loop + vertex 0.817668 1.24342 2.5549 + vertex 0.820397 1.24615 2.55814 + vertex 0.816633 1.24853 2.55499 + endloop + endfacet + facet normal -0.691371 -0.15977 0.704614 + outer loop + vertex 0.820397 1.24615 2.55814 + vertex 0.819269 1.25181 2.55832 + vertex 0.816633 1.24853 2.55499 + endloop + endfacet + facet normal -0.694258 -0.155527 0.702722 + outer loop + vertex 0.816633 1.24853 2.55499 + vertex 0.819269 1.25181 2.55832 + vertex 0.816241 1.25425 2.55587 + endloop + endfacet + facet normal -0.714973 -0.15377 0.682032 + outer loop + vertex 0.816241 1.25425 2.55587 + vertex 0.813953 1.25155 2.55286 + vertex 0.816633 1.24853 2.55499 + endloop + endfacet + facet normal -0.713993 -0.15188 0.683481 + outer loop + vertex 0.813953 1.25155 2.55286 + vertex 0.814095 1.24762 2.55214 + vertex 0.816633 1.24853 2.55499 + endloop + endfacet + facet normal -0.738943 -0.147946 0.657324 + outer loop + vertex 0.814095 1.24762 2.55214 + vertex 0.813953 1.25155 2.55286 + vertex 0.81209 1.24851 2.55008 + endloop + endfacet + facet normal -0.739138 -0.149953 0.65665 + outer loop + vertex 0.812939 1.24521 2.55028 + vertex 0.814095 1.24762 2.55214 + vertex 0.81209 1.24851 2.55008 + endloop + endfacet + facet normal -0.755059 -0.155256 0.63701 + outer loop + vertex 0.812939 1.24521 2.55028 + vertex 0.81209 1.24851 2.55008 + vertex 0.810715 1.24433 2.54743 + endloop + endfacet + facet normal -0.755065 -0.155234 0.637008 + outer loop + vertex 0.812939 1.24521 2.55028 + vertex 0.810715 1.24433 2.54743 + vertex 0.813046 1.24151 2.54951 + endloop + endfacet + facet normal -0.754855 -0.154799 0.637363 + outer loop + vertex 0.810901 1.2391 2.54638 + vertex 0.813046 1.24151 2.54951 + vertex 0.810715 1.24433 2.54743 + endloop + endfacet + facet normal -0.77847 -0.150035 0.609487 + outer loop + vertex 0.810715 1.24433 2.54743 + vertex 0.808558 1.24127 2.54393 + vertex 0.810901 1.2391 2.54638 + endloop + endfacet + facet normal -0.779413 -0.153349 0.607453 + outer loop + vertex 0.808558 1.24127 2.54393 + vertex 0.808989 1.23664 2.54331 + vertex 0.810901 1.2391 2.54638 + endloop + endfacet + facet normal -0.776977 -0.157741 0.609446 + outer loop + vertex 0.810901 1.2391 2.54638 + vertex 0.808989 1.23664 2.54331 + vertex 0.811435 1.23436 2.54584 + endloop + endfacet + facet normal -0.778626 -0.163557 0.605798 + outer loop + vertex 0.808989 1.23664 2.54331 + vertex 0.809614 1.23199 2.54286 + vertex 0.811435 1.23436 2.54584 + endloop + endfacet + facet normal -0.774637 -0.170591 0.608963 + outer loop + vertex 0.811435 1.23436 2.54584 + vertex 0.809614 1.23199 2.54286 + vertex 0.812405 1.22973 2.54578 + endloop + endfacet + facet normal -0.773376 -0.16495 0.612112 + outer loop + vertex 0.809614 1.23199 2.54286 + vertex 0.810782 1.22723 2.54305 + vertex 0.812405 1.22973 2.54578 + endloop + endfacet + facet normal -0.762484 -0.181648 0.620985 + outer loop + vertex 0.813722 1.22522 2.54607 + vertex 0.812405 1.22973 2.54578 + vertex 0.810782 1.22723 2.54305 + endloop + endfacet + facet normal -0.76003 -0.167679 0.627884 + outer loop + vertex 0.812336 1.22211 2.54357 + vertex 0.813722 1.22522 2.54607 + vertex 0.810782 1.22723 2.54305 + endloop + endfacet + facet normal -0.72949 -0.169289 0.662711 + outer loop + vertex 0.813722 1.22522 2.54607 + vertex 0.815476 1.22736 2.54855 + vertex 0.812405 1.22973 2.54578 + endloop + endfacet + facet normal -0.73266 -0.181203 0.65603 + outer loop + vertex 0.815476 1.22736 2.54855 + vertex 0.814238 1.23204 2.54846 + vertex 0.812405 1.22973 2.54578 + endloop + endfacet + facet normal -0.775976 -0.154237 0.611615 + outer loop + vertex 0.808139 1.24607 2.54461 + vertex 0.808558 1.24127 2.54393 + vertex 0.810715 1.24433 2.54743 + endloop + endfacet + facet normal -0.776831 -0.159434 0.609191 + outer loop + vertex 0.809808 1.24908 2.54752 + vertex 0.808139 1.24607 2.54461 + vertex 0.810715 1.24433 2.54743 + endloop + endfacet + facet normal -0.75459 -0.155695 0.637459 + outer loop + vertex 0.81209 1.24851 2.55008 + vertex 0.809808 1.24908 2.54752 + vertex 0.810715 1.24433 2.54743 + endloop + endfacet + facet normal -0.754607 -0.153855 0.637885 + outer loop + vertex 0.811153 1.25341 2.55016 + vertex 0.809808 1.24908 2.54752 + vertex 0.81209 1.24851 2.55008 + endloop + endfacet + facet normal -0.752177 -0.159709 0.639314 + outer loop + vertex 0.813467 1.2368 2.54883 + vertex 0.813046 1.24151 2.54951 + vertex 0.810901 1.2391 2.54638 + endloop + endfacet + facet normal -0.751775 -0.158416 0.640108 + outer loop + vertex 0.811435 1.23436 2.54584 + vertex 0.813467 1.2368 2.54883 + vertex 0.810901 1.2391 2.54638 + endloop + endfacet + facet normal -0.744716 -0.170564 0.645218 + outer loop + vertex 0.814238 1.23204 2.54846 + vertex 0.813467 1.2368 2.54883 + vertex 0.811435 1.23436 2.54584 + endloop + endfacet + facet normal -0.743012 -0.164516 0.648743 + outer loop + vertex 0.812405 1.22973 2.54578 + vertex 0.814238 1.23204 2.54846 + vertex 0.811435 1.23436 2.54584 + endloop + endfacet + facet normal -0.736845 -0.150789 0.659032 + outer loop + vertex 0.81209 1.24851 2.55008 + vertex 0.813953 1.25155 2.55286 + vertex 0.811153 1.25341 2.55016 + endloop + endfacet + facet normal -0.736893 -0.151017 0.658925 + outer loop + vertex 0.813953 1.25155 2.55286 + vertex 0.813548 1.25659 2.55356 + vertex 0.811153 1.25341 2.55016 + endloop + endfacet + facet normal -0.736505 -0.151625 0.65922 + outer loop + vertex 0.811153 1.25341 2.55016 + vertex 0.813548 1.25659 2.55356 + vertex 0.811033 1.25905 2.55132 + endloop + endfacet + facet normal -0.735269 -0.148447 0.661319 + outer loop + vertex 0.813548 1.25659 2.55356 + vertex 0.813363 1.2612 2.55439 + vertex 0.811033 1.25905 2.55132 + endloop + endfacet + facet normal -0.735774 -0.147425 0.660987 + outer loop + vertex 0.811033 1.25905 2.55132 + vertex 0.813363 1.2612 2.55439 + vertex 0.811063 1.26449 2.55257 + endloop + endfacet + facet normal -0.72895 -0.137257 0.670666 + outer loop + vertex 0.814139 1.26451 2.55591 + vertex 0.811063 1.26449 2.55257 + vertex 0.813363 1.2612 2.55439 + endloop + endfacet + facet normal -0.719305 -0.143663 0.679677 + outer loop + vertex 0.813363 1.2612 2.55439 + vertex 0.815058 1.26205 2.55637 + vertex 0.814139 1.26451 2.55591 + endloop + endfacet + facet normal -0.701731 -0.133401 0.699841 + outer loop + vertex 0.817227 1.26234 2.5586 + vertex 0.814139 1.26451 2.55591 + vertex 0.815058 1.26205 2.55637 + endloop + endfacet + facet normal -0.699246 -0.148034 0.699386 + outer loop + vertex 0.815632 1.25913 2.55632 + vertex 0.817227 1.26234 2.5586 + vertex 0.815058 1.26205 2.55637 + endloop + endfacet + facet normal -0.6968 -0.150587 0.70128 + outer loop + vertex 0.818394 1.25706 2.55862 + vertex 0.817227 1.26234 2.5586 + vertex 0.815632 1.25913 2.55632 + endloop + endfacet + facet normal -0.697273 -0.15211 0.70048 + outer loop + vertex 0.816241 1.25425 2.55587 + vertex 0.818394 1.25706 2.55862 + vertex 0.815632 1.25913 2.55632 + endloop + endfacet + facet normal -0.715857 -0.152651 0.681356 + outer loop + vertex 0.815632 1.25913 2.55632 + vertex 0.813548 1.25659 2.55356 + vertex 0.816241 1.25425 2.55587 + endloop + endfacet + facet normal -0.716773 -0.151201 0.680716 + outer loop + vertex 0.813363 1.2612 2.55439 + vertex 0.813548 1.25659 2.55356 + vertex 0.815632 1.25913 2.55632 + endloop + endfacet + facet normal -0.707158 -0.152964 0.690311 + outer loop + vertex 0.817227 1.26234 2.5586 + vertex 0.815769 1.26719 2.55818 + vertex 0.814139 1.26451 2.55591 + endloop + endfacet + facet normal -0.712071 -0.146831 0.686582 + outer loop + vertex 0.814139 1.26451 2.55591 + vertex 0.815769 1.26719 2.55818 + vertex 0.812727 1.26855 2.55531 + endloop + endfacet + facet normal -0.713266 -0.156798 0.683129 + outer loop + vertex 0.815769 1.26719 2.55818 + vertex 0.814569 1.27171 2.55796 + vertex 0.812727 1.26855 2.55531 + endloop + endfacet + facet normal -0.716559 -0.152759 0.680594 + outer loop + vertex 0.812727 1.26855 2.55531 + vertex 0.814569 1.27171 2.55796 + vertex 0.811387 1.27344 2.555 + endloop + endfacet + facet normal -0.729572 -0.157288 0.665571 + outer loop + vertex 0.811387 1.27344 2.555 + vertex 0.809993 1.26927 2.55249 + vertex 0.812727 1.26855 2.55531 + endloop + endfacet + facet normal -0.729516 -0.152175 0.66682 + outer loop + vertex 0.812727 1.26855 2.55531 + vertex 0.809993 1.26927 2.55249 + vertex 0.811063 1.26449 2.55257 + endloop + endfacet + facet normal -0.756641 -0.158788 0.634256 + outer loop + vertex 0.809993 1.26927 2.55249 + vertex 0.808224 1.26641 2.54966 + vertex 0.811063 1.26449 2.55257 + endloop + endfacet + facet normal -0.754386 -0.162029 0.63612 + outer loop + vertex 0.808224 1.26641 2.54966 + vertex 0.809993 1.26927 2.55249 + vertex 0.808021 1.2701 2.55036 + endloop + endfacet + facet normal -0.754469 -0.163355 0.635682 + outer loop + vertex 0.809039 1.27245 2.55217 + vertex 0.808021 1.2701 2.55036 + vertex 0.809993 1.26927 2.55249 + endloop + endfacet + facet normal -0.733022 -0.154271 0.66248 + outer loop + vertex 0.809039 1.27245 2.55217 + vertex 0.809993 1.26927 2.55249 + vertex 0.811387 1.27344 2.555 + endloop + endfacet + facet normal -0.71656 -0.152765 0.680591 + outer loop + vertex 0.814569 1.27171 2.55796 + vertex 0.813806 1.27662 2.55826 + vertex 0.811387 1.27344 2.555 + endloop + endfacet + facet normal -0.70475 -0.154089 0.69252 + outer loop + vertex 0.814569 1.27171 2.55796 + vertex 0.815769 1.26719 2.55818 + vertex 0.817565 1.26979 2.56058 + endloop + endfacet + facet normal -0.705411 -0.1569 0.691215 + outer loop + vertex 0.816644 1.2744 2.56069 + vertex 0.814569 1.27171 2.55796 + vertex 0.817565 1.26979 2.56058 + endloop + endfacet + facet normal -0.698747 -0.155729 0.698213 + outer loop + vertex 0.817565 1.26979 2.56058 + vertex 0.819549 1.27209 2.56308 + vertex 0.816644 1.2744 2.56069 + endloop + endfacet + facet normal -0.69673 -0.149745 0.70153 + outer loop + vertex 0.819549 1.27209 2.56308 + vertex 0.818821 1.27686 2.56338 + vertex 0.816644 1.2744 2.56069 + endloop + endfacet + facet normal -0.701202 -0.142558 0.698565 + outer loop + vertex 0.816644 1.2744 2.56069 + vertex 0.818821 1.27686 2.56338 + vertex 0.816027 1.27933 2.56108 + endloop + endfacet + facet normal -0.705708 -0.142763 0.69397 + outer loop + vertex 0.816027 1.27933 2.56108 + vertex 0.813806 1.27662 2.55826 + vertex 0.816644 1.2744 2.56069 + endloop + endfacet + facet normal -0.708648 -0.138187 0.691897 + outer loop + vertex 0.813385 1.28175 2.55885 + vertex 0.813806 1.27662 2.55826 + vertex 0.816027 1.27933 2.56108 + endloop + endfacet + facet normal -0.703 -0.12439 0.700227 + outer loop + vertex 0.815505 1.28427 2.56143 + vertex 0.813385 1.28175 2.55885 + vertex 0.816027 1.27933 2.56108 + endloop + endfacet + facet normal -0.698925 -0.124254 0.704319 + outer loop + vertex 0.816027 1.27933 2.56108 + vertex 0.818225 1.28196 2.56372 + vertex 0.815505 1.28427 2.56143 + endloop + endfacet + facet normal -0.714736 -0.137966 0.685651 + outer loop + vertex 0.813806 1.27662 2.55826 + vertex 0.813385 1.28175 2.55885 + vertex 0.811121 1.27903 2.55595 + endloop + endfacet + facet normal -0.718488 -0.131918 0.682915 + outer loop + vertex 0.811121 1.27903 2.55595 + vertex 0.813385 1.28175 2.55885 + vertex 0.810809 1.28437 2.55665 + endloop + endfacet + facet normal -0.731221 -0.130889 0.669465 + outer loop + vertex 0.810809 1.28437 2.55665 + vertex 0.80852 1.28155 2.5536 + vertex 0.811121 1.27903 2.55595 + endloop + endfacet + facet normal -0.735769 -0.142455 0.66208 + outer loop + vertex 0.80852 1.28155 2.5536 + vertex 0.808891 1.27632 2.55289 + vertex 0.811121 1.27903 2.55595 + endloop + endfacet + facet normal -0.732731 -0.128395 0.668296 + outer loop + vertex 0.80807 1.28699 2.55415 + vertex 0.80852 1.28155 2.5536 + vertex 0.810809 1.28437 2.55665 + endloop + endfacet + facet normal -0.725655 -0.11072 0.679092 + outer loop + vertex 0.810652 1.28989 2.55738 + vertex 0.80807 1.28699 2.55415 + vertex 0.810809 1.28437 2.55665 + endloop + endfacet + facet normal -0.716824 -0.111684 0.688251 + outer loop + vertex 0.810809 1.28437 2.55665 + vertex 0.813082 1.28651 2.55937 + vertex 0.810652 1.28989 2.55738 + endloop + endfacet + facet normal -0.711865 -0.104441 0.694508 + outer loop + vertex 0.813265 1.28999 2.56008 + vertex 0.810652 1.28989 2.55738 + vertex 0.813082 1.28651 2.55937 + endloop + endfacet + facet normal -0.704319 -0.10634 0.701874 + outer loop + vertex 0.813082 1.28651 2.55937 + vertex 0.814889 1.28806 2.56141 + vertex 0.813265 1.28999 2.56008 + endloop + endfacet + facet normal -0.700517 -0.0998661 0.706613 + outer loop + vertex 0.814889 1.28806 2.56141 + vertex 0.815182 1.29129 2.56216 + vertex 0.813265 1.28999 2.56008 + endloop + endfacet + facet normal -0.700645 -0.0995471 0.706532 + outer loop + vertex 0.813265 1.28999 2.56008 + vertex 0.815182 1.29129 2.56216 + vertex 0.812618 1.29345 2.55992 + endloop + endfacet + facet normal -0.701791 -0.102536 0.704965 + outer loop + vertex 0.815182 1.29129 2.56216 + vertex 0.815334 1.29589 2.56298 + vertex 0.812618 1.29345 2.55992 + endloop + endfacet + facet normal -0.699647 -0.106785 0.706464 + outer loop + vertex 0.812618 1.29345 2.55992 + vertex 0.815334 1.29589 2.56298 + vertex 0.811703 1.29841 2.55976 + endloop + endfacet + facet normal -0.7106 -0.109166 0.695075 + outer loop + vertex 0.811703 1.29841 2.55976 + vertex 0.8098 1.29475 2.55724 + vertex 0.812618 1.29345 2.55992 + endloop + endfacet + facet normal -0.709892 -0.104742 0.696479 + outer loop + vertex 0.812618 1.29345 2.55992 + vertex 0.8098 1.29475 2.55724 + vertex 0.810652 1.28989 2.55738 + endloop + endfacet + facet normal -0.726135 -0.108088 0.679002 + outer loop + vertex 0.8098 1.29475 2.55724 + vertex 0.807014 1.29255 2.55392 + vertex 0.810652 1.28989 2.55738 + endloop + endfacet + facet normal -0.722403 -0.116687 0.681556 + outer loop + vertex 0.807014 1.29255 2.55392 + vertex 0.8098 1.29475 2.55724 + vertex 0.807746 1.29634 2.55534 + endloop + endfacet + facet normal -0.741918 -0.105615 0.66212 + outer loop + vertex 0.807014 1.29255 2.55392 + vertex 0.807746 1.29634 2.55534 + vertex 0.805526 1.29719 2.55299 + endloop + endfacet + facet normal -0.75553 -0.113361 0.645231 + outer loop + vertex 0.807014 1.29255 2.55392 + vertex 0.805526 1.29719 2.55299 + vertex 0.804059 1.29419 2.55074 + endloop + endfacet + facet normal -0.74935 -0.0785454 0.657499 + outer loop + vertex 0.807014 1.29255 2.55392 + vertex 0.804059 1.29419 2.55074 + vertex 0.804959 1.29174 2.55148 + endloop + endfacet + facet normal -0.739465 -0.11901 0.662592 + outer loop + vertex 0.805501 1.28892 2.55157 + vertex 0.807014 1.29255 2.55392 + vertex 0.804959 1.29174 2.55148 + endloop + endfacet + facet normal -0.778185 -0.128097 0.614832 + outer loop + vertex 0.804959 1.29174 2.55148 + vertex 0.803499 1.29075 2.54942 + vertex 0.805501 1.28892 2.55157 + endloop + endfacet + facet normal -0.780728 -0.13692 0.609686 + outer loop + vertex 0.803499 1.29075 2.54942 + vertex 0.803759 1.28653 2.54881 + vertex 0.805501 1.28892 2.55157 + endloop + endfacet + facet normal -0.782296 -0.134157 0.608289 + outer loop + vertex 0.805501 1.28892 2.55157 + vertex 0.803759 1.28653 2.54881 + vertex 0.80599 1.28407 2.55113 + endloop + endfacet + facet normal -0.750142 -0.134463 0.647461 + outer loop + vertex 0.80599 1.28407 2.55113 + vertex 0.80807 1.28699 2.55415 + vertex 0.805501 1.28892 2.55157 + endloop + endfacet + facet normal -0.788786 -0.152094 0.595554 + outer loop + vertex 0.803759 1.28653 2.54881 + vertex 0.804006 1.28164 2.54789 + vertex 0.80599 1.28407 2.55113 + endloop + endfacet + facet normal -0.794124 -0.141678 0.591011 + outer loop + vertex 0.80599 1.28407 2.55113 + vertex 0.804006 1.28164 2.54789 + vertex 0.806236 1.27831 2.55008 + endloop + endfacet + facet normal -0.761642 -0.147569 0.630972 + outer loop + vertex 0.806236 1.27831 2.55008 + vertex 0.80852 1.28155 2.5536 + vertex 0.80599 1.28407 2.55113 + endloop + endfacet + facet normal -0.766411 -0.139842 0.626943 + outer loop + vertex 0.808891 1.27632 2.55289 + vertex 0.80852 1.28155 2.5536 + vertex 0.806236 1.27831 2.55008 + endloop + endfacet + facet normal -0.744719 -0.113624 0.657634 + outer loop + vertex 0.80807 1.28699 2.55415 + vertex 0.807014 1.29255 2.55392 + vertex 0.805501 1.28892 2.55157 + endloop + endfacet + facet normal -0.785607 -0.106192 0.609545 + outer loop + vertex 0.803499 1.29075 2.54942 + vertex 0.804959 1.29174 2.55148 + vertex 0.804059 1.29419 2.55074 + endloop + endfacet + facet normal -0.742262 -0.109236 0.661146 + outer loop + vertex 0.807746 1.29634 2.55534 + vertex 0.807217 1.2997 2.5553 + vertex 0.805526 1.29719 2.55299 + endloop + endfacet + facet normal -0.743912 -0.106788 0.65969 + outer loop + vertex 0.8047 1.30175 2.55279 + vertex 0.805526 1.29719 2.55299 + vertex 0.807217 1.2997 2.5553 + endloop + endfacet + facet normal -0.745488 -0.111966 0.657047 + outer loop + vertex 0.806813 1.30411 2.55559 + vertex 0.8047 1.30175 2.55279 + vertex 0.807217 1.2997 2.5553 + endloop + endfacet + facet normal -0.725007 -0.111596 0.67964 + outer loop + vertex 0.807217 1.2997 2.5553 + vertex 0.809269 1.30168 2.55782 + vertex 0.806813 1.30411 2.55559 + endloop + endfacet + facet normal -0.726434 -0.114941 0.677556 + outer loop + vertex 0.809269 1.30168 2.55782 + vertex 0.80904 1.30658 2.5584 + vertex 0.806813 1.30411 2.55559 + endloop + endfacet + facet normal -0.725334 -0.116891 0.6784 + outer loop + vertex 0.806813 1.30411 2.55559 + vertex 0.80904 1.30658 2.5584 + vertex 0.806423 1.30908 2.55603 + endloop + endfacet + facet normal -0.722387 -0.116936 0.68153 + outer loop + vertex 0.806423 1.30908 2.55603 + vertex 0.804309 1.30663 2.55337 + vertex 0.806813 1.30411 2.55559 + endloop + endfacet + facet normal -0.725186 -0.112156 0.679357 + outer loop + vertex 0.803893 1.31149 2.55373 + vertex 0.804309 1.30663 2.55337 + vertex 0.806423 1.30908 2.55603 + endloop + endfacet + facet normal -0.726937 -0.116465 0.676755 + outer loop + vertex 0.806065 1.31418 2.55653 + vertex 0.803893 1.31149 2.55373 + vertex 0.806423 1.30908 2.55603 + endloop + endfacet + facet normal -0.724956 -0.11653 0.678867 + outer loop + vertex 0.806423 1.30908 2.55603 + vertex 0.808698 1.31173 2.55892 + vertex 0.806065 1.31418 2.55653 + endloop + endfacet + facet normal -0.723514 -0.112898 0.681015 + outer loop + vertex 0.808698 1.31173 2.55892 + vertex 0.808315 1.31666 2.55933 + vertex 0.806065 1.31418 2.55653 + endloop + endfacet + facet normal -0.724711 -0.110768 0.680091 + outer loop + vertex 0.806065 1.31418 2.55653 + vertex 0.808315 1.31666 2.55933 + vertex 0.805768 1.31923 2.55703 + endloop + endfacet + facet normal -0.752329 -0.109348 0.649649 + outer loop + vertex 0.805768 1.31923 2.55703 + vertex 0.803464 1.31656 2.55391 + vertex 0.806065 1.31418 2.55653 + endloop + endfacet + facet normal -0.754288 -0.105709 0.647978 + outer loop + vertex 0.803104 1.32183 2.55436 + vertex 0.803464 1.31656 2.55391 + vertex 0.805768 1.31923 2.55703 + endloop + endfacet + facet normal -0.751041 -0.097169 0.653066 + outer loop + vertex 0.80569 1.32449 2.55773 + vertex 0.803104 1.32183 2.55436 + vertex 0.805768 1.31923 2.55703 + endloop + endfacet + facet normal -0.724393 -0.100592 0.682009 + outer loop + vertex 0.805768 1.31923 2.55703 + vertex 0.808105 1.32094 2.55977 + vertex 0.80569 1.32449 2.55773 + endloop + endfacet + facet normal -0.721121 -0.0959957 0.686126 + outer loop + vertex 0.808912 1.32405 2.56105 + vertex 0.80569 1.32449 2.55773 + vertex 0.808105 1.32094 2.55977 + endloop + endfacet + facet normal -0.721015 -0.108857 0.684316 + outer loop + vertex 0.808912 1.32405 2.56105 + vertex 0.807578 1.32818 2.5603 + vertex 0.80569 1.32449 2.55773 + endloop + endfacet + facet normal -0.726142 -0.103065 0.679776 + outer loop + vertex 0.807578 1.32818 2.5603 + vertex 0.804663 1.32943 2.55738 + vertex 0.80569 1.32449 2.55773 + endloop + endfacet + facet normal -0.726774 -0.107865 0.678354 + outer loop + vertex 0.806405 1.3332 2.55984 + vertex 0.804663 1.32943 2.55738 + vertex 0.807578 1.32818 2.5603 + endloop + endfacet + facet normal -0.714537 -0.103769 0.691859 + outer loop + vertex 0.807578 1.32818 2.5603 + vertex 0.809575 1.33128 2.56283 + vertex 0.806405 1.3332 2.55984 + endloop + endfacet + facet normal -0.714982 -0.10566 0.691113 + outer loop + vertex 0.809575 1.33128 2.56283 + vertex 0.808988 1.33626 2.56298 + vertex 0.806405 1.3332 2.55984 + endloop + endfacet + facet normal -0.71661 -0.102973 0.689831 + outer loop + vertex 0.806405 1.3332 2.55984 + vertex 0.808988 1.33626 2.56298 + vertex 0.806367 1.33874 2.56063 + endloop + endfacet + facet normal -0.731292 -0.100902 0.67456 + outer loop + vertex 0.806367 1.33874 2.56063 + vertex 0.804061 1.33643 2.55779 + vertex 0.806405 1.3332 2.55984 + endloop + endfacet + facet normal -0.730244 -0.0992642 0.675937 + outer loop + vertex 0.804061 1.33643 2.55779 + vertex 0.803937 1.33276 2.55711 + vertex 0.806405 1.3332 2.55984 + endloop + endfacet + facet normal -0.729306 -0.10519 0.676053 + outer loop + vertex 0.803937 1.33276 2.55711 + vertex 0.804663 1.32943 2.55738 + vertex 0.806405 1.3332 2.55984 + endloop + endfacet + facet normal -0.752631 -0.112463 0.648767 + outer loop + vertex 0.803937 1.33276 2.55711 + vertex 0.802636 1.33109 2.55531 + vertex 0.804663 1.32943 2.55738 + endloop + endfacet + facet normal -0.733955 -0.0956181 0.672434 + outer loop + vertex 0.803899 1.3414 2.55832 + vertex 0.804061 1.33643 2.55779 + vertex 0.806367 1.33874 2.56063 + endloop + endfacet + facet normal -0.734524 -0.096841 0.671637 + outer loop + vertex 0.806165 1.34405 2.56118 + vertex 0.803899 1.3414 2.55832 + vertex 0.806367 1.33874 2.56063 + endloop + endfacet + facet normal -0.718203 -0.0979916 0.688899 + outer loop + vertex 0.806367 1.33874 2.56063 + vertex 0.808748 1.34149 2.5635 + vertex 0.806165 1.34405 2.56118 + endloop + endfacet + facet normal -0.717914 -0.0973414 0.689293 + outer loop + vertex 0.808748 1.34149 2.5635 + vertex 0.808464 1.34673 2.56395 + vertex 0.806165 1.34405 2.56118 + endloop + endfacet + facet normal -0.719714 -0.0942911 0.687838 + outer loop + vertex 0.806165 1.34405 2.56118 + vertex 0.808464 1.34673 2.56395 + vertex 0.805805 1.34924 2.56151 + endloop + endfacet + facet normal -0.736747 -0.0942928 0.669561 + outer loop + vertex 0.805805 1.34924 2.56151 + vertex 0.803608 1.34662 2.55872 + vertex 0.806165 1.34405 2.56118 + endloop + endfacet + facet normal -0.719709 -0.0942801 0.687844 + outer loop + vertex 0.808464 1.34673 2.56395 + vertex 0.807933 1.35184 2.56409 + vertex 0.805805 1.34924 2.56151 + endloop + endfacet + facet normal -0.708725 -0.0934609 0.699267 + outer loop + vertex 0.807933 1.35184 2.56409 + vertex 0.808464 1.34673 2.56395 + vertex 0.810742 1.34925 2.56659 + endloop + endfacet + facet normal -0.707448 -0.0956546 0.700262 + outer loop + vertex 0.810742 1.34925 2.56659 + vertex 0.808464 1.34673 2.56395 + vertex 0.811117 1.34414 2.56628 + endloop + endfacet + facet normal -0.700559 -0.0955794 0.707164 + outer loop + vertex 0.811117 1.34414 2.56628 + vertex 0.813476 1.34665 2.56895 + vertex 0.810742 1.34925 2.56659 + endloop + endfacet + facet normal -0.699662 -0.0935926 0.708318 + outer loop + vertex 0.813476 1.34665 2.56895 + vertex 0.812951 1.35173 2.5691 + vertex 0.810742 1.34925 2.56659 + endloop + endfacet + facet normal -0.700629 -0.0919765 0.707573 + outer loop + vertex 0.810742 1.34925 2.56659 + vertex 0.812951 1.35173 2.5691 + vertex 0.810059 1.35412 2.56655 + endloop + endfacet + facet normal -0.692825 -0.0930899 0.715072 + outer loop + vertex 0.812951 1.35173 2.5691 + vertex 0.813476 1.34665 2.56895 + vertex 0.815795 1.3491 2.57152 + endloop + endfacet + facet normal -0.69259 -0.0925649 0.715368 + outer loop + vertex 0.81512 1.35402 2.5715 + vertex 0.812951 1.35173 2.5691 + vertex 0.815795 1.3491 2.57152 + endloop + endfacet + facet normal -0.684612 -0.0914396 0.723149 + outer loop + vertex 0.815795 1.3491 2.57152 + vertex 0.818019 1.35169 2.57395 + vertex 0.81512 1.35402 2.5715 + endloop + endfacet + facet normal -0.684833 -0.0920097 0.722868 + outer loop + vertex 0.818019 1.35169 2.57395 + vertex 0.816909 1.3573 2.57361 + vertex 0.81512 1.35402 2.5715 + endloop + endfacet + facet normal -0.686543 -0.0901822 0.721474 + outer loop + vertex 0.81512 1.35402 2.5715 + vertex 0.816909 1.3573 2.57361 + vertex 0.814493 1.35714 2.57129 + endloop + endfacet + facet normal -0.695377 -0.0925366 0.712663 + outer loop + vertex 0.814493 1.35714 2.57129 + vertex 0.811944 1.35711 2.5688 + vertex 0.81512 1.35402 2.5715 + endloop + endfacet + facet normal -0.686907 -0.0864527 0.721585 + outer loop + vertex 0.816909 1.3573 2.57361 + vertex 0.813719 1.36009 2.57091 + vertex 0.814493 1.35714 2.57129 + endloop + endfacet + facet normal -0.688853 -0.0910287 0.719163 + outer loop + vertex 0.816909 1.3573 2.57361 + vertex 0.815575 1.36232 2.57297 + vertex 0.813719 1.36009 2.57091 + endloop + endfacet + facet normal -0.68468 -0.0893818 0.723343 + outer loop + vertex 0.816909 1.3573 2.57361 + vertex 0.817962 1.36079 2.57504 + vertex 0.815575 1.36232 2.57297 + endloop + endfacet + facet normal -0.683658 -0.085918 0.724727 + outer loop + vertex 0.817962 1.36079 2.57504 + vertex 0.817588 1.3645 2.57513 + vertex 0.815575 1.36232 2.57297 + endloop + endfacet + facet normal -0.684188 -0.0850366 0.724331 + outer loop + vertex 0.814776 1.36683 2.57274 + vertex 0.815575 1.36232 2.57297 + vertex 0.817588 1.3645 2.57513 + endloop + endfacet + facet normal -0.683673 -0.0837651 0.724965 + outer loop + vertex 0.817117 1.36915 2.57522 + vertex 0.814776 1.36683 2.57274 + vertex 0.817588 1.3645 2.57513 + endloop + endfacet + facet normal -0.673878 -0.0829578 0.73417 + outer loop + vertex 0.817588 1.3645 2.57513 + vertex 0.820299 1.3664 2.57783 + vertex 0.817117 1.36915 2.57522 + endloop + endfacet + facet normal -0.674029 -0.0832991 0.733994 + outer loop + vertex 0.820299 1.3664 2.57783 + vertex 0.819535 1.37168 2.57773 + vertex 0.817117 1.36915 2.57522 + endloop + endfacet + facet normal -0.674756 -0.0820805 0.733463 + outer loop + vertex 0.817117 1.36915 2.57522 + vertex 0.819535 1.37168 2.57773 + vertex 0.816679 1.37406 2.57537 + endloop + endfacet + facet normal -0.683594 -0.0826228 0.725171 + outer loop + vertex 0.816679 1.37406 2.57537 + vertex 0.814254 1.37156 2.5728 + vertex 0.817117 1.36915 2.57522 + endloop + endfacet + facet normal -0.684006 -0.0819083 0.724864 + outer loop + vertex 0.813945 1.37646 2.57306 + vertex 0.814254 1.37156 2.5728 + vertex 0.816679 1.37406 2.57537 + endloop + endfacet + facet normal -0.68298 -0.0795606 0.726092 + outer loop + vertex 0.816407 1.37901 2.57565 + vertex 0.813945 1.37646 2.57306 + vertex 0.816679 1.37406 2.57537 + endloop + endfacet + facet normal -0.67436 -0.0795508 0.734105 + outer loop + vertex 0.816679 1.37406 2.57537 + vertex 0.819159 1.37661 2.57792 + vertex 0.816407 1.37901 2.57565 + endloop + endfacet + facet normal -0.673173 -0.0768914 0.735477 + outer loop + vertex 0.819159 1.37661 2.57792 + vertex 0.818906 1.38154 2.57821 + vertex 0.816407 1.37901 2.57565 + endloop + endfacet + facet normal -0.673907 -0.0756235 0.734935 + outer loop + vertex 0.816407 1.37901 2.57565 + vertex 0.818906 1.38154 2.57821 + vertex 0.816199 1.38397 2.57597 + endloop + endfacet + facet normal -0.682096 -0.0754764 0.727357 + outer loop + vertex 0.816199 1.38397 2.57597 + vertex 0.813744 1.38144 2.57341 + vertex 0.816407 1.37901 2.57565 + endloop + endfacet + facet normal -0.682778 -0.0742897 0.72684 + outer loop + vertex 0.813556 1.38645 2.57374 + vertex 0.813744 1.38144 2.57341 + vertex 0.816199 1.38397 2.57597 + endloop + endfacet + facet normal -0.681084 -0.0707306 0.728781 + outer loop + vertex 0.816003 1.38895 2.57627 + vertex 0.813556 1.38645 2.57374 + vertex 0.816199 1.38397 2.57597 + endloop + endfacet + facet normal -0.673415 -0.0708534 0.735862 + outer loop + vertex 0.816199 1.38397 2.57597 + vertex 0.818681 1.38649 2.57849 + vertex 0.816003 1.38895 2.57627 + endloop + endfacet + facet normal -0.672139 -0.0681943 0.737278 + outer loop + vertex 0.818681 1.38649 2.57849 + vertex 0.818477 1.39144 2.57876 + vertex 0.816003 1.38895 2.57627 + endloop + endfacet + facet normal -0.672636 -0.0673291 0.736904 + outer loop + vertex 0.816003 1.38895 2.57627 + vertex 0.818477 1.39144 2.57876 + vertex 0.815762 1.39399 2.57651 + endloop + endfacet + facet normal -0.680537 -0.0673581 0.729611 + outer loop + vertex 0.815762 1.39399 2.57651 + vertex 0.813323 1.39149 2.57401 + vertex 0.816003 1.38895 2.57627 + endloop + endfacet + facet normal -0.680993 -0.0665583 0.729259 + outer loop + vertex 0.812942 1.39667 2.57412 + vertex 0.813323 1.39149 2.57401 + vertex 0.815762 1.39399 2.57651 + endloop + endfacet + facet normal -0.680363 -0.0652676 0.729964 + outer loop + vertex 0.81539 1.39914 2.57663 + vertex 0.812942 1.39667 2.57412 + vertex 0.815762 1.39399 2.57651 + endloop + endfacet + facet normal -0.672356 -0.0648531 0.737382 + outer loop + vertex 0.815762 1.39399 2.57651 + vertex 0.818231 1.39646 2.57898 + vertex 0.81539 1.39914 2.57663 + endloop + endfacet + facet normal -0.672378 -0.0648983 0.737357 + outer loop + vertex 0.818231 1.39646 2.57898 + vertex 0.817858 1.40158 2.57909 + vertex 0.81539 1.39914 2.57663 + endloop + endfacet + facet normal -0.672529 -0.0646308 0.737243 + outer loop + vertex 0.81539 1.39914 2.57663 + vertex 0.817858 1.40158 2.57909 + vertex 0.814985 1.40412 2.5767 + endloop + endfacet + facet normal -0.680812 -0.0651983 0.729551 + outer loop + vertex 0.814985 1.40412 2.5767 + vertex 0.812226 1.40226 2.57395 + vertex 0.81539 1.39914 2.57663 + endloop + endfacet + facet normal -0.680454 -0.0660995 0.729804 + outer loop + vertex 0.812494 1.40702 2.57463 + vertex 0.812226 1.40226 2.57395 + vertex 0.814985 1.40412 2.5767 + endloop + endfacet + facet normal -0.687239 -0.0648213 0.723534 + outer loop + vertex 0.812226 1.40226 2.57395 + vertex 0.812494 1.40702 2.57463 + vertex 0.809988 1.40648 2.57221 + endloop + endfacet + facet normal -0.687746 -0.0615581 0.723337 + outer loop + vertex 0.812494 1.40702 2.57463 + vertex 0.810286 1.41111 2.57288 + vertex 0.809988 1.40648 2.57221 + endloop + endfacet + facet normal -0.687948 -0.0617565 0.723128 + outer loop + vertex 0.812908 1.41024 2.5753 + vertex 0.810286 1.41111 2.57288 + vertex 0.812494 1.40702 2.57463 + endloop + endfacet + facet normal -0.687554 -0.0588505 0.723745 + outer loop + vertex 0.812908 1.41024 2.5753 + vertex 0.812455 1.414 2.57518 + vertex 0.810286 1.41111 2.57288 + endloop + endfacet + facet normal -0.678318 -0.0574491 0.732519 + outer loop + vertex 0.812908 1.41024 2.5753 + vertex 0.814931 1.41119 2.57725 + vertex 0.812455 1.414 2.57518 + endloop + endfacet + facet normal -0.677771 -0.0565417 0.733096 + outer loop + vertex 0.814931 1.41119 2.57725 + vertex 0.815208 1.41604 2.57788 + vertex 0.812455 1.414 2.57518 + endloop + endfacet + facet normal -0.678235 -0.0554545 0.732749 + outer loop + vertex 0.812455 1.414 2.57518 + vertex 0.815208 1.41604 2.57788 + vertex 0.812103 1.41891 2.57523 + endloop + endfacet + facet normal -0.687617 -0.0560446 0.723908 + outer loop + vertex 0.812103 1.41891 2.57523 + vertex 0.809645 1.41645 2.5727 + vertex 0.812455 1.414 2.57518 + endloop + endfacet + facet normal -0.688653 -0.0541451 0.723067 + outer loop + vertex 0.809327 1.42149 2.57277 + vertex 0.809645 1.41645 2.5727 + vertex 0.812103 1.41891 2.57523 + endloop + endfacet + facet normal -0.688116 -0.0530041 0.723662 + outer loop + vertex 0.8118 1.42396 2.57531 + vertex 0.809327 1.42149 2.57277 + vertex 0.812103 1.41891 2.57523 + endloop + endfacet + facet normal -0.678618 -0.0525792 0.732607 + outer loop + vertex 0.812103 1.41891 2.57523 + vertex 0.814576 1.42145 2.5777 + vertex 0.8118 1.42396 2.57531 + endloop + endfacet + facet normal -0.677506 -0.050215 0.733801 + outer loop + vertex 0.814576 1.42145 2.5777 + vertex 0.81432 1.42645 2.5778 + vertex 0.8118 1.42396 2.57531 + endloop + endfacet + facet normal -0.677828 -0.0496314 0.733543 + outer loop + vertex 0.8118 1.42396 2.57531 + vertex 0.81432 1.42645 2.5778 + vertex 0.811624 1.42894 2.57548 + endloop + endfacet + facet normal -0.688533 -0.0496584 0.723503 + outer loop + vertex 0.811624 1.42894 2.57548 + vertex 0.809141 1.42648 2.57295 + vertex 0.8118 1.42396 2.57531 + endloop + endfacet + facet normal -0.689367 -0.0481054 0.722814 + outer loop + vertex 0.808998 1.43144 2.57314 + vertex 0.809141 1.42648 2.57295 + vertex 0.811624 1.42894 2.57548 + endloop + endfacet + facet normal -0.688932 -0.0472074 0.723287 + outer loop + vertex 0.811481 1.43391 2.57567 + vertex 0.808998 1.43144 2.57314 + vertex 0.811624 1.42894 2.57548 + endloop + endfacet + facet normal -0.677595 -0.0472807 0.733914 + outer loop + vertex 0.811624 1.42894 2.57548 + vertex 0.814167 1.43143 2.57799 + vertex 0.811481 1.43391 2.57567 + endloop + endfacet + facet normal -0.676868 -0.045776 0.73468 + outer loop + vertex 0.814167 1.43143 2.57799 + vertex 0.814013 1.43642 2.57816 + vertex 0.811481 1.43391 2.57567 + endloop + endfacet + facet normal -0.677593 -0.0444611 0.734092 + outer loop + vertex 0.811481 1.43391 2.57567 + vertex 0.814013 1.43642 2.57816 + vertex 0.811328 1.43891 2.57583 + endloop + endfacet + facet normal -0.689133 -0.0444643 0.72327 + outer loop + vertex 0.811328 1.43891 2.57583 + vertex 0.808847 1.43641 2.57331 + vertex 0.811481 1.43391 2.57567 + endloop + endfacet + facet normal -0.690122 -0.0426366 0.722436 + outer loop + vertex 0.808689 1.44141 2.57346 + vertex 0.808847 1.43641 2.57331 + vertex 0.811328 1.43891 2.57583 + endloop + endfacet + facet normal -0.689272 -0.0408776 0.723348 + outer loop + vertex 0.811173 1.44391 2.57597 + vertex 0.808689 1.44141 2.57346 + vertex 0.811328 1.43891 2.57583 + endloop + endfacet + facet normal -0.677652 -0.040813 0.734249 + outer loop + vertex 0.811328 1.43891 2.57583 + vertex 0.813855 1.44141 2.5783 + vertex 0.811173 1.44391 2.57597 + endloop + endfacet + facet normal -0.67686 -0.0391987 0.735068 + outer loop + vertex 0.813855 1.44141 2.5783 + vertex 0.813702 1.44641 2.57843 + vertex 0.811173 1.44391 2.57597 + endloop + endfacet + facet normal -0.677665 -0.0377271 0.734402 + outer loop + vertex 0.811173 1.44391 2.57597 + vertex 0.813702 1.44641 2.57843 + vertex 0.811027 1.44892 2.57609 + endloop + endfacet + facet normal -0.689128 -0.0377993 0.723653 + outer loop + vertex 0.811027 1.44892 2.57609 + vertex 0.808538 1.44642 2.57359 + vertex 0.811173 1.44391 2.57597 + endloop + endfacet + facet normal -0.689286 -0.0375072 0.723518 + outer loop + vertex 0.808398 1.45142 2.57371 + vertex 0.808538 1.44642 2.57359 + vertex 0.811027 1.44892 2.57609 + endloop + endfacet + facet normal -0.688745 -0.0363958 0.724089 + outer loop + vertex 0.810889 1.45392 2.57621 + vertex 0.808398 1.45142 2.57371 + vertex 0.811027 1.44892 2.57609 + endloop + endfacet + facet normal -0.677403 -0.0363387 0.734714 + outer loop + vertex 0.811027 1.44892 2.57609 + vertex 0.813558 1.45141 2.57855 + vertex 0.810889 1.45392 2.57621 + endloop + endfacet + facet normal -0.677363 -0.0362571 0.734755 + outer loop + vertex 0.813558 1.45141 2.57855 + vertex 0.81342 1.45641 2.57866 + vertex 0.810889 1.45392 2.57621 + endloop + endfacet + facet normal -0.677562 -0.0358909 0.73459 + outer loop + vertex 0.810889 1.45392 2.57621 + vertex 0.81342 1.45641 2.57866 + vertex 0.810755 1.45891 2.57633 + endloop + endfacet + facet normal -0.687816 -0.0359371 0.724995 + outer loop + vertex 0.810755 1.45891 2.57633 + vertex 0.808261 1.45641 2.57384 + vertex 0.810889 1.45392 2.57621 + endloop + endfacet + facet normal -0.687805 -0.0359577 0.725004 + outer loop + vertex 0.808129 1.4614 2.57396 + vertex 0.808261 1.45641 2.57384 + vertex 0.810755 1.45891 2.57633 + endloop + endfacet + facet normal -0.687063 -0.0344392 0.725781 + outer loop + vertex 0.810625 1.46389 2.57644 + vertex 0.808129 1.4614 2.57396 + vertex 0.810755 1.45891 2.57633 + endloop + endfacet + facet normal -0.678094 -0.0343987 0.73417 + outer loop + vertex 0.810755 1.45891 2.57633 + vertex 0.813285 1.4614 2.57878 + vertex 0.810625 1.46389 2.57644 + endloop + endfacet + facet normal -0.677572 -0.0333436 0.7347 + outer loop + vertex 0.813285 1.4614 2.57878 + vertex 0.813157 1.46639 2.57889 + vertex 0.810625 1.46389 2.57644 + endloop + endfacet + facet normal -0.678685 -0.0312975 0.733762 + outer loop + vertex 0.810625 1.46389 2.57644 + vertex 0.813157 1.46639 2.57889 + vertex 0.810508 1.46888 2.57655 + endloop + endfacet + facet normal -0.687076 -0.0313317 0.72591 + outer loop + vertex 0.810508 1.46888 2.57655 + vertex 0.808007 1.46638 2.57407 + vertex 0.810625 1.46389 2.57644 + endloop + endfacet + facet normal -0.688473 -0.0287232 0.724693 + outer loop + vertex 0.807901 1.47137 2.57417 + vertex 0.808007 1.46638 2.57407 + vertex 0.810508 1.46888 2.57655 + endloop + endfacet + facet normal -0.687807 -0.0273719 0.725378 + outer loop + vertex 0.810404 1.47387 2.57664 + vertex 0.807901 1.47137 2.57417 + vertex 0.810508 1.46888 2.57655 + endloop + endfacet + facet normal -0.679266 -0.0273377 0.733383 + outer loop + vertex 0.810508 1.46888 2.57655 + vertex 0.813041 1.47138 2.57899 + vertex 0.810404 1.47387 2.57664 + endloop + endfacet + facet normal -0.678351 -0.0255013 0.734296 + outer loop + vertex 0.813041 1.47138 2.57899 + vertex 0.812942 1.47638 2.57907 + vertex 0.810404 1.47387 2.57664 + endloop + endfacet + facet normal -0.679101 -0.0241176 0.733649 + outer loop + vertex 0.810404 1.47387 2.57664 + vertex 0.812942 1.47638 2.57907 + vertex 0.810313 1.47886 2.57672 + endloop + endfacet + facet normal -0.688552 -0.0241471 0.724785 + outer loop + vertex 0.810313 1.47886 2.57672 + vertex 0.807808 1.47636 2.57425 + vertex 0.810404 1.47387 2.57664 + endloop + endfacet + facet normal -0.688954 -0.0233916 0.724428 + outer loop + vertex 0.807723 1.48134 2.57433 + vertex 0.807808 1.47636 2.57425 + vertex 0.810313 1.47886 2.57672 + endloop + endfacet + facet normal -0.688171 -0.0218151 0.72522 + outer loop + vertex 0.810234 1.48384 2.57679 + vertex 0.807723 1.48134 2.57433 + vertex 0.810313 1.47886 2.57672 + endloop + endfacet + facet normal -0.678526 -0.0217978 0.734253 + outer loop + vertex 0.810313 1.47886 2.57672 + vertex 0.812856 1.48137 2.57914 + vertex 0.810234 1.48384 2.57679 + endloop + endfacet + facet normal -0.67715 -0.0190555 0.735598 + outer loop + vertex 0.812856 1.48137 2.57914 + vertex 0.812785 1.48635 2.5792 + vertex 0.810234 1.48384 2.57679 + endloop + endfacet + facet normal -0.677516 -0.0183757 0.735278 + outer loop + vertex 0.810234 1.48384 2.57679 + vertex 0.812785 1.48635 2.5792 + vertex 0.810168 1.48881 2.57685 + endloop + endfacet + facet normal -0.687394 -0.0183873 0.726052 + outer loop + vertex 0.810168 1.48881 2.57685 + vertex 0.807651 1.48632 2.57441 + vertex 0.810234 1.48384 2.57679 + endloop + endfacet + facet normal -0.688394 -0.0164923 0.725149 + outer loop + vertex 0.807588 1.4913 2.57446 + vertex 0.807651 1.48632 2.57441 + vertex 0.810168 1.48881 2.57685 + endloop + endfacet + facet normal -0.686977 -0.0136782 0.72655 + outer loop + vertex 0.81011 1.49381 2.57689 + vertex 0.807588 1.4913 2.57446 + vertex 0.810168 1.48881 2.57685 + endloop + endfacet + facet normal -0.676755 -0.013633 0.736082 + outer loop + vertex 0.810168 1.48881 2.57685 + vertex 0.812729 1.49132 2.57926 + vertex 0.81011 1.49381 2.57689 + endloop + endfacet + facet normal -0.675338 -0.0108597 0.737429 + outer loop + vertex 0.812729 1.49132 2.57926 + vertex 0.812679 1.49631 2.57928 + vertex 0.81011 1.49381 2.57689 + endloop + endfacet + facet normal -0.676499 -0.00868073 0.736393 + outer loop + vertex 0.81011 1.49381 2.57689 + vertex 0.812679 1.49631 2.57928 + vertex 0.810044 1.49887 2.57689 + endloop + endfacet + facet normal -0.686803 -0.0088159 0.72679 + outer loop + vertex 0.810044 1.49887 2.57689 + vertex 0.807518 1.49634 2.57447 + vertex 0.81011 1.49381 2.57689 + endloop + endfacet + facet normal -0.67575 -0.00725259 0.737096 + outer loop + vertex 0.812679 1.49631 2.57928 + vertex 0.812633 1.50135 2.57929 + vertex 0.810044 1.49887 2.57689 + endloop + endfacet + facet normal -0.676616 -0.00559608 0.736315 + outer loop + vertex 0.810044 1.49887 2.57689 + vertex 0.812633 1.50135 2.57929 + vertex 0.809977 1.50405 2.57687 + endloop + endfacet + facet normal -0.68742 -0.00578187 0.726237 + outer loop + vertex 0.809977 1.50405 2.57687 + vertex 0.807409 1.5015 2.57442 + vertex 0.810044 1.49887 2.57689 + endloop + endfacet + facet normal -0.688081 -0.00452608 0.72562 + outer loop + vertex 0.807158 1.50713 2.57422 + vertex 0.807409 1.5015 2.57442 + vertex 0.809977 1.50405 2.57687 + endloop + endfacet + facet normal -0.687932 -0.00426733 0.725762 + outer loop + vertex 0.810075 1.5091 2.57699 + vertex 0.807158 1.50713 2.57422 + vertex 0.809977 1.50405 2.57687 + endloop + endfacet + facet normal -0.67644 -0.00475176 0.736482 + outer loop + vertex 0.809977 1.50405 2.57687 + vertex 0.812622 1.50641 2.57931 + vertex 0.810075 1.5091 2.57699 + endloop + endfacet + facet normal -0.675636 -0.00334221 0.737228 + outer loop + vertex 0.812622 1.50641 2.57931 + vertex 0.812638 1.51141 2.57935 + vertex 0.810075 1.5091 2.57699 + endloop + endfacet + facet normal -0.675935 -0.00273375 0.736956 + outer loop + vertex 0.810075 1.5091 2.57699 + vertex 0.812638 1.51141 2.57935 + vertex 0.810129 1.51387 2.57706 + endloop + endfacet + facet normal -0.684432 -0.00252712 0.729072 + outer loop + vertex 0.810129 1.51387 2.57706 + vertex 0.808026 1.51161 2.57508 + vertex 0.810075 1.5091 2.57699 + endloop + endfacet + facet normal -0.68594 0.000120286 0.727658 + outer loop + vertex 0.807527 1.51577 2.57461 + vertex 0.808026 1.51161 2.57508 + vertex 0.810129 1.51387 2.57706 + endloop + endfacet + facet normal -0.685667 0.000825606 0.727915 + outer loop + vertex 0.809962 1.51872 2.5769 + vertex 0.807527 1.51577 2.57461 + vertex 0.810129 1.51387 2.57706 + endloop + endfacet + facet normal -0.675519 0.00148979 0.737341 + outer loop + vertex 0.810129 1.51387 2.57706 + vertex 0.812624 1.51636 2.57934 + vertex 0.809962 1.51872 2.5769 + endloop + endfacet + facet normal -0.674635 0.00332025 0.738144 + outer loop + vertex 0.812624 1.51636 2.57934 + vertex 0.812606 1.52133 2.5793 + vertex 0.809962 1.51872 2.5769 + endloop + endfacet + facet normal -0.675025 0.00404774 0.737783 + outer loop + vertex 0.809962 1.51872 2.5769 + vertex 0.812606 1.52133 2.5793 + vertex 0.809932 1.52377 2.57684 + endloop + endfacet + facet normal -0.673652 0.00679846 0.739018 + outer loop + vertex 0.812606 1.52133 2.5793 + vertex 0.812635 1.52632 2.57928 + vertex 0.809932 1.52377 2.57684 + endloop + endfacet + facet normal -0.673857 0.00720011 0.738826 + outer loop + vertex 0.809932 1.52377 2.57684 + vertex 0.812635 1.52632 2.57928 + vertex 0.810033 1.52879 2.57688 + endloop + endfacet + facet normal -0.683787 0.0074758 0.729643 + outer loop + vertex 0.810033 1.52879 2.57688 + vertex 0.807378 1.52635 2.57442 + vertex 0.809932 1.52377 2.57684 + endloop + endfacet + facet normal -0.684788 0.00953214 0.72868 + outer loop + vertex 0.807492 1.53128 2.57447 + vertex 0.807378 1.52635 2.57442 + vertex 0.810033 1.52879 2.57688 + endloop + endfacet + facet normal -0.683445 0.0120928 0.729902 + outer loop + vertex 0.810095 1.53376 2.57686 + vertex 0.807492 1.53128 2.57447 + vertex 0.810033 1.52879 2.57688 + endloop + endfacet + facet normal -0.673036 0.0120082 0.739512 + outer loop + vertex 0.810033 1.52879 2.57688 + vertex 0.812684 1.53129 2.57926 + vertex 0.810095 1.53376 2.57686 + endloop + endfacet + facet normal -0.672221 0.0135569 0.740226 + outer loop + vertex 0.812684 1.53129 2.57926 + vertex 0.81273 1.53627 2.57921 + vertex 0.810095 1.53376 2.57686 + endloop + endfacet + facet normal -0.673681 0.0163806 0.738841 + outer loop + vertex 0.810095 1.53376 2.57686 + vertex 0.81273 1.53627 2.57921 + vertex 0.810148 1.53874 2.5768 + endloop + endfacet + facet normal -0.684129 0.0163718 0.729177 + outer loop + vertex 0.810148 1.53874 2.5768 + vertex 0.80755 1.53624 2.57442 + vertex 0.810095 1.53376 2.57686 + endloop + endfacet + facet normal -0.685541 0.0191628 0.727782 + outer loop + vertex 0.807611 1.54123 2.57434 + vertex 0.80755 1.53624 2.57442 + vertex 0.810148 1.53874 2.5768 + endloop + endfacet + facet normal -0.684945 0.020294 0.728312 + outer loop + vertex 0.810215 1.54374 2.57672 + vertex 0.807611 1.54123 2.57434 + vertex 0.810148 1.53874 2.5768 + endloop + endfacet + facet normal -0.675134 0.0203005 0.737416 + outer loop + vertex 0.810148 1.53874 2.5768 + vertex 0.812785 1.54127 2.57914 + vertex 0.810215 1.54374 2.57672 + endloop + endfacet + facet normal -0.675091 0.0203815 0.737453 + outer loop + vertex 0.812785 1.54127 2.57914 + vertex 0.812858 1.54627 2.57907 + vertex 0.810215 1.54374 2.57672 + endloop + endfacet + facet normal -0.676645 0.0234143 0.735937 + outer loop + vertex 0.810215 1.54374 2.57672 + vertex 0.812858 1.54627 2.57907 + vertex 0.8103 1.54875 2.57664 + endloop + endfacet + facet normal -0.686151 0.0234323 0.727082 + outer loop + vertex 0.8103 1.54875 2.57664 + vertex 0.807692 1.54624 2.57426 + vertex 0.810215 1.54374 2.57672 + endloop + endfacet + facet normal -0.686971 0.0250703 0.726252 + outer loop + vertex 0.807783 1.55124 2.57418 + vertex 0.807692 1.54624 2.57426 + vertex 0.8103 1.54875 2.57664 + endloop + endfacet + facet normal -0.686541 0.0258795 0.72663 + outer loop + vertex 0.810397 1.55375 2.57656 + vertex 0.807783 1.55124 2.57418 + vertex 0.8103 1.54875 2.57664 + endloop + endfacet + facet normal -0.67718 0.0258509 0.735363 + outer loop + vertex 0.8103 1.54875 2.57664 + vertex 0.812949 1.55127 2.57899 + vertex 0.810397 1.55375 2.57656 + endloop + endfacet + facet normal -0.676465 0.0271866 0.735973 + outer loop + vertex 0.812949 1.55127 2.57899 + vertex 0.813051 1.55627 2.5789 + vertex 0.810397 1.55375 2.57656 + endloop + endfacet + facet normal -0.676304 0.0268687 0.736132 + outer loop + vertex 0.810397 1.55375 2.57656 + vertex 0.813051 1.55627 2.5789 + vertex 0.810496 1.55875 2.57646 + endloop + endfacet + facet normal -0.685901 0.0268953 0.727198 + outer loop + vertex 0.810496 1.55875 2.57646 + vertex 0.807878 1.55624 2.57409 + vertex 0.810397 1.55375 2.57656 + endloop + endfacet + facet normal -0.685536 0.0261659 0.727568 + outer loop + vertex 0.807974 1.56124 2.574 + vertex 0.807878 1.55624 2.57409 + vertex 0.810496 1.55875 2.57646 + endloop + endfacet + facet normal -0.684736 0.0276703 0.728266 + outer loop + vertex 0.810596 1.56375 2.57637 + vertex 0.807974 1.56124 2.574 + vertex 0.810496 1.55875 2.57646 + endloop + endfacet + facet normal -0.675111 0.0276487 0.737198 + outer loop + vertex 0.810496 1.55875 2.57646 + vertex 0.813155 1.56126 2.5788 + vertex 0.810596 1.56375 2.57637 + endloop + endfacet + facet normal -0.674122 0.0294821 0.738031 + outer loop + vertex 0.813155 1.56126 2.5788 + vertex 0.813258 1.56625 2.5787 + vertex 0.810596 1.56375 2.57637 + endloop + endfacet + facet normal -0.674266 0.0297699 0.737888 + outer loop + vertex 0.810596 1.56375 2.57637 + vertex 0.813258 1.56625 2.5787 + vertex 0.810701 1.56875 2.57626 + endloop + endfacet + facet normal -0.683589 0.0297836 0.729259 + outer loop + vertex 0.810701 1.56875 2.57626 + vertex 0.808074 1.56624 2.5739 + vertex 0.810596 1.56375 2.57637 + endloop + endfacet + facet normal -0.684182 0.0309722 0.728653 + outer loop + vertex 0.808186 1.57124 2.57379 + vertex 0.808074 1.56624 2.5739 + vertex 0.810701 1.56875 2.57626 + endloop + endfacet + facet normal -0.683015 0.0331407 0.729652 + outer loop + vertex 0.81082 1.57374 2.57615 + vertex 0.808186 1.57124 2.57379 + vertex 0.810701 1.56875 2.57626 + endloop + endfacet + facet normal -0.674778 0.0331208 0.737277 + outer loop + vertex 0.810701 1.56875 2.57626 + vertex 0.813365 1.57122 2.57859 + vertex 0.81082 1.57374 2.57615 + endloop + endfacet + facet normal -0.674307 0.0339767 0.737669 + outer loop + vertex 0.813365 1.57122 2.57859 + vertex 0.813486 1.57619 2.57847 + vertex 0.81082 1.57374 2.57615 + endloop + endfacet + facet normal -0.676021 0.0374975 0.735928 + outer loop + vertex 0.81082 1.57374 2.57615 + vertex 0.813486 1.57619 2.57847 + vertex 0.810958 1.57872 2.57602 + endloop + endfacet + facet normal -0.683993 0.03753 0.728522 + outer loop + vertex 0.810958 1.57872 2.57602 + vertex 0.808319 1.57624 2.57367 + vertex 0.81082 1.57374 2.57615 + endloop + endfacet + facet normal -0.68569 0.0410297 0.726737 + outer loop + vertex 0.808467 1.58124 2.57353 + vertex 0.808319 1.57624 2.57367 + vertex 0.810958 1.57872 2.57602 + endloop + endfacet + facet normal -0.68536 0.0416294 0.727013 + outer loop + vertex 0.811103 1.58369 2.57587 + vertex 0.808467 1.58124 2.57353 + vertex 0.810958 1.57872 2.57602 + endloop + endfacet + facet normal -0.677548 0.0416171 0.7343 + outer loop + vertex 0.810958 1.57872 2.57602 + vertex 0.813623 1.58114 2.57834 + vertex 0.811103 1.58369 2.57587 + endloop + endfacet + facet normal -0.677325 0.0420151 0.734483 + outer loop + vertex 0.813623 1.58114 2.57834 + vertex 0.81376 1.58608 2.57819 + vertex 0.811103 1.58369 2.57587 + endloop + endfacet + facet normal -0.678405 0.0443041 0.733351 + outer loop + vertex 0.811103 1.58369 2.57587 + vertex 0.81376 1.58608 2.57819 + vertex 0.811238 1.58864 2.5757 + endloop + endfacet + facet normal -0.686575 0.0442565 0.72571 + outer loop + vertex 0.811238 1.58864 2.5757 + vertex 0.808614 1.58622 2.57336 + vertex 0.811103 1.58369 2.57587 + endloop + endfacet + facet normal -0.687372 0.0459504 0.72485 + outer loop + vertex 0.808755 1.59119 2.57318 + vertex 0.808614 1.58622 2.57336 + vertex 0.811238 1.58864 2.5757 + endloop + endfacet + facet normal -0.68688 0.0468333 0.72526 + outer loop + vertex 0.811375 1.59361 2.57551 + vertex 0.808755 1.59119 2.57318 + vertex 0.811238 1.58864 2.5757 + endloop + endfacet + facet normal -0.678792 0.0469021 0.732832 + outer loop + vertex 0.811238 1.58864 2.5757 + vertex 0.813892 1.59104 2.578 + vertex 0.811375 1.59361 2.57551 + endloop + endfacet + facet normal -0.678072 0.0481777 0.733415 + outer loop + vertex 0.813892 1.59104 2.578 + vertex 0.814059 1.59608 2.57783 + vertex 0.811375 1.59361 2.57551 + endloop + endfacet + facet normal -0.678362 0.0487816 0.733107 + outer loop + vertex 0.811375 1.59361 2.57551 + vertex 0.814059 1.59608 2.57783 + vertex 0.811559 1.59861 2.57534 + endloop + endfacet + facet normal -0.68704 0.0488354 0.724977 + outer loop + vertex 0.811559 1.59861 2.57534 + vertex 0.80892 1.59616 2.57301 + vertex 0.811375 1.59361 2.57551 + endloop + endfacet + facet normal -0.688057 0.0509945 0.723862 + outer loop + vertex 0.809147 1.60115 2.57287 + vertex 0.80892 1.59616 2.57301 + vertex 0.811559 1.59861 2.57534 + endloop + endfacet + facet normal -0.687671 0.0516731 0.724182 + outer loop + vertex 0.811828 1.60366 2.57524 + vertex 0.809147 1.60115 2.57287 + vertex 0.811559 1.59861 2.57534 + endloop + endfacet + facet normal -0.678334 0.0513541 0.732957 + outer loop + vertex 0.811559 1.59861 2.57534 + vertex 0.8143 1.60121 2.5777 + vertex 0.811828 1.60366 2.57524 + endloop + endfacet + facet normal -0.678103 0.0517725 0.733141 + outer loop + vertex 0.8143 1.60121 2.5777 + vertex 0.814636 1.60636 2.57765 + vertex 0.811828 1.60366 2.57524 + endloop + endfacet + facet normal -0.679613 0.0547828 0.731522 + outer loop + vertex 0.811828 1.60366 2.57524 + vertex 0.814636 1.60636 2.57765 + vertex 0.812117 1.6087 2.57513 + endloop + endfacet + facet normal -0.688664 0.0551151 0.722983 + outer loop + vertex 0.812117 1.6087 2.57513 + vertex 0.809399 1.60612 2.57274 + vertex 0.811828 1.60366 2.57524 + endloop + endfacet + facet normal -0.690157 0.058228 0.721313 + outer loop + vertex 0.809499 1.61096 2.57244 + vertex 0.809399 1.60612 2.57274 + vertex 0.812117 1.6087 2.57513 + endloop + endfacet + facet normal -0.689924 0.0587174 0.721497 + outer loop + vertex 0.812072 1.61358 2.57469 + vertex 0.809499 1.61096 2.57244 + vertex 0.812117 1.6087 2.57513 + endloop + endfacet + facet normal -0.681625 0.0594963 0.729279 + outer loop + vertex 0.812117 1.6087 2.57513 + vertex 0.815185 1.6118 2.57774 + vertex 0.812072 1.61358 2.57469 + endloop + endfacet + facet normal -0.681722 0.0592097 0.729211 + outer loop + vertex 0.815185 1.6118 2.57774 + vertex 0.814546 1.61673 2.57675 + vertex 0.812072 1.61358 2.57469 + endloop + endfacet + facet normal -0.685142 0.0642585 0.72557 + outer loop + vertex 0.812072 1.61358 2.57469 + vertex 0.814546 1.61673 2.57675 + vertex 0.811541 1.61817 2.57378 + endloop + endfacet + facet normal -0.69215 0.0621609 0.719072 + outer loop + vertex 0.811541 1.61817 2.57378 + vertex 0.80926 1.61558 2.57181 + vertex 0.812072 1.61358 2.57469 + endloop + endfacet + facet normal -0.694589 0.0663948 0.716337 + outer loop + vertex 0.808702 1.61997 2.57086 + vertex 0.80926 1.61558 2.57181 + vertex 0.811541 1.61817 2.57378 + endloop + endfacet + facet normal -0.694881 0.0655938 0.716127 + outer loop + vertex 0.810806 1.62309 2.57262 + vertex 0.808702 1.61997 2.57086 + vertex 0.811541 1.61817 2.57378 + endloop + endfacet + facet normal -0.689446 0.0675996 0.721176 + outer loop + vertex 0.810806 1.62309 2.57262 + vertex 0.811541 1.61817 2.57378 + vertex 0.813702 1.62087 2.5756 + endloop + endfacet + facet normal -0.692639 0.0602052 0.718767 + outer loop + vertex 0.810806 1.62309 2.57262 + vertex 0.813702 1.62087 2.5756 + vertex 0.81311 1.62339 2.57481 + endloop + endfacet + facet normal -0.692861 0.0690579 0.717757 + outer loop + vertex 0.81311 1.62339 2.57481 + vertex 0.81294 1.62627 2.57437 + vertex 0.810806 1.62309 2.57262 + endloop + endfacet + facet normal -0.692803 0.0689846 0.71782 + outer loop + vertex 0.810806 1.62309 2.57262 + vertex 0.81294 1.62627 2.57437 + vertex 0.810453 1.62838 2.57177 + endloop + endfacet + facet normal -0.697873 0.0678733 0.712998 + outer loop + vertex 0.810453 1.62838 2.57177 + vertex 0.808021 1.62603 2.56961 + vertex 0.810806 1.62309 2.57262 + endloop + endfacet + facet normal -0.698669 0.0695589 0.712055 + outer loop + vertex 0.807892 1.63099 2.569 + vertex 0.808021 1.62603 2.56961 + vertex 0.810453 1.62838 2.57177 + endloop + endfacet + facet normal -0.699059 0.0688454 0.711742 + outer loop + vertex 0.810489 1.6335 2.57131 + vertex 0.807892 1.63099 2.569 + vertex 0.810453 1.62838 2.57177 + endloop + endfacet + facet normal -0.692246 0.0693864 0.718318 + outer loop + vertex 0.810453 1.62838 2.57177 + vertex 0.812983 1.63097 2.57396 + vertex 0.810489 1.6335 2.57131 + endloop + endfacet + facet normal -0.691956 0.0699129 0.718547 + outer loop + vertex 0.812983 1.63097 2.57396 + vertex 0.813157 1.63602 2.57363 + vertex 0.810489 1.6335 2.57131 + endloop + endfacet + facet normal -0.691844 0.0696733 0.718678 + outer loop + vertex 0.810489 1.6335 2.57131 + vertex 0.813157 1.63602 2.57363 + vertex 0.81073 1.63861 2.57105 + endloop + endfacet + facet normal -0.699253 0.0696506 0.711473 + outer loop + vertex 0.81073 1.63861 2.57105 + vertex 0.808057 1.63611 2.56866 + vertex 0.810489 1.6335 2.57131 + endloop + endfacet + facet normal -0.699683 0.0706034 0.710957 + outer loop + vertex 0.808383 1.64117 2.56848 + vertex 0.808057 1.63611 2.56866 + vertex 0.81073 1.63861 2.57105 + endloop + endfacet + facet normal -0.6988 0.0721249 0.711671 + outer loop + vertex 0.81107 1.64365 2.57087 + vertex 0.808383 1.64117 2.56848 + vertex 0.81073 1.63861 2.57105 + endloop + endfacet + facet normal -0.690923 0.0718652 0.719347 + outer loop + vertex 0.81073 1.63861 2.57105 + vertex 0.813429 1.64108 2.57339 + vertex 0.81107 1.64365 2.57087 + endloop + endfacet + facet normal -0.689113 0.0749216 0.72077 + outer loop + vertex 0.813429 1.64108 2.57339 + vertex 0.813776 1.6461 2.5732 + vertex 0.81107 1.64365 2.57087 + endloop + endfacet + facet normal -0.68968 0.0761962 0.720094 + outer loop + vertex 0.81107 1.64365 2.57087 + vertex 0.813776 1.6461 2.5732 + vertex 0.811443 1.64864 2.5707 + endloop + endfacet + facet normal -0.697407 0.0765169 0.712579 + outer loop + vertex 0.811443 1.64864 2.5707 + vertex 0.80876 1.64618 2.56834 + vertex 0.81107 1.64365 2.57087 + endloop + endfacet + facet normal -0.698393 0.0787551 0.711369 + outer loop + vertex 0.809099 1.65115 2.56812 + vertex 0.80876 1.64618 2.56834 + vertex 0.811443 1.64864 2.5707 + endloop + endfacet + facet normal -0.696289 0.0824205 0.713014 + outer loop + vertex 0.811728 1.65355 2.57041 + vertex 0.809099 1.65115 2.56812 + vertex 0.811443 1.64864 2.5707 + endloop + endfacet + facet normal -0.687849 0.0824084 0.721161 + outer loop + vertex 0.811443 1.64864 2.5707 + vertex 0.814149 1.65106 2.573 + vertex 0.811728 1.65355 2.57041 + endloop + endfacet + facet normal -0.6858 0.0860047 0.722691 + outer loop + vertex 0.814149 1.65106 2.573 + vertex 0.814353 1.65591 2.57262 + vertex 0.811728 1.65355 2.57041 + endloop + endfacet + facet normal -0.686913 0.0885107 0.72133 + outer loop + vertex 0.811728 1.65355 2.57041 + vertex 0.814353 1.65591 2.57262 + vertex 0.811736 1.65829 2.56983 + endloop + endfacet + facet normal -0.695623 0.0875225 0.713055 + outer loop + vertex 0.811736 1.65829 2.56983 + vertex 0.809259 1.656 2.5677 + vertex 0.811728 1.65355 2.57041 + endloop + endfacet + facet normal -0.696973 0.090562 0.711356 + outer loop + vertex 0.809093 1.66066 2.56694 + vertex 0.809259 1.656 2.5677 + vertex 0.811736 1.65829 2.56983 + endloop + endfacet + facet normal -0.696818 0.0908712 0.711468 + outer loop + vertex 0.811362 1.66292 2.56888 + vertex 0.809093 1.66066 2.56694 + vertex 0.811736 1.65829 2.56983 + endloop + endfacet + facet normal -0.687773 0.0933465 0.719899 + outer loop + vertex 0.811736 1.65829 2.56983 + vertex 0.814175 1.66055 2.57187 + vertex 0.811362 1.66292 2.56888 + endloop + endfacet + facet normal -0.689003 0.0908108 0.719047 + outer loop + vertex 0.813661 1.66495 2.57082 + vertex 0.811362 1.66292 2.56888 + vertex 0.814175 1.66055 2.57187 + endloop + endfacet + facet normal -0.681308 0.0933697 0.726018 + outer loop + vertex 0.813661 1.66495 2.57082 + vertex 0.814175 1.66055 2.57187 + vertex 0.816555 1.66306 2.57378 + endloop + endfacet + facet normal -0.682471 0.0904504 0.725295 + outer loop + vertex 0.815858 1.66794 2.57252 + vertex 0.813661 1.66495 2.57082 + vertex 0.816555 1.66306 2.57378 + endloop + endfacet + facet normal -0.676531 0.0926641 0.730561 + outer loop + vertex 0.815858 1.66794 2.57252 + vertex 0.816555 1.66306 2.57378 + vertex 0.818774 1.6657 2.5755 + endloop + endfacet + facet normal -0.679591 0.0859971 0.728533 + outer loop + vertex 0.815858 1.66794 2.57252 + vertex 0.818774 1.6657 2.5755 + vertex 0.8182 1.66819 2.57467 + endloop + endfacet + facet normal -0.679565 0.0920875 0.727813 + outer loop + vertex 0.8182 1.66819 2.57467 + vertex 0.818023 1.67103 2.57415 + vertex 0.815858 1.66794 2.57252 + endloop + endfacet + facet normal -0.680408 0.0931662 0.726887 + outer loop + vertex 0.815858 1.66794 2.57252 + vertex 0.818023 1.67103 2.57415 + vertex 0.81553 1.67319 2.57154 + endloop + endfacet + facet normal -0.685709 0.0919311 0.722047 + outer loop + vertex 0.81553 1.67319 2.57154 + vertex 0.813042 1.67094 2.56946 + vertex 0.815858 1.66794 2.57252 + endloop + endfacet + facet normal -0.683905 0.0949649 0.723364 + outer loop + vertex 0.813042 1.67094 2.56946 + vertex 0.813268 1.66784 2.57008 + vertex 0.815858 1.66794 2.57252 + endloop + endfacet + facet normal -0.693688 0.0924457 0.714318 + outer loop + vertex 0.813268 1.66784 2.57008 + vertex 0.813042 1.67094 2.56946 + vertex 0.810756 1.66801 2.56762 + endloop + endfacet + facet normal -0.694043 0.0888444 0.71443 + outer loop + vertex 0.810756 1.66801 2.56762 + vertex 0.813661 1.66495 2.57082 + vertex 0.813268 1.66784 2.57008 + endloop + endfacet + facet normal -0.694749 0.0940538 0.713076 + outer loop + vertex 0.810756 1.66801 2.56762 + vertex 0.813042 1.67094 2.56946 + vertex 0.810445 1.67341 2.56661 + endloop + endfacet + facet normal -0.703428 0.0919957 0.704788 + outer loop + vertex 0.810445 1.67341 2.56661 + vertex 0.808023 1.67118 2.56448 + vertex 0.810756 1.66801 2.56762 + endloop + endfacet + facet normal -0.705016 0.0957089 0.702704 + outer loop + vertex 0.808004 1.67609 2.56379 + vertex 0.808023 1.67118 2.56448 + vertex 0.810445 1.67341 2.56661 + endloop + endfacet + facet normal -0.704751 0.0961647 0.702907 + outer loop + vertex 0.810607 1.67853 2.56607 + vertex 0.808004 1.67609 2.56379 + vertex 0.810445 1.67341 2.56661 + endloop + endfacet + facet normal -0.695982 0.0967909 0.711506 + outer loop + vertex 0.810445 1.67341 2.56661 + vertex 0.812991 1.67585 2.56876 + vertex 0.810607 1.67853 2.56607 + endloop + endfacet + facet normal -0.694709 0.0988865 0.712461 + outer loop + vertex 0.812991 1.67585 2.56876 + vertex 0.813323 1.68098 2.56838 + vertex 0.810607 1.67853 2.56607 + endloop + endfacet + facet normal -0.695631 0.101041 0.711259 + outer loop + vertex 0.810607 1.67853 2.56607 + vertex 0.813323 1.68098 2.56838 + vertex 0.811073 1.6836 2.5658 + endloop + endfacet + facet normal -0.704024 0.101375 0.702904 + outer loop + vertex 0.811073 1.6836 2.5658 + vertex 0.808355 1.68114 2.56344 + vertex 0.810607 1.67853 2.56607 + endloop + endfacet + facet normal -0.704701 0.103006 0.701987 + outer loop + vertex 0.808846 1.68612 2.5632 + vertex 0.808355 1.68114 2.56344 + vertex 0.811073 1.6836 2.5658 + endloop + endfacet + facet normal -0.702984 0.105867 0.703282 + outer loop + vertex 0.811529 1.68853 2.56552 + vertex 0.808846 1.68612 2.5632 + vertex 0.811073 1.6836 2.5658 + endloop + endfacet + facet normal -0.6946 0.105574 0.711608 + outer loop + vertex 0.811073 1.6836 2.5658 + vertex 0.813843 1.68606 2.56814 + vertex 0.811529 1.68853 2.56552 + endloop + endfacet + facet normal -0.693716 0.107078 0.712245 + outer loop + vertex 0.813843 1.68606 2.56814 + vertex 0.814195 1.69095 2.56775 + vertex 0.811529 1.68853 2.56552 + endloop + endfacet + facet normal -0.694434 0.108751 0.711291 + outer loop + vertex 0.811529 1.68853 2.56552 + vertex 0.814195 1.69095 2.56775 + vertex 0.811652 1.69324 2.56492 + endloop + endfacet + facet normal -0.702641 0.107949 0.703309 + outer loop + vertex 0.811652 1.69324 2.56492 + vertex 0.809146 1.69091 2.56277 + vertex 0.811529 1.68853 2.56552 + endloop + endfacet + facet normal -0.702956 0.108683 0.70288 + outer loop + vertex 0.809062 1.69552 2.56197 + vertex 0.809146 1.69091 2.56277 + vertex 0.811652 1.69324 2.56492 + endloop + endfacet + facet normal -0.703652 0.107271 0.702401 + outer loop + vertex 0.811345 1.69785 2.56391 + vertex 0.809062 1.69552 2.56197 + vertex 0.811652 1.69324 2.56492 + endloop + endfacet + facet normal -0.696295 0.109296 0.709386 + outer loop + vertex 0.811652 1.69324 2.56492 + vertex 0.814105 1.69558 2.56696 + vertex 0.811345 1.69785 2.56391 + endloop + endfacet + facet normal -0.698554 0.104518 0.707883 + outer loop + vertex 0.813646 1.69997 2.56586 + vertex 0.811345 1.69785 2.56391 + vertex 0.814105 1.69558 2.56696 + endloop + endfacet + facet normal -0.692841 0.106447 0.713191 + outer loop + vertex 0.813646 1.69997 2.56586 + vertex 0.814105 1.69558 2.56696 + vertex 0.816486 1.69819 2.56889 + endloop + endfacet + facet normal -0.694769 0.101442 0.712043 + outer loop + vertex 0.81584 1.70303 2.56757 + vertex 0.813646 1.69997 2.56586 + vertex 0.816486 1.69819 2.56889 + endloop + endfacet + facet normal -0.688969 0.103658 0.71734 + outer loop + vertex 0.81584 1.70303 2.56757 + vertex 0.816486 1.69819 2.56889 + vertex 0.818691 1.70087 2.57062 + endloop + endfacet + facet normal -0.692938 0.094755 0.714743 + outer loop + vertex 0.81584 1.70303 2.56757 + vertex 0.818691 1.70087 2.57062 + vertex 0.818145 1.70332 2.56976 + endloop + endfacet + facet normal -0.681255 0.10095 0.725052 + outer loop + vertex 0.82003 1.70405 2.57143 + vertex 0.818145 1.70332 2.56976 + vertex 0.818691 1.70087 2.57062 + endloop + endfacet + facet normal -0.678142 0.0988171 0.728257 + outer loop + vertex 0.818691 1.70087 2.57062 + vertex 0.821961 1.70074 2.57368 + vertex 0.82003 1.70405 2.57143 + endloop + endfacet + facet normal -0.672601 0.104948 0.732526 + outer loop + vertex 0.821961 1.70074 2.57368 + vertex 0.822805 1.70585 2.57372 + vertex 0.82003 1.70405 2.57143 + endloop + endfacet + facet normal -0.673212 0.106975 0.731671 + outer loop + vertex 0.82003 1.70405 2.57143 + vertex 0.822805 1.70585 2.57372 + vertex 0.820485 1.70835 2.57122 + endloop + endfacet + facet normal -0.682061 0.107504 0.72335 + outer loop + vertex 0.820485 1.70835 2.57122 + vertex 0.817997 1.70612 2.56921 + vertex 0.82003 1.70405 2.57143 + endloop + endfacet + facet normal -0.682151 0.10735 0.723288 + outer loop + vertex 0.817997 1.70612 2.56921 + vertex 0.818145 1.70332 2.56976 + vertex 0.82003 1.70405 2.57143 + endloop + endfacet + facet normal -0.69291 0.104813 0.713365 + outer loop + vertex 0.818145 1.70332 2.56976 + vertex 0.817997 1.70612 2.56921 + vertex 0.81584 1.70303 2.56757 + endloop + endfacet + facet normal -0.692259 0.103957 0.714122 + outer loop + vertex 0.81584 1.70303 2.56757 + vertex 0.817997 1.70612 2.56921 + vertex 0.815563 1.70822 2.56654 + endloop + endfacet + facet normal -0.697711 0.102653 0.708986 + outer loop + vertex 0.815563 1.70822 2.56654 + vertex 0.813092 1.70595 2.56444 + vertex 0.81584 1.70303 2.56757 + endloop + endfacet + facet normal -0.696601 0.104565 0.709798 + outer loop + vertex 0.813092 1.70595 2.56444 + vertex 0.813287 1.70286 2.56509 + vertex 0.81584 1.70303 2.56757 + endloop + endfacet + facet normal -0.702933 0.102905 0.703772 + outer loop + vertex 0.813287 1.70286 2.56509 + vertex 0.813092 1.70595 2.56444 + vertex 0.810794 1.70295 2.56258 + endloop + endfacet + facet normal -0.703054 0.101578 0.703844 + outer loop + vertex 0.810794 1.70295 2.56258 + vertex 0.813646 1.69997 2.56586 + vertex 0.813287 1.70286 2.56509 + endloop + endfacet + facet normal -0.703488 0.10375 0.703094 + outer loop + vertex 0.810794 1.70295 2.56258 + vertex 0.813092 1.70595 2.56444 + vertex 0.810537 1.70838 2.56153 + endloop + endfacet + facet normal -0.710748 0.102027 0.696009 + outer loop + vertex 0.810537 1.70838 2.56153 + vertex 0.808107 1.70608 2.55938 + vertex 0.810794 1.70295 2.56258 + endloop + endfacet + facet normal -0.704275 0.102241 0.702526 + outer loop + vertex 0.813092 1.70595 2.56444 + vertex 0.813078 1.71085 2.56371 + vertex 0.810537 1.70838 2.56153 + endloop + endfacet + facet normal -0.703897 0.101408 0.703026 + outer loop + vertex 0.810537 1.70838 2.56153 + vertex 0.813078 1.71085 2.56371 + vertex 0.810721 1.71351 2.56097 + endloop + endfacet + facet normal -0.711182 0.100879 0.695732 + outer loop + vertex 0.810721 1.71351 2.56097 + vertex 0.808125 1.71103 2.55868 + vertex 0.810537 1.70838 2.56153 + endloop + endfacet + facet normal -0.710322 0.098898 0.696895 + outer loop + vertex 0.808465 1.71609 2.5583 + vertex 0.808125 1.71103 2.55868 + vertex 0.810721 1.71351 2.56097 + endloop + endfacet + facet normal -0.709375 0.100484 0.697632 + outer loop + vertex 0.811168 1.71854 2.5607 + vertex 0.808465 1.71609 2.5583 + vertex 0.810721 1.71351 2.56097 + endloop + endfacet + facet normal -0.702922 0.100262 0.704165 + outer loop + vertex 0.810721 1.71351 2.56097 + vertex 0.813417 1.71596 2.56331 + vertex 0.811168 1.71854 2.5607 + endloop + endfacet + facet normal -0.70183 0.102052 0.704996 + outer loop + vertex 0.813417 1.71596 2.56331 + vertex 0.813904 1.72097 2.56307 + vertex 0.811168 1.71854 2.5607 + endloop + endfacet + facet normal -0.702409 0.103472 0.704212 + outer loop + vertex 0.811168 1.71854 2.5607 + vertex 0.813904 1.72097 2.56307 + vertex 0.811587 1.72338 2.56041 + endloop + endfacet + facet normal -0.708009 0.103615 0.698561 + outer loop + vertex 0.811587 1.72338 2.56041 + vertex 0.808901 1.72104 2.55803 + vertex 0.811168 1.71854 2.5607 + endloop + endfacet + facet normal -0.710666 0.110473 0.694802 + outer loop + vertex 0.809202 1.72585 2.55757 + vertex 0.808901 1.72104 2.55803 + vertex 0.811587 1.72338 2.56041 + endloop + endfacet + facet normal -0.70938 0.112792 0.695743 + outer loop + vertex 0.811767 1.72796 2.55985 + vertex 0.809202 1.72585 2.55757 + vertex 0.811587 1.72338 2.56041 + endloop + endfacet + facet normal -0.704003 0.113235 0.701112 + outer loop + vertex 0.811587 1.72338 2.56041 + vertex 0.814225 1.72572 2.56268 + vertex 0.811767 1.72796 2.55985 + endloop + endfacet + facet normal -0.702269 0.116637 0.702292 + outer loop + vertex 0.814225 1.72572 2.56268 + vertex 0.814169 1.73019 2.56188 + vertex 0.811767 1.72796 2.55985 + endloop + endfacet + facet normal -0.707037 0.127947 0.695505 + outer loop + vertex 0.811767 1.72796 2.55985 + vertex 0.814169 1.73019 2.56188 + vertex 0.811666 1.73231 2.55895 + endloop + endfacet + facet normal -0.712414 0.126727 0.690222 + outer loop + vertex 0.811666 1.73231 2.55895 + vertex 0.809433 1.73035 2.557 + vertex 0.811767 1.72796 2.55985 + endloop + endfacet + facet normal -0.695751 0.117838 0.708551 + outer loop + vertex 0.814169 1.73019 2.56188 + vertex 0.814225 1.72572 2.56268 + vertex 0.816869 1.72834 2.56484 + endloop + endfacet + facet normal -0.694252 0.121417 0.709417 + outer loop + vertex 0.816515 1.73281 2.56373 + vertex 0.814169 1.73019 2.56188 + vertex 0.816869 1.72834 2.56484 + endloop + endfacet + facet normal -0.69039 0.122606 0.712972 + outer loop + vertex 0.816869 1.72834 2.56484 + vertex 0.819438 1.73152 2.56678 + vertex 0.816515 1.73281 2.56373 + endloop + endfacet + facet normal -0.689592 0.125176 0.713297 + outer loop + vertex 0.818773 1.73555 2.56543 + vertex 0.816515 1.73281 2.56373 + vertex 0.819438 1.73152 2.56678 + endloop + endfacet + facet normal -0.68252 0.128416 0.719497 + outer loop + vertex 0.818773 1.73555 2.56543 + vertex 0.819438 1.73152 2.56678 + vertex 0.822089 1.73559 2.56857 + endloop + endfacet + facet normal -0.681862 0.135998 0.718728 + outer loop + vertex 0.818773 1.73555 2.56543 + vertex 0.822089 1.73559 2.56857 + vertex 0.820273 1.73892 2.56621 + endloop + endfacet + facet normal -0.685202 0.138332 0.715097 + outer loop + vertex 0.820273 1.73892 2.56621 + vertex 0.81832 1.73808 2.56451 + vertex 0.818773 1.73555 2.56543 + endloop + endfacet + facet normal -0.700311 0.130745 0.701762 + outer loop + vertex 0.816045 1.73774 2.5623 + vertex 0.818773 1.73555 2.56543 + vertex 0.81832 1.73808 2.56451 + endloop + endfacet + facet normal -0.687012 0.151394 0.710699 + outer loop + vertex 0.818345 1.74107 2.56389 + vertex 0.81832 1.73808 2.56451 + vertex 0.820273 1.73892 2.56621 + endloop + endfacet + facet normal -0.687856 0.15006 0.710167 + outer loop + vertex 0.820928 1.74344 2.56589 + vertex 0.818345 1.74107 2.56389 + vertex 0.820273 1.73892 2.56621 + endloop + endfacet + facet normal -0.681364 0.149568 0.7165 + outer loop + vertex 0.820273 1.73892 2.56621 + vertex 0.823173 1.74092 2.56856 + vertex 0.820928 1.74344 2.56589 + endloop + endfacet + facet normal -0.678418 0.13967 0.721277 + outer loop + vertex 0.822089 1.73559 2.56857 + vertex 0.823173 1.74092 2.56856 + vertex 0.820273 1.73892 2.56621 + endloop + endfacet + facet normal -0.697154 0.137375 0.703637 + outer loop + vertex 0.816045 1.73774 2.5623 + vertex 0.816515 1.73281 2.56373 + vertex 0.818773 1.73555 2.56543 + endloop + endfacet + facet normal -0.698916 0.136735 0.702011 + outer loop + vertex 0.816045 1.73774 2.5623 + vertex 0.813811 1.73448 2.56071 + vertex 0.816515 1.73281 2.56373 + endloop + endfacet + facet normal -0.683846 0.112456 0.720908 + outer loop + vertex 0.819911 1.72669 2.56798 + vertex 0.819438 1.73152 2.56678 + vertex 0.816869 1.72834 2.56484 + endloop + endfacet + facet normal -0.684752 0.109896 0.720443 + outer loop + vertex 0.816724 1.72356 2.56543 + vertex 0.819911 1.72669 2.56798 + vertex 0.816869 1.72834 2.56484 + endloop + endfacet + facet normal -0.682911 0.106146 0.722749 + outer loop + vertex 0.819124 1.72119 2.56804 + vertex 0.819911 1.72669 2.56798 + vertex 0.816724 1.72356 2.56543 + endloop + endfacet + facet normal -0.684129 0.103985 0.72191 + outer loop + vertex 0.8162 1.71848 2.56566 + vertex 0.819124 1.72119 2.56804 + vertex 0.816724 1.72356 2.56543 + endloop + endfacet + facet normal -0.692628 0.104485 0.713688 + outer loop + vertex 0.816724 1.72356 2.56543 + vertex 0.813904 1.72097 2.56307 + vertex 0.8162 1.71848 2.56566 + endloop + endfacet + facet normal -0.693297 0.10601 0.712812 + outer loop + vertex 0.814225 1.72572 2.56268 + vertex 0.813904 1.72097 2.56307 + vertex 0.816724 1.72356 2.56543 + endloop + endfacet + facet normal -0.685053 0.106009 0.720739 + outer loop + vertex 0.818518 1.71591 2.56825 + vertex 0.819124 1.72119 2.56804 + vertex 0.8162 1.71848 2.56566 + endloop + endfacet + facet normal -0.686541 0.103594 0.719674 + outer loop + vertex 0.815735 1.71331 2.56596 + vertex 0.818518 1.71591 2.56825 + vertex 0.8162 1.71848 2.56566 + endloop + endfacet + facet normal -0.695244 0.103885 0.711227 + outer loop + vertex 0.8162 1.71848 2.56566 + vertex 0.813417 1.71596 2.56331 + vertex 0.815735 1.71331 2.56596 + endloop + endfacet + facet normal -0.696423 0.101973 0.71035 + outer loop + vertex 0.813417 1.71596 2.56331 + vertex 0.813078 1.71085 2.56371 + vertex 0.815735 1.71331 2.56596 + endloop + endfacet + facet normal -0.697376 0.104144 0.709099 + outer loop + vertex 0.815735 1.71331 2.56596 + vertex 0.813078 1.71085 2.56371 + vertex 0.815563 1.70822 2.56654 + endloop + endfacet + facet normal -0.689908 0.10471 0.716284 + outer loop + vertex 0.815563 1.70822 2.56654 + vertex 0.81812 1.71076 2.56864 + vertex 0.815735 1.71331 2.56596 + endloop + endfacet + facet normal -0.68829 0.107426 0.717438 + outer loop + vertex 0.81812 1.71076 2.56864 + vertex 0.818518 1.71591 2.56825 + vertex 0.815735 1.71331 2.56596 + endloop + endfacet + facet normal -0.679144 0.107376 0.726109 + outer loop + vertex 0.818518 1.71591 2.56825 + vertex 0.81812 1.71076 2.56864 + vertex 0.820889 1.71336 2.57084 + endloop + endfacet + facet normal -0.677765 0.109625 0.727061 + outer loop + vertex 0.821484 1.71871 2.57059 + vertex 0.818518 1.71591 2.56825 + vertex 0.820889 1.71336 2.57084 + endloop + endfacet + facet normal -0.668655 0.10901 0.735539 + outer loop + vertex 0.820889 1.71336 2.57084 + vertex 0.823879 1.71619 2.57314 + vertex 0.821484 1.71871 2.57059 + endloop + endfacet + facet normal -0.668336 0.109528 0.735752 + outer loop + vertex 0.823879 1.71619 2.57314 + vertex 0.824786 1.72195 2.57311 + vertex 0.821484 1.71871 2.57059 + endloop + endfacet + facet normal -0.666064 0.105115 0.738451 + outer loop + vertex 0.821484 1.71871 2.57059 + vertex 0.824786 1.72195 2.57311 + vertex 0.822099 1.72386 2.57041 + endloop + endfacet + facet normal -0.667189 0.102599 0.737789 + outer loop + vertex 0.824786 1.72195 2.57311 + vertex 0.824703 1.72681 2.57235 + vertex 0.822099 1.72386 2.57041 + endloop + endfacet + facet normal -0.667032 0.102343 0.737967 + outer loop + vertex 0.822099 1.72386 2.57041 + vertex 0.824703 1.72681 2.57235 + vertex 0.822693 1.72768 2.57042 + endloop + endfacet + facet normal -0.675898 0.103736 0.729658 + outer loop + vertex 0.822693 1.72768 2.57042 + vertex 0.819911 1.72669 2.56798 + vertex 0.822099 1.72386 2.57041 + endloop + endfacet + facet normal -0.676571 0.109104 0.72825 + outer loop + vertex 0.822693 1.72768 2.57042 + vertex 0.822276 1.73084 2.56956 + vertex 0.819911 1.72669 2.56798 + endloop + endfacet + facet normal -0.659859 0.108239 0.743553 + outer loop + vertex 0.824786 1.72195 2.57311 + vertex 0.823879 1.71619 2.57314 + vertex 0.826909 1.71891 2.57543 + endloop + endfacet + facet normal -0.659997 0.108068 0.743455 + outer loop + vertex 0.827517 1.72286 2.5754 + vertex 0.824786 1.72195 2.57311 + vertex 0.826909 1.71891 2.57543 + endloop + endfacet + facet normal -0.655191 0.107368 0.747795 + outer loop + vertex 0.826909 1.71891 2.57543 + vertex 0.829556 1.72184 2.57733 + vertex 0.827517 1.72286 2.5754 + endloop + endfacet + facet normal -0.656562 0.103404 0.74715 + outer loop + vertex 0.82921 1.72517 2.57657 + vertex 0.827517 1.72286 2.5754 + vertex 0.829556 1.72184 2.57733 + endloop + endfacet + facet normal -0.650475 0.105199 0.752207 + outer loop + vertex 0.82921 1.72517 2.57657 + vertex 0.829556 1.72184 2.57733 + vertex 0.831953 1.72581 2.57885 + endloop + endfacet + facet normal -0.650188 0.101065 0.753021 + outer loop + vertex 0.82921 1.72517 2.57657 + vertex 0.831953 1.72581 2.57885 + vertex 0.829767 1.72883 2.57656 + endloop + endfacet + facet normal -0.650129 0.104857 0.752554 + outer loop + vertex 0.829556 1.72184 2.57733 + vertex 0.832109 1.72109 2.57964 + vertex 0.831953 1.72581 2.57885 + endloop + endfacet + facet normal -0.649015 0.109544 0.752848 + outer loop + vertex 0.829681 1.71691 2.57816 + vertex 0.832109 1.72109 2.57964 + vertex 0.829556 1.72184 2.57733 + endloop + endfacet + facet normal -0.648033 0.108625 0.753826 + outer loop + vertex 0.832465 1.71779 2.58042 + vertex 0.832109 1.72109 2.57964 + vertex 0.829681 1.71691 2.57816 + endloop + endfacet + facet normal -0.648329 0.111179 0.753199 + outer loop + vertex 0.832465 1.71779 2.58042 + vertex 0.829681 1.71691 2.57816 + vertex 0.831873 1.71387 2.58049 + endloop + endfacet + facet normal -0.639796 0.110022 0.760629 + outer loop + vertex 0.831873 1.71387 2.58049 + vertex 0.834555 1.71679 2.58233 + vertex 0.832465 1.71779 2.58042 + endloop + endfacet + facet normal -0.639796 0.11002 0.760629 + outer loop + vertex 0.834196 1.7201 2.58154 + vertex 0.832465 1.71779 2.58042 + vertex 0.834555 1.71679 2.58233 + endloop + endfacet + facet normal -0.628727 0.113268 0.769333 + outer loop + vertex 0.834196 1.7201 2.58154 + vertex 0.834555 1.71679 2.58233 + vertex 0.837037 1.72082 2.58376 + endloop + endfacet + facet normal -0.62831 0.108403 0.770374 + outer loop + vertex 0.834196 1.7201 2.58154 + vertex 0.837037 1.72082 2.58376 + vertex 0.834779 1.72379 2.5815 + endloop + endfacet + facet normal -0.640708 0.110246 0.759829 + outer loop + vertex 0.834779 1.72379 2.5815 + vertex 0.832109 1.72109 2.57964 + vertex 0.834196 1.7201 2.58154 + endloop + endfacet + facet normal -0.638738 0.106816 0.761974 + outer loop + vertex 0.831953 1.72581 2.57885 + vertex 0.832109 1.72109 2.57964 + vertex 0.834779 1.72379 2.5815 + endloop + endfacet + facet normal -0.639117 0.106015 0.761768 + outer loop + vertex 0.83534 1.72861 2.5813 + vertex 0.831953 1.72581 2.57885 + vertex 0.834779 1.72379 2.5815 + endloop + endfacet + facet normal -0.622425 0.104657 0.775651 + outer loop + vertex 0.834779 1.72379 2.5815 + vertex 0.83794 1.7262 2.58371 + vertex 0.83534 1.72861 2.5813 + endloop + endfacet + facet normal -0.620296 0.108168 0.776873 + outer loop + vertex 0.83794 1.7262 2.58371 + vertex 0.838605 1.73133 2.58353 + vertex 0.83534 1.72861 2.5813 + endloop + endfacet + facet normal -0.619483 0.106465 0.777757 + outer loop + vertex 0.83534 1.72861 2.5813 + vertex 0.838605 1.73133 2.58353 + vertex 0.835973 1.73375 2.5811 + endloop + endfacet + facet normal -0.632978 0.107698 0.766642 + outer loop + vertex 0.835973 1.73375 2.5811 + vertex 0.832781 1.73111 2.57884 + vertex 0.83534 1.72861 2.5813 + endloop + endfacet + facet normal -0.615481 0.113063 0.78 + outer loop + vertex 0.838605 1.73133 2.58353 + vertex 0.839494 1.73688 2.58343 + vertex 0.835973 1.73375 2.5811 + endloop + endfacet + facet normal -0.618486 0.118862 0.776754 + outer loop + vertex 0.835973 1.73375 2.5811 + vertex 0.839494 1.73688 2.58343 + vertex 0.836397 1.73886 2.58066 + endloop + endfacet + facet normal -0.629277 0.119 0.768016 + outer loop + vertex 0.836397 1.73886 2.58066 + vertex 0.83334 1.73615 2.57857 + vertex 0.835973 1.73375 2.5811 + endloop + endfacet + facet normal -0.614209 0.128203 0.77866 + outer loop + vertex 0.839494 1.73688 2.58343 + vertex 0.839359 1.74201 2.58247 + vertex 0.836397 1.73886 2.58066 + endloop + endfacet + facet normal -0.620887 0.138565 0.771556 + outer loop + vertex 0.836397 1.73886 2.58066 + vertex 0.839359 1.74201 2.58247 + vertex 0.836568 1.74363 2.57994 + endloop + endfacet + facet normal -0.625505 0.111897 0.772155 + outer loop + vertex 0.837037 1.72082 2.58376 + vertex 0.83794 1.7262 2.58371 + vertex 0.834779 1.72379 2.5815 + endloop + endfacet + facet normal -0.636949 0.101251 0.764228 + outer loop + vertex 0.832781 1.73111 2.57884 + vertex 0.831953 1.72581 2.57885 + vertex 0.83534 1.72861 2.5813 + endloop + endfacet + facet normal -0.63085 0.1153 0.76729 + outer loop + vertex 0.834555 1.71679 2.58233 + vertex 0.837158 1.71606 2.58457 + vertex 0.837037 1.72082 2.58376 + endloop + endfacet + facet normal -0.631505 0.11255 0.76716 + outer loop + vertex 0.834687 1.7119 2.58315 + vertex 0.837158 1.71606 2.58457 + vertex 0.834555 1.71679 2.58233 + endloop + endfacet + facet normal -0.632251 0.113237 0.766443 + outer loop + vertex 0.837492 1.71276 2.58534 + vertex 0.837158 1.71606 2.58457 + vertex 0.834687 1.7119 2.58315 + endloop + endfacet + facet normal -0.631699 0.108617 0.767566 + outer loop + vertex 0.837492 1.71276 2.58534 + vertex 0.834687 1.7119 2.58315 + vertex 0.836866 1.70895 2.58536 + endloop + endfacet + facet normal -0.615276 0.106015 0.78115 + outer loop + vertex 0.836866 1.70895 2.58536 + vertex 0.839576 1.71174 2.58712 + vertex 0.837492 1.71276 2.58534 + endloop + endfacet + facet normal -0.613515 0.110855 0.781864 + outer loop + vertex 0.839279 1.71506 2.58641 + vertex 0.837492 1.71276 2.58534 + vertex 0.839576 1.71174 2.58712 + endloop + endfacet + facet normal -0.597782 0.114706 0.79341 + outer loop + vertex 0.839279 1.71506 2.58641 + vertex 0.839576 1.71174 2.58712 + vertex 0.842245 1.71572 2.58855 + endloop + endfacet + facet normal -0.598109 0.11909 0.792517 + outer loop + vertex 0.839279 1.71506 2.58641 + vertex 0.842245 1.71572 2.58855 + vertex 0.839945 1.71883 2.58635 + endloop + endfacet + facet normal -0.616747 0.12213 0.77763 + outer loop + vertex 0.839945 1.71883 2.58635 + vertex 0.837158 1.71606 2.58457 + vertex 0.839279 1.71506 2.58641 + endloop + endfacet + facet normal -0.61425 0.117942 0.780248 + outer loop + vertex 0.837037 1.72082 2.58376 + vertex 0.837158 1.71606 2.58457 + vertex 0.839945 1.71883 2.58635 + endloop + endfacet + facet normal -0.613767 0.118945 0.780476 + outer loop + vertex 0.840636 1.72386 2.58613 + vertex 0.837037 1.72082 2.58376 + vertex 0.839945 1.71883 2.58635 + endloop + endfacet + facet normal -0.596397 0.117162 0.794093 + outer loop + vertex 0.839945 1.71883 2.58635 + vertex 0.843306 1.72134 2.5885 + vertex 0.840636 1.72386 2.58613 + endloop + endfacet + facet normal -0.597532 0.119753 0.792852 + outer loop + vertex 0.842245 1.71572 2.58855 + vertex 0.843306 1.72134 2.5885 + vertex 0.839945 1.71883 2.58635 + endloop + endfacet + facet normal -0.597613 0.114538 0.793561 + outer loop + vertex 0.839576 1.71174 2.58712 + vertex 0.842258 1.71057 2.58931 + vertex 0.842245 1.71572 2.58855 + endloop + endfacet + facet normal -0.586006 0.115801 0.801989 + outer loop + vertex 0.842245 1.71572 2.58855 + vertex 0.842258 1.71057 2.58931 + vertex 0.845373 1.71357 2.59115 + endloop + endfacet + facet normal -0.585482 0.116845 0.802221 + outer loop + vertex 0.845998 1.71874 2.59085 + vertex 0.842245 1.71572 2.58855 + vertex 0.845373 1.71357 2.59115 + endloop + endfacet + facet normal -0.576076 0.116104 0.809108 + outer loop + vertex 0.845373 1.71357 2.59115 + vertex 0.848756 1.7163 2.59317 + vertex 0.845998 1.71874 2.59085 + endloop + endfacet + facet normal -0.576647 0.115196 0.808831 + outer loop + vertex 0.848756 1.7163 2.59317 + vertex 0.849697 1.72174 2.59306 + vertex 0.845998 1.71874 2.59085 + endloop + endfacet + facet normal -0.570878 0.114279 0.813043 + outer loop + vertex 0.849697 1.72174 2.59306 + vertex 0.848756 1.7163 2.59317 + vertex 0.851989 1.71873 2.59509 + endloop + endfacet + facet normal -0.572922 0.111968 0.811926 + outer loop + vertex 0.852675 1.72242 2.59507 + vertex 0.849697 1.72174 2.59306 + vertex 0.851989 1.71873 2.59509 + endloop + endfacet + facet normal -0.56728 0.110945 0.816018 + outer loop + vertex 0.851989 1.71873 2.59509 + vertex 0.854877 1.7214 2.59674 + vertex 0.852675 1.72242 2.59507 + endloop + endfacet + facet normal -0.567934 0.109172 0.815802 + outer loop + vertex 0.854586 1.72475 2.59609 + vertex 0.852675 1.72242 2.59507 + vertex 0.854877 1.7214 2.59674 + endloop + endfacet + facet normal -0.56395 0.110032 0.818445 + outer loop + vertex 0.854586 1.72475 2.59609 + vertex 0.854877 1.7214 2.59674 + vertex 0.857764 1.72564 2.59816 + endloop + endfacet + facet normal -0.563534 0.106914 0.819145 + outer loop + vertex 0.854586 1.72475 2.59609 + vertex 0.857764 1.72564 2.59816 + vertex 0.855331 1.72875 2.59608 + endloop + endfacet + facet normal -0.571245 0.108333 0.813599 + outer loop + vertex 0.855331 1.72875 2.59608 + vertex 0.852334 1.7258 2.59437 + vertex 0.854586 1.72475 2.59609 + endloop + endfacet + facet normal -0.564484 0.105827 0.818632 + outer loop + vertex 0.857764 1.72564 2.59816 + vertex 0.859196 1.73185 2.59834 + vertex 0.855331 1.72875 2.59608 + endloop + endfacet + facet normal -0.562582 0.102162 0.820405 + outer loop + vertex 0.855331 1.72875 2.59608 + vertex 0.859196 1.73185 2.59834 + vertex 0.855888 1.73393 2.59582 + endloop + endfacet + facet normal -0.574147 0.102994 0.812248 + outer loop + vertex 0.855888 1.73393 2.59582 + vertex 0.852183 1.73073 2.5936 + vertex 0.855331 1.72875 2.59608 + endloop + endfacet + facet normal -0.571472 0.108683 0.813393 + outer loop + vertex 0.852183 1.73073 2.5936 + vertex 0.852334 1.7258 2.59437 + vertex 0.855331 1.72875 2.59608 + endloop + endfacet + facet normal -0.577777 0.107813 0.809042 + outer loop + vertex 0.849578 1.72665 2.59229 + vertex 0.852334 1.7258 2.59437 + vertex 0.852183 1.73073 2.5936 + endloop + endfacet + facet normal -0.581137 0.11087 0.806218 + outer loop + vertex 0.849214 1.73003 2.59156 + vertex 0.849578 1.72665 2.59229 + vertex 0.852183 1.73073 2.5936 + endloop + endfacet + facet normal -0.580589 0.105158 0.807377 + outer loop + vertex 0.849214 1.73003 2.59156 + vertex 0.852183 1.73073 2.5936 + vertex 0.849839 1.73373 2.59153 + endloop + endfacet + facet normal -0.583374 0.105611 0.805308 + outer loop + vertex 0.849839 1.73373 2.59153 + vertex 0.847058 1.7311 2.58986 + vertex 0.849214 1.73003 2.59156 + endloop + endfacet + facet normal -0.584305 0.107152 0.804429 + outer loop + vertex 0.847204 1.73556 2.58937 + vertex 0.847058 1.7311 2.58986 + vertex 0.849839 1.73373 2.59153 + endloop + endfacet + facet normal -0.581725 0.103825 0.806732 + outer loop + vertex 0.852183 1.73073 2.5936 + vertex 0.85303 1.7362 2.59351 + vertex 0.849839 1.73373 2.59153 + endloop + endfacet + facet normal -0.583209 0.106936 0.805252 + outer loop + vertex 0.849839 1.73373 2.59153 + vertex 0.85303 1.7362 2.59351 + vertex 0.850295 1.73855 2.59122 + endloop + endfacet + facet normal -0.582285 0.110577 0.80543 + outer loop + vertex 0.849214 1.73003 2.59156 + vertex 0.847379 1.72775 2.59054 + vertex 0.849578 1.72665 2.59229 + endloop + endfacet + facet normal -0.580548 0.115035 0.806059 + outer loop + vertex 0.846703 1.72386 2.59061 + vertex 0.849578 1.72665 2.59229 + vertex 0.847379 1.72775 2.59054 + endloop + endfacet + facet normal -0.584452 0.115661 0.803143 + outer loop + vertex 0.847379 1.72775 2.59054 + vertex 0.844369 1.72703 2.58846 + vertex 0.846703 1.72386 2.59061 + endloop + endfacet + facet normal -0.584491 0.115617 0.803121 + outer loop + vertex 0.844369 1.72703 2.58846 + vertex 0.843306 1.72134 2.5885 + vertex 0.846703 1.72386 2.59061 + endloop + endfacet + facet normal -0.585585 0.118049 0.801969 + outer loop + vertex 0.846703 1.72386 2.59061 + vertex 0.843306 1.72134 2.5885 + vertex 0.845998 1.71874 2.59085 + endloop + endfacet + facet normal -0.577683 0.117232 0.807799 + outer loop + vertex 0.845998 1.71874 2.59085 + vertex 0.849697 1.72174 2.59306 + vertex 0.846703 1.72386 2.59061 + endloop + endfacet + facet normal -0.585868 0.117625 0.801825 + outer loop + vertex 0.843306 1.72134 2.5885 + vertex 0.842245 1.71572 2.58855 + vertex 0.845998 1.71874 2.59085 + endloop + endfacet + facet normal -0.583848 0.109403 0.804458 + outer loop + vertex 0.847379 1.72775 2.59054 + vertex 0.847058 1.7311 2.58986 + vertex 0.844369 1.72703 2.58846 + endloop + endfacet + facet normal -0.579607 0.113532 0.806949 + outer loop + vertex 0.849697 1.72174 2.59306 + vertex 0.849578 1.72665 2.59229 + vertex 0.846703 1.72386 2.59061 + endloop + endfacet + facet normal -0.576124 0.114 0.809374 + outer loop + vertex 0.849697 1.72174 2.59306 + vertex 0.852334 1.7258 2.59437 + vertex 0.849578 1.72665 2.59229 + endloop + endfacet + facet normal -0.581728 0.109908 0.805924 + outer loop + vertex 0.847379 1.72775 2.59054 + vertex 0.849214 1.73003 2.59156 + vertex 0.847058 1.7311 2.58986 + endloop + endfacet + facet normal -0.573997 0.102723 0.812389 + outer loop + vertex 0.85303 1.7362 2.59351 + vertex 0.852183 1.73073 2.5936 + vertex 0.855888 1.73393 2.59582 + endloop + endfacet + facet normal -0.5746 0.101665 0.812095 + outer loop + vertex 0.856337 1.73901 2.5955 + vertex 0.85303 1.7362 2.59351 + vertex 0.855888 1.73393 2.59582 + endloop + endfacet + facet normal -0.564809 0.101233 0.818989 + outer loop + vertex 0.855888 1.73393 2.59582 + vertex 0.859226 1.7372 2.59771 + vertex 0.856337 1.73901 2.5955 + endloop + endfacet + facet normal -0.562948 0.105159 0.819775 + outer loop + vertex 0.859226 1.7372 2.59771 + vertex 0.8595 1.742 2.59729 + vertex 0.856337 1.73901 2.5955 + endloop + endfacet + facet normal -0.566637 0.11106 0.816449 + outer loop + vertex 0.856337 1.73901 2.5955 + vertex 0.8595 1.742 2.59729 + vertex 0.856858 1.74375 2.59521 + endloop + endfacet + facet normal -0.576541 0.111728 0.809393 + outer loop + vertex 0.856858 1.74375 2.59521 + vertex 0.853645 1.74129 2.59327 + vertex 0.856337 1.73901 2.5955 + endloop + endfacet + facet normal -0.551657 0.105196 0.82741 + outer loop + vertex 0.859226 1.7372 2.59771 + vertex 0.862379 1.74053 2.59939 + vertex 0.8595 1.742 2.59729 + endloop + endfacet + facet normal -0.547457 0.115461 0.82883 + outer loop + vertex 0.862379 1.74053 2.59939 + vertex 0.862658 1.74534 2.59891 + vertex 0.8595 1.742 2.59729 + endloop + endfacet + facet normal -0.550896 0.120143 0.825881 + outer loop + vertex 0.8595 1.742 2.59729 + vertex 0.862658 1.74534 2.59891 + vertex 0.859768 1.74643 2.59682 + endloop + endfacet + facet normal -0.540604 0.115516 0.833309 + outer loop + vertex 0.862658 1.74534 2.59891 + vertex 0.862379 1.74053 2.59939 + vertex 0.865711 1.74377 2.6011 + endloop + endfacet + facet normal -0.537026 0.124026 0.834398 + outer loop + vertex 0.866043 1.74878 2.60057 + vertex 0.862658 1.74534 2.59891 + vertex 0.865711 1.74377 2.6011 + endloop + endfacet + facet normal -0.533773 0.12403 0.836483 + outer loop + vertex 0.865711 1.74377 2.6011 + vertex 0.869111 1.74719 2.60277 + vertex 0.866043 1.74878 2.60057 + endloop + endfacet + facet normal -0.532424 0.12718 0.836869 + outer loop + vertex 0.869111 1.74719 2.60277 + vertex 0.869467 1.75203 2.60226 + vertex 0.866043 1.74878 2.60057 + endloop + endfacet + facet normal -0.537368 0.134641 0.832531 + outer loop + vertex 0.866043 1.74878 2.60057 + vertex 0.869467 1.75203 2.60226 + vertex 0.866677 1.75369 2.60019 + endloop + endfacet + facet normal -0.526073 0.127134 0.840883 + outer loop + vertex 0.869111 1.74719 2.60277 + vertex 0.872425 1.75059 2.60433 + vertex 0.869467 1.75203 2.60226 + endloop + endfacet + facet normal -0.529176 0.119545 0.840049 + outer loop + vertex 0.872425 1.75059 2.60433 + vertex 0.872734 1.75539 2.60384 + vertex 0.869467 1.75203 2.60226 + endloop + endfacet + facet normal -0.526683 0.114119 0.842367 + outer loop + vertex 0.869064 1.7419 2.60345 + vertex 0.869111 1.74719 2.60277 + vertex 0.865711 1.74377 2.6011 + endloop + endfacet + facet normal -0.528841 0.109357 0.841646 + outer loop + vertex 0.865201 1.73886 2.60142 + vertex 0.869064 1.7419 2.60345 + vertex 0.865711 1.74377 2.6011 + endloop + endfacet + facet normal -0.526162 0.104405 0.843951 + outer loop + vertex 0.867631 1.73583 2.60331 + vertex 0.869064 1.7419 2.60345 + vertex 0.865201 1.73886 2.60142 + endloop + endfacet + facet normal -0.527867 0.10252 0.843117 + outer loop + vertex 0.864406 1.73504 2.60139 + vertex 0.867631 1.73583 2.60331 + vertex 0.865201 1.73886 2.60142 + endloop + endfacet + facet normal -0.540037 0.105122 0.83505 + outer loop + vertex 0.865201 1.73886 2.60142 + vertex 0.86213 1.73604 2.59979 + vertex 0.864406 1.73504 2.60139 + endloop + endfacet + facet normal -0.540958 0.102569 0.834772 + outer loop + vertex 0.862405 1.7327 2.60038 + vertex 0.864406 1.73504 2.60139 + vertex 0.86213 1.73604 2.59979 + endloop + endfacet + facet normal -0.551986 0.100432 0.827783 + outer loop + vertex 0.862405 1.7327 2.60038 + vertex 0.86213 1.73604 2.59979 + vertex 0.859196 1.73185 2.59834 + endloop + endfacet + facet normal -0.552436 0.103895 0.827055 + outer loop + vertex 0.862405 1.7327 2.60038 + vertex 0.859196 1.73185 2.59834 + vertex 0.861587 1.72881 2.60032 + endloop + endfacet + facet normal -0.539803 0.101111 0.835697 + outer loop + vertex 0.861587 1.72881 2.60032 + vertex 0.864677 1.73169 2.60197 + vertex 0.862405 1.7327 2.60038 + endloop + endfacet + facet normal -0.542879 0.105883 0.833109 + outer loop + vertex 0.864396 1.72715 2.60236 + vertex 0.864677 1.73169 2.60197 + vertex 0.861587 1.72881 2.60032 + endloop + endfacet + facet normal -0.542746 0.106171 0.833159 + outer loop + vertex 0.861051 1.72382 2.60061 + vertex 0.864396 1.72715 2.60236 + vertex 0.861587 1.72881 2.60032 + endloop + endfacet + facet normal -0.55545 0.107044 0.824631 + outer loop + vertex 0.861587 1.72881 2.60032 + vertex 0.857764 1.72564 2.59816 + vertex 0.861051 1.72382 2.60061 + endloop + endfacet + facet normal -0.554854 0.108418 0.824853 + outer loop + vertex 0.857764 1.72564 2.59816 + vertex 0.857741 1.7203 2.59884 + vertex 0.861051 1.72382 2.60061 + endloop + endfacet + facet normal -0.554551 0.108003 0.825111 + outer loop + vertex 0.861051 1.72382 2.60061 + vertex 0.857741 1.7203 2.59884 + vertex 0.860754 1.71876 2.60107 + endloop + endfacet + facet normal -0.545322 0.108021 0.831237 + outer loop + vertex 0.860754 1.71876 2.60107 + vertex 0.864099 1.72228 2.60281 + vertex 0.861051 1.72382 2.60061 + endloop + endfacet + facet normal -0.544968 0.10754 0.831532 + outer loop + vertex 0.864054 1.71696 2.60347 + vertex 0.864099 1.72228 2.60281 + vertex 0.860754 1.71876 2.60107 + endloop + endfacet + facet normal -0.545084 0.107272 0.83149 + outer loop + vertex 0.860227 1.7138 2.60137 + vertex 0.864054 1.71696 2.60347 + vertex 0.860754 1.71876 2.60107 + endloop + endfacet + facet normal -0.5544 0.10789 0.825228 + outer loop + vertex 0.860754 1.71876 2.60107 + vertex 0.857465 1.71546 2.59929 + vertex 0.860227 1.7138 2.60137 + endloop + endfacet + facet normal -0.554157 0.10841 0.825322 + outer loop + vertex 0.857465 1.71546 2.59929 + vertex 0.857205 1.71096 2.59971 + vertex 0.860227 1.7138 2.60137 + endloop + endfacet + facet normal -0.554917 0.10961 0.824653 + outer loop + vertex 0.860227 1.7138 2.60137 + vertex 0.857205 1.71096 2.59971 + vertex 0.859417 1.70993 2.60134 + endloop + endfacet + facet normal -0.545571 0.107596 0.831129 + outer loop + vertex 0.859417 1.70993 2.60134 + vertex 0.862595 1.71079 2.60331 + vertex 0.860227 1.7138 2.60137 + endloop + endfacet + facet normal -0.545792 0.109249 0.830768 + outer loop + vertex 0.859417 1.70993 2.60134 + vertex 0.859682 1.70662 2.60195 + vertex 0.862595 1.71079 2.60331 + endloop + endfacet + facet normal -0.543008 0.106596 0.832935 + outer loop + vertex 0.859682 1.70662 2.60195 + vertex 0.862576 1.70546 2.60398 + vertex 0.862595 1.71079 2.60331 + endloop + endfacet + facet normal -0.542728 0.107428 0.83301 + outer loop + vertex 0.859411 1.70213 2.60235 + vertex 0.862576 1.70546 2.60398 + vertex 0.859682 1.70662 2.60195 + endloop + endfacet + facet normal -0.552519 0.10744 0.826547 + outer loop + vertex 0.859411 1.70213 2.60235 + vertex 0.859682 1.70662 2.60195 + vertex 0.856733 1.70392 2.60032 + endloop + endfacet + facet normal -0.553247 0.10601 0.826245 + outer loop + vertex 0.856139 1.69904 2.60055 + vertex 0.859411 1.70213 2.60235 + vertex 0.856733 1.70392 2.60032 + endloop + endfacet + facet normal -0.558983 0.106525 0.822308 + outer loop + vertex 0.856733 1.70392 2.60032 + vertex 0.853378 1.70136 2.59838 + vertex 0.856139 1.69904 2.60055 + endloop + endfacet + facet normal -0.559971 0.104909 0.821843 + outer loop + vertex 0.853378 1.70136 2.59838 + vertex 0.852417 1.69577 2.59843 + vertex 0.856139 1.69904 2.60055 + endloop + endfacet + facet normal -0.557532 0.100728 0.824022 + outer loop + vertex 0.856139 1.69904 2.60055 + vertex 0.852417 1.69577 2.59843 + vertex 0.855824 1.69391 2.60097 + endloop + endfacet + facet normal -0.553055 0.100698 0.827037 + outer loop + vertex 0.855824 1.69391 2.60097 + vertex 0.859149 1.6973 2.60278 + vertex 0.856139 1.69904 2.60055 + endloop + endfacet + facet normal -0.549801 0.0960572 0.829754 + outer loop + vertex 0.859264 1.69207 2.60346 + vertex 0.859149 1.6973 2.60278 + vertex 0.855824 1.69391 2.60097 + endloop + endfacet + facet normal -0.550332 0.094787 0.829548 + outer loop + vertex 0.855532 1.68879 2.60136 + vertex 0.859264 1.69207 2.60346 + vertex 0.855824 1.69391 2.60097 + endloop + endfacet + facet normal -0.554914 0.0948144 0.826487 + outer loop + vertex 0.855824 1.69391 2.60097 + vertex 0.852537 1.69053 2.59915 + vertex 0.855532 1.68879 2.60136 + endloop + endfacet + facet normal -0.554725 0.0952371 0.826565 + outer loop + vertex 0.852537 1.69053 2.59915 + vertex 0.852306 1.68571 2.59955 + vertex 0.855532 1.68879 2.60136 + endloop + endfacet + facet normal -0.552994 0.0925567 0.828028 + outer loop + vertex 0.855532 1.68879 2.60136 + vertex 0.852306 1.68571 2.59955 + vertex 0.854988 1.68394 2.60154 + endloop + endfacet + facet normal -0.547407 0.0920668 0.831787 + outer loop + vertex 0.854988 1.68394 2.60154 + vertex 0.858325 1.68648 2.60345 + vertex 0.855532 1.68879 2.60136 + endloop + endfacet + facet normal -0.546775 0.0908194 0.832339 + outer loop + vertex 0.857388 1.68091 2.60344 + vertex 0.858325 1.68648 2.60345 + vertex 0.854988 1.68394 2.60154 + endloop + endfacet + facet normal -0.544301 0.0935983 0.833652 + outer loop + vertex 0.854287 1.68027 2.60149 + vertex 0.857388 1.68091 2.60344 + vertex 0.854988 1.68394 2.60154 + endloop + endfacet + facet normal -0.544524 0.0959584 0.833238 + outer loop + vertex 0.854287 1.68027 2.60149 + vertex 0.85458 1.67692 2.60207 + vertex 0.857388 1.68091 2.60344 + endloop + endfacet + facet normal -0.540367 0.0919373 0.836392 + outer loop + vertex 0.85458 1.67692 2.60207 + vertex 0.857515 1.67559 2.60411 + vertex 0.857388 1.68091 2.60344 + endloop + endfacet + facet normal -0.536869 0.0922987 0.838601 + outer loop + vertex 0.857388 1.68091 2.60344 + vertex 0.857515 1.67559 2.60411 + vertex 0.86087 1.67885 2.6059 + endloop + endfacet + facet normal -0.538595 0.0885299 0.837901 + outer loop + vertex 0.861152 1.68409 2.60553 + vertex 0.857388 1.68091 2.60344 + vertex 0.86087 1.67885 2.6059 + endloop + endfacet + facet normal -0.529788 0.0884528 0.843505 + outer loop + vertex 0.86087 1.67885 2.6059 + vertex 0.864252 1.68219 2.60767 + vertex 0.861152 1.68409 2.60553 + endloop + endfacet + facet normal -0.529703 0.0886301 0.84354 + outer loop + vertex 0.864252 1.68219 2.60767 + vertex 0.864477 1.68717 2.60729 + vertex 0.861152 1.68409 2.60553 + endloop + endfacet + facet normal -0.528714 0.0871181 0.844317 + outer loop + vertex 0.861152 1.68409 2.60553 + vertex 0.864477 1.68717 2.60729 + vertex 0.861698 1.68905 2.60536 + endloop + endfacet + facet normal -0.540071 0.0881142 0.836994 + outer loop + vertex 0.861698 1.68905 2.60536 + vertex 0.858325 1.68648 2.60345 + vertex 0.861152 1.68409 2.60553 + endloop + endfacet + facet normal -0.540924 0.0897726 0.836267 + outer loop + vertex 0.859264 1.69207 2.60346 + vertex 0.858325 1.68648 2.60345 + vertex 0.861698 1.68905 2.60536 + endloop + endfacet + facet normal -0.541247 0.0894054 0.836097 + outer loop + vertex 0.862398 1.69282 2.60541 + vertex 0.859264 1.69207 2.60346 + vertex 0.861698 1.68905 2.60536 + endloop + endfacet + facet normal -0.526472 0.0865311 0.845777 + outer loop + vertex 0.861698 1.68905 2.60536 + vertex 0.864698 1.69175 2.60695 + vertex 0.862398 1.69282 2.60541 + endloop + endfacet + facet normal -0.52787 0.0887328 0.844677 + outer loop + vertex 0.864477 1.68717 2.60729 + vertex 0.864698 1.69175 2.60695 + vertex 0.861698 1.68905 2.60536 + endloop + endfacet + facet normal -0.513399 0.0886991 0.853554 + outer loop + vertex 0.864477 1.68717 2.60729 + vertex 0.867693 1.69052 2.60888 + vertex 0.864698 1.69175 2.60695 + endloop + endfacet + facet normal -0.515157 0.0909984 0.852252 + outer loop + vertex 0.867462 1.68559 2.60926 + vertex 0.867693 1.69052 2.60888 + vertex 0.864477 1.68717 2.60729 + endloop + endfacet + facet normal -0.516153 0.08866 0.851895 + outer loop + vertex 0.864252 1.68219 2.60767 + vertex 0.867462 1.68559 2.60926 + vertex 0.864477 1.68717 2.60729 + endloop + endfacet + facet normal -0.517847 0.0908473 0.850636 + outer loop + vertex 0.867269 1.681 2.60964 + vertex 0.867462 1.68559 2.60926 + vertex 0.864252 1.68219 2.60767 + endloop + endfacet + facet normal -0.518661 0.0883909 0.850399 + outer loop + vertex 0.864401 1.67686 2.60832 + vertex 0.867269 1.681 2.60964 + vertex 0.864252 1.68219 2.60767 + endloop + endfacet + facet normal -0.517446 0.0872784 0.851254 + outer loop + vertex 0.867635 1.67768 2.6102 + vertex 0.867269 1.681 2.60964 + vertex 0.864401 1.67686 2.60832 + endloop + endfacet + facet normal -0.516841 0.0831066 0.852038 + outer loop + vertex 0.867635 1.67768 2.6102 + vertex 0.864401 1.67686 2.60832 + vertex 0.866936 1.67394 2.61014 + endloop + endfacet + facet normal -0.497096 0.0792271 0.864071 + outer loop + vertex 0.866936 1.67394 2.61014 + vertex 0.870117 1.67697 2.61169 + vertex 0.867635 1.67768 2.6102 + endloop + endfacet + facet normal -0.496285 0.0824203 0.864238 + outer loop + vertex 0.869657 1.6802 2.61112 + vertex 0.867635 1.67768 2.6102 + vertex 0.870117 1.67697 2.61169 + endloop + endfacet + facet normal -0.498318 0.080951 0.863207 + outer loop + vertex 0.8699 1.67236 2.612 + vertex 0.870117 1.67697 2.61169 + vertex 0.866936 1.67394 2.61014 + endloop + endfacet + facet normal -0.499164 0.0790056 0.862898 + outer loop + vertex 0.866369 1.66906 2.61026 + vertex 0.8699 1.67236 2.612 + vertex 0.866936 1.67394 2.61014 + endloop + endfacet + facet normal -0.514631 0.0805779 0.853617 + outer loop + vertex 0.866936 1.67394 2.61014 + vertex 0.863466 1.6713 2.6083 + vertex 0.866369 1.66906 2.61026 + endloop + endfacet + facet normal -0.514821 0.080258 0.853533 + outer loop + vertex 0.863466 1.6713 2.6083 + vertex 0.862555 1.6658 2.60827 + vertex 0.866369 1.66906 2.61026 + endloop + endfacet + facet normal -0.513401 0.0779405 0.854602 + outer loop + vertex 0.866369 1.66906 2.61026 + vertex 0.862555 1.6658 2.60827 + vertex 0.866041 1.66398 2.61053 + endloop + endfacet + facet normal -0.499944 0.077489 0.862584 + outer loop + vertex 0.866041 1.66398 2.61053 + vertex 0.869497 1.66732 2.61223 + vertex 0.866369 1.66906 2.61026 + endloop + endfacet + facet normal -0.498305 0.0752076 0.863734 + outer loop + vertex 0.869235 1.66231 2.61252 + vertex 0.869497 1.66732 2.61223 + vertex 0.866041 1.66398 2.61053 + endloop + endfacet + facet normal -0.498571 0.074581 0.863635 + outer loop + vertex 0.865889 1.65896 2.61087 + vertex 0.869235 1.66231 2.61252 + vertex 0.866041 1.66398 2.61053 + endloop + endfacet + facet normal -0.510346 0.0744606 0.856739 + outer loop + vertex 0.866041 1.66398 2.61053 + vertex 0.862749 1.66058 2.60886 + vertex 0.865889 1.65896 2.61087 + endloop + endfacet + facet normal -0.510483 0.0741296 0.856687 + outer loop + vertex 0.862749 1.66058 2.60886 + vertex 0.862602 1.65564 2.6092 + vertex 0.865889 1.65896 2.61087 + endloop + endfacet + facet normal -0.507854 0.0705934 0.858546 + outer loop + vertex 0.865889 1.65896 2.61087 + vertex 0.862602 1.65564 2.6092 + vertex 0.865658 1.654 2.61114 + endloop + endfacet + facet normal -0.495937 0.0704189 0.865498 + outer loop + vertex 0.865658 1.654 2.61114 + vertex 0.869015 1.65734 2.6128 + vertex 0.865889 1.65896 2.61087 + endloop + endfacet + facet normal -0.494031 0.0678653 0.866791 + outer loop + vertex 0.868744 1.65231 2.61303 + vertex 0.869015 1.65734 2.6128 + vertex 0.865658 1.654 2.61114 + endloop + endfacet + facet normal -0.494048 0.0678265 0.866785 + outer loop + vertex 0.865334 1.6491 2.61134 + vertex 0.868744 1.65231 2.61303 + vertex 0.865658 1.654 2.61114 + endloop + endfacet + facet normal -0.505833 0.0683261 0.859921 + outer loop + vertex 0.865658 1.654 2.61114 + vertex 0.862375 1.65072 2.60947 + vertex 0.865334 1.6491 2.61134 + endloop + endfacet + facet normal -0.505651 0.0687443 0.859995 + outer loop + vertex 0.862375 1.65072 2.60947 + vertex 0.862232 1.6461 2.60976 + vertex 0.865334 1.6491 2.61134 + endloop + endfacet + facet normal -0.505445 0.0684547 0.860139 + outer loop + vertex 0.865334 1.6491 2.61134 + vertex 0.862232 1.6461 2.60976 + vertex 0.864698 1.64518 2.61128 + endloop + endfacet + facet normal -0.491789 0.0661102 0.868201 + outer loop + vertex 0.864698 1.64518 2.61128 + vertex 0.868448 1.64648 2.61331 + vertex 0.865334 1.6491 2.61134 + endloop + endfacet + facet normal -0.491351 0.0642529 0.868588 + outer loop + vertex 0.864698 1.64518 2.61128 + vertex 0.865081 1.64181 2.61175 + vertex 0.868448 1.64648 2.61331 + endloop + endfacet + facet normal -0.491684 0.0645634 0.868377 + outer loop + vertex 0.865081 1.64181 2.61175 + vertex 0.868172 1.64067 2.61358 + vertex 0.868448 1.64648 2.61331 + endloop + endfacet + facet normal -0.482275 0.0643657 0.873652 + outer loop + vertex 0.868448 1.64648 2.61331 + vertex 0.868172 1.64067 2.61358 + vertex 0.871614 1.64389 2.61524 + endloop + endfacet + facet normal -0.481424 0.0656808 0.874023 + outer loop + vertex 0.87228 1.6478 2.61532 + vertex 0.868448 1.64648 2.61331 + vertex 0.871614 1.64389 2.61524 + endloop + endfacet + facet normal -0.470191 0.0636518 0.880266 + outer loop + vertex 0.871614 1.64389 2.61524 + vertex 0.874951 1.64694 2.61681 + vertex 0.87228 1.6478 2.61532 + endloop + endfacet + facet normal -0.471186 0.0650657 0.879631 + outer loop + vertex 0.874699 1.64227 2.61702 + vertex 0.874951 1.64694 2.61681 + vertex 0.871614 1.64389 2.61524 + endloop + endfacet + facet normal -0.471956 0.0632828 0.879348 + outer loop + vertex 0.871303 1.639 2.61543 + vertex 0.874699 1.64227 2.61702 + vertex 0.871614 1.64389 2.61524 + endloop + endfacet + facet normal -0.470863 0.0618122 0.880038 + outer loop + vertex 0.874465 1.63735 2.61724 + vertex 0.874699 1.64227 2.61702 + vertex 0.871303 1.639 2.61543 + endloop + endfacet + facet normal -0.471915 0.059369 0.879643 + outer loop + vertex 0.871101 1.63405 2.61565 + vertex 0.874465 1.63735 2.61724 + vertex 0.871303 1.639 2.61543 + endloop + endfacet + facet normal -0.481767 0.0595274 0.874275 + outer loop + vertex 0.871303 1.639 2.61543 + vertex 0.867942 1.63566 2.6138 + vertex 0.871101 1.63405 2.61565 + endloop + endfacet + facet normal -0.482706 0.0572659 0.873908 + outer loop + vertex 0.867942 1.63566 2.6138 + vertex 0.867759 1.63072 2.61403 + vertex 0.871101 1.63405 2.61565 + endloop + endfacet + facet normal -0.480762 0.054713 0.875143 + outer loop + vertex 0.871101 1.63405 2.61565 + vertex 0.867759 1.63072 2.61403 + vertex 0.870938 1.62907 2.61588 + endloop + endfacet + facet normal -0.470952 0.054631 0.880465 + outer loop + vertex 0.870938 1.62907 2.61588 + vertex 0.874298 1.63237 2.61747 + vertex 0.871101 1.63405 2.61565 + endloop + endfacet + facet normal -0.469201 0.0523295 0.88154 + outer loop + vertex 0.874152 1.62737 2.61769 + vertex 0.874298 1.63237 2.61747 + vertex 0.870938 1.62907 2.61588 + endloop + endfacet + facet normal -0.469677 0.0512287 0.881351 + outer loop + vertex 0.870763 1.62406 2.61607 + vertex 0.874152 1.62737 2.61769 + vertex 0.870938 1.62907 2.61588 + endloop + endfacet + facet normal -0.479324 0.0513609 0.876134 + outer loop + vertex 0.870938 1.62907 2.61588 + vertex 0.867586 1.62575 2.61424 + vertex 0.870763 1.62406 2.61607 + endloop + endfacet + facet normal -0.479385 0.051218 0.876109 + outer loop + vertex 0.867586 1.62575 2.61424 + vertex 0.867394 1.62074 2.61443 + vertex 0.870763 1.62406 2.61607 + endloop + endfacet + facet normal -0.478385 0.049893 0.876732 + outer loop + vertex 0.870763 1.62406 2.61607 + vertex 0.867394 1.62074 2.61443 + vertex 0.870548 1.61902 2.61624 + endloop + endfacet + facet normal -0.468732 0.0496565 0.881944 + outer loop + vertex 0.870548 1.61902 2.61624 + vertex 0.873972 1.62234 2.61788 + vertex 0.870763 1.62406 2.61607 + endloop + endfacet + facet normal -0.468039 0.0487347 0.882363 + outer loop + vertex 0.873747 1.61724 2.61804 + vertex 0.873972 1.62234 2.61788 + vertex 0.870548 1.61902 2.61624 + endloop + endfacet + facet normal -0.468235 0.048304 0.882283 + outer loop + vertex 0.870282 1.61409 2.61637 + vertex 0.873747 1.61724 2.61804 + vertex 0.870548 1.61902 2.61624 + endloop + endfacet + facet normal -0.477511 0.0486724 0.877277 + outer loop + vertex 0.870548 1.61902 2.61624 + vertex 0.86721 1.61578 2.61461 + vertex 0.870282 1.61409 2.61637 + endloop + endfacet + facet normal -0.477761 0.0481085 0.877172 + outer loop + vertex 0.86721 1.61578 2.61461 + vertex 0.867143 1.61117 2.61482 + vertex 0.870282 1.61409 2.61637 + endloop + endfacet + facet normal -0.477434 0.047649 0.877375 + outer loop + vertex 0.870282 1.61409 2.61637 + vertex 0.867143 1.61117 2.61482 + vertex 0.869702 1.61019 2.61627 + endloop + endfacet + facet normal -0.465688 0.0457304 0.883767 + outer loop + vertex 0.869702 1.61019 2.61627 + vertex 0.873542 1.6114 2.61823 + vertex 0.870282 1.61409 2.61637 + endloop + endfacet + facet normal -0.464541 0.0407179 0.884615 + outer loop + vertex 0.869702 1.61019 2.61627 + vertex 0.870166 1.60682 2.61667 + vertex 0.873542 1.6114 2.61823 + endloop + endfacet + facet normal -0.463105 0.0393822 0.885428 + outer loop + vertex 0.870166 1.60682 2.61667 + vertex 0.873381 1.60562 2.6184 + vertex 0.873542 1.6114 2.61823 + endloop + endfacet + facet normal -0.458705 0.0393274 0.887718 + outer loop + vertex 0.873542 1.6114 2.61823 + vertex 0.873381 1.60562 2.6184 + vertex 0.876867 1.60889 2.62006 + endloop + endfacet + facet normal -0.458888 0.0390244 0.887637 + outer loop + vertex 0.877418 1.61273 2.62018 + vertex 0.873542 1.6114 2.61823 + vertex 0.876867 1.60889 2.62006 + endloop + endfacet + facet normal -0.444893 0.0367947 0.894828 + outer loop + vertex 0.876867 1.60889 2.62006 + vertex 0.88013 1.61215 2.62155 + vertex 0.877418 1.61273 2.62018 + endloop + endfacet + facet normal -0.444321 0.0398519 0.894981 + outer loop + vertex 0.879594 1.61534 2.62114 + vertex 0.877418 1.61273 2.62018 + vertex 0.88013 1.61215 2.62155 + endloop + endfacet + facet normal -0.432238 0.0426165 0.900752 + outer loop + vertex 0.879594 1.61534 2.62114 + vertex 0.88013 1.61215 2.62155 + vertex 0.883101 1.61671 2.62276 + endloop + endfacet + facet normal -0.433681 0.0474308 0.899817 + outer loop + vertex 0.879594 1.61534 2.62114 + vertex 0.883101 1.61671 2.62276 + vertex 0.880245 1.61918 2.62125 + endloop + endfacet + facet normal -0.449671 0.0503773 0.891772 + outer loop + vertex 0.880245 1.61918 2.62125 + vertex 0.876968 1.61607 2.61977 + vertex 0.879594 1.61534 2.62114 + endloop + endfacet + facet normal -0.448249 0.0484954 0.892592 + outer loop + vertex 0.87718 1.62074 2.61963 + vertex 0.876968 1.61607 2.61977 + vertex 0.880245 1.61918 2.62125 + endloop + endfacet + facet normal -0.447617 0.049992 0.892827 + outer loop + vertex 0.88062 1.62403 2.62117 + vertex 0.87718 1.62074 2.61963 + vertex 0.880245 1.61918 2.62125 + endloop + endfacet + facet normal -0.433538 0.0490222 0.899801 + outer loop + vertex 0.880245 1.61918 2.62125 + vertex 0.883818 1.62229 2.6228 + vertex 0.88062 1.62403 2.62117 + endloop + endfacet + facet normal -0.433026 0.0501387 0.899986 + outer loop + vertex 0.883818 1.62229 2.6228 + vertex 0.884115 1.62735 2.62266 + vertex 0.88062 1.62403 2.62117 + endloop + endfacet + facet normal -0.432865 0.0499286 0.900075 + outer loop + vertex 0.88062 1.62403 2.62117 + vertex 0.884115 1.62735 2.62266 + vertex 0.880818 1.62898 2.62099 + endloop + endfacet + facet normal -0.446672 0.050234 0.893286 + outer loop + vertex 0.880818 1.62898 2.62099 + vertex 0.877393 1.62568 2.61946 + vertex 0.88062 1.62403 2.62117 + endloop + endfacet + facet normal -0.446996 0.0506568 0.8931 + outer loop + vertex 0.877541 1.63066 2.61925 + vertex 0.877393 1.62568 2.61946 + vertex 0.880818 1.62898 2.62099 + endloop + endfacet + facet normal -0.446388 0.0520716 0.893323 + outer loop + vertex 0.880963 1.63396 2.62077 + vertex 0.877541 1.63066 2.61925 + vertex 0.880818 1.62898 2.62099 + endloop + endfacet + facet normal -0.43288 0.0519689 0.899952 + outer loop + vertex 0.880818 1.62898 2.62099 + vertex 0.884281 1.63233 2.62246 + vertex 0.880963 1.63396 2.62077 + endloop + endfacet + facet normal -0.432179 0.0536418 0.900191 + outer loop + vertex 0.884281 1.63233 2.62246 + vertex 0.88449 1.63737 2.62226 + vertex 0.880963 1.63396 2.62077 + endloop + endfacet + facet normal -0.434004 0.0559702 0.899171 + outer loop + vertex 0.880963 1.63396 2.62077 + vertex 0.88449 1.63737 2.62226 + vertex 0.881163 1.63899 2.62055 + endloop + endfacet + facet normal -0.447046 0.0562147 0.892743 + outer loop + vertex 0.881163 1.63899 2.62055 + vertex 0.877685 1.63565 2.61902 + vertex 0.880963 1.63396 2.62077 + endloop + endfacet + facet normal -0.449206 0.059046 0.891475 + outer loop + vertex 0.877892 1.64065 2.6188 + vertex 0.877685 1.63565 2.61902 + vertex 0.881163 1.63899 2.62055 + endloop + endfacet + facet normal -0.448343 0.0610629 0.891773 + outer loop + vertex 0.881439 1.64402 2.62035 + vertex 0.877892 1.64065 2.6188 + vertex 0.881163 1.63899 2.62055 + endloop + endfacet + facet normal -0.435274 0.0606128 0.898255 + outer loop + vertex 0.881163 1.63899 2.62055 + vertex 0.884841 1.64256 2.62209 + vertex 0.881439 1.64402 2.62035 + endloop + endfacet + facet normal -0.434893 0.0616388 0.89837 + outer loop + vertex 0.884841 1.64256 2.62209 + vertex 0.885097 1.64763 2.62187 + vertex 0.881439 1.64402 2.62035 + endloop + endfacet + facet normal -0.43642 0.0635556 0.897496 + outer loop + vertex 0.881439 1.64402 2.62035 + vertex 0.885097 1.64763 2.62187 + vertex 0.881767 1.6489 2.62016 + endloop + endfacet + facet normal -0.436465 0.0634196 0.897483 + outer loop + vertex 0.885097 1.64763 2.62187 + vertex 0.885114 1.65212 2.62156 + vertex 0.881767 1.6489 2.62016 + endloop + endfacet + facet normal -0.426382 0.0637119 0.902297 + outer loop + vertex 0.885097 1.64763 2.62187 + vertex 0.888573 1.65169 2.62323 + vertex 0.885114 1.65212 2.62156 + endloop + endfacet + facet normal -0.425998 0.0666914 0.902262 + outer loop + vertex 0.885114 1.65212 2.62156 + vertex 0.888573 1.65169 2.62323 + vertex 0.88814 1.65667 2.62265 + endloop + endfacet + facet normal -0.424751 0.0657033 0.902923 + outer loop + vertex 0.884621 1.65528 2.6211 + vertex 0.885114 1.65212 2.62156 + vertex 0.88814 1.65667 2.62265 + endloop + endfacet + facet normal -0.425289 0.0675014 0.902537 + outer loop + vertex 0.884621 1.65528 2.6211 + vertex 0.88814 1.65667 2.62265 + vertex 0.885289 1.6591 2.62113 + endloop + endfacet + facet normal -0.43537 0.0633312 0.898021 + outer loop + vertex 0.884621 1.65528 2.6211 + vertex 0.882407 1.65271 2.62021 + vertex 0.885114 1.65212 2.62156 + endloop + endfacet + facet normal -0.435583 0.0622824 0.897991 + outer loop + vertex 0.881767 1.6489 2.62016 + vertex 0.885114 1.65212 2.62156 + vertex 0.882407 1.65271 2.62021 + endloop + endfacet + facet normal -0.434789 0.0654536 0.898151 + outer loop + vertex 0.888573 1.65169 2.62323 + vertex 0.891947 1.65557 2.62458 + vertex 0.88814 1.65667 2.62265 + endloop + endfacet + facet normal -0.43332 0.0710581 0.898434 + outer loop + vertex 0.891947 1.65557 2.62458 + vertex 0.892171 1.66049 2.6243 + vertex 0.88814 1.65667 2.62265 + endloop + endfacet + facet normal -0.433369 0.071122 0.898406 + outer loop + vertex 0.88814 1.65667 2.62265 + vertex 0.892171 1.66049 2.6243 + vertex 0.888894 1.66222 2.62258 + endloop + endfacet + facet normal -0.432093 0.0739261 0.898794 + outer loop + vertex 0.892171 1.66049 2.6243 + vertex 0.892572 1.66564 2.62407 + vertex 0.888894 1.66222 2.62258 + endloop + endfacet + facet normal -0.433747 0.0643445 0.898734 + outer loop + vertex 0.891957 1.65121 2.62489 + vertex 0.891947 1.65557 2.62458 + vertex 0.888573 1.65169 2.62323 + endloop + endfacet + facet normal -0.425986 0.0633003 0.902513 + outer loop + vertex 0.888976 1.64666 2.62377 + vertex 0.888573 1.65169 2.62323 + vertex 0.885097 1.64763 2.62187 + endloop + endfacet + facet normal -0.426429 0.0613919 0.902435 + outer loop + vertex 0.884841 1.64256 2.62209 + vertex 0.888976 1.64666 2.62377 + vertex 0.885097 1.64763 2.62187 + endloop + endfacet + facet normal -0.424827 0.0594096 0.903323 + outer loop + vertex 0.888165 1.64095 2.62376 + vertex 0.888976 1.64666 2.62377 + vertex 0.884841 1.64256 2.62209 + endloop + endfacet + facet normal -0.425605 0.0575528 0.903077 + outer loop + vertex 0.88449 1.63737 2.62226 + vertex 0.888165 1.64095 2.62376 + vertex 0.884841 1.64256 2.62209 + endloop + endfacet + facet normal -0.450199 0.063522 0.890666 + outer loop + vertex 0.878174 1.64569 2.61858 + vertex 0.877892 1.64065 2.6188 + vertex 0.881439 1.64402 2.62035 + endloop + endfacet + facet normal -0.460703 0.0638756 0.885253 + outer loop + vertex 0.877892 1.64065 2.6188 + vertex 0.878174 1.64569 2.61858 + vertex 0.874699 1.64227 2.61702 + endloop + endfacet + facet normal -0.459902 0.0592403 0.885992 + outer loop + vertex 0.877685 1.63565 2.61902 + vertex 0.877892 1.64065 2.6188 + vertex 0.874465 1.63735 2.61724 + endloop + endfacet + facet normal -0.460989 0.0567611 0.885589 + outer loop + vertex 0.874298 1.63237 2.61747 + vertex 0.877685 1.63565 2.61902 + vertex 0.874465 1.63735 2.61724 + endloop + endfacet + facet normal -0.459028 0.0541745 0.886769 + outer loop + vertex 0.877541 1.63066 2.61925 + vertex 0.877685 1.63565 2.61902 + vertex 0.874298 1.63237 2.61747 + endloop + endfacet + facet normal -0.433182 0.0579499 0.899442 + outer loop + vertex 0.88449 1.63737 2.62226 + vertex 0.884841 1.64256 2.62209 + vertex 0.881163 1.63899 2.62055 + endloop + endfacet + facet normal -0.424135 0.053461 0.904019 + outer loop + vertex 0.884281 1.63233 2.62246 + vertex 0.887801 1.63578 2.62391 + vertex 0.88449 1.63737 2.62226 + endloop + endfacet + facet normal -0.423327 0.0524535 0.904457 + outer loop + vertex 0.887614 1.63076 2.62411 + vertex 0.887801 1.63578 2.62391 + vertex 0.884281 1.63233 2.62246 + endloop + endfacet + facet normal -0.423866 0.0511252 0.904281 + outer loop + vertex 0.884115 1.62735 2.62266 + vertex 0.887614 1.63076 2.62411 + vertex 0.884281 1.63233 2.62246 + endloop + endfacet + facet normal -0.447956 0.0541156 0.892416 + outer loop + vertex 0.877685 1.63565 2.61902 + vertex 0.877541 1.63066 2.61925 + vertex 0.880963 1.63396 2.62077 + endloop + endfacet + facet normal -0.458704 0.0507531 0.887139 + outer loop + vertex 0.877393 1.62568 2.61946 + vertex 0.877541 1.63066 2.61925 + vertex 0.874152 1.62737 2.61769 + endloop + endfacet + facet normal -0.459154 0.0497101 0.886965 + outer loop + vertex 0.873972 1.62234 2.61788 + vertex 0.877393 1.62568 2.61946 + vertex 0.874152 1.62737 2.61769 + endloop + endfacet + facet normal -0.459066 0.0495948 0.887017 + outer loop + vertex 0.87718 1.62074 2.61963 + vertex 0.877393 1.62568 2.61946 + vertex 0.873972 1.62234 2.61788 + endloop + endfacet + facet normal -0.432312 0.0512431 0.900267 + outer loop + vertex 0.884115 1.62735 2.62266 + vertex 0.884281 1.63233 2.62246 + vertex 0.880818 1.62898 2.62099 + endloop + endfacet + facet normal -0.425484 0.0497955 0.903595 + outer loop + vertex 0.883818 1.62229 2.6228 + vertex 0.887446 1.62574 2.62432 + vertex 0.884115 1.62735 2.62266 + endloop + endfacet + facet normal -0.426156 0.0506612 0.90323 + outer loop + vertex 0.887167 1.62061 2.62448 + vertex 0.887446 1.62574 2.62432 + vertex 0.883818 1.62229 2.6228 + endloop + endfacet + facet normal -0.427475 0.0475808 0.902774 + outer loop + vertex 0.883101 1.61671 2.62276 + vertex 0.887167 1.62061 2.62448 + vertex 0.883818 1.62229 2.6228 + endloop + endfacet + facet normal -0.447078 0.0492845 0.893136 + outer loop + vertex 0.877393 1.62568 2.61946 + vertex 0.87718 1.62074 2.61963 + vertex 0.88062 1.62403 2.62117 + endloop + endfacet + facet normal -0.459783 0.0488337 0.886687 + outer loop + vertex 0.876968 1.61607 2.61977 + vertex 0.87718 1.62074 2.61963 + vertex 0.873747 1.61724 2.61804 + endloop + endfacet + facet normal -0.460929 0.0451004 0.88629 + outer loop + vertex 0.873542 1.6114 2.61823 + vertex 0.876968 1.61607 2.61977 + vertex 0.873747 1.61724 2.61804 + endloop + endfacet + facet normal -0.433047 0.0483198 0.900075 + outer loop + vertex 0.883101 1.61671 2.62276 + vertex 0.883818 1.62229 2.6228 + vertex 0.880245 1.61918 2.62125 + endloop + endfacet + facet normal -0.431786 0.0422599 0.900985 + outer loop + vertex 0.88013 1.61215 2.62155 + vertex 0.883582 1.61165 2.62323 + vertex 0.883101 1.61671 2.62276 + endloop + endfacet + facet normal -0.428288 0.0427457 0.902631 + outer loop + vertex 0.883582 1.61165 2.62323 + vertex 0.886957 1.61556 2.62464 + vertex 0.883101 1.61671 2.62276 + endloop + endfacet + facet normal -0.427438 0.0418494 0.903076 + outer loop + vertex 0.88698 1.61106 2.62486 + vertex 0.886957 1.61556 2.62464 + vertex 0.883582 1.61165 2.62323 + endloop + endfacet + facet normal -0.432536 0.0366528 0.900871 + outer loop + vertex 0.880211 1.60765 2.62177 + vertex 0.883582 1.61165 2.62323 + vertex 0.88013 1.61215 2.62155 + endloop + endfacet + facet normal -0.432511 0.0366275 0.900884 + outer loop + vertex 0.884084 1.60658 2.62367 + vertex 0.883582 1.61165 2.62323 + vertex 0.880211 1.60765 2.62177 + endloop + endfacet + facet normal -0.433203 0.0337364 0.900665 + outer loop + vertex 0.880086 1.60261 2.6219 + vertex 0.884084 1.60658 2.62367 + vertex 0.880211 1.60765 2.62177 + endloop + endfacet + facet normal -0.444171 0.0338726 0.895301 + outer loop + vertex 0.880086 1.60261 2.6219 + vertex 0.880211 1.60765 2.62177 + vertex 0.876678 1.60405 2.62015 + endloop + endfacet + facet normal -0.444752 0.0322217 0.895074 + outer loop + vertex 0.876529 1.59906 2.62026 + vertex 0.880086 1.60261 2.6219 + vertex 0.876678 1.60405 2.62015 + endloop + endfacet + facet normal -0.454716 0.0324123 0.890047 + outer loop + vertex 0.876678 1.60405 2.62015 + vertex 0.873236 1.60065 2.61852 + vertex 0.876529 1.59906 2.62026 + endloop + endfacet + facet normal -0.455095 0.0314501 0.889887 + outer loop + vertex 0.873236 1.60065 2.61852 + vertex 0.873132 1.59571 2.61864 + vertex 0.876529 1.59906 2.62026 + endloop + endfacet + facet normal -0.454044 0.0301027 0.89047 + outer loop + vertex 0.876529 1.59906 2.62026 + vertex 0.873132 1.59571 2.61864 + vertex 0.876415 1.59405 2.62037 + endloop + endfacet + facet normal -0.445216 0.0300013 0.894921 + outer loop + vertex 0.876415 1.59405 2.62037 + vertex 0.879848 1.59745 2.62196 + vertex 0.876529 1.59906 2.62026 + endloop + endfacet + facet normal -0.444358 0.028916 0.895383 + outer loop + vertex 0.879718 1.59238 2.62206 + vertex 0.879848 1.59745 2.62196 + vertex 0.876415 1.59405 2.62037 + endloop + endfacet + facet normal -0.445136 0.0270432 0.895054 + outer loop + vertex 0.876339 1.58907 2.62048 + vertex 0.879718 1.59238 2.62206 + vertex 0.876415 1.59405 2.62037 + endloop + endfacet + facet normal -0.452828 0.0270726 0.891187 + outer loop + vertex 0.876415 1.59405 2.62037 + vertex 0.873058 1.59076 2.61876 + vertex 0.876339 1.58907 2.62048 + endloop + endfacet + facet normal -0.45337 0.025781 0.89095 + outer loop + vertex 0.873058 1.59076 2.61876 + vertex 0.872986 1.58579 2.61887 + vertex 0.876339 1.58907 2.62048 + endloop + endfacet + facet normal -0.451248 0.0230457 0.892101 + outer loop + vertex 0.876339 1.58907 2.62048 + vertex 0.872986 1.58579 2.61887 + vertex 0.876272 1.58408 2.62058 + endloop + endfacet + facet normal -0.444161 0.0230165 0.895651 + outer loop + vertex 0.876272 1.58408 2.62058 + vertex 0.879649 1.58738 2.62217 + vertex 0.876339 1.58907 2.62048 + endloop + endfacet + facet normal -0.442839 0.0213253 0.896348 + outer loop + vertex 0.879586 1.5824 2.62225 + vertex 0.879649 1.58738 2.62217 + vertex 0.876272 1.58408 2.62058 + endloop + endfacet + facet normal -0.443358 0.020079 0.89612 + outer loop + vertex 0.876197 1.5791 2.62065 + vertex 0.879586 1.5824 2.62225 + vertex 0.876272 1.58408 2.62058 + endloop + endfacet + facet normal -0.450753 0.0201348 0.892422 + outer loop + vertex 0.876272 1.58408 2.62058 + vertex 0.872906 1.5808 2.61895 + vertex 0.876197 1.5791 2.62065 + endloop + endfacet + facet normal -0.450964 0.0196314 0.892326 + outer loop + vertex 0.872906 1.5808 2.61895 + vertex 0.872824 1.5758 2.61902 + vertex 0.876197 1.5791 2.62065 + endloop + endfacet + facet normal -0.450657 0.0192364 0.89249 + outer loop + vertex 0.876197 1.5791 2.62065 + vertex 0.872824 1.5758 2.61902 + vertex 0.876117 1.5741 2.62072 + endloop + endfacet + facet normal -0.44294 0.0191657 0.896346 + outer loop + vertex 0.876117 1.5741 2.62072 + vertex 0.879512 1.57741 2.62233 + vertex 0.876197 1.5791 2.62065 + endloop + endfacet + facet normal -0.443277 0.0195973 0.89617 + outer loop + vertex 0.879429 1.57242 2.62239 + vertex 0.879512 1.57741 2.62233 + vertex 0.876117 1.5741 2.62072 + endloop + endfacet + facet normal -0.443307 0.0195245 0.896157 + outer loop + vertex 0.876038 1.56911 2.62079 + vertex 0.879429 1.57242 2.62239 + vertex 0.876117 1.5741 2.62072 + endloop + endfacet + facet normal -0.451397 0.0195965 0.892108 + outer loop + vertex 0.876117 1.5741 2.62072 + vertex 0.872749 1.5708 2.61909 + vertex 0.876038 1.56911 2.62079 + endloop + endfacet + facet normal -0.451525 0.0192907 0.89205 + outer loop + vertex 0.872749 1.5708 2.61909 + vertex 0.872679 1.5658 2.61916 + vertex 0.876038 1.56911 2.62079 + endloop + endfacet + facet normal -0.45205 0.0199625 0.891769 + outer loop + vertex 0.876038 1.56911 2.62079 + vertex 0.872679 1.5658 2.61916 + vertex 0.875964 1.56412 2.62086 + endloop + endfacet + facet normal -0.444647 0.0199075 0.895485 + outer loop + vertex 0.875964 1.56412 2.62086 + vertex 0.879344 1.56743 2.62247 + vertex 0.876038 1.56911 2.62079 + endloop + endfacet + facet normal -0.445329 0.0207768 0.895126 + outer loop + vertex 0.879267 1.56244 2.62255 + vertex 0.879344 1.56743 2.62247 + vertex 0.875964 1.56412 2.62086 + endloop + endfacet + facet normal -0.446202 0.0186689 0.894737 + outer loop + vertex 0.875899 1.55912 2.62093 + vertex 0.879267 1.56244 2.62255 + vertex 0.875964 1.56412 2.62086 + endloop + endfacet + facet normal -0.452786 0.0187062 0.891423 + outer loop + vertex 0.875964 1.56412 2.62086 + vertex 0.872617 1.56081 2.61923 + vertex 0.875899 1.55912 2.62093 + endloop + endfacet + facet normal -0.453887 0.0160488 0.890915 + outer loop + vertex 0.872617 1.56081 2.61923 + vertex 0.872564 1.55582 2.6193 + vertex 0.875899 1.55912 2.62093 + endloop + endfacet + facet normal -0.453362 0.0153813 0.891194 + outer loop + vertex 0.875899 1.55912 2.62093 + vertex 0.872564 1.55582 2.6193 + vertex 0.875847 1.55413 2.62099 + endloop + endfacet + facet normal -0.447301 0.0153552 0.894251 + outer loop + vertex 0.875847 1.55413 2.62099 + vertex 0.879203 1.55744 2.62262 + vertex 0.875899 1.55912 2.62093 + endloop + endfacet + facet normal -0.44648 0.0143132 0.894679 + outer loop + vertex 0.879156 1.55245 2.62267 + vertex 0.879203 1.55744 2.62262 + vertex 0.875847 1.55413 2.62099 + endloop + endfacet + facet normal -0.447691 0.0113719 0.894116 + outer loop + vertex 0.875809 1.54914 2.62104 + vertex 0.879156 1.55245 2.62267 + vertex 0.875847 1.55413 2.62099 + endloop + endfacet + facet normal -0.453447 0.0113909 0.891211 + outer loop + vertex 0.875847 1.55413 2.62099 + vertex 0.872522 1.55082 2.61934 + vertex 0.875809 1.54914 2.62104 + endloop + endfacet + facet normal -0.454322 0.00926182 0.890789 + outer loop + vertex 0.872522 1.55082 2.61934 + vertex 0.872488 1.54583 2.61938 + vertex 0.875809 1.54914 2.62104 + endloop + endfacet + facet normal -0.453065 0.0076685 0.891445 + outer loop + vertex 0.875809 1.54914 2.62104 + vertex 0.872488 1.54583 2.61938 + vertex 0.875781 1.54414 2.62107 + endloop + endfacet + facet normal -0.447492 0.00765441 0.894255 + outer loop + vertex 0.875781 1.54414 2.62107 + vertex 0.879123 1.54745 2.62271 + vertex 0.875809 1.54914 2.62104 + endloop + endfacet + facet normal -0.446385 0.00625506 0.894819 + outer loop + vertex 0.879103 1.54245 2.62274 + vertex 0.879123 1.54745 2.62271 + vertex 0.875781 1.54414 2.62107 + endloop + endfacet + facet normal -0.446818 0.00519686 0.89461 + outer loop + vertex 0.875763 1.53915 2.62109 + vertex 0.879103 1.54245 2.62274 + vertex 0.875781 1.54414 2.62107 + endloop + endfacet + facet normal -0.451964 0.00520502 0.892021 + outer loop + vertex 0.875781 1.54414 2.62107 + vertex 0.872462 1.54084 2.61941 + vertex 0.875763 1.53915 2.62109 + endloop + endfacet + facet normal -0.45183 0.0055338 0.892087 + outer loop + vertex 0.872462 1.54084 2.61941 + vertex 0.872443 1.53585 2.61943 + vertex 0.875763 1.53915 2.62109 + endloop + endfacet + facet normal -0.450469 0.00381331 0.892784 + outer loop + vertex 0.875763 1.53915 2.62109 + vertex 0.872443 1.53585 2.61943 + vertex 0.875751 1.53415 2.6211 + endloop + endfacet + facet normal -0.445787 0.00380919 0.895131 + outer loop + vertex 0.875751 1.53415 2.6211 + vertex 0.879091 1.53745 2.62275 + vertex 0.875763 1.53915 2.62109 + endloop + endfacet + facet normal -0.444818 0.00258574 0.895617 + outer loop + vertex 0.879082 1.53246 2.62276 + vertex 0.879091 1.53745 2.62275 + vertex 0.875751 1.53415 2.6211 + endloop + endfacet + facet normal -0.444545 0.00325287 0.895751 + outer loop + vertex 0.87574 1.52916 2.62112 + vertex 0.879082 1.53246 2.62276 + vertex 0.875751 1.53415 2.6211 + endloop + endfacet + facet normal -0.449136 0.00325781 0.893458 + outer loop + vertex 0.875751 1.53415 2.6211 + vertex 0.872429 1.53086 2.61945 + vertex 0.87574 1.52916 2.62112 + endloop + endfacet + facet normal -0.44865 0.00443922 0.893696 + outer loop + vertex 0.872429 1.53086 2.61945 + vertex 0.872414 1.52587 2.61946 + vertex 0.87574 1.52916 2.62112 + endloop + endfacet + facet normal -0.448206 0.00387731 0.893922 + outer loop + vertex 0.87574 1.52916 2.62112 + vertex 0.872414 1.52587 2.61946 + vertex 0.875725 1.52417 2.62113 + endloop + endfacet + facet normal -0.443634 0.00386986 0.8962 + outer loop + vertex 0.875725 1.52417 2.62113 + vertex 0.87907 1.52746 2.62277 + vertex 0.87574 1.52916 2.62112 + endloop + endfacet + facet normal -0.443438 0.00362141 0.896298 + outer loop + vertex 0.879054 1.52247 2.62278 + vertex 0.87907 1.52746 2.62277 + vertex 0.875725 1.52417 2.62113 + endloop + endfacet + facet normal -0.443108 0.00442385 0.896457 + outer loop + vertex 0.875707 1.51917 2.62115 + vertex 0.879054 1.52247 2.62278 + vertex 0.875725 1.52417 2.62113 + endloop + endfacet + facet normal -0.448079 0.00443339 0.893983 + outer loop + vertex 0.875725 1.52417 2.62113 + vertex 0.872398 1.52087 2.61948 + vertex 0.875707 1.51917 2.62115 + endloop + endfacet + facet normal -0.448422 0.00360124 0.893815 + outer loop + vertex 0.872398 1.52087 2.61948 + vertex 0.872383 1.51588 2.61949 + vertex 0.875707 1.51917 2.62115 + endloop + endfacet + facet normal -0.448265 0.00340257 0.893894 + outer loop + vertex 0.875707 1.51917 2.62115 + vertex 0.872383 1.51588 2.61949 + vertex 0.875694 1.51418 2.62116 + endloop + endfacet + facet normal -0.44308 0.00339592 0.896476 + outer loop + vertex 0.875694 1.51418 2.62116 + vertex 0.879038 1.51747 2.6228 + vertex 0.875707 1.51917 2.62115 + endloop + endfacet + facet normal -0.442626 0.0028224 0.896702 + outer loop + vertex 0.87903 1.51248 2.62281 + vertex 0.879038 1.51747 2.6228 + vertex 0.875694 1.51418 2.62116 + endloop + endfacet + facet normal -0.44335 0.00105779 0.896348 + outer loop + vertex 0.875693 1.50919 2.62116 + vertex 0.87903 1.51248 2.62281 + vertex 0.875694 1.51418 2.62116 + endloop + endfacet + facet normal -0.448598 0.00105704 0.893733 + outer loop + vertex 0.875694 1.51418 2.62116 + vertex 0.872378 1.51089 2.6195 + vertex 0.875693 1.50919 2.62116 + endloop + endfacet + facet normal -0.449397 -0.000892655 0.893332 + outer loop + vertex 0.872378 1.51089 2.6195 + vertex 0.872382 1.5059 2.61949 + vertex 0.875693 1.50919 2.62116 + endloop + endfacet + facet normal -0.448803 -0.00164102 0.893629 + outer loop + vertex 0.875693 1.50919 2.62116 + vertex 0.872382 1.5059 2.61949 + vertex 0.875701 1.5042 2.62116 + endloop + endfacet + facet normal -0.443326 -0.00163467 0.896359 + outer loop + vertex 0.875701 1.5042 2.62116 + vertex 0.879034 1.50749 2.62281 + vertex 0.875693 1.50919 2.62116 + endloop + endfacet + facet normal -0.442669 -0.00246154 0.896682 + outer loop + vertex 0.879045 1.5025 2.6228 + vertex 0.879034 1.50749 2.62281 + vertex 0.875701 1.5042 2.62116 + endloop + endfacet + facet normal -0.443023 -0.00333393 0.896504 + outer loop + vertex 0.875712 1.49921 2.62115 + vertex 0.879045 1.5025 2.6228 + vertex 0.875701 1.5042 2.62116 + endloop + endfacet + facet normal -0.449045 -0.00333935 0.893503 + outer loop + vertex 0.875701 1.5042 2.62116 + vertex 0.872391 1.5009 2.61948 + vertex 0.875712 1.49921 2.62115 + endloop + endfacet + facet normal -0.449029 -0.00329997 0.893511 + outer loop + vertex 0.872391 1.5009 2.61948 + vertex 0.8724 1.49591 2.61947 + vertex 0.875712 1.49921 2.62115 + endloop + endfacet + facet normal -0.44893 -0.00342473 0.89356 + outer loop + vertex 0.875712 1.49921 2.62115 + vertex 0.8724 1.49591 2.61947 + vertex 0.875721 1.49422 2.62113 + endloop + endfacet + facet normal -0.44283 -0.00342171 0.896599 + outer loop + vertex 0.875721 1.49422 2.62113 + vertex 0.879056 1.49752 2.62279 + vertex 0.875712 1.49921 2.62115 + endloop + endfacet + facet normal -0.443155 -0.0030128 0.89644 + outer loop + vertex 0.879065 1.49253 2.62278 + vertex 0.879056 1.49752 2.62279 + vertex 0.875721 1.49422 2.62113 + endloop + endfacet + facet normal -0.443293 -0.0033542 0.89637 + outer loop + vertex 0.875735 1.48922 2.62112 + vertex 0.879065 1.49253 2.62278 + vertex 0.875721 1.49422 2.62113 + endloop + endfacet + facet normal -0.448748 -0.00336198 0.893652 + outer loop + vertex 0.875721 1.49422 2.62113 + vertex 0.872412 1.49092 2.61946 + vertex 0.875735 1.48922 2.62112 + endloop + endfacet + facet normal -0.449397 -0.00496261 0.893319 + outer loop + vertex 0.872412 1.49092 2.61946 + vertex 0.872437 1.48593 2.61944 + vertex 0.875735 1.48922 2.62112 + endloop + endfacet + facet normal -0.448921 -0.00555761 0.893554 + outer loop + vertex 0.875735 1.48922 2.62112 + vertex 0.872437 1.48593 2.61944 + vertex 0.875762 1.48424 2.6211 + endloop + endfacet + facet normal -0.443901 -0.00553846 0.896059 + outer loop + vertex 0.875762 1.48424 2.6211 + vertex 0.87908 1.48754 2.62277 + vertex 0.875735 1.48922 2.62112 + endloop + endfacet + facet normal -0.443252 -0.0063485 0.896375 + outer loop + vertex 0.879111 1.48256 2.62275 + vertex 0.87908 1.48754 2.62277 + vertex 0.875762 1.48424 2.6211 + endloop + endfacet + facet normal -0.444612 -0.00974964 0.89567 + outer loop + vertex 0.875811 1.47925 2.62107 + vertex 0.879111 1.48256 2.62275 + vertex 0.875762 1.48424 2.6211 + endloop + endfacet + facet normal -0.449268 -0.00978069 0.893344 + outer loop + vertex 0.875762 1.48424 2.6211 + vertex 0.872481 1.48094 2.61942 + vertex 0.875811 1.47925 2.62107 + endloop + endfacet + facet normal -0.450664 -0.0132656 0.892595 + outer loop + vertex 0.872481 1.48094 2.61942 + vertex 0.872541 1.47595 2.61937 + vertex 0.875811 1.47925 2.62107 + endloop + endfacet + facet normal -0.449747 -0.0144034 0.89304 + outer loop + vertex 0.875811 1.47925 2.62107 + vertex 0.872541 1.47595 2.61937 + vertex 0.875874 1.47426 2.62102 + endloop + endfacet + facet normal -0.4451 -0.0143673 0.895366 + outer loop + vertex 0.875874 1.47426 2.62102 + vertex 0.879161 1.47757 2.62271 + vertex 0.875811 1.47925 2.62107 + endloop + endfacet + facet normal -0.444414 -0.0152155 0.895692 + outer loop + vertex 0.879225 1.47258 2.62266 + vertex 0.879161 1.47757 2.62271 + vertex 0.875874 1.47426 2.62102 + endloop + endfacet + facet normal -0.44525 -0.0173238 0.895239 + outer loop + vertex 0.875945 1.46927 2.62096 + vertex 0.879225 1.47258 2.62266 + vertex 0.875874 1.47426 2.62102 + endloop + endfacet + facet normal -0.450136 -0.0173637 0.892791 + outer loop + vertex 0.875874 1.47426 2.62102 + vertex 0.872611 1.47096 2.61931 + vertex 0.875945 1.46927 2.62096 + endloop + endfacet + facet normal -0.450457 -0.0181707 0.892613 + outer loop + vertex 0.872611 1.47096 2.61931 + vertex 0.872683 1.46598 2.61925 + vertex 0.875945 1.46927 2.62096 + endloop + endfacet + facet normal -0.450556 -0.0180482 0.892566 + outer loop + vertex 0.875945 1.46927 2.62096 + vertex 0.872683 1.46598 2.61925 + vertex 0.876015 1.46429 2.6209 + endloop + endfacet + facet normal -0.445389 -0.0180093 0.895156 + outer loop + vertex 0.876015 1.46429 2.6209 + vertex 0.879296 1.46759 2.62259 + vertex 0.875945 1.46927 2.62096 + endloop + endfacet + facet normal -0.445537 -0.0178253 0.895086 + outer loop + vertex 0.879365 1.4626 2.62253 + vertex 0.879296 1.46759 2.62259 + vertex 0.876015 1.46429 2.6209 + endloop + endfacet + facet normal -0.445308 -0.0172481 0.895211 + outer loop + vertex 0.876079 1.45931 2.62083 + vertex 0.879365 1.4626 2.62253 + vertex 0.876015 1.46429 2.6209 + endloop + endfacet + facet normal -0.45084 -0.0172828 0.892437 + outer loop + vertex 0.876015 1.46429 2.6209 + vertex 0.872747 1.461 2.61918 + vertex 0.876079 1.45931 2.62083 + endloop + endfacet + facet normal -0.450744 -0.0170435 0.89249 + outer loop + vertex 0.872747 1.461 2.61918 + vertex 0.872798 1.45602 2.61911 + vertex 0.876079 1.45931 2.62083 + endloop + endfacet + facet normal -0.451434 -0.0161811 0.892158 + outer loop + vertex 0.876079 1.45931 2.62083 + vertex 0.872798 1.45602 2.61911 + vertex 0.876135 1.45433 2.62077 + endloop + endfacet + facet normal -0.444996 -0.0161488 0.895387 + outer loop + vertex 0.876135 1.45433 2.62077 + vertex 0.879431 1.45762 2.62247 + vertex 0.876079 1.45931 2.62083 + endloop + endfacet + facet normal -0.445031 -0.0161049 0.89537 + outer loop + vertex 0.879496 1.45263 2.62241 + vertex 0.879431 1.45762 2.62247 + vertex 0.876135 1.45433 2.62077 + endloop + endfacet + facet normal -0.444831 -0.0156015 0.895479 + outer loop + vertex 0.876196 1.44933 2.62071 + vertex 0.879496 1.45263 2.62241 + vertex 0.876135 1.45433 2.62077 + endloop + endfacet + facet normal -0.452155 -0.0156493 0.891802 + outer loop + vertex 0.876135 1.45433 2.62077 + vertex 0.872846 1.45102 2.61904 + vertex 0.876196 1.44933 2.62071 + endloop + endfacet + facet normal -0.452758 -0.017174 0.891468 + outer loop + vertex 0.872846 1.45102 2.61904 + vertex 0.872908 1.44599 2.61898 + vertex 0.876196 1.44933 2.62071 + endloop + endfacet + facet normal -0.452863 -0.0170444 0.891417 + outer loop + vertex 0.876196 1.44933 2.62071 + vertex 0.872908 1.44599 2.61898 + vertex 0.87627 1.44431 2.62066 + endloop + endfacet + facet normal -0.444911 -0.0169728 0.895414 + outer loop + vertex 0.87627 1.44431 2.62066 + vertex 0.879573 1.44764 2.62236 + vertex 0.876196 1.44933 2.62071 + endloop + endfacet + facet normal -0.444282 -0.0177473 0.895711 + outer loop + vertex 0.879656 1.44264 2.6223 + vertex 0.879573 1.44764 2.62236 + vertex 0.87627 1.44431 2.62066 + endloop + endfacet + facet normal -0.44526 -0.0202674 0.895172 + outer loop + vertex 0.87634 1.43927 2.62058 + vertex 0.879656 1.44264 2.6223 + vertex 0.87627 1.44431 2.62066 + endloop + endfacet + facet normal -0.453822 -0.0203177 0.890861 + outer loop + vertex 0.87627 1.44431 2.62066 + vertex 0.872983 1.44094 2.6189 + vertex 0.87634 1.43927 2.62058 + endloop + endfacet + facet normal -0.455127 -0.0237056 0.890111 + outer loop + vertex 0.872983 1.44094 2.6189 + vertex 0.873042 1.43589 2.6188 + vertex 0.87634 1.43927 2.62058 + endloop + endfacet + facet normal -0.454158 -0.0248919 0.890573 + outer loop + vertex 0.87634 1.43927 2.62058 + vertex 0.873042 1.43589 2.6188 + vertex 0.876385 1.43425 2.62046 + endloop + endfacet + facet normal -0.445569 -0.0249158 0.894901 + outer loop + vertex 0.876385 1.43425 2.62046 + vertex 0.879716 1.43764 2.62221 + vertex 0.87634 1.43927 2.62058 + endloop + endfacet + facet normal -0.444937 -0.0256889 0.895193 + outer loop + vertex 0.879746 1.43264 2.62208 + vertex 0.879716 1.43764 2.62221 + vertex 0.876385 1.43425 2.62046 + endloop + endfacet + facet normal -0.445912 -0.028286 0.89463 + outer loop + vertex 0.876451 1.42927 2.62033 + vertex 0.879746 1.43264 2.62208 + vertex 0.876385 1.43425 2.62046 + endloop + endfacet + facet normal -0.4548 -0.028291 0.890144 + outer loop + vertex 0.876385 1.43425 2.62046 + vertex 0.873106 1.4309 2.61868 + vertex 0.876451 1.42927 2.62033 + endloop + endfacet + facet normal -0.455637 -0.0305294 0.889642 + outer loop + vertex 0.873106 1.4309 2.61868 + vertex 0.873284 1.42596 2.6186 + vertex 0.876451 1.42927 2.62033 + endloop + endfacet + facet normal -0.455213 -0.0310392 0.889842 + outer loop + vertex 0.876451 1.42927 2.62033 + vertex 0.873284 1.42596 2.6186 + vertex 0.876681 1.42434 2.62028 + endloop + endfacet + facet normal -0.445705 -0.0306487 0.894655 + outer loop + vertex 0.876681 1.42434 2.62028 + vertex 0.879835 1.42765 2.62196 + vertex 0.876451 1.42927 2.62033 + endloop + endfacet + facet normal -0.445396 -0.0310134 0.894796 + outer loop + vertex 0.880133 1.42263 2.62194 + vertex 0.879835 1.42765 2.62196 + vertex 0.876681 1.42434 2.62028 + endloop + endfacet + facet normal -0.445737 -0.0318968 0.894596 + outer loop + vertex 0.877191 1.41953 2.62036 + vertex 0.880133 1.42263 2.62194 + vertex 0.876681 1.42434 2.62028 + endloop + endfacet + facet normal -0.45519 -0.0329808 0.889783 + outer loop + vertex 0.876681 1.42434 2.62028 + vertex 0.873741 1.42105 2.61865 + vertex 0.877191 1.41953 2.62036 + endloop + endfacet + facet normal -0.455389 -0.0335697 0.889659 + outer loop + vertex 0.873741 1.42105 2.61865 + vertex 0.874711 1.41633 2.61897 + vertex 0.877191 1.41953 2.62036 + endloop + endfacet + facet normal -0.455193 -0.0337621 0.889752 + outer loop + vertex 0.877671 1.41558 2.62046 + vertex 0.877191 1.41953 2.62036 + vertex 0.874711 1.41633 2.61897 + endloop + endfacet + facet normal -0.455643 -0.0361924 0.889426 + outer loop + vertex 0.877671 1.41558 2.62046 + vertex 0.874711 1.41633 2.61897 + vertex 0.876469 1.41159 2.61968 + endloop + endfacet + facet normal -0.450947 -0.0380598 0.891739 + outer loop + vertex 0.876469 1.41159 2.61968 + vertex 0.879456 1.41324 2.62126 + vertex 0.877671 1.41558 2.62046 + endloop + endfacet + facet normal -0.444975 -0.0323973 0.894957 + outer loop + vertex 0.879456 1.41324 2.62126 + vertex 0.880689 1.41725 2.62202 + vertex 0.877671 1.41558 2.62046 + endloop + endfacet + facet normal -0.438518 -0.0349667 0.898042 + outer loop + vertex 0.879456 1.41324 2.62126 + vertex 0.88245 1.41254 2.6227 + vertex 0.880689 1.41725 2.62202 + endloop + endfacet + facet normal -0.433548 -0.0327462 0.900535 + outer loop + vertex 0.88245 1.41254 2.6227 + vertex 0.884633 1.41624 2.62388 + vertex 0.880689 1.41725 2.62202 + endloop + endfacet + facet normal -0.438971 -0.0375907 0.897715 + outer loop + vertex 0.879964 1.40929 2.62134 + vertex 0.88245 1.41254 2.6227 + vertex 0.879456 1.41324 2.62126 + endloop + endfacet + facet normal -0.4372 -0.0392725 0.898507 + outer loop + vertex 0.883468 1.40778 2.62298 + vertex 0.88245 1.41254 2.6227 + vertex 0.879964 1.40929 2.62134 + endloop + endfacet + facet normal -0.437394 -0.0398531 0.898387 + outer loop + vertex 0.880534 1.40444 2.62141 + vertex 0.883468 1.40778 2.62298 + vertex 0.879964 1.40929 2.62134 + endloop + endfacet + facet normal -0.448338 -0.0412106 0.892913 + outer loop + vertex 0.879964 1.40929 2.62134 + vertex 0.877087 1.40617 2.61975 + vertex 0.880534 1.40444 2.62141 + endloop + endfacet + facet normal -0.4487 -0.0421481 0.892688 + outer loop + vertex 0.877087 1.40617 2.61975 + vertex 0.877454 1.40111 2.6197 + vertex 0.880534 1.40444 2.62141 + endloop + endfacet + facet normal -0.447191 -0.0438852 0.893361 + outer loop + vertex 0.880534 1.40444 2.62141 + vertex 0.877454 1.40111 2.6197 + vertex 0.880838 1.39947 2.62131 + endloop + endfacet + facet normal -0.435871 -0.0432967 0.898967 + outer loop + vertex 0.880838 1.39947 2.62131 + vertex 0.884006 1.40279 2.62301 + vertex 0.880534 1.40444 2.62141 + endloop + endfacet + facet normal -0.433664 -0.0458826 0.899906 + outer loop + vertex 0.884252 1.39781 2.62287 + vertex 0.884006 1.40279 2.62301 + vertex 0.880838 1.39947 2.62131 + endloop + endfacet + facet normal -0.434304 -0.0475662 0.89951 + outer loop + vertex 0.880952 1.39447 2.6211 + vertex 0.884252 1.39781 2.62287 + vertex 0.880838 1.39947 2.62131 + endloop + endfacet + facet normal -0.446895 -0.0475943 0.89332 + outer loop + vertex 0.880838 1.39947 2.62131 + vertex 0.877591 1.39609 2.61951 + vertex 0.880952 1.39447 2.6211 + endloop + endfacet + facet normal -0.447855 -0.0502046 0.892695 + outer loop + vertex 0.877591 1.39609 2.61951 + vertex 0.877646 1.39106 2.61925 + vertex 0.880952 1.39447 2.6211 + endloop + endfacet + facet normal -0.44685 -0.0514158 0.89313 + outer loop + vertex 0.880952 1.39447 2.6211 + vertex 0.877646 1.39106 2.61925 + vertex 0.881018 1.38943 2.62085 + endloop + endfacet + facet normal -0.432313 -0.0515882 0.900247 + outer loop + vertex 0.881018 1.38943 2.62085 + vertex 0.884356 1.39282 2.62264 + vertex 0.880952 1.39447 2.6211 + endloop + endfacet + facet normal -0.429904 -0.0544853 0.901229 + outer loop + vertex 0.884462 1.3878 2.62239 + vertex 0.884356 1.39282 2.62264 + vertex 0.881018 1.38943 2.62085 + endloop + endfacet + facet normal -0.42988 -0.0544195 0.901244 + outer loop + vertex 0.881164 1.3844 2.62061 + vertex 0.884462 1.3878 2.62239 + vertex 0.881018 1.38943 2.62085 + endloop + endfacet + facet normal -0.445699 -0.054518 0.893521 + outer loop + vertex 0.881018 1.38943 2.62085 + vertex 0.877743 1.38603 2.61901 + vertex 0.881164 1.3844 2.62061 + endloop + endfacet + facet normal -0.445743 -0.0546382 0.893492 + outer loop + vertex 0.877743 1.38603 2.61901 + vertex 0.878012 1.38102 2.61883 + vertex 0.881164 1.3844 2.62061 + endloop + endfacet + facet normal -0.444577 -0.0559886 0.893989 + outer loop + vertex 0.881164 1.3844 2.62061 + vertex 0.878012 1.38102 2.61883 + vertex 0.881526 1.37939 2.62048 + endloop + endfacet + facet normal -0.427096 -0.0549549 0.902535 + outer loop + vertex 0.881526 1.37939 2.62048 + vertex 0.8847 1.38277 2.62219 + vertex 0.881164 1.3844 2.62061 + endloop + endfacet + facet normal -0.425238 -0.0570779 0.90328 + outer loop + vertex 0.885181 1.3777 2.62209 + vertex 0.8847 1.38277 2.62219 + vertex 0.881526 1.37939 2.62048 + endloop + endfacet + facet normal -0.424202 -0.0542099 0.903943 + outer loop + vertex 0.882154 1.37457 2.62049 + vertex 0.885181 1.3777 2.62209 + vertex 0.881526 1.37939 2.62048 + endloop + endfacet + facet normal -0.443365 -0.0567183 0.894545 + outer loop + vertex 0.881526 1.37939 2.62048 + vertex 0.878594 1.37602 2.61881 + vertex 0.882154 1.37457 2.62049 + endloop + endfacet + facet normal -0.443325 -0.0565861 0.894573 + outer loop + vertex 0.878594 1.37602 2.61881 + vertex 0.879692 1.37126 2.61906 + vertex 0.882154 1.37457 2.62049 + endloop + endfacet + facet normal -0.459058 -0.0606403 0.886334 + outer loop + vertex 0.879692 1.37126 2.61906 + vertex 0.878594 1.37602 2.61881 + vertex 0.875733 1.37233 2.61708 + endloop + endfacet + facet normal -0.460702 -0.0590146 0.885591 + outer loop + vertex 0.875733 1.37233 2.61708 + vertex 0.878594 1.37602 2.61881 + vertex 0.875023 1.37776 2.61707 + endloop + endfacet + facet normal -0.473054 -0.0606396 0.878944 + outer loop + vertex 0.875733 1.37233 2.61708 + vertex 0.875023 1.37776 2.61707 + vertex 0.872043 1.37488 2.61527 + endloop + endfacet + facet normal -0.473335 -0.0611816 0.878755 + outer loop + vertex 0.872687 1.37068 2.61532 + vertex 0.875733 1.37233 2.61708 + vertex 0.872043 1.37488 2.61527 + endloop + endfacet + facet normal -0.486894 -0.0633627 0.87116 + outer loop + vertex 0.872687 1.37068 2.61532 + vertex 0.872043 1.37488 2.61527 + vertex 0.869181 1.37133 2.61341 + endloop + endfacet + facet normal -0.487293 -0.0669352 0.87067 + outer loop + vertex 0.872687 1.37068 2.61532 + vertex 0.869181 1.37133 2.61341 + vertex 0.871711 1.3665 2.61446 + endloop + endfacet + facet normal -0.480667 -0.0692064 0.874168 + outer loop + vertex 0.871711 1.3665 2.61446 + vertex 0.874639 1.36829 2.61621 + vertex 0.872687 1.37068 2.61532 + endloop + endfacet + facet normal -0.479908 -0.0707388 0.874462 + outer loop + vertex 0.874639 1.36829 2.61621 + vertex 0.871711 1.3665 2.61446 + vertex 0.875203 1.36429 2.61619 + endloop + endfacet + facet normal -0.490329 -0.0689256 0.868808 + outer loop + vertex 0.871711 1.3665 2.61446 + vertex 0.869181 1.37133 2.61341 + vertex 0.868379 1.3668 2.6126 + endloop + endfacet + facet normal -0.490405 -0.0711267 0.868587 + outer loop + vertex 0.869078 1.36272 2.61266 + vertex 0.871711 1.3665 2.61446 + vertex 0.868379 1.3668 2.6126 + endloop + endfacet + facet normal -0.500453 -0.0729373 0.862686 + outer loop + vertex 0.869078 1.36272 2.61266 + vertex 0.868379 1.3668 2.6126 + vertex 0.865958 1.36425 2.61098 + endloop + endfacet + facet normal -0.500705 -0.0736814 0.862477 + outer loop + vertex 0.86636 1.35967 2.61082 + vertex 0.869078 1.36272 2.61266 + vertex 0.865958 1.36425 2.61098 + endloop + endfacet + facet normal -0.510964 -0.0743723 0.856378 + outer loop + vertex 0.865958 1.36425 2.61098 + vertex 0.863278 1.36121 2.60912 + vertex 0.86636 1.35967 2.61082 + endloop + endfacet + facet normal -0.511066 -0.0746717 0.856292 + outer loop + vertex 0.863278 1.36121 2.60912 + vertex 0.863957 1.35714 2.60917 + vertex 0.86636 1.35967 2.61082 + endloop + endfacet + facet normal -0.509613 -0.0765107 0.856995 + outer loop + vertex 0.86636 1.35967 2.61082 + vertex 0.863957 1.35714 2.60917 + vertex 0.866586 1.35495 2.61053 + endloop + endfacet + facet normal -0.500781 -0.0764047 0.862195 + outer loop + vertex 0.866586 1.35495 2.61053 + vertex 0.869502 1.35787 2.61249 + vertex 0.86636 1.35967 2.61082 + endloop + endfacet + facet normal -0.50113 -0.075948 0.862033 + outer loop + vertex 0.869922 1.35282 2.61229 + vertex 0.869502 1.35787 2.61249 + vertex 0.866586 1.35495 2.61053 + endloop + endfacet + facet normal -0.50229 -0.0785158 0.861127 + outer loop + vertex 0.866992 1.3499 2.61031 + vertex 0.869922 1.35282 2.61229 + vertex 0.866586 1.35495 2.61053 + endloop + endfacet + facet normal -0.514094 -0.0791518 0.854074 + outer loop + vertex 0.866586 1.35495 2.61053 + vertex 0.863187 1.35256 2.60827 + vertex 0.866992 1.3499 2.61031 + endloop + endfacet + facet normal -0.514858 -0.0807107 0.853468 + outer loop + vertex 0.863187 1.35256 2.60827 + vertex 0.864221 1.34636 2.6083 + vertex 0.866992 1.3499 2.61031 + endloop + endfacet + facet normal -0.514509 -0.0810828 0.853643 + outer loop + vertex 0.867686 1.34559 2.61032 + vertex 0.866992 1.3499 2.61031 + vertex 0.864221 1.34636 2.6083 + endloop + endfacet + facet normal -0.51479 -0.0833826 0.853252 + outer loop + vertex 0.867686 1.34559 2.61032 + vertex 0.864221 1.34636 2.6083 + vertex 0.866798 1.34139 2.60937 + endloop + endfacet + facet normal -0.505846 -0.0864066 0.858285 + outer loop + vertex 0.866798 1.34139 2.60937 + vertex 0.869831 1.34304 2.61133 + vertex 0.867686 1.34559 2.61032 + endloop + endfacet + facet normal -0.500652 -0.0806311 0.861885 + outer loop + vertex 0.869831 1.34304 2.61133 + vertex 0.87073 1.34731 2.61225 + vertex 0.867686 1.34559 2.61032 + endloop + endfacet + facet normal -0.490637 -0.0839144 0.867314 + outer loop + vertex 0.869831 1.34304 2.61133 + vertex 0.873642 1.34192 2.61337 + vertex 0.87073 1.34731 2.61225 + endloop + endfacet + facet normal -0.489626 -0.0832343 0.867951 + outer loop + vertex 0.873642 1.34192 2.61337 + vertex 0.87417 1.34693 2.61415 + vertex 0.87073 1.34731 2.61225 + endloop + endfacet + facet normal -0.490942 -0.0855694 0.86698 + outer loop + vertex 0.870333 1.33894 2.61121 + vertex 0.873642 1.34192 2.61337 + vertex 0.869831 1.34304 2.61133 + endloop + endfacet + facet normal -0.491896 -0.0842117 0.866572 + outer loop + vertex 0.873123 1.3369 2.61259 + vertex 0.873642 1.34192 2.61337 + vertex 0.870333 1.33894 2.61121 + endloop + endfacet + facet normal -0.493961 -0.0880811 0.865011 + outer loop + vertex 0.870826 1.33426 2.61101 + vertex 0.873123 1.3369 2.61259 + vertex 0.870333 1.33894 2.61121 + endloop + endfacet + facet normal -0.504564 -0.0889369 0.858781 + outer loop + vertex 0.870333 1.33894 2.61121 + vertex 0.867599 1.33608 2.6093 + vertex 0.870826 1.33426 2.61101 + endloop + endfacet + facet normal -0.505315 -0.0908757 0.858137 + outer loop + vertex 0.867599 1.33608 2.6093 + vertex 0.868257 1.33124 2.60918 + vertex 0.870826 1.33426 2.61101 + endloop + endfacet + facet normal -0.50448 -0.0918231 0.858527 + outer loop + vertex 0.870826 1.33426 2.61101 + vertex 0.868257 1.33124 2.60918 + vertex 0.871408 1.3297 2.61086 + endloop + endfacet + facet normal -0.491844 -0.0904504 0.865972 + outer loop + vertex 0.871408 1.3297 2.61086 + vertex 0.874029 1.33274 2.61267 + vertex 0.870826 1.33426 2.61101 + endloop + endfacet + facet normal -0.491104 -0.0912853 0.866304 + outer loop + vertex 0.874597 1.32792 2.61249 + vertex 0.874029 1.33274 2.61267 + vertex 0.871408 1.3297 2.61086 + endloop + endfacet + facet normal -0.492131 -0.0939172 0.86544 + outer loop + vertex 0.871717 1.32504 2.61054 + vertex 0.874597 1.32792 2.61249 + vertex 0.871408 1.3297 2.61086 + endloop + endfacet + facet normal -0.503225 -0.0941982 0.859006 + outer loop + vertex 0.871408 1.3297 2.61086 + vertex 0.869047 1.32719 2.60921 + vertex 0.871717 1.32504 2.61054 + endloop + endfacet + facet normal -0.506472 -0.0998006 0.856461 + outer loop + vertex 0.869047 1.32719 2.60921 + vertex 0.8683 1.32267 2.60824 + vertex 0.871717 1.32504 2.61054 + endloop + endfacet + facet normal -0.508139 -0.0967838 0.85582 + outer loop + vertex 0.871717 1.32504 2.61054 + vertex 0.8683 1.32267 2.60824 + vertex 0.872124 1.32008 2.61022 + endloop + endfacet + facet normal -0.494326 -0.0961753 0.86394 + outer loop + vertex 0.872124 1.32008 2.61022 + vertex 0.875082 1.32295 2.61223 + vertex 0.871717 1.32504 2.61054 + endloop + endfacet + facet normal -0.493761 -0.0969265 0.864179 + outer loop + vertex 0.875775 1.31752 2.61201 + vertex 0.875082 1.32295 2.61223 + vertex 0.872124 1.32008 2.61022 + endloop + endfacet + facet normal -0.49352 -0.0964497 0.86437 + outer loop + vertex 0.872777 1.31586 2.61012 + vertex 0.875775 1.31752 2.61201 + vertex 0.872124 1.32008 2.61022 + endloop + endfacet + facet normal -0.509406 -0.0986857 0.854849 + outer loop + vertex 0.872777 1.31586 2.61012 + vertex 0.872124 1.32008 2.61022 + vertex 0.869353 1.31655 2.60816 + endloop + endfacet + facet normal -0.509759 -0.102214 0.854224 + outer loop + vertex 0.872777 1.31586 2.61012 + vertex 0.869353 1.31655 2.60816 + vertex 0.87198 1.31168 2.60914 + endloop + endfacet + facet normal -0.500941 -0.10503 0.859085 + outer loop + vertex 0.87198 1.31168 2.60914 + vertex 0.874736 1.31346 2.61097 + vertex 0.872777 1.31586 2.61012 + endloop + endfacet + facet normal -0.499548 -0.107677 0.859569 + outer loop + vertex 0.874736 1.31346 2.61097 + vertex 0.87198 1.31168 2.60914 + vertex 0.87548 1.30949 2.6109 + endloop + endfacet + facet normal -0.511379 -0.10331 0.853123 + outer loop + vertex 0.87198 1.31168 2.60914 + vertex 0.869353 1.31655 2.60816 + vertex 0.868717 1.31207 2.60723 + endloop + endfacet + facet normal -0.511444 -0.10506 0.85287 + outer loop + vertex 0.869685 1.30792 2.6073 + vertex 0.87198 1.31168 2.60914 + vertex 0.868717 1.31207 2.60723 + endloop + endfacet + facet normal -0.52094 -0.107375 0.846813 + outer loop + vertex 0.869685 1.30792 2.6073 + vertex 0.868717 1.31207 2.60723 + vertex 0.866453 1.30988 2.60556 + endloop + endfacet + facet normal -0.52085 -0.107153 0.846897 + outer loop + vertex 0.867076 1.30506 2.60534 + vertex 0.869685 1.30792 2.6073 + vertex 0.866453 1.30988 2.60556 + endloop + endfacet + facet normal -0.531818 -0.108239 0.839913 + outer loop + vertex 0.866453 1.30988 2.60556 + vertex 0.863299 1.30773 2.60329 + vertex 0.867076 1.30506 2.60534 + endloop + endfacet + facet normal -0.531401 -0.107362 0.84029 + outer loop + vertex 0.863299 1.30773 2.60329 + vertex 0.864418 1.30158 2.60321 + vertex 0.867076 1.30506 2.60534 + endloop + endfacet + facet normal -0.531031 -0.107756 0.840473 + outer loop + vertex 0.867869 1.30077 2.60529 + vertex 0.867076 1.30506 2.60534 + vertex 0.864418 1.30158 2.60321 + endloop + endfacet + facet normal -0.531007 -0.10755 0.840514 + outer loop + vertex 0.867869 1.30077 2.60529 + vertex 0.864418 1.30158 2.60321 + vertex 0.867056 1.29654 2.60423 + endloop + endfacet + facet normal -0.522288 -0.110492 0.845581 + outer loop + vertex 0.867056 1.29654 2.60423 + vertex 0.870016 1.29818 2.60627 + vertex 0.867869 1.30077 2.60529 + endloop + endfacet + facet normal -0.518418 -0.106166 0.848511 + outer loop + vertex 0.870016 1.29818 2.60627 + vertex 0.870814 1.30248 2.6073 + vertex 0.867869 1.30077 2.60529 + endloop + endfacet + facet normal -0.507084 -0.109786 0.854876 + outer loop + vertex 0.870016 1.29818 2.60627 + vertex 0.873787 1.29702 2.60836 + vertex 0.870814 1.30248 2.6073 + endloop + endfacet + facet normal -0.506093 -0.109116 0.855548 + outer loop + vertex 0.873787 1.29702 2.60836 + vertex 0.874234 1.30211 2.60928 + vertex 0.870814 1.30248 2.6073 + endloop + endfacet + facet normal -0.506079 -0.108584 0.855625 + outer loop + vertex 0.874234 1.30211 2.60928 + vertex 0.873101 1.3064 2.60915 + vertex 0.870814 1.30248 2.6073 + endloop + endfacet + facet normal -0.509223 -0.106016 0.85408 + outer loop + vertex 0.870814 1.30248 2.6073 + vertex 0.873101 1.3064 2.60915 + vertex 0.869685 1.30792 2.6073 + endloop + endfacet + facet normal -0.506961 -0.109095 0.855037 + outer loop + vertex 0.870565 1.29409 2.60608 + vertex 0.873787 1.29702 2.60836 + vertex 0.870016 1.29818 2.60627 + endloop + endfacet + facet normal -0.507415 -0.10845 0.85485 + outer loop + vertex 0.873308 1.29201 2.60744 + vertex 0.873787 1.29702 2.60836 + vertex 0.870565 1.29409 2.60608 + endloop + endfacet + facet normal -0.509205 -0.111798 0.853353 + outer loop + vertex 0.871152 1.28958 2.60584 + vertex 0.873308 1.29201 2.60744 + vertex 0.870565 1.29409 2.60608 + endloop + endfacet + facet normal -0.520031 -0.112848 0.84666 + outer loop + vertex 0.870565 1.29409 2.60608 + vertex 0.868038 1.2913 2.60416 + vertex 0.871152 1.28958 2.60584 + endloop + endfacet + facet normal -0.519797 -0.112204 0.846889 + outer loop + vertex 0.868038 1.2913 2.60416 + vertex 0.869001 1.28725 2.60421 + vertex 0.871152 1.28958 2.60584 + endloop + endfacet + facet normal -0.516382 -0.11642 0.848408 + outer loop + vertex 0.871152 1.28958 2.60584 + vertex 0.869001 1.28725 2.60421 + vertex 0.87169 1.2851 2.60555 + endloop + endfacet + facet normal -0.503356 -0.115367 0.856343 + outer loop + vertex 0.87169 1.2851 2.60555 + vertex 0.874281 1.28791 2.60745 + vertex 0.871152 1.28958 2.60584 + endloop + endfacet + facet normal -0.50066 -0.118616 0.857478 + outer loop + vertex 0.875071 1.28309 2.60725 + vertex 0.874281 1.28791 2.60745 + vertex 0.87169 1.2851 2.60555 + endloop + endfacet + facet normal -0.498098 -0.112338 0.859813 + outer loop + vertex 0.87224 1.28021 2.60523 + vertex 0.875071 1.28309 2.60725 + vertex 0.87169 1.2851 2.60555 + endloop + endfacet + facet normal -0.517575 -0.113764 0.848041 + outer loop + vertex 0.87169 1.2851 2.60555 + vertex 0.868423 1.28278 2.60325 + vertex 0.87224 1.28021 2.60523 + endloop + endfacet + facet normal -0.514028 -0.106049 0.851193 + outer loop + vertex 0.868423 1.28278 2.60325 + vertex 0.869493 1.27666 2.60313 + vertex 0.87224 1.28021 2.60523 + endloop + endfacet + facet normal -0.513149 -0.106975 0.851607 + outer loop + vertex 0.872914 1.27601 2.60511 + vertex 0.87224 1.28021 2.60523 + vertex 0.869493 1.27666 2.60313 + endloop + endfacet + facet normal -0.512996 -0.105232 0.851916 + outer loop + vertex 0.872914 1.27601 2.60511 + vertex 0.869493 1.27666 2.60313 + vertex 0.872067 1.27175 2.60407 + endloop + endfacet + facet normal -0.514573 -0.106266 0.850836 + outer loop + vertex 0.872067 1.27175 2.60407 + vertex 0.869493 1.27666 2.60313 + vertex 0.868761 1.27213 2.60212 + endloop + endfacet + facet normal -0.51476 -0.113092 0.849842 + outer loop + vertex 0.869588 1.26793 2.60206 + vertex 0.872067 1.27175 2.60407 + vertex 0.868761 1.27213 2.60212 + endloop + endfacet + facet normal -0.530642 -0.116085 0.839609 + outer loop + vertex 0.869588 1.26793 2.60206 + vertex 0.868761 1.27213 2.60212 + vertex 0.866399 1.26997 2.60033 + endloop + endfacet + facet normal -0.532476 -0.120469 0.837829 + outer loop + vertex 0.867043 1.26573 2.60013 + vertex 0.869588 1.26793 2.60206 + vertex 0.866399 1.26997 2.60033 + endloop + endfacet + facet normal -0.546814 -0.122198 0.828289 + outer loop + vertex 0.866399 1.26997 2.60033 + vertex 0.863894 1.26727 2.59828 + vertex 0.867043 1.26573 2.60013 + endloop + endfacet + facet normal -0.550849 -0.136398 0.823384 + outer loop + vertex 0.863894 1.26727 2.59828 + vertex 0.865332 1.26188 2.59835 + vertex 0.867043 1.26573 2.60013 + endloop + endfacet + facet normal -0.556299 -0.1379 0.81946 + outer loop + vertex 0.865332 1.26188 2.59835 + vertex 0.863894 1.26727 2.59828 + vertex 0.861326 1.26456 2.59608 + endloop + endfacet + facet normal -0.560877 -0.131844 0.817334 + outer loop + vertex 0.861326 1.26456 2.59608 + vertex 0.863894 1.26727 2.59828 + vertex 0.860553 1.26935 2.59632 + endloop + endfacet + facet normal -0.563347 -0.132154 0.815583 + outer loop + vertex 0.860553 1.26935 2.59632 + vertex 0.858459 1.26706 2.5945 + vertex 0.861326 1.26456 2.59608 + endloop + endfacet + facet normal -0.571282 -0.146248 0.807619 + outer loop + vertex 0.858459 1.26706 2.5945 + vertex 0.858124 1.26257 2.59345 + vertex 0.861326 1.26456 2.59608 + endloop + endfacet + facet normal -0.569711 -0.149477 0.808138 + outer loop + vertex 0.861326 1.26456 2.59608 + vertex 0.858124 1.26257 2.59345 + vertex 0.861948 1.25958 2.5956 + endloop + endfacet + facet normal -0.560847 -0.148975 0.814406 + outer loop + vertex 0.861948 1.25958 2.5956 + vertex 0.865332 1.26188 2.59835 + vertex 0.861326 1.26456 2.59608 + endloop + endfacet + facet normal -0.561825 -0.147126 0.814068 + outer loop + vertex 0.865089 1.25671 2.59725 + vertex 0.865332 1.26188 2.59835 + vertex 0.861948 1.25958 2.5956 + endloop + endfacet + facet normal -0.566569 -0.15507 0.809292 + outer loop + vertex 0.862652 1.25551 2.59531 + vertex 0.865089 1.25671 2.59725 + vertex 0.861948 1.25958 2.5956 + endloop + endfacet + facet normal -0.575323 -0.156128 0.802887 + outer loop + vertex 0.862652 1.25551 2.59531 + vertex 0.861948 1.25958 2.5956 + vertex 0.859444 1.25648 2.5932 + endloop + endfacet + facet normal -0.575266 -0.155659 0.803019 + outer loop + vertex 0.862652 1.25551 2.59531 + vertex 0.859444 1.25648 2.5932 + vertex 0.86223 1.25162 2.59425 + endloop + endfacet + facet normal -0.569715 -0.157251 0.806658 + outer loop + vertex 0.86223 1.25162 2.59425 + vertex 0.864683 1.25316 2.59628 + vertex 0.862652 1.25551 2.59531 + endloop + endfacet + facet normal -0.570607 -0.15545 0.806376 + outer loop + vertex 0.864683 1.25316 2.59628 + vertex 0.86223 1.25162 2.59425 + vertex 0.865656 1.24931 2.59623 + endloop + endfacet + facet normal -0.557208 -0.152197 0.816306 + outer loop + vertex 0.865656 1.24931 2.59623 + vertex 0.867929 1.25262 2.5984 + vertex 0.864683 1.25316 2.59628 + endloop + endfacet + facet normal -0.557335 -0.156686 0.81537 + outer loop + vertex 0.864683 1.25316 2.59628 + vertex 0.867929 1.25262 2.5984 + vertex 0.865089 1.25671 2.59725 + endloop + endfacet + facet normal -0.553591 -0.15318 0.81858 + outer loop + vertex 0.867929 1.25262 2.5984 + vertex 0.868259 1.25767 2.59957 + vertex 0.865089 1.25671 2.59725 + endloop + endfacet + facet normal -0.553541 -0.155888 0.818102 + outer loop + vertex 0.869383 1.24661 2.59824 + vertex 0.867929 1.25262 2.5984 + vertex 0.865656 1.24931 2.59623 + endloop + endfacet + facet normal -0.550923 -0.150174 0.820933 + outer loop + vertex 0.866293 1.24464 2.5958 + vertex 0.869383 1.24661 2.59824 + vertex 0.865656 1.24931 2.59623 + endloop + endfacet + facet normal -0.566945 -0.151332 0.809736 + outer loop + vertex 0.865656 1.24931 2.59623 + vertex 0.863576 1.2472 2.59438 + vertex 0.866293 1.24464 2.5958 + endloop + endfacet + facet normal -0.567653 -0.152478 0.809024 + outer loop + vertex 0.863576 1.2472 2.59438 + vertex 0.863282 1.24278 2.59334 + vertex 0.866293 1.24464 2.5958 + endloop + endfacet + facet normal -0.565872 -0.156104 0.809581 + outer loop + vertex 0.866293 1.24464 2.5958 + vertex 0.863282 1.24278 2.59334 + vertex 0.866984 1.23994 2.59538 + endloop + endfacet + facet normal -0.552089 -0.154948 0.819261 + outer loop + vertex 0.866984 1.23994 2.59538 + vertex 0.869083 1.24207 2.5972 + vertex 0.866293 1.24464 2.5958 + endloop + endfacet + facet normal -0.543663 -0.166166 0.82269 + outer loop + vertex 0.870605 1.23753 2.59729 + vertex 0.869083 1.24207 2.5972 + vertex 0.866984 1.23994 2.59538 + endloop + endfacet + facet normal -0.539796 -0.156871 0.82705 + outer loop + vertex 0.868059 1.23603 2.59534 + vertex 0.870605 1.23753 2.59729 + vertex 0.866984 1.23994 2.59538 + endloop + endfacet + facet normal -0.558037 -0.161761 0.813897 + outer loop + vertex 0.868059 1.23603 2.59534 + vertex 0.866984 1.23994 2.59538 + vertex 0.864798 1.23671 2.59324 + endloop + endfacet + facet normal -0.558222 -0.165132 0.813093 + outer loop + vertex 0.868059 1.23603 2.59534 + vertex 0.864798 1.23671 2.59324 + vertex 0.867798 1.23253 2.59445 + endloop + endfacet + facet normal -0.553482 -0.160533 0.817243 + outer loop + vertex 0.867798 1.23253 2.59445 + vertex 0.864798 1.23671 2.59324 + vertex 0.864925 1.23164 2.59233 + endloop + endfacet + facet normal -0.528783 -0.160958 0.833356 + outer loop + vertex 0.870605 1.23753 2.59729 + vertex 0.872364 1.24173 2.59921 + vertex 0.869083 1.24207 2.5972 + endloop + endfacet + facet normal -0.528827 -0.156153 0.834241 + outer loop + vertex 0.872364 1.24173 2.59921 + vertex 0.869383 1.24661 2.59824 + vertex 0.869083 1.24207 2.5972 + endloop + endfacet + facet normal -0.528025 -0.155539 0.834863 + outer loop + vertex 0.872844 1.24588 2.60029 + vertex 0.869383 1.24661 2.59824 + vertex 0.872364 1.24173 2.59921 + endloop + endfacet + facet normal -0.507398 -0.160953 0.846547 + outer loop + vertex 0.872364 1.24173 2.59921 + vertex 0.87514 1.2434 2.6012 + vertex 0.872844 1.24588 2.60029 + endloop + endfacet + facet normal -0.499911 -0.151798 0.85267 + outer loop + vertex 0.87514 1.2434 2.6012 + vertex 0.875739 1.24762 2.6023 + vertex 0.872844 1.24588 2.60029 + endloop + endfacet + facet normal -0.486143 -0.15564 0.859908 + outer loop + vertex 0.87514 1.2434 2.6012 + vertex 0.879007 1.24231 2.60318 + vertex 0.875739 1.24762 2.6023 + endloop + endfacet + facet normal -0.482324 -0.152851 0.862555 + outer loop + vertex 0.879007 1.24231 2.60318 + vertex 0.879242 1.24725 2.60419 + vertex 0.875739 1.24762 2.6023 + endloop + endfacet + facet normal -0.482344 -0.155539 0.862062 + outer loop + vertex 0.879242 1.24725 2.60419 + vertex 0.877998 1.25142 2.60425 + vertex 0.875739 1.24762 2.6023 + endloop + endfacet + facet normal -0.484976 -0.153409 0.860967 + outer loop + vertex 0.875739 1.24762 2.6023 + vertex 0.877998 1.25142 2.60425 + vertex 0.874326 1.25305 2.60247 + endloop + endfacet + facet normal -0.485438 -0.155048 0.860413 + outer loop + vertex 0.877998 1.25142 2.60425 + vertex 0.876826 1.25667 2.60453 + vertex 0.874326 1.25305 2.60247 + endloop + endfacet + facet normal -0.49072 -0.150178 0.858278 + outer loop + vertex 0.874326 1.25305 2.60247 + vertex 0.876826 1.25667 2.60453 + vertex 0.872836 1.25767 2.60243 + endloop + endfacet + facet normal -0.490244 -0.146296 0.85922 + outer loop + vertex 0.876826 1.25667 2.60453 + vertex 0.874554 1.26136 2.60404 + vertex 0.872836 1.25767 2.60243 + endloop + endfacet + facet normal -0.488041 -0.145075 0.860679 + outer loop + vertex 0.877723 1.26072 2.60572 + vertex 0.874554 1.26136 2.60404 + vertex 0.876826 1.25667 2.60453 + endloop + endfacet + facet normal -0.478059 -0.148749 0.86564 + outer loop + vertex 0.876826 1.25667 2.60453 + vertex 0.879886 1.25823 2.60649 + vertex 0.877723 1.26072 2.60572 + endloop + endfacet + facet normal -0.486946 -0.133046 0.86324 + outer loop + vertex 0.877723 1.26072 2.60572 + vertex 0.876804 1.26478 2.60583 + vertex 0.874554 1.26136 2.60404 + endloop + endfacet + facet normal -0.492797 -0.127851 0.8607 + outer loop + vertex 0.873125 1.26625 2.60394 + vertex 0.874554 1.26136 2.60404 + vertex 0.876804 1.26478 2.60583 + endloop + endfacet + facet normal -0.491322 -0.122018 0.862389 + outer loop + vertex 0.875652 1.26962 2.60586 + vertex 0.873125 1.26625 2.60394 + vertex 0.876804 1.26478 2.60583 + endloop + endfacet + facet normal -0.474819 -0.118154 0.872116 + outer loop + vertex 0.876804 1.26478 2.60583 + vertex 0.879239 1.26807 2.6076 + vertex 0.875652 1.26962 2.60586 + endloop + endfacet + facet normal -0.470093 -0.122689 0.874048 + outer loop + vertex 0.880613 1.26249 2.60756 + vertex 0.879239 1.26807 2.6076 + vertex 0.876804 1.26478 2.60583 + endloop + endfacet + facet normal -0.468225 -0.122237 0.875113 + outer loop + vertex 0.880613 1.26249 2.60756 + vertex 0.882874 1.26648 2.60932 + vertex 0.879239 1.26807 2.6076 + endloop + endfacet + facet normal -0.468824 -0.121783 0.874856 + outer loop + vertex 0.884107 1.26214 2.60938 + vertex 0.882874 1.26648 2.60932 + vertex 0.880613 1.26249 2.60756 + endloop + endfacet + facet normal -0.469144 -0.138916 0.872127 + outer loop + vertex 0.883765 1.25711 2.6084 + vertex 0.884107 1.26214 2.60938 + vertex 0.880613 1.26249 2.60756 + endloop + endfacet + facet normal -0.468741 -0.138639 0.872388 + outer loop + vertex 0.879886 1.25823 2.60649 + vertex 0.883765 1.25711 2.6084 + vertex 0.880613 1.26249 2.60756 + endloop + endfacet + facet normal -0.468812 -0.138618 0.872353 + outer loop + vertex 0.879886 1.25823 2.60649 + vertex 0.880613 1.26249 2.60756 + vertex 0.877723 1.26072 2.60572 + endloop + endfacet + facet normal -0.47094 -0.152014 0.868969 + outer loop + vertex 0.880548 1.25421 2.60615 + vertex 0.883765 1.25711 2.6084 + vertex 0.879886 1.25823 2.60649 + endloop + endfacet + facet normal -0.476273 -0.152633 0.865949 + outer loop + vertex 0.879886 1.25823 2.60649 + vertex 0.876826 1.25667 2.60453 + vertex 0.880548 1.25421 2.60615 + endloop + endfacet + facet normal -0.471887 -0.150737 0.868678 + outer loop + vertex 0.883456 1.25216 2.60737 + vertex 0.883765 1.25711 2.6084 + vertex 0.880548 1.25421 2.60615 + endloop + endfacet + facet normal -0.473776 -0.15442 0.867001 + outer loop + vertex 0.881353 1.24971 2.60578 + vertex 0.883456 1.25216 2.60737 + vertex 0.880548 1.25421 2.60615 + endloop + endfacet + facet normal -0.475496 -0.154648 0.866018 + outer loop + vertex 0.880548 1.25421 2.60615 + vertex 0.877998 1.25142 2.60425 + vertex 0.881353 1.24971 2.60578 + endloop + endfacet + facet normal -0.476328 -0.151645 0.866092 + outer loop + vertex 0.884676 1.248 2.60731 + vertex 0.883456 1.25216 2.60737 + vertex 0.881353 1.24971 2.60578 + endloop + endfacet + facet normal -0.476303 -0.151573 0.866119 + outer loop + vertex 0.882156 1.2452 2.60544 + vertex 0.884676 1.248 2.60731 + vertex 0.881353 1.24971 2.60578 + endloop + endfacet + facet normal -0.476728 -0.15163 0.865875 + outer loop + vertex 0.881353 1.24971 2.60578 + vertex 0.879242 1.24725 2.60419 + vertex 0.882156 1.2452 2.60544 + endloop + endfacet + facet normal -0.478883 -0.148642 0.865203 + outer loop + vertex 0.885824 1.24272 2.60704 + vertex 0.884676 1.248 2.60731 + vertex 0.882156 1.2452 2.60544 + endloop + endfacet + facet normal -0.479356 -0.149625 0.864772 + outer loop + vertex 0.882843 1.2412 2.60513 + vertex 0.885824 1.24272 2.60704 + vertex 0.882156 1.2452 2.60544 + endloop + endfacet + facet normal -0.480545 -0.149776 0.864086 + outer loop + vertex 0.882843 1.2412 2.60513 + vertex 0.882156 1.2452 2.60544 + vertex 0.879007 1.24231 2.60318 + endloop + endfacet + facet normal -0.481025 -0.152841 0.863281 + outer loop + vertex 0.882843 1.2412 2.60513 + vertex 0.879007 1.24231 2.60318 + vertex 0.882288 1.23706 2.60408 + endloop + endfacet + facet normal -0.483598 -0.152163 0.861962 + outer loop + vertex 0.882288 1.23706 2.60408 + vertex 0.884975 1.23875 2.60589 + vertex 0.882843 1.2412 2.60513 + endloop + endfacet + facet normal -0.483581 -0.152195 0.861966 + outer loop + vertex 0.884975 1.23875 2.60589 + vertex 0.882288 1.23706 2.60408 + vertex 0.885943 1.2349 2.60575 + endloop + endfacet + facet normal -0.479886 -0.151346 0.864178 + outer loop + vertex 0.885943 1.2349 2.60575 + vertex 0.887993 1.23797 2.60743 + vertex 0.884975 1.23875 2.60589 + endloop + endfacet + facet normal -0.479495 -0.148382 0.864909 + outer loop + vertex 0.884975 1.23875 2.60589 + vertex 0.887993 1.23797 2.60743 + vertex 0.885824 1.24272 2.60704 + endloop + endfacet + facet normal -0.476396 -0.146807 0.866888 + outer loop + vertex 0.887993 1.23797 2.60743 + vertex 0.889802 1.2416 2.60904 + vertex 0.885824 1.24272 2.60704 + endloop + endfacet + facet normal -0.477904 -0.153098 0.864968 + outer loop + vertex 0.889481 1.23315 2.6074 + vertex 0.887993 1.23797 2.60743 + vertex 0.885943 1.2349 2.60575 + endloop + endfacet + facet normal -0.479452 -0.157858 0.863254 + outer loop + vertex 0.886995 1.23023 2.60548 + vertex 0.889481 1.23315 2.6074 + vertex 0.885943 1.2349 2.60575 + endloop + endfacet + facet normal -0.484402 -0.158806 0.860311 + outer loop + vertex 0.885943 1.2349 2.60575 + vertex 0.883938 1.23241 2.60416 + vertex 0.886995 1.23023 2.60548 + endloop + endfacet + facet normal -0.488312 -0.166545 0.85663 + outer loop + vertex 0.883938 1.23241 2.60416 + vertex 0.883977 1.22733 2.6032 + vertex 0.886995 1.23023 2.60548 + endloop + endfacet + facet normal -0.487713 -0.167317 0.85682 + outer loop + vertex 0.887851 1.22616 2.60517 + vertex 0.886995 1.23023 2.60548 + vertex 0.883977 1.22733 2.6032 + endloop + endfacet + facet normal -0.488722 -0.173762 0.854961 + outer loop + vertex 0.887851 1.22616 2.60517 + vertex 0.883977 1.22733 2.6032 + vertex 0.887409 1.22203 2.60408 + endloop + endfacet + facet normal -0.481941 -0.175415 0.858465 + outer loop + vertex 0.887409 1.22203 2.60408 + vertex 0.890056 1.22371 2.60591 + vertex 0.887851 1.22616 2.60517 + endloop + endfacet + facet normal -0.47604 -0.168711 0.863089 + outer loop + vertex 0.890056 1.22371 2.60591 + vertex 0.89079 1.22772 2.6071 + vertex 0.887851 1.22616 2.60517 + endloop + endfacet + facet normal -0.469125 -0.170965 0.866425 + outer loop + vertex 0.890056 1.22371 2.60591 + vertex 0.893078 1.22299 2.60741 + vertex 0.89079 1.22772 2.6071 + endloop + endfacet + facet normal -0.462944 -0.16772 0.870375 + outer loop + vertex 0.893078 1.22299 2.60741 + vertex 0.894818 1.22665 2.60904 + vertex 0.89079 1.22772 2.6071 + endloop + endfacet + facet normal -0.462551 -0.164871 0.871128 + outer loop + vertex 0.894818 1.22665 2.60904 + vertex 0.893251 1.23147 2.60912 + vertex 0.89079 1.22772 2.6071 + endloop + endfacet + facet normal -0.467946 -0.160244 0.869108 + outer loop + vertex 0.89079 1.22772 2.6071 + vertex 0.893251 1.23147 2.60912 + vertex 0.889481 1.23315 2.6074 + endloop + endfacet + facet normal -0.466481 -0.155253 0.8708 + outer loop + vertex 0.893251 1.23147 2.60912 + vertex 0.891951 1.23687 2.60938 + vertex 0.889481 1.23315 2.6074 + endloop + endfacet + facet normal -0.452208 -0.152219 0.878828 + outer loop + vertex 0.891951 1.23687 2.60938 + vertex 0.893251 1.23147 2.60912 + vertex 0.895657 1.23465 2.61091 + endloop + endfacet + facet normal -0.446862 -0.157287 0.880667 + outer loop + vertex 0.895657 1.23465 2.61091 + vertex 0.893251 1.23147 2.60912 + vertex 0.896918 1.22995 2.61071 + endloop + endfacet + facet normal -0.42648 -0.152292 0.891584 + outer loop + vertex 0.896918 1.22995 2.61071 + vertex 0.899368 1.23319 2.61243 + vertex 0.895657 1.23465 2.61091 + endloop + endfacet + facet normal -0.42614 -0.151042 0.891959 + outer loop + vertex 0.899368 1.23319 2.61243 + vertex 0.897844 1.23798 2.61251 + vertex 0.895657 1.23465 2.61091 + endloop + endfacet + facet normal -0.418476 -0.148673 0.895977 + outer loop + vertex 0.899368 1.23319 2.61243 + vertex 0.901993 1.23704 2.6143 + vertex 0.897844 1.23798 2.61251 + endloop + endfacet + facet normal -0.414861 -0.151703 0.897149 + outer loop + vertex 0.903248 1.23163 2.61396 + vertex 0.901993 1.23704 2.6143 + vertex 0.899368 1.23319 2.61243 + endloop + endfacet + facet normal -0.416893 -0.158906 0.894958 + outer loop + vertex 0.900715 1.2278 2.6121 + vertex 0.903248 1.23163 2.61396 + vertex 0.899368 1.23319 2.61243 + endloop + endfacet + facet normal -0.418849 -0.159334 0.893968 + outer loop + vertex 0.900715 1.2278 2.6121 + vertex 0.899368 1.23319 2.61243 + vertex 0.896918 1.22995 2.61071 + endloop + endfacet + facet normal -0.419054 -0.159814 0.893786 + outer loop + vertex 0.897863 1.22601 2.61045 + vertex 0.900715 1.2278 2.6121 + vertex 0.896918 1.22995 2.61071 + endloop + endfacet + facet normal -0.44225 -0.16458 0.881662 + outer loop + vertex 0.897863 1.22601 2.61045 + vertex 0.896918 1.22995 2.61071 + vertex 0.894818 1.22665 2.60904 + endloop + endfacet + facet normal -0.442707 -0.169199 0.880558 + outer loop + vertex 0.897863 1.22601 2.61045 + vertex 0.894818 1.22665 2.60904 + vertex 0.897059 1.22198 2.60927 + endloop + endfacet + facet normal -0.423486 -0.175429 0.888754 + outer loop + vertex 0.897059 1.22198 2.60927 + vertex 0.899894 1.22374 2.61097 + vertex 0.897863 1.22601 2.61045 + endloop + endfacet + facet normal -0.426567 -0.170052 0.888326 + outer loop + vertex 0.899894 1.22374 2.61097 + vertex 0.897059 1.22198 2.60927 + vertex 0.900835 1.21981 2.61066 + endloop + endfacet + facet normal -0.415113 -0.166651 0.894376 + outer loop + vertex 0.899894 1.22374 2.61097 + vertex 0.900715 1.2278 2.6121 + vertex 0.897863 1.22601 2.61045 + endloop + endfacet + facet normal -0.410051 -0.168246 0.89641 + outer loop + vertex 0.899894 1.22374 2.61097 + vertex 0.903045 1.2231 2.61229 + vertex 0.900715 1.2278 2.6121 + endloop + endfacet + facet normal -0.447656 -0.16017 0.879744 + outer loop + vertex 0.893251 1.23147 2.60912 + vertex 0.894818 1.22665 2.60904 + vertex 0.896918 1.22995 2.61071 + endloop + endfacet + facet normal -0.452787 -0.174342 0.874408 + outer loop + vertex 0.897059 1.22198 2.60927 + vertex 0.894818 1.22665 2.60904 + vertex 0.893078 1.22299 2.60741 + endloop + endfacet + facet normal -0.450653 -0.158191 0.878571 + outer loop + vertex 0.894557 1.21824 2.60731 + vertex 0.897059 1.22198 2.60927 + vertex 0.893078 1.22299 2.60741 + endloop + endfacet + facet normal -0.475029 -0.165502 0.864267 + outer loop + vertex 0.894557 1.21824 2.60731 + vertex 0.893078 1.22299 2.60741 + vertex 0.891074 1.21991 2.60572 + endloop + endfacet + facet normal -0.469592 -0.148385 0.870325 + outer loop + vertex 0.892014 1.21535 2.60545 + vertex 0.894557 1.21824 2.60731 + vertex 0.891074 1.21991 2.60572 + endloop + endfacet + facet normal -0.490193 -0.15192 0.858272 + outer loop + vertex 0.891074 1.21991 2.60572 + vertex 0.889064 1.21745 2.60413 + vertex 0.892014 1.21535 2.60545 + endloop + endfacet + facet normal -0.480465 -0.13284 0.866895 + outer loop + vertex 0.889064 1.21745 2.60413 + vertex 0.888878 1.21244 2.60326 + vertex 0.892014 1.21535 2.60545 + endloop + endfacet + facet normal -0.495721 -0.130825 0.858572 + outer loop + vertex 0.888878 1.21244 2.60326 + vertex 0.889064 1.21745 2.60413 + vertex 0.885673 1.21768 2.60221 + endloop + endfacet + facet normal -0.527762 -0.1551 0.835111 + outer loop + vertex 0.885195 1.21354 2.60114 + vertex 0.888878 1.21244 2.60326 + vertex 0.885673 1.21768 2.60221 + endloop + endfacet + facet normal -0.51469 -0.15854 0.842591 + outer loop + vertex 0.885195 1.21354 2.60114 + vertex 0.885673 1.21768 2.60221 + vertex 0.882894 1.21612 2.60022 + endloop + endfacet + facet normal -0.509577 -0.152495 0.846804 + outer loop + vertex 0.882321 1.212 2.59913 + vertex 0.885195 1.21354 2.60114 + vertex 0.882894 1.21612 2.60022 + endloop + endfacet + facet normal -0.504112 -0.154042 0.84979 + outer loop + vertex 0.882894 1.21612 2.60022 + vertex 0.879068 1.21737 2.59818 + vertex 0.882321 1.212 2.59913 + endloop + endfacet + facet normal -0.508558 -0.180664 0.841861 + outer loop + vertex 0.882894 1.21612 2.60022 + vertex 0.881959 1.22006 2.6005 + vertex 0.879068 1.21737 2.59818 + endloop + endfacet + facet normal -0.503732 -0.187131 0.843348 + outer loop + vertex 0.878991 1.22235 2.59923 + vertex 0.879068 1.21737 2.59818 + vertex 0.881959 1.22006 2.6005 + endloop + endfacet + facet normal -0.501668 -0.183301 0.845417 + outer loop + vertex 0.881046 1.22459 2.60094 + vertex 0.878991 1.22235 2.59923 + vertex 0.881959 1.22006 2.6005 + endloop + endfacet + facet normal -0.498285 -0.182822 0.847519 + outer loop + vertex 0.881959 1.22006 2.6005 + vertex 0.884017 1.22231 2.6022 + vertex 0.881046 1.22459 2.60094 + endloop + endfacet + facet normal -0.493739 -0.174429 0.851937 + outer loop + vertex 0.884017 1.22231 2.6022 + vertex 0.883977 1.22733 2.6032 + vertex 0.881046 1.22459 2.60094 + endloop + endfacet + facet normal -0.493419 -0.174852 0.852036 + outer loop + vertex 0.881046 1.22459 2.60094 + vertex 0.883977 1.22733 2.6032 + vertex 0.880092 1.22852 2.60119 + endloop + endfacet + facet normal -0.501861 -0.176554 0.846737 + outer loop + vertex 0.880092 1.22852 2.60119 + vertex 0.877303 1.22699 2.59922 + vertex 0.881046 1.22459 2.60094 + endloop + endfacet + facet normal -0.50278 -0.17468 0.846581 + outer loop + vertex 0.877303 1.22699 2.59922 + vertex 0.880092 1.22852 2.60119 + vertex 0.877697 1.2311 2.6003 + endloop + endfacet + facet normal -0.507548 -0.173534 0.843968 + outer loop + vertex 0.877697 1.2311 2.6003 + vertex 0.873891 1.23232 2.59826 + vertex 0.877303 1.22699 2.59922 + endloop + endfacet + facet normal -0.508817 -0.174522 0.842999 + outer loop + vertex 0.877303 1.22699 2.59922 + vertex 0.873891 1.23232 2.59826 + vertex 0.87389 1.22736 2.59724 + endloop + endfacet + facet normal -0.508736 -0.181717 0.841527 + outer loop + vertex 0.875604 1.22269 2.59726 + vertex 0.877303 1.22699 2.59922 + vertex 0.87389 1.22736 2.59724 + endloop + endfacet + facet normal -0.513813 -0.183598 0.838026 + outer loop + vertex 0.875604 1.22269 2.59726 + vertex 0.87389 1.22736 2.59724 + vertex 0.871778 1.22503 2.59543 + endloop + endfacet + facet normal -0.513239 -0.182135 0.838697 + outer loop + vertex 0.872936 1.22101 2.59527 + vertex 0.875604 1.22269 2.59726 + vertex 0.871778 1.22503 2.59543 + endloop + endfacet + facet normal -0.521937 -0.184398 0.832814 + outer loop + vertex 0.872936 1.22101 2.59527 + vertex 0.871778 1.22503 2.59543 + vertex 0.869477 1.22171 2.59326 + endloop + endfacet + facet normal -0.522166 -0.188646 0.831718 + outer loop + vertex 0.872936 1.22101 2.59527 + vertex 0.869477 1.22171 2.59326 + vertex 0.872584 1.21692 2.59412 + endloop + endfacet + facet normal -0.518859 -0.186019 0.834375 + outer loop + vertex 0.872584 1.21692 2.59412 + vertex 0.869477 1.22171 2.59326 + vertex 0.869245 1.21725 2.59212 + endloop + endfacet + facet normal -0.518994 -0.180448 0.835514 + outer loop + vertex 0.870813 1.21272 2.59211 + vertex 0.872584 1.21692 2.59412 + vertex 0.869245 1.21725 2.59212 + endloop + endfacet + facet normal -0.517992 -0.1811 0.835995 + outer loop + vertex 0.874129 1.21241 2.5941 + vertex 0.872584 1.21692 2.59412 + vertex 0.870813 1.21272 2.59211 + endloop + endfacet + facet normal -0.518598 -0.133741 0.844494 + outer loop + vertex 0.873898 1.20747 2.59318 + vertex 0.874129 1.21241 2.5941 + vertex 0.870813 1.21272 2.59211 + endloop + endfacet + facet normal -0.508245 -0.13535 0.85051 + outer loop + vertex 0.874129 1.21241 2.5941 + vertex 0.873898 1.20747 2.59318 + vertex 0.876907 1.2102 2.59541 + endloop + endfacet + facet normal -0.521991 -0.160192 0.837773 + outer loop + vertex 0.876209 1.21467 2.59583 + vertex 0.874129 1.21241 2.5941 + vertex 0.876907 1.2102 2.59541 + endloop + endfacet + facet normal -0.515249 -0.159541 0.84206 + outer loop + vertex 0.876907 1.2102 2.59541 + vertex 0.879019 1.21242 2.59712 + vertex 0.876209 1.21467 2.59583 + endloop + endfacet + facet normal -0.522487 -0.17265 0.834984 + outer loop + vertex 0.879019 1.21242 2.59712 + vertex 0.879068 1.21737 2.59818 + vertex 0.876209 1.21467 2.59583 + endloop + endfacet + facet normal -0.510506 -0.188727 0.838907 + outer loop + vertex 0.876209 1.21467 2.59583 + vertex 0.879068 1.21737 2.59818 + vertex 0.875286 1.21856 2.59614 + endloop + endfacet + facet normal -0.512211 -0.189042 0.837796 + outer loop + vertex 0.875286 1.21856 2.59614 + vertex 0.872584 1.21692 2.59412 + vertex 0.876209 1.21467 2.59583 + endloop + endfacet + facet normal -0.510968 -0.191383 0.838024 + outer loop + vertex 0.872584 1.21692 2.59412 + vertex 0.875286 1.21856 2.59614 + vertex 0.872936 1.22101 2.59527 + endloop + endfacet + facet normal -0.509331 -0.189287 0.839495 + outer loop + vertex 0.875286 1.21856 2.59614 + vertex 0.875604 1.22269 2.59726 + vertex 0.872936 1.22101 2.59527 + endloop + endfacet + facet normal -0.510547 -0.18901 0.838819 + outer loop + vertex 0.875286 1.21856 2.59614 + vertex 0.879068 1.21737 2.59818 + vertex 0.875604 1.22269 2.59726 + endloop + endfacet + facet normal -0.507623 -0.186713 0.841104 + outer loop + vertex 0.879068 1.21737 2.59818 + vertex 0.878991 1.22235 2.59923 + vertex 0.875604 1.22269 2.59726 + endloop + endfacet + facet normal -0.528184 -0.171864 0.831555 + outer loop + vertex 0.882321 1.212 2.59913 + vertex 0.879068 1.21737 2.59818 + vertex 0.879019 1.21242 2.59712 + endloop + endfacet + facet normal -0.52735 -0.117947 0.841422 + outer loop + vertex 0.880206 1.2078 2.59722 + vertex 0.882321 1.212 2.59913 + vertex 0.879019 1.21242 2.59712 + endloop + endfacet + facet normal -0.54426 -0.122538 0.829919 + outer loop + vertex 0.880206 1.2078 2.59722 + vertex 0.879019 1.21242 2.59712 + vertex 0.876907 1.2102 2.59541 + endloop + endfacet + facet normal -0.507569 -0.177567 0.843116 + outer loop + vertex 0.872584 1.21692 2.59412 + vertex 0.874129 1.21241 2.5941 + vertex 0.876209 1.21467 2.59583 + endloop + endfacet + facet normal -0.530453 -0.176124 0.829216 + outer loop + vertex 0.867892 1.22758 2.59349 + vertex 0.869477 1.22171 2.59326 + vertex 0.871778 1.22503 2.59543 + endloop + endfacet + facet normal -0.530951 -0.17732 0.828642 + outer loop + vertex 0.870911 1.22973 2.59588 + vertex 0.867892 1.22758 2.59349 + vertex 0.871778 1.22503 2.59543 + endloop + endfacet + facet normal -0.534529 -0.171182 0.827632 + outer loop + vertex 0.867798 1.23253 2.59445 + vertex 0.867892 1.22758 2.59349 + vertex 0.870911 1.22973 2.59588 + endloop + endfacet + facet normal -0.536696 -0.17469 0.825494 + outer loop + vertex 0.870236 1.23361 2.59626 + vertex 0.867798 1.23253 2.59445 + vertex 0.870911 1.22973 2.59588 + endloop + endfacet + facet normal -0.538719 -0.169672 0.825223 + outer loop + vertex 0.867798 1.23253 2.59445 + vertex 0.870236 1.23361 2.59626 + vertex 0.868059 1.23603 2.59534 + endloop + endfacet + facet normal -0.535467 -0.165636 0.828155 + outer loop + vertex 0.870236 1.23361 2.59626 + vertex 0.870605 1.23753 2.59729 + vertex 0.868059 1.23603 2.59534 + endloop + endfacet + facet normal -0.518575 -0.169792 0.838004 + outer loop + vertex 0.870236 1.23361 2.59626 + vertex 0.873891 1.23232 2.59826 + vertex 0.870605 1.23753 2.59729 + endloop + endfacet + facet normal -0.52036 -0.171176 0.836615 + outer loop + vertex 0.873891 1.23232 2.59826 + vertex 0.873879 1.23721 2.59926 + vertex 0.870605 1.23753 2.59729 + endloop + endfacet + facet normal -0.505892 -0.172864 0.845099 + outer loop + vertex 0.873879 1.23721 2.59926 + vertex 0.873891 1.23232 2.59826 + vertex 0.876773 1.23501 2.60054 + endloop + endfacet + facet normal -0.502173 -0.165859 0.848712 + outer loop + vertex 0.875965 1.23949 2.60094 + vertex 0.873879 1.23721 2.59926 + vertex 0.876773 1.23501 2.60054 + endloop + endfacet + facet normal -0.493357 -0.164743 0.854084 + outer loop + vertex 0.876773 1.23501 2.60054 + vertex 0.878881 1.2373 2.6022 + vertex 0.875965 1.23949 2.60094 + endloop + endfacet + facet normal -0.488897 -0.156419 0.858203 + outer loop + vertex 0.878881 1.2373 2.6022 + vertex 0.879007 1.24231 2.60318 + vertex 0.875965 1.23949 2.60094 + endloop + endfacet + facet normal -0.493755 -0.164275 0.853944 + outer loop + vertex 0.880506 1.23266 2.60225 + vertex 0.878881 1.2373 2.6022 + vertex 0.876773 1.23501 2.60054 + endloop + endfacet + facet normal -0.495722 -0.168882 0.851903 + outer loop + vertex 0.877697 1.2311 2.6003 + vertex 0.880506 1.23266 2.60225 + vertex 0.876773 1.23501 2.60054 + endloop + endfacet + facet normal -0.486183 -0.161575 0.858789 + outer loop + vertex 0.880506 1.23266 2.60225 + vertex 0.882288 1.23706 2.60408 + vertex 0.878881 1.2373 2.6022 + endloop + endfacet + facet normal -0.490294 -0.159123 0.856908 + outer loop + vertex 0.883938 1.23241 2.60416 + vertex 0.882288 1.23706 2.60408 + vertex 0.880506 1.23266 2.60225 + endloop + endfacet + facet normal -0.505923 -0.16142 0.84734 + outer loop + vertex 0.872364 1.24173 2.59921 + vertex 0.873879 1.23721 2.59926 + vertex 0.875965 1.23949 2.60094 + endloop + endfacet + facet normal -0.519112 -0.172769 0.837063 + outer loop + vertex 0.870911 1.22973 2.59588 + vertex 0.873891 1.23232 2.59826 + vertex 0.870236 1.23361 2.59626 + endloop + endfacet + facet normal -0.520209 -0.176015 0.835704 + outer loop + vertex 0.871778 1.22503 2.59543 + vertex 0.87389 1.22736 2.59724 + vertex 0.870911 1.22973 2.59588 + endloop + endfacet + facet normal -0.507712 -0.18234 0.84201 + outer loop + vertex 0.878991 1.22235 2.59923 + vertex 0.877303 1.22699 2.59922 + vertex 0.875604 1.22269 2.59726 + endloop + endfacet + facet normal -0.518735 -0.173315 0.837183 + outer loop + vertex 0.87389 1.22736 2.59724 + vertex 0.873891 1.23232 2.59826 + vertex 0.870911 1.22973 2.59588 + endloop + endfacet + facet normal -0.507168 -0.171148 0.844683 + outer loop + vertex 0.877697 1.2311 2.6003 + vertex 0.876773 1.23501 2.60054 + vertex 0.873891 1.23232 2.59826 + endloop + endfacet + facet normal -0.496585 -0.167134 0.851745 + outer loop + vertex 0.880092 1.22852 2.60119 + vertex 0.880506 1.23266 2.60225 + vertex 0.877697 1.2311 2.6003 + endloop + endfacet + facet normal -0.492369 -0.168128 0.853994 + outer loop + vertex 0.880092 1.22852 2.60119 + vertex 0.883977 1.22733 2.6032 + vertex 0.880506 1.23266 2.60225 + endloop + endfacet + facet normal -0.503086 -0.177196 0.845876 + outer loop + vertex 0.885673 1.21768 2.60221 + vertex 0.884017 1.22231 2.6022 + vertex 0.881959 1.22006 2.6005 + endloop + endfacet + facet normal -0.490132 -0.172536 0.854401 + outer loop + vertex 0.885673 1.21768 2.60221 + vertex 0.887409 1.22203 2.60408 + vertex 0.884017 1.22231 2.6022 + endloop + endfacet + facet normal -0.503721 -0.180884 0.844717 + outer loop + vertex 0.877303 1.22699 2.59922 + vertex 0.878991 1.22235 2.59923 + vertex 0.881046 1.22459 2.60094 + endloop + endfacet + facet normal -0.528429 -0.110622 0.841739 + outer loop + vertex 0.885195 1.21354 2.60114 + vertex 0.882321 1.212 2.59913 + vertex 0.885823 1.20951 2.601 + endloop + endfacet + facet normal -0.522436 -0.0982186 0.847003 + outer loop + vertex 0.882321 1.212 2.59913 + vertex 0.883443 1.20726 2.59927 + vertex 0.885823 1.20951 2.601 + endloop + endfacet + facet normal -0.504211 -0.179833 0.844649 + outer loop + vertex 0.882894 1.21612 2.60022 + vertex 0.885673 1.21768 2.60221 + vertex 0.881959 1.22006 2.6005 + endloop + endfacet + facet normal -0.494843 -0.169728 0.852246 + outer loop + vertex 0.889064 1.21745 2.60413 + vertex 0.887409 1.22203 2.60408 + vertex 0.885673 1.21768 2.60221 + endloop + endfacet + facet normal -0.478862 -0.163857 0.862463 + outer loop + vertex 0.887409 1.22203 2.60408 + vertex 0.889064 1.21745 2.60413 + vertex 0.891074 1.21991 2.60572 + endloop + endfacet + facet normal -0.492196 -0.12297 0.861755 + outer loop + vertex 0.895549 1.21283 2.6071 + vertex 0.894557 1.21824 2.60731 + vertex 0.892014 1.21535 2.60545 + endloop + endfacet + facet normal -0.45414 -0.155198 0.877309 + outer loop + vertex 0.898291 1.21662 2.60896 + vertex 0.897059 1.22198 2.60927 + vertex 0.894557 1.21824 2.60731 + endloop + endfacet + facet normal -0.442039 -0.114846 0.889613 + outer loop + vertex 0.895549 1.21283 2.6071 + vertex 0.898291 1.21662 2.60896 + vertex 0.894557 1.21824 2.60731 + endloop + endfacet + facet normal -0.469085 -0.170612 0.866516 + outer loop + vertex 0.891074 1.21991 2.60572 + vertex 0.893078 1.22299 2.60741 + vertex 0.890056 1.22371 2.60591 + endloop + endfacet + facet normal -0.482805 -0.173863 0.858296 + outer loop + vertex 0.890056 1.22371 2.60591 + vertex 0.887409 1.22203 2.60408 + vertex 0.891074 1.21991 2.60572 + endloop + endfacet + facet normal -0.490079 -0.174807 0.85397 + outer loop + vertex 0.887409 1.22203 2.60408 + vertex 0.883977 1.22733 2.6032 + vertex 0.884017 1.22231 2.6022 + endloop + endfacet + facet normal -0.477523 -0.165639 0.862865 + outer loop + vertex 0.887851 1.22616 2.60517 + vertex 0.89079 1.22772 2.6071 + vertex 0.886995 1.23023 2.60548 + endloop + endfacet + facet normal -0.490118 -0.166369 0.855632 + outer loop + vertex 0.883977 1.22733 2.6032 + vertex 0.883938 1.23241 2.60416 + vertex 0.880506 1.23266 2.60225 + endloop + endfacet + facet normal -0.475744 -0.161871 0.864561 + outer loop + vertex 0.89079 1.22772 2.6071 + vertex 0.889481 1.23315 2.6074 + vertex 0.886995 1.23023 2.60548 + endloop + endfacet + facet normal -0.471277 -0.151076 0.86895 + outer loop + vertex 0.889481 1.23315 2.6074 + vertex 0.891951 1.23687 2.60938 + vertex 0.887993 1.23797 2.60743 + endloop + endfacet + facet normal -0.485707 -0.157446 0.859825 + outer loop + vertex 0.882288 1.23706 2.60408 + vertex 0.883938 1.23241 2.60416 + vertex 0.885943 1.2349 2.60575 + endloop + endfacet + facet normal -0.486298 -0.156762 0.859616 + outer loop + vertex 0.882288 1.23706 2.60408 + vertex 0.879007 1.24231 2.60318 + vertex 0.878881 1.2373 2.6022 + endloop + endfacet + facet normal -0.480011 -0.148198 0.864654 + outer loop + vertex 0.884975 1.23875 2.60589 + vertex 0.885824 1.24272 2.60704 + vertex 0.882843 1.2412 2.60513 + endloop + endfacet + facet normal -0.475972 -0.148096 0.866902 + outer loop + vertex 0.885824 1.24272 2.60704 + vertex 0.888308 1.24642 2.60904 + vertex 0.884676 1.248 2.60731 + endloop + endfacet + facet normal -0.476641 -0.150487 0.866122 + outer loop + vertex 0.888308 1.24642 2.60904 + vertex 0.886896 1.25182 2.6092 + vertex 0.884676 1.248 2.60731 + endloop + endfacet + facet normal -0.475476 -0.151402 0.866603 + outer loop + vertex 0.884676 1.248 2.60731 + vertex 0.886896 1.25182 2.6092 + vertex 0.883456 1.25216 2.60737 + endloop + endfacet + facet normal -0.475469 -0.15013 0.866828 + outer loop + vertex 0.886896 1.25182 2.6092 + vertex 0.883765 1.25711 2.6084 + vertex 0.883456 1.25216 2.60737 + endloop + endfacet + facet normal -0.47292 -0.148363 0.868525 + outer loop + vertex 0.887624 1.25599 2.61031 + vertex 0.883765 1.25711 2.6084 + vertex 0.886896 1.25182 2.6092 + endloop + endfacet + facet normal -0.469195 -0.149497 0.870348 + outer loop + vertex 0.886896 1.25182 2.6092 + vertex 0.889744 1.25356 2.61103 + vertex 0.887624 1.25599 2.61031 + endloop + endfacet + facet normal -0.458665 -0.138096 0.877813 + outer loop + vertex 0.889744 1.25356 2.61103 + vertex 0.890732 1.25759 2.61218 + vertex 0.887624 1.25599 2.61031 + endloop + endfacet + facet normal -0.459398 -0.136514 0.877677 + outer loop + vertex 0.887624 1.25599 2.61031 + vertex 0.890732 1.25759 2.61218 + vertex 0.887042 1.26004 2.61063 + endloop + endfacet + facet normal -0.45009 -0.141314 0.881731 + outer loop + vertex 0.889744 1.25356 2.61103 + vertex 0.892839 1.25289 2.6125 + vertex 0.890732 1.25759 2.61218 + endloop + endfacet + facet normal -0.46857 -0.150666 0.870484 + outer loop + vertex 0.889744 1.25356 2.61103 + vertex 0.886896 1.25182 2.6092 + vertex 0.890679 1.24959 2.61085 + endloop + endfacet + facet normal -0.471162 -0.137681 0.871235 + outer loop + vertex 0.887624 1.25599 2.61031 + vertex 0.887042 1.26004 2.61063 + vertex 0.883765 1.25711 2.6084 + endloop + endfacet + facet normal -0.470413 -0.138703 0.871478 + outer loop + vertex 0.884107 1.26214 2.60938 + vertex 0.883765 1.25711 2.6084 + vertex 0.887042 1.26004 2.61063 + endloop + endfacet + facet normal -0.462821 -0.124343 0.877688 + outer loop + vertex 0.886321 1.26481 2.61093 + vertex 0.884107 1.26214 2.60938 + vertex 0.887042 1.26004 2.61063 + endloop + endfacet + facet normal -0.458756 -0.123864 0.879887 + outer loop + vertex 0.887042 1.26004 2.61063 + vertex 0.88981 1.26296 2.61249 + vertex 0.886321 1.26481 2.61093 + endloop + endfacet + facet normal -0.454897 -0.113707 0.883255 + outer loop + vertex 0.88981 1.26296 2.61249 + vertex 0.888863 1.26799 2.61265 + vertex 0.886321 1.26481 2.61093 + endloop + endfacet + facet normal -0.458615 -0.109955 0.881806 + outer loop + vertex 0.886321 1.26481 2.61093 + vertex 0.888863 1.26799 2.61265 + vertex 0.885326 1.26957 2.611 + endloop + endfacet + facet normal -0.462562 -0.110746 0.879643 + outer loop + vertex 0.885326 1.26957 2.611 + vertex 0.882874 1.26648 2.60932 + vertex 0.886321 1.26481 2.61093 + endloop + endfacet + facet normal -0.463009 -0.110294 0.879464 + outer loop + vertex 0.881756 1.27192 2.60942 + vertex 0.882874 1.26648 2.60932 + vertex 0.885326 1.26957 2.611 + endloop + endfacet + facet normal -0.460742 -0.105669 0.881221 + outer loop + vertex 0.884617 1.27357 2.61111 + vertex 0.881756 1.27192 2.60942 + vertex 0.885326 1.26957 2.611 + endloop + endfacet + facet normal -0.45783 -0.105195 0.882794 + outer loop + vertex 0.885326 1.26957 2.611 + vertex 0.88763 1.2728 2.61258 + vertex 0.884617 1.27357 2.61111 + endloop + endfacet + facet normal -0.458289 -0.108155 0.882198 + outer loop + vertex 0.884617 1.27357 2.61111 + vertex 0.88763 1.2728 2.61258 + vertex 0.885724 1.27757 2.61218 + endloop + endfacet + facet normal -0.459106 -0.107827 0.881814 + outer loop + vertex 0.884617 1.27357 2.61111 + vertex 0.885724 1.27757 2.61218 + vertex 0.882774 1.27595 2.61044 + endloop + endfacet + facet normal -0.456296 -0.113705 0.882533 + outer loop + vertex 0.882774 1.27595 2.61044 + vertex 0.885724 1.27757 2.61218 + vertex 0.882149 1.27989 2.61063 + endloop + endfacet + facet normal -0.460598 -0.11428 0.880221 + outer loop + vertex 0.882774 1.27595 2.61044 + vertex 0.882149 1.27989 2.61063 + vertex 0.87981 1.27668 2.60899 + endloop + endfacet + facet normal -0.459698 -0.108117 0.881469 + outer loop + vertex 0.882774 1.27595 2.61044 + vertex 0.87981 1.27668 2.60899 + vertex 0.881756 1.27192 2.60942 + endloop + endfacet + facet normal -0.464581 -0.11037 0.878626 + outer loop + vertex 0.881756 1.27192 2.60942 + vertex 0.87981 1.27668 2.60899 + vertex 0.877848 1.27299 2.60749 + endloop + endfacet + facet normal -0.464641 -0.110724 0.87855 + outer loop + vertex 0.879239 1.26807 2.6076 + vertex 0.881756 1.27192 2.60942 + vertex 0.877848 1.27299 2.60749 + endloop + endfacet + facet normal -0.47341 -0.11332 0.873522 + outer loop + vertex 0.879239 1.26807 2.6076 + vertex 0.877848 1.27299 2.60749 + vertex 0.875652 1.26962 2.60586 + endloop + endfacet + facet normal -0.476859 -0.110349 0.872026 + outer loop + vertex 0.875652 1.26962 2.60586 + vertex 0.877848 1.27299 2.60749 + vertex 0.87487 1.27366 2.60594 + endloop + endfacet + facet normal -0.496619 -0.113938 0.860458 + outer loop + vertex 0.87487 1.27366 2.60594 + vertex 0.872067 1.27175 2.60407 + vertex 0.875652 1.26962 2.60586 + endloop + endfacet + facet normal -0.498831 -0.109939 0.859698 + outer loop + vertex 0.872067 1.27175 2.60407 + vertex 0.87487 1.27366 2.60594 + vertex 0.872914 1.27601 2.60511 + endloop + endfacet + facet normal -0.476639 -0.108578 0.872368 + outer loop + vertex 0.87487 1.27366 2.60594 + vertex 0.877848 1.27299 2.60749 + vertex 0.875896 1.27774 2.60701 + endloop + endfacet + facet normal -0.470893 -0.105869 0.875815 + outer loop + vertex 0.877848 1.27299 2.60749 + vertex 0.87981 1.27668 2.60899 + vertex 0.875896 1.27774 2.60701 + endloop + endfacet + facet normal -0.472566 -0.116196 0.873602 + outer loop + vertex 0.87981 1.27668 2.60899 + vertex 0.878635 1.2814 2.60898 + vertex 0.875896 1.27774 2.60701 + endloop + endfacet + facet normal -0.47704 -0.111846 0.871736 + outer loop + vertex 0.875896 1.27774 2.60701 + vertex 0.878635 1.2814 2.60898 + vertex 0.875071 1.28309 2.60725 + endloop + endfacet + facet normal -0.479954 -0.120883 0.868926 + outer loop + vertex 0.878635 1.2814 2.60898 + vertex 0.87772 1.28632 2.60916 + vertex 0.875071 1.28309 2.60725 + endloop + endfacet + facet normal -0.465265 -0.118455 0.87721 + outer loop + vertex 0.87772 1.28632 2.60916 + vertex 0.878635 1.2814 2.60898 + vertex 0.881263 1.28466 2.61081 + endloop + endfacet + facet normal -0.466619 -0.122621 0.875917 + outer loop + vertex 0.880329 1.28943 2.61098 + vertex 0.87772 1.28632 2.60916 + vertex 0.881263 1.28466 2.61081 + endloop + endfacet + facet normal -0.453734 -0.120349 0.882973 + outer loop + vertex 0.881263 1.28466 2.61081 + vertex 0.883904 1.28799 2.61262 + vertex 0.880329 1.28943 2.61098 + endloop + endfacet + facet normal -0.453613 -0.119912 0.883095 + outer loop + vertex 0.883904 1.28799 2.61262 + vertex 0.882674 1.29273 2.61264 + vertex 0.880329 1.28943 2.61098 + endloop + endfacet + facet normal -0.454223 -0.11986 0.882788 + outer loop + vertex 0.884846 1.28297 2.61243 + vertex 0.883904 1.28799 2.61262 + vertex 0.881263 1.28466 2.61081 + endloop + endfacet + facet normal -0.453822 -0.118656 0.883157 + outer loop + vertex 0.882149 1.27989 2.61063 + vertex 0.884846 1.28297 2.61243 + vertex 0.881263 1.28466 2.61081 + endloop + endfacet + facet normal -0.443704 -0.118101 0.888358 + outer loop + vertex 0.884846 1.28297 2.61243 + vertex 0.887578 1.28639 2.61425 + vertex 0.883904 1.28799 2.61262 + endloop + endfacet + facet normal -0.443146 -0.116289 0.888875 + outer loop + vertex 0.887578 1.28639 2.61425 + vertex 0.886666 1.29179 2.6145 + vertex 0.883904 1.28799 2.61262 + endloop + endfacet + facet normal -0.442356 -0.117011 0.889174 + outer loop + vertex 0.883904 1.28799 2.61262 + vertex 0.886666 1.29179 2.6145 + vertex 0.882674 1.29273 2.61264 + endloop + endfacet + facet normal -0.442191 -0.115851 0.889408 + outer loop + vertex 0.886666 1.29179 2.6145 + vertex 0.884741 1.29645 2.61415 + vertex 0.882674 1.29273 2.61264 + endloop + endfacet + facet normal -0.435737 -0.112922 0.892963 + outer loop + vertex 0.887785 1.29583 2.61556 + vertex 0.884741 1.29645 2.61415 + vertex 0.886666 1.29179 2.6145 + endloop + endfacet + facet normal -0.431222 -0.114687 0.894927 + outer loop + vertex 0.886666 1.29179 2.6145 + vertex 0.889647 1.29354 2.61616 + vertex 0.887785 1.29583 2.61556 + endloop + endfacet + facet normal -0.424678 -0.108314 0.898842 + outer loop + vertex 0.889647 1.29354 2.61616 + vertex 0.890787 1.29758 2.61719 + vertex 0.887785 1.29583 2.61556 + endloop + endfacet + facet normal -0.420301 -0.110021 0.90069 + outer loop + vertex 0.889647 1.29354 2.61616 + vertex 0.892703 1.2929 2.61751 + vertex 0.890787 1.29758 2.61719 + endloop + endfacet + facet normal -0.417337 -0.108701 0.902227 + outer loop + vertex 0.892703 1.2929 2.61751 + vertex 0.894803 1.29663 2.61893 + vertex 0.890787 1.29758 2.61719 + endloop + endfacet + facet normal -0.420569 -0.112094 0.900309 + outer loop + vertex 0.890297 1.28958 2.61597 + vertex 0.892703 1.2929 2.61751 + vertex 0.889647 1.29354 2.61616 + endloop + endfacet + facet normal -0.4216 -0.111176 0.899941 + outer loop + vertex 0.893935 1.28812 2.61749 + vertex 0.892703 1.2929 2.61751 + vertex 0.890297 1.28958 2.61597 + endloop + endfacet + facet normal -0.421593 -0.111152 0.899947 + outer loop + vertex 0.891227 1.28472 2.61581 + vertex 0.893935 1.28812 2.61749 + vertex 0.890297 1.28958 2.61597 + endloop + endfacet + facet normal -0.433629 -0.113253 0.893946 + outer loop + vertex 0.890297 1.28958 2.61597 + vertex 0.887578 1.28639 2.61425 + vertex 0.891227 1.28472 2.61581 + endloop + endfacet + facet normal -0.433385 -0.112525 0.894156 + outer loop + vertex 0.887578 1.28639 2.61425 + vertex 0.888524 1.28132 2.61407 + vertex 0.891227 1.28472 2.61581 + endloop + endfacet + facet normal -0.436455 -0.109508 0.893037 + outer loop + vertex 0.891227 1.28472 2.61581 + vertex 0.888524 1.28132 2.61407 + vertex 0.892149 1.27985 2.61566 + endloop + endfacet + facet normal -0.421402 -0.106888 0.900553 + outer loop + vertex 0.892149 1.27985 2.61566 + vertex 0.894912 1.28307 2.61734 + vertex 0.891227 1.28472 2.61581 + endloop + endfacet + facet normal -0.421778 -0.106499 0.900423 + outer loop + vertex 0.895819 1.27769 2.61712 + vertex 0.894912 1.28307 2.61734 + vertex 0.892149 1.27985 2.61566 + endloop + endfacet + facet normal -0.419224 -0.100923 0.902256 + outer loop + vertex 0.892781 1.27585 2.61551 + vertex 0.895819 1.27769 2.61712 + vertex 0.892149 1.27985 2.61566 + endloop + endfacet + facet normal -0.43743 -0.103458 0.893281 + outer loop + vertex 0.892781 1.27585 2.61551 + vertex 0.892149 1.27985 2.61566 + vertex 0.889719 1.2765 2.61408 + endloop + endfacet + facet normal -0.437267 -0.102204 0.893505 + outer loop + vertex 0.892781 1.27585 2.61551 + vertex 0.889719 1.2765 2.61408 + vertex 0.891627 1.27177 2.61447 + endloop + endfacet + facet normal -0.427475 -0.106053 0.897785 + outer loop + vertex 0.891627 1.27177 2.61447 + vertex 0.894647 1.27357 2.61612 + vertex 0.892781 1.27585 2.61551 + endloop + endfacet + facet normal -0.428124 -0.104812 0.897621 + outer loop + vertex 0.894647 1.27357 2.61612 + vertex 0.891627 1.27177 2.61447 + vertex 0.895263 1.26958 2.61595 + endloop + endfacet + facet normal -0.447512 -0.106799 0.887878 + outer loop + vertex 0.891627 1.27177 2.61447 + vertex 0.889719 1.2765 2.61408 + vertex 0.88763 1.2728 2.61258 + endloop + endfacet + facet normal -0.446884 -0.10296 0.888647 + outer loop + vertex 0.888863 1.26799 2.61265 + vertex 0.891627 1.27177 2.61447 + vertex 0.88763 1.2728 2.61258 + endloop + endfacet + facet normal -0.442943 -0.106587 0.890191 + outer loop + vertex 0.892523 1.26635 2.61427 + vertex 0.891627 1.27177 2.61447 + vertex 0.888863 1.26799 2.61265 + endloop + endfacet + facet normal -0.42024 -0.099009 0.901995 + outer loop + vertex 0.894647 1.27357 2.61612 + vertex 0.895819 1.27769 2.61712 + vertex 0.892781 1.27585 2.61551 + endloop + endfacet + facet normal -0.414516 -0.101219 0.904395 + outer loop + vertex 0.894647 1.27357 2.61612 + vertex 0.89772 1.27301 2.61747 + vertex 0.895819 1.27769 2.61712 + endloop + endfacet + facet normal -0.420447 -0.1063 0.901069 + outer loop + vertex 0.895819 1.27769 2.61712 + vertex 0.898645 1.28148 2.61889 + vertex 0.894912 1.28307 2.61734 + endloop + endfacet + facet normal -0.419069 -0.107554 0.901561 + outer loop + vertex 0.899851 1.27682 2.61889 + vertex 0.898645 1.28148 2.61889 + vertex 0.895819 1.27769 2.61712 + endloop + endfacet + facet normal -0.435263 -0.105423 0.89411 + outer loop + vertex 0.888524 1.28132 2.61407 + vertex 0.889719 1.2765 2.61408 + vertex 0.892149 1.27985 2.61566 + endloop + endfacet + facet normal -0.451255 -0.109413 0.885662 + outer loop + vertex 0.889719 1.2765 2.61408 + vertex 0.888524 1.28132 2.61407 + vertex 0.885724 1.27757 2.61218 + endloop + endfacet + facet normal -0.446656 -0.113746 0.887446 + outer loop + vertex 0.885724 1.27757 2.61218 + vertex 0.888524 1.28132 2.61407 + vertex 0.884846 1.28297 2.61243 + endloop + endfacet + facet normal -0.422519 -0.110254 0.899623 + outer loop + vertex 0.894912 1.28307 2.61734 + vertex 0.893935 1.28812 2.61749 + vertex 0.891227 1.28472 2.61581 + endloop + endfacet + facet normal -0.425116 -0.110716 0.898342 + outer loop + vertex 0.894912 1.28307 2.61734 + vertex 0.897702 1.28643 2.61907 + vertex 0.893935 1.28812 2.61749 + endloop + endfacet + facet normal -0.424529 -0.108945 0.898836 + outer loop + vertex 0.897702 1.28643 2.61907 + vertex 0.896759 1.29187 2.61928 + vertex 0.893935 1.28812 2.61749 + endloop + endfacet + facet normal -0.422002 -0.111279 0.899739 + outer loop + vertex 0.893935 1.28812 2.61749 + vertex 0.896759 1.29187 2.61928 + vertex 0.892703 1.2929 2.61751 + endloop + endfacet + facet normal -0.431755 -0.113665 0.894801 + outer loop + vertex 0.889647 1.29354 2.61616 + vertex 0.886666 1.29179 2.6145 + vertex 0.890297 1.28958 2.61597 + endloop + endfacet + facet normal -0.432237 -0.114703 0.894435 + outer loop + vertex 0.886666 1.29179 2.6145 + vertex 0.887578 1.28639 2.61425 + vertex 0.890297 1.28958 2.61597 + endloop + endfacet + facet normal -0.446998 -0.114817 0.887136 + outer loop + vertex 0.888524 1.28132 2.61407 + vertex 0.887578 1.28639 2.61425 + vertex 0.884846 1.28297 2.61243 + endloop + endfacet + facet normal -0.471806 -0.117074 0.873895 + outer loop + vertex 0.876679 1.29166 2.60931 + vertex 0.87772 1.28632 2.60916 + vertex 0.880329 1.28943 2.61098 + endloop + endfacet + facet normal -0.463514 -0.12025 0.877892 + outer loop + vertex 0.881263 1.28466 2.61081 + vertex 0.878635 1.2814 2.60898 + vertex 0.882149 1.27989 2.61063 + endloop + endfacet + facet normal -0.461507 -0.113431 0.879855 + outer loop + vertex 0.878635 1.2814 2.60898 + vertex 0.87981 1.27668 2.60899 + vertex 0.882149 1.27989 2.61063 + endloop + endfacet + facet normal -0.457007 -0.115177 0.881974 + outer loop + vertex 0.885724 1.27757 2.61218 + vertex 0.884846 1.28297 2.61243 + vertex 0.882149 1.27989 2.61063 + endloop + endfacet + facet normal -0.450447 -0.104646 0.886649 + outer loop + vertex 0.88763 1.2728 2.61258 + vertex 0.889719 1.2765 2.61408 + vertex 0.885724 1.27757 2.61218 + endloop + endfacet + facet normal -0.459492 -0.108194 0.881567 + outer loop + vertex 0.881756 1.27192 2.60942 + vertex 0.884617 1.27357 2.61111 + vertex 0.882774 1.27595 2.61044 + endloop + endfacet + facet normal -0.464746 -0.110634 0.878505 + outer loop + vertex 0.882874 1.26648 2.60932 + vertex 0.881756 1.27192 2.60942 + vertex 0.879239 1.26807 2.6076 + endloop + endfacet + facet normal -0.45728 -0.105696 0.883019 + outer loop + vertex 0.888863 1.26799 2.61265 + vertex 0.88763 1.2728 2.61258 + vertex 0.885326 1.26957 2.611 + endloop + endfacet + facet normal -0.44467 -0.111953 0.88867 + outer loop + vertex 0.88981 1.26296 2.61249 + vertex 0.892523 1.26635 2.61427 + vertex 0.888863 1.26799 2.61265 + endloop + endfacet + facet normal -0.455204 -0.128024 0.881135 + outer loop + vertex 0.890732 1.25759 2.61218 + vertex 0.88981 1.26296 2.61249 + vertex 0.887042 1.26004 2.61063 + endloop + endfacet + facet normal -0.443614 -0.126382 0.887262 + outer loop + vertex 0.890732 1.25759 2.61218 + vertex 0.893479 1.26133 2.61409 + vertex 0.88981 1.26296 2.61249 + endloop + endfacet + facet normal -0.439686 -0.13 0.888693 + outer loop + vertex 0.894759 1.25661 2.61403 + vertex 0.893479 1.26133 2.61409 + vertex 0.890732 1.25759 2.61218 + endloop + endfacet + facet normal -0.466031 -0.120968 0.87646 + outer loop + vertex 0.882874 1.26648 2.60932 + vertex 0.884107 1.26214 2.60938 + vertex 0.886321 1.26481 2.61093 + endloop + endfacet + facet normal -0.49743 -0.115919 0.859724 + outer loop + vertex 0.872067 1.27175 2.60407 + vertex 0.873125 1.26625 2.60394 + vertex 0.875652 1.26962 2.60586 + endloop + endfacet + facet normal -0.473297 -0.130167 0.871233 + outer loop + vertex 0.877723 1.26072 2.60572 + vertex 0.880613 1.26249 2.60756 + vertex 0.876804 1.26478 2.60583 + endloop + endfacet + facet normal -0.476617 -0.153361 0.865631 + outer loop + vertex 0.876826 1.25667 2.60453 + vertex 0.877998 1.25142 2.60425 + vertex 0.880548 1.25421 2.60615 + endloop + endfacet + facet normal -0.475079 -0.15343 0.866464 + outer loop + vertex 0.877998 1.25142 2.60425 + vertex 0.879242 1.24725 2.60419 + vertex 0.881353 1.24971 2.60578 + endloop + endfacet + facet normal -0.477714 -0.153567 0.864989 + outer loop + vertex 0.879242 1.24725 2.60419 + vertex 0.879007 1.24231 2.60318 + vertex 0.882156 1.2452 2.60544 + endloop + endfacet + facet normal -0.486683 -0.159375 0.858917 + outer loop + vertex 0.875965 1.23949 2.60094 + vertex 0.879007 1.24231 2.60318 + vertex 0.87514 1.2434 2.6012 + endloop + endfacet + facet normal -0.50647 -0.162748 0.846759 + outer loop + vertex 0.87514 1.2434 2.6012 + vertex 0.872364 1.24173 2.59921 + vertex 0.875965 1.23949 2.60094 + endloop + endfacet + facet normal -0.528039 -0.155731 0.834819 + outer loop + vertex 0.872844 1.24588 2.60029 + vertex 0.871814 1.2501 2.60043 + vertex 0.869383 1.24661 2.59824 + endloop + endfacet + facet normal -0.500994 -0.149697 0.852406 + outer loop + vertex 0.872844 1.24588 2.60029 + vertex 0.875739 1.24762 2.6023 + vertex 0.871814 1.2501 2.60043 + endloop + endfacet + facet normal -0.504573 -0.158123 0.848766 + outer loop + vertex 0.875739 1.24762 2.6023 + vertex 0.874326 1.25305 2.60247 + vertex 0.871814 1.2501 2.60043 + endloop + endfacet + facet normal -0.506835 -0.155591 0.847885 + outer loop + vertex 0.871814 1.2501 2.60043 + vertex 0.874326 1.25305 2.60247 + vertex 0.870899 1.25485 2.60075 + endloop + endfacet + facet normal -0.536223 -0.159936 0.828785 + outer loop + vertex 0.870899 1.25485 2.60075 + vertex 0.867929 1.25262 2.5984 + vertex 0.871814 1.2501 2.60043 + endloop + endfacet + facet normal -0.538345 -0.156376 0.828089 + outer loop + vertex 0.868259 1.25767 2.59957 + vertex 0.867929 1.25262 2.5984 + vertex 0.870899 1.25485 2.60075 + endloop + endfacet + facet normal -0.538611 -0.156726 0.82785 + outer loop + vertex 0.870485 1.25804 2.60109 + vertex 0.868259 1.25767 2.59957 + vertex 0.870899 1.25485 2.60075 + endloop + endfacet + facet normal -0.507541 -0.15476 0.847615 + outer loop + vertex 0.870899 1.25485 2.60075 + vertex 0.872836 1.25767 2.60243 + vertex 0.870485 1.25804 2.60109 + endloop + endfacet + facet normal -0.506426 -0.131215 0.852241 + outer loop + vertex 0.870485 1.25804 2.60109 + vertex 0.872836 1.25767 2.60243 + vertex 0.870122 1.26204 2.60149 + endloop + endfacet + facet normal -0.509334 -0.133471 0.850155 + outer loop + vertex 0.872836 1.25767 2.60243 + vertex 0.874554 1.26136 2.60404 + vertex 0.870122 1.26204 2.60149 + endloop + endfacet + facet normal -0.509307 -0.132872 0.850266 + outer loop + vertex 0.874554 1.26136 2.60404 + vertex 0.873125 1.26625 2.60394 + vertex 0.870122 1.26204 2.60149 + endloop + endfacet + facet normal -0.512736 -0.129527 0.84872 + outer loop + vertex 0.870122 1.26204 2.60149 + vertex 0.873125 1.26625 2.60394 + vertex 0.869588 1.26793 2.60206 + endloop + endfacet + facet normal -0.543492 -0.132249 0.828931 + outer loop + vertex 0.868259 1.25767 2.59957 + vertex 0.870485 1.25804 2.60109 + vertex 0.870122 1.26204 2.60149 + endloop + endfacet + facet normal -0.540118 -0.134497 0.830773 + outer loop + vertex 0.870122 1.26204 2.60149 + vertex 0.865332 1.26188 2.59835 + vertex 0.868259 1.25767 2.59957 + endloop + endfacet + facet normal -0.506793 -0.155464 0.847934 + outer loop + vertex 0.874326 1.25305 2.60247 + vertex 0.872836 1.25767 2.60243 + vertex 0.870899 1.25485 2.60075 + endloop + endfacet + facet normal -0.520435 -0.166381 0.837535 + outer loop + vertex 0.873879 1.23721 2.59926 + vertex 0.872364 1.24173 2.59921 + vertex 0.870605 1.23753 2.59729 + endloop + endfacet + facet normal -0.565151 -0.154598 0.810373 + outer loop + vertex 0.863282 1.24278 2.59334 + vertex 0.864798 1.23671 2.59324 + vertex 0.866984 1.23994 2.59538 + endloop + endfacet + facet normal -0.571243 -0.156043 0.805811 + outer loop + vertex 0.864798 1.23671 2.59324 + vertex 0.863282 1.24278 2.59334 + vertex 0.860919 1.23965 2.59106 + endloop + endfacet + facet normal -0.570915 -0.155337 0.80618 + outer loop + vertex 0.861752 1.23457 2.59067 + vertex 0.864798 1.23671 2.59324 + vertex 0.860919 1.23965 2.59106 + endloop + endfacet + facet normal -0.581358 -0.156457 0.798464 + outer loop + vertex 0.860919 1.23965 2.59106 + vertex 0.857905 1.23756 2.58846 + vertex 0.861752 1.23457 2.59067 + endloop + endfacet + facet normal -0.582378 -0.154528 0.798096 + outer loop + vertex 0.857841 1.24258 2.58938 + vertex 0.857905 1.23756 2.58846 + vertex 0.860919 1.23965 2.59106 + endloop + endfacet + facet normal -0.581346 -0.15282 0.799177 + outer loop + vertex 0.860103 1.24375 2.59125 + vertex 0.857841 1.24258 2.58938 + vertex 0.860919 1.23965 2.59106 + endloop + endfacet + facet normal -0.58282 -0.149322 0.798764 + outer loop + vertex 0.857841 1.24258 2.58938 + vertex 0.860103 1.24375 2.59125 + vertex 0.858126 1.24609 2.59025 + endloop + endfacet + facet normal -0.58836 -0.147934 0.794951 + outer loop + vertex 0.858126 1.24609 2.59025 + vertex 0.85509 1.24663 2.5881 + vertex 0.857841 1.24258 2.58938 + endloop + endfacet + facet normal -0.588526 -0.148095 0.794799 + outer loop + vertex 0.857841 1.24258 2.58938 + vertex 0.85509 1.24663 2.5881 + vertex 0.8551 1.24174 2.5872 + endloop + endfacet + facet normal -0.596842 -0.147 0.788778 + outer loop + vertex 0.8551 1.24174 2.5872 + vertex 0.85509 1.24663 2.5881 + vertex 0.852203 1.24452 2.58552 + endloop + endfacet + facet normal -0.597167 -0.147548 0.788429 + outer loop + vertex 0.852934 1.24071 2.58536 + vertex 0.8551 1.24174 2.5872 + vertex 0.852203 1.24452 2.58552 + endloop + endfacet + facet normal -0.609344 -0.149479 0.778689 + outer loop + vertex 0.852934 1.24071 2.58536 + vertex 0.852203 1.24452 2.58552 + vertex 0.85002 1.24147 2.58323 + endloop + endfacet + facet normal -0.610001 -0.158467 0.776394 + outer loop + vertex 0.852934 1.24071 2.58536 + vertex 0.85002 1.24147 2.58323 + vertex 0.852685 1.2374 2.58449 + endloop + endfacet + facet normal -0.600729 -0.160927 0.783089 + outer loop + vertex 0.852685 1.2374 2.58449 + vertex 0.854829 1.2384 2.58634 + vertex 0.852934 1.24071 2.58536 + endloop + endfacet + facet normal -0.599323 -0.164553 0.783412 + outer loop + vertex 0.854829 1.2384 2.58634 + vertex 0.852685 1.2374 2.58449 + vertex 0.855644 1.2345 2.58615 + endloop + endfacet + facet normal -0.588862 -0.162773 0.791673 + outer loop + vertex 0.855644 1.2345 2.58615 + vertex 0.857905 1.23756 2.58846 + vertex 0.854829 1.2384 2.58634 + endloop + endfacet + facet normal -0.588203 -0.155309 0.79366 + outer loop + vertex 0.854829 1.2384 2.58634 + vertex 0.857905 1.23756 2.58846 + vertex 0.8551 1.24174 2.5872 + endloop + endfacet + facet normal -0.590565 -0.160852 0.790797 + outer loop + vertex 0.859381 1.23147 2.58832 + vertex 0.857905 1.23756 2.58846 + vertex 0.855644 1.2345 2.58615 + endloop + endfacet + facet normal -0.592688 -0.165248 0.788298 + outer loop + vertex 0.856348 1.22958 2.58564 + vertex 0.859381 1.23147 2.58832 + vertex 0.855644 1.2345 2.58615 + endloop + endfacet + facet normal -0.6017 -0.165824 0.781319 + outer loop + vertex 0.855644 1.2345 2.58615 + vertex 0.852729 1.2326 2.5835 + vertex 0.856348 1.22958 2.58564 + endloop + endfacet + facet normal -0.603064 -0.16864 0.779663 + outer loop + vertex 0.852729 1.2326 2.5835 + vertex 0.85393 1.22714 2.58324 + vertex 0.856348 1.22958 2.58564 + endloop + endfacet + facet normal -0.604324 -0.166823 0.779078 + outer loop + vertex 0.856348 1.22958 2.58564 + vertex 0.85393 1.22714 2.58324 + vertex 0.857198 1.22485 2.58529 + endloop + endfacet + facet normal -0.610571 -0.170003 0.773499 + outer loop + vertex 0.85393 1.22714 2.58324 + vertex 0.852729 1.2326 2.5835 + vertex 0.85059 1.22959 2.58115 + endloop + endfacet + facet normal -0.611021 -0.171131 0.772895 + outer loop + vertex 0.851499 1.22463 2.58077 + vertex 0.85393 1.22714 2.58324 + vertex 0.85059 1.22959 2.58115 + endloop + endfacet + facet normal -0.619088 -0.1721 0.766232 + outer loop + vertex 0.85059 1.22959 2.58115 + vertex 0.847776 1.22758 2.57842 + vertex 0.851499 1.22463 2.58077 + endloop + endfacet + facet normal -0.618798 -0.17143 0.766617 + outer loop + vertex 0.847776 1.22758 2.57842 + vertex 0.84913 1.2222 2.57831 + vertex 0.851499 1.22463 2.58077 + endloop + endfacet + facet normal -0.617579 -0.17321 0.767199 + outer loop + vertex 0.851499 1.22463 2.58077 + vertex 0.84913 1.2222 2.57831 + vertex 0.852395 1.21979 2.58039 + endloop + endfacet + facet normal -0.611187 -0.172434 0.772474 + outer loop + vertex 0.852395 1.21979 2.58039 + vertex 0.855177 1.2217 2.58302 + vertex 0.851499 1.22463 2.58077 + endloop + endfacet + facet normal -0.608036 -0.178528 0.773576 + outer loop + vertex 0.855256 1.21689 2.58197 + vertex 0.855177 1.2217 2.58302 + vertex 0.852395 1.21979 2.58039 + endloop + endfacet + facet normal -0.609611 -0.181079 0.771742 + outer loop + vertex 0.853021 1.21603 2.58001 + vertex 0.855256 1.21689 2.58197 + vertex 0.852395 1.21979 2.58039 + endloop + endfacet + facet normal -0.615856 -0.181593 0.766646 + outer loop + vertex 0.853021 1.21603 2.58001 + vertex 0.852395 1.21979 2.58039 + vertex 0.850406 1.21748 2.57825 + endloop + endfacet + facet normal -0.618407 -0.191595 0.762144 + outer loop + vertex 0.852181 1.21252 2.57844 + vertex 0.853021 1.21603 2.58001 + vertex 0.850406 1.21748 2.57825 + endloop + endfacet + facet normal -0.617564 -0.191263 0.762911 + outer loop + vertex 0.852181 1.21252 2.57844 + vertex 0.850406 1.21748 2.57825 + vertex 0.848735 1.21499 2.57627 + endloop + endfacet + facet normal -0.616749 -0.189066 0.764117 + outer loop + vertex 0.852181 1.21252 2.57844 + vertex 0.848735 1.21499 2.57627 + vertex 0.849843 1.2122 2.57648 + endloop + endfacet + facet normal -0.626643 -0.19368 0.754855 + outer loop + vertex 0.847875 1.21198 2.57479 + vertex 0.849843 1.2122 2.57648 + vertex 0.848735 1.21499 2.57627 + endloop + endfacet + facet normal -0.631801 -0.190485 0.751361 + outer loop + vertex 0.848735 1.21499 2.57627 + vertex 0.845105 1.21629 2.57355 + vertex 0.847875 1.21198 2.57479 + endloop + endfacet + facet normal -0.632865 -0.1915 0.750206 + outer loop + vertex 0.847875 1.21198 2.57479 + vertex 0.845105 1.21629 2.57355 + vertex 0.845131 1.2116 2.57238 + endloop + endfacet + facet normal -0.631269 -0.185386 0.753081 + outer loop + vertex 0.848735 1.21499 2.57627 + vertex 0.847078 1.21952 2.576 + vertex 0.845105 1.21629 2.57355 + endloop + endfacet + facet normal -0.635576 -0.180847 0.750558 + outer loop + vertex 0.843541 1.22188 2.57357 + vertex 0.845105 1.21629 2.57355 + vertex 0.847078 1.21952 2.576 + endloop + endfacet + facet normal -0.63424 -0.176658 0.752683 + outer loop + vertex 0.845685 1.22446 2.57599 + vertex 0.843541 1.22188 2.57357 + vertex 0.847078 1.21952 2.576 + endloop + endfacet + facet normal -0.627065 -0.174616 0.759143 + outer loop + vertex 0.847078 1.21952 2.576 + vertex 0.84913 1.2222 2.57831 + vertex 0.845685 1.22446 2.57599 + endloop + endfacet + facet normal -0.623936 -0.178462 0.760825 + outer loop + vertex 0.850406 1.21748 2.57825 + vertex 0.84913 1.2222 2.57831 + vertex 0.847078 1.21952 2.576 + endloop + endfacet + facet normal -0.636819 -0.173224 0.751302 + outer loop + vertex 0.841956 1.2274 2.5735 + vertex 0.843541 1.22188 2.57357 + vertex 0.845685 1.22446 2.57599 + endloop + endfacet + facet normal -0.63754 -0.175007 0.750277 + outer loop + vertex 0.844677 1.22837 2.57604 + vertex 0.841956 1.2274 2.5735 + vertex 0.845685 1.22446 2.57599 + endloop + endfacet + facet normal -0.627315 -0.172498 0.759421 + outer loop + vertex 0.845685 1.22446 2.57599 + vertex 0.847776 1.22758 2.57842 + vertex 0.844677 1.22837 2.57604 + endloop + endfacet + facet normal -0.627306 -0.172316 0.75947 + outer loop + vertex 0.844677 1.22837 2.57604 + vertex 0.847776 1.22758 2.57842 + vertex 0.845092 1.23168 2.57714 + endloop + endfacet + facet normal -0.634101 -0.169779 0.754381 + outer loop + vertex 0.844677 1.22837 2.57604 + vertex 0.845092 1.23168 2.57714 + vertex 0.84289 1.23086 2.5751 + endloop + endfacet + facet normal -0.635302 -0.166076 0.754195 + outer loop + vertex 0.84289 1.23086 2.5751 + vertex 0.845092 1.23168 2.57714 + vertex 0.842391 1.2346 2.5755 + endloop + endfacet + facet normal -0.64405 -0.166434 0.746659 + outer loop + vertex 0.84289 1.23086 2.5751 + vertex 0.842391 1.2346 2.5755 + vertex 0.840397 1.23236 2.57328 + endloop + endfacet + facet normal -0.644942 -0.16977 0.745137 + outer loop + vertex 0.841956 1.2274 2.5735 + vertex 0.84289 1.23086 2.5751 + vertex 0.840397 1.23236 2.57328 + endloop + endfacet + facet normal -0.648257 -0.170952 0.741983 + outer loop + vertex 0.841956 1.2274 2.5735 + vertex 0.840397 1.23236 2.57328 + vertex 0.838681 1.22993 2.57122 + endloop + endfacet + facet normal -0.645612 -0.164056 0.745836 + outer loop + vertex 0.841956 1.2274 2.5735 + vertex 0.838681 1.22993 2.57122 + vertex 0.839642 1.22715 2.57144 + endloop + endfacet + facet normal -0.64378 -0.174494 0.74505 + outer loop + vertex 0.840281 1.22424 2.57132 + vertex 0.841956 1.2274 2.5735 + vertex 0.839642 1.22715 2.57144 + endloop + endfacet + facet normal -0.653799 -0.164203 0.738637 + outer loop + vertex 0.838681 1.22993 2.57122 + vertex 0.840397 1.23236 2.57328 + vertex 0.837261 1.23446 2.57097 + endloop + endfacet + facet normal -0.659926 -0.166451 0.732661 + outer loop + vertex 0.838681 1.22993 2.57122 + vertex 0.837261 1.23446 2.57097 + vertex 0.835242 1.23124 2.56843 + endloop + endfacet + facet normal -0.659885 -0.166098 0.732777 + outer loop + vertex 0.838681 1.22993 2.57122 + vertex 0.835242 1.23124 2.56843 + vertex 0.837746 1.22697 2.56971 + endloop + endfacet + facet normal -0.662798 -0.163177 0.730803 + outer loop + vertex 0.833908 1.23688 2.56847 + vertex 0.835242 1.23124 2.56843 + vertex 0.837261 1.23446 2.57097 + endloop + endfacet + facet normal -0.662441 -0.162104 0.731364 + outer loop + vertex 0.836117 1.23949 2.57105 + vertex 0.833908 1.23688 2.56847 + vertex 0.837261 1.23446 2.57097 + endloop + endfacet + facet normal -0.65646 -0.160829 0.737017 + outer loop + vertex 0.837261 1.23446 2.57097 + vertex 0.839333 1.23702 2.57338 + vertex 0.836117 1.23949 2.57105 + endloop + endfacet + facet normal -0.655706 -0.158801 0.738128 + outer loop + vertex 0.839333 1.23702 2.57338 + vertex 0.838305 1.24199 2.57354 + vertex 0.836117 1.23949 2.57105 + endloop + endfacet + facet normal -0.656342 -0.157881 0.737759 + outer loop + vertex 0.836117 1.23949 2.57105 + vertex 0.838305 1.24199 2.57354 + vertex 0.835255 1.24426 2.57131 + endloop + endfacet + facet normal -0.663155 -0.158775 0.731448 + outer loop + vertex 0.835255 1.24426 2.57131 + vertex 0.832639 1.24245 2.56854 + vertex 0.836117 1.23949 2.57105 + endloop + endfacet + facet normal -0.66272 -0.1597 0.731641 + outer loop + vertex 0.832792 1.24697 2.56967 + vertex 0.832639 1.24245 2.56854 + vertex 0.835255 1.24426 2.57131 + endloop + endfacet + facet normal -0.661015 -0.156853 0.733796 + outer loop + vertex 0.834688 1.24718 2.57142 + vertex 0.832792 1.24697 2.56967 + vertex 0.835255 1.24426 2.57131 + endloop + endfacet + facet normal -0.652232 -0.15546 0.741907 + outer loop + vertex 0.835255 1.24426 2.57131 + vertex 0.836963 1.24747 2.57348 + vertex 0.834688 1.24718 2.57142 + endloop + endfacet + facet normal -0.65338 -0.148853 0.742252 + outer loop + vertex 0.836963 1.24747 2.57348 + vertex 0.833757 1.24997 2.57116 + vertex 0.834688 1.24718 2.57142 + endloop + endfacet + facet normal -0.653635 -0.149511 0.741895 + outer loop + vertex 0.836963 1.24747 2.57348 + vertex 0.835501 1.25242 2.57319 + vertex 0.833757 1.24997 2.57116 + endloop + endfacet + facet normal -0.652037 -0.151478 0.742901 + outer loop + vertex 0.833757 1.24997 2.57116 + vertex 0.835501 1.25242 2.57319 + vertex 0.832372 1.25448 2.57087 + endloop + endfacet + facet normal -0.652602 -0.153322 0.742026 + outer loop + vertex 0.835501 1.25242 2.57319 + vertex 0.834479 1.25705 2.57325 + vertex 0.832372 1.25448 2.57087 + endloop + endfacet + facet normal -0.648522 -0.158903 0.744425 + outer loop + vertex 0.832372 1.25448 2.57087 + vertex 0.834479 1.25705 2.57325 + vertex 0.83124 1.25948 2.57095 + endloop + endfacet + facet normal -0.65038 -0.163941 0.741707 + outer loop + vertex 0.834479 1.25705 2.57325 + vertex 0.833438 1.262 2.57343 + vertex 0.83124 1.25948 2.57095 + endloop + endfacet + facet normal -0.647226 -0.168431 0.743458 + outer loop + vertex 0.83124 1.25948 2.57095 + vertex 0.833438 1.262 2.57343 + vertex 0.830334 1.26426 2.57124 + endloop + endfacet + facet normal -0.643842 -0.162783 0.747643 + outer loop + vertex 0.833438 1.262 2.57343 + vertex 0.834479 1.25705 2.57325 + vertex 0.836751 1.25942 2.57572 + endloop + endfacet + facet normal -0.645801 -0.167791 0.74484 + outer loop + vertex 0.835647 1.26446 2.5759 + vertex 0.833438 1.262 2.57343 + vertex 0.836751 1.25942 2.57572 + endloop + endfacet + facet normal -0.640542 -0.166807 0.749587 + outer loop + vertex 0.836751 1.25942 2.57572 + vertex 0.839037 1.26197 2.57824 + vertex 0.835647 1.26446 2.5759 + endloop + endfacet + facet normal -0.643969 -0.161899 0.747725 + outer loop + vertex 0.840231 1.2565 2.57809 + vertex 0.839037 1.26197 2.57824 + vertex 0.836751 1.25942 2.57572 + endloop + endfacet + facet normal -0.64142 -0.156072 0.751147 + outer loop + vertex 0.837519 1.25468 2.57539 + vertex 0.840231 1.2565 2.57809 + vertex 0.836751 1.25942 2.57572 + endloop + endfacet + facet normal -0.645138 -0.148201 0.749555 + outer loop + vertex 0.84015 1.25179 2.57708 + vertex 0.840231 1.2565 2.57809 + vertex 0.837519 1.25468 2.57539 + endloop + endfacet + facet normal -0.644341 -0.146928 0.750491 + outer loop + vertex 0.837966 1.25096 2.57505 + vertex 0.84015 1.25179 2.57708 + vertex 0.837519 1.25468 2.57539 + endloop + endfacet + facet normal -0.649234 -0.147123 0.746224 + outer loop + vertex 0.837966 1.25096 2.57505 + vertex 0.837519 1.25468 2.57539 + vertex 0.835501 1.25242 2.57319 + endloop + endfacet + facet normal -0.645169 -0.144251 0.750299 + outer loop + vertex 0.839677 1.24846 2.57604 + vertex 0.84015 1.25179 2.57708 + vertex 0.837966 1.25096 2.57505 + endloop + endfacet + facet normal -0.648916 -0.148413 0.746245 + outer loop + vertex 0.836963 1.24747 2.57348 + vertex 0.839677 1.24846 2.57604 + vertex 0.837966 1.25096 2.57505 + endloop + endfacet + facet normal -0.648527 -0.149689 0.746328 + outer loop + vertex 0.839677 1.24846 2.57604 + vertex 0.836963 1.24747 2.57348 + vertex 0.840538 1.24447 2.57599 + endloop + endfacet + facet normal -0.640201 -0.147991 0.753818 + outer loop + vertex 0.840538 1.24447 2.57599 + vertex 0.842711 1.24761 2.57845 + vertex 0.839677 1.24846 2.57604 + endloop + endfacet + facet normal -0.638817 -0.149616 0.754671 + outer loop + vertex 0.843922 1.24196 2.57835 + vertex 0.842711 1.24761 2.57845 + vertex 0.840538 1.24447 2.57599 + endloop + endfacet + facet normal -0.640298 -0.153553 0.752622 + outer loop + vertex 0.841598 1.23939 2.57585 + vertex 0.843922 1.24196 2.57835 + vertex 0.840538 1.24447 2.57599 + endloop + endfacet + facet normal -0.647313 -0.154849 0.746329 + outer loop + vertex 0.840538 1.24447 2.57599 + vertex 0.838305 1.24199 2.57354 + vertex 0.841598 1.23939 2.57585 + endloop + endfacet + facet normal -0.6367 -0.15872 0.7546 + outer loop + vertex 0.845122 1.23643 2.5782 + vertex 0.843922 1.24196 2.57835 + vertex 0.841598 1.23939 2.57585 + endloop + endfacet + facet normal -0.637445 -0.160389 0.753617 + outer loop + vertex 0.842391 1.2346 2.5755 + vertex 0.845122 1.23643 2.5782 + vertex 0.841598 1.23939 2.57585 + endloop + endfacet + facet normal -0.645908 -0.161251 0.746191 + outer loop + vertex 0.841598 1.23939 2.57585 + vertex 0.839333 1.23702 2.57338 + vertex 0.842391 1.2346 2.5755 + endloop + endfacet + facet normal -0.631559 -0.157729 0.759114 + outer loop + vertex 0.843922 1.24196 2.57835 + vertex 0.845122 1.23643 2.5782 + vertex 0.847225 1.23945 2.58058 + endloop + endfacet + facet normal -0.629499 -0.152591 0.761871 + outer loop + vertex 0.846366 1.24452 2.58088 + vertex 0.843922 1.24196 2.57835 + vertex 0.847225 1.23945 2.58058 + endloop + endfacet + facet normal -0.619925 -0.151453 0.769906 + outer loop + vertex 0.847225 1.23945 2.58058 + vertex 0.85002 1.24147 2.58323 + vertex 0.846366 1.24452 2.58088 + endloop + endfacet + facet normal -0.61927 -0.15005 0.770707 + outer loop + vertex 0.85002 1.24147 2.58323 + vertex 0.848853 1.24704 2.58337 + vertex 0.846366 1.24452 2.58088 + endloop + endfacet + facet normal -0.621894 -0.146122 0.769348 + outer loop + vertex 0.846366 1.24452 2.58088 + vertex 0.848853 1.24704 2.58337 + vertex 0.845531 1.24962 2.58118 + endloop + endfacet + facet normal -0.631883 -0.147275 0.760943 + outer loop + vertex 0.845531 1.24962 2.58118 + vertex 0.842711 1.24761 2.57845 + vertex 0.846366 1.24452 2.58088 + endloop + endfacet + facet normal -0.632347 -0.146343 0.760737 + outer loop + vertex 0.84275 1.25246 2.57941 + vertex 0.842711 1.24761 2.57845 + vertex 0.845531 1.24962 2.58118 + endloop + endfacet + facet normal -0.632756 -0.147035 0.760264 + outer loop + vertex 0.844818 1.25344 2.58132 + vertex 0.84275 1.25246 2.57941 + vertex 0.845531 1.24962 2.58118 + endloop + endfacet + facet normal -0.62493 -0.145833 0.766939 + outer loop + vertex 0.845531 1.24962 2.58118 + vertex 0.847697 1.25261 2.58351 + vertex 0.844818 1.25344 2.58132 + endloop + endfacet + facet normal -0.625626 -0.154052 0.764761 + outer loop + vertex 0.844818 1.25344 2.58132 + vertex 0.847697 1.25261 2.58351 + vertex 0.84509 1.25669 2.5822 + endloop + endfacet + facet normal -0.633802 -0.151674 0.758478 + outer loop + vertex 0.844818 1.25344 2.58132 + vertex 0.84509 1.25669 2.5822 + vertex 0.843038 1.25573 2.5803 + endloop + endfacet + facet normal -0.631518 -0.15785 0.759124 + outer loop + vertex 0.843038 1.25573 2.5803 + vertex 0.84509 1.25669 2.5822 + vertex 0.842308 1.25947 2.58047 + endloop + endfacet + facet normal -0.637035 -0.158709 0.75432 + outer loop + vertex 0.843038 1.25573 2.5803 + vertex 0.842308 1.25947 2.58047 + vertex 0.840231 1.2565 2.57809 + endloop + endfacet + facet normal -0.636293 -0.147998 0.757118 + outer loop + vertex 0.843038 1.25573 2.5803 + vertex 0.840231 1.2565 2.57809 + vertex 0.84275 1.25246 2.57941 + endloop + endfacet + facet normal -0.633007 -0.160456 0.757335 + outer loop + vertex 0.84509 1.25669 2.5822 + vertex 0.845046 1.26143 2.58317 + vertex 0.842308 1.25947 2.58047 + endloop + endfacet + facet normal -0.631013 -0.16438 0.758157 + outer loop + vertex 0.842308 1.25947 2.58047 + vertex 0.845046 1.26143 2.58317 + vertex 0.841418 1.26449 2.58081 + endloop + endfacet + facet normal -0.637584 -0.165151 0.752471 + outer loop + vertex 0.841418 1.26449 2.58081 + vertex 0.839037 1.26197 2.57824 + vertex 0.842308 1.25947 2.58047 + endloop + endfacet + facet normal -0.62921 -0.160435 0.760497 + outer loop + vertex 0.845046 1.26143 2.58317 + vertex 0.843872 1.26698 2.58337 + vertex 0.841418 1.26449 2.58081 + endloop + endfacet + facet normal -0.624079 -0.161821 0.764421 + outer loop + vertex 0.847676 1.25738 2.58446 + vertex 0.845046 1.26143 2.58317 + vertex 0.84509 1.25669 2.5822 + endloop + endfacet + facet normal -0.623667 -0.161419 0.764842 + outer loop + vertex 0.847927 1.26063 2.58535 + vertex 0.845046 1.26143 2.58317 + vertex 0.847676 1.25738 2.58446 + endloop + endfacet + facet normal -0.614195 -0.164086 0.771907 + outer loop + vertex 0.847676 1.25738 2.58446 + vertex 0.849781 1.25835 2.58634 + vertex 0.847927 1.26063 2.58535 + endloop + endfacet + facet normal -0.612622 -0.16208 0.773579 + outer loop + vertex 0.849781 1.25835 2.58634 + vertex 0.850037 1.26163 2.58723 + vertex 0.847927 1.26063 2.58535 + endloop + endfacet + facet normal -0.613713 -0.159247 0.773302 + outer loop + vertex 0.847927 1.26063 2.58535 + vertex 0.850037 1.26163 2.58723 + vertex 0.84718 1.26441 2.58553 + endloop + endfacet + facet normal -0.610618 -0.153907 0.776826 + outer loop + vertex 0.850037 1.26163 2.58723 + vertex 0.850023 1.26645 2.58817 + vertex 0.84718 1.26441 2.58553 + endloop + endfacet + facet normal -0.614026 -0.147332 0.775413 + outer loop + vertex 0.84718 1.26441 2.58553 + vertex 0.850023 1.26645 2.58817 + vertex 0.846417 1.26944 2.58589 + endloop + endfacet + facet normal -0.619691 -0.147868 0.770791 + outer loop + vertex 0.846417 1.26944 2.58589 + vertex 0.843872 1.26698 2.58337 + vertex 0.84718 1.26441 2.58553 + endloop + endfacet + facet normal -0.624643 -0.159609 0.764425 + outer loop + vertex 0.843872 1.26698 2.58337 + vertex 0.845046 1.26143 2.58317 + vertex 0.84718 1.26441 2.58553 + endloop + endfacet + facet normal -0.623176 -0.142435 0.769002 + outer loop + vertex 0.842844 1.27265 2.58358 + vertex 0.843872 1.26698 2.58337 + vertex 0.846417 1.26944 2.58589 + endloop + endfacet + facet normal -0.615059 -0.126784 0.778221 + outer loop + vertex 0.845842 1.27451 2.58626 + vertex 0.842844 1.27265 2.58358 + vertex 0.846417 1.26944 2.58589 + endloop + endfacet + facet normal -0.612284 -0.126631 0.780431 + outer loop + vertex 0.846417 1.26944 2.58589 + vertex 0.849022 1.27185 2.58832 + vertex 0.845842 1.27451 2.58626 + endloop + endfacet + facet normal -0.605098 -0.111971 0.788238 + outer loop + vertex 0.849022 1.27185 2.58832 + vertex 0.848377 1.27695 2.58855 + vertex 0.845842 1.27451 2.58626 + endloop + endfacet + facet normal -0.60864 -0.10645 0.786273 + outer loop + vertex 0.845842 1.27451 2.58626 + vertex 0.848377 1.27695 2.58855 + vertex 0.845288 1.27926 2.58647 + endloop + endfacet + facet normal -0.611542 -0.106685 0.783987 + outer loop + vertex 0.845288 1.27926 2.58647 + vertex 0.843283 1.27707 2.58461 + vertex 0.845842 1.27451 2.58626 + endloop + endfacet + facet normal -0.615169 -0.101526 0.781831 + outer loop + vertex 0.842191 1.2815 2.58433 + vertex 0.843283 1.27707 2.58461 + vertex 0.845288 1.27926 2.58647 + endloop + endfacet + facet normal -0.614808 -0.100647 0.782228 + outer loop + vertex 0.844554 1.28307 2.58638 + vertex 0.842191 1.2815 2.58433 + vertex 0.845288 1.27926 2.58647 + endloop + endfacet + facet normal -0.609198 -0.0994587 0.786757 + outer loop + vertex 0.845288 1.27926 2.58647 + vertex 0.847511 1.28248 2.5886 + vertex 0.844554 1.28307 2.58638 + endloop + endfacet + facet normal -0.609705 -0.107431 0.785314 + outer loop + vertex 0.844554 1.28307 2.58638 + vertex 0.847511 1.28248 2.5886 + vertex 0.844981 1.28656 2.58719 + endloop + endfacet + facet normal -0.614802 -0.105932 0.781535 + outer loop + vertex 0.844554 1.28307 2.58638 + vertex 0.844981 1.28656 2.58719 + vertex 0.842758 1.28538 2.58528 + endloop + endfacet + facet normal -0.611764 -0.113738 0.782821 + outer loop + vertex 0.842758 1.28538 2.58528 + vertex 0.844981 1.28656 2.58719 + vertex 0.842205 1.28934 2.58543 + endloop + endfacet + facet normal -0.616314 -0.114239 0.77917 + outer loop + vertex 0.842758 1.28538 2.58528 + vertex 0.842205 1.28934 2.58543 + vertex 0.839814 1.28625 2.58309 + endloop + endfacet + facet normal -0.615001 -0.103452 0.78171 + outer loop + vertex 0.842758 1.28538 2.58528 + vertex 0.839814 1.28625 2.58309 + vertex 0.842191 1.2815 2.58433 + endloop + endfacet + facet normal -0.62034 -0.107369 0.776949 + outer loop + vertex 0.842191 1.2815 2.58433 + vertex 0.839814 1.28625 2.58309 + vertex 0.839306 1.28185 2.58207 + endloop + endfacet + facet normal -0.624466 -0.106167 0.773803 + outer loop + vertex 0.839306 1.28185 2.58207 + vertex 0.839814 1.28625 2.58309 + vertex 0.836854 1.2843 2.58043 + endloop + endfacet + facet normal -0.620399 -0.115061 0.7758 + outer loop + vertex 0.836854 1.2843 2.58043 + vertex 0.839814 1.28625 2.58309 + vertex 0.836352 1.28941 2.58078 + endloop + endfacet + facet normal -0.628893 -0.115416 0.768877 + outer loop + vertex 0.836352 1.28941 2.58078 + vertex 0.833786 1.28692 2.57831 + vertex 0.836854 1.2843 2.58043 + endloop + endfacet + facet normal -0.626609 -0.110664 0.771437 + outer loop + vertex 0.833786 1.28692 2.57831 + vertex 0.834428 1.2818 2.5781 + vertex 0.836854 1.2843 2.58043 + endloop + endfacet + facet normal -0.633845 -0.111321 0.765407 + outer loop + vertex 0.834428 1.2818 2.5781 + vertex 0.833786 1.28692 2.57831 + vertex 0.831356 1.28427 2.57591 + endloop + endfacet + facet normal -0.633826 -0.11135 0.765419 + outer loop + vertex 0.831356 1.28427 2.57591 + vertex 0.833786 1.28692 2.57831 + vertex 0.830591 1.28938 2.57602 + endloop + endfacet + facet normal -0.638184 -0.1219 0.760172 + outer loop + vertex 0.833786 1.28692 2.57831 + vertex 0.832811 1.29258 2.5784 + vertex 0.830591 1.28938 2.57602 + endloop + endfacet + facet normal -0.639698 -0.120116 0.759183 + outer loop + vertex 0.830591 1.28938 2.57602 + vertex 0.832811 1.29258 2.5784 + vertex 0.829815 1.29344 2.57601 + endloop + endfacet + facet normal -0.640537 -0.128956 0.757022 + outer loop + vertex 0.829815 1.29344 2.57601 + vertex 0.832811 1.29258 2.5784 + vertex 0.830247 1.29683 2.57696 + endloop + endfacet + facet normal -0.626044 -0.11997 0.770504 + outer loop + vertex 0.832811 1.29258 2.5784 + vertex 0.833786 1.28692 2.57831 + vertex 0.836352 1.28941 2.58078 + endloop + endfacet + facet normal -0.629775 -0.127322 0.766271 + outer loop + vertex 0.835672 1.29461 2.58109 + vertex 0.832811 1.29258 2.5784 + vertex 0.836352 1.28941 2.58078 + endloop + endfacet + facet normal -0.618585 -0.126403 0.775484 + outer loop + vertex 0.836352 1.28941 2.58078 + vertex 0.838948 1.29192 2.58327 + vertex 0.835672 1.29461 2.58109 + endloop + endfacet + facet normal -0.618797 -0.126859 0.77524 + outer loop + vertex 0.838948 1.29192 2.58327 + vertex 0.837991 1.29766 2.58344 + vertex 0.835672 1.29461 2.58109 + endloop + endfacet + facet normal -0.615917 -0.130365 0.77695 + outer loop + vertex 0.835672 1.29461 2.58109 + vertex 0.837991 1.29766 2.58344 + vertex 0.834988 1.2987 2.58123 + endloop + endfacet + facet normal -0.628421 -0.132097 0.766575 + outer loop + vertex 0.834988 1.2987 2.58123 + vertex 0.832846 1.29757 2.57928 + vertex 0.835672 1.29461 2.58109 + endloop + endfacet + facet normal -0.629371 -0.129659 0.766212 + outer loop + vertex 0.832846 1.29757 2.57928 + vertex 0.834988 1.2987 2.58123 + vertex 0.83313 1.30107 2.58011 + endloop + endfacet + facet normal -0.641097 -0.126527 0.756958 + outer loop + vertex 0.83313 1.30107 2.58011 + vertex 0.830311 1.3016 2.57781 + vertex 0.832846 1.29757 2.57928 + endloop + endfacet + facet normal -0.641444 -0.126874 0.756606 + outer loop + vertex 0.832846 1.29757 2.57928 + vertex 0.830311 1.3016 2.57781 + vertex 0.830247 1.29683 2.57696 + endloop + endfacet + facet normal -0.640853 -0.129255 0.756704 + outer loop + vertex 0.832811 1.29258 2.5784 + vertex 0.832846 1.29757 2.57928 + vertex 0.830247 1.29683 2.57696 + endloop + endfacet + facet normal -0.651607 -0.125223 0.748149 + outer loop + vertex 0.830247 1.29683 2.57696 + vertex 0.830311 1.3016 2.57781 + vertex 0.827597 1.29971 2.57513 + endloop + endfacet + facet normal -0.650564 -0.123508 0.749341 + outer loop + vertex 0.828073 1.296 2.57493 + vertex 0.830247 1.29683 2.57696 + vertex 0.827597 1.29971 2.57513 + endloop + endfacet + facet normal -0.653476 -0.121181 0.747185 + outer loop + vertex 0.827597 1.29971 2.57513 + vertex 0.830311 1.3016 2.57781 + vertex 0.827022 1.3043 2.57537 + endloop + endfacet + facet normal -0.664412 -0.122031 0.737337 + outer loop + vertex 0.827022 1.3043 2.57537 + vertex 0.824676 1.30199 2.57287 + vertex 0.827597 1.29971 2.57513 + endloop + endfacet + facet normal -0.663993 -0.120943 0.737893 + outer loop + vertex 0.824676 1.30199 2.57287 + vertex 0.82558 1.2975 2.57295 + vertex 0.827597 1.29971 2.57513 + endloop + endfacet + facet normal -0.661752 -0.124406 0.739329 + outer loop + vertex 0.828073 1.296 2.57493 + vertex 0.827597 1.29971 2.57513 + vertex 0.82558 1.2975 2.57295 + endloop + endfacet + facet normal -0.660555 -0.12008 0.741113 + outer loop + vertex 0.827033 1.29245 2.57343 + vertex 0.828073 1.296 2.57493 + vertex 0.82558 1.2975 2.57295 + endloop + endfacet + facet normal -0.668225 -0.122986 0.733723 + outer loop + vertex 0.827033 1.29245 2.57343 + vertex 0.82558 1.2975 2.57295 + vertex 0.823713 1.29522 2.57087 + endloop + endfacet + facet normal -0.663001 -0.11054 0.740412 + outer loop + vertex 0.827033 1.29245 2.57343 + vertex 0.823713 1.29522 2.57087 + vertex 0.824534 1.29225 2.57116 + endloop + endfacet + facet normal -0.663465 -0.106615 0.740572 + outer loop + vertex 0.825175 1.2891 2.57128 + vertex 0.827033 1.29245 2.57343 + vertex 0.824534 1.29225 2.57116 + endloop + endfacet + facet normal -0.672692 -0.108827 0.731876 + outer loop + vertex 0.824534 1.29225 2.57116 + vertex 0.821947 1.29218 2.56877 + vertex 0.825175 1.2891 2.57128 + endloop + endfacet + facet normal -0.669121 -0.10156 0.736181 + outer loop + vertex 0.821947 1.29218 2.56877 + vertex 0.822905 1.28682 2.56891 + vertex 0.825175 1.2891 2.57128 + endloop + endfacet + facet normal -0.66645 -0.106077 0.737965 + outer loop + vertex 0.825175 1.2891 2.57128 + vertex 0.822905 1.28682 2.56891 + vertex 0.825906 1.28419 2.57124 + endloop + endfacet + facet normal -0.65479 -0.104446 0.748559 + outer loop + vertex 0.825906 1.28419 2.57124 + vertex 0.828234 1.28681 2.57364 + vertex 0.825175 1.2891 2.57128 + endloop + endfacet + facet normal -0.651563 -0.109263 0.750685 + outer loop + vertex 0.82891 1.28173 2.57349 + vertex 0.828234 1.28681 2.57364 + vertex 0.825906 1.28419 2.57124 + endloop + endfacet + facet normal -0.653481 -0.113746 0.748348 + outer loop + vertex 0.826503 1.27922 2.571 + vertex 0.82891 1.28173 2.57349 + vertex 0.825906 1.28419 2.57124 + endloop + endfacet + facet normal -0.663398 -0.114521 0.739452 + outer loop + vertex 0.825906 1.28419 2.57124 + vertex 0.823507 1.28173 2.5687 + vertex 0.826503 1.27922 2.571 + endloop + endfacet + facet normal -0.668249 -0.126074 0.733177 + outer loop + vertex 0.823507 1.28173 2.5687 + vertex 0.824163 1.27665 2.56843 + vertex 0.826503 1.27922 2.571 + endloop + endfacet + facet normal -0.661832 -0.135959 0.737221 + outer loop + vertex 0.826503 1.27922 2.571 + vertex 0.824163 1.27665 2.56843 + vertex 0.827336 1.27439 2.57086 + endloop + endfacet + facet normal -0.655565 -0.135047 0.742964 + outer loop + vertex 0.827336 1.27439 2.57086 + vertex 0.829529 1.27692 2.57326 + vertex 0.826503 1.27922 2.571 + endloop + endfacet + facet normal -0.650325 -0.142605 0.746151 + outer loop + vertex 0.830431 1.27241 2.57318 + vertex 0.829529 1.27692 2.57326 + vertex 0.827336 1.27439 2.57086 + endloop + endfacet + facet normal -0.667193 -0.152172 0.729176 + outer loop + vertex 0.824163 1.27665 2.56843 + vertex 0.825261 1.27123 2.5683 + vertex 0.827336 1.27439 2.57086 + endloop + endfacet + facet normal -0.672213 -0.153075 0.72436 + outer loop + vertex 0.825261 1.27123 2.5683 + vertex 0.824163 1.27665 2.56843 + vertex 0.821803 1.27427 2.56573 + endloop + endfacet + facet normal -0.674121 -0.15756 0.72162 + outer loop + vertex 0.82247 1.26965 2.56535 + vertex 0.825261 1.27123 2.5683 + vertex 0.821803 1.27427 2.56573 + endloop + endfacet + facet normal -0.684509 -0.15823 0.711625 + outer loop + vertex 0.821803 1.27427 2.56573 + vertex 0.819549 1.27209 2.56308 + vertex 0.82247 1.26965 2.56535 + endloop + endfacet + facet normal -0.685602 -0.161121 0.709923 + outer loop + vertex 0.819549 1.27209 2.56308 + vertex 0.820526 1.26764 2.56302 + vertex 0.82247 1.26965 2.56535 + endloop + endfacet + facet normal -0.682438 -0.166323 0.711769 + outer loop + vertex 0.822971 1.26603 2.56498 + vertex 0.82247 1.26965 2.56535 + vertex 0.820526 1.26764 2.56302 + endloop + endfacet + facet normal -0.681877 -0.164226 0.712792 + outer loop + vertex 0.822055 1.26268 2.56333 + vertex 0.822971 1.26603 2.56498 + vertex 0.820526 1.26764 2.56302 + endloop + endfacet + facet normal -0.687299 -0.166262 0.707091 + outer loop + vertex 0.822055 1.26268 2.56333 + vertex 0.820526 1.26764 2.56302 + vertex 0.818784 1.26546 2.56081 + endloop + endfacet + facet normal -0.681981 -0.152574 0.715278 + outer loop + vertex 0.822055 1.26268 2.56333 + vertex 0.818784 1.26546 2.56081 + vertex 0.819652 1.26257 2.56102 + endloop + endfacet + facet normal -0.681745 -0.154392 0.715113 + outer loop + vertex 0.82042 1.25947 2.56108 + vertex 0.822055 1.26268 2.56333 + vertex 0.819652 1.26257 2.56102 + endloop + endfacet + facet normal -0.675453 -0.160787 0.71966 + outer loop + vertex 0.823509 1.25712 2.56346 + vertex 0.822055 1.26268 2.56333 + vertex 0.82042 1.25947 2.56108 + endloop + endfacet + facet normal -0.673365 -0.1547 0.722944 + outer loop + vertex 0.821458 1.2546 2.56101 + vertex 0.823509 1.25712 2.56346 + vertex 0.82042 1.25947 2.56108 + endloop + endfacet + facet normal -0.669176 -0.160624 0.725537 + outer loop + vertex 0.824548 1.25218 2.56332 + vertex 0.823509 1.25712 2.56346 + vertex 0.821458 1.2546 2.56101 + endloop + endfacet + facet normal -0.668525 -0.158845 0.726528 + outer loop + vertex 0.822497 1.24966 2.56089 + vertex 0.824548 1.25218 2.56332 + vertex 0.821458 1.2546 2.56101 + endloop + endfacet + facet normal -0.665657 -0.162867 0.728268 + outer loop + vertex 0.825552 1.24761 2.56322 + vertex 0.824548 1.25218 2.56332 + vertex 0.822497 1.24966 2.56089 + endloop + endfacet + facet normal -0.665151 -0.161158 0.729111 + outer loop + vertex 0.82383 1.24522 2.56112 + vertex 0.825552 1.24761 2.56322 + vertex 0.822497 1.24966 2.56089 + endloop + endfacet + facet normal -0.663942 -0.162697 0.72987 + outer loop + vertex 0.827005 1.24265 2.56343 + vertex 0.825552 1.24761 2.56322 + vertex 0.82383 1.24522 2.56112 + endloop + endfacet + facet normal -0.663753 -0.162212 0.73015 + outer loop + vertex 0.827005 1.24265 2.56343 + vertex 0.82383 1.24522 2.56112 + vertex 0.82475 1.24248 2.56135 + endloop + endfacet + facet normal -0.663473 -0.16405 0.729994 + outer loop + vertex 0.825319 1.23949 2.56119 + vertex 0.827005 1.24265 2.56343 + vertex 0.82475 1.24248 2.56135 + endloop + endfacet + facet normal -0.664709 -0.164226 0.728829 + outer loop + vertex 0.82475 1.24248 2.56135 + vertex 0.82286 1.24217 2.55955 + vertex 0.825319 1.23949 2.56119 + endloop + endfacet + facet normal -0.666522 -0.167347 0.726459 + outer loop + vertex 0.82286 1.24217 2.55955 + vertex 0.822779 1.23756 2.55842 + vertex 0.825319 1.23949 2.56119 + endloop + endfacet + facet normal -0.667065 -0.166274 0.726207 + outer loop + vertex 0.825319 1.23949 2.56119 + vertex 0.822779 1.23756 2.55842 + vertex 0.826222 1.23468 2.56092 + endloop + endfacet + facet normal -0.666498 -0.166198 0.726745 + outer loop + vertex 0.826222 1.23468 2.56092 + vertex 0.828365 1.2371 2.56344 + vertex 0.825319 1.23949 2.56119 + endloop + endfacet + facet normal -0.667977 -0.163995 0.725887 + outer loop + vertex 0.829429 1.2321 2.56329 + vertex 0.828365 1.2371 2.56344 + vertex 0.826222 1.23468 2.56092 + endloop + endfacet + facet normal -0.669917 -0.169123 0.722917 + outer loop + vertex 0.827416 1.22976 2.56087 + vertex 0.829429 1.2321 2.56329 + vertex 0.826222 1.23468 2.56092 + endloop + endfacet + facet normal -0.672789 -0.169793 0.720087 + outer loop + vertex 0.826222 1.23468 2.56092 + vertex 0.824162 1.23221 2.55841 + vertex 0.827416 1.22976 2.56087 + endloop + endfacet + facet normal -0.675092 -0.176705 0.716259 + outer loop + vertex 0.824162 1.23221 2.55841 + vertex 0.825554 1.22728 2.55851 + vertex 0.827416 1.22976 2.56087 + endloop + endfacet + facet normal -0.677866 -0.172979 0.714546 + outer loop + vertex 0.828714 1.22517 2.561 + vertex 0.827416 1.22976 2.56087 + vertex 0.825554 1.22728 2.55851 + endloop + endfacet + facet normal -0.679098 -0.177499 0.712265 + outer loop + vertex 0.827072 1.22208 2.55866 + vertex 0.828714 1.22517 2.561 + vertex 0.825554 1.22728 2.55851 + endloop + endfacet + facet normal -0.685053 -0.179419 0.706053 + outer loop + vertex 0.827072 1.22208 2.55866 + vertex 0.825554 1.22728 2.55851 + vertex 0.823694 1.22506 2.55614 + endloop + endfacet + facet normal -0.686437 -0.182878 0.703818 + outer loop + vertex 0.827072 1.22208 2.55866 + vertex 0.823694 1.22506 2.55614 + vertex 0.824596 1.22208 2.55624 + endloop + endfacet + facet normal -0.686679 -0.181035 0.704058 + outer loop + vertex 0.825341 1.21907 2.5562 + vertex 0.827072 1.22208 2.55866 + vertex 0.824596 1.22208 2.55624 + endloop + endfacet + facet normal -0.690055 -0.181817 0.700547 + outer loop + vertex 0.824596 1.22208 2.55624 + vertex 0.822046 1.22211 2.55374 + vertex 0.825341 1.21907 2.5562 + endloop + endfacet + facet normal -0.687308 -0.180323 0.703628 + outer loop + vertex 0.828363 1.21686 2.55858 + vertex 0.827072 1.22208 2.55866 + vertex 0.825341 1.21907 2.5562 + endloop + endfacet + facet normal -0.687893 -0.182283 0.702549 + outer loop + vertex 0.826378 1.21448 2.55602 + vertex 0.828363 1.21686 2.55858 + vertex 0.825341 1.21907 2.5562 + endloop + endfacet + facet normal -0.693152 -0.183263 0.697105 + outer loop + vertex 0.825341 1.21907 2.5562 + vertex 0.82334 1.21689 2.55363 + vertex 0.826378 1.21448 2.55602 + endloop + endfacet + facet normal -0.694023 -0.185925 0.695531 + outer loop + vertex 0.82334 1.21689 2.55363 + vertex 0.824432 1.21218 2.55346 + vertex 0.826378 1.21448 2.55602 + endloop + endfacet + facet normal -0.691979 -0.188995 0.69674 + outer loop + vertex 0.826378 1.21448 2.55602 + vertex 0.824432 1.21218 2.55346 + vertex 0.827495 1.20991 2.55589 + endloop + endfacet + facet normal -0.686157 -0.187748 0.702808 + outer loop + vertex 0.827495 1.20991 2.55589 + vertex 0.829418 1.21214 2.55837 + vertex 0.826378 1.21448 2.55602 + endloop + endfacet + facet normal -0.681875 -0.194126 0.705239 + outer loop + vertex 0.830546 1.20766 2.55822 + vertex 0.829418 1.21214 2.55837 + vertex 0.827495 1.20991 2.55589 + endloop + endfacet + facet normal -0.682102 -0.194881 0.70481 + outer loop + vertex 0.82884 1.20549 2.55597 + vertex 0.830546 1.20766 2.55822 + vertex 0.827495 1.20991 2.55589 + endloop + endfacet + facet normal -0.687087 -0.196494 0.699501 + outer loop + vertex 0.82884 1.20549 2.55597 + vertex 0.827495 1.20991 2.55589 + vertex 0.825697 1.20759 2.55347 + endloop + endfacet + facet normal -0.685946 -0.19198 0.70187 + outer loop + vertex 0.827282 1.20246 2.55362 + vertex 0.82884 1.20549 2.55597 + vertex 0.825697 1.20759 2.55347 + endloop + endfacet + facet normal -0.692666 -0.194265 0.694604 + outer loop + vertex 0.827282 1.20246 2.55362 + vertex 0.825697 1.20759 2.55347 + vertex 0.823874 1.20547 2.55106 + endloop + endfacet + facet normal -0.690622 -0.188976 0.69809 + outer loop + vertex 0.827282 1.20246 2.55362 + vertex 0.823874 1.20547 2.55106 + vertex 0.824792 1.20256 2.55118 + endloop + endfacet + facet normal -0.690234 -0.192333 0.697556 + outer loop + vertex 0.825607 1.19934 2.5511 + vertex 0.827282 1.20246 2.55362 + vertex 0.824792 1.20256 2.55118 + endloop + endfacet + facet normal -0.701512 -0.194879 0.685494 + outer loop + vertex 0.824792 1.20256 2.55118 + vertex 0.822348 1.20233 2.54862 + vertex 0.825607 1.19934 2.5511 + endloop + endfacet + facet normal -0.701858 -0.193045 0.68566 + outer loop + vertex 0.822348 1.20233 2.54862 + vertex 0.824792 1.20256 2.55118 + vertex 0.823874 1.20547 2.55106 + endloop + endfacet + facet normal -0.696275 -0.188786 0.692503 + outer loop + vertex 0.823874 1.20547 2.55106 + vertex 0.825697 1.20759 2.55347 + vertex 0.82255 1.20983 2.55092 + endloop + endfacet + facet normal -0.704125 -0.191446 0.683781 + outer loop + vertex 0.823874 1.20547 2.55106 + vertex 0.82255 1.20983 2.55092 + vertex 0.820802 1.20725 2.5484 + endloop + endfacet + facet normal -0.696805 -0.190751 0.691431 + outer loop + vertex 0.825697 1.20759 2.55347 + vertex 0.824432 1.21218 2.55346 + vertex 0.82255 1.20983 2.55092 + endloop + endfacet + facet normal -0.698307 -0.188554 0.690518 + outer loop + vertex 0.82255 1.20983 2.55092 + vertex 0.824432 1.21218 2.55346 + vertex 0.821397 1.21443 2.55101 + endloop + endfacet + facet normal -0.682415 -0.195677 0.704287 + outer loop + vertex 0.827282 1.20246 2.55362 + vertex 0.829815 1.2025 2.55609 + vertex 0.82884 1.20549 2.55597 + endloop + endfacet + facet normal -0.68067 -0.195034 0.706151 + outer loop + vertex 0.832199 1.20264 2.55842 + vertex 0.82884 1.20549 2.55597 + vertex 0.829815 1.2025 2.55609 + endloop + endfacet + facet normal -0.684738 -0.179272 0.706396 + outer loop + vertex 0.829815 1.2025 2.55609 + vertex 0.827282 1.20246 2.55362 + vertex 0.830619 1.19925 2.55604 + endloop + endfacet + facet normal -0.681124 -0.196236 0.70538 + outer loop + vertex 0.832199 1.20264 2.55842 + vertex 0.830546 1.20766 2.55822 + vertex 0.82884 1.20549 2.55597 + endloop + endfacet + facet normal -0.67118 -0.192544 0.715852 + outer loop + vertex 0.832199 1.20264 2.55842 + vertex 0.833056 1.20608 2.56015 + vertex 0.830546 1.20766 2.55822 + endloop + endfacet + facet normal -0.672193 -0.196694 0.713771 + outer loop + vertex 0.833056 1.20608 2.56015 + vertex 0.832453 1.20972 2.56059 + vertex 0.830546 1.20766 2.55822 + endloop + endfacet + facet normal -0.665272 -0.196328 0.720325 + outer loop + vertex 0.833056 1.20608 2.56015 + vertex 0.835214 1.20674 2.56232 + vertex 0.832453 1.20972 2.56059 + endloop + endfacet + facet normal -0.666302 -0.19287 0.720308 + outer loop + vertex 0.834858 1.20354 2.56114 + vertex 0.835214 1.20674 2.56232 + vertex 0.833056 1.20608 2.56015 + endloop + endfacet + facet normal -0.669232 -0.191654 0.717912 + outer loop + vertex 0.834858 1.20354 2.56114 + vertex 0.837788 1.20254 2.5636 + vertex 0.835214 1.20674 2.56232 + endloop + endfacet + facet normal -0.667814 -0.194672 0.71842 + outer loop + vertex 0.832199 1.20264 2.55842 + vertex 0.834858 1.20354 2.56114 + vertex 0.833056 1.20608 2.56015 + endloop + endfacet + facet normal -0.674873 -0.192588 0.712359 + outer loop + vertex 0.829418 1.21214 2.55837 + vertex 0.830546 1.20766 2.55822 + vertex 0.832453 1.20972 2.56059 + endloop + endfacet + facet normal -0.674093 -0.190392 0.713687 + outer loop + vertex 0.83155 1.21434 2.56097 + vertex 0.829418 1.21214 2.55837 + vertex 0.832453 1.20972 2.56059 + endloop + endfacet + facet normal -0.665256 -0.189365 0.722201 + outer loop + vertex 0.832453 1.20972 2.56059 + vertex 0.835191 1.21134 2.56353 + vertex 0.83155 1.21434 2.56097 + endloop + endfacet + facet normal -0.664717 -0.187974 0.723061 + outer loop + vertex 0.835191 1.21134 2.56353 + vertex 0.833638 1.2169 2.56355 + vertex 0.83155 1.21434 2.56097 + endloop + endfacet + facet normal -0.669418 -0.181439 0.720389 + outer loop + vertex 0.83155 1.21434 2.56097 + vertex 0.833638 1.2169 2.56355 + vertex 0.830393 1.21913 2.5611 + endloop + endfacet + facet normal -0.677405 -0.183148 0.712446 + outer loop + vertex 0.830393 1.21913 2.5611 + vertex 0.828363 1.21686 2.55858 + vertex 0.83155 1.21434 2.56097 + endloop + endfacet + facet normal -0.668667 -0.178878 0.721725 + outer loop + vertex 0.833638 1.2169 2.56355 + vertex 0.832031 1.22246 2.56344 + vertex 0.830393 1.21913 2.5611 + endloop + endfacet + facet normal -0.670302 -0.177283 0.720601 + outer loop + vertex 0.830393 1.21913 2.5611 + vertex 0.832031 1.22246 2.56344 + vertex 0.829592 1.2222 2.56111 + endloop + endfacet + facet normal -0.680871 -0.180022 0.709934 + outer loop + vertex 0.829592 1.2222 2.56111 + vertex 0.827072 1.22208 2.55866 + vertex 0.830393 1.21913 2.5611 + endloop + endfacet + facet normal -0.671366 -0.171369 0.721041 + outer loop + vertex 0.832031 1.22246 2.56344 + vertex 0.828714 1.22517 2.561 + vertex 0.829592 1.2222 2.56111 + endloop + endfacet + facet normal -0.67178 -0.17246 0.720395 + outer loop + vertex 0.832031 1.22246 2.56344 + vertex 0.830502 1.22746 2.56321 + vertex 0.828714 1.22517 2.561 + endloop + endfacet + facet normal -0.66986 -0.171783 0.722342 + outer loop + vertex 0.832031 1.22246 2.56344 + vertex 0.832956 1.22591 2.56512 + vertex 0.830502 1.22746 2.56321 + endloop + endfacet + facet normal -0.668617 -0.167019 0.724608 + outer loop + vertex 0.832956 1.22591 2.56512 + vertex 0.83247 1.22959 2.56552 + vertex 0.830502 1.22746 2.56321 + endloop + endfacet + facet normal -0.668824 -0.1667 0.72449 + outer loop + vertex 0.829429 1.2321 2.56329 + vertex 0.830502 1.22746 2.56321 + vertex 0.83247 1.22959 2.56552 + endloop + endfacet + facet normal -0.667812 -0.164126 0.72601 + outer loop + vertex 0.831656 1.23436 2.56585 + vertex 0.829429 1.2321 2.56329 + vertex 0.83247 1.22959 2.56552 + endloop + endfacet + facet normal -0.665683 -0.163901 0.728012 + outer loop + vertex 0.83247 1.22959 2.56552 + vertex 0.835242 1.23124 2.56843 + vertex 0.831656 1.23436 2.56585 + endloop + endfacet + facet normal -0.664638 -0.166351 0.728412 + outer loop + vertex 0.83511 1.22662 2.56725 + vertex 0.835242 1.23124 2.56843 + vertex 0.83247 1.22959 2.56552 + endloop + endfacet + facet normal -0.661103 -0.167218 0.731424 + outer loop + vertex 0.837746 1.22697 2.56971 + vertex 0.835242 1.23124 2.56843 + vertex 0.83511 1.22662 2.56725 + endloop + endfacet + facet normal -0.659863 -0.173766 0.731017 + outer loop + vertex 0.837662 1.22251 2.56858 + vertex 0.837746 1.22697 2.56971 + vertex 0.83511 1.22662 2.56725 + endloop + endfacet + facet normal -0.658899 -0.172813 0.732112 + outer loop + vertex 0.834681 1.22343 2.56611 + vertex 0.837662 1.22251 2.56858 + vertex 0.83511 1.22662 2.56725 + endloop + endfacet + facet normal -0.663851 -0.170722 0.728118 + outer loop + vertex 0.834681 1.22343 2.56611 + vertex 0.83511 1.22662 2.56725 + vertex 0.832956 1.22591 2.56512 + endloop + endfacet + facet normal -0.659132 -0.176536 0.731013 + outer loop + vertex 0.835669 1.21953 2.56606 + vertex 0.837662 1.22251 2.56858 + vertex 0.834681 1.22343 2.56611 + endloop + endfacet + facet normal -0.665267 -0.178013 0.725074 + outer loop + vertex 0.834681 1.22343 2.56611 + vertex 0.832031 1.22246 2.56344 + vertex 0.835669 1.21953 2.56606 + endloop + endfacet + facet normal -0.656658 -0.179464 0.732525 + outer loop + vertex 0.839011 1.2172 2.56848 + vertex 0.837662 1.22251 2.56858 + vertex 0.835669 1.21953 2.56606 + endloop + endfacet + facet normal -0.65757 -0.182383 0.730984 + outer loop + vertex 0.837061 1.21458 2.56608 + vertex 0.839011 1.2172 2.56848 + vertex 0.835669 1.21953 2.56606 + endloop + endfacet + facet normal -0.653163 -0.187979 0.733513 + outer loop + vertex 0.840317 1.21246 2.56843 + vertex 0.839011 1.2172 2.56848 + vertex 0.837061 1.21458 2.56608 + endloop + endfacet + facet normal -0.652089 -0.178378 0.736859 + outer loop + vertex 0.837662 1.22251 2.56858 + vertex 0.839011 1.2172 2.56848 + vertex 0.841279 1.21946 2.57104 + endloop + endfacet + facet normal -0.652322 -0.17893 0.736519 + outer loop + vertex 0.840281 1.22424 2.57132 + vertex 0.837662 1.22251 2.56858 + vertex 0.841279 1.21946 2.57104 + endloop + endfacet + facet normal -0.644022 -0.177634 0.744098 + outer loop + vertex 0.841279 1.21946 2.57104 + vertex 0.843541 1.22188 2.57357 + vertex 0.840281 1.22424 2.57132 + endloop + endfacet + facet normal -0.64834 -0.184246 0.738721 + outer loop + vertex 0.841279 1.21946 2.57104 + vertex 0.839011 1.2172 2.56848 + vertex 0.842264 1.21465 2.5707 + endloop + endfacet + facet normal -0.641247 -0.183244 0.745134 + outer loop + vertex 0.842264 1.21465 2.5707 + vertex 0.845105 1.21629 2.57355 + vertex 0.841279 1.21946 2.57104 + endloop + endfacet + facet normal -0.654132 -0.1751 0.735834 + outer loop + vertex 0.837746 1.22697 2.56971 + vertex 0.837662 1.22251 2.56858 + vertex 0.840281 1.22424 2.57132 + endloop + endfacet + facet normal -0.664974 -0.166905 0.727978 + outer loop + vertex 0.832956 1.22591 2.56512 + vertex 0.83511 1.22662 2.56725 + vertex 0.83247 1.22959 2.56552 + endloop + endfacet + facet normal -0.666566 -0.173901 0.724878 + outer loop + vertex 0.832031 1.22246 2.56344 + vertex 0.834681 1.22343 2.56611 + vertex 0.832956 1.22591 2.56512 + endloop + endfacet + facet normal -0.665187 -0.177803 0.725199 + outer loop + vertex 0.832031 1.22246 2.56344 + vertex 0.833638 1.2169 2.56355 + vertex 0.835669 1.21953 2.56606 + endloop + endfacet + facet normal -0.661003 -0.183361 0.727636 + outer loop + vertex 0.835669 1.21953 2.56606 + vertex 0.833638 1.2169 2.56355 + vertex 0.837061 1.21458 2.56608 + endloop + endfacet + facet normal -0.662148 -0.187265 0.725598 + outer loop + vertex 0.833638 1.2169 2.56355 + vertex 0.835191 1.21134 2.56353 + vertex 0.837061 1.21458 2.56608 + endloop + endfacet + facet normal -0.657173 -0.19259 0.72872 + outer loop + vertex 0.838712 1.21001 2.56636 + vertex 0.837061 1.21458 2.56608 + vertex 0.835191 1.21134 2.56353 + endloop + endfacet + facet normal -0.657143 -0.192279 0.728829 + outer loop + vertex 0.838712 1.21001 2.56636 + vertex 0.835191 1.21134 2.56353 + vertex 0.837881 1.20703 2.56482 + endloop + endfacet + facet normal -0.65917 -0.194251 0.726472 + outer loop + vertex 0.837881 1.20703 2.56482 + vertex 0.835191 1.21134 2.56353 + vertex 0.835214 1.20674 2.56232 + endloop + endfacet + facet normal -0.663524 -0.193296 0.722753 + outer loop + vertex 0.835214 1.20674 2.56232 + vertex 0.835191 1.21134 2.56353 + vertex 0.832453 1.20972 2.56059 + endloop + endfacet + facet normal -0.677845 -0.184412 0.711701 + outer loop + vertex 0.828363 1.21686 2.55858 + vertex 0.829418 1.21214 2.55837 + vertex 0.83155 1.21434 2.56097 + endloop + endfacet + facet normal -0.692111 -0.189445 0.696486 + outer loop + vertex 0.824432 1.21218 2.55346 + vertex 0.825697 1.20759 2.55347 + vertex 0.827495 1.20991 2.55589 + endloop + endfacet + facet normal -0.685521 -0.185775 0.703952 + outer loop + vertex 0.829418 1.21214 2.55837 + vertex 0.828363 1.21686 2.55858 + vertex 0.826378 1.21448 2.55602 + endloop + endfacet + facet normal -0.680328 -0.178707 0.710786 + outer loop + vertex 0.827072 1.22208 2.55866 + vertex 0.828363 1.21686 2.55858 + vertex 0.830393 1.21913 2.5611 + endloop + endfacet + facet normal -0.689783 -0.18401 0.700243 + outer loop + vertex 0.822046 1.22211 2.55374 + vertex 0.824596 1.22208 2.55624 + vertex 0.823694 1.22506 2.55614 + endloop + endfacet + facet normal -0.681647 -0.174799 0.710494 + outer loop + vertex 0.827072 1.22208 2.55866 + vertex 0.829592 1.2222 2.56111 + vertex 0.828714 1.22517 2.561 + endloop + endfacet + facet normal -0.672595 -0.171347 0.719901 + outer loop + vertex 0.828714 1.22517 2.561 + vertex 0.830502 1.22746 2.56321 + vertex 0.827416 1.22976 2.56087 + endloop + endfacet + facet normal -0.680805 -0.178437 0.710397 + outer loop + vertex 0.825554 1.22728 2.55851 + vertex 0.824162 1.23221 2.55841 + vertex 0.82229 1.22968 2.55598 + endloop + endfacet + facet normal -0.682336 -0.183408 0.707657 + outer loop + vertex 0.823694 1.22506 2.55614 + vertex 0.825554 1.22728 2.55851 + vertex 0.82229 1.22968 2.55598 + endloop + endfacet + facet normal -0.677652 -0.182643 0.712341 + outer loop + vertex 0.82229 1.22968 2.55598 + vertex 0.824162 1.23221 2.55841 + vertex 0.821022 1.23437 2.55598 + endloop + endfacet + facet normal -0.675513 -0.175153 0.716243 + outer loop + vertex 0.824162 1.23221 2.55841 + vertex 0.822779 1.23756 2.55842 + vertex 0.821022 1.23437 2.55598 + endloop + endfacet + facet normal -0.67134 -0.179606 0.719058 + outer loop + vertex 0.821022 1.23437 2.55598 + vertex 0.822779 1.23756 2.55842 + vertex 0.820026 1.23806 2.55597 + endloop + endfacet + facet normal -0.671524 -0.169527 0.721329 + outer loop + vertex 0.820026 1.23806 2.55597 + vertex 0.822779 1.23756 2.55842 + vertex 0.820262 1.24137 2.55697 + endloop + endfacet + facet normal -0.683403 -0.165571 0.711019 + outer loop + vertex 0.820026 1.23806 2.55597 + vertex 0.820262 1.24137 2.55697 + vertex 0.818311 1.23991 2.55475 + endloop + endfacet + facet normal -0.671219 -0.167215 0.722152 + outer loop + vertex 0.830502 1.22746 2.56321 + vertex 0.829429 1.2321 2.56329 + vertex 0.827416 1.22976 2.56087 + endloop + endfacet + facet normal -0.667901 -0.163981 0.72596 + outer loop + vertex 0.828365 1.2371 2.56344 + vertex 0.829429 1.2321 2.56329 + vertex 0.831656 1.23436 2.56585 + endloop + endfacet + facet normal -0.667083 -0.161941 0.72717 + outer loop + vertex 0.830551 1.23947 2.56597 + vertex 0.828365 1.2371 2.56344 + vertex 0.831656 1.23436 2.56585 + endloop + endfacet + facet normal -0.666934 -0.161912 0.727312 + outer loop + vertex 0.831656 1.23436 2.56585 + vertex 0.833908 1.23688 2.56847 + vertex 0.830551 1.23947 2.56597 + endloop + endfacet + facet normal -0.66654 -0.160816 0.727916 + outer loop + vertex 0.833908 1.23688 2.56847 + vertex 0.832639 1.24245 2.56854 + vertex 0.830551 1.23947 2.56597 + endloop + endfacet + facet normal -0.666515 -0.160848 0.727933 + outer loop + vertex 0.830551 1.23947 2.56597 + vertex 0.832639 1.24245 2.56854 + vertex 0.82967 1.24346 2.56605 + endloop + endfacet + facet normal -0.665623 -0.160668 0.728787 + outer loop + vertex 0.82967 1.24346 2.56605 + vertex 0.827005 1.24265 2.56343 + vertex 0.830551 1.23947 2.56597 + endloop + endfacet + facet normal -0.665428 -0.161375 0.72881 + outer loop + vertex 0.827005 1.24265 2.56343 + vertex 0.82967 1.24346 2.56605 + vertex 0.827973 1.24603 2.56507 + endloop + endfacet + facet normal -0.665514 -0.161469 0.72871 + outer loop + vertex 0.82967 1.24346 2.56605 + vertex 0.830144 1.24665 2.56719 + vertex 0.827973 1.24603 2.56507 + endloop + endfacet + facet normal -0.665159 -0.162804 0.728738 + outer loop + vertex 0.827973 1.24603 2.56507 + vertex 0.830144 1.24665 2.56719 + vertex 0.827531 1.24969 2.56548 + endloop + endfacet + facet normal -0.663042 -0.159482 0.731397 + outer loop + vertex 0.830144 1.24665 2.56719 + vertex 0.830319 1.25128 2.56835 + vertex 0.827531 1.24969 2.56548 + endloop + endfacet + facet normal -0.662067 -0.161849 0.731759 + outer loop + vertex 0.827531 1.24969 2.56548 + vertex 0.830319 1.25128 2.56835 + vertex 0.826761 1.2544 2.56583 + endloop + endfacet + facet normal -0.663615 -0.161996 0.730323 + outer loop + vertex 0.826761 1.2544 2.56583 + vertex 0.824548 1.25218 2.56332 + vertex 0.827531 1.24969 2.56548 + endloop + endfacet + facet normal -0.661311 -0.160131 0.73282 + outer loop + vertex 0.830319 1.25128 2.56835 + vertex 0.829013 1.25689 2.5684 + vertex 0.826761 1.2544 2.56583 + endloop + endfacet + facet normal -0.660351 -0.16157 0.73337 + outer loop + vertex 0.826761 1.2544 2.56583 + vertex 0.829013 1.25689 2.5684 + vertex 0.825656 1.25947 2.56595 + endloop + endfacet + facet normal -0.666098 -0.162693 0.727904 + outer loop + vertex 0.825656 1.25947 2.56595 + vertex 0.823509 1.25712 2.56346 + vertex 0.826761 1.2544 2.56583 + endloop + endfacet + facet normal -0.662115 -0.166408 0.730693 + outer loop + vertex 0.829013 1.25689 2.5684 + vertex 0.827714 1.26244 2.56849 + vertex 0.825656 1.25947 2.56595 + endloop + endfacet + facet normal -0.662442 -0.166006 0.730488 + outer loop + vertex 0.825656 1.25947 2.56595 + vertex 0.827714 1.26244 2.56849 + vertex 0.824726 1.26345 2.56601 + endloop + endfacet + facet normal -0.6727 -0.168247 0.720533 + outer loop + vertex 0.824726 1.26345 2.56601 + vertex 0.822055 1.26268 2.56333 + vertex 0.825656 1.25947 2.56595 + endloop + endfacet + facet normal -0.662927 -0.171823 0.7287 + outer loop + vertex 0.824726 1.26345 2.56601 + vertex 0.827714 1.26244 2.56849 + vertex 0.825134 1.26664 2.56713 + endloop + endfacet + facet normal -0.670301 -0.168751 0.722647 + outer loop + vertex 0.824726 1.26345 2.56601 + vertex 0.825134 1.26664 2.56713 + vertex 0.822971 1.26603 2.56498 + endloop + endfacet + facet normal -0.662078 -0.170989 0.729668 + outer loop + vertex 0.827714 1.26244 2.56849 + vertex 0.827791 1.26698 2.56962 + vertex 0.825134 1.26664 2.56713 + endloop + endfacet + facet normal -0.66271 -0.167579 0.729885 + outer loop + vertex 0.827791 1.26698 2.56962 + vertex 0.825261 1.27123 2.5683 + vertex 0.825134 1.26664 2.56713 + endloop + endfacet + facet normal -0.653456 -0.172952 0.736942 + outer loop + vertex 0.827791 1.26698 2.56962 + vertex 0.827714 1.26244 2.56849 + vertex 0.830334 1.26426 2.57124 + endloop + endfacet + facet normal -0.654955 -0.175507 0.735004 + outer loop + vertex 0.829704 1.26719 2.57138 + vertex 0.827791 1.26698 2.56962 + vertex 0.830334 1.26426 2.57124 + endloop + endfacet + facet normal -0.646854 -0.174122 0.74247 + outer loop + vertex 0.830334 1.26426 2.57124 + vertex 0.831991 1.26747 2.57344 + vertex 0.829704 1.26719 2.57138 + endloop + endfacet + facet normal -0.655137 -0.16949 0.736253 + outer loop + vertex 0.830334 1.26426 2.57124 + vertex 0.827714 1.26244 2.56849 + vertex 0.83124 1.25948 2.57095 + endloop + endfacet + facet normal -0.653002 -0.164415 0.739294 + outer loop + vertex 0.827714 1.26244 2.56849 + vertex 0.829013 1.25689 2.5684 + vertex 0.83124 1.25948 2.57095 + endloop + endfacet + facet normal -0.655801 -0.160442 0.737688 + outer loop + vertex 0.83124 1.25948 2.57095 + vertex 0.829013 1.25689 2.5684 + vertex 0.832372 1.25448 2.57087 + endloop + endfacet + facet normal -0.655236 -0.158763 0.738553 + outer loop + vertex 0.829013 1.25689 2.5684 + vertex 0.830319 1.25128 2.56835 + vertex 0.832372 1.25448 2.57087 + endloop + endfacet + facet normal -0.659264 -0.154144 0.735942 + outer loop + vertex 0.833757 1.24997 2.57116 + vertex 0.832372 1.25448 2.57087 + vertex 0.830319 1.25128 2.56835 + endloop + endfacet + facet normal -0.659264 -0.154145 0.735942 + outer loop + vertex 0.833757 1.24997 2.57116 + vertex 0.830319 1.25128 2.56835 + vertex 0.832792 1.24697 2.56967 + endloop + endfacet + facet normal -0.664676 -0.159068 0.730002 + outer loop + vertex 0.832792 1.24697 2.56967 + vertex 0.830319 1.25128 2.56835 + vertex 0.830144 1.24665 2.56719 + endloop + endfacet + facet normal -0.66653 -0.161021 0.72788 + outer loop + vertex 0.82967 1.24346 2.56605 + vertex 0.832639 1.24245 2.56854 + vertex 0.830144 1.24665 2.56719 + endloop + endfacet + facet normal -0.666553 -0.162755 0.727473 + outer loop + vertex 0.827005 1.24265 2.56343 + vertex 0.828365 1.2371 2.56344 + vertex 0.830551 1.23947 2.56597 + endloop + endfacet + facet normal -0.670028 -0.17374 0.721718 + outer loop + vertex 0.822779 1.23756 2.55842 + vertex 0.824162 1.23221 2.55841 + vertex 0.826222 1.23468 2.56092 + endloop + endfacet + facet normal -0.669037 -0.166765 0.724278 + outer loop + vertex 0.822779 1.23756 2.55842 + vertex 0.82286 1.24217 2.55955 + vertex 0.820262 1.24137 2.55697 + endloop + endfacet + facet normal -0.671197 -0.158954 0.724036 + outer loop + vertex 0.82286 1.24217 2.55955 + vertex 0.820397 1.24615 2.55814 + vertex 0.820262 1.24137 2.55697 + endloop + endfacet + facet normal -0.670849 -0.158598 0.724436 + outer loop + vertex 0.82383 1.24522 2.56112 + vertex 0.820397 1.24615 2.55814 + vertex 0.82286 1.24217 2.55955 + endloop + endfacet + facet normal -0.671053 -0.163238 0.723216 + outer loop + vertex 0.82383 1.24522 2.56112 + vertex 0.822497 1.24966 2.56089 + vertex 0.820397 1.24615 2.55814 + endloop + endfacet + facet normal -0.676357 -0.15724 0.719595 + outer loop + vertex 0.819269 1.25181 2.55832 + vertex 0.820397 1.24615 2.55814 + vertex 0.822497 1.24966 2.56089 + endloop + endfacet + facet normal -0.67726 -0.160471 0.71803 + outer loop + vertex 0.821458 1.2546 2.56101 + vertex 0.819269 1.25181 2.55832 + vertex 0.822497 1.24966 2.56089 + endloop + endfacet + facet normal -0.681385 -0.154695 0.715391 + outer loop + vertex 0.818394 1.25706 2.55862 + vertex 0.819269 1.25181 2.55832 + vertex 0.821458 1.2546 2.56101 + endloop + endfacet + facet normal -0.682011 -0.156415 0.71442 + outer loop + vertex 0.82042 1.25947 2.56108 + vertex 0.818394 1.25706 2.55862 + vertex 0.821458 1.2546 2.56101 + endloop + endfacet + facet normal -0.687324 -0.148448 0.71102 + outer loop + vertex 0.817227 1.26234 2.5586 + vertex 0.818394 1.25706 2.55862 + vertex 0.82042 1.25947 2.56108 + endloop + endfacet + facet normal -0.69082 -0.156819 0.705816 + outer loop + vertex 0.819652 1.26257 2.56102 + vertex 0.817227 1.26234 2.5586 + vertex 0.82042 1.25947 2.56108 + endloop + endfacet + facet normal -0.690956 -0.15597 0.705871 + outer loop + vertex 0.817227 1.26234 2.5586 + vertex 0.819652 1.26257 2.56102 + vertex 0.818784 1.26546 2.56081 + endloop + endfacet + facet normal -0.665094 -0.162396 0.728888 + outer loop + vertex 0.828365 1.2371 2.56344 + vertex 0.827005 1.24265 2.56343 + vertex 0.825319 1.23949 2.56119 + endloop + endfacet + facet normal -0.66501 -0.162738 0.728888 + outer loop + vertex 0.82286 1.24217 2.55955 + vertex 0.82475 1.24248 2.56135 + vertex 0.82383 1.24522 2.56112 + endloop + endfacet + facet normal -0.66359 -0.162578 0.730216 + outer loop + vertex 0.827005 1.24265 2.56343 + vertex 0.827973 1.24603 2.56507 + vertex 0.825552 1.24761 2.56322 + endloop + endfacet + facet normal -0.663647 -0.162778 0.730121 + outer loop + vertex 0.827973 1.24603 2.56507 + vertex 0.827531 1.24969 2.56548 + vertex 0.825552 1.24761 2.56322 + endloop + endfacet + facet normal -0.663822 -0.162504 0.730022 + outer loop + vertex 0.824548 1.25218 2.56332 + vertex 0.825552 1.24761 2.56322 + vertex 0.827531 1.24969 2.56548 + endloop + endfacet + facet normal -0.664942 -0.159847 0.729589 + outer loop + vertex 0.823509 1.25712 2.56346 + vertex 0.824548 1.25218 2.56332 + vertex 0.826761 1.2544 2.56583 + endloop + endfacet + facet normal -0.668613 -0.158844 0.726447 + outer loop + vertex 0.822055 1.26268 2.56333 + vertex 0.823509 1.25712 2.56346 + vertex 0.825656 1.25947 2.56595 + endloop + endfacet + facet normal -0.672021 -0.170744 0.720579 + outer loop + vertex 0.822055 1.26268 2.56333 + vertex 0.824726 1.26345 2.56601 + vertex 0.822971 1.26603 2.56498 + endloop + endfacet + facet normal -0.671076 -0.16585 0.7226 + outer loop + vertex 0.822971 1.26603 2.56498 + vertex 0.825134 1.26664 2.56713 + vertex 0.82247 1.26965 2.56535 + endloop + endfacet + facet normal -0.670897 -0.165553 0.722834 + outer loop + vertex 0.825134 1.26664 2.56713 + vertex 0.825261 1.27123 2.5683 + vertex 0.82247 1.26965 2.56535 + endloop + endfacet + facet normal -0.680457 -0.139328 0.719421 + outer loop + vertex 0.821803 1.27427 2.56573 + vertex 0.824163 1.27665 2.56843 + vertex 0.821123 1.27929 2.56606 + endloop + endfacet + facet normal -0.68593 -0.139722 0.714127 + outer loop + vertex 0.821123 1.27929 2.56606 + vertex 0.818821 1.27686 2.56338 + vertex 0.821803 1.27427 2.56573 + endloop + endfacet + facet normal -0.69242 -0.128867 0.709893 + outer loop + vertex 0.818225 1.28196 2.56372 + vertex 0.818821 1.27686 2.56338 + vertex 0.821123 1.27929 2.56606 + endloop + endfacet + facet normal -0.687193 -0.117005 0.71699 + outer loop + vertex 0.820552 1.28444 2.56636 + vertex 0.818225 1.28196 2.56372 + vertex 0.821123 1.27929 2.56606 + endloop + endfacet + facet normal -0.681052 -0.11666 0.722882 + outer loop + vertex 0.821123 1.27929 2.56606 + vertex 0.823507 1.28173 2.5687 + vertex 0.820552 1.28444 2.56636 + endloop + endfacet + facet normal -0.677499 -0.108864 0.727423 + outer loop + vertex 0.823507 1.28173 2.5687 + vertex 0.822905 1.28682 2.56891 + vertex 0.820552 1.28444 2.56636 + endloop + endfacet + facet normal -0.680217 -0.104193 0.725568 + outer loop + vertex 0.820552 1.28444 2.56636 + vertex 0.822905 1.28682 2.56891 + vertex 0.820058 1.28927 2.56659 + endloop + endfacet + facet normal -0.688494 -0.104659 0.717651 + outer loop + vertex 0.820058 1.28927 2.56659 + vertex 0.817448 1.28744 2.56382 + vertex 0.820552 1.28444 2.56636 + endloop + endfacet + facet normal -0.691169 -0.110332 0.714222 + outer loop + vertex 0.817448 1.28744 2.56382 + vertex 0.818225 1.28196 2.56372 + vertex 0.820552 1.28444 2.56636 + endloop + endfacet + facet normal -0.693649 -0.110642 0.711765 + outer loop + vertex 0.818225 1.28196 2.56372 + vertex 0.817448 1.28744 2.56382 + vertex 0.815505 1.28427 2.56143 + endloop + endfacet + facet normal -0.694503 -0.109611 0.711091 + outer loop + vertex 0.815505 1.28427 2.56143 + vertex 0.817448 1.28744 2.56382 + vertex 0.814889 1.28806 2.56141 + endloop + endfacet + facet normal -0.68922 -0.102946 0.717202 + outer loop + vertex 0.817713 1.29197 2.56472 + vertex 0.817448 1.28744 2.56382 + vertex 0.820058 1.28927 2.56659 + endloop + endfacet + facet normal -0.688933 -0.102458 0.717547 + outer loop + vertex 0.819619 1.2922 2.56659 + vertex 0.817713 1.29197 2.56472 + vertex 0.820058 1.28927 2.56659 + endloop + endfacet + facet normal -0.681967 -0.101405 0.724319 + outer loop + vertex 0.820058 1.28927 2.56659 + vertex 0.821947 1.29218 2.56877 + vertex 0.819619 1.2922 2.56659 + endloop + endfacet + facet normal -0.68191 -0.102298 0.724247 + outer loop + vertex 0.821947 1.29218 2.56877 + vertex 0.818734 1.29489 2.56613 + vertex 0.819619 1.2922 2.56659 + endloop + endfacet + facet normal -0.686317 -0.113151 0.718447 + outer loop + vertex 0.821947 1.29218 2.56877 + vertex 0.820598 1.29722 2.56828 + vertex 0.818734 1.29489 2.56613 + endloop + endfacet + facet normal -0.687381 -0.111584 0.717675 + outer loop + vertex 0.818734 1.29489 2.56613 + vertex 0.820598 1.29722 2.56828 + vertex 0.817446 1.29927 2.56558 + endloop + endfacet + facet normal -0.693122 -0.11402 0.711745 + outer loop + vertex 0.818734 1.29489 2.56613 + vertex 0.817446 1.29927 2.56558 + vertex 0.815334 1.29589 2.56298 + endloop + endfacet + facet normal -0.692215 -0.102782 0.714335 + outer loop + vertex 0.818734 1.29489 2.56613 + vertex 0.815334 1.29589 2.56298 + vertex 0.817713 1.29197 2.56472 + endloop + endfacet + facet normal -0.693512 -0.10422 0.712867 + outer loop + vertex 0.817713 1.29197 2.56472 + vertex 0.815334 1.29589 2.56298 + vertex 0.815182 1.29129 2.56216 + endloop + endfacet + facet normal -0.694474 -0.112364 0.71069 + outer loop + vertex 0.814374 1.30138 2.56291 + vertex 0.815334 1.29589 2.56298 + vertex 0.817446 1.29927 2.56558 + endloop + endfacet + facet normal -0.695944 -0.117351 0.708443 + outer loop + vertex 0.816664 1.30414 2.56562 + vertex 0.814374 1.30138 2.56291 + vertex 0.817446 1.29927 2.56558 + endloop + endfacet + facet normal -0.690932 -0.116586 0.713457 + outer loop + vertex 0.817446 1.29927 2.56558 + vertex 0.819557 1.30185 2.56804 + vertex 0.816664 1.30414 2.56562 + endloop + endfacet + facet normal -0.691513 -0.118196 0.712629 + outer loop + vertex 0.819557 1.30185 2.56804 + vertex 0.818953 1.30664 2.56825 + vertex 0.816664 1.30414 2.56562 + endloop + endfacet + facet normal -0.69273 -0.116178 0.711778 + outer loop + vertex 0.816664 1.30414 2.56562 + vertex 0.818953 1.30664 2.56825 + vertex 0.81623 1.30915 2.56601 + endloop + endfacet + facet normal -0.696453 -0.116215 0.708129 + outer loop + vertex 0.81623 1.30915 2.56601 + vertex 0.81392 1.30659 2.56332 + vertex 0.816664 1.30414 2.56562 + endloop + endfacet + facet normal -0.697383 -0.114675 0.707465 + outer loop + vertex 0.813542 1.31174 2.56378 + vertex 0.81392 1.30659 2.56332 + vertex 0.81623 1.30915 2.56601 + endloop + endfacet + facet normal -0.696942 -0.113708 0.708055 + outer loop + vertex 0.815788 1.3142 2.56639 + vertex 0.813542 1.31174 2.56378 + vertex 0.81623 1.30915 2.56601 + endloop + endfacet + facet normal -0.692945 -0.113651 0.711977 + outer loop + vertex 0.81623 1.30915 2.56601 + vertex 0.818561 1.31161 2.56867 + vertex 0.815788 1.3142 2.56639 + endloop + endfacet + facet normal -0.692372 -0.112364 0.712738 + outer loop + vertex 0.818561 1.31161 2.56867 + vertex 0.817988 1.31674 2.56893 + vertex 0.815788 1.3142 2.56639 + endloop + endfacet + facet normal -0.693187 -0.111071 0.712149 + outer loop + vertex 0.815788 1.3142 2.56639 + vertex 0.817988 1.31674 2.56893 + vertex 0.815066 1.31905 2.56644 + endloop + endfacet + facet normal -0.698376 -0.111784 0.706948 + outer loop + vertex 0.815066 1.31905 2.56644 + vertex 0.812978 1.31675 2.56402 + vertex 0.815788 1.3142 2.56639 + endloop + endfacet + facet normal -0.700223 -0.10869 0.705602 + outer loop + vertex 0.811978 1.32185 2.56381 + vertex 0.812978 1.31675 2.56402 + vertex 0.815066 1.31905 2.56644 + endloop + endfacet + facet normal -0.701731 -0.112296 0.703536 + outer loop + vertex 0.814419 1.32212 2.56629 + vertex 0.811978 1.32185 2.56381 + vertex 0.815066 1.31905 2.56644 + endloop + endfacet + facet normal -0.693245 -0.11006 0.712248 + outer loop + vertex 0.815066 1.31905 2.56644 + vertex 0.816827 1.32232 2.56866 + vertex 0.814419 1.32212 2.56629 + endloop + endfacet + facet normal -0.693768 -0.105691 0.712401 + outer loop + vertex 0.816827 1.32232 2.56866 + vertex 0.813631 1.32499 2.56595 + vertex 0.814419 1.32212 2.56629 + endloop + endfacet + facet normal -0.69538 -0.109864 0.710195 + outer loop + vertex 0.816827 1.32232 2.56866 + vertex 0.815446 1.32731 2.56808 + vertex 0.813631 1.32499 2.56595 + endloop + endfacet + facet normal -0.697796 -0.106287 0.708367 + outer loop + vertex 0.813631 1.32499 2.56595 + vertex 0.815446 1.32731 2.56808 + vertex 0.812534 1.32938 2.56552 + endloop + endfacet + facet normal -0.704109 -0.108505 0.701753 + outer loop + vertex 0.813631 1.32499 2.56595 + vertex 0.812534 1.32938 2.56552 + vertex 0.810646 1.32667 2.56321 + endloop + endfacet + facet normal -0.703827 -0.107218 0.702233 + outer loop + vertex 0.811978 1.32185 2.56381 + vertex 0.813631 1.32499 2.56595 + vertex 0.810646 1.32667 2.56321 + endloop + endfacet + facet normal -0.706709 -0.1084 0.699151 + outer loop + vertex 0.811978 1.32185 2.56381 + vertex 0.810646 1.32667 2.56321 + vertex 0.808912 1.32405 2.56105 + endloop + endfacet + facet normal -0.704627 -0.101574 0.70227 + outer loop + vertex 0.811978 1.32185 2.56381 + vertex 0.808912 1.32405 2.56105 + vertex 0.809805 1.32156 2.56159 + endloop + endfacet + facet normal -0.703972 -0.106179 0.702245 + outer loop + vertex 0.810345 1.31882 2.56171 + vertex 0.811978 1.32185 2.56381 + vertex 0.809805 1.32156 2.56159 + endloop + endfacet + facet normal -0.707952 -0.107155 0.698084 + outer loop + vertex 0.809805 1.32156 2.56159 + vertex 0.808105 1.32094 2.55977 + vertex 0.810345 1.31882 2.56171 + endloop + endfacet + facet normal -0.707598 -0.106341 0.698567 + outer loop + vertex 0.808105 1.32094 2.55977 + vertex 0.808315 1.31666 2.55933 + vertex 0.810345 1.31882 2.56171 + endloop + endfacet + facet normal -0.705831 -0.109452 0.699873 + outer loop + vertex 0.810345 1.31882 2.56171 + vertex 0.808315 1.31666 2.55933 + vertex 0.810889 1.31425 2.56155 + endloop + endfacet + facet normal -0.701487 -0.109093 0.704283 + outer loop + vertex 0.810889 1.31425 2.56155 + vertex 0.812978 1.31675 2.56402 + vertex 0.810345 1.31882 2.56171 + endloop + endfacet + facet normal -0.699887 -0.111614 0.705479 + outer loop + vertex 0.813542 1.31174 2.56378 + vertex 0.812978 1.31675 2.56402 + vertex 0.810889 1.31425 2.56155 + endloop + endfacet + facet normal -0.700682 -0.113407 0.704403 + outer loop + vertex 0.811297 1.30917 2.56114 + vertex 0.813542 1.31174 2.56378 + vertex 0.810889 1.31425 2.56155 + endloop + endfacet + facet normal -0.707151 -0.113398 0.69791 + outer loop + vertex 0.810889 1.31425 2.56155 + vertex 0.808698 1.31173 2.55892 + vertex 0.811297 1.30917 2.56114 + endloop + endfacet + facet normal -0.708733 -0.116908 0.695723 + outer loop + vertex 0.808698 1.31173 2.55892 + vertex 0.80904 1.30658 2.5584 + vertex 0.811297 1.30917 2.56114 + endloop + endfacet + facet normal -0.709387 -0.115826 0.695237 + outer loop + vertex 0.811297 1.30917 2.56114 + vertex 0.80904 1.30658 2.5584 + vertex 0.811588 1.30393 2.56056 + endloop + endfacet + facet normal -0.700696 -0.116297 0.703918 + outer loop + vertex 0.811588 1.30393 2.56056 + vertex 0.81392 1.30659 2.56332 + vertex 0.811297 1.30917 2.56114 + endloop + endfacet + facet normal -0.700593 -0.116465 0.703993 + outer loop + vertex 0.814374 1.30138 2.56291 + vertex 0.81392 1.30659 2.56332 + vertex 0.811588 1.30393 2.56056 + endloop + endfacet + facet normal -0.700365 -0.115924 0.704308 + outer loop + vertex 0.811703 1.29841 2.55976 + vertex 0.814374 1.30138 2.56291 + vertex 0.811588 1.30393 2.56056 + endloop + endfacet + facet normal -0.71039 -0.114708 0.694397 + outer loop + vertex 0.811588 1.30393 2.56056 + vertex 0.809269 1.30168 2.55782 + vertex 0.811703 1.29841 2.55976 + endloop + endfacet + facet normal -0.709601 -0.113526 0.695398 + outer loop + vertex 0.809269 1.30168 2.55782 + vertex 0.809154 1.29804 2.5571 + vertex 0.811703 1.29841 2.55976 + endloop + endfacet + facet normal -0.709584 -0.116235 0.694968 + outer loop + vertex 0.80904 1.30658 2.5584 + vertex 0.809269 1.30168 2.55782 + vertex 0.811588 1.30393 2.56056 + endloop + endfacet + facet normal -0.70874 -0.104016 0.69776 + outer loop + vertex 0.808105 1.32094 2.55977 + vertex 0.809805 1.32156 2.56159 + vertex 0.808912 1.32405 2.56105 + endloop + endfacet + facet normal -0.705774 -0.106214 0.70043 + outer loop + vertex 0.809575 1.33128 2.56283 + vertex 0.810646 1.32667 2.56321 + vertex 0.812534 1.32938 2.56552 + endloop + endfacet + facet normal -0.705891 -0.106659 0.700245 + outer loop + vertex 0.811761 1.33406 2.56546 + vertex 0.809575 1.33128 2.56283 + vertex 0.812534 1.32938 2.56552 + endloop + endfacet + facet normal -0.698681 -0.105368 0.707631 + outer loop + vertex 0.812534 1.32938 2.56552 + vertex 0.814592 1.33183 2.56792 + vertex 0.811761 1.33406 2.56546 + endloop + endfacet + facet normal -0.698691 -0.105395 0.707618 + outer loop + vertex 0.814592 1.33183 2.56792 + vertex 0.814036 1.33661 2.56808 + vertex 0.811761 1.33406 2.56546 + endloop + endfacet + facet normal -0.69959 -0.103904 0.70695 + outer loop + vertex 0.811761 1.33406 2.56546 + vertex 0.814036 1.33661 2.56808 + vertex 0.811357 1.33902 2.56579 + endloop + endfacet + facet normal -0.70666 -0.10401 0.699867 + outer loop + vertex 0.811357 1.33902 2.56579 + vertex 0.808988 1.33626 2.56298 + vertex 0.811761 1.33406 2.56546 + endloop + endfacet + facet normal -0.707827 -0.102095 0.698969 + outer loop + vertex 0.808748 1.34149 2.5635 + vertex 0.808988 1.33626 2.56298 + vertex 0.811357 1.33902 2.56579 + endloop + endfacet + facet normal -0.706941 -0.100057 0.70016 + outer loop + vertex 0.811117 1.34414 2.56628 + vertex 0.808748 1.34149 2.5635 + vertex 0.811357 1.33902 2.56579 + endloop + endfacet + facet normal -0.700347 -0.100373 0.70671 + outer loop + vertex 0.811357 1.33902 2.56579 + vertex 0.813735 1.34159 2.56851 + vertex 0.811117 1.34414 2.56628 + endloop + endfacet + facet normal -0.699046 -0.102607 0.707677 + outer loop + vertex 0.814036 1.33661 2.56808 + vertex 0.813735 1.34159 2.56851 + vertex 0.811357 1.33902 2.56579 + endloop + endfacet + facet normal -0.691438 -0.102777 0.715088 + outer loop + vertex 0.813735 1.34159 2.56851 + vertex 0.814036 1.33661 2.56808 + vertex 0.816412 1.33906 2.57073 + endloop + endfacet + facet normal -0.690648 -0.101049 0.716097 + outer loop + vertex 0.81614 1.34406 2.57118 + vertex 0.813735 1.34159 2.56851 + vertex 0.816412 1.33906 2.57073 + endloop + endfacet + facet normal -0.68344 -0.101264 0.722949 + outer loop + vertex 0.816412 1.33906 2.57073 + vertex 0.81883 1.34153 2.57336 + vertex 0.81614 1.34406 2.57118 + endloop + endfacet + facet normal -0.682204 -0.0986221 0.72448 + outer loop + vertex 0.81883 1.34153 2.57336 + vertex 0.818535 1.34655 2.57377 + vertex 0.81614 1.34406 2.57118 + endloop + endfacet + facet normal -0.683831 -0.0958437 0.723318 + outer loop + vertex 0.81614 1.34406 2.57118 + vertex 0.818535 1.34655 2.57377 + vertex 0.815795 1.3491 2.57152 + endloop + endfacet + facet normal -0.675307 -0.0987343 0.730898 + outer loop + vertex 0.818535 1.34655 2.57377 + vertex 0.81883 1.34153 2.57336 + vertex 0.821263 1.34403 2.57595 + endloop + endfacet + facet normal -0.674064 -0.0960969 0.732395 + outer loop + vertex 0.820912 1.34907 2.57629 + vertex 0.818535 1.34655 2.57377 + vertex 0.821263 1.34403 2.57595 + endloop + endfacet + facet normal -0.667103 -0.0960398 0.738749 + outer loop + vertex 0.821263 1.34403 2.57595 + vertex 0.823715 1.34653 2.57849 + vertex 0.820912 1.34907 2.57629 + endloop + endfacet + facet normal -0.666135 -0.0939873 0.739885 + outer loop + vertex 0.823715 1.34653 2.57849 + vertex 0.82328 1.35168 2.57875 + vertex 0.820912 1.34907 2.57629 + endloop + endfacet + facet normal -0.667295 -0.0921629 0.739069 + outer loop + vertex 0.820912 1.34907 2.57629 + vertex 0.82328 1.35168 2.57875 + vertex 0.820283 1.35419 2.57636 + endloop + endfacet + facet normal -0.675429 -0.0930562 0.73153 + outer loop + vertex 0.820283 1.35419 2.57636 + vertex 0.818019 1.35169 2.57395 + vertex 0.820912 1.34907 2.57629 + endloop + endfacet + facet normal -0.667061 -0.0916187 0.739348 + outer loop + vertex 0.82328 1.35168 2.57875 + vertex 0.822469 1.35734 2.57872 + vertex 0.820283 1.35419 2.57636 + endloop + endfacet + facet normal -0.667464 -0.0911134 0.739047 + outer loop + vertex 0.820283 1.35419 2.57636 + vertex 0.822469 1.35734 2.57872 + vertex 0.819596 1.35824 2.57624 + endloop + endfacet + facet normal -0.678821 -0.0933662 0.728344 + outer loop + vertex 0.819596 1.35824 2.57624 + vertex 0.816909 1.3573 2.57361 + vertex 0.820283 1.35419 2.57636 + endloop + endfacet + facet normal -0.667375 -0.0903415 0.739222 + outer loop + vertex 0.819596 1.35824 2.57624 + vertex 0.822469 1.35734 2.57872 + vertex 0.820096 1.3616 2.5771 + endloop + endfacet + facet normal -0.674172 -0.0878159 0.733335 + outer loop + vertex 0.819596 1.35824 2.57624 + vertex 0.820096 1.3616 2.5771 + vertex 0.817962 1.36079 2.57504 + endloop + endfacet + facet normal -0.665189 -0.0882764 0.741439 + outer loop + vertex 0.822469 1.35734 2.57872 + vertex 0.822661 1.36233 2.57949 + vertex 0.820096 1.3616 2.5771 + endloop + endfacet + facet normal -0.665948 -0.0847493 0.741168 + outer loop + vertex 0.822661 1.36233 2.57949 + vertex 0.820299 1.3664 2.57783 + vertex 0.820096 1.3616 2.5771 + endloop + endfacet + facet normal -0.664512 -0.0833227 0.742618 + outer loop + vertex 0.823056 1.36586 2.58024 + vertex 0.820299 1.3664 2.57783 + vertex 0.822661 1.36233 2.57949 + endloop + endfacet + facet normal -0.657317 -0.0854341 0.748756 + outer loop + vertex 0.822661 1.36233 2.57949 + vertex 0.824788 1.36347 2.58149 + vertex 0.823056 1.36586 2.58024 + endloop + endfacet + facet normal -0.65348 -0.0806194 0.752638 + outer loop + vertex 0.824788 1.36347 2.58149 + vertex 0.825336 1.36739 2.58238 + vertex 0.823056 1.36586 2.58024 + endloop + endfacet + facet normal -0.653872 -0.0796963 0.752396 + outer loop + vertex 0.823056 1.36586 2.58024 + vertex 0.825336 1.36739 2.58238 + vertex 0.822368 1.36959 2.58003 + endloop + endfacet + facet normal -0.654653 -0.0816962 0.751502 + outer loop + vertex 0.825336 1.36739 2.58238 + vertex 0.824306 1.37181 2.58196 + vertex 0.822368 1.36959 2.58003 + endloop + endfacet + facet normal -0.655922 -0.0798 0.750599 + outer loop + vertex 0.822368 1.36959 2.58003 + vertex 0.824306 1.37181 2.58196 + vertex 0.821955 1.3742 2.58016 + endloop + endfacet + facet normal -0.664214 -0.080336 0.743213 + outer loop + vertex 0.821955 1.3742 2.58016 + vertex 0.819535 1.37168 2.57773 + vertex 0.822368 1.36959 2.58003 + endloop + endfacet + facet normal -0.664519 -0.079831 0.742995 + outer loop + vertex 0.819159 1.37661 2.57792 + vertex 0.819535 1.37168 2.57773 + vertex 0.821955 1.3742 2.58016 + endloop + endfacet + facet normal -0.663596 -0.0777928 0.744035 + outer loop + vertex 0.821742 1.37905 2.58048 + vertex 0.819159 1.37661 2.57792 + vertex 0.821955 1.3742 2.58016 + endloop + endfacet + facet normal -0.654243 -0.077919 0.752259 + outer loop + vertex 0.821955 1.3742 2.58016 + vertex 0.824896 1.37614 2.58292 + vertex 0.821742 1.37905 2.58048 + endloop + endfacet + facet normal -0.653884 -0.077207 0.752645 + outer loop + vertex 0.824896 1.37614 2.58292 + vertex 0.824341 1.38155 2.583 + vertex 0.821742 1.37905 2.58048 + endloop + endfacet + facet normal -0.655353 -0.0746542 0.751625 + outer loop + vertex 0.821742 1.37905 2.58048 + vertex 0.824341 1.38155 2.583 + vertex 0.821439 1.38405 2.58071 + endloop + endfacet + facet normal -0.663129 -0.0748086 0.744758 + outer loop + vertex 0.821439 1.38405 2.58071 + vertex 0.818906 1.38154 2.57821 + vertex 0.821742 1.37905 2.58048 + endloop + endfacet + facet normal -0.664429 -0.0725554 0.743821 + outer loop + vertex 0.818681 1.38649 2.57849 + vertex 0.818906 1.38154 2.57821 + vertex 0.821439 1.38405 2.58071 + endloop + endfacet + facet normal -0.663359 -0.0702775 0.744994 + outer loop + vertex 0.821194 1.38898 2.58096 + vertex 0.818681 1.38649 2.57849 + vertex 0.821439 1.38405 2.58071 + endloop + endfacet + facet normal -0.655793 -0.0702364 0.751666 + outer loop + vertex 0.821439 1.38405 2.58071 + vertex 0.823996 1.38655 2.58318 + vertex 0.821194 1.38898 2.58096 + endloop + endfacet + facet normal -0.655066 -0.0686913 0.752443 + outer loop + vertex 0.823996 1.38655 2.58318 + vertex 0.823742 1.39148 2.58341 + vertex 0.821194 1.38898 2.58096 + endloop + endfacet + facet normal -0.656092 -0.0669219 0.751708 + outer loop + vertex 0.821194 1.38898 2.58096 + vertex 0.823742 1.39148 2.58341 + vertex 0.820984 1.39393 2.58122 + endloop + endfacet + facet normal -0.663867 -0.0668958 0.744853 + outer loop + vertex 0.820984 1.39393 2.58122 + vertex 0.818477 1.39144 2.57876 + vertex 0.821194 1.38898 2.58096 + endloop + endfacet + facet normal -0.664572 -0.0656707 0.744333 + outer loop + vertex 0.818231 1.39646 2.57898 + vertex 0.818477 1.39144 2.57876 + vertex 0.820984 1.39393 2.58122 + endloop + endfacet + facet normal -0.664434 -0.0653902 0.744481 + outer loop + vertex 0.820731 1.39894 2.58143 + vertex 0.818231 1.39646 2.57898 + vertex 0.820984 1.39393 2.58122 + endloop + endfacet + facet normal -0.656472 -0.0652899 0.751519 + outer loop + vertex 0.820984 1.39393 2.58122 + vertex 0.823527 1.39642 2.58365 + vertex 0.820731 1.39894 2.58143 + endloop + endfacet + facet normal -0.656172 -0.0646788 0.751835 + outer loop + vertex 0.823527 1.39642 2.58365 + vertex 0.823268 1.40143 2.58386 + vertex 0.820731 1.39894 2.58143 + endloop + endfacet + facet normal -0.65695 -0.0633348 0.751269 + outer loop + vertex 0.820731 1.39894 2.58143 + vertex 0.823268 1.40143 2.58386 + vertex 0.820359 1.40408 2.58154 + endloop + endfacet + facet normal -0.66457 -0.0637439 0.744502 + outer loop + vertex 0.820359 1.40408 2.58154 + vertex 0.817858 1.40158 2.57909 + vertex 0.820731 1.39894 2.58143 + endloop + endfacet + facet normal -0.665033 -0.0629409 0.744157 + outer loop + vertex 0.817179 1.40709 2.57895 + vertex 0.817858 1.40158 2.57909 + vertex 0.820359 1.40408 2.58154 + endloop + endfacet + facet normal -0.664491 -0.0618783 0.74473 + outer loop + vertex 0.820002 1.40914 2.58164 + vertex 0.817179 1.40709 2.57895 + vertex 0.820359 1.40408 2.58154 + endloop + endfacet + facet normal -0.656433 -0.061454 0.751877 + outer loop + vertex 0.820359 1.40408 2.58154 + vertex 0.822923 1.40659 2.58398 + vertex 0.820002 1.40914 2.58164 + endloop + endfacet + facet normal -0.654565 -0.0575397 0.753813 + outer loop + vertex 0.822923 1.40659 2.58398 + vertex 0.822389 1.41224 2.58395 + vertex 0.820002 1.40914 2.58164 + endloop + endfacet + facet normal -0.653647 -0.0587708 0.754515 + outer loop + vertex 0.820002 1.40914 2.58164 + vertex 0.822389 1.41224 2.58395 + vertex 0.819597 1.41316 2.5816 + endloop + endfacet + facet normal -0.662692 -0.0597581 0.746504 + outer loop + vertex 0.819597 1.41316 2.5816 + vertex 0.817464 1.41198 2.57962 + vertex 0.820002 1.40914 2.58164 + endloop + endfacet + facet normal -0.663411 -0.0576527 0.746031 + outer loop + vertex 0.817464 1.41198 2.57962 + vertex 0.819597 1.41316 2.5816 + vertex 0.817937 1.4155 2.58031 + endloop + endfacet + facet normal -0.669599 -0.0557537 0.740627 + outer loop + vertex 0.817937 1.4155 2.58031 + vertex 0.815208 1.41604 2.57788 + vertex 0.817464 1.41198 2.57962 + endloop + endfacet + facet normal -0.669397 -0.0530086 0.741011 + outer loop + vertex 0.817937 1.4155 2.58031 + vertex 0.817338 1.41928 2.58004 + vertex 0.815208 1.41604 2.57788 + endloop + endfacet + facet normal -0.669379 -0.0530302 0.741026 + outer loop + vertex 0.814576 1.42145 2.5777 + vertex 0.815208 1.41604 2.57788 + vertex 0.817338 1.41928 2.58004 + endloop + endfacet + facet normal -0.668063 -0.0498315 0.742434 + outer loop + vertex 0.817041 1.42398 2.58009 + vertex 0.814576 1.42145 2.5777 + vertex 0.817338 1.41928 2.58004 + endloop + endfacet + facet normal -0.66043 -0.049419 0.749259 + outer loop + vertex 0.817338 1.41928 2.58004 + vertex 0.819315 1.42158 2.58193 + vertex 0.817041 1.42398 2.58009 + endloop + endfacet + facet normal -0.658393 -0.0459475 0.751271 + outer loop + vertex 0.819315 1.42158 2.58193 + vertex 0.820016 1.4261 2.58282 + vertex 0.817041 1.42398 2.58009 + endloop + endfacet + facet normal -0.657612 -0.0477752 0.75184 + outer loop + vertex 0.817041 1.42398 2.58009 + vertex 0.820016 1.4261 2.58282 + vertex 0.816949 1.42893 2.58032 + endloop + endfacet + facet normal -0.666869 -0.0475601 0.743656 + outer loop + vertex 0.816949 1.42893 2.58032 + vertex 0.81432 1.42645 2.5778 + vertex 0.817041 1.42398 2.58009 + endloop + endfacet + facet normal -0.666529 -0.0481886 0.74392 + outer loop + vertex 0.814167 1.43143 2.57799 + vertex 0.81432 1.42645 2.5778 + vertex 0.816949 1.42893 2.58032 + endloop + endfacet + facet normal -0.665907 -0.0469024 0.744559 + outer loop + vertex 0.816752 1.43397 2.58046 + vertex 0.814167 1.43143 2.57799 + vertex 0.816949 1.42893 2.58032 + endloop + endfacet + facet normal -0.657773 -0.0467866 0.751762 + outer loop + vertex 0.816949 1.42893 2.58032 + vertex 0.819563 1.43159 2.58277 + vertex 0.816752 1.43397 2.58046 + endloop + endfacet + facet normal -0.657113 -0.045361 0.752426 + outer loop + vertex 0.819563 1.43159 2.58277 + vertex 0.819322 1.43652 2.58286 + vertex 0.816752 1.43397 2.58046 + endloop + endfacet + facet normal -0.657877 -0.0440372 0.751837 + outer loop + vertex 0.816752 1.43397 2.58046 + vertex 0.819322 1.43652 2.58286 + vertex 0.81658 1.43893 2.5806 + endloop + endfacet + facet normal -0.665741 -0.0441137 0.744878 + outer loop + vertex 0.81658 1.43893 2.5806 + vertex 0.814013 1.43642 2.57816 + vertex 0.816752 1.43397 2.58046 + endloop + endfacet + facet normal -0.666627 -0.0425252 0.744177 + outer loop + vertex 0.813855 1.44141 2.5783 + vertex 0.814013 1.43642 2.57816 + vertex 0.81658 1.43893 2.5806 + endloop + endfacet + facet normal -0.665715 -0.0406715 0.745097 + outer loop + vertex 0.816424 1.44389 2.58073 + vertex 0.813855 1.44141 2.5783 + vertex 0.81658 1.43893 2.5806 + endloop + endfacet + facet normal -0.65757 -0.0406061 0.752299 + outer loop + vertex 0.81658 1.43893 2.5806 + vertex 0.819178 1.44138 2.583 + vertex 0.816424 1.44389 2.58073 + endloop + endfacet + facet normal -0.656704 -0.0388871 0.753145 + outer loop + vertex 0.819178 1.44138 2.583 + vertex 0.819039 1.44632 2.58314 + vertex 0.816424 1.44389 2.58073 + endloop + endfacet + facet normal -0.657275 -0.0378361 0.752701 + outer loop + vertex 0.816424 1.44389 2.58073 + vertex 0.819039 1.44632 2.58314 + vertex 0.816274 1.44887 2.58085 + endloop + endfacet + facet normal -0.665965 -0.0379154 0.745019 + outer loop + vertex 0.816274 1.44887 2.58085 + vertex 0.813702 1.44641 2.57843 + vertex 0.816424 1.44389 2.58073 + endloop + endfacet + facet normal -0.666643 -0.0366703 0.744474 + outer loop + vertex 0.813558 1.45141 2.57855 + vertex 0.813702 1.44641 2.57843 + vertex 0.816274 1.44887 2.58085 + endloop + endfacet + facet normal -0.666538 -0.0364622 0.744579 + outer loop + vertex 0.816131 1.45387 2.58097 + vertex 0.813558 1.45141 2.57855 + vertex 0.816274 1.44887 2.58085 + endloop + endfacet + facet normal -0.657036 -0.036387 0.75298 + outer loop + vertex 0.816274 1.44887 2.58085 + vertex 0.818888 1.45132 2.58325 + vertex 0.816131 1.45387 2.58097 + endloop + endfacet + facet normal -0.65707 -0.0364529 0.752947 + outer loop + vertex 0.818888 1.45132 2.58325 + vertex 0.818747 1.45633 2.58337 + vertex 0.816131 1.45387 2.58097 + endloop + endfacet + facet normal -0.657221 -0.0361762 0.752829 + outer loop + vertex 0.816131 1.45387 2.58097 + vertex 0.818747 1.45633 2.58337 + vertex 0.815992 1.45888 2.58109 + endloop + endfacet + facet normal -0.666708 -0.0362397 0.744437 + outer loop + vertex 0.815992 1.45888 2.58109 + vertex 0.81342 1.45641 2.57866 + vertex 0.816131 1.45387 2.58097 + endloop + endfacet + facet normal -0.667076 -0.0355646 0.74414 + outer loop + vertex 0.813285 1.4614 2.57878 + vertex 0.81342 1.45641 2.57866 + vertex 0.815992 1.45888 2.58109 + endloop + endfacet + facet normal -0.666847 -0.0351108 0.744367 + outer loop + vertex 0.815855 1.46388 2.5812 + vertex 0.813285 1.4614 2.57878 + vertex 0.815992 1.45888 2.58109 + endloop + endfacet + facet normal -0.657135 -0.0350388 0.752958 + outer loop + vertex 0.815992 1.45888 2.58109 + vertex 0.818608 1.46135 2.58349 + vertex 0.815855 1.46388 2.5812 + endloop + endfacet + facet normal -0.656298 -0.0334032 0.753762 + outer loop + vertex 0.818608 1.46135 2.58349 + vertex 0.81847 1.46637 2.58359 + vertex 0.815855 1.46388 2.5812 + endloop + endfacet + facet normal -0.657162 -0.031838 0.753077 + outer loop + vertex 0.815855 1.46388 2.5812 + vertex 0.81847 1.46637 2.58359 + vertex 0.815725 1.46889 2.5813 + endloop + endfacet + facet normal -0.667159 -0.0319212 0.744231 + outer loop + vertex 0.815725 1.46889 2.5813 + vertex 0.813157 1.46639 2.57889 + vertex 0.815855 1.46388 2.5812 + endloop + endfacet + facet normal -0.668362 -0.0297317 0.743241 + outer loop + vertex 0.813041 1.47138 2.57899 + vertex 0.813157 1.46639 2.57889 + vertex 0.815725 1.46889 2.5813 + endloop + endfacet + facet normal -0.667365 -0.0277554 0.744213 + outer loop + vertex 0.815613 1.4739 2.58139 + vertex 0.813041 1.47138 2.57899 + vertex 0.815725 1.46889 2.5813 + endloop + endfacet + facet normal -0.657321 -0.0276813 0.753102 + outer loop + vertex 0.815725 1.46889 2.5813 + vertex 0.818342 1.47139 2.58368 + vertex 0.815613 1.4739 2.58139 + endloop + endfacet + facet normal -0.656398 -0.0258842 0.753971 + outer loop + vertex 0.818342 1.47139 2.58368 + vertex 0.818233 1.47639 2.58375 + vertex 0.815613 1.4739 2.58139 + endloop + endfacet + facet normal -0.657695 -0.0235213 0.752917 + outer loop + vertex 0.815613 1.4739 2.58139 + vertex 0.818233 1.47639 2.58375 + vertex 0.815518 1.4789 2.58146 + endloop + endfacet + facet normal -0.66768 -0.0235787 0.744074 + outer loop + vertex 0.815518 1.4789 2.58146 + vertex 0.812942 1.47638 2.57907 + vertex 0.815613 1.4739 2.58139 + endloop + endfacet + facet normal -0.66837 -0.0223216 0.743494 + outer loop + vertex 0.812856 1.48137 2.57914 + vertex 0.812942 1.47638 2.57907 + vertex 0.815518 1.4789 2.58146 + endloop + endfacet + facet normal -0.666978 -0.0195805 0.74482 + outer loop + vertex 0.815442 1.48389 2.58152 + vertex 0.812856 1.48137 2.57914 + vertex 0.815518 1.4789 2.58146 + endloop + endfacet + facet normal -0.657425 -0.0195419 0.753267 + outer loop + vertex 0.815518 1.4789 2.58146 + vertex 0.81815 1.48139 2.58382 + vertex 0.815442 1.48389 2.58152 + endloop + endfacet + facet normal -0.65618 -0.0171401 0.75441 + outer loop + vertex 0.81815 1.48139 2.58382 + vertex 0.818082 1.48639 2.58388 + vertex 0.815442 1.48389 2.58152 + endloop + endfacet + facet normal -0.656698 -0.016189 0.75398 + outer loop + vertex 0.815442 1.48389 2.58152 + vertex 0.818082 1.48639 2.58388 + vertex 0.815381 1.48887 2.58158 + endloop + endfacet + facet normal -0.665847 -0.0162154 0.745912 + outer loop + vertex 0.815381 1.48887 2.58158 + vertex 0.812785 1.48635 2.5792 + vertex 0.815442 1.48389 2.58152 + endloop + endfacet + facet normal -0.666412 -0.0151795 0.74543 + outer loop + vertex 0.812729 1.49132 2.57926 + vertex 0.812785 1.48635 2.5792 + vertex 0.815381 1.48887 2.58158 + endloop + endfacet + facet normal -0.664864 -0.0121433 0.746866 + outer loop + vertex 0.815334 1.49384 2.58161 + vertex 0.812729 1.49132 2.57926 + vertex 0.815381 1.48887 2.58158 + endloop + endfacet + facet normal -0.655906 -0.0121192 0.754746 + outer loop + vertex 0.815381 1.48887 2.58158 + vertex 0.81803 1.49138 2.58392 + vertex 0.815334 1.49384 2.58161 + endloop + endfacet + facet normal -0.655044 -0.0104543 0.755518 + outer loop + vertex 0.81803 1.49138 2.58392 + vertex 0.817988 1.49635 2.58395 + vertex 0.815334 1.49384 2.58161 + endloop + endfacet + facet normal -0.655919 -0.00884327 0.75478 + outer loop + vertex 0.815334 1.49384 2.58161 + vertex 0.817988 1.49635 2.58395 + vertex 0.815294 1.49882 2.58164 + endloop + endfacet + facet normal -0.66459 -0.00887676 0.747156 + outer loop + vertex 0.815294 1.49882 2.58164 + vertex 0.812679 1.49631 2.57928 + vertex 0.815334 1.49384 2.58161 + endloop + endfacet + facet normal -0.65545 -0.00794145 0.755197 + outer loop + vertex 0.817988 1.49635 2.58395 + vertex 0.817952 1.50133 2.58397 + vertex 0.815294 1.49882 2.58164 + endloop + endfacet + facet normal -0.656183 -0.00658468 0.754573 + outer loop + vertex 0.815294 1.49882 2.58164 + vertex 0.817952 1.50133 2.58397 + vertex 0.815261 1.50383 2.58165 + endloop + endfacet + facet normal -0.665212 -0.00661855 0.746625 + outer loop + vertex 0.815261 1.50383 2.58165 + vertex 0.812633 1.50135 2.57929 + vertex 0.815294 1.49882 2.58164 + endloop + endfacet + facet normal -0.666039 -0.00504996 0.7459 + outer loop + vertex 0.812622 1.50641 2.57931 + vertex 0.812633 1.50135 2.57929 + vertex 0.815261 1.50383 2.58165 + endloop + endfacet + facet normal -0.665572 -0.00419155 0.746322 + outer loop + vertex 0.815246 1.50885 2.58167 + vertex 0.812622 1.50641 2.57931 + vertex 0.815261 1.50383 2.58165 + endloop + endfacet + facet normal -0.6566 -0.00418707 0.754227 + outer loop + vertex 0.815261 1.50383 2.58165 + vertex 0.817924 1.50632 2.58399 + vertex 0.815246 1.50885 2.58167 + endloop + endfacet + facet normal -0.655923 -0.00292413 0.754822 + outer loop + vertex 0.817924 1.50632 2.58399 + vertex 0.817909 1.51133 2.58399 + vertex 0.815246 1.50885 2.58167 + endloop + endfacet + facet normal -0.656682 -0.00149361 0.754166 + outer loop + vertex 0.815246 1.50885 2.58167 + vertex 0.817909 1.51133 2.58399 + vertex 0.815242 1.51386 2.58168 + endloop + endfacet + facet normal -0.664897 -0.0014893 0.746934 + outer loop + vertex 0.815242 1.51386 2.58168 + vertex 0.812638 1.51141 2.57935 + vertex 0.815246 1.50885 2.58167 + endloop + endfacet + facet normal -0.66559 -0.000165799 0.746317 + outer loop + vertex 0.812624 1.51636 2.57934 + vertex 0.812638 1.51141 2.57935 + vertex 0.815242 1.51386 2.58168 + endloop + endfacet + facet normal -0.664342 0.00217546 0.747426 + outer loop + vertex 0.815248 1.51886 2.58167 + vertex 0.812624 1.51636 2.57934 + vertex 0.815242 1.51386 2.58168 + endloop + endfacet + facet normal -0.656301 0.00218066 0.754496 + outer loop + vertex 0.815242 1.51386 2.58168 + vertex 0.81791 1.51634 2.58399 + vertex 0.815248 1.51886 2.58167 + endloop + endfacet + facet normal -0.654958 0.00466209 0.755651 + outer loop + vertex 0.81791 1.51634 2.58399 + vertex 0.817929 1.52134 2.58397 + vertex 0.815248 1.51886 2.58167 + endloop + endfacet + facet normal -0.655705 0.00608307 0.754993 + outer loop + vertex 0.815248 1.51886 2.58167 + vertex 0.817929 1.52134 2.58397 + vertex 0.81527 1.52384 2.58165 + endloop + endfacet + facet normal -0.663603 0.00609044 0.74806 + outer loop + vertex 0.81527 1.52384 2.58165 + vertex 0.812606 1.52133 2.5793 + vertex 0.815248 1.51886 2.58167 + endloop + endfacet + facet normal -0.654365 0.00856019 0.75613 + outer loop + vertex 0.817929 1.52134 2.58397 + vertex 0.817962 1.52633 2.58395 + vertex 0.81527 1.52384 2.58165 + endloop + endfacet + facet normal -0.654717 0.00923051 0.755818 + outer loop + vertex 0.81527 1.52384 2.58165 + vertex 0.817962 1.52633 2.58395 + vertex 0.815306 1.52883 2.58162 + endloop + endfacet + facet normal -0.662657 0.00924602 0.748866 + outer loop + vertex 0.815306 1.52883 2.58162 + vertex 0.812635 1.52632 2.57928 + vertex 0.81527 1.52384 2.58165 + endloop + endfacet + facet normal -0.66322 0.010324 0.748353 + outer loop + vertex 0.812684 1.53129 2.57926 + vertex 0.812635 1.52632 2.57928 + vertex 0.815306 1.52883 2.58162 + endloop + endfacet + facet normal -0.66238 0.0119043 0.749073 + outer loop + vertex 0.815348 1.53381 2.58157 + vertex 0.812684 1.53129 2.57926 + vertex 0.815306 1.52883 2.58162 + endloop + endfacet + facet normal -0.654692 0.0118982 0.755802 + outer loop + vertex 0.815306 1.52883 2.58162 + vertex 0.818002 1.53132 2.58391 + vertex 0.815348 1.53381 2.58157 + endloop + endfacet + facet normal -0.654408 0.0124242 0.756039 + outer loop + vertex 0.818002 1.53132 2.58391 + vertex 0.818047 1.53631 2.58387 + vertex 0.815348 1.53381 2.58157 + endloop + endfacet + facet normal -0.655335 0.0141884 0.755205 + outer loop + vertex 0.815348 1.53381 2.58157 + vertex 0.818047 1.53631 2.58387 + vertex 0.815395 1.5388 2.58152 + endloop + endfacet + facet normal -0.662911 0.0141902 0.748564 + outer loop + vertex 0.815395 1.5388 2.58152 + vertex 0.81273 1.53627 2.57921 + vertex 0.815348 1.53381 2.58157 + endloop + endfacet + facet normal -0.664352 0.01693 0.747228 + outer loop + vertex 0.812785 1.54127 2.57914 + vertex 0.81273 1.53627 2.57921 + vertex 0.815395 1.5388 2.58152 + endloop + endfacet + facet normal -0.664306 0.0170165 0.747267 + outer loop + vertex 0.815455 1.5438 2.58146 + vertex 0.812785 1.54127 2.57914 + vertex 0.815395 1.5388 2.58152 + endloop + endfacet + facet normal -0.656989 0.0170055 0.753708 + outer loop + vertex 0.815395 1.5388 2.58152 + vertex 0.818095 1.5413 2.58382 + vertex 0.815455 1.5438 2.58146 + endloop + endfacet + facet normal -0.656741 0.0174609 0.753914 + outer loop + vertex 0.818095 1.5413 2.58382 + vertex 0.818157 1.54627 2.58376 + vertex 0.815455 1.5438 2.58146 + endloop + endfacet + facet normal -0.658399 0.0206863 0.752385 + outer loop + vertex 0.815455 1.5438 2.58146 + vertex 0.818157 1.54627 2.58376 + vertex 0.815533 1.54879 2.58139 + endloop + endfacet + facet normal -0.665869 0.0207105 0.745781 + outer loop + vertex 0.815533 1.54879 2.58139 + vertex 0.812858 1.54627 2.57907 + vertex 0.815455 1.5438 2.58146 + endloop + endfacet + facet normal -0.667594 0.0240588 0.744137 + outer loop + vertex 0.812949 1.55127 2.57899 + vertex 0.812858 1.54627 2.57907 + vertex 0.815533 1.54879 2.58139 + endloop + endfacet + facet normal -0.666947 0.0252523 0.744677 + outer loop + vertex 0.815629 1.55377 2.58131 + vertex 0.812949 1.55127 2.57899 + vertex 0.815533 1.54879 2.58139 + endloop + endfacet + facet normal -0.659231 0.0252183 0.751517 + outer loop + vertex 0.815533 1.54879 2.58139 + vertex 0.818237 1.55124 2.58368 + vertex 0.815629 1.55377 2.58131 + endloop + endfacet + facet normal -0.658458 0.0266064 0.752147 + outer loop + vertex 0.818237 1.55124 2.58368 + vertex 0.818337 1.5562 2.58359 + vertex 0.815629 1.55377 2.58131 + endloop + endfacet + facet normal -0.659415 0.02853 0.751237 + outer loop + vertex 0.815629 1.55377 2.58131 + vertex 0.818337 1.5562 2.58359 + vertex 0.815735 1.55875 2.58121 + endloop + endfacet + facet normal -0.667141 0.0285649 0.744384 + outer loop + vertex 0.815735 1.55875 2.58121 + vertex 0.813051 1.55627 2.5789 + vertex 0.815629 1.55377 2.58131 + endloop + endfacet + facet normal -0.66704 0.0283641 0.744482 + outer loop + vertex 0.813155 1.56126 2.5788 + vertex 0.813051 1.55627 2.5789 + vertex 0.815735 1.55875 2.58121 + endloop + endfacet + facet normal -0.666301 0.0297038 0.745091 + outer loop + vertex 0.815842 1.56371 2.58111 + vertex 0.813155 1.56126 2.5788 + vertex 0.815735 1.55875 2.58121 + endloop + endfacet + facet normal -0.658743 0.0296801 0.751783 + outer loop + vertex 0.815735 1.55875 2.58121 + vertex 0.818447 1.56115 2.58349 + vertex 0.815842 1.56371 2.58111 + endloop + endfacet + facet normal -0.658566 0.029992 0.751925 + outer loop + vertex 0.818447 1.56115 2.58349 + vertex 0.818551 1.56609 2.58339 + vertex 0.815842 1.56371 2.58111 + endloop + endfacet + facet normal -0.658585 0.0300301 0.751907 + outer loop + vertex 0.815842 1.56371 2.58111 + vertex 0.818551 1.56609 2.58339 + vertex 0.815944 1.56867 2.581 + endloop + endfacet + facet normal -0.665869 0.0300384 0.745464 + outer loop + vertex 0.815944 1.56867 2.581 + vertex 0.813258 1.56625 2.5787 + vertex 0.815842 1.56371 2.58111 + endloop + endfacet + facet normal -0.666275 0.0308655 0.745067 + outer loop + vertex 0.813365 1.57122 2.57859 + vertex 0.813258 1.56625 2.5787 + vertex 0.815944 1.56867 2.581 + endloop + endfacet + facet normal -0.665958 0.0314294 0.745327 + outer loop + vertex 0.816054 1.57363 2.58089 + vertex 0.813365 1.57122 2.57859 + vertex 0.815944 1.56867 2.581 + endloop + endfacet + facet normal -0.659277 0.0314137 0.751243 + outer loop + vertex 0.815944 1.56867 2.581 + vertex 0.818659 1.57105 2.58328 + vertex 0.816054 1.57363 2.58089 + endloop + endfacet + facet normal -0.658694 0.0324397 0.751711 + outer loop + vertex 0.818659 1.57105 2.58328 + vertex 0.818796 1.57607 2.58319 + vertex 0.816054 1.57363 2.58089 + endloop + endfacet + facet normal -0.65961 0.034301 0.750825 + outer loop + vertex 0.816054 1.57363 2.58089 + vertex 0.818796 1.57607 2.58319 + vertex 0.816182 1.57859 2.58078 + endloop + endfacet + facet normal -0.666965 0.0343399 0.744297 + outer loop + vertex 0.816182 1.57859 2.58078 + vertex 0.813486 1.57619 2.57847 + vertex 0.816054 1.57363 2.58089 + endloop + endfacet + facet normal -0.668673 0.0378953 0.74259 + outer loop + vertex 0.813623 1.58114 2.57834 + vertex 0.813486 1.57619 2.57847 + vertex 0.816182 1.57859 2.58078 + endloop + endfacet + facet normal -0.667992 0.0391053 0.743141 + outer loop + vertex 0.816321 1.58356 2.58064 + vertex 0.813623 1.58114 2.57834 + vertex 0.816182 1.57859 2.58078 + endloop + endfacet + facet normal -0.65998 0.0390751 0.750266 + outer loop + vertex 0.816182 1.57859 2.58078 + vertex 0.818947 1.58113 2.58308 + vertex 0.816321 1.58356 2.58064 + endloop + endfacet + facet normal -0.658879 0.0411258 0.751124 + outer loop + vertex 0.818947 1.58113 2.58308 + vertex 0.819083 1.58618 2.58292 + vertex 0.816321 1.58356 2.58064 + endloop + endfacet + facet normal -0.660046 0.0433572 0.749973 + outer loop + vertex 0.816321 1.58356 2.58064 + vertex 0.819083 1.58618 2.58292 + vertex 0.816459 1.58853 2.58047 + endloop + endfacet + facet normal -0.66866 0.0433382 0.742304 + outer loop + vertex 0.816459 1.58853 2.58047 + vertex 0.81376 1.58608 2.57819 + vertex 0.816321 1.58356 2.58064 + endloop + endfacet + facet normal -0.669553 0.0451774 0.741389 + outer loop + vertex 0.813892 1.59104 2.578 + vertex 0.81376 1.58608 2.57819 + vertex 0.816459 1.58853 2.58047 + endloop + endfacet + facet normal -0.668592 0.0469074 0.742149 + outer loop + vertex 0.816626 1.59357 2.58031 + vertex 0.813892 1.59104 2.578 + vertex 0.816459 1.58853 2.58047 + endloop + endfacet + facet normal -0.659911 0.0468771 0.74988 + outer loop + vertex 0.816459 1.58853 2.58047 + vertex 0.819221 1.5912 2.58274 + vertex 0.816626 1.59357 2.58031 + endloop + endfacet + facet normal -0.658793 0.0489776 0.750729 + outer loop + vertex 0.819221 1.5912 2.58274 + vertex 0.819474 1.59629 2.58263 + vertex 0.816626 1.59357 2.58031 + endloop + endfacet + facet normal -0.659158 0.049672 0.750362 + outer loop + vertex 0.816626 1.59357 2.58031 + vertex 0.819474 1.59629 2.58263 + vertex 0.816917 1.5988 2.58021 + endloop + endfacet + facet normal -0.668171 0.0500359 0.742324 + outer loop + vertex 0.816917 1.5988 2.58021 + vertex 0.814059 1.59608 2.57783 + vertex 0.816626 1.59357 2.58031 + endloop + endfacet + facet normal -0.668039 0.0497778 0.74246 + outer loop + vertex 0.8143 1.60121 2.5777 + vertex 0.814059 1.59608 2.57783 + vertex 0.816917 1.5988 2.58021 + endloop + endfacet + facet normal -0.667674 0.0504685 0.742741 + outer loop + vertex 0.817178 1.60408 2.58009 + vertex 0.8143 1.60121 2.5777 + vertex 0.816917 1.5988 2.58021 + endloop + endfacet + facet normal -0.656745 0.0501594 0.752443 + outer loop + vertex 0.816917 1.5988 2.58021 + vertex 0.820257 1.60202 2.58292 + vertex 0.817178 1.60408 2.58009 + endloop + endfacet + facet normal -0.657228 0.0489662 0.752099 + outer loop + vertex 0.820257 1.60202 2.58292 + vertex 0.819898 1.60735 2.58225 + vertex 0.817178 1.60408 2.58009 + endloop + endfacet + facet normal -0.657935 0.0500101 0.751412 + outer loop + vertex 0.817178 1.60408 2.58009 + vertex 0.819898 1.60735 2.58225 + vertex 0.817432 1.609 2.57999 + endloop + endfacet + facet normal -0.668517 0.050356 0.74199 + outer loop + vertex 0.817432 1.609 2.57999 + vertex 0.814636 1.60636 2.57765 + vertex 0.817178 1.60408 2.58009 + endloop + endfacet + facet normal -0.670445 0.0541741 0.739979 + outer loop + vertex 0.815185 1.6118 2.57774 + vertex 0.814636 1.60636 2.57765 + vertex 0.817432 1.609 2.57999 + endloop + endfacet + facet normal -0.67136 0.0528509 0.739244 + outer loop + vertex 0.817926 1.61271 2.58017 + vertex 0.815185 1.6118 2.57774 + vertex 0.817432 1.609 2.57999 + endloop + endfacet + facet normal -0.657776 0.0504296 0.751524 + outer loop + vertex 0.817432 1.609 2.57999 + vertex 0.819927 1.6118 2.58198 + vertex 0.817926 1.61271 2.58017 + endloop + endfacet + facet normal -0.656807 0.0537793 0.752138 + outer loop + vertex 0.81955 1.615 2.58142 + vertex 0.817926 1.61271 2.58017 + vertex 0.819927 1.6118 2.58198 + endloop + endfacet + facet normal -0.64837 0.0560093 0.759262 + outer loop + vertex 0.81955 1.615 2.58142 + vertex 0.819927 1.6118 2.58198 + vertex 0.822269 1.6157 2.58369 + endloop + endfacet + facet normal -0.649077 0.0623118 0.758167 + outer loop + vertex 0.81955 1.615 2.58142 + vertex 0.822269 1.6157 2.58369 + vertex 0.819984 1.61868 2.58149 + endloop + endfacet + facet normal -0.662263 0.0640882 0.746525 + outer loop + vertex 0.819984 1.61868 2.58149 + vertex 0.817428 1.61591 2.57946 + vertex 0.81955 1.615 2.58142 + endloop + endfacet + facet normal -0.663745 0.0665854 0.74499 + outer loop + vertex 0.817034 1.62075 2.57868 + vertex 0.817428 1.61591 2.57946 + vertex 0.819984 1.61868 2.58149 + endloop + endfacet + facet normal -0.66408 0.0657981 0.744761 + outer loop + vertex 0.820325 1.62349 2.58137 + vertex 0.817034 1.62075 2.57868 + vertex 0.819984 1.61868 2.58149 + endloop + endfacet + facet normal -0.652109 0.0652136 0.755315 + outer loop + vertex 0.819984 1.61868 2.58149 + vertex 0.822901 1.62105 2.58381 + vertex 0.820325 1.62349 2.58137 + endloop + endfacet + facet normal -0.651836 0.0656946 0.755509 + outer loop + vertex 0.822901 1.62105 2.58381 + vertex 0.823227 1.62601 2.58366 + vertex 0.820325 1.62349 2.58137 + endloop + endfacet + facet normal -0.652886 0.0678975 0.754407 + outer loop + vertex 0.820325 1.62349 2.58137 + vertex 0.823227 1.62601 2.58366 + vertex 0.820666 1.62846 2.58122 + endloop + endfacet + facet normal -0.662364 0.0682906 0.746063 + outer loop + vertex 0.820666 1.62846 2.58122 + vertex 0.817809 1.62599 2.57891 + vertex 0.820325 1.62349 2.58137 + endloop + endfacet + facet normal -0.663073 0.0698397 0.74529 + outer loop + vertex 0.81814 1.63094 2.57874 + vertex 0.817809 1.62599 2.57891 + vertex 0.820666 1.62846 2.58122 + endloop + endfacet + facet normal -0.662068 0.0715856 0.746017 + outer loop + vertex 0.820898 1.63344 2.58095 + vertex 0.81814 1.63094 2.57874 + vertex 0.820666 1.62846 2.58122 + endloop + endfacet + facet normal -0.652751 0.0715967 0.754181 + outer loop + vertex 0.820666 1.62846 2.58122 + vertex 0.823478 1.631 2.58341 + vertex 0.820898 1.63344 2.58095 + endloop + endfacet + facet normal -0.651902 0.0730914 0.754773 + outer loop + vertex 0.823478 1.631 2.58341 + vertex 0.823739 1.63611 2.58314 + vertex 0.820898 1.63344 2.58095 + endloop + endfacet + facet normal -0.652304 0.0738675 0.75435 + outer loop + vertex 0.820898 1.63344 2.58095 + vertex 0.823739 1.63611 2.58314 + vertex 0.821149 1.63853 2.58067 + endloop + endfacet + facet normal -0.661208 0.0738751 0.746557 + outer loop + vertex 0.821149 1.63853 2.58067 + vertex 0.818358 1.63595 2.57845 + vertex 0.820898 1.63344 2.58095 + endloop + endfacet + facet normal -0.661389 0.0742395 0.74636 + outer loop + vertex 0.818616 1.64102 2.57817 + vertex 0.818358 1.63595 2.57845 + vertex 0.821149 1.63853 2.58067 + endloop + endfacet + facet normal -0.660485 0.0758026 0.747003 + outer loop + vertex 0.821525 1.64378 2.58047 + vertex 0.818616 1.64102 2.57817 + vertex 0.821149 1.63853 2.58067 + endloop + endfacet + facet normal -0.652318 0.0754916 0.754177 + outer loop + vertex 0.821149 1.63853 2.58067 + vertex 0.824106 1.64138 2.58294 + vertex 0.821525 1.64378 2.58047 + endloop + endfacet + facet normal -0.652008 0.0760436 0.754389 + outer loop + vertex 0.824106 1.64138 2.58294 + vertex 0.824846 1.64712 2.583 + vertex 0.821525 1.64378 2.58047 + endloop + endfacet + facet normal -0.652671 0.0772291 0.753695 + outer loop + vertex 0.821525 1.64378 2.58047 + vertex 0.824846 1.64712 2.583 + vertex 0.821913 1.64903 2.58026 + endloop + endfacet + facet normal -0.660135 0.077527 0.747135 + outer loop + vertex 0.821913 1.64903 2.58026 + vertex 0.818967 1.64613 2.57796 + vertex 0.821525 1.64378 2.58047 + endloop + endfacet + facet normal -0.661311 0.0797315 0.745862 + outer loop + vertex 0.819434 1.65126 2.57783 + vertex 0.818967 1.64613 2.57796 + vertex 0.821913 1.64903 2.58026 + endloop + endfacet + facet normal -0.661201 0.0799358 0.745938 + outer loop + vertex 0.822315 1.65391 2.5801 + vertex 0.819434 1.65126 2.57783 + vertex 0.821913 1.64903 2.58026 + endloop + endfacet + facet normal -0.654382 0.0795774 0.751965 + outer loop + vertex 0.821913 1.64903 2.58026 + vertex 0.824754 1.65232 2.58239 + vertex 0.822315 1.65391 2.5801 + endloop + endfacet + facet normal -0.654082 0.0803012 0.752149 + outer loop + vertex 0.824754 1.65232 2.58239 + vertex 0.824886 1.65671 2.58203 + vertex 0.822315 1.65391 2.5801 + endloop + endfacet + facet normal -0.654846 0.0815585 0.751348 + outer loop + vertex 0.822315 1.65391 2.5801 + vertex 0.824886 1.65671 2.58203 + vertex 0.822894 1.65758 2.5802 + endloop + endfacet + facet normal -0.664141 0.0832655 0.742956 + outer loop + vertex 0.822894 1.65758 2.5802 + vertex 0.820117 1.65668 2.57782 + vertex 0.822315 1.65391 2.5801 + endloop + endfacet + facet normal -0.664699 0.0876429 0.741953 + outer loop + vertex 0.822894 1.65758 2.5802 + vertex 0.822442 1.66076 2.57942 + vertex 0.820117 1.65668 2.57782 + endloop + endfacet + facet normal -0.666585 0.0894717 0.74004 + outer loop + vertex 0.820117 1.65668 2.57782 + vertex 0.822442 1.66076 2.57942 + vertex 0.819568 1.66158 2.57673 + endloop + endfacet + facet normal -0.670956 0.0881388 0.73624 + outer loop + vertex 0.820117 1.65668 2.57782 + vertex 0.819568 1.66158 2.57673 + vertex 0.817016 1.65848 2.57478 + endloop + endfacet + facet normal -0.670886 0.0883304 0.736281 + outer loop + vertex 0.816954 1.65362 2.57531 + vertex 0.820117 1.65668 2.57782 + vertex 0.817016 1.65848 2.57478 + endloop + endfacet + facet normal -0.677466 0.0877669 0.730299 + outer loop + vertex 0.817016 1.65848 2.57478 + vertex 0.814353 1.65591 2.57262 + vertex 0.816954 1.65362 2.57531 + endloop + endfacet + facet normal -0.679162 0.091204 0.7283 + outer loop + vertex 0.814175 1.66055 2.57187 + vertex 0.814353 1.65591 2.57262 + vertex 0.817016 1.65848 2.57478 + endloop + endfacet + facet normal -0.669235 0.0850864 0.738163 + outer loop + vertex 0.819434 1.65126 2.57783 + vertex 0.820117 1.65668 2.57782 + vertex 0.816954 1.65362 2.57531 + endloop + endfacet + facet normal -0.670168 0.0834031 0.737508 + outer loop + vertex 0.816542 1.64858 2.5755 + vertex 0.819434 1.65126 2.57783 + vertex 0.816954 1.65362 2.57531 + endloop + endfacet + facet normal -0.677079 0.0837207 0.731133 + outer loop + vertex 0.816954 1.65362 2.57531 + vertex 0.814149 1.65106 2.573 + vertex 0.816542 1.64858 2.5755 + endloop + endfacet + facet normal -0.679085 0.0803046 0.729654 + outer loop + vertex 0.814149 1.65106 2.573 + vertex 0.813776 1.6461 2.5732 + vertex 0.816542 1.64858 2.5755 + endloop + endfacet + facet normal -0.678195 0.0783484 0.730694 + outer loop + vertex 0.816542 1.64858 2.5755 + vertex 0.813776 1.6461 2.5732 + vertex 0.816154 1.64354 2.57568 + endloop + endfacet + facet normal -0.669929 0.077985 0.738318 + outer loop + vertex 0.816154 1.64354 2.57568 + vertex 0.818967 1.64613 2.57796 + vertex 0.816542 1.64858 2.5755 + endloop + endfacet + facet normal -0.669273 0.0766269 0.739054 + outer loop + vertex 0.818616 1.64102 2.57817 + vertex 0.818967 1.64613 2.57796 + vertex 0.816154 1.64354 2.57568 + endloop + endfacet + facet normal -0.670714 0.0741757 0.737998 + outer loop + vertex 0.81586 1.6385 2.57592 + vertex 0.818616 1.64102 2.57817 + vertex 0.816154 1.64354 2.57568 + endloop + endfacet + facet normal -0.680284 0.0743153 0.729171 + outer loop + vertex 0.816154 1.64354 2.57568 + vertex 0.813429 1.64108 2.57339 + vertex 0.81586 1.6385 2.57592 + endloop + endfacet + facet normal -0.681971 0.0714575 0.72788 + outer loop + vertex 0.813429 1.64108 2.57339 + vertex 0.813157 1.63602 2.57363 + vertex 0.81586 1.6385 2.57592 + endloop + endfacet + facet normal -0.682131 0.0718012 0.727696 + outer loop + vertex 0.81586 1.6385 2.57592 + vertex 0.813157 1.63602 2.57363 + vertex 0.815639 1.63346 2.57621 + endloop + endfacet + facet normal -0.672138 0.071893 0.736927 + outer loop + vertex 0.815639 1.63346 2.57621 + vertex 0.818358 1.63595 2.57845 + vertex 0.81586 1.6385 2.57592 + endloop + endfacet + facet normal -0.672159 0.0719366 0.736904 + outer loop + vertex 0.81814 1.63094 2.57874 + vertex 0.818358 1.63595 2.57845 + vertex 0.815639 1.63346 2.57621 + endloop + endfacet + facet normal -0.672915 0.070622 0.736341 + outer loop + vertex 0.815425 1.62855 2.57649 + vertex 0.81814 1.63094 2.57874 + vertex 0.815639 1.63346 2.57621 + endloop + endfacet + facet normal -0.683265 0.0705338 0.726756 + outer loop + vertex 0.815639 1.63346 2.57621 + vertex 0.812983 1.63097 2.57396 + vertex 0.815425 1.62855 2.57649 + endloop + endfacet + facet normal -0.683318 0.0704378 0.726715 + outer loop + vertex 0.812983 1.63097 2.57396 + vertex 0.81294 1.62627 2.57437 + vertex 0.815425 1.62855 2.57649 + endloop + endfacet + facet normal -0.683182 0.070144 0.726871 + outer loop + vertex 0.815425 1.62855 2.57649 + vertex 0.81294 1.62627 2.57437 + vertex 0.815024 1.62415 2.57654 + endloop + endfacet + facet normal -0.673229 0.0693409 0.736176 + outer loop + vertex 0.815024 1.62415 2.57654 + vertex 0.817809 1.62599 2.57891 + vertex 0.815425 1.62855 2.57649 + endloop + endfacet + facet normal -0.672504 0.0671366 0.737042 + outer loop + vertex 0.817034 1.62075 2.57868 + vertex 0.817809 1.62599 2.57891 + vertex 0.815024 1.62415 2.57654 + endloop + endfacet + facet normal -0.676774 0.062402 0.733541 + outer loop + vertex 0.813702 1.62087 2.5756 + vertex 0.817034 1.62075 2.57868 + vertex 0.815024 1.62415 2.57654 + endloop + endfacet + facet normal -0.681736 0.0658085 0.728633 + outer loop + vertex 0.815024 1.62415 2.57654 + vertex 0.81311 1.62339 2.57481 + vertex 0.813702 1.62087 2.5756 + endloop + endfacet + facet normal -0.676537 0.0662071 0.733427 + outer loop + vertex 0.813702 1.62087 2.5756 + vertex 0.814546 1.61673 2.57675 + vertex 0.817034 1.62075 2.57868 + endloop + endfacet + facet normal -0.682625 0.0711256 0.727299 + outer loop + vertex 0.81294 1.62627 2.57437 + vertex 0.81311 1.62339 2.57481 + vertex 0.815024 1.62415 2.57654 + endloop + endfacet + facet normal -0.68308 0.0701451 0.726968 + outer loop + vertex 0.813157 1.63602 2.57363 + vertex 0.812983 1.63097 2.57396 + vertex 0.815639 1.63346 2.57621 + endloop + endfacet + facet normal -0.673509 0.0920116 0.73343 + outer loop + vertex 0.817016 1.65848 2.57478 + vertex 0.819568 1.66158 2.57673 + vertex 0.816555 1.66306 2.57378 + endloop + endfacet + facet normal -0.666293 0.0908071 0.74014 + outer loop + vertex 0.819568 1.66158 2.57673 + vertex 0.822442 1.66076 2.57942 + vertex 0.822101 1.66555 2.57853 + endloop + endfacet + facet normal -0.667652 0.0923155 0.738728 + outer loop + vertex 0.818774 1.6657 2.5755 + vertex 0.819568 1.66158 2.57673 + vertex 0.822101 1.66555 2.57853 + endloop + endfacet + facet normal -0.668001 0.0882391 0.738911 + outer loop + vertex 0.818774 1.6657 2.5755 + vertex 0.822101 1.66555 2.57853 + vertex 0.820114 1.66891 2.57633 + endloop + endfacet + facet normal -0.664556 0.0919988 0.741554 + outer loop + vertex 0.822101 1.66555 2.57853 + vertex 0.822925 1.67079 2.57862 + vertex 0.820114 1.66891 2.57633 + endloop + endfacet + facet normal -0.664956 0.0932254 0.741042 + outer loop + vertex 0.820114 1.66891 2.57633 + vertex 0.822925 1.67079 2.57862 + vertex 0.820539 1.67332 2.57616 + endloop + endfacet + facet normal -0.67183 0.0936423 0.734762 + outer loop + vertex 0.820539 1.67332 2.57616 + vertex 0.818023 1.67103 2.57415 + vertex 0.820114 1.66891 2.57633 + endloop + endfacet + facet normal -0.672618 0.095335 0.733823 + outer loop + vertex 0.818111 1.67575 2.57362 + vertex 0.818023 1.67103 2.57415 + vertex 0.820539 1.67332 2.57616 + endloop + endfacet + facet normal -0.671926 0.096526 0.734301 + outer loop + vertex 0.820898 1.6784 2.57582 + vertex 0.818111 1.67575 2.57362 + vertex 0.820539 1.67332 2.57616 + endloop + endfacet + facet normal -0.664444 0.0964498 0.741088 + outer loop + vertex 0.820539 1.67332 2.57616 + vertex 0.823383 1.6759 2.57837 + vertex 0.820898 1.6784 2.57582 + endloop + endfacet + facet normal -0.663325 0.0983309 0.741843 + outer loop + vertex 0.823383 1.6759 2.57837 + vertex 0.823906 1.68128 2.57813 + vertex 0.820898 1.6784 2.57582 + endloop + endfacet + facet normal -0.66389 0.0994454 0.741189 + outer loop + vertex 0.820898 1.6784 2.57582 + vertex 0.823906 1.68128 2.57813 + vertex 0.821459 1.68379 2.5756 + endloop + endfacet + facet normal -0.671792 0.0999718 0.733963 + outer loop + vertex 0.821459 1.68379 2.5756 + vertex 0.818475 1.68094 2.57325 + vertex 0.820898 1.6784 2.57582 + endloop + endfacet + facet normal -0.672749 0.101918 0.732818 + outer loop + vertex 0.819088 1.68627 2.57308 + vertex 0.818475 1.68094 2.57325 + vertex 0.821459 1.68379 2.5756 + endloop + endfacet + facet normal -0.67262 0.102132 0.732907 + outer loop + vertex 0.822078 1.68898 2.57544 + vertex 0.819088 1.68627 2.57308 + vertex 0.821459 1.68379 2.5756 + endloop + endfacet + facet normal -0.663294 0.101277 0.741474 + outer loop + vertex 0.821459 1.68379 2.5756 + vertex 0.824785 1.68708 2.57812 + vertex 0.822078 1.68898 2.57544 + endloop + endfacet + facet normal -0.663813 0.100111 0.741168 + outer loop + vertex 0.824785 1.68708 2.57812 + vertex 0.824698 1.69195 2.57739 + vertex 0.822078 1.68898 2.57544 + endloop + endfacet + facet normal -0.664205 0.100744 0.740731 + outer loop + vertex 0.822078 1.68898 2.57544 + vertex 0.824698 1.69195 2.57739 + vertex 0.82269 1.69285 2.57546 + endloop + endfacet + facet normal -0.674101 0.102366 0.731511 + outer loop + vertex 0.82269 1.69285 2.57546 + vertex 0.819908 1.69187 2.57304 + vertex 0.822078 1.68898 2.57544 + endloop + endfacet + facet normal -0.674111 0.10244 0.731492 + outer loop + vertex 0.82269 1.69285 2.57546 + vertex 0.822262 1.69603 2.57462 + vertex 0.819908 1.69187 2.57304 + endloop + endfacet + facet normal -0.676409 0.104673 0.72905 + outer loop + vertex 0.819908 1.69187 2.57304 + vertex 0.822262 1.69603 2.57462 + vertex 0.819433 1.69681 2.57189 + endloop + endfacet + facet normal -0.68301 0.102666 0.723158 + outer loop + vertex 0.819908 1.69187 2.57304 + vertex 0.819433 1.69681 2.57189 + vertex 0.816875 1.69362 2.56993 + endloop + endfacet + facet normal -0.681637 0.106396 0.723913 + outer loop + vertex 0.8167 1.68869 2.57048 + vertex 0.819908 1.69187 2.57304 + vertex 0.816875 1.69362 2.56993 + endloop + endfacet + facet normal -0.688133 0.105935 0.71781 + outer loop + vertex 0.816875 1.69362 2.56993 + vertex 0.814195 1.69095 2.56775 + vertex 0.8167 1.68869 2.57048 + endloop + endfacet + facet normal -0.689235 0.108172 0.716417 + outer loop + vertex 0.814105 1.69558 2.56696 + vertex 0.814195 1.69095 2.56775 + vertex 0.816875 1.69362 2.56993 + endloop + endfacet + facet normal -0.680716 0.104558 0.725047 + outer loop + vertex 0.819088 1.68627 2.57308 + vertex 0.819908 1.69187 2.57304 + vertex 0.8167 1.68869 2.57048 + endloop + endfacet + facet normal -0.680726 0.104542 0.72504 + outer loop + vertex 0.816138 1.68352 2.5707 + vertex 0.819088 1.68627 2.57308 + vertex 0.8167 1.68869 2.57048 + endloop + endfacet + facet normal -0.686547 0.10494 0.719472 + outer loop + vertex 0.8167 1.68869 2.57048 + vertex 0.813843 1.68606 2.56814 + vertex 0.816138 1.68352 2.5707 + endloop + endfacet + facet normal -0.687452 0.103467 0.718822 + outer loop + vertex 0.813843 1.68606 2.56814 + vertex 0.813323 1.68098 2.56838 + vertex 0.816138 1.68352 2.5707 + endloop + endfacet + facet normal -0.686465 0.101219 0.720083 + outer loop + vertex 0.816138 1.68352 2.5707 + vertex 0.813323 1.68098 2.56838 + vertex 0.81567 1.67831 2.57099 + endloop + endfacet + facet normal -0.680709 0.101002 0.725558 + outer loop + vertex 0.81567 1.67831 2.57099 + vertex 0.818475 1.68094 2.57325 + vertex 0.816138 1.68352 2.5707 + endloop + endfacet + facet normal -0.679455 0.0983397 0.727097 + outer loop + vertex 0.818111 1.67575 2.57362 + vertex 0.818475 1.68094 2.57325 + vertex 0.81567 1.67831 2.57099 + endloop + endfacet + facet normal -0.680522 0.0965455 0.726339 + outer loop + vertex 0.81553 1.67319 2.57154 + vertex 0.818111 1.67575 2.57362 + vertex 0.81567 1.67831 2.57099 + endloop + endfacet + facet normal -0.68661 0.0960993 0.720647 + outer loop + vertex 0.81567 1.67831 2.57099 + vertex 0.812991 1.67585 2.56876 + vertex 0.81553 1.67319 2.57154 + endloop + endfacet + facet normal -0.684798 0.105386 0.721073 + outer loop + vertex 0.816875 1.69362 2.56993 + vertex 0.819433 1.69681 2.57189 + vertex 0.816486 1.69819 2.56889 + endloop + endfacet + facet normal -0.676806 0.102845 0.728942 + outer loop + vertex 0.819433 1.69681 2.57189 + vertex 0.822262 1.69603 2.57462 + vertex 0.821961 1.70074 2.57368 + endloop + endfacet + facet normal -0.66688 0.105235 0.737697 + outer loop + vertex 0.821961 1.70074 2.57368 + vertex 0.822262 1.69603 2.57462 + vertex 0.824839 1.69872 2.57657 + endloop + endfacet + facet normal -0.666751 0.105526 0.737772 + outer loop + vertex 0.825261 1.70339 2.57628 + vertex 0.821961 1.70074 2.57368 + vertex 0.824839 1.69872 2.57657 + endloop + endfacet + facet normal -0.656432 0.105158 0.74702 + outer loop + vertex 0.824839 1.69872 2.57657 + vertex 0.827767 1.70101 2.57882 + vertex 0.825261 1.70339 2.57628 + endloop + endfacet + facet normal -0.655429 0.106886 0.747655 + outer loop + vertex 0.827767 1.70101 2.57882 + vertex 0.828262 1.70597 2.57855 + vertex 0.825261 1.70339 2.57628 + endloop + endfacet + facet normal -0.655911 0.107956 0.747078 + outer loop + vertex 0.825261 1.70339 2.57628 + vertex 0.828262 1.70597 2.57855 + vertex 0.825764 1.70839 2.576 + endloop + endfacet + facet normal -0.663378 0.108332 0.740401 + outer loop + vertex 0.825764 1.70839 2.576 + vertex 0.822805 1.70585 2.57372 + vertex 0.825261 1.70339 2.57628 + endloop + endfacet + facet normal -0.663967 0.109668 0.739676 + outer loop + vertex 0.823304 1.71086 2.57343 + vertex 0.822805 1.70585 2.57372 + vertex 0.825764 1.70839 2.576 + endloop + endfacet + facet normal -0.662293 0.112465 0.740756 + outer loop + vertex 0.826327 1.71367 2.5757 + vertex 0.823304 1.71086 2.57343 + vertex 0.825764 1.70839 2.576 + endloop + endfacet + facet normal -0.655045 0.112059 0.747234 + outer loop + vertex 0.825764 1.70839 2.576 + vertex 0.828816 1.71119 2.57826 + vertex 0.826327 1.71367 2.5757 + endloop + endfacet + facet normal -0.654811 0.112445 0.747381 + outer loop + vertex 0.828816 1.71119 2.57826 + vertex 0.829681 1.71691 2.57816 + vertex 0.826327 1.71367 2.5757 + endloop + endfacet + facet normal -0.654358 0.111578 0.747907 + outer loop + vertex 0.826327 1.71367 2.5757 + vertex 0.829681 1.71691 2.57816 + vertex 0.826909 1.71891 2.57543 + endloop + endfacet + facet normal -0.661894 0.11165 0.741236 + outer loop + vertex 0.823879 1.71619 2.57314 + vertex 0.823304 1.71086 2.57343 + vertex 0.826327 1.71367 2.5757 + endloop + endfacet + facet normal -0.654338 0.110617 0.748068 + outer loop + vertex 0.828262 1.70597 2.57855 + vertex 0.828816 1.71119 2.57826 + vertex 0.825764 1.70839 2.576 + endloop + endfacet + facet normal -0.648123 0.110259 0.753511 + outer loop + vertex 0.828816 1.71119 2.57826 + vertex 0.828262 1.70597 2.57855 + vertex 0.831321 1.70871 2.58078 + endloop + endfacet + facet normal -0.647742 0.110884 0.753747 + outer loop + vertex 0.831873 1.71387 2.58049 + vertex 0.828816 1.71119 2.57826 + vertex 0.831321 1.70871 2.58078 + endloop + endfacet + facet normal -0.640748 0.110468 0.759762 + outer loop + vertex 0.831321 1.70871 2.58078 + vertex 0.834687 1.7119 2.58315 + vertex 0.831873 1.71387 2.58049 + endloop + endfacet + facet normal -0.640088 0.109219 0.760499 + outer loop + vertex 0.833849 1.70628 2.58325 + vertex 0.834687 1.7119 2.58315 + vertex 0.831321 1.70871 2.58078 + endloop + endfacet + facet normal -0.640823 0.108002 0.760054 + outer loop + vertex 0.830775 1.70354 2.58105 + vertex 0.833849 1.70628 2.58325 + vertex 0.831321 1.70871 2.58078 + endloop + endfacet + facet normal -0.639741 0.10581 0.761272 + outer loop + vertex 0.833325 1.70113 2.58353 + vertex 0.833849 1.70628 2.58325 + vertex 0.830775 1.70354 2.58105 + endloop + endfacet + facet normal -0.640505 0.104525 0.760808 + outer loop + vertex 0.830265 1.69859 2.5813 + vertex 0.833325 1.70113 2.58353 + vertex 0.830775 1.70354 2.58105 + endloop + endfacet + facet normal -0.647613 0.104947 0.754708 + outer loop + vertex 0.830775 1.70354 2.58105 + vertex 0.827767 1.70101 2.57882 + vertex 0.830265 1.69859 2.5813 + endloop + endfacet + facet normal -0.648481 0.103493 0.754163 + outer loop + vertex 0.827767 1.70101 2.57882 + vertex 0.827029 1.69587 2.57889 + vertex 0.830265 1.69859 2.5813 + endloop + endfacet + facet normal -0.648365 0.103236 0.754298 + outer loop + vertex 0.830265 1.69859 2.5813 + vertex 0.827029 1.69587 2.57889 + vertex 0.829786 1.6939 2.58153 + endloop + endfacet + facet normal -0.64021 0.102745 0.761298 + outer loop + vertex 0.829786 1.6939 2.58153 + vertex 0.832801 1.69612 2.58377 + vertex 0.830265 1.69859 2.5813 + endloop + endfacet + facet normal -0.639833 0.101786 0.761744 + outer loop + vertex 0.832002 1.69086 2.5838 + vertex 0.832801 1.69612 2.58377 + vertex 0.829786 1.6939 2.58153 + endloop + endfacet + facet normal -0.639527 0.102164 0.76195 + outer loop + vertex 0.829238 1.69029 2.58156 + vertex 0.832002 1.69086 2.5838 + vertex 0.829786 1.6939 2.58153 + endloop + endfacet + facet normal -0.647784 0.10337 0.754779 + outer loop + vertex 0.829786 1.6939 2.58153 + vertex 0.827188 1.69127 2.57966 + vertex 0.829238 1.69029 2.58156 + endloop + endfacet + facet normal -0.648113 0.102396 0.754629 + outer loop + vertex 0.827534 1.688 2.5804 + vertex 0.829238 1.69029 2.58156 + vertex 0.827188 1.69127 2.57966 + endloop + endfacet + facet normal -0.654794 0.100441 0.749104 + outer loop + vertex 0.827534 1.688 2.5804 + vertex 0.827188 1.69127 2.57966 + vertex 0.824785 1.68708 2.57812 + endloop + endfacet + facet normal -0.654669 0.0994841 0.74934 + outer loop + vertex 0.827534 1.688 2.5804 + vertex 0.824785 1.68708 2.57812 + vertex 0.826951 1.68403 2.58042 + endloop + endfacet + facet normal -0.645673 0.0982013 0.757273 + outer loop + vertex 0.826951 1.68403 2.58042 + vertex 0.829606 1.68694 2.58231 + vertex 0.827534 1.688 2.5804 + endloop + endfacet + facet normal -0.645588 0.0980653 0.757363 + outer loop + vertex 0.829781 1.68198 2.5831 + vertex 0.829606 1.68694 2.58231 + vertex 0.826951 1.68403 2.58042 + endloop + endfacet + facet normal -0.645405 0.0984557 0.757468 + outer loop + vertex 0.826423 1.67877 2.58065 + vertex 0.829781 1.68198 2.5831 + vertex 0.826951 1.68403 2.58042 + endloop + endfacet + facet normal -0.654359 0.0990093 0.749674 + outer loop + vertex 0.826951 1.68403 2.58042 + vertex 0.823906 1.68128 2.57813 + vertex 0.826423 1.67877 2.58065 + endloop + endfacet + facet normal -0.645756 0.0991146 0.757084 + outer loop + vertex 0.828971 1.67627 2.58316 + vertex 0.829781 1.68198 2.5831 + vertex 0.826423 1.67877 2.58065 + endloop + endfacet + facet normal -0.646959 0.0971205 0.756315 + outer loop + vertex 0.825911 1.67344 2.5809 + vertex 0.828971 1.67627 2.58316 + vertex 0.826423 1.67877 2.58065 + endloop + endfacet + facet normal -0.654895 0.0975633 0.749396 + outer loop + vertex 0.826423 1.67877 2.58065 + vertex 0.823383 1.6759 2.57837 + vertex 0.825911 1.67344 2.5809 + endloop + endfacet + facet normal -0.656546 0.0947548 0.748311 + outer loop + vertex 0.823383 1.6759 2.57837 + vertex 0.822925 1.67079 2.57862 + vertex 0.825911 1.67344 2.5809 + endloop + endfacet + facet normal -0.656337 0.0943125 0.74855 + outer loop + vertex 0.825911 1.67344 2.5809 + vertex 0.822925 1.67079 2.57862 + vertex 0.825437 1.66831 2.58113 + endloop + endfacet + facet normal -0.648431 0.0938917 0.755461 + outer loop + vertex 0.825437 1.66831 2.58113 + vertex 0.828461 1.67101 2.58339 + vertex 0.825911 1.67344 2.5809 + endloop + endfacet + facet normal -0.648167 0.0933504 0.755754 + outer loop + vertex 0.827997 1.66592 2.58362 + vertex 0.828461 1.67101 2.58339 + vertex 0.825437 1.66831 2.58113 + endloop + endfacet + facet normal -0.649044 0.0918225 0.755189 + outer loop + vertex 0.825034 1.6635 2.58137 + vertex 0.827997 1.66592 2.58362 + vertex 0.825437 1.66831 2.58113 + endloop + endfacet + facet normal -0.658896 0.0922198 0.74656 + outer loop + vertex 0.825437 1.66831 2.58113 + vertex 0.822101 1.66555 2.57853 + vertex 0.825034 1.6635 2.58137 + endloop + endfacet + facet normal -0.647953 0.0893447 0.756422 + outer loop + vertex 0.827285 1.6606 2.58364 + vertex 0.827997 1.66592 2.58362 + vertex 0.825034 1.6635 2.58137 + endloop + endfacet + facet normal -0.647417 0.0900545 0.756797 + outer loop + vertex 0.824558 1.65986 2.5814 + vertex 0.827285 1.6606 2.58364 + vertex 0.825034 1.6635 2.58137 + endloop + endfacet + facet normal -0.658061 0.0913804 0.747399 + outer loop + vertex 0.825034 1.6635 2.58137 + vertex 0.822442 1.66076 2.57942 + vertex 0.824558 1.65986 2.5814 + endloop + endfacet + facet normal -0.64701 0.086086 0.757606 + outer loop + vertex 0.824558 1.65986 2.5814 + vertex 0.824886 1.65671 2.58203 + vertex 0.827285 1.6606 2.58364 + endloop + endfacet + facet normal -0.64534 0.0843904 0.75922 + outer loop + vertex 0.824886 1.65671 2.58203 + vertex 0.827417 1.65567 2.5843 + vertex 0.827285 1.6606 2.58364 + endloop + endfacet + facet normal -0.639115 0.0852483 0.764372 + outer loop + vertex 0.827285 1.6606 2.58364 + vertex 0.827417 1.65567 2.5843 + vertex 0.83025 1.65859 2.58634 + endloop + endfacet + facet normal -0.638692 0.0862031 0.764618 + outer loop + vertex 0.830583 1.66351 2.58607 + vertex 0.827285 1.6606 2.58364 + vertex 0.83025 1.65859 2.58634 + endloop + endfacet + facet normal -0.62997 0.0860177 0.771841 + outer loop + vertex 0.83025 1.65859 2.58634 + vertex 0.833265 1.66114 2.58852 + vertex 0.830583 1.66351 2.58607 + endloop + endfacet + facet normal -0.628937 0.0878439 0.772478 + outer loop + vertex 0.833265 1.66114 2.58852 + vertex 0.83363 1.66614 2.58825 + vertex 0.830583 1.66351 2.58607 + endloop + endfacet + facet normal -0.630162 0.0903359 0.771191 + outer loop + vertex 0.830583 1.66351 2.58607 + vertex 0.83363 1.66614 2.58825 + vertex 0.831021 1.66857 2.58583 + endloop + endfacet + facet normal -0.638284 0.0907238 0.764436 + outer loop + vertex 0.831021 1.66857 2.58583 + vertex 0.827997 1.66592 2.58362 + vertex 0.830583 1.66351 2.58607 + endloop + endfacet + facet normal -0.628693 0.092809 0.772096 + outer loop + vertex 0.83363 1.66614 2.58825 + vertex 0.834082 1.67126 2.588 + vertex 0.831021 1.66857 2.58583 + endloop + endfacet + facet normal -0.629625 0.0946638 0.77111 + outer loop + vertex 0.831021 1.66857 2.58583 + vertex 0.834082 1.67126 2.588 + vertex 0.83152 1.67376 2.5856 + endloop + endfacet + facet normal -0.637986 0.0951622 0.764146 + outer loop + vertex 0.83152 1.67376 2.5856 + vertex 0.828461 1.67101 2.58339 + vertex 0.831021 1.66857 2.58583 + endloop + endfacet + facet normal -0.638537 0.0962573 0.763547 + outer loop + vertex 0.828971 1.67627 2.58316 + vertex 0.828461 1.67101 2.58339 + vertex 0.83152 1.67376 2.5856 + endloop + endfacet + facet normal -0.637695 0.0976289 0.764077 + outer loop + vertex 0.832024 1.67887 2.58537 + vertex 0.828971 1.67627 2.58316 + vertex 0.83152 1.67376 2.5856 + endloop + endfacet + facet normal -0.629085 0.0971068 0.771247 + outer loop + vertex 0.83152 1.67376 2.5856 + vertex 0.834866 1.67678 2.58795 + vertex 0.832024 1.67887 2.58537 + endloop + endfacet + facet normal -0.629242 0.0967848 0.77116 + outer loop + vertex 0.834866 1.67678 2.58795 + vertex 0.834692 1.68167 2.5872 + vertex 0.832024 1.67887 2.58537 + endloop + endfacet + facet normal -0.629316 0.0969042 0.771084 + outer loop + vertex 0.832024 1.67887 2.58537 + vertex 0.834692 1.68167 2.5872 + vertex 0.832581 1.68277 2.58534 + endloop + endfacet + facet normal -0.637906 0.0980662 0.763845 + outer loop + vertex 0.832581 1.68277 2.58534 + vertex 0.829781 1.68198 2.5831 + vertex 0.832024 1.67887 2.58537 + endloop + endfacet + facet normal -0.62048 0.098165 0.778054 + outer loop + vertex 0.834866 1.67678 2.58795 + vertex 0.837318 1.68082 2.5894 + vertex 0.834692 1.68167 2.5872 + endloop + endfacet + facet normal -0.620164 0.0993894 0.778151 + outer loop + vertex 0.834692 1.68167 2.5872 + vertex 0.837318 1.68082 2.5894 + vertex 0.837158 1.68566 2.58865 + endloop + endfacet + facet normal -0.62041 0.0996241 0.777924 + outer loop + vertex 0.834302 1.68503 2.58646 + vertex 0.834692 1.68167 2.5872 + vertex 0.837158 1.68566 2.58865 + endloop + endfacet + facet normal -0.620374 0.099157 0.778013 + outer loop + vertex 0.834302 1.68503 2.58646 + vertex 0.837158 1.68566 2.58865 + vertex 0.834858 1.68874 2.58643 + endloop + endfacet + facet normal -0.631517 0.100748 0.768789 + outer loop + vertex 0.834858 1.68874 2.58643 + vertex 0.832192 1.68611 2.58458 + vertex 0.834302 1.68503 2.58646 + endloop + endfacet + facet normal -0.63172 0.100187 0.768695 + outer loop + vertex 0.832581 1.68277 2.58534 + vertex 0.834302 1.68503 2.58646 + vertex 0.832192 1.68611 2.58458 + endloop + endfacet + facet normal -0.637937 0.0983509 0.763783 + outer loop + vertex 0.832581 1.68277 2.58534 + vertex 0.832192 1.68611 2.58458 + vertex 0.829781 1.68198 2.5831 + endloop + endfacet + facet normal -0.631738 0.101133 0.768557 + outer loop + vertex 0.832002 1.69086 2.5838 + vertex 0.832192 1.68611 2.58458 + vertex 0.834858 1.68874 2.58643 + endloop + endfacet + facet normal -0.631995 0.100608 0.768414 + outer loop + vertex 0.835383 1.69362 2.58622 + vertex 0.832002 1.69086 2.5838 + vertex 0.834858 1.68874 2.58643 + endloop + endfacet + facet normal -0.619724 0.0997117 0.77846 + outer loop + vertex 0.834858 1.68874 2.58643 + vertex 0.838015 1.69113 2.58863 + vertex 0.835383 1.69362 2.58622 + endloop + endfacet + facet normal -0.618913 0.10103 0.778935 + outer loop + vertex 0.838015 1.69113 2.58863 + vertex 0.838632 1.69635 2.58845 + vertex 0.835383 1.69362 2.58622 + endloop + endfacet + facet normal -0.619095 0.101404 0.778742 + outer loop + vertex 0.835383 1.69362 2.58622 + vertex 0.838632 1.69635 2.58845 + vertex 0.835983 1.69878 2.58602 + endloop + endfacet + facet normal -0.630918 0.102413 0.769061 + outer loop + vertex 0.835983 1.69878 2.58602 + vertex 0.832801 1.69612 2.58377 + vertex 0.835383 1.69362 2.58622 + endloop + endfacet + facet normal -0.63103 0.102653 0.768937 + outer loop + vertex 0.833325 1.70113 2.58353 + vertex 0.832801 1.69612 2.58377 + vertex 0.835983 1.69878 2.58602 + endloop + endfacet + facet normal -0.630184 0.104134 0.769431 + outer loop + vertex 0.83644 1.70398 2.58569 + vertex 0.833325 1.70113 2.58353 + vertex 0.835983 1.69878 2.58602 + endloop + endfacet + facet normal -0.617054 0.103654 0.780064 + outer loop + vertex 0.835983 1.69878 2.58602 + vertex 0.839492 1.702 2.58837 + vertex 0.83644 1.70398 2.58569 + endloop + endfacet + facet normal -0.61681 0.104195 0.780186 + outer loop + vertex 0.839492 1.702 2.58837 + vertex 0.83942 1.70722 2.58762 + vertex 0.83644 1.70398 2.58569 + endloop + endfacet + facet normal -0.617343 0.105 0.779656 + outer loop + vertex 0.83644 1.70398 2.58569 + vertex 0.83942 1.70722 2.58762 + vertex 0.836866 1.70895 2.58536 + endloop + endfacet + facet normal -0.630723 0.105424 0.768814 + outer loop + vertex 0.836866 1.70895 2.58536 + vertex 0.833849 1.70628 2.58325 + vertex 0.83644 1.70398 2.58569 + endloop + endfacet + facet normal -0.61738 0.104255 0.779726 + outer loop + vertex 0.838632 1.69635 2.58845 + vertex 0.839492 1.702 2.58837 + vertex 0.835983 1.69878 2.58602 + endloop + endfacet + facet normal -0.63865 0.0999394 0.76298 + outer loop + vertex 0.829606 1.68694 2.58231 + vertex 0.832192 1.68611 2.58458 + vertex 0.832002 1.69086 2.5838 + endloop + endfacet + facet normal -0.619789 0.0998646 0.778388 + outer loop + vertex 0.837158 1.68566 2.58865 + vertex 0.838015 1.69113 2.58863 + vertex 0.834858 1.68874 2.58643 + endloop + endfacet + facet normal -0.629245 0.0970974 0.771118 + outer loop + vertex 0.834302 1.68503 2.58646 + vertex 0.832581 1.68277 2.58534 + vertex 0.834692 1.68167 2.5872 + endloop + endfacet + facet normal -0.619786 0.0975163 0.778688 + outer loop + vertex 0.837677 1.67749 2.5901 + vertex 0.837318 1.68082 2.5894 + vertex 0.834866 1.67678 2.58795 + endloop + endfacet + facet normal -0.619634 0.0959596 0.779003 + outer loop + vertex 0.837677 1.67749 2.5901 + vertex 0.834866 1.67678 2.58795 + vertex 0.83708 1.67376 2.59009 + endloop + endfacet + facet normal -0.605753 0.0936933 0.790117 + outer loop + vertex 0.83708 1.67376 2.59009 + vertex 0.839804 1.67646 2.59185 + vertex 0.837677 1.67749 2.5901 + endloop + endfacet + facet normal -0.604874 0.0961425 0.790496 + outer loop + vertex 0.839475 1.67976 2.5912 + vertex 0.837677 1.67749 2.5901 + vertex 0.839804 1.67646 2.59185 + endloop + endfacet + facet normal -0.591692 0.0993344 0.800021 + outer loop + vertex 0.839475 1.67976 2.5912 + vertex 0.839804 1.67646 2.59185 + vertex 0.842506 1.68059 2.59334 + endloop + endfacet + facet normal -0.59179 0.100143 0.799847 + outer loop + vertex 0.839475 1.67976 2.5912 + vertex 0.842506 1.68059 2.59334 + vertex 0.840121 1.6836 2.5912 + endloop + endfacet + facet normal -0.607615 0.102798 0.787551 + outer loop + vertex 0.840121 1.6836 2.5912 + vertex 0.837318 1.68082 2.5894 + vertex 0.839475 1.67976 2.5912 + endloop + endfacet + facet normal -0.606769 0.10141 0.788383 + outer loop + vertex 0.837158 1.68566 2.58865 + vertex 0.837318 1.68082 2.5894 + vertex 0.840121 1.6836 2.5912 + endloop + endfacet + facet normal -0.607019 0.100893 0.788257 + outer loop + vertex 0.840762 1.68872 2.59104 + vertex 0.837158 1.68566 2.58865 + vertex 0.840121 1.6836 2.5912 + endloop + endfacet + facet normal -0.590875 0.0992612 0.800634 + outer loop + vertex 0.840121 1.6836 2.5912 + vertex 0.84349 1.68627 2.59335 + vertex 0.840762 1.68872 2.59104 + endloop + endfacet + facet normal -0.589967 0.100731 0.801119 + outer loop + vertex 0.84349 1.68627 2.59335 + vertex 0.844487 1.69197 2.59337 + vertex 0.840762 1.68872 2.59104 + endloop + endfacet + facet normal -0.588907 0.0987818 0.802141 + outer loop + vertex 0.840762 1.68872 2.59104 + vertex 0.844487 1.69197 2.59337 + vertex 0.841324 1.69401 2.5908 + endloop + endfacet + facet normal -0.604051 0.0998745 0.790663 + outer loop + vertex 0.841324 1.69401 2.5908 + vertex 0.838015 1.69113 2.58863 + vertex 0.840762 1.68872 2.59104 + endloop + endfacet + facet normal -0.603952 0.099686 0.790762 + outer loop + vertex 0.838632 1.69635 2.58845 + vertex 0.838015 1.69113 2.58863 + vertex 0.841324 1.69401 2.5908 + endloop + endfacet + facet normal -0.603068 0.101188 0.791245 + outer loop + vertex 0.841767 1.699 2.5905 + vertex 0.838632 1.69635 2.58845 + vertex 0.841324 1.69401 2.5908 + endloop + endfacet + facet normal -0.588172 0.100543 0.802462 + outer loop + vertex 0.841324 1.69401 2.5908 + vertex 0.844418 1.69723 2.59266 + vertex 0.841767 1.699 2.5905 + endloop + endfacet + facet normal -0.586699 0.103589 0.803152 + outer loop + vertex 0.844418 1.69723 2.59266 + vertex 0.844549 1.70179 2.59217 + vertex 0.841767 1.699 2.5905 + endloop + endfacet + facet normal -0.58533 0.101461 0.804421 + outer loop + vertex 0.841767 1.699 2.5905 + vertex 0.844549 1.70179 2.59217 + vertex 0.842399 1.70283 2.59047 + endloop + endfacet + facet normal -0.602084 0.104155 0.79161 + outer loop + vertex 0.842399 1.70283 2.59047 + vertex 0.839492 1.702 2.58837 + vertex 0.841767 1.699 2.5905 + endloop + endfacet + facet normal -0.603637 0.102305 0.790668 + outer loop + vertex 0.839492 1.702 2.58837 + vertex 0.838632 1.69635 2.58845 + vertex 0.841767 1.699 2.5905 + endloop + endfacet + facet normal -0.602272 0.105684 0.791265 + outer loop + vertex 0.842399 1.70283 2.59047 + vertex 0.842095 1.70612 2.5898 + vertex 0.839492 1.702 2.58837 + endloop + endfacet + facet normal -0.60256 0.105954 0.791009 + outer loop + vertex 0.839492 1.702 2.58837 + vertex 0.842095 1.70612 2.5898 + vertex 0.83942 1.70722 2.58762 + endloop + endfacet + facet normal -0.601195 0.110202 0.791467 + outer loop + vertex 0.842095 1.70612 2.5898 + vertex 0.842258 1.71057 2.58931 + vertex 0.83942 1.70722 2.58762 + endloop + endfacet + facet normal -0.585999 0.110895 0.802688 + outer loop + vertex 0.842258 1.71057 2.58931 + vertex 0.842095 1.70612 2.5898 + vertex 0.844888 1.70878 2.59147 + endloop + endfacet + facet normal -0.586821 0.112253 0.801898 + outer loop + vertex 0.844888 1.70878 2.59147 + vertex 0.842095 1.70612 2.5898 + vertex 0.844227 1.70512 2.5915 + endloop + endfacet + facet normal -0.57353 0.109938 0.811774 + outer loop + vertex 0.844227 1.70512 2.5915 + vertex 0.847248 1.70579 2.59355 + vertex 0.844888 1.70878 2.59147 + endloop + endfacet + facet normal -0.573021 0.110532 0.812053 + outer loop + vertex 0.847248 1.70579 2.59355 + vertex 0.848124 1.71124 2.59342 + vertex 0.844888 1.70878 2.59147 + endloop + endfacet + facet normal -0.574221 0.113062 0.810856 + outer loop + vertex 0.844888 1.70878 2.59147 + vertex 0.848124 1.71124 2.59342 + vertex 0.845373 1.71357 2.59115 + endloop + endfacet + facet normal -0.56718 0.109689 0.816257 + outer loop + vertex 0.848124 1.71124 2.59342 + vertex 0.847248 1.70579 2.59355 + vertex 0.851024 1.70897 2.59574 + endloop + endfacet + facet normal -0.567137 0.109765 0.816277 + outer loop + vertex 0.851464 1.71401 2.59537 + vertex 0.848124 1.71124 2.59342 + vertex 0.851024 1.70897 2.59574 + endloop + endfacet + facet normal -0.563594 0.109638 0.818744 + outer loop + vertex 0.851024 1.70897 2.59574 + vertex 0.854349 1.71217 2.5976 + vertex 0.851464 1.71401 2.59537 + endloop + endfacet + facet normal -0.564093 0.108607 0.818538 + outer loop + vertex 0.854349 1.71217 2.5976 + vertex 0.854625 1.71695 2.59716 + vertex 0.851464 1.71401 2.59537 + endloop + endfacet + facet normal -0.565337 0.110633 0.817407 + outer loop + vertex 0.851464 1.71401 2.59537 + vertex 0.854625 1.71695 2.59716 + vertex 0.851989 1.71873 2.59509 + endloop + endfacet + facet normal -0.560259 0.108629 0.821164 + outer loop + vertex 0.854349 1.71217 2.5976 + vertex 0.857465 1.71546 2.59929 + vertex 0.854625 1.71695 2.59716 + endloop + endfacet + facet normal -0.560504 0.108036 0.821075 + outer loop + vertex 0.857465 1.71546 2.59929 + vertex 0.857741 1.7203 2.59884 + vertex 0.854625 1.71695 2.59716 + endloop + endfacet + facet normal -0.561283 0.109099 0.820402 + outer loop + vertex 0.854625 1.71695 2.59716 + vertex 0.857741 1.7203 2.59884 + vertex 0.854877 1.7214 2.59674 + endloop + endfacet + facet normal -0.563225 0.109064 0.819074 + outer loop + vertex 0.854385 1.70694 2.59832 + vertex 0.854349 1.71217 2.5976 + vertex 0.851024 1.70897 2.59574 + endloop + endfacet + facet normal -0.563104 0.109328 0.819123 + outer loop + vertex 0.850571 1.70375 2.59613 + vertex 0.854385 1.70694 2.59832 + vertex 0.851024 1.70897 2.59574 + endloop + endfacet + facet normal -0.563014 0.109164 0.819206 + outer loop + vertex 0.853378 1.70136 2.59838 + vertex 0.854385 1.70694 2.59832 + vertex 0.850571 1.70375 2.59613 + endloop + endfacet + facet normal -0.563689 0.108071 0.818887 + outer loop + vertex 0.850039 1.69878 2.59642 + vertex 0.853378 1.70136 2.59838 + vertex 0.850571 1.70375 2.59613 + endloop + endfacet + facet normal -0.567589 0.108329 0.816154 + outer loop + vertex 0.850571 1.70375 2.59613 + vertex 0.847331 1.70059 2.59429 + vertex 0.850039 1.69878 2.59642 + endloop + endfacet + facet normal -0.568698 0.106116 0.815673 + outer loop + vertex 0.847331 1.70059 2.59429 + vertex 0.847182 1.69607 2.59478 + vertex 0.850039 1.69878 2.59642 + endloop + endfacet + facet normal -0.568892 0.106426 0.815497 + outer loop + vertex 0.850039 1.69878 2.59642 + vertex 0.847182 1.69607 2.59478 + vertex 0.84936 1.69503 2.59643 + endloop + endfacet + facet normal -0.562342 0.105259 0.820178 + outer loop + vertex 0.84936 1.69503 2.59643 + vertex 0.852417 1.69577 2.59843 + vertex 0.850039 1.69878 2.59642 + endloop + endfacet + facet normal -0.56184 0.100688 0.821096 + outer loop + vertex 0.84936 1.69503 2.59643 + vertex 0.849682 1.69172 2.59706 + vertex 0.852417 1.69577 2.59843 + endloop + endfacet + facet normal -0.560193 0.0991313 0.822409 + outer loop + vertex 0.849682 1.69172 2.59706 + vertex 0.852537 1.69053 2.59915 + vertex 0.852417 1.69577 2.59843 + endloop + endfacet + facet normal -0.560945 0.0968949 0.822163 + outer loop + vertex 0.849468 1.68722 2.59744 + vertex 0.852537 1.69053 2.59915 + vertex 0.849682 1.69172 2.59706 + endloop + endfacet + facet normal -0.567377 0.0968238 0.817746 + outer loop + vertex 0.849468 1.68722 2.59744 + vertex 0.849682 1.69172 2.59706 + vertex 0.846812 1.68897 2.59539 + endloop + endfacet + facet normal -0.567188 0.0972115 0.817831 + outer loop + vertex 0.84623 1.68403 2.59558 + vertex 0.849468 1.68722 2.59744 + vertex 0.846812 1.68897 2.59539 + endloop + endfacet + facet normal -0.567314 0.0974031 0.817721 + outer loop + vertex 0.849193 1.68238 2.59783 + vertex 0.849468 1.68722 2.59744 + vertex 0.84623 1.68403 2.59558 + endloop + endfacet + facet normal -0.56632 0.0997388 0.818128 + outer loop + vertex 0.845843 1.67886 2.59594 + vertex 0.849193 1.68238 2.59783 + vertex 0.84623 1.68403 2.59558 + endloop + endfacet + facet normal -0.558797 0.0973862 0.823567 + outer loop + vertex 0.849193 1.68238 2.59783 + vertex 0.852306 1.68571 2.59955 + vertex 0.849468 1.68722 2.59744 + endloop + endfacet + facet normal -0.567688 0.0973154 0.817472 + outer loop + vertex 0.846812 1.68897 2.59539 + vertex 0.849682 1.69172 2.59706 + vertex 0.847501 1.69275 2.59542 + endloop + endfacet + facet normal -0.577424 0.099144 0.810403 + outer loop + vertex 0.847501 1.69275 2.59542 + vertex 0.844487 1.69197 2.59337 + vertex 0.846812 1.68897 2.59539 + endloop + endfacet + facet normal -0.577715 0.101625 0.809887 + outer loop + vertex 0.847501 1.69275 2.59542 + vertex 0.847182 1.69607 2.59478 + vertex 0.844487 1.69197 2.59337 + endloop + endfacet + facet normal -0.577689 0.1016 0.809909 + outer loop + vertex 0.844487 1.69197 2.59337 + vertex 0.847182 1.69607 2.59478 + vertex 0.844418 1.69723 2.59266 + endloop + endfacet + facet normal -0.566849 0.0995762 0.817782 + outer loop + vertex 0.84936 1.69503 2.59643 + vertex 0.847501 1.69275 2.59542 + vertex 0.849682 1.69172 2.59706 + endloop + endfacet + facet normal -0.570038 0.103373 0.81509 + outer loop + vertex 0.847501 1.69275 2.59542 + vertex 0.84936 1.69503 2.59643 + vertex 0.847182 1.69607 2.59478 + endloop + endfacet + facet normal -0.57628 0.105798 0.810375 + outer loop + vertex 0.847182 1.69607 2.59478 + vertex 0.847331 1.70059 2.59429 + vertex 0.844418 1.69723 2.59266 + endloop + endfacet + facet normal -0.575008 0.104155 0.811491 + outer loop + vertex 0.844418 1.69723 2.59266 + vertex 0.847331 1.70059 2.59429 + vertex 0.844549 1.70179 2.59217 + endloop + endfacet + facet normal -0.573818 0.107617 0.811882 + outer loop + vertex 0.844549 1.70179 2.59217 + vertex 0.847331 1.70059 2.59429 + vertex 0.847248 1.70579 2.59355 + endloop + endfacet + facet normal -0.56759 0.10833 0.816153 + outer loop + vertex 0.847248 1.70579 2.59355 + vertex 0.847331 1.70059 2.59429 + vertex 0.850571 1.70375 2.59613 + endloop + endfacet + facet normal -0.559722 0.109413 0.821426 + outer loop + vertex 0.854385 1.70694 2.59832 + vertex 0.857205 1.71096 2.59971 + vertex 0.854349 1.71217 2.5976 + endloop + endfacet + facet normal -0.568466 0.112256 0.815012 + outer loop + vertex 0.848756 1.7163 2.59317 + vertex 0.848124 1.71124 2.59342 + vertex 0.851464 1.71401 2.59537 + endloop + endfacet + facet normal -0.56706 0.109467 0.81637 + outer loop + vertex 0.851024 1.70897 2.59574 + vertex 0.847248 1.70579 2.59355 + vertex 0.850571 1.70375 2.59613 + endloop + endfacet + facet normal -0.573277 0.107097 0.812332 + outer loop + vertex 0.844227 1.70512 2.5915 + vertex 0.844549 1.70179 2.59217 + vertex 0.847248 1.70579 2.59355 + endloop + endfacet + facet normal -0.587979 0.109088 0.801486 + outer loop + vertex 0.842399 1.70283 2.59047 + vertex 0.844227 1.70512 2.5915 + vertex 0.842095 1.70612 2.5898 + endloop + endfacet + facet normal -0.584186 0.104548 0.804858 + outer loop + vertex 0.844227 1.70512 2.5915 + vertex 0.842399 1.70283 2.59047 + vertex 0.844549 1.70179 2.59217 + endloop + endfacet + facet normal -0.58812 0.100466 0.802509 + outer loop + vertex 0.844487 1.69197 2.59337 + vertex 0.844418 1.69723 2.59266 + vertex 0.841324 1.69401 2.5908 + endloop + endfacet + facet normal -0.605369 0.0976445 0.789933 + outer loop + vertex 0.838015 1.69113 2.58863 + vertex 0.837158 1.68566 2.58865 + vertex 0.840762 1.68872 2.59104 + endloop + endfacet + facet normal -0.591482 0.100516 0.800029 + outer loop + vertex 0.842506 1.68059 2.59334 + vertex 0.84349 1.68627 2.59335 + vertex 0.840121 1.6836 2.5912 + endloop + endfacet + facet normal -0.577717 0.0981078 0.81032 + outer loop + vertex 0.84349 1.68627 2.59335 + vertex 0.842506 1.68059 2.59334 + vertex 0.84623 1.68403 2.59558 + endloop + endfacet + facet normal -0.577683 0.098167 0.810337 + outer loop + vertex 0.846812 1.68897 2.59539 + vertex 0.84349 1.68627 2.59335 + vertex 0.84623 1.68403 2.59558 + endloop + endfacet + facet normal -0.5779 0.0985905 0.81013 + outer loop + vertex 0.844487 1.69197 2.59337 + vertex 0.84349 1.68627 2.59335 + vertex 0.846812 1.68897 2.59539 + endloop + endfacet + facet normal -0.578876 0.100058 0.809253 + outer loop + vertex 0.84623 1.68403 2.59558 + vertex 0.842506 1.68059 2.59334 + vertex 0.845843 1.67886 2.59594 + endloop + endfacet + facet normal -0.57825 0.101644 0.809503 + outer loop + vertex 0.842506 1.68059 2.59334 + vertex 0.842577 1.67539 2.59404 + vertex 0.845843 1.67886 2.59594 + endloop + endfacet + facet normal -0.579755 0.103795 0.808152 + outer loop + vertex 0.845843 1.67886 2.59594 + vertex 0.842577 1.67539 2.59404 + vertex 0.845359 1.6738 2.59624 + endloop + endfacet + facet normal -0.564524 0.102985 0.818967 + outer loop + vertex 0.845359 1.6738 2.59624 + vertex 0.84916 1.67706 2.59845 + vertex 0.845843 1.67886 2.59594 + endloop + endfacet + facet normal -0.566044 0.0993469 0.818367 + outer loop + vertex 0.84916 1.67706 2.59845 + vertex 0.849193 1.68238 2.59783 + vertex 0.845843 1.67886 2.59594 + endloop + endfacet + facet normal -0.556658 0.100029 0.824698 + outer loop + vertex 0.84916 1.67706 2.59845 + vertex 0.852063 1.68127 2.5999 + vertex 0.849193 1.68238 2.59783 + endloop + endfacet + facet normal -0.557884 0.0961414 0.824331 + outer loop + vertex 0.852063 1.68127 2.5999 + vertex 0.852306 1.68571 2.59955 + vertex 0.849193 1.68238 2.59783 + endloop + endfacet + facet normal -0.554047 0.0975223 0.826753 + outer loop + vertex 0.852343 1.67799 2.60048 + vertex 0.852063 1.68127 2.5999 + vertex 0.84916 1.67706 2.59845 + endloop + endfacet + facet normal -0.554327 0.0993754 0.826345 + outer loop + vertex 0.852343 1.67799 2.60048 + vertex 0.84916 1.67706 2.59845 + vertex 0.851536 1.67409 2.6004 + endloop + endfacet + facet normal -0.545856 0.0975174 0.832185 + outer loop + vertex 0.851536 1.67409 2.6004 + vertex 0.85458 1.67692 2.60207 + vertex 0.852343 1.67799 2.60048 + endloop + endfacet + facet normal -0.544134 0.0948269 0.833622 + outer loop + vertex 0.854351 1.67234 2.60244 + vertex 0.85458 1.67692 2.60207 + vertex 0.851536 1.67409 2.6004 + endloop + endfacet + facet normal -0.553818 0.0999593 0.826616 + outer loop + vertex 0.84916 1.67706 2.59845 + vertex 0.847722 1.67085 2.59824 + vertex 0.851536 1.67409 2.6004 + endloop + endfacet + facet normal -0.552264 0.0972163 0.827982 + outer loop + vertex 0.851536 1.67409 2.6004 + vertex 0.847722 1.67085 2.59824 + vertex 0.851026 1.66904 2.60066 + endloop + endfacet + facet normal -0.543284 0.0966085 0.833972 + outer loop + vertex 0.851026 1.66904 2.60066 + vertex 0.854351 1.67234 2.60244 + vertex 0.851536 1.67409 2.6004 + endloop + endfacet + facet normal -0.53999 0.091852 0.836645 + outer loop + vertex 0.854122 1.66741 2.60283 + vertex 0.854351 1.67234 2.60244 + vertex 0.851026 1.66904 2.60066 + endloop + endfacet + facet normal -0.540063 0.0916746 0.836617 + outer loop + vertex 0.85078 1.66389 2.60106 + vertex 0.854122 1.66741 2.60283 + vertex 0.851026 1.66904 2.60066 + endloop + endfacet + facet normal -0.54857 0.0916447 0.831067 + outer loop + vertex 0.851026 1.66904 2.60066 + vertex 0.847709 1.66545 2.59886 + vertex 0.85078 1.66389 2.60106 + endloop + endfacet + facet normal -0.549505 0.089297 0.830704 + outer loop + vertex 0.847709 1.66545 2.59886 + vertex 0.847484 1.66049 2.59925 + vertex 0.85078 1.66389 2.60106 + endloop + endfacet + facet normal -0.547972 0.0871513 0.831945 + outer loop + vertex 0.85078 1.66389 2.60106 + vertex 0.847484 1.66049 2.59925 + vertex 0.850307 1.65883 2.60128 + endloop + endfacet + facet normal -0.535678 0.0863518 0.839995 + outer loop + vertex 0.850307 1.65883 2.60128 + vertex 0.854171 1.66205 2.60341 + vertex 0.85078 1.66389 2.60106 + endloop + endfacet + facet normal -0.53318 0.0820103 0.842018 + outer loop + vertex 0.852789 1.65585 2.60314 + vertex 0.854171 1.66205 2.60341 + vertex 0.850307 1.65883 2.60128 + endloop + endfacet + facet normal -0.532668 0.0826018 0.842283 + outer loop + vertex 0.849536 1.6549 2.60118 + vertex 0.852789 1.65585 2.60314 + vertex 0.850307 1.65883 2.60128 + endloop + endfacet + facet normal -0.549924 0.0862821 0.830746 + outer loop + vertex 0.850307 1.65883 2.60128 + vertex 0.847294 1.65588 2.59959 + vertex 0.849536 1.6549 2.60118 + endloop + endfacet + facet normal -0.531797 0.0774884 0.843319 + outer loop + vertex 0.849536 1.6549 2.60118 + vertex 0.849897 1.65158 2.60171 + vertex 0.852789 1.65585 2.60314 + endloop + endfacet + facet normal -0.53064 0.0764281 0.844145 + outer loop + vertex 0.849897 1.65158 2.60171 + vertex 0.852877 1.6505 2.60368 + vertex 0.852789 1.65585 2.60314 + endloop + endfacet + facet normal -0.526543 0.0767508 0.846677 + outer loop + vertex 0.852789 1.65585 2.60314 + vertex 0.852877 1.6505 2.60368 + vertex 0.856203 1.65401 2.60543 + endloop + endfacet + facet normal -0.526435 0.0770075 0.846721 + outer loop + vertex 0.856667 1.65902 2.60527 + vertex 0.852789 1.65585 2.60314 + vertex 0.856203 1.65401 2.60543 + endloop + endfacet + facet normal -0.523817 0.07682 0.84836 + outer loop + vertex 0.856203 1.65401 2.60543 + vertex 0.859564 1.65725 2.60721 + vertex 0.856667 1.65902 2.60527 + endloop + endfacet + facet normal -0.523882 0.0766823 0.848332 + outer loop + vertex 0.859564 1.65725 2.60721 + vertex 0.859753 1.66181 2.60692 + vertex 0.856667 1.65902 2.60527 + endloop + endfacet + facet normal -0.52555 0.0792748 0.847061 + outer loop + vertex 0.856667 1.65902 2.60527 + vertex 0.859753 1.66181 2.60692 + vertex 0.857441 1.66289 2.60538 + endloop + endfacet + facet normal -0.529312 0.0801005 0.844638 + outer loop + vertex 0.857441 1.66289 2.60538 + vertex 0.854171 1.66205 2.60341 + vertex 0.856667 1.65902 2.60527 + endloop + endfacet + facet normal -0.529755 0.0831638 0.844063 + outer loop + vertex 0.857441 1.66289 2.60538 + vertex 0.857101 1.66621 2.60484 + vertex 0.854171 1.66205 2.60341 + endloop + endfacet + facet normal -0.532954 0.0862139 0.84174 + outer loop + vertex 0.854171 1.66205 2.60341 + vertex 0.857101 1.66621 2.60484 + vertex 0.854122 1.66741 2.60283 + endloop + endfacet + facet normal -0.532594 0.0872977 0.841857 + outer loop + vertex 0.857101 1.66621 2.60484 + vertex 0.8573 1.6707 2.6045 + vertex 0.854122 1.66741 2.60283 + endloop + endfacet + facet normal -0.530185 0.087306 0.843375 + outer loop + vertex 0.8573 1.6707 2.6045 + vertex 0.857101 1.66621 2.60484 + vertex 0.860076 1.66881 2.60644 + endloop + endfacet + facet normal -0.530737 0.0862524 0.843136 + outer loop + vertex 0.860595 1.67366 2.60627 + vertex 0.8573 1.6707 2.6045 + vertex 0.860076 1.66881 2.60644 + endloop + endfacet + facet normal -0.526029 0.0858537 0.846122 + outer loop + vertex 0.860076 1.66881 2.60644 + vertex 0.863466 1.6713 2.6083 + vertex 0.860595 1.67366 2.60627 + endloop + endfacet + facet normal -0.526299 0.0854196 0.845998 + outer loop + vertex 0.863466 1.6713 2.6083 + vertex 0.864401 1.67686 2.60832 + vertex 0.860595 1.67366 2.60627 + endloop + endfacet + facet normal -0.528326 0.0888735 0.844377 + outer loop + vertex 0.860595 1.67366 2.60627 + vertex 0.864401 1.67686 2.60832 + vertex 0.86087 1.67885 2.6059 + endloop + endfacet + facet normal -0.533628 0.0908515 0.840825 + outer loop + vertex 0.857515 1.67559 2.60411 + vertex 0.8573 1.6707 2.6045 + vertex 0.860595 1.67366 2.60627 + endloop + endfacet + facet normal -0.536406 0.0908326 0.839058 + outer loop + vertex 0.8573 1.6707 2.6045 + vertex 0.857515 1.67559 2.60411 + vertex 0.854351 1.67234 2.60244 + endloop + endfacet + facet normal -0.52819 0.0840499 0.844956 + outer loop + vertex 0.860076 1.66881 2.60644 + vertex 0.857101 1.66621 2.60484 + vertex 0.859405 1.66514 2.60639 + endloop + endfacet + facet normal -0.522894 0.083034 0.848344 + outer loop + vertex 0.859405 1.66514 2.60639 + vertex 0.862555 1.6658 2.60827 + vertex 0.860076 1.66881 2.60644 + endloop + endfacet + facet normal -0.522589 0.080311 0.848794 + outer loop + vertex 0.859405 1.66514 2.60639 + vertex 0.859753 1.66181 2.60692 + vertex 0.862555 1.6658 2.60827 + endloop + endfacet + facet normal -0.51972 0.0776167 0.850804 + outer loop + vertex 0.859753 1.66181 2.60692 + vertex 0.862749 1.66058 2.60886 + vertex 0.862555 1.6658 2.60827 + endloop + endfacet + facet normal -0.528421 0.0834329 0.844873 + outer loop + vertex 0.857441 1.66289 2.60538 + vertex 0.859405 1.66514 2.60639 + vertex 0.857101 1.66621 2.60484 + endloop + endfacet + facet normal -0.525371 0.0797546 0.847127 + outer loop + vertex 0.859405 1.66514 2.60639 + vertex 0.857441 1.66289 2.60538 + vertex 0.859753 1.66181 2.60692 + endloop + endfacet + facet normal -0.520037 0.0766757 0.850695 + outer loop + vertex 0.859564 1.65725 2.60721 + vertex 0.862749 1.66058 2.60886 + vertex 0.859753 1.66181 2.60692 + endloop + endfacet + facet normal -0.521666 0.0737178 0.849959 + outer loop + vertex 0.859321 1.65232 2.60749 + vertex 0.859564 1.65725 2.60721 + vertex 0.856203 1.65401 2.60543 + endloop + endfacet + facet normal -0.521733 0.0735606 0.849932 + outer loop + vertex 0.85602 1.64892 2.60576 + vertex 0.859321 1.65232 2.60749 + vertex 0.856203 1.65401 2.60543 + endloop + endfacet + facet normal -0.519618 0.0707178 0.851467 + outer loop + vertex 0.859184 1.64729 2.60783 + vertex 0.859321 1.65232 2.60749 + vertex 0.85602 1.64892 2.60576 + endloop + endfacet + facet normal -0.519891 0.0700494 0.851356 + outer loop + vertex 0.855898 1.64381 2.60611 + vertex 0.859184 1.64729 2.60783 + vertex 0.85602 1.64892 2.60576 + endloop + endfacet + facet normal -0.522335 0.0700065 0.849862 + outer loop + vertex 0.85602 1.64892 2.60576 + vertex 0.85275 1.64552 2.60403 + vertex 0.855898 1.64381 2.60611 + endloop + endfacet + facet normal -0.522656 0.0692545 0.849726 + outer loop + vertex 0.85275 1.64552 2.60403 + vertex 0.85256 1.64053 2.60432 + vertex 0.855898 1.64381 2.60611 + endloop + endfacet + facet normal -0.520465 0.0661599 0.851316 + outer loop + vertex 0.855898 1.64381 2.60611 + vertex 0.85256 1.64053 2.60432 + vertex 0.855625 1.63864 2.60634 + endloop + endfacet + facet normal -0.517446 0.0660845 0.85316 + outer loop + vertex 0.855625 1.63864 2.60634 + vertex 0.859402 1.64193 2.60838 + vertex 0.855898 1.64381 2.60611 + endloop + endfacet + facet normal -0.515362 0.0627604 0.854671 + outer loop + vertex 0.858527 1.6363 2.60826 + vertex 0.859402 1.64193 2.60838 + vertex 0.855625 1.63864 2.60634 + endloop + endfacet + facet normal -0.51566 0.0622722 0.854527 + outer loop + vertex 0.855144 1.63369 2.60641 + vertex 0.858527 1.6363 2.60826 + vertex 0.855625 1.63864 2.60634 + endloop + endfacet + facet normal -0.519025 0.0625703 0.852466 + outer loop + vertex 0.855625 1.63864 2.60634 + vertex 0.852336 1.63559 2.60456 + vertex 0.855144 1.63369 2.60641 + endloop + endfacet + facet normal -0.519381 0.0618806 0.852299 + outer loop + vertex 0.852336 1.63559 2.60456 + vertex 0.852218 1.63104 2.60482 + vertex 0.855144 1.63369 2.60641 + endloop + endfacet + facet normal -0.518888 0.0611249 0.852654 + outer loop + vertex 0.855144 1.63369 2.60641 + vertex 0.852218 1.63104 2.60482 + vertex 0.854524 1.62994 2.6063 + endloop + endfacet + facet normal -0.514132 0.0602531 0.855592 + outer loop + vertex 0.854524 1.62994 2.6063 + vertex 0.857681 1.63072 2.60815 + vertex 0.855144 1.63369 2.60641 + endloop + endfacet + facet normal -0.514019 0.0595088 0.855712 + outer loop + vertex 0.854524 1.62994 2.6063 + vertex 0.85495 1.62665 2.60679 + vertex 0.857681 1.63072 2.60815 + endloop + endfacet + facet normal -0.513369 0.0589282 0.856142 + outer loop + vertex 0.85495 1.62665 2.60679 + vertex 0.857953 1.62552 2.60867 + vertex 0.857681 1.63072 2.60815 + endloop + endfacet + facet normal -0.510593 0.0592382 0.85778 + outer loop + vertex 0.857681 1.63072 2.60815 + vertex 0.857953 1.62552 2.60867 + vertex 0.861208 1.62899 2.61036 + endloop + endfacet + facet normal -0.510961 0.0582883 0.857626 + outer loop + vertex 0.861456 1.63405 2.61017 + vertex 0.857681 1.63072 2.60815 + vertex 0.861208 1.62899 2.61036 + endloop + endfacet + facet normal -0.504586 0.0581227 0.861403 + outer loop + vertex 0.861208 1.62899 2.61036 + vertex 0.864597 1.63233 2.61212 + vertex 0.861456 1.63405 2.61017 + endloop + endfacet + facet normal -0.504228 0.0589495 0.861556 + outer loop + vertex 0.864597 1.63233 2.61212 + vertex 0.864839 1.63721 2.61193 + vertex 0.861456 1.63405 2.61017 + endloop + endfacet + facet normal -0.504439 0.0592572 0.861411 + outer loop + vertex 0.861456 1.63405 2.61017 + vertex 0.864839 1.63721 2.61193 + vertex 0.861954 1.63894 2.61012 + endloop + endfacet + facet normal -0.511511 0.0599371 0.857184 + outer loop + vertex 0.861954 1.63894 2.61012 + vertex 0.858527 1.6363 2.60826 + vertex 0.861456 1.63405 2.61017 + endloop + endfacet + facet normal -0.503502 0.061242 0.861821 + outer loop + vertex 0.864839 1.63721 2.61193 + vertex 0.865081 1.64181 2.61175 + vertex 0.861954 1.63894 2.61012 + endloop + endfacet + facet normal -0.502637 0.0599621 0.862416 + outer loop + vertex 0.861954 1.63894 2.61012 + vertex 0.865081 1.64181 2.61175 + vertex 0.862627 1.64272 2.61025 + endloop + endfacet + facet normal -0.513091 0.0620443 0.856089 + outer loop + vertex 0.862627 1.64272 2.61025 + vertex 0.859402 1.64193 2.60838 + vertex 0.861954 1.63894 2.61012 + endloop + endfacet + facet normal -0.513564 0.0652199 0.855569 + outer loop + vertex 0.862627 1.64272 2.61025 + vertex 0.862232 1.6461 2.60976 + vertex 0.859402 1.64193 2.60838 + endloop + endfacet + facet normal -0.494134 0.0586786 0.867403 + outer loop + vertex 0.864597 1.63233 2.61212 + vertex 0.867942 1.63566 2.6138 + vertex 0.864839 1.63721 2.61193 + endloop + endfacet + facet normal -0.493087 0.0612895 0.867818 + outer loop + vertex 0.867942 1.63566 2.6138 + vertex 0.868172 1.64067 2.61358 + vertex 0.864839 1.63721 2.61193 + endloop + endfacet + facet normal -0.503321 0.0563863 0.862258 + outer loop + vertex 0.864423 1.62738 2.61235 + vertex 0.864597 1.63233 2.61212 + vertex 0.861208 1.62899 2.61036 + endloop + endfacet + facet normal -0.503068 0.0570199 0.862364 + outer loop + vertex 0.861118 1.624 2.61064 + vertex 0.864423 1.62738 2.61235 + vertex 0.861208 1.62899 2.61036 + endloop + endfacet + facet normal -0.500858 0.0541129 0.863836 + outer loop + vertex 0.864257 1.6224 2.61256 + vertex 0.864423 1.62738 2.61235 + vertex 0.861118 1.624 2.61064 + endloop + endfacet + facet normal -0.500664 0.0545919 0.863919 + outer loop + vertex 0.86097 1.61904 2.61087 + vertex 0.864257 1.6224 2.61256 + vertex 0.861118 1.624 2.61064 + endloop + endfacet + facet normal -0.506342 0.0546093 0.860602 + outer loop + vertex 0.861118 1.624 2.61064 + vertex 0.857875 1.62063 2.60895 + vertex 0.86097 1.61904 2.61087 + endloop + endfacet + facet normal -0.506401 0.0544622 0.860576 + outer loop + vertex 0.857875 1.62063 2.60895 + vertex 0.857707 1.61569 2.60916 + vertex 0.86097 1.61904 2.61087 + endloop + endfacet + facet normal -0.504023 0.0513295 0.862164 + outer loop + vertex 0.86097 1.61904 2.61087 + vertex 0.857707 1.61569 2.60916 + vertex 0.860824 1.61403 2.61108 + endloop + endfacet + facet normal -0.498439 0.0513044 0.865405 + outer loop + vertex 0.860824 1.61403 2.61108 + vertex 0.864088 1.6174 2.61276 + vertex 0.86097 1.61904 2.61087 + endloop + endfacet + facet normal -0.496568 0.0488844 0.86662 + outer loop + vertex 0.864016 1.61238 2.613 + vertex 0.864088 1.6174 2.61276 + vertex 0.860824 1.61403 2.61108 + endloop + endfacet + facet normal -0.497089 0.0476131 0.866392 + outer loop + vertex 0.860744 1.60895 2.61132 + vertex 0.864016 1.61238 2.613 + vertex 0.860824 1.61403 2.61108 + endloop + endfacet + facet normal -0.50155 0.0475654 0.86382 + outer loop + vertex 0.860824 1.61403 2.61108 + vertex 0.857545 1.61071 2.60936 + vertex 0.860744 1.60895 2.61132 + endloop + endfacet + facet normal -0.501686 0.04725 0.863758 + outer loop + vertex 0.857545 1.61071 2.60936 + vertex 0.857382 1.60571 2.60954 + vertex 0.860744 1.60895 2.61132 + endloop + endfacet + facet normal -0.499461 0.0441394 0.865211 + outer loop + vertex 0.860744 1.60895 2.61132 + vertex 0.857382 1.60571 2.60954 + vertex 0.860524 1.60382 2.61145 + endloop + endfacet + facet normal -0.494363 0.0439987 0.868141 + outer loop + vertex 0.860524 1.60382 2.61145 + vertex 0.864329 1.60706 2.61345 + vertex 0.860744 1.60895 2.61132 + endloop + endfacet + facet normal -0.492047 0.0403569 0.869633 + outer loop + vertex 0.86353 1.60147 2.61326 + vertex 0.864329 1.60706 2.61345 + vertex 0.860524 1.60382 2.61145 + endloop + endfacet + facet normal -0.491566 0.0411531 0.869868 + outer loop + vertex 0.860089 1.59891 2.61144 + vertex 0.86353 1.60147 2.61326 + vertex 0.860524 1.60382 2.61145 + endloop + endfacet + facet normal -0.497608 0.0416995 0.866399 + outer loop + vertex 0.860524 1.60382 2.61145 + vertex 0.857194 1.60081 2.60968 + vertex 0.860089 1.59891 2.61144 + endloop + endfacet + facet normal -0.497415 0.0420796 0.866492 + outer loop + vertex 0.857194 1.60081 2.60968 + vertex 0.857111 1.59626 2.60986 + vertex 0.860089 1.59891 2.61144 + endloop + endfacet + facet normal -0.496269 0.0403491 0.867231 + outer loop + vertex 0.860089 1.59891 2.61144 + vertex 0.857111 1.59626 2.60986 + vertex 0.859491 1.59516 2.61127 + endloop + endfacet + facet normal -0.488154 0.0388449 0.871892 + outer loop + vertex 0.859491 1.59516 2.61127 + vertex 0.862747 1.59589 2.61306 + vertex 0.860089 1.59891 2.61144 + endloop + endfacet + facet normal -0.489454 0.0373411 0.871229 + outer loop + vertex 0.862747 1.59589 2.61306 + vertex 0.86353 1.60147 2.61326 + vertex 0.860089 1.59891 2.61144 + endloop + endfacet + facet normal -0.482917 0.0362891 0.874914 + outer loop + vertex 0.86353 1.60147 2.61326 + vertex 0.862747 1.59589 2.61306 + vertex 0.866588 1.59917 2.61504 + endloop + endfacet + facet normal -0.483486 0.0353179 0.874639 + outer loop + vertex 0.867006 1.60405 2.61508 + vertex 0.86353 1.60147 2.61326 + vertex 0.866588 1.59917 2.61504 + endloop + endfacet + facet normal -0.474107 0.0344781 0.879792 + outer loop + vertex 0.866588 1.59917 2.61504 + vertex 0.870012 1.60224 2.61677 + vertex 0.867006 1.60405 2.61508 + endloop + endfacet + facet normal -0.473729 0.0352689 0.879964 + outer loop + vertex 0.870012 1.60224 2.61677 + vertex 0.870166 1.60682 2.61667 + vertex 0.867006 1.60405 2.61508 + endloop + endfacet + facet normal -0.474094 0.0358104 0.879746 + outer loop + vertex 0.867006 1.60405 2.61508 + vertex 0.870166 1.60682 2.61667 + vertex 0.867618 1.6078 2.61525 + endloop + endfacet + facet normal -0.4867 0.0381969 0.872733 + outer loop + vertex 0.867618 1.6078 2.61525 + vertex 0.864329 1.60706 2.61345 + vertex 0.867006 1.60405 2.61508 + endloop + endfacet + facet normal -0.487427 0.0429526 0.872107 + outer loop + vertex 0.867618 1.6078 2.61525 + vertex 0.867143 1.61117 2.61482 + vertex 0.864329 1.60706 2.61345 + endloop + endfacet + facet normal -0.489324 0.044633 0.870959 + outer loop + vertex 0.864329 1.60706 2.61345 + vertex 0.867143 1.61117 2.61482 + vertex 0.864016 1.61238 2.613 + endloop + endfacet + facet normal -0.473107 0.0330296 0.880386 + outer loop + vertex 0.869856 1.59737 2.61687 + vertex 0.870012 1.60224 2.61677 + vertex 0.866588 1.59917 2.61504 + endloop + endfacet + facet normal -0.472982 0.0333133 0.880442 + outer loop + vertex 0.86643 1.5941 2.61515 + vertex 0.869856 1.59737 2.61687 + vertex 0.866588 1.59917 2.61504 + endloop + endfacet + facet normal -0.471351 0.031104 0.881397 + outer loop + vertex 0.869778 1.59243 2.617 + vertex 0.869856 1.59737 2.61687 + vertex 0.86643 1.5941 2.61515 + endloop + endfacet + facet normal -0.471324 0.0311712 0.881409 + outer loop + vertex 0.866441 1.58908 2.61533 + vertex 0.869778 1.59243 2.617 + vertex 0.86643 1.5941 2.61515 + endloop + endfacet + facet normal -0.477928 0.0310267 0.877851 + outer loop + vertex 0.86643 1.5941 2.61515 + vertex 0.863125 1.59064 2.61347 + vertex 0.866441 1.58908 2.61533 + endloop + endfacet + facet normal -0.478496 0.0295115 0.877594 + outer loop + vertex 0.863125 1.59064 2.61347 + vertex 0.863155 1.58568 2.61366 + vertex 0.866441 1.58908 2.61533 + endloop + endfacet + facet normal -0.476432 0.0269185 0.878799 + outer loop + vertex 0.866441 1.58908 2.61533 + vertex 0.863155 1.58568 2.61366 + vertex 0.866395 1.58409 2.61546 + endloop + endfacet + facet normal -0.469692 0.0269491 0.882419 + outer loop + vertex 0.866395 1.58409 2.61546 + vertex 0.86972 1.58746 2.61713 + vertex 0.866441 1.58908 2.61533 + endloop + endfacet + facet normal -0.467589 0.0242796 0.883613 + outer loop + vertex 0.869642 1.58247 2.61722 + vertex 0.86972 1.58746 2.61713 + vertex 0.866395 1.58409 2.61546 + endloop + endfacet + facet normal -0.468193 0.0227648 0.883333 + outer loop + vertex 0.866321 1.5791 2.61555 + vertex 0.869642 1.58247 2.61722 + vertex 0.866395 1.58409 2.61546 + endloop + endfacet + facet normal -0.474966 0.0228008 0.879709 + outer loop + vertex 0.866395 1.58409 2.61546 + vertex 0.863096 1.58071 2.61377 + vertex 0.866321 1.5791 2.61555 + endloop + endfacet + facet normal -0.475181 0.0222572 0.879607 + outer loop + vertex 0.863096 1.58071 2.61377 + vertex 0.86302 1.57575 2.61385 + vertex 0.866321 1.5791 2.61555 + endloop + endfacet + facet normal -0.47356 0.0201973 0.88053 + outer loop + vertex 0.866321 1.5791 2.61555 + vertex 0.86302 1.57575 2.61385 + vertex 0.866245 1.57412 2.61562 + endloop + endfacet + facet normal -0.466691 0.0201465 0.884191 + outer loop + vertex 0.866245 1.57412 2.61562 + vertex 0.86956 1.57747 2.6173 + vertex 0.866321 1.5791 2.61555 + endloop + endfacet + facet normal -0.466002 0.0192745 0.884573 + outer loop + vertex 0.869484 1.57248 2.61737 + vertex 0.86956 1.57747 2.6173 + vertex 0.866245 1.57412 2.61562 + endloop + endfacet + facet normal -0.465937 0.0194367 0.884605 + outer loop + vertex 0.866171 1.56914 2.6157 + vertex 0.869484 1.57248 2.61737 + vertex 0.866245 1.57412 2.61562 + endloop + endfacet + facet normal -0.472303 0.0194822 0.881221 + outer loop + vertex 0.866245 1.57412 2.61562 + vertex 0.862945 1.57079 2.61393 + vertex 0.866171 1.56914 2.6157 + endloop + endfacet + facet normal -0.472014 0.0201981 0.881359 + outer loop + vertex 0.862945 1.57079 2.61393 + vertex 0.862868 1.56582 2.614 + vertex 0.866171 1.56914 2.6157 + endloop + endfacet + facet normal -0.471101 0.0190272 0.881874 + outer loop + vertex 0.866171 1.56914 2.6157 + vertex 0.862868 1.56582 2.614 + vertex 0.8661 1.56416 2.61576 + endloop + endfacet + facet normal -0.465466 0.0189888 0.884862 + outer loop + vertex 0.8661 1.56416 2.61576 + vertex 0.869414 1.56748 2.61744 + vertex 0.866171 1.56914 2.6157 + endloop + endfacet + facet normal -0.465028 0.0184296 0.885104 + outer loop + vertex 0.86935 1.56249 2.61751 + vertex 0.869414 1.56748 2.61744 + vertex 0.8661 1.56416 2.61576 + endloop + endfacet + facet normal -0.465405 0.017509 0.884925 + outer loop + vertex 0.866036 1.55917 2.61583 + vertex 0.86935 1.56249 2.61751 + vertex 0.8661 1.56416 2.61576 + endloop + endfacet + facet normal -0.469724 0.0175346 0.882639 + outer loop + vertex 0.8661 1.56416 2.61576 + vertex 0.862792 1.56085 2.61407 + vertex 0.866036 1.55917 2.61583 + endloop + endfacet + facet normal -0.469905 0.0170922 0.882551 + outer loop + vertex 0.862792 1.56085 2.61407 + vertex 0.862724 1.55586 2.61413 + vertex 0.866036 1.55917 2.61583 + endloop + endfacet + facet normal -0.468563 0.0153691 0.883296 + outer loop + vertex 0.866036 1.55917 2.61583 + vertex 0.862724 1.55586 2.61413 + vertex 0.865983 1.55418 2.61589 + endloop + endfacet + facet normal -0.465503 0.0153554 0.884913 + outer loop + vertex 0.865983 1.55418 2.61589 + vertex 0.869296 1.55749 2.61757 + vertex 0.866036 1.55917 2.61583 + endloop + endfacet + facet normal -0.464453 0.0140148 0.885487 + outer loop + vertex 0.86925 1.5525 2.61763 + vertex 0.869296 1.55749 2.61757 + vertex 0.865983 1.55418 2.61589 + endloop + endfacet + facet normal -0.465018 0.0126289 0.885211 + outer loop + vertex 0.865941 1.54919 2.61594 + vertex 0.86925 1.5525 2.61763 + vertex 0.865983 1.55418 2.61589 + endloop + endfacet + facet normal -0.467565 0.0126374 0.883868 + outer loop + vertex 0.865983 1.55418 2.61589 + vertex 0.862672 1.55086 2.61418 + vertex 0.865941 1.54919 2.61594 + endloop + endfacet + facet normal -0.467958 0.0116694 0.883674 + outer loop + vertex 0.862672 1.55086 2.61418 + vertex 0.862634 1.54587 2.61423 + vertex 0.865941 1.54919 2.61594 + endloop + endfacet + facet normal -0.466789 0.0101748 0.88431 + outer loop + vertex 0.865941 1.54919 2.61594 + vertex 0.862634 1.54587 2.61423 + vertex 0.865906 1.54419 2.61598 + endloop + endfacet + facet normal -0.46393 0.0101663 0.885814 + outer loop + vertex 0.865906 1.54419 2.61598 + vertex 0.869212 1.54751 2.61767 + vertex 0.865941 1.54919 2.61594 + endloop + endfacet + facet normal -0.462928 0.00889319 0.886351 + outer loop + vertex 0.869179 1.54252 2.6177 + vertex 0.869212 1.54751 2.61767 + vertex 0.865906 1.54419 2.61598 + endloop + endfacet + facet normal -0.463118 0.00842386 0.886256 + outer loop + vertex 0.865877 1.5392 2.61601 + vertex 0.869179 1.54252 2.6177 + vertex 0.865906 1.54419 2.61598 + endloop + endfacet + facet normal -0.466491 0.00843177 0.884486 + outer loop + vertex 0.865906 1.54419 2.61598 + vertex 0.862605 1.54088 2.61427 + vertex 0.865877 1.5392 2.61601 + endloop + endfacet + facet normal -0.467018 0.00712636 0.884219 + outer loop + vertex 0.862605 1.54088 2.61427 + vertex 0.862586 1.53589 2.6143 + vertex 0.865877 1.5392 2.61601 + endloop + endfacet + facet normal -0.466837 0.00689608 0.884317 + outer loop + vertex 0.865877 1.5392 2.61601 + vertex 0.862586 1.53589 2.6143 + vertex 0.865855 1.53421 2.61604 + endloop + endfacet + facet normal -0.462167 0.00688969 0.886766 + outer loop + vertex 0.865855 1.53421 2.61604 + vertex 0.869154 1.53753 2.61773 + vertex 0.865877 1.5392 2.61601 + endloop + endfacet + facet normal -0.461423 0.00594755 0.887161 + outer loop + vertex 0.869135 1.53254 2.61775 + vertex 0.869154 1.53753 2.61773 + vertex 0.865855 1.53421 2.61604 + endloop + endfacet + facet normal -0.461521 0.00570514 0.887111 + outer loop + vertex 0.86584 1.52922 2.61606 + vertex 0.869135 1.53254 2.61775 + vertex 0.865855 1.53421 2.61604 + endloop + endfacet + facet normal -0.468101 0.00570804 0.883657 + outer loop + vertex 0.865855 1.53421 2.61604 + vertex 0.862575 1.5309 2.61432 + vertex 0.86584 1.52922 2.61606 + endloop + endfacet + facet normal -0.468868 0.00380456 0.88326 + outer loop + vertex 0.862575 1.5309 2.61432 + vertex 0.862568 1.52591 2.61434 + vertex 0.86584 1.52922 2.61606 + endloop + endfacet + facet normal -0.469444 0.00453418 0.882951 + outer loop + vertex 0.86584 1.52922 2.61606 + vertex 0.862568 1.52591 2.61434 + vertex 0.865828 1.52423 2.61608 + endloop + endfacet + facet normal -0.461451 0.00453048 0.887154 + outer loop + vertex 0.865828 1.52423 2.61608 + vertex 0.86912 1.52755 2.61777 + vertex 0.86584 1.52922 2.61606 + endloop + endfacet + facet normal -0.461585 0.00469957 0.887084 + outer loop + vertex 0.869105 1.52255 2.61779 + vertex 0.86912 1.52755 2.61777 + vertex 0.865828 1.52423 2.61608 + endloop + endfacet + facet normal -0.461847 0.0040516 0.88695 + outer loop + vertex 0.865816 1.51924 2.6161 + vertex 0.869105 1.52255 2.61779 + vertex 0.865828 1.52423 2.61608 + endloop + endfacet + facet normal -0.470249 0.00405657 0.882525 + outer loop + vertex 0.865828 1.52423 2.61608 + vertex 0.862561 1.52091 2.61435 + vertex 0.865816 1.51924 2.6161 + endloop + endfacet + facet normal -0.470756 0.00279537 0.882259 + outer loop + vertex 0.862561 1.52091 2.61435 + vertex 0.862554 1.51592 2.61437 + vertex 0.865816 1.51924 2.6161 + endloop + endfacet + facet normal -0.470467 0.00243026 0.882414 + outer loop + vertex 0.865816 1.51924 2.6161 + vertex 0.862554 1.51592 2.61437 + vertex 0.865809 1.51425 2.61611 + endloop + endfacet + facet normal -0.462041 0.00242638 0.886855 + outer loop + vertex 0.865809 1.51425 2.61611 + vertex 0.869091 1.51756 2.61781 + vertex 0.865816 1.51924 2.6161 + endloop + endfacet + facet normal -0.461823 0.00215163 0.886969 + outer loop + vertex 0.869083 1.51257 2.61782 + vertex 0.869091 1.51756 2.61781 + vertex 0.865809 1.51425 2.61611 + endloop + endfacet + facet normal -0.462621 0.000171188 0.886556 + outer loop + vertex 0.86581 1.50925 2.61611 + vertex 0.869083 1.51257 2.61782 + vertex 0.865809 1.51425 2.61611 + endloop + endfacet + facet normal -0.470618 0.000168547 0.882337 + outer loop + vertex 0.865809 1.51425 2.61611 + vertex 0.862554 1.51093 2.61437 + vertex 0.86581 1.50925 2.61611 + endloop + endfacet + facet normal -0.471471 -0.00196227 0.881879 + outer loop + vertex 0.862554 1.51093 2.61437 + vertex 0.862565 1.50594 2.61437 + vertex 0.86581 1.50925 2.61611 + endloop + endfacet + facet normal -0.471032 -0.00251466 0.882112 + outer loop + vertex 0.86581 1.50925 2.61611 + vertex 0.862565 1.50594 2.61437 + vertex 0.86582 1.50426 2.6161 + endloop + endfacet + facet normal -0.462765 -0.0025056 0.886478 + outer loop + vertex 0.86582 1.50426 2.6161 + vertex 0.869085 1.50758 2.61781 + vertex 0.86581 1.50925 2.61611 + endloop + endfacet + facet normal -0.462715 -0.002568 0.886503 + outer loop + vertex 0.869094 1.50259 2.6178 + vertex 0.869085 1.50758 2.61781 + vertex 0.86582 1.50426 2.6161 + endloop + endfacet + facet normal -0.463394 -0.00426198 0.886142 + outer loop + vertex 0.865834 1.49927 2.61608 + vertex 0.869094 1.50259 2.6178 + vertex 0.86582 1.50426 2.6161 + endloop + endfacet + facet normal -0.47237 -0.00427127 0.88139 + outer loop + vertex 0.86582 1.50426 2.6161 + vertex 0.862584 1.50095 2.61435 + vertex 0.865834 1.49927 2.61608 + endloop + endfacet + facet normal -0.47294 -0.00570098 0.881076 + outer loop + vertex 0.862584 1.50095 2.61435 + vertex 0.862605 1.49595 2.61433 + vertex 0.865834 1.49927 2.61608 + endloop + endfacet + facet normal -0.473819 -0.00459898 0.88061 + outer loop + vertex 0.865834 1.49927 2.61608 + vertex 0.862605 1.49595 2.61433 + vertex 0.86585 1.49427 2.61606 + endloop + endfacet + facet normal -0.464176 -0.0045868 0.885731 + outer loop + vertex 0.86585 1.49427 2.61606 + vertex 0.869104 1.49759 2.61779 + vertex 0.865834 1.49927 2.61608 + endloop + endfacet + facet normal -0.465028 -0.00352141 0.885289 + outer loop + vertex 0.869117 1.4926 2.61777 + vertex 0.869104 1.49759 2.61779 + vertex 0.86585 1.49427 2.61606 + endloop + endfacet + facet normal -0.465529 -0.00477188 0.88502 + outer loop + vertex 0.86587 1.48928 2.61605 + vertex 0.869117 1.4926 2.61777 + vertex 0.86585 1.49427 2.61606 + endloop + endfacet + facet normal -0.475281 -0.00479589 0.879821 + outer loop + vertex 0.86585 1.49427 2.61606 + vertex 0.862629 1.49096 2.61431 + vertex 0.86587 1.48928 2.61605 + endloop + endfacet + facet normal -0.47609 -0.00682583 0.87937 + outer loop + vertex 0.862629 1.49096 2.61431 + vertex 0.862661 1.48597 2.61429 + vertex 0.86587 1.48928 2.61605 + endloop + endfacet + facet normal -0.476041 -0.00688724 0.879396 + outer loop + vertex 0.86587 1.48928 2.61605 + vertex 0.862661 1.48597 2.61429 + vertex 0.865904 1.48429 2.61603 + endloop + endfacet + facet normal -0.466685 -0.00684454 0.884397 + outer loop + vertex 0.865904 1.48429 2.61603 + vertex 0.869138 1.48761 2.61776 + vertex 0.86587 1.48928 2.61605 + endloop + endfacet + facet normal -0.466102 -0.00757094 0.884698 + outer loop + vertex 0.869176 1.48262 2.61774 + vertex 0.869138 1.48761 2.61776 + vertex 0.865904 1.48429 2.61603 + endloop + endfacet + facet normal -0.467327 -0.010652 0.88402 + outer loop + vertex 0.865952 1.47931 2.61599 + vertex 0.869176 1.48262 2.61774 + vertex 0.865904 1.48429 2.61603 + endloop + endfacet + facet normal -0.476488 -0.0107056 0.879116 + outer loop + vertex 0.865904 1.48429 2.61603 + vertex 0.862702 1.48099 2.61425 + vertex 0.865952 1.47931 2.61599 + endloop + endfacet + facet normal -0.477644 -0.0136375 0.878448 + outer loop + vertex 0.862702 1.48099 2.61425 + vertex 0.862748 1.47599 2.6142 + vertex 0.865952 1.47931 2.61599 + endloop + endfacet + facet normal -0.476743 -0.0147629 0.878919 + outer loop + vertex 0.865952 1.47931 2.61599 + vertex 0.862748 1.47599 2.6142 + vertex 0.866009 1.47432 2.61594 + endloop + endfacet + facet normal -0.467449 -0.0147096 0.883898 + outer loop + vertex 0.866009 1.47432 2.61594 + vertex 0.869231 1.47763 2.6177 + vertex 0.865952 1.47931 2.61599 + endloop + endfacet + facet normal -0.466547 -0.0158303 0.884355 + outer loop + vertex 0.869297 1.47264 2.61764 + vertex 0.869231 1.47763 2.6177 + vertex 0.866009 1.47432 2.61594 + endloop + endfacet + facet normal -0.467192 -0.0174756 0.883983 + outer loop + vertex 0.866072 1.46932 2.61587 + vertex 0.869297 1.47264 2.61764 + vertex 0.866009 1.47432 2.61594 + endloop + endfacet + facet normal -0.477391 -0.0175324 0.878516 + outer loop + vertex 0.866009 1.47432 2.61594 + vertex 0.862798 1.47098 2.61413 + vertex 0.866072 1.46932 2.61587 + endloop + endfacet + facet normal -0.477925 -0.0189182 0.878197 + outer loop + vertex 0.862798 1.47098 2.61413 + vertex 0.86286 1.46595 2.61405 + vertex 0.866072 1.46932 2.61587 + endloop + endfacet + facet normal -0.477948 -0.0188894 0.878185 + outer loop + vertex 0.866072 1.46932 2.61587 + vertex 0.86286 1.46595 2.61405 + vertex 0.866138 1.46431 2.6158 + endloop + endfacet + facet normal -0.467016 -0.0188289 0.884048 + outer loop + vertex 0.866138 1.46431 2.6158 + vertex 0.869367 1.46766 2.61758 + vertex 0.866072 1.46932 2.61587 + endloop + endfacet + facet normal -0.467233 -0.0185619 0.883939 + outer loop + vertex 0.869434 1.46267 2.61751 + vertex 0.869367 1.46766 2.61758 + vertex 0.866138 1.46431 2.6158 + endloop + endfacet + facet normal -0.467506 -0.0192775 0.88378 + outer loop + vertex 0.866196 1.45929 2.61572 + vertex 0.869434 1.46267 2.61751 + vertex 0.866138 1.46431 2.6158 + endloop + endfacet + facet normal -0.478711 -0.0193114 0.87776 + outer loop + vertex 0.866138 1.46431 2.6158 + vertex 0.862924 1.46091 2.61398 + vertex 0.866196 1.45929 2.61572 + endloop + endfacet + facet normal -0.479089 -0.020322 0.877531 + outer loop + vertex 0.862924 1.46091 2.61398 + vertex 0.862973 1.45588 2.61389 + vertex 0.866196 1.45929 2.61572 + endloop + endfacet + facet normal -0.479909 -0.0193176 0.877106 + outer loop + vertex 0.866196 1.45929 2.61572 + vertex 0.862973 1.45588 2.61389 + vertex 0.866238 1.45427 2.61564 + endloop + endfacet + facet normal -0.468644 -0.0193291 0.883176 + outer loop + vertex 0.866238 1.45427 2.61564 + vertex 0.869486 1.45768 2.61743 + vertex 0.866196 1.45929 2.61572 + endloop + endfacet + facet normal -0.469824 -0.0178875 0.882579 + outer loop + vertex 0.869526 1.45267 2.61735 + vertex 0.869486 1.45768 2.61743 + vertex 0.866238 1.45427 2.61564 + endloop + endfacet + facet normal -0.470435 -0.0195301 0.882219 + outer loop + vertex 0.866291 1.44925 2.61555 + vertex 0.869526 1.45267 2.61735 + vertex 0.866238 1.45427 2.61564 + endloop + endfacet + facet normal -0.481134 -0.0195487 0.876429 + outer loop + vertex 0.866238 1.45427 2.61564 + vertex 0.863024 1.45085 2.6138 + vertex 0.866291 1.44925 2.61555 + endloop + endfacet + facet normal -0.481786 -0.0213139 0.87603 + outer loop + vertex 0.863024 1.45085 2.6138 + vertex 0.863153 1.44583 2.61374 + vertex 0.866291 1.44925 2.61555 + endloop + endfacet + facet normal -0.482238 -0.0207738 0.875794 + outer loop + vertex 0.866291 1.44925 2.61555 + vertex 0.863153 1.44583 2.61374 + vertex 0.866412 1.44424 2.6155 + endloop + endfacet + facet normal -0.472165 -0.0205899 0.88127 + outer loop + vertex 0.866412 1.44424 2.6155 + vertex 0.869582 1.44765 2.61728 + vertex 0.866291 1.44925 2.61555 + endloop + endfacet + facet normal -0.472619 -0.0200467 0.881039 + outer loop + vertex 0.869673 1.44261 2.61721 + vertex 0.869582 1.44765 2.61728 + vertex 0.866412 1.44424 2.6155 + endloop + endfacet + facet normal -0.473585 -0.0225979 0.880458 + outer loop + vertex 0.866601 1.43938 2.61548 + vertex 0.869673 1.44261 2.61721 + vertex 0.866412 1.44424 2.6155 + endloop + endfacet + facet normal -0.483225 -0.0229497 0.875195 + outer loop + vertex 0.866412 1.44424 2.6155 + vertex 0.863452 1.4409 2.61378 + vertex 0.866601 1.43938 2.61548 + endloop + endfacet + facet normal -0.484013 -0.0251413 0.8747 + outer loop + vertex 0.863452 1.4409 2.61378 + vertex 0.86402 1.43676 2.61397 + vertex 0.866601 1.43938 2.61548 + endloop + endfacet + facet normal -0.482544 -0.0270213 0.875455 + outer loop + vertex 0.866601 1.43938 2.61548 + vertex 0.86402 1.43676 2.61397 + vertex 0.866586 1.43462 2.61532 + endloop + endfacet + facet normal -0.474557 -0.0271887 0.879805 + outer loop + vertex 0.866586 1.43462 2.61532 + vertex 0.869752 1.43761 2.61712 + vertex 0.866601 1.43938 2.61548 + endloop + endfacet + facet normal -0.474677 -0.0270252 0.879745 + outer loop + vertex 0.869797 1.43263 2.61699 + vertex 0.869752 1.43761 2.61712 + vertex 0.866586 1.43462 2.61532 + endloop + endfacet + facet normal -0.476327 -0.0305443 0.878738 + outer loop + vertex 0.866574 1.42968 2.61514 + vertex 0.869797 1.43263 2.61699 + vertex 0.866586 1.43462 2.61532 + endloop + endfacet + facet normal -0.487162 -0.0303033 0.872786 + outer loop + vertex 0.866586 1.43462 2.61532 + vertex 0.862989 1.43231 2.61323 + vertex 0.866574 1.42968 2.61514 + endloop + endfacet + facet normal -0.488372 -0.0325032 0.87203 + outer loop + vertex 0.862989 1.43231 2.61323 + vertex 0.863478 1.4268 2.6133 + vertex 0.866574 1.42968 2.61514 + endloop + endfacet + facet normal -0.48815 -0.0328149 0.872143 + outer loop + vertex 0.866574 1.42968 2.61514 + vertex 0.863478 1.4268 2.6133 + vertex 0.866864 1.42469 2.61512 + endloop + endfacet + facet normal -0.477208 -0.0322103 0.8782 + outer loop + vertex 0.866864 1.42469 2.61512 + vertex 0.869925 1.42768 2.61689 + vertex 0.866574 1.42968 2.61514 + endloop + endfacet + facet normal -0.476557 -0.0330675 0.878522 + outer loop + vertex 0.870256 1.42275 2.61689 + vertex 0.869925 1.42768 2.61689 + vertex 0.866864 1.42469 2.61512 + endloop + endfacet + facet normal -0.476946 -0.0339696 0.878276 + outer loop + vertex 0.8673 1.41983 2.61517 + vertex 0.870256 1.42275 2.61689 + vertex 0.866864 1.42469 2.61512 + endloop + endfacet + facet normal -0.489007 -0.0351177 0.871573 + outer loop + vertex 0.866864 1.42469 2.61512 + vertex 0.863886 1.42175 2.61333 + vertex 0.8673 1.41983 2.61517 + endloop + endfacet + facet normal -0.489593 -0.0365271 0.871186 + outer loop + vertex 0.863886 1.42175 2.61333 + vertex 0.864383 1.41635 2.61338 + vertex 0.8673 1.41983 2.61517 + endloop + endfacet + facet normal -0.489504 -0.0366248 0.871231 + outer loop + vertex 0.867767 1.41583 2.61526 + vertex 0.8673 1.41983 2.61517 + vertex 0.864383 1.41635 2.61338 + endloop + endfacet + facet normal -0.489669 -0.0382925 0.871067 + outer loop + vertex 0.867767 1.41583 2.61526 + vertex 0.864383 1.41635 2.61338 + vertex 0.866688 1.41166 2.61447 + endloop + endfacet + facet normal -0.482355 -0.0409352 0.875019 + outer loop + vertex 0.866688 1.41166 2.61447 + vertex 0.869629 1.41349 2.61618 + vertex 0.867767 1.41583 2.61526 + endloop + endfacet + facet normal -0.481775 -0.042116 0.875283 + outer loop + vertex 0.869629 1.41349 2.61618 + vertex 0.866688 1.41166 2.61447 + vertex 0.870142 1.40945 2.61627 + endloop + endfacet + facet normal -0.469048 -0.0403459 0.88225 + outer loop + vertex 0.870142 1.40945 2.61627 + vertex 0.872588 1.41272 2.61772 + vertex 0.869629 1.41349 2.61618 + endloop + endfacet + facet normal -0.468494 -0.0373467 0.882677 + outer loop + vertex 0.869629 1.41349 2.61618 + vertex 0.872588 1.41272 2.61772 + vertex 0.870824 1.41745 2.61698 + endloop + endfacet + facet normal -0.463536 -0.0350771 0.885383 + outer loop + vertex 0.872588 1.41272 2.61772 + vertex 0.874711 1.41633 2.61897 + vertex 0.870824 1.41745 2.61698 + endloop + endfacet + facet normal -0.463638 -0.0355563 0.885311 + outer loop + vertex 0.874711 1.41633 2.61897 + vertex 0.873741 1.42105 2.61865 + vertex 0.870824 1.41745 2.61698 + endloop + endfacet + facet normal -0.465126 -0.0340148 0.884591 + outer loop + vertex 0.870824 1.41745 2.61698 + vertex 0.873741 1.42105 2.61865 + vertex 0.870256 1.42275 2.61689 + endloop + endfacet + facet normal -0.464863 -0.0333022 0.884756 + outer loop + vertex 0.873741 1.42105 2.61865 + vertex 0.873284 1.42596 2.6186 + vertex 0.870256 1.42275 2.61689 + endloop + endfacet + facet normal -0.468443 -0.0409298 0.882545 + outer loop + vertex 0.873578 1.40787 2.61802 + vertex 0.872588 1.41272 2.61772 + vertex 0.870142 1.40945 2.61627 + endloop + endfacet + facet normal -0.468922 -0.0423245 0.882225 + outer loop + vertex 0.870678 1.40446 2.61631 + vertex 0.873578 1.40787 2.61802 + vertex 0.870142 1.40945 2.61627 + endloop + endfacet + facet normal -0.480217 -0.0435929 0.876066 + outer loop + vertex 0.870142 1.40945 2.61627 + vertex 0.867294 1.40623 2.61455 + vertex 0.870678 1.40446 2.61631 + endloop + endfacet + facet normal -0.480939 -0.0454691 0.875574 + outer loop + vertex 0.867294 1.40623 2.61455 + vertex 0.867614 1.40105 2.61445 + vertex 0.870678 1.40446 2.61631 + endloop + endfacet + facet normal -0.480656 -0.0457987 0.875712 + outer loop + vertex 0.870678 1.40446 2.61631 + vertex 0.867614 1.40105 2.61445 + vertex 0.870936 1.39935 2.61619 + endloop + endfacet + facet normal -0.469597 -0.0453875 0.881714 + outer loop + vertex 0.870936 1.39935 2.61619 + vertex 0.874068 1.40277 2.61803 + vertex 0.870678 1.40446 2.61631 + endloop + endfacet + facet normal -0.469271 -0.0457689 0.881868 + outer loop + vertex 0.87426 1.3977 2.61787 + vertex 0.874068 1.40277 2.61803 + vertex 0.870936 1.39935 2.61619 + endloop + endfacet + facet normal -0.470492 -0.0490841 0.881038 + outer loop + vertex 0.871036 1.39428 2.61596 + vertex 0.87426 1.3977 2.61787 + vertex 0.870936 1.39935 2.61619 + endloop + endfacet + facet normal -0.481332 -0.0490327 0.875166 + outer loop + vertex 0.870936 1.39935 2.61619 + vertex 0.867753 1.39594 2.61425 + vertex 0.871036 1.39428 2.61596 + endloop + endfacet + facet normal -0.48212 -0.0511666 0.87461 + outer loop + vertex 0.867753 1.39594 2.61425 + vertex 0.867902 1.39089 2.61403 + vertex 0.871036 1.39428 2.61596 + endloop + endfacet + facet normal -0.481718 -0.0516495 0.874803 + outer loop + vertex 0.871036 1.39428 2.61596 + vertex 0.867902 1.39089 2.61403 + vertex 0.871166 1.3893 2.61574 + endloop + endfacet + facet normal -0.471192 -0.0516311 0.880518 + outer loop + vertex 0.871166 1.3893 2.61574 + vertex 0.874327 1.39267 2.61762 + vertex 0.871036 1.39428 2.61596 + endloop + endfacet + facet normal -0.47067 -0.0522556 0.880761 + outer loop + vertex 0.874426 1.38769 2.61738 + vertex 0.874327 1.39267 2.61762 + vertex 0.871166 1.3893 2.61574 + endloop + endfacet + facet normal -0.471262 -0.0538811 0.880346 + outer loop + vertex 0.871424 1.38452 2.61558 + vertex 0.874426 1.38769 2.61738 + vertex 0.871166 1.3893 2.61574 + endloop + endfacet + facet normal -0.481595 -0.0542579 0.874713 + outer loop + vertex 0.871166 1.3893 2.61574 + vertex 0.868256 1.38601 2.61393 + vertex 0.871424 1.38452 2.61558 + endloop + endfacet + facet normal -0.481894 -0.0551378 0.874493 + outer loop + vertex 0.868256 1.38601 2.61393 + vertex 0.868947 1.38194 2.61405 + vertex 0.871424 1.38452 2.61558 + endloop + endfacet + facet normal -0.479886 -0.0576215 0.875436 + outer loop + vertex 0.871424 1.38452 2.61558 + vertex 0.868947 1.38194 2.61405 + vertex 0.871632 1.37983 2.61539 + endloop + endfacet + facet normal -0.471859 -0.0574468 0.879801 + outer loop + vertex 0.871632 1.37983 2.61539 + vertex 0.874622 1.38276 2.61718 + vertex 0.871424 1.38452 2.61558 + endloop + endfacet + facet normal -0.471971 -0.057302 0.87975 + outer loop + vertex 0.875023 1.37776 2.61707 + vertex 0.874622 1.38276 2.61718 + vertex 0.871632 1.37983 2.61539 + endloop + endfacet + facet normal -0.460806 -0.0565385 0.885698 + outer loop + vertex 0.875023 1.37776 2.61707 + vertex 0.878012 1.38102 2.61883 + vertex 0.874622 1.38276 2.61718 + endloop + endfacet + facet normal -0.48326 -0.0633227 0.873184 + outer loop + vertex 0.868947 1.38194 2.61405 + vertex 0.868179 1.37743 2.6133 + vertex 0.871632 1.37983 2.61539 + endloop + endfacet + facet normal -0.48451 -0.0610587 0.872652 + outer loop + vertex 0.871632 1.37983 2.61539 + vertex 0.868179 1.37743 2.6133 + vertex 0.872043 1.37488 2.61527 + endloop + endfacet + facet normal -0.493553 -0.0606395 0.867599 + outer loop + vertex 0.868179 1.37743 2.6133 + vertex 0.868947 1.38194 2.61405 + vertex 0.865631 1.38225 2.61219 + endloop + endfacet + facet normal -0.496122 -0.0623663 0.86601 + outer loop + vertex 0.864706 1.37805 2.61136 + vertex 0.868179 1.37743 2.6133 + vertex 0.865631 1.38225 2.61219 + endloop + endfacet + facet normal -0.506103 -0.0590615 0.860448 + outer loop + vertex 0.864706 1.37805 2.61136 + vertex 0.865631 1.38225 2.61219 + vertex 0.862687 1.38045 2.61033 + endloop + endfacet + facet normal -0.513004 -0.0668749 0.855777 + outer loop + vertex 0.861756 1.37629 2.60945 + vertex 0.864706 1.37805 2.61136 + vertex 0.862687 1.38045 2.61033 + endloop + endfacet + facet normal -0.522444 -0.0635969 0.850299 + outer loop + vertex 0.862687 1.38045 2.61033 + vertex 0.859362 1.38112 2.60834 + vertex 0.861756 1.37629 2.60945 + endloop + endfacet + facet normal -0.525133 -0.0653427 0.848508 + outer loop + vertex 0.861756 1.37629 2.60945 + vertex 0.859362 1.38112 2.60834 + vertex 0.858511 1.37677 2.60748 + endloop + endfacet + facet normal -0.525336 -0.0681518 0.848161 + outer loop + vertex 0.859149 1.37271 2.60755 + vertex 0.861756 1.37629 2.60945 + vertex 0.858511 1.37677 2.60748 + endloop + endfacet + facet normal -0.535947 -0.0699333 0.841351 + outer loop + vertex 0.859149 1.37271 2.60755 + vertex 0.858511 1.37677 2.60748 + vertex 0.856124 1.37462 2.60578 + endloop + endfacet + facet normal -0.536731 -0.0717834 0.840694 + outer loop + vertex 0.856336 1.36984 2.60551 + vertex 0.859149 1.37271 2.60755 + vertex 0.856124 1.37462 2.60578 + endloop + endfacet + facet normal -0.545776 -0.0718518 0.834845 + outer loop + vertex 0.856124 1.37462 2.60578 + vertex 0.852866 1.3725 2.60347 + vertex 0.856336 1.36984 2.60551 + endloop + endfacet + facet normal -0.547268 -0.0747392 0.833614 + outer loop + vertex 0.852866 1.3725 2.60347 + vertex 0.853493 1.36692 2.60338 + vertex 0.856336 1.36984 2.60551 + endloop + endfacet + facet normal -0.54794 -0.0738206 0.833254 + outer loop + vertex 0.856336 1.36984 2.60551 + vertex 0.853493 1.36692 2.60338 + vertex 0.856778 1.36476 2.60535 + endloop + endfacet + facet normal -0.536889 -0.0730868 0.840481 + outer loop + vertex 0.856778 1.36476 2.60535 + vertex 0.859607 1.36782 2.60742 + vertex 0.856336 1.36984 2.60551 + endloop + endfacet + facet normal -0.536472 -0.07362 0.840701 + outer loop + vertex 0.860055 1.3628 2.60727 + vertex 0.859607 1.36782 2.60742 + vertex 0.856778 1.36476 2.60535 + endloop + endfacet + facet normal -0.537013 -0.074982 0.840235 + outer loop + vertex 0.857285 1.35974 2.60522 + vertex 0.860055 1.3628 2.60727 + vertex 0.856778 1.36476 2.60535 + endloop + endfacet + facet normal -0.549266 -0.0760223 0.832182 + outer loop + vertex 0.856778 1.36476 2.60535 + vertex 0.854002 1.36178 2.60324 + vertex 0.857285 1.35974 2.60522 + endloop + endfacet + facet normal -0.550538 -0.0791671 0.831048 + outer loop + vertex 0.854002 1.36178 2.60324 + vertex 0.854588 1.35628 2.60311 + vertex 0.857285 1.35974 2.60522 + endloop + endfacet + facet normal -0.551096 -0.0785426 0.830737 + outer loop + vertex 0.857825 1.35562 2.60519 + vertex 0.857285 1.35974 2.60522 + vertex 0.854588 1.35628 2.60311 + endloop + endfacet + facet normal -0.551369 -0.081316 0.830289 + outer loop + vertex 0.857825 1.35562 2.60519 + vertex 0.854588 1.35628 2.60311 + vertex 0.856984 1.35142 2.60422 + endloop + endfacet + facet normal -0.541641 -0.0846587 0.836336 + outer loop + vertex 0.856984 1.35142 2.60422 + vertex 0.859787 1.35322 2.60622 + vertex 0.857825 1.35562 2.60519 + endloop + endfacet + facet normal -0.535174 -0.0772877 0.841199 + outer loop + vertex 0.859787 1.35322 2.60622 + vertex 0.860707 1.35745 2.60719 + vertex 0.857825 1.35562 2.60519 + endloop + endfacet + facet normal -0.525383 -0.0807605 0.847025 + outer loop + vertex 0.859787 1.35322 2.60622 + vertex 0.863187 1.35256 2.60827 + vertex 0.860707 1.35745 2.60719 + endloop + endfacet + facet normal -0.522554 -0.0789048 0.848948 + outer loop + vertex 0.863187 1.35256 2.60827 + vertex 0.863957 1.35714 2.60917 + vertex 0.860707 1.35745 2.60719 + endloop + endfacet + facet normal -0.52562 -0.0831398 0.846647 + outer loop + vertex 0.86049 1.349 2.60624 + vertex 0.863187 1.35256 2.60827 + vertex 0.859787 1.35322 2.60622 + endloop + endfacet + facet normal -0.541099 -0.0857659 0.836574 + outer loop + vertex 0.859787 1.35322 2.60622 + vertex 0.856984 1.35142 2.60422 + vertex 0.86049 1.349 2.60624 + endloop + endfacet + facet normal -0.540122 -0.0836502 0.837419 + outer loop + vertex 0.856984 1.35142 2.60422 + vertex 0.857902 1.34613 2.60429 + vertex 0.86049 1.349 2.60624 + endloop + endfacet + facet normal -0.539521 -0.0844042 0.837731 + outer loop + vertex 0.86049 1.349 2.60624 + vertex 0.857902 1.34613 2.60429 + vertex 0.861013 1.34418 2.60609 + endloop + endfacet + facet normal -0.526403 -0.0832394 0.84615 + outer loop + vertex 0.861013 1.34418 2.60609 + vertex 0.864221 1.34636 2.6083 + vertex 0.86049 1.349 2.60624 + endloop + endfacet + facet normal -0.526924 -0.0822442 0.845924 + outer loop + vertex 0.86352 1.34188 2.60743 + vertex 0.864221 1.34636 2.6083 + vertex 0.861013 1.34418 2.60609 + endloop + endfacet + facet normal -0.530549 -0.087845 0.84309 + outer loop + vertex 0.861199 1.33969 2.60574 + vertex 0.86352 1.34188 2.60743 + vertex 0.861013 1.34418 2.60609 + endloop + endfacet + facet normal -0.538196 -0.0877833 0.838236 + outer loop + vertex 0.861013 1.34418 2.60609 + vertex 0.858738 1.34198 2.6044 + vertex 0.861199 1.33969 2.60574 + endloop + endfacet + facet normal -0.541412 -0.0927718 0.835623 + outer loop + vertex 0.858738 1.34198 2.6044 + vertex 0.858012 1.33758 2.60344 + vertex 0.861199 1.33969 2.60574 + endloop + endfacet + facet normal -0.541579 -0.0924417 0.835551 + outer loop + vertex 0.861199 1.33969 2.60574 + vertex 0.858012 1.33758 2.60344 + vertex 0.861573 1.33491 2.60546 + endloop + endfacet + facet normal -0.529546 -0.0919653 0.843281 + outer loop + vertex 0.861573 1.33491 2.60546 + vertex 0.864289 1.33778 2.60748 + vertex 0.861199 1.33969 2.60574 + endloop + endfacet + facet normal -0.528754 -0.0929856 0.843666 + outer loop + vertex 0.864943 1.33287 2.60734 + vertex 0.864289 1.33778 2.60748 + vertex 0.861573 1.33491 2.60546 + endloop + endfacet + facet normal -0.528958 -0.0934907 0.843483 + outer loop + vertex 0.862221 1.32984 2.6053 + vertex 0.864943 1.33287 2.60734 + vertex 0.861573 1.33491 2.60546 + endloop + endfacet + facet normal -0.540907 -0.0947804 0.835725 + outer loop + vertex 0.861573 1.33491 2.60546 + vertex 0.858797 1.33198 2.60333 + vertex 0.862221 1.32984 2.6053 + endloop + endfacet + facet normal -0.54138 -0.095945 0.835286 + outer loop + vertex 0.858797 1.33198 2.60333 + vertex 0.859547 1.32634 2.60317 + vertex 0.862221 1.32984 2.6053 + endloop + endfacet + facet normal -0.540625 -0.0967625 0.83568 + outer loop + vertex 0.862847 1.32569 2.60522 + vertex 0.862221 1.32984 2.6053 + vertex 0.859547 1.32634 2.60317 + endloop + endfacet + facet normal -0.540726 -0.0978857 0.835484 + outer loop + vertex 0.862847 1.32569 2.60522 + vertex 0.859547 1.32634 2.60317 + vertex 0.862022 1.3215 2.6042 + endloop + endfacet + facet normal -0.531384 -0.101094 0.841077 + outer loop + vertex 0.862022 1.3215 2.6042 + vertex 0.864858 1.3233 2.60621 + vertex 0.862847 1.32569 2.60522 + endloop + endfacet + facet normal -0.526816 -0.0958191 0.844561 + outer loop + vertex 0.864858 1.3233 2.60621 + vertex 0.865746 1.32752 2.60724 + vertex 0.862847 1.32569 2.60522 + endloop + endfacet + facet normal -0.518868 -0.0986149 0.849148 + outer loop + vertex 0.864858 1.3233 2.60621 + vertex 0.8683 1.32267 2.60824 + vertex 0.865746 1.32752 2.60724 + endloop + endfacet + facet normal -0.51901 -0.100321 0.848861 + outer loop + vertex 0.865578 1.31912 2.60615 + vertex 0.8683 1.32267 2.60824 + vertex 0.864858 1.3233 2.60621 + endloop + endfacet + facet normal -0.518815 -0.100526 0.848956 + outer loop + vertex 0.869353 1.31655 2.60816 + vertex 0.8683 1.32267 2.60824 + vertex 0.865578 1.31912 2.60615 + endloop + endfacet + facet normal -0.519365 -0.101705 0.848479 + outer loop + vertex 0.866143 1.31435 2.60593 + vertex 0.869353 1.31655 2.60816 + vertex 0.865578 1.31912 2.60615 + endloop + endfacet + facet normal -0.529179 -0.102576 0.842287 + outer loop + vertex 0.865578 1.31912 2.60615 + vertex 0.862979 1.31627 2.60418 + vertex 0.866143 1.31435 2.60593 + endloop + endfacet + facet normal -0.529602 -0.103636 0.841891 + outer loop + vertex 0.862979 1.31627 2.60418 + vertex 0.863889 1.31218 2.60424 + vertex 0.866143 1.31435 2.60593 + endloop + endfacet + facet normal -0.52823 -0.105542 0.842516 + outer loop + vertex 0.866143 1.31435 2.60593 + vertex 0.863889 1.31218 2.60424 + vertex 0.866453 1.30988 2.60556 + endloop + endfacet + facet normal -0.539738 -0.105998 0.835133 + outer loop + vertex 0.863889 1.31218 2.60424 + vertex 0.862979 1.31627 2.60418 + vertex 0.860695 1.31259 2.60223 + endloop + endfacet + facet normal -0.539794 -0.107558 0.834898 + outer loop + vertex 0.863299 1.30773 2.60329 + vertex 0.863889 1.31218 2.60424 + vertex 0.860695 1.31259 2.60223 + endloop + endfacet + facet normal -0.542974 -0.109771 0.832544 + outer loop + vertex 0.859982 1.30844 2.60122 + vertex 0.863299 1.30773 2.60329 + vertex 0.860695 1.31259 2.60223 + endloop + endfacet + facet normal -0.552339 -0.106752 0.826756 + outer loop + vertex 0.859982 1.30844 2.60122 + vertex 0.860695 1.31259 2.60223 + vertex 0.857982 1.3108 2.60019 + endloop + endfacet + facet normal -0.557369 -0.112851 0.82256 + outer loop + vertex 0.857355 1.30666 2.59919 + vertex 0.859982 1.30844 2.60122 + vertex 0.857982 1.3108 2.60019 + endloop + endfacet + facet normal -0.569101 -0.109256 0.814977 + outer loop + vertex 0.857982 1.3108 2.60019 + vertex 0.854804 1.31139 2.59805 + vertex 0.857355 1.30666 2.59919 + endloop + endfacet + facet normal -0.57083 -0.110524 0.813595 + outer loop + vertex 0.857355 1.30666 2.59919 + vertex 0.854804 1.31139 2.59805 + vertex 0.854248 1.30691 2.59705 + endloop + endfacet + facet normal -0.570835 -0.11001 0.813662 + outer loop + vertex 0.855402 1.30247 2.59726 + vertex 0.857355 1.30666 2.59919 + vertex 0.854248 1.30691 2.59705 + endloop + endfacet + facet normal -0.580833 -0.112967 0.806146 + outer loop + vertex 0.855402 1.30247 2.59726 + vertex 0.854248 1.30691 2.59705 + vertex 0.85215 1.30462 2.59522 + endloop + endfacet + facet normal -0.57952 -0.109651 0.807548 + outer loop + vertex 0.852878 1.30073 2.59521 + vertex 0.855402 1.30247 2.59726 + vertex 0.85215 1.30462 2.59522 + endloop + endfacet + facet normal -0.589662 -0.111532 0.799912 + outer loop + vertex 0.852878 1.30073 2.59521 + vertex 0.85215 1.30462 2.59522 + vertex 0.849788 1.30136 2.59302 + endloop + endfacet + facet normal -0.58972 -0.112368 0.799752 + outer loop + vertex 0.852878 1.30073 2.59521 + vertex 0.849788 1.30136 2.59302 + vertex 0.852315 1.29665 2.59422 + endloop + endfacet + facet normal -0.582328 -0.114619 0.804834 + outer loop + vertex 0.852315 1.29665 2.59422 + vertex 0.854823 1.2984 2.59629 + vertex 0.852878 1.30073 2.59521 + endloop + endfacet + facet normal -0.581941 -0.115376 0.805005 + outer loop + vertex 0.854823 1.2984 2.59629 + vertex 0.852315 1.29665 2.59422 + vertex 0.855608 1.2944 2.59628 + endloop + endfacet + facet normal -0.570414 -0.113125 0.81353 + outer loop + vertex 0.855608 1.2944 2.59628 + vertex 0.857973 1.29769 2.5984 + vertex 0.854823 1.2984 2.59629 + endloop + endfacet + facet normal -0.570417 -0.113158 0.813523 + outer loop + vertex 0.854823 1.2984 2.59629 + vertex 0.857973 1.29769 2.5984 + vertex 0.855402 1.30247 2.59726 + endloop + endfacet + facet normal -0.567924 -0.111345 0.815515 + outer loop + vertex 0.857973 1.29769 2.5984 + vertex 0.858517 1.30215 2.59938 + vertex 0.855402 1.30247 2.59726 + endloop + endfacet + facet normal -0.557891 -0.114016 0.822045 + outer loop + vertex 0.858517 1.30215 2.59938 + vertex 0.857973 1.29769 2.5984 + vertex 0.861149 1.29959 2.60081 + endloop + endfacet + facet normal -0.555234 -0.109979 0.82439 + outer loop + vertex 0.860766 1.30435 2.60119 + vertex 0.858517 1.30215 2.59938 + vertex 0.861149 1.29959 2.60081 + endloop + endfacet + facet normal -0.543267 -0.109649 0.832369 + outer loop + vertex 0.861149 1.29959 2.60081 + vertex 0.864418 1.30158 2.60321 + vertex 0.860766 1.30435 2.60119 + endloop + endfacet + facet normal -0.543139 -0.109396 0.832486 + outer loop + vertex 0.864418 1.30158 2.60321 + vertex 0.863299 1.30773 2.60329 + vertex 0.860766 1.30435 2.60119 + endloop + endfacet + facet normal -0.544735 -0.10656 0.83181 + outer loop + vertex 0.863763 1.29706 2.6022 + vertex 0.864418 1.30158 2.60321 + vertex 0.861149 1.29959 2.60081 + endloop + endfacet + facet normal -0.547763 -0.111107 0.829223 + outer loop + vertex 0.861457 1.29484 2.60038 + vertex 0.863763 1.29706 2.6022 + vertex 0.861149 1.29959 2.60081 + endloop + endfacet + facet normal -0.546107 -0.11346 0.829996 + outer loop + vertex 0.864717 1.29286 2.60226 + vertex 0.863763 1.29706 2.6022 + vertex 0.861457 1.29484 2.60038 + endloop + endfacet + facet normal -0.545788 -0.112627 0.83032 + outer loop + vertex 0.862249 1.28992 2.60024 + vertex 0.864717 1.29286 2.60226 + vertex 0.861457 1.29484 2.60038 + endloop + endfacet + facet normal -0.558424 -0.114405 0.821629 + outer loop + vertex 0.861457 1.29484 2.60038 + vertex 0.858872 1.2921 2.59824 + vertex 0.862249 1.28992 2.60024 + endloop + endfacet + facet normal -0.55794 -0.113206 0.822124 + outer loop + vertex 0.858872 1.2921 2.59824 + vertex 0.859765 1.28647 2.59807 + vertex 0.862249 1.28992 2.60024 + endloop + endfacet + facet normal -0.556705 -0.114506 0.82278 + outer loop + vertex 0.863014 1.2858 2.60018 + vertex 0.862249 1.28992 2.60024 + vertex 0.859765 1.28647 2.59807 + endloop + endfacet + facet normal -0.556347 -0.110093 0.823625 + outer loop + vertex 0.863014 1.2858 2.60018 + vertex 0.859765 1.28647 2.59807 + vertex 0.86238 1.28164 2.5992 + endloop + endfacet + facet normal -0.545088 -0.113469 0.830665 + outer loop + vertex 0.86238 1.28164 2.5992 + vertex 0.865053 1.28343 2.60119 + vertex 0.863014 1.2858 2.60018 + endloop + endfacet + facet normal -0.543076 -0.11104 0.832309 + outer loop + vertex 0.865053 1.28343 2.60119 + vertex 0.865762 1.28761 2.60221 + vertex 0.863014 1.2858 2.60018 + endloop + endfacet + facet normal -0.53264 -0.114342 0.838582 + outer loop + vertex 0.865053 1.28343 2.60119 + vertex 0.868423 1.28278 2.60325 + vertex 0.865762 1.28761 2.60221 + endloop + endfacet + facet normal -0.530162 -0.112589 0.840388 + outer loop + vertex 0.868423 1.28278 2.60325 + vertex 0.869001 1.28725 2.60421 + vertex 0.865762 1.28761 2.60221 + endloop + endfacet + facet normal -0.532171 -0.108526 0.839653 + outer loop + vertex 0.865833 1.27935 2.60116 + vertex 0.868423 1.28278 2.60325 + vertex 0.865053 1.28343 2.60119 + endloop + endfacet + facet normal -0.546291 -0.111142 0.830189 + outer loop + vertex 0.865053 1.28343 2.60119 + vertex 0.86238 1.28164 2.5992 + vertex 0.865833 1.27935 2.60116 + endloop + endfacet + facet normal -0.543722 -0.105157 0.832652 + outer loop + vertex 0.86238 1.28164 2.5992 + vertex 0.863535 1.2771 2.59938 + vertex 0.865833 1.27935 2.60116 + endloop + endfacet + facet normal -0.543562 -0.105381 0.832728 + outer loop + vertex 0.865833 1.27935 2.60116 + vertex 0.863535 1.2771 2.59938 + vertex 0.866169 1.27459 2.60078 + endloop + endfacet + facet normal -0.529883 -0.105122 0.84153 + outer loop + vertex 0.866169 1.27459 2.60078 + vertex 0.869493 1.27666 2.60313 + vertex 0.865833 1.27935 2.60116 + endloop + endfacet + facet normal -0.546149 -0.10933 0.830523 + outer loop + vertex 0.863535 1.2771 2.59938 + vertex 0.862941 1.27266 2.5984 + vertex 0.866169 1.27459 2.60078 + endloop + endfacet + facet normal -0.546869 -0.107794 0.83025 + outer loop + vertex 0.866169 1.27459 2.60078 + vertex 0.862941 1.27266 2.5984 + vertex 0.866399 1.26997 2.60033 + endloop + endfacet + facet normal -0.555124 -0.106888 0.824871 + outer loop + vertex 0.862941 1.27266 2.5984 + vertex 0.863535 1.2771 2.59938 + vertex 0.860376 1.27741 2.59729 + endloop + endfacet + facet normal -0.556236 -0.107688 0.824018 + outer loop + vertex 0.859752 1.2733 2.59633 + vertex 0.862941 1.27266 2.5984 + vertex 0.860376 1.27741 2.59729 + endloop + endfacet + facet normal -0.565536 -0.104877 0.818028 + outer loop + vertex 0.859752 1.2733 2.59633 + vertex 0.860376 1.27741 2.59729 + vertex 0.857802 1.27565 2.59528 + endloop + endfacet + facet normal -0.570727 -0.111167 0.81358 + outer loop + vertex 0.857211 1.27155 2.59431 + vertex 0.859752 1.2733 2.59633 + vertex 0.857802 1.27565 2.59528 + endloop + endfacet + facet normal -0.577881 -0.108999 0.80881 + outer loop + vertex 0.857802 1.27565 2.59528 + vertex 0.854662 1.27634 2.59314 + vertex 0.857211 1.27155 2.59431 + endloop + endfacet + facet normal -0.57733 -0.108595 0.809257 + outer loop + vertex 0.857211 1.27155 2.59431 + vertex 0.854662 1.27634 2.59314 + vertex 0.85415 1.27184 2.59217 + endloop + endfacet + facet normal -0.57727 -0.124344 0.80703 + outer loop + vertex 0.855374 1.26743 2.59236 + vertex 0.857211 1.27155 2.59431 + vertex 0.85415 1.27184 2.59217 + endloop + endfacet + facet normal -0.575813 -0.125408 0.807906 + outer loop + vertex 0.858459 1.26706 2.5945 + vertex 0.857211 1.27155 2.59431 + vertex 0.855374 1.26743 2.59236 + endloop + endfacet + facet normal -0.586555 -0.106179 0.802919 + outer loop + vertex 0.85415 1.27184 2.59217 + vertex 0.854662 1.27634 2.59314 + vertex 0.851552 1.27432 2.5906 + endloop + endfacet + facet normal -0.588145 -0.102826 0.802192 + outer loop + vertex 0.851552 1.27432 2.5906 + vertex 0.854662 1.27634 2.59314 + vertex 0.851083 1.27943 2.59091 + endloop + endfacet + facet normal -0.597697 -0.103268 0.795044 + outer loop + vertex 0.851083 1.27943 2.59091 + vertex 0.848377 1.27695 2.58855 + vertex 0.851552 1.27432 2.5906 + endloop + endfacet + facet normal -0.599105 -0.101001 0.794274 + outer loop + vertex 0.847511 1.28248 2.5886 + vertex 0.848377 1.27695 2.58855 + vertex 0.851083 1.27943 2.59091 + endloop + endfacet + facet normal -0.601127 -0.104915 0.792237 + outer loop + vertex 0.85052 1.2846 2.59116 + vertex 0.847511 1.28248 2.5886 + vertex 0.851083 1.27943 2.59091 + endloop + endfacet + facet normal -0.590041 -0.104127 0.80063 + outer loop + vertex 0.851083 1.27943 2.59091 + vertex 0.85382 1.28202 2.59326 + vertex 0.85052 1.2846 2.59116 + endloop + endfacet + facet normal -0.592836 -0.110006 0.797775 + outer loop + vertex 0.85382 1.28202 2.59326 + vertex 0.852997 1.28769 2.59343 + vertex 0.85052 1.2846 2.59116 + endloop + endfacet + facet normal -0.592068 -0.110945 0.798215 + outer loop + vertex 0.85052 1.2846 2.59116 + vertex 0.852997 1.28769 2.59343 + vertex 0.849944 1.28864 2.5913 + endloop + endfacet + facet normal -0.601407 -0.112037 0.791048 + outer loop + vertex 0.849944 1.28864 2.5913 + vertex 0.847694 1.28746 2.58942 + vertex 0.85052 1.2846 2.59116 + endloop + endfacet + facet normal -0.599719 -0.116294 0.791715 + outer loop + vertex 0.847694 1.28746 2.58942 + vertex 0.849944 1.28864 2.5913 + vertex 0.848083 1.29096 2.59023 + endloop + endfacet + facet normal -0.604937 -0.114845 0.787948 + outer loop + vertex 0.848083 1.29096 2.59023 + vertex 0.84513 1.29147 2.58804 + vertex 0.847694 1.28746 2.58942 + endloop + endfacet + facet normal -0.606684 -0.116511 0.786359 + outer loop + vertex 0.847694 1.28746 2.58942 + vertex 0.84513 1.29147 2.58804 + vertex 0.844981 1.28656 2.58719 + endloop + endfacet + facet normal -0.605095 -0.118922 0.787222 + outer loop + vertex 0.848083 1.29096 2.59023 + vertex 0.847281 1.29468 2.59017 + vertex 0.84513 1.29147 2.58804 + endloop + endfacet + facet normal -0.604543 -0.119514 0.787556 + outer loop + vertex 0.84419 1.29686 2.58813 + vertex 0.84513 1.29147 2.58804 + vertex 0.847281 1.29468 2.59017 + endloop + endfacet + facet normal -0.603173 -0.116118 0.789113 + outer loop + vertex 0.846709 1.29934 2.59042 + vertex 0.84419 1.29686 2.58813 + vertex 0.847281 1.29468 2.59017 + endloop + endfacet + facet normal -0.599604 -0.115827 0.79187 + outer loop + vertex 0.847281 1.29468 2.59017 + vertex 0.849281 1.29692 2.59202 + vertex 0.846709 1.29934 2.59042 + endloop + endfacet + facet normal -0.597044 -0.111418 0.794434 + outer loop + vertex 0.849281 1.29692 2.59202 + vertex 0.849788 1.30136 2.59302 + vertex 0.846709 1.29934 2.59042 + endloop + endfacet + facet normal -0.597086 -0.111328 0.794414 + outer loop + vertex 0.846709 1.29934 2.59042 + vertex 0.849788 1.30136 2.59302 + vertex 0.846288 1.30438 2.59081 + endloop + endfacet + facet normal -0.601043 -0.111426 0.791411 + outer loop + vertex 0.846288 1.30438 2.59081 + vertex 0.843558 1.30195 2.5884 + vertex 0.846709 1.29934 2.59042 + endloop + endfacet + facet normal -0.601262 -0.111066 0.791295 + outer loop + vertex 0.84279 1.30752 2.5886 + vertex 0.843558 1.30195 2.5884 + vertex 0.846288 1.30438 2.59081 + endloop + endfacet + facet normal -0.600273 -0.109259 0.792297 + outer loop + vertex 0.845891 1.30944 2.59121 + vertex 0.84279 1.30752 2.5886 + vertex 0.846288 1.30438 2.59081 + endloop + endfacet + facet normal -0.597419 -0.109205 0.794459 + outer loop + vertex 0.846288 1.30438 2.59081 + vertex 0.849036 1.30682 2.59322 + vertex 0.845891 1.30944 2.59121 + endloop + endfacet + facet normal -0.597388 -0.109143 0.794491 + outer loop + vertex 0.849036 1.30682 2.59322 + vertex 0.848496 1.31189 2.59351 + vertex 0.845891 1.30944 2.59121 + endloop + endfacet + facet normal -0.596914 -0.109884 0.794745 + outer loop + vertex 0.845891 1.30944 2.59121 + vertex 0.848496 1.31189 2.59351 + vertex 0.845395 1.3142 2.5915 + endloop + endfacet + facet normal -0.599492 -0.110035 0.792781 + outer loop + vertex 0.845395 1.3142 2.5915 + vertex 0.843326 1.31199 2.58962 + vertex 0.845891 1.30944 2.59121 + endloop + endfacet + facet normal -0.597538 -0.112788 0.793868 + outer loop + vertex 0.842212 1.31646 2.58942 + vertex 0.843326 1.31199 2.58962 + vertex 0.845395 1.3142 2.5915 + endloop + endfacet + facet normal -0.597106 -0.111749 0.79434 + outer loop + vertex 0.844679 1.31814 2.59151 + vertex 0.842212 1.31646 2.58942 + vertex 0.845395 1.3142 2.5915 + endloop + endfacet + facet normal -0.595259 -0.111419 0.795772 + outer loop + vertex 0.845395 1.3142 2.5915 + vertex 0.84775 1.31739 2.5937 + vertex 0.844679 1.31814 2.59151 + endloop + endfacet + facet normal -0.595286 -0.111711 0.795711 + outer loop + vertex 0.844679 1.31814 2.59151 + vertex 0.84775 1.31739 2.5937 + vertex 0.845252 1.32219 2.59251 + endloop + endfacet + facet normal -0.593763 -0.11219 0.79678 + outer loop + vertex 0.844679 1.31814 2.59151 + vertex 0.845252 1.32219 2.59251 + vertex 0.84278 1.32049 2.59043 + endloop + endfacet + facet normal -0.591617 -0.109025 0.798814 + outer loop + vertex 0.84775 1.31739 2.5937 + vertex 0.848285 1.32186 2.59471 + vertex 0.845252 1.32219 2.59251 + endloop + endfacet + facet normal -0.591604 -0.107007 0.799096 + outer loop + vertex 0.848285 1.32186 2.59471 + vertex 0.847144 1.32636 2.59447 + vertex 0.845252 1.32219 2.59251 + endloop + endfacet + facet normal -0.588146 -0.109604 0.801293 + outer loop + vertex 0.845252 1.32219 2.59251 + vertex 0.847144 1.32636 2.59447 + vertex 0.844088 1.32669 2.59227 + endloop + endfacet + facet normal -0.59138 -0.110572 0.798776 + outer loop + vertex 0.845252 1.32219 2.59251 + vertex 0.844088 1.32669 2.59227 + vertex 0.842019 1.32445 2.59043 + endloop + endfacet + facet normal -0.59283 -0.114078 0.797207 + outer loop + vertex 0.84278 1.32049 2.59043 + vertex 0.845252 1.32219 2.59251 + vertex 0.842019 1.32445 2.59043 + endloop + endfacet + facet normal -0.595842 -0.114656 0.794875 + outer loop + vertex 0.84278 1.32049 2.59043 + vertex 0.842019 1.32445 2.59043 + vertex 0.839722 1.32123 2.58824 + endloop + endfacet + facet normal -0.595833 -0.114556 0.794896 + outer loop + vertex 0.84278 1.32049 2.59043 + vertex 0.839722 1.32123 2.58824 + vertex 0.842212 1.31646 2.58942 + endloop + endfacet + facet normal -0.598134 -0.116248 0.79292 + outer loop + vertex 0.842212 1.31646 2.58942 + vertex 0.839722 1.32123 2.58824 + vertex 0.839239 1.31679 2.58723 + endloop + endfacet + facet normal -0.598131 -0.114566 0.793167 + outer loop + vertex 0.84033 1.31236 2.58741 + vertex 0.842212 1.31646 2.58942 + vertex 0.839239 1.31679 2.58723 + endloop + endfacet + facet normal -0.603188 -0.115977 0.789122 + outer loop + vertex 0.84033 1.31236 2.58741 + vertex 0.839239 1.31679 2.58723 + vertex 0.837201 1.31456 2.58534 + endloop + endfacet + facet normal -0.602443 -0.114127 0.789961 + outer loop + vertex 0.837857 1.3107 2.58528 + vertex 0.84033 1.31236 2.58741 + vertex 0.837201 1.31456 2.58534 + endloop + endfacet + facet normal -0.610968 -0.115472 0.783188 + outer loop + vertex 0.837857 1.3107 2.58528 + vertex 0.837201 1.31456 2.58534 + vertex 0.83488 1.31134 2.58306 + endloop + endfacet + facet normal -0.610753 -0.112251 0.783824 + outer loop + vertex 0.837857 1.3107 2.58528 + vertex 0.83488 1.31134 2.58306 + vertex 0.837257 1.30665 2.58424 + endloop + endfacet + facet normal -0.605373 -0.114059 0.787727 + outer loop + vertex 0.837257 1.30665 2.58424 + vertex 0.839719 1.30833 2.58637 + vertex 0.837857 1.3107 2.58528 + endloop + endfacet + facet normal -0.6061 -0.112556 0.787384 + outer loop + vertex 0.839719 1.30833 2.58637 + vertex 0.837257 1.30665 2.58424 + vertex 0.84044 1.30433 2.58635 + endloop + endfacet + facet normal -0.602098 -0.11185 0.790549 + outer loop + vertex 0.84044 1.30433 2.58635 + vertex 0.84279 1.30752 2.5886 + vertex 0.839719 1.30833 2.58637 + endloop + endfacet + facet normal -0.602145 -0.112301 0.790449 + outer loop + vertex 0.839719 1.30833 2.58637 + vertex 0.84279 1.30752 2.5886 + vertex 0.84033 1.31236 2.58741 + endloop + endfacet + facet normal -0.59961 -0.110479 0.79263 + outer loop + vertex 0.84279 1.30752 2.5886 + vertex 0.843326 1.31199 2.58962 + vertex 0.84033 1.31236 2.58741 + endloop + endfacet + facet normal -0.606919 -0.114507 0.786472 + outer loop + vertex 0.837257 1.30665 2.58424 + vertex 0.838401 1.30213 2.58446 + vertex 0.84044 1.30433 2.58635 + endloop + endfacet + facet normal -0.605775 -0.116121 0.787116 + outer loop + vertex 0.84044 1.30433 2.58635 + vertex 0.838401 1.30213 2.58446 + vertex 0.84101 1.29951 2.58608 + endloop + endfacet + facet normal -0.604797 -0.116049 0.787879 + outer loop + vertex 0.84101 1.29951 2.58608 + vertex 0.843558 1.30195 2.5884 + vertex 0.84044 1.30433 2.58635 + endloop + endfacet + facet normal -0.604774 -0.116084 0.787891 + outer loop + vertex 0.84419 1.29686 2.58813 + vertex 0.843558 1.30195 2.5884 + vertex 0.84101 1.29951 2.58608 + endloop + endfacet + facet normal -0.607638 -0.121916 0.784801 + outer loop + vertex 0.841572 1.29442 2.58573 + vertex 0.84419 1.29686 2.58813 + vertex 0.84101 1.29951 2.58608 + endloop + endfacet + facet normal -0.610322 -0.122066 0.782693 + outer loop + vertex 0.84101 1.29951 2.58608 + vertex 0.837991 1.29766 2.58344 + vertex 0.841572 1.29442 2.58573 + endloop + endfacet + facet normal -0.609944 -0.122915 0.782854 + outer loop + vertex 0.838401 1.30213 2.58446 + vertex 0.837991 1.29766 2.58344 + vertex 0.84101 1.29951 2.58608 + endloop + endfacet + facet normal -0.612953 -0.122129 0.780623 + outer loop + vertex 0.837991 1.29766 2.58344 + vertex 0.838401 1.30213 2.58446 + vertex 0.835438 1.30258 2.58221 + endloop + endfacet + facet normal -0.612815 -0.116235 0.781631 + outer loop + vertex 0.838401 1.30213 2.58446 + vertex 0.837257 1.30665 2.58424 + vertex 0.835438 1.30258 2.58221 + endloop + endfacet + facet normal -0.613541 -0.115669 0.781146 + outer loop + vertex 0.835438 1.30258 2.58221 + vertex 0.837257 1.30665 2.58424 + vertex 0.834303 1.30698 2.58196 + endloop + endfacet + facet normal -0.613544 -0.114294 0.781346 + outer loop + vertex 0.837257 1.30665 2.58424 + vertex 0.83488 1.31134 2.58306 + vertex 0.834303 1.30698 2.58196 + endloop + endfacet + facet normal -0.61169 -0.11464 0.782747 + outer loop + vertex 0.834208 1.31672 2.58332 + vertex 0.83488 1.31134 2.58306 + vertex 0.837201 1.31456 2.58534 + endloop + endfacet + facet normal -0.612504 -0.116646 0.781813 + outer loop + vertex 0.836711 1.31924 2.58566 + vertex 0.834208 1.31672 2.58332 + vertex 0.837201 1.31456 2.58534 + endloop + endfacet + facet normal -0.614316 -0.113905 0.780796 + outer loop + vertex 0.833577 1.32183 2.58357 + vertex 0.834208 1.31672 2.58332 + vertex 0.836711 1.31924 2.58566 + endloop + endfacet + facet normal -0.615084 -0.115513 0.779954 + outer loop + vertex 0.83619 1.32433 2.586 + vertex 0.833577 1.32183 2.58357 + vertex 0.836711 1.31924 2.58566 + endloop + endfacet + facet normal -0.617868 -0.111083 0.778396 + outer loop + vertex 0.832604 1.32745 2.5836 + vertex 0.833577 1.32183 2.58357 + vertex 0.83619 1.32433 2.586 + endloop + endfacet + facet normal -0.619616 -0.114549 0.776502 + outer loop + vertex 0.835538 1.32953 2.58625 + vertex 0.832604 1.32745 2.5836 + vertex 0.83619 1.32433 2.586 + endloop + endfacet + facet normal -0.621191 -0.111319 0.775712 + outer loop + vertex 0.832726 1.33246 2.58441 + vertex 0.832604 1.32745 2.5836 + vertex 0.835538 1.32953 2.58625 + endloop + endfacet + facet normal -0.622054 -0.112704 0.774821 + outer loop + vertex 0.834912 1.33361 2.58634 + vertex 0.832726 1.33246 2.58441 + vertex 0.835538 1.32953 2.58625 + endloop + endfacet + facet normal -0.623951 -0.10775 0.773999 + outer loop + vertex 0.832726 1.33246 2.58441 + vertex 0.834912 1.33361 2.58634 + vertex 0.833075 1.33598 2.58519 + endloop + endfacet + facet normal -0.603547 -0.111831 0.789446 + outer loop + vertex 0.839719 1.30833 2.58637 + vertex 0.84033 1.31236 2.58741 + vertex 0.837857 1.3107 2.58528 + endloop + endfacet + facet normal -0.603062 -0.116151 0.789193 + outer loop + vertex 0.837201 1.31456 2.58534 + vertex 0.839239 1.31679 2.58723 + vertex 0.836711 1.31924 2.58566 + endloop + endfacet + facet normal -0.602423 -0.115076 0.789838 + outer loop + vertex 0.839239 1.31679 2.58723 + vertex 0.839722 1.32123 2.58824 + vertex 0.836711 1.31924 2.58566 + endloop + endfacet + facet normal -0.602513 -0.114888 0.789797 + outer loop + vertex 0.836711 1.31924 2.58566 + vertex 0.839722 1.32123 2.58824 + vertex 0.83619 1.32433 2.586 + endloop + endfacet + facet normal -0.60298 -0.115772 0.789311 + outer loop + vertex 0.839722 1.32123 2.58824 + vertex 0.838814 1.32688 2.58838 + vertex 0.83619 1.32433 2.586 + endloop + endfacet + facet normal -0.604635 -0.113237 0.788413 + outer loop + vertex 0.83619 1.32433 2.586 + vertex 0.838814 1.32688 2.58838 + vertex 0.835538 1.32953 2.58625 + endloop + endfacet + facet normal -0.604339 -0.112615 0.788728 + outer loop + vertex 0.838814 1.32688 2.58838 + vertex 0.837923 1.33259 2.58851 + vertex 0.835538 1.32953 2.58625 + endloop + endfacet + facet normal -0.606043 -0.110538 0.787714 + outer loop + vertex 0.835538 1.32953 2.58625 + vertex 0.837923 1.33259 2.58851 + vertex 0.834912 1.33361 2.58634 + endloop + endfacet + facet normal -0.605661 -0.108074 0.788349 + outer loop + vertex 0.834912 1.33361 2.58634 + vertex 0.837923 1.33259 2.58851 + vertex 0.8354 1.3375 2.58724 + endloop + endfacet + facet normal -0.620629 -0.103595 0.777231 + outer loop + vertex 0.834912 1.33361 2.58634 + vertex 0.8354 1.3375 2.58724 + vertex 0.833075 1.33598 2.58519 + endloop + endfacet + facet normal -0.606651 -0.108805 0.787487 + outer loop + vertex 0.837923 1.33259 2.58851 + vertex 0.838383 1.33703 2.58948 + vertex 0.8354 1.3375 2.58724 + endloop + endfacet + facet normal -0.606637 -0.108358 0.78756 + outer loop + vertex 0.838383 1.33703 2.58948 + vertex 0.837226 1.34156 2.58921 + vertex 0.8354 1.3375 2.58724 + endloop + endfacet + facet normal -0.613386 -0.103127 0.783021 + outer loop + vertex 0.8354 1.3375 2.58724 + vertex 0.837226 1.34156 2.58921 + vertex 0.834275 1.34187 2.58694 + endloop + endfacet + facet normal -0.613384 -0.102313 0.78313 + outer loop + vertex 0.837226 1.34156 2.58921 + vertex 0.834852 1.34625 2.58796 + vertex 0.834275 1.34187 2.58694 + endloop + endfacet + facet normal -0.630136 -0.0971245 0.770386 + outer loop + vertex 0.834275 1.34187 2.58694 + vertex 0.834852 1.34625 2.58796 + vertex 0.831876 1.3442 2.58527 + endloop + endfacet + facet normal -0.631482 -0.0995229 0.768977 + outer loop + vertex 0.832324 1.33966 2.58505 + vertex 0.834275 1.34187 2.58694 + vertex 0.831876 1.3442 2.58527 + endloop + endfacet + facet normal -0.642374 -0.100157 0.759819 + outer loop + vertex 0.831876 1.3442 2.58527 + vertex 0.82944 1.34171 2.58288 + vertex 0.832324 1.33966 2.58505 + endloop + endfacet + facet normal -0.641904 -0.0989023 0.76038 + outer loop + vertex 0.82944 1.34171 2.58288 + vertex 0.830242 1.33649 2.58288 + vertex 0.832324 1.33966 2.58505 + endloop + endfacet + facet normal -0.638783 -0.102425 0.762539 + outer loop + vertex 0.833075 1.33598 2.58519 + vertex 0.832324 1.33966 2.58505 + vertex 0.830242 1.33649 2.58288 + endloop + endfacet + facet normal -0.638837 -0.103709 0.76232 + outer loop + vertex 0.833075 1.33598 2.58519 + vertex 0.830242 1.33649 2.58288 + vertex 0.832726 1.33246 2.58441 + endloop + endfacet + facet normal -0.637688 -0.102578 0.763434 + outer loop + vertex 0.832726 1.33246 2.58441 + vertex 0.830242 1.33649 2.58288 + vertex 0.830062 1.33167 2.58208 + endloop + endfacet + facet normal -0.636142 -0.109021 0.763831 + outer loop + vertex 0.832604 1.32745 2.5836 + vertex 0.832726 1.33246 2.58441 + vertex 0.830062 1.33167 2.58208 + endloop + endfacet + facet normal -0.636728 -0.109576 0.763263 + outer loop + vertex 0.82957 1.32828 2.58119 + vertex 0.832604 1.32745 2.5836 + vertex 0.830062 1.33167 2.58208 + endloop + endfacet + facet normal -0.64957 -0.105003 0.753016 + outer loop + vertex 0.82957 1.32828 2.58119 + vertex 0.830062 1.33167 2.58208 + vertex 0.827853 1.33082 2.58006 + endloop + endfacet + facet normal -0.655917 -0.112203 0.746447 + outer loop + vertex 0.826842 1.3273 2.57864 + vertex 0.82957 1.32828 2.58119 + vertex 0.827853 1.33082 2.58006 + endloop + endfacet + facet normal -0.663707 -0.107468 0.740232 + outer loop + vertex 0.826842 1.3273 2.57864 + vertex 0.827853 1.33082 2.58006 + vertex 0.825403 1.33229 2.57808 + endloop + endfacet + facet normal -0.667459 -0.108957 0.736632 + outer loop + vertex 0.826842 1.3273 2.57864 + vertex 0.825403 1.33229 2.57808 + vertex 0.82366 1.32983 2.57613 + endloop + endfacet + facet normal -0.665499 -0.10404 0.739112 + outer loop + vertex 0.826842 1.3273 2.57864 + vertex 0.82366 1.32983 2.57613 + vertex 0.824589 1.32703 2.57658 + endloop + endfacet + facet normal -0.665189 -0.106329 0.739066 + outer loop + vertex 0.825099 1.32407 2.57661 + vertex 0.826842 1.3273 2.57864 + vertex 0.824589 1.32703 2.57658 + endloop + endfacet + facet normal -0.670529 -0.107303 0.734083 + outer loop + vertex 0.824589 1.32703 2.57658 + vertex 0.822687 1.32682 2.57481 + vertex 0.825099 1.32407 2.57661 + endloop + endfacet + facet normal -0.66977 -0.106064 0.734955 + outer loop + vertex 0.822687 1.32682 2.57481 + vertex 0.822431 1.32224 2.57391 + vertex 0.825099 1.32407 2.57661 + endloop + endfacet + facet normal -0.669311 -0.107122 0.735219 + outer loop + vertex 0.825099 1.32407 2.57661 + vertex 0.822431 1.32224 2.57391 + vertex 0.825682 1.31923 2.57643 + endloop + endfacet + facet normal -0.661064 -0.1064 0.742747 + outer loop + vertex 0.825682 1.31923 2.57643 + vertex 0.828027 1.32176 2.57888 + vertex 0.825099 1.32407 2.57661 + endloop + endfacet + facet normal -0.658913 -0.109768 0.744167 + outer loop + vertex 0.828659 1.31665 2.57869 + vertex 0.828027 1.32176 2.57888 + vertex 0.825682 1.31923 2.57643 + endloop + endfacet + facet normal -0.658085 -0.107936 0.745167 + outer loop + vertex 0.826179 1.31411 2.57613 + vertex 0.828659 1.31665 2.57869 + vertex 0.825682 1.31923 2.57643 + endloop + endfacet + facet normal -0.667309 -0.108341 0.736859 + outer loop + vertex 0.825682 1.31923 2.57643 + vertex 0.823267 1.3167 2.57387 + vertex 0.826179 1.31411 2.57613 + endloop + endfacet + facet normal -0.667824 -0.109475 0.736224 + outer loop + vertex 0.823267 1.3167 2.57387 + vertex 0.823723 1.31156 2.57352 + vertex 0.826179 1.31411 2.57613 + endloop + endfacet + facet normal -0.666563 -0.111541 0.737057 + outer loop + vertex 0.826179 1.31411 2.57613 + vertex 0.823723 1.31156 2.57352 + vertex 0.826537 1.30914 2.5757 + endloop + endfacet + facet normal -0.656615 -0.111591 0.745925 + outer loop + vertex 0.826537 1.30914 2.5757 + vertex 0.829036 1.31168 2.57828 + vertex 0.826179 1.31411 2.57613 + endloop + endfacet + facet normal -0.654918 -0.114356 0.746997 + outer loop + vertex 0.829448 1.30681 2.5779 + vertex 0.829036 1.31168 2.57828 + vertex 0.826537 1.30914 2.5757 + endloop + endfacet + facet normal -0.655884 -0.116703 0.745786 + outer loop + vertex 0.827022 1.3043 2.57537 + vertex 0.829448 1.30681 2.5779 + vertex 0.826537 1.30914 2.5757 + endloop + endfacet + facet normal -0.665764 -0.117088 0.736918 + outer loop + vertex 0.826537 1.30914 2.5757 + vertex 0.824095 1.30666 2.5731 + vertex 0.827022 1.3043 2.57537 + endloop + endfacet + facet normal -0.642084 -0.114146 0.758089 + outer loop + vertex 0.829036 1.31168 2.57828 + vertex 0.829448 1.30681 2.5779 + vertex 0.831888 1.30932 2.58034 + endloop + endfacet + facet normal -0.641401 -0.112618 0.758895 + outer loop + vertex 0.831637 1.31414 2.58085 + vertex 0.829036 1.31168 2.57828 + vertex 0.831888 1.30932 2.58034 + endloop + endfacet + facet normal -0.624518 -0.113189 0.772765 + outer loop + vertex 0.831888 1.30932 2.58034 + vertex 0.83488 1.31134 2.58306 + vertex 0.831637 1.31414 2.58085 + endloop + endfacet + facet normal -0.625826 -0.115844 0.771312 + outer loop + vertex 0.83488 1.31134 2.58306 + vertex 0.834208 1.31672 2.58332 + vertex 0.831637 1.31414 2.58085 + endloop + endfacet + facet normal -0.628023 -0.112418 0.770032 + outer loop + vertex 0.831637 1.31414 2.58085 + vertex 0.834208 1.31672 2.58332 + vertex 0.831127 1.31919 2.58117 + endloop + endfacet + facet normal -0.643573 -0.113154 0.756975 + outer loop + vertex 0.831127 1.31919 2.58117 + vertex 0.828659 1.31665 2.57869 + vertex 0.831637 1.31414 2.58085 + endloop + endfacet + facet normal -0.629243 -0.115156 0.76863 + outer loop + vertex 0.834208 1.31672 2.58332 + vertex 0.833577 1.32183 2.58357 + vertex 0.831127 1.31919 2.58117 + endloop + endfacet + facet normal -0.632509 -0.110324 0.766655 + outer loop + vertex 0.831127 1.31919 2.58117 + vertex 0.833577 1.32183 2.58357 + vertex 0.830348 1.32427 2.58125 + endloop + endfacet + facet normal -0.648132 -0.112496 0.753173 + outer loop + vertex 0.830348 1.32427 2.58125 + vertex 0.828027 1.32176 2.57888 + vertex 0.831127 1.31919 2.58117 + endloop + endfacet + facet normal -0.651913 -0.106702 0.750749 + outer loop + vertex 0.826842 1.3273 2.57864 + vertex 0.828027 1.32176 2.57888 + vertex 0.830348 1.32427 2.58125 + endloop + endfacet + facet normal -0.633924 -0.113794 0.764978 + outer loop + vertex 0.833577 1.32183 2.58357 + vertex 0.832604 1.32745 2.5836 + vertex 0.830348 1.32427 2.58125 + endloop + endfacet + facet normal -0.625836 -0.110356 0.772108 + outer loop + vertex 0.834303 1.30698 2.58196 + vertex 0.83488 1.31134 2.58306 + vertex 0.831888 1.30932 2.58034 + endloop + endfacet + facet normal -0.628209 -0.114575 0.769562 + outer loop + vertex 0.832343 1.30477 2.58004 + vertex 0.834303 1.30698 2.58196 + vertex 0.831888 1.30932 2.58034 + endloop + endfacet + facet normal -0.624965 -0.119148 0.771507 + outer loop + vertex 0.835438 1.30258 2.58221 + vertex 0.834303 1.30698 2.58196 + vertex 0.832343 1.30477 2.58004 + endloop + endfacet + facet normal -0.624398 -0.117663 0.772194 + outer loop + vertex 0.83313 1.30107 2.58011 + vertex 0.835438 1.30258 2.58221 + vertex 0.832343 1.30477 2.58004 + endloop + endfacet + facet normal -0.642494 -0.110784 0.75824 + outer loop + vertex 0.828659 1.31665 2.57869 + vertex 0.829036 1.31168 2.57828 + vertex 0.831637 1.31414 2.58085 + endloop + endfacet + facet normal -0.64144 -0.115157 0.758481 + outer loop + vertex 0.831888 1.30932 2.58034 + vertex 0.829448 1.30681 2.5779 + vertex 0.832343 1.30477 2.58004 + endloop + endfacet + facet normal -0.642924 -0.119234 0.756592 + outer loop + vertex 0.829448 1.30681 2.5779 + vertex 0.830311 1.3016 2.57781 + vertex 0.832343 1.30477 2.58004 + endloop + endfacet + facet normal -0.667632 -0.113994 0.735713 + outer loop + vertex 0.823723 1.31156 2.57352 + vertex 0.824095 1.30666 2.5731 + vertex 0.826537 1.30914 2.5757 + endloop + endfacet + facet normal -0.676167 -0.113966 0.727881 + outer loop + vertex 0.824095 1.30666 2.5731 + vertex 0.823723 1.31156 2.57352 + vertex 0.821311 1.30907 2.57089 + endloop + endfacet + facet normal -0.677333 -0.116706 0.726361 + outer loop + vertex 0.821765 1.30426 2.57054 + vertex 0.824095 1.30666 2.5731 + vertex 0.821311 1.30907 2.57089 + endloop + endfacet + facet normal -0.68486 -0.116899 0.719237 + outer loop + vertex 0.821311 1.30907 2.57089 + vertex 0.818953 1.30664 2.56825 + vertex 0.821765 1.30426 2.57054 + endloop + endfacet + facet normal -0.685998 -0.114956 0.718465 + outer loop + vertex 0.818561 1.31161 2.56867 + vertex 0.818953 1.30664 2.56825 + vertex 0.821311 1.30907 2.57089 + endloop + endfacet + facet normal -0.684905 -0.112535 0.719889 + outer loop + vertex 0.820911 1.3141 2.5713 + vertex 0.818561 1.31161 2.56867 + vertex 0.821311 1.30907 2.57089 + endloop + endfacet + facet normal -0.675714 -0.119414 0.727427 + outer loop + vertex 0.824676 1.30199 2.57287 + vertex 0.824095 1.30666 2.5731 + vertex 0.821765 1.30426 2.57054 + endloop + endfacet + facet normal -0.675628 -0.119181 0.727546 + outer loop + vertex 0.822562 1.29966 2.57053 + vertex 0.824676 1.30199 2.57287 + vertex 0.821765 1.30426 2.57054 + endloop + endfacet + facet normal -0.683416 -0.120512 0.720014 + outer loop + vertex 0.821765 1.30426 2.57054 + vertex 0.819557 1.30185 2.56804 + vertex 0.822562 1.29966 2.57053 + endloop + endfacet + facet normal -0.682199 -0.116858 0.721767 + outer loop + vertex 0.819557 1.30185 2.56804 + vertex 0.820598 1.29722 2.56828 + vertex 0.822562 1.29966 2.57053 + endloop + endfacet + facet normal -0.679514 -0.12076 0.723656 + outer loop + vertex 0.823713 1.29522 2.57087 + vertex 0.822562 1.29966 2.57053 + vertex 0.820598 1.29722 2.56828 + endloop + endfacet + facet normal -0.67704 -0.112506 0.727296 + outer loop + vertex 0.821311 1.30907 2.57089 + vertex 0.823723 1.31156 2.57352 + vertex 0.820911 1.3141 2.5713 + endloop + endfacet + facet normal -0.675771 -0.109683 0.728906 + outer loop + vertex 0.823723 1.31156 2.57352 + vertex 0.823267 1.3167 2.57387 + vertex 0.820911 1.3141 2.5713 + endloop + endfacet + facet normal -0.676277 -0.10888 0.728557 + outer loop + vertex 0.820911 1.3141 2.5713 + vertex 0.823267 1.3167 2.57387 + vertex 0.820251 1.3192 2.57145 + endloop + endfacet + facet normal -0.684299 -0.10969 0.720905 + outer loop + vertex 0.820251 1.3192 2.57145 + vertex 0.817988 1.31674 2.56893 + vertex 0.820911 1.3141 2.5713 + endloop + endfacet + facet normal -0.685095 -0.108385 0.720345 + outer loop + vertex 0.816827 1.32232 2.56866 + vertex 0.817988 1.31674 2.56893 + vertex 0.820251 1.3192 2.57145 + endloop + endfacet + facet normal -0.685391 -0.109052 0.719963 + outer loop + vertex 0.819536 1.32321 2.57137 + vertex 0.816827 1.32232 2.56866 + vertex 0.820251 1.3192 2.57145 + endloop + endfacet + facet normal -0.675378 -0.107085 0.729656 + outer loop + vertex 0.820251 1.3192 2.57145 + vertex 0.822431 1.32224 2.57391 + vertex 0.819536 1.32321 2.57137 + endloop + endfacet + facet normal -0.675271 -0.106148 0.729891 + outer loop + vertex 0.819536 1.32321 2.57137 + vertex 0.822431 1.32224 2.57391 + vertex 0.820036 1.32645 2.57231 + endloop + endfacet + facet normal -0.679833 -0.104298 0.725912 + outer loop + vertex 0.819536 1.32321 2.57137 + vertex 0.820036 1.32645 2.57231 + vertex 0.817861 1.32576 2.57017 + endloop + endfacet + facet normal -0.679921 -0.10393 0.725883 + outer loop + vertex 0.817861 1.32576 2.57017 + vertex 0.820036 1.32645 2.57231 + vertex 0.817449 1.32944 2.57031 + endloop + endfacet + facet normal -0.688607 -0.104583 0.717554 + outer loop + vertex 0.817861 1.32576 2.57017 + vertex 0.817449 1.32944 2.57031 + vertex 0.815446 1.32731 2.56808 + endloop + endfacet + facet normal -0.688642 -0.104523 0.717528 + outer loop + vertex 0.814592 1.33183 2.56792 + vertex 0.815446 1.32731 2.56808 + vertex 0.817449 1.32944 2.57031 + endloop + endfacet + facet normal -0.68906 -0.105581 0.716972 + outer loop + vertex 0.8169 1.3341 2.57047 + vertex 0.814592 1.33183 2.56792 + vertex 0.817449 1.32944 2.57031 + endloop + endfacet + facet normal -0.679737 -0.10479 0.725932 + outer loop + vertex 0.817449 1.32944 2.57031 + vertex 0.820269 1.33109 2.57319 + vertex 0.8169 1.3341 2.57047 + endloop + endfacet + facet normal -0.68084 -0.107286 0.724532 + outer loop + vertex 0.820269 1.33109 2.57319 + vertex 0.819298 1.33653 2.57309 + vertex 0.8169 1.3341 2.57047 + endloop + endfacet + facet normal -0.682131 -0.105058 0.723644 + outer loop + vertex 0.8169 1.3341 2.57047 + vertex 0.819298 1.33653 2.57309 + vertex 0.816412 1.33906 2.57073 + endloop + endfacet + facet normal -0.675098 -0.106155 0.730051 + outer loop + vertex 0.819298 1.33653 2.57309 + vertex 0.820269 1.33109 2.57319 + vertex 0.822376 1.3343 2.57561 + endloop + endfacet + facet normal -0.674685 -0.104964 0.730604 + outer loop + vertex 0.821641 1.33912 2.57562 + vertex 0.819298 1.33653 2.57309 + vertex 0.822376 1.3343 2.57561 + endloop + endfacet + facet normal -0.669233 -0.10415 0.735718 + outer loop + vertex 0.822376 1.3343 2.57561 + vertex 0.824557 1.33685 2.57795 + vertex 0.821641 1.33912 2.57562 + endloop + endfacet + facet normal -0.667833 -0.100545 0.737489 + outer loop + vertex 0.824557 1.33685 2.57795 + vertex 0.824054 1.34161 2.57815 + vertex 0.821641 1.33912 2.57562 + endloop + endfacet + facet normal -0.667703 -0.100762 0.737577 + outer loop + vertex 0.821641 1.33912 2.57562 + vertex 0.824054 1.34161 2.57815 + vertex 0.821263 1.34403 2.57595 + endloop + endfacet + facet normal -0.660577 -0.100047 0.744062 + outer loop + vertex 0.824054 1.34161 2.57815 + vertex 0.824557 1.33685 2.57795 + vertex 0.826974 1.33922 2.58042 + endloop + endfacet + facet normal -0.659715 -0.0980115 0.745098 + outer loop + vertex 0.826536 1.34408 2.58067 + vertex 0.824054 1.34161 2.57815 + vertex 0.826974 1.33922 2.58042 + endloop + endfacet + facet normal -0.652653 -0.0976975 0.751332 + outer loop + vertex 0.826974 1.33922 2.58042 + vertex 0.82944 1.34171 2.58288 + vertex 0.826536 1.34408 2.58067 + endloop + endfacet + facet normal -0.652439 -0.0972012 0.751582 + outer loop + vertex 0.82944 1.34171 2.58288 + vertex 0.829042 1.34656 2.58316 + vertex 0.826536 1.34408 2.58067 + endloop + endfacet + facet normal -0.653554 -0.0953419 0.750851 + outer loop + vertex 0.826536 1.34408 2.58067 + vertex 0.829042 1.34656 2.58316 + vertex 0.826192 1.34903 2.581 + endloop + endfacet + facet normal -0.659125 -0.0954029 0.745958 + outer loop + vertex 0.826192 1.34903 2.581 + vertex 0.823715 1.34653 2.57849 + vertex 0.826536 1.34408 2.58067 + endloop + endfacet + facet normal -0.652832 -0.0937866 0.751675 + outer loop + vertex 0.829042 1.34656 2.58316 + vertex 0.828706 1.35153 2.58349 + vertex 0.826192 1.34903 2.581 + endloop + endfacet + facet normal -0.653981 -0.0918656 0.750913 + outer loop + vertex 0.826192 1.34903 2.581 + vertex 0.828706 1.35153 2.58349 + vertex 0.825745 1.35421 2.58124 + endloop + endfacet + facet normal -0.65932 -0.0921036 0.7462 + outer loop + vertex 0.825745 1.35421 2.58124 + vertex 0.82328 1.35168 2.57875 + vertex 0.826192 1.34903 2.581 + endloop + endfacet + facet normal -0.65258 -0.0890115 0.752474 + outer loop + vertex 0.828706 1.35153 2.58349 + vertex 0.828278 1.35672 2.58373 + vertex 0.825745 1.35421 2.58124 + endloop + endfacet + facet normal -0.652972 -0.0883534 0.752211 + outer loop + vertex 0.825745 1.35421 2.58124 + vertex 0.828278 1.35672 2.58373 + vertex 0.825287 1.35937 2.58145 + endloop + endfacet + facet normal -0.659239 -0.0886866 0.746685 + outer loop + vertex 0.825287 1.35937 2.58145 + vertex 0.822469 1.35734 2.57872 + vertex 0.825745 1.35421 2.58124 + endloop + endfacet + facet normal -0.650841 -0.0839344 0.75456 + outer loop + vertex 0.828278 1.35672 2.58373 + vertex 0.827636 1.36244 2.58382 + vertex 0.825287 1.35937 2.58145 + endloop + endfacet + facet normal -0.649692 -0.0854503 0.75538 + outer loop + vertex 0.825287 1.35937 2.58145 + vertex 0.827636 1.36244 2.58382 + vertex 0.824788 1.36347 2.58149 + endloop + endfacet + facet normal -0.644742 -0.0833266 0.759845 + outer loop + vertex 0.827636 1.36244 2.58382 + vertex 0.828278 1.35672 2.58373 + vertex 0.830884 1.35919 2.58622 + endloop + endfacet + facet normal -0.642734 -0.0797799 0.761924 + outer loop + vertex 0.830618 1.36426 2.58652 + vertex 0.827636 1.36244 2.58382 + vertex 0.830884 1.35919 2.58622 + endloop + endfacet + facet normal -0.632336 -0.0797583 0.770578 + outer loop + vertex 0.830884 1.35919 2.58622 + vertex 0.833569 1.36155 2.58867 + vertex 0.830618 1.36426 2.58652 + endloop + endfacet + facet normal -0.631528 -0.0782273 0.771397 + outer loop + vertex 0.833569 1.36155 2.58867 + vertex 0.833154 1.36667 2.58884 + vertex 0.830618 1.36426 2.58652 + endloop + endfacet + facet normal -0.631454 -0.0783496 0.771445 + outer loop + vertex 0.830618 1.36426 2.58652 + vertex 0.833154 1.36667 2.58884 + vertex 0.830162 1.36908 2.58664 + endloop + endfacet + facet normal -0.640323 -0.0790112 0.764031 + outer loop + vertex 0.830162 1.36908 2.58664 + vertex 0.828187 1.36692 2.58476 + vertex 0.830618 1.36426 2.58652 + endloop + endfacet + facet normal -0.640742 -0.07838 0.763745 + outer loop + vertex 0.827143 1.37142 2.58435 + vertex 0.828187 1.36692 2.58476 + vertex 0.830162 1.36908 2.58664 + endloop + endfacet + facet normal -0.641889 -0.0810819 0.762498 + outer loop + vertex 0.829452 1.37293 2.58645 + vertex 0.827143 1.37142 2.58435 + vertex 0.830162 1.36908 2.58664 + endloop + endfacet + facet normal -0.63373 -0.0792407 0.769485 + outer loop + vertex 0.830162 1.36908 2.58664 + vertex 0.832333 1.37226 2.58876 + vertex 0.829452 1.37293 2.58645 + endloop + endfacet + facet normal -0.633916 -0.0813094 0.769116 + outer loop + vertex 0.829452 1.37293 2.58645 + vertex 0.832333 1.37226 2.58876 + vertex 0.829903 1.37642 2.58719 + endloop + endfacet + facet normal -0.640548 -0.0793243 0.76381 + outer loop + vertex 0.829452 1.37293 2.58645 + vertex 0.829903 1.37642 2.58719 + vertex 0.827721 1.37529 2.58525 + endloop + endfacet + facet normal -0.641261 -0.0772769 0.763422 + outer loop + vertex 0.827721 1.37529 2.58525 + vertex 0.829903 1.37642 2.58719 + vertex 0.827294 1.3792 2.58528 + endloop + endfacet + facet normal -0.647117 -0.0778691 0.758404 + outer loop + vertex 0.827721 1.37529 2.58525 + vertex 0.827294 1.3792 2.58528 + vertex 0.824896 1.37614 2.58292 + endloop + endfacet + facet normal -0.647286 -0.0792012 0.758121 + outer loop + vertex 0.827721 1.37529 2.58525 + vertex 0.824896 1.37614 2.58292 + vertex 0.827143 1.37142 2.58435 + endloop + endfacet + facet normal -0.647648 -0.0794749 0.757784 + outer loop + vertex 0.827143 1.37142 2.58435 + vertex 0.824896 1.37614 2.58292 + vertex 0.824306 1.37181 2.58196 + endloop + endfacet + facet normal -0.647648 -0.0794747 0.757784 + outer loop + vertex 0.825336 1.36739 2.58238 + vertex 0.827143 1.37142 2.58435 + vertex 0.824306 1.37181 2.58196 + endloop + endfacet + facet normal -0.640528 -0.0760809 0.764157 + outer loop + vertex 0.829903 1.37642 2.58719 + vertex 0.830189 1.38136 2.58792 + vertex 0.827294 1.3792 2.58528 + endloop + endfacet + facet normal -0.641417 -0.0742058 0.763596 + outer loop + vertex 0.827294 1.3792 2.58528 + vertex 0.830189 1.38136 2.58792 + vertex 0.826931 1.3841 2.58545 + endloop + endfacet + facet normal -0.647045 -0.0744535 0.758808 + outer loop + vertex 0.826931 1.3841 2.58545 + vertex 0.824341 1.38155 2.583 + vertex 0.827294 1.3792 2.58528 + endloop + endfacet + facet normal -0.648273 -0.0723876 0.757959 + outer loop + vertex 0.823996 1.38655 2.58318 + vertex 0.824341 1.38155 2.583 + vertex 0.826931 1.3841 2.58545 + endloop + endfacet + facet normal -0.647261 -0.0701721 0.759032 + outer loop + vertex 0.826565 1.38908 2.5856 + vertex 0.823996 1.38655 2.58318 + vertex 0.826931 1.3841 2.58545 + endloop + endfacet + facet normal -0.640968 -0.0698684 0.764381 + outer loop + vertex 0.826931 1.3841 2.58545 + vertex 0.829481 1.38675 2.58783 + vertex 0.826565 1.38908 2.5856 + endloop + endfacet + facet normal -0.639967 -0.0676173 0.765421 + outer loop + vertex 0.829481 1.38675 2.58783 + vertex 0.829127 1.39165 2.58797 + vertex 0.826565 1.38908 2.5856 + endloop + endfacet + facet normal -0.640253 -0.0671491 0.765224 + outer loop + vertex 0.826565 1.38908 2.5856 + vertex 0.829127 1.39165 2.58797 + vertex 0.82632 1.39398 2.58583 + endloop + endfacet + facet normal -0.647542 -0.0672316 0.759058 + outer loop + vertex 0.82632 1.39398 2.58583 + vertex 0.823742 1.39148 2.58341 + vertex 0.826565 1.38908 2.5856 + endloop + endfacet + facet normal -0.648034 -0.0663902 0.758712 + outer loop + vertex 0.823527 1.39642 2.58365 + vertex 0.823742 1.39148 2.58341 + vertex 0.82632 1.39398 2.58583 + endloop + endfacet + facet normal -0.647828 -0.0659628 0.758926 + outer loop + vertex 0.826106 1.3989 2.58607 + vertex 0.823527 1.39642 2.58365 + vertex 0.82632 1.39398 2.58583 + endloop + endfacet + facet normal -0.639482 -0.065952 0.765972 + outer loop + vertex 0.82632 1.39398 2.58583 + vertex 0.828933 1.39647 2.58822 + vertex 0.826106 1.3989 2.58607 + endloop + endfacet + facet normal -0.638601 -0.0641372 0.766861 + outer loop + vertex 0.828933 1.39647 2.58822 + vertex 0.828733 1.40137 2.58847 + vertex 0.826106 1.3989 2.58607 + endloop + endfacet + facet normal -0.639281 -0.0629581 0.766391 + outer loop + vertex 0.826106 1.3989 2.58607 + vertex 0.828733 1.40137 2.58847 + vertex 0.825852 1.4039 2.58627 + endloop + endfacet + facet normal -0.647921 -0.0631075 0.759089 + outer loop + vertex 0.825852 1.4039 2.58627 + vertex 0.823268 1.40143 2.58386 + vertex 0.826106 1.3989 2.58607 + endloop + endfacet + facet normal -0.648841 -0.0615031 0.758434 + outer loop + vertex 0.822923 1.40659 2.58398 + vertex 0.823268 1.40143 2.58386 + vertex 0.825852 1.4039 2.58627 + endloop + endfacet + facet normal -0.647218 -0.0583492 0.760068 + outer loop + vertex 0.825548 1.40904 2.58641 + vertex 0.822923 1.40659 2.58398 + vertex 0.825852 1.4039 2.58627 + endloop + endfacet + facet normal -0.639326 -0.0580599 0.76674 + outer loop + vertex 0.825852 1.4039 2.58627 + vertex 0.828485 1.40635 2.58865 + vertex 0.825548 1.40904 2.58641 + endloop + endfacet + facet normal -0.637647 -0.0548732 0.768371 + outer loop + vertex 0.828485 1.40635 2.58865 + vertex 0.828235 1.41142 2.58881 + vertex 0.825548 1.40904 2.58641 + endloop + endfacet + facet normal -0.638242 -0.0537783 0.767955 + outer loop + vertex 0.825548 1.40904 2.58641 + vertex 0.828235 1.41142 2.58881 + vertex 0.825366 1.41414 2.58661 + endloop + endfacet + facet normal -0.646264 -0.0537948 0.761216 + outer loop + vertex 0.825366 1.41414 2.58661 + vertex 0.822389 1.41224 2.58395 + vertex 0.825548 1.40904 2.58641 + endloop + endfacet + facet normal -0.646156 -0.0540657 0.761288 + outer loop + vertex 0.823027 1.41675 2.58481 + vertex 0.822389 1.41224 2.58395 + vertex 0.825366 1.41414 2.58661 + endloop + endfacet + facet normal -0.643488 -0.0499369 0.763825 + outer loop + vertex 0.82507 1.41903 2.58668 + vertex 0.823027 1.41675 2.58481 + vertex 0.825366 1.41414 2.58661 + endloop + endfacet + facet normal -0.637143 -0.0496317 0.769146 + outer loop + vertex 0.825366 1.41414 2.58661 + vertex 0.827947 1.41661 2.58891 + vertex 0.82507 1.41903 2.58668 + endloop + endfacet + facet normal -0.636593 -0.0484929 0.769674 + outer loop + vertex 0.827947 1.41661 2.58891 + vertex 0.827481 1.4223 2.58888 + vertex 0.82507 1.41903 2.58668 + endloop + endfacet + facet normal -0.637238 -0.0476916 0.76919 + outer loop + vertex 0.82507 1.41903 2.58668 + vertex 0.827481 1.4223 2.58888 + vertex 0.82457 1.42312 2.58652 + endloop + endfacet + facet normal -0.645383 -0.0489586 0.762288 + outer loop + vertex 0.82457 1.42312 2.58652 + vertex 0.822134 1.42133 2.58435 + vertex 0.82507 1.41903 2.58668 + endloop + endfacet + facet normal -0.645468 -0.0487717 0.762229 + outer loop + vertex 0.822134 1.42133 2.58435 + vertex 0.82457 1.42312 2.58652 + vertex 0.822884 1.42553 2.58525 + endloop + endfacet + facet normal -0.650515 -0.0469689 0.75804 + outer loop + vertex 0.822884 1.42553 2.58525 + vertex 0.820016 1.4261 2.58282 + vertex 0.822134 1.42133 2.58435 + endloop + endfacet + facet normal -0.650524 -0.0470777 0.758025 + outer loop + vertex 0.822884 1.42553 2.58525 + vertex 0.822417 1.4296 2.5851 + vertex 0.820016 1.4261 2.58282 + endloop + endfacet + facet normal -0.650766 -0.0467878 0.757835 + outer loop + vertex 0.819563 1.43159 2.58277 + vertex 0.820016 1.4261 2.58282 + vertex 0.822417 1.4296 2.5851 + endloop + endfacet + facet normal -0.650672 -0.0465388 0.757932 + outer loop + vertex 0.821998 1.43432 2.58503 + vertex 0.819563 1.43159 2.58277 + vertex 0.822417 1.4296 2.5851 + endloop + endfacet + facet normal -0.644692 -0.0459314 0.763061 + outer loop + vertex 0.822417 1.4296 2.5851 + vertex 0.824724 1.43254 2.58723 + vertex 0.821998 1.43432 2.58503 + endloop + endfacet + facet normal -0.644506 -0.045413 0.76325 + outer loop + vertex 0.824724 1.43254 2.58723 + vertex 0.824081 1.43661 2.58693 + vertex 0.821998 1.43432 2.58503 + endloop + endfacet + facet normal -0.645976 -0.0431538 0.762137 + outer loop + vertex 0.821998 1.43432 2.58503 + vertex 0.824081 1.43661 2.58693 + vertex 0.821888 1.43892 2.5852 + endloop + endfacet + facet normal -0.650624 -0.0431192 0.758175 + outer loop + vertex 0.821888 1.43892 2.5852 + vertex 0.819322 1.43652 2.58286 + vertex 0.821998 1.43432 2.58503 + endloop + endfacet + facet normal -0.651303 -0.0418925 0.757661 + outer loop + vertex 0.819178 1.44138 2.583 + vertex 0.819322 1.43652 2.58286 + vertex 0.821888 1.43892 2.5852 + endloop + endfacet + facet normal -0.649907 -0.039156 0.759005 + outer loop + vertex 0.821863 1.44378 2.58543 + vertex 0.819178 1.44138 2.583 + vertex 0.821888 1.43892 2.5852 + endloop + endfacet + facet normal -0.643134 -0.0393904 0.76474 + outer loop + vertex 0.821888 1.43892 2.5852 + vertex 0.824911 1.44096 2.58785 + vertex 0.821863 1.44378 2.58543 + endloop + endfacet + facet normal -0.642072 -0.0373894 0.765732 + outer loop + vertex 0.824911 1.44096 2.58785 + vertex 0.824545 1.44647 2.58781 + vertex 0.821863 1.44378 2.58543 + endloop + endfacet + facet normal -0.642269 -0.0370609 0.765583 + outer loop + vertex 0.821863 1.44378 2.58543 + vertex 0.824545 1.44647 2.58781 + vertex 0.821688 1.44882 2.58552 + endloop + endfacet + facet normal -0.649221 -0.0371884 0.75969 + outer loop + vertex 0.821688 1.44882 2.58552 + vertex 0.819039 1.44632 2.58314 + vertex 0.821863 1.44378 2.58543 + endloop + endfacet + facet normal -0.649445 -0.0367867 0.759519 + outer loop + vertex 0.818888 1.45132 2.58325 + vertex 0.819039 1.44632 2.58314 + vertex 0.821688 1.44882 2.58552 + endloop + endfacet + facet normal -0.64902 -0.0359442 0.759922 + outer loop + vertex 0.821537 1.45384 2.58563 + vertex 0.818888 1.45132 2.58325 + vertex 0.821688 1.44882 2.58552 + endloop + endfacet + facet normal -0.641479 -0.0358548 0.766302 + outer loop + vertex 0.821688 1.44882 2.58552 + vertex 0.824341 1.45154 2.58787 + vertex 0.821537 1.45384 2.58563 + endloop + endfacet + facet normal -0.640965 -0.0347577 0.766783 + outer loop + vertex 0.824341 1.45154 2.58787 + vertex 0.824194 1.45651 2.58798 + vertex 0.821537 1.45384 2.58563 + endloop + endfacet + facet normal -0.640713 -0.035175 0.766974 + outer loop + vertex 0.821537 1.45384 2.58563 + vertex 0.824194 1.45651 2.58798 + vertex 0.821404 1.45885 2.58575 + endloop + endfacet + facet normal -0.648182 -0.0352245 0.76067 + outer loop + vertex 0.821404 1.45885 2.58575 + vertex 0.818747 1.45633 2.58337 + vertex 0.821537 1.45384 2.58563 + endloop + endfacet + facet normal -0.648061 -0.0354403 0.760763 + outer loop + vertex 0.818608 1.46135 2.58349 + vertex 0.818747 1.45633 2.58337 + vertex 0.821404 1.45885 2.58575 + endloop + endfacet + facet normal -0.647216 -0.0337779 0.761558 + outer loop + vertex 0.821271 1.46385 2.58586 + vertex 0.818608 1.46135 2.58349 + vertex 0.821404 1.45885 2.58575 + endloop + endfacet + facet normal -0.639341 -0.0337135 0.768184 + outer loop + vertex 0.821404 1.45885 2.58575 + vertex 0.824078 1.46143 2.58809 + vertex 0.821271 1.46385 2.58586 + endloop + endfacet + facet normal -0.637974 -0.0309763 0.769435 + outer loop + vertex 0.824078 1.46143 2.58809 + vertex 0.823978 1.46636 2.58821 + vertex 0.821271 1.46385 2.58586 + endloop + endfacet + facet normal -0.637908 -0.0310946 0.769485 + outer loop + vertex 0.821271 1.46385 2.58586 + vertex 0.823978 1.46636 2.58821 + vertex 0.821136 1.46885 2.58595 + endloop + endfacet + facet normal -0.646387 -0.0311954 0.762372 + outer loop + vertex 0.821136 1.46885 2.58595 + vertex 0.81847 1.46637 2.58359 + vertex 0.821271 1.46385 2.58586 + endloop + endfacet + facet normal -0.647192 -0.0297361 0.761747 + outer loop + vertex 0.818342 1.47139 2.58368 + vertex 0.81847 1.46637 2.58359 + vertex 0.821136 1.46885 2.58595 + endloop + endfacet + facet normal -0.64621 -0.0278392 0.762652 + outer loop + vertex 0.821011 1.47385 2.58603 + vertex 0.818342 1.47139 2.58368 + vertex 0.821136 1.46885 2.58595 + endloop + endfacet + facet normal -0.637139 -0.0277273 0.77025 + outer loop + vertex 0.821136 1.46885 2.58595 + vertex 0.823854 1.47131 2.58829 + vertex 0.821011 1.47385 2.58603 + endloop + endfacet + facet normal -0.636059 -0.0256556 0.771214 + outer loop + vertex 0.823854 1.47131 2.58829 + vertex 0.823729 1.47627 2.58835 + vertex 0.821011 1.47385 2.58603 + endloop + endfacet + facet normal -0.637219 -0.0235029 0.770324 + outer loop + vertex 0.821011 1.47385 2.58603 + vertex 0.823729 1.47627 2.58835 + vertex 0.820911 1.47884 2.5861 + endloop + endfacet + facet normal -0.646146 -0.0235764 0.76285 + outer loop + vertex 0.820911 1.47884 2.5861 + vertex 0.818233 1.47639 2.58375 + vertex 0.821011 1.47385 2.58603 + endloop + endfacet + facet normal -0.647439 -0.0211767 0.761823 + outer loop + vertex 0.81815 1.48139 2.58382 + vertex 0.818233 1.47639 2.58375 + vertex 0.820911 1.47884 2.5861 + endloop + endfacet + facet normal -0.646291 -0.0190189 0.762854 + outer loop + vertex 0.820837 1.48383 2.58616 + vertex 0.81815 1.48139 2.58382 + vertex 0.820911 1.47884 2.5861 + endloop + endfacet + facet normal -0.637177 -0.0189787 0.770484 + outer loop + vertex 0.820911 1.47884 2.5861 + vertex 0.823642 1.48124 2.58841 + vertex 0.820837 1.48383 2.58616 + endloop + endfacet + facet normal -0.635797 -0.0164453 0.771681 + outer loop + vertex 0.823642 1.48124 2.58841 + vertex 0.823583 1.48623 2.58847 + vertex 0.820837 1.48383 2.58616 + endloop + endfacet + facet normal -0.636699 -0.0147285 0.770972 + outer loop + vertex 0.820837 1.48383 2.58616 + vertex 0.823583 1.48623 2.58847 + vertex 0.82078 1.48884 2.58621 + endloop + endfacet + facet normal -0.646061 -0.0147596 0.763143 + outer loop + vertex 0.82078 1.48884 2.58621 + vertex 0.818082 1.48639 2.58388 + vertex 0.820837 1.48383 2.58616 + endloop + endfacet + facet normal -0.646819 -0.0133347 0.762527 + outer loop + vertex 0.81803 1.49138 2.58392 + vertex 0.818082 1.48639 2.58388 + vertex 0.82078 1.48884 2.58621 + endloop + endfacet + facet normal -0.645796 -0.011418 0.763425 + outer loop + vertex 0.820733 1.49383 2.58624 + vertex 0.81803 1.49138 2.58392 + vertex 0.82078 1.48884 2.58621 + endloop + endfacet + facet normal -0.636476 -0.0113853 0.771212 + outer loop + vertex 0.82078 1.48884 2.58621 + vertex 0.823533 1.49124 2.58851 + vertex 0.820733 1.49383 2.58624 + endloop + endfacet + facet normal -0.635806 -0.0101633 0.771782 + outer loop + vertex 0.823533 1.49124 2.58851 + vertex 0.823487 1.49623 2.58854 + vertex 0.820733 1.49383 2.58624 + endloop + endfacet + facet normal -0.636288 -0.00924288 0.771396 + outer loop + vertex 0.820733 1.49383 2.58624 + vertex 0.823487 1.49623 2.58854 + vertex 0.820693 1.49881 2.58627 + endloop + endfacet + facet normal -0.645711 -0.00927727 0.763526 + outer loop + vertex 0.820693 1.49881 2.58627 + vertex 0.817988 1.49635 2.58395 + vertex 0.820733 1.49383 2.58624 + endloop + endfacet + facet normal -0.636025 -0.00876039 0.771619 + outer loop + vertex 0.823487 1.49623 2.58854 + vertex 0.823447 1.50122 2.58857 + vertex 0.820693 1.49881 2.58627 + endloop + endfacet + facet normal -0.636748 -0.00737941 0.771037 + outer loop + vertex 0.820693 1.49881 2.58627 + vertex 0.823447 1.50122 2.58857 + vertex 0.820658 1.50379 2.58629 + endloop + endfacet + facet normal -0.646175 -0.00741476 0.763153 + outer loop + vertex 0.820658 1.50379 2.58629 + vertex 0.817952 1.50133 2.58397 + vertex 0.820693 1.49881 2.58627 + endloop + endfacet + facet normal -0.647065 -0.00574178 0.762413 + outer loop + vertex 0.817924 1.50632 2.58399 + vertex 0.817952 1.50133 2.58397 + vertex 0.820658 1.50379 2.58629 + endloop + endfacet + facet normal -0.646594 -0.00486356 0.762819 + outer loop + vertex 0.820633 1.50878 2.5863 + vertex 0.817924 1.50632 2.58399 + vertex 0.820658 1.50379 2.58629 + endloop + endfacet + facet normal -0.637192 -0.00483271 0.77069 + outer loop + vertex 0.820658 1.50379 2.58629 + vertex 0.823415 1.50621 2.58858 + vertex 0.820633 1.50878 2.5863 + endloop + endfacet + facet normal -0.636331 -0.00326345 0.771409 + outer loop + vertex 0.823415 1.50621 2.58858 + vertex 0.823396 1.5112 2.58859 + vertex 0.820633 1.50878 2.5863 + endloop + endfacet + facet normal -0.637478 -0.00105953 0.770468 + outer loop + vertex 0.820633 1.50878 2.5863 + vertex 0.823396 1.5112 2.58859 + vertex 0.820624 1.51378 2.5863 + endloop + endfacet + facet normal -0.646637 -0.00107654 0.762797 + outer loop + vertex 0.820624 1.51378 2.5863 + vertex 0.817909 1.51133 2.58399 + vertex 0.820633 1.50878 2.5863 + endloop + endfacet + facet normal -0.647558 0.000679771 0.762016 + outer loop + vertex 0.81791 1.51634 2.58399 + vertex 0.817909 1.51133 2.58399 + vertex 0.820624 1.51378 2.5863 + endloop + endfacet + facet normal -0.646241 0.00308008 0.763128 + outer loop + vertex 0.820634 1.51878 2.58629 + vertex 0.81791 1.51634 2.58399 + vertex 0.820624 1.51378 2.5863 + endloop + endfacet + facet normal -0.637436 0.00307879 0.770497 + outer loop + vertex 0.820624 1.51378 2.5863 + vertex 0.823395 1.51619 2.58858 + vertex 0.820634 1.51878 2.58629 + endloop + endfacet + facet normal -0.636426 0.00488839 0.771322 + outer loop + vertex 0.823395 1.51619 2.58858 + vertex 0.823414 1.52118 2.58856 + vertex 0.820634 1.51878 2.58629 + endloop + endfacet + facet normal -0.637353 0.00669772 0.770543 + outer loop + vertex 0.820634 1.51878 2.58629 + vertex 0.823414 1.52118 2.58856 + vertex 0.820661 1.52378 2.58626 + endloop + endfacet + facet normal -0.645921 0.00671167 0.763374 + outer loop + vertex 0.820661 1.52378 2.58626 + vertex 0.817929 1.52134 2.58397 + vertex 0.820634 1.51878 2.58629 + endloop + endfacet + facet normal -0.636668 0.00791759 0.771097 + outer loop + vertex 0.823414 1.52118 2.58856 + vertex 0.823447 1.52618 2.58854 + vertex 0.820661 1.52378 2.58626 + endloop + endfacet + facet normal -0.63751 0.00956982 0.770382 + outer loop + vertex 0.820661 1.52378 2.58626 + vertex 0.823447 1.52618 2.58854 + vertex 0.8207 1.52877 2.58623 + endloop + endfacet + facet normal -0.646288 0.00959447 0.763033 + outer loop + vertex 0.8207 1.52877 2.58623 + vertex 0.817962 1.52633 2.58395 + vertex 0.820661 1.52378 2.58626 + endloop + endfacet + facet normal -0.646784 0.0105549 0.762601 + outer loop + vertex 0.818002 1.53132 2.58391 + vertex 0.817962 1.52633 2.58395 + vertex 0.8207 1.52877 2.58623 + endloop + endfacet + facet normal -0.646433 0.011188 0.762889 + outer loop + vertex 0.820743 1.53376 2.5862 + vertex 0.818002 1.53132 2.58391 + vertex 0.8207 1.52877 2.58623 + endloop + endfacet + facet normal -0.637928 0.011167 0.770015 + outer loop + vertex 0.8207 1.52877 2.58623 + vertex 0.823488 1.53117 2.58851 + vertex 0.820743 1.53376 2.5862 + endloop + endfacet + facet normal -0.637908 0.0112012 0.770031 + outer loop + vertex 0.823488 1.53117 2.58851 + vertex 0.823527 1.53615 2.58847 + vertex 0.820743 1.53376 2.5862 + endloop + endfacet + facet normal -0.638601 0.0125754 0.769435 + outer loop + vertex 0.820743 1.53376 2.5862 + vertex 0.823527 1.53615 2.58847 + vertex 0.820786 1.53875 2.58615 + endloop + endfacet + facet normal -0.646969 0.0125846 0.762412 + outer loop + vertex 0.820786 1.53875 2.58615 + vertex 0.818047 1.53631 2.58387 + vertex 0.820743 1.53376 2.5862 + endloop + endfacet + facet normal -0.647696 0.0140059 0.76177 + outer loop + vertex 0.818095 1.5413 2.58382 + vertex 0.818047 1.53631 2.58387 + vertex 0.820786 1.53875 2.58615 + endloop + endfacet + facet normal -0.647572 0.0142285 0.761871 + outer loop + vertex 0.820831 1.54371 2.5861 + vertex 0.818095 1.5413 2.58382 + vertex 0.820786 1.53875 2.58615 + endloop + endfacet + facet normal -0.639084 0.0142293 0.769006 + outer loop + vertex 0.820786 1.53875 2.58615 + vertex 0.823563 1.54112 2.58842 + vertex 0.820831 1.54371 2.5861 + endloop + endfacet + facet normal -0.638173 0.0158365 0.76973 + outer loop + vertex 0.823563 1.54112 2.58842 + vertex 0.823611 1.5461 2.58835 + vertex 0.820831 1.54371 2.5861 + endloop + endfacet + facet normal -0.639643 0.0187678 0.768443 + outer loop + vertex 0.820831 1.54371 2.5861 + vertex 0.823611 1.5461 2.58835 + vertex 0.820894 1.54867 2.58603 + endloop + endfacet + facet normal -0.648456 0.0187754 0.761021 + outer loop + vertex 0.820894 1.54867 2.58603 + vertex 0.818157 1.54627 2.58376 + vertex 0.820831 1.54371 2.5861 + endloop + endfacet + facet normal -0.65009 0.0220448 0.759537 + outer loop + vertex 0.818237 1.55124 2.58368 + vertex 0.818157 1.54627 2.58376 + vertex 0.820894 1.54867 2.58603 + endloop + endfacet + facet normal -0.64908 0.0238325 0.760347 + outer loop + vertex 0.820982 1.55365 2.58595 + vertex 0.818237 1.55124 2.58368 + vertex 0.820894 1.54867 2.58603 + endloop + endfacet + facet normal -0.640207 0.0237957 0.767834 + outer loop + vertex 0.820894 1.54867 2.58603 + vertex 0.823697 1.55112 2.58829 + vertex 0.820982 1.55365 2.58595 + endloop + endfacet + facet normal -0.639479 0.0251012 0.768398 + outer loop + vertex 0.823697 1.55112 2.58829 + vertex 0.823804 1.55618 2.58821 + vertex 0.820982 1.55365 2.58595 + endloop + endfacet + facet normal -0.640963 0.0279435 0.767063 + outer loop + vertex 0.820982 1.55365 2.58595 + vertex 0.823804 1.55618 2.58821 + vertex 0.821087 1.55862 2.58586 + endloop + endfacet + facet normal -0.649636 0.0279886 0.75973 + outer loop + vertex 0.821087 1.55862 2.58586 + vertex 0.818337 1.5562 2.58359 + vertex 0.820982 1.55365 2.58595 + endloop + endfacet + facet normal -0.65047 0.0296662 0.758952 + outer loop + vertex 0.818447 1.56115 2.58349 + vertex 0.818337 1.5562 2.58359 + vertex 0.821087 1.55862 2.58586 + endloop + endfacet + facet normal -0.650568 0.029493 0.758875 + outer loop + vertex 0.821192 1.56358 2.58575 + vertex 0.818447 1.56115 2.58349 + vertex 0.821087 1.55862 2.58586 + endloop + endfacet + facet normal -0.641841 0.0294631 0.766272 + outer loop + vertex 0.821087 1.55862 2.58586 + vertex 0.823894 1.56122 2.58811 + vertex 0.821192 1.56358 2.58575 + endloop + endfacet + facet normal -0.64207 0.0290238 0.766096 + outer loop + vertex 0.823894 1.56122 2.58811 + vertex 0.82398 1.56623 2.58799 + vertex 0.821192 1.56358 2.58575 + endloop + endfacet + facet normal -0.642393 0.029608 0.765804 + outer loop + vertex 0.821192 1.56358 2.58575 + vertex 0.82398 1.56623 2.58799 + vertex 0.821298 1.56855 2.58565 + endloop + endfacet + facet normal -0.650992 0.0296399 0.758505 + outer loop + vertex 0.821298 1.56855 2.58565 + vertex 0.818551 1.56609 2.58339 + vertex 0.821192 1.56358 2.58575 + endloop + endfacet + facet normal -0.651166 0.0299843 0.758343 + outer loop + vertex 0.818659 1.57105 2.58328 + vertex 0.818551 1.56609 2.58339 + vertex 0.821298 1.56855 2.58565 + endloop + endfacet + facet normal -0.650613 0.0309772 0.758778 + outer loop + vertex 0.821444 1.5736 2.58557 + vertex 0.818659 1.57105 2.58328 + vertex 0.821298 1.56855 2.58565 + endloop + endfacet + facet normal -0.642923 0.0308588 0.765309 + outer loop + vertex 0.821298 1.56855 2.58565 + vertex 0.824105 1.57129 2.5879 + vertex 0.821444 1.5736 2.58557 + endloop + endfacet + facet normal -0.642027 0.0325746 0.76599 + outer loop + vertex 0.824105 1.57129 2.5879 + vertex 0.824346 1.57649 2.58788 + vertex 0.821444 1.5736 2.58557 + endloop + endfacet + facet normal -0.643103 0.0344415 0.765005 + outer loop + vertex 0.821444 1.5736 2.58557 + vertex 0.824346 1.57649 2.58788 + vertex 0.821675 1.57883 2.58553 + endloop + endfacet + facet normal -0.650047 0.0347028 0.759101 + outer loop + vertex 0.821675 1.57883 2.58553 + vertex 0.818796 1.57607 2.58319 + vertex 0.821444 1.5736 2.58557 + endloop + endfacet + facet normal -0.650826 0.03614 0.758366 + outer loop + vertex 0.818947 1.58113 2.58308 + vertex 0.818796 1.57607 2.58319 + vertex 0.821675 1.57883 2.58553 + endloop + endfacet + facet normal -0.64937 0.0390415 0.759469 + outer loop + vertex 0.82183 1.58408 2.58539 + vertex 0.818947 1.58113 2.58308 + vertex 0.821675 1.57883 2.58553 + endloop + endfacet + facet normal -0.642007 0.0389892 0.765707 + outer loop + vertex 0.821675 1.57883 2.58553 + vertex 0.82493 1.58222 2.58808 + vertex 0.82183 1.58408 2.58539 + endloop + endfacet + facet normal -0.641022 0.0416323 0.766392 + outer loop + vertex 0.82493 1.58222 2.58808 + vertex 0.824649 1.58753 2.58756 + vertex 0.82183 1.58408 2.58539 + endloop + endfacet + facet normal -0.642339 0.043467 0.765187 + outer loop + vertex 0.82183 1.58408 2.58539 + vertex 0.824649 1.58753 2.58756 + vertex 0.821884 1.58917 2.58515 + endloop + endfacet + facet normal -0.649608 0.0432508 0.759038 + outer loop + vertex 0.821884 1.58917 2.58515 + vertex 0.819083 1.58618 2.58292 + vertex 0.82183 1.58408 2.58539 + endloop + endfacet + facet normal -0.650851 0.0452947 0.757853 + outer loop + vertex 0.819221 1.5912 2.58274 + vertex 0.819083 1.58618 2.58292 + vertex 0.821884 1.58917 2.58515 + endloop + endfacet + facet normal -0.649998 0.0471448 0.758472 + outer loop + vertex 0.82198 1.59411 2.58492 + vertex 0.819221 1.5912 2.58274 + vertex 0.821884 1.58917 2.58515 + endloop + endfacet + facet normal -0.642367 0.0472918 0.764937 + outer loop + vertex 0.821884 1.58917 2.58515 + vertex 0.824664 1.59247 2.58728 + vertex 0.82198 1.59411 2.58492 + endloop + endfacet + facet normal -0.641757 0.0488805 0.765349 + outer loop + vertex 0.824664 1.59247 2.58728 + vertex 0.82465 1.59743 2.58695 + vertex 0.82198 1.59411 2.58492 + endloop + endfacet + facet normal -0.642692 0.0501622 0.764481 + outer loop + vertex 0.82198 1.59411 2.58492 + vertex 0.82465 1.59743 2.58695 + vertex 0.822091 1.59852 2.58473 + endloop + endfacet + facet normal -0.650256 0.0500699 0.758064 + outer loop + vertex 0.822091 1.59852 2.58473 + vertex 0.819474 1.59629 2.58263 + vertex 0.82198 1.59411 2.58492 + endloop + endfacet + facet normal -0.650597 0.0507908 0.757723 + outer loop + vertex 0.820257 1.60202 2.58292 + vertex 0.819474 1.59629 2.58263 + vertex 0.822091 1.59852 2.58473 + endloop + endfacet + facet normal -0.646442 0.0546587 0.761003 + outer loop + vertex 0.824208 1.60287 2.58621 + vertex 0.820257 1.60202 2.58292 + vertex 0.822091 1.59852 2.58473 + endloop + endfacet + facet normal -0.645798 0.0476644 0.762019 + outer loop + vertex 0.824208 1.60287 2.58621 + vertex 0.822346 1.60636 2.58441 + vertex 0.820257 1.60202 2.58292 + endloop + endfacet + facet normal -0.641711 0.0514874 0.765217 + outer loop + vertex 0.824998 1.60854 2.58649 + vertex 0.822346 1.60636 2.58441 + vertex 0.824208 1.60287 2.58621 + endloop + endfacet + facet normal -0.63624 0.0504969 0.769837 + outer loop + vertex 0.824208 1.60287 2.58621 + vertex 0.827654 1.60601 2.58885 + vertex 0.824998 1.60854 2.58649 + endloop + endfacet + facet normal -0.635156 0.0523556 0.770607 + outer loop + vertex 0.827654 1.60601 2.58885 + vertex 0.827973 1.61115 2.58877 + vertex 0.824998 1.60854 2.58649 + endloop + endfacet + facet normal -0.63561 0.0532529 0.770171 + outer loop + vertex 0.824998 1.60854 2.58649 + vertex 0.827973 1.61115 2.58877 + vertex 0.825265 1.61355 2.58637 + endloop + endfacet + facet normal -0.641034 0.0534289 0.76565 + outer loop + vertex 0.825265 1.61355 2.58637 + vertex 0.822457 1.61065 2.58422 + vertex 0.824998 1.60854 2.58649 + endloop + endfacet + facet normal -0.642154 0.0553085 0.764577 + outer loop + vertex 0.822269 1.6157 2.58369 + vertex 0.822457 1.61065 2.58422 + vertex 0.825265 1.61355 2.58637 + endloop + endfacet + facet normal -0.641415 0.0569599 0.765077 + outer loop + vertex 0.825514 1.61856 2.5862 + vertex 0.822269 1.6157 2.58369 + vertex 0.825265 1.61355 2.58637 + endloop + endfacet + facet normal -0.63545 0.0568271 0.770048 + outer loop + vertex 0.825265 1.61355 2.58637 + vertex 0.82822 1.61612 2.58861 + vertex 0.825514 1.61856 2.5862 + endloop + endfacet + facet normal -0.6339 0.0595957 0.771115 + outer loop + vertex 0.82822 1.61612 2.58861 + vertex 0.828464 1.62109 2.58843 + vertex 0.825514 1.61856 2.5862 + endloop + endfacet + facet normal -0.634925 0.0616843 0.770107 + outer loop + vertex 0.825514 1.61856 2.5862 + vertex 0.828464 1.62109 2.58843 + vertex 0.825817 1.62356 2.58605 + endloop + endfacet + facet normal -0.641661 0.0619239 0.764484 + outer loop + vertex 0.825817 1.62356 2.58605 + vertex 0.822901 1.62105 2.58381 + vertex 0.825514 1.61856 2.5862 + endloop + endfacet + facet normal -0.633243 0.0645905 0.771253 + outer loop + vertex 0.828464 1.62109 2.58843 + vertex 0.828728 1.62615 2.58822 + vertex 0.825817 1.62356 2.58605 + endloop + endfacet + facet normal -0.634558 0.0671568 0.769952 + outer loop + vertex 0.825817 1.62356 2.58605 + vertex 0.828728 1.62615 2.58822 + vertex 0.826085 1.62858 2.58583 + endloop + endfacet + facet normal -0.642205 0.0672898 0.763574 + outer loop + vertex 0.826085 1.62858 2.58583 + vertex 0.823227 1.62601 2.58366 + vertex 0.825817 1.62356 2.58605 + endloop + endfacet + facet normal -0.643408 0.0696727 0.762346 + outer loop + vertex 0.823478 1.631 2.58341 + vertex 0.823227 1.62601 2.58366 + vertex 0.826085 1.62858 2.58583 + endloop + endfacet + facet normal -0.642559 0.0711646 0.762925 + outer loop + vertex 0.826418 1.63379 2.58563 + vertex 0.823478 1.631 2.58341 + vertex 0.826085 1.62858 2.58583 + endloop + endfacet + facet normal -0.634928 0.0709305 0.769308 + outer loop + vertex 0.826085 1.62858 2.58583 + vertex 0.829075 1.63138 2.58804 + vertex 0.826418 1.63379 2.58563 + endloop + endfacet + facet normal -0.634707 0.0713206 0.769454 + outer loop + vertex 0.829075 1.63138 2.58804 + vertex 0.829778 1.63714 2.58809 + vertex 0.826418 1.63379 2.58563 + endloop + endfacet + facet normal -0.63571 0.0730518 0.768464 + outer loop + vertex 0.826418 1.63379 2.58563 + vertex 0.829778 1.63714 2.58809 + vertex 0.826727 1.6391 2.58538 + endloop + endfacet + facet normal -0.643482 0.0731993 0.761953 + outer loop + vertex 0.826727 1.6391 2.58538 + vertex 0.823739 1.63611 2.58314 + vertex 0.826418 1.63379 2.58563 + endloop + endfacet + facet normal -0.644143 0.074363 0.761282 + outer loop + vertex 0.824106 1.64138 2.58294 + vertex 0.823739 1.63611 2.58314 + vertex 0.826727 1.6391 2.58538 + endloop + endfacet + facet normal -0.64448 0.0737367 0.761058 + outer loop + vertex 0.82706 1.64417 2.58517 + vertex 0.824106 1.64138 2.58294 + vertex 0.826727 1.6391 2.58538 + endloop + endfacet + facet normal -0.637067 0.0735064 0.767295 + outer loop + vertex 0.826727 1.6391 2.58538 + vertex 0.829619 1.64246 2.58746 + vertex 0.82706 1.64417 2.58517 + endloop + endfacet + facet normal -0.637026 0.0736021 0.767321 + outer loop + vertex 0.829619 1.64246 2.58746 + vertex 0.829694 1.64703 2.58708 + vertex 0.82706 1.64417 2.58517 + endloop + endfacet + facet normal -0.636833 0.0732987 0.76751 + outer loop + vertex 0.82706 1.64417 2.58517 + vertex 0.829694 1.64703 2.58708 + vertex 0.827634 1.64805 2.58528 + endloop + endfacet + facet normal -0.645462 0.0747759 0.760123 + outer loop + vertex 0.827634 1.64805 2.58528 + vertex 0.824846 1.64712 2.583 + vertex 0.82706 1.64417 2.58517 + endloop + endfacet + facet normal -0.645729 0.0765839 0.759716 + outer loop + vertex 0.827634 1.64805 2.58528 + vertex 0.827313 1.65132 2.58467 + vertex 0.824846 1.64712 2.583 + endloop + endfacet + facet normal -0.646931 0.0777458 0.758575 + outer loop + vertex 0.824846 1.64712 2.583 + vertex 0.827313 1.65132 2.58467 + vertex 0.824754 1.65232 2.58239 + endloop + endfacet + facet normal -0.646225 0.0803229 0.758908 + outer loop + vertex 0.827313 1.65132 2.58467 + vertex 0.827417 1.65567 2.5843 + vertex 0.824754 1.65232 2.58239 + endloop + endfacet + facet normal -0.638379 0.0806971 0.76548 + outer loop + vertex 0.827417 1.65567 2.5843 + vertex 0.827313 1.65132 2.58467 + vertex 0.82992 1.65395 2.58657 + endloop + endfacet + facet normal -0.638352 0.0806496 0.765508 + outer loop + vertex 0.82992 1.65395 2.58657 + vertex 0.827313 1.65132 2.58467 + vertex 0.829356 1.65036 2.58648 + endloop + endfacet + facet normal -0.63914 0.0782212 0.765102 + outer loop + vertex 0.827634 1.64805 2.58528 + vertex 0.829356 1.65036 2.58648 + vertex 0.827313 1.65132 2.58467 + endloop + endfacet + facet normal -0.636348 0.0747478 0.767772 + outer loop + vertex 0.829356 1.65036 2.58648 + vertex 0.827634 1.64805 2.58528 + vertex 0.829694 1.64703 2.58708 + endloop + endfacet + facet normal -0.62863 0.0766454 0.773918 + outer loop + vertex 0.829356 1.65036 2.58648 + vertex 0.829694 1.64703 2.58708 + vertex 0.832163 1.65091 2.5887 + endloop + endfacet + facet normal -0.628796 0.0789485 0.773552 + outer loop + vertex 0.829356 1.65036 2.58648 + vertex 0.832163 1.65091 2.5887 + vertex 0.82992 1.65395 2.58657 + endloop + endfacet + facet normal -0.628317 0.0795333 0.773881 + outer loop + vertex 0.832163 1.65091 2.5887 + vertex 0.832868 1.65621 2.58873 + vertex 0.82992 1.65395 2.58657 + endloop + endfacet + facet normal -0.629527 0.0823396 0.772604 + outer loop + vertex 0.82992 1.65395 2.58657 + vertex 0.832868 1.65621 2.58873 + vertex 0.83025 1.65859 2.58634 + endloop + endfacet + facet normal -0.621307 0.078571 0.779618 + outer loop + vertex 0.832868 1.65621 2.58873 + vertex 0.832163 1.65091 2.5887 + vertex 0.835539 1.65366 2.59112 + endloop + endfacet + facet normal -0.620051 0.0806274 0.780407 + outer loop + vertex 0.835929 1.65866 2.59091 + vertex 0.832868 1.65621 2.58873 + vertex 0.835539 1.65366 2.59112 + endloop + endfacet + facet normal -0.612709 0.0802925 0.78622 + outer loop + vertex 0.835539 1.65366 2.59112 + vertex 0.838625 1.6562 2.59326 + vertex 0.835929 1.65866 2.59091 + endloop + endfacet + facet normal -0.611215 0.082796 0.787122 + outer loop + vertex 0.838625 1.6562 2.59326 + vertex 0.839011 1.66126 2.59303 + vertex 0.835929 1.65866 2.59091 + endloop + endfacet + facet normal -0.612444 0.085251 0.785903 + outer loop + vertex 0.835929 1.65866 2.59091 + vertex 0.839011 1.66126 2.59303 + vertex 0.836343 1.66373 2.59068 + endloop + endfacet + facet normal -0.619859 0.0855906 0.780032 + outer loop + vertex 0.836343 1.66373 2.59068 + vertex 0.833265 1.66114 2.58852 + vertex 0.835929 1.65866 2.59091 + endloop + endfacet + facet normal -0.610149 0.0890179 0.78727 + outer loop + vertex 0.839011 1.66126 2.59303 + vertex 0.839773 1.66677 2.593 + vertex 0.836343 1.66373 2.59068 + endloop + endfacet + facet normal -0.610676 0.0900111 0.786748 + outer loop + vertex 0.836343 1.66373 2.59068 + vertex 0.839773 1.66677 2.593 + vertex 0.836703 1.66887 2.59037 + endloop + endfacet + facet normal -0.61935 0.0902095 0.779915 + outer loop + vertex 0.836703 1.66887 2.59037 + vertex 0.83363 1.66614 2.58825 + vertex 0.836343 1.66373 2.59068 + endloop + endfacet + facet normal -0.609055 0.0934578 0.787603 + outer loop + vertex 0.839773 1.66677 2.593 + vertex 0.839671 1.67196 2.5923 + vertex 0.836703 1.66887 2.59037 + endloop + endfacet + facet normal -0.609052 0.0934541 0.787605 + outer loop + vertex 0.836703 1.66887 2.59037 + vertex 0.839671 1.67196 2.5923 + vertex 0.83708 1.67376 2.59009 + endloop + endfacet + facet normal -0.619679 0.0937798 0.779232 + outer loop + vertex 0.83708 1.67376 2.59009 + vertex 0.834082 1.67126 2.588 + vertex 0.836703 1.66887 2.59037 + endloop + endfacet + facet normal -0.598629 0.0947097 0.795408 + outer loop + vertex 0.839773 1.66677 2.593 + vertex 0.842392 1.67084 2.59448 + vertex 0.839671 1.67196 2.5923 + endloop + endfacet + facet normal -0.596498 0.101418 0.796181 + outer loop + vertex 0.842392 1.67084 2.59448 + vertex 0.842577 1.67539 2.59404 + vertex 0.839671 1.67196 2.5923 + endloop + endfacet + facet normal -0.593322 0.0972622 0.799067 + outer loop + vertex 0.839671 1.67196 2.5923 + vertex 0.842577 1.67539 2.59404 + vertex 0.839804 1.67646 2.59185 + endloop + endfacet + facet normal -0.592464 0.100077 0.799357 + outer loop + vertex 0.839804 1.67646 2.59185 + vertex 0.842577 1.67539 2.59404 + vertex 0.842506 1.68059 2.59334 + endloop + endfacet + facet normal -0.601324 0.0973019 0.793059 + outer loop + vertex 0.842663 1.6675 2.5951 + vertex 0.842392 1.67084 2.59448 + vertex 0.839773 1.66677 2.593 + endloop + endfacet + facet normal -0.60054 0.0900487 0.794508 + outer loop + vertex 0.842663 1.6675 2.5951 + vertex 0.839773 1.66677 2.593 + vertex 0.842034 1.66376 2.59505 + endloop + endfacet + facet normal -0.581662 0.0866883 0.808798 + outer loop + vertex 0.842034 1.66376 2.59505 + vertex 0.844839 1.66654 2.59677 + vertex 0.842663 1.6675 2.5951 + endloop + endfacet + facet normal -0.57941 0.093283 0.809681 + outer loop + vertex 0.844556 1.66988 2.59618 + vertex 0.842663 1.6675 2.5951 + vertex 0.844839 1.66654 2.59677 + endloop + endfacet + facet normal -0.563605 0.0965024 0.820388 + outer loop + vertex 0.844556 1.66988 2.59618 + vertex 0.844839 1.66654 2.59677 + vertex 0.847722 1.67085 2.59824 + endloop + endfacet + facet normal -0.56453 0.102418 0.819034 + outer loop + vertex 0.844556 1.66988 2.59618 + vertex 0.847722 1.67085 2.59824 + vertex 0.845359 1.6738 2.59624 + endloop + endfacet + facet normal -0.563081 0.0960089 0.820806 + outer loop + vertex 0.844839 1.66654 2.59677 + vertex 0.847709 1.66545 2.59886 + vertex 0.847722 1.67085 2.59824 + endloop + endfacet + facet normal -0.565265 0.0888669 0.820109 + outer loop + vertex 0.844639 1.66198 2.59712 + vertex 0.847709 1.66545 2.59886 + vertex 0.844839 1.66654 2.59677 + endloop + endfacet + facet normal -0.582935 0.088672 0.807666 + outer loop + vertex 0.844639 1.66198 2.59712 + vertex 0.844839 1.66654 2.59677 + vertex 0.842034 1.66376 2.59505 + endloop + endfacet + facet normal -0.585299 0.083806 0.806475 + outer loop + vertex 0.841649 1.65894 2.59527 + vertex 0.844639 1.66198 2.59712 + vertex 0.842034 1.66376 2.59505 + endloop + endfacet + facet normal -0.600572 0.0845048 0.795093 + outer loop + vertex 0.842034 1.66376 2.59505 + vertex 0.839011 1.66126 2.59303 + vertex 0.841649 1.65894 2.59527 + endloop + endfacet + facet normal -0.585155 0.0835874 0.806602 + outer loop + vertex 0.844469 1.65709 2.59751 + vertex 0.844639 1.66198 2.59712 + vertex 0.841649 1.65894 2.59527 + endloop + endfacet + facet normal -0.586817 0.0800362 0.805755 + outer loop + vertex 0.841443 1.65392 2.59562 + vertex 0.844469 1.65709 2.59751 + vertex 0.841649 1.65894 2.59527 + endloop + endfacet + facet normal -0.600405 0.0798957 0.795695 + outer loop + vertex 0.841649 1.65894 2.59527 + vertex 0.838625 1.6562 2.59326 + vertex 0.841443 1.65392 2.59562 + endloop + endfacet + facet normal -0.601191 0.0784637 0.795244 + outer loop + vertex 0.838625 1.6562 2.59326 + vertex 0.838325 1.65122 2.59353 + vertex 0.841443 1.65392 2.59562 + endloop + endfacet + facet normal -0.600468 0.0771017 0.795923 + outer loop + vertex 0.841443 1.65392 2.59562 + vertex 0.838325 1.65122 2.59353 + vertex 0.841153 1.64879 2.5959 + endloop + endfacet + facet normal -0.585809 0.0768639 0.806796 + outer loop + vertex 0.841153 1.64879 2.5959 + vertex 0.844661 1.65181 2.59815 + vertex 0.841443 1.65392 2.59562 + endloop + endfacet + facet normal -0.585761 0.0767752 0.806839 + outer loop + vertex 0.843933 1.64632 2.59815 + vertex 0.844661 1.65181 2.59815 + vertex 0.841153 1.64879 2.5959 + endloop + endfacet + facet normal -0.587395 0.0740747 0.805903 + outer loop + vertex 0.840696 1.64364 2.59604 + vertex 0.843933 1.64632 2.59815 + vertex 0.841153 1.64879 2.5959 + endloop + endfacet + facet normal -0.600698 0.0749847 0.795952 + outer loop + vertex 0.841153 1.64879 2.5959 + vertex 0.837946 1.64621 2.59372 + vertex 0.840696 1.64364 2.59604 + endloop + endfacet + facet normal -0.602263 0.0724559 0.795003 + outer loop + vertex 0.837946 1.64621 2.59372 + vertex 0.837222 1.6408 2.59366 + vertex 0.840696 1.64364 2.59604 + endloop + endfacet + facet normal -0.601936 0.0717992 0.79531 + outer loop + vertex 0.840696 1.64364 2.59604 + vertex 0.837222 1.6408 2.59366 + vertex 0.840353 1.63856 2.59624 + endloop + endfacet + facet normal -0.588018 0.0712669 0.805702 + outer loop + vertex 0.840353 1.63856 2.59624 + vertex 0.843523 1.64129 2.59831 + vertex 0.840696 1.64364 2.59604 + endloop + endfacet + facet normal -0.586817 0.0690652 0.806769 + outer loop + vertex 0.843139 1.63626 2.59846 + vertex 0.843523 1.64129 2.59831 + vertex 0.840353 1.63856 2.59624 + endloop + endfacet + facet normal -0.586803 0.0690902 0.806777 + outer loop + vertex 0.840036 1.63372 2.59642 + vertex 0.843139 1.63626 2.59846 + vertex 0.840353 1.63856 2.59624 + endloop + endfacet + facet normal -0.601079 0.0696223 0.796151 + outer loop + vertex 0.840353 1.63856 2.59624 + vertex 0.837398 1.63559 2.59426 + vertex 0.840036 1.63372 2.59642 + endloop + endfacet + facet normal -0.601336 0.0690888 0.796003 + outer loop + vertex 0.837398 1.63559 2.59426 + vertex 0.837343 1.63105 2.59462 + vertex 0.840036 1.63372 2.59642 + endloop + endfacet + facet normal -0.601821 0.0698706 0.795569 + outer loop + vertex 0.840036 1.63372 2.59642 + vertex 0.837343 1.63105 2.59462 + vertex 0.839469 1.63 2.59632 + endloop + endfacet + facet normal -0.585401 0.0670213 0.807969 + outer loop + vertex 0.839469 1.63 2.59632 + vertex 0.842449 1.63075 2.59841 + vertex 0.840036 1.63372 2.59642 + endloop + endfacet + facet normal -0.585282 0.0660901 0.808132 + outer loop + vertex 0.839469 1.63 2.59632 + vertex 0.839837 1.62669 2.59685 + vertex 0.842449 1.63075 2.59841 + endloop + endfacet + facet normal -0.581918 0.0629015 0.810811 + outer loop + vertex 0.839837 1.62669 2.59685 + vertex 0.842691 1.62547 2.599 + vertex 0.842449 1.63075 2.59841 + endloop + endfacet + facet normal -0.56543 0.0649161 0.822238 + outer loop + vertex 0.842449 1.63075 2.59841 + vertex 0.842691 1.62547 2.599 + vertex 0.845937 1.6289 2.60096 + endloop + endfacet + facet normal -0.566504 0.0621711 0.82171 + outer loop + vertex 0.846067 1.63412 2.60065 + vertex 0.842449 1.63075 2.59841 + vertex 0.845937 1.6289 2.60096 + endloop + endfacet + facet normal -0.546651 0.0624552 0.835028 + outer loop + vertex 0.845937 1.6289 2.60096 + vertex 0.849218 1.63233 2.60285 + vertex 0.846067 1.63412 2.60065 + endloop + endfacet + facet normal -0.546366 0.0631227 0.835164 + outer loop + vertex 0.849218 1.63233 2.60285 + vertex 0.849333 1.63732 2.60255 + vertex 0.846067 1.63412 2.60065 + endloop + endfacet + facet normal -0.547686 0.0650647 0.83415 + outer loop + vertex 0.846067 1.63412 2.60065 + vertex 0.849333 1.63732 2.60255 + vertex 0.846368 1.63918 2.60046 + endloop + endfacet + facet normal -0.567249 0.0657104 0.820921 + outer loop + vertex 0.846368 1.63918 2.60046 + vertex 0.843139 1.63626 2.59846 + vertex 0.846067 1.63412 2.60065 + endloop + endfacet + facet normal -0.546516 0.067569 0.834718 + outer loop + vertex 0.849333 1.63732 2.60255 + vertex 0.849547 1.64226 2.60229 + vertex 0.846368 1.63918 2.60046 + endloop + endfacet + facet normal -0.547806 0.0694966 0.833714 + outer loop + vertex 0.846368 1.63918 2.60046 + vertex 0.849547 1.64226 2.60229 + vertex 0.846668 1.64409 2.60024 + endloop + endfacet + facet normal -0.567579 0.0701261 0.820327 + outer loop + vertex 0.846668 1.64409 2.60024 + vertex 0.843523 1.64129 2.59831 + vertex 0.846368 1.63918 2.60046 + endloop + endfacet + facet normal -0.568743 0.0721099 0.819348 + outer loop + vertex 0.843933 1.64632 2.59815 + vertex 0.843523 1.64129 2.59831 + vertex 0.846668 1.64409 2.60024 + endloop + endfacet + facet normal -0.568082 0.0732547 0.819705 + outer loop + vertex 0.847046 1.64882 2.60008 + vertex 0.843933 1.64632 2.59815 + vertex 0.846668 1.64409 2.60024 + endloop + endfacet + facet normal -0.547466 0.0720865 0.833717 + outer loop + vertex 0.846668 1.64409 2.60024 + vertex 0.849759 1.64709 2.60201 + vertex 0.847046 1.64882 2.60008 + endloop + endfacet + facet normal -0.547001 0.0730612 0.833938 + outer loop + vertex 0.849759 1.64709 2.60201 + vertex 0.849897 1.65158 2.60171 + vertex 0.847046 1.64882 2.60008 + endloop + endfacet + facet normal -0.545815 0.0712831 0.834868 + outer loop + vertex 0.847046 1.64882 2.60008 + vertex 0.849897 1.65158 2.60171 + vertex 0.847632 1.65253 2.60015 + endloop + endfacet + facet normal -0.568222 0.0751054 0.81944 + outer loop + vertex 0.847632 1.65253 2.60015 + vertex 0.844661 1.65181 2.59815 + vertex 0.847046 1.64882 2.60008 + endloop + endfacet + facet normal -0.568659 0.0787046 0.8188 + outer loop + vertex 0.847632 1.65253 2.60015 + vertex 0.847294 1.65588 2.59959 + vertex 0.844661 1.65181 2.59815 + endloop + endfacet + facet normal -0.569808 0.079767 0.817897 + outer loop + vertex 0.844661 1.65181 2.59815 + vertex 0.847294 1.65588 2.59959 + vertex 0.844469 1.65709 2.59751 + endloop + endfacet + facet normal -0.568174 0.0847069 0.818537 + outer loop + vertex 0.847294 1.65588 2.59959 + vertex 0.847484 1.66049 2.59925 + vertex 0.844469 1.65709 2.59751 + endloop + endfacet + facet normal -0.551289 0.0823557 0.83024 + outer loop + vertex 0.847632 1.65253 2.60015 + vertex 0.849536 1.6549 2.60118 + vertex 0.847294 1.65588 2.59959 + endloop + endfacet + facet normal -0.544649 0.0748081 0.835321 + outer loop + vertex 0.849536 1.6549 2.60118 + vertex 0.847632 1.65253 2.60015 + vertex 0.849897 1.65158 2.60171 + endloop + endfacet + facet normal -0.546946 0.0713091 0.834125 + outer loop + vertex 0.849547 1.64226 2.60229 + vertex 0.849759 1.64709 2.60201 + vertex 0.846668 1.64409 2.60024 + endloop + endfacet + facet normal -0.544411 0.0593792 0.836714 + outer loop + vertex 0.849502 1.627 2.60341 + vertex 0.849218 1.63233 2.60285 + vertex 0.845937 1.6289 2.60096 + endloop + endfacet + facet normal -0.543548 0.0615254 0.83712 + outer loop + vertex 0.845795 1.62366 2.60125 + vertex 0.849502 1.627 2.60341 + vertex 0.845937 1.6289 2.60096 + endloop + endfacet + facet normal -0.543406 0.0612979 0.837229 + outer loop + vertex 0.848774 1.62144 2.60335 + vertex 0.849502 1.627 2.60341 + vertex 0.845795 1.62366 2.60125 + endloop + endfacet + facet normal -0.545052 0.0582754 0.836374 + outer loop + vertex 0.845454 1.61853 2.60139 + vertex 0.848774 1.62144 2.60335 + vertex 0.845795 1.62366 2.60125 + endloop + endfacet + facet normal -0.562451 0.059123 0.824714 + outer loop + vertex 0.845795 1.62366 2.60125 + vertex 0.842559 1.62046 2.59927 + vertex 0.845454 1.61853 2.60139 + endloop + endfacet + facet normal -0.564036 0.0558205 0.823862 + outer loop + vertex 0.842559 1.62046 2.59927 + vertex 0.842364 1.61553 2.59947 + vertex 0.845454 1.61853 2.60139 + endloop + endfacet + facet normal -0.5812 0.0560085 0.811831 + outer loop + vertex 0.842364 1.61553 2.59947 + vertex 0.842559 1.62046 2.59927 + vertex 0.839532 1.61726 2.59733 + endloop + endfacet + facet normal -0.582459 0.0530624 0.811126 + outer loop + vertex 0.839461 1.61225 2.5976 + vertex 0.842364 1.61553 2.59947 + vertex 0.839532 1.61726 2.59733 + endloop + endfacet + facet normal -0.595381 0.0527244 0.801712 + outer loop + vertex 0.839461 1.61225 2.5976 + vertex 0.839532 1.61726 2.59733 + vertex 0.836577 1.61411 2.59534 + endloop + endfacet + facet normal -0.595969 0.0513906 0.801362 + outer loop + vertex 0.836495 1.609 2.59561 + vertex 0.839461 1.61225 2.5976 + vertex 0.836577 1.61411 2.59534 + endloop + endfacet + facet normal -0.606204 0.0511506 0.793663 + outer loop + vertex 0.836577 1.61411 2.59534 + vertex 0.833631 1.61124 2.59327 + vertex 0.836495 1.609 2.59561 + endloop + endfacet + facet normal -0.6062 0.0511589 0.793665 + outer loop + vertex 0.833631 1.61124 2.59327 + vertex 0.833461 1.6062 2.59347 + vertex 0.836495 1.609 2.59561 + endloop + endfacet + facet normal -0.605157 0.0493345 0.794576 + outer loop + vertex 0.836495 1.609 2.59561 + vertex 0.833461 1.6062 2.59347 + vertex 0.836325 1.60379 2.5958 + endloop + endfacet + facet normal -0.592863 0.0492754 0.803795 + outer loop + vertex 0.836325 1.60379 2.5958 + vertex 0.839762 1.6069 2.59815 + vertex 0.836495 1.609 2.59561 + endloop + endfacet + facet normal -0.592402 0.0484731 0.804183 + outer loop + vertex 0.839135 1.60132 2.59802 + vertex 0.839762 1.6069 2.59815 + vertex 0.836325 1.60379 2.5958 + endloop + endfacet + facet normal -0.59261 0.0481168 0.804051 + outer loop + vertex 0.836053 1.59866 2.59591 + vertex 0.839135 1.60132 2.59802 + vertex 0.836325 1.60379 2.5958 + endloop + endfacet + facet normal -0.60404 0.0485449 0.795474 + outer loop + vertex 0.836325 1.60379 2.5958 + vertex 0.833272 1.60116 2.59364 + vertex 0.836053 1.59866 2.59591 + endloop + endfacet + facet normal -0.604175 0.0483147 0.795386 + outer loop + vertex 0.833272 1.60116 2.59364 + vertex 0.833072 1.59622 2.59379 + vertex 0.836053 1.59866 2.59591 + endloop + endfacet + facet normal -0.602995 0.0459827 0.796418 + outer loop + vertex 0.836053 1.59866 2.59591 + vertex 0.833072 1.59622 2.59379 + vertex 0.835828 1.5937 2.59602 + endloop + endfacet + facet normal -0.592175 0.045683 0.804513 + outer loop + vertex 0.835828 1.5937 2.59602 + vertex 0.838847 1.59625 2.5981 + vertex 0.836053 1.59866 2.59591 + endloop + endfacet + facet normal -0.590595 0.0427454 0.805835 + outer loop + vertex 0.838661 1.5913 2.59823 + vertex 0.838847 1.59625 2.5981 + vertex 0.835828 1.5937 2.59602 + endloop + endfacet + facet normal -0.591016 0.0419996 0.805566 + outer loop + vertex 0.835581 1.5887 2.5961 + vertex 0.838661 1.5913 2.59823 + vertex 0.835828 1.5937 2.59602 + endloop + endfacet + facet normal -0.601938 0.0424111 0.797416 + outer loop + vertex 0.835828 1.5937 2.59602 + vertex 0.832797 1.5913 2.59386 + vertex 0.835581 1.5887 2.5961 + endloop + endfacet + facet normal -0.602218 0.0419502 0.797229 + outer loop + vertex 0.832797 1.5913 2.59386 + vertex 0.832199 1.58594 2.59369 + vertex 0.835581 1.5887 2.5961 + endloop + endfacet + facet normal -0.600958 0.0394656 0.798305 + outer loop + vertex 0.835581 1.5887 2.5961 + vertex 0.832199 1.58594 2.59369 + vertex 0.83544 1.58361 2.59625 + endloop + endfacet + facet normal -0.589322 0.0393879 0.806938 + outer loop + vertex 0.83544 1.58361 2.59625 + vertex 0.838515 1.58634 2.59836 + vertex 0.835581 1.5887 2.5961 + endloop + endfacet + facet normal -0.587499 0.0361941 0.808415 + outer loop + vertex 0.8384 1.58136 2.5985 + vertex 0.838515 1.58634 2.59836 + vertex 0.83544 1.58361 2.59625 + endloop + endfacet + facet normal -0.587203 0.036773 0.808604 + outer loop + vertex 0.8354 1.57856 2.59645 + vertex 0.8384 1.58136 2.5985 + vertex 0.83544 1.58361 2.59625 + endloop + endfacet + facet normal -0.597948 0.0365439 0.800702 + outer loop + vertex 0.83544 1.58361 2.59625 + vertex 0.832504 1.58062 2.59419 + vertex 0.8354 1.57856 2.59645 + endloop + endfacet + facet normal -0.598605 0.0351518 0.800273 + outer loop + vertex 0.832504 1.58062 2.59419 + vertex 0.832485 1.57561 2.5944 + vertex 0.8354 1.57856 2.59645 + endloop + endfacet + facet normal -0.597315 0.033149 0.801321 + outer loop + vertex 0.8354 1.57856 2.59645 + vertex 0.832485 1.57561 2.5944 + vertex 0.835302 1.57359 2.59658 + endloop + endfacet + facet normal -0.585496 0.0331498 0.809997 + outer loop + vertex 0.835302 1.57359 2.59658 + vertex 0.838293 1.57639 2.59863 + vertex 0.8354 1.57856 2.59645 + endloop + endfacet + facet normal -0.583963 0.0306374 0.811202 + outer loop + vertex 0.838168 1.57143 2.59873 + vertex 0.838293 1.57639 2.59863 + vertex 0.835302 1.57359 2.59658 + endloop + endfacet + facet normal -0.584464 0.0296506 0.810878 + outer loop + vertex 0.835152 1.5687 2.59665 + vertex 0.838168 1.57143 2.59873 + vertex 0.835302 1.57359 2.59658 + endloop + endfacet + facet normal -0.597255 0.0299078 0.801493 + outer loop + vertex 0.835302 1.57359 2.59658 + vertex 0.832393 1.57065 2.59452 + vertex 0.835152 1.5687 2.59665 + endloop + endfacet + facet normal -0.597717 0.0289167 0.801185 + outer loop + vertex 0.832393 1.57065 2.59452 + vertex 0.832297 1.56583 2.59463 + vertex 0.835152 1.5687 2.59665 + endloop + endfacet + facet normal -0.597287 0.0282443 0.80153 + outer loop + vertex 0.835152 1.5687 2.59665 + vertex 0.832297 1.56583 2.59463 + vertex 0.834901 1.56401 2.59663 + endloop + endfacet + facet normal -0.583793 0.0274737 0.811438 + outer loop + vertex 0.834901 1.56401 2.59663 + vertex 0.837943 1.56641 2.59874 + vertex 0.835152 1.5687 2.59665 + endloop + endfacet + facet normal -0.582606 0.0251508 0.812366 + outer loop + vertex 0.837373 1.56094 2.5985 + vertex 0.837943 1.56641 2.59874 + vertex 0.834901 1.56401 2.59663 + endloop + endfacet + facet normal -0.582325 0.0254919 0.812556 + outer loop + vertex 0.834428 1.56038 2.5964 + vertex 0.837373 1.56094 2.5985 + vertex 0.834901 1.56401 2.59663 + endloop + endfacet + facet normal -0.597778 0.028214 0.801165 + outer loop + vertex 0.834901 1.56401 2.59663 + vertex 0.832293 1.56139 2.59478 + vertex 0.834428 1.56038 2.5964 + endloop + endfacet + facet normal -0.598424 0.0261725 0.800752 + outer loop + vertex 0.832749 1.55811 2.59522 + vertex 0.834428 1.56038 2.5964 + vertex 0.832293 1.56139 2.59478 + endloop + endfacet + facet normal -0.609289 0.0235465 0.792598 + outer loop + vertex 0.832749 1.55811 2.59522 + vertex 0.832293 1.56139 2.59478 + vertex 0.829923 1.55722 2.59308 + endloop + endfacet + facet normal -0.608623 0.0199721 0.793208 + outer loop + vertex 0.832749 1.55811 2.59522 + vertex 0.829923 1.55722 2.59308 + vertex 0.83231 1.55428 2.59498 + endloop + endfacet + facet normal -0.593061 0.017445 0.804969 + outer loop + vertex 0.83231 1.55428 2.59498 + vertex 0.834907 1.55704 2.59684 + vertex 0.832749 1.55811 2.59522 + endloop + endfacet + facet normal -0.593225 0.0176858 0.804842 + outer loop + vertex 0.83494 1.55245 2.59696 + vertex 0.834907 1.55704 2.59684 + vertex 0.83231 1.55428 2.59498 + endloop + endfacet + facet normal -0.593296 0.0175322 0.804794 + outer loop + vertex 0.832105 1.54936 2.59494 + vertex 0.83494 1.55245 2.59696 + vertex 0.83231 1.55428 2.59498 + endloop + endfacet + facet normal -0.605751 0.0181343 0.795447 + outer loop + vertex 0.83231 1.55428 2.59498 + vertex 0.829407 1.55153 2.59284 + vertex 0.832105 1.54936 2.59494 + endloop + endfacet + facet normal -0.605684 0.0182645 0.795495 + outer loop + vertex 0.829407 1.55153 2.59284 + vertex 0.829228 1.54635 2.59282 + vertex 0.832105 1.54936 2.59494 + endloop + endfacet + facet normal -0.604222 0.0160559 0.796654 + outer loop + vertex 0.832105 1.54936 2.59494 + vertex 0.829228 1.54635 2.59282 + vertex 0.832017 1.54433 2.59497 + endloop + endfacet + facet normal -0.592732 0.0159146 0.805243 + outer loop + vertex 0.832017 1.54433 2.59497 + vertex 0.834893 1.54752 2.59703 + vertex 0.832105 1.54936 2.59494 + endloop + endfacet + facet normal -0.592522 0.0156229 0.805403 + outer loop + vertex 0.834846 1.54251 2.59709 + vertex 0.834893 1.54752 2.59703 + vertex 0.832017 1.54433 2.59497 + endloop + endfacet + facet normal -0.593109 0.0142326 0.804996 + outer loop + vertex 0.831978 1.53931 2.59503 + vertex 0.834846 1.54251 2.59709 + vertex 0.832017 1.54433 2.59497 + endloop + endfacet + facet normal -0.603993 0.0142202 0.796863 + outer loop + vertex 0.832017 1.54433 2.59497 + vertex 0.829166 1.5413 2.59287 + vertex 0.831978 1.53931 2.59503 + endloop + endfacet + facet normal -0.604684 0.0126984 0.796364 + outer loop + vertex 0.829166 1.5413 2.59287 + vertex 0.829139 1.53631 2.59293 + vertex 0.831978 1.53931 2.59503 + endloop + endfacet + facet normal -0.604384 0.0122493 0.796599 + outer loop + vertex 0.831978 1.53931 2.59503 + vertex 0.829139 1.53631 2.59293 + vertex 0.83195 1.53432 2.59509 + endloop + endfacet + facet normal -0.593452 0.0122813 0.804776 + outer loop + vertex 0.83195 1.53432 2.59509 + vertex 0.83481 1.53752 2.59715 + vertex 0.831978 1.53931 2.59503 + endloop + endfacet + facet normal -0.592992 0.0116443 0.805124 + outer loop + vertex 0.834779 1.53253 2.5972 + vertex 0.83481 1.53752 2.59715 + vertex 0.83195 1.53432 2.59509 + endloop + endfacet + facet normal -0.593764 0.00979213 0.80458 + outer loop + vertex 0.831923 1.52934 2.59513 + vertex 0.834779 1.53253 2.5972 + vertex 0.83195 1.53432 2.59509 + endloop + endfacet + facet normal -0.604349 0.00978469 0.796659 + outer loop + vertex 0.83195 1.53432 2.59509 + vertex 0.82911 1.53133 2.59297 + vertex 0.831923 1.52934 2.59513 + endloop + endfacet + facet normal -0.604779 0.00883926 0.796344 + outer loop + vertex 0.82911 1.53133 2.59297 + vertex 0.829079 1.52634 2.593 + vertex 0.831923 1.52934 2.59513 + endloop + endfacet + facet normal -0.603885 0.0074976 0.797036 + outer loop + vertex 0.831923 1.52934 2.59513 + vertex 0.829079 1.52634 2.593 + vertex 0.831898 1.52435 2.59516 + endloop + endfacet + facet normal -0.593742 0.0074879 0.804621 + outer loop + vertex 0.831898 1.52435 2.59516 + vertex 0.834754 1.52753 2.59724 + vertex 0.831923 1.52934 2.59513 + endloop + endfacet + facet normal -0.593037 0.00651189 0.805149 + outer loop + vertex 0.834734 1.52254 2.59726 + vertex 0.834754 1.52753 2.59724 + vertex 0.831898 1.52435 2.59516 + endloop + endfacet + facet normal -0.593415 0.00560224 0.804878 + outer loop + vertex 0.831878 1.51935 2.59518 + vertex 0.834734 1.52254 2.59726 + vertex 0.831898 1.52435 2.59516 + endloop + endfacet + facet normal -0.603525 0.00561238 0.797325 + outer loop + vertex 0.831898 1.52435 2.59516 + vertex 0.829051 1.52135 2.59303 + vertex 0.831878 1.51935 2.59518 + endloop + endfacet + facet normal -0.604147 0.00423137 0.796862 + outer loop + vertex 0.829051 1.52135 2.59303 + vertex 0.829035 1.51636 2.59304 + vertex 0.831878 1.51935 2.59518 + endloop + endfacet + facet normal -0.60358 0.00338281 0.797295 + outer loop + vertex 0.831878 1.51935 2.59518 + vertex 0.829035 1.51636 2.59304 + vertex 0.831867 1.51436 2.59519 + endloop + endfacet + facet normal -0.593571 0.00338107 0.804775 + outer loop + vertex 0.831867 1.51436 2.59519 + vertex 0.834718 1.51755 2.59728 + vertex 0.831878 1.51935 2.59518 + endloop + endfacet + facet normal -0.593053 0.00266671 0.805159 + outer loop + vertex 0.834711 1.51256 2.59729 + vertex 0.834718 1.51755 2.59728 + vertex 0.831867 1.51436 2.59519 + endloop + endfacet + facet normal -0.594117 8.09457e-05 0.804379 + outer loop + vertex 0.831871 1.50937 2.5952 + vertex 0.834711 1.51256 2.59729 + vertex 0.831867 1.51436 2.59519 + endloop + endfacet + facet normal -0.603654 6.97906e-05 0.797246 + outer loop + vertex 0.831867 1.51436 2.59519 + vertex 0.829033 1.51137 2.59305 + vertex 0.831871 1.50937 2.5952 + endloop + endfacet + facet normal -0.604893 -0.00270687 0.796302 + outer loop + vertex 0.829033 1.51137 2.59305 + vertex 0.829049 1.50638 2.59304 + vertex 0.831871 1.50937 2.5952 + endloop + endfacet + facet normal -0.604047 -0.00396243 0.796939 + outer loop + vertex 0.831871 1.50937 2.5952 + vertex 0.829049 1.50638 2.59304 + vertex 0.831891 1.50438 2.59519 + endloop + endfacet + facet normal -0.594743 -0.00393908 0.803907 + outer loop + vertex 0.831891 1.50438 2.59519 + vertex 0.834717 1.50757 2.59729 + vertex 0.831871 1.50937 2.5952 + endloop + endfacet + facet normal -0.594027 -0.00491989 0.80443 + outer loop + vertex 0.834739 1.50257 2.59728 + vertex 0.834717 1.50757 2.59729 + vertex 0.831891 1.50438 2.59519 + endloop + endfacet + facet normal -0.595044 -0.00741762 0.803659 + outer loop + vertex 0.831926 1.49939 2.59517 + vertex 0.834739 1.50257 2.59728 + vertex 0.831891 1.50438 2.59519 + endloop + endfacet + facet normal -0.604305 -0.00745413 0.796718 + outer loop + vertex 0.831891 1.50438 2.59519 + vertex 0.82908 1.50139 2.59303 + vertex 0.831926 1.49939 2.59517 + endloop + endfacet + facet normal -0.605007 -0.00904129 0.796169 + outer loop + vertex 0.82908 1.50139 2.59303 + vertex 0.829123 1.49639 2.593 + vertex 0.831926 1.49939 2.59517 + endloop + endfacet + facet normal -0.604357 -0.00999776 0.796651 + outer loop + vertex 0.831926 1.49939 2.59517 + vertex 0.829123 1.49639 2.593 + vertex 0.831968 1.49439 2.59513 + endloop + endfacet + facet normal -0.594837 -0.00996139 0.803784 + outer loop + vertex 0.831968 1.49439 2.59513 + vertex 0.834775 1.49758 2.59725 + vertex 0.831926 1.49939 2.59517 + endloop + endfacet + facet normal -0.59417 -0.0108676 0.804266 + outer loop + vertex 0.834814 1.49258 2.59721 + vertex 0.834775 1.49758 2.59725 + vertex 0.831968 1.49439 2.59513 + endloop + endfacet + facet normal -0.594525 -0.0117425 0.803992 + outer loop + vertex 0.832004 1.48939 2.59509 + vertex 0.834814 1.49258 2.59721 + vertex 0.831968 1.49439 2.59513 + endloop + endfacet + facet normal -0.603863 -0.0117464 0.797002 + outer loop + vertex 0.831968 1.49439 2.59513 + vertex 0.829167 1.49139 2.59297 + vertex 0.832004 1.48939 2.59509 + endloop + endfacet + facet normal -0.604189 -0.0124836 0.796743 + outer loop + vertex 0.829167 1.49139 2.59297 + vertex 0.829204 1.48639 2.59292 + vertex 0.832004 1.48939 2.59509 + endloop + endfacet + facet normal -0.603117 -0.0140528 0.797529 + outer loop + vertex 0.832004 1.48939 2.59509 + vertex 0.829204 1.48639 2.59292 + vertex 0.832029 1.48441 2.59502 + endloop + endfacet + facet normal -0.594199 -0.0141021 0.804195 + outer loop + vertex 0.832029 1.48441 2.59502 + vertex 0.834841 1.48759 2.59715 + vertex 0.832004 1.48939 2.59509 + endloop + endfacet + facet normal -0.593251 -0.0153931 0.80487 + outer loop + vertex 0.83486 1.48261 2.59707 + vertex 0.834841 1.48759 2.59715 + vertex 0.832029 1.48441 2.59502 + endloop + endfacet + facet normal -0.594002 -0.0172498 0.804279 + outer loop + vertex 0.832067 1.47947 2.59494 + vertex 0.83486 1.48261 2.59707 + vertex 0.832029 1.48441 2.59502 + endloop + endfacet + facet normal -0.603073 -0.017215 0.7975 + outer loop + vertex 0.832029 1.48441 2.59502 + vertex 0.829242 1.48143 2.59285 + vertex 0.832067 1.47947 2.59494 + endloop + endfacet + facet normal -0.604184 -0.0197754 0.7966 + outer loop + vertex 0.829242 1.48143 2.59285 + vertex 0.829325 1.47652 2.59279 + vertex 0.832067 1.47947 2.59494 + endloop + endfacet + facet normal -0.603854 -0.0202547 0.796837 + outer loop + vertex 0.832067 1.47947 2.59494 + vertex 0.829325 1.47652 2.59279 + vertex 0.832194 1.47456 2.59491 + endloop + endfacet + facet normal -0.594124 -0.0200476 0.804124 + outer loop + vertex 0.832194 1.47456 2.59491 + vertex 0.834917 1.47765 2.597 + vertex 0.832067 1.47947 2.59494 + endloop + endfacet + facet normal -0.59383 -0.0204461 0.80433 + outer loop + vertex 0.835113 1.47267 2.59702 + vertex 0.834917 1.47765 2.597 + vertex 0.832194 1.47456 2.59491 + endloop + endfacet + facet normal -0.594248 -0.021463 0.803996 + outer loop + vertex 0.832483 1.46966 2.595 + vertex 0.835113 1.47267 2.59702 + vertex 0.832194 1.47456 2.59491 + endloop + endfacet + facet normal -0.604955 -0.0222313 0.795949 + outer loop + vertex 0.832194 1.47456 2.59491 + vertex 0.829517 1.47155 2.59279 + vertex 0.832483 1.46966 2.595 + endloop + endfacet + facet normal -0.605795 -0.0243658 0.795247 + outer loop + vertex 0.829517 1.47155 2.59279 + vertex 0.829892 1.46611 2.59291 + vertex 0.832483 1.46966 2.595 + endloop + endfacet + facet normal -0.606753 -0.0232562 0.79455 + outer loop + vertex 0.832858 1.46559 2.59516 + vertex 0.832483 1.46966 2.595 + vertex 0.829892 1.46611 2.59291 + endloop + endfacet + facet normal -0.606972 -0.0255327 0.794313 + outer loop + vertex 0.832858 1.46559 2.59516 + vertex 0.829892 1.46611 2.59291 + vertex 0.831881 1.46137 2.59428 + endloop + endfacet + facet normal -0.598852 -0.0286694 0.800346 + outer loop + vertex 0.831881 1.46137 2.59428 + vertex 0.834574 1.46319 2.59636 + vertex 0.832858 1.46559 2.59516 + endloop + endfacet + facet normal -0.593046 -0.0222738 0.80486 + outer loop + vertex 0.834574 1.46319 2.59636 + vertex 0.835574 1.46734 2.59721 + vertex 0.832858 1.46559 2.59516 + endloop + endfacet + facet normal -0.58574 -0.0251162 0.81011 + outer loop + vertex 0.834574 1.46319 2.59636 + vertex 0.837682 1.46234 2.59858 + vertex 0.835574 1.46734 2.59721 + endloop + endfacet + facet normal -0.584281 -0.0242049 0.81119 + outer loop + vertex 0.837682 1.46234 2.59858 + vertex 0.838604 1.46672 2.59938 + vertex 0.835574 1.46734 2.59721 + endloop + endfacet + facet normal -0.584033 -0.0221645 0.811428 + outer loop + vertex 0.838604 1.46672 2.59938 + vertex 0.838082 1.47086 2.59911 + vertex 0.835574 1.46734 2.59721 + endloop + endfacet + facet normal -0.584856 -0.0212704 0.810858 + outer loop + vertex 0.835574 1.46734 2.59721 + vertex 0.838082 1.47086 2.59911 + vertex 0.835113 1.47267 2.59702 + endloop + endfacet + facet normal -0.584682 -0.020825 0.810995 + outer loop + vertex 0.838082 1.47086 2.59911 + vertex 0.837834 1.47575 2.59906 + vertex 0.835113 1.47267 2.59702 + endloop + endfacet + facet normal -0.575795 -0.0203066 0.817342 + outer loop + vertex 0.837834 1.47575 2.59906 + vertex 0.838082 1.47086 2.59911 + vertex 0.840804 1.47367 2.6011 + endloop + endfacet + facet normal -0.575367 -0.0193777 0.817666 + outer loop + vertex 0.84071 1.47866 2.60115 + vertex 0.837834 1.47575 2.59906 + vertex 0.840804 1.47367 2.6011 + endloop + endfacet + facet normal -0.561958 -0.0192199 0.826942 + outer loop + vertex 0.840804 1.47367 2.6011 + vertex 0.843739 1.47646 2.60316 + vertex 0.84071 1.47866 2.60115 + endloop + endfacet + facet normal -0.560915 -0.0170949 0.827697 + outer loop + vertex 0.843739 1.47646 2.60316 + vertex 0.843696 1.4815 2.60324 + vertex 0.84071 1.47866 2.60115 + endloop + endfacet + facet normal -0.561085 -0.0168354 0.827587 + outer loop + vertex 0.84071 1.47866 2.60115 + vertex 0.843696 1.4815 2.60324 + vertex 0.840669 1.48369 2.60123 + endloop + endfacet + facet normal -0.574845 -0.0168046 0.81809 + outer loop + vertex 0.840669 1.48369 2.60123 + vertex 0.837746 1.48074 2.59911 + vertex 0.84071 1.47866 2.60115 + endloop + endfacet + facet normal -0.575179 -0.016311 0.817865 + outer loop + vertex 0.837719 1.48574 2.59919 + vertex 0.837746 1.48074 2.59911 + vertex 0.840669 1.48369 2.60123 + endloop + endfacet + facet normal -0.574018 -0.0137878 0.818727 + outer loop + vertex 0.840638 1.4887 2.60129 + vertex 0.837719 1.48574 2.59919 + vertex 0.840669 1.48369 2.60123 + endloop + endfacet + facet normal -0.559022 -0.0138226 0.829038 + outer loop + vertex 0.840669 1.48369 2.60123 + vertex 0.843658 1.48652 2.60329 + vertex 0.840638 1.4887 2.60129 + endloop + endfacet + facet normal -0.557295 -0.0103198 0.830251 + outer loop + vertex 0.843658 1.48652 2.60329 + vertex 0.843616 1.49152 2.60332 + vertex 0.840638 1.4887 2.60129 + endloop + endfacet + facet normal -0.557105 -0.0106101 0.830375 + outer loop + vertex 0.840638 1.4887 2.60129 + vertex 0.843616 1.49152 2.60332 + vertex 0.840602 1.4937 2.60133 + endloop + endfacet + facet normal -0.572861 -0.0106387 0.819583 + outer loop + vertex 0.840602 1.4937 2.60133 + vertex 0.837694 1.49074 2.59926 + vertex 0.840638 1.4887 2.60129 + endloop + endfacet + facet normal -0.572474 -0.0112045 0.819847 + outer loop + vertex 0.837659 1.49574 2.5993 + vertex 0.837694 1.49074 2.59926 + vertex 0.840602 1.4937 2.60133 + endloop + endfacet + facet normal -0.571237 -0.00853126 0.820741 + outer loop + vertex 0.840566 1.49869 2.60136 + vertex 0.837659 1.49574 2.5993 + vertex 0.840602 1.4937 2.60133 + endloop + endfacet + facet normal -0.554907 -0.00847412 0.831869 + outer loop + vertex 0.840602 1.4937 2.60133 + vertex 0.84358 1.49651 2.60335 + vertex 0.840566 1.49869 2.60136 + endloop + endfacet + facet normal -0.553628 -0.00590906 0.832743 + outer loop + vertex 0.84358 1.49651 2.60335 + vertex 0.843553 1.5015 2.60336 + vertex 0.840566 1.49869 2.60136 + endloop + endfacet + facet normal -0.553492 -0.00611821 0.832832 + outer loop + vertex 0.840566 1.49869 2.60136 + vertex 0.843553 1.5015 2.60336 + vertex 0.84054 1.50368 2.60138 + endloop + endfacet + facet normal -0.569779 -0.00615892 0.821775 + outer loop + vertex 0.84054 1.50368 2.60138 + vertex 0.837623 1.50073 2.59933 + vertex 0.840566 1.49869 2.60136 + endloop + endfacet + facet normal -0.570027 -0.00579718 0.821606 + outer loop + vertex 0.8376 1.50572 2.59935 + vertex 0.837623 1.50073 2.59933 + vertex 0.84054 1.50368 2.60138 + endloop + endfacet + facet normal -0.568784 -0.00313726 0.822481 + outer loop + vertex 0.840529 1.50867 2.60139 + vertex 0.8376 1.50572 2.59935 + vertex 0.84054 1.50368 2.60138 + endloop + endfacet + facet normal -0.552532 -0.00312509 0.833486 + outer loop + vertex 0.84054 1.50368 2.60138 + vertex 0.843539 1.50649 2.60338 + vertex 0.840529 1.50867 2.60139 + endloop + endfacet + facet normal -0.551443 -0.000961133 0.834212 + outer loop + vertex 0.843539 1.50649 2.60338 + vertex 0.843537 1.51148 2.60338 + vertex 0.840529 1.50867 2.60139 + endloop + endfacet + facet normal -0.552277 0.00032389 0.83366 + outer loop + vertex 0.840529 1.50867 2.60139 + vertex 0.843537 1.51148 2.60338 + vertex 0.840531 1.51366 2.60139 + endloop + endfacet + facet normal -0.568294 0.000328267 0.822825 + outer loop + vertex 0.840531 1.51366 2.60139 + vertex 0.83759 1.51071 2.59936 + vertex 0.840529 1.50867 2.60139 + endloop + endfacet + facet normal -0.569332 0.00185876 0.822105 + outer loop + vertex 0.837596 1.5157 2.59935 + vertex 0.83759 1.51071 2.59936 + vertex 0.840531 1.51366 2.60139 + endloop + endfacet + facet normal -0.568843 0.00289801 0.822441 + outer loop + vertex 0.840541 1.51866 2.60138 + vertex 0.837596 1.5157 2.59935 + vertex 0.840531 1.51366 2.60139 + endloop + endfacet + facet normal -0.55306 0.00288643 0.833137 + outer loop + vertex 0.840531 1.51366 2.60139 + vertex 0.843543 1.51647 2.60338 + vertex 0.840541 1.51866 2.60138 + endloop + endfacet + facet normal -0.553228 0.00255452 0.833026 + outer loop + vertex 0.843543 1.51647 2.60338 + vertex 0.843554 1.52146 2.60337 + vertex 0.840541 1.51866 2.60138 + endloop + endfacet + facet normal -0.554434 0.00442359 0.832216 + outer loop + vertex 0.840541 1.51866 2.60138 + vertex 0.843554 1.52146 2.60337 + vertex 0.840556 1.52365 2.60136 + endloop + endfacet + facet normal -0.569477 0.00443397 0.821995 + outer loop + vertex 0.840556 1.52365 2.60136 + vertex 0.837609 1.5207 2.59933 + vertex 0.840541 1.51866 2.60138 + endloop + endfacet + facet normal -0.570498 0.0059475 0.821277 + outer loop + vertex 0.837626 1.52569 2.59931 + vertex 0.837609 1.5207 2.59933 + vertex 0.840556 1.52365 2.60136 + endloop + endfacet + facet normal -0.570432 0.00608689 0.821322 + outer loop + vertex 0.840575 1.52864 2.60134 + vertex 0.837626 1.52569 2.59931 + vertex 0.840556 1.52365 2.60136 + endloop + endfacet + facet normal -0.556368 0.00608076 0.830913 + outer loop + vertex 0.840556 1.52365 2.60136 + vertex 0.843567 1.52646 2.60336 + vertex 0.840575 1.52864 2.60134 + endloop + endfacet + facet normal -0.556727 0.00537145 0.830678 + outer loop + vertex 0.843567 1.52646 2.60336 + vertex 0.843585 1.53145 2.60334 + vertex 0.840575 1.52864 2.60134 + endloop + endfacet + facet normal -0.558738 0.00850635 0.8293 + outer loop + vertex 0.840575 1.52864 2.60134 + vertex 0.843585 1.53145 2.60334 + vertex 0.840602 1.53363 2.6013 + endloop + endfacet + facet normal -0.570955 0.00851901 0.820937 + outer loop + vertex 0.840602 1.53363 2.6013 + vertex 0.837648 1.53068 2.59928 + vertex 0.840575 1.52864 2.60134 + endloop + endfacet + facet normal -0.572273 0.0104844 0.819996 + outer loop + vertex 0.83768 1.53568 2.59924 + vertex 0.837648 1.53068 2.59928 + vertex 0.840602 1.53363 2.6013 + endloop + endfacet + facet normal -0.571608 0.0118851 0.820441 + outer loop + vertex 0.840645 1.53862 2.60126 + vertex 0.83768 1.53568 2.59924 + vertex 0.840602 1.53363 2.6013 + endloop + endfacet + facet normal -0.560277 0.011854 0.828221 + outer loop + vertex 0.840602 1.53363 2.6013 + vertex 0.843617 1.53644 2.6033 + vertex 0.840645 1.53862 2.60126 + endloop + endfacet + facet normal -0.559804 0.012783 0.828526 + outer loop + vertex 0.843617 1.53644 2.6033 + vertex 0.843668 1.54143 2.60326 + vertex 0.840645 1.53862 2.60126 + endloop + endfacet + facet normal -0.561139 0.0148893 0.827588 + outer loop + vertex 0.840645 1.53862 2.60126 + vertex 0.843668 1.54143 2.60326 + vertex 0.840701 1.54361 2.60121 + endloop + endfacet + facet normal -0.571982 0.0149337 0.82013 + outer loop + vertex 0.840701 1.54361 2.60121 + vertex 0.837723 1.54067 2.59919 + vertex 0.840645 1.53862 2.60126 + endloop + endfacet + facet normal -0.57249 0.0157008 0.819762 + outer loop + vertex 0.837772 1.54565 2.59912 + vertex 0.837723 1.54067 2.59919 + vertex 0.840701 1.54361 2.60121 + endloop + endfacet + facet normal -0.572178 0.016355 0.819966 + outer loop + vertex 0.840755 1.54859 2.60115 + vertex 0.837772 1.54565 2.59912 + vertex 0.840701 1.54361 2.60121 + endloop + endfacet + facet normal -0.56121 0.01633 0.827512 + outer loop + vertex 0.840701 1.54361 2.60121 + vertex 0.843728 1.54641 2.60321 + vertex 0.840755 1.54859 2.60115 + endloop + endfacet + facet normal -0.560738 0.0172597 0.827813 + outer loop + vertex 0.843728 1.54641 2.60321 + vertex 0.843789 1.55139 2.60314 + vertex 0.840755 1.54859 2.60115 + endloop + endfacet + facet normal -0.561101 0.0178358 0.827555 + outer loop + vertex 0.840755 1.54859 2.60115 + vertex 0.843789 1.55139 2.60314 + vertex 0.840786 1.55358 2.60106 + endloop + endfacet + facet normal -0.571647 0.0177769 0.820307 + outer loop + vertex 0.840786 1.55358 2.60106 + vertex 0.837804 1.55064 2.59905 + vertex 0.840755 1.54859 2.60115 + endloop + endfacet + facet normal -0.571856 0.0180947 0.820154 + outer loop + vertex 0.837756 1.55562 2.5989 + vertex 0.837804 1.55064 2.59905 + vertex 0.840786 1.55358 2.60106 + endloop + endfacet + facet normal -0.571129 0.019673 0.820625 + outer loop + vertex 0.840792 1.55869 2.60094 + vertex 0.837756 1.55562 2.5989 + vertex 0.840786 1.55358 2.60106 + endloop + endfacet + facet normal -0.561279 0.0198182 0.827389 + outer loop + vertex 0.840786 1.55358 2.60106 + vertex 0.843865 1.55641 2.60308 + vertex 0.840792 1.55869 2.60094 + endloop + endfacet + facet normal -0.560315 0.0216888 0.827995 + outer loop + vertex 0.843865 1.55641 2.60308 + vertex 0.844063 1.56155 2.60308 + vertex 0.840792 1.55869 2.60094 + endloop + endfacet + facet normal -0.560925 0.0227126 0.827555 + outer loop + vertex 0.840792 1.55869 2.60094 + vertex 0.844063 1.56155 2.60308 + vertex 0.840983 1.56398 2.60093 + endloop + endfacet + facet normal -0.571391 0.0230682 0.820353 + outer loop + vertex 0.840983 1.56398 2.60093 + vertex 0.837373 1.56094 2.5985 + vertex 0.840792 1.55869 2.60094 + endloop + endfacet + facet normal -0.559533 0.0252457 0.828424 + outer loop + vertex 0.844063 1.56155 2.60308 + vertex 0.844652 1.56717 2.60331 + vertex 0.840983 1.56398 2.60093 + endloop + endfacet + facet normal -0.559584 0.0253329 0.828386 + outer loop + vertex 0.840983 1.56398 2.60093 + vertex 0.844652 1.56717 2.60331 + vertex 0.84119 1.56925 2.60091 + endloop + endfacet + facet normal -0.570613 0.0257338 0.820816 + outer loop + vertex 0.84119 1.56925 2.60091 + vertex 0.837943 1.56641 2.59874 + vertex 0.840983 1.56398 2.60093 + endloop + endfacet + facet normal -0.571645 0.0275016 0.82004 + outer loop + vertex 0.838168 1.57143 2.59873 + vertex 0.837943 1.56641 2.59874 + vertex 0.84119 1.56925 2.60091 + endloop + endfacet + facet normal -0.571167 0.0284652 0.82034 + outer loop + vertex 0.841239 1.57432 2.60076 + vertex 0.838168 1.57143 2.59873 + vertex 0.84119 1.56925 2.60091 + endloop + endfacet + facet normal -0.560692 0.0285632 0.827532 + outer loop + vertex 0.84119 1.56925 2.60091 + vertex 0.844287 1.57246 2.60289 + vertex 0.841239 1.57432 2.60076 + endloop + endfacet + facet normal -0.560161 0.0297987 0.827847 + outer loop + vertex 0.844287 1.57246 2.60289 + vertex 0.844281 1.5774 2.60271 + vertex 0.841239 1.57432 2.60076 + endloop + endfacet + facet normal -0.560984 0.0309912 0.827246 + outer loop + vertex 0.841239 1.57432 2.60076 + vertex 0.844281 1.5774 2.60271 + vertex 0.841325 1.57928 2.60064 + endloop + endfacet + facet normal -0.572209 0.0309854 0.819523 + outer loop + vertex 0.841325 1.57928 2.60064 + vertex 0.838293 1.57639 2.59863 + vertex 0.841239 1.57432 2.60076 + endloop + endfacet + facet normal -0.573834 0.0335527 0.818284 + outer loop + vertex 0.8384 1.58136 2.5985 + vertex 0.838293 1.57639 2.59863 + vertex 0.841325 1.57928 2.60064 + endloop + endfacet + facet normal -0.574135 0.0329393 0.818098 + outer loop + vertex 0.841431 1.58424 2.60051 + vertex 0.8384 1.58136 2.5985 + vertex 0.841325 1.57928 2.60064 + endloop + endfacet + facet normal -0.561943 0.0328887 0.826522 + outer loop + vertex 0.841325 1.57928 2.60064 + vertex 0.844364 1.58235 2.60258 + vertex 0.841431 1.58424 2.60051 + endloop + endfacet + facet normal -0.561815 0.0331712 0.826598 + outer loop + vertex 0.844364 1.58235 2.60258 + vertex 0.844469 1.58734 2.60245 + vertex 0.841431 1.58424 2.60051 + endloop + endfacet + facet normal -0.563594 0.0357415 0.825278 + outer loop + vertex 0.841431 1.58424 2.60051 + vertex 0.844469 1.58734 2.60245 + vertex 0.841547 1.5892 2.60038 + endloop + endfacet + facet normal -0.57634 0.0357953 0.816426 + outer loop + vertex 0.841547 1.5892 2.60038 + vertex 0.838515 1.58634 2.59836 + vertex 0.841431 1.58424 2.60051 + endloop + endfacet + facet normal -0.578331 0.0390092 0.814869 + outer loop + vertex 0.838661 1.5913 2.59823 + vertex 0.838515 1.58634 2.59836 + vertex 0.841547 1.5892 2.60038 + endloop + endfacet + facet normal -0.57781 0.040049 0.815188 + outer loop + vertex 0.841684 1.59415 2.60023 + vertex 0.838661 1.5913 2.59823 + vertex 0.841547 1.5892 2.60038 + endloop + endfacet + facet normal -0.565379 0.0399588 0.823863 + outer loop + vertex 0.841547 1.5892 2.60038 + vertex 0.844584 1.59233 2.60231 + vertex 0.841684 1.59415 2.60023 + endloop + endfacet + facet normal -0.564589 0.0417408 0.824316 + outer loop + vertex 0.844584 1.59233 2.60231 + vertex 0.844724 1.59729 2.60215 + vertex 0.841684 1.59415 2.60023 + endloop + endfacet + facet normal -0.565782 0.0434488 0.823409 + outer loop + vertex 0.841684 1.59415 2.60023 + vertex 0.844724 1.59729 2.60215 + vertex 0.841877 1.59907 2.6001 + endloop + endfacet + facet normal -0.578735 0.0437194 0.814343 + outer loop + vertex 0.841877 1.59907 2.6001 + vertex 0.838847 1.59625 2.5981 + vertex 0.841684 1.59415 2.60023 + endloop + endfacet + facet normal -0.58009 0.0459497 0.813255 + outer loop + vertex 0.839135 1.60132 2.59802 + vertex 0.838847 1.59625 2.5981 + vertex 0.841877 1.59907 2.6001 + endloop + endfacet + facet normal -0.57989 0.0463072 0.813377 + outer loop + vertex 0.842188 1.60387 2.60005 + vertex 0.839135 1.60132 2.59802 + vertex 0.841877 1.59907 2.6001 + endloop + endfacet + facet normal -0.565146 0.0454599 0.823738 + outer loop + vertex 0.841877 1.59907 2.6001 + vertex 0.84488 1.60213 2.60199 + vertex 0.842188 1.60387 2.60005 + endloop + endfacet + facet normal -0.564941 0.0459071 0.823853 + outer loop + vertex 0.84488 1.60213 2.60199 + vertex 0.844945 1.60661 2.60179 + vertex 0.842188 1.60387 2.60005 + endloop + endfacet + facet normal -0.547499 0.0461889 0.835531 + outer loop + vertex 0.84488 1.60213 2.60199 + vertex 0.847875 1.60555 2.60377 + vertex 0.844945 1.60661 2.60179 + endloop + endfacet + facet normal -0.546729 0.0489508 0.835877 + outer loop + vertex 0.844945 1.60661 2.60179 + vertex 0.847875 1.60555 2.60377 + vertex 0.847578 1.61075 2.60327 + endloop + endfacet + facet normal -0.546653 0.0488825 0.835931 + outer loop + vertex 0.844508 1.60991 2.60131 + vertex 0.844945 1.60661 2.60179 + vertex 0.847578 1.61075 2.60327 + endloop + endfacet + facet normal -0.546957 0.0507261 0.835622 + outer loop + vertex 0.844508 1.60991 2.60131 + vertex 0.847578 1.61075 2.60327 + vertex 0.845069 1.61367 2.60145 + endloop + endfacet + facet normal -0.566448 0.0541279 0.822318 + outer loop + vertex 0.845069 1.61367 2.60145 + vertex 0.842289 1.61096 2.59971 + vertex 0.844508 1.60991 2.60131 + endloop + endfacet + facet normal -0.567609 0.0507799 0.821731 + outer loop + vertex 0.842715 1.60761 2.60021 + vertex 0.844508 1.60991 2.60131 + vertex 0.842289 1.61096 2.59971 + endloop + endfacet + facet normal -0.580774 0.0477472 0.812664 + outer loop + vertex 0.842715 1.60761 2.60021 + vertex 0.842289 1.61096 2.59971 + vertex 0.839762 1.6069 2.59815 + endloop + endfacet + facet normal -0.580598 0.04644 0.812865 + outer loop + vertex 0.842715 1.60761 2.60021 + vertex 0.839762 1.6069 2.59815 + vertex 0.842188 1.60387 2.60005 + endloop + endfacet + facet normal -0.582445 0.0492836 0.811375 + outer loop + vertex 0.839762 1.6069 2.59815 + vertex 0.842289 1.61096 2.59971 + vertex 0.839461 1.61225 2.5976 + endloop + endfacet + facet normal -0.565206 0.0522245 0.823295 + outer loop + vertex 0.842364 1.61553 2.59947 + vertex 0.842289 1.61096 2.59971 + vertex 0.845069 1.61367 2.60145 + endloop + endfacet + facet normal -0.563696 0.0552991 0.824129 + outer loop + vertex 0.845454 1.61853 2.60139 + vertex 0.842364 1.61553 2.59947 + vertex 0.845069 1.61367 2.60145 + endloop + endfacet + facet normal -0.546018 0.0540501 0.836028 + outer loop + vertex 0.845069 1.61367 2.60145 + vertex 0.848294 1.61628 2.60339 + vertex 0.845454 1.61853 2.60139 + endloop + endfacet + facet normal -0.545296 0.0527509 0.836582 + outer loop + vertex 0.847578 1.61075 2.60327 + vertex 0.848294 1.61628 2.60339 + vertex 0.845069 1.61367 2.60145 + endloop + endfacet + facet normal -0.548114 0.0469614 0.835084 + outer loop + vertex 0.847819 1.60065 2.60401 + vertex 0.847875 1.60555 2.60377 + vertex 0.84488 1.60213 2.60199 + endloop + endfacet + facet normal -0.548823 0.045068 0.834723 + outer loop + vertex 0.844724 1.59729 2.60215 + vertex 0.847819 1.60065 2.60401 + vertex 0.84488 1.60213 2.60199 + endloop + endfacet + facet normal -0.547909 0.0438587 0.835388 + outer loop + vertex 0.847698 1.59568 2.60419 + vertex 0.847819 1.60065 2.60401 + vertex 0.844724 1.59729 2.60215 + endloop + endfacet + facet normal -0.564989 0.0452319 0.823858 + outer loop + vertex 0.844724 1.59729 2.60215 + vertex 0.84488 1.60213 2.60199 + vertex 0.841877 1.59907 2.6001 + endloop + endfacet + facet normal -0.548795 0.0416286 0.83492 + outer loop + vertex 0.844584 1.59233 2.60231 + vertex 0.847698 1.59568 2.60419 + vertex 0.844724 1.59729 2.60215 + endloop + endfacet + facet normal -0.546854 0.0390401 0.836317 + outer loop + vertex 0.84758 1.59062 2.60435 + vertex 0.847698 1.59568 2.60419 + vertex 0.844584 1.59233 2.60231 + endloop + endfacet + facet normal -0.547833 0.036696 0.835783 + outer loop + vertex 0.844469 1.58734 2.60245 + vertex 0.84758 1.59062 2.60435 + vertex 0.844584 1.59233 2.60231 + endloop + endfacet + facet normal -0.546685 0.0351338 0.836601 + outer loop + vertex 0.847452 1.58553 2.60448 + vertex 0.84758 1.59062 2.60435 + vertex 0.844469 1.58734 2.60245 + endloop + endfacet + facet normal -0.563139 0.0367543 0.825544 + outer loop + vertex 0.844469 1.58734 2.60245 + vertex 0.844584 1.59233 2.60231 + vertex 0.841547 1.5892 2.60038 + endloop + endfacet + facet normal -0.547571 0.0331163 0.836104 + outer loop + vertex 0.844364 1.58235 2.60258 + vertex 0.847452 1.58553 2.60448 + vertex 0.844469 1.58734 2.60245 + endloop + endfacet + facet normal -0.546833 0.0320872 0.836627 + outer loop + vertex 0.847332 1.58052 2.60459 + vertex 0.847452 1.58553 2.60448 + vertex 0.844364 1.58235 2.60258 + endloop + endfacet + facet normal -0.547181 0.0313063 0.836429 + outer loop + vertex 0.844281 1.5774 2.60271 + vertex 0.847332 1.58052 2.60459 + vertex 0.844364 1.58235 2.60258 + endloop + endfacet + facet normal -0.546574 0.0304559 0.836857 + outer loop + vertex 0.847237 1.57567 2.60471 + vertex 0.847332 1.58052 2.60459 + vertex 0.844281 1.5774 2.60271 + endloop + endfacet + facet normal -0.529809 0.0303821 0.847573 + outer loop + vertex 0.847332 1.58052 2.60459 + vertex 0.847237 1.57567 2.60471 + vertex 0.850302 1.57858 2.60652 + endloop + endfacet + facet normal -0.529593 0.0308297 0.847692 + outer loop + vertex 0.850481 1.58356 2.60645 + vertex 0.847332 1.58052 2.60459 + vertex 0.850302 1.57858 2.60652 + endloop + endfacet + facet normal -0.514044 0.0304032 0.857225 + outer loop + vertex 0.850302 1.57858 2.60652 + vertex 0.853518 1.58142 2.60834 + vertex 0.850481 1.58356 2.60645 + endloop + endfacet + facet normal -0.51365 0.0311465 0.857434 + outer loop + vertex 0.853518 1.58142 2.60834 + vertex 0.853781 1.58654 2.60832 + vertex 0.850481 1.58356 2.60645 + endloop + endfacet + facet normal -0.515129 0.0333956 0.856462 + outer loop + vertex 0.850481 1.58356 2.60645 + vertex 0.853781 1.58654 2.60832 + vertex 0.850706 1.58876 2.60638 + endloop + endfacet + facet normal -0.529409 0.0339003 0.847689 + outer loop + vertex 0.850706 1.58876 2.60638 + vertex 0.847452 1.58553 2.60448 + vertex 0.850481 1.58356 2.60645 + endloop + endfacet + facet normal -0.53018 0.0349878 0.847163 + outer loop + vertex 0.84758 1.59062 2.60435 + vertex 0.847452 1.58553 2.60448 + vertex 0.850706 1.58876 2.60638 + endloop + endfacet + facet normal -0.529216 0.0371653 0.847673 + outer loop + vertex 0.850839 1.59401 2.60623 + vertex 0.84758 1.59062 2.60435 + vertex 0.850706 1.58876 2.60638 + endloop + endfacet + facet normal -0.51453 0.0370435 0.856672 + outer loop + vertex 0.850706 1.58876 2.60638 + vertex 0.854403 1.59217 2.60845 + vertex 0.850839 1.59401 2.60623 + endloop + endfacet + facet normal -0.514052 0.0382548 0.856906 + outer loop + vertex 0.854403 1.59217 2.60845 + vertex 0.854056 1.59751 2.60801 + vertex 0.850839 1.59401 2.60623 + endloop + endfacet + facet normal -0.516576 0.0414165 0.855239 + outer loop + vertex 0.850839 1.59401 2.60623 + vertex 0.854056 1.59751 2.60801 + vertex 0.850888 1.59911 2.60602 + endloop + endfacet + facet normal -0.529691 0.0412003 0.84719 + outer loop + vertex 0.850888 1.59911 2.60602 + vertex 0.847698 1.59568 2.60419 + vertex 0.850839 1.59401 2.60623 + endloop + endfacet + facet normal -0.531724 0.0438454 0.845782 + outer loop + vertex 0.847819 1.60065 2.60401 + vertex 0.847698 1.59568 2.60419 + vertex 0.850888 1.59911 2.60602 + endloop + endfacet + facet normal -0.531001 0.045746 0.846136 + outer loop + vertex 0.850994 1.60407 2.60581 + vertex 0.847819 1.60065 2.60401 + vertex 0.850888 1.59911 2.60602 + endloop + endfacet + facet normal -0.517424 0.0457989 0.854503 + outer loop + vertex 0.850888 1.59911 2.60602 + vertex 0.854111 1.60248 2.60779 + vertex 0.850994 1.60407 2.60581 + endloop + endfacet + facet normal -0.516981 0.0469182 0.85471 + outer loop + vertex 0.854111 1.60248 2.60779 + vertex 0.854252 1.60743 2.6076 + vertex 0.850994 1.60407 2.60581 + endloop + endfacet + facet normal -0.518841 0.049401 0.853442 + outer loop + vertex 0.850994 1.60407 2.60581 + vertex 0.854252 1.60743 2.6076 + vertex 0.851072 1.60906 2.60557 + endloop + endfacet + facet normal -0.531477 0.0492218 0.845641 + outer loop + vertex 0.851072 1.60906 2.60557 + vertex 0.847875 1.60555 2.60377 + vertex 0.850994 1.60407 2.60581 + endloop + endfacet + facet normal -0.532578 0.0506214 0.844866 + outer loop + vertex 0.847578 1.61075 2.60327 + vertex 0.847875 1.60555 2.60377 + vertex 0.851072 1.60906 2.60557 + endloop + endfacet + facet normal -0.532117 0.0518731 0.84508 + outer loop + vertex 0.851279 1.61416 2.60539 + vertex 0.847578 1.61075 2.60327 + vertex 0.851072 1.60906 2.60557 + endloop + endfacet + facet normal -0.519462 0.0516409 0.852932 + outer loop + vertex 0.851072 1.60906 2.60557 + vertex 0.854419 1.6124 2.60741 + vertex 0.851279 1.61416 2.60539 + endloop + endfacet + facet normal -0.518573 0.0536973 0.853345 + outer loop + vertex 0.854419 1.6124 2.60741 + vertex 0.854632 1.61736 2.60723 + vertex 0.851279 1.61416 2.60539 + endloop + endfacet + facet normal -0.510947 0.0535379 0.857944 + outer loop + vertex 0.854419 1.6124 2.60741 + vertex 0.857707 1.61569 2.60916 + vertex 0.854632 1.61736 2.60723 + endloop + endfacet + facet normal -0.509125 0.0510646 0.859177 + outer loop + vertex 0.857545 1.61071 2.60936 + vertex 0.857707 1.61569 2.60916 + vertex 0.854419 1.6124 2.60741 + endloop + endfacet + facet normal -0.50949 0.0501971 0.859011 + outer loop + vertex 0.854252 1.60743 2.6076 + vertex 0.857545 1.61071 2.60936 + vertex 0.854419 1.6124 2.60741 + endloop + endfacet + facet normal -0.531394 0.0507646 0.845603 + outer loop + vertex 0.848294 1.61628 2.60339 + vertex 0.847578 1.61075 2.60327 + vertex 0.851279 1.61416 2.60539 + endloop + endfacet + facet normal -0.518487 0.0502913 0.853605 + outer loop + vertex 0.854252 1.60743 2.6076 + vertex 0.854419 1.6124 2.60741 + vertex 0.851072 1.60906 2.60557 + endloop + endfacet + facet normal -0.507567 0.0468631 0.860337 + outer loop + vertex 0.854111 1.60248 2.60779 + vertex 0.857382 1.60571 2.60954 + vertex 0.854252 1.60743 2.6076 + endloop + endfacet + facet normal -0.505813 0.044463 0.861496 + outer loop + vertex 0.857194 1.60081 2.60968 + vertex 0.857382 1.60571 2.60954 + vertex 0.854111 1.60248 2.60779 + endloop + endfacet + facet normal -0.506121 0.0437316 0.861353 + outer loop + vertex 0.854056 1.59751 2.60801 + vertex 0.857194 1.60081 2.60968 + vertex 0.854111 1.60248 2.60779 + endloop + endfacet + facet normal -0.53218 0.0472753 0.84531 + outer loop + vertex 0.847875 1.60555 2.60377 + vertex 0.847819 1.60065 2.60401 + vertex 0.850994 1.60407 2.60581 + endloop + endfacet + facet normal -0.515734 0.0435853 0.85564 + outer loop + vertex 0.854056 1.59751 2.60801 + vertex 0.854111 1.60248 2.60779 + vertex 0.850888 1.59911 2.60602 + endloop + endfacet + facet normal -0.505732 0.0392051 0.861799 + outer loop + vertex 0.854403 1.59217 2.60845 + vertex 0.857111 1.59626 2.60986 + vertex 0.854056 1.59751 2.60801 + endloop + endfacet + facet normal -0.504243 0.0378999 0.86273 + outer loop + vertex 0.85758 1.59291 2.61028 + vertex 0.857111 1.59626 2.60986 + vertex 0.854403 1.59217 2.60845 + endloop + endfacet + facet normal -0.50372 0.0345363 0.863176 + outer loop + vertex 0.85758 1.59291 2.61028 + vertex 0.854403 1.59217 2.60845 + vertex 0.857054 1.58914 2.61012 + endloop + endfacet + facet normal -0.493414 0.0328471 0.869174 + outer loop + vertex 0.857054 1.58914 2.61012 + vertex 0.859984 1.59182 2.61168 + vertex 0.85758 1.59291 2.61028 + endloop + endfacet + facet normal -0.492614 0.0350945 0.86954 + outer loop + vertex 0.859491 1.59516 2.61127 + vertex 0.85758 1.59291 2.61028 + vertex 0.859984 1.59182 2.61168 + endloop + endfacet + facet normal -0.4925 0.0315172 0.869741 + outer loop + vertex 0.859986 1.58729 2.61185 + vertex 0.859984 1.59182 2.61168 + vertex 0.857054 1.58914 2.61012 + endloop + endfacet + facet normal -0.492947 0.030606 0.869521 + outer loop + vertex 0.856784 1.5843 2.61014 + vertex 0.859986 1.58729 2.61185 + vertex 0.857054 1.58914 2.61012 + endloop + endfacet + facet normal -0.501531 0.0310659 0.864582 + outer loop + vertex 0.857054 1.58914 2.61012 + vertex 0.853781 1.58654 2.60832 + vertex 0.856784 1.5843 2.61014 + endloop + endfacet + facet normal -0.491189 0.0281103 0.870599 + outer loop + vertex 0.859897 1.5824 2.61196 + vertex 0.859986 1.58729 2.61185 + vertex 0.856784 1.5843 2.61014 + endloop + endfacet + facet normal -0.491482 0.027491 0.870454 + outer loop + vertex 0.856609 1.57931 2.6102 + vertex 0.859897 1.5824 2.61196 + vertex 0.856784 1.5843 2.61014 + endloop + endfacet + facet normal -0.499948 0.0277313 0.865611 + outer loop + vertex 0.856784 1.5843 2.61014 + vertex 0.853518 1.58142 2.60834 + vertex 0.856609 1.57931 2.6102 + endloop + endfacet + facet normal -0.499948 0.0277323 0.865611 + outer loop + vertex 0.853518 1.58142 2.60834 + vertex 0.853265 1.57637 2.60836 + vertex 0.856609 1.57931 2.6102 + endloop + endfacet + facet normal -0.498427 0.0254053 0.866559 + outer loop + vertex 0.856609 1.57931 2.6102 + vertex 0.853265 1.57637 2.60836 + vertex 0.85641 1.57424 2.61023 + endloop + endfacet + facet normal -0.489422 0.0250853 0.871686 + outer loop + vertex 0.85641 1.57424 2.61023 + vertex 0.859795 1.57743 2.61204 + vertex 0.856609 1.57931 2.6102 + endloop + endfacet + facet normal -0.487787 0.0227903 0.872665 + outer loop + vertex 0.859701 1.57245 2.61212 + vertex 0.859795 1.57743 2.61204 + vertex 0.85641 1.57424 2.61023 + endloop + endfacet + facet normal -0.487133 0.0243304 0.872989 + outer loop + vertex 0.85632 1.56915 2.61032 + vertex 0.859701 1.57245 2.61212 + vertex 0.85641 1.57424 2.61023 + endloop + endfacet + facet normal -0.496886 0.0244025 0.867473 + outer loop + vertex 0.85641 1.57424 2.61023 + vertex 0.852681 1.57091 2.60819 + vertex 0.85632 1.56915 2.61032 + endloop + endfacet + facet normal -0.496168 0.0263177 0.867828 + outer loop + vertex 0.852681 1.57091 2.60819 + vertex 0.853085 1.56567 2.60858 + vertex 0.85632 1.56915 2.61032 + endloop + endfacet + facet normal -0.493989 0.0236245 0.869147 + outer loop + vertex 0.85632 1.56915 2.61032 + vertex 0.853085 1.56567 2.60858 + vertex 0.85633 1.56412 2.61047 + endloop + endfacet + facet normal -0.484976 0.0237848 0.874204 + outer loop + vertex 0.85633 1.56412 2.61047 + vertex 0.859631 1.56747 2.61221 + vertex 0.85632 1.56915 2.61032 + endloop + endfacet + facet normal -0.483163 0.0214484 0.875268 + outer loop + vertex 0.859561 1.5625 2.61229 + vertex 0.859631 1.56747 2.61221 + vertex 0.85633 1.56412 2.61047 + endloop + endfacet + facet normal -0.483034 0.0217771 0.875331 + outer loop + vertex 0.856273 1.55913 2.61056 + vertex 0.859561 1.5625 2.61229 + vertex 0.85633 1.56412 2.61047 + endloop + endfacet + facet normal -0.492924 0.0217879 0.8698 + outer loop + vertex 0.85633 1.56412 2.61047 + vertex 0.853106 1.56072 2.60872 + vertex 0.856273 1.55913 2.61056 + endloop + endfacet + facet normal -0.493259 0.02092 0.869631 + outer loop + vertex 0.853106 1.56072 2.60872 + vertex 0.853041 1.55573 2.60881 + vertex 0.856273 1.55913 2.61056 + endloop + endfacet + facet normal -0.49187 0.0191762 0.870457 + outer loop + vertex 0.856273 1.55913 2.61056 + vertex 0.853041 1.55573 2.60881 + vertex 0.8562 1.55414 2.61063 + endloop + endfacet + facet normal -0.481209 0.0191027 0.876398 + outer loop + vertex 0.8562 1.55414 2.61063 + vertex 0.859483 1.55752 2.61236 + vertex 0.856273 1.55913 2.61056 + endloop + endfacet + facet normal -0.479385 0.0167953 0.877444 + outer loop + vertex 0.859417 1.55253 2.61242 + vertex 0.859483 1.55752 2.61236 + vertex 0.8562 1.55414 2.61063 + endloop + endfacet + facet normal -0.479761 0.0158367 0.877256 + outer loop + vertex 0.856143 1.54914 2.61069 + vertex 0.859417 1.55253 2.61242 + vertex 0.8562 1.55414 2.61063 + endloop + endfacet + facet normal -0.490539 0.0158886 0.871275 + outer loop + vertex 0.8562 1.55414 2.61063 + vertex 0.852975 1.55073 2.60887 + vertex 0.856143 1.54914 2.61069 + endloop + endfacet + facet normal -0.491013 0.0146607 0.871029 + outer loop + vertex 0.852975 1.55073 2.60887 + vertex 0.852929 1.54573 2.60893 + vertex 0.856143 1.54914 2.61069 + endloop + endfacet + facet normal -0.489273 0.0125015 0.872041 + outer loop + vertex 0.856143 1.54914 2.61069 + vertex 0.852929 1.54573 2.60893 + vertex 0.856107 1.54414 2.61074 + endloop + endfacet + facet normal -0.47819 0.0124838 0.878168 + outer loop + vertex 0.856107 1.54414 2.61074 + vertex 0.859372 1.54753 2.61247 + vertex 0.856143 1.54914 2.61069 + endloop + endfacet + facet normal -0.47658 0.0104712 0.879069 + outer loop + vertex 0.859342 1.54254 2.61251 + vertex 0.859372 1.54753 2.61247 + vertex 0.856107 1.54414 2.61074 + endloop + endfacet + facet normal -0.477456 0.00820553 0.878617 + outer loop + vertex 0.856089 1.53915 2.61077 + vertex 0.859342 1.54254 2.61251 + vertex 0.856107 1.54414 2.61074 + endloop + endfacet + facet normal -0.487601 0.00819914 0.873028 + outer loop + vertex 0.856107 1.54414 2.61074 + vertex 0.8529 1.54073 2.60898 + vertex 0.856089 1.53915 2.61077 + endloop + endfacet + facet normal -0.488333 0.00627639 0.872635 + outer loop + vertex 0.8529 1.54073 2.60898 + vertex 0.852889 1.53574 2.60901 + vertex 0.856089 1.53915 2.61077 + endloop + endfacet + facet normal -0.486946 0.00456791 0.87342 + outer loop + vertex 0.856089 1.53915 2.61077 + vertex 0.852889 1.53574 2.60901 + vertex 0.856085 1.53416 2.6108 + endloop + endfacet + facet normal -0.477762 0.00458461 0.878477 + outer loop + vertex 0.856085 1.53416 2.6108 + vertex 0.859326 1.53755 2.61254 + vertex 0.856089 1.53915 2.61077 + endloop + endfacet + facet normal -0.477641 0.00443366 0.878544 + outer loop + vertex 0.859321 1.53256 2.61257 + vertex 0.859326 1.53755 2.61254 + vertex 0.856085 1.53416 2.6108 + endloop + endfacet + facet normal -0.478854 0.00126934 0.877894 + outer loop + vertex 0.85609 1.52917 2.61081 + vertex 0.859321 1.53256 2.61257 + vertex 0.856085 1.53416 2.6108 + endloop + endfacet + facet normal -0.487128 0.00125169 0.87333 + outer loop + vertex 0.856085 1.53416 2.6108 + vertex 0.85289 1.53075 2.60902 + vertex 0.85609 1.52917 2.61081 + endloop + endfacet + facet normal -0.487784 -0.000490562 0.872964 + outer loop + vertex 0.85289 1.53075 2.60902 + vertex 0.852897 1.52576 2.60902 + vertex 0.85609 1.52917 2.61081 + endloop + endfacet + facet normal -0.488192 1.14235e-05 0.872736 + outer loop + vertex 0.85609 1.52917 2.61081 + vertex 0.852897 1.52576 2.60902 + vertex 0.856096 1.52418 2.61081 + endloop + endfacet + facet normal -0.48038 2.25955e-05 0.87706 + outer loop + vertex 0.856096 1.52418 2.61081 + vertex 0.859321 1.52756 2.61258 + vertex 0.85609 1.52917 2.61081 + endloop + endfacet + facet normal -0.481841 0.00183249 0.876257 + outer loop + vertex 0.85932 1.52257 2.61259 + vertex 0.859321 1.52756 2.61258 + vertex 0.856096 1.52418 2.61081 + endloop + endfacet + facet normal -0.482409 0.000346495 0.875946 + outer loop + vertex 0.856097 1.51918 2.61081 + vertex 0.85932 1.52257 2.61259 + vertex 0.856096 1.52418 2.61081 + endloop + endfacet + facet normal -0.489322 0.000342064 0.872103 + outer loop + vertex 0.856096 1.52418 2.61081 + vertex 0.8529 1.52076 2.60902 + vertex 0.856097 1.51918 2.61081 + endloop + endfacet + facet normal -0.48952 -0.000184835 0.871992 + outer loop + vertex 0.8529 1.52076 2.60902 + vertex 0.8529 1.51577 2.60902 + vertex 0.856097 1.51918 2.61081 + endloop + endfacet + facet normal -0.490219 0.000677061 0.871599 + outer loop + vertex 0.856097 1.51918 2.61081 + vertex 0.8529 1.51577 2.60902 + vertex 0.856097 1.51419 2.61082 + endloop + endfacet + facet normal -0.484226 0.000678812 0.874943 + outer loop + vertex 0.856097 1.51419 2.61082 + vertex 0.859317 1.51758 2.6126 + vertex 0.856097 1.51918 2.61081 + endloop + endfacet + facet normal -0.484729 0.00130408 0.874663 + outer loop + vertex 0.859316 1.51259 2.6126 + vertex 0.859317 1.51758 2.6126 + vertex 0.856097 1.51419 2.61082 + endloop + endfacet + facet normal -0.485341 -0.000302348 0.874325 + outer loop + vertex 0.856102 1.5092 2.61082 + vertex 0.859316 1.51259 2.6126 + vertex 0.856097 1.51419 2.61082 + endloop + endfacet + facet normal -0.490616 -0.000308012 0.871376 + outer loop + vertex 0.856097 1.51419 2.61082 + vertex 0.852902 1.51078 2.60902 + vertex 0.856102 1.5092 2.61082 + endloop + endfacet + facet normal -0.491168 -0.0017829 0.871063 + outer loop + vertex 0.852902 1.51078 2.60902 + vertex 0.85291 1.50579 2.60901 + vertex 0.856102 1.5092 2.61082 + endloop + endfacet + facet normal -0.490164 -0.00302016 0.871625 + outer loop + vertex 0.856102 1.5092 2.61082 + vertex 0.85291 1.50579 2.60901 + vertex 0.856117 1.50421 2.61081 + endloop + endfacet + facet normal -0.485446 -0.00301005 0.874262 + outer loop + vertex 0.856117 1.50421 2.61081 + vertex 0.859325 1.50759 2.6126 + vertex 0.856102 1.5092 2.61082 + endloop + endfacet + facet normal -0.484306 -0.00442081 0.874888 + outer loop + vertex 0.859345 1.5026 2.61259 + vertex 0.859325 1.50759 2.6126 + vertex 0.856117 1.50421 2.61081 + endloop + endfacet + facet normal -0.484795 -0.00571375 0.874609 + outer loop + vertex 0.856142 1.49921 2.61079 + vertex 0.859345 1.5026 2.61259 + vertex 0.856117 1.50421 2.61081 + endloop + endfacet + facet normal -0.489418 -0.00572653 0.87203 + outer loop + vertex 0.856117 1.50421 2.61081 + vertex 0.852929 1.5008 2.609 + vertex 0.856142 1.49921 2.61079 + endloop + endfacet + facet normal -0.489584 -0.0061726 0.871934 + outer loop + vertex 0.852929 1.5008 2.609 + vertex 0.852956 1.49581 2.60898 + vertex 0.856142 1.49921 2.61079 + endloop + endfacet + facet normal -0.488715 -0.00723989 0.872414 + outer loop + vertex 0.856142 1.49921 2.61079 + vertex 0.852956 1.49581 2.60898 + vertex 0.856172 1.49422 2.61077 + endloop + endfacet + facet normal -0.484657 -0.00722609 0.874674 + outer loop + vertex 0.856172 1.49422 2.61077 + vertex 0.859371 1.49761 2.61257 + vertex 0.856142 1.49921 2.61079 + endloop + endfacet + facet normal -0.484693 -0.00718163 0.874655 + outer loop + vertex 0.8594 1.49262 2.61254 + vertex 0.859371 1.49761 2.61257 + vertex 0.856172 1.49422 2.61077 + endloop + endfacet + facet normal -0.484838 -0.00756404 0.874572 + outer loop + vertex 0.856207 1.48924 2.61074 + vertex 0.8594 1.49262 2.61254 + vertex 0.856172 1.49422 2.61077 + endloop + endfacet + facet normal -0.488011 -0.00757774 0.872805 + outer loop + vertex 0.856172 1.49422 2.61077 + vertex 0.85299 1.49082 2.60896 + vertex 0.856207 1.48924 2.61074 + endloop + endfacet + facet normal -0.488214 -0.00812544 0.872686 + outer loop + vertex 0.85299 1.49082 2.60896 + vertex 0.853031 1.48583 2.60893 + vertex 0.856207 1.48924 2.61074 + endloop + endfacet + facet normal -0.487749 -0.00869481 0.872941 + outer loop + vertex 0.856207 1.48924 2.61074 + vertex 0.853031 1.48583 2.60893 + vertex 0.856245 1.48425 2.61071 + endloop + endfacet + facet normal -0.485573 -0.00868533 0.874153 + outer loop + vertex 0.856245 1.48425 2.61071 + vertex 0.859433 1.48763 2.61252 + vertex 0.856207 1.48924 2.61074 + endloop + endfacet + facet normal -0.48507 -0.00930487 0.874426 + outer loop + vertex 0.85947 1.48264 2.61249 + vertex 0.859433 1.48763 2.61252 + vertex 0.856245 1.48425 2.61071 + endloop + endfacet + facet normal -0.48604 -0.0118811 0.873856 + outer loop + vertex 0.856277 1.47926 2.61066 + vertex 0.85947 1.48264 2.61249 + vertex 0.856245 1.48425 2.61071 + endloop + endfacet + facet normal -0.487667 -0.0118824 0.872949 + outer loop + vertex 0.856245 1.48425 2.61071 + vertex 0.853066 1.48084 2.60889 + vertex 0.856277 1.47926 2.61066 + endloop + endfacet + facet normal -0.488702 -0.0146792 0.872327 + outer loop + vertex 0.853066 1.48084 2.60889 + vertex 0.853087 1.47585 2.60882 + vertex 0.856277 1.47926 2.61066 + endloop + endfacet + facet normal -0.487887 -0.0156767 0.872766 + outer loop + vertex 0.856277 1.47926 2.61066 + vertex 0.853087 1.47585 2.60882 + vertex 0.856299 1.47426 2.61059 + endloop + endfacet + facet normal -0.486576 -0.015682 0.873497 + outer loop + vertex 0.856299 1.47426 2.61059 + vertex 0.859505 1.47765 2.61243 + vertex 0.856277 1.47926 2.61066 + endloop + endfacet + facet normal -0.485857 -0.016571 0.873881 + outer loop + vertex 0.85954 1.47264 2.61236 + vertex 0.859505 1.47765 2.61243 + vertex 0.856299 1.47426 2.61059 + endloop + endfacet + facet normal -0.486861 -0.0192476 0.873268 + outer loop + vertex 0.85634 1.46924 2.6105 + vertex 0.85954 1.47264 2.61236 + vertex 0.856299 1.47426 2.61059 + endloop + endfacet + facet normal -0.488969 -0.019244 0.872089 + outer loop + vertex 0.856299 1.47426 2.61059 + vertex 0.853115 1.47085 2.60873 + vertex 0.85634 1.46924 2.6105 + endloop + endfacet + facet normal -0.489777 -0.0214281 0.871585 + outer loop + vertex 0.853115 1.47085 2.60873 + vertex 0.853217 1.46585 2.60866 + vertex 0.85634 1.46924 2.6105 + endloop + endfacet + facet normal -0.489993 -0.0211671 0.87147 + outer loop + vertex 0.85634 1.46924 2.6105 + vertex 0.853217 1.46585 2.60866 + vertex 0.856448 1.46425 2.61044 + endloop + endfacet + facet normal -0.487832 -0.021135 0.872682 + outer loop + vertex 0.856448 1.46425 2.61044 + vertex 0.859593 1.46761 2.61228 + vertex 0.85634 1.46924 2.6105 + endloop + endfacet + facet normal -0.488291 -0.0205719 0.872438 + outer loop + vertex 0.859677 1.46259 2.61221 + vertex 0.859593 1.46761 2.61228 + vertex 0.856448 1.46425 2.61044 + endloop + endfacet + facet normal -0.488679 -0.0215834 0.872197 + outer loop + vertex 0.85662 1.45941 2.61042 + vertex 0.859677 1.46259 2.61221 + vertex 0.856448 1.46425 2.61044 + endloop + endfacet + facet normal -0.490702 -0.0216496 0.871058 + outer loop + vertex 0.856448 1.46425 2.61044 + vertex 0.85349 1.46095 2.60869 + vertex 0.85662 1.45941 2.61042 + endloop + endfacet + facet normal -0.49068 -0.0215902 0.871072 + outer loop + vertex 0.85349 1.46095 2.60869 + vertex 0.854032 1.45683 2.60889 + vertex 0.85662 1.45941 2.61042 + endloop + endfacet + facet normal -0.490618 -0.0216723 0.871105 + outer loop + vertex 0.85662 1.45941 2.61042 + vertex 0.854032 1.45683 2.60889 + vertex 0.856582 1.45465 2.61028 + endloop + endfacet + facet normal -0.489505 -0.0216995 0.87173 + outer loop + vertex 0.856582 1.45465 2.61028 + vertex 0.859739 1.4576 2.61212 + vertex 0.85662 1.45941 2.61042 + endloop + endfacet + facet normal -0.489892 -0.0211593 0.871527 + outer loop + vertex 0.859768 1.45261 2.61202 + vertex 0.859739 1.4576 2.61212 + vertex 0.856582 1.45465 2.61028 + endloop + endfacet + facet normal -0.490414 -0.0222514 0.871205 + outer loop + vertex 0.856544 1.44966 2.61013 + vertex 0.859768 1.45261 2.61202 + vertex 0.856582 1.45465 2.61028 + endloop + endfacet + facet normal -0.492508 -0.0222003 0.870025 + outer loop + vertex 0.856582 1.45465 2.61028 + vertex 0.85298 1.45237 2.60818 + vertex 0.856544 1.44966 2.61013 + endloop + endfacet + facet normal -0.493966 -0.0247597 0.869128 + outer loop + vertex 0.85298 1.45237 2.60818 + vertex 0.853432 1.44679 2.60828 + vertex 0.856544 1.44966 2.61013 + endloop + endfacet + facet normal -0.494135 -0.024519 0.869039 + outer loop + vertex 0.856544 1.44966 2.61013 + vertex 0.853432 1.44679 2.60828 + vertex 0.856803 1.44454 2.61013 + endloop + endfacet + facet normal -0.491951 -0.0244078 0.870281 + outer loop + vertex 0.856803 1.44454 2.61013 + vertex 0.85987 1.44757 2.61195 + vertex 0.856544 1.44966 2.61013 + endloop + endfacet + facet normal -0.492145 -0.0241505 0.870178 + outer loop + vertex 0.860152 1.4425 2.61197 + vertex 0.85987 1.44757 2.61195 + vertex 0.856803 1.44454 2.61013 + endloop + endfacet + facet normal -0.49381 -0.027833 0.869124 + outer loop + vertex 0.857207 1.43952 2.6102 + vertex 0.860152 1.4425 2.61197 + vertex 0.856803 1.44454 2.61013 + endloop + endfacet + facet normal -0.496607 -0.0280798 0.867521 + outer loop + vertex 0.856803 1.44454 2.61013 + vertex 0.853803 1.44162 2.60832 + vertex 0.857207 1.43952 2.6102 + endloop + endfacet + facet normal -0.498837 -0.0330053 0.866067 + outer loop + vertex 0.853803 1.44162 2.60832 + vertex 0.854272 1.4361 2.60838 + vertex 0.857207 1.43952 2.6102 + endloop + endfacet + facet normal -0.499977 -0.0317041 0.865458 + outer loop + vertex 0.857668 1.4354 2.61031 + vertex 0.857207 1.43952 2.6102 + vertex 0.854272 1.4361 2.60838 + endloop + endfacet + facet normal -0.500486 -0.0353971 0.865021 + outer loop + vertex 0.857668 1.4354 2.61031 + vertex 0.854272 1.4361 2.60838 + vertex 0.856579 1.43127 2.60951 + endloop + endfacet + facet normal -0.499788 -0.0356573 0.865414 + outer loop + vertex 0.856579 1.43127 2.60951 + vertex 0.859606 1.43296 2.61133 + vertex 0.857668 1.4354 2.61031 + endloop + endfacet + facet normal -0.495797 -0.0314566 0.867868 + outer loop + vertex 0.859606 1.43296 2.61133 + vertex 0.860697 1.43713 2.61211 + vertex 0.857668 1.4354 2.61031 + endloop + endfacet + facet normal -0.494609 -0.0318912 0.86853 + outer loop + vertex 0.859606 1.43296 2.61133 + vertex 0.862989 1.43231 2.61323 + vertex 0.860697 1.43713 2.61211 + endloop + endfacet + facet normal -0.49235 -0.0305047 0.869863 + outer loop + vertex 0.862989 1.43231 2.61323 + vertex 0.86402 1.43676 2.61397 + vertex 0.860697 1.43713 2.61211 + endloop + endfacet + facet normal -0.494965 -0.0346284 0.868223 + outer loop + vertex 0.860076 1.42884 2.61144 + vertex 0.862989 1.43231 2.61323 + vertex 0.859606 1.43296 2.61133 + endloop + endfacet + facet normal -0.499956 -0.0352694 0.865332 + outer loop + vertex 0.859606 1.43296 2.61133 + vertex 0.856579 1.43127 2.60951 + vertex 0.860076 1.42884 2.61144 + endloop + endfacet + facet normal -0.501321 -0.0379506 0.864429 + outer loop + vertex 0.856579 1.43127 2.60951 + vertex 0.857166 1.42591 2.60962 + vertex 0.860076 1.42884 2.61144 + endloop + endfacet + facet normal -0.502408 -0.0365176 0.863859 + outer loop + vertex 0.860076 1.42884 2.61144 + vertex 0.857166 1.42591 2.60962 + vertex 0.860509 1.42386 2.61148 + endloop + endfacet + facet normal -0.497431 -0.0360604 0.866754 + outer loop + vertex 0.860509 1.42386 2.61148 + vertex 0.863478 1.4268 2.6133 + vertex 0.860076 1.42884 2.61144 + endloop + endfacet + facet normal -0.497729 -0.0356642 0.866599 + outer loop + vertex 0.863886 1.42175 2.61333 + vertex 0.863478 1.4268 2.6133 + vertex 0.860509 1.42386 2.61148 + endloop + endfacet + facet normal -0.498548 -0.0374532 0.866053 + outer loop + vertex 0.860806 1.41885 2.61143 + vertex 0.863886 1.42175 2.61333 + vertex 0.860509 1.42386 2.61148 + endloop + endfacet + facet normal -0.504529 -0.0377752 0.862568 + outer loop + vertex 0.860509 1.42386 2.61148 + vertex 0.857495 1.42087 2.60958 + vertex 0.860806 1.41885 2.61143 + endloop + endfacet + facet normal -0.505486 -0.0399451 0.86191 + outer loop + vertex 0.857495 1.42087 2.60958 + vertex 0.857643 1.41588 2.60944 + vertex 0.860806 1.41885 2.61143 + endloop + endfacet + facet normal -0.506185 -0.0389551 0.861545 + outer loop + vertex 0.860806 1.41885 2.61143 + vertex 0.857643 1.41588 2.60944 + vertex 0.860801 1.41396 2.61121 + endloop + endfacet + facet normal -0.499474 -0.0391402 0.865444 + outer loop + vertex 0.860801 1.41396 2.61121 + vertex 0.864383 1.41635 2.61338 + vertex 0.860806 1.41885 2.61143 + endloop + endfacet + facet normal -0.5003 -0.0375343 0.865038 + outer loop + vertex 0.863355 1.4119 2.6126 + vertex 0.864383 1.41635 2.61338 + vertex 0.860801 1.41396 2.61121 + endloop + endfacet + facet normal -0.502951 -0.0420091 0.863294 + outer loop + vertex 0.860813 1.40923 2.61098 + vertex 0.863355 1.4119 2.6126 + vertex 0.860801 1.41396 2.61121 + endloop + endfacet + facet normal -0.507873 -0.0418858 0.860413 + outer loop + vertex 0.860801 1.41396 2.61121 + vertex 0.857727 1.41094 2.60925 + vertex 0.860813 1.40923 2.61098 + endloop + endfacet + facet normal -0.509523 -0.0460717 0.859223 + outer loop + vertex 0.857727 1.41094 2.60925 + vertex 0.857913 1.40601 2.60909 + vertex 0.860813 1.40923 2.61098 + endloop + endfacet + facet normal -0.50941 -0.046208 0.859282 + outer loop + vertex 0.860813 1.40923 2.61098 + vertex 0.857913 1.40601 2.60909 + vertex 0.861098 1.4044 2.61089 + endloop + endfacet + facet normal -0.502299 -0.0458667 0.863477 + outer loop + vertex 0.861098 1.4044 2.61089 + vertex 0.86396 1.40776 2.61274 + vertex 0.860813 1.40923 2.61098 + endloop + endfacet + facet normal -0.502075 -0.0461206 0.863593 + outer loop + vertex 0.864324 1.40277 2.61268 + vertex 0.86396 1.40776 2.61274 + vertex 0.861098 1.4044 2.61089 + endloop + endfacet + facet normal -0.503045 -0.0488164 0.86288 + outer loop + vertex 0.861384 1.39955 2.61079 + vertex 0.864324 1.40277 2.61268 + vertex 0.861098 1.4044 2.61089 + endloop + endfacet + facet normal -0.511341 -0.0491972 0.857968 + outer loop + vertex 0.861098 1.4044 2.61089 + vertex 0.858276 1.40111 2.60902 + vertex 0.861384 1.39955 2.61079 + endloop + endfacet + facet normal -0.512449 -0.0523705 0.857119 + outer loop + vertex 0.858276 1.40111 2.60902 + vertex 0.858881 1.39697 2.60913 + vertex 0.861384 1.39955 2.61079 + endloop + endfacet + facet normal -0.51244 -0.0523824 0.857124 + outer loop + vertex 0.861384 1.39955 2.61079 + vertex 0.858881 1.39697 2.60913 + vertex 0.861432 1.39476 2.61052 + endloop + endfacet + facet normal -0.504713 -0.0525574 0.861686 + outer loop + vertex 0.861432 1.39476 2.61052 + vertex 0.864502 1.39772 2.6125 + vertex 0.861384 1.39955 2.61079 + endloop + endfacet + facet normal -0.505504 -0.0514694 0.861288 + outer loop + vertex 0.864627 1.39268 2.61227 + vertex 0.864502 1.39772 2.6125 + vertex 0.861432 1.39476 2.61052 + endloop + endfacet + facet normal -0.507066 -0.0548141 0.860163 + outer loop + vertex 0.861557 1.38974 2.61028 + vertex 0.864627 1.39268 2.61227 + vertex 0.861432 1.39476 2.61052 + endloop + endfacet + facet normal -0.517906 -0.0547663 0.853683 + outer loop + vertex 0.861432 1.39476 2.61052 + vertex 0.857957 1.39248 2.60827 + vertex 0.861557 1.38974 2.61028 + endloop + endfacet + facet normal -0.519632 -0.057955 0.852423 + outer loop + vertex 0.857957 1.39248 2.60827 + vertex 0.858636 1.38677 2.60829 + vertex 0.861557 1.38974 2.61028 + endloop + endfacet + facet normal -0.520465 -0.0568441 0.851989 + outer loop + vertex 0.861557 1.38974 2.61028 + vertex 0.858636 1.38677 2.60829 + vertex 0.862088 1.38461 2.61026 + endloop + endfacet + facet normal -0.508537 -0.0556346 0.859241 + outer loop + vertex 0.862088 1.38461 2.61026 + vertex 0.864939 1.38761 2.61214 + vertex 0.861557 1.38974 2.61028 + endloop + endfacet + facet normal -0.507045 -0.057526 0.859998 + outer loop + vertex 0.865631 1.38225 2.61219 + vertex 0.864939 1.38761 2.61214 + vertex 0.862088 1.38461 2.61026 + endloop + endfacet + facet normal -0.50694 -0.0573058 0.860074 + outer loop + vertex 0.862687 1.38045 2.61033 + vertex 0.865631 1.38225 2.61219 + vertex 0.862088 1.38461 2.61026 + endloop + endfacet + facet normal -0.494917 -0.0558961 0.867141 + outer loop + vertex 0.865631 1.38225 2.61219 + vertex 0.868256 1.38601 2.61393 + vertex 0.864939 1.38761 2.61214 + endloop + endfacet + facet normal -0.494313 -0.054129 0.867597 + outer loop + vertex 0.868256 1.38601 2.61393 + vertex 0.867902 1.39089 2.61403 + vertex 0.864939 1.38761 2.61214 + endloop + endfacet + facet normal -0.495026 -0.0532819 0.867243 + outer loop + vertex 0.864939 1.38761 2.61214 + vertex 0.867902 1.39089 2.61403 + vertex 0.864627 1.39268 2.61227 + endloop + endfacet + facet normal -0.521783 -0.0598627 0.850975 + outer loop + vertex 0.858636 1.38677 2.60829 + vertex 0.859362 1.38112 2.60834 + vertex 0.862088 1.38461 2.61026 + endloop + endfacet + facet normal -0.530914 -0.0610827 0.845221 + outer loop + vertex 0.859362 1.38112 2.60834 + vertex 0.858636 1.38677 2.60829 + vertex 0.855821 1.38384 2.60631 + endloop + endfacet + facet normal -0.532541 -0.0641278 0.843971 + outer loop + vertex 0.85611 1.37906 2.60613 + vertex 0.859362 1.38112 2.60834 + vertex 0.855821 1.38384 2.60631 + endloop + endfacet + facet normal -0.539533 -0.0643817 0.839499 + outer loop + vertex 0.855821 1.38384 2.60631 + vertex 0.853114 1.38101 2.60436 + vertex 0.85611 1.37906 2.60613 + endloop + endfacet + facet normal -0.541244 -0.0683078 0.838087 + outer loop + vertex 0.853114 1.38101 2.60436 + vertex 0.85375 1.37691 2.60443 + vertex 0.85611 1.37906 2.60613 + endloop + endfacet + facet normal -0.541303 -0.0682181 0.838056 + outer loop + vertex 0.85611 1.37906 2.60613 + vertex 0.85375 1.37691 2.60443 + vertex 0.856124 1.37462 2.60578 + endloop + endfacet + facet normal -0.537801 -0.0666788 0.840431 + outer loop + vertex 0.852536 1.38597 2.60438 + vertex 0.853114 1.38101 2.60436 + vertex 0.855821 1.38384 2.60631 + endloop + endfacet + facet normal -0.53625 -0.0631457 0.841694 + outer loop + vertex 0.855222 1.38895 2.60631 + vertex 0.852536 1.38597 2.60438 + vertex 0.855821 1.38384 2.60631 + endloop + endfacet + facet normal -0.534648 -0.0651524 0.842559 + outer loop + vertex 0.8518 1.39138 2.60433 + vertex 0.852536 1.38597 2.60438 + vertex 0.855222 1.38895 2.60631 + endloop + endfacet + facet normal -0.533396 -0.062579 0.843547 + outer loop + vertex 0.854651 1.39315 2.60627 + vertex 0.8518 1.39138 2.60433 + vertex 0.855222 1.38895 2.60631 + endloop + endfacet + facet normal -0.52611 -0.0615332 0.848187 + outer loop + vertex 0.855222 1.38895 2.60631 + vertex 0.857957 1.39248 2.60827 + vertex 0.854651 1.39315 2.60627 + endloop + endfacet + facet normal -0.525897 -0.0596843 0.848452 + outer loop + vertex 0.854651 1.39315 2.60627 + vertex 0.857957 1.39248 2.60827 + vertex 0.855637 1.39734 2.60717 + endloop + endfacet + facet normal -0.527644 -0.0590482 0.847411 + outer loop + vertex 0.854651 1.39315 2.60627 + vertex 0.855637 1.39734 2.60717 + vertex 0.852744 1.39556 2.60525 + endloop + endfacet + facet normal -0.526971 -0.0604844 0.847728 + outer loop + vertex 0.852744 1.39556 2.60525 + vertex 0.855637 1.39734 2.60717 + vertex 0.852234 1.39965 2.60522 + endloop + endfacet + facet normal -0.535201 -0.0615388 0.84248 + outer loop + vertex 0.852744 1.39556 2.60525 + vertex 0.852234 1.39965 2.60522 + vertex 0.8495 1.39623 2.60323 + endloop + endfacet + facet normal -0.53541 -0.0633624 0.842212 + outer loop + vertex 0.852744 1.39556 2.60525 + vertex 0.8495 1.39623 2.60323 + vertex 0.8518 1.39138 2.60433 + endloop + endfacet + facet normal -0.538627 -0.065388 0.840003 + outer loop + vertex 0.8518 1.39138 2.60433 + vertex 0.8495 1.39623 2.60323 + vertex 0.848599 1.39188 2.60232 + endloop + endfacet + facet normal -0.538743 -0.0669271 0.839808 + outer loop + vertex 0.849305 1.38772 2.60244 + vertex 0.8518 1.39138 2.60433 + vertex 0.848599 1.39188 2.60232 + endloop + endfacet + facet normal -0.546956 -0.0684821 0.834355 + outer loop + vertex 0.849305 1.38772 2.60244 + vertex 0.848599 1.39188 2.60232 + vertex 0.846173 1.38965 2.60054 + endloop + endfacet + facet normal -0.546924 -0.0684025 0.834383 + outer loop + vertex 0.846682 1.3847 2.60047 + vertex 0.849305 1.38772 2.60244 + vertex 0.846173 1.38965 2.60054 + endloop + endfacet + facet normal -0.546142 -0.0693628 0.834816 + outer loop + vertex 0.849916 1.38274 2.60242 + vertex 0.849305 1.38772 2.60244 + vertex 0.846682 1.3847 2.60047 + endloop + endfacet + facet normal -0.547486 -0.0727496 0.833646 + outer loop + vertex 0.847242 1.37967 2.6004 + vertex 0.849916 1.38274 2.60242 + vertex 0.846682 1.3847 2.60047 + endloop + endfacet + facet normal -0.54785 -0.0723006 0.833446 + outer loop + vertex 0.850597 1.37735 2.60241 + vertex 0.849916 1.38274 2.60242 + vertex 0.847242 1.37967 2.6004 + endloop + endfacet + facet normal -0.549982 -0.0769587 0.831623 + outer loop + vertex 0.847772 1.37551 2.60037 + vertex 0.850597 1.37735 2.60241 + vertex 0.847242 1.37967 2.6004 + endloop + endfacet + facet normal -0.543804 -0.0717987 0.836135 + outer loop + vertex 0.850597 1.37735 2.60241 + vertex 0.853114 1.38101 2.60436 + vertex 0.849916 1.38274 2.60242 + endloop + endfacet + facet normal -0.540817 -0.06872 0.838328 + outer loop + vertex 0.849916 1.38274 2.60242 + vertex 0.852536 1.38597 2.60438 + vertex 0.849305 1.38772 2.60244 + endloop + endfacet + facet normal -0.548078 -0.0667795 0.833757 + outer loop + vertex 0.846173 1.38965 2.60054 + vertex 0.848599 1.39188 2.60232 + vertex 0.846143 1.39436 2.6009 + endloop + endfacet + facet normal -0.559241 -0.0662905 0.82635 + outer loop + vertex 0.846143 1.39436 2.6009 + vertex 0.842812 1.39249 2.5985 + vertex 0.846173 1.38965 2.60054 + endloop + endfacet + facet normal -0.558729 -0.0653816 0.826769 + outer loop + vertex 0.842812 1.39249 2.5985 + vertex 0.843435 1.3869 2.59848 + vertex 0.846173 1.38965 2.60054 + endloop + endfacet + facet normal -0.555993 -0.0692453 0.828298 + outer loop + vertex 0.846173 1.38965 2.60054 + vertex 0.843435 1.3869 2.59848 + vertex 0.846682 1.3847 2.60047 + endloop + endfacet + facet normal -0.556739 -0.070934 0.827653 + outer loop + vertex 0.843435 1.3869 2.59848 + vertex 0.843971 1.38172 2.59839 + vertex 0.846682 1.3847 2.60047 + endloop + endfacet + facet normal -0.554772 -0.0734904 0.82875 + outer loop + vertex 0.846682 1.3847 2.60047 + vertex 0.843971 1.38172 2.59839 + vertex 0.847242 1.37967 2.6004 + endloop + endfacet + facet normal -0.556812 -0.0785342 0.826917 + outer loop + vertex 0.843971 1.38172 2.59839 + vertex 0.844567 1.37615 2.59827 + vertex 0.847242 1.37967 2.6004 + endloop + endfacet + facet normal -0.557419 -0.077863 0.826572 + outer loop + vertex 0.847772 1.37551 2.60037 + vertex 0.847242 1.37967 2.6004 + vertex 0.844567 1.37615 2.59827 + endloop + endfacet + facet normal -0.557741 -0.0812016 0.826033 + outer loop + vertex 0.847772 1.37551 2.60037 + vertex 0.844567 1.37615 2.59827 + vertex 0.846903 1.37129 2.59936 + endloop + endfacet + facet normal -0.558247 -0.0686767 0.826828 + outer loop + vertex 0.843706 1.39689 2.59947 + vertex 0.842812 1.39249 2.5985 + vertex 0.846143 1.39436 2.6009 + endloop + endfacet + facet normal -0.555517 -0.0648259 0.828974 + outer loop + vertex 0.846146 1.39902 2.60127 + vertex 0.843706 1.39689 2.59947 + vertex 0.846143 1.39436 2.6009 + endloop + endfacet + facet normal -0.5445 -0.0654017 0.836207 + outer loop + vertex 0.846143 1.39436 2.6009 + vertex 0.8495 1.39623 2.60323 + vertex 0.846146 1.39902 2.60127 + endloop + endfacet + facet normal -0.543273 -0.0632496 0.83717 + outer loop + vertex 0.8495 1.39623 2.60323 + vertex 0.848955 1.40165 2.60329 + vertex 0.846146 1.39902 2.60127 + endloop + endfacet + facet normal -0.545044 -0.0606246 0.836213 + outer loop + vertex 0.846146 1.39902 2.60127 + vertex 0.848955 1.40165 2.60329 + vertex 0.845759 1.40384 2.60137 + endloop + endfacet + facet normal -0.543932 -0.0582198 0.837107 + outer loop + vertex 0.848955 1.40165 2.60329 + vertex 0.848571 1.40665 2.60339 + vertex 0.845759 1.40384 2.60137 + endloop + endfacet + facet normal -0.557971 -0.0608711 0.827625 + outer loop + vertex 0.84309 1.40102 2.59935 + vertex 0.843706 1.39689 2.59947 + vertex 0.846146 1.39902 2.60127 + endloop + endfacet + facet normal -0.558242 -0.0615052 0.827395 + outer loop + vertex 0.845759 1.40384 2.60137 + vertex 0.84309 1.40102 2.59935 + vertex 0.846146 1.39902 2.60127 + endloop + endfacet + facet normal -0.560596 -0.0583131 0.826034 + outer loop + vertex 0.842673 1.40588 2.59942 + vertex 0.84309 1.40102 2.59935 + vertex 0.845759 1.40384 2.60137 + endloop + endfacet + facet normal -0.559832 -0.0565432 0.826675 + outer loop + vertex 0.845406 1.40878 2.60146 + vertex 0.842673 1.40588 2.59942 + vertex 0.845759 1.40384 2.60137 + endloop + endfacet + facet normal -0.545714 -0.0557218 0.836117 + outer loop + vertex 0.845759 1.40384 2.60137 + vertex 0.848571 1.40665 2.60339 + vertex 0.845406 1.40878 2.60146 + endloop + endfacet + facet normal -0.544145 -0.0522588 0.837362 + outer loop + vertex 0.848571 1.40665 2.60339 + vertex 0.84824 1.41174 2.60349 + vertex 0.845406 1.40878 2.60146 + endloop + endfacet + facet normal -0.545119 -0.0509481 0.836809 + outer loop + vertex 0.845406 1.40878 2.60146 + vertex 0.84824 1.41174 2.60349 + vertex 0.84501 1.41377 2.60151 + endloop + endfacet + facet normal -0.561468 -0.052142 0.825854 + outer loop + vertex 0.84501 1.41377 2.60151 + vertex 0.842313 1.41084 2.59949 + vertex 0.845406 1.40878 2.60146 + endloop + endfacet + facet normal -0.563226 -0.0497943 0.824801 + outer loop + vertex 0.841777 1.41614 2.59945 + vertex 0.842313 1.41084 2.59949 + vertex 0.84501 1.41377 2.60151 + endloop + endfacet + facet normal -0.564223 -0.05186 0.823992 + outer loop + vertex 0.844559 1.41792 2.60146 + vertex 0.841777 1.41614 2.59945 + vertex 0.84501 1.41377 2.60151 + endloop + endfacet + facet normal -0.54376 -0.0494745 0.837782 + outer loop + vertex 0.84501 1.41377 2.60151 + vertex 0.847783 1.41735 2.60352 + vertex 0.844559 1.41792 2.60146 + endloop + endfacet + facet normal -0.54369 -0.0487596 0.837869 + outer loop + vertex 0.844559 1.41792 2.60146 + vertex 0.847783 1.41735 2.60352 + vertex 0.845549 1.42218 2.60235 + endloop + endfacet + facet normal -0.557681 -0.0436347 0.828908 + outer loop + vertex 0.844559 1.41792 2.60146 + vertex 0.845549 1.42218 2.60235 + vertex 0.842742 1.4203 2.60037 + endloop + endfacet + facet normal -0.538567 -0.0455435 0.841351 + outer loop + vertex 0.847783 1.41735 2.60352 + vertex 0.848731 1.42192 2.60438 + vertex 0.845549 1.42218 2.60235 + endloop + endfacet + facet normal -0.538571 -0.0456464 0.841343 + outer loop + vertex 0.848731 1.42192 2.60438 + vertex 0.848104 1.42605 2.6042 + vertex 0.845549 1.42218 2.60235 + endloop + endfacet + facet normal -0.54124 -0.0431346 0.839761 + outer loop + vertex 0.845549 1.42218 2.60235 + vertex 0.848104 1.42605 2.6042 + vertex 0.844985 1.42759 2.60227 + endloop + endfacet + facet normal -0.558878 -0.045157 0.828019 + outer loop + vertex 0.845549 1.42218 2.60235 + vertex 0.844985 1.42759 2.60227 + vertex 0.842279 1.42443 2.60027 + endloop + endfacet + facet normal -0.557935 -0.0431024 0.828765 + outer loop + vertex 0.842742 1.4203 2.60037 + vertex 0.845549 1.42218 2.60235 + vertex 0.842279 1.42443 2.60027 + endloop + endfacet + facet normal -0.577516 -0.0456191 0.815104 + outer loop + vertex 0.842742 1.4203 2.60037 + vertex 0.842279 1.42443 2.60027 + vertex 0.839634 1.42092 2.5982 + endloop + endfacet + facet normal -0.577581 -0.0462204 0.815024 + outer loop + vertex 0.842742 1.4203 2.60037 + vertex 0.839634 1.42092 2.5982 + vertex 0.841777 1.41614 2.59945 + endloop + endfacet + facet normal -0.58083 -0.0483115 0.81259 + outer loop + vertex 0.841777 1.41614 2.59945 + vertex 0.839634 1.42092 2.5982 + vertex 0.83876 1.41657 2.59731 + endloop + endfacet + facet normal -0.580861 -0.0487783 0.81254 + outer loop + vertex 0.839321 1.41255 2.59747 + vertex 0.841777 1.41614 2.59945 + vertex 0.83876 1.41657 2.59731 + endloop + endfacet + facet normal -0.578328 -0.0514123 0.814183 + outer loop + vertex 0.842313 1.41084 2.59949 + vertex 0.841777 1.41614 2.59945 + vertex 0.839321 1.41255 2.59747 + endloop + endfacet + facet normal -0.578514 -0.0519353 0.814018 + outer loop + vertex 0.839672 1.40776 2.59742 + vertex 0.842313 1.41084 2.59949 + vertex 0.839321 1.41255 2.59747 + endloop + endfacet + facet normal -0.592691 -0.0528525 0.803694 + outer loop + vertex 0.839672 1.40776 2.59742 + vertex 0.839321 1.41255 2.59747 + vertex 0.836751 1.40956 2.59538 + endloop + endfacet + facet normal -0.593364 -0.0546369 0.803078 + outer loop + vertex 0.837022 1.4047 2.59525 + vertex 0.839672 1.40776 2.59742 + vertex 0.836751 1.40956 2.59538 + endloop + endfacet + facet normal -0.605437 -0.0550654 0.793986 + outer loop + vertex 0.836751 1.40956 2.59538 + vertex 0.834084 1.40665 2.59315 + vertex 0.837022 1.4047 2.59525 + endloop + endfacet + facet normal -0.606583 -0.0579468 0.792905 + outer loop + vertex 0.834084 1.40665 2.59315 + vertex 0.834366 1.40167 2.593 + vertex 0.837022 1.4047 2.59525 + endloop + endfacet + facet normal -0.605346 -0.0596418 0.793725 + outer loop + vertex 0.837022 1.4047 2.59525 + vertex 0.834366 1.40167 2.593 + vertex 0.837392 1.39976 2.59516 + endloop + endfacet + facet normal -0.591788 -0.0588105 0.803946 + outer loop + vertex 0.837392 1.39976 2.59516 + vertex 0.840022 1.4028 2.59732 + vertex 0.837022 1.4047 2.59525 + endloop + endfacet + facet normal -0.589643 -0.0616394 0.805308 + outer loop + vertex 0.840583 1.39744 2.59732 + vertex 0.840022 1.4028 2.59732 + vertex 0.837392 1.39976 2.59516 + endloop + endfacet + facet normal -0.588585 -0.0593074 0.806257 + outer loop + vertex 0.837826 1.39564 2.59518 + vertex 0.840583 1.39744 2.59732 + vertex 0.837392 1.39976 2.59516 + endloop + endfacet + facet normal -0.606202 -0.0612103 0.792952 + outer loop + vertex 0.837826 1.39564 2.59518 + vertex 0.837392 1.39976 2.59516 + vertex 0.834811 1.39621 2.59292 + endloop + endfacet + facet normal -0.606238 -0.0616497 0.79289 + outer loop + vertex 0.837826 1.39564 2.59518 + vertex 0.834811 1.39621 2.59292 + vertex 0.836955 1.3914 2.59418 + endloop + endfacet + facet normal -0.593535 -0.0664153 0.802063 + outer loop + vertex 0.836955 1.3914 2.59418 + vertex 0.839634 1.39322 2.59631 + vertex 0.837826 1.39564 2.59518 + endloop + endfacet + facet normal -0.593398 -0.0667074 0.80214 + outer loop + vertex 0.839634 1.39322 2.59631 + vertex 0.836955 1.3914 2.59418 + vertex 0.840204 1.38901 2.59639 + endloop + endfacet + facet normal -0.575037 -0.0639903 0.815621 + outer loop + vertex 0.840204 1.38901 2.59639 + vertex 0.842812 1.39249 2.5985 + vertex 0.839634 1.39322 2.59631 + endloop + endfacet + facet normal -0.575195 -0.0653363 0.815403 + outer loop + vertex 0.839634 1.39322 2.59631 + vertex 0.842812 1.39249 2.5985 + vertex 0.840583 1.39744 2.59732 + endloop + endfacet + facet normal -0.572564 -0.0636794 0.817383 + outer loop + vertex 0.842812 1.39249 2.5985 + vertex 0.843706 1.39689 2.59947 + vertex 0.840583 1.39744 2.59732 + endloop + endfacet + facet normal -0.572535 -0.0633249 0.817431 + outer loop + vertex 0.843706 1.39689 2.59947 + vertex 0.84309 1.40102 2.59935 + vertex 0.840583 1.39744 2.59732 + endloop + endfacet + facet normal -0.572464 -0.0668731 0.817198 + outer loop + vertex 0.843435 1.3869 2.59848 + vertex 0.842812 1.39249 2.5985 + vertex 0.840204 1.38901 2.59639 + endloop + endfacet + facet normal -0.572015 -0.0657888 0.817601 + outer loop + vertex 0.84082 1.38406 2.59642 + vertex 0.843435 1.3869 2.59848 + vertex 0.840204 1.38901 2.59639 + endloop + endfacet + facet normal -0.587687 -0.0678156 0.806242 + outer loop + vertex 0.840204 1.38901 2.59639 + vertex 0.83776 1.38605 2.59436 + vertex 0.84082 1.38406 2.59642 + endloop + endfacet + facet normal -0.58759 -0.067574 0.806332 + outer loop + vertex 0.83776 1.38605 2.59436 + vertex 0.838582 1.38178 2.5946 + vertex 0.84082 1.38406 2.59642 + endloop + endfacet + facet normal -0.581921 -0.0758422 0.809701 + outer loop + vertex 0.84082 1.38406 2.59642 + vertex 0.838582 1.38178 2.5946 + vertex 0.841145 1.37917 2.59619 + endloop + endfacet + facet normal -0.569114 -0.0754112 0.818793 + outer loop + vertex 0.841145 1.37917 2.59619 + vertex 0.843971 1.38172 2.59839 + vertex 0.84082 1.38406 2.59642 + endloop + endfacet + facet normal -0.566567 -0.0794237 0.820179 + outer loop + vertex 0.844567 1.37615 2.59827 + vertex 0.843971 1.38172 2.59839 + vertex 0.841145 1.37917 2.59619 + endloop + endfacet + facet normal -0.586489 -0.0827513 0.805719 + outer loop + vertex 0.838582 1.38178 2.5946 + vertex 0.837839 1.37741 2.59361 + vertex 0.841145 1.37917 2.59619 + endloop + endfacet + facet normal -0.586617 -0.082424 0.805659 + outer loop + vertex 0.841145 1.37917 2.59619 + vertex 0.837839 1.37741 2.59361 + vertex 0.841228 1.37423 2.59575 + endloop + endfacet + facet normal -0.568782 -0.0832568 0.818264 + outer loop + vertex 0.841228 1.37423 2.59575 + vertex 0.844567 1.37615 2.59827 + vertex 0.841145 1.37917 2.59619 + endloop + endfacet + facet normal -0.569777 -0.0809291 0.817805 + outer loop + vertex 0.843784 1.37172 2.59728 + vertex 0.844567 1.37615 2.59827 + vertex 0.841228 1.37423 2.59575 + endloop + endfacet + facet normal -0.561459 -0.0836092 0.82327 + outer loop + vertex 0.846903 1.37129 2.59936 + vertex 0.844567 1.37615 2.59827 + vertex 0.843784 1.37172 2.59728 + endloop + endfacet + facet normal -0.56157 -0.085976 0.82295 + outer loop + vertex 0.84463 1.36757 2.59743 + vertex 0.846903 1.37129 2.59936 + vertex 0.843784 1.37172 2.59728 + endloop + endfacet + facet normal -0.570402 -0.0880022 0.816638 + outer loop + vertex 0.84463 1.36757 2.59743 + vertex 0.843784 1.37172 2.59728 + vertex 0.841577 1.36941 2.59549 + endloop + endfacet + facet normal -0.569553 -0.0857118 0.817473 + outer loop + vertex 0.842215 1.36463 2.59543 + vertex 0.84463 1.36757 2.59743 + vertex 0.841577 1.36941 2.59549 + endloop + endfacet + facet normal -0.581316 -0.0871775 0.808994 + outer loop + vertex 0.841577 1.36941 2.59549 + vertex 0.839028 1.36666 2.59336 + vertex 0.842215 1.36463 2.59543 + endloop + endfacet + facet normal -0.579168 -0.0816682 0.811107 + outer loop + vertex 0.839028 1.36666 2.59336 + vertex 0.839671 1.36114 2.59327 + vertex 0.842215 1.36463 2.59543 + endloop + endfacet + facet normal -0.576078 -0.0850736 0.812955 + outer loop + vertex 0.842794 1.36057 2.59542 + vertex 0.842215 1.36463 2.59543 + vertex 0.839671 1.36114 2.59327 + endloop + endfacet + facet normal -0.575883 -0.08246 0.813363 + outer loop + vertex 0.842794 1.36057 2.59542 + vertex 0.839671 1.36114 2.59327 + vertex 0.84193 1.35638 2.59438 + endloop + endfacet + facet normal -0.568098 -0.0853401 0.818524 + outer loop + vertex 0.84193 1.35638 2.59438 + vertex 0.844648 1.35819 2.59646 + vertex 0.842794 1.36057 2.59542 + endloop + endfacet + facet normal -0.567854 -0.0858419 0.818641 + outer loop + vertex 0.844648 1.35819 2.59646 + vertex 0.84193 1.35638 2.59438 + vertex 0.845232 1.35404 2.59643 + endloop + endfacet + facet normal -0.566962 -0.0857208 0.819272 + outer loop + vertex 0.845232 1.35404 2.59643 + vertex 0.847824 1.35742 2.59858 + vertex 0.844648 1.35819 2.59646 + endloop + endfacet + facet normal -0.566848 -0.0847508 0.819451 + outer loop + vertex 0.844648 1.35819 2.59646 + vertex 0.847824 1.35742 2.59858 + vertex 0.845497 1.36234 2.59748 + endloop + endfacet + facet normal -0.565671 -0.0839951 0.820342 + outer loop + vertex 0.847824 1.35742 2.59858 + vertex 0.848612 1.36182 2.59957 + vertex 0.845497 1.36234 2.59748 + endloop + endfacet + facet normal -0.565655 -0.0837601 0.820377 + outer loop + vertex 0.848612 1.36182 2.59957 + vertex 0.847776 1.36601 2.59942 + vertex 0.845497 1.36234 2.59748 + endloop + endfacet + facet normal -0.563654 -0.0856316 0.821561 + outer loop + vertex 0.845497 1.36234 2.59748 + vertex 0.847776 1.36601 2.59942 + vertex 0.84463 1.36757 2.59743 + endloop + endfacet + facet normal -0.562884 -0.0831374 0.822344 + outer loop + vertex 0.847776 1.36601 2.59942 + vertex 0.848612 1.36182 2.59957 + vertex 0.850859 1.36409 2.60134 + endloop + endfacet + facet normal -0.56165 -0.0800129 0.823497 + outer loop + vertex 0.850235 1.36896 2.60139 + vertex 0.847776 1.36601 2.59942 + vertex 0.850859 1.36409 2.60134 + endloop + endfacet + facet normal -0.556043 -0.0793335 0.827359 + outer loop + vertex 0.850859 1.36409 2.60134 + vertex 0.853493 1.36692 2.60338 + vertex 0.850235 1.36896 2.60139 + endloop + endfacet + facet normal -0.557776 -0.0770413 0.826408 + outer loop + vertex 0.854002 1.36178 2.60324 + vertex 0.853493 1.36692 2.60338 + vertex 0.850859 1.36409 2.60134 + endloop + endfacet + facet normal -0.559698 -0.0810587 0.824723 + outer loop + vertex 0.851169 1.35926 2.60107 + vertex 0.854002 1.36178 2.60324 + vertex 0.850859 1.36409 2.60134 + endloop + endfacet + facet normal -0.558676 -0.0836032 0.825162 + outer loop + vertex 0.846903 1.37129 2.59936 + vertex 0.847776 1.36601 2.59942 + vertex 0.850235 1.36896 2.60139 + endloop + endfacet + facet normal -0.556823 -0.079515 0.826816 + outer loop + vertex 0.84965 1.37311 2.60139 + vertex 0.846903 1.37129 2.59936 + vertex 0.850235 1.36896 2.60139 + endloop + endfacet + facet normal -0.551435 -0.0787603 0.830491 + outer loop + vertex 0.850235 1.36896 2.60139 + vertex 0.852866 1.3725 2.60347 + vertex 0.84965 1.37311 2.60139 + endloop + endfacet + facet normal -0.55117 -0.0758326 0.83094 + outer loop + vertex 0.84965 1.37311 2.60139 + vertex 0.852866 1.3725 2.60347 + vertex 0.850597 1.37735 2.60241 + endloop + endfacet + facet normal -0.546672 -0.0730218 0.834157 + outer loop + vertex 0.852866 1.3725 2.60347 + vertex 0.85375 1.37691 2.60443 + vertex 0.850597 1.37735 2.60241 + endloop + endfacet + facet normal -0.546445 -0.0691794 0.834633 + outer loop + vertex 0.85375 1.37691 2.60443 + vertex 0.853114 1.38101 2.60436 + vertex 0.850597 1.37735 2.60241 + endloop + endfacet + facet normal -0.555621 -0.0819597 0.827386 + outer loop + vertex 0.846903 1.37129 2.59936 + vertex 0.84965 1.37311 2.60139 + vertex 0.847772 1.37551 2.60037 + endloop + endfacet + facet normal -0.564267 -0.0811806 0.821591 + outer loop + vertex 0.850859 1.36409 2.60134 + vertex 0.848612 1.36182 2.59957 + vertex 0.851169 1.35926 2.60107 + endloop + endfacet + facet normal -0.566066 -0.083866 0.820083 + outer loop + vertex 0.848612 1.36182 2.59957 + vertex 0.847824 1.35742 2.59858 + vertex 0.851169 1.35926 2.60107 + endloop + endfacet + facet normal -0.566624 -0.0825146 0.819834 + outer loop + vertex 0.851169 1.35926 2.60107 + vertex 0.847824 1.35742 2.59858 + vertex 0.851223 1.35436 2.60062 + endloop + endfacet + facet normal -0.561912 -0.0827603 0.823046 + outer loop + vertex 0.851223 1.35436 2.60062 + vertex 0.854588 1.35628 2.60311 + vertex 0.851169 1.35926 2.60107 + endloop + endfacet + facet normal -0.56034 -0.0800459 0.824386 + outer loop + vertex 0.854588 1.35628 2.60311 + vertex 0.854002 1.36178 2.60324 + vertex 0.851169 1.35926 2.60107 + endloop + endfacet + facet normal -0.562842 -0.0805818 0.822627 + outer loop + vertex 0.853795 1.35186 2.60213 + vertex 0.854588 1.35628 2.60311 + vertex 0.851223 1.35436 2.60062 + endloop + endfacet + facet normal -0.565438 -0.0845754 0.820443 + outer loop + vertex 0.851551 1.34954 2.60035 + vertex 0.853795 1.35186 2.60213 + vertex 0.851223 1.35436 2.60062 + endloop + endfacet + facet normal -0.568648 -0.0846673 0.818212 + outer loop + vertex 0.851223 1.35436 2.60062 + vertex 0.848441 1.35188 2.59843 + vertex 0.851551 1.34954 2.60035 + endloop + endfacet + facet normal -0.569991 -0.0874613 0.816982 + outer loop + vertex 0.848441 1.35188 2.59843 + vertex 0.848981 1.34678 2.59826 + vertex 0.851551 1.34954 2.60035 + endloop + endfacet + facet normal -0.569928 -0.0875468 0.817017 + outer loop + vertex 0.851551 1.34954 2.60035 + vertex 0.848981 1.34678 2.59826 + vertex 0.852206 1.34469 2.60028 + endloop + endfacet + facet normal -0.564126 -0.0868155 0.821112 + outer loop + vertex 0.852206 1.34469 2.60028 + vertex 0.854662 1.34768 2.60229 + vertex 0.851551 1.34954 2.60035 + endloop + endfacet + facet normal -0.562934 -0.0882401 0.821778 + outer loop + vertex 0.85558 1.34239 2.60235 + vertex 0.854662 1.34768 2.60229 + vertex 0.852206 1.34469 2.60028 + endloop + endfacet + facet normal -0.562835 -0.0880115 0.82187 + outer loop + vertex 0.852865 1.34057 2.60029 + vertex 0.85558 1.34239 2.60235 + vertex 0.852206 1.34469 2.60028 + endloop + endfacet + facet normal -0.572342 -0.0895459 0.815111 + outer loop + vertex 0.852865 1.34057 2.60029 + vertex 0.852206 1.34469 2.60028 + vertex 0.849683 1.34123 2.59813 + endloop + endfacet + facet normal -0.572671 -0.093182 0.814472 + outer loop + vertex 0.852865 1.34057 2.60029 + vertex 0.849683 1.34123 2.59813 + vertex 0.852189 1.3364 2.59934 + endloop + endfacet + facet normal -0.568047 -0.094632 0.817537 + outer loop + vertex 0.852189 1.3364 2.59934 + vertex 0.8548 1.33819 2.60136 + vertex 0.852865 1.34057 2.60029 + endloop + endfacet + facet normal -0.567365 -0.0959811 0.817854 + outer loop + vertex 0.8548 1.33819 2.60136 + vertex 0.852189 1.3364 2.59934 + vertex 0.855503 1.33418 2.60138 + endloop + endfacet + facet normal -0.553781 -0.0935673 0.827388 + outer loop + vertex 0.855503 1.33418 2.60138 + vertex 0.858012 1.33758 2.60344 + vertex 0.8548 1.33819 2.60136 + endloop + endfacet + facet normal -0.553597 -0.0913421 0.82776 + outer loop + vertex 0.8548 1.33819 2.60136 + vertex 0.858012 1.33758 2.60344 + vertex 0.85558 1.34239 2.60235 + endloop + endfacet + facet normal -0.552745 -0.094675 0.827955 + outer loop + vertex 0.858797 1.33198 2.60333 + vertex 0.858012 1.33758 2.60344 + vertex 0.855503 1.33418 2.60138 + endloop + endfacet + facet normal -0.553624 -0.0967242 0.82713 + outer loop + vertex 0.856018 1.32931 2.60116 + vertex 0.858797 1.33198 2.60333 + vertex 0.855503 1.33418 2.60138 + endloop + endfacet + facet normal -0.564738 -0.0975493 0.819485 + outer loop + vertex 0.855503 1.33418 2.60138 + vertex 0.853331 1.33186 2.59961 + vertex 0.856018 1.32931 2.60116 + endloop + endfacet + facet normal -0.567245 -0.101536 0.817266 + outer loop + vertex 0.853331 1.33186 2.59961 + vertex 0.852764 1.32738 2.59866 + vertex 0.856018 1.32931 2.60116 + endloop + endfacet + facet normal -0.568792 -0.0980788 0.816613 + outer loop + vertex 0.856018 1.32931 2.60116 + vertex 0.852764 1.32738 2.59866 + vertex 0.856206 1.32437 2.60069 + endloop + endfacet + facet normal -0.553882 -0.0984602 0.826753 + outer loop + vertex 0.856206 1.32437 2.60069 + vertex 0.859547 1.32634 2.60317 + vertex 0.856018 1.32931 2.60116 + endloop + endfacet + facet normal -0.555336 -0.0952435 0.826154 + outer loop + vertex 0.858807 1.32191 2.60216 + vertex 0.859547 1.32634 2.60317 + vertex 0.856206 1.32437 2.60069 + endloop + endfacet + facet normal -0.558525 -0.100243 0.823408 + outer loop + vertex 0.856585 1.3196 2.60037 + vertex 0.858807 1.32191 2.60216 + vertex 0.856206 1.32437 2.60069 + endloop + endfacet + facet normal -0.569437 -0.100594 0.815857 + outer loop + vertex 0.856206 1.32437 2.60069 + vertex 0.853482 1.32191 2.59849 + vertex 0.856585 1.3196 2.60037 + endloop + endfacet + facet normal -0.555474 -0.104371 0.824958 + outer loop + vertex 0.859709 1.31779 2.60224 + vertex 0.858807 1.32191 2.60216 + vertex 0.856585 1.3196 2.60037 + endloop + endfacet + facet normal -0.55551 -0.104472 0.82492 + outer loop + vertex 0.857278 1.31484 2.60023 + vertex 0.859709 1.31779 2.60224 + vertex 0.856585 1.3196 2.60037 + endloop + endfacet + facet normal -0.569399 -0.106217 0.81517 + outer loop + vertex 0.856585 1.3196 2.60037 + vertex 0.854039 1.31688 2.59824 + vertex 0.857278 1.31484 2.60023 + endloop + endfacet + facet normal -0.569841 -0.107369 0.814711 + outer loop + vertex 0.854039 1.31688 2.59824 + vertex 0.854804 1.31139 2.59805 + vertex 0.857278 1.31484 2.60023 + endloop + endfacet + facet normal -0.581795 -0.108739 0.806033 + outer loop + vertex 0.854804 1.31139 2.59805 + vertex 0.854039 1.31688 2.59824 + vertex 0.851261 1.31434 2.59589 + endloop + endfacet + facet normal -0.581602 -0.108367 0.806223 + outer loop + vertex 0.851651 1.30932 2.5955 + vertex 0.854804 1.31139 2.59805 + vertex 0.851261 1.31434 2.59589 + endloop + endfacet + facet normal -0.591975 -0.108578 0.798609 + outer loop + vertex 0.851261 1.31434 2.59589 + vertex 0.848496 1.31189 2.59351 + vertex 0.851651 1.30932 2.5955 + endloop + endfacet + facet normal -0.591662 -0.109089 0.798771 + outer loop + vertex 0.84775 1.31739 2.5937 + vertex 0.848496 1.31189 2.59351 + vertex 0.851261 1.31434 2.59589 + endloop + endfacet + facet normal -0.590989 -0.107839 0.799439 + outer loop + vertex 0.850869 1.31937 2.59628 + vertex 0.84775 1.31739 2.5937 + vertex 0.851261 1.31434 2.59589 + endloop + endfacet + facet normal -0.582483 -0.107661 0.805681 + outer loop + vertex 0.851261 1.31434 2.59589 + vertex 0.854039 1.31688 2.59824 + vertex 0.850869 1.31937 2.59628 + endloop + endfacet + facet normal -0.581059 -0.104747 0.807092 + outer loop + vertex 0.854039 1.31688 2.59824 + vertex 0.853482 1.32191 2.59849 + vertex 0.850869 1.31937 2.59628 + endloop + endfacet + facet normal -0.581227 -0.104498 0.807004 + outer loop + vertex 0.850869 1.31937 2.59628 + vertex 0.853482 1.32191 2.59849 + vertex 0.850377 1.32413 2.59654 + endloop + endfacet + facet normal -0.58752 -0.104895 0.802382 + outer loop + vertex 0.850377 1.32413 2.59654 + vertex 0.848285 1.32186 2.59471 + vertex 0.850869 1.31937 2.59628 + endloop + endfacet + facet normal -0.579706 -0.101021 0.808539 + outer loop + vertex 0.853482 1.32191 2.59849 + vertex 0.852764 1.32738 2.59866 + vertex 0.850377 1.32413 2.59654 + endloop + endfacet + facet normal -0.579054 -0.101746 0.808915 + outer loop + vertex 0.850377 1.32413 2.59654 + vertex 0.852764 1.32738 2.59866 + vertex 0.849656 1.32809 2.59652 + endloop + endfacet + facet normal -0.585888 -0.103013 0.803818 + outer loop + vertex 0.849656 1.32809 2.59652 + vertex 0.847144 1.32636 2.59447 + vertex 0.850377 1.32413 2.59654 + endloop + endfacet + facet normal -0.585167 -0.10446 0.804157 + outer loop + vertex 0.847144 1.32636 2.59447 + vertex 0.849656 1.32809 2.59652 + vertex 0.847717 1.33045 2.59542 + endloop + endfacet + facet normal -0.584229 -0.10474 0.804802 + outer loop + vertex 0.847717 1.33045 2.59542 + vertex 0.844584 1.33119 2.59324 + vertex 0.847144 1.32636 2.59447 + endloop + endfacet + facet normal -0.584012 -0.102503 0.805247 + outer loop + vertex 0.847717 1.33045 2.59542 + vertex 0.846946 1.33444 2.59537 + vertex 0.844584 1.33119 2.59324 + endloop + endfacet + facet normal -0.581432 -0.105362 0.806744 + outer loop + vertex 0.843713 1.33681 2.59334 + vertex 0.844584 1.33119 2.59324 + vertex 0.846946 1.33444 2.59537 + endloop + endfacet + facet normal -0.579196 -0.100407 0.808981 + outer loop + vertex 0.846405 1.33931 2.59558 + vertex 0.843713 1.33681 2.59334 + vertex 0.846946 1.33444 2.59537 + endloop + endfacet + facet normal -0.57898 -0.10039 0.809138 + outer loop + vertex 0.846946 1.33444 2.59537 + vertex 0.849074 1.33671 2.59717 + vertex 0.846405 1.33931 2.59558 + endloop + endfacet + facet normal -0.575739 -0.095279 0.812063 + outer loop + vertex 0.849074 1.33671 2.59717 + vertex 0.849683 1.34123 2.59813 + vertex 0.846405 1.33931 2.59558 + endloop + endfacet + facet normal -0.575249 -0.0963961 0.812278 + outer loop + vertex 0.846405 1.33931 2.59558 + vertex 0.849683 1.34123 2.59813 + vertex 0.84622 1.34428 2.59604 + endloop + endfacet + facet normal -0.57401 -0.0964308 0.81315 + outer loop + vertex 0.84622 1.34428 2.59604 + vertex 0.842914 1.34244 2.59349 + vertex 0.846405 1.33931 2.59558 + endloop + endfacet + facet normal -0.573405 -0.097872 0.813405 + outer loop + vertex 0.843618 1.34688 2.59452 + vertex 0.842914 1.34244 2.59349 + vertex 0.84622 1.34428 2.59604 + endloop + endfacet + facet normal -0.569514 -0.091959 0.816822 + outer loop + vertex 0.845858 1.34916 2.59634 + vertex 0.843618 1.34688 2.59452 + vertex 0.84622 1.34428 2.59604 + endloop + endfacet + facet normal -0.571361 -0.0920173 0.815524 + outer loop + vertex 0.84622 1.34428 2.59604 + vertex 0.848981 1.34678 2.59826 + vertex 0.845858 1.34916 2.59634 + endloop + endfacet + facet normal -0.56957 -0.0918794 0.816791 + outer loop + vertex 0.842765 1.3511 2.5944 + vertex 0.843618 1.34688 2.59452 + vertex 0.845858 1.34916 2.59634 + endloop + endfacet + facet normal -0.568054 -0.0879929 0.818274 + outer loop + vertex 0.845232 1.35404 2.59643 + vertex 0.842765 1.3511 2.5944 + vertex 0.845858 1.34916 2.59634 + endloop + endfacet + facet normal -0.56863 -0.0880593 0.817867 + outer loop + vertex 0.845858 1.34916 2.59634 + vertex 0.848441 1.35188 2.59843 + vertex 0.845232 1.35404 2.59643 + endloop + endfacet + facet normal -0.574416 -0.0929557 0.813268 + outer loop + vertex 0.843618 1.34688 2.59452 + vertex 0.842765 1.3511 2.5944 + vertex 0.840488 1.3474 2.59237 + endloop + endfacet + facet normal -0.574715 -0.0926741 0.813089 + outer loop + vertex 0.840488 1.3474 2.59237 + vertex 0.842765 1.3511 2.5944 + vertex 0.839631 1.35264 2.59236 + endloop + endfacet + facet normal -0.573421 -0.0881661 0.814503 + outer loop + vertex 0.842765 1.3511 2.5944 + vertex 0.84193 1.35638 2.59438 + vertex 0.839631 1.35264 2.59236 + endloop + endfacet + facet normal -0.575573 -0.0861389 0.813201 + outer loop + vertex 0.839631 1.35264 2.59236 + vertex 0.84193 1.35638 2.59438 + vertex 0.83887 1.35673 2.59225 + endloop + endfacet + facet normal -0.574678 -0.0974723 0.812554 + outer loop + vertex 0.842914 1.34244 2.59349 + vertex 0.843618 1.34688 2.59452 + vertex 0.840488 1.3474 2.59237 + endloop + endfacet + facet normal -0.579058 -0.100403 0.80908 + outer loop + vertex 0.839739 1.34326 2.59132 + vertex 0.842914 1.34244 2.59349 + vertex 0.840488 1.3474 2.59237 + endloop + endfacet + facet normal -0.588057 -0.0972184 0.802956 + outer loop + vertex 0.839739 1.34326 2.59132 + vertex 0.840488 1.3474 2.59237 + vertex 0.837852 1.34565 2.59023 + endloop + endfacet + facet normal -0.57958 -0.104945 0.80813 + outer loop + vertex 0.840469 1.33923 2.59132 + vertex 0.842914 1.34244 2.59349 + vertex 0.839739 1.34326 2.59132 + endloop + endfacet + facet normal -0.581118 -0.103182 0.807252 + outer loop + vertex 0.843713 1.33681 2.59334 + vertex 0.842914 1.34244 2.59349 + vertex 0.840469 1.33923 2.59132 + endloop + endfacet + facet normal -0.583274 -0.107893 0.805078 + outer loop + vertex 0.841067 1.33434 2.5911 + vertex 0.843713 1.33681 2.59334 + vertex 0.840469 1.33923 2.59132 + endloop + endfacet + facet normal -0.591014 -0.108577 0.799321 + outer loop + vertex 0.840469 1.33923 2.59132 + vertex 0.838383 1.33703 2.58948 + vertex 0.841067 1.33434 2.5911 + endloop + endfacet + facet normal -0.572098 -0.0908606 0.815137 + outer loop + vertex 0.849683 1.34123 2.59813 + vertex 0.848981 1.34678 2.59826 + vertex 0.84622 1.34428 2.59604 + endloop + endfacet + facet normal -0.58 -0.0989878 0.80858 + outer loop + vertex 0.850235 1.33218 2.59745 + vertex 0.849074 1.33671 2.59717 + vertex 0.846946 1.33444 2.59537 + endloop + endfacet + facet normal -0.575665 -0.0976745 0.811831 + outer loop + vertex 0.850235 1.33218 2.59745 + vertex 0.852189 1.3364 2.59934 + vertex 0.849074 1.33671 2.59717 + endloop + endfacet + facet normal -0.575999 -0.0974265 0.811624 + outer loop + vertex 0.853331 1.33186 2.59961 + vertex 0.852189 1.3364 2.59934 + vertex 0.850235 1.33218 2.59745 + endloop + endfacet + facet normal -0.576022 -0.0991795 0.811395 + outer loop + vertex 0.852764 1.32738 2.59866 + vertex 0.853331 1.33186 2.59961 + vertex 0.850235 1.33218 2.59745 + endloop + endfacet + facet normal -0.577674 -0.102758 0.809774 + outer loop + vertex 0.842914 1.34244 2.59349 + vertex 0.843713 1.33681 2.59334 + vertex 0.846405 1.33931 2.59558 + endloop + endfacet + facet normal -0.584621 -0.105812 0.804377 + outer loop + vertex 0.844584 1.33119 2.59324 + vertex 0.843713 1.33681 2.59334 + vertex 0.841067 1.33434 2.5911 + endloop + endfacet + facet normal -0.586884 -0.109831 0.802187 + outer loop + vertex 0.841419 1.32933 2.59067 + vertex 0.844584 1.33119 2.59324 + vertex 0.841067 1.33434 2.5911 + endloop + endfacet + facet normal -0.594353 -0.109884 0.796662 + outer loop + vertex 0.841067 1.33434 2.5911 + vertex 0.837923 1.33259 2.58851 + vertex 0.841419 1.32933 2.59067 + endloop + endfacet + facet normal -0.587811 -0.107714 0.801796 + outer loop + vertex 0.844088 1.32669 2.59227 + vertex 0.844584 1.33119 2.59324 + vertex 0.841419 1.32933 2.59067 + endloop + endfacet + facet normal -0.581231 -0.101938 0.807328 + outer loop + vertex 0.847717 1.33045 2.59542 + vertex 0.850235 1.33218 2.59745 + vertex 0.846946 1.33444 2.59537 + endloop + endfacet + facet normal -0.581951 -0.100494 0.806991 + outer loop + vertex 0.849656 1.32809 2.59652 + vertex 0.850235 1.33218 2.59745 + vertex 0.847717 1.33045 2.59542 + endloop + endfacet + facet normal -0.579017 -0.101362 0.80899 + outer loop + vertex 0.849656 1.32809 2.59652 + vertex 0.852764 1.32738 2.59866 + vertex 0.850235 1.33218 2.59745 + endloop + endfacet + facet normal -0.571042 -0.104002 0.814306 + outer loop + vertex 0.853482 1.32191 2.59849 + vertex 0.854039 1.31688 2.59824 + vertex 0.856585 1.3196 2.60037 + endloop + endfacet + facet normal -0.553485 -0.106857 0.825975 + outer loop + vertex 0.860695 1.31259 2.60223 + vertex 0.859709 1.31779 2.60224 + vertex 0.857278 1.31484 2.60023 + endloop + endfacet + facet normal -0.542731 -0.101395 0.833764 + outer loop + vertex 0.859709 1.31779 2.60224 + vertex 0.862022 1.3215 2.6042 + vertex 0.858807 1.32191 2.60216 + endloop + endfacet + facet normal -0.540894 -0.103064 0.834752 + outer loop + vertex 0.862979 1.31627 2.60418 + vertex 0.862022 1.3215 2.6042 + vertex 0.859709 1.31779 2.60224 + endloop + endfacet + facet normal -0.569852 -0.0999465 0.815647 + outer loop + vertex 0.852764 1.32738 2.59866 + vertex 0.853482 1.32191 2.59849 + vertex 0.856206 1.32437 2.60069 + endloop + endfacet + facet normal -0.566838 -0.0947247 0.818366 + outer loop + vertex 0.852189 1.3364 2.59934 + vertex 0.853331 1.33186 2.59961 + vertex 0.855503 1.33418 2.60138 + endloop + endfacet + facet normal -0.57564 -0.0953065 0.81213 + outer loop + vertex 0.852189 1.3364 2.59934 + vertex 0.849683 1.34123 2.59813 + vertex 0.849074 1.33671 2.59717 + endloop + endfacet + facet normal -0.562697 -0.0882885 0.821935 + outer loop + vertex 0.8548 1.33819 2.60136 + vertex 0.85558 1.34239 2.60235 + vertex 0.852865 1.34057 2.60029 + endloop + endfacet + facet normal -0.552797 -0.0864021 0.828825 + outer loop + vertex 0.85558 1.34239 2.60235 + vertex 0.857902 1.34613 2.60429 + vertex 0.854662 1.34768 2.60229 + endloop + endfacet + facet normal -0.551222 -0.0878474 0.829721 + outer loop + vertex 0.858738 1.34198 2.6044 + vertex 0.857902 1.34613 2.60429 + vertex 0.85558 1.34239 2.60235 + endloop + endfacet + facet normal -0.571225 -0.0907645 0.81576 + outer loop + vertex 0.848981 1.34678 2.59826 + vertex 0.849683 1.34123 2.59813 + vertex 0.852206 1.34469 2.60028 + endloop + endfacet + facet normal -0.569119 -0.0873891 0.817598 + outer loop + vertex 0.848981 1.34678 2.59826 + vertex 0.848441 1.35188 2.59843 + vertex 0.845858 1.34916 2.59634 + endloop + endfacet + facet normal -0.564022 -0.0865359 0.821213 + outer loop + vertex 0.854662 1.34768 2.60229 + vertex 0.853795 1.35186 2.60213 + vertex 0.851551 1.34954 2.60035 + endloop + endfacet + facet normal -0.554429 -0.0842962 0.827951 + outer loop + vertex 0.854662 1.34768 2.60229 + vertex 0.856984 1.35142 2.60422 + vertex 0.853795 1.35186 2.60213 + endloop + endfacet + facet normal -0.568261 -0.0852817 0.818417 + outer loop + vertex 0.847824 1.35742 2.59858 + vertex 0.848441 1.35188 2.59843 + vertex 0.851223 1.35436 2.60062 + endloop + endfacet + facet normal -0.567419 -0.085204 0.819009 + outer loop + vertex 0.848441 1.35188 2.59843 + vertex 0.847824 1.35742 2.59858 + vertex 0.845232 1.35404 2.59643 + endloop + endfacet + facet normal -0.568548 -0.0873848 0.817995 + outer loop + vertex 0.84193 1.35638 2.59438 + vertex 0.842765 1.3511 2.5944 + vertex 0.845232 1.35404 2.59643 + endloop + endfacet + facet normal -0.57546 -0.0821828 0.81369 + outer loop + vertex 0.84193 1.35638 2.59438 + vertex 0.839671 1.36114 2.59327 + vertex 0.83887 1.35673 2.59225 + endloop + endfacet + facet normal -0.58391 -0.0836181 0.807501 + outer loop + vertex 0.838467 1.37182 2.59349 + vertex 0.839028 1.36666 2.59336 + vertex 0.841577 1.36941 2.59549 + endloop + endfacet + facet normal -0.584827 -0.0855178 0.806638 + outer loop + vertex 0.841228 1.37423 2.59575 + vertex 0.838467 1.37182 2.59349 + vertex 0.841577 1.36941 2.59549 + endloop + endfacet + facet normal -0.586652 -0.0824819 0.805628 + outer loop + vertex 0.837839 1.37741 2.59361 + vertex 0.838467 1.37182 2.59349 + vertex 0.841228 1.37423 2.59575 + endloop + endfacet + facet normal -0.568873 -0.0865311 0.817861 + outer loop + vertex 0.845497 1.36234 2.59748 + vertex 0.84463 1.36757 2.59743 + vertex 0.842215 1.36463 2.59543 + endloop + endfacet + facet normal -0.567712 -0.0838978 0.818941 + outer loop + vertex 0.842794 1.36057 2.59542 + vertex 0.845497 1.36234 2.59748 + vertex 0.842215 1.36463 2.59543 + endloop + endfacet + facet normal -0.567399 -0.0845498 0.819091 + outer loop + vertex 0.844648 1.35819 2.59646 + vertex 0.845497 1.36234 2.59748 + vertex 0.842794 1.36057 2.59542 + endloop + endfacet + facet normal -0.572492 -0.0851006 0.815482 + outer loop + vertex 0.841577 1.36941 2.59549 + vertex 0.843784 1.37172 2.59728 + vertex 0.841228 1.37423 2.59575 + endloop + endfacet + facet normal -0.563284 -0.0844005 0.821942 + outer loop + vertex 0.847776 1.36601 2.59942 + vertex 0.846903 1.37129 2.59936 + vertex 0.84463 1.36757 2.59743 + endloop + endfacet + facet normal -0.60401 -0.0769571 0.793253 + outer loop + vertex 0.837839 1.37741 2.59361 + vertex 0.838582 1.38178 2.5946 + vertex 0.835547 1.38242 2.59235 + endloop + endfacet + facet normal -0.603624 -0.0767008 0.793571 + outer loop + vertex 0.834812 1.37843 2.5914 + vertex 0.837839 1.37741 2.59361 + vertex 0.835547 1.38242 2.59235 + endloop + endfacet + facet normal -0.617899 -0.0715627 0.782994 + outer loop + vertex 0.834812 1.37843 2.5914 + vertex 0.835547 1.38242 2.59235 + vertex 0.833053 1.38085 2.59024 + endloop + endfacet + facet normal -0.624587 -0.0793534 0.776913 + outer loop + vertex 0.832563 1.37727 2.58948 + vertex 0.834812 1.37843 2.5914 + vertex 0.833053 1.38085 2.59024 + endloop + endfacet + facet normal -0.634462 -0.0763578 0.769173 + outer loop + vertex 0.833053 1.38085 2.59024 + vertex 0.830189 1.38136 2.58792 + vertex 0.832563 1.37727 2.58948 + endloop + endfacet + facet normal -0.634116 -0.0706319 0.770005 + outer loop + vertex 0.833053 1.38085 2.59024 + vertex 0.832426 1.38477 2.59008 + vertex 0.830189 1.38136 2.58792 + endloop + endfacet + facet normal -0.634261 -0.070471 0.769901 + outer loop + vertex 0.829481 1.38675 2.58783 + vertex 0.830189 1.38136 2.58792 + vertex 0.832426 1.38477 2.59008 + endloop + endfacet + facet normal -0.633121 -0.0673991 0.771113 + outer loop + vertex 0.831881 1.38948 2.59004 + vertex 0.829481 1.38675 2.58783 + vertex 0.832426 1.38477 2.59008 + endloop + endfacet + facet normal -0.622674 -0.0661231 0.779682 + outer loop + vertex 0.832426 1.38477 2.59008 + vertex 0.834718 1.38768 2.59216 + vertex 0.831881 1.38948 2.59004 + endloop + endfacet + facet normal -0.62262 -0.0659721 0.779738 + outer loop + vertex 0.834718 1.38768 2.59216 + vertex 0.833989 1.39181 2.59192 + vertex 0.831881 1.38948 2.59004 + endloop + endfacet + facet normal -0.623588 -0.0645639 0.779083 + outer loop + vertex 0.831881 1.38948 2.59004 + vertex 0.833989 1.39181 2.59192 + vertex 0.831716 1.3941 2.59029 + endloop + endfacet + facet normal -0.631954 -0.0644965 0.772317 + outer loop + vertex 0.831716 1.3941 2.59029 + vertex 0.829127 1.39165 2.58797 + vertex 0.831881 1.38948 2.59004 + endloop + endfacet + facet normal -0.6312 -0.0657745 0.772826 + outer loop + vertex 0.828933 1.39647 2.58822 + vertex 0.829127 1.39165 2.58797 + vertex 0.831716 1.3941 2.59029 + endloop + endfacet + facet normal -0.630158 -0.0636541 0.773853 + outer loop + vertex 0.831645 1.39893 2.59063 + vertex 0.828933 1.39647 2.58822 + vertex 0.831716 1.3941 2.59029 + endloop + endfacet + facet normal -0.619194 -0.0641112 0.782617 + outer loop + vertex 0.831716 1.3941 2.59029 + vertex 0.834811 1.39621 2.59292 + vertex 0.831645 1.39893 2.59063 + endloop + endfacet + facet normal -0.618259 -0.0622821 0.783503 + outer loop + vertex 0.834811 1.39621 2.59292 + vertex 0.834366 1.40167 2.593 + vertex 0.831645 1.39893 2.59063 + endloop + endfacet + facet normal -0.618741 -0.0615257 0.783182 + outer loop + vertex 0.831645 1.39893 2.59063 + vertex 0.834366 1.40167 2.593 + vertex 0.8314 1.40391 2.59083 + endloop + endfacet + facet normal -0.628704 -0.061698 0.775193 + outer loop + vertex 0.8314 1.40391 2.59083 + vertex 0.828733 1.40137 2.58847 + vertex 0.831645 1.39893 2.59063 + endloop + endfacet + facet normal -0.629578 -0.0602306 0.774599 + outer loop + vertex 0.828485 1.40635 2.58865 + vertex 0.828733 1.40137 2.58847 + vertex 0.8314 1.40391 2.59083 + endloop + endfacet + facet normal -0.627876 -0.0567249 0.776244 + outer loop + vertex 0.83116 1.40888 2.591 + vertex 0.828485 1.40635 2.58865 + vertex 0.8314 1.40391 2.59083 + endloop + endfacet + facet normal -0.61846 -0.0565263 0.783781 + outer loop + vertex 0.8314 1.40391 2.59083 + vertex 0.834084 1.40665 2.59315 + vertex 0.83116 1.40888 2.591 + endloop + endfacet + facet normal -0.617012 -0.0533084 0.785146 + outer loop + vertex 0.834084 1.40665 2.59315 + vertex 0.833855 1.41156 2.5933 + vertex 0.83116 1.40888 2.591 + endloop + endfacet + facet normal -0.618179 -0.0514535 0.784352 + outer loop + vertex 0.83116 1.40888 2.591 + vertex 0.833855 1.41156 2.5933 + vertex 0.83092 1.41393 2.59114 + endloop + endfacet + facet normal -0.627581 -0.0516881 0.776834 + outer loop + vertex 0.83092 1.41393 2.59114 + vertex 0.828235 1.41142 2.58881 + vertex 0.83116 1.40888 2.591 + endloop + endfacet + facet normal -0.628364 -0.050346 0.776288 + outer loop + vertex 0.827947 1.41661 2.58891 + vertex 0.828235 1.41142 2.58881 + vertex 0.83092 1.41393 2.59114 + endloop + endfacet + facet normal -0.627591 -0.0488855 0.777007 + outer loop + vertex 0.830669 1.41912 2.59127 + vertex 0.827947 1.41661 2.58891 + vertex 0.83092 1.41393 2.59114 + endloop + endfacet + facet normal -0.618106 -0.0486064 0.784591 + outer loop + vertex 0.83092 1.41393 2.59114 + vertex 0.833653 1.41649 2.59345 + vertex 0.830669 1.41912 2.59127 + endloop + endfacet + facet normal -0.617642 -0.0477308 0.78501 + outer loop + vertex 0.833653 1.41649 2.59345 + vertex 0.833485 1.42145 2.59362 + vertex 0.830669 1.41912 2.59127 + endloop + endfacet + facet normal -0.617404 -0.0481785 0.78517 + outer loop + vertex 0.830669 1.41912 2.59127 + vertex 0.833485 1.42145 2.59362 + vertex 0.83058 1.42417 2.59151 + endloop + endfacet + facet normal -0.628337 -0.0479596 0.776461 + outer loop + vertex 0.83058 1.42417 2.59151 + vertex 0.827481 1.4223 2.58888 + vertex 0.830669 1.41912 2.59127 + endloop + endfacet + facet normal -0.627393 -0.0503899 0.777071 + outer loop + vertex 0.828268 1.42677 2.58981 + vertex 0.827481 1.4223 2.58888 + vertex 0.83058 1.42417 2.59151 + endloop + endfacet + facet normal -0.625092 -0.0470001 0.779135 + outer loop + vertex 0.830408 1.42895 2.59166 + vertex 0.828268 1.42677 2.58981 + vertex 0.83058 1.42417 2.59151 + endloop + endfacet + facet normal -0.616292 -0.0469061 0.786119 + outer loop + vertex 0.83058 1.42417 2.59151 + vertex 0.833277 1.42643 2.59376 + vertex 0.830408 1.42895 2.59166 + endloop + endfacet + facet normal -0.614518 -0.0435747 0.787698 + outer loop + vertex 0.833277 1.42643 2.59376 + vertex 0.83295 1.4315 2.59378 + vertex 0.830408 1.42895 2.59166 + endloop + endfacet + facet normal -0.615108 -0.0426452 0.787289 + outer loop + vertex 0.830408 1.42895 2.59166 + vertex 0.83295 1.4315 2.59378 + vertex 0.829938 1.4338 2.59155 + endloop + endfacet + facet normal -0.626261 -0.0439216 0.778375 + outer loop + vertex 0.829938 1.4338 2.59155 + vertex 0.827589 1.43097 2.5895 + vertex 0.830408 1.42895 2.59166 + endloop + endfacet + facet normal -0.626868 -0.0430977 0.777932 + outer loop + vertex 0.826909 1.4362 2.58924 + vertex 0.827589 1.43097 2.5895 + vertex 0.829938 1.4338 2.59155 + endloop + endfacet + facet normal -0.636275 -0.0447033 0.770166 + outer loop + vertex 0.827589 1.43097 2.5895 + vertex 0.826909 1.4362 2.58924 + vertex 0.824724 1.43254 2.58723 + endloop + endfacet + facet normal -0.636654 -0.0459534 0.769779 + outer loop + vertex 0.825399 1.4273 2.58747 + vertex 0.827589 1.43097 2.5895 + vertex 0.824724 1.43254 2.58723 + endloop + endfacet + facet normal -0.635887 -0.0467356 0.770365 + outer loop + vertex 0.828268 1.42677 2.58981 + vertex 0.827589 1.43097 2.5895 + vertex 0.825399 1.4273 2.58747 + endloop + endfacet + facet normal -0.613977 -0.0401809 0.788301 + outer loop + vertex 0.83295 1.4315 2.59378 + vertex 0.832479 1.43712 2.5937 + vertex 0.829938 1.4338 2.59155 + endloop + endfacet + facet normal -0.613153 -0.0411922 0.788889 + outer loop + vertex 0.829938 1.4338 2.59155 + vertex 0.832479 1.43712 2.5937 + vertex 0.829469 1.43794 2.5914 + endloop + endfacet + facet normal -0.612819 -0.0389159 0.789264 + outer loop + vertex 0.829469 1.43794 2.5914 + vertex 0.832479 1.43712 2.5937 + vertex 0.830438 1.44213 2.59236 + endloop + endfacet + facet normal -0.621063 -0.0355644 0.782954 + outer loop + vertex 0.829469 1.43794 2.5914 + vertex 0.830438 1.44213 2.59236 + vertex 0.827794 1.44036 2.59018 + endloop + endfacet + facet normal -0.621277 -0.0350647 0.782806 + outer loop + vertex 0.827794 1.44036 2.59018 + vertex 0.830438 1.44213 2.59236 + vertex 0.827434 1.44449 2.59008 + endloop + endfacet + facet normal -0.634291 -0.0364546 0.772235 + outer loop + vertex 0.827794 1.44036 2.59018 + vertex 0.827434 1.44449 2.59008 + vertex 0.824911 1.44096 2.58785 + endloop + endfacet + facet normal -0.621647 -0.0358564 0.782476 + outer loop + vertex 0.830438 1.44213 2.59236 + vertex 0.830002 1.44758 2.59227 + vertex 0.827434 1.44449 2.59008 + endloop + endfacet + facet normal -0.622322 -0.0349474 0.781981 + outer loop + vertex 0.827434 1.44449 2.59008 + vertex 0.830002 1.44758 2.59227 + vertex 0.827151 1.4495 2.59008 + endloop + endfacet + facet normal -0.633517 -0.0355793 0.77291 + outer loop + vertex 0.827151 1.4495 2.59008 + vertex 0.824545 1.44647 2.58781 + vertex 0.827434 1.44449 2.59008 + endloop + endfacet + facet normal -0.633633 -0.0354136 0.772823 + outer loop + vertex 0.824341 1.45154 2.58787 + vertex 0.824545 1.44647 2.58781 + vertex 0.827151 1.4495 2.59008 + endloop + endfacet + facet normal -0.633138 -0.0342309 0.773281 + outer loop + vertex 0.826959 1.45448 2.59015 + vertex 0.824341 1.45154 2.58787 + vertex 0.827151 1.4495 2.59008 + endloop + endfacet + facet normal -0.622398 -0.0339269 0.781965 + outer loop + vertex 0.827151 1.4495 2.59008 + vertex 0.829749 1.45267 2.59229 + vertex 0.826959 1.45448 2.59015 + endloop + endfacet + facet normal -0.622157 -0.0332961 0.782184 + outer loop + vertex 0.829749 1.45267 2.59229 + vertex 0.829472 1.4576 2.59228 + vertex 0.826959 1.45448 2.59015 + endloop + endfacet + facet normal -0.622351 -0.0330404 0.78204 + outer loop + vertex 0.826959 1.45448 2.59015 + vertex 0.829472 1.4576 2.59228 + vertex 0.826774 1.45926 2.5902 + endloop + endfacet + facet normal -0.632285 -0.0333343 0.774018 + outer loop + vertex 0.826774 1.45926 2.5902 + vertex 0.824194 1.45651 2.58798 + vertex 0.826959 1.45448 2.59015 + endloop + endfacet + facet normal -0.632467 -0.0330533 0.773882 + outer loop + vertex 0.824078 1.46143 2.58809 + vertex 0.824194 1.45651 2.58798 + vertex 0.826774 1.45926 2.5902 + endloop + endfacet + facet normal -0.631024 -0.0299991 0.775183 + outer loop + vertex 0.826766 1.46394 2.59038 + vertex 0.824078 1.46143 2.58809 + vertex 0.826774 1.45926 2.5902 + endloop + endfacet + facet normal -0.623363 -0.0302155 0.781348 + outer loop + vertex 0.826774 1.45926 2.5902 + vertex 0.828986 1.46168 2.59206 + vertex 0.826766 1.46394 2.59038 + endloop + endfacet + facet normal -0.619793 -0.0244376 0.784385 + outer loop + vertex 0.828986 1.46168 2.59206 + vertex 0.829892 1.46611 2.59291 + vertex 0.826766 1.46394 2.59038 + endloop + endfacet + facet normal -0.618347 -0.0277216 0.785416 + outer loop + vertex 0.826766 1.46394 2.59038 + vertex 0.829892 1.46611 2.59291 + vertex 0.826763 1.46883 2.59055 + endloop + endfacet + facet normal -0.628659 -0.0274407 0.777197 + outer loop + vertex 0.826763 1.46883 2.59055 + vertex 0.823978 1.46636 2.58821 + vertex 0.826766 1.46394 2.59038 + endloop + endfacet + facet normal -0.628063 -0.0285306 0.777639 + outer loop + vertex 0.823854 1.47131 2.58829 + vertex 0.823978 1.46636 2.58821 + vertex 0.826763 1.46883 2.59055 + endloop + endfacet + facet normal -0.626784 -0.0260126 0.778759 + outer loop + vertex 0.826595 1.47382 2.59058 + vertex 0.823854 1.47131 2.58829 + vertex 0.826763 1.46883 2.59055 + endloop + endfacet + facet normal -0.616845 -0.025725 0.786664 + outer loop + vertex 0.826763 1.46883 2.59055 + vertex 0.829517 1.47155 2.59279 + vertex 0.826595 1.47382 2.59058 + endloop + endfacet + facet normal -0.615506 -0.0228848 0.7878 + outer loop + vertex 0.829517 1.47155 2.59279 + vertex 0.829325 1.47652 2.59279 + vertex 0.826595 1.47382 2.59058 + endloop + endfacet + facet normal -0.615643 -0.0226645 0.787699 + outer loop + vertex 0.826595 1.47382 2.59058 + vertex 0.829325 1.47652 2.59279 + vertex 0.826477 1.47875 2.59063 + endloop + endfacet + facet normal -0.625678 -0.0228219 0.779747 + outer loop + vertex 0.826477 1.47875 2.59063 + vertex 0.823729 1.47627 2.58835 + vertex 0.826595 1.47382 2.59058 + endloop + endfacet + facet normal -0.626608 -0.0211468 0.779048 + outer loop + vertex 0.823642 1.48124 2.58841 + vertex 0.823729 1.47627 2.58835 + vertex 0.826477 1.47875 2.59063 + endloop + endfacet + facet normal -0.625237 -0.0185512 0.780214 + outer loop + vertex 0.826413 1.4837 2.59069 + vertex 0.823642 1.48124 2.58841 + vertex 0.826477 1.47875 2.59063 + endloop + endfacet + facet normal -0.615104 -0.018527 0.788229 + outer loop + vertex 0.826477 1.47875 2.59063 + vertex 0.829242 1.48143 2.59285 + vertex 0.826413 1.4837 2.59069 + endloop + endfacet + facet normal -0.61381 -0.0159035 0.789294 + outer loop + vertex 0.829242 1.48143 2.59285 + vertex 0.829204 1.48639 2.59292 + vertex 0.826413 1.4837 2.59069 + endloop + endfacet + facet normal -0.61481 -0.0142475 0.788547 + outer loop + vertex 0.826413 1.4837 2.59069 + vertex 0.829204 1.48639 2.59292 + vertex 0.826367 1.48869 2.59075 + endloop + endfacet + facet normal -0.625233 -0.0142538 0.780308 + outer loop + vertex 0.826367 1.48869 2.59075 + vertex 0.823583 1.48623 2.58847 + vertex 0.826413 1.4837 2.59069 + endloop + endfacet + facet normal -0.62599 -0.0128578 0.779725 + outer loop + vertex 0.823533 1.49124 2.58851 + vertex 0.823583 1.48623 2.58847 + vertex 0.826367 1.48869 2.59075 + endloop + endfacet + facet normal -0.625033 -0.0110943 0.780519 + outer loop + vertex 0.826322 1.4937 2.59078 + vertex 0.823533 1.49124 2.58851 + vertex 0.826367 1.48869 2.59075 + endloop + endfacet + facet normal -0.614782 -0.0110576 0.788619 + outer loop + vertex 0.826367 1.48869 2.59075 + vertex 0.829167 1.49139 2.59297 + vertex 0.826322 1.4937 2.59078 + endloop + endfacet + facet normal -0.614581 -0.0106562 0.788782 + outer loop + vertex 0.829167 1.49139 2.59297 + vertex 0.829123 1.49639 2.593 + vertex 0.826322 1.4937 2.59078 + endloop + endfacet + facet normal -0.61515 -0.00970742 0.78835 + outer loop + vertex 0.826322 1.4937 2.59078 + vertex 0.829123 1.49639 2.593 + vertex 0.826276 1.4987 2.59081 + endloop + endfacet + facet normal -0.625366 -0.00975751 0.78027 + outer loop + vertex 0.826276 1.4987 2.59081 + vertex 0.823487 1.49623 2.58854 + vertex 0.826322 1.4937 2.59078 + endloop + endfacet + facet normal -0.625929 -0.00871619 0.779831 + outer loop + vertex 0.823447 1.50122 2.58857 + vertex 0.823487 1.49623 2.58854 + vertex 0.826276 1.4987 2.59081 + endloop + endfacet + facet normal -0.625501 -0.0079235 0.780183 + outer loop + vertex 0.826238 1.50369 2.59083 + vertex 0.823447 1.50122 2.58857 + vertex 0.826276 1.4987 2.59081 + endloop + endfacet + facet normal -0.615564 -0.00787792 0.788047 + outer loop + vertex 0.826276 1.4987 2.59081 + vertex 0.82908 1.50139 2.59303 + vertex 0.826238 1.50369 2.59083 + endloop + endfacet + facet normal -0.614793 -0.00633856 0.788663 + outer loop + vertex 0.82908 1.50139 2.59303 + vertex 0.829049 1.50638 2.59304 + vertex 0.826238 1.50369 2.59083 + endloop + endfacet + facet normal -0.615559 -0.00505326 0.788075 + outer loop + vertex 0.826238 1.50369 2.59083 + vertex 0.829049 1.50638 2.59304 + vertex 0.826212 1.50868 2.59084 + endloop + endfacet + facet normal -0.625493 -0.0050866 0.780213 + outer loop + vertex 0.826212 1.50868 2.59084 + vertex 0.823415 1.50621 2.58858 + vertex 0.826238 1.50369 2.59083 + endloop + endfacet + facet normal -0.626263 -0.00651084 0.779584 + outer loop + vertex 0.823415 1.50621 2.58858 + vertex 0.823447 1.50122 2.58857 + vertex 0.826238 1.50369 2.59083 + endloop + endfacet + facet normal -0.613925 -0.0124803 0.789266 + outer loop + vertex 0.829204 1.48639 2.59292 + vertex 0.829167 1.49139 2.59297 + vertex 0.826367 1.48869 2.59075 + endloop + endfacet + facet normal -0.622038 -0.0321746 0.782326 + outer loop + vertex 0.829472 1.4576 2.59228 + vertex 0.828986 1.46168 2.59206 + vertex 0.826774 1.45926 2.5902 + endloop + endfacet + facet normal -0.610531 -0.0303214 0.791411 + outer loop + vertex 0.829472 1.4576 2.59228 + vertex 0.831881 1.46137 2.59428 + vertex 0.828986 1.46168 2.59206 + endloop + endfacet + facet normal -0.609775 -0.0310986 0.791964 + outer loop + vertex 0.832339 1.45594 2.59442 + vertex 0.831881 1.46137 2.59428 + vertex 0.829472 1.4576 2.59228 + endloop + endfacet + facet normal -0.59862 -0.0299386 0.800474 + outer loop + vertex 0.831881 1.46137 2.59428 + vertex 0.832339 1.45594 2.59442 + vertex 0.834981 1.45896 2.59651 + endloop + endfacet + facet normal -0.597831 -0.0310083 0.801022 + outer loop + vertex 0.834981 1.45896 2.59651 + vertex 0.832339 1.45594 2.59442 + vertex 0.835316 1.45384 2.59656 + endloop + endfacet + facet normal -0.587763 -0.0302758 0.808467 + outer loop + vertex 0.835316 1.45384 2.59656 + vertex 0.838108 1.45668 2.5987 + vertex 0.834981 1.45896 2.59651 + endloop + endfacet + facet normal -0.586556 -0.0276964 0.809435 + outer loop + vertex 0.838108 1.45668 2.5987 + vertex 0.837682 1.46234 2.59858 + vertex 0.834981 1.45896 2.59651 + endloop + endfacet + facet normal -0.576749 -0.0268138 0.816481 + outer loop + vertex 0.837682 1.46234 2.59858 + vertex 0.838108 1.45668 2.5987 + vertex 0.841109 1.45913 2.6009 + endloop + endfacet + facet normal -0.57615 -0.025846 0.816935 + outer loop + vertex 0.841025 1.46416 2.601 + vertex 0.837682 1.46234 2.59858 + vertex 0.841109 1.45913 2.6009 + endloop + endfacet + facet normal -0.561735 -0.0258025 0.826915 + outer loop + vertex 0.841109 1.45913 2.6009 + vertex 0.844133 1.46157 2.60303 + vertex 0.841025 1.46416 2.601 + endloop + endfacet + facet normal -0.560967 -0.0244346 0.827477 + outer loop + vertex 0.844133 1.46157 2.60303 + vertex 0.843921 1.46656 2.60303 + vertex 0.841025 1.46416 2.601 + endloop + endfacet + facet normal -0.56139 -0.023701 0.827212 + outer loop + vertex 0.841025 1.46416 2.601 + vertex 0.843921 1.46656 2.60303 + vertex 0.840977 1.46887 2.6011 + endloop + endfacet + facet normal -0.573225 -0.0236436 0.819057 + outer loop + vertex 0.840977 1.46887 2.6011 + vertex 0.838604 1.46672 2.59938 + vertex 0.841025 1.46416 2.601 + endloop + endfacet + facet normal -0.560769 -0.0225278 0.827666 + outer loop + vertex 0.843921 1.46656 2.60303 + vertex 0.843808 1.47147 2.60309 + vertex 0.840977 1.46887 2.6011 + endloop + endfacet + facet normal -0.562003 -0.0205879 0.826879 + outer loop + vertex 0.840977 1.46887 2.6011 + vertex 0.843808 1.47147 2.60309 + vertex 0.840804 1.47367 2.6011 + endloop + endfacet + facet normal -0.541247 -0.0222252 0.84057 + outer loop + vertex 0.843808 1.47147 2.60309 + vertex 0.843921 1.46656 2.60303 + vertex 0.846875 1.46938 2.60501 + endloop + endfacet + facet normal -0.540488 -0.020631 0.841099 + outer loop + vertex 0.846816 1.47436 2.60509 + vertex 0.843808 1.47147 2.60309 + vertex 0.846875 1.46938 2.60501 + endloop + endfacet + facet normal -0.517941 -0.0206069 0.855168 + outer loop + vertex 0.846875 1.46938 2.60501 + vertex 0.849938 1.47251 2.60694 + vertex 0.846816 1.47436 2.60509 + endloop + endfacet + facet normal -0.516846 -0.0180495 0.855888 + outer loop + vertex 0.849938 1.47251 2.60694 + vertex 0.849914 1.47751 2.60703 + vertex 0.846816 1.47436 2.60509 + endloop + endfacet + facet normal -0.517155 -0.0176351 0.85571 + outer loop + vertex 0.846816 1.47436 2.60509 + vertex 0.849914 1.47751 2.60703 + vertex 0.846783 1.47938 2.60518 + endloop + endfacet + facet normal -0.540122 -0.0175486 0.841404 + outer loop + vertex 0.846783 1.47938 2.60518 + vertex 0.843739 1.47646 2.60316 + vertex 0.846816 1.47436 2.60509 + endloop + endfacet + facet normal -0.51559 -0.0140212 0.856721 + outer loop + vertex 0.849914 1.47751 2.60703 + vertex 0.849885 1.48251 2.60709 + vertex 0.846783 1.47938 2.60518 + endloop + endfacet + facet normal -0.515914 -0.0135838 0.856532 + outer loop + vertex 0.846783 1.47938 2.60518 + vertex 0.849885 1.48251 2.60709 + vertex 0.846745 1.4844 2.60523 + endloop + endfacet + facet normal -0.538722 -0.0135985 0.842374 + outer loop + vertex 0.846745 1.4844 2.60523 + vertex 0.843696 1.4815 2.60324 + vertex 0.846783 1.47938 2.60518 + endloop + endfacet + facet normal -0.538919 -0.0133079 0.842252 + outer loop + vertex 0.843658 1.48652 2.60329 + vertex 0.843696 1.4815 2.60324 + vertex 0.846745 1.4844 2.60523 + endloop + endfacet + facet normal -0.537158 -0.00966657 0.843426 + outer loop + vertex 0.846701 1.4894 2.60526 + vertex 0.843658 1.48652 2.60329 + vertex 0.846745 1.4844 2.60523 + endloop + endfacet + facet normal -0.514821 -0.00955136 0.857245 + outer loop + vertex 0.846745 1.4844 2.60523 + vertex 0.849843 1.48751 2.60713 + vertex 0.846701 1.4894 2.60526 + endloop + endfacet + facet normal -0.513794 -0.00721909 0.857883 + outer loop + vertex 0.849843 1.48751 2.60713 + vertex 0.849802 1.49249 2.60715 + vertex 0.846701 1.4894 2.60526 + endloop + endfacet + facet normal -0.513885 -0.00709562 0.85783 + outer loop + vertex 0.846701 1.4894 2.60526 + vertex 0.849802 1.49249 2.60715 + vertex 0.846661 1.49439 2.60528 + endloop + endfacet + facet normal -0.535302 -0.00722052 0.84463 + outer loop + vertex 0.846661 1.49439 2.60528 + vertex 0.843616 1.49152 2.60332 + vertex 0.846701 1.4894 2.60526 + endloop + endfacet + facet normal -0.535186 -0.00739271 0.844702 + outer loop + vertex 0.84358 1.49651 2.60335 + vertex 0.843616 1.49152 2.60332 + vertex 0.846661 1.49439 2.60528 + endloop + endfacet + facet normal -0.534209 -0.00539704 0.845335 + outer loop + vertex 0.846633 1.49938 2.60529 + vertex 0.84358 1.49651 2.60335 + vertex 0.846661 1.49439 2.60528 + endloop + endfacet + facet normal -0.514061 -0.00531837 0.857737 + outer loop + vertex 0.846661 1.49439 2.60528 + vertex 0.84977 1.49748 2.60716 + vertex 0.846633 1.49938 2.60529 + endloop + endfacet + facet normal -0.513833 -0.00480448 0.857877 + outer loop + vertex 0.84977 1.49748 2.60716 + vertex 0.849749 1.50247 2.60718 + vertex 0.846633 1.49938 2.60529 + endloop + endfacet + facet normal -0.514268 -0.00420902 0.857619 + outer loop + vertex 0.846633 1.49938 2.60529 + vertex 0.849749 1.50247 2.60718 + vertex 0.846615 1.50436 2.60531 + endloop + endfacet + facet normal -0.533118 -0.00424402 0.84603 + outer loop + vertex 0.846615 1.50436 2.60531 + vertex 0.843553 1.5015 2.60336 + vertex 0.846633 1.49938 2.60529 + endloop + endfacet + facet normal -0.533568 -0.00357312 0.84575 + outer loop + vertex 0.843539 1.50649 2.60338 + vertex 0.843553 1.5015 2.60336 + vertex 0.846615 1.50436 2.60531 + endloop + endfacet + facet normal -0.532659 -0.00173113 0.846328 + outer loop + vertex 0.84661 1.50936 2.60531 + vertex 0.843539 1.50649 2.60338 + vertex 0.846615 1.50436 2.60531 + endloop + endfacet + facet normal -0.514468 -0.0017275 0.857508 + outer loop + vertex 0.846615 1.50436 2.60531 + vertex 0.849737 1.50746 2.60719 + vertex 0.84661 1.50936 2.60531 + endloop + endfacet + facet normal -0.514149 -0.00101333 0.8577 + outer loop + vertex 0.849737 1.50746 2.60719 + vertex 0.849734 1.51246 2.60719 + vertex 0.84661 1.50936 2.60531 + endloop + endfacet + facet normal -0.514598 -0.000397349 0.857431 + outer loop + vertex 0.84661 1.50936 2.60531 + vertex 0.849734 1.51246 2.60719 + vertex 0.846611 1.51435 2.60532 + endloop + endfacet + facet normal -0.532886 -0.000385559 0.846187 + outer loop + vertex 0.846611 1.51435 2.60532 + vertex 0.843537 1.51148 2.60338 + vertex 0.84661 1.50936 2.60531 + endloop + endfacet + facet normal -0.533857 0.00106919 0.845574 + outer loop + vertex 0.843543 1.51647 2.60338 + vertex 0.843537 1.51148 2.60338 + vertex 0.846611 1.51435 2.60532 + endloop + endfacet + facet normal -0.533919 0.000943299 0.845535 + outer loop + vertex 0.846618 1.51934 2.60532 + vertex 0.843543 1.51647 2.60338 + vertex 0.846611 1.51435 2.60532 + endloop + endfacet + facet normal -0.515364 0.000922212 0.856971 + outer loop + vertex 0.846611 1.51435 2.60532 + vertex 0.849736 1.51745 2.60719 + vertex 0.846618 1.51934 2.60532 + endloop + endfacet + facet normal -0.515829 -0.00011786 0.856692 + outer loop + vertex 0.849736 1.51745 2.60719 + vertex 0.849738 1.52244 2.60719 + vertex 0.846618 1.51934 2.60532 + endloop + endfacet + facet normal -0.516702 0.0010813 0.856165 + outer loop + vertex 0.846618 1.51934 2.60532 + vertex 0.849738 1.52244 2.60719 + vertex 0.846624 1.52433 2.60531 + endloop + endfacet + facet normal -0.535687 0.00110039 0.844416 + outer loop + vertex 0.846624 1.52433 2.60531 + vertex 0.843554 1.52146 2.60337 + vertex 0.846618 1.51934 2.60532 + endloop + endfacet + facet normal -0.537386 0.0036537 0.843328 + outer loop + vertex 0.843567 1.52646 2.60336 + vertex 0.843554 1.52146 2.60337 + vertex 0.846624 1.52433 2.60531 + endloop + endfacet + facet normal -0.538077 0.00225682 0.842893 + outer loop + vertex 0.846632 1.52933 2.6053 + vertex 0.843567 1.52646 2.60336 + vertex 0.846624 1.52433 2.60531 + endloop + endfacet + facet normal -0.519162 0.0022467 0.854673 + outer loop + vertex 0.846624 1.52433 2.60531 + vertex 0.849737 1.52743 2.6072 + vertex 0.846632 1.52933 2.6053 + endloop + endfacet + facet normal -0.519492 0.00150999 0.854474 + outer loop + vertex 0.849737 1.52743 2.6072 + vertex 0.849739 1.53242 2.60719 + vertex 0.846632 1.52933 2.6053 + endloop + endfacet + facet normal -0.522022 0.00499457 0.852917 + outer loop + vertex 0.846632 1.52933 2.6053 + vertex 0.849739 1.53242 2.60719 + vertex 0.846648 1.53432 2.60529 + endloop + endfacet + facet normal -0.540307 0.0050096 0.841453 + outer loop + vertex 0.846648 1.53432 2.60529 + vertex 0.843585 1.53145 2.60334 + vertex 0.846632 1.52933 2.6053 + endloop + endfacet + facet normal -0.542938 0.00899322 0.839724 + outer loop + vertex 0.843617 1.53644 2.6033 + vertex 0.843585 1.53145 2.60334 + vertex 0.846648 1.53432 2.60529 + endloop + endfacet + facet normal -0.542883 0.00910426 0.839759 + outer loop + vertex 0.846681 1.53931 2.60525 + vertex 0.843617 1.53644 2.6033 + vertex 0.846648 1.53432 2.60529 + endloop + endfacet + facet normal -0.52508 0.00906508 0.851004 + outer loop + vertex 0.846648 1.53432 2.60529 + vertex 0.849751 1.53741 2.60717 + vertex 0.846681 1.53931 2.60525 + endloop + endfacet + facet normal -0.52477 0.00975313 0.851188 + outer loop + vertex 0.849751 1.53741 2.60717 + vertex 0.849779 1.54241 2.60713 + vertex 0.846681 1.53931 2.60525 + endloop + endfacet + facet normal -0.527113 0.0130014 0.849695 + outer loop + vertex 0.846681 1.53931 2.60525 + vertex 0.849779 1.54241 2.60713 + vertex 0.846728 1.5443 2.60521 + endloop + endfacet + facet normal -0.545087 0.0130662 0.838278 + outer loop + vertex 0.846728 1.5443 2.60521 + vertex 0.843668 1.54143 2.60326 + vertex 0.846681 1.53931 2.60525 + endloop + endfacet + facet normal -0.546716 0.0155534 0.837174 + outer loop + vertex 0.843728 1.54641 2.60321 + vertex 0.843668 1.54143 2.60326 + vertex 0.846728 1.5443 2.60521 + endloop + endfacet + facet normal -0.546402 0.0161826 0.837367 + outer loop + vertex 0.846787 1.54928 2.60515 + vertex 0.843728 1.54641 2.60321 + vertex 0.846728 1.5443 2.60521 + endloop + endfacet + facet normal -0.528749 0.0161067 0.848625 + outer loop + vertex 0.846728 1.5443 2.60521 + vertex 0.849823 1.5474 2.60707 + vertex 0.846787 1.54928 2.60515 + endloop + endfacet + facet normal -0.528369 0.016944 0.848846 + outer loop + vertex 0.849823 1.5474 2.60707 + vertex 0.849882 1.5524 2.60701 + vertex 0.846787 1.54928 2.60515 + endloop + endfacet + facet normal -0.529009 0.0178296 0.848429 + outer loop + vertex 0.846787 1.54928 2.60515 + vertex 0.849882 1.5524 2.60701 + vertex 0.846859 1.55427 2.60509 + endloop + endfacet + facet normal -0.546702 0.0179521 0.837135 + outer loop + vertex 0.846859 1.55427 2.60509 + vertex 0.843789 1.55139 2.60314 + vertex 0.846787 1.54928 2.60515 + endloop + endfacet + facet normal -0.547178 0.0186782 0.836808 + outer loop + vertex 0.843865 1.55641 2.60308 + vertex 0.843789 1.55139 2.60314 + vertex 0.846859 1.55427 2.60509 + endloop + endfacet + facet normal -0.546318 0.0203737 0.83733 + outer loop + vertex 0.846982 1.55927 2.60505 + vertex 0.843865 1.55641 2.60308 + vertex 0.846859 1.55427 2.60509 + endloop + endfacet + facet normal -0.528563 0.0200299 0.848658 + outer loop + vertex 0.846859 1.55427 2.60509 + vertex 0.849961 1.55739 2.60695 + vertex 0.846982 1.55927 2.60505 + endloop + endfacet + facet normal -0.527825 0.0216226 0.849078 + outer loop + vertex 0.849961 1.55739 2.60695 + vertex 0.850048 1.5623 2.60687 + vertex 0.846982 1.55927 2.60505 + endloop + endfacet + facet normal -0.52751 0.021179 0.849285 + outer loop + vertex 0.846982 1.55927 2.60505 + vertex 0.850048 1.5623 2.60687 + vertex 0.84723 1.56412 2.60508 + endloop + endfacet + facet normal -0.546246 0.0222148 0.83733 + outer loop + vertex 0.84723 1.56412 2.60508 + vertex 0.844063 1.56155 2.60308 + vertex 0.846982 1.55927 2.60505 + endloop + endfacet + facet normal -0.527012 0.022228 0.849567 + outer loop + vertex 0.850048 1.5623 2.60687 + vertex 0.850042 1.56683 2.60675 + vertex 0.84723 1.56412 2.60508 + endloop + endfacet + facet normal -0.526152 0.0209889 0.850132 + outer loop + vertex 0.84723 1.56412 2.60508 + vertex 0.850042 1.56683 2.60675 + vertex 0.847725 1.56788 2.60529 + endloop + endfacet + facet normal -0.54637 0.024386 0.837189 + outer loop + vertex 0.847725 1.56788 2.60529 + vertex 0.844652 1.56717 2.60331 + vertex 0.84723 1.56412 2.60508 + endloop + endfacet + facet normal -0.546752 0.0269401 0.836861 + outer loop + vertex 0.847725 1.56788 2.60529 + vertex 0.847237 1.57119 2.60487 + vertex 0.844652 1.56717 2.60331 + endloop + endfacet + facet normal -0.547654 0.0277582 0.836244 + outer loop + vertex 0.844652 1.56717 2.60331 + vertex 0.847237 1.57119 2.60487 + vertex 0.844287 1.57246 2.60289 + endloop + endfacet + facet normal -0.546845 0.0303244 0.836684 + outer loop + vertex 0.847237 1.57119 2.60487 + vertex 0.847237 1.57567 2.60471 + vertex 0.844287 1.57246 2.60289 + endloop + endfacet + facet normal -0.531071 0.0305226 0.846778 + outer loop + vertex 0.847725 1.56788 2.60529 + vertex 0.849542 1.57015 2.60635 + vertex 0.847237 1.57119 2.60487 + endloop + endfacet + facet normal -0.530461 0.0323134 0.847093 + outer loop + vertex 0.850045 1.57383 2.60652 + vertex 0.847237 1.57119 2.60487 + vertex 0.849542 1.57015 2.60635 + endloop + endfacet + facet normal -0.510417 0.0289975 0.859438 + outer loop + vertex 0.849542 1.57015 2.60635 + vertex 0.852681 1.57091 2.60819 + vertex 0.850045 1.57383 2.60652 + endloop + endfacet + facet normal -0.511395 0.0278079 0.858896 + outer loop + vertex 0.852681 1.57091 2.60819 + vertex 0.853265 1.57637 2.60836 + vertex 0.850045 1.57383 2.60652 + endloop + endfacet + facet normal -0.512222 0.0292452 0.858355 + outer loop + vertex 0.850045 1.57383 2.60652 + vertex 0.853265 1.57637 2.60836 + vertex 0.850302 1.57858 2.60652 + endloop + endfacet + facet normal -0.510138 0.0273084 0.859659 + outer loop + vertex 0.849542 1.57015 2.60635 + vertex 0.850042 1.56683 2.60675 + vertex 0.852681 1.57091 2.60819 + endloop + endfacet + facet normal -0.50743 0.0249629 0.861331 + outer loop + vertex 0.850042 1.56683 2.60675 + vertex 0.853085 1.56567 2.60858 + vertex 0.852681 1.57091 2.60819 + endloop + endfacet + facet normal -0.529398 0.0307272 0.847817 + outer loop + vertex 0.847237 1.57567 2.60471 + vertex 0.847237 1.57119 2.60487 + vertex 0.850045 1.57383 2.60652 + endloop + endfacet + facet normal -0.525151 0.0239566 0.850672 + outer loop + vertex 0.849542 1.57015 2.60635 + vertex 0.847725 1.56788 2.60529 + vertex 0.850042 1.56683 2.60675 + endloop + endfacet + facet normal -0.508135 0.0225625 0.860982 + outer loop + vertex 0.850048 1.5623 2.60687 + vertex 0.853085 1.56567 2.60858 + vertex 0.850042 1.56683 2.60675 + endloop + endfacet + facet normal -0.508479 0.0229794 0.860768 + outer loop + vertex 0.853106 1.56072 2.60872 + vertex 0.853085 1.56567 2.60858 + vertex 0.850048 1.5623 2.60687 + endloop + endfacet + facet normal -0.509077 0.0214556 0.860453 + outer loop + vertex 0.849961 1.55739 2.60695 + vertex 0.853106 1.56072 2.60872 + vertex 0.850048 1.5623 2.60687 + endloop + endfacet + facet normal -0.528223 0.0195583 0.848881 + outer loop + vertex 0.849882 1.5524 2.60701 + vertex 0.849961 1.55739 2.60695 + vertex 0.846859 1.55427 2.60509 + endloop + endfacet + facet normal -0.509338 0.0194124 0.860348 + outer loop + vertex 0.849882 1.5524 2.60701 + vertex 0.853041 1.55573 2.60881 + vertex 0.849961 1.55739 2.60695 + endloop + endfacet + facet normal -0.508368 0.0181685 0.860948 + outer loop + vertex 0.852975 1.55073 2.60887 + vertex 0.853041 1.55573 2.60881 + vertex 0.849882 1.5524 2.60701 + endloop + endfacet + facet normal -0.508901 0.0168603 0.86066 + outer loop + vertex 0.849823 1.5474 2.60707 + vertex 0.852975 1.55073 2.60887 + vertex 0.849882 1.5524 2.60701 + endloop + endfacet + facet normal -0.526881 0.0135158 0.849832 + outer loop + vertex 0.849779 1.54241 2.60713 + vertex 0.849823 1.5474 2.60707 + vertex 0.846728 1.5443 2.60521 + endloop + endfacet + facet normal -0.507712 0.0134707 0.861421 + outer loop + vertex 0.849779 1.54241 2.60713 + vertex 0.852929 1.54573 2.60893 + vertex 0.849823 1.5474 2.60707 + endloop + endfacet + facet normal -0.505774 0.0109921 0.862596 + outer loop + vertex 0.8529 1.54073 2.60898 + vertex 0.852929 1.54573 2.60893 + vertex 0.849779 1.54241 2.60713 + endloop + endfacet + facet normal -0.506281 0.00973538 0.862314 + outer loop + vertex 0.849751 1.53741 2.60717 + vertex 0.8529 1.54073 2.60898 + vertex 0.849779 1.54241 2.60713 + endloop + endfacet + facet normal -0.522066 0.00489629 0.852891 + outer loop + vertex 0.849739 1.53242 2.60719 + vertex 0.849751 1.53741 2.60717 + vertex 0.846648 1.53432 2.60529 + endloop + endfacet + facet normal -0.504099 0.0049002 0.863632 + outer loop + vertex 0.849739 1.53242 2.60719 + vertex 0.852889 1.53574 2.60901 + vertex 0.849751 1.53741 2.60717 + endloop + endfacet + facet normal -0.50192 0.00212846 0.864912 + outer loop + vertex 0.85289 1.53075 2.60902 + vertex 0.852889 1.53574 2.60901 + vertex 0.849739 1.53242 2.60719 + endloop + endfacet + facet normal -0.502163 0.0015189 0.864772 + outer loop + vertex 0.849737 1.52743 2.6072 + vertex 0.85289 1.53075 2.60902 + vertex 0.849739 1.53242 2.60719 + endloop + endfacet + facet normal -0.517315 -0.000293301 0.855795 + outer loop + vertex 0.849738 1.52244 2.60719 + vertex 0.849737 1.52743 2.6072 + vertex 0.846624 1.52433 2.60531 + endloop + endfacet + facet normal -0.500477 -0.00029098 0.86575 + outer loop + vertex 0.849738 1.52244 2.60719 + vertex 0.852897 1.52576 2.60902 + vertex 0.849737 1.52743 2.6072 + endloop + endfacet + facet normal -0.50014 -0.000718387 0.865944 + outer loop + vertex 0.8529 1.52076 2.60902 + vertex 0.852897 1.52576 2.60902 + vertex 0.849738 1.52244 2.60719 + endloop + endfacet + facet normal -0.499906 -0.000127906 0.86608 + outer loop + vertex 0.849736 1.51745 2.60719 + vertex 0.8529 1.52076 2.60902 + vertex 0.849738 1.52244 2.60719 + endloop + endfacet + facet normal -0.514524 -0.00023146 0.857476 + outer loop + vertex 0.849734 1.51246 2.60719 + vertex 0.849736 1.51745 2.60719 + vertex 0.846611 1.51435 2.60532 + endloop + endfacet + facet normal -0.513659 -0.00283499 0.85799 + outer loop + vertex 0.849749 1.50247 2.60718 + vertex 0.849737 1.50746 2.60719 + vertex 0.846615 1.50436 2.60531 + endloop + endfacet + facet normal -0.513461 -0.00613692 0.858091 + outer loop + vertex 0.849802 1.49249 2.60715 + vertex 0.84977 1.49748 2.60716 + vertex 0.846661 1.49439 2.60528 + endloop + endfacet + facet normal -0.5144 -0.010122 0.857491 + outer loop + vertex 0.849885 1.48251 2.60709 + vertex 0.849843 1.48751 2.60713 + vertex 0.846745 1.4844 2.60523 + endloop + endfacet + facet normal -0.517329 -0.0214232 0.855519 + outer loop + vertex 0.850013 1.46752 2.60686 + vertex 0.849938 1.47251 2.60694 + vertex 0.846875 1.46938 2.60501 + endloop + endfacet + facet normal -0.517752 -0.0224196 0.855237 + outer loop + vertex 0.847034 1.46442 2.60497 + vertex 0.850013 1.46752 2.60686 + vertex 0.846875 1.46938 2.60501 + endloop + endfacet + facet normal -0.517148 -0.0232105 0.855581 + outer loop + vertex 0.850245 1.46251 2.60686 + vertex 0.850013 1.46752 2.60686 + vertex 0.847034 1.46442 2.60497 + endloop + endfacet + facet normal -0.516688 -0.0221333 0.855888 + outer loop + vertex 0.847373 1.45948 2.60505 + vertex 0.850245 1.46251 2.60686 + vertex 0.847034 1.46442 2.60497 + endloop + endfacet + facet normal -0.540645 -0.0240088 0.840908 + outer loop + vertex 0.847034 1.46442 2.60497 + vertex 0.844133 1.46157 2.60303 + vertex 0.847373 1.45948 2.60505 + endloop + endfacet + facet normal -0.540701 -0.0241327 0.840869 + outer loop + vertex 0.844133 1.46157 2.60303 + vertex 0.844575 1.45607 2.60315 + vertex 0.847373 1.45948 2.60505 + endloop + endfacet + facet normal -0.541394 -0.0233288 0.840445 + outer loop + vertex 0.847801 1.45539 2.60521 + vertex 0.847373 1.45948 2.60505 + vertex 0.844575 1.45607 2.60315 + endloop + endfacet + facet normal -0.541518 -0.0242474 0.840339 + outer loop + vertex 0.847801 1.45539 2.60521 + vertex 0.844575 1.45607 2.60315 + vertex 0.84677 1.45123 2.60443 + endloop + endfacet + facet normal -0.54713 -0.0277858 0.836586 + outer loop + vertex 0.84677 1.45123 2.60443 + vertex 0.844575 1.45607 2.60315 + vertex 0.843644 1.45165 2.6024 + endloop + endfacet + facet normal -0.547232 -0.0290719 0.836476 + outer loop + vertex 0.844201 1.44755 2.60262 + vertex 0.84677 1.45123 2.60443 + vertex 0.843644 1.45165 2.6024 + endloop + endfacet + facet normal -0.5667 -0.0324318 0.823286 + outer loop + vertex 0.844201 1.44755 2.60262 + vertex 0.843644 1.45165 2.6024 + vertex 0.841269 1.4493 2.60067 + endloop + endfacet + facet normal -0.566649 -0.0323006 0.823326 + outer loop + vertex 0.841477 1.44449 2.60063 + vertex 0.844201 1.44755 2.60262 + vertex 0.841269 1.4493 2.60067 + endloop + endfacet + facet normal -0.580034 -0.032788 0.813932 + outer loop + vertex 0.841269 1.4493 2.60067 + vertex 0.838503 1.44656 2.59859 + vertex 0.841477 1.44449 2.60063 + endloop + endfacet + facet normal -0.580335 -0.0334577 0.81369 + outer loop + vertex 0.838503 1.44656 2.59859 + vertex 0.838617 1.44158 2.59847 + vertex 0.841477 1.44449 2.60063 + endloop + endfacet + facet normal -0.580198 -0.0336594 0.81378 + outer loop + vertex 0.841477 1.44449 2.60063 + vertex 0.838617 1.44158 2.59847 + vertex 0.841598 1.4395 2.60051 + endloop + endfacet + facet normal -0.565764 -0.0335509 0.823885 + outer loop + vertex 0.841598 1.4395 2.60051 + vertex 0.844478 1.44267 2.60261 + vertex 0.841477 1.44449 2.60063 + endloop + endfacet + facet normal -0.564982 -0.0345901 0.824378 + outer loop + vertex 0.844601 1.43767 2.60249 + vertex 0.844478 1.44267 2.60261 + vertex 0.841598 1.4395 2.60051 + endloop + endfacet + facet normal -0.565164 -0.035043 0.824234 + outer loop + vertex 0.841694 1.43448 2.60036 + vertex 0.844601 1.43767 2.60249 + vertex 0.841598 1.4395 2.60051 + endloop + endfacet + facet normal -0.580045 -0.0350188 0.813831 + outer loop + vertex 0.841598 1.4395 2.60051 + vertex 0.838684 1.43657 2.5983 + vertex 0.841694 1.43448 2.60036 + endloop + endfacet + facet normal -0.580769 -0.0366332 0.813244 + outer loop + vertex 0.838684 1.43657 2.5983 + vertex 0.838832 1.43153 2.59818 + vertex 0.841694 1.43448 2.60036 + endloop + endfacet + facet normal -0.579391 -0.0386273 0.814134 + outer loop + vertex 0.841694 1.43448 2.60036 + vertex 0.838832 1.43153 2.59818 + vertex 0.841891 1.42945 2.60026 + endloop + endfacet + facet normal -0.564037 -0.0382361 0.824864 + outer loop + vertex 0.841891 1.42945 2.60026 + vertex 0.844712 1.43265 2.60234 + vertex 0.841694 1.43448 2.60036 + endloop + endfacet + facet normal -0.561393 -0.0416269 0.826502 + outer loop + vertex 0.844985 1.42759 2.60227 + vertex 0.844712 1.43265 2.60234 + vertex 0.841891 1.42945 2.60026 + endloop + endfacet + facet normal -0.542706 -0.0407907 0.838931 + outer loop + vertex 0.844985 1.42759 2.60227 + vertex 0.847771 1.43092 2.60423 + vertex 0.844712 1.43265 2.60234 + endloop + endfacet + facet normal -0.542269 -0.0396483 0.839269 + outer loop + vertex 0.847771 1.43092 2.60423 + vertex 0.847647 1.43587 2.60439 + vertex 0.844712 1.43265 2.60234 + endloop + endfacet + facet normal -0.544263 -0.0370822 0.838095 + outer loop + vertex 0.844712 1.43265 2.60234 + vertex 0.847647 1.43587 2.60439 + vertex 0.844601 1.43767 2.60249 + endloop + endfacet + facet normal -0.543958 -0.036322 0.838326 + outer loop + vertex 0.847647 1.43587 2.60439 + vertex 0.847541 1.44086 2.60453 + vertex 0.844601 1.43767 2.60249 + endloop + endfacet + facet normal -0.523921 -0.0395518 0.850848 + outer loop + vertex 0.847647 1.43587 2.60439 + vertex 0.847771 1.43092 2.60423 + vertex 0.850716 1.43387 2.60618 + endloop + endfacet + facet normal -0.522613 -0.0367052 0.851779 + outer loop + vertex 0.85073 1.43878 2.6064 + vertex 0.847647 1.43587 2.60439 + vertex 0.850716 1.43387 2.60618 + endloop + endfacet + facet normal -0.50802 -0.0371382 0.860544 + outer loop + vertex 0.850716 1.43387 2.60618 + vertex 0.854272 1.4361 2.60838 + vertex 0.85073 1.43878 2.6064 + endloop + endfacet + facet normal -0.506099 -0.0336678 0.861818 + outer loop + vertex 0.854272 1.4361 2.60838 + vertex 0.853803 1.44162 2.60832 + vertex 0.85073 1.43878 2.6064 + endloop + endfacet + facet normal -0.506248 -0.0334519 0.861739 + outer loop + vertex 0.85073 1.43878 2.6064 + vertex 0.853803 1.44162 2.60832 + vertex 0.85048 1.44385 2.60645 + endloop + endfacet + facet normal -0.521934 -0.0341299 0.852303 + outer loop + vertex 0.85048 1.44385 2.60645 + vertex 0.847541 1.44086 2.60453 + vertex 0.85073 1.43878 2.6064 + endloop + endfacet + facet normal -0.523142 -0.0325105 0.851625 + outer loop + vertex 0.847287 1.44589 2.60457 + vertex 0.847541 1.44086 2.60453 + vertex 0.85048 1.44385 2.60645 + endloop + endfacet + facet normal -0.52227 -0.030582 0.852231 + outer loop + vertex 0.850099 1.44888 2.6064 + vertex 0.847287 1.44589 2.60457 + vertex 0.85048 1.44385 2.60645 + endloop + endfacet + facet normal -0.504314 -0.0291041 0.86303 + outer loop + vertex 0.85048 1.44385 2.60645 + vertex 0.853432 1.44679 2.60828 + vertex 0.850099 1.44888 2.6064 + endloop + endfacet + facet normal -0.50269 -0.0255541 0.864089 + outer loop + vertex 0.853432 1.44679 2.60828 + vertex 0.85298 1.45237 2.60818 + vertex 0.850099 1.44888 2.6064 + endloop + endfacet + facet normal -0.501393 -0.0269838 0.864799 + outer loop + vertex 0.850099 1.44888 2.6064 + vertex 0.85298 1.45237 2.60818 + vertex 0.849659 1.45301 2.60627 + endloop + endfacet + facet normal -0.524627 -0.0298865 0.850807 + outer loop + vertex 0.849659 1.45301 2.60627 + vertex 0.84677 1.45123 2.60443 + vertex 0.850099 1.44888 2.6064 + endloop + endfacet + facet normal -0.52391 -0.0284641 0.851298 + outer loop + vertex 0.84677 1.45123 2.60443 + vertex 0.847287 1.44589 2.60457 + vertex 0.850099 1.44888 2.6064 + endloop + endfacet + facet normal -0.524341 -0.0305116 0.850961 + outer loop + vertex 0.84677 1.45123 2.60443 + vertex 0.849659 1.45301 2.60627 + vertex 0.847801 1.45539 2.60521 + endloop + endfacet + facet normal -0.514049 -0.0195601 0.857538 + outer loop + vertex 0.849659 1.45301 2.60627 + vertex 0.850743 1.45718 2.60702 + vertex 0.847801 1.45539 2.60521 + endloop + endfacet + facet normal -0.50104 -0.0242923 0.865083 + outer loop + vertex 0.849659 1.45301 2.60627 + vertex 0.85298 1.45237 2.60818 + vertex 0.850743 1.45718 2.60702 + endloop + endfacet + facet normal -0.497059 -0.021871 0.867441 + outer loop + vertex 0.85298 1.45237 2.60818 + vertex 0.854032 1.45683 2.60889 + vertex 0.850743 1.45718 2.60702 + endloop + endfacet + facet normal -0.504193 -0.0292658 0.863095 + outer loop + vertex 0.853803 1.44162 2.60832 + vertex 0.853432 1.44679 2.60828 + vertex 0.85048 1.44385 2.60645 + endloop + endfacet + facet normal -0.508899 -0.0352995 0.860102 + outer loop + vertex 0.853246 1.43171 2.60759 + vertex 0.854272 1.4361 2.60838 + vertex 0.850716 1.43387 2.60618 + endloop + endfacet + facet normal -0.511799 -0.0399535 0.858176 + outer loop + vertex 0.850783 1.4292 2.606 + vertex 0.853246 1.43171 2.60759 + vertex 0.850716 1.43387 2.60618 + endloop + endfacet + facet normal -0.510915 -0.0411173 0.858648 + outer loop + vertex 0.853875 1.42763 2.60777 + vertex 0.853246 1.43171 2.60759 + vertex 0.850783 1.4292 2.606 + endloop + endfacet + facet normal -0.511312 -0.0422287 0.858357 + outer loop + vertex 0.851148 1.42455 2.60599 + vertex 0.853875 1.42763 2.60777 + vertex 0.850783 1.4292 2.606 + endloop + endfacet + facet normal -0.523115 -0.0431411 0.85117 + outer loop + vertex 0.850783 1.4292 2.606 + vertex 0.848104 1.42605 2.6042 + vertex 0.851148 1.42455 2.60599 + endloop + endfacet + facet normal -0.524412 -0.041619 0.850447 + outer loop + vertex 0.847771 1.43092 2.60423 + vertex 0.848104 1.42605 2.6042 + vertex 0.850783 1.4292 2.606 + endloop + endfacet + facet normal -0.511844 -0.0415926 0.858071 + outer loop + vertex 0.854246 1.42276 2.60775 + vertex 0.853875 1.42763 2.60777 + vertex 0.851148 1.42455 2.60599 + endloop + endfacet + facet normal -0.512891 -0.0441367 0.857318 + outer loop + vertex 0.851259 1.41978 2.60581 + vertex 0.854246 1.42276 2.60775 + vertex 0.851148 1.42455 2.60599 + endloop + endfacet + facet normal -0.522009 -0.0441398 0.851797 + outer loop + vertex 0.851148 1.42455 2.60599 + vertex 0.848731 1.42192 2.60438 + vertex 0.851259 1.41978 2.60581 + endloop + endfacet + facet normal -0.51449 -0.0419796 0.856468 + outer loop + vertex 0.85442 1.41776 2.60761 + vertex 0.854246 1.42276 2.60775 + vertex 0.851259 1.41978 2.60581 + endloop + endfacet + facet normal -0.51599 -0.0452835 0.855397 + outer loop + vertex 0.851279 1.41473 2.60556 + vertex 0.85442 1.41776 2.60761 + vertex 0.851259 1.41978 2.60581 + endloop + endfacet + facet normal -0.527924 -0.0449638 0.8481 + outer loop + vertex 0.851259 1.41978 2.60581 + vertex 0.847783 1.41735 2.60352 + vertex 0.851279 1.41473 2.60556 + endloop + endfacet + facet normal -0.5294 -0.0477638 0.847026 + outer loop + vertex 0.847783 1.41735 2.60352 + vertex 0.84824 1.41174 2.60349 + vertex 0.851279 1.41473 2.60556 + endloop + endfacet + facet normal -0.529695 -0.0473526 0.846865 + outer loop + vertex 0.851279 1.41473 2.60556 + vertex 0.84824 1.41174 2.60349 + vertex 0.851493 1.4096 2.60541 + endloop + endfacet + facet normal -0.519261 -0.0471092 0.853316 + outer loop + vertex 0.851493 1.4096 2.60541 + vertex 0.854536 1.41272 2.60743 + vertex 0.851279 1.41473 2.60556 + endloop + endfacet + facet normal -0.51959 -0.0466746 0.85314 + outer loop + vertex 0.854713 1.40771 2.60726 + vertex 0.854536 1.41272 2.60743 + vertex 0.851493 1.4096 2.60541 + endloop + endfacet + facet normal -0.521846 -0.052188 0.851442 + outer loop + vertex 0.851789 1.4046 2.60528 + vertex 0.854713 1.40771 2.60726 + vertex 0.851493 1.4096 2.60541 + endloop + endfacet + facet normal -0.530917 -0.0525831 0.845791 + outer loop + vertex 0.851493 1.4096 2.60541 + vertex 0.848571 1.40665 2.60339 + vertex 0.851789 1.4046 2.60528 + endloop + endfacet + facet normal -0.533076 -0.0575224 0.844109 + outer loop + vertex 0.848571 1.40665 2.60339 + vertex 0.848955 1.40165 2.60329 + vertex 0.851789 1.4046 2.60528 + endloop + endfacet + facet normal -0.532634 -0.0581089 0.844349 + outer loop + vertex 0.851789 1.4046 2.60528 + vertex 0.848955 1.40165 2.60329 + vertex 0.852234 1.39965 2.60522 + endloop + endfacet + facet normal -0.524202 -0.0574132 0.849656 + outer loop + vertex 0.852234 1.39965 2.60522 + vertex 0.855043 1.40269 2.60716 + vertex 0.851789 1.4046 2.60528 + endloop + endfacet + facet normal -0.522002 -0.0519883 0.851359 + outer loop + vertex 0.855043 1.40269 2.60716 + vertex 0.854713 1.40771 2.60726 + vertex 0.851789 1.4046 2.60528 + endloop + endfacet + facet normal -0.516039 -0.0516727 0.855005 + outer loop + vertex 0.855043 1.40269 2.60716 + vertex 0.857913 1.40601 2.60909 + vertex 0.854713 1.40771 2.60726 + endloop + endfacet + facet normal -0.517171 -0.0503409 0.854401 + outer loop + vertex 0.858276 1.40111 2.60902 + vertex 0.857913 1.40601 2.60909 + vertex 0.855043 1.40269 2.60716 + endloop + endfacet + facet normal -0.518968 -0.0556891 0.852978 + outer loop + vertex 0.855637 1.39734 2.60717 + vertex 0.858276 1.40111 2.60902 + vertex 0.855043 1.40269 2.60716 + endloop + endfacet + facet normal -0.513647 -0.0465841 0.856736 + outer loop + vertex 0.854713 1.40771 2.60726 + vertex 0.857727 1.41094 2.60925 + vertex 0.854536 1.41272 2.60743 + endloop + endfacet + facet normal -0.511918 -0.0421995 0.857997 + outer loop + vertex 0.857727 1.41094 2.60925 + vertex 0.857643 1.41588 2.60944 + vertex 0.854536 1.41272 2.60743 + endloop + endfacet + facet normal -0.511221 -0.0431194 0.858367 + outer loop + vertex 0.854536 1.41272 2.60743 + vertex 0.857643 1.41588 2.60944 + vertex 0.85442 1.41776 2.60761 + endloop + endfacet + facet normal -0.517533 -0.0431264 0.854576 + outer loop + vertex 0.854536 1.41272 2.60743 + vertex 0.85442 1.41776 2.60761 + vertex 0.851279 1.41473 2.60556 + endloop + endfacet + facet normal -0.508516 -0.0418711 0.860034 + outer loop + vertex 0.85442 1.41776 2.60761 + vertex 0.857495 1.42087 2.60958 + vertex 0.854246 1.42276 2.60775 + endloop + endfacet + facet normal -0.507458 -0.0393239 0.860779 + outer loop + vertex 0.857495 1.42087 2.60958 + vertex 0.857166 1.42591 2.60962 + vertex 0.854246 1.42276 2.60775 + endloop + endfacet + facet normal -0.505978 -0.0411564 0.861564 + outer loop + vertex 0.854246 1.42276 2.60775 + vertex 0.857166 1.42591 2.60962 + vertex 0.853875 1.42763 2.60777 + endloop + endfacet + facet normal -0.503549 -0.0397907 0.86305 + outer loop + vertex 0.853875 1.42763 2.60777 + vertex 0.856579 1.43127 2.60951 + vertex 0.853246 1.43171 2.60759 + endloop + endfacet + facet normal -0.522918 -0.0362669 0.851611 + outer loop + vertex 0.847541 1.44086 2.60453 + vertex 0.847647 1.43587 2.60439 + vertex 0.85073 1.43878 2.6064 + endloop + endfacet + facet normal -0.523704 -0.0398476 0.850968 + outer loop + vertex 0.850716 1.43387 2.60618 + vertex 0.847771 1.43092 2.60423 + vertex 0.850783 1.4292 2.606 + endloop + endfacet + facet normal -0.580244 -0.0405821 0.813431 + outer loop + vertex 0.838832 1.43153 2.59818 + vertex 0.839135 1.42643 2.59814 + vertex 0.841891 1.42945 2.60026 + endloop + endfacet + facet normal -0.57831 -0.0432204 0.814671 + outer loop + vertex 0.841891 1.42945 2.60026 + vertex 0.839135 1.42643 2.59814 + vertex 0.842279 1.42443 2.60027 + endloop + endfacet + facet normal -0.592342 -0.0412378 0.80463 + outer loop + vertex 0.839135 1.42643 2.59814 + vertex 0.838832 1.43153 2.59818 + vertex 0.836022 1.42888 2.59598 + endloop + endfacet + facet normal -0.593548 -0.043676 0.803612 + outer loop + vertex 0.836323 1.42379 2.59592 + vertex 0.839135 1.42643 2.59814 + vertex 0.836022 1.42888 2.59598 + endloop + endfacet + facet normal -0.604247 -0.0442243 0.795569 + outer loop + vertex 0.836022 1.42888 2.59598 + vertex 0.833277 1.42643 2.59376 + vertex 0.836323 1.42379 2.59592 + endloop + endfacet + facet normal -0.605367 -0.0463165 0.794597 + outer loop + vertex 0.833277 1.42643 2.59376 + vertex 0.833485 1.42145 2.59362 + vertex 0.836323 1.42379 2.59592 + endloop + endfacet + facet normal -0.605541 -0.0459941 0.794484 + outer loop + vertex 0.836323 1.42379 2.59592 + vertex 0.833485 1.42145 2.59362 + vertex 0.836413 1.41889 2.59571 + endloop + endfacet + facet normal -0.592698 -0.046179 0.8041 + outer loop + vertex 0.836413 1.41889 2.59571 + vertex 0.839634 1.42092 2.5982 + vertex 0.836323 1.42379 2.59592 + endloop + endfacet + facet normal -0.593677 -0.0438949 0.803505 + outer loop + vertex 0.83876 1.41657 2.59731 + vertex 0.839634 1.42092 2.5982 + vertex 0.836413 1.41889 2.59571 + endloop + endfacet + facet normal -0.596231 -0.0479362 0.80138 + outer loop + vertex 0.836492 1.41425 2.59549 + vertex 0.83876 1.41657 2.59731 + vertex 0.836413 1.41889 2.59571 + endloop + endfacet + facet normal -0.606373 -0.0477489 0.793745 + outer loop + vertex 0.836413 1.41889 2.59571 + vertex 0.833653 1.41649 2.59345 + vertex 0.836492 1.41425 2.59549 + endloop + endfacet + facet normal -0.607284 -0.049648 0.792932 + outer loop + vertex 0.833653 1.41649 2.59345 + vertex 0.833855 1.41156 2.5933 + vertex 0.836492 1.41425 2.59549 + endloop + endfacet + facet normal -0.606131 -0.0514049 0.793702 + outer loop + vertex 0.836492 1.41425 2.59549 + vertex 0.833855 1.41156 2.5933 + vertex 0.836751 1.40956 2.59538 + endloop + endfacet + facet normal -0.594165 -0.0510233 0.802723 + outer loop + vertex 0.839321 1.41255 2.59747 + vertex 0.83876 1.41657 2.59731 + vertex 0.836492 1.41425 2.59549 + endloop + endfacet + facet normal -0.592368 -0.0455789 0.804377 + outer loop + vertex 0.839634 1.42092 2.5982 + vertex 0.839135 1.42643 2.59814 + vertex 0.836323 1.42379 2.59592 + endloop + endfacet + facet normal -0.593496 -0.0393845 0.803872 + outer loop + vertex 0.836022 1.42888 2.59598 + vertex 0.838832 1.43153 2.59818 + vertex 0.835751 1.43401 2.59603 + endloop + endfacet + facet normal -0.603278 -0.0398244 0.796536 + outer loop + vertex 0.835751 1.43401 2.59603 + vertex 0.83295 1.4315 2.59378 + vertex 0.836022 1.42888 2.59598 + endloop + endfacet + facet normal -0.592159 -0.0367681 0.804982 + outer loop + vertex 0.838832 1.43153 2.59818 + vertex 0.838684 1.43657 2.5983 + vertex 0.835751 1.43401 2.59603 + endloop + endfacet + facet normal -0.592118 -0.0368388 0.805008 + outer loop + vertex 0.835751 1.43401 2.59603 + vertex 0.838684 1.43657 2.5983 + vertex 0.835739 1.43904 2.59625 + endloop + endfacet + facet normal -0.602056 -0.036539 0.797617 + outer loop + vertex 0.835739 1.43904 2.59625 + vertex 0.832479 1.43712 2.5937 + vertex 0.835751 1.43401 2.59603 + endloop + endfacet + facet normal -0.600819 -0.0396766 0.7984 + outer loop + vertex 0.833399 1.44157 2.59461 + vertex 0.832479 1.43712 2.5937 + vertex 0.835739 1.43904 2.59625 + endloop + endfacet + facet normal -0.597682 -0.0351092 0.800964 + outer loop + vertex 0.835743 1.44385 2.59646 + vertex 0.833399 1.44157 2.59461 + vertex 0.835739 1.43904 2.59625 + endloop + endfacet + facet normal -0.590065 -0.0353651 0.806581 + outer loop + vertex 0.835739 1.43904 2.59625 + vertex 0.838617 1.44158 2.59847 + vertex 0.835743 1.44385 2.59646 + endloop + endfacet + facet normal -0.598368 -0.0340258 0.800498 + outer loop + vertex 0.832898 1.4458 2.59442 + vertex 0.833399 1.44157 2.59461 + vertex 0.835743 1.44385 2.59646 + endloop + endfacet + facet normal -0.598266 -0.0337863 0.800585 + outer loop + vertex 0.835544 1.44875 2.59652 + vertex 0.832898 1.4458 2.59442 + vertex 0.835743 1.44385 2.59646 + endloop + endfacet + facet normal -0.589133 -0.0334966 0.807342 + outer loop + vertex 0.835743 1.44385 2.59646 + vertex 0.838503 1.44656 2.59859 + vertex 0.835544 1.44875 2.59652 + endloop + endfacet + facet normal -0.588638 -0.032448 0.807745 + outer loop + vertex 0.838503 1.44656 2.59859 + vertex 0.838337 1.45154 2.59867 + vertex 0.835544 1.44875 2.59652 + endloop + endfacet + facet normal -0.588493 -0.0326672 0.807842 + outer loop + vertex 0.835544 1.44875 2.59652 + vertex 0.838337 1.45154 2.59867 + vertex 0.835316 1.45384 2.59656 + endloop + endfacet + facet normal -0.598047 -0.0330415 0.80078 + outer loop + vertex 0.835316 1.45384 2.59656 + vertex 0.832613 1.45081 2.59442 + vertex 0.835544 1.44875 2.59652 + endloop + endfacet + facet normal -0.598333 -0.033694 0.800539 + outer loop + vertex 0.832613 1.45081 2.59442 + vertex 0.832898 1.4458 2.59442 + vertex 0.835544 1.44875 2.59652 + endloop + endfacet + facet normal -0.6098 -0.0343489 0.79181 + outer loop + vertex 0.832898 1.4458 2.59442 + vertex 0.832613 1.45081 2.59442 + vertex 0.830002 1.44758 2.59227 + endloop + endfacet + facet normal -0.610229 -0.0337986 0.791504 + outer loop + vertex 0.830002 1.44758 2.59227 + vertex 0.832613 1.45081 2.59442 + vertex 0.829749 1.45267 2.59229 + endloop + endfacet + facet normal -0.60994 -0.0330648 0.791758 + outer loop + vertex 0.832613 1.45081 2.59442 + vertex 0.832339 1.45594 2.59442 + vertex 0.829749 1.45267 2.59229 + endloop + endfacet + facet normal -0.609102 -0.0356714 0.792289 + outer loop + vertex 0.833399 1.44157 2.59461 + vertex 0.832898 1.4458 2.59442 + vertex 0.830438 1.44213 2.59236 + endloop + endfacet + facet normal -0.590728 -0.0342346 0.806144 + outer loop + vertex 0.838684 1.43657 2.5983 + vertex 0.838617 1.44158 2.59847 + vertex 0.835739 1.43904 2.59625 + endloop + endfacet + facet normal -0.563596 -0.0371267 0.825216 + outer loop + vertex 0.844712 1.43265 2.60234 + vertex 0.844601 1.43767 2.60249 + vertex 0.841694 1.43448 2.60036 + endloop + endfacet + facet normal -0.545406 -0.0344342 0.837464 + outer loop + vertex 0.844601 1.43767 2.60249 + vertex 0.847541 1.44086 2.60453 + vertex 0.844478 1.44267 2.60261 + endloop + endfacet + facet normal -0.545038 -0.0335194 0.837741 + outer loop + vertex 0.847541 1.44086 2.60453 + vertex 0.847287 1.44589 2.60457 + vertex 0.844478 1.44267 2.60261 + endloop + endfacet + facet normal -0.545952 -0.0323889 0.83719 + outer loop + vertex 0.844478 1.44267 2.60261 + vertex 0.847287 1.44589 2.60457 + vertex 0.844201 1.44755 2.60262 + endloop + endfacet + facet normal -0.580504 -0.0343393 0.813533 + outer loop + vertex 0.838617 1.44158 2.59847 + vertex 0.838684 1.43657 2.5983 + vertex 0.841598 1.4395 2.60051 + endloop + endfacet + facet normal -0.58913 -0.0335016 0.807344 + outer loop + vertex 0.838617 1.44158 2.59847 + vertex 0.838503 1.44656 2.59859 + vertex 0.835743 1.44385 2.59646 + endloop + endfacet + facet normal -0.580381 -0.0322672 0.813706 + outer loop + vertex 0.838337 1.45154 2.59867 + vertex 0.838503 1.44656 2.59859 + vertex 0.841269 1.4493 2.60067 + endloop + endfacet + facet normal -0.578972 -0.0294334 0.814816 + outer loop + vertex 0.841199 1.45406 2.60079 + vertex 0.838337 1.45154 2.59867 + vertex 0.841269 1.4493 2.60067 + endloop + endfacet + facet normal -0.578468 -0.0302814 0.815143 + outer loop + vertex 0.838108 1.45668 2.5987 + vertex 0.838337 1.45154 2.59867 + vertex 0.841199 1.45406 2.60079 + endloop + endfacet + facet normal -0.565738 -0.0334861 0.823905 + outer loop + vertex 0.844478 1.44267 2.60261 + vertex 0.844201 1.44755 2.60262 + vertex 0.841477 1.44449 2.60063 + endloop + endfacet + facet normal -0.568709 -0.0294675 0.822011 + outer loop + vertex 0.841269 1.4493 2.60067 + vertex 0.843644 1.45165 2.6024 + vertex 0.841199 1.45406 2.60079 + endloop + endfacet + facet normal -0.545408 -0.0308992 0.837601 + outer loop + vertex 0.847287 1.44589 2.60457 + vertex 0.84677 1.45123 2.60443 + vertex 0.844201 1.44755 2.60262 + endloop + endfacet + facet normal -0.563965 -0.0223317 0.825496 + outer loop + vertex 0.843644 1.45165 2.6024 + vertex 0.844575 1.45607 2.60315 + vertex 0.841199 1.45406 2.60079 + endloop + endfacet + facet normal -0.562046 -0.0269466 0.826667 + outer loop + vertex 0.841199 1.45406 2.60079 + vertex 0.844575 1.45607 2.60315 + vertex 0.841109 1.45913 2.6009 + endloop + endfacet + facet normal -0.513953 -0.0197699 0.85759 + outer loop + vertex 0.847801 1.45539 2.60521 + vertex 0.850743 1.45718 2.60702 + vertex 0.847373 1.45948 2.60505 + endloop + endfacet + facet normal -0.51573 -0.0233654 0.856432 + outer loop + vertex 0.850743 1.45718 2.60702 + vertex 0.850245 1.46251 2.60686 + vertex 0.847373 1.45948 2.60505 + endloop + endfacet + facet normal -0.541137 -0.0196815 0.840704 + outer loop + vertex 0.843739 1.47646 2.60316 + vertex 0.843808 1.47147 2.60309 + vertex 0.846816 1.47436 2.60509 + endloop + endfacet + facet normal -0.540679 -0.0230608 0.840913 + outer loop + vertex 0.846875 1.46938 2.60501 + vertex 0.843921 1.46656 2.60303 + vertex 0.847034 1.46442 2.60497 + endloop + endfacet + facet normal -0.540934 -0.0235948 0.840734 + outer loop + vertex 0.843921 1.46656 2.60303 + vertex 0.844133 1.46157 2.60303 + vertex 0.847034 1.46442 2.60497 + endloop + endfacet + facet normal -0.561554 -0.0261248 0.827028 + outer loop + vertex 0.844575 1.45607 2.60315 + vertex 0.844133 1.46157 2.60303 + vertex 0.841109 1.45913 2.6009 + endloop + endfacet + facet normal -0.576646 -0.0269999 0.816548 + outer loop + vertex 0.841109 1.45913 2.6009 + vertex 0.838108 1.45668 2.5987 + vertex 0.841199 1.45406 2.60079 + endloop + endfacet + facet normal -0.587513 -0.0306476 0.808634 + outer loop + vertex 0.838337 1.45154 2.59867 + vertex 0.838108 1.45668 2.5987 + vertex 0.835316 1.45384 2.59656 + endloop + endfacet + facet normal -0.59847 -0.0324562 0.800488 + outer loop + vertex 0.832339 1.45594 2.59442 + vertex 0.832613 1.45081 2.59442 + vertex 0.835316 1.45384 2.59656 + endloop + endfacet + facet normal -0.6103 -0.0326099 0.791499 + outer loop + vertex 0.829749 1.45267 2.59229 + vertex 0.832339 1.45594 2.59442 + vertex 0.829472 1.4576 2.59228 + endloop + endfacet + facet normal -0.622083 -0.0343466 0.782198 + outer loop + vertex 0.830002 1.44758 2.59227 + vertex 0.829749 1.45267 2.59229 + vertex 0.827151 1.4495 2.59008 + endloop + endfacet + facet normal -0.609952 -0.0347571 0.791676 + outer loop + vertex 0.830438 1.44213 2.59236 + vertex 0.832898 1.4458 2.59442 + vertex 0.830002 1.44758 2.59227 + endloop + endfacet + facet normal -0.609199 -0.0366652 0.792169 + outer loop + vertex 0.832479 1.43712 2.5937 + vertex 0.833399 1.44157 2.59461 + vertex 0.830438 1.44213 2.59236 + endloop + endfacet + facet normal -0.60364 -0.0392012 0.796292 + outer loop + vertex 0.832479 1.43712 2.5937 + vertex 0.83295 1.4315 2.59378 + vertex 0.835751 1.43401 2.59603 + endloop + endfacet + facet normal -0.604959 -0.0429948 0.795095 + outer loop + vertex 0.83295 1.4315 2.59378 + vertex 0.833277 1.42643 2.59376 + vertex 0.836022 1.42888 2.59598 + endloop + endfacet + facet normal -0.62657 -0.0446651 0.778084 + outer loop + vertex 0.827589 1.43097 2.5895 + vertex 0.828268 1.42677 2.58981 + vertex 0.830408 1.42895 2.59166 + endloop + endfacet + facet normal -0.635947 -0.0474706 0.770271 + outer loop + vertex 0.827481 1.4223 2.58888 + vertex 0.828268 1.42677 2.58981 + vertex 0.825399 1.4273 2.58747 + endloop + endfacet + facet normal -0.616483 -0.0465517 0.785991 + outer loop + vertex 0.833485 1.42145 2.59362 + vertex 0.833277 1.42643 2.59376 + vertex 0.83058 1.42417 2.59151 + endloop + endfacet + facet normal -0.606432 -0.0476466 0.793707 + outer loop + vertex 0.833485 1.42145 2.59362 + vertex 0.833653 1.41649 2.59345 + vertex 0.836413 1.41889 2.59571 + endloop + endfacet + facet normal -0.628228 -0.0477753 0.776561 + outer loop + vertex 0.827481 1.4223 2.58888 + vertex 0.827947 1.41661 2.58891 + vertex 0.830669 1.41912 2.59127 + endloop + endfacet + facet normal -0.61739 -0.0498155 0.785078 + outer loop + vertex 0.833855 1.41156 2.5933 + vertex 0.833653 1.41649 2.59345 + vertex 0.83092 1.41393 2.59114 + endloop + endfacet + facet normal -0.617311 -0.058304 0.784556 + outer loop + vertex 0.834366 1.40167 2.593 + vertex 0.834084 1.40665 2.59315 + vertex 0.8314 1.40391 2.59083 + endloop + endfacet + facet normal -0.620945 -0.0601963 0.781539 + outer loop + vertex 0.833989 1.39181 2.59192 + vertex 0.834811 1.39621 2.59292 + vertex 0.831716 1.3941 2.59029 + endloop + endfacet + facet normal -0.609917 -0.063153 0.789945 + outer loop + vertex 0.834718 1.38768 2.59216 + vertex 0.836955 1.3914 2.59418 + vertex 0.833989 1.39181 2.59192 + endloop + endfacet + facet normal -0.607405 -0.065606 0.791679 + outer loop + vertex 0.83776 1.38605 2.59436 + vertex 0.836955 1.3914 2.59418 + vertex 0.834718 1.38768 2.59216 + endloop + endfacet + facet normal -0.607847 -0.0670543 0.791218 + outer loop + vertex 0.835547 1.38242 2.59235 + vertex 0.83776 1.38605 2.59436 + vertex 0.834718 1.38768 2.59216 + endloop + endfacet + facet normal -0.620153 -0.0693463 0.78141 + outer loop + vertex 0.835547 1.38242 2.59235 + vertex 0.834718 1.38768 2.59216 + vertex 0.832426 1.38477 2.59008 + endloop + endfacet + facet normal -0.622795 -0.0843482 0.777825 + outer loop + vertex 0.834812 1.37843 2.5914 + vertex 0.832563 1.37727 2.58948 + vertex 0.835288 1.37435 2.59134 + endloop + endfacet + facet normal -0.62219 -0.0834111 0.77841 + outer loop + vertex 0.832563 1.37727 2.58948 + vertex 0.832333 1.37226 2.58876 + vertex 0.835288 1.37435 2.59134 + endloop + endfacet + facet normal -0.621664 -0.084528 0.77871 + outer loop + vertex 0.835288 1.37435 2.59134 + vertex 0.832333 1.37226 2.58876 + vertex 0.835783 1.36923 2.59118 + endloop + endfacet + facet normal -0.602888 -0.083175 0.793478 + outer loop + vertex 0.835783 1.36923 2.59118 + vertex 0.838467 1.37182 2.59349 + vertex 0.835288 1.37435 2.59134 + endloop + endfacet + facet normal -0.60333 -0.084098 0.793045 + outer loop + vertex 0.838467 1.37182 2.59349 + vertex 0.837839 1.37741 2.59361 + vertex 0.835288 1.37435 2.59134 + endloop + endfacet + facet normal -0.601587 -0.0852107 0.794249 + outer loop + vertex 0.839028 1.36666 2.59336 + vertex 0.838467 1.37182 2.59349 + vertex 0.835783 1.36923 2.59118 + endloop + endfacet + facet normal -0.598794 -0.0793814 0.796959 + outer loop + vertex 0.836307 1.36399 2.59105 + vertex 0.839028 1.36666 2.59336 + vertex 0.835783 1.36923 2.59118 + endloop + endfacet + facet normal -0.616983 -0.0808555 0.782812 + outer loop + vertex 0.835783 1.36923 2.59118 + vertex 0.833154 1.36667 2.58884 + vertex 0.836307 1.36399 2.59105 + endloop + endfacet + facet normal -0.596154 -0.083427 0.798524 + outer loop + vertex 0.839671 1.36114 2.59327 + vertex 0.839028 1.36666 2.59336 + vertex 0.836307 1.36399 2.59105 + endloop + endfacet + facet normal -0.593108 -0.0776189 0.801372 + outer loop + vertex 0.836496 1.35903 2.59071 + vertex 0.839671 1.36114 2.59327 + vertex 0.836307 1.36399 2.59105 + endloop + endfacet + facet normal -0.615261 -0.0773092 0.784524 + outer loop + vertex 0.836307 1.36399 2.59105 + vertex 0.833569 1.36155 2.58867 + vertex 0.836496 1.35903 2.59071 + endloop + endfacet + facet normal -0.616193 -0.0791329 0.783609 + outer loop + vertex 0.833569 1.36155 2.58867 + vertex 0.833852 1.35658 2.58839 + vertex 0.836496 1.35903 2.59071 + endloop + endfacet + facet normal -0.61462 -0.0817514 0.784576 + outer loop + vertex 0.836496 1.35903 2.59071 + vertex 0.833852 1.35658 2.58839 + vertex 0.836696 1.35438 2.59038 + endloop + endfacet + facet normal -0.597582 -0.0819416 0.79761 + outer loop + vertex 0.836696 1.35438 2.59038 + vertex 0.83887 1.35673 2.59225 + vertex 0.836496 1.35903 2.59071 + endloop + endfacet + facet normal -0.592147 -0.0895434 0.80084 + outer loop + vertex 0.839631 1.35264 2.59236 + vertex 0.83887 1.35673 2.59225 + vertex 0.836696 1.35438 2.59038 + endloop + endfacet + facet normal -0.592517 -0.0906172 0.800445 + outer loop + vertex 0.837242 1.34968 2.59026 + vertex 0.839631 1.35264 2.59236 + vertex 0.836696 1.35438 2.59038 + endloop + endfacet + facet normal -0.613459 -0.0926076 0.784278 + outer loop + vertex 0.836696 1.35438 2.59038 + vertex 0.834228 1.35164 2.58813 + vertex 0.837242 1.34968 2.59026 + endloop + endfacet + facet normal -0.614499 -0.0954629 0.783121 + outer loop + vertex 0.834228 1.35164 2.58813 + vertex 0.834852 1.34625 2.58796 + vertex 0.837242 1.34968 2.59026 + endloop + endfacet + facet normal -0.61178 -0.0985222 0.784868 + outer loop + vertex 0.837852 1.34565 2.59023 + vertex 0.837242 1.34968 2.59026 + vertex 0.834852 1.34625 2.58796 + endloop + endfacet + facet normal -0.589017 -0.0952028 0.802493 + outer loop + vertex 0.837852 1.34565 2.59023 + vertex 0.840488 1.3474 2.59237 + vertex 0.837242 1.34968 2.59026 + endloop + endfacet + facet normal -0.630472 -0.0969065 0.770139 + outer loop + vertex 0.834852 1.34625 2.58796 + vertex 0.834228 1.35164 2.58813 + vertex 0.831637 1.34901 2.58568 + endloop + endfacet + facet normal -0.633949 -0.0914432 0.76795 + outer loop + vertex 0.831637 1.34901 2.58568 + vertex 0.834228 1.35164 2.58813 + vertex 0.831265 1.35404 2.58597 + endloop + endfacet + facet normal -0.644743 -0.0917134 0.758877 + outer loop + vertex 0.831265 1.35404 2.58597 + vertex 0.828706 1.35153 2.58349 + vertex 0.831637 1.34901 2.58568 + endloop + endfacet + facet normal -0.632347 -0.0879113 0.769681 + outer loop + vertex 0.834228 1.35164 2.58813 + vertex 0.833852 1.35658 2.58839 + vertex 0.831265 1.35404 2.58597 + endloop + endfacet + facet normal -0.63484 -0.0838553 0.76808 + outer loop + vertex 0.831265 1.35404 2.58597 + vertex 0.833852 1.35658 2.58839 + vertex 0.830884 1.35919 2.58622 + endloop + endfacet + facet normal -0.588938 -0.0950149 0.802574 + outer loop + vertex 0.840488 1.3474 2.59237 + vertex 0.839631 1.35264 2.59236 + vertex 0.837242 1.34968 2.59026 + endloop + endfacet + facet normal -0.617157 -0.0873913 0.781972 + outer loop + vertex 0.833852 1.35658 2.58839 + vertex 0.834228 1.35164 2.58813 + vertex 0.836696 1.35438 2.59038 + endloop + endfacet + facet normal -0.593904 -0.0759073 0.800947 + outer loop + vertex 0.83887 1.35673 2.59225 + vertex 0.839671 1.36114 2.59327 + vertex 0.836496 1.35903 2.59071 + endloop + endfacet + facet normal -0.618507 -0.0784167 0.781857 + outer loop + vertex 0.832333 1.37226 2.58876 + vertex 0.833154 1.36667 2.58884 + vertex 0.835783 1.36923 2.59118 + endloop + endfacet + facet normal -0.619479 -0.0678121 0.782079 + outer loop + vertex 0.833053 1.38085 2.59024 + vertex 0.835547 1.38242 2.59235 + vertex 0.832426 1.38477 2.59008 + endloop + endfacet + facet normal -0.604604 -0.0824424 0.792248 + outer loop + vertex 0.835288 1.37435 2.59134 + vertex 0.837839 1.37741 2.59361 + vertex 0.834812 1.37843 2.5914 + endloop + endfacet + facet normal -0.603506 -0.0713218 0.794162 + outer loop + vertex 0.838582 1.38178 2.5946 + vertex 0.83776 1.38605 2.59436 + vertex 0.835547 1.38242 2.59235 + endloop + endfacet + facet normal -0.567448 -0.0719269 0.820262 + outer loop + vertex 0.843971 1.38172 2.59839 + vertex 0.843435 1.3869 2.59848 + vertex 0.84082 1.38406 2.59642 + endloop + endfacet + facet normal -0.591641 -0.0628378 0.803749 + outer loop + vertex 0.836955 1.3914 2.59418 + vertex 0.83776 1.38605 2.59436 + vertex 0.840204 1.38901 2.59639 + endloop + endfacet + facet normal -0.609962 -0.0641179 0.789832 + outer loop + vertex 0.836955 1.3914 2.59418 + vertex 0.834811 1.39621 2.59292 + vertex 0.833989 1.39181 2.59192 + endloop + endfacet + facet normal -0.588136 -0.0602999 0.806511 + outer loop + vertex 0.839634 1.39322 2.59631 + vertex 0.840583 1.39744 2.59732 + vertex 0.837826 1.39564 2.59518 + endloop + endfacet + facet normal -0.575534 -0.0601633 0.815561 + outer loop + vertex 0.840583 1.39744 2.59732 + vertex 0.84309 1.40102 2.59935 + vertex 0.840022 1.4028 2.59732 + endloop + endfacet + facet normal -0.606012 -0.0614295 0.79308 + outer loop + vertex 0.834366 1.40167 2.593 + vertex 0.834811 1.39621 2.59292 + vertex 0.837392 1.39976 2.59516 + endloop + endfacet + facet normal -0.606827 -0.0530784 0.79306 + outer loop + vertex 0.833855 1.41156 2.5933 + vertex 0.834084 1.40665 2.59315 + vertex 0.836751 1.40956 2.59538 + endloop + endfacet + facet normal -0.591253 -0.0574299 0.804438 + outer loop + vertex 0.840022 1.4028 2.59732 + vertex 0.839672 1.40776 2.59742 + vertex 0.837022 1.4047 2.59525 + endloop + endfacet + facet normal -0.577461 -0.0566493 0.81445 + outer loop + vertex 0.840022 1.4028 2.59732 + vertex 0.842673 1.40588 2.59942 + vertex 0.839672 1.40776 2.59742 + endloop + endfacet + facet normal -0.594136 -0.0509462 0.802749 + outer loop + vertex 0.836751 1.40956 2.59538 + vertex 0.839321 1.41255 2.59747 + vertex 0.836492 1.41425 2.59549 + endloop + endfacet + facet normal -0.576578 -0.0544044 0.815229 + outer loop + vertex 0.842673 1.40588 2.59942 + vertex 0.842313 1.41084 2.59949 + vertex 0.839672 1.40776 2.59742 + endloop + endfacet + facet normal -0.578726 -0.0442457 0.814321 + outer loop + vertex 0.839135 1.42643 2.59814 + vertex 0.839634 1.42092 2.5982 + vertex 0.842279 1.42443 2.60027 + endloop + endfacet + facet normal -0.561498 -0.0418949 0.826417 + outer loop + vertex 0.842279 1.42443 2.60027 + vertex 0.844985 1.42759 2.60227 + vertex 0.841891 1.42945 2.60026 + endloop + endfacet + facet normal -0.541096 -0.0426941 0.839877 + outer loop + vertex 0.848104 1.42605 2.6042 + vertex 0.847771 1.43092 2.60423 + vertex 0.844985 1.42759 2.60227 + endloop + endfacet + facet normal -0.523021 -0.0428668 0.851241 + outer loop + vertex 0.848104 1.42605 2.6042 + vertex 0.848731 1.42192 2.60438 + vertex 0.851148 1.42455 2.60599 + endloop + endfacet + facet normal -0.525419 -0.0497704 0.849387 + outer loop + vertex 0.848731 1.42192 2.60438 + vertex 0.847783 1.41735 2.60352 + vertex 0.851259 1.41978 2.60581 + endloop + endfacet + facet normal -0.56453 -0.0511907 0.823824 + outer loop + vertex 0.841777 1.41614 2.59945 + vertex 0.844559 1.41792 2.60146 + vertex 0.842742 1.4203 2.60037 + endloop + endfacet + facet normal -0.544261 -0.048922 0.837488 + outer loop + vertex 0.84824 1.41174 2.60349 + vertex 0.847783 1.41735 2.60352 + vertex 0.84501 1.41377 2.60151 + endloop + endfacet + facet normal -0.531631 -0.0516086 0.845402 + outer loop + vertex 0.84824 1.41174 2.60349 + vertex 0.848571 1.40665 2.60339 + vertex 0.851493 1.4096 2.60541 + endloop + endfacet + facet normal -0.562064 -0.0535064 0.825361 + outer loop + vertex 0.842313 1.41084 2.59949 + vertex 0.842673 1.40588 2.59942 + vertex 0.845406 1.40878 2.60146 + endloop + endfacet + facet normal -0.575274 -0.0594433 0.815798 + outer loop + vertex 0.84309 1.40102 2.59935 + vertex 0.842673 1.40588 2.59942 + vertex 0.840022 1.4028 2.59732 + endloop + endfacet + facet normal -0.545474 -0.0630749 0.835751 + outer loop + vertex 0.848599 1.39188 2.60232 + vertex 0.8495 1.39623 2.60323 + vertex 0.846143 1.39436 2.6009 + endloop + endfacet + facet normal -0.534413 -0.0624193 0.842915 + outer loop + vertex 0.848955 1.40165 2.60329 + vertex 0.8495 1.39623 2.60323 + vertex 0.852234 1.39965 2.60522 + endloop + endfacet + facet normal -0.525026 -0.056371 0.849217 + outer loop + vertex 0.855637 1.39734 2.60717 + vertex 0.855043 1.40269 2.60716 + vertex 0.852234 1.39965 2.60522 + endloop + endfacet + facet normal -0.521126 -0.0566984 0.851595 + outer loop + vertex 0.857957 1.39248 2.60827 + vertex 0.858881 1.39697 2.60913 + vertex 0.855637 1.39734 2.60717 + endloop + endfacet + facet normal -0.532545 -0.064389 0.843949 + outer loop + vertex 0.8518 1.39138 2.60433 + vertex 0.854651 1.39315 2.60627 + vertex 0.852744 1.39556 2.60525 + endloop + endfacet + facet normal -0.53981 -0.0658863 0.839205 + outer loop + vertex 0.852536 1.38597 2.60438 + vertex 0.8518 1.39138 2.60433 + vertex 0.849305 1.38772 2.60244 + endloop + endfacet + facet normal -0.542168 -0.0671729 0.837581 + outer loop + vertex 0.853114 1.38101 2.60436 + vertex 0.852536 1.38597 2.60438 + vertex 0.849916 1.38274 2.60242 + endloop + endfacet + facet normal -0.529914 -0.0624036 0.845753 + outer loop + vertex 0.855821 1.38384 2.60631 + vertex 0.858636 1.38677 2.60829 + vertex 0.855222 1.38895 2.60631 + endloop + endfacet + facet normal -0.528436 -0.0590286 0.846919 + outer loop + vertex 0.858636 1.38677 2.60829 + vertex 0.857957 1.39248 2.60827 + vertex 0.855222 1.38895 2.60631 + endloop + endfacet + facet normal -0.507746 -0.0538719 0.859821 + outer loop + vertex 0.864939 1.38761 2.61214 + vertex 0.864627 1.39268 2.61227 + vertex 0.861557 1.38974 2.61028 + endloop + endfacet + facet normal -0.494025 -0.051485 0.867922 + outer loop + vertex 0.864627 1.39268 2.61227 + vertex 0.867753 1.39594 2.61425 + vertex 0.864502 1.39772 2.6125 + endloop + endfacet + facet normal -0.492898 -0.0486344 0.868727 + outer loop + vertex 0.867753 1.39594 2.61425 + vertex 0.867614 1.40105 2.61445 + vertex 0.864502 1.39772 2.6125 + endloop + endfacet + facet normal -0.49293 -0.0485945 0.868711 + outer loop + vertex 0.864502 1.39772 2.6125 + vertex 0.867614 1.40105 2.61445 + vertex 0.864324 1.40277 2.61268 + endloop + endfacet + facet normal -0.516138 -0.0582877 0.85452 + outer loop + vertex 0.858881 1.39697 2.60913 + vertex 0.857957 1.39248 2.60827 + vertex 0.861432 1.39476 2.61052 + endloop + endfacet + facet normal -0.520965 -0.0537537 0.851884 + outer loop + vertex 0.858881 1.39697 2.60913 + vertex 0.858276 1.40111 2.60902 + vertex 0.855637 1.39734 2.60717 + endloop + endfacet + facet normal -0.503106 -0.0487424 0.862849 + outer loop + vertex 0.864502 1.39772 2.6125 + vertex 0.864324 1.40277 2.61268 + vertex 0.861384 1.39955 2.61079 + endloop + endfacet + facet normal -0.492459 -0.0454819 0.869146 + outer loop + vertex 0.864324 1.40277 2.61268 + vertex 0.867294 1.40623 2.61455 + vertex 0.86396 1.40776 2.61274 + endloop + endfacet + facet normal -0.491673 -0.0431076 0.869712 + outer loop + vertex 0.867294 1.40623 2.61455 + vertex 0.866688 1.41166 2.61447 + vertex 0.86396 1.40776 2.61274 + endloop + endfacet + facet normal -0.492608 -0.0422365 0.869226 + outer loop + vertex 0.86396 1.40776 2.61274 + vertex 0.866688 1.41166 2.61447 + vertex 0.863355 1.4119 2.6126 + endloop + endfacet + facet normal -0.510719 -0.049917 0.858297 + outer loop + vertex 0.857913 1.40601 2.60909 + vertex 0.858276 1.40111 2.60902 + vertex 0.861098 1.4044 2.61089 + endloop + endfacet + facet normal -0.513987 -0.0461562 0.856555 + outer loop + vertex 0.857913 1.40601 2.60909 + vertex 0.857727 1.41094 2.60925 + vertex 0.854713 1.40771 2.60726 + endloop + endfacet + facet normal -0.501592 -0.0437282 0.863998 + outer loop + vertex 0.86396 1.40776 2.61274 + vertex 0.863355 1.4119 2.6126 + vertex 0.860813 1.40923 2.61098 + endloop + endfacet + facet normal -0.507622 -0.0422266 0.860544 + outer loop + vertex 0.857643 1.41588 2.60944 + vertex 0.857727 1.41094 2.60925 + vertex 0.860801 1.41396 2.61121 + endloop + endfacet + facet normal -0.50993 -0.0400017 0.859285 + outer loop + vertex 0.857643 1.41588 2.60944 + vertex 0.857495 1.42087 2.60958 + vertex 0.85442 1.41776 2.60761 + endloop + endfacet + facet normal -0.503551 -0.0390857 0.863081 + outer loop + vertex 0.857166 1.42591 2.60962 + vertex 0.857495 1.42087 2.60958 + vertex 0.860509 1.42386 2.61148 + endloop + endfacet + facet normal -0.504949 -0.0383899 0.862295 + outer loop + vertex 0.857166 1.42591 2.60962 + vertex 0.856579 1.43127 2.60951 + vertex 0.853875 1.42763 2.60777 + endloop + endfacet + facet normal -0.503341 -0.037171 0.863288 + outer loop + vertex 0.856579 1.43127 2.60951 + vertex 0.854272 1.4361 2.60838 + vertex 0.853246 1.43171 2.60759 + endloop + endfacet + facet normal -0.495918 -0.0311836 0.867809 + outer loop + vertex 0.857668 1.4354 2.61031 + vertex 0.860697 1.43713 2.61211 + vertex 0.857207 1.43952 2.6102 + endloop + endfacet + facet normal -0.494052 -0.0275184 0.868997 + outer loop + vertex 0.860697 1.43713 2.61211 + vertex 0.860152 1.4425 2.61197 + vertex 0.857207 1.43952 2.6102 + endloop + endfacet + facet normal -0.491307 -0.0271994 0.870562 + outer loop + vertex 0.860697 1.43713 2.61211 + vertex 0.863452 1.4409 2.61378 + vertex 0.860152 1.4425 2.61197 + endloop + endfacet + facet normal -0.489995 -0.0235521 0.871407 + outer loop + vertex 0.863452 1.4409 2.61378 + vertex 0.863153 1.44583 2.61374 + vertex 0.860152 1.4425 2.61197 + endloop + endfacet + facet normal -0.489614 -0.0240041 0.871609 + outer loop + vertex 0.860152 1.4425 2.61197 + vertex 0.863153 1.44583 2.61374 + vertex 0.85987 1.44757 2.61195 + endloop + endfacet + facet normal -0.496182 -0.0286544 0.867746 + outer loop + vertex 0.853432 1.44679 2.60828 + vertex 0.853803 1.44162 2.60832 + vertex 0.856803 1.44454 2.61013 + endloop + endfacet + facet normal -0.490729 -0.0218013 0.871039 + outer loop + vertex 0.85987 1.44757 2.61195 + vertex 0.859768 1.45261 2.61202 + vertex 0.856544 1.44966 2.61013 + endloop + endfacet + facet normal -0.488349 -0.0217714 0.872377 + outer loop + vertex 0.85987 1.44757 2.61195 + vertex 0.863024 1.45085 2.6138 + vertex 0.859768 1.45261 2.61202 + endloop + endfacet + facet normal -0.487839 -0.0205072 0.872693 + outer loop + vertex 0.863024 1.45085 2.6138 + vertex 0.862973 1.45588 2.61389 + vertex 0.859768 1.45261 2.61202 + endloop + endfacet + facet normal -0.487318 -0.021175 0.872968 + outer loop + vertex 0.859768 1.45261 2.61202 + vertex 0.862973 1.45588 2.61389 + vertex 0.859739 1.4576 2.61212 + endloop + endfacet + facet normal -0.491842 -0.0235683 0.870365 + outer loop + vertex 0.854032 1.45683 2.60889 + vertex 0.85298 1.45237 2.60818 + vertex 0.856582 1.45465 2.61028 + endloop + endfacet + facet normal -0.49711 -0.0226176 0.867393 + outer loop + vertex 0.854032 1.45683 2.60889 + vertex 0.85349 1.46095 2.60869 + vertex 0.850743 1.45718 2.60702 + endloop + endfacet + facet normal -0.498324 -0.0214374 0.866726 + outer loop + vertex 0.850743 1.45718 2.60702 + vertex 0.85349 1.46095 2.60869 + vertex 0.850245 1.46251 2.60686 + endloop + endfacet + facet normal -0.498727 -0.0225817 0.866465 + outer loop + vertex 0.85349 1.46095 2.60869 + vertex 0.853217 1.46585 2.60866 + vertex 0.850245 1.46251 2.60686 + endloop + endfacet + facet normal -0.498917 -0.0223571 0.866361 + outer loop + vertex 0.850245 1.46251 2.60686 + vertex 0.853217 1.46585 2.60866 + vertex 0.850013 1.46752 2.60686 + endloop + endfacet + facet normal -0.498607 -0.0215442 0.866561 + outer loop + vertex 0.853217 1.46585 2.60866 + vertex 0.853115 1.47085 2.60873 + vertex 0.850013 1.46752 2.60686 + endloop + endfacet + facet normal -0.489181 -0.0209502 0.87193 + outer loop + vertex 0.859739 1.4576 2.61212 + vertex 0.859677 1.46259 2.61221 + vertex 0.85662 1.45941 2.61042 + endloop + endfacet + facet normal -0.486484 -0.0209425 0.873439 + outer loop + vertex 0.859739 1.4576 2.61212 + vertex 0.862924 1.46091 2.61398 + vertex 0.859677 1.46259 2.61221 + endloop + endfacet + facet normal -0.486061 -0.0198478 0.873699 + outer loop + vertex 0.862924 1.46091 2.61398 + vertex 0.86286 1.46595 2.61405 + vertex 0.859677 1.46259 2.61221 + endloop + endfacet + facet normal -0.485495 -0.0205472 0.873998 + outer loop + vertex 0.859677 1.46259 2.61221 + vertex 0.86286 1.46595 2.61405 + vertex 0.859593 1.46761 2.61228 + endloop + endfacet + facet normal -0.490332 -0.0220865 0.871256 + outer loop + vertex 0.853217 1.46585 2.60866 + vertex 0.85349 1.46095 2.60869 + vertex 0.856448 1.46425 2.61044 + endloop + endfacet + facet normal -0.48704 -0.0190268 0.873173 + outer loop + vertex 0.859593 1.46761 2.61228 + vertex 0.85954 1.47264 2.61236 + vertex 0.85634 1.46924 2.6105 + endloop + endfacet + facet normal -0.484824 -0.0190228 0.874405 + outer loop + vertex 0.859593 1.46761 2.61228 + vertex 0.862798 1.47098 2.61413 + vertex 0.85954 1.47264 2.61236 + endloop + endfacet + facet normal -0.484119 -0.0171834 0.874833 + outer loop + vertex 0.862798 1.47098 2.61413 + vertex 0.862748 1.47599 2.6142 + vertex 0.85954 1.47264 2.61236 + endloop + endfacet + facet normal -0.484609 -0.0165728 0.874574 + outer loop + vertex 0.85954 1.47264 2.61236 + vertex 0.862748 1.47599 2.6142 + vertex 0.859505 1.47765 2.61243 + endloop + endfacet + facet normal -0.48913 -0.019046 0.872003 + outer loop + vertex 0.853087 1.47585 2.60882 + vertex 0.853115 1.47085 2.60873 + vertex 0.856299 1.47426 2.61059 + endloop + endfacet + facet normal -0.497897 -0.0190003 0.867028 + outer loop + vertex 0.853115 1.47085 2.60873 + vertex 0.853087 1.47585 2.60882 + vertex 0.849938 1.47251 2.60694 + endloop + endfacet + facet normal -0.498788 -0.0213196 0.866462 + outer loop + vertex 0.850013 1.46752 2.60686 + vertex 0.853115 1.47085 2.60873 + vertex 0.849938 1.47251 2.60694 + endloop + endfacet + facet normal -0.498568 -0.0181603 0.86666 + outer loop + vertex 0.849938 1.47251 2.60694 + vertex 0.853087 1.47585 2.60882 + vertex 0.849914 1.47751 2.60703 + endloop + endfacet + facet normal -0.497207 -0.0146454 0.867508 + outer loop + vertex 0.853087 1.47585 2.60882 + vertex 0.853066 1.48084 2.60889 + vertex 0.849914 1.47751 2.60703 + endloop + endfacet + facet normal -0.497682 -0.0140505 0.867246 + outer loop + vertex 0.849914 1.47751 2.60703 + vertex 0.853066 1.48084 2.60889 + vertex 0.849885 1.48251 2.60709 + endloop + endfacet + facet normal -0.496428 -0.010836 0.86801 + outer loop + vertex 0.853066 1.48084 2.60889 + vertex 0.853031 1.48583 2.60893 + vertex 0.849885 1.48251 2.60709 + endloop + endfacet + facet normal -0.497058 -0.0100456 0.867659 + outer loop + vertex 0.849885 1.48251 2.60709 + vertex 0.853031 1.48583 2.60893 + vertex 0.849843 1.48751 2.60713 + endloop + endfacet + facet normal -0.496322 -0.00816913 0.8681 + outer loop + vertex 0.853031 1.48583 2.60893 + vertex 0.85299 1.49082 2.60896 + vertex 0.849843 1.48751 2.60713 + endloop + endfacet + facet normal -0.497157 -0.0071163 0.867631 + outer loop + vertex 0.849843 1.48751 2.60713 + vertex 0.85299 1.49082 2.60896 + vertex 0.849802 1.49249 2.60715 + endloop + endfacet + facet normal -0.497079 -0.0069181 0.867678 + outer loop + vertex 0.85299 1.49082 2.60896 + vertex 0.852956 1.49581 2.60898 + vertex 0.849802 1.49249 2.60715 + endloop + endfacet + facet normal -0.497751 -0.00606784 0.867299 + outer loop + vertex 0.849802 1.49249 2.60715 + vertex 0.852956 1.49581 2.60898 + vertex 0.84977 1.49748 2.60716 + endloop + endfacet + facet normal -0.485432 -0.0126323 0.874183 + outer loop + vertex 0.859505 1.47765 2.61243 + vertex 0.85947 1.48264 2.61249 + vertex 0.856277 1.47926 2.61066 + endloop + endfacet + facet normal -0.484303 -0.0126309 0.874809 + outer loop + vertex 0.859505 1.47765 2.61243 + vertex 0.862702 1.48099 2.61425 + vertex 0.85947 1.48264 2.61249 + endloop + endfacet + facet normal -0.483218 -0.0098399 0.875445 + outer loop + vertex 0.862702 1.48099 2.61425 + vertex 0.862661 1.48597 2.61429 + vertex 0.85947 1.48264 2.61249 + endloop + endfacet + facet normal -0.483651 -0.0092994 0.875212 + outer loop + vertex 0.85947 1.48264 2.61249 + vertex 0.862661 1.48597 2.61429 + vertex 0.859433 1.48763 2.61252 + endloop + endfacet + facet normal -0.482696 -0.00685254 0.875761 + outer loop + vertex 0.862661 1.48597 2.61429 + vertex 0.862629 1.49096 2.61431 + vertex 0.859433 1.48763 2.61252 + endloop + endfacet + facet normal -0.482345 -0.00729064 0.875951 + outer loop + vertex 0.859433 1.48763 2.61252 + vertex 0.862629 1.49096 2.61431 + vertex 0.8594 1.49262 2.61254 + endloop + endfacet + facet normal -0.481829 -0.00597146 0.876245 + outer loop + vertex 0.862629 1.49096 2.61431 + vertex 0.862605 1.49595 2.61433 + vertex 0.8594 1.49262 2.61254 + endloop + endfacet + facet normal -0.488537 -0.0108174 0.872476 + outer loop + vertex 0.853031 1.48583 2.60893 + vertex 0.853066 1.48084 2.60889 + vertex 0.856245 1.48425 2.61071 + endloop + endfacet + facet normal -0.48505 -0.00730151 0.874456 + outer loop + vertex 0.859433 1.48763 2.61252 + vertex 0.8594 1.49262 2.61254 + vertex 0.856207 1.48924 2.61074 + endloop + endfacet + facet normal -0.48087 -0.00717016 0.876762 + outer loop + vertex 0.8594 1.49262 2.61254 + vertex 0.862605 1.49595 2.61433 + vertex 0.859371 1.49761 2.61257 + endloop + endfacet + facet normal -0.488581 -0.00687873 0.872492 + outer loop + vertex 0.852956 1.49581 2.60898 + vertex 0.85299 1.49082 2.60896 + vertex 0.856172 1.49422 2.61077 + endloop + endfacet + facet normal -0.497802 -0.00619783 0.867268 + outer loop + vertex 0.852956 1.49581 2.60898 + vertex 0.852929 1.5008 2.609 + vertex 0.84977 1.49748 2.60716 + endloop + endfacet + facet normal -0.498932 -0.00476639 0.866628 + outer loop + vertex 0.84977 1.49748 2.60716 + vertex 0.852929 1.5008 2.609 + vertex 0.849749 1.50247 2.60718 + endloop + endfacet + facet normal -0.498735 -0.00426443 0.866744 + outer loop + vertex 0.852929 1.5008 2.609 + vertex 0.85291 1.50579 2.60901 + vertex 0.849749 1.50247 2.60718 + endloop + endfacet + facet normal -0.499874 -0.00281838 0.866093 + outer loop + vertex 0.849749 1.50247 2.60718 + vertex 0.85291 1.50579 2.60901 + vertex 0.849737 1.50746 2.60719 + endloop + endfacet + facet normal -0.484312 -0.00631097 0.874873 + outer loop + vertex 0.859371 1.49761 2.61257 + vertex 0.859345 1.5026 2.61259 + vertex 0.856142 1.49921 2.61079 + endloop + endfacet + facet normal -0.479835 -0.00629848 0.877336 + outer loop + vertex 0.859371 1.49761 2.61257 + vertex 0.862584 1.50095 2.61435 + vertex 0.859345 1.5026 2.61259 + endloop + endfacet + facet normal -0.479255 -0.00481778 0.877663 + outer loop + vertex 0.862584 1.50095 2.61435 + vertex 0.862565 1.50594 2.61437 + vertex 0.859345 1.5026 2.61259 + endloop + endfacet + facet normal -0.47958 -0.00440958 0.877487 + outer loop + vertex 0.859345 1.5026 2.61259 + vertex 0.862565 1.50594 2.61437 + vertex 0.859325 1.50759 2.6126 + endloop + endfacet + facet normal -0.490622 -0.0042469 0.871362 + outer loop + vertex 0.85291 1.50579 2.60901 + vertex 0.852929 1.5008 2.609 + vertex 0.856117 1.50421 2.61081 + endloop + endfacet + facet normal -0.499469 -0.00179259 0.86633 + outer loop + vertex 0.85291 1.50579 2.60901 + vertex 0.852902 1.51078 2.60902 + vertex 0.849737 1.50746 2.60719 + endloop + endfacet + facet normal -0.500083 -0.00101289 0.865977 + outer loop + vertex 0.849737 1.50746 2.60719 + vertex 0.852902 1.51078 2.60902 + vertex 0.849734 1.51246 2.60719 + endloop + endfacet + facet normal -0.499813 -0.000332659 0.866133 + outer loop + vertex 0.852902 1.51078 2.60902 + vertex 0.8529 1.51577 2.60902 + vertex 0.849734 1.51246 2.60719 + endloop + endfacet + facet normal -0.499885 -0.000240647 0.866092 + outer loop + vertex 0.849734 1.51246 2.60719 + vertex 0.8529 1.51577 2.60902 + vertex 0.849736 1.51745 2.60719 + endloop + endfacet + facet normal -0.484713 -0.00108126 0.874672 + outer loop + vertex 0.859325 1.50759 2.6126 + vertex 0.859316 1.51259 2.6126 + vertex 0.856102 1.5092 2.61082 + endloop + endfacet + facet normal -0.479342 -0.0010717 0.877627 + outer loop + vertex 0.859325 1.50759 2.6126 + vertex 0.862554 1.51093 2.61437 + vertex 0.859316 1.51259 2.6126 + endloop + endfacet + facet normal -0.478605 0.000798674 0.87803 + outer loop + vertex 0.862554 1.51093 2.61437 + vertex 0.862554 1.51592 2.61437 + vertex 0.859316 1.51259 2.6126 + endloop + endfacet + facet normal -0.479009 0.00130734 0.877809 + outer loop + vertex 0.859316 1.51259 2.6126 + vertex 0.862554 1.51592 2.61437 + vertex 0.859317 1.51758 2.6126 + endloop + endfacet + facet normal -0.490597 -0.000330581 0.871386 + outer loop + vertex 0.8529 1.51577 2.60902 + vertex 0.852902 1.51078 2.60902 + vertex 0.856097 1.51419 2.61082 + endloop + endfacet + facet normal -0.499862 -0.000182935 0.866105 + outer loop + vertex 0.8529 1.51577 2.60902 + vertex 0.8529 1.52076 2.60902 + vertex 0.849736 1.51745 2.60719 + endloop + endfacet + facet normal -0.483728 0.00198272 0.875216 + outer loop + vertex 0.859317 1.51758 2.6126 + vertex 0.85932 1.52257 2.61259 + vertex 0.856097 1.51918 2.61081 + endloop + endfacet + facet normal -0.477777 0.00198447 0.878479 + outer loop + vertex 0.859317 1.51758 2.6126 + vertex 0.862561 1.52091 2.61435 + vertex 0.85932 1.52257 2.61259 + endloop + endfacet + facet normal -0.477161 0.00354155 0.878809 + outer loop + vertex 0.862561 1.52091 2.61435 + vertex 0.862568 1.52591 2.61434 + vertex 0.85932 1.52257 2.61259 + endloop + endfacet + facet normal -0.475809 0.00183816 0.879547 + outer loop + vertex 0.85932 1.52257 2.61259 + vertex 0.862568 1.52591 2.61434 + vertex 0.859321 1.52756 2.61258 + endloop + endfacet + facet normal -0.488465 -0.000713156 0.872583 + outer loop + vertex 0.852897 1.52576 2.60902 + vertex 0.8529 1.52076 2.60902 + vertex 0.856096 1.52418 2.61081 + endloop + endfacet + facet normal -0.500564 -0.000510614 0.865699 + outer loop + vertex 0.852897 1.52576 2.60902 + vertex 0.85289 1.53075 2.60902 + vertex 0.849737 1.52743 2.6072 + endloop + endfacet + facet normal -0.479566 0.00215046 0.877503 + outer loop + vertex 0.859321 1.52756 2.61258 + vertex 0.859321 1.53256 2.61257 + vertex 0.85609 1.52917 2.61081 + endloop + endfacet + facet normal -0.473727 0.00215867 0.880669 + outer loop + vertex 0.859321 1.52756 2.61258 + vertex 0.862575 1.5309 2.61432 + vertex 0.859321 1.53256 2.61257 + endloop + endfacet + facet normal -0.472581 0.00504865 0.881273 + outer loop + vertex 0.862575 1.5309 2.61432 + vertex 0.862586 1.53589 2.6143 + vertex 0.859321 1.53256 2.61257 + endloop + endfacet + facet normal -0.472099 0.00444079 0.881535 + outer loop + vertex 0.859321 1.53256 2.61257 + vertex 0.862586 1.53589 2.6143 + vertex 0.859326 1.53755 2.61254 + endloop + endfacet + facet normal -0.48786 0.00215196 0.872919 + outer loop + vertex 0.852889 1.53574 2.60901 + vertex 0.85289 1.53075 2.60902 + vertex 0.856085 1.53416 2.6108 + endloop + endfacet + facet normal -0.503555 0.00625943 0.863941 + outer loop + vertex 0.852889 1.53574 2.60901 + vertex 0.8529 1.54073 2.60898 + vertex 0.849751 1.53741 2.60717 + endloop + endfacet + facet normal -0.476721 0.00729034 0.879025 + outer loop + vertex 0.859326 1.53755 2.61254 + vertex 0.859342 1.54254 2.61251 + vertex 0.856089 1.53915 2.61077 + endloop + endfacet + facet normal -0.47116 0.007292 0.882018 + outer loop + vertex 0.859326 1.53755 2.61254 + vertex 0.862605 1.54088 2.61427 + vertex 0.859342 1.54254 2.61251 + endloop + endfacet + facet normal -0.470368 0.00928142 0.882422 + outer loop + vertex 0.862605 1.54088 2.61427 + vertex 0.862634 1.54587 2.61423 + vertex 0.859342 1.54254 2.61251 + endloop + endfacet + facet normal -0.4713 0.0104651 0.881911 + outer loop + vertex 0.859342 1.54254 2.61251 + vertex 0.862634 1.54587 2.61423 + vertex 0.859372 1.54753 2.61247 + endloop + endfacet + facet normal -0.489855 0.0109856 0.871735 + outer loop + vertex 0.852929 1.54573 2.60893 + vertex 0.8529 1.54073 2.60898 + vertex 0.856107 1.54414 2.61074 + endloop + endfacet + facet normal -0.507213 0.0147013 0.861695 + outer loop + vertex 0.852929 1.54573 2.60893 + vertex 0.852975 1.55073 2.60887 + vertex 0.849823 1.5474 2.60707 + endloop + endfacet + facet normal -0.477829 0.0134098 0.87835 + outer loop + vertex 0.859372 1.54753 2.61247 + vertex 0.859417 1.55253 2.61242 + vertex 0.856143 1.54914 2.61069 + endloop + endfacet + facet normal -0.472159 0.0133897 0.881412 + outer loop + vertex 0.859372 1.54753 2.61247 + vertex 0.862672 1.55086 2.61418 + vertex 0.859417 1.55253 2.61242 + endloop + endfacet + facet normal -0.471742 0.0144284 0.881619 + outer loop + vertex 0.862672 1.55086 2.61418 + vertex 0.862724 1.55586 2.61413 + vertex 0.859417 1.55253 2.61242 + endloop + endfacet + facet normal -0.47356 0.0167555 0.880602 + outer loop + vertex 0.859417 1.55253 2.61242 + vertex 0.862724 1.55586 2.61413 + vertex 0.859483 1.55752 2.61236 + endloop + endfacet + facet normal -0.492296 0.0180813 0.87024 + outer loop + vertex 0.853041 1.55573 2.60881 + vertex 0.852975 1.55073 2.60887 + vertex 0.8562 1.55414 2.61063 + endloop + endfacet + facet normal -0.508701 0.0209749 0.860688 + outer loop + vertex 0.853041 1.55573 2.60881 + vertex 0.853106 1.56072 2.60872 + vertex 0.849961 1.55739 2.60695 + endloop + endfacet + facet normal -0.481118 0.0193341 0.876443 + outer loop + vertex 0.859483 1.55752 2.61236 + vertex 0.859561 1.5625 2.61229 + vertex 0.856273 1.55913 2.61056 + endloop + endfacet + facet normal -0.4751 0.0192844 0.87972 + outer loop + vertex 0.859483 1.55752 2.61236 + vertex 0.862792 1.56085 2.61407 + vertex 0.859561 1.5625 2.61229 + endloop + endfacet + facet normal -0.475118 0.0192411 0.879712 + outer loop + vertex 0.862792 1.56085 2.61407 + vertex 0.862868 1.56582 2.614 + vertex 0.859561 1.5625 2.61229 + endloop + endfacet + facet normal -0.476804 0.0214179 0.878748 + outer loop + vertex 0.859561 1.5625 2.61229 + vertex 0.862868 1.56582 2.614 + vertex 0.859631 1.56747 2.61221 + endloop + endfacet + facet normal -0.494116 0.0232825 0.869084 + outer loop + vertex 0.853085 1.56567 2.60858 + vertex 0.853106 1.56072 2.60872 + vertex 0.85633 1.56412 2.61047 + endloop + endfacet + facet normal -0.485584 0.0222474 0.873907 + outer loop + vertex 0.859631 1.56747 2.61221 + vertex 0.859701 1.57245 2.61212 + vertex 0.85632 1.56915 2.61032 + endloop + endfacet + facet normal -0.478802 0.0222177 0.877642 + outer loop + vertex 0.859631 1.56747 2.61221 + vertex 0.862945 1.57079 2.61393 + vertex 0.859701 1.57245 2.61212 + endloop + endfacet + facet normal -0.479363 0.0208283 0.877369 + outer loop + vertex 0.862945 1.57079 2.61393 + vertex 0.86302 1.57575 2.61385 + vertex 0.859701 1.57245 2.61212 + endloop + endfacet + facet normal -0.480803 0.0227179 0.876534 + outer loop + vertex 0.859701 1.57245 2.61212 + vertex 0.86302 1.57575 2.61385 + vertex 0.859795 1.57743 2.61204 + endloop + endfacet + facet normal -0.498047 0.0261383 0.866756 + outer loop + vertex 0.853265 1.57637 2.60836 + vertex 0.852681 1.57091 2.60819 + vertex 0.85641 1.57424 2.61023 + endloop + endfacet + facet normal -0.489561 0.024783 0.871617 + outer loop + vertex 0.859795 1.57743 2.61204 + vertex 0.859897 1.5824 2.61196 + vertex 0.856609 1.57931 2.6102 + endloop + endfacet + facet normal -0.48282 0.0247087 0.875371 + outer loop + vertex 0.859795 1.57743 2.61204 + vertex 0.863096 1.58071 2.61377 + vertex 0.859897 1.5824 2.61196 + endloop + endfacet + facet normal -0.482534 0.0254016 0.875509 + outer loop + vertex 0.863096 1.58071 2.61377 + vertex 0.863155 1.58568 2.61366 + vertex 0.859897 1.5824 2.61196 + endloop + endfacet + facet normal -0.484589 0.0280716 0.874291 + outer loop + vertex 0.859897 1.5824 2.61196 + vertex 0.863155 1.58568 2.61366 + vertex 0.859986 1.58729 2.61185 + endloop + endfacet + facet normal -0.485935 0.0316537 0.873422 + outer loop + vertex 0.859986 1.58729 2.61185 + vertex 0.863125 1.59064 2.61347 + vertex 0.859984 1.59182 2.61168 + endloop + endfacet + facet normal -0.485239 0.0339514 0.873722 + outer loop + vertex 0.859984 1.59182 2.61168 + vertex 0.863125 1.59064 2.61347 + vertex 0.862747 1.59589 2.61306 + endloop + endfacet + facet normal -0.503627 0.0346445 0.863226 + outer loop + vertex 0.854403 1.59217 2.60845 + vertex 0.853781 1.58654 2.60832 + vertex 0.857054 1.58914 2.61012 + endloop + endfacet + facet normal -0.530575 0.0389904 0.846741 + outer loop + vertex 0.847698 1.59568 2.60419 + vertex 0.84758 1.59062 2.60435 + vertex 0.850839 1.59401 2.60623 + endloop + endfacet + facet normal -0.513768 0.0359116 0.857177 + outer loop + vertex 0.853781 1.58654 2.60832 + vertex 0.854403 1.59217 2.60845 + vertex 0.850706 1.58876 2.60638 + endloop + endfacet + facet normal -0.50181 0.0305768 0.864438 + outer loop + vertex 0.853781 1.58654 2.60832 + vertex 0.853518 1.58142 2.60834 + vertex 0.856784 1.5843 2.61014 + endloop + endfacet + facet normal -0.51272 0.0283512 0.858088 + outer loop + vertex 0.853265 1.57637 2.60836 + vertex 0.853518 1.58142 2.60834 + vertex 0.850302 1.57858 2.60652 + endloop + endfacet + facet normal -0.530353 0.0319303 0.847175 + outer loop + vertex 0.847452 1.58553 2.60448 + vertex 0.847332 1.58052 2.60459 + vertex 0.850481 1.58356 2.60645 + endloop + endfacet + facet normal -0.529666 0.0301709 0.84767 + outer loop + vertex 0.850302 1.57858 2.60652 + vertex 0.847237 1.57567 2.60471 + vertex 0.850045 1.57383 2.60652 + endloop + endfacet + facet normal -0.560848 0.0312938 0.827327 + outer loop + vertex 0.844281 1.5774 2.60271 + vertex 0.844364 1.58235 2.60258 + vertex 0.841325 1.57928 2.60064 + endloop + endfacet + facet normal -0.546707 0.0301422 0.836781 + outer loop + vertex 0.844287 1.57246 2.60289 + vertex 0.847237 1.57567 2.60471 + vertex 0.844281 1.5774 2.60271 + endloop + endfacet + facet normal -0.559142 0.0263717 0.828652 + outer loop + vertex 0.844652 1.56717 2.60331 + vertex 0.844287 1.57246 2.60289 + vertex 0.84119 1.56925 2.60091 + endloop + endfacet + facet normal -0.547023 0.0235979 0.836785 + outer loop + vertex 0.844652 1.56717 2.60331 + vertex 0.844063 1.56155 2.60308 + vertex 0.84723 1.56412 2.60508 + endloop + endfacet + facet normal -0.546827 0.0211694 0.836978 + outer loop + vertex 0.844063 1.56155 2.60308 + vertex 0.843865 1.55641 2.60308 + vertex 0.846982 1.55927 2.60505 + endloop + endfacet + facet normal -0.572206 0.0212668 0.819834 + outer loop + vertex 0.837373 1.56094 2.5985 + vertex 0.837756 1.55562 2.5989 + vertex 0.840792 1.55869 2.60094 + endloop + endfacet + facet normal -0.580262 0.0202566 0.814178 + outer loop + vertex 0.834907 1.55704 2.59684 + vertex 0.837756 1.55562 2.5989 + vertex 0.837373 1.56094 2.5985 + endloop + endfacet + facet normal -0.580875 0.0178225 0.813797 + outer loop + vertex 0.837804 1.55064 2.59905 + vertex 0.837756 1.55562 2.5989 + vertex 0.83494 1.55245 2.59696 + endloop + endfacet + facet normal -0.581474 0.0164206 0.813399 + outer loop + vertex 0.834893 1.54752 2.59703 + vertex 0.837804 1.55064 2.59905 + vertex 0.83494 1.55245 2.59696 + endloop + endfacet + facet normal -0.581487 0.016439 0.813389 + outer loop + vertex 0.837772 1.54565 2.59912 + vertex 0.837804 1.55064 2.59905 + vertex 0.834893 1.54752 2.59703 + endloop + endfacet + facet normal -0.581843 0.0156204 0.813151 + outer loop + vertex 0.834846 1.54251 2.59709 + vertex 0.837772 1.54565 2.59912 + vertex 0.834893 1.54752 2.59703 + endloop + endfacet + facet normal -0.560626 0.0187727 0.827856 + outer loop + vertex 0.843789 1.55139 2.60314 + vertex 0.843865 1.55641 2.60308 + vertex 0.840786 1.55358 2.60106 + endloop + endfacet + facet normal -0.547073 0.0172075 0.836908 + outer loop + vertex 0.843789 1.55139 2.60314 + vertex 0.843728 1.54641 2.60321 + vertex 0.846787 1.54928 2.60515 + endloop + endfacet + facet normal -0.572261 0.016481 0.819906 + outer loop + vertex 0.837804 1.55064 2.59905 + vertex 0.837772 1.54565 2.59912 + vertex 0.840755 1.54859 2.60115 + endloop + endfacet + facet normal -0.581907 0.0157116 0.813103 + outer loop + vertex 0.837723 1.54067 2.59919 + vertex 0.837772 1.54565 2.59912 + vertex 0.834846 1.54251 2.59709 + endloop + endfacet + facet normal -0.582717 0.0138314 0.812558 + outer loop + vertex 0.83481 1.53752 2.59715 + vertex 0.837723 1.54067 2.59919 + vertex 0.834846 1.54251 2.59709 + endloop + endfacet + facet normal -0.582478 0.0134957 0.812735 + outer loop + vertex 0.83768 1.53568 2.59924 + vertex 0.837723 1.54067 2.59919 + vertex 0.83481 1.53752 2.59715 + endloop + endfacet + facet normal -0.560765 0.0156236 0.827827 + outer loop + vertex 0.843668 1.54143 2.60326 + vertex 0.843728 1.54641 2.60321 + vertex 0.840701 1.54361 2.60121 + endloop + endfacet + facet normal -0.545259 0.0127206 0.838171 + outer loop + vertex 0.843668 1.54143 2.60326 + vertex 0.843617 1.53644 2.6033 + vertex 0.846681 1.53931 2.60525 + endloop + endfacet + facet normal -0.572672 0.0134823 0.819673 + outer loop + vertex 0.837723 1.54067 2.59919 + vertex 0.83768 1.53568 2.59924 + vertex 0.840645 1.53862 2.60126 + endloop + endfacet + facet normal -0.582435 0.0104899 0.81281 + outer loop + vertex 0.837648 1.53068 2.59928 + vertex 0.83768 1.53568 2.59924 + vertex 0.834779 1.53253 2.5972 + endloop + endfacet + facet normal -0.583101 0.00893319 0.81235 + outer loop + vertex 0.834754 1.52753 2.59724 + vertex 0.837648 1.53068 2.59928 + vertex 0.834779 1.53253 2.5972 + endloop + endfacet + facet normal -0.582105 0.00754623 0.813078 + outer loop + vertex 0.837626 1.52569 2.59931 + vertex 0.837648 1.53068 2.59928 + vertex 0.834754 1.52753 2.59724 + endloop + endfacet + facet normal -0.558474 0.00902791 0.829473 + outer loop + vertex 0.843585 1.53145 2.60334 + vertex 0.843617 1.53644 2.6033 + vertex 0.840602 1.53363 2.6013 + endloop + endfacet + facet normal -0.540135 0.00535771 0.841562 + outer loop + vertex 0.843585 1.53145 2.60334 + vertex 0.843567 1.52646 2.60336 + vertex 0.846632 1.52933 2.6053 + endloop + endfacet + facet normal -0.571416 0.00754714 0.820626 + outer loop + vertex 0.837648 1.53068 2.59928 + vertex 0.837626 1.52569 2.59931 + vertex 0.840575 1.52864 2.60134 + endloop + endfacet + facet normal -0.582146 0.00594958 0.813062 + outer loop + vertex 0.837609 1.5207 2.59933 + vertex 0.837626 1.52569 2.59931 + vertex 0.834734 1.52254 2.59726 + endloop + endfacet + facet normal -0.582581 0.0049274 0.812757 + outer loop + vertex 0.834718 1.51755 2.59728 + vertex 0.837609 1.5207 2.59933 + vertex 0.834734 1.52254 2.59726 + endloop + endfacet + facet normal -0.581974 0.00408382 0.813197 + outer loop + vertex 0.837596 1.5157 2.59935 + vertex 0.837609 1.5207 2.59933 + vertex 0.834718 1.51755 2.59728 + endloop + endfacet + facet normal -0.554816 0.00366867 0.831965 + outer loop + vertex 0.843554 1.52146 2.60337 + vertex 0.843567 1.52646 2.60336 + vertex 0.840556 1.52365 2.60136 + endloop + endfacet + facet normal -0.534979 0.00253221 0.844862 + outer loop + vertex 0.843554 1.52146 2.60337 + vertex 0.843543 1.51647 2.60338 + vertex 0.846618 1.51934 2.60532 + endloop + endfacet + facet normal -0.569644 0.0040814 0.821882 + outer loop + vertex 0.837609 1.5207 2.59933 + vertex 0.837596 1.5157 2.59935 + vertex 0.840541 1.51866 2.60138 + endloop + endfacet + facet normal -0.581993 0.00186111 0.813191 + outer loop + vertex 0.83759 1.51071 2.59936 + vertex 0.837596 1.5157 2.59935 + vertex 0.834711 1.51256 2.59729 + endloop + endfacet + facet normal -0.583121 -0.000805934 0.812385 + outer loop + vertex 0.834717 1.50757 2.59729 + vertex 0.83759 1.51071 2.59936 + vertex 0.834711 1.51256 2.59729 + endloop + endfacet + facet normal -0.582139 -0.00216271 0.813087 + outer loop + vertex 0.8376 1.50572 2.59935 + vertex 0.83759 1.51071 2.59936 + vertex 0.834717 1.50757 2.59729 + endloop + endfacet + facet normal -0.551893 0.00108417 0.833914 + outer loop + vertex 0.843537 1.51148 2.60338 + vertex 0.843543 1.51647 2.60338 + vertex 0.840531 1.51366 2.60139 + endloop + endfacet + facet normal -0.533172 -0.000965072 0.846006 + outer loop + vertex 0.843537 1.51148 2.60338 + vertex 0.843539 1.50649 2.60338 + vertex 0.84661 1.50936 2.60531 + endloop + endfacet + facet normal -0.569458 -0.00214867 0.822018 + outer loop + vertex 0.83759 1.51071 2.59936 + vertex 0.8376 1.50572 2.59935 + vertex 0.840529 1.50867 2.60139 + endloop + endfacet + facet normal -0.582615 -0.0058219 0.812727 + outer loop + vertex 0.837623 1.50073 2.59933 + vertex 0.8376 1.50572 2.59935 + vertex 0.834739 1.50257 2.59728 + endloop + endfacet + facet normal -0.583724 -0.00847026 0.811908 + outer loop + vertex 0.834775 1.49758 2.59725 + vertex 0.837623 1.50073 2.59933 + vertex 0.834739 1.50257 2.59728 + endloop + endfacet + facet normal -0.583428 -0.00887577 0.812117 + outer loop + vertex 0.837659 1.49574 2.5993 + vertex 0.837623 1.50073 2.59933 + vertex 0.834775 1.49758 2.59725 + endloop + endfacet + facet normal -0.552227 -0.00359463 0.833686 + outer loop + vertex 0.843553 1.5015 2.60336 + vertex 0.843539 1.50649 2.60338 + vertex 0.84054 1.50368 2.60138 + endloop + endfacet + facet normal -0.533906 -0.00584869 0.845524 + outer loop + vertex 0.843553 1.5015 2.60336 + vertex 0.84358 1.49651 2.60335 + vertex 0.846633 1.49938 2.60529 + endloop + endfacet + facet normal -0.571026 -0.00883876 0.820884 + outer loop + vertex 0.837623 1.50073 2.59933 + vertex 0.837659 1.49574 2.5993 + vertex 0.840566 1.49869 2.60136 + endloop + endfacet + facet normal -0.583979 -0.0112158 0.811691 + outer loop + vertex 0.837694 1.49074 2.59926 + vertex 0.837659 1.49574 2.5993 + vertex 0.834814 1.49258 2.59721 + endloop + endfacet + facet normal -0.584677 -0.0128931 0.811164 + outer loop + vertex 0.834841 1.48759 2.59715 + vertex 0.837694 1.49074 2.59926 + vertex 0.834814 1.49258 2.59721 + endloop + endfacet + facet normal -0.584243 -0.0134868 0.811466 + outer loop + vertex 0.837719 1.48574 2.59919 + vertex 0.837694 1.49074 2.59926 + vertex 0.834841 1.48759 2.59715 + endloop + endfacet + facet normal -0.555555 -0.00748531 0.831446 + outer loop + vertex 0.843616 1.49152 2.60332 + vertex 0.84358 1.49651 2.60335 + vertex 0.840602 1.4937 2.60133 + endloop + endfacet + facet normal -0.53677 -0.0102398 0.843666 + outer loop + vertex 0.843616 1.49152 2.60332 + vertex 0.843658 1.48652 2.60329 + vertex 0.846701 1.4894 2.60526 + endloop + endfacet + facet normal -0.574193 -0.0135305 0.818608 + outer loop + vertex 0.837694 1.49074 2.59926 + vertex 0.837719 1.48574 2.59919 + vertex 0.840638 1.4887 2.60129 + endloop + endfacet + facet normal -0.584491 -0.016254 0.811238 + outer loop + vertex 0.837746 1.48074 2.59911 + vertex 0.837719 1.48574 2.59919 + vertex 0.83486 1.48261 2.59707 + endloop + endfacet + facet normal -0.585275 -0.0181294 0.810632 + outer loop + vertex 0.834917 1.47765 2.597 + vertex 0.837746 1.48074 2.59911 + vertex 0.83486 1.48261 2.59707 + endloop + endfacet + facet normal -0.584731 -0.0188834 0.811008 + outer loop + vertex 0.837834 1.47575 2.59906 + vertex 0.837746 1.48074 2.59911 + vertex 0.834917 1.47765 2.597 + endloop + endfacet + facet normal -0.559353 -0.0133151 0.828822 + outer loop + vertex 0.843696 1.4815 2.60324 + vertex 0.843658 1.48652 2.60329 + vertex 0.840669 1.48369 2.60123 + endloop + endfacet + facet normal -0.540413 -0.0171211 0.841225 + outer loop + vertex 0.843696 1.4815 2.60324 + vertex 0.843739 1.47646 2.60316 + vertex 0.846783 1.47938 2.60518 + endloop + endfacet + facet normal -0.561598 -0.0197696 0.827174 + outer loop + vertex 0.843808 1.47147 2.60309 + vertex 0.843739 1.47646 2.60316 + vertex 0.840804 1.47367 2.6011 + endloop + endfacet + facet normal -0.575765 -0.0187927 0.8174 + outer loop + vertex 0.837746 1.48074 2.59911 + vertex 0.837834 1.47575 2.59906 + vertex 0.84071 1.47866 2.60115 + endloop + endfacet + facet normal -0.57527 -0.0210611 0.817692 + outer loop + vertex 0.840804 1.47367 2.6011 + vertex 0.838082 1.47086 2.59911 + vertex 0.840977 1.46887 2.6011 + endloop + endfacet + facet normal -0.575074 -0.0206284 0.817841 + outer loop + vertex 0.838082 1.47086 2.59911 + vertex 0.838604 1.46672 2.59938 + vertex 0.840977 1.46887 2.6011 + endloop + endfacet + facet normal -0.575674 -0.0271142 0.81723 + outer loop + vertex 0.838604 1.46672 2.59938 + vertex 0.837682 1.46234 2.59858 + vertex 0.841025 1.46416 2.601 + endloop + endfacet + facet normal -0.586233 -0.0280895 0.809655 + outer loop + vertex 0.834981 1.45896 2.59651 + vertex 0.837682 1.46234 2.59858 + vertex 0.834574 1.46319 2.59636 + endloop + endfacet + facet normal -0.598445 -0.0295798 0.800618 + outer loop + vertex 0.834574 1.46319 2.59636 + vertex 0.831881 1.46137 2.59428 + vertex 0.834981 1.45896 2.59651 + endloop + endfacet + facet normal -0.610401 -0.0277492 0.791607 + outer loop + vertex 0.831881 1.46137 2.59428 + vertex 0.829892 1.46611 2.59291 + vertex 0.828986 1.46168 2.59206 + endloop + endfacet + facet normal -0.593334 -0.0215987 0.804667 + outer loop + vertex 0.832858 1.46559 2.59516 + vertex 0.835574 1.46734 2.59721 + vertex 0.832483 1.46966 2.595 + endloop + endfacet + facet normal -0.617086 -0.0253359 0.786488 + outer loop + vertex 0.829892 1.46611 2.59291 + vertex 0.829517 1.47155 2.59279 + vertex 0.826763 1.46883 2.59055 + endloop + endfacet + facet normal -0.593652 -0.0222646 0.804413 + outer loop + vertex 0.835574 1.46734 2.59721 + vertex 0.835113 1.47267 2.59702 + vertex 0.832483 1.46966 2.595 + endloop + endfacet + facet normal -0.585235 -0.0200858 0.810615 + outer loop + vertex 0.835113 1.47267 2.59702 + vertex 0.837834 1.47575 2.59906 + vertex 0.834917 1.47765 2.597 + endloop + endfacet + facet normal -0.60479 -0.022461 0.796068 + outer loop + vertex 0.829325 1.47652 2.59279 + vertex 0.829517 1.47155 2.59279 + vertex 0.832194 1.47456 2.59491 + endloop + endfacet + facet normal -0.614296 -0.0198535 0.788826 + outer loop + vertex 0.829325 1.47652 2.59279 + vertex 0.829242 1.48143 2.59285 + vertex 0.826477 1.47875 2.59063 + endloop + endfacet + facet normal -0.593351 -0.0181406 0.804739 + outer loop + vertex 0.834917 1.47765 2.597 + vertex 0.83486 1.48261 2.59707 + vertex 0.832067 1.47947 2.59494 + endloop + endfacet + facet normal -0.585064 -0.0154612 0.81084 + outer loop + vertex 0.83486 1.48261 2.59707 + vertex 0.837719 1.48574 2.59919 + vertex 0.834841 1.48759 2.59715 + endloop + endfacet + facet normal -0.603946 -0.0159352 0.796866 + outer loop + vertex 0.829204 1.48639 2.59292 + vertex 0.829242 1.48143 2.59285 + vertex 0.832029 1.48441 2.59502 + endloop + endfacet + facet normal -0.593698 -0.0128642 0.804585 + outer loop + vertex 0.834841 1.48759 2.59715 + vertex 0.834814 1.49258 2.59721 + vertex 0.832004 1.48939 2.59509 + endloop + endfacet + facet normal -0.584249 -0.0108469 0.811502 + outer loop + vertex 0.834814 1.49258 2.59721 + vertex 0.837659 1.49574 2.5993 + vertex 0.834775 1.49758 2.59725 + endloop + endfacet + facet normal -0.604631 -0.010619 0.796435 + outer loop + vertex 0.829123 1.49639 2.593 + vertex 0.829167 1.49139 2.59297 + vertex 0.831968 1.49439 2.59513 + endloop + endfacet + facet normal -0.61484 -0.00908843 0.7886 + outer loop + vertex 0.829123 1.49639 2.593 + vertex 0.82908 1.50139 2.59303 + vertex 0.826276 1.4987 2.59081 + endloop + endfacet + facet normal -0.594247 -0.00850473 0.804238 + outer loop + vertex 0.834775 1.49758 2.59725 + vertex 0.834739 1.50257 2.59728 + vertex 0.831926 1.49939 2.59517 + endloop + endfacet + facet normal -0.583289 -0.00489398 0.81225 + outer loop + vertex 0.834739 1.50257 2.59728 + vertex 0.8376 1.50572 2.59935 + vertex 0.834717 1.50757 2.59729 + endloop + endfacet + facet normal -0.605086 -0.00630033 0.796135 + outer loop + vertex 0.829049 1.50638 2.59304 + vertex 0.82908 1.50139 2.59303 + vertex 0.831891 1.50438 2.59519 + endloop + endfacet + facet normal -0.614391 -0.00272949 0.788997 + outer loop + vertex 0.829049 1.50638 2.59304 + vertex 0.829033 1.51137 2.59305 + vertex 0.826212 1.50868 2.59084 + endloop + endfacet + facet normal -0.61546 -0.000929849 0.788168 + outer loop + vertex 0.826212 1.50868 2.59084 + vertex 0.829033 1.51137 2.59305 + vertex 0.826203 1.51367 2.59084 + endloop + endfacet + facet normal -0.625244 -0.000948506 0.780428 + outer loop + vertex 0.826203 1.51367 2.59084 + vertex 0.823396 1.5112 2.58859 + vertex 0.826212 1.50868 2.59084 + endloop + endfacet + facet normal -0.626283 0.00098993 0.779595 + outer loop + vertex 0.823395 1.51619 2.58858 + vertex 0.823396 1.5112 2.58859 + vertex 0.826203 1.51367 2.59084 + endloop + endfacet + facet normal -0.625424 0.00256041 0.780281 + outer loop + vertex 0.826212 1.51866 2.59083 + vertex 0.823395 1.51619 2.58858 + vertex 0.826203 1.51367 2.59084 + endloop + endfacet + facet normal -0.615046 0.00255836 0.788487 + outer loop + vertex 0.826203 1.51367 2.59084 + vertex 0.829035 1.51636 2.59304 + vertex 0.826212 1.51866 2.59083 + endloop + endfacet + facet normal -0.614318 0.00132722 0.789057 + outer loop + vertex 0.829033 1.51137 2.59305 + vertex 0.829035 1.51636 2.59304 + vertex 0.826203 1.51367 2.59084 + endloop + endfacet + facet normal -0.593465 -0.000817086 0.80486 + outer loop + vertex 0.834717 1.50757 2.59729 + vertex 0.834711 1.51256 2.59729 + vertex 0.831871 1.50937 2.5952 + endloop + endfacet + facet normal -0.582576 0.00266965 0.812772 + outer loop + vertex 0.834711 1.51256 2.59729 + vertex 0.837596 1.5157 2.59935 + vertex 0.834718 1.51755 2.59728 + endloop + endfacet + facet normal -0.604502 0.00133391 0.796603 + outer loop + vertex 0.829035 1.51636 2.59304 + vertex 0.829033 1.51137 2.59305 + vertex 0.831867 1.51436 2.59519 + endloop + endfacet + facet normal -0.614192 0.00424262 0.789145 + outer loop + vertex 0.829035 1.51636 2.59304 + vertex 0.829051 1.52135 2.59303 + vertex 0.826212 1.51866 2.59083 + endloop + endfacet + facet normal -0.615238 0.00601942 0.788318 + outer loop + vertex 0.826212 1.51866 2.59083 + vertex 0.829051 1.52135 2.59303 + vertex 0.826237 1.52365 2.59081 + endloop + endfacet + facet normal -0.626015 0.00604168 0.779787 + outer loop + vertex 0.826237 1.52365 2.59081 + vertex 0.823414 1.52118 2.58856 + vertex 0.826212 1.51866 2.59083 + endloop + endfacet + facet normal -0.614881 0.00671961 0.788592 + outer loop + vertex 0.829051 1.52135 2.59303 + vertex 0.829079 1.52634 2.593 + vertex 0.826237 1.52365 2.59081 + endloop + endfacet + facet normal -0.615862 0.00839208 0.787809 + outer loop + vertex 0.826237 1.52365 2.59081 + vertex 0.829079 1.52634 2.593 + vertex 0.826272 1.52864 2.59079 + endloop + endfacet + facet normal -0.626698 0.00842501 0.779217 + outer loop + vertex 0.826272 1.52864 2.59079 + vertex 0.823447 1.52618 2.58854 + vertex 0.826237 1.52365 2.59081 + endloop + endfacet + facet normal -0.627477 0.00990642 0.778572 + outer loop + vertex 0.823488 1.53117 2.58851 + vertex 0.823447 1.52618 2.58854 + vertex 0.826272 1.52864 2.59079 + endloop + endfacet + facet normal -0.627314 0.0102004 0.778699 + outer loop + vertex 0.826308 1.53363 2.59075 + vertex 0.823488 1.53117 2.58851 + vertex 0.826272 1.52864 2.59079 + endloop + endfacet + facet normal -0.616403 0.0101834 0.787365 + outer loop + vertex 0.826272 1.52864 2.59079 + vertex 0.82911 1.53133 2.59297 + vertex 0.826308 1.53363 2.59075 + endloop + endfacet + facet normal -0.616088 0.0107985 0.787604 + outer loop + vertex 0.82911 1.53133 2.59297 + vertex 0.829139 1.53631 2.59293 + vertex 0.826308 1.53363 2.59075 + endloop + endfacet + facet normal -0.616567 0.0116174 0.787217 + outer loop + vertex 0.826308 1.53363 2.59075 + vertex 0.829139 1.53631 2.59293 + vertex 0.826339 1.5386 2.5907 + endloop + endfacet + facet normal -0.627605 0.0115972 0.778446 + outer loop + vertex 0.826339 1.5386 2.5907 + vertex 0.823527 1.53615 2.58847 + vertex 0.826308 1.53363 2.59075 + endloop + endfacet + facet normal -0.628294 0.0129165 0.777868 + outer loop + vertex 0.823563 1.54112 2.58842 + vertex 0.823527 1.53615 2.58847 + vertex 0.826339 1.5386 2.5907 + endloop + endfacet + facet normal -0.627721 0.0139504 0.778313 + outer loop + vertex 0.826375 1.54359 2.59064 + vertex 0.823563 1.54112 2.58842 + vertex 0.826339 1.5386 2.5907 + endloop + endfacet + facet normal -0.616812 0.0139775 0.786987 + outer loop + vertex 0.826339 1.5386 2.5907 + vertex 0.829166 1.5413 2.59287 + vertex 0.826375 1.54359 2.59064 + endloop + endfacet + facet normal -0.616171 0.0152274 0.787465 + outer loop + vertex 0.829166 1.5413 2.59287 + vertex 0.829228 1.54635 2.59282 + vertex 0.826375 1.54359 2.59064 + endloop + endfacet + facet normal -0.617471 0.0174124 0.786401 + outer loop + vertex 0.826375 1.54359 2.59064 + vertex 0.829228 1.54635 2.59282 + vertex 0.826458 1.54865 2.59059 + endloop + endfacet + facet normal -0.627795 0.0175063 0.778182 + outer loop + vertex 0.826458 1.54865 2.59059 + vertex 0.823611 1.5461 2.58835 + vertex 0.826375 1.54359 2.59064 + endloop + endfacet + facet normal -0.629432 0.0205581 0.776783 + outer loop + vertex 0.823697 1.55112 2.58829 + vertex 0.823611 1.5461 2.58835 + vertex 0.826458 1.54865 2.59059 + endloop + endfacet + facet normal -0.628505 0.0222501 0.777487 + outer loop + vertex 0.826632 1.55387 2.59058 + vertex 0.823697 1.55112 2.58829 + vertex 0.826458 1.54865 2.59059 + endloop + endfacet + facet normal -0.618765 0.0219369 0.78527 + outer loop + vertex 0.826458 1.54865 2.59059 + vertex 0.829407 1.55153 2.59284 + vertex 0.826632 1.55387 2.59058 + endloop + endfacet + facet normal -0.618409 0.0226109 0.785531 + outer loop + vertex 0.829407 1.55153 2.59284 + vertex 0.829923 1.55722 2.59308 + vertex 0.826632 1.55387 2.59058 + endloop + endfacet + facet normal -0.62013 0.0253777 0.784089 + outer loop + vertex 0.826632 1.55387 2.59058 + vertex 0.829923 1.55722 2.59308 + vertex 0.826728 1.55911 2.59049 + endloop + endfacet + facet normal -0.629855 0.0254146 0.776297 + outer loop + vertex 0.826728 1.55911 2.59049 + vertex 0.823804 1.55618 2.58821 + vertex 0.826632 1.55387 2.59058 + endloop + endfacet + facet normal -0.631327 0.0278832 0.775015 + outer loop + vertex 0.823894 1.56122 2.58811 + vertex 0.823804 1.55618 2.58821 + vertex 0.826728 1.55911 2.59049 + endloop + endfacet + facet normal -0.631694 0.0270853 0.774744 + outer loop + vertex 0.826733 1.56421 2.59032 + vertex 0.823894 1.56122 2.58811 + vertex 0.826728 1.55911 2.59049 + endloop + endfacet + facet normal -0.622362 0.027333 0.782252 + outer loop + vertex 0.826728 1.55911 2.59049 + vertex 0.829567 1.56251 2.59263 + vertex 0.826733 1.56421 2.59032 + endloop + endfacet + facet normal -0.622346 0.0273747 0.782264 + outer loop + vertex 0.829567 1.56251 2.59263 + vertex 0.829555 1.56746 2.59245 + vertex 0.826733 1.56421 2.59032 + endloop + endfacet + facet normal -0.623181 0.0285627 0.781556 + outer loop + vertex 0.826733 1.56421 2.59032 + vertex 0.829555 1.56746 2.59245 + vertex 0.826802 1.56924 2.59019 + endloop + endfacet + facet normal -0.63317 0.0284946 0.773488 + outer loop + vertex 0.826802 1.56924 2.59019 + vertex 0.82398 1.56623 2.58799 + vertex 0.826733 1.56421 2.59032 + endloop + endfacet + facet normal -0.633926 0.0296897 0.772824 + outer loop + vertex 0.824105 1.57129 2.5879 + vertex 0.82398 1.56623 2.58799 + vertex 0.826802 1.56924 2.59019 + endloop + endfacet + facet normal -0.633516 0.0305654 0.773126 + outer loop + vertex 0.826945 1.57431 2.5901 + vertex 0.824105 1.57129 2.5879 + vertex 0.826802 1.56924 2.59019 + endloop + endfacet + facet normal -0.623728 0.0304202 0.78105 + outer loop + vertex 0.826802 1.56924 2.59019 + vertex 0.829635 1.57245 2.59232 + vertex 0.826945 1.57431 2.5901 + endloop + endfacet + facet normal -0.622818 0.0325052 0.781691 + outer loop + vertex 0.829635 1.57245 2.59232 + vertex 0.829741 1.57743 2.5922 + vertex 0.826945 1.57431 2.5901 + endloop + endfacet + facet normal -0.623643 0.033719 0.780982 + outer loop + vertex 0.826945 1.57431 2.5901 + vertex 0.829741 1.57743 2.5922 + vertex 0.827212 1.57928 2.5901 + endloop + endfacet + facet normal -0.633551 0.0342479 0.772942 + outer loop + vertex 0.827212 1.57928 2.5901 + vertex 0.824346 1.57649 2.58788 + vertex 0.826945 1.57431 2.5901 + endloop + endfacet + facet normal -0.635144 0.0370293 0.771506 + outer loop + vertex 0.82493 1.58222 2.58808 + vertex 0.824346 1.57649 2.58788 + vertex 0.827212 1.57928 2.5901 + endloop + endfacet + facet normal -0.634306 0.0381172 0.772142 + outer loop + vertex 0.827702 1.58316 2.59031 + vertex 0.82493 1.58222 2.58808 + vertex 0.827212 1.57928 2.5901 + endloop + endfacet + facet normal -0.622872 0.0361642 0.781488 + outer loop + vertex 0.827212 1.57928 2.5901 + vertex 0.829777 1.58208 2.59202 + vertex 0.827702 1.58316 2.59031 + endloop + endfacet + facet normal -0.621978 0.0387909 0.782073 + outer loop + vertex 0.829369 1.58547 2.59153 + vertex 0.827702 1.58316 2.59031 + vertex 0.829777 1.58208 2.59202 + endloop + endfacet + facet normal -0.611935 0.0411257 0.789838 + outer loop + vertex 0.829369 1.58547 2.59153 + vertex 0.829777 1.58208 2.59202 + vertex 0.832199 1.58594 2.59369 + endloop + endfacet + facet normal -0.612176 0.0441839 0.789486 + outer loop + vertex 0.829369 1.58547 2.59153 + vertex 0.832199 1.58594 2.59369 + vertex 0.829876 1.58908 2.59172 + endloop + endfacet + facet normal -0.625531 0.0466151 0.778805 + outer loop + vertex 0.829876 1.58908 2.59172 + vertex 0.827308 1.58646 2.58981 + vertex 0.829369 1.58547 2.59153 + endloop + endfacet + facet normal -0.625316 0.0462641 0.778999 + outer loop + vertex 0.827362 1.5909 2.58959 + vertex 0.827308 1.58646 2.58981 + vertex 0.829876 1.58908 2.59172 + endloop + endfacet + facet normal -0.625185 0.0465498 0.779088 + outer loop + vertex 0.830163 1.59374 2.59167 + vertex 0.827362 1.5909 2.58959 + vertex 0.829876 1.58908 2.59172 + endloop + endfacet + facet normal -0.614007 0.04595 0.787962 + outer loop + vertex 0.829876 1.58908 2.59172 + vertex 0.832797 1.5913 2.59386 + vertex 0.830163 1.59374 2.59167 + endloop + endfacet + facet normal -0.614078 0.0458295 0.787914 + outer loop + vertex 0.832797 1.5913 2.59386 + vertex 0.833072 1.59622 2.59379 + vertex 0.830163 1.59374 2.59167 + endloop + endfacet + facet normal -0.615524 0.0486369 0.786616 + outer loop + vertex 0.830163 1.59374 2.59167 + vertex 0.833072 1.59622 2.59379 + vertex 0.83033 1.5986 2.5915 + endloop + endfacet + facet normal -0.625831 0.0487052 0.778437 + outer loop + vertex 0.83033 1.5986 2.5915 + vertex 0.827457 1.59573 2.58937 + vertex 0.830163 1.59374 2.59167 + endloop + endfacet + facet normal -0.626896 0.0504891 0.777465 + outer loop + vertex 0.827479 1.60078 2.58906 + vertex 0.827457 1.59573 2.58937 + vertex 0.83033 1.5986 2.5915 + endloop + endfacet + facet normal -0.627034 0.0502064 0.777373 + outer loop + vertex 0.830484 1.6036 2.5913 + vertex 0.827479 1.60078 2.58906 + vertex 0.83033 1.5986 2.5915 + endloop + endfacet + facet normal -0.616489 0.0502163 0.785761 + outer loop + vertex 0.83033 1.5986 2.5915 + vertex 0.833272 1.60116 2.59364 + vertex 0.830484 1.6036 2.5913 + endloop + endfacet + facet normal -0.61655 0.0501075 0.78572 + outer loop + vertex 0.833272 1.60116 2.59364 + vertex 0.833461 1.6062 2.59347 + vertex 0.830484 1.6036 2.5913 + endloop + endfacet + facet normal -0.617221 0.0513886 0.78511 + outer loop + vertex 0.830484 1.6036 2.5913 + vertex 0.833461 1.6062 2.59347 + vertex 0.830686 1.60865 2.59113 + endloop + endfacet + facet normal -0.627734 0.0515238 0.776721 + outer loop + vertex 0.830686 1.60865 2.59113 + vertex 0.827654 1.60601 2.58885 + vertex 0.830484 1.6036 2.5913 + endloop + endfacet + facet normal -0.627981 0.0520086 0.776489 + outer loop + vertex 0.827973 1.61115 2.58877 + vertex 0.827654 1.60601 2.58885 + vertex 0.830686 1.60865 2.59113 + endloop + endfacet + facet normal -0.627123 0.0534986 0.777081 + outer loop + vertex 0.830905 1.61364 2.59096 + vertex 0.827973 1.61115 2.58877 + vertex 0.830686 1.60865 2.59113 + endloop + endfacet + facet normal -0.618462 0.0533476 0.784002 + outer loop + vertex 0.830686 1.60865 2.59113 + vertex 0.833631 1.61124 2.59327 + vertex 0.830905 1.61364 2.59096 + endloop + endfacet + facet normal -0.617609 0.0548642 0.784569 + outer loop + vertex 0.833631 1.61124 2.59327 + vertex 0.833826 1.61626 2.59308 + vertex 0.830905 1.61364 2.59096 + endloop + endfacet + facet normal -0.618922 0.0573045 0.783359 + outer loop + vertex 0.830905 1.61364 2.59096 + vertex 0.833826 1.61626 2.59308 + vertex 0.831144 1.61862 2.59079 + endloop + endfacet + facet normal -0.626388 0.0574511 0.777392 + outer loop + vertex 0.831144 1.61862 2.59079 + vertex 0.82822 1.61612 2.58861 + vertex 0.830905 1.61364 2.59096 + endloop + endfacet + facet normal -0.617533 0.0597632 0.784272 + outer loop + vertex 0.833826 1.61626 2.59308 + vertex 0.834149 1.62135 2.59294 + vertex 0.831144 1.61862 2.59079 + endloop + endfacet + facet normal -0.618966 0.0623992 0.782935 + outer loop + vertex 0.831144 1.61862 2.59079 + vertex 0.834149 1.62135 2.59294 + vertex 0.831463 1.62376 2.59063 + endloop + endfacet + facet normal -0.625565 0.0626465 0.777653 + outer loop + vertex 0.831463 1.62376 2.59063 + vertex 0.828464 1.62109 2.58843 + vertex 0.831144 1.61862 2.59079 + endloop + endfacet + facet normal -0.617449 0.0650312 0.783918 + outer loop + vertex 0.834149 1.62135 2.59294 + vertex 0.834844 1.62696 2.59303 + vertex 0.831463 1.62376 2.59063 + endloop + endfacet + facet normal -0.61815 0.0662644 0.783262 + outer loop + vertex 0.831463 1.62376 2.59063 + vertex 0.834844 1.62696 2.59303 + vertex 0.831748 1.62902 2.59041 + endloop + endfacet + facet normal -0.625438 0.0664146 0.777443 + outer loop + vertex 0.831748 1.62902 2.59041 + vertex 0.828728 1.62615 2.58822 + vertex 0.831463 1.62376 2.59063 + endloop + endfacet + facet normal -0.626546 0.0683865 0.776378 + outer loop + vertex 0.829075 1.63138 2.58804 + vertex 0.828728 1.62615 2.58822 + vertex 0.831748 1.62902 2.59041 + endloop + endfacet + facet normal -0.626587 0.0683139 0.776352 + outer loop + vertex 0.832056 1.6341 2.59021 + vertex 0.829075 1.63138 2.58804 + vertex 0.831748 1.62902 2.59041 + endloop + endfacet + facet normal -0.619118 0.0680942 0.78234 + outer loop + vertex 0.831748 1.62902 2.59041 + vertex 0.834658 1.63226 2.59243 + vertex 0.832056 1.6341 2.59021 + endloop + endfacet + facet normal -0.61906 0.0682198 0.782375 + outer loop + vertex 0.834658 1.63226 2.59243 + vertex 0.834716 1.6369 2.59207 + vertex 0.832056 1.6341 2.59021 + endloop + endfacet + facet normal -0.619121 0.0683165 0.782318 + outer loop + vertex 0.832056 1.6341 2.59021 + vertex 0.834716 1.6369 2.59207 + vertex 0.83262 1.63801 2.59031 + endloop + endfacet + facet normal -0.628193 0.0698247 0.774918 + outer loop + vertex 0.83262 1.63801 2.59031 + vertex 0.829778 1.63714 2.58809 + vertex 0.832056 1.6341 2.59021 + endloop + endfacet + facet normal -0.628453 0.0716362 0.774542 + outer loop + vertex 0.83262 1.63801 2.59031 + vertex 0.832272 1.64136 2.58972 + vertex 0.829778 1.63714 2.58809 + endloop + endfacet + facet normal -0.629795 0.0728982 0.773334 + outer loop + vertex 0.829778 1.63714 2.58809 + vertex 0.832272 1.64136 2.58972 + vertex 0.829619 1.64246 2.58746 + endloop + endfacet + facet normal -0.629276 0.074674 0.773586 + outer loop + vertex 0.832272 1.64136 2.58972 + vertex 0.832335 1.64583 2.58934 + vertex 0.829619 1.64246 2.58746 + endloop + endfacet + facet normal -0.621369 0.0750984 0.779911 + outer loop + vertex 0.832335 1.64583 2.58934 + vertex 0.832272 1.64136 2.58972 + vertex 0.834922 1.64396 2.59158 + endloop + endfacet + facet normal -0.621466 0.0752632 0.779818 + outer loop + vertex 0.834922 1.64396 2.59158 + vertex 0.832272 1.64136 2.58972 + vertex 0.834362 1.64031 2.59149 + endloop + endfacet + facet normal -0.622201 0.0731533 0.779432 + outer loop + vertex 0.83262 1.63801 2.59031 + vertex 0.834362 1.64031 2.59149 + vertex 0.832272 1.64136 2.58972 + endloop + endfacet + facet normal -0.618853 0.0690545 0.782465 + outer loop + vertex 0.834362 1.64031 2.59149 + vertex 0.83262 1.63801 2.59031 + vertex 0.834716 1.6369 2.59207 + endloop + endfacet + facet normal -0.611235 0.0708351 0.788273 + outer loop + vertex 0.834362 1.64031 2.59149 + vertex 0.834716 1.6369 2.59207 + vertex 0.837222 1.6408 2.59366 + endloop + endfacet + facet normal -0.611408 0.073516 0.787893 + outer loop + vertex 0.834362 1.64031 2.59149 + vertex 0.837222 1.6408 2.59366 + vertex 0.834922 1.64396 2.59158 + endloop + endfacet + facet normal -0.610705 0.0703076 0.788731 + outer loop + vertex 0.834716 1.6369 2.59207 + vertex 0.837398 1.63559 2.59426 + vertex 0.837222 1.6408 2.59366 + endloop + endfacet + facet normal -0.611295 0.0685915 0.788425 + outer loop + vertex 0.834658 1.63226 2.59243 + vertex 0.837398 1.63559 2.59426 + vertex 0.834716 1.6369 2.59207 + endloop + endfacet + facet normal -0.618041 0.0665104 0.783327 + outer loop + vertex 0.834844 1.62696 2.59303 + vertex 0.834658 1.63226 2.59243 + vertex 0.831748 1.62902 2.59041 + endloop + endfacet + facet normal -0.611749 0.0672773 0.788186 + outer loop + vertex 0.834844 1.62696 2.59303 + vertex 0.837343 1.63105 2.59462 + vertex 0.834658 1.63226 2.59243 + endloop + endfacet + facet normal -0.611021 0.0665906 0.788808 + outer loop + vertex 0.837701 1.62772 2.59517 + vertex 0.837343 1.63105 2.59462 + vertex 0.834844 1.62696 2.59303 + endloop + endfacet + facet normal -0.610734 0.064354 0.789217 + outer loop + vertex 0.837701 1.62772 2.59517 + vertex 0.834844 1.62696 2.59303 + vertex 0.837129 1.62396 2.59504 + endloop + endfacet + facet normal -0.598166 0.0620911 0.798963 + outer loop + vertex 0.837129 1.62396 2.59504 + vertex 0.839837 1.62669 2.59685 + vertex 0.837701 1.62772 2.59517 + endloop + endfacet + facet normal -0.597767 0.0614639 0.799311 + outer loop + vertex 0.839714 1.62216 2.59711 + vertex 0.839837 1.62669 2.59685 + vertex 0.837129 1.62396 2.59504 + endloop + endfacet + facet normal -0.598315 0.0603046 0.798988 + outer loop + vertex 0.836775 1.61912 2.59514 + vertex 0.839714 1.62216 2.59711 + vertex 0.837129 1.62396 2.59504 + endloop + endfacet + facet normal -0.609199 0.060931 0.790673 + outer loop + vertex 0.837129 1.62396 2.59504 + vertex 0.834149 1.62135 2.59294 + vertex 0.836775 1.61912 2.59514 + endloop + endfacet + facet normal -0.596556 0.0576225 0.8005 + outer loop + vertex 0.839532 1.61726 2.59733 + vertex 0.839714 1.62216 2.59711 + vertex 0.836775 1.61912 2.59514 + endloop + endfacet + facet normal -0.610906 0.0641453 0.789101 + outer loop + vertex 0.834844 1.62696 2.59303 + vertex 0.834149 1.62135 2.59294 + vertex 0.837129 1.62396 2.59504 + endloop + endfacet + facet normal -0.610026 0.0594421 0.790149 + outer loop + vertex 0.834149 1.62135 2.59294 + vertex 0.833826 1.61626 2.59308 + vertex 0.836775 1.61912 2.59514 + endloop + endfacet + facet normal -0.607866 0.0558312 0.792074 + outer loop + vertex 0.836775 1.61912 2.59514 + vertex 0.833826 1.61626 2.59308 + vertex 0.836577 1.61411 2.59534 + endloop + endfacet + facet normal -0.62784 0.0549413 0.776401 + outer loop + vertex 0.82822 1.61612 2.58861 + vertex 0.827973 1.61115 2.58877 + vertex 0.830905 1.61364 2.59096 + endloop + endfacet + facet normal -0.627749 0.0514946 0.776711 + outer loop + vertex 0.827654 1.60601 2.58885 + vertex 0.827479 1.60078 2.58906 + vertex 0.830484 1.6036 2.5913 + endloop + endfacet + facet normal -0.634646 0.0501365 0.771175 + outer loop + vertex 0.827457 1.59573 2.58937 + vertex 0.827479 1.60078 2.58906 + vertex 0.82465 1.59743 2.58695 + endloop + endfacet + facet normal -0.636347 0.0525592 0.76961 + outer loop + vertex 0.82465 1.59743 2.58695 + vertex 0.827479 1.60078 2.58906 + vertex 0.824208 1.60287 2.58621 + endloop + endfacet + facet normal -0.626118 0.0480907 0.778244 + outer loop + vertex 0.827457 1.59573 2.58937 + vertex 0.827362 1.5909 2.58959 + vertex 0.830163 1.59374 2.59167 + endloop + endfacet + facet normal -0.63407 0.0479517 0.771788 + outer loop + vertex 0.827362 1.5909 2.58959 + vertex 0.827457 1.59573 2.58937 + vertex 0.824664 1.59247 2.58728 + endloop + endfacet + facet normal -0.634711 0.0462291 0.771366 + outer loop + vertex 0.824649 1.58753 2.58756 + vertex 0.827362 1.5909 2.58959 + vertex 0.824664 1.59247 2.58728 + endloop + endfacet + facet normal -0.634544 0.0460044 0.771516 + outer loop + vertex 0.827308 1.58646 2.58981 + vertex 0.827362 1.5909 2.58959 + vertex 0.824649 1.58753 2.58756 + endloop + endfacet + facet normal -0.610026 0.0392459 0.791409 + outer loop + vertex 0.829777 1.58208 2.59202 + vertex 0.832504 1.58062 2.59419 + vertex 0.832199 1.58594 2.59369 + endloop + endfacet + facet normal -0.611134 0.0361165 0.790703 + outer loop + vertex 0.829741 1.57743 2.5922 + vertex 0.832504 1.58062 2.59419 + vertex 0.829777 1.58208 2.59202 + endloop + endfacet + facet normal -0.626375 0.0439681 0.778281 + outer loop + vertex 0.827702 1.58316 2.59031 + vertex 0.829369 1.58547 2.59153 + vertex 0.827308 1.58646 2.58981 + endloop + endfacet + facet normal -0.634981 0.0418909 0.771391 + outer loop + vertex 0.827702 1.58316 2.59031 + vertex 0.827308 1.58646 2.58981 + vertex 0.82493 1.58222 2.58808 + endloop + endfacet + facet normal -0.62266 0.0358446 0.781671 + outer loop + vertex 0.829741 1.57743 2.5922 + vertex 0.829777 1.58208 2.59202 + vertex 0.827212 1.57928 2.5901 + endloop + endfacet + facet normal -0.611226 0.032482 0.790789 + outer loop + vertex 0.829635 1.57245 2.59232 + vertex 0.832485 1.57561 2.5944 + vertex 0.829741 1.57743 2.5922 + endloop + endfacet + facet normal -0.610433 0.0313317 0.791448 + outer loop + vertex 0.832393 1.57065 2.59452 + vertex 0.832485 1.57561 2.5944 + vertex 0.829635 1.57245 2.59232 + endloop + endfacet + facet normal -0.611307 0.0292697 0.790852 + outer loop + vertex 0.829555 1.56746 2.59245 + vertex 0.832393 1.57065 2.59452 + vertex 0.829635 1.57245 2.59232 + endloop + endfacet + facet normal -0.622908 0.0292319 0.781749 + outer loop + vertex 0.829555 1.56746 2.59245 + vertex 0.829635 1.57245 2.59232 + vertex 0.826802 1.56924 2.59019 + endloop + endfacet + facet normal -0.611579 0.0277109 0.790698 + outer loop + vertex 0.829567 1.56251 2.59263 + vertex 0.832297 1.56583 2.59463 + vertex 0.829555 1.56746 2.59245 + endloop + endfacet + facet normal -0.611371 0.0274378 0.790868 + outer loop + vertex 0.832293 1.56139 2.59478 + vertex 0.832297 1.56583 2.59463 + vertex 0.829567 1.56251 2.59263 + endloop + endfacet + facet normal -0.6204 0.0246594 0.783898 + outer loop + vertex 0.829923 1.55722 2.59308 + vertex 0.829567 1.56251 2.59263 + vertex 0.826728 1.55911 2.59049 + endloop + endfacet + facet normal -0.592929 0.00493104 0.805239 + outer loop + vertex 0.834718 1.51755 2.59728 + vertex 0.834734 1.52254 2.59726 + vertex 0.831878 1.51935 2.59518 + endloop + endfacet + facet normal -0.582548 0.0065095 0.81277 + outer loop + vertex 0.834734 1.52254 2.59726 + vertex 0.837626 1.52569 2.59931 + vertex 0.834754 1.52753 2.59724 + endloop + endfacet + facet normal -0.604248 0.0066961 0.796768 + outer loop + vertex 0.829079 1.52634 2.593 + vertex 0.829051 1.52135 2.59303 + vertex 0.831898 1.52435 2.59516 + endloop + endfacet + facet normal -0.615625 0.00885498 0.787989 + outer loop + vertex 0.829079 1.52634 2.593 + vertex 0.82911 1.53133 2.59297 + vertex 0.826272 1.52864 2.59079 + endloop + endfacet + facet normal -0.593141 0.00893043 0.805049 + outer loop + vertex 0.834754 1.52753 2.59724 + vertex 0.834779 1.53253 2.5972 + vertex 0.831923 1.52934 2.59513 + endloop + endfacet + facet normal -0.583268 0.0116538 0.812196 + outer loop + vertex 0.834779 1.53253 2.5972 + vertex 0.83768 1.53568 2.59924 + vertex 0.83481 1.53752 2.59715 + endloop + endfacet + facet normal -0.605035 0.010814 0.796125 + outer loop + vertex 0.829139 1.53631 2.59293 + vertex 0.82911 1.53133 2.59297 + vertex 0.83195 1.53432 2.59509 + endloop + endfacet + facet normal -0.616035 0.0126591 0.787617 + outer loop + vertex 0.829139 1.53631 2.59293 + vertex 0.829166 1.5413 2.59287 + vertex 0.826339 1.5386 2.5907 + endloop + endfacet + facet normal -0.592811 0.0138186 0.805223 + outer loop + vertex 0.83481 1.53752 2.59715 + vertex 0.834846 1.54251 2.59709 + vertex 0.831978 1.53931 2.59503 + endloop + endfacet + facet normal -0.604633 0.0151746 0.796359 + outer loop + vertex 0.829228 1.54635 2.59282 + vertex 0.829166 1.5413 2.59287 + vertex 0.832017 1.54433 2.59497 + endloop + endfacet + facet normal -0.616811 0.0186779 0.786889 + outer loop + vertex 0.829228 1.54635 2.59282 + vertex 0.829407 1.55153 2.59284 + vertex 0.826458 1.54865 2.59059 + endloop + endfacet + facet normal -0.592511 0.0164188 0.805395 + outer loop + vertex 0.834893 1.54752 2.59703 + vertex 0.83494 1.55245 2.59696 + vertex 0.832105 1.54936 2.59494 + endloop + endfacet + facet normal -0.58102 0.0180174 0.81369 + outer loop + vertex 0.83494 1.55245 2.59696 + vertex 0.837756 1.55562 2.5989 + vertex 0.834907 1.55704 2.59684 + endloop + endfacet + facet normal -0.607615 0.0212722 0.793947 + outer loop + vertex 0.829923 1.55722 2.59308 + vertex 0.829407 1.55153 2.59284 + vertex 0.83231 1.55428 2.59498 + endloop + endfacet + facet normal -0.611816 0.0258029 0.790579 + outer loop + vertex 0.829923 1.55722 2.59308 + vertex 0.832293 1.56139 2.59478 + vertex 0.829567 1.56251 2.59263 + endloop + endfacet + facet normal -0.592431 0.0193418 0.805389 + outer loop + vertex 0.834428 1.56038 2.5964 + vertex 0.832749 1.55811 2.59522 + vertex 0.834907 1.55704 2.59684 + endloop + endfacet + facet normal -0.581918 0.0218238 0.812955 + outer loop + vertex 0.834428 1.56038 2.5964 + vertex 0.834907 1.55704 2.59684 + vertex 0.837373 1.56094 2.5985 + endloop + endfacet + facet normal -0.571735 0.0236803 0.820097 + outer loop + vertex 0.837943 1.56641 2.59874 + vertex 0.837373 1.56094 2.5985 + vertex 0.840983 1.56398 2.60093 + endloop + endfacet + facet normal -0.5975 0.0277809 0.801387 + outer loop + vertex 0.832297 1.56583 2.59463 + vertex 0.832293 1.56139 2.59478 + vertex 0.834901 1.56401 2.59663 + endloop + endfacet + facet normal -0.611094 0.0289663 0.791028 + outer loop + vertex 0.832297 1.56583 2.59463 + vertex 0.832393 1.57065 2.59452 + vertex 0.829555 1.56746 2.59245 + endloop + endfacet + facet normal -0.583497 0.0280115 0.811632 + outer loop + vertex 0.837943 1.56641 2.59874 + vertex 0.838168 1.57143 2.59873 + vertex 0.835152 1.5687 2.59665 + endloop + endfacet + facet normal -0.572442 0.0305048 0.819377 + outer loop + vertex 0.838293 1.57639 2.59863 + vertex 0.838168 1.57143 2.59873 + vertex 0.841239 1.57432 2.60076 + endloop + endfacet + facet normal -0.598174 0.0313364 0.800753 + outer loop + vertex 0.832485 1.57561 2.5944 + vertex 0.832393 1.57065 2.59452 + vertex 0.835302 1.57359 2.59658 + endloop + endfacet + facet normal -0.610209 0.0348322 0.791475 + outer loop + vertex 0.832485 1.57561 2.5944 + vertex 0.832504 1.58062 2.59419 + vertex 0.829741 1.57743 2.5922 + endloop + endfacet + facet normal -0.585275 0.0335879 0.810139 + outer loop + vertex 0.838293 1.57639 2.59863 + vertex 0.8384 1.58136 2.5985 + vertex 0.8354 1.57856 2.59645 + endloop + endfacet + facet normal -0.576158 0.0361624 0.816538 + outer loop + vertex 0.838515 1.58634 2.59836 + vertex 0.8384 1.58136 2.5985 + vertex 0.841431 1.58424 2.60051 + endloop + endfacet + facet normal -0.600481 0.0404685 0.798614 + outer loop + vertex 0.832199 1.58594 2.59369 + vertex 0.832504 1.58062 2.59419 + vertex 0.83544 1.58361 2.59625 + endloop + endfacet + facet normal -0.612842 0.043394 0.789013 + outer loop + vertex 0.832199 1.58594 2.59369 + vertex 0.832797 1.5913 2.59386 + vertex 0.829876 1.58908 2.59172 + endloop + endfacet + facet normal -0.589465 0.0391219 0.806846 + outer loop + vertex 0.838515 1.58634 2.59836 + vertex 0.838661 1.5913 2.59823 + vertex 0.835581 1.5887 2.5961 + endloop + endfacet + facet normal -0.579341 0.0425315 0.813975 + outer loop + vertex 0.838847 1.59625 2.5981 + vertex 0.838661 1.5913 2.59823 + vertex 0.841684 1.59415 2.60023 + endloop + endfacet + facet normal -0.603373 0.0453491 0.796169 + outer loop + vertex 0.833072 1.59622 2.59379 + vertex 0.832797 1.5913 2.59386 + vertex 0.835828 1.5937 2.59602 + endloop + endfacet + facet normal -0.615594 0.0485114 0.786569 + outer loop + vertex 0.833072 1.59622 2.59379 + vertex 0.833272 1.60116 2.59364 + vertex 0.83033 1.5986 2.5915 + endloop + endfacet + facet normal -0.591717 0.0464791 0.804805 + outer loop + vertex 0.838847 1.59625 2.5981 + vertex 0.839135 1.60132 2.59802 + vertex 0.836053 1.59866 2.59591 + endloop + endfacet + facet normal -0.580214 0.0469045 0.813113 + outer loop + vertex 0.839762 1.6069 2.59815 + vertex 0.839135 1.60132 2.59802 + vertex 0.842188 1.60387 2.60005 + endloop + endfacet + facet normal -0.604801 0.0499799 0.794807 + outer loop + vertex 0.833461 1.6062 2.59347 + vertex 0.833272 1.60116 2.59364 + vertex 0.836325 1.60379 2.5958 + endloop + endfacet + facet normal -0.617327 0.0511994 0.785038 + outer loop + vertex 0.833461 1.6062 2.59347 + vertex 0.833631 1.61124 2.59327 + vertex 0.830686 1.60865 2.59113 + endloop + endfacet + facet normal -0.608402 0.0547863 0.791736 + outer loop + vertex 0.833826 1.61626 2.59308 + vertex 0.833631 1.61124 2.59327 + vertex 0.836577 1.61411 2.59534 + endloop + endfacet + facet normal -0.593484 0.0478577 0.803421 + outer loop + vertex 0.839762 1.6069 2.59815 + vertex 0.839461 1.61225 2.5976 + vertex 0.836495 1.609 2.59561 + endloop + endfacet + facet normal -0.597424 0.055736 0.799986 + outer loop + vertex 0.836577 1.61411 2.59534 + vertex 0.839532 1.61726 2.59733 + vertex 0.836775 1.61912 2.59514 + endloop + endfacet + facet normal -0.581591 0.0518966 0.811824 + outer loop + vertex 0.842289 1.61096 2.59971 + vertex 0.842364 1.61553 2.59947 + vertex 0.839461 1.61225 2.5976 + endloop + endfacet + facet normal -0.582271 0.057552 0.810955 + outer loop + vertex 0.839532 1.61726 2.59733 + vertex 0.842559 1.62046 2.59927 + vertex 0.839714 1.62216 2.59711 + endloop + endfacet + facet normal -0.581175 0.0601487 0.811553 + outer loop + vertex 0.842559 1.62046 2.59927 + vertex 0.842691 1.62547 2.599 + vertex 0.839714 1.62216 2.59711 + endloop + endfacet + facet normal -0.563278 0.0603664 0.82406 + outer loop + vertex 0.842691 1.62547 2.599 + vertex 0.842559 1.62046 2.59927 + vertex 0.845795 1.62366 2.60125 + endloop + endfacet + facet normal -0.544305 0.05704 0.836946 + outer loop + vertex 0.848294 1.61628 2.60339 + vertex 0.848774 1.62144 2.60335 + vertex 0.845454 1.61853 2.60139 + endloop + endfacet + facet normal -0.567908 0.0644459 0.820565 + outer loop + vertex 0.843139 1.63626 2.59846 + vertex 0.842449 1.63075 2.59841 + vertex 0.846067 1.63412 2.60065 + endloop + endfacet + facet normal -0.562866 0.0613322 0.824269 + outer loop + vertex 0.845937 1.6289 2.60096 + vertex 0.842691 1.62547 2.599 + vertex 0.845795 1.62366 2.60125 + endloop + endfacet + facet normal -0.582301 0.0616878 0.81063 + outer loop + vertex 0.839714 1.62216 2.59711 + vertex 0.842691 1.62547 2.599 + vertex 0.839837 1.62669 2.59685 + endloop + endfacet + facet normal -0.597768 0.0632521 0.79917 + outer loop + vertex 0.839469 1.63 2.59632 + vertex 0.837701 1.62772 2.59517 + vertex 0.839837 1.62669 2.59685 + endloop + endfacet + facet normal -0.602254 0.0686331 0.795349 + outer loop + vertex 0.837701 1.62772 2.59517 + vertex 0.839469 1.63 2.59632 + vertex 0.837343 1.63105 2.59462 + endloop + endfacet + facet normal -0.611318 0.0686221 0.788404 + outer loop + vertex 0.837343 1.63105 2.59462 + vertex 0.837398 1.63559 2.59426 + vertex 0.834658 1.63226 2.59243 + endloop + endfacet + facet normal -0.585606 0.0667695 0.807841 + outer loop + vertex 0.842449 1.63075 2.59841 + vertex 0.843139 1.63626 2.59846 + vertex 0.840036 1.63372 2.59642 + endloop + endfacet + facet normal -0.568663 0.0680719 0.819749 + outer loop + vertex 0.843523 1.64129 2.59831 + vertex 0.843139 1.63626 2.59846 + vertex 0.846368 1.63918 2.60046 + endloop + endfacet + facet normal -0.602159 0.0713413 0.795182 + outer loop + vertex 0.837222 1.6408 2.59366 + vertex 0.837398 1.63559 2.59426 + vertex 0.840353 1.63856 2.59624 + endloop + endfacet + facet normal -0.611227 0.0737268 0.788014 + outer loop + vertex 0.837222 1.6408 2.59366 + vertex 0.837946 1.64621 2.59372 + vertex 0.834922 1.64396 2.59158 + endloop + endfacet + facet normal -0.612154 0.0758496 0.787092 + outer loop + vertex 0.834922 1.64396 2.59158 + vertex 0.837946 1.64621 2.59372 + vertex 0.835233 1.64869 2.59137 + endloop + endfacet + facet normal -0.620887 0.0761108 0.780196 + outer loop + vertex 0.835233 1.64869 2.59137 + vertex 0.832335 1.64583 2.58934 + vertex 0.834922 1.64396 2.59158 + endloop + endfacet + facet normal -0.621422 0.0770147 0.779682 + outer loop + vertex 0.832163 1.65091 2.5887 + vertex 0.832335 1.64583 2.58934 + vertex 0.835233 1.64869 2.59137 + endloop + endfacet + facet normal -0.611821 0.0764065 0.787297 + outer loop + vertex 0.837946 1.64621 2.59372 + vertex 0.838325 1.65122 2.59353 + vertex 0.835233 1.64869 2.59137 + endloop + endfacet + facet normal -0.612461 0.0777271 0.78667 + outer loop + vertex 0.835233 1.64869 2.59137 + vertex 0.838325 1.65122 2.59353 + vertex 0.835539 1.65366 2.59112 + endloop + endfacet + facet normal -0.586928 0.0731825 0.806325 + outer loop + vertex 0.843523 1.64129 2.59831 + vertex 0.843933 1.64632 2.59815 + vertex 0.840696 1.64364 2.59604 + endloop + endfacet + facet normal -0.568734 0.0745031 0.81914 + outer loop + vertex 0.844661 1.65181 2.59815 + vertex 0.843933 1.64632 2.59815 + vertex 0.847046 1.64882 2.60008 + endloop + endfacet + facet normal -0.601152 0.0759131 0.795521 + outer loop + vertex 0.838325 1.65122 2.59353 + vertex 0.837946 1.64621 2.59372 + vertex 0.841153 1.64879 2.5959 + endloop + endfacet + facet normal -0.585344 0.0778667 0.807037 + outer loop + vertex 0.844661 1.65181 2.59815 + vertex 0.844469 1.65709 2.59751 + vertex 0.841443 1.65392 2.59562 + endloop + endfacet + facet normal -0.5676 0.0839543 0.819013 + outer loop + vertex 0.844469 1.65709 2.59751 + vertex 0.847484 1.66049 2.59925 + vertex 0.844639 1.66198 2.59712 + endloop + endfacet + facet normal -0.585609 0.100655 0.80432 + outer loop + vertex 0.842663 1.6675 2.5951 + vertex 0.844556 1.66988 2.59618 + vertex 0.842392 1.67084 2.59448 + endloop + endfacet + facet normal -0.602308 0.0879709 0.793401 + outer loop + vertex 0.839773 1.66677 2.593 + vertex 0.839011 1.66126 2.59303 + vertex 0.842034 1.66376 2.59505 + endloop + endfacet + facet normal -0.601806 0.08241 0.794379 + outer loop + vertex 0.839011 1.66126 2.59303 + vertex 0.838625 1.6562 2.59326 + vertex 0.841649 1.65894 2.59527 + endloop + endfacet + facet normal -0.611917 0.0786718 0.787 + outer loop + vertex 0.838325 1.65122 2.59353 + vertex 0.838625 1.6562 2.59326 + vertex 0.835539 1.65366 2.59112 + endloop + endfacet + facet normal -0.621265 0.0832467 0.779166 + outer loop + vertex 0.833265 1.66114 2.58852 + vertex 0.832868 1.65621 2.58873 + vertex 0.835929 1.65866 2.59091 + endloop + endfacet + facet normal -0.620994 0.077909 0.779934 + outer loop + vertex 0.835539 1.65366 2.59112 + vertex 0.832163 1.65091 2.5887 + vertex 0.835233 1.64869 2.59137 + endloop + endfacet + facet normal -0.628117 0.076123 0.774387 + outer loop + vertex 0.829694 1.64703 2.58708 + vertex 0.832335 1.64583 2.58934 + vertex 0.832163 1.65091 2.5887 + endloop + endfacet + facet normal -0.628786 0.0740217 0.774047 + outer loop + vertex 0.829619 1.64246 2.58746 + vertex 0.832335 1.64583 2.58934 + vertex 0.829694 1.64703 2.58708 + endloop + endfacet + facet normal -0.636106 0.0721022 0.768225 + outer loop + vertex 0.829778 1.63714 2.58809 + vertex 0.829619 1.64246 2.58746 + vertex 0.826727 1.6391 2.58538 + endloop + endfacet + facet normal -0.627711 0.0704204 0.775254 + outer loop + vertex 0.829778 1.63714 2.58809 + vertex 0.829075 1.63138 2.58804 + vertex 0.832056 1.6341 2.59021 + endloop + endfacet + facet normal -0.633697 0.0686586 0.770528 + outer loop + vertex 0.828728 1.62615 2.58822 + vertex 0.829075 1.63138 2.58804 + vertex 0.826085 1.62858 2.58583 + endloop + endfacet + facet normal -0.626517 0.0644648 0.776737 + outer loop + vertex 0.828728 1.62615 2.58822 + vertex 0.828464 1.62109 2.58843 + vertex 0.831463 1.62376 2.59063 + endloop + endfacet + facet normal -0.6274 0.0594715 0.776423 + outer loop + vertex 0.828464 1.62109 2.58843 + vertex 0.82822 1.61612 2.58861 + vertex 0.831144 1.61862 2.59079 + endloop + endfacet + facet normal -0.642858 0.0598558 0.763643 + outer loop + vertex 0.822901 1.62105 2.58381 + vertex 0.822269 1.6157 2.58369 + vertex 0.825514 1.61856 2.5862 + endloop + endfacet + facet normal -0.634591 0.0551077 0.770881 + outer loop + vertex 0.827973 1.61115 2.58877 + vertex 0.82822 1.61612 2.58861 + vertex 0.825265 1.61355 2.58637 + endloop + endfacet + facet normal -0.636772 0.0515071 0.76933 + outer loop + vertex 0.824208 1.60287 2.58621 + vertex 0.827479 1.60078 2.58906 + vertex 0.827654 1.60601 2.58885 + endloop + endfacet + facet normal -0.641861 0.051811 0.765069 + outer loop + vertex 0.822457 1.61065 2.58422 + vertex 0.822346 1.60636 2.58441 + vertex 0.824998 1.60854 2.58649 + endloop + endfacet + facet normal -0.648831 0.0517188 0.759173 + outer loop + vertex 0.822346 1.60636 2.58441 + vertex 0.822457 1.61065 2.58422 + vertex 0.819898 1.60735 2.58225 + endloop + endfacet + facet normal -0.648191 0.0508635 0.759777 + outer loop + vertex 0.819898 1.60735 2.58225 + vertex 0.822457 1.61065 2.58422 + vertex 0.819927 1.6118 2.58198 + endloop + endfacet + facet normal -0.642346 0.0514045 0.764689 + outer loop + vertex 0.82465 1.59743 2.58695 + vertex 0.824208 1.60287 2.58621 + vertex 0.822091 1.59852 2.58473 + endloop + endfacet + facet normal -0.634982 0.0492716 0.770954 + outer loop + vertex 0.824664 1.59247 2.58728 + vertex 0.827457 1.59573 2.58937 + vertex 0.82465 1.59743 2.58695 + endloop + endfacet + facet normal -0.641421 0.0459302 0.765813 + outer loop + vertex 0.824649 1.58753 2.58756 + vertex 0.824664 1.59247 2.58728 + vertex 0.821884 1.58917 2.58515 + endloop + endfacet + facet normal -0.635505 0.0423718 0.770933 + outer loop + vertex 0.82493 1.58222 2.58808 + vertex 0.827308 1.58646 2.58981 + vertex 0.824649 1.58753 2.58756 + endloop + endfacet + facet normal -0.641312 0.0378427 0.766346 + outer loop + vertex 0.824346 1.57649 2.58788 + vertex 0.82493 1.58222 2.58808 + vertex 0.821675 1.57883 2.58553 + endloop + endfacet + facet normal -0.634579 0.0322533 0.772185 + outer loop + vertex 0.824346 1.57649 2.58788 + vertex 0.824105 1.57129 2.5879 + vertex 0.826945 1.57431 2.5901 + endloop + endfacet + facet normal -0.642308 0.0297714 0.765868 + outer loop + vertex 0.82398 1.56623 2.58799 + vertex 0.824105 1.57129 2.5879 + vertex 0.821298 1.56855 2.58565 + endloop + endfacet + facet normal -0.632921 0.0290446 0.773672 + outer loop + vertex 0.82398 1.56623 2.58799 + vertex 0.823894 1.56122 2.58811 + vertex 0.826733 1.56421 2.59032 + endloop + endfacet + facet normal -0.640993 0.0278868 0.76704 + outer loop + vertex 0.823804 1.55618 2.58821 + vertex 0.823894 1.56122 2.58811 + vertex 0.821087 1.55862 2.58586 + endloop + endfacet + facet normal -0.630053 0.0250197 0.776149 + outer loop + vertex 0.823804 1.55618 2.58821 + vertex 0.823697 1.55112 2.58829 + vertex 0.826632 1.55387 2.59058 + endloop + endfacet + facet normal -0.638592 0.0206197 0.769269 + outer loop + vertex 0.823611 1.5461 2.58835 + vertex 0.823697 1.55112 2.58829 + vertex 0.820894 1.54867 2.58603 + endloop + endfacet + facet normal -0.628718 0.0158441 0.777472 + outer loop + vertex 0.823611 1.5461 2.58835 + vertex 0.823563 1.54112 2.58842 + vertex 0.826375 1.54359 2.59064 + endloop + endfacet + facet normal -0.638418 0.0129008 0.769582 + outer loop + vertex 0.823527 1.53615 2.58847 + vertex 0.823563 1.54112 2.58842 + vertex 0.820786 1.53875 2.58615 + endloop + endfacet + facet normal -0.627832 0.0111873 0.778269 + outer loop + vertex 0.823527 1.53615 2.58847 + vertex 0.823488 1.53117 2.58851 + vertex 0.826308 1.53363 2.59075 + endloop + endfacet + facet normal -0.637304 0.00993701 0.770549 + outer loop + vertex 0.823447 1.52618 2.58854 + vertex 0.823488 1.53117 2.58851 + vertex 0.8207 1.52877 2.58623 + endloop + endfacet + facet normal -0.626993 0.00789082 0.778985 + outer loop + vertex 0.823447 1.52618 2.58854 + vertex 0.823414 1.52118 2.58856 + vertex 0.826237 1.52365 2.59081 + endloop + endfacet + facet normal -0.626656 0.00487761 0.779281 + outer loop + vertex 0.823414 1.52118 2.58856 + vertex 0.823395 1.51619 2.58858 + vertex 0.826212 1.51866 2.59083 + endloop + endfacet + facet normal -0.636351 0.000976142 0.771399 + outer loop + vertex 0.823396 1.5112 2.58859 + vertex 0.823395 1.51619 2.58858 + vertex 0.820624 1.51378 2.5863 + endloop + endfacet + facet normal -0.626489 -0.0032368 0.779424 + outer loop + vertex 0.823396 1.5112 2.58859 + vertex 0.823415 1.50621 2.58858 + vertex 0.826212 1.50868 2.59084 + endloop + endfacet + facet normal -0.636294 -0.00654896 0.771418 + outer loop + vertex 0.823447 1.50122 2.58857 + vertex 0.823415 1.50621 2.58858 + vertex 0.820658 1.50379 2.58629 + endloop + endfacet + facet normal -0.625562 -0.0101184 0.780109 + outer loop + vertex 0.823487 1.49623 2.58854 + vertex 0.823533 1.49124 2.58851 + vertex 0.826322 1.4937 2.59078 + endloop + endfacet + facet normal -0.635689 -0.0128886 0.771837 + outer loop + vertex 0.823583 1.48623 2.58847 + vertex 0.823533 1.49124 2.58851 + vertex 0.82078 1.48884 2.58621 + endloop + endfacet + facet normal -0.626401 -0.0164205 0.779328 + outer loop + vertex 0.823583 1.48623 2.58847 + vertex 0.823642 1.48124 2.58841 + vertex 0.826413 1.4837 2.59069 + endloop + endfacet + facet normal -0.635994 -0.0212096 0.771402 + outer loop + vertex 0.823729 1.47627 2.58835 + vertex 0.823642 1.48124 2.58841 + vertex 0.820911 1.47884 2.5861 + endloop + endfacet + facet normal -0.627061 -0.0255199 0.778552 + outer loop + vertex 0.823729 1.47627 2.58835 + vertex 0.823854 1.47131 2.58829 + vertex 0.826595 1.47382 2.59058 + endloop + endfacet + facet normal -0.636645 -0.0286294 0.770625 + outer loop + vertex 0.823978 1.46636 2.58821 + vertex 0.823854 1.47131 2.58829 + vertex 0.821136 1.46885 2.58595 + endloop + endfacet + facet normal -0.63047 -0.0309683 0.775596 + outer loop + vertex 0.823978 1.46636 2.58821 + vertex 0.824078 1.46143 2.58809 + vertex 0.826766 1.46394 2.59038 + endloop + endfacet + facet normal -0.639707 -0.0330846 0.767907 + outer loop + vertex 0.824194 1.45651 2.58798 + vertex 0.824078 1.46143 2.58809 + vertex 0.821404 1.45885 2.58575 + endloop + endfacet + facet normal -0.632848 -0.0346579 0.7735 + outer loop + vertex 0.824194 1.45651 2.58798 + vertex 0.824341 1.45154 2.58787 + vertex 0.826959 1.45448 2.59015 + endloop + endfacet + facet normal -0.641605 -0.0356503 0.766207 + outer loop + vertex 0.824545 1.44647 2.58781 + vertex 0.824341 1.45154 2.58787 + vertex 0.821688 1.44882 2.58552 + endloop + endfacet + facet normal -0.633999 -0.0368045 0.772457 + outer loop + vertex 0.824545 1.44647 2.58781 + vertex 0.824911 1.44096 2.58785 + vertex 0.827434 1.44449 2.59008 + endloop + endfacet + facet normal -0.643356 -0.0388539 0.764581 + outer loop + vertex 0.824081 1.43661 2.58693 + vertex 0.824911 1.44096 2.58785 + vertex 0.821888 1.43892 2.5852 + endloop + endfacet + facet normal -0.63701 -0.0411556 0.769756 + outer loop + vertex 0.826909 1.4362 2.58924 + vertex 0.824911 1.44096 2.58785 + vertex 0.824081 1.43661 2.58693 + endloop + endfacet + facet normal -0.634608 -0.0395431 0.771822 + outer loop + vertex 0.827794 1.44036 2.59018 + vertex 0.824911 1.44096 2.58785 + vertex 0.826909 1.4362 2.58924 + endloop + endfacet + facet normal -0.637166 -0.0437942 0.769481 + outer loop + vertex 0.824724 1.43254 2.58723 + vertex 0.826909 1.4362 2.58924 + vertex 0.824081 1.43661 2.58693 + endloop + endfacet + facet normal -0.643777 -0.0471551 0.763759 + outer loop + vertex 0.825399 1.4273 2.58747 + vertex 0.824724 1.43254 2.58723 + vertex 0.822417 1.4296 2.5851 + endloop + endfacet + facet normal -0.643287 -0.0460212 0.764241 + outer loop + vertex 0.822884 1.42553 2.58525 + vertex 0.825399 1.4273 2.58747 + vertex 0.822417 1.4296 2.5851 + endloop + endfacet + facet normal -0.64324 -0.0461277 0.764274 + outer loop + vertex 0.82457 1.42312 2.58652 + vertex 0.825399 1.4273 2.58747 + vertex 0.822884 1.42553 2.58525 + endloop + endfacet + facet normal -0.637334 -0.0483882 0.769067 + outer loop + vertex 0.82457 1.42312 2.58652 + vertex 0.827481 1.4223 2.58888 + vertex 0.825399 1.4273 2.58747 + endloop + endfacet + facet normal -0.644887 -0.0478252 0.76278 + outer loop + vertex 0.822134 1.42133 2.58435 + vertex 0.823027 1.41675 2.58481 + vertex 0.82507 1.41903 2.58668 + endloop + endfacet + facet normal -0.651184 -0.0496117 0.757297 + outer loop + vertex 0.823027 1.41675 2.58481 + vertex 0.822134 1.42133 2.58435 + vertex 0.820227 1.41711 2.58243 + endloop + endfacet + facet normal -0.65197 -0.0489681 0.756662 + outer loop + vertex 0.820227 1.41711 2.58243 + vertex 0.822134 1.42133 2.58435 + vertex 0.819315 1.42158 2.58193 + endloop + endfacet + facet normal -0.651302 -0.052519 0.756999 + outer loop + vertex 0.822389 1.41224 2.58395 + vertex 0.823027 1.41675 2.58481 + vertex 0.820227 1.41711 2.58243 + endloop + endfacet + facet normal -0.636538 -0.0506666 0.769579 + outer loop + vertex 0.828235 1.41142 2.58881 + vertex 0.827947 1.41661 2.58891 + vertex 0.825366 1.41414 2.58661 + endloop + endfacet + facet normal -0.629092 -0.0546655 0.775407 + outer loop + vertex 0.828235 1.41142 2.58881 + vertex 0.828485 1.40635 2.58865 + vertex 0.83116 1.40888 2.591 + endloop + endfacet + facet normal -0.637997 -0.060389 0.767668 + outer loop + vertex 0.828733 1.40137 2.58847 + vertex 0.828485 1.40635 2.58865 + vertex 0.825852 1.4039 2.58627 + endloop + endfacet + facet normal -0.629884 -0.0641363 0.774037 + outer loop + vertex 0.828733 1.40137 2.58847 + vertex 0.828933 1.39647 2.58822 + vertex 0.831645 1.39893 2.59063 + endloop + endfacet + facet normal -0.639599 -0.0657511 0.765891 + outer loop + vertex 0.829127 1.39165 2.58797 + vertex 0.828933 1.39647 2.58822 + vertex 0.82632 1.39398 2.58583 + endloop + endfacet + facet normal -0.633199 -0.0672863 0.771059 + outer loop + vertex 0.829127 1.39165 2.58797 + vertex 0.829481 1.38675 2.58783 + vertex 0.831881 1.38948 2.59004 + endloop + endfacet + facet normal -0.640055 -0.0713139 0.765012 + outer loop + vertex 0.830189 1.38136 2.58792 + vertex 0.829481 1.38675 2.58783 + vertex 0.826931 1.3841 2.58545 + endloop + endfacet + facet normal -0.63519 -0.0770337 0.768505 + outer loop + vertex 0.832563 1.37727 2.58948 + vertex 0.830189 1.38136 2.58792 + vertex 0.829903 1.37642 2.58719 + endloop + endfacet + facet normal -0.634121 -0.0815001 0.768927 + outer loop + vertex 0.832333 1.37226 2.58876 + vertex 0.832563 1.37727 2.58948 + vertex 0.829903 1.37642 2.58719 + endloop + endfacet + facet normal -0.641919 -0.081013 0.762481 + outer loop + vertex 0.827143 1.37142 2.58435 + vertex 0.829452 1.37293 2.58645 + vertex 0.827721 1.37529 2.58525 + endloop + endfacet + facet normal -0.646709 -0.0802465 0.758503 + outer loop + vertex 0.828187 1.36692 2.58476 + vertex 0.827143 1.37142 2.58435 + vertex 0.825336 1.36739 2.58238 + endloop + endfacet + facet normal -0.64671 -0.0802521 0.758503 + outer loop + vertex 0.827636 1.36244 2.58382 + vertex 0.828187 1.36692 2.58476 + vertex 0.825336 1.36739 2.58238 + endloop + endfacet + facet normal -0.632499 -0.080654 0.77035 + outer loop + vertex 0.833154 1.36667 2.58884 + vertex 0.832333 1.37226 2.58876 + vertex 0.830162 1.36908 2.58664 + endloop + endfacet + facet normal -0.615228 -0.0773661 0.784544 + outer loop + vertex 0.833154 1.36667 2.58884 + vertex 0.833569 1.36155 2.58867 + vertex 0.836307 1.36399 2.59105 + endloop + endfacet + facet normal -0.632577 -0.079326 0.770424 + outer loop + vertex 0.833852 1.35658 2.58839 + vertex 0.833569 1.36155 2.58867 + vertex 0.830884 1.35919 2.58622 + endloop + endfacet + facet normal -0.641987 -0.0816434 0.762356 + outer loop + vertex 0.828187 1.36692 2.58476 + vertex 0.827636 1.36244 2.58382 + vertex 0.830618 1.36426 2.58652 + endloop + endfacet + facet normal -0.64425 -0.0841709 0.760169 + outer loop + vertex 0.830884 1.35919 2.58622 + vertex 0.828278 1.35672 2.58373 + vertex 0.831265 1.35404 2.58597 + endloop + endfacet + facet normal -0.646523 -0.0887574 0.757714 + outer loop + vertex 0.828278 1.35672 2.58373 + vertex 0.828706 1.35153 2.58349 + vertex 0.831265 1.35404 2.58597 + endloop + endfacet + facet normal -0.645682 -0.0937088 0.757835 + outer loop + vertex 0.828706 1.35153 2.58349 + vertex 0.829042 1.34656 2.58316 + vertex 0.831637 1.34901 2.58568 + endloop + endfacet + facet normal -0.644128 -0.0963751 0.758822 + outer loop + vertex 0.831637 1.34901 2.58568 + vertex 0.829042 1.34656 2.58316 + vertex 0.831876 1.3442 2.58527 + endloop + endfacet + facet normal -0.660055 -0.0974392 0.744871 + outer loop + vertex 0.823715 1.34653 2.57849 + vertex 0.824054 1.34161 2.57815 + vertex 0.826536 1.34408 2.58067 + endloop + endfacet + facet normal -0.660787 -0.0996877 0.743924 + outer loop + vertex 0.826974 1.33922 2.58042 + vertex 0.824557 1.33685 2.57795 + vertex 0.827455 1.33456 2.58022 + endloop + endfacet + facet normal -0.650478 -0.0990046 0.753044 + outer loop + vertex 0.827455 1.33456 2.58022 + vertex 0.830242 1.33649 2.58288 + vertex 0.826974 1.33922 2.58042 + endloop + endfacet + facet normal -0.662036 -0.102798 0.742389 + outer loop + vertex 0.824557 1.33685 2.57795 + vertex 0.825403 1.33229 2.57808 + vertex 0.827455 1.33456 2.58022 + endloop + endfacet + facet normal -0.669135 -0.104296 0.735785 + outer loop + vertex 0.825403 1.33229 2.57808 + vertex 0.824557 1.33685 2.57795 + vertex 0.822376 1.3343 2.57561 + endloop + endfacet + facet normal -0.675351 -0.103908 0.73014 + outer loop + vertex 0.81883 1.34153 2.57336 + vertex 0.819298 1.33653 2.57309 + vertex 0.821641 1.33912 2.57562 + endloop + endfacet + facet normal -0.673797 -0.107739 0.731019 + outer loop + vertex 0.82366 1.32983 2.57613 + vertex 0.822376 1.3343 2.57561 + vertex 0.820269 1.33109 2.57319 + endloop + endfacet + facet normal -0.673379 -0.104666 0.731851 + outer loop + vertex 0.82366 1.32983 2.57613 + vertex 0.820269 1.33109 2.57319 + vertex 0.822687 1.32682 2.57481 + endloop + endfacet + facet normal -0.674111 -0.105373 0.731075 + outer loop + vertex 0.822687 1.32682 2.57481 + vertex 0.820269 1.33109 2.57319 + vertex 0.820036 1.32645 2.57231 + endloop + endfacet + facet normal -0.680006 -0.10407 0.725783 + outer loop + vertex 0.820036 1.32645 2.57231 + vertex 0.820269 1.33109 2.57319 + vertex 0.817449 1.32944 2.57031 + endloop + endfacet + facet normal -0.685047 -0.110458 0.720076 + outer loop + vertex 0.816827 1.32232 2.56866 + vertex 0.819536 1.32321 2.57137 + vertex 0.817861 1.32576 2.57017 + endloop + endfacet + facet normal -0.675487 -0.106941 0.729576 + outer loop + vertex 0.823267 1.3167 2.57387 + vertex 0.822431 1.32224 2.57391 + vertex 0.820251 1.3192 2.57145 + endloop + endfacet + facet normal -0.656288 -0.110855 0.746322 + outer loop + vertex 0.829036 1.31168 2.57828 + vertex 0.828659 1.31665 2.57869 + vertex 0.826179 1.31411 2.57613 + endloop + endfacet + facet normal -0.646434 -0.10864 0.755196 + outer loop + vertex 0.828027 1.32176 2.57888 + vertex 0.828659 1.31665 2.57869 + vertex 0.831127 1.31919 2.58117 + endloop + endfacet + facet normal -0.668762 -0.10597 0.735886 + outer loop + vertex 0.822431 1.32224 2.57391 + vertex 0.823267 1.3167 2.57387 + vertex 0.825682 1.31923 2.57643 + endloop + endfacet + facet normal -0.674157 -0.105061 0.731078 + outer loop + vertex 0.822431 1.32224 2.57391 + vertex 0.822687 1.32682 2.57481 + vertex 0.820036 1.32645 2.57231 + endloop + endfacet + facet normal -0.662233 -0.109322 0.74128 + outer loop + vertex 0.828027 1.32176 2.57888 + vertex 0.826842 1.3273 2.57864 + vertex 0.825099 1.32407 2.57661 + endloop + endfacet + facet normal -0.670631 -0.10654 0.7341 + outer loop + vertex 0.822687 1.32682 2.57481 + vertex 0.824589 1.32703 2.57658 + vertex 0.82366 1.32983 2.57613 + endloop + endfacet + facet normal -0.669698 -0.106091 0.735016 + outer loop + vertex 0.82366 1.32983 2.57613 + vertex 0.825403 1.33229 2.57808 + vertex 0.822376 1.3343 2.57561 + endloop + endfacet + facet normal -0.662287 -0.102411 0.742218 + outer loop + vertex 0.827853 1.33082 2.58006 + vertex 0.827455 1.33456 2.58022 + vertex 0.825403 1.33229 2.57808 + endloop + endfacet + facet normal -0.655357 -0.114234 0.746631 + outer loop + vertex 0.82957 1.32828 2.58119 + vertex 0.826842 1.3273 2.57864 + vertex 0.830348 1.32427 2.58125 + endloop + endfacet + facet normal -0.650539 -0.101611 0.752645 + outer loop + vertex 0.827853 1.33082 2.58006 + vertex 0.830062 1.33167 2.58208 + vertex 0.827455 1.33456 2.58022 + endloop + endfacet + facet normal -0.636803 -0.11036 0.763087 + outer loop + vertex 0.830348 1.32427 2.58125 + vertex 0.832604 1.32745 2.5836 + vertex 0.82957 1.32828 2.58119 + endloop + endfacet + facet normal -0.649823 -0.100468 0.753417 + outer loop + vertex 0.830062 1.33167 2.58208 + vertex 0.830242 1.33649 2.58288 + vertex 0.827455 1.33456 2.58022 + endloop + endfacet + facet normal -0.651056 -0.100303 0.752373 + outer loop + vertex 0.830242 1.33649 2.58288 + vertex 0.82944 1.34171 2.58288 + vertex 0.826974 1.33922 2.58042 + endloop + endfacet + facet normal -0.644386 -0.096943 0.758531 + outer loop + vertex 0.829042 1.34656 2.58316 + vertex 0.82944 1.34171 2.58288 + vertex 0.831876 1.3442 2.58527 + endloop + endfacet + facet normal -0.626118 -0.107146 0.772332 + outer loop + vertex 0.8354 1.3375 2.58724 + vertex 0.834275 1.34187 2.58694 + vertex 0.832324 1.33966 2.58505 + endloop + endfacet + facet normal -0.622838 -0.0986843 0.776102 + outer loop + vertex 0.833075 1.33598 2.58519 + vertex 0.8354 1.3375 2.58724 + vertex 0.832324 1.33966 2.58505 + endloop + endfacet + facet normal -0.630351 -0.0966585 0.770269 + outer loop + vertex 0.831876 1.3442 2.58527 + vertex 0.834852 1.34625 2.58796 + vertex 0.831637 1.34901 2.58568 + endloop + endfacet + facet normal -0.611956 -0.101257 0.784383 + outer loop + vertex 0.837852 1.34565 2.59023 + vertex 0.834852 1.34625 2.58796 + vertex 0.837226 1.34156 2.58921 + endloop + endfacet + facet normal -0.595878 -0.106594 0.79597 + outer loop + vertex 0.837226 1.34156 2.58921 + vertex 0.839739 1.34326 2.59132 + vertex 0.837852 1.34565 2.59023 + endloop + endfacet + facet normal -0.595296 -0.107791 0.796244 + outer loop + vertex 0.839739 1.34326 2.59132 + vertex 0.837226 1.34156 2.58921 + vertex 0.840469 1.33923 2.59132 + endloop + endfacet + facet normal -0.593896 -0.104499 0.797726 + outer loop + vertex 0.837226 1.34156 2.58921 + vertex 0.838383 1.33703 2.58948 + vertex 0.840469 1.33923 2.59132 + endloop + endfacet + facet normal -0.593359 -0.112267 0.79707 + outer loop + vertex 0.838383 1.33703 2.58948 + vertex 0.837923 1.33259 2.58851 + vertex 0.841067 1.33434 2.5911 + endloop + endfacet + facet normal -0.595202 -0.111352 0.795824 + outer loop + vertex 0.837923 1.33259 2.58851 + vertex 0.838814 1.32688 2.58838 + vertex 0.841419 1.32933 2.59067 + endloop + endfacet + facet normal -0.594631 -0.11224 0.796125 + outer loop + vertex 0.841419 1.32933 2.59067 + vertex 0.838814 1.32688 2.58838 + vertex 0.842019 1.32445 2.59043 + endloop + endfacet + facet normal -0.595761 -0.114746 0.794923 + outer loop + vertex 0.838814 1.32688 2.58838 + vertex 0.839722 1.32123 2.58824 + vertex 0.842019 1.32445 2.59043 + endloop + endfacet + facet normal -0.59043 -0.111878 0.799297 + outer loop + vertex 0.842019 1.32445 2.59043 + vertex 0.844088 1.32669 2.59227 + vertex 0.841419 1.32933 2.59067 + endloop + endfacet + facet normal -0.588133 -0.107631 0.801571 + outer loop + vertex 0.847144 1.32636 2.59447 + vertex 0.844584 1.33119 2.59324 + vertex 0.844088 1.32669 2.59227 + endloop + endfacet + facet normal -0.586974 -0.105641 0.802684 + outer loop + vertex 0.847144 1.32636 2.59447 + vertex 0.848285 1.32186 2.59471 + vertex 0.850377 1.32413 2.59654 + endloop + endfacet + facet normal -0.590265 -0.109401 0.799762 + outer loop + vertex 0.848285 1.32186 2.59471 + vertex 0.84775 1.31739 2.5937 + vertex 0.850869 1.31937 2.59628 + endloop + endfacet + facet normal -0.595717 -0.114593 0.794977 + outer loop + vertex 0.842212 1.31646 2.58942 + vertex 0.844679 1.31814 2.59151 + vertex 0.84278 1.32049 2.59043 + endloop + endfacet + facet normal -0.599649 -0.113389 0.79219 + outer loop + vertex 0.843326 1.31199 2.58962 + vertex 0.842212 1.31646 2.58942 + vertex 0.84033 1.31236 2.58741 + endloop + endfacet + facet normal -0.596809 -0.109645 0.794857 + outer loop + vertex 0.848496 1.31189 2.59351 + vertex 0.84775 1.31739 2.5937 + vertex 0.845395 1.3142 2.5915 + endloop + endfacet + facet normal -0.592088 -0.108806 0.798494 + outer loop + vertex 0.848496 1.31189 2.59351 + vertex 0.849036 1.30682 2.59322 + vertex 0.851651 1.30932 2.5955 + endloop + endfacet + facet normal -0.591242 -0.110101 0.798943 + outer loop + vertex 0.851651 1.30932 2.5955 + vertex 0.849036 1.30682 2.59322 + vertex 0.85215 1.30462 2.59522 + endloop + endfacet + facet normal -0.599743 -0.110441 0.792535 + outer loop + vertex 0.843326 1.31199 2.58962 + vertex 0.84279 1.30752 2.5886 + vertex 0.845891 1.30944 2.59121 + endloop + endfacet + facet normal -0.602644 -0.111218 0.790222 + outer loop + vertex 0.843558 1.30195 2.5884 + vertex 0.84279 1.30752 2.5886 + vertex 0.84044 1.30433 2.58635 + endloop + endfacet + facet normal -0.596641 -0.11048 0.794867 + outer loop + vertex 0.849788 1.30136 2.59302 + vertex 0.849036 1.30682 2.59322 + vertex 0.846288 1.30438 2.59081 + endloop + endfacet + facet normal -0.598119 -0.117832 0.792698 + outer loop + vertex 0.850464 1.29253 2.59226 + vertex 0.849281 1.29692 2.59202 + vertex 0.847281 1.29468 2.59017 + endloop + endfacet + facet normal -0.590726 -0.115521 0.79856 + outer loop + vertex 0.850464 1.29253 2.59226 + vertex 0.852315 1.29665 2.59422 + vertex 0.849281 1.29692 2.59202 + endloop + endfacet + facet normal -0.589645 -0.116331 0.799241 + outer loop + vertex 0.853507 1.29214 2.59445 + vertex 0.852315 1.29665 2.59422 + vertex 0.850464 1.29253 2.59226 + endloop + endfacet + facet normal -0.589619 -0.114671 0.7995 + outer loop + vertex 0.852997 1.28769 2.59343 + vertex 0.853507 1.29214 2.59445 + vertex 0.850464 1.29253 2.59226 + endloop + endfacet + facet normal -0.580694 -0.117098 0.805656 + outer loop + vertex 0.853507 1.29214 2.59445 + vertex 0.852997 1.28769 2.59343 + vertex 0.856207 1.28952 2.59601 + endloop + endfacet + facet normal -0.579858 -0.115761 0.806452 + outer loop + vertex 0.855608 1.2944 2.59628 + vertex 0.853507 1.29214 2.59445 + vertex 0.856207 1.28952 2.59601 + endloop + endfacet + facet normal -0.570253 -0.114965 0.813384 + outer loop + vertex 0.856207 1.28952 2.59601 + vertex 0.858872 1.2921 2.59824 + vertex 0.855608 1.2944 2.59628 + endloop + endfacet + facet normal -0.58265 -0.112586 0.804887 + outer loop + vertex 0.856207 1.28952 2.59601 + vertex 0.852997 1.28769 2.59343 + vertex 0.856516 1.28452 2.59554 + endloop + endfacet + facet normal -0.569061 -0.112662 0.814541 + outer loop + vertex 0.856516 1.28452 2.59554 + vertex 0.859765 1.28647 2.59807 + vertex 0.856207 1.28952 2.59601 + endloop + endfacet + facet normal -0.570894 -0.108644 0.813804 + outer loop + vertex 0.859216 1.28193 2.59708 + vertex 0.859765 1.28647 2.59807 + vertex 0.856516 1.28452 2.59554 + endloop + endfacet + facet normal -0.569771 -0.106866 0.814825 + outer loop + vertex 0.857068 1.27964 2.59528 + vertex 0.859216 1.28193 2.59708 + vertex 0.856516 1.28452 2.59554 + endloop + endfacet + facet normal -0.580797 -0.1077 0.806893 + outer loop + vertex 0.856516 1.28452 2.59554 + vertex 0.85382 1.28202 2.59326 + vertex 0.857068 1.27964 2.59528 + endloop + endfacet + facet normal -0.57903 -0.103771 0.808676 + outer loop + vertex 0.85382 1.28202 2.59326 + vertex 0.854662 1.27634 2.59314 + vertex 0.857068 1.27964 2.59528 + endloop + endfacet + facet normal -0.568525 -0.108544 0.815474 + outer loop + vertex 0.860376 1.27741 2.59729 + vertex 0.859216 1.28193 2.59708 + vertex 0.857068 1.27964 2.59528 + endloop + endfacet + facet normal -0.55876 -0.105715 0.822564 + outer loop + vertex 0.860376 1.27741 2.59729 + vertex 0.86238 1.28164 2.5992 + vertex 0.859216 1.28193 2.59708 + endloop + endfacet + facet normal -0.603278 -0.115958 0.789056 + outer loop + vertex 0.843558 1.30195 2.5884 + vertex 0.84419 1.29686 2.58813 + vertex 0.846709 1.29934 2.59042 + endloop + endfacet + facet normal -0.608724 -0.120183 0.784226 + outer loop + vertex 0.84513 1.29147 2.58804 + vertex 0.84419 1.29686 2.58813 + vertex 0.841572 1.29442 2.58573 + endloop + endfacet + facet normal -0.609582 -0.121948 0.783287 + outer loop + vertex 0.842205 1.28934 2.58543 + vertex 0.84513 1.29147 2.58804 + vertex 0.841572 1.29442 2.58573 + endloop + endfacet + facet normal -0.614691 -0.122345 0.779222 + outer loop + vertex 0.841572 1.29442 2.58573 + vertex 0.838948 1.29192 2.58327 + vertex 0.842205 1.28934 2.58543 + endloop + endfacet + facet normal -0.597907 -0.117286 0.792938 + outer loop + vertex 0.848083 1.29096 2.59023 + vertex 0.850464 1.29253 2.59226 + vertex 0.847281 1.29468 2.59017 + endloop + endfacet + facet normal -0.598876 -0.115253 0.792505 + outer loop + vertex 0.849944 1.28864 2.5913 + vertex 0.850464 1.29253 2.59226 + vertex 0.848083 1.29096 2.59023 + endloop + endfacet + facet normal -0.592928 -0.117083 0.796698 + outer loop + vertex 0.849944 1.28864 2.5913 + vertex 0.852997 1.28769 2.59343 + vertex 0.850464 1.29253 2.59226 + endloop + endfacet + facet normal -0.580298 -0.10847 0.807149 + outer loop + vertex 0.852997 1.28769 2.59343 + vertex 0.85382 1.28202 2.59326 + vertex 0.856516 1.28452 2.59554 + endloop + endfacet + facet normal -0.599267 -0.108638 0.793144 + outer loop + vertex 0.847694 1.28746 2.58942 + vertex 0.847511 1.28248 2.5886 + vertex 0.85052 1.2846 2.59116 + endloop + endfacet + facet normal -0.589386 -0.105139 0.80098 + outer loop + vertex 0.854662 1.27634 2.59314 + vertex 0.85382 1.28202 2.59326 + vertex 0.851083 1.27943 2.59091 + endloop + endfacet + facet normal -0.577564 -0.105386 0.809514 + outer loop + vertex 0.857802 1.27565 2.59528 + vertex 0.857068 1.27964 2.59528 + vertex 0.854662 1.27634 2.59314 + endloop + endfacet + facet normal -0.567472 -0.117511 0.814964 + outer loop + vertex 0.859752 1.2733 2.59633 + vertex 0.857211 1.27155 2.59431 + vertex 0.860553 1.26935 2.59632 + endloop + endfacet + facet normal -0.566332 -0.103313 0.817676 + outer loop + vertex 0.857802 1.27565 2.59528 + vertex 0.860376 1.27741 2.59729 + vertex 0.857068 1.27964 2.59528 + endloop + endfacet + facet normal -0.556842 -0.115381 0.822566 + outer loop + vertex 0.860553 1.26935 2.59632 + vertex 0.862941 1.27266 2.5984 + vertex 0.859752 1.2733 2.59633 + endloop + endfacet + facet normal -0.555248 -0.117058 0.823406 + outer loop + vertex 0.863894 1.26727 2.59828 + vertex 0.862941 1.27266 2.5984 + vertex 0.860553 1.26935 2.59632 + endloop + endfacet + facet normal -0.555135 -0.10838 0.824669 + outer loop + vertex 0.863535 1.2771 2.59938 + vertex 0.86238 1.28164 2.5992 + vertex 0.860376 1.27741 2.59729 + endloop + endfacet + facet normal -0.558778 -0.111844 0.821741 + outer loop + vertex 0.86238 1.28164 2.5992 + vertex 0.859765 1.28647 2.59807 + vertex 0.859216 1.28193 2.59708 + endloop + endfacet + facet normal -0.542581 -0.112012 0.832501 + outer loop + vertex 0.863014 1.2858 2.60018 + vertex 0.865762 1.28761 2.60221 + vertex 0.862249 1.28992 2.60024 + endloop + endfacet + facet normal -0.570297 -0.114901 0.813363 + outer loop + vertex 0.859765 1.28647 2.59807 + vertex 0.858872 1.2921 2.59824 + vertex 0.856207 1.28952 2.59601 + endloop + endfacet + facet normal -0.559902 -0.112432 0.820895 + outer loop + vertex 0.857973 1.29769 2.5984 + vertex 0.858872 1.2921 2.59824 + vertex 0.861457 1.29484 2.60038 + endloop + endfacet + facet normal -0.543828 -0.114941 0.831288 + outer loop + vertex 0.865762 1.28761 2.60221 + vertex 0.864717 1.29286 2.60226 + vertex 0.862249 1.28992 2.60024 + endloop + endfacet + facet normal -0.556096 -0.108756 0.823972 + outer loop + vertex 0.857355 1.30666 2.59919 + vertex 0.858517 1.30215 2.59938 + vertex 0.860766 1.30435 2.60119 + endloop + endfacet + facet normal -0.559216 -0.111148 0.821537 + outer loop + vertex 0.861149 1.29959 2.60081 + vertex 0.857973 1.29769 2.5984 + vertex 0.861457 1.29484 2.60038 + endloop + endfacet + facet normal -0.569759 -0.113828 0.813891 + outer loop + vertex 0.858872 1.2921 2.59824 + vertex 0.857973 1.29769 2.5984 + vertex 0.855608 1.2944 2.59628 + endloop + endfacet + facet normal -0.581297 -0.113805 0.805694 + outer loop + vertex 0.852315 1.29665 2.59422 + vertex 0.853507 1.29214 2.59445 + vertex 0.855608 1.2944 2.59628 + endloop + endfacet + facet normal -0.59075 -0.113143 0.798883 + outer loop + vertex 0.852315 1.29665 2.59422 + vertex 0.849788 1.30136 2.59302 + vertex 0.849281 1.29692 2.59202 + endloop + endfacet + facet normal -0.591147 -0.109873 0.799045 + outer loop + vertex 0.849036 1.30682 2.59322 + vertex 0.849788 1.30136 2.59302 + vertex 0.85215 1.30462 2.59522 + endloop + endfacet + facet normal -0.579065 -0.11055 0.807752 + outer loop + vertex 0.854823 1.2984 2.59629 + vertex 0.855402 1.30247 2.59726 + vertex 0.852878 1.30073 2.59521 + endloop + endfacet + facet normal -0.583329 -0.109607 0.804807 + outer loop + vertex 0.85215 1.30462 2.59522 + vertex 0.854248 1.30691 2.59705 + vertex 0.851651 1.30932 2.5955 + endloop + endfacet + facet normal -0.567929 -0.112168 0.815398 + outer loop + vertex 0.858517 1.30215 2.59938 + vertex 0.857355 1.30666 2.59919 + vertex 0.855402 1.30247 2.59726 + endloop + endfacet + facet normal -0.582048 -0.107441 0.806025 + outer loop + vertex 0.854248 1.30691 2.59705 + vertex 0.854804 1.31139 2.59805 + vertex 0.851651 1.30932 2.5955 + endloop + endfacet + facet normal -0.569034 -0.108232 0.81516 + outer loop + vertex 0.857982 1.3108 2.60019 + vertex 0.857278 1.31484 2.60023 + vertex 0.854804 1.31139 2.59805 + endloop + endfacet + facet normal -0.55763 -0.112343 0.822452 + outer loop + vertex 0.859982 1.30844 2.60122 + vertex 0.857355 1.30666 2.59919 + vertex 0.860766 1.30435 2.60119 + endloop + endfacet + facet normal -0.552942 -0.105557 0.826507 + outer loop + vertex 0.857982 1.3108 2.60019 + vertex 0.860695 1.31259 2.60223 + vertex 0.857278 1.31484 2.60023 + endloop + endfacet + facet normal -0.542957 -0.109591 0.832579 + outer loop + vertex 0.860766 1.30435 2.60119 + vertex 0.863299 1.30773 2.60329 + vertex 0.859982 1.30844 2.60122 + endloop + endfacet + facet normal -0.54132 -0.10457 0.834289 + outer loop + vertex 0.860695 1.31259 2.60223 + vertex 0.862979 1.31627 2.60418 + vertex 0.859709 1.31779 2.60224 + endloop + endfacet + facet normal -0.530315 -0.101159 0.841744 + outer loop + vertex 0.862022 1.3215 2.6042 + vertex 0.862979 1.31627 2.60418 + vertex 0.865578 1.31912 2.60615 + endloop + endfacet + facet normal -0.530806 -0.102255 0.841302 + outer loop + vertex 0.864858 1.3233 2.60621 + vertex 0.862022 1.3215 2.6042 + vertex 0.865578 1.31912 2.60615 + endloop + endfacet + facet normal -0.542648 -0.0991652 0.834086 + outer loop + vertex 0.862022 1.3215 2.6042 + vertex 0.859547 1.32634 2.60317 + vertex 0.858807 1.32191 2.60216 + endloop + endfacet + facet normal -0.527267 -0.0949085 0.844383 + outer loop + vertex 0.862847 1.32569 2.60522 + vertex 0.865746 1.32752 2.60724 + vertex 0.862221 1.32984 2.6053 + endloop + endfacet + facet normal -0.55323 -0.0972945 0.827327 + outer loop + vertex 0.859547 1.32634 2.60317 + vertex 0.858797 1.33198 2.60333 + vertex 0.856018 1.32931 2.60116 + endloop + endfacet + facet normal -0.527458 -0.0953378 0.844215 + outer loop + vertex 0.865746 1.32752 2.60724 + vertex 0.864943 1.33287 2.60734 + vertex 0.862221 1.32984 2.6053 + endloop + endfacet + facet normal -0.51721 -0.093922 0.850689 + outer loop + vertex 0.865746 1.32752 2.60724 + vertex 0.868257 1.33124 2.60918 + vertex 0.864943 1.33287 2.60734 + endloop + endfacet + facet normal -0.516343 -0.094734 0.851126 + outer loop + vertex 0.869047 1.32719 2.60921 + vertex 0.868257 1.33124 2.60918 + vertex 0.865746 1.32752 2.60724 + endloop + endfacet + facet normal -0.517202 -0.0916468 0.850943 + outer loop + vertex 0.864943 1.33287 2.60734 + vertex 0.867599 1.33608 2.6093 + vertex 0.864289 1.33778 2.60748 + endloop + endfacet + facet normal -0.516292 -0.0889925 0.851776 + outer loop + vertex 0.867599 1.33608 2.6093 + vertex 0.866798 1.34139 2.60937 + vertex 0.864289 1.33778 2.60748 + endloop + endfacet + facet normal -0.517296 -0.0880263 0.851267 + outer loop + vertex 0.864289 1.33778 2.60748 + vertex 0.866798 1.34139 2.60937 + vertex 0.86352 1.34188 2.60743 + endloop + endfacet + facet normal -0.542021 -0.0933218 0.835167 + outer loop + vertex 0.858012 1.33758 2.60344 + vertex 0.858797 1.33198 2.60333 + vertex 0.861573 1.33491 2.60546 + endloop + endfacet + facet normal -0.551305 -0.0897973 0.829457 + outer loop + vertex 0.858012 1.33758 2.60344 + vertex 0.858738 1.34198 2.6044 + vertex 0.85558 1.34239 2.60235 + endloop + endfacet + facet normal -0.52885 -0.0902781 0.8439 + outer loop + vertex 0.864289 1.33778 2.60748 + vertex 0.86352 1.34188 2.60743 + vertex 0.861199 1.33969 2.60574 + endloop + endfacet + facet normal -0.539911 -0.0853485 0.837384 + outer loop + vertex 0.857902 1.34613 2.60429 + vertex 0.858738 1.34198 2.6044 + vertex 0.861013 1.34418 2.60609 + endloop + endfacet + facet normal -0.552656 -0.0859254 0.828968 + outer loop + vertex 0.857902 1.34613 2.60429 + vertex 0.856984 1.35142 2.60422 + vertex 0.854662 1.34768 2.60229 + endloop + endfacet + facet normal -0.554379 -0.0833066 0.828084 + outer loop + vertex 0.856984 1.35142 2.60422 + vertex 0.854588 1.35628 2.60311 + vertex 0.853795 1.35186 2.60213 + endloop + endfacet + facet normal -0.535517 -0.0765785 0.841045 + outer loop + vertex 0.857825 1.35562 2.60519 + vertex 0.860707 1.35745 2.60719 + vertex 0.857285 1.35974 2.60522 + endloop + endfacet + facet normal -0.535599 -0.0767591 0.840977 + outer loop + vertex 0.860707 1.35745 2.60719 + vertex 0.860055 1.3628 2.60727 + vertex 0.857285 1.35974 2.60522 + endloop + endfacet + facet normal -0.523788 -0.0754199 0.848503 + outer loop + vertex 0.860707 1.35745 2.60719 + vertex 0.863278 1.36121 2.60912 + vertex 0.860055 1.3628 2.60727 + endloop + endfacet + facet normal -0.523231 -0.0737189 0.848996 + outer loop + vertex 0.863278 1.36121 2.60912 + vertex 0.86285 1.36601 2.60927 + vertex 0.860055 1.3628 2.60727 + endloop + endfacet + facet normal -0.524042 -0.0727531 0.84858 + outer loop + vertex 0.860055 1.3628 2.60727 + vertex 0.86285 1.36601 2.60927 + vertex 0.859607 1.36782 2.60742 + endloop + endfacet + facet normal -0.523711 -0.0718777 0.848858 + outer loop + vertex 0.86285 1.36601 2.60927 + vertex 0.862435 1.37096 2.60943 + vertex 0.859607 1.36782 2.60742 + endloop + endfacet + facet normal -0.524286 -0.0711706 0.848563 + outer loop + vertex 0.859607 1.36782 2.60742 + vertex 0.862435 1.37096 2.60943 + vertex 0.859149 1.37271 2.60755 + endloop + endfacet + facet normal -0.511566 -0.071105 0.856297 + outer loop + vertex 0.862435 1.37096 2.60943 + vertex 0.86285 1.36601 2.60927 + vertex 0.865726 1.36892 2.61123 + endloop + endfacet + facet normal -0.510788 -0.0693129 0.856908 + outer loop + vertex 0.865348 1.37387 2.6114 + vertex 0.862435 1.37096 2.60943 + vertex 0.865726 1.36892 2.61123 + endloop + endfacet + facet normal -0.498116 -0.0686094 0.864392 + outer loop + vertex 0.865726 1.36892 2.61123 + vertex 0.869181 1.37133 2.61341 + vertex 0.865348 1.37387 2.6114 + endloop + endfacet + facet normal -0.496944 -0.066147 0.865258 + outer loop + vertex 0.869181 1.37133 2.61341 + vertex 0.868179 1.37743 2.6133 + vertex 0.865348 1.37387 2.6114 + endloop + endfacet + facet normal -0.511612 -0.068212 0.856505 + outer loop + vertex 0.861756 1.37629 2.60945 + vertex 0.862435 1.37096 2.60943 + vertex 0.865348 1.37387 2.6114 + endloop + endfacet + facet normal -0.511487 -0.0712094 0.856336 + outer loop + vertex 0.865726 1.36892 2.61123 + vertex 0.86285 1.36601 2.60927 + vertex 0.865958 1.36425 2.61098 + endloop + endfacet + facet normal -0.549032 -0.076331 0.832309 + outer loop + vertex 0.853493 1.36692 2.60338 + vertex 0.854002 1.36178 2.60324 + vertex 0.856778 1.36476 2.60535 + endloop + endfacet + facet normal -0.554491 -0.0754735 0.82876 + outer loop + vertex 0.853493 1.36692 2.60338 + vertex 0.852866 1.3725 2.60347 + vertex 0.850235 1.36896 2.60139 + endloop + endfacet + facet normal -0.54492 -0.0736122 0.835251 + outer loop + vertex 0.85375 1.37691 2.60443 + vertex 0.852866 1.3725 2.60347 + vertex 0.856124 1.37462 2.60578 + endloop + endfacet + facet normal -0.536487 -0.0721123 0.840822 + outer loop + vertex 0.859607 1.36782 2.60742 + vertex 0.859149 1.37271 2.60755 + vertex 0.856336 1.36984 2.60551 + endloop + endfacet + facet normal -0.53694 -0.068426 0.840841 + outer loop + vertex 0.856124 1.37462 2.60578 + vertex 0.858511 1.37677 2.60748 + vertex 0.85611 1.37906 2.60613 + endloop + endfacet + facet normal -0.523773 -0.0697349 0.848999 + outer loop + vertex 0.862435 1.37096 2.60943 + vertex 0.861756 1.37629 2.60945 + vertex 0.859149 1.37271 2.60755 + endloop + endfacet + facet normal -0.533169 -0.0628135 0.843673 + outer loop + vertex 0.858511 1.37677 2.60748 + vertex 0.859362 1.38112 2.60834 + vertex 0.85611 1.37906 2.60613 + endloop + endfacet + facet normal -0.521988 -0.0596425 0.850865 + outer loop + vertex 0.862687 1.38045 2.61033 + vertex 0.862088 1.38461 2.61026 + vertex 0.859362 1.38112 2.60834 + endloop + endfacet + facet normal -0.511999 -0.0690236 0.856208 + outer loop + vertex 0.864706 1.37805 2.61136 + vertex 0.861756 1.37629 2.60945 + vertex 0.865348 1.37387 2.6114 + endloop + endfacet + facet normal -0.496558 -0.0665548 0.865448 + outer loop + vertex 0.865348 1.37387 2.6114 + vertex 0.868179 1.37743 2.6133 + vertex 0.864706 1.37805 2.61136 + endloop + endfacet + facet normal -0.493416 -0.0572957 0.867904 + outer loop + vertex 0.868947 1.38194 2.61405 + vertex 0.868256 1.38601 2.61393 + vertex 0.865631 1.38225 2.61219 + endloop + endfacet + facet normal -0.470682 -0.0545832 0.880613 + outer loop + vertex 0.874622 1.38276 2.61718 + vertex 0.874426 1.38769 2.61738 + vertex 0.871424 1.38452 2.61558 + endloop + endfacet + facet normal -0.460909 -0.0544041 0.885778 + outer loop + vertex 0.874622 1.38276 2.61718 + vertex 0.877743 1.38603 2.61901 + vertex 0.874426 1.38769 2.61738 + endloop + endfacet + facet normal -0.460211 -0.0525402 0.886254 + outer loop + vertex 0.877743 1.38603 2.61901 + vertex 0.877646 1.39106 2.61925 + vertex 0.874426 1.38769 2.61738 + endloop + endfacet + facet normal -0.460396 -0.0523164 0.886171 + outer loop + vertex 0.874426 1.38769 2.61738 + vertex 0.877646 1.39106 2.61925 + vertex 0.874327 1.39267 2.61762 + endloop + endfacet + facet normal -0.48234 -0.0534011 0.874355 + outer loop + vertex 0.867902 1.39089 2.61403 + vertex 0.868256 1.38601 2.61393 + vertex 0.871166 1.3893 2.61574 + endloop + endfacet + facet normal -0.494223 -0.051236 0.867824 + outer loop + vertex 0.867902 1.39089 2.61403 + vertex 0.867753 1.39594 2.61425 + vertex 0.864627 1.39268 2.61227 + endloop + endfacet + facet normal -0.470338 -0.0492694 0.88111 + outer loop + vertex 0.874327 1.39267 2.61762 + vertex 0.87426 1.3977 2.61787 + vertex 0.871036 1.39428 2.61596 + endloop + endfacet + facet normal -0.46009 -0.0493944 0.886497 + outer loop + vertex 0.874327 1.39267 2.61762 + vertex 0.877591 1.39609 2.61951 + vertex 0.87426 1.3977 2.61787 + endloop + endfacet + facet normal -0.458957 -0.0462981 0.887251 + outer loop + vertex 0.877591 1.39609 2.61951 + vertex 0.877454 1.40111 2.6197 + vertex 0.87426 1.3977 2.61787 + endloop + endfacet + facet normal -0.459577 -0.0455638 0.886968 + outer loop + vertex 0.87426 1.3977 2.61787 + vertex 0.877454 1.40111 2.6197 + vertex 0.874068 1.40277 2.61803 + endloop + endfacet + facet normal -0.481705 -0.0485834 0.874986 + outer loop + vertex 0.867614 1.40105 2.61445 + vertex 0.867753 1.39594 2.61425 + vertex 0.870936 1.39935 2.61619 + endloop + endfacet + facet normal -0.491966 -0.04604 0.869396 + outer loop + vertex 0.867614 1.40105 2.61445 + vertex 0.867294 1.40623 2.61455 + vertex 0.864324 1.40277 2.61268 + endloop + endfacet + facet normal -0.46859 -0.0426868 0.882384 + outer loop + vertex 0.874068 1.40277 2.61803 + vertex 0.873578 1.40787 2.61802 + vertex 0.870678 1.40446 2.61631 + endloop + endfacet + facet normal -0.459454 -0.0417959 0.887218 + outer loop + vertex 0.874068 1.40277 2.61803 + vertex 0.877087 1.40617 2.61975 + vertex 0.873578 1.40787 2.61802 + endloop + endfacet + facet normal -0.458781 -0.039964 0.88765 + outer loop + vertex 0.877087 1.40617 2.61975 + vertex 0.876469 1.41159 2.61968 + vertex 0.873578 1.40787 2.61802 + endloop + endfacet + facet normal -0.459862 -0.0388961 0.887138 + outer loop + vertex 0.873578 1.40787 2.61802 + vertex 0.876469 1.41159 2.61968 + vertex 0.872588 1.41272 2.61772 + endloop + endfacet + facet normal -0.481679 -0.0419163 0.875345 + outer loop + vertex 0.866688 1.41166 2.61447 + vertex 0.867294 1.40623 2.61455 + vertex 0.870142 1.40945 2.61627 + endloop + endfacet + facet normal -0.492534 -0.040096 0.869369 + outer loop + vertex 0.866688 1.41166 2.61447 + vertex 0.864383 1.41635 2.61338 + vertex 0.863355 1.4119 2.6126 + endloop + endfacet + facet normal -0.498582 -0.0374049 0.866035 + outer loop + vertex 0.864383 1.41635 2.61338 + vertex 0.863886 1.42175 2.61333 + vertex 0.860806 1.41885 2.61143 + endloop + endfacet + facet normal -0.465663 -0.0323442 0.884371 + outer loop + vertex 0.870256 1.42275 2.61689 + vertex 0.873284 1.42596 2.6186 + vertex 0.869925 1.42768 2.61689 + endloop + endfacet + facet normal -0.489138 -0.0349445 0.871506 + outer loop + vertex 0.863478 1.4268 2.6133 + vertex 0.863886 1.42175 2.61333 + vertex 0.866864 1.42469 2.61512 + endloop + endfacet + facet normal -0.496198 -0.033254 0.867572 + outer loop + vertex 0.863478 1.4268 2.6133 + vertex 0.862989 1.43231 2.61323 + vertex 0.860076 1.42884 2.61144 + endloop + endfacet + facet normal -0.476408 -0.0304305 0.878698 + outer loop + vertex 0.869925 1.42768 2.61689 + vertex 0.869797 1.43263 2.61699 + vertex 0.866574 1.42968 2.61514 + endloop + endfacet + facet normal -0.465472 -0.0302684 0.884545 + outer loop + vertex 0.869925 1.42768 2.61689 + vertex 0.873106 1.4309 2.61868 + vertex 0.869797 1.43263 2.61699 + endloop + endfacet + facet normal -0.464462 -0.0277493 0.885158 + outer loop + vertex 0.873106 1.4309 2.61868 + vertex 0.873042 1.43589 2.6188 + vertex 0.869797 1.43263 2.61699 + endloop + endfacet + facet normal -0.464999 -0.0270701 0.884897 + outer loop + vertex 0.869797 1.43263 2.61699 + vertex 0.873042 1.43589 2.6188 + vertex 0.869752 1.43761 2.61712 + endloop + endfacet + facet normal -0.486041 -0.0325426 0.87333 + outer loop + vertex 0.86402 1.43676 2.61397 + vertex 0.862989 1.43231 2.61323 + vertex 0.866586 1.43462 2.61532 + endloop + endfacet + facet normal -0.492069 -0.0264617 0.870154 + outer loop + vertex 0.86402 1.43676 2.61397 + vertex 0.863452 1.4409 2.61378 + vertex 0.860697 1.43713 2.61211 + endloop + endfacet + facet normal -0.472937 -0.0233904 0.880786 + outer loop + vertex 0.869752 1.43761 2.61712 + vertex 0.869673 1.44261 2.61721 + vertex 0.866601 1.43938 2.61548 + endloop + endfacet + facet normal -0.463959 -0.0233356 0.885549 + outer loop + vertex 0.869752 1.43761 2.61712 + vertex 0.872983 1.44094 2.6189 + vertex 0.869673 1.44261 2.61721 + endloop + endfacet + facet normal -0.462703 -0.0201159 0.886285 + outer loop + vertex 0.872983 1.44094 2.6189 + vertex 0.872908 1.44599 2.61898 + vertex 0.869673 1.44261 2.61721 + endloop + endfacet + facet normal -0.462849 -0.0199381 0.886213 + outer loop + vertex 0.869673 1.44261 2.61721 + vertex 0.872908 1.44599 2.61898 + vertex 0.869582 1.44765 2.61728 + endloop + endfacet + facet normal -0.48309 -0.0231055 0.875266 + outer loop + vertex 0.863153 1.44583 2.61374 + vertex 0.863452 1.4409 2.61378 + vertex 0.866412 1.44424 2.6155 + endloop + endfacet + facet normal -0.488604 -0.0214505 0.872242 + outer loop + vertex 0.863153 1.44583 2.61374 + vertex 0.863024 1.45085 2.6138 + vertex 0.85987 1.44757 2.61195 + endloop + endfacet + facet normal -0.471357 -0.0184134 0.88175 + outer loop + vertex 0.869582 1.44765 2.61728 + vertex 0.869526 1.45267 2.61735 + vertex 0.866291 1.44925 2.61555 + endloop + endfacet + facet normal -0.460865 -0.0183792 0.88728 + outer loop + vertex 0.869582 1.44765 2.61728 + vertex 0.872846 1.45102 2.61904 + vertex 0.869526 1.45267 2.61735 + endloop + endfacet + facet normal -0.460119 -0.0164475 0.887705 + outer loop + vertex 0.872846 1.45102 2.61904 + vertex 0.872798 1.45602 2.61911 + vertex 0.869526 1.45267 2.61735 + endloop + endfacet + facet normal -0.458951 -0.0178919 0.888281 + outer loop + vertex 0.869526 1.45267 2.61735 + vertex 0.872798 1.45602 2.61911 + vertex 0.869486 1.45768 2.61743 + endloop + endfacet + facet normal -0.48035 -0.0205049 0.876837 + outer loop + vertex 0.862973 1.45588 2.61389 + vertex 0.863024 1.45085 2.6138 + vertex 0.866238 1.45427 2.61564 + endloop + endfacet + facet normal -0.486978 -0.0203206 0.873178 + outer loop + vertex 0.862973 1.45588 2.61389 + vertex 0.862924 1.46091 2.61398 + vertex 0.859739 1.4576 2.61212 + endloop + endfacet + facet normal -0.468272 -0.0183396 0.883394 + outer loop + vertex 0.869486 1.45768 2.61743 + vertex 0.869434 1.46267 2.61751 + vertex 0.866196 1.45929 2.61572 + endloop + endfacet + facet normal -0.457627 -0.0183122 0.888956 + outer loop + vertex 0.869486 1.45768 2.61743 + vertex 0.872747 1.461 2.61918 + vertex 0.869434 1.46267 2.61751 + endloop + endfacet + facet normal -0.457433 -0.0178155 0.889066 + outer loop + vertex 0.872747 1.461 2.61918 + vertex 0.872683 1.46598 2.61925 + vertex 0.869434 1.46267 2.61751 + endloop + endfacet + facet normal -0.45688 -0.0184993 0.889336 + outer loop + vertex 0.869434 1.46267 2.61751 + vertex 0.872683 1.46598 2.61925 + vertex 0.869367 1.46766 2.61758 + endloop + endfacet + facet normal -0.4783 -0.0198155 0.877973 + outer loop + vertex 0.86286 1.46595 2.61405 + vertex 0.862924 1.46091 2.61398 + vertex 0.866138 1.46431 2.6158 + endloop + endfacet + facet normal -0.484886 -0.0189466 0.874372 + outer loop + vertex 0.86286 1.46595 2.61405 + vertex 0.862798 1.47098 2.61413 + vertex 0.859593 1.46761 2.61228 + endloop + endfacet + facet normal -0.466719 -0.0180608 0.884221 + outer loop + vertex 0.869367 1.46766 2.61758 + vertex 0.869297 1.47264 2.61764 + vertex 0.866072 1.46932 2.61587 + endloop + endfacet + facet normal -0.456956 -0.0179896 0.889307 + outer loop + vertex 0.869367 1.46766 2.61758 + vertex 0.872611 1.47096 2.61931 + vertex 0.869297 1.47264 2.61764 + endloop + endfacet + facet normal -0.456468 -0.016753 0.889582 + outer loop + vertex 0.872611 1.47096 2.61931 + vertex 0.872541 1.47595 2.61937 + vertex 0.869297 1.47264 2.61764 + endloop + endfacet + facet normal -0.457269 -0.015761 0.889189 + outer loop + vertex 0.869297 1.47264 2.61764 + vertex 0.872541 1.47595 2.61937 + vertex 0.869231 1.47763 2.6177 + endloop + endfacet + facet normal -0.477683 -0.0171684 0.878364 + outer loop + vertex 0.862748 1.47599 2.6142 + vertex 0.862798 1.47098 2.61413 + vertex 0.866009 1.47432 2.61594 + endloop + endfacet + facet normal -0.483483 -0.0136564 0.875247 + outer loop + vertex 0.862748 1.47599 2.6142 + vertex 0.862702 1.48099 2.61425 + vertex 0.859505 1.47765 2.61243 + endloop + endfacet + facet normal -0.466334 -0.0118877 0.884529 + outer loop + vertex 0.869231 1.47763 2.6177 + vertex 0.869176 1.48262 2.61774 + vertex 0.865952 1.47931 2.61599 + endloop + endfacet + facet normal -0.457492 -0.0118249 0.889135 + outer loop + vertex 0.869231 1.47763 2.6177 + vertex 0.872481 1.48094 2.61942 + vertex 0.869176 1.48262 2.61774 + endloop + endfacet + facet normal -0.456244 -0.00869393 0.889812 + outer loop + vertex 0.872481 1.48094 2.61942 + vertex 0.872437 1.48593 2.61944 + vertex 0.869176 1.48262 2.61774 + endloop + endfacet + facet normal -0.457185 -0.00752298 0.88934 + outer loop + vertex 0.869176 1.48262 2.61774 + vertex 0.872437 1.48593 2.61944 + vertex 0.869138 1.48761 2.61776 + endloop + endfacet + facet normal -0.477202 -0.0098124 0.878739 + outer loop + vertex 0.862661 1.48597 2.61429 + vertex 0.862702 1.48099 2.61425 + vertex 0.865904 1.48429 2.61603 + endloop + endfacet + facet normal -0.465748 -0.00449851 0.884906 + outer loop + vertex 0.869138 1.48761 2.61776 + vertex 0.869117 1.4926 2.61777 + vertex 0.86587 1.48928 2.61605 + endloop + endfacet + facet normal -0.456579 -0.00447352 0.889672 + outer loop + vertex 0.869138 1.48761 2.61776 + vertex 0.872412 1.49092 2.61946 + vertex 0.869117 1.4926 2.61777 + endloop + endfacet + facet normal -0.456082 -0.00323976 0.889932 + outer loop + vertex 0.872412 1.49092 2.61946 + vertex 0.8724 1.49591 2.61947 + vertex 0.869117 1.4926 2.61777 + endloop + endfacet + facet normal -0.455865 -0.00351137 0.890042 + outer loop + vertex 0.869117 1.4926 2.61777 + vertex 0.8724 1.49591 2.61947 + vertex 0.869104 1.49759 2.61779 + endloop + endfacet + facet normal -0.474359 -0.00595223 0.880312 + outer loop + vertex 0.862605 1.49595 2.61433 + vertex 0.862629 1.49096 2.61431 + vertex 0.86585 1.49427 2.61606 + endloop + endfacet + facet normal -0.480301 -0.00571531 0.877085 + outer loop + vertex 0.862605 1.49595 2.61433 + vertex 0.862584 1.50095 2.61435 + vertex 0.859371 1.49761 2.61257 + endloop + endfacet + facet normal -0.463828 -0.00371853 0.885917 + outer loop + vertex 0.869104 1.49759 2.61779 + vertex 0.869094 1.50259 2.6178 + vertex 0.865834 1.49927 2.61608 + endloop + endfacet + facet normal -0.455452 -0.00371448 0.890252 + outer loop + vertex 0.869104 1.49759 2.61779 + vertex 0.872391 1.5009 2.61948 + vertex 0.869094 1.50259 2.6178 + endloop + endfacet + facet normal -0.455152 -0.00296896 0.890409 + outer loop + vertex 0.872391 1.5009 2.61948 + vertex 0.872382 1.5059 2.61949 + vertex 0.869094 1.50259 2.6178 + endloop + endfacet + facet normal -0.455476 -0.00256314 0.890244 + outer loop + vertex 0.869094 1.50259 2.6178 + vertex 0.872382 1.5059 2.61949 + vertex 0.869085 1.50758 2.61781 + endloop + endfacet + facet normal -0.471946 -0.00480309 0.881614 + outer loop + vertex 0.862565 1.50594 2.61437 + vertex 0.862584 1.50095 2.61435 + vertex 0.86582 1.50426 2.6161 + endloop + endfacet + facet normal -0.478624 -0.00197393 0.878018 + outer loop + vertex 0.862565 1.50594 2.61437 + vertex 0.862554 1.51093 2.61437 + vertex 0.859325 1.50759 2.6126 + endloop + endfacet + facet normal -0.462002 -0.000605569 0.886879 + outer loop + vertex 0.869085 1.50758 2.61781 + vertex 0.869083 1.51257 2.61782 + vertex 0.86581 1.50925 2.61611 + endloop + endfacet + facet normal -0.455035 -0.00060454 0.890473 + outer loop + vertex 0.869085 1.50758 2.61781 + vertex 0.872378 1.51089 2.6195 + vertex 0.869083 1.51257 2.61782 + endloop + endfacet + facet normal -0.454148 0.00158425 0.890925 + outer loop + vertex 0.872378 1.51089 2.6195 + vertex 0.872383 1.51588 2.61949 + vertex 0.869083 1.51257 2.61782 + endloop + endfacet + facet normal -0.454596 0.00214654 0.890695 + outer loop + vertex 0.869083 1.51257 2.61782 + vertex 0.872383 1.51588 2.61949 + vertex 0.869091 1.51756 2.61781 + endloop + endfacet + facet normal -0.471121 0.000803157 0.882068 + outer loop + vertex 0.862554 1.51592 2.61437 + vertex 0.862554 1.51093 2.61437 + vertex 0.865809 1.51425 2.61611 + endloop + endfacet + facet normal -0.47842 0.00279583 0.878127 + outer loop + vertex 0.862554 1.51592 2.61437 + vertex 0.862561 1.52091 2.61435 + vertex 0.859317 1.51758 2.6126 + endloop + endfacet + facet normal -0.461541 0.00366631 0.887111 + outer loop + vertex 0.869091 1.51756 2.61781 + vertex 0.869105 1.52255 2.61779 + vertex 0.865816 1.51924 2.6161 + endloop + endfacet + facet normal -0.454039 0.00365649 0.890974 + outer loop + vertex 0.869091 1.51756 2.61781 + vertex 0.872398 1.52087 2.61948 + vertex 0.869105 1.52255 2.61779 + endloop + endfacet + facet normal -0.453754 0.00435709 0.891116 + outer loop + vertex 0.872398 1.52087 2.61948 + vertex 0.872414 1.52587 2.61946 + vertex 0.869105 1.52255 2.61779 + endloop + endfacet + facet normal -0.454019 0.00469122 0.89098 + outer loop + vertex 0.869105 1.52255 2.61779 + vertex 0.872414 1.52587 2.61946 + vertex 0.86912 1.52755 2.61777 + endloop + endfacet + facet normal -0.469843 0.00354295 0.882743 + outer loop + vertex 0.862568 1.52591 2.61434 + vertex 0.862561 1.52091 2.61435 + vertex 0.865828 1.52423 2.61608 + endloop + endfacet + facet normal -0.475031 0.00380187 0.879961 + outer loop + vertex 0.862568 1.52591 2.61434 + vertex 0.862575 1.5309 2.61432 + vertex 0.859321 1.52756 2.61258 + endloop + endfacet + facet normal -0.46116 0.00525007 0.887301 + outer loop + vertex 0.86912 1.52755 2.61777 + vertex 0.869135 1.53254 2.61775 + vertex 0.86584 1.52922 2.61606 + endloop + endfacet + facet normal -0.454753 0.00524506 0.890602 + outer loop + vertex 0.86912 1.52755 2.61777 + vertex 0.872429 1.53086 2.61945 + vertex 0.869135 1.53254 2.61775 + endloop + endfacet + facet normal -0.455031 0.00456212 0.890464 + outer loop + vertex 0.872429 1.53086 2.61945 + vertex 0.872443 1.53585 2.61943 + vertex 0.869135 1.53254 2.61775 + endloop + endfacet + facet normal -0.456124 0.00594037 0.889896 + outer loop + vertex 0.869135 1.53254 2.61775 + vertex 0.872443 1.53585 2.61943 + vertex 0.869154 1.53753 2.61773 + endloop + endfacet + facet normal -0.467582 0.00504962 0.883935 + outer loop + vertex 0.862586 1.53589 2.6143 + vertex 0.862575 1.5309 2.61432 + vertex 0.865855 1.53421 2.61604 + endloop + endfacet + facet normal -0.471031 0.00712857 0.882088 + outer loop + vertex 0.862586 1.53589 2.6143 + vertex 0.862605 1.54088 2.61427 + vertex 0.859326 1.53755 2.61254 + endloop + endfacet + facet normal -0.46208 0.00710622 0.88681 + outer loop + vertex 0.869154 1.53753 2.61773 + vertex 0.869179 1.54252 2.6177 + vertex 0.865877 1.5392 2.61601 + endloop + endfacet + facet normal -0.457518 0.00709554 0.889172 + outer loop + vertex 0.869154 1.53753 2.61773 + vertex 0.872462 1.54084 2.61941 + vertex 0.869179 1.54252 2.6177 + endloop + endfacet + facet normal -0.457567 0.00697412 0.889148 + outer loop + vertex 0.872462 1.54084 2.61941 + vertex 0.872488 1.54583 2.61938 + vertex 0.869179 1.54252 2.6177 + endloop + endfacet + facet normal -0.459075 0.00888144 0.888353 + outer loop + vertex 0.869179 1.54252 2.6177 + vertex 0.872488 1.54583 2.61938 + vertex 0.869212 1.54751 2.61767 + endloop + endfacet + facet normal -0.467153 0.00927602 0.884128 + outer loop + vertex 0.862634 1.54587 2.61423 + vertex 0.862605 1.54088 2.61427 + vertex 0.865906 1.54419 2.61598 + endloop + endfacet + facet normal -0.470816 0.0116776 0.882154 + outer loop + vertex 0.862634 1.54587 2.61423 + vertex 0.862672 1.55086 2.61418 + vertex 0.859372 1.54753 2.61247 + endloop + endfacet + facet normal -0.463642 0.0108758 0.885956 + outer loop + vertex 0.869212 1.54751 2.61767 + vertex 0.86925 1.5525 2.61763 + vertex 0.865941 1.54919 2.61594 + endloop + endfacet + facet normal -0.460166 0.0108641 0.887766 + outer loop + vertex 0.869212 1.54751 2.61767 + vertex 0.872522 1.55082 2.61934 + vertex 0.86925 1.5525 2.61763 + endloop + endfacet + facet normal -0.459413 0.0127091 0.888132 + outer loop + vertex 0.872522 1.55082 2.61934 + vertex 0.872564 1.55582 2.6193 + vertex 0.86925 1.5525 2.61763 + endloop + endfacet + facet normal -0.46043 0.0140011 0.887586 + outer loop + vertex 0.86925 1.5525 2.61763 + vertex 0.872564 1.55582 2.6193 + vertex 0.869296 1.55749 2.61757 + endloop + endfacet + facet normal -0.468952 0.0144154 0.883106 + outer loop + vertex 0.862724 1.55586 2.61413 + vertex 0.862672 1.55086 2.61418 + vertex 0.865983 1.55418 2.61589 + endloop + endfacet + facet normal -0.473414 0.0171171 0.880674 + outer loop + vertex 0.862724 1.55586 2.61413 + vertex 0.862792 1.56085 2.61407 + vertex 0.859483 1.55752 2.61236 + endloop + endfacet + facet normal -0.464891 0.0168519 0.885208 + outer loop + vertex 0.869296 1.55749 2.61757 + vertex 0.86935 1.56249 2.61751 + vertex 0.866036 1.55917 2.61583 + endloop + endfacet + facet normal -0.460179 0.0168327 0.887667 + outer loop + vertex 0.869296 1.55749 2.61757 + vertex 0.872617 1.56081 2.61923 + vertex 0.86935 1.56249 2.61751 + endloop + endfacet + facet normal -0.459466 0.0185623 0.888001 + outer loop + vertex 0.872617 1.56081 2.61923 + vertex 0.872679 1.5658 2.61916 + vertex 0.86935 1.56249 2.61751 + endloop + endfacet + facet normal -0.459338 0.0183996 0.888071 + outer loop + vertex 0.86935 1.56249 2.61751 + vertex 0.872679 1.5658 2.61916 + vertex 0.869414 1.56748 2.61744 + endloop + endfacet + facet normal -0.471027 0.0192079 0.88191 + outer loop + vertex 0.862868 1.56582 2.614 + vertex 0.862792 1.56085 2.61407 + vertex 0.8661 1.56416 2.61576 + endloop + endfacet + facet normal -0.477279 0.0202372 0.878519 + outer loop + vertex 0.862868 1.56582 2.614 + vertex 0.862945 1.57079 2.61393 + vertex 0.859631 1.56747 2.61221 + endloop + endfacet + facet normal -0.465506 0.0188898 0.884843 + outer loop + vertex 0.869414 1.56748 2.61744 + vertex 0.869484 1.57248 2.61737 + vertex 0.866171 1.56914 2.6157 + endloop + endfacet + facet normal -0.458562 0.0188432 0.888463 + outer loop + vertex 0.869414 1.56748 2.61744 + vertex 0.872749 1.5708 2.61909 + vertex 0.869484 1.57248 2.61737 + endloop + endfacet + facet normal -0.458532 0.0189156 0.888477 + outer loop + vertex 0.872749 1.5708 2.61909 + vertex 0.872824 1.5758 2.61902 + vertex 0.869484 1.57248 2.61737 + endloop + endfacet + facet normal -0.458766 0.019215 0.888349 + outer loop + vertex 0.869484 1.57248 2.61737 + vertex 0.872824 1.5758 2.61902 + vertex 0.86956 1.57747 2.6173 + endloop + endfacet + facet normal -0.473325 0.020787 0.880643 + outer loop + vertex 0.86302 1.57575 2.61385 + vertex 0.862945 1.57079 2.61393 + vertex 0.866245 1.57412 2.61562 + endloop + endfacet + facet normal -0.480978 0.0222914 0.876449 + outer loop + vertex 0.86302 1.57575 2.61385 + vertex 0.863096 1.58071 2.61377 + vertex 0.859795 1.57743 2.61204 + endloop + endfacet + facet normal -0.4665 0.0206222 0.884281 + outer loop + vertex 0.86956 1.57747 2.6173 + vertex 0.869642 1.58247 2.61722 + vertex 0.866321 1.5791 2.61555 + endloop + endfacet + facet normal -0.459236 0.0205585 0.888076 + outer loop + vertex 0.86956 1.57747 2.6173 + vertex 0.872906 1.5808 2.61895 + vertex 0.869642 1.58247 2.61722 + endloop + endfacet + facet normal -0.458796 0.0216257 0.888278 + outer loop + vertex 0.872906 1.5808 2.61895 + vertex 0.872986 1.58579 2.61887 + vertex 0.869642 1.58247 2.61722 + endloop + endfacet + facet normal -0.460838 0.0242432 0.887153 + outer loop + vertex 0.869642 1.58247 2.61722 + vertex 0.872986 1.58579 2.61887 + vertex 0.86972 1.58746 2.61713 + endloop + endfacet + facet normal -0.477022 0.0254038 0.878524 + outer loop + vertex 0.863155 1.58568 2.61366 + vertex 0.863096 1.58071 2.61377 + vertex 0.866395 1.58409 2.61546 + endloop + endfacet + facet normal -0.484072 0.0293658 0.874535 + outer loop + vertex 0.863155 1.58568 2.61366 + vertex 0.863125 1.59064 2.61347 + vertex 0.859986 1.58729 2.61185 + endloop + endfacet + facet normal -0.480706 0.0344732 0.876204 + outer loop + vertex 0.862747 1.59589 2.61306 + vertex 0.863125 1.59064 2.61347 + vertex 0.86643 1.5941 2.61515 + endloop + endfacet + facet normal -0.469133 0.0283588 0.882672 + outer loop + vertex 0.86972 1.58746 2.61713 + vertex 0.869778 1.59243 2.617 + vertex 0.866441 1.58908 2.61533 + endloop + endfacet + facet normal -0.462185 0.0283713 0.88633 + outer loop + vertex 0.86972 1.58746 2.61713 + vertex 0.873058 1.59076 2.61876 + vertex 0.869778 1.59243 2.617 + endloop + endfacet + facet normal -0.461861 0.0291585 0.886473 + outer loop + vertex 0.873058 1.59076 2.61876 + vertex 0.873132 1.59571 2.61864 + vertex 0.869778 1.59243 2.617 + endloop + endfacet + facet normal -0.463345 0.0310912 0.885633 + outer loop + vertex 0.869778 1.59243 2.617 + vertex 0.873132 1.59571 2.61864 + vertex 0.869856 1.59737 2.61687 + endloop + endfacet + facet normal -0.485726 0.0393297 0.873226 + outer loop + vertex 0.864329 1.60706 2.61345 + vertex 0.86353 1.60147 2.61326 + vertex 0.867006 1.60405 2.61508 + endloop + endfacet + facet normal -0.481093 0.0334743 0.87603 + outer loop + vertex 0.866588 1.59917 2.61504 + vertex 0.862747 1.59589 2.61306 + vertex 0.86643 1.5941 2.61515 + endloop + endfacet + facet normal -0.48774 0.0361498 0.87224 + outer loop + vertex 0.859491 1.59516 2.61127 + vertex 0.859984 1.59182 2.61168 + vertex 0.862747 1.59589 2.61306 + endloop + endfacet + facet normal -0.496571 0.0395234 0.867096 + outer loop + vertex 0.85758 1.59291 2.61028 + vertex 0.859491 1.59516 2.61127 + vertex 0.857111 1.59626 2.60986 + endloop + endfacet + facet normal -0.504814 0.042053 0.862203 + outer loop + vertex 0.857111 1.59626 2.60986 + vertex 0.857194 1.60081 2.60968 + vertex 0.854056 1.59751 2.60801 + endloop + endfacet + facet normal -0.499374 0.044326 0.865252 + outer loop + vertex 0.857382 1.60571 2.60954 + vertex 0.857194 1.60081 2.60968 + vertex 0.860524 1.60382 2.61145 + endloop + endfacet + facet normal -0.507374 0.0473165 0.860426 + outer loop + vertex 0.857382 1.60571 2.60954 + vertex 0.857545 1.61071 2.60936 + vertex 0.854252 1.60743 2.6076 + endloop + endfacet + facet normal -0.49432 0.0441029 0.868161 + outer loop + vertex 0.864329 1.60706 2.61345 + vertex 0.864016 1.61238 2.613 + vertex 0.860744 1.60895 2.61132 + endloop + endfacet + facet normal -0.489067 0.0489819 0.87087 + outer loop + vertex 0.864016 1.61238 2.613 + vertex 0.86721 1.61578 2.61461 + vertex 0.864088 1.6174 2.61276 + endloop + endfacet + facet normal -0.48863 0.0500339 0.871055 + outer loop + vertex 0.86721 1.61578 2.61461 + vertex 0.867394 1.62074 2.61443 + vertex 0.864088 1.6174 2.61276 + endloop + endfacet + facet normal -0.489716 0.0514534 0.870362 + outer loop + vertex 0.864088 1.6174 2.61276 + vertex 0.867394 1.62074 2.61443 + vertex 0.864257 1.6224 2.61256 + endloop + endfacet + facet normal -0.504152 0.0510207 0.862106 + outer loop + vertex 0.857707 1.61569 2.60916 + vertex 0.857545 1.61071 2.60936 + vertex 0.860824 1.61403 2.61108 + endloop + endfacet + facet normal -0.510541 0.0544967 0.858125 + outer loop + vertex 0.857707 1.61569 2.60916 + vertex 0.857875 1.62063 2.60895 + vertex 0.854632 1.61736 2.60723 + endloop + endfacet + facet normal -0.512358 0.0569544 0.856881 + outer loop + vertex 0.854632 1.61736 2.60723 + vertex 0.857875 1.62063 2.60895 + vertex 0.854852 1.6222 2.60704 + endloop + endfacet + facet normal -0.517863 0.0570731 0.853558 + outer loop + vertex 0.854632 1.61736 2.60723 + vertex 0.854852 1.6222 2.60704 + vertex 0.851644 1.61921 2.60529 + endloop + endfacet + facet normal -0.519102 0.0544638 0.852975 + outer loop + vertex 0.851279 1.61416 2.60539 + vertex 0.854632 1.61736 2.60723 + vertex 0.851644 1.61921 2.60529 + endloop + endfacet + facet normal -0.529112 0.0550649 0.846763 + outer loop + vertex 0.851644 1.61921 2.60529 + vertex 0.848294 1.61628 2.60339 + vertex 0.851279 1.61416 2.60539 + endloop + endfacet + facet normal -0.529527 0.0557358 0.84646 + outer loop + vertex 0.848774 1.62144 2.60335 + vertex 0.848294 1.61628 2.60339 + vertex 0.851644 1.61921 2.60529 + endloop + endfacet + facet normal -0.527992 0.058391 0.847239 + outer loop + vertex 0.852052 1.62401 2.60521 + vertex 0.848774 1.62144 2.60335 + vertex 0.851644 1.61921 2.60529 + endloop + endfacet + facet normal -0.528451 0.0592268 0.846895 + outer loop + vertex 0.849502 1.627 2.60341 + vertex 0.848774 1.62144 2.60335 + vertex 0.852052 1.62401 2.60521 + endloop + endfacet + facet normal -0.527564 0.0602686 0.847375 + outer loop + vertex 0.852641 1.62771 2.60532 + vertex 0.849502 1.627 2.60341 + vertex 0.852052 1.62401 2.60521 + endloop + endfacet + facet normal -0.527402 0.0590307 0.847563 + outer loop + vertex 0.852641 1.62771 2.60532 + vertex 0.852218 1.63104 2.60482 + vertex 0.849502 1.627 2.60341 + endloop + endfacet + facet normal -0.529711 0.0611416 0.845972 + outer loop + vertex 0.849502 1.627 2.60341 + vertex 0.852218 1.63104 2.60482 + vertex 0.849218 1.63233 2.60285 + endloop + endfacet + facet normal -0.518258 0.0576603 0.853278 + outer loop + vertex 0.851644 1.61921 2.60529 + vertex 0.854852 1.6222 2.60704 + vertex 0.852052 1.62401 2.60521 + endloop + endfacet + facet normal -0.51764 0.0589118 0.853568 + outer loop + vertex 0.854852 1.6222 2.60704 + vertex 0.85495 1.62665 2.60679 + vertex 0.852052 1.62401 2.60521 + endloop + endfacet + facet normal -0.512161 0.0574373 0.856967 + outer loop + vertex 0.857875 1.62063 2.60895 + vertex 0.857953 1.62552 2.60867 + vertex 0.854852 1.6222 2.60704 + endloop + endfacet + facet normal -0.508565 0.0575023 0.859101 + outer loop + vertex 0.857953 1.62552 2.60867 + vertex 0.857875 1.62063 2.60895 + vertex 0.861118 1.624 2.61064 + endloop + endfacet + facet normal -0.498338 0.0515478 0.865449 + outer loop + vertex 0.864088 1.6174 2.61276 + vertex 0.864257 1.6224 2.61256 + vertex 0.86097 1.61904 2.61087 + endloop + endfacet + facet normal -0.491738 0.0540354 0.869065 + outer loop + vertex 0.864257 1.6224 2.61256 + vertex 0.867586 1.62575 2.61424 + vertex 0.864423 1.62738 2.61235 + endloop + endfacet + facet normal -0.491797 0.0538908 0.86904 + outer loop + vertex 0.867586 1.62575 2.61424 + vertex 0.867759 1.63072 2.61403 + vertex 0.864423 1.62738 2.61235 + endloop + endfacet + facet normal -0.493613 0.0562958 0.867858 + outer loop + vertex 0.864423 1.62738 2.61235 + vertex 0.867759 1.63072 2.61403 + vertex 0.864597 1.63233 2.61212 + endloop + endfacet + facet normal -0.511753 0.0595245 0.857068 + outer loop + vertex 0.858527 1.6363 2.60826 + vertex 0.857681 1.63072 2.60815 + vertex 0.861456 1.63405 2.61017 + endloop + endfacet + facet normal -0.50878 0.0569369 0.859012 + outer loop + vertex 0.861208 1.62899 2.61036 + vertex 0.857953 1.62552 2.60867 + vertex 0.861118 1.624 2.61064 + endloop + endfacet + facet normal -0.513359 0.0589611 0.856146 + outer loop + vertex 0.854852 1.6222 2.60704 + vertex 0.857953 1.62552 2.60867 + vertex 0.85495 1.62665 2.60679 + endloop + endfacet + facet normal -0.517214 0.0588174 0.853832 + outer loop + vertex 0.854524 1.62994 2.6063 + vertex 0.852641 1.62771 2.60532 + vertex 0.85495 1.62665 2.60679 + endloop + endfacet + facet normal -0.517343 0.0584612 0.853779 + outer loop + vertex 0.852052 1.62401 2.60521 + vertex 0.85495 1.62665 2.60679 + vertex 0.852641 1.62771 2.60532 + endloop + endfacet + facet normal -0.51899 0.0608512 0.852611 + outer loop + vertex 0.852641 1.62771 2.60532 + vertex 0.854524 1.62994 2.6063 + vertex 0.852218 1.63104 2.60482 + endloop + endfacet + facet normal -0.529491 0.0617901 0.846062 + outer loop + vertex 0.852218 1.63104 2.60482 + vertex 0.852336 1.63559 2.60456 + vertex 0.849218 1.63233 2.60285 + endloop + endfacet + facet normal -0.530673 0.0633689 0.845204 + outer loop + vertex 0.849218 1.63233 2.60285 + vertex 0.852336 1.63559 2.60456 + vertex 0.849333 1.63732 2.60255 + endloop + endfacet + facet normal -0.529749 0.0654621 0.845624 + outer loop + vertex 0.852336 1.63559 2.60456 + vertex 0.85256 1.64053 2.60432 + vertex 0.849333 1.63732 2.60255 + endloop + endfacet + facet normal -0.531137 0.0674262 0.844599 + outer loop + vertex 0.849333 1.63732 2.60255 + vertex 0.85256 1.64053 2.60432 + vertex 0.849547 1.64226 2.60229 + endloop + endfacet + facet normal -0.530322 0.0692678 0.844962 + outer loop + vertex 0.85256 1.64053 2.60432 + vertex 0.85275 1.64552 2.60403 + vertex 0.849547 1.64226 2.60229 + endloop + endfacet + facet normal -0.531716 0.0711921 0.843925 + outer loop + vertex 0.849547 1.64226 2.60229 + vertex 0.85275 1.64552 2.60403 + vertex 0.849759 1.64709 2.60201 + endloop + endfacet + facet normal -0.531116 0.0726612 0.844178 + outer loop + vertex 0.85275 1.64552 2.60403 + vertex 0.852877 1.6505 2.60368 + vertex 0.849759 1.64709 2.60201 + endloop + endfacet + facet normal -0.514388 0.0599577 0.855459 + outer loop + vertex 0.857681 1.63072 2.60815 + vertex 0.858527 1.6363 2.60826 + vertex 0.855144 1.63369 2.60641 + endloop + endfacet + facet normal -0.512838 0.0623365 0.856219 + outer loop + vertex 0.859402 1.64193 2.60838 + vertex 0.858527 1.6363 2.60826 + vertex 0.861954 1.63894 2.61012 + endloop + endfacet + facet normal -0.520861 0.0653287 0.851138 + outer loop + vertex 0.85256 1.64053 2.60432 + vertex 0.852336 1.63559 2.60456 + vertex 0.855625 1.63864 2.60634 + endloop + endfacet + facet normal -0.524419 0.0727817 0.848344 + outer loop + vertex 0.852877 1.6505 2.60368 + vertex 0.85275 1.64552 2.60403 + vertex 0.85602 1.64892 2.60576 + endloop + endfacet + facet normal -0.517231 0.0665971 0.853251 + outer loop + vertex 0.859402 1.64193 2.60838 + vertex 0.859184 1.64729 2.60783 + vertex 0.855898 1.64381 2.60611 + endloop + endfacet + facet normal -0.515309 0.0667936 0.854397 + outer loop + vertex 0.859402 1.64193 2.60838 + vertex 0.862232 1.6461 2.60976 + vertex 0.859184 1.64729 2.60783 + endloop + endfacet + facet normal -0.516334 0.07076 0.853459 + outer loop + vertex 0.859184 1.64729 2.60783 + vertex 0.862375 1.65072 2.60947 + vertex 0.859321 1.65232 2.60749 + endloop + endfacet + facet normal -0.516234 0.0710028 0.8535 + outer loop + vertex 0.862375 1.65072 2.60947 + vertex 0.862602 1.65564 2.6092 + vertex 0.859321 1.65232 2.60749 + endloop + endfacet + facet normal -0.518196 0.0736672 0.852083 + outer loop + vertex 0.859321 1.65232 2.60749 + vertex 0.862602 1.65564 2.6092 + vertex 0.859564 1.65725 2.60721 + endloop + endfacet + facet normal -0.524114 0.0735521 0.848466 + outer loop + vertex 0.856203 1.65401 2.60543 + vertex 0.852877 1.6505 2.60368 + vertex 0.85602 1.64892 2.60576 + endloop + endfacet + facet normal -0.531582 0.0732563 0.843833 + outer loop + vertex 0.849759 1.64709 2.60201 + vertex 0.852877 1.6505 2.60368 + vertex 0.849897 1.65158 2.60171 + endloop + endfacet + facet normal -0.528638 0.0808675 0.844987 + outer loop + vertex 0.854171 1.66205 2.60341 + vertex 0.852789 1.65585 2.60314 + vertex 0.856667 1.65902 2.60527 + endloop + endfacet + facet normal -0.548985 0.0848868 0.83151 + outer loop + vertex 0.847484 1.66049 2.59925 + vertex 0.847294 1.65588 2.59959 + vertex 0.850307 1.65883 2.60128 + endloop + endfacet + facet normal -0.565511 0.0891873 0.819904 + outer loop + vertex 0.847484 1.66049 2.59925 + vertex 0.847709 1.66545 2.59886 + vertex 0.844639 1.66198 2.59712 + endloop + endfacet + facet normal -0.535831 0.085992 0.839935 + outer loop + vertex 0.854171 1.66205 2.60341 + vertex 0.854122 1.66741 2.60283 + vertex 0.85078 1.66389 2.60106 + endloop + endfacet + facet normal -0.535952 0.0918713 0.839235 + outer loop + vertex 0.854122 1.66741 2.60283 + vertex 0.8573 1.6707 2.6045 + vertex 0.854351 1.67234 2.60244 + endloop + endfacet + facet normal -0.552439 0.0968042 0.827913 + outer loop + vertex 0.847722 1.67085 2.59824 + vertex 0.847709 1.66545 2.59886 + vertex 0.851026 1.66904 2.60066 + endloop + endfacet + facet normal -0.564334 0.102647 0.81914 + outer loop + vertex 0.847722 1.67085 2.59824 + vertex 0.84916 1.67706 2.59845 + vertex 0.845359 1.6738 2.59624 + endloop + endfacet + facet normal -0.580567 0.101896 0.807811 + outer loop + vertex 0.842577 1.67539 2.59404 + vertex 0.842392 1.67084 2.59448 + vertex 0.845359 1.6738 2.59624 + endloop + endfacet + facet normal -0.583566 0.106544 0.805046 + outer loop + vertex 0.845359 1.6738 2.59624 + vertex 0.842392 1.67084 2.59448 + vertex 0.844556 1.66988 2.59618 + endloop + endfacet + facet normal -0.607533 0.0966162 0.788396 + outer loop + vertex 0.839671 1.67196 2.5923 + vertex 0.839804 1.67646 2.59185 + vertex 0.83708 1.67376 2.59009 + endloop + endfacet + facet normal -0.620329 0.0951321 0.778551 + outer loop + vertex 0.834866 1.67678 2.58795 + vertex 0.834082 1.67126 2.588 + vertex 0.83708 1.67376 2.59009 + endloop + endfacet + facet normal -0.608432 0.100541 0.787212 + outer loop + vertex 0.837677 1.67749 2.5901 + vertex 0.839475 1.67976 2.5912 + vertex 0.837318 1.68082 2.5894 + endloop + endfacet + facet normal -0.637903 0.0980699 0.763847 + outer loop + vertex 0.829781 1.68198 2.5831 + vertex 0.828971 1.67627 2.58316 + vertex 0.832024 1.67887 2.58537 + endloop + endfacet + facet normal -0.628643 0.096254 0.771715 + outer loop + vertex 0.834082 1.67126 2.588 + vertex 0.834866 1.67678 2.58795 + vertex 0.83152 1.67376 2.5856 + endloop + endfacet + facet normal -0.620495 0.0924082 0.778747 + outer loop + vertex 0.834082 1.67126 2.588 + vertex 0.83363 1.66614 2.58825 + vertex 0.836703 1.66887 2.59037 + endloop + endfacet + facet normal -0.620849 0.0876095 0.779019 + outer loop + vertex 0.83363 1.66614 2.58825 + vertex 0.833265 1.66114 2.58852 + vertex 0.836343 1.66373 2.59068 + endloop + endfacet + facet normal -0.628801 0.0835945 0.77306 + outer loop + vertex 0.832868 1.65621 2.58873 + vertex 0.833265 1.66114 2.58852 + vertex 0.83025 1.65859 2.58634 + endloop + endfacet + facet normal -0.637535 0.0825877 0.765982 + outer loop + vertex 0.83025 1.65859 2.58634 + vertex 0.827417 1.65567 2.5843 + vertex 0.82992 1.65395 2.58657 + endloop + endfacet + facet normal -0.639714 0.0882685 0.763528 + outer loop + vertex 0.827997 1.66592 2.58362 + vertex 0.827285 1.6606 2.58364 + vertex 0.830583 1.66351 2.58607 + endloop + endfacet + facet normal -0.639341 0.0928842 0.763293 + outer loop + vertex 0.828461 1.67101 2.58339 + vertex 0.827997 1.66592 2.58362 + vertex 0.831021 1.66857 2.58583 + endloop + endfacet + facet normal -0.646764 0.0967383 0.75653 + outer loop + vertex 0.828461 1.67101 2.58339 + vertex 0.828971 1.67627 2.58316 + vertex 0.825911 1.67344 2.5809 + endloop + endfacet + facet normal -0.638839 0.0991888 0.76292 + outer loop + vertex 0.829781 1.68198 2.5831 + vertex 0.832192 1.68611 2.58458 + vertex 0.829606 1.68694 2.58231 + endloop + endfacet + facet normal -0.654619 0.0995472 0.749376 + outer loop + vertex 0.824785 1.68708 2.57812 + vertex 0.823906 1.68128 2.57813 + vertex 0.826951 1.68403 2.58042 + endloop + endfacet + facet normal -0.645398 0.0989802 0.757406 + outer loop + vertex 0.829238 1.69029 2.58156 + vertex 0.827534 1.688 2.5804 + vertex 0.829606 1.68694 2.58231 + endloop + endfacet + facet normal -0.639441 0.100714 0.762215 + outer loop + vertex 0.829238 1.69029 2.58156 + vertex 0.829606 1.68694 2.58231 + vertex 0.832002 1.69086 2.5838 + endloop + endfacet + facet normal -0.632009 0.100639 0.768399 + outer loop + vertex 0.832801 1.69612 2.58377 + vertex 0.832002 1.69086 2.5838 + vertex 0.835383 1.69362 2.58622 + endloop + endfacet + facet normal -0.648068 0.103875 0.754465 + outer loop + vertex 0.827029 1.69587 2.57889 + vertex 0.827188 1.69127 2.57966 + vertex 0.829786 1.6939 2.58153 + endloop + endfacet + facet normal -0.655445 0.102579 0.748244 + outer loop + vertex 0.824698 1.69195 2.57739 + vertex 0.827188 1.69127 2.57966 + vertex 0.827029 1.69587 2.57889 + endloop + endfacet + facet normal -0.656112 0.103234 0.747569 + outer loop + vertex 0.824358 1.69516 2.57665 + vertex 0.824698 1.69195 2.57739 + vertex 0.827029 1.69587 2.57889 + endloop + endfacet + facet normal -0.656216 0.104443 0.74731 + outer loop + vertex 0.824358 1.69516 2.57665 + vertex 0.827029 1.69587 2.57889 + vertex 0.824839 1.69872 2.57657 + endloop + endfacet + facet normal -0.639917 0.103229 0.761479 + outer loop + vertex 0.832801 1.69612 2.58377 + vertex 0.833325 1.70113 2.58353 + vertex 0.830265 1.69859 2.5813 + endloop + endfacet + facet normal -0.630794 0.105301 0.768773 + outer loop + vertex 0.833849 1.70628 2.58325 + vertex 0.833325 1.70113 2.58353 + vertex 0.83644 1.70398 2.58569 + endloop + endfacet + facet normal -0.64721 0.108385 0.754568 + outer loop + vertex 0.831321 1.70871 2.58078 + vertex 0.828262 1.70597 2.57855 + vertex 0.830775 1.70354 2.58105 + endloop + endfacet + facet normal -0.648323 0.106521 0.753877 + outer loop + vertex 0.828262 1.70597 2.57855 + vertex 0.827767 1.70101 2.57882 + vertex 0.830775 1.70354 2.58105 + endloop + endfacet + facet normal -0.65617 0.104505 0.747342 + outer loop + vertex 0.827029 1.69587 2.57889 + vertex 0.827767 1.70101 2.57882 + vertex 0.824839 1.69872 2.57657 + endloop + endfacet + facet normal -0.667142 0.105706 0.737392 + outer loop + vertex 0.824839 1.69872 2.57657 + vertex 0.822262 1.69603 2.57462 + vertex 0.824358 1.69516 2.57665 + endloop + endfacet + facet normal -0.667389 0.104874 0.737288 + outer loop + vertex 0.82269 1.69285 2.57546 + vertex 0.824358 1.69516 2.57665 + vertex 0.822262 1.69603 2.57462 + endloop + endfacet + facet normal -0.664186 0.100805 0.74074 + outer loop + vertex 0.824358 1.69516 2.57665 + vertex 0.82269 1.69285 2.57546 + vertex 0.824698 1.69195 2.57739 + endloop + endfacet + facet normal -0.655722 0.101314 0.748174 + outer loop + vertex 0.824785 1.68708 2.57812 + vertex 0.827188 1.69127 2.57966 + vertex 0.824698 1.69195 2.57739 + endloop + endfacet + facet normal -0.673256 0.103514 0.732128 + outer loop + vertex 0.819908 1.69187 2.57304 + vertex 0.819088 1.68627 2.57308 + vertex 0.822078 1.68898 2.57544 + endloop + endfacet + facet normal -0.679775 0.102505 0.726222 + outer loop + vertex 0.818475 1.68094 2.57325 + vertex 0.819088 1.68627 2.57308 + vertex 0.816138 1.68352 2.5707 + endloop + endfacet + facet normal -0.663056 0.100825 0.741749 + outer loop + vertex 0.823906 1.68128 2.57813 + vertex 0.824785 1.68708 2.57812 + vertex 0.821459 1.68379 2.5756 + endloop + endfacet + facet normal -0.655048 0.0978633 0.749223 + outer loop + vertex 0.823906 1.68128 2.57813 + vertex 0.823383 1.6759 2.57837 + vertex 0.826423 1.67877 2.58065 + endloop + endfacet + facet normal -0.6728 0.0983044 0.733264 + outer loop + vertex 0.818475 1.68094 2.57325 + vertex 0.818111 1.67575 2.57362 + vertex 0.820898 1.6784 2.57582 + endloop + endfacet + facet normal -0.663798 0.0950928 0.741842 + outer loop + vertex 0.822925 1.67079 2.57862 + vertex 0.823383 1.6759 2.57837 + vertex 0.820539 1.67332 2.57616 + endloop + endfacet + facet normal -0.658333 0.0909252 0.747215 + outer loop + vertex 0.822925 1.67079 2.57862 + vertex 0.822101 1.66555 2.57853 + vertex 0.825437 1.66831 2.58113 + endloop + endfacet + facet normal -0.658746 0.0925596 0.74665 + outer loop + vertex 0.822101 1.66555 2.57853 + vertex 0.822442 1.66076 2.57942 + vertex 0.825034 1.6635 2.58137 + endloop + endfacet + facet normal -0.658522 0.0898101 0.747183 + outer loop + vertex 0.822894 1.65758 2.5802 + vertex 0.824558 1.65986 2.5814 + vertex 0.822442 1.66076 2.57942 + endloop + endfacet + facet normal -0.654063 0.0841655 0.751743 + outer loop + vertex 0.824558 1.65986 2.5814 + vertex 0.822894 1.65758 2.5802 + vertex 0.824886 1.65671 2.58203 + endloop + endfacet + facet normal -0.646428 0.0805996 0.758706 + outer loop + vertex 0.824754 1.65232 2.58239 + vertex 0.827417 1.65567 2.5843 + vertex 0.824886 1.65671 2.58203 + endloop + endfacet + facet normal -0.663363 0.0843523 0.743528 + outer loop + vertex 0.820117 1.65668 2.57782 + vertex 0.819434 1.65126 2.57783 + vertex 0.822315 1.65391 2.5801 + endloop + endfacet + facet normal -0.668625 0.0802254 0.739259 + outer loop + vertex 0.818967 1.64613 2.57796 + vertex 0.819434 1.65126 2.57783 + vertex 0.816542 1.64858 2.5755 + endloop + endfacet + facet normal -0.652738 0.0770649 0.753654 + outer loop + vertex 0.824846 1.64712 2.583 + vertex 0.824754 1.65232 2.58239 + vertex 0.821913 1.64903 2.58026 + endloop + endfacet + facet normal -0.645205 0.0751048 0.760309 + outer loop + vertex 0.824846 1.64712 2.583 + vertex 0.824106 1.64138 2.58294 + vertex 0.82706 1.64417 2.58517 + endloop + endfacet + facet normal -0.660772 0.0763616 0.746692 + outer loop + vertex 0.818967 1.64613 2.57796 + vertex 0.818616 1.64102 2.57817 + vertex 0.821525 1.64378 2.58047 + endloop + endfacet + facet normal -0.670755 0.074261 0.737952 + outer loop + vertex 0.818358 1.63595 2.57845 + vertex 0.818616 1.64102 2.57817 + vertex 0.81586 1.6385 2.57592 + endloop + endfacet + facet normal -0.651866 0.0746448 0.754651 + outer loop + vertex 0.823739 1.63611 2.58314 + vertex 0.824106 1.64138 2.58294 + vertex 0.821149 1.63853 2.58067 + endloop + endfacet + facet normal -0.643566 0.0730428 0.761897 + outer loop + vertex 0.823739 1.63611 2.58314 + vertex 0.823478 1.631 2.58341 + vertex 0.826418 1.63379 2.58563 + endloop + endfacet + facet normal -0.662279 0.0720209 0.745787 + outer loop + vertex 0.818358 1.63595 2.57845 + vertex 0.81814 1.63094 2.57874 + vertex 0.820898 1.63344 2.58095 + endloop + endfacet + facet normal -0.672717 0.0701871 0.736564 + outer loop + vertex 0.817809 1.62599 2.57891 + vertex 0.81814 1.63094 2.57874 + vertex 0.815425 1.62855 2.57649 + endloop + endfacet + facet normal -0.65183 0.0697453 0.755151 + outer loop + vertex 0.823227 1.62601 2.58366 + vertex 0.823478 1.631 2.58341 + vertex 0.820666 1.62846 2.58122 + endloop + endfacet + facet normal -0.643321 0.0653581 0.762801 + outer loop + vertex 0.823227 1.62601 2.58366 + vertex 0.822901 1.62105 2.58381 + vertex 0.825817 1.62356 2.58605 + endloop + endfacet + facet normal -0.663963 0.065532 0.744889 + outer loop + vertex 0.817809 1.62599 2.57891 + vertex 0.817034 1.62075 2.57868 + vertex 0.820325 1.62349 2.58137 + endloop + endfacet + facet normal -0.674667 0.0641322 0.735331 + outer loop + vertex 0.814546 1.61673 2.57675 + vertex 0.817428 1.61591 2.57946 + vertex 0.817034 1.62075 2.57868 + endloop + endfacet + facet normal -0.650178 0.0608558 0.757341 + outer loop + vertex 0.822269 1.6157 2.58369 + vertex 0.822901 1.62105 2.58381 + vertex 0.819984 1.61868 2.58149 + endloop + endfacet + facet normal -0.647067 0.0546994 0.760469 + outer loop + vertex 0.819927 1.6118 2.58198 + vertex 0.822457 1.61065 2.58422 + vertex 0.822269 1.6157 2.58369 + endloop + endfacet + facet normal -0.662995 0.0614595 0.746097 + outer loop + vertex 0.817926 1.61271 2.58017 + vertex 0.81955 1.615 2.58142 + vertex 0.817428 1.61591 2.57946 + endloop + endfacet + facet normal -0.672155 0.0582777 0.738114 + outer loop + vertex 0.817926 1.61271 2.58017 + vertex 0.817428 1.61591 2.57946 + vertex 0.815185 1.6118 2.57774 + endloop + endfacet + facet normal -0.657769 0.0504192 0.75153 + outer loop + vertex 0.819898 1.60735 2.58225 + vertex 0.819927 1.6118 2.58198 + vertex 0.817432 1.609 2.57999 + endloop + endfacet + facet normal -0.649191 0.0503586 0.758957 + outer loop + vertex 0.820257 1.60202 2.58292 + vertex 0.822346 1.60636 2.58441 + vertex 0.819898 1.60735 2.58225 + endloop + endfacet + facet normal -0.657774 0.0520894 0.751412 + outer loop + vertex 0.819474 1.59629 2.58263 + vertex 0.820257 1.60202 2.58292 + vertex 0.816917 1.5988 2.58021 + endloop + endfacet + facet normal -0.65095 0.0487345 0.757555 + outer loop + vertex 0.819474 1.59629 2.58263 + vertex 0.819221 1.5912 2.58274 + vertex 0.82198 1.59411 2.58492 + endloop + endfacet + facet normal -0.659049 0.0452623 0.750736 + outer loop + vertex 0.819083 1.58618 2.58292 + vertex 0.819221 1.5912 2.58274 + vertex 0.816459 1.58853 2.58047 + endloop + endfacet + facet normal -0.650584 0.0411292 0.758319 + outer loop + vertex 0.819083 1.58618 2.58292 + vertex 0.818947 1.58113 2.58308 + vertex 0.82183 1.58408 2.58539 + endloop + endfacet + facet normal -0.658538 0.0362254 0.751675 + outer loop + vertex 0.818796 1.57607 2.58319 + vertex 0.818947 1.58113 2.58308 + vertex 0.816182 1.57859 2.58078 + endloop + endfacet + facet normal -0.651329 0.0323619 0.758105 + outer loop + vertex 0.818796 1.57607 2.58319 + vertex 0.818659 1.57105 2.58328 + vertex 0.821444 1.5736 2.58557 + endloop + endfacet + facet normal -0.658596 0.0300107 0.751898 + outer loop + vertex 0.818551 1.56609 2.58339 + vertex 0.818659 1.57105 2.58328 + vertex 0.815944 1.56867 2.581 + endloop + endfacet + facet normal -0.650807 0.0299716 0.758651 + outer loop + vertex 0.818551 1.56609 2.58339 + vertex 0.818447 1.56115 2.58349 + vertex 0.821192 1.56358 2.58575 + endloop + endfacet + facet normal -0.658754 0.0297042 0.751771 + outer loop + vertex 0.818337 1.5562 2.58359 + vertex 0.818447 1.56115 2.58349 + vertex 0.815735 1.55875 2.58121 + endloop + endfacet + facet normal -0.650441 0.0265673 0.759092 + outer loop + vertex 0.818337 1.5562 2.58359 + vertex 0.818237 1.55124 2.58368 + vertex 0.820982 1.55365 2.58595 + endloop + endfacet + facet normal -0.657639 0.0220679 0.75301 + outer loop + vertex 0.818157 1.54627 2.58376 + vertex 0.818237 1.55124 2.58368 + vertex 0.815533 1.54879 2.58139 + endloop + endfacet + facet normal -0.649199 0.0174479 0.760418 + outer loop + vertex 0.818157 1.54627 2.58376 + vertex 0.818095 1.5413 2.58382 + vertex 0.820831 1.54371 2.5861 + endloop + endfacet + facet normal -0.655429 0.0140144 0.755127 + outer loop + vertex 0.818047 1.53631 2.58387 + vertex 0.818095 1.5413 2.58382 + vertex 0.815395 1.5388 2.58152 + endloop + endfacet + facet normal -0.647064 0.0124132 0.762335 + outer loop + vertex 0.818047 1.53631 2.58387 + vertex 0.818002 1.53132 2.58391 + vertex 0.820743 1.53376 2.5862 + endloop + endfacet + facet normal -0.653993 0.0105681 0.756427 + outer loop + vertex 0.817962 1.52633 2.58395 + vertex 0.818002 1.53132 2.58391 + vertex 0.815306 1.52883 2.58162 + endloop + endfacet + facet normal -0.646869 0.00854499 0.762553 + outer loop + vertex 0.817962 1.52633 2.58395 + vertex 0.817929 1.52134 2.58397 + vertex 0.820661 1.52378 2.58626 + endloop + endfacet + facet normal -0.647058 0.00465283 0.762426 + outer loop + vertex 0.817929 1.52134 2.58397 + vertex 0.81791 1.51634 2.58399 + vertex 0.820634 1.51878 2.58629 + endloop + endfacet + facet normal -0.655507 0.0006781 0.755189 + outer loop + vertex 0.817909 1.51133 2.58399 + vertex 0.81791 1.51634 2.58399 + vertex 0.815242 1.51386 2.58168 + endloop + endfacet + facet normal -0.64763 -0.00290621 0.76195 + outer loop + vertex 0.817909 1.51133 2.58399 + vertex 0.817924 1.50632 2.58399 + vertex 0.820633 1.50878 2.5863 + endloop + endfacet + facet normal -0.655753 -0.00576987 0.754953 + outer loop + vertex 0.817952 1.50133 2.58397 + vertex 0.817924 1.50632 2.58399 + vertex 0.815261 1.50383 2.58165 + endloop + endfacet + facet normal -0.646439 -0.00791034 0.762925 + outer loop + vertex 0.817952 1.50133 2.58397 + vertex 0.817988 1.49635 2.58395 + vertex 0.820693 1.49881 2.58627 + endloop + endfacet + facet normal -0.646323 -0.0104277 0.762993 + outer loop + vertex 0.817988 1.49635 2.58395 + vertex 0.81803 1.49138 2.58392 + vertex 0.820733 1.49383 2.58624 + endloop + endfacet + facet normal -0.655232 -0.013359 0.75531 + outer loop + vertex 0.818082 1.48639 2.58388 + vertex 0.81803 1.49138 2.58392 + vertex 0.815381 1.48887 2.58158 + endloop + endfacet + facet normal -0.647315 -0.017104 0.762031 + outer loop + vertex 0.818082 1.48639 2.58388 + vertex 0.81815 1.48139 2.58382 + vertex 0.820837 1.48383 2.58616 + endloop + endfacet + facet normal -0.656507 -0.0212233 0.754021 + outer loop + vertex 0.818233 1.47639 2.58375 + vertex 0.81815 1.48139 2.58382 + vertex 0.815518 1.4789 2.58146 + endloop + endfacet + facet normal -0.647318 -0.0258085 0.761783 + outer loop + vertex 0.818233 1.47639 2.58375 + vertex 0.818342 1.47139 2.58368 + vertex 0.821011 1.47385 2.58603 + endloop + endfacet + facet normal -0.656135 -0.0298315 0.754053 + outer loop + vertex 0.81847 1.46637 2.58359 + vertex 0.818342 1.47139 2.58368 + vertex 0.815725 1.46889 2.5813 + endloop + endfacet + facet normal -0.647474 -0.0333152 0.761359 + outer loop + vertex 0.81847 1.46637 2.58359 + vertex 0.818608 1.46135 2.58349 + vertex 0.821271 1.46385 2.58586 + endloop + endfacet + facet normal -0.656878 -0.0355075 0.75316 + outer loop + vertex 0.818747 1.45633 2.58337 + vertex 0.818608 1.46135 2.58349 + vertex 0.815992 1.45888 2.58109 + endloop + endfacet + facet normal -0.648771 -0.0363884 0.760114 + outer loop + vertex 0.818747 1.45633 2.58337 + vertex 0.818888 1.45132 2.58325 + vertex 0.821537 1.45384 2.58563 + endloop + endfacet + facet normal -0.666684 -0.0361926 0.744461 + outer loop + vertex 0.81342 1.45641 2.57866 + vertex 0.813558 1.45141 2.57855 + vertex 0.816131 1.45387 2.58097 + endloop + endfacet + facet normal -0.656777 -0.0368639 0.753183 + outer loop + vertex 0.819039 1.44632 2.58314 + vertex 0.818888 1.45132 2.58325 + vertex 0.816274 1.44887 2.58085 + endloop + endfacet + facet normal -0.650066 -0.0388544 0.758883 + outer loop + vertex 0.819039 1.44632 2.58314 + vertex 0.819178 1.44138 2.583 + vertex 0.821863 1.44378 2.58543 + endloop + endfacet + facet normal -0.65685 -0.0419131 0.752855 + outer loop + vertex 0.819322 1.43652 2.58286 + vertex 0.819178 1.44138 2.583 + vertex 0.81658 1.43893 2.5806 + endloop + endfacet + facet normal -0.651565 -0.0451741 0.757247 + outer loop + vertex 0.819322 1.43652 2.58286 + vertex 0.819563 1.43159 2.58277 + vertex 0.821998 1.43432 2.58503 + endloop + endfacet + facet normal -0.657416 -0.0473894 0.752036 + outer loop + vertex 0.820016 1.4261 2.58282 + vertex 0.819563 1.43159 2.58277 + vertex 0.816949 1.42893 2.58032 + endloop + endfacet + facet normal -0.651953 -0.0480228 0.756737 + outer loop + vertex 0.822134 1.42133 2.58435 + vertex 0.820016 1.4261 2.58282 + vertex 0.819315 1.42158 2.58193 + endloop + endfacet + facet normal -0.659259 -0.0511798 0.750172 + outer loop + vertex 0.820227 1.41711 2.58243 + vertex 0.819315 1.42158 2.58193 + vertex 0.817338 1.41928 2.58004 + endloop + endfacet + facet normal -0.659068 -0.0507037 0.750373 + outer loop + vertex 0.817937 1.4155 2.58031 + vertex 0.820227 1.41711 2.58243 + vertex 0.817338 1.41928 2.58004 + endloop + endfacet + facet normal -0.658646 -0.0516988 0.750674 + outer loop + vertex 0.819597 1.41316 2.5816 + vertex 0.820227 1.41711 2.58243 + vertex 0.817937 1.4155 2.58031 + endloop + endfacet + facet normal -0.652852 -0.0536487 0.755583 + outer loop + vertex 0.819597 1.41316 2.5816 + vertex 0.822389 1.41224 2.58395 + vertex 0.820227 1.41711 2.58243 + endloop + endfacet + facet normal -0.64804 -0.0568893 0.759479 + outer loop + vertex 0.822389 1.41224 2.58395 + vertex 0.822923 1.40659 2.58398 + vertex 0.825548 1.40904 2.58641 + endloop + endfacet + facet normal -0.664288 -0.0623449 0.744872 + outer loop + vertex 0.817464 1.41198 2.57962 + vertex 0.817179 1.40709 2.57895 + vertex 0.820002 1.40914 2.58164 + endloop + endfacet + facet normal -0.670773 -0.0611905 0.739134 + outer loop + vertex 0.817179 1.40709 2.57895 + vertex 0.817464 1.41198 2.57962 + vertex 0.814931 1.41119 2.57725 + endloop + endfacet + facet normal -0.671694 -0.0620747 0.738224 + outer loop + vertex 0.814507 1.4079 2.57659 + vertex 0.817179 1.40709 2.57895 + vertex 0.814931 1.41119 2.57725 + endloop + endfacet + facet normal -0.671979 -0.0643432 0.73777 + outer loop + vertex 0.814985 1.40412 2.5767 + vertex 0.817179 1.40709 2.57895 + vertex 0.814507 1.4079 2.57659 + endloop + endfacet + facet normal -0.656209 -0.0618421 0.752041 + outer loop + vertex 0.823268 1.40143 2.58386 + vertex 0.822923 1.40659 2.58398 + vertex 0.820359 1.40408 2.58154 + endloop + endfacet + facet normal -0.648641 -0.0645566 0.758352 + outer loop + vertex 0.823268 1.40143 2.58386 + vertex 0.823527 1.39642 2.58365 + vertex 0.826106 1.3989 2.58607 + endloop + endfacet + facet normal -0.655836 -0.0663907 0.751979 + outer loop + vertex 0.823742 1.39148 2.58341 + vertex 0.823527 1.39642 2.58365 + vertex 0.820984 1.39393 2.58122 + endloop + endfacet + facet normal -0.648188 -0.0686114 0.758383 + outer loop + vertex 0.823742 1.39148 2.58341 + vertex 0.823996 1.38655 2.58318 + vertex 0.826565 1.38908 2.5856 + endloop + endfacet + facet normal -0.654408 -0.0726173 0.752647 + outer loop + vertex 0.824341 1.38155 2.583 + vertex 0.823996 1.38655 2.58318 + vertex 0.821439 1.38405 2.58071 + endloop + endfacet + facet normal -0.648009 -0.0766735 0.757763 + outer loop + vertex 0.824341 1.38155 2.583 + vertex 0.824896 1.37614 2.58292 + vertex 0.827294 1.3792 2.58528 + endloop + endfacet + facet normal -0.654509 -0.0772823 0.752094 + outer loop + vertex 0.824306 1.37181 2.58196 + vertex 0.824896 1.37614 2.58292 + vertex 0.821955 1.3742 2.58016 + endloop + endfacet + facet normal -0.649147 -0.0820456 0.756225 + outer loop + vertex 0.824788 1.36347 2.58149 + vertex 0.827636 1.36244 2.58382 + vertex 0.825336 1.36739 2.58238 + endloop + endfacet + facet normal -0.657017 -0.0862873 0.748921 + outer loop + vertex 0.824788 1.36347 2.58149 + vertex 0.822661 1.36233 2.57949 + vertex 0.825287 1.35937 2.58145 + endloop + endfacet + facet normal -0.664448 -0.0821636 0.742804 + outer loop + vertex 0.823056 1.36586 2.58024 + vertex 0.822368 1.36959 2.58003 + vertex 0.820299 1.3664 2.57783 + endloop + endfacet + facet normal -0.658939 -0.0893521 0.746871 + outer loop + vertex 0.822661 1.36233 2.57949 + vertex 0.822469 1.35734 2.57872 + vertex 0.825287 1.35937 2.58145 + endloop + endfacet + facet normal -0.660228 -0.0906088 0.74558 + outer loop + vertex 0.822469 1.35734 2.57872 + vertex 0.82328 1.35168 2.57875 + vertex 0.825745 1.35421 2.58124 + endloop + endfacet + facet normal -0.660116 -0.0937535 0.74529 + outer loop + vertex 0.82328 1.35168 2.57875 + vertex 0.823715 1.34653 2.57849 + vertex 0.826192 1.34903 2.581 + endloop + endfacet + facet normal -0.666242 -0.0974793 0.739337 + outer loop + vertex 0.824054 1.34161 2.57815 + vertex 0.823715 1.34653 2.57849 + vertex 0.821263 1.34403 2.57595 + endloop + endfacet + facet normal -0.675635 -0.0935034 0.731283 + outer loop + vertex 0.818019 1.35169 2.57395 + vertex 0.818535 1.34655 2.57377 + vertex 0.820912 1.34907 2.57629 + endloop + endfacet + facet normal -0.674048 -0.100864 0.731769 + outer loop + vertex 0.821263 1.34403 2.57595 + vertex 0.81883 1.34153 2.57336 + vertex 0.821641 1.33912 2.57562 + endloop + endfacet + facet normal -0.681751 -0.104172 0.72413 + outer loop + vertex 0.819298 1.33653 2.57309 + vertex 0.81883 1.34153 2.57336 + vertex 0.816412 1.33906 2.57073 + endloop + endfacet + facet normal -0.692297 -0.0981629 0.714905 + outer loop + vertex 0.813476 1.34665 2.56895 + vertex 0.813735 1.34159 2.56851 + vertex 0.81614 1.34406 2.57118 + endloop + endfacet + facet normal -0.689911 -0.105433 0.716175 + outer loop + vertex 0.816412 1.33906 2.57073 + vertex 0.814036 1.33661 2.56808 + vertex 0.8169 1.3341 2.57047 + endloop + endfacet + facet normal -0.689581 -0.104643 0.716609 + outer loop + vertex 0.814036 1.33661 2.56808 + vertex 0.814592 1.33183 2.56792 + vertex 0.8169 1.3341 2.57047 + endloop + endfacet + facet normal -0.697895 -0.106605 0.708222 + outer loop + vertex 0.815446 1.32731 2.56808 + vertex 0.814592 1.33183 2.56792 + vertex 0.812534 1.32938 2.56552 + endloop + endfacet + facet normal -0.689423 -0.1075 0.716337 + outer loop + vertex 0.816827 1.32232 2.56866 + vertex 0.817861 1.32576 2.57017 + vertex 0.815446 1.32731 2.56808 + endloop + endfacet + facet normal -0.702165 -0.109035 0.703616 + outer loop + vertex 0.811978 1.32185 2.56381 + vertex 0.814419 1.32212 2.56629 + vertex 0.813631 1.32499 2.56595 + endloop + endfacet + facet normal -0.701448 -0.108981 0.704339 + outer loop + vertex 0.812978 1.31675 2.56402 + vertex 0.811978 1.32185 2.56381 + vertex 0.810345 1.31882 2.56171 + endloop + endfacet + facet normal -0.692941 -0.11039 0.712493 + outer loop + vertex 0.817988 1.31674 2.56893 + vertex 0.816827 1.32232 2.56866 + vertex 0.815066 1.31905 2.56644 + endloop + endfacet + facet normal -0.685277 -0.111912 0.719632 + outer loop + vertex 0.817988 1.31674 2.56893 + vertex 0.818561 1.31161 2.56867 + vertex 0.820911 1.3141 2.5713 + endloop + endfacet + facet normal -0.698258 -0.111506 0.707108 + outer loop + vertex 0.812978 1.31675 2.56402 + vertex 0.813542 1.31174 2.56378 + vertex 0.815788 1.3142 2.56639 + endloop + endfacet + facet normal -0.699927 -0.114637 0.704954 + outer loop + vertex 0.81392 1.30659 2.56332 + vertex 0.813542 1.31174 2.56378 + vertex 0.811297 1.30917 2.56114 + endloop + endfacet + facet normal -0.692187 -0.11494 0.712507 + outer loop + vertex 0.818953 1.30664 2.56825 + vertex 0.818561 1.31161 2.56867 + vertex 0.81623 1.30915 2.56601 + endloop + endfacet + facet normal -0.685167 -0.117664 0.718819 + outer loop + vertex 0.818953 1.30664 2.56825 + vertex 0.819557 1.30185 2.56804 + vertex 0.821765 1.30426 2.57054 + endloop + endfacet + facet normal -0.696542 -0.116428 0.708007 + outer loop + vertex 0.81392 1.30659 2.56332 + vertex 0.814374 1.30138 2.56291 + vertex 0.816664 1.30414 2.56562 + endloop + endfacet + facet normal -0.689431 -0.118846 0.714535 + outer loop + vertex 0.820598 1.29722 2.56828 + vertex 0.819557 1.30185 2.56804 + vertex 0.817446 1.29927 2.56558 + endloop + endfacet + facet normal -0.676292 -0.109485 0.728452 + outer loop + vertex 0.821947 1.29218 2.56877 + vertex 0.823713 1.29522 2.57087 + vertex 0.820598 1.29722 2.56828 + endloop + endfacet + facet normal -0.688506 -0.105605 0.717501 + outer loop + vertex 0.817713 1.29197 2.56472 + vertex 0.819619 1.2922 2.56659 + vertex 0.818734 1.29489 2.56613 + endloop + endfacet + facet normal -0.694025 -0.10177 0.712721 + outer loop + vertex 0.817448 1.28744 2.56382 + vertex 0.817713 1.29197 2.56472 + vertex 0.815182 1.29129 2.56216 + endloop + endfacet + facet normal -0.675134 -0.126614 0.726749 + outer loop + vertex 0.824163 1.27665 2.56843 + vertex 0.823507 1.28173 2.5687 + vertex 0.821123 1.27929 2.56606 + endloop + endfacet + facet normal -0.649693 -0.119723 0.75071 + outer loop + vertex 0.829529 1.27692 2.57326 + vertex 0.82891 1.28173 2.57349 + vertex 0.826503 1.27922 2.571 + endloop + endfacet + facet normal -0.667332 -0.108036 0.736883 + outer loop + vertex 0.822905 1.28682 2.56891 + vertex 0.823507 1.28173 2.5687 + vertex 0.825906 1.28419 2.57124 + endloop + endfacet + facet normal -0.680038 -0.103771 0.725796 + outer loop + vertex 0.822905 1.28682 2.56891 + vertex 0.821947 1.29218 2.56877 + vertex 0.820058 1.28927 2.56659 + endloop + endfacet + facet normal -0.657828 -0.112409 0.744733 + outer loop + vertex 0.828234 1.28681 2.57364 + vertex 0.827033 1.29245 2.57343 + vertex 0.825175 1.2891 2.57128 + endloop + endfacet + facet normal -0.672222 -0.113961 0.731526 + outer loop + vertex 0.821947 1.29218 2.56877 + vertex 0.824534 1.29225 2.57116 + vertex 0.823713 1.29522 2.57087 + endloop + endfacet + facet normal -0.671612 -0.118115 0.731428 + outer loop + vertex 0.823713 1.29522 2.57087 + vertex 0.82558 1.2975 2.57295 + vertex 0.822562 1.29966 2.57053 + endloop + endfacet + facet normal -0.673232 -0.122959 0.729136 + outer loop + vertex 0.82558 1.2975 2.57295 + vertex 0.824676 1.30199 2.57287 + vertex 0.822562 1.29966 2.57053 + endloop + endfacet + facet normal -0.666399 -0.118676 0.73609 + outer loop + vertex 0.824095 1.30666 2.5731 + vertex 0.824676 1.30199 2.57287 + vertex 0.827022 1.3043 2.57537 + endloop + endfacet + facet normal -0.653314 -0.120801 0.747387 + outer loop + vertex 0.830311 1.3016 2.57781 + vertex 0.829448 1.30681 2.5779 + vertex 0.827022 1.3043 2.57537 + endloop + endfacet + facet normal -0.640929 -0.121458 0.75793 + outer loop + vertex 0.83313 1.30107 2.58011 + vertex 0.832343 1.30477 2.58004 + vertex 0.830311 1.3016 2.57781 + endloop + endfacet + facet normal -0.622742 -0.121269 0.772972 + outer loop + vertex 0.834988 1.2987 2.58123 + vertex 0.835438 1.30258 2.58221 + vertex 0.83313 1.30107 2.58011 + endloop + endfacet + facet normal -0.614964 -0.12363 0.778804 + outer loop + vertex 0.834988 1.2987 2.58123 + vertex 0.837991 1.29766 2.58344 + vertex 0.835438 1.30258 2.58221 + endloop + endfacet + facet normal -0.612403 -0.125952 0.780448 + outer loop + vertex 0.837991 1.29766 2.58344 + vertex 0.838948 1.29192 2.58327 + vertex 0.841572 1.29442 2.58573 + endloop + endfacet + facet normal -0.627869 -0.1312 0.767181 + outer loop + vertex 0.832846 1.29757 2.57928 + vertex 0.832811 1.29258 2.5784 + vertex 0.835672 1.29461 2.58109 + endloop + endfacet + facet normal -0.622846 -0.119692 0.773134 + outer loop + vertex 0.839814 1.28625 2.58309 + vertex 0.838948 1.29192 2.58327 + vertex 0.836352 1.28941 2.58078 + endloop + endfacet + facet normal -0.612914 -0.118431 0.781223 + outer loop + vertex 0.838948 1.29192 2.58327 + vertex 0.839814 1.28625 2.58309 + vertex 0.842205 1.28934 2.58543 + endloop + endfacet + facet normal -0.61285 -0.115526 0.781709 + outer loop + vertex 0.844981 1.28656 2.58719 + vertex 0.84513 1.29147 2.58804 + vertex 0.842205 1.28934 2.58543 + endloop + endfacet + facet normal -0.609288 -0.107043 0.785691 + outer loop + vertex 0.847511 1.28248 2.5886 + vertex 0.847694 1.28746 2.58942 + vertex 0.844981 1.28656 2.58719 + endloop + endfacet + facet normal -0.613253 -0.104029 0.783006 + outer loop + vertex 0.842191 1.2815 2.58433 + vertex 0.844554 1.28307 2.58638 + vertex 0.842758 1.28538 2.58528 + endloop + endfacet + facet normal -0.620194 -0.103033 0.777653 + outer loop + vertex 0.843283 1.27707 2.58461 + vertex 0.842191 1.2815 2.58433 + vertex 0.840378 1.27748 2.58235 + endloop + endfacet + facet normal -0.620447 -0.118098 0.775305 + outer loop + vertex 0.842844 1.27265 2.58358 + vertex 0.843283 1.27707 2.58461 + vertex 0.840378 1.27748 2.58235 + endloop + endfacet + facet normal -0.618738 -0.116826 0.776862 + outer loop + vertex 0.839869 1.27362 2.58136 + vertex 0.842844 1.27265 2.58358 + vertex 0.840378 1.27748 2.58235 + endloop + endfacet + facet normal -0.623153 -0.115396 0.77354 + outer loop + vertex 0.839869 1.27362 2.58136 + vertex 0.840378 1.27748 2.58235 + vertex 0.838074 1.27595 2.58026 + endloop + endfacet + facet normal -0.634813 -0.13001 0.76165 + outer loop + vertex 0.837739 1.27249 2.57939 + vertex 0.839869 1.27362 2.58136 + vertex 0.838074 1.27595 2.58026 + endloop + endfacet + facet normal -0.635773 -0.129728 0.760896 + outer loop + vertex 0.838074 1.27595 2.58026 + vertex 0.835265 1.2765 2.57801 + vertex 0.837739 1.27249 2.57939 + endloop + endfacet + facet normal -0.634916 -0.109849 0.764732 + outer loop + vertex 0.838074 1.27595 2.58026 + vertex 0.837354 1.27965 2.5802 + vertex 0.835265 1.2765 2.57801 + endloop + endfacet + facet normal -0.629452 -0.143627 0.76365 + outer loop + vertex 0.839869 1.27362 2.58136 + vertex 0.837739 1.27249 2.57939 + vertex 0.840553 1.26961 2.58117 + endloop + endfacet + facet normal -0.636256 -0.155158 0.755715 + outer loop + vertex 0.837739 1.27249 2.57939 + vertex 0.837753 1.26758 2.5784 + vertex 0.840553 1.26961 2.58117 + endloop + endfacet + facet normal -0.633867 -0.155541 0.757641 + outer loop + vertex 0.837753 1.26758 2.5784 + vertex 0.837739 1.27249 2.57939 + vertex 0.835124 1.27177 2.57706 + endloop + endfacet + facet normal -0.637145 -0.158694 0.75423 + outer loop + vertex 0.834704 1.26844 2.576 + vertex 0.837753 1.26758 2.5784 + vertex 0.835124 1.27177 2.57706 + endloop + endfacet + facet normal -0.636699 -0.158859 0.754572 + outer loop + vertex 0.834704 1.26844 2.576 + vertex 0.835124 1.27177 2.57706 + vertex 0.832925 1.27095 2.57503 + endloop + endfacet + facet normal -0.644976 -0.168241 0.745453 + outer loop + vertex 0.831991 1.26747 2.57344 + vertex 0.834704 1.26844 2.576 + vertex 0.832925 1.27095 2.57503 + endloop + endfacet + facet normal -0.64384 -0.171839 0.745615 + outer loop + vertex 0.834704 1.26844 2.576 + vertex 0.831991 1.26747 2.57344 + vertex 0.835647 1.26446 2.5759 + endloop + endfacet + facet normal -0.643517 -0.171074 0.74607 + outer loop + vertex 0.831991 1.26747 2.57344 + vertex 0.833438 1.262 2.57343 + vertex 0.835647 1.26446 2.5759 + endloop + endfacet + facet normal -0.648626 -0.172419 0.74132 + outer loop + vertex 0.833438 1.262 2.57343 + vertex 0.831991 1.26747 2.57344 + vertex 0.830334 1.26426 2.57124 + endloop + endfacet + facet normal -0.640524 -0.146606 0.753814 + outer loop + vertex 0.832925 1.27095 2.57503 + vertex 0.835124 1.27177 2.57706 + vertex 0.832482 1.27464 2.57537 + endloop + endfacet + facet normal -0.632963 -0.134623 0.762388 + outer loop + vertex 0.835124 1.27177 2.57706 + vertex 0.835265 1.2765 2.57801 + vertex 0.832482 1.27464 2.57537 + endloop + endfacet + facet normal -0.637821 -0.124147 0.760113 + outer loop + vertex 0.832482 1.27464 2.57537 + vertex 0.835265 1.2765 2.57801 + vertex 0.831961 1.27928 2.57569 + endloop + endfacet + facet normal -0.637927 -0.170578 0.750968 + outer loop + vertex 0.835647 1.26446 2.5759 + vertex 0.837753 1.26758 2.5784 + vertex 0.834704 1.26844 2.576 + endloop + endfacet + facet normal -0.640739 -0.167347 0.749299 + outer loop + vertex 0.839037 1.26197 2.57824 + vertex 0.837753 1.26758 2.5784 + vertex 0.835647 1.26446 2.5759 + endloop + endfacet + facet normal -0.636661 -0.166515 0.752951 + outer loop + vertex 0.837753 1.26758 2.5784 + vertex 0.839037 1.26197 2.57824 + vertex 0.841418 1.26449 2.58081 + endloop + endfacet + facet normal -0.633757 -0.16008 0.756787 + outer loop + vertex 0.840553 1.26961 2.58117 + vertex 0.837753 1.26758 2.5784 + vertex 0.841418 1.26449 2.58081 + endloop + endfacet + facet normal -0.629736 -0.159641 0.760229 + outer loop + vertex 0.841418 1.26449 2.58081 + vertex 0.843872 1.26698 2.58337 + vertex 0.840553 1.26961 2.58117 + endloop + endfacet + facet normal -0.639544 -0.133362 0.757099 + outer loop + vertex 0.837739 1.27249 2.57939 + vertex 0.835265 1.2765 2.57801 + vertex 0.835124 1.27177 2.57706 + endloop + endfacet + facet normal -0.626506 -0.108088 0.771886 + outer loop + vertex 0.838074 1.27595 2.58026 + vertex 0.840378 1.27748 2.58235 + vertex 0.837354 1.27965 2.5802 + endloop + endfacet + facet normal -0.625038 -0.10436 0.773587 + outer loop + vertex 0.840378 1.27748 2.58235 + vertex 0.839306 1.28185 2.58207 + vertex 0.837354 1.27965 2.5802 + endloop + endfacet + facet normal -0.624144 -0.10562 0.774138 + outer loop + vertex 0.837354 1.27965 2.5802 + vertex 0.839306 1.28185 2.58207 + vertex 0.836854 1.2843 2.58043 + endloop + endfacet + facet normal -0.629672 -0.105987 0.769597 + outer loop + vertex 0.836854 1.2843 2.58043 + vertex 0.834428 1.2818 2.5781 + vertex 0.837354 1.27965 2.5802 + endloop + endfacet + facet normal -0.632355 -0.112733 0.766432 + outer loop + vertex 0.834428 1.2818 2.5781 + vertex 0.835265 1.2765 2.57801 + vertex 0.837354 1.27965 2.5802 + endloop + endfacet + facet normal -0.632563 -0.112763 0.766257 + outer loop + vertex 0.835265 1.2765 2.57801 + vertex 0.834428 1.2818 2.5781 + vertex 0.831961 1.27928 2.57569 + endloop + endfacet + facet normal -0.633701 -0.110994 0.765574 + outer loop + vertex 0.831961 1.27928 2.57569 + vertex 0.834428 1.2818 2.5781 + vertex 0.831356 1.28427 2.57591 + endloop + endfacet + facet normal -0.621999 -0.142655 0.769914 + outer loop + vertex 0.840553 1.26961 2.58117 + vertex 0.842844 1.27265 2.58358 + vertex 0.839869 1.27362 2.58136 + endloop + endfacet + facet normal -0.6203 -0.102949 0.777579 + outer loop + vertex 0.840378 1.27748 2.58235 + vertex 0.842191 1.2815 2.58433 + vertex 0.839306 1.28185 2.58207 + endloop + endfacet + facet normal -0.606771 -0.102149 0.788286 + outer loop + vertex 0.848377 1.27695 2.58855 + vertex 0.847511 1.28248 2.5886 + vertex 0.845288 1.27926 2.58647 + endloop + endfacet + facet normal -0.601891 -0.111678 0.790731 + outer loop + vertex 0.848377 1.27695 2.58855 + vertex 0.849022 1.27185 2.58832 + vertex 0.851552 1.27432 2.5906 + endloop + endfacet + facet normal -0.618721 -0.118571 0.776611 + outer loop + vertex 0.843283 1.27707 2.58461 + vertex 0.842844 1.27265 2.58358 + vertex 0.845842 1.27451 2.58626 + endloop + endfacet + facet normal -0.622289 -0.142302 0.769745 + outer loop + vertex 0.843872 1.26698 2.58337 + vertex 0.842844 1.27265 2.58358 + vertex 0.840553 1.26961 2.58117 + endloop + endfacet + facet normal -0.607667 -0.134014 0.782803 + outer loop + vertex 0.850023 1.26645 2.58817 + vertex 0.849022 1.27185 2.58832 + vertex 0.846417 1.26944 2.58589 + endloop + endfacet + facet normal -0.60578 -0.133706 0.784317 + outer loop + vertex 0.849022 1.27185 2.58832 + vertex 0.850023 1.26645 2.58817 + vertex 0.852136 1.26962 2.59035 + endloop + endfacet + facet normal -0.598723 -0.116502 0.792438 + outer loop + vertex 0.851552 1.27432 2.5906 + vertex 0.849022 1.27185 2.58832 + vertex 0.852136 1.26962 2.59035 + endloop + endfacet + facet normal -0.592434 -0.115976 0.797227 + outer loop + vertex 0.852136 1.26962 2.59035 + vertex 0.85415 1.27184 2.59217 + vertex 0.851552 1.27432 2.5906 + endloop + endfacet + facet normal -0.584505 -0.1266 0.801452 + outer loop + vertex 0.855374 1.26743 2.59236 + vertex 0.85415 1.27184 2.59217 + vertex 0.852136 1.26962 2.59035 + endloop + endfacet + facet normal -0.586961 -0.132842 0.798642 + outer loop + vertex 0.852986 1.26589 2.59035 + vertex 0.855374 1.26743 2.59236 + vertex 0.852136 1.26962 2.59035 + endloop + endfacet + facet normal -0.582073 -0.142828 0.800495 + outer loop + vertex 0.854937 1.26356 2.59135 + vertex 0.855374 1.26743 2.59236 + vertex 0.852986 1.26589 2.59035 + endloop + endfacet + facet normal -0.592905 -0.156448 0.789929 + outer loop + vertex 0.852709 1.26243 2.58946 + vertex 0.854937 1.26356 2.59135 + vertex 0.852986 1.26589 2.59035 + endloop + endfacet + facet normal -0.603683 -0.153614 0.782285 + outer loop + vertex 0.852986 1.26589 2.59035 + vertex 0.850023 1.26645 2.58817 + vertex 0.852709 1.26243 2.58946 + endloop + endfacet + facet normal -0.575333 -0.144765 0.805006 + outer loop + vertex 0.854937 1.26356 2.59135 + vertex 0.858124 1.26257 2.59345 + vertex 0.855374 1.26743 2.59236 + endloop + endfacet + facet normal -0.603122 -0.136546 0.785875 + outer loop + vertex 0.852986 1.26589 2.59035 + vertex 0.852136 1.26962 2.59035 + vertex 0.850023 1.26645 2.58817 + endloop + endfacet + facet normal -0.604836 -0.154741 0.781171 + outer loop + vertex 0.852709 1.26243 2.58946 + vertex 0.850023 1.26645 2.58817 + vertex 0.850037 1.26163 2.58723 + endloop + endfacet + facet normal -0.602454 -0.163099 0.781312 + outer loop + vertex 0.852726 1.25759 2.58846 + vertex 0.852709 1.26243 2.58946 + vertex 0.850037 1.26163 2.58723 + endloop + endfacet + facet normal -0.591086 -0.164767 0.789601 + outer loop + vertex 0.852709 1.26243 2.58946 + vertex 0.852726 1.25759 2.58846 + vertex 0.855706 1.25952 2.59109 + endloop + endfacet + facet normal -0.590113 -0.163167 0.79066 + outer loop + vertex 0.854937 1.26356 2.59135 + vertex 0.852709 1.26243 2.58946 + vertex 0.855706 1.25952 2.59109 + endloop + endfacet + facet normal -0.577408 -0.161369 0.80035 + outer loop + vertex 0.855706 1.25952 2.59109 + vertex 0.858124 1.26257 2.59345 + vertex 0.854937 1.26356 2.59135 + endloop + endfacet + facet normal -0.579452 -0.158977 0.799351 + outer loop + vertex 0.859444 1.25648 2.5932 + vertex 0.858124 1.26257 2.59345 + vertex 0.855706 1.25952 2.59109 + endloop + endfacet + facet normal -0.580904 -0.161898 0.797709 + outer loop + vertex 0.856368 1.25459 2.59057 + vertex 0.859444 1.25648 2.5932 + vertex 0.855706 1.25952 2.59109 + endloop + endfacet + facet normal -0.583437 -0.15667 0.796904 + outer loop + vertex 0.859157 1.25203 2.59211 + vertex 0.859444 1.25648 2.5932 + vertex 0.856368 1.25459 2.59057 + endloop + endfacet + facet normal -0.581958 -0.154102 0.798484 + outer loop + vertex 0.857196 1.24984 2.59026 + vertex 0.859157 1.25203 2.59211 + vertex 0.856368 1.25459 2.59057 + endloop + endfacet + facet normal -0.591008 -0.155228 0.79159 + outer loop + vertex 0.856368 1.25459 2.59057 + vertex 0.853895 1.25212 2.58824 + vertex 0.857196 1.24984 2.59026 + endloop + endfacet + facet normal -0.588623 -0.149156 0.794529 + outer loop + vertex 0.853895 1.25212 2.58824 + vertex 0.85509 1.24663 2.5881 + vertex 0.857196 1.24984 2.59026 + endloop + endfacet + facet normal -0.599933 -0.151382 0.785598 + outer loop + vertex 0.85509 1.24663 2.5881 + vertex 0.853895 1.25212 2.58824 + vertex 0.851378 1.24957 2.58583 + endloop + endfacet + facet normal -0.599875 -0.151466 0.785626 + outer loop + vertex 0.851378 1.24957 2.58583 + vertex 0.853895 1.25212 2.58824 + vertex 0.850537 1.25459 2.58616 + endloop + endfacet + facet normal -0.614087 -0.153107 0.774245 + outer loop + vertex 0.850537 1.25459 2.58616 + vertex 0.847697 1.25261 2.58351 + vertex 0.851378 1.24957 2.58583 + endloop + endfacet + facet normal -0.610766 -0.146069 0.778222 + outer loop + vertex 0.847697 1.25261 2.58351 + vertex 0.848853 1.24704 2.58337 + vertex 0.851378 1.24957 2.58583 + endloop + endfacet + facet normal -0.609895 -0.147364 0.77866 + outer loop + vertex 0.851378 1.24957 2.58583 + vertex 0.848853 1.24704 2.58337 + vertex 0.852203 1.24452 2.58552 + endloop + endfacet + facet normal -0.612388 -0.156458 0.774921 + outer loop + vertex 0.847676 1.25738 2.58446 + vertex 0.847697 1.25261 2.58351 + vertex 0.850537 1.25459 2.58616 + endloop + endfacet + facet normal -0.603301 -0.159737 0.781353 + outer loop + vertex 0.853895 1.25212 2.58824 + vertex 0.852726 1.25759 2.58846 + vertex 0.850537 1.25459 2.58616 + endloop + endfacet + facet normal -0.603532 -0.159473 0.781228 + outer loop + vertex 0.850537 1.25459 2.58616 + vertex 0.852726 1.25759 2.58846 + vertex 0.849781 1.25835 2.58634 + endloop + endfacet + facet normal -0.589608 -0.157239 0.792236 + outer loop + vertex 0.852726 1.25759 2.58846 + vertex 0.853895 1.25212 2.58824 + vertex 0.856368 1.25459 2.59057 + endloop + endfacet + facet normal -0.583195 -0.152492 0.79789 + outer loop + vertex 0.860512 1.24763 2.59226 + vertex 0.859157 1.25203 2.59211 + vertex 0.857196 1.24984 2.59026 + endloop + endfacet + facet normal -0.581326 -0.147652 0.800162 + outer loop + vertex 0.858126 1.24609 2.59025 + vertex 0.860512 1.24763 2.59226 + vertex 0.857196 1.24984 2.59026 + endloop + endfacet + facet normal -0.578186 -0.150821 0.801844 + outer loop + vertex 0.860512 1.24763 2.59226 + vertex 0.86223 1.25162 2.59425 + vertex 0.859157 1.25203 2.59211 + endloop + endfacet + facet normal -0.576292 -0.152186 0.802949 + outer loop + vertex 0.863576 1.2472 2.59438 + vertex 0.86223 1.25162 2.59425 + vertex 0.860512 1.24763 2.59226 + endloop + endfacet + facet normal -0.592211 -0.162521 0.789223 + outer loop + vertex 0.855706 1.25952 2.59109 + vertex 0.852726 1.25759 2.58846 + vertex 0.856368 1.25459 2.59057 + endloop + endfacet + facet normal -0.603888 -0.164478 0.779914 + outer loop + vertex 0.849781 1.25835 2.58634 + vertex 0.852726 1.25759 2.58846 + vertex 0.850037 1.26163 2.58723 + endloop + endfacet + facet normal -0.615233 -0.16135 0.771657 + outer loop + vertex 0.849781 1.25835 2.58634 + vertex 0.847676 1.25738 2.58446 + vertex 0.850537 1.25459 2.58616 + endloop + endfacet + facet normal -0.623623 -0.160804 0.765008 + outer loop + vertex 0.847927 1.26063 2.58535 + vertex 0.84718 1.26441 2.58553 + vertex 0.845046 1.26143 2.58317 + endloop + endfacet + facet normal -0.626013 -0.154425 0.76437 + outer loop + vertex 0.847697 1.25261 2.58351 + vertex 0.847676 1.25738 2.58446 + vertex 0.84509 1.25669 2.5822 + endloop + endfacet + facet normal -0.631921 -0.1493 0.760517 + outer loop + vertex 0.84275 1.25246 2.57941 + vertex 0.844818 1.25344 2.58132 + vertex 0.843038 1.25573 2.5803 + endloop + endfacet + facet normal -0.639007 -0.145221 0.755368 + outer loop + vertex 0.842711 1.24761 2.57845 + vertex 0.84275 1.25246 2.57941 + vertex 0.84015 1.25179 2.57708 + endloop + endfacet + facet normal -0.622822 -0.148319 0.768176 + outer loop + vertex 0.848853 1.24704 2.58337 + vertex 0.847697 1.25261 2.58351 + vertex 0.845531 1.24962 2.58118 + endloop + endfacet + facet normal -0.616941 -0.157196 0.771151 + outer loop + vertex 0.85006 1.23666 2.58228 + vertex 0.85002 1.24147 2.58323 + vertex 0.847225 1.23945 2.58058 + endloop + endfacet + facet normal -0.617991 -0.159005 0.769938 + outer loop + vertex 0.847977 1.23565 2.5804 + vertex 0.85006 1.23666 2.58228 + vertex 0.847225 1.23945 2.58058 + endloop + endfacet + facet normal -0.615558 -0.165224 0.770577 + outer loop + vertex 0.849815 1.23337 2.58138 + vertex 0.85006 1.23666 2.58228 + vertex 0.847977 1.23565 2.5804 + endloop + endfacet + facet normal -0.619982 -0.170834 0.765793 + outer loop + vertex 0.847728 1.23237 2.57946 + vertex 0.849815 1.23337 2.58138 + vertex 0.847977 1.23565 2.5804 + endloop + endfacet + facet normal -0.629432 -0.168086 0.758658 + outer loop + vertex 0.847977 1.23565 2.5804 + vertex 0.845122 1.23643 2.5782 + vertex 0.847728 1.23237 2.57946 + endloop + endfacet + facet normal -0.628104 -0.166803 0.760041 + outer loop + vertex 0.847728 1.23237 2.57946 + vertex 0.845122 1.23643 2.5782 + vertex 0.845092 1.23168 2.57714 + endloop + endfacet + facet normal -0.61887 -0.17366 0.766056 + outer loop + vertex 0.849815 1.23337 2.58138 + vertex 0.847728 1.23237 2.57946 + vertex 0.85059 1.22959 2.58115 + endloop + endfacet + facet normal -0.608395 -0.167193 0.775823 + outer loop + vertex 0.849815 1.23337 2.58138 + vertex 0.852729 1.2326 2.5835 + vertex 0.85006 1.23666 2.58228 + endloop + endfacet + facet normal -0.607505 -0.166343 0.776703 + outer loop + vertex 0.852729 1.2326 2.5835 + vertex 0.852685 1.2374 2.58449 + vertex 0.85006 1.23666 2.58228 + endloop + endfacet + facet normal -0.628961 -0.160741 0.760639 + outer loop + vertex 0.847977 1.23565 2.5804 + vertex 0.847225 1.23945 2.58058 + vertex 0.845122 1.23643 2.5782 + endloop + endfacet + facet normal -0.632368 -0.148326 0.760336 + outer loop + vertex 0.842711 1.24761 2.57845 + vertex 0.843922 1.24196 2.57835 + vertex 0.846366 1.24452 2.58088 + endloop + endfacet + facet normal -0.649422 -0.151759 0.745131 + outer loop + vertex 0.836963 1.24747 2.57348 + vertex 0.838305 1.24199 2.57354 + vertex 0.840538 1.24447 2.57599 + endloop + endfacet + facet normal -0.640069 -0.146228 0.754274 + outer loop + vertex 0.839677 1.24846 2.57604 + vertex 0.842711 1.24761 2.57845 + vertex 0.84015 1.25179 2.57708 + endloop + endfacet + facet normal -0.63793 -0.149572 0.75543 + outer loop + vertex 0.84275 1.25246 2.57941 + vertex 0.840231 1.2565 2.57809 + vertex 0.84015 1.25179 2.57708 + endloop + endfacet + facet normal -0.635683 -0.160299 0.755124 + outer loop + vertex 0.839037 1.26197 2.57824 + vertex 0.840231 1.2565 2.57809 + vertex 0.842308 1.25947 2.58047 + endloop + endfacet + facet normal -0.647825 -0.156718 0.745495 + outer loop + vertex 0.836751 1.25942 2.57572 + vertex 0.834479 1.25705 2.57325 + vertex 0.837519 1.25468 2.57539 + endloop + endfacet + facet normal -0.645938 -0.151923 0.74812 + outer loop + vertex 0.834479 1.25705 2.57325 + vertex 0.835501 1.25242 2.57319 + vertex 0.837519 1.25468 2.57539 + endloop + endfacet + facet normal -0.649485 -0.14806 0.74582 + outer loop + vertex 0.836963 1.24747 2.57348 + vertex 0.837966 1.25096 2.57505 + vertex 0.835501 1.25242 2.57319 + endloop + endfacet + facet normal -0.661749 -0.152411 0.73407 + outer loop + vertex 0.832792 1.24697 2.56967 + vertex 0.834688 1.24718 2.57142 + vertex 0.833757 1.24997 2.57116 + endloop + endfacet + facet normal -0.664649 -0.159225 0.729993 + outer loop + vertex 0.832639 1.24245 2.56854 + vertex 0.832792 1.24697 2.56967 + vertex 0.830144 1.24665 2.56719 + endloop + endfacet + facet normal -0.65463 -0.153085 0.740287 + outer loop + vertex 0.838305 1.24199 2.57354 + vertex 0.836963 1.24747 2.57348 + vertex 0.835255 1.24426 2.57131 + endloop + endfacet + facet normal -0.648373 -0.157498 0.744853 + outer loop + vertex 0.838305 1.24199 2.57354 + vertex 0.839333 1.23702 2.57338 + vertex 0.841598 1.23939 2.57585 + endloop + endfacet + facet normal -0.663759 -0.160215 0.730585 + outer loop + vertex 0.832639 1.24245 2.56854 + vertex 0.833908 1.23688 2.56847 + vertex 0.836117 1.23949 2.57105 + endloop + endfacet + facet normal -0.665653 -0.163828 0.728057 + outer loop + vertex 0.835242 1.23124 2.56843 + vertex 0.833908 1.23688 2.56847 + vertex 0.831656 1.23436 2.56585 + endloop + endfacet + facet normal -0.653854 -0.164382 0.738548 + outer loop + vertex 0.840397 1.23236 2.57328 + vertex 0.839333 1.23702 2.57338 + vertex 0.837261 1.23446 2.57097 + endloop + endfacet + facet normal -0.646548 -0.162851 0.745289 + outer loop + vertex 0.839333 1.23702 2.57338 + vertex 0.840397 1.23236 2.57328 + vertex 0.842391 1.2346 2.5755 + endloop + endfacet + facet normal -0.634964 -0.165537 0.754598 + outer loop + vertex 0.845092 1.23168 2.57714 + vertex 0.845122 1.23643 2.5782 + vertex 0.842391 1.2346 2.5755 + endloop + endfacet + facet normal -0.62678 -0.171798 0.760021 + outer loop + vertex 0.847776 1.22758 2.57842 + vertex 0.847728 1.23237 2.57946 + vertex 0.845092 1.23168 2.57714 + endloop + endfacet + facet normal -0.637852 -0.174034 0.750238 + outer loop + vertex 0.841956 1.2274 2.5735 + vertex 0.844677 1.22837 2.57604 + vertex 0.84289 1.23086 2.5751 + endloop + endfacet + facet normal -0.64314 -0.175114 0.745457 + outer loop + vertex 0.843541 1.22188 2.57357 + vertex 0.841956 1.2274 2.5735 + vertex 0.840281 1.22424 2.57132 + endloop + endfacet + facet normal -0.640842 -0.182298 0.745713 + outer loop + vertex 0.845105 1.21629 2.57355 + vertex 0.843541 1.22188 2.57357 + vertex 0.841279 1.21946 2.57104 + endloop + endfacet + facet normal -0.625207 -0.182831 0.758742 + outer loop + vertex 0.848735 1.21499 2.57627 + vertex 0.850406 1.21748 2.57825 + vertex 0.847078 1.21952 2.576 + endloop + endfacet + facet normal -0.611667 -0.195218 0.766651 + outer loop + vertex 0.852181 1.21252 2.57844 + vertex 0.854944 1.21353 2.58091 + vertex 0.853021 1.21603 2.58001 + endloop + endfacet + facet normal -0.612774 -0.192021 0.766574 + outer loop + vertex 0.854944 1.21353 2.58091 + vertex 0.852181 1.21252 2.57844 + vertex 0.856057 1.20954 2.5808 + endloop + endfacet + facet normal -0.606677 -0.189414 0.772053 + outer loop + vertex 0.854944 1.21353 2.58091 + vertex 0.855256 1.21689 2.58197 + vertex 0.853021 1.21603 2.58001 + endloop + endfacet + facet normal -0.603444 -0.19044 0.774331 + outer loop + vertex 0.854944 1.21353 2.58091 + vertex 0.858183 1.2127 2.58323 + vertex 0.855256 1.21689 2.58197 + endloop + endfacet + facet normal -0.601436 -0.188423 0.776383 + outer loop + vertex 0.858183 1.2127 2.58323 + vertex 0.857959 1.21766 2.58426 + vertex 0.855256 1.21689 2.58197 + endloop + endfacet + facet normal -0.619154 -0.177223 0.76501 + outer loop + vertex 0.84913 1.2222 2.57831 + vertex 0.850406 1.21748 2.57825 + vertex 0.852395 1.21979 2.58039 + endloop + endfacet + facet normal -0.62663 -0.173263 0.759813 + outer loop + vertex 0.84913 1.2222 2.57831 + vertex 0.847776 1.22758 2.57842 + vertex 0.845685 1.22446 2.57599 + endloop + endfacet + facet normal -0.618558 -0.173112 0.766432 + outer loop + vertex 0.847728 1.23237 2.57946 + vertex 0.847776 1.22758 2.57842 + vertex 0.85059 1.22959 2.58115 + endloop + endfacet + facet normal -0.610769 -0.171493 0.773015 + outer loop + vertex 0.855177 1.2217 2.58302 + vertex 0.85393 1.22714 2.58324 + vertex 0.851499 1.22463 2.58077 + endloop + endfacet + facet normal -0.608722 -0.172095 0.774494 + outer loop + vertex 0.85059 1.22959 2.58115 + vertex 0.852729 1.2326 2.5835 + vertex 0.849815 1.23337 2.58138 + endloop + endfacet + facet normal -0.60097 -0.167289 0.781569 + outer loop + vertex 0.852685 1.2374 2.58449 + vertex 0.852729 1.2326 2.5835 + vertex 0.855644 1.2345 2.58615 + endloop + endfacet + facet normal -0.609744 -0.158221 0.776645 + outer loop + vertex 0.852685 1.2374 2.58449 + vertex 0.85002 1.24147 2.58323 + vertex 0.85006 1.23666 2.58228 + endloop + endfacet + facet normal -0.610317 -0.148369 0.778139 + outer loop + vertex 0.848853 1.24704 2.58337 + vertex 0.85002 1.24147 2.58323 + vertex 0.852203 1.24452 2.58552 + endloop + endfacet + facet normal -0.594826 -0.153592 0.789045 + outer loop + vertex 0.854829 1.2384 2.58634 + vertex 0.8551 1.24174 2.5872 + vertex 0.852934 1.24071 2.58536 + endloop + endfacet + facet normal -0.597416 -0.145926 0.788543 + outer loop + vertex 0.852203 1.24452 2.58552 + vertex 0.85509 1.24663 2.5881 + vertex 0.851378 1.24957 2.58583 + endloop + endfacet + facet normal -0.588404 -0.14938 0.794649 + outer loop + vertex 0.858126 1.24609 2.59025 + vertex 0.857196 1.24984 2.59026 + vertex 0.85509 1.24663 2.5881 + endloop + endfacet + facet normal -0.58139 -0.147523 0.800139 + outer loop + vertex 0.860103 1.24375 2.59125 + vertex 0.860512 1.24763 2.59226 + vertex 0.858126 1.24609 2.59025 + endloop + endfacet + facet normal -0.574751 -0.149381 0.804579 + outer loop + vertex 0.860103 1.24375 2.59125 + vertex 0.863282 1.24278 2.59334 + vertex 0.860512 1.24763 2.59226 + endloop + endfacet + facet normal -0.586829 -0.154002 0.794931 + outer loop + vertex 0.857905 1.23756 2.58846 + vertex 0.857841 1.24258 2.58938 + vertex 0.8551 1.24174 2.5872 + endloop + endfacet + facet normal -0.575048 -0.151788 0.803915 + outer loop + vertex 0.860919 1.23965 2.59106 + vertex 0.863282 1.24278 2.59334 + vertex 0.860103 1.24375 2.59125 + endloop + endfacet + facet normal -0.576282 -0.15055 0.803264 + outer loop + vertex 0.863282 1.24278 2.59334 + vertex 0.863576 1.2472 2.59438 + vertex 0.860512 1.24763 2.59226 + endloop + endfacet + facet normal -0.550112 -0.15176 0.821186 + outer loop + vertex 0.869083 1.24207 2.5972 + vertex 0.869383 1.24661 2.59824 + vertex 0.866293 1.24464 2.5958 + endloop + endfacet + facet normal -0.532624 -0.151228 0.832731 + outer loop + vertex 0.867929 1.25262 2.5984 + vertex 0.869383 1.24661 2.59824 + vertex 0.871814 1.2501 2.60043 + endloop + endfacet + facet normal -0.568235 -0.149555 0.809161 + outer loop + vertex 0.86223 1.25162 2.59425 + vertex 0.863576 1.2472 2.59438 + vertex 0.865656 1.24931 2.59623 + endloop + endfacet + facet normal -0.578184 -0.157882 0.800485 + outer loop + vertex 0.86223 1.25162 2.59425 + vertex 0.859444 1.25648 2.5932 + vertex 0.859157 1.25203 2.59211 + endloop + endfacet + facet normal -0.567055 -0.153903 0.809174 + outer loop + vertex 0.864683 1.25316 2.59628 + vertex 0.865089 1.25671 2.59725 + vertex 0.862652 1.25551 2.59531 + endloop + endfacet + facet normal -0.554984 -0.148397 0.818518 + outer loop + vertex 0.868259 1.25767 2.59957 + vertex 0.865332 1.26188 2.59835 + vertex 0.865089 1.25671 2.59725 + endloop + endfacet + facet normal -0.573798 -0.157931 0.803625 + outer loop + vertex 0.858124 1.26257 2.59345 + vertex 0.859444 1.25648 2.5932 + vertex 0.861948 1.25958 2.5956 + endloop + endfacet + facet normal -0.575884 -0.145182 0.804537 + outer loop + vertex 0.858124 1.26257 2.59345 + vertex 0.858459 1.26706 2.5945 + vertex 0.855374 1.26743 2.59236 + endloop + endfacet + facet normal -0.569915 -0.12358 0.812357 + outer loop + vertex 0.857211 1.27155 2.59431 + vertex 0.858459 1.26706 2.5945 + vertex 0.860553 1.26935 2.59632 + endloop + endfacet + facet normal -0.551288 -0.11642 0.826152 + outer loop + vertex 0.862941 1.27266 2.5984 + vertex 0.863894 1.26727 2.59828 + vertex 0.866399 1.26997 2.60033 + endloop + endfacet + facet normal -0.536228 -0.107932 0.837144 + outer loop + vertex 0.866399 1.26997 2.60033 + vertex 0.868761 1.27213 2.60212 + vertex 0.866169 1.27459 2.60078 + endloop + endfacet + facet normal -0.509278 -0.118029 0.85247 + outer loop + vertex 0.873125 1.26625 2.60394 + vertex 0.872067 1.27175 2.60407 + vertex 0.869588 1.26793 2.60206 + endloop + endfacet + facet normal -0.531781 -0.101258 0.840807 + outer loop + vertex 0.868761 1.27213 2.60212 + vertex 0.869493 1.27666 2.60313 + vertex 0.866169 1.27459 2.60078 + endloop + endfacet + facet normal -0.531777 -0.108942 0.839848 + outer loop + vertex 0.869493 1.27666 2.60313 + vertex 0.868423 1.28278 2.60325 + vertex 0.865833 1.27935 2.60116 + endloop + endfacet + facet normal -0.484235 -0.116342 0.867169 + outer loop + vertex 0.875071 1.28309 2.60725 + vertex 0.87772 1.28632 2.60916 + vertex 0.874281 1.28791 2.60745 + endloop + endfacet + facet normal -0.485199 -0.119462 0.866205 + outer loop + vertex 0.87772 1.28632 2.60916 + vertex 0.876679 1.29166 2.60931 + vertex 0.874281 1.28791 2.60745 + endloop + endfacet + facet normal -0.490928 -0.114524 0.86364 + outer loop + vertex 0.874281 1.28791 2.60745 + vertex 0.876679 1.29166 2.60931 + vertex 0.873308 1.29201 2.60744 + endloop + endfacet + facet normal -0.516231 -0.116151 0.848537 + outer loop + vertex 0.869001 1.28725 2.60421 + vertex 0.868423 1.28278 2.60325 + vertex 0.87169 1.2851 2.60555 + endloop + endfacet + facet normal -0.530205 -0.114765 0.840066 + outer loop + vertex 0.869001 1.28725 2.60421 + vertex 0.868038 1.2913 2.60416 + vertex 0.865762 1.28761 2.60221 + endloop + endfacet + facet normal -0.532488 -0.112745 0.838895 + outer loop + vertex 0.865762 1.28761 2.60221 + vertex 0.868038 1.2913 2.60416 + vertex 0.864717 1.29286 2.60226 + endloop + endfacet + facet normal -0.532335 -0.112211 0.839064 + outer loop + vertex 0.868038 1.2913 2.60416 + vertex 0.867056 1.29654 2.60423 + vertex 0.864717 1.29286 2.60226 + endloop + endfacet + facet normal -0.534076 -0.110625 0.838168 + outer loop + vertex 0.864717 1.29286 2.60226 + vertex 0.867056 1.29654 2.60423 + vertex 0.863763 1.29706 2.6022 + endloop + endfacet + facet normal -0.52205 -0.110382 0.845742 + outer loop + vertex 0.867056 1.29654 2.60423 + vertex 0.868038 1.2913 2.60416 + vertex 0.870565 1.29409 2.60608 + endloop + endfacet + facet normal -0.504177 -0.117688 0.855544 + outer loop + vertex 0.874281 1.28791 2.60745 + vertex 0.873308 1.29201 2.60744 + vertex 0.871152 1.28958 2.60584 + endloop + endfacet + facet normal -0.522198 -0.110692 0.84561 + outer loop + vertex 0.870016 1.29818 2.60627 + vertex 0.867056 1.29654 2.60423 + vertex 0.870565 1.29409 2.60608 + endloop + endfacet + facet normal -0.534018 -0.109569 0.838343 + outer loop + vertex 0.867056 1.29654 2.60423 + vertex 0.864418 1.30158 2.60321 + vertex 0.863763 1.29706 2.6022 + endloop + endfacet + facet normal -0.518701 -0.105567 0.848413 + outer loop + vertex 0.867869 1.30077 2.60529 + vertex 0.870814 1.30248 2.6073 + vertex 0.867076 1.30506 2.60534 + endloop + endfacet + facet normal -0.530942 -0.109879 0.840254 + outer loop + vertex 0.863889 1.31218 2.60424 + vertex 0.863299 1.30773 2.60329 + vertex 0.866453 1.30988 2.60556 + endloop + endfacet + facet normal -0.51996 -0.108243 0.847305 + outer loop + vertex 0.870814 1.30248 2.6073 + vertex 0.869685 1.30792 2.6073 + vertex 0.867076 1.30506 2.60534 + endloop + endfacet + facet normal -0.522355 -0.105434 0.846185 + outer loop + vertex 0.866453 1.30988 2.60556 + vertex 0.868717 1.31207 2.60723 + vertex 0.866143 1.31435 2.60593 + endloop + endfacet + facet normal -0.509438 -0.106769 0.853858 + outer loop + vertex 0.873101 1.3064 2.60915 + vertex 0.87198 1.31168 2.60914 + vertex 0.869685 1.30792 2.6073 + endloop + endfacet + facet normal -0.519664 -0.101147 0.848362 + outer loop + vertex 0.868717 1.31207 2.60723 + vertex 0.869353 1.31655 2.60816 + vertex 0.866143 1.31435 2.60593 + endloop + endfacet + facet normal -0.509161 -0.0989456 0.854965 + outer loop + vertex 0.8683 1.32267 2.60824 + vertex 0.869353 1.31655 2.60816 + vertex 0.872124 1.32008 2.61022 + endloop + endfacet + facet normal -0.493314 -0.0968973 0.864437 + outer loop + vertex 0.874736 1.31346 2.61097 + vertex 0.875775 1.31752 2.61201 + vertex 0.872777 1.31586 2.61012 + endloop + endfacet + facet normal -0.48258 -0.101082 0.869999 + outer loop + vertex 0.874736 1.31346 2.61097 + vertex 0.877684 1.31275 2.61252 + vertex 0.875775 1.31752 2.61201 + endloop + endfacet + facet normal -0.478221 -0.0952934 0.873054 + outer loop + vertex 0.875775 1.31752 2.61201 + vertex 0.87861 1.32118 2.61397 + vertex 0.875082 1.32295 2.61223 + endloop + endfacet + facet normal -0.477232 -0.0924963 0.873896 + outer loop + vertex 0.87861 1.32118 2.61397 + vertex 0.877985 1.32616 2.61415 + vertex 0.875082 1.32295 2.61223 + endloop + endfacet + facet normal -0.477751 -0.091896 0.873676 + outer loop + vertex 0.875082 1.32295 2.61223 + vertex 0.877985 1.32616 2.61415 + vertex 0.874597 1.32792 2.61249 + endloop + endfacet + facet normal -0.477186 -0.0903624 0.874144 + outer loop + vertex 0.877985 1.32616 2.61415 + vertex 0.877418 1.33118 2.61436 + vertex 0.874597 1.32792 2.61249 + endloop + endfacet + facet normal -0.461107 -0.0889051 0.88288 + outer loop + vertex 0.877418 1.33118 2.61436 + vertex 0.877985 1.32616 2.61415 + vertex 0.880902 1.32945 2.61601 + endloop + endfacet + facet normal -0.461616 -0.0903286 0.882469 + outer loop + vertex 0.880208 1.33434 2.61615 + vertex 0.877418 1.33118 2.61436 + vertex 0.880902 1.32945 2.61601 + endloop + endfacet + facet normal -0.443668 -0.0880407 0.891856 + outer loop + vertex 0.880902 1.32945 2.61601 + vertex 0.883774 1.33287 2.61777 + vertex 0.880208 1.33434 2.61615 + endloop + endfacet + facet normal -0.44102 -0.0908047 0.892892 + outer loop + vertex 0.884425 1.32784 2.61758 + vertex 0.883774 1.33287 2.61777 + vertex 0.880902 1.32945 2.61601 + endloop + endfacet + facet normal -0.440476 -0.0892013 0.893322 + outer loop + vertex 0.881453 1.3245 2.61578 + vertex 0.884425 1.32784 2.61758 + vertex 0.880902 1.32945 2.61601 + endloop + endfacet + facet normal -0.43785 -0.0920753 0.894321 + outer loop + vertex 0.884988 1.32281 2.61734 + vertex 0.884425 1.32784 2.61758 + vertex 0.881453 1.3245 2.61578 + endloop + endfacet + facet normal -0.437247 -0.0903733 0.894789 + outer loop + vertex 0.882102 1.31966 2.61561 + vertex 0.884988 1.32281 2.61734 + vertex 0.881453 1.3245 2.61578 + endloop + endfacet + facet normal -0.457325 -0.092704 0.884454 + outer loop + vertex 0.881453 1.3245 2.61578 + vertex 0.87861 1.32118 2.61397 + vertex 0.882102 1.31966 2.61561 + endloop + endfacet + facet normal -0.457661 -0.0937883 0.884167 + outer loop + vertex 0.87861 1.32118 2.61397 + vertex 0.879683 1.31641 2.61402 + vertex 0.882102 1.31966 2.61561 + endloop + endfacet + facet normal -0.433931 -0.0940853 0.89602 + outer loop + vertex 0.885691 1.31745 2.61712 + vertex 0.884988 1.32281 2.61734 + vertex 0.882102 1.31966 2.61561 + endloop + endfacet + facet normal -0.433285 -0.0927282 0.896474 + outer loop + vertex 0.882662 1.31571 2.61548 + vertex 0.885691 1.31745 2.61712 + vertex 0.882102 1.31966 2.61561 + endloop + endfacet + facet normal -0.459355 -0.0908607 0.883594 + outer loop + vertex 0.880902 1.32945 2.61601 + vertex 0.877985 1.32616 2.61415 + vertex 0.881453 1.3245 2.61578 + endloop + endfacet + facet normal -0.459267 -0.0906068 0.883665 + outer loop + vertex 0.877985 1.32616 2.61415 + vertex 0.87861 1.32118 2.61397 + vertex 0.881453 1.3245 2.61578 + endloop + endfacet + facet normal -0.475606 -0.0979253 0.874191 + outer loop + vertex 0.879683 1.31641 2.61402 + vertex 0.87861 1.32118 2.61397 + vertex 0.875775 1.31752 2.61201 + endloop + endfacet + facet normal -0.516392 -0.0969614 0.850845 + outer loop + vertex 0.8683 1.32267 2.60824 + vertex 0.869047 1.32719 2.60921 + vertex 0.865746 1.32752 2.60724 + endloop + endfacet + facet normal -0.492895 -0.0929289 0.865112 + outer loop + vertex 0.875082 1.32295 2.61223 + vertex 0.874597 1.32792 2.61249 + vertex 0.871717 1.32504 2.61054 + endloop + endfacet + facet normal -0.477527 -0.0899814 0.873997 + outer loop + vertex 0.874597 1.32792 2.61249 + vertex 0.877418 1.33118 2.61436 + vertex 0.874029 1.33274 2.61267 + endloop + endfacet + facet normal -0.477416 -0.0896354 0.874094 + outer loop + vertex 0.877418 1.33118 2.61436 + vertex 0.876547 1.3366 2.61444 + vertex 0.874029 1.33274 2.61267 + endloop + endfacet + facet normal -0.479667 -0.0876911 0.873058 + outer loop + vertex 0.874029 1.33274 2.61267 + vertex 0.876547 1.3366 2.61444 + vertex 0.873123 1.3369 2.61259 + endloop + endfacet + facet normal -0.50467 -0.0924022 0.858353 + outer loop + vertex 0.868257 1.33124 2.60918 + vertex 0.869047 1.32719 2.60921 + vertex 0.871408 1.3297 2.61086 + endloop + endfacet + facet normal -0.516671 -0.0922431 0.8512 + outer loop + vertex 0.868257 1.33124 2.60918 + vertex 0.867599 1.33608 2.6093 + vertex 0.864943 1.33287 2.60734 + endloop + endfacet + facet normal -0.50572 -0.0874835 0.858251 + outer loop + vertex 0.866798 1.34139 2.60937 + vertex 0.867599 1.33608 2.6093 + vertex 0.870333 1.33894 2.61121 + endloop + endfacet + facet normal -0.491856 -0.0904849 0.865962 + outer loop + vertex 0.874029 1.33274 2.61267 + vertex 0.873123 1.3369 2.61259 + vertex 0.870826 1.33426 2.61101 + endloop + endfacet + facet normal -0.505536 -0.0871088 0.858397 + outer loop + vertex 0.869831 1.34304 2.61133 + vertex 0.866798 1.34139 2.60937 + vertex 0.870333 1.33894 2.61121 + endloop + endfacet + facet normal -0.517093 -0.0849095 0.851707 + outer loop + vertex 0.866798 1.34139 2.60937 + vertex 0.864221 1.34636 2.6083 + vertex 0.86352 1.34188 2.60743 + endloop + endfacet + facet normal -0.501415 -0.0789518 0.861597 + outer loop + vertex 0.867686 1.34559 2.61032 + vertex 0.87073 1.34731 2.61225 + vertex 0.866992 1.3499 2.61031 + endloop + endfacet + facet normal -0.526107 -0.0826282 0.846395 + outer loop + vertex 0.864221 1.34636 2.6083 + vertex 0.863187 1.35256 2.60827 + vertex 0.86049 1.349 2.60624 + endloop + endfacet + facet normal -0.50163 -0.079385 0.861432 + outer loop + vertex 0.87073 1.34731 2.61225 + vertex 0.869922 1.35282 2.61229 + vertex 0.866992 1.3499 2.61031 + endloop + endfacet + facet normal -0.491516 -0.0779436 0.867374 + outer loop + vertex 0.87073 1.34731 2.61225 + vertex 0.873313 1.35114 2.61406 + vertex 0.869922 1.35282 2.61229 + endloop + endfacet + facet normal -0.490702 -0.075598 0.868042 + outer loop + vertex 0.873313 1.35114 2.61406 + vertex 0.872819 1.35609 2.61421 + vertex 0.869922 1.35282 2.61229 + endloop + endfacet + facet normal -0.49093 -0.075333 0.867936 + outer loop + vertex 0.869922 1.35282 2.61229 + vertex 0.872819 1.35609 2.61421 + vertex 0.869502 1.35787 2.61249 + endloop + endfacet + facet normal -0.512711 -0.0816842 0.854667 + outer loop + vertex 0.863957 1.35714 2.60917 + vertex 0.863187 1.35256 2.60827 + vertex 0.866586 1.35495 2.61053 + endloop + endfacet + facet normal -0.522486 -0.0766644 0.849194 + outer loop + vertex 0.863957 1.35714 2.60917 + vertex 0.863278 1.36121 2.60912 + vertex 0.860707 1.35745 2.60719 + endloop + endfacet + facet normal -0.512166 -0.0729488 0.855783 + outer loop + vertex 0.86285 1.36601 2.60927 + vertex 0.863278 1.36121 2.60912 + vertex 0.865958 1.36425 2.61098 + endloop + endfacet + facet normal -0.500012 -0.0744978 0.862808 + outer loop + vertex 0.869502 1.35787 2.61249 + vertex 0.869078 1.36272 2.61266 + vertex 0.86636 1.35967 2.61082 + endloop + endfacet + facet normal -0.4902 -0.0738425 0.868477 + outer loop + vertex 0.869502 1.35787 2.61249 + vertex 0.872389 1.36114 2.61439 + vertex 0.869078 1.36272 2.61266 + endloop + endfacet + facet normal -0.501971 -0.0710367 0.861963 + outer loop + vertex 0.865958 1.36425 2.61098 + vertex 0.868379 1.3668 2.6126 + vertex 0.865726 1.36892 2.61123 + endloop + endfacet + facet normal -0.489555 -0.0719167 0.869002 + outer loop + vertex 0.872389 1.36114 2.61439 + vertex 0.871711 1.3665 2.61446 + vertex 0.869078 1.36272 2.61266 + endloop + endfacet + facet normal -0.499297 -0.0664545 0.863879 + outer loop + vertex 0.868379 1.3668 2.6126 + vertex 0.869181 1.37133 2.61341 + vertex 0.865726 1.36892 2.61123 + endloop + endfacet + facet normal -0.486062 -0.0642452 0.87156 + outer loop + vertex 0.868179 1.37743 2.6133 + vertex 0.869181 1.37133 2.61341 + vertex 0.872043 1.37488 2.61527 + endloop + endfacet + facet normal -0.473225 -0.0614305 0.878797 + outer loop + vertex 0.874639 1.36829 2.61621 + vertex 0.875733 1.37233 2.61708 + vertex 0.872687 1.37068 2.61532 + endloop + endfacet + facet normal -0.465545 -0.064345 0.882682 + outer loop + vertex 0.874639 1.36829 2.61621 + vertex 0.877621 1.36758 2.61773 + vertex 0.875733 1.37233 2.61708 + endloop + endfacet + facet normal -0.473328 -0.0602791 0.878821 + outer loop + vertex 0.872043 1.37488 2.61527 + vertex 0.875023 1.37776 2.61707 + vertex 0.871632 1.37983 2.61539 + endloop + endfacet + facet normal -0.460099 -0.057356 0.886013 + outer loop + vertex 0.878594 1.37602 2.61881 + vertex 0.878012 1.38102 2.61883 + vertex 0.875023 1.37776 2.61707 + endloop + endfacet + facet normal -0.422134 -0.056632 0.904763 + outer loop + vertex 0.885779 1.37252 2.62205 + vertex 0.885181 1.3777 2.62209 + vertex 0.882154 1.37457 2.62049 + endloop + endfacet + facet normal -0.41188 -0.0554882 0.909547 + outer loop + vertex 0.885779 1.37252 2.62205 + vertex 0.889109 1.37577 2.62375 + vertex 0.885181 1.3777 2.62209 + endloop + endfacet + facet normal -0.412793 -0.05783 0.908987 + outer loop + vertex 0.889109 1.37577 2.62375 + vertex 0.88835 1.38112 2.62375 + vertex 0.885181 1.3777 2.62209 + endloop + endfacet + facet normal -0.414315 -0.0561377 0.908401 + outer loop + vertex 0.885181 1.3777 2.62209 + vertex 0.88835 1.38112 2.62375 + vertex 0.8847 1.38277 2.62219 + endloop + endfacet + facet normal -0.444429 -0.0555684 0.894089 + outer loop + vertex 0.878012 1.38102 2.61883 + vertex 0.878594 1.37602 2.61881 + vertex 0.881526 1.37939 2.62048 + endloop + endfacet + facet normal -0.460277 -0.0551625 0.88606 + outer loop + vertex 0.878012 1.38102 2.61883 + vertex 0.877743 1.38603 2.61901 + vertex 0.874622 1.38276 2.61718 + endloop + endfacet + facet normal -0.427786 -0.0568871 0.902088 + outer loop + vertex 0.8847 1.38277 2.62219 + vertex 0.884462 1.3878 2.62239 + vertex 0.881164 1.3844 2.62061 + endloop + endfacet + facet normal -0.41726 -0.05659 0.907024 + outer loop + vertex 0.8847 1.38277 2.62219 + vertex 0.887964 1.38618 2.6239 + vertex 0.884462 1.3878 2.62239 + endloop + endfacet + facet normal -0.417653 -0.0576685 0.906775 + outer loop + vertex 0.887964 1.38618 2.6239 + vertex 0.88777 1.39114 2.62413 + vertex 0.884462 1.3878 2.62239 + endloop + endfacet + facet normal -0.420305 -0.0545081 0.905744 + outer loop + vertex 0.884462 1.3878 2.62239 + vertex 0.88777 1.39114 2.62413 + vertex 0.884356 1.39282 2.62264 + endloop + endfacet + facet normal -0.447291 -0.0526162 0.89284 + outer loop + vertex 0.877646 1.39106 2.61925 + vertex 0.877743 1.38603 2.61901 + vertex 0.881018 1.38943 2.62085 + endloop + endfacet + facet normal -0.459562 -0.0500304 0.886735 + outer loop + vertex 0.877646 1.39106 2.61925 + vertex 0.877591 1.39609 2.61951 + vertex 0.874327 1.39267 2.61762 + endloop + endfacet + facet normal -0.431893 -0.0504758 0.900511 + outer loop + vertex 0.884356 1.39282 2.62264 + vertex 0.884252 1.39781 2.62287 + vertex 0.880952 1.39447 2.6211 + endloop + endfacet + facet normal -0.423269 -0.0504846 0.904596 + outer loop + vertex 0.884356 1.39282 2.62264 + vertex 0.887658 1.39605 2.62437 + vertex 0.884252 1.39781 2.62287 + endloop + endfacet + facet normal -0.422914 -0.0496139 0.904811 + outer loop + vertex 0.887658 1.39605 2.62437 + vertex 0.8875 1.40097 2.62457 + vertex 0.884252 1.39781 2.62287 + endloop + endfacet + facet normal -0.426134 -0.0456087 0.90351 + outer loop + vertex 0.884252 1.39781 2.62287 + vertex 0.8875 1.40097 2.62457 + vertex 0.884006 1.40279 2.62301 + endloop + endfacet + facet normal -0.448054 -0.0462124 0.892811 + outer loop + vertex 0.877454 1.40111 2.6197 + vertex 0.877591 1.39609 2.61951 + vertex 0.880838 1.39947 2.62131 + endloop + endfacet + facet normal -0.458552 -0.0428089 0.887636 + outer loop + vertex 0.877454 1.40111 2.6197 + vertex 0.877087 1.40617 2.61975 + vertex 0.874068 1.40277 2.61803 + endloop + endfacet + facet normal -0.450308 -0.0389393 0.892024 + outer loop + vertex 0.876469 1.41159 2.61968 + vertex 0.877087 1.40617 2.61975 + vertex 0.879964 1.40929 2.62134 + endloop + endfacet + facet normal -0.435397 -0.0420206 0.899257 + outer loop + vertex 0.884006 1.40279 2.62301 + vertex 0.883468 1.40778 2.62298 + vertex 0.880534 1.40444 2.62141 + endloop + endfacet + facet normal -0.428412 -0.0412493 0.902642 + outer loop + vertex 0.884006 1.40279 2.62301 + vertex 0.887107 1.40601 2.62463 + vertex 0.883468 1.40778 2.62298 + endloop + endfacet + facet normal -0.427594 -0.0391163 0.903124 + outer loop + vertex 0.887107 1.40601 2.62463 + vertex 0.886452 1.41148 2.62456 + vertex 0.883468 1.40778 2.62298 + endloop + endfacet + facet normal -0.429361 -0.0373657 0.90236 + outer loop + vertex 0.883468 1.40778 2.62298 + vertex 0.886452 1.41148 2.62456 + vertex 0.88245 1.41254 2.6227 + endloop + endfacet + facet normal -0.450436 -0.0391879 0.891948 + outer loop + vertex 0.879456 1.41324 2.62126 + vertex 0.876469 1.41159 2.61968 + vertex 0.879964 1.40929 2.62134 + endloop + endfacet + facet normal -0.459674 -0.0380122 0.887274 + outer loop + vertex 0.876469 1.41159 2.61968 + vertex 0.874711 1.41633 2.61897 + vertex 0.872588 1.41272 2.61772 + endloop + endfacet + facet normal -0.444976 -0.0323944 0.894956 + outer loop + vertex 0.877671 1.41558 2.62046 + vertex 0.880689 1.41725 2.62202 + vertex 0.877191 1.41953 2.62036 + endloop + endfacet + facet normal -0.445103 -0.0326428 0.894884 + outer loop + vertex 0.880689 1.41725 2.62202 + vertex 0.880133 1.42263 2.62194 + vertex 0.877191 1.41953 2.62036 + endloop + endfacet + facet normal -0.435309 -0.0315606 0.899728 + outer loop + vertex 0.880689 1.41725 2.62202 + vertex 0.883678 1.42103 2.6236 + vertex 0.880133 1.42263 2.62194 + endloop + endfacet + facet normal -0.435238 -0.0313615 0.899769 + outer loop + vertex 0.883678 1.42103 2.6236 + vertex 0.883251 1.42604 2.62357 + vertex 0.880133 1.42263 2.62194 + endloop + endfacet + facet normal -0.43602 -0.0304796 0.899421 + outer loop + vertex 0.880133 1.42263 2.62194 + vertex 0.883251 1.42604 2.62357 + vertex 0.879835 1.42765 2.62196 + endloop + endfacet + facet normal -0.45571 -0.0323952 0.889539 + outer loop + vertex 0.873284 1.42596 2.6186 + vertex 0.873741 1.42105 2.61865 + vertex 0.876681 1.42434 2.62028 + endloop + endfacet + facet normal -0.465057 -0.0307904 0.884745 + outer loop + vertex 0.873284 1.42596 2.6186 + vertex 0.873106 1.4309 2.61868 + vertex 0.869925 1.42768 2.61689 + endloop + endfacet + facet normal -0.445163 -0.0291974 0.894973 + outer loop + vertex 0.879835 1.42765 2.62196 + vertex 0.879746 1.43264 2.62208 + vertex 0.876451 1.42927 2.62033 + endloop + endfacet + facet normal -0.435957 -0.0291421 0.899496 + outer loop + vertex 0.879835 1.42765 2.62196 + vertex 0.88312 1.43104 2.62367 + vertex 0.879746 1.43264 2.62208 + endloop + endfacet + facet normal -0.435144 -0.0269732 0.899957 + outer loop + vertex 0.88312 1.43104 2.62367 + vertex 0.883091 1.43603 2.6238 + vertex 0.879746 1.43264 2.62208 + endloop + endfacet + facet normal -0.436153 -0.0257471 0.899504 + outer loop + vertex 0.879746 1.43264 2.62208 + vertex 0.883091 1.43603 2.6238 + vertex 0.879716 1.43764 2.62221 + endloop + endfacet + facet normal -0.455241 -0.0277489 0.889936 + outer loop + vertex 0.873042 1.43589 2.6188 + vertex 0.873106 1.4309 2.61868 + vertex 0.876385 1.43425 2.62046 + endloop + endfacet + facet normal -0.463652 -0.0237142 0.8857 + outer loop + vertex 0.873042 1.43589 2.6188 + vertex 0.872983 1.44094 2.6189 + vertex 0.869752 1.43761 2.61712 + endloop + endfacet + facet normal -0.444263 -0.021488 0.895638 + outer loop + vertex 0.879716 1.43764 2.62221 + vertex 0.879656 1.44264 2.6223 + vertex 0.87634 1.43927 2.62058 + endloop + endfacet + facet normal -0.436514 -0.0214629 0.899441 + outer loop + vertex 0.879716 1.43764 2.62221 + vertex 0.883045 1.44102 2.62391 + vertex 0.879656 1.44264 2.6223 + endloop + endfacet + facet normal -0.435738 -0.0194277 0.899864 + outer loop + vertex 0.883045 1.44102 2.62391 + vertex 0.882962 1.446 2.62397 + vertex 0.879656 1.44264 2.6223 + endloop + endfacet + facet normal -0.437188 -0.01767 0.899197 + outer loop + vertex 0.879656 1.44264 2.6223 + vertex 0.882962 1.446 2.62397 + vertex 0.879573 1.44764 2.62236 + endloop + endfacet + facet normal -0.454038 -0.0200532 0.890757 + outer loop + vertex 0.872908 1.44599 2.61898 + vertex 0.872983 1.44094 2.6189 + vertex 0.87627 1.44431 2.62066 + endloop + endfacet + facet normal -0.461806 -0.0172255 0.886814 + outer loop + vertex 0.872908 1.44599 2.61898 + vertex 0.872846 1.45102 2.61904 + vertex 0.869582 1.44765 2.61728 + endloop + endfacet + facet normal -0.444521 -0.0159855 0.895626 + outer loop + vertex 0.879573 1.44764 2.62236 + vertex 0.879496 1.45263 2.62241 + vertex 0.876196 1.44933 2.62071 + endloop + endfacet + facet normal -0.43807 -0.0159189 0.8988 + outer loop + vertex 0.879573 1.44764 2.62236 + vertex 0.882875 1.45099 2.62403 + vertex 0.879496 1.45263 2.62241 + endloop + endfacet + facet normal -0.438477 -0.0169726 0.898582 + outer loop + vertex 0.882875 1.45099 2.62403 + vertex 0.882799 1.45598 2.62409 + vertex 0.879496 1.45263 2.62241 + endloop + endfacet + facet normal -0.439224 -0.0160611 0.898234 + outer loop + vertex 0.879496 1.45263 2.62241 + vertex 0.882799 1.45598 2.62409 + vertex 0.879431 1.45762 2.62247 + endloop + endfacet + facet normal -0.451532 -0.0164265 0.892104 + outer loop + vertex 0.872798 1.45602 2.61911 + vertex 0.872846 1.45102 2.61904 + vertex 0.876135 1.45433 2.62077 + endloop + endfacet + facet normal -0.458631 -0.0170691 0.888463 + outer loop + vertex 0.872798 1.45602 2.61911 + vertex 0.872747 1.461 2.61918 + vertex 0.869486 1.45768 2.61743 + endloop + endfacet + facet normal -0.445392 -0.0171429 0.895171 + outer loop + vertex 0.879431 1.45762 2.62247 + vertex 0.879365 1.4626 2.62253 + vertex 0.876079 1.45931 2.62083 + endloop + endfacet + facet normal -0.440046 -0.0171061 0.897812 + outer loop + vertex 0.879431 1.45762 2.62247 + vertex 0.882731 1.46096 2.62415 + vertex 0.879365 1.4626 2.62253 + endloop + endfacet + facet normal -0.440319 -0.0178144 0.897664 + outer loop + vertex 0.882731 1.46096 2.62415 + vertex 0.882662 1.46595 2.62421 + vertex 0.879365 1.4626 2.62253 + endloop + endfacet + facet normal -0.440343 -0.017786 0.897653 + outer loop + vertex 0.879365 1.4626 2.62253 + vertex 0.882662 1.46595 2.62421 + vertex 0.879296 1.46759 2.62259 + endloop + endfacet + facet normal -0.450446 -0.0177733 0.892627 + outer loop + vertex 0.872683 1.46598 2.61925 + vertex 0.872747 1.461 2.61918 + vertex 0.876015 1.46429 2.6209 + endloop + endfacet + facet normal -0.45677 -0.0182192 0.889398 + outer loop + vertex 0.872683 1.46598 2.61925 + vertex 0.872611 1.47096 2.61931 + vertex 0.869367 1.46766 2.61758 + endloop + endfacet + facet normal -0.445161 -0.0174346 0.895281 + outer loop + vertex 0.879296 1.46759 2.62259 + vertex 0.879225 1.47258 2.62266 + vertex 0.875945 1.46927 2.62096 + endloop + endfacet + facet normal -0.440134 -0.0173947 0.897764 + outer loop + vertex 0.879296 1.46759 2.62259 + vertex 0.882593 1.47095 2.62428 + vertex 0.879225 1.47258 2.62266 + endloop + endfacet + facet normal -0.43935 -0.0153608 0.898184 + outer loop + vertex 0.882593 1.47095 2.62428 + vertex 0.88253 1.47594 2.62433 + vertex 0.879225 1.47258 2.62266 + endloop + endfacet + facet normal -0.439501 -0.0151774 0.898114 + outer loop + vertex 0.879225 1.47258 2.62266 + vertex 0.88253 1.47594 2.62433 + vertex 0.879161 1.47757 2.62271 + endloop + endfacet + facet normal -0.450666 -0.0167059 0.892536 + outer loop + vertex 0.872541 1.47595 2.61937 + vertex 0.872611 1.47096 2.61931 + vertex 0.875874 1.47426 2.62102 + endloop + endfacet + facet normal -0.456296 -0.0133087 0.889729 + outer loop + vertex 0.872541 1.47595 2.61937 + vertex 0.872481 1.48094 2.61942 + vertex 0.869231 1.47763 2.6177 + endloop + endfacet + facet normal -0.443708 -0.0108716 0.896105 + outer loop + vertex 0.879161 1.47757 2.62271 + vertex 0.879111 1.48256 2.62275 + vertex 0.875811 1.47925 2.62107 + endloop + endfacet + facet normal -0.43933 -0.0108432 0.89826 + outer loop + vertex 0.879161 1.47757 2.62271 + vertex 0.882479 1.48093 2.62437 + vertex 0.879111 1.48256 2.62275 + endloop + endfacet + facet normal -0.438146 -0.00778143 0.89887 + outer loop + vertex 0.882479 1.48093 2.62437 + vertex 0.882446 1.48592 2.6244 + vertex 0.879111 1.48256 2.62275 + endloop + endfacet + facet normal -0.439328 -0.00633191 0.898304 + outer loop + vertex 0.879111 1.48256 2.62275 + vertex 0.882446 1.48592 2.6244 + vertex 0.87908 1.48754 2.62277 + endloop + endfacet + facet normal -0.45017 -0.00865669 0.892901 + outer loop + vertex 0.872437 1.48593 2.61944 + vertex 0.872481 1.48094 2.61942 + vertex 0.875762 1.48424 2.6211 + endloop + endfacet + facet normal -0.456168 -0.00498573 0.88988 + outer loop + vertex 0.872437 1.48593 2.61944 + vertex 0.872412 1.49092 2.61946 + vertex 0.869138 1.48761 2.61776 + endloop + endfacet + facet normal -0.443113 -0.00358023 0.896459 + outer loop + vertex 0.87908 1.48754 2.62277 + vertex 0.879065 1.49253 2.62278 + vertex 0.875735 1.48922 2.62112 + endloop + endfacet + facet normal -0.438921 -0.00357257 0.898519 + outer loop + vertex 0.87908 1.48754 2.62277 + vertex 0.88243 1.49091 2.62442 + vertex 0.879065 1.49253 2.62278 + endloop + endfacet + facet normal -0.438566 -0.00265698 0.898695 + outer loop + vertex 0.88243 1.49091 2.62442 + vertex 0.882422 1.4959 2.62443 + vertex 0.879065 1.49253 2.62278 + endloop + endfacet + facet normal -0.438279 -0.00301071 0.898834 + outer loop + vertex 0.879065 1.49253 2.62278 + vertex 0.882422 1.4959 2.62443 + vertex 0.879056 1.49752 2.62279 + endloop + endfacet + facet normal -0.448852 -0.00323169 0.8936 + outer loop + vertex 0.8724 1.49591 2.61947 + vertex 0.872412 1.49092 2.61946 + vertex 0.875721 1.49422 2.62113 + endloop + endfacet + facet normal -0.455781 -0.0033029 0.890086 + outer loop + vertex 0.8724 1.49591 2.61947 + vertex 0.872391 1.5009 2.61948 + vertex 0.869104 1.49759 2.61779 + endloop + endfacet + facet normal -0.442872 -0.00352492 0.896578 + outer loop + vertex 0.879056 1.49752 2.62279 + vertex 0.879045 1.5025 2.6228 + vertex 0.875712 1.49921 2.62115 + endloop + endfacet + facet normal -0.437769 -0.00352051 0.899081 + outer loop + vertex 0.879056 1.49752 2.62279 + vertex 0.882413 1.50089 2.62444 + vertex 0.879045 1.5025 2.6228 + endloop + endfacet + facet normal -0.437475 -0.00276207 0.899226 + outer loop + vertex 0.882413 1.50089 2.62444 + vertex 0.882402 1.50587 2.62445 + vertex 0.879045 1.5025 2.6228 + endloop + endfacet + facet normal -0.437725 -0.00245426 0.899105 + outer loop + vertex 0.879045 1.5025 2.6228 + vertex 0.882402 1.50587 2.62445 + vertex 0.879034 1.50749 2.62281 + endloop + endfacet + facet normal -0.449343 -0.00296455 0.893354 + outer loop + vertex 0.872382 1.5059 2.61949 + vertex 0.872391 1.5009 2.61948 + vertex 0.875701 1.5042 2.62116 + endloop + endfacet + facet normal -0.454803 -0.000895021 0.890592 + outer loop + vertex 0.872382 1.5059 2.61949 + vertex 0.872378 1.51089 2.6195 + vertex 0.869085 1.50758 2.61781 + endloop + endfacet + facet normal -0.442608 0.000122326 0.896715 + outer loop + vertex 0.879034 1.50749 2.62281 + vertex 0.87903 1.51248 2.62281 + vertex 0.875693 1.50919 2.62116 + endloop + endfacet + facet normal -0.438122 0.000127018 0.898916 + outer loop + vertex 0.879034 1.50749 2.62281 + vertex 0.882394 1.51086 2.62445 + vertex 0.87903 1.51248 2.62281 + endloop + endfacet + facet normal -0.437587 0.00149812 0.899175 + outer loop + vertex 0.882394 1.51086 2.62445 + vertex 0.882397 1.51585 2.62444 + vertex 0.87903 1.51248 2.62281 + endloop + endfacet + facet normal -0.438655 0.00282047 0.898651 + outer loop + vertex 0.87903 1.51248 2.62281 + vertex 0.882397 1.51585 2.62444 + vertex 0.879038 1.51747 2.6228 + endloop + endfacet + facet normal -0.449014 0.00158147 0.893523 + outer loop + vertex 0.872383 1.51588 2.61949 + vertex 0.872378 1.51089 2.6195 + vertex 0.875694 1.51418 2.62116 + endloop + endfacet + facet normal -0.454002 0.00361009 0.890993 + outer loop + vertex 0.872383 1.51588 2.61949 + vertex 0.872398 1.52087 2.61948 + vertex 0.869091 1.51756 2.61781 + endloop + endfacet + facet normal -0.442812 0.00404919 0.896606 + outer loop + vertex 0.879038 1.51747 2.6228 + vertex 0.879054 1.52247 2.62278 + vertex 0.875707 1.51917 2.62115 + endloop + endfacet + facet normal -0.439234 0.00404269 0.898364 + outer loop + vertex 0.879038 1.51747 2.6228 + vertex 0.882409 1.52084 2.62443 + vertex 0.879054 1.52247 2.62278 + endloop + endfacet + facet normal -0.439561 0.0032095 0.898207 + outer loop + vertex 0.882409 1.52084 2.62443 + vertex 0.882423 1.52584 2.62442 + vertex 0.879054 1.52247 2.62278 + endloop + endfacet + facet normal -0.439887 0.00361414 0.898046 + outer loop + vertex 0.879054 1.52247 2.62278 + vertex 0.882423 1.52584 2.62442 + vertex 0.87907 1.52746 2.62277 + endloop + endfacet + facet normal -0.448012 0.00434799 0.894017 + outer loop + vertex 0.872414 1.52587 2.61946 + vertex 0.872398 1.52087 2.61948 + vertex 0.875725 1.52417 2.62113 + endloop + endfacet + facet normal -0.454119 0.00444571 0.89093 + outer loop + vertex 0.872414 1.52587 2.61946 + vertex 0.872429 1.53086 2.61945 + vertex 0.86912 1.52755 2.61777 + endloop + endfacet + facet normal -0.444112 0.00270593 0.895967 + outer loop + vertex 0.87907 1.52746 2.62277 + vertex 0.879082 1.53246 2.62276 + vertex 0.87574 1.52916 2.62112 + endloop + endfacet + facet normal -0.440321 0.00270055 0.897837 + outer loop + vertex 0.87907 1.52746 2.62277 + vertex 0.882435 1.53083 2.62441 + vertex 0.879082 1.53246 2.62276 + endloop + endfacet + facet normal -0.440463 0.00233866 0.897768 + outer loop + vertex 0.882435 1.53083 2.62441 + vertex 0.882443 1.53582 2.6244 + vertex 0.879082 1.53246 2.62276 + endloop + endfacet + facet normal -0.440659 0.00258246 0.897671 + outer loop + vertex 0.879082 1.53246 2.62276 + vertex 0.882443 1.53582 2.6244 + vertex 0.879091 1.53745 2.62275 + endloop + endfacet + facet normal -0.450164 0.00455744 0.892934 + outer loop + vertex 0.872443 1.53585 2.61943 + vertex 0.872429 1.53086 2.61945 + vertex 0.875751 1.53415 2.6211 + endloop + endfacet + facet normal -0.456286 0.0055408 0.889816 + outer loop + vertex 0.872443 1.53585 2.61943 + vertex 0.872462 1.54084 2.61941 + vertex 0.869154 1.53753 2.61773 + endloop + endfacet + facet normal -0.445764 0.00386573 0.895142 + outer loop + vertex 0.879091 1.53745 2.62275 + vertex 0.879103 1.54245 2.62274 + vertex 0.875763 1.53915 2.62109 + endloop + endfacet + facet normal -0.440867 0.00386127 0.897564 + outer loop + vertex 0.879091 1.53745 2.62275 + vertex 0.882453 1.54082 2.62439 + vertex 0.879103 1.54245 2.62274 + endloop + endfacet + facet normal -0.440265 0.00538499 0.897852 + outer loop + vertex 0.882453 1.54082 2.62439 + vertex 0.882468 1.54581 2.62437 + vertex 0.879103 1.54245 2.62274 + endloop + endfacet + facet normal -0.440957 0.00624632 0.897506 + outer loop + vertex 0.879103 1.54245 2.62274 + vertex 0.882468 1.54581 2.62437 + vertex 0.879123 1.54745 2.62271 + endloop + endfacet + facet normal -0.453354 0.00696326 0.891303 + outer loop + vertex 0.872488 1.54583 2.61938 + vertex 0.872462 1.54084 2.61941 + vertex 0.875781 1.54414 2.62107 + endloop + endfacet + facet normal -0.458914 0.00927674 0.888432 + outer loop + vertex 0.872488 1.54583 2.61938 + vertex 0.872522 1.55082 2.61934 + vertex 0.869212 1.54751 2.61767 + endloop + endfacet + facet normal -0.446555 0.0099349 0.894701 + outer loop + vertex 0.879123 1.54745 2.62271 + vertex 0.879156 1.55245 2.62267 + vertex 0.875809 1.54914 2.62104 + endloop + endfacet + facet normal -0.440978 0.00992053 0.897463 + outer loop + vertex 0.879123 1.54745 2.62271 + vertex 0.882494 1.5508 2.62433 + vertex 0.879156 1.55245 2.62267 + endloop + endfacet + facet normal -0.439679 0.0131605 0.898059 + outer loop + vertex 0.882494 1.5508 2.62433 + vertex 0.882534 1.5558 2.62428 + vertex 0.879156 1.55245 2.62267 + endloop + endfacet + facet normal -0.440583 0.0142909 0.897598 + outer loop + vertex 0.879156 1.55245 2.62267 + vertex 0.882534 1.5558 2.62428 + vertex 0.879203 1.55744 2.62262 + endloop + endfacet + facet normal -0.454472 0.012692 0.89067 + outer loop + vertex 0.872564 1.55582 2.6193 + vertex 0.872522 1.55082 2.61934 + vertex 0.875847 1.55413 2.62099 + endloop + endfacet + facet normal -0.459581 0.0160716 0.887991 + outer loop + vertex 0.872564 1.55582 2.6193 + vertex 0.872617 1.56081 2.61923 + vertex 0.869296 1.55749 2.61757 + endloop + endfacet + facet normal -0.446025 0.0184434 0.89483 + outer loop + vertex 0.879203 1.55744 2.62262 + vertex 0.879267 1.56244 2.62255 + vertex 0.875899 1.55912 2.62093 + endloop + endfacet + facet normal -0.439782 0.0184073 0.897916 + outer loop + vertex 0.879203 1.55744 2.62262 + vertex 0.88259 1.5608 2.62421 + vertex 0.879267 1.56244 2.62255 + endloop + endfacet + facet normal -0.438741 0.0209783 0.898369 + outer loop + vertex 0.88259 1.5608 2.62421 + vertex 0.882664 1.56579 2.62413 + vertex 0.879267 1.56244 2.62255 + endloop + endfacet + facet normal -0.438537 0.0207229 0.898474 + outer loop + vertex 0.879267 1.56244 2.62255 + vertex 0.882664 1.56579 2.62413 + vertex 0.879344 1.56743 2.62247 + endloop + endfacet + facet normal -0.452646 0.018528 0.891498 + outer loop + vertex 0.872679 1.5658 2.61916 + vertex 0.872617 1.56081 2.61923 + vertex 0.875964 1.56412 2.62086 + endloop + endfacet + facet normal -0.45895 0.0193392 0.888251 + outer loop + vertex 0.872679 1.5658 2.61916 + vertex 0.872749 1.5708 2.61909 + vertex 0.869414 1.56748 2.61744 + endloop + endfacet + facet normal -0.444287 0.0207761 0.895644 + outer loop + vertex 0.879344 1.56743 2.62247 + vertex 0.879429 1.57242 2.62239 + vertex 0.876038 1.56911 2.62079 + endloop + endfacet + facet normal -0.437322 0.0207081 0.899066 + outer loop + vertex 0.879344 1.56743 2.62247 + vertex 0.882749 1.57079 2.62405 + vertex 0.879429 1.57242 2.62239 + endloop + endfacet + facet normal -0.437327 0.0206972 0.899065 + outer loop + vertex 0.882749 1.57079 2.62405 + vertex 0.882836 1.57578 2.62397 + vertex 0.879429 1.57242 2.62239 + endloop + endfacet + facet normal -0.436397 0.0195285 0.899542 + outer loop + vertex 0.879429 1.57242 2.62239 + vertex 0.882836 1.57578 2.62397 + vertex 0.879512 1.57741 2.62233 + endloop + endfacet + facet normal -0.450817 0.0188522 0.892417 + outer loop + vertex 0.872824 1.5758 2.61902 + vertex 0.872749 1.5708 2.61909 + vertex 0.876117 1.5741 2.62072 + endloop + endfacet + facet normal -0.458566 0.0197014 0.888442 + outer loop + vertex 0.872824 1.5758 2.61902 + vertex 0.872906 1.5808 2.61895 + vertex 0.86956 1.57747 2.6173 + endloop + endfacet + facet normal -0.442838 0.0194119 0.896392 + outer loop + vertex 0.879512 1.57741 2.62233 + vertex 0.879586 1.5824 2.62225 + vertex 0.876197 1.5791 2.62065 + endloop + endfacet + facet normal -0.43611 0.0193597 0.899685 + outer loop + vertex 0.879512 1.57741 2.62233 + vertex 0.882913 1.58076 2.6239 + vertex 0.879586 1.5824 2.62225 + endloop + endfacet + facet normal -0.435641 0.0205184 0.899887 + outer loop + vertex 0.882913 1.58076 2.6239 + vertex 0.882976 1.58575 2.62382 + vertex 0.879586 1.5824 2.62225 + endloop + endfacet + facet normal -0.436265 0.0212996 0.899566 + outer loop + vertex 0.879586 1.5824 2.62225 + vertex 0.882976 1.58575 2.62382 + vertex 0.879649 1.58738 2.62217 + endloop + endfacet + facet normal -0.451867 0.0215715 0.891824 + outer loop + vertex 0.872986 1.58579 2.61887 + vertex 0.872906 1.5808 2.61895 + vertex 0.876272 1.58408 2.62058 + endloop + endfacet + facet normal -0.460193 0.0258056 0.887444 + outer loop + vertex 0.872986 1.58579 2.61887 + vertex 0.873058 1.59076 2.61876 + vertex 0.86972 1.58746 2.61713 + endloop + endfacet + facet normal -0.443401 0.0248368 0.895979 + outer loop + vertex 0.879649 1.58738 2.62217 + vertex 0.879718 1.59238 2.62206 + vertex 0.876339 1.58907 2.62048 + endloop + endfacet + facet normal -0.436421 0.0248106 0.8994 + outer loop + vertex 0.879649 1.58738 2.62217 + vertex 0.883039 1.59075 2.62372 + vertex 0.879718 1.59238 2.62206 + endloop + endfacet + facet normal -0.435269 0.0276262 0.899877 + outer loop + vertex 0.883039 1.59075 2.62372 + vertex 0.883151 1.59579 2.62362 + vertex 0.879718 1.59238 2.62206 + endloop + endfacet + facet normal -0.436198 0.0287856 0.89939 + outer loop + vertex 0.879718 1.59238 2.62206 + vertex 0.883151 1.59579 2.62362 + vertex 0.879848 1.59745 2.62196 + endloop + endfacet + facet normal -0.454439 0.0291439 0.890301 + outer loop + vertex 0.873132 1.59571 2.61864 + vertex 0.873058 1.59076 2.61876 + vertex 0.876415 1.59405 2.62037 + endloop + endfacet + facet normal -0.46317 0.0315171 0.885709 + outer loop + vertex 0.873132 1.59571 2.61864 + vertex 0.873236 1.60065 2.61852 + vertex 0.869856 1.59737 2.61687 + endloop + endfacet + facet normal -0.464172 0.0328404 0.885136 + outer loop + vertex 0.869856 1.59737 2.61687 + vertex 0.873236 1.60065 2.61852 + vertex 0.870012 1.60224 2.61677 + endloop + endfacet + facet normal -0.46367 0.0340948 0.885352 + outer loop + vertex 0.873236 1.60065 2.61852 + vertex 0.873381 1.60562 2.6184 + vertex 0.870012 1.60224 2.61677 + endloop + endfacet + facet normal -0.455927 0.0339632 0.889369 + outer loop + vertex 0.873381 1.60562 2.6184 + vertex 0.873236 1.60065 2.61852 + vertex 0.876678 1.60405 2.62015 + endloop + endfacet + facet normal -0.444467 0.0318643 0.895228 + outer loop + vertex 0.879848 1.59745 2.62196 + vertex 0.880086 1.60261 2.6219 + vertex 0.876529 1.59906 2.62026 + endloop + endfacet + facet normal -0.435439 0.0315046 0.899667 + outer loop + vertex 0.879848 1.59745 2.62196 + vertex 0.883415 1.60094 2.62357 + vertex 0.880086 1.60261 2.6219 + endloop + endfacet + facet normal -0.444838 0.03469 0.894939 + outer loop + vertex 0.876678 1.60405 2.62015 + vertex 0.880211 1.60765 2.62177 + vertex 0.876867 1.60889 2.62006 + endloop + endfacet + facet normal -0.43406 0.0348025 0.900211 + outer loop + vertex 0.883415 1.60094 2.62357 + vertex 0.884084 1.60658 2.62367 + vertex 0.880086 1.60261 2.6219 + endloop + endfacet + facet normal -0.450631 0.0463745 0.891505 + outer loop + vertex 0.877418 1.61273 2.62018 + vertex 0.879594 1.61534 2.62114 + vertex 0.876968 1.61607 2.61977 + endloop + endfacet + facet normal -0.44438 0.0361532 0.895108 + outer loop + vertex 0.880211 1.60765 2.62177 + vertex 0.88013 1.61215 2.62155 + vertex 0.876867 1.60889 2.62006 + endloop + endfacet + facet normal -0.460271 0.0444931 0.886663 + outer loop + vertex 0.877418 1.61273 2.62018 + vertex 0.876968 1.61607 2.61977 + vertex 0.873542 1.6114 2.61823 + endloop + endfacet + facet normal -0.455518 0.0350041 0.889538 + outer loop + vertex 0.876867 1.60889 2.62006 + vertex 0.873381 1.60562 2.6184 + vertex 0.876678 1.60405 2.62015 + endloop + endfacet + facet normal -0.464432 0.0350649 0.884914 + outer loop + vertex 0.870012 1.60224 2.61677 + vertex 0.873381 1.60562 2.6184 + vertex 0.870166 1.60682 2.61667 + endloop + endfacet + facet normal -0.473091 0.0390126 0.880149 + outer loop + vertex 0.869702 1.61019 2.61627 + vertex 0.867618 1.6078 2.61525 + vertex 0.870166 1.60682 2.61667 + endloop + endfacet + facet normal -0.478309 0.0448692 0.877045 + outer loop + vertex 0.867618 1.6078 2.61525 + vertex 0.869702 1.61019 2.61627 + vertex 0.867143 1.61117 2.61482 + endloop + endfacet + facet normal -0.488265 0.0479901 0.871375 + outer loop + vertex 0.867143 1.61117 2.61482 + vertex 0.86721 1.61578 2.61461 + vertex 0.864016 1.61238 2.613 + endloop + endfacet + facet normal -0.466041 0.0451919 0.883608 + outer loop + vertex 0.873542 1.6114 2.61823 + vertex 0.873747 1.61724 2.61804 + vertex 0.870282 1.61409 2.61637 + endloop + endfacet + facet normal -0.459518 0.0485022 0.886843 + outer loop + vertex 0.873747 1.61724 2.61804 + vertex 0.87718 1.62074 2.61963 + vertex 0.873972 1.62234 2.61788 + endloop + endfacet + facet normal -0.478398 0.0498629 0.876726 + outer loop + vertex 0.867394 1.62074 2.61443 + vertex 0.86721 1.61578 2.61461 + vertex 0.870548 1.61902 2.61624 + endloop + endfacet + facet normal -0.489738 0.0514003 0.870353 + outer loop + vertex 0.867394 1.62074 2.61443 + vertex 0.867586 1.62575 2.61424 + vertex 0.864257 1.6224 2.61256 + endloop + endfacet + facet normal -0.468642 0.0498632 0.88198 + outer loop + vertex 0.873972 1.62234 2.61788 + vertex 0.874152 1.62737 2.61769 + vertex 0.870763 1.62406 2.61607 + endloop + endfacet + facet normal -0.45986 0.0522716 0.886452 + outer loop + vertex 0.874152 1.62737 2.61769 + vertex 0.877541 1.63066 2.61925 + vertex 0.874298 1.63237 2.61747 + endloop + endfacet + facet normal -0.481156 0.0537731 0.874984 + outer loop + vertex 0.867759 1.63072 2.61403 + vertex 0.867586 1.62575 2.61424 + vertex 0.870938 1.62907 2.61588 + endloop + endfacet + facet normal -0.493167 0.0573896 0.86804 + outer loop + vertex 0.867759 1.63072 2.61403 + vertex 0.867942 1.63566 2.6138 + vertex 0.864597 1.63233 2.61212 + endloop + endfacet + facet normal -0.482943 0.0610782 0.873519 + outer loop + vertex 0.868172 1.64067 2.61358 + vertex 0.867942 1.63566 2.6138 + vertex 0.871303 1.639 2.61543 + endloop + endfacet + facet normal -0.47 0.0568421 0.880834 + outer loop + vertex 0.874298 1.63237 2.61747 + vertex 0.874465 1.63735 2.61724 + vertex 0.871101 1.63405 2.61565 + endloop + endfacet + facet normal -0.461674 0.0615934 0.884909 + outer loop + vertex 0.874465 1.63735 2.61724 + vertex 0.877892 1.64065 2.6188 + vertex 0.874699 1.64227 2.61702 + endloop + endfacet + facet normal -0.481297 0.0651452 0.874133 + outer loop + vertex 0.87228 1.6478 2.61532 + vertex 0.871903 1.65118 2.61486 + vertex 0.868448 1.64648 2.61331 + endloop + endfacet + facet normal -0.481214 0.0650666 0.874185 + outer loop + vertex 0.868448 1.64648 2.61331 + vertex 0.871903 1.65118 2.61486 + vertex 0.868744 1.65231 2.61303 + endloop + endfacet + facet normal -0.481806 0.0637061 0.873959 + outer loop + vertex 0.871614 1.64389 2.61524 + vertex 0.868172 1.64067 2.61358 + vertex 0.871303 1.639 2.61543 + endloop + endfacet + facet normal -0.492806 0.0609303 0.868003 + outer loop + vertex 0.864839 1.63721 2.61193 + vertex 0.868172 1.64067 2.61358 + vertex 0.865081 1.64181 2.61175 + endloop + endfacet + facet normal -0.501945 0.062228 0.862658 + outer loop + vertex 0.864698 1.64518 2.61128 + vertex 0.862627 1.64272 2.61025 + vertex 0.865081 1.64181 2.61175 + endloop + endfacet + facet normal -0.505973 0.0667508 0.859963 + outer loop + vertex 0.862627 1.64272 2.61025 + vertex 0.864698 1.64518 2.61128 + vertex 0.862232 1.6461 2.60976 + endloop + endfacet + facet normal -0.514705 0.0686922 0.854611 + outer loop + vertex 0.862232 1.6461 2.60976 + vertex 0.862375 1.65072 2.60947 + vertex 0.859184 1.64729 2.60783 + endloop + endfacet + facet normal -0.492292 0.0653403 0.867974 + outer loop + vertex 0.868448 1.64648 2.61331 + vertex 0.868744 1.65231 2.61303 + vertex 0.865334 1.6491 2.61134 + endloop + endfacet + facet normal -0.481667 0.0675313 0.873749 + outer loop + vertex 0.868744 1.65231 2.61303 + vertex 0.872151 1.6558 2.61464 + vertex 0.869015 1.65734 2.6128 + endloop + endfacet + facet normal -0.481412 0.0681604 0.87384 + outer loop + vertex 0.872151 1.6558 2.61464 + vertex 0.872396 1.66068 2.6144 + vertex 0.869015 1.65734 2.6128 + endloop + endfacet + facet normal -0.483304 0.0706687 0.872596 + outer loop + vertex 0.869015 1.65734 2.6128 + vertex 0.872396 1.66068 2.6144 + vertex 0.869235 1.66231 2.61252 + endloop + endfacet + facet normal -0.507725 0.0708934 0.858597 + outer loop + vertex 0.862602 1.65564 2.6092 + vertex 0.862375 1.65072 2.60947 + vertex 0.865658 1.654 2.61114 + endloop + endfacet + facet normal -0.518038 0.0740425 0.852147 + outer loop + vertex 0.862602 1.65564 2.6092 + vertex 0.862749 1.66058 2.60886 + vertex 0.859564 1.65725 2.60721 + endloop + endfacet + facet normal -0.495766 0.070825 0.865563 + outer loop + vertex 0.869015 1.65734 2.6128 + vertex 0.869235 1.66231 2.61252 + vertex 0.865889 1.65896 2.61087 + endloop + endfacet + facet normal -0.484904 0.0749411 0.871351 + outer loop + vertex 0.869235 1.66231 2.61252 + vertex 0.872639 1.66567 2.61412 + vertex 0.869497 1.66732 2.61223 + endloop + endfacet + facet normal -0.484089 0.076825 0.87164 + outer loop + vertex 0.872639 1.66567 2.61412 + vertex 0.873017 1.67078 2.61388 + vertex 0.869497 1.66732 2.61223 + endloop + endfacet + facet normal -0.485218 0.0783358 0.870877 + outer loop + vertex 0.869497 1.66732 2.61223 + vertex 0.873017 1.67078 2.61388 + vertex 0.8699 1.67236 2.612 + endloop + endfacet + facet normal -0.513252 0.0782965 0.854659 + outer loop + vertex 0.862555 1.6658 2.60827 + vertex 0.862749 1.66058 2.60886 + vertex 0.866041 1.66398 2.61053 + endloop + endfacet + facet normal -0.523976 0.0818104 0.847795 + outer loop + vertex 0.862555 1.6658 2.60827 + vertex 0.863466 1.6713 2.6083 + vertex 0.860076 1.66881 2.60644 + endloop + endfacet + facet normal -0.499224 0.0790922 0.862856 + outer loop + vertex 0.869497 1.66732 2.61223 + vertex 0.8699 1.67236 2.612 + vertex 0.866369 1.66906 2.61026 + endloop + endfacet + facet normal -0.51632 0.0837195 0.852294 + outer loop + vertex 0.864401 1.67686 2.60832 + vertex 0.863466 1.6713 2.6083 + vertex 0.866936 1.67394 2.61014 + endloop + endfacet + facet normal -0.503615 0.0901537 0.859212 + outer loop + vertex 0.867635 1.67768 2.6102 + vertex 0.869657 1.6802 2.61112 + vertex 0.867269 1.681 2.60964 + endloop + endfacet + facet normal -0.529008 0.0873422 0.84411 + outer loop + vertex 0.864401 1.67686 2.60832 + vertex 0.864252 1.68219 2.60767 + vertex 0.86087 1.67885 2.6059 + endloop + endfacet + facet normal -0.534563 0.0889208 0.840437 + outer loop + vertex 0.86087 1.67885 2.6059 + vertex 0.857515 1.67559 2.60411 + vertex 0.860595 1.67366 2.60627 + endloop + endfacet + facet normal -0.539303 0.094839 0.836754 + outer loop + vertex 0.854351 1.67234 2.60244 + vertex 0.857515 1.67559 2.60411 + vertex 0.85458 1.67692 2.60207 + endloop + endfacet + facet normal -0.546606 0.0955485 0.831921 + outer loop + vertex 0.854287 1.68027 2.60149 + vertex 0.852343 1.67799 2.60048 + vertex 0.85458 1.67692 2.60207 + endloop + endfacet + facet normal -0.539179 0.0895362 0.837418 + outer loop + vertex 0.858325 1.68648 2.60345 + vertex 0.857388 1.68091 2.60344 + vertex 0.861152 1.68409 2.60553 + endloop + endfacet + facet normal -0.559698 0.0951969 0.82321 + outer loop + vertex 0.852306 1.68571 2.59955 + vertex 0.852537 1.69053 2.59915 + vertex 0.849468 1.68722 2.59744 + endloop + endfacet + facet normal -0.548067 0.0909804 0.831471 + outer loop + vertex 0.858325 1.68648 2.60345 + vertex 0.859264 1.69207 2.60346 + vertex 0.855532 1.68879 2.60136 + endloop + endfacet + facet normal -0.543637 0.0967108 0.83373 + outer loop + vertex 0.859264 1.69207 2.60346 + vertex 0.862086 1.69614 2.60483 + vertex 0.859149 1.6973 2.60278 + endloop + endfacet + facet normal -0.541697 0.102592 0.834289 + outer loop + vertex 0.862086 1.69614 2.60483 + vertex 0.862318 1.70062 2.60443 + vertex 0.859149 1.6973 2.60278 + endloop + endfacet + facet normal -0.542498 0.103683 0.833634 + outer loop + vertex 0.859149 1.6973 2.60278 + vertex 0.862318 1.70062 2.60443 + vertex 0.859411 1.70213 2.60235 + endloop + endfacet + facet normal -0.527935 0.102662 0.843057 + outer loop + vertex 0.862318 1.70062 2.60443 + vertex 0.862086 1.69614 2.60483 + vertex 0.865176 1.69891 2.60643 + endloop + endfacet + facet normal -0.527333 0.10393 0.843278 + outer loop + vertex 0.865667 1.70383 2.60613 + vertex 0.862318 1.70062 2.60443 + vertex 0.865176 1.69891 2.60643 + endloop + endfacet + facet normal -0.512691 0.103023 0.85237 + outer loop + vertex 0.865176 1.69891 2.60643 + vertex 0.869105 1.70192 2.60842 + vertex 0.865667 1.70383 2.60613 + endloop + endfacet + facet normal -0.513355 0.101556 0.852146 + outer loop + vertex 0.869105 1.70192 2.60842 + vertex 0.86908 1.70726 2.60777 + vertex 0.865667 1.70383 2.60613 + endloop + endfacet + facet normal -0.515562 0.104569 0.850448 + outer loop + vertex 0.865667 1.70383 2.60613 + vertex 0.86908 1.70726 2.60777 + vertex 0.865928 1.7089 2.60566 + endloop + endfacet + facet normal -0.529332 0.104499 0.841955 + outer loop + vertex 0.865928 1.7089 2.60566 + vertex 0.862576 1.70546 2.60398 + vertex 0.865667 1.70383 2.60613 + endloop + endfacet + facet normal -0.531506 0.107469 0.840209 + outer loop + vertex 0.862595 1.71079 2.60331 + vertex 0.862576 1.70546 2.60398 + vertex 0.865928 1.7089 2.60566 + endloop + endfacet + facet normal -0.532889 0.104411 0.839719 + outer loop + vertex 0.866473 1.71395 2.60538 + vertex 0.862595 1.71079 2.60331 + vertex 0.865928 1.7089 2.60566 + endloop + endfacet + facet normal -0.51605 0.103188 0.85032 + outer loop + vertex 0.865928 1.7089 2.60566 + vertex 0.869375 1.71224 2.60735 + vertex 0.866473 1.71395 2.60538 + endloop + endfacet + facet normal -0.515625 0.10408 0.850469 + outer loop + vertex 0.869375 1.71224 2.60735 + vertex 0.869762 1.71698 2.607 + vertex 0.866473 1.71395 2.60538 + endloop + endfacet + facet normal -0.513061 0.100208 0.852483 + outer loop + vertex 0.866473 1.71395 2.60538 + vertex 0.869762 1.71698 2.607 + vertex 0.867339 1.71791 2.60543 + endloop + endfacet + facet normal -0.532974 0.104753 0.839622 + outer loop + vertex 0.867339 1.71791 2.60543 + vertex 0.864054 1.71696 2.60347 + vertex 0.866473 1.71395 2.60538 + endloop + endfacet + facet normal -0.533566 0.108607 0.838756 + outer loop + vertex 0.867339 1.71791 2.60543 + vertex 0.867079 1.72126 2.60484 + vertex 0.864054 1.71696 2.60347 + endloop + endfacet + facet normal -0.517257 0.111616 0.84852 + outer loop + vertex 0.867339 1.71791 2.60543 + vertex 0.869513 1.7204 2.60643 + vertex 0.867079 1.72126 2.60484 + endloop + endfacet + facet normal -0.516339 0.114546 0.848689 + outer loop + vertex 0.870258 1.72423 2.60637 + vertex 0.867079 1.72126 2.60484 + vertex 0.869513 1.7204 2.60643 + endloop + endfacet + facet normal -0.49818 0.111202 0.859913 + outer loop + vertex 0.869513 1.7204 2.60643 + vertex 0.873275 1.72161 2.60846 + vertex 0.870258 1.72423 2.60637 + endloop + endfacet + facet normal -0.499119 0.109831 0.859545 + outer loop + vertex 0.873275 1.72161 2.60846 + vertex 0.873724 1.72735 2.60798 + vertex 0.870258 1.72423 2.60637 + endloop + endfacet + facet normal -0.499442 0.11032 0.859294 + outer loop + vertex 0.870258 1.72423 2.60637 + vertex 0.873724 1.72735 2.60798 + vertex 0.870676 1.729 2.606 + endloop + endfacet + facet normal -0.514775 0.110951 0.850116 + outer loop + vertex 0.870676 1.729 2.606 + vertex 0.867349 1.72575 2.60441 + vertex 0.870258 1.72423 2.60637 + endloop + endfacet + facet normal -0.514438 0.111729 0.850218 + outer loop + vertex 0.867349 1.72575 2.60441 + vertex 0.867079 1.72126 2.60484 + vertex 0.870258 1.72423 2.60637 + endloop + endfacet + facet normal -0.513542 0.109218 0.851085 + outer loop + vertex 0.867621 1.73056 2.60396 + vertex 0.867349 1.72575 2.60441 + vertex 0.870676 1.729 2.606 + endloop + endfacet + facet normal -0.515107 0.105507 0.850607 + outer loop + vertex 0.870997 1.73392 2.60558 + vertex 0.867621 1.73056 2.60396 + vertex 0.870676 1.729 2.606 + endloop + endfacet + facet normal -0.500653 0.105291 0.859221 + outer loop + vertex 0.870676 1.729 2.606 + vertex 0.8741 1.73226 2.60759 + vertex 0.870997 1.73392 2.60558 + endloop + endfacet + facet normal -0.50309 0.0997888 0.858454 + outer loop + vertex 0.8741 1.73226 2.60759 + vertex 0.874466 1.73712 2.60724 + vertex 0.870997 1.73392 2.60558 + endloop + endfacet + facet normal -0.50281 0.0993752 0.858666 + outer loop + vertex 0.870997 1.73392 2.60558 + vertex 0.874466 1.73712 2.60724 + vertex 0.871532 1.73885 2.60533 + endloop + endfacet + facet normal -0.516574 0.100432 0.850332 + outer loop + vertex 0.871532 1.73885 2.60533 + vertex 0.867631 1.73583 2.60331 + vertex 0.870997 1.73392 2.60558 + endloop + endfacet + facet normal -0.503664 0.0976016 0.858368 + outer loop + vertex 0.874466 1.73712 2.60724 + vertex 0.874829 1.74177 2.60693 + vertex 0.871532 1.73885 2.60533 + endloop + endfacet + facet normal -0.503701 0.097659 0.85834 + outer loop + vertex 0.871532 1.73885 2.60533 + vertex 0.874829 1.74177 2.60693 + vertex 0.872379 1.74273 2.60538 + endloop + endfacet + facet normal -0.518625 0.101057 0.849009 + outer loop + vertex 0.872379 1.74273 2.60538 + vertex 0.869064 1.7419 2.60345 + vertex 0.871532 1.73885 2.60533 + endloop + endfacet + facet normal -0.519839 0.110346 0.847108 + outer loop + vertex 0.872379 1.74273 2.60538 + vertex 0.872115 1.74609 2.60478 + vertex 0.869064 1.7419 2.60345 + endloop + endfacet + facet normal -0.490202 0.0993567 0.865927 + outer loop + vertex 0.8741 1.73226 2.60759 + vertex 0.877549 1.73555 2.60917 + vertex 0.874466 1.73712 2.60724 + endloop + endfacet + facet normal -0.491093 0.0972728 0.865659 + outer loop + vertex 0.877549 1.73555 2.60917 + vertex 0.877917 1.74055 2.60882 + vertex 0.874466 1.73712 2.60724 + endloop + endfacet + facet normal -0.514572 0.104768 0.851023 + outer loop + vertex 0.867631 1.73583 2.60331 + vertex 0.867621 1.73056 2.60396 + vertex 0.870997 1.73392 2.60558 + endloop + endfacet + facet normal -0.528387 0.103771 0.842638 + outer loop + vertex 0.864677 1.73169 2.60197 + vertex 0.867621 1.73056 2.60396 + vertex 0.867631 1.73583 2.60331 + endloop + endfacet + facet normal -0.5303 0.109194 0.840749 + outer loop + vertex 0.867349 1.72575 2.60441 + vertex 0.867621 1.73056 2.60396 + vertex 0.864396 1.72715 2.60236 + endloop + endfacet + facet normal -0.53031 0.109168 0.840746 + outer loop + vertex 0.864099 1.72228 2.60281 + vertex 0.867349 1.72575 2.60441 + vertex 0.864396 1.72715 2.60236 + endloop + endfacet + facet normal -0.532278 0.111746 0.839162 + outer loop + vertex 0.867079 1.72126 2.60484 + vertex 0.867349 1.72575 2.60441 + vertex 0.864099 1.72228 2.60281 + endloop + endfacet + facet normal -0.501302 0.106215 0.858728 + outer loop + vertex 0.873724 1.72735 2.60798 + vertex 0.8741 1.73226 2.60759 + vertex 0.870676 1.729 2.606 + endloop + endfacet + facet normal -0.497417 0.107227 0.860859 + outer loop + vertex 0.869513 1.7204 2.60643 + vertex 0.869762 1.71698 2.607 + vertex 0.873275 1.72161 2.60846 + endloop + endfacet + facet normal -0.498547 0.108334 0.860067 + outer loop + vertex 0.869762 1.71698 2.607 + vertex 0.872805 1.71574 2.60892 + vertex 0.873275 1.72161 2.60846 + endloop + endfacet + facet normal -0.511508 0.104872 0.852855 + outer loop + vertex 0.869513 1.7204 2.60643 + vertex 0.867339 1.71791 2.60543 + vertex 0.869762 1.71698 2.607 + endloop + endfacet + facet normal -0.500263 0.103493 0.859666 + outer loop + vertex 0.869375 1.71224 2.60735 + vertex 0.872805 1.71574 2.60892 + vertex 0.869762 1.71698 2.607 + endloop + endfacet + facet normal -0.53304 0.10468 0.83959 + outer loop + vertex 0.864054 1.71696 2.60347 + vertex 0.862595 1.71079 2.60331 + vertex 0.866473 1.71395 2.60538 + endloop + endfacet + facet normal -0.516115 0.103281 0.850269 + outer loop + vertex 0.86908 1.70726 2.60777 + vertex 0.869375 1.71224 2.60735 + vertex 0.865928 1.7089 2.60566 + endloop + endfacet + facet normal -0.50213 0.103166 0.858616 + outer loop + vertex 0.86908 1.70726 2.60777 + vertex 0.872419 1.7107 2.60931 + vertex 0.869375 1.71224 2.60735 + endloop + endfacet + facet normal -0.50257 0.103739 0.85829 + outer loop + vertex 0.872173 1.70609 2.60972 + vertex 0.872419 1.7107 2.60931 + vertex 0.86908 1.70726 2.60777 + endloop + endfacet + facet normal -0.511248 0.100353 0.853554 + outer loop + vertex 0.867669 1.69586 2.60828 + vertex 0.869105 1.70192 2.60842 + vertex 0.865176 1.69891 2.60643 + endloop + endfacet + facet normal -0.51213 0.0993806 0.853139 + outer loop + vertex 0.86438 1.6951 2.60639 + vertex 0.867669 1.69586 2.60828 + vertex 0.865176 1.69891 2.60643 + endloop + endfacet + facet normal -0.51144 0.0937739 0.854187 + outer loop + vertex 0.86438 1.6951 2.60639 + vertex 0.864698 1.69175 2.60695 + vertex 0.867669 1.69586 2.60828 + endloop + endfacet + facet normal -0.5247 0.0912147 0.846387 + outer loop + vertex 0.86438 1.6951 2.60639 + vertex 0.862398 1.69282 2.60541 + vertex 0.864698 1.69175 2.60695 + endloop + endfacet + facet normal -0.529983 0.0975262 0.842382 + outer loop + vertex 0.862398 1.69282 2.60541 + vertex 0.86438 1.6951 2.60639 + vertex 0.862086 1.69614 2.60483 + endloop + endfacet + facet normal -0.52871 0.105953 0.842164 + outer loop + vertex 0.862576 1.70546 2.60398 + vertex 0.862318 1.70062 2.60443 + vertex 0.865667 1.70383 2.60613 + endloop + endfacet + facet normal -0.528022 0.102799 0.842986 + outer loop + vertex 0.865176 1.69891 2.60643 + vertex 0.862086 1.69614 2.60483 + vertex 0.86438 1.6951 2.60639 + endloop + endfacet + facet normal -0.541949 0.0951083 0.835013 + outer loop + vertex 0.862398 1.69282 2.60541 + vertex 0.862086 1.69614 2.60483 + vertex 0.859264 1.69207 2.60346 + endloop + endfacet + facet normal -0.558107 0.0993677 0.823798 + outer loop + vertex 0.852417 1.69577 2.59843 + vertex 0.852537 1.69053 2.59915 + vertex 0.855824 1.69391 2.60097 + endloop + endfacet + facet normal -0.562311 0.105294 0.820195 + outer loop + vertex 0.852417 1.69577 2.59843 + vertex 0.853378 1.70136 2.59838 + vertex 0.850039 1.69878 2.59642 + endloop + endfacet + facet normal -0.560029 0.108644 0.821318 + outer loop + vertex 0.854385 1.70694 2.59832 + vertex 0.853378 1.70136 2.59838 + vertex 0.856733 1.70392 2.60032 + endloop + endfacet + facet normal -0.559222 0.109556 0.821747 + outer loop + vertex 0.857473 1.70764 2.60033 + vertex 0.854385 1.70694 2.59832 + vertex 0.856733 1.70392 2.60032 + endloop + endfacet + facet normal -0.559154 0.108857 0.821886 + outer loop + vertex 0.857473 1.70764 2.60033 + vertex 0.857205 1.71096 2.59971 + vertex 0.854385 1.70694 2.59832 + endloop + endfacet + facet normal -0.551733 0.103643 0.827556 + outer loop + vertex 0.859149 1.6973 2.60278 + vertex 0.859411 1.70213 2.60235 + vertex 0.856139 1.69904 2.60055 + endloop + endfacet + facet normal -0.553062 0.108322 0.826068 + outer loop + vertex 0.856733 1.70392 2.60032 + vertex 0.859682 1.70662 2.60195 + vertex 0.857473 1.70764 2.60033 + endloop + endfacet + facet normal -0.541583 0.105877 0.833953 + outer loop + vertex 0.862318 1.70062 2.60443 + vertex 0.862576 1.70546 2.60398 + vertex 0.859411 1.70213 2.60235 + endloop + endfacet + facet normal -0.553268 0.107775 0.826002 + outer loop + vertex 0.859417 1.70993 2.60134 + vertex 0.857473 1.70764 2.60033 + vertex 0.859682 1.70662 2.60195 + endloop + endfacet + facet normal -0.554875 0.109722 0.824666 + outer loop + vertex 0.857473 1.70764 2.60033 + vertex 0.859417 1.70993 2.60134 + vertex 0.857205 1.71096 2.59971 + endloop + endfacet + facet normal -0.560081 0.108381 0.821318 + outer loop + vertex 0.857205 1.71096 2.59971 + vertex 0.857465 1.71546 2.59929 + vertex 0.854349 1.71217 2.5976 + endloop + endfacet + facet normal -0.545382 0.107808 0.831226 + outer loop + vertex 0.862595 1.71079 2.60331 + vertex 0.864054 1.71696 2.60347 + vertex 0.860227 1.7138 2.60137 + endloop + endfacet + facet normal -0.533303 0.108359 0.838955 + outer loop + vertex 0.864054 1.71696 2.60347 + vertex 0.867079 1.72126 2.60484 + vertex 0.864099 1.72228 2.60281 + endloop + endfacet + facet normal -0.554524 0.108071 0.825121 + outer loop + vertex 0.857741 1.7203 2.59884 + vertex 0.857465 1.71546 2.59929 + vertex 0.860754 1.71876 2.60107 + endloop + endfacet + facet normal -0.544844 0.109201 0.831397 + outer loop + vertex 0.864099 1.72228 2.60281 + vertex 0.864396 1.72715 2.60236 + vertex 0.861051 1.72382 2.60061 + endloop + endfacet + facet normal -0.527721 0.105788 0.842805 + outer loop + vertex 0.864396 1.72715 2.60236 + vertex 0.867621 1.73056 2.60396 + vertex 0.864677 1.73169 2.60197 + endloop + endfacet + facet normal -0.552057 0.100501 0.827727 + outer loop + vertex 0.859196 1.73185 2.59834 + vertex 0.86213 1.73604 2.59979 + vertex 0.859226 1.7372 2.59771 + endloop + endfacet + facet normal -0.539783 0.101166 0.835703 + outer loop + vertex 0.864406 1.73504 2.60139 + vertex 0.862405 1.7327 2.60038 + vertex 0.864677 1.73169 2.60197 + endloop + endfacet + facet normal -0.539415 0.104143 0.835575 + outer loop + vertex 0.862379 1.74053 2.59939 + vertex 0.86213 1.73604 2.59979 + vertex 0.865201 1.73886 2.60142 + endloop + endfacet + facet normal -0.527974 0.103377 0.842945 + outer loop + vertex 0.864406 1.73504 2.60139 + vertex 0.864677 1.73169 2.60197 + vertex 0.867631 1.73583 2.60331 + endloop + endfacet + facet normal -0.517553 0.102239 0.849521 + outer loop + vertex 0.869064 1.7419 2.60345 + vertex 0.867631 1.73583 2.60331 + vertex 0.871532 1.73885 2.60533 + endloop + endfacet + facet normal -0.523949 0.114313 0.844044 + outer loop + vertex 0.869064 1.7419 2.60345 + vertex 0.872115 1.74609 2.60478 + vertex 0.869111 1.74719 2.60277 + endloop + endfacet + facet normal -0.544178 0.134083 0.828186 + outer loop + vertex 0.862763 1.75061 2.59812 + vertex 0.862658 1.74534 2.59891 + vertex 0.866043 1.74878 2.60057 + endloop + endfacet + facet normal -0.536755 0.109849 0.836557 + outer loop + vertex 0.865711 1.74377 2.6011 + vertex 0.862379 1.74053 2.59939 + vertex 0.865201 1.73886 2.60142 + endloop + endfacet + facet normal -0.550863 0.104109 0.828077 + outer loop + vertex 0.86213 1.73604 2.59979 + vertex 0.862379 1.74053 2.59939 + vertex 0.859226 1.7372 2.59771 + endloop + endfacet + facet normal -0.578389 0.108659 0.808492 + outer loop + vertex 0.853645 1.74129 2.59327 + vertex 0.85303 1.7362 2.59351 + vertex 0.856337 1.73901 2.5955 + endloop + endfacet + facet normal -0.563773 0.0996475 0.819897 + outer loop + vertex 0.859196 1.73185 2.59834 + vertex 0.859226 1.7372 2.59771 + vertex 0.855888 1.73393 2.59582 + endloop + endfacet + facet normal -0.55323 0.102999 0.826636 + outer loop + vertex 0.859196 1.73185 2.59834 + vertex 0.857764 1.72564 2.59816 + vertex 0.861587 1.72881 2.60032 + endloop + endfacet + facet normal -0.561678 0.107862 0.820294 + outer loop + vertex 0.854877 1.7214 2.59674 + vertex 0.857741 1.7203 2.59884 + vertex 0.857764 1.72564 2.59816 + endloop + endfacet + facet normal -0.570008 0.111654 0.814017 + outer loop + vertex 0.852675 1.72242 2.59507 + vertex 0.854586 1.72475 2.59609 + vertex 0.852334 1.7258 2.59437 + endloop + endfacet + facet normal -0.566134 0.109059 0.817067 + outer loop + vertex 0.854625 1.71695 2.59716 + vertex 0.854877 1.7214 2.59674 + vertex 0.851989 1.71873 2.59509 + endloop + endfacet + facet normal -0.572832 0.110977 0.812125 + outer loop + vertex 0.852675 1.72242 2.59507 + vertex 0.852334 1.7258 2.59437 + vertex 0.849697 1.72174 2.59306 + endloop + endfacet + facet normal -0.569288 0.11091 0.814623 + outer loop + vertex 0.851989 1.71873 2.59509 + vertex 0.848756 1.7163 2.59317 + vertex 0.851464 1.71401 2.59537 + endloop + endfacet + facet normal -0.574391 0.112781 0.810775 + outer loop + vertex 0.848124 1.71124 2.59342 + vertex 0.848756 1.7163 2.59317 + vertex 0.845373 1.71357 2.59115 + endloop + endfacet + facet normal -0.584656 0.113608 0.803288 + outer loop + vertex 0.845373 1.71357 2.59115 + vertex 0.842258 1.71057 2.58931 + vertex 0.844888 1.70878 2.59147 + endloop + endfacet + facet normal -0.59975 0.108292 0.792826 + outer loop + vertex 0.83942 1.70722 2.58762 + vertex 0.842258 1.71057 2.58931 + vertex 0.839576 1.71174 2.58712 + endloop + endfacet + facet normal -0.616183 0.107469 0.780236 + outer loop + vertex 0.83942 1.70722 2.58762 + vertex 0.839576 1.71174 2.58712 + vertex 0.836866 1.70895 2.58536 + endloop + endfacet + facet normal -0.632082 0.108148 0.767317 + outer loop + vertex 0.834687 1.7119 2.58315 + vertex 0.833849 1.70628 2.58325 + vertex 0.836866 1.70895 2.58536 + endloop + endfacet + facet normal -0.618558 0.117056 0.776971 + outer loop + vertex 0.837492 1.71276 2.58534 + vertex 0.839279 1.71506 2.58641 + vertex 0.837158 1.71606 2.58457 + endloop + endfacet + facet normal -0.640462 0.111082 0.759914 + outer loop + vertex 0.834687 1.7119 2.58315 + vertex 0.834555 1.71679 2.58233 + vertex 0.831873 1.71387 2.58049 + endloop + endfacet + facet normal -0.648046 0.11153 0.75339 + outer loop + vertex 0.829681 1.71691 2.57816 + vertex 0.828816 1.71119 2.57826 + vertex 0.831873 1.71387 2.58049 + endloop + endfacet + facet normal -0.64049 0.110883 0.75992 + outer loop + vertex 0.832465 1.71779 2.58042 + vertex 0.834196 1.7201 2.58154 + vertex 0.832109 1.72109 2.57964 + endloop + endfacet + facet normal -0.656478 0.103297 0.747239 + outer loop + vertex 0.827517 1.72286 2.5754 + vertex 0.82921 1.72517 2.57657 + vertex 0.827181 1.72615 2.57465 + endloop + endfacet + facet normal -0.655832 0.108407 0.747083 + outer loop + vertex 0.829681 1.71691 2.57816 + vertex 0.829556 1.72184 2.57733 + vertex 0.826909 1.71891 2.57543 + endloop + endfacet + facet normal -0.659309 0.102465 0.744857 + outer loop + vertex 0.827517 1.72286 2.5754 + vertex 0.827181 1.72615 2.57465 + vertex 0.824786 1.72195 2.57311 + endloop + endfacet + facet normal -0.661648 0.112052 0.741395 + outer loop + vertex 0.826909 1.71891 2.57543 + vertex 0.823879 1.71619 2.57314 + vertex 0.826327 1.71367 2.5757 + endloop + endfacet + facet normal -0.670177 0.112132 0.733682 + outer loop + vertex 0.823304 1.71086 2.57343 + vertex 0.823879 1.71619 2.57314 + vertex 0.820889 1.71336 2.57084 + endloop + endfacet + facet normal -0.671387 0.110136 0.732878 + outer loop + vertex 0.820485 1.70835 2.57122 + vertex 0.823304 1.71086 2.57343 + vertex 0.820889 1.71336 2.57084 + endloop + endfacet + facet normal -0.675691 0.105273 0.72963 + outer loop + vertex 0.819124 1.72119 2.56804 + vertex 0.818518 1.71591 2.56825 + vertex 0.821484 1.71871 2.57059 + endloop + endfacet + facet normal -0.675299 0.105921 0.729898 + outer loop + vertex 0.822099 1.72386 2.57041 + vertex 0.819124 1.72119 2.56804 + vertex 0.821484 1.71871 2.57059 + endloop + endfacet + facet normal -0.680482 0.110221 0.724428 + outer loop + vertex 0.820889 1.71336 2.57084 + vertex 0.81812 1.71076 2.56864 + vertex 0.820485 1.70835 2.57122 + endloop + endfacet + facet normal -0.674926 0.105092 0.730364 + outer loop + vertex 0.819911 1.72669 2.56798 + vertex 0.819124 1.72119 2.56804 + vertex 0.822099 1.72386 2.57041 + endloop + endfacet + facet normal -0.680929 0.113392 0.723517 + outer loop + vertex 0.819911 1.72669 2.56798 + vertex 0.822276 1.73084 2.56956 + vertex 0.819438 1.73152 2.56678 + endloop + endfacet + facet normal -0.70048 0.132773 0.701212 + outer loop + vertex 0.813811 1.73448 2.56071 + vertex 0.814169 1.73019 2.56188 + vertex 0.816515 1.73281 2.56373 + endloop + endfacet + facet normal -0.69166 0.109294 0.713906 + outer loop + vertex 0.816869 1.72834 2.56484 + vertex 0.814225 1.72572 2.56268 + vertex 0.816724 1.72356 2.56543 + endloop + endfacet + facet normal -0.701036 0.105903 0.705218 + outer loop + vertex 0.813904 1.72097 2.56307 + vertex 0.814225 1.72572 2.56268 + vertex 0.811587 1.72338 2.56041 + endloop + endfacet + facet normal -0.694295 0.10168 0.712471 + outer loop + vertex 0.813904 1.72097 2.56307 + vertex 0.813417 1.71596 2.56331 + vertex 0.8162 1.71848 2.56566 + endloop + endfacet + facet normal -0.703607 0.101893 0.703246 + outer loop + vertex 0.813078 1.71085 2.56371 + vertex 0.813417 1.71596 2.56331 + vertex 0.810721 1.71351 2.56097 + endloop + endfacet + facet normal -0.697936 0.103174 0.708689 + outer loop + vertex 0.813078 1.71085 2.56371 + vertex 0.813092 1.70595 2.56444 + vertex 0.815563 1.70822 2.56654 + endloop + endfacet + facet normal -0.690885 0.106717 0.715045 + outer loop + vertex 0.817997 1.70612 2.56921 + vertex 0.81812 1.71076 2.56864 + vertex 0.815563 1.70822 2.56654 + endloop + endfacet + facet normal -0.682063 0.107509 0.723347 + outer loop + vertex 0.81812 1.71076 2.56864 + vertex 0.817997 1.70612 2.56921 + vertex 0.820485 1.70835 2.57122 + endloop + endfacet + facet normal -0.671328 0.110006 0.732951 + outer loop + vertex 0.822805 1.70585 2.57372 + vertex 0.823304 1.71086 2.57343 + vertex 0.820485 1.70835 2.57122 + endloop + endfacet + facet normal -0.666059 0.103815 0.738639 + outer loop + vertex 0.822805 1.70585 2.57372 + vertex 0.821961 1.70074 2.57368 + vertex 0.825261 1.70339 2.57628 + endloop + endfacet + facet normal -0.677686 0.103848 0.727982 + outer loop + vertex 0.818691 1.70087 2.57062 + vertex 0.819433 1.69681 2.57189 + vertex 0.821961 1.70074 2.57368 + endloop + endfacet + facet normal -0.686536 0.0998031 0.720214 + outer loop + vertex 0.818691 1.70087 2.57062 + vertex 0.816486 1.69819 2.56889 + vertex 0.819433 1.69681 2.57189 + endloop + endfacet + facet normal -0.696623 0.103993 0.70986 + outer loop + vertex 0.81584 1.70303 2.56757 + vertex 0.813287 1.70286 2.56509 + vertex 0.813646 1.69997 2.56586 + endloop + endfacet + facet normal -0.69123 0.1035 0.715184 + outer loop + vertex 0.816486 1.69819 2.56889 + vertex 0.814105 1.69558 2.56696 + vertex 0.816875 1.69362 2.56993 + endloop + endfacet + facet normal -0.69978 0.107356 0.706245 + outer loop + vertex 0.810794 1.70295 2.56258 + vertex 0.811345 1.69785 2.56391 + vertex 0.813646 1.69997 2.56586 + endloop + endfacet + facet normal -0.706839 0.104862 0.699559 + outer loop + vertex 0.810794 1.70295 2.56258 + vertex 0.808632 1.69996 2.56085 + vertex 0.811345 1.69785 2.56391 + endloop + endfacet + facet normal -0.704752 0.109554 0.700944 + outer loop + vertex 0.808632 1.69996 2.56085 + vertex 0.809062 1.69552 2.56197 + vertex 0.811345 1.69785 2.56391 + endloop + endfacet + facet normal -0.69529 0.107086 0.710707 + outer loop + vertex 0.814195 1.69095 2.56775 + vertex 0.814105 1.69558 2.56696 + vertex 0.811652 1.69324 2.56492 + endloop + endfacet + facet normal -0.687522 0.107112 0.718221 + outer loop + vertex 0.814195 1.69095 2.56775 + vertex 0.813843 1.68606 2.56814 + vertex 0.8167 1.68869 2.57048 + endloop + endfacet + facet normal -0.693873 0.103835 0.712572 + outer loop + vertex 0.813323 1.68098 2.56838 + vertex 0.813843 1.68606 2.56814 + vertex 0.811073 1.6836 2.5658 + endloop + endfacet + facet normal -0.68789 0.0989427 0.719039 + outer loop + vertex 0.813323 1.68098 2.56838 + vertex 0.812991 1.67585 2.56876 + vertex 0.81567 1.67831 2.57099 + endloop + endfacet + facet normal -0.694733 0.0940839 0.713088 + outer loop + vertex 0.813042 1.67094 2.56946 + vertex 0.812991 1.67585 2.56876 + vertex 0.810445 1.67341 2.56661 + endloop + endfacet + facet normal -0.687146 0.0951815 0.720257 + outer loop + vertex 0.812991 1.67585 2.56876 + vertex 0.813042 1.67094 2.56946 + vertex 0.81553 1.67319 2.57154 + endloop + endfacet + facet normal -0.679611 0.094745 0.727428 + outer loop + vertex 0.818023 1.67103 2.57415 + vertex 0.818111 1.67575 2.57362 + vertex 0.81553 1.67319 2.57154 + endloop + endfacet + facet normal -0.671691 0.093879 0.734859 + outer loop + vertex 0.818023 1.67103 2.57415 + vertex 0.8182 1.66819 2.57467 + vertex 0.820114 1.66891 2.57633 + endloop + endfacet + facet normal -0.671158 0.0903563 0.735787 + outer loop + vertex 0.820114 1.66891 2.57633 + vertex 0.8182 1.66819 2.57467 + vertex 0.818774 1.6657 2.5755 + endloop + endfacet + facet normal -0.674387 0.0892867 0.73296 + outer loop + vertex 0.818774 1.6657 2.5755 + vertex 0.816555 1.66306 2.57378 + vertex 0.819568 1.66158 2.57673 + endloop + endfacet + facet normal -0.684011 0.0925548 0.723576 + outer loop + vertex 0.815858 1.66794 2.57252 + vertex 0.813268 1.66784 2.57008 + vertex 0.813661 1.66495 2.57082 + endloop + endfacet + facet normal -0.679591 0.0902216 0.728022 + outer loop + vertex 0.816555 1.66306 2.57378 + vertex 0.814175 1.66055 2.57187 + vertex 0.817016 1.65848 2.57478 + endloop + endfacet + facet normal -0.690659 0.0946927 0.716954 + outer loop + vertex 0.810756 1.66801 2.56762 + vertex 0.811362 1.66292 2.56888 + vertex 0.813661 1.66495 2.57082 + endloop + endfacet + facet normal -0.699357 0.0916633 0.70887 + outer loop + vertex 0.810756 1.66801 2.56762 + vertex 0.808614 1.66512 2.56588 + vertex 0.811362 1.66292 2.56888 + endloop + endfacet + facet normal -0.69831 0.0939676 0.709601 + outer loop + vertex 0.808614 1.66512 2.56588 + vertex 0.809093 1.66066 2.56694 + vertex 0.811362 1.66292 2.56888 + endloop + endfacet + facet normal -0.706813 0.0886648 0.701822 + outer loop + vertex 0.809259 1.656 2.5677 + vertex 0.809093 1.66066 2.56694 + vertex 0.806752 1.65839 2.56487 + endloop + endfacet + facet normal -0.707579 0.0871731 0.701237 + outer loop + vertex 0.806705 1.6536 2.56542 + vertex 0.809259 1.656 2.5677 + vertex 0.806752 1.65839 2.56487 + endloop + endfacet + facet normal -0.71695 0.0861846 0.691777 + outer loop + vertex 0.806752 1.65839 2.56487 + vertex 0.804228 1.65608 2.56254 + vertex 0.806705 1.6536 2.56542 + endloop + endfacet + facet normal -0.717003 0.0860822 0.691734 + outer loop + vertex 0.804228 1.65608 2.56254 + vertex 0.804082 1.65109 2.56301 + vertex 0.806705 1.6536 2.56542 + endloop + endfacet + facet normal -0.715105 0.0817017 0.694226 + outer loop + vertex 0.806705 1.6536 2.56542 + vertex 0.804082 1.65109 2.56301 + vertex 0.806448 1.64865 2.56574 + endloop + endfacet + facet normal -0.707469 0.0818039 0.701994 + outer loop + vertex 0.806448 1.64865 2.56574 + vertex 0.809099 1.65115 2.56812 + vertex 0.806705 1.6536 2.56542 + endloop + endfacet + facet normal -0.706229 0.0840928 0.702971 + outer loop + vertex 0.809099 1.65115 2.56812 + vertex 0.809259 1.656 2.5677 + vertex 0.806705 1.6536 2.56542 + endloop + endfacet + facet normal -0.707973 0.0912359 0.700321 + outer loop + vertex 0.806752 1.65839 2.56487 + vertex 0.809093 1.66066 2.56694 + vertex 0.806528 1.66295 2.56405 + endloop + endfacet + facet normal -0.71804 0.0889347 0.690297 + outer loop + vertex 0.806528 1.66295 2.56405 + vertex 0.804335 1.6608 2.56205 + vertex 0.806752 1.65839 2.56487 + endloop + endfacet + facet normal -0.686197 0.0898935 0.72184 + outer loop + vertex 0.814353 1.65591 2.57262 + vertex 0.814175 1.66055 2.57187 + vertex 0.811736 1.65829 2.56983 + endloop + endfacet + facet normal -0.678246 0.0862472 0.729756 + outer loop + vertex 0.814353 1.65591 2.57262 + vertex 0.814149 1.65106 2.573 + vertex 0.816954 1.65362 2.57531 + endloop + endfacet + facet normal -0.697229 0.0845648 0.711844 + outer loop + vertex 0.809259 1.656 2.5677 + vertex 0.809099 1.65115 2.56812 + vertex 0.811728 1.65355 2.57041 + endloop + endfacet + facet normal -0.706214 0.0789513 0.703583 + outer loop + vertex 0.80876 1.64618 2.56834 + vertex 0.809099 1.65115 2.56812 + vertex 0.806448 1.64865 2.56574 + endloop + endfacet + facet normal -0.70757 0.0765273 0.702487 + outer loop + vertex 0.806086 1.64368 2.56592 + vertex 0.80876 1.64618 2.56834 + vertex 0.806448 1.64865 2.56574 + endloop + endfacet + facet normal -0.713849 0.0767545 0.696081 + outer loop + vertex 0.806448 1.64865 2.56574 + vertex 0.803791 1.64611 2.56329 + vertex 0.806086 1.64368 2.56592 + endloop + endfacet + facet normal -0.714162 0.0761816 0.695823 + outer loop + vertex 0.803791 1.64611 2.56329 + vertex 0.803438 1.64116 2.56347 + vertex 0.806086 1.64368 2.56592 + endloop + endfacet + facet normal -0.71285 0.073185 0.697487 + outer loop + vertex 0.806086 1.64368 2.56592 + vertex 0.803438 1.64116 2.56347 + vertex 0.805716 1.63868 2.56606 + endloop + endfacet + facet normal -0.706659 0.0729098 0.703788 + outer loop + vertex 0.805716 1.63868 2.56606 + vertex 0.808383 1.64117 2.56848 + vertex 0.806086 1.64368 2.56592 + endloop + endfacet + facet normal -0.712413 0.0739664 0.697851 + outer loop + vertex 0.803438 1.64116 2.56347 + vertex 0.803096 1.63619 2.56365 + vertex 0.805716 1.63868 2.56606 + endloop + endfacet + facet normal -0.711152 0.0711034 0.699433 + outer loop + vertex 0.805716 1.63868 2.56606 + vertex 0.803096 1.63619 2.56365 + vertex 0.805434 1.63362 2.56629 + endloop + endfacet + facet normal -0.705563 0.0710464 0.705077 + outer loop + vertex 0.805434 1.63362 2.56629 + vertex 0.808057 1.63611 2.56866 + vertex 0.805716 1.63868 2.56606 + endloop + endfacet + facet normal -0.704774 0.0692964 0.70604 + outer loop + vertex 0.807892 1.63099 2.569 + vertex 0.808057 1.63611 2.56866 + vertex 0.805434 1.63362 2.56629 + endloop + endfacet + facet normal -0.704363 0.0700283 0.706377 + outer loop + vertex 0.805404 1.62845 2.56677 + vertex 0.807892 1.63099 2.569 + vertex 0.805434 1.63362 2.56629 + endloop + endfacet + facet normal -0.710088 0.0695293 0.700671 + outer loop + vertex 0.805434 1.63362 2.56629 + vertex 0.802883 1.63114 2.56395 + vertex 0.805404 1.62845 2.56677 + endloop + endfacet + facet normal -0.71096 0.0714423 0.699594 + outer loop + vertex 0.803096 1.63619 2.56365 + vertex 0.802883 1.63114 2.56395 + vertex 0.805434 1.63362 2.56629 + endloop + endfacet + facet normal -0.723055 0.0712092 0.687111 + outer loop + vertex 0.802883 1.63114 2.56395 + vertex 0.803096 1.63619 2.56365 + vertex 0.800568 1.63366 2.56125 + endloop + endfacet + facet normal -0.72371 0.0700015 0.686544 + outer loop + vertex 0.800421 1.62855 2.56162 + vertex 0.802883 1.63114 2.56395 + vertex 0.800568 1.63366 2.56125 + endloop + endfacet + facet normal -0.74931 0.0687454 0.658641 + outer loop + vertex 0.800568 1.63366 2.56125 + vertex 0.79817 1.63109 2.55879 + vertex 0.800421 1.62855 2.56162 + endloop + endfacet + facet normal -0.750783 0.0658986 0.657253 + outer loop + vertex 0.79817 1.63109 2.55879 + vertex 0.798028 1.62597 2.55914 + vertex 0.800421 1.62855 2.56162 + endloop + endfacet + facet normal -0.749949 0.0640354 0.658389 + outer loop + vertex 0.800421 1.62855 2.56162 + vertex 0.798028 1.62597 2.55914 + vertex 0.800573 1.62299 2.56233 + endloop + endfacet + facet normal -0.74831 0.0671051 0.659946 + outer loop + vertex 0.798028 1.62597 2.55914 + vertex 0.797933 1.62094 2.55955 + vertex 0.800573 1.62299 2.56233 + endloop + endfacet + facet normal -0.749037 0.0681331 0.659015 + outer loop + vertex 0.798423 1.63606 2.55857 + vertex 0.79817 1.63109 2.55879 + vertex 0.800568 1.63366 2.56125 + endloop + endfacet + facet normal -0.746651 0.0727491 0.661226 + outer loop + vertex 0.80086 1.63863 2.56104 + vertex 0.798423 1.63606 2.55857 + vertex 0.800568 1.63366 2.56125 + endloop + endfacet + facet normal -0.746486 0.0723735 0.661454 + outer loop + vertex 0.798696 1.64096 2.55834 + vertex 0.798423 1.63606 2.55857 + vertex 0.80086 1.63863 2.56104 + endloop + endfacet + facet normal -0.722867 0.0682433 0.687609 + outer loop + vertex 0.802943 1.62605 2.56452 + vertex 0.802883 1.63114 2.56395 + vertex 0.800421 1.62855 2.56162 + endloop + endfacet + facet normal -0.723636 0.0724967 0.686364 + outer loop + vertex 0.800568 1.63366 2.56125 + vertex 0.803096 1.63619 2.56365 + vertex 0.80086 1.63863 2.56104 + endloop + endfacet + facet normal -0.722659 0.0742952 0.6872 + outer loop + vertex 0.803096 1.63619 2.56365 + vertex 0.803438 1.64116 2.56347 + vertex 0.80086 1.63863 2.56104 + endloop + endfacet + facet normal -0.723337 0.0758338 0.686318 + outer loop + vertex 0.80086 1.63863 2.56104 + vertex 0.803438 1.64116 2.56347 + vertex 0.801175 1.64355 2.56082 + endloop + endfacet + facet normal -0.706274 0.0735853 0.704103 + outer loop + vertex 0.808383 1.64117 2.56848 + vertex 0.80876 1.64618 2.56834 + vertex 0.806086 1.64368 2.56592 + endloop + endfacet + facet normal -0.687051 0.0805998 0.722125 + outer loop + vertex 0.813776 1.6461 2.5732 + vertex 0.814149 1.65106 2.573 + vertex 0.811443 1.64864 2.5707 + endloop + endfacet + facet normal -0.680429 0.0746302 0.729004 + outer loop + vertex 0.813776 1.6461 2.5732 + vertex 0.813429 1.64108 2.57339 + vertex 0.816154 1.64354 2.57568 + endloop + endfacet + facet normal -0.699306 0.0732627 0.711058 + outer loop + vertex 0.80876 1.64618 2.56834 + vertex 0.808383 1.64117 2.56848 + vertex 0.81107 1.64365 2.57087 + endloop + endfacet + facet normal -0.705718 0.0707751 0.704949 + outer loop + vertex 0.808057 1.63611 2.56866 + vertex 0.808383 1.64117 2.56848 + vertex 0.805716 1.63868 2.56606 + endloop + endfacet + facet normal -0.690771 0.0715292 0.719527 + outer loop + vertex 0.813157 1.63602 2.57363 + vertex 0.813429 1.64108 2.57339 + vertex 0.81073 1.63861 2.57105 + endloop + endfacet + facet normal -0.699354 0.0694749 0.711391 + outer loop + vertex 0.808057 1.63611 2.56866 + vertex 0.807892 1.63099 2.569 + vertex 0.810489 1.6335 2.57131 + endloop + endfacet + facet normal -0.692437 0.0697593 0.718098 + outer loop + vertex 0.81294 1.62627 2.57437 + vertex 0.812983 1.63097 2.57396 + vertex 0.810453 1.62838 2.57177 + endloop + endfacet + facet normal -0.685795 0.0620108 0.725148 + outer loop + vertex 0.813702 1.62087 2.5756 + vertex 0.811541 1.61817 2.57378 + vertex 0.814546 1.61673 2.57675 + endloop + endfacet + facet normal -0.675235 0.0612338 0.735056 + outer loop + vertex 0.815185 1.6118 2.57774 + vertex 0.817428 1.61591 2.57946 + vertex 0.814546 1.61673 2.57675 + endloop + endfacet + facet normal -0.679381 0.0552275 0.731704 + outer loop + vertex 0.814636 1.60636 2.57765 + vertex 0.815185 1.6118 2.57774 + vertex 0.812117 1.6087 2.57513 + endloop + endfacet + facet normal -0.668075 0.0512127 0.742329 + outer loop + vertex 0.814636 1.60636 2.57765 + vertex 0.8143 1.60121 2.5777 + vertex 0.817178 1.60408 2.58009 + endloop + endfacet + facet normal -0.67767 0.050011 0.733664 + outer loop + vertex 0.814059 1.59608 2.57783 + vertex 0.8143 1.60121 2.5777 + vertex 0.811559 1.59861 2.57534 + endloop + endfacet + facet normal -0.669214 0.0481655 0.741507 + outer loop + vertex 0.814059 1.59608 2.57783 + vertex 0.813892 1.59104 2.578 + vertex 0.816626 1.59357 2.58031 + endloop + endfacet + facet normal -0.677948 0.0451161 0.733724 + outer loop + vertex 0.81376 1.58608 2.57819 + vertex 0.813892 1.59104 2.578 + vertex 0.811238 1.58864 2.5757 + endloop + endfacet + facet normal -0.669394 0.0420234 0.741718 + outer loop + vertex 0.81376 1.58608 2.57819 + vertex 0.813623 1.58114 2.57834 + vertex 0.816321 1.58356 2.58064 + endloop + endfacet + facet normal -0.675784 0.0379234 0.736124 + outer loop + vertex 0.813486 1.57619 2.57847 + vertex 0.813623 1.58114 2.57834 + vertex 0.810958 1.57872 2.57602 + endloop + endfacet + facet normal -0.667182 0.0339558 0.74412 + outer loop + vertex 0.813486 1.57619 2.57847 + vertex 0.813365 1.57122 2.57859 + vertex 0.816054 1.57363 2.58089 + endloop + endfacet + facet normal -0.673666 0.0308749 0.738391 + outer loop + vertex 0.813258 1.56625 2.5787 + vertex 0.813365 1.57122 2.57859 + vertex 0.810701 1.56875 2.57626 + endloop + endfacet + facet normal -0.666185 0.0294702 0.745204 + outer loop + vertex 0.813258 1.56625 2.5787 + vertex 0.813155 1.56126 2.5788 + vertex 0.815842 1.56371 2.58111 + endloop + endfacet + facet normal -0.675486 0.0283922 0.736826 + outer loop + vertex 0.813051 1.55627 2.5789 + vertex 0.813155 1.56126 2.5788 + vertex 0.810496 1.55875 2.57646 + endloop + endfacet + facet normal -0.667913 0.0271533 0.743744 + outer loop + vertex 0.813051 1.55627 2.5789 + vertex 0.812949 1.55127 2.57899 + vertex 0.815629 1.55377 2.58131 + endloop + endfacet + facet normal -0.676285 0.0240904 0.736246 + outer loop + vertex 0.812858 1.54627 2.57907 + vertex 0.812949 1.55127 2.57899 + vertex 0.8103 1.54875 2.57664 + endloop + endfacet + facet normal -0.666054 0.0203667 0.745625 + outer loop + vertex 0.812858 1.54627 2.57907 + vertex 0.812785 1.54127 2.57914 + vertex 0.815455 1.5438 2.58146 + endloop + endfacet + facet normal -0.673392 0.0169272 0.739092 + outer loop + vertex 0.81273 1.53627 2.57921 + vertex 0.812785 1.54127 2.57914 + vertex 0.810148 1.53874 2.5768 + endloop + endfacet + facet normal -0.663248 0.0135562 0.748277 + outer loop + vertex 0.81273 1.53627 2.57921 + vertex 0.812684 1.53129 2.57926 + vertex 0.815348 1.53381 2.58157 + endloop + endfacet + facet normal -0.672197 0.0103714 0.740299 + outer loop + vertex 0.812635 1.52632 2.57928 + vertex 0.812684 1.53129 2.57926 + vertex 0.810033 1.52879 2.57688 + endloop + endfacet + facet normal -0.663962 0.0067747 0.747735 + outer loop + vertex 0.812635 1.52632 2.57928 + vertex 0.812606 1.52133 2.5793 + vertex 0.81527 1.52384 2.58165 + endloop + endfacet + facet normal -0.665003 0.00342319 0.746833 + outer loop + vertex 0.812606 1.52133 2.5793 + vertex 0.812624 1.51636 2.57934 + vertex 0.815248 1.51886 2.58167 + endloop + endfacet + facet normal -0.674594 -0.000208427 0.738189 + outer loop + vertex 0.812638 1.51141 2.57935 + vertex 0.812624 1.51636 2.57934 + vertex 0.810129 1.51387 2.57706 + endloop + endfacet + facet normal -0.665962 -0.00343799 0.745978 + outer loop + vertex 0.812638 1.51141 2.57935 + vertex 0.812622 1.50641 2.57931 + vertex 0.815246 1.50885 2.58167 + endloop + endfacet + facet normal -0.687088 -0.00662213 0.726544 + outer loop + vertex 0.808026 1.51161 2.57508 + vertex 0.807158 1.50713 2.57422 + vertex 0.810075 1.5091 2.57699 + endloop + endfacet + facet normal -0.676305 -0.00502988 0.736605 + outer loop + vertex 0.812633 1.50135 2.57929 + vertex 0.812622 1.50641 2.57931 + vertex 0.809977 1.50405 2.57687 + endloop + endfacet + facet normal -0.665506 -0.00717454 0.746358 + outer loop + vertex 0.812633 1.50135 2.57929 + vertex 0.812679 1.49631 2.57928 + vertex 0.815294 1.49882 2.58164 + endloop + endfacet + facet normal -0.665587 -0.0108117 0.746242 + outer loop + vertex 0.812679 1.49631 2.57928 + vertex 0.812729 1.49132 2.57926 + vertex 0.815334 1.49384 2.58161 + endloop + endfacet + facet normal -0.688151 -0.0114496 0.725477 + outer loop + vertex 0.807518 1.49634 2.57447 + vertex 0.807588 1.4913 2.57446 + vertex 0.81011 1.49381 2.57689 + endloop + endfacet + facet normal -0.675915 -0.0152004 0.736823 + outer loop + vertex 0.812785 1.48635 2.5792 + vertex 0.812729 1.49132 2.57926 + vertex 0.810168 1.48881 2.57685 + endloop + endfacet + facet normal -0.667278 -0.0190313 0.744565 + outer loop + vertex 0.812785 1.48635 2.5792 + vertex 0.812856 1.48137 2.57914 + vertex 0.815442 1.48389 2.58152 + endloop + endfacet + facet normal -0.688652 -0.0209093 0.724791 + outer loop + vertex 0.807651 1.48632 2.57441 + vertex 0.807723 1.48134 2.57433 + vertex 0.810234 1.48384 2.57679 + endloop + endfacet + facet normal -0.678222 -0.0223612 0.734517 + outer loop + vertex 0.812942 1.47638 2.57907 + vertex 0.812856 1.48137 2.57914 + vertex 0.810313 1.47886 2.57672 + endloop + endfacet + facet normal -0.66863 -0.0254533 0.74316 + outer loop + vertex 0.812942 1.47638 2.57907 + vertex 0.813041 1.47138 2.57899 + vertex 0.815613 1.4739 2.58139 + endloop + endfacet + facet normal -0.677935 -0.0297876 0.734518 + outer loop + vertex 0.813157 1.46639 2.57889 + vertex 0.813041 1.47138 2.57899 + vertex 0.810508 1.46888 2.57655 + endloop + endfacet + facet normal -0.667847 -0.0332864 0.743554 + outer loop + vertex 0.813157 1.46639 2.57889 + vertex 0.813285 1.4614 2.57878 + vertex 0.815855 1.46388 2.5812 + endloop + endfacet + facet normal -0.677429 -0.035622 0.734725 + outer loop + vertex 0.81342 1.45641 2.57866 + vertex 0.813285 1.4614 2.57878 + vertex 0.810755 1.45891 2.57633 + endloop + endfacet + facet normal -0.677181 -0.036747 0.734899 + outer loop + vertex 0.813702 1.44641 2.57843 + vertex 0.813558 1.45141 2.57855 + vertex 0.811027 1.44892 2.57609 + endloop + endfacet + facet normal -0.666569 -0.0391175 0.744416 + outer loop + vertex 0.813702 1.44641 2.57843 + vertex 0.813855 1.44141 2.5783 + vertex 0.816424 1.44389 2.58073 + endloop + endfacet + facet normal -0.676679 -0.0425794 0.735046 + outer loop + vertex 0.814013 1.43642 2.57816 + vertex 0.813855 1.44141 2.5783 + vertex 0.811328 1.43891 2.57583 + endloop + endfacet + facet normal -0.66654 -0.0457744 0.744062 + outer loop + vertex 0.814013 1.43642 2.57816 + vertex 0.814167 1.43143 2.57799 + vertex 0.816752 1.43397 2.58046 + endloop + endfacet + facet normal -0.677117 -0.0481555 0.734298 + outer loop + vertex 0.81432 1.42645 2.5778 + vertex 0.814167 1.43143 2.57799 + vertex 0.811624 1.42894 2.57548 + endloop + endfacet + facet normal -0.668015 -0.0499141 0.742472 + outer loop + vertex 0.81432 1.42645 2.5778 + vertex 0.814576 1.42145 2.5777 + vertex 0.817041 1.42398 2.58009 + endloop + endfacet + facet normal -0.67766 -0.0542581 0.733371 + outer loop + vertex 0.815208 1.41604 2.57788 + vertex 0.814576 1.42145 2.5777 + vertex 0.812103 1.41891 2.57523 + endloop + endfacet + facet normal -0.671523 -0.0576319 0.738739 + outer loop + vertex 0.817464 1.41198 2.57962 + vertex 0.815208 1.41604 2.57788 + vertex 0.814931 1.41119 2.57725 + endloop + endfacet + facet normal -0.677499 -0.0602834 0.733049 + outer loop + vertex 0.814507 1.4079 2.57659 + vertex 0.814931 1.41119 2.57725 + vertex 0.812908 1.41024 2.5753 + endloop + endfacet + facet normal -0.672237 -0.0639962 0.737565 + outer loop + vertex 0.817858 1.40158 2.57909 + vertex 0.817179 1.40709 2.57895 + vertex 0.814985 1.40412 2.5767 + endloop + endfacet + facet normal -0.664944 -0.0645025 0.744103 + outer loop + vertex 0.817858 1.40158 2.57909 + vertex 0.818231 1.39646 2.57898 + vertex 0.820731 1.39894 2.58143 + endloop + endfacet + facet normal -0.671852 -0.0657354 0.737762 + outer loop + vertex 0.818477 1.39144 2.57876 + vertex 0.818231 1.39646 2.57898 + vertex 0.815762 1.39399 2.57651 + endloop + endfacet + facet normal -0.664525 -0.0682585 0.744142 + outer loop + vertex 0.818477 1.39144 2.57876 + vertex 0.818681 1.38649 2.57849 + vertex 0.821194 1.38898 2.58096 + endloop + endfacet + facet normal -0.67246 -0.0725071 0.736574 + outer loop + vertex 0.818906 1.38154 2.57821 + vertex 0.818681 1.38649 2.57849 + vertex 0.816199 1.38397 2.57597 + endloop + endfacet + facet normal -0.664096 -0.0768959 0.743682 + outer loop + vertex 0.818906 1.38154 2.57821 + vertex 0.819159 1.37661 2.57792 + vertex 0.821742 1.37905 2.58048 + endloop + endfacet + facet normal -0.673971 -0.0802146 0.73439 + outer loop + vertex 0.819535 1.37168 2.57773 + vertex 0.819159 1.37661 2.57792 + vertex 0.816679 1.37406 2.57537 + endloop + endfacet + facet normal -0.664761 -0.0817953 0.742564 + outer loop + vertex 0.819535 1.37168 2.57773 + vertex 0.820299 1.3664 2.57783 + vertex 0.822368 1.36959 2.58003 + endloop + endfacet + facet normal -0.673702 -0.0833738 0.734285 + outer loop + vertex 0.820096 1.3616 2.5771 + vertex 0.820299 1.3664 2.57783 + vertex 0.817588 1.3645 2.57513 + endloop + endfacet + facet normal -0.674848 -0.0852255 0.733019 + outer loop + vertex 0.817962 1.36079 2.57504 + vertex 0.820096 1.3616 2.5771 + vertex 0.817588 1.3645 2.57513 + endloop + endfacet + facet normal -0.678867 -0.0931777 0.728325 + outer loop + vertex 0.816909 1.3573 2.57361 + vertex 0.819596 1.35824 2.57624 + vertex 0.817962 1.36079 2.57504 + endloop + endfacet + facet normal -0.677289 -0.0900819 0.730182 + outer loop + vertex 0.816909 1.3573 2.57361 + vertex 0.818019 1.35169 2.57395 + vertex 0.820283 1.35419 2.57636 + endloop + endfacet + facet normal -0.682974 -0.0939979 0.724369 + outer loop + vertex 0.818535 1.34655 2.57377 + vertex 0.818019 1.35169 2.57395 + vertex 0.815795 1.3491 2.57152 + endloop + endfacet + facet normal -0.694129 -0.0898969 0.714216 + outer loop + vertex 0.811944 1.35711 2.5688 + vertex 0.812951 1.35173 2.5691 + vertex 0.81512 1.35402 2.5715 + endloop + endfacet + facet normal -0.691207 -0.0958693 0.716269 + outer loop + vertex 0.815795 1.3491 2.57152 + vertex 0.813476 1.34665 2.56895 + vertex 0.81614 1.34406 2.57118 + endloop + endfacet + facet normal -0.699211 -0.0979245 0.708177 + outer loop + vertex 0.813735 1.34159 2.56851 + vertex 0.813476 1.34665 2.56895 + vertex 0.811117 1.34414 2.56628 + endloop + endfacet + facet normal -0.708354 -0.0976532 0.69907 + outer loop + vertex 0.808464 1.34673 2.56395 + vertex 0.808748 1.34149 2.5635 + vertex 0.811117 1.34414 2.56628 + endloop + endfacet + facet normal -0.736413 -0.0935028 0.67004 + outer loop + vertex 0.803608 1.34662 2.55872 + vertex 0.803899 1.3414 2.55832 + vertex 0.806165 1.34405 2.56118 + endloop + endfacet + facet normal -0.762145 -0.0926474 0.640743 + outer loop + vertex 0.803899 1.3414 2.55832 + vertex 0.803608 1.34662 2.55872 + vertex 0.801457 1.34403 2.55579 + endloop + endfacet + facet normal -0.762705 -0.093994 0.63988 + outer loop + vertex 0.801781 1.33896 2.55543 + vertex 0.803899 1.3414 2.55832 + vertex 0.801457 1.34403 2.55579 + endloop + endfacet + facet normal -0.797085 -0.0931406 0.596641 + outer loop + vertex 0.801457 1.34403 2.55579 + vertex 0.799457 1.34163 2.55275 + vertex 0.801781 1.33896 2.55543 + endloop + endfacet + facet normal -0.798545 -0.0970058 0.594068 + outer loop + vertex 0.799457 1.34163 2.55275 + vertex 0.799878 1.33665 2.5525 + vertex 0.801781 1.33896 2.55543 + endloop + endfacet + facet normal -0.800516 -0.0928606 0.592074 + outer loop + vertex 0.801781 1.33896 2.55543 + vertex 0.799878 1.33665 2.5525 + vertex 0.802119 1.33449 2.55519 + endloop + endfacet + facet normal -0.762999 -0.0926357 0.639728 + outer loop + vertex 0.802119 1.33449 2.55519 + vertex 0.804061 1.33643 2.55779 + vertex 0.801781 1.33896 2.55543 + endloop + endfacet + facet normal -0.76357 -0.0913924 0.639225 + outer loop + vertex 0.803937 1.33276 2.55711 + vertex 0.804061 1.33643 2.55779 + vertex 0.802119 1.33449 2.55519 + endloop + endfacet + facet normal -0.764003 -0.0926175 0.638531 + outer loop + vertex 0.802636 1.33109 2.55531 + vertex 0.803937 1.33276 2.55711 + vertex 0.802119 1.33449 2.55519 + endloop + endfacet + facet normal -0.796849 -0.099168 0.595984 + outer loop + vertex 0.802636 1.33109 2.55531 + vertex 0.802119 1.33449 2.55519 + vertex 0.800636 1.33209 2.55281 + endloop + endfacet + facet normal -0.800544 -0.0929552 0.592021 + outer loop + vertex 0.799878 1.33665 2.5525 + vertex 0.800636 1.33209 2.55281 + vertex 0.802119 1.33449 2.55519 + endloop + endfacet + facet normal -0.79383 -0.0999569 0.599868 + outer loop + vertex 0.799117 1.34672 2.55314 + vertex 0.799457 1.34163 2.55275 + vertex 0.801457 1.34403 2.55579 + endloop + endfacet + facet normal -0.791463 -0.0938626 0.603966 + outer loop + vertex 0.80113 1.34916 2.55616 + vertex 0.799117 1.34672 2.55314 + vertex 0.801457 1.34403 2.55579 + endloop + endfacet + facet normal -0.78765 -0.101614 0.607686 + outer loop + vertex 0.798852 1.3516 2.55361 + vertex 0.799117 1.34672 2.55314 + vertex 0.80113 1.34916 2.55616 + endloop + endfacet + facet normal -0.785129 -0.0947184 0.612046 + outer loop + vertex 0.800888 1.35408 2.55661 + vertex 0.798852 1.3516 2.55361 + vertex 0.80113 1.34916 2.55616 + endloop + endfacet + facet normal -0.759284 -0.0963383 0.643589 + outer loop + vertex 0.80113 1.34916 2.55616 + vertex 0.803268 1.35163 2.55905 + vertex 0.800888 1.35408 2.55661 + endloop + endfacet + facet normal -0.758203 -0.0936222 0.645262 + outer loop + vertex 0.803268 1.35163 2.55905 + vertex 0.803128 1.35598 2.55952 + vertex 0.800888 1.35408 2.55661 + endloop + endfacet + facet normal -0.756462 -0.0978434 0.646677 + outer loop + vertex 0.800888 1.35408 2.55661 + vertex 0.803128 1.35598 2.55952 + vertex 0.800971 1.35924 2.55749 + endloop + endfacet + facet normal -0.781371 -0.0924224 0.617185 + outer loop + vertex 0.800971 1.35924 2.55749 + vertex 0.798574 1.35629 2.55401 + vertex 0.800888 1.35408 2.55661 + endloop + endfacet + facet normal -0.774672 -0.105351 0.623526 + outer loop + vertex 0.798225 1.36108 2.55439 + vertex 0.798574 1.35629 2.55401 + vertex 0.800971 1.35924 2.55749 + endloop + endfacet + facet normal -0.775145 -0.107737 0.622529 + outer loop + vertex 0.800043 1.3641 2.55717 + vertex 0.798225 1.36108 2.55439 + vertex 0.800971 1.35924 2.55749 + endloop + endfacet + facet normal -0.744746 -0.0995179 0.659886 + outer loop + vertex 0.80274 1.36328 2.56009 + vertex 0.800043 1.3641 2.55717 + vertex 0.800971 1.35924 2.55749 + endloop + endfacet + facet normal -0.747789 -0.0847144 0.65851 + outer loop + vertex 0.803976 1.35919 2.56089 + vertex 0.800971 1.35924 2.55749 + vertex 0.803128 1.35598 2.55952 + endloop + endfacet + facet normal -0.747042 -0.0970708 0.657652 + outer loop + vertex 0.803976 1.35919 2.56089 + vertex 0.80274 1.36328 2.56009 + vertex 0.800971 1.35924 2.55749 + endloop + endfacet + facet normal -0.760693 -0.0936435 0.642322 + outer loop + vertex 0.803608 1.34662 2.55872 + vertex 0.803268 1.35163 2.55905 + vertex 0.80113 1.34916 2.55616 + endloop + endfacet + facet normal -0.783286 -0.0983752 0.613829 + outer loop + vertex 0.798574 1.35629 2.55401 + vertex 0.798852 1.3516 2.55361 + vertex 0.800888 1.35408 2.55661 + endloop + endfacet + facet normal -0.763183 -0.0930636 0.639446 + outer loop + vertex 0.804061 1.33643 2.55779 + vertex 0.803899 1.3414 2.55832 + vertex 0.801781 1.33896 2.55543 + endloop + endfacet + facet normal -0.761081 -0.0946342 0.641716 + outer loop + vertex 0.801457 1.34403 2.55579 + vertex 0.803608 1.34662 2.55872 + vertex 0.80113 1.34916 2.55616 + endloop + endfacet + facet normal -0.716051 -0.101641 0.690609 + outer loop + vertex 0.808988 1.33626 2.56298 + vertex 0.808748 1.34149 2.5635 + vertex 0.806367 1.33874 2.56063 + endloop + endfacet + facet normal -0.706996 -0.104977 0.699383 + outer loop + vertex 0.808988 1.33626 2.56298 + vertex 0.809575 1.33128 2.56283 + vertex 0.811761 1.33406 2.56546 + endloop + endfacet + facet normal -0.711335 -0.107995 0.694507 + outer loop + vertex 0.810646 1.32667 2.56321 + vertex 0.809575 1.33128 2.56283 + vertex 0.807578 1.32818 2.5603 + endloop + endfacet + facet normal -0.710509 -0.103338 0.696059 + outer loop + vertex 0.808912 1.32405 2.56105 + vertex 0.810646 1.32667 2.56321 + vertex 0.807578 1.32818 2.5603 + endloop + endfacet + facet normal -0.753695 -0.0917069 0.650795 + outer loop + vertex 0.802079 1.32738 2.55395 + vertex 0.803104 1.32183 2.55436 + vertex 0.80569 1.32449 2.55773 + endloop + endfacet + facet normal -0.722393 -0.10551 0.683386 + outer loop + vertex 0.808315 1.31666 2.55933 + vertex 0.808105 1.32094 2.55977 + vertex 0.805768 1.31923 2.55703 + endloop + endfacet + facet normal -0.707366 -0.113045 0.69775 + outer loop + vertex 0.808315 1.31666 2.55933 + vertex 0.808698 1.31173 2.55892 + vertex 0.810889 1.31425 2.56155 + endloop + endfacet + facet normal -0.744417 -0.0870387 0.662018 + outer loop + vertex 0.803464 1.31656 2.55391 + vertex 0.803893 1.31149 2.55373 + vertex 0.806065 1.31418 2.55653 + endloop + endfacet + facet normal 0.953137 0.0594359 0.296643 + outer loop + vertex 0.804309 1.30663 2.55337 + vertex 0.803893 1.31149 2.55373 + vertex 0.803592 1.31 2.555 + endloop + endfacet + facet normal -0.525225 -0.458053 0.717165 + outer loop + vertex 0.80229 1.30481 2.55073 + vertex 0.804309 1.30663 2.55337 + vertex 0.803592 1.31 2.555 + endloop + endfacet + facet normal -0.738773 -0.137312 0.659818 + outer loop + vertex 0.8047 1.30175 2.55279 + vertex 0.804309 1.30663 2.55337 + vertex 0.80229 1.30481 2.55073 + endloop + endfacet + facet normal -0.746028 -0.150498 0.648685 + outer loop + vertex 0.802543 1.29901 2.54968 + vertex 0.8047 1.30175 2.55279 + vertex 0.80229 1.30481 2.55073 + endloop + endfacet + facet normal -0.768067 -0.112399 0.630428 + outer loop + vertex 0.805526 1.29719 2.55299 + vertex 0.8047 1.30175 2.55279 + vertex 0.802543 1.29901 2.54968 + endloop + endfacet + facet normal -0.765936 -0.100595 0.634998 + outer loop + vertex 0.804059 1.29419 2.55074 + vertex 0.805526 1.29719 2.55299 + vertex 0.802543 1.29901 2.54968 + endloop + endfacet + facet normal -0.80197 -0.123091 0.584545 + outer loop + vertex 0.804059 1.29419 2.55074 + vertex 0.802543 1.29901 2.54968 + vertex 0.801208 1.29353 2.54669 + endloop + endfacet + facet normal -0.807061 -0.0925763 0.583166 + outer loop + vertex 0.804059 1.29419 2.55074 + vertex 0.801208 1.29353 2.54669 + vertex 0.803499 1.29075 2.54942 + endloop + endfacet + facet normal -0.816724 -0.118635 0.564701 + outer loop + vertex 0.802005 1.28873 2.54684 + vertex 0.803499 1.29075 2.54942 + vertex 0.801208 1.29353 2.54669 + endloop + endfacet + facet normal -0.85727 -0.127318 0.498877 + outer loop + vertex 0.801208 1.29353 2.54669 + vertex 0.800103 1.288 2.54338 + vertex 0.802005 1.28873 2.54684 + endloop + endfacet + facet normal -0.853893 -0.143214 0.500357 + outer loop + vertex 0.800103 1.288 2.54338 + vertex 0.801972 1.28434 2.54552 + vertex 0.802005 1.28873 2.54684 + endloop + endfacet + facet normal -0.818793 -0.158831 0.55168 + outer loop + vertex 0.801972 1.28434 2.54552 + vertex 0.803759 1.28653 2.54881 + vertex 0.802005 1.28873 2.54684 + endloop + endfacet + facet normal -0.825385 -0.144556 0.54575 + outer loop + vertex 0.804006 1.28164 2.54789 + vertex 0.803759 1.28653 2.54881 + vertex 0.801972 1.28434 2.54552 + endloop + endfacet + facet normal -0.809443 -0.133196 0.571892 + outer loop + vertex 0.803759 1.28653 2.54881 + vertex 0.803499 1.29075 2.54942 + vertex 0.802005 1.28873 2.54684 + endloop + endfacet + facet normal -0.293601 0.652186 0.698893 + outer loop + vertex 0.803592 1.31 2.555 + vertex 0.803893 1.31149 2.55373 + vertex 0.801282 1.31351 2.55075 + endloop + endfacet + facet normal -0.806922 0.157774 0.569197 + outer loop + vertex 0.801282 1.31351 2.55075 + vertex 0.800065 1.31 2.55 + vertex 0.803592 1.31 2.555 + endloop + endfacet + facet normal -0.778149 -0.0884497 0.62182 + outer loop + vertex 0.803893 1.31149 2.55373 + vertex 0.803464 1.31656 2.55391 + vertex 0.801282 1.31351 2.55075 + endloop + endfacet + facet normal -0.786426 -0.0736305 0.613281 + outer loop + vertex 0.801282 1.31351 2.55075 + vertex 0.803464 1.31656 2.55391 + vertex 0.801117 1.31902 2.5512 + endloop + endfacet + facet normal -0.856045 -0.0674837 0.512477 + outer loop + vertex 0.801117 1.31902 2.5512 + vertex 0.799292 1.31665 2.54784 + vertex 0.801282 1.31351 2.55075 + endloop + endfacet + facet normal -0.85027 -0.0534812 0.523622 + outer loop + vertex 0.799292 1.31665 2.54784 + vertex 0.799328 1.31274 2.5475 + vertex 0.801282 1.31351 2.55075 + endloop + endfacet + facet normal -0.842328 -0.101878 0.529248 + outer loop + vertex 0.799087 1.32163 2.54847 + vertex 0.799292 1.31665 2.54784 + vertex 0.801117 1.31902 2.5512 + endloop + endfacet + facet normal -0.797091 -0.104175 0.594805 + outer loop + vertex 0.803464 1.31656 2.55391 + vertex 0.803104 1.32183 2.55436 + vertex 0.801117 1.31902 2.5512 + endloop + endfacet + facet normal -0.794856 -0.108278 0.597059 + outer loop + vertex 0.801117 1.31902 2.5512 + vertex 0.803104 1.32183 2.55436 + vertex 0.800713 1.32387 2.55154 + endloop + endfacet + facet normal -0.793476 -0.102796 0.599858 + outer loop + vertex 0.803104 1.32183 2.55436 + vertex 0.802079 1.32738 2.55395 + vertex 0.800713 1.32387 2.55154 + endloop + endfacet + facet normal -0.725093 -0.116296 0.67876 + outer loop + vertex 0.80904 1.30658 2.5584 + vertex 0.808698 1.31173 2.55892 + vertex 0.806423 1.30908 2.55603 + endloop + endfacet + facet normal -0.725915 -0.109797 0.678964 + outer loop + vertex 0.809154 1.29804 2.5571 + vertex 0.809269 1.30168 2.55782 + vertex 0.807217 1.2997 2.5553 + endloop + endfacet + facet normal -0.731272 -0.137684 0.668046 + outer loop + vertex 0.804309 1.30663 2.55337 + vertex 0.8047 1.30175 2.55279 + vertex 0.806813 1.30411 2.55559 + endloop + endfacet + facet normal -0.724644 -0.106223 0.680887 + outer loop + vertex 0.807746 1.29634 2.55534 + vertex 0.809154 1.29804 2.5571 + vertex 0.807217 1.2997 2.5553 + endloop + endfacet + facet normal -0.721005 -0.112235 0.68378 + outer loop + vertex 0.809154 1.29804 2.5571 + vertex 0.807746 1.29634 2.55534 + vertex 0.8098 1.29475 2.55724 + endloop + endfacet + facet normal -0.710188 -0.109622 0.695426 + outer loop + vertex 0.809154 1.29804 2.5571 + vertex 0.8098 1.29475 2.55724 + vertex 0.811703 1.29841 2.55976 + endloop + endfacet + facet normal -0.701688 -0.113722 0.70335 + outer loop + vertex 0.815334 1.29589 2.56298 + vertex 0.814374 1.30138 2.56291 + vertex 0.811703 1.29841 2.55976 + endloop + endfacet + facet normal -0.694094 -0.101844 0.712643 + outer loop + vertex 0.814889 1.28806 2.56141 + vertex 0.817448 1.28744 2.56382 + vertex 0.815182 1.29129 2.56216 + endloop + endfacet + facet normal -0.702122 -0.110891 0.703369 + outer loop + vertex 0.814889 1.28806 2.56141 + vertex 0.813082 1.28651 2.55937 + vertex 0.815505 1.28427 2.56143 + endloop + endfacet + facet normal -0.705889 -0.119805 0.698117 + outer loop + vertex 0.813082 1.28651 2.55937 + vertex 0.813385 1.28175 2.55885 + vertex 0.815505 1.28427 2.56143 + endloop + endfacet + facet normal -0.712072 -0.102213 0.694626 + outer loop + vertex 0.813265 1.28999 2.56008 + vertex 0.812618 1.29345 2.55992 + vertex 0.810652 1.28989 2.55738 + endloop + endfacet + facet normal -0.712836 -0.11949 0.691077 + outer loop + vertex 0.813385 1.28175 2.55885 + vertex 0.813082 1.28651 2.55937 + vertex 0.810809 1.28437 2.55665 + endloop + endfacet + facet normal -0.726475 -0.109274 0.678449 + outer loop + vertex 0.807014 1.29255 2.55392 + vertex 0.80807 1.28699 2.55415 + vertex 0.810652 1.28989 2.55738 + endloop + endfacet + facet normal -0.754407 -0.127704 0.643864 + outer loop + vertex 0.80852 1.28155 2.5536 + vertex 0.80807 1.28699 2.55415 + vertex 0.80599 1.28407 2.55113 + endloop + endfacet + facet normal -0.695832 -0.129038 0.706518 + outer loop + vertex 0.818821 1.27686 2.56338 + vertex 0.818225 1.28196 2.56372 + vertex 0.816027 1.27933 2.56108 + endloop + endfacet + facet normal -0.689708 -0.149109 0.708568 + outer loop + vertex 0.818821 1.27686 2.56338 + vertex 0.819549 1.27209 2.56308 + vertex 0.821803 1.27427 2.56573 + endloop + endfacet + facet normal -0.694161 -0.162869 0.701152 + outer loop + vertex 0.820526 1.26764 2.56302 + vertex 0.819549 1.27209 2.56308 + vertex 0.817565 1.26979 2.56058 + endloop + endfacet + facet normal -0.692802 -0.15829 0.703541 + outer loop + vertex 0.818784 1.26546 2.56081 + vertex 0.820526 1.26764 2.56302 + vertex 0.817565 1.26979 2.56058 + endloop + endfacet + facet normal -0.708691 -0.152053 0.688939 + outer loop + vertex 0.813806 1.27662 2.55826 + vertex 0.814569 1.27171 2.55796 + vertex 0.816644 1.2744 2.56069 + endloop + endfacet + facet normal -0.699858 -0.160668 0.695977 + outer loop + vertex 0.818784 1.26546 2.56081 + vertex 0.817565 1.26979 2.56058 + vertex 0.815769 1.26719 2.55818 + endloop + endfacet + facet normal -0.697511 -0.149147 0.70088 + outer loop + vertex 0.817227 1.26234 2.5586 + vertex 0.818784 1.26546 2.56081 + vertex 0.815769 1.26719 2.55818 + endloop + endfacet + facet normal -0.716773 -0.1512 0.680717 + outer loop + vertex 0.815058 1.26205 2.55637 + vertex 0.813363 1.2612 2.55439 + vertex 0.815632 1.25913 2.55632 + endloop + endfacet + facet normal -0.727005 -0.154668 0.668985 + outer loop + vertex 0.814139 1.26451 2.55591 + vertex 0.812727 1.26855 2.55531 + vertex 0.811063 1.26449 2.55257 + endloop + endfacet + facet normal -0.715788 -0.152456 0.681473 + outer loop + vertex 0.813548 1.25659 2.55356 + vertex 0.813953 1.25155 2.55286 + vertex 0.816241 1.25425 2.55587 + endloop + endfacet + facet normal -0.694465 -0.156124 0.702384 + outer loop + vertex 0.819269 1.25181 2.55832 + vertex 0.818394 1.25706 2.55862 + vertex 0.816241 1.25425 2.55587 + endloop + endfacet + facet normal -0.68758 -0.154895 0.709395 + outer loop + vertex 0.820262 1.24137 2.55697 + vertex 0.820397 1.24615 2.55814 + vertex 0.817668 1.24342 2.5549 + endloop + endfacet + facet normal -0.713921 -0.152135 0.683499 + outer loop + vertex 0.814095 1.24762 2.55214 + vertex 0.814979 1.24433 2.55233 + vertex 0.816633 1.24853 2.55499 + endloop + endfacet + facet normal -0.731888 -0.158157 0.662817 + outer loop + vertex 0.814095 1.24762 2.55214 + vertex 0.812939 1.24521 2.55028 + vertex 0.814979 1.24433 2.55233 + endloop + endfacet + facet normal -0.732041 -0.159852 0.66224 + outer loop + vertex 0.813046 1.24151 2.54951 + vertex 0.814979 1.24433 2.55233 + vertex 0.812939 1.24521 2.55028 + endloop + endfacet + facet normal -0.729881 -0.162962 0.663866 + outer loop + vertex 0.814979 1.24433 2.55233 + vertex 0.813046 1.24151 2.54951 + vertex 0.815878 1.23959 2.55215 + endloop + endfacet + facet normal -0.729521 -0.161347 0.664655 + outer loop + vertex 0.813046 1.24151 2.54951 + vertex 0.813467 1.2368 2.54883 + vertex 0.815878 1.23959 2.55215 + endloop + endfacet + facet normal -0.723749 -0.170973 0.668547 + outer loop + vertex 0.815878 1.23959 2.55215 + vertex 0.813467 1.2368 2.54883 + vertex 0.816238 1.23443 2.55122 + endloop + endfacet + facet normal -0.723082 -0.168951 0.669782 + outer loop + vertex 0.813467 1.2368 2.54883 + vertex 0.814238 1.23204 2.54846 + vertex 0.816238 1.23443 2.55122 + endloop + endfacet + facet normal -0.713981 -0.183449 0.675705 + outer loop + vertex 0.816238 1.23443 2.55122 + vertex 0.814238 1.23204 2.54846 + vertex 0.817273 1.2297 2.55103 + endloop + endfacet + facet normal -0.711573 -0.175166 0.680426 + outer loop + vertex 0.814238 1.23204 2.54846 + vertex 0.815476 1.22736 2.54855 + vertex 0.817273 1.2297 2.55103 + endloop + endfacet + facet normal -0.702869 -0.187846 0.686068 + outer loop + vertex 0.818644 1.22515 2.55119 + vertex 0.817273 1.2297 2.55103 + vertex 0.815476 1.22736 2.54855 + endloop + endfacet + facet normal -0.701904 -0.184063 0.688078 + outer loop + vertex 0.817024 1.22217 2.54874 + vertex 0.818644 1.22515 2.55119 + vertex 0.815476 1.22736 2.54855 + endloop + endfacet + facet normal -0.687971 -0.156018 0.708769 + outer loop + vertex 0.818311 1.23991 2.55475 + vertex 0.820262 1.24137 2.55697 + vertex 0.817668 1.24342 2.5549 + endloop + endfacet + facet normal -0.686468 -0.186196 0.702917 + outer loop + vertex 0.819159 1.23199 2.55354 + vertex 0.820487 1.22727 2.55358 + vertex 0.82229 1.22968 2.55598 + endloop + endfacet + facet normal -0.686087 -0.184932 0.703623 + outer loop + vertex 0.821022 1.23437 2.55598 + vertex 0.819159 1.23199 2.55354 + vertex 0.82229 1.22968 2.55598 + endloop + endfacet + facet normal -0.686862 -0.183843 0.703152 + outer loop + vertex 0.818307 1.23646 2.55387 + vertex 0.819159 1.23199 2.55354 + vertex 0.821022 1.23437 2.55598 + endloop + endfacet + facet normal -0.68686 -0.183838 0.703155 + outer loop + vertex 0.820026 1.23806 2.55597 + vertex 0.818307 1.23646 2.55387 + vertex 0.821022 1.23437 2.55598 + endloop + endfacet + facet normal -0.690134 -0.178062 0.701433 + outer loop + vertex 0.818307 1.23646 2.55387 + vertex 0.820026 1.23806 2.55597 + vertex 0.818311 1.23991 2.55475 + endloop + endfacet + facet normal -0.687278 -0.18509 0.702417 + outer loop + vertex 0.823694 1.22506 2.55614 + vertex 0.82229 1.22968 2.55598 + vertex 0.820487 1.22727 2.55358 + endloop + endfacet + facet normal -0.687632 -0.186408 0.701723 + outer loop + vertex 0.822046 1.22211 2.55374 + vertex 0.823694 1.22506 2.55614 + vertex 0.820487 1.22727 2.55358 + endloop + endfacet + facet normal -0.691654 -0.185643 0.697962 + outer loop + vertex 0.822046 1.22211 2.55374 + vertex 0.82334 1.21689 2.55363 + vertex 0.825341 1.21907 2.5562 + endloop + endfacet + facet normal -0.697759 -0.18665 0.691588 + outer loop + vertex 0.824432 1.21218 2.55346 + vertex 0.82334 1.21689 2.55363 + vertex 0.821397 1.21443 2.55101 + endloop + endfacet + facet normal -0.697716 -0.194328 0.689513 + outer loop + vertex 0.817024 1.22217 2.54874 + vertex 0.818312 1.21674 2.54851 + vertex 0.820331 1.2191 2.55122 + endloop + endfacet + facet normal -0.7067 -0.196049 0.679809 + outer loop + vertex 0.818312 1.21674 2.54851 + vertex 0.817024 1.22217 2.54874 + vertex 0.815342 1.21905 2.54609 + endloop + endfacet + facet normal -0.705644 -0.197253 0.680557 + outer loop + vertex 0.815342 1.21905 2.54609 + vertex 0.817024 1.22217 2.54874 + vertex 0.814613 1.22222 2.54626 + endloop + endfacet + facet normal -0.709162 -0.168896 0.684517 + outer loop + vertex 0.817024 1.22217 2.54874 + vertex 0.813722 1.22522 2.54607 + vertex 0.814613 1.22222 2.54626 + endloop + endfacet + facet normal -0.71692 -0.189176 0.670998 + outer loop + vertex 0.817024 1.22217 2.54874 + vertex 0.815476 1.22736 2.54855 + vertex 0.813722 1.22522 2.54607 + endloop + endfacet + facet normal -0.70488 -0.190063 0.683388 + outer loop + vertex 0.821397 1.21443 2.55101 + vertex 0.819459 1.21182 2.54829 + vertex 0.82255 1.20983 2.55092 + endloop + endfacet + facet normal -0.704945 -0.190361 0.683239 + outer loop + vertex 0.819459 1.21182 2.54829 + vertex 0.820802 1.20725 2.5484 + vertex 0.82255 1.20983 2.55092 + endloop + endfacet + facet normal -0.704004 -0.190776 0.684092 + outer loop + vertex 0.822348 1.20233 2.54862 + vertex 0.823874 1.20547 2.55106 + vertex 0.820802 1.20725 2.5484 + endloop + endfacet + facet normal -0.736616 -0.197233 0.646913 + outer loop + vertex 0.818518 1.20113 2.54408 + vertex 0.820193 1.20201 2.54626 + vertex 0.819221 1.20455 2.54593 + endloop + endfacet + facet normal -0.715595 -0.195957 0.670466 + outer loop + vertex 0.823586 1.1968 2.54832 + vertex 0.822348 1.20233 2.54862 + vertex 0.820806 1.19896 2.54599 + endloop + endfacet + facet normal -0.700982 -0.193538 0.686416 + outer loop + vertex 0.822348 1.20233 2.54862 + vertex 0.823586 1.1968 2.54832 + vertex 0.825607 1.19934 2.5511 + endloop + endfacet + facet normal -0.697731 -0.184082 0.692304 + outer loop + vertex 0.828602 1.19685 2.55346 + vertex 0.827282 1.20246 2.55362 + vertex 0.825607 1.19934 2.5511 + endloop + endfacet + facet normal -0.685817 -0.181638 0.704743 + outer loop + vertex 0.827282 1.20246 2.55362 + vertex 0.828602 1.19685 2.55346 + vertex 0.830619 1.19925 2.55604 + endloop + endfacet + facet normal -0.683302 -0.178938 0.70787 + outer loop + vertex 0.830619 1.19925 2.55604 + vertex 0.832199 1.20264 2.55842 + vertex 0.829815 1.2025 2.55609 + endloop + endfacet + facet normal -0.683198 -0.149535 0.714759 + outer loop + vertex 0.838713 1.19702 2.56333 + vertex 0.837788 1.20254 2.5636 + vertex 0.835711 1.19952 2.56098 + endloop + endfacet + facet normal -0.66117 -0.183836 0.727364 + outer loop + vertex 0.837788 1.20254 2.5636 + vertex 0.837881 1.20703 2.56482 + vertex 0.835214 1.20674 2.56232 + endloop + endfacet + facet normal -0.652824 -0.195096 0.731955 + outer loop + vertex 0.837881 1.20703 2.56482 + vertex 0.839801 1.2072 2.56658 + vertex 0.838712 1.21001 2.56636 + endloop + endfacet + facet normal -0.654095 -0.191285 0.731826 + outer loop + vertex 0.838712 1.21001 2.56636 + vertex 0.840317 1.21246 2.56843 + vertex 0.837061 1.21458 2.56608 + endloop + endfacet + facet normal -0.649391 -0.186981 0.737109 + outer loop + vertex 0.839011 1.2172 2.56848 + vertex 0.840317 1.21246 2.56843 + vertex 0.842264 1.21465 2.5707 + endloop + endfacet + facet normal -0.638013 -0.190498 0.74609 + outer loop + vertex 0.845131 1.2116 2.57238 + vertex 0.845105 1.21629 2.57355 + vertex 0.842264 1.21465 2.5707 + endloop + endfacet + facet normal -0.632391 -0.193779 0.750021 + outer loop + vertex 0.847814 1.20744 2.57356 + vertex 0.847875 1.21198 2.57479 + vertex 0.845131 1.2116 2.57238 + endloop + endfacet + facet normal -0.623354 -0.195791 0.757031 + outer loop + vertex 0.847875 1.21198 2.57479 + vertex 0.847814 1.20744 2.57356 + vertex 0.85053 1.20929 2.57628 + endloop + endfacet + facet normal -0.625503 -0.199434 0.754303 + outer loop + vertex 0.849843 1.2122 2.57648 + vertex 0.847875 1.21198 2.57479 + vertex 0.85053 1.20929 2.57628 + endloop + endfacet + facet normal -0.614983 -0.197576 0.763387 + outer loop + vertex 0.85053 1.20929 2.57628 + vertex 0.852181 1.21252 2.57844 + vertex 0.849843 1.2122 2.57648 + endloop + endfacet + facet normal -0.623546 -0.18984 0.758387 + outer loop + vertex 0.853746 1.20704 2.57836 + vertex 0.852181 1.21252 2.57844 + vertex 0.85053 1.20929 2.57628 + endloop + endfacet + facet normal -0.618957 -0.176978 0.765226 + outer loop + vertex 0.851361 1.20447 2.57584 + vertex 0.853746 1.20704 2.57836 + vertex 0.85053 1.20929 2.57628 + endloop + endfacet + facet normal -0.632251 -0.178239 0.753983 + outer loop + vertex 0.85053 1.20929 2.57628 + vertex 0.847814 1.20744 2.57356 + vertex 0.851361 1.20447 2.57584 + endloop + endfacet + facet normal -0.646986 -0.167696 0.743833 + outer loop + vertex 0.848845 1.20198 2.57323 + vertex 0.847814 1.20744 2.57356 + vertex 0.845657 1.20441 2.571 + endloop + endfacet + facet normal -0.639226 -0.198296 0.743014 + outer loop + vertex 0.842047 1.20744 2.56863 + vertex 0.844765 1.20835 2.57121 + vertex 0.84291 1.21089 2.57029 + endloop + endfacet + facet normal -0.658802 -0.178055 0.730942 + outer loop + vertex 0.843391 1.20195 2.5685 + vertex 0.842047 1.20744 2.56863 + vertex 0.840417 1.20428 2.56639 + endloop + endfacet + facet normal -0.670921 -0.128235 0.730357 + outer loop + vertex 0.843992 1.19685 2.56816 + vertex 0.843391 1.20195 2.5685 + vertex 0.841087 1.19949 2.56595 + endloop + endfacet + facet normal -0.67179 -0.0562608 0.738602 + outer loop + vertex 0.849586 1.1918 2.57276 + vertex 0.849312 1.19687 2.5729 + vertex 0.846781 1.19431 2.5704 + endloop + endfacet + facet normal -0.66129 -0.0559489 0.748041 + outer loop + vertex 0.849312 1.19687 2.5729 + vertex 0.849586 1.1918 2.57276 + vertex 0.852115 1.19446 2.57519 + endloop + endfacet + facet normal -0.638107 -0.144591 0.756249 + outer loop + vertex 0.846432 1.19936 2.57069 + vertex 0.848845 1.20198 2.57323 + vertex 0.845657 1.20441 2.571 + endloop + endfacet + facet normal -0.626219 -0.164886 0.762012 + outer loop + vertex 0.847814 1.20744 2.57356 + vertex 0.848845 1.20198 2.57323 + vertex 0.851361 1.20447 2.57584 + endloop + endfacet + facet normal -0.634046 -0.116956 0.7644 + outer loop + vertex 0.85758 1.20087 2.58039 + vertex 0.859723 1.20182 2.58232 + vertex 0.85706 1.20464 2.58054 + endloop + endfacet + facet normal -0.640667 -0.145611 0.753885 + outer loop + vertex 0.854755 1.20157 2.57816 + vertex 0.853746 1.20704 2.57836 + vertex 0.851361 1.20447 2.57584 + endloop + endfacet + facet normal -0.610372 -0.186258 0.769905 + outer loop + vertex 0.852181 1.21252 2.57844 + vertex 0.853746 1.20704 2.57836 + vertex 0.856057 1.20954 2.5808 + endloop + endfacet + facet normal -0.635239 -0.118891 0.76311 + outer loop + vertex 0.859723 1.20182 2.58232 + vertex 0.859864 1.2067 2.58319 + vertex 0.85706 1.20464 2.58054 + endloop + endfacet + facet normal -0.603401 -0.189625 0.774565 + outer loop + vertex 0.856057 1.20954 2.5808 + vertex 0.858183 1.2127 2.58323 + vertex 0.854944 1.21353 2.58091 + endloop + endfacet + facet normal -0.586812 -0.156589 0.794438 + outer loop + vertex 0.865107 1.20683 2.58715 + vertex 0.864982 1.21186 2.58805 + vertex 0.862061 1.20977 2.58548 + endloop + endfacet + facet normal -0.591137 -0.189539 0.783984 + outer loop + vertex 0.857959 1.21766 2.58426 + vertex 0.858183 1.2127 2.58323 + vertex 0.861083 1.21478 2.58591 + endloop + endfacet + facet normal -0.604172 -0.179094 0.776467 + outer loop + vertex 0.857959 1.21766 2.58426 + vertex 0.855177 1.2217 2.58302 + vertex 0.855256 1.21689 2.58197 + endloop + endfacet + facet normal -0.60572 -0.170505 0.777194 + outer loop + vertex 0.85393 1.22714 2.58324 + vertex 0.855177 1.2217 2.58302 + vertex 0.857198 1.22485 2.58529 + endloop + endfacet + facet normal -0.589413 -0.174919 0.788667 + outer loop + vertex 0.860154 1.21881 2.58619 + vertex 0.860509 1.22264 2.58731 + vertex 0.858158 1.22112 2.58521 + endloop + endfacet + facet normal -0.59705 -0.165948 0.784852 + outer loop + vertex 0.857198 1.22485 2.58529 + vertex 0.859133 1.22702 2.58722 + vertex 0.856348 1.22958 2.58564 + endloop + endfacet + facet normal -0.59452 -0.161451 0.787705 + outer loop + vertex 0.859133 1.22702 2.58722 + vertex 0.859381 1.23147 2.58832 + vertex 0.856348 1.22958 2.58564 + endloop + endfacet + facet normal -0.582575 -0.159059 0.797061 + outer loop + vertex 0.857905 1.23756 2.58846 + vertex 0.859381 1.23147 2.58832 + vertex 0.861752 1.23457 2.59067 + endloop + endfacet + facet normal -0.568891 -0.159061 0.806885 + outer loop + vertex 0.864925 1.23164 2.59233 + vertex 0.864798 1.23671 2.59324 + vertex 0.861752 1.23457 2.59067 + endloop + endfacet + facet normal -0.550748 -0.16948 0.817284 + outer loop + vertex 0.867892 1.22758 2.59349 + vertex 0.867798 1.23253 2.59445 + vertex 0.864925 1.23164 2.59233 + endloop + endfacet + facet normal -0.569405 -0.167132 0.804888 + outer loop + vertex 0.862223 1.2266 2.5894 + vertex 0.864675 1.22811 2.59145 + vertex 0.862604 1.23046 2.59048 + endloop + endfacet + facet normal -0.578335 -0.171493 0.797571 + outer loop + vertex 0.86359 1.22224 2.58946 + vertex 0.862223 1.2266 2.5894 + vertex 0.860509 1.22264 2.58731 + endloop + endfacet + facet normal -0.537807 -0.177907 0.824083 + outer loop + vertex 0.869477 1.22171 2.59326 + vertex 0.867892 1.22758 2.59349 + vertex 0.865687 1.22433 2.59135 + endloop + endfacet + facet normal -0.538429 -0.187165 0.821622 + outer loop + vertex 0.870813 1.21272 2.59211 + vertex 0.869245 1.21725 2.59212 + vertex 0.867136 1.21511 2.59025 + endloop + endfacet + facet normal -0.558798 -0.186375 0.80809 + outer loop + vertex 0.86359 1.22224 2.58946 + vertex 0.863352 1.21788 2.58829 + vertex 0.866369 1.21976 2.59081 + endloop + endfacet + facet normal -0.535282 -0.179342 0.825415 + outer loop + vertex 0.868253 1.21119 2.59012 + vertex 0.870813 1.21272 2.59211 + vertex 0.867136 1.21511 2.59025 + endloop + endfacet + facet normal -0.539477 -0.150327 0.828472 + outer loop + vertex 0.867908 1.20762 2.58925 + vertex 0.870381 1.20872 2.59106 + vertex 0.868253 1.21119 2.59012 + endloop + endfacet + facet normal -0.545969 -0.158089 0.822755 + outer loop + vertex 0.870381 1.20872 2.59106 + vertex 0.870813 1.21272 2.59211 + vertex 0.868253 1.21119 2.59012 + endloop + endfacet + facet normal -0.549929 -0.157019 0.820319 + outer loop + vertex 0.870381 1.20872 2.59106 + vertex 0.873898 1.20747 2.59318 + vertex 0.870813 1.21272 2.59211 + endloop + endfacet + facet normal -0.527379 -0.107938 0.842746 + outer loop + vertex 0.877472 1.20638 2.59527 + vertex 0.876907 1.2102 2.59541 + vertex 0.873898 1.20747 2.59318 + endloop + endfacet + facet normal -0.53788 -0.109248 0.835913 + outer loop + vertex 0.877472 1.20638 2.59527 + vertex 0.880206 1.2078 2.59722 + vertex 0.876907 1.2102 2.59541 + endloop + endfacet + facet normal -0.545676 -0.104191 0.831494 + outer loop + vertex 0.883443 1.20726 2.59927 + vertex 0.882321 1.212 2.59913 + vertex 0.880206 1.2078 2.59722 + endloop + endfacet + facet normal -0.52082 -0.109598 0.846602 + outer loop + vertex 0.885823 1.20951 2.601 + vertex 0.888878 1.21244 2.60326 + vertex 0.885195 1.21354 2.60114 + endloop + endfacet + facet normal -0.500854 -0.105051 0.859133 + outer loop + vertex 0.892538 1.21141 2.60527 + vertex 0.892014 1.21535 2.60545 + vertex 0.888878 1.21244 2.60326 + endloop + endfacet + facet normal -0.481897 -0.103021 0.870151 + outer loop + vertex 0.892538 1.21141 2.60527 + vertex 0.895549 1.21283 2.6071 + vertex 0.892014 1.21535 2.60545 + endloop + endfacet + facet normal -0.414432 -0.0884587 0.905771 + outer loop + vertex 0.902642 1.21138 2.61042 + vertex 0.905611 1.213 2.61193 + vertex 0.901964 1.21516 2.61048 + endloop + endfacet + facet normal -0.453968 -0.103935 0.884935 + outer loop + vertex 0.899565 1.21181 2.60905 + vertex 0.898291 1.21662 2.60896 + vertex 0.895549 1.21283 2.6071 + endloop + endfacet + facet normal -0.416906 -0.147778 0.896856 + outer loop + vertex 0.897059 1.22198 2.60927 + vertex 0.898291 1.21662 2.60896 + vertex 0.900835 1.21981 2.61066 + endloop + endfacet + facet normal -0.428821 -0.119746 0.895418 + outer loop + vertex 0.905611 1.213 2.61193 + vertex 0.904655 1.21822 2.61217 + vertex 0.901964 1.21516 2.61048 + endloop + endfacet + facet normal -0.409888 -0.166706 0.896772 + outer loop + vertex 0.900835 1.21981 2.61066 + vertex 0.903045 1.2231 2.61229 + vertex 0.899894 1.22374 2.61097 + endloop + endfacet + facet normal -0.449962 -0.141058 0.881837 + outer loop + vertex 0.90895 1.21601 2.61401 + vertex 0.907328 1.22201 2.61414 + vertex 0.904655 1.21822 2.61217 + endloop + endfacet + facet normal -0.442883 -0.121984 0.888242 + outer loop + vertex 0.905611 1.213 2.61193 + vertex 0.90895 1.21601 2.61401 + vertex 0.904655 1.21822 2.61217 + endloop + endfacet + facet normal -0.443022 -0.1218 0.888199 + outer loop + vertex 0.908516 1.21224 2.61328 + vertex 0.90895 1.21601 2.61401 + vertex 0.905611 1.213 2.61193 + endloop + endfacet + facet normal -0.428461 -0.0402135 0.902665 + outer loop + vertex 0.907831 1.20815 2.61277 + vertex 0.908516 1.21224 2.61328 + vertex 0.905611 1.213 2.61193 + endloop + endfacet + facet normal -0.44463 -0.0490501 0.89437 + outer loop + vertex 0.904429 1.20932 2.61114 + vertex 0.907831 1.20815 2.61277 + vertex 0.905611 1.213 2.61193 + endloop + endfacet + facet normal -0.412686 -0.169608 0.894943 + outer loop + vertex 0.903045 1.2231 2.61229 + vertex 0.904847 1.22682 2.61382 + vertex 0.900715 1.2278 2.6121 + endloop + endfacet + facet normal -0.492739 -0.184159 0.850467 + outer loop + vertex 0.907951 1.22613 2.61522 + vertex 0.910492 1.22784 2.61706 + vertex 0.906866 1.22998 2.61543 + endloop + endfacet + facet normal -0.493727 -0.18246 0.85026 + outer loop + vertex 0.9102 1.22376 2.61602 + vertex 0.910492 1.22784 2.61706 + vertex 0.907951 1.22613 2.61522 + endloop + endfacet + facet normal -0.471737 -0.155689 0.867885 + outer loop + vertex 0.907328 1.22201 2.61414 + vertex 0.9102 1.22376 2.61602 + vertex 0.907951 1.22613 2.61522 + endloop + endfacet + facet normal -0.478113 -0.14374 0.866456 + outer loop + vertex 0.9102 1.22376 2.61602 + vertex 0.907328 1.22201 2.61414 + vertex 0.911472 1.21967 2.61604 + endloop + endfacet + facet normal -0.543137 -0.164208 0.82343 + outer loop + vertex 0.911472 1.21967 2.61604 + vertex 0.913582 1.22303 2.6181 + vertex 0.9102 1.22376 2.61602 + endloop + endfacet + facet normal -0.559641 -0.14884 0.81526 + outer loop + vertex 0.915116 1.21799 2.61824 + vertex 0.913582 1.22303 2.6181 + vertex 0.911472 1.21967 2.61604 + endloop + endfacet + facet normal -0.555473 -0.132357 0.820933 + outer loop + vertex 0.913169 1.21506 2.61645 + vertex 0.915116 1.21799 2.61824 + vertex 0.911472 1.21967 2.61604 + endloop + endfacet + facet normal -0.515998 -0.115359 0.848786 + outer loop + vertex 0.913169 1.21506 2.61645 + vertex 0.911472 1.21967 2.61604 + vertex 0.90895 1.21601 2.61401 + endloop + endfacet + facet normal -0.514606 -0.102878 0.851232 + outer loop + vertex 0.913169 1.21506 2.61645 + vertex 0.90895 1.21601 2.61401 + vertex 0.911392 1.21135 2.61492 + endloop + endfacet + facet normal -0.480086 -0.148833 0.864503 + outer loop + vertex 0.907328 1.22201 2.61414 + vertex 0.90895 1.21601 2.61401 + vertex 0.911472 1.21967 2.61604 + endloop + endfacet + facet normal -0.543604 -0.171549 0.821624 + outer loop + vertex 0.9102 1.22376 2.61602 + vertex 0.913582 1.22303 2.6181 + vertex 0.910492 1.22784 2.61706 + endloop + endfacet + facet normal -0.411815 -0.163043 0.896563 + outer loop + vertex 0.904847 1.22682 2.61382 + vertex 0.903248 1.23163 2.61396 + vertex 0.900715 1.2278 2.6121 + endloop + endfacet + facet normal -0.484001 -0.162164 0.85991 + outer loop + vertex 0.910492 1.22784 2.61706 + vertex 0.908859 1.23242 2.61701 + vertex 0.906866 1.22998 2.61543 + endloop + endfacet + facet normal -0.437804 -0.156296 0.885381 + outer loop + vertex 0.901993 1.23704 2.6143 + vertex 0.903248 1.23163 2.61396 + vertex 0.905828 1.2346 2.61576 + endloop + endfacet + facet normal -0.491619 -0.148685 0.858023 + outer loop + vertex 0.905092 1.23867 2.61609 + vertex 0.908924 1.23734 2.61806 + vertex 0.905781 1.24279 2.6172 + endloop + endfacet + facet normal -0.512642 -0.16317 0.842955 + outer loop + vertex 0.908924 1.23734 2.61806 + vertex 0.909189 1.24218 2.61916 + vertex 0.905781 1.24279 2.6172 + endloop + endfacet + facet normal -0.512496 -0.160343 0.843586 + outer loop + vertex 0.909189 1.24218 2.61916 + vertex 0.907953 1.24638 2.6192 + vertex 0.905781 1.24279 2.6172 + endloop + endfacet + facet normal -0.508577 -0.163683 0.845315 + outer loop + vertex 0.905781 1.24279 2.6172 + vertex 0.907953 1.24638 2.6192 + vertex 0.904345 1.24814 2.61737 + endloop + endfacet + facet normal -0.425291 -0.145644 0.893261 + outer loop + vertex 0.896877 1.25196 2.61431 + vertex 0.898195 1.24657 2.61406 + vertex 0.900646 1.24978 2.61575 + endloop + endfacet + facet normal -0.422766 -0.148403 0.894005 + outer loop + vertex 0.902912 1.24113 2.6154 + vertex 0.90194 1.24509 2.6156 + vertex 0.899749 1.24176 2.61401 + endloop + endfacet + facet normal -0.417859 -0.143925 0.897039 + outer loop + vertex 0.901993 1.23704 2.6143 + vertex 0.899749 1.24176 2.61401 + vertex 0.897844 1.23798 2.61251 + endloop + endfacet + facet normal -0.428984 -0.148702 0.890988 + outer loop + vertex 0.895657 1.23465 2.61091 + vertex 0.897844 1.23798 2.61251 + vertex 0.894765 1.23858 2.61113 + endloop + endfacet + facet normal -0.452703 -0.153358 0.878374 + outer loop + vertex 0.894765 1.23858 2.61113 + vertex 0.891951 1.23687 2.60938 + vertex 0.895657 1.23465 2.61091 + endloop + endfacet + facet normal -0.471175 -0.150402 0.869122 + outer loop + vertex 0.891951 1.23687 2.60938 + vertex 0.889802 1.2416 2.60904 + vertex 0.887993 1.23797 2.60743 + endloop + endfacet + facet normal -0.44228 -0.140707 0.885771 + outer loop + vertex 0.892812 1.24089 2.61052 + vertex 0.895656 1.24266 2.61222 + vertex 0.891934 1.24486 2.61071 + endloop + endfacet + facet normal -0.47652 -0.14761 0.866683 + outer loop + vertex 0.889802 1.2416 2.60904 + vertex 0.888308 1.24642 2.60904 + vertex 0.885824 1.24272 2.60704 + endloop + endfacet + facet normal -0.467573 -0.148272 0.87143 + outer loop + vertex 0.886896 1.25182 2.6092 + vertex 0.888308 1.24642 2.60904 + vertex 0.890679 1.24959 2.61085 + endloop + endfacet + facet normal -0.444885 -0.146684 0.883494 + outer loop + vertex 0.895656 1.24266 2.61222 + vertex 0.894355 1.24808 2.61247 + vertex 0.891934 1.24486 2.61071 + endloop + endfacet + facet normal -0.450712 -0.146914 0.880497 + outer loop + vertex 0.890679 1.24959 2.61085 + vertex 0.892839 1.25289 2.6125 + vertex 0.889744 1.25356 2.61103 + endloop + endfacet + facet normal -0.427901 -0.14622 0.891919 + outer loop + vertex 0.898195 1.24657 2.61406 + vertex 0.896877 1.25196 2.61431 + vertex 0.894355 1.24808 2.61247 + endloop + endfacet + facet normal -0.440645 -0.136707 0.887211 + outer loop + vertex 0.892839 1.25289 2.6125 + vertex 0.894759 1.25661 2.61403 + vertex 0.890732 1.25759 2.61218 + endloop + endfacet + facet normal -0.424286 -0.128559 0.896356 + outer loop + vertex 0.897794 1.25599 2.61538 + vertex 0.897078 1.2599 2.6156 + vertex 0.894759 1.25661 2.61403 + endloop + endfacet + facet normal -0.423684 -0.141979 0.894614 + outer loop + vertex 0.899748 1.2537 2.61595 + vertex 0.896877 1.25196 2.61431 + vertex 0.900646 1.24978 2.61575 + endloop + endfacet + facet normal -0.431121 -0.129616 0.892936 + outer loop + vertex 0.897794 1.25599 2.61538 + vertex 0.900757 1.25763 2.61705 + vertex 0.897078 1.2599 2.6156 + endloop + endfacet + facet normal -0.448137 -0.146933 0.881807 + outer loop + vertex 0.900646 1.24978 2.61575 + vertex 0.90285 1.2529 2.61739 + vertex 0.899748 1.2537 2.61595 + endloop + endfacet + facet normal -0.426603 -0.126538 0.895543 + outer loop + vertex 0.893479 1.26133 2.61409 + vertex 0.894759 1.25661 2.61403 + vertex 0.897078 1.2599 2.6156 + endloop + endfacet + facet normal -0.440389 -0.116216 0.890254 + outer loop + vertex 0.893479 1.26133 2.61409 + vertex 0.892523 1.26635 2.61427 + vertex 0.88981 1.26296 2.61249 + endloop + endfacet + facet normal -0.427927 -0.104386 0.897765 + outer loop + vertex 0.891627 1.27177 2.61447 + vertex 0.892523 1.26635 2.61427 + vertex 0.895263 1.26958 2.61595 + endloop + endfacet + facet normal -0.420966 -0.105615 0.900907 + outer loop + vertex 0.899784 1.26304 2.61729 + vertex 0.898873 1.26816 2.61746 + vertex 0.89615 1.26472 2.61579 + endloop + endfacet + facet normal -0.414714 -0.103017 0.904102 + outer loop + vertex 0.895263 1.26958 2.61595 + vertex 0.89772 1.27301 2.61747 + vertex 0.894647 1.27357 2.61612 + endloop + endfacet + facet normal -0.448055 -0.0955616 0.888884 + outer loop + vertex 0.902526 1.2664 2.61912 + vertex 0.901726 1.27204 2.61932 + vertex 0.898873 1.26816 2.61746 + endloop + endfacet + facet normal -0.41845 -0.102967 0.902384 + outer loop + vertex 0.89772 1.27301 2.61747 + vertex 0.899851 1.27682 2.61889 + vertex 0.895819 1.27769 2.61712 + endloop + endfacet + facet normal -0.454611 -0.116778 0.883002 + outer loop + vertex 0.898645 1.28148 2.61889 + vertex 0.899851 1.27682 2.61889 + vertex 0.902109 1.27993 2.62047 + endloop + endfacet + facet normal -0.422626 -0.113231 0.899203 + outer loop + vertex 0.898645 1.28148 2.61889 + vertex 0.897702 1.28643 2.61907 + vertex 0.894912 1.28307 2.61734 + endloop + endfacet + facet normal -0.465522 -0.115209 0.877505 + outer loop + vertex 0.896759 1.29187 2.61928 + vertex 0.897702 1.28643 2.61907 + vertex 0.900567 1.28925 2.62096 + endloop + endfacet + facet normal -0.53681 -0.159164 0.828554 + outer loop + vertex 0.904203 1.28207 2.62211 + vertex 0.904558 1.28629 2.62315 + vertex 0.901335 1.28437 2.62069 + endloop + endfacet + facet normal -0.45764 -0.0999471 0.883502 + outer loop + vertex 0.899797 1.2935 2.62104 + vertex 0.896759 1.29187 2.61928 + vertex 0.900567 1.28925 2.62096 + endloop + endfacet + facet normal -0.421123 -0.106018 0.900786 + outer loop + vertex 0.896759 1.29187 2.61928 + vertex 0.894803 1.29663 2.61893 + vertex 0.892703 1.2929 2.61751 + endloop + endfacet + facet normal -0.478048 -0.118519 0.870301 + outer loop + vertex 0.89783 1.29595 2.62029 + vertex 0.900667 1.29764 2.62208 + vertex 0.897178 1.29994 2.62048 + endloop + endfacet + facet normal -0.4174 -0.10911 0.902149 + outer loop + vertex 0.894803 1.29663 2.61893 + vertex 0.893612 1.3014 2.61895 + vertex 0.890787 1.29758 2.61719 + endloop + endfacet + facet normal -0.417985 -0.108582 0.901941 + outer loop + vertex 0.890787 1.29758 2.61719 + vertex 0.893612 1.3014 2.61895 + vertex 0.889886 1.30295 2.61741 + endloop + endfacet + facet normal -0.417451 -0.106846 0.902396 + outer loop + vertex 0.893612 1.3014 2.61895 + vertex 0.892662 1.30647 2.61912 + vertex 0.889886 1.30295 2.61741 + endloop + endfacet + facet normal -0.427137 -0.108513 0.897652 + outer loop + vertex 0.892662 1.30647 2.61912 + vertex 0.893612 1.3014 2.61895 + vertex 0.896314 1.30481 2.62065 + endloop + endfacet + facet normal -0.472708 -0.107375 0.874653 + outer loop + vertex 0.900667 1.29764 2.62208 + vertex 0.899809 1.30305 2.62228 + vertex 0.897178 1.29994 2.62048 + endloop + endfacet + facet normal -0.420097 -0.0930917 0.902692 + outer loop + vertex 0.891704 1.31191 2.61928 + vertex 0.894737 1.31371 2.62088 + vertex 0.892824 1.31601 2.62023 + endloop + endfacet + facet normal -0.424831 -0.101667 0.899546 + outer loop + vertex 0.895412 1.30971 2.62078 + vertex 0.892662 1.30647 2.61912 + vertex 0.896314 1.30481 2.62065 + endloop + endfacet + facet normal -0.417532 -0.106768 0.902368 + outer loop + vertex 0.889886 1.30295 2.61741 + vertex 0.892662 1.30647 2.61912 + vertex 0.888896 1.308 2.61755 + endloop + endfacet + facet normal -0.424204 -0.109496 0.898922 + outer loop + vertex 0.890787 1.29758 2.61719 + vertex 0.889886 1.30295 2.61741 + vertex 0.887139 1.29975 2.61573 + endloop + endfacet + facet normal -0.42414 -0.109356 0.89897 + outer loop + vertex 0.887785 1.29583 2.61556 + vertex 0.890787 1.29758 2.61719 + vertex 0.887139 1.29975 2.61573 + endloop + endfacet + facet normal -0.439074 -0.109353 0.891772 + outer loop + vertex 0.882549 1.30626 2.61428 + vertex 0.883522 1.30121 2.61414 + vertex 0.886202 1.30458 2.61587 + endloop + endfacet + facet normal -0.45365 -0.111945 0.884121 + outer loop + vertex 0.883522 1.30121 2.61414 + vertex 0.882549 1.30626 2.61428 + vertex 0.879862 1.3029 2.61247 + endloop + endfacet + facet normal -0.457678 -0.107874 0.88255 + outer loop + vertex 0.879862 1.3029 2.61247 + vertex 0.882549 1.30626 2.61428 + vertex 0.878928 1.30795 2.61261 + endloop + endfacet + facet normal -0.435504 -0.110976 0.89332 + outer loop + vertex 0.887785 1.29583 2.61556 + vertex 0.887139 1.29975 2.61573 + vertex 0.884741 1.29645 2.61415 + endloop + endfacet + facet normal -0.4549 -0.118745 0.88259 + outer loop + vertex 0.880329 1.28943 2.61098 + vertex 0.882674 1.29273 2.61264 + vertex 0.879614 1.29339 2.61115 + endloop + endfacet + facet normal -0.473858 -0.121734 0.872147 + outer loop + vertex 0.879614 1.29339 2.61115 + vertex 0.876679 1.29166 2.60931 + vertex 0.880329 1.28943 2.61098 + endloop + endfacet + facet normal -0.49086 -0.11172 0.864045 + outer loop + vertex 0.876679 1.29166 2.60931 + vertex 0.873787 1.29702 2.60836 + vertex 0.873308 1.29201 2.60744 + endloop + endfacet + facet normal -0.45278 -0.109309 0.884896 + outer loop + vertex 0.880721 1.29747 2.61224 + vertex 0.883522 1.30121 2.61414 + vertex 0.879862 1.3029 2.61247 + endloop + endfacet + facet normal -0.489445 -0.112238 0.864781 + outer loop + vertex 0.874234 1.30211 2.60928 + vertex 0.873787 1.29702 2.60836 + vertex 0.877092 1.29998 2.61062 + endloop + endfacet + facet normal -0.498101 -0.104351 0.860817 + outer loop + vertex 0.87198 1.31168 2.60914 + vertex 0.873101 1.3064 2.60915 + vertex 0.87548 1.30949 2.6109 + endloop + endfacet + facet normal -0.473399 -0.110554 0.873883 + outer loop + vertex 0.879862 1.3029 2.61247 + vertex 0.878928 1.30795 2.61261 + vertex 0.876439 1.30478 2.61086 + endloop + endfacet + facet normal -0.483089 -0.104746 0.869283 + outer loop + vertex 0.87548 1.30949 2.6109 + vertex 0.877684 1.31275 2.61252 + vertex 0.874736 1.31346 2.61097 + endloop + endfacet + facet normal -0.458287 -0.109712 0.882007 + outer loop + vertex 0.882549 1.30626 2.61428 + vertex 0.881591 1.31168 2.61446 + vertex 0.878928 1.30795 2.61261 + endloop + endfacet + facet normal -0.47559 -0.0978386 0.874209 + outer loop + vertex 0.877684 1.31275 2.61252 + vertex 0.879683 1.31641 2.61402 + vertex 0.875775 1.31752 2.61201 + endloop + endfacet + facet normal -0.455833 -0.0955187 0.884925 + outer loop + vertex 0.882662 1.31571 2.61548 + vertex 0.882102 1.31966 2.61561 + vertex 0.879683 1.31641 2.61402 + endloop + endfacet + facet normal -0.443644 -0.108801 0.889574 + outer loop + vertex 0.884532 1.31339 2.61613 + vertex 0.881591 1.31168 2.61446 + vertex 0.885231 1.30943 2.61599 + endloop + endfacet + facet normal -0.423731 -0.105643 0.899606 + outer loop + vertex 0.885231 1.30943 2.61599 + vertex 0.887618 1.31278 2.61751 + vertex 0.884532 1.31339 2.61613 + endloop + endfacet + facet normal -0.413274 -0.0972426 0.9054 + outer loop + vertex 0.891704 1.31191 2.61928 + vertex 0.889737 1.31657 2.61889 + vertex 0.887618 1.31278 2.61751 + endloop + endfacet + facet normal -0.410157 -0.092272 0.907335 + outer loop + vertex 0.887992 1.32624 2.61909 + vertex 0.888635 1.32129 2.61887 + vertex 0.891554 1.3247 2.62054 + endloop + endfacet + facet normal -0.411904 -0.0911781 0.906654 + outer loop + vertex 0.88742 1.33129 2.61933 + vertex 0.887992 1.32624 2.61909 + vertex 0.891 1.32963 2.62079 + endloop + endfacet + facet normal -0.413842 -0.088887 0.905999 + outer loop + vertex 0.886681 1.33673 2.61953 + vertex 0.88742 1.33129 2.61933 + vertex 0.890331 1.33453 2.62098 + endloop + endfacet + facet normal -0.420078 -0.0844051 0.903554 + outer loop + vertex 0.887811 1.34085 2.62044 + vertex 0.884722 1.34143 2.61906 + vertex 0.886681 1.33673 2.61953 + endloop + endfacet + facet normal -0.444419 -0.0905532 0.89123 + outer loop + vertex 0.883774 1.33287 2.61777 + vertex 0.882642 1.33768 2.6177 + vertex 0.880208 1.33434 2.61615 + endloop + endfacet + facet normal -0.464063 -0.0876011 0.88146 + outer loop + vertex 0.876547 1.3366 2.61444 + vertex 0.877418 1.33118 2.61436 + vertex 0.880208 1.33434 2.61615 + endloop + endfacet + facet normal -0.479637 -0.086511 0.873192 + outer loop + vertex 0.876547 1.3366 2.61444 + vertex 0.873642 1.34192 2.61337 + vertex 0.873123 1.3369 2.61259 + endloop + endfacet + facet normal -0.459026 -0.0808138 0.884739 + outer loop + vertex 0.879551 1.33836 2.61621 + vertex 0.880666 1.34243 2.61716 + vertex 0.877483 1.34082 2.61537 + endloop + endfacet + facet normal -0.440672 -0.080413 0.894059 + outer loop + vertex 0.880666 1.34243 2.61716 + vertex 0.883562 1.34617 2.61893 + vertex 0.87995 1.34778 2.61729 + endloop + endfacet + facet normal -0.476576 -0.0856957 0.874947 + outer loop + vertex 0.87417 1.34693 2.61415 + vertex 0.873642 1.34192 2.61337 + vertex 0.877008 1.34488 2.6155 + endloop + endfacet + facet normal -0.489477 -0.0797812 0.868359 + outer loop + vertex 0.87417 1.34693 2.61415 + vertex 0.873313 1.35114 2.61406 + vertex 0.87073 1.34731 2.61225 + endloop + endfacet + facet normal -0.459776 -0.077967 0.884606 + outer loop + vertex 0.87995 1.34778 2.61729 + vertex 0.879517 1.35274 2.6175 + vertex 0.876589 1.3496 2.61571 + endloop + endfacet + facet normal -0.478188 -0.0745633 0.875087 + outer loop + vertex 0.872819 1.35609 2.61421 + vertex 0.873313 1.35114 2.61406 + vertex 0.876159 1.35441 2.61589 + endloop + endfacet + facet normal -0.490313 -0.0737114 0.868424 + outer loop + vertex 0.872819 1.35609 2.61421 + vertex 0.872389 1.36114 2.61439 + vertex 0.869502 1.35787 2.61249 + endloop + endfacet + facet normal -0.479918 -0.070761 0.874455 + outer loop + vertex 0.871711 1.3665 2.61446 + vertex 0.872389 1.36114 2.61439 + vertex 0.875203 1.36429 2.61619 + endloop + endfacet + facet normal -0.463196 -0.0725423 0.883282 + outer loop + vertex 0.879189 1.35773 2.61775 + vertex 0.878669 1.36277 2.61789 + vertex 0.875773 1.35939 2.6161 + endloop + endfacet + facet normal -0.466254 -0.0688439 0.881968 + outer loop + vertex 0.875203 1.36429 2.61619 + vertex 0.877621 1.36758 2.61773 + vertex 0.874639 1.36829 2.61621 + endloop + endfacet + facet normal -0.445606 -0.0711195 0.8924 + outer loop + vertex 0.882261 1.36117 2.61956 + vertex 0.881599 1.3666 2.61966 + vertex 0.878669 1.36277 2.61789 + endloop + endfacet + facet normal -0.459189 -0.061337 0.886219 + outer loop + vertex 0.877621 1.36758 2.61773 + vertex 0.879692 1.37126 2.61906 + vertex 0.875733 1.37233 2.61708 + endloop + endfacet + facet normal -0.441629 -0.0581654 0.89531 + outer loop + vertex 0.882743 1.37066 2.62052 + vertex 0.882154 1.37457 2.62049 + vertex 0.879692 1.37126 2.61906 + endloop + endfacet + facet normal -0.428854 -0.0708656 0.90059 + outer loop + vertex 0.884732 1.36851 2.6213 + vertex 0.881599 1.3666 2.61966 + vertex 0.885323 1.3645 2.62127 + endloop + endfacet + facet normal -0.421415 -0.0550246 0.905197 + outer loop + vertex 0.882743 1.37066 2.62052 + vertex 0.885779 1.37252 2.62205 + vertex 0.882154 1.37457 2.62049 + endloop + endfacet + facet normal -0.411924 -0.0684413 0.908644 + outer loop + vertex 0.885323 1.3645 2.62127 + vertex 0.888191 1.36835 2.62286 + vertex 0.884732 1.36851 2.6213 + endloop + endfacet + facet normal -0.418561 -0.0604399 0.906175 + outer loop + vertex 0.892069 1.36621 2.62451 + vertex 0.891495 1.37152 2.6246 + vertex 0.888191 1.36835 2.62286 + endloop + endfacet + facet normal -0.410802 -0.0568075 0.909953 + outer loop + vertex 0.888645 1.37208 2.62331 + vertex 0.889109 1.37577 2.62375 + vertex 0.885779 1.37252 2.62205 + endloop + endfacet + facet normal -0.426463 -0.0597761 0.902528 + outer loop + vertex 0.88835 1.38112 2.62375 + vertex 0.889109 1.37577 2.62375 + vertex 0.891949 1.3796 2.62535 + endloop + endfacet + facet normal -0.415283 -0.0588664 0.907786 + outer loop + vertex 0.88835 1.38112 2.62375 + vertex 0.887964 1.38618 2.6239 + vertex 0.8847 1.38277 2.62219 + endloop + endfacet + facet normal -0.475676 -0.0617844 0.877448 + outer loop + vertex 0.894815 1.38284 2.62715 + vertex 0.894448 1.38793 2.62731 + vertex 0.89145 1.38457 2.62544 + endloop + endfacet + facet normal -0.428641 -0.0578616 0.90162 + outer loop + vertex 0.88777 1.39114 2.62413 + vertex 0.887964 1.38618 2.6239 + vertex 0.89115 1.38953 2.62563 + endloop + endfacet + facet normal -0.420208 -0.0542557 0.905804 + outer loop + vertex 0.88777 1.39114 2.62413 + vertex 0.887658 1.39605 2.62437 + vertex 0.884356 1.39282 2.62264 + endloop + endfacet + facet normal -0.471108 -0.0468706 0.880829 + outer loop + vertex 0.894127 1.39286 2.62746 + vertex 0.893554 1.39691 2.62737 + vertex 0.890922 1.39429 2.62582 + endloop + endfacet + facet normal -0.432991 -0.0497481 0.900024 + outer loop + vertex 0.8875 1.40097 2.62457 + vertex 0.887658 1.39605 2.62437 + vertex 0.890888 1.39895 2.62608 + endloop + endfacet + facet normal -0.425665 -0.0444701 0.903787 + outer loop + vertex 0.8875 1.40097 2.62457 + vertex 0.887107 1.40601 2.62463 + vertex 0.884006 1.40279 2.62301 + endloop + endfacet + facet normal -0.436611 -0.0402569 0.898749 + outer loop + vertex 0.886452 1.41148 2.62456 + vertex 0.887107 1.40601 2.62463 + vertex 0.890177 1.40895 2.62625 + endloop + endfacet + facet normal -0.475172 -0.0454105 0.87872 + outer loop + vertex 0.894469 1.40133 2.62817 + vertex 0.893779 1.40675 2.62808 + vertex 0.890732 1.40386 2.62628 + endloop + endfacet + facet normal -0.433929 -0.0352931 0.900255 + outer loop + vertex 0.889613 1.41315 2.62614 + vertex 0.886452 1.41148 2.62456 + vertex 0.890177 1.40895 2.62625 + endloop + endfacet + facet normal -0.429089 -0.036026 0.902543 + outer loop + vertex 0.886452 1.41148 2.62456 + vertex 0.884633 1.41624 2.62388 + vertex 0.88245 1.41254 2.6227 + endloop + endfacet + facet normal -0.443782 -0.0358828 0.895416 + outer loop + vertex 0.887666 1.41556 2.62529 + vertex 0.890693 1.41734 2.62686 + vertex 0.887166 1.41957 2.6252 + endloop + endfacet + facet normal -0.433636 -0.0331962 0.900477 + outer loop + vertex 0.884633 1.41624 2.62388 + vertex 0.883678 1.42103 2.6236 + vertex 0.880689 1.41725 2.62202 + endloop + endfacet + facet normal -0.430104 -0.0309087 0.90225 + outer loop + vertex 0.883251 1.42604 2.62357 + vertex 0.883678 1.42103 2.6236 + vertex 0.886682 1.42446 2.62515 + endloop + endfacet + facet normal -0.442479 -0.0332697 0.896161 + outer loop + vertex 0.890693 1.41734 2.62686 + vertex 0.890091 1.42275 2.62677 + vertex 0.887166 1.41957 2.6252 + endloop + endfacet + facet normal -0.488957 -0.0355212 0.871584 + outer loop + vertex 0.890091 1.42275 2.62677 + vertex 0.893065 1.42602 2.62857 + vertex 0.889815 1.42782 2.62682 + endloop + endfacet + facet normal -0.435656 -0.029502 0.89963 + outer loop + vertex 0.883251 1.42604 2.62357 + vertex 0.88312 1.43104 2.62367 + vertex 0.879835 1.42765 2.62196 + endloop + endfacet + facet normal -0.444165 -0.0312311 0.8954 + outer loop + vertex 0.889815 1.42782 2.62682 + vertex 0.889734 1.43284 2.62695 + vertex 0.886483 1.42946 2.62522 + endloop + endfacet + facet normal -0.49133 -0.0313188 0.87041 + outer loop + vertex 0.889815 1.42782 2.62682 + vertex 0.892931 1.43105 2.62869 + vertex 0.889734 1.43284 2.62695 + endloop + endfacet + facet normal -0.491624 -0.0320291 0.870218 + outer loop + vertex 0.892931 1.43105 2.62869 + vertex 0.892872 1.43606 2.62884 + vertex 0.889734 1.43284 2.62695 + endloop + endfacet + facet normal -0.488632 -0.0347289 0.871799 + outer loop + vertex 0.893065 1.42602 2.62857 + vertex 0.892931 1.43105 2.62869 + vertex 0.889815 1.42782 2.62682 + endloop + endfacet + facet normal -0.494681 -0.0281046 0.86862 + outer loop + vertex 0.889734 1.43284 2.62695 + vertex 0.892872 1.43606 2.62884 + vertex 0.889699 1.43783 2.62709 + endloop + endfacet + facet normal -0.494577 -0.0278505 0.868688 + outer loop + vertex 0.892872 1.43606 2.62884 + vertex 0.892807 1.44104 2.62897 + vertex 0.889699 1.43783 2.62709 + endloop + endfacet + facet normal -0.497373 -0.0242784 0.867197 + outer loop + vertex 0.889699 1.43783 2.62709 + vertex 0.892807 1.44104 2.62897 + vertex 0.889638 1.44282 2.6272 + endloop + endfacet + facet normal -0.498316 -0.0265742 0.866588 + outer loop + vertex 0.892807 1.44104 2.62897 + vertex 0.892715 1.44603 2.62907 + vertex 0.889638 1.44282 2.6272 + endloop + endfacet + facet normal -0.43244 -0.0269931 0.901259 + outer loop + vertex 0.883091 1.43603 2.6238 + vertex 0.88312 1.43104 2.62367 + vertex 0.88644 1.43445 2.62536 + endloop + endfacet + facet normal -0.435156 -0.0231102 0.900058 + outer loop + vertex 0.883091 1.43603 2.6238 + vertex 0.883045 1.44102 2.62391 + vertex 0.879716 1.43764 2.62221 + endloop + endfacet + facet normal -0.448783 -0.0242229 0.893313 + outer loop + vertex 0.889699 1.43783 2.62709 + vertex 0.889638 1.44282 2.6272 + vertex 0.886407 1.43943 2.62548 + endloop + endfacet + facet normal -0.501349 -0.0227118 0.864947 + outer loop + vertex 0.889638 1.44282 2.6272 + vertex 0.892715 1.44603 2.62907 + vertex 0.889549 1.4478 2.62728 + endloop + endfacet + facet normal -0.502179 -0.024734 0.86441 + outer loop + vertex 0.892715 1.44603 2.62907 + vertex 0.892622 1.45101 2.62916 + vertex 0.889549 1.4478 2.62728 + endloop + endfacet + facet normal -0.50492 -0.0212306 0.862905 + outer loop + vertex 0.889549 1.4478 2.62728 + vertex 0.892622 1.45101 2.62916 + vertex 0.889465 1.45279 2.62735 + endloop + endfacet + facet normal -0.505038 -0.0215155 0.862829 + outer loop + vertex 0.892622 1.45101 2.62916 + vertex 0.892547 1.45601 2.62924 + vertex 0.889465 1.45279 2.62735 + endloop + endfacet + facet normal -0.434842 -0.0194188 0.900297 + outer loop + vertex 0.882962 1.446 2.62397 + vertex 0.883045 1.44102 2.62391 + vertex 0.886334 1.44442 2.62557 + endloop + endfacet + facet normal -0.43701 -0.0172089 0.899292 + outer loop + vertex 0.882962 1.446 2.62397 + vertex 0.882875 1.45099 2.62403 + vertex 0.879573 1.44764 2.62236 + endloop + endfacet + facet normal -0.453681 -0.0207765 0.890922 + outer loop + vertex 0.889549 1.4478 2.62728 + vertex 0.889465 1.45279 2.62735 + vertex 0.886243 1.4494 2.62563 + endloop + endfacet + facet normal -0.505796 -0.0205422 0.862408 + outer loop + vertex 0.889465 1.45279 2.62735 + vertex 0.892547 1.45601 2.62924 + vertex 0.889392 1.45779 2.62743 + endloop + endfacet + facet normal -0.505787 -0.0205212 0.862414 + outer loop + vertex 0.892547 1.45601 2.62924 + vertex 0.892478 1.461 2.62932 + vertex 0.889392 1.45779 2.62743 + endloop + endfacet + facet normal -0.507589 -0.0182013 0.861407 + outer loop + vertex 0.889392 1.45779 2.62743 + vertex 0.892478 1.461 2.62932 + vertex 0.88933 1.46278 2.6275 + endloop + endfacet + facet normal -0.507351 -0.0176259 0.861559 + outer loop + vertex 0.892478 1.461 2.62932 + vertex 0.892418 1.46599 2.62938 + vertex 0.88933 1.46278 2.6275 + endloop + endfacet + facet normal -0.438426 -0.0169721 0.898607 + outer loop + vertex 0.882799 1.45598 2.62409 + vertex 0.882875 1.45099 2.62403 + vertex 0.886162 1.45439 2.6257 + endloop + endfacet + facet normal -0.439762 -0.0174526 0.897945 + outer loop + vertex 0.882799 1.45598 2.62409 + vertex 0.882731 1.46096 2.62415 + vertex 0.879431 1.45762 2.62247 + endloop + endfacet + facet normal -0.457501 -0.0179584 0.889028 + outer loop + vertex 0.889392 1.45779 2.62743 + vertex 0.88933 1.46278 2.6275 + vertex 0.886092 1.45938 2.62576 + endloop + endfacet + facet normal -0.507549 -0.0173699 0.861448 + outer loop + vertex 0.88933 1.46278 2.6275 + vertex 0.892418 1.46599 2.62938 + vertex 0.889269 1.46777 2.62756 + endloop + endfacet + facet normal -0.507322 -0.0168215 0.861592 + outer loop + vertex 0.892418 1.46599 2.62938 + vertex 0.892364 1.47098 2.62945 + vertex 0.889269 1.46777 2.62756 + endloop + endfacet + facet normal -0.507934 -0.0160274 0.861247 + outer loop + vertex 0.889269 1.46777 2.62756 + vertex 0.892364 1.47098 2.62945 + vertex 0.889214 1.47276 2.62762 + endloop + endfacet + facet normal -0.507849 -0.0158228 0.861301 + outer loop + vertex 0.892364 1.47098 2.62945 + vertex 0.892322 1.47596 2.62951 + vertex 0.889214 1.47276 2.62762 + endloop + endfacet + facet normal -0.440147 -0.0178131 0.897749 + outer loop + vertex 0.882662 1.46595 2.62421 + vertex 0.882731 1.46096 2.62415 + vertex 0.886024 1.46438 2.62583 + endloop + endfacet + facet normal -0.440174 -0.0173464 0.897745 + outer loop + vertex 0.882662 1.46595 2.62421 + vertex 0.882593 1.47095 2.62428 + vertex 0.879296 1.46759 2.62259 + endloop + endfacet + facet normal -0.456179 -0.0158052 0.889748 + outer loop + vertex 0.889269 1.46777 2.62756 + vertex 0.889214 1.47276 2.62762 + vertex 0.885959 1.46937 2.62589 + endloop + endfacet + facet normal -0.508544 -0.0149147 0.860907 + outer loop + vertex 0.889214 1.47276 2.62762 + vertex 0.892322 1.47596 2.62951 + vertex 0.889169 1.47776 2.62768 + endloop + endfacet + facet normal -0.508107 -0.0138664 0.861182 + outer loop + vertex 0.892322 1.47596 2.62951 + vertex 0.892293 1.48096 2.62958 + vertex 0.889169 1.47776 2.62768 + endloop + endfacet + facet normal -0.509748 -0.0117112 0.860244 + outer loop + vertex 0.889169 1.47776 2.62768 + vertex 0.892293 1.48096 2.62958 + vertex 0.88914 1.48276 2.62773 + endloop + endfacet + facet normal -0.510095 -0.0125396 0.860027 + outer loop + vertex 0.892293 1.48096 2.62958 + vertex 0.892267 1.48596 2.62963 + vertex 0.88914 1.48276 2.62773 + endloop + endfacet + facet normal -0.438892 -0.0153575 0.898409 + outer loop + vertex 0.88253 1.47594 2.62433 + vertex 0.882593 1.47095 2.62428 + vertex 0.8859 1.47436 2.62595 + endloop + endfacet + facet normal -0.43831 -0.0120889 0.898743 + outer loop + vertex 0.88253 1.47594 2.62433 + vertex 0.882479 1.48093 2.62437 + vertex 0.879161 1.47757 2.62271 + endloop + endfacet + facet normal -0.456799 -0.0117088 0.889493 + outer loop + vertex 0.889169 1.47776 2.62768 + vertex 0.88914 1.48276 2.62773 + vertex 0.885852 1.47936 2.626 + endloop + endfacet + facet normal -0.512601 -0.00922245 0.858577 + outer loop + vertex 0.88914 1.48276 2.62773 + vertex 0.892267 1.48596 2.62963 + vertex 0.889121 1.48778 2.62778 + endloop + endfacet + facet normal -0.512993 -0.0101479 0.858333 + outer loop + vertex 0.892267 1.48596 2.62963 + vertex 0.892245 1.49096 2.62968 + vertex 0.889121 1.48778 2.62778 + endloop + endfacet + facet normal -0.51622 -0.0058396 0.856436 + outer loop + vertex 0.889121 1.48778 2.62778 + vertex 0.892245 1.49096 2.62968 + vertex 0.88911 1.49281 2.6278 + endloop + endfacet + facet normal -0.516196 -0.00578326 0.856451 + outer loop + vertex 0.892245 1.49096 2.62968 + vertex 0.892233 1.49598 2.62971 + vertex 0.88911 1.49281 2.6278 + endloop + endfacet + facet normal -0.44 -0.00778872 0.897964 + outer loop + vertex 0.882446 1.48592 2.6244 + vertex 0.882479 1.48093 2.62437 + vertex 0.885819 1.48436 2.62604 + endloop + endfacet + facet normal -0.438473 -0.00412331 0.898735 + outer loop + vertex 0.882446 1.48592 2.6244 + vertex 0.88243 1.49091 2.62442 + vertex 0.87908 1.48754 2.62277 + endloop + endfacet + facet normal -0.460526 -0.00588359 0.887627 + outer loop + vertex 0.889121 1.48778 2.62778 + vertex 0.88911 1.49281 2.6278 + vertex 0.885802 1.48937 2.62606 + endloop + endfacet + facet normal -0.518014 -0.00334386 0.855366 + outer loop + vertex 0.88911 1.49281 2.6278 + vertex 0.892233 1.49598 2.62971 + vertex 0.889099 1.49784 2.62782 + endloop + endfacet + facet normal -0.518501 -0.00447788 0.855065 + outer loop + vertex 0.892233 1.49598 2.62971 + vertex 0.892213 1.50101 2.62972 + vertex 0.889099 1.49784 2.62782 + endloop + endfacet + facet normal -0.520098 -0.00233443 0.854103 + outer loop + vertex 0.889099 1.49784 2.62782 + vertex 0.892213 1.50101 2.62972 + vertex 0.889085 1.50285 2.62782 + endloop + endfacet + facet normal -0.520161 -0.00248122 0.854065 + outer loop + vertex 0.892213 1.50101 2.62972 + vertex 0.89219 1.50602 2.62972 + vertex 0.889085 1.50285 2.62782 + endloop + endfacet + facet normal -0.520721 -0.00173079 0.853725 + outer loop + vertex 0.889085 1.50285 2.62782 + vertex 0.89219 1.50602 2.62972 + vertex 0.889073 1.50785 2.62782 + endloop + endfacet + facet normal -0.520034 -0.000118651 0.854146 + outer loop + vertex 0.89219 1.50602 2.62972 + vertex 0.892182 1.51103 2.62972 + vertex 0.889073 1.50785 2.62782 + endloop + endfacet + facet normal -0.520028 -0.000125974 0.854149 + outer loop + vertex 0.889073 1.50785 2.62782 + vertex 0.892182 1.51103 2.62972 + vertex 0.889071 1.51284 2.62782 + endloop + endfacet + facet normal -0.519922 0.000124033 0.854213 + outer loop + vertex 0.892182 1.51103 2.62972 + vertex 0.892183 1.51603 2.62972 + vertex 0.889071 1.51284 2.62782 + endloop + endfacet + facet normal -0.51979 -5.24827e-05 0.854294 + outer loop + vertex 0.889071 1.51284 2.62782 + vertex 0.892183 1.51603 2.62972 + vertex 0.889072 1.51782 2.62783 + endloop + endfacet + facet normal -0.520036 -0.000635092 0.854144 + outer loop + vertex 0.892183 1.51603 2.62972 + vertex 0.892183 1.52101 2.62972 + vertex 0.889072 1.51782 2.62783 + endloop + endfacet + facet normal -0.521743 0.00165035 0.853101 + outer loop + vertex 0.889072 1.51782 2.62783 + vertex 0.892183 1.52101 2.62972 + vertex 0.88908 1.52282 2.62782 + endloop + endfacet + facet normal -0.521174 0.00299338 0.853445 + outer loop + vertex 0.892183 1.52101 2.62972 + vertex 0.892191 1.52601 2.62971 + vertex 0.88908 1.52282 2.62782 + endloop + endfacet + facet normal -0.521077 0.00286385 0.853505 + outer loop + vertex 0.88908 1.52282 2.62782 + vertex 0.892191 1.52601 2.62971 + vertex 0.889086 1.52781 2.62781 + endloop + endfacet + facet normal -0.520679 0.00380427 0.853744 + outer loop + vertex 0.892191 1.52601 2.62971 + vertex 0.892191 1.531 2.62969 + vertex 0.889086 1.52781 2.62781 + endloop + endfacet + facet normal -0.520353 0.00336852 0.853944 + outer loop + vertex 0.889086 1.52781 2.62781 + vertex 0.892191 1.531 2.62969 + vertex 0.889088 1.53279 2.62779 + endloop + endfacet + facet normal -0.518656 0.00737282 0.854951 + outer loop + vertex 0.892191 1.531 2.62969 + vertex 0.892201 1.53599 2.62965 + vertex 0.889088 1.53279 2.62779 + endloop + endfacet + facet normal -0.517106 0.00530946 0.855905 + outer loop + vertex 0.889088 1.53279 2.62779 + vertex 0.892201 1.53599 2.62965 + vertex 0.889095 1.53776 2.62776 + endloop + endfacet + facet normal -0.516163 0.00754411 0.856457 + outer loop + vertex 0.892201 1.53599 2.62965 + vertex 0.892215 1.54097 2.62961 + vertex 0.889095 1.53776 2.62776 + endloop + endfacet + facet normal -0.515125 0.00616489 0.857093 + outer loop + vertex 0.889095 1.53776 2.62776 + vertex 0.892215 1.54097 2.62961 + vertex 0.889106 1.54273 2.62773 + endloop + endfacet + facet normal -0.513924 0.00902853 0.857788 + outer loop + vertex 0.892215 1.54097 2.62961 + vertex 0.892239 1.54595 2.62958 + vertex 0.889106 1.54273 2.62773 + endloop + endfacet + facet normal -0.441022 -0.00265815 0.897492 + outer loop + vertex 0.882422 1.4959 2.62443 + vertex 0.88243 1.49091 2.62442 + vertex 0.885794 1.49438 2.62608 + endloop + endfacet + facet normal -0.438248 -0.00292983 0.898849 + outer loop + vertex 0.882422 1.4959 2.62443 + vertex 0.882413 1.50089 2.62444 + vertex 0.879056 1.49752 2.62279 + endloop + endfacet + facet normal -0.463163 -0.00221036 0.88627 + outer loop + vertex 0.889099 1.49784 2.62782 + vertex 0.889085 1.50285 2.62782 + vertex 0.885785 1.49938 2.62609 + endloop + endfacet + facet normal -0.439797 -0.00276515 0.898093 + outer loop + vertex 0.882402 1.50587 2.62445 + vertex 0.882413 1.50089 2.62444 + vertex 0.885775 1.50437 2.6261 + endloop + endfacet + facet normal -0.437176 -0.00103992 0.899375 + outer loop + vertex 0.882402 1.50587 2.62445 + vertex 0.882394 1.51086 2.62445 + vertex 0.879034 1.50749 2.62281 + endloop + endfacet + facet normal -0.4626 -9.39036e-05 0.886567 + outer loop + vertex 0.889073 1.50785 2.62782 + vertex 0.889071 1.51284 2.62782 + vertex 0.885766 1.50935 2.6261 + endloop + endfacet + facet normal -0.440826 0.0014974 0.897591 + outer loop + vertex 0.882397 1.51585 2.62444 + vertex 0.882394 1.51086 2.62445 + vertex 0.885765 1.51434 2.6261 + endloop + endfacet + facet normal -0.438522 0.00315997 0.898715 + outer loop + vertex 0.882397 1.51585 2.62444 + vertex 0.882409 1.52084 2.62443 + vertex 0.879038 1.51747 2.6228 + endloop + endfacet + facet normal -0.464434 0.0016017 0.885606 + outer loop + vertex 0.889072 1.51782 2.62783 + vertex 0.88908 1.52282 2.62782 + vertex 0.885773 1.51933 2.62609 + endloop + endfacet + facet normal -0.442674 0.00321527 0.896677 + outer loop + vertex 0.882423 1.52584 2.62442 + vertex 0.882409 1.52084 2.62443 + vertex 0.885782 1.52432 2.62608 + endloop + endfacet + facet normal -0.44027 0.00263756 0.897862 + outer loop + vertex 0.882423 1.52584 2.62442 + vertex 0.882435 1.53083 2.62441 + vertex 0.87907 1.52746 2.62277 + endloop + endfacet + facet normal -0.464664 0.00346693 0.885481 + outer loop + vertex 0.889086 1.52781 2.62781 + vertex 0.889088 1.53279 2.62779 + vertex 0.885792 1.52931 2.62607 + endloop + endfacet + facet normal -0.442129 0.00233985 0.896948 + outer loop + vertex 0.882443 1.53582 2.6244 + vertex 0.882435 1.53083 2.62441 + vertex 0.885798 1.5343 2.62606 + endloop + endfacet + facet normal -0.44039 0.0032686 0.897801 + outer loop + vertex 0.882443 1.53582 2.6244 + vertex 0.882453 1.54082 2.62439 + vertex 0.879091 1.53745 2.62275 + endloop + endfacet + facet normal -0.460853 0.00621085 0.887455 + outer loop + vertex 0.889095 1.53776 2.62776 + vertex 0.889106 1.54273 2.62773 + vertex 0.885805 1.53928 2.62604 + endloop + endfacet + facet normal -0.513054 0.00787739 0.85832 + outer loop + vertex 0.889106 1.54273 2.62773 + vertex 0.892239 1.54595 2.62958 + vertex 0.889128 1.54769 2.6277 + endloop + endfacet + facet normal -0.511927 0.0105871 0.858964 + outer loop + vertex 0.892239 1.54595 2.62958 + vertex 0.892271 1.55092 2.62953 + vertex 0.889128 1.54769 2.6277 + endloop + endfacet + facet normal -0.512055 0.0107568 0.858885 + outer loop + vertex 0.889128 1.54769 2.6277 + vertex 0.892271 1.55092 2.62953 + vertex 0.889159 1.55265 2.62766 + endloop + endfacet + facet normal -0.510564 0.0143422 0.85972 + outer loop + vertex 0.892271 1.55092 2.62953 + vertex 0.892318 1.55589 2.62948 + vertex 0.889159 1.55265 2.62766 + endloop + endfacet + facet normal -0.440822 0.00538554 0.897578 + outer loop + vertex 0.882468 1.54581 2.62437 + vertex 0.882453 1.54082 2.62439 + vertex 0.885819 1.54426 2.62602 + endloop + endfacet + facet normal -0.439987 0.00868363 0.897962 + outer loop + vertex 0.882468 1.54581 2.62437 + vertex 0.882494 1.5508 2.62433 + vertex 0.879123 1.54745 2.62271 + endloop + endfacet + facet normal -0.458175 0.0106767 0.888798 + outer loop + vertex 0.889128 1.54769 2.6277 + vertex 0.889159 1.55265 2.62766 + vertex 0.885841 1.54924 2.62599 + endloop + endfacet + facet normal -0.510613 0.0144067 0.85969 + outer loop + vertex 0.889159 1.55265 2.62766 + vertex 0.892318 1.55589 2.62948 + vertex 0.889199 1.55762 2.6276 + endloop + endfacet + facet normal -0.509599 0.0168349 0.860247 + outer loop + vertex 0.892318 1.55589 2.62948 + vertex 0.892369 1.56085 2.62941 + vertex 0.889199 1.55762 2.6276 + endloop + endfacet + facet normal -0.512013 0.0200478 0.858743 + outer loop + vertex 0.889199 1.55762 2.6276 + vertex 0.892369 1.56085 2.62941 + vertex 0.889254 1.56261 2.62751 + endloop + endfacet + facet normal -0.510956 0.0225368 0.859311 + outer loop + vertex 0.892369 1.56085 2.62941 + vertex 0.892432 1.56584 2.62932 + vertex 0.889254 1.56261 2.62751 + endloop + endfacet + facet normal -0.440318 0.0131622 0.897745 + outer loop + vertex 0.882534 1.5558 2.62428 + vertex 0.882494 1.5508 2.62433 + vertex 0.885874 1.55422 2.62594 + endloop + endfacet + facet normal -0.439211 0.0176915 0.89821 + outer loop + vertex 0.882534 1.5558 2.62428 + vertex 0.88259 1.5608 2.62421 + vertex 0.879203 1.55744 2.62262 + endloop + endfacet + facet normal -0.458301 0.0199571 0.888573 + outer loop + vertex 0.889199 1.55762 2.6276 + vertex 0.889254 1.56261 2.62751 + vertex 0.88592 1.55921 2.62587 + endloop + endfacet + facet normal -0.510862 0.0224112 0.85937 + outer loop + vertex 0.889254 1.56261 2.62751 + vertex 0.892432 1.56584 2.62932 + vertex 0.889318 1.5676 2.62742 + endloop + endfacet + facet normal -0.510469 0.0233311 0.85958 + outer loop + vertex 0.892432 1.56584 2.62932 + vertex 0.892495 1.57083 2.62922 + vertex 0.889318 1.5676 2.62742 + endloop + endfacet + facet normal -0.510335 0.0231515 0.859664 + outer loop + vertex 0.889318 1.5676 2.62742 + vertex 0.892495 1.57083 2.62922 + vertex 0.889389 1.57259 2.62733 + endloop + endfacet + facet normal -0.510034 0.0238496 0.859823 + outer loop + vertex 0.892495 1.57083 2.62922 + vertex 0.892563 1.57582 2.62912 + vertex 0.889389 1.57259 2.62733 + endloop + endfacet + facet normal -0.439395 0.0209828 0.898049 + outer loop + vertex 0.882664 1.56579 2.62413 + vertex 0.88259 1.5608 2.62421 + vertex 0.885983 1.56421 2.62579 + endloop + endfacet + facet normal -0.438131 0.0217248 0.898649 + outer loop + vertex 0.882664 1.56579 2.62413 + vertex 0.882749 1.57079 2.62405 + vertex 0.879344 1.56743 2.62247 + endloop + endfacet + facet normal -0.45841 0.0229382 0.888445 + outer loop + vertex 0.889318 1.5676 2.62742 + vertex 0.889389 1.57259 2.62733 + vertex 0.88606 1.5692 2.6257 + endloop + endfacet + facet normal -0.508738 0.0221223 0.860637 + outer loop + vertex 0.889389 1.57259 2.62733 + vertex 0.892563 1.57582 2.62912 + vertex 0.889462 1.57758 2.62724 + endloop + endfacet + facet normal -0.50791 0.0240427 0.861074 + outer loop + vertex 0.892563 1.57582 2.62912 + vertex 0.892634 1.58082 2.62902 + vertex 0.889462 1.57758 2.62724 + endloop + endfacet + facet normal -0.506206 0.0217839 0.862137 + outer loop + vertex 0.889462 1.57758 2.62724 + vertex 0.892634 1.58082 2.62902 + vertex 0.889531 1.58258 2.62716 + endloop + endfacet + facet normal -0.505523 0.0233694 0.862497 + outer loop + vertex 0.892634 1.58082 2.62902 + vertex 0.892703 1.58581 2.62893 + vertex 0.889531 1.58258 2.62716 + endloop + endfacet + facet normal -0.43718 0.0206957 0.899136 + outer loop + vertex 0.882836 1.57578 2.62397 + vertex 0.882749 1.57079 2.62405 + vertex 0.886142 1.57419 2.62562 + endloop + endfacet + facet normal -0.436346 0.0196552 0.899564 + outer loop + vertex 0.882836 1.57578 2.62397 + vertex 0.882913 1.58076 2.6239 + vertex 0.879512 1.57741 2.62233 + endloop + endfacet + facet normal -0.45647 0.0215595 0.889478 + outer loop + vertex 0.889462 1.57758 2.62724 + vertex 0.889531 1.58258 2.62716 + vertex 0.886221 1.57918 2.62554 + endloop + endfacet + facet normal -0.505665 0.0235572 0.862408 + outer loop + vertex 0.889531 1.58258 2.62716 + vertex 0.892703 1.58581 2.62893 + vertex 0.889598 1.58757 2.62706 + endloop + endfacet + facet normal -0.503717 0.0280528 0.863413 + outer loop + vertex 0.892703 1.58581 2.62893 + vertex 0.892788 1.59082 2.62882 + vertex 0.889598 1.58757 2.62706 + endloop + endfacet + facet normal -0.503214 0.0273881 0.863728 + outer loop + vertex 0.889598 1.58757 2.62706 + vertex 0.892788 1.59082 2.62882 + vertex 0.889675 1.59257 2.62695 + endloop + endfacet + facet normal -0.501279 0.0318472 0.864699 + outer loop + vertex 0.892788 1.59082 2.62882 + vertex 0.892885 1.5958 2.62869 + vertex 0.889675 1.59257 2.62695 + endloop + endfacet + facet normal -0.435928 0.0205197 0.899748 + outer loop + vertex 0.882976 1.58575 2.62382 + vertex 0.882913 1.58076 2.6239 + vertex 0.886289 1.58417 2.62546 + endloop + endfacet + facet normal -0.435372 0.023503 0.899944 + outer loop + vertex 0.882976 1.58575 2.62382 + vertex 0.883039 1.59075 2.62372 + vertex 0.879649 1.58738 2.62217 + endloop + endfacet + facet normal -0.453014 0.0272378 0.891087 + outer loop + vertex 0.889598 1.58757 2.62706 + vertex 0.889675 1.59257 2.62695 + vertex 0.886351 1.58917 2.62536 + endloop + endfacet + facet normal -0.501458 0.0320858 0.864587 + outer loop + vertex 0.889675 1.59257 2.62695 + vertex 0.892885 1.5958 2.62869 + vertex 0.88978 1.59755 2.62682 + endloop + endfacet + facet normal -0.499788 0.0359123 0.865403 + outer loop + vertex 0.892885 1.5958 2.62869 + vertex 0.892983 1.60074 2.62854 + vertex 0.88978 1.59755 2.62682 + endloop + endfacet + facet normal -0.500198 0.0364642 0.865143 + outer loop + vertex 0.88978 1.59755 2.62682 + vertex 0.892983 1.60074 2.62854 + vertex 0.889913 1.60244 2.62669 + endloop + endfacet + facet normal -0.498483 0.0404503 0.865955 + outer loop + vertex 0.892983 1.60074 2.62854 + vertex 0.893017 1.60566 2.62833 + vertex 0.889913 1.60244 2.62669 + endloop + endfacet + facet normal -0.434244 0.0276133 0.900372 + outer loop + vertex 0.883151 1.59579 2.62362 + vertex 0.883039 1.59075 2.62372 + vertex 0.886435 1.59417 2.62525 + endloop + endfacet + facet normal -0.435193 0.031194 0.899796 + outer loop + vertex 0.883151 1.59579 2.62362 + vertex 0.883415 1.60094 2.62357 + vertex 0.879848 1.59745 2.62196 + endloop + endfacet + facet normal -0.449205 0.0358147 0.892711 + outer loop + vertex 0.88978 1.59755 2.62682 + vertex 0.889913 1.60244 2.62669 + vertex 0.886596 1.59918 2.62516 + endloop + endfacet + facet normal -0.497267 0.0388871 0.866726 + outer loop + vertex 0.889913 1.60244 2.62669 + vertex 0.893017 1.60566 2.62833 + vertex 0.889971 1.60696 2.62653 + endloop + endfacet + facet normal -0.495795 0.0432355 0.867363 + outer loop + vertex 0.889971 1.60696 2.62653 + vertex 0.893017 1.60566 2.62833 + vertex 0.892723 1.61091 2.6279 + endloop + endfacet + facet normal -0.431308 0.0344517 0.901547 + outer loop + vertex 0.884084 1.60658 2.62367 + vertex 0.883415 1.60094 2.62357 + vertex 0.886914 1.60404 2.62512 + endloop + endfacet + facet normal -0.42817 0.0372361 0.902931 + outer loop + vertex 0.884084 1.60658 2.62367 + vertex 0.88698 1.61106 2.62486 + vertex 0.883582 1.61165 2.62323 + endloop + endfacet + facet normal -0.447131 0.0438769 0.893392 + outer loop + vertex 0.889502 1.61026 2.62613 + vertex 0.887506 1.60786 2.62525 + vertex 0.889971 1.60696 2.62653 + endloop + endfacet + facet normal -0.487426 0.0356402 0.872437 + outer loop + vertex 0.889502 1.61026 2.62613 + vertex 0.889971 1.60696 2.62653 + vertex 0.892723 1.61091 2.6279 + endloop + endfacet + facet normal -0.442586 0.0414174 0.895769 + outer loop + vertex 0.886957 1.61556 2.62464 + vertex 0.88698 1.61106 2.62486 + vertex 0.890108 1.61396 2.62627 + endloop + endfacet + facet normal -0.427137 0.0471473 0.902957 + outer loop + vertex 0.886957 1.61556 2.62464 + vertex 0.887167 1.62061 2.62448 + vertex 0.883101 1.61671 2.62276 + endloop + endfacet + facet normal -0.488972 0.0504531 0.870839 + outer loop + vertex 0.893576 1.61646 2.62808 + vertex 0.894439 1.62205 2.62824 + vertex 0.890575 1.61889 2.62625 + endloop + endfacet + facet normal -0.441032 0.0512533 0.896027 + outer loop + vertex 0.887446 1.62574 2.62432 + vertex 0.887167 1.62061 2.62448 + vertex 0.890842 1.62406 2.62609 + endloop + endfacet + facet normal -0.42457 0.0520093 0.9039 + outer loop + vertex 0.887446 1.62574 2.62432 + vertex 0.887614 1.63076 2.62411 + vertex 0.884115 1.62735 2.62266 + endloop + endfacet + facet normal -0.486803 0.0511335 0.872014 + outer loop + vertex 0.894182 1.62742 2.62774 + vertex 0.894229 1.63245 2.62747 + vertex 0.890932 1.62916 2.62583 + endloop + endfacet + facet normal -0.437093 0.0526977 0.897871 + outer loop + vertex 0.887801 1.63578 2.62391 + vertex 0.887614 1.63076 2.62411 + vertex 0.89106 1.63418 2.62559 + endloop + endfacet + facet normal -0.423524 0.0549345 0.904218 + outer loop + vertex 0.887801 1.63578 2.62391 + vertex 0.888165 1.64095 2.62376 + vertex 0.88449 1.63737 2.62226 + endloop + endfacet + facet normal -0.485396 0.060333 0.87221 + outer loop + vertex 0.894367 1.6375 2.62722 + vertex 0.894573 1.64249 2.62699 + vertex 0.891296 1.63922 2.6254 + endloop + endfacet + facet normal -0.568502 0.0613583 0.820391 + outer loop + vertex 0.894367 1.6375 2.62722 + vertex 0.897428 1.6406 2.62911 + vertex 0.894573 1.64249 2.62699 + endloop + endfacet + facet normal -0.566122 0.0663674 0.821645 + outer loop + vertex 0.897428 1.6406 2.62911 + vertex 0.897531 1.64564 2.62878 + vertex 0.894573 1.64249 2.62699 + endloop + endfacet + facet normal -0.566078 0.066306 0.82168 + outer loop + vertex 0.894573 1.64249 2.62699 + vertex 0.897531 1.64564 2.62878 + vertex 0.894746 1.64709 2.62674 + endloop + endfacet + facet normal -0.565138 0.0687315 0.822128 + outer loop + vertex 0.894746 1.64709 2.62674 + vertex 0.897531 1.64564 2.62878 + vertex 0.897349 1.65091 2.62821 + endloop + endfacet + facet normal -0.437791 0.0612594 0.896987 + outer loop + vertex 0.888976 1.64666 2.62377 + vertex 0.888165 1.64095 2.62376 + vertex 0.891727 1.64416 2.62528 + endloop + endfacet + facet normal -0.434048 0.0622481 0.898737 + outer loop + vertex 0.888976 1.64666 2.62377 + vertex 0.891957 1.65121 2.62489 + vertex 0.888573 1.65169 2.62323 + endloop + endfacet + facet normal -0.490054 0.0750528 0.868455 + outer loop + vertex 0.894393 1.65043 2.62625 + vertex 0.892423 1.64805 2.62535 + vertex 0.894746 1.64709 2.62674 + endloop + endfacet + facet normal -0.558093 0.06187 0.827469 + outer loop + vertex 0.894393 1.65043 2.62625 + vertex 0.894746 1.64709 2.62674 + vertex 0.897349 1.65091 2.62821 + endloop + endfacet + facet normal -0.479737 0.0625259 0.875182 + outer loop + vertex 0.891947 1.65557 2.62458 + vertex 0.891957 1.65121 2.62489 + vertex 0.894962 1.654 2.62634 + endloop + endfacet + facet normal -0.479515 0.0765185 0.874191 + outer loop + vertex 0.892572 1.66564 2.62407 + vertex 0.892171 1.66049 2.6243 + vertex 0.895678 1.66365 2.62594 + endloop + endfacet + facet normal -0.560877 0.0761959 0.824385 + outer loop + vertex 0.898068 1.65624 2.62826 + vertex 0.898478 1.66125 2.62808 + vertex 0.895337 1.65867 2.62618 + endloop + endfacet + facet normal -0.47911 0.0772951 0.874345 + outer loop + vertex 0.896137 1.66884 2.62574 + vertex 0.892572 1.66564 2.62407 + vertex 0.895678 1.66365 2.62594 + endloop + endfacet + facet normal -0.477439 0.0899569 0.874048 + outer loop + vertex 0.893918 1.6766 2.62372 + vertex 0.893054 1.67089 2.62384 + vertex 0.896665 1.67398 2.62549 + endloop + endfacet + facet normal -0.415725 0.0805297 0.905918 + outer loop + vertex 0.890025 1.6776 2.62182 + vertex 0.89357 1.68164 2.62309 + vertex 0.890093 1.68207 2.62145 + endloop + endfacet + facet normal -0.466905 0.0911931 0.879593 + outer loop + vertex 0.897337 1.67794 2.6254 + vertex 0.896899 1.68112 2.62483 + vertex 0.893918 1.6766 2.62372 + endloop + endfacet + facet normal -0.41503 0.0855594 0.905776 + outer loop + vertex 0.890093 1.68207 2.62145 + vertex 0.89357 1.68164 2.62309 + vertex 0.893218 1.68664 2.62245 + endloop + endfacet + facet normal -0.450994 0.0840805 0.888558 + outer loop + vertex 0.879811 1.677 2.61694 + vertex 0.883002 1.6757 2.61868 + vertex 0.883381 1.68151 2.61833 + endloop + endfacet + facet normal -0.452277 0.0805096 0.888236 + outer loop + vertex 0.879495 1.67227 2.61721 + vertex 0.883002 1.6757 2.61868 + vertex 0.879811 1.677 2.61694 + endloop + endfacet + facet normal -0.450782 0.0785762 0.889169 + outer loop + vertex 0.88268 1.67061 2.61897 + vertex 0.883002 1.6757 2.61868 + vertex 0.879495 1.67227 2.61721 + endloop + endfacet + facet normal -0.414484 0.0805572 0.906484 + outer loop + vertex 0.890025 1.6776 2.62182 + vertex 0.890093 1.68207 2.62145 + vertex 0.886658 1.67887 2.62017 + endloop + endfacet + facet normal -0.433701 0.0779759 0.897677 + outer loop + vertex 0.883002 1.6757 2.61868 + vertex 0.88268 1.67061 2.61897 + vertex 0.886289 1.674 2.62042 + endloop + endfacet + facet normal -0.450198 0.0722165 0.890004 + outer loop + vertex 0.882438 1.66559 2.61926 + vertex 0.88268 1.67061 2.61897 + vertex 0.879211 1.66728 2.61749 + endloop + endfacet + facet normal -0.451169 0.0700351 0.889686 + outer loop + vertex 0.878995 1.66228 2.61777 + vertex 0.882438 1.66559 2.61926 + vertex 0.879211 1.66728 2.61749 + endloop + endfacet + facet normal -0.449841 0.0682921 0.890494 + outer loop + vertex 0.882209 1.66066 2.61952 + vertex 0.882438 1.66559 2.61926 + vertex 0.878995 1.66228 2.61777 + endloop + endfacet + facet normal -0.41728 0.0756248 0.905626 + outer loop + vertex 0.889306 1.66737 2.62236 + vertex 0.889725 1.67255 2.62212 + vertex 0.885978 1.66897 2.62069 + endloop + endfacet + facet normal -0.431362 0.0729514 0.899225 + outer loop + vertex 0.888894 1.66222 2.62258 + vertex 0.892572 1.66564 2.62407 + vertex 0.889306 1.66737 2.62236 + endloop + endfacet + facet normal -0.423602 0.0698614 0.903151 + outer loop + vertex 0.88814 1.65667 2.62265 + vertex 0.888894 1.66222 2.62258 + vertex 0.885289 1.6591 2.62113 + endloop + endfacet + facet normal -0.434094 0.0679749 0.898299 + outer loop + vertex 0.882438 1.66559 2.61926 + vertex 0.882209 1.66066 2.61952 + vertex 0.885684 1.66395 2.62095 + endloop + endfacet + facet normal -0.438577 0.0698774 0.895973 + outer loop + vertex 0.885289 1.6591 2.62113 + vertex 0.881989 1.65603 2.61975 + vertex 0.884621 1.65528 2.6211 + endloop + endfacet + facet normal -0.43922 0.0673915 0.895848 + outer loop + vertex 0.882407 1.65271 2.62021 + vertex 0.884621 1.65528 2.6211 + vertex 0.881989 1.65603 2.61975 + endloop + endfacet + facet normal -0.449904 0.0642057 0.890766 + outer loop + vertex 0.881767 1.6489 2.62016 + vertex 0.878174 1.64569 2.61858 + vertex 0.881439 1.64402 2.62035 + endloop + endfacet + facet normal -0.461394 0.0647708 0.884828 + outer loop + vertex 0.874699 1.64227 2.61702 + vertex 0.878174 1.64569 2.61858 + vertex 0.874951 1.64694 2.61681 + endloop + endfacet + facet normal -0.469858 0.0648409 0.880357 + outer loop + vertex 0.87457 1.65035 2.61635 + vertex 0.87228 1.6478 2.61532 + vertex 0.874951 1.64694 2.61681 + endloop + endfacet + facet normal -0.471659 0.0669157 0.879238 + outer loop + vertex 0.87228 1.6478 2.61532 + vertex 0.87457 1.65035 2.61635 + vertex 0.871903 1.65118 2.61486 + endloop + endfacet + facet normal -0.480799 0.0664238 0.874311 + outer loop + vertex 0.871903 1.65118 2.61486 + vertex 0.872151 1.6558 2.61464 + vertex 0.868744 1.65231 2.61303 + endloop + endfacet + facet normal -0.461142 0.0653185 0.884919 + outer loop + vertex 0.878485 1.65149 2.61831 + vertex 0.878766 1.65725 2.61803 + vertex 0.87525 1.65419 2.61642 + endloop + endfacet + facet normal -0.450695 0.0662954 0.890213 + outer loop + vertex 0.878766 1.65725 2.61803 + vertex 0.882209 1.66066 2.61952 + vertex 0.878995 1.66228 2.61777 + endloop + endfacet + facet normal -0.471492 0.0679364 0.879249 + outer loop + vertex 0.872396 1.66068 2.6144 + vertex 0.872151 1.6558 2.61464 + vertex 0.875566 1.65903 2.61622 + endloop + endfacet + facet normal -0.482724 0.0720419 0.872804 + outer loop + vertex 0.872396 1.66068 2.6144 + vertex 0.872639 1.66567 2.61412 + vertex 0.869235 1.66231 2.61252 + endloop + endfacet + facet normal -0.462462 0.0701899 0.883856 + outer loop + vertex 0.878995 1.66228 2.61777 + vertex 0.879211 1.66728 2.61749 + vertex 0.875794 1.66399 2.61596 + endloop + endfacet + facet normal -0.452352 0.0750554 0.888675 + outer loop + vertex 0.879211 1.66728 2.61749 + vertex 0.88268 1.67061 2.61897 + vertex 0.879495 1.67227 2.61721 + endloop + endfacet + facet normal -0.474876 0.0763832 0.876732 + outer loop + vertex 0.873017 1.67078 2.61388 + vertex 0.872639 1.66567 2.61412 + vertex 0.876069 1.669 2.61569 + endloop + endfacet + facet normal -0.483661 0.0820411 0.871402 + outer loop + vertex 0.873017 1.67078 2.61388 + vertex 0.873766 1.6764 2.61377 + vertex 0.8699 1.67236 2.612 + endloop + endfacet + facet normal -0.46454 0.0809664 0.881843 + outer loop + vertex 0.879495 1.67227 2.61721 + vertex 0.879811 1.677 2.61694 + vertex 0.876518 1.67394 2.61549 + endloop + endfacet + facet normal -0.465436 0.0862579 0.880868 + outer loop + vertex 0.876965 1.68567 2.6146 + vertex 0.876765 1.68111 2.61494 + vertex 0.880152 1.6842 2.61642 + endloop + endfacet + facet normal -0.451955 0.0850186 0.88798 + outer loop + vertex 0.879456 1.68041 2.61643 + vertex 0.879811 1.677 2.61694 + vertex 0.883381 1.68151 2.61833 + endloop + endfacet + facet normal -0.450062 0.0864026 0.888807 + outer loop + vertex 0.880152 1.6842 2.61642 + vertex 0.88377 1.68725 2.61796 + vertex 0.880568 1.689 2.61617 + endloop + endfacet + facet normal -0.43674 0.0886769 0.895206 + outer loop + vertex 0.887352 1.68268 2.62015 + vertex 0.886996 1.68601 2.61964 + vertex 0.883381 1.68151 2.61833 + endloop + endfacet + facet normal -0.419417 0.0917318 0.903147 + outer loop + vertex 0.887352 1.68268 2.62015 + vertex 0.889644 1.68524 2.62095 + vertex 0.886996 1.68601 2.61964 + endloop + endfacet + facet normal -0.416017 0.0932806 0.90456 + outer loop + vertex 0.887374 1.69065 2.61934 + vertex 0.886996 1.68601 2.61964 + vertex 0.890419 1.68909 2.6209 + endloop + endfacet + facet normal -0.448068 0.0906515 0.889392 + outer loop + vertex 0.88377 1.68725 2.61796 + vertex 0.884182 1.69227 2.61766 + vertex 0.880568 1.689 2.61617 + endloop + endfacet + facet normal -0.463937 0.0896185 0.881324 + outer loop + vertex 0.877763 1.69556 2.61403 + vertex 0.877391 1.69061 2.61433 + vertex 0.880957 1.69394 2.61587 + endloop + endfacet + facet normal -0.465028 0.0872848 0.880983 + outer loop + vertex 0.880568 1.689 2.61617 + vertex 0.876965 1.68567 2.6146 + vertex 0.880152 1.6842 2.61642 + endloop + endfacet + facet normal -0.474683 0.0843063 0.87611 + outer loop + vertex 0.877236 1.67786 2.61551 + vertex 0.876765 1.68111 2.61494 + vertex 0.873766 1.6764 2.61377 + endloop + endfacet + facet normal -0.48267 0.0808056 0.872066 + outer loop + vertex 0.8699 1.67236 2.612 + vertex 0.873766 1.6764 2.61377 + vertex 0.870117 1.67697 2.61169 + endloop + endfacet + facet normal -0.486106 0.088221 0.869435 + outer loop + vertex 0.873051 1.68166 2.61287 + vertex 0.873808 1.68721 2.61273 + vertex 0.870336 1.68406 2.6111 + endloop + endfacet + facet normal -0.477054 0.0895692 0.874298 + outer loop + vertex 0.873808 1.68721 2.61273 + vertex 0.877391 1.69061 2.61433 + vertex 0.874254 1.69223 2.61245 + endloop + endfacet + facet normal -0.501428 0.0909956 0.860401 + outer loop + vertex 0.867693 1.69052 2.60888 + vertex 0.867462 1.68559 2.60926 + vertex 0.870783 1.68892 2.61085 + endloop + endfacet + facet normal -0.511596 0.0939218 0.854078 + outer loop + vertex 0.864698 1.69175 2.60695 + vertex 0.867693 1.69052 2.60888 + vertex 0.867669 1.69586 2.60828 + endloop + endfacet + facet normal -0.489436 0.0931279 0.867052 + outer loop + vertex 0.874254 1.69223 2.61245 + vertex 0.874634 1.69714 2.61214 + vertex 0.87111 1.69392 2.6105 + endloop + endfacet + facet normal -0.479361 0.0960716 0.872344 + outer loop + vertex 0.874634 1.69714 2.61214 + vertex 0.87809 1.70055 2.61367 + vertex 0.874981 1.70175 2.61183 + endloop + endfacet + facet normal -0.478585 0.0983627 0.872514 + outer loop + vertex 0.874981 1.70175 2.61183 + vertex 0.87809 1.70055 2.61367 + vertex 0.878394 1.70622 2.61319 + endloop + endfacet + facet normal -0.467243 0.0982645 0.878651 + outer loop + vertex 0.878394 1.70622 2.61319 + vertex 0.87809 1.70055 2.61367 + vertex 0.881505 1.7039 2.61511 + endloop + endfacet + facet normal -0.469428 0.0947 0.877878 + outer loop + vertex 0.881649 1.70713 2.61484 + vertex 0.878394 1.70622 2.61319 + vertex 0.881505 1.7039 2.61511 + endloop + endfacet + facet normal -0.47109 0.104207 0.875908 + outer loop + vertex 0.881649 1.70713 2.61484 + vertex 0.881942 1.71044 2.6146 + vertex 0.878394 1.70622 2.61319 + endloop + endfacet + facet normal -0.502576 0.0981664 0.858942 + outer loop + vertex 0.869105 1.70192 2.60842 + vertex 0.867669 1.69586 2.60828 + vertex 0.871649 1.69887 2.61026 + endloop + endfacet + facet normal -0.503032 0.102342 0.858187 + outer loop + vertex 0.869105 1.70192 2.60842 + vertex 0.872173 1.70609 2.60972 + vertex 0.86908 1.70726 2.60777 + endloop + endfacet + facet normal -0.488926 0.0988872 0.866702 + outer loop + vertex 0.874676 1.70512 2.61127 + vertex 0.872497 1.70272 2.61031 + vertex 0.874981 1.70175 2.61183 + endloop + endfacet + facet normal -0.480661 0.100366 0.871144 + outer loop + vertex 0.874676 1.70512 2.61127 + vertex 0.874981 1.70175 2.61183 + vertex 0.878394 1.70622 2.61319 + endloop + endfacet + facet normal -0.469254 0.102256 0.877123 + outer loop + vertex 0.878394 1.70622 2.61319 + vertex 0.881942 1.71044 2.6146 + vertex 0.878884 1.71205 2.61278 + endloop + endfacet + facet normal -0.491677 0.10372 0.864578 + outer loop + vertex 0.872419 1.7107 2.60931 + vertex 0.872173 1.70609 2.60972 + vertex 0.875389 1.709 2.6112 + endloop + endfacet + facet normal -0.501372 0.104951 0.858843 + outer loop + vertex 0.872419 1.7107 2.60931 + vertex 0.872805 1.71574 2.60892 + vertex 0.869375 1.71224 2.60735 + endloop + endfacet + facet normal -0.481016 0.105624 0.870326 + outer loop + vertex 0.878884 1.71205 2.61278 + vertex 0.879329 1.71719 2.6124 + vertex 0.875842 1.71394 2.61087 + endloop + endfacet + facet normal -0.467109 0.108572 0.877508 + outer loop + vertex 0.879329 1.71719 2.6124 + vertex 0.882881 1.72066 2.61386 + vertex 0.879721 1.72194 2.61202 + endloop + endfacet + facet normal -0.490746 0.108068 0.864575 + outer loop + vertex 0.873275 1.72161 2.60846 + vertex 0.872805 1.71574 2.60892 + vertex 0.876329 1.71891 2.61053 + endloop + endfacet + facet normal -0.489077 0.109523 0.865337 + outer loop + vertex 0.873275 1.72161 2.60846 + vertex 0.876828 1.7262 2.60988 + vertex 0.873724 1.72735 2.60798 + endloop + endfacet + facet normal -0.489879 0.107106 0.865186 + outer loop + vertex 0.876828 1.7262 2.60988 + vertex 0.877186 1.73074 2.60952 + vertex 0.873724 1.72735 2.60798 + endloop + endfacet + facet normal -0.48894 0.105835 0.865873 + outer loop + vertex 0.873724 1.72735 2.60798 + vertex 0.877186 1.73074 2.60952 + vertex 0.8741 1.73226 2.60759 + endloop + endfacet + facet normal -0.479133 0.109873 0.870838 + outer loop + vertex 0.879439 1.72535 2.61143 + vertex 0.87711 1.72284 2.61047 + vertex 0.879721 1.72194 2.61202 + endloop + endfacet + facet normal -0.467041 0.111949 0.87712 + outer loop + vertex 0.879439 1.72535 2.61143 + vertex 0.879721 1.72194 2.61202 + vertex 0.883335 1.72647 2.61336 + endloop + endfacet + facet normal -0.444876 0.107112 0.889164 + outer loop + vertex 0.883335 1.72647 2.61336 + vertex 0.88694 1.731 2.61462 + vertex 0.883782 1.7322 2.6129 + endloop + endfacet + facet normal -0.478303 0.106708 0.871688 + outer loop + vertex 0.877186 1.73074 2.60952 + vertex 0.876828 1.7262 2.60988 + vertex 0.88021 1.72915 2.61138 + endloop + endfacet + facet normal -0.49112 0.10064 0.865259 + outer loop + vertex 0.877186 1.73074 2.60952 + vertex 0.877549 1.73555 2.60917 + vertex 0.8741 1.73226 2.60759 + endloop + endfacet + facet normal -0.476798 0.0967873 0.873668 + outer loop + vertex 0.877917 1.74055 2.60882 + vertex 0.877549 1.73555 2.60917 + vertex 0.88105 1.73885 2.61071 + endloop + endfacet + facet normal -0.462578 0.103324 0.880537 + outer loop + vertex 0.883782 1.7322 2.6129 + vertex 0.884219 1.73721 2.61254 + vertex 0.880659 1.73393 2.61105 + endloop + endfacet + facet normal -0.479426 0.1066 0.871084 + outer loop + vertex 0.882207 1.74772 2.61033 + vertex 0.881922 1.75108 2.60976 + vertex 0.878358 1.7464 2.60837 + endloop + endfacet + facet normal -0.481486 0.108581 0.869702 + outer loop + vertex 0.878358 1.7464 2.60837 + vertex 0.881922 1.75108 2.60976 + vertex 0.878845 1.7522 2.60791 + endloop + endfacet + facet normal -0.475988 0.0985569 0.873912 + outer loop + vertex 0.88148 1.74378 2.61039 + vertex 0.877917 1.74055 2.60882 + vertex 0.88105 1.73885 2.61071 + endloop + endfacet + facet normal -0.490974 0.0971133 0.865745 + outer loop + vertex 0.874466 1.73712 2.60724 + vertex 0.877917 1.74055 2.60882 + vertex 0.874829 1.74177 2.60693 + endloop + endfacet + facet normal -0.502018 0.10262 0.858747 + outer loop + vertex 0.874565 1.74518 2.60637 + vertex 0.872379 1.74273 2.60538 + vertex 0.874829 1.74177 2.60693 + endloop + endfacet + facet normal -0.510015 0.112139 0.852824 + outer loop + vertex 0.872379 1.74273 2.60538 + vertex 0.874565 1.74518 2.60637 + vertex 0.872115 1.74609 2.60478 + endloop + endfacet + facet normal -0.521696 0.121209 0.844477 + outer loop + vertex 0.872115 1.74609 2.60478 + vertex 0.872425 1.75059 2.60433 + vertex 0.869111 1.74719 2.60277 + endloop + endfacet + facet normal -0.516756 0.119529 0.847747 + outer loop + vertex 0.872734 1.75539 2.60384 + vertex 0.872425 1.75059 2.60433 + vertex 0.875803 1.75385 2.60593 + endloop + endfacet + facet normal -0.495398 0.109128 0.861784 + outer loop + vertex 0.878358 1.7464 2.60837 + vertex 0.878845 1.7522 2.60791 + vertex 0.875339 1.74904 2.6063 + endloop + endfacet + facet normal -0.505352 0.0998924 0.857112 + outer loop + vertex 0.875803 1.75385 2.60593 + vertex 0.879237 1.75717 2.60756 + vertex 0.876092 1.75881 2.60552 + endloop + endfacet + facet normal -0.484007 0.100876 0.86923 + outer loop + vertex 0.881922 1.75108 2.60976 + vertex 0.882319 1.75566 2.60945 + vertex 0.878845 1.7522 2.60791 + endloop + endfacet + facet normal -0.524817 0.100053 0.845314 + outer loop + vertex 0.876092 1.75881 2.60552 + vertex 0.872734 1.75539 2.60384 + vertex 0.875803 1.75385 2.60593 + endloop + endfacet + facet normal -0.534152 0.126338 0.835895 + outer loop + vertex 0.869467 1.75203 2.60226 + vertex 0.872734 1.75539 2.60384 + vertex 0.869804 1.7565 2.6018 + endloop + endfacet + facet normal -0.541758 0.0975412 0.834856 + outer loop + vertex 0.867571 1.75751 2.60018 + vertex 0.869545 1.75979 2.6012 + vertex 0.867298 1.76083 2.59962 + endloop + endfacet + facet normal -0.541342 0.126401 0.831247 + outer loop + vertex 0.869467 1.75203 2.60226 + vertex 0.869804 1.7565 2.6018 + vertex 0.866677 1.75369 2.60019 + endloop + endfacet + facet normal -0.542976 0.0973109 0.834091 + outer loop + vertex 0.867571 1.75751 2.60018 + vertex 0.867298 1.76083 2.59962 + vertex 0.864354 1.75672 2.59818 + endloop + endfacet + facet normal -0.548316 0.102594 0.829954 + outer loop + vertex 0.864354 1.75672 2.59818 + vertex 0.867298 1.76083 2.59962 + vertex 0.86443 1.76207 2.59757 + endloop + endfacet + facet normal -0.575525 0.100875 0.811539 + outer loop + vertex 0.864354 1.75672 2.59818 + vertex 0.86443 1.76207 2.59757 + vertex 0.861124 1.75879 2.59563 + endloop + endfacet + facet normal -0.569246 0.0912471 0.817088 + outer loop + vertex 0.861124 1.75879 2.59563 + vertex 0.86443 1.76207 2.59757 + vertex 0.861544 1.7639 2.59535 + endloop + endfacet + facet normal -0.596726 0.0924275 0.797104 + outer loop + vertex 0.861544 1.7639 2.59535 + vertex 0.858338 1.76104 2.59328 + vertex 0.861124 1.75879 2.59563 + endloop + endfacet + facet normal -0.577818 0.125593 0.806444 + outer loop + vertex 0.858338 1.76104 2.59328 + vertex 0.857359 1.75561 2.59343 + vertex 0.861124 1.75879 2.59563 + endloop + endfacet + facet normal -0.58829 0.0772512 0.804952 + outer loop + vertex 0.858782 1.76605 2.59313 + vertex 0.858338 1.76104 2.59328 + vertex 0.861544 1.7639 2.59535 + endloop + endfacet + facet normal -0.602105 0.0510991 0.79678 + outer loop + vertex 0.861758 1.76884 2.5952 + vertex 0.858782 1.76605 2.59313 + vertex 0.861544 1.7639 2.59535 + endloop + endfacet + facet normal -0.576622 0.0505867 0.815443 + outer loop + vertex 0.861544 1.7639 2.59535 + vertex 0.864583 1.76702 2.59731 + vertex 0.861758 1.76884 2.5952 + endloop + endfacet + facet normal -0.5833 0.0604927 0.810001 + outer loop + vertex 0.86443 1.76207 2.59757 + vertex 0.864583 1.76702 2.59731 + vertex 0.861544 1.7639 2.59535 + endloop + endfacet + facet normal -0.557153 0.0606362 0.828193 + outer loop + vertex 0.86443 1.76207 2.59757 + vertex 0.867474 1.76537 2.59937 + vertex 0.864583 1.76702 2.59731 + endloop + endfacet + facet normal -0.560923 0.0657239 0.825255 + outer loop + vertex 0.867298 1.76083 2.59962 + vertex 0.867474 1.76537 2.59937 + vertex 0.86443 1.76207 2.59757 + endloop + endfacet + facet normal -0.546784 0.0656819 0.834693 + outer loop + vertex 0.867474 1.76537 2.59937 + vertex 0.867298 1.76083 2.59962 + vertex 0.870207 1.76354 2.60131 + endloop + endfacet + facet normal -0.552951 0.0530959 0.83152 + outer loop + vertex 0.870651 1.76851 2.60129 + vertex 0.867474 1.76537 2.59937 + vertex 0.870207 1.76354 2.60131 + endloop + endfacet + facet normal -0.543701 0.135128 0.828329 + outer loop + vertex 0.866677 1.75369 2.60019 + vertex 0.862763 1.75061 2.59812 + vertex 0.866043 1.74878 2.60057 + endloop + endfacet + facet normal -0.546361 0.133916 0.826775 + outer loop + vertex 0.859768 1.74643 2.59682 + vertex 0.862658 1.74534 2.59891 + vertex 0.862763 1.75061 2.59812 + endloop + endfacet + facet normal -0.562142 0.120027 0.818285 + outer loop + vertex 0.8595 1.742 2.59729 + vertex 0.859768 1.74643 2.59682 + vertex 0.856858 1.74375 2.59521 + endloop + endfacet + facet normal -0.572582 0.152167 0.805602 + outer loop + vertex 0.85757 1.74741 2.59514 + vertex 0.859536 1.74973 2.5961 + vertex 0.857329 1.75074 2.59434 + endloop + endfacet + facet normal -0.583835 0.127246 0.801839 + outer loop + vertex 0.854612 1.74671 2.59311 + vertex 0.853645 1.74129 2.59327 + vertex 0.856858 1.74375 2.59521 + endloop + endfacet + facet normal -0.581981 0.108967 0.805869 + outer loop + vertex 0.85303 1.7362 2.59351 + vertex 0.853645 1.74129 2.59327 + vertex 0.850295 1.73855 2.59122 + endloop + endfacet + facet normal -0.584385 0.106993 0.804392 + outer loop + vertex 0.850295 1.73855 2.59122 + vertex 0.847204 1.73556 2.58937 + vertex 0.849839 1.73373 2.59153 + endloop + endfacet + facet normal -0.585806 0.107083 0.803346 + outer loop + vertex 0.847058 1.7311 2.58986 + vertex 0.847204 1.73556 2.58937 + vertex 0.844343 1.73225 2.58772 + endloop + endfacet + facet normal -0.584739 0.110254 0.803694 + outer loop + vertex 0.844369 1.72703 2.58846 + vertex 0.847058 1.7311 2.58986 + vertex 0.844343 1.73225 2.58772 + endloop + endfacet + facet normal -0.596047 0.117705 0.794276 + outer loop + vertex 0.843306 1.72134 2.5885 + vertex 0.844369 1.72703 2.58846 + vertex 0.840636 1.72386 2.58613 + endloop + endfacet + facet normal -0.608971 0.109236 0.785635 + outer loop + vertex 0.83794 1.7262 2.58371 + vertex 0.837037 1.72082 2.58376 + vertex 0.840636 1.72386 2.58613 + endloop + endfacet + facet normal -0.611357 0.12868 0.780823 + outer loop + vertex 0.839494 1.73688 2.58343 + vertex 0.842121 1.74093 2.58481 + vertex 0.839359 1.74201 2.58247 + endloop + endfacet + facet normal -0.606368 0.14401 0.782035 + outer loop + vertex 0.842121 1.74093 2.58481 + vertex 0.842307 1.7454 2.58414 + vertex 0.839359 1.74201 2.58247 + endloop + endfacet + facet normal -0.612066 0.151889 0.776083 + outer loop + vertex 0.839359 1.74201 2.58247 + vertex 0.842307 1.7454 2.58414 + vertex 0.839321 1.74668 2.58153 + endloop + endfacet + facet normal -0.590363 0.114714 0.798945 + outer loop + vertex 0.84423 1.73998 2.58657 + vertex 0.842407 1.7377 2.58555 + vertex 0.84451 1.73672 2.58724 + endloop + endfacet + facet normal -0.586158 0.115686 0.801895 + outer loop + vertex 0.84423 1.73998 2.58657 + vertex 0.84451 1.73672 2.58724 + vertex 0.847189 1.74068 2.58863 + endloop + endfacet + facet normal -0.592761 0.134092 0.794137 + outer loop + vertex 0.848284 1.74623 2.58851 + vertex 0.847189 1.74068 2.58863 + vertex 0.850919 1.74371 2.5909 + endloop + endfacet + facet normal -0.601675 0.144355 0.785588 + outer loop + vertex 0.842307 1.7454 2.58414 + vertex 0.842121 1.74093 2.58481 + vertex 0.844956 1.74365 2.58649 + endloop + endfacet + facet normal -0.608504 0.161821 0.776876 + outer loop + vertex 0.839321 1.74668 2.58153 + vertex 0.842307 1.7454 2.58414 + vertex 0.84246 1.7508 2.58313 + endloop + endfacet + facet normal -0.594116 0.154284 0.789444 + outer loop + vertex 0.848284 1.74623 2.58851 + vertex 0.849453 1.75185 2.58829 + vertex 0.845639 1.7486 2.58606 + endloop + endfacet + facet normal -0.59491 0.160772 0.78755 + outer loop + vertex 0.849453 1.75185 2.58829 + vertex 0.852214 1.75598 2.58953 + vertex 0.849524 1.75676 2.58734 + endloop + endfacet + facet normal -0.600652 0.139802 0.787192 + outer loop + vertex 0.849524 1.75676 2.58734 + vertex 0.852214 1.75598 2.58953 + vertex 0.852194 1.76074 2.58867 + endloop + endfacet + facet normal -0.590729 0.141152 0.794428 + outer loop + vertex 0.852194 1.76074 2.58867 + vertex 0.852214 1.75598 2.58953 + vertex 0.855095 1.75866 2.5912 + endloop + endfacet + facet normal -0.607005 0.109629 0.7871 + outer loop + vertex 0.855669 1.76349 2.59097 + vertex 0.852194 1.76074 2.58867 + vertex 0.855095 1.75866 2.5912 + endloop + endfacet + facet normal -0.592877 0.108469 0.797955 + outer loop + vertex 0.855095 1.75866 2.5912 + vertex 0.858338 1.76104 2.59328 + vertex 0.855669 1.76349 2.59097 + endloop + endfacet + facet normal -0.611111 0.0787381 0.787619 + outer loop + vertex 0.858338 1.76104 2.59328 + vertex 0.858782 1.76605 2.59313 + vertex 0.855669 1.76349 2.59097 + endloop + endfacet + facet normal -0.60318 0.0627899 0.79513 + outer loop + vertex 0.855669 1.76349 2.59097 + vertex 0.858782 1.76605 2.59313 + vertex 0.856058 1.76844 2.59087 + endloop + endfacet + facet normal -0.601915 0.12944 0.788 + outer loop + vertex 0.857359 1.75561 2.59343 + vertex 0.858338 1.76104 2.59328 + vertex 0.855095 1.75866 2.5912 + endloop + endfacet + facet normal -0.604437 0.162881 0.779824 + outer loop + vertex 0.844253 1.75684 2.58326 + vertex 0.84246 1.7508 2.58313 + vertex 0.846442 1.75375 2.5856 + endloop + endfacet + facet normal -0.608609 0.148862 0.779381 + outer loop + vertex 0.844253 1.75684 2.58326 + vertex 0.847166 1.761 2.58474 + vertex 0.844504 1.76198 2.58247 + endloop + endfacet + facet normal -0.621265 0.147968 0.769504 + outer loop + vertex 0.844253 1.75684 2.58326 + vertex 0.844504 1.76198 2.58247 + vertex 0.841401 1.7588 2.58058 + endloop + endfacet + facet normal -0.613848 0.162755 0.772465 + outer loop + vertex 0.840566 1.75424 2.58088 + vertex 0.844253 1.75684 2.58326 + vertex 0.841401 1.7588 2.58058 + endloop + endfacet + facet normal -0.624155 0.164082 0.763877 + outer loop + vertex 0.841401 1.7588 2.58058 + vertex 0.838408 1.75609 2.57872 + vertex 0.840566 1.75424 2.58088 + endloop + endfacet + facet normal -0.619902 0.145728 0.771029 + outer loop + vertex 0.841401 1.7588 2.58058 + vertex 0.844504 1.76198 2.58247 + vertex 0.842035 1.7636 2.58018 + endloop + endfacet + facet normal -0.631908 0.119892 0.765714 + outer loop + vertex 0.844504 1.76198 2.58247 + vertex 0.844774 1.76643 2.582 + vertex 0.842035 1.7636 2.58018 + endloop + endfacet + facet normal -0.619201 0.114289 0.776871 + outer loop + vertex 0.847166 1.761 2.58474 + vertex 0.847393 1.76538 2.58428 + vertex 0.844504 1.76198 2.58247 + endloop + endfacet + facet normal -0.604168 0.149724 0.782664 + outer loop + vertex 0.849303 1.76008 2.58654 + vertex 0.847357 1.75773 2.58548 + vertex 0.849524 1.75676 2.58734 + endloop + endfacet + facet normal -0.609402 0.148448 0.778841 + outer loop + vertex 0.849303 1.76008 2.58654 + vertex 0.849524 1.75676 2.58734 + vertex 0.852194 1.76074 2.58867 + endloop + endfacet + facet normal -0.600374 0.0954445 0.794004 + outer loop + vertex 0.853012 1.76599 2.58866 + vertex 0.852194 1.76074 2.58867 + vertex 0.855669 1.76349 2.59097 + endloop + endfacet + facet normal -0.619815 0.0638468 0.782146 + outer loop + vertex 0.856058 1.76844 2.59087 + vertex 0.853012 1.76599 2.58866 + vertex 0.855669 1.76349 2.59097 + endloop + endfacet + facet normal -0.607801 0.114641 0.785771 + outer loop + vertex 0.847393 1.76538 2.58428 + vertex 0.847166 1.761 2.58474 + vertex 0.849982 1.76369 2.58652 + endloop + endfacet + facet normal -0.623396 0.12011 0.772626 + outer loop + vertex 0.844504 1.76198 2.58247 + vertex 0.847393 1.76538 2.58428 + vertex 0.844774 1.76643 2.582 + endloop + endfacet + facet normal -0.636338 0.080481 0.7672 + outer loop + vertex 0.842754 1.7674 2.58018 + vertex 0.844482 1.76975 2.58136 + vertex 0.842356 1.77084 2.57948 + endloop + endfacet + facet normal -0.621012 0.131917 0.77262 + outer loop + vertex 0.839922 1.76653 2.57798 + vertex 0.838942 1.7609 2.57816 + vertex 0.842035 1.7636 2.58018 + endloop + endfacet + facet normal -0.628058 0.146249 0.7643 + outer loop + vertex 0.842035 1.7636 2.58018 + vertex 0.838942 1.7609 2.57816 + vertex 0.841401 1.7588 2.58058 + endloop + endfacet + facet normal -0.621116 0.158179 0.76759 + outer loop + vertex 0.838942 1.7609 2.57816 + vertex 0.838408 1.75609 2.57872 + vertex 0.841401 1.7588 2.58058 + endloop + endfacet + facet normal -0.620643 0.17001 0.76544 + outer loop + vertex 0.838408 1.75609 2.57872 + vertex 0.838343 1.7532 2.57931 + vertex 0.840566 1.75424 2.58088 + endloop + endfacet + facet normal -0.615157 0.166262 0.770674 + outer loop + vertex 0.84246 1.7508 2.58313 + vertex 0.844253 1.75684 2.58326 + vertex 0.840566 1.75424 2.58088 + endloop + endfacet + facet normal -0.625644 0.175081 0.760208 + outer loop + vertex 0.835769 1.75243 2.57734 + vertex 0.83646 1.7479 2.57896 + vertex 0.8388 1.75075 2.58023 + endloop + endfacet + facet normal -0.630048 0.173262 0.756981 + outer loop + vertex 0.835769 1.75243 2.57734 + vertex 0.834192 1.74865 2.5769 + vertex 0.83646 1.7479 2.57896 + endloop + endfacet + facet normal -0.632415 0.165483 0.756747 + outer loop + vertex 0.834192 1.74865 2.5769 + vertex 0.834148 1.74533 2.57759 + vertex 0.83646 1.7479 2.57896 + endloop + endfacet + facet normal -0.642883 0.163852 0.748234 + outer loop + vertex 0.834192 1.74865 2.5769 + vertex 0.83235 1.74696 2.57569 + vertex 0.834148 1.74533 2.57759 + endloop + endfacet + facet normal -0.646886 0.172049 0.742925 + outer loop + vertex 0.83235 1.74696 2.57569 + vertex 0.834192 1.74865 2.5769 + vertex 0.832227 1.75029 2.57481 + endloop + endfacet + facet normal -0.65929 0.168884 0.732677 + outer loop + vertex 0.83235 1.74696 2.57569 + vertex 0.832227 1.75029 2.57481 + vertex 0.82958 1.7466 2.57328 + endloop + endfacet + facet normal -0.655188 0.163948 0.737462 + outer loop + vertex 0.82958 1.7466 2.57328 + vertex 0.832227 1.75029 2.57481 + vertex 0.829267 1.75163 2.57188 + endloop + endfacet + facet normal -0.642472 0.179866 0.744902 + outer loop + vertex 0.835769 1.75243 2.57734 + vertex 0.832227 1.75029 2.57481 + vertex 0.834192 1.74865 2.5769 + endloop + endfacet + facet normal -0.615345 0.151359 0.773589 + outer loop + vertex 0.839359 1.74201 2.58247 + vertex 0.839321 1.74668 2.58153 + vertex 0.836568 1.74363 2.57994 + endloop + endfacet + facet normal -0.628615 0.137911 0.765391 + outer loop + vertex 0.836568 1.74363 2.57994 + vertex 0.833799 1.74103 2.57813 + vertex 0.836397 1.73886 2.58066 + endloop + endfacet + facet normal -0.633931 0.128352 0.762665 + outer loop + vertex 0.833799 1.74103 2.57813 + vertex 0.83334 1.73615 2.57857 + vertex 0.836397 1.73886 2.58066 + endloop + endfacet + facet normal -0.634266 0.110515 0.765175 + outer loop + vertex 0.83334 1.73615 2.57857 + vertex 0.832781 1.73111 2.57884 + vertex 0.835973 1.73375 2.5811 + endloop + endfacet + facet normal -0.648602 0.103047 0.75412 + outer loop + vertex 0.831953 1.72581 2.57885 + vertex 0.832781 1.73111 2.57884 + vertex 0.829767 1.72883 2.57656 + endloop + endfacet + facet normal -0.66088 0.11455 0.741698 + outer loop + vertex 0.827912 1.7361 2.57383 + vertex 0.827045 1.7308 2.57388 + vertex 0.830299 1.73363 2.57634 + endloop + endfacet + facet normal -0.65689 0.102065 0.747046 + outer loop + vertex 0.829767 1.72883 2.57656 + vertex 0.827181 1.72615 2.57465 + vertex 0.82921 1.72517 2.57657 + endloop + endfacet + facet normal -0.660526 0.103615 0.743619 + outer loop + vertex 0.824786 1.72195 2.57311 + vertex 0.827181 1.72615 2.57465 + vertex 0.824703 1.72681 2.57235 + endloop + endfacet + facet normal -0.66675 0.103272 0.738092 + outer loop + vertex 0.824361 1.73001 2.5716 + vertex 0.822693 1.72768 2.57042 + vertex 0.824703 1.72681 2.57235 + endloop + endfacet + facet normal -0.672505 0.110603 0.731781 + outer loop + vertex 0.822693 1.72768 2.57042 + vertex 0.824361 1.73001 2.5716 + vertex 0.822276 1.73084 2.56956 + endloop + endfacet + facet normal -0.678716 0.124024 0.723853 + outer loop + vertex 0.819438 1.73152 2.56678 + vertex 0.822276 1.73084 2.56956 + vertex 0.822089 1.73559 2.56857 + endloop + endfacet + facet normal -0.663125 0.114899 0.739638 + outer loop + vertex 0.827045 1.7308 2.57388 + vertex 0.827912 1.7361 2.57383 + vertex 0.824911 1.73365 2.57152 + endloop + endfacet + facet normal -0.662585 0.134739 0.736767 + outer loop + vertex 0.828645 1.74119 2.57356 + vertex 0.827912 1.7361 2.57383 + vertex 0.830916 1.73862 2.57607 + endloop + endfacet + facet normal -0.676997 0.139384 0.722667 + outer loop + vertex 0.823173 1.74092 2.56856 + vertex 0.822089 1.73559 2.56857 + vertex 0.825535 1.73849 2.57124 + endloop + endfacet + facet normal -0.680019 0.151651 0.71734 + outer loop + vertex 0.823173 1.74092 2.56856 + vertex 0.82372 1.74595 2.56801 + vertex 0.820928 1.74344 2.56589 + endloop + endfacet + facet normal -0.680412 0.152567 0.716772 + outer loop + vertex 0.820928 1.74344 2.56589 + vertex 0.82372 1.74595 2.56801 + vertex 0.821276 1.74833 2.56518 + endloop + endfacet + facet normal -0.68822 0.152052 0.709389 + outer loop + vertex 0.821276 1.74833 2.56518 + vertex 0.818678 1.74587 2.56319 + vertex 0.820928 1.74344 2.56589 + endloop + endfacet + facet normal -0.686824 0.148939 0.7114 + outer loop + vertex 0.81903 1.75051 2.56256 + vertex 0.818678 1.74587 2.56319 + vertex 0.821276 1.74833 2.56518 + endloop + endfacet + facet normal -0.672345 0.154325 0.723973 + outer loop + vertex 0.823826 1.75077 2.56708 + vertex 0.82372 1.74595 2.56801 + vertex 0.826546 1.74866 2.57006 + endloop + endfacet + facet normal -0.680076 0.153146 0.716968 + outer loop + vertex 0.82372 1.74595 2.56801 + vertex 0.823826 1.75077 2.56708 + vertex 0.821276 1.74833 2.56518 + endloop + endfacet + facet normal -0.678516 0.14983 0.719143 + outer loop + vertex 0.821276 1.74833 2.56518 + vertex 0.823826 1.75077 2.56708 + vertex 0.821259 1.7529 2.56421 + endloop + endfacet + facet normal -0.665805 0.15363 0.730138 + outer loop + vertex 0.828645 1.74119 2.57356 + vertex 0.82958 1.7466 2.57328 + vertex 0.826248 1.74364 2.57086 + endloop + endfacet + facet normal -0.651321 0.161074 0.741509 + outer loop + vertex 0.828635 1.75577 2.57042 + vertex 0.829267 1.75163 2.57188 + vertex 0.832125 1.75526 2.5736 + endloop + endfacet + facet normal -0.654625 0.165518 0.737611 + outer loop + vertex 0.829267 1.75163 2.57188 + vertex 0.832227 1.75029 2.57481 + vertex 0.832125 1.75526 2.5736 + endloop + endfacet + facet normal -0.655025 0.146033 0.741362 + outer loop + vertex 0.828125 1.76107 2.56891 + vertex 0.828151 1.75826 2.56948 + vertex 0.830133 1.75886 2.57112 + endloop + endfacet + facet normal -0.666927 0.13278 0.733197 + outer loop + vertex 0.828125 1.76107 2.56891 + vertex 0.828416 1.76575 2.56832 + vertex 0.825728 1.76322 2.56634 + endloop + endfacet + facet normal -0.663635 0.126003 0.737368 + outer loop + vertex 0.825728 1.76322 2.56634 + vertex 0.828416 1.76575 2.56832 + vertex 0.826014 1.76828 2.56573 + endloop + endfacet + facet normal -0.649089 0.135858 0.748482 + outer loop + vertex 0.833153 1.76061 2.57338 + vertex 0.833895 1.76589 2.57306 + vertex 0.830799 1.76328 2.57085 + endloop + endfacet + facet normal -0.655122 0.109212 0.747588 + outer loop + vertex 0.828851 1.77095 2.56795 + vertex 0.828416 1.76575 2.56832 + vertex 0.831363 1.76849 2.57051 + endloop + endfacet + facet normal -0.673816 0.109547 0.730734 + outer loop + vertex 0.828416 1.76575 2.56832 + vertex 0.828851 1.77095 2.56795 + vertex 0.826014 1.76828 2.56573 + endloop + endfacet + facet normal -0.683022 0.0940441 0.724318 + outer loop + vertex 0.824133 1.77595 2.56291 + vertex 0.823682 1.77086 2.56314 + vertex 0.826475 1.77348 2.56544 + endloop + endfacet + facet normal -0.693183 0.0765694 0.716683 + outer loop + vertex 0.826879 1.77865 2.56528 + vertex 0.824133 1.77595 2.56291 + vertex 0.826475 1.77348 2.56544 + endloop + endfacet + facet normal -0.690735 0.0715528 0.719559 + outer loop + vertex 0.824315 1.78087 2.56259 + vertex 0.824133 1.77595 2.56291 + vertex 0.826879 1.77865 2.56528 + endloop + endfacet + facet normal -0.677759 0.125262 0.724536 + outer loop + vertex 0.826014 1.76828 2.56573 + vertex 0.823261 1.76579 2.56359 + vertex 0.825728 1.76322 2.56634 + endloop + endfacet + facet normal -0.693468 0.13325 0.708058 + outer loop + vertex 0.81867 1.77081 2.55823 + vertex 0.818079 1.7658 2.5586 + vertex 0.820903 1.76832 2.56089 + endloop + endfacet + facet normal -0.700546 0.139961 0.699747 + outer loop + vertex 0.817252 1.76047 2.55884 + vertex 0.818079 1.7658 2.5586 + vertex 0.815407 1.76373 2.55634 + endloop + endfacet + facet normal -0.681547 0.134716 0.719267 + outer loop + vertex 0.823141 1.76098 2.56437 + vertex 0.823261 1.76579 2.56359 + vertex 0.820491 1.7632 2.56145 + endloop + endfacet + facet normal -0.670775 0.143357 0.727674 + outer loop + vertex 0.823141 1.76098 2.56437 + vertex 0.823254 1.75799 2.56507 + vertex 0.825831 1.75812 2.56742 + endloop + endfacet + facet normal -0.67053 0.146806 0.727212 + outer loop + vertex 0.825831 1.75812 2.56742 + vertex 0.823254 1.75799 2.56507 + vertex 0.82353 1.75516 2.56589 + endloop + endfacet + facet normal -0.678954 0.148982 0.718906 + outer loop + vertex 0.82353 1.75516 2.56589 + vertex 0.821259 1.7529 2.56421 + vertex 0.823826 1.75077 2.56708 + endloop + endfacet + facet normal -0.687307 0.148094 0.71111 + outer loop + vertex 0.821259 1.7529 2.56421 + vertex 0.81903 1.75051 2.56256 + vertex 0.821276 1.74833 2.56518 + endloop + endfacet + facet normal -0.703804 0.139045 0.696654 + outer loop + vertex 0.817287 1.7523 2.56048 + vertex 0.817228 1.75566 2.55975 + vertex 0.814607 1.75178 2.55788 + endloop + endfacet + facet normal -0.696077 0.148425 0.702458 + outer loop + vertex 0.818678 1.74587 2.56319 + vertex 0.81903 1.75051 2.56256 + vertex 0.816534 1.74841 2.56053 + endloop + endfacet + facet normal -0.68851 0.151582 0.709208 + outer loop + vertex 0.818678 1.74587 2.56319 + vertex 0.818345 1.74107 2.56389 + vertex 0.820928 1.74344 2.56589 + endloop + endfacet + facet normal -0.6999 0.149011 0.698523 + outer loop + vertex 0.81832 1.73808 2.56451 + vertex 0.818345 1.74107 2.56389 + vertex 0.816045 1.73774 2.5623 + endloop + endfacet + facet normal -0.706691 0.148981 0.691659 + outer loop + vertex 0.813795 1.74599 2.55824 + vertex 0.813519 1.74071 2.5591 + vertex 0.816072 1.74325 2.56116 + endloop + endfacet + facet normal -0.703104 0.142191 0.696726 + outer loop + vertex 0.816045 1.73774 2.5623 + vertex 0.813548 1.73741 2.55985 + vertex 0.813811 1.73448 2.56071 + endloop + endfacet + facet normal -0.705522 0.13106 0.696464 + outer loop + vertex 0.813811 1.73448 2.56071 + vertex 0.811666 1.73231 2.55895 + vertex 0.814169 1.73019 2.56188 + endloop + endfacet + facet normal -0.716639 0.138053 0.683644 + outer loop + vertex 0.809652 1.73394 2.55651 + vertex 0.809433 1.73035 2.557 + vertex 0.811666 1.73231 2.55895 + endloop + endfacet + facet normal -0.724268 0.158336 0.671093 + outer loop + vertex 0.808585 1.74056 2.55381 + vertex 0.808555 1.73652 2.55473 + vertex 0.811222 1.73731 2.55742 + endloop + endfacet + facet normal -0.742072 0.154189 0.652345 + outer loop + vertex 0.808555 1.73652 2.55473 + vertex 0.808585 1.74056 2.55381 + vertex 0.806092 1.73755 2.55169 + endloop + endfacet + facet normal -0.760265 0.165479 0.628183 + outer loop + vertex 0.806092 1.73755 2.55169 + vertex 0.803312 1.73566 2.54882 + vertex 0.805126 1.73276 2.55178 + endloop + endfacet + facet normal -0.725739 0.15426 0.670452 + outer loop + vertex 0.804264 1.72948 2.5516 + vertex 0.806628 1.72873 2.55433 + vertex 0.805126 1.73276 2.55178 + endloop + endfacet + facet normal -0.751608 0.162751 0.639216 + outer loop + vertex 0.805126 1.73276 2.55178 + vertex 0.80317 1.73175 2.54974 + vertex 0.804264 1.72948 2.5516 + endloop + endfacet + facet normal -0.766035 0.145102 0.626208 + outer loop + vertex 0.80317 1.73175 2.54974 + vertex 0.802394 1.72837 2.54957 + vertex 0.804264 1.72948 2.5516 + endloop + endfacet + facet normal -0.763153 0.126332 0.633749 + outer loop + vertex 0.804264 1.72948 2.5516 + vertex 0.802394 1.72837 2.54957 + vertex 0.804212 1.72576 2.55228 + endloop + endfacet + facet normal -0.753032 0.17597 0.634017 + outer loop + vertex 0.803312 1.73566 2.54882 + vertex 0.80317 1.73175 2.54974 + vertex 0.805126 1.73276 2.55178 + endloop + endfacet + facet normal -0.731212 0.132361 0.669186 + outer loop + vertex 0.804264 1.72948 2.5516 + vertex 0.804212 1.72576 2.55228 + vertex 0.806628 1.72873 2.55433 + endloop + endfacet + facet normal -0.727651 0.137134 0.672099 + outer loop + vertex 0.809652 1.73394 2.55651 + vertex 0.807554 1.73331 2.55436 + vertex 0.809433 1.73035 2.557 + endloop + endfacet + facet normal -0.713538 0.124688 0.689432 + outer loop + vertex 0.809433 1.73035 2.557 + vertex 0.809202 1.72585 2.55757 + vertex 0.811767 1.72796 2.55985 + endloop + endfacet + facet normal -0.715031 0.110322 0.690333 + outer loop + vertex 0.808901 1.72104 2.55803 + vertex 0.809202 1.72585 2.55757 + vertex 0.806546 1.7235 2.5552 + endloop + endfacet + facet normal -0.709561 0.100938 0.697377 + outer loop + vertex 0.808901 1.72104 2.55803 + vertex 0.808465 1.71609 2.5583 + vertex 0.811168 1.71854 2.5607 + endloop + endfacet + facet normal -0.736742 0.0949091 0.66948 + outer loop + vertex 0.80396 1.72093 2.55279 + vertex 0.803678 1.71594 2.55319 + vertex 0.806223 1.71855 2.55562 + endloop + endfacet + facet normal -0.720225 0.0988134 0.686667 + outer loop + vertex 0.808125 1.71103 2.55868 + vertex 0.808465 1.71609 2.5583 + vertex 0.805851 1.71353 2.55593 + endloop + endfacet + facet normal -0.710651 0.101802 0.696141 + outer loop + vertex 0.808125 1.71103 2.55868 + vertex 0.808107 1.70608 2.55938 + vertex 0.810537 1.70838 2.56153 + endloop + endfacet + facet normal -0.70836 0.105965 0.697852 + outer loop + vertex 0.808107 1.70608 2.55938 + vertex 0.80828 1.70293 2.56003 + vertex 0.810794 1.70295 2.56258 + endloop + endfacet + facet normal -0.708289 0.106944 0.697775 + outer loop + vertex 0.810794 1.70295 2.56258 + vertex 0.80828 1.70293 2.56003 + vertex 0.808632 1.69996 2.56085 + endloop + endfacet + facet normal -0.714373 0.106263 0.69165 + outer loop + vertex 0.808632 1.69996 2.56085 + vertex 0.806542 1.6977 2.55904 + vertex 0.809062 1.69552 2.56197 + endloop + endfacet + facet normal -0.739336 0.114258 0.663571 + outer loop + vertex 0.805963 1.70273 2.55763 + vertex 0.803385 1.7017 2.55493 + vertex 0.80451 1.69918 2.55662 + endloop + endfacet + facet normal -0.751476 0.101054 0.651976 + outer loop + vertex 0.803385 1.7017 2.55493 + vertex 0.80252 1.69831 2.55446 + vertex 0.80451 1.69918 2.55662 + endloop + endfacet + facet normal -0.7513 0.0996196 0.652399 + outer loop + vertex 0.80451 1.69918 2.55662 + vertex 0.80252 1.69831 2.55446 + vertex 0.804392 1.69546 2.55705 + endloop + endfacet + facet normal -0.752559 0.0977277 0.651233 + outer loop + vertex 0.801777 1.69356 2.55432 + vertex 0.804392 1.69546 2.55705 + vertex 0.80252 1.69831 2.55446 + endloop + endfacet + facet normal -0.775982 0.102275 0.622408 + outer loop + vertex 0.800277 1.69758 2.55179 + vertex 0.801777 1.69356 2.55432 + vertex 0.80252 1.69831 2.55446 + endloop + endfacet + facet normal -0.775573 0.102704 0.622847 + outer loop + vertex 0.799573 1.69422 2.55146 + vertex 0.801777 1.69356 2.55432 + vertex 0.800277 1.69758 2.55179 + endloop + endfacet + facet normal -0.798367 0.11045 0.591955 + outer loop + vertex 0.800277 1.69758 2.55179 + vertex 0.798435 1.69665 2.54948 + vertex 0.799573 1.69422 2.55146 + endloop + endfacet + facet normal -0.799098 0.117885 0.58953 + outer loop + vertex 0.798538 1.70065 2.54881 + vertex 0.798435 1.69665 2.54948 + vertex 0.800277 1.69758 2.55179 + endloop + endfacet + facet normal -0.80346 0.110967 0.584926 + outer loop + vertex 0.80107 1.70254 2.55194 + vertex 0.798538 1.70065 2.54881 + vertex 0.800277 1.69758 2.55179 + endloop + endfacet + facet normal -0.776141 0.105483 0.621674 + outer loop + vertex 0.80107 1.70254 2.55194 + vertex 0.800277 1.69758 2.55179 + vertex 0.80252 1.69831 2.55446 + endloop + endfacet + facet normal -0.803246 0.109839 0.585433 + outer loop + vertex 0.798909 1.70577 2.54836 + vertex 0.798538 1.70065 2.54881 + vertex 0.80107 1.70254 2.55194 + endloop + endfacet + facet normal -0.811929 0.0938147 0.576169 + outer loop + vertex 0.80113 1.70818 2.5511 + vertex 0.798909 1.70577 2.54836 + vertex 0.80107 1.70254 2.55194 + endloop + endfacet + facet normal -0.774299 0.100592 0.624773 + outer loop + vertex 0.80107 1.70254 2.55194 + vertex 0.803323 1.70575 2.55421 + vertex 0.80113 1.70818 2.5511 + endloop + endfacet + facet normal -0.77894 0.0908877 0.620477 + outer loop + vertex 0.803323 1.70575 2.55421 + vertex 0.803406 1.71088 2.55356 + vertex 0.80113 1.70818 2.5511 + endloop + endfacet + facet normal -0.773954 0.0999795 0.625299 + outer loop + vertex 0.803385 1.7017 2.55493 + vertex 0.803323 1.70575 2.55421 + vertex 0.80107 1.70254 2.55194 + endloop + endfacet + facet normal -0.771781 0.109769 0.626343 + outer loop + vertex 0.803385 1.7017 2.55493 + vertex 0.80107 1.70254 2.55194 + vertex 0.80252 1.69831 2.55446 + endloop + endfacet + facet normal -0.81347 0.0986301 0.573183 + outer loop + vertex 0.799228 1.71089 2.54794 + vertex 0.798909 1.70577 2.54836 + vertex 0.80113 1.70818 2.5511 + endloop + endfacet + facet normal -0.775914 0.100972 0.622705 + outer loop + vertex 0.799573 1.69422 2.55146 + vertex 0.799631 1.69057 2.55213 + vertex 0.801777 1.69356 2.55432 + endloop + endfacet + facet normal -0.77452 0.0983941 0.62485 + outer loop + vertex 0.801777 1.69356 2.55432 + vertex 0.799631 1.69057 2.55213 + vertex 0.801764 1.68833 2.55512 + endloop + endfacet + facet normal -0.751577 0.10247 0.651637 + outer loop + vertex 0.801764 1.68833 2.55512 + vertex 0.804244 1.69084 2.55759 + vertex 0.801777 1.69356 2.55432 + endloop + endfacet + facet normal -0.751597 0.102519 0.651607 + outer loop + vertex 0.803983 1.68598 2.55805 + vertex 0.804244 1.69084 2.55759 + vertex 0.801764 1.68833 2.55512 + endloop + endfacet + facet normal -0.751291 0.103128 0.651864 + outer loop + vertex 0.801422 1.68344 2.55551 + vertex 0.803983 1.68598 2.55805 + vertex 0.801764 1.68833 2.55512 + endloop + endfacet + facet normal -0.772551 0.102654 0.6266 + outer loop + vertex 0.801764 1.68833 2.55512 + vertex 0.799362 1.68591 2.55256 + vertex 0.801422 1.68344 2.55551 + endloop + endfacet + facet normal -0.771819 0.104061 0.62727 + outer loop + vertex 0.799362 1.68591 2.55256 + vertex 0.798888 1.68101 2.55279 + vertex 0.801422 1.68344 2.55551 + endloop + endfacet + facet normal -0.771879 0.104241 0.627165 + outer loop + vertex 0.801422 1.68344 2.55551 + vertex 0.798888 1.68101 2.55279 + vertex 0.800987 1.67849 2.55579 + endloop + endfacet + facet normal -0.750509 0.103839 0.652651 + outer loop + vertex 0.800987 1.67849 2.55579 + vertex 0.803551 1.68106 2.55833 + vertex 0.801422 1.68344 2.55551 + endloop + endfacet + facet normal -0.749124 0.100344 0.654786 + outer loop + vertex 0.803188 1.67606 2.55868 + vertex 0.803551 1.68106 2.55833 + vertex 0.800987 1.67849 2.55579 + endloop + endfacet + facet normal -0.748115 0.102271 0.655641 + outer loop + vertex 0.800709 1.6734 2.55627 + vertex 0.803188 1.67606 2.55868 + vertex 0.800987 1.67849 2.55579 + endloop + endfacet + facet normal -0.769036 0.101119 0.631156 + outer loop + vertex 0.800987 1.67849 2.55579 + vertex 0.798485 1.67594 2.55315 + vertex 0.800709 1.6734 2.55627 + endloop + endfacet + facet normal -0.769006 0.10118 0.631184 + outer loop + vertex 0.798485 1.67594 2.55315 + vertex 0.798305 1.67078 2.55376 + vertex 0.800709 1.6734 2.55627 + endloop + endfacet + facet normal -0.76651 0.0950749 0.635156 + outer loop + vertex 0.800709 1.6734 2.55627 + vertex 0.798305 1.67078 2.55376 + vertex 0.800737 1.66788 2.55713 + endloop + endfacet + facet normal -0.743139 0.0993371 0.661723 + outer loop + vertex 0.800737 1.66788 2.55713 + vertex 0.803122 1.67102 2.55934 + vertex 0.800709 1.6734 2.55627 + endloop + endfacet + facet normal -0.76456 0.0987756 0.636939 + outer loop + vertex 0.798305 1.67078 2.55376 + vertex 0.79813 1.66578 2.55433 + vertex 0.800737 1.66788 2.55713 + endloop + endfacet + facet normal -0.772544 0.102635 0.626611 + outer loop + vertex 0.799631 1.69057 2.55213 + vertex 0.799362 1.68591 2.55256 + vertex 0.801764 1.68833 2.55512 + endloop + endfacet + facet normal -0.751117 0.102682 0.652135 + outer loop + vertex 0.803551 1.68106 2.55833 + vertex 0.803983 1.68598 2.55805 + vertex 0.801422 1.68344 2.55551 + endloop + endfacet + facet normal -0.753048 0.0996187 0.65038 + outer loop + vertex 0.804244 1.69084 2.55759 + vertex 0.804392 1.69546 2.55705 + vertex 0.801777 1.69356 2.55432 + endloop + endfacet + facet normal -0.713903 0.106619 0.69208 + outer loop + vertex 0.809146 1.69091 2.56277 + vertex 0.809062 1.69552 2.56197 + vertex 0.806719 1.6932 2.55991 + endloop + endfacet + facet normal -0.703326 0.106696 0.702815 + outer loop + vertex 0.809146 1.69091 2.56277 + vertex 0.808846 1.68612 2.5632 + vertex 0.811529 1.68853 2.56552 + endloop + endfacet + facet normal -0.731651 0.10356 0.673767 + outer loop + vertex 0.804244 1.69084 2.55759 + vertex 0.803983 1.68598 2.55805 + vertex 0.806576 1.6885 2.56048 + endloop + endfacet + facet normal -0.716348 0.103585 0.690012 + outer loop + vertex 0.808355 1.68114 2.56344 + vertex 0.808846 1.68612 2.5632 + vertex 0.806173 1.68362 2.5608 + endloop + endfacet + facet normal -0.705772 0.0985146 0.701556 + outer loop + vertex 0.808355 1.68114 2.56344 + vertex 0.808004 1.67609 2.56379 + vertex 0.810607 1.67853 2.56607 + endloop + endfacet + facet normal -0.732597 0.100438 0.673211 + outer loop + vertex 0.803551 1.68106 2.55833 + vertex 0.803188 1.67606 2.55868 + vertex 0.805728 1.67862 2.56106 + endloop + endfacet + facet normal -0.745068 0.0953392 0.66014 + outer loop + vertex 0.803122 1.67102 2.55934 + vertex 0.803188 1.67606 2.55868 + vertex 0.800709 1.6734 2.55627 + endloop + endfacet + facet normal -0.716374 0.0940757 0.691345 + outer loop + vertex 0.808023 1.67118 2.56448 + vertex 0.808004 1.67609 2.56379 + vertex 0.805544 1.67352 2.56159 + endloop + endfacet + facet normal -0.700559 0.0966778 0.707015 + outer loop + vertex 0.808023 1.67118 2.56448 + vertex 0.808228 1.66807 2.56511 + vertex 0.810756 1.66801 2.56762 + endloop + endfacet + facet normal -0.700794 0.0937432 0.707178 + outer loop + vertex 0.810756 1.66801 2.56762 + vertex 0.808228 1.66807 2.56511 + vertex 0.808614 1.66512 2.56588 + endloop + endfacet + facet normal -0.708264 0.0906383 0.700105 + outer loop + vertex 0.808614 1.66512 2.56588 + vertex 0.806528 1.66295 2.56405 + vertex 0.809093 1.66066 2.56694 + endloop + endfacet + facet normal -0.718777 0.090607 0.689311 + outer loop + vertex 0.804439 1.66453 2.56167 + vertex 0.804335 1.6608 2.56205 + vertex 0.806528 1.66295 2.56405 + endloop + endfacet + facet normal -0.724311 0.0982358 0.682439 + outer loop + vertex 0.803122 1.67102 2.55934 + vertex 0.803236 1.66706 2.56003 + vertex 0.805888 1.66796 2.56271 + endloop + endfacet + facet normal -0.740494 0.0947863 0.665345 + outer loop + vertex 0.803236 1.66706 2.56003 + vertex 0.803122 1.67102 2.55934 + vertex 0.800737 1.66788 2.55713 + endloop + endfacet + facet normal -0.765545 0.102335 0.635191 + outer loop + vertex 0.800737 1.66788 2.55713 + vertex 0.79813 1.66578 2.55433 + vertex 0.799957 1.66303 2.55697 + endloop + endfacet + facet normal -0.763324 0.105831 0.637288 + outer loop + vertex 0.79813 1.66578 2.55433 + vertex 0.798101 1.66195 2.55493 + vertex 0.799957 1.66303 2.55697 + endloop + endfacet + facet normal -0.762527 0.10125 0.638984 + outer loop + vertex 0.799957 1.66303 2.55697 + vertex 0.798101 1.66195 2.55493 + vertex 0.799236 1.65969 2.55664 + endloop + endfacet + facet normal -0.739184 0.0934553 0.666988 + outer loop + vertex 0.799236 1.65969 2.55664 + vertex 0.80158 1.65898 2.55934 + vertex 0.799957 1.66303 2.55697 + endloop + endfacet + facet normal -0.740171 0.0885814 0.666558 + outer loop + vertex 0.799236 1.65969 2.55664 + vertex 0.799332 1.65593 2.55725 + vertex 0.80158 1.65898 2.55934 + endloop + endfacet + facet normal -0.728893 0.0898018 0.678712 + outer loop + vertex 0.804439 1.66453 2.56167 + vertex 0.802346 1.66374 2.55952 + vertex 0.804335 1.6608 2.56205 + endloop + endfacet + facet normal -0.718058 0.0888989 0.690282 + outer loop + vertex 0.804335 1.6608 2.56205 + vertex 0.804228 1.65608 2.56254 + vertex 0.806752 1.65839 2.56487 + endloop + endfacet + facet normal -0.724719 0.0855551 0.683712 + outer loop + vertex 0.804082 1.65109 2.56301 + vertex 0.804228 1.65608 2.56254 + vertex 0.801647 1.65358 2.56012 + endloop + endfacet + facet normal -0.715604 0.0807651 0.693821 + outer loop + vertex 0.804082 1.65109 2.56301 + vertex 0.803791 1.64611 2.56329 + vertex 0.806448 1.64865 2.56574 + endloop + endfacet + facet normal -0.722997 0.0764743 0.686605 + outer loop + vertex 0.803438 1.64116 2.56347 + vertex 0.803791 1.64611 2.56329 + vertex 0.801175 1.64355 2.56082 + endloop + endfacet + facet normal -0.743065 0.0806688 0.664339 + outer loop + vertex 0.799135 1.65105 2.55764 + vertex 0.798901 1.64596 2.558 + vertex 0.801456 1.64853 2.56055 + endloop + endfacet + facet normal -0.74455 0.0761913 0.663205 + outer loop + vertex 0.801175 1.64355 2.56082 + vertex 0.798696 1.64096 2.55834 + vertex 0.80086 1.63863 2.56104 + endloop + endfacet + facet normal -0.831383 0.0629484 0.552122 + outer loop + vertex 0.794113 1.63117 2.55313 + vertex 0.793853 1.62619 2.5533 + vertex 0.795932 1.62856 2.55616 + endloop + endfacet + facet normal -0.790604 0.0638082 0.608994 + outer loop + vertex 0.797933 1.62094 2.55955 + vertex 0.798028 1.62597 2.55914 + vertex 0.795779 1.62342 2.55649 + endloop + endfacet + facet normal -0.826833 0.0655575 0.558613 + outer loop + vertex 0.795862 1.61777 2.55719 + vertex 0.793429 1.61579 2.55382 + vertex 0.795295 1.61248 2.55697 + endloop + endfacet + facet normal -0.755835 0.0526602 0.652641 + outer loop + vertex 0.797184 1.60918 2.55974 + vertex 0.799472 1.6111 2.56223 + vertex 0.797476 1.61372 2.55971 + endloop + endfacet + facet normal -0.758418 0.0481271 0.649989 + outer loop + vertex 0.799279 1.61483 2.56173 + vertex 0.797476 1.61372 2.55971 + vertex 0.799472 1.6111 2.56223 + endloop + endfacet + facet normal -0.825764 0.0674495 0.559969 + outer loop + vertex 0.793429 1.61579 2.55382 + vertex 0.793177 1.61077 2.55405 + vertex 0.795295 1.61248 2.55697 + endloop + endfacet + facet normal -0.788249 0.053539 0.613022 + outer loop + vertex 0.794968 1.6079 2.557 + vertex 0.796641 1.60398 2.55949 + vertex 0.797184 1.60918 2.55974 + endloop + endfacet + facet normal -0.757513 0.0485479 0.651012 + outer loop + vertex 0.796641 1.60398 2.55949 + vertex 0.799362 1.60625 2.56249 + vertex 0.797184 1.60918 2.55974 + endloop + endfacet + facet normal -0.758439 0.0513693 0.649717 + outer loop + vertex 0.799194 1.60114 2.5627 + vertex 0.799362 1.60625 2.56249 + vertex 0.796641 1.60398 2.55949 + endloop + endfacet + facet normal -0.758862 0.0484189 0.649449 + outer loop + vertex 0.798888 1.59109 2.56311 + vertex 0.79906 1.59607 2.56294 + vertex 0.79667 1.59354 2.56033 + endloop + endfacet + facet normal -0.759341 0.0474338 0.648962 + outer loop + vertex 0.796496 1.58857 2.56049 + vertex 0.798888 1.59109 2.56311 + vertex 0.79667 1.59354 2.56033 + endloop + endfacet + facet normal -0.785273 0.0490103 0.617207 + outer loop + vertex 0.794615 1.60085 2.55715 + vertex 0.79456 1.59612 2.55746 + vertex 0.796778 1.59854 2.56009 + endloop + endfacet + facet normal -0.751968 0.0265033 0.658666 + outer loop + vertex 0.795715 1.5587 2.56138 + vertex 0.798115 1.56118 2.56402 + vertex 0.795791 1.56367 2.56127 + endloop + endfacet + facet normal -0.730139 0.0286299 0.682699 + outer loop + vertex 0.798198 1.56615 2.5639 + vertex 0.798115 1.56118 2.56402 + vertex 0.800569 1.56371 2.56654 + endloop + endfacet + facet normal -0.752627 0.033279 0.657605 + outer loop + vertex 0.798198 1.56615 2.5639 + vertex 0.7983 1.57114 2.56377 + vertex 0.795887 1.56864 2.56113 + endloop + endfacet + facet normal -0.715092 0.0305589 0.698362 + outer loop + vertex 0.803062 1.56623 2.56899 + vertex 0.803167 1.57123 2.56888 + vertex 0.800662 1.5687 2.56643 + endloop + endfacet + facet normal -0.733935 0.0390917 0.678093 + outer loop + vertex 0.798422 1.57613 2.56361 + vertex 0.7983 1.57114 2.56377 + vertex 0.800772 1.5737 2.56629 + endloop + endfacet + facet normal -0.75776 0.043157 0.651105 + outer loop + vertex 0.798422 1.57613 2.56361 + vertex 0.79856 1.58113 2.56344 + vertex 0.796158 1.57861 2.56081 + endloop + endfacet + facet normal -0.716339 0.0418385 0.696496 + outer loop + vertex 0.80329 1.57623 2.56874 + vertex 0.803429 1.58124 2.56859 + vertex 0.800898 1.5787 2.56614 + endloop + endfacet + facet normal -0.735899 0.0463345 0.675505 + outer loop + vertex 0.798716 1.58612 2.56327 + vertex 0.79856 1.58113 2.56344 + vertex 0.801039 1.58369 2.56597 + endloop + endfacet + facet normal -0.759292 0.0473196 0.649027 + outer loop + vertex 0.798716 1.58612 2.56327 + vertex 0.798888 1.59109 2.56311 + vertex 0.796496 1.58857 2.56049 + endloop + endfacet + facet normal -0.73607 0.0485124 0.675165 + outer loop + vertex 0.79906 1.59607 2.56294 + vertex 0.798888 1.59109 2.56311 + vertex 0.801374 1.59365 2.56563 + endloop + endfacet + facet normal -0.733276 0.0516842 0.677964 + outer loop + vertex 0.799362 1.60625 2.56249 + vertex 0.799194 1.60114 2.5627 + vertex 0.801766 1.60366 2.56529 + endloop + endfacet + facet normal -0.755571 0.0518696 0.65301 + outer loop + vertex 0.799362 1.60625 2.56249 + vertex 0.799472 1.6111 2.56223 + vertex 0.797184 1.60918 2.55974 + endloop + endfacet + facet normal -0.726811 0.054428 0.684677 + outer loop + vertex 0.799279 1.61483 2.56173 + vertex 0.799472 1.6111 2.56223 + vertex 0.801668 1.6141 2.56432 + endloop + endfacet + facet normal -0.725609 0.0608963 0.685408 + outer loop + vertex 0.799279 1.61483 2.56173 + vertex 0.801668 1.6141 2.56432 + vertex 0.799909 1.61816 2.5621 + endloop + endfacet + facet normal -0.749656 0.0715335 0.65795 + outer loop + vertex 0.800573 1.62299 2.56233 + vertex 0.797933 1.62094 2.55955 + vertex 0.799909 1.61816 2.5621 + endloop + endfacet + facet normal -0.749532 0.0717333 0.658071 + outer loop + vertex 0.797933 1.62094 2.55955 + vertex 0.798028 1.61709 2.56008 + vertex 0.799909 1.61816 2.5621 + endloop + endfacet + facet normal -0.748812 0.0682025 0.659264 + outer loop + vertex 0.799909 1.61816 2.5621 + vertex 0.798028 1.61709 2.56008 + vertex 0.799279 1.61483 2.56173 + endloop + endfacet + facet normal -0.759744 0.0538934 0.647985 + outer loop + vertex 0.798028 1.61709 2.56008 + vertex 0.797476 1.61372 2.55971 + vertex 0.799279 1.61483 2.56173 + endloop + endfacet + facet normal -0.722714 0.0685494 0.687739 + outer loop + vertex 0.800573 1.62299 2.56233 + vertex 0.802943 1.62605 2.56452 + vertex 0.800421 1.62855 2.56162 + endloop + endfacet + facet normal -0.709899 0.0698712 0.700829 + outer loop + vertex 0.802883 1.63114 2.56395 + vertex 0.802943 1.62605 2.56452 + vertex 0.805404 1.62845 2.56677 + endloop + endfacet + facet normal -0.703765 0.0688155 0.707093 + outer loop + vertex 0.808021 1.62603 2.56961 + vertex 0.807892 1.63099 2.569 + vertex 0.805404 1.62845 2.56677 + endloop + endfacet + facet normal -0.69658 0.0701643 0.71404 + outer loop + vertex 0.808021 1.62603 2.56961 + vertex 0.808277 1.62288 2.57017 + vertex 0.810806 1.62309 2.57262 + endloop + endfacet + facet normal -0.696592 0.0677986 0.714257 + outer loop + vertex 0.810806 1.62309 2.57262 + vertex 0.808277 1.62288 2.57017 + vertex 0.808702 1.61997 2.57086 + endloop + endfacet + facet normal -0.707577 0.0697806 0.703182 + outer loop + vertex 0.805862 1.62283 2.56778 + vertex 0.803141 1.62208 2.56512 + vertex 0.804426 1.6195 2.56667 + endloop + endfacet + facet normal -0.711977 0.062918 0.699378 + outer loop + vertex 0.804426 1.6195 2.56667 + vertex 0.802311 1.61882 2.56457 + vertex 0.804402 1.61581 2.56697 + endloop + endfacet + facet normal -0.699857 0.0646466 0.711351 + outer loop + vertex 0.808702 1.61997 2.57086 + vertex 0.806596 1.61782 2.56899 + vertex 0.80926 1.61558 2.57181 + endloop + endfacet + facet normal -0.691949 0.0626594 0.719222 + outer loop + vertex 0.80926 1.61558 2.57181 + vertex 0.809499 1.61096 2.57244 + vertex 0.812072 1.61358 2.57469 + endloop + endfacet + facet normal -0.706333 0.0611604 0.705233 + outer loop + vertex 0.804402 1.61581 2.56697 + vertex 0.804403 1.61114 2.56738 + vertex 0.806903 1.61332 2.56969 + endloop + endfacet + facet normal -0.714689 0.0586474 0.69698 + outer loop + vertex 0.804352 1.60617 2.56775 + vertex 0.804403 1.61114 2.56738 + vertex 0.801867 1.60872 2.56498 + endloop + endfacet + facet normal -0.697966 0.057933 0.713784 + outer loop + vertex 0.809399 1.60612 2.57274 + vertex 0.809499 1.61096 2.57244 + vertex 0.806936 1.60858 2.57013 + endloop + endfacet + facet normal -0.689005 0.0544954 0.722705 + outer loop + vertex 0.809399 1.60612 2.57274 + vertex 0.809147 1.60115 2.57287 + vertex 0.811828 1.60366 2.57524 + endloop + endfacet + facet normal -0.706223 0.056002 0.705771 + outer loop + vertex 0.804352 1.60617 2.56775 + vertex 0.804155 1.60118 2.56794 + vertex 0.806767 1.60366 2.57036 + endloop + endfacet + facet normal -0.716895 0.0529781 0.695165 + outer loop + vertex 0.80393 1.5962 2.56809 + vertex 0.804155 1.60118 2.56794 + vertex 0.801571 1.59864 2.56547 + endloop + endfacet + facet normal -0.696149 0.0511522 0.716072 + outer loop + vertex 0.80892 1.59616 2.57301 + vertex 0.809147 1.60115 2.57287 + vertex 0.806525 1.59869 2.5705 + endloop + endfacet + facet normal -0.687466 0.0480816 0.724623 + outer loop + vertex 0.80892 1.59616 2.57301 + vertex 0.808755 1.59119 2.57318 + vertex 0.811375 1.59361 2.57551 + endloop + endfacet + facet normal -0.705473 0.0493644 0.707015 + outer loop + vertex 0.80393 1.5962 2.56809 + vertex 0.803738 1.59122 2.56825 + vertex 0.806319 1.59372 2.57065 + endloop + endfacet + facet normal -0.717619 0.0466432 0.694872 + outer loop + vertex 0.803577 1.58624 2.56842 + vertex 0.803738 1.59122 2.56825 + vertex 0.801197 1.58868 2.56579 + endloop + endfacet + facet normal -0.695053 0.0458996 0.717492 + outer loop + vertex 0.808614 1.58622 2.57336 + vertex 0.808755 1.59119 2.57318 + vertex 0.806155 1.58874 2.57082 + endloop + endfacet + facet normal -0.686595 0.0442218 0.725694 + outer loop + vertex 0.808614 1.58622 2.57336 + vertex 0.808467 1.58124 2.57353 + vertex 0.811103 1.58369 2.57587 + endloop + endfacet + facet normal -0.704809 0.0451226 0.707961 + outer loop + vertex 0.803577 1.58624 2.56842 + vertex 0.803429 1.58124 2.56859 + vertex 0.806006 1.58375 2.57099 + endloop + endfacet + facet normal -0.693829 0.0410504 0.718969 + outer loop + vertex 0.808319 1.57624 2.57367 + vertex 0.808467 1.58124 2.57353 + vertex 0.805857 1.57874 2.57115 + endloop + endfacet + facet normal -0.684616 0.0363852 0.727996 + outer loop + vertex 0.808319 1.57624 2.57367 + vertex 0.808186 1.57124 2.57379 + vertex 0.81082 1.57374 2.57615 + endloop + endfacet + facet normal -0.704958 0.0369021 0.708288 + outer loop + vertex 0.80329 1.57623 2.56874 + vertex 0.803167 1.57123 2.56888 + vertex 0.805718 1.57374 2.57129 + endloop + endfacet + facet normal -0.693339 0.0309891 0.719945 + outer loop + vertex 0.808074 1.56624 2.5739 + vertex 0.808186 1.57124 2.57379 + vertex 0.805598 1.56874 2.57141 + endloop + endfacet + facet normal -0.684727 0.0276527 0.728275 + outer loop + vertex 0.808074 1.56624 2.5739 + vertex 0.807974 1.56124 2.574 + vertex 0.810596 1.56375 2.57637 + endloop + endfacet + facet normal -0.705132 0.0267416 0.708571 + outer loop + vertex 0.803062 1.56623 2.56899 + vertex 0.80297 1.56124 2.56909 + vertex 0.805495 1.56374 2.57151 + endloop + endfacet + facet normal -0.714801 0.0254828 0.698863 + outer loop + vertex 0.802883 1.55625 2.56918 + vertex 0.80297 1.56124 2.56909 + vertex 0.800488 1.55872 2.56664 + endloop + endfacet + facet normal -0.695389 0.0261876 0.718156 + outer loop + vertex 0.807878 1.55624 2.57409 + vertex 0.807974 1.56124 2.574 + vertex 0.805401 1.55874 2.5716 + endloop + endfacet + facet normal -0.686492 0.0257816 0.72668 + outer loop + vertex 0.807878 1.55624 2.57409 + vertex 0.807783 1.55124 2.57418 + vertex 0.810397 1.55375 2.57656 + endloop + endfacet + facet normal -0.704847 0.0251194 0.708914 + outer loop + vertex 0.802883 1.55625 2.56918 + vertex 0.802798 1.55126 2.56928 + vertex 0.80531 1.55374 2.57169 + endloop + endfacet + facet normal -0.716643 0.0242346 0.697019 + outer loop + vertex 0.802713 1.54626 2.56936 + vertex 0.802798 1.55126 2.56928 + vertex 0.800341 1.54876 2.56684 + endloop + endfacet + facet normal -0.69603 0.0250867 0.717574 + outer loop + vertex 0.807692 1.54624 2.57426 + vertex 0.807783 1.55124 2.57418 + vertex 0.805219 1.54874 2.57177 + endloop + endfacet + facet normal -0.686343 0.0230695 0.726912 + outer loop + vertex 0.807692 1.54624 2.57426 + vertex 0.807611 1.54123 2.57434 + vertex 0.810215 1.54374 2.57672 + endloop + endfacet + facet normal -0.707205 0.02112 0.706693 + outer loop + vertex 0.802713 1.54626 2.56936 + vertex 0.802632 1.54125 2.56943 + vertex 0.805132 1.54374 2.57186 + endloop + endfacet + facet normal -0.720776 0.0183092 0.692926 + outer loop + vertex 0.802568 1.53624 2.5695 + vertex 0.802632 1.54125 2.56943 + vertex 0.800188 1.53878 2.56695 + endloop + endfacet + facet normal -0.696059 0.0191458 0.717729 + outer loop + vertex 0.80755 1.53624 2.57442 + vertex 0.807611 1.54123 2.57434 + vertex 0.805057 1.53873 2.57193 + endloop + endfacet + facet normal -0.684876 0.0149441 0.728507 + outer loop + vertex 0.80755 1.53624 2.57442 + vertex 0.807492 1.53128 2.57447 + vertex 0.810095 1.53376 2.57686 + endloop + endfacet + facet normal -0.709201 0.0149709 0.704848 + outer loop + vertex 0.802568 1.53624 2.5695 + vertex 0.802557 1.53127 2.56959 + vertex 0.805007 1.53375 2.572 + endloop + endfacet + facet normal -0.69539 0.00986785 0.718565 + outer loop + vertex 0.807378 1.52635 2.57442 + vertex 0.807492 1.53128 2.57447 + vertex 0.804974 1.52889 2.57206 + endloop + endfacet + facet normal -0.706007 -0.00180904 0.708203 + outer loop + vertex 0.804407 1.52091 2.57158 + vertex 0.802448 1.5193 2.56962 + vertex 0.804802 1.51719 2.57197 + endloop + endfacet + facet normal -0.686666 0.00238211 0.726969 + outer loop + vertex 0.806982 1.52102 2.57408 + vertex 0.807527 1.51577 2.57461 + vertex 0.809962 1.51872 2.5769 + endloop + endfacet + facet normal -0.687914 -0.00672417 0.725761 + outer loop + vertex 0.807409 1.5015 2.57442 + vertex 0.807518 1.49634 2.57447 + vertex 0.810044 1.49887 2.57689 + endloop + endfacet + facet normal -0.706429 -0.0113428 0.707693 + outer loop + vertex 0.802547 1.49631 2.56958 + vertex 0.802598 1.49133 2.56955 + vertex 0.805043 1.49381 2.57203 + endloop + endfacet + facet normal -0.714948 -0.0165579 0.698982 + outer loop + vertex 0.802661 1.48635 2.5695 + vertex 0.802598 1.49133 2.56955 + vertex 0.800184 1.48889 2.56702 + endloop + endfacet + facet normal -0.696745 -0.0165114 0.717129 + outer loop + vertex 0.807651 1.48632 2.57441 + vertex 0.807588 1.4913 2.57446 + vertex 0.805105 1.48881 2.57199 + endloop + endfacet + facet normal -0.705818 -0.0207079 0.708091 + outer loop + vertex 0.802661 1.48635 2.5695 + vertex 0.802735 1.48136 2.56942 + vertex 0.805173 1.48383 2.57193 + endloop + endfacet + facet normal -0.716723 -0.0227726 0.696986 + outer loop + vertex 0.802816 1.47637 2.56934 + vertex 0.802735 1.48136 2.56942 + vertex 0.800334 1.47888 2.56687 + endloop + endfacet + facet normal -0.696961 -0.023402 0.716727 + outer loop + vertex 0.807808 1.47636 2.57425 + vertex 0.807723 1.48134 2.57433 + vertex 0.805251 1.47885 2.57185 + endloop + endfacet + facet normal -0.689022 -0.0250956 0.724306 + outer loop + vertex 0.807808 1.47636 2.57425 + vertex 0.807901 1.47137 2.57417 + vertex 0.810404 1.47387 2.57664 + endloop + endfacet + facet normal -0.704882 -0.0234569 0.708936 + outer loop + vertex 0.802816 1.47637 2.56934 + vertex 0.802903 1.47138 2.56927 + vertex 0.805337 1.47387 2.57177 + endloop + endfacet + facet normal -0.715169 -0.0275145 0.69841 + outer loop + vertex 0.803005 1.46639 2.56917 + vertex 0.802903 1.47138 2.56927 + vertex 0.80051 1.46886 2.56672 + endloop + endfacet + facet normal -0.69504 -0.0287426 0.718396 + outer loop + vertex 0.808007 1.46638 2.57407 + vertex 0.807901 1.47137 2.57417 + vertex 0.805432 1.46888 2.57168 + endloop + endfacet + facet normal -0.687867 -0.0329433 0.725089 + outer loop + vertex 0.808007 1.46638 2.57407 + vertex 0.808129 1.4614 2.57396 + vertex 0.810625 1.46389 2.57644 + endloop + endfacet + facet normal -0.703926 -0.0330796 0.709503 + outer loop + vertex 0.803005 1.46639 2.56917 + vertex 0.803124 1.4614 2.56906 + vertex 0.805544 1.4639 2.57158 + endloop + endfacet + facet normal -0.714594 -0.0388031 0.698462 + outer loop + vertex 0.803257 1.45642 2.56892 + vertex 0.803124 1.4614 2.56906 + vertex 0.800751 1.45887 2.56649 + endloop + endfacet + facet normal -0.695743 -0.0359822 0.717389 + outer loop + vertex 0.808261 1.45641 2.57384 + vertex 0.808129 1.4614 2.57396 + vertex 0.805671 1.45891 2.57145 + endloop + endfacet + facet normal -0.688375 -0.0370835 0.724407 + outer loop + vertex 0.808261 1.45641 2.57384 + vertex 0.808398 1.45142 2.57371 + vertex 0.810889 1.45392 2.57621 + endloop + endfacet + facet normal -0.705697 -0.0410659 0.707323 + outer loop + vertex 0.803257 1.45642 2.56892 + vertex 0.803394 1.45142 2.56876 + vertex 0.805808 1.45392 2.57132 + endloop + endfacet + facet normal -0.717324 -0.0405796 0.695557 + outer loop + vertex 0.80353 1.44642 2.56861 + vertex 0.803394 1.45142 2.56876 + vertex 0.801018 1.44888 2.56617 + endloop + endfacet + facet normal -0.699372 -0.0375453 0.713771 + outer loop + vertex 0.808538 1.44642 2.57359 + vertex 0.808398 1.45142 2.57371 + vertex 0.805946 1.44893 2.57118 + endloop + endfacet + facet normal -0.689984 -0.0395639 0.722742 + outer loop + vertex 0.808538 1.44642 2.57359 + vertex 0.808689 1.44141 2.57346 + vertex 0.811173 1.44391 2.57597 + endloop + endfacet + facet normal -0.708569 -0.0403515 0.704487 + outer loop + vertex 0.80353 1.44642 2.56861 + vertex 0.803675 1.44143 2.56847 + vertex 0.80609 1.44392 2.57104 + endloop + endfacet + facet normal -0.715732 -0.0419869 0.697112 + outer loop + vertex 0.803836 1.43647 2.56834 + vertex 0.803675 1.44143 2.56847 + vertex 0.801296 1.43893 2.56588 + endloop + endfacet + facet normal -0.700091 -0.0426734 0.712777 + outer loop + vertex 0.808847 1.43641 2.57331 + vertex 0.808689 1.44141 2.57346 + vertex 0.806246 1.43893 2.57091 + endloop + endfacet + facet normal -0.689736 -0.0457146 0.722616 + outer loop + vertex 0.808847 1.43641 2.57331 + vertex 0.808998 1.43144 2.57314 + vertex 0.811481 1.43391 2.57567 + endloop + endfacet + facet normal -0.707572 -0.044242 0.705255 + outer loop + vertex 0.803836 1.43647 2.56834 + vertex 0.804 1.43151 2.56819 + vertex 0.806408 1.43396 2.57076 + endloop + endfacet + facet normal -0.713578 -0.046608 0.699024 + outer loop + vertex 0.804143 1.42653 2.56801 + vertex 0.804 1.43151 2.56819 + vertex 0.801616 1.42897 2.56559 + endloop + endfacet + facet normal -0.699072 -0.0480176 0.713437 + outer loop + vertex 0.809141 1.42648 2.57295 + vertex 0.808998 1.43144 2.57314 + vertex 0.806558 1.429 2.57059 + endloop + endfacet + facet normal -0.689189 -0.0510243 0.722783 + outer loop + vertex 0.809141 1.42648 2.57295 + vertex 0.809327 1.42149 2.57277 + vertex 0.8118 1.42396 2.57531 + endloop + endfacet + facet normal -0.706307 -0.0498683 0.706147 + outer loop + vertex 0.804143 1.42653 2.56801 + vertex 0.804259 1.42148 2.56777 + vertex 0.806696 1.42403 2.57038 + endloop + endfacet + facet normal -0.712496 -0.0542174 0.699579 + outer loop + vertex 0.804399 1.41636 2.56751 + vertex 0.804259 1.42148 2.56777 + vertex 0.801812 1.41876 2.56506 + endloop + endfacet + facet normal -0.697286 -0.0545652 0.714714 + outer loop + vertex 0.809645 1.41645 2.5727 + vertex 0.809327 1.42149 2.57277 + vertex 0.806875 1.41901 2.57019 + endloop + endfacet + facet normal -0.68835 -0.0577231 0.723078 + outer loop + vertex 0.809645 1.41645 2.5727 + vertex 0.810286 1.41111 2.57288 + vertex 0.812455 1.414 2.57518 + endloop + endfacet + facet normal -0.695451 -0.0599988 0.716064 + outer loop + vertex 0.809988 1.40648 2.57221 + vertex 0.810286 1.41111 2.57288 + vertex 0.807585 1.40933 2.57011 + endloop + endfacet + facet normal -0.705816 -0.0582101 0.706 + outer loop + vertex 0.804399 1.41636 2.56751 + vertex 0.804812 1.41138 2.56751 + vertex 0.807208 1.414 2.57013 + endloop + endfacet + facet normal -0.696399 -0.0615733 0.715009 + outer loop + vertex 0.807874 1.40568 2.57008 + vertex 0.809988 1.40648 2.57221 + vertex 0.807585 1.40933 2.57011 + endloop + endfacet + facet normal -0.695792 -0.0641557 0.715372 + outer loop + vertex 0.809417 1.4032 2.57136 + vertex 0.809988 1.40648 2.57221 + vertex 0.807874 1.40568 2.57008 + endloop + endfacet + facet normal -0.689331 -0.0668304 0.721357 + outer loop + vertex 0.809417 1.4032 2.57136 + vertex 0.812226 1.40226 2.57395 + vertex 0.809988 1.40648 2.57221 + endloop + endfacet + facet normal -0.680617 -0.0648154 0.729767 + outer loop + vertex 0.812226 1.40226 2.57395 + vertex 0.812942 1.39667 2.57412 + vertex 0.81539 1.39914 2.57663 + endloop + endfacet + facet normal -0.689759 -0.0670184 0.72093 + outer loop + vertex 0.813323 1.39149 2.57401 + vertex 0.812942 1.39667 2.57412 + vertex 0.81058 1.3941 2.57163 + endloop + endfacet + facet normal -0.681674 -0.069698 0.728328 + outer loop + vertex 0.813323 1.39149 2.57401 + vertex 0.813556 1.38645 2.57374 + vertex 0.816003 1.38895 2.57627 + endloop + endfacet + facet normal -0.690941 -0.0740769 0.719105 + outer loop + vertex 0.813744 1.38144 2.57341 + vertex 0.813556 1.38645 2.57374 + vertex 0.811131 1.38395 2.57116 + endloop + endfacet + facet normal -0.683534 -0.0785997 0.725675 + outer loop + vertex 0.813744 1.38144 2.57341 + vertex 0.813945 1.37646 2.57306 + vertex 0.816407 1.37901 2.57565 + endloop + endfacet + facet normal -0.692201 -0.0820049 0.717031 + outer loop + vertex 0.814254 1.37156 2.5728 + vertex 0.813945 1.37646 2.57306 + vertex 0.811531 1.37397 2.57044 + endloop + endfacet + facet normal -0.683899 -0.0833601 0.724799 + outer loop + vertex 0.814254 1.37156 2.5728 + vertex 0.814776 1.36683 2.57274 + vertex 0.817117 1.36915 2.57522 + endloop + endfacet + facet normal -0.691298 -0.0866456 0.717356 + outer loop + vertex 0.815575 1.36232 2.57297 + vertex 0.814776 1.36683 2.57274 + vertex 0.812666 1.36453 2.57043 + endloop + endfacet + facet normal -0.691437 -0.0870369 0.717175 + outer loop + vertex 0.813719 1.36009 2.57091 + vertex 0.815575 1.36232 2.57297 + vertex 0.812666 1.36453 2.57043 + endloop + endfacet + facet normal -0.695566 -0.0898602 0.712821 + outer loop + vertex 0.811944 1.35711 2.5688 + vertex 0.814493 1.35714 2.57129 + vertex 0.813719 1.36009 2.57091 + endloop + endfacet + facet normal -0.700425 -0.0914358 0.707845 + outer loop + vertex 0.812951 1.35173 2.5691 + vertex 0.811944 1.35711 2.5688 + vertex 0.810059 1.35412 2.56655 + endloop + endfacet + facet normal -0.708601 -0.0931675 0.699432 + outer loop + vertex 0.810059 1.35412 2.56655 + vertex 0.807933 1.35184 2.56409 + vertex 0.810742 1.34925 2.56659 + endloop + endfacet + facet normal -0.739901 -0.0902888 0.666629 + outer loop + vertex 0.803128 1.35598 2.55952 + vertex 0.804795 1.35674 2.56147 + vertex 0.803976 1.35919 2.56089 + endloop + endfacet + facet normal -0.728755 -0.08734 0.679181 + outer loop + vertex 0.803976 1.35919 2.56089 + vertex 0.805712 1.36185 2.5631 + vertex 0.80274 1.36328 2.56009 + endloop + endfacet + facet normal -0.712213 -0.0901995 0.696144 + outer loop + vertex 0.806975 1.35702 2.56379 + vertex 0.809443 1.35718 2.56633 + vertex 0.808703 1.36005 2.56595 + endloop + endfacet + facet normal -0.705597 -0.0860592 0.703368 + outer loop + vertex 0.808703 1.36005 2.56595 + vertex 0.810688 1.36218 2.5682 + vertex 0.807656 1.36445 2.56544 + endloop + endfacet + facet normal -0.728985 -0.0887182 0.678756 + outer loop + vertex 0.805712 1.36185 2.5631 + vertex 0.804716 1.36645 2.56263 + vertex 0.80274 1.36328 2.56009 + endloop + endfacet + facet normal -0.729938 -0.0874383 0.677898 + outer loop + vertex 0.80274 1.36328 2.56009 + vertex 0.804716 1.36645 2.56263 + vertex 0.801628 1.36831 2.55955 + endloop + endfacet + facet normal -0.744273 -0.0923904 0.661455 + outer loop + vertex 0.801628 1.36831 2.55955 + vertex 0.800043 1.3641 2.55717 + vertex 0.80274 1.36328 2.56009 + endloop + endfacet + facet normal -0.741656 -0.0948326 0.664043 + outer loop + vertex 0.799206 1.36754 2.55673 + vertex 0.800043 1.3641 2.55717 + vertex 0.801628 1.36831 2.55955 + endloop + endfacet + facet normal -0.742434 -0.091126 0.663692 + outer loop + vertex 0.79938 1.3714 2.55745 + vertex 0.799206 1.36754 2.55673 + vertex 0.801628 1.36831 2.55955 + endloop + endfacet + facet normal -0.738528 -0.0847584 0.668874 + outer loop + vertex 0.80162 1.37385 2.56024 + vertex 0.79938 1.3714 2.55745 + vertex 0.801628 1.36831 2.55955 + endloop + endfacet + facet normal -0.728146 -0.0861312 0.679989 + outer loop + vertex 0.801628 1.36831 2.55955 + vertex 0.80418 1.3714 2.56267 + vertex 0.80162 1.37385 2.56024 + endloop + endfacet + facet normal -0.726155 -0.0813502 0.682701 + outer loop + vertex 0.80418 1.3714 2.56267 + vertex 0.803979 1.37652 2.56307 + vertex 0.80162 1.37385 2.56024 + endloop + endfacet + facet normal -0.725307 -0.0828622 0.68342 + outer loop + vertex 0.80162 1.37385 2.56024 + vertex 0.803979 1.37652 2.56307 + vertex 0.801463 1.37898 2.5607 + endloop + endfacet + facet normal -0.7378 -0.0820496 0.670015 + outer loop + vertex 0.801463 1.37898 2.5607 + vertex 0.799266 1.37622 2.55794 + vertex 0.80162 1.37385 2.56024 + endloop + endfacet + facet normal -0.738896 -0.0801976 0.66903 + outer loop + vertex 0.79898 1.38129 2.55823 + vertex 0.799266 1.37622 2.55794 + vertex 0.801463 1.37898 2.5607 + endloop + endfacet + facet normal -0.739054 -0.0806068 0.668806 + outer loop + vertex 0.80122 1.38407 2.56104 + vertex 0.79898 1.38129 2.55823 + vertex 0.801463 1.37898 2.5607 + endloop + endfacet + facet normal -0.723506 -0.080998 0.68555 + outer loop + vertex 0.801463 1.37898 2.5607 + vertex 0.803785 1.3816 2.56345 + vertex 0.80122 1.38407 2.56104 + endloop + endfacet + facet normal -0.740778 -0.0776418 0.667248 + outer loop + vertex 0.798735 1.38645 2.55856 + vertex 0.79898 1.38129 2.55823 + vertex 0.80122 1.38407 2.56104 + endloop + endfacet + facet normal -0.740567 -0.0771137 0.667543 + outer loop + vertex 0.800945 1.38911 2.56132 + vertex 0.798735 1.38645 2.55856 + vertex 0.80122 1.38407 2.56104 + endloop + endfacet + facet normal -0.722127 -0.0771973 0.68744 + outer loop + vertex 0.80122 1.38407 2.56104 + vertex 0.803537 1.38665 2.56376 + vertex 0.800945 1.38911 2.56132 + endloop + endfacet + facet normal -0.72074 -0.0739391 0.689251 + outer loop + vertex 0.803537 1.38665 2.56376 + vertex 0.803256 1.39165 2.564 + vertex 0.800945 1.38911 2.56132 + endloop + endfacet + facet normal -0.722383 -0.0709496 0.687844 + outer loop + vertex 0.800945 1.38911 2.56132 + vertex 0.803256 1.39165 2.564 + vertex 0.800694 1.39407 2.56156 + endloop + endfacet + facet normal -0.743515 -0.070877 0.664953 + outer loop + vertex 0.800694 1.39407 2.56156 + vertex 0.798474 1.39147 2.5588 + vertex 0.800945 1.38911 2.56132 + endloop + endfacet + facet normal -0.74675 -0.0649048 0.661931 + outer loop + vertex 0.798261 1.39641 2.55905 + vertex 0.798474 1.39147 2.5588 + vertex 0.800694 1.39407 2.56156 + endloop + endfacet + facet normal -0.743746 -0.0714623 0.664631 + outer loop + vertex 0.798474 1.39147 2.5588 + vertex 0.798735 1.38645 2.55856 + vertex 0.800945 1.38911 2.56132 + endloop + endfacet + facet normal -0.724064 -0.0800038 0.685077 + outer loop + vertex 0.803979 1.37652 2.56307 + vertex 0.803785 1.3816 2.56345 + vertex 0.801463 1.37898 2.5607 + endloop + endfacet + facet normal -0.738763 -0.0843116 0.66867 + outer loop + vertex 0.799266 1.37622 2.55794 + vertex 0.79938 1.3714 2.55745 + vertex 0.80162 1.37385 2.56024 + endloop + endfacet + facet normal -0.768498 -0.105617 0.631076 + outer loop + vertex 0.799206 1.36754 2.55673 + vertex 0.798095 1.36507 2.55496 + vertex 0.800043 1.3641 2.55717 + endloop + endfacet + facet normal -0.769761 -0.115782 0.627744 + outer loop + vertex 0.798225 1.36108 2.55439 + vertex 0.800043 1.3641 2.55717 + vertex 0.798095 1.36507 2.55496 + endloop + endfacet + facet normal -0.729218 -0.0843127 0.679067 + outer loop + vertex 0.804716 1.36645 2.56263 + vertex 0.80418 1.3714 2.56267 + vertex 0.801628 1.36831 2.55955 + endloop + endfacet + facet normal -0.706255 -0.0880484 0.702461 + outer loop + vertex 0.810688 1.36218 2.5682 + vertex 0.809744 1.3668 2.56783 + vertex 0.807656 1.36445 2.56544 + endloop + endfacet + facet normal -0.700914 -0.0835652 0.708333 + outer loop + vertex 0.80919 1.37155 2.56784 + vertex 0.809744 1.3668 2.56783 + vertex 0.811933 1.36915 2.57027 + endloop + endfacet + facet normal -0.719265 -0.0833202 0.689722 + outer loop + vertex 0.80418 1.3714 2.56267 + vertex 0.804716 1.36645 2.56263 + vertex 0.806919 1.36911 2.56525 + endloop + endfacet + facet normal -0.710269 -0.0815435 0.699191 + outer loop + vertex 0.80919 1.37155 2.56784 + vertex 0.808912 1.37647 2.56813 + vertex 0.806546 1.37401 2.56544 + endloop + endfacet + facet normal -0.702206 -0.0790258 0.707575 + outer loop + vertex 0.808728 1.38148 2.56851 + vertex 0.808912 1.37647 2.56813 + vertex 0.811312 1.37893 2.57079 + endloop + endfacet + facet normal -0.717942 -0.0802576 0.691461 + outer loop + vertex 0.803785 1.3816 2.56345 + vertex 0.803979 1.37652 2.56307 + vertex 0.806346 1.37903 2.56582 + endloop + endfacet + facet normal -0.721984 -0.0774535 0.687561 + outer loop + vertex 0.803785 1.3816 2.56345 + vertex 0.803537 1.38665 2.56376 + vertex 0.80122 1.38407 2.56104 + endloop + endfacet + facet normal -0.709836 -0.0751116 0.700351 + outer loop + vertex 0.808728 1.38148 2.56851 + vertex 0.808522 1.38652 2.56884 + vertex 0.806144 1.38408 2.56617 + endloop + endfacet + facet normal -0.701464 -0.0715314 0.709106 + outer loop + vertex 0.808233 1.39159 2.56907 + vertex 0.808522 1.38652 2.56884 + vertex 0.810915 1.38899 2.57146 + endloop + endfacet + facet normal -0.715308 -0.0739073 0.69489 + outer loop + vertex 0.803256 1.39165 2.564 + vertex 0.803537 1.38665 2.56376 + vertex 0.805887 1.38912 2.56645 + endloop + endfacet + facet normal -0.722382 -0.0709491 0.687844 + outer loop + vertex 0.803256 1.39165 2.564 + vertex 0.803004 1.39647 2.56424 + vertex 0.800694 1.39407 2.56156 + endloop + endfacet + facet normal -0.724141 -0.0675712 0.686334 + outer loop + vertex 0.800694 1.39407 2.56156 + vertex 0.803004 1.39647 2.56424 + vertex 0.800579 1.39892 2.56192 + endloop + endfacet + facet normal -0.714719 -0.0701941 0.695881 + outer loop + vertex 0.802974 1.40075 2.56464 + vertex 0.803004 1.39647 2.56424 + vertex 0.805133 1.39872 2.56665 + endloop + endfacet + facet normal -0.708449 -0.0698824 0.702293 + outer loop + vertex 0.808233 1.39159 2.56907 + vertex 0.807759 1.39669 2.5691 + vertex 0.805558 1.3941 2.56662 + endloop + endfacet + facet normal -0.700063 -0.0672335 0.710909 + outer loop + vertex 0.806805 1.4021 2.56867 + vertex 0.807759 1.39669 2.5691 + vertex 0.81001 1.3992 2.57155 + endloop + endfacet + facet normal -0.710215 -0.0682268 0.700671 + outer loop + vertex 0.806805 1.4021 2.56867 + vertex 0.805579 1.40688 2.56789 + vertex 0.80389 1.40404 2.5659 + endloop + endfacet + facet normal -0.71525 -0.0714196 0.69521 + outer loop + vertex 0.804685 1.40154 2.56648 + vertex 0.802974 1.40075 2.56464 + vertex 0.805133 1.39872 2.56665 + endloop + endfacet + facet normal -0.72301 -0.0691688 0.687367 + outer loop + vertex 0.80389 1.40404 2.5659 + vertex 0.802734 1.40815 2.5651 + vertex 0.800828 1.40409 2.56269 + endloop + endfacet + facet normal -0.724921 -0.0692764 0.68534 + outer loop + vertex 0.803004 1.39647 2.56424 + vertex 0.802974 1.40075 2.56464 + vertex 0.800579 1.39892 2.56192 + endloop + endfacet + facet normal -0.74849 -0.0653059 0.659923 + outer loop + vertex 0.798027 1.40617 2.55972 + vertex 0.798166 1.40135 2.5594 + vertex 0.800828 1.40409 2.56269 + endloop + endfacet + facet normal -0.747292 -0.0662669 0.661183 + outer loop + vertex 0.800579 1.39892 2.56192 + vertex 0.798261 1.39641 2.55905 + vertex 0.800694 1.39407 2.56156 + endloop + endfacet + facet normal -0.849066 -0.0556129 0.525352 + outer loop + vertex 0.794003 1.4014 2.55333 + vertex 0.794206 1.39648 2.55314 + vertex 0.796024 1.39881 2.55632 + endloop + endfacet + facet normal -0.791718 -0.0641507 0.607509 + outer loop + vertex 0.798474 1.39147 2.5588 + vertex 0.798261 1.39641 2.55905 + vertex 0.796214 1.39386 2.55611 + endloop + endfacet + facet normal -0.78044 -0.0765478 0.620527 + outer loop + vertex 0.79898 1.38129 2.55823 + vertex 0.798735 1.38645 2.55856 + vertex 0.796677 1.38375 2.55564 + endloop + endfacet + facet normal -0.84582 -0.0584621 0.530255 + outer loop + vertex 0.79443 1.39154 2.55299 + vertex 0.794666 1.38656 2.55282 + vertex 0.796453 1.38887 2.55592 + endloop + endfacet +endsolid diff --git a/noether_examples/meshes/outputsBackDoor/output_1.stl b/noether_examples/meshes/outputsBackDoor/output_1.stl new file mode 100644 index 00000000..e7391a1f --- /dev/null +++ b/noether_examples/meshes/outputsBackDoor/output_1.stl @@ -0,0 +1,11454 @@ +solid ascii + facet normal -0.761026 0.11927 0.637663 + outer loop + vertex 0.810858 1.79833 2.54571 + vertex 0.808407 1.7958 2.54326 + vertex 0.810643 1.79311 2.54643 + endloop + endfacet + facet normal -0.754245 0.120075 0.64552 + outer loop + vertex 0.810643 1.79311 2.54643 + vertex 0.81313 1.79566 2.54886 + vertex 0.810858 1.79833 2.54571 + endloop + endfacet + facet normal -0.742581 0.140883 0.654771 + outer loop + vertex 0.81313 1.79566 2.54886 + vertex 0.813425 1.80087 2.54807 + vertex 0.810858 1.79833 2.54571 + endloop + endfacet + facet normal -0.749211 0.158543 0.643076 + outer loop + vertex 0.810858 1.79833 2.54571 + vertex 0.813425 1.80087 2.54807 + vertex 0.811118 1.80371 2.54468 + endloop + endfacet + facet normal -0.738028 0.141383 0.659792 + outer loop + vertex 0.813425 1.80087 2.54807 + vertex 0.81313 1.79566 2.54886 + vertex 0.815727 1.7983 2.5512 + endloop + endfacet + facet normal -0.72528 0.163698 0.668709 + outer loop + vertex 0.816185 1.80358 2.5504 + vertex 0.813425 1.80087 2.54807 + vertex 0.815727 1.7983 2.5512 + endloop + endfacet + facet normal -0.715954 0.164366 0.678523 + outer loop + vertex 0.815727 1.7983 2.5512 + vertex 0.818484 1.80109 2.55343 + vertex 0.816185 1.80358 2.5504 + endloop + endfacet + facet normal -0.705699 0.181529 0.684862 + outer loop + vertex 0.818484 1.80109 2.55343 + vertex 0.819464 1.80667 2.55296 + vertex 0.816185 1.80358 2.5504 + endloop + endfacet + facet normal -0.704281 0.17807 0.687225 + outer loop + vertex 0.816185 1.80358 2.5504 + vertex 0.819464 1.80667 2.55296 + vertex 0.81654 1.80896 2.54937 + endloop + endfacet + facet normal -0.721917 0.175793 0.669278 + outer loop + vertex 0.81654 1.80896 2.54937 + vertex 0.813889 1.80572 2.54736 + vertex 0.816185 1.80358 2.5504 + endloop + endfacet + facet normal -0.718986 0.170622 0.673756 + outer loop + vertex 0.814115 1.80932 2.54669 + vertex 0.813889 1.80572 2.54736 + vertex 0.81654 1.80896 2.54937 + endloop + endfacet + facet normal -0.718718 0.171985 0.673696 + outer loop + vertex 0.814115 1.80932 2.54669 + vertex 0.81654 1.80896 2.54937 + vertex 0.815093 1.81261 2.5469 + endloop + endfacet + facet normal -0.712743 0.177654 0.678554 + outer loop + vertex 0.815093 1.81261 2.5469 + vertex 0.81654 1.80896 2.54937 + vertex 0.817625 1.81371 2.54927 + endloop + endfacet + facet normal -0.712863 0.178918 0.678096 + outer loop + vertex 0.816139 1.81744 2.54672 + vertex 0.815093 1.81261 2.5469 + vertex 0.817625 1.81371 2.54927 + endloop + endfacet + facet normal -0.707916 0.183575 0.682023 + outer loop + vertex 0.818596 1.81703 2.54938 + vertex 0.816139 1.81744 2.54672 + vertex 0.817625 1.81371 2.54927 + endloop + endfacet + facet normal -0.699309 0.180726 0.691596 + outer loop + vertex 0.818596 1.81703 2.54938 + vertex 0.817625 1.81371 2.54927 + vertex 0.819837 1.8152 2.55112 + endloop + endfacet + facet normal -0.706838 0.188538 0.681787 + outer loop + vertex 0.818596 1.81703 2.54938 + vertex 0.818622 1.82065 2.54841 + vertex 0.816139 1.81744 2.54672 + endloop + endfacet + facet normal -0.705769 0.186893 0.683346 + outer loop + vertex 0.816139 1.81744 2.54672 + vertex 0.818622 1.82065 2.54841 + vertex 0.816234 1.82277 2.54536 + endloop + endfacet + facet normal -0.722535 0.182945 0.666689 + outer loop + vertex 0.816234 1.82277 2.54536 + vertex 0.813648 1.82038 2.54321 + vertex 0.816139 1.81744 2.54672 + endloop + endfacet + facet normal -0.727487 0.174909 0.663452 + outer loop + vertex 0.813648 1.82038 2.54321 + vertex 0.813299 1.81534 2.54416 + vertex 0.816139 1.81744 2.54672 + endloop + endfacet + facet normal -0.729203 0.181797 0.659706 + outer loop + vertex 0.816139 1.81744 2.54672 + vertex 0.813299 1.81534 2.54416 + vertex 0.815093 1.81261 2.5469 + endloop + endfacet + facet normal -0.733134 0.176324 0.656829 + outer loop + vertex 0.813299 1.81534 2.54416 + vertex 0.81308 1.81152 2.54494 + vertex 0.815093 1.81261 2.5469 + endloop + endfacet + facet normal -0.733278 0.177391 0.656381 + outer loop + vertex 0.815093 1.81261 2.5469 + vertex 0.81308 1.81152 2.54494 + vertex 0.814115 1.80932 2.54669 + endloop + endfacet + facet normal -0.744077 0.16513 0.647365 + outer loop + vertex 0.81308 1.81152 2.54494 + vertex 0.812153 1.80833 2.54469 + vertex 0.814115 1.80932 2.54669 + endloop + endfacet + facet normal -0.721687 0.180633 0.668236 + outer loop + vertex 0.81399 1.82531 2.54225 + vertex 0.813648 1.82038 2.54321 + vertex 0.816234 1.82277 2.54536 + endloop + endfacet + facet normal -0.714001 0.193194 0.672963 + outer loop + vertex 0.816333 1.82751 2.54411 + vertex 0.81399 1.82531 2.54225 + vertex 0.816234 1.82277 2.54536 + endloop + endfacet + facet normal -0.71314 0.190969 0.674508 + outer loop + vertex 0.814374 1.82913 2.54158 + vertex 0.81399 1.82531 2.54225 + vertex 0.816333 1.82751 2.54411 + endloop + endfacet + facet normal -0.706123 0.20465 0.67787 + outer loop + vertex 0.81613 1.83256 2.54237 + vertex 0.814374 1.82913 2.54158 + vertex 0.816333 1.82751 2.54411 + endloop + endfacet + facet normal -0.701426 0.206334 0.682222 + outer loop + vertex 0.81613 1.83256 2.54237 + vertex 0.816333 1.82751 2.54411 + vertex 0.818657 1.82977 2.54581 + endloop + endfacet + facet normal -0.706046 0.198961 0.679643 + outer loop + vertex 0.81613 1.83256 2.54237 + vertex 0.818657 1.82977 2.54581 + vertex 0.818552 1.83274 2.54484 + endloop + endfacet + facet normal -0.706299 0.196601 0.680066 + outer loop + vertex 0.818552 1.83274 2.54484 + vertex 0.818496 1.83581 2.54389 + vertex 0.81613 1.83256 2.54237 + endloop + endfacet + facet normal -0.703406 0.197496 0.682799 + outer loop + vertex 0.818496 1.83581 2.54389 + vertex 0.818552 1.83274 2.54484 + vertex 0.821034 1.83282 2.54737 + endloop + endfacet + facet normal -0.707785 0.190737 0.680191 + outer loop + vertex 0.820989 1.8382 2.54581 + vertex 0.818496 1.83581 2.54389 + vertex 0.821034 1.83282 2.54737 + endloop + endfacet + facet normal -0.706135 0.191208 0.681772 + outer loop + vertex 0.821034 1.83282 2.54737 + vertex 0.823472 1.83584 2.54905 + vertex 0.820989 1.8382 2.54581 + endloop + endfacet + facet normal -0.708952 0.186149 0.680247 + outer loop + vertex 0.823472 1.83584 2.54905 + vertex 0.823601 1.8406 2.54788 + vertex 0.820989 1.8382 2.54581 + endloop + endfacet + facet normal -0.710009 0.18891 0.678381 + outer loop + vertex 0.820989 1.8382 2.54581 + vertex 0.823601 1.8406 2.54788 + vertex 0.821042 1.84371 2.54433 + endloop + endfacet + facet normal -0.712762 0.188212 0.675682 + outer loop + vertex 0.821042 1.84371 2.54433 + vertex 0.818447 1.84058 2.54247 + vertex 0.820989 1.8382 2.54581 + endloop + endfacet + facet normal -0.715646 0.193279 0.671188 + outer loop + vertex 0.818192 1.84511 2.54089 + vertex 0.818447 1.84058 2.54247 + vertex 0.821042 1.84371 2.54433 + endloop + endfacet + facet normal -0.71851 0.18538 0.670357 + outer loop + vertex 0.818192 1.84511 2.54089 + vertex 0.821042 1.84371 2.54433 + vertex 0.819776 1.84806 2.54177 + endloop + endfacet + facet normal -0.723111 0.189684 0.664176 + outer loop + vertex 0.819776 1.84806 2.54177 + vertex 0.817998 1.84791 2.53988 + vertex 0.818192 1.84511 2.54089 + endloop + endfacet + facet normal -0.745876 0.179874 0.641338 + outer loop + vertex 0.815928 1.84766 2.53754 + vertex 0.818192 1.84511 2.54089 + vertex 0.817998 1.84791 2.53988 + endloop + endfacet + facet normal -0.744593 0.194282 0.63862 + outer loop + vertex 0.817998 1.84791 2.53988 + vertex 0.818187 1.8508 2.53922 + vertex 0.815928 1.84766 2.53754 + endloop + endfacet + facet normal -0.74866 0.200857 0.631795 + outer loop + vertex 0.815928 1.84766 2.53754 + vertex 0.818187 1.8508 2.53922 + vertex 0.816071 1.85306 2.53599 + endloop + endfacet + facet normal -0.752919 0.193103 0.629145 + outer loop + vertex 0.818187 1.8508 2.53922 + vertex 0.818553 1.85551 2.53821 + vertex 0.816071 1.85306 2.53599 + endloop + endfacet + facet normal -0.754969 0.19913 0.624795 + outer loop + vertex 0.816071 1.85306 2.53599 + vertex 0.818553 1.85551 2.53821 + vertex 0.81631 1.85839 2.53459 + endloop + endfacet + facet normal -0.759066 0.192353 0.621948 + outer loop + vertex 0.818553 1.85551 2.53821 + vertex 0.81893 1.8603 2.53719 + vertex 0.81631 1.85839 2.53459 + endloop + endfacet + facet normal -0.759301 0.193597 0.621274 + outer loop + vertex 0.81631 1.85839 2.53459 + vertex 0.81893 1.8603 2.53719 + vertex 0.817361 1.86316 2.53438 + endloop + endfacet + facet normal -0.732762 0.196585 0.651471 + outer loop + vertex 0.81893 1.8603 2.53719 + vertex 0.818553 1.85551 2.53821 + vertex 0.821104 1.85784 2.54038 + endloop + endfacet + facet normal -0.730811 0.190815 0.655367 + outer loop + vertex 0.821104 1.85784 2.54038 + vertex 0.818553 1.85551 2.53821 + vertex 0.820991 1.85252 2.5418 + endloop + endfacet + facet normal -0.7175 0.194162 0.66895 + outer loop + vertex 0.820991 1.85252 2.5418 + vertex 0.823579 1.85542 2.54374 + vertex 0.821104 1.85784 2.54038 + endloop + endfacet + facet normal -0.716937 0.195171 0.66926 + outer loop + vertex 0.823579 1.85542 2.54374 + vertex 0.823541 1.86029 2.54228 + vertex 0.821104 1.85784 2.54038 + endloop + endfacet + facet normal -0.719659 0.201609 0.664413 + outer loop + vertex 0.821104 1.85784 2.54038 + vertex 0.823541 1.86029 2.54228 + vertex 0.821212 1.86256 2.53906 + endloop + endfacet + facet normal -0.70874 0.197624 0.677224 + outer loop + vertex 0.823541 1.86029 2.54228 + vertex 0.823579 1.85542 2.54374 + vertex 0.826072 1.85781 2.54565 + endloop + endfacet + facet normal -0.707498 0.199789 0.677887 + outer loop + vertex 0.82593 1.86274 2.54405 + vertex 0.823541 1.86029 2.54228 + vertex 0.826072 1.85781 2.54565 + endloop + endfacet + facet normal -0.699186 0.202547 0.685649 + outer loop + vertex 0.826072 1.85781 2.54565 + vertex 0.828491 1.86027 2.54739 + vertex 0.82593 1.86274 2.54405 + endloop + endfacet + facet normal -0.697682 0.199317 0.688123 + outer loop + vertex 0.82866 1.85554 2.54893 + vertex 0.828491 1.86027 2.54739 + vertex 0.826072 1.85781 2.54565 + endloop + endfacet + facet normal -0.699397 0.196151 0.687291 + outer loop + vertex 0.826298 1.8523 2.54745 + vertex 0.82866 1.85554 2.54893 + vertex 0.826072 1.85781 2.54565 + endloop + endfacet + facet normal -0.699784 0.196682 0.686744 + outer loop + vertex 0.828755 1.85248 2.5499 + vertex 0.82866 1.85554 2.54893 + vertex 0.826298 1.8523 2.54745 + endloop + endfacet + facet normal -0.700376 0.190913 0.687769 + outer loop + vertex 0.826298 1.8523 2.54745 + vertex 0.828815 1.84959 2.55077 + vertex 0.828755 1.85248 2.5499 + endloop + endfacet + facet normal -0.686524 0.194994 0.700473 + outer loop + vertex 0.831246 1.85277 2.55226 + vertex 0.828755 1.85248 2.5499 + vertex 0.828815 1.84959 2.55077 + endloop + endfacet + facet normal -0.68713 0.195848 0.69964 + outer loop + vertex 0.831246 1.85277 2.55226 + vertex 0.828815 1.84959 2.55077 + vertex 0.831377 1.84793 2.55375 + endloop + endfacet + facet normal -0.677974 0.198584 0.707754 + outer loop + vertex 0.831246 1.85277 2.55226 + vertex 0.831377 1.84793 2.55375 + vertex 0.833911 1.85065 2.55541 + endloop + endfacet + facet normal -0.680053 0.194635 0.706856 + outer loop + vertex 0.831246 1.85277 2.55226 + vertex 0.833911 1.85065 2.55541 + vertex 0.833617 1.85313 2.55445 + endloop + endfacet + facet normal -0.679585 0.202789 0.705011 + outer loop + vertex 0.833617 1.85313 2.55445 + vertex 0.833569 1.85581 2.55363 + vertex 0.831246 1.85277 2.55226 + endloop + endfacet + facet normal -0.679324 0.202431 0.705366 + outer loop + vertex 0.831246 1.85277 2.55226 + vertex 0.833569 1.85581 2.55363 + vertex 0.831091 1.85782 2.55067 + endloop + endfacet + facet normal -0.686625 0.200166 0.698913 + outer loop + vertex 0.831091 1.85782 2.55067 + vertex 0.82866 1.85554 2.54893 + vertex 0.831246 1.85277 2.55226 + endloop + endfacet + facet normal -0.678845 0.203326 0.70557 + outer loop + vertex 0.833569 1.85581 2.55363 + vertex 0.833535 1.86017 2.55234 + vertex 0.831091 1.85782 2.55067 + endloop + endfacet + facet normal -0.679694 0.205168 0.704218 + outer loop + vertex 0.831091 1.85782 2.55067 + vertex 0.833535 1.86017 2.55234 + vertex 0.830924 1.86264 2.5491 + endloop + endfacet + facet normal -0.687691 0.202599 0.697162 + outer loop + vertex 0.830924 1.86264 2.5491 + vertex 0.828491 1.86027 2.54739 + vertex 0.831091 1.85782 2.55067 + endloop + endfacet + facet normal -0.681766 0.20167 0.703225 + outer loop + vertex 0.833378 1.86477 2.55087 + vertex 0.830924 1.86264 2.5491 + vertex 0.833535 1.86017 2.55234 + endloop + endfacet + facet normal -0.676487 0.203325 0.70783 + outer loop + vertex 0.833378 1.86477 2.55087 + vertex 0.833535 1.86017 2.55234 + vertex 0.836015 1.8625 2.55404 + endloop + endfacet + facet normal -0.678622 0.199509 0.706872 + outer loop + vertex 0.835872 1.86774 2.55243 + vertex 0.833378 1.86477 2.55087 + vertex 0.836015 1.8625 2.55404 + endloop + endfacet + facet normal -0.674438 0.200747 0.710516 + outer loop + vertex 0.835872 1.86774 2.55243 + vertex 0.836015 1.8625 2.55404 + vertex 0.838512 1.86472 2.55578 + endloop + endfacet + facet normal -0.676466 0.197757 0.709426 + outer loop + vertex 0.835872 1.86774 2.55243 + vertex 0.838512 1.86472 2.55578 + vertex 0.838374 1.86769 2.55482 + endloop + endfacet + facet normal -0.673717 0.2154 0.7069 + outer loop + vertex 0.838374 1.86769 2.55482 + vertex 0.838415 1.87072 2.55394 + vertex 0.835872 1.86774 2.55243 + endloop + endfacet + facet normal -0.670056 0.20963 0.712096 + outer loop + vertex 0.835872 1.86774 2.55243 + vertex 0.838415 1.87072 2.55394 + vertex 0.836121 1.87294 2.55113 + endloop + endfacet + facet normal -0.677106 0.208389 0.705764 + outer loop + vertex 0.836121 1.87294 2.55113 + vertex 0.833465 1.87104 2.54914 + vertex 0.835872 1.86774 2.55243 + endloop + endfacet + facet normal -0.679044 0.205859 0.704643 + outer loop + vertex 0.833465 1.87104 2.54914 + vertex 0.833298 1.86786 2.54991 + vertex 0.835872 1.86774 2.55243 + endloop + endfacet + facet normal -0.686054 0.204665 0.698171 + outer loop + vertex 0.833298 1.86786 2.54991 + vertex 0.833465 1.87104 2.54914 + vertex 0.830812 1.86794 2.54744 + endloop + endfacet + facet normal -0.686923 0.199241 0.698885 + outer loop + vertex 0.830812 1.86794 2.54744 + vertex 0.833378 1.86477 2.55087 + vertex 0.833298 1.86786 2.54991 + endloop + endfacet + facet normal -0.686331 0.205125 0.697764 + outer loop + vertex 0.830812 1.86794 2.54744 + vertex 0.833465 1.87104 2.54914 + vertex 0.831058 1.87334 2.5461 + endloop + endfacet + facet normal -0.694737 0.203537 0.689865 + outer loop + vertex 0.831058 1.87334 2.5461 + vertex 0.828349 1.87098 2.54406 + vertex 0.830812 1.86794 2.54744 + endloop + endfacet + facet normal -0.691939 0.207579 0.69147 + outer loop + vertex 0.828349 1.87098 2.54406 + vertex 0.828262 1.86794 2.54489 + vertex 0.830812 1.86794 2.54744 + endloop + endfacet + facet normal -0.706813 0.204156 0.677301 + outer loop + vertex 0.828262 1.86794 2.54489 + vertex 0.828349 1.87098 2.54406 + vertex 0.825847 1.86793 2.54237 + endloop + endfacet + facet normal -0.707405 0.200115 0.677888 + outer loop + vertex 0.825847 1.86793 2.54237 + vertex 0.828332 1.86493 2.54585 + vertex 0.828262 1.86794 2.54489 + endloop + endfacet + facet normal -0.692337 0.20493 0.691862 + outer loop + vertex 0.830812 1.86794 2.54744 + vertex 0.828262 1.86794 2.54489 + vertex 0.828332 1.86493 2.54585 + endloop + endfacet + facet normal -0.690808 0.202477 0.694109 + outer loop + vertex 0.830812 1.86794 2.54744 + vertex 0.828332 1.86493 2.54585 + vertex 0.830924 1.86264 2.5491 + endloop + endfacet + facet normal -0.689056 0.205614 0.694928 + outer loop + vertex 0.828332 1.86493 2.54585 + vertex 0.828491 1.86027 2.54739 + vertex 0.830924 1.86264 2.5491 + endloop + endfacet + facet normal -0.701848 0.208483 0.681134 + outer loop + vertex 0.825847 1.86793 2.54237 + vertex 0.82593 1.86274 2.54405 + vertex 0.828332 1.86493 2.54585 + endloop + endfacet + facet normal -0.699407 0.202166 0.685535 + outer loop + vertex 0.828332 1.86493 2.54585 + vertex 0.82593 1.86274 2.54405 + vertex 0.828491 1.86027 2.54739 + endloop + endfacet + facet normal -0.710819 0.205603 0.672654 + outer loop + vertex 0.825847 1.86793 2.54237 + vertex 0.823472 1.86488 2.5408 + vertex 0.82593 1.86274 2.54405 + endloop + endfacet + facet normal -0.710445 0.206307 0.672834 + outer loop + vertex 0.823472 1.86488 2.5408 + vertex 0.823541 1.86029 2.54228 + vertex 0.82593 1.86274 2.54405 + endloop + endfacet + facet normal -0.718504 0.203671 0.665034 + outer loop + vertex 0.823472 1.86488 2.5408 + vertex 0.821212 1.86256 2.53906 + vertex 0.823541 1.86029 2.54228 + endloop + endfacet + facet normal -0.723025 0.21425 0.656758 + outer loop + vertex 0.821096 1.86754 2.53731 + vertex 0.821212 1.86256 2.53906 + vertex 0.823472 1.86488 2.5408 + endloop + endfacet + facet normal -0.72792 0.206164 0.653934 + outer loop + vertex 0.821096 1.86754 2.53731 + vertex 0.823472 1.86488 2.5408 + vertex 0.823424 1.86783 2.53981 + endloop + endfacet + facet normal -0.727295 0.212429 0.652623 + outer loop + vertex 0.823424 1.86783 2.53981 + vertex 0.823454 1.87081 2.53888 + vertex 0.821096 1.86754 2.53731 + endloop + endfacet + facet normal -0.713363 0.216638 0.66647 + outer loop + vertex 0.823454 1.87081 2.53888 + vertex 0.823424 1.86783 2.53981 + vertex 0.825847 1.86793 2.54237 + endloop + endfacet + facet normal -0.721102 0.20467 0.661908 + outer loop + vertex 0.825943 1.87321 2.54085 + vertex 0.823454 1.87081 2.53888 + vertex 0.825847 1.86793 2.54237 + endloop + endfacet + facet normal -0.723466 0.210842 0.657375 + outer loop + vertex 0.823528 1.87547 2.53746 + vertex 0.823454 1.87081 2.53888 + vertex 0.825943 1.87321 2.54085 + endloop + endfacet + facet normal -0.727252 0.203837 0.655405 + outer loop + vertex 0.826125 1.87857 2.53938 + vertex 0.823528 1.87547 2.53746 + vertex 0.825943 1.87321 2.54085 + endloop + endfacet + facet normal -0.713271 0.207229 0.669553 + outer loop + vertex 0.825943 1.87321 2.54085 + vertex 0.828615 1.87569 2.54292 + vertex 0.826125 1.87857 2.53938 + endloop + endfacet + facet normal -0.709719 0.212793 0.671579 + outer loop + vertex 0.828615 1.87569 2.54292 + vertex 0.829138 1.88021 2.54205 + vertex 0.826125 1.87857 2.53938 + endloop + endfacet + facet normal -0.709984 0.21476 0.670672 + outer loop + vertex 0.826125 1.87857 2.53938 + vertex 0.829138 1.88021 2.54205 + vertex 0.827439 1.88301 2.53935 + endloop + endfacet + facet normal -0.715828 0.216441 0.663885 + outer loop + vertex 0.824937 1.88279 2.53672 + vertex 0.826125 1.87857 2.53938 + vertex 0.827439 1.88301 2.53935 + endloop + endfacet + facet normal -0.711572 0.248624 0.657154 + outer loop + vertex 0.826105 1.88704 2.53638 + vertex 0.824937 1.88279 2.53672 + vertex 0.827439 1.88301 2.53935 + endloop + endfacet + facet normal -0.70768 0.247911 0.661611 + outer loop + vertex 0.826105 1.88704 2.53638 + vertex 0.823334 1.88545 2.53401 + vertex 0.824937 1.88279 2.53672 + endloop + endfacet + facet normal -0.729607 0.205287 0.652327 + outer loop + vertex 0.823372 1.87992 2.53588 + vertex 0.826125 1.87857 2.53938 + vertex 0.824937 1.88279 2.53672 + endloop + endfacet + facet normal -0.729412 0.2051 0.652604 + outer loop + vertex 0.824937 1.88279 2.53672 + vertex 0.823209 1.88269 2.53482 + vertex 0.823372 1.87992 2.53588 + endloop + endfacet + facet normal -0.750621 0.195679 0.631092 + outer loop + vertex 0.821118 1.8824 2.53243 + vertex 0.823372 1.87992 2.53588 + vertex 0.823209 1.88269 2.53482 + endloop + endfacet + facet normal -0.748352 0.218021 0.626447 + outer loop + vertex 0.823209 1.88269 2.53482 + vertex 0.823334 1.88545 2.53401 + vertex 0.821118 1.8824 2.53243 + endloop + endfacet + facet normal -0.747805 0.217123 0.627411 + outer loop + vertex 0.821118 1.8824 2.53243 + vertex 0.823334 1.88545 2.53401 + vertex 0.82117 1.8876 2.53069 + endloop + endfacet + facet normal -0.771001 0.208741 0.601651 + outer loop + vertex 0.82117 1.8876 2.53069 + vertex 0.818824 1.88548 2.52842 + vertex 0.821118 1.8824 2.53243 + endloop + endfacet + facet normal -0.773498 0.218765 0.594847 + outer loop + vertex 0.81923 1.89007 2.52726 + vertex 0.818824 1.88548 2.52842 + vertex 0.82117 1.8876 2.53069 + endloop + endfacet + facet normal -0.74289 0.209301 0.635852 + outer loop + vertex 0.821118 1.8824 2.53243 + vertex 0.82124 1.87747 2.53419 + vertex 0.823372 1.87992 2.53588 + endloop + endfacet + facet normal -0.726887 0.223766 0.64928 + outer loop + vertex 0.823334 1.88545 2.53401 + vertex 0.823209 1.88269 2.53482 + vertex 0.824937 1.88279 2.53672 + endloop + endfacet + facet normal -0.688285 0.21448 0.69301 + outer loop + vertex 0.829138 1.88021 2.54205 + vertex 0.828615 1.87569 2.54292 + vertex 0.831438 1.87817 2.54496 + endloop + endfacet + facet normal -0.665623 0.253094 0.702061 + outer loop + vertex 0.831755 1.88257 2.54368 + vertex 0.829138 1.88021 2.54205 + vertex 0.831438 1.87817 2.54496 + endloop + endfacet + facet normal -0.649906 0.255929 0.715627 + outer loop + vertex 0.831438 1.87817 2.54496 + vertex 0.834345 1.88113 2.54654 + vertex 0.831755 1.88257 2.54368 + endloop + endfacet + facet normal -0.653566 0.262614 0.709849 + outer loop + vertex 0.834224 1.87624 2.54824 + vertex 0.834345 1.88113 2.54654 + vertex 0.831438 1.87817 2.54496 + endloop + endfacet + facet normal -0.676388 0.218701 0.703327 + outer loop + vertex 0.831058 1.87334 2.5461 + vertex 0.834224 1.87624 2.54824 + vertex 0.831438 1.87817 2.54496 + endloop + endfacet + facet normal -0.662787 0.246497 0.707073 + outer loop + vertex 0.829728 1.88374 2.54137 + vertex 0.829138 1.88021 2.54205 + vertex 0.831755 1.88257 2.54368 + endloop + endfacet + facet normal -0.622659 0.32513 0.711748 + outer loop + vertex 0.831828 1.88739 2.54154 + vertex 0.829728 1.88374 2.54137 + vertex 0.831755 1.88257 2.54368 + endloop + endfacet + facet normal -0.621749 0.324558 0.712804 + outer loop + vertex 0.831828 1.88739 2.54154 + vertex 0.828734 1.88612 2.53942 + vertex 0.829728 1.88374 2.54137 + endloop + endfacet + facet normal -0.683854 0.246127 0.686852 + outer loop + vertex 0.829728 1.88374 2.54137 + vertex 0.827439 1.88301 2.53935 + vertex 0.829138 1.88021 2.54205 + endloop + endfacet + facet normal -0.68366 0.270161 0.677954 + outer loop + vertex 0.828734 1.88612 2.53942 + vertex 0.827439 1.88301 2.53935 + vertex 0.829728 1.88374 2.54137 + endloop + endfacet + facet normal -0.689204 0.216895 0.691343 + outer loop + vertex 0.831438 1.87817 2.54496 + vertex 0.828615 1.87569 2.54292 + vertex 0.831058 1.87334 2.5461 + endloop + endfacet + facet normal -0.711701 0.203081 0.672488 + outer loop + vertex 0.828349 1.87098 2.54406 + vertex 0.828615 1.87569 2.54292 + vertex 0.825943 1.87321 2.54085 + endloop + endfacet + facet normal -0.728956 0.207058 0.652495 + outer loop + vertex 0.823372 1.87992 2.53588 + vertex 0.823528 1.87547 2.53746 + vertex 0.826125 1.87857 2.53938 + endloop + endfacet + facet normal -0.73985 0.202753 0.641492 + outer loop + vertex 0.823372 1.87992 2.53588 + vertex 0.82124 1.87747 2.53419 + vertex 0.823528 1.87547 2.53746 + endloop + endfacet + facet normal -0.735704 0.210946 0.643616 + outer loop + vertex 0.821119 1.87283 2.53557 + vertex 0.823528 1.87547 2.53746 + vertex 0.82124 1.87747 2.53419 + endloop + endfacet + facet normal -0.749267 0.206969 0.629097 + outer loop + vertex 0.82124 1.87747 2.53419 + vertex 0.818979 1.87517 2.53226 + vertex 0.821119 1.87283 2.53557 + endloop + endfacet + facet normal -0.745959 0.212807 0.631078 + outer loop + vertex 0.818979 1.87517 2.53226 + vertex 0.818655 1.87043 2.53347 + vertex 0.821119 1.87283 2.53557 + endloop + endfacet + facet normal -0.734253 0.207665 0.646334 + outer loop + vertex 0.823454 1.87081 2.53888 + vertex 0.823528 1.87547 2.53746 + vertex 0.821119 1.87283 2.53557 + endloop + endfacet + facet normal -0.729862 0.21625 0.648488 + outer loop + vertex 0.821096 1.86754 2.53731 + vertex 0.823454 1.87081 2.53888 + vertex 0.821119 1.87283 2.53557 + endloop + endfacet + facet normal -0.745347 0.211029 0.632396 + outer loop + vertex 0.821119 1.87283 2.53557 + vertex 0.818655 1.87043 2.53347 + vertex 0.821096 1.86754 2.53731 + endloop + endfacet + facet normal -0.71416 0.210897 0.667456 + outer loop + vertex 0.825847 1.86793 2.54237 + vertex 0.823424 1.86783 2.53981 + vertex 0.823472 1.86488 2.5408 + endloop + endfacet + facet normal -0.709035 0.2079 0.67383 + outer loop + vertex 0.825847 1.86793 2.54237 + vertex 0.828349 1.87098 2.54406 + vertex 0.825943 1.87321 2.54085 + endloop + endfacet + facet normal -0.695642 0.205987 0.688224 + outer loop + vertex 0.828615 1.87569 2.54292 + vertex 0.828349 1.87098 2.54406 + vertex 0.831058 1.87334 2.5461 + endloop + endfacet + facet normal -0.677123 0.22043 0.702079 + outer loop + vertex 0.833465 1.87104 2.54914 + vertex 0.834224 1.87624 2.54824 + vertex 0.831058 1.87334 2.5461 + endloop + endfacet + facet normal -0.680496 0.220359 0.698833 + outer loop + vertex 0.834224 1.87624 2.54824 + vertex 0.833465 1.87104 2.54914 + vertex 0.836121 1.87294 2.55113 + endloop + endfacet + facet normal -0.66702 0.235203 0.70694 + outer loop + vertex 0.836856 1.8766 2.5506 + vertex 0.834224 1.87624 2.54824 + vertex 0.836121 1.87294 2.55113 + endloop + endfacet + facet normal -0.652971 0.234284 0.720236 + outer loop + vertex 0.836121 1.87294 2.55113 + vertex 0.838641 1.87496 2.55276 + vertex 0.836856 1.8766 2.5506 + endloop + endfacet + facet normal -0.653521 0.235763 0.719254 + outer loop + vertex 0.838415 1.87072 2.55394 + vertex 0.838641 1.87496 2.55276 + vertex 0.836121 1.87294 2.55113 + endloop + endfacet + facet normal -0.63354 0.239307 0.735771 + outer loop + vertex 0.838641 1.87496 2.55276 + vertex 0.838415 1.87072 2.55394 + vertex 0.841182 1.87324 2.5555 + endloop + endfacet + facet normal -0.637162 0.246766 0.730159 + outer loop + vertex 0.841182 1.87324 2.5555 + vertex 0.838415 1.87072 2.55394 + vertex 0.84106 1.86801 2.55716 + endloop + endfacet + facet normal -0.629039 0.248606 0.73655 + outer loop + vertex 0.84106 1.86801 2.55716 + vertex 0.844244 1.87176 2.55862 + vertex 0.841182 1.87324 2.5555 + endloop + endfacet + facet normal -0.650082 0.277838 0.707248 + outer loop + vertex 0.843543 1.8684 2.55929 + vertex 0.844244 1.87176 2.55862 + vertex 0.84106 1.86801 2.55716 + endloop + endfacet + facet normal -0.654614 0.221077 0.722915 + outer loop + vertex 0.84106 1.86801 2.55716 + vertex 0.843738 1.86563 2.56032 + vertex 0.843543 1.8684 2.55929 + endloop + endfacet + facet normal -0.631284 0.229348 0.740865 + outer loop + vertex 0.845571 1.86869 2.56093 + vertex 0.843543 1.8684 2.55929 + vertex 0.843738 1.86563 2.56032 + endloop + endfacet + facet normal -0.630296 0.228537 0.741955 + outer loop + vertex 0.843738 1.86563 2.56032 + vertex 0.847209 1.8651 2.56343 + vertex 0.845571 1.86869 2.56093 + endloop + endfacet + facet normal -0.604153 0.250565 0.756449 + outer loop + vertex 0.847209 1.8651 2.56343 + vertex 0.848438 1.86986 2.56283 + vertex 0.845571 1.86869 2.56093 + endloop + endfacet + facet normal -0.607631 0.281331 0.742723 + outer loop + vertex 0.845571 1.86869 2.56093 + vertex 0.848438 1.86986 2.56283 + vertex 0.846955 1.8719 2.56085 + endloop + endfacet + facet normal -0.617613 0.285389 0.732876 + outer loop + vertex 0.846955 1.8719 2.56085 + vertex 0.844244 1.87176 2.55862 + vertex 0.845571 1.86869 2.56093 + endloop + endfacet + facet normal -0.60126 0.250125 0.758896 + outer loop + vertex 0.848438 1.86986 2.56283 + vertex 0.847209 1.8651 2.56343 + vertex 0.851026 1.86802 2.56549 + endloop + endfacet + facet normal -0.605599 0.260777 0.751828 + outer loop + vertex 0.851026 1.86802 2.56549 + vertex 0.847209 1.8651 2.56343 + vertex 0.850886 1.86252 2.56729 + endloop + endfacet + facet normal -0.593031 0.263409 0.760875 + outer loop + vertex 0.850886 1.86252 2.56729 + vertex 0.854403 1.86699 2.56848 + vertex 0.851026 1.86802 2.56549 + endloop + endfacet + facet normal -0.623957 0.297957 0.722426 + outer loop + vertex 0.853683 1.86354 2.56928 + vertex 0.854403 1.86699 2.56848 + vertex 0.850886 1.86252 2.56729 + endloop + endfacet + facet normal -0.619282 0.228786 0.751097 + outer loop + vertex 0.850886 1.86252 2.56729 + vertex 0.85395 1.86092 2.5703 + vertex 0.853683 1.86354 2.56928 + endloop + endfacet + facet normal -0.58328 0.241892 0.775418 + outer loop + vertex 0.855989 1.86439 2.57075 + vertex 0.853683 1.86354 2.56928 + vertex 0.85395 1.86092 2.5703 + endloop + endfacet + facet normal -0.59064 0.247162 0.76815 + outer loop + vertex 0.85395 1.86092 2.5703 + vertex 0.85802 1.86124 2.57332 + vertex 0.855989 1.86439 2.57075 + endloop + endfacet + facet normal -0.564296 0.273119 0.779087 + outer loop + vertex 0.85802 1.86124 2.57332 + vertex 0.859164 1.86645 2.57233 + vertex 0.855989 1.86439 2.57075 + endloop + endfacet + facet normal -0.574478 0.303286 0.760259 + outer loop + vertex 0.855989 1.86439 2.57075 + vertex 0.859164 1.86645 2.57233 + vertex 0.857378 1.86783 2.57043 + endloop + endfacet + facet normal -0.580498 0.305215 0.754895 + outer loop + vertex 0.857378 1.86783 2.57043 + vertex 0.854403 1.86699 2.56848 + vertex 0.855989 1.86439 2.57075 + endloop + endfacet + facet normal -0.593614 0.214312 0.775689 + outer loop + vertex 0.85395 1.86092 2.5703 + vertex 0.854334 1.85668 2.57176 + vertex 0.85802 1.86124 2.57332 + endloop + endfacet + facet normal -0.602704 0.225133 0.765547 + outer loop + vertex 0.854334 1.85668 2.57176 + vertex 0.857309 1.85579 2.57437 + vertex 0.85802 1.86124 2.57332 + endloop + endfacet + facet normal -0.608376 0.225017 0.761082 + outer loop + vertex 0.85802 1.86124 2.57332 + vertex 0.857309 1.85579 2.57437 + vertex 0.860371 1.85834 2.57606 + endloop + endfacet + facet normal -0.599512 0.235749 0.764858 + outer loop + vertex 0.861535 1.86193 2.57587 + vertex 0.85802 1.86124 2.57332 + vertex 0.860371 1.85834 2.57606 + endloop + endfacet + facet normal -0.595627 0.234673 0.768217 + outer loop + vertex 0.860371 1.85834 2.57606 + vertex 0.863467 1.8603 2.57786 + vertex 0.861535 1.86193 2.57587 + endloop + endfacet + facet normal -0.589797 0.216524 0.777983 + outer loop + vertex 0.86236 1.85544 2.57838 + vertex 0.863467 1.8603 2.57786 + vertex 0.860371 1.85834 2.57606 + endloop + endfacet + facet normal -0.594383 0.211652 0.77583 + outer loop + vertex 0.859406 1.85469 2.57632 + vertex 0.86236 1.85544 2.57838 + vertex 0.860371 1.85834 2.57606 + endloop + endfacet + facet normal -0.5937 0.197043 0.780189 + outer loop + vertex 0.859406 1.85469 2.57632 + vertex 0.859529 1.85135 2.57726 + vertex 0.86236 1.85544 2.57838 + endloop + endfacet + facet normal -0.594772 0.198082 0.779108 + outer loop + vertex 0.859529 1.85135 2.57726 + vertex 0.862203 1.85071 2.57946 + vertex 0.86236 1.85544 2.57838 + endloop + endfacet + facet normal -0.592096 0.198438 0.781053 + outer loop + vertex 0.86236 1.85544 2.57838 + vertex 0.862203 1.85071 2.57946 + vertex 0.865292 1.85364 2.58106 + endloop + endfacet + facet normal -0.587487 0.20759 0.782154 + outer loop + vertex 0.866043 1.85851 2.58033 + vertex 0.86236 1.85544 2.57838 + vertex 0.865292 1.85364 2.58106 + endloop + endfacet + facet normal -0.584989 0.207489 0.784051 + outer loop + vertex 0.865292 1.85364 2.58106 + vertex 0.869188 1.85656 2.58319 + vertex 0.866043 1.85851 2.58033 + endloop + endfacet + facet normal -0.576278 0.224193 0.785902 + outer loop + vertex 0.869188 1.85656 2.58319 + vertex 0.869409 1.86175 2.58187 + vertex 0.866043 1.85851 2.58033 + endloop + endfacet + facet normal -0.586959 0.241559 0.772741 + outer loop + vertex 0.866043 1.85851 2.58033 + vertex 0.869409 1.86175 2.58187 + vertex 0.86634 1.86299 2.57915 + endloop + endfacet + facet normal -0.577333 0.242719 0.779599 + outer loop + vertex 0.86634 1.86299 2.57915 + vertex 0.863467 1.8603 2.57786 + vertex 0.866043 1.85851 2.58033 + endloop + endfacet + facet normal -0.575136 0.269798 0.772288 + outer loop + vertex 0.869106 1.86584 2.58022 + vertex 0.86634 1.86299 2.57915 + vertex 0.869409 1.86175 2.58187 + endloop + endfacet + facet normal -0.577927 0.268877 0.770523 + outer loop + vertex 0.869106 1.86584 2.58022 + vertex 0.869409 1.86175 2.58187 + vertex 0.87324 1.8661 2.58323 + endloop + endfacet + facet normal -0.570331 0.323026 0.755233 + outer loop + vertex 0.869106 1.86584 2.58022 + vertex 0.87324 1.8661 2.58323 + vertex 0.870867 1.86903 2.58019 + endloop + endfacet + facet normal -0.567061 0.321255 0.758444 + outer loop + vertex 0.870867 1.86903 2.58019 + vertex 0.86866 1.86818 2.5789 + vertex 0.869106 1.86584 2.58022 + endloop + endfacet + facet normal -0.569157 0.257984 0.780708 + outer loop + vertex 0.869409 1.86175 2.58187 + vertex 0.872436 1.86076 2.58441 + vertex 0.87324 1.8661 2.58323 + endloop + endfacet + facet normal -0.573714 0.257936 0.777381 + outer loop + vertex 0.87324 1.8661 2.58323 + vertex 0.872436 1.86076 2.58441 + vertex 0.875839 1.86352 2.586 + endloop + endfacet + facet normal -0.559561 0.229421 0.796403 + outer loop + vertex 0.875839 1.86352 2.586 + vertex 0.872436 1.86076 2.58441 + vertex 0.87469 1.85975 2.58628 + endloop + endfacet + facet normal -0.534264 0.223103 0.815345 + outer loop + vertex 0.87469 1.85975 2.58628 + vertex 0.878364 1.86107 2.58833 + vertex 0.875839 1.86352 2.586 + endloop + endfacet + facet normal -0.538675 0.217278 0.814015 + outer loop + vertex 0.878364 1.86107 2.58833 + vertex 0.879363 1.86647 2.58755 + vertex 0.875839 1.86352 2.586 + endloop + endfacet + facet normal -0.551287 0.240161 0.799003 + outer loop + vertex 0.875839 1.86352 2.586 + vertex 0.879363 1.86647 2.58755 + vertex 0.87702 1.86721 2.58571 + endloop + endfacet + facet normal -0.581272 0.247845 0.775046 + outer loop + vertex 0.87702 1.86721 2.58571 + vertex 0.87324 1.8661 2.58323 + vertex 0.875839 1.86352 2.586 + endloop + endfacet + facet normal -0.53143 0.205079 0.821903 + outer loop + vertex 0.87469 1.85975 2.58628 + vertex 0.874707 1.85639 2.58713 + vertex 0.878364 1.86107 2.58833 + endloop + endfacet + facet normal -0.549584 0.202134 0.810617 + outer loop + vertex 0.87469 1.85975 2.58628 + vertex 0.872415 1.85731 2.58535 + vertex 0.874707 1.85639 2.58713 + endloop + endfacet + facet normal -0.55397 0.190838 0.810369 + outer loop + vertex 0.871361 1.85342 2.58554 + vertex 0.874707 1.85639 2.58713 + vertex 0.872415 1.85731 2.58535 + endloop + endfacet + facet normal -0.575825 0.195919 0.793752 + outer loop + vertex 0.872415 1.85731 2.58535 + vertex 0.869188 1.85656 2.58319 + vertex 0.871361 1.85342 2.58554 + endloop + endfacet + facet normal -0.576574 0.195136 0.7934 + outer loop + vertex 0.869188 1.85656 2.58319 + vertex 0.867473 1.85059 2.58341 + vertex 0.871361 1.85342 2.58554 + endloop + endfacet + facet normal -0.573896 0.188854 0.796855 + outer loop + vertex 0.871361 1.85342 2.58554 + vertex 0.867473 1.85059 2.58341 + vertex 0.870368 1.84853 2.58599 + endloop + endfacet + facet normal -0.559108 0.186844 0.807767 + outer loop + vertex 0.870368 1.84853 2.58599 + vertex 0.87431 1.8514 2.58805 + vertex 0.871361 1.85342 2.58554 + endloop + endfacet + facet normal -0.560037 0.188926 0.806639 + outer loop + vertex 0.872559 1.84547 2.58822 + vertex 0.87431 1.8514 2.58805 + vertex 0.870368 1.84853 2.58599 + endloop + endfacet + facet normal -0.563317 0.185484 0.805152 + outer loop + vertex 0.869418 1.84469 2.58621 + vertex 0.872559 1.84547 2.58822 + vertex 0.870368 1.84853 2.58599 + endloop + endfacet + facet normal -0.573743 0.187614 0.797258 + outer loop + vertex 0.870368 1.84853 2.58599 + vertex 0.867241 1.84571 2.5844 + vertex 0.869418 1.84469 2.58621 + endloop + endfacet + facet normal -0.573928 0.18717 0.797229 + outer loop + vertex 0.867391 1.84239 2.58529 + vertex 0.869418 1.84469 2.58621 + vertex 0.867241 1.84571 2.5844 + endloop + endfacet + facet normal -0.578581 0.186126 0.794104 + outer loop + vertex 0.867391 1.84239 2.58529 + vertex 0.867241 1.84571 2.5844 + vertex 0.86426 1.84153 2.58321 + endloop + endfacet + facet normal -0.578724 0.187963 0.793567 + outer loop + vertex 0.867391 1.84239 2.58529 + vertex 0.86426 1.84153 2.58321 + vertex 0.866427 1.83851 2.5855 + endloop + endfacet + facet normal -0.571117 0.186395 0.799427 + outer loop + vertex 0.866427 1.83851 2.5855 + vertex 0.869574 1.84135 2.58709 + vertex 0.867391 1.84239 2.58529 + endloop + endfacet + facet normal -0.570173 0.184765 0.800478 + outer loop + vertex 0.86935 1.83649 2.58805 + vertex 0.869574 1.84135 2.58709 + vertex 0.866427 1.83851 2.5855 + endloop + endfacet + facet normal -0.568375 0.188019 0.800999 + outer loop + vertex 0.865445 1.8336 2.58596 + vertex 0.86935 1.83649 2.58805 + vertex 0.866427 1.83851 2.5855 + endloop + endfacet + facet normal -0.57681 0.189119 0.794685 + outer loop + vertex 0.866427 1.83851 2.5855 + vertex 0.862518 1.83553 2.58338 + vertex 0.865445 1.8336 2.58596 + endloop + endfacet + facet normal -0.576874 0.188999 0.794667 + outer loop + vertex 0.862518 1.83553 2.58338 + vertex 0.862274 1.83063 2.58436 + vertex 0.865445 1.8336 2.58596 + endloop + endfacet + facet normal -0.576664 0.188648 0.794903 + outer loop + vertex 0.865445 1.8336 2.58596 + vertex 0.862274 1.83063 2.58436 + vertex 0.86447 1.82973 2.58617 + endloop + endfacet + facet normal -0.565644 0.186332 0.803323 + outer loop + vertex 0.86447 1.82973 2.58617 + vertex 0.867652 1.83057 2.58822 + vertex 0.865445 1.8336 2.58596 + endloop + endfacet + facet normal -0.565142 0.180147 0.805085 + outer loop + vertex 0.86447 1.82973 2.58617 + vertex 0.864594 1.82644 2.58699 + vertex 0.867652 1.83057 2.58822 + endloop + endfacet + facet normal -0.564592 0.179588 0.805596 + outer loop + vertex 0.864594 1.82644 2.58699 + vertex 0.867381 1.82544 2.58917 + vertex 0.867652 1.83057 2.58822 + endloop + endfacet + facet normal -0.557378 0.180117 0.810486 + outer loop + vertex 0.867652 1.83057 2.58822 + vertex 0.867381 1.82544 2.58917 + vertex 0.870821 1.82864 2.59082 + endloop + endfacet + facet normal -0.557665 0.17955 0.810414 + outer loop + vertex 0.871562 1.8335 2.59026 + vertex 0.867652 1.83057 2.58822 + vertex 0.870821 1.82864 2.59082 + endloop + endfacet + facet normal -0.547207 0.178804 0.817676 + outer loop + vertex 0.870821 1.82864 2.59082 + vertex 0.874328 1.83184 2.59247 + vertex 0.871562 1.8335 2.59026 + endloop + endfacet + facet normal -0.546947 0.179318 0.817737 + outer loop + vertex 0.874328 1.83184 2.59247 + vertex 0.874849 1.83637 2.59183 + vertex 0.871562 1.8335 2.59026 + endloop + endfacet + facet normal -0.532199 0.179013 0.827477 + outer loop + vertex 0.874328 1.83184 2.59247 + vertex 0.877725 1.83532 2.5939 + vertex 0.874849 1.83637 2.59183 + endloop + endfacet + facet normal -0.530628 0.183403 0.827525 + outer loop + vertex 0.874849 1.83637 2.59183 + vertex 0.877725 1.83532 2.5939 + vertex 0.878476 1.841 2.59313 + endloop + endfacet + facet normal -0.530273 0.18304 0.827833 + outer loop + vertex 0.874723 1.8397 2.59101 + vertex 0.874849 1.83637 2.59183 + vertex 0.878476 1.841 2.59313 + endloop + endfacet + facet normal -0.530452 0.184127 0.827477 + outer loop + vertex 0.874723 1.8397 2.59101 + vertex 0.878476 1.841 2.59313 + vertex 0.875616 1.84361 2.59071 + endloop + endfacet + facet normal -0.549346 0.187434 0.814302 + outer loop + vertex 0.875616 1.84361 2.59071 + vertex 0.872362 1.8406 2.58921 + vertex 0.874723 1.8397 2.59101 + endloop + endfacet + facet normal -0.550041 0.185547 0.814265 + outer loop + vertex 0.872535 1.83728 2.59008 + vertex 0.874723 1.8397 2.59101 + vertex 0.872362 1.8406 2.58921 + endloop + endfacet + facet normal -0.560506 0.183254 0.807621 + outer loop + vertex 0.872535 1.83728 2.59008 + vertex 0.872362 1.8406 2.58921 + vertex 0.86935 1.83649 2.58805 + endloop + endfacet + facet normal -0.56038 0.18154 0.808095 + outer loop + vertex 0.872535 1.83728 2.59008 + vertex 0.86935 1.83649 2.58805 + vertex 0.871562 1.8335 2.59026 + endloop + endfacet + facet normal -0.549055 0.186966 0.814606 + outer loop + vertex 0.872559 1.84547 2.58822 + vertex 0.872362 1.8406 2.58921 + vertex 0.875616 1.84361 2.59071 + endloop + endfacet + facet normal -0.548777 0.187504 0.814669 + outer loop + vertex 0.876505 1.84847 2.59019 + vertex 0.872559 1.84547 2.58822 + vertex 0.875616 1.84361 2.59071 + endloop + endfacet + facet normal -0.527817 0.185192 0.828923 + outer loop + vertex 0.875616 1.84361 2.59071 + vertex 0.879348 1.84687 2.59236 + vertex 0.876505 1.84847 2.59019 + endloop + endfacet + facet normal -0.524963 0.190951 0.829429 + outer loop + vertex 0.879348 1.84687 2.59236 + vertex 0.87994 1.85158 2.59165 + vertex 0.876505 1.84847 2.59019 + endloop + endfacet + facet normal -0.521036 0.184805 0.833288 + outer loop + vertex 0.876505 1.84847 2.59019 + vertex 0.87994 1.85158 2.59165 + vertex 0.877553 1.85232 2.58999 + endloop + endfacet + facet normal -0.543571 0.190121 0.817548 + outer loop + vertex 0.877553 1.85232 2.58999 + vertex 0.87431 1.8514 2.58805 + vertex 0.876505 1.84847 2.59019 + endloop + endfacet + facet normal -0.544494 0.199447 0.814707 + outer loop + vertex 0.877553 1.85232 2.58999 + vertex 0.877532 1.85571 2.58915 + vertex 0.87431 1.8514 2.58805 + endloop + endfacet + facet normal -0.539019 0.194091 0.819626 + outer loop + vertex 0.87431 1.8514 2.58805 + vertex 0.877532 1.85571 2.58915 + vertex 0.874707 1.85639 2.58713 + endloop + endfacet + facet normal -0.534911 0.208597 0.818754 + outer loop + vertex 0.874707 1.85639 2.58713 + vertex 0.877532 1.85571 2.58915 + vertex 0.878364 1.86107 2.58833 + endloop + endfacet + facet normal -0.524358 0.202639 0.827035 + outer loop + vertex 0.877553 1.85232 2.58999 + vertex 0.879773 1.85483 2.59079 + vertex 0.877532 1.85571 2.58915 + endloop + endfacet + facet normal -0.521635 0.209577 0.827028 + outer loop + vertex 0.880852 1.85859 2.59051 + vertex 0.877532 1.85571 2.58915 + vertex 0.879773 1.85483 2.59079 + endloop + endfacet + facet normal -0.52056 0.207813 0.828149 + outer loop + vertex 0.878364 1.86107 2.58833 + vertex 0.877532 1.85571 2.58915 + vertex 0.880852 1.85859 2.59051 + endloop + endfacet + facet normal -0.51902 0.209774 0.828621 + outer loop + vertex 0.882053 1.86242 2.5903 + vertex 0.878364 1.86107 2.58833 + vertex 0.880852 1.85859 2.59051 + endloop + endfacet + facet normal -0.50555 0.206062 0.837829 + outer loop + vertex 0.880852 1.85859 2.59051 + vertex 0.884399 1.86147 2.59195 + vertex 0.882053 1.86242 2.5903 + endloop + endfacet + facet normal -0.506373 0.204027 0.83783 + outer loop + vertex 0.884555 1.86499 2.59118 + vertex 0.882053 1.86242 2.5903 + vertex 0.884399 1.86147 2.59195 + endloop + endfacet + facet normal -0.502584 0.204335 0.840034 + outer loop + vertex 0.884555 1.86499 2.59118 + vertex 0.884399 1.86147 2.59195 + vertex 0.888382 1.86617 2.59319 + endloop + endfacet + facet normal -0.5025 0.203728 0.840231 + outer loop + vertex 0.884555 1.86499 2.59118 + vertex 0.888382 1.86617 2.59319 + vertex 0.885772 1.86883 2.59098 + endloop + endfacet + facet normal -0.513236 0.206746 0.832973 + outer loop + vertex 0.885772 1.86883 2.59098 + vertex 0.882213 1.86588 2.58952 + vertex 0.884555 1.86499 2.59118 + endloop + endfacet + facet normal -0.525954 0.22898 0.81911 + outer loop + vertex 0.883164 1.87123 2.58863 + vertex 0.882213 1.86588 2.58952 + vertex 0.885772 1.86883 2.59098 + endloop + endfacet + facet normal -0.539715 0.210177 0.815189 + outer loop + vertex 0.886932 1.87261 2.59077 + vertex 0.883164 1.87123 2.58863 + vertex 0.885772 1.86883 2.59098 + endloop + endfacet + facet normal -0.513535 0.20316 0.833672 + outer loop + vertex 0.885772 1.86883 2.59098 + vertex 0.8893 1.8717 2.59245 + vertex 0.886932 1.87261 2.59077 + endloop + endfacet + facet normal -0.514605 0.200394 0.833681 + outer loop + vertex 0.889349 1.8751 2.59167 + vertex 0.886932 1.87261 2.59077 + vertex 0.8893 1.8717 2.59245 + endloop + endfacet + facet normal -0.502535 0.201839 0.840666 + outer loop + vertex 0.889349 1.8751 2.59167 + vertex 0.8893 1.8717 2.59245 + vertex 0.893122 1.87635 2.59362 + endloop + endfacet + facet normal -0.506406 0.227502 0.831742 + outer loop + vertex 0.889349 1.8751 2.59167 + vertex 0.893122 1.87635 2.59362 + vertex 0.890348 1.87881 2.59126 + endloop + endfacet + facet normal -0.54069 0.234143 0.80798 + outer loop + vertex 0.890348 1.87881 2.59126 + vertex 0.886887 1.87583 2.58981 + vertex 0.889349 1.8751 2.59167 + endloop + endfacet + facet normal -0.568272 0.283404 0.772495 + outer loop + vertex 0.887255 1.88043 2.58839 + vertex 0.886887 1.87583 2.58981 + vertex 0.890348 1.87881 2.59126 + endloop + endfacet + facet normal -0.579173 0.261805 0.772021 + outer loop + vertex 0.891074 1.88332 2.59028 + vertex 0.887255 1.88043 2.58839 + vertex 0.890348 1.87881 2.59126 + endloop + endfacet + facet normal -0.546767 0.261668 0.795346 + outer loop + vertex 0.890348 1.87881 2.59126 + vertex 0.894095 1.88197 2.5928 + vertex 0.891074 1.88332 2.59028 + endloop + endfacet + facet normal -0.553526 0.246726 0.795447 + outer loop + vertex 0.894095 1.88197 2.5928 + vertex 0.894548 1.88667 2.59165 + vertex 0.891074 1.88332 2.59028 + endloop + endfacet + facet normal -0.518114 0.211424 0.828769 + outer loop + vertex 0.893122 1.87635 2.59362 + vertex 0.894095 1.88197 2.5928 + vertex 0.890348 1.87881 2.59126 + endloop + endfacet + facet normal -0.496588 0.209681 0.842279 + outer loop + vertex 0.893122 1.87635 2.59362 + vertex 0.897055 1.88098 2.59479 + vertex 0.894095 1.88197 2.5928 + endloop + endfacet + facet normal -0.494333 0.215939 0.842025 + outer loop + vertex 0.897055 1.88098 2.59479 + vertex 0.898299 1.88609 2.59421 + vertex 0.894095 1.88197 2.5928 + endloop + endfacet + facet normal -0.518544 0.248839 0.818041 + outer loop + vertex 0.894095 1.88197 2.5928 + vertex 0.898299 1.88609 2.59421 + vertex 0.894548 1.88667 2.59165 + endloop + endfacet + facet normal -0.521636 0.236369 0.819772 + outer loop + vertex 0.894548 1.88667 2.59165 + vertex 0.898299 1.88609 2.59421 + vertex 0.898153 1.89128 2.59262 + endloop + endfacet + facet normal -0.497225 0.241235 0.83341 + outer loop + vertex 0.898299 1.88609 2.59421 + vertex 0.901842 1.89077 2.59497 + vertex 0.898153 1.89128 2.59262 + endloop + endfacet + facet normal -0.497677 0.239315 0.833694 + outer loop + vertex 0.901842 1.89077 2.59497 + vertex 0.903057 1.89589 2.59422 + vertex 0.898153 1.89128 2.59262 + endloop + endfacet + facet normal -0.509485 0.256151 0.821469 + outer loop + vertex 0.898153 1.89128 2.59262 + vertex 0.903057 1.89589 2.59422 + vertex 0.899278 1.89645 2.5917 + endloop + endfacet + facet normal -0.510722 0.251219 0.822224 + outer loop + vertex 0.899278 1.89645 2.5917 + vertex 0.903057 1.89589 2.59422 + vertex 0.903018 1.90118 2.59258 + endloop + endfacet + facet normal -0.489533 0.254985 0.83387 + outer loop + vertex 0.903057 1.89589 2.59422 + vertex 0.906799 1.90073 2.59494 + vertex 0.903018 1.90118 2.59258 + endloop + endfacet + facet normal -0.490824 0.249259 0.834843 + outer loop + vertex 0.906799 1.90073 2.59494 + vertex 0.90802 1.90585 2.59413 + vertex 0.903018 1.90118 2.59258 + endloop + endfacet + facet normal -0.499826 0.261978 0.825555 + outer loop + vertex 0.903018 1.90118 2.59258 + vertex 0.90802 1.90585 2.59413 + vertex 0.904105 1.90645 2.59157 + endloop + endfacet + facet normal -0.503275 0.248387 0.827658 + outer loop + vertex 0.904105 1.90645 2.59157 + vertex 0.90802 1.90585 2.59413 + vertex 0.908047 1.91116 2.59255 + endloop + endfacet + facet normal -0.524982 0.270881 0.806856 + outer loop + vertex 0.903898 1.91049 2.59008 + vertex 0.904105 1.90645 2.59157 + vertex 0.908047 1.91116 2.59255 + endloop + endfacet + facet normal -0.525673 0.227984 0.819567 + outer loop + vertex 0.903898 1.91049 2.59008 + vertex 0.908047 1.91116 2.59255 + vertex 0.905996 1.91373 2.59052 + endloop + endfacet + facet normal -0.558829 0.253597 0.789556 + outer loop + vertex 0.905996 1.91373 2.59052 + vertex 0.903679 1.913 2.58912 + vertex 0.903898 1.91049 2.59008 + endloop + endfacet + facet normal -0.559666 0.26377 0.78562 + outer loop + vertex 0.90429 1.91634 2.58843 + vertex 0.903679 1.913 2.58912 + vertex 0.905996 1.91373 2.59052 + endloop + endfacet + facet normal -0.568285 0.255386 0.782196 + outer loop + vertex 0.907223 1.91696 2.59036 + vertex 0.90429 1.91634 2.58843 + vertex 0.905996 1.91373 2.59052 + endloop + endfacet + facet normal -0.503685 0.233314 0.831785 + outer loop + vertex 0.905996 1.91373 2.59052 + vertex 0.909505 1.91625 2.59194 + vertex 0.907223 1.91696 2.59036 + endloop + endfacet + facet normal -0.503743 0.233152 0.831795 + outer loop + vertex 0.909556 1.91945 2.59107 + vertex 0.907223 1.91696 2.59036 + vertex 0.909505 1.91625 2.59194 + endloop + endfacet + facet normal -0.460966 0.238661 0.854723 + outer loop + vertex 0.909556 1.91945 2.59107 + vertex 0.909505 1.91625 2.59194 + vertex 0.913345 1.9213 2.5926 + endloop + endfacet + facet normal -0.459078 0.232612 0.857403 + outer loop + vertex 0.909556 1.91945 2.59107 + vertex 0.913345 1.9213 2.5926 + vertex 0.910773 1.92327 2.59069 + endloop + endfacet + facet normal -0.520177 0.247977 0.817266 + outer loop + vertex 0.910773 1.92327 2.59069 + vertex 0.907329 1.92029 2.5894 + vertex 0.909556 1.91945 2.59107 + endloop + endfacet + facet normal -0.521797 0.250637 0.815419 + outer loop + vertex 0.908181 1.92568 2.58829 + vertex 0.907329 1.92029 2.5894 + vertex 0.910773 1.92327 2.59069 + endloop + endfacet + facet normal -0.527865 0.242628 0.813935 + outer loop + vertex 0.911995 1.92707 2.59035 + vertex 0.908181 1.92568 2.58829 + vertex 0.910773 1.92327 2.59069 + endloop + endfacet + facet normal -0.455634 0.223628 0.861619 + outer loop + vertex 0.910773 1.92327 2.59069 + vertex 0.914541 1.92653 2.59183 + vertex 0.911995 1.92707 2.59035 + endloop + endfacet + facet normal -0.45486 0.226425 0.861298 + outer loop + vertex 0.914572 1.9298 2.59099 + vertex 0.911995 1.92707 2.59035 + vertex 0.914541 1.92653 2.59183 + endloop + endfacet + facet normal -0.478462 0.253557 0.840704 + outer loop + vertex 0.911995 1.92707 2.59035 + vertex 0.914572 1.9298 2.59099 + vertex 0.912055 1.93048 2.58935 + endloop + endfacet + facet normal -0.5284 0.246216 0.812509 + outer loop + vertex 0.911995 1.92707 2.59035 + vertex 0.912055 1.93048 2.58935 + vertex 0.908181 1.92568 2.58829 + endloop + endfacet + facet normal -0.541658 0.25984 0.799431 + outer loop + vertex 0.908181 1.92568 2.58829 + vertex 0.912055 1.93048 2.58935 + vertex 0.908902 1.93127 2.58696 + endloop + endfacet + facet normal -0.540328 0.263862 0.799013 + outer loop + vertex 0.908902 1.93127 2.58696 + vertex 0.912055 1.93048 2.58935 + vertex 0.913127 1.93613 2.58821 + endloop + endfacet + facet normal -0.460405 0.230692 0.85721 + outer loop + vertex 0.913345 1.9213 2.5926 + vertex 0.914541 1.92653 2.59183 + vertex 0.910773 1.92327 2.59069 + endloop + endfacet + facet normal -0.456766 0.235045 0.857974 + outer loop + vertex 0.909505 1.91625 2.59194 + vertex 0.913319 1.91606 2.59402 + vertex 0.913345 1.9213 2.5926 + endloop + endfacet + facet normal -0.456907 0.234125 0.85815 + outer loop + vertex 0.908047 1.91116 2.59255 + vertex 0.913319 1.91606 2.59402 + vertex 0.909505 1.91625 2.59194 + endloop + endfacet + facet normal -0.46992 0.251742 0.84605 + outer loop + vertex 0.911853 1.91076 2.59478 + vertex 0.913319 1.91606 2.59402 + vertex 0.908047 1.91116 2.59255 + endloop + endfacet + facet normal -0.518755 0.251443 0.817111 + outer loop + vertex 0.907223 1.91696 2.59036 + vertex 0.909556 1.91945 2.59107 + vertex 0.907329 1.92029 2.5894 + endloop + endfacet + facet normal -0.568276 0.244023 0.785821 + outer loop + vertex 0.907223 1.91696 2.59036 + vertex 0.907329 1.92029 2.5894 + vertex 0.90429 1.91634 2.58843 + endloop + endfacet + facet normal -0.509395 0.245155 0.824873 + outer loop + vertex 0.908047 1.91116 2.59255 + vertex 0.909505 1.91625 2.59194 + vertex 0.905996 1.91373 2.59052 + endloop + endfacet + facet normal -0.469531 0.253582 0.845717 + outer loop + vertex 0.90802 1.90585 2.59413 + vertex 0.911853 1.91076 2.59478 + vertex 0.908047 1.91116 2.59255 + endloop + endfacet + facet normal -0.454511 0.232875 0.859761 + outer loop + vertex 0.903057 1.89589 2.59422 + vertex 0.901842 1.89077 2.59497 + vertex 0.905541 1.89385 2.59609 + endloop + endfacet + facet normal -0.460656 0.224449 0.858731 + outer loop + vertex 0.906801 1.89755 2.5958 + vertex 0.903057 1.89589 2.59422 + vertex 0.905541 1.89385 2.59609 + endloop + endfacet + facet normal -0.41132 0.209897 0.886995 + outer loop + vertex 0.905541 1.89385 2.59609 + vertex 0.909369 1.89703 2.59711 + vertex 0.906801 1.89755 2.5958 + endloop + endfacet + facet normal -0.46234 0.230648 0.856179 + outer loop + vertex 0.906801 1.89755 2.5958 + vertex 0.906799 1.90073 2.59494 + vertex 0.903057 1.89589 2.59422 + endloop + endfacet + facet normal -0.435475 0.234175 0.869209 + outer loop + vertex 0.906801 1.89755 2.5958 + vertex 0.909342 1.90028 2.59633 + vertex 0.906799 1.90073 2.59494 + endloop + endfacet + facet normal -0.411693 0.208473 0.887157 + outer loop + vertex 0.909342 1.90028 2.59633 + vertex 0.906801 1.89755 2.5958 + vertex 0.909369 1.89703 2.59711 + endloop + endfacet + facet normal -0.471353 0.218195 0.854527 + outer loop + vertex 0.901837 1.88754 2.59579 + vertex 0.901842 1.89077 2.59497 + vertex 0.898299 1.88609 2.59421 + endloop + endfacet + facet normal -0.468813 0.207642 0.858545 + outer loop + vertex 0.901837 1.88754 2.59579 + vertex 0.898299 1.88609 2.59421 + vertex 0.900627 1.88385 2.59602 + endloop + endfacet + facet normal -0.429828 0.1963 0.881314 + outer loop + vertex 0.900627 1.88385 2.59602 + vertex 0.904296 1.88684 2.59714 + vertex 0.901837 1.88754 2.59579 + endloop + endfacet + facet normal -0.428155 0.201476 0.88096 + outer loop + vertex 0.904281 1.89015 2.59638 + vertex 0.901837 1.88754 2.59579 + vertex 0.904296 1.88684 2.59714 + endloop + endfacet + facet normal -0.408702 0.203574 0.889674 + outer loop + vertex 0.904281 1.89015 2.59638 + vertex 0.904296 1.88684 2.59714 + vertex 0.908089 1.89169 2.59778 + endloop + endfacet + facet normal -0.410364 0.209708 0.887482 + outer loop + vertex 0.904281 1.89015 2.59638 + vertex 0.908089 1.89169 2.59778 + vertex 0.905541 1.89385 2.59609 + endloop + endfacet + facet normal -0.44638 0.220392 0.867279 + outer loop + vertex 0.905541 1.89385 2.59609 + vertex 0.901842 1.89077 2.59497 + vertex 0.904281 1.89015 2.59638 + endloop + endfacet + facet normal -0.410802 0.209139 0.887413 + outer loop + vertex 0.908089 1.89169 2.59778 + vertex 0.909369 1.89703 2.59711 + vertex 0.905541 1.89385 2.59609 + endloop + endfacet + facet normal -0.388551 0.205169 0.898295 + outer loop + vertex 0.908089 1.89169 2.59778 + vertex 0.913374 1.89654 2.59895 + vertex 0.909369 1.89703 2.59711 + endloop + endfacet + facet normal -0.387544 0.210445 0.897509 + outer loop + vertex 0.909369 1.89703 2.59711 + vertex 0.913374 1.89654 2.59895 + vertex 0.913269 1.90202 2.59762 + endloop + endfacet + facet normal -0.388243 0.211037 0.897068 + outer loop + vertex 0.909342 1.90028 2.59633 + vertex 0.909369 1.89703 2.59711 + vertex 0.913269 1.90202 2.59762 + endloop + endfacet + facet normal -0.390626 0.218502 0.894242 + outer loop + vertex 0.909342 1.90028 2.59633 + vertex 0.913269 1.90202 2.59762 + vertex 0.910588 1.90394 2.59598 + endloop + endfacet + facet normal -0.436123 0.231616 0.869569 + outer loop + vertex 0.910588 1.90394 2.59598 + vertex 0.906799 1.90073 2.59494 + vertex 0.909342 1.90028 2.59633 + endloop + endfacet + facet normal -0.393333 0.214532 0.894016 + outer loop + vertex 0.913269 1.90202 2.59762 + vertex 0.914384 1.90719 2.59688 + vertex 0.910588 1.90394 2.59598 + endloop + endfacet + facet normal -0.379091 0.212416 0.900649 + outer loop + vertex 0.913269 1.90202 2.59762 + vertex 0.918072 1.90677 2.59853 + vertex 0.914384 1.90719 2.59688 + endloop + endfacet + facet normal -0.377656 0.220147 0.899395 + outer loop + vertex 0.914384 1.90719 2.59688 + vertex 0.918072 1.90677 2.59853 + vertex 0.918269 1.91194 2.59734 + endloop + endfacet + facet normal -0.376546 0.219171 0.900099 + outer loop + vertex 0.914385 1.91034 2.59611 + vertex 0.914384 1.90719 2.59688 + vertex 0.918269 1.91194 2.59734 + endloop + endfacet + facet normal -0.379804 0.230245 0.895955 + outer loop + vertex 0.914385 1.91034 2.59611 + vertex 0.918269 1.91194 2.59734 + vertex 0.915735 1.91403 2.59573 + endloop + endfacet + facet normal -0.417709 0.242014 0.875756 + outer loop + vertex 0.915735 1.91403 2.59573 + vertex 0.911853 1.91076 2.59478 + vertex 0.914385 1.91034 2.59611 + endloop + endfacet + facet normal -0.417381 0.241543 0.876042 + outer loop + vertex 0.913319 1.91606 2.59402 + vertex 0.911853 1.91076 2.59478 + vertex 0.915735 1.91403 2.59573 + endloop + endfacet + facet normal -0.418515 0.240077 0.875904 + outer loop + vertex 0.917221 1.91785 2.59539 + vertex 0.913319 1.91606 2.59402 + vertex 0.915735 1.91403 2.59573 + endloop + endfacet + facet normal -0.3824 0.22774 0.895491 + outer loop + vertex 0.915735 1.91403 2.59573 + vertex 0.91953 1.91707 2.59658 + vertex 0.917221 1.91785 2.59539 + endloop + endfacet + facet normal -0.38164 0.229713 0.895312 + outer loop + vertex 0.919823 1.92027 2.59588 + vertex 0.917221 1.91785 2.59539 + vertex 0.91953 1.91707 2.59658 + endloop + endfacet + facet normal -0.390304 0.240352 0.888759 + outer loop + vertex 0.917221 1.91785 2.59539 + vertex 0.919823 1.92027 2.59588 + vertex 0.917823 1.92162 2.59464 + endloop + endfacet + facet normal -0.419178 0.242219 0.874997 + outer loop + vertex 0.917221 1.91785 2.59539 + vertex 0.917823 1.92162 2.59464 + vertex 0.913319 1.91606 2.59402 + endloop + endfacet + facet normal -0.382099 0.227295 0.895733 + outer loop + vertex 0.918269 1.91194 2.59734 + vertex 0.91953 1.91707 2.59658 + vertex 0.915735 1.91403 2.59573 + endloop + endfacet + facet normal -0.392845 0.229173 0.890591 + outer loop + vertex 0.918269 1.91194 2.59734 + vertex 0.922922 1.91626 2.59828 + vertex 0.91953 1.91707 2.59658 + endloop + endfacet + facet normal -0.392087 0.231682 0.890276 + outer loop + vertex 0.91953 1.91707 2.59658 + vertex 0.922922 1.91626 2.59828 + vertex 0.923244 1.92129 2.59712 + endloop + endfacet + facet normal -0.39003 0.229692 0.891694 + outer loop + vertex 0.919823 1.92027 2.59588 + vertex 0.91953 1.91707 2.59658 + vertex 0.923244 1.92129 2.59712 + endloop + endfacet + facet normal -0.392791 0.245559 0.886237 + outer loop + vertex 0.919823 1.92027 2.59588 + vertex 0.923244 1.92129 2.59712 + vertex 0.921319 1.92302 2.59578 + endloop + endfacet + facet normal -0.388386 0.243254 0.88881 + outer loop + vertex 0.921319 1.92302 2.59578 + vertex 0.917823 1.92162 2.59464 + vertex 0.919823 1.92027 2.59588 + endloop + endfacet + facet normal -0.387649 0.240566 0.889863 + outer loop + vertex 0.921319 1.92302 2.59578 + vertex 0.921664 1.92614 2.59509 + vertex 0.917823 1.92162 2.59464 + endloop + endfacet + facet normal -0.383715 0.236964 0.892531 + outer loop + vertex 0.917823 1.92162 2.59464 + vertex 0.921664 1.92614 2.59509 + vertex 0.918157 1.92641 2.59351 + endloop + endfacet + facet normal -0.383076 0.240852 0.891764 + outer loop + vertex 0.921664 1.92614 2.59509 + vertex 0.923054 1.93115 2.59434 + vertex 0.918157 1.92641 2.59351 + endloop + endfacet + facet normal -0.391671 0.242602 0.887546 + outer loop + vertex 0.923054 1.93115 2.59434 + vertex 0.921664 1.92614 2.59509 + vertex 0.925512 1.9289 2.59604 + endloop + endfacet + facet normal -0.391591 0.242466 0.887618 + outer loop + vertex 0.925512 1.9289 2.59604 + vertex 0.921664 1.92614 2.59509 + vertex 0.923977 1.92522 2.59636 + endloop + endfacet + facet normal -0.446687 0.262609 0.855282 + outer loop + vertex 0.923977 1.92522 2.59636 + vertex 0.927994 1.92612 2.59819 + vertex 0.925512 1.9289 2.59604 + endloop + endfacet + facet normal -0.44687 0.262417 0.855245 + outer loop + vertex 0.927994 1.92612 2.59819 + vertex 0.929214 1.93162 2.59714 + vertex 0.925512 1.9289 2.59604 + endloop + endfacet + facet normal -0.445656 0.248127 0.86013 + outer loop + vertex 0.923977 1.92522 2.59636 + vertex 0.923244 1.92129 2.59712 + vertex 0.927994 1.92612 2.59819 + endloop + endfacet + facet normal -0.441748 0.243546 0.863449 + outer loop + vertex 0.923244 1.92129 2.59712 + vertex 0.927038 1.92003 2.59941 + vertex 0.927994 1.92612 2.59819 + endloop + endfacet + facet normal -0.447183 0.229251 0.864564 + outer loop + vertex 0.922922 1.91626 2.59828 + vertex 0.927038 1.92003 2.59941 + vertex 0.923244 1.92129 2.59712 + endloop + endfacet + facet normal -0.444156 0.225155 0.867197 + outer loop + vertex 0.92646 1.91511 2.60039 + vertex 0.927038 1.92003 2.59941 + vertex 0.922922 1.91626 2.59828 + endloop + endfacet + facet normal -0.442767 0.22892 0.866921 + outer loop + vertex 0.922876 1.9109 2.59968 + vertex 0.92646 1.91511 2.60039 + vertex 0.922922 1.91626 2.59828 + endloop + endfacet + facet normal -0.392403 0.240625 0.887761 + outer loop + vertex 0.921319 1.92302 2.59578 + vertex 0.923977 1.92522 2.59636 + vertex 0.921664 1.92614 2.59509 + endloop + endfacet + facet normal -0.394459 0.243558 0.886048 + outer loop + vertex 0.923977 1.92522 2.59636 + vertex 0.921319 1.92302 2.59578 + vertex 0.923244 1.92129 2.59712 + endloop + endfacet + facet normal -0.396653 0.233914 0.887666 + outer loop + vertex 0.922876 1.9109 2.59968 + vertex 0.922922 1.91626 2.59828 + vertex 0.918269 1.91194 2.59734 + endloop + endfacet + facet normal -0.401041 0.218785 0.88955 + outer loop + vertex 0.918072 1.90677 2.59853 + vertex 0.922876 1.9109 2.59968 + vertex 0.918269 1.91194 2.59734 + endloop + endfacet + facet normal -0.40384 0.222665 0.887318 + outer loop + vertex 0.921673 1.90571 2.60043 + vertex 0.922876 1.9109 2.59968 + vertex 0.918072 1.90677 2.59853 + endloop + endfacet + facet normal -0.406707 0.214249 0.88808 + outer loop + vertex 0.91786 1.90175 2.59964 + vertex 0.921673 1.90571 2.60043 + vertex 0.918072 1.90677 2.59853 + endloop + endfacet + facet normal -0.408984 0.216772 0.886421 + outer loop + vertex 0.921243 1.90239 2.60105 + vertex 0.921673 1.90571 2.60043 + vertex 0.91786 1.90175 2.59964 + endloop + endfacet + facet normal -0.408624 0.211836 0.887779 + outer loop + vertex 0.921243 1.90239 2.60105 + vertex 0.91786 1.90175 2.59964 + vertex 0.919817 1.89982 2.601 + endloop + endfacet + facet normal -0.46254 0.242462 0.852801 + outer loop + vertex 0.919817 1.89982 2.601 + vertex 0.922779 1.89989 2.60259 + vertex 0.921243 1.90239 2.60105 + endloop + endfacet + facet normal -0.469549 0.236771 0.850567 + outer loop + vertex 0.923656 1.90379 2.60199 + vertex 0.921243 1.90239 2.60105 + vertex 0.922779 1.89989 2.60259 + endloop + endfacet + facet normal -0.463968 0.227814 0.856058 + outer loop + vertex 0.919817 1.89982 2.601 + vertex 0.919481 1.89641 2.60173 + vertex 0.922779 1.89989 2.60259 + endloop + endfacet + facet normal -0.412924 0.228247 0.881701 + outer loop + vertex 0.919817 1.89982 2.601 + vertex 0.917315 1.89782 2.60035 + vertex 0.919481 1.89641 2.60173 + endloop + endfacet + facet normal -0.414354 0.22596 0.88162 + outer loop + vertex 0.915843 1.89394 2.60065 + vertex 0.919481 1.89641 2.60173 + vertex 0.917315 1.89782 2.60035 + endloop + endfacet + facet normal -0.387049 0.216732 0.896226 + outer loop + vertex 0.917315 1.89782 2.60035 + vertex 0.913374 1.89654 2.59895 + vertex 0.915843 1.89394 2.60065 + endloop + endfacet + facet normal -0.39062 0.212924 0.895589 + outer loop + vertex 0.913374 1.89654 2.59895 + vertex 0.911962 1.89103 2.59965 + vertex 0.915843 1.89394 2.60065 + endloop + endfacet + facet normal -0.389983 0.211894 0.896111 + outer loop + vertex 0.915843 1.89394 2.60065 + vertex 0.911962 1.89103 2.59965 + vertex 0.914538 1.89016 2.60098 + endloop + endfacet + facet normal -0.405782 0.216641 0.887923 + outer loop + vertex 0.914538 1.89016 2.60098 + vertex 0.918257 1.89134 2.60239 + vertex 0.915843 1.89394 2.60065 + endloop + endfacet + facet normal -0.403327 0.203921 0.892045 + outer loop + vertex 0.914538 1.89016 2.60098 + vertex 0.914595 1.88679 2.60177 + vertex 0.918257 1.89134 2.60239 + endloop + endfacet + facet normal -0.407956 0.208071 0.888976 + outer loop + vertex 0.914595 1.88679 2.60177 + vertex 0.918473 1.88603 2.60373 + vertex 0.918257 1.89134 2.60239 + endloop + endfacet + facet normal -0.409241 0.203031 0.889551 + outer loop + vertex 0.913359 1.88157 2.60239 + vertex 0.918473 1.88603 2.60373 + vertex 0.914595 1.88679 2.60177 + endloop + endfacet + facet normal -0.385779 0.198827 0.900912 + outer loop + vertex 0.913359 1.88157 2.60239 + vertex 0.914595 1.88679 2.60177 + vertex 0.910742 1.88387 2.60077 + endloop + endfacet + facet normal -0.384285 0.200688 0.901138 + outer loop + vertex 0.909516 1.88016 2.60107 + vertex 0.913359 1.88157 2.60239 + vertex 0.910742 1.88387 2.60077 + endloop + endfacet + facet normal -0.401389 0.205634 0.892525 + outer loop + vertex 0.910742 1.88387 2.60077 + vertex 0.906913 1.88088 2.59973 + vertex 0.909516 1.88016 2.60107 + endloop + endfacet + facet normal -0.400233 0.203832 0.893457 + outer loop + vertex 0.908114 1.8862 2.59906 + vertex 0.906913 1.88088 2.59973 + vertex 0.910742 1.88387 2.60077 + endloop + endfacet + facet normal -0.398553 0.205925 0.893728 + outer loop + vertex 0.911975 1.88761 2.60046 + vertex 0.908114 1.8862 2.59906 + vertex 0.910742 1.88387 2.60077 + endloop + endfacet + facet normal -0.399239 0.208771 0.892761 + outer loop + vertex 0.911975 1.88761 2.60046 + vertex 0.911962 1.89103 2.59965 + vertex 0.908114 1.8862 2.59906 + endloop + endfacet + facet normal -0.397042 0.206847 0.894188 + outer loop + vertex 0.908114 1.8862 2.59906 + vertex 0.911962 1.89103 2.59965 + vertex 0.908089 1.89169 2.59778 + endloop + endfacet + facet normal -0.382242 0.192698 0.903747 + outer loop + vertex 0.909516 1.88016 2.60107 + vertex 0.909543 1.87688 2.60178 + vertex 0.913359 1.88157 2.60239 + endloop + endfacet + facet normal -0.380024 0.190717 0.905101 + outer loop + vertex 0.909543 1.87688 2.60178 + vertex 0.913082 1.87643 2.60336 + vertex 0.913359 1.88157 2.60239 + endloop + endfacet + facet normal -0.404976 0.190039 0.89436 + outer loop + vertex 0.913082 1.87643 2.60336 + vertex 0.91721 1.88053 2.60436 + vertex 0.913359 1.88157 2.60239 + endloop + endfacet + facet normal -0.404076 0.188978 0.894991 + outer loop + vertex 0.916592 1.87604 2.60503 + vertex 0.91721 1.88053 2.60436 + vertex 0.913082 1.87643 2.60336 + endloop + endfacet + facet normal -0.403943 0.189742 0.89489 + outer loop + vertex 0.912978 1.87141 2.60438 + vertex 0.916592 1.87604 2.60503 + vertex 0.913082 1.87643 2.60336 + endloop + endfacet + facet normal -0.382575 0.191136 0.903938 + outer loop + vertex 0.912978 1.87141 2.60438 + vertex 0.913082 1.87643 2.60336 + vertex 0.908408 1.87168 2.60239 + endloop + endfacet + facet normal -0.382861 0.188912 0.904284 + outer loop + vertex 0.908223 1.8665 2.60339 + vertex 0.912978 1.87141 2.60438 + vertex 0.908408 1.87168 2.60239 + endloop + endfacet + facet normal -0.389546 0.188609 0.901488 + outer loop + vertex 0.904577 1.86672 2.60177 + vertex 0.908223 1.8665 2.60339 + vertex 0.908408 1.87168 2.60239 + endloop + endfacet + facet normal -0.389939 0.185505 0.901962 + outer loop + vertex 0.903472 1.86154 2.60236 + vertex 0.908223 1.8665 2.60339 + vertex 0.904577 1.86672 2.60177 + endloop + endfacet + facet normal -0.419006 0.190119 0.887856 + outer loop + vertex 0.903472 1.86154 2.60236 + vertex 0.904577 1.86672 2.60177 + vertex 0.900875 1.86361 2.60069 + endloop + endfacet + facet normal -0.419201 0.189846 0.887823 + outer loop + vertex 0.899679 1.8599 2.60092 + vertex 0.903472 1.86154 2.60236 + vertex 0.900875 1.86361 2.60069 + endloop + endfacet + facet normal -0.453042 0.199606 0.868856 + outer loop + vertex 0.900875 1.86361 2.60069 + vertex 0.897249 1.86075 2.59946 + vertex 0.899679 1.8599 2.60092 + endloop + endfacet + facet normal -0.454013 0.19698 0.868948 + outer loop + vertex 0.897203 1.85736 2.6002 + vertex 0.899679 1.8599 2.60092 + vertex 0.897249 1.86075 2.59946 + endloop + endfacet + facet normal -0.472239 0.195172 0.859592 + outer loop + vertex 0.897203 1.85736 2.6002 + vertex 0.897249 1.86075 2.59946 + vertex 0.893272 1.85618 2.59831 + endloop + endfacet + facet normal -0.471637 0.191224 0.860809 + outer loop + vertex 0.897203 1.85736 2.6002 + vertex 0.893272 1.85618 2.59831 + vertex 0.896168 1.85361 2.60047 + endloop + endfacet + facet normal -0.446029 0.185218 0.875644 + outer loop + vertex 0.896168 1.85361 2.60047 + vertex 0.899818 1.85677 2.60166 + vertex 0.897203 1.85736 2.6002 + endloop + endfacet + facet normal -0.446831 0.186391 0.874986 + outer loop + vertex 0.899253 1.85225 2.60233 + vertex 0.899818 1.85677 2.60166 + vertex 0.896168 1.85361 2.60047 + endloop + endfacet + facet normal -0.44691 0.18621 0.874984 + outer loop + vertex 0.895286 1.84896 2.601 + vertex 0.899253 1.85225 2.60233 + vertex 0.896168 1.85361 2.60047 + endloop + endfacet + facet normal -0.467111 0.188758 0.863816 + outer loop + vertex 0.896168 1.85361 2.60047 + vertex 0.89232 1.85042 2.59908 + vertex 0.895286 1.84896 2.601 + endloop + endfacet + facet normal -0.467498 0.187932 0.863787 + outer loop + vertex 0.89232 1.85042 2.59908 + vertex 0.891746 1.84579 2.59978 + vertex 0.895286 1.84896 2.601 + endloop + endfacet + facet normal -0.466739 0.186836 0.864434 + outer loop + vertex 0.895286 1.84896 2.601 + vertex 0.891746 1.84579 2.59978 + vertex 0.894312 1.84518 2.60129 + endloop + endfacet + facet normal -0.449069 0.183063 0.874543 + outer loop + vertex 0.894312 1.84518 2.60129 + vertex 0.898039 1.84667 2.6029 + vertex 0.895286 1.84896 2.601 + endloop + endfacet + facet normal -0.448421 0.180513 0.875405 + outer loop + vertex 0.894312 1.84518 2.60129 + vertex 0.894588 1.84195 2.6021 + vertex 0.898039 1.84667 2.6029 + endloop + endfacet + facet normal -0.44945 0.181383 0.874697 + outer loop + vertex 0.894588 1.84195 2.6021 + vertex 0.898252 1.84129 2.60412 + vertex 0.898039 1.84667 2.6029 + endloop + endfacet + facet normal -0.431617 0.184 0.883092 + outer loop + vertex 0.898252 1.84129 2.60412 + vertex 0.901808 1.84601 2.60488 + vertex 0.898039 1.84667 2.6029 + endloop + endfacet + facet normal -0.429898 0.191521 0.882331 + outer loop + vertex 0.901808 1.84601 2.60488 + vertex 0.903052 1.85133 2.60433 + vertex 0.898039 1.84667 2.6029 + endloop + endfacet + facet normal -0.422757 0.182168 0.887745 + outer loop + vertex 0.898039 1.84667 2.6029 + vertex 0.903052 1.85133 2.60433 + vertex 0.899253 1.85225 2.60233 + endloop + endfacet + facet normal -0.421148 0.187901 0.887315 + outer loop + vertex 0.903052 1.85133 2.60433 + vertex 0.903364 1.8565 2.60338 + vertex 0.899253 1.85225 2.60233 + endloop + endfacet + facet normal -0.398539 0.188421 0.897588 + outer loop + vertex 0.903052 1.85133 2.60433 + vertex 0.906814 1.85614 2.60499 + vertex 0.903364 1.8565 2.60338 + endloop + endfacet + facet normal -0.397467 0.194742 0.896714 + outer loop + vertex 0.906814 1.85614 2.60499 + vertex 0.908 1.86133 2.60439 + vertex 0.903364 1.8565 2.60338 + endloop + endfacet + facet normal -0.394186 0.19113 0.898936 + outer loop + vertex 0.903364 1.8565 2.60338 + vertex 0.908 1.86133 2.60439 + vertex 0.903472 1.86154 2.60236 + endloop + endfacet + facet normal -0.393901 0.194126 0.898419 + outer loop + vertex 0.908 1.86133 2.60439 + vertex 0.906814 1.85614 2.60499 + vertex 0.910525 1.85922 2.60595 + endloop + endfacet + facet normal -0.391588 0.197155 0.898771 + outer loop + vertex 0.911811 1.86301 2.60568 + vertex 0.908 1.86133 2.60439 + vertex 0.910525 1.85922 2.60595 + endloop + endfacet + facet normal -0.434063 0.20997 0.876072 + outer loop + vertex 0.910525 1.85922 2.60595 + vertex 0.914213 1.86204 2.6071 + vertex 0.911811 1.86301 2.60568 + endloop + endfacet + facet normal -0.43416 0.209739 0.876079 + outer loop + vertex 0.914352 1.86555 2.60633 + vertex 0.911811 1.86301 2.60568 + vertex 0.914213 1.86204 2.6071 + endloop + endfacet + facet normal -0.495281 0.205144 0.844164 + outer loop + vertex 0.914352 1.86555 2.60633 + vertex 0.914213 1.86204 2.6071 + vertex 0.918092 1.86633 2.60834 + endloop + endfacet + facet normal -0.495945 0.217096 0.840778 + outer loop + vertex 0.914352 1.86555 2.60633 + vertex 0.918092 1.86633 2.60834 + vertex 0.915551 1.86923 2.60609 + endloop + endfacet + facet normal -0.419133 0.195094 0.886716 + outer loop + vertex 0.915551 1.86923 2.60609 + vertex 0.911854 1.86628 2.60499 + vertex 0.914352 1.86555 2.60633 + endloop + endfacet + facet normal -0.420708 0.197543 0.885427 + outer loop + vertex 0.912978 1.87141 2.60438 + vertex 0.911854 1.86628 2.60499 + vertex 0.915551 1.86923 2.60609 + endloop + endfacet + facet normal -0.414168 0.206153 0.886547 + outer loop + vertex 0.916695 1.87293 2.60576 + vertex 0.912978 1.87141 2.60438 + vertex 0.915551 1.86923 2.60609 + endloop + endfacet + facet normal -0.49795 0.227716 0.836774 + outer loop + vertex 0.915551 1.86923 2.60609 + vertex 0.918927 1.87181 2.60739 + vertex 0.916695 1.87293 2.60576 + endloop + endfacet + facet normal -0.500434 0.222585 0.836673 + outer loop + vertex 0.918976 1.87523 2.60651 + vertex 0.916695 1.87293 2.60576 + vertex 0.918927 1.87181 2.60739 + endloop + endfacet + facet normal -0.47288 0.187378 0.860973 + outer loop + vertex 0.916695 1.87293 2.60576 + vertex 0.918976 1.87523 2.60651 + vertex 0.916592 1.87604 2.60503 + endloop + endfacet + facet normal -0.493621 0.219672 0.841477 + outer loop + vertex 0.918092 1.86633 2.60834 + vertex 0.918927 1.87181 2.60739 + vertex 0.915551 1.86923 2.60609 + endloop + endfacet + facet normal -0.496681 0.206759 0.842946 + outer loop + vertex 0.914213 1.86204 2.6071 + vertex 0.917287 1.86034 2.60933 + vertex 0.918092 1.86633 2.60834 + endloop + endfacet + facet normal -0.495422 0.209216 0.843081 + outer loop + vertex 0.912975 1.85672 2.6077 + vertex 0.917287 1.86034 2.60933 + vertex 0.914213 1.86204 2.6071 + endloop + endfacet + facet normal -0.482793 0.18875 0.855152 + outer loop + vertex 0.916689 1.85543 2.61008 + vertex 0.917287 1.86034 2.60933 + vertex 0.912975 1.85672 2.6077 + endloop + endfacet + facet normal -0.484955 0.182695 0.855243 + outer loop + vertex 0.913166 1.85122 2.60898 + vertex 0.916689 1.85543 2.61008 + vertex 0.912975 1.85672 2.6077 + endloop + endfacet + facet normal -0.47929 0.176792 0.859666 + outer loop + vertex 0.91669 1.85199 2.61079 + vertex 0.916689 1.85543 2.61008 + vertex 0.913166 1.85122 2.60898 + endloop + endfacet + facet normal -0.479865 0.183501 0.857938 + outer loop + vertex 0.91669 1.85199 2.61079 + vertex 0.913166 1.85122 2.60898 + vertex 0.915552 1.84844 2.61091 + endloop + endfacet + facet normal -0.564941 0.208659 0.798313 + outer loop + vertex 0.915552 1.84844 2.61091 + vertex 0.918594 1.85022 2.61259 + vertex 0.91669 1.85199 2.61079 + endloop + endfacet + facet normal -0.5713 0.199537 0.796116 + outer loop + vertex 0.918873 1.85373 2.61191 + vertex 0.91669 1.85199 2.61079 + vertex 0.918594 1.85022 2.61259 + endloop + endfacet + facet normal -0.562667 0.201571 0.801732 + outer loop + vertex 0.917522 1.84544 2.61304 + vertex 0.918594 1.85022 2.61259 + vertex 0.915552 1.84844 2.61091 + endloop + endfacet + facet normal -0.479063 0.184369 0.858199 + outer loop + vertex 0.913166 1.85122 2.60898 + vertex 0.912123 1.84596 2.60953 + vertex 0.915552 1.84844 2.61091 + endloop + endfacet + facet normal -0.474201 0.17504 0.862841 + outer loop + vertex 0.915552 1.84844 2.61091 + vertex 0.912123 1.84596 2.60953 + vertex 0.914531 1.8449 2.61107 + endloop + endfacet + facet normal -0.56563 0.198659 0.800373 + outer loop + vertex 0.914531 1.8449 2.61107 + vertex 0.917522 1.84544 2.61304 + vertex 0.915552 1.84844 2.61091 + endloop + endfacet + facet normal -0.565571 0.193851 0.801593 + outer loop + vertex 0.914531 1.8449 2.61107 + vertex 0.914634 1.84157 2.61194 + vertex 0.917522 1.84544 2.61304 + endloop + endfacet + facet normal -0.555281 0.167505 0.81462 + outer loop + vertex 0.91669 1.85199 2.61079 + vertex 0.918873 1.85373 2.61191 + vertex 0.916689 1.85543 2.61008 + endloop + endfacet + facet normal -0.419892 0.192759 0.886868 + outer loop + vertex 0.911811 1.86301 2.60568 + vertex 0.914352 1.86555 2.60633 + vertex 0.911854 1.86628 2.60499 + endloop + endfacet + facet normal -0.426662 0.197628 0.882554 + outer loop + vertex 0.912975 1.85672 2.6077 + vertex 0.914213 1.86204 2.6071 + vertex 0.910525 1.85922 2.60595 + endloop + endfacet + facet normal -0.423063 0.201712 0.883363 + outer loop + vertex 0.909293 1.8555 2.60621 + vertex 0.912975 1.85672 2.6077 + vertex 0.910525 1.85922 2.60595 + endloop + endfacet + facet normal -0.420651 0.189784 0.88715 + outer loop + vertex 0.909293 1.8555 2.60621 + vertex 0.909355 1.85212 2.60696 + vertex 0.912975 1.85672 2.6077 + endloop + endfacet + facet normal -0.423026 0.191909 0.885562 + outer loop + vertex 0.909355 1.85212 2.60696 + vertex 0.913166 1.85122 2.60898 + vertex 0.912975 1.85672 2.6077 + endloop + endfacet + facet normal -0.423657 0.189653 0.885746 + outer loop + vertex 0.908235 1.84674 2.60758 + vertex 0.913166 1.85122 2.60898 + vertex 0.909355 1.85212 2.60696 + endloop + endfacet + facet normal -0.392642 0.18493 0.900907 + outer loop + vertex 0.908235 1.84674 2.60758 + vertex 0.909355 1.85212 2.60696 + vertex 0.905575 1.84908 2.60594 + endloop + endfacet + facet normal -0.391848 0.185933 0.901046 + outer loop + vertex 0.904357 1.84526 2.6062 + vertex 0.908235 1.84674 2.60758 + vertex 0.905575 1.84908 2.60594 + endloop + endfacet + facet normal -0.406905 0.190225 0.893444 + outer loop + vertex 0.905575 1.84908 2.60594 + vertex 0.901808 1.84601 2.60488 + vertex 0.904357 1.84526 2.6062 + endloop + endfacet + facet normal -0.408264 0.186058 0.893702 + outer loop + vertex 0.90187 1.84262 2.60561 + vertex 0.904357 1.84526 2.6062 + vertex 0.901808 1.84601 2.60488 + endloop + endfacet + facet normal -0.39769 0.174545 0.900764 + outer loop + vertex 0.904357 1.84526 2.6062 + vertex 0.90187 1.84262 2.60561 + vertex 0.90448 1.84187 2.60691 + endloop + endfacet + facet normal -0.399244 0.1696 0.901022 + outer loop + vertex 0.900721 1.83886 2.60581 + vertex 0.90448 1.84187 2.60691 + vertex 0.90187 1.84262 2.60561 + endloop + endfacet + facet normal -0.429704 0.178066 0.885239 + outer loop + vertex 0.90187 1.84262 2.60561 + vertex 0.898252 1.84129 2.60412 + vertex 0.900721 1.83886 2.60581 + endloop + endfacet + facet normal -0.430841 0.176716 0.884956 + outer loop + vertex 0.898252 1.84129 2.60412 + vertex 0.897085 1.83603 2.60461 + vertex 0.900721 1.83886 2.60581 + endloop + endfacet + facet normal -0.432636 0.179643 0.88349 + outer loop + vertex 0.900721 1.83886 2.60581 + vertex 0.897085 1.83603 2.60461 + vertex 0.899567 1.83512 2.60601 + endloop + endfacet + facet normal -0.401949 0.171007 0.899552 + outer loop + vertex 0.899567 1.83512 2.60601 + vertex 0.903358 1.83655 2.60743 + vertex 0.900721 1.83886 2.60581 + endloop + endfacet + facet normal -0.400793 0.166625 0.900889 + outer loop + vertex 0.899567 1.83512 2.60601 + vertex 0.899773 1.83193 2.60669 + vertex 0.903358 1.83655 2.60743 + endloop + endfacet + facet normal -0.399842 0.165796 0.901464 + outer loop + vertex 0.899773 1.83193 2.60669 + vertex 0.903285 1.83148 2.60833 + vertex 0.903358 1.83655 2.60743 + endloop + endfacet + facet normal -0.398009 0.16591 0.902254 + outer loop + vertex 0.903285 1.83148 2.60833 + vertex 0.907277 1.83554 2.60934 + vertex 0.903358 1.83655 2.60743 + endloop + endfacet + facet normal -0.395901 0.173198 0.901812 + outer loop + vertex 0.907277 1.83554 2.60934 + vertex 0.908474 1.84119 2.60878 + vertex 0.903358 1.83655 2.60743 + endloop + endfacet + facet normal -0.394327 0.171144 0.902893 + outer loop + vertex 0.903358 1.83655 2.60743 + vertex 0.908474 1.84119 2.60878 + vertex 0.90448 1.84187 2.60691 + endloop + endfacet + facet normal -0.39269 0.178688 0.902145 + outer loop + vertex 0.90448 1.84187 2.60691 + vertex 0.908474 1.84119 2.60878 + vertex 0.908235 1.84674 2.60758 + endloop + endfacet + facet normal -0.412346 0.176046 0.893856 + outer loop + vertex 0.908474 1.84119 2.60878 + vertex 0.912123 1.84596 2.60953 + vertex 0.908235 1.84674 2.60758 + endloop + endfacet + facet normal -0.421786 0.184206 0.887787 + outer loop + vertex 0.912295 1.84255 2.61032 + vertex 0.912123 1.84596 2.60953 + vertex 0.908474 1.84119 2.60878 + endloop + endfacet + facet normal -0.423127 0.190082 0.885908 + outer loop + vertex 0.912295 1.84255 2.61032 + vertex 0.908474 1.84119 2.60878 + vertex 0.911282 1.83866 2.61067 + endloop + endfacet + facet normal -0.49919 0.205901 0.841673 + outer loop + vertex 0.911282 1.83866 2.61067 + vertex 0.914634 1.84157 2.61194 + vertex 0.912295 1.84255 2.61032 + endloop + endfacet + facet normal -0.498952 0.206472 0.841675 + outer loop + vertex 0.914531 1.8449 2.61107 + vertex 0.912295 1.84255 2.61032 + vertex 0.914634 1.84157 2.61194 + endloop + endfacet + facet normal -0.499679 0.206675 0.841194 + outer loop + vertex 0.914322 1.83669 2.61296 + vertex 0.914634 1.84157 2.61194 + vertex 0.911282 1.83866 2.61067 + endloop + endfacet + facet normal -0.509798 0.188865 0.839307 + outer loop + vertex 0.910284 1.83392 2.61113 + vertex 0.914322 1.83669 2.61296 + vertex 0.911282 1.83866 2.61067 + endloop + endfacet + facet normal -0.430289 0.176582 0.885252 + outer loop + vertex 0.911282 1.83866 2.61067 + vertex 0.907277 1.83554 2.60934 + vertex 0.910284 1.83392 2.61113 + endloop + endfacet + facet normal -0.435139 0.166999 0.88474 + outer loop + vertex 0.907277 1.83554 2.60934 + vertex 0.906727 1.831 2.60993 + vertex 0.910284 1.83392 2.61113 + endloop + endfacet + facet normal -0.429629 0.158556 0.888976 + outer loop + vertex 0.910284 1.83392 2.61113 + vertex 0.906727 1.831 2.60993 + vertex 0.909174 1.83018 2.61126 + endloop + endfacet + facet normal -0.506385 0.179758 0.843363 + outer loop + vertex 0.909174 1.83018 2.61126 + vertex 0.912517 1.8307 2.61315 + vertex 0.910284 1.83392 2.61113 + endloop + endfacet + facet normal -0.506258 0.175004 0.844439 + outer loop + vertex 0.909174 1.83018 2.61126 + vertex 0.909162 1.82671 2.61197 + vertex 0.912517 1.8307 2.61315 + endloop + endfacet + facet normal -0.445338 0.181428 0.876788 + outer loop + vertex 0.909174 1.83018 2.61126 + vertex 0.906845 1.82781 2.61057 + vertex 0.909162 1.82671 2.61197 + endloop + endfacet + facet normal -0.444784 0.182634 0.876819 + outer loop + vertex 0.9057 1.82406 2.61076 + vertex 0.909162 1.82671 2.61197 + vertex 0.906845 1.82781 2.61057 + endloop + endfacet + facet normal -0.40223 0.170826 0.899461 + outer loop + vertex 0.906845 1.82781 2.61057 + vertex 0.903179 1.8264 2.60919 + vertex 0.9057 1.82406 2.61076 + endloop + endfacet + facet normal -0.405683 0.166589 0.898704 + outer loop + vertex 0.903179 1.8264 2.60919 + vertex 0.902055 1.82108 2.60967 + vertex 0.9057 1.82406 2.61076 + endloop + endfacet + facet normal -0.405872 0.16687 0.898567 + outer loop + vertex 0.9057 1.82406 2.61076 + vertex 0.902055 1.82108 2.60967 + vertex 0.904603 1.82033 2.61096 + endloop + endfacet + facet normal -0.436891 0.175127 0.882302 + outer loop + vertex 0.904603 1.82033 2.61096 + vertex 0.90818 1.82152 2.6125 + vertex 0.9057 1.82406 2.61076 + endloop + endfacet + facet normal -0.434356 0.162782 0.88591 + outer loop + vertex 0.904603 1.82033 2.61096 + vertex 0.904847 1.81706 2.61168 + vertex 0.90818 1.82152 2.6125 + endloop + endfacet + facet normal -0.438268 0.16618 0.883349 + outer loop + vertex 0.904847 1.81706 2.61168 + vertex 0.908574 1.81618 2.6137 + vertex 0.90818 1.82152 2.6125 + endloop + endfacet + facet normal -0.439163 0.162808 0.883532 + outer loop + vertex 0.904251 1.81238 2.61225 + vertex 0.908574 1.81618 2.6137 + vertex 0.904847 1.81706 2.61168 + endloop + endfacet + facet normal -0.431578 0.152037 0.889171 + outer loop + vertex 0.907406 1.81069 2.61407 + vertex 0.908574 1.81618 2.6137 + vertex 0.904251 1.81238 2.61225 + endloop + endfacet + facet normal -0.428185 0.158841 0.889622 + outer loop + vertex 0.903084 1.80682 2.61268 + vertex 0.907406 1.81069 2.61407 + vertex 0.904251 1.81238 2.61225 + endloop + endfacet + facet normal -0.399823 0.153972 0.903567 + outer loop + vertex 0.903084 1.80682 2.61268 + vertex 0.904251 1.81238 2.61225 + vertex 0.900263 1.80922 2.61102 + endloop + endfacet + facet normal -0.395815 0.159266 0.904414 + outer loop + vertex 0.899306 1.80543 2.61127 + vertex 0.903084 1.80682 2.61268 + vertex 0.900263 1.80922 2.61102 + endloop + endfacet + facet normal -0.409747 0.162334 0.897639 + outer loop + vertex 0.900263 1.80922 2.61102 + vertex 0.896602 1.80603 2.60993 + vertex 0.899306 1.80543 2.61127 + endloop + endfacet + facet normal -0.410575 0.159062 0.897846 + outer loop + vertex 0.896946 1.80279 2.61066 + vertex 0.899306 1.80543 2.61127 + vertex 0.896602 1.80603 2.60993 + endloop + endfacet + facet normal -0.428388 0.155429 0.890127 + outer loop + vertex 0.896946 1.80279 2.61066 + vertex 0.896602 1.80603 2.60993 + vertex 0.89316 1.80122 2.60911 + endloop + endfacet + facet normal -0.426018 0.147208 0.892658 + outer loop + vertex 0.896946 1.80279 2.61066 + vertex 0.89316 1.80122 2.60911 + vertex 0.896041 1.79894 2.61086 + endloop + endfacet + facet normal -0.399285 0.141613 0.905824 + outer loop + vertex 0.896041 1.79894 2.61086 + vertex 0.899697 1.80218 2.61197 + vertex 0.896946 1.80279 2.61066 + endloop + endfacet + facet normal -0.400402 0.14312 0.905094 + outer loop + vertex 0.899177 1.79747 2.61248 + vertex 0.899697 1.80218 2.61197 + vertex 0.896041 1.79894 2.61086 + endloop + endfacet + facet normal -0.40053 0.142835 0.905082 + outer loop + vertex 0.895204 1.79423 2.61124 + vertex 0.899177 1.79747 2.61248 + vertex 0.896041 1.79894 2.61086 + endloop + endfacet + facet normal -0.422441 0.145897 0.894572 + outer loop + vertex 0.896041 1.79894 2.61086 + vertex 0.892103 1.79554 2.60956 + vertex 0.895204 1.79423 2.61124 + endloop + endfacet + facet normal -0.421017 0.149376 0.894668 + outer loop + vertex 0.892103 1.79554 2.60956 + vertex 0.891664 1.79094 2.61012 + vertex 0.895204 1.79423 2.61124 + endloop + endfacet + facet normal -0.421697 0.150269 0.894198 + outer loop + vertex 0.895204 1.79423 2.61124 + vertex 0.891664 1.79094 2.61012 + vertex 0.894235 1.79039 2.61142 + endloop + endfacet + facet normal -0.401195 0.145596 0.904347 + outer loop + vertex 0.894235 1.79039 2.61142 + vertex 0.89797 1.79183 2.61285 + vertex 0.895204 1.79423 2.61124 + endloop + endfacet + facet normal -0.40201 0.148545 0.903506 + outer loop + vertex 0.894235 1.79039 2.61142 + vertex 0.894414 1.787 2.61206 + vertex 0.89797 1.79183 2.61285 + endloop + endfacet + facet normal -0.399438 0.146406 0.904994 + outer loop + vertex 0.894414 1.787 2.61206 + vertex 0.898309 1.78634 2.61389 + vertex 0.89797 1.79183 2.61285 + endloop + endfacet + facet normal -0.40024 0.146293 0.904658 + outer loop + vertex 0.898309 1.78634 2.61389 + vertex 0.901826 1.79111 2.61467 + vertex 0.89797 1.79183 2.61285 + endloop + endfacet + facet normal -0.400812 0.143649 0.904829 + outer loop + vertex 0.901826 1.79111 2.61467 + vertex 0.902439 1.79586 2.61419 + vertex 0.89797 1.79183 2.61285 + endloop + endfacet + facet normal -0.40163 0.144732 0.904293 + outer loop + vertex 0.89797 1.79183 2.61285 + vertex 0.902439 1.79586 2.61419 + vertex 0.899177 1.79747 2.61248 + endloop + endfacet + facet normal -0.400314 0.147552 0.904421 + outer loop + vertex 0.902439 1.79586 2.61419 + vertex 0.903601 1.80147 2.61379 + vertex 0.899177 1.79747 2.61248 + endloop + endfacet + facet normal -0.442022 0.154709 0.883562 + outer loop + vertex 0.903601 1.80147 2.61379 + vertex 0.902439 1.79586 2.61419 + vertex 0.906343 1.79882 2.61562 + endloop + endfacet + facet normal -0.432674 0.166128 0.886112 + outer loop + vertex 0.907239 1.80268 2.61534 + vertex 0.903601 1.80147 2.61379 + vertex 0.906343 1.79882 2.61562 + endloop + endfacet + facet normal -0.524478 0.183411 0.831435 + outer loop + vertex 0.906343 1.79882 2.61562 + vertex 0.909581 1.80156 2.61706 + vertex 0.907239 1.80268 2.61534 + endloop + endfacet + facet normal -0.526434 0.178911 0.831179 + outer loop + vertex 0.909351 1.80496 2.61619 + vertex 0.907239 1.80268 2.61534 + vertex 0.909581 1.80156 2.61706 + endloop + endfacet + facet normal -0.495192 0.140247 0.857389 + outer loop + vertex 0.907239 1.80268 2.61534 + vertex 0.909351 1.80496 2.61619 + vertex 0.906887 1.80599 2.61459 + endloop + endfacet + facet normal -0.522629 0.180256 0.833287 + outer loop + vertex 0.909343 1.7966 2.61799 + vertex 0.909581 1.80156 2.61706 + vertex 0.906343 1.79882 2.61562 + endloop + endfacet + facet normal -0.530032 0.167994 0.83117 + outer loop + vertex 0.905408 1.79401 2.616 + vertex 0.909343 1.7966 2.61799 + vertex 0.906343 1.79882 2.61562 + endloop + endfacet + facet normal -0.524918 0.155916 0.836751 + outer loop + vertex 0.907684 1.79066 2.61805 + vertex 0.909343 1.7966 2.61799 + vertex 0.905408 1.79401 2.616 + endloop + endfacet + facet normal -0.523515 0.157255 0.837379 + outer loop + vertex 0.90439 1.79022 2.61608 + vertex 0.907684 1.79066 2.61805 + vertex 0.905408 1.79401 2.616 + endloop + endfacet + facet normal -0.439094 0.135632 0.888145 + outer loop + vertex 0.905408 1.79401 2.616 + vertex 0.901826 1.79111 2.61467 + vertex 0.90439 1.79022 2.61608 + endloop + endfacet + facet normal -0.437089 0.141505 0.888217 + outer loop + vertex 0.902109 1.7878 2.61534 + vertex 0.90439 1.79022 2.61608 + vertex 0.901826 1.79111 2.61467 + endloop + endfacet + facet normal -0.456653 0.164203 0.87436 + outer loop + vertex 0.90439 1.79022 2.61608 + vertex 0.902109 1.7878 2.61534 + vertex 0.904567 1.78678 2.61681 + endloop + endfacet + facet normal -0.45573 0.166495 0.874408 + outer loop + vertex 0.901152 1.78393 2.61558 + vertex 0.904567 1.78678 2.61681 + vertex 0.902109 1.7878 2.61534 + endloop + endfacet + facet normal -0.403957 0.15535 0.90149 + outer loop + vertex 0.902109 1.7878 2.61534 + vertex 0.898309 1.78634 2.61389 + vertex 0.901152 1.78393 2.61558 + endloop + endfacet + facet normal -0.407671 0.150388 0.90066 + outer loop + vertex 0.898309 1.78634 2.61389 + vertex 0.897208 1.78065 2.61434 + vertex 0.901152 1.78393 2.61558 + endloop + endfacet + facet normal -0.408182 0.151137 0.900303 + outer loop + vertex 0.901152 1.78393 2.61558 + vertex 0.897208 1.78065 2.61434 + vertex 0.90038 1.77919 2.61602 + endloop + endfacet + facet normal -0.451022 0.156082 0.878759 + outer loop + vertex 0.90038 1.77919 2.61602 + vertex 0.904099 1.78209 2.61742 + vertex 0.901152 1.78393 2.61558 + endloop + endfacet + facet normal -0.445572 0.14699 0.883096 + outer loop + vertex 0.903455 1.77633 2.61805 + vertex 0.904099 1.78209 2.61742 + vertex 0.90038 1.77919 2.61602 + endloop + endfacet + facet normal -0.448941 0.142658 0.8821 + outer loop + vertex 0.899509 1.77537 2.6162 + vertex 0.903455 1.77633 2.61805 + vertex 0.90038 1.77919 2.61602 + endloop + endfacet + facet normal -0.413479 0.135406 0.900389 + outer loop + vertex 0.90038 1.77919 2.61602 + vertex 0.896832 1.77601 2.61487 + vertex 0.899509 1.77537 2.6162 + endloop + endfacet + facet normal -0.418705 0.114493 0.900876 + outer loop + vertex 0.897206 1.77277 2.61546 + vertex 0.899509 1.77537 2.6162 + vertex 0.896832 1.77601 2.61487 + endloop + endfacet + facet normal -0.425616 0.113139 0.897803 + outer loop + vertex 0.897206 1.77277 2.61546 + vertex 0.896832 1.77601 2.61487 + vertex 0.893663 1.77134 2.61396 + endloop + endfacet + facet normal -0.416977 0.0843534 0.904995 + outer loop + vertex 0.897206 1.77277 2.61546 + vertex 0.893663 1.77134 2.61396 + vertex 0.896518 1.76887 2.6155 + endloop + endfacet + facet normal -0.424584 0.0856518 0.901328 + outer loop + vertex 0.896518 1.76887 2.6155 + vertex 0.899846 1.77199 2.61677 + vertex 0.897206 1.77277 2.61546 + endloop + endfacet + facet normal -0.427317 0.0892422 0.899687 + outer loop + vertex 0.899582 1.76731 2.61711 + vertex 0.899846 1.77199 2.61677 + vertex 0.896518 1.76887 2.6155 + endloop + endfacet + facet normal -0.471153 0.0901154 0.877436 + outer loop + vertex 0.899582 1.76731 2.61711 + vertex 0.90296 1.77061 2.61859 + vertex 0.899846 1.77199 2.61677 + endloop + endfacet + facet normal -0.458428 0.122517 0.880246 + outer loop + vertex 0.899846 1.77199 2.61677 + vertex 0.90296 1.77061 2.61859 + vertex 0.903455 1.77633 2.61805 + endloop + endfacet + facet normal -0.479049 0.100632 0.872001 + outer loop + vertex 0.902634 1.76554 2.61899 + vertex 0.90296 1.77061 2.61859 + vertex 0.899582 1.76731 2.61711 + endloop + endfacet + facet normal -0.427723 0.069522 0.901232 + outer loop + vertex 0.893663 1.77134 2.61396 + vertex 0.892943 1.76567 2.61405 + vertex 0.896518 1.76887 2.6155 + endloop + endfacet + facet normal -0.423678 0.06904 0.903178 + outer loop + vertex 0.892943 1.76567 2.61405 + vertex 0.893663 1.77134 2.61396 + vertex 0.88959 1.7673 2.61236 + endloop + endfacet + facet normal -0.424623 0.0702059 0.902644 + outer loop + vertex 0.88959 1.7673 2.61236 + vertex 0.893663 1.77134 2.61396 + vertex 0.889758 1.77233 2.61204 + endloop + endfacet + facet normal -0.416812 0.102041 0.903247 + outer loop + vertex 0.893663 1.77134 2.61396 + vertex 0.893365 1.77646 2.61324 + vertex 0.889758 1.77233 2.61204 + endloop + endfacet + facet normal -0.416732 0.101958 0.903293 + outer loop + vertex 0.889758 1.77233 2.61204 + vertex 0.893365 1.77646 2.61324 + vertex 0.889863 1.77688 2.61158 + endloop + endfacet + facet normal -0.439211 0.101384 0.892645 + outer loop + vertex 0.889758 1.77233 2.61204 + vertex 0.889863 1.77688 2.61158 + vertex 0.886463 1.7736 2.61028 + endloop + endfacet + facet normal -0.44759 0.0771676 0.890903 + outer loop + vertex 0.886201 1.76874 2.61057 + vertex 0.889758 1.77233 2.61204 + vertex 0.886463 1.7736 2.61028 + endloop + endfacet + facet normal -0.469664 0.077678 0.879421 + outer loop + vertex 0.886463 1.7736 2.61028 + vertex 0.883005 1.77037 2.60872 + vertex 0.886201 1.76874 2.61057 + endloop + endfacet + facet normal -0.476517 0.0614994 0.877012 + outer loop + vertex 0.883005 1.77037 2.60872 + vertex 0.882822 1.76537 2.60897 + vertex 0.886201 1.76874 2.61057 + endloop + endfacet + facet normal -0.493067 0.061643 0.867805 + outer loop + vertex 0.882822 1.76537 2.60897 + vertex 0.883005 1.77037 2.60872 + vertex 0.879717 1.76699 2.60709 + endloop + endfacet + facet normal -0.48218 0.0952039 0.870884 + outer loop + vertex 0.883365 1.77622 2.60828 + vertex 0.883005 1.77037 2.60872 + vertex 0.886463 1.7736 2.61028 + endloop + endfacet + facet normal -0.472558 0.109328 0.874492 + outer loop + vertex 0.887193 1.77748 2.61019 + vertex 0.883365 1.77622 2.60828 + vertex 0.886463 1.7736 2.61028 + endloop + endfacet + facet normal -0.479368 0.142946 0.865894 + outer loop + vertex 0.887193 1.77748 2.61019 + vertex 0.887144 1.78098 2.60958 + vertex 0.883365 1.77622 2.60828 + endloop + endfacet + facet normal -0.470048 0.133765 0.872446 + outer loop + vertex 0.883365 1.77622 2.60828 + vertex 0.887144 1.78098 2.60958 + vertex 0.884029 1.78221 2.60772 + endloop + endfacet + facet normal -0.470554 0.133795 0.872168 + outer loop + vertex 0.883365 1.77622 2.60828 + vertex 0.884029 1.78221 2.60772 + vertex 0.880285 1.77895 2.6062 + endloop + endfacet + facet normal -0.479546 0.121302 0.869093 + outer loop + vertex 0.879547 1.77505 2.60633 + vertex 0.883365 1.77622 2.60828 + vertex 0.880285 1.77895 2.6062 + endloop + endfacet + facet normal -0.502714 0.125207 0.855337 + outer loop + vertex 0.880285 1.77895 2.6062 + vertex 0.877103 1.77604 2.60475 + vertex 0.879547 1.77505 2.60633 + endloop + endfacet + facet normal -0.51248 0.0974193 0.853155 + outer loop + vertex 0.877476 1.77266 2.60536 + vertex 0.879547 1.77505 2.60633 + vertex 0.877103 1.77604 2.60475 + endloop + endfacet + facet normal -0.537732 0.0919135 0.838091 + outer loop + vertex 0.877476 1.77266 2.60536 + vertex 0.877103 1.77604 2.60475 + vertex 0.874322 1.77188 2.60342 + endloop + endfacet + facet normal -0.529044 0.0840822 0.844419 + outer loop + vertex 0.874322 1.77188 2.60342 + vertex 0.877103 1.77604 2.60475 + vertex 0.874123 1.77717 2.60277 + endloop + endfacet + facet normal -0.53138 0.083817 0.842977 + outer loop + vertex 0.874322 1.77188 2.60342 + vertex 0.874123 1.77717 2.60277 + vertex 0.870901 1.77372 2.60108 + endloop + endfacet + facet normal -0.5356 0.089358 0.83973 + outer loop + vertex 0.870901 1.77372 2.60108 + vertex 0.874123 1.77717 2.60277 + vertex 0.871167 1.77878 2.60071 + endloop + endfacet + facet normal -0.53659 0.089364 0.839098 + outer loop + vertex 0.871167 1.77878 2.60071 + vertex 0.867849 1.77549 2.59894 + vertex 0.870901 1.77372 2.60108 + endloop + endfacet + facet normal -0.548021 0.063502 0.83405 + outer loop + vertex 0.867849 1.77549 2.59894 + vertex 0.867646 1.77033 2.5992 + vertex 0.870901 1.77372 2.60108 + endloop + endfacet + facet normal -0.551839 0.0635253 0.831528 + outer loop + vertex 0.867646 1.77033 2.5992 + vertex 0.867849 1.77549 2.59894 + vertex 0.864714 1.77194 2.59713 + endloop + endfacet + facet normal -0.550927 0.062368 0.83222 + outer loop + vertex 0.864714 1.77194 2.59713 + vertex 0.867849 1.77549 2.59894 + vertex 0.864881 1.77663 2.59689 + endloop + endfacet + facet normal -0.566909 0.0623797 0.821415 + outer loop + vertex 0.864714 1.77194 2.59713 + vertex 0.864881 1.77663 2.59689 + vertex 0.861998 1.77365 2.59513 + endloop + endfacet + facet normal -0.564554 0.0589956 0.823285 + outer loop + vertex 0.861998 1.77365 2.59513 + vertex 0.864881 1.77663 2.59689 + vertex 0.862538 1.77746 2.59523 + endloop + endfacet + facet normal -0.596503 0.0641121 0.800046 + outer loop + vertex 0.862538 1.77746 2.59523 + vertex 0.859617 1.77659 2.59312 + vertex 0.861998 1.77365 2.59513 + endloop + endfacet + facet normal -0.602861 0.108884 0.790382 + outer loop + vertex 0.862538 1.77746 2.59523 + vertex 0.86227 1.78083 2.59456 + vertex 0.859617 1.77659 2.59312 + endloop + endfacet + facet normal -0.59006 0.0970955 0.8015 + outer loop + vertex 0.859617 1.77659 2.59312 + vertex 0.86227 1.78083 2.59456 + vertex 0.859493 1.78183 2.59239 + endloop + endfacet + facet normal -0.591705 0.0968919 0.800311 + outer loop + vertex 0.859617 1.77659 2.59312 + vertex 0.859493 1.78183 2.59239 + vertex 0.856452 1.77861 2.59053 + endloop + endfacet + facet normal -0.59486 0.101564 0.797387 + outer loop + vertex 0.856452 1.77861 2.59053 + vertex 0.859493 1.78183 2.59239 + vertex 0.856818 1.78352 2.59018 + endloop + endfacet + facet normal -0.599111 0.101651 0.794187 + outer loop + vertex 0.856818 1.78352 2.59018 + vertex 0.853748 1.78097 2.58819 + vertex 0.856452 1.77861 2.59053 + endloop + endfacet + facet normal -0.616749 0.0713068 0.783924 + outer loop + vertex 0.853748 1.78097 2.58819 + vertex 0.85345 1.77589 2.58842 + vertex 0.856452 1.77861 2.59053 + endloop + endfacet + facet normal -0.616325 0.0712969 0.784258 + outer loop + vertex 0.85345 1.77589 2.58842 + vertex 0.853748 1.78097 2.58819 + vertex 0.850747 1.77836 2.58607 + endloop + endfacet + facet normal -0.624105 0.0864684 0.776541 + outer loop + vertex 0.850747 1.77836 2.58607 + vertex 0.853748 1.78097 2.58819 + vertex 0.851145 1.78346 2.58582 + endloop + endfacet + facet normal -0.622622 0.086411 0.777737 + outer loop + vertex 0.851145 1.78346 2.58582 + vertex 0.848143 1.78086 2.58371 + vertex 0.850747 1.77836 2.58607 + endloop + endfacet + facet normal -0.630071 0.101417 0.769887 + outer loop + vertex 0.848586 1.78595 2.5834 + vertex 0.848143 1.78086 2.58371 + vertex 0.851145 1.78346 2.58582 + endloop + endfacet + facet normal -0.612025 0.129888 0.780099 + outer loop + vertex 0.851699 1.78846 2.58542 + vertex 0.848586 1.78595 2.5834 + vertex 0.851145 1.78346 2.58582 + endloop + endfacet + facet normal -0.608383 0.129713 0.782972 + outer loop + vertex 0.851145 1.78346 2.58582 + vertex 0.854581 1.78647 2.58799 + vertex 0.851699 1.78846 2.58542 + endloop + endfacet + facet normal -0.596914 0.152363 0.787705 + outer loop + vertex 0.854581 1.78647 2.58799 + vertex 0.85457 1.79135 2.58704 + vertex 0.851699 1.78846 2.58542 + endloop + endfacet + facet normal -0.598471 0.154843 0.786039 + outer loop + vertex 0.851699 1.78846 2.58542 + vertex 0.85457 1.79135 2.58704 + vertex 0.852407 1.79233 2.5852 + endloop + endfacet + facet normal -0.60828 0.156187 0.778204 + outer loop + vertex 0.852407 1.79233 2.5852 + vertex 0.849536 1.7915 2.58313 + vertex 0.851699 1.78846 2.58542 + endloop + endfacet + facet normal -0.609098 0.165257 0.775686 + outer loop + vertex 0.852407 1.79233 2.5852 + vertex 0.852252 1.79572 2.58436 + vertex 0.849536 1.7915 2.58313 + endloop + endfacet + facet normal -0.606219 0.162585 0.778502 + outer loop + vertex 0.849536 1.7915 2.58313 + vertex 0.852252 1.79572 2.58436 + vertex 0.849631 1.79638 2.58218 + endloop + endfacet + facet normal -0.614841 0.161483 0.771942 + outer loop + vertex 0.849536 1.7915 2.58313 + vertex 0.849631 1.79638 2.58218 + vertex 0.84672 1.79345 2.58047 + endloop + endfacet + facet normal -0.620225 0.150792 0.769794 + outer loop + vertex 0.845973 1.7884 2.58086 + vertex 0.849536 1.7915 2.58313 + vertex 0.84672 1.79345 2.58047 + endloop + endfacet + facet normal -0.623419 0.151061 0.767156 + outer loop + vertex 0.84672 1.79345 2.58047 + vertex 0.843442 1.79101 2.57829 + vertex 0.845973 1.7884 2.58086 + endloop + endfacet + facet normal -0.635313 0.13314 0.760691 + outer loop + vertex 0.843442 1.79101 2.57829 + vertex 0.842429 1.78563 2.57839 + vertex 0.845973 1.7884 2.58086 + endloop + endfacet + facet normal -0.62849 0.116979 0.768971 + outer loop + vertex 0.845973 1.7884 2.58086 + vertex 0.842429 1.78563 2.57839 + vertex 0.845543 1.78332 2.58128 + endloop + endfacet + facet normal -0.633552 0.117062 0.764793 + outer loop + vertex 0.845543 1.78332 2.58128 + vertex 0.848586 1.78595 2.5834 + vertex 0.845973 1.7884 2.58086 + endloop + endfacet + facet normal -0.645298 0.0825004 0.759463 + outer loop + vertex 0.842429 1.78563 2.57839 + vertex 0.843051 1.78096 2.57942 + vertex 0.845543 1.78332 2.58128 + endloop + endfacet + facet normal -0.643565 0.0830437 0.760873 + outer loop + vertex 0.840049 1.78138 2.57684 + vertex 0.843051 1.78096 2.57942 + vertex 0.842429 1.78563 2.57839 + endloop + endfacet + facet normal -0.636322 0.0765313 0.767618 + outer loop + vertex 0.838912 1.78584 2.57545 + vertex 0.840049 1.78138 2.57684 + vertex 0.842429 1.78563 2.57839 + endloop + endfacet + facet normal -0.632063 0.11997 0.765574 + outer loop + vertex 0.838912 1.78584 2.57545 + vertex 0.842429 1.78563 2.57839 + vertex 0.8403 1.78914 2.57608 + endloop + endfacet + facet normal -0.628168 0.117659 0.76913 + outer loop + vertex 0.8403 1.78914 2.57608 + vertex 0.838218 1.78836 2.5745 + vertex 0.838912 1.78584 2.57545 + endloop + endfacet + facet normal -0.661863 0.0985643 0.743117 + outer loop + vertex 0.835827 1.78767 2.57246 + vertex 0.838912 1.78584 2.57545 + vertex 0.838218 1.78836 2.5745 + endloop + endfacet + facet normal -0.666676 0.159327 0.728119 + outer loop + vertex 0.838218 1.78836 2.5745 + vertex 0.838217 1.7912 2.57387 + vertex 0.835827 1.78767 2.57246 + endloop + endfacet + facet normal -0.661805 0.153782 0.733734 + outer loop + vertex 0.835827 1.78767 2.57246 + vertex 0.838217 1.7912 2.57387 + vertex 0.835731 1.79316 2.57122 + endloop + endfacet + facet normal -0.657039 0.15478 0.737796 + outer loop + vertex 0.835731 1.79316 2.57122 + vertex 0.83218 1.79042 2.56864 + vertex 0.835827 1.78767 2.57246 + endloop + endfacet + facet normal -0.668044 0.132446 0.73224 + outer loop + vertex 0.83218 1.79042 2.56864 + vertex 0.832395 1.78542 2.56973 + vertex 0.835827 1.78767 2.57246 + endloop + endfacet + facet normal -0.662797 0.115124 0.739896 + outer loop + vertex 0.835827 1.78767 2.57246 + vertex 0.832395 1.78542 2.56973 + vertex 0.834553 1.78383 2.57192 + endloop + endfacet + facet normal -0.647428 0.107964 0.75444 + outer loop + vertex 0.835827 1.78767 2.57246 + vertex 0.834553 1.78383 2.57192 + vertex 0.836987 1.78321 2.57409 + endloop + endfacet + facet normal -0.657071 0.0598161 0.751451 + outer loop + vertex 0.834553 1.78383 2.57192 + vertex 0.835017 1.78016 2.57261 + vertex 0.836987 1.78321 2.57409 + endloop + endfacet + facet normal -0.659137 0.0592189 0.749687 + outer loop + vertex 0.834553 1.78383 2.57192 + vertex 0.83278 1.78206 2.5705 + vertex 0.835017 1.78016 2.57261 + endloop + endfacet + facet normal -0.674866 0.0887793 0.732581 + outer loop + vertex 0.83278 1.78206 2.5705 + vertex 0.834553 1.78383 2.57192 + vertex 0.832395 1.78542 2.56973 + endloop + endfacet + facet normal -0.660529 0.164171 0.732632 + outer loop + vertex 0.83335 1.79588 2.56847 + vertex 0.83218 1.79042 2.56864 + vertex 0.835731 1.79316 2.57122 + endloop + endfacet + facet normal -0.654064 0.173515 0.73627 + outer loop + vertex 0.836448 1.7981 2.57069 + vertex 0.83335 1.79588 2.56847 + vertex 0.835731 1.79316 2.57122 + endloop + endfacet + facet normal -0.650904 0.173359 0.739102 + outer loop + vertex 0.835731 1.79316 2.57122 + vertex 0.838652 1.79577 2.57318 + vertex 0.836448 1.7981 2.57069 + endloop + endfacet + facet normal -0.649349 0.175699 0.739916 + outer loop + vertex 0.838652 1.79577 2.57318 + vertex 0.839121 1.80017 2.57255 + vertex 0.836448 1.7981 2.57069 + endloop + endfacet + facet normal -0.648376 0.173136 0.741372 + outer loop + vertex 0.836448 1.7981 2.57069 + vertex 0.839121 1.80017 2.57255 + vertex 0.83733 1.80181 2.5706 + endloop + endfacet + facet normal -0.653125 0.174151 0.736953 + outer loop + vertex 0.83733 1.80181 2.5706 + vertex 0.834474 1.80136 2.56817 + vertex 0.836448 1.7981 2.57069 + endloop + endfacet + facet normal -0.653246 0.169009 0.738042 + outer loop + vertex 0.83733 1.80181 2.5706 + vertex 0.837235 1.80522 2.56973 + vertex 0.834474 1.80136 2.56817 + endloop + endfacet + facet normal -0.654715 0.17075 0.736338 + outer loop + vertex 0.834474 1.80136 2.56817 + vertex 0.837235 1.80522 2.56973 + vertex 0.834245 1.80646 2.56679 + endloop + endfacet + facet normal -0.659577 0.169432 0.732292 + outer loop + vertex 0.834474 1.80136 2.56817 + vertex 0.834245 1.80646 2.56679 + vertex 0.831432 1.8034 2.56496 + endloop + endfacet + facet normal -0.657099 0.174698 0.733281 + outer loop + vertex 0.831072 1.79848 2.56581 + vertex 0.834474 1.80136 2.56817 + vertex 0.831432 1.8034 2.56496 + endloop + endfacet + facet normal -0.65938 0.174518 0.731273 + outer loop + vertex 0.831432 1.8034 2.56496 + vertex 0.828581 1.80074 2.56303 + vertex 0.831072 1.79848 2.56581 + endloop + endfacet + facet normal -0.657714 0.177361 0.732089 + outer loop + vertex 0.828581 1.80074 2.56303 + vertex 0.828268 1.79609 2.56387 + vertex 0.831072 1.79848 2.56581 + endloop + endfacet + facet normal -0.65614 0.173642 0.73439 + outer loop + vertex 0.831072 1.79848 2.56581 + vertex 0.828268 1.79609 2.56387 + vertex 0.830258 1.79396 2.56615 + endloop + endfacet + facet normal -0.656624 0.173695 0.733944 + outer loop + vertex 0.830258 1.79396 2.56615 + vertex 0.83335 1.79588 2.56847 + vertex 0.831072 1.79848 2.56581 + endloop + endfacet + facet normal -0.653721 0.162909 0.738992 + outer loop + vertex 0.83218 1.79042 2.56864 + vertex 0.83335 1.79588 2.56847 + vertex 0.830258 1.79396 2.56615 + endloop + endfacet + facet normal -0.658922 0.157651 0.735506 + outer loop + vertex 0.828659 1.7907 2.56542 + vertex 0.83218 1.79042 2.56864 + vertex 0.830258 1.79396 2.56615 + endloop + endfacet + facet normal -0.65437 0.154349 0.740254 + outer loop + vertex 0.830258 1.79396 2.56615 + vertex 0.828206 1.79322 2.56449 + vertex 0.828659 1.7907 2.56542 + endloop + endfacet + facet normal -0.665977 0.148841 0.730973 + outer loop + vertex 0.825848 1.79297 2.5624 + vertex 0.828659 1.7907 2.56542 + vertex 0.828206 1.79322 2.56449 + endloop + endfacet + facet normal -0.664798 0.171866 0.726984 + outer loop + vertex 0.828206 1.79322 2.56449 + vertex 0.828268 1.79609 2.56387 + vertex 0.825848 1.79297 2.5624 + endloop + endfacet + facet normal -0.66318 0.16967 0.728975 + outer loop + vertex 0.825848 1.79297 2.5624 + vertex 0.828268 1.79609 2.56387 + vertex 0.82585 1.79823 2.56118 + endloop + endfacet + facet normal -0.662445 0.169817 0.729609 + outer loop + vertex 0.82585 1.79823 2.56118 + vertex 0.823212 1.79596 2.55931 + vertex 0.825848 1.79297 2.5624 + endloop + endfacet + facet normal -0.663836 0.16777 0.728818 + outer loop + vertex 0.823212 1.79596 2.55931 + vertex 0.82325 1.79281 2.56007 + vertex 0.825848 1.79297 2.5624 + endloop + endfacet + facet normal -0.66638 0.128901 0.734386 + outer loop + vertex 0.825848 1.79297 2.5624 + vertex 0.82325 1.79281 2.56007 + vertex 0.823574 1.7899 2.56087 + endloop + endfacet + facet normal -0.669785 0.133347 0.730484 + outer loop + vertex 0.825848 1.79297 2.5624 + vertex 0.823574 1.7899 2.56087 + vertex 0.826374 1.7881 2.56377 + endloop + endfacet + facet normal -0.685716 0.0943587 0.721727 + outer loop + vertex 0.823574 1.7899 2.56087 + vertex 0.824078 1.78551 2.56192 + vertex 0.826374 1.7881 2.56377 + endloop + endfacet + facet normal -0.665707 0.177601 0.72477 + outer loop + vertex 0.823432 1.80081 2.55832 + vertex 0.823212 1.79596 2.55931 + vertex 0.82585 1.79823 2.56118 + endloop + endfacet + facet normal -0.664226 0.179868 0.72557 + outer loop + vertex 0.826094 1.80311 2.56019 + vertex 0.823432 1.80081 2.55832 + vertex 0.82585 1.79823 2.56118 + endloop + endfacet + facet normal -0.660308 0.180369 0.729014 + outer loop + vertex 0.82585 1.79823 2.56118 + vertex 0.828581 1.80074 2.56303 + vertex 0.826094 1.80311 2.56019 + endloop + endfacet + facet normal -0.662281 0.177112 0.728021 + outer loop + vertex 0.828581 1.80074 2.56303 + vertex 0.828723 1.8055 2.562 + vertex 0.826094 1.80311 2.56019 + endloop + endfacet + facet normal -0.664103 0.181129 0.725368 + outer loop + vertex 0.826094 1.80311 2.56019 + vertex 0.828723 1.8055 2.562 + vertex 0.826196 1.80766 2.55915 + endloop + endfacet + facet normal -0.667715 0.174616 0.723648 + outer loop + vertex 0.828592 1.80994 2.5608 + vertex 0.826196 1.80766 2.55915 + vertex 0.828723 1.8055 2.562 + endloop + endfacet + facet normal -0.665977 0.175068 0.725139 + outer loop + vertex 0.828592 1.80994 2.5608 + vertex 0.828723 1.8055 2.562 + vertex 0.8313 1.80809 2.56374 + endloop + endfacet + facet normal -0.66842 0.169889 0.724122 + outer loop + vertex 0.831037 1.81299 2.56235 + vertex 0.828592 1.80994 2.5608 + vertex 0.8313 1.80809 2.56374 + endloop + endfacet + facet normal -0.665874 0.170641 0.726287 + outer loop + vertex 0.831037 1.81299 2.56235 + vertex 0.8313 1.80809 2.56374 + vertex 0.833719 1.81067 2.56535 + endloop + endfacet + facet normal -0.669801 0.163532 0.724309 + outer loop + vertex 0.831037 1.81299 2.56235 + vertex 0.833719 1.81067 2.56535 + vertex 0.833338 1.81319 2.56443 + endloop + endfacet + facet normal -0.669194 0.172503 0.722788 + outer loop + vertex 0.833338 1.81319 2.56443 + vertex 0.833434 1.81598 2.56385 + vertex 0.831037 1.81299 2.56235 + endloop + endfacet + facet normal -0.669834 0.173424 0.721974 + outer loop + vertex 0.831037 1.81299 2.56235 + vertex 0.833434 1.81598 2.56385 + vertex 0.83111 1.81806 2.5612 + endloop + endfacet + facet normal -0.672486 0.172929 0.719624 + outer loop + vertex 0.83111 1.81806 2.5612 + vertex 0.828499 1.81587 2.55928 + vertex 0.831037 1.81299 2.56235 + endloop + endfacet + facet normal -0.670388 0.176051 0.720823 + outer loop + vertex 0.828499 1.81587 2.55928 + vertex 0.828472 1.81284 2.56 + vertex 0.831037 1.81299 2.56235 + endloop + endfacet + facet normal -0.674816 0.175164 0.716897 + outer loop + vertex 0.828472 1.81284 2.56 + vertex 0.828499 1.81587 2.55928 + vertex 0.825819 1.81248 2.55759 + endloop + endfacet + facet normal -0.674964 0.171891 0.71755 + outer loop + vertex 0.825819 1.81248 2.55759 + vertex 0.828592 1.80994 2.5608 + vertex 0.828472 1.81284 2.56 + endloop + endfacet + facet normal -0.674518 0.178138 0.716444 + outer loop + vertex 0.828639 1.82058 2.55824 + vertex 0.828499 1.81587 2.55928 + vertex 0.83111 1.81806 2.5612 + endloop + endfacet + facet normal -0.675446 0.176638 0.715941 + outer loop + vertex 0.831233 1.82279 2.56015 + vertex 0.828639 1.82058 2.55824 + vertex 0.83111 1.81806 2.5612 + endloop + endfacet + facet normal -0.670033 0.177571 0.72078 + outer loop + vertex 0.83111 1.81806 2.5612 + vertex 0.833736 1.82043 2.56306 + vertex 0.831233 1.82279 2.56015 + endloop + endfacet + facet normal -0.670532 0.176728 0.720524 + outer loop + vertex 0.833736 1.82043 2.56306 + vertex 0.833806 1.82504 2.56199 + vertex 0.831233 1.82279 2.56015 + endloop + endfacet + facet normal -0.672081 0.18043 0.718158 + outer loop + vertex 0.831233 1.82279 2.56015 + vertex 0.833806 1.82504 2.56199 + vertex 0.831149 1.82748 2.55889 + endloop + endfacet + facet normal -0.679301 0.178594 0.711796 + outer loop + vertex 0.831149 1.82748 2.55889 + vertex 0.828686 1.82528 2.55709 + vertex 0.831233 1.82279 2.56015 + endloop + endfacet + facet normal -0.681241 0.183259 0.70875 + outer loop + vertex 0.828537 1.82979 2.55578 + vertex 0.828686 1.82528 2.55709 + vertex 0.831149 1.82748 2.55889 + endloop + endfacet + facet normal -0.683499 0.179185 0.707617 + outer loop + vertex 0.830972 1.83269 2.5574 + vertex 0.828537 1.82979 2.55578 + vertex 0.831149 1.82748 2.55889 + endloop + endfacet + facet normal -0.675053 0.181604 0.715069 + outer loop + vertex 0.830972 1.83269 2.5574 + vertex 0.831149 1.82748 2.55889 + vertex 0.83362 1.82955 2.5607 + endloop + endfacet + facet normal -0.678455 0.17665 0.713087 + outer loop + vertex 0.830972 1.83269 2.5574 + vertex 0.83362 1.82955 2.5607 + vertex 0.833493 1.83256 2.55983 + endloop + endfacet + facet normal -0.677515 0.182826 0.712424 + outer loop + vertex 0.833493 1.83256 2.55983 + vertex 0.833619 1.83584 2.55911 + vertex 0.830972 1.83269 2.5574 + endloop + endfacet + facet normal -0.678 0.18359 0.711766 + outer loop + vertex 0.830972 1.83269 2.5574 + vertex 0.833619 1.83584 2.55911 + vertex 0.831119 1.83823 2.55611 + endloop + endfacet + facet normal -0.68684 0.18194 0.703668 + outer loop + vertex 0.831119 1.83823 2.55611 + vertex 0.828427 1.83581 2.55411 + vertex 0.830972 1.83269 2.5574 + endloop + endfacet + facet normal -0.684429 0.185418 0.705108 + outer loop + vertex 0.828427 1.83581 2.55411 + vertex 0.828406 1.83275 2.55489 + vertex 0.830972 1.83269 2.5574 + endloop + endfacet + facet normal -0.697101 0.182497 0.693358 + outer loop + vertex 0.828406 1.83275 2.55489 + vertex 0.828427 1.83581 2.55411 + vertex 0.825965 1.83281 2.55242 + endloop + endfacet + facet normal -0.697817 0.177504 0.693933 + outer loop + vertex 0.825965 1.83281 2.55242 + vertex 0.828537 1.82979 2.55578 + vertex 0.828406 1.83275 2.55489 + endloop + endfacet + facet normal -0.691641 0.186879 0.697646 + outer loop + vertex 0.825965 1.83281 2.55242 + vertex 0.82613 1.82774 2.55395 + vertex 0.828537 1.82979 2.55578 + endloop + endfacet + facet normal -0.698387 0.184801 0.691451 + outer loop + vertex 0.825965 1.83281 2.55242 + vertex 0.823587 1.82988 2.5508 + vertex 0.82613 1.82774 2.55395 + endloop + endfacet + facet normal -0.694325 0.192533 0.693429 + outer loop + vertex 0.823587 1.82988 2.5508 + vertex 0.823659 1.82537 2.55213 + vertex 0.82613 1.82774 2.55395 + endloop + endfacet + facet normal -0.691428 0.185887 0.698121 + outer loop + vertex 0.82613 1.82774 2.55395 + vertex 0.823659 1.82537 2.55213 + vertex 0.826139 1.82303 2.55521 + endloop + endfacet + facet normal -0.685644 0.187319 0.703423 + outer loop + vertex 0.826139 1.82303 2.55521 + vertex 0.828686 1.82528 2.55709 + vertex 0.82613 1.82774 2.55395 + endloop + endfacet + facet normal -0.682919 0.180542 0.707833 + outer loop + vertex 0.828639 1.82058 2.55824 + vertex 0.828686 1.82528 2.55709 + vertex 0.826139 1.82303 2.55521 + endloop + endfacet + facet normal -0.681214 0.183402 0.708739 + outer loop + vertex 0.825882 1.81807 2.55624 + vertex 0.828639 1.82058 2.55824 + vertex 0.826139 1.82303 2.55521 + endloop + endfacet + facet normal -0.68507 0.182853 0.705155 + outer loop + vertex 0.826139 1.82303 2.55521 + vertex 0.823412 1.82063 2.55318 + vertex 0.825882 1.81807 2.55624 + endloop + endfacet + facet normal -0.683837 0.184856 0.70583 + outer loop + vertex 0.823412 1.82063 2.55318 + vertex 0.822539 1.81534 2.55372 + vertex 0.825882 1.81807 2.55624 + endloop + endfacet + facet normal -0.681536 0.178483 0.709685 + outer loop + vertex 0.825882 1.81807 2.55624 + vertex 0.822539 1.81534 2.55372 + vertex 0.825819 1.81248 2.55759 + endloop + endfacet + facet normal -0.677672 0.17928 0.713175 + outer loop + vertex 0.825819 1.81248 2.55759 + vertex 0.828499 1.81587 2.55928 + vertex 0.825882 1.81807 2.55624 + endloop + endfacet + facet normal -0.678513 0.183968 0.711179 + outer loop + vertex 0.822539 1.81534 2.55372 + vertex 0.822276 1.81047 2.55473 + vertex 0.825819 1.81248 2.55759 + endloop + endfacet + facet normal -0.6787 0.184892 0.710761 + outer loop + vertex 0.825819 1.81248 2.55759 + vertex 0.822276 1.81047 2.55473 + vertex 0.824057 1.8088 2.55686 + endloop + endfacet + facet normal -0.671256 0.179676 0.719119 + outer loop + vertex 0.825819 1.81248 2.55759 + vertex 0.824057 1.8088 2.55686 + vertex 0.826196 1.80766 2.55915 + endloop + endfacet + facet normal -0.669458 0.184128 0.719669 + outer loop + vertex 0.824057 1.8088 2.55686 + vertex 0.823847 1.80533 2.55756 + vertex 0.826196 1.80766 2.55915 + endloop + endfacet + facet normal -0.667631 0.1805 0.72228 + outer loop + vertex 0.826196 1.80766 2.55915 + vertex 0.823847 1.80533 2.55756 + vertex 0.826094 1.80311 2.56019 + endloop + endfacet + facet normal -0.676407 0.183288 0.713357 + outer loop + vertex 0.824057 1.8088 2.55686 + vertex 0.822157 1.80711 2.5555 + vertex 0.823847 1.80533 2.55756 + endloop + endfacet + facet normal -0.676159 0.183679 0.713492 + outer loop + vertex 0.821279 1.80338 2.55563 + vertex 0.823847 1.80533 2.55756 + vertex 0.822157 1.80711 2.5555 + endloop + endfacet + facet normal -0.689276 0.186296 0.700137 + outer loop + vertex 0.822157 1.80711 2.5555 + vertex 0.819464 1.80667 2.55296 + vertex 0.821279 1.80338 2.55563 + endloop + endfacet + facet normal -0.694449 0.180533 0.696527 + outer loop + vertex 0.819464 1.80667 2.55296 + vertex 0.818484 1.80109 2.55343 + vertex 0.821279 1.80338 2.55563 + endloop + endfacet + facet normal -0.69317 0.176845 0.698742 + outer loop + vertex 0.821279 1.80338 2.55563 + vertex 0.818484 1.80109 2.55343 + vertex 0.82077 1.79837 2.55639 + endloop + endfacet + facet normal -0.67965 0.177448 0.71175 + outer loop + vertex 0.82077 1.79837 2.55639 + vertex 0.823432 1.80081 2.55832 + vertex 0.821279 1.80338 2.55563 + endloop + endfacet + facet normal -0.702536 0.16254 0.692837 + outer loop + vertex 0.818484 1.80109 2.55343 + vertex 0.818126 1.79587 2.55429 + vertex 0.82077 1.79837 2.55639 + endloop + endfacet + facet normal -0.698736 0.153625 0.69869 + outer loop + vertex 0.82077 1.79837 2.55639 + vertex 0.818126 1.79587 2.55429 + vertex 0.820855 1.79272 2.55771 + endloop + endfacet + facet normal -0.690861 0.155478 0.706072 + outer loop + vertex 0.820855 1.79272 2.55771 + vertex 0.823212 1.79596 2.55931 + vertex 0.82077 1.79837 2.55639 + endloop + endfacet + facet normal -0.6947 0.160704 0.701118 + outer loop + vertex 0.82325 1.79281 2.56007 + vertex 0.823212 1.79596 2.55931 + vertex 0.820855 1.79272 2.55771 + endloop + endfacet + facet normal -0.698109 0.117615 0.706266 + outer loop + vertex 0.820855 1.79272 2.55771 + vertex 0.823574 1.7899 2.56087 + vertex 0.82325 1.79281 2.56007 + endloop + endfacet + facet normal -0.70365 0.107858 0.702313 + outer loop + vertex 0.820855 1.79272 2.55771 + vertex 0.821455 1.78768 2.55909 + vertex 0.823574 1.7899 2.56087 + endloop + endfacet + facet normal -0.69521 0.0911718 0.713001 + outer loop + vertex 0.823574 1.7899 2.56087 + vertex 0.821455 1.78768 2.55909 + vertex 0.824078 1.78551 2.56192 + endloop + endfacet + facet normal -0.708896 0.137363 0.691808 + outer loop + vertex 0.818126 1.79587 2.55429 + vertex 0.818121 1.79183 2.55509 + vertex 0.820855 1.79272 2.55771 + endloop + endfacet + facet normal -0.689357 0.184484 0.700537 + outer loop + vertex 0.822157 1.80711 2.5555 + vertex 0.822276 1.81047 2.55473 + vertex 0.819464 1.80667 2.55296 + endloop + endfacet + facet normal -0.688275 0.183008 0.701987 + outer loop + vertex 0.819464 1.80667 2.55296 + vertex 0.822276 1.81047 2.55473 + vertex 0.819691 1.8117 2.55187 + endloop + endfacet + facet normal -0.675901 0.182898 0.713937 + outer loop + vertex 0.823432 1.80081 2.55832 + vertex 0.823847 1.80533 2.55756 + vertex 0.821279 1.80338 2.55563 + endloop + endfacet + facet normal -0.677752 0.186518 0.711241 + outer loop + vertex 0.822157 1.80711 2.5555 + vertex 0.824057 1.8088 2.55686 + vertex 0.822276 1.81047 2.55473 + endloop + endfacet + facet normal -0.688428 0.182591 0.701946 + outer loop + vertex 0.819691 1.8117 2.55187 + vertex 0.822276 1.81047 2.55473 + vertex 0.822539 1.81534 2.55372 + endloop + endfacet + facet normal -0.687334 0.180982 0.703433 + outer loop + vertex 0.819837 1.8152 2.55112 + vertex 0.819691 1.8117 2.55187 + vertex 0.822539 1.81534 2.55372 + endloop + endfacet + facet normal -0.686852 0.185681 0.702678 + outer loop + vertex 0.819837 1.8152 2.55112 + vertex 0.822539 1.81534 2.55372 + vertex 0.820728 1.81861 2.55109 + endloop + endfacet + facet normal -0.694105 0.187506 0.695025 + outer loop + vertex 0.820728 1.81861 2.55109 + vertex 0.818596 1.81703 2.54938 + vertex 0.819837 1.8152 2.55112 + endloop + endfacet + facet normal -0.698902 0.179083 0.692434 + outer loop + vertex 0.819837 1.8152 2.55112 + vertex 0.817625 1.81371 2.54927 + vertex 0.819691 1.8117 2.55187 + endloop + endfacet + facet normal -0.701078 0.175262 0.691211 + outer loop + vertex 0.81654 1.80896 2.54937 + vertex 0.819691 1.8117 2.55187 + vertex 0.817625 1.81371 2.54927 + endloop + endfacet + facet normal -0.687392 0.185084 0.702308 + outer loop + vertex 0.822539 1.81534 2.55372 + vertex 0.823412 1.82063 2.55318 + vertex 0.820728 1.81861 2.55109 + endloop + endfacet + facet normal -0.689932 0.193402 0.697559 + outer loop + vertex 0.820728 1.81861 2.55109 + vertex 0.823412 1.82063 2.55318 + vertex 0.821117 1.82304 2.55024 + endloop + endfacet + facet normal -0.694346 0.192976 0.693285 + outer loop + vertex 0.821117 1.82304 2.55024 + vertex 0.818622 1.82065 2.54841 + vertex 0.820728 1.81861 2.55109 + endloop + endfacet + facet normal -0.695864 0.196491 0.690771 + outer loop + vertex 0.818723 1.82525 2.5472 + vertex 0.818622 1.82065 2.54841 + vertex 0.821117 1.82304 2.55024 + endloop + endfacet + facet normal -0.695605 0.19695 0.690901 + outer loop + vertex 0.821169 1.82769 2.54897 + vertex 0.818723 1.82525 2.5472 + vertex 0.821117 1.82304 2.55024 + endloop + endfacet + facet normal -0.694304 0.197269 0.692118 + outer loop + vertex 0.821117 1.82304 2.55024 + vertex 0.823659 1.82537 2.55213 + vertex 0.821169 1.82769 2.54897 + endloop + endfacet + facet normal -0.697548 0.201191 0.687713 + outer loop + vertex 0.818657 1.82977 2.54581 + vertex 0.818723 1.82525 2.5472 + vertex 0.821169 1.82769 2.54897 + endloop + endfacet + facet normal -0.700359 0.195807 0.686409 + outer loop + vertex 0.821034 1.83282 2.54737 + vertex 0.818657 1.82977 2.54581 + vertex 0.821169 1.82769 2.54897 + endloop + endfacet + facet normal -0.699265 0.196152 0.687425 + outer loop + vertex 0.821034 1.83282 2.54737 + vertex 0.821169 1.82769 2.54897 + vertex 0.823587 1.82988 2.5508 + endloop + endfacet + facet normal -0.703834 0.189063 0.684743 + outer loop + vertex 0.821034 1.83282 2.54737 + vertex 0.823587 1.82988 2.5508 + vertex 0.823484 1.83281 2.54989 + endloop + endfacet + facet normal -0.691611 0.190689 0.696644 + outer loop + vertex 0.823412 1.82063 2.55318 + vertex 0.823659 1.82537 2.55213 + vertex 0.821117 1.82304 2.55024 + endloop + endfacet + facet normal -0.688373 0.191199 0.699704 + outer loop + vertex 0.823659 1.82537 2.55213 + vertex 0.823412 1.82063 2.55318 + vertex 0.826139 1.82303 2.55521 + endloop + endfacet + facet normal -0.6975 0.191619 0.690489 + outer loop + vertex 0.823587 1.82988 2.5508 + vertex 0.821169 1.82769 2.54897 + vertex 0.823659 1.82537 2.55213 + endloop + endfacet + facet normal -0.701509 0.189823 0.686915 + outer loop + vertex 0.825965 1.83281 2.55242 + vertex 0.823484 1.83281 2.54989 + vertex 0.823587 1.82988 2.5508 + endloop + endfacet + facet normal -0.701707 0.188375 0.687112 + outer loop + vertex 0.823472 1.83584 2.54905 + vertex 0.823484 1.83281 2.54989 + vertex 0.825965 1.83281 2.55242 + endloop + endfacet + facet normal -0.705113 0.183229 0.685013 + outer loop + vertex 0.825994 1.83803 2.55106 + vertex 0.823472 1.83584 2.54905 + vertex 0.825965 1.83281 2.55242 + endloop + endfacet + facet normal -0.698535 0.184836 0.691292 + outer loop + vertex 0.825965 1.83281 2.55242 + vertex 0.828427 1.83581 2.55411 + vertex 0.825994 1.83803 2.55106 + endloop + endfacet + facet normal -0.699128 0.183756 0.69098 + outer loop + vertex 0.828427 1.83581 2.55411 + vertex 0.82859 1.84053 2.55302 + vertex 0.825994 1.83803 2.55106 + endloop + endfacet + facet normal -0.700142 0.186113 0.689321 + outer loop + vertex 0.825994 1.83803 2.55106 + vertex 0.82859 1.84053 2.55302 + vertex 0.826218 1.84277 2.55 + endloop + endfacet + facet normal -0.707465 0.184864 0.682143 + outer loop + vertex 0.826218 1.84277 2.55 + vertex 0.823601 1.8406 2.54788 + vertex 0.825994 1.83803 2.55106 + endloop + endfacet + facet normal -0.707968 0.186383 0.681207 + outer loop + vertex 0.824027 1.84523 2.54705 + vertex 0.823601 1.8406 2.54788 + vertex 0.826218 1.84277 2.55 + endloop + endfacet + facet normal -0.707591 0.186988 0.681432 + outer loop + vertex 0.826444 1.84728 2.549 + vertex 0.824027 1.84523 2.54705 + vertex 0.826218 1.84277 2.55 + endloop + endfacet + facet normal -0.700259 0.188222 0.688629 + outer loop + vertex 0.826218 1.84277 2.55 + vertex 0.828778 1.84518 2.55195 + vertex 0.826444 1.84728 2.549 + endloop + endfacet + facet normal -0.699017 0.190496 0.689265 + outer loop + vertex 0.828815 1.84959 2.55077 + vertex 0.826444 1.84728 2.549 + vertex 0.828778 1.84518 2.55195 + endloop + endfacet + facet normal -0.707488 0.186685 0.681623 + outer loop + vertex 0.824532 1.8489 2.54657 + vertex 0.824027 1.84523 2.54705 + vertex 0.826444 1.84728 2.549 + endloop + endfacet + facet normal -0.705716 0.190113 0.682512 + outer loop + vertex 0.826298 1.8523 2.54745 + vertex 0.824532 1.8489 2.54657 + vertex 0.826444 1.84728 2.549 + endloop + endfacet + facet normal -0.707345 0.191499 0.680435 + outer loop + vertex 0.826298 1.8523 2.54745 + vertex 0.823541 1.8515 2.54481 + vertex 0.824532 1.8489 2.54657 + endloop + endfacet + facet normal -0.711731 0.18748 0.676972 + outer loop + vertex 0.823541 1.8515 2.54481 + vertex 0.822319 1.84831 2.54441 + vertex 0.824532 1.8489 2.54657 + endloop + endfacet + facet normal -0.716149 0.189849 0.671631 + outer loop + vertex 0.823541 1.8515 2.54481 + vertex 0.820991 1.85252 2.5418 + vertex 0.822319 1.84831 2.54441 + endloop + endfacet + facet normal -0.715481 0.190403 0.672185 + outer loop + vertex 0.820991 1.85252 2.5418 + vertex 0.819776 1.84806 2.54177 + vertex 0.822319 1.84831 2.54441 + endloop + endfacet + facet normal -0.726112 0.193385 0.659821 + outer loop + vertex 0.820991 1.85252 2.5418 + vertex 0.818187 1.8508 2.53922 + vertex 0.819776 1.84806 2.54177 + endloop + endfacet + facet normal -0.707359 0.193036 0.679985 + outer loop + vertex 0.823579 1.85542 2.54374 + vertex 0.823541 1.8515 2.54481 + vertex 0.826298 1.8523 2.54745 + endloop + endfacet + facet normal -0.711732 0.186686 0.67719 + outer loop + vertex 0.824532 1.8489 2.54657 + vertex 0.822319 1.84831 2.54441 + vertex 0.824027 1.84523 2.54705 + endloop + endfacet + facet normal -0.711941 0.18644 0.677038 + outer loop + vertex 0.821042 1.84371 2.54433 + vertex 0.824027 1.84523 2.54705 + vertex 0.822319 1.84831 2.54441 + endloop + endfacet + facet normal -0.699706 0.186888 0.689554 + outer loop + vertex 0.82859 1.84053 2.55302 + vertex 0.828778 1.84518 2.55195 + vertex 0.826218 1.84277 2.55 + endloop + endfacet + facet normal -0.688638 0.188862 0.700078 + outer loop + vertex 0.828778 1.84518 2.55195 + vertex 0.82859 1.84053 2.55302 + vertex 0.831347 1.84327 2.55499 + endloop + endfacet + facet normal -0.687461 0.191248 0.700587 + outer loop + vertex 0.831377 1.84793 2.55375 + vertex 0.828778 1.84518 2.55195 + vertex 0.831347 1.84327 2.55499 + endloop + endfacet + facet normal -0.676453 0.193825 0.710523 + outer loop + vertex 0.831347 1.84327 2.55499 + vertex 0.834201 1.84647 2.55683 + vertex 0.831377 1.84793 2.55375 + endloop + endfacet + facet normal -0.675179 0.191657 0.712321 + outer loop + vertex 0.834312 1.8413 2.55833 + vertex 0.834201 1.84647 2.55683 + vertex 0.831347 1.84327 2.55499 + endloop + endfacet + facet normal -0.67656 0.188697 0.711801 + outer loop + vertex 0.831119 1.83823 2.55611 + vertex 0.834312 1.8413 2.55833 + vertex 0.831347 1.84327 2.55499 + endloop + endfacet + facet normal -0.666133 0.194111 0.72013 + outer loop + vertex 0.834312 1.8413 2.55833 + vertex 0.837062 1.8453 2.5598 + vertex 0.834201 1.84647 2.55683 + endloop + endfacet + facet normal -0.664678 0.198221 0.720355 + outer loop + vertex 0.834201 1.84647 2.55683 + vertex 0.837062 1.8453 2.5598 + vertex 0.837298 1.85038 2.55862 + endloop + endfacet + facet normal -0.665125 0.198842 0.719771 + outer loop + vertex 0.833911 1.85065 2.55541 + vertex 0.834201 1.84647 2.55683 + vertex 0.837298 1.85038 2.55862 + endloop + endfacet + facet normal -0.66543 0.19717 0.719949 + outer loop + vertex 0.833911 1.85065 2.55541 + vertex 0.837298 1.85038 2.55862 + vertex 0.835538 1.8538 2.55605 + endloop + endfacet + facet normal -0.664072 0.198528 0.720829 + outer loop + vertex 0.837298 1.85038 2.55862 + vertex 0.83839 1.85556 2.5582 + vertex 0.835538 1.8538 2.55605 + endloop + endfacet + facet normal -0.665079 0.202694 0.718738 + outer loop + vertex 0.835538 1.8538 2.55605 + vertex 0.83839 1.85556 2.5582 + vertex 0.836027 1.8579 2.55535 + endloop + endfacet + facet normal -0.671201 0.202453 0.713094 + outer loop + vertex 0.836027 1.8579 2.55535 + vertex 0.833569 1.85581 2.55363 + vertex 0.835538 1.8538 2.55605 + endloop + endfacet + facet normal -0.668439 0.197322 0.717115 + outer loop + vertex 0.83839 1.85556 2.5582 + vertex 0.838652 1.86021 2.55716 + vertex 0.836027 1.8579 2.55535 + endloop + endfacet + facet normal -0.670158 0.201448 0.714358 + outer loop + vertex 0.836027 1.8579 2.55535 + vertex 0.838652 1.86021 2.55716 + vertex 0.836015 1.8625 2.55404 + endloop + endfacet + facet normal -0.662716 0.198128 0.722186 + outer loop + vertex 0.838652 1.86021 2.55716 + vertex 0.83839 1.85556 2.5582 + vertex 0.841366 1.85824 2.56019 + endloop + endfacet + facet normal -0.664473 0.194671 0.721511 + outer loop + vertex 0.841253 1.86292 2.55882 + vertex 0.838652 1.86021 2.55716 + vertex 0.841366 1.85824 2.56019 + endloop + endfacet + facet normal -0.657306 0.196601 0.727528 + outer loop + vertex 0.841366 1.85824 2.56019 + vertex 0.844181 1.86135 2.56189 + vertex 0.841253 1.86292 2.55882 + endloop + endfacet + facet normal -0.655666 0.200485 0.727948 + outer loop + vertex 0.843738 1.86563 2.56032 + vertex 0.841253 1.86292 2.55882 + vertex 0.844181 1.86135 2.56189 + endloop + endfacet + facet normal -0.655366 0.193434 0.730123 + outer loop + vertex 0.844388 1.85637 2.5634 + vertex 0.844181 1.86135 2.56189 + vertex 0.841366 1.85824 2.56019 + endloop + endfacet + facet normal -0.654933 0.194376 0.730261 + outer loop + vertex 0.840997 1.85328 2.56118 + vertex 0.844388 1.85637 2.5634 + vertex 0.841366 1.85824 2.56019 + endloop + endfacet + facet normal -0.653574 0.191464 0.732245 + outer loop + vertex 0.84351 1.85144 2.56391 + vertex 0.844388 1.85637 2.5634 + vertex 0.840997 1.85328 2.56118 + endloop + endfacet + facet normal -0.651278 0.19589 0.73312 + outer loop + vertex 0.840747 1.84774 2.56244 + vertex 0.84351 1.85144 2.56391 + vertex 0.840997 1.85328 2.56118 + endloop + endfacet + facet normal -0.657439 0.194971 0.727846 + outer loop + vertex 0.840997 1.85328 2.56118 + vertex 0.837298 1.85038 2.55862 + vertex 0.840747 1.84774 2.56244 + endloop + endfacet + facet normal -0.648785 0.192836 0.736133 + outer loop + vertex 0.843297 1.84859 2.56446 + vertex 0.84351 1.85144 2.56391 + vertex 0.840747 1.84774 2.56244 + endloop + endfacet + facet normal -0.648667 0.191287 0.736641 + outer loop + vertex 0.840747 1.84774 2.56244 + vertex 0.84363 1.84595 2.56544 + vertex 0.843297 1.84859 2.56446 + endloop + endfacet + facet normal -0.64499 0.192801 0.73947 + outer loop + vertex 0.845337 1.84924 2.56607 + vertex 0.843297 1.84859 2.56446 + vertex 0.84363 1.84595 2.56544 + endloop + endfacet + facet normal -0.64142 0.190231 0.743231 + outer loop + vertex 0.84363 1.84595 2.56544 + vertex 0.847137 1.84549 2.56859 + vertex 0.845337 1.84924 2.56607 + endloop + endfacet + facet normal -0.642444 0.189307 0.742583 + outer loop + vertex 0.847137 1.84549 2.56859 + vertex 0.848268 1.85074 2.56823 + vertex 0.845337 1.84924 2.56607 + endloop + endfacet + facet normal -0.642281 0.18848 0.742934 + outer loop + vertex 0.845337 1.84924 2.56607 + vertex 0.848268 1.85074 2.56823 + vertex 0.846246 1.8533 2.56583 + endloop + endfacet + facet normal -0.647804 0.189415 0.737883 + outer loop + vertex 0.846246 1.8533 2.56583 + vertex 0.84351 1.85144 2.56391 + vertex 0.845337 1.84924 2.56607 + endloop + endfacet + facet normal -0.64416 0.186048 0.741919 + outer loop + vertex 0.848268 1.85074 2.56823 + vertex 0.848862 1.85507 2.56766 + vertex 0.846246 1.8533 2.56583 + endloop + endfacet + facet normal -0.644327 0.186585 0.741639 + outer loop + vertex 0.846246 1.8533 2.56583 + vertex 0.848862 1.85507 2.56766 + vertex 0.847128 1.85672 2.56573 + endloop + endfacet + facet normal -0.65097 0.188125 0.735423 + outer loop + vertex 0.847128 1.85672 2.56573 + vertex 0.844388 1.85637 2.5634 + vertex 0.846246 1.8533 2.56583 + endloop + endfacet + facet normal -0.650446 0.197604 0.733398 + outer loop + vertex 0.847128 1.85672 2.56573 + vertex 0.847119 1.8601 2.56482 + vertex 0.844388 1.85637 2.5634 + endloop + endfacet + facet normal -0.644825 0.19887 0.738005 + outer loop + vertex 0.847128 1.85672 2.56573 + vertex 0.849032 1.85846 2.56693 + vertex 0.847119 1.8601 2.56482 + endloop + endfacet + facet normal -0.63046 0.222777 0.743566 + outer loop + vertex 0.850886 1.86252 2.56729 + vertex 0.847119 1.8601 2.56482 + vertex 0.849032 1.85846 2.56693 + endloop + endfacet + facet normal -0.62412 0.219332 0.749912 + outer loop + vertex 0.850886 1.86252 2.56729 + vertex 0.849032 1.85846 2.56693 + vertex 0.851335 1.85777 2.56905 + endloop + endfacet + facet normal -0.632431 0.192563 0.750301 + outer loop + vertex 0.849032 1.85846 2.56693 + vertex 0.848862 1.85507 2.56766 + vertex 0.851335 1.85777 2.56905 + endloop + endfacet + facet normal -0.631526 0.191159 0.751421 + outer loop + vertex 0.851335 1.85777 2.56905 + vertex 0.848862 1.85507 2.56766 + vertex 0.851305 1.85327 2.57017 + endloop + endfacet + facet normal -0.619011 0.193501 0.761172 + outer loop + vertex 0.851305 1.85327 2.57017 + vertex 0.854334 1.85668 2.57176 + vertex 0.851335 1.85777 2.56905 + endloop + endfacet + facet normal -0.620552 0.195718 0.759349 + outer loop + vertex 0.854428 1.85146 2.57319 + vertex 0.854334 1.85668 2.57176 + vertex 0.851305 1.85327 2.57017 + endloop + endfacet + facet normal -0.62386 0.188501 0.758463 + outer loop + vertex 0.850863 1.84818 2.57107 + vertex 0.854428 1.85146 2.57319 + vertex 0.851305 1.85327 2.57017 + endloop + endfacet + facet normal -0.635254 0.187835 0.749113 + outer loop + vertex 0.851305 1.85327 2.57017 + vertex 0.848268 1.85074 2.56823 + vertex 0.850863 1.84818 2.57107 + endloop + endfacet + facet normal -0.625604 0.191865 0.75618 + outer loop + vertex 0.853532 1.84618 2.57379 + vertex 0.854428 1.85146 2.57319 + vertex 0.850863 1.84818 2.57107 + endloop + endfacet + facet normal -0.62627 0.190647 0.755937 + outer loop + vertex 0.850749 1.84251 2.57241 + vertex 0.853532 1.84618 2.57379 + vertex 0.850863 1.84818 2.57107 + endloop + endfacet + facet normal -0.635376 0.189122 0.748685 + outer loop + vertex 0.850863 1.84818 2.57107 + vertex 0.847137 1.84549 2.56859 + vertex 0.850749 1.84251 2.57241 + endloop + endfacet + facet normal -0.633387 0.192568 0.749492 + outer loop + vertex 0.847137 1.84549 2.56859 + vertex 0.847088 1.84033 2.56987 + vertex 0.850749 1.84251 2.57241 + endloop + endfacet + facet normal -0.63385 0.19434 0.748643 + outer loop + vertex 0.850749 1.84251 2.57241 + vertex 0.847088 1.84033 2.56987 + vertex 0.849091 1.83867 2.572 + endloop + endfacet + facet normal -0.627984 0.1912 0.754373 + outer loop + vertex 0.850749 1.84251 2.57241 + vertex 0.849091 1.83867 2.572 + vertex 0.851349 1.83787 2.57408 + endloop + endfacet + facet normal -0.622796 0.193236 0.758146 + outer loop + vertex 0.850749 1.84251 2.57241 + vertex 0.851349 1.83787 2.57408 + vertex 0.853722 1.84071 2.57531 + endloop + endfacet + facet normal -0.6265 0.18537 0.757057 + outer loop + vertex 0.850749 1.84251 2.57241 + vertex 0.853722 1.84071 2.57531 + vertex 0.85334 1.84321 2.57438 + endloop + endfacet + facet normal -0.619778 0.189195 0.76163 + outer loop + vertex 0.853722 1.84071 2.57531 + vertex 0.851349 1.83787 2.57408 + vertex 0.8542 1.83657 2.57672 + endloop + endfacet + facet normal -0.609384 0.192933 0.769043 + outer loop + vertex 0.853722 1.84071 2.57531 + vertex 0.8542 1.83657 2.57672 + vertex 0.857338 1.8407 2.57817 + endloop + endfacet + facet normal -0.610074 0.187274 0.769895 + outer loop + vertex 0.853722 1.84071 2.57531 + vertex 0.857338 1.8407 2.57817 + vertex 0.855571 1.84413 2.57594 + endloop + endfacet + facet normal -0.614432 0.190408 0.765649 + outer loop + vertex 0.855571 1.84413 2.57594 + vertex 0.85334 1.84321 2.57438 + vertex 0.853722 1.84071 2.57531 + endloop + endfacet + facet normal -0.614736 0.192387 0.76491 + outer loop + vertex 0.853532 1.84618 2.57379 + vertex 0.85334 1.84321 2.57438 + vertex 0.855571 1.84413 2.57594 + endloop + endfacet + facet normal -0.61518 0.19174 0.764716 + outer loop + vertex 0.856576 1.84854 2.57564 + vertex 0.853532 1.84618 2.57379 + vertex 0.855571 1.84413 2.57594 + endloop + endfacet + facet normal -0.603884 0.189796 0.774146 + outer loop + vertex 0.855571 1.84413 2.57594 + vertex 0.85925 1.84653 2.57822 + vertex 0.856576 1.84854 2.57564 + endloop + endfacet + facet normal -0.603796 0.189953 0.774176 + outer loop + vertex 0.85925 1.84653 2.57822 + vertex 0.859529 1.85135 2.57726 + vertex 0.856576 1.84854 2.57564 + endloop + endfacet + facet normal -0.603891 0.190119 0.774061 + outer loop + vertex 0.856576 1.84854 2.57564 + vertex 0.859529 1.85135 2.57726 + vertex 0.857424 1.85232 2.57538 + endloop + endfacet + facet normal -0.614242 0.19183 0.765446 + outer loop + vertex 0.857424 1.85232 2.57538 + vertex 0.854428 1.85146 2.57319 + vertex 0.856576 1.84854 2.57564 + endloop + endfacet + facet normal -0.614798 0.200909 0.762666 + outer loop + vertex 0.857424 1.85232 2.57538 + vertex 0.857309 1.85579 2.57437 + vertex 0.854428 1.85146 2.57319 + endloop + endfacet + facet normal -0.607776 0.202636 0.767819 + outer loop + vertex 0.857424 1.85232 2.57538 + vertex 0.859406 1.85469 2.57632 + vertex 0.857309 1.85579 2.57437 + endloop + endfacet + facet normal -0.60465 0.192073 0.772985 + outer loop + vertex 0.857338 1.8407 2.57817 + vertex 0.85925 1.84653 2.57822 + vertex 0.855571 1.84413 2.57594 + endloop + endfacet + facet normal -0.596496 0.189347 0.779962 + outer loop + vertex 0.85925 1.84653 2.57822 + vertex 0.857338 1.8407 2.57817 + vertex 0.861336 1.84349 2.58056 + endloop + endfacet + facet normal -0.596102 0.189769 0.78016 + outer loop + vertex 0.862342 1.84738 2.58038 + vertex 0.85925 1.84653 2.57822 + vertex 0.861336 1.84349 2.58056 + endloop + endfacet + facet normal -0.588294 0.188039 0.78648 + outer loop + vertex 0.861336 1.84349 2.58056 + vertex 0.864516 1.84643 2.58223 + vertex 0.862342 1.84738 2.58038 + endloop + endfacet + facet normal -0.58857 0.187333 0.786443 + outer loop + vertex 0.864379 1.84978 2.58133 + vertex 0.862342 1.84738 2.58038 + vertex 0.864516 1.84643 2.58223 + endloop + endfacet + facet normal -0.582127 0.188789 0.790877 + outer loop + vertex 0.864379 1.84978 2.58133 + vertex 0.864516 1.84643 2.58223 + vertex 0.867473 1.85059 2.58341 + endloop + endfacet + facet normal -0.582441 0.193452 0.789518 + outer loop + vertex 0.864379 1.84978 2.58133 + vertex 0.867473 1.85059 2.58341 + vertex 0.865292 1.85364 2.58106 + endloop + endfacet + facet normal -0.581036 0.187713 0.791935 + outer loop + vertex 0.864516 1.84643 2.58223 + vertex 0.867241 1.84571 2.5844 + vertex 0.867473 1.85059 2.58341 + endloop + endfacet + facet normal -0.591435 0.190966 0.783413 + outer loop + vertex 0.862342 1.84738 2.58038 + vertex 0.864379 1.84978 2.58133 + vertex 0.862203 1.85071 2.57946 + endloop + endfacet + facet normal -0.588104 0.187707 0.786702 + outer loop + vertex 0.86426 1.84153 2.58321 + vertex 0.864516 1.84643 2.58223 + vertex 0.861336 1.84349 2.58056 + endloop + endfacet + facet normal -0.586019 0.191649 0.787307 + outer loop + vertex 0.860322 1.83854 2.581 + vertex 0.86426 1.84153 2.58321 + vertex 0.861336 1.84349 2.58056 + endloop + endfacet + facet normal -0.586252 0.192177 0.787005 + outer loop + vertex 0.862518 1.83553 2.58338 + vertex 0.86426 1.84153 2.58321 + vertex 0.860322 1.83854 2.581 + endloop + endfacet + facet normal -0.585168 0.193371 0.787519 + outer loop + vertex 0.859365 1.83458 2.58127 + vertex 0.862518 1.83553 2.58338 + vertex 0.860322 1.83854 2.581 + endloop + endfacet + facet normal -0.597961 0.195781 0.777247 + outer loop + vertex 0.860322 1.83854 2.581 + vertex 0.857145 1.83561 2.5793 + vertex 0.859365 1.83458 2.58127 + endloop + endfacet + facet normal -0.599494 0.192003 0.777008 + outer loop + vertex 0.857379 1.83219 2.58032 + vertex 0.859365 1.83458 2.58127 + vertex 0.857145 1.83561 2.5793 + endloop + endfacet + facet normal -0.610728 0.188832 0.768995 + outer loop + vertex 0.857379 1.83219 2.58032 + vertex 0.857145 1.83561 2.5793 + vertex 0.854415 1.83147 2.57815 + endloop + endfacet + facet normal -0.610452 0.182096 0.770837 + outer loop + vertex 0.857379 1.83219 2.58032 + vertex 0.854415 1.83147 2.57815 + vertex 0.856596 1.82847 2.58058 + endloop + endfacet + facet normal -0.596785 0.18 0.781951 + outer loop + vertex 0.856596 1.82847 2.58058 + vertex 0.859548 1.83124 2.5822 + vertex 0.857379 1.83219 2.58032 + endloop + endfacet + facet normal -0.595923 0.178502 0.782951 + outer loop + vertex 0.859328 1.82645 2.58312 + vertex 0.859548 1.83124 2.5822 + vertex 0.856596 1.82847 2.58058 + endloop + endfacet + facet normal -0.597366 0.17591 0.782438 + outer loop + vertex 0.85566 1.82407 2.58086 + vertex 0.859328 1.82645 2.58312 + vertex 0.856596 1.82847 2.58058 + endloop + endfacet + facet normal -0.608115 0.177658 0.773715 + outer loop + vertex 0.856596 1.82847 2.58058 + vertex 0.853571 1.82621 2.57872 + vertex 0.85566 1.82407 2.58086 + endloop + endfacet + facet normal -0.607007 0.179241 0.774219 + outer loop + vertex 0.853571 1.82621 2.57872 + vertex 0.853404 1.82319 2.57929 + vertex 0.85566 1.82407 2.58086 + endloop + endfacet + facet normal -0.606017 0.172672 0.776484 + outer loop + vertex 0.85566 1.82407 2.58086 + vertex 0.853404 1.82319 2.57929 + vertex 0.853838 1.82063 2.5802 + endloop + endfacet + facet normal -0.601705 0.16962 0.7805 + outer loop + vertex 0.853838 1.82063 2.5802 + vertex 0.857544 1.82061 2.58306 + vertex 0.85566 1.82407 2.58086 + endloop + endfacet + facet normal -0.601318 0.173146 0.780024 + outer loop + vertex 0.853838 1.82063 2.5802 + vertex 0.854364 1.81651 2.58152 + vertex 0.857544 1.82061 2.58306 + endloop + endfacet + facet normal -0.599965 0.171575 0.781412 + outer loop + vertex 0.854364 1.81651 2.58152 + vertex 0.857406 1.81534 2.58411 + vertex 0.857544 1.82061 2.58306 + endloop + endfacet + facet normal -0.590406 0.172721 0.788409 + outer loop + vertex 0.857544 1.82061 2.58306 + vertex 0.857406 1.81534 2.58411 + vertex 0.86079 1.81866 2.58592 + endloop + endfacet + facet normal -0.590721 0.172061 0.788317 + outer loop + vertex 0.861471 1.82353 2.58537 + vertex 0.857544 1.82061 2.58306 + vertex 0.86079 1.81866 2.58592 + endloop + endfacet + facet normal -0.578992 0.171417 0.79711 + outer loop + vertex 0.86079 1.81866 2.58592 + vertex 0.864191 1.82201 2.58767 + vertex 0.861471 1.82353 2.58537 + endloop + endfacet + facet normal -0.577686 0.174266 0.79744 + outer loop + vertex 0.864191 1.82201 2.58767 + vertex 0.864594 1.82644 2.58699 + vertex 0.861471 1.82353 2.58537 + endloop + endfacet + facet normal -0.576425 0.172153 0.79881 + outer loop + vertex 0.861471 1.82353 2.58537 + vertex 0.864594 1.82644 2.58699 + vertex 0.862415 1.82732 2.58523 + endloop + endfacet + facet normal -0.588497 0.174817 0.789373 + outer loop + vertex 0.862415 1.82732 2.58523 + vertex 0.859328 1.82645 2.58312 + vertex 0.861471 1.82353 2.58537 + endloop + endfacet + facet normal -0.589063 0.181386 0.787467 + outer loop + vertex 0.862415 1.82732 2.58523 + vertex 0.862274 1.83063 2.58436 + vertex 0.859328 1.82645 2.58312 + endloop + endfacet + facet normal -0.578516 0.183734 0.794708 + outer loop + vertex 0.862415 1.82732 2.58523 + vertex 0.86447 1.82973 2.58617 + vertex 0.862274 1.83063 2.58436 + endloop + endfacet + facet normal -0.574164 0.178308 0.799088 + outer loop + vertex 0.86447 1.82973 2.58617 + vertex 0.862415 1.82732 2.58523 + vertex 0.864594 1.82644 2.58699 + endloop + endfacet + facet normal -0.579213 0.171765 0.796875 + outer loop + vertex 0.863944 1.8169 2.58859 + vertex 0.864191 1.82201 2.58767 + vertex 0.86079 1.81866 2.58592 + endloop + endfacet + facet normal -0.579071 0.172074 0.796911 + outer loop + vertex 0.860143 1.81381 2.5865 + vertex 0.863944 1.8169 2.58859 + vertex 0.86079 1.81866 2.58592 + endloop + endfacet + facet normal -0.579075 0.172082 0.796906 + outer loop + vertex 0.862308 1.81094 2.58869 + vertex 0.863944 1.8169 2.58859 + vertex 0.860143 1.81381 2.5865 + endloop + endfacet + facet normal -0.580174 0.170846 0.796373 + outer loop + vertex 0.859244 1.81006 2.58665 + vertex 0.862308 1.81094 2.58869 + vertex 0.860143 1.81381 2.5865 + endloop + endfacet + facet normal -0.5917 0.173248 0.787323 + outer loop + vertex 0.860143 1.81381 2.5865 + vertex 0.857115 1.81092 2.58486 + vertex 0.859244 1.81006 2.58665 + endloop + endfacet + facet normal -0.593132 0.16927 0.78711 + outer loop + vertex 0.857254 1.80768 2.58566 + vertex 0.859244 1.81006 2.58665 + vertex 0.857115 1.81092 2.58486 + endloop + endfacet + facet normal -0.601028 0.167536 0.781471 + outer loop + vertex 0.857254 1.80768 2.58566 + vertex 0.857115 1.81092 2.58486 + vertex 0.854159 1.80674 2.58348 + endloop + endfacet + facet normal -0.600694 0.164208 0.782434 + outer loop + vertex 0.857254 1.80768 2.58566 + vertex 0.854159 1.80674 2.58348 + vertex 0.856305 1.80375 2.58575 + endloop + endfacet + facet normal -0.590753 0.162002 0.790421 + outer loop + vertex 0.856305 1.80375 2.58575 + vertex 0.859393 1.80675 2.58745 + vertex 0.857254 1.80768 2.58566 + endloop + endfacet + facet normal -0.590496 0.16158 0.7907 + outer loop + vertex 0.859178 1.80178 2.5883 + vertex 0.859393 1.80675 2.58745 + vertex 0.856305 1.80375 2.58575 + endloop + endfacet + facet normal -0.589856 0.162807 0.790926 + outer loop + vertex 0.855332 1.79873 2.58606 + vertex 0.859178 1.80178 2.5883 + vertex 0.856305 1.80375 2.58575 + endloop + endfacet + facet normal -0.599238 0.164174 0.783556 + outer loop + vertex 0.856305 1.80375 2.58575 + vertex 0.852497 1.80067 2.58349 + vertex 0.855332 1.79873 2.58606 + endloop + endfacet + facet normal -0.597514 0.167505 0.784168 + outer loop + vertex 0.852497 1.80067 2.58349 + vertex 0.852252 1.79572 2.58436 + vertex 0.855332 1.79873 2.58606 + endloop + endfacet + facet normal -0.597465 0.167424 0.784222 + outer loop + vertex 0.855332 1.79873 2.58606 + vertex 0.852252 1.79572 2.58436 + vertex 0.854365 1.79475 2.58618 + endloop + endfacet + facet normal -0.588821 0.165522 0.791134 + outer loop + vertex 0.854365 1.79475 2.58618 + vertex 0.857496 1.79568 2.58831 + vertex 0.855332 1.79873 2.58606 + endloop + endfacet + facet normal -0.588887 0.166166 0.790949 + outer loop + vertex 0.854365 1.79475 2.58618 + vertex 0.85457 1.79135 2.58704 + vertex 0.857496 1.79568 2.58831 + endloop + endfacet + facet normal -0.587683 0.165019 0.792084 + outer loop + vertex 0.85457 1.79135 2.58704 + vertex 0.857336 1.7907 2.58923 + vertex 0.857496 1.79568 2.58831 + endloop + endfacet + facet normal -0.577466 0.166033 0.799354 + outer loop + vertex 0.857496 1.79568 2.58831 + vertex 0.857336 1.7907 2.58923 + vertex 0.860521 1.79386 2.59087 + endloop + endfacet + facet normal -0.579676 0.161437 0.798695 + outer loop + vertex 0.861341 1.79877 2.59048 + vertex 0.857496 1.79568 2.58831 + vertex 0.860521 1.79386 2.59087 + endloop + endfacet + facet normal -0.565969 0.159966 0.808758 + outer loop + vertex 0.860521 1.79386 2.59087 + vertex 0.864003 1.79702 2.59269 + vertex 0.861341 1.79877 2.59048 + endloop + endfacet + facet normal -0.567927 0.156192 0.808123 + outer loop + vertex 0.864003 1.79702 2.59269 + vertex 0.864483 1.80164 2.59213 + vertex 0.861341 1.79877 2.59048 + endloop + endfacet + facet normal -0.56749 0.155453 0.808572 + outer loop + vertex 0.861341 1.79877 2.59048 + vertex 0.864483 1.80164 2.59213 + vertex 0.862294 1.80266 2.5904 + endloop + endfacet + facet normal -0.581403 0.158653 0.797997 + outer loop + vertex 0.862294 1.80266 2.5904 + vertex 0.859178 1.80178 2.5883 + vertex 0.861341 1.79877 2.59048 + endloop + endfacet + facet normal -0.581723 0.161895 0.797113 + outer loop + vertex 0.862294 1.80266 2.5904 + vertex 0.862114 1.80604 2.58958 + vertex 0.859178 1.80178 2.5883 + endloop + endfacet + facet normal -0.571946 0.164017 0.803726 + outer loop + vertex 0.862294 1.80266 2.5904 + vertex 0.864328 1.80501 2.59137 + vertex 0.862114 1.80604 2.58958 + endloop + endfacet + facet normal -0.566704 0.157423 0.808743 + outer loop + vertex 0.864328 1.80501 2.59137 + vertex 0.862294 1.80266 2.5904 + vertex 0.864483 1.80164 2.59213 + endloop + endfacet + facet normal -0.565653 0.15943 0.809085 + outer loop + vertex 0.863334 1.79127 2.59335 + vertex 0.864003 1.79702 2.59269 + vertex 0.860521 1.79386 2.59087 + endloop + endfacet + facet normal -0.562921 0.163452 0.810187 + outer loop + vertex 0.859668 1.78987 2.59109 + vertex 0.863334 1.79127 2.59335 + vertex 0.860521 1.79386 2.59087 + endloop + endfacet + facet normal -0.561838 0.157469 0.812122 + outer loop + vertex 0.859668 1.78987 2.59109 + vertex 0.859837 1.78648 2.59186 + vertex 0.863334 1.79127 2.59335 + endloop + endfacet + facet normal -0.563185 0.158826 0.810924 + outer loop + vertex 0.859837 1.78648 2.59186 + vertex 0.862676 1.7855 2.59403 + vertex 0.863334 1.79127 2.59335 + endloop + endfacet + facet normal -0.555516 0.158572 0.816246 + outer loop + vertex 0.863334 1.79127 2.59335 + vertex 0.862676 1.7855 2.59403 + vertex 0.866104 1.78877 2.59572 + endloop + endfacet + facet normal -0.55275 0.162659 0.817318 + outer loop + vertex 0.867012 1.79264 2.59557 + vertex 0.863334 1.79127 2.59335 + vertex 0.866104 1.78877 2.59572 + endloop + endfacet + facet normal -0.542591 0.160563 0.824509 + outer loop + vertex 0.866104 1.78877 2.59572 + vertex 0.869341 1.79177 2.59727 + vertex 0.867012 1.79264 2.59557 + endloop + endfacet + facet normal -0.543559 0.15777 0.82441 + outer loop + vertex 0.869206 1.79509 2.59654 + vertex 0.867012 1.79264 2.59557 + vertex 0.869341 1.79177 2.59727 + endloop + endfacet + facet normal -0.536049 0.159092 0.829061 + outer loop + vertex 0.869206 1.79509 2.59654 + vertex 0.869341 1.79177 2.59727 + vertex 0.872462 1.79584 2.5985 + endloop + endfacet + facet normal -0.53562 0.154113 0.830277 + outer loop + vertex 0.869206 1.79509 2.59654 + vertex 0.872462 1.79584 2.5985 + vertex 0.870132 1.79885 2.59644 + endloop + endfacet + facet normal -0.545006 0.15624 0.823746 + outer loop + vertex 0.870132 1.79885 2.59644 + vertex 0.866871 1.79595 2.59484 + vertex 0.869206 1.79509 2.59654 + endloop + endfacet + facet normal -0.54466 0.155665 0.824083 + outer loop + vertex 0.867318 1.80052 2.59427 + vertex 0.866871 1.79595 2.59484 + vertex 0.870132 1.79885 2.59644 + endloop + endfacet + facet normal -0.544699 0.155585 0.824073 + outer loop + vertex 0.870768 1.80374 2.59594 + vertex 0.867318 1.80052 2.59427 + vertex 0.870132 1.79885 2.59644 + endloop + endfacet + facet normal -0.534832 0.154971 0.830626 + outer loop + vertex 0.870132 1.79885 2.59644 + vertex 0.874047 1.80177 2.59842 + vertex 0.870768 1.80374 2.59594 + endloop + endfacet + facet normal -0.534031 0.156575 0.83084 + outer loop + vertex 0.874047 1.80177 2.59842 + vertex 0.874246 1.80694 2.59757 + vertex 0.870768 1.80374 2.59594 + endloop + endfacet + facet normal -0.535556 0.158963 0.829404 + outer loop + vertex 0.870768 1.80374 2.59594 + vertex 0.874246 1.80694 2.59757 + vertex 0.87142 1.80865 2.59542 + endloop + endfacet + facet normal -0.546239 0.159628 0.822279 + outer loop + vertex 0.87142 1.80865 2.59542 + vertex 0.86752 1.80574 2.59339 + vertex 0.870768 1.80374 2.59594 + endloop + endfacet + facet normal -0.547995 0.163314 0.820384 + outer loop + vertex 0.86913 1.81172 2.59328 + vertex 0.86752 1.80574 2.59339 + vertex 0.87142 1.80865 2.59542 + endloop + endfacet + facet normal -0.546814 0.164568 0.820921 + outer loop + vertex 0.872347 1.81246 2.59527 + vertex 0.86913 1.81172 2.59328 + vertex 0.87142 1.80865 2.59542 + endloop + endfacet + facet normal -0.532561 0.161491 0.830843 + outer loop + vertex 0.87142 1.80865 2.59542 + vertex 0.874712 1.81152 2.59697 + vertex 0.872347 1.81246 2.59527 + endloop + endfacet + facet normal -0.530891 0.165997 0.831024 + outer loop + vertex 0.874551 1.8149 2.5962 + vertex 0.872347 1.81246 2.59527 + vertex 0.874712 1.81152 2.59697 + endloop + endfacet + facet normal -0.51724 0.168503 0.839088 + outer loop + vertex 0.874551 1.8149 2.5962 + vertex 0.874712 1.81152 2.59697 + vertex 0.878351 1.81619 2.59828 + endloop + endfacet + facet normal -0.517736 0.171402 0.838195 + outer loop + vertex 0.874551 1.8149 2.5962 + vertex 0.878351 1.81619 2.59828 + vertex 0.875438 1.81886 2.59593 + endloop + endfacet + facet normal -0.534317 0.174379 0.827102 + outer loop + vertex 0.875438 1.81886 2.59593 + vertex 0.872143 1.81585 2.59444 + vertex 0.874551 1.8149 2.5962 + endloop + endfacet + facet normal -0.534204 0.1742 0.827213 + outer loop + vertex 0.872322 1.82078 2.59352 + vertex 0.872143 1.81585 2.59444 + vertex 0.875438 1.81886 2.59593 + endloop + endfacet + facet normal -0.534315 0.173985 0.827186 + outer loop + vertex 0.87631 1.82374 2.59547 + vertex 0.872322 1.82078 2.59352 + vertex 0.875438 1.81886 2.59593 + endloop + endfacet + facet normal -0.517086 0.171982 0.838477 + outer loop + vertex 0.875438 1.81886 2.59593 + vertex 0.879192 1.82211 2.59758 + vertex 0.87631 1.82374 2.59547 + endloop + endfacet + facet normal -0.516244 0.173683 0.838645 + outer loop + vertex 0.879192 1.82211 2.59758 + vertex 0.879747 1.82683 2.59695 + vertex 0.87631 1.82374 2.59547 + endloop + endfacet + facet normal -0.513486 0.16938 0.841215 + outer loop + vertex 0.87631 1.82374 2.59547 + vertex 0.879747 1.82683 2.59695 + vertex 0.877329 1.82756 2.59532 + endloop + endfacet + facet normal -0.532767 0.174029 0.828175 + outer loop + vertex 0.877329 1.82756 2.59532 + vertex 0.874026 1.82669 2.59338 + vertex 0.87631 1.82374 2.59547 + endloop + endfacet + facet normal -0.532972 0.176084 0.827608 + outer loop + vertex 0.877329 1.82756 2.59532 + vertex 0.877195 1.83081 2.59455 + vertex 0.874026 1.82669 2.59338 + endloop + endfacet + facet normal -0.534121 0.177249 0.826618 + outer loop + vertex 0.874026 1.82669 2.59338 + vertex 0.877195 1.83081 2.59455 + vertex 0.874328 1.83184 2.59247 + endloop + endfacet + facet normal -0.517593 0.178891 0.836717 + outer loop + vertex 0.877329 1.82756 2.59532 + vertex 0.879516 1.83004 2.59614 + vertex 0.877195 1.83081 2.59455 + endloop + endfacet + facet normal -0.516573 0.181939 0.836691 + outer loop + vertex 0.880455 1.83382 2.5959 + vertex 0.877195 1.83081 2.59455 + vertex 0.879516 1.83004 2.59614 + endloop + endfacet + facet normal -0.496718 0.177811 0.849503 + outer loop + vertex 0.879516 1.83004 2.59614 + vertex 0.882993 1.8315 2.59787 + vertex 0.880455 1.83382 2.5959 + endloop + endfacet + facet normal -0.495899 0.178919 0.849748 + outer loop + vertex 0.882993 1.8315 2.59787 + vertex 0.884188 1.83704 2.5974 + vertex 0.880455 1.83382 2.5959 + endloop + endfacet + facet normal -0.495605 0.178454 0.850017 + outer loop + vertex 0.880455 1.83382 2.5959 + vertex 0.884188 1.83704 2.5974 + vertex 0.881289 1.8385 2.59541 + endloop + endfacet + facet normal -0.514684 0.180593 0.838145 + outer loop + vertex 0.881289 1.8385 2.59541 + vertex 0.877725 1.83532 2.5939 + vertex 0.880455 1.83382 2.5959 + endloop + endfacet + facet normal -0.516058 0.182755 0.83683 + outer loop + vertex 0.878476 1.841 2.59313 + vertex 0.877725 1.83532 2.5939 + vertex 0.881289 1.8385 2.59541 + endloop + endfacet + facet normal -0.516006 0.182828 0.836847 + outer loop + vertex 0.882278 1.84238 2.59517 + vertex 0.878476 1.841 2.59313 + vertex 0.881289 1.8385 2.59541 + endloop + endfacet + facet normal -0.49464 0.178227 0.850627 + outer loop + vertex 0.881289 1.8385 2.59541 + vertex 0.884817 1.84173 2.59678 + vertex 0.882278 1.84238 2.59517 + endloop + endfacet + facet normal -0.493544 0.182087 0.850446 + outer loop + vertex 0.884657 1.84501 2.59599 + vertex 0.882278 1.84238 2.59517 + vertex 0.884817 1.84173 2.59678 + endloop + endfacet + facet normal -0.481498 0.184227 0.856866 + outer loop + vertex 0.884657 1.84501 2.59599 + vertex 0.884817 1.84173 2.59678 + vertex 0.888156 1.84637 2.59766 + endloop + endfacet + facet normal -0.483182 0.19177 0.85426 + outer loop + vertex 0.884657 1.84501 2.59599 + vertex 0.888156 1.84637 2.59766 + vertex 0.885813 1.84876 2.5958 + endloop + endfacet + facet normal -0.498699 0.196066 0.844309 + outer loop + vertex 0.885813 1.84876 2.5958 + vertex 0.882315 1.84583 2.59441 + vertex 0.884657 1.84501 2.59599 + endloop + endfacet + facet normal -0.497967 0.194855 0.845021 + outer loop + vertex 0.883478 1.85107 2.59389 + vertex 0.882315 1.84583 2.59441 + vertex 0.885813 1.84876 2.5958 + endloop + endfacet + facet normal -0.49513 0.198411 0.845861 + outer loop + vertex 0.886972 1.85248 2.5956 + vertex 0.883478 1.85107 2.59389 + vertex 0.885813 1.84876 2.5958 + endloop + endfacet + facet normal -0.485466 0.195732 0.852063 + outer loop + vertex 0.885813 1.84876 2.5958 + vertex 0.889324 1.85158 2.59715 + vertex 0.886972 1.85248 2.5956 + endloop + endfacet + facet normal -0.484839 0.197344 0.852048 + outer loop + vertex 0.88937 1.85501 2.59638 + vertex 0.886972 1.85248 2.5956 + vertex 0.889324 1.85158 2.59715 + endloop + endfacet + facet normal -0.480771 0.197783 0.854249 + outer loop + vertex 0.88937 1.85501 2.59638 + vertex 0.889324 1.85158 2.59715 + vertex 0.893272 1.85618 2.59831 + endloop + endfacet + facet normal -0.480987 0.199274 0.853781 + outer loop + vertex 0.88937 1.85501 2.59638 + vertex 0.893272 1.85618 2.59831 + vertex 0.890391 1.85881 2.59607 + endloop + endfacet + facet normal -0.488737 0.200959 0.848971 + outer loop + vertex 0.890391 1.85881 2.59607 + vertex 0.886816 1.8557 2.59475 + vertex 0.88937 1.85501 2.59638 + endloop + endfacet + facet normal -0.489045 0.201435 0.848681 + outer loop + vertex 0.887409 1.86034 2.59399 + vertex 0.886816 1.8557 2.59475 + vertex 0.890391 1.85881 2.59607 + endloop + endfacet + facet normal -0.490407 0.198615 0.848559 + outer loop + vertex 0.891232 1.86356 2.59545 + vertex 0.887409 1.86034 2.59399 + vertex 0.890391 1.85881 2.59607 + endloop + endfacet + facet normal -0.482874 0.19787 0.853042 + outer loop + vertex 0.890391 1.85881 2.59607 + vertex 0.894218 1.86195 2.59751 + vertex 0.891232 1.86356 2.59545 + endloop + endfacet + facet normal -0.483635 0.196348 0.852962 + outer loop + vertex 0.894218 1.86195 2.59751 + vertex 0.894812 1.86666 2.59676 + vertex 0.891232 1.86356 2.59545 + endloop + endfacet + facet normal -0.481389 0.192891 0.855019 + outer loop + vertex 0.891232 1.86356 2.59545 + vertex 0.894812 1.86666 2.59676 + vertex 0.89223 1.86743 2.59513 + endloop + endfacet + facet normal -0.493249 0.195352 0.847669 + outer loop + vertex 0.89223 1.86743 2.59513 + vertex 0.888382 1.86617 2.59319 + vertex 0.891232 1.86356 2.59545 + endloop + endfacet + facet normal -0.492598 0.191377 0.848954 + outer loop + vertex 0.89223 1.86743 2.59513 + vertex 0.892211 1.8709 2.59434 + vertex 0.888382 1.86617 2.59319 + endloop + endfacet + facet normal -0.495524 0.194329 0.846577 + outer loop + vertex 0.888382 1.86617 2.59319 + vertex 0.892211 1.8709 2.59434 + vertex 0.8893 1.8717 2.59245 + endloop + endfacet + facet normal -0.483101 0.19261 0.854116 + outer loop + vertex 0.89223 1.86743 2.59513 + vertex 0.894619 1.86999 2.59591 + vertex 0.892211 1.8709 2.59434 + endloop + endfacet + facet normal -0.48193 0.191221 0.85509 + outer loop + vertex 0.894619 1.86999 2.59591 + vertex 0.89223 1.86743 2.59513 + vertex 0.894812 1.86666 2.59676 + endloop + endfacet + facet normal -0.46754 0.193941 0.862435 + outer loop + vertex 0.894619 1.86999 2.59591 + vertex 0.894812 1.86666 2.59676 + vertex 0.898279 1.87136 2.59758 + endloop + endfacet + facet normal -0.466625 0.189768 0.863857 + outer loop + vertex 0.894619 1.86999 2.59591 + vertex 0.898279 1.87136 2.59758 + vertex 0.895723 1.87379 2.59567 + endloop + endfacet + facet normal -0.482643 0.193805 0.854105 + outer loop + vertex 0.895723 1.87379 2.59567 + vertex 0.892211 1.8709 2.59434 + vertex 0.894619 1.86999 2.59591 + endloop + endfacet + facet normal -0.482386 0.193382 0.854346 + outer loop + vertex 0.893122 1.87635 2.59362 + vertex 0.892211 1.8709 2.59434 + vertex 0.895723 1.87379 2.59567 + endloop + endfacet + facet normal -0.482784 0.192886 0.854233 + outer loop + vertex 0.896905 1.87759 2.59548 + vertex 0.893122 1.87635 2.59362 + vertex 0.895723 1.87379 2.59567 + endloop + endfacet + facet normal -0.458142 0.185956 0.86921 + outer loop + vertex 0.895723 1.87379 2.59567 + vertex 0.899388 1.87672 2.59697 + vertex 0.896905 1.87759 2.59548 + endloop + endfacet + facet normal -0.456639 0.190084 0.869108 + outer loop + vertex 0.899379 1.88013 2.59622 + vertex 0.896905 1.87759 2.59548 + vertex 0.899388 1.87672 2.59697 + endloop + endfacet + facet normal -0.462292 0.196898 0.864591 + outer loop + vertex 0.896905 1.87759 2.59548 + vertex 0.899379 1.88013 2.59622 + vertex 0.897055 1.88098 2.59479 + endloop + endfacet + facet normal -0.463121 0.194168 0.864765 + outer loop + vertex 0.898279 1.87136 2.59758 + vertex 0.899388 1.87672 2.59697 + vertex 0.895723 1.87379 2.59567 + endloop + endfacet + facet normal -0.442882 0.191249 0.875945 + outer loop + vertex 0.898279 1.87136 2.59758 + vertex 0.903177 1.87604 2.59904 + vertex 0.899388 1.87672 2.59697 + endloop + endfacet + facet normal -0.441453 0.197341 0.875315 + outer loop + vertex 0.899388 1.87672 2.59697 + vertex 0.903177 1.87604 2.59904 + vertex 0.903089 1.88152 2.59776 + endloop + endfacet + facet normal -0.435826 0.192364 0.879234 + outer loop + vertex 0.899379 1.88013 2.59622 + vertex 0.899388 1.87672 2.59697 + vertex 0.903089 1.88152 2.59776 + endloop + endfacet + facet normal -0.436307 0.194407 0.878545 + outer loop + vertex 0.899379 1.88013 2.59622 + vertex 0.903089 1.88152 2.59776 + vertex 0.900627 1.88385 2.59602 + endloop + endfacet + facet normal -0.460445 0.201732 0.864462 + outer loop + vertex 0.900627 1.88385 2.59602 + vertex 0.897055 1.88098 2.59479 + vertex 0.899379 1.88013 2.59622 + endloop + endfacet + facet normal -0.422991 0.199633 0.883869 + outer loop + vertex 0.903177 1.87604 2.59904 + vertex 0.906913 1.88088 2.59973 + vertex 0.903089 1.88152 2.59776 + endloop + endfacet + facet normal -0.421241 0.207243 0.882953 + outer loop + vertex 0.906913 1.88088 2.59973 + vertex 0.908114 1.8862 2.59906 + vertex 0.903089 1.88152 2.59776 + endloop + endfacet + facet normal -0.41285 0.196454 0.88936 + outer loop + vertex 0.903089 1.88152 2.59776 + vertex 0.908114 1.8862 2.59906 + vertex 0.904296 1.88684 2.59714 + endloop + endfacet + facet normal -0.424614 0.201044 0.882771 + outer loop + vertex 0.906977 1.87754 2.60052 + vertex 0.906913 1.88088 2.59973 + vertex 0.903177 1.87604 2.59904 + endloop + endfacet + facet normal -0.423844 0.198053 0.883816 + outer loop + vertex 0.906977 1.87754 2.60052 + vertex 0.903177 1.87604 2.59904 + vertex 0.905772 1.87378 2.60079 + endloop + endfacet + facet normal -0.392033 0.189008 0.900326 + outer loop + vertex 0.905772 1.87378 2.60079 + vertex 0.909543 1.87688 2.60178 + vertex 0.906977 1.87754 2.60052 + endloop + endfacet + facet normal -0.393274 0.190816 0.899402 + outer loop + vertex 0.908408 1.87168 2.60239 + vertex 0.909543 1.87688 2.60178 + vertex 0.905772 1.87378 2.60079 + endloop + endfacet + facet normal -0.392174 0.192319 0.899563 + outer loop + vertex 0.904549 1.86999 2.60107 + vertex 0.908408 1.87168 2.60239 + vertex 0.905772 1.87378 2.60079 + endloop + endfacet + facet normal -0.426839 0.202159 0.881442 + outer loop + vertex 0.905772 1.87378 2.60079 + vertex 0.902019 1.87069 2.59968 + vertex 0.904549 1.86999 2.60107 + endloop + endfacet + facet normal -0.427289 0.200739 0.881549 + outer loop + vertex 0.902059 1.86732 2.60047 + vertex 0.904549 1.86999 2.60107 + vertex 0.902019 1.87069 2.59968 + endloop + endfacet + facet normal -0.451169 0.19781 0.87024 + outer loop + vertex 0.902059 1.86732 2.60047 + vertex 0.902019 1.87069 2.59968 + vertex 0.898463 1.86597 2.59891 + endloop + endfacet + facet normal -0.450701 0.195728 0.870953 + outer loop + vertex 0.902059 1.86732 2.60047 + vertex 0.898463 1.86597 2.59891 + vertex 0.900875 1.86361 2.60069 + endloop + endfacet + facet normal -0.452009 0.198542 0.869637 + outer loop + vertex 0.898463 1.86597 2.59891 + vertex 0.902019 1.87069 2.59968 + vertex 0.898279 1.87136 2.59758 + endloop + endfacet + facet normal -0.415482 0.187868 0.889989 + outer loop + vertex 0.904549 1.86999 2.60107 + vertex 0.902059 1.86732 2.60047 + vertex 0.904577 1.86672 2.60177 + endloop + endfacet + facet normal -0.391527 0.190287 0.900276 + outer loop + vertex 0.904549 1.86999 2.60107 + vertex 0.904577 1.86672 2.60177 + vertex 0.908408 1.87168 2.60239 + endloop + endfacet + facet normal -0.423989 0.197866 0.883789 + outer loop + vertex 0.903177 1.87604 2.59904 + vertex 0.902019 1.87069 2.59968 + vertex 0.905772 1.87378 2.60079 + endloop + endfacet + facet normal -0.401969 0.203827 0.892679 + outer loop + vertex 0.906977 1.87754 2.60052 + vertex 0.909516 1.88016 2.60107 + vertex 0.906913 1.88088 2.59973 + endloop + endfacet + facet normal -0.451182 0.202001 0.86927 + outer loop + vertex 0.902019 1.87069 2.59968 + vertex 0.903177 1.87604 2.59904 + vertex 0.898279 1.87136 2.59758 + endloop + endfacet + facet normal -0.469657 0.195778 0.860868 + outer loop + vertex 0.894812 1.86666 2.59676 + vertex 0.898463 1.86597 2.59891 + vertex 0.898279 1.87136 2.59758 + endloop + endfacet + facet normal -0.469642 0.195837 0.860862 + outer loop + vertex 0.894218 1.86195 2.59751 + vertex 0.898463 1.86597 2.59891 + vertex 0.894812 1.86666 2.59676 + endloop + endfacet + facet normal -0.472313 0.199458 0.858567 + outer loop + vertex 0.897249 1.86075 2.59946 + vertex 0.898463 1.86597 2.59891 + vertex 0.894218 1.86195 2.59751 + endloop + endfacet + facet normal -0.490577 0.198891 0.848396 + outer loop + vertex 0.888382 1.86617 2.59319 + vertex 0.887409 1.86034 2.59399 + vertex 0.891232 1.86356 2.59545 + endloop + endfacet + facet normal -0.495509 0.201636 0.844875 + outer loop + vertex 0.886816 1.8557 2.59475 + vertex 0.887409 1.86034 2.59399 + vertex 0.883222 1.85622 2.59252 + endloop + endfacet + facet normal -0.49574 0.20056 0.844996 + outer loop + vertex 0.883478 1.85107 2.59389 + vertex 0.886816 1.8557 2.59475 + vertex 0.883222 1.85622 2.59252 + endloop + endfacet + facet normal -0.503504 0.199043 0.840753 + outer loop + vertex 0.87994 1.85158 2.59165 + vertex 0.883478 1.85107 2.59389 + vertex 0.883222 1.85622 2.59252 + endloop + endfacet + facet normal -0.50228 0.197996 0.841732 + outer loop + vertex 0.879773 1.85483 2.59079 + vertex 0.87994 1.85158 2.59165 + vertex 0.883222 1.85622 2.59252 + endloop + endfacet + facet normal -0.503885 0.205362 0.839003 + outer loop + vertex 0.879773 1.85483 2.59079 + vertex 0.883222 1.85622 2.59252 + vertex 0.880852 1.85859 2.59051 + endloop + endfacet + facet normal -0.505335 0.190324 0.841673 + outer loop + vertex 0.879348 1.84687 2.59236 + vertex 0.883478 1.85107 2.59389 + vertex 0.87994 1.85158 2.59165 + endloop + endfacet + facet normal -0.49668 0.203205 0.843811 + outer loop + vertex 0.883222 1.85622 2.59252 + vertex 0.887409 1.86034 2.59399 + vertex 0.884399 1.86147 2.59195 + endloop + endfacet + facet normal -0.482512 0.197272 0.853385 + outer loop + vertex 0.893272 1.85618 2.59831 + vertex 0.894218 1.86195 2.59751 + vertex 0.890391 1.85881 2.59607 + endloop + endfacet + facet normal -0.477242 0.194037 0.857082 + outer loop + vertex 0.889324 1.85158 2.59715 + vertex 0.89232 1.85042 2.59908 + vertex 0.893272 1.85618 2.59831 + endloop + endfacet + facet normal -0.478423 0.191019 0.857102 + outer loop + vertex 0.888156 1.84637 2.59766 + vertex 0.89232 1.85042 2.59908 + vertex 0.889324 1.85158 2.59715 + endloop + endfacet + facet normal -0.488485 0.201774 0.848923 + outer loop + vertex 0.886972 1.85248 2.5956 + vertex 0.88937 1.85501 2.59638 + vertex 0.886816 1.8557 2.59475 + endloop + endfacet + facet normal -0.495581 0.200422 0.845122 + outer loop + vertex 0.886972 1.85248 2.5956 + vertex 0.886816 1.8557 2.59475 + vertex 0.883478 1.85107 2.59389 + endloop + endfacet + facet normal -0.510268 0.196801 0.837195 + outer loop + vertex 0.882315 1.84583 2.59441 + vertex 0.883478 1.85107 2.59389 + vertex 0.879348 1.84687 2.59236 + endloop + endfacet + facet normal -0.514244 0.185675 0.837304 + outer loop + vertex 0.878476 1.841 2.59313 + vertex 0.882315 1.84583 2.59441 + vertex 0.879348 1.84687 2.59236 + endloop + endfacet + facet normal -0.483154 0.191804 0.854268 + outer loop + vertex 0.888156 1.84637 2.59766 + vertex 0.889324 1.85158 2.59715 + vertex 0.885813 1.84876 2.5958 + endloop + endfacet + facet normal -0.480055 0.182985 0.857942 + outer loop + vertex 0.884817 1.84173 2.59678 + vertex 0.88845 1.84115 2.59894 + vertex 0.888156 1.84637 2.59766 + endloop + endfacet + facet normal -0.477416 0.183468 0.85931 + outer loop + vertex 0.88845 1.84115 2.59894 + vertex 0.891746 1.84579 2.59978 + vertex 0.888156 1.84637 2.59766 + endloop + endfacet + facet normal -0.475069 0.181491 0.861028 + outer loop + vertex 0.892016 1.84258 2.6006 + vertex 0.891746 1.84579 2.59978 + vertex 0.88845 1.84115 2.59894 + endloop + endfacet + facet normal -0.474229 0.17803 0.862213 + outer loop + vertex 0.892016 1.84258 2.6006 + vertex 0.88845 1.84115 2.59894 + vertex 0.891067 1.83879 2.60087 + endloop + endfacet + facet normal -0.463257 0.175733 0.868626 + outer loop + vertex 0.891067 1.83879 2.60087 + vertex 0.894588 1.84195 2.6021 + vertex 0.892016 1.84258 2.6006 + endloop + endfacet + facet normal -0.464715 0.177826 0.86742 + outer loop + vertex 0.89402 1.83724 2.60276 + vertex 0.894588 1.84195 2.6021 + vertex 0.891067 1.83879 2.60087 + endloop + endfacet + facet normal -0.465281 0.176662 0.867354 + outer loop + vertex 0.890194 1.83407 2.60136 + vertex 0.89402 1.83724 2.60276 + vertex 0.891067 1.83879 2.60087 + endloop + endfacet + facet normal -0.474172 0.177779 0.862297 + outer loop + vertex 0.891067 1.83879 2.60087 + vertex 0.887241 1.83561 2.59942 + vertex 0.890194 1.83407 2.60136 + endloop + endfacet + facet normal -0.464897 0.176052 0.867685 + outer loop + vertex 0.893122 1.83139 2.60347 + vertex 0.89402 1.83724 2.60276 + vertex 0.890194 1.83407 2.60136 + endloop + endfacet + facet normal -0.463922 0.177327 0.867947 + outer loop + vertex 0.889176 1.83023 2.6016 + vertex 0.893122 1.83139 2.60347 + vertex 0.890194 1.83407 2.60136 + endloop + endfacet + facet normal -0.463746 0.176219 0.868266 + outer loop + vertex 0.889176 1.83023 2.6016 + vertex 0.88918 1.82676 2.6023 + vertex 0.893122 1.83139 2.60347 + endloop + endfacet + facet normal -0.459403 0.171723 0.87147 + outer loop + vertex 0.88918 1.82676 2.6023 + vertex 0.892256 1.82554 2.60417 + vertex 0.893122 1.83139 2.60347 + endloop + endfacet + facet normal -0.449525 0.170894 0.876768 + outer loop + vertex 0.893122 1.83139 2.60347 + vertex 0.892256 1.82554 2.60417 + vertex 0.896129 1.82876 2.60552 + endloop + endfacet + facet normal -0.452174 0.167339 0.876091 + outer loop + vertex 0.897101 1.83258 2.6053 + vertex 0.893122 1.83139 2.60347 + vertex 0.896129 1.82876 2.60552 + endloop + endfacet + facet normal -0.42445 0.161175 0.890991 + outer loop + vertex 0.896129 1.82876 2.60552 + vertex 0.899773 1.83193 2.60669 + vertex 0.897101 1.83258 2.6053 + endloop + endfacet + facet normal -0.423952 0.162997 0.890897 + outer loop + vertex 0.899567 1.83512 2.60601 + vertex 0.897101 1.83258 2.6053 + vertex 0.899773 1.83193 2.60669 + endloop + endfacet + facet normal -0.434324 0.175136 0.883567 + outer loop + vertex 0.897101 1.83258 2.6053 + vertex 0.899567 1.83512 2.60601 + vertex 0.897085 1.83603 2.60461 + endloop + endfacet + facet normal -0.42445 0.161175 0.890991 + outer loop + vertex 0.899309 1.82736 2.60729 + vertex 0.899773 1.83193 2.60669 + vertex 0.896129 1.82876 2.60552 + endloop + endfacet + facet normal -0.423791 0.162709 0.891026 + outer loop + vertex 0.895328 1.82403 2.60601 + vertex 0.899309 1.82736 2.60729 + vertex 0.896129 1.82876 2.60552 + endloop + endfacet + facet normal -0.423799 0.16272 0.89102 + outer loop + vertex 0.898199 1.82172 2.60779 + vertex 0.899309 1.82736 2.60729 + vertex 0.895328 1.82403 2.60601 + endloop + endfacet + facet normal -0.424677 0.161479 0.890827 + outer loop + vertex 0.894403 1.82019 2.60626 + vertex 0.898199 1.82172 2.60779 + vertex 0.895328 1.82403 2.60601 + endloop + endfacet + facet normal -0.444883 0.165632 0.880139 + outer loop + vertex 0.895328 1.82403 2.60601 + vertex 0.891761 1.82083 2.60481 + vertex 0.894403 1.82019 2.60626 + endloop + endfacet + facet normal -0.445156 0.164622 0.88019 + outer loop + vertex 0.892088 1.81758 2.60558 + vertex 0.894403 1.82019 2.60626 + vertex 0.891761 1.82083 2.60481 + endloop + endfacet + facet normal -0.455039 0.162513 0.875516 + outer loop + vertex 0.892088 1.81758 2.60558 + vertex 0.891761 1.82083 2.60481 + vertex 0.888465 1.8162 2.60395 + endloop + endfacet + facet normal -0.455079 0.162677 0.875466 + outer loop + vertex 0.892088 1.81758 2.60558 + vertex 0.888465 1.8162 2.60395 + vertex 0.89114 1.81381 2.60579 + endloop + endfacet + facet normal -0.44049 0.159453 0.883484 + outer loop + vertex 0.89114 1.81381 2.60579 + vertex 0.894721 1.81695 2.60701 + vertex 0.892088 1.81758 2.60558 + endloop + endfacet + facet normal -0.443364 0.163585 0.881288 + outer loop + vertex 0.894093 1.81227 2.60756 + vertex 0.894721 1.81695 2.60701 + vertex 0.89114 1.81381 2.60579 + endloop + endfacet + facet normal -0.443671 0.162952 0.88125 + outer loop + vertex 0.890209 1.80915 2.60618 + vertex 0.894093 1.81227 2.60756 + vertex 0.89114 1.81381 2.60579 + endloop + endfacet + facet normal -0.457419 0.16507 0.873796 + outer loop + vertex 0.89114 1.81381 2.60579 + vertex 0.887276 1.81064 2.60436 + vertex 0.890209 1.80915 2.60618 + endloop + endfacet + facet normal -0.458165 0.163485 0.873703 + outer loop + vertex 0.887276 1.81064 2.60436 + vertex 0.886664 1.80593 2.60492 + vertex 0.890209 1.80915 2.60618 + endloop + endfacet + facet normal -0.460612 0.166935 0.871762 + outer loop + vertex 0.890209 1.80915 2.60618 + vertex 0.886664 1.80593 2.60492 + vertex 0.889202 1.80531 2.60638 + endloop + endfacet + facet normal -0.446231 0.163593 0.879838 + outer loop + vertex 0.889202 1.80531 2.60638 + vertex 0.892832 1.80669 2.60797 + vertex 0.890209 1.80915 2.60618 + endloop + endfacet + facet normal -0.445603 0.161027 0.880629 + outer loop + vertex 0.889202 1.80531 2.60638 + vertex 0.889366 1.80188 2.60709 + vertex 0.892832 1.80669 2.60797 + endloop + endfacet + facet normal -0.442085 0.158073 0.882935 + outer loop + vertex 0.889366 1.80188 2.60709 + vertex 0.89316 1.80122 2.60911 + vertex 0.892832 1.80669 2.60797 + endloop + endfacet + facet normal -0.443223 0.152672 0.883314 + outer loop + vertex 0.888326 1.79647 2.60751 + vertex 0.89316 1.80122 2.60911 + vertex 0.889366 1.80188 2.60709 + endloop + endfacet + facet normal -0.45648 0.154682 0.876185 + outer loop + vertex 0.888326 1.79647 2.60751 + vertex 0.889366 1.80188 2.60709 + vertex 0.885834 1.7988 2.6058 + endloop + endfacet + facet normal -0.457287 0.153643 0.875946 + outer loop + vertex 0.884762 1.79499 2.60591 + vertex 0.888326 1.79647 2.60751 + vertex 0.885834 1.7988 2.6058 + endloop + endfacet + facet normal -0.474987 0.158327 0.865633 + outer loop + vertex 0.885834 1.7988 2.6058 + vertex 0.88246 1.79595 2.60447 + vertex 0.884762 1.79499 2.60591 + endloop + endfacet + facet normal -0.47437 0.157358 0.866147 + outer loop + vertex 0.88341 1.8012 2.60403 + vertex 0.88246 1.79595 2.60447 + vertex 0.885834 1.7988 2.6058 + endloop + endfacet + facet normal -0.472353 0.15987 0.86679 + outer loop + vertex 0.886888 1.80264 2.60566 + vertex 0.88341 1.8012 2.60403 + vertex 0.885834 1.7988 2.6058 + endloop + endfacet + facet normal -0.473031 0.162479 0.865934 + outer loop + vertex 0.886888 1.80264 2.60566 + vertex 0.886664 1.80593 2.60492 + vertex 0.88341 1.8012 2.60403 + endloop + endfacet + facet normal -0.470903 0.160736 0.867418 + outer loop + vertex 0.88341 1.8012 2.60403 + vertex 0.886664 1.80593 2.60492 + vertex 0.883004 1.80649 2.60283 + endloop + endfacet + facet normal -0.483074 0.158376 0.861137 + outer loop + vertex 0.879805 1.8018 2.6019 + vertex 0.88341 1.8012 2.60403 + vertex 0.883004 1.80649 2.60283 + endloop + endfacet + facet normal -0.481117 0.156764 0.862526 + outer loop + vertex 0.879488 1.80506 2.60113 + vertex 0.879805 1.8018 2.6019 + vertex 0.883004 1.80649 2.60283 + endloop + endfacet + facet normal -0.482224 0.1612 0.861089 + outer loop + vertex 0.879488 1.80506 2.60113 + vertex 0.883004 1.80649 2.60283 + vertex 0.880404 1.80888 2.60093 + endloop + endfacet + facet normal -0.50339 0.165592 0.848043 + outer loop + vertex 0.880404 1.80888 2.60093 + vertex 0.877143 1.80588 2.59958 + vertex 0.879488 1.80506 2.60113 + endloop + endfacet + facet normal -0.5052 0.160287 0.847986 + outer loop + vertex 0.877333 1.80259 2.60032 + vertex 0.879488 1.80506 2.60113 + vertex 0.877143 1.80588 2.59958 + endloop + endfacet + facet normal -0.522595 0.157055 0.837991 + outer loop + vertex 0.877333 1.80259 2.60032 + vertex 0.877143 1.80588 2.59958 + vertex 0.874047 1.80177 2.59842 + endloop + endfacet + facet normal -0.52212 0.152502 0.839127 + outer loop + vertex 0.877333 1.80259 2.60032 + vertex 0.874047 1.80177 2.59842 + vertex 0.876441 1.79877 2.60045 + endloop + endfacet + facet normal -0.500204 0.147889 0.853185 + outer loop + vertex 0.876441 1.79877 2.60045 + vertex 0.879805 1.8018 2.6019 + vertex 0.877333 1.80259 2.60032 + endloop + endfacet + facet normal -0.50383 0.153396 0.850074 + outer loop + vertex 0.879454 1.79713 2.60254 + vertex 0.879805 1.8018 2.6019 + vertex 0.876441 1.79877 2.60045 + endloop + endfacet + facet normal -0.50466 0.151646 0.849895 + outer loop + vertex 0.875776 1.79381 2.60094 + vertex 0.879454 1.79713 2.60254 + vertex 0.876441 1.79877 2.60045 + endloop + endfacet + facet normal -0.523298 0.152999 0.838302 + outer loop + vertex 0.876441 1.79877 2.60045 + vertex 0.872462 1.79584 2.5985 + vertex 0.875776 1.79381 2.60094 + endloop + endfacet + facet normal -0.520932 0.1576 0.838923 + outer loop + vertex 0.872462 1.79584 2.5985 + vertex 0.872218 1.79065 2.59933 + vertex 0.875776 1.79381 2.60094 + endloop + endfacet + facet normal -0.521012 0.157728 0.838849 + outer loop + vertex 0.875776 1.79381 2.60094 + vertex 0.872218 1.79065 2.59933 + vertex 0.875057 1.78889 2.60142 + endloop + endfacet + facet normal -0.504538 0.156321 0.84912 + outer loop + vertex 0.875057 1.78889 2.60142 + vertex 0.87913 1.79174 2.60332 + vertex 0.875776 1.79381 2.60094 + endloop + endfacet + facet normal -0.504369 0.15597 0.849285 + outer loop + vertex 0.877429 1.7858 2.6034 + vertex 0.87913 1.79174 2.60332 + vertex 0.875057 1.78889 2.60142 + endloop + endfacet + facet normal -0.490471 0.152113 0.858079 + outer loop + vertex 0.87913 1.79174 2.60332 + vertex 0.877429 1.7858 2.6034 + vertex 0.881525 1.78873 2.60522 + endloop + endfacet + facet normal -0.490271 0.152321 0.858157 + outer loop + vertex 0.882506 1.7925 2.60511 + vertex 0.87913 1.79174 2.60332 + vertex 0.881525 1.78873 2.60522 + endloop + endfacet + facet normal -0.490414 0.153763 0.857818 + outer loop + vertex 0.882506 1.7925 2.60511 + vertex 0.88246 1.79595 2.60447 + vertex 0.87913 1.79174 2.60332 + endloop + endfacet + facet normal -0.49064 0.153989 0.857648 + outer loop + vertex 0.87913 1.79174 2.60332 + vertex 0.88246 1.79595 2.60447 + vertex 0.879454 1.79713 2.60254 + endloop + endfacet + facet normal -0.490272 0.15172 0.858262 + outer loop + vertex 0.881525 1.78873 2.60522 + vertex 0.877429 1.7858 2.6034 + vertex 0.880813 1.78387 2.60567 + endloop + endfacet + facet normal -0.472846 0.150097 0.868267 + outer loop + vertex 0.880813 1.78387 2.60567 + vertex 0.884612 1.7873 2.60715 + vertex 0.881525 1.78873 2.60522 + endloop + endfacet + facet normal -0.472839 0.150112 0.868268 + outer loop + vertex 0.884612 1.7873 2.60715 + vertex 0.884957 1.79179 2.60656 + vertex 0.881525 1.78873 2.60522 + endloop + endfacet + facet normal -0.456247 0.149998 0.87712 + outer loop + vertex 0.884612 1.7873 2.60715 + vertex 0.8883 1.79135 2.60837 + vertex 0.884957 1.79179 2.60656 + endloop + endfacet + facet normal -0.456077 0.150977 0.877041 + outer loop + vertex 0.884957 1.79179 2.60656 + vertex 0.8883 1.79135 2.60837 + vertex 0.888326 1.79647 2.60751 + endloop + endfacet + facet normal -0.442376 0.152062 0.883844 + outer loop + vertex 0.8883 1.79135 2.60837 + vertex 0.892103 1.79554 2.60956 + vertex 0.888326 1.79647 2.60751 + endloop + endfacet + facet normal -0.456886 0.150717 0.876664 + outer loop + vertex 0.88831 1.78632 2.60925 + vertex 0.8883 1.79135 2.60837 + vertex 0.884612 1.7873 2.60715 + endloop + endfacet + facet normal -0.457136 0.149823 0.876687 + outer loop + vertex 0.884029 1.78221 2.60772 + vertex 0.88831 1.78632 2.60925 + vertex 0.884612 1.7873 2.60715 + endloop + endfacet + facet normal -0.44022 0.152175 0.884901 + outer loop + vertex 0.88831 1.78632 2.60925 + vertex 0.891664 1.79094 2.61012 + vertex 0.8883 1.79135 2.60837 + endloop + endfacet + facet normal -0.437983 0.150284 0.886333 + outer loop + vertex 0.891871 1.78773 2.61076 + vertex 0.891664 1.79094 2.61012 + vertex 0.88831 1.78632 2.60925 + endloop + endfacet + facet normal -0.439495 0.155943 0.884605 + outer loop + vertex 0.891871 1.78773 2.61076 + vertex 0.88831 1.78632 2.60925 + vertex 0.890747 1.78394 2.61088 + endloop + endfacet + facet normal -0.414547 0.148935 0.897758 + outer loop + vertex 0.890747 1.78394 2.61088 + vertex 0.894414 1.787 2.61206 + vertex 0.891871 1.78773 2.61076 + endloop + endfacet + facet normal -0.414952 0.149531 0.897471 + outer loop + vertex 0.893322 1.78162 2.61245 + vertex 0.894414 1.787 2.61206 + vertex 0.890747 1.78394 2.61088 + endloop + endfacet + facet normal -0.414826 0.149693 0.897503 + outer loop + vertex 0.889589 1.78012 2.61098 + vertex 0.893322 1.78162 2.61245 + vertex 0.890747 1.78394 2.61088 + endloop + endfacet + facet normal -0.446546 0.158867 0.880544 + outer loop + vertex 0.890747 1.78394 2.61088 + vertex 0.887144 1.78098 2.60958 + vertex 0.889589 1.78012 2.61098 + endloop + endfacet + facet normal -0.409933 0.132644 0.902419 + outer loop + vertex 0.889589 1.78012 2.61098 + vertex 0.889863 1.77688 2.61158 + vertex 0.893322 1.78162 2.61245 + endloop + endfacet + facet normal -0.435333 0.128402 0.891066 + outer loop + vertex 0.889589 1.78012 2.61098 + vertex 0.887193 1.77748 2.61019 + vertex 0.889863 1.77688 2.61158 + endloop + endfacet + facet normal -0.442399 0.152397 0.883775 + outer loop + vertex 0.88831 1.78632 2.60925 + vertex 0.887144 1.78098 2.60958 + vertex 0.890747 1.78394 2.61088 + endloop + endfacet + facet normal -0.473259 0.150697 0.867938 + outer loop + vertex 0.884029 1.78221 2.60772 + vertex 0.884612 1.7873 2.60715 + vertex 0.880813 1.78387 2.60567 + endloop + endfacet + facet normal -0.493176 0.145867 0.857613 + outer loop + vertex 0.877429 1.7858 2.6034 + vertex 0.877291 1.7806 2.60421 + vertex 0.880813 1.78387 2.60567 + endloop + endfacet + facet normal -0.491801 0.143885 0.858737 + outer loop + vertex 0.880813 1.78387 2.60567 + vertex 0.877291 1.7806 2.60421 + vertex 0.880285 1.77895 2.6062 + endloop + endfacet + facet normal -0.503951 0.145196 0.851441 + outer loop + vertex 0.874301 1.78176 2.60224 + vertex 0.877291 1.7806 2.60421 + vertex 0.877429 1.7858 2.6034 + endloop + endfacet + facet normal -0.502718 0.143973 0.852377 + outer loop + vertex 0.874078 1.78512 2.60154 + vertex 0.874301 1.78176 2.60224 + vertex 0.877429 1.7858 2.6034 + endloop + endfacet + facet normal -0.503716 0.156641 0.849549 + outer loop + vertex 0.874078 1.78512 2.60154 + vertex 0.877429 1.7858 2.6034 + vertex 0.875057 1.78889 2.60142 + endloop + endfacet + facet normal -0.51603 0.14151 0.8448 + outer loop + vertex 0.874078 1.78512 2.60154 + vertex 0.871885 1.78273 2.6006 + vertex 0.874301 1.78176 2.60224 + endloop + endfacet + facet normal -0.523674 0.120104 0.84341 + outer loop + vertex 0.871167 1.77878 2.60071 + vertex 0.874301 1.78176 2.60224 + vertex 0.871885 1.78273 2.6006 + endloop + endfacet + facet normal -0.536433 0.122178 0.835052 + outer loop + vertex 0.871885 1.78273 2.6006 + vertex 0.868237 1.78142 2.59845 + vertex 0.871167 1.77878 2.60071 + endloop + endfacet + facet normal -0.541673 0.14974 0.827144 + outer loop + vertex 0.871885 1.78273 2.6006 + vertex 0.871725 1.78608 2.59989 + vertex 0.868237 1.78142 2.59845 + endloop + endfacet + facet normal -0.537622 0.145676 0.830506 + outer loop + vertex 0.868237 1.78142 2.59845 + vertex 0.871725 1.78608 2.59989 + vertex 0.868841 1.78719 2.59783 + endloop + endfacet + facet normal -0.535081 0.145589 0.832162 + outer loop + vertex 0.868237 1.78142 2.59845 + vertex 0.868841 1.78719 2.59783 + vertex 0.86539 1.78397 2.59617 + endloop + endfacet + facet normal -0.539491 0.139118 0.830419 + outer loop + vertex 0.864559 1.78003 2.59629 + vertex 0.868237 1.78142 2.59845 + vertex 0.86539 1.78397 2.59617 + endloop + endfacet + facet normal -0.564485 0.143862 0.81281 + outer loop + vertex 0.86539 1.78397 2.59617 + vertex 0.86227 1.78083 2.59456 + vertex 0.864559 1.78003 2.59629 + endloop + endfacet + facet normal -0.563271 0.142061 0.813968 + outer loop + vertex 0.862676 1.7855 2.59403 + vertex 0.86227 1.78083 2.59456 + vertex 0.86539 1.78397 2.59617 + endloop + endfacet + facet normal -0.530996 0.0991201 0.841557 + outer loop + vertex 0.864559 1.78003 2.59629 + vertex 0.864881 1.77663 2.59689 + vertex 0.868237 1.78142 2.59845 + endloop + endfacet + facet normal -0.542841 0.157652 0.824906 + outer loop + vertex 0.86539 1.78397 2.59617 + vertex 0.868841 1.78719 2.59783 + vertex 0.866104 1.78877 2.59572 + endloop + endfacet + facet normal -0.532922 0.159046 0.831083 + outer loop + vertex 0.871725 1.78608 2.59989 + vertex 0.872218 1.79065 2.59933 + vertex 0.868841 1.78719 2.59783 + endloop + endfacet + facet normal -0.533086 0.159269 0.830935 + outer loop + vertex 0.868841 1.78719 2.59783 + vertex 0.872218 1.79065 2.59933 + vertex 0.869341 1.79177 2.59727 + endloop + endfacet + facet normal -0.513192 0.118979 0.849987 + outer loop + vertex 0.874123 1.77717 2.60277 + vertex 0.877291 1.7806 2.60421 + vertex 0.874301 1.78176 2.60224 + endloop + endfacet + facet normal -0.505955 0.153623 0.84877 + outer loop + vertex 0.87913 1.79174 2.60332 + vertex 0.879454 1.79713 2.60254 + vertex 0.875776 1.79381 2.60094 + endloop + endfacet + facet normal -0.522726 0.151844 0.838869 + outer loop + vertex 0.874047 1.80177 2.59842 + vertex 0.872462 1.79584 2.5985 + vertex 0.876441 1.79877 2.60045 + endloop + endfacet + facet normal -0.502101 0.163681 0.849178 + outer loop + vertex 0.877635 1.81043 2.59899 + vertex 0.877143 1.80588 2.59958 + vertex 0.880404 1.80888 2.60093 + endloop + endfacet + facet normal -0.501309 0.165288 0.849335 + outer loop + vertex 0.88122 1.81362 2.60049 + vertex 0.877635 1.81043 2.59899 + vertex 0.880404 1.80888 2.60093 + endloop + endfacet + facet normal -0.480943 0.162919 0.861482 + outer loop + vertex 0.880404 1.80888 2.60093 + vertex 0.884172 1.8121 2.60242 + vertex 0.88122 1.81362 2.60049 + endloop + endfacet + facet normal -0.481058 0.162672 0.861464 + outer loop + vertex 0.884172 1.8121 2.60242 + vertex 0.884768 1.81686 2.60186 + vertex 0.88122 1.81362 2.60049 + endloop + endfacet + facet normal -0.480536 0.161915 0.861898 + outer loop + vertex 0.88122 1.81362 2.60049 + vertex 0.884768 1.81686 2.60186 + vertex 0.882191 1.81755 2.60029 + endloop + endfacet + facet normal -0.503653 0.166918 0.847627 + outer loop + vertex 0.882191 1.81755 2.60029 + vertex 0.878351 1.81619 2.59828 + vertex 0.88122 1.81362 2.60049 + endloop + endfacet + facet normal -0.504537 0.171571 0.846171 + outer loop + vertex 0.882191 1.81755 2.60029 + vertex 0.882189 1.82103 2.59959 + vertex 0.878351 1.81619 2.59828 + endloop + endfacet + facet normal -0.504229 0.17126 0.846418 + outer loop + vertex 0.878351 1.81619 2.59828 + vertex 0.882189 1.82103 2.59959 + vertex 0.879192 1.82211 2.59758 + endloop + endfacet + facet normal -0.501607 0.178609 0.846457 + outer loop + vertex 0.882189 1.82103 2.59959 + vertex 0.883301 1.8263 2.59913 + vertex 0.879192 1.82211 2.59758 + endloop + endfacet + facet normal -0.488304 0.173426 0.855268 + outer loop + vertex 0.882191 1.81755 2.60029 + vertex 0.884566 1.82018 2.60111 + vertex 0.882189 1.82103 2.59959 + endloop + endfacet + facet normal -0.479977 0.163865 0.861841 + outer loop + vertex 0.884566 1.82018 2.60111 + vertex 0.882191 1.81755 2.60029 + vertex 0.884768 1.81686 2.60186 + endloop + endfacet + facet normal -0.466615 0.166212 0.868703 + outer loop + vertex 0.884566 1.82018 2.60111 + vertex 0.884768 1.81686 2.60186 + vertex 0.888088 1.82149 2.60276 + endloop + endfacet + facet normal -0.467994 0.172348 0.866763 + outer loop + vertex 0.884566 1.82018 2.60111 + vertex 0.888088 1.82149 2.60276 + vertex 0.885677 1.82394 2.60097 + endloop + endfacet + facet normal -0.48686 0.177465 0.855263 + outer loop + vertex 0.885677 1.82394 2.60097 + vertex 0.882189 1.82103 2.59959 + vertex 0.884566 1.82018 2.60111 + endloop + endfacet + facet normal -0.48605 0.176149 0.855994 + outer loop + vertex 0.883301 1.8263 2.59913 + vertex 0.882189 1.82103 2.59959 + vertex 0.885677 1.82394 2.60097 + endloop + endfacet + facet normal -0.484323 0.178303 0.856527 + outer loop + vertex 0.886788 1.82769 2.60081 + vertex 0.883301 1.8263 2.59913 + vertex 0.885677 1.82394 2.60097 + endloop + endfacet + facet normal -0.470803 0.174633 0.864782 + outer loop + vertex 0.885677 1.82394 2.60097 + vertex 0.88918 1.82676 2.6023 + vertex 0.886788 1.82769 2.60081 + endloop + endfacet + facet normal -0.484385 0.178568 0.856437 + outer loop + vertex 0.886788 1.82769 2.60081 + vertex 0.886611 1.83095 2.60004 + vertex 0.883301 1.8263 2.59913 + endloop + endfacet + facet normal -0.484566 0.178723 0.856302 + outer loop + vertex 0.883301 1.8263 2.59913 + vertex 0.886611 1.83095 2.60004 + vertex 0.882993 1.8315 2.59787 + endloop + endfacet + facet normal -0.484485 0.179112 0.856267 + outer loop + vertex 0.886611 1.83095 2.60004 + vertex 0.887241 1.83561 2.59942 + vertex 0.882993 1.8315 2.59787 + endloop + endfacet + facet normal -0.468825 0.171347 0.866512 + outer loop + vertex 0.888088 1.82149 2.60276 + vertex 0.88918 1.82676 2.6023 + vertex 0.885677 1.82394 2.60097 + endloop + endfacet + facet normal -0.463936 0.163933 0.870568 + outer loop + vertex 0.884768 1.81686 2.60186 + vertex 0.888465 1.8162 2.60395 + vertex 0.888088 1.82149 2.60276 + endloop + endfacet + facet normal -0.464425 0.16169 0.870727 + outer loop + vertex 0.884172 1.8121 2.60242 + vertex 0.888465 1.8162 2.60395 + vertex 0.884768 1.81686 2.60186 + endloop + endfacet + facet normal -0.466068 0.163894 0.869436 + outer loop + vertex 0.887276 1.81064 2.60436 + vertex 0.888465 1.8162 2.60395 + vertex 0.884172 1.8121 2.60242 + endloop + endfacet + facet normal -0.467485 0.160681 0.869275 + outer loop + vertex 0.883004 1.80649 2.60283 + vertex 0.887276 1.81064 2.60436 + vertex 0.884172 1.8121 2.60242 + endloop + endfacet + facet normal -0.502976 0.167861 0.847843 + outer loop + vertex 0.878351 1.81619 2.59828 + vertex 0.877635 1.81043 2.59899 + vertex 0.88122 1.81362 2.60049 + endloop + endfacet + facet normal -0.520413 0.16421 0.837977 + outer loop + vertex 0.877143 1.80588 2.59958 + vertex 0.877635 1.81043 2.59899 + vertex 0.874246 1.80694 2.59757 + endloop + endfacet + facet normal -0.51934 0.162786 0.83892 + outer loop + vertex 0.874246 1.80694 2.59757 + vertex 0.877635 1.81043 2.59899 + vertex 0.874712 1.81152 2.59697 + endloop + endfacet + facet normal -0.480939 0.162913 0.861485 + outer loop + vertex 0.883004 1.80649 2.60283 + vertex 0.884172 1.8121 2.60242 + vertex 0.880404 1.80888 2.60093 + endloop + endfacet + facet normal -0.498652 0.152857 0.853218 + outer loop + vertex 0.879488 1.80506 2.60113 + vertex 0.877333 1.80259 2.60032 + vertex 0.879805 1.8018 2.6019 + endloop + endfacet + facet normal -0.484087 0.153458 0.861458 + outer loop + vertex 0.879454 1.79713 2.60254 + vertex 0.88341 1.8012 2.60403 + vertex 0.879805 1.8018 2.6019 + endloop + endfacet + facet normal -0.488675 0.159257 0.857808 + outer loop + vertex 0.88246 1.79595 2.60447 + vertex 0.88341 1.8012 2.60403 + vertex 0.879454 1.79713 2.60254 + endloop + endfacet + facet normal -0.457415 0.156067 0.875451 + outer loop + vertex 0.885834 1.7988 2.6058 + vertex 0.889366 1.80188 2.60709 + vertex 0.886888 1.80264 2.60566 + endloop + endfacet + facet normal -0.442468 0.151719 0.883857 + outer loop + vertex 0.892103 1.79554 2.60956 + vertex 0.89316 1.80122 2.60911 + vertex 0.888326 1.79647 2.60751 + endloop + endfacet + facet normal -0.456353 0.15943 0.8754 + outer loop + vertex 0.889202 1.80531 2.60638 + vertex 0.886888 1.80264 2.60566 + vertex 0.889366 1.80188 2.60709 + endloop + endfacet + facet normal -0.461242 0.164615 0.87187 + outer loop + vertex 0.886888 1.80264 2.60566 + vertex 0.889202 1.80531 2.60638 + vertex 0.886664 1.80593 2.60492 + endloop + endfacet + facet normal -0.470203 0.164268 0.867136 + outer loop + vertex 0.886664 1.80593 2.60492 + vertex 0.887276 1.81064 2.60436 + vertex 0.883004 1.80649 2.60283 + endloop + endfacet + facet normal -0.445023 0.165115 0.880165 + outer loop + vertex 0.892832 1.80669 2.60797 + vertex 0.894093 1.81227 2.60756 + vertex 0.890209 1.80915 2.60618 + endloop + endfacet + facet normal -0.429965 0.162302 0.888137 + outer loop + vertex 0.892832 1.80669 2.60797 + vertex 0.897223 1.81072 2.60936 + vertex 0.894093 1.81227 2.60756 + endloop + endfacet + facet normal -0.428001 0.166479 0.888313 + outer loop + vertex 0.897223 1.81072 2.60936 + vertex 0.8985 1.8163 2.60893 + vertex 0.894093 1.81227 2.60756 + endloop + endfacet + facet normal -0.411034 0.163253 0.896883 + outer loop + vertex 0.8985 1.8163 2.60893 + vertex 0.897223 1.81072 2.60936 + vertex 0.901194 1.81389 2.6106 + endloop + endfacet + facet normal -0.409908 0.164688 0.897136 + outer loop + vertex 0.902216 1.81772 2.61036 + vertex 0.8985 1.8163 2.60893 + vertex 0.901194 1.81389 2.6106 + endloop + endfacet + facet normal -0.408636 0.164387 0.897771 + outer loop + vertex 0.901194 1.81389 2.6106 + vertex 0.904847 1.81706 2.61168 + vertex 0.902216 1.81772 2.61036 + endloop + endfacet + facet normal -0.40586 0.160524 0.899728 + outer loop + vertex 0.904251 1.81238 2.61225 + vertex 0.904847 1.81706 2.61168 + vertex 0.901194 1.81389 2.6106 + endloop + endfacet + facet normal -0.410033 0.165161 0.896992 + outer loop + vertex 0.902216 1.81772 2.61036 + vertex 0.902055 1.82108 2.60967 + vertex 0.8985 1.8163 2.60893 + endloop + endfacet + facet normal -0.409508 0.164721 0.897313 + outer loop + vertex 0.8985 1.8163 2.60893 + vertex 0.902055 1.82108 2.60967 + vertex 0.898199 1.82172 2.60779 + endloop + endfacet + facet normal -0.410873 0.163005 0.897002 + outer loop + vertex 0.901194 1.81389 2.6106 + vertex 0.897223 1.81072 2.60936 + vertex 0.900263 1.80922 2.61102 + endloop + endfacet + facet normal -0.432064 0.165115 0.886599 + outer loop + vertex 0.896602 1.80603 2.60993 + vertex 0.897223 1.81072 2.60936 + vertex 0.892832 1.80669 2.60797 + endloop + endfacet + facet normal -0.42481 0.162198 0.890633 + outer loop + vertex 0.894093 1.81227 2.60756 + vertex 0.8985 1.8163 2.60893 + vertex 0.894721 1.81695 2.60701 + endloop + endfacet + facet normal -0.424752 0.162473 0.890611 + outer loop + vertex 0.894721 1.81695 2.60701 + vertex 0.8985 1.8163 2.60893 + vertex 0.898199 1.82172 2.60779 + endloop + endfacet + facet normal -0.45553 0.162076 0.875342 + outer loop + vertex 0.888465 1.8162 2.60395 + vertex 0.887276 1.81064 2.60436 + vertex 0.89114 1.81381 2.60579 + endloop + endfacet + facet normal -0.458028 0.165014 0.873488 + outer loop + vertex 0.888465 1.8162 2.60395 + vertex 0.891761 1.82083 2.60481 + vertex 0.888088 1.82149 2.60276 + endloop + endfacet + facet normal -0.457639 0.16677 0.873358 + outer loop + vertex 0.891761 1.82083 2.60481 + vertex 0.892256 1.82554 2.60417 + vertex 0.888088 1.82149 2.60276 + endloop + endfacet + facet normal -0.440456 0.159579 0.883478 + outer loop + vertex 0.894403 1.82019 2.60626 + vertex 0.892088 1.81758 2.60558 + vertex 0.894721 1.81695 2.60701 + endloop + endfacet + facet normal -0.445395 0.166351 0.879745 + outer loop + vertex 0.892256 1.82554 2.60417 + vertex 0.891761 1.82083 2.60481 + vertex 0.895328 1.82403 2.60601 + endloop + endfacet + facet normal -0.425013 0.162691 0.890447 + outer loop + vertex 0.894403 1.82019 2.60626 + vertex 0.894721 1.81695 2.60701 + vertex 0.898199 1.82172 2.60779 + endloop + endfacet + facet normal -0.453169 0.173215 0.874434 + outer loop + vertex 0.897101 1.83258 2.6053 + vertex 0.897085 1.83603 2.60461 + vertex 0.893122 1.83139 2.60347 + endloop + endfacet + facet normal -0.445888 0.165289 0.879695 + outer loop + vertex 0.896129 1.82876 2.60552 + vertex 0.892256 1.82554 2.60417 + vertex 0.895328 1.82403 2.60601 + endloop + endfacet + facet normal -0.460091 0.169959 0.871453 + outer loop + vertex 0.888088 1.82149 2.60276 + vertex 0.892256 1.82554 2.60417 + vertex 0.88918 1.82676 2.6023 + endloop + endfacet + facet normal -0.470467 0.175503 0.864789 + outer loop + vertex 0.889176 1.83023 2.6016 + vertex 0.886788 1.82769 2.60081 + vertex 0.88918 1.82676 2.6023 + endloop + endfacet + facet normal -0.455081 0.175191 0.873046 + outer loop + vertex 0.893122 1.83139 2.60347 + vertex 0.897085 1.83603 2.60461 + vertex 0.89402 1.83724 2.60276 + endloop + endfacet + facet normal -0.474283 0.177958 0.862198 + outer loop + vertex 0.88845 1.84115 2.59894 + vertex 0.887241 1.83561 2.59942 + vertex 0.891067 1.83879 2.60087 + endloop + endfacet + facet normal -0.481664 0.179194 0.85784 + outer loop + vertex 0.887241 1.83561 2.59942 + vertex 0.88845 1.84115 2.59894 + vertex 0.884188 1.83704 2.5974 + endloop + endfacet + facet normal -0.481046 0.178359 0.85836 + outer loop + vertex 0.884188 1.83704 2.5974 + vertex 0.88845 1.84115 2.59894 + vertex 0.884817 1.84173 2.59678 + endloop + endfacet + facet normal -0.500718 0.190433 0.844403 + outer loop + vertex 0.882278 1.84238 2.59517 + vertex 0.884657 1.84501 2.59599 + vertex 0.882315 1.84583 2.59441 + endloop + endfacet + facet normal -0.517042 0.188533 0.834939 + outer loop + vertex 0.882278 1.84238 2.59517 + vertex 0.882315 1.84583 2.59441 + vertex 0.878476 1.841 2.59313 + endloop + endfacet + facet normal -0.495278 0.179164 0.850059 + outer loop + vertex 0.884188 1.83704 2.5974 + vertex 0.884817 1.84173 2.59678 + vertex 0.881289 1.8385 2.59541 + endloop + endfacet + facet normal -0.482742 0.176753 0.857741 + outer loop + vertex 0.882993 1.8315 2.59787 + vertex 0.887241 1.83561 2.59942 + vertex 0.884188 1.83704 2.5974 + endloop + endfacet + facet normal -0.496331 0.176232 0.850058 + outer loop + vertex 0.879516 1.83004 2.59614 + vertex 0.879747 1.82683 2.59695 + vertex 0.882993 1.8315 2.59787 + endloop + endfacet + facet normal -0.496589 0.176451 0.849862 + outer loop + vertex 0.879747 1.82683 2.59695 + vertex 0.883301 1.8263 2.59913 + vertex 0.882993 1.8315 2.59787 + endloop + endfacet + facet normal -0.515107 0.179727 0.838071 + outer loop + vertex 0.877725 1.83532 2.5939 + vertex 0.877195 1.83081 2.59455 + vertex 0.880455 1.83382 2.5959 + endloop + endfacet + facet normal -0.512405 0.172861 0.841166 + outer loop + vertex 0.879516 1.83004 2.59614 + vertex 0.877329 1.82756 2.59532 + vertex 0.879747 1.82683 2.59695 + endloop + endfacet + facet normal -0.497284 0.173003 0.850164 + outer loop + vertex 0.879192 1.82211 2.59758 + vertex 0.883301 1.8263 2.59913 + vertex 0.879747 1.82683 2.59695 + endloop + endfacet + facet normal -0.533799 0.172924 0.827742 + outer loop + vertex 0.874026 1.82669 2.59338 + vertex 0.872322 1.82078 2.59352 + vertex 0.87631 1.82374 2.59547 + endloop + endfacet + facet normal -0.544881 0.175938 0.819848 + outer loop + vertex 0.872322 1.82078 2.59352 + vertex 0.874026 1.82669 2.59338 + vertex 0.870093 1.82378 2.59139 + endloop + endfacet + facet normal -0.545699 0.175077 0.819488 + outer loop + vertex 0.869137 1.82003 2.59156 + vertex 0.872322 1.82078 2.59352 + vertex 0.870093 1.82378 2.59139 + endloop + endfacet + facet normal -0.557804 0.17777 0.810711 + outer loop + vertex 0.870093 1.82378 2.59139 + vertex 0.866966 1.82103 2.58984 + vertex 0.869137 1.82003 2.59156 + endloop + endfacet + facet normal -0.559036 0.174756 0.810518 + outer loop + vertex 0.867087 1.81774 2.59064 + vertex 0.869137 1.82003 2.59156 + vertex 0.866966 1.82103 2.58984 + endloop + endfacet + facet normal -0.569025 0.172811 0.803957 + outer loop + vertex 0.867087 1.81774 2.59064 + vertex 0.866966 1.82103 2.58984 + vertex 0.863944 1.8169 2.58859 + endloop + endfacet + facet normal -0.568828 0.170587 0.804571 + outer loop + vertex 0.867087 1.81774 2.59064 + vertex 0.863944 1.8169 2.58859 + vertex 0.866149 1.81384 2.5908 + endloop + endfacet + facet normal -0.556888 0.168083 0.813403 + outer loop + vertex 0.866149 1.81384 2.5908 + vertex 0.869303 1.81667 2.59237 + vertex 0.867087 1.81774 2.59064 + endloop + endfacet + facet normal -0.557024 0.168313 0.813262 + outer loop + vertex 0.86913 1.81172 2.59328 + vertex 0.869303 1.81667 2.59237 + vertex 0.866149 1.81384 2.5908 + endloop + endfacet + facet normal -0.557174 0.168046 0.813214 + outer loop + vertex 0.865241 1.8089 2.5912 + vertex 0.86913 1.81172 2.59328 + vertex 0.866149 1.81384 2.5908 + endloop + endfacet + facet normal -0.569717 0.169621 0.804146 + outer loop + vertex 0.866149 1.81384 2.5908 + vertex 0.862308 1.81094 2.58869 + vertex 0.865241 1.8089 2.5912 + endloop + endfacet + facet normal -0.570214 0.168707 0.803986 + outer loop + vertex 0.862308 1.81094 2.58869 + vertex 0.862114 1.80604 2.58958 + vertex 0.865241 1.8089 2.5912 + endloop + endfacet + facet normal -0.570129 0.168563 0.804077 + outer loop + vertex 0.865241 1.8089 2.5912 + vertex 0.862114 1.80604 2.58958 + vertex 0.864328 1.80501 2.59137 + endloop + endfacet + facet normal -0.555692 0.165634 0.814722 + outer loop + vertex 0.864328 1.80501 2.59137 + vertex 0.86752 1.80574 2.59339 + vertex 0.865241 1.8089 2.5912 + endloop + endfacet + facet normal -0.555263 0.159645 0.816209 + outer loop + vertex 0.864328 1.80501 2.59137 + vertex 0.864483 1.80164 2.59213 + vertex 0.86752 1.80574 2.59339 + endloop + endfacet + facet normal -0.553846 0.158216 0.817449 + outer loop + vertex 0.864483 1.80164 2.59213 + vertex 0.867318 1.80052 2.59427 + vertex 0.86752 1.80574 2.59339 + endloop + endfacet + facet normal -0.554666 0.155917 0.817335 + outer loop + vertex 0.864003 1.79702 2.59269 + vertex 0.867318 1.80052 2.59427 + vertex 0.864483 1.80164 2.59213 + endloop + endfacet + facet normal -0.580604 0.167793 0.796708 + outer loop + vertex 0.859393 1.80675 2.58745 + vertex 0.862114 1.80604 2.58958 + vertex 0.862308 1.81094 2.58869 + endloop + endfacet + facet normal -0.54723 0.169151 0.819712 + outer loop + vertex 0.86913 1.81172 2.59328 + vertex 0.872143 1.81585 2.59444 + vertex 0.869303 1.81667 2.59237 + endloop + endfacet + facet normal -0.569722 0.16963 0.804141 + outer loop + vertex 0.863944 1.8169 2.58859 + vertex 0.862308 1.81094 2.58869 + vertex 0.866149 1.81384 2.5908 + endloop + endfacet + facet normal -0.555815 0.170637 0.813605 + outer loop + vertex 0.869137 1.82003 2.59156 + vertex 0.867087 1.81774 2.59064 + vertex 0.869303 1.81667 2.59237 + endloop + endfacet + facet normal -0.556946 0.176286 0.811624 + outer loop + vertex 0.867381 1.82544 2.58917 + vertex 0.866966 1.82103 2.58984 + vertex 0.870093 1.82378 2.59139 + endloop + endfacet + facet normal -0.567583 0.176159 0.80425 + outer loop + vertex 0.866966 1.82103 2.58984 + vertex 0.867381 1.82544 2.58917 + vertex 0.864191 1.82201 2.58767 + endloop + endfacet + facet normal -0.545523 0.172726 0.820104 + outer loop + vertex 0.869137 1.82003 2.59156 + vertex 0.869303 1.81667 2.59237 + vertex 0.872322 1.82078 2.59352 + endloop + endfacet + facet normal -0.54551 0.177272 0.819142 + outer loop + vertex 0.870093 1.82378 2.59139 + vertex 0.874026 1.82669 2.59338 + vertex 0.870821 1.82864 2.59082 + endloop + endfacet + facet normal -0.546026 0.173217 0.819666 + outer loop + vertex 0.869303 1.81667 2.59237 + vertex 0.872143 1.81585 2.59444 + vertex 0.872322 1.82078 2.59352 + endloop + endfacet + facet normal -0.517191 0.172155 0.838377 + outer loop + vertex 0.878351 1.81619 2.59828 + vertex 0.879192 1.82211 2.59758 + vertex 0.875438 1.81886 2.59593 + endloop + endfacet + facet normal -0.517288 0.168551 0.839049 + outer loop + vertex 0.874712 1.81152 2.59697 + vertex 0.877635 1.81043 2.59899 + vertex 0.878351 1.81619 2.59828 + endloop + endfacet + facet normal -0.535365 0.171568 0.827012 + outer loop + vertex 0.872347 1.81246 2.59527 + vertex 0.874551 1.8149 2.5962 + vertex 0.872143 1.81585 2.59444 + endloop + endfacet + facet normal -0.547151 0.169074 0.81978 + outer loop + vertex 0.872347 1.81246 2.59527 + vertex 0.872143 1.81585 2.59444 + vertex 0.86913 1.81172 2.59328 + endloop + endfacet + facet normal -0.555963 0.16535 0.814595 + outer loop + vertex 0.86752 1.80574 2.59339 + vertex 0.86913 1.81172 2.59328 + vertex 0.865241 1.8089 2.5912 + endloop + endfacet + facet normal -0.533495 0.163049 0.829939 + outer loop + vertex 0.874246 1.80694 2.59757 + vertex 0.874712 1.81152 2.59697 + vertex 0.87142 1.80865 2.59542 + endloop + endfacet + facet normal -0.522829 0.157285 0.837801 + outer loop + vertex 0.874047 1.80177 2.59842 + vertex 0.877143 1.80588 2.59958 + vertex 0.874246 1.80694 2.59757 + endloop + endfacet + facet normal -0.546695 0.158726 0.82215 + outer loop + vertex 0.86752 1.80574 2.59339 + vertex 0.867318 1.80052 2.59427 + vertex 0.870768 1.80374 2.59594 + endloop + endfacet + facet normal -0.554585 0.155806 0.817411 + outer loop + vertex 0.866871 1.79595 2.59484 + vertex 0.867318 1.80052 2.59427 + vertex 0.864003 1.79702 2.59269 + endloop + endfacet + facet normal -0.553493 0.158995 0.817537 + outer loop + vertex 0.863334 1.79127 2.59335 + vertex 0.866871 1.79595 2.59484 + vertex 0.864003 1.79702 2.59269 + endloop + endfacet + facet normal -0.534829 0.154966 0.830628 + outer loop + vertex 0.872462 1.79584 2.5985 + vertex 0.874047 1.80177 2.59842 + vertex 0.870132 1.79885 2.59644 + endloop + endfacet + facet normal -0.533929 0.156927 0.830839 + outer loop + vertex 0.869341 1.79177 2.59727 + vertex 0.872218 1.79065 2.59933 + vertex 0.872462 1.79584 2.5985 + endloop + endfacet + facet normal -0.544202 0.158579 0.823831 + outer loop + vertex 0.867012 1.79264 2.59557 + vertex 0.869206 1.79509 2.59654 + vertex 0.866871 1.79595 2.59484 + endloop + endfacet + facet normal -0.541934 0.159529 0.825142 + outer loop + vertex 0.868841 1.78719 2.59783 + vertex 0.869341 1.79177 2.59727 + vertex 0.866104 1.78877 2.59572 + endloop + endfacet + facet normal -0.551758 0.157203 0.819055 + outer loop + vertex 0.867012 1.79264 2.59557 + vertex 0.866871 1.79595 2.59484 + vertex 0.863334 1.79127 2.59335 + endloop + endfacet + facet normal -0.555618 0.158731 0.816145 + outer loop + vertex 0.866104 1.78877 2.59572 + vertex 0.862676 1.7855 2.59403 + vertex 0.86539 1.78397 2.59617 + endloop + endfacet + facet normal -0.570755 0.134907 0.809962 + outer loop + vertex 0.859493 1.78183 2.59239 + vertex 0.862676 1.7855 2.59403 + vertex 0.859837 1.78648 2.59186 + endloop + endfacet + facet normal -0.572612 0.1553 0.804983 + outer loop + vertex 0.859668 1.78987 2.59109 + vertex 0.857553 1.78733 2.59007 + vertex 0.859837 1.78648 2.59186 + endloop + endfacet + facet normal -0.579279 0.13492 0.803886 + outer loop + vertex 0.856818 1.78352 2.59018 + vertex 0.859837 1.78648 2.59186 + vertex 0.857553 1.78733 2.59007 + endloop + endfacet + facet normal -0.593956 0.137431 0.792672 + outer loop + vertex 0.857553 1.78733 2.59007 + vertex 0.854581 1.78647 2.58799 + vertex 0.856818 1.78352 2.59018 + endloop + endfacet + facet normal -0.596119 0.158363 0.787124 + outer loop + vertex 0.857553 1.78733 2.59007 + vertex 0.857336 1.7907 2.58923 + vertex 0.854581 1.78647 2.58799 + endloop + endfacet + facet normal -0.578572 0.162522 0.799275 + outer loop + vertex 0.857553 1.78733 2.59007 + vertex 0.859668 1.78987 2.59109 + vertex 0.857336 1.7907 2.58923 + endloop + endfacet + facet normal -0.579386 0.160845 0.799025 + outer loop + vertex 0.859178 1.80178 2.5883 + vertex 0.857496 1.79568 2.58831 + vertex 0.861341 1.79877 2.59048 + endloop + endfacet + facet normal -0.577434 0.165985 0.799386 + outer loop + vertex 0.860521 1.79386 2.59087 + vertex 0.857336 1.7907 2.58923 + vertex 0.859668 1.78987 2.59109 + endloop + endfacet + facet normal -0.590348 0.163855 0.790342 + outer loop + vertex 0.857496 1.79568 2.58831 + vertex 0.859178 1.80178 2.5883 + vertex 0.855332 1.79873 2.58606 + endloop + endfacet + facet normal -0.582099 0.16226 0.796764 + outer loop + vertex 0.859178 1.80178 2.5883 + vertex 0.862114 1.80604 2.58958 + vertex 0.859393 1.80675 2.58745 + endloop + endfacet + facet normal -0.599751 0.165266 0.782934 + outer loop + vertex 0.854159 1.80674 2.58348 + vertex 0.852497 1.80067 2.58349 + vertex 0.856305 1.80375 2.58575 + endloop + endfacet + facet normal -0.608757 0.167724 0.775425 + outer loop + vertex 0.852497 1.80067 2.58349 + vertex 0.854159 1.80674 2.58348 + vertex 0.85032 1.80363 2.58114 + endloop + endfacet + facet normal -0.60722 0.169503 0.776242 + outer loop + vertex 0.849453 1.7997 2.58132 + vertex 0.852497 1.80067 2.58349 + vertex 0.85032 1.80363 2.58114 + endloop + endfacet + facet normal -0.619607 0.17176 0.765889 + outer loop + vertex 0.85032 1.80363 2.58114 + vertex 0.847253 1.80065 2.57933 + vertex 0.849453 1.7997 2.58132 + endloop + endfacet + facet normal -0.61948 0.172109 0.765914 + outer loop + vertex 0.847508 1.79729 2.58029 + vertex 0.849453 1.7997 2.58132 + vertex 0.847253 1.80065 2.57933 + endloop + endfacet + facet normal -0.627349 0.16982 0.759996 + outer loop + vertex 0.847508 1.79729 2.58029 + vertex 0.847253 1.80065 2.57933 + vertex 0.844527 1.79648 2.57801 + endloop + endfacet + facet normal -0.627092 0.165778 0.7611 + outer loop + vertex 0.847508 1.79729 2.58029 + vertex 0.844527 1.79648 2.57801 + vertex 0.84672 1.79345 2.58047 + endloop + endfacet + facet normal -0.629486 0.171926 0.757753 + outer loop + vertex 0.844527 1.79648 2.57801 + vertex 0.847253 1.80065 2.57933 + vertex 0.844322 1.80154 2.57669 + endloop + endfacet + facet normal -0.636183 0.170289 0.752511 + outer loop + vertex 0.844527 1.79648 2.57801 + vertex 0.844322 1.80154 2.57669 + vertex 0.841521 1.79838 2.57504 + endloop + endfacet + facet normal -0.634246 0.174431 0.753197 + outer loop + vertex 0.841056 1.79358 2.57576 + vertex 0.844527 1.79648 2.57801 + vertex 0.841521 1.79838 2.57504 + endloop + endfacet + facet normal -0.641298 0.174222 0.747251 + outer loop + vertex 0.841521 1.79838 2.57504 + vertex 0.838652 1.79577 2.57318 + vertex 0.841056 1.79358 2.57576 + endloop + endfacet + facet normal -0.641221 0.174348 0.747287 + outer loop + vertex 0.838652 1.79577 2.57318 + vertex 0.838217 1.7912 2.57387 + vertex 0.841056 1.79358 2.57576 + endloop + endfacet + facet normal -0.636309 0.163167 0.753981 + outer loop + vertex 0.841056 1.79358 2.57576 + vertex 0.838217 1.7912 2.57387 + vertex 0.8403 1.78914 2.57608 + endloop + endfacet + facet normal -0.630834 0.162575 0.758695 + outer loop + vertex 0.8403 1.78914 2.57608 + vertex 0.843442 1.79101 2.57829 + vertex 0.841056 1.79358 2.57576 + endloop + endfacet + facet normal -0.629677 0.164242 0.759296 + outer loop + vertex 0.843442 1.79101 2.57829 + vertex 0.844527 1.79648 2.57801 + vertex 0.841056 1.79358 2.57576 + endloop + endfacet + facet normal -0.637531 0.172318 0.750906 + outer loop + vertex 0.841521 1.79838 2.57504 + vertex 0.844322 1.80154 2.57669 + vertex 0.841477 1.80283 2.57398 + endloop + endfacet + facet normal -0.644663 0.170873 0.745126 + outer loop + vertex 0.841477 1.80283 2.57398 + vertex 0.839121 1.80017 2.57255 + vertex 0.841521 1.79838 2.57504 + endloop + endfacet + facet normal -0.64488 0.171209 0.74486 + outer loop + vertex 0.839218 1.8036 2.57185 + vertex 0.839121 1.80017 2.57255 + vertex 0.841477 1.80283 2.57398 + endloop + endfacet + facet normal -0.646269 0.166664 0.744687 + outer loop + vertex 0.840827 1.80754 2.57236 + vertex 0.839218 1.8036 2.57185 + vertex 0.841477 1.80283 2.57398 + endloop + endfacet + facet normal -0.641414 0.168621 0.748435 + outer loop + vertex 0.840827 1.80754 2.57236 + vertex 0.841477 1.80283 2.57398 + vertex 0.843785 1.80573 2.5753 + endloop + endfacet + facet normal -0.645111 0.160382 0.747068 + outer loop + vertex 0.840827 1.80754 2.57236 + vertex 0.843785 1.80573 2.5753 + vertex 0.843361 1.8083 2.57438 + endloop + endfacet + facet normal -0.645624 0.167329 0.745097 + outer loop + vertex 0.843361 1.8083 2.57438 + vertex 0.843503 1.8113 2.57383 + vertex 0.840827 1.80754 2.57236 + endloop + endfacet + facet normal -0.645317 0.166974 0.745443 + outer loop + vertex 0.840827 1.80754 2.57236 + vertex 0.843503 1.8113 2.57383 + vertex 0.840958 1.81334 2.57117 + endloop + endfacet + facet normal -0.650901 0.166143 0.740759 + outer loop + vertex 0.840958 1.81334 2.57117 + vertex 0.837224 1.81034 2.56856 + vertex 0.840827 1.80754 2.57236 + endloop + endfacet + facet normal -0.649977 0.167895 0.741176 + outer loop + vertex 0.837224 1.81034 2.56856 + vertex 0.837235 1.80522 2.56973 + vertex 0.840827 1.80754 2.57236 + endloop + endfacet + facet normal -0.651282 0.167096 0.74021 + outer loop + vertex 0.838444 1.81589 2.56839 + vertex 0.837224 1.81034 2.56856 + vertex 0.840958 1.81334 2.57117 + endloop + endfacet + facet normal -0.649817 0.169379 0.740979 + outer loop + vertex 0.841672 1.81858 2.5706 + vertex 0.838444 1.81589 2.56839 + vertex 0.840958 1.81334 2.57117 + endloop + endfacet + facet normal -0.643211 0.169113 0.74678 + outer loop + vertex 0.840958 1.81334 2.57117 + vertex 0.844408 1.81654 2.57342 + vertex 0.841672 1.81858 2.5706 + endloop + endfacet + facet normal -0.641768 0.171885 0.747388 + outer loop + vertex 0.844408 1.81654 2.57342 + vertex 0.844507 1.82153 2.57236 + vertex 0.841672 1.81858 2.5706 + endloop + endfacet + facet normal -0.6421 0.172452 0.746973 + outer loop + vertex 0.841672 1.81858 2.5706 + vertex 0.844507 1.82153 2.57236 + vertex 0.842442 1.82253 2.57035 + endloop + endfacet + facet normal -0.650889 0.173664 0.739043 + outer loop + vertex 0.842442 1.82253 2.57035 + vertex 0.83955 1.82145 2.56806 + vertex 0.841672 1.81858 2.5706 + endloop + endfacet + facet normal -0.651525 0.179608 0.737059 + outer loop + vertex 0.842442 1.82253 2.57035 + vertex 0.842224 1.82579 2.56936 + vertex 0.83955 1.82145 2.56806 + endloop + endfacet + facet normal -0.651265 0.17936 0.737349 + outer loop + vertex 0.83955 1.82145 2.56806 + vertex 0.842224 1.82579 2.56936 + vertex 0.839361 1.82641 2.56668 + endloop + endfacet + facet normal -0.65619 0.178049 0.733289 + outer loop + vertex 0.83955 1.82145 2.56806 + vertex 0.839361 1.82641 2.56668 + vertex 0.83653 1.82307 2.56496 + endloop + endfacet + facet normal -0.656911 0.176284 0.73307 + outer loop + vertex 0.836166 1.8183 2.56578 + vertex 0.83955 1.82145 2.56806 + vertex 0.83653 1.82307 2.56496 + endloop + endfacet + facet normal -0.663082 0.175817 0.727607 + outer loop + vertex 0.83653 1.82307 2.56496 + vertex 0.833736 1.82043 2.56306 + vertex 0.836166 1.8183 2.56578 + endloop + endfacet + facet normal -0.663224 0.175565 0.727537 + outer loop + vertex 0.833736 1.82043 2.56306 + vertex 0.833434 1.81598 2.56385 + vertex 0.836166 1.8183 2.56578 + endloop + endfacet + facet normal -0.662084 0.172808 0.729234 + outer loop + vertex 0.836166 1.8183 2.56578 + vertex 0.833434 1.81598 2.56385 + vertex 0.835346 1.81388 2.56609 + endloop + endfacet + facet normal -0.65666 0.172148 0.734277 + outer loop + vertex 0.835346 1.81388 2.56609 + vertex 0.838444 1.81589 2.56839 + vertex 0.836166 1.8183 2.56578 + endloop + endfacet + facet normal -0.655654 0.173677 0.734815 + outer loop + vertex 0.838444 1.81589 2.56839 + vertex 0.83955 1.82145 2.56806 + vertex 0.836166 1.8183 2.56578 + endloop + endfacet + facet normal -0.657265 0.179656 0.731933 + outer loop + vertex 0.83653 1.82307 2.56496 + vertex 0.839361 1.82641 2.56668 + vertex 0.836393 1.82771 2.5637 + endloop + endfacet + facet normal -0.664125 0.177881 0.726152 + outer loop + vertex 0.836393 1.82771 2.5637 + vertex 0.833806 1.82504 2.56199 + vertex 0.83653 1.82307 2.56496 + endloop + endfacet + facet normal -0.665364 0.180183 0.724448 + outer loop + vertex 0.83362 1.82955 2.5607 + vertex 0.833806 1.82504 2.56199 + vertex 0.836393 1.82771 2.5637 + endloop + endfacet + facet normal -0.665755 0.179347 0.724296 + outer loop + vertex 0.83611 1.83272 2.5622 + vertex 0.83362 1.82955 2.5607 + vertex 0.836393 1.82771 2.5637 + endloop + endfacet + facet normal -0.658393 0.181601 0.730438 + outer loop + vertex 0.83611 1.83272 2.5622 + vertex 0.836393 1.82771 2.5637 + vertex 0.838895 1.83059 2.56524 + endloop + endfacet + facet normal -0.660196 0.178146 0.729661 + outer loop + vertex 0.83611 1.83272 2.5622 + vertex 0.838895 1.83059 2.56524 + vertex 0.838506 1.83313 2.56427 + endloop + endfacet + facet normal -0.660008 0.18542 0.728017 + outer loop + vertex 0.838506 1.83313 2.56427 + vertex 0.838551 1.83598 2.56358 + vertex 0.83611 1.83272 2.5622 + endloop + endfacet + facet normal -0.659218 0.184416 0.728987 + outer loop + vertex 0.83611 1.83272 2.5622 + vertex 0.838551 1.83598 2.56358 + vertex 0.836326 1.83794 2.56107 + endloop + endfacet + facet normal -0.666951 0.183274 0.722209 + outer loop + vertex 0.836326 1.83794 2.56107 + vertex 0.833619 1.83584 2.55911 + vertex 0.83611 1.83272 2.5622 + endloop + endfacet + facet normal -0.668356 0.18725 0.719887 + outer loop + vertex 0.834312 1.8413 2.55833 + vertex 0.833619 1.83584 2.55911 + vertex 0.836326 1.83794 2.56107 + endloop + endfacet + facet normal -0.667274 0.188462 0.720574 + outer loop + vertex 0.837033 1.84177 2.56073 + vertex 0.834312 1.8413 2.55833 + vertex 0.836326 1.83794 2.56107 + endloop + endfacet + facet normal -0.657253 0.187463 0.729983 + outer loop + vertex 0.836326 1.83794 2.56107 + vertex 0.838837 1.84019 2.56276 + vertex 0.837033 1.84177 2.56073 + endloop + endfacet + facet normal -0.654655 0.191927 0.731158 + outer loop + vertex 0.838947 1.84369 2.56194 + vertex 0.837033 1.84177 2.56073 + vertex 0.838837 1.84019 2.56276 + endloop + endfacet + facet normal -0.648221 0.192996 0.736588 + outer loop + vertex 0.838947 1.84369 2.56194 + vertex 0.838837 1.84019 2.56276 + vertex 0.841231 1.843 2.56413 + endloop + endfacet + facet normal -0.647184 0.196432 0.736591 + outer loop + vertex 0.840747 1.84774 2.56244 + vertex 0.838947 1.84369 2.56194 + vertex 0.841231 1.843 2.56413 + endloop + endfacet + facet normal -0.655275 0.201078 0.728137 + outer loop + vertex 0.840747 1.84774 2.56244 + vertex 0.837062 1.8453 2.5598 + vertex 0.838947 1.84369 2.56194 + endloop + endfacet + facet normal -0.647132 0.1914 0.737961 + outer loop + vertex 0.841231 1.843 2.56413 + vertex 0.838837 1.84019 2.56276 + vertex 0.841232 1.83855 2.56528 + endloop + endfacet + facet normal -0.643246 0.192226 0.741137 + outer loop + vertex 0.841232 1.83855 2.56528 + vertex 0.844087 1.84165 2.56696 + vertex 0.841231 1.843 2.56413 + endloop + endfacet + facet normal -0.643045 0.192739 0.741178 + outer loop + vertex 0.84363 1.84595 2.56544 + vertex 0.841231 1.843 2.56413 + vertex 0.844087 1.84165 2.56696 + endloop + endfacet + facet normal -0.642257 0.190635 0.742404 + outer loop + vertex 0.84413 1.83653 2.56831 + vertex 0.844087 1.84165 2.56696 + vertex 0.841232 1.83855 2.56528 + endloop + endfacet + facet normal -0.643246 0.18868 0.742047 + outer loop + vertex 0.840617 1.83411 2.56588 + vertex 0.84413 1.83653 2.56831 + vertex 0.841232 1.83855 2.56528 + endloop + endfacet + facet normal -0.648673 0.188793 0.73728 + outer loop + vertex 0.841232 1.83855 2.56528 + vertex 0.838551 1.83598 2.56358 + vertex 0.840617 1.83411 2.56588 + endloop + endfacet + facet normal -0.643035 0.188022 0.742397 + outer loop + vertex 0.842386 1.83071 2.56827 + vertex 0.84413 1.83653 2.56831 + vertex 0.840617 1.83411 2.56588 + endloop + endfacet + facet normal -0.648327 0.182917 0.739063 + outer loop + vertex 0.838895 1.83059 2.56524 + vertex 0.842386 1.83071 2.56827 + vertex 0.840617 1.83411 2.56588 + endloop + endfacet + facet normal -0.648296 0.183224 0.739014 + outer loop + vertex 0.838895 1.83059 2.56524 + vertex 0.839361 1.82641 2.56668 + vertex 0.842386 1.83071 2.56827 + endloop + endfacet + facet normal -0.64136 0.187509 0.743974 + outer loop + vertex 0.84413 1.83653 2.56831 + vertex 0.842386 1.83071 2.56827 + vertex 0.846064 1.83326 2.5708 + endloop + endfacet + facet normal -0.639291 0.189674 0.745206 + outer loop + vertex 0.847125 1.83693 2.57078 + vertex 0.84413 1.83653 2.56831 + vertex 0.846064 1.83326 2.5708 + endloop + endfacet + facet normal -0.634563 0.188333 0.749573 + outer loop + vertex 0.846064 1.83326 2.5708 + vertex 0.848932 1.8353 2.57272 + vertex 0.847125 1.83693 2.57078 + endloop + endfacet + facet normal -0.633751 0.189653 0.749927 + outer loop + vertex 0.849091 1.83867 2.572 + vertex 0.847125 1.83693 2.57078 + vertex 0.848932 1.8353 2.57272 + endloop + endfacet + facet normal -0.634093 0.186975 0.750311 + outer loop + vertex 0.848306 1.83085 2.5733 + vertex 0.848932 1.8353 2.57272 + vertex 0.846064 1.83326 2.5708 + endloop + endfacet + facet normal -0.634081 0.186992 0.750317 + outer loop + vertex 0.845131 1.8286 2.57117 + vertex 0.848306 1.83085 2.5733 + vertex 0.846064 1.83326 2.5708 + endloop + endfacet + facet normal -0.632935 0.183697 0.752096 + outer loop + vertex 0.847288 1.82542 2.57377 + vertex 0.848306 1.83085 2.5733 + vertex 0.845131 1.8286 2.57117 + endloop + endfacet + facet normal -0.632185 0.184551 0.752518 + outer loop + vertex 0.844317 1.8249 2.5714 + vertex 0.847288 1.82542 2.57377 + vertex 0.845131 1.8286 2.57117 + endloop + endfacet + facet normal -0.642554 0.186281 0.743253 + outer loop + vertex 0.845131 1.8286 2.57117 + vertex 0.842224 1.82579 2.56936 + vertex 0.844317 1.8249 2.5714 + endloop + endfacet + facet normal -0.64248 0.186142 0.743351 + outer loop + vertex 0.842386 1.83071 2.56827 + vertex 0.842224 1.82579 2.56936 + vertex 0.845131 1.8286 2.57117 + endloop + endfacet + facet normal -0.632242 0.179205 0.753761 + outer loop + vertex 0.844317 1.8249 2.5714 + vertex 0.844507 1.82153 2.57236 + vertex 0.847288 1.82542 2.57377 + endloop + endfacet + facet normal -0.632132 0.179083 0.753882 + outer loop + vertex 0.844507 1.82153 2.57236 + vertex 0.847159 1.82037 2.57486 + vertex 0.847288 1.82542 2.57377 + endloop + endfacet + facet normal -0.624829 0.180151 0.759693 + outer loop + vertex 0.847288 1.82542 2.57377 + vertex 0.847159 1.82037 2.57486 + vertex 0.850795 1.82254 2.57733 + endloop + endfacet + facet normal -0.625411 0.179145 0.759453 + outer loop + vertex 0.850928 1.82834 2.57607 + vertex 0.847288 1.82542 2.57377 + vertex 0.850795 1.82254 2.57733 + endloop + endfacet + facet normal -0.620392 0.179884 0.763384 + outer loop + vertex 0.850795 1.82254 2.57733 + vertex 0.853571 1.82621 2.57872 + vertex 0.850928 1.82834 2.57607 + endloop + endfacet + facet normal -0.618533 0.183118 0.764124 + outer loop + vertex 0.853571 1.82621 2.57872 + vertex 0.854415 1.83147 2.57815 + vertex 0.850928 1.82834 2.57607 + endloop + endfacet + facet normal -0.619332 0.184686 0.763098 + outer loop + vertex 0.850928 1.82834 2.57607 + vertex 0.854415 1.83147 2.57815 + vertex 0.851356 1.83344 2.57519 + endloop + endfacet + facet normal -0.62625 0.184299 0.757526 + outer loop + vertex 0.851356 1.83344 2.57519 + vertex 0.848306 1.83085 2.5733 + vertex 0.850928 1.82834 2.57607 + endloop + endfacet + facet normal -0.618195 0.186997 0.763457 + outer loop + vertex 0.854415 1.83147 2.57815 + vertex 0.8542 1.83657 2.57672 + vertex 0.851356 1.83344 2.57519 + endloop + endfacet + facet normal -0.624751 0.179872 0.759824 + outer loop + vertex 0.850795 1.82254 2.57733 + vertex 0.847159 1.82037 2.57486 + vertex 0.84908 1.81861 2.57685 + endloop + endfacet + facet normal -0.616513 0.17534 0.767573 + outer loop + vertex 0.850795 1.82254 2.57733 + vertex 0.84908 1.81861 2.57685 + vertex 0.85143 1.81777 2.57893 + endloop + endfacet + facet normal -0.614237 0.176189 0.769201 + outer loop + vertex 0.850795 1.82254 2.57733 + vertex 0.85143 1.81777 2.57893 + vertex 0.853838 1.82063 2.5802 + endloop + endfacet + facet normal -0.617639 0.171871 0.767452 + outer loop + vertex 0.84908 1.81861 2.57685 + vertex 0.848989 1.81515 2.57755 + vertex 0.85143 1.81777 2.57893 + endloop + endfacet + facet normal -0.616249 0.169736 0.769043 + outer loop + vertex 0.85143 1.81777 2.57893 + vertex 0.848989 1.81515 2.57755 + vertex 0.851481 1.81342 2.57993 + endloop + endfacet + facet normal -0.609408 0.171004 0.774196 + outer loop + vertex 0.851481 1.81342 2.57993 + vertex 0.854364 1.81651 2.58152 + vertex 0.85143 1.81777 2.57893 + endloop + endfacet + facet normal -0.608416 0.169516 0.775303 + outer loop + vertex 0.854315 1.81188 2.58249 + vertex 0.854364 1.81651 2.58152 + vertex 0.851481 1.81342 2.57993 + endloop + endfacet + facet normal -0.609266 0.167544 0.775064 + outer loop + vertex 0.851056 1.80863 2.58063 + vertex 0.854315 1.81188 2.58249 + vertex 0.851481 1.81342 2.57993 + endloop + endfacet + facet normal -0.617505 0.167328 0.768563 + outer loop + vertex 0.851481 1.81342 2.57993 + vertex 0.848451 1.81082 2.57807 + vertex 0.851056 1.80863 2.58063 + endloop + endfacet + facet normal -0.618778 0.165156 0.768009 + outer loop + vertex 0.848451 1.81082 2.57807 + vertex 0.847265 1.80563 2.57822 + vertex 0.851056 1.80863 2.58063 + endloop + endfacet + facet normal -0.620207 0.168467 0.766135 + outer loop + vertex 0.851056 1.80863 2.58063 + vertex 0.847265 1.80563 2.57822 + vertex 0.85032 1.80363 2.58114 + endloop + endfacet + facet normal -0.609025 0.167145 0.775339 + outer loop + vertex 0.854159 1.80674 2.58348 + vertex 0.854315 1.81188 2.58249 + vertex 0.851056 1.80863 2.58063 + endloop + endfacet + facet normal -0.617495 0.167309 0.768575 + outer loop + vertex 0.848989 1.81515 2.57755 + vertex 0.848451 1.81082 2.57807 + vertex 0.851481 1.81342 2.57993 + endloop + endfacet + facet normal -0.626405 0.167553 0.761277 + outer loop + vertex 0.848451 1.81082 2.57807 + vertex 0.848989 1.81515 2.57755 + vertex 0.846299 1.8133 2.57575 + endloop + endfacet + facet normal -0.62709 0.166623 0.760917 + outer loop + vertex 0.845437 1.80908 2.57596 + vertex 0.848451 1.81082 2.57807 + vertex 0.846299 1.8133 2.57575 + endloop + endfacet + facet normal -0.636035 0.168055 0.753138 + outer loop + vertex 0.846299 1.8133 2.57575 + vertex 0.843503 1.8113 2.57383 + vertex 0.845437 1.80908 2.57596 + endloop + endfacet + facet normal -0.636466 0.169269 0.752501 + outer loop + vertex 0.844408 1.81654 2.57342 + vertex 0.843503 1.8113 2.57383 + vertex 0.846299 1.8133 2.57575 + endloop + endfacet + facet normal -0.635799 0.169953 0.752911 + outer loop + vertex 0.847151 1.81689 2.57566 + vertex 0.844408 1.81654 2.57342 + vertex 0.846299 1.8133 2.57575 + endloop + endfacet + facet normal -0.63564 0.174481 0.75201 + outer loop + vertex 0.847151 1.81689 2.57566 + vertex 0.847159 1.82037 2.57486 + vertex 0.844408 1.81654 2.57342 + endloop + endfacet + facet normal -0.627152 0.166851 0.760816 + outer loop + vertex 0.847265 1.80563 2.57822 + vertex 0.848451 1.81082 2.57807 + vertex 0.845437 1.80908 2.57596 + endloop + endfacet + facet normal -0.631972 0.162314 0.757803 + outer loop + vertex 0.843785 1.80573 2.5753 + vertex 0.847265 1.80563 2.57822 + vertex 0.845437 1.80908 2.57596 + endloop + endfacet + facet normal -0.631063 0.169663 0.756951 + outer loop + vertex 0.843785 1.80573 2.5753 + vertex 0.844322 1.80154 2.57669 + vertex 0.847265 1.80563 2.57822 + endloop + endfacet + facet normal -0.626547 0.16796 0.761071 + outer loop + vertex 0.846299 1.8133 2.57575 + vertex 0.848989 1.81515 2.57755 + vertex 0.847151 1.81689 2.57566 + endloop + endfacet + facet normal -0.624653 0.170944 0.761962 + outer loop + vertex 0.84908 1.81861 2.57685 + vertex 0.847151 1.81689 2.57566 + vertex 0.848989 1.81515 2.57755 + endloop + endfacet + facet normal -0.627166 0.176009 0.758738 + outer loop + vertex 0.847151 1.81689 2.57566 + vertex 0.84908 1.81861 2.57685 + vertex 0.847159 1.82037 2.57486 + endloop + endfacet + facet normal -0.627069 0.183033 0.757155 + outer loop + vertex 0.848306 1.83085 2.5733 + vertex 0.847288 1.82542 2.57377 + vertex 0.850928 1.82834 2.57607 + endloop + endfacet + facet normal -0.627391 0.186772 0.755974 + outer loop + vertex 0.848932 1.8353 2.57272 + vertex 0.848306 1.83085 2.5733 + vertex 0.851356 1.83344 2.57519 + endloop + endfacet + facet normal -0.626752 0.187928 0.756217 + outer loop + vertex 0.851349 1.83787 2.57408 + vertex 0.848932 1.8353 2.57272 + vertex 0.851356 1.83344 2.57519 + endloop + endfacet + facet normal -0.639214 0.191393 0.744831 + outer loop + vertex 0.847125 1.83693 2.57078 + vertex 0.847088 1.84033 2.56987 + vertex 0.84413 1.83653 2.56831 + endloop + endfacet + facet normal -0.641502 0.187946 0.743741 + outer loop + vertex 0.846064 1.83326 2.5708 + vertex 0.842386 1.83071 2.56827 + vertex 0.845131 1.8286 2.57117 + endloop + endfacet + facet normal -0.639157 0.19132 0.7449 + outer loop + vertex 0.84413 1.83653 2.56831 + vertex 0.847088 1.84033 2.56987 + vertex 0.844087 1.84165 2.56696 + endloop + endfacet + facet normal -0.648548 0.188548 0.737452 + outer loop + vertex 0.838837 1.84019 2.56276 + vertex 0.838551 1.83598 2.56358 + vertex 0.841232 1.83855 2.56528 + endloop + endfacet + facet normal -0.657479 0.197242 0.727198 + outer loop + vertex 0.837033 1.84177 2.56073 + vertex 0.838947 1.84369 2.56194 + vertex 0.837062 1.8453 2.5598 + endloop + endfacet + facet normal -0.65734 0.187656 0.729856 + outer loop + vertex 0.838551 1.83598 2.56358 + vertex 0.838837 1.84019 2.56276 + vertex 0.836326 1.83794 2.56107 + endloop + endfacet + facet normal -0.649518 0.187387 0.736894 + outer loop + vertex 0.838551 1.83598 2.56358 + vertex 0.838506 1.83313 2.56427 + vertex 0.840617 1.83411 2.56588 + endloop + endfacet + facet normal -0.648846 0.183269 0.738519 + outer loop + vertex 0.840617 1.83411 2.56588 + vertex 0.838506 1.83313 2.56427 + vertex 0.838895 1.83059 2.56524 + endloop + endfacet + facet normal -0.657221 0.179779 0.731943 + outer loop + vertex 0.838895 1.83059 2.56524 + vertex 0.836393 1.82771 2.5637 + vertex 0.839361 1.82641 2.56668 + endloop + endfacet + facet normal -0.649877 0.185016 0.737177 + outer loop + vertex 0.839361 1.82641 2.56668 + vertex 0.842224 1.82579 2.56936 + vertex 0.842386 1.83071 2.56827 + endloop + endfacet + facet normal -0.644142 0.181887 0.742966 + outer loop + vertex 0.842442 1.82253 2.57035 + vertex 0.844317 1.8249 2.5714 + vertex 0.842224 1.82579 2.56936 + endloop + endfacet + facet normal -0.640358 0.176942 0.747418 + outer loop + vertex 0.844317 1.8249 2.5714 + vertex 0.842442 1.82253 2.57035 + vertex 0.844507 1.82153 2.57236 + endloop + endfacet + facet normal -0.634355 0.173026 0.75343 + outer loop + vertex 0.844408 1.81654 2.57342 + vertex 0.847159 1.82037 2.57486 + vertex 0.844507 1.82153 2.57236 + endloop + endfacet + facet normal -0.651369 0.17306 0.738761 + outer loop + vertex 0.83955 1.82145 2.56806 + vertex 0.838444 1.81589 2.56839 + vertex 0.841672 1.81858 2.5706 + endloop + endfacet + facet normal -0.655444 0.167888 0.736347 + outer loop + vertex 0.837224 1.81034 2.56856 + vertex 0.838444 1.81589 2.56839 + vertex 0.835346 1.81388 2.56609 + endloop + endfacet + facet normal -0.658055 0.165282 0.734606 + outer loop + vertex 0.833719 1.81067 2.56535 + vertex 0.837224 1.81034 2.56856 + vertex 0.835346 1.81388 2.56609 + endloop + endfacet + facet normal -0.65751 0.168567 0.734347 + outer loop + vertex 0.833719 1.81067 2.56535 + vertex 0.834245 1.80646 2.56679 + vertex 0.837224 1.81034 2.56856 + endloop + endfacet + facet normal -0.643662 0.170016 0.746186 + outer loop + vertex 0.843503 1.8113 2.57383 + vertex 0.844408 1.81654 2.57342 + vertex 0.840958 1.81334 2.57117 + endloop + endfacet + facet normal -0.635812 0.168363 0.753257 + outer loop + vertex 0.843503 1.8113 2.57383 + vertex 0.843361 1.8083 2.57438 + vertex 0.845437 1.80908 2.57596 + endloop + endfacet + facet normal -0.635342 0.164628 0.754478 + outer loop + vertex 0.845437 1.80908 2.57596 + vertex 0.843361 1.8083 2.57438 + vertex 0.843785 1.80573 2.5753 + endloop + endfacet + facet normal -0.650241 0.168799 0.740738 + outer loop + vertex 0.840827 1.80754 2.57236 + vertex 0.837235 1.80522 2.56973 + vertex 0.839218 1.8036 2.57185 + endloop + endfacet + facet normal -0.639717 0.166378 0.750387 + outer loop + vertex 0.843785 1.80573 2.5753 + vertex 0.841477 1.80283 2.57398 + vertex 0.844322 1.80154 2.57669 + endloop + endfacet + facet normal -0.630368 0.16888 0.757704 + outer loop + vertex 0.844322 1.80154 2.57669 + vertex 0.847253 1.80065 2.57933 + vertex 0.847265 1.80563 2.57822 + endloop + endfacet + facet normal -0.615341 0.16685 0.770401 + outer loop + vertex 0.849453 1.7997 2.58132 + vertex 0.847508 1.79729 2.58029 + vertex 0.849631 1.79638 2.58218 + endloop + endfacet + facet normal -0.619064 0.170803 0.766542 + outer loop + vertex 0.847265 1.80563 2.57822 + vertex 0.847253 1.80065 2.57933 + vertex 0.85032 1.80363 2.58114 + endloop + endfacet + facet normal -0.607152 0.168853 0.776437 + outer loop + vertex 0.849453 1.7997 2.58132 + vertex 0.849631 1.79638 2.58218 + vertex 0.852497 1.80067 2.58349 + endloop + endfacet + facet normal -0.608755 0.16772 0.775427 + outer loop + vertex 0.85032 1.80363 2.58114 + vertex 0.854159 1.80674 2.58348 + vertex 0.851056 1.80863 2.58063 + endloop + endfacet + facet normal -0.601483 0.168006 0.78102 + outer loop + vertex 0.854159 1.80674 2.58348 + vertex 0.857115 1.81092 2.58486 + vertex 0.854315 1.81188 2.58249 + endloop + endfacet + facet normal -0.600511 0.171052 0.781107 + outer loop + vertex 0.857115 1.81092 2.58486 + vertex 0.857406 1.81534 2.58411 + vertex 0.854315 1.81188 2.58249 + endloop + endfacet + facet normal -0.589665 0.164911 0.790632 + outer loop + vertex 0.859244 1.81006 2.58665 + vertex 0.857254 1.80768 2.58566 + vertex 0.859393 1.80675 2.58745 + endloop + endfacet + facet normal -0.590741 0.171634 0.788395 + outer loop + vertex 0.857406 1.81534 2.58411 + vertex 0.857115 1.81092 2.58486 + vertex 0.860143 1.81381 2.5865 + endloop + endfacet + facet normal -0.579797 0.167009 0.79746 + outer loop + vertex 0.859244 1.81006 2.58665 + vertex 0.859393 1.80675 2.58745 + vertex 0.862308 1.81094 2.58869 + endloop + endfacet + facet normal -0.568793 0.172577 0.804171 + outer loop + vertex 0.863944 1.8169 2.58859 + vertex 0.866966 1.82103 2.58984 + vertex 0.864191 1.82201 2.58767 + endloop + endfacet + facet normal -0.590798 0.172241 0.78822 + outer loop + vertex 0.859328 1.82645 2.58312 + vertex 0.857544 1.82061 2.58306 + vertex 0.861471 1.82353 2.58537 + endloop + endfacet + facet normal -0.590315 0.172573 0.788509 + outer loop + vertex 0.86079 1.81866 2.58592 + vertex 0.857406 1.81534 2.58411 + vertex 0.860143 1.81381 2.5865 + endloop + endfacet + facet normal -0.600264 0.170707 0.781372 + outer loop + vertex 0.854315 1.81188 2.58249 + vertex 0.857406 1.81534 2.58411 + vertex 0.854364 1.81651 2.58152 + endloop + endfacet + facet normal -0.609706 0.170191 0.77414 + outer loop + vertex 0.853838 1.82063 2.5802 + vertex 0.85143 1.81777 2.57893 + vertex 0.854364 1.81651 2.58152 + endloop + endfacet + facet normal -0.618382 0.167496 0.767821 + outer loop + vertex 0.850795 1.82254 2.57733 + vertex 0.853838 1.82063 2.5802 + vertex 0.853404 1.82319 2.57929 + endloop + endfacet + facet normal -0.618916 0.178164 0.764984 + outer loop + vertex 0.853404 1.82319 2.57929 + vertex 0.853571 1.82621 2.57872 + vertex 0.850795 1.82254 2.57733 + endloop + endfacet + facet normal -0.596744 0.174114 0.783314 + outer loop + vertex 0.857544 1.82061 2.58306 + vertex 0.859328 1.82645 2.58312 + vertex 0.85566 1.82407 2.58086 + endloop + endfacet + facet normal -0.587014 0.179351 0.789461 + outer loop + vertex 0.859328 1.82645 2.58312 + vertex 0.862274 1.83063 2.58436 + vertex 0.859548 1.83124 2.5822 + endloop + endfacet + facet normal -0.610083 0.182519 0.771029 + outer loop + vertex 0.854415 1.83147 2.57815 + vertex 0.853571 1.82621 2.57872 + vertex 0.856596 1.82847 2.58058 + endloop + endfacet + facet normal -0.610749 0.188852 0.768973 + outer loop + vertex 0.854415 1.83147 2.57815 + vertex 0.857145 1.83561 2.5793 + vertex 0.8542 1.83657 2.57672 + endloop + endfacet + facet normal -0.594544 0.185804 0.782301 + outer loop + vertex 0.859365 1.83458 2.58127 + vertex 0.857379 1.83219 2.58032 + vertex 0.859548 1.83124 2.5822 + endloop + endfacet + facet normal -0.597261 0.194529 0.778099 + outer loop + vertex 0.857338 1.8407 2.57817 + vertex 0.857145 1.83561 2.5793 + vertex 0.860322 1.83854 2.581 + endloop + endfacet + facet normal -0.584695 0.188241 0.789111 + outer loop + vertex 0.859365 1.83458 2.58127 + vertex 0.859548 1.83124 2.5822 + vertex 0.862518 1.83553 2.58338 + endloop + endfacet + facet normal -0.596109 0.189866 0.780131 + outer loop + vertex 0.862342 1.84738 2.58038 + vertex 0.862203 1.85071 2.57946 + vertex 0.85925 1.84653 2.57822 + endloop + endfacet + facet normal -0.597972 0.193247 0.777872 + outer loop + vertex 0.861336 1.84349 2.58056 + vertex 0.857338 1.8407 2.57817 + vertex 0.860322 1.83854 2.581 + endloop + endfacet + facet normal -0.609423 0.192978 0.769001 + outer loop + vertex 0.8542 1.83657 2.57672 + vertex 0.857145 1.83561 2.5793 + vertex 0.857338 1.8407 2.57817 + endloop + endfacet + facet normal -0.61974 0.189293 0.761637 + outer loop + vertex 0.851356 1.83344 2.57519 + vertex 0.8542 1.83657 2.57672 + vertex 0.851349 1.83787 2.57408 + endloop + endfacet + facet normal -0.628269 0.190338 0.754354 + outer loop + vertex 0.849091 1.83867 2.572 + vertex 0.848932 1.8353 2.57272 + vertex 0.851349 1.83787 2.57408 + endloop + endfacet + facet normal -0.635021 0.192328 0.74817 + outer loop + vertex 0.847125 1.83693 2.57078 + vertex 0.849091 1.83867 2.572 + vertex 0.847088 1.84033 2.56987 + endloop + endfacet + facet normal -0.639096 0.191483 0.74491 + outer loop + vertex 0.844087 1.84165 2.56696 + vertex 0.847088 1.84033 2.56987 + vertex 0.847137 1.84549 2.56859 + endloop + endfacet + facet normal -0.62679 0.191263 0.755349 + outer loop + vertex 0.85334 1.84321 2.57438 + vertex 0.853532 1.84618 2.57379 + vertex 0.850749 1.84251 2.57241 + endloop + endfacet + facet normal -0.614898 0.191066 0.76511 + outer loop + vertex 0.854428 1.85146 2.57319 + vertex 0.853532 1.84618 2.57379 + vertex 0.856576 1.84854 2.57564 + endloop + endfacet + facet normal -0.641254 0.191456 0.74306 + outer loop + vertex 0.849032 1.85846 2.56693 + vertex 0.847128 1.85672 2.56573 + vertex 0.848862 1.85507 2.56766 + endloop + endfacet + facet normal -0.634373 0.185819 0.750362 + outer loop + vertex 0.848862 1.85507 2.56766 + vertex 0.848268 1.85074 2.56823 + vertex 0.851305 1.85327 2.57017 + endloop + endfacet + facet normal -0.635037 0.188166 0.749214 + outer loop + vertex 0.848268 1.85074 2.56823 + vertex 0.847137 1.84549 2.56859 + vertex 0.850863 1.84818 2.57107 + endloop + endfacet + facet normal -0.640726 0.193611 0.742957 + outer loop + vertex 0.84363 1.84595 2.56544 + vertex 0.844087 1.84165 2.56696 + vertex 0.847137 1.84549 2.56859 + endloop + endfacet + facet normal -0.646071 0.196853 0.737455 + outer loop + vertex 0.840747 1.84774 2.56244 + vertex 0.841231 1.843 2.56413 + vertex 0.84363 1.84595 2.56544 + endloop + endfacet + facet normal -0.645016 0.193182 0.739348 + outer loop + vertex 0.84351 1.85144 2.56391 + vertex 0.843297 1.84859 2.56446 + vertex 0.845337 1.84924 2.56607 + endloop + endfacet + facet normal -0.648298 0.191017 0.737036 + outer loop + vertex 0.844388 1.85637 2.5634 + vertex 0.84351 1.85144 2.56391 + vertex 0.846246 1.8533 2.56583 + endloop + endfacet + facet normal -0.648584 0.195383 0.735639 + outer loop + vertex 0.844388 1.85637 2.5634 + vertex 0.847119 1.8601 2.56482 + vertex 0.844181 1.86135 2.56189 + endloop + endfacet + facet normal -0.640795 0.216041 0.736687 + outer loop + vertex 0.844181 1.86135 2.56189 + vertex 0.847119 1.8601 2.56482 + vertex 0.847209 1.8651 2.56343 + endloop + endfacet + facet normal -0.666628 0.198613 0.718443 + outer loop + vertex 0.838512 1.86472 2.55578 + vertex 0.838652 1.86021 2.55716 + vertex 0.841253 1.86292 2.55882 + endloop + endfacet + facet normal -0.661179 0.209952 0.720252 + outer loop + vertex 0.84106 1.86801 2.55716 + vertex 0.838512 1.86472 2.55578 + vertex 0.841253 1.86292 2.55882 + endloop + endfacet + facet normal -0.660789 0.193787 0.725124 + outer loop + vertex 0.841366 1.85824 2.56019 + vertex 0.83839 1.85556 2.5582 + vertex 0.840997 1.85328 2.56118 + endloop + endfacet + facet normal -0.658472 0.197782 0.726152 + outer loop + vertex 0.83839 1.85556 2.5582 + vertex 0.837298 1.85038 2.55862 + vertex 0.840997 1.85328 2.56118 + endloop + endfacet + facet normal -0.654896 0.199738 0.728846 + outer loop + vertex 0.837298 1.85038 2.55862 + vertex 0.837062 1.8453 2.5598 + vertex 0.840747 1.84774 2.56244 + endloop + endfacet + facet normal -0.667052 0.195158 0.718996 + outer loop + vertex 0.837033 1.84177 2.56073 + vertex 0.837062 1.8453 2.5598 + vertex 0.834312 1.8413 2.55833 + endloop + endfacet + facet normal -0.687721 0.186913 0.701501 + outer loop + vertex 0.831347 1.84327 2.55499 + vertex 0.82859 1.84053 2.55302 + vertex 0.831119 1.83823 2.55611 + endloop + endfacet + facet normal -0.688382 0.185737 0.701165 + outer loop + vertex 0.82859 1.84053 2.55302 + vertex 0.828427 1.83581 2.55411 + vertex 0.831119 1.83823 2.55611 + endloop + endfacet + facet normal -0.675861 0.187204 0.712858 + outer loop + vertex 0.833619 1.83584 2.55911 + vertex 0.834312 1.8413 2.55833 + vertex 0.831119 1.83823 2.55611 + endloop + endfacet + facet normal -0.665937 0.184661 0.722791 + outer loop + vertex 0.833619 1.83584 2.55911 + vertex 0.833493 1.83256 2.55983 + vertex 0.83611 1.83272 2.5622 + endloop + endfacet + facet normal -0.666348 0.180167 0.723547 + outer loop + vertex 0.83611 1.83272 2.5622 + vertex 0.833493 1.83256 2.55983 + vertex 0.83362 1.82955 2.5607 + endloop + endfacet + facet normal -0.684979 0.181571 0.705575 + outer loop + vertex 0.830972 1.83269 2.5574 + vertex 0.828406 1.83275 2.55489 + vertex 0.828537 1.82979 2.55578 + endloop + endfacet + facet normal -0.6894 0.180866 0.701438 + outer loop + vertex 0.828537 1.82979 2.55578 + vertex 0.82613 1.82774 2.55395 + vertex 0.828686 1.82528 2.55709 + endloop + endfacet + facet normal -0.673586 0.177822 0.717399 + outer loop + vertex 0.83362 1.82955 2.5607 + vertex 0.831149 1.82748 2.55889 + vertex 0.833806 1.82504 2.56199 + endloop + endfacet + facet normal -0.664099 0.177934 0.726163 + outer loop + vertex 0.833806 1.82504 2.56199 + vertex 0.833736 1.82043 2.56306 + vertex 0.83653 1.82307 2.56496 + endloop + endfacet + facet normal -0.677444 0.1817 0.712779 + outer loop + vertex 0.828686 1.82528 2.55709 + vertex 0.828639 1.82058 2.55824 + vertex 0.831233 1.82279 2.56015 + endloop + endfacet + facet normal -0.678665 0.177433 0.712693 + outer loop + vertex 0.828499 1.81587 2.55928 + vertex 0.828639 1.82058 2.55824 + vertex 0.825882 1.81807 2.55624 + endloop + endfacet + facet normal -0.668918 0.175037 0.722434 + outer loop + vertex 0.833434 1.81598 2.56385 + vertex 0.833736 1.82043 2.56306 + vertex 0.83111 1.81806 2.5612 + endloop + endfacet + facet normal -0.66153 0.173638 0.72954 + outer loop + vertex 0.833434 1.81598 2.56385 + vertex 0.833338 1.81319 2.56443 + vertex 0.835346 1.81388 2.56609 + endloop + endfacet + facet normal -0.660986 0.167486 0.731468 + outer loop + vertex 0.835346 1.81388 2.56609 + vertex 0.833338 1.81319 2.56443 + vertex 0.833719 1.81067 2.56535 + endloop + endfacet + facet normal -0.663361 0.166217 0.729605 + outer loop + vertex 0.833719 1.81067 2.56535 + vertex 0.8313 1.80809 2.56374 + vertex 0.834245 1.80646 2.56679 + endloop + endfacet + facet normal -0.670648 0.173112 0.721293 + outer loop + vertex 0.831037 1.81299 2.56235 + vertex 0.828472 1.81284 2.56 + vertex 0.828592 1.80994 2.5608 + endloop + endfacet + facet normal -0.663948 0.171175 0.727923 + outer loop + vertex 0.8313 1.80809 2.56374 + vertex 0.828723 1.8055 2.562 + vertex 0.831432 1.8034 2.56496 + endloop + endfacet + facet normal -0.670296 0.180013 0.719929 + outer loop + vertex 0.825819 1.81248 2.55759 + vertex 0.826196 1.80766 2.55915 + vertex 0.828592 1.80994 2.5608 + endloop + endfacet + facet normal -0.665761 0.18354 0.72324 + outer loop + vertex 0.823847 1.80533 2.55756 + vertex 0.823432 1.80081 2.55832 + vertex 0.826094 1.80311 2.56019 + endloop + endfacet + facet normal -0.678922 0.175776 0.712858 + outer loop + vertex 0.823212 1.79596 2.55931 + vertex 0.823432 1.80081 2.55832 + vertex 0.82077 1.79837 2.55639 + endloop + endfacet + facet normal -0.674767 0.131603 0.726202 + outer loop + vertex 0.825848 1.79297 2.5624 + vertex 0.826374 1.7881 2.56377 + vertex 0.828659 1.7907 2.56542 + endloop + endfacet + facet normal -0.669482 0.122914 0.732588 + outer loop + vertex 0.828659 1.7907 2.56542 + vertex 0.826374 1.7881 2.56377 + vertex 0.82938 1.78659 2.56677 + endloop + endfacet + facet normal -0.663454 0.125615 0.737597 + outer loop + vertex 0.828659 1.7907 2.56542 + vertex 0.82938 1.78659 2.56677 + vertex 0.83218 1.79042 2.56864 + endloop + endfacet + facet normal -0.668656 0.132302 0.731707 + outer loop + vertex 0.82938 1.78659 2.56677 + vertex 0.832395 1.78542 2.56973 + vertex 0.83218 1.79042 2.56864 + endloop + endfacet + facet normal -0.656395 0.173257 0.734253 + outer loop + vertex 0.828268 1.79609 2.56387 + vertex 0.828206 1.79322 2.56449 + vertex 0.830258 1.79396 2.56615 + endloop + endfacet + facet normal -0.658851 0.177256 0.731092 + outer loop + vertex 0.828268 1.79609 2.56387 + vertex 0.828581 1.80074 2.56303 + vertex 0.82585 1.79823 2.56118 + endloop + endfacet + facet normal -0.66073 0.177357 0.72937 + outer loop + vertex 0.828723 1.8055 2.562 + vertex 0.828581 1.80074 2.56303 + vertex 0.831432 1.8034 2.56496 + endloop + endfacet + facet normal -0.656658 0.173648 0.733926 + outer loop + vertex 0.83335 1.79588 2.56847 + vertex 0.834474 1.80136 2.56817 + vertex 0.831072 1.79848 2.56581 + endloop + endfacet + facet normal -0.661039 0.171902 0.730395 + outer loop + vertex 0.831432 1.8034 2.56496 + vertex 0.834245 1.80646 2.56679 + vertex 0.8313 1.80809 2.56374 + endloop + endfacet + facet normal -0.656096 0.166708 0.736035 + outer loop + vertex 0.834245 1.80646 2.56679 + vertex 0.837235 1.80522 2.56973 + vertex 0.837224 1.81034 2.56856 + endloop + endfacet + facet normal -0.649658 0.169861 0.741007 + outer loop + vertex 0.83733 1.80181 2.5706 + vertex 0.839218 1.8036 2.57185 + vertex 0.837235 1.80522 2.56973 + endloop + endfacet + facet normal -0.649967 0.170475 0.740595 + outer loop + vertex 0.839218 1.8036 2.57185 + vertex 0.83733 1.80181 2.5706 + vertex 0.839121 1.80017 2.57255 + endloop + endfacet + facet normal -0.642079 0.175828 0.746203 + outer loop + vertex 0.839121 1.80017 2.57255 + vertex 0.838652 1.79577 2.57318 + vertex 0.841521 1.79838 2.57504 + endloop + endfacet + facet normal -0.653969 0.17323 0.736421 + outer loop + vertex 0.834474 1.80136 2.56817 + vertex 0.83335 1.79588 2.56847 + vertex 0.836448 1.7981 2.57069 + endloop + endfacet + facet normal -0.651198 0.173994 0.738693 + outer loop + vertex 0.838217 1.7912 2.57387 + vertex 0.838652 1.79577 2.57318 + vertex 0.835731 1.79316 2.57122 + endloop + endfacet + facet normal -0.661157 0.100385 0.743501 + outer loop + vertex 0.835827 1.78767 2.57246 + vertex 0.836987 1.78321 2.57409 + vertex 0.838912 1.78584 2.57545 + endloop + endfacet + facet normal -0.635034 0.165146 0.754624 + outer loop + vertex 0.838217 1.7912 2.57387 + vertex 0.838218 1.78836 2.5745 + vertex 0.8403 1.78914 2.57608 + endloop + endfacet + facet normal -0.640447 0.0744734 0.764383 + outer loop + vertex 0.838912 1.78584 2.57545 + vertex 0.836987 1.78321 2.57409 + vertex 0.840049 1.78138 2.57684 + endloop + endfacet + facet normal -0.621601 0.130763 0.772343 + outer loop + vertex 0.842429 1.78563 2.57839 + vertex 0.843442 1.79101 2.57829 + vertex 0.8403 1.78914 2.57608 + endloop + endfacet + facet normal -0.628535 0.164067 0.76028 + outer loop + vertex 0.844527 1.79648 2.57801 + vertex 0.843442 1.79101 2.57829 + vertex 0.84672 1.79345 2.58047 + endloop + endfacet + facet normal -0.616909 0.144111 0.773728 + outer loop + vertex 0.848586 1.78595 2.5834 + vertex 0.849536 1.7915 2.58313 + vertex 0.845973 1.7884 2.58086 + endloop + endfacet + facet normal -0.616367 0.164021 0.770188 + outer loop + vertex 0.84672 1.79345 2.58047 + vertex 0.849631 1.79638 2.58218 + vertex 0.847508 1.79729 2.58029 + endloop + endfacet + facet normal -0.605111 0.166876 0.778455 + outer loop + vertex 0.849631 1.79638 2.58218 + vertex 0.852252 1.79572 2.58436 + vertex 0.852497 1.80067 2.58349 + endloop + endfacet + facet normal -0.597267 0.167931 0.784265 + outer loop + vertex 0.852407 1.79233 2.5852 + vertex 0.854365 1.79475 2.58618 + vertex 0.852252 1.79572 2.58436 + endloop + endfacet + facet normal -0.594687 0.16478 0.786889 + outer loop + vertex 0.854365 1.79475 2.58618 + vertex 0.852407 1.79233 2.5852 + vertex 0.85457 1.79135 2.58704 + endloop + endfacet + facet normal -0.590605 0.153269 0.792272 + outer loop + vertex 0.854581 1.78647 2.58799 + vertex 0.857336 1.7907 2.58923 + vertex 0.85457 1.79135 2.58704 + endloop + endfacet + facet normal -0.618631 0.144335 0.77231 + outer loop + vertex 0.849536 1.7915 2.58313 + vertex 0.848586 1.78595 2.5834 + vertex 0.851699 1.78846 2.58542 + endloop + endfacet + facet normal -0.62583 0.101257 0.773358 + outer loop + vertex 0.848143 1.78086 2.58371 + vertex 0.848586 1.78595 2.5834 + vertex 0.845543 1.78332 2.58128 + endloop + endfacet + facet normal -0.603204 0.11978 0.788541 + outer loop + vertex 0.853748 1.78097 2.58819 + vertex 0.854581 1.78647 2.58799 + vertex 0.851145 1.78346 2.58582 + endloop + endfacet + facet normal -0.608369 0.120417 0.784466 + outer loop + vertex 0.854581 1.78647 2.58799 + vertex 0.853748 1.78097 2.58819 + vertex 0.856818 1.78352 2.59018 + endloop + endfacet + facet normal -0.57923 0.134844 0.803934 + outer loop + vertex 0.859493 1.78183 2.59239 + vertex 0.859837 1.78648 2.59186 + vertex 0.856818 1.78352 2.59018 + endloop + endfacet + facet normal -0.576405 0.142144 0.804707 + outer loop + vertex 0.86227 1.78083 2.59456 + vertex 0.862676 1.7855 2.59403 + vertex 0.859493 1.78183 2.59239 + endloop + endfacet + facet normal -0.573213 0.11538 0.811243 + outer loop + vertex 0.862538 1.77746 2.59523 + vertex 0.864559 1.78003 2.59629 + vertex 0.86227 1.78083 2.59456 + endloop + endfacet + facet normal -0.554531 0.0942806 0.826805 + outer loop + vertex 0.864559 1.78003 2.59629 + vertex 0.862538 1.77746 2.59523 + vertex 0.864881 1.77663 2.59689 + endloop + endfacet + facet normal -0.537513 0.105281 0.836657 + outer loop + vertex 0.864881 1.77663 2.59689 + vertex 0.867849 1.77549 2.59894 + vertex 0.868237 1.78142 2.59845 + endloop + endfacet + facet normal -0.547654 0.105391 0.830041 + outer loop + vertex 0.868237 1.78142 2.59845 + vertex 0.867849 1.77549 2.59894 + vertex 0.871167 1.77878 2.60071 + endloop + endfacet + facet normal -0.522706 0.118676 0.844212 + outer loop + vertex 0.874123 1.77717 2.60277 + vertex 0.874301 1.78176 2.60224 + vertex 0.871167 1.77878 2.60071 + endloop + endfacet + facet normal -0.516349 0.122932 0.847509 + outer loop + vertex 0.877103 1.77604 2.60475 + vertex 0.877291 1.7806 2.60421 + vertex 0.874123 1.77717 2.60277 + endloop + endfacet + facet normal -0.499399 0.0823494 0.862449 + outer loop + vertex 0.879547 1.77505 2.60633 + vertex 0.877476 1.77266 2.60536 + vertex 0.87992 1.77164 2.60687 + endloop + endfacet + facet normal -0.501486 0.123377 0.856323 + outer loop + vertex 0.877291 1.7806 2.60421 + vertex 0.877103 1.77604 2.60475 + vertex 0.880285 1.77895 2.6062 + endloop + endfacet + facet normal -0.473077 0.0874781 0.876667 + outer loop + vertex 0.879547 1.77505 2.60633 + vertex 0.87992 1.77164 2.60687 + vertex 0.883365 1.77622 2.60828 + endloop + endfacet + facet normal -0.476744 0.143179 0.867303 + outer loop + vertex 0.880285 1.77895 2.6062 + vertex 0.884029 1.78221 2.60772 + vertex 0.880813 1.78387 2.60567 + endloop + endfacet + facet normal -0.461783 0.155969 0.873172 + outer loop + vertex 0.887144 1.78098 2.60958 + vertex 0.88831 1.78632 2.60925 + vertex 0.884029 1.78221 2.60772 + endloop + endfacet + facet normal -0.451089 0.145861 0.880479 + outer loop + vertex 0.887193 1.77748 2.61019 + vertex 0.889589 1.78012 2.61098 + vertex 0.887144 1.78098 2.60958 + endloop + endfacet + facet normal -0.481196 0.0951844 0.87143 + outer loop + vertex 0.87992 1.77164 2.60687 + vertex 0.883005 1.77037 2.60872 + vertex 0.883365 1.77622 2.60828 + endloop + endfacet + facet normal -0.442012 0.0702669 0.894253 + outer loop + vertex 0.88959 1.7673 2.61236 + vertex 0.889758 1.77233 2.61204 + vertex 0.886201 1.76874 2.61057 + endloop + endfacet + facet normal -0.441099 0.10382 0.891433 + outer loop + vertex 0.886463 1.7736 2.61028 + vertex 0.889863 1.77688 2.61158 + vertex 0.887193 1.77748 2.61019 + endloop + endfacet + facet normal -0.411896 0.134284 0.901282 + outer loop + vertex 0.889863 1.77688 2.61158 + vertex 0.893365 1.77646 2.61324 + vertex 0.893322 1.78162 2.61245 + endloop + endfacet + facet normal -0.405237 0.13479 0.90422 + outer loop + vertex 0.893365 1.77646 2.61324 + vertex 0.897208 1.78065 2.61434 + vertex 0.893322 1.78162 2.61245 + endloop + endfacet + facet normal -0.406884 0.136561 0.903215 + outer loop + vertex 0.896832 1.77601 2.61487 + vertex 0.897208 1.78065 2.61434 + vertex 0.893365 1.77646 2.61324 + endloop + endfacet + facet normal -0.412211 0.102594 0.905294 + outer loop + vertex 0.893663 1.77134 2.61396 + vertex 0.896832 1.77601 2.61487 + vertex 0.893365 1.77646 2.61324 + endloop + endfacet + facet normal -0.416898 0.112585 0.901954 + outer loop + vertex 0.899509 1.77537 2.6162 + vertex 0.897206 1.77277 2.61546 + vertex 0.899846 1.77199 2.61677 + endloop + endfacet + facet normal -0.44396 0.107769 0.889542 + outer loop + vertex 0.899509 1.77537 2.6162 + vertex 0.899846 1.77199 2.61677 + vertex 0.903455 1.77633 2.61805 + endloop + endfacet + facet normal -0.519099 0.150632 0.841336 + outer loop + vertex 0.903455 1.77633 2.61805 + vertex 0.907139 1.78027 2.61962 + vertex 0.904099 1.78209 2.61742 + endloop + endfacet + facet normal -0.52259 0.143645 0.840396 + outer loop + vertex 0.907139 1.78027 2.61962 + vertex 0.907575 1.7851 2.61906 + vertex 0.904099 1.78209 2.61742 + endloop + endfacet + facet normal -0.532312 0.159821 0.831325 + outer loop + vertex 0.904099 1.78209 2.61742 + vertex 0.907575 1.7851 2.61906 + vertex 0.904567 1.78678 2.61681 + endloop + endfacet + facet normal -0.531472 0.161585 0.831522 + outer loop + vertex 0.904567 1.78678 2.61681 + vertex 0.907575 1.7851 2.61906 + vertex 0.907684 1.79066 2.61805 + endloop + endfacet + facet normal -0.414489 0.136777 0.899717 + outer loop + vertex 0.897208 1.78065 2.61434 + vertex 0.896832 1.77601 2.61487 + vertex 0.90038 1.77919 2.61602 + endloop + endfacet + facet normal -0.401327 0.149399 0.903668 + outer loop + vertex 0.897208 1.78065 2.61434 + vertex 0.898309 1.78634 2.61389 + vertex 0.893322 1.78162 2.61245 + endloop + endfacet + facet normal -0.450086 0.157755 0.87894 + outer loop + vertex 0.904099 1.78209 2.61742 + vertex 0.904567 1.78678 2.61681 + vertex 0.901152 1.78393 2.61558 + endloop + endfacet + facet normal -0.523439 0.153005 0.838213 + outer loop + vertex 0.90439 1.79022 2.61608 + vertex 0.904567 1.78678 2.61681 + vertex 0.907684 1.79066 2.61805 + endloop + endfacet + facet normal -0.4302 0.154363 0.889438 + outer loop + vertex 0.907239 1.80268 2.61534 + vertex 0.906887 1.80599 2.61459 + vertex 0.903601 1.80147 2.61379 + endloop + endfacet + facet normal -0.419188 0.145138 0.896223 + outer loop + vertex 0.903601 1.80147 2.61379 + vertex 0.906887 1.80599 2.61459 + vertex 0.903084 1.80682 2.61268 + endloop + endfacet + facet normal -0.395361 0.149524 0.906274 + outer loop + vertex 0.899697 1.80218 2.61197 + vertex 0.903601 1.80147 2.61379 + vertex 0.903084 1.80682 2.61268 + endloop + endfacet + facet normal -0.442177 0.154974 0.883438 + outer loop + vertex 0.906343 1.79882 2.61562 + vertex 0.902439 1.79586 2.61419 + vertex 0.905408 1.79401 2.616 + endloop + endfacet + facet normal -0.446469 0.147269 0.882597 + outer loop + vertex 0.902439 1.79586 2.61419 + vertex 0.901826 1.79111 2.61467 + vertex 0.905408 1.79401 2.616 + endloop + endfacet + facet normal -0.401851 0.147634 0.903726 + outer loop + vertex 0.902109 1.7878 2.61534 + vertex 0.901826 1.79111 2.61467 + vertex 0.898309 1.78634 2.61389 + endloop + endfacet + facet normal -0.399337 0.146906 0.904958 + outer loop + vertex 0.893322 1.78162 2.61245 + vertex 0.898309 1.78634 2.61389 + vertex 0.894414 1.787 2.61206 + endloop + endfacet + facet normal -0.415196 0.146779 0.897813 + outer loop + vertex 0.894235 1.79039 2.61142 + vertex 0.891871 1.78773 2.61076 + vertex 0.894414 1.787 2.61206 + endloop + endfacet + facet normal -0.421048 0.152925 0.894054 + outer loop + vertex 0.891871 1.78773 2.61076 + vertex 0.894235 1.79039 2.61142 + vertex 0.891664 1.79094 2.61012 + endloop + endfacet + facet normal -0.44057 0.150073 0.885085 + outer loop + vertex 0.891664 1.79094 2.61012 + vertex 0.892103 1.79554 2.60956 + vertex 0.8883 1.79135 2.60837 + endloop + endfacet + facet normal -0.401827 0.144769 0.9042 + outer loop + vertex 0.89797 1.79183 2.61285 + vertex 0.899177 1.79747 2.61248 + vertex 0.895204 1.79423 2.61124 + endloop + endfacet + facet normal -0.396779 0.1429 0.906723 + outer loop + vertex 0.899177 1.79747 2.61248 + vertex 0.903601 1.80147 2.61379 + vertex 0.899697 1.80218 2.61197 + endloop + endfacet + facet normal -0.424695 0.149125 0.892971 + outer loop + vertex 0.89316 1.80122 2.60911 + vertex 0.892103 1.79554 2.60956 + vertex 0.896041 1.79894 2.61086 + endloop + endfacet + facet normal -0.433284 0.159458 0.887039 + outer loop + vertex 0.89316 1.80122 2.60911 + vertex 0.896602 1.80603 2.60993 + vertex 0.892832 1.80669 2.60797 + endloop + endfacet + facet normal -0.398173 0.146187 0.905587 + outer loop + vertex 0.899306 1.80543 2.61127 + vertex 0.896946 1.80279 2.61066 + vertex 0.899697 1.80218 2.61197 + endloop + endfacet + facet normal -0.410617 0.163543 0.897021 + outer loop + vertex 0.897223 1.81072 2.60936 + vertex 0.896602 1.80603 2.60993 + vertex 0.900263 1.80922 2.61102 + endloop + endfacet + facet normal -0.392673 0.147324 0.907802 + outer loop + vertex 0.899306 1.80543 2.61127 + vertex 0.899697 1.80218 2.61197 + vertex 0.903084 1.80682 2.61268 + endloop + endfacet + facet normal -0.405108 0.162107 0.899783 + outer loop + vertex 0.900263 1.80922 2.61102 + vertex 0.904251 1.81238 2.61225 + vertex 0.901194 1.81389 2.6106 + endloop + endfacet + facet normal -0.418941 0.146155 0.896174 + outer loop + vertex 0.906887 1.80599 2.61459 + vertex 0.907406 1.81069 2.61407 + vertex 0.903084 1.80682 2.61268 + endloop + endfacet + facet normal -0.407817 0.16734 0.897598 + outer loop + vertex 0.904603 1.82033 2.61096 + vertex 0.902216 1.81772 2.61036 + vertex 0.904847 1.81706 2.61168 + endloop + endfacet + facet normal -0.406249 0.165677 0.898617 + outer loop + vertex 0.902216 1.81772 2.61036 + vertex 0.904603 1.82033 2.61096 + vertex 0.902055 1.82108 2.60967 + endloop + endfacet + facet normal -0.409001 0.167146 0.897095 + outer loop + vertex 0.902055 1.82108 2.60967 + vertex 0.903179 1.8264 2.60919 + vertex 0.898199 1.82172 2.60779 + endloop + endfacet + facet normal -0.402993 0.159524 0.901193 + outer loop + vertex 0.898199 1.82172 2.60779 + vertex 0.903179 1.8264 2.60919 + vertex 0.899309 1.82736 2.60729 + endloop + endfacet + facet normal -0.402328 0.161946 0.901058 + outer loop + vertex 0.903179 1.8264 2.60919 + vertex 0.903285 1.83148 2.60833 + vertex 0.899309 1.82736 2.60729 + endloop + endfacet + facet normal -0.397441 0.162205 0.903178 + outer loop + vertex 0.903179 1.8264 2.60919 + vertex 0.906727 1.831 2.60993 + vertex 0.903285 1.83148 2.60833 + endloop + endfacet + facet normal -0.40066 0.164998 0.901248 + outer loop + vertex 0.906845 1.82781 2.61057 + vertex 0.906727 1.831 2.60993 + vertex 0.903179 1.8264 2.60919 + endloop + endfacet + facet normal -0.438954 0.172743 0.881748 + outer loop + vertex 0.90818 1.82152 2.6125 + vertex 0.909162 1.82671 2.61197 + vertex 0.9057 1.82406 2.61076 + endloop + endfacet + facet normal -0.428626 0.161502 0.88893 + outer loop + vertex 0.906845 1.82781 2.61057 + vertex 0.909174 1.83018 2.61126 + vertex 0.906727 1.831 2.60993 + endloop + endfacet + facet normal -0.505839 0.180275 0.84358 + outer loop + vertex 0.912517 1.8307 2.61315 + vertex 0.914322 1.83669 2.61296 + vertex 0.910284 1.83392 2.61113 + endloop + endfacet + facet normal -0.473871 0.17582 0.862863 + outer loop + vertex 0.912295 1.84255 2.61032 + vertex 0.914531 1.8449 2.61107 + vertex 0.912123 1.84596 2.60953 + endloop + endfacet + facet normal -0.431799 0.179039 0.884022 + outer loop + vertex 0.908474 1.84119 2.60878 + vertex 0.907277 1.83554 2.60934 + vertex 0.911282 1.83866 2.61067 + endloop + endfacet + facet normal -0.396971 0.16472 0.902929 + outer loop + vertex 0.906727 1.831 2.60993 + vertex 0.907277 1.83554 2.60934 + vertex 0.903285 1.83148 2.60833 + endloop + endfacet + facet normal -0.400815 0.160242 0.902036 + outer loop + vertex 0.899309 1.82736 2.60729 + vertex 0.903285 1.83148 2.60833 + vertex 0.899773 1.83193 2.60669 + endloop + endfacet + facet normal -0.452971 0.180525 0.873057 + outer loop + vertex 0.897085 1.83603 2.60461 + vertex 0.898252 1.84129 2.60412 + vertex 0.89402 1.83724 2.60276 + endloop + endfacet + facet normal -0.400986 0.172243 0.899746 + outer loop + vertex 0.903358 1.83655 2.60743 + vertex 0.90448 1.84187 2.60691 + vertex 0.900721 1.83886 2.60581 + endloop + endfacet + facet normal -0.389068 0.175602 0.904317 + outer loop + vertex 0.904357 1.84526 2.6062 + vertex 0.90448 1.84187 2.60691 + vertex 0.908235 1.84674 2.60758 + endloop + endfacet + facet normal -0.395379 0.189018 0.898859 + outer loop + vertex 0.905575 1.84908 2.60594 + vertex 0.909355 1.85212 2.60696 + vertex 0.906796 1.85287 2.60568 + endloop + endfacet + facet normal -0.401627 0.190817 0.895703 + outer loop + vertex 0.906796 1.85287 2.60568 + vertex 0.903052 1.85133 2.60433 + vertex 0.905575 1.84908 2.60594 + endloop + endfacet + facet normal -0.412618 0.174927 0.89395 + outer loop + vertex 0.912123 1.84596 2.60953 + vertex 0.913166 1.85122 2.60898 + vertex 0.908235 1.84674 2.60758 + endloop + endfacet + facet normal -0.394142 0.192812 0.898597 + outer loop + vertex 0.909293 1.8555 2.60621 + vertex 0.906796 1.85287 2.60568 + vertex 0.909355 1.85212 2.60696 + endloop + endfacet + facet normal -0.39331 0.19191 0.899154 + outer loop + vertex 0.906796 1.85287 2.60568 + vertex 0.909293 1.8555 2.60621 + vertex 0.906814 1.85614 2.60499 + endloop + endfacet + facet normal -0.390918 0.195051 0.899521 + outer loop + vertex 0.911811 1.86301 2.60568 + vertex 0.911854 1.86628 2.60499 + vertex 0.908 1.86133 2.60439 + endloop + endfacet + facet normal -0.385711 0.190607 0.902716 + outer loop + vertex 0.908 1.86133 2.60439 + vertex 0.911854 1.86628 2.60499 + vertex 0.908223 1.8665 2.60339 + endloop + endfacet + facet normal -0.393024 0.192867 0.899074 + outer loop + vertex 0.910525 1.85922 2.60595 + vertex 0.906814 1.85614 2.60499 + vertex 0.909293 1.8555 2.60621 + endloop + endfacet + facet normal -0.401737 0.191202 0.895572 + outer loop + vertex 0.906796 1.85287 2.60568 + vertex 0.906814 1.85614 2.60499 + vertex 0.903052 1.85133 2.60433 + endloop + endfacet + facet normal -0.404714 0.186949 0.895129 + outer loop + vertex 0.903052 1.85133 2.60433 + vertex 0.901808 1.84601 2.60488 + vertex 0.905575 1.84908 2.60594 + endloop + endfacet + facet normal -0.430969 0.183443 0.883524 + outer loop + vertex 0.90187 1.84262 2.60561 + vertex 0.901808 1.84601 2.60488 + vertex 0.898252 1.84129 2.60412 + endloop + endfacet + facet normal -0.450407 0.177174 0.875067 + outer loop + vertex 0.89402 1.83724 2.60276 + vertex 0.898252 1.84129 2.60412 + vertex 0.894588 1.84195 2.6021 + endloop + endfacet + facet normal -0.462744 0.177575 0.868525 + outer loop + vertex 0.894312 1.84518 2.60129 + vertex 0.892016 1.84258 2.6006 + vertex 0.894588 1.84195 2.6021 + endloop + endfacet + facet normal -0.467781 0.183044 0.864682 + outer loop + vertex 0.892016 1.84258 2.6006 + vertex 0.894312 1.84518 2.60129 + vertex 0.891746 1.84579 2.59978 + endloop + endfacet + facet normal -0.476364 0.188287 0.858851 + outer loop + vertex 0.891746 1.84579 2.59978 + vertex 0.89232 1.85042 2.59908 + vertex 0.888156 1.84637 2.59766 + endloop + endfacet + facet normal -0.446856 0.186127 0.875029 + outer loop + vertex 0.898039 1.84667 2.6029 + vertex 0.899253 1.85225 2.60233 + vertex 0.895286 1.84896 2.601 + endloop + endfacet + facet normal -0.418585 0.184972 0.889141 + outer loop + vertex 0.899253 1.85225 2.60233 + vertex 0.903364 1.8565 2.60338 + vertex 0.899818 1.85677 2.60166 + endloop + endfacet + facet normal -0.417925 0.189517 0.888494 + outer loop + vertex 0.899818 1.85677 2.60166 + vertex 0.903364 1.8565 2.60338 + vertex 0.903472 1.86154 2.60236 + endloop + endfacet + facet normal -0.470011 0.193395 0.861213 + outer loop + vertex 0.893272 1.85618 2.59831 + vertex 0.89232 1.85042 2.59908 + vertex 0.896168 1.85361 2.60047 + endloop + endfacet + facet normal -0.473498 0.196518 0.858592 + outer loop + vertex 0.893272 1.85618 2.59831 + vertex 0.897249 1.86075 2.59946 + vertex 0.894218 1.86195 2.59751 + endloop + endfacet + facet normal -0.445576 0.186911 0.875515 + outer loop + vertex 0.899679 1.8599 2.60092 + vertex 0.897203 1.85736 2.6002 + vertex 0.899818 1.85677 2.60166 + endloop + endfacet + facet normal -0.4507 0.195729 0.870953 + outer loop + vertex 0.898463 1.86597 2.59891 + vertex 0.897249 1.86075 2.59946 + vertex 0.900875 1.86361 2.60069 + endloop + endfacet + facet normal -0.419511 0.190883 0.887454 + outer loop + vertex 0.899679 1.8599 2.60092 + vertex 0.899818 1.85677 2.60166 + vertex 0.903472 1.86154 2.60236 + endloop + endfacet + facet normal -0.416056 0.18581 0.890153 + outer loop + vertex 0.900875 1.86361 2.60069 + vertex 0.904577 1.86672 2.60177 + vertex 0.902059 1.86732 2.60047 + endloop + endfacet + facet normal -0.394288 0.190274 0.899073 + outer loop + vertex 0.908 1.86133 2.60439 + vertex 0.908223 1.8665 2.60339 + vertex 0.903472 1.86154 2.60236 + endloop + endfacet + facet normal -0.385546 0.191871 0.902518 + outer loop + vertex 0.911854 1.86628 2.60499 + vertex 0.912978 1.87141 2.60438 + vertex 0.908223 1.8665 2.60339 + endloop + endfacet + facet normal -0.411436 0.196266 0.890056 + outer loop + vertex 0.916695 1.87293 2.60576 + vertex 0.916592 1.87604 2.60503 + vertex 0.912978 1.87141 2.60438 + endloop + endfacet + facet normal -0.3804 0.188701 0.905366 + outer loop + vertex 0.908408 1.87168 2.60239 + vertex 0.913082 1.87643 2.60336 + vertex 0.909543 1.87688 2.60178 + endloop + endfacet + facet normal -0.391193 0.191831 0.900094 + outer loop + vertex 0.909516 1.88016 2.60107 + vertex 0.906977 1.87754 2.60052 + vertex 0.909543 1.87688 2.60178 + endloop + endfacet + facet normal -0.388407 0.203003 0.898849 + outer loop + vertex 0.910742 1.88387 2.60077 + vertex 0.914595 1.88679 2.60177 + vertex 0.911975 1.88761 2.60046 + endloop + endfacet + facet normal -0.403428 0.195024 0.893986 + outer loop + vertex 0.91721 1.88053 2.60436 + vertex 0.918473 1.88603 2.60373 + vertex 0.913359 1.88157 2.60239 + endloop + endfacet + facet normal -0.387448 0.205747 0.898639 + outer loop + vertex 0.914538 1.89016 2.60098 + vertex 0.911975 1.88761 2.60046 + vertex 0.914595 1.88679 2.60177 + endloop + endfacet + facet normal -0.390834 0.20963 0.896272 + outer loop + vertex 0.911975 1.88761 2.60046 + vertex 0.914538 1.89016 2.60098 + vertex 0.911962 1.89103 2.59965 + endloop + endfacet + facet normal -0.3867 0.215045 0.896783 + outer loop + vertex 0.917315 1.89782 2.60035 + vertex 0.91786 1.90175 2.59964 + vertex 0.913374 1.89654 2.59895 + endloop + endfacet + facet normal -0.408087 0.214196 0.88746 + outer loop + vertex 0.918257 1.89134 2.60239 + vertex 0.919481 1.89641 2.60173 + vertex 0.915843 1.89394 2.60065 + endloop + endfacet + facet normal -0.466685 0.224154 0.855547 + outer loop + vertex 0.918257 1.89134 2.60239 + vertex 0.922388 1.89502 2.60368 + vertex 0.919481 1.89641 2.60173 + endloop + endfacet + facet normal -0.464582 0.228527 0.855534 + outer loop + vertex 0.919481 1.89641 2.60173 + vertex 0.922388 1.89502 2.60368 + vertex 0.922779 1.89989 2.60259 + endloop + endfacet + facet normal -0.45312 0.204732 0.867621 + outer loop + vertex 0.921927 1.89053 2.6045 + vertex 0.922388 1.89502 2.60368 + vertex 0.918257 1.89134 2.60239 + endloop + endfacet + facet normal -0.454171 0.200884 0.867972 + outer loop + vertex 0.918473 1.88603 2.60373 + vertex 0.921927 1.89053 2.6045 + vertex 0.918257 1.89134 2.60239 + endloop + endfacet + facet normal -0.404919 0.216072 0.888456 + outer loop + vertex 0.917315 1.89782 2.60035 + vertex 0.919817 1.89982 2.601 + vertex 0.91786 1.90175 2.59964 + endloop + endfacet + facet normal -0.462424 0.218653 0.859276 + outer loop + vertex 0.921243 1.90239 2.60105 + vertex 0.923656 1.90379 2.60199 + vertex 0.921673 1.90571 2.60043 + endloop + endfacet + facet normal -0.381844 0.215566 0.898736 + outer loop + vertex 0.91786 1.90175 2.59964 + vertex 0.918072 1.90677 2.59853 + vertex 0.913269 1.90202 2.59762 + endloop + endfacet + facet normal -0.382465 0.211037 0.899546 + outer loop + vertex 0.913374 1.89654 2.59895 + vertex 0.91786 1.90175 2.59964 + vertex 0.913269 1.90202 2.59762 + endloop + endfacet + facet normal -0.395413 0.213859 0.89326 + outer loop + vertex 0.911962 1.89103 2.59965 + vertex 0.913374 1.89654 2.59895 + vertex 0.908089 1.89169 2.59778 + endloop + endfacet + facet normal -0.410808 0.205406 0.888282 + outer loop + vertex 0.904296 1.88684 2.59714 + vertex 0.908114 1.8862 2.59906 + vertex 0.908089 1.89169 2.59778 + endloop + endfacet + facet normal -0.432006 0.199657 0.879493 + outer loop + vertex 0.903089 1.88152 2.59776 + vertex 0.904296 1.88684 2.59714 + vertex 0.900627 1.88385 2.59602 + endloop + endfacet + facet normal -0.46609 0.211011 0.859206 + outer loop + vertex 0.898299 1.88609 2.59421 + vertex 0.897055 1.88098 2.59479 + vertex 0.900627 1.88385 2.59602 + endloop + endfacet + facet normal -0.446077 0.221379 0.867183 + outer loop + vertex 0.901837 1.88754 2.59579 + vertex 0.904281 1.89015 2.59638 + vertex 0.901842 1.89077 2.59497 + endloop + endfacet + facet normal -0.483229 0.195536 0.853379 + outer loop + vertex 0.896905 1.87759 2.59548 + vertex 0.897055 1.88098 2.59479 + vertex 0.893122 1.87635 2.59362 + endloop + endfacet + facet normal -0.495459 0.194539 0.846566 + outer loop + vertex 0.8893 1.8717 2.59245 + vertex 0.892211 1.8709 2.59434 + vertex 0.893122 1.87635 2.59362 + endloop + endfacet + facet normal -0.540483 0.23475 0.807942 + outer loop + vertex 0.886932 1.87261 2.59077 + vertex 0.889349 1.8751 2.59167 + vertex 0.886887 1.87583 2.58981 + endloop + endfacet + facet normal -0.543405 0.234171 0.806148 + outer loop + vertex 0.886932 1.87261 2.59077 + vertex 0.886887 1.87583 2.58981 + vertex 0.883164 1.87123 2.58863 + endloop + endfacet + facet normal -0.521405 0.228664 0.822101 + outer loop + vertex 0.879363 1.86647 2.58755 + vertex 0.882213 1.86588 2.58952 + vertex 0.883164 1.87123 2.58863 + endloop + endfacet + facet normal -0.524848 0.216064 0.823317 + outer loop + vertex 0.878364 1.86107 2.58833 + vertex 0.882213 1.86588 2.58952 + vertex 0.879363 1.86647 2.58755 + endloop + endfacet + facet normal -0.509164 0.19548 0.838176 + outer loop + vertex 0.888382 1.86617 2.59319 + vertex 0.8893 1.8717 2.59245 + vertex 0.885772 1.86883 2.59098 + endloop + endfacet + facet normal -0.498088 0.199521 0.84386 + outer loop + vertex 0.884399 1.86147 2.59195 + vertex 0.887409 1.86034 2.59399 + vertex 0.888382 1.86617 2.59319 + endloop + endfacet + facet normal -0.511647 0.210835 0.832926 + outer loop + vertex 0.882053 1.86242 2.5903 + vertex 0.884555 1.86499 2.59118 + vertex 0.882213 1.86588 2.58952 + endloop + endfacet + facet normal -0.504623 0.204441 0.838785 + outer loop + vertex 0.883222 1.85622 2.59252 + vertex 0.884399 1.86147 2.59195 + vertex 0.880852 1.85859 2.59051 + endloop + endfacet + facet normal -0.519089 0.210178 0.828475 + outer loop + vertex 0.882053 1.86242 2.5903 + vertex 0.882213 1.86588 2.58952 + vertex 0.878364 1.86107 2.58833 + endloop + endfacet + facet normal -0.517739 0.194892 0.833045 + outer loop + vertex 0.879773 1.85483 2.59079 + vertex 0.877553 1.85232 2.58999 + vertex 0.87994 1.85158 2.59165 + endloop + endfacet + facet normal -0.562631 0.185689 0.805585 + outer loop + vertex 0.869574 1.84135 2.58709 + vertex 0.872362 1.8406 2.58921 + vertex 0.872559 1.84547 2.58822 + endloop + endfacet + facet normal -0.528677 0.186613 0.828056 + outer loop + vertex 0.878476 1.841 2.59313 + vertex 0.879348 1.84687 2.59236 + vertex 0.875616 1.84361 2.59071 + endloop + endfacet + facet normal -0.545783 0.180127 0.818337 + outer loop + vertex 0.874723 1.8397 2.59101 + vertex 0.872535 1.83728 2.59008 + vertex 0.874849 1.83637 2.59183 + endloop + endfacet + facet normal -0.54642 0.178413 0.818287 + outer loop + vertex 0.871562 1.8335 2.59026 + vertex 0.874849 1.83637 2.59183 + vertex 0.872535 1.83728 2.59008 + endloop + endfacet + facet normal -0.533081 0.180215 0.826648 + outer loop + vertex 0.877195 1.83081 2.59455 + vertex 0.877725 1.83532 2.5939 + vertex 0.874328 1.83184 2.59247 + endloop + endfacet + facet normal -0.54585 0.176604 0.81906 + outer loop + vertex 0.874026 1.82669 2.59338 + vertex 0.874328 1.83184 2.59247 + vertex 0.870821 1.82864 2.59082 + endloop + endfacet + facet normal -0.559188 0.182822 0.808632 + outer loop + vertex 0.86935 1.83649 2.58805 + vertex 0.867652 1.83057 2.58822 + vertex 0.871562 1.8335 2.59026 + endloop + endfacet + facet normal -0.556075 0.178008 0.811846 + outer loop + vertex 0.870821 1.82864 2.59082 + vertex 0.867381 1.82544 2.58917 + vertex 0.870093 1.82378 2.59139 + endloop + endfacet + facet normal -0.566346 0.174467 0.80549 + outer loop + vertex 0.864191 1.82201 2.58767 + vertex 0.867381 1.82544 2.58917 + vertex 0.864594 1.82644 2.58699 + endloop + endfacet + facet normal -0.584718 0.188263 0.789089 + outer loop + vertex 0.859548 1.83124 2.5822 + vertex 0.862274 1.83063 2.58436 + vertex 0.862518 1.83553 2.58338 + endloop + endfacet + facet normal -0.566985 0.184897 0.802708 + outer loop + vertex 0.867652 1.83057 2.58822 + vertex 0.86935 1.83649 2.58805 + vertex 0.865445 1.8336 2.58596 + endloop + endfacet + facet normal -0.562705 0.185434 0.805591 + outer loop + vertex 0.86935 1.83649 2.58805 + vertex 0.872362 1.8406 2.58921 + vertex 0.869574 1.84135 2.58709 + endloop + endfacet + facet normal -0.577086 0.189725 0.79434 + outer loop + vertex 0.86426 1.84153 2.58321 + vertex 0.862518 1.83553 2.58338 + vertex 0.866427 1.83851 2.5855 + endloop + endfacet + facet normal -0.580849 0.188368 0.791917 + outer loop + vertex 0.86426 1.84153 2.58321 + vertex 0.867241 1.84571 2.5844 + vertex 0.864516 1.84643 2.58223 + endloop + endfacet + facet normal -0.571888 0.184549 0.799303 + outer loop + vertex 0.869418 1.84469 2.58621 + vertex 0.867391 1.84239 2.58529 + vertex 0.869574 1.84135 2.58709 + endloop + endfacet + facet normal -0.563382 0.186425 0.804889 + outer loop + vertex 0.869418 1.84469 2.58621 + vertex 0.869574 1.84135 2.58709 + vertex 0.872559 1.84547 2.58822 + endloop + endfacet + facet normal -0.547855 0.185593 0.815727 + outer loop + vertex 0.87431 1.8514 2.58805 + vertex 0.872559 1.84547 2.58822 + vertex 0.876505 1.84847 2.59019 + endloop + endfacet + facet normal -0.574172 0.188364 0.796772 + outer loop + vertex 0.867473 1.85059 2.58341 + vertex 0.867241 1.84571 2.5844 + vertex 0.870368 1.84853 2.58599 + endloop + endfacet + facet normal -0.576731 0.218182 0.78726 + outer loop + vertex 0.872415 1.85731 2.58535 + vertex 0.872436 1.86076 2.58441 + vertex 0.869188 1.85656 2.58319 + endloop + endfacet + facet normal -0.555461 0.193393 0.808741 + outer loop + vertex 0.87431 1.8514 2.58805 + vertex 0.874707 1.85639 2.58713 + vertex 0.871361 1.85342 2.58554 + endloop + endfacet + facet normal -0.563385 0.220543 0.796215 + outer loop + vertex 0.872415 1.85731 2.58535 + vertex 0.87469 1.85975 2.58628 + vertex 0.872436 1.86076 2.58441 + endloop + endfacet + facet normal -0.594653 0.298479 0.746524 + outer loop + vertex 0.8659 1.86744 2.57702 + vertex 0.86634 1.86299 2.57915 + vertex 0.869106 1.86584 2.58022 + endloop + endfacet + facet normal -0.588626 0.310359 0.746456 + outer loop + vertex 0.8659 1.86744 2.57702 + vertex 0.869106 1.86584 2.58022 + vertex 0.86866 1.86818 2.5789 + endloop + endfacet + facet normal -0.566663 0.309442 0.763635 + outer loop + vertex 0.8659 1.86744 2.57702 + vertex 0.863854 1.86373 2.57701 + vertex 0.86634 1.86299 2.57915 + endloop + endfacet + facet normal -0.586083 0.25749 0.768248 + outer loop + vertex 0.863854 1.86373 2.57701 + vertex 0.863467 1.8603 2.57786 + vertex 0.86634 1.86299 2.57915 + endloop + endfacet + facet normal -0.580397 0.257888 0.77242 + outer loop + vertex 0.863854 1.86373 2.57701 + vertex 0.861535 1.86193 2.57587 + vertex 0.863467 1.8603 2.57786 + endloop + endfacet + facet normal -0.592903 0.286527 0.752574 + outer loop + vertex 0.861535 1.86193 2.57587 + vertex 0.863854 1.86373 2.57701 + vertex 0.86183 1.86525 2.57484 + endloop + endfacet + facet normal -0.597798 0.285838 0.748955 + outer loop + vertex 0.861535 1.86193 2.57587 + vertex 0.86183 1.86525 2.57484 + vertex 0.85802 1.86124 2.57332 + endloop + endfacet + facet normal -0.590326 0.274984 0.75888 + outer loop + vertex 0.85802 1.86124 2.57332 + vertex 0.86183 1.86525 2.57484 + vertex 0.859164 1.86645 2.57233 + endloop + endfacet + facet normal -0.575156 0.314156 0.755316 + outer loop + vertex 0.8659 1.86744 2.57702 + vertex 0.86183 1.86525 2.57484 + vertex 0.863854 1.86373 2.57701 + endloop + endfacet + facet normal -0.581659 0.223465 0.782136 + outer loop + vertex 0.869188 1.85656 2.58319 + vertex 0.872436 1.86076 2.58441 + vertex 0.869409 1.86175 2.58187 + endloop + endfacet + facet normal -0.580046 0.196033 0.790644 + outer loop + vertex 0.867473 1.85059 2.58341 + vertex 0.869188 1.85656 2.58319 + vertex 0.865292 1.85364 2.58106 + endloop + endfacet + facet normal -0.589949 0.194806 0.783588 + outer loop + vertex 0.865292 1.85364 2.58106 + vertex 0.862203 1.85071 2.57946 + vertex 0.864379 1.84978 2.58133 + endloop + endfacet + facet normal -0.596831 0.190595 0.779401 + outer loop + vertex 0.85925 1.84653 2.57822 + vertex 0.862203 1.85071 2.57946 + vertex 0.859529 1.85135 2.57726 + endloop + endfacet + facet normal -0.601887 0.19511 0.77438 + outer loop + vertex 0.859406 1.85469 2.57632 + vertex 0.857424 1.85232 2.57538 + vertex 0.859529 1.85135 2.57726 + endloop + endfacet + facet normal -0.592037 0.216846 0.77619 + outer loop + vertex 0.863467 1.8603 2.57786 + vertex 0.86236 1.85544 2.57838 + vertex 0.866043 1.85851 2.58033 + endloop + endfacet + facet normal -0.602947 0.213417 0.768706 + outer loop + vertex 0.860371 1.85834 2.57606 + vertex 0.857309 1.85579 2.57437 + vertex 0.859406 1.85469 2.57632 + endloop + endfacet + facet normal -0.611469 0.197736 0.766163 + outer loop + vertex 0.854428 1.85146 2.57319 + vertex 0.857309 1.85579 2.57437 + vertex 0.854334 1.85668 2.57176 + endloop + endfacet + facet normal -0.614156 0.207508 0.761415 + outer loop + vertex 0.85395 1.86092 2.5703 + vertex 0.851335 1.85777 2.56905 + vertex 0.854334 1.85668 2.57176 + endloop + endfacet + facet normal -0.623423 0.219585 0.750418 + outer loop + vertex 0.850886 1.86252 2.56729 + vertex 0.851335 1.85777 2.56905 + vertex 0.85395 1.86092 2.5703 + endloop + endfacet + facet normal -0.588676 0.297421 0.751666 + outer loop + vertex 0.854403 1.86699 2.56848 + vertex 0.853683 1.86354 2.56928 + vertex 0.855989 1.86439 2.57075 + endloop + endfacet + facet normal -0.629195 0.218399 0.745933 + outer loop + vertex 0.847209 1.8651 2.56343 + vertex 0.847119 1.8601 2.56482 + vertex 0.850886 1.86252 2.56729 + endloop + endfacet + facet normal -0.635037 0.208473 0.743819 + outer loop + vertex 0.843738 1.86563 2.56032 + vertex 0.844181 1.86135 2.56189 + vertex 0.847209 1.8651 2.56343 + endloop + endfacet + facet normal -0.661289 0.209918 0.720161 + outer loop + vertex 0.84106 1.86801 2.55716 + vertex 0.841253 1.86292 2.55882 + vertex 0.843738 1.86563 2.56032 + endloop + endfacet + facet normal -0.62742 0.277222 0.727663 + outer loop + vertex 0.844244 1.87176 2.55862 + vertex 0.843543 1.8684 2.55929 + vertex 0.845571 1.86869 2.56093 + endloop + endfacet + facet normal -0.655501 0.219718 0.722525 + outer loop + vertex 0.838415 1.87072 2.55394 + vertex 0.838374 1.86769 2.55482 + vertex 0.84106 1.86801 2.55716 + endloop + endfacet + facet normal -0.656684 0.204041 0.72604 + outer loop + vertex 0.84106 1.86801 2.55716 + vertex 0.838374 1.86769 2.55482 + vertex 0.838512 1.86472 2.55578 + endloop + endfacet + facet normal -0.672789 0.196813 0.713175 + outer loop + vertex 0.838512 1.86472 2.55578 + vertex 0.836015 1.8625 2.55404 + vertex 0.838652 1.86021 2.55716 + endloop + endfacet + facet normal -0.679807 0.201383 0.705201 + outer loop + vertex 0.835872 1.86774 2.55243 + vertex 0.833298 1.86786 2.54991 + vertex 0.833378 1.86477 2.55087 + endloop + endfacet + facet normal -0.675087 0.200211 0.710052 + outer loop + vertex 0.836015 1.8625 2.55404 + vertex 0.833535 1.86017 2.55234 + vertex 0.836027 1.8579 2.55535 + endloop + endfacet + facet normal -0.682997 0.204833 0.701113 + outer loop + vertex 0.830812 1.86794 2.54744 + vertex 0.830924 1.86264 2.5491 + vertex 0.833378 1.86477 2.55087 + endloop + endfacet + facet normal -0.67223 0.20509 0.711369 + outer loop + vertex 0.833535 1.86017 2.55234 + vertex 0.833569 1.85581 2.55363 + vertex 0.836027 1.8579 2.55535 + endloop + endfacet + facet normal -0.669089 0.205761 0.71413 + outer loop + vertex 0.833569 1.85581 2.55363 + vertex 0.833617 1.85313 2.55445 + vertex 0.835538 1.8538 2.55605 + endloop + endfacet + facet normal -0.668707 0.199627 0.716227 + outer loop + vertex 0.835538 1.8538 2.55605 + vertex 0.833617 1.85313 2.55445 + vertex 0.833911 1.85065 2.55541 + endloop + endfacet + facet normal -0.675992 0.19498 0.710646 + outer loop + vertex 0.833911 1.85065 2.55541 + vertex 0.831377 1.84793 2.55375 + vertex 0.834201 1.84647 2.55683 + endloop + endfacet + facet normal -0.688393 0.193059 0.699173 + outer loop + vertex 0.828815 1.84959 2.55077 + vertex 0.828778 1.84518 2.55195 + vertex 0.831377 1.84793 2.55375 + endloop + endfacet + facet normal -0.699685 0.192033 0.68816 + outer loop + vertex 0.826298 1.8523 2.54745 + vertex 0.826444 1.84728 2.549 + vertex 0.828815 1.84959 2.55077 + endloop + endfacet + facet normal -0.686045 0.201076 0.699221 + outer loop + vertex 0.82866 1.85554 2.54893 + vertex 0.828755 1.85248 2.5499 + vertex 0.831246 1.85277 2.55226 + endloop + endfacet + facet normal -0.687676 0.202624 0.697169 + outer loop + vertex 0.828491 1.86027 2.54739 + vertex 0.82866 1.85554 2.54893 + vertex 0.831091 1.85782 2.55067 + endloop + endfacet + facet normal -0.70706 0.193506 0.680163 + outer loop + vertex 0.826072 1.85781 2.54565 + vertex 0.823579 1.85542 2.54374 + vertex 0.826298 1.8523 2.54745 + endloop + endfacet + facet normal -0.715825 0.190845 0.671694 + outer loop + vertex 0.823541 1.8515 2.54481 + vertex 0.823579 1.85542 2.54374 + vertex 0.820991 1.85252 2.5418 + endloop + endfacet + facet normal -0.726763 0.197231 0.657964 + outer loop + vertex 0.818553 1.85551 2.53821 + vertex 0.818187 1.8508 2.53922 + vertex 0.820991 1.85252 2.5418 + endloop + endfacet + facet normal -0.731378 0.204769 0.650505 + outer loop + vertex 0.815928 1.84766 2.53754 + vertex 0.816068 1.84268 2.53927 + vertex 0.818192 1.84511 2.54089 + endloop + endfacet + facet normal -0.724049 0.189979 0.663069 + outer loop + vertex 0.818192 1.84511 2.54089 + vertex 0.816068 1.84268 2.53927 + vertex 0.818447 1.84058 2.54247 + endloop + endfacet + facet normal -0.719772 0.19824 0.665303 + outer loop + vertex 0.816039 1.83796 2.54064 + vertex 0.818447 1.84058 2.54247 + vertex 0.816068 1.84268 2.53927 + endloop + endfacet + facet normal -0.741329 0.191911 0.643119 + outer loop + vertex 0.816068 1.84268 2.53927 + vertex 0.81383 1.8404 2.53737 + vertex 0.816039 1.83796 2.54064 + endloop + endfacet + facet normal -0.743985 0.198864 0.637918 + outer loop + vertex 0.814222 1.8442 2.53664 + vertex 0.81383 1.8404 2.53737 + vertex 0.816068 1.84268 2.53927 + endloop + endfacet + facet normal -0.716897 0.192208 0.67016 + outer loop + vertex 0.818496 1.83581 2.54389 + vertex 0.818447 1.84058 2.54247 + vertex 0.816039 1.83796 2.54064 + endloop + endfacet + facet normal -0.711052 0.203309 0.673105 + outer loop + vertex 0.81613 1.83256 2.54237 + vertex 0.818496 1.83581 2.54389 + vertex 0.816039 1.83796 2.54064 + endloop + endfacet + facet normal -0.733446 0.19584 0.650925 + outer loop + vertex 0.816039 1.83796 2.54064 + vertex 0.81357 1.8356 2.53857 + vertex 0.81613 1.83256 2.54237 + endloop + endfacet + facet normal -0.720961 0.215808 0.658515 + outer loop + vertex 0.81357 1.8356 2.53857 + vertex 0.813433 1.83166 2.53971 + vertex 0.81613 1.83256 2.54237 + endloop + endfacet + facet normal -0.735598 0.201847 0.646647 + outer loop + vertex 0.81383 1.8404 2.53737 + vertex 0.81357 1.8356 2.53857 + vertex 0.816039 1.83796 2.54064 + endloop + endfacet + facet normal -0.743357 0.20018 0.638239 + outer loop + vertex 0.815928 1.84766 2.53754 + vertex 0.814222 1.8442 2.53664 + vertex 0.816068 1.84268 2.53927 + endloop + endfacet + facet normal -0.722205 0.19829 0.662647 + outer loop + vertex 0.818187 1.8508 2.53922 + vertex 0.817998 1.84791 2.53988 + vertex 0.819776 1.84806 2.54177 + endloop + endfacet + facet normal -0.715742 0.187566 0.672705 + outer loop + vertex 0.819776 1.84806 2.54177 + vertex 0.821042 1.84371 2.54433 + vertex 0.822319 1.84831 2.54441 + endloop + endfacet + facet normal -0.711887 0.186031 0.677207 + outer loop + vertex 0.823601 1.8406 2.54788 + vertex 0.824027 1.84523 2.54705 + vertex 0.821042 1.84371 2.54433 + endloop + endfacet + facet normal -0.706356 0.186702 0.682791 + outer loop + vertex 0.823601 1.8406 2.54788 + vertex 0.823472 1.83584 2.54905 + vertex 0.825994 1.83803 2.55106 + endloop + endfacet + facet normal -0.704017 0.187755 0.684915 + outer loop + vertex 0.823484 1.83281 2.54989 + vertex 0.823472 1.83584 2.54905 + vertex 0.821034 1.83282 2.54737 + endloop + endfacet + facet normal -0.709321 0.19448 0.677526 + outer loop + vertex 0.818447 1.84058 2.54247 + vertex 0.818496 1.83581 2.54389 + vertex 0.820989 1.8382 2.54581 + endloop + endfacet + facet normal -0.703088 0.199974 0.682406 + outer loop + vertex 0.821034 1.83282 2.54737 + vertex 0.818552 1.83274 2.54484 + vertex 0.818657 1.82977 2.54581 + endloop + endfacet + facet normal -0.720966 0.216849 0.658168 + outer loop + vertex 0.81613 1.83256 2.54237 + vertex 0.813433 1.83166 2.53971 + vertex 0.814374 1.82913 2.54158 + endloop + endfacet + facet normal -0.701261 0.195266 0.685641 + outer loop + vertex 0.818622 1.82065 2.54841 + vertex 0.818723 1.82525 2.5472 + vertex 0.816234 1.82277 2.54536 + endloop + endfacet + facet normal -0.701645 0.196127 0.685002 + outer loop + vertex 0.816234 1.82277 2.54536 + vertex 0.818723 1.82525 2.5472 + vertex 0.816333 1.82751 2.54411 + endloop + endfacet + facet normal -0.699018 0.200749 0.686348 + outer loop + vertex 0.818657 1.82977 2.54581 + vertex 0.816333 1.82751 2.54411 + vertex 0.818723 1.82525 2.5472 + endloop + endfacet + facet normal -0.695246 0.191424 0.692812 + outer loop + vertex 0.818622 1.82065 2.54841 + vertex 0.818596 1.81703 2.54938 + vertex 0.820728 1.81861 2.55109 + endloop + endfacet + facet normal -0.744304 0.167154 0.646584 + outer loop + vertex 0.814115 1.80932 2.54669 + vertex 0.812153 1.80833 2.54469 + vertex 0.813889 1.80572 2.54736 + endloop + endfacet + facet normal -0.745069 0.166037 0.645991 + outer loop + vertex 0.811118 1.80371 2.54468 + vertex 0.813889 1.80572 2.54736 + vertex 0.812153 1.80833 2.54469 + endloop + endfacet + facet normal -0.771003 0.171913 0.613189 + outer loop + vertex 0.809927 1.80771 2.54207 + vertex 0.811118 1.80371 2.54468 + vertex 0.812153 1.80833 2.54469 + endloop + endfacet + facet normal -0.744985 0.165665 0.646183 + outer loop + vertex 0.813425 1.80087 2.54807 + vertex 0.813889 1.80572 2.54736 + vertex 0.811118 1.80371 2.54468 + endloop + endfacet + facet normal -0.703038 0.180612 0.687835 + outer loop + vertex 0.819464 1.80667 2.55296 + vertex 0.819691 1.8117 2.55187 + vertex 0.81654 1.80896 2.54937 + endloop + endfacet + facet normal -0.714626 0.161354 0.680643 + outer loop + vertex 0.818126 1.79587 2.55429 + vertex 0.818484 1.80109 2.55343 + vertex 0.815727 1.7983 2.5512 + endloop + endfacet + facet normal -0.732238 0.128834 0.668752 + outer loop + vertex 0.815651 1.79265 2.5522 + vertex 0.818126 1.79587 2.55429 + vertex 0.815727 1.7983 2.5512 + endloop + endfacet + facet normal -0.734272 0.132279 0.665843 + outer loop + vertex 0.818121 1.79183 2.55509 + vertex 0.818126 1.79587 2.55429 + vertex 0.815651 1.79265 2.5522 + endloop + endfacet + facet normal -0.726568 0.166885 0.666519 + outer loop + vertex 0.813889 1.80572 2.54736 + vertex 0.813425 1.80087 2.54807 + vertex 0.816185 1.80358 2.5504 + endloop + endfacet + facet normal -0.732743 0.128745 0.668216 + outer loop + vertex 0.815727 1.7983 2.5512 + vertex 0.81313 1.79566 2.54886 + vertex 0.815651 1.79265 2.5522 + endloop + endfacet + facet normal -0.748145 0.101912 0.655662 + outer loop + vertex 0.81313 1.79566 2.54886 + vertex 0.812955 1.79056 2.54945 + vertex 0.815651 1.79265 2.5522 + endloop + endfacet + facet normal -0.746975 0.102024 0.656978 + outer loop + vertex 0.812955 1.79056 2.54945 + vertex 0.81313 1.79566 2.54886 + vertex 0.810643 1.79311 2.54643 + endloop + endfacet + facet normal -0.769794 0.14281 0.622111 + outer loop + vertex 0.808754 1.80075 2.54255 + vertex 0.808407 1.7958 2.54326 + vertex 0.810858 1.79833 2.54571 + endloop + endfacet +endsolid diff --git a/noether_examples/meshes/outputsBackDoor/output_2.stl b/noether_examples/meshes/outputsBackDoor/output_2.stl new file mode 100644 index 00000000..eec6ba63 --- /dev/null +++ b/noether_examples/meshes/outputsBackDoor/output_2.stl @@ -0,0 +1,6841 @@ +solid ascii + facet normal -0.790611 -0.200339 0.578618 + outer loop + vertex 0.82088 1.15952 2.53756 + vertex 0.818772 1.157 2.53381 + vertex 0.821308 1.15438 2.53637 + endloop + endfacet + facet normal -0.759398 -0.206652 0.616936 + outer loop + vertex 0.821308 1.15438 2.53637 + vertex 0.823341 1.15581 2.53935 + vertex 0.82088 1.15952 2.53756 + endloop + endfacet + facet normal -0.765747 -0.19146 0.613982 + outer loop + vertex 0.823629 1.15177 2.53845 + vertex 0.823341 1.15581 2.53935 + vertex 0.821308 1.15438 2.53637 + endloop + endfacet + facet normal -0.733618 -0.197264 0.650301 + outer loop + vertex 0.823341 1.15581 2.53935 + vertex 0.823629 1.15177 2.53845 + vertex 0.825541 1.15365 2.54118 + endloop + endfacet + facet normal -0.735306 -0.201787 0.646998 + outer loop + vertex 0.824943 1.15648 2.54138 + vertex 0.823341 1.15581 2.53935 + vertex 0.825541 1.15365 2.54118 + endloop + endfacet + facet normal -0.716063 -0.199296 0.668981 + outer loop + vertex 0.825541 1.15365 2.54118 + vertex 0.827026 1.15741 2.54388 + vertex 0.824943 1.15648 2.54138 + endloop + endfacet + facet normal -0.713031 -0.202197 0.671344 + outer loop + vertex 0.828344 1.15189 2.54362 + vertex 0.827026 1.15741 2.54388 + vertex 0.825541 1.15365 2.54118 + endloop + endfacet + facet normal -0.712758 -0.200765 0.672063 + outer loop + vertex 0.826095 1.14872 2.54029 + vertex 0.828344 1.15189 2.54362 + vertex 0.825541 1.15365 2.54118 + endloop + endfacet + facet normal -0.710908 -0.203329 0.673251 + outer loop + vertex 0.829365 1.14695 2.54321 + vertex 0.828344 1.15189 2.54362 + vertex 0.826095 1.14872 2.54029 + endloop + endfacet + facet normal -0.702679 -0.202372 0.68212 + outer loop + vertex 0.828344 1.15189 2.54362 + vertex 0.829365 1.14695 2.54321 + vertex 0.831388 1.14971 2.54611 + endloop + endfacet + facet normal -0.702827 -0.20295 0.681796 + outer loop + vertex 0.830838 1.15495 2.5471 + vertex 0.828344 1.15189 2.54362 + vertex 0.831388 1.14971 2.54611 + endloop + endfacet + facet normal -0.695998 -0.203522 0.688597 + outer loop + vertex 0.831388 1.14971 2.54611 + vertex 0.833488 1.15177 2.54884 + vertex 0.830838 1.15495 2.5471 + endloop + endfacet + facet normal -0.69626 -0.203956 0.688203 + outer loop + vertex 0.833448 1.15512 2.5498 + vertex 0.830838 1.15495 2.5471 + vertex 0.833488 1.15177 2.54884 + endloop + endfacet + facet normal -0.687283 -0.206208 0.696506 + outer loop + vertex 0.833488 1.15177 2.54884 + vertex 0.835224 1.15325 2.55099 + vertex 0.833448 1.15512 2.5498 + endloop + endfacet + facet normal -0.685508 -0.202764 0.69926 + outer loop + vertex 0.835224 1.15325 2.55099 + vertex 0.835358 1.15645 2.55205 + vertex 0.833448 1.15512 2.5498 + endloop + endfacet + facet normal -0.685705 -0.202354 0.699186 + outer loop + vertex 0.833448 1.15512 2.5498 + vertex 0.835358 1.15645 2.55205 + vertex 0.83266 1.15862 2.55004 + endloop + endfacet + facet normal -0.685986 -0.203181 0.698671 + outer loop + vertex 0.835358 1.15645 2.55205 + vertex 0.835281 1.16116 2.55335 + vertex 0.83266 1.15862 2.55004 + endloop + endfacet + facet normal -0.684548 -0.205589 0.699376 + outer loop + vertex 0.83266 1.15862 2.55004 + vertex 0.835281 1.16116 2.55335 + vertex 0.831382 1.16383 2.55032 + endloop + endfacet + facet normal -0.695411 -0.207642 0.68796 + outer loop + vertex 0.831382 1.16383 2.55032 + vertex 0.829747 1.15991 2.54748 + vertex 0.83266 1.15862 2.55004 + endloop + endfacet + facet normal -0.695173 -0.205115 0.688958 + outer loop + vertex 0.83266 1.15862 2.55004 + vertex 0.829747 1.15991 2.54748 + vertex 0.830838 1.15495 2.5471 + endloop + endfacet + facet normal -0.705662 -0.206574 0.677767 + outer loop + vertex 0.829747 1.15991 2.54748 + vertex 0.827026 1.15741 2.54388 + vertex 0.830838 1.15495 2.5471 + endloop + endfacet + facet normal -0.703566 -0.210327 0.678791 + outer loop + vertex 0.827026 1.15741 2.54388 + vertex 0.829747 1.15991 2.54748 + vertex 0.82757 1.16148 2.54571 + endloop + endfacet + facet normal -0.714043 -0.204759 0.669489 + outer loop + vertex 0.827026 1.15741 2.54388 + vertex 0.82757 1.16148 2.54571 + vertex 0.825304 1.16211 2.54349 + endloop + endfacet + facet normal -0.721687 -0.208345 0.660121 + outer loop + vertex 0.827026 1.15741 2.54388 + vertex 0.825304 1.16211 2.54349 + vertex 0.823956 1.15911 2.54106 + endloop + endfacet + facet normal -0.719178 -0.190327 0.66825 + outer loop + vertex 0.827026 1.15741 2.54388 + vertex 0.823956 1.15911 2.54106 + vertex 0.824943 1.15648 2.54138 + endloop + endfacet + facet normal -0.736147 -0.199263 0.646824 + outer loop + vertex 0.823341 1.15581 2.53935 + vertex 0.824943 1.15648 2.54138 + vertex 0.823956 1.15911 2.54106 + endloop + endfacet + facet normal -0.748569 -0.190803 0.635011 + outer loop + vertex 0.823956 1.15911 2.54106 + vertex 0.82088 1.15952 2.53756 + vertex 0.823341 1.15581 2.53935 + endloop + endfacet + facet normal -0.746654 -0.210684 0.630967 + outer loop + vertex 0.823956 1.15911 2.54106 + vertex 0.822414 1.16342 2.54068 + vertex 0.82088 1.15952 2.53756 + endloop + endfacet + facet normal -0.727843 -0.201769 0.655388 + outer loop + vertex 0.823956 1.15911 2.54106 + vertex 0.825304 1.16211 2.54349 + vertex 0.822414 1.16342 2.54068 + endloop + endfacet + facet normal -0.72793 -0.202965 0.654922 + outer loop + vertex 0.825304 1.16211 2.54349 + vertex 0.824114 1.1666 2.54356 + vertex 0.822414 1.16342 2.54068 + endloop + endfacet + facet normal -0.739549 -0.188783 0.646087 + outer loop + vertex 0.822414 1.16342 2.54068 + vertex 0.824114 1.1666 2.54356 + vertex 0.821009 1.16864 2.5406 + endloop + endfacet + facet normal -0.737664 -0.178588 0.651121 + outer loop + vertex 0.824114 1.1666 2.54356 + vertex 0.823483 1.17113 2.54408 + vertex 0.821009 1.16864 2.5406 + endloop + endfacet + facet normal -0.762912 -0.128864 0.633529 + outer loop + vertex 0.821009 1.16864 2.5406 + vertex 0.823483 1.17113 2.54408 + vertex 0.821034 1.17461 2.54184 + endloop + endfacet + facet normal -0.757211 -0.130247 0.640053 + outer loop + vertex 0.821034 1.17461 2.54184 + vertex 0.818564 1.17194 2.53838 + vertex 0.821009 1.16864 2.5406 + endloop + endfacet + facet normal -0.752806 -0.12249 0.646746 + outer loop + vertex 0.818564 1.17194 2.53838 + vertex 0.818563 1.16813 2.53765 + vertex 0.821009 1.16864 2.5406 + endloop + endfacet + facet normal -0.760915 -0.125477 0.636604 + outer loop + vertex 0.824111 1.17465 2.54553 + vertex 0.821034 1.17461 2.54184 + vertex 0.823483 1.17113 2.54408 + endloop + endfacet + facet normal -0.754038 -0.129695 0.643899 + outer loop + vertex 0.823483 1.17113 2.54408 + vertex 0.825148 1.1721 2.54623 + vertex 0.824111 1.17465 2.54553 + endloop + endfacet + facet normal -0.721688 -0.105438 0.684141 + outer loop + vertex 0.827268 1.17244 2.54852 + vertex 0.824111 1.17465 2.54553 + vertex 0.825148 1.1721 2.54623 + endloop + endfacet + facet normal -0.708846 -0.176586 0.682902 + outer loop + vertex 0.82588 1.16921 2.54624 + vertex 0.827268 1.17244 2.54852 + vertex 0.825148 1.1721 2.54623 + endloop + endfacet + facet normal -0.70472 -0.180618 0.68611 + outer loop + vertex 0.828498 1.16727 2.54842 + vertex 0.827268 1.17244 2.54852 + vertex 0.82588 1.16921 2.54624 + endloop + endfacet + facet normal -0.709212 -0.196972 0.67692 + outer loop + vertex 0.82674 1.16498 2.54591 + vertex 0.828498 1.16727 2.54842 + vertex 0.82588 1.16921 2.54624 + endloop + endfacet + facet normal -0.719349 -0.198165 0.665784 + outer loop + vertex 0.82588 1.16921 2.54624 + vertex 0.824114 1.1666 2.54356 + vertex 0.82674 1.16498 2.54591 + endloop + endfacet + facet normal -0.70529 -0.202641 0.67934 + outer loop + vertex 0.828846 1.16343 2.54763 + vertex 0.828498 1.16727 2.54842 + vertex 0.82674 1.16498 2.54591 + endloop + endfacet + facet normal -0.706215 -0.206135 0.677325 + outer loop + vertex 0.82757 1.16148 2.54571 + vertex 0.828846 1.16343 2.54763 + vertex 0.82674 1.16498 2.54591 + endloop + endfacet + facet normal -0.696022 -0.203676 0.688527 + outer loop + vertex 0.828498 1.16727 2.54842 + vertex 0.828846 1.16343 2.54763 + vertex 0.831382 1.16383 2.55032 + endloop + endfacet + facet normal -0.695702 -0.203142 0.689008 + outer loop + vertex 0.830532 1.16939 2.5511 + vertex 0.828498 1.16727 2.54842 + vertex 0.831382 1.16383 2.55032 + endloop + endfacet + facet normal -0.688703 -0.20306 0.696028 + outer loop + vertex 0.831382 1.16383 2.55032 + vertex 0.833768 1.16689 2.55357 + vertex 0.830532 1.16939 2.5511 + endloop + endfacet + facet normal -0.684663 -0.190453 0.703537 + outer loop + vertex 0.833768 1.16689 2.55357 + vertex 0.832178 1.17254 2.55355 + vertex 0.830532 1.16939 2.5511 + endloop + endfacet + facet normal -0.689746 -0.185038 0.700009 + outer loop + vertex 0.830532 1.16939 2.5511 + vertex 0.832178 1.17254 2.55355 + vertex 0.829704 1.17265 2.55114 + endloop + endfacet + facet normal -0.71225 -0.190444 0.675597 + outer loop + vertex 0.829704 1.17265 2.55114 + vertex 0.827268 1.17244 2.54852 + vertex 0.830532 1.16939 2.5511 + endloop + endfacet + facet normal -0.720552 -0.139023 0.679321 + outer loop + vertex 0.827268 1.17244 2.54852 + vertex 0.829704 1.17265 2.55114 + vertex 0.828669 1.1754 2.55061 + endloop + endfacet + facet normal -0.695055 -0.123856 0.708207 + outer loop + vertex 0.832178 1.17254 2.55355 + vertex 0.828669 1.1754 2.55061 + vertex 0.829704 1.17265 2.55114 + endloop + endfacet + facet normal -0.696268 -0.12717 0.706427 + outer loop + vertex 0.832178 1.17254 2.55355 + vertex 0.830296 1.17742 2.55258 + vertex 0.828669 1.1754 2.55061 + endloop + endfacet + facet normal -0.72063 -0.0891306 0.687566 + outer loop + vertex 0.828669 1.1754 2.55061 + vertex 0.830296 1.17742 2.55258 + vertex 0.827087 1.179 2.54942 + endloop + endfacet + facet normal -0.723759 -0.0917101 0.683931 + outer loop + vertex 0.828669 1.1754 2.55061 + vertex 0.827087 1.179 2.54942 + vertex 0.825628 1.17704 2.54761 + endloop + endfacet + facet normal -0.730491 -0.128274 0.670767 + outer loop + vertex 0.827268 1.17244 2.54852 + vertex 0.828669 1.1754 2.55061 + vertex 0.825628 1.17704 2.54761 + endloop + endfacet + facet normal -0.713994 -0.137999 0.686417 + outer loop + vertex 0.832178 1.17254 2.55355 + vertex 0.833632 1.17557 2.55567 + vertex 0.830296 1.17742 2.55258 + endloop + endfacet + facet normal -0.705608 -0.0968373 0.701954 + outer loop + vertex 0.833632 1.17557 2.55567 + vertex 0.832026 1.18031 2.55471 + vertex 0.830296 1.17742 2.55258 + endloop + endfacet + facet normal -0.721219 -0.105653 0.684602 + outer loop + vertex 0.833632 1.17557 2.55567 + vertex 0.835421 1.17772 2.55789 + vertex 0.832026 1.18031 2.55471 + endloop + endfacet + facet normal -0.719025 -0.0986807 0.687942 + outer loop + vertex 0.835421 1.17772 2.55789 + vertex 0.834707 1.18205 2.55776 + vertex 0.832026 1.18031 2.55471 + endloop + endfacet + facet normal -0.731262 -0.0642739 0.679061 + outer loop + vertex 0.832026 1.18031 2.55471 + vertex 0.834707 1.18205 2.55776 + vertex 0.832428 1.18421 2.55551 + endloop + endfacet + facet normal -0.713033 -0.0975079 0.694317 + outer loop + vertex 0.834707 1.18205 2.55776 + vertex 0.835421 1.17772 2.55789 + vertex 0.837464 1.17969 2.56026 + endloop + endfacet + facet normal -0.70596 -0.0791496 0.703815 + outer loop + vertex 0.837063 1.18424 2.56037 + vertex 0.834707 1.18205 2.55776 + vertex 0.837464 1.17969 2.56026 + endloop + endfacet + facet normal -0.693108 -0.0783212 0.716566 + outer loop + vertex 0.837464 1.17969 2.56026 + vertex 0.840266 1.18133 2.56315 + vertex 0.837063 1.18424 2.56037 + endloop + endfacet + facet normal -0.676625 -0.123137 0.725958 + outer loop + vertex 0.840063 1.17674 2.56219 + vertex 0.840266 1.18133 2.56315 + vertex 0.837464 1.17969 2.56026 + endloop + endfacet + facet normal -0.67802 -0.125477 0.724255 + outer loop + vertex 0.83791 1.17609 2.56006 + vertex 0.840063 1.17674 2.56219 + vertex 0.837464 1.17969 2.56026 + endloop + endfacet + facet normal -0.666125 -0.170562 0.726076 + outer loop + vertex 0.839722 1.17357 2.56113 + vertex 0.840063 1.17674 2.56219 + vertex 0.83791 1.17609 2.56006 + endloop + endfacet + facet normal -0.678048 -0.185441 0.71124 + outer loop + vertex 0.837133 1.17274 2.55844 + vertex 0.839722 1.17357 2.56113 + vertex 0.83791 1.17609 2.56006 + endloop + endfacet + facet normal -0.707478 -0.16681 0.686767 + outer loop + vertex 0.837133 1.17274 2.55844 + vertex 0.83791 1.17609 2.56006 + vertex 0.835421 1.17772 2.55789 + endloop + endfacet + facet normal -0.670759 -0.209266 0.711541 + outer loop + vertex 0.839722 1.17357 2.56113 + vertex 0.837133 1.17274 2.55844 + vertex 0.84085 1.16971 2.56106 + endloop + endfacet + facet normal -0.654575 -0.204827 0.727721 + outer loop + vertex 0.84085 1.16971 2.56106 + vertex 0.842731 1.17262 2.56357 + vertex 0.839722 1.17357 2.56113 + endloop + endfacet + facet normal -0.651322 -0.208544 0.729582 + outer loop + vertex 0.844189 1.16736 2.56336 + vertex 0.842731 1.17262 2.56357 + vertex 0.84085 1.16971 2.56106 + endloop + endfacet + facet normal -0.651781 -0.210006 0.728752 + outer loop + vertex 0.842289 1.16493 2.56097 + vertex 0.844189 1.16736 2.56336 + vertex 0.84085 1.16971 2.56106 + endloop + endfacet + facet normal -0.659214 -0.212103 0.721422 + outer loop + vertex 0.84085 1.16971 2.56106 + vertex 0.838973 1.16729 2.55863 + vertex 0.842289 1.16493 2.56097 + endloop + endfacet + facet normal -0.658086 -0.208438 0.723517 + outer loop + vertex 0.838973 1.16729 2.55863 + vertex 0.84051 1.16244 2.55863 + vertex 0.842289 1.16493 2.56097 + endloop + endfacet + facet normal -0.657384 -0.209302 0.723906 + outer loop + vertex 0.843725 1.16039 2.56096 + vertex 0.842289 1.16493 2.56097 + vertex 0.84051 1.16244 2.55863 + endloop + endfacet + facet normal -0.656366 -0.205379 0.725949 + outer loop + vertex 0.842133 1.15738 2.55867 + vertex 0.843725 1.16039 2.56096 + vertex 0.84051 1.16244 2.55863 + endloop + endfacet + facet normal -0.663683 -0.207787 0.718574 + outer loop + vertex 0.842133 1.15738 2.55867 + vertex 0.84051 1.16244 2.55863 + vertex 0.838768 1.16007 2.55634 + endloop + endfacet + facet normal -0.661313 -0.201341 0.722584 + outer loop + vertex 0.842133 1.15738 2.55867 + vertex 0.838768 1.16007 2.55634 + vertex 0.839764 1.15737 2.5565 + endloop + endfacet + facet normal -0.660663 -0.205852 0.721907 + outer loop + vertex 0.840466 1.15454 2.55633 + vertex 0.842133 1.15738 2.55867 + vertex 0.839764 1.15737 2.5565 + endloop + endfacet + facet normal -0.668823 -0.207402 0.713905 + outer loop + vertex 0.839764 1.15737 2.5565 + vertex 0.837886 1.15715 2.55467 + vertex 0.840466 1.15454 2.55633 + endloop + endfacet + facet normal -0.668926 -0.207601 0.71375 + outer loop + vertex 0.837886 1.15715 2.55467 + vertex 0.838022 1.15263 2.55348 + vertex 0.840466 1.15454 2.55633 + endloop + endfacet + facet normal -0.666722 -0.211701 0.714608 + outer loop + vertex 0.840466 1.15454 2.55633 + vertex 0.838022 1.15263 2.55348 + vertex 0.841692 1.1499 2.5561 + endloop + endfacet + facet normal -0.659268 -0.210093 0.72196 + outer loop + vertex 0.841692 1.1499 2.5561 + vertex 0.843634 1.15229 2.55857 + vertex 0.840466 1.15454 2.55633 + endloop + endfacet + facet normal -0.651098 -0.221005 0.726104 + outer loop + vertex 0.845073 1.14768 2.55846 + vertex 0.843634 1.15229 2.55857 + vertex 0.841692 1.1499 2.5561 + endloop + endfacet + facet normal -0.652654 -0.226741 0.722932 + outer loop + vertex 0.843522 1.14528 2.5563 + vertex 0.845073 1.14768 2.55846 + vertex 0.841692 1.1499 2.5561 + endloop + endfacet + facet normal -0.656337 -0.228369 0.719075 + outer loop + vertex 0.843522 1.14528 2.5563 + vertex 0.841692 1.1499 2.5561 + vertex 0.839891 1.14669 2.55344 + endloop + endfacet + facet normal -0.658242 -0.255441 0.708144 + outer loop + vertex 0.843522 1.14528 2.5563 + vertex 0.839891 1.14669 2.55344 + vertex 0.843028 1.14216 2.55472 + endloop + endfacet + facet normal -0.653709 -0.257845 0.711464 + outer loop + vertex 0.843028 1.14216 2.55472 + vertex 0.844857 1.14244 2.5565 + vertex 0.843522 1.14528 2.5563 + endloop + endfacet + facet normal -0.613923 -0.236259 0.75318 + outer loop + vertex 0.847245 1.14277 2.55855 + vertex 0.843522 1.14528 2.5563 + vertex 0.844857 1.14244 2.5565 + endloop + endfacet + facet normal -0.647123 -0.243703 0.722385 + outer loop + vertex 0.843028 1.14216 2.55472 + vertex 0.839891 1.14669 2.55344 + vertex 0.840293 1.14187 2.55217 + endloop + endfacet + facet normal -0.626042 -0.324553 0.709039 + outer loop + vertex 0.844276 1.13707 2.55349 + vertex 0.843028 1.14216 2.55472 + vertex 0.840293 1.14187 2.55217 + endloop + endfacet + facet normal -0.592512 -0.284499 0.753651 + outer loop + vertex 0.84021 1.13873 2.55092 + vertex 0.844276 1.13707 2.55349 + vertex 0.840293 1.14187 2.55217 + endloop + endfacet + facet normal -0.635175 -0.271237 0.723176 + outer loop + vertex 0.84021 1.13873 2.55092 + vertex 0.840293 1.14187 2.55217 + vertex 0.837997 1.14138 2.54997 + endloop + endfacet + facet normal -0.647006 -0.231117 0.726614 + outer loop + vertex 0.837997 1.14138 2.54997 + vertex 0.840293 1.14187 2.55217 + vertex 0.837233 1.14504 2.55046 + endloop + endfacet + facet normal -0.668154 -0.232892 0.706633 + outer loop + vertex 0.837997 1.14138 2.54997 + vertex 0.837233 1.14504 2.55046 + vertex 0.835415 1.14301 2.54807 + endloop + endfacet + facet normal -0.674117 -0.260485 0.691169 + outer loop + vertex 0.837449 1.13817 2.54823 + vertex 0.837997 1.14138 2.54997 + vertex 0.835415 1.14301 2.54807 + endloop + endfacet + facet normal -0.65848 -0.25334 0.708677 + outer loop + vertex 0.837449 1.13817 2.54823 + vertex 0.835415 1.14301 2.54807 + vertex 0.833805 1.14076 2.54577 + endloop + endfacet + facet normal -0.650968 -0.228333 0.723951 + outer loop + vertex 0.837449 1.13817 2.54823 + vertex 0.833805 1.14076 2.54577 + vertex 0.834928 1.13798 2.5459 + endloop + endfacet + facet normal -0.681038 -0.242005 0.691101 + outer loop + vertex 0.832585 1.13765 2.54347 + vertex 0.834928 1.13798 2.5459 + vertex 0.833805 1.14076 2.54577 + endloop + endfacet + facet normal -0.685479 -0.219245 0.694299 + outer loop + vertex 0.833805 1.14076 2.54577 + vertex 0.835415 1.14301 2.54807 + vertex 0.832405 1.14508 2.54575 + endloop + endfacet + facet normal -0.689215 -0.220475 0.690198 + outer loop + vertex 0.833805 1.14076 2.54577 + vertex 0.832405 1.14508 2.54575 + vertex 0.830719 1.14239 2.54321 + endloop + endfacet + facet normal -0.690957 -0.233107 0.68428 + outer loop + vertex 0.832585 1.13765 2.54347 + vertex 0.833805 1.14076 2.54577 + vertex 0.830719 1.14239 2.54321 + endloop + endfacet + facet normal -0.685796 -0.230739 0.690249 + outer loop + vertex 0.832585 1.13765 2.54347 + vertex 0.830719 1.14239 2.54321 + vertex 0.829158 1.13966 2.54074 + endloop + endfacet + facet normal -0.681458 -0.207705 0.701765 + outer loop + vertex 0.832585 1.13765 2.54347 + vertex 0.829158 1.13966 2.54074 + vertex 0.830301 1.13719 2.54112 + endloop + endfacet + facet normal -0.711622 -0.227377 0.664751 + outer loop + vertex 0.828651 1.13622 2.53902 + vertex 0.830301 1.13719 2.54112 + vertex 0.829158 1.13966 2.54074 + endloop + endfacet + facet normal -0.719735 -0.222601 0.657594 + outer loop + vertex 0.829158 1.13966 2.54074 + vertex 0.825888 1.13976 2.5372 + vertex 0.828651 1.13622 2.53902 + endloop + endfacet + facet normal -0.722779 -0.227598 0.652525 + outer loop + vertex 0.826172 1.1338 2.53543 + vertex 0.828651 1.13622 2.53902 + vertex 0.825888 1.13976 2.5372 + endloop + endfacet + facet normal -0.731944 -0.225234 0.643062 + outer loop + vertex 0.825888 1.13976 2.5372 + vertex 0.823405 1.13679 2.53333 + vertex 0.826172 1.1338 2.53543 + endloop + endfacet + facet normal -0.731299 -0.223755 0.64431 + outer loop + vertex 0.823405 1.13679 2.53333 + vertex 0.823816 1.13286 2.53243 + vertex 0.826172 1.1338 2.53543 + endloop + endfacet + facet normal -0.750868 -0.194132 0.631277 + outer loop + vertex 0.822208 1.14247 2.53365 + vertex 0.823405 1.13679 2.53333 + vertex 0.825888 1.13976 2.5372 + endloop + endfacet + facet normal -0.696803 -0.271224 0.664006 + outer loop + vertex 0.829931 1.13136 2.53838 + vertex 0.828651 1.13622 2.53902 + vertex 0.826172 1.1338 2.53543 + endloop + endfacet + facet normal -0.69635 -0.268729 0.665494 + outer loop + vertex 0.827663 1.12895 2.53504 + vertex 0.829931 1.13136 2.53838 + vertex 0.826172 1.1338 2.53543 + endloop + endfacet + facet normal -0.664593 -0.315216 0.677462 + outer loop + vertex 0.830583 1.127 2.53699 + vertex 0.829931 1.13136 2.53838 + vertex 0.827663 1.12895 2.53504 + endloop + endfacet + facet normal -0.688668 -0.270252 0.67283 + outer loop + vertex 0.828651 1.13622 2.53902 + vertex 0.829931 1.13136 2.53838 + vertex 0.831486 1.13442 2.5412 + endloop + endfacet + facet normal -0.689628 -0.27556 0.669686 + outer loop + vertex 0.830301 1.13719 2.54112 + vertex 0.828651 1.13622 2.53902 + vertex 0.831486 1.13442 2.5412 + endloop + endfacet + facet normal -0.665852 -0.264572 0.697598 + outer loop + vertex 0.831486 1.13442 2.5412 + vertex 0.832585 1.13765 2.54347 + vertex 0.830301 1.13719 2.54112 + endloop + endfacet + facet normal -0.637215 -0.28683 0.715323 + outer loop + vertex 0.835089 1.13265 2.5437 + vertex 0.832585 1.13765 2.54347 + vertex 0.831486 1.13442 2.5412 + endloop + endfacet + facet normal -0.720703 -0.216178 0.658676 + outer loop + vertex 0.829158 1.13966 2.54074 + vertex 0.827582 1.14378 2.54037 + vertex 0.825888 1.13976 2.5372 + endloop + endfacet + facet normal -0.724589 -0.212192 0.655702 + outer loop + vertex 0.827582 1.14378 2.54037 + vertex 0.824654 1.14493 2.53751 + vertex 0.825888 1.13976 2.5372 + endloop + endfacet + facet normal -0.705079 -0.208488 0.677788 + outer loop + vertex 0.829158 1.13966 2.54074 + vertex 0.830719 1.14239 2.54321 + vertex 0.827582 1.14378 2.54037 + endloop + endfacet + facet normal -0.705194 -0.209841 0.67725 + outer loop + vertex 0.830719 1.14239 2.54321 + vertex 0.829365 1.14695 2.54321 + vertex 0.827582 1.14378 2.54037 + endloop + endfacet + facet normal -0.71088 -0.20313 0.673341 + outer loop + vertex 0.827582 1.14378 2.54037 + vertex 0.829365 1.14695 2.54321 + vertex 0.826095 1.14872 2.54029 + endloop + endfacet + facet normal -0.724412 -0.207459 0.65741 + outer loop + vertex 0.826095 1.14872 2.54029 + vertex 0.824654 1.14493 2.53751 + vertex 0.827582 1.14378 2.54037 + endloop + endfacet + facet normal -0.699336 -0.208103 0.68383 + outer loop + vertex 0.829365 1.14695 2.54321 + vertex 0.830719 1.14239 2.54321 + vertex 0.832405 1.14508 2.54575 + endloop + endfacet + facet normal -0.685165 -0.218005 0.694998 + outer loop + vertex 0.835415 1.14301 2.54807 + vertex 0.834265 1.14743 2.54832 + vertex 0.832405 1.14508 2.54575 + endloop + endfacet + facet normal -0.693388 -0.20642 0.690366 + outer loop + vertex 0.832405 1.14508 2.54575 + vertex 0.834265 1.14743 2.54832 + vertex 0.831388 1.14971 2.54611 + endloop + endfacet + facet normal -0.641051 -0.279054 0.71497 + outer loop + vertex 0.837449 1.13817 2.54823 + vertex 0.84021 1.13873 2.55092 + vertex 0.837997 1.14138 2.54997 + endloop + endfacet + facet normal -0.679129 -0.21679 0.701275 + outer loop + vertex 0.834265 1.14743 2.54832 + vertex 0.835415 1.14301 2.54807 + vertex 0.837233 1.14504 2.55046 + endloop + endfacet + facet normal -0.678627 -0.215322 0.702212 + outer loop + vertex 0.83625 1.14957 2.55089 + vertex 0.834265 1.14743 2.54832 + vertex 0.837233 1.14504 2.55046 + endloop + endfacet + facet normal -0.667461 -0.213968 0.713241 + outer loop + vertex 0.837233 1.14504 2.55046 + vertex 0.839891 1.14669 2.55344 + vertex 0.83625 1.14957 2.55089 + endloop + endfacet + facet normal -0.668171 -0.21599 0.711966 + outer loop + vertex 0.839891 1.14669 2.55344 + vertex 0.838022 1.15263 2.55348 + vertex 0.83625 1.14957 2.55089 + endloop + endfacet + facet normal -0.67573 -0.20765 0.707298 + outer loop + vertex 0.83625 1.14957 2.55089 + vertex 0.838022 1.15263 2.55348 + vertex 0.835224 1.15325 2.55099 + endloop + endfacet + facet normal -0.684134 -0.206861 0.699407 + outer loop + vertex 0.833488 1.15177 2.54884 + vertex 0.834265 1.14743 2.54832 + vertex 0.83625 1.14957 2.55089 + endloop + endfacet + facet normal -0.653613 -0.242785 0.71683 + outer loop + vertex 0.840293 1.14187 2.55217 + vertex 0.839891 1.14669 2.55344 + vertex 0.837233 1.14504 2.55046 + endloop + endfacet + facet normal -0.621645 -0.260823 0.7386 + outer loop + vertex 0.847245 1.14277 2.55855 + vertex 0.845073 1.14768 2.55846 + vertex 0.843522 1.14528 2.5563 + endloop + endfacet + facet normal -0.641702 -0.270112 0.717815 + outer loop + vertex 0.847245 1.14277 2.55855 + vertex 0.847816 1.14607 2.5603 + vertex 0.845073 1.14768 2.55846 + endloop + endfacet + facet normal -0.63434 -0.237054 0.735811 + outer loop + vertex 0.847816 1.14607 2.5603 + vertex 0.846958 1.14976 2.56075 + vertex 0.845073 1.14768 2.55846 + endloop + endfacet + facet normal -0.612313 -0.234307 0.755098 + outer loop + vertex 0.847816 1.14607 2.5603 + vertex 0.850182 1.14666 2.5624 + vertex 0.846958 1.14976 2.56075 + endloop + endfacet + facet normal -0.619961 -0.247921 0.744435 + outer loop + vertex 0.850182 1.14666 2.5624 + vertex 0.849645 1.15152 2.56357 + vertex 0.846958 1.14976 2.56075 + endloop + endfacet + facet normal -0.636857 -0.21533 0.740301 + outer loop + vertex 0.846958 1.14976 2.56075 + vertex 0.849645 1.15152 2.56357 + vertex 0.845706 1.15434 2.56101 + endloop + endfacet + facet normal -0.645915 -0.217338 0.731819 + outer loop + vertex 0.845706 1.15434 2.56101 + vertex 0.843634 1.15229 2.55857 + vertex 0.846958 1.14976 2.56075 + endloop + endfacet + facet normal -0.652972 -0.206477 0.728694 + outer loop + vertex 0.842133 1.15738 2.55867 + vertex 0.843634 1.15229 2.55857 + vertex 0.845706 1.15434 2.56101 + endloop + endfacet + facet normal -0.654985 -0.211292 0.7255 + outer loop + vertex 0.844704 1.15743 2.561 + vertex 0.842133 1.15738 2.55867 + vertex 0.845706 1.15434 2.56101 + endloop + endfacet + facet normal -0.646576 -0.208545 0.73379 + outer loop + vertex 0.845706 1.15434 2.56101 + vertex 0.84731 1.15761 2.56335 + vertex 0.844704 1.15743 2.561 + endloop + endfacet + facet normal -0.64756 -0.203103 0.734449 + outer loop + vertex 0.84731 1.15761 2.56335 + vertex 0.843725 1.16039 2.56096 + vertex 0.844704 1.15743 2.561 + endloop + endfacet + facet normal -0.64971 -0.208935 0.730906 + outer loop + vertex 0.84731 1.15761 2.56335 + vertex 0.84548 1.16268 2.56317 + vertex 0.843725 1.16039 2.56096 + endloop + endfacet + facet normal -0.64775 -0.208158 0.732865 + outer loop + vertex 0.84731 1.15761 2.56335 + vertex 0.848059 1.16113 2.56501 + vertex 0.84548 1.16268 2.56317 + endloop + endfacet + facet normal -0.647321 -0.206407 0.733738 + outer loop + vertex 0.848059 1.16113 2.56501 + vertex 0.847411 1.16484 2.56548 + vertex 0.84548 1.16268 2.56317 + endloop + endfacet + facet normal -0.645819 -0.208523 0.734463 + outer loop + vertex 0.844189 1.16736 2.56336 + vertex 0.84548 1.16268 2.56317 + vertex 0.847411 1.16484 2.56548 + endloop + endfacet + facet normal -0.646164 -0.209444 0.733897 + outer loop + vertex 0.846405 1.1696 2.56596 + vertex 0.844189 1.16736 2.56336 + vertex 0.847411 1.16484 2.56548 + endloop + endfacet + facet normal -0.640185 -0.208717 0.739324 + outer loop + vertex 0.847411 1.16484 2.56548 + vertex 0.850214 1.16652 2.56839 + vertex 0.846405 1.1696 2.56596 + endloop + endfacet + facet normal -0.640049 -0.208379 0.739537 + outer loop + vertex 0.850214 1.16652 2.56839 + vertex 0.848617 1.17203 2.56856 + vertex 0.846405 1.1696 2.56596 + endloop + endfacet + facet normal -0.641386 -0.206492 0.738908 + outer loop + vertex 0.846405 1.1696 2.56596 + vertex 0.848617 1.17203 2.56856 + vertex 0.84531 1.17435 2.56633 + endloop + endfacet + facet normal -0.647316 -0.207426 0.733455 + outer loop + vertex 0.84531 1.17435 2.56633 + vertex 0.842731 1.17262 2.56357 + vertex 0.846405 1.1696 2.56596 + endloop + endfacet + facet normal -0.657878 -0.185908 0.729818 + outer loop + vertex 0.842697 1.17708 2.56467 + vertex 0.842731 1.17262 2.56357 + vertex 0.84531 1.17435 2.56633 + endloop + endfacet + facet normal -0.662931 -0.19497 0.722848 + outer loop + vertex 0.844587 1.17727 2.56646 + vertex 0.842697 1.17708 2.56467 + vertex 0.84531 1.17435 2.56633 + endloop + endfacet + facet normal -0.640505 -0.190318 0.743998 + outer loop + vertex 0.84531 1.17435 2.56633 + vertex 0.846907 1.17752 2.56852 + vertex 0.844587 1.17727 2.56646 + endloop + endfacet + facet normal -0.650235 -0.13287 0.748024 + outer loop + vertex 0.846907 1.17752 2.56852 + vertex 0.843599 1.18006 2.56609 + vertex 0.844587 1.17727 2.56646 + endloop + endfacet + facet normal -0.652708 -0.139258 0.744701 + outer loop + vertex 0.846907 1.17752 2.56852 + vertex 0.845327 1.18247 2.56806 + vertex 0.843599 1.18006 2.56609 + endloop + endfacet + facet normal -0.68306 -0.100145 0.723464 + outer loop + vertex 0.843599 1.18006 2.56609 + vertex 0.845327 1.18247 2.56806 + vertex 0.84237 1.18453 2.56555 + endloop + endfacet + facet normal -0.679193 -0.0986168 0.727305 + outer loop + vertex 0.843599 1.18006 2.56609 + vertex 0.84237 1.18453 2.56555 + vertex 0.840266 1.18133 2.56315 + endloop + endfacet + facet normal -0.683897 -0.134884 0.717002 + outer loop + vertex 0.843599 1.18006 2.56609 + vertex 0.840266 1.18133 2.56315 + vertex 0.842697 1.17708 2.56467 + endloop + endfacet + facet normal -0.678689 -0.149936 0.718958 + outer loop + vertex 0.846907 1.17752 2.56852 + vertex 0.847775 1.18095 2.57005 + vertex 0.845327 1.18247 2.56806 + endloop + endfacet + facet normal -0.666281 -0.104516 0.73834 + outer loop + vertex 0.847775 1.18095 2.57005 + vertex 0.847373 1.18464 2.57021 + vertex 0.845327 1.18247 2.56806 + endloop + endfacet + facet normal -0.654534 -0.103693 0.748888 + outer loop + vertex 0.847775 1.18095 2.57005 + vertex 0.849988 1.18171 2.57209 + vertex 0.847373 1.18464 2.57021 + endloop + endfacet + facet normal -0.653613 -0.102228 0.749893 + outer loop + vertex 0.849988 1.18171 2.57209 + vertex 0.850176 1.1864 2.5729 + vertex 0.847373 1.18464 2.57021 + endloop + endfacet + facet normal -0.67031 -0.0600408 0.739649 + outer loop + vertex 0.847373 1.18464 2.57021 + vertex 0.850176 1.1864 2.5729 + vertex 0.847037 1.18932 2.57029 + endloop + endfacet + facet normal -0.654604 -0.102044 0.749053 + outer loop + vertex 0.852593 1.18233 2.57445 + vertex 0.850176 1.1864 2.5729 + vertex 0.849988 1.18171 2.57209 + endloop + endfacet + facet normal -0.639905 -0.167159 0.750053 + outer loop + vertex 0.852711 1.17763 2.57351 + vertex 0.852593 1.18233 2.57445 + vertex 0.849988 1.18171 2.57209 + endloop + endfacet + facet normal -0.628686 -0.155537 0.761947 + outer loop + vertex 0.849606 1.17845 2.57111 + vertex 0.852711 1.17763 2.57351 + vertex 0.849988 1.18171 2.57209 + endloop + endfacet + facet normal -0.63067 -0.193523 0.751535 + outer loop + vertex 0.850706 1.17459 2.57104 + vertex 0.852711 1.17763 2.57351 + vertex 0.849606 1.17845 2.57111 + endloop + endfacet + facet normal -0.643174 -0.196879 0.739977 + outer loop + vertex 0.849606 1.17845 2.57111 + vertex 0.846907 1.17752 2.56852 + vertex 0.850706 1.17459 2.57104 + endloop + endfacet + facet normal -0.642546 -0.195212 0.740964 + outer loop + vertex 0.846907 1.17752 2.56852 + vertex 0.848617 1.17203 2.56856 + vertex 0.850706 1.17459 2.57104 + endloop + endfacet + facet normal -0.634274 -0.20603 0.74515 + outer loop + vertex 0.850706 1.17459 2.57104 + vertex 0.848617 1.17203 2.56856 + vertex 0.85216 1.16974 2.57094 + endloop + endfacet + facet normal -0.627824 -0.204221 0.751087 + outer loop + vertex 0.85216 1.16974 2.57094 + vertex 0.854165 1.17238 2.57333 + vertex 0.850706 1.17459 2.57104 + endloop + endfacet + facet normal -0.627073 -0.205134 0.751465 + outer loop + vertex 0.855479 1.16775 2.57316 + vertex 0.854165 1.17238 2.57333 + vertex 0.85216 1.16974 2.57094 + endloop + endfacet + facet normal -0.626863 -0.204351 0.751854 + outer loop + vertex 0.853812 1.16528 2.5711 + vertex 0.855479 1.16775 2.57316 + vertex 0.85216 1.16974 2.57094 + endloop + endfacet + facet normal -0.634182 -0.20732 0.74487 + outer loop + vertex 0.853812 1.16528 2.5711 + vertex 0.85216 1.16974 2.57094 + vertex 0.850214 1.16652 2.56839 + endloop + endfacet + facet normal -0.633891 -0.203813 0.746085 + outer loop + vertex 0.853812 1.16528 2.5711 + vertex 0.850214 1.16652 2.56839 + vertex 0.852971 1.16231 2.56958 + endloop + endfacet + facet normal -0.631804 -0.205127 0.747494 + outer loop + vertex 0.852971 1.16231 2.56958 + vertex 0.85492 1.16252 2.57128 + vertex 0.853812 1.16528 2.5711 + endloop + endfacet + facet normal -0.619128 -0.199276 0.759585 + outer loop + vertex 0.857337 1.16275 2.57331 + vertex 0.853812 1.16528 2.5711 + vertex 0.85492 1.16252 2.57128 + endloop + endfacet + facet normal -0.616365 -0.213647 0.757924 + outer loop + vertex 0.855745 1.15959 2.57113 + vertex 0.857337 1.16275 2.57331 + vertex 0.85492 1.16252 2.57128 + endloop + endfacet + facet normal -0.629433 -0.216707 0.746225 + outer loop + vertex 0.85492 1.16252 2.57128 + vertex 0.852971 1.16231 2.56958 + vertex 0.855745 1.15959 2.57113 + endloop + endfacet + facet normal -0.627344 -0.212961 0.749057 + outer loop + vertex 0.852971 1.16231 2.56958 + vertex 0.85312 1.15789 2.56845 + vertex 0.855745 1.15959 2.57113 + endloop + endfacet + facet normal -0.635714 -0.211534 0.742376 + outer loop + vertex 0.85312 1.15789 2.56845 + vertex 0.852971 1.16231 2.56958 + vertex 0.850258 1.1619 2.56714 + endloop + endfacet + facet normal -0.633998 -0.209658 0.744372 + outer loop + vertex 0.849989 1.15867 2.566 + vertex 0.85312 1.15789 2.56845 + vertex 0.850258 1.1619 2.56714 + endloop + endfacet + facet normal -0.641541 -0.207005 0.73863 + outer loop + vertex 0.849989 1.15867 2.566 + vertex 0.850258 1.1619 2.56714 + vertex 0.848059 1.16113 2.56501 + endloop + endfacet + facet normal -0.634079 -0.214582 0.742899 + outer loop + vertex 0.851361 1.1548 2.56605 + vertex 0.85312 1.15789 2.56845 + vertex 0.849989 1.15867 2.566 + endloop + endfacet + facet normal -0.64145 -0.217294 0.735748 + outer loop + vertex 0.849989 1.15867 2.566 + vertex 0.84731 1.15761 2.56335 + vertex 0.851361 1.1548 2.56605 + endloop + endfacet + facet normal -0.641952 -0.218897 0.734835 + outer loop + vertex 0.84731 1.15761 2.56335 + vertex 0.849645 1.15152 2.56357 + vertex 0.851361 1.1548 2.56605 + endloop + endfacet + facet normal -0.62446 -0.224171 0.748196 + outer loop + vertex 0.854929 1.15283 2.56844 + vertex 0.85312 1.15789 2.56845 + vertex 0.851361 1.1548 2.56605 + endloop + endfacet + facet normal -0.622098 -0.22333 0.750411 + outer loop + vertex 0.85312 1.15789 2.56845 + vertex 0.854929 1.15283 2.56844 + vertex 0.856848 1.15504 2.57069 + endloop + endfacet + facet normal -0.622081 -0.223285 0.750439 + outer loop + vertex 0.855745 1.15959 2.57113 + vertex 0.85312 1.15789 2.56845 + vertex 0.856848 1.15504 2.57069 + endloop + endfacet + facet normal -0.60836 -0.221091 0.762245 + outer loop + vertex 0.856848 1.15504 2.57069 + vertex 0.859528 1.15682 2.57334 + vertex 0.855745 1.15959 2.57113 + endloop + endfacet + facet normal -0.608258 -0.220825 0.762403 + outer loop + vertex 0.859528 1.15682 2.57334 + vertex 0.857337 1.16275 2.57331 + vertex 0.855745 1.15959 2.57113 + endloop + endfacet + facet normal -0.608881 -0.221059 0.761838 + outer loop + vertex 0.857337 1.16275 2.57331 + vertex 0.859528 1.15682 2.57334 + vertex 0.861336 1.15976 2.57564 + endloop + endfacet + facet normal -0.60926 -0.222023 0.761254 + outer loop + vertex 0.860152 1.16366 2.57583 + vertex 0.857337 1.16275 2.57331 + vertex 0.861336 1.15976 2.57564 + endloop + endfacet + facet normal -0.593349 -0.217844 0.774907 + outer loop + vertex 0.861336 1.15976 2.57564 + vertex 0.863848 1.16228 2.57827 + vertex 0.860152 1.16366 2.57583 + endloop + endfacet + facet normal -0.592486 -0.210961 0.777467 + outer loop + vertex 0.860152 1.16366 2.57583 + vertex 0.863848 1.16228 2.57827 + vertex 0.860427 1.16699 2.57694 + endloop + endfacet + facet normal -0.606315 -0.206627 0.767911 + outer loop + vertex 0.860152 1.16366 2.57583 + vertex 0.860427 1.16699 2.57694 + vertex 0.858117 1.16627 2.57492 + endloop + endfacet + facet normal -0.608023 -0.201335 0.767967 + outer loop + vertex 0.858117 1.16627 2.57492 + vertex 0.860427 1.16699 2.57694 + vertex 0.857448 1.17 2.57537 + endloop + endfacet + facet normal -0.619913 -0.202283 0.758149 + outer loop + vertex 0.858117 1.16627 2.57492 + vertex 0.857448 1.17 2.57537 + vertex 0.855479 1.16775 2.57316 + endloop + endfacet + facet normal -0.62145 -0.208535 0.755191 + outer loop + vertex 0.857337 1.16275 2.57331 + vertex 0.858117 1.16627 2.57492 + vertex 0.855479 1.16775 2.57316 + endloop + endfacet + facet normal -0.608272 -0.201741 0.767662 + outer loop + vertex 0.860427 1.16699 2.57694 + vertex 0.860202 1.17184 2.57804 + vertex 0.857448 1.17 2.57537 + endloop + endfacet + facet normal -0.608401 -0.201494 0.767625 + outer loop + vertex 0.857448 1.17 2.57537 + vertex 0.860202 1.17184 2.57804 + vertex 0.856462 1.17473 2.57584 + endloop + endfacet + facet normal -0.619128 -0.20285 0.758638 + outer loop + vertex 0.856462 1.17473 2.57584 + vertex 0.854165 1.17238 2.57333 + vertex 0.857448 1.17 2.57537 + endloop + endfacet + facet normal -0.622707 -0.197689 0.75707 + outer loop + vertex 0.852711 1.17763 2.57351 + vertex 0.854165 1.17238 2.57333 + vertex 0.856462 1.17473 2.57584 + endloop + endfacet + facet normal -0.621773 -0.195384 0.758435 + outer loop + vertex 0.855446 1.17957 2.57625 + vertex 0.852711 1.17763 2.57351 + vertex 0.856462 1.17473 2.57584 + endloop + endfacet + facet normal -0.614231 -0.194346 0.76482 + outer loop + vertex 0.856462 1.17473 2.57584 + vertex 0.858807 1.17718 2.57834 + vertex 0.855446 1.17957 2.57625 + endloop + endfacet + facet normal -0.609413 -0.181431 0.771815 + outer loop + vertex 0.858807 1.17718 2.57834 + vertex 0.857535 1.18258 2.57861 + vertex 0.855446 1.17957 2.57625 + endloop + endfacet + facet normal -0.621972 -0.167344 0.764949 + outer loop + vertex 0.855446 1.17957 2.57625 + vertex 0.857535 1.18258 2.57861 + vertex 0.854634 1.18332 2.57641 + endloop + endfacet + facet normal -0.637433 -0.170124 0.75149 + outer loop + vertex 0.854634 1.18332 2.57641 + vertex 0.852593 1.18233 2.57445 + vertex 0.855446 1.17957 2.57625 + endloop + endfacet + facet normal -0.654216 -0.124385 0.74601 + outer loop + vertex 0.852593 1.18233 2.57445 + vertex 0.854634 1.18332 2.57641 + vertex 0.852882 1.18563 2.57526 + endloop + endfacet + facet normal -0.640427 -0.1067 0.760571 + outer loop + vertex 0.854634 1.18332 2.57641 + vertex 0.855003 1.18675 2.5772 + vertex 0.852882 1.18563 2.57526 + endloop + endfacet + facet normal -0.618101 -0.113092 0.777921 + outer loop + vertex 0.854634 1.18332 2.57641 + vertex 0.857535 1.18258 2.57861 + vertex 0.855003 1.18675 2.5772 + endloop + endfacet + facet normal -0.641544 -0.135023 0.75511 + outer loop + vertex 0.857535 1.18258 2.57861 + vertex 0.857606 1.18752 2.57955 + vertex 0.855003 1.18675 2.5772 + endloop + endfacet + facet normal -0.6301 -0.136949 0.764342 + outer loop + vertex 0.857606 1.18752 2.57955 + vertex 0.857535 1.18258 2.57861 + vertex 0.860434 1.1845 2.58134 + endloop + endfacet + facet normal -0.632175 -0.140267 0.762024 + outer loop + vertex 0.859741 1.18852 2.5815 + vertex 0.857606 1.18752 2.57955 + vertex 0.860434 1.1845 2.58134 + endloop + endfacet + facet normal -0.603176 -0.136226 0.785889 + outer loop + vertex 0.860434 1.1845 2.58134 + vertex 0.862833 1.18755 2.58371 + vertex 0.859741 1.18852 2.5815 + endloop + endfacet + facet normal -0.594376 -0.0745088 0.800728 + outer loop + vertex 0.859741 1.18852 2.5815 + vertex 0.862833 1.18755 2.58371 + vertex 0.860304 1.19229 2.58227 + endloop + endfacet + facet normal -0.6255 -0.0651358 0.7775 + outer loop + vertex 0.859741 1.18852 2.5815 + vertex 0.860304 1.19229 2.58227 + vertex 0.858083 1.19084 2.58037 + endloop + endfacet + facet normal -0.637673 -0.0358944 0.76947 + outer loop + vertex 0.858083 1.19084 2.58037 + vertex 0.860304 1.19229 2.58227 + vertex 0.857888 1.19372 2.58034 + endloop + endfacet + facet normal -0.615035 -0.0907976 0.783255 + outer loop + vertex 0.862833 1.18755 2.58371 + vertex 0.863219 1.1922 2.58455 + vertex 0.860304 1.19229 2.58227 + endloop + endfacet + facet normal -0.603191 -0.0933817 0.792112 + outer loop + vertex 0.863219 1.1922 2.58455 + vertex 0.862833 1.18755 2.58371 + vertex 0.865997 1.18949 2.58635 + endloop + endfacet + facet normal -0.58729 -0.0675069 0.806557 + outer loop + vertex 0.865483 1.19454 2.5864 + vertex 0.863219 1.1922 2.58455 + vertex 0.865997 1.18949 2.58635 + endloop + endfacet + facet normal -0.592029 -0.0679551 0.803047 + outer loop + vertex 0.865997 1.18949 2.58635 + vertex 0.868713 1.19192 2.58856 + vertex 0.865483 1.19454 2.5864 + endloop + endfacet + facet normal -0.568135 -0.106443 0.816023 + outer loop + vertex 0.869656 1.18648 2.5885 + vertex 0.868713 1.19192 2.58856 + vertex 0.865997 1.18949 2.58635 + endloop + endfacet + facet normal -0.580601 -0.13043 0.803673 + outer loop + vertex 0.866553 1.1845 2.58594 + vertex 0.869656 1.18648 2.5885 + vertex 0.865997 1.18949 2.58635 + endloop + endfacet + facet normal -0.586345 -0.130724 0.799444 + outer loop + vertex 0.865997 1.18949 2.58635 + vertex 0.862833 1.18755 2.58371 + vertex 0.866553 1.1845 2.58594 + endloop + endfacet + facet normal -0.599392 -0.157396 0.784829 + outer loop + vertex 0.862833 1.18755 2.58371 + vertex 0.864169 1.18149 2.58351 + vertex 0.866553 1.1845 2.58594 + endloop + endfacet + facet normal -0.581767 -0.178352 0.79356 + outer loop + vertex 0.867379 1.18051 2.58565 + vertex 0.866553 1.1845 2.58594 + vertex 0.864169 1.18149 2.58351 + endloop + endfacet + facet normal -0.584129 -0.202962 0.785875 + outer loop + vertex 0.867379 1.18051 2.58565 + vertex 0.864169 1.18149 2.58351 + vertex 0.867155 1.17668 2.58449 + endloop + endfacet + facet normal -0.565021 -0.207872 0.798461 + outer loop + vertex 0.867155 1.17668 2.58449 + vertex 0.869525 1.17819 2.58656 + vertex 0.867379 1.18051 2.58565 + endloop + endfacet + facet normal -0.558434 -0.199103 0.805301 + outer loop + vertex 0.869525 1.17819 2.58656 + vertex 0.869689 1.18162 2.58752 + vertex 0.867379 1.18051 2.58565 + endloop + endfacet + facet normal -0.549359 -0.201136 0.811017 + outer loop + vertex 0.869525 1.17819 2.58656 + vertex 0.872773 1.17759 2.58861 + vertex 0.869689 1.18162 2.58752 + endloop + endfacet + facet normal -0.549137 -0.20091 0.811223 + outer loop + vertex 0.872773 1.17759 2.58861 + vertex 0.872528 1.18245 2.58965 + vertex 0.869689 1.18162 2.58752 + endloop + endfacet + facet normal -0.559447 -0.167187 0.81183 + outer loop + vertex 0.872528 1.18245 2.58965 + vertex 0.869656 1.18648 2.5885 + vertex 0.869689 1.18162 2.58752 + endloop + endfacet + facet normal -0.567596 -0.175101 0.804471 + outer loop + vertex 0.872778 1.1859 2.59058 + vertex 0.869656 1.18648 2.5885 + vertex 0.872528 1.18245 2.58965 + endloop + endfacet + facet normal -0.543301 -0.180983 0.819798 + outer loop + vertex 0.872528 1.18245 2.58965 + vertex 0.874927 1.18353 2.59148 + vertex 0.872778 1.1859 2.59058 + endloop + endfacet + facet normal -0.528411 -0.162337 0.833324 + outer loop + vertex 0.874927 1.18353 2.59148 + vertex 0.875343 1.18746 2.59251 + vertex 0.872778 1.1859 2.59058 + endloop + endfacet + facet normal -0.547565 -0.123817 0.827551 + outer loop + vertex 0.872778 1.1859 2.59058 + vertex 0.875343 1.18746 2.59251 + vertex 0.871896 1.18969 2.59056 + endloop + endfacet + facet normal -0.542567 -0.111739 0.832548 + outer loop + vertex 0.875343 1.18746 2.59251 + vertex 0.874063 1.19209 2.5923 + vertex 0.871896 1.18969 2.59056 + endloop + endfacet + facet normal -0.573006 -0.0725416 0.816334 + outer loop + vertex 0.871896 1.18969 2.59056 + vertex 0.874063 1.19209 2.5923 + vertex 0.871432 1.19455 2.59067 + endloop + endfacet + facet normal -0.567593 -0.0721084 0.820145 + outer loop + vertex 0.871432 1.19455 2.59067 + vertex 0.868713 1.19192 2.58856 + vertex 0.871896 1.18969 2.59056 + endloop + endfacet + facet normal -0.518351 -0.164916 0.839115 + outer loop + vertex 0.874927 1.18353 2.59148 + vertex 0.878617 1.18222 2.5935 + vertex 0.875343 1.18746 2.59251 + endloop + endfacet + facet normal -0.536279 -0.17879 0.824888 + outer loop + vertex 0.878617 1.18222 2.5935 + vertex 0.878563 1.18715 2.59453 + vertex 0.875343 1.18746 2.59251 + endloop + endfacet + facet normal -0.536941 -0.127591 0.833916 + outer loop + vertex 0.878563 1.18715 2.59453 + vertex 0.877227 1.19174 2.59438 + vertex 0.875343 1.18746 2.59251 + endloop + endfacet + facet normal -0.554652 -0.115468 0.824032 + outer loop + vertex 0.875343 1.18746 2.59251 + vertex 0.877227 1.19174 2.59438 + vertex 0.874063 1.19209 2.5923 + endloop + endfacet + facet normal -0.544694 -0.130032 0.828492 + outer loop + vertex 0.877227 1.19174 2.59438 + vertex 0.878563 1.18715 2.59453 + vertex 0.880603 1.18939 2.59623 + endloop + endfacet + facet normal -0.539765 -0.119113 0.833346 + outer loop + vertex 0.879883 1.19323 2.59631 + vertex 0.877227 1.19174 2.59438 + vertex 0.880603 1.18939 2.59623 + endloop + endfacet + facet normal -0.518774 -0.115476 0.847076 + outer loop + vertex 0.880603 1.18939 2.59623 + vertex 0.883578 1.1921 2.59842 + vertex 0.879883 1.19323 2.59631 + endloop + endfacet + facet normal -0.508341 -0.0588265 0.859144 + outer loop + vertex 0.879883 1.19323 2.59631 + vertex 0.883578 1.1921 2.59842 + vertex 0.880619 1.19719 2.59702 + endloop + endfacet + facet normal -0.533676 -0.0514247 0.844124 + outer loop + vertex 0.879883 1.19323 2.59631 + vertex 0.880619 1.19719 2.59702 + vertex 0.878 1.19562 2.59527 + endloop + endfacet + facet normal -0.545166 -0.0253532 0.837944 + outer loop + vertex 0.878 1.19562 2.59527 + vertex 0.880619 1.19719 2.59702 + vertex 0.877853 1.19868 2.59526 + endloop + endfacet + facet normal -0.53735 -0.0811504 0.839446 + outer loop + vertex 0.883578 1.1921 2.59842 + vertex 0.883824 1.19725 2.59907 + vertex 0.880619 1.19719 2.59702 + endloop + endfacet + facet normal -0.542247 -0.0805222 0.836352 + outer loop + vertex 0.883824 1.19725 2.59907 + vertex 0.883578 1.1921 2.59842 + vertex 0.886628 1.19492 2.60067 + endloop + endfacet + facet normal -0.529759 -0.0588562 0.846103 + outer loop + vertex 0.886264 1.19974 2.60078 + vertex 0.883824 1.19725 2.59907 + vertex 0.886628 1.19492 2.60067 + endloop + endfacet + facet normal -0.540939 -0.0595391 0.838952 + outer loop + vertex 0.886628 1.19492 2.60067 + vertex 0.88899 1.19719 2.60235 + vertex 0.886264 1.19974 2.60078 + endloop + endfacet + facet normal -0.507725 -0.105911 0.854984 + outer loop + vertex 0.890267 1.19249 2.60253 + vertex 0.88899 1.19719 2.60235 + vertex 0.886628 1.19492 2.60067 + endloop + endfacet + facet normal -0.510839 -0.112674 0.852261 + outer loop + vertex 0.88736 1.19091 2.60058 + vertex 0.890267 1.19249 2.60253 + vertex 0.886628 1.19492 2.60067 + endloop + endfacet + facet normal -0.49264 -0.15184 0.856884 + outer loop + vertex 0.889762 1.18835 2.6015 + vertex 0.890267 1.19249 2.60253 + vertex 0.88736 1.19091 2.60058 + endloop + endfacet + facet normal -0.502464 -0.163951 0.848911 + outer loop + vertex 0.886936 1.18679 2.59953 + vertex 0.889762 1.18835 2.6015 + vertex 0.88736 1.19091 2.60058 + endloop + endfacet + facet normal -0.526432 -0.158048 0.835398 + outer loop + vertex 0.88736 1.19091 2.60058 + vertex 0.883578 1.1921 2.59842 + vertex 0.886936 1.18679 2.59953 + endloop + endfacet + facet normal -0.500221 -0.137401 0.854927 + outer loop + vertex 0.886936 1.18679 2.59953 + vertex 0.883578 1.1921 2.59842 + vertex 0.883496 1.18714 2.59757 + endloop + endfacet + facet normal -0.50006 -0.179843 0.847111 + outer loop + vertex 0.885219 1.18249 2.5976 + vertex 0.886936 1.18679 2.59953 + vertex 0.883496 1.18714 2.59757 + endloop + endfacet + facet normal -0.49611 -0.18223 0.848921 + outer loop + vertex 0.888668 1.18215 2.59955 + vertex 0.886936 1.18679 2.59953 + vertex 0.885219 1.18249 2.5976 + endloop + endfacet + facet normal -0.496006 -0.18769 0.847792 + outer loop + vertex 0.888749 1.17718 2.59849 + vertex 0.888668 1.18215 2.59955 + vertex 0.885219 1.18249 2.5976 + endloop + endfacet + facet normal -0.500606 -0.191339 0.844265 + outer loop + vertex 0.88488 1.17837 2.59647 + vertex 0.888749 1.17718 2.59849 + vertex 0.885219 1.18249 2.5976 + endloop + endfacet + facet normal -0.505746 -0.190144 0.841467 + outer loop + vertex 0.88488 1.17837 2.59647 + vertex 0.885219 1.18249 2.5976 + vertex 0.882446 1.18096 2.59559 + endloop + endfacet + facet normal -0.50971 -0.195081 0.837937 + outer loop + vertex 0.882112 1.17686 2.59443 + vertex 0.88488 1.17837 2.59647 + vertex 0.882446 1.18096 2.59559 + endloop + endfacet + facet normal -0.511995 -0.190459 0.837608 + outer loop + vertex 0.88488 1.17837 2.59647 + vertex 0.882112 1.17686 2.59443 + vertex 0.88585 1.17446 2.59617 + endloop + endfacet + facet normal -0.511288 -0.188771 0.838421 + outer loop + vertex 0.882112 1.17686 2.59443 + vertex 0.883802 1.17224 2.59442 + vertex 0.88585 1.17446 2.59617 + endloop + endfacet + facet normal -0.512078 -0.187829 0.838151 + outer loop + vertex 0.88585 1.17446 2.59617 + vertex 0.883802 1.17224 2.59442 + vertex 0.886733 1.16998 2.59571 + endloop + endfacet + facet normal -0.504025 -0.186769 0.843253 + outer loop + vertex 0.886733 1.16998 2.59571 + vertex 0.888804 1.17222 2.59744 + vertex 0.88585 1.17446 2.59617 + endloop + endfacet + facet normal -0.502844 -0.184524 0.844452 + outer loop + vertex 0.888804 1.17222 2.59744 + vertex 0.888749 1.17718 2.59849 + vertex 0.88585 1.17446 2.59617 + endloop + endfacet + facet normal -0.493487 -0.18554 0.849733 + outer loop + vertex 0.892193 1.17196 2.59935 + vertex 0.888749 1.17718 2.59849 + vertex 0.888804 1.17222 2.59744 + endloop + endfacet + facet normal -0.49348 -0.185746 0.849692 + outer loop + vertex 0.890468 1.16764 2.59741 + vertex 0.892193 1.17196 2.59935 + vertex 0.888804 1.17222 2.59744 + endloop + endfacet + facet normal -0.49091 -0.187291 0.85084 + outer loop + vertex 0.8939 1.16741 2.59934 + vertex 0.892193 1.17196 2.59935 + vertex 0.890468 1.16764 2.59741 + endloop + endfacet + facet normal -0.490798 -0.189858 0.850336 + outer loop + vertex 0.893945 1.16243 2.59825 + vertex 0.8939 1.16741 2.59934 + vertex 0.890468 1.16764 2.59741 + endloop + endfacet + facet normal -0.491235 -0.190202 0.850007 + outer loop + vertex 0.890046 1.16356 2.59625 + vertex 0.893945 1.16243 2.59825 + vertex 0.890468 1.16764 2.59741 + endloop + endfacet + facet normal -0.501129 -0.187697 0.844772 + outer loop + vertex 0.890046 1.16356 2.59625 + vertex 0.890468 1.16764 2.59741 + vertex 0.887656 1.1661 2.5954 + endloop + endfacet + facet normal -0.503681 -0.190852 0.842545 + outer loop + vertex 0.887246 1.16203 2.59423 + vertex 0.890046 1.16356 2.59625 + vertex 0.887656 1.1661 2.5954 + endloop + endfacet + facet normal -0.513836 -0.188231 0.836983 + outer loop + vertex 0.887656 1.1661 2.5954 + vertex 0.883844 1.16734 2.59334 + vertex 0.887246 1.16203 2.59423 + endloop + endfacet + facet normal -0.515481 -0.189504 0.835684 + outer loop + vertex 0.887246 1.16203 2.59423 + vertex 0.883844 1.16734 2.59334 + vertex 0.88385 1.1624 2.59222 + endloop + endfacet + facet normal -0.515458 -0.190621 0.835444 + outer loop + vertex 0.885594 1.1578 2.59225 + vertex 0.887246 1.16203 2.59423 + vertex 0.88385 1.1624 2.59222 + endloop + endfacet + facet normal -0.513083 -0.192076 0.836572 + outer loop + vertex 0.888941 1.15744 2.59422 + vertex 0.887246 1.16203 2.59423 + vertex 0.885594 1.1578 2.59225 + endloop + endfacet + facet normal -0.512969 -0.196994 0.835498 + outer loop + vertex 0.889196 1.15256 2.59322 + vertex 0.888941 1.15744 2.59422 + vertex 0.885594 1.1578 2.59225 + endloop + endfacet + facet normal -0.519061 -0.202114 0.830497 + outer loop + vertex 0.885422 1.15385 2.59118 + vertex 0.889196 1.15256 2.59322 + vertex 0.885594 1.1578 2.59225 + endloop + endfacet + facet normal -0.52972 -0.199962 0.824265 + outer loop + vertex 0.885422 1.15385 2.59118 + vertex 0.885594 1.1578 2.59225 + vertex 0.883099 1.15625 2.59027 + endloop + endfacet + facet normal -0.546498 -0.222526 0.807355 + outer loop + vertex 0.883136 1.15269 2.58931 + vertex 0.885422 1.15385 2.59118 + vertex 0.883099 1.15625 2.59027 + endloop + endfacet + facet normal -0.553175 -0.221452 0.803092 + outer loop + vertex 0.883099 1.15625 2.59027 + vertex 0.879844 1.15685 2.58819 + vertex 0.883136 1.15269 2.58931 + endloop + endfacet + facet normal -0.566269 -0.235347 0.789906 + outer loop + vertex 0.883136 1.15269 2.58931 + vertex 0.879844 1.15685 2.58819 + vertex 0.880357 1.15189 2.58708 + endloop + endfacet + facet normal -0.560587 -0.252057 0.788803 + outer loop + vertex 0.884026 1.14733 2.58823 + vertex 0.883136 1.15269 2.58931 + vertex 0.880357 1.15189 2.58708 + endloop + endfacet + facet normal -0.560053 -0.252046 0.789185 + outer loop + vertex 0.883136 1.15269 2.58931 + vertex 0.884026 1.14733 2.58823 + vertex 0.886482 1.14992 2.5908 + endloop + endfacet + facet normal -0.57127 -0.237823 0.785551 + outer loop + vertex 0.887605 1.14608 2.59045 + vertex 0.886482 1.14992 2.5908 + vertex 0.884026 1.14733 2.58823 + endloop + endfacet + facet normal -0.574221 -0.266832 0.773997 + outer loop + vertex 0.887605 1.14608 2.59045 + vertex 0.884026 1.14733 2.58823 + vertex 0.887825 1.14263 2.58943 + endloop + endfacet + facet normal -0.567183 -0.267821 0.778829 + outer loop + vertex 0.887825 1.14263 2.58943 + vertex 0.890046 1.14351 2.59135 + vertex 0.887605 1.14608 2.59045 + endloop + endfacet + facet normal -0.541379 -0.233212 0.807788 + outer loop + vertex 0.890046 1.14351 2.59135 + vertex 0.889937 1.14702 2.59229 + vertex 0.887605 1.14608 2.59045 + endloop + endfacet + facet normal -0.531126 -0.234602 0.814167 + outer loop + vertex 0.890046 1.14351 2.59135 + vertex 0.893786 1.14228 2.59344 + vertex 0.889937 1.14702 2.59229 + endloop + endfacet + facet normal -0.533611 -0.256058 0.806036 + outer loop + vertex 0.891312 1.13967 2.59097 + vertex 0.893786 1.14228 2.59344 + vertex 0.890046 1.14351 2.59135 + endloop + endfacet + facet normal -0.568449 -0.264844 0.778925 + outer loop + vertex 0.890046 1.14351 2.59135 + vertex 0.887825 1.14263 2.58943 + vertex 0.891312 1.13967 2.59097 + endloop + endfacet + facet normal -0.542155 -0.231325 0.80781 + outer loop + vertex 0.887605 1.14608 2.59045 + vertex 0.889937 1.14702 2.59229 + vertex 0.886482 1.14992 2.5908 + endloop + endfacet + facet normal -0.560499 -0.23565 0.793921 + outer loop + vertex 0.880357 1.15189 2.58708 + vertex 0.879844 1.15685 2.58819 + vertex 0.876995 1.15491 2.5856 + endloop + endfacet + facet normal -0.56171 -0.233556 0.793683 + outer loop + vertex 0.876995 1.15491 2.5856 + vertex 0.879844 1.15685 2.58819 + vertex 0.875817 1.15962 2.58616 + endloop + endfacet + facet normal -0.561332 -0.233495 0.793969 + outer loop + vertex 0.875817 1.15962 2.58616 + vertex 0.872982 1.15772 2.58359 + vertex 0.876995 1.15491 2.5856 + endloop + endfacet + facet normal -0.564178 -0.228487 0.793408 + outer loop + vertex 0.872446 1.16257 2.58461 + vertex 0.872982 1.15772 2.58359 + vertex 0.875817 1.15962 2.58616 + endloop + endfacet + facet normal -0.557682 -0.216976 0.801194 + outer loop + vertex 0.874731 1.16346 2.58644 + vertex 0.872446 1.16257 2.58461 + vertex 0.875817 1.15962 2.58616 + endloop + endfacet + facet normal -0.549103 -0.215025 0.80762 + outer loop + vertex 0.875817 1.15962 2.58616 + vertex 0.877955 1.1627 2.58843 + vertex 0.874731 1.16346 2.58644 + endloop + endfacet + facet normal -0.548411 -0.201972 0.811451 + outer loop + vertex 0.874731 1.16346 2.58644 + vertex 0.877955 1.1627 2.58843 + vertex 0.8749 1.16683 2.58739 + endloop + endfacet + facet normal -0.553323 -0.200859 0.808387 + outer loop + vertex 0.874731 1.16346 2.58644 + vertex 0.8749 1.16683 2.58739 + vertex 0.872562 1.16593 2.58557 + endloop + endfacet + facet normal -0.544725 -0.198393 0.81481 + outer loop + vertex 0.877955 1.1627 2.58843 + vertex 0.877759 1.16761 2.58949 + vertex 0.8749 1.16683 2.58739 + endloop + endfacet + facet normal -0.545035 -0.197374 0.81485 + outer loop + vertex 0.877759 1.16761 2.58949 + vertex 0.874657 1.17175 2.58842 + vertex 0.8749 1.16683 2.58739 + endloop + endfacet + facet normal -0.552631 -0.19671 0.809879 + outer loop + vertex 0.8749 1.16683 2.58739 + vertex 0.874657 1.17175 2.58842 + vertex 0.871769 1.16972 2.58596 + endloop + endfacet + facet normal -0.554033 -0.19897 0.808368 + outer loop + vertex 0.872562 1.16593 2.58557 + vertex 0.8749 1.16683 2.58739 + vertex 0.871769 1.16972 2.58596 + endloop + endfacet + facet normal -0.563735 -0.200271 0.801308 + outer loop + vertex 0.872562 1.16593 2.58557 + vertex 0.871769 1.16972 2.58596 + vertex 0.869035 1.1673 2.58343 + endloop + endfacet + facet normal -0.565111 -0.208691 0.798184 + outer loop + vertex 0.872562 1.16593 2.58557 + vertex 0.869035 1.1673 2.58343 + vertex 0.872446 1.16257 2.58461 + endloop + endfacet + facet normal -0.565745 -0.2093 0.797575 + outer loop + vertex 0.872446 1.16257 2.58461 + vertex 0.869035 1.1673 2.58343 + vertex 0.869631 1.16188 2.58243 + endloop + endfacet + facet normal -0.56143 -0.203664 0.802071 + outer loop + vertex 0.868833 1.17218 2.58453 + vertex 0.869035 1.1673 2.58343 + vertex 0.871769 1.16972 2.58596 + endloop + endfacet + facet normal -0.560991 -0.202838 0.802587 + outer loop + vertex 0.870762 1.17438 2.58643 + vertex 0.868833 1.17218 2.58453 + vertex 0.871769 1.16972 2.58596 + endloop + endfacet + facet normal -0.56092 -0.202923 0.802615 + outer loop + vertex 0.867155 1.17668 2.58449 + vertex 0.868833 1.17218 2.58453 + vertex 0.870762 1.17438 2.58643 + endloop + endfacet + facet normal -0.570867 -0.206693 0.7946 + outer loop + vertex 0.868833 1.17218 2.58453 + vertex 0.867155 1.17668 2.58449 + vertex 0.865637 1.17264 2.58235 + endloop + endfacet + facet normal -0.570953 -0.202601 0.795591 + outer loop + vertex 0.869035 1.1673 2.58343 + vertex 0.868833 1.17218 2.58453 + vertex 0.865637 1.17264 2.58235 + endloop + endfacet + facet normal -0.57133 -0.202912 0.795241 + outer loop + vertex 0.865411 1.16876 2.5812 + vertex 0.869035 1.1673 2.58343 + vertex 0.865637 1.17264 2.58235 + endloop + endfacet + facet normal -0.583588 -0.19978 0.787092 + outer loop + vertex 0.865411 1.16876 2.5812 + vertex 0.865637 1.17264 2.58235 + vertex 0.863246 1.17122 2.58022 + endloop + endfacet + facet normal -0.586757 -0.203943 0.783661 + outer loop + vertex 0.863171 1.16768 2.57924 + vertex 0.865411 1.16876 2.5812 + vertex 0.863246 1.17122 2.58022 + endloop + endfacet + facet normal -0.596627 -0.201823 0.776726 + outer loop + vertex 0.863246 1.17122 2.58022 + vertex 0.860202 1.17184 2.57804 + vertex 0.863171 1.16768 2.57924 + endloop + endfacet + facet normal -0.596647 -0.203661 0.776231 + outer loop + vertex 0.863246 1.17122 2.58022 + vertex 0.862138 1.17495 2.58035 + vertex 0.860202 1.17184 2.57804 + endloop + endfacet + facet normal -0.600017 -0.20029 0.774509 + outer loop + vertex 0.858807 1.17718 2.57834 + vertex 0.860202 1.17184 2.57804 + vertex 0.862138 1.17495 2.58035 + endloop + endfacet + facet normal -0.599919 -0.200012 0.774656 + outer loop + vertex 0.861152 1.17961 2.58078 + vertex 0.858807 1.17718 2.57834 + vertex 0.862138 1.17495 2.58035 + endloop + endfacet + facet normal -0.59187 -0.198917 0.781103 + outer loop + vertex 0.862138 1.17495 2.58035 + vertex 0.864016 1.1771 2.58231 + vertex 0.861152 1.17961 2.58078 + endloop + endfacet + facet normal -0.589189 -0.193864 0.784394 + outer loop + vertex 0.864016 1.1771 2.58231 + vertex 0.864169 1.18149 2.58351 + vertex 0.861152 1.17961 2.58078 + endloop + endfacet + facet normal -0.597749 -0.176598 0.78199 + outer loop + vertex 0.861152 1.17961 2.58078 + vertex 0.864169 1.18149 2.58351 + vertex 0.860434 1.1845 2.58134 + endloop + endfacet + facet normal -0.585767 -0.206638 0.783695 + outer loop + vertex 0.865637 1.17264 2.58235 + vertex 0.864016 1.1771 2.58231 + vertex 0.862138 1.17495 2.58035 + endloop + endfacet + facet normal -0.585232 -0.207488 0.78387 + outer loop + vertex 0.865411 1.16876 2.5812 + vertex 0.863171 1.16768 2.57924 + vertex 0.866352 1.16479 2.58085 + endloop + endfacet + facet normal -0.588544 -0.213409 0.77979 + outer loop + vertex 0.863171 1.16768 2.57924 + vertex 0.863848 1.16228 2.57827 + vertex 0.866352 1.16479 2.58085 + endloop + endfacet + facet normal -0.584977 -0.218322 0.781113 + outer loop + vertex 0.867399 1.16093 2.58055 + vertex 0.866352 1.16479 2.58085 + vertex 0.863848 1.16228 2.57827 + endloop + endfacet + facet normal -0.587959 -0.241338 0.772049 + outer loop + vertex 0.867399 1.16093 2.58055 + vertex 0.863848 1.16228 2.57827 + vertex 0.867623 1.15749 2.57965 + endloop + endfacet + facet normal -0.577157 -0.242659 0.779748 + outer loop + vertex 0.867623 1.15749 2.57965 + vertex 0.869756 1.15845 2.58153 + vertex 0.867399 1.16093 2.58055 + endloop + endfacet + facet normal -0.56718 -0.22868 0.791209 + outer loop + vertex 0.869756 1.15845 2.58153 + vertex 0.869631 1.16188 2.58243 + vertex 0.867399 1.16093 2.58055 + endloop + endfacet + facet normal -0.560877 -0.229562 0.795436 + outer loop + vertex 0.869756 1.15845 2.58153 + vertex 0.872982 1.15772 2.58359 + vertex 0.869631 1.16188 2.58243 + endloop + endfacet + facet normal -0.57915 -0.23164 0.781619 + outer loop + vertex 0.867623 1.15749 2.57965 + vertex 0.863848 1.16228 2.57827 + vertex 0.864847 1.15685 2.5774 + endloop + endfacet + facet normal -0.572551 -0.215716 0.790982 + outer loop + vertex 0.867399 1.16093 2.58055 + vertex 0.869631 1.16188 2.58243 + vertex 0.866352 1.16479 2.58085 + endloop + endfacet + facet normal -0.568898 -0.209236 0.795346 + outer loop + vertex 0.869631 1.16188 2.58243 + vertex 0.869035 1.1673 2.58343 + vertex 0.866352 1.16479 2.58085 + endloop + endfacet + facet normal -0.583424 -0.200112 0.787129 + outer loop + vertex 0.863246 1.17122 2.58022 + vertex 0.865637 1.17264 2.58235 + vertex 0.862138 1.17495 2.58035 + endloop + endfacet + facet normal -0.571721 -0.205207 0.794371 + outer loop + vertex 0.866352 1.16479 2.58085 + vertex 0.869035 1.1673 2.58343 + vertex 0.865411 1.16876 2.5812 + endloop + endfacet + facet normal -0.576235 -0.203108 0.791644 + outer loop + vertex 0.865637 1.17264 2.58235 + vertex 0.867155 1.17668 2.58449 + vertex 0.864016 1.1771 2.58231 + endloop + endfacet + facet normal -0.550005 -0.201273 0.810545 + outer loop + vertex 0.871769 1.16972 2.58596 + vertex 0.874657 1.17175 2.58842 + vertex 0.870762 1.17438 2.58643 + endloop + endfacet + facet normal -0.551312 -0.204479 0.808853 + outer loop + vertex 0.874657 1.17175 2.58842 + vertex 0.872773 1.17759 2.58861 + vertex 0.870762 1.17438 2.58643 + endloop + endfacet + facet normal -0.540444 -0.198817 0.817553 + outer loop + vertex 0.877759 1.16761 2.58949 + vertex 0.877955 1.1627 2.58843 + vertex 0.88089 1.16478 2.59088 + endloop + endfacet + facet normal -0.536456 -0.192383 0.821708 + outer loop + vertex 0.880187 1.16867 2.59133 + vertex 0.877759 1.16761 2.58949 + vertex 0.88089 1.16478 2.59088 + endloop + endfacet + facet normal -0.525183 -0.19122 0.829227 + outer loop + vertex 0.88089 1.16478 2.59088 + vertex 0.883844 1.16734 2.59334 + vertex 0.880187 1.16867 2.59133 + endloop + endfacet + facet normal -0.525288 -0.191811 0.829024 + outer loop + vertex 0.880187 1.16867 2.59133 + vertex 0.883844 1.16734 2.59334 + vertex 0.880479 1.17263 2.59243 + endloop + endfacet + facet normal -0.532539 -0.190095 0.824783 + outer loop + vertex 0.880187 1.16867 2.59133 + vertex 0.880479 1.17263 2.59243 + vertex 0.877964 1.17112 2.59046 + endloop + endfacet + facet normal -0.52191 -0.189192 0.831755 + outer loop + vertex 0.883844 1.16734 2.59334 + vertex 0.883802 1.17224 2.59442 + vertex 0.880479 1.17263 2.59243 + endloop + endfacet + facet normal -0.535751 -0.194098 0.821765 + outer loop + vertex 0.877759 1.16761 2.58949 + vertex 0.880187 1.16867 2.59133 + vertex 0.877964 1.17112 2.59046 + endloop + endfacet + facet normal -0.540603 -0.193011 0.818838 + outer loop + vertex 0.877964 1.17112 2.59046 + vertex 0.874657 1.17175 2.58842 + vertex 0.877759 1.16761 2.58949 + endloop + endfacet + facet normal -0.540754 -0.197873 0.817577 + outer loop + vertex 0.877964 1.17112 2.59046 + vertex 0.876712 1.175 2.59057 + vertex 0.874657 1.17175 2.58842 + endloop + endfacet + facet normal -0.537909 -0.200488 0.818815 + outer loop + vertex 0.872773 1.17759 2.58861 + vertex 0.874657 1.17175 2.58842 + vertex 0.876712 1.175 2.59057 + endloop + endfacet + facet normal -0.530157 -0.194672 0.825249 + outer loop + vertex 0.877964 1.17112 2.59046 + vertex 0.880479 1.17263 2.59243 + vertex 0.876712 1.175 2.59057 + endloop + endfacet + facet normal -0.531132 -0.197181 0.824026 + outer loop + vertex 0.880479 1.17263 2.59243 + vertex 0.878716 1.17726 2.5924 + vertex 0.876712 1.175 2.59057 + endloop + endfacet + facet normal -0.528166 -0.200666 0.82509 + outer loop + vertex 0.876712 1.175 2.59057 + vertex 0.878716 1.17726 2.5924 + vertex 0.875687 1.17967 2.59105 + endloop + endfacet + facet normal -0.53861 -0.202219 0.817928 + outer loop + vertex 0.875687 1.17967 2.59105 + vertex 0.872773 1.17759 2.58861 + vertex 0.876712 1.175 2.59057 + endloop + endfacet + facet normal -0.524933 -0.194627 0.828593 + outer loop + vertex 0.878716 1.17726 2.5924 + vertex 0.878617 1.18222 2.5935 + vertex 0.875687 1.17967 2.59105 + endloop + endfacet + facet normal -0.520829 -0.195094 0.831069 + outer loop + vertex 0.882112 1.17686 2.59443 + vertex 0.878617 1.18222 2.5935 + vertex 0.878716 1.17726 2.5924 + endloop + endfacet + facet normal -0.520858 -0.193232 0.831486 + outer loop + vertex 0.880479 1.17263 2.59243 + vertex 0.882112 1.17686 2.59443 + vertex 0.878716 1.17726 2.5924 + endloop + endfacet + facet normal -0.51824 -0.193039 0.833165 + outer loop + vertex 0.882446 1.18096 2.59559 + vertex 0.878617 1.18222 2.5935 + vertex 0.882112 1.17686 2.59443 + endloop + endfacet + facet normal -0.517956 -0.191172 0.833771 + outer loop + vertex 0.882446 1.18096 2.59559 + vertex 0.881443 1.18489 2.59587 + vertex 0.878617 1.18222 2.5935 + endloop + endfacet + facet normal -0.506429 -0.188775 0.841364 + outer loop + vertex 0.882446 1.18096 2.59559 + vertex 0.885219 1.18249 2.5976 + vertex 0.881443 1.18489 2.59587 + endloop + endfacet + facet normal -0.503169 -0.18101 0.845018 + outer loop + vertex 0.885219 1.18249 2.5976 + vertex 0.883496 1.18714 2.59757 + vertex 0.881443 1.18489 2.59587 + endloop + endfacet + facet normal -0.517904 -0.163493 0.83967 + outer loop + vertex 0.881443 1.18489 2.59587 + vertex 0.883496 1.18714 2.59757 + vertex 0.880603 1.18939 2.59623 + endloop + endfacet + facet normal -0.542089 -0.196007 0.817142 + outer loop + vertex 0.88089 1.16478 2.59088 + vertex 0.877955 1.1627 2.58843 + vertex 0.881831 1.16011 2.59038 + endloop + endfacet + facet normal -0.531109 -0.194595 0.824655 + outer loop + vertex 0.881831 1.16011 2.59038 + vertex 0.88385 1.1624 2.59222 + vertex 0.88089 1.16478 2.59088 + endloop + endfacet + facet normal -0.52981 -0.196123 0.825129 + outer loop + vertex 0.885594 1.1578 2.59225 + vertex 0.88385 1.1624 2.59222 + vertex 0.881831 1.16011 2.59038 + endloop + endfacet + facet normal -0.547758 -0.209947 0.809866 + outer loop + vertex 0.877955 1.1627 2.58843 + vertex 0.879844 1.15685 2.58819 + vertex 0.881831 1.16011 2.59038 + endloop + endfacet + facet normal -0.56049 -0.209704 0.801171 + outer loop + vertex 0.872446 1.16257 2.58461 + vertex 0.874731 1.16346 2.58644 + vertex 0.872562 1.16593 2.58557 + endloop + endfacet + facet normal -0.560027 -0.228635 0.796302 + outer loop + vertex 0.872982 1.15772 2.58359 + vertex 0.872446 1.16257 2.58461 + vertex 0.869631 1.16188 2.58243 + endloop + endfacet + facet normal -0.552724 -0.211395 0.806107 + outer loop + vertex 0.879844 1.15685 2.58819 + vertex 0.877955 1.1627 2.58843 + vertex 0.875817 1.15962 2.58616 + endloop + endfacet + facet normal -0.553018 -0.205164 0.807514 + outer loop + vertex 0.883099 1.15625 2.59027 + vertex 0.881831 1.16011 2.59038 + vertex 0.879844 1.15685 2.58819 + endloop + endfacet + facet normal -0.545518 -0.224597 0.807444 + outer loop + vertex 0.885422 1.15385 2.59118 + vertex 0.883136 1.15269 2.58931 + vertex 0.886482 1.14992 2.5908 + endloop + endfacet + facet normal -0.530621 -0.198281 0.824091 + outer loop + vertex 0.883099 1.15625 2.59027 + vertex 0.885594 1.1578 2.59225 + vertex 0.881831 1.16011 2.59038 + endloop + endfacet + facet normal -0.521737 -0.219788 0.824308 + outer loop + vertex 0.886482 1.14992 2.5908 + vertex 0.889196 1.15256 2.59322 + vertex 0.885422 1.15385 2.59118 + endloop + endfacet + facet normal -0.503802 -0.197618 0.84091 + outer loop + vertex 0.888941 1.15744 2.59422 + vertex 0.889196 1.15256 2.59322 + vertex 0.891896 1.15523 2.59547 + endloop + endfacet + facet normal -0.500251 -0.190812 0.844594 + outer loop + vertex 0.890982 1.15968 2.59593 + vertex 0.888941 1.15744 2.59422 + vertex 0.891896 1.15523 2.59547 + endloop + endfacet + facet normal -0.491516 -0.18958 0.849983 + outer loop + vertex 0.891896 1.15523 2.59547 + vertex 0.893958 1.15745 2.59716 + vertex 0.890982 1.15968 2.59593 + endloop + endfacet + facet normal -0.490988 -0.188583 0.85051 + outer loop + vertex 0.893958 1.15745 2.59716 + vertex 0.893945 1.16243 2.59825 + vertex 0.890982 1.15968 2.59593 + endloop + endfacet + facet normal -0.479141 -0.189966 0.856935 + outer loop + vertex 0.89747 1.15713 2.59905 + vertex 0.893945 1.16243 2.59825 + vertex 0.893958 1.15745 2.59716 + endloop + endfacet + facet normal -0.479165 -0.188793 0.85718 + outer loop + vertex 0.895584 1.15287 2.59706 + vertex 0.89747 1.15713 2.59905 + vertex 0.893958 1.15745 2.59716 + endloop + endfacet + facet normal -0.472756 -0.192868 0.859828 + outer loop + vertex 0.899607 1.15186 2.59904 + vertex 0.89747 1.15713 2.59905 + vertex 0.895584 1.15287 2.59706 + endloop + endfacet + facet normal -0.472355 -0.189248 0.860852 + outer loop + vertex 0.89821 1.14807 2.59744 + vertex 0.899607 1.15186 2.59904 + vertex 0.895584 1.15287 2.59706 + endloop + endfacet + facet normal -0.476871 -0.191968 0.857754 + outer loop + vertex 0.895156 1.14904 2.59596 + vertex 0.89821 1.14807 2.59744 + vertex 0.895584 1.15287 2.59706 + endloop + endfacet + facet normal -0.487826 -0.189155 0.852201 + outer loop + vertex 0.895156 1.14904 2.59596 + vertex 0.895584 1.15287 2.59706 + vertex 0.892905 1.15148 2.59521 + endloop + endfacet + facet normal -0.497528 -0.200658 0.843921 + outer loop + vertex 0.892846 1.14787 2.59432 + vertex 0.895156 1.14904 2.59596 + vertex 0.892905 1.15148 2.59521 + endloop + endfacet + facet normal -0.507824 -0.199062 0.838146 + outer loop + vertex 0.892905 1.15148 2.59521 + vertex 0.889196 1.15256 2.59322 + vertex 0.892846 1.14787 2.59432 + endloop + endfacet + facet normal -0.518024 -0.209051 0.829427 + outer loop + vertex 0.892846 1.14787 2.59432 + vertex 0.889196 1.15256 2.59322 + vertex 0.889937 1.14702 2.59229 + endloop + endfacet + facet normal -0.515082 -0.217953 0.828967 + outer loop + vertex 0.893786 1.14228 2.59344 + vertex 0.892846 1.14787 2.59432 + vertex 0.889937 1.14702 2.59229 + endloop + endfacet + facet normal -0.504162 -0.217205 0.835849 + outer loop + vertex 0.892846 1.14787 2.59432 + vertex 0.893786 1.14228 2.59344 + vertex 0.896304 1.14514 2.5957 + endloop + endfacet + facet normal -0.511301 -0.209118 0.833571 + outer loop + vertex 0.89759 1.14123 2.5955 + vertex 0.896304 1.14514 2.5957 + vertex 0.893786 1.14228 2.59344 + endloop + endfacet + facet normal -0.511952 -0.215428 0.831562 + outer loop + vertex 0.89759 1.14123 2.5955 + vertex 0.893786 1.14228 2.59344 + vertex 0.897654 1.13759 2.5946 + endloop + endfacet + facet normal -0.529284 -0.233656 0.815637 + outer loop + vertex 0.897654 1.13759 2.5946 + vertex 0.893786 1.14228 2.59344 + vertex 0.894817 1.13673 2.59251 + endloop + endfacet + facet normal -0.528088 -0.237082 0.815423 + outer loop + vertex 0.898708 1.1321 2.59369 + vertex 0.897654 1.13759 2.5946 + vertex 0.894817 1.13673 2.59251 + endloop + endfacet + facet normal -0.504458 -0.235105 0.830812 + outer loop + vertex 0.897654 1.13759 2.5946 + vertex 0.898708 1.1321 2.59369 + vertex 0.901145 1.13492 2.59597 + endloop + endfacet + facet normal -0.495935 -0.219106 0.840262 + outer loop + vertex 0.89994 1.13879 2.59626 + vertex 0.897654 1.13759 2.5946 + vertex 0.901145 1.13492 2.59597 + endloop + endfacet + facet normal -0.464845 -0.210918 0.859903 + outer loop + vertex 0.901145 1.13492 2.59597 + vertex 0.90302 1.13787 2.5977 + vertex 0.89994 1.13879 2.59626 + endloop + endfacet + facet normal -0.4632 -0.199884 0.863419 + outer loop + vertex 0.89994 1.13879 2.59626 + vertex 0.90302 1.13787 2.5977 + vertex 0.900271 1.14276 2.59736 + endloop + endfacet + facet normal -0.479748 -0.196228 0.855182 + outer loop + vertex 0.89994 1.13879 2.59626 + vertex 0.900271 1.14276 2.59736 + vertex 0.89759 1.14123 2.5955 + endloop + endfacet + facet normal -0.453265 -0.193836 0.870045 + outer loop + vertex 0.90302 1.13787 2.5977 + vertex 0.904453 1.14168 2.5993 + vertex 0.900271 1.14276 2.59736 + endloop + endfacet + facet normal -0.453614 -0.196634 0.869235 + outer loop + vertex 0.904453 1.14168 2.5993 + vertex 0.902353 1.147 2.59941 + vertex 0.900271 1.14276 2.59736 + endloop + endfacet + facet normal -0.460483 -0.192014 0.866652 + outer loop + vertex 0.900271 1.14276 2.59736 + vertex 0.902353 1.147 2.59941 + vertex 0.89821 1.14807 2.59744 + endloop + endfacet + facet normal -0.434542 -0.189333 0.880526 + outer loop + vertex 0.902353 1.147 2.59941 + vertex 0.904453 1.14168 2.5993 + vertex 0.906292 1.14489 2.60089 + endloop + endfacet + facet normal -0.43792 -0.198191 0.876896 + outer loop + vertex 0.904955 1.14881 2.60111 + vertex 0.902353 1.147 2.59941 + vertex 0.906292 1.14489 2.60089 + endloop + endfacet + facet normal -0.413485 -0.190603 0.890337 + outer loop + vertex 0.906292 1.14489 2.60089 + vertex 0.908146 1.14813 2.60245 + vertex 0.904955 1.14881 2.60111 + endloop + endfacet + facet normal -0.413596 -0.191696 0.890051 + outer loop + vertex 0.904955 1.14881 2.60111 + vertex 0.908146 1.14813 2.60245 + vertex 0.905345 1.15295 2.60219 + endloop + endfacet + facet normal -0.432264 -0.18784 0.881966 + outer loop + vertex 0.904955 1.14881 2.60111 + vertex 0.905345 1.15295 2.60219 + vertex 0.902709 1.15113 2.60051 + endloop + endfacet + facet normal -0.433545 -0.185803 0.881769 + outer loop + vertex 0.902709 1.15113 2.60051 + vertex 0.905345 1.15295 2.60219 + vertex 0.901391 1.15504 2.60068 + endloop + endfacet + facet normal -0.456067 -0.192816 0.868807 + outer loop + vertex 0.902709 1.15113 2.60051 + vertex 0.901391 1.15504 2.60068 + vertex 0.899607 1.15186 2.59904 + endloop + endfacet + facet normal -0.456033 -0.192493 0.868896 + outer loop + vertex 0.902709 1.15113 2.60051 + vertex 0.899607 1.15186 2.59904 + vertex 0.902353 1.147 2.59941 + endloop + endfacet + facet normal -0.437233 -0.195643 0.87781 + outer loop + vertex 0.905345 1.15295 2.60219 + vertex 0.903302 1.15818 2.60233 + vertex 0.901391 1.15504 2.60068 + endloop + endfacet + facet normal -0.444192 -0.190198 0.87551 + outer loop + vertex 0.901391 1.15504 2.60068 + vertex 0.903302 1.15818 2.60233 + vertex 0.900123 1.15893 2.60088 + endloop + endfacet + facet normal -0.464682 -0.196258 0.863455 + outer loop + vertex 0.900123 1.15893 2.60088 + vertex 0.89747 1.15713 2.59905 + vertex 0.901391 1.15504 2.60068 + endloop + endfacet + facet normal -0.46662 -0.193062 0.86313 + outer loop + vertex 0.89747 1.15713 2.59905 + vertex 0.900123 1.15893 2.60088 + vertex 0.897839 1.16134 2.60019 + endloop + endfacet + facet normal -0.460261 -0.185602 0.868166 + outer loop + vertex 0.900123 1.15893 2.60088 + vertex 0.900809 1.16292 2.6021 + vertex 0.897839 1.16134 2.60019 + endloop + endfacet + facet normal -0.459486 -0.187157 0.868242 + outer loop + vertex 0.897839 1.16134 2.60019 + vertex 0.900809 1.16292 2.6021 + vertex 0.896968 1.16533 2.60059 + endloop + endfacet + facet normal -0.479463 -0.190362 0.856666 + outer loop + vertex 0.897839 1.16134 2.60019 + vertex 0.896968 1.16533 2.60059 + vertex 0.893945 1.16243 2.59825 + endloop + endfacet + facet normal -0.460372 -0.189127 0.867346 + outer loop + vertex 0.900809 1.16292 2.6021 + vertex 0.899448 1.16821 2.60253 + vertex 0.896968 1.16533 2.60059 + endloop + endfacet + facet normal -0.463557 -0.185733 0.866382 + outer loop + vertex 0.896968 1.16533 2.60059 + vertex 0.899448 1.16821 2.60253 + vertex 0.895883 1.16986 2.60098 + endloop + endfacet + facet normal -0.477478 -0.188362 0.858216 + outer loop + vertex 0.895883 1.16986 2.60098 + vertex 0.8939 1.16741 2.59934 + vertex 0.896968 1.16533 2.60059 + endloop + endfacet + facet normal -0.463213 -0.184585 0.866812 + outer loop + vertex 0.899448 1.16821 2.60253 + vertex 0.897837 1.17292 2.60267 + vertex 0.895883 1.16986 2.60098 + endloop + endfacet + facet normal -0.467284 -0.181167 0.865346 + outer loop + vertex 0.895883 1.16986 2.60098 + vertex 0.897837 1.17292 2.60267 + vertex 0.894813 1.17362 2.60119 + endloop + endfacet + facet normal -0.482187 -0.184905 0.856333 + outer loop + vertex 0.894813 1.17362 2.60119 + vertex 0.892193 1.17196 2.59935 + vertex 0.895883 1.16986 2.60098 + endloop + endfacet + facet normal -0.482894 -0.183651 0.856204 + outer loop + vertex 0.892193 1.17196 2.59935 + vertex 0.894813 1.17362 2.60119 + vertex 0.892594 1.17602 2.60045 + endloop + endfacet + facet normal -0.477711 -0.177568 0.860385 + outer loop + vertex 0.894813 1.17362 2.60119 + vertex 0.895388 1.17757 2.60232 + vertex 0.892594 1.17602 2.60045 + endloop + endfacet + facet normal -0.475451 -0.18203 0.860704 + outer loop + vertex 0.892594 1.17602 2.60045 + vertex 0.895388 1.17757 2.60232 + vertex 0.891676 1.17991 2.60077 + endloop + endfacet + facet normal -0.489534 -0.18466 0.852207 + outer loop + vertex 0.892594 1.17602 2.60045 + vertex 0.891676 1.17991 2.60077 + vertex 0.888749 1.17718 2.59849 + endloop + endfacet + facet normal -0.477203 -0.186013 0.858881 + outer loop + vertex 0.895388 1.17757 2.60232 + vertex 0.893791 1.18219 2.60244 + vertex 0.891676 1.17991 2.60077 + endloop + endfacet + facet normal -0.476959 -0.186293 0.858955 + outer loop + vertex 0.891676 1.17991 2.60077 + vertex 0.893791 1.18219 2.60244 + vertex 0.890751 1.18443 2.60123 + endloop + endfacet + facet normal -0.485912 -0.18758 0.853641 + outer loop + vertex 0.890751 1.18443 2.60123 + vertex 0.888668 1.18215 2.59955 + vertex 0.891676 1.17991 2.60077 + endloop + endfacet + facet normal -0.475531 -0.183616 0.860323 + outer loop + vertex 0.893791 1.18219 2.60244 + vertex 0.893727 1.18723 2.60347 + vertex 0.890751 1.18443 2.60123 + endloop + endfacet + facet normal -0.478243 -0.180115 0.859559 + outer loop + vertex 0.890751 1.18443 2.60123 + vertex 0.893727 1.18723 2.60347 + vertex 0.889762 1.18835 2.6015 + endloop + endfacet + facet normal -0.467222 -0.180567 0.865505 + outer loop + vertex 0.894813 1.17362 2.60119 + vertex 0.897837 1.17292 2.60267 + vertex 0.895388 1.17757 2.60232 + endloop + endfacet + facet normal -0.459246 -0.175973 0.870705 + outer loop + vertex 0.897837 1.17292 2.60267 + vertex 0.899424 1.17663 2.60426 + vertex 0.895388 1.17757 2.60232 + endloop + endfacet + facet normal -0.448104 -0.182628 0.875128 + outer loop + vertex 0.901872 1.17191 2.60453 + vertex 0.899424 1.17663 2.60426 + vertex 0.897837 1.17292 2.60267 + endloop + endfacet + facet normal -0.438841 -0.1775 0.880859 + outer loop + vertex 0.902546 1.17592 2.60567 + vertex 0.899424 1.17663 2.60426 + vertex 0.901872 1.17191 2.60453 + endloop + endfacet + facet normal -0.422158 -0.182334 0.887996 + outer loop + vertex 0.901872 1.17191 2.60453 + vertex 0.904673 1.17366 2.60622 + vertex 0.902546 1.17592 2.60567 + endloop + endfacet + facet normal -0.411698 -0.170759 0.89518 + outer loop + vertex 0.904673 1.17366 2.60622 + vertex 0.905255 1.17782 2.60728 + vertex 0.902546 1.17592 2.60567 + endloop + endfacet + facet normal -0.412476 -0.169537 0.895054 + outer loop + vertex 0.902546 1.17592 2.60567 + vertex 0.905255 1.17782 2.60728 + vertex 0.901344 1.17982 2.60586 + endloop + endfacet + facet normal -0.416759 -0.180905 0.890834 + outer loop + vertex 0.905255 1.17782 2.60728 + vertex 0.903293 1.18305 2.60742 + vertex 0.901344 1.17982 2.60586 + endloop + endfacet + facet normal -0.41984 -0.178572 0.889858 + outer loop + vertex 0.901344 1.17982 2.60586 + vertex 0.903293 1.18305 2.60742 + vertex 0.900079 1.18373 2.60605 + endloop + endfacet + facet normal -0.444267 -0.185816 0.876413 + outer loop + vertex 0.900079 1.18373 2.60605 + vertex 0.897361 1.18189 2.60428 + vertex 0.901344 1.17982 2.60586 + endloop + endfacet + facet normal -0.440551 -0.175627 0.880381 + outer loop + vertex 0.897361 1.18189 2.60428 + vertex 0.899424 1.17663 2.60426 + vertex 0.901344 1.17982 2.60586 + endloop + endfacet + facet normal -0.44237 -0.188897 0.876714 + outer loop + vertex 0.897361 1.18189 2.60428 + vertex 0.900079 1.18373 2.60605 + vertex 0.897706 1.18615 2.60537 + endloop + endfacet + facet normal -0.462857 -0.184743 0.866968 + outer loop + vertex 0.897706 1.18615 2.60537 + vertex 0.893727 1.18723 2.60347 + vertex 0.897361 1.18189 2.60428 + endloop + endfacet + facet normal -0.462947 -0.184813 0.866905 + outer loop + vertex 0.897361 1.18189 2.60428 + vertex 0.893727 1.18723 2.60347 + vertex 0.893791 1.18219 2.60244 + endloop + endfacet + facet normal -0.463008 -0.181328 0.867608 + outer loop + vertex 0.895388 1.17757 2.60232 + vertex 0.897361 1.18189 2.60428 + vertex 0.893791 1.18219 2.60244 + endloop + endfacet + facet normal -0.46002 -0.183232 0.868797 + outer loop + vertex 0.899424 1.17663 2.60426 + vertex 0.897361 1.18189 2.60428 + vertex 0.895388 1.17757 2.60232 + endloop + endfacet + facet normal -0.463152 -0.186963 0.866334 + outer loop + vertex 0.897706 1.18615 2.60537 + vertex 0.896745 1.1902 2.60573 + vertex 0.893727 1.18723 2.60347 + endloop + endfacet + facet normal -0.472072 -0.176012 0.86381 + outer loop + vertex 0.893666 1.19227 2.60447 + vertex 0.893727 1.18723 2.60347 + vertex 0.896745 1.1902 2.60573 + endloop + endfacet + facet normal -0.465983 -0.163394 0.869576 + outer loop + vertex 0.895672 1.19479 2.60602 + vertex 0.893666 1.19227 2.60447 + vertex 0.896745 1.1902 2.60573 + endloop + endfacet + facet normal -0.44817 -0.159848 0.879541 + outer loop + vertex 0.896745 1.1902 2.60573 + vertex 0.899272 1.1932 2.60756 + vertex 0.895672 1.19479 2.60602 + endloop + endfacet + facet normal -0.438253 -0.127355 0.889784 + outer loop + vertex 0.899272 1.1932 2.60756 + vertex 0.897789 1.19801 2.60752 + vertex 0.895672 1.19479 2.60602 + endloop + endfacet + facet normal -0.456014 -0.112458 0.882839 + outer loop + vertex 0.895672 1.19479 2.60602 + vertex 0.897789 1.19801 2.60752 + vertex 0.894785 1.19851 2.60603 + endloop + endfacet + facet normal -0.498103 -0.122396 0.858436 + outer loop + vertex 0.894785 1.19851 2.60603 + vertex 0.892248 1.19683 2.60432 + vertex 0.895672 1.19479 2.60602 + endloop + endfacet + facet normal -0.519627 -0.0816303 0.850484 + outer loop + vertex 0.892248 1.19683 2.60432 + vertex 0.894785 1.19851 2.60603 + vertex 0.893016 1.20071 2.60516 + endloop + endfacet + facet normal -0.486069 -0.0459246 0.872713 + outer loop + vertex 0.894785 1.19851 2.60603 + vertex 0.895645 1.20239 2.60672 + vertex 0.893016 1.20071 2.60516 + endloop + endfacet + facet normal -0.494437 -0.0291229 0.868725 + outer loop + vertex 0.893016 1.20071 2.60516 + vertex 0.895645 1.20239 2.60672 + vertex 0.892867 1.20375 2.60518 + endloop + endfacet + facet normal -0.450781 -0.0569353 0.890817 + outer loop + vertex 0.894785 1.19851 2.60603 + vertex 0.897789 1.19801 2.60752 + vertex 0.895645 1.20239 2.60672 + endloop + endfacet + facet normal -0.451299 -0.0572409 0.890535 + outer loop + vertex 0.897789 1.19801 2.60752 + vertex 0.899942 1.20243 2.6089 + vertex 0.895645 1.20239 2.60672 + endloop + endfacet + facet normal -0.426134 -0.0729931 0.901711 + outer loop + vertex 0.901881 1.19705 2.60938 + vertex 0.899942 1.20243 2.6089 + vertex 0.897789 1.19801 2.60752 + endloop + endfacet + facet normal -0.451954 -0.0835322 0.888122 + outer loop + vertex 0.903005 1.20093 2.61031 + vertex 0.899942 1.20243 2.6089 + vertex 0.901881 1.19705 2.60938 + endloop + endfacet + facet normal -0.421978 -0.095468 0.901565 + outer loop + vertex 0.901881 1.19705 2.60938 + vertex 0.904806 1.19873 2.61092 + vertex 0.903005 1.20093 2.61031 + endloop + endfacet + facet normal -0.390994 -0.0655528 0.918056 + outer loop + vertex 0.904806 1.19873 2.61092 + vertex 0.905843 1.20273 2.61165 + vertex 0.903005 1.20093 2.61031 + endloop + endfacet + facet normal -0.395505 -0.0640492 0.916228 + outer loop + vertex 0.904806 1.19873 2.61092 + vertex 0.90794 1.19826 2.61224 + vertex 0.905843 1.20273 2.61165 + endloop + endfacet + facet normal -0.433813 -0.0845859 0.897024 + outer loop + vertex 0.90794 1.19826 2.61224 + vertex 0.910219 1.2026 2.61376 + vertex 0.905843 1.20273 2.61165 + endloop + endfacet + facet normal -0.448214 -0.0748511 0.890787 + outer loop + vertex 0.911962 1.19714 2.61417 + vertex 0.910219 1.2026 2.61376 + vertex 0.90794 1.19826 2.61224 + endloop + endfacet + facet normal -0.459878 -0.141127 0.876696 + outer loop + vertex 0.909393 1.19337 2.61222 + vertex 0.911962 1.19714 2.61417 + vertex 0.90794 1.19826 2.61224 + endloop + endfacet + facet normal -0.401686 -0.124007 0.907343 + outer loop + vertex 0.909393 1.19337 2.61222 + vertex 0.90794 1.19826 2.61224 + vertex 0.905646 1.19485 2.61076 + endloop + endfacet + facet normal -0.4134 -0.165286 0.895422 + outer loop + vertex 0.906961 1.19019 2.61051 + vertex 0.909393 1.19337 2.61222 + vertex 0.905646 1.19485 2.61076 + endloop + endfacet + facet normal -0.398802 -0.161571 0.902692 + outer loop + vertex 0.905646 1.19485 2.61076 + vertex 0.903186 1.19164 2.6091 + vertex 0.906961 1.19019 2.61051 + endloop + endfacet + facet normal -0.403239 -0.178069 0.897602 + outer loop + vertex 0.903186 1.19164 2.6091 + vertex 0.904916 1.18688 2.60893 + vertex 0.906961 1.19019 2.61051 + endloop + endfacet + facet normal -0.397616 -0.182332 0.899253 + outer loop + vertex 0.908037 1.18631 2.6102 + vertex 0.906961 1.19019 2.61051 + vertex 0.904916 1.18688 2.60893 + endloop + endfacet + facet normal -0.397533 -0.181348 0.899489 + outer loop + vertex 0.908037 1.18631 2.6102 + vertex 0.904916 1.18688 2.60893 + vertex 0.907492 1.18222 2.60913 + endloop + endfacet + facet normal -0.407619 -0.17895 0.895446 + outer loop + vertex 0.907492 1.18222 2.60913 + vertex 0.91018 1.18404 2.61072 + vertex 0.908037 1.18631 2.6102 + endloop + endfacet + facet normal -0.421587 -0.194374 0.88571 + outer loop + vertex 0.91018 1.18404 2.61072 + vertex 0.91083 1.18795 2.61189 + vertex 0.908037 1.18631 2.6102 + endloop + endfacet + facet normal -0.45882 -0.183325 0.869412 + outer loop + vertex 0.91018 1.18404 2.61072 + vertex 0.913302 1.18313 2.61218 + vertex 0.91083 1.18795 2.61189 + endloop + endfacet + facet normal -0.4915 -0.201411 0.847267 + outer loop + vertex 0.913302 1.18313 2.61218 + vertex 0.914952 1.18657 2.61395 + vertex 0.91083 1.18795 2.61189 + endloop + endfacet + facet normal -0.485727 -0.168716 0.857673 + outer loop + vertex 0.914952 1.18657 2.61395 + vertex 0.913224 1.19159 2.61396 + vertex 0.91083 1.18795 2.61189 + endloop + endfacet + facet normal -0.474552 -0.178506 0.861937 + outer loop + vertex 0.91083 1.18795 2.61189 + vertex 0.913224 1.19159 2.61396 + vertex 0.909393 1.19337 2.61222 + endloop + endfacet + facet normal -0.459307 -0.1865 0.868478 + outer loop + vertex 0.911412 1.18017 2.61054 + vertex 0.913302 1.18313 2.61218 + vertex 0.91018 1.18404 2.61072 + endloop + endfacet + facet normal -0.474156 -0.174053 0.863065 + outer loop + vertex 0.915384 1.17785 2.61225 + vertex 0.913302 1.18313 2.61218 + vertex 0.911412 1.18017 2.61054 + endloop + endfacet + facet normal -0.483324 -0.197289 0.852921 + outer loop + vertex 0.912727 1.17624 2.61038 + vertex 0.915384 1.17785 2.61225 + vertex 0.911412 1.18017 2.61054 + endloop + endfacet + facet normal -0.420924 -0.17788 0.889484 + outer loop + vertex 0.912727 1.17624 2.61038 + vertex 0.911412 1.18017 2.61054 + vertex 0.909487 1.17699 2.60899 + endloop + endfacet + facet normal -0.421243 -0.180563 0.888792 + outer loop + vertex 0.912727 1.17624 2.61038 + vertex 0.909487 1.17699 2.60899 + vertex 0.912154 1.17209 2.60926 + endloop + endfacet + facet normal -0.404171 -0.170722 0.89861 + outer loop + vertex 0.912154 1.17209 2.60926 + vertex 0.909487 1.17699 2.60899 + vertex 0.907833 1.1731 2.60751 + endloop + endfacet + facet normal -0.405717 -0.18264 0.895565 + outer loop + vertex 0.909588 1.16829 2.60732 + vertex 0.912154 1.17209 2.60926 + vertex 0.907833 1.1731 2.60751 + endloop + endfacet + facet normal -0.398012 -0.179984 0.899551 + outer loop + vertex 0.909588 1.16829 2.60732 + vertex 0.907833 1.1731 2.60751 + vertex 0.905721 1.16976 2.60591 + endloop + endfacet + facet normal -0.398213 -0.18074 0.899311 + outer loop + vertex 0.907049 1.16518 2.60558 + vertex 0.909588 1.16829 2.60732 + vertex 0.905721 1.16976 2.60591 + endloop + endfacet + facet normal -0.414537 -0.184874 0.891056 + outer loop + vertex 0.905721 1.16976 2.60591 + vertex 0.903285 1.16662 2.60412 + vertex 0.907049 1.16518 2.60558 + endloop + endfacet + facet normal -0.413934 -0.182515 0.891822 + outer loop + vertex 0.903285 1.16662 2.60412 + vertex 0.904948 1.16192 2.60393 + vertex 0.907049 1.16518 2.60558 + endloop + endfacet + facet normal -0.435382 -0.18963 0.880047 + outer loop + vertex 0.904948 1.16192 2.60393 + vertex 0.903285 1.16662 2.60412 + vertex 0.900809 1.16292 2.6021 + endloop + endfacet + facet normal -0.434864 -0.185353 0.881214 + outer loop + vertex 0.903302 1.15818 2.60233 + vertex 0.904948 1.16192 2.60393 + vertex 0.900809 1.16292 2.6021 + endloop + endfacet + facet normal -0.419588 -0.194402 0.886653 + outer loop + vertex 0.907545 1.1573 2.60415 + vertex 0.904948 1.16192 2.60393 + vertex 0.903302 1.15818 2.60233 + endloop + endfacet + facet normal -0.410628 -0.189109 0.891977 + outer loop + vertex 0.908088 1.16137 2.60526 + vertex 0.904948 1.16192 2.60393 + vertex 0.907545 1.1573 2.60415 + endloop + endfacet + facet normal -0.410361 -0.185351 0.892888 + outer loop + vertex 0.908088 1.16137 2.60526 + vertex 0.907049 1.16518 2.60558 + vertex 0.904948 1.16192 2.60393 + endloop + endfacet + facet normal -0.395892 -0.181999 0.900081 + outer loop + vertex 0.908088 1.16137 2.60526 + vertex 0.910917 1.16318 2.60687 + vertex 0.907049 1.16518 2.60558 + endloop + endfacet + facet normal -0.396166 -0.182698 0.899819 + outer loop + vertex 0.910917 1.16318 2.60687 + vertex 0.909588 1.16829 2.60732 + vertex 0.907049 1.16518 2.60558 + endloop + endfacet + facet normal -0.419378 -0.180364 0.889714 + outer loop + vertex 0.901872 1.17191 2.60453 + vertex 0.903285 1.16662 2.60412 + vertex 0.905721 1.16976 2.60591 + endloop + endfacet + facet normal -0.398939 -0.179269 0.899283 + outer loop + vertex 0.905721 1.16976 2.60591 + vertex 0.907833 1.1731 2.60751 + vertex 0.904673 1.17366 2.60622 + endloop + endfacet + facet normal -0.408061 -0.180716 0.89489 + outer loop + vertex 0.913846 1.16629 2.60886 + vertex 0.912154 1.17209 2.60926 + vertex 0.909588 1.16829 2.60732 + endloop + endfacet + facet normal -0.409722 -0.18563 0.893123 + outer loop + vertex 0.910917 1.16318 2.60687 + vertex 0.913846 1.16629 2.60886 + vertex 0.909588 1.16829 2.60732 + endloop + endfacet + facet normal -0.40295 -0.192968 0.894648 + outer loop + vertex 0.913849 1.16267 2.60808 + vertex 0.913846 1.16629 2.60886 + vertex 0.910917 1.16318 2.60687 + endloop + endfacet + facet normal -0.401929 -0.179268 0.897951 + outer loop + vertex 0.913877 1.15894 2.60735 + vertex 0.913849 1.16267 2.60808 + vertex 0.910917 1.16318 2.60687 + endloop + endfacet + facet normal -0.404976 -0.181607 0.89611 + outer loop + vertex 0.910348 1.15925 2.60582 + vertex 0.913877 1.15894 2.60735 + vertex 0.910917 1.16318 2.60687 + endloop + endfacet + facet normal -0.394552 -0.184221 0.900217 + outer loop + vertex 0.910348 1.15925 2.60582 + vertex 0.910917 1.16318 2.60687 + vertex 0.908088 1.16137 2.60526 + endloop + endfacet + facet normal -0.400437 -0.191586 0.896072 + outer loop + vertex 0.907545 1.1573 2.60415 + vertex 0.910348 1.15925 2.60582 + vertex 0.908088 1.16137 2.60526 + endloop + endfacet + facet normal -0.400904 -0.190867 0.896017 + outer loop + vertex 0.910348 1.15925 2.60582 + vertex 0.907545 1.1573 2.60415 + vertex 0.911623 1.15536 2.60556 + endloop + endfacet + facet normal -0.404949 -0.192057 0.893941 + outer loop + vertex 0.911623 1.15536 2.60556 + vertex 0.913877 1.15894 2.60735 + vertex 0.910348 1.15925 2.60582 + endloop + endfacet + facet normal -0.39841 -0.173921 0.900567 + outer loop + vertex 0.907833 1.1731 2.60751 + vertex 0.909487 1.17699 2.60899 + vertex 0.905255 1.17782 2.60728 + endloop + endfacet + facet normal -0.398618 -0.176009 0.900069 + outer loop + vertex 0.909487 1.17699 2.60899 + vertex 0.907492 1.18222 2.60913 + vertex 0.905255 1.17782 2.60728 + endloop + endfacet + facet normal -0.415319 -0.182135 0.891256 + outer loop + vertex 0.907492 1.18222 2.60913 + vertex 0.909487 1.17699 2.60899 + vertex 0.911412 1.18017 2.61054 + endloop + endfacet + facet normal -0.484119 -0.19584 0.852805 + outer loop + vertex 0.915154 1.1737 2.61117 + vertex 0.915384 1.17785 2.61225 + vertex 0.912727 1.17624 2.61038 + endloop + endfacet + facet normal -0.462533 -0.169861 0.870178 + outer loop + vertex 0.912154 1.17209 2.60926 + vertex 0.915154 1.1737 2.61117 + vertex 0.912727 1.17624 2.61038 + endloop + endfacet + facet normal -0.455395 -0.184202 0.871025 + outer loop + vertex 0.915154 1.1737 2.61117 + vertex 0.912154 1.17209 2.60926 + vertex 0.916242 1.1696 2.61087 + endloop + endfacet + facet normal -0.540523 -0.202864 0.816505 + outer loop + vertex 0.916242 1.1696 2.61087 + vertex 0.919138 1.17226 2.61345 + vertex 0.915154 1.1737 2.61117 + endloop + endfacet + facet normal -0.53075 -0.216366 0.819445 + outer loop + vertex 0.919628 1.16694 2.61236 + vertex 0.919138 1.17226 2.61345 + vertex 0.916242 1.1696 2.61087 + endloop + endfacet + facet normal -0.529831 -0.214605 0.820502 + outer loop + vertex 0.917246 1.16576 2.61052 + vertex 0.919628 1.16694 2.61236 + vertex 0.916242 1.1696 2.61087 + endloop + endfacet + facet normal -0.453706 -0.19919 0.868605 + outer loop + vertex 0.917246 1.16576 2.61052 + vertex 0.916242 1.1696 2.61087 + vertex 0.913846 1.16629 2.60886 + endloop + endfacet + facet normal -0.453318 -0.189268 0.871023 + outer loop + vertex 0.917246 1.16576 2.61052 + vertex 0.913846 1.16629 2.60886 + vertex 0.916746 1.16198 2.60943 + endloop + endfacet + facet normal -0.451838 -0.18814 0.872035 + outer loop + vertex 0.916746 1.16198 2.60943 + vertex 0.913846 1.16629 2.60886 + vertex 0.913849 1.16267 2.60808 + endloop + endfacet + facet normal -0.450369 -0.175229 0.875478 + outer loop + vertex 0.913877 1.15894 2.60735 + vertex 0.916746 1.16198 2.60943 + vertex 0.913849 1.16267 2.60808 + endloop + endfacet + facet normal -0.446725 -0.179381 0.876504 + outer loop + vertex 0.918096 1.1567 2.60904 + vertex 0.916746 1.16198 2.60943 + vertex 0.913877 1.15894 2.60735 + endloop + endfacet + facet normal -0.4547 -0.201021 0.867663 + outer loop + vertex 0.915684 1.15313 2.60695 + vertex 0.918096 1.1567 2.60904 + vertex 0.913877 1.15894 2.60735 + endloop + endfacet + facet normal -0.409335 -0.188658 0.892666 + outer loop + vertex 0.915684 1.15313 2.60695 + vertex 0.913877 1.15894 2.60735 + vertex 0.911623 1.15536 2.60556 + endloop + endfacet + facet normal -0.414066 -0.200168 0.887965 + outer loop + vertex 0.912902 1.1514 2.60526 + vertex 0.915684 1.15313 2.60695 + vertex 0.911623 1.15536 2.60556 + endloop + endfacet + facet normal -0.397195 -0.195386 0.896694 + outer loop + vertex 0.912902 1.1514 2.60526 + vertex 0.911623 1.15536 2.60556 + vertex 0.909637 1.15207 2.60396 + endloop + endfacet + facet normal -0.397308 -0.196503 0.8964 + outer loop + vertex 0.912902 1.1514 2.60526 + vertex 0.909637 1.15207 2.60396 + vertex 0.912462 1.14728 2.60417 + endloop + endfacet + facet normal -0.39842 -0.196266 0.895958 + outer loop + vertex 0.912462 1.14728 2.60417 + vertex 0.915183 1.1491 2.60577 + vertex 0.912902 1.1514 2.60526 + endloop + endfacet + facet normal -0.39919 -0.195048 0.895881 + outer loop + vertex 0.915183 1.1491 2.60577 + vertex 0.912462 1.14728 2.60417 + vertex 0.91651 1.14526 2.60553 + endloop + endfacet + facet normal -0.43627 -0.206581 0.875781 + outer loop + vertex 0.91651 1.14526 2.60553 + vertex 0.918335 1.14831 2.60716 + vertex 0.915183 1.1491 2.60577 + endloop + endfacet + facet normal -0.435713 -0.201967 0.877134 + outer loop + vertex 0.915183 1.1491 2.60577 + vertex 0.918335 1.14831 2.60716 + vertex 0.915684 1.15313 2.60695 + endloop + endfacet + facet normal -0.463154 -0.217867 0.859082 + outer loop + vertex 0.918335 1.14831 2.60716 + vertex 0.919809 1.15181 2.60884 + vertex 0.915684 1.15313 2.60695 + endloop + endfacet + facet normal -0.395386 -0.195323 0.897507 + outer loop + vertex 0.912462 1.14728 2.60417 + vertex 0.909637 1.15207 2.60396 + vertex 0.908146 1.14813 2.60245 + endloop + endfacet + facet normal -0.394854 -0.189794 0.898926 + outer loop + vertex 0.910281 1.14288 2.60228 + vertex 0.912462 1.14728 2.60417 + vertex 0.908146 1.14813 2.60245 + endloop + endfacet + facet normal -0.388085 -0.194026 0.900968 + outer loop + vertex 0.914611 1.14207 2.60397 + vertex 0.912462 1.14728 2.60417 + vertex 0.910281 1.14288 2.60228 + endloop + endfacet + facet normal -0.387683 -0.189457 0.902113 + outer loop + vertex 0.913078 1.13814 2.60249 + vertex 0.914611 1.14207 2.60397 + vertex 0.910281 1.14288 2.60228 + endloop + endfacet + facet normal -0.38865 -0.190052 0.901572 + outer loop + vertex 0.909847 1.13873 2.60122 + vertex 0.913078 1.13814 2.60249 + vertex 0.910281 1.14288 2.60228 + endloop + endfacet + facet normal -0.402564 -0.187186 0.896049 + outer loop + vertex 0.909847 1.13873 2.60122 + vertex 0.910281 1.14288 2.60228 + vertex 0.907603 1.14098 2.60068 + endloop + endfacet + facet normal -0.412444 -0.19873 0.889042 + outer loop + vertex 0.907203 1.13687 2.59957 + vertex 0.909847 1.13873 2.60122 + vertex 0.907603 1.14098 2.60068 + endloop + endfacet + facet normal -0.41211 -0.199241 0.889083 + outer loop + vertex 0.909847 1.13873 2.60122 + vertex 0.907203 1.13687 2.59957 + vertex 0.911168 1.13488 2.60097 + endloop + endfacet + facet normal -0.411151 -0.196616 0.890111 + outer loop + vertex 0.907203 1.13687 2.59957 + vertex 0.909329 1.13165 2.5994 + vertex 0.911168 1.13488 2.60097 + endloop + endfacet + facet normal -0.40627 -0.200109 0.891572 + outer loop + vertex 0.912509 1.13103 2.60071 + vertex 0.911168 1.13488 2.60097 + vertex 0.909329 1.13165 2.5994 + endloop + endfacet + facet normal -0.406954 -0.208087 0.889432 + outer loop + vertex 0.912509 1.13103 2.60071 + vertex 0.909329 1.13165 2.5994 + vertex 0.912182 1.12694 2.59961 + endloop + endfacet + facet normal -0.391686 -0.210971 0.895586 + outer loop + vertex 0.912182 1.12694 2.59961 + vertex 0.91482 1.12882 2.6012 + vertex 0.912509 1.13103 2.60071 + endloop + endfacet + facet normal -0.382174 -0.199511 0.902296 + outer loop + vertex 0.91482 1.12882 2.6012 + vertex 0.915213 1.13294 2.60228 + vertex 0.912509 1.13103 2.60071 + endloop + endfacet + facet normal -0.382674 -0.199413 0.902106 + outer loop + vertex 0.91482 1.12882 2.6012 + vertex 0.918083 1.12819 2.60245 + vertex 0.915213 1.13294 2.60228 + endloop + endfacet + facet normal -0.39515 -0.207215 0.894941 + outer loop + vertex 0.918083 1.12819 2.60245 + vertex 0.919568 1.13201 2.60399 + vertex 0.915213 1.13294 2.60228 + endloop + endfacet + facet normal -0.393703 -0.193673 0.898604 + outer loop + vertex 0.919568 1.13201 2.60399 + vertex 0.917457 1.13729 2.6042 + vertex 0.915213 1.13294 2.60228 + endloop + endfacet + facet normal -0.390564 -0.195702 0.899533 + outer loop + vertex 0.915213 1.13294 2.60228 + vertex 0.917457 1.13729 2.6042 + vertex 0.913078 1.13814 2.60249 + endloop + endfacet + facet normal -0.38612 -0.193969 0.901825 + outer loop + vertex 0.915213 1.13294 2.60228 + vertex 0.913078 1.13814 2.60249 + vertex 0.911168 1.13488 2.60097 + endloop + endfacet + facet normal -0.389867 -0.188339 0.901406 + outer loop + vertex 0.917457 1.13729 2.6042 + vertex 0.914611 1.14207 2.60397 + vertex 0.913078 1.13814 2.60249 + endloop + endfacet + facet normal -0.401941 -0.19586 0.894474 + outer loop + vertex 0.917891 1.14142 2.6053 + vertex 0.914611 1.14207 2.60397 + vertex 0.917457 1.13729 2.6042 + endloop + endfacet + facet normal -0.402127 -0.19786 0.89395 + outer loop + vertex 0.917891 1.14142 2.6053 + vertex 0.91651 1.14526 2.60553 + vertex 0.914611 1.14207 2.60397 + endloop + endfacet + facet normal -0.453244 -0.214527 0.865187 + outer loop + vertex 0.917891 1.14142 2.6053 + vertex 0.920514 1.14315 2.6071 + vertex 0.91651 1.14526 2.60553 + endloop + endfacet + facet normal -0.447298 -0.19806 0.872179 + outer loop + vertex 0.920514 1.14315 2.6071 + vertex 0.918335 1.14831 2.60716 + vertex 0.91651 1.14526 2.60553 + endloop + endfacet + facet normal -0.413904 -0.197392 0.888662 + outer loop + vertex 0.922408 1.12712 2.60423 + vertex 0.919568 1.13201 2.60399 + vertex 0.918083 1.12819 2.60245 + endloop + endfacet + facet normal -0.417258 -0.224065 0.880733 + outer loop + vertex 0.920331 1.123 2.60219 + vertex 0.922408 1.12712 2.60423 + vertex 0.918083 1.12819 2.60245 + endloop + endfacet + facet normal -0.430982 -0.215003 0.876372 + outer loop + vertex 0.924554 1.12189 2.604 + vertex 0.922408 1.12712 2.60423 + vertex 0.920331 1.123 2.60219 + endloop + endfacet + facet normal -0.434107 -0.240244 0.868236 + outer loop + vertex 0.923226 1.11829 2.60234 + vertex 0.924554 1.12189 2.604 + vertex 0.920331 1.123 2.60219 + endloop + endfacet + facet normal -0.410794 -0.225436 0.883417 + outer loop + vertex 0.920037 1.11899 2.60103 + vertex 0.923226 1.11829 2.60234 + vertex 0.920331 1.123 2.60219 + endloop + endfacet + facet normal -0.383656 -0.23055 0.894234 + outer loop + vertex 0.920037 1.11899 2.60103 + vertex 0.920331 1.123 2.60219 + vertex 0.917689 1.12118 2.60059 + endloop + endfacet + facet normal -0.378792 -0.224616 0.897811 + outer loop + vertex 0.917372 1.11712 2.59944 + vertex 0.920037 1.11899 2.60103 + vertex 0.917689 1.12118 2.60059 + endloop + endfacet + facet normal -0.383174 -0.223803 0.896153 + outer loop + vertex 0.917689 1.12118 2.60059 + vertex 0.914441 1.12178 2.59935 + vertex 0.917372 1.11712 2.59944 + endloop + endfacet + facet normal -0.387362 -0.226485 0.893675 + outer loop + vertex 0.917372 1.11712 2.59944 + vertex 0.914441 1.12178 2.59935 + vertex 0.913028 1.11796 2.59777 + endloop + endfacet + facet normal -0.38688 -0.220715 0.895326 + outer loop + vertex 0.915211 1.11279 2.59744 + vertex 0.917372 1.11712 2.59944 + vertex 0.913028 1.11796 2.59777 + endloop + endfacet + facet normal -0.380257 -0.224851 0.897133 + outer loop + vertex 0.919615 1.112 2.59911 + vertex 0.917372 1.11712 2.59944 + vertex 0.915211 1.11279 2.59744 + endloop + endfacet + facet normal -0.379438 -0.213683 0.900203 + outer loop + vertex 0.918099 1.10809 2.59754 + vertex 0.919615 1.112 2.59911 + vertex 0.915211 1.11279 2.59744 + endloop + endfacet + facet normal -0.391656 -0.221352 0.89309 + outer loop + vertex 0.914823 1.10866 2.59625 + vertex 0.918099 1.10809 2.59754 + vertex 0.915211 1.11279 2.59744 + endloop + endfacet + facet normal -0.422735 -0.214769 0.880437 + outer loop + vertex 0.914823 1.10866 2.59625 + vertex 0.915211 1.11279 2.59744 + vertex 0.912359 1.11101 2.59564 + endloop + endfacet + facet normal -0.440061 -0.236649 0.866224 + outer loop + vertex 0.912214 1.10688 2.59443 + vertex 0.914823 1.10866 2.59625 + vertex 0.912359 1.11101 2.59564 + endloop + endfacet + facet normal -0.440983 -0.235222 0.866144 + outer loop + vertex 0.914823 1.10866 2.59625 + vertex 0.912214 1.10688 2.59443 + vertex 0.916217 1.10487 2.59593 + endloop + endfacet + facet normal -0.437254 -0.224228 0.870937 + outer loop + vertex 0.912214 1.10688 2.59443 + vertex 0.914493 1.10177 2.59426 + vertex 0.916217 1.10487 2.59593 + endloop + endfacet + facet normal -0.391525 -0.219391 0.893631 + outer loop + vertex 0.916217 1.10487 2.59593 + vertex 0.918099 1.10809 2.59754 + vertex 0.914823 1.10866 2.59625 + endloop + endfacet + facet normal -0.38546 -0.223719 0.895193 + outer loop + vertex 0.920256 1.10299 2.5972 + vertex 0.918099 1.10809 2.59754 + vertex 0.916217 1.10487 2.59593 + endloop + endfacet + facet normal -0.383721 -0.218609 0.8972 + outer loop + vertex 0.91759 1.10112 2.5956 + vertex 0.920256 1.10299 2.5972 + vertex 0.916217 1.10487 2.59593 + endloop + endfacet + facet normal -0.426211 -0.232193 0.874317 + outer loop + vertex 0.91759 1.10112 2.5956 + vertex 0.916217 1.10487 2.59593 + vertex 0.914493 1.10177 2.59426 + endloop + endfacet + facet normal -0.427085 -0.243588 0.870783 + outer loop + vertex 0.91759 1.10112 2.5956 + vertex 0.914493 1.10177 2.59426 + vertex 0.917424 1.09716 2.59441 + endloop + endfacet + facet normal -0.382894 -0.22017 0.897172 + outer loop + vertex 0.917689 1.12118 2.60059 + vertex 0.916246 1.12499 2.60091 + vertex 0.914441 1.12178 2.59935 + endloop + endfacet + facet normal -0.390157 -0.215156 0.895257 + outer loop + vertex 0.912182 1.12694 2.59961 + vertex 0.914441 1.12178 2.59935 + vertex 0.916246 1.12499 2.60091 + endloop + endfacet + facet normal -0.380374 -0.222284 0.897722 + outer loop + vertex 0.920037 1.11899 2.60103 + vertex 0.917372 1.11712 2.59944 + vertex 0.921479 1.1152 2.60071 + endloop + endfacet + facet normal -0.381421 -0.225322 0.89652 + outer loop + vertex 0.917372 1.11712 2.59944 + vertex 0.919615 1.112 2.59911 + vertex 0.921479 1.1152 2.60071 + endloop + endfacet + facet normal -0.38365 -0.223746 0.895963 + outer loop + vertex 0.92293 1.11141 2.60038 + vertex 0.921479 1.1152 2.60071 + vertex 0.919615 1.112 2.59911 + endloop + endfacet + facet normal -0.383383 -0.220105 0.896979 + outer loop + vertex 0.92293 1.11141 2.60038 + vertex 0.919615 1.112 2.59911 + vertex 0.922509 1.10731 2.5992 + endloop + endfacet + facet normal -0.375958 -0.215447 0.901242 + outer loop + vertex 0.922509 1.10731 2.5992 + vertex 0.919615 1.112 2.59911 + vertex 0.918099 1.10809 2.59754 + endloop + endfacet + facet normal -0.376308 -0.220167 0.899955 + outer loop + vertex 0.920256 1.10299 2.5972 + vertex 0.922509 1.10731 2.5992 + vertex 0.918099 1.10809 2.59754 + endloop + endfacet + facet normal -0.379185 -0.218314 0.899198 + outer loop + vertex 0.924629 1.10215 2.59884 + vertex 0.922509 1.10731 2.5992 + vertex 0.920256 1.10299 2.5972 + endloop + endfacet + facet normal -0.380187 -0.229982 0.89586 + outer loop + vertex 0.923186 1.09836 2.59725 + vertex 0.924629 1.10215 2.59884 + vertex 0.920256 1.10299 2.5972 + endloop + endfacet + facet normal -0.434375 -0.240717 0.867971 + outer loop + vertex 0.92293 1.11141 2.60038 + vertex 0.925544 1.11316 2.60217 + vertex 0.921479 1.1152 2.60071 + endloop + endfacet + facet normal -0.427577 -0.221114 0.876519 + outer loop + vertex 0.925544 1.11316 2.60217 + vertex 0.923226 1.11829 2.60234 + vertex 0.921479 1.1152 2.60071 + endloop + endfacet + facet normal -0.389165 -0.222277 0.893948 + outer loop + vertex 0.917689 1.12118 2.60059 + vertex 0.920331 1.123 2.60219 + vertex 0.916246 1.12499 2.60091 + endloop + endfacet + facet normal -0.385084 -0.211029 0.89843 + outer loop + vertex 0.920331 1.123 2.60219 + vertex 0.918083 1.12819 2.60245 + vertex 0.916246 1.12499 2.60091 + endloop + endfacet + facet normal -0.411489 -0.232699 0.881208 + outer loop + vertex 0.921479 1.1152 2.60071 + vertex 0.923226 1.11829 2.60234 + vertex 0.920037 1.11899 2.60103 + endloop + endfacet + facet normal -0.38381 -0.211921 0.898765 + outer loop + vertex 0.916246 1.12499 2.60091 + vertex 0.918083 1.12819 2.60245 + vertex 0.91482 1.12882 2.6012 + endloop + endfacet + facet normal -0.389708 -0.213883 0.895758 + outer loop + vertex 0.91482 1.12882 2.6012 + vertex 0.912182 1.12694 2.59961 + vertex 0.916246 1.12499 2.60091 + endloop + endfacet + facet normal -0.415606 -0.213548 0.88412 + outer loop + vertex 0.912182 1.12694 2.59961 + vertex 0.909329 1.13165 2.5994 + vertex 0.907935 1.12786 2.59783 + endloop + endfacet + facet normal -0.415743 -0.214966 0.883712 + outer loop + vertex 0.91014 1.1227 2.59761 + vertex 0.912182 1.12694 2.59961 + vertex 0.907935 1.12786 2.59783 + endloop + endfacet + facet normal -0.386034 -0.19373 0.901913 + outer loop + vertex 0.912509 1.13103 2.60071 + vertex 0.915213 1.13294 2.60228 + vertex 0.911168 1.13488 2.60097 + endloop + endfacet + facet normal -0.388818 -0.192043 0.901077 + outer loop + vertex 0.911168 1.13488 2.60097 + vertex 0.913078 1.13814 2.60249 + vertex 0.909847 1.13873 2.60122 + endloop + endfacet + facet normal -0.400631 -0.198959 0.894377 + outer loop + vertex 0.912462 1.14728 2.60417 + vertex 0.914611 1.14207 2.60397 + vertex 0.91651 1.14526 2.60553 + endloop + endfacet + facet normal -0.401393 -0.192276 0.895496 + outer loop + vertex 0.907545 1.1573 2.60415 + vertex 0.909637 1.15207 2.60396 + vertex 0.911623 1.15536 2.60556 + endloop + endfacet + facet normal -0.409215 -0.195252 0.891302 + outer loop + vertex 0.909637 1.15207 2.60396 + vertex 0.907545 1.1573 2.60415 + vertex 0.905345 1.15295 2.60219 + endloop + endfacet + facet normal -0.40908 -0.208553 0.888346 + outer loop + vertex 0.915183 1.1491 2.60577 + vertex 0.915684 1.15313 2.60695 + vertex 0.912902 1.1514 2.60526 + endloop + endfacet + facet normal -0.459627 -0.196746 0.866045 + outer loop + vertex 0.919809 1.15181 2.60884 + vertex 0.918096 1.1567 2.60904 + vertex 0.915684 1.15313 2.60695 + endloop + endfacet + facet normal -0.459563 -0.193812 0.86674 + outer loop + vertex 0.912154 1.17209 2.60926 + vertex 0.913846 1.16629 2.60886 + vertex 0.916242 1.1696 2.61087 + endloop + endfacet + facet normal -0.537591 -0.185009 0.822659 + outer loop + vertex 0.915154 1.1737 2.61117 + vertex 0.919138 1.17226 2.61345 + vertex 0.915384 1.17785 2.61225 + endloop + endfacet + facet normal -0.549607 -0.195293 0.812276 + outer loop + vertex 0.919138 1.17226 2.61345 + vertex 0.918764 1.17719 2.61438 + vertex 0.915384 1.17785 2.61225 + endloop + endfacet + facet normal -0.549128 -0.181348 0.815826 + outer loop + vertex 0.918764 1.17719 2.61438 + vertex 0.917227 1.18165 2.61434 + vertex 0.915384 1.17785 2.61225 + endloop + endfacet + facet normal -0.4116 -0.172568 0.894878 + outer loop + vertex 0.91018 1.18404 2.61072 + vertex 0.907492 1.18222 2.60913 + vertex 0.911412 1.18017 2.61054 + endloop + endfacet + facet normal -0.401081 -0.183397 0.897496 + outer loop + vertex 0.907492 1.18222 2.60913 + vertex 0.904916 1.18688 2.60893 + vertex 0.903293 1.18305 2.60742 + endloop + endfacet + facet normal -0.408872 -0.179057 0.894853 + outer loop + vertex 0.903293 1.18305 2.60742 + vertex 0.904916 1.18688 2.60893 + vertex 0.900712 1.18781 2.6072 + endloop + endfacet + facet normal -0.42472 -0.188756 0.885429 + outer loop + vertex 0.908037 1.18631 2.6102 + vertex 0.91083 1.18795 2.61189 + vertex 0.906961 1.19019 2.61051 + endloop + endfacet + facet normal -0.408989 -0.180054 0.8946 + outer loop + vertex 0.904916 1.18688 2.60893 + vertex 0.903186 1.19164 2.6091 + vertex 0.900712 1.18781 2.6072 + endloop + endfacet + facet normal -0.418883 -0.172142 0.891574 + outer loop + vertex 0.900712 1.18781 2.6072 + vertex 0.903186 1.19164 2.6091 + vertex 0.899272 1.1932 2.60756 + endloop + endfacet + facet normal -0.411352 -0.145173 0.899841 + outer loop + vertex 0.903186 1.19164 2.6091 + vertex 0.901881 1.19705 2.60938 + vertex 0.899272 1.1932 2.60756 + endloop + endfacet + facet normal -0.415665 -0.146102 0.897706 + outer loop + vertex 0.901881 1.19705 2.60938 + vertex 0.903186 1.19164 2.6091 + vertex 0.905646 1.19485 2.61076 + endloop + endfacet + facet normal -0.414219 -0.164532 0.895183 + outer loop + vertex 0.91083 1.18795 2.61189 + vertex 0.909393 1.19337 2.61222 + vertex 0.906961 1.19019 2.61051 + endloop + endfacet + facet normal -0.462394 -0.138911 0.875725 + outer loop + vertex 0.913224 1.19159 2.61396 + vertex 0.911962 1.19714 2.61417 + vertex 0.909393 1.19337 2.61222 + endloop + endfacet + facet normal -0.400915 -0.124636 0.907597 + outer loop + vertex 0.905646 1.19485 2.61076 + vertex 0.90794 1.19826 2.61224 + vertex 0.904806 1.19873 2.61092 + endloop + endfacet + facet normal -0.406436 -0.125725 0.904988 + outer loop + vertex 0.904806 1.19873 2.61092 + vertex 0.901881 1.19705 2.60938 + vertex 0.905646 1.19485 2.61076 + endloop + endfacet + facet normal -0.434205 -0.0357696 0.900104 + outer loop + vertex 0.903005 1.20093 2.61031 + vertex 0.90291 1.20397 2.61039 + vertex 0.899942 1.20243 2.6089 + endloop + endfacet + facet normal -0.407571 -0.0352322 0.912494 + outer loop + vertex 0.903005 1.20093 2.61031 + vertex 0.905843 1.20273 2.61165 + vertex 0.90291 1.20397 2.61039 + endloop + endfacet + facet normal -0.434121 -0.126061 0.891991 + outer loop + vertex 0.899272 1.1932 2.60756 + vertex 0.901881 1.19705 2.60938 + vertex 0.897789 1.19801 2.60752 + endloop + endfacet + facet normal -0.43304 -0.175427 0.884139 + outer loop + vertex 0.900712 1.18781 2.6072 + vertex 0.899272 1.1932 2.60756 + vertex 0.896745 1.1902 2.60573 + endloop + endfacet + facet normal -0.500343 -0.127884 0.856331 + outer loop + vertex 0.892248 1.19683 2.60432 + vertex 0.893666 1.19227 2.60447 + vertex 0.895672 1.19479 2.60602 + endloop + endfacet + facet normal -0.435896 -0.181831 0.881437 + outer loop + vertex 0.897706 1.18615 2.60537 + vertex 0.900712 1.18781 2.6072 + vertex 0.896745 1.1902 2.60573 + endloop + endfacet + facet normal -0.436099 -0.181442 0.881417 + outer loop + vertex 0.900079 1.18373 2.60605 + vertex 0.900712 1.18781 2.6072 + vertex 0.897706 1.18615 2.60537 + endloop + endfacet + facet normal -0.420587 -0.185717 0.888041 + outer loop + vertex 0.900079 1.18373 2.60605 + vertex 0.903293 1.18305 2.60742 + vertex 0.900712 1.18781 2.6072 + endloop + endfacet + facet normal -0.40026 -0.174955 0.899546 + outer loop + vertex 0.905255 1.17782 2.60728 + vertex 0.907492 1.18222 2.60913 + vertex 0.903293 1.18305 2.60742 + endloop + endfacet + facet normal -0.398498 -0.173971 0.900518 + outer loop + vertex 0.904673 1.17366 2.60622 + vertex 0.907833 1.1731 2.60751 + vertex 0.905255 1.17782 2.60728 + endloop + endfacet + facet normal -0.421008 -0.184303 0.888135 + outer loop + vertex 0.904673 1.17366 2.60622 + vertex 0.901872 1.17191 2.60453 + vertex 0.905721 1.16976 2.60591 + endloop + endfacet + facet normal -0.438785 -0.176995 0.880988 + outer loop + vertex 0.902546 1.17592 2.60567 + vertex 0.901344 1.17982 2.60586 + vertex 0.899424 1.17663 2.60426 + endloop + endfacet + facet normal -0.447717 -0.179553 0.875962 + outer loop + vertex 0.899448 1.16821 2.60253 + vertex 0.901872 1.17191 2.60453 + vertex 0.897837 1.17292 2.60267 + endloop + endfacet + facet normal -0.440919 -0.185234 0.878225 + outer loop + vertex 0.903285 1.16662 2.60412 + vertex 0.901872 1.17191 2.60453 + vertex 0.899448 1.16821 2.60253 + endloop + endfacet + facet normal -0.440858 -0.18501 0.878303 + outer loop + vertex 0.900809 1.16292 2.6021 + vertex 0.903285 1.16662 2.60412 + vertex 0.899448 1.16821 2.60253 + endloop + endfacet + facet normal -0.444233 -0.190568 0.875409 + outer loop + vertex 0.900123 1.15893 2.60088 + vertex 0.903302 1.15818 2.60233 + vertex 0.900809 1.16292 2.6021 + endloop + endfacet + facet normal -0.41906 -0.188832 0.888105 + outer loop + vertex 0.905345 1.15295 2.60219 + vertex 0.907545 1.1573 2.60415 + vertex 0.903302 1.15818 2.60233 + endloop + endfacet + facet normal -0.408562 -0.188606 0.893031 + outer loop + vertex 0.908146 1.14813 2.60245 + vertex 0.909637 1.15207 2.60396 + vertex 0.905345 1.15295 2.60219 + endloop + endfacet + facet normal -0.407669 -0.194778 0.892114 + outer loop + vertex 0.910281 1.14288 2.60228 + vertex 0.908146 1.14813 2.60245 + vertex 0.906292 1.14489 2.60089 + endloop + endfacet + facet normal -0.404023 -0.184967 0.895853 + outer loop + vertex 0.907603 1.14098 2.60068 + vertex 0.910281 1.14288 2.60228 + vertex 0.906292 1.14489 2.60089 + endloop + endfacet + facet normal -0.439298 -0.196019 0.876695 + outer loop + vertex 0.902353 1.147 2.59941 + vertex 0.904955 1.14881 2.60111 + vertex 0.902709 1.15113 2.60051 + endloop + endfacet + facet normal -0.429789 -0.19284 0.882097 + outer loop + vertex 0.907603 1.14098 2.60068 + vertex 0.906292 1.14489 2.60089 + vertex 0.904453 1.14168 2.5993 + endloop + endfacet + facet normal -0.430014 -0.194998 0.881512 + outer loop + vertex 0.907603 1.14098 2.60068 + vertex 0.904453 1.14168 2.5993 + vertex 0.907203 1.13687 2.59957 + endloop + endfacet + facet normal -0.439933 -0.201029 0.875241 + outer loop + vertex 0.907203 1.13687 2.59957 + vertex 0.904453 1.14168 2.5993 + vertex 0.90302 1.13787 2.5977 + endloop + endfacet + facet normal -0.439816 -0.199985 0.875539 + outer loop + vertex 0.905119 1.13264 2.59756 + vertex 0.907203 1.13687 2.59957 + vertex 0.90302 1.13787 2.5977 + endloop + endfacet + facet normal -0.432374 -0.204874 0.878111 + outer loop + vertex 0.909329 1.13165 2.5994 + vertex 0.907203 1.13687 2.59957 + vertex 0.905119 1.13264 2.59756 + endloop + endfacet + facet normal -0.432376 -0.204895 0.878105 + outer loop + vertex 0.907935 1.12786 2.59783 + vertex 0.909329 1.13165 2.5994 + vertex 0.905119 1.13264 2.59756 + endloop + endfacet + facet normal -0.443792 -0.212041 0.870682 + outer loop + vertex 0.904827 1.12872 2.59646 + vertex 0.907935 1.12786 2.59783 + vertex 0.905119 1.13264 2.59756 + endloop + endfacet + facet normal -0.468662 -0.206848 0.858819 + outer loop + vertex 0.904827 1.12872 2.59646 + vertex 0.905119 1.13264 2.59756 + vertex 0.902464 1.13109 2.59574 + endloop + endfacet + facet normal -0.489974 -0.233805 0.839798 + outer loop + vertex 0.902582 1.12751 2.59481 + vertex 0.904827 1.12872 2.59646 + vertex 0.902464 1.13109 2.59574 + endloop + endfacet + facet normal -0.513685 -0.231085 0.826274 + outer loop + vertex 0.902464 1.13109 2.59574 + vertex 0.898708 1.1321 2.59369 + vertex 0.902582 1.12751 2.59481 + endloop + endfacet + facet normal -0.532306 -0.251172 0.808433 + outer loop + vertex 0.902582 1.12751 2.59481 + vertex 0.898708 1.1321 2.59369 + vertex 0.899774 1.12666 2.5927 + endloop + endfacet + facet normal -0.53054 -0.256075 0.808055 + outer loop + vertex 0.903678 1.12206 2.5938 + vertex 0.902582 1.12751 2.59481 + vertex 0.899774 1.12666 2.5927 + endloop + endfacet + facet normal -0.495029 -0.253213 0.831161 + outer loop + vertex 0.902582 1.12751 2.59481 + vertex 0.903678 1.12206 2.5938 + vertex 0.906098 1.12492 2.59612 + endloop + endfacet + facet normal -0.503995 -0.243581 0.828648 + outer loop + vertex 0.907465 1.12113 2.59583 + vertex 0.906098 1.12492 2.59612 + vertex 0.903678 1.12206 2.5938 + endloop + endfacet + facet normal -0.503869 -0.241722 0.829268 + outer loop + vertex 0.907465 1.12113 2.59583 + vertex 0.903678 1.12206 2.5938 + vertex 0.907543 1.11756 2.59484 + endloop + endfacet + facet normal -0.467844 -0.246359 0.848781 + outer loop + vertex 0.907543 1.11756 2.59484 + vertex 0.909859 1.11879 2.59647 + vertex 0.907465 1.12113 2.59583 + endloop + endfacet + facet normal -0.447555 -0.220721 0.866589 + outer loop + vertex 0.909859 1.11879 2.59647 + vertex 0.91014 1.1227 2.59761 + vertex 0.907465 1.12113 2.59583 + endloop + endfacet + facet normal -0.419112 -0.226459 0.879239 + outer loop + vertex 0.909859 1.11879 2.59647 + vertex 0.913028 1.11796 2.59777 + vertex 0.91014 1.1227 2.59761 + endloop + endfacet + facet normal -0.405059 -0.217599 0.888019 + outer loop + vertex 0.913028 1.11796 2.59777 + vertex 0.914441 1.12178 2.59935 + vertex 0.91014 1.1227 2.59761 + endloop + endfacet + facet normal -0.405426 -0.221434 0.886903 + outer loop + vertex 0.914441 1.12178 2.59935 + vertex 0.912182 1.12694 2.59961 + vertex 0.91014 1.1227 2.59761 + endloop + endfacet + facet normal -0.42012 -0.234335 0.87669 + outer loop + vertex 0.911082 1.11497 2.59604 + vertex 0.913028 1.11796 2.59777 + vertex 0.909859 1.11879 2.59647 + endloop + endfacet + facet normal -0.467809 -0.246424 0.848781 + outer loop + vertex 0.909859 1.11879 2.59647 + vertex 0.907543 1.11756 2.59484 + vertex 0.911082 1.11497 2.59604 + endloop + endfacet + facet normal -0.470642 -0.25173 0.845652 + outer loop + vertex 0.907543 1.11756 2.59484 + vertex 0.908408 1.11215 2.59371 + vertex 0.911082 1.11497 2.59604 + endloop + endfacet + facet normal -0.480283 -0.240736 0.84343 + outer loop + vertex 0.912359 1.11101 2.59564 + vertex 0.911082 1.11497 2.59604 + vertex 0.908408 1.11215 2.59371 + endloop + endfacet + facet normal -0.478963 -0.229759 0.847234 + outer loop + vertex 0.912359 1.11101 2.59564 + vertex 0.908408 1.11215 2.59371 + vertex 0.912214 1.10688 2.59443 + endloop + endfacet + facet normal -0.417123 -0.22414 0.880778 + outer loop + vertex 0.912359 1.11101 2.59564 + vertex 0.915211 1.11279 2.59744 + vertex 0.911082 1.11497 2.59604 + endloop + endfacet + facet normal -0.420786 -0.2338 0.876514 + outer loop + vertex 0.915211 1.11279 2.59744 + vertex 0.913028 1.11796 2.59777 + vertex 0.911082 1.11497 2.59604 + endloop + endfacet + facet normal -0.519488 -0.253357 0.816053 + outer loop + vertex 0.908408 1.11215 2.59371 + vertex 0.907543 1.11756 2.59484 + vertex 0.904735 1.11667 2.59278 + endloop + endfacet + facet normal -0.518098 -0.257064 0.815777 + outer loop + vertex 0.907543 1.11756 2.59484 + vertex 0.903678 1.12206 2.5938 + vertex 0.904735 1.11667 2.59278 + endloop + endfacet + facet normal -0.44505 -0.225159 0.866738 + outer loop + vertex 0.907465 1.12113 2.59583 + vertex 0.91014 1.1227 2.59761 + vertex 0.906098 1.12492 2.59612 + endloop + endfacet + facet normal -0.445768 -0.22705 0.865875 + outer loop + vertex 0.91014 1.1227 2.59761 + vertex 0.907935 1.12786 2.59783 + vertex 0.906098 1.12492 2.59612 + endloop + endfacet + facet normal -0.487475 -0.2386 0.839904 + outer loop + vertex 0.904827 1.12872 2.59646 + vertex 0.902582 1.12751 2.59481 + vertex 0.906098 1.12492 2.59612 + endloop + endfacet + facet normal -0.466345 -0.211101 0.859045 + outer loop + vertex 0.902464 1.13109 2.59574 + vertex 0.905119 1.13264 2.59756 + vertex 0.901145 1.13492 2.59597 + endloop + endfacet + facet normal -0.445813 -0.227014 0.865861 + outer loop + vertex 0.906098 1.12492 2.59612 + vertex 0.907935 1.12786 2.59783 + vertex 0.904827 1.12872 2.59646 + endloop + endfacet + facet normal -0.465922 -0.21002 0.85954 + outer loop + vertex 0.905119 1.13264 2.59756 + vertex 0.90302 1.13787 2.5977 + vertex 0.901145 1.13492 2.59597 + endloop + endfacet + facet normal -0.496836 -0.217304 0.840199 + outer loop + vertex 0.897654 1.13759 2.5946 + vertex 0.89994 1.13879 2.59626 + vertex 0.89759 1.14123 2.5955 + endloop + endfacet + facet normal -0.513183 -0.22541 0.82815 + outer loop + vertex 0.902464 1.13109 2.59574 + vertex 0.901145 1.13492 2.59597 + vertex 0.898708 1.1321 2.59369 + endloop + endfacet + facet normal -0.478142 -0.19928 0.855376 + outer loop + vertex 0.89759 1.14123 2.5955 + vertex 0.900271 1.14276 2.59736 + vertex 0.896304 1.14514 2.5957 + endloop + endfacet + facet normal -0.477861 -0.198592 0.855693 + outer loop + vertex 0.900271 1.14276 2.59736 + vertex 0.89821 1.14807 2.59744 + vertex 0.896304 1.14514 2.5957 + endloop + endfacet + facet normal -0.496336 -0.20316 0.844024 + outer loop + vertex 0.895156 1.14904 2.59596 + vertex 0.892846 1.14787 2.59432 + vertex 0.896304 1.14514 2.5957 + endloop + endfacet + facet normal -0.487868 -0.189068 0.852196 + outer loop + vertex 0.892905 1.15148 2.59521 + vertex 0.895584 1.15287 2.59706 + vertex 0.891896 1.15523 2.59547 + endloop + endfacet + facet normal -0.477937 -0.198527 0.855666 + outer loop + vertex 0.896304 1.14514 2.5957 + vertex 0.89821 1.14807 2.59744 + vertex 0.895156 1.14904 2.59596 + endloop + endfacet + facet normal -0.460906 -0.195488 0.86565 + outer loop + vertex 0.902353 1.147 2.59941 + vertex 0.899607 1.15186 2.59904 + vertex 0.89821 1.14807 2.59744 + endloop + endfacet + facet normal -0.461869 -0.188461 0.866695 + outer loop + vertex 0.89747 1.15713 2.59905 + vertex 0.899607 1.15186 2.59904 + vertex 0.901391 1.15504 2.60068 + endloop + endfacet + facet normal -0.479442 -0.190199 0.856715 + outer loop + vertex 0.897839 1.16134 2.60019 + vertex 0.893945 1.16243 2.59825 + vertex 0.89747 1.15713 2.59905 + endloop + endfacet + facet normal -0.489242 -0.192228 0.8507 + outer loop + vertex 0.895584 1.15287 2.59706 + vertex 0.893958 1.15745 2.59716 + vertex 0.891896 1.15523 2.59547 + endloop + endfacet + facet normal -0.507115 -0.193411 0.839897 + outer loop + vertex 0.892905 1.15148 2.59521 + vertex 0.891896 1.15523 2.59547 + vertex 0.889196 1.15256 2.59322 + endloop + endfacet + facet normal -0.502496 -0.188188 0.84385 + outer loop + vertex 0.887246 1.16203 2.59423 + vertex 0.888941 1.15744 2.59422 + vertex 0.890982 1.15968 2.59593 + endloop + endfacet + facet normal -0.527476 -0.187901 0.82853 + outer loop + vertex 0.88385 1.1624 2.59222 + vertex 0.883844 1.16734 2.59334 + vertex 0.88089 1.16478 2.59088 + endloop + endfacet + facet normal -0.514007 -0.18935 0.836626 + outer loop + vertex 0.887656 1.1661 2.5954 + vertex 0.886733 1.16998 2.59571 + vertex 0.883844 1.16734 2.59334 + endloop + endfacet + facet normal -0.503638 -0.190938 0.842551 + outer loop + vertex 0.890046 1.16356 2.59625 + vertex 0.887246 1.16203 2.59423 + vertex 0.890982 1.15968 2.59593 + endloop + endfacet + facet normal -0.501467 -0.187018 0.844722 + outer loop + vertex 0.887656 1.1661 2.5954 + vertex 0.890468 1.16764 2.59741 + vertex 0.886733 1.16998 2.59571 + endloop + endfacet + facet normal -0.491011 -0.188553 0.850504 + outer loop + vertex 0.890982 1.15968 2.59593 + vertex 0.893945 1.16243 2.59825 + vertex 0.890046 1.16356 2.59625 + endloop + endfacet + facet normal -0.478825 -0.19117 0.856843 + outer loop + vertex 0.8939 1.16741 2.59934 + vertex 0.893945 1.16243 2.59825 + vertex 0.896968 1.16533 2.60059 + endloop + endfacet + facet normal -0.481803 -0.183891 0.856767 + outer loop + vertex 0.892193 1.17196 2.59935 + vertex 0.8939 1.16741 2.59934 + vertex 0.895883 1.16986 2.60098 + endloop + endfacet + facet normal -0.489162 -0.182155 0.85296 + outer loop + vertex 0.892594 1.17602 2.60045 + vertex 0.888749 1.17718 2.59849 + vertex 0.892193 1.17196 2.59935 + endloop + endfacet + facet normal -0.502237 -0.188883 0.843849 + outer loop + vertex 0.890468 1.16764 2.59741 + vertex 0.888804 1.17222 2.59744 + vertex 0.886733 1.16998 2.59571 + endloop + endfacet + facet normal -0.513353 -0.190244 0.836825 + outer loop + vertex 0.883802 1.17224 2.59442 + vertex 0.883844 1.16734 2.59334 + vertex 0.886733 1.16998 2.59571 + endloop + endfacet + facet normal -0.521858 -0.192616 0.831001 + outer loop + vertex 0.883802 1.17224 2.59442 + vertex 0.882112 1.17686 2.59443 + vertex 0.880479 1.17263 2.59243 + endloop + endfacet + facet normal -0.500136 -0.188104 0.84527 + outer loop + vertex 0.88585 1.17446 2.59617 + vertex 0.888749 1.17718 2.59849 + vertex 0.88488 1.17837 2.59647 + endloop + endfacet + facet normal -0.486484 -0.188653 0.853079 + outer loop + vertex 0.888668 1.18215 2.59955 + vertex 0.888749 1.17718 2.59849 + vertex 0.891676 1.17991 2.60077 + endloop + endfacet + facet normal -0.491911 -0.180652 0.851698 + outer loop + vertex 0.886936 1.18679 2.59953 + vertex 0.888668 1.18215 2.59955 + vertex 0.890751 1.18443 2.60123 + endloop + endfacet + facet normal -0.492973 -0.183206 0.850537 + outer loop + vertex 0.889762 1.18835 2.6015 + vertex 0.886936 1.18679 2.59953 + vertex 0.890751 1.18443 2.60123 + endloop + endfacet + facet normal -0.474752 -0.156311 0.866128 + outer loop + vertex 0.889762 1.18835 2.6015 + vertex 0.893727 1.18723 2.60347 + vertex 0.890267 1.19249 2.60253 + endloop + endfacet + facet normal -0.496815 -0.173647 0.850307 + outer loop + vertex 0.893727 1.18723 2.60347 + vertex 0.893666 1.19227 2.60447 + vertex 0.890267 1.19249 2.60253 + endloop + endfacet + facet normal -0.498014 -0.127114 0.857802 + outer loop + vertex 0.893666 1.19227 2.60447 + vertex 0.892248 1.19683 2.60432 + vertex 0.890267 1.19249 2.60253 + endloop + endfacet + facet normal -0.523058 -0.11045 0.84511 + outer loop + vertex 0.890267 1.19249 2.60253 + vertex 0.892248 1.19683 2.60432 + vertex 0.88899 1.19719 2.60235 + endloop + endfacet + facet normal -0.519172 -0.114079 0.847022 + outer loop + vertex 0.88736 1.19091 2.60058 + vertex 0.886628 1.19492 2.60067 + vertex 0.883578 1.1921 2.59842 + endloop + endfacet + facet normal -0.503518 -0.137027 0.85305 + outer loop + vertex 0.883496 1.18714 2.59757 + vertex 0.883578 1.1921 2.59842 + vertex 0.880603 1.18939 2.59623 + endloop + endfacet + facet normal -0.557714 -0.0782146 0.82634 + outer loop + vertex 0.877227 1.19174 2.59438 + vertex 0.879883 1.19323 2.59631 + vertex 0.878 1.19562 2.59527 + endloop + endfacet + facet normal -0.517462 -0.163433 0.839954 + outer loop + vertex 0.880603 1.18939 2.59623 + vertex 0.878563 1.18715 2.59453 + vertex 0.881443 1.18489 2.59587 + endloop + endfacet + facet normal -0.526278 -0.179972 0.831048 + outer loop + vertex 0.878563 1.18715 2.59453 + vertex 0.878617 1.18222 2.5935 + vertex 0.881443 1.18489 2.59587 + endloop + endfacet + facet normal -0.523865 -0.196159 0.828907 + outer loop + vertex 0.875687 1.17967 2.59105 + vertex 0.878617 1.18222 2.5935 + vertex 0.874927 1.18353 2.59148 + endloop + endfacet + facet normal -0.536372 -0.197681 0.820505 + outer loop + vertex 0.874927 1.18353 2.59148 + vertex 0.872528 1.18245 2.58965 + vertex 0.875687 1.17967 2.59105 + endloop + endfacet + facet normal -0.565593 -0.128057 0.814682 + outer loop + vertex 0.872778 1.1859 2.59058 + vertex 0.871896 1.18969 2.59056 + vertex 0.869656 1.18648 2.5885 + endloop + endfacet + facet normal -0.538851 -0.201813 0.81787 + outer loop + vertex 0.872528 1.18245 2.58965 + vertex 0.872773 1.17759 2.58861 + vertex 0.875687 1.17967 2.59105 + endloop + endfacet + facet normal -0.549448 -0.20621 0.809681 + outer loop + vertex 0.870762 1.17438 2.58643 + vertex 0.872773 1.17759 2.58861 + vertex 0.869525 1.17819 2.58656 + endloop + endfacet + facet normal -0.56364 -0.210451 0.798761 + outer loop + vertex 0.869525 1.17819 2.58656 + vertex 0.867155 1.17668 2.58449 + vertex 0.870762 1.17438 2.58643 + endloop + endfacet + facet normal -0.576415 -0.196695 0.793131 + outer loop + vertex 0.867155 1.17668 2.58449 + vertex 0.864169 1.18149 2.58351 + vertex 0.864016 1.1771 2.58231 + endloop + endfacet + facet normal -0.568182 -0.176287 0.803798 + outer loop + vertex 0.867379 1.18051 2.58565 + vertex 0.869689 1.18162 2.58752 + vertex 0.866553 1.1845 2.58594 + endloop + endfacet + facet normal -0.5625 -0.166798 0.809797 + outer loop + vertex 0.869689 1.18162 2.58752 + vertex 0.869656 1.18648 2.5885 + vertex 0.866553 1.1845 2.58594 + endloop + endfacet + facet normal -0.583668 -0.109023 0.80464 + outer loop + vertex 0.868713 1.19192 2.58856 + vertex 0.869656 1.18648 2.5885 + vertex 0.871896 1.18969 2.59056 + endloop + endfacet + facet normal -0.587497 -0.155075 0.794228 + outer loop + vertex 0.864169 1.18149 2.58351 + vertex 0.862833 1.18755 2.58371 + vertex 0.860434 1.1845 2.58134 + endloop + endfacet + facet normal -0.648561 -0.0923051 0.755545 + outer loop + vertex 0.857606 1.18752 2.57955 + vertex 0.859741 1.18852 2.5815 + vertex 0.858083 1.19084 2.58037 + endloop + endfacet + facet normal -0.610499 -0.177323 0.771912 + outer loop + vertex 0.860434 1.1845 2.58134 + vertex 0.857535 1.18258 2.57861 + vertex 0.861152 1.17961 2.58078 + endloop + endfacet + facet normal -0.612684 -0.182068 0.76907 + outer loop + vertex 0.857535 1.18258 2.57861 + vertex 0.858807 1.17718 2.57834 + vertex 0.861152 1.17961 2.58078 + endloop + endfacet + facet normal -0.608673 -0.202137 0.767241 + outer loop + vertex 0.860202 1.17184 2.57804 + vertex 0.858807 1.17718 2.57834 + vertex 0.856462 1.17473 2.57584 + endloop + endfacet + facet normal -0.597815 -0.203026 0.775499 + outer loop + vertex 0.863171 1.16768 2.57924 + vertex 0.860202 1.17184 2.57804 + vertex 0.860427 1.16699 2.57694 + endloop + endfacet + facet normal -0.594817 -0.213343 0.775034 + outer loop + vertex 0.863848 1.16228 2.57827 + vertex 0.863171 1.16768 2.57924 + vertex 0.860427 1.16699 2.57694 + endloop + endfacet + facet normal -0.583124 -0.231885 0.778585 + outer loop + vertex 0.864847 1.15685 2.5774 + vertex 0.863848 1.16228 2.57827 + vertex 0.861336 1.15976 2.57564 + endloop + endfacet + facet normal -0.580948 -0.227497 0.781502 + outer loop + vertex 0.862678 1.15593 2.57552 + vertex 0.864847 1.15685 2.5774 + vertex 0.861336 1.15976 2.57564 + endloop + endfacet + facet normal -0.571398 -0.250199 0.781604 + outer loop + vertex 0.865082 1.15344 2.57649 + vertex 0.864847 1.15685 2.5774 + vertex 0.862678 1.15593 2.57552 + endloop + endfacet + facet normal -0.581091 -0.264127 0.769786 + outer loop + vertex 0.862942 1.15253 2.57455 + vertex 0.865082 1.15344 2.57649 + vertex 0.862678 1.15593 2.57552 + endloop + endfacet + facet normal -0.598281 -0.261894 0.757279 + outer loop + vertex 0.862678 1.15593 2.57552 + vertex 0.859528 1.15682 2.57334 + vertex 0.862942 1.15253 2.57455 + endloop + endfacet + facet normal -0.584894 -0.246939 0.772606 + outer loop + vertex 0.862942 1.15253 2.57455 + vertex 0.859528 1.15682 2.57334 + vertex 0.86019 1.15189 2.57227 + endloop + endfacet + facet normal -0.56717 -0.301571 0.766402 + outer loop + vertex 0.864155 1.1472 2.57336 + vertex 0.862942 1.15253 2.57455 + vertex 0.86019 1.15189 2.57227 + endloop + endfacet + facet normal -0.547397 -0.279666 0.788761 + outer loop + vertex 0.860172 1.14857 2.57108 + vertex 0.864155 1.1472 2.57336 + vertex 0.86019 1.15189 2.57227 + endloop + endfacet + facet normal -0.576386 -0.272874 0.770272 + outer loop + vertex 0.860172 1.14857 2.57108 + vertex 0.86019 1.15189 2.57227 + vertex 0.857833 1.15121 2.57026 + endloop + endfacet + facet normal -0.5874 -0.286841 0.756759 + outer loop + vertex 0.85732 1.14781 2.56858 + vertex 0.860172 1.14857 2.57108 + vertex 0.857833 1.15121 2.57026 + endloop + endfacet + facet normal -0.616435 -0.273365 0.73843 + outer loop + vertex 0.85732 1.14781 2.56858 + vertex 0.857833 1.15121 2.57026 + vertex 0.854929 1.15283 2.56844 + endloop + endfacet + facet normal -0.588863 -0.237006 0.772702 + outer loop + vertex 0.857833 1.15121 2.57026 + vertex 0.86019 1.15189 2.57227 + vertex 0.856848 1.15504 2.57069 + endloop + endfacet + facet normal -0.576644 -0.302088 0.759095 + outer loop + vertex 0.862942 1.15253 2.57455 + vertex 0.864155 1.1472 2.57336 + vertex 0.866439 1.14968 2.57608 + endloop + endfacet + facet normal -0.558854 -0.32342 0.763598 + outer loop + vertex 0.867985 1.14588 2.5756 + vertex 0.866439 1.14968 2.57608 + vertex 0.864155 1.1472 2.57336 + endloop + endfacet + facet normal -0.561846 -0.388385 0.730402 + outer loop + vertex 0.867985 1.14588 2.5756 + vertex 0.864155 1.1472 2.57336 + vertex 0.86886 1.14214 2.57429 + endloop + endfacet + facet normal -0.565957 -0.388252 0.727291 + outer loop + vertex 0.86886 1.14214 2.57429 + vertex 0.87076 1.14355 2.57652 + vertex 0.867985 1.14588 2.5756 + endloop + endfacet + facet normal -0.545914 -0.351335 0.760619 + outer loop + vertex 0.87076 1.14355 2.57652 + vertex 0.8701 1.14689 2.57759 + vertex 0.867985 1.14588 2.5756 + endloop + endfacet + facet normal -0.557852 -0.350957 0.752084 + outer loop + vertex 0.87076 1.14355 2.57652 + vertex 0.874104 1.14292 2.5787 + vertex 0.8701 1.14689 2.57759 + endloop + endfacet + facet normal -0.552034 -0.342853 0.760073 + outer loop + vertex 0.874104 1.14292 2.5787 + vertex 0.872927 1.14734 2.57984 + vertex 0.8701 1.14689 2.57759 + endloop + endfacet + facet normal -0.578459 -0.344555 0.73937 + outer loop + vertex 0.872927 1.14734 2.57984 + vertex 0.874104 1.14292 2.5787 + vertex 0.87629 1.14475 2.58126 + endloop + endfacet + facet normal -0.569005 -0.323068 0.756215 + outer loop + vertex 0.875013 1.14746 2.58146 + vertex 0.872927 1.14734 2.57984 + vertex 0.87629 1.14475 2.58126 + endloop + endfacet + facet normal -0.566378 -0.322007 0.758636 + outer loop + vertex 0.87629 1.14475 2.58126 + vertex 0.877459 1.14775 2.58341 + vertex 0.875013 1.14746 2.58146 + endloop + endfacet + facet normal -0.577344 -0.31417 0.753638 + outer loop + vertex 0.879901 1.14281 2.58322 + vertex 0.877459 1.14775 2.58341 + vertex 0.87629 1.14475 2.58126 + endloop + endfacet + facet normal -0.585095 -0.351935 0.73062 + outer loop + vertex 0.878387 1.14058 2.58094 + vertex 0.879901 1.14281 2.58322 + vertex 0.87629 1.14475 2.58126 + endloop + endfacet + facet normal -0.593178 -0.343747 0.727995 + outer loop + vertex 0.882568 1.13801 2.58313 + vertex 0.879901 1.14281 2.58322 + vertex 0.878387 1.14058 2.58094 + endloop + endfacet + facet normal -0.602269 -0.38127 0.70136 + outer loop + vertex 0.882568 1.13801 2.58313 + vertex 0.878387 1.14058 2.58094 + vertex 0.880024 1.13778 2.58082 + endloop + endfacet + facet normal -0.619101 -0.390279 0.681467 + outer loop + vertex 0.877559 1.13755 2.57845 + vertex 0.880024 1.13778 2.58082 + vertex 0.878387 1.14058 2.58094 + endloop + endfacet + facet normal -0.587924 -0.411201 0.696606 + outer loop + vertex 0.877559 1.13755 2.57845 + vertex 0.878387 1.14058 2.58094 + vertex 0.874104 1.14292 2.5787 + endloop + endfacet + facet normal -0.575941 -0.348037 0.739704 + outer loop + vertex 0.878387 1.14058 2.58094 + vertex 0.87629 1.14475 2.58126 + vertex 0.874104 1.14292 2.5787 + endloop + endfacet + facet normal -0.535656 -0.357717 0.764926 + outer loop + vertex 0.86886 1.14214 2.57429 + vertex 0.864155 1.1472 2.57336 + vertex 0.865412 1.14221 2.57191 + endloop + endfacet + facet normal -0.525682 -0.357271 0.772021 + outer loop + vertex 0.865412 1.14221 2.57191 + vertex 0.864155 1.1472 2.57336 + vertex 0.86169 1.14494 2.57063 + endloop + endfacet + facet normal -0.551341 -0.324958 0.768392 + outer loop + vertex 0.86169 1.14494 2.57063 + vertex 0.864155 1.1472 2.57336 + vertex 0.860172 1.14857 2.57108 + endloop + endfacet + facet normal -0.570825 -0.331006 0.751395 + outer loop + vertex 0.860172 1.14857 2.57108 + vertex 0.85732 1.14781 2.56858 + vertex 0.86169 1.14494 2.57063 + endloop + endfacet + facet normal -0.560506 -0.323913 0.762177 + outer loop + vertex 0.867985 1.14588 2.5756 + vertex 0.8701 1.14689 2.57759 + vertex 0.866439 1.14968 2.57608 + endloop + endfacet + facet normal -0.549475 -0.299885 0.779837 + outer loop + vertex 0.8701 1.14689 2.57759 + vertex 0.868899 1.15206 2.57873 + vertex 0.866439 1.14968 2.57608 + endloop + endfacet + facet normal -0.560297 -0.285941 0.77737 + outer loop + vertex 0.866439 1.14968 2.57608 + vertex 0.868899 1.15206 2.57873 + vertex 0.865082 1.15344 2.57649 + endloop + endfacet + facet normal -0.565111 -0.300947 0.768167 + outer loop + vertex 0.872927 1.14734 2.57984 + vertex 0.868899 1.15206 2.57873 + vertex 0.8701 1.14689 2.57759 + endloop + endfacet + facet normal -0.568281 -0.304542 0.764402 + outer loop + vertex 0.873412 1.15025 2.58136 + vertex 0.868899 1.15206 2.57873 + vertex 0.872927 1.14734 2.57984 + endloop + endfacet + facet normal -0.574017 -0.301894 0.76116 + outer loop + vertex 0.872927 1.14734 2.57984 + vertex 0.875013 1.14746 2.58146 + vertex 0.873412 1.15025 2.58136 + endloop + endfacet + facet normal -0.572312 -0.300859 0.762852 + outer loop + vertex 0.877459 1.14775 2.58341 + vertex 0.873412 1.15025 2.58136 + vertex 0.875013 1.14746 2.58146 + endloop + endfacet + facet normal -0.566396 -0.281759 0.774473 + outer loop + vertex 0.877459 1.14775 2.58341 + vertex 0.87502 1.15265 2.58341 + vertex 0.873412 1.15025 2.58136 + endloop + endfacet + facet normal -0.569467 -0.278716 0.77332 + outer loop + vertex 0.873412 1.15025 2.58136 + vertex 0.87502 1.15265 2.58341 + vertex 0.871262 1.15469 2.58138 + endloop + endfacet + facet normal -0.57753 -0.287302 0.764145 + outer loop + vertex 0.877459 1.14775 2.58341 + vertex 0.878023 1.1511 2.5851 + vertex 0.87502 1.15265 2.58341 + endloop + endfacet + facet normal -0.570828 -0.257368 0.779691 + outer loop + vertex 0.878023 1.1511 2.5851 + vertex 0.876995 1.15491 2.5856 + vertex 0.87502 1.15265 2.58341 + endloop + endfacet + facet normal -0.573276 -0.257774 0.777758 + outer loop + vertex 0.878023 1.1511 2.5851 + vertex 0.880357 1.15189 2.58708 + vertex 0.876995 1.15491 2.5856 + endloop + endfacet + facet normal -0.569756 -0.266968 0.777243 + outer loop + vertex 0.880299 1.14857 2.5859 + vertex 0.880357 1.15189 2.58708 + vertex 0.878023 1.1511 2.5851 + endloop + endfacet + facet normal -0.573543 -0.266023 0.774777 + outer loop + vertex 0.880299 1.14857 2.5859 + vertex 0.884026 1.14733 2.58823 + vertex 0.880357 1.15189 2.58708 + endloop + endfacet + facet normal -0.575501 -0.29336 0.763373 + outer loop + vertex 0.881644 1.14491 2.5855 + vertex 0.884026 1.14733 2.58823 + vertex 0.880299 1.14857 2.5859 + endloop + endfacet + facet normal -0.579787 -0.294538 0.759668 + outer loop + vertex 0.880299 1.14857 2.5859 + vertex 0.877459 1.14775 2.58341 + vertex 0.881644 1.14491 2.5855 + endloop + endfacet + facet normal -0.581416 -0.285745 0.761778 + outer loop + vertex 0.885133 1.14198 2.58707 + vertex 0.884026 1.14733 2.58823 + vertex 0.881644 1.14491 2.5855 + endloop + endfacet + facet normal -0.596199 -0.316056 0.738008 + outer loop + vertex 0.882941 1.14122 2.58497 + vertex 0.885133 1.14198 2.58707 + vertex 0.881644 1.14491 2.5855 + endloop + endfacet + facet normal -0.591735 -0.315061 0.742015 + outer loop + vertex 0.882941 1.14122 2.58497 + vertex 0.881644 1.14491 2.5855 + vertex 0.879901 1.14281 2.58322 + endloop + endfacet + facet normal -0.597238 -0.345921 0.723633 + outer loop + vertex 0.882568 1.13801 2.58313 + vertex 0.882941 1.14122 2.58497 + vertex 0.879901 1.14281 2.58322 + endloop + endfacet + facet normal -0.610532 -0.339685 0.715447 + outer loop + vertex 0.882568 1.13801 2.58313 + vertex 0.885316 1.13867 2.58579 + vertex 0.882941 1.14122 2.58497 + endloop + endfacet + facet normal -0.611054 -0.338319 0.715649 + outer loop + vertex 0.885316 1.13867 2.58579 + vertex 0.882568 1.13801 2.58313 + vertex 0.886858 1.1351 2.58542 + endloop + endfacet + facet normal -0.607688 -0.33722 0.719026 + outer loop + vertex 0.886858 1.1351 2.58542 + vertex 0.889023 1.1373 2.58828 + vertex 0.885316 1.13867 2.58579 + endloop + endfacet + facet normal -0.606747 -0.315739 0.729498 + outer loop + vertex 0.885316 1.13867 2.58579 + vertex 0.889023 1.1373 2.58828 + vertex 0.885133 1.14198 2.58707 + endloop + endfacet + facet normal -0.62164 -0.318855 0.715469 + outer loop + vertex 0.890377 1.13221 2.58719 + vertex 0.889023 1.1373 2.58828 + vertex 0.886858 1.1351 2.58542 + endloop + endfacet + facet normal -0.635749 -0.354304 0.685778 + outer loop + vertex 0.888455 1.13153 2.58506 + vertex 0.890377 1.13221 2.58719 + vertex 0.886858 1.1351 2.58542 + endloop + endfacet + facet normal -0.636066 -0.354411 0.685429 + outer loop + vertex 0.888455 1.13153 2.58506 + vertex 0.886858 1.1351 2.58542 + vertex 0.885424 1.13319 2.5831 + endloop + endfacet + facet normal -0.638616 -0.374755 0.672107 + outer loop + vertex 0.888616 1.12836 2.58344 + vertex 0.888455 1.13153 2.58506 + vertex 0.885424 1.13319 2.5831 + endloop + endfacet + facet normal -0.640808 -0.343099 0.686767 + outer loop + vertex 0.890943 1.12905 2.58613 + vertex 0.890377 1.13221 2.58719 + vertex 0.888455 1.13153 2.58506 + endloop + endfacet + facet normal -0.645887 -0.342516 0.682285 + outer loop + vertex 0.890943 1.12905 2.58613 + vertex 0.894044 1.12808 2.58859 + vertex 0.890377 1.13221 2.58719 + endloop + endfacet + facet normal -0.645829 -0.343667 0.68176 + outer loop + vertex 0.892993 1.12536 2.58622 + vertex 0.894044 1.12808 2.58859 + vertex 0.890943 1.12905 2.58613 + endloop + endfacet + facet normal -0.657473 -0.333753 0.675529 + outer loop + vertex 0.89705 1.12229 2.58865 + vertex 0.894044 1.12808 2.58859 + vertex 0.892993 1.12536 2.58622 + endloop + endfacet + facet normal -0.66053 -0.344472 0.667112 + outer loop + vertex 0.89705 1.12229 2.58865 + vertex 0.892993 1.12536 2.58622 + vertex 0.89461 1.12215 2.58616 + endloop + endfacet + facet normal -0.662234 -0.338583 0.668437 + outer loop + vertex 0.89574 1.11859 2.58548 + vertex 0.89705 1.12229 2.58865 + vertex 0.89461 1.12215 2.58616 + endloop + endfacet + facet normal -0.684258 -0.341001 0.6446 + outer loop + vertex 0.89461 1.12215 2.58616 + vertex 0.891976 1.12266 2.58364 + vertex 0.89574 1.11859 2.58548 + endloop + endfacet + facet normal -0.695857 -0.362904 0.619745 + outer loop + vertex 0.891976 1.12266 2.58364 + vertex 0.893444 1.11859 2.5829 + vertex 0.89574 1.11859 2.58548 + endloop + endfacet + facet normal -0.701944 -0.341115 0.625232 + outer loop + vertex 0.893444 1.11859 2.5829 + vertex 0.894801 1.11495 2.58244 + vertex 0.89574 1.11859 2.58548 + endloop + endfacet + facet normal -0.720921 -0.345076 0.600995 + outer loop + vertex 0.893444 1.11859 2.5829 + vertex 0.892573 1.1168 2.58083 + vertex 0.894801 1.11495 2.58244 + endloop + endfacet + facet normal -0.72262 -0.352838 0.594412 + outer loop + vertex 0.89248 1.11271 2.57829 + vertex 0.894801 1.11495 2.58244 + vertex 0.892573 1.1168 2.58083 + endloop + endfacet + facet normal -0.724066 -0.352015 0.59314 + outer loop + vertex 0.89248 1.11271 2.57829 + vertex 0.892573 1.1168 2.58083 + vertex 0.890202 1.11752 2.57836 + endloop + endfacet + facet normal -0.722212 -0.36497 0.587543 + outer loop + vertex 0.892573 1.1168 2.58083 + vertex 0.891109 1.12016 2.58111 + vertex 0.890202 1.11752 2.57836 + endloop + endfacet + facet normal -0.712798 -0.374154 0.593236 + outer loop + vertex 0.887591 1.12236 2.57827 + vertex 0.890202 1.11752 2.57836 + vertex 0.891109 1.12016 2.58111 + endloop + endfacet + facet normal -0.713223 -0.381906 0.587759 + outer loop + vertex 0.88983 1.12276 2.58125 + vertex 0.887591 1.12236 2.57827 + vertex 0.891109 1.12016 2.58111 + endloop + endfacet + facet normal -0.696553 -0.374993 0.611714 + outer loop + vertex 0.891109 1.12016 2.58111 + vertex 0.891976 1.12266 2.58364 + vertex 0.88983 1.12276 2.58125 + endloop + endfacet + facet normal -0.691089 -0.393835 0.606044 + outer loop + vertex 0.891976 1.12266 2.58364 + vertex 0.888112 1.12553 2.58109 + vertex 0.88983 1.12276 2.58125 + endloop + endfacet + facet normal -0.68954 -0.385363 0.613213 + outer loop + vertex 0.891976 1.12266 2.58364 + vertex 0.888616 1.12836 2.58344 + vertex 0.888112 1.12553 2.58109 + endloop + endfacet + facet normal -0.670894 -0.398662 0.625275 + outer loop + vertex 0.888112 1.12553 2.58109 + vertex 0.888616 1.12836 2.58344 + vertex 0.886284 1.12837 2.58094 + endloop + endfacet + facet normal -0.7044 -0.40338 0.584042 + outer loop + vertex 0.887591 1.12236 2.57827 + vertex 0.88983 1.12276 2.58125 + vertex 0.888112 1.12553 2.58109 + endloop + endfacet + facet normal -0.742727 -0.320212 0.588066 + outer loop + vertex 0.894801 1.11495 2.58244 + vertex 0.89248 1.11271 2.57829 + vertex 0.896162 1.10945 2.58116 + endloop + endfacet + facet normal -0.72146 -0.320871 0.613627 + outer loop + vertex 0.897596 1.11353 2.58498 + vertex 0.894801 1.11495 2.58244 + vertex 0.896162 1.10945 2.58116 + endloop + endfacet + facet normal -0.745626 -0.296557 0.596738 + outer loop + vertex 0.898688 1.11006 2.58462 + vertex 0.897596 1.11353 2.58498 + vertex 0.896162 1.10945 2.58116 + endloop + endfacet + facet normal -0.748755 -0.28724 0.597377 + outer loop + vertex 0.898688 1.11006 2.58462 + vertex 0.896162 1.10945 2.58116 + vertex 0.899168 1.10668 2.5836 + endloop + endfacet + facet normal -0.75204 -0.300055 0.586859 + outer loop + vertex 0.89775 1.10382 2.58032 + vertex 0.899168 1.10668 2.5836 + vertex 0.896162 1.10945 2.58116 + endloop + endfacet + facet normal -0.759293 -0.290975 0.582073 + outer loop + vertex 0.900606 1.10234 2.58331 + vertex 0.899168 1.10668 2.5836 + vertex 0.89775 1.10382 2.58032 + endloop + endfacet + facet normal -0.759262 -0.279598 0.587661 + outer loop + vertex 0.899418 1.09955 2.58044 + vertex 0.900606 1.10234 2.58331 + vertex 0.89775 1.10382 2.58032 + endloop + endfacet + facet normal -0.781803 -0.289408 0.552292 + outer loop + vertex 0.899418 1.09955 2.58044 + vertex 0.89775 1.10382 2.58032 + vertex 0.896536 1.09921 2.57618 + endloop + endfacet + facet normal -0.787463 -0.26911 0.554511 + outer loop + vertex 0.899418 1.09955 2.58044 + vertex 0.896536 1.09921 2.57618 + vertex 0.899264 1.09628 2.57864 + endloop + endfacet + facet normal -0.779873 -0.274031 0.562766 + outer loop + vertex 0.899264 1.09628 2.57864 + vertex 0.900536 1.09718 2.58083 + vertex 0.899418 1.09955 2.58044 + endloop + endfacet + facet normal -0.777247 -0.279765 0.563577 + outer loop + vertex 0.900536 1.09718 2.58083 + vertex 0.899264 1.09628 2.57864 + vertex 0.901336 1.09487 2.58079 + endloop + endfacet + facet normal -0.77723 -0.279509 0.563728 + outer loop + vertex 0.899264 1.09628 2.57864 + vertex 0.900366 1.09242 2.57824 + vertex 0.901336 1.09487 2.58079 + endloop + endfacet + facet normal -0.772237 -0.285497 0.567575 + outer loop + vertex 0.902348 1.09179 2.58062 + vertex 0.901336 1.09487 2.58079 + vertex 0.900366 1.09242 2.57824 + endloop + endfacet + facet normal -0.771996 -0.28771 0.566785 + outer loop + vertex 0.902191 1.08799 2.57848 + vertex 0.902348 1.09179 2.58062 + vertex 0.900366 1.09242 2.57824 + endloop + endfacet + facet normal -0.778477 -0.290952 0.556167 + outer loop + vertex 0.902191 1.08799 2.57848 + vertex 0.900366 1.09242 2.57824 + vertex 0.89942 1.08948 2.57538 + endloop + endfacet + facet normal -0.778647 -0.271022 0.565912 + outer loop + vertex 0.902191 1.08799 2.57848 + vertex 0.89942 1.08948 2.57538 + vertex 0.90053 1.08715 2.57579 + endloop + endfacet + facet normal -0.791126 -0.280959 0.543307 + outer loop + vertex 0.899332 1.08612 2.57351 + vertex 0.90053 1.08715 2.57579 + vertex 0.89942 1.08948 2.57538 + endloop + endfacet + facet normal -0.804679 -0.271966 0.527756 + outer loop + vertex 0.89942 1.08948 2.57538 + vertex 0.896659 1.08905 2.57095 + vertex 0.899332 1.08612 2.57351 + endloop + endfacet + facet normal -0.806385 -0.27912 0.521378 + outer loop + vertex 0.898102 1.08355 2.57023 + vertex 0.899332 1.08612 2.57351 + vertex 0.896659 1.08905 2.57095 + endloop + endfacet + facet normal -0.801391 -0.283253 0.52682 + outer loop + vertex 0.89942 1.08948 2.57538 + vertex 0.897847 1.09364 2.57522 + vertex 0.896659 1.08905 2.57095 + endloop + endfacet + facet normal -0.802563 -0.281943 0.525738 + outer loop + vertex 0.897847 1.09364 2.57522 + vertex 0.895401 1.0947 2.57206 + vertex 0.896659 1.08905 2.57095 + endloop + endfacet + facet normal -0.822072 -0.280363 0.495575 + outer loop + vertex 0.895401 1.0947 2.57206 + vertex 0.894026 1.09206 2.56828 + vertex 0.896659 1.08905 2.57095 + endloop + endfacet + facet normal -0.82238 -0.281817 0.494237 + outer loop + vertex 0.894026 1.09206 2.56828 + vertex 0.894414 1.0882 2.56673 + vertex 0.896659 1.08905 2.57095 + endloop + endfacet + facet normal -0.8158 -0.290259 0.50022 + outer loop + vertex 0.894026 1.09206 2.56828 + vertex 0.895401 1.0947 2.57206 + vertex 0.893594 1.09577 2.56973 + endloop + endfacet + facet normal -0.802751 -0.279787 0.526602 + outer loop + vertex 0.896536 1.09921 2.57618 + vertex 0.895401 1.0947 2.57206 + vertex 0.897847 1.09364 2.57522 + endloop + endfacet + facet normal -0.799391 -0.28349 0.529724 + outer loop + vertex 0.89431 1.09814 2.57225 + vertex 0.895401 1.0947 2.57206 + vertex 0.896536 1.09921 2.57618 + endloop + endfacet + facet normal -0.792302 -0.301293 0.530547 + outer loop + vertex 0.893794 1.10184 2.57358 + vertex 0.89431 1.09814 2.57225 + vertex 0.896536 1.09921 2.57618 + endloop + endfacet + facet normal -0.791469 -0.296568 0.534439 + outer loop + vertex 0.89516 1.10477 2.57723 + vertex 0.893794 1.10184 2.57358 + vertex 0.896536 1.09921 2.57618 + endloop + endfacet + facet normal -0.773717 -0.320103 0.546714 + outer loop + vertex 0.893794 1.10184 2.57358 + vertex 0.89516 1.10477 2.57723 + vertex 0.893162 1.10553 2.57485 + endloop + endfacet + facet normal -0.792303 -0.31497 0.522541 + outer loop + vertex 0.893162 1.10553 2.57485 + vertex 0.891248 1.10416 2.57112 + vertex 0.893794 1.10184 2.57358 + endloop + endfacet + facet normal -0.793043 -0.320654 0.517942 + outer loop + vertex 0.892554 1.09906 2.56996 + vertex 0.893794 1.10184 2.57358 + vertex 0.891248 1.10416 2.57112 + endloop + endfacet + facet normal -0.773325 -0.323387 0.545334 + outer loop + vertex 0.893775 1.10826 2.57734 + vertex 0.893162 1.10553 2.57485 + vertex 0.89516 1.10477 2.57723 + endloop + endfacet + facet normal -0.756881 -0.317617 0.571184 + outer loop + vertex 0.893775 1.10826 2.57734 + vertex 0.89516 1.10477 2.57723 + vertex 0.896162 1.10945 2.58116 + endloop + endfacet + facet normal -0.746945 -0.339368 0.571754 + outer loop + vertex 0.89248 1.11271 2.57829 + vertex 0.893775 1.10826 2.57734 + vertex 0.896162 1.10945 2.58116 + endloop + endfacet + facet normal -0.774023 -0.301731 0.556639 + outer loop + vertex 0.896162 1.10945 2.58116 + vertex 0.89516 1.10477 2.57723 + vertex 0.89775 1.10382 2.58032 + endloop + endfacet + facet normal -0.789778 -0.278112 0.546721 + outer loop + vertex 0.89942 1.08948 2.57538 + vertex 0.900366 1.09242 2.57824 + vertex 0.897847 1.09364 2.57522 + endloop + endfacet + facet normal -0.789635 -0.281163 0.545365 + outer loop + vertex 0.900366 1.09242 2.57824 + vertex 0.899264 1.09628 2.57864 + vertex 0.897847 1.09364 2.57522 + endloop + endfacet + facet normal -0.749589 -0.279874 0.599823 + outer loop + vertex 0.902348 1.09179 2.58062 + vertex 0.90326 1.09361 2.58261 + vertex 0.901336 1.09487 2.58079 + endloop + endfacet + facet normal -0.748604 -0.270389 0.605378 + outer loop + vertex 0.90326 1.09361 2.58261 + vertex 0.902361 1.09751 2.58324 + vertex 0.901336 1.09487 2.58079 + endloop + endfacet + facet normal -0.748461 -0.270544 0.605485 + outer loop + vertex 0.901336 1.09487 2.58079 + vertex 0.902361 1.09751 2.58324 + vertex 0.900536 1.09718 2.58083 + endloop + endfacet + facet normal -0.753151 -0.254097 0.606794 + outer loop + vertex 0.902361 1.09751 2.58324 + vertex 0.899418 1.09955 2.58044 + vertex 0.900536 1.09718 2.58083 + endloop + endfacet + facet normal -0.790425 -0.28002 0.544809 + outer loop + vertex 0.897847 1.09364 2.57522 + vertex 0.899264 1.09628 2.57864 + vertex 0.896536 1.09921 2.57618 + endloop + endfacet + facet normal -0.774515 -0.296926 0.558535 + outer loop + vertex 0.89775 1.10382 2.58032 + vertex 0.89516 1.10477 2.57723 + vertex 0.896536 1.09921 2.57618 + endloop + endfacet + facet normal -0.756616 -0.282696 0.589589 + outer loop + vertex 0.902361 1.09751 2.58324 + vertex 0.900606 1.10234 2.58331 + vertex 0.899418 1.09955 2.58044 + endloop + endfacet + facet normal -0.7071 -0.289432 0.645166 + outer loop + vertex 0.898688 1.11006 2.58462 + vertex 0.900345 1.11157 2.58711 + vertex 0.897596 1.11353 2.58498 + endloop + endfacet + facet normal -0.705902 -0.283427 0.649131 + outer loop + vertex 0.900345 1.11157 2.58711 + vertex 0.899658 1.11623 2.5884 + vertex 0.897596 1.11353 2.58498 + endloop + endfacet + facet normal -0.682253 -0.314976 0.659788 + outer loop + vertex 0.897596 1.11353 2.58498 + vertex 0.899658 1.11623 2.5884 + vertex 0.89574 1.11859 2.58548 + endloop + endfacet + facet normal -0.683036 -0.320739 0.656192 + outer loop + vertex 0.899658 1.11623 2.5884 + vertex 0.89705 1.12229 2.58865 + vertex 0.89574 1.11859 2.58548 + endloop + endfacet + facet normal -0.721511 -0.324655 0.611573 + outer loop + vertex 0.89574 1.11859 2.58548 + vertex 0.894801 1.11495 2.58244 + vertex 0.897596 1.11353 2.58498 + endloop + endfacet + facet normal -0.707232 -0.360213 0.608333 + outer loop + vertex 0.892573 1.1168 2.58083 + vertex 0.893444 1.11859 2.5829 + vertex 0.891109 1.12016 2.58111 + endloop + endfacet + facet normal -0.707719 -0.364548 0.605176 + outer loop + vertex 0.893444 1.11859 2.5829 + vertex 0.891976 1.12266 2.58364 + vertex 0.891109 1.12016 2.58111 + endloop + endfacet + facet normal -0.682058 -0.354805 0.63946 + outer loop + vertex 0.891976 1.12266 2.58364 + vertex 0.89461 1.12215 2.58616 + vertex 0.892993 1.12536 2.58622 + endloop + endfacet + facet normal -0.665289 -0.369831 0.648549 + outer loop + vertex 0.891976 1.12266 2.58364 + vertex 0.892993 1.12536 2.58622 + vertex 0.888616 1.12836 2.58344 + endloop + endfacet + facet normal -0.661859 -0.353047 0.661287 + outer loop + vertex 0.892993 1.12536 2.58622 + vertex 0.890943 1.12905 2.58613 + vertex 0.888616 1.12836 2.58344 + endloop + endfacet + facet normal -0.654952 -0.369106 0.659393 + outer loop + vertex 0.888616 1.12836 2.58344 + vertex 0.890943 1.12905 2.58613 + vertex 0.888455 1.13153 2.58506 + endloop + endfacet + facet normal -0.626416 -0.3192 0.711136 + outer loop + vertex 0.892884 1.13267 2.5896 + vertex 0.889023 1.1373 2.58828 + vertex 0.890377 1.13221 2.58719 + endloop + endfacet + facet normal -0.627419 -0.316174 0.711604 + outer loop + vertex 0.894044 1.12808 2.58859 + vertex 0.892884 1.13267 2.5896 + vertex 0.890377 1.13221 2.58719 + endloop + endfacet + facet normal -0.61009 -0.315184 0.726945 + outer loop + vertex 0.892884 1.13267 2.5896 + vertex 0.894044 1.12808 2.58859 + vertex 0.896314 1.12971 2.59119 + endloop + endfacet + facet normal -0.623111 -0.293678 0.724904 + outer loop + vertex 0.897448 1.12591 2.59063 + vertex 0.896314 1.12971 2.59119 + vertex 0.894044 1.12808 2.58859 + endloop + endfacet + facet normal -0.629412 -0.318822 0.708656 + outer loop + vertex 0.89705 1.12229 2.58865 + vertex 0.897448 1.12591 2.59063 + vertex 0.894044 1.12808 2.58859 + endloop + endfacet + facet normal -0.582882 -0.286895 0.760223 + outer loop + vertex 0.897448 1.12591 2.59063 + vertex 0.899774 1.12666 2.5927 + vertex 0.896314 1.12971 2.59119 + endloop + endfacet + facet normal -0.620498 -0.372078 0.690319 + outer loop + vertex 0.882568 1.13801 2.58313 + vertex 0.885424 1.13319 2.5831 + vertex 0.886858 1.1351 2.58542 + endloop + endfacet + facet normal -0.588216 -0.319134 0.743071 + outer loop + vertex 0.877459 1.14775 2.58341 + vertex 0.879901 1.14281 2.58322 + vertex 0.881644 1.14491 2.5855 + endloop + endfacet + facet normal -0.595235 -0.318318 0.737814 + outer loop + vertex 0.885316 1.13867 2.58579 + vertex 0.885133 1.14198 2.58707 + vertex 0.882941 1.14122 2.58497 + endloop + endfacet + facet normal -0.591687 -0.286115 0.753688 + outer loop + vertex 0.887825 1.14263 2.58943 + vertex 0.884026 1.14733 2.58823 + vertex 0.885133 1.14198 2.58707 + endloop + endfacet + facet normal -0.588713 -0.294786 0.752674 + outer loop + vertex 0.889023 1.1373 2.58828 + vertex 0.887825 1.14263 2.58943 + vertex 0.885133 1.14198 2.58707 + endloop + endfacet + facet normal -0.583768 -0.294526 0.756617 + outer loop + vertex 0.887825 1.14263 2.58943 + vertex 0.889023 1.1373 2.58828 + vertex 0.891312 1.13967 2.59097 + endloop + endfacet + facet normal -0.601362 -0.271633 0.751385 + outer loop + vertex 0.892584 1.13587 2.59061 + vertex 0.891312 1.13967 2.59097 + vertex 0.889023 1.1373 2.58828 + endloop + endfacet + facet normal -0.603296 -0.290892 0.742574 + outer loop + vertex 0.892584 1.13587 2.59061 + vertex 0.889023 1.1373 2.58828 + vertex 0.892884 1.13267 2.5896 + endloop + endfacet + facet normal -0.565138 -0.262385 0.782159 + outer loop + vertex 0.892584 1.13587 2.59061 + vertex 0.894817 1.13673 2.59251 + vertex 0.891312 1.13967 2.59097 + endloop + endfacet + facet normal -0.583506 -0.284531 0.760633 + outer loop + vertex 0.877459 1.14775 2.58341 + vertex 0.880299 1.14857 2.5859 + vertex 0.878023 1.1511 2.5851 + endloop + endfacet + facet normal -0.564743 -0.276438 0.777591 + outer loop + vertex 0.873412 1.15025 2.58136 + vertex 0.871262 1.15469 2.58138 + vertex 0.868899 1.15206 2.57873 + endloop + endfacet + facet normal -0.573051 -0.266378 0.77502 + outer loop + vertex 0.867623 1.15749 2.57965 + vertex 0.868899 1.15206 2.57873 + vertex 0.871262 1.15469 2.58138 + endloop + endfacet + facet normal -0.569817 -0.259242 0.779809 + outer loop + vertex 0.869756 1.15845 2.58153 + vertex 0.867623 1.15749 2.57965 + vertex 0.871262 1.15469 2.58138 + endloop + endfacet + facet normal -0.561366 -0.25614 0.786931 + outer loop + vertex 0.871262 1.15469 2.58138 + vertex 0.872982 1.15772 2.58359 + vertex 0.869756 1.15845 2.58153 + endloop + endfacet + facet normal -0.568626 -0.265919 0.778429 + outer loop + vertex 0.868899 1.15206 2.57873 + vertex 0.867623 1.15749 2.57965 + vertex 0.864847 1.15685 2.5774 + endloop + endfacet + facet normal -0.57009 -0.288597 0.769226 + outer loop + vertex 0.865082 1.15344 2.57649 + vertex 0.862942 1.15253 2.57455 + vertex 0.866439 1.14968 2.57608 + endloop + endfacet + facet normal -0.556422 -0.251913 0.791792 + outer loop + vertex 0.865082 1.15344 2.57649 + vertex 0.868899 1.15206 2.57873 + vertex 0.864847 1.15685 2.5774 + endloop + endfacet + facet normal -0.61215 -0.21344 0.761391 + outer loop + vertex 0.857337 1.16275 2.57331 + vertex 0.860152 1.16366 2.57583 + vertex 0.858117 1.16627 2.57492 + endloop + endfacet + facet normal -0.597175 -0.232756 0.767598 + outer loop + vertex 0.862678 1.15593 2.57552 + vertex 0.861336 1.15976 2.57564 + vertex 0.859528 1.15682 2.57334 + endloop + endfacet + facet normal -0.594475 -0.246647 0.765353 + outer loop + vertex 0.86019 1.15189 2.57227 + vertex 0.859528 1.15682 2.57334 + vertex 0.856848 1.15504 2.57069 + endloop + endfacet + facet normal -0.608964 -0.240308 0.75592 + outer loop + vertex 0.857833 1.15121 2.57026 + vertex 0.856848 1.15504 2.57069 + vertex 0.854929 1.15283 2.56844 + endloop + endfacet + facet normal -0.636824 -0.206659 0.742797 + outer loop + vertex 0.852971 1.16231 2.56958 + vertex 0.850214 1.16652 2.56839 + vertex 0.850258 1.1619 2.56714 + endloop + endfacet + facet normal -0.62267 -0.209022 0.75405 + outer loop + vertex 0.857337 1.16275 2.57331 + vertex 0.855479 1.16775 2.57316 + vertex 0.853812 1.16528 2.5711 + endloop + endfacet + facet normal -0.619246 -0.203169 0.758457 + outer loop + vertex 0.854165 1.17238 2.57333 + vertex 0.855479 1.16775 2.57316 + vertex 0.857448 1.17 2.57537 + endloop + endfacet + facet normal -0.626129 -0.198535 0.75402 + outer loop + vertex 0.854165 1.17238 2.57333 + vertex 0.852711 1.17763 2.57351 + vertex 0.850706 1.17459 2.57104 + endloop + endfacet + facet normal -0.636119 -0.167688 0.753149 + outer loop + vertex 0.852593 1.18233 2.57445 + vertex 0.852711 1.17763 2.57351 + vertex 0.855446 1.17957 2.57625 + endloop + endfacet + facet normal -0.641329 -0.151132 0.752235 + outer loop + vertex 0.849606 1.17845 2.57111 + vertex 0.849988 1.18171 2.57209 + vertex 0.847775 1.18095 2.57005 + endloop + endfacet + facet normal -0.653106 -0.165374 0.738988 + outer loop + vertex 0.846907 1.17752 2.56852 + vertex 0.849606 1.17845 2.57111 + vertex 0.847775 1.18095 2.57005 + endloop + endfacet + facet normal -0.671751 -0.143242 0.726796 + outer loop + vertex 0.842697 1.17708 2.56467 + vertex 0.844587 1.17727 2.56646 + vertex 0.843599 1.18006 2.56609 + endloop + endfacet + facet normal -0.661948 -0.185078 0.726341 + outer loop + vertex 0.842731 1.17262 2.56357 + vertex 0.842697 1.17708 2.56467 + vertex 0.840063 1.17674 2.56219 + endloop + endfacet + facet normal -0.637106 -0.19348 0.746097 + outer loop + vertex 0.848617 1.17203 2.56856 + vertex 0.846907 1.17752 2.56852 + vertex 0.84531 1.17435 2.56633 + endloop + endfacet + facet normal -0.634541 -0.206943 0.744669 + outer loop + vertex 0.848617 1.17203 2.56856 + vertex 0.850214 1.16652 2.56839 + vertex 0.85216 1.16974 2.57094 + endloop + endfacet + facet normal -0.641616 -0.205665 0.738939 + outer loop + vertex 0.850258 1.1619 2.56714 + vertex 0.850214 1.16652 2.56839 + vertex 0.847411 1.16484 2.56548 + endloop + endfacet + facet normal -0.641854 -0.206075 0.738618 + outer loop + vertex 0.848059 1.16113 2.56501 + vertex 0.850258 1.1619 2.56714 + vertex 0.847411 1.16484 2.56548 + endloop + endfacet + facet normal -0.644043 -0.210211 0.735541 + outer loop + vertex 0.84731 1.15761 2.56335 + vertex 0.849989 1.15867 2.566 + vertex 0.848059 1.16113 2.56501 + endloop + endfacet + facet normal -0.637418 -0.216995 0.739332 + outer loop + vertex 0.849645 1.15152 2.56357 + vertex 0.84731 1.15761 2.56335 + vertex 0.845706 1.15434 2.56101 + endloop + endfacet + facet normal -0.6174 -0.248133 0.746489 + outer loop + vertex 0.852976 1.14709 2.56486 + vertex 0.849645 1.15152 2.56357 + vertex 0.850182 1.14666 2.5624 + endloop + endfacet + facet normal -0.594197 -0.328543 0.734159 + outer loop + vertex 0.8542 1.142 2.56357 + vertex 0.852976 1.14709 2.56486 + vertex 0.850182 1.14666 2.5624 + endloop + endfacet + facet normal -0.558891 -0.287154 0.777935 + outer loop + vertex 0.850063 1.14348 2.56114 + vertex 0.8542 1.142 2.56357 + vertex 0.850182 1.14666 2.5624 + endloop + endfacet + facet normal -0.598269 -0.328669 0.730788 + outer loop + vertex 0.852976 1.14709 2.56486 + vertex 0.8542 1.142 2.56357 + vertex 0.856273 1.14457 2.56642 + endloop + endfacet + facet normal -0.601063 -0.33577 0.725246 + outer loop + vertex 0.854874 1.14744 2.56659 + vertex 0.852976 1.14709 2.56486 + vertex 0.856273 1.14457 2.56642 + endloop + endfacet + facet normal -0.623474 -0.265097 0.73553 + outer loop + vertex 0.852976 1.14709 2.56486 + vertex 0.854874 1.14744 2.56659 + vertex 0.853428 1.15026 2.56638 + endloop + endfacet + facet normal -0.629943 -0.262042 0.731099 + outer loop + vertex 0.853428 1.15026 2.56638 + vertex 0.849645 1.15152 2.56357 + vertex 0.852976 1.14709 2.56486 + endloop + endfacet + facet normal -0.628389 -0.2318 0.742561 + outer loop + vertex 0.853428 1.15026 2.56638 + vertex 0.851361 1.1548 2.56605 + vertex 0.849645 1.15152 2.56357 + endloop + endfacet + facet normal -0.625872 -0.230472 0.745096 + outer loop + vertex 0.853428 1.15026 2.56638 + vertex 0.854929 1.15283 2.56844 + vertex 0.851361 1.1548 2.56605 + endloop + endfacet + facet normal -0.593653 -0.261908 0.760908 + outer loop + vertex 0.85732 1.14781 2.56858 + vertex 0.854929 1.15283 2.56844 + vertex 0.853428 1.15026 2.56638 + endloop + endfacet + facet normal -0.58824 -0.244381 0.770877 + outer loop + vertex 0.85732 1.14781 2.56858 + vertex 0.853428 1.15026 2.56638 + vertex 0.854874 1.14744 2.56659 + endloop + endfacet + facet normal -0.566843 -0.321034 0.7587 + outer loop + vertex 0.856273 1.14457 2.56642 + vertex 0.85732 1.14781 2.56858 + vertex 0.854874 1.14744 2.56659 + endloop + endfacet + facet normal -0.5991 -0.275326 0.751847 + outer loop + vertex 0.850063 1.14348 2.56114 + vertex 0.850182 1.14666 2.5624 + vertex 0.847816 1.14607 2.5603 + endloop + endfacet + facet normal -0.608515 -0.287461 0.739646 + outer loop + vertex 0.847245 1.14277 2.55855 + vertex 0.850063 1.14348 2.56114 + vertex 0.847816 1.14607 2.5603 + endloop + endfacet + facet normal -0.646779 -0.219762 0.73033 + outer loop + vertex 0.843634 1.15229 2.55857 + vertex 0.845073 1.14768 2.55846 + vertex 0.846958 1.14976 2.56075 + endloop + endfacet + facet normal -0.668076 -0.215961 0.712064 + outer loop + vertex 0.838022 1.15263 2.55348 + vertex 0.839891 1.14669 2.55344 + vertex 0.841692 1.1499 2.5561 + endloop + endfacet + facet normal -0.675931 -0.20618 0.707536 + outer loop + vertex 0.838022 1.15263 2.55348 + vertex 0.837886 1.15715 2.55467 + vertex 0.835358 1.15645 2.55205 + endloop + endfacet + facet normal -0.658639 -0.208039 0.723129 + outer loop + vertex 0.843634 1.15229 2.55857 + vertex 0.842133 1.15738 2.55867 + vertex 0.840466 1.15454 2.55633 + endloop + endfacet + facet normal -0.669364 -0.204806 0.714147 + outer loop + vertex 0.837886 1.15715 2.55467 + vertex 0.839764 1.15737 2.5565 + vertex 0.838768 1.16007 2.55634 + endloop + endfacet + facet normal -0.673041 -0.202156 0.711442 + outer loop + vertex 0.838768 1.16007 2.55634 + vertex 0.835281 1.16116 2.55335 + vertex 0.837886 1.15715 2.55467 + endloop + endfacet + facet normal -0.673313 -0.210037 0.708896 + outer loop + vertex 0.838768 1.16007 2.55634 + vertex 0.83719 1.16458 2.55617 + vertex 0.835281 1.16116 2.55335 + endloop + endfacet + facet normal -0.676915 -0.206136 0.706607 + outer loop + vertex 0.833768 1.16689 2.55357 + vertex 0.835281 1.16116 2.55335 + vertex 0.83719 1.16458 2.55617 + endloop + endfacet + facet normal -0.677684 -0.209091 0.705 + outer loop + vertex 0.835716 1.16947 2.55621 + vertex 0.833768 1.16689 2.55357 + vertex 0.83719 1.16458 2.55617 + endloop + endfacet + facet normal -0.669207 -0.206595 0.713779 + outer loop + vertex 0.83719 1.16458 2.55617 + vertex 0.838973 1.16729 2.55863 + vertex 0.835716 1.16947 2.55621 + endloop + endfacet + facet normal -0.667683 -0.20094 0.716814 + outer loop + vertex 0.838973 1.16729 2.55863 + vertex 0.837133 1.17274 2.55844 + vertex 0.835716 1.16947 2.55621 + endloop + endfacet + facet normal -0.674187 -0.195067 0.712335 + outer loop + vertex 0.835716 1.16947 2.55621 + vertex 0.837133 1.17274 2.55844 + vertex 0.834719 1.17261 2.55612 + endloop + endfacet + facet normal -0.69395 -0.201899 0.691137 + outer loop + vertex 0.834719 1.17261 2.55612 + vertex 0.832178 1.17254 2.55355 + vertex 0.835716 1.16947 2.55621 + endloop + endfacet + facet normal -0.682099 -0.141288 0.717481 + outer loop + vertex 0.837133 1.17274 2.55844 + vertex 0.833632 1.17557 2.55567 + vertex 0.834719 1.17261 2.55612 + endloop + endfacet + facet normal -0.664578 -0.206646 0.718077 + outer loop + vertex 0.838768 1.16007 2.55634 + vertex 0.84051 1.16244 2.55863 + vertex 0.83719 1.16458 2.55617 + endloop + endfacet + facet normal -0.655799 -0.205948 0.726301 + outer loop + vertex 0.842133 1.15738 2.55867 + vertex 0.844704 1.15743 2.561 + vertex 0.843725 1.16039 2.56096 + endloop + endfacet + facet normal -0.650994 -0.207296 0.730229 + outer loop + vertex 0.843725 1.16039 2.56096 + vertex 0.84548 1.16268 2.56317 + vertex 0.842289 1.16493 2.56097 + endloop + endfacet + facet normal -0.665646 -0.21083 0.715868 + outer loop + vertex 0.84051 1.16244 2.55863 + vertex 0.838973 1.16729 2.55863 + vertex 0.83719 1.16458 2.55617 + endloop + endfacet + facet normal -0.651827 -0.209946 0.728728 + outer loop + vertex 0.84548 1.16268 2.56317 + vertex 0.844189 1.16736 2.56336 + vertex 0.842289 1.16493 2.56097 + endloop + endfacet + facet normal -0.647386 -0.207598 0.733345 + outer loop + vertex 0.842731 1.17262 2.56357 + vertex 0.844189 1.16736 2.56336 + vertex 0.846405 1.1696 2.56596 + endloop + endfacet + facet normal -0.667681 -0.200939 0.716817 + outer loop + vertex 0.837133 1.17274 2.55844 + vertex 0.838973 1.16729 2.55863 + vertex 0.84085 1.16971 2.56106 + endloop + endfacet + facet normal -0.652775 -0.175609 0.736916 + outer loop + vertex 0.839722 1.17357 2.56113 + vertex 0.842731 1.17262 2.56357 + vertex 0.840063 1.17674 2.56219 + endloop + endfacet + facet normal -0.672728 -0.124039 0.729418 + outer loop + vertex 0.842697 1.17708 2.56467 + vertex 0.840266 1.18133 2.56315 + vertex 0.840063 1.17674 2.56219 + endloop + endfacet + facet normal -0.697476 -0.126797 0.705302 + outer loop + vertex 0.83791 1.17609 2.56006 + vertex 0.837464 1.17969 2.56026 + vertex 0.835421 1.17772 2.55789 + endloop + endfacet + facet normal -0.68809 -0.157733 0.708275 + outer loop + vertex 0.837133 1.17274 2.55844 + vertex 0.835421 1.17772 2.55789 + vertex 0.833632 1.17557 2.55567 + endloop + endfacet + facet normal -0.701123 -0.151418 0.696777 + outer loop + vertex 0.832178 1.17254 2.55355 + vertex 0.834719 1.17261 2.55612 + vertex 0.833632 1.17557 2.55567 + endloop + endfacet + facet normal -0.69026 -0.192047 0.697609 + outer loop + vertex 0.832178 1.17254 2.55355 + vertex 0.833768 1.16689 2.55357 + vertex 0.835716 1.16947 2.55621 + endloop + endfacet + facet normal -0.708739 -0.181489 0.681727 + outer loop + vertex 0.827268 1.17244 2.54852 + vertex 0.828498 1.16727 2.54842 + vertex 0.830532 1.16939 2.5511 + endloop + endfacet + facet normal -0.727272 -0.126368 0.674616 + outer loop + vertex 0.827268 1.17244 2.54852 + vertex 0.825628 1.17704 2.54761 + vertex 0.824111 1.17465 2.54553 + endloop + endfacet + facet normal -0.756352 -0.0852984 0.64858 + outer loop + vertex 0.824111 1.17465 2.54553 + vertex 0.825628 1.17704 2.54761 + vertex 0.822668 1.179 2.54442 + endloop + endfacet + facet normal -0.734676 -0.183272 0.653194 + outer loop + vertex 0.825148 1.1721 2.54623 + vertex 0.823483 1.17113 2.54408 + vertex 0.82588 1.16921 2.54624 + endloop + endfacet + facet normal -0.764037 -0.0903264 0.638819 + outer loop + vertex 0.824111 1.17465 2.54553 + vertex 0.822668 1.179 2.54442 + vertex 0.821034 1.17461 2.54184 + endloop + endfacet + facet normal -0.733384 -0.178552 0.655947 + outer loop + vertex 0.823483 1.17113 2.54408 + vertex 0.824114 1.1666 2.54356 + vertex 0.82588 1.16921 2.54624 + endloop + endfacet + facet normal -0.719842 -0.200964 0.66441 + outer loop + vertex 0.824114 1.1666 2.54356 + vertex 0.825304 1.16211 2.54349 + vertex 0.82674 1.16498 2.54591 + endloop + endfacet + facet normal -0.714013 -0.207488 0.668681 + outer loop + vertex 0.82757 1.16148 2.54571 + vertex 0.82674 1.16498 2.54591 + vertex 0.825304 1.16211 2.54349 + endloop + endfacet + facet normal -0.703417 -0.209743 0.679126 + outer loop + vertex 0.828846 1.16343 2.54763 + vertex 0.82757 1.16148 2.54571 + vertex 0.829747 1.15991 2.54748 + endloop + endfacet + facet normal -0.695033 -0.207998 0.688234 + outer loop + vertex 0.828846 1.16343 2.54763 + vertex 0.829747 1.15991 2.54748 + vertex 0.831382 1.16383 2.55032 + endloop + endfacet + facet normal -0.685167 -0.207984 0.698061 + outer loop + vertex 0.835281 1.16116 2.55335 + vertex 0.833768 1.16689 2.55357 + vertex 0.831382 1.16383 2.55032 + endloop + endfacet + facet normal -0.676141 -0.205457 0.707545 + outer loop + vertex 0.837886 1.15715 2.55467 + vertex 0.835281 1.16116 2.55335 + vertex 0.835358 1.15645 2.55205 + endloop + endfacet + facet normal -0.675764 -0.205982 0.707753 + outer loop + vertex 0.835224 1.15325 2.55099 + vertex 0.838022 1.15263 2.55348 + vertex 0.835358 1.15645 2.55205 + endloop + endfacet + facet normal -0.685181 -0.210022 0.697437 + outer loop + vertex 0.835224 1.15325 2.55099 + vertex 0.833488 1.15177 2.54884 + vertex 0.83625 1.14957 2.55089 + endloop + endfacet + facet normal -0.696257 -0.203974 0.688201 + outer loop + vertex 0.833448 1.15512 2.5498 + vertex 0.83266 1.15862 2.55004 + vertex 0.830838 1.15495 2.5471 + endloop + endfacet + facet normal -0.693702 -0.207405 0.689754 + outer loop + vertex 0.834265 1.14743 2.54832 + vertex 0.833488 1.15177 2.54884 + vertex 0.831388 1.14971 2.54611 + endloop + endfacet + facet normal -0.699162 -0.207211 0.684278 + outer loop + vertex 0.831388 1.14971 2.54611 + vertex 0.829365 1.14695 2.54321 + vertex 0.832405 1.14508 2.54575 + endloop + endfacet + facet normal -0.704412 -0.200591 0.680857 + outer loop + vertex 0.827026 1.15741 2.54388 + vertex 0.828344 1.15189 2.54362 + vertex 0.830838 1.15495 2.5471 + endloop + endfacet + facet normal -0.732569 -0.199194 0.650895 + outer loop + vertex 0.825541 1.15365 2.54118 + vertex 0.823629 1.15177 2.53845 + vertex 0.826095 1.14872 2.54029 + endloop + endfacet + facet normal -0.778859 -0.221996 0.586598 + outer loop + vertex 0.817271 1.16231 2.53383 + vertex 0.818772 1.157 2.53381 + vertex 0.82088 1.15952 2.53756 + endloop + endfacet + facet normal -0.779126 -0.223673 0.585605 + outer loop + vertex 0.819513 1.16466 2.53771 + vertex 0.817271 1.16231 2.53383 + vertex 0.82088 1.15952 2.53756 + endloop + endfacet +endsolid diff --git a/noether_examples/meshes/outputsBackDoor/output_3.stl b/noether_examples/meshes/outputsBackDoor/output_3.stl new file mode 100644 index 00000000..14601fea --- /dev/null +++ b/noether_examples/meshes/outputsBackDoor/output_3.stl @@ -0,0 +1,5721 @@ +solid ascii + facet normal -0.56302 -0.0908504 0.821435 + outer loop + vertex 0.903419 1.31494 2.62621 + vertex 0.902157 1.31942 2.62584 + vertex 0.899962 1.31641 2.624 + endloop + endfacet + facet normal -0.568397 -0.113435 0.814897 + outer loop + vertex 0.903419 1.31494 2.62621 + vertex 0.899962 1.31641 2.624 + vertex 0.901759 1.31149 2.62457 + endloop + endfacet + facet normal -0.550003 -0.104692 0.828575 + outer loop + vertex 0.898689 1.32123 2.62377 + vertex 0.899962 1.31641 2.624 + vertex 0.902157 1.31942 2.62584 + endloop + endfacet + facet normal -0.546044 -0.0924952 0.832635 + outer loop + vertex 0.90126 1.32413 2.62578 + vertex 0.898689 1.32123 2.62377 + vertex 0.902157 1.31942 2.62584 + endloop + endfacet + facet normal -0.627869 -0.108927 0.770659 + outer loop + vertex 0.902157 1.31942 2.62584 + vertex 0.904371 1.32182 2.62799 + vertex 0.90126 1.32413 2.62578 + endloop + endfacet + facet normal -0.625411 -0.102905 0.773481 + outer loop + vertex 0.904371 1.32182 2.62799 + vertex 0.903732 1.3266 2.6281 + vertex 0.90126 1.32413 2.62578 + endloop + endfacet + facet normal -0.625861 -0.1022 0.77321 + outer loop + vertex 0.90126 1.32413 2.62578 + vertex 0.903732 1.3266 2.6281 + vertex 0.900696 1.32907 2.62597 + endloop + endfacet + facet normal -0.54036 -0.0949533 0.836059 + outer loop + vertex 0.900696 1.32907 2.62597 + vertex 0.897959 1.32618 2.62388 + vertex 0.90126 1.32413 2.62578 + endloop + endfacet + facet normal -0.537807 -0.0982907 0.837319 + outer loop + vertex 0.897424 1.33129 2.62413 + vertex 0.897959 1.32618 2.62388 + vertex 0.900696 1.32907 2.62597 + endloop + endfacet + facet normal -0.534988 -0.0920485 0.83983 + outer loop + vertex 0.900199 1.33424 2.62622 + vertex 0.897424 1.33129 2.62413 + vertex 0.900696 1.32907 2.62597 + endloop + endfacet + facet normal -0.624269 -0.0975275 0.775098 + outer loop + vertex 0.900696 1.32907 2.62597 + vertex 0.903261 1.33173 2.62837 + vertex 0.900199 1.33424 2.62622 + endloop + endfacet + facet normal -0.62096 -0.0904685 0.778604 + outer loop + vertex 0.903261 1.33173 2.62837 + vertex 0.902669 1.33753 2.62858 + vertex 0.900199 1.33424 2.62622 + endloop + endfacet + facet normal -0.623627 -0.087213 0.776842 + outer loop + vertex 0.900199 1.33424 2.62622 + vertex 0.902669 1.33753 2.62858 + vertex 0.899681 1.33858 2.62629 + endloop + endfacet + facet normal -0.524555 -0.0765935 0.847924 + outer loop + vertex 0.899681 1.33858 2.62629 + vertex 0.896772 1.33692 2.62435 + vertex 0.900199 1.33424 2.62622 + endloop + endfacet + facet normal -0.530031 -0.0641848 0.845546 + outer loop + vertex 0.896772 1.33692 2.62435 + vertex 0.899681 1.33858 2.62629 + vertex 0.897836 1.34109 2.62533 + endloop + endfacet + facet normal -0.565824 -0.100916 0.818327 + outer loop + vertex 0.899681 1.33858 2.62629 + vertex 0.900361 1.34263 2.62726 + vertex 0.897836 1.34109 2.62533 + endloop + endfacet + facet normal -0.622722 -0.081749 0.778161 + outer loop + vertex 0.899681 1.33858 2.62629 + vertex 0.902669 1.33753 2.62858 + vertex 0.900361 1.34263 2.62726 + endloop + endfacet + facet normal -0.642613 -0.095372 0.760232 + outer loop + vertex 0.902669 1.33753 2.62858 + vertex 0.90322 1.34198 2.6296 + vertex 0.900361 1.34263 2.62726 + endloop + endfacet + facet normal -0.642274 -0.0908922 0.761067 + outer loop + vertex 0.90322 1.34198 2.6296 + vertex 0.90223 1.34629 2.62928 + vertex 0.900361 1.34263 2.62726 + endloop + endfacet + facet normal -0.629933 -0.102046 0.769916 + outer loop + vertex 0.900361 1.34263 2.62726 + vertex 0.90223 1.34629 2.62928 + vertex 0.899243 1.34705 2.62694 + endloop + endfacet + facet normal -0.629197 -0.0941913 0.771517 + outer loop + vertex 0.90223 1.34629 2.62928 + vertex 0.899866 1.35118 2.62795 + vertex 0.899243 1.34705 2.62694 + endloop + endfacet + facet normal -0.654311 -0.112808 0.747764 + outer loop + vertex 0.903403 1.34974 2.63083 + vertex 0.899866 1.35118 2.62795 + vertex 0.90223 1.34629 2.62928 + endloop + endfacet + facet normal -0.648283 -0.078993 0.757291 + outer loop + vertex 0.903403 1.34974 2.63083 + vertex 0.902273 1.35432 2.63034 + vertex 0.899866 1.35118 2.62795 + endloop + endfacet + facet normal -0.644161 -0.0843856 0.760221 + outer loop + vertex 0.899136 1.35661 2.62793 + vertex 0.899866 1.35118 2.62795 + vertex 0.902273 1.35432 2.63034 + endloop + endfacet + facet normal -0.638952 -0.0712444 0.76594 + outer loop + vertex 0.901668 1.35916 2.63028 + vertex 0.899136 1.35661 2.62793 + vertex 0.902273 1.35432 2.63034 + endloop + endfacet + facet normal -0.681375 -0.0769586 0.727878 + outer loop + vertex 0.902273 1.35432 2.63034 + vertex 0.904532 1.35694 2.63273 + vertex 0.901668 1.35916 2.63028 + endloop + endfacet + facet normal -0.680065 -0.0735277 0.729456 + outer loop + vertex 0.904532 1.35694 2.63273 + vertex 0.904095 1.36172 2.6328 + vertex 0.901668 1.35916 2.63028 + endloop + endfacet + facet normal -0.679536 -0.0744256 0.729857 + outer loop + vertex 0.901668 1.35916 2.63028 + vertex 0.904095 1.36172 2.6328 + vertex 0.901292 1.36412 2.63044 + endloop + endfacet + facet normal -0.635373 -0.0722876 0.768814 + outer loop + vertex 0.901292 1.36412 2.63044 + vertex 0.898714 1.3616 2.62807 + vertex 0.901668 1.35916 2.63028 + endloop + endfacet + facet normal -0.632647 -0.0767873 0.770624 + outer loop + vertex 0.898302 1.36673 2.62824 + vertex 0.898714 1.3616 2.62807 + vertex 0.901292 1.36412 2.63044 + endloop + endfacet + facet normal -0.63096 -0.0734238 0.772333 + outer loop + vertex 0.900968 1.36925 2.63066 + vertex 0.898302 1.36673 2.62824 + vertex 0.901292 1.36412 2.63044 + endloop + endfacet + facet normal -0.679631 -0.074638 0.729747 + outer loop + vertex 0.901292 1.36412 2.63044 + vertex 0.90381 1.36661 2.63304 + vertex 0.900968 1.36925 2.63066 + endloop + endfacet + facet normal -0.678851 -0.0729969 0.730638 + outer loop + vertex 0.90381 1.36661 2.63304 + vertex 0.903602 1.37157 2.63334 + vertex 0.900968 1.36925 2.63066 + endloop + endfacet + facet normal -0.68313 -0.0644509 0.727447 + outer loop + vertex 0.900968 1.36925 2.63066 + vertex 0.903602 1.37157 2.63334 + vertex 0.900841 1.37429 2.63099 + endloop + endfacet + facet normal -0.629009 -0.0661482 0.774579 + outer loop + vertex 0.900841 1.37429 2.63099 + vertex 0.897731 1.37243 2.6283 + vertex 0.900968 1.36925 2.63066 + endloop + endfacet + facet normal -0.638029 -0.0427871 0.768823 + outer loop + vertex 0.898553 1.37689 2.62923 + vertex 0.897731 1.37243 2.6283 + vertex 0.900841 1.37429 2.63099 + endloop + endfacet + facet normal -0.651212 -0.0628148 0.756292 + outer loop + vertex 0.900703 1.37908 2.63127 + vertex 0.898553 1.37689 2.62923 + vertex 0.900841 1.37429 2.63099 + endloop + endfacet + facet normal -0.689639 -0.0618939 0.721504 + outer loop + vertex 0.900841 1.37429 2.63099 + vertex 0.903382 1.37654 2.63361 + vertex 0.900703 1.37908 2.63127 + endloop + endfacet + facet normal -0.692171 -0.0672349 0.718595 + outer loop + vertex 0.903382 1.37654 2.63361 + vertex 0.903114 1.38152 2.63382 + vertex 0.900703 1.37908 2.63127 + endloop + endfacet + facet normal -0.692635 -0.0663898 0.718226 + outer loop + vertex 0.900703 1.37908 2.63127 + vertex 0.903114 1.38152 2.63382 + vertex 0.900409 1.38398 2.63144 + endloop + endfacet + facet normal -0.643064 -0.0649647 0.763052 + outer loop + vertex 0.900409 1.38398 2.63144 + vertex 0.897928 1.38111 2.6291 + vertex 0.900703 1.37908 2.63127 + endloop + endfacet + facet normal -0.64018 -0.06913 0.765108 + outer loop + vertex 0.89756 1.38612 2.62925 + vertex 0.897928 1.38111 2.6291 + vertex 0.900409 1.38398 2.63144 + endloop + endfacet + facet normal -0.63845 -0.0649843 0.766915 + outer loop + vertex 0.900262 1.3891 2.63175 + vertex 0.89756 1.38612 2.62925 + vertex 0.900409 1.38398 2.63144 + endloop + endfacet + facet normal -0.692209 -0.0636158 0.718888 + outer loop + vertex 0.900409 1.38398 2.63144 + vertex 0.902877 1.38654 2.63404 + vertex 0.900262 1.3891 2.63175 + endloop + endfacet + facet normal -0.692136 -0.0634668 0.718971 + outer loop + vertex 0.902877 1.38654 2.63404 + vertex 0.902785 1.39132 2.63437 + vertex 0.900262 1.3891 2.63175 + endloop + endfacet + facet normal -0.695131 -0.057242 0.7166 + outer loop + vertex 0.900262 1.3891 2.63175 + vertex 0.902785 1.39132 2.63437 + vertex 0.900447 1.39468 2.63237 + endloop + endfacet + facet normal -0.638211 -0.0648008 0.767129 + outer loop + vertex 0.900447 1.39468 2.63237 + vertex 0.897346 1.39135 2.62951 + vertex 0.900262 1.3891 2.63175 + endloop + endfacet + facet normal -0.638353 -0.06513 0.766984 + outer loop + vertex 0.897346 1.39135 2.62951 + vertex 0.89756 1.38612 2.62925 + vertex 0.900262 1.3891 2.63175 + endloop + endfacet + facet normal -0.643609 -0.0564604 0.763269 + outer loop + vertex 0.896878 1.3969 2.62953 + vertex 0.897346 1.39135 2.62951 + vertex 0.900447 1.39468 2.63237 + endloop + endfacet + facet normal -0.635343 -0.0326307 0.77154 + outer loop + vertex 0.899842 1.39968 2.63209 + vertex 0.896878 1.3969 2.62953 + vertex 0.900447 1.39468 2.63237 + endloop + endfacet + facet normal -0.707864 -0.0452032 0.7049 + outer loop + vertex 0.902466 1.39854 2.63465 + vertex 0.899842 1.39968 2.63209 + vertex 0.900447 1.39468 2.63237 + endloop + endfacet + facet normal -0.702327 -0.0511123 0.710018 + outer loop + vertex 0.903141 1.395 2.63506 + vertex 0.902466 1.39854 2.63465 + vertex 0.900447 1.39468 2.63237 + endloop + endfacet + facet normal -0.709779 -0.0534187 0.702396 + outer loop + vertex 0.903141 1.395 2.63506 + vertex 0.905208 1.39682 2.63729 + vertex 0.902466 1.39854 2.63465 + endloop + endfacet + facet normal -0.714966 -0.0724297 0.695397 + outer loop + vertex 0.905208 1.39682 2.63729 + vertex 0.904179 1.4011 2.63668 + vertex 0.902466 1.39854 2.63465 + endloop + endfacet + facet normal -0.726625 -0.0561763 0.684734 + outer loop + vertex 0.902466 1.39854 2.63465 + vertex 0.904179 1.4011 2.63668 + vertex 0.901749 1.40337 2.63428 + endloop + endfacet + facet normal -0.726172 -0.0550917 0.685302 + outer loop + vertex 0.904179 1.4011 2.63668 + vertex 0.904719 1.40562 2.63761 + vertex 0.901749 1.40337 2.63428 + endloop + endfacet + facet normal -0.722925 -0.0633987 0.688012 + outer loop + vertex 0.901749 1.40337 2.63428 + vertex 0.904719 1.40562 2.63761 + vertex 0.901907 1.40865 2.63493 + endloop + endfacet + facet normal -0.71318 -0.0649197 0.697969 + outer loop + vertex 0.901907 1.40865 2.63493 + vertex 0.899427 1.40675 2.63223 + vertex 0.901749 1.40337 2.63428 + endloop + endfacet + facet normal -0.714074 -0.0661601 0.696937 + outer loop + vertex 0.899427 1.40675 2.63223 + vertex 0.899266 1.40313 2.63172 + vertex 0.901749 1.40337 2.63428 + endloop + endfacet + facet normal -0.715919 -0.0449037 0.696738 + outer loop + vertex 0.899266 1.40313 2.63172 + vertex 0.899842 1.39968 2.63209 + vertex 0.901749 1.40337 2.63428 + endloop + endfacet + facet normal -0.713704 -0.0636347 0.697551 + outer loop + vertex 0.899308 1.4115 2.63254 + vertex 0.899427 1.40675 2.63223 + vertex 0.901907 1.40865 2.63493 + endloop + endfacet + facet normal -0.711722 -0.0598454 0.699907 + outer loop + vertex 0.901718 1.41374 2.63518 + vertex 0.899308 1.4115 2.63254 + vertex 0.901907 1.40865 2.63493 + endloop + endfacet + facet normal -0.72277 -0.0597113 0.688504 + outer loop + vertex 0.901907 1.40865 2.63493 + vertex 0.90428 1.4112 2.63765 + vertex 0.901718 1.41374 2.63518 + endloop + endfacet + facet normal -0.720196 -0.054062 0.691661 + outer loop + vertex 0.90428 1.4112 2.63765 + vertex 0.904021 1.41628 2.63778 + vertex 0.901718 1.41374 2.63518 + endloop + endfacet + facet normal -0.722179 -0.0504317 0.689866 + outer loop + vertex 0.901718 1.41374 2.63518 + vertex 0.904021 1.41628 2.63778 + vertex 0.901515 1.41877 2.63533 + endloop + endfacet + facet normal -0.715011 -0.0503712 0.697297 + outer loop + vertex 0.901515 1.41877 2.63533 + vertex 0.899134 1.41645 2.63272 + vertex 0.901718 1.41374 2.63518 + endloop + endfacet + facet normal -0.716755 -0.0468417 0.69575 + outer loop + vertex 0.898939 1.42144 2.63286 + vertex 0.899134 1.41645 2.63272 + vertex 0.901515 1.41877 2.63533 + endloop + endfacet + facet normal -0.715326 -0.0439247 0.697409 + outer loop + vertex 0.901341 1.42378 2.63547 + vertex 0.898939 1.42144 2.63286 + vertex 0.901515 1.41877 2.63533 + endloop + endfacet + facet normal -0.722002 -0.0439668 0.690493 + outer loop + vertex 0.901515 1.41877 2.63533 + vertex 0.903841 1.42128 2.63793 + vertex 0.901341 1.42378 2.63547 + endloop + endfacet + facet normal -0.720023 -0.0397215 0.692812 + outer loop + vertex 0.903841 1.42128 2.63793 + vertex 0.903706 1.42627 2.63807 + vertex 0.901341 1.42378 2.63547 + endloop + endfacet + facet normal -0.719369 -0.0409787 0.693419 + outer loop + vertex 0.901341 1.42378 2.63547 + vertex 0.903706 1.42627 2.63807 + vertex 0.901191 1.42879 2.63561 + endloop + endfacet + facet normal -0.71499 -0.0409738 0.697932 + outer loop + vertex 0.901191 1.42879 2.63561 + vertex 0.898763 1.42645 2.63299 + vertex 0.901341 1.42378 2.63547 + endloop + endfacet + facet normal -0.715729 -0.0394536 0.697263 + outer loop + vertex 0.898627 1.43147 2.63313 + vertex 0.898763 1.42645 2.63299 + vertex 0.901191 1.42879 2.63561 + endloop + endfacet + facet normal -0.71638 -0.0407657 0.696518 + outer loop + vertex 0.901044 1.43379 2.63575 + vertex 0.898627 1.43147 2.63313 + vertex 0.901191 1.42879 2.63561 + endloop + endfacet + facet normal -0.717668 -0.0407657 0.695191 + outer loop + vertex 0.901191 1.42879 2.63561 + vertex 0.903575 1.43127 2.63822 + vertex 0.901044 1.43379 2.63575 + endloop + endfacet + facet normal -0.716091 -0.0374013 0.697004 + outer loop + vertex 0.903575 1.43127 2.63822 + vertex 0.903443 1.4363 2.63835 + vertex 0.901044 1.43379 2.63575 + endloop + endfacet + facet normal -0.71437 -0.0406733 0.698585 + outer loop + vertex 0.901044 1.43379 2.63575 + vertex 0.903443 1.4363 2.63835 + vertex 0.900892 1.43878 2.63589 + endloop + endfacet + facet normal -0.719364 -0.040687 0.69344 + outer loop + vertex 0.900892 1.43878 2.63589 + vertex 0.898503 1.43646 2.63327 + vertex 0.901044 1.43379 2.63575 + endloop + endfacet + facet normal -0.720872 -0.0375648 0.69205 + outer loop + vertex 0.898369 1.44144 2.6334 + vertex 0.898503 1.43646 2.63327 + vertex 0.900892 1.43878 2.63589 + endloop + endfacet + facet normal -0.721532 -0.0389021 0.691288 + outer loop + vertex 0.90074 1.44377 2.63601 + vertex 0.898369 1.44144 2.6334 + vertex 0.900892 1.43878 2.63589 + endloop + endfacet + facet normal -0.713275 -0.0388616 0.699806 + outer loop + vertex 0.900892 1.43878 2.63589 + vertex 0.903301 1.44133 2.63848 + vertex 0.90074 1.44377 2.63601 + endloop + endfacet + facet normal -0.711509 -0.0349888 0.701805 + outer loop + vertex 0.903301 1.44133 2.63848 + vertex 0.903172 1.44635 2.6386 + vertex 0.90074 1.44377 2.63601 + endloop + endfacet + facet normal -0.711321 -0.0353408 0.701978 + outer loop + vertex 0.90074 1.44377 2.63601 + vertex 0.903172 1.44635 2.6386 + vertex 0.900602 1.44877 2.63612 + endloop + endfacet + facet normal -0.723309 -0.0353948 0.689617 + outer loop + vertex 0.900602 1.44877 2.63612 + vertex 0.898234 1.44642 2.63352 + vertex 0.90074 1.44377 2.63601 + endloop + endfacet + facet normal -0.724815 -0.0322924 0.688186 + outer loop + vertex 0.898111 1.4514 2.63362 + vertex 0.898234 1.44642 2.63352 + vertex 0.900602 1.44877 2.63612 + endloop + endfacet + facet normal -0.725054 -0.0327807 0.687911 + outer loop + vertex 0.900477 1.45375 2.63623 + vertex 0.898111 1.4514 2.63362 + vertex 0.900602 1.44877 2.63612 + endloop + endfacet + facet normal -0.709837 -0.0327315 0.703605 + outer loop + vertex 0.900602 1.44877 2.63612 + vertex 0.903053 1.45135 2.63872 + vertex 0.900477 1.45375 2.63623 + endloop + endfacet + facet normal -0.708029 -0.028717 0.705599 + outer loop + vertex 0.903053 1.45135 2.63872 + vertex 0.902956 1.45635 2.63882 + vertex 0.900477 1.45375 2.63623 + endloop + endfacet + facet normal -0.708629 -0.0275871 0.705042 + outer loop + vertex 0.900477 1.45375 2.63623 + vertex 0.902956 1.45635 2.63882 + vertex 0.900376 1.45874 2.63632 + endloop + endfacet + facet normal -0.727612 -0.0276025 0.685434 + outer loop + vertex 0.900376 1.45874 2.63632 + vertex 0.898009 1.45639 2.63371 + vertex 0.900477 1.45375 2.63623 + endloop + endfacet + facet normal -0.72896 -0.024773 0.684108 + outer loop + vertex 0.897919 1.46137 2.6338 + vertex 0.898009 1.45639 2.63371 + vertex 0.900376 1.45874 2.63632 + endloop + endfacet + facet normal -0.727666 -0.0221612 0.685574 + outer loop + vertex 0.900302 1.46374 2.6364 + vertex 0.897919 1.46137 2.6338 + vertex 0.900376 1.45874 2.63632 + endloop + endfacet + facet normal -0.707049 -0.0222042 0.706816 + outer loop + vertex 0.900376 1.45874 2.63632 + vertex 0.902891 1.46134 2.63892 + vertex 0.900302 1.46374 2.6364 + endloop + endfacet + facet normal -0.705471 -0.0187335 0.708491 + outer loop + vertex 0.902891 1.46134 2.63892 + vertex 0.902846 1.46637 2.63901 + vertex 0.900302 1.46374 2.6364 + endloop + endfacet + facet normal -0.704227 -0.0210912 0.709661 + outer loop + vertex 0.900302 1.46374 2.6364 + vertex 0.902846 1.46637 2.63901 + vertex 0.900234 1.46874 2.63648 + endloop + endfacet + facet normal -0.728847 -0.0210167 0.684354 + outer loop + vertex 0.900234 1.46874 2.63648 + vertex 0.897848 1.46636 2.63387 + vertex 0.900302 1.46374 2.6364 + endloop + endfacet + facet normal -0.729784 -0.0190413 0.683412 + outer loop + vertex 0.897788 1.47135 2.63395 + vertex 0.897848 1.46636 2.63387 + vertex 0.900234 1.46874 2.63648 + endloop + endfacet + facet normal -0.732274 -0.0241196 0.680582 + outer loop + vertex 0.900158 1.47373 2.63658 + vertex 0.897788 1.47135 2.63395 + vertex 0.900234 1.46874 2.63648 + endloop + endfacet + facet normal -0.706063 -0.0242453 0.707733 + outer loop + vertex 0.900234 1.46874 2.63648 + vertex 0.902756 1.47137 2.63909 + vertex 0.900158 1.47373 2.63658 + endloop + endfacet + facet normal -0.710162 -0.0335324 0.70324 + outer loop + vertex 0.902756 1.47137 2.63909 + vertex 0.902615 1.47629 2.63918 + vertex 0.900158 1.47373 2.63658 + endloop + endfacet + facet normal -0.711859 -0.0302973 0.701668 + outer loop + vertex 0.900158 1.47373 2.63658 + vertex 0.902615 1.47629 2.63918 + vertex 0.900105 1.47873 2.63674 + endloop + endfacet + facet normal -0.737046 -0.0297125 0.675189 + outer loop + vertex 0.900105 1.47873 2.63674 + vertex 0.897737 1.47635 2.63405 + vertex 0.900158 1.47373 2.63658 + endloop + endfacet + facet normal -0.740874 -0.0215281 0.671299 + outer loop + vertex 0.897708 1.48139 2.63418 + vertex 0.897737 1.47635 2.63405 + vertex 0.900105 1.47873 2.63674 + endloop + endfacet + facet normal -0.740688 -0.0211508 0.671516 + outer loop + vertex 0.900265 1.48419 2.63709 + vertex 0.897708 1.48139 2.63418 + vertex 0.900105 1.47873 2.63674 + endloop + endfacet + facet normal -0.723433 -0.0228352 0.690017 + outer loop + vertex 0.900105 1.47873 2.63674 + vertex 0.902518 1.48093 2.63935 + vertex 0.900265 1.48419 2.63709 + endloop + endfacet + facet normal -0.71452 -0.0100927 0.699542 + outer loop + vertex 0.902947 1.48486 2.63984 + vertex 0.900265 1.48419 2.63709 + vertex 0.902518 1.48093 2.63935 + endloop + endfacet + facet normal -0.715464 -0.00258977 0.698644 + outer loop + vertex 0.902947 1.48486 2.63984 + vertex 0.902149 1.48926 2.63904 + vertex 0.900265 1.48419 2.63709 + endloop + endfacet + facet normal -0.720624 0.00137516 0.693324 + outer loop + vertex 0.902149 1.48926 2.63904 + vertex 0.899417 1.48861 2.6362 + vertex 0.900265 1.48419 2.63709 + endloop + endfacet + facet normal -0.742877 -0.00772639 0.669383 + outer loop + vertex 0.899417 1.48861 2.6362 + vertex 0.897574 1.4863 2.63413 + vertex 0.900265 1.48419 2.63709 + endloop + endfacet + facet normal -0.740927 -0.0111821 0.671492 + outer loop + vertex 0.897466 1.49099 2.63409 + vertex 0.897574 1.4863 2.63413 + vertex 0.899417 1.48861 2.6362 + endloop + endfacet + facet normal -0.741925 -0.0130102 0.670357 + outer loop + vertex 0.899738 1.49274 2.63664 + vertex 0.897466 1.49099 2.63409 + vertex 0.899417 1.48861 2.6362 + endloop + endfacet + facet normal -0.741928 -0.0130018 0.670353 + outer loop + vertex 0.897498 1.49574 2.63422 + vertex 0.897466 1.49099 2.63409 + vertex 0.899738 1.49274 2.63664 + endloop + endfacet + facet normal -0.74253 -0.0140055 0.669667 + outer loop + vertex 0.899813 1.49764 2.63682 + vertex 0.897498 1.49574 2.63422 + vertex 0.899738 1.49274 2.63664 + endloop + endfacet + facet normal -0.713538 -0.01562 0.700442 + outer loop + vertex 0.899738 1.49274 2.63664 + vertex 0.902321 1.49492 2.63932 + vertex 0.899813 1.49764 2.63682 + endloop + endfacet + facet normal -0.712089 -0.0128798 0.701971 + outer loop + vertex 0.899813 1.49764 2.63682 + vertex 0.902321 1.49492 2.63932 + vertex 0.902342 1.49999 2.63943 + endloop + endfacet + facet normal -0.71365 -0.00949327 0.700438 + outer loop + vertex 0.899813 1.49764 2.63682 + vertex 0.902342 1.49999 2.63943 + vertex 0.899811 1.50261 2.63689 + endloop + endfacet + facet normal -0.742777 -0.00910058 0.669477 + outer loop + vertex 0.899811 1.50261 2.63689 + vertex 0.89749 1.50068 2.63429 + vertex 0.899813 1.49764 2.63682 + endloop + endfacet + facet normal -0.744082 -0.00562713 0.668065 + outer loop + vertex 0.897465 1.50568 2.6343 + vertex 0.89749 1.50068 2.63429 + vertex 0.899811 1.50261 2.63689 + endloop + endfacet + facet normal -0.743477 -0.00458915 0.668746 + outer loop + vertex 0.89979 1.50759 2.6369 + vertex 0.897465 1.50568 2.6343 + vertex 0.899811 1.50261 2.63689 + endloop + endfacet + facet normal -0.712293 -0.00452538 0.701868 + outer loop + vertex 0.899811 1.50261 2.63689 + vertex 0.902339 1.50497 2.63947 + vertex 0.89979 1.50759 2.6369 + endloop + endfacet + facet normal -0.712269 -0.00447854 0.701892 + outer loop + vertex 0.89979 1.50759 2.6369 + vertex 0.902339 1.50497 2.63947 + vertex 0.902315 1.50994 2.63948 + endloop + endfacet + facet normal -0.712665 -0.00361466 0.701496 + outer loop + vertex 0.89979 1.50759 2.6369 + vertex 0.902315 1.50994 2.63948 + vertex 0.899762 1.51257 2.6369 + endloop + endfacet + facet normal -0.744861 -0.00380956 0.667208 + outer loop + vertex 0.899762 1.51257 2.6369 + vertex 0.897443 1.51068 2.6343 + vertex 0.89979 1.50759 2.6369 + endloop + endfacet + facet normal -0.745536 -0.00196001 0.666463 + outer loop + vertex 0.897429 1.51567 2.63429 + vertex 0.897443 1.51068 2.6343 + vertex 0.899762 1.51257 2.6369 + endloop + endfacet + facet normal -0.745922 -0.00261516 0.666028 + outer loop + vertex 0.899743 1.51755 2.63689 + vertex 0.897429 1.51567 2.63429 + vertex 0.899762 1.51257 2.6369 + endloop + endfacet + facet normal -0.713785 -0.00248137 0.700361 + outer loop + vertex 0.899762 1.51257 2.6369 + vertex 0.902283 1.5149 2.63947 + vertex 0.899743 1.51755 2.63689 + endloop + endfacet + facet normal -0.713241 -0.00141918 0.700918 + outer loop + vertex 0.899743 1.51755 2.63689 + vertex 0.902283 1.5149 2.63947 + vertex 0.902265 1.51988 2.63946 + endloop + endfacet + facet normal -0.714442 0.00123169 0.699694 + outer loop + vertex 0.899743 1.51755 2.63689 + vertex 0.902265 1.51988 2.63946 + vertex 0.899741 1.52254 2.63688 + endloop + endfacet + facet normal -0.746022 0.00114698 0.665921 + outer loop + vertex 0.899741 1.52254 2.63688 + vertex 0.897425 1.52066 2.63429 + vertex 0.899743 1.51755 2.63689 + endloop + endfacet + facet normal -0.746798 0.00331428 0.665042 + outer loop + vertex 0.897433 1.52566 2.63428 + vertex 0.897425 1.52066 2.63429 + vertex 0.899741 1.52254 2.63688 + endloop + endfacet + facet normal -0.744533 0.00708613 0.667548 + outer loop + vertex 0.899764 1.52754 2.63686 + vertex 0.897433 1.52566 2.63428 + vertex 0.899741 1.52254 2.63688 + endloop + endfacet + facet normal -0.713507 0.00713083 0.700612 + outer loop + vertex 0.899741 1.52254 2.63688 + vertex 0.902279 1.52488 2.63944 + vertex 0.899764 1.52754 2.63686 + endloop + endfacet + facet normal -0.712095 0.00983588 0.702014 + outer loop + vertex 0.899764 1.52754 2.63686 + vertex 0.902279 1.52488 2.63944 + vertex 0.902306 1.52985 2.6394 + endloop + endfacet + facet normal -0.712028 0.00968454 0.702085 + outer loop + vertex 0.899764 1.52754 2.63686 + vertex 0.902306 1.52985 2.6394 + vertex 0.899806 1.5325 2.63683 + endloop + endfacet + facet normal -0.743816 0.00977606 0.668313 + outer loop + vertex 0.899806 1.5325 2.63683 + vertex 0.897457 1.53067 2.63424 + vertex 0.899764 1.52754 2.63686 + endloop + endfacet + facet normal -0.743693 0.00941999 0.668455 + outer loop + vertex 0.897507 1.53568 2.63423 + vertex 0.897457 1.53067 2.63424 + vertex 0.899806 1.5325 2.63683 + endloop + endfacet + facet normal -0.744967 0.00735483 0.667061 + outer loop + vertex 0.899906 1.53744 2.63689 + vertex 0.897507 1.53568 2.63423 + vertex 0.899806 1.5325 2.63683 + endloop + endfacet + facet normal -0.714423 0.00635279 0.699686 + outer loop + vertex 0.899806 1.5325 2.63683 + vertex 0.902307 1.53465 2.63936 + vertex 0.899906 1.53744 2.63689 + endloop + endfacet + facet normal -0.720842 -0.0050133 0.693081 + outer loop + vertex 0.899906 1.53744 2.63689 + vertex 0.902307 1.53465 2.63936 + vertex 0.902334 1.53903 2.63942 + endloop + endfacet + facet normal -0.724772 0.00756919 0.688947 + outer loop + vertex 0.90032 1.54279 2.63726 + vertex 0.899906 1.53744 2.63689 + vertex 0.902334 1.53903 2.63942 + endloop + endfacet + facet normal -0.72143 0.0113502 0.692395 + outer loop + vertex 0.902805 1.54243 2.63986 + vertex 0.90032 1.54279 2.63726 + vertex 0.902334 1.53903 2.63942 + endloop + endfacet + facet normal -0.61539 -0.0156325 0.788068 + outer loop + vertex 0.902805 1.54243 2.63986 + vertex 0.902334 1.53903 2.63942 + vertex 0.904568 1.54089 2.64121 + endloop + endfacet + facet normal -0.71994 0.0291763 0.693423 + outer loop + vertex 0.902805 1.54243 2.63986 + vertex 0.90254 1.54622 2.63942 + vertex 0.90032 1.54279 2.63726 + endloop + endfacet + facet normal -0.715187 0.02288 0.698559 + outer loop + vertex 0.90032 1.54279 2.63726 + vertex 0.90254 1.54622 2.63942 + vertex 0.900038 1.54843 2.63679 + endloop + endfacet + facet normal -0.742583 0.0190728 0.669483 + outer loop + vertex 0.900038 1.54843 2.63679 + vertex 0.897662 1.54603 2.63422 + vertex 0.90032 1.54279 2.63726 + endloop + endfacet + facet normal -0.745878 0.0130653 0.665954 + outer loop + vertex 0.897662 1.54603 2.63422 + vertex 0.897613 1.54078 2.63427 + vertex 0.90032 1.54279 2.63726 + endloop + endfacet + facet normal -0.741801 0.0173243 0.670396 + outer loop + vertex 0.897654 1.55124 2.63408 + vertex 0.897662 1.54603 2.63422 + vertex 0.900038 1.54843 2.63679 + endloop + endfacet + facet normal -0.741076 0.0186776 0.671161 + outer loop + vertex 0.900015 1.55359 2.63662 + vertex 0.897654 1.55124 2.63408 + vertex 0.900038 1.54843 2.63679 + endloop + endfacet + facet normal -0.714157 0.0197341 0.699708 + outer loop + vertex 0.900038 1.54843 2.63679 + vertex 0.902484 1.55113 2.63921 + vertex 0.900015 1.55359 2.63662 + endloop + endfacet + facet normal -0.715526 0.0169632 0.69838 + outer loop + vertex 0.902484 1.55113 2.63921 + vertex 0.902501 1.55612 2.63911 + vertex 0.900015 1.55359 2.63662 + endloop + endfacet + facet normal -0.717204 0.0203941 0.696565 + outer loop + vertex 0.900015 1.55359 2.63662 + vertex 0.902501 1.55612 2.63911 + vertex 0.900082 1.55861 2.63654 + endloop + endfacet + facet normal -0.73969 0.0203252 0.672641 + outer loop + vertex 0.900082 1.55861 2.63654 + vertex 0.897705 1.5563 2.634 + vertex 0.900015 1.55359 2.63662 + endloop + endfacet + facet normal -0.740226 0.0215684 0.672012 + outer loop + vertex 0.897791 1.56129 2.63393 + vertex 0.897705 1.5563 2.634 + vertex 0.900082 1.55861 2.63654 + endloop + endfacet + facet normal -0.737668 0.0263257 0.674651 + outer loop + vertex 0.900192 1.56359 2.63647 + vertex 0.897791 1.56129 2.63393 + vertex 0.900082 1.55861 2.63654 + endloop + endfacet + facet normal -0.719324 0.0262097 0.69418 + outer loop + vertex 0.900082 1.55861 2.63654 + vertex 0.902574 1.56109 2.63903 + vertex 0.900192 1.56359 2.63647 + endloop + endfacet + facet normal -0.717949 0.0288626 0.695497 + outer loop + vertex 0.902574 1.56109 2.63903 + vertex 0.902689 1.56605 2.63894 + vertex 0.900192 1.56359 2.63647 + endloop + endfacet + facet normal -0.719151 0.0314508 0.694142 + outer loop + vertex 0.900192 1.56359 2.63647 + vertex 0.902689 1.56605 2.63894 + vertex 0.900316 1.56858 2.63637 + endloop + endfacet + facet normal -0.734899 0.0315173 0.677444 + outer loop + vertex 0.900316 1.56858 2.63637 + vertex 0.897891 1.56627 2.63385 + vertex 0.900192 1.56359 2.63647 + endloop + endfacet + facet normal -0.734178 0.0298205 0.678302 + outer loop + vertex 0.897992 1.57127 2.63374 + vertex 0.897891 1.56627 2.63385 + vertex 0.900316 1.56858 2.63637 + endloop + endfacet + facet normal -0.732037 0.0337522 0.680428 + outer loop + vertex 0.900441 1.57358 2.63626 + vertex 0.897992 1.57127 2.63374 + vertex 0.900316 1.56858 2.63637 + endloop + endfacet + facet normal -0.717742 0.0337408 0.695491 + outer loop + vertex 0.900316 1.56858 2.63637 + vertex 0.902821 1.57103 2.63884 + vertex 0.900441 1.57358 2.63626 + endloop + endfacet + facet normal -0.716298 0.0364574 0.696842 + outer loop + vertex 0.902821 1.57103 2.63884 + vertex 0.902957 1.57603 2.63872 + vertex 0.900441 1.57358 2.63626 + endloop + endfacet + facet normal -0.714735 0.0330822 0.698613 + outer loop + vertex 0.900441 1.57358 2.63626 + vertex 0.902957 1.57603 2.63872 + vertex 0.90056 1.57858 2.63614 + endloop + endfacet + facet normal -0.727777 0.0330819 0.685015 + outer loop + vertex 0.90056 1.57858 2.63614 + vertex 0.898086 1.57627 2.63363 + vertex 0.900441 1.57358 2.63626 + endloop + endfacet + facet normal -0.725701 0.0282393 0.68743 + outer loop + vertex 0.89818 1.58126 2.63352 + vertex 0.898086 1.57627 2.63363 + vertex 0.90056 1.57858 2.63614 + endloop + endfacet + facet normal -0.723475 0.0323342 0.689593 + outer loop + vertex 0.90068 1.58358 2.63603 + vertex 0.89818 1.58126 2.63352 + vertex 0.90056 1.57858 2.63614 + endloop + endfacet + facet normal -0.712363 0.0323175 0.701066 + outer loop + vertex 0.90056 1.57858 2.63614 + vertex 0.903088 1.58104 2.6386 + vertex 0.90068 1.58358 2.63603 + endloop + endfacet + facet normal -0.711774 0.0334274 0.701613 + outer loop + vertex 0.903088 1.58104 2.6386 + vertex 0.903213 1.58603 2.63849 + vertex 0.90068 1.58358 2.63603 + endloop + endfacet + facet normal -0.71155 0.0329454 0.701863 + outer loop + vertex 0.90068 1.58358 2.63603 + vertex 0.903213 1.58603 2.63849 + vertex 0.900806 1.58858 2.63593 + endloop + endfacet + facet normal -0.719959 0.032972 0.693233 + outer loop + vertex 0.900806 1.58858 2.63593 + vertex 0.898282 1.58626 2.63342 + vertex 0.90068 1.58358 2.63603 + endloop + endfacet + facet normal -0.719891 0.0328121 0.693312 + outer loop + vertex 0.8984 1.59126 2.6333 + vertex 0.898282 1.58626 2.63342 + vertex 0.900806 1.58858 2.63593 + endloop + endfacet + facet normal -0.718284 0.0357409 0.694831 + outer loop + vertex 0.900937 1.59356 2.63581 + vertex 0.8984 1.59126 2.6333 + vertex 0.900806 1.58858 2.63593 + endloop + endfacet + facet normal -0.709236 0.0357259 0.704065 + outer loop + vertex 0.900806 1.58858 2.63593 + vertex 0.903348 1.59103 2.63836 + vertex 0.900937 1.59356 2.63581 + endloop + endfacet + facet normal -0.709135 0.0359154 0.704157 + outer loop + vertex 0.903348 1.59103 2.63836 + vertex 0.903468 1.596 2.63823 + vertex 0.900937 1.59356 2.63581 + endloop + endfacet + facet normal -0.710893 0.0397074 0.702179 + outer loop + vertex 0.900937 1.59356 2.63581 + vertex 0.903468 1.596 2.63823 + vertex 0.90107 1.59853 2.63566 + endloop + endfacet + facet normal -0.71647 0.0396897 0.696488 + outer loop + vertex 0.90107 1.59853 2.63566 + vertex 0.898524 1.59623 2.63317 + vertex 0.900937 1.59356 2.63581 + endloop + endfacet + facet normal -0.716915 0.040746 0.695969 + outer loop + vertex 0.898651 1.60117 2.63301 + vertex 0.898524 1.59623 2.63317 + vertex 0.90107 1.59853 2.63566 + endloop + endfacet + facet normal -0.714882 0.044462 0.69783 + outer loop + vertex 0.901216 1.6035 2.63549 + vertex 0.898651 1.60117 2.63301 + vertex 0.90107 1.59853 2.63566 + endloop + endfacet + facet normal -0.71012 0.0444859 0.702674 + outer loop + vertex 0.90107 1.59853 2.63566 + vertex 0.903601 1.60099 2.63806 + vertex 0.901216 1.6035 2.63549 + endloop + endfacet + facet normal -0.708007 0.0484132 0.704544 + outer loop + vertex 0.903601 1.60099 2.63806 + vertex 0.903781 1.60603 2.6379 + vertex 0.901216 1.6035 2.63549 + endloop + endfacet + facet normal -0.709068 0.0506466 0.703319 + outer loop + vertex 0.901216 1.6035 2.63549 + vertex 0.903781 1.60603 2.6379 + vertex 0.901421 1.60854 2.63534 + endloop + endfacet + facet normal -0.706662 0.0550387 0.705407 + outer loop + vertex 0.903781 1.60603 2.6379 + vertex 0.904091 1.6112 2.6378 + vertex 0.901421 1.60854 2.63534 + endloop + endfacet + facet normal -0.708178 0.0582092 0.70363 + outer loop + vertex 0.901421 1.60854 2.63534 + vertex 0.904091 1.6112 2.6378 + vertex 0.901722 1.61374 2.63521 + endloop + endfacet + facet normal -0.706151 0.0618703 0.705353 + outer loop + vertex 0.904091 1.6112 2.6378 + vertex 0.904719 1.61684 2.63794 + vertex 0.901722 1.61374 2.63521 + endloop + endfacet + facet normal -0.707863 0.0653001 0.703325 + outer loop + vertex 0.901722 1.61374 2.63521 + vertex 0.904719 1.61684 2.63794 + vertex 0.901894 1.61895 2.6349 + endloop + endfacet + facet normal -0.709758 0.0652486 0.701417 + outer loop + vertex 0.901894 1.61895 2.6349 + vertex 0.899257 1.61617 2.63249 + vertex 0.901722 1.61374 2.63521 + endloop + endfacet + facet normal -0.710726 0.063367 0.700609 + outer loop + vertex 0.899257 1.61617 2.63249 + vertex 0.898986 1.61116 2.63267 + vertex 0.901722 1.61374 2.63521 + endloop + endfacet + facet normal -0.70844 0.058218 0.703366 + outer loop + vertex 0.901722 1.61374 2.63521 + vertex 0.898986 1.61116 2.63267 + vertex 0.901421 1.60854 2.63534 + endloop + endfacet + facet normal -0.712024 0.051702 0.700249 + outer loop + vertex 0.898986 1.61116 2.63267 + vertex 0.898786 1.60613 2.63284 + vertex 0.901421 1.60854 2.63534 + endloop + endfacet + facet normal -0.71158 0.05067 0.700775 + outer loop + vertex 0.901421 1.60854 2.63534 + vertex 0.898786 1.60613 2.63284 + vertex 0.901216 1.6035 2.63549 + endloop + endfacet + facet normal -0.713032 0.0717914 0.697447 + outer loop + vertex 0.899441 1.62081 2.6322 + vertex 0.899257 1.61617 2.63249 + vertex 0.901894 1.61895 2.6349 + endloop + endfacet + facet normal -0.716761 0.0625845 0.694504 + outer loop + vertex 0.90166 1.6243 2.63417 + vertex 0.899441 1.62081 2.6322 + vertex 0.901894 1.61895 2.6349 + endloop + endfacet + facet normal -0.709413 0.0639072 0.70189 + outer loop + vertex 0.901894 1.61895 2.6349 + vertex 0.904476 1.62218 2.63721 + vertex 0.90166 1.6243 2.63417 + endloop + endfacet + facet normal -0.710377 0.0615274 0.701127 + outer loop + vertex 0.904476 1.62218 2.63721 + vertex 0.90448 1.62699 2.6368 + vertex 0.90166 1.6243 2.63417 + endloop + endfacet + facet normal -0.703317 0.0460639 0.709383 + outer loop + vertex 0.90166 1.6243 2.63417 + vertex 0.90448 1.62699 2.6368 + vertex 0.902258 1.62916 2.63445 + endloop + endfacet + facet normal -0.70927 0.0471407 0.703359 + outer loop + vertex 0.899673 1.62786 2.63193 + vertex 0.90166 1.6243 2.63417 + vertex 0.902258 1.62916 2.63445 + endloop + endfacet + facet normal -0.709324 0.0473845 0.703288 + outer loop + vertex 0.900364 1.6329 2.63229 + vertex 0.899673 1.62786 2.63193 + vertex 0.902258 1.62916 2.63445 + endloop + endfacet + facet normal -0.707208 0.0495995 0.705264 + outer loop + vertex 0.902934 1.63253 2.63489 + vertex 0.900364 1.6329 2.63229 + vertex 0.902258 1.62916 2.63445 + endloop + endfacet + facet normal -0.703158 0.0482461 0.709395 + outer loop + vertex 0.902934 1.63253 2.63489 + vertex 0.902258 1.62916 2.63445 + vertex 0.904327 1.63058 2.63641 + endloop + endfacet + facet normal -0.704713 0.0712929 0.705902 + outer loop + vertex 0.902934 1.63253 2.63489 + vertex 0.902771 1.63624 2.63436 + vertex 0.900364 1.6329 2.63229 + endloop + endfacet + facet normal -0.697029 0.0604356 0.714492 + outer loop + vertex 0.900364 1.6329 2.63229 + vertex 0.902771 1.63624 2.63436 + vertex 0.900187 1.63836 2.63166 + endloop + endfacet + facet normal -0.65295 0.0665086 0.754475 + outer loop + vertex 0.900187 1.63836 2.63166 + vertex 0.897344 1.63547 2.62945 + vertex 0.900364 1.6329 2.63229 + endloop + endfacet + facet normal -0.660938 0.0507698 0.748721 + outer loop + vertex 0.897344 1.63547 2.62945 + vertex 0.897203 1.63041 2.62967 + vertex 0.900364 1.6329 2.63229 + endloop + endfacet + facet normal -0.649468 0.0603956 0.757987 + outer loop + vertex 0.897428 1.6406 2.62911 + vertex 0.897344 1.63547 2.62945 + vertex 0.900187 1.63836 2.63166 + endloop + endfacet + facet normal -0.645897 0.067566 0.760429 + outer loop + vertex 0.900258 1.64345 2.63126 + vertex 0.897428 1.6406 2.62911 + vertex 0.900187 1.63836 2.63166 + endloop + endfacet + facet normal -0.685919 0.0653729 0.724735 + outer loop + vertex 0.900187 1.63836 2.63166 + vertex 0.90287 1.6411 2.63395 + vertex 0.900258 1.64345 2.63126 + endloop + endfacet + facet normal -0.68244 0.0722436 0.727363 + outer loop + vertex 0.90287 1.6411 2.63395 + vertex 0.903044 1.64612 2.63361 + vertex 0.900258 1.64345 2.63126 + endloop + endfacet + facet normal -0.678751 0.064743 0.731509 + outer loop + vertex 0.900258 1.64345 2.63126 + vertex 0.903044 1.64612 2.63361 + vertex 0.900376 1.6485 2.63093 + endloop + endfacet + facet normal -0.642852 0.0660086 0.763141 + outer loop + vertex 0.900376 1.6485 2.63093 + vertex 0.897531 1.64564 2.62878 + vertex 0.900258 1.64345 2.63126 + endloop + endfacet + facet normal -0.639496 0.0601932 0.766434 + outer loop + vertex 0.897349 1.65091 2.62821 + vertex 0.897531 1.64564 2.62878 + vertex 0.900376 1.6485 2.63093 + endloop + endfacet + facet normal -0.635157 0.068868 0.769307 + outer loop + vertex 0.900631 1.65355 2.63068 + vertex 0.897349 1.65091 2.62821 + vertex 0.900376 1.6485 2.63093 + endloop + endfacet + facet normal -0.677933 0.0692253 0.731857 + outer loop + vertex 0.900376 1.6485 2.63093 + vertex 0.903247 1.6511 2.63334 + vertex 0.900631 1.65355 2.63068 + endloop + endfacet + facet normal -0.678459 0.0682359 0.731462 + outer loop + vertex 0.903247 1.6511 2.63334 + vertex 0.903496 1.65607 2.63311 + vertex 0.900631 1.65355 2.63068 + endloop + endfacet + facet normal -0.682179 0.0766203 0.72716 + outer loop + vertex 0.900631 1.65355 2.63068 + vertex 0.903496 1.65607 2.63311 + vertex 0.900997 1.65858 2.6305 + endloop + endfacet + facet normal -0.642585 0.0750555 0.762529 + outer loop + vertex 0.900997 1.65858 2.6305 + vertex 0.898068 1.65624 2.62826 + vertex 0.900631 1.65355 2.63068 + endloop + endfacet + facet normal -0.64506 0.0807116 0.759857 + outer loop + vertex 0.898478 1.66125 2.62808 + vertex 0.898068 1.65624 2.62826 + vertex 0.900997 1.65858 2.6305 + endloop + endfacet + facet normal -0.645776 0.079592 0.759368 + outer loop + vertex 0.90134 1.6636 2.63026 + vertex 0.898478 1.66125 2.62808 + vertex 0.900997 1.65858 2.6305 + endloop + endfacet + facet normal -0.687212 0.0806808 0.721963 + outer loop + vertex 0.900997 1.65858 2.6305 + vertex 0.90376 1.66107 2.63285 + vertex 0.90134 1.6636 2.63026 + endloop + endfacet + facet normal -0.688455 0.0785265 0.721015 + outer loop + vertex 0.90376 1.66107 2.63285 + vertex 0.903999 1.66598 2.63254 + vertex 0.90134 1.6636 2.63026 + endloop + endfacet + facet normal -0.692264 0.0872669 0.716349 + outer loop + vertex 0.90134 1.6636 2.63026 + vertex 0.903999 1.66598 2.63254 + vertex 0.901774 1.66847 2.63009 + endloop + endfacet + facet normal -0.647274 0.0847249 0.757535 + outer loop + vertex 0.901774 1.66847 2.63009 + vertex 0.898912 1.66638 2.62788 + vertex 0.90134 1.6636 2.63026 + endloop + endfacet + facet normal -0.65031 0.0926304 0.754 + outer loop + vertex 0.899723 1.67192 2.6279 + vertex 0.898912 1.66638 2.62788 + vertex 0.901774 1.66847 2.63009 + endloop + endfacet + facet normal -0.655662 0.0869277 0.750034 + outer loop + vertex 0.902419 1.67218 2.63022 + vertex 0.899723 1.67192 2.6279 + vertex 0.901774 1.66847 2.63009 + endloop + endfacet + facet normal -0.697554 0.0956532 0.710119 + outer loop + vertex 0.901774 1.66847 2.63009 + vertex 0.904176 1.67041 2.63219 + vertex 0.902419 1.67218 2.63022 + endloop + endfacet + facet normal -0.701885 0.0877314 0.706867 + outer loop + vertex 0.904104 1.67388 2.63169 + vertex 0.902419 1.67218 2.63022 + vertex 0.904176 1.67041 2.63219 + endloop + endfacet + facet normal -0.681384 0.0909582 0.726253 + outer loop + vertex 0.904104 1.67388 2.63169 + vertex 0.904176 1.67041 2.63219 + vertex 0.906341 1.67315 2.63388 + endloop + endfacet + facet normal -0.683496 0.0817511 0.725362 + outer loop + vertex 0.905456 1.67775 2.63252 + vertex 0.904104 1.67388 2.63169 + vertex 0.906341 1.67315 2.63388 + endloop + endfacet + facet normal -0.631066 0.104584 0.768647 + outer loop + vertex 0.905456 1.67775 2.63252 + vertex 0.906341 1.67315 2.63388 + vertex 0.908607 1.67624 2.63532 + endloop + endfacet + facet normal -0.665172 -0.00758118 0.746652 + outer loop + vertex 0.905456 1.67775 2.63252 + vertex 0.908607 1.67624 2.63532 + vertex 0.907838 1.67851 2.63465 + endloop + endfacet + facet normal -0.680743 0.100444 0.725603 + outer loop + vertex 0.907838 1.67851 2.63465 + vertex 0.907721 1.68127 2.63416 + vertex 0.905456 1.67775 2.63252 + endloop + endfacet + facet normal -0.679606 0.0991326 0.726849 + outer loop + vertex 0.905456 1.67775 2.63252 + vertex 0.907721 1.68127 2.63416 + vertex 0.905205 1.68324 2.63154 + endloop + endfacet + facet normal -0.695691 0.0957279 0.711935 + outer loop + vertex 0.905205 1.68324 2.63154 + vertex 0.902102 1.68064 2.62886 + vertex 0.905456 1.67775 2.63252 + endloop + endfacet + facet normal -0.698331 0.0902838 0.710059 + outer loop + vertex 0.902102 1.68064 2.62886 + vertex 0.90226 1.67566 2.62965 + vertex 0.905456 1.67775 2.63252 + endloop + endfacet + facet normal -0.696542 0.0979067 0.710804 + outer loop + vertex 0.902742 1.68603 2.62874 + vertex 0.902102 1.68064 2.62886 + vertex 0.905205 1.68324 2.63154 + endloop + endfacet + facet normal -0.693548 0.102789 0.71304 + outer loop + vertex 0.905548 1.6884 2.63113 + vertex 0.902742 1.68603 2.62874 + vertex 0.905205 1.68324 2.63154 + endloop + endfacet + facet normal -0.672794 0.102969 0.732629 + outer loop + vertex 0.905205 1.68324 2.63154 + vertex 0.907941 1.6859 2.63368 + vertex 0.905548 1.6884 2.63113 + endloop + endfacet + facet normal -0.671996 0.104288 0.733175 + outer loop + vertex 0.907941 1.6859 2.63368 + vertex 0.908413 1.69104 2.63338 + vertex 0.905548 1.6884 2.63113 + endloop + endfacet + facet normal -0.670986 0.102149 0.7344 + outer loop + vertex 0.905548 1.6884 2.63113 + vertex 0.908413 1.69104 2.63338 + vertex 0.906049 1.69367 2.63085 + endloop + endfacet + facet normal -0.687563 0.10291 0.718795 + outer loop + vertex 0.906049 1.69367 2.63085 + vertex 0.90318 1.69111 2.62848 + vertex 0.905548 1.6884 2.63113 + endloop + endfacet + facet normal -0.68612 0.0995797 0.72064 + outer loop + vertex 0.903576 1.6962 2.62815 + vertex 0.90318 1.69111 2.62848 + vertex 0.906049 1.69367 2.63085 + endloop + endfacet + facet normal -0.680736 0.108858 0.724396 + outer loop + vertex 0.906475 1.69896 2.63046 + vertex 0.903576 1.6962 2.62815 + vertex 0.906049 1.69367 2.63085 + endloop + endfacet + facet normal -0.666266 0.108688 0.737751 + outer loop + vertex 0.906049 1.69367 2.63085 + vertex 0.909321 1.69681 2.63335 + vertex 0.906475 1.69896 2.63046 + endloop + endfacet + facet normal -0.6605 0.120778 0.741048 + outer loop + vertex 0.909321 1.69681 2.63335 + vertex 0.909434 1.70231 2.63255 + vertex 0.906475 1.69896 2.63046 + endloop + endfacet + facet normal -0.658516 0.117614 0.743319 + outer loop + vertex 0.906475 1.69896 2.63046 + vertex 0.909434 1.70231 2.63255 + vertex 0.906648 1.70388 2.62984 + endloop + endfacet + facet normal -0.674761 0.116344 0.728809 + outer loop + vertex 0.906648 1.70388 2.62984 + vertex 0.903909 1.70114 2.62774 + vertex 0.906475 1.69896 2.63046 + endloop + endfacet + facet normal -0.673915 0.114695 0.729851 + outer loop + vertex 0.904147 1.70553 2.62727 + vertex 0.903909 1.70114 2.62774 + vertex 0.906648 1.70388 2.62984 + endloop + endfacet + facet normal -0.675766 0.110299 0.728817 + outer loop + vertex 0.906434 1.70823 2.62898 + vertex 0.904147 1.70553 2.62727 + vertex 0.906648 1.70388 2.62984 + endloop + endfacet + facet normal -0.647871 0.116389 0.752806 + outer loop + vertex 0.906648 1.70388 2.62984 + vertex 0.909433 1.70722 2.63172 + vertex 0.906434 1.70823 2.62898 + endloop + endfacet + facet normal -0.653558 0.0945357 0.750949 + outer loop + vertex 0.908651 1.71123 2.63053 + vertex 0.906434 1.70823 2.62898 + vertex 0.909433 1.70722 2.63172 + endloop + endfacet + facet normal -0.656955 0.0988784 0.747418 + outer loop + vertex 0.905555 1.71274 2.62761 + vertex 0.906434 1.70823 2.62898 + vertex 0.908651 1.71123 2.63053 + endloop + endfacet + facet normal -0.668934 0.061514 0.740772 + outer loop + vertex 0.905555 1.71274 2.62761 + vertex 0.908651 1.71123 2.63053 + vertex 0.907978 1.71355 2.62973 + endloop + endfacet + facet normal -0.675036 0.108717 0.729731 + outer loop + vertex 0.907978 1.71355 2.62973 + vertex 0.907839 1.71631 2.62919 + vertex 0.905555 1.71274 2.62761 + endloop + endfacet + facet normal -0.670646 0.103803 0.734478 + outer loop + vertex 0.905555 1.71274 2.62761 + vertex 0.907839 1.71631 2.62919 + vertex 0.905221 1.71808 2.62655 + endloop + endfacet + facet normal -0.639572 0.110948 0.760683 + outer loop + vertex 0.905221 1.71808 2.62655 + vertex 0.902292 1.7153 2.62449 + vertex 0.905555 1.71274 2.62761 + endloop + endfacet + facet normal -0.64385 0.102527 0.758251 + outer loop + vertex 0.902292 1.7153 2.62449 + vertex 0.901969 1.71059 2.62486 + vertex 0.905555 1.71274 2.62761 + endloop + endfacet + facet normal -0.632467 0.0663117 0.771743 + outer loop + vertex 0.905555 1.71274 2.62761 + vertex 0.901969 1.71059 2.62486 + vertex 0.904091 1.70893 2.62674 + endloop + endfacet + facet normal -0.640073 0.111889 0.760123 + outer loop + vertex 0.902426 1.7203 2.62387 + vertex 0.902292 1.7153 2.62449 + vertex 0.905221 1.71808 2.62655 + endloop + endfacet + facet normal -0.637777 0.116309 0.761388 + outer loop + vertex 0.905381 1.72323 2.6259 + vertex 0.902426 1.7203 2.62387 + vertex 0.905221 1.71808 2.62655 + endloop + endfacet + facet normal -0.666062 0.114116 0.737115 + outer loop + vertex 0.905221 1.71808 2.62655 + vertex 0.907992 1.72092 2.62861 + vertex 0.905381 1.72323 2.6259 + endloop + endfacet + facet normal -0.663013 0.119753 0.738968 + outer loop + vertex 0.907992 1.72092 2.62861 + vertex 0.908441 1.72605 2.62819 + vertex 0.905381 1.72323 2.6259 + endloop + endfacet + facet normal -0.665527 0.125034 0.735826 + outer loop + vertex 0.905381 1.72323 2.6259 + vertex 0.908441 1.72605 2.62819 + vertex 0.905972 1.72861 2.62552 + endloop + endfacet + facet normal -0.628765 0.123249 0.767766 + outer loop + vertex 0.905972 1.72861 2.62552 + vertex 0.902405 1.72568 2.62307 + vertex 0.905381 1.72323 2.6259 + endloop + endfacet + facet normal -0.630608 0.127321 0.765587 + outer loop + vertex 0.903505 1.73133 2.62303 + vertex 0.902405 1.72568 2.62307 + vertex 0.905972 1.72861 2.62552 + endloop + endfacet + facet normal -0.626724 0.132885 0.767827 + outer loop + vertex 0.906773 1.73382 2.62527 + vertex 0.903505 1.73133 2.62303 + vertex 0.905972 1.72861 2.62552 + endloop + endfacet + facet normal -0.662613 0.136903 0.736344 + outer loop + vertex 0.905972 1.72861 2.62552 + vertex 0.909406 1.73168 2.62804 + vertex 0.906773 1.73382 2.62527 + endloop + endfacet + facet normal -0.659643 0.142599 0.737927 + outer loop + vertex 0.909406 1.73168 2.62804 + vertex 0.909492 1.73659 2.62716 + vertex 0.906773 1.73382 2.62527 + endloop + endfacet + facet normal -0.659358 0.142075 0.738283 + outer loop + vertex 0.906773 1.73382 2.62527 + vertex 0.909492 1.73659 2.62716 + vertex 0.907553 1.7377 2.62522 + endloop + endfacet + facet normal -0.619703 0.134559 0.773216 + outer loop + vertex 0.907553 1.7377 2.62522 + vertex 0.904634 1.73701 2.623 + vertex 0.906773 1.73382 2.62527 + endloop + endfacet + facet normal -0.61851 0.117963 0.776872 + outer loop + vertex 0.907553 1.7377 2.62522 + vertex 0.907337 1.74102 2.62454 + vertex 0.904634 1.73701 2.623 + endloop + endfacet + facet normal -0.650108 0.110782 0.751722 + outer loop + vertex 0.907553 1.7377 2.62522 + vertex 0.909301 1.73993 2.6264 + vertex 0.907337 1.74102 2.62454 + endloop + endfacet + facet normal -0.660753 0.0821921 0.74609 + outer loop + vertex 0.909905 1.74355 2.62654 + vertex 0.907337 1.74102 2.62454 + vertex 0.909301 1.73993 2.6264 + endloop + endfacet + facet normal -0.639224 0.0778897 0.765066 + outer loop + vertex 0.909301 1.73993 2.6264 + vertex 0.912012 1.74068 2.62859 + vertex 0.909905 1.74355 2.62654 + endloop + endfacet + facet normal -0.644766 0.134912 0.75238 + outer loop + vertex 0.909301 1.73993 2.6264 + vertex 0.909492 1.73659 2.62716 + vertex 0.912012 1.74068 2.62859 + endloop + endfacet + facet normal -0.637008 0.127371 0.760262 + outer loop + vertex 0.909492 1.73659 2.62716 + vertex 0.912005 1.73591 2.62938 + vertex 0.912012 1.74068 2.62859 + endloop + endfacet + facet normal -0.66414 0.130109 0.7362 + outer loop + vertex 0.909301 1.73993 2.6264 + vertex 0.907553 1.7377 2.62522 + vertex 0.909492 1.73659 2.62716 + endloop + endfacet + facet normal -0.632337 0.146174 0.760778 + outer loop + vertex 0.909406 1.73168 2.62804 + vertex 0.912005 1.73591 2.62938 + vertex 0.909492 1.73659 2.62716 + endloop + endfacet + facet normal -0.629418 0.14344 0.763713 + outer loop + vertex 0.912241 1.73261 2.6302 + vertex 0.912005 1.73591 2.62938 + vertex 0.909406 1.73168 2.62804 + endloop + endfacet + facet normal -0.627314 0.125623 0.768567 + outer loop + vertex 0.912241 1.73261 2.6302 + vertex 0.909406 1.73168 2.62804 + vertex 0.911569 1.7288 2.63027 + endloop + endfacet + facet normal -0.481823 0.10184 0.870331 + outer loop + vertex 0.911569 1.7288 2.63027 + vertex 0.914763 1.73207 2.63166 + vertex 0.912241 1.73261 2.6302 + endloop + endfacet + facet normal -0.478591 0.116729 0.870244 + outer loop + vertex 0.914329 1.73525 2.63099 + vertex 0.912241 1.73261 2.6302 + vertex 0.914763 1.73207 2.63166 + endloop + endfacet + facet normal -0.491491 0.114259 0.863355 + outer loop + vertex 0.914634 1.72753 2.63218 + vertex 0.914763 1.73207 2.63166 + vertex 0.911569 1.7288 2.63027 + endloop + endfacet + facet normal -0.49251 0.111469 0.863139 + outer loop + vertex 0.911087 1.72392 2.63063 + vertex 0.914634 1.72753 2.63218 + vertex 0.911569 1.7288 2.63027 + endloop + endfacet + facet normal -0.620731 0.117719 0.775136 + outer loop + vertex 0.911569 1.7288 2.63027 + vertex 0.908441 1.72605 2.62819 + vertex 0.911087 1.72392 2.63063 + endloop + endfacet + facet normal -0.62002 0.119025 0.775505 + outer loop + vertex 0.908441 1.72605 2.62819 + vertex 0.907992 1.72092 2.62861 + vertex 0.911087 1.72392 2.63063 + endloop + endfacet + facet normal -0.617999 0.115494 0.777649 + outer loop + vertex 0.911087 1.72392 2.63063 + vertex 0.907992 1.72092 2.62861 + vertex 0.910716 1.71905 2.63106 + endloop + endfacet + facet normal -0.497539 0.113563 0.859976 + outer loop + vertex 0.910716 1.71905 2.63106 + vertex 0.914347 1.72257 2.63269 + vertex 0.911087 1.72392 2.63063 + endloop + endfacet + facet normal -0.499938 0.11689 0.858137 + outer loop + vertex 0.913875 1.7175 2.63311 + vertex 0.914347 1.72257 2.63269 + vertex 0.910716 1.71905 2.63106 + endloop + endfacet + facet normal -0.504174 0.106726 0.856982 + outer loop + vertex 0.910171 1.71468 2.63128 + vertex 0.913875 1.7175 2.63311 + vertex 0.910716 1.71905 2.63106 + endloop + endfacet + facet normal -0.616285 0.116681 0.778831 + outer loop + vertex 0.910716 1.71905 2.63106 + vertex 0.907839 1.71631 2.62919 + vertex 0.910171 1.71468 2.63128 + endloop + endfacet + facet normal -0.613875 0.1216 0.779982 + outer loop + vertex 0.907839 1.71631 2.62919 + vertex 0.907978 1.71355 2.62973 + vertex 0.910171 1.71468 2.63128 + endloop + endfacet + facet normal -0.607027 0.0960792 0.788852 + outer loop + vertex 0.910171 1.71468 2.63128 + vertex 0.907978 1.71355 2.62973 + vertex 0.908651 1.71123 2.63053 + endloop + endfacet + facet normal -0.559209 0.0668694 0.826325 + outer loop + vertex 0.908651 1.71123 2.63053 + vertex 0.912689 1.7119 2.63321 + vertex 0.910171 1.71468 2.63128 + endloop + endfacet + facet normal -0.563034 0.131382 0.815924 + outer loop + vertex 0.908651 1.71123 2.63053 + vertex 0.909433 1.70722 2.63172 + vertex 0.912689 1.7119 2.63321 + endloop + endfacet + facet normal -0.565597 0.133861 0.813745 + outer loop + vertex 0.909433 1.70722 2.63172 + vertex 0.913034 1.70642 2.63435 + vertex 0.912689 1.7119 2.63321 + endloop + endfacet + facet normal -0.564545 0.138484 0.813702 + outer loop + vertex 0.909434 1.70231 2.63255 + vertex 0.913034 1.70642 2.63435 + vertex 0.909433 1.70722 2.63172 + endloop + endfacet + facet normal -0.513499 0.124092 0.84907 + outer loop + vertex 0.912689 1.7119 2.63321 + vertex 0.913875 1.7175 2.63311 + vertex 0.910171 1.71468 2.63128 + endloop + endfacet + facet normal -0.616902 0.117774 0.778178 + outer loop + vertex 0.907992 1.72092 2.62861 + vertex 0.907839 1.71631 2.62919 + vertex 0.910716 1.71905 2.63106 + endloop + endfacet + facet normal -0.496436 0.116584 0.860209 + outer loop + vertex 0.914347 1.72257 2.63269 + vertex 0.914634 1.72753 2.63218 + vertex 0.911087 1.72392 2.63063 + endloop + endfacet + facet normal -0.625704 0.127599 0.769554 + outer loop + vertex 0.909406 1.73168 2.62804 + vertex 0.908441 1.72605 2.62819 + vertex 0.911569 1.7288 2.63027 + endloop + endfacet + facet normal -0.528436 0.167572 0.832271 + outer loop + vertex 0.912241 1.73261 2.6302 + vertex 0.914329 1.73525 2.63099 + vertex 0.912005 1.73591 2.62938 + endloop + endfacet + facet normal -0.624983 0.128689 0.769958 + outer loop + vertex 0.904634 1.73701 2.623 + vertex 0.903505 1.73133 2.62303 + vertex 0.906773 1.73382 2.62527 + endloop + endfacet + facet normal -0.660718 0.132774 0.738798 + outer loop + vertex 0.908441 1.72605 2.62819 + vertex 0.909406 1.73168 2.62804 + vertex 0.905972 1.72861 2.62552 + endloop + endfacet + facet normal -0.635105 0.111579 0.764325 + outer loop + vertex 0.902405 1.72568 2.62307 + vertex 0.902426 1.7203 2.62387 + vertex 0.905381 1.72323 2.6259 + endloop + endfacet + facet normal -0.666136 0.114252 0.737027 + outer loop + vertex 0.907839 1.71631 2.62919 + vertex 0.907992 1.72092 2.62861 + vertex 0.905221 1.71808 2.62655 + endloop + endfacet + facet normal -0.674107 0.0911506 0.732988 + outer loop + vertex 0.905555 1.71274 2.62761 + vertex 0.904091 1.70893 2.62674 + vertex 0.906434 1.70823 2.62898 + endloop + endfacet + facet normal -0.671356 0.103336 0.733895 + outer loop + vertex 0.904091 1.70893 2.62674 + vertex 0.904147 1.70553 2.62727 + vertex 0.906434 1.70823 2.62898 + endloop + endfacet + facet normal -0.654979 0.126738 0.744943 + outer loop + vertex 0.909434 1.70231 2.63255 + vertex 0.909433 1.70722 2.63172 + vertex 0.906648 1.70388 2.62984 + endloop + endfacet + facet normal -0.679697 0.106672 0.725695 + outer loop + vertex 0.903909 1.70114 2.62774 + vertex 0.903576 1.6962 2.62815 + vertex 0.906475 1.69896 2.63046 + endloop + endfacet + facet normal -0.666494 0.109143 0.737478 + outer loop + vertex 0.908413 1.69104 2.63338 + vertex 0.909321 1.69681 2.63335 + vertex 0.906049 1.69367 2.63085 + endloop + endfacet + facet normal -0.691255 0.0970179 0.716068 + outer loop + vertex 0.90318 1.69111 2.62848 + vertex 0.902742 1.68603 2.62874 + vertex 0.905548 1.6884 2.63113 + endloop + endfacet + facet normal -0.675357 0.108104 0.729525 + outer loop + vertex 0.907721 1.68127 2.63416 + vertex 0.907941 1.6859 2.63368 + vertex 0.905205 1.68324 2.63154 + endloop + endfacet + facet normal -0.58501 0.0518517 0.809367 + outer loop + vertex 0.908607 1.67624 2.63532 + vertex 0.906341 1.67315 2.63388 + vertex 0.909587 1.67236 2.63627 + endloop + endfacet + facet normal -0.576017 0.0958898 0.811794 + outer loop + vertex 0.906657 1.6688 2.63461 + vertex 0.909587 1.67236 2.63627 + vertex 0.906341 1.67315 2.63388 + endloop + endfacet + facet normal -0.560842 0.0775761 0.824281 + outer loop + vertex 0.909882 1.66766 2.63692 + vertex 0.909587 1.67236 2.63627 + vertex 0.906657 1.6688 2.63461 + endloop + endfacet + facet normal -0.559079 0.0837688 0.824872 + outer loop + vertex 0.906629 1.66401 2.63508 + vertex 0.909882 1.66766 2.63692 + vertex 0.906657 1.6688 2.63461 + endloop + endfacet + facet normal -0.662086 0.0766469 0.745498 + outer loop + vertex 0.906657 1.6688 2.63461 + vertex 0.903999 1.66598 2.63254 + vertex 0.906629 1.66401 2.63508 + endloop + endfacet + facet normal -0.66747 0.0860152 0.739652 + outer loop + vertex 0.904176 1.67041 2.63219 + vertex 0.903999 1.66598 2.63254 + vertex 0.906657 1.6688 2.63461 + endloop + endfacet + facet normal -0.551306 0.0737433 0.831038 + outer loop + vertex 0.90983 1.6627 2.63732 + vertex 0.909882 1.66766 2.63692 + vertex 0.906629 1.66401 2.63508 + endloop + endfacet + facet normal -0.551654 0.0726622 0.830902 + outer loop + vertex 0.906453 1.65902 2.6354 + vertex 0.90983 1.6627 2.63732 + vertex 0.906629 1.66401 2.63508 + endloop + endfacet + facet normal -0.656881 0.0712394 0.750621 + outer loop + vertex 0.906629 1.66401 2.63508 + vertex 0.90376 1.66107 2.63285 + vertex 0.906453 1.65902 2.6354 + endloop + endfacet + facet normal -0.65594 0.073259 0.751249 + outer loop + vertex 0.90376 1.66107 2.63285 + vertex 0.903496 1.65607 2.63311 + vertex 0.906453 1.65902 2.6354 + endloop + endfacet + facet normal -0.651571 0.0653715 0.755766 + outer loop + vertex 0.906453 1.65902 2.6354 + vertex 0.903496 1.65607 2.63311 + vertex 0.906242 1.65401 2.63565 + endloop + endfacet + facet normal -0.54824 0.0649491 0.833795 + outer loop + vertex 0.906242 1.65401 2.63565 + vertex 0.909637 1.65763 2.6376 + vertex 0.906453 1.65902 2.6354 + endloop + endfacet + facet normal -0.552525 0.070762 0.830487 + outer loop + vertex 0.90941 1.65248 2.63789 + vertex 0.909637 1.65763 2.6376 + vertex 0.906242 1.65401 2.63565 + endloop + endfacet + facet normal -0.553056 0.0693266 0.830255 + outer loop + vertex 0.906014 1.64898 2.63592 + vertex 0.90941 1.65248 2.63789 + vertex 0.906242 1.65401 2.63565 + endloop + endfacet + facet normal -0.651326 0.069801 0.755581 + outer loop + vertex 0.906242 1.65401 2.63565 + vertex 0.903247 1.6511 2.63334 + vertex 0.906014 1.64898 2.63592 + endloop + endfacet + facet normal -0.65221 0.0679264 0.754989 + outer loop + vertex 0.903247 1.6511 2.63334 + vertex 0.903044 1.64612 2.63361 + vertex 0.906014 1.64898 2.63592 + endloop + endfacet + facet normal -0.657351 0.0776239 0.749576 + outer loop + vertex 0.906014 1.64898 2.63592 + vertex 0.903044 1.64612 2.63361 + vertex 0.905792 1.64386 2.63626 + endloop + endfacet + facet normal -0.569335 0.0783222 0.818367 + outer loop + vertex 0.905792 1.64386 2.63626 + vertex 0.909086 1.64724 2.63822 + vertex 0.906014 1.64898 2.63592 + endloop + endfacet + facet normal -0.579313 0.0930403 0.809778 + outer loop + vertex 0.908973 1.64173 2.63878 + vertex 0.909086 1.64724 2.63822 + vertex 0.905792 1.64386 2.63626 + endloop + endfacet + facet normal -0.583615 0.0841154 0.807662 + outer loop + vertex 0.905466 1.63873 2.63656 + vertex 0.908973 1.64173 2.63878 + vertex 0.905792 1.64386 2.63626 + endloop + endfacet + facet normal -0.666115 0.0854686 0.740936 + outer loop + vertex 0.905792 1.64386 2.63626 + vertex 0.90287 1.6411 2.63395 + vertex 0.905466 1.63873 2.63656 + endloop + endfacet + facet normal -0.671411 0.0755786 0.737221 + outer loop + vertex 0.90287 1.6411 2.63395 + vertex 0.902771 1.63624 2.63436 + vertex 0.905466 1.63873 2.63656 + endloop + endfacet + facet normal -0.677254 0.0878565 0.730485 + outer loop + vertex 0.905466 1.63873 2.63656 + vertex 0.902771 1.63624 2.63436 + vertex 0.905022 1.63403 2.63671 + endloop + endfacet + facet normal -0.601645 0.0827968 0.794461 + outer loop + vertex 0.905022 1.63403 2.63671 + vertex 0.907981 1.63615 2.63873 + vertex 0.905466 1.63873 2.63656 + endloop + endfacet + facet normal -0.599581 0.0779495 0.796509 + outer loop + vertex 0.90709 1.63074 2.63859 + vertex 0.907981 1.63615 2.63873 + vertex 0.905022 1.63403 2.63671 + endloop + endfacet + facet normal -0.620591 0.0565478 0.782093 + outer loop + vertex 0.904327 1.63058 2.63641 + vertex 0.90709 1.63074 2.63859 + vertex 0.905022 1.63403 2.63671 + endloop + endfacet + facet normal -0.684191 0.0743537 0.725503 + outer loop + vertex 0.905022 1.63403 2.63671 + vertex 0.902934 1.63253 2.63489 + vertex 0.904327 1.63058 2.63641 + endloop + endfacet + facet normal -0.620587 0.0584495 0.781956 + outer loop + vertex 0.904327 1.63058 2.63641 + vertex 0.90448 1.62699 2.6368 + vertex 0.90709 1.63074 2.63859 + endloop + endfacet + facet normal -0.629474 0.068434 0.774002 + outer loop + vertex 0.90448 1.62699 2.6368 + vertex 0.907202 1.62556 2.63914 + vertex 0.90709 1.63074 2.63859 + endloop + endfacet + facet normal -0.629713 0.0677575 0.773867 + outer loop + vertex 0.904476 1.62218 2.63721 + vertex 0.907202 1.62556 2.63914 + vertex 0.90448 1.62699 2.6368 + endloop + endfacet + facet normal -0.641664 0.083952 0.762378 + outer loop + vertex 0.907108 1.62102 2.63956 + vertex 0.907202 1.62556 2.63914 + vertex 0.904476 1.62218 2.63721 + endloop + endfacet + facet normal -0.64476 0.0737592 0.760818 + outer loop + vertex 0.904719 1.61684 2.63794 + vertex 0.907108 1.62102 2.63956 + vertex 0.904476 1.62218 2.63721 + endloop + endfacet + facet normal -0.63164 0.0616156 0.772809 + outer loop + vertex 0.907451 1.61774 2.6401 + vertex 0.907108 1.62102 2.63956 + vertex 0.904719 1.61684 2.63794 + endloop + endfacet + facet normal -0.629624 0.0494672 0.775323 + outer loop + vertex 0.907451 1.61774 2.6401 + vertex 0.904719 1.61684 2.63794 + vertex 0.906923 1.61395 2.63991 + endloop + endfacet + facet normal -0.433456 0.015928 0.901034 + outer loop + vertex 0.906923 1.61395 2.63991 + vertex 0.909907 1.61723 2.64129 + vertex 0.907451 1.61774 2.6401 + endloop + endfacet + facet normal -0.431108 0.0290234 0.901834 + outer loop + vertex 0.909399 1.62037 2.64095 + vertex 0.907451 1.61774 2.6401 + vertex 0.909907 1.61723 2.64129 + endloop + endfacet + facet normal -0.447828 0.0321547 0.893542 + outer loop + vertex 0.909894 1.61274 2.64144 + vertex 0.909907 1.61723 2.64129 + vertex 0.906923 1.61395 2.63991 + endloop + endfacet + facet normal -0.446923 0.0348135 0.893895 + outer loop + vertex 0.906615 1.60907 2.63995 + vertex 0.909894 1.61274 2.64144 + vertex 0.906923 1.61395 2.63991 + endloop + endfacet + facet normal -0.624322 0.0451093 0.779864 + outer loop + vertex 0.906923 1.61395 2.63991 + vertex 0.904091 1.6112 2.6378 + vertex 0.906615 1.60907 2.63995 + endloop + endfacet + facet normal -0.621024 0.0512631 0.782114 + outer loop + vertex 0.904091 1.6112 2.6378 + vertex 0.903781 1.60603 2.6379 + vertex 0.906615 1.60907 2.63995 + endloop + endfacet + facet normal -0.619455 0.0488522 0.783511 + outer loop + vertex 0.906615 1.60907 2.63995 + vertex 0.903781 1.60603 2.6379 + vertex 0.906419 1.60402 2.64011 + endloop + endfacet + facet normal -0.455163 0.0458172 0.889228 + outer loop + vertex 0.906419 1.60402 2.64011 + vertex 0.909773 1.60779 2.64163 + vertex 0.906615 1.60907 2.63995 + endloop + endfacet + facet normal -0.455874 0.0466126 0.888823 + outer loop + vertex 0.909671 1.60276 2.64184 + vertex 0.909773 1.60779 2.64163 + vertex 0.906419 1.60402 2.64011 + endloop + endfacet + facet normal -0.456299 0.0453056 0.888672 + outer loop + vertex 0.906289 1.59899 2.6403 + vertex 0.909671 1.60276 2.64184 + vertex 0.906419 1.60402 2.64011 + endloop + endfacet + facet normal -0.618427 0.0455712 0.78452 + outer loop + vertex 0.906419 1.60402 2.64011 + vertex 0.903601 1.60099 2.63806 + vertex 0.906289 1.59899 2.6403 + endloop + endfacet + facet normal -0.619652 0.0430064 0.783698 + outer loop + vertex 0.903601 1.60099 2.63806 + vertex 0.903468 1.596 2.63823 + vertex 0.906289 1.59899 2.6403 + endloop + endfacet + facet normal -0.617541 0.0397489 0.785533 + outer loop + vertex 0.906289 1.59899 2.6403 + vertex 0.903468 1.596 2.63823 + vertex 0.906183 1.594 2.64047 + endloop + endfacet + facet normal -0.454844 0.039808 0.889681 + outer loop + vertex 0.906183 1.594 2.64047 + vertex 0.909593 1.59775 2.64204 + vertex 0.906289 1.59899 2.6403 + endloop + endfacet + facet normal -0.451802 0.0363341 0.891378 + outer loop + vertex 0.909528 1.59277 2.64221 + vertex 0.909593 1.59775 2.64204 + vertex 0.906183 1.594 2.64047 + endloop + endfacet + facet normal -0.452342 0.0345765 0.891174 + outer loop + vertex 0.906079 1.58902 2.64061 + vertex 0.909528 1.59277 2.64221 + vertex 0.906183 1.594 2.64047 + endloop + endfacet + facet normal -0.61883 0.0350372 0.784743 + outer loop + vertex 0.906183 1.594 2.64047 + vertex 0.903348 1.59103 2.63836 + vertex 0.906079 1.58902 2.64061 + endloop + endfacet + facet normal -0.618322 0.0361173 0.785094 + outer loop + vertex 0.903348 1.59103 2.63836 + vertex 0.903213 1.58603 2.63849 + vertex 0.906079 1.58902 2.64061 + endloop + endfacet + facet normal -0.616735 0.0336263 0.786453 + outer loop + vertex 0.906079 1.58902 2.64061 + vertex 0.903213 1.58603 2.63849 + vertex 0.905971 1.58402 2.64074 + endloop + endfacet + facet normal -0.454065 0.0327575 0.890366 + outer loop + vertex 0.905971 1.58402 2.64074 + vertex 0.909452 1.58777 2.64237 + vertex 0.906079 1.58902 2.64061 + endloop + endfacet + facet normal -0.454975 0.0338236 0.889861 + outer loop + vertex 0.909377 1.58277 2.64252 + vertex 0.909452 1.58777 2.64237 + vertex 0.905971 1.58402 2.64074 + endloop + endfacet + facet normal -0.455342 0.032624 0.889719 + outer loop + vertex 0.90586 1.57902 2.64086 + vertex 0.909377 1.58277 2.64252 + vertex 0.905971 1.58402 2.64074 + endloop + endfacet + facet normal -0.617486 0.0335896 0.785864 + outer loop + vertex 0.905971 1.58402 2.64074 + vertex 0.903088 1.58104 2.6386 + vertex 0.90586 1.57902 2.64086 + endloop + endfacet + facet normal -0.617001 0.0346343 0.7862 + outer loop + vertex 0.903088 1.58104 2.6386 + vertex 0.902957 1.57603 2.63872 + vertex 0.90586 1.57902 2.64086 + endloop + endfacet + facet normal -0.617168 0.0349003 0.786057 + outer loop + vertex 0.90586 1.57902 2.64086 + vertex 0.902957 1.57603 2.63872 + vertex 0.90574 1.57402 2.64099 + endloop + endfacet + facet normal -0.452715 0.0336663 0.891019 + outer loop + vertex 0.90574 1.57402 2.64099 + vertex 0.90931 1.57778 2.64266 + vertex 0.90586 1.57902 2.64086 + endloop + endfacet + facet normal -0.454379 0.0356577 0.890094 + outer loop + vertex 0.909205 1.57279 2.64281 + vertex 0.90931 1.57778 2.64266 + vertex 0.90574 1.57402 2.64099 + endloop + endfacet + facet normal -0.455071 0.0333242 0.889831 + outer loop + vertex 0.905616 1.56904 2.64111 + vertex 0.909205 1.57279 2.64281 + vertex 0.90574 1.57402 2.64099 + endloop + endfacet + facet normal -0.616013 0.0347987 0.786967 + outer loop + vertex 0.90574 1.57402 2.64099 + vertex 0.902821 1.57103 2.63884 + vertex 0.905616 1.56904 2.64111 + endloop + endfacet + facet normal -0.616717 0.0332544 0.786482 + outer loop + vertex 0.902821 1.57103 2.63884 + vertex 0.902689 1.56605 2.63894 + vertex 0.905616 1.56904 2.64111 + endloop + endfacet + facet normal -0.616556 0.0329976 0.786619 + outer loop + vertex 0.905616 1.56904 2.64111 + vertex 0.902689 1.56605 2.63894 + vertex 0.905497 1.56408 2.64123 + endloop + endfacet + facet normal -0.452422 0.0314955 0.891248 + outer loop + vertex 0.905497 1.56408 2.64123 + vertex 0.909116 1.56784 2.64293 + vertex 0.905616 1.56904 2.64111 + endloop + endfacet + facet normal -0.445164 0.0227543 0.89516 + outer loop + vertex 0.909078 1.56291 2.64304 + vertex 0.909116 1.56784 2.64293 + vertex 0.905497 1.56408 2.64123 + endloop + endfacet + facet normal -0.446241 0.0187685 0.894716 + outer loop + vertex 0.90545 1.55915 2.64131 + vertex 0.909078 1.56291 2.64304 + vertex 0.905497 1.56408 2.64123 + endloop + endfacet + facet normal -0.612778 0.0186843 0.790034 + outer loop + vertex 0.905497 1.56408 2.64123 + vertex 0.902574 1.56109 2.63903 + vertex 0.90545 1.55915 2.64131 + endloop + endfacet + facet normal -0.611839 0.0208669 0.790707 + outer loop + vertex 0.902574 1.56109 2.63903 + vertex 0.902501 1.55612 2.63911 + vertex 0.90545 1.55915 2.64131 + endloop + endfacet + facet normal -0.607691 0.0144017 0.794043 + outer loop + vertex 0.90545 1.55915 2.64131 + vertex 0.902501 1.55612 2.63911 + vertex 0.905438 1.5542 2.64139 + endloop + endfacet + facet normal -0.445376 0.0156681 0.895206 + outer loop + vertex 0.905438 1.5542 2.64139 + vertex 0.90908 1.55792 2.64314 + vertex 0.90545 1.55915 2.64131 + endloop + endfacet + facet normal -0.441983 0.0115332 0.896949 + outer loop + vertex 0.909082 1.55289 2.6432 + vertex 0.90908 1.55792 2.64314 + vertex 0.905438 1.5542 2.64139 + endloop + endfacet + facet normal -0.440916 0.015172 0.89742 + outer loop + vertex 0.905427 1.54927 2.64147 + vertex 0.909082 1.55289 2.6432 + vertex 0.905438 1.5542 2.64139 + endloop + endfacet + facet normal -0.602862 0.0139533 0.797723 + outer loop + vertex 0.905438 1.5542 2.64139 + vertex 0.902484 1.55113 2.63921 + vertex 0.905427 1.54927 2.64147 + endloop + endfacet + facet normal -0.597002 0.0281028 0.801748 + outer loop + vertex 0.902484 1.55113 2.63921 + vertex 0.90254 1.54622 2.63942 + vertex 0.905427 1.54927 2.64147 + endloop + endfacet + facet normal -0.598859 0.0308639 0.800259 + outer loop + vertex 0.905427 1.54927 2.64147 + vertex 0.90254 1.54622 2.63942 + vertex 0.905245 1.54457 2.64151 + endloop + endfacet + facet normal -0.440301 0.0256267 0.897484 + outer loop + vertex 0.905245 1.54457 2.64151 + vertex 0.908925 1.54778 2.64323 + vertex 0.905427 1.54927 2.64147 + endloop + endfacet + facet normal -0.436414 0.0200807 0.899522 + outer loop + vertex 0.90827 1.54217 2.64303 + vertex 0.908925 1.54778 2.64323 + vertex 0.905245 1.54457 2.64151 + endloop + endfacet + facet normal -0.444713 0.00717227 0.895645 + outer loop + vertex 0.904568 1.54089 2.64121 + vertex 0.90827 1.54217 2.64303 + vertex 0.905245 1.54457 2.64151 + endloop + endfacet + facet normal -0.584241 0.0399163 0.810598 + outer loop + vertex 0.905245 1.54457 2.64151 + vertex 0.902805 1.54243 2.63986 + vertex 0.904568 1.54089 2.64121 + endloop + endfacet + facet normal -0.444109 0.00496852 0.895959 + outer loop + vertex 0.904568 1.54089 2.64121 + vertex 0.90511 1.53758 2.64149 + vertex 0.90827 1.54217 2.64303 + endloop + endfacet + facet normal -0.448188 0.00846463 0.893899 + outer loop + vertex 0.90511 1.53758 2.64149 + vertex 0.908843 1.53708 2.64337 + vertex 0.90827 1.54217 2.64303 + endloop + endfacet + facet normal -0.448086 0.00938927 0.893941 + outer loop + vertex 0.905317 1.533 2.64164 + vertex 0.908843 1.53708 2.64337 + vertex 0.90511 1.53758 2.64149 + endloop + endfacet + facet normal -0.449372 0.0107805 0.893279 + outer loop + vertex 0.909036 1.53212 2.64353 + vertex 0.908843 1.53708 2.64337 + vertex 0.905317 1.533 2.64164 + endloop + endfacet + facet normal -0.449507 0.0100871 0.89322 + outer loop + vertex 0.905354 1.52809 2.64172 + vertex 0.909036 1.53212 2.64353 + vertex 0.905317 1.533 2.64164 + endloop + endfacet + facet normal -0.453101 0.0142078 0.891346 + outer loop + vertex 0.908978 1.52693 2.64358 + vertex 0.909036 1.53212 2.64353 + vertex 0.905354 1.52809 2.64172 + endloop + endfacet + facet normal -0.454079 0.0104376 0.8909 + outer loop + vertex 0.905306 1.52303 2.64175 + vertex 0.908978 1.52693 2.64358 + vertex 0.905354 1.52809 2.64172 + endloop + endfacet + facet normal -0.459892 0.0173587 0.887805 + outer loop + vertex 0.908805 1.5217 2.64359 + vertex 0.908978 1.52693 2.64358 + vertex 0.905306 1.52303 2.64175 + endloop + endfacet + facet normal -0.46365 0.00491038 0.886005 + outer loop + vertex 0.905283 1.51799 2.64177 + vertex 0.908805 1.5217 2.64359 + vertex 0.905306 1.52303 2.64175 + endloop + endfacet + facet normal -0.462056 0.00298881 0.886845 + outer loop + vertex 0.908783 1.51665 2.6436 + vertex 0.908805 1.5217 2.64359 + vertex 0.905283 1.51799 2.64177 + endloop + endfacet + facet normal -0.463369 -0.00137795 0.886164 + outer loop + vertex 0.905312 1.513 2.64178 + vertex 0.908783 1.51665 2.6436 + vertex 0.905283 1.51799 2.64177 + endloop + endfacet + facet normal -0.463328 -0.0014276 0.886186 + outer loop + vertex 0.908819 1.51166 2.64361 + vertex 0.908783 1.51665 2.6436 + vertex 0.905312 1.513 2.64178 + endloop + endfacet + facet normal -0.463847 -0.00315997 0.88591 + outer loop + vertex 0.905345 1.50804 2.64178 + vertex 0.908819 1.51166 2.64361 + vertex 0.905312 1.513 2.64178 + endloop + endfacet + facet normal -0.462945 -0.00426097 0.886377 + outer loop + vertex 0.908839 1.5067 2.64359 + vertex 0.908819 1.51166 2.64361 + vertex 0.905345 1.50804 2.64178 + endloop + endfacet + facet normal -0.462878 -0.00403853 0.886413 + outer loop + vertex 0.905349 1.50308 2.64176 + vertex 0.908839 1.5067 2.64359 + vertex 0.905345 1.50804 2.64178 + endloop + endfacet + facet normal -0.462802 -0.00413189 0.886452 + outer loop + vertex 0.908826 1.50174 2.64356 + vertex 0.908839 1.5067 2.64359 + vertex 0.905349 1.50308 2.64176 + endloop + endfacet + facet normal -0.464341 -0.00927581 0.885608 + outer loop + vertex 0.905354 1.4981 2.64171 + vertex 0.908826 1.50174 2.64356 + vertex 0.905349 1.50308 2.64176 + endloop + endfacet + facet normal -0.465071 -0.00838873 0.885234 + outer loop + vertex 0.908871 1.4968 2.64354 + vertex 0.908826 1.50174 2.64356 + vertex 0.905354 1.4981 2.64171 + endloop + endfacet + facet normal -0.466594 -0.0137563 0.884365 + outer loop + vertex 0.905446 1.49299 2.64167 + vertex 0.908871 1.4968 2.64354 + vertex 0.905354 1.4981 2.64171 + endloop + endfacet + facet normal -0.465181 -0.0153743 0.885082 + outer loop + vertex 0.909161 1.49197 2.64361 + vertex 0.908871 1.4968 2.64354 + vertex 0.905446 1.49299 2.64167 + endloop + endfacet + facet normal -0.462268 -0.00164721 0.886739 + outer loop + vertex 0.905951 1.48755 2.64193 + vertex 0.909161 1.49197 2.64361 + vertex 0.905446 1.49299 2.64167 + endloop + endfacet + facet normal -0.436798 -0.0248902 0.899215 + outer loop + vertex 0.90989 1.48788 2.64385 + vertex 0.909161 1.49197 2.64361 + vertex 0.905951 1.48755 2.64193 + endloop + endfacet + facet normal -0.438532 -0.00174166 0.898714 + outer loop + vertex 0.908507 1.48321 2.64317 + vertex 0.90989 1.48788 2.64385 + vertex 0.905951 1.48755 2.64193 + endloop + endfacet + facet normal -0.459073 -0.0168426 0.888239 + outer loop + vertex 0.904856 1.48307 2.64128 + vertex 0.908507 1.48321 2.64317 + vertex 0.905951 1.48755 2.64193 + endloop + endfacet + facet normal -0.585813 0.0255119 0.810045 + outer loop + vertex 0.904856 1.48307 2.64128 + vertex 0.905951 1.48755 2.64193 + vertex 0.902947 1.48486 2.63984 + endloop + endfacet + facet normal -0.619631 -0.0311211 0.784276 + outer loop + vertex 0.902518 1.48093 2.63935 + vertex 0.904856 1.48307 2.64128 + vertex 0.902947 1.48486 2.63984 + endloop + endfacet + facet normal -0.609316 -0.0488731 0.79142 + outer loop + vertex 0.904856 1.48307 2.64128 + vertex 0.902518 1.48093 2.63935 + vertex 0.905345 1.47925 2.64142 + endloop + endfacet + facet normal -0.606287 -0.0403438 0.794222 + outer loop + vertex 0.902518 1.48093 2.63935 + vertex 0.902615 1.47629 2.63918 + vertex 0.905345 1.47925 2.64142 + endloop + endfacet + facet normal -0.606154 -0.0405366 0.794314 + outer loop + vertex 0.905345 1.47925 2.64142 + vertex 0.902615 1.47629 2.63918 + vertex 0.905653 1.47449 2.64141 + endloop + endfacet + facet normal -0.464076 -0.0314659 0.885236 + outer loop + vertex 0.905653 1.47449 2.64141 + vertex 0.908877 1.47801 2.64323 + vertex 0.905345 1.47925 2.64142 + endloop + endfacet + facet normal -0.461798 -0.0228632 0.88669 + outer loop + vertex 0.908877 1.47801 2.64323 + vertex 0.908507 1.48321 2.64317 + vertex 0.905345 1.47925 2.64142 + endloop + endfacet + facet normal -0.603174 -0.0322004 0.796959 + outer loop + vertex 0.902615 1.47629 2.63918 + vertex 0.902756 1.47137 2.63909 + vertex 0.905653 1.47449 2.64141 + endloop + endfacet + facet normal -0.605377 -0.0290056 0.79541 + outer loop + vertex 0.905653 1.47449 2.64141 + vertex 0.902756 1.47137 2.63909 + vertex 0.90583 1.46953 2.64136 + endloop + endfacet + facet normal -0.461358 -0.024733 0.886869 + outer loop + vertex 0.90583 1.46953 2.64136 + vertex 0.909262 1.47315 2.64325 + vertex 0.905653 1.47449 2.64141 + endloop + endfacet + facet normal -0.463457 -0.0321877 0.885534 + outer loop + vertex 0.909262 1.47315 2.64325 + vertex 0.908877 1.47801 2.64323 + vertex 0.905653 1.47449 2.64141 + endloop + endfacet + facet normal -0.461991 -0.0239726 0.886561 + outer loop + vertex 0.909417 1.46815 2.6432 + vertex 0.909262 1.47315 2.64325 + vertex 0.90583 1.46953 2.64136 + endloop + endfacet + facet normal -0.461071 -0.020834 0.887119 + outer loop + vertex 0.905887 1.4645 2.64128 + vertex 0.909417 1.46815 2.6432 + vertex 0.90583 1.46953 2.64136 + endloop + endfacet + facet normal -0.606045 -0.0208557 0.795157 + outer loop + vertex 0.90583 1.46953 2.64136 + vertex 0.902846 1.46637 2.63901 + vertex 0.905887 1.4645 2.64128 + endloop + endfacet + facet normal -0.605472 -0.0193447 0.795631 + outer loop + vertex 0.902846 1.46637 2.63901 + vertex 0.902891 1.46134 2.63892 + vertex 0.905887 1.4645 2.64128 + endloop + endfacet + facet normal -0.606479 -0.0178424 0.794899 + outer loop + vertex 0.905887 1.4645 2.64128 + vertex 0.902891 1.46134 2.63892 + vertex 0.9059 1.45948 2.64117 + endloop + endfacet + facet normal -0.465204 -0.0193165 0.884992 + outer loop + vertex 0.9059 1.45948 2.64117 + vertex 0.909423 1.46312 2.6431 + vertex 0.905887 1.4645 2.64128 + endloop + endfacet + facet normal -0.463756 -0.0210995 0.885712 + outer loop + vertex 0.909433 1.4581 2.64299 + vertex 0.909423 1.46312 2.6431 + vertex 0.9059 1.45948 2.64117 + endloop + endfacet + facet normal -0.464592 -0.0239131 0.885202 + outer loop + vertex 0.905949 1.45448 2.64106 + vertex 0.909433 1.4581 2.64299 + vertex 0.9059 1.45948 2.64117 + endloop + endfacet + facet normal -0.608761 -0.0233084 0.793011 + outer loop + vertex 0.9059 1.45948 2.64117 + vertex 0.902956 1.45635 2.63882 + vertex 0.905949 1.45448 2.64106 + endloop + endfacet + facet normal -0.610786 -0.0286285 0.791278 + outer loop + vertex 0.902956 1.45635 2.63882 + vertex 0.903053 1.45135 2.63872 + vertex 0.905949 1.45448 2.64106 + endloop + endfacet + facet normal -0.61115 -0.0280942 0.791016 + outer loop + vertex 0.905949 1.45448 2.64106 + vertex 0.903053 1.45135 2.63872 + vertex 0.906034 1.44947 2.64095 + endloop + endfacet + facet normal -0.46342 -0.027707 0.885706 + outer loop + vertex 0.906034 1.44947 2.64095 + vertex 0.909509 1.45309 2.64288 + vertex 0.905949 1.45448 2.64106 + endloop + endfacet + facet normal -0.464346 -0.0265766 0.885255 + outer loop + vertex 0.909585 1.4481 2.64277 + vertex 0.909509 1.45309 2.64288 + vertex 0.906034 1.44947 2.64095 + endloop + endfacet + facet normal -0.464796 -0.0281163 0.884971 + outer loop + vertex 0.90612 1.44445 2.64084 + vertex 0.909585 1.4481 2.64277 + vertex 0.906034 1.44947 2.64095 + endloop + endfacet + facet normal -0.615104 -0.0284688 0.787932 + outer loop + vertex 0.906034 1.44947 2.64095 + vertex 0.903172 1.44635 2.6386 + vertex 0.90612 1.44445 2.64084 + endloop + endfacet + facet normal -0.617448 -0.0345602 0.785852 + outer loop + vertex 0.903172 1.44635 2.6386 + vertex 0.903301 1.44133 2.63848 + vertex 0.90612 1.44445 2.64084 + endloop + endfacet + facet normal -0.620323 -0.0303905 0.783757 + outer loop + vertex 0.90612 1.44445 2.64084 + vertex 0.903301 1.44133 2.63848 + vertex 0.906208 1.43942 2.64071 + endloop + endfacet + facet normal -0.469366 -0.0302167 0.882486 + outer loop + vertex 0.906208 1.43942 2.64071 + vertex 0.909616 1.44315 2.64265 + vertex 0.90612 1.44445 2.64084 + endloop + endfacet + facet normal -0.470809 -0.0285284 0.881774 + outer loop + vertex 0.909671 1.4382 2.64252 + vertex 0.909616 1.44315 2.64265 + vertex 0.906208 1.43942 2.64071 + endloop + endfacet + facet normal -0.471632 -0.0316698 0.881227 + outer loop + vertex 0.906298 1.43436 2.64058 + vertex 0.909671 1.4382 2.64252 + vertex 0.906208 1.43942 2.64071 + endloop + endfacet + facet normal -0.627843 -0.0317043 0.777694 + outer loop + vertex 0.906208 1.43942 2.64071 + vertex 0.903443 1.4363 2.63835 + vertex 0.906298 1.43436 2.64058 + endloop + endfacet + facet normal -0.630039 -0.0372467 0.77567 + outer loop + vertex 0.903443 1.4363 2.63835 + vertex 0.903575 1.43127 2.63822 + vertex 0.906298 1.43436 2.64058 + endloop + endfacet + facet normal -0.632702 -0.0333762 0.773676 + outer loop + vertex 0.906298 1.43436 2.64058 + vertex 0.903575 1.43127 2.63822 + vertex 0.906382 1.42931 2.64043 + endloop + endfacet + facet normal -0.475763 -0.0338378 0.878922 + outer loop + vertex 0.906382 1.42931 2.64043 + vertex 0.909719 1.43317 2.64238 + vertex 0.906298 1.43436 2.64058 + endloop + endfacet + facet normal -0.481015 -0.0279474 0.876267 + outer loop + vertex 0.909721 1.42809 2.64222 + vertex 0.909719 1.43317 2.64238 + vertex 0.906382 1.42931 2.64043 + endloop + endfacet + facet normal -0.482902 -0.03503 0.874974 + outer loop + vertex 0.906456 1.42429 2.64027 + vertex 0.909721 1.42809 2.64222 + vertex 0.906382 1.42931 2.64043 + endloop + endfacet + facet normal -0.638638 -0.0339352 0.768759 + outer loop + vertex 0.906382 1.42931 2.64043 + vertex 0.903706 1.42627 2.63807 + vertex 0.906456 1.42429 2.64027 + endloop + endfacet + facet normal -0.641016 -0.0397449 0.766498 + outer loop + vertex 0.903706 1.42627 2.63807 + vertex 0.903841 1.42128 2.63793 + vertex 0.906456 1.42429 2.64027 + endloop + endfacet + facet normal -0.641923 -0.03842 0.765806 + outer loop + vertex 0.906456 1.42429 2.64027 + vertex 0.903841 1.42128 2.63793 + vertex 0.906556 1.4193 2.6401 + endloop + endfacet + facet normal -0.487059 -0.0388974 0.872503 + outer loop + vertex 0.906556 1.4193 2.6401 + vertex 0.909721 1.42305 2.64204 + vertex 0.906456 1.42429 2.64027 + endloop + endfacet + facet normal -0.483583 -0.0427366 0.874255 + outer loop + vertex 0.909806 1.41804 2.64184 + vertex 0.909721 1.42305 2.64204 + vertex 0.906556 1.4193 2.6401 + endloop + endfacet + facet normal -0.484138 -0.0447344 0.873847 + outer loop + vertex 0.90675 1.41431 2.63995 + vertex 0.909806 1.41804 2.64184 + vertex 0.906556 1.4193 2.6401 + endloop + endfacet + facet normal -0.644022 -0.0476917 0.763519 + outer loop + vertex 0.906556 1.4193 2.6401 + vertex 0.904021 1.41628 2.63778 + vertex 0.90675 1.41431 2.63995 + endloop + endfacet + facet normal -0.645777 -0.0520635 0.761749 + outer loop + vertex 0.904021 1.41628 2.63778 + vertex 0.90428 1.4112 2.63765 + vertex 0.90675 1.41431 2.63995 + endloop + endfacet + facet normal -0.643678 -0.0548985 0.763325 + outer loop + vertex 0.90675 1.41431 2.63995 + vertex 0.90428 1.4112 2.63765 + vertex 0.907101 1.40931 2.63989 + endloop + endfacet + facet normal -0.48175 -0.0449315 0.875156 + outer loop + vertex 0.907101 1.40931 2.63989 + vertex 0.910042 1.41301 2.6417 + vertex 0.90675 1.41431 2.63995 + endloop + endfacet + facet normal -0.470116 -0.0569379 0.880766 + outer loop + vertex 0.91063 1.40771 2.64167 + vertex 0.910042 1.41301 2.6417 + vertex 0.907101 1.40931 2.63989 + endloop + endfacet + facet normal -0.459443 -0.025485 0.887842 + outer loop + vertex 0.907542 1.40519 2.64 + vertex 0.91063 1.40771 2.64167 + vertex 0.907101 1.40931 2.63989 + endloop + endfacet + facet normal -0.649654 -0.0492873 0.75863 + outer loop + vertex 0.907542 1.40519 2.64 + vertex 0.907101 1.40931 2.63989 + vertex 0.904719 1.40562 2.63761 + endloop + endfacet + facet normal -0.643959 -0.055671 0.763032 + outer loop + vertex 0.90428 1.4112 2.63765 + vertex 0.904719 1.40562 2.63761 + vertex 0.907101 1.40931 2.63989 + endloop + endfacet + facet normal -0.482264 -0.0467376 0.874779 + outer loop + vertex 0.910042 1.41301 2.6417 + vertex 0.909806 1.41804 2.64184 + vertex 0.90675 1.41431 2.63995 + endloop + endfacet + facet normal -0.645089 -0.0461703 0.762711 + outer loop + vertex 0.903841 1.42128 2.63793 + vertex 0.904021 1.41628 2.63778 + vertex 0.906556 1.4193 2.6401 + endloop + endfacet + facet normal -0.485263 -0.032384 0.873768 + outer loop + vertex 0.909721 1.42305 2.64204 + vertex 0.909721 1.42809 2.64222 + vertex 0.906456 1.42429 2.64027 + endloop + endfacet + facet normal -0.635045 -0.0392072 0.77148 + outer loop + vertex 0.903575 1.43127 2.63822 + vertex 0.903706 1.42627 2.63807 + vertex 0.906382 1.42931 2.64043 + endloop + endfacet + facet normal -0.474401 -0.0285357 0.879846 + outer loop + vertex 0.909719 1.43317 2.64238 + vertex 0.909671 1.4382 2.64252 + vertex 0.906298 1.43436 2.64058 + endloop + endfacet + facet normal -0.623351 -0.0382024 0.781008 + outer loop + vertex 0.903301 1.44133 2.63848 + vertex 0.903443 1.4363 2.63835 + vertex 0.906208 1.43942 2.64071 + endloop + endfacet + facet normal -0.46777 -0.024514 0.88351 + outer loop + vertex 0.909616 1.44315 2.64265 + vertex 0.909585 1.4481 2.64277 + vertex 0.90612 1.44445 2.64084 + endloop + endfacet + facet normal -0.612656 -0.0320436 0.7897 + outer loop + vertex 0.903053 1.45135 2.63872 + vertex 0.903172 1.44635 2.6386 + vertex 0.906034 1.44947 2.64095 + endloop + endfacet + facet normal -0.462908 -0.0259697 0.886026 + outer loop + vertex 0.909509 1.45309 2.64288 + vertex 0.909433 1.4581 2.64299 + vertex 0.905949 1.45448 2.64106 + endloop + endfacet + facet normal -0.608637 -0.0234924 0.793101 + outer loop + vertex 0.902891 1.46134 2.63892 + vertex 0.902956 1.45635 2.63882 + vertex 0.9059 1.45948 2.64117 + endloop + endfacet + facet normal -0.464424 -0.0167131 0.885455 + outer loop + vertex 0.909423 1.46312 2.6431 + vertex 0.909417 1.46815 2.6432 + vertex 0.905887 1.4645 2.64128 + endloop + endfacet + facet normal -0.60367 -0.0243733 0.796861 + outer loop + vertex 0.902756 1.47137 2.63909 + vertex 0.902846 1.46637 2.63901 + vertex 0.90583 1.46953 2.64136 + endloop + endfacet + facet normal -0.458701 -0.0260058 0.88821 + outer loop + vertex 0.905345 1.47925 2.64142 + vertex 0.908507 1.48321 2.64317 + vertex 0.904856 1.48307 2.64128 + endloop + endfacet + facet normal -0.590506 0.0510399 0.805418 + outer loop + vertex 0.90254 1.54622 2.63942 + vertex 0.902805 1.54243 2.63986 + vertex 0.905245 1.54457 2.64151 + endloop + endfacet + facet normal -0.443034 0.0178295 0.896327 + outer loop + vertex 0.908925 1.54778 2.64323 + vertex 0.909082 1.55289 2.6432 + vertex 0.905427 1.54927 2.64147 + endloop + endfacet + facet normal -0.605919 0.0186115 0.795309 + outer loop + vertex 0.902501 1.55612 2.63911 + vertex 0.902484 1.55113 2.63921 + vertex 0.905438 1.5542 2.64139 + endloop + endfacet + facet normal -0.444949 0.0172095 0.895391 + outer loop + vertex 0.90908 1.55792 2.64314 + vertex 0.909078 1.56291 2.64304 + vertex 0.90545 1.55915 2.64131 + endloop + endfacet + facet normal -0.618735 0.0281384 0.785096 + outer loop + vertex 0.902689 1.56605 2.63894 + vertex 0.902574 1.56109 2.63903 + vertex 0.905497 1.56408 2.64123 + endloop + endfacet + facet normal -0.452712 0.0304765 0.891136 + outer loop + vertex 0.909116 1.56784 2.64293 + vertex 0.909205 1.57279 2.64281 + vertex 0.905616 1.56904 2.64111 + endloop + endfacet + facet normal -0.616705 0.0359008 0.786375 + outer loop + vertex 0.902957 1.57603 2.63872 + vertex 0.902821 1.57103 2.63884 + vertex 0.90574 1.57402 2.64099 + endloop + endfacet + facet normal -0.453632 0.0305988 0.890664 + outer loop + vertex 0.90931 1.57778 2.64266 + vertex 0.909377 1.58277 2.64252 + vertex 0.90586 1.57902 2.64086 + endloop + endfacet + facet normal -0.617062 0.0329221 0.786225 + outer loop + vertex 0.903213 1.58603 2.63849 + vertex 0.903088 1.58104 2.6386 + vertex 0.905971 1.58402 2.64074 + endloop + endfacet + facet normal -0.453202 0.0355703 0.890698 + outer loop + vertex 0.909452 1.58777 2.64237 + vertex 0.909528 1.59277 2.64221 + vertex 0.906079 1.58902 2.64061 + endloop + endfacet + facet normal -0.619366 0.0358761 0.784282 + outer loop + vertex 0.903468 1.596 2.63823 + vertex 0.903348 1.59103 2.63836 + vertex 0.906183 1.594 2.64047 + endloop + endfacet + facet normal -0.453949 0.0426528 0.890006 + outer loop + vertex 0.909593 1.59775 2.64204 + vertex 0.909671 1.60276 2.64184 + vertex 0.906289 1.59899 2.6403 + endloop + endfacet + facet normal -0.619935 0.0478715 0.783191 + outer loop + vertex 0.903781 1.60603 2.6379 + vertex 0.903601 1.60099 2.63806 + vertex 0.906419 1.60402 2.64011 + endloop + endfacet + facet normal -0.4556 0.0445257 0.88907 + outer loop + vertex 0.909773 1.60779 2.64163 + vertex 0.909894 1.61274 2.64144 + vertex 0.906615 1.60907 2.63995 + endloop + endfacet + facet normal -0.628015 0.0514935 0.776495 + outer loop + vertex 0.904719 1.61684 2.63794 + vertex 0.904091 1.6112 2.6378 + vertex 0.906923 1.61395 2.63991 + endloop + endfacet + facet normal -0.497043 0.0905819 0.862985 + outer loop + vertex 0.907451 1.61774 2.6401 + vertex 0.909399 1.62037 2.64095 + vertex 0.907108 1.62102 2.63956 + endloop + endfacet + facet normal -0.684407 0.0749782 0.725235 + outer loop + vertex 0.902771 1.63624 2.63436 + vertex 0.902934 1.63253 2.63489 + vertex 0.905022 1.63403 2.63671 + endloop + endfacet + facet normal -0.591137 0.0981666 0.800575 + outer loop + vertex 0.907981 1.63615 2.63873 + vertex 0.908973 1.64173 2.63878 + vertex 0.905466 1.63873 2.63656 + endloop + endfacet + facet normal -0.659736 0.0728343 0.74796 + outer loop + vertex 0.903044 1.64612 2.63361 + vertex 0.90287 1.6411 2.63395 + vertex 0.905792 1.64386 2.63626 + endloop + endfacet + facet normal -0.565576 0.0872085 0.820072 + outer loop + vertex 0.909086 1.64724 2.63822 + vertex 0.90941 1.65248 2.63789 + vertex 0.906014 1.64898 2.63592 + endloop + endfacet + facet normal -0.54749 0.0671679 0.834112 + outer loop + vertex 0.909637 1.65763 2.6376 + vertex 0.90983 1.6627 2.63732 + vertex 0.906453 1.65902 2.6354 + endloop + endfacet + facet normal -0.698316 0.0902339 0.710079 + outer loop + vertex 0.905456 1.67775 2.63252 + vertex 0.90226 1.67566 2.62965 + vertex 0.904104 1.67388 2.63169 + endloop + endfacet + facet normal -0.671373 0.0763028 0.737182 + outer loop + vertex 0.906341 1.67315 2.63388 + vertex 0.904176 1.67041 2.63219 + vertex 0.906657 1.6688 2.63461 + endloop + endfacet + facet normal -0.70081 0.0855117 0.708204 + outer loop + vertex 0.902419 1.67218 2.63022 + vertex 0.904104 1.67388 2.63169 + vertex 0.90226 1.67566 2.62965 + endloop + endfacet + facet normal -0.655631 0.0943818 0.749159 + outer loop + vertex 0.902419 1.67218 2.63022 + vertex 0.90226 1.67566 2.62965 + vertex 0.899723 1.67192 2.6279 + endloop + endfacet + facet normal -0.658732 0.0979706 0.745972 + outer loop + vertex 0.899723 1.67192 2.6279 + vertex 0.90226 1.67566 2.62965 + vertex 0.899619 1.67691 2.62715 + endloop + endfacet + facet normal -0.658982 0.0971993 0.745851 + outer loop + vertex 0.899619 1.67691 2.62715 + vertex 0.90226 1.67566 2.62965 + vertex 0.902102 1.68064 2.62886 + endloop + endfacet + facet normal -0.653012 0.0904385 0.751928 + outer loop + vertex 0.899249 1.68027 2.62642 + vertex 0.899619 1.67691 2.62715 + vertex 0.902102 1.68064 2.62886 + endloop + endfacet + facet normal -0.652935 0.0856316 0.752557 + outer loop + vertex 0.899249 1.68027 2.62642 + vertex 0.902102 1.68064 2.62886 + vertex 0.899811 1.68386 2.6265 + endloop + endfacet + facet normal -0.542583 0.0664603 0.837369 + outer loop + vertex 0.899811 1.68386 2.6265 + vertex 0.896899 1.68112 2.62483 + vertex 0.899249 1.68027 2.62642 + endloop + endfacet + facet normal -0.546479 0.0724552 0.834333 + outer loop + vertex 0.896941 1.68551 2.62448 + vertex 0.896899 1.68112 2.62483 + vertex 0.899811 1.68386 2.6265 + endloop + endfacet + facet normal -0.542411 0.0817052 0.836131 + outer loop + vertex 0.900207 1.68856 2.6263 + vertex 0.896941 1.68551 2.62448 + vertex 0.899811 1.68386 2.6265 + endloop + endfacet + facet normal -0.644582 0.0870003 0.759569 + outer loop + vertex 0.899811 1.68386 2.6265 + vertex 0.902742 1.68603 2.62874 + vertex 0.900207 1.68856 2.6263 + endloop + endfacet + facet normal -0.639666 0.0950179 0.762758 + outer loop + vertex 0.902742 1.68603 2.62874 + vertex 0.90318 1.69111 2.62848 + vertex 0.900207 1.68856 2.6263 + endloop + endfacet + facet normal -0.639204 0.0940488 0.763265 + outer loop + vertex 0.900207 1.68856 2.6263 + vertex 0.90318 1.69111 2.62848 + vertex 0.900577 1.69353 2.626 + endloop + endfacet + facet normal -0.545609 0.0913146 0.83305 + outer loop + vertex 0.900577 1.69353 2.626 + vertex 0.897237 1.69047 2.62415 + vertex 0.900207 1.68856 2.6263 + endloop + endfacet + facet normal -0.550296 0.0988029 0.829103 + outer loop + vertex 0.897674 1.69556 2.62383 + vertex 0.897237 1.69047 2.62415 + vertex 0.900577 1.69353 2.626 + endloop + endfacet + facet normal -0.550658 0.0981156 0.828945 + outer loop + vertex 0.900942 1.69853 2.62565 + vertex 0.897674 1.69556 2.62383 + vertex 0.900577 1.69353 2.626 + endloop + endfacet + facet normal -0.637236 0.0999045 0.764166 + outer loop + vertex 0.900577 1.69353 2.626 + vertex 0.903576 1.6962 2.62815 + vertex 0.900942 1.69853 2.62565 + endloop + endfacet + facet normal -0.63324 0.106961 0.766529 + outer loop + vertex 0.903576 1.6962 2.62815 + vertex 0.903909 1.70114 2.62774 + vertex 0.900942 1.69853 2.62565 + endloop + endfacet + facet normal -0.633179 0.106838 0.766596 + outer loop + vertex 0.900942 1.69853 2.62565 + vertex 0.903909 1.70114 2.62774 + vertex 0.901347 1.70337 2.62531 + endloop + endfacet + facet normal -0.552192 0.104327 0.827164 + outer loop + vertex 0.901347 1.70337 2.62531 + vertex 0.898069 1.70064 2.62347 + vertex 0.900942 1.69853 2.62565 + endloop + endfacet + facet normal -0.549282 0.0990972 0.82974 + outer loop + vertex 0.898484 1.70643 2.62305 + vertex 0.898069 1.70064 2.62347 + vertex 0.901347 1.70337 2.62531 + endloop + endfacet + facet normal -0.546395 0.102869 0.831186 + outer loop + vertex 0.902082 1.70712 2.62533 + vertex 0.898484 1.70643 2.62305 + vertex 0.901347 1.70337 2.62531 + endloop + endfacet + facet normal -0.628989 0.119416 0.768188 + outer loop + vertex 0.901347 1.70337 2.62531 + vertex 0.904147 1.70553 2.62727 + vertex 0.902082 1.70712 2.62533 + endloop + endfacet + facet normal -0.634396 0.10884 0.765308 + outer loop + vertex 0.904091 1.70893 2.62674 + vertex 0.902082 1.70712 2.62533 + vertex 0.904147 1.70553 2.62727 + endloop + endfacet + facet normal -0.622547 0.0859188 0.777852 + outer loop + vertex 0.902082 1.70712 2.62533 + vertex 0.904091 1.70893 2.62674 + vertex 0.901969 1.71059 2.62486 + endloop + endfacet + facet normal -0.545823 0.095854 0.832399 + outer loop + vertex 0.902082 1.70712 2.62533 + vertex 0.901969 1.71059 2.62486 + vertex 0.898484 1.70643 2.62305 + endloop + endfacet + facet normal -0.627733 0.116446 0.76967 + outer loop + vertex 0.903909 1.70114 2.62774 + vertex 0.904147 1.70553 2.62727 + vertex 0.901347 1.70337 2.62531 + endloop + endfacet + facet normal -0.553268 0.102367 0.826689 + outer loop + vertex 0.898069 1.70064 2.62347 + vertex 0.897674 1.69556 2.62383 + vertex 0.900942 1.69853 2.62565 + endloop + endfacet + facet normal -0.636565 0.0985618 0.764899 + outer loop + vertex 0.90318 1.69111 2.62848 + vertex 0.903576 1.6962 2.62815 + vertex 0.900577 1.69353 2.626 + endloop + endfacet + facet normal -0.546895 0.088681 0.832491 + outer loop + vertex 0.897237 1.69047 2.62415 + vertex 0.896941 1.68551 2.62448 + vertex 0.900207 1.68856 2.6263 + endloop + endfacet + facet normal -0.646959 0.0930117 0.756831 + outer loop + vertex 0.902102 1.68064 2.62886 + vertex 0.902742 1.68603 2.62874 + vertex 0.899811 1.68386 2.6265 + endloop + endfacet + facet normal -0.693574 0.0851032 0.715341 + outer loop + vertex 0.903999 1.66598 2.63254 + vertex 0.904176 1.67041 2.63219 + vertex 0.901774 1.66847 2.63009 + endloop + endfacet + facet normal -0.661117 0.0787666 0.746137 + outer loop + vertex 0.903999 1.66598 2.63254 + vertex 0.90376 1.66107 2.63285 + vertex 0.906629 1.66401 2.63508 + endloop + endfacet + facet normal -0.647755 0.0840186 0.757202 + outer loop + vertex 0.898912 1.66638 2.62788 + vertex 0.898478 1.66125 2.62808 + vertex 0.90134 1.6636 2.63026 + endloop + endfacet + facet normal -0.683971 0.0734339 0.725804 + outer loop + vertex 0.903496 1.65607 2.63311 + vertex 0.90376 1.66107 2.63285 + vertex 0.900997 1.65858 2.6305 + endloop + endfacet + facet normal -0.650354 0.0680082 0.756581 + outer loop + vertex 0.903496 1.65607 2.63311 + vertex 0.903247 1.6511 2.63334 + vertex 0.906242 1.65401 2.63565 + endloop + endfacet + facet normal -0.639862 0.0793195 0.764385 + outer loop + vertex 0.898068 1.65624 2.62826 + vertex 0.897349 1.65091 2.62821 + vertex 0.900631 1.65355 2.63068 + endloop + endfacet + facet normal -0.677234 0.0677256 0.732644 + outer loop + vertex 0.903044 1.64612 2.63361 + vertex 0.903247 1.6511 2.63334 + vertex 0.900376 1.6485 2.63093 + endloop + endfacet + facet normal -0.643852 0.0639983 0.762469 + outer loop + vertex 0.897531 1.64564 2.62878 + vertex 0.897428 1.6406 2.62911 + vertex 0.900258 1.64345 2.63126 + endloop + endfacet + facet normal -0.690627 0.0744694 0.719367 + outer loop + vertex 0.902771 1.63624 2.63436 + vertex 0.90287 1.6411 2.63395 + vertex 0.900187 1.63836 2.63166 + endloop + endfacet + facet normal -0.65471 0.0362419 0.755011 + outer loop + vertex 0.900364 1.6329 2.63229 + vertex 0.897203 1.63041 2.62967 + vertex 0.899673 1.62786 2.63193 + endloop + endfacet + facet normal -0.653686 0.0379455 0.755814 + outer loop + vertex 0.897203 1.63041 2.62967 + vertex 0.897086 1.62582 2.6298 + vertex 0.899673 1.62786 2.63193 + endloop + endfacet + facet normal -0.648307 0.0257414 0.760944 + outer loop + vertex 0.899673 1.62786 2.63193 + vertex 0.897086 1.62582 2.6298 + vertex 0.899135 1.62428 2.6316 + endloop + endfacet + facet normal -0.714169 0.0414998 0.698742 + outer loop + vertex 0.899135 1.62428 2.6316 + vertex 0.90166 1.6243 2.63417 + vertex 0.899673 1.62786 2.63193 + endloop + endfacet + facet normal -0.702787 0.0470965 0.709839 + outer loop + vertex 0.904327 1.63058 2.63641 + vertex 0.902258 1.62916 2.63445 + vertex 0.90448 1.62699 2.6368 + endloop + endfacet + facet normal -0.713608 0.0585443 0.698094 + outer loop + vertex 0.899135 1.62428 2.6316 + vertex 0.899441 1.62081 2.6322 + vertex 0.90166 1.6243 2.63417 + endloop + endfacet + facet normal -0.70882 0.0629411 0.702576 + outer loop + vertex 0.904719 1.61684 2.63794 + vertex 0.904476 1.62218 2.63721 + vertex 0.901894 1.61895 2.6349 + endloop + endfacet + facet normal -0.714926 0.0445641 0.697779 + outer loop + vertex 0.898786 1.60613 2.63284 + vertex 0.898651 1.60117 2.63301 + vertex 0.901216 1.6035 2.63549 + endloop + endfacet + facet normal -0.709287 0.0427037 0.703625 + outer loop + vertex 0.903468 1.596 2.63823 + vertex 0.903601 1.60099 2.63806 + vertex 0.90107 1.59853 2.63566 + endloop + endfacet + facet normal -0.718437 0.0361004 0.694655 + outer loop + vertex 0.898524 1.59623 2.63317 + vertex 0.8984 1.59126 2.6333 + vertex 0.900937 1.59356 2.63581 + endloop + endfacet + facet normal -0.709622 0.0365531 0.703634 + outer loop + vertex 0.903213 1.58603 2.63849 + vertex 0.903348 1.59103 2.63836 + vertex 0.900806 1.58858 2.63593 + endloop + endfacet + facet normal -0.722078 0.0290869 0.6912 + outer loop + vertex 0.898282 1.58626 2.63342 + vertex 0.89818 1.58126 2.63352 + vertex 0.90068 1.58358 2.63603 + endloop + endfacet + facet normal -0.71366 0.0351037 0.699612 + outer loop + vertex 0.902957 1.57603 2.63872 + vertex 0.903088 1.58104 2.6386 + vertex 0.90056 1.57858 2.63614 + endloop + endfacet + facet normal -0.730006 0.0289846 0.682826 + outer loop + vertex 0.898086 1.57627 2.63363 + vertex 0.897992 1.57127 2.63374 + vertex 0.900441 1.57358 2.63626 + endloop + endfacet + facet normal -0.717837 0.0339456 0.695383 + outer loop + vertex 0.902689 1.56605 2.63894 + vertex 0.902821 1.57103 2.63884 + vertex 0.900316 1.56858 2.63637 + endloop + endfacet + facet normal -0.737686 0.0263692 0.674629 + outer loop + vertex 0.897891 1.56627 2.63385 + vertex 0.897791 1.56129 2.63393 + vertex 0.900192 1.56359 2.63647 + endloop + endfacet + facet normal -0.71688 0.0210325 0.69688 + outer loop + vertex 0.902501 1.55612 2.63911 + vertex 0.902574 1.56109 2.63903 + vertex 0.900082 1.55861 2.63654 + endloop + endfacet + facet normal -0.740849 0.018162 0.671426 + outer loop + vertex 0.897705 1.5563 2.634 + vertex 0.897654 1.55124 2.63408 + vertex 0.900015 1.55359 2.63662 + endloop + endfacet + facet normal -0.71548 0.022216 0.69828 + outer loop + vertex 0.90254 1.54622 2.63942 + vertex 0.902484 1.55113 2.63921 + vertex 0.900038 1.54843 2.63679 + endloop + endfacet + facet normal -0.745117 0.0107013 0.666848 + outer loop + vertex 0.90032 1.54279 2.63726 + vertex 0.897613 1.54078 2.63427 + vertex 0.899906 1.53744 2.63689 + endloop + endfacet + facet normal -0.745737 0.00974486 0.66617 + outer loop + vertex 0.897613 1.54078 2.63427 + vertex 0.897507 1.53568 2.63423 + vertex 0.899906 1.53744 2.63689 + endloop + endfacet + facet normal -0.714135 0.00566395 0.699985 + outer loop + vertex 0.899806 1.5325 2.63683 + vertex 0.902306 1.52985 2.6394 + vertex 0.902307 1.53465 2.63936 + endloop + endfacet + facet normal -0.744869 0.00803634 0.667162 + outer loop + vertex 0.897457 1.53067 2.63424 + vertex 0.897433 1.52566 2.63428 + vertex 0.899764 1.52754 2.63686 + endloop + endfacet + facet normal -0.71252 0.00494079 0.701635 + outer loop + vertex 0.899741 1.52254 2.63688 + vertex 0.902265 1.51988 2.63946 + vertex 0.902279 1.52488 2.63944 + endloop + endfacet + facet normal -0.60457 0.00504629 0.796536 + outer loop + vertex 0.902265 1.51988 2.63946 + vertex 0.905306 1.52303 2.64175 + vertex 0.902279 1.52488 2.63944 + endloop + endfacet + facet normal -0.602135 0.0112245 0.798315 + outer loop + vertex 0.905306 1.52303 2.64175 + vertex 0.905354 1.52809 2.64172 + vertex 0.902279 1.52488 2.63944 + endloop + endfacet + facet normal -0.601369 0.0100672 0.798908 + outer loop + vertex 0.902279 1.52488 2.63944 + vertex 0.905354 1.52809 2.64172 + vertex 0.902306 1.52985 2.6394 + endloop + endfacet + facet normal -0.602325 0.00750372 0.798216 + outer loop + vertex 0.905354 1.52809 2.64172 + vertex 0.905317 1.533 2.64164 + vertex 0.902306 1.52985 2.6394 + endloop + endfacet + facet normal -0.601598 0.00641295 0.798773 + outer loop + vertex 0.902306 1.52985 2.6394 + vertex 0.905317 1.533 2.64164 + vertex 0.902307 1.53465 2.63936 + endloop + endfacet + facet normal -0.604153 -0.000907597 0.796868 + outer loop + vertex 0.905317 1.533 2.64164 + vertex 0.90511 1.53758 2.64149 + vertex 0.902307 1.53465 2.63936 + endloop + endfacet + facet normal -0.599924 -0.00725353 0.800024 + outer loop + vertex 0.902307 1.53465 2.63936 + vertex 0.90511 1.53758 2.64149 + vertex 0.902334 1.53903 2.63942 + endloop + endfacet + facet normal -0.607492 -0.0305535 0.793738 + outer loop + vertex 0.904568 1.54089 2.64121 + vertex 0.902334 1.53903 2.63942 + vertex 0.90511 1.53758 2.64149 + endloop + endfacet + facet normal -0.604725 0.00528303 0.796417 + outer loop + vertex 0.905283 1.51799 2.64177 + vertex 0.905306 1.52303 2.64175 + vertex 0.902265 1.51988 2.63946 + endloop + endfacet + facet normal -0.607191 -0.000895647 0.794555 + outer loop + vertex 0.902283 1.5149 2.63947 + vertex 0.905283 1.51799 2.64177 + vertex 0.902265 1.51988 2.63946 + endloop + endfacet + facet normal -0.606229 -0.00237776 0.795287 + outer loop + vertex 0.905312 1.513 2.64178 + vertex 0.905283 1.51799 2.64177 + vertex 0.902283 1.5149 2.63947 + endloop + endfacet + facet normal -0.606663 -0.0034766 0.794952 + outer loop + vertex 0.902315 1.50994 2.63948 + vertex 0.905312 1.513 2.64178 + vertex 0.902283 1.5149 2.63947 + endloop + endfacet + facet normal -0.606262 -0.00409534 0.795255 + outer loop + vertex 0.905345 1.50804 2.64178 + vertex 0.905312 1.513 2.64178 + vertex 0.902315 1.50994 2.63948 + endloop + endfacet + facet normal -0.746804 -0.000170653 0.665044 + outer loop + vertex 0.897425 1.52066 2.63429 + vertex 0.897429 1.51567 2.63429 + vertex 0.899743 1.51755 2.63689 + endloop + endfacet + facet normal -0.712983 -0.00424251 0.701169 + outer loop + vertex 0.899762 1.51257 2.6369 + vertex 0.902315 1.50994 2.63948 + vertex 0.902283 1.5149 2.63947 + endloop + endfacet + facet normal -0.606266 -0.00410625 0.795251 + outer loop + vertex 0.902339 1.50497 2.63947 + vertex 0.905345 1.50804 2.64178 + vertex 0.902315 1.50994 2.63948 + endloop + endfacet + facet normal -0.606478 -0.00377862 0.795091 + outer loop + vertex 0.905349 1.50308 2.64176 + vertex 0.905345 1.50804 2.64178 + vertex 0.902339 1.50497 2.63947 + endloop + endfacet + facet normal -0.607496 -0.00635932 0.794297 + outer loop + vertex 0.902342 1.49999 2.63943 + vertex 0.905349 1.50308 2.64176 + vertex 0.902339 1.50497 2.63947 + endloop + endfacet + facet normal -0.606096 -0.00851386 0.795346 + outer loop + vertex 0.905354 1.4981 2.64171 + vertex 0.905349 1.50308 2.64176 + vertex 0.902342 1.49999 2.63943 + endloop + endfacet + facet normal -0.60877 -0.0153651 0.793198 + outer loop + vertex 0.902321 1.49492 2.63932 + vertex 0.905354 1.4981 2.64171 + vertex 0.902342 1.49999 2.63943 + endloop + endfacet + facet normal -0.608521 -0.0157409 0.793381 + outer loop + vertex 0.905446 1.49299 2.64167 + vertex 0.905354 1.4981 2.64171 + vertex 0.902321 1.49492 2.63932 + endloop + endfacet + facet normal -0.610242 -0.0202529 0.791956 + outer loop + vertex 0.902149 1.48926 2.63904 + vertex 0.905446 1.49299 2.64167 + vertex 0.902321 1.49492 2.63932 + endloop + endfacet + facet normal -0.610543 -0.0198293 0.791735 + outer loop + vertex 0.905951 1.48755 2.64193 + vertex 0.905446 1.49299 2.64167 + vertex 0.902149 1.48926 2.63904 + endloop + endfacet + facet normal -0.744191 -0.00266311 0.667962 + outer loop + vertex 0.897443 1.51068 2.6343 + vertex 0.897465 1.50568 2.6343 + vertex 0.89979 1.50759 2.6369 + endloop + endfacet + facet normal -0.711739 -0.00572402 0.70242 + outer loop + vertex 0.899811 1.50261 2.63689 + vertex 0.902342 1.49999 2.63943 + vertex 0.902339 1.50497 2.63947 + endloop + endfacet + facet normal -0.714845 -0.0125079 0.699171 + outer loop + vertex 0.899738 1.49274 2.63664 + vertex 0.902149 1.48926 2.63904 + vertex 0.902321 1.49492 2.63932 + endloop + endfacet + facet normal -0.743744 -0.0107562 0.668379 + outer loop + vertex 0.89749 1.50068 2.63429 + vertex 0.897498 1.49574 2.63422 + vertex 0.899813 1.49764 2.63682 + endloop + endfacet + facet normal -0.718348 -0.0174877 0.695464 + outer loop + vertex 0.899417 1.48861 2.6362 + vertex 0.902149 1.48926 2.63904 + vertex 0.899738 1.49274 2.63664 + endloop + endfacet + facet normal -0.593422 0.0387563 0.803958 + outer loop + vertex 0.902947 1.48486 2.63984 + vertex 0.905951 1.48755 2.64193 + vertex 0.902149 1.48926 2.63904 + endloop + endfacet + facet normal -0.744717 -0.0130643 0.667252 + outer loop + vertex 0.897574 1.4863 2.63413 + vertex 0.897708 1.48139 2.63418 + vertex 0.900265 1.48419 2.63709 + endloop + endfacet + facet normal -0.716008 -0.0392249 0.69699 + outer loop + vertex 0.902615 1.47629 2.63918 + vertex 0.902518 1.48093 2.63935 + vertex 0.900105 1.47873 2.63674 + endloop + endfacet + facet normal -0.733283 -0.0219902 0.679568 + outer loop + vertex 0.897737 1.47635 2.63405 + vertex 0.897788 1.47135 2.63395 + vertex 0.900158 1.47373 2.63658 + endloop + endfacet + facet normal -0.705833 -0.0246797 0.707949 + outer loop + vertex 0.902846 1.46637 2.63901 + vertex 0.902756 1.47137 2.63909 + vertex 0.900234 1.46874 2.63648 + endloop + endfacet + facet normal -0.728522 -0.0203593 0.68472 + outer loop + vertex 0.897848 1.46636 2.63387 + vertex 0.897919 1.46137 2.6338 + vertex 0.900302 1.46374 2.6364 + endloop + endfacet + facet normal -0.706589 -0.0230784 0.707248 + outer loop + vertex 0.902956 1.45635 2.63882 + vertex 0.902891 1.46134 2.63892 + vertex 0.900376 1.45874 2.63632 + endloop + endfacet + facet normal -0.727579 -0.0275365 0.685471 + outer loop + vertex 0.898009 1.45639 2.63371 + vertex 0.898111 1.4514 2.63362 + vertex 0.900477 1.45375 2.63623 + endloop + endfacet + facet normal -0.710001 -0.0324239 0.703453 + outer loop + vertex 0.903172 1.44635 2.6386 + vertex 0.903053 1.45135 2.63872 + vertex 0.900602 1.44877 2.63612 + endloop + endfacet + facet normal -0.723271 -0.0353188 0.68966 + outer loop + vertex 0.898234 1.44642 2.63352 + vertex 0.898369 1.44144 2.6334 + vertex 0.90074 1.44377 2.63601 + endloop + endfacet + facet normal -0.713415 -0.0385995 0.699678 + outer loop + vertex 0.903443 1.4363 2.63835 + vertex 0.903301 1.44133 2.63848 + vertex 0.900892 1.43878 2.63589 + endloop + endfacet + facet normal -0.717868 -0.0376734 0.695159 + outer loop + vertex 0.898503 1.43646 2.63327 + vertex 0.898627 1.43147 2.63313 + vertex 0.901044 1.43379 2.63575 + endloop + endfacet + facet normal -0.718508 -0.0391456 0.694416 + outer loop + vertex 0.903706 1.42627 2.63807 + vertex 0.903575 1.43127 2.63822 + vertex 0.901191 1.42879 2.63561 + endloop + endfacet + facet normal -0.715885 -0.0427916 0.696905 + outer loop + vertex 0.898763 1.42645 2.63299 + vertex 0.898939 1.42144 2.63286 + vertex 0.901341 1.42378 2.63547 + endloop + endfacet + facet normal -0.720507 -0.0467764 0.691869 + outer loop + vertex 0.904021 1.41628 2.63778 + vertex 0.903841 1.42128 2.63793 + vertex 0.901515 1.41877 2.63533 + endloop + endfacet + facet normal -0.715651 -0.0516634 0.696545 + outer loop + vertex 0.899134 1.41645 2.63272 + vertex 0.899308 1.4115 2.63254 + vertex 0.901718 1.41374 2.63518 + endloop + endfacet + facet normal -0.721901 -0.0613373 0.689272 + outer loop + vertex 0.904719 1.40562 2.63761 + vertex 0.90428 1.4112 2.63765 + vertex 0.901907 1.40865 2.63493 + endloop + endfacet + facet normal -0.706353 -0.0607806 0.705245 + outer loop + vertex 0.904729 1.39293 2.63647 + vertex 0.905208 1.39682 2.63729 + vertex 0.903141 1.395 2.63506 + endloop + endfacet + facet normal -0.707857 -0.0631112 0.703531 + outer loop + vertex 0.902785 1.39132 2.63437 + vertex 0.904729 1.39293 2.63647 + vertex 0.903141 1.395 2.63506 + endloop + endfacet + facet normal -0.704032 -0.0716296 0.706546 + outer loop + vertex 0.904729 1.39293 2.63647 + vertex 0.902785 1.39132 2.63437 + vertex 0.905196 1.38894 2.63653 + endloop + endfacet + facet normal -0.647648 -0.0642301 0.759228 + outer loop + vertex 0.905196 1.38894 2.63653 + vertex 0.907434 1.39222 2.63872 + vertex 0.904729 1.39293 2.63647 + endloop + endfacet + facet normal -0.642581 -0.0701919 0.762996 + outer loop + vertex 0.908019 1.38661 2.6387 + vertex 0.907434 1.39222 2.63872 + vertex 0.905196 1.38894 2.63653 + endloop + endfacet + facet normal -0.639991 -0.0645601 0.765666 + outer loop + vertex 0.905537 1.38395 2.6364 + vertex 0.908019 1.38661 2.6387 + vertex 0.905196 1.38894 2.63653 + endloop + endfacet + facet normal -0.697747 -0.0670856 0.713196 + outer loop + vertex 0.905196 1.38894 2.63653 + vertex 0.902877 1.38654 2.63404 + vertex 0.905537 1.38395 2.6364 + endloop + endfacet + facet normal -0.69649 -0.0644505 0.714666 + outer loop + vertex 0.902877 1.38654 2.63404 + vertex 0.903114 1.38152 2.63382 + vertex 0.905537 1.38395 2.6364 + endloop + endfacet + facet normal -0.693249 -0.0704191 0.717249 + outer loop + vertex 0.905537 1.38395 2.6364 + vertex 0.903114 1.38152 2.63382 + vertex 0.905874 1.37892 2.63623 + endloop + endfacet + facet normal -0.636665 -0.0683495 0.768106 + outer loop + vertex 0.905874 1.37892 2.63623 + vertex 0.908406 1.38149 2.63856 + vertex 0.905537 1.38395 2.6364 + endloop + endfacet + facet normal -0.630414 -0.0783077 0.7723 + outer loop + vertex 0.908848 1.37647 2.63841 + vertex 0.908406 1.38149 2.63856 + vertex 0.905874 1.37892 2.63623 + endloop + endfacet + facet normal -0.629249 -0.0758288 0.773496 + outer loop + vertex 0.906231 1.37389 2.63603 + vertex 0.908848 1.37647 2.63841 + vertex 0.905874 1.37892 2.63623 + endloop + endfacet + facet normal -0.686142 -0.0778572 0.72329 + outer loop + vertex 0.905874 1.37892 2.63623 + vertex 0.903382 1.37654 2.63361 + vertex 0.906231 1.37389 2.63603 + endloop + endfacet + facet normal -0.682339 -0.0697379 0.727702 + outer loop + vertex 0.903382 1.37654 2.63361 + vertex 0.903602 1.37157 2.63334 + vertex 0.906231 1.37389 2.63603 + endloop + endfacet + facet normal -0.679311 -0.0757517 0.72993 + outer loop + vertex 0.906231 1.37389 2.63603 + vertex 0.903602 1.37157 2.63334 + vertex 0.906386 1.369 2.63566 + endloop + endfacet + facet normal -0.611607 -0.0778762 0.787319 + outer loop + vertex 0.906386 1.369 2.63566 + vertex 0.909519 1.37105 2.6383 + vertex 0.906231 1.37389 2.63603 + endloop + endfacet + facet normal -0.617976 -0.0634128 0.783636 + outer loop + vertex 0.908769 1.36666 2.63735 + vertex 0.909519 1.37105 2.6383 + vertex 0.906386 1.369 2.63566 + endloop + endfacet + facet normal -0.627137 -0.0790441 0.774888 + outer loop + vertex 0.906553 1.36433 2.63532 + vertex 0.908769 1.36666 2.63735 + vertex 0.906386 1.369 2.63566 + endloop + endfacet + facet normal -0.6755 -0.0777392 0.73325 + outer loop + vertex 0.906386 1.369 2.63566 + vertex 0.90381 1.36661 2.63304 + vertex 0.906553 1.36433 2.63532 + endloop + endfacet + facet normal -0.674164 -0.0745666 0.734808 + outer loop + vertex 0.90381 1.36661 2.63304 + vertex 0.904095 1.36172 2.6328 + vertex 0.906553 1.36433 2.63532 + endloop + endfacet + facet normal -0.669608 -0.0820882 0.738164 + outer loop + vertex 0.906553 1.36433 2.63532 + vertex 0.904095 1.36172 2.6328 + vertex 0.906961 1.35966 2.63517 + endloop + endfacet + facet normal -0.601735 -0.0779873 0.794879 + outer loop + vertex 0.906961 1.35966 2.63517 + vertex 0.909575 1.36255 2.63744 + vertex 0.906553 1.36433 2.63532 + endloop + endfacet + facet normal -0.596367 -0.085405 0.798156 + outer loop + vertex 0.910095 1.35777 2.63731 + vertex 0.909575 1.36255 2.63744 + vertex 0.906961 1.35966 2.63517 + endloop + endfacet + facet normal -0.591188 -0.0708947 0.803412 + outer loop + vertex 0.907451 1.35503 2.63512 + vertex 0.910095 1.35777 2.63731 + vertex 0.906961 1.35966 2.63517 + endloop + endfacet + facet normal -0.662634 -0.077867 0.744884 + outer loop + vertex 0.906961 1.35966 2.63517 + vertex 0.904532 1.35694 2.63273 + vertex 0.907451 1.35503 2.63512 + endloop + endfacet + facet normal -0.661222 -0.0735964 0.746572 + outer loop + vertex 0.904532 1.35694 2.63273 + vertex 0.905258 1.35234 2.63292 + vertex 0.907451 1.35503 2.63512 + endloop + endfacet + facet normal -0.657547 -0.0788081 0.749281 + outer loop + vertex 0.907853 1.35118 2.63507 + vertex 0.907451 1.35503 2.63512 + vertex 0.905258 1.35234 2.63292 + endloop + endfacet + facet normal -0.66039 -0.0928169 0.745164 + outer loop + vertex 0.906652 1.34734 2.63353 + vertex 0.907853 1.35118 2.63507 + vertex 0.905258 1.35234 2.63292 + endloop + endfacet + facet normal -0.679233 -0.100302 0.727037 + outer loop + vertex 0.906652 1.34734 2.63353 + vertex 0.905258 1.35234 2.63292 + vertex 0.903403 1.34974 2.63083 + endloop + endfacet + facet normal -0.678728 -0.0988648 0.727704 + outer loop + vertex 0.906652 1.34734 2.63353 + vertex 0.903403 1.34974 2.63083 + vertex 0.904309 1.34684 2.63128 + endloop + endfacet + facet normal -0.680012 -0.0917246 0.72744 + outer loop + vertex 0.904965 1.3439 2.63152 + vertex 0.906652 1.34734 2.63353 + vertex 0.904309 1.34684 2.63128 + endloop + endfacet + facet normal -0.677395 -0.090932 0.729978 + outer loop + vertex 0.904309 1.34684 2.63128 + vertex 0.90223 1.34629 2.62928 + vertex 0.904965 1.3439 2.63152 + endloop + endfacet + facet normal -0.682594 -0.102922 0.723514 + outer loop + vertex 0.90223 1.34629 2.62928 + vertex 0.90322 1.34198 2.6296 + vertex 0.904965 1.3439 2.63152 + endloop + endfacet + facet normal -0.6898 -0.0911291 0.718242 + outer loop + vertex 0.904965 1.3439 2.63152 + vertex 0.90322 1.34198 2.6296 + vertex 0.905481 1.33925 2.63142 + endloop + endfacet + facet normal -0.673852 -0.0896654 0.733405 + outer loop + vertex 0.905481 1.33925 2.63142 + vertex 0.907774 1.34179 2.63384 + vertex 0.904965 1.3439 2.63152 + endloop + endfacet + facet normal -0.67425 -0.0890319 0.733117 + outer loop + vertex 0.908275 1.33663 2.63368 + vertex 0.907774 1.34179 2.63384 + vertex 0.905481 1.33925 2.63142 + endloop + endfacet + facet normal -0.675075 -0.0907468 0.732147 + outer loop + vertex 0.905746 1.33413 2.63103 + vertex 0.908275 1.33663 2.63368 + vertex 0.905481 1.33925 2.63142 + endloop + endfacet + facet normal -0.680896 -0.0906377 0.72675 + outer loop + vertex 0.905481 1.33925 2.63142 + vertex 0.902669 1.33753 2.62858 + vertex 0.905746 1.33413 2.63103 + endloop + endfacet + facet normal -0.683357 -0.0949359 0.723886 + outer loop + vertex 0.902669 1.33753 2.62858 + vertex 0.903261 1.33173 2.62837 + vertex 0.905746 1.33413 2.63103 + endloop + endfacet + facet normal -0.682512 -0.0964704 0.72448 + outer loop + vertex 0.905746 1.33413 2.63103 + vertex 0.903261 1.33173 2.62837 + vertex 0.906119 1.32891 2.63069 + endloop + endfacet + facet normal -0.681278 -0.0964588 0.725642 + outer loop + vertex 0.906119 1.32891 2.63069 + vertex 0.908558 1.33146 2.63332 + vertex 0.905746 1.33413 2.63103 + endloop + endfacet + facet normal -0.681726 -0.0957005 0.725322 + outer loop + vertex 0.908961 1.32632 2.63302 + vertex 0.908558 1.33146 2.63332 + vertex 0.906119 1.32891 2.63069 + endloop + endfacet + facet normal -0.685508 -0.104114 0.720582 + outer loop + vertex 0.906643 1.3239 2.63047 + vertex 0.908961 1.32632 2.63302 + vertex 0.906119 1.32891 2.63069 + endloop + endfacet + facet normal -0.682914 -0.103954 0.723064 + outer loop + vertex 0.906119 1.32891 2.63069 + vertex 0.903732 1.3266 2.6281 + vertex 0.906643 1.3239 2.63047 + endloop + endfacet + facet normal -0.685488 -0.109597 0.719788 + outer loop + vertex 0.903732 1.3266 2.6281 + vertex 0.904371 1.32182 2.62799 + vertex 0.906643 1.3239 2.63047 + endloop + endfacet + facet normal -0.682977 -0.11431 0.72144 + outer loop + vertex 0.906643 1.3239 2.63047 + vertex 0.904371 1.32182 2.62799 + vertex 0.907244 1.31928 2.6303 + endloop + endfacet + facet normal -0.68602 -0.114601 0.718501 + outer loop + vertex 0.907244 1.31928 2.6303 + vertex 0.909801 1.32089 2.633 + vertex 0.906643 1.3239 2.63047 + endloop + endfacet + facet normal -0.685158 -0.116764 0.718975 + outer loop + vertex 0.909782 1.3162 2.63222 + vertex 0.909801 1.32089 2.633 + vertex 0.907244 1.31928 2.6303 + endloop + endfacet + facet normal -0.68778 -0.120919 0.715778 + outer loop + vertex 0.907737 1.31563 2.63016 + vertex 0.909782 1.3162 2.63222 + vertex 0.907244 1.31928 2.6303 + endloop + endfacet + facet normal -0.683506 -0.120503 0.719929 + outer loop + vertex 0.907737 1.31563 2.63016 + vertex 0.907244 1.31928 2.6303 + vertex 0.905301 1.31731 2.62813 + endloop + endfacet + facet normal -0.682154 -0.116119 0.72193 + outer loop + vertex 0.906728 1.31227 2.62867 + vertex 0.907737 1.31563 2.63016 + vertex 0.905301 1.31731 2.62813 + endloop + endfacet + facet normal -0.644209 -0.101507 0.758084 + outer loop + vertex 0.906728 1.31227 2.62867 + vertex 0.905301 1.31731 2.62813 + vertex 0.903419 1.31494 2.62621 + endloop + endfacet + facet normal -0.656614 -0.130953 0.742771 + outer loop + vertex 0.906728 1.31227 2.62867 + vertex 0.903419 1.31494 2.62621 + vertex 0.904295 1.31203 2.62647 + endloop + endfacet + facet normal -0.66043 -0.102623 0.743842 + outer loop + vertex 0.904867 1.3089 2.62655 + vertex 0.906728 1.31227 2.62867 + vertex 0.904295 1.31203 2.62647 + endloop + endfacet + facet normal -0.585152 -0.0873752 0.806203 + outer loop + vertex 0.904295 1.31203 2.62647 + vertex 0.901759 1.31149 2.62457 + vertex 0.904867 1.3089 2.62655 + endloop + endfacet + facet normal -0.596457 -0.109312 0.795166 + outer loop + vertex 0.901759 1.31149 2.62457 + vertex 0.90241 1.30623 2.62434 + vertex 0.904867 1.3089 2.62655 + endloop + endfacet + facet normal -0.602729 -0.10056 0.791584 + outer loop + vertex 0.904867 1.3089 2.62655 + vertex 0.90241 1.30623 2.62434 + vertex 0.905496 1.30403 2.62641 + endloop + endfacet + facet normal -0.657493 -0.106347 0.745918 + outer loop + vertex 0.905496 1.30403 2.62641 + vertex 0.907878 1.3067 2.62889 + vertex 0.904867 1.3089 2.62655 + endloop + endfacet + facet normal -0.659442 -0.103391 0.744612 + outer loop + vertex 0.908413 1.30162 2.62866 + vertex 0.907878 1.3067 2.62889 + vertex 0.905496 1.30403 2.62641 + endloop + endfacet + facet normal -0.661043 -0.107147 0.742658 + outer loop + vertex 0.905952 1.29917 2.62611 + vertex 0.908413 1.30162 2.62866 + vertex 0.905496 1.30403 2.62641 + endloop + endfacet + facet normal -0.61448 -0.105174 0.781891 + outer loop + vertex 0.905496 1.30403 2.62641 + vertex 0.903054 1.30124 2.62411 + vertex 0.905952 1.29917 2.62611 + endloop + endfacet + facet normal -0.619393 -0.117511 0.776237 + outer loop + vertex 0.903054 1.30124 2.62411 + vertex 0.903809 1.29701 2.62408 + vertex 0.905952 1.29917 2.62611 + endloop + endfacet + facet normal -0.630089 -0.100937 0.769935 + outer loop + vertex 0.905952 1.29917 2.62611 + vertex 0.903809 1.29701 2.62408 + vertex 0.906242 1.29441 2.62573 + endloop + endfacet + facet normal -0.663786 -0.100655 0.741118 + outer loop + vertex 0.906242 1.29441 2.62573 + vertex 0.908724 1.29672 2.62826 + vertex 0.905952 1.29917 2.62611 + endloop + endfacet + facet normal -0.661735 -0.104317 0.742445 + outer loop + vertex 0.909194 1.29193 2.62801 + vertex 0.908724 1.29672 2.62826 + vertex 0.906242 1.29441 2.62573 + endloop + endfacet + facet normal -0.664075 -0.109734 0.73957 + outer loop + vertex 0.906883 1.28944 2.62557 + vertex 0.909194 1.29193 2.62801 + vertex 0.906242 1.29441 2.62573 + endloop + endfacet + facet normal -0.614405 -0.104706 0.782012 + outer loop + vertex 0.906242 1.29441 2.62573 + vertex 0.903202 1.29253 2.62309 + vertex 0.906883 1.28944 2.62557 + endloop + endfacet + facet normal -0.62568 -0.128218 0.76947 + outer loop + vertex 0.903202 1.29253 2.62309 + vertex 0.904558 1.28629 2.62315 + vertex 0.906883 1.28944 2.62557 + endloop + endfacet + facet normal -0.630787 -0.122021 0.766302 + outer loop + vertex 0.908294 1.28465 2.62596 + vertex 0.906883 1.28944 2.62557 + vertex 0.904558 1.28629 2.62315 + endloop + endfacet + facet normal -0.637288 -0.157091 0.754445 + outer loop + vertex 0.908294 1.28465 2.62596 + vertex 0.904558 1.28629 2.62315 + vertex 0.907243 1.28126 2.62437 + endloop + endfacet + facet normal -0.614673 -0.139747 0.776304 + outer loop + vertex 0.907243 1.28126 2.62437 + vertex 0.904558 1.28629 2.62315 + vertex 0.904203 1.28207 2.62211 + endloop + endfacet + facet normal -0.614244 -0.134702 0.777535 + outer loop + vertex 0.905404 1.2777 2.6223 + vertex 0.907243 1.28126 2.62437 + vertex 0.904203 1.28207 2.62211 + endloop + endfacet + facet normal -0.627381 -0.122919 0.76895 + outer loop + vertex 0.908315 1.27702 2.62457 + vertex 0.907243 1.28126 2.62437 + vertex 0.905404 1.2777 2.6223 + endloop + endfacet + facet normal -0.626688 -0.112966 0.771039 + outer loop + vertex 0.907767 1.27268 2.62349 + vertex 0.908315 1.27702 2.62457 + vertex 0.905404 1.2777 2.6223 + endloop + endfacet + facet normal -0.665933 -0.135069 0.733682 + outer loop + vertex 0.908294 1.28465 2.62596 + vertex 0.910092 1.28724 2.62807 + vertex 0.906883 1.28944 2.62557 + endloop + endfacet + facet normal -0.659855 -0.116371 0.742326 + outer loop + vertex 0.910092 1.28724 2.62807 + vertex 0.909194 1.29193 2.62801 + vertex 0.906883 1.28944 2.62557 + endloop + endfacet + facet normal -0.621699 -0.0877516 0.778325 + outer loop + vertex 0.903809 1.29701 2.62408 + vertex 0.903202 1.29253 2.62309 + vertex 0.906242 1.29441 2.62573 + endloop + endfacet + facet normal -0.664269 -0.101708 0.740542 + outer loop + vertex 0.908724 1.29672 2.62826 + vertex 0.908413 1.30162 2.62866 + vertex 0.905952 1.29917 2.62611 + endloop + endfacet + facet normal -0.650816 -0.101808 0.752379 + outer loop + vertex 0.908413 1.30162 2.62866 + vertex 0.908724 1.29672 2.62826 + vertex 0.911318 1.29915 2.63084 + endloop + endfacet + facet normal -0.653256 -0.107198 0.74951 + outer loop + vertex 0.911016 1.30406 2.63127 + vertex 0.908413 1.30162 2.62866 + vertex 0.911318 1.29915 2.63084 + endloop + endfacet + facet normal -0.568821 -0.107892 0.815354 + outer loop + vertex 0.911318 1.29915 2.63084 + vertex 0.914583 1.30141 2.63341 + vertex 0.911016 1.30406 2.63127 + endloop + endfacet + facet normal -0.583209 -0.139437 0.800265 + outer loop + vertex 0.914583 1.30141 2.63341 + vertex 0.913551 1.30676 2.63359 + vertex 0.911016 1.30406 2.63127 + endloop + endfacet + facet normal -0.603947 -0.11059 0.789315 + outer loop + vertex 0.911016 1.30406 2.63127 + vertex 0.913551 1.30676 2.63359 + vertex 0.910221 1.30911 2.63137 + endloop + endfacet + facet normal -0.6624 -0.118828 0.739666 + outer loop + vertex 0.910221 1.30911 2.63137 + vertex 0.907878 1.3067 2.62889 + vertex 0.911016 1.30406 2.63127 + endloop + endfacet + facet normal -0.668645 -0.108569 0.735613 + outer loop + vertex 0.906728 1.31227 2.62867 + vertex 0.907878 1.3067 2.62889 + vertex 0.910221 1.30911 2.63137 + endloop + endfacet + facet normal -0.677939 -0.128983 0.723714 + outer loop + vertex 0.909422 1.31303 2.63132 + vertex 0.906728 1.31227 2.62867 + vertex 0.910221 1.30911 2.63137 + endloop + endfacet + facet normal -0.630886 -0.118841 0.76672 + outer loop + vertex 0.910221 1.30911 2.63137 + vertex 0.912366 1.31213 2.63361 + vertex 0.909422 1.31303 2.63132 + endloop + endfacet + facet normal -0.633389 -0.143072 0.760492 + outer loop + vertex 0.909422 1.31303 2.63132 + vertex 0.912366 1.31213 2.63361 + vertex 0.909782 1.3162 2.63222 + endloop + endfacet + facet normal -0.628087 -0.137879 0.76583 + outer loop + vertex 0.912366 1.31213 2.63361 + vertex 0.912294 1.31685 2.6344 + vertex 0.909782 1.3162 2.63222 + endloop + endfacet + facet normal -0.631218 -0.124703 0.765515 + outer loop + vertex 0.912294 1.31685 2.6344 + vertex 0.909801 1.32089 2.633 + vertex 0.909782 1.3162 2.63222 + endloop + endfacet + facet normal -0.610648 -0.105311 0.784869 + outer loop + vertex 0.912631 1.32039 2.63514 + vertex 0.909801 1.32089 2.633 + vertex 0.912294 1.31685 2.6344 + endloop + endfacet + facet normal -0.609666 -0.0863937 0.787936 + outer loop + vertex 0.912631 1.32039 2.63514 + vertex 0.912018 1.32445 2.63511 + vertex 0.909801 1.32089 2.633 + endloop + endfacet + facet normal -0.600335 -0.0957809 0.793992 + outer loop + vertex 0.908961 1.32632 2.63302 + vertex 0.909801 1.32089 2.633 + vertex 0.912018 1.32445 2.63511 + endloop + endfacet + facet normal -0.598303 -0.0900036 0.796199 + outer loop + vertex 0.911576 1.3295 2.63534 + vertex 0.908961 1.32632 2.63302 + vertex 0.912018 1.32445 2.63511 + endloop + endfacet + facet normal -0.436322 -0.0805402 0.896179 + outer loop + vertex 0.912018 1.32445 2.63511 + vertex 0.915093 1.32828 2.63695 + vertex 0.911576 1.3295 2.63534 + endloop + endfacet + facet normal -0.437996 -0.0872467 0.894733 + outer loop + vertex 0.915093 1.32828 2.63695 + vertex 0.914868 1.33337 2.63733 + vertex 0.911576 1.3295 2.63534 + endloop + endfacet + facet normal -0.439106 -0.0860794 0.894302 + outer loop + vertex 0.911576 1.3295 2.63534 + vertex 0.914868 1.33337 2.63733 + vertex 0.911353 1.33461 2.63573 + endloop + endfacet + facet normal -0.592932 -0.0857696 0.800672 + outer loop + vertex 0.911353 1.33461 2.63573 + vertex 0.908558 1.33146 2.63332 + vertex 0.911576 1.3295 2.63534 + endloop + endfacet + facet normal -0.591526 -0.0876546 0.801507 + outer loop + vertex 0.908275 1.33663 2.63368 + vertex 0.908558 1.33146 2.63332 + vertex 0.911353 1.33461 2.63573 + endloop + endfacet + facet normal -0.589797 -0.0832456 0.80325 + outer loop + vertex 0.911049 1.33973 2.63603 + vertex 0.908275 1.33663 2.63368 + vertex 0.911353 1.33461 2.63573 + endloop + endfacet + facet normal -0.446434 -0.0800103 0.891232 + outer loop + vertex 0.911353 1.33461 2.63573 + vertex 0.91468 1.33834 2.63773 + vertex 0.911049 1.33973 2.63603 + endloop + endfacet + facet normal -0.448264 -0.0867012 0.889687 + outer loop + vertex 0.91468 1.33834 2.63773 + vertex 0.91424 1.34322 2.63798 + vertex 0.911049 1.33973 2.63603 + endloop + endfacet + facet normal -0.460191 -0.0730807 0.884807 + outer loop + vertex 0.911049 1.33973 2.63603 + vertex 0.91424 1.34322 2.63798 + vertex 0.910441 1.34478 2.63614 + endloop + endfacet + facet normal -0.591435 -0.0871976 0.801624 + outer loop + vertex 0.910441 1.34478 2.63614 + vertex 0.907774 1.34179 2.63384 + vertex 0.911049 1.33973 2.63603 + endloop + endfacet + facet normal -0.599422 -0.0763628 0.796782 + outer loop + vertex 0.906652 1.34734 2.63353 + vertex 0.907774 1.34179 2.63384 + vertex 0.910441 1.34478 2.63614 + endloop + endfacet + facet normal -0.612848 -0.110872 0.782384 + outer loop + vertex 0.909759 1.34883 2.63618 + vertex 0.906652 1.34734 2.63353 + vertex 0.910441 1.34478 2.63614 + endloop + endfacet + facet normal -0.467251 -0.0873311 0.879801 + outer loop + vertex 0.910441 1.34478 2.63614 + vertex 0.913599 1.34847 2.63818 + vertex 0.909759 1.34883 2.63618 + endloop + endfacet + facet normal -0.467952 -0.113282 0.876463 + outer loop + vertex 0.909759 1.34883 2.63618 + vertex 0.913599 1.34847 2.63818 + vertex 0.910779 1.35285 2.63724 + endloop + endfacet + facet normal -0.565941 -0.0737737 0.821139 + outer loop + vertex 0.909759 1.34883 2.63618 + vertex 0.910779 1.35285 2.63724 + vertex 0.907853 1.35118 2.63507 + endloop + endfacet + facet normal -0.436929 -0.0893272 0.89505 + outer loop + vertex 0.913599 1.34847 2.63818 + vertex 0.914436 1.35289 2.63903 + vertex 0.910779 1.35285 2.63724 + endloop + endfacet + facet normal -0.435058 -0.123408 0.891906 + outer loop + vertex 0.914436 1.35289 2.63903 + vertex 0.913005 1.35608 2.63877 + vertex 0.910779 1.35285 2.63724 + endloop + endfacet + facet normal -0.483677 -0.0801666 0.871568 + outer loop + vertex 0.910779 1.35285 2.63724 + vertex 0.913005 1.35608 2.63877 + vertex 0.910095 1.35777 2.63731 + endloop + endfacet + facet normal -0.475859 -0.0616873 0.877356 + outer loop + vertex 0.913005 1.35608 2.63877 + vertex 0.913436 1.36057 2.63932 + vertex 0.910095 1.35777 2.63731 + endloop + endfacet + facet normal -0.467905 -0.0735761 0.880711 + outer loop + vertex 0.910095 1.35777 2.63731 + vertex 0.913436 1.36057 2.63932 + vertex 0.909575 1.36255 2.63744 + endloop + endfacet + facet normal -0.607655 -0.125065 0.784292 + outer loop + vertex 0.906652 1.34734 2.63353 + vertex 0.909759 1.34883 2.63618 + vertex 0.907853 1.35118 2.63507 + endloop + endfacet + facet normal -0.465053 -0.0897224 0.880725 + outer loop + vertex 0.91424 1.34322 2.63798 + vertex 0.913599 1.34847 2.63818 + vertex 0.910441 1.34478 2.63614 + endloop + endfacet + facet normal -0.589901 -0.0831046 0.803188 + outer loop + vertex 0.907774 1.34179 2.63384 + vertex 0.908275 1.33663 2.63368 + vertex 0.911049 1.33973 2.63603 + endloop + endfacet + facet normal -0.439505 -0.0876559 0.893953 + outer loop + vertex 0.914868 1.33337 2.63733 + vertex 0.91468 1.33834 2.63773 + vertex 0.911353 1.33461 2.63573 + endloop + endfacet + facet normal -0.43009 -0.0867148 0.898612 + outer loop + vertex 0.915672 1.32287 2.6367 + vertex 0.915093 1.32828 2.63695 + vertex 0.912018 1.32445 2.63511 + endloop + endfacet + facet normal -0.595777 -0.0931958 0.797725 + outer loop + vertex 0.908558 1.33146 2.63332 + vertex 0.908961 1.32632 2.63302 + vertex 0.911576 1.3295 2.63534 + endloop + endfacet + facet normal -0.420297 -0.0569387 0.905598 + outer loop + vertex 0.912631 1.32039 2.63514 + vertex 0.915672 1.32287 2.6367 + vertex 0.912018 1.32445 2.63511 + endloop + endfacet + facet normal -0.61463 -0.137718 0.7767 + outer loop + vertex 0.913551 1.30676 2.63359 + vertex 0.912366 1.31213 2.63361 + vertex 0.910221 1.30911 2.63137 + endloop + endfacet + facet normal -0.57441 -0.0969332 0.812808 + outer loop + vertex 0.913885 1.297 2.63239 + vertex 0.914583 1.30141 2.63341 + vertex 0.911318 1.29915 2.63084 + endloop + endfacet + facet normal -0.580306 -0.108057 0.807198 + outer loop + vertex 0.911596 1.29454 2.63042 + vertex 0.913885 1.297 2.63239 + vertex 0.911318 1.29915 2.63084 + endloop + endfacet + facet normal -0.551609 -0.146022 0.821222 + outer loop + vertex 0.914891 1.29312 2.63238 + vertex 0.913885 1.297 2.63239 + vertex 0.911596 1.29454 2.63042 + endloop + endfacet + facet normal -0.542638 -0.109228 0.832834 + outer loop + vertex 0.912273 1.29003 2.63027 + vertex 0.914891 1.29312 2.63238 + vertex 0.911596 1.29454 2.63042 + endloop + endfacet + facet normal -0.634583 -0.120724 0.763367 + outer loop + vertex 0.911596 1.29454 2.63042 + vertex 0.909194 1.29193 2.62801 + vertex 0.912273 1.29003 2.63027 + endloop + endfacet + facet normal -0.631386 -0.110573 0.767545 + outer loop + vertex 0.909194 1.29193 2.62801 + vertex 0.910092 1.28724 2.62807 + vertex 0.912273 1.29003 2.63027 + endloop + endfacet + facet normal -0.625834 -0.117668 0.771029 + outer loop + vertex 0.912822 1.28613 2.63012 + vertex 0.912273 1.29003 2.63027 + vertex 0.910092 1.28724 2.62807 + endloop + endfacet + facet normal -0.627948 -0.129527 0.767401 + outer loop + vertex 0.911669 1.28223 2.62852 + vertex 0.912822 1.28613 2.63012 + vertex 0.910092 1.28724 2.62807 + endloop + endfacet + facet normal -0.660094 -0.142289 0.737584 + outer loop + vertex 0.911669 1.28223 2.62852 + vertex 0.910092 1.28724 2.62807 + vertex 0.908294 1.28465 2.62596 + endloop + endfacet + facet normal -0.659737 -0.141242 0.738104 + outer loop + vertex 0.911669 1.28223 2.62852 + vertex 0.908294 1.28465 2.62596 + vertex 0.909347 1.28171 2.62634 + endloop + endfacet + facet normal -0.662825 -0.126867 0.737948 + outer loop + vertex 0.91006 1.27884 2.62649 + vertex 0.911669 1.28223 2.62852 + vertex 0.909347 1.28171 2.62634 + endloop + endfacet + facet normal -0.663743 -0.127141 0.737075 + outer loop + vertex 0.909347 1.28171 2.62634 + vertex 0.907243 1.28126 2.62437 + vertex 0.91006 1.27884 2.62649 + endloop + endfacet + facet normal -0.666959 -0.134622 0.732832 + outer loop + vertex 0.907243 1.28126 2.62437 + vertex 0.908315 1.27702 2.62457 + vertex 0.91006 1.27884 2.62649 + endloop + endfacet + facet normal -0.676592 -0.118914 0.726693 + outer loop + vertex 0.91006 1.27884 2.62649 + vertex 0.908315 1.27702 2.62457 + vertex 0.910649 1.2743 2.62629 + endloop + endfacet + facet normal -0.65198 -0.11669 0.749204 + outer loop + vertex 0.910649 1.2743 2.62629 + vertex 0.912906 1.27677 2.62864 + vertex 0.91006 1.27884 2.62649 + endloop + endfacet + facet normal -0.651528 -0.117376 0.749489 + outer loop + vertex 0.9136 1.2716 2.62844 + vertex 0.912906 1.27677 2.62864 + vertex 0.910649 1.2743 2.62629 + endloop + endfacet + facet normal -0.648683 -0.111616 0.75283 + outer loop + vertex 0.911065 1.26923 2.6259 + vertex 0.9136 1.2716 2.62844 + vertex 0.910649 1.2743 2.62629 + endloop + endfacet + facet normal -0.660717 -0.111782 0.742265 + outer loop + vertex 0.910649 1.2743 2.62629 + vertex 0.907767 1.27268 2.62349 + vertex 0.911065 1.26923 2.6259 + endloop + endfacet + facet normal -0.658603 -0.108069 0.74469 + outer loop + vertex 0.907767 1.27268 2.62349 + vertex 0.908495 1.26698 2.6233 + vertex 0.911065 1.26923 2.6259 + endloop + endfacet + facet normal -0.654151 -0.116266 0.747374 + outer loop + vertex 0.911065 1.26923 2.6259 + vertex 0.908495 1.26698 2.6233 + vertex 0.911539 1.26421 2.62553 + endloop + endfacet + facet normal -0.641493 -0.115871 0.758328 + outer loop + vertex 0.911539 1.26421 2.62553 + vertex 0.914406 1.26596 2.62823 + vertex 0.911065 1.26923 2.6259 + endloop + endfacet + facet normal -0.639995 -0.119408 0.759044 + outer loop + vertex 0.914046 1.26159 2.62724 + vertex 0.914406 1.26596 2.62823 + vertex 0.911539 1.26421 2.62553 + endloop + endfacet + facet normal -0.648148 -0.133248 0.749766 + outer loop + vertex 0.912196 1.25974 2.62531 + vertex 0.914046 1.26159 2.62724 + vertex 0.911539 1.26421 2.62553 + endloop + endfacet + facet normal -0.647092 -0.133139 0.750697 + outer loop + vertex 0.911539 1.26421 2.62553 + vertex 0.909239 1.26201 2.62316 + vertex 0.912196 1.25974 2.62531 + endloop + endfacet + facet normal -0.649636 -0.139666 0.747306 + outer loop + vertex 0.909239 1.26201 2.62316 + vertex 0.910262 1.25744 2.6232 + vertex 0.912196 1.25974 2.62531 + endloop + endfacet + facet normal -0.641185 -0.151352 0.752312 + outer loop + vertex 0.912883 1.25609 2.62516 + vertex 0.912196 1.25974 2.62531 + vertex 0.910262 1.25744 2.6232 + endloop + endfacet + facet normal -0.644412 -0.166329 0.74637 + outer loop + vertex 0.911882 1.25246 2.62349 + vertex 0.912883 1.25609 2.62516 + vertex 0.910262 1.25744 2.6232 + endloop + endfacet + facet normal -0.61028 -0.153407 0.777191 + outer loop + vertex 0.911882 1.25246 2.62349 + vertex 0.910262 1.25744 2.6232 + vertex 0.908373 1.25487 2.62121 + endloop + endfacet + facet normal -0.617283 -0.172786 0.767533 + outer loop + vertex 0.911882 1.25246 2.62349 + vertex 0.908373 1.25487 2.62121 + vertex 0.909339 1.25197 2.62133 + endloop + endfacet + facet normal -0.566569 -0.154082 0.80948 + outer loop + vertex 0.906852 1.25143 2.61949 + vertex 0.909339 1.25197 2.62133 + vertex 0.908373 1.25487 2.62121 + endloop + endfacet + facet normal -0.616548 -0.147567 0.773364 + outer loop + vertex 0.912883 1.25609 2.62516 + vertex 0.915348 1.25725 2.62735 + vertex 0.912196 1.25974 2.62531 + endloop + endfacet + facet normal -0.625556 -0.168426 0.761783 + outer loop + vertex 0.915348 1.25725 2.62735 + vertex 0.914046 1.26159 2.62724 + vertex 0.912196 1.25974 2.62531 + endloop + endfacet + facet normal -0.655489 -0.119023 0.745766 + outer loop + vertex 0.908495 1.26698 2.6233 + vertex 0.909239 1.26201 2.62316 + vertex 0.911539 1.26421 2.62553 + endloop + endfacet + facet normal -0.643755 -0.120013 0.755762 + outer loop + vertex 0.914406 1.26596 2.62823 + vertex 0.9136 1.2716 2.62844 + vertex 0.911065 1.26923 2.6259 + endloop + endfacet + facet normal -0.664981 -0.10041 0.740079 + outer loop + vertex 0.908315 1.27702 2.62457 + vertex 0.907767 1.27268 2.62349 + vertex 0.910649 1.2743 2.62629 + endloop + endfacet + facet normal -0.657443 -0.131784 0.741891 + outer loop + vertex 0.912906 1.27677 2.62864 + vertex 0.911669 1.28223 2.62852 + vertex 0.91006 1.27884 2.62649 + endloop + endfacet + facet normal -0.660699 -0.141709 0.737153 + outer loop + vertex 0.907243 1.28126 2.62437 + vertex 0.909347 1.28171 2.62634 + vertex 0.908294 1.28465 2.62596 + endloop + endfacet + facet normal -0.507527 -0.10426 0.855305 + outer loop + vertex 0.912822 1.28613 2.63012 + vertex 0.915928 1.28816 2.63221 + vertex 0.912273 1.29003 2.63027 + endloop + endfacet + facet normal -0.646102 -0.103516 0.756199 + outer loop + vertex 0.908724 1.29672 2.62826 + vertex 0.909194 1.29193 2.62801 + vertex 0.911596 1.29454 2.63042 + endloop + endfacet + facet normal -0.518459 -0.137345 0.844001 + outer loop + vertex 0.915928 1.28816 2.63221 + vertex 0.914891 1.29312 2.63238 + vertex 0.912273 1.29003 2.63027 + endloop + endfacet + facet normal -0.647625 -0.107332 0.754362 + outer loop + vertex 0.911318 1.29915 2.63084 + vertex 0.908724 1.29672 2.62826 + vertex 0.911596 1.29454 2.63042 + endloop + endfacet + facet normal -0.655586 -0.10314 0.748043 + outer loop + vertex 0.907878 1.3067 2.62889 + vertex 0.908413 1.30162 2.62866 + vertex 0.911016 1.30406 2.63127 + endloop + endfacet + facet normal -0.60815 -0.113778 0.785626 + outer loop + vertex 0.90241 1.30623 2.62434 + vertex 0.903054 1.30124 2.62411 + vertex 0.905496 1.30403 2.62641 + endloop + endfacet + facet normal -0.657295 -0.105809 0.746168 + outer loop + vertex 0.907878 1.3067 2.62889 + vertex 0.906728 1.31227 2.62867 + vertex 0.904867 1.3089 2.62655 + endloop + endfacet + facet normal -0.582131 -0.102878 0.80656 + outer loop + vertex 0.901759 1.31149 2.62457 + vertex 0.904295 1.31203 2.62647 + vertex 0.903419 1.31494 2.62621 + endloop + endfacet + facet normal -0.680698 -0.117096 0.723145 + outer loop + vertex 0.906728 1.31227 2.62867 + vertex 0.909422 1.31303 2.63132 + vertex 0.907737 1.31563 2.63016 + endloop + endfacet + facet normal -0.686992 -0.124374 0.715942 + outer loop + vertex 0.909422 1.31303 2.63132 + vertex 0.909782 1.3162 2.63222 + vertex 0.907737 1.31563 2.63016 + endloop + endfacet + facet normal -0.684727 -0.118396 0.719118 + outer loop + vertex 0.904371 1.32182 2.62799 + vertex 0.905301 1.31731 2.62813 + vertex 0.907244 1.31928 2.6303 + endloop + endfacet + facet normal -0.683044 -0.108294 0.722304 + outer loop + vertex 0.909801 1.32089 2.633 + vertex 0.908961 1.32632 2.63302 + vertex 0.906643 1.3239 2.63047 + endloop + endfacet + facet normal -0.68466 -0.1008 0.721859 + outer loop + vertex 0.903261 1.33173 2.62837 + vertex 0.903732 1.3266 2.6281 + vertex 0.906119 1.32891 2.63069 + endloop + endfacet + facet normal -0.676943 -0.0874569 0.730821 + outer loop + vertex 0.908558 1.33146 2.63332 + vertex 0.908275 1.33663 2.63368 + vertex 0.905746 1.33413 2.63103 + endloop + endfacet + facet normal -0.684107 -0.0820536 0.724752 + outer loop + vertex 0.90322 1.34198 2.6296 + vertex 0.902669 1.33753 2.62858 + vertex 0.905481 1.33925 2.63142 + endloop + endfacet + facet normal -0.676015 -0.0955676 0.730664 + outer loop + vertex 0.907774 1.34179 2.63384 + vertex 0.906652 1.34734 2.63353 + vertex 0.904965 1.3439 2.63152 + endloop + endfacet + facet normal -0.676032 -0.0976062 0.730379 + outer loop + vertex 0.90223 1.34629 2.62928 + vertex 0.904309 1.34684 2.63128 + vertex 0.903403 1.34974 2.63083 + endloop + endfacet + facet normal -0.567375 -0.0703783 0.820447 + outer loop + vertex 0.907853 1.35118 2.63507 + vertex 0.910779 1.35285 2.63724 + vertex 0.907451 1.35503 2.63512 + endloop + endfacet + facet normal -0.576294 -0.0921869 0.812027 + outer loop + vertex 0.910779 1.35285 2.63724 + vertex 0.910095 1.35777 2.63731 + vertex 0.907451 1.35503 2.63512 + endloop + endfacet + facet normal -0.666114 -0.0724487 0.742323 + outer loop + vertex 0.904095 1.36172 2.6328 + vertex 0.904532 1.35694 2.63273 + vertex 0.906961 1.35966 2.63517 + endloop + endfacet + facet normal -0.61038 -0.104056 0.785245 + outer loop + vertex 0.909575 1.36255 2.63744 + vertex 0.908769 1.36666 2.63735 + vertex 0.906553 1.36433 2.63532 + endloop + endfacet + facet normal -0.618959 -0.0922785 0.779983 + outer loop + vertex 0.909519 1.37105 2.6383 + vertex 0.908848 1.37647 2.63841 + vertex 0.906231 1.37389 2.63603 + endloop + endfacet + facet normal -0.637032 -0.0691015 0.767734 + outer loop + vertex 0.908406 1.38149 2.63856 + vertex 0.908019 1.38661 2.6387 + vertex 0.905537 1.38395 2.6364 + endloop + endfacet + facet normal -0.649194 -0.0785765 0.756553 + outer loop + vertex 0.904729 1.39293 2.63647 + vertex 0.907434 1.39222 2.63872 + vertex 0.905208 1.39682 2.63729 + endloop + endfacet + facet normal -0.641066 -0.0722959 0.764073 + outer loop + vertex 0.907434 1.39222 2.63872 + vertex 0.907946 1.39668 2.63957 + vertex 0.905208 1.39682 2.63729 + endloop + endfacet + facet normal -0.640913 -0.0801195 0.763421 + outer loop + vertex 0.907946 1.39668 2.63957 + vertex 0.906902 1.40104 2.63915 + vertex 0.905208 1.39682 2.63729 + endloop + endfacet + facet normal -0.672517 -0.0561539 0.737948 + outer loop + vertex 0.905208 1.39682 2.63729 + vertex 0.906902 1.40104 2.63915 + vertex 0.904179 1.4011 2.63668 + endloop + endfacet + facet normal -0.672022 -0.0722686 0.736997 + outer loop + vertex 0.906902 1.40104 2.63915 + vertex 0.904719 1.40562 2.63761 + vertex 0.904179 1.4011 2.63668 + endloop + endfacet + facet normal -0.709165 -0.0521972 0.703108 + outer loop + vertex 0.901749 1.40337 2.63428 + vertex 0.899842 1.39968 2.63209 + vertex 0.902466 1.39854 2.63465 + endloop + endfacet + facet normal -0.645946 -0.0137116 0.76326 + outer loop + vertex 0.896878 1.3969 2.62953 + vertex 0.899842 1.39968 2.63209 + vertex 0.897625 1.40116 2.63024 + endloop + endfacet + facet normal -0.700923 -0.0650408 0.710265 + outer loop + vertex 0.903141 1.395 2.63506 + vertex 0.900447 1.39468 2.63237 + vertex 0.902785 1.39132 2.63437 + endloop + endfacet + facet normal -0.699953 -0.0630881 0.711397 + outer loop + vertex 0.902785 1.39132 2.63437 + vertex 0.902877 1.38654 2.63404 + vertex 0.905196 1.38894 2.63653 + endloop + endfacet + facet normal -0.691753 -0.0644287 0.719254 + outer loop + vertex 0.903114 1.38152 2.63382 + vertex 0.902877 1.38654 2.63404 + vertex 0.900409 1.38398 2.63144 + endloop + endfacet + facet normal -0.691762 -0.0672294 0.718989 + outer loop + vertex 0.903114 1.38152 2.63382 + vertex 0.903382 1.37654 2.63361 + vertex 0.905874 1.37892 2.63623 + endloop + endfacet + facet normal -0.645762 -0.071751 0.76016 + outer loop + vertex 0.897928 1.38111 2.6291 + vertex 0.898553 1.37689 2.62923 + vertex 0.900703 1.37908 2.63127 + endloop + endfacet + facet normal -0.685774 -0.0697149 0.724468 + outer loop + vertex 0.903602 1.37157 2.63334 + vertex 0.903382 1.37654 2.63361 + vertex 0.900841 1.37429 2.63099 + endloop + endfacet + facet normal -0.678017 -0.073009 0.731412 + outer loop + vertex 0.903602 1.37157 2.63334 + vertex 0.90381 1.36661 2.63304 + vertex 0.906386 1.369 2.63566 + endloop + endfacet + facet normal -0.632091 -0.071513 0.771587 + outer loop + vertex 0.897731 1.37243 2.6283 + vertex 0.898302 1.36673 2.62824 + vertex 0.900968 1.36925 2.63066 + endloop + endfacet + facet normal -0.679629 -0.0746415 0.729749 + outer loop + vertex 0.904095 1.36172 2.6328 + vertex 0.90381 1.36661 2.63304 + vertex 0.901292 1.36412 2.63044 + endloop + endfacet + facet normal -0.681046 -0.0774719 0.728131 + outer loop + vertex 0.905258 1.35234 2.63292 + vertex 0.904532 1.35694 2.63273 + vertex 0.902273 1.35432 2.63034 + endloop + endfacet + facet normal -0.63663 -0.0749881 0.767515 + outer loop + vertex 0.898714 1.3616 2.62807 + vertex 0.899136 1.35661 2.62793 + vertex 0.901668 1.35916 2.63028 + endloop + endfacet + facet normal -0.685523 -0.0919406 0.722222 + outer loop + vertex 0.903403 1.34974 2.63083 + vertex 0.905258 1.35234 2.63292 + vertex 0.902273 1.35432 2.63034 + endloop + endfacet + facet normal -0.533781 -0.093607 0.840426 + outer loop + vertex 0.896772 1.33692 2.62435 + vertex 0.897424 1.33129 2.62413 + vertex 0.900199 1.33424 2.62622 + endloop + endfacet + facet normal -0.623938 -0.0980292 0.775301 + outer loop + vertex 0.903732 1.3266 2.6281 + vertex 0.903261 1.33173 2.62837 + vertex 0.900696 1.32907 2.62597 + endloop + endfacet + facet normal -0.630161 -0.105565 0.769255 + outer loop + vertex 0.905301 1.31731 2.62813 + vertex 0.904371 1.32182 2.62799 + vertex 0.902157 1.31942 2.62584 + endloop + endfacet + facet normal -0.541601 -0.0980154 0.834902 + outer loop + vertex 0.897959 1.32618 2.62388 + vertex 0.898689 1.32123 2.62377 + vertex 0.90126 1.32413 2.62578 + endloop + endfacet + facet normal -0.633653 -0.115449 0.764954 + outer loop + vertex 0.903419 1.31494 2.62621 + vertex 0.905301 1.31731 2.62813 + vertex 0.902157 1.31942 2.62584 + endloop + endfacet +endsolid diff --git a/noether_examples/meshes/outputsBackDoor/output_4.stl b/noether_examples/meshes/outputsBackDoor/output_4.stl new file mode 100644 index 00000000..31152a31 --- /dev/null +++ b/noether_examples/meshes/outputsBackDoor/output_4.stl @@ -0,0 +1,65865 @@ +solid ascii + facet normal -0.314128 -3.18379e-05 0.949381 + outer loop + vertex 0.90989 1.48788 2.64385 + vertex 0.912972 1.49086 2.64487 + vertex 0.909161 1.49197 2.64361 + endloop + endfacet + facet normal -0.317669 -0.0137432 0.948102 + outer loop + vertex 0.912972 1.49086 2.64487 + vertex 0.912625 1.49566 2.64482 + vertex 0.909161 1.49197 2.64361 + endloop + endfacet + facet normal -0.324972 -0.00611011 0.945704 + outer loop + vertex 0.909161 1.49197 2.64361 + vertex 0.912625 1.49566 2.64482 + vertex 0.908871 1.4968 2.64354 + endloop + endfacet + facet normal -0.325853 -0.00937371 0.945374 + outer loop + vertex 0.912625 1.49566 2.64482 + vertex 0.912525 1.50055 2.64484 + vertex 0.908871 1.4968 2.64354 + endloop + endfacet + facet normal -0.327635 -0.00743048 0.944775 + outer loop + vertex 0.908871 1.4968 2.64354 + vertex 0.912525 1.50055 2.64484 + vertex 0.908826 1.50174 2.64356 + endloop + endfacet + facet normal -0.326479 -0.00336131 0.945199 + outer loop + vertex 0.912525 1.50055 2.64484 + vertex 0.912545 1.50551 2.64486 + vertex 0.908826 1.50174 2.64356 + endloop + endfacet + facet normal -0.325135 -0.00484353 0.945655 + outer loop + vertex 0.908826 1.50174 2.64356 + vertex 0.912545 1.50551 2.64486 + vertex 0.908839 1.5067 2.64359 + endloop + endfacet + facet normal -0.324532 -0.00273174 0.945871 + outer loop + vertex 0.912545 1.50551 2.64486 + vertex 0.912547 1.51048 2.64488 + vertex 0.908839 1.5067 2.64359 + endloop + endfacet + facet normal -0.323504 -0.00385619 0.946219 + outer loop + vertex 0.908839 1.5067 2.64359 + vertex 0.912547 1.51048 2.64488 + vertex 0.908819 1.51166 2.64361 + endloop + endfacet + facet normal -0.323143 -0.00257659 0.946347 + outer loop + vertex 0.912547 1.51048 2.64488 + vertex 0.912508 1.51547 2.64488 + vertex 0.908819 1.51166 2.64361 + endloop + endfacet + facet normal -0.325239 -0.00030582 0.945632 + outer loop + vertex 0.908819 1.51166 2.64361 + vertex 0.912508 1.51547 2.64488 + vertex 0.908783 1.51665 2.6436 + endloop + endfacet + facet normal -0.324269 0.00310969 0.94596 + outer loop + vertex 0.912508 1.51547 2.64488 + vertex 0.912502 1.52049 2.64486 + vertex 0.908783 1.51665 2.6436 + endloop + endfacet + facet normal -0.323655 0.00244608 0.946172 + outer loop + vertex 0.908783 1.51665 2.6436 + vertex 0.912502 1.52049 2.64486 + vertex 0.908805 1.5217 2.64359 + endloop + endfacet + facet normal -0.321352 0.010245 0.946904 + outer loop + vertex 0.912502 1.52049 2.64486 + vertex 0.912686 1.52566 2.64487 + vertex 0.908805 1.5217 2.64359 + endloop + endfacet + facet normal -0.323856 0.0129855 0.946017 + outer loop + vertex 0.908805 1.5217 2.64359 + vertex 0.912686 1.52566 2.64487 + vertex 0.908978 1.52693 2.64358 + endloop + endfacet + facet normal -0.319967 0.0254775 0.947086 + outer loop + vertex 0.912686 1.52566 2.64487 + vertex 0.913399 1.53142 2.64495 + vertex 0.908978 1.52693 2.64358 + endloop + endfacet + facet normal -0.308751 0.0132322 0.951051 + outer loop + vertex 0.908978 1.52693 2.64358 + vertex 0.913399 1.53142 2.64495 + vertex 0.909036 1.53212 2.64353 + endloop + endfacet + facet normal -0.309293 0.00958208 0.950918 + outer loop + vertex 0.913399 1.53142 2.64495 + vertex 0.912952 1.53657 2.64475 + vertex 0.909036 1.53212 2.64353 + endloop + endfacet + facet normal -0.317532 0.0176165 0.948084 + outer loop + vertex 0.909036 1.53212 2.64353 + vertex 0.912952 1.53657 2.64475 + vertex 0.908843 1.53708 2.64337 + endloop + endfacet + facet normal -0.316865 0.0232272 0.948186 + outer loop + vertex 0.912952 1.53657 2.64475 + vertex 0.912869 1.5415 2.64461 + vertex 0.908843 1.53708 2.64337 + endloop + endfacet + facet normal -0.320006 0.0264068 0.947047 + outer loop + vertex 0.908843 1.53708 2.64337 + vertex 0.912869 1.5415 2.64461 + vertex 0.90827 1.54217 2.64303 + endloop + endfacet + facet normal -0.320729 0.0211584 0.946935 + outer loop + vertex 0.912869 1.5415 2.64461 + vertex 0.912969 1.54662 2.64453 + vertex 0.90827 1.54217 2.64303 + endloop + endfacet + facet normal -0.305192 0.00295894 0.952286 + outer loop + vertex 0.90827 1.54217 2.64303 + vertex 0.912969 1.54662 2.64453 + vertex 0.908925 1.54778 2.64323 + endloop + endfacet + facet normal -0.301856 0.0156281 0.953225 + outer loop + vertex 0.912969 1.54662 2.64453 + vertex 0.913166 1.55184 2.6445 + vertex 0.908925 1.54778 2.64323 + endloop + endfacet + facet normal -0.300205 0.0137289 0.953776 + outer loop + vertex 0.908925 1.54778 2.64323 + vertex 0.913166 1.55184 2.6445 + vertex 0.909082 1.55289 2.6432 + endloop + endfacet + facet normal -0.29873 0.0198736 0.954131 + outer loop + vertex 0.913166 1.55184 2.6445 + vertex 0.913349 1.55709 2.64445 + vertex 0.909082 1.55289 2.6432 + endloop + endfacet + facet normal -0.291979 0.0123458 0.956345 + outer loop + vertex 0.909082 1.55289 2.6432 + vertex 0.913349 1.55709 2.64445 + vertex 0.90908 1.55792 2.64314 + endloop + endfacet + facet normal -0.290121 0.0224597 0.956727 + outer loop + vertex 0.913349 1.55709 2.64445 + vertex 0.913429 1.56231 2.64435 + vertex 0.90908 1.55792 2.64314 + endloop + endfacet + facet normal -0.286443 0.0184883 0.957919 + outer loop + vertex 0.90908 1.55792 2.64314 + vertex 0.913429 1.56231 2.64435 + vertex 0.909078 1.56291 2.64304 + endloop + endfacet + facet normal -0.285954 0.0222318 0.957985 + outer loop + vertex 0.913429 1.56231 2.64435 + vertex 0.913396 1.56738 2.64422 + vertex 0.909078 1.56291 2.64304 + endloop + endfacet + facet normal -0.286575 0.0228847 0.957785 + outer loop + vertex 0.909078 1.56291 2.64304 + vertex 0.913396 1.56738 2.64422 + vertex 0.909116 1.56784 2.64293 + endloop + endfacet + facet normal -0.286079 0.0275021 0.957811 + outer loop + vertex 0.913396 1.56738 2.64422 + vertex 0.913441 1.57233 2.6441 + vertex 0.909116 1.56784 2.64293 + endloop + endfacet + facet normal -0.287664 0.0291636 0.957287 + outer loop + vertex 0.909116 1.56784 2.64293 + vertex 0.913441 1.57233 2.6441 + vertex 0.909205 1.57279 2.64281 + endloop + endfacet + facet normal -0.287224 0.033244 0.957286 + outer loop + vertex 0.913441 1.57233 2.6441 + vertex 0.913523 1.5773 2.64395 + vertex 0.909205 1.57279 2.64281 + endloop + endfacet + facet normal -0.288064 0.0341209 0.957003 + outer loop + vertex 0.909205 1.57279 2.64281 + vertex 0.913523 1.5773 2.64395 + vertex 0.90931 1.57778 2.64266 + endloop + endfacet + facet normal -0.288104 0.0337752 0.957003 + outer loop + vertex 0.913523 1.5773 2.64395 + vertex 0.913577 1.58228 2.64379 + vertex 0.90931 1.57778 2.64266 + endloop + endfacet + facet normal -0.28462 0.0301777 0.958165 + outer loop + vertex 0.90931 1.57778 2.64266 + vertex 0.913577 1.58228 2.64379 + vertex 0.909377 1.58277 2.64252 + endloop + endfacet + facet normal -0.284409 0.0319965 0.958169 + outer loop + vertex 0.913577 1.58228 2.64379 + vertex 0.913597 1.58727 2.64363 + vertex 0.909377 1.58277 2.64252 + endloop + endfacet + facet normal -0.285738 0.0333513 0.957727 + outer loop + vertex 0.909377 1.58277 2.64252 + vertex 0.913597 1.58727 2.64363 + vertex 0.909452 1.58777 2.64237 + endloop + endfacet + facet normal -0.285431 0.0358903 0.957727 + outer loop + vertex 0.913597 1.58727 2.64363 + vertex 0.913626 1.59227 2.64345 + vertex 0.909452 1.58777 2.64237 + endloop + endfacet + facet normal -0.284727 0.0351803 0.957963 + outer loop + vertex 0.909452 1.58777 2.64237 + vertex 0.913626 1.59227 2.64345 + vertex 0.909528 1.59277 2.64221 + endloop + endfacet + facet normal -0.284422 0.0376671 0.957959 + outer loop + vertex 0.913626 1.59227 2.64345 + vertex 0.913658 1.59726 2.64326 + vertex 0.909528 1.59277 2.64221 + endloop + endfacet + facet normal -0.283175 0.0364223 0.958377 + outer loop + vertex 0.909528 1.59277 2.64221 + vertex 0.913658 1.59726 2.64326 + vertex 0.909593 1.59775 2.64204 + endloop + endfacet + facet normal -0.282702 0.0402823 0.958361 + outer loop + vertex 0.913658 1.59726 2.64326 + vertex 0.91369 1.60226 2.64306 + vertex 0.909593 1.59775 2.64204 + endloop + endfacet + facet normal -0.285192 0.0427386 0.957517 + outer loop + vertex 0.909593 1.59775 2.64204 + vertex 0.91369 1.60226 2.64306 + vertex 0.909671 1.60276 2.64184 + endloop + endfacet + facet normal -0.284673 0.0467659 0.957483 + outer loop + vertex 0.91369 1.60226 2.64306 + vertex 0.913741 1.60728 2.64283 + vertex 0.909671 1.60276 2.64184 + endloop + endfacet + facet normal -0.283893 0.0460041 0.957752 + outer loop + vertex 0.909671 1.60276 2.64184 + vertex 0.913741 1.60728 2.64283 + vertex 0.909773 1.60779 2.64163 + endloop + endfacet + facet normal -0.283617 0.0480786 0.957732 + outer loop + vertex 0.913741 1.60728 2.64283 + vertex 0.913788 1.61229 2.64259 + vertex 0.909773 1.60779 2.64163 + endloop + endfacet + facet normal -0.27819 0.0428371 0.95957 + outer loop + vertex 0.909773 1.60779 2.64163 + vertex 0.913788 1.61229 2.64259 + vertex 0.909894 1.61274 2.64144 + endloop + endfacet + facet normal -0.277783 0.0462457 0.95953 + outer loop + vertex 0.913788 1.61229 2.64259 + vertex 0.913744 1.61723 2.64234 + vertex 0.909894 1.61274 2.64144 + endloop + endfacet + facet normal -0.264586 0.034076 0.96376 + outer loop + vertex 0.909894 1.61274 2.64144 + vertex 0.913744 1.61723 2.64234 + vertex 0.909907 1.61723 2.64129 + endloop + endfacet + facet normal -0.264466 0.0442916 0.963377 + outer loop + vertex 0.909907 1.61723 2.64129 + vertex 0.913744 1.61723 2.64234 + vertex 0.913251 1.62225 2.64198 + endloop + endfacet + facet normal -0.2848 0.0587505 0.956785 + outer loop + vertex 0.909399 1.62037 2.64095 + vertex 0.909907 1.61723 2.64129 + vertex 0.913251 1.62225 2.64198 + endloop + endfacet + facet normal -0.289945 0.0705652 0.954438 + outer loop + vertex 0.909399 1.62037 2.64095 + vertex 0.913251 1.62225 2.64198 + vertex 0.910106 1.62422 2.64088 + endloop + endfacet + facet normal -0.492913 0.106192 0.863574 + outer loop + vertex 0.910106 1.62422 2.64088 + vertex 0.907108 1.62102 2.63956 + vertex 0.909399 1.62037 2.64095 + endloop + endfacet + facet normal -0.480375 0.0907903 0.872351 + outer loop + vertex 0.907202 1.62556 2.63914 + vertex 0.907108 1.62102 2.63956 + vertex 0.910106 1.62422 2.64088 + endloop + endfacet + facet normal -0.483529 0.0827495 0.871408 + outer loop + vertex 0.910461 1.62903 2.64062 + vertex 0.907202 1.62556 2.63914 + vertex 0.910106 1.62422 2.64088 + endloop + endfacet + facet normal -0.302122 0.0736355 0.950421 + outer loop + vertex 0.910106 1.62422 2.64088 + vertex 0.914035 1.62787 2.64184 + vertex 0.910461 1.62903 2.64062 + endloop + endfacet + facet normal -0.305912 0.0615732 0.950067 + outer loop + vertex 0.914035 1.62787 2.64184 + vertex 0.91435 1.63285 2.64162 + vertex 0.910461 1.62903 2.64062 + endloop + endfacet + facet normal -0.306347 0.0620625 0.949894 + outer loop + vertex 0.910461 1.62903 2.64062 + vertex 0.91435 1.63285 2.64162 + vertex 0.910809 1.63399 2.6404 + endloop + endfacet + facet normal -0.487367 0.0713314 0.870279 + outer loop + vertex 0.910809 1.63399 2.6404 + vertex 0.90709 1.63074 2.63859 + vertex 0.910461 1.62903 2.64062 + endloop + endfacet + facet normal -0.307115 0.0595919 0.949805 + outer loop + vertex 0.91435 1.63285 2.64162 + vertex 0.914586 1.63764 2.6414 + vertex 0.910809 1.63399 2.6404 + endloop + endfacet + facet normal -0.482906 0.0819878 0.871825 + outer loop + vertex 0.90709 1.63074 2.63859 + vertex 0.907202 1.62556 2.63914 + vertex 0.910461 1.62903 2.64062 + endloop + endfacet + facet normal -0.293865 0.0638947 0.953709 + outer loop + vertex 0.913251 1.62225 2.64198 + vertex 0.914035 1.62787 2.64184 + vertex 0.910106 1.62422 2.64088 + endloop + endfacet + facet normal -0.208841 0.0193237 0.977759 + outer loop + vertex 0.913399 1.53142 2.64495 + vertex 0.916708 1.53623 2.64556 + vertex 0.912952 1.53657 2.64475 + endloop + endfacet + facet normal -0.208134 0.0270547 0.977726 + outer loop + vertex 0.916708 1.53623 2.64556 + vertex 0.916862 1.54072 2.64547 + vertex 0.912952 1.53657 2.64475 + endloop + endfacet + facet normal -0.207045 0.0259843 0.977986 + outer loop + vertex 0.912952 1.53657 2.64475 + vertex 0.916862 1.54072 2.64547 + vertex 0.912869 1.5415 2.64461 + endloop + endfacet + facet normal -0.207542 0.0234059 0.977946 + outer loop + vertex 0.916862 1.54072 2.64547 + vertex 0.917092 1.54563 2.6454 + vertex 0.912869 1.5415 2.64461 + endloop + endfacet + facet normal -0.203761 0.0193649 0.978829 + outer loop + vertex 0.912869 1.5415 2.64461 + vertex 0.917092 1.54563 2.6454 + vertex 0.912969 1.54662 2.64453 + endloop + endfacet + facet normal -0.20398 0.0184321 0.978802 + outer loop + vertex 0.917092 1.54563 2.6454 + vertex 0.917246 1.55071 2.64534 + vertex 0.912969 1.54662 2.64453 + endloop + endfacet + facet normal -0.197921 0.0118207 0.980147 + outer loop + vertex 0.912969 1.54662 2.64453 + vertex 0.917246 1.55071 2.64534 + vertex 0.913166 1.55184 2.6445 + endloop + endfacet + facet normal -0.195695 0.020065 0.98046 + outer loop + vertex 0.917246 1.55071 2.64534 + vertex 0.917466 1.5559 2.64528 + vertex 0.913166 1.55184 2.6445 + endloop + endfacet + facet normal -0.192408 0.0164472 0.981177 + outer loop + vertex 0.913166 1.55184 2.6445 + vertex 0.917466 1.5559 2.64528 + vertex 0.913349 1.55709 2.64445 + endloop + endfacet + facet normal -0.186473 0.037391 0.981748 + outer loop + vertex 0.917466 1.5559 2.64528 + vertex 0.918496 1.56173 2.64525 + vertex 0.913349 1.55709 2.64445 + endloop + endfacet + facet normal -0.172335 0.0211699 0.984811 + outer loop + vertex 0.913349 1.55709 2.64445 + vertex 0.918496 1.56173 2.64525 + vertex 0.913429 1.56231 2.64435 + endloop + endfacet + facet normal -0.17158 0.0276312 0.984783 + outer loop + vertex 0.918496 1.56173 2.64525 + vertex 0.918273 1.56722 2.64506 + vertex 0.913429 1.56231 2.64435 + endloop + endfacet + facet normal -0.167705 0.0236967 0.985552 + outer loop + vertex 0.913429 1.56231 2.64435 + vertex 0.918273 1.56722 2.64506 + vertex 0.913396 1.56738 2.64422 + endloop + endfacet + facet normal -0.16758 0.027298 0.98548 + outer loop + vertex 0.918273 1.56722 2.64506 + vertex 0.918223 1.57232 2.64491 + vertex 0.913396 1.56738 2.64422 + endloop + endfacet + facet normal -0.167431 0.0271487 0.98551 + outer loop + vertex 0.913396 1.56738 2.64422 + vertex 0.918223 1.57232 2.64491 + vertex 0.913441 1.57233 2.6441 + endloop + endfacet + facet normal -0.167393 0.0319984 0.985371 + outer loop + vertex 0.918223 1.57232 2.64491 + vertex 0.9183 1.5773 2.64476 + vertex 0.913441 1.57233 2.6441 + endloop + endfacet + facet normal -0.167486 0.0320922 0.985352 + outer loop + vertex 0.913441 1.57233 2.6441 + vertex 0.9183 1.5773 2.64476 + vertex 0.913523 1.5773 2.64395 + endloop + endfacet + facet normal -0.167472 0.0347851 0.985263 + outer loop + vertex 0.9183 1.5773 2.64476 + vertex 0.918363 1.58227 2.64459 + vertex 0.913523 1.5773 2.64395 + endloop + endfacet + facet normal -0.166062 0.0333751 0.98555 + outer loop + vertex 0.913523 1.5773 2.64395 + vertex 0.918363 1.58227 2.64459 + vertex 0.913577 1.58228 2.64379 + endloop + endfacet + facet normal -0.166059 0.0336999 0.98554 + outer loop + vertex 0.918363 1.58227 2.64459 + vertex 0.918366 1.58725 2.64442 + vertex 0.913577 1.58228 2.64379 + endloop + endfacet + facet normal -0.16475 0.0324047 0.985803 + outer loop + vertex 0.913577 1.58228 2.64379 + vertex 0.918366 1.58725 2.64442 + vertex 0.913597 1.58727 2.64363 + endloop + endfacet + facet normal -0.164709 0.0365695 0.985664 + outer loop + vertex 0.918366 1.58725 2.64442 + vertex 0.918354 1.59224 2.64424 + vertex 0.913597 1.58727 2.64363 + endloop + endfacet + facet normal -0.164336 0.0362037 0.98574 + outer loop + vertex 0.913597 1.58727 2.64363 + vertex 0.918354 1.59224 2.64424 + vertex 0.913626 1.59227 2.64345 + endloop + endfacet + facet normal -0.164304 0.0390757 0.985635 + outer loop + vertex 0.918354 1.59224 2.64424 + vertex 0.918352 1.59724 2.64404 + vertex 0.913626 1.59227 2.64345 + endloop + endfacet + facet normal -0.163123 0.0379247 0.985876 + outer loop + vertex 0.913626 1.59227 2.64345 + vertex 0.918352 1.59724 2.64404 + vertex 0.913658 1.59726 2.64326 + endloop + endfacet + facet normal -0.163089 0.0411651 0.985752 + outer loop + vertex 0.918352 1.59724 2.64404 + vertex 0.918361 1.60223 2.64383 + vertex 0.913658 1.59726 2.64326 + endloop + endfacet + facet normal -0.162523 0.0406164 0.985868 + outer loop + vertex 0.913658 1.59726 2.64326 + vertex 0.918361 1.60223 2.64383 + vertex 0.91369 1.60226 2.64306 + endloop + endfacet + facet normal -0.162488 0.0437625 0.98574 + outer loop + vertex 0.918361 1.60223 2.64383 + vertex 0.918373 1.60724 2.64361 + vertex 0.91369 1.60226 2.64306 + endloop + endfacet + facet normal -0.165663 0.0468221 0.98507 + outer loop + vertex 0.91369 1.60226 2.64306 + vertex 0.918373 1.60724 2.64361 + vertex 0.913741 1.60728 2.64283 + endloop + endfacet + facet normal -0.16562 0.0494382 0.98495 + outer loop + vertex 0.918373 1.60724 2.64361 + vertex 0.918398 1.61225 2.64336 + vertex 0.913741 1.60728 2.64283 + endloop + endfacet + facet normal -0.164398 0.0482661 0.985212 + outer loop + vertex 0.913741 1.60728 2.64283 + vertex 0.918398 1.61225 2.64336 + vertex 0.913788 1.61229 2.64259 + endloop + endfacet + facet normal -0.164358 0.050797 0.985092 + outer loop + vertex 0.918398 1.61225 2.64336 + vertex 0.918394 1.61725 2.64311 + vertex 0.913788 1.61229 2.64259 + endloop + endfacet + facet normal -0.16203 0.048585 0.985589 + outer loop + vertex 0.913788 1.61229 2.64259 + vertex 0.918394 1.61725 2.64311 + vertex 0.913744 1.61723 2.64234 + endloop + endfacet + facet normal -0.162023 0.0508545 0.985476 + outer loop + vertex 0.918394 1.61725 2.64311 + vertex 0.918311 1.62224 2.64283 + vertex 0.913744 1.61723 2.64234 + endloop + endfacet + facet normal -0.166925 0.0554199 0.984411 + outer loop + vertex 0.913744 1.61723 2.64234 + vertex 0.918311 1.62224 2.64283 + vertex 0.913251 1.62225 2.64198 + endloop + endfacet + facet normal -0.166989 0.0485625 0.984762 + outer loop + vertex 0.918311 1.62224 2.64283 + vertex 0.918362 1.62732 2.64259 + vertex 0.913251 1.62225 2.64198 + endloop + endfacet + facet normal -0.165202 0.0467117 0.985153 + outer loop + vertex 0.913251 1.62225 2.64198 + vertex 0.918362 1.62732 2.64259 + vertex 0.914035 1.62787 2.64184 + endloop + endfacet + facet normal -0.164761 0.0500153 0.985065 + outer loop + vertex 0.918362 1.62732 2.64259 + vertex 0.918547 1.63234 2.64237 + vertex 0.914035 1.62787 2.64184 + endloop + endfacet + facet normal -0.169007 0.0544114 0.984112 + outer loop + vertex 0.914035 1.62787 2.64184 + vertex 0.918547 1.63234 2.64237 + vertex 0.91435 1.63285 2.64162 + endloop + endfacet + facet normal -0.168825 0.0558552 0.984062 + outer loop + vertex 0.918547 1.63234 2.64237 + vertex 0.918665 1.63723 2.64211 + vertex 0.91435 1.63285 2.64162 + endloop + endfacet + facet normal -0.167307 0.0543213 0.984407 + outer loop + vertex 0.91435 1.63285 2.64162 + vertex 0.918665 1.63723 2.64211 + vertex 0.914586 1.63764 2.6414 + endloop + endfacet + facet normal -0.166231 0.0643588 0.983984 + outer loop + vertex 0.918665 1.63723 2.64211 + vertex 0.918743 1.64208 2.64181 + vertex 0.914586 1.63764 2.6414 + endloop + endfacet + facet normal -0.159723 0.058138 0.985448 + outer loop + vertex 0.914586 1.63764 2.6414 + vertex 0.918743 1.64208 2.64181 + vertex 0.914774 1.64205 2.64117 + endloop + endfacet + facet normal -0.159711 0.0698255 0.984691 + outer loop + vertex 0.914774 1.64205 2.64117 + vertex 0.918743 1.64208 2.64181 + vertex 0.918474 1.64708 2.64141 + endloop + endfacet + facet normal -0.169864 0.0774033 0.982423 + outer loop + vertex 0.91445 1.64518 2.64086 + vertex 0.914774 1.64205 2.64117 + vertex 0.918474 1.64708 2.64141 + endloop + endfacet + facet normal -0.169939 0.0775704 0.982397 + outer loop + vertex 0.91445 1.64518 2.64086 + vertex 0.918474 1.64708 2.64141 + vertex 0.915597 1.64902 2.64076 + endloop + endfacet + facet normal -0.324598 0.122654 0.937866 + outer loop + vertex 0.915597 1.64902 2.64076 + vertex 0.912081 1.64602 2.63993 + vertex 0.91445 1.64518 2.64086 + endloop + endfacet + facet normal -0.170841 0.0762161 0.982346 + outer loop + vertex 0.918474 1.64708 2.64141 + vertex 0.919457 1.65236 2.64117 + vertex 0.915597 1.64902 2.64076 + endloop + endfacet + facet normal -0.0878258 0.0613201 0.994247 + outer loop + vertex 0.918474 1.64708 2.64141 + vertex 0.923644 1.65236 2.64154 + vertex 0.919457 1.65236 2.64117 + endloop + endfacet + facet normal -0.0878283 0.060894 0.994273 + outer loop + vertex 0.919457 1.65236 2.64117 + vertex 0.923644 1.65236 2.64154 + vertex 0.923379 1.65748 2.6412 + endloop + endfacet + facet normal -0.0920579 0.0641379 0.993686 + outer loop + vertex 0.919304 1.65565 2.64094 + vertex 0.919457 1.65236 2.64117 + vertex 0.923379 1.65748 2.6412 + endloop + endfacet + facet normal -0.0898676 0.0591776 0.994194 + outer loop + vertex 0.919304 1.65565 2.64094 + vertex 0.923379 1.65748 2.6412 + vertex 0.920529 1.6595 2.64083 + endloop + endfacet + facet normal -0.185571 0.089172 0.978576 + outer loop + vertex 0.920529 1.6595 2.64083 + vertex 0.91674 1.65623 2.6404 + vertex 0.919304 1.65565 2.64094 + endloop + endfacet + facet normal -0.171181 0.0719702 0.982607 + outer loop + vertex 0.918029 1.66171 2.64023 + vertex 0.91674 1.65623 2.6404 + vertex 0.920529 1.6595 2.64083 + endloop + endfacet + facet normal -0.165747 0.0782583 0.983058 + outer loop + vertex 0.921918 1.66337 2.64075 + vertex 0.918029 1.66171 2.64023 + vertex 0.920529 1.6595 2.64083 + endloop + endfacet + facet normal -0.0824698 0.0486343 0.995406 + outer loop + vertex 0.920529 1.6595 2.64083 + vertex 0.92427 1.66244 2.64099 + vertex 0.921918 1.66337 2.64075 + endloop + endfacet + facet normal -0.0798153 0.0552853 0.995275 + outer loop + vertex 0.924513 1.66558 2.64084 + vertex 0.921918 1.66337 2.64075 + vertex 0.92427 1.66244 2.64099 + endloop + endfacet + facet normal -0.100513 0.0798185 0.991729 + outer loop + vertex 0.921918 1.66337 2.64075 + vertex 0.924513 1.66558 2.64084 + vertex 0.92282 1.66728 2.64053 + endloop + endfacet + facet normal -0.17294 0.095905 0.980252 + outer loop + vertex 0.921918 1.66337 2.64075 + vertex 0.92282 1.66728 2.64053 + vertex 0.918029 1.66171 2.64023 + endloop + endfacet + facet normal -0.147743 0.0739124 0.98626 + outer loop + vertex 0.918029 1.66171 2.64023 + vertex 0.92282 1.66728 2.64053 + vertex 0.918171 1.66703 2.63985 + endloop + endfacet + facet normal -0.258847 0.0752263 0.962984 + outer loop + vertex 0.918029 1.66171 2.64023 + vertex 0.918171 1.66703 2.63985 + vertex 0.913634 1.66202 2.63902 + endloop + endfacet + facet normal -0.259325 0.0696539 0.963275 + outer loop + vertex 0.913283 1.65676 2.63931 + vertex 0.918029 1.66171 2.64023 + vertex 0.913634 1.66202 2.63902 + endloop + endfacet + facet normal -0.254006 0.0705727 0.964625 + outer loop + vertex 0.913634 1.66202 2.63902 + vertex 0.918171 1.66703 2.63985 + vertex 0.913788 1.66713 2.63869 + endloop + endfacet + facet normal -0.253756 0.0769797 0.9642 + outer loop + vertex 0.918171 1.66703 2.63985 + vertex 0.918324 1.67207 2.63949 + vertex 0.913788 1.66713 2.63869 + endloop + endfacet + facet normal -0.263887 0.0868584 0.960635 + outer loop + vertex 0.913788 1.66713 2.63869 + vertex 0.918324 1.67207 2.63949 + vertex 0.913713 1.67209 2.63822 + endloop + endfacet + facet normal -0.263828 0.0889343 0.960461 + outer loop + vertex 0.918324 1.67207 2.63949 + vertex 0.918316 1.67705 2.63903 + vertex 0.913713 1.67209 2.63822 + endloop + endfacet + facet normal -0.280437 0.105405 0.954068 + outer loop + vertex 0.913713 1.67209 2.63822 + vertex 0.918316 1.67705 2.63903 + vertex 0.913119 1.67725 2.63748 + endloop + endfacet + facet normal -0.281502 0.0886906 0.955453 + outer loop + vertex 0.918316 1.67705 2.63903 + vertex 0.918388 1.68209 2.63858 + vertex 0.913119 1.67725 2.63748 + endloop + endfacet + facet normal -0.257809 0.0608885 0.964275 + outer loop + vertex 0.913119 1.67725 2.63748 + vertex 0.918388 1.68209 2.63858 + vertex 0.914028 1.6827 2.63737 + endloop + endfacet + facet normal -0.253929 0.0865536 0.963342 + outer loop + vertex 0.918388 1.68209 2.63858 + vertex 0.918565 1.68713 2.63817 + vertex 0.914028 1.6827 2.63737 + endloop + endfacet + facet normal -0.251352 0.0837418 0.964266 + outer loop + vertex 0.914028 1.6827 2.63737 + vertex 0.918565 1.68713 2.63817 + vertex 0.91436 1.68764 2.63703 + endloop + endfacet + facet normal -0.250855 0.087379 0.964073 + outer loop + vertex 0.918565 1.68713 2.63817 + vertex 0.918613 1.6921 2.63773 + vertex 0.91436 1.68764 2.63703 + endloop + endfacet + facet normal -0.244584 0.0810666 0.966233 + outer loop + vertex 0.91436 1.68764 2.63703 + vertex 0.918613 1.6921 2.63773 + vertex 0.914552 1.69256 2.63667 + endloop + endfacet + facet normal -0.24395 0.0860729 0.965961 + outer loop + vertex 0.918613 1.6921 2.63773 + vertex 0.918584 1.69708 2.63728 + vertex 0.914552 1.69256 2.63667 + endloop + endfacet + facet normal -0.230508 0.0735093 0.97029 + outer loop + vertex 0.914552 1.69256 2.63667 + vertex 0.918584 1.69708 2.63728 + vertex 0.914677 1.69715 2.63635 + endloop + endfacet + facet normal -0.230185 0.0832967 0.969575 + outer loop + vertex 0.914677 1.69715 2.63635 + vertex 0.918584 1.69708 2.63728 + vertex 0.91822 1.70215 2.63676 + endloop + endfacet + facet normal -0.236103 0.0876353 0.967768 + outer loop + vertex 0.914325 1.70037 2.63597 + vertex 0.914677 1.69715 2.63635 + vertex 0.91822 1.70215 2.63676 + endloop + endfacet + facet normal -0.240992 0.0993851 0.965425 + outer loop + vertex 0.914325 1.70037 2.63597 + vertex 0.91822 1.70215 2.63676 + vertex 0.915401 1.70415 2.63585 + endloop + endfacet + facet normal -0.441384 0.15381 0.884037 + outer loop + vertex 0.915401 1.70415 2.63585 + vertex 0.912137 1.70119 2.63474 + vertex 0.914325 1.70037 2.63597 + endloop + endfacet + facet normal -0.431391 0.140084 0.891223 + outer loop + vertex 0.913034 1.70642 2.63435 + vertex 0.912137 1.70119 2.63474 + vertex 0.915401 1.70415 2.63585 + endloop + endfacet + facet normal -0.430407 0.141298 0.891507 + outer loop + vertex 0.916478 1.70784 2.63579 + vertex 0.913034 1.70642 2.63435 + vertex 0.915401 1.70415 2.63585 + endloop + endfacet + facet normal -0.232586 0.0848607 0.968867 + outer loop + vertex 0.915401 1.70415 2.63585 + vertex 0.919152 1.70733 2.63647 + vertex 0.916478 1.70784 2.63579 + endloop + endfacet + facet normal -0.230813 0.0937057 0.968475 + outer loop + vertex 0.919024 1.7105 2.63614 + vertex 0.916478 1.70784 2.63579 + vertex 0.919152 1.70733 2.63647 + endloop + endfacet + facet normal -0.296415 0.159995 0.941563 + outer loop + vertex 0.916478 1.70784 2.63579 + vertex 0.919024 1.7105 2.63614 + vertex 0.916479 1.71111 2.63523 + endloop + endfacet + facet normal -0.433176 0.151015 0.888568 + outer loop + vertex 0.916478 1.70784 2.63579 + vertex 0.916479 1.71111 2.63523 + vertex 0.913034 1.70642 2.63435 + endloop + endfacet + facet normal -0.439602 0.156512 0.884451 + outer loop + vertex 0.913034 1.70642 2.63435 + vertex 0.916479 1.71111 2.63523 + vertex 0.912689 1.7119 2.63321 + endloop + endfacet + facet normal -0.242477 0.0972251 0.965273 + outer loop + vertex 0.91822 1.70215 2.63676 + vertex 0.919152 1.70733 2.63647 + vertex 0.915401 1.70415 2.63585 + endloop + endfacet + facet normal -0.150446 0.084653 0.984987 + outer loop + vertex 0.918388 1.68209 2.63858 + vertex 0.92341 1.6871 2.63891 + vertex 0.918565 1.68713 2.63817 + endloop + endfacet + facet normal -0.150335 0.0910067 0.984438 + outer loop + vertex 0.92341 1.6871 2.63891 + vertex 0.923365 1.69207 2.63845 + vertex 0.918565 1.68713 2.63817 + endloop + endfacet + facet normal -0.0821852 0.092357 0.992328 + outer loop + vertex 0.92341 1.6871 2.63891 + vertex 0.928417 1.69218 2.63886 + vertex 0.923365 1.69207 2.63845 + endloop + endfacet + facet normal -0.0821887 0.0925838 0.992307 + outer loop + vertex 0.928417 1.69218 2.63886 + vertex 0.928353 1.69715 2.63839 + vertex 0.923365 1.69207 2.63845 + endloop + endfacet + facet normal -0.0844409 0.0947906 0.99191 + outer loop + vertex 0.923365 1.69207 2.63845 + vertex 0.928353 1.69715 2.63839 + vertex 0.923308 1.69706 2.63797 + endloop + endfacet + facet normal -0.147407 0.0933638 0.98466 + outer loop + vertex 0.923365 1.69207 2.63845 + vertex 0.923308 1.69706 2.63797 + vertex 0.918613 1.6921 2.63773 + endloop + endfacet + facet normal -0.147517 0.0882311 0.985116 + outer loop + vertex 0.918565 1.68713 2.63817 + vertex 0.923365 1.69207 2.63845 + vertex 0.918613 1.6921 2.63773 + endloop + endfacet + facet normal -0.142308 0.0884817 0.98586 + outer loop + vertex 0.918613 1.6921 2.63773 + vertex 0.923308 1.69706 2.63797 + vertex 0.918584 1.69708 2.63728 + endloop + endfacet + facet normal -0.142209 0.0941569 0.985348 + outer loop + vertex 0.923308 1.69706 2.63797 + vertex 0.923259 1.70213 2.63748 + vertex 0.918584 1.69708 2.63728 + endloop + endfacet + facet normal -0.139374 0.0915073 0.986003 + outer loop + vertex 0.918584 1.69708 2.63728 + vertex 0.923259 1.70213 2.63748 + vertex 0.91822 1.70215 2.63676 + endloop + endfacet + facet normal -0.139372 0.0916228 0.985992 + outer loop + vertex 0.923259 1.70213 2.63748 + vertex 0.923356 1.70725 2.63701 + vertex 0.91822 1.70215 2.63676 + endloop + endfacet + facet normal -0.125509 0.0775188 0.989059 + outer loop + vertex 0.91822 1.70215 2.63676 + vertex 0.923356 1.70725 2.63701 + vertex 0.919152 1.70733 2.63647 + endloop + endfacet + facet normal -0.125048 0.0929741 0.987785 + outer loop + vertex 0.919152 1.70733 2.63647 + vertex 0.923356 1.70725 2.63701 + vertex 0.923259 1.71229 2.63653 + endloop + endfacet + facet normal -0.0773704 0.0943437 0.992529 + outer loop + vertex 0.923356 1.70725 2.63701 + vertex 0.928448 1.71238 2.63692 + vertex 0.923259 1.71229 2.63653 + endloop + endfacet + facet normal -0.0773757 0.0949479 0.992471 + outer loop + vertex 0.928448 1.71238 2.63692 + vertex 0.928531 1.71718 2.63647 + vertex 0.923259 1.71229 2.63653 + endloop + endfacet + facet normal -0.0725965 0.0898072 0.99331 + outer loop + vertex 0.923259 1.71229 2.63653 + vertex 0.928531 1.71718 2.63647 + vertex 0.924516 1.71724 2.63617 + endloop + endfacet + facet normal -0.0725596 0.091538 0.993155 + outer loop + vertex 0.924516 1.71724 2.63617 + vertex 0.928531 1.71718 2.63647 + vertex 0.928481 1.72152 2.63607 + endloop + endfacet + facet normal -0.0773689 0.0959727 0.992373 + outer loop + vertex 0.924837 1.72034 2.6359 + vertex 0.924516 1.71724 2.63617 + vertex 0.928481 1.72152 2.63607 + endloop + endfacet + facet normal -0.0765703 0.0934729 0.992673 + outer loop + vertex 0.924837 1.72034 2.6359 + vertex 0.928481 1.72152 2.63607 + vertex 0.926652 1.72318 2.63577 + endloop + endfacet + facet normal -0.148072 0.138543 0.979224 + outer loop + vertex 0.926652 1.72318 2.63577 + vertex 0.922884 1.72189 2.63538 + vertex 0.924837 1.72034 2.6359 + endloop + endfacet + facet normal -0.146087 0.132421 0.980369 + outer loop + vertex 0.926652 1.72318 2.63577 + vertex 0.927885 1.72701 2.63544 + vertex 0.922884 1.72189 2.63538 + endloop + endfacet + facet normal -0.137071 0.123589 0.982821 + outer loop + vertex 0.922884 1.72189 2.63538 + vertex 0.927885 1.72701 2.63544 + vertex 0.923122 1.72689 2.63479 + endloop + endfacet + facet normal -0.137046 0.119973 0.983273 + outer loop + vertex 0.927885 1.72701 2.63544 + vertex 0.928223 1.73204 2.63487 + vertex 0.923122 1.72689 2.63479 + endloop + endfacet + facet normal -0.142503 0.125409 0.981817 + outer loop + vertex 0.923122 1.72689 2.63479 + vertex 0.928223 1.73204 2.63487 + vertex 0.923315 1.73196 2.63417 + endloop + endfacet + facet normal -0.14252 0.118759 0.982642 + outer loop + vertex 0.928223 1.73204 2.63487 + vertex 0.928354 1.73709 2.63428 + vertex 0.923315 1.73196 2.63417 + endloop + endfacet + facet normal -0.151713 0.12784 0.980122 + outer loop + vertex 0.923315 1.73196 2.63417 + vertex 0.928354 1.73709 2.63428 + vertex 0.923356 1.73702 2.63351 + endloop + endfacet + facet normal -0.151784 0.106156 0.982697 + outer loop + vertex 0.928354 1.73709 2.63428 + vertex 0.928422 1.7421 2.63375 + vertex 0.923356 1.73702 2.63351 + endloop + endfacet + facet normal -0.144223 0.0985309 0.984627 + outer loop + vertex 0.923356 1.73702 2.63351 + vertex 0.928422 1.7421 2.63375 + vertex 0.923486 1.74213 2.63302 + endloop + endfacet + facet normal -0.144839 0.064103 0.987377 + outer loop + vertex 0.928422 1.7421 2.63375 + vertex 0.928442 1.74706 2.63343 + vertex 0.923486 1.74213 2.63302 + endloop + endfacet + facet normal -0.0882086 0.114565 0.989492 + outer loop + vertex 0.926652 1.72318 2.63577 + vertex 0.929433 1.72506 2.6358 + vertex 0.927885 1.72701 2.63544 + endloop + endfacet + facet normal -0.0824305 0.119159 0.989448 + outer loop + vertex 0.931752 1.72782 2.63566 + vertex 0.927885 1.72701 2.63544 + vertex 0.929433 1.72506 2.6358 + endloop + endfacet + facet normal -0.0509134 0.0928496 0.994378 + outer loop + vertex 0.929433 1.72506 2.6358 + vertex 0.932534 1.72536 2.63593 + vertex 0.931752 1.72782 2.63566 + endloop + endfacet + facet normal -0.041984 0.0957078 0.994524 + outer loop + vertex 0.935638 1.72913 2.6357 + vertex 0.931752 1.72782 2.63566 + vertex 0.932534 1.72536 2.63593 + endloop + endfacet + facet normal -0.0440562 0.101836 0.993825 + outer loop + vertex 0.931752 1.72782 2.63566 + vertex 0.935638 1.72913 2.6357 + vertex 0.933443 1.73202 2.6353 + endloop + endfacet + facet normal -0.0505322 0.0886836 0.994777 + outer loop + vertex 0.929433 1.72506 2.6358 + vertex 0.928481 1.72152 2.63607 + vertex 0.932534 1.72536 2.63593 + endloop + endfacet + facet normal -0.0486205 0.0866736 0.99505 + outer loop + vertex 0.928481 1.72152 2.63607 + vertex 0.93303 1.72176 2.63627 + vertex 0.932534 1.72536 2.63593 + endloop + endfacet + facet normal -0.0819401 0.116726 0.989778 + outer loop + vertex 0.931752 1.72782 2.63566 + vertex 0.933443 1.73202 2.6353 + vertex 0.927885 1.72701 2.63544 + endloop + endfacet + facet normal -0.0822035 0.117017 0.989722 + outer loop + vertex 0.927885 1.72701 2.63544 + vertex 0.933443 1.73202 2.6353 + vertex 0.928223 1.73204 2.63487 + endloop + endfacet + facet normal -0.0823382 0.105575 0.990997 + outer loop + vertex 0.933443 1.73202 2.6353 + vertex 0.933388 1.73718 2.63475 + vertex 0.928223 1.73204 2.63487 + endloop + endfacet + facet normal -0.0949809 0.118208 0.988436 + outer loop + vertex 0.928223 1.73204 2.63487 + vertex 0.933388 1.73718 2.63475 + vertex 0.928354 1.73709 2.63428 + endloop + endfacet + facet normal -0.0948655 0.101438 0.990308 + outer loop + vertex 0.933388 1.73718 2.63475 + vertex 0.933449 1.74218 2.63424 + vertex 0.928354 1.73709 2.63428 + endloop + endfacet + facet normal -0.0995747 0.106147 0.989352 + outer loop + vertex 0.928354 1.73709 2.63428 + vertex 0.933449 1.74218 2.63424 + vertex 0.928422 1.7421 2.63375 + endloop + endfacet + facet normal -0.0993903 0.0785105 0.991946 + outer loop + vertex 0.933449 1.74218 2.63424 + vertex 0.93346 1.74714 2.63385 + vertex 0.928422 1.7421 2.63375 + endloop + endfacet + facet normal -0.085236 0.0643054 0.994283 + outer loop + vertex 0.928422 1.7421 2.63375 + vertex 0.93346 1.74714 2.63385 + vertex 0.928442 1.74706 2.63343 + endloop + endfacet + facet normal -0.0849901 0.0405609 0.995556 + outer loop + vertex 0.93346 1.74714 2.63385 + vertex 0.933404 1.75205 2.63365 + vertex 0.928442 1.74706 2.63343 + endloop + endfacet + facet normal -0.0549159 0.010528 0.998435 + outer loop + vertex 0.928442 1.74706 2.63343 + vertex 0.933404 1.75205 2.63365 + vertex 0.928382 1.752 2.63337 + endloop + endfacet + facet normal -0.0750707 0.0951196 0.992631 + outer loop + vertex 0.929433 1.72506 2.6358 + vertex 0.926652 1.72318 2.63577 + vertex 0.928481 1.72152 2.63607 + endloop + endfacet + facet normal -0.0488695 0.091944 0.994564 + outer loop + vertex 0.928531 1.71718 2.63647 + vertex 0.93303 1.72176 2.63627 + vertex 0.928481 1.72152 2.63607 + endloop + endfacet + facet normal -0.0477099 0.0908103 0.994725 + outer loop + vertex 0.933467 1.7174 2.63669 + vertex 0.93303 1.72176 2.63627 + vertex 0.928531 1.71718 2.63647 + endloop + endfacet + facet normal -0.047857 0.0946166 0.994363 + outer loop + vertex 0.928448 1.71238 2.63692 + vertex 0.933467 1.7174 2.63669 + vertex 0.928531 1.71718 2.63647 + endloop + endfacet + facet normal -0.0474667 0.0942289 0.994418 + outer loop + vertex 0.933658 1.71251 2.63716 + vertex 0.933467 1.7174 2.63669 + vertex 0.928448 1.71238 2.63692 + endloop + endfacet + facet normal -0.0475071 0.0961265 0.994235 + outer loop + vertex 0.928422 1.70731 2.63741 + vertex 0.933658 1.71251 2.63716 + vertex 0.928448 1.71238 2.63692 + endloop + endfacet + facet normal -0.0469703 0.0955899 0.994312 + outer loop + vertex 0.933627 1.70738 2.63765 + vertex 0.933658 1.71251 2.63716 + vertex 0.928422 1.70731 2.63741 + endloop + endfacet + facet normal -0.0469808 0.0967574 0.994199 + outer loop + vertex 0.928356 1.70219 2.63791 + vertex 0.933627 1.70738 2.63765 + vertex 0.928422 1.70731 2.63741 + endloop + endfacet + facet normal -0.0438224 0.0935722 0.994648 + outer loop + vertex 0.93351 1.70224 2.63813 + vertex 0.933627 1.70738 2.63765 + vertex 0.928356 1.70219 2.63791 + endloop + endfacet + facet normal -0.0438321 0.0949587 0.994516 + outer loop + vertex 0.928353 1.69715 2.63839 + vertex 0.93351 1.70224 2.63813 + vertex 0.928356 1.70219 2.63791 + endloop + endfacet + facet normal -0.0397265 0.0908354 0.995073 + outer loop + vertex 0.933456 1.69721 2.63859 + vertex 0.93351 1.70224 2.63813 + vertex 0.928353 1.69715 2.63839 + endloop + endfacet + facet normal -0.0397515 0.0933624 0.994838 + outer loop + vertex 0.928417 1.69218 2.63886 + vertex 0.933456 1.69721 2.63859 + vertex 0.928353 1.69715 2.63839 + endloop + endfacet + facet normal -0.0343713 0.0880113 0.995526 + outer loop + vertex 0.933478 1.69226 2.63903 + vertex 0.933456 1.69721 2.63859 + vertex 0.928417 1.69218 2.63886 + endloop + endfacet + facet normal -0.0344015 0.0906714 0.995287 + outer loop + vertex 0.928474 1.68725 2.63931 + vertex 0.933478 1.69226 2.63903 + vertex 0.928417 1.69218 2.63886 + endloop + endfacet + facet normal -0.0281915 0.0845075 0.996024 + outer loop + vertex 0.933473 1.6873 2.63945 + vertex 0.933478 1.69226 2.63903 + vertex 0.928474 1.68725 2.63931 + endloop + endfacet + facet normal -0.0282065 0.0862536 0.995874 + outer loop + vertex 0.928424 1.68231 2.63973 + vertex 0.933473 1.6873 2.63945 + vertex 0.928474 1.68725 2.63931 + endloop + endfacet + facet normal -0.0218198 0.0798388 0.996569 + outer loop + vertex 0.933378 1.68235 2.63984 + vertex 0.933473 1.6873 2.63945 + vertex 0.928424 1.68231 2.63973 + endloop + endfacet + facet normal -0.021807 0.0780915 0.996708 + outer loop + vertex 0.928286 1.67736 2.64012 + vertex 0.933378 1.68235 2.63984 + vertex 0.928424 1.68231 2.63973 + endloop + endfacet + facet normal -0.0180888 0.0743184 0.99707 + outer loop + vertex 0.9334 1.67752 2.6402 + vertex 0.933378 1.68235 2.63984 + vertex 0.928286 1.67736 2.64012 + endloop + endfacet + facet normal -0.0180547 0.0731657 0.997156 + outer loop + vertex 0.928292 1.67227 2.64049 + vertex 0.9334 1.67752 2.6402 + vertex 0.928286 1.67736 2.64012 + endloop + endfacet + facet normal -0.0142331 0.0694658 0.997483 + outer loop + vertex 0.934165 1.67323 2.64051 + vertex 0.9334 1.67752 2.6402 + vertex 0.928292 1.67227 2.64049 + endloop + endfacet + facet normal -0.0163584 0.0823891 0.996466 + outer loop + vertex 0.928292 1.67227 2.64049 + vertex 0.930535 1.66936 2.64077 + vertex 0.934165 1.67323 2.64051 + endloop + endfacet + facet normal -0.00297947 0.0699381 0.997547 + outer loop + vertex 0.930535 1.66936 2.64077 + vertex 0.935408 1.66949 2.64078 + vertex 0.934165 1.67323 2.64051 + endloop + endfacet + facet normal 0.00944391 0.0740437 0.99721 + outer loop + vertex 0.934165 1.67323 2.64051 + vertex 0.935408 1.66949 2.64078 + vertex 0.939764 1.67292 2.64048 + endloop + endfacet + facet normal 0.00924742 0.0705009 0.997469 + outer loop + vertex 0.939764 1.67292 2.64048 + vertex 0.938594 1.67753 2.64017 + vertex 0.934165 1.67323 2.64051 + endloop + endfacet + facet normal 0.0192717 0.0730252 0.997144 + outer loop + vertex 0.939764 1.67292 2.64048 + vertex 0.943603 1.6775 2.64007 + vertex 0.938594 1.67753 2.64017 + endloop + endfacet + facet normal 0.0192759 0.0741442 0.997061 + outer loop + vertex 0.943603 1.6775 2.64007 + vertex 0.943272 1.68215 2.63973 + vertex 0.938594 1.67753 2.64017 + endloop + endfacet + facet normal 0.0191867 0.074234 0.997056 + outer loop + vertex 0.938594 1.67753 2.64017 + vertex 0.943272 1.68215 2.63973 + vertex 0.938321 1.68228 2.63982 + endloop + endfacet + facet normal 0.00663559 0.0735283 0.997271 + outer loop + vertex 0.938594 1.67753 2.64017 + vertex 0.938321 1.68228 2.63982 + vertex 0.9334 1.67752 2.6402 + endloop + endfacet + facet normal 0.0192338 0.0761168 0.996913 + outer loop + vertex 0.943272 1.68215 2.63973 + vertex 0.943293 1.68712 2.63935 + vertex 0.938321 1.68228 2.63982 + endloop + endfacet + facet normal 0.0187292 0.0766314 0.996884 + outer loop + vertex 0.938321 1.68228 2.63982 + vertex 0.943293 1.68712 2.63935 + vertex 0.938384 1.68724 2.63943 + endloop + endfacet + facet normal 0.00578578 0.0768085 0.997029 + outer loop + vertex 0.938321 1.68228 2.63982 + vertex 0.938384 1.68724 2.63943 + vertex 0.933378 1.68235 2.63984 + endloop + endfacet + facet normal 0.0187705 0.0785691 0.996732 + outer loop + vertex 0.943293 1.68712 2.63935 + vertex 0.943395 1.69218 2.63895 + vertex 0.938384 1.68724 2.63943 + endloop + endfacet + facet normal 0.0172637 0.0800884 0.996638 + outer loop + vertex 0.938384 1.68724 2.63943 + vertex 0.943395 1.69218 2.63895 + vertex 0.938453 1.69223 2.63903 + endloop + endfacet + facet normal 0.00327463 0.0802916 0.996766 + outer loop + vertex 0.938384 1.68724 2.63943 + vertex 0.938453 1.69223 2.63903 + vertex 0.933473 1.6873 2.63945 + endloop + endfacet + facet normal 0.0172744 0.0811503 0.996552 + outer loop + vertex 0.943395 1.69218 2.63895 + vertex 0.943501 1.69722 2.63854 + vertex 0.938453 1.69223 2.63903 + endloop + endfacet + facet normal 0.0263897 0.0809446 0.996369 + outer loop + vertex 0.943395 1.69218 2.63895 + vertex 0.948529 1.69726 2.6384 + vertex 0.943501 1.69722 2.63854 + endloop + endfacet + facet normal 0.0263715 0.0826631 0.996229 + outer loop + vertex 0.948529 1.69726 2.6384 + vertex 0.948686 1.70236 2.63797 + vertex 0.943501 1.69722 2.63854 + endloop + endfacet + facet normal 0.0261764 0.0828585 0.996217 + outer loop + vertex 0.943501 1.69722 2.63854 + vertex 0.948686 1.70236 2.63797 + vertex 0.943649 1.70229 2.63811 + endloop + endfacet + facet normal 0.0154773 0.0831875 0.996414 + outer loop + vertex 0.943501 1.69722 2.63854 + vertex 0.943649 1.70229 2.63811 + vertex 0.938497 1.69722 2.63862 + endloop + endfacet + facet normal 0.0154775 0.0829565 0.996433 + outer loop + vertex 0.938453 1.69223 2.63903 + vertex 0.943501 1.69722 2.63854 + vertex 0.938497 1.69722 2.63862 + endloop + endfacet + facet normal -0.000938889 0.0831108 0.99654 + outer loop + vertex 0.938453 1.69223 2.63903 + vertex 0.938497 1.69722 2.63862 + vertex 0.933478 1.69226 2.63903 + endloop + endfacet + facet normal 0.0131849 0.0855018 0.996251 + outer loop + vertex 0.938497 1.69722 2.63862 + vertex 0.943649 1.70229 2.63811 + vertex 0.938607 1.70227 2.63818 + endloop + endfacet + facet normal -0.00600024 0.0859227 0.996284 + outer loop + vertex 0.938497 1.69722 2.63862 + vertex 0.938607 1.70227 2.63818 + vertex 0.933456 1.69721 2.63859 + endloop + endfacet + facet normal 0.0131873 0.0850745 0.996287 + outer loop + vertex 0.943649 1.70229 2.63811 + vertex 0.943822 1.70742 2.63767 + vertex 0.938607 1.70227 2.63818 + endloop + endfacet + facet normal 0.010553 0.0877193 0.996089 + outer loop + vertex 0.938607 1.70227 2.63818 + vertex 0.943822 1.70742 2.63767 + vertex 0.938774 1.70741 2.63773 + endloop + endfacet + facet normal -0.0106041 0.088401 0.996029 + outer loop + vertex 0.938607 1.70227 2.63818 + vertex 0.938774 1.70741 2.63773 + vertex 0.93351 1.70224 2.63813 + endloop + endfacet + facet normal 0.0105584 0.0861564 0.996226 + outer loop + vertex 0.943822 1.70742 2.63767 + vertex 0.943837 1.71255 2.63723 + vertex 0.938774 1.70741 2.63773 + endloop + endfacet + facet normal 0.00639141 0.09023 0.9959 + outer loop + vertex 0.938774 1.70741 2.63773 + vertex 0.943837 1.71255 2.63723 + vertex 0.938825 1.71256 2.63726 + endloop + endfacet + facet normal -0.0151461 0.0904333 0.995787 + outer loop + vertex 0.938774 1.70741 2.63773 + vertex 0.938825 1.71256 2.63726 + vertex 0.933627 1.70738 2.63765 + endloop + endfacet + facet normal 0.00638407 0.0865935 0.996223 + outer loop + vertex 0.943837 1.71255 2.63723 + vertex 0.94345 1.71738 2.63681 + vertex 0.938825 1.71256 2.63726 + endloop + endfacet + facet normal 0.000679087 0.092029 0.995756 + outer loop + vertex 0.938825 1.71256 2.63726 + vertex 0.94345 1.71738 2.63681 + vertex 0.938568 1.7175 2.6368 + endloop + endfacet + facet normal -0.0202161 0.0909291 0.995652 + outer loop + vertex 0.938825 1.71256 2.63726 + vertex 0.938568 1.7175 2.6368 + vertex 0.933658 1.71251 2.63716 + endloop + endfacet + facet normal -0.0245908 0.0951962 0.995155 + outer loop + vertex 0.933658 1.71251 2.63716 + vertex 0.938568 1.7175 2.6368 + vertex 0.933467 1.7174 2.63669 + endloop + endfacet + facet normal -0.0244752 0.0890242 0.995729 + outer loop + vertex 0.938568 1.7175 2.6368 + vertex 0.937913 1.722 2.63638 + vertex 0.933467 1.7174 2.63669 + endloop + endfacet + facet normal -0.0284151 0.0927977 0.995279 + outer loop + vertex 0.933467 1.7174 2.63669 + vertex 0.937913 1.722 2.63638 + vertex 0.93303 1.72176 2.63627 + endloop + endfacet + facet normal -0.0280838 0.0858923 0.995909 + outer loop + vertex 0.937913 1.722 2.63638 + vertex 0.93691 1.72588 2.63602 + vertex 0.93303 1.72176 2.63627 + endloop + endfacet + facet normal -0.031487 0.0890754 0.995527 + outer loop + vertex 0.93303 1.72176 2.63627 + vertex 0.93691 1.72588 2.63602 + vertex 0.932534 1.72536 2.63593 + endloop + endfacet + facet normal -0.0312404 0.086947 0.995723 + outer loop + vertex 0.93691 1.72588 2.63602 + vertex 0.935638 1.72913 2.6357 + vertex 0.932534 1.72536 2.63593 + endloop + endfacet + facet normal -0.0182767 0.0919917 0.995592 + outer loop + vertex 0.940395 1.72963 2.63574 + vertex 0.935638 1.72913 2.6357 + vertex 0.93691 1.72588 2.63602 + endloop + endfacet + facet normal -0.00939566 0.0838188 0.996437 + outer loop + vertex 0.941779 1.72593 2.63606 + vertex 0.940395 1.72963 2.63574 + vertex 0.93691 1.72588 2.63602 + endloop + endfacet + facet normal 0.00733904 0.0900261 0.995912 + outer loop + vertex 0.945255 1.72936 2.63573 + vertex 0.940395 1.72963 2.63574 + vertex 0.941779 1.72593 2.63606 + endloop + endfacet + facet normal 0.0140262 0.0832955 0.996426 + outer loop + vertex 0.947026 1.72524 2.63605 + vertex 0.945255 1.72936 2.63573 + vertex 0.941779 1.72593 2.63606 + endloop + endfacet + facet normal 0.0150267 0.0908924 0.995747 + outer loop + vertex 0.942815 1.72183 2.63642 + vertex 0.947026 1.72524 2.63605 + vertex 0.941779 1.72593 2.63606 + endloop + endfacet + facet normal -0.00461846 0.0859754 0.996287 + outer loop + vertex 0.942815 1.72183 2.63642 + vertex 0.941779 1.72593 2.63606 + vertex 0.937913 1.722 2.63638 + endloop + endfacet + facet normal 0.0163269 0.089299 0.995871 + outer loop + vertex 0.946843 1.72107 2.63642 + vertex 0.947026 1.72524 2.63605 + vertex 0.942815 1.72183 2.63642 + endloop + endfacet + facet normal 0.016335 0.0893418 0.995867 + outer loop + vertex 0.94345 1.71738 2.63681 + vertex 0.946843 1.72107 2.63642 + vertex 0.942815 1.72183 2.63642 + endloop + endfacet + facet normal 0.0223747 0.0838242 0.996229 + outer loop + vertex 0.948146 1.71732 2.63671 + vertex 0.946843 1.72107 2.63642 + vertex 0.94345 1.71738 2.63681 + endloop + endfacet + facet normal 0.0332206 0.0875535 0.995606 + outer loop + vertex 0.948146 1.71732 2.63671 + vertex 0.951397 1.72201 2.63619 + vertex 0.946843 1.72107 2.63642 + endloop + endfacet + facet normal 0.0347798 0.0864752 0.995647 + outer loop + vertex 0.952883 1.71704 2.63657 + vertex 0.951397 1.72201 2.63619 + vertex 0.948146 1.71732 2.63671 + endloop + endfacet + facet normal 0.0347773 0.0864304 0.995651 + outer loop + vertex 0.948725 1.7125 2.63711 + vertex 0.952883 1.71704 2.63657 + vertex 0.948146 1.71732 2.63671 + endloop + endfacet + facet normal 0.0252346 0.0853172 0.996034 + outer loop + vertex 0.948725 1.7125 2.63711 + vertex 0.948146 1.71732 2.63671 + vertex 0.943837 1.71255 2.63723 + endloop + endfacet + facet normal 0.0342883 0.0868748 0.995629 + outer loop + vertex 0.953456 1.71236 2.63696 + vertex 0.952883 1.71704 2.63657 + vertex 0.948725 1.7125 2.63711 + endloop + endfacet + facet normal 0.0342517 0.0854507 0.995753 + outer loop + vertex 0.948805 1.70746 2.63754 + vertex 0.953456 1.71236 2.63696 + vertex 0.948725 1.7125 2.63711 + endloop + endfacet + facet normal 0.0260215 0.0853422 0.996012 + outer loop + vertex 0.948805 1.70746 2.63754 + vertex 0.948725 1.7125 2.63711 + vertex 0.943822 1.70742 2.63767 + endloop + endfacet + facet normal 0.0337446 0.0859289 0.99573 + outer loop + vertex 0.953754 1.70754 2.63736 + vertex 0.953456 1.71236 2.63696 + vertex 0.948805 1.70746 2.63754 + endloop + endfacet + facet normal 0.0337781 0.0843077 0.995867 + outer loop + vertex 0.948686 1.70236 2.63797 + vertex 0.953754 1.70754 2.63736 + vertex 0.948805 1.70746 2.63754 + endloop + endfacet + facet normal 0.0338291 0.0842581 0.99587 + outer loop + vertex 0.95375 1.70248 2.63779 + vertex 0.953754 1.70754 2.63736 + vertex 0.948686 1.70236 2.63797 + endloop + endfacet + facet normal 0.0404374 0.0842332 0.995625 + outer loop + vertex 0.95375 1.70248 2.63779 + vertex 0.958689 1.70758 2.63716 + vertex 0.953754 1.70754 2.63736 + endloop + endfacet + facet normal 0.0404196 0.0859243 0.995481 + outer loop + vertex 0.958689 1.70758 2.63716 + vertex 0.958118 1.71237 2.63677 + vertex 0.953754 1.70754 2.63736 + endloop + endfacet + facet normal 0.0451209 0.0864647 0.995233 + outer loop + vertex 0.958689 1.70758 2.63716 + vertex 0.962899 1.71205 2.63658 + vertex 0.958118 1.71237 2.63677 + endloop + endfacet + facet normal 0.0452051 0.0877978 0.995112 + outer loop + vertex 0.962899 1.71205 2.63658 + vertex 0.961407 1.71704 2.63621 + vertex 0.958118 1.71237 2.63677 + endloop + endfacet + facet normal 0.0442533 0.0884662 0.995096 + outer loop + vertex 0.958118 1.71237 2.63677 + vertex 0.961407 1.71704 2.63621 + vertex 0.956854 1.71613 2.63649 + endloop + endfacet + facet normal 0.0400057 0.08706 0.995399 + outer loop + vertex 0.958118 1.71237 2.63677 + vertex 0.956854 1.71613 2.63649 + vertex 0.953456 1.71236 2.63696 + endloop + endfacet + facet normal 0.0441481 0.0889797 0.995055 + outer loop + vertex 0.957048 1.72052 2.63609 + vertex 0.956854 1.71613 2.63649 + vertex 0.961407 1.71704 2.63621 + endloop + endfacet + facet normal 0.0440634 0.0888742 0.995068 + outer loop + vertex 0.961318 1.72125 2.63584 + vertex 0.957048 1.72052 2.63609 + vertex 0.961407 1.71704 2.63621 + endloop + endfacet + facet normal 0.0449993 0.0888902 0.995024 + outer loop + vertex 0.961318 1.72125 2.63584 + vertex 0.961407 1.71704 2.63621 + vertex 0.965338 1.71991 2.63577 + endloop + endfacet + facet normal 0.044747 0.0881257 0.995104 + outer loop + vertex 0.965338 1.71991 2.63577 + vertex 0.963731 1.72441 2.63545 + vertex 0.961318 1.72125 2.63584 + endloop + endfacet + facet normal 0.0444487 0.0883526 0.995097 + outer loop + vertex 0.959268 1.72382 2.6357 + vertex 0.961318 1.72125 2.63584 + vertex 0.963731 1.72441 2.63545 + endloop + endfacet + facet normal 0.0445454 0.0876371 0.995156 + outer loop + vertex 0.959268 1.72382 2.6357 + vertex 0.963731 1.72441 2.63545 + vertex 0.959499 1.72785 2.63533 + endloop + endfacet + facet normal 0.0434742 0.0877022 0.995198 + outer loop + vertex 0.955323 1.72502 2.63577 + vertex 0.959268 1.72382 2.6357 + vertex 0.959499 1.72785 2.63533 + endloop + endfacet + facet normal 0.0433338 0.0879075 0.995186 + outer loop + vertex 0.953759 1.72941 2.63545 + vertex 0.955323 1.72502 2.63577 + vertex 0.959499 1.72785 2.63533 + endloop + endfacet + facet normal 0.0427723 0.0858315 0.995391 + outer loop + vertex 0.959499 1.72785 2.63533 + vertex 0.958473 1.73263 2.63497 + vertex 0.953759 1.72941 2.63545 + endloop + endfacet + facet normal 0.0431643 0.085262 0.995423 + outer loop + vertex 0.953759 1.72941 2.63545 + vertex 0.958473 1.73263 2.63497 + vertex 0.954442 1.73363 2.63506 + endloop + endfacet + facet normal 0.0372349 0.0862371 0.995579 + outer loop + vertex 0.949589 1.73263 2.63532 + vertex 0.953759 1.72941 2.63545 + vertex 0.954442 1.73363 2.63506 + endloop + endfacet + facet normal 0.038331 0.0810162 0.995975 + outer loop + vertex 0.954442 1.73363 2.63506 + vertex 0.953462 1.73728 2.6348 + vertex 0.949589 1.73263 2.63532 + endloop + endfacet + facet normal 0.0346848 0.0840399 0.995859 + outer loop + vertex 0.949589 1.73263 2.63532 + vertex 0.953462 1.73728 2.6348 + vertex 0.948482 1.73737 2.63496 + endloop + endfacet + facet normal 0.023131 0.0813841 0.996414 + outer loop + vertex 0.949589 1.73263 2.63532 + vertex 0.948482 1.73737 2.63496 + vertex 0.944195 1.73329 2.63539 + endloop + endfacet + facet normal 0.0242934 0.0908866 0.995565 + outer loop + vertex 0.944195 1.73329 2.63539 + vertex 0.945255 1.72936 2.63573 + vertex 0.949589 1.73263 2.63532 + endloop + endfacet + facet normal 0.025826 0.0888735 0.995708 + outer loop + vertex 0.945255 1.72936 2.63573 + vertex 0.949248 1.72863 2.63569 + vertex 0.949589 1.73263 2.63532 + endloop + endfacet + facet normal 0.0173269 0.0874501 0.996018 + outer loop + vertex 0.944195 1.73329 2.63539 + vertex 0.948482 1.73737 2.63496 + vertex 0.943489 1.73755 2.63503 + endloop + endfacet + facet normal -0.00131548 0.0843907 0.996432 + outer loop + vertex 0.944195 1.73329 2.63539 + vertex 0.943489 1.73755 2.63503 + vertex 0.93914 1.73321 2.63539 + endloop + endfacet + facet normal -0.00148384 0.0951913 0.995458 + outer loop + vertex 0.93914 1.73321 2.63539 + vertex 0.940395 1.72963 2.63574 + vertex 0.944195 1.73329 2.63539 + endloop + endfacet + facet normal -0.0120183 0.0950475 0.9954 + outer loop + vertex 0.93914 1.73321 2.63539 + vertex 0.943489 1.73755 2.63503 + vertex 0.938461 1.73739 2.63499 + endloop + endfacet + facet normal -0.0348546 0.0913218 0.995211 + outer loop + vertex 0.93914 1.73321 2.63539 + vertex 0.938461 1.73739 2.63499 + vertex 0.933443 1.73202 2.6353 + endloop + endfacet + facet normal -0.0379881 0.106418 0.993596 + outer loop + vertex 0.933443 1.73202 2.6353 + vertex 0.935638 1.72913 2.6357 + vertex 0.93914 1.73321 2.63539 + endloop + endfacet + facet normal -0.0508455 0.106135 0.993051 + outer loop + vertex 0.933443 1.73202 2.6353 + vertex 0.938461 1.73739 2.63499 + vertex 0.933388 1.73718 2.63475 + endloop + endfacet + facet normal -0.050281 0.0910063 0.99458 + outer loop + vertex 0.938461 1.73739 2.63499 + vertex 0.938419 1.74222 2.63454 + vertex 0.933388 1.73718 2.63475 + endloop + endfacet + facet normal -0.0606461 0.101291 0.993007 + outer loop + vertex 0.933388 1.73718 2.63475 + vertex 0.938419 1.74222 2.63454 + vertex 0.933449 1.74218 2.63424 + endloop + endfacet + facet normal -0.0606016 0.0792911 0.995008 + outer loop + vertex 0.938419 1.74222 2.63454 + vertex 0.938464 1.74718 2.63415 + vertex 0.933449 1.74218 2.63424 + endloop + endfacet + facet normal -0.0599812 0.0786704 0.995095 + outer loop + vertex 0.933449 1.74218 2.63424 + vertex 0.938464 1.74718 2.63415 + vertex 0.93346 1.74714 2.63385 + endloop + endfacet + facet normal -0.0598898 0.0580116 0.996518 + outer loop + vertex 0.938464 1.74718 2.63415 + vertex 0.938449 1.75213 2.63386 + vertex 0.93346 1.74714 2.63385 + endloop + endfacet + facet normal -0.0275159 0.0791021 0.996487 + outer loop + vertex 0.938419 1.74222 2.63454 + vertex 0.943392 1.74714 2.63429 + vertex 0.938464 1.74718 2.63415 + endloop + endfacet + facet normal -0.0276961 0.0622794 0.997674 + outer loop + vertex 0.943392 1.74714 2.63429 + vertex 0.943444 1.75213 2.63398 + vertex 0.938464 1.74718 2.63415 + endloop + endfacet + facet normal -0.0236364 0.05821 0.998025 + outer loop + vertex 0.938464 1.74718 2.63415 + vertex 0.943444 1.75213 2.63398 + vertex 0.938449 1.75213 2.63386 + endloop + endfacet + facet normal -0.0236426 0.0530517 0.998312 + outer loop + vertex 0.943444 1.75213 2.63398 + vertex 0.943485 1.75713 2.63372 + vertex 0.938449 1.75213 2.63386 + endloop + endfacet + facet normal -0.00965939 0.0389915 0.999193 + outer loop + vertex 0.938449 1.75213 2.63386 + vertex 0.943485 1.75713 2.63372 + vertex 0.938441 1.75709 2.63367 + endloop + endfacet + facet normal 0.00731188 0.0528129 0.998578 + outer loop + vertex 0.943444 1.75213 2.63398 + vertex 0.948502 1.75713 2.63368 + vertex 0.943485 1.75713 2.63372 + endloop + endfacet + facet normal 0.00363341 0.0565244 0.998395 + outer loop + vertex 0.948401 1.75208 2.63397 + vertex 0.948502 1.75713 2.63368 + vertex 0.943444 1.75213 2.63398 + endloop + endfacet + facet normal 0.0274288 0.0560295 0.998052 + outer loop + vertex 0.948401 1.75208 2.63397 + vertex 0.95352 1.75714 2.63354 + vertex 0.948502 1.75713 2.63368 + endloop + endfacet + facet normal 0.0277559 0.055699 0.998062 + outer loop + vertex 0.953367 1.75205 2.63383 + vertex 0.95352 1.75714 2.63354 + vertex 0.948401 1.75208 2.63397 + endloop + endfacet + facet normal 0.0277804 0.0595768 0.997837 + outer loop + vertex 0.948289 1.74705 2.63427 + vertex 0.953367 1.75205 2.63383 + vertex 0.948401 1.75208 2.63397 + endloop + endfacet + facet normal 0.00555558 0.0600923 0.998177 + outer loop + vertex 0.948289 1.74705 2.63427 + vertex 0.948401 1.75208 2.63397 + vertex 0.943392 1.74714 2.63429 + endloop + endfacet + facet normal 0.00577918 0.0732975 0.997293 + outer loop + vertex 0.943322 1.7422 2.63465 + vertex 0.948289 1.74705 2.63427 + vertex 0.943392 1.74714 2.63429 + endloop + endfacet + facet normal 0.0111942 0.0677805 0.997637 + outer loop + vertex 0.948222 1.74211 2.63461 + vertex 0.948289 1.74705 2.63427 + vertex 0.943322 1.7422 2.63465 + endloop + endfacet + facet normal 0.0114489 0.0816978 0.996591 + outer loop + vertex 0.943489 1.73755 2.63503 + vertex 0.948222 1.74211 2.63461 + vertex 0.943322 1.7422 2.63465 + endloop + endfacet + facet normal 0.0300234 0.067501 0.997267 + outer loop + vertex 0.948222 1.74211 2.63461 + vertex 0.953218 1.74697 2.63413 + vertex 0.948289 1.74705 2.63427 + endloop + endfacet + facet normal 0.032078 0.0653974 0.997344 + outer loop + vertex 0.953166 1.74199 2.63445 + vertex 0.953218 1.74697 2.63413 + vertex 0.948222 1.74211 2.63461 + endloop + endfacet + facet normal 0.0323385 0.0768584 0.996517 + outer loop + vertex 0.948482 1.73737 2.63496 + vertex 0.953166 1.74199 2.63445 + vertex 0.948222 1.74211 2.63461 + endloop + endfacet + facet normal 0.0430075 0.0652572 0.996941 + outer loop + vertex 0.953166 1.74199 2.63445 + vertex 0.958219 1.74693 2.63391 + vertex 0.953218 1.74697 2.63413 + endloop + endfacet + facet normal 0.0429571 0.0570037 0.997449 + outer loop + vertex 0.958219 1.74693 2.63391 + vertex 0.958387 1.75205 2.63361 + vertex 0.953218 1.74697 2.63413 + endloop + endfacet + facet normal 0.0498957 0.0567585 0.99714 + outer loop + vertex 0.958219 1.74693 2.63391 + vertex 0.963482 1.7521 2.63335 + vertex 0.958387 1.75205 2.63361 + endloop + endfacet + facet normal 0.0486065 0.0580684 0.997129 + outer loop + vertex 0.963295 1.74694 2.63366 + vertex 0.963482 1.7521 2.63335 + vertex 0.958219 1.74693 2.63391 + endloop + endfacet + facet normal 0.0485642 0.0655611 0.996666 + outer loop + vertex 0.958133 1.74189 2.63425 + vertex 0.963295 1.74694 2.63366 + vertex 0.958219 1.74693 2.63391 + endloop + endfacet + facet normal 0.0469263 0.0672318 0.996633 + outer loop + vertex 0.963147 1.74185 2.63402 + vertex 0.963295 1.74694 2.63366 + vertex 0.958133 1.74189 2.63425 + endloop + endfacet + facet normal 0.0469702 0.0754545 0.996042 + outer loop + vertex 0.958261 1.73716 2.6346 + vertex 0.963147 1.74185 2.63402 + vertex 0.958133 1.74189 2.63425 + endloop + endfacet + facet normal 0.0425219 0.0753493 0.99625 + outer loop + vertex 0.958261 1.73716 2.6346 + vertex 0.958133 1.74189 2.63425 + vertex 0.953462 1.73728 2.6348 + endloop + endfacet + facet normal 0.0427432 0.0751263 0.996258 + outer loop + vertex 0.953462 1.73728 2.6348 + vertex 0.958133 1.74189 2.63425 + vertex 0.953166 1.74199 2.63445 + endloop + endfacet + facet normal 0.0456823 0.0767924 0.996 + outer loop + vertex 0.963102 1.73691 2.6344 + vertex 0.963147 1.74185 2.63402 + vertex 0.958261 1.73716 2.6346 + endloop + endfacet + facet normal 0.045964 0.0825255 0.995528 + outer loop + vertex 0.958473 1.73263 2.63497 + vertex 0.963102 1.73691 2.6344 + vertex 0.958261 1.73716 2.6346 + endloop + endfacet + facet normal 0.0452698 0.0832727 0.995498 + outer loop + vertex 0.963385 1.73225 2.63477 + vertex 0.963102 1.73691 2.6344 + vertex 0.958473 1.73263 2.63497 + endloop + endfacet + facet normal 0.047419 0.0833942 0.995388 + outer loop + vertex 0.963385 1.73225 2.63477 + vertex 0.968163 1.73691 2.63416 + vertex 0.963102 1.73691 2.6344 + endloop + endfacet + facet normal 0.0474371 0.0775844 0.995857 + outer loop + vertex 0.968163 1.73691 2.63416 + vertex 0.96826 1.74193 2.63376 + vertex 0.963102 1.73691 2.6344 + endloop + endfacet + facet normal 0.0497684 0.0775308 0.995747 + outer loop + vertex 0.968163 1.73691 2.63416 + vertex 0.973439 1.74214 2.63349 + vertex 0.96826 1.74193 2.63376 + endloop + endfacet + facet normal 0.0501759 0.0683137 0.996401 + outer loop + vertex 0.973439 1.74214 2.63349 + vertex 0.973602 1.74727 2.63313 + vertex 0.96826 1.74193 2.63376 + endloop + endfacet + facet normal 0.049857 0.0686319 0.996395 + outer loop + vertex 0.96826 1.74193 2.63376 + vertex 0.973602 1.74727 2.63313 + vertex 0.968442 1.74706 2.6334 + endloop + endfacet + facet normal 0.0483941 0.0686884 0.996464 + outer loop + vertex 0.96826 1.74193 2.63376 + vertex 0.968442 1.74706 2.6334 + vertex 0.963147 1.74185 2.63402 + endloop + endfacet + facet normal 0.0502519 0.0598306 0.996943 + outer loop + vertex 0.973602 1.74727 2.63313 + vertex 0.973774 1.75239 2.63281 + vertex 0.968442 1.74706 2.6334 + endloop + endfacet + facet normal 0.050535 0.0595481 0.996945 + outer loop + vertex 0.968442 1.74706 2.6334 + vertex 0.973774 1.75239 2.63281 + vertex 0.968636 1.75222 2.63308 + endloop + endfacet + facet normal 0.0501182 0.059565 0.996965 + outer loop + vertex 0.968442 1.74706 2.6334 + vertex 0.968636 1.75222 2.63308 + vertex 0.963295 1.74694 2.63366 + endloop + endfacet + facet normal 0.0506964 0.0552494 0.997185 + outer loop + vertex 0.973774 1.75239 2.63281 + vertex 0.973878 1.75748 2.63252 + vertex 0.968636 1.75222 2.63308 + endloop + endfacet + facet normal 0.0508788 0.0550679 0.997185 + outer loop + vertex 0.968636 1.75222 2.63308 + vertex 0.973878 1.75748 2.63252 + vertex 0.968802 1.75738 2.63279 + endloop + endfacet + facet normal 0.0517906 0.055036 0.99714 + outer loop + vertex 0.968636 1.75222 2.63308 + vertex 0.968802 1.75738 2.63279 + vertex 0.963482 1.7521 2.63335 + endloop + endfacet + facet normal 0.0524806 0.0543408 0.997142 + outer loop + vertex 0.963482 1.7521 2.63335 + vertex 0.968802 1.75738 2.63279 + vertex 0.963666 1.75728 2.63306 + endloop + endfacet + facet normal 0.0499262 0.0544388 0.997268 + outer loop + vertex 0.963482 1.7521 2.63335 + vertex 0.963666 1.75728 2.63306 + vertex 0.958387 1.75205 2.63361 + endloop + endfacet + facet normal 0.0500899 0.0542735 0.997269 + outer loop + vertex 0.958387 1.75205 2.63361 + vertex 0.963666 1.75728 2.63306 + vertex 0.958568 1.75719 2.63332 + endloop + endfacet + facet normal 0.0429264 0.0545437 0.997588 + outer loop + vertex 0.958387 1.75205 2.63361 + vertex 0.958568 1.75719 2.63332 + vertex 0.953367 1.75205 2.63383 + endloop + endfacet + facet normal 0.0429183 0.0570431 0.997449 + outer loop + vertex 0.953218 1.74697 2.63413 + vertex 0.958387 1.75205 2.63361 + vertex 0.953367 1.75205 2.63383 + endloop + endfacet + facet normal 0.0508057 0.0582334 0.997009 + outer loop + vertex 0.973878 1.75748 2.63252 + vertex 0.973814 1.76249 2.63223 + vertex 0.968802 1.75738 2.63279 + endloop + endfacet + facet normal 0.0498522 0.0591683 0.997002 + outer loop + vertex 0.968802 1.75738 2.63279 + vertex 0.973814 1.76249 2.63223 + vertex 0.968849 1.7625 2.63248 + endloop + endfacet + facet normal 0.0523674 0.0591376 0.996875 + outer loop + vertex 0.968802 1.75738 2.63279 + vertex 0.968849 1.7625 2.63248 + vertex 0.963666 1.75728 2.63306 + endloop + endfacet + facet normal 0.0517948 0.0597056 0.996871 + outer loop + vertex 0.963666 1.75728 2.63306 + vertex 0.968849 1.7625 2.63248 + vertex 0.963785 1.76243 2.63275 + endloop + endfacet + facet normal 0.0499804 0.0597528 0.996961 + outer loop + vertex 0.963666 1.75728 2.63306 + vertex 0.963785 1.76243 2.63275 + vertex 0.958568 1.75719 2.63332 + endloop + endfacet + facet normal 0.0491309 0.0605972 0.996952 + outer loop + vertex 0.958568 1.75719 2.63332 + vertex 0.963785 1.76243 2.63275 + vertex 0.958718 1.76233 2.633 + endloop + endfacet + facet normal 0.0421726 0.0608192 0.997257 + outer loop + vertex 0.958568 1.75719 2.63332 + vertex 0.958718 1.76233 2.633 + vertex 0.95352 1.75714 2.63354 + endloop + endfacet + facet normal 0.0412122 0.0617795 0.997239 + outer loop + vertex 0.95352 1.75714 2.63354 + vertex 0.958718 1.76233 2.633 + vertex 0.953677 1.76225 2.63322 + endloop + endfacet + facet normal 0.0274105 0.0622328 0.997685 + outer loop + vertex 0.95352 1.75714 2.63354 + vertex 0.953677 1.76225 2.63322 + vertex 0.948502 1.75713 2.63368 + endloop + endfacet + facet normal 0.0278304 0.0618093 0.9977 + outer loop + vertex 0.948502 1.75713 2.63368 + vertex 0.953677 1.76225 2.63322 + vertex 0.948645 1.76222 2.63336 + endloop + endfacet + facet normal 0.00730851 0.0624087 0.998024 + outer loop + vertex 0.948502 1.75713 2.63368 + vertex 0.948645 1.76222 2.63336 + vertex 0.943485 1.75713 2.63372 + endloop + endfacet + facet normal 0.014911 0.054718 0.998391 + outer loop + vertex 0.943485 1.75713 2.63372 + vertex 0.948645 1.76222 2.63336 + vertex 0.943607 1.76219 2.63344 + endloop + endfacet + facet normal -0.00980075 0.0553159 0.998421 + outer loop + vertex 0.943485 1.75713 2.63372 + vertex 0.943607 1.76219 2.63344 + vertex 0.938441 1.75709 2.63367 + endloop + endfacet + facet normal 0.014776 0.0754697 0.997039 + outer loop + vertex 0.948645 1.76222 2.63336 + vertex 0.948807 1.76736 2.63297 + vertex 0.943607 1.76219 2.63344 + endloop + endfacet + facet normal 0.0291412 0.0749969 0.996758 + outer loop + vertex 0.948645 1.76222 2.63336 + vertex 0.953786 1.76735 2.63282 + vertex 0.948807 1.76736 2.63297 + endloop + endfacet + facet normal 0.0291261 0.0927922 0.995259 + outer loop + vertex 0.953786 1.76735 2.63282 + vertex 0.953679 1.77236 2.63236 + vertex 0.948807 1.76736 2.63297 + endloop + endfacet + facet normal 0.028591 0.093309 0.995227 + outer loop + vertex 0.948807 1.76736 2.63297 + vertex 0.953679 1.77236 2.63236 + vertex 0.948766 1.77248 2.63249 + endloop + endfacet + facet normal 0.0213363 0.0932686 0.995412 + outer loop + vertex 0.948807 1.76736 2.63297 + vertex 0.948766 1.77248 2.63249 + vertex 0.943791 1.76734 2.63308 + endloop + endfacet + facet normal 0.0214428 0.0687946 0.9974 + outer loop + vertex 0.943607 1.76219 2.63344 + vertex 0.948807 1.76736 2.63297 + vertex 0.943791 1.76734 2.63308 + endloop + endfacet + facet normal 0.00676189 0.0693322 0.997571 + outer loop + vertex 0.943607 1.76219 2.63344 + vertex 0.943791 1.76734 2.63308 + vertex 0.93854 1.76213 2.63348 + endloop + endfacet + facet normal 0.00713192 0.0382102 0.999244 + outer loop + vertex 0.938441 1.75709 2.63367 + vertex 0.943607 1.76219 2.63344 + vertex 0.93854 1.76213 2.63348 + endloop + endfacet + facet normal -0.0179457 0.0386983 0.99909 + outer loop + vertex 0.938441 1.75709 2.63367 + vertex 0.93854 1.76213 2.63348 + vertex 0.933365 1.757 2.63358 + endloop + endfacet + facet normal 0.0288536 0.106391 0.993906 + outer loop + vertex 0.953679 1.77236 2.63236 + vertex 0.953063 1.77724 2.63186 + vertex 0.948766 1.77248 2.63249 + endloop + endfacet + facet normal 0.0264724 0.108517 0.993742 + outer loop + vertex 0.948766 1.77248 2.63249 + vertex 0.953063 1.77724 2.63186 + vertex 0.948181 1.7773 2.63198 + endloop + endfacet + facet normal 0.0227016 0.108075 0.993884 + outer loop + vertex 0.948766 1.77248 2.63249 + vertex 0.948181 1.7773 2.63198 + vertex 0.943826 1.77248 2.6326 + endloop + endfacet + facet normal 0.0227221 0.0919359 0.995506 + outer loop + vertex 0.943791 1.76734 2.63308 + vertex 0.948766 1.77248 2.63249 + vertex 0.943826 1.77248 2.6326 + endloop + endfacet + facet normal 0.0154375 0.0919972 0.99564 + outer loop + vertex 0.943791 1.76734 2.63308 + vertex 0.943826 1.77248 2.6326 + vertex 0.938719 1.7673 2.63316 + endloop + endfacet + facet normal 0.015769 0.0602968 0.998056 + outer loop + vertex 0.93854 1.76213 2.63348 + vertex 0.943791 1.76734 2.63308 + vertex 0.938719 1.7673 2.63316 + endloop + endfacet + facet normal 0.0020212 0.0607772 0.998149 + outer loop + vertex 0.93854 1.76213 2.63348 + vertex 0.938719 1.7673 2.63316 + vertex 0.933421 1.76205 2.63349 + endloop + endfacet + facet normal 0.00269921 0.0178974 0.999836 + outer loop + vertex 0.933365 1.757 2.63358 + vertex 0.93854 1.76213 2.63348 + vertex 0.933421 1.76205 2.63349 + endloop + endfacet + facet normal -0.0256198 0.0182075 0.999506 + outer loop + vertex 0.933365 1.757 2.63358 + vertex 0.933421 1.76205 2.63349 + vertex 0.928313 1.75697 2.63345 + endloop + endfacet + facet normal -0.0149867 0.00751387 0.999859 + outer loop + vertex 0.928313 1.75697 2.63345 + vertex 0.933421 1.76205 2.63349 + vertex 0.928308 1.762 2.63341 + endloop + endfacet + facet normal -0.0619489 0.00745634 0.998051 + outer loop + vertex 0.928313 1.75697 2.63345 + vertex 0.928308 1.762 2.63341 + vertex 0.923506 1.75721 2.63315 + endloop + endfacet + facet normal -0.073023 0.0186021 0.997157 + outer loop + vertex 0.923506 1.75721 2.63315 + vertex 0.928308 1.762 2.63341 + vertex 0.923424 1.76205 2.63306 + endloop + endfacet + facet normal -0.139024 0.0173365 0.990137 + outer loop + vertex 0.923506 1.75721 2.63315 + vertex 0.923424 1.76205 2.63306 + vertex 0.919771 1.75797 2.63261 + endloop + endfacet + facet normal -0.0723545 0.0706783 0.994872 + outer loop + vertex 0.928308 1.762 2.63341 + vertex 0.928348 1.7671 2.63305 + vertex 0.923424 1.76205 2.63306 + endloop + endfacet + facet normal -0.100146 0.0977898 0.990155 + outer loop + vertex 0.923424 1.76205 2.63306 + vertex 0.928348 1.7671 2.63305 + vertex 0.923315 1.76695 2.63256 + endloop + endfacet + facet normal -0.200758 0.0940449 0.975116 + outer loop + vertex 0.923424 1.76205 2.63306 + vertex 0.923315 1.76695 2.63256 + vertex 0.918587 1.76195 2.63207 + endloop + endfacet + facet normal -0.200696 0.0739499 0.976858 + outer loop + vertex 0.919771 1.75797 2.63261 + vertex 0.923424 1.76205 2.63306 + vertex 0.918587 1.76195 2.63207 + endloop + endfacet + facet normal -0.100618 0.123884 0.987182 + outer loop + vertex 0.928348 1.7671 2.63305 + vertex 0.928378 1.77218 2.63242 + vertex 0.923315 1.76695 2.63256 + endloop + endfacet + facet normal -0.0492233 0.124061 0.991053 + outer loop + vertex 0.928348 1.7671 2.63305 + vertex 0.933617 1.77238 2.63266 + vertex 0.928378 1.77218 2.63242 + endloop + endfacet + facet normal -0.0493935 0.129482 0.990351 + outer loop + vertex 0.933617 1.77238 2.63266 + vertex 0.933478 1.77728 2.63201 + vertex 0.928378 1.77218 2.63242 + endloop + endfacet + facet normal -0.0293247 0.10443 0.9941 + outer loop + vertex 0.933551 1.76722 2.6332 + vertex 0.933617 1.77238 2.63266 + vertex 0.928348 1.7671 2.63305 + endloop + endfacet + facet normal -0.00555833 0.104172 0.994544 + outer loop + vertex 0.933551 1.76722 2.6332 + vertex 0.938807 1.77246 2.63268 + vertex 0.933617 1.77238 2.63266 + endloop + endfacet + facet normal 0.00549079 0.0932026 0.995632 + outer loop + vertex 0.938719 1.7673 2.63316 + vertex 0.938807 1.77246 2.63268 + vertex 0.933551 1.76722 2.6332 + endloop + endfacet + facet normal 0.0143665 0.0930436 0.995558 + outer loop + vertex 0.938719 1.7673 2.63316 + vertex 0.943826 1.77248 2.6326 + vertex 0.938807 1.77246 2.63268 + endloop + endfacet + facet normal 0.0142708 0.111444 0.993668 + outer loop + vertex 0.943826 1.77248 2.6326 + vertex 0.943481 1.77727 2.63207 + vertex 0.938807 1.77246 2.63268 + endloop + endfacet + facet normal -0.0286246 0.0704937 0.997101 + outer loop + vertex 0.928308 1.762 2.63341 + vertex 0.933551 1.76722 2.6332 + vertex 0.928348 1.7671 2.63305 + endloop + endfacet + facet normal -0.0154044 0.0572491 0.998241 + outer loop + vertex 0.933421 1.76205 2.63349 + vertex 0.933551 1.76722 2.6332 + vertex 0.928308 1.762 2.63341 + endloop + endfacet + facet normal 0.00605771 0.0567156 0.998372 + outer loop + vertex 0.933421 1.76205 2.63349 + vertex 0.938719 1.7673 2.63316 + vertex 0.933551 1.76722 2.6332 + endloop + endfacet + facet normal 0.0185929 0.111744 0.993563 + outer loop + vertex 0.943826 1.77248 2.6326 + vertex 0.948181 1.7773 2.63198 + vertex 0.943481 1.77727 2.63207 + endloop + endfacet + facet normal 0.0185495 0.116555 0.993011 + outer loop + vertex 0.948181 1.7773 2.63198 + vertex 0.946867 1.78093 2.63158 + vertex 0.943481 1.77727 2.63207 + endloop + endfacet + facet normal 0.0117825 0.122731 0.99237 + outer loop + vertex 0.943481 1.77727 2.63207 + vertex 0.946867 1.78093 2.63158 + vertex 0.942871 1.78162 2.63154 + endloop + endfacet + facet normal 0.00533593 0.121847 0.992535 + outer loop + vertex 0.943481 1.77727 2.63207 + vertex 0.942871 1.78162 2.63154 + vertex 0.938598 1.77737 2.63208 + endloop + endfacet + facet normal 0.00529853 0.120047 0.992754 + outer loop + vertex 0.938807 1.77246 2.63268 + vertex 0.943481 1.77727 2.63207 + vertex 0.938598 1.77737 2.63208 + endloop + endfacet + facet normal -0.0057993 0.119581 0.992808 + outer loop + vertex 0.938807 1.77246 2.63268 + vertex 0.938598 1.77737 2.63208 + vertex 0.933617 1.77238 2.63266 + endloop + endfacet + facet normal 0.0112156 0.11947 0.992774 + outer loop + vertex 0.946867 1.78093 2.63158 + vertex 0.94705 1.78501 2.63108 + vertex 0.942871 1.78162 2.63154 + endloop + endfacet + facet normal 0.00942292 0.121651 0.992528 + outer loop + vertex 0.942871 1.78162 2.63154 + vertex 0.94705 1.78501 2.63108 + vertex 0.941821 1.78561 2.63106 + endloop + endfacet + facet normal -0.00124749 0.118887 0.992907 + outer loop + vertex 0.942871 1.78162 2.63154 + vertex 0.941821 1.78561 2.63106 + vertex 0.93797 1.78181 2.63151 + endloop + endfacet + facet normal -0.000891642 0.128014 0.991772 + outer loop + vertex 0.938598 1.77737 2.63208 + vertex 0.942871 1.78162 2.63154 + vertex 0.93797 1.78181 2.63151 + endloop + endfacet + facet normal -0.0168727 0.125767 0.991916 + outer loop + vertex 0.938598 1.77737 2.63208 + vertex 0.93797 1.78181 2.63151 + vertex 0.933478 1.77728 2.63201 + endloop + endfacet + facet normal -0.0169515 0.130526 0.9913 + outer loop + vertex 0.933617 1.77238 2.63266 + vertex 0.938598 1.77737 2.63208 + vertex 0.933478 1.77728 2.63201 + endloop + endfacet + facet normal 0.00861742 0.114705 0.993362 + outer loop + vertex 0.94705 1.78501 2.63108 + vertex 0.945224 1.78895 2.63064 + vertex 0.941821 1.78561 2.63106 + endloop + endfacet + facet normal 0.00719704 0.116133 0.993208 + outer loop + vertex 0.945224 1.78895 2.63064 + vertex 0.940361 1.78923 2.63065 + vertex 0.941821 1.78561 2.63106 + endloop + endfacet + facet normal -0.00289917 0.11212 0.99369 + outer loop + vertex 0.941821 1.78561 2.63106 + vertex 0.940361 1.78923 2.63065 + vertex 0.936939 1.78563 2.63104 + endloop + endfacet + facet normal -0.00285858 0.120496 0.99271 + outer loop + vertex 0.93797 1.78181 2.63151 + vertex 0.941821 1.78561 2.63106 + vertex 0.936939 1.78563 2.63104 + endloop + endfacet + facet normal -0.0208154 0.1157 0.993066 + outer loop + vertex 0.93797 1.78181 2.63151 + vertex 0.936939 1.78563 2.63104 + vertex 0.93307 1.78165 2.63143 + endloop + endfacet + facet normal -0.0212567 0.130045 0.99128 + outer loop + vertex 0.933478 1.77728 2.63201 + vertex 0.93797 1.78181 2.63151 + vertex 0.93307 1.78165 2.63143 + endloop + endfacet + facet normal -0.0577388 0.126499 0.990285 + outer loop + vertex 0.933478 1.77728 2.63201 + vertex 0.93307 1.78165 2.63143 + vertex 0.928521 1.77707 2.63175 + endloop + endfacet + facet normal -0.0581462 0.138108 0.988709 + outer loop + vertex 0.928378 1.77218 2.63242 + vertex 0.933478 1.77728 2.63201 + vertex 0.928521 1.77707 2.63175 + endloop + endfacet + facet normal -0.0574223 0.126188 0.990343 + outer loop + vertex 0.928521 1.77707 2.63175 + vertex 0.93307 1.78165 2.63143 + vertex 0.928497 1.78147 2.63118 + endloop + endfacet + facet normal -0.0568835 0.109195 0.992391 + outer loop + vertex 0.928497 1.78147 2.63118 + vertex 0.93307 1.78165 2.63143 + vertex 0.93254 1.78524 2.631 + endloop + endfacet + facet normal -0.0530349 0.105093 0.993047 + outer loop + vertex 0.929413 1.78499 2.63086 + vertex 0.928497 1.78147 2.63118 + vertex 0.93254 1.78524 2.631 + endloop + endfacet + facet normal -0.0536438 0.113446 0.992095 + outer loop + vertex 0.929413 1.78499 2.63086 + vertex 0.93254 1.78524 2.631 + vertex 0.931691 1.78766 2.63068 + endloop + endfacet + facet normal -0.126524 0.1747 0.976459 + outer loop + vertex 0.931691 1.78766 2.63068 + vertex 0.92784 1.78684 2.63033 + vertex 0.929413 1.78499 2.63086 + endloop + endfacet + facet normal -0.123658 0.15999 0.979343 + outer loop + vertex 0.931691 1.78766 2.63068 + vertex 0.93332 1.79174 2.63022 + vertex 0.92784 1.78684 2.63033 + endloop + endfacet + facet normal -0.100269 0.133967 0.9859 + outer loop + vertex 0.92784 1.78684 2.63033 + vertex 0.93332 1.79174 2.63022 + vertex 0.928173 1.79173 2.62969 + endloop + endfacet + facet normal -0.100396 0.12414 0.987173 + outer loop + vertex 0.93332 1.79174 2.63022 + vertex 0.93328 1.79688 2.62957 + vertex 0.928173 1.79173 2.62969 + endloop + endfacet + facet normal -0.109555 0.133171 0.985019 + outer loop + vertex 0.928173 1.79173 2.62969 + vertex 0.93328 1.79688 2.62957 + vertex 0.928356 1.79674 2.62904 + endloop + endfacet + facet normal -0.109613 0.137048 0.984481 + outer loop + vertex 0.93328 1.79688 2.62957 + vertex 0.933452 1.80199 2.62887 + vertex 0.928356 1.79674 2.62904 + endloop + endfacet + facet normal -0.125978 0.152782 0.980198 + outer loop + vertex 0.928356 1.79674 2.62904 + vertex 0.933452 1.80199 2.62887 + vertex 0.928429 1.8018 2.62826 + endloop + endfacet + facet normal -0.12585 0.146049 0.98124 + outer loop + vertex 0.933452 1.80199 2.62887 + vertex 0.933562 1.80713 2.62812 + vertex 0.928429 1.8018 2.62826 + endloop + endfacet + facet normal -0.126869 0.147023 0.980963 + outer loop + vertex 0.928429 1.8018 2.62826 + vertex 0.933562 1.80713 2.62812 + vertex 0.928604 1.80693 2.62751 + endloop + endfacet + facet normal -0.12669 0.139332 0.982108 + outer loop + vertex 0.933562 1.80713 2.62812 + vertex 0.933444 1.81208 2.62741 + vertex 0.928604 1.80693 2.62751 + endloop + endfacet + facet normal -0.116256 0.12959 0.984729 + outer loop + vertex 0.928604 1.80693 2.62751 + vertex 0.933444 1.81208 2.62741 + vertex 0.928777 1.81177 2.6269 + endloop + endfacet + facet normal -0.116314 0.130689 0.984577 + outer loop + vertex 0.933444 1.81208 2.62741 + vertex 0.933008 1.81651 2.62677 + vertex 0.928777 1.81177 2.6269 + endloop + endfacet + facet normal -0.0314667 0.125239 0.991627 + outer loop + vertex 0.93332 1.79174 2.63022 + vertex 0.938378 1.7971 2.6297 + vertex 0.93328 1.79688 2.62957 + endloop + endfacet + facet normal -0.0315477 0.127337 0.991358 + outer loop + vertex 0.938378 1.7971 2.6297 + vertex 0.938484 1.8021 2.62906 + vertex 0.93328 1.79688 2.62957 + endloop + endfacet + facet normal -0.0398197 0.135448 0.989984 + outer loop + vertex 0.93328 1.79688 2.62957 + vertex 0.938484 1.8021 2.62906 + vertex 0.933452 1.80199 2.62887 + endloop + endfacet + facet normal -0.0398226 0.135621 0.98996 + outer loop + vertex 0.938484 1.8021 2.62906 + vertex 0.938672 1.80731 2.62836 + vertex 0.933452 1.80199 2.62887 + endloop + endfacet + facet normal -0.00130195 0.134359 0.990932 + outer loop + vertex 0.938484 1.8021 2.62906 + vertex 0.943728 1.80732 2.62836 + vertex 0.938672 1.80731 2.62836 + endloop + endfacet + facet normal -0.00130159 0.13422 0.990951 + outer loop + vertex 0.943728 1.80732 2.62836 + vertex 0.943634 1.81246 2.62766 + vertex 0.938672 1.80731 2.62836 + endloop + endfacet + facet normal -0.00909318 0.141578 0.989885 + outer loop + vertex 0.938672 1.80731 2.62836 + vertex 0.943634 1.81246 2.62766 + vertex 0.938512 1.81237 2.62763 + endloop + endfacet + facet normal -0.04985 0.140149 0.988875 + outer loop + vertex 0.938672 1.80731 2.62836 + vertex 0.938512 1.81237 2.62763 + vertex 0.933562 1.80713 2.62812 + endloop + endfacet + facet normal -0.0499964 0.145429 0.988105 + outer loop + vertex 0.933452 1.80199 2.62887 + vertex 0.938672 1.80731 2.62836 + vertex 0.933562 1.80713 2.62812 + endloop + endfacet + facet normal -0.051887 0.142038 0.9885 + outer loop + vertex 0.933562 1.80713 2.62812 + vertex 0.938512 1.81237 2.62763 + vertex 0.933444 1.81208 2.62741 + endloop + endfacet + facet normal -0.0515833 0.136067 0.989356 + outer loop + vertex 0.938512 1.81237 2.62763 + vertex 0.937859 1.81696 2.62697 + vertex 0.933444 1.81208 2.62741 + endloop + endfacet + facet normal -0.0532581 0.137556 0.989061 + outer loop + vertex 0.933444 1.81208 2.62741 + vertex 0.937859 1.81696 2.62697 + vertex 0.933008 1.81651 2.62677 + endloop + endfacet + facet normal -0.0526386 0.130531 0.990046 + outer loop + vertex 0.937859 1.81696 2.62697 + vertex 0.936833 1.82084 2.6264 + vertex 0.933008 1.81651 2.62677 + endloop + endfacet + facet normal -0.0184812 0.139586 0.990038 + outer loop + vertex 0.937859 1.81696 2.62697 + vertex 0.941695 1.82123 2.62644 + vertex 0.936833 1.82084 2.6264 + endloop + endfacet + facet normal -0.0141433 0.135758 0.990641 + outer loop + vertex 0.942923 1.81717 2.62701 + vertex 0.941695 1.82123 2.62644 + vertex 0.937859 1.81696 2.62697 + endloop + endfacet + facet normal -0.0143707 0.14143 0.989844 + outer loop + vertex 0.938512 1.81237 2.62763 + vertex 0.942923 1.81717 2.62701 + vertex 0.937859 1.81696 2.62697 + endloop + endfacet + facet normal 0.00463366 0.141344 0.98995 + outer loop + vertex 0.942923 1.81717 2.62701 + vertex 0.946684 1.82129 2.6264 + vertex 0.941695 1.82123 2.62644 + endloop + endfacet + facet normal 0.00469036 0.137189 0.990534 + outer loop + vertex 0.946684 1.82129 2.6264 + vertex 0.945207 1.82493 2.62591 + vertex 0.941695 1.82123 2.62644 + endloop + endfacet + facet normal -2.31616e-06 0.141553 0.989931 + outer loop + vertex 0.945207 1.82493 2.62591 + vertex 0.940307 1.82472 2.62594 + vertex 0.941695 1.82123 2.62644 + endloop + endfacet + facet normal -0.0180773 0.134487 0.990751 + outer loop + vertex 0.941695 1.82123 2.62644 + vertex 0.940307 1.82472 2.62594 + vertex 0.936833 1.82084 2.6264 + endloop + endfacet + facet normal 0.000155398 0.137949 0.990439 + outer loop + vertex 0.940307 1.82472 2.62594 + vertex 0.945207 1.82493 2.62591 + vertex 0.944053 1.82846 2.62541 + endloop + endfacet + facet normal -0.0124081 0.150254 0.988569 + outer loop + vertex 0.939033 1.82806 2.62541 + vertex 0.940307 1.82472 2.62594 + vertex 0.944053 1.82846 2.62541 + endloop + endfacet + facet normal -0.0116237 0.140453 0.990019 + outer loop + vertex 0.944053 1.82846 2.62541 + vertex 0.943531 1.83244 2.62484 + vertex 0.939033 1.82806 2.62541 + endloop + endfacet + facet normal -0.0258278 0.154731 0.987619 + outer loop + vertex 0.939033 1.82806 2.62541 + vertex 0.943531 1.83244 2.62484 + vertex 0.938416 1.83212 2.62476 + endloop + endfacet + facet normal -0.0804588 0.146168 0.985982 + outer loop + vertex 0.939033 1.82806 2.62541 + vertex 0.938416 1.83212 2.62476 + vertex 0.933289 1.82667 2.62515 + endloop + endfacet + facet normal -0.0910071 0.191311 0.977301 + outer loop + vertex 0.933289 1.82667 2.62515 + vertex 0.93552 1.82398 2.62588 + vertex 0.939033 1.82806 2.62541 + endloop + endfacet + facet normal -0.102617 0.181874 0.977953 + outer loop + vertex 0.93161 1.82253 2.62574 + vertex 0.93552 1.82398 2.62588 + vertex 0.933289 1.82667 2.62515 + endloop + endfacet + facet normal -0.258088 0.238899 0.936118 + outer loop + vertex 0.93161 1.82253 2.62574 + vertex 0.933289 1.82667 2.62515 + vertex 0.927818 1.82159 2.62494 + endloop + endfacet + facet normal -0.261682 0.258984 0.929758 + outer loop + vertex 0.93161 1.82253 2.62574 + vertex 0.927818 1.82159 2.62494 + vertex 0.929348 1.8197 2.62589 + endloop + endfacet + facet normal -0.132835 0.158251 0.978423 + outer loop + vertex 0.929348 1.8197 2.62589 + vertex 0.932452 1.82014 2.62624 + vertex 0.93161 1.82253 2.62574 + endloop + endfacet + facet normal -0.130104 0.135705 0.98217 + outer loop + vertex 0.929348 1.8197 2.62589 + vertex 0.928543 1.81609 2.62629 + vertex 0.932452 1.82014 2.62624 + endloop + endfacet + facet normal -0.0985744 0.170736 0.980374 + outer loop + vertex 0.93552 1.82398 2.62588 + vertex 0.93161 1.82253 2.62574 + vertex 0.932452 1.82014 2.62624 + endloop + endfacet + facet normal -0.0570776 0.138343 0.988738 + outer loop + vertex 0.936833 1.82084 2.6264 + vertex 0.93552 1.82398 2.62588 + vertex 0.932452 1.82014 2.62624 + endloop + endfacet + facet normal -0.0563756 0.133778 0.989406 + outer loop + vertex 0.933008 1.81651 2.62677 + vertex 0.936833 1.82084 2.6264 + vertex 0.932452 1.82014 2.62624 + endloop + endfacet + facet normal -0.0336066 0.148101 0.988401 + outer loop + vertex 0.940307 1.82472 2.62594 + vertex 0.93552 1.82398 2.62588 + vertex 0.936833 1.82084 2.6264 + endloop + endfacet + facet normal -0.10324 0.167207 0.980502 + outer loop + vertex 0.933289 1.82667 2.62515 + vertex 0.938416 1.83212 2.62476 + vertex 0.933272 1.83179 2.62427 + endloop + endfacet + facet normal -0.102775 0.157586 0.982143 + outer loop + vertex 0.938416 1.83212 2.62476 + vertex 0.938479 1.83705 2.62397 + vertex 0.933272 1.83179 2.62427 + endloop + endfacet + facet normal -0.108416 0.163077 0.980639 + outer loop + vertex 0.933272 1.83179 2.62427 + vertex 0.938479 1.83705 2.62397 + vertex 0.933373 1.83693 2.62343 + endloop + endfacet + facet normal -0.108419 0.163557 0.980558 + outer loop + vertex 0.938479 1.83705 2.62397 + vertex 0.938573 1.84221 2.62313 + vertex 0.933373 1.83693 2.62343 + endloop + endfacet + facet normal -0.108429 0.163567 0.980555 + outer loop + vertex 0.933373 1.83693 2.62343 + vertex 0.938573 1.84221 2.62313 + vertex 0.933533 1.84209 2.62259 + endloop + endfacet + facet normal -0.10842 0.161528 0.980894 + outer loop + vertex 0.938573 1.84221 2.62313 + vertex 0.938359 1.8471 2.6223 + vertex 0.933533 1.84209 2.62259 + endloop + endfacet + facet normal -0.0988686 0.152457 0.983352 + outer loop + vertex 0.933533 1.84209 2.62259 + vertex 0.938359 1.8471 2.6223 + vertex 0.933533 1.84672 2.62187 + endloop + endfacet + facet normal -0.0988504 0.152171 0.983399 + outer loop + vertex 0.938359 1.8471 2.6223 + vertex 0.937709 1.85167 2.62152 + vertex 0.933533 1.84672 2.62187 + endloop + endfacet + facet normal -0.106252 0.1583 0.981658 + outer loop + vertex 0.933533 1.84672 2.62187 + vertex 0.937709 1.85167 2.62152 + vertex 0.932894 1.8501 2.62126 + endloop + endfacet + facet normal -0.105047 0.154469 0.982397 + outer loop + vertex 0.937709 1.85167 2.62152 + vertex 0.935349 1.85402 2.6209 + vertex 0.932894 1.8501 2.62126 + endloop + endfacet + facet normal -0.0986007 0.160843 0.982042 + outer loop + vertex 0.938928 1.85556 2.62101 + vertex 0.935349 1.85402 2.6209 + vertex 0.937709 1.85167 2.62152 + endloop + endfacet + facet normal -0.0364392 0.142294 0.989153 + outer loop + vertex 0.938928 1.85556 2.62101 + vertex 0.937709 1.85167 2.62152 + vertex 0.942208 1.8554 2.62115 + endloop + endfacet + facet normal -0.0360429 0.149492 0.988106 + outer loop + vertex 0.938928 1.85556 2.62101 + vertex 0.942208 1.8554 2.62115 + vertex 0.941549 1.85806 2.62073 + endloop + endfacet + facet normal -0.073037 0.187297 0.979584 + outer loop + vertex 0.941549 1.85806 2.62073 + vertex 0.938309 1.85801 2.6205 + vertex 0.938928 1.85556 2.62101 + endloop + endfacet + facet normal -0.0730357 0.18669 0.9797 + outer loop + vertex 0.941549 1.85806 2.62073 + vertex 0.943423 1.86196 2.62012 + vertex 0.938309 1.85801 2.6205 + endloop + endfacet + facet normal -0.0763392 0.190858 0.978645 + outer loop + vertex 0.938309 1.85801 2.6205 + vertex 0.943423 1.86196 2.62012 + vertex 0.938257 1.86191 2.61973 + endloop + endfacet + facet normal -0.180125 0.186934 0.965718 + outer loop + vertex 0.938309 1.85801 2.6205 + vertex 0.938257 1.86191 2.61973 + vertex 0.933218 1.85642 2.61985 + endloop + endfacet + facet normal -0.195307 0.24198 0.950421 + outer loop + vertex 0.933218 1.85642 2.61985 + vertex 0.935349 1.85402 2.6209 + vertex 0.938309 1.85801 2.6205 + endloop + endfacet + facet normal -0.0764502 0.165079 0.983313 + outer loop + vertex 0.943423 1.86196 2.62012 + vertex 0.943474 1.86706 2.61927 + vertex 0.938257 1.86191 2.61973 + endloop + endfacet + facet normal -0.0901791 0.178686 0.979765 + outer loop + vertex 0.938257 1.86191 2.61973 + vertex 0.943474 1.86706 2.61927 + vertex 0.938431 1.86681 2.61885 + endloop + endfacet + facet normal -0.198429 0.179622 0.963515 + outer loop + vertex 0.938257 1.86191 2.61973 + vertex 0.938431 1.86681 2.61885 + vertex 0.93337 1.8616 2.61878 + endloop + endfacet + facet normal -0.199009 0.204098 0.958509 + outer loop + vertex 0.933218 1.85642 2.61985 + vertex 0.938257 1.86191 2.61973 + vertex 0.93337 1.8616 2.61878 + endloop + endfacet + facet normal -0.207504 0.188501 0.959901 + outer loop + vertex 0.93337 1.8616 2.61878 + vertex 0.938431 1.86681 2.61885 + vertex 0.933619 1.86667 2.61784 + endloop + endfacet + facet normal -0.207508 0.18816 0.959967 + outer loop + vertex 0.938431 1.86681 2.61885 + vertex 0.938474 1.87179 2.61788 + vertex 0.933619 1.86667 2.61784 + endloop + endfacet + facet normal -0.220688 0.200682 0.954476 + outer loop + vertex 0.933619 1.86667 2.61784 + vertex 0.938474 1.87179 2.61788 + vertex 0.933318 1.87174 2.6167 + endloop + endfacet + facet normal -0.221464 0.17767 0.958847 + outer loop + vertex 0.938474 1.87179 2.61788 + vertex 0.93837 1.87646 2.617 + vertex 0.933318 1.87174 2.6167 + endloop + endfacet + facet normal -0.190341 0.143532 0.971169 + outer loop + vertex 0.933318 1.87174 2.6167 + vertex 0.93837 1.87646 2.617 + vertex 0.934432 1.87643 2.61623 + endloop + endfacet + facet normal -0.18989 0.163318 0.968127 + outer loop + vertex 0.934432 1.87643 2.61623 + vertex 0.93837 1.87646 2.617 + vertex 0.937834 1.88004 2.61629 + endloop + endfacet + facet normal -0.213998 0.186133 0.958937 + outer loop + vertex 0.934727 1.8794 2.61572 + vertex 0.934432 1.87643 2.61623 + vertex 0.937834 1.88004 2.61629 + endloop + endfacet + facet normal -0.217332 0.206682 0.953965 + outer loop + vertex 0.934727 1.8794 2.61572 + vertex 0.937834 1.88004 2.61629 + vertex 0.936727 1.88225 2.61556 + endloop + endfacet + facet normal -0.342836 0.291331 0.893079 + outer loop + vertex 0.936727 1.88225 2.61556 + vertex 0.933175 1.88139 2.61447 + vertex 0.934727 1.8794 2.61572 + endloop + endfacet + facet normal -0.341809 0.283402 0.896019 + outer loop + vertex 0.936727 1.88225 2.61556 + vertex 0.938188 1.88656 2.61475 + vertex 0.933175 1.88139 2.61447 + endloop + endfacet + facet normal -0.197261 0.244406 0.949396 + outer loop + vertex 0.936727 1.88225 2.61556 + vertex 0.940421 1.88406 2.61586 + vertex 0.938188 1.88656 2.61475 + endloop + endfacet + facet normal -0.18728 0.253179 0.949119 + outer loop + vertex 0.938188 1.88656 2.61475 + vertex 0.940421 1.88406 2.61586 + vertex 0.943411 1.88803 2.61539 + endloop + endfacet + facet normal -0.176555 0.209334 0.961773 + outer loop + vertex 0.943411 1.88803 2.61539 + vertex 0.943268 1.89205 2.61449 + vertex 0.938188 1.88656 2.61475 + endloop + endfacet + facet normal -0.187813 0.219559 0.95735 + outer loop + vertex 0.938188 1.88656 2.61475 + vertex 0.943268 1.89205 2.61449 + vertex 0.938309 1.89183 2.61357 + endloop + endfacet + facet normal -0.187721 0.195981 0.962472 + outer loop + vertex 0.943268 1.89205 2.61449 + vertex 0.94332 1.89698 2.61349 + vertex 0.938309 1.89183 2.61357 + endloop + endfacet + facet normal -0.180934 0.189419 0.965082 + outer loop + vertex 0.938309 1.89183 2.61357 + vertex 0.94332 1.89698 2.61349 + vertex 0.938623 1.89679 2.61265 + endloop + endfacet + facet normal -0.180935 0.189716 0.965023 + outer loop + vertex 0.94332 1.89698 2.61349 + vertex 0.94325 1.9018 2.61253 + vertex 0.938623 1.89679 2.61265 + endloop + endfacet + facet normal -0.182704 0.191335 0.964371 + outer loop + vertex 0.938623 1.89679 2.61265 + vertex 0.94325 1.9018 2.61253 + vertex 0.938529 1.90131 2.61174 + endloop + endfacet + facet normal -0.181944 0.180124 0.966671 + outer loop + vertex 0.938529 1.90131 2.61174 + vertex 0.94325 1.9018 2.61253 + vertex 0.94304 1.90631 2.61165 + endloop + endfacet + facet normal -0.0950445 0.193254 0.976534 + outer loop + vertex 0.94332 1.89698 2.61349 + vertex 0.948247 1.90206 2.61297 + vertex 0.94325 1.9018 2.61253 + endloop + endfacet + facet normal -0.0947648 0.185237 0.978114 + outer loop + vertex 0.948247 1.90206 2.61297 + vertex 0.947795 1.90655 2.61207 + vertex 0.94325 1.9018 2.61253 + endloop + endfacet + facet normal -0.0959121 0.186303 0.9778 + outer loop + vertex 0.94325 1.9018 2.61253 + vertex 0.947795 1.90655 2.61207 + vertex 0.94304 1.90631 2.61165 + endloop + endfacet + facet normal -0.0955685 0.176476 0.979654 + outer loop + vertex 0.94304 1.90631 2.61165 + vertex 0.947795 1.90655 2.61207 + vertex 0.947292 1.91023 2.61136 + endloop + endfacet + facet normal -0.0931846 0.173945 0.980337 + outer loop + vertex 0.944116 1.90996 2.61111 + vertex 0.94304 1.90631 2.61165 + vertex 0.947292 1.91023 2.61136 + endloop + endfacet + facet normal -0.0946928 0.195921 0.976037 + outer loop + vertex 0.944116 1.90996 2.61111 + vertex 0.947292 1.91023 2.61136 + vertex 0.946554 1.91266 2.6108 + endloop + endfacet + facet normal -0.200664 0.287162 0.936628 + outer loop + vertex 0.946554 1.91266 2.6108 + vertex 0.942675 1.91174 2.61025 + vertex 0.944116 1.90996 2.61111 + endloop + endfacet + facet normal -0.19784 0.272248 0.941669 + outer loop + vertex 0.946554 1.91266 2.6108 + vertex 0.948421 1.91676 2.61001 + vertex 0.942675 1.91174 2.61025 + endloop + endfacet + facet normal -0.176847 0.248744 0.952287 + outer loop + vertex 0.942675 1.91174 2.61025 + vertex 0.948421 1.91676 2.61001 + vertex 0.94315 1.9166 2.60907 + endloop + endfacet + facet normal -0.177306 0.207618 0.962007 + outer loop + vertex 0.948421 1.91676 2.61001 + vertex 0.948398 1.92189 2.6089 + vertex 0.94315 1.9166 2.60907 + endloop + endfacet + facet normal -0.177757 0.208061 0.961828 + outer loop + vertex 0.94315 1.9166 2.60907 + vertex 0.948398 1.92189 2.6089 + vertex 0.943379 1.92162 2.60803 + endloop + endfacet + facet normal -0.177594 0.198227 0.963933 + outer loop + vertex 0.948398 1.92189 2.6089 + vertex 0.948164 1.92679 2.60785 + vertex 0.943379 1.92162 2.60803 + endloop + endfacet + facet normal -0.186041 0.205928 0.96072 + outer loop + vertex 0.943379 1.92162 2.60803 + vertex 0.948164 1.92679 2.60785 + vertex 0.943094 1.92649 2.60693 + endloop + endfacet + facet normal -0.185748 0.192138 0.963629 + outer loop + vertex 0.948164 1.92679 2.60785 + vertex 0.947702 1.93156 2.60681 + vertex 0.943094 1.92649 2.60693 + endloop + endfacet + facet normal -0.187358 0.193586 0.963027 + outer loop + vertex 0.943094 1.92649 2.60693 + vertex 0.947702 1.93156 2.60681 + vertex 0.943681 1.93055 2.60623 + endloop + endfacet + facet normal -0.191593 0.213314 0.958013 + outer loop + vertex 0.947702 1.93156 2.60681 + vertex 0.945548 1.93404 2.60582 + vertex 0.943681 1.93055 2.60623 + endloop + endfacet + facet normal -0.192961 0.212121 0.958004 + outer loop + vertex 0.948882 1.93545 2.60618 + vertex 0.945548 1.93404 2.60582 + vertex 0.947702 1.93156 2.60681 + endloop + endfacet + facet normal -0.211125 0.258977 0.942527 + outer loop + vertex 0.945548 1.93404 2.60582 + vertex 0.948882 1.93545 2.60618 + vertex 0.948307 1.93797 2.60536 + endloop + endfacet + facet normal -0.298507 0.315368 0.900798 + outer loop + vertex 0.943407 1.93643 2.60428 + vertex 0.945548 1.93404 2.60582 + vertex 0.948307 1.93797 2.60536 + endloop + endfacet + facet normal -0.286219 0.261436 0.921808 + outer loop + vertex 0.948307 1.93797 2.60536 + vertex 0.948205 1.94194 2.6042 + vertex 0.943407 1.93643 2.60428 + endloop + endfacet + facet normal -0.0901348 0.203854 0.974843 + outer loop + vertex 0.948164 1.92679 2.60785 + vertex 0.952714 1.93152 2.60728 + vertex 0.947702 1.93156 2.60681 + endloop + endfacet + facet normal -0.0905513 0.188911 0.97781 + outer loop + vertex 0.947702 1.93156 2.60681 + vertex 0.952714 1.93152 2.60728 + vertex 0.95208 1.93532 2.60649 + endloop + endfacet + facet normal -0.0852314 0.182849 0.97944 + outer loop + vertex 0.948882 1.93545 2.60618 + vertex 0.947702 1.93156 2.60681 + vertex 0.95208 1.93532 2.60649 + endloop + endfacet + facet normal -0.0837053 0.208491 0.974436 + outer loop + vertex 0.948882 1.93545 2.60618 + vertex 0.95208 1.93532 2.60649 + vertex 0.95145 1.93799 2.60586 + endloop + endfacet + facet normal -0.152225 0.274661 0.949415 + outer loop + vertex 0.95145 1.93799 2.60586 + vertex 0.948307 1.93797 2.60536 + vertex 0.948882 1.93545 2.60618 + endloop + endfacet + facet normal -0.152169 0.276062 0.949017 + outer loop + vertex 0.95145 1.93799 2.60586 + vertex 0.953355 1.94202 2.60499 + vertex 0.948307 1.93797 2.60536 + endloop + endfacet + facet normal -0.149789 0.273201 0.950223 + outer loop + vertex 0.948307 1.93797 2.60536 + vertex 0.953355 1.94202 2.60499 + vertex 0.948205 1.94194 2.6042 + endloop + endfacet + facet normal -0.15105 0.223182 0.963002 + outer loop + vertex 0.953355 1.94202 2.60499 + vertex 0.953304 1.94699 2.60383 + vertex 0.948205 1.94194 2.6042 + endloop + endfacet + facet normal -0.159791 0.231767 0.959558 + outer loop + vertex 0.948205 1.94194 2.6042 + vertex 0.953304 1.94699 2.60383 + vertex 0.948345 1.9468 2.60305 + endloop + endfacet + facet normal -0.159768 0.211835 0.964158 + outer loop + vertex 0.953304 1.94699 2.60383 + vertex 0.953169 1.95177 2.60276 + vertex 0.948345 1.9468 2.60305 + endloop + endfacet + facet normal -0.169151 0.22074 0.960553 + outer loop + vertex 0.948345 1.9468 2.60305 + vertex 0.953169 1.95177 2.60276 + vertex 0.948129 1.95159 2.60192 + endloop + endfacet + facet normal -0.169174 0.203882 0.964268 + outer loop + vertex 0.953169 1.95177 2.60276 + vertex 0.952858 1.95643 2.60172 + vertex 0.948129 1.95159 2.60192 + endloop + endfacet + facet normal -0.171651 0.206261 0.963324 + outer loop + vertex 0.948129 1.95159 2.60192 + vertex 0.952858 1.95643 2.60172 + vertex 0.948802 1.95553 2.60119 + endloop + endfacet + facet normal -0.175526 0.226836 0.957986 + outer loop + vertex 0.952858 1.95643 2.60172 + vertex 0.950734 1.95894 2.60074 + vertex 0.948802 1.95553 2.60119 + endloop + endfacet + facet normal -0.175329 0.227001 0.957982 + outer loop + vertex 0.954152 1.96026 2.60105 + vertex 0.950734 1.95894 2.60074 + vertex 0.952858 1.95643 2.60172 + endloop + endfacet + facet normal -0.191313 0.271757 0.943158 + outer loop + vertex 0.950734 1.95894 2.60074 + vertex 0.954152 1.96026 2.60105 + vertex 0.953541 1.96285 2.60018 + endloop + endfacet + facet normal -0.274968 0.326214 0.904421 + outer loop + vertex 0.948526 1.96141 2.59918 + vertex 0.950734 1.95894 2.60074 + vertex 0.953541 1.96285 2.60018 + endloop + endfacet + facet normal -0.262874 0.268719 0.926654 + outer loop + vertex 0.953541 1.96285 2.60018 + vertex 0.953292 1.96688 2.59894 + vertex 0.948526 1.96141 2.59918 + endloop + endfacet + facet normal -0.0490556 0.232134 0.971446 + outer loop + vertex 0.95145 1.93799 2.60586 + vertex 0.955407 1.93894 2.60583 + vertex 0.953355 1.94202 2.60499 + endloop + endfacet + facet normal -0.0455461 0.217617 0.974971 + outer loop + vertex 0.955407 1.93894 2.60583 + vertex 0.95145 1.93799 2.60586 + vertex 0.95208 1.93532 2.60649 + endloop + endfacet + facet normal -0.0816537 0.195972 0.977204 + outer loop + vertex 0.953336 1.92703 2.60823 + vertex 0.952714 1.93152 2.60728 + vertex 0.948164 1.92679 2.60785 + endloop + endfacet + facet normal -0.0819389 0.205215 0.975281 + outer loop + vertex 0.948398 1.92189 2.6089 + vertex 0.953336 1.92703 2.60823 + vertex 0.948164 1.92679 2.60785 + endloop + endfacet + facet normal -0.0715566 0.195608 0.978068 + outer loop + vertex 0.953657 1.92228 2.60921 + vertex 0.953336 1.92703 2.60823 + vertex 0.948398 1.92189 2.6089 + endloop + endfacet + facet normal -0.0725023 0.210875 0.974821 + outer loop + vertex 0.948421 1.91676 2.61001 + vertex 0.953657 1.92228 2.60921 + vertex 0.948398 1.92189 2.6089 + endloop + endfacet + facet normal -0.0498805 0.190214 0.980475 + outer loop + vertex 0.954275 1.91802 2.61006 + vertex 0.953657 1.92228 2.60921 + vertex 0.948421 1.91676 2.61001 + endloop + endfacet + facet normal -0.0575941 0.226515 0.972303 + outer loop + vertex 0.948421 1.91676 2.61001 + vertex 0.950554 1.91392 2.6108 + vertex 0.954275 1.91802 2.61006 + endloop + endfacet + facet normal -0.0122049 0.187163 0.982253 + outer loop + vertex 0.950554 1.91392 2.6108 + vertex 0.955406 1.91439 2.61077 + vertex 0.954275 1.91802 2.61006 + endloop + endfacet + facet normal -0.0128299 0.193499 0.981017 + outer loop + vertex 0.955406 1.91439 2.61077 + vertex 0.950554 1.91392 2.6108 + vertex 0.951772 1.91065 2.61146 + endloop + endfacet + facet normal -0.0384197 0.184174 0.982142 + outer loop + vertex 0.951772 1.91065 2.61146 + vertex 0.950554 1.91392 2.6108 + vertex 0.947292 1.91023 2.61136 + endloop + endfacet + facet normal -0.0677696 0.219181 0.973328 + outer loop + vertex 0.946554 1.91266 2.6108 + vertex 0.950554 1.91392 2.6108 + vertex 0.948421 1.91676 2.61001 + endloop + endfacet + facet normal -0.0634869 0.205515 0.976593 + outer loop + vertex 0.950554 1.91392 2.6108 + vertex 0.946554 1.91266 2.6108 + vertex 0.947292 1.91023 2.61136 + endloop + endfacet + facet normal -0.0384697 0.18473 0.982036 + outer loop + vertex 0.947795 1.90655 2.61207 + vertex 0.951772 1.91065 2.61146 + vertex 0.947292 1.91023 2.61136 + endloop + endfacet + facet normal -0.0908528 0.189306 0.977706 + outer loop + vertex 0.948435 1.89708 2.61395 + vertex 0.948247 1.90206 2.61297 + vertex 0.94332 1.89698 2.61349 + endloop + endfacet + facet normal -0.0908739 0.1977 0.976041 + outer loop + vertex 0.943268 1.89205 2.61449 + vertex 0.948435 1.89708 2.61395 + vertex 0.94332 1.89698 2.61349 + endloop + endfacet + facet normal -0.0789056 0.185785 0.979417 + outer loop + vertex 0.948581 1.8918 2.61496 + vertex 0.948435 1.89708 2.61395 + vertex 0.943268 1.89205 2.61449 + endloop + endfacet + facet normal -0.077027 0.215489 0.973463 + outer loop + vertex 0.943411 1.88803 2.61539 + vertex 0.948581 1.8918 2.61496 + vertex 0.943268 1.89205 2.61449 + endloop + endfacet + facet normal -0.0763875 0.214641 0.973701 + outer loop + vertex 0.946685 1.88786 2.61568 + vertex 0.948581 1.8918 2.61496 + vertex 0.943411 1.88803 2.61539 + endloop + endfacet + facet normal -0.0767493 0.209374 0.974819 + outer loop + vertex 0.946685 1.88786 2.61568 + vertex 0.943411 1.88803 2.61539 + vertex 0.944077 1.88548 2.61599 + endloop + endfacet + facet normal -0.0383679 0.1687 0.98492 + outer loop + vertex 0.944077 1.88548 2.61599 + vertex 0.947343 1.88509 2.61618 + vertex 0.946685 1.88786 2.61568 + endloop + endfacet + facet normal -0.0122999 0.174811 0.984525 + outer loop + vertex 0.950531 1.88834 2.61565 + vertex 0.946685 1.88786 2.61568 + vertex 0.947343 1.88509 2.61618 + endloop + endfacet + facet normal -0.0394551 0.160254 0.986287 + outer loop + vertex 0.944077 1.88548 2.61599 + vertex 0.942789 1.88153 2.61658 + vertex 0.947343 1.88509 2.61618 + endloop + endfacet + facet normal -0.0137236 0.186087 0.982437 + outer loop + vertex 0.946685 1.88786 2.61568 + vertex 0.950531 1.88834 2.61565 + vertex 0.948581 1.8918 2.61496 + endloop + endfacet + facet normal -0.112497 0.199681 0.973382 + outer loop + vertex 0.940421 1.88406 2.61586 + vertex 0.944077 1.88548 2.61599 + vertex 0.943411 1.88803 2.61539 + endloop + endfacet + facet normal -0.105202 0.180472 0.977938 + outer loop + vertex 0.944077 1.88548 2.61599 + vertex 0.940421 1.88406 2.61586 + vertex 0.942789 1.88153 2.61658 + endloop + endfacet + facet normal -0.110523 0.175571 0.978243 + outer loop + vertex 0.942789 1.88153 2.61658 + vertex 0.940421 1.88406 2.61586 + vertex 0.937834 1.88004 2.61629 + endloop + endfacet + facet normal -0.187234 0.222691 0.95674 + outer loop + vertex 0.940421 1.88406 2.61586 + vertex 0.936727 1.88225 2.61556 + vertex 0.937834 1.88004 2.61629 + endloop + endfacet + facet normal -0.110944 0.177033 0.977932 + outer loop + vertex 0.93837 1.87646 2.617 + vertex 0.942789 1.88153 2.61658 + vertex 0.937834 1.88004 2.61629 + endloop + endfacet + facet normal -0.108188 0.174694 0.978661 + outer loop + vertex 0.943371 1.87691 2.61747 + vertex 0.942789 1.88153 2.61658 + vertex 0.93837 1.87646 2.617 + endloop + endfacet + facet normal -0.108848 0.183636 0.976949 + outer loop + vertex 0.938474 1.87179 2.61788 + vertex 0.943371 1.87691 2.61747 + vertex 0.93837 1.87646 2.617 + endloop + endfacet + facet normal -0.106173 0.181139 0.97771 + outer loop + vertex 0.943568 1.8721 2.61838 + vertex 0.943371 1.87691 2.61747 + vertex 0.938474 1.87179 2.61788 + endloop + endfacet + facet normal -0.106556 0.190388 0.975909 + outer loop + vertex 0.938431 1.86681 2.61885 + vertex 0.943568 1.8721 2.61838 + vertex 0.938474 1.87179 2.61788 + endloop + endfacet + facet normal -0.0900431 0.174779 0.980482 + outer loop + vertex 0.943474 1.86706 2.61927 + vertex 0.943568 1.8721 2.61838 + vertex 0.938431 1.86681 2.61885 + endloop + endfacet + facet normal -0.0159797 0.160449 0.986915 + outer loop + vertex 0.941549 1.85806 2.62073 + vertex 0.945483 1.85881 2.62067 + vertex 0.943423 1.86196 2.62012 + endloop + endfacet + facet normal -0.0148665 0.154692 0.987851 + outer loop + vertex 0.945483 1.85881 2.62067 + vertex 0.941549 1.85806 2.62073 + vertex 0.942208 1.8554 2.62115 + endloop + endfacet + facet normal -0.0436932 0.150885 0.987585 + outer loop + vertex 0.937709 1.85167 2.62152 + vertex 0.942874 1.85164 2.62176 + vertex 0.942208 1.8554 2.62115 + endloop + endfacet + facet normal -0.106135 0.178635 0.978174 + outer loop + vertex 0.935349 1.85402 2.6209 + vertex 0.938928 1.85556 2.62101 + vertex 0.938309 1.85801 2.6205 + endloop + endfacet + facet normal -0.0435861 0.160491 0.986075 + outer loop + vertex 0.938359 1.8471 2.6223 + vertex 0.942874 1.85164 2.62176 + vertex 0.937709 1.85167 2.62152 + endloop + endfacet + facet normal -0.0441861 0.161072 0.985953 + outer loop + vertex 0.943522 1.8472 2.62251 + vertex 0.942874 1.85164 2.62176 + vertex 0.938359 1.8471 2.6223 + endloop + endfacet + facet normal -0.0442418 0.165083 0.985287 + outer loop + vertex 0.938573 1.84221 2.62313 + vertex 0.943522 1.8472 2.62251 + vertex 0.938359 1.8471 2.6223 + endloop + endfacet + facet normal -0.0410448 0.161997 0.985937 + outer loop + vertex 0.943714 1.84224 2.62333 + vertex 0.943522 1.8472 2.62251 + vertex 0.938573 1.84221 2.62313 + endloop + endfacet + facet normal -0.0410455 0.163185 0.985741 + outer loop + vertex 0.938479 1.83705 2.62397 + vertex 0.943714 1.84224 2.62333 + vertex 0.938573 1.84221 2.62313 + endloop + endfacet + facet normal -0.0347673 0.157006 0.986986 + outer loop + vertex 0.943574 1.83714 2.62414 + vertex 0.943714 1.84224 2.62333 + vertex 0.938479 1.83705 2.62397 + endloop + endfacet + facet normal -0.0347725 0.157476 0.98691 + outer loop + vertex 0.938416 1.83212 2.62476 + vertex 0.943574 1.83714 2.62414 + vertex 0.938479 1.83705 2.62397 + endloop + endfacet + facet normal -0.0254275 0.148087 0.988647 + outer loop + vertex 0.943531 1.83244 2.62484 + vertex 0.943574 1.83714 2.62414 + vertex 0.938416 1.83212 2.62476 + endloop + endfacet + facet normal 0.0124572 0.143548 0.989565 + outer loop + vertex 0.944053 1.82846 2.62541 + vertex 0.948479 1.83249 2.62477 + vertex 0.943531 1.83244 2.62484 + endloop + endfacet + facet normal 0.0124513 0.144005 0.989499 + outer loop + vertex 0.948479 1.83249 2.62477 + vertex 0.948557 1.83714 2.6241 + vertex 0.943531 1.83244 2.62484 + endloop + endfacet + facet normal 0.00880953 0.147818 0.988975 + outer loop + vertex 0.943531 1.83244 2.62484 + vertex 0.948557 1.83714 2.6241 + vertex 0.943574 1.83714 2.62414 + endloop + endfacet + facet normal 0.00880739 0.149479 0.988726 + outer loop + vertex 0.948557 1.83714 2.6241 + vertex 0.948705 1.8422 2.62333 + vertex 0.943574 1.83714 2.62414 + endloop + endfacet + facet normal 0.00211229 0.156113 0.987737 + outer loop + vertex 0.943574 1.83714 2.62414 + vertex 0.948705 1.8422 2.62333 + vertex 0.943714 1.84224 2.62333 + endloop + endfacet + facet normal 0.00210862 0.155727 0.987798 + outer loop + vertex 0.948705 1.8422 2.62333 + vertex 0.94845 1.84707 2.62256 + vertex 0.943714 1.84224 2.62333 + endloop + endfacet + facet normal -0.00598001 0.163455 0.986533 + outer loop + vertex 0.943714 1.84224 2.62333 + vertex 0.94845 1.84707 2.62256 + vertex 0.943522 1.8472 2.62251 + endloop + endfacet + facet normal -0.00604282 0.161228 0.986899 + outer loop + vertex 0.94845 1.84707 2.62256 + vertex 0.94785 1.85147 2.62184 + vertex 0.943522 1.8472 2.62251 + endloop + endfacet + facet normal -0.0108367 0.165962 0.986073 + outer loop + vertex 0.943522 1.8472 2.62251 + vertex 0.94785 1.85147 2.62184 + vertex 0.942874 1.85164 2.62176 + endloop + endfacet + facet normal -0.0111382 0.157956 0.987383 + outer loop + vertex 0.94785 1.85147 2.62184 + vertex 0.946852 1.85539 2.6212 + vertex 0.942874 1.85164 2.62176 + endloop + endfacet + facet normal -0.0100718 0.156851 0.987571 + outer loop + vertex 0.942874 1.85164 2.62176 + vertex 0.946852 1.85539 2.6212 + vertex 0.942208 1.8554 2.62115 + endloop + endfacet + facet normal -0.0100896 0.150213 0.988602 + outer loop + vertex 0.946852 1.85539 2.6212 + vertex 0.945483 1.85881 2.62067 + vertex 0.942208 1.8554 2.62115 + endloop + endfacet + facet normal 0.00600569 0.156518 0.987657 + outer loop + vertex 0.950328 1.85875 2.62065 + vertex 0.945483 1.85881 2.62067 + vertex 0.946852 1.85539 2.6212 + endloop + endfacet + facet normal 0.0088956 0.153603 0.988093 + outer loop + vertex 0.952082 1.85486 2.62124 + vertex 0.950328 1.85875 2.62065 + vertex 0.946852 1.85539 2.6212 + endloop + endfacet + facet normal 0.0195356 0.158264 0.987203 + outer loop + vertex 0.954291 1.85823 2.62065 + vertex 0.950328 1.85875 2.62065 + vertex 0.952082 1.85486 2.62124 + endloop + endfacet + facet normal 0.0248513 0.15485 0.987625 + outer loop + vertex 0.956328 1.85601 2.62095 + vertex 0.954291 1.85823 2.62065 + vertex 0.952082 1.85486 2.62124 + endloop + endfacet + facet normal 0.023991 0.157908 0.987162 + outer loop + vertex 0.956328 1.85601 2.62095 + vertex 0.952082 1.85486 2.62124 + vertex 0.956414 1.85199 2.62159 + endloop + endfacet + facet normal 0.0323275 0.158045 0.986903 + outer loop + vertex 0.956328 1.85601 2.62095 + vertex 0.956414 1.85199 2.62159 + vertex 0.960349 1.85535 2.62092 + endloop + endfacet + facet normal 0.0321524 0.156982 0.987078 + outer loop + vertex 0.960349 1.85535 2.62092 + vertex 0.95875 1.85935 2.62034 + vertex 0.956328 1.85601 2.62095 + endloop + endfacet + facet normal 0.0357109 0.158353 0.986737 + outer loop + vertex 0.95875 1.85935 2.62034 + vertex 0.960349 1.85535 2.62092 + vertex 0.964009 1.8586 2.62027 + endloop + endfacet + facet normal 0.0354913 0.156801 0.986992 + outer loop + vertex 0.964009 1.8586 2.62027 + vertex 0.963605 1.86277 2.61962 + vertex 0.95875 1.85935 2.62034 + endloop + endfacet + facet normal 0.0365157 0.155386 0.987179 + outer loop + vertex 0.95875 1.85935 2.62034 + vertex 0.963605 1.86277 2.61962 + vertex 0.959659 1.86348 2.61966 + endloop + endfacet + facet normal 0.0304131 0.156728 0.987173 + outer loop + vertex 0.954751 1.86224 2.62 + vertex 0.95875 1.85935 2.62034 + vertex 0.959659 1.86348 2.61966 + endloop + endfacet + facet normal 0.0305852 0.156076 0.987271 + outer loop + vertex 0.959659 1.86348 2.61966 + vertex 0.958845 1.86719 2.6191 + vertex 0.954751 1.86224 2.62 + endloop + endfacet + facet normal 0.0302911 0.156314 0.987243 + outer loop + vertex 0.954751 1.86224 2.62 + vertex 0.958845 1.86719 2.6191 + vertex 0.953812 1.86715 2.61926 + endloop + endfacet + facet normal 0.0198173 0.1544 0.98781 + outer loop + vertex 0.954751 1.86224 2.62 + vertex 0.953812 1.86715 2.61926 + vertex 0.949226 1.86264 2.62005 + endloop + endfacet + facet normal 0.0199916 0.156848 0.98742 + outer loop + vertex 0.949226 1.86264 2.62005 + vertex 0.950328 1.85875 2.62065 + vertex 0.954751 1.86224 2.62 + endloop + endfacet + facet normal 0.0360039 0.15721 0.986909 + outer loop + vertex 0.959659 1.86348 2.61966 + vertex 0.963642 1.86723 2.61891 + vertex 0.958845 1.86719 2.6191 + endloop + endfacet + facet normal 0.0359768 0.159004 0.986622 + outer loop + vertex 0.963642 1.86723 2.61891 + vertex 0.963431 1.87199 2.61815 + vertex 0.958845 1.86719 2.6191 + endloop + endfacet + facet normal 0.038682 0.159104 0.986504 + outer loop + vertex 0.963642 1.86723 2.61891 + vertex 0.968371 1.87194 2.61797 + vertex 0.963431 1.87199 2.61815 + endloop + endfacet + facet normal 0.0386916 0.161784 0.986067 + outer loop + vertex 0.968371 1.87194 2.61797 + vertex 0.967813 1.87664 2.61722 + vertex 0.963431 1.87199 2.61815 + endloop + endfacet + facet normal 0.0362869 0.163996 0.985793 + outer loop + vertex 0.963431 1.87199 2.61815 + vertex 0.967813 1.87664 2.61722 + vertex 0.962826 1.8768 2.61738 + endloop + endfacet + facet normal 0.0363939 0.167771 0.985154 + outer loop + vertex 0.967813 1.87664 2.61722 + vertex 0.966663 1.88093 2.61653 + vertex 0.962826 1.8768 2.61738 + endloop + endfacet + facet normal 0.0334869 0.170403 0.984805 + outer loop + vertex 0.962826 1.8768 2.61738 + vertex 0.966663 1.88093 2.61653 + vertex 0.961634 1.88127 2.61664 + endloop + endfacet + facet normal 0.0328382 0.170238 0.984856 + outer loop + vertex 0.962826 1.8768 2.61738 + vertex 0.961634 1.88127 2.61664 + vertex 0.957826 1.87704 2.6175 + endloop + endfacet + facet normal 0.0326578 0.166141 0.985561 + outer loop + vertex 0.958465 1.87207 2.61832 + vertex 0.962826 1.8768 2.61738 + vertex 0.957826 1.87704 2.6175 + endloop + endfacet + facet normal 0.029471 0.165759 0.985726 + outer loop + vertex 0.958465 1.87207 2.61832 + vertex 0.957826 1.87704 2.6175 + vertex 0.953507 1.8722 2.61844 + endloop + endfacet + facet normal 0.0293486 0.160268 0.986637 + outer loop + vertex 0.953812 1.86715 2.61926 + vertex 0.958465 1.87207 2.61832 + vertex 0.953507 1.8722 2.61844 + endloop + endfacet + facet normal 0.0302546 0.159431 0.986745 + outer loop + vertex 0.958845 1.86719 2.6191 + vertex 0.958465 1.87207 2.61832 + vertex 0.953812 1.86715 2.61926 + endloop + endfacet + facet normal 0.0351476 0.159777 0.986527 + outer loop + vertex 0.958845 1.86719 2.6191 + vertex 0.963431 1.87199 2.61815 + vertex 0.958465 1.87207 2.61832 + endloop + endfacet + facet normal 0.0257787 0.168963 0.985285 + outer loop + vertex 0.953507 1.8722 2.61844 + vertex 0.957826 1.87704 2.6175 + vertex 0.952971 1.87708 2.61762 + endloop + endfacet + facet normal 0.0126039 0.167599 0.985775 + outer loop + vertex 0.953507 1.8722 2.61844 + vertex 0.952971 1.87708 2.61762 + vertex 0.948569 1.87224 2.6185 + endloop + endfacet + facet normal 0.012576 0.163843 0.986406 + outer loop + vertex 0.948631 1.8672 2.61934 + vertex 0.953507 1.8722 2.61844 + vertex 0.948569 1.87224 2.6185 + endloop + endfacet + facet normal -0.0171764 0.16348 0.986397 + outer loop + vertex 0.948631 1.8672 2.61934 + vertex 0.948569 1.87224 2.6185 + vertex 0.943474 1.86706 2.61927 + endloop + endfacet + facet normal -0.017213 0.164955 0.986151 + outer loop + vertex 0.943423 1.86196 2.62012 + vertex 0.948631 1.8672 2.61934 + vertex 0.943474 1.86706 2.61927 + endloop + endfacet + facet normal -0.0061428 0.15422 0.988017 + outer loop + vertex 0.949226 1.86264 2.62005 + vertex 0.948631 1.8672 2.61934 + vertex 0.943423 1.86196 2.62012 + endloop + endfacet + facet normal -0.00751472 0.165837 0.986124 + outer loop + vertex 0.943423 1.86196 2.62012 + vertex 0.945483 1.85881 2.62067 + vertex 0.949226 1.86264 2.62005 + endloop + endfacet + facet normal 0.0170369 0.157156 0.987427 + outer loop + vertex 0.949226 1.86264 2.62005 + vertex 0.953812 1.86715 2.61926 + vertex 0.948631 1.8672 2.61934 + endloop + endfacet + facet normal -0.028515 0.174307 0.984278 + outer loop + vertex 0.943474 1.86706 2.61927 + vertex 0.948569 1.87224 2.6185 + vertex 0.943568 1.8721 2.61838 + endloop + endfacet + facet normal -0.0284909 0.173299 0.984457 + outer loop + vertex 0.948569 1.87224 2.6185 + vertex 0.948272 1.87701 2.61765 + vertex 0.943568 1.8721 2.61838 + endloop + endfacet + facet normal -0.0406819 0.184627 0.981966 + outer loop + vertex 0.943568 1.8721 2.61838 + vertex 0.948272 1.87701 2.61765 + vertex 0.943371 1.87691 2.61747 + endloop + endfacet + facet normal -0.0406072 0.178151 0.983165 + outer loop + vertex 0.948272 1.87701 2.61765 + vertex 0.947793 1.88129 2.61686 + vertex 0.943371 1.87691 2.61747 + endloop + endfacet + facet normal -0.0457634 0.183199 0.98201 + outer loop + vertex 0.943371 1.87691 2.61747 + vertex 0.947793 1.88129 2.61686 + vertex 0.942789 1.88153 2.61658 + endloop + endfacet + facet normal -0.0465777 0.169172 0.984485 + outer loop + vertex 0.942789 1.88153 2.61658 + vertex 0.947793 1.88129 2.61686 + vertex 0.947343 1.88509 2.61618 + endloop + endfacet + facet normal -0.0067104 0.181961 0.983283 + outer loop + vertex 0.948272 1.87701 2.61765 + vertex 0.951744 1.8807 2.61699 + vertex 0.947793 1.88129 2.61686 + endloop + endfacet + facet normal -0.00718499 0.178912 0.983839 + outer loop + vertex 0.951744 1.8807 2.61699 + vertex 0.952109 1.88468 2.61627 + vertex 0.947793 1.88129 2.61686 + endloop + endfacet + facet normal -0.00346723 0.174318 0.984683 + outer loop + vertex 0.947793 1.88129 2.61686 + vertex 0.952109 1.88468 2.61627 + vertex 0.947343 1.88509 2.61618 + endloop + endfacet + facet normal -0.00412264 0.167028 0.985943 + outer loop + vertex 0.952109 1.88468 2.61627 + vertex 0.950531 1.88834 2.61565 + vertex 0.947343 1.88509 2.61618 + endloop + endfacet + facet normal 0.010546 0.173152 0.984839 + outer loop + vertex 0.95437 1.88807 2.61565 + vertex 0.950531 1.88834 2.61565 + vertex 0.952109 1.88468 2.61627 + endloop + endfacet + facet normal 0.0191052 0.167599 0.98567 + outer loop + vertex 0.956317 1.8859 2.61598 + vertex 0.95437 1.88807 2.61565 + vertex 0.952109 1.88468 2.61627 + endloop + endfacet + facet normal 0.017212 0.173847 0.984622 + outer loop + vertex 0.956317 1.8859 2.61598 + vertex 0.952109 1.88468 2.61627 + vertex 0.956283 1.88191 2.61669 + endloop + endfacet + facet normal 0.0282922 0.173712 0.98439 + outer loop + vertex 0.956317 1.8859 2.61598 + vertex 0.956283 1.88191 2.61669 + vertex 0.960314 1.8853 2.61597 + endloop + endfacet + facet normal 0.0279506 0.171433 0.984799 + outer loop + vertex 0.960314 1.8853 2.61597 + vertex 0.958836 1.88932 2.61532 + vertex 0.956317 1.8859 2.61598 + endloop + endfacet + facet normal 0.0332841 0.173314 0.984304 + outer loop + vertex 0.958836 1.88932 2.61532 + vertex 0.960314 1.8853 2.61597 + vertex 0.964079 1.88866 2.61526 + endloop + endfacet + facet normal 0.0332194 0.172795 0.984398 + outer loop + vertex 0.964079 1.88866 2.61526 + vertex 0.963716 1.89282 2.61454 + vertex 0.958836 1.88932 2.61532 + endloop + endfacet + facet normal 0.0360415 0.168984 0.98496 + outer loop + vertex 0.958836 1.88932 2.61532 + vertex 0.963716 1.89282 2.61454 + vertex 0.95982 1.89354 2.61456 + endloop + endfacet + facet normal 0.0250243 0.17154 0.984859 + outer loop + vertex 0.954807 1.8921 2.61493 + vertex 0.958836 1.88932 2.61532 + vertex 0.95982 1.89354 2.61456 + endloop + endfacet + facet normal 0.0254947 0.169965 0.98512 + outer loop + vertex 0.95982 1.89354 2.61456 + vertex 0.958948 1.89723 2.61394 + vertex 0.954807 1.8921 2.61493 + endloop + endfacet + facet normal 0.0177531 0.17605 0.984221 + outer loop + vertex 0.954807 1.8921 2.61493 + vertex 0.958948 1.89723 2.61394 + vertex 0.953769 1.89708 2.61406 + endloop + endfacet + facet normal -0.00377606 0.171715 0.985139 + outer loop + vertex 0.954807 1.8921 2.61493 + vertex 0.953769 1.89708 2.61406 + vertex 0.948581 1.8918 2.61496 + endloop + endfacet + facet normal -0.00472014 0.190992 0.98158 + outer loop + vertex 0.948581 1.8918 2.61496 + vertex 0.950531 1.88834 2.61565 + vertex 0.954807 1.8921 2.61493 + endloop + endfacet + facet normal -0.0207515 0.187879 0.981973 + outer loop + vertex 0.948581 1.8918 2.61496 + vertex 0.953769 1.89708 2.61406 + vertex 0.948435 1.89708 2.61395 + endloop + endfacet + facet normal -0.0207887 0.180767 0.983306 + outer loop + vertex 0.953769 1.89708 2.61406 + vertex 0.953395 1.90212 2.61313 + vertex 0.948435 1.89708 2.61395 + endloop + endfacet + facet normal -0.032727 0.192123 0.980825 + outer loop + vertex 0.948435 1.89708 2.61395 + vertex 0.953395 1.90212 2.61313 + vertex 0.948247 1.90206 2.61297 + endloop + endfacet + facet normal -0.0326965 0.186975 0.98182 + outer loop + vertex 0.953395 1.90212 2.61313 + vertex 0.952761 1.90673 2.61223 + vertex 0.948247 1.90206 2.61297 + endloop + endfacet + facet normal -0.0375765 0.19152 0.980769 + outer loop + vertex 0.948247 1.90206 2.61297 + vertex 0.952761 1.90673 2.61223 + vertex 0.947795 1.90655 2.61207 + endloop + endfacet + facet normal -0.0373379 0.183669 0.982279 + outer loop + vertex 0.952761 1.90673 2.61223 + vertex 0.951772 1.91065 2.61146 + vertex 0.947795 1.90655 2.61207 + endloop + endfacet + facet normal -0.00329283 0.192073 0.981375 + outer loop + vertex 0.952761 1.90673 2.61223 + vertex 0.956684 1.91074 2.61146 + vertex 0.951772 1.91065 2.61146 + endloop + endfacet + facet normal -0.00315589 0.184429 0.982841 + outer loop + vertex 0.956684 1.91074 2.61146 + vertex 0.955406 1.91439 2.61077 + vertex 0.951772 1.91065 2.61146 + endloop + endfacet + facet normal 0.0162663 0.190973 0.98146 + outer loop + vertex 0.960356 1.91429 2.61071 + vertex 0.955406 1.91439 2.61077 + vertex 0.956684 1.91074 2.61146 + endloop + endfacet + facet normal 0.0161471 0.184014 0.982791 + outer loop + vertex 0.955406 1.91439 2.61077 + vertex 0.960356 1.91429 2.61071 + vertex 0.959341 1.9182 2.60999 + endloop + endfacet + facet normal 0.0071429 0.192979 0.981177 + outer loop + vertex 0.954275 1.91802 2.61006 + vertex 0.955406 1.91439 2.61077 + vertex 0.959341 1.9182 2.60999 + endloop + endfacet + facet normal 0.00745953 0.184695 0.982768 + outer loop + vertex 0.959341 1.9182 2.60999 + vertex 0.958781 1.92249 2.60919 + vertex 0.954275 1.91802 2.61006 + endloop + endfacet + facet normal 0.02936 0.187275 0.981869 + outer loop + vertex 0.959341 1.9182 2.60999 + vertex 0.960356 1.91429 2.61071 + vertex 0.96436 1.91792 2.60989 + endloop + endfacet + facet normal 0.0292488 0.185113 0.982282 + outer loop + vertex 0.96436 1.91792 2.60989 + vertex 0.963677 1.92237 2.60908 + vertex 0.959341 1.9182 2.60999 + endloop + endfacet + facet normal 0.0272449 0.187126 0.981958 + outer loop + vertex 0.959341 1.9182 2.60999 + vertex 0.963677 1.92237 2.60908 + vertex 0.958781 1.92249 2.60919 + endloop + endfacet + facet normal 0.0272469 0.187225 0.981939 + outer loop + vertex 0.963677 1.92237 2.60908 + vertex 0.963186 1.92688 2.60823 + vertex 0.958781 1.92249 2.60919 + endloop + endfacet + facet normal 0.0219937 0.192314 0.981087 + outer loop + vertex 0.958781 1.92249 2.60919 + vertex 0.963186 1.92688 2.60823 + vertex 0.958426 1.92709 2.60829 + endloop + endfacet + facet normal 0.0220559 0.193761 0.980801 + outer loop + vertex 0.963186 1.92688 2.60823 + vertex 0.962699 1.93128 2.60737 + vertex 0.958426 1.92709 2.60829 + endloop + endfacet + facet normal 0.0154665 0.200235 0.979626 + outer loop + vertex 0.958426 1.92709 2.60829 + vertex 0.962699 1.93128 2.60737 + vertex 0.957789 1.93158 2.60739 + endloop + endfacet + facet normal 0.0153379 0.198157 0.98005 + outer loop + vertex 0.962699 1.93128 2.60737 + vertex 0.961771 1.93544 2.60654 + vertex 0.957789 1.93158 2.60739 + endloop + endfacet + facet normal 0.0310522 0.201448 0.979007 + outer loop + vertex 0.962699 1.93128 2.60737 + vertex 0.967071 1.93475 2.60652 + vertex 0.961771 1.93544 2.60654 + endloop + endfacet + facet normal 0.0305339 0.197439 0.97984 + outer loop + vertex 0.967071 1.93475 2.60652 + vertex 0.965467 1.93893 2.60573 + vertex 0.961771 1.93544 2.60654 + endloop + endfacet + facet normal 0.0244573 0.203616 0.978745 + outer loop + vertex 0.965467 1.93893 2.60573 + vertex 0.960407 1.93925 2.60579 + vertex 0.961771 1.93544 2.60654 + endloop + endfacet + facet normal 0.00820324 0.198069 0.980154 + outer loop + vertex 0.961771 1.93544 2.60654 + vertex 0.960407 1.93925 2.60579 + vertex 0.956712 1.93554 2.60657 + endloop + endfacet + facet normal 0.00833701 0.205085 0.978709 + outer loop + vertex 0.957789 1.93158 2.60739 + vertex 0.961771 1.93544 2.60654 + vertex 0.956712 1.93554 2.60657 + endloop + endfacet + facet normal -0.0232014 0.19682 0.980165 + outer loop + vertex 0.957789 1.93158 2.60739 + vertex 0.956712 1.93554 2.60657 + vertex 0.952714 1.93152 2.60728 + endloop + endfacet + facet normal -0.0232674 0.204363 0.978619 + outer loop + vertex 0.953336 1.92703 2.60823 + vertex 0.957789 1.93158 2.60739 + vertex 0.952714 1.93152 2.60728 + endloop + endfacet + facet normal -0.0145159 0.196146 0.980467 + outer loop + vertex 0.958426 1.92709 2.60829 + vertex 0.957789 1.93158 2.60739 + vertex 0.953336 1.92703 2.60823 + endloop + endfacet + facet normal -0.0145523 0.199807 0.979727 + outer loop + vertex 0.953657 1.92228 2.60921 + vertex 0.958426 1.92709 2.60829 + vertex 0.953336 1.92703 2.60823 + endloop + endfacet + facet normal -0.00465558 0.190379 0.9817 + outer loop + vertex 0.958781 1.92249 2.60919 + vertex 0.958426 1.92709 2.60829 + vertex 0.953657 1.92228 2.60921 + endloop + endfacet + facet normal -0.0049215 0.196726 0.980446 + outer loop + vertex 0.954275 1.91802 2.61006 + vertex 0.958781 1.92249 2.60919 + vertex 0.953657 1.92228 2.60921 + endloop + endfacet + facet normal -0.0264761 0.199943 0.97945 + outer loop + vertex 0.952714 1.93152 2.60728 + vertex 0.956712 1.93554 2.60657 + vertex 0.95208 1.93532 2.60649 + endloop + endfacet + facet normal -0.0265194 0.200896 0.979254 + outer loop + vertex 0.956712 1.93554 2.60657 + vertex 0.955407 1.93894 2.60583 + vertex 0.95208 1.93532 2.60649 + endloop + endfacet + facet normal -0.00364128 0.209394 0.977825 + outer loop + vertex 0.960407 1.93925 2.60579 + vertex 0.955407 1.93894 2.60583 + vertex 0.956712 1.93554 2.60657 + endloop + endfacet + facet normal -0.00317765 0.202194 0.97934 + outer loop + vertex 0.955407 1.93894 2.60583 + vertex 0.960407 1.93925 2.60579 + vertex 0.959187 1.943 2.60501 + endloop + endfacet + facet normal -0.0420593 0.236591 0.970699 + outer loop + vertex 0.953355 1.94202 2.60499 + vertex 0.955407 1.93894 2.60583 + vertex 0.959187 1.943 2.60501 + endloop + endfacet + facet normal -0.0360989 0.20123 0.978879 + outer loop + vertex 0.959187 1.943 2.60501 + vertex 0.9585 1.94726 2.60411 + vertex 0.953355 1.94202 2.60499 + endloop + endfacet + facet normal -0.0627357 0.226213 0.972056 + outer loop + vertex 0.953355 1.94202 2.60499 + vertex 0.9585 1.94726 2.60411 + vertex 0.953304 1.94699 2.60383 + endloop + endfacet + facet normal -0.0619031 0.205731 0.976649 + outer loop + vertex 0.9585 1.94726 2.60411 + vertex 0.958232 1.95187 2.60312 + vertex 0.953304 1.94699 2.60383 + endloop + endfacet + facet normal -0.0729117 0.216388 0.973581 + outer loop + vertex 0.953304 1.94699 2.60383 + vertex 0.958232 1.95187 2.60312 + vertex 0.953169 1.95177 2.60276 + endloop + endfacet + facet normal -0.0728408 0.204309 0.976193 + outer loop + vertex 0.958232 1.95187 2.60312 + vertex 0.957808 1.95625 2.60217 + vertex 0.953169 1.95177 2.60276 + endloop + endfacet + facet normal -0.0805319 0.21196 0.973955 + outer loop + vertex 0.953169 1.95177 2.60276 + vertex 0.957808 1.95625 2.60217 + vertex 0.952858 1.95643 2.60172 + endloop + endfacet + facet normal -0.0810612 0.202289 0.975965 + outer loop + vertex 0.952858 1.95643 2.60172 + vertex 0.957808 1.95625 2.60217 + vertex 0.957347 1.96003 2.60135 + endloop + endfacet + facet normal -0.0767525 0.197065 0.977381 + outer loop + vertex 0.954152 1.96026 2.60105 + vertex 0.952858 1.95643 2.60172 + vertex 0.957347 1.96003 2.60135 + endloop + endfacet + facet normal -0.0746629 0.220344 0.972561 + outer loop + vertex 0.954152 1.96026 2.60105 + vertex 0.957347 1.96003 2.60135 + vertex 0.956753 1.96278 2.60068 + endloop + endfacet + facet normal -0.141047 0.285244 0.94802 + outer loop + vertex 0.956753 1.96278 2.60068 + vertex 0.953541 1.96285 2.60018 + vertex 0.954152 1.96026 2.60105 + endloop + endfacet + facet normal -0.14092 0.287125 0.947471 + outer loop + vertex 0.956753 1.96278 2.60068 + vertex 0.958537 1.96686 2.59971 + vertex 0.953541 1.96285 2.60018 + endloop + endfacet + facet normal -0.137736 0.283353 0.949073 + outer loop + vertex 0.953541 1.96285 2.60018 + vertex 0.958537 1.96686 2.59971 + vertex 0.953292 1.96688 2.59894 + endloop + endfacet + facet normal -0.139885 0.230737 0.962908 + outer loop + vertex 0.958537 1.96686 2.59971 + vertex 0.958145 1.97184 2.59846 + vertex 0.953292 1.96688 2.59894 + endloop + endfacet + facet normal -0.150489 0.240707 0.95886 + outer loop + vertex 0.953292 1.96688 2.59894 + vertex 0.958145 1.97184 2.59846 + vertex 0.953297 1.97164 2.59775 + endloop + endfacet + facet normal -0.150288 0.21281 0.965466 + outer loop + vertex 0.958145 1.97184 2.59846 + vertex 0.957725 1.97631 2.59741 + vertex 0.953297 1.97164 2.59775 + endloop + endfacet + facet normal -0.0687185 0.222157 0.972586 + outer loop + vertex 0.958145 1.97184 2.59846 + vertex 0.9626 1.9766 2.59769 + vertex 0.957725 1.97631 2.59741 + endloop + endfacet + facet normal -0.0679795 0.20611 0.976165 + outer loop + vertex 0.9626 1.9766 2.59769 + vertex 0.96169 1.98058 2.59678 + vertex 0.957725 1.97631 2.59741 + endloop + endfacet + facet normal -0.0842328 0.220547 0.971732 + outer loop + vertex 0.957725 1.97631 2.59741 + vertex 0.96169 1.98058 2.59678 + vertex 0.957276 1.98001 2.59653 + endloop + endfacet + facet normal -0.0848765 0.226088 0.970402 + outer loop + vertex 0.96169 1.98058 2.59678 + vertex 0.960513 1.98387 2.59591 + vertex 0.957276 1.98001 2.59653 + endloop + endfacet + facet normal -0.0186942 0.217308 0.975924 + outer loop + vertex 0.9626 1.9766 2.59769 + vertex 0.96658 1.9808 2.59683 + vertex 0.96169 1.98058 2.59678 + endloop + endfacet + facet normal -0.0183549 0.209346 0.977669 + outer loop + vertex 0.96658 1.9808 2.59683 + vertex 0.965394 1.98454 2.596 + vertex 0.96169 1.98058 2.59678 + endloop + endfacet + facet normal -0.0507772 0.238169 0.969895 + outer loop + vertex 0.965394 1.98454 2.596 + vertex 0.960513 1.98387 2.59591 + vertex 0.96169 1.98058 2.59678 + endloop + endfacet + facet normal -0.0494039 0.227814 0.97245 + outer loop + vertex 0.960513 1.98387 2.59591 + vertex 0.965394 1.98454 2.596 + vertex 0.964212 1.98809 2.59511 + endloop + endfacet + facet normal -0.0203983 0.237166 0.971255 + outer loop + vertex 0.964212 1.98809 2.59511 + vertex 0.965394 1.98454 2.596 + vertex 0.969372 1.98844 2.59513 + endloop + endfacet + facet normal -0.0189738 0.215907 0.97623 + outer loop + vertex 0.969372 1.98844 2.59513 + vertex 0.968635 1.99251 2.59422 + vertex 0.964212 1.98809 2.59511 + endloop + endfacet + facet normal 0.0107235 0.207039 0.978274 + outer loop + vertex 0.965394 1.98454 2.596 + vertex 0.970378 1.98455 2.59595 + vertex 0.969372 1.98844 2.59513 + endloop + endfacet + facet normal 0.0106736 0.218154 0.975856 + outer loop + vertex 0.970378 1.98455 2.59595 + vertex 0.965394 1.98454 2.596 + vertex 0.96658 1.9808 2.59683 + endloop + endfacet + facet normal -0.0559969 0.210774 0.97593 + outer loop + vertex 0.963374 1.97209 2.5987 + vertex 0.9626 1.9766 2.59769 + vertex 0.958145 1.97184 2.59846 + endloop + endfacet + facet normal -0.0569944 0.238878 0.969375 + outer loop + vertex 0.958537 1.96686 2.59971 + vertex 0.963374 1.97209 2.5987 + vertex 0.958145 1.97184 2.59846 + endloop + endfacet + facet normal -0.0300138 0.215176 0.976114 + outer loop + vertex 0.964417 1.96767 2.59971 + vertex 0.963374 1.97209 2.5987 + vertex 0.958537 1.96686 2.59971 + endloop + endfacet + facet normal -0.0351803 0.252738 0.966895 + outer loop + vertex 0.958537 1.96686 2.59971 + vertex 0.960693 1.96361 2.60064 + vertex 0.964417 1.96767 2.59971 + endloop + endfacet + facet normal 0.0028084 0.21986 0.975527 + outer loop + vertex 0.960693 1.96361 2.60064 + vertex 0.965547 1.96369 2.6006 + vertex 0.964417 1.96767 2.59971 + endloop + endfacet + facet normal 0.00277542 0.2217 0.975111 + outer loop + vertex 0.965547 1.96369 2.6006 + vertex 0.960693 1.96361 2.60064 + vertex 0.961908 1.96008 2.60143 + endloop + endfacet + facet normal -0.0209708 0.213874 0.976636 + outer loop + vertex 0.961908 1.96008 2.60143 + vertex 0.960693 1.96361 2.60064 + vertex 0.957347 1.96003 2.60135 + endloop + endfacet + facet normal 0.00689563 0.223571 0.974663 + outer loop + vertex 0.964417 1.96767 2.59971 + vertex 0.968625 1.97209 2.59867 + vertex 0.963374 1.97209 2.5987 + endloop + endfacet + facet normal 0.00692755 0.207736 0.97816 + outer loop + vertex 0.968625 1.97209 2.59867 + vertex 0.967655 1.97661 2.59771 + vertex 0.963374 1.97209 2.5987 + endloop + endfacet + facet normal -0.00588651 0.219311 0.975637 + outer loop + vertex 0.963374 1.97209 2.5987 + vertex 0.967655 1.97661 2.59771 + vertex 0.9626 1.9766 2.59769 + endloop + endfacet + facet normal -0.00586566 0.205708 0.978596 + outer loop + vertex 0.967655 1.97661 2.59771 + vertex 0.96658 1.9808 2.59683 + vertex 0.9626 1.9766 2.59769 + endloop + endfacet + facet normal 0.0345261 0.213283 0.97638 + outer loop + vertex 0.968625 1.97209 2.59867 + vertex 0.972552 1.97621 2.59763 + vertex 0.967655 1.97661 2.59771 + endloop + endfacet + facet normal 0.033994 0.206363 0.977885 + outer loop + vertex 0.972552 1.97621 2.59763 + vertex 0.97159 1.98051 2.59675 + vertex 0.967655 1.97661 2.59771 + endloop + endfacet + facet normal 0.0265052 0.213585 0.976565 + outer loop + vertex 0.967655 1.97661 2.59771 + vertex 0.97159 1.98051 2.59675 + vertex 0.96658 1.9808 2.59683 + endloop + endfacet + facet normal 0.0259556 0.203353 0.978761 + outer loop + vertex 0.97159 1.98051 2.59675 + vertex 0.970378 1.98455 2.59595 + vertex 0.96658 1.9808 2.59683 + endloop + endfacet + facet normal 0.0460164 0.208999 0.976833 + outer loop + vertex 0.975337 1.98404 2.59582 + vertex 0.970378 1.98455 2.59595 + vertex 0.97159 1.98051 2.59675 + endloop + endfacet + facet normal 0.0519275 0.202971 0.977807 + outer loop + vertex 0.976849 1.97969 2.59665 + vertex 0.975337 1.98404 2.59582 + vertex 0.97159 1.98051 2.59675 + endloop + endfacet + facet normal 0.061293 0.206004 0.97663 + outer loop + vertex 0.979375 1.98333 2.59572 + vertex 0.975337 1.98404 2.59582 + vertex 0.976849 1.97969 2.59665 + endloop + endfacet + facet normal 0.06398 0.204192 0.976838 + outer loop + vertex 0.981308 1.98086 2.59611 + vertex 0.979375 1.98333 2.59572 + vertex 0.976849 1.97969 2.59665 + endloop + endfacet + facet normal 0.0653401 0.205208 0.976535 + outer loop + vertex 0.979375 1.98333 2.59572 + vertex 0.981308 1.98086 2.59611 + vertex 0.984029 1.98445 2.59517 + endloop + endfacet + facet normal 0.066073 0.202424 0.977066 + outer loop + vertex 0.979375 1.98333 2.59572 + vertex 0.984029 1.98445 2.59517 + vertex 0.979929 1.98752 2.59481 + endloop + endfacet + facet normal 0.0665785 0.203079 0.976896 + outer loop + vertex 0.979929 1.98752 2.59481 + vertex 0.984029 1.98445 2.59517 + vertex 0.984827 1.98865 2.59424 + endloop + endfacet + facet normal 0.0674397 0.20291 0.976872 + outer loop + vertex 0.984029 1.98445 2.59517 + vertex 0.988748 1.98779 2.59415 + vertex 0.984827 1.98865 2.59424 + endloop + endfacet + facet normal 0.0664578 0.204233 0.976664 + outer loop + vertex 0.989465 1.98346 2.59501 + vertex 0.988748 1.98779 2.59415 + vertex 0.984029 1.98445 2.59517 + endloop + endfacet + facet normal 0.0668558 0.206507 0.976158 + outer loop + vertex 0.984029 1.98445 2.59517 + vertex 0.985452 1.98003 2.59601 + vertex 0.989465 1.98346 2.59501 + endloop + endfacet + facet normal 0.0656725 0.207832 0.975957 + outer loop + vertex 0.985452 1.98003 2.59601 + vertex 0.990481 1.97913 2.59586 + vertex 0.989465 1.98346 2.59501 + endloop + endfacet + facet normal 0.07082 0.208924 0.975364 + outer loop + vertex 0.989465 1.98346 2.59501 + vertex 0.990481 1.97913 2.59586 + vertex 0.995029 1.98257 2.5948 + endloop + endfacet + facet normal 0.0700004 0.203517 0.976566 + outer loop + vertex 0.995029 1.98257 2.5948 + vertex 0.993637 1.98723 2.59392 + vertex 0.989465 1.98346 2.59501 + endloop + endfacet + facet normal 0.0699675 0.209999 0.975195 + outer loop + vertex 0.990481 1.97913 2.59586 + vertex 0.99459 1.97838 2.59573 + vertex 0.995029 1.98257 2.5948 + endloop + endfacet + facet normal 0.0701915 0.211266 0.974905 + outer loop + vertex 0.99459 1.97838 2.59573 + vertex 0.990481 1.97913 2.59586 + vertex 0.991994 1.97466 2.59672 + endloop + endfacet + facet normal 0.0743665 0.208429 0.975206 + outer loop + vertex 0.996496 1.97591 2.59611 + vertex 0.99459 1.97838 2.59573 + vertex 0.991994 1.97466 2.59672 + endloop + endfacet + facet normal 0.0743166 0.208594 0.975175 + outer loop + vertex 0.996496 1.97591 2.59611 + vertex 0.991994 1.97466 2.59672 + vertex 0.996186 1.97157 2.59706 + endloop + endfacet + facet normal 0.0859704 0.207599 0.974429 + outer loop + vertex 0.996496 1.97591 2.59611 + vertex 0.996186 1.97157 2.59706 + vertex 1.00052 1.97509 2.59593 + endloop + endfacet + facet normal 0.08619 0.208741 0.974165 + outer loop + vertex 1.00052 1.97509 2.59593 + vertex 0.999174 1.97953 2.5951 + vertex 0.996496 1.97591 2.59611 + endloop + endfacet + facet normal 0.0935412 0.210765 0.973051 + outer loop + vertex 0.999174 1.97953 2.5951 + vertex 1.00052 1.97509 2.59593 + vertex 1.00443 1.97848 2.59482 + endloop + endfacet + facet normal 0.0923097 0.204196 0.974568 + outer loop + vertex 1.00443 1.97848 2.59482 + vertex 1.00371 1.98281 2.59398 + vertex 0.999174 1.97953 2.5951 + endloop + endfacet + facet normal 0.0925043 0.203939 0.974603 + outer loop + vertex 0.999174 1.97953 2.5951 + vertex 1.00371 1.98281 2.59398 + vertex 0.999854 1.98371 2.59416 + endloop + endfacet + facet normal 0.0797454 0.206166 0.975262 + outer loop + vertex 0.995029 1.98257 2.5948 + vertex 0.999174 1.97953 2.5951 + vertex 0.999854 1.98371 2.59416 + endloop + endfacet + facet normal 0.0811171 0.200892 0.976249 + outer loop + vertex 0.999854 1.98371 2.59416 + vertex 0.998465 1.98699 2.5936 + vertex 0.995029 1.98257 2.5948 + endloop + endfacet + facet normal 0.0756118 0.205054 0.975826 + outer loop + vertex 0.995029 1.98257 2.5948 + vertex 0.998465 1.98699 2.5936 + vertex 0.993637 1.98723 2.59392 + endloop + endfacet + facet normal 0.0754992 0.201809 0.976511 + outer loop + vertex 0.998465 1.98699 2.5936 + vertex 0.997481 1.99126 2.59279 + vertex 0.993637 1.98723 2.59392 + endloop + endfacet + facet normal 0.0730141 0.2041 0.976223 + outer loop + vertex 0.993637 1.98723 2.59392 + vertex 0.997481 1.99126 2.59279 + vertex 0.992655 1.99159 2.59309 + endloop + endfacet + facet normal 0.0688392 0.203252 0.976703 + outer loop + vertex 0.993637 1.98723 2.59392 + vertex 0.992655 1.99159 2.59309 + vertex 0.988748 1.98779 2.59415 + endloop + endfacet + facet normal 0.0688936 0.203199 0.976711 + outer loop + vertex 0.988748 1.98779 2.59415 + vertex 0.992655 1.99159 2.59309 + vertex 0.988165 1.99186 2.59335 + endloop + endfacet + facet normal 0.0674634 0.203021 0.976848 + outer loop + vertex 0.988748 1.98779 2.59415 + vertex 0.988165 1.99186 2.59335 + vertex 0.984827 1.98865 2.59424 + endloop + endfacet + facet normal 0.0687721 0.201713 0.977027 + outer loop + vertex 0.984827 1.98865 2.59424 + vertex 0.988165 1.99186 2.59335 + vertex 0.983627 1.99212 2.59361 + endloop + endfacet + facet normal 0.0670614 0.201163 0.97726 + outer loop + vertex 0.984827 1.98865 2.59424 + vertex 0.983627 1.99212 2.59361 + vertex 0.979929 1.98752 2.59481 + endloop + endfacet + facet normal 0.0670075 0.201205 0.977255 + outer loop + vertex 0.979929 1.98752 2.59481 + vertex 0.983627 1.99212 2.59361 + vertex 0.978664 1.99227 2.59392 + endloop + endfacet + facet normal 0.059447 0.199354 0.978123 + outer loop + vertex 0.979929 1.98752 2.59481 + vertex 0.978664 1.99227 2.59392 + vertex 0.974449 1.98822 2.595 + endloop + endfacet + facet normal 0.0600234 0.20415 0.977098 + outer loop + vertex 0.974449 1.98822 2.595 + vertex 0.975337 1.98404 2.59582 + vertex 0.979929 1.98752 2.59481 + endloop + endfacet + facet normal 0.052939 0.205868 0.977147 + outer loop + vertex 0.974449 1.98822 2.595 + vertex 0.978664 1.99227 2.59392 + vertex 0.97365 1.99251 2.59414 + endloop + endfacet + facet normal 0.0340409 0.202653 0.978659 + outer loop + vertex 0.974449 1.98822 2.595 + vertex 0.97365 1.99251 2.59414 + vertex 0.969372 1.98844 2.59513 + endloop + endfacet + facet normal 0.0344329 0.212788 0.976492 + outer loop + vertex 0.969372 1.98844 2.59513 + vertex 0.970378 1.98455 2.59595 + vertex 0.974449 1.98822 2.595 + endloop + endfacet + facet normal 0.0150054 0.221777 0.974982 + outer loop + vertex 0.969372 1.98844 2.59513 + vertex 0.97365 1.99251 2.59414 + vertex 0.968635 1.99251 2.59422 + endloop + endfacet + facet normal 0.0150401 0.209378 0.977719 + outer loop + vertex 0.97365 1.99251 2.59414 + vertex 0.97296 1.99675 2.59325 + vertex 0.968635 1.99251 2.59422 + endloop + endfacet + facet normal -0.00619631 0.230004 0.97317 + outer loop + vertex 0.968635 1.99251 2.59422 + vertex 0.97296 1.99675 2.59325 + vertex 0.968049 1.99686 2.59319 + endloop + endfacet + facet normal -0.00644859 0.21993 0.975494 + outer loop + vertex 0.97296 1.99675 2.59325 + vertex 0.972455 2.00095 2.5923 + vertex 0.968049 1.99686 2.59319 + endloop + endfacet + facet normal 0.0406781 0.213218 0.976157 + outer loop + vertex 0.97365 1.99251 2.59414 + vertex 0.977687 1.99672 2.59306 + vertex 0.97296 1.99675 2.59325 + endloop + endfacet + facet normal 0.0406868 0.20706 0.977482 + outer loop + vertex 0.977687 1.99672 2.59306 + vertex 0.97639 2.00021 2.59237 + vertex 0.97296 1.99675 2.59325 + endloop + endfacet + facet normal 0.0235401 0.223309 0.974463 + outer loop + vertex 0.97296 1.99675 2.59325 + vertex 0.97639 2.00021 2.59237 + vertex 0.972455 2.00095 2.5923 + endloop + endfacet + facet normal 0.0234816 0.223004 0.974535 + outer loop + vertex 0.97639 2.00021 2.59237 + vertex 0.976955 2.00434 2.59141 + vertex 0.972455 2.00095 2.5923 + endloop + endfacet + facet normal 0.0213297 0.225706 0.973962 + outer loop + vertex 0.972455 2.00095 2.5923 + vertex 0.976955 2.00434 2.59141 + vertex 0.972164 2.0049 2.59139 + endloop + endfacet + facet normal 0.0209941 0.22283 0.974631 + outer loop + vertex 0.976955 2.00434 2.59141 + vertex 0.975501 2.00825 2.59055 + vertex 0.972164 2.0049 2.59139 + endloop + endfacet + facet normal 0.0550326 0.218626 0.974256 + outer loop + vertex 0.976955 2.00434 2.59141 + vertex 0.97639 2.00021 2.59237 + vertex 0.981072 2.0014 2.59184 + endloop + endfacet + facet normal 0.051409 0.21374 0.975537 + outer loop + vertex 0.981329 2.00566 2.59089 + vertex 0.976955 2.00434 2.59141 + vertex 0.981072 2.0014 2.59184 + endloop + endfacet + facet normal 0.070501 0.212389 0.974639 + outer loop + vertex 0.981329 2.00566 2.59089 + vertex 0.981072 2.0014 2.59184 + vertex 0.985369 2.00488 2.59077 + endloop + endfacet + facet normal 0.0715924 0.21825 0.973263 + outer loop + vertex 0.985369 2.00488 2.59077 + vertex 0.983941 2.00927 2.58989 + vertex 0.981329 2.00566 2.59089 + endloop + endfacet + facet normal 0.0622183 0.224799 0.972417 + outer loop + vertex 0.979419 2.00799 2.59048 + vertex 0.981329 2.00566 2.59089 + vertex 0.983941 2.00927 2.58989 + endloop + endfacet + facet normal 0.0596469 0.233079 0.970627 + outer loop + vertex 0.979419 2.00799 2.59048 + vertex 0.983941 2.00927 2.58989 + vertex 0.979622 2.01208 2.58948 + endloop + endfacet + facet normal 0.0338204 0.234578 0.971509 + outer loop + vertex 0.975501 2.00825 2.59055 + vertex 0.979419 2.00799 2.59048 + vertex 0.979622 2.01208 2.58948 + endloop + endfacet + facet normal 0.0155685 0.253046 0.967329 + outer loop + vertex 0.973413 2.01179 2.58966 + vertex 0.975501 2.00825 2.59055 + vertex 0.979622 2.01208 2.58948 + endloop + endfacet + facet normal 0.016831 0.229928 0.973062 + outer loop + vertex 0.979622 2.01208 2.58948 + vertex 0.977767 2.01663 2.58844 + vertex 0.973413 2.01179 2.58966 + endloop + endfacet + facet normal -0.00715697 0.250279 0.968147 + outer loop + vertex 0.973413 2.01179 2.58966 + vertex 0.977767 2.01663 2.58844 + vertex 0.972704 2.01659 2.58841 + endloop + endfacet + facet normal -0.00706019 0.23212 0.972662 + outer loop + vertex 0.977767 2.01663 2.58844 + vertex 0.976351 2.02024 2.58757 + vertex 0.972704 2.01659 2.58841 + endloop + endfacet + facet normal 0.0364112 0.237394 0.970731 + outer loop + vertex 0.979622 2.01208 2.58948 + vertex 0.982955 2.01693 2.58817 + vertex 0.977767 2.01663 2.58844 + endloop + endfacet + facet normal 0.0367062 0.233273 0.971718 + outer loop + vertex 0.982955 2.01693 2.58817 + vertex 0.9812 2.02149 2.58714 + vertex 0.977767 2.01663 2.58844 + endloop + endfacet + facet normal 0.0222959 0.24293 0.969788 + outer loop + vertex 0.977767 2.01663 2.58844 + vertex 0.9812 2.02149 2.58714 + vertex 0.976351 2.02024 2.58757 + endloop + endfacet + facet normal 0.023599 0.238261 0.970914 + outer loop + vertex 0.977405 2.02432 2.58654 + vertex 0.976351 2.02024 2.58757 + vertex 0.9812 2.02149 2.58714 + endloop + endfacet + facet normal 0.0245314 0.239444 0.9706 + outer loop + vertex 0.98154 2.02563 2.58611 + vertex 0.977405 2.02432 2.58654 + vertex 0.9812 2.02149 2.58714 + endloop + endfacet + facet normal 0.053392 0.236936 0.970057 + outer loop + vertex 0.98154 2.02563 2.58611 + vertex 0.9812 2.02149 2.58714 + vertex 0.9855 2.02508 2.58603 + endloop + endfacet + facet normal 0.0540008 0.241552 0.968884 + outer loop + vertex 0.9855 2.02508 2.58603 + vertex 0.984013 2.02923 2.58508 + vertex 0.98154 2.02563 2.58611 + endloop + endfacet + facet normal 0.0412749 0.249861 0.967402 + outer loop + vertex 0.979704 2.0277 2.58565 + vertex 0.98154 2.02563 2.58611 + vertex 0.984013 2.02923 2.58508 + endloop + endfacet + facet normal 0.0364977 0.262167 0.964332 + outer loop + vertex 0.979704 2.0277 2.58565 + vertex 0.984013 2.02923 2.58508 + vertex 0.979088 2.03149 2.58465 + endloop + endfacet + facet normal 0.0251958 0.238797 0.970743 + outer loop + vertex 0.979088 2.03149 2.58465 + vertex 0.984013 2.02923 2.58508 + vertex 0.98452 2.03342 2.58403 + endloop + endfacet + facet normal 0.0285289 0.230031 0.972765 + outer loop + vertex 0.98452 2.03342 2.58403 + vertex 0.982901 2.03673 2.5833 + vertex 0.979088 2.03149 2.58465 + endloop + endfacet + facet normal 0.000841534 0.249094 0.968479 + outer loop + vertex 0.979088 2.03149 2.58465 + vertex 0.982901 2.03673 2.5833 + vertex 0.977875 2.03651 2.58336 + endloop + endfacet + facet normal 0.00172442 0.230321 0.973113 + outer loop + vertex 0.982901 2.03673 2.5833 + vertex 0.981441 2.04018 2.58248 + vertex 0.977875 2.03651 2.58336 + endloop + endfacet + facet normal -0.0210987 0.251177 0.967711 + outer loop + vertex 0.977875 2.03651 2.58336 + vertex 0.981441 2.04018 2.58248 + vertex 0.977331 2.04127 2.58211 + endloop + endfacet + facet normal -0.0210616 0.251306 0.967678 + outer loop + vertex 0.977331 2.04127 2.58211 + vertex 0.981441 2.04018 2.58248 + vertex 0.982498 2.0443 2.58144 + endloop + endfacet + facet normal -0.0135811 0.239271 0.970858 + outer loop + vertex 0.979147 2.04533 2.58113 + vertex 0.977331 2.04127 2.58211 + vertex 0.982498 2.0443 2.58144 + endloop + endfacet + facet normal -0.00880296 0.253721 0.967237 + outer loop + vertex 0.979147 2.04533 2.58113 + vertex 0.982498 2.0443 2.58144 + vertex 0.981831 2.04753 2.58058 + endloop + endfacet + facet normal -0.0393929 0.288448 0.956685 + outer loop + vertex 0.981831 2.04753 2.58058 + vertex 0.978784 2.04823 2.58024 + vertex 0.979147 2.04533 2.58113 + endloop + endfacet + facet normal -0.0339409 0.308995 0.950458 + outer loop + vertex 0.981831 2.04753 2.58058 + vertex 0.984051 2.05137 2.57941 + vertex 0.978784 2.04823 2.58024 + endloop + endfacet + facet normal -0.0290565 0.30148 0.95303 + outer loop + vertex 0.978784 2.04823 2.58024 + vertex 0.984051 2.05137 2.57941 + vertex 0.978384 2.05203 2.57903 + endloop + endfacet + facet normal 0.0129965 0.284374 0.958625 + outer loop + vertex 0.981831 2.04753 2.58058 + vertex 0.984764 2.04771 2.58049 + vertex 0.984051 2.05137 2.57941 + endloop + endfacet + facet normal 0.0148178 0.258264 0.965961 + outer loop + vertex 0.984764 2.04771 2.58049 + vertex 0.981831 2.04753 2.58058 + vertex 0.982498 2.0443 2.58144 + endloop + endfacet + facet normal 0.0330805 0.238162 0.970662 + outer loop + vertex 0.982498 2.0443 2.58144 + vertex 0.981441 2.04018 2.58248 + vertex 0.986254 2.04142 2.58202 + endloop + endfacet + facet normal 0.0341728 0.239511 0.970292 + outer loop + vertex 0.986594 2.0456 2.58097 + vertex 0.982498 2.0443 2.58144 + vertex 0.986254 2.04142 2.58202 + endloop + endfacet + facet normal 0.0676026 0.236543 0.969266 + outer loop + vertex 0.986594 2.0456 2.58097 + vertex 0.986254 2.04142 2.58202 + vertex 0.990509 2.04492 2.58086 + endloop + endfacet + facet normal 0.0708243 0.255774 0.964139 + outer loop + vertex 0.990509 2.04492 2.58086 + vertex 0.988911 2.04914 2.57986 + vertex 0.986594 2.0456 2.58097 + endloop + endfacet + facet normal 0.0690503 0.234884 0.969568 + outer loop + vertex 0.991603 2.04056 2.58184 + vertex 0.990509 2.04492 2.58086 + vertex 0.986254 2.04142 2.58202 + endloop + endfacet + facet normal 0.0693839 0.237071 0.969011 + outer loop + vertex 0.987811 2.03688 2.58301 + vertex 0.991603 2.04056 2.58184 + vertex 0.986254 2.04142 2.58202 + endloop + endfacet + facet normal 0.048971 0.230672 0.971799 + outer loop + vertex 0.987811 2.03688 2.58301 + vertex 0.986254 2.04142 2.58202 + vertex 0.982901 2.03673 2.5833 + endloop + endfacet + facet normal 0.0773027 0.229298 0.970282 + outer loop + vertex 0.992483 2.0362 2.5828 + vertex 0.991603 2.04056 2.58184 + vertex 0.987811 2.03688 2.58301 + endloop + endfacet + facet normal 0.0775476 0.231096 0.969835 + outer loop + vertex 0.9886 2.03272 2.58394 + vertex 0.992483 2.0362 2.5828 + vertex 0.987811 2.03688 2.58301 + endloop + endfacet + facet normal 0.0606282 0.228304 0.9717 + outer loop + vertex 0.9886 2.03272 2.58394 + vertex 0.987811 2.03688 2.58301 + vertex 0.98452 2.03342 2.58403 + endloop + endfacet + facet normal 0.0898148 0.231472 0.968687 + outer loop + vertex 0.992483 2.0362 2.5828 + vertex 0.996833 2.03947 2.58162 + vertex 0.991603 2.04056 2.58184 + endloop + endfacet + facet normal 0.0902939 0.233899 0.968059 + outer loop + vertex 0.996833 2.03947 2.58162 + vertex 0.995372 2.044 2.58066 + vertex 0.991603 2.04056 2.58184 + endloop + endfacet + facet normal 0.095068 0.23527 0.96727 + outer loop + vertex 0.999387 2.04311 2.58048 + vertex 0.995372 2.044 2.58066 + vertex 0.996833 2.03947 2.58162 + endloop + endfacet + facet normal 0.0983225 0.233054 0.967481 + outer loop + vertex 1.00128 2.0405 2.58092 + vertex 0.999387 2.04311 2.58048 + vertex 0.996833 2.03947 2.58162 + endloop + endfacet + facet normal 0.0985051 0.232367 0.967627 + outer loop + vertex 1.00128 2.0405 2.58092 + vertex 0.996833 2.03947 2.58162 + vertex 1.00105 2.03614 2.58199 + endloop + endfacet + facet normal 0.102143 0.2321 0.967314 + outer loop + vertex 1.00128 2.0405 2.58092 + vertex 1.00105 2.03614 2.58199 + vertex 1.00529 2.0394 2.58076 + endloop + endfacet + facet normal 0.102995 0.235333 0.966442 + outer loop + vertex 1.00529 2.0394 2.58076 + vertex 1.00388 2.04403 2.57978 + vertex 1.00128 2.0405 2.58092 + endloop + endfacet + facet normal 0.100001 0.23453 0.966952 + outer loop + vertex 1.00388 2.04403 2.57978 + vertex 1.00529 2.0394 2.58076 + vertex 1.00961 2.04252 2.57956 + endloop + endfacet + facet normal 0.101792 0.232194 0.967328 + outer loop + vertex 1.00529 2.0394 2.58076 + vertex 1.00933 2.03824 2.58061 + vertex 1.00961 2.04252 2.57956 + endloop + endfacet + facet normal 0.100221 0.232331 0.96746 + outer loop + vertex 1.00933 2.03824 2.58061 + vertex 1.01394 2.03905 2.57994 + vertex 1.00961 2.04252 2.57956 + endloop + endfacet + facet normal 0.0993228 0.231249 0.967812 + outer loop + vertex 1.00961 2.04252 2.57956 + vertex 1.01394 2.03905 2.57994 + vertex 1.01425 2.04317 2.57892 + endloop + endfacet + facet normal 0.0982019 0.23776 0.966347 + outer loop + vertex 1.01425 2.04317 2.57892 + vertex 1.01279 2.0466 2.57823 + vertex 1.00961 2.04252 2.57956 + endloop + endfacet + facet normal 0.0973568 0.238395 0.966276 + outer loop + vertex 1.00961 2.04252 2.57956 + vertex 1.01279 2.0466 2.57823 + vertex 1.00802 2.04716 2.57857 + endloop + endfacet + facet normal 0.101284 0.239594 0.965576 + outer loop + vertex 1.00961 2.04252 2.57956 + vertex 1.00802 2.04716 2.57857 + vertex 1.00388 2.04403 2.57978 + endloop + endfacet + facet normal 0.097824 0.243874 0.96486 + outer loop + vertex 1.00388 2.04403 2.57978 + vertex 1.00802 2.04716 2.57857 + vertex 1.00417 2.04806 2.57873 + endloop + endfacet + facet normal 0.0988611 0.24378 0.964779 + outer loop + vertex 0.999656 2.04727 2.57939 + vertex 1.00388 2.04403 2.57978 + vertex 1.00417 2.04806 2.57873 + endloop + endfacet + facet normal 0.0967415 0.253905 0.962379 + outer loop + vertex 1.00417 2.04806 2.57873 + vertex 1.00278 2.0513 2.57802 + vertex 0.999656 2.04727 2.57939 + endloop + endfacet + facet normal 0.0962343 0.254282 0.96233 + outer loop + vertex 0.999656 2.04727 2.57939 + vertex 1.00278 2.0513 2.57802 + vertex 0.997916 2.05192 2.57834 + endloop + endfacet + facet normal 0.0951782 0.253932 0.962528 + outer loop + vertex 0.999656 2.04727 2.57939 + vertex 0.997916 2.05192 2.57834 + vertex 0.994231 2.04833 2.57965 + endloop + endfacet + facet normal 0.0943086 0.249136 0.963866 + outer loop + vertex 0.994231 2.04833 2.57965 + vertex 0.995372 2.044 2.58066 + vertex 0.999656 2.04727 2.57939 + endloop + endfacet + facet normal 0.0873789 0.247553 0.964926 + outer loop + vertex 0.990509 2.04492 2.58086 + vertex 0.995372 2.044 2.58066 + vertex 0.994231 2.04833 2.57965 + endloop + endfacet + facet normal 0.0772531 0.257955 0.963063 + outer loop + vertex 0.988911 2.04914 2.57986 + vertex 0.990509 2.04492 2.58086 + vertex 0.994231 2.04833 2.57965 + endloop + endfacet + facet normal 0.0767549 0.254429 0.964041 + outer loop + vertex 0.994231 2.04833 2.57965 + vertex 0.993049 2.05248 2.57865 + vertex 0.988911 2.04914 2.57986 + endloop + endfacet + facet normal 0.0703925 0.261767 0.962561 + outer loop + vertex 0.988911 2.04914 2.57986 + vertex 0.993049 2.05248 2.57865 + vertex 0.989148 2.05304 2.57878 + endloop + endfacet + facet normal 0.069836 0.257598 0.963725 + outer loop + vertex 0.993049 2.05248 2.57865 + vertex 0.9917 2.05563 2.57791 + vertex 0.989148 2.05304 2.57878 + endloop + endfacet + facet normal 0.0540826 0.272106 0.960746 + outer loop + vertex 0.989148 2.05304 2.57878 + vertex 0.9917 2.05563 2.57791 + vertex 0.987783 2.05612 2.57799 + endloop + endfacet + facet normal 0.0532133 0.264877 0.962813 + outer loop + vertex 0.9917 2.05563 2.57791 + vertex 0.992019 2.05955 2.57681 + vertex 0.987783 2.05612 2.57799 + endloop + endfacet + facet normal 0.0472688 0.271682 0.961226 + outer loop + vertex 0.987783 2.05612 2.57799 + vertex 0.992019 2.05955 2.57681 + vertex 0.986718 2.06017 2.57689 + endloop + endfacet + facet normal 0.0107995 0.26304 0.964725 + outer loop + vertex 0.987783 2.05612 2.57799 + vertex 0.986718 2.06017 2.57689 + vertex 0.982726 2.05619 2.57803 + endloop + endfacet + facet normal 0.0109842 0.279442 0.9601 + outer loop + vertex 0.984051 2.05137 2.57941 + vertex 0.987783 2.05612 2.57799 + vertex 0.982726 2.05619 2.57803 + endloop + endfacet + facet normal 0.0327614 0.263528 0.964095 + outer loop + vertex 0.989148 2.05304 2.57878 + vertex 0.987783 2.05612 2.57799 + vertex 0.984051 2.05137 2.57941 + endloop + endfacet + facet normal 0.0324358 0.264436 0.963858 + outer loop + vertex 0.984051 2.05137 2.57941 + vertex 0.988911 2.04914 2.57986 + vertex 0.989148 2.05304 2.57878 + endloop + endfacet + facet normal 0.0448366 0.289804 0.956035 + outer loop + vertex 0.984764 2.04771 2.58049 + vertex 0.988911 2.04914 2.57986 + vertex 0.984051 2.05137 2.57941 + endloop + endfacet + facet normal 0.0538852 0.266335 0.962373 + outer loop + vertex 0.984764 2.04771 2.58049 + vertex 0.986594 2.0456 2.58097 + vertex 0.988911 2.04914 2.57986 + endloop + endfacet + facet normal 0.0453763 0.255017 0.965871 + outer loop + vertex 0.992019 2.05955 2.57681 + vertex 0.990484 2.06382 2.57576 + vertex 0.986718 2.06017 2.57689 + endloop + endfacet + facet normal 0.0631196 0.260769 0.963335 + outer loop + vertex 0.994552 2.06317 2.57566 + vertex 0.990484 2.06382 2.57576 + vertex 0.992019 2.05955 2.57681 + endloop + endfacet + facet normal 0.0623148 0.255514 0.964795 + outer loop + vertex 0.990484 2.06382 2.57576 + vertex 0.994552 2.06317 2.57566 + vertex 0.994811 2.06729 2.57456 + endloop + endfacet + facet normal 0.0517667 0.267733 0.962102 + outer loop + vertex 0.989308 2.06794 2.57467 + vertex 0.990484 2.06382 2.57576 + vertex 0.994811 2.06729 2.57456 + endloop + endfacet + facet normal 0.0498374 0.250519 0.966828 + outer loop + vertex 0.994811 2.06729 2.57456 + vertex 0.992999 2.07181 2.57348 + vertex 0.989308 2.06794 2.57467 + endloop + endfacet + facet normal 0.0248383 0.272804 0.961749 + outer loop + vertex 0.989308 2.06794 2.57467 + vertex 0.992999 2.07181 2.57348 + vertex 0.988008 2.072 2.57355 + endloop + endfacet + facet normal 0.0242476 0.255637 0.966469 + outer loop + vertex 0.992999 2.07181 2.57348 + vertex 0.991441 2.07529 2.5726 + vertex 0.988008 2.072 2.57355 + endloop + endfacet + facet normal 0.000593587 0.278515 0.960432 + outer loop + vertex 0.988008 2.072 2.57355 + vertex 0.991441 2.07529 2.5726 + vertex 0.98728 2.07648 2.57225 + endloop + endfacet + facet normal -0.0360914 0.272835 0.961384 + outer loop + vertex 0.988008 2.072 2.57355 + vertex 0.98728 2.07648 2.57225 + vertex 0.982844 2.07176 2.57343 + endloop + endfacet + facet normal -0.0369392 0.295098 0.954753 + outer loop + vertex 0.984047 2.06786 2.57468 + vertex 0.988008 2.072 2.57355 + vertex 0.982844 2.07176 2.57343 + endloop + endfacet + facet normal -0.0796382 0.282342 0.956002 + outer loop + vertex 0.984047 2.06786 2.57468 + vertex 0.982844 2.07176 2.57343 + vertex 0.978259 2.06669 2.57454 + endloop + endfacet + facet normal -0.0885705 0.328683 0.940278 + outer loop + vertex 0.978259 2.06669 2.57454 + vertex 0.980486 2.06377 2.57577 + vertex 0.984047 2.06786 2.57468 + endloop + endfacet + facet normal -0.0267064 0.27989 0.95966 + outer loop + vertex 0.980486 2.06377 2.57577 + vertex 0.985446 2.06413 2.57581 + vertex 0.984047 2.06786 2.57468 + endloop + endfacet + facet normal -0.00286976 0.288196 0.957567 + outer loop + vertex 0.984047 2.06786 2.57468 + vertex 0.985446 2.06413 2.57581 + vertex 0.989308 2.06794 2.57467 + endloop + endfacet + facet normal 0.0259983 0.261127 0.964954 + outer loop + vertex 0.985446 2.06413 2.57581 + vertex 0.990484 2.06382 2.57576 + vertex 0.989308 2.06794 2.57467 + endloop + endfacet + facet normal 0.0266961 0.273004 0.961642 + outer loop + vertex 0.990484 2.06382 2.57576 + vertex 0.985446 2.06413 2.57581 + vertex 0.986718 2.06017 2.57689 + endloop + endfacet + facet normal -0.00215567 0.264479 0.964389 + outer loop + vertex 0.986718 2.06017 2.57689 + vertex 0.985446 2.06413 2.57581 + vertex 0.981677 2.06026 2.57686 + endloop + endfacet + facet normal -0.0019523 0.274895 0.961472 + outer loop + vertex 0.982726 2.05619 2.57803 + vertex 0.986718 2.06017 2.57689 + vertex 0.981677 2.06026 2.57686 + endloop + endfacet + facet normal -0.0271997 0.287029 0.957536 + outer loop + vertex 0.985446 2.06413 2.57581 + vertex 0.980486 2.06377 2.57577 + vertex 0.981677 2.06026 2.57686 + endloop + endfacet + facet normal -0.0622831 0.275654 0.959237 + outer loop + vertex 0.981677 2.06026 2.57686 + vertex 0.980486 2.06377 2.57577 + vertex 0.977125 2.06003 2.57663 + endloop + endfacet + facet normal -0.0622186 0.273914 0.959739 + outer loop + vertex 0.977597 2.0562 2.57775 + vertex 0.981677 2.06026 2.57686 + vertex 0.977125 2.06003 2.57663 + endloop + endfacet + facet normal -0.0505146 0.262968 0.963481 + outer loop + vertex 0.982726 2.05619 2.57803 + vertex 0.981677 2.06026 2.57686 + vertex 0.977597 2.0562 2.57775 + endloop + endfacet + facet normal -0.0501405 0.283947 0.957528 + outer loop + vertex 0.978384 2.05203 2.57903 + vertex 0.982726 2.05619 2.57803 + vertex 0.977597 2.0562 2.57775 + endloop + endfacet + facet normal -0.121993 0.269686 0.95519 + outer loop + vertex 0.978384 2.05203 2.57903 + vertex 0.977597 2.0562 2.57775 + vertex 0.973109 2.05163 2.57847 + endloop + endfacet + facet normal -0.123847 0.312497 0.941811 + outer loop + vertex 0.974084 2.04776 2.57988 + vertex 0.978384 2.05203 2.57903 + vertex 0.973109 2.05163 2.57847 + endloop + endfacet + facet normal -0.207301 0.288823 0.93467 + outer loop + vertex 0.974084 2.04776 2.57988 + vertex 0.973109 2.05163 2.57847 + vertex 0.96839 2.04611 2.57913 + endloop + endfacet + facet normal -0.222665 0.353804 0.908429 + outer loop + vertex 0.96839 2.04611 2.57913 + vertex 0.970724 2.04346 2.58073 + vertex 0.974084 2.04776 2.57988 + endloop + endfacet + facet normal -0.138331 0.29524 0.945356 + outer loop + vertex 0.970724 2.04346 2.58073 + vertex 0.97533 2.04454 2.58107 + vertex 0.974084 2.04776 2.57988 + endloop + endfacet + facet normal -0.103881 0.308622 0.945495 + outer loop + vertex 0.974084 2.04776 2.57988 + vertex 0.97533 2.04454 2.58107 + vertex 0.978784 2.04823 2.58024 + endloop + endfacet + facet normal -0.0748227 0.283792 0.955962 + outer loop + vertex 0.97533 2.04454 2.58107 + vertex 0.979147 2.04533 2.58113 + vertex 0.978784 2.04823 2.58024 + endloop + endfacet + facet normal -0.0705489 0.262659 0.962306 + outer loop + vertex 0.979147 2.04533 2.58113 + vertex 0.97533 2.04454 2.58107 + vertex 0.977331 2.04127 2.58211 + endloop + endfacet + facet normal -0.0839066 0.254824 0.96334 + outer loop + vertex 0.977331 2.04127 2.58211 + vertex 0.97533 2.04454 2.58107 + vertex 0.972 2.04037 2.58188 + endloop + endfacet + facet normal -0.0856135 0.265789 0.960222 + outer loop + vertex 0.972822 2.03649 2.58303 + vertex 0.977331 2.04127 2.58211 + vertex 0.972 2.04037 2.58188 + endloop + endfacet + facet normal -0.145099 0.252151 0.956748 + outer loop + vertex 0.972822 2.03649 2.58303 + vertex 0.972 2.04037 2.58188 + vertex 0.968029 2.03608 2.58241 + endloop + endfacet + facet normal -0.145988 0.269873 0.951765 + outer loop + vertex 0.968244 2.03181 2.58366 + vertex 0.972822 2.03649 2.58303 + vertex 0.968029 2.03608 2.58241 + endloop + endfacet + facet normal -0.127935 0.253192 0.958919 + outer loop + vertex 0.973427 2.03217 2.58425 + vertex 0.972822 2.03649 2.58303 + vertex 0.968244 2.03181 2.58366 + endloop + endfacet + facet normal -0.129429 0.295621 0.946497 + outer loop + vertex 0.969028 2.02788 2.58499 + vertex 0.973427 2.03217 2.58425 + vertex 0.968244 2.03181 2.58366 + endloop + endfacet + facet normal -0.104931 0.272217 0.956497 + outer loop + vertex 0.973693 2.02827 2.58539 + vertex 0.973427 2.03217 2.58425 + vertex 0.969028 2.02788 2.58499 + endloop + endfacet + facet normal -0.106259 0.294703 0.949663 + outer loop + vertex 0.969028 2.02788 2.58499 + vertex 0.970225 2.02461 2.58614 + vertex 0.973693 2.02827 2.58539 + endloop + endfacet + facet normal -0.0756505 0.267955 0.960457 + outer loop + vertex 0.970225 2.02461 2.58614 + vertex 0.974033 2.02536 2.58623 + vertex 0.973693 2.02827 2.58539 + endloop + endfacet + facet normal -0.0400528 0.27236 0.961361 + outer loop + vertex 0.97673 2.02753 2.58573 + vertex 0.973693 2.02827 2.58539 + vertex 0.974033 2.02536 2.58623 + endloop + endfacet + facet normal -0.0141175 0.242125 0.970142 + outer loop + vertex 0.974033 2.02536 2.58623 + vertex 0.977405 2.02432 2.58654 + vertex 0.97673 2.02753 2.58573 + endloop + endfacet + facet normal -0.0169933 0.233406 0.972231 + outer loop + vertex 0.974033 2.02536 2.58623 + vertex 0.97225 2.02133 2.58717 + vertex 0.977405 2.02432 2.58654 + endloop + endfacet + facet normal -0.0275634 0.250669 0.96768 + outer loop + vertex 0.97225 2.02133 2.58717 + vertex 0.976351 2.02024 2.58757 + vertex 0.977405 2.02432 2.58654 + endloop + endfacet + facet normal -0.0273922 0.251259 0.967532 + outer loop + vertex 0.972704 2.01659 2.58841 + vertex 0.976351 2.02024 2.58757 + vertex 0.97225 2.02133 2.58717 + endloop + endfacet + facet normal -0.0370119 0.283366 0.958297 + outer loop + vertex 0.97673 2.02753 2.58573 + vertex 0.979088 2.03149 2.58465 + vertex 0.973693 2.02827 2.58539 + endloop + endfacet + facet normal 0.0089633 0.258154 0.966062 + outer loop + vertex 0.97673 2.02753 2.58573 + vertex 0.979704 2.0277 2.58565 + vertex 0.979088 2.03149 2.58465 + endloop + endfacet + facet normal 0.00969531 0.24685 0.969005 + outer loop + vertex 0.979704 2.0277 2.58565 + vertex 0.97673 2.02753 2.58573 + vertex 0.977405 2.02432 2.58654 + endloop + endfacet + facet normal -0.0734479 0.256418 0.963771 + outer loop + vertex 0.974033 2.02536 2.58623 + vertex 0.970225 2.02461 2.58614 + vertex 0.97225 2.02133 2.58717 + endloop + endfacet + facet normal -0.0892288 0.247021 0.964893 + outer loop + vertex 0.97225 2.02133 2.58717 + vertex 0.970225 2.02461 2.58614 + vertex 0.966931 2.02043 2.5869 + endloop + endfacet + facet normal -0.0917491 0.26332 0.960336 + outer loop + vertex 0.967771 2.01654 2.58805 + vertex 0.97225 2.02133 2.58717 + vertex 0.966931 2.02043 2.5869 + endloop + endfacet + facet normal -0.151036 0.249437 0.95654 + outer loop + vertex 0.967771 2.01654 2.58805 + vertex 0.966931 2.02043 2.5869 + vertex 0.963015 2.01613 2.58741 + endloop + endfacet + facet normal -0.151904 0.267521 0.951503 + outer loop + vertex 0.963264 2.01184 2.58865 + vertex 0.967771 2.01654 2.58805 + vertex 0.963015 2.01613 2.58741 + endloop + endfacet + facet normal -0.249027 0.256751 0.933844 + outer loop + vertex 0.963264 2.01184 2.58865 + vertex 0.963015 2.01613 2.58741 + vertex 0.95823 2.0116 2.58738 + endloop + endfacet + facet normal -0.247952 0.296058 0.922426 + outer loop + vertex 0.958555 2.00645 2.58912 + vertex 0.963264 2.01184 2.58865 + vertex 0.95823 2.0116 2.58738 + endloop + endfacet + facet normal -0.221714 0.274282 0.935742 + outer loop + vertex 0.964014 2.00788 2.58999 + vertex 0.963264 2.01184 2.58865 + vertex 0.958555 2.00645 2.58912 + endloop + endfacet + facet normal -0.234492 0.337488 0.911655 + outer loop + vertex 0.958555 2.00645 2.58912 + vertex 0.960814 2.00369 2.59072 + vertex 0.964014 2.00788 2.58999 + endloop + endfacet + facet normal -0.140487 0.293066 0.945714 + outer loop + vertex 0.964014 2.00788 2.58999 + vertex 0.968263 2.01223 2.58928 + vertex 0.963264 2.01184 2.58865 + endloop + endfacet + facet normal -0.113887 0.268813 0.956436 + outer loop + vertex 0.968505 2.00837 2.59039 + vertex 0.968263 2.01223 2.58928 + vertex 0.964014 2.00788 2.58999 + endloop + endfacet + facet normal -0.115481 0.288241 0.950569 + outer loop + vertex 0.964014 2.00788 2.58999 + vertex 0.965219 2.00466 2.59112 + vertex 0.968505 2.00837 2.59039 + endloop + endfacet + facet normal -0.0773904 0.257009 0.963305 + outer loop + vertex 0.965219 2.00466 2.59112 + vertex 0.968938 2.00556 2.59117 + vertex 0.968505 2.00837 2.59039 + endloop + endfacet + facet normal -0.0449438 0.262193 0.963968 + outer loop + vertex 0.971644 2.00786 2.59068 + vertex 0.968505 2.00837 2.59039 + vertex 0.968938 2.00556 2.59117 + endloop + endfacet + facet normal -0.0168337 0.231025 0.972802 + outer loop + vertex 0.968938 2.00556 2.59117 + vertex 0.972164 2.0049 2.59139 + vertex 0.971644 2.00786 2.59068 + endloop + endfacet + facet normal 0.00790872 0.235167 0.971923 + outer loop + vertex 0.975501 2.00825 2.59055 + vertex 0.971644 2.00786 2.59068 + vertex 0.972164 2.0049 2.59139 + endloop + endfacet + facet normal 0.00647764 0.248032 0.96873 + outer loop + vertex 0.971644 2.00786 2.59068 + vertex 0.975501 2.00825 2.59055 + vertex 0.973413 2.01179 2.58966 + endloop + endfacet + facet normal -0.0193005 0.219782 0.975358 + outer loop + vertex 0.968938 2.00556 2.59117 + vertex 0.967422 2.00157 2.59204 + vertex 0.972164 2.0049 2.59139 + endloop + endfacet + facet normal -0.0436808 0.268898 0.962178 + outer loop + vertex 0.971644 2.00786 2.59068 + vertex 0.973413 2.01179 2.58966 + vertex 0.968505 2.00837 2.59039 + endloop + endfacet + facet normal -0.0730449 0.238686 0.968346 + outer loop + vertex 0.968938 2.00556 2.59117 + vertex 0.965219 2.00466 2.59112 + vertex 0.967422 2.00157 2.59204 + endloop + endfacet + facet normal -0.0851843 0.230341 0.969374 + outer loop + vertex 0.967422 2.00157 2.59204 + vertex 0.965219 2.00466 2.59112 + vertex 0.962051 2.0006 2.5918 + endloop + endfacet + facet normal -0.0872497 0.242539 0.96621 + outer loop + vertex 0.962823 1.99661 2.59287 + vertex 0.967422 2.00157 2.59204 + vertex 0.962051 2.0006 2.5918 + endloop + endfacet + facet normal -0.159382 0.227108 0.960739 + outer loop + vertex 0.962823 1.99661 2.59287 + vertex 0.962051 2.0006 2.5918 + vertex 0.957669 1.99634 2.59208 + endloop + endfacet + facet normal -0.166653 0.234403 0.957748 + outer loop + vertex 0.957669 1.99634 2.59208 + vertex 0.962051 2.0006 2.5918 + vertex 0.958507 2.0003 2.59126 + endloop + endfacet + facet normal -0.167938 0.264829 0.949559 + outer loop + vertex 0.962051 2.0006 2.5918 + vertex 0.960814 2.00369 2.59072 + vertex 0.958507 2.0003 2.59126 + endloop + endfacet + facet normal -0.0695484 0.226997 0.971409 + outer loop + vertex 0.968049 1.99686 2.59319 + vertex 0.967422 2.00157 2.59204 + vertex 0.962823 1.99661 2.59287 + endloop + endfacet + facet normal -0.0700935 0.243063 0.967475 + outer loop + vertex 0.963381 1.99212 2.59404 + vertex 0.968049 1.99686 2.59319 + vertex 0.962823 1.99661 2.59287 + endloop + endfacet + facet normal -0.144337 0.232365 0.961859 + outer loop + vertex 0.963381 1.99212 2.59404 + vertex 0.962823 1.99661 2.59287 + vertex 0.958129 1.99164 2.59337 + endloop + endfacet + facet normal -0.146047 0.2616 0.954063 + outer loop + vertex 0.958344 1.98668 2.59476 + vertex 0.963381 1.99212 2.59404 + vertex 0.958129 1.99164 2.59337 + endloop + endfacet + facet normal -0.256287 0.251014 0.933439 + outer loop + vertex 0.958344 1.98668 2.59476 + vertex 0.958129 1.99164 2.59337 + vertex 0.953318 1.98656 2.59341 + endloop + endfacet + facet normal -0.254238 0.291253 0.922244 + outer loop + vertex 0.952766 1.98163 2.59482 + vertex 0.958344 1.98668 2.59476 + vertex 0.953318 1.98656 2.59341 + endloop + endfacet + facet normal -0.292915 0.333704 0.896015 + outer loop + vertex 0.956536 1.98248 2.59573 + vertex 0.958344 1.98668 2.59476 + vertex 0.952766 1.98163 2.59482 + endloop + endfacet + facet normal -0.29431 0.344967 0.89128 + outer loop + vertex 0.956536 1.98248 2.59573 + vertex 0.952766 1.98163 2.59482 + vertex 0.954176 1.9797 2.59603 + endloop + endfacet + facet normal -0.177786 0.252529 0.951116 + outer loop + vertex 0.954176 1.9797 2.59603 + vertex 0.957276 1.98001 2.59653 + vertex 0.956536 1.98248 2.59573 + endloop + endfacet + facet normal -0.135709 0.266144 0.954332 + outer loop + vertex 0.960513 1.98387 2.59591 + vertex 0.956536 1.98248 2.59573 + vertex 0.957276 1.98001 2.59653 + endloop + endfacet + facet normal -0.176195 0.224764 0.958351 + outer loop + vertex 0.954176 1.9797 2.59603 + vertex 0.953234 1.9761 2.5967 + vertex 0.957276 1.98001 2.59653 + endloop + endfacet + facet normal -0.14046 0.280395 0.949552 + outer loop + vertex 0.956536 1.98248 2.59573 + vertex 0.960513 1.98387 2.59591 + vertex 0.958344 1.98668 2.59476 + endloop + endfacet + facet normal -0.113629 0.233171 0.965774 + outer loop + vertex 0.964212 1.98809 2.59511 + vertex 0.963381 1.99212 2.59404 + vertex 0.958344 1.98668 2.59476 + endloop + endfacet + facet normal -0.126471 0.290723 0.948412 + outer loop + vertex 0.958344 1.98668 2.59476 + vertex 0.960513 1.98387 2.59591 + vertex 0.964212 1.98809 2.59511 + endloop + endfacet + facet normal -0.0513087 0.246549 0.967771 + outer loop + vertex 0.964212 1.98809 2.59511 + vertex 0.968635 1.99251 2.59422 + vertex 0.963381 1.99212 2.59404 + endloop + endfacet + facet normal -0.0498309 0.224147 0.973281 + outer loop + vertex 0.968635 1.99251 2.59422 + vertex 0.968049 1.99686 2.59319 + vertex 0.963381 1.99212 2.59404 + endloop + endfacet + facet normal -0.145471 0.274187 0.95061 + outer loop + vertex 0.965219 2.00466 2.59112 + vertex 0.960814 2.00369 2.59072 + vertex 0.962051 2.0006 2.5918 + endloop + endfacet + facet normal -0.145935 0.276602 0.949839 + outer loop + vertex 0.960814 2.00369 2.59072 + vertex 0.965219 2.00466 2.59112 + vertex 0.964014 2.00788 2.58999 + endloop + endfacet + facet normal -0.0475854 0.274146 0.96051 + outer loop + vertex 0.968505 2.00837 2.59039 + vertex 0.973413 2.01179 2.58966 + vertex 0.968263 2.01223 2.58928 + endloop + endfacet + facet normal -0.0507349 0.243929 0.968465 + outer loop + vertex 0.973413 2.01179 2.58966 + vertex 0.972704 2.01659 2.58841 + vertex 0.968263 2.01223 2.58928 + endloop + endfacet + facet normal -0.0725328 0.264734 0.96159 + outer loop + vertex 0.968263 2.01223 2.58928 + vertex 0.972704 2.01659 2.58841 + vertex 0.967771 2.01654 2.58805 + endloop + endfacet + facet normal -0.138943 0.255758 0.956704 + outer loop + vertex 0.968263 2.01223 2.58928 + vertex 0.967771 2.01654 2.58805 + vertex 0.963264 2.01184 2.58865 + endloop + endfacet + facet normal -0.171547 0.267125 0.94827 + outer loop + vertex 0.963015 2.01613 2.58741 + vertex 0.966931 2.02043 2.5869 + vertex 0.962699 2.01969 2.58635 + endloop + endfacet + facet normal -0.172447 0.273731 0.94622 + outer loop + vertex 0.966931 2.02043 2.5869 + vertex 0.965623 2.02357 2.58576 + vertex 0.962699 2.01969 2.58635 + endloop + endfacet + facet normal -0.07267 0.246615 0.966385 + outer loop + vertex 0.972704 2.01659 2.58841 + vertex 0.97225 2.02133 2.58717 + vertex 0.967771 2.01654 2.58805 + endloop + endfacet + facet normal -0.143128 0.286363 0.94737 + outer loop + vertex 0.970225 2.02461 2.58614 + vertex 0.965623 2.02357 2.58576 + vertex 0.966931 2.02043 2.5869 + endloop + endfacet + facet normal -0.142139 0.28134 0.949023 + outer loop + vertex 0.965623 2.02357 2.58576 + vertex 0.970225 2.02461 2.58614 + vertex 0.969028 2.02788 2.58499 + endloop + endfacet + facet normal -0.0336378 0.2781 0.959963 + outer loop + vertex 0.973693 2.02827 2.58539 + vertex 0.979088 2.03149 2.58465 + vertex 0.973427 2.03217 2.58425 + endloop + endfacet + facet normal -0.0388708 0.239882 0.970024 + outer loop + vertex 0.979088 2.03149 2.58465 + vertex 0.977875 2.03651 2.58336 + vertex 0.973427 2.03217 2.58425 + endloop + endfacet + facet normal -0.06321 0.263291 0.962643 + outer loop + vertex 0.973427 2.03217 2.58425 + vertex 0.977875 2.03651 2.58336 + vertex 0.972822 2.03649 2.58303 + endloop + endfacet + facet normal -0.163132 0.267946 0.949522 + outer loop + vertex 0.968029 2.03608 2.58241 + vertex 0.972 2.04037 2.58188 + vertex 0.967799 2.03961 2.58138 + endloop + endfacet + facet normal -0.16533 0.283212 0.944699 + outer loop + vertex 0.972 2.04037 2.58188 + vertex 0.970724 2.04346 2.58073 + vertex 0.967799 2.03961 2.58138 + endloop + endfacet + facet normal -0.0634595 0.246189 0.967142 + outer loop + vertex 0.977875 2.03651 2.58336 + vertex 0.977331 2.04127 2.58211 + vertex 0.972822 2.03649 2.58303 + endloop + endfacet + facet normal -0.138225 0.294734 0.945529 + outer loop + vertex 0.97533 2.04454 2.58107 + vertex 0.970724 2.04346 2.58073 + vertex 0.972 2.04037 2.58188 + endloop + endfacet + facet normal -0.239633 0.314555 0.918494 + outer loop + vertex 0.96839 2.04611 2.57913 + vertex 0.973109 2.05163 2.57847 + vertex 0.967794 2.05106 2.57728 + endloop + endfacet + facet normal -0.102693 0.292941 0.9506 + outer loop + vertex 0.978784 2.04823 2.58024 + vertex 0.978384 2.05203 2.57903 + vertex 0.974084 2.04776 2.57988 + endloop + endfacet + facet normal -0.138595 0.284908 0.948482 + outer loop + vertex 0.973109 2.05163 2.57847 + vertex 0.977597 2.0562 2.57775 + vertex 0.972643 2.05619 2.57703 + endloop + endfacet + facet normal -0.139441 0.262907 0.954692 + outer loop + vertex 0.972643 2.05619 2.57703 + vertex 0.977597 2.0562 2.57775 + vertex 0.977125 2.06003 2.57663 + endloop + endfacet + facet normal -0.136224 0.2593 0.956142 + outer loop + vertex 0.974012 2.06015 2.57615 + vertex 0.972643 2.05619 2.57703 + vertex 0.977125 2.06003 2.57663 + endloop + endfacet + facet normal -0.133981 0.287191 0.948457 + outer loop + vertex 0.974012 2.06015 2.57615 + vertex 0.977125 2.06003 2.57663 + vertex 0.976596 2.06277 2.57573 + endloop + endfacet + facet normal -0.211406 0.357175 0.909799 + outer loop + vertex 0.976596 2.06277 2.57573 + vertex 0.973428 2.06264 2.57504 + vertex 0.974012 2.06015 2.57615 + endloop + endfacet + facet normal -0.211146 0.363213 0.907465 + outer loop + vertex 0.976596 2.06277 2.57573 + vertex 0.978259 2.06669 2.57454 + vertex 0.973428 2.06264 2.57504 + endloop + endfacet + facet normal -0.211847 0.363991 0.90699 + outer loop + vertex 0.973428 2.06264 2.57504 + vertex 0.978259 2.06669 2.57454 + vertex 0.973088 2.06631 2.57349 + endloop + endfacet + facet normal -0.211792 0.300391 0.930005 + outer loop + vertex 0.978259 2.06669 2.57454 + vertex 0.977655 2.07105 2.573 + vertex 0.973088 2.06631 2.57349 + endloop + endfacet + facet normal -0.0950007 0.324174 0.941215 + outer loop + vertex 0.976596 2.06277 2.57573 + vertex 0.980486 2.06377 2.57577 + vertex 0.978259 2.06669 2.57454 + endloop + endfacet + facet normal -0.0880504 0.296846 0.950857 + outer loop + vertex 0.980486 2.06377 2.57577 + vertex 0.976596 2.06277 2.57573 + vertex 0.977125 2.06003 2.57663 + endloop + endfacet + facet normal -0.121384 0.31673 0.940717 + outer loop + vertex 0.978259 2.06669 2.57454 + vertex 0.982844 2.07176 2.57343 + vertex 0.977655 2.07105 2.573 + endloop + endfacet + facet normal -0.117476 0.281013 0.952487 + outer loop + vertex 0.982844 2.07176 2.57343 + vertex 0.981797 2.07561 2.57216 + vertex 0.977655 2.07105 2.573 + endloop + endfacet + facet normal -0.141229 0.300899 0.943141 + outer loop + vertex 0.977655 2.07105 2.573 + vertex 0.981797 2.07561 2.57216 + vertex 0.97722 2.07474 2.57175 + endloop + endfacet + facet normal -0.140763 0.297971 0.944139 + outer loop + vertex 0.981797 2.07561 2.57216 + vertex 0.98052 2.07882 2.57096 + vertex 0.97722 2.07474 2.57175 + endloop + endfacet + facet normal -0.00250219 0.264761 0.964311 + outer loop + vertex 0.989308 2.06794 2.57467 + vertex 0.988008 2.072 2.57355 + vertex 0.984047 2.06786 2.57468 + endloop + endfacet + facet normal -0.0629871 0.296044 0.953095 + outer loop + vertex 0.982844 2.07176 2.57343 + vertex 0.98728 2.07648 2.57225 + vertex 0.981797 2.07561 2.57216 + endloop + endfacet + facet normal -0.0600366 0.27696 0.959004 + outer loop + vertex 0.98728 2.07648 2.57225 + vertex 0.985239 2.07979 2.57117 + vertex 0.981797 2.07561 2.57216 + endloop + endfacet + facet normal -0.106425 0.311634 0.944223 + outer loop + vertex 0.985239 2.07979 2.57117 + vertex 0.98052 2.07882 2.57096 + vertex 0.981797 2.07561 2.57216 + endloop + endfacet + facet normal -0.106294 0.310939 0.944467 + outer loop + vertex 0.98052 2.07882 2.57096 + vertex 0.985239 2.07979 2.57117 + vertex 0.984067 2.08302 2.56998 + endloop + endfacet + facet normal -0.185968 0.370259 0.910123 + outer loop + vertex 0.978318 2.08149 2.56942 + vertex 0.98052 2.07882 2.57096 + vertex 0.984067 2.08302 2.56998 + endloop + endfacet + facet normal -0.172135 0.309269 0.935266 + outer loop + vertex 0.984067 2.08302 2.56998 + vertex 0.98325 2.08673 2.5686 + vertex 0.978318 2.08149 2.56942 + endloop + endfacet + facet normal -0.0945268 0.328101 0.939901 + outer loop + vertex 0.984067 2.08302 2.56998 + vertex 0.988395 2.08701 2.56902 + vertex 0.98325 2.08673 2.5686 + endloop + endfacet + facet normal -0.0937153 0.298102 0.949922 + outer loop + vertex 0.988395 2.08701 2.56902 + vertex 0.98774 2.09098 2.56771 + vertex 0.98325 2.08673 2.5686 + endloop + endfacet + facet normal -0.114094 0.317788 0.941272 + outer loop + vertex 0.98325 2.08673 2.5686 + vertex 0.98774 2.09098 2.56771 + vertex 0.982725 2.09101 2.56709 + endloop + endfacet + facet normal -0.204399 0.303033 0.930802 + outer loop + vertex 0.98325 2.08673 2.5686 + vertex 0.982725 2.09101 2.56709 + vertex 0.978215 2.08616 2.56768 + endloop + endfacet + facet normal -0.206048 0.338496 0.918131 + outer loop + vertex 0.978318 2.08149 2.56942 + vertex 0.98325 2.08673 2.5686 + vertex 0.978215 2.08616 2.56768 + endloop + endfacet + facet normal -0.228562 0.323976 0.918041 + outer loop + vertex 0.978215 2.08616 2.56768 + vertex 0.982725 2.09101 2.56709 + vertex 0.977838 2.08988 2.56627 + endloop + endfacet + facet normal -0.225385 0.304918 0.925325 + outer loop + vertex 0.982725 2.09101 2.56709 + vertex 0.980607 2.09354 2.56574 + vertex 0.977838 2.08988 2.56627 + endloop + endfacet + facet normal -0.115102 0.295146 0.948494 + outer loop + vertex 0.982725 2.09101 2.56709 + vertex 0.98774 2.09098 2.56771 + vertex 0.987345 2.09469 2.5665 + endloop + endfacet + facet normal -0.113951 0.293791 0.949053 + outer loop + vertex 0.984159 2.09483 2.56608 + vertex 0.982725 2.09101 2.56709 + vertex 0.987345 2.09469 2.5665 + endloop + endfacet + facet normal -0.205072 0.321443 0.924457 + outer loop + vertex 0.984159 2.09483 2.56608 + vertex 0.980607 2.09354 2.56574 + vertex 0.982725 2.09101 2.56709 + endloop + endfacet + facet normal -0.216602 0.35728 0.908534 + outer loop + vertex 0.980607 2.09354 2.56574 + vertex 0.984159 2.09483 2.56608 + vertex 0.983492 2.09737 2.56492 + endloop + endfacet + facet normal -0.171969 0.370877 0.912621 + outer loop + vertex 0.98677 2.09741 2.56552 + vertex 0.983492 2.09737 2.56492 + vertex 0.984159 2.09483 2.56608 + endloop + endfacet + facet normal -0.172228 0.366618 0.914291 + outer loop + vertex 0.98677 2.09741 2.56552 + vertex 0.988254 2.10137 2.56421 + vertex 0.983492 2.09737 2.56492 + endloop + endfacet + facet normal -0.187577 0.38316 0.904436 + outer loop + vertex 0.983492 2.09737 2.56492 + vertex 0.988254 2.10137 2.56421 + vertex 0.982917 2.101 2.56326 + endloop + endfacet + facet normal -0.187431 0.311974 0.931419 + outer loop + vertex 0.988254 2.10137 2.56421 + vertex 0.987375 2.10618 2.56243 + vertex 0.982917 2.101 2.56326 + endloop + endfacet + facet normal -0.114921 0.327625 0.937793 + outer loop + vertex 0.988254 2.10137 2.56421 + vertex 0.992707 2.10633 2.56303 + vertex 0.987375 2.10618 2.56243 + endloop + endfacet + facet normal -0.115292 0.276195 0.954162 + outer loop + vertex 0.987375 2.10618 2.56243 + vertex 0.992707 2.10633 2.56303 + vertex 0.992026 2.11022 2.56182 + endloop + endfacet + facet normal -0.122976 0.284524 0.950748 + outer loop + vertex 0.988815 2.11036 2.56136 + vertex 0.987375 2.10618 2.56243 + vertex 0.992026 2.11022 2.56182 + endloop + endfacet + facet normal -0.121344 0.303464 0.945085 + outer loop + vertex 0.988815 2.11036 2.56136 + vertex 0.992026 2.11022 2.56182 + vertex 0.991464 2.11298 2.56086 + endloop + endfacet + facet normal -0.197237 0.372713 0.906743 + outer loop + vertex 0.991464 2.11298 2.56086 + vertex 0.988242 2.11284 2.56022 + vertex 0.988815 2.11036 2.56136 + endloop + endfacet + facet normal -0.0678533 0.314893 0.946699 + outer loop + vertex 0.995316 2.11385 2.56085 + vertex 0.991464 2.11298 2.56086 + vertex 0.992026 2.11022 2.56182 + endloop + endfacet + facet normal -0.0451306 0.296285 0.954033 + outer loop + vertex 0.996642 2.11042 2.56198 + vertex 0.995316 2.11385 2.56085 + vertex 0.992026 2.11022 2.56182 + endloop + endfacet + facet normal -0.00740286 0.309779 0.95078 + outer loop + vertex 1.00021 2.11409 2.56081 + vertex 0.995316 2.11385 2.56085 + vertex 0.996642 2.11042 2.56198 + endloop + endfacet + facet normal -0.00991753 0.358202 0.933591 + outer loop + vertex 0.995316 2.11385 2.56085 + vertex 1.00021 2.11409 2.56081 + vertex 0.998538 2.11743 2.55951 + endloop + endfacet + facet normal -0.0680807 0.402732 0.912782 + outer loop + vertex 0.992911 2.11655 2.55948 + vertex 0.995316 2.11385 2.56085 + vertex 0.998538 2.11743 2.55951 + endloop + endfacet + facet normal -0.0848508 0.389888 0.916945 + outer loop + vertex 0.991464 2.11298 2.56086 + vertex 0.995316 2.11385 2.56085 + vertex 0.992911 2.11655 2.55948 + endloop + endfacet + facet normal -0.195148 0.422336 0.885183 + outer loop + vertex 0.991464 2.11298 2.56086 + vertex 0.992911 2.11655 2.55948 + vertex 0.988242 2.11284 2.56022 + endloop + endfacet + facet normal -0.191117 0.417858 0.888183 + outer loop + vertex 0.988242 2.11284 2.56022 + vertex 0.992911 2.11655 2.55948 + vertex 0.987857 2.11626 2.55852 + endloop + endfacet + facet normal -0.190381 0.439398 0.877887 + outer loop + vertex 0.992911 2.11655 2.55948 + vertex 0.991667 2.12032 2.55732 + vertex 0.987857 2.11626 2.55852 + endloop + endfacet + facet normal -0.206048 0.451268 0.868275 + outer loop + vertex 0.987857 2.11626 2.55852 + vertex 0.991667 2.12032 2.55732 + vertex 0.987178 2.11986 2.55649 + endloop + endfacet + facet normal -0.0448981 0.289147 0.956231 + outer loop + vertex 0.992707 2.10633 2.56303 + vertex 0.996642 2.11042 2.56198 + vertex 0.992026 2.11022 2.56182 + endloop + endfacet + facet normal -0.0766588 0.338589 0.937806 + outer loop + vertex 0.98677 2.09741 2.56552 + vertex 0.990665 2.09833 2.56551 + vertex 0.988254 2.10137 2.56421 + endloop + endfacet + facet normal -0.0456893 0.303591 0.951706 + outer loop + vertex 0.98774 2.09098 2.56771 + vertex 0.991869 2.09478 2.56669 + vertex 0.987345 2.09469 2.5665 + endloop + endfacet + facet normal -0.036213 0.294176 0.955065 + outer loop + vertex 0.992652 2.09079 2.56795 + vertex 0.991869 2.09478 2.56669 + vertex 0.98774 2.09098 2.56771 + endloop + endfacet + facet normal -0.0354538 0.307961 0.950738 + outer loop + vertex 0.988395 2.08701 2.56902 + vertex 0.992652 2.09079 2.56795 + vertex 0.98774 2.09098 2.56771 + endloop + endfacet + facet normal -0.0153521 0.287306 0.957716 + outer loop + vertex 0.993843 2.0862 2.56935 + vertex 0.992652 2.09079 2.56795 + vertex 0.988395 2.08701 2.56902 + endloop + endfacet + facet normal -0.0108631 0.314224 0.949287 + outer loop + vertex 0.988716 2.08334 2.57024 + vertex 0.993843 2.0862 2.56935 + vertex 0.988395 2.08701 2.56902 + endloop + endfacet + facet normal -0.0135854 0.31863 0.947782 + outer loop + vertex 0.99174 2.08254 2.57055 + vertex 0.993843 2.0862 2.56935 + vertex 0.988716 2.08334 2.57024 + endloop + endfacet + facet normal -0.0186302 0.301645 0.953238 + outer loop + vertex 0.99174 2.08254 2.57055 + vertex 0.988716 2.08334 2.57024 + vertex 0.989075 2.08045 2.57116 + endloop + endfacet + facet normal 0.00767618 0.270791 0.962608 + outer loop + vertex 0.989075 2.08045 2.57116 + vertex 0.99245 2.07929 2.57146 + vertex 0.99174 2.08254 2.57055 + endloop + endfacet + facet normal 0.029828 0.27516 0.960936 + outer loop + vertex 0.994696 2.0826 2.57044 + vertex 0.99174 2.08254 2.57055 + vertex 0.99245 2.07929 2.57146 + endloop + endfacet + facet normal 0.00517167 0.264031 0.9645 + outer loop + vertex 0.989075 2.08045 2.57116 + vertex 0.98728 2.07648 2.57225 + vertex 0.99245 2.07929 2.57146 + endloop + endfacet + facet normal -0.0481091 0.298013 0.953349 + outer loop + vertex 0.985239 2.07979 2.57117 + vertex 0.989075 2.08045 2.57116 + vertex 0.988716 2.08334 2.57024 + endloop + endfacet + facet normal 0.0291659 0.296322 0.954643 + outer loop + vertex 0.99174 2.08254 2.57055 + vertex 0.994696 2.0826 2.57044 + vertex 0.993843 2.0862 2.56935 + endloop + endfacet + facet normal -0.0744568 0.308346 0.948356 + outer loop + vertex 0.988716 2.08334 2.57024 + vertex 0.988395 2.08701 2.56902 + vertex 0.984067 2.08302 2.56998 + endloop + endfacet + facet normal -0.0751291 0.321986 0.943759 + outer loop + vertex 0.984067 2.08302 2.56998 + vertex 0.985239 2.07979 2.57117 + vertex 0.988716 2.08334 2.57024 + endloop + endfacet + facet normal -0.0458835 0.285165 0.95738 + outer loop + vertex 0.989075 2.08045 2.57116 + vertex 0.985239 2.07979 2.57117 + vertex 0.98728 2.07648 2.57225 + endloop + endfacet + facet normal 0.0835266 0.262025 0.96144 + outer loop + vertex 0.992019 2.05955 2.57681 + vertex 0.9917 2.05563 2.57791 + vertex 0.996188 2.05655 2.57726 + endloop + endfacet + facet normal 0.078392 0.255216 0.963701 + outer loop + vertex 0.996442 2.0607 2.57615 + vertex 0.992019 2.05955 2.57681 + vertex 0.996188 2.05655 2.57726 + endloop + endfacet + facet normal 0.0946644 0.253915 0.962583 + outer loop + vertex 0.996442 2.0607 2.57615 + vertex 0.996188 2.05655 2.57726 + vertex 1.00044 2.05985 2.57598 + endloop + endfacet + facet normal 0.0935724 0.248521 0.964096 + outer loop + vertex 1.00044 2.05985 2.57598 + vertex 0.998979 2.06425 2.57498 + vertex 0.996442 2.0607 2.57615 + endloop + endfacet + facet normal 0.0860643 0.253682 0.963451 + outer loop + vertex 0.994552 2.06317 2.57566 + vertex 0.996442 2.0607 2.57615 + vertex 0.998979 2.06425 2.57498 + endloop + endfacet + facet normal 0.0860703 0.253661 0.963456 + outer loop + vertex 0.994552 2.06317 2.57566 + vertex 0.998979 2.06425 2.57498 + vertex 0.994811 2.06729 2.57456 + endloop + endfacet + facet normal 0.0804776 0.246327 0.96584 + outer loop + vertex 0.994811 2.06729 2.57456 + vertex 0.998979 2.06425 2.57498 + vertex 0.999334 2.06821 2.57395 + endloop + endfacet + facet normal 0.0803491 0.246874 0.965711 + outer loop + vertex 0.999334 2.06821 2.57395 + vertex 0.99791 2.07152 2.57322 + vertex 0.994811 2.06729 2.57456 + endloop + endfacet + facet normal 0.0664624 0.256568 0.964238 + outer loop + vertex 0.994811 2.06729 2.57456 + vertex 0.99791 2.07152 2.57322 + vertex 0.992999 2.07181 2.57348 + endloop + endfacet + facet normal 0.0663271 0.253442 0.965074 + outer loop + vertex 0.99791 2.07152 2.57322 + vertex 0.996305 2.07617 2.57211 + vertex 0.992999 2.07181 2.57348 + endloop + endfacet + facet normal 0.0490614 0.265788 0.962782 + outer loop + vertex 0.992999 2.07181 2.57348 + vertex 0.996305 2.07617 2.57211 + vertex 0.991441 2.07529 2.5726 + endloop + endfacet + facet normal 0.0498514 0.261979 0.963785 + outer loop + vertex 0.99245 2.07929 2.57146 + vertex 0.991441 2.07529 2.5726 + vertex 0.996305 2.07617 2.57211 + endloop + endfacet + facet normal 0.0471578 0.258846 0.964767 + outer loop + vertex 0.996583 2.08039 2.57096 + vertex 0.99245 2.07929 2.57146 + vertex 0.996305 2.07617 2.57211 + endloop + endfacet + facet normal 0.0804448 0.256246 0.963258 + outer loop + vertex 0.996583 2.08039 2.57096 + vertex 0.996305 2.07617 2.57211 + vertex 1.00053 2.07943 2.57089 + endloop + endfacet + facet normal 0.0838615 0.270493 0.959063 + outer loop + vertex 1.00053 2.07943 2.57089 + vertex 0.998904 2.08386 2.56978 + vertex 0.996583 2.08039 2.57096 + endloop + endfacet + facet normal 0.0915121 0.272957 0.957664 + outer loop + vertex 0.998904 2.08386 2.56978 + vertex 1.00053 2.07943 2.57089 + vertex 1.00476 2.08256 2.56959 + endloop + endfacet + facet normal 0.0901638 0.266576 0.959587 + outer loop + vertex 1.00476 2.08256 2.56959 + vertex 1.00308 2.08722 2.56845 + vertex 0.998904 2.08386 2.56978 + endloop + endfacet + facet normal 0.0822253 0.275688 0.957724 + outer loop + vertex 0.998904 2.08386 2.56978 + vertex 1.00308 2.08722 2.56845 + vertex 0.998804 2.08796 2.56861 + endloop + endfacet + facet normal 0.045744 0.275512 0.960209 + outer loop + vertex 0.993843 2.0862 2.56935 + vertex 0.998904 2.08386 2.56978 + vertex 0.998804 2.08796 2.56861 + endloop + endfacet + facet normal 0.0452431 0.276781 0.959867 + outer loop + vertex 0.998804 2.08796 2.56861 + vertex 0.996768 2.09033 2.56802 + vertex 0.993843 2.0862 2.56935 + endloop + endfacet + facet normal 0.0173559 0.295066 0.955319 + outer loop + vertex 0.993843 2.0862 2.56935 + vertex 0.996768 2.09033 2.56802 + vertex 0.992652 2.09079 2.56795 + endloop + endfacet + facet normal 0.0172091 0.293805 0.955711 + outer loop + vertex 0.996768 2.09033 2.56802 + vertex 0.997046 2.09438 2.56677 + vertex 0.992652 2.09079 2.56795 + endloop + endfacet + facet normal 0.0589253 0.302372 0.951367 + outer loop + vertex 0.994696 2.0826 2.57044 + vertex 0.998904 2.08386 2.56978 + vertex 0.993843 2.0862 2.56935 + endloop + endfacet + facet normal 0.065991 0.28183 0.957192 + outer loop + vertex 0.994696 2.0826 2.57044 + vertex 0.996583 2.08039 2.57096 + vertex 0.998904 2.08386 2.56978 + endloop + endfacet + facet normal 0.0451927 0.265405 0.963077 + outer loop + vertex 0.996583 2.08039 2.57096 + vertex 0.994696 2.0826 2.57044 + vertex 0.99245 2.07929 2.57146 + endloop + endfacet + facet normal 0.0823243 0.2763 0.957539 + outer loop + vertex 1.00308 2.08722 2.56845 + vertex 1.00134 2.09165 2.56732 + vertex 0.998804 2.08796 2.56861 + endloop + endfacet + facet normal 0.0616326 0.289679 0.955137 + outer loop + vertex 0.998804 2.08796 2.56861 + vertex 1.00134 2.09165 2.56732 + vertex 0.996768 2.09033 2.56802 + endloop + endfacet + facet normal 0.0613542 0.290519 0.9549 + outer loop + vertex 0.997046 2.09438 2.56677 + vertex 0.996768 2.09033 2.56802 + vertex 1.00134 2.09165 2.56732 + endloop + endfacet + facet normal 0.0540108 0.279704 0.958566 + outer loop + vertex 1.00146 2.09568 2.56614 + vertex 0.997046 2.09438 2.56677 + vertex 1.00134 2.09165 2.56732 + endloop + endfacet + facet normal 0.0876083 0.278078 0.956555 + outer loop + vertex 1.00146 2.09568 2.56614 + vertex 1.00134 2.09165 2.56732 + vertex 1.00547 2.09487 2.56601 + endloop + endfacet + facet normal 0.0870088 0.274957 0.957511 + outer loop + vertex 1.00547 2.09487 2.56601 + vertex 1.00396 2.09921 2.5649 + vertex 1.00146 2.09568 2.56614 + endloop + endfacet + facet normal 0.0681372 0.287537 0.955343 + outer loop + vertex 0.999545 2.09804 2.56557 + vertex 1.00146 2.09568 2.56614 + vertex 1.00396 2.09921 2.5649 + endloop + endfacet + facet normal 0.0686598 0.285833 0.955817 + outer loop + vertex 0.999545 2.09804 2.56557 + vertex 1.00396 2.09921 2.5649 + vertex 0.999765 2.10208 2.56434 + endloop + endfacet + facet normal 0.0986407 0.278473 0.955365 + outer loop + vertex 1.00396 2.09921 2.5649 + vertex 1.00547 2.09487 2.56601 + vertex 1.00917 2.09814 2.56468 + endloop + endfacet + facet normal 0.0956185 0.262852 0.960087 + outer loop + vertex 1.00917 2.09814 2.56468 + vertex 1.00806 2.10233 2.56364 + vertex 1.00396 2.09921 2.5649 + endloop + endfacet + facet normal 0.0925926 0.266533 0.959368 + outer loop + vertex 1.00396 2.09921 2.5649 + vertex 1.00806 2.10233 2.56364 + vertex 1.00431 2.10315 2.56377 + endloop + endfacet + facet normal 0.0572221 0.27016 0.961114 + outer loop + vertex 0.999765 2.10208 2.56434 + vertex 1.00396 2.09921 2.5649 + vertex 1.00431 2.10315 2.56377 + endloop + endfacet + facet normal 0.0592486 0.262603 0.963083 + outer loop + vertex 1.00431 2.10315 2.56377 + vertex 1.00293 2.1063 2.563 + vertex 0.999765 2.10208 2.56434 + endloop + endfacet + facet normal 0.0340929 0.280254 0.95932 + outer loop + vertex 0.999765 2.10208 2.56434 + vertex 1.00293 2.1063 2.563 + vertex 0.997972 2.10646 2.56313 + endloop + endfacet + facet normal 0.0761444 0.269258 0.960053 + outer loop + vertex 1.00431 2.10315 2.56377 + vertex 1.00674 2.10559 2.5629 + vertex 1.00293 2.1063 2.563 + endloop + endfacet + facet normal 0.0903904 0.255926 0.962461 + outer loop + vertex 1.00806 2.10233 2.56364 + vertex 1.00674 2.10559 2.5629 + vertex 1.00431 2.10315 2.56377 + endloop + endfacet + facet normal 0.103647 0.260703 0.959839 + outer loop + vertex 1.00806 2.10233 2.56364 + vertex 1.0112 2.10628 2.56222 + vertex 1.00674 2.10559 2.5629 + endloop + endfacet + facet normal 0.109917 0.255915 0.96043 + outer loop + vertex 1.01281 2.10152 2.56331 + vertex 1.0112 2.10628 2.56222 + vertex 1.00806 2.10233 2.56364 + endloop + endfacet + facet normal 0.121442 0.259278 0.958137 + outer loop + vertex 1.01281 2.10152 2.56331 + vertex 1.01693 2.10471 2.56193 + vertex 1.0112 2.10628 2.56222 + endloop + endfacet + facet normal 0.120927 0.257291 0.958738 + outer loop + vertex 1.01693 2.10471 2.56193 + vertex 1.01527 2.10936 2.56089 + vertex 1.0112 2.10628 2.56222 + endloop + endfacet + facet normal 0.123283 0.254379 0.959215 + outer loop + vertex 1.0113 2.11052 2.56109 + vertex 1.0112 2.10628 2.56222 + vertex 1.01527 2.10936 2.56089 + endloop + endfacet + facet normal 0.131434 0.283942 0.94979 + outer loop + vertex 1.01527 2.10936 2.56089 + vertex 1.01354 2.11377 2.55981 + vertex 1.0113 2.11052 2.56109 + endloop + endfacet + facet normal 0.120124 0.291414 0.949025 + outer loop + vertex 1.00928 2.11304 2.56057 + vertex 1.0113 2.11052 2.56109 + vertex 1.01354 2.11377 2.55981 + endloop + endfacet + facet normal 0.107573 0.346609 0.931821 + outer loop + vertex 1.00928 2.11304 2.56057 + vertex 1.01354 2.11377 2.55981 + vertex 1.00922 2.11679 2.55918 + endloop + endfacet + facet normal 0.0866472 0.347043 0.933838 + outer loop + vertex 1.00521 2.11375 2.56069 + vertex 1.00928 2.11304 2.56057 + vertex 1.00922 2.11679 2.55918 + endloop + endfacet + facet normal 0.0767668 0.358386 0.930412 + outer loop + vertex 1.00374 2.11745 2.55938 + vertex 1.00521 2.11375 2.56069 + vertex 1.00922 2.11679 2.55918 + endloop + endfacet + facet normal 0.0763187 0.284207 0.95572 + outer loop + vertex 1.00928 2.11304 2.56057 + vertex 1.00521 2.11375 2.56069 + vertex 1.00695 2.10954 2.5618 + endloop + endfacet + facet normal 0.0639837 0.279679 0.957959 + outer loop + vertex 1.00695 2.10954 2.5618 + vertex 1.00521 2.11375 2.56069 + vertex 1.00167 2.11028 2.56193 + endloop + endfacet + facet normal 0.0635653 0.27651 0.958907 + outer loop + vertex 1.00293 2.1063 2.563 + vertex 1.00695 2.10954 2.5618 + vertex 1.00167 2.11028 2.56193 + endloop + endfacet + facet normal 0.0338061 0.268139 0.962787 + outer loop + vertex 1.00293 2.1063 2.563 + vertex 1.00167 2.11028 2.56193 + vertex 0.997972 2.10646 2.56313 + endloop + endfacet + facet normal 0.0157735 0.284282 0.958611 + outer loop + vertex 0.997972 2.10646 2.56313 + vertex 1.00167 2.11028 2.56193 + vertex 0.996642 2.11042 2.56198 + endloop + endfacet + facet normal 0.0750723 0.263269 0.961797 + outer loop + vertex 1.00674 2.10559 2.5629 + vertex 1.00695 2.10954 2.5618 + vertex 1.00293 2.1063 2.563 + endloop + endfacet + facet normal 0.103566 0.26112 0.959734 + outer loop + vertex 1.00695 2.10954 2.5618 + vertex 1.00674 2.10559 2.5629 + vertex 1.0112 2.10628 2.56222 + endloop + endfacet + facet normal 0.108867 0.348295 0.931042 + outer loop + vertex 1.00922 2.11679 2.55918 + vertex 1.01354 2.11377 2.55981 + vertex 1.01367 2.11744 2.55842 + endloop + endfacet + facet normal 0.119754 0.347508 0.929999 + outer loop + vertex 1.01354 2.11377 2.55981 + vertex 1.01686 2.11608 2.55852 + vertex 1.01367 2.11744 2.55842 + endloop + endfacet + facet normal 0.09461 0.272661 0.957447 + outer loop + vertex 1.0113 2.11052 2.56109 + vertex 1.00928 2.11304 2.56057 + vertex 1.00695 2.10954 2.5618 + endloop + endfacet + facet normal 0.129455 0.283277 0.950261 + outer loop + vertex 1.01354 2.11377 2.55981 + vertex 1.01527 2.10936 2.56089 + vertex 1.01911 2.11235 2.55947 + endloop + endfacet + facet normal 0.138796 0.323501 0.935993 + outer loop + vertex 1.01911 2.11235 2.55947 + vertex 1.01686 2.11608 2.55852 + vertex 1.01354 2.11377 2.55981 + endloop + endfacet + facet normal 0.133021 0.279064 0.951015 + outer loop + vertex 1.01527 2.10936 2.56089 + vertex 1.01932 2.10818 2.56067 + vertex 1.01911 2.11235 2.55947 + endloop + endfacet + facet normal 0.126046 0.27899 0.951986 + outer loop + vertex 1.01932 2.10818 2.56067 + vertex 1.02379 2.10893 2.55985 + vertex 1.01911 2.11235 2.55947 + endloop + endfacet + facet normal 0.131902 0.286656 0.94891 + outer loop + vertex 1.01911 2.11235 2.55947 + vertex 1.02379 2.10893 2.55985 + vertex 1.02374 2.11314 2.55859 + endloop + endfacet + facet normal 0.121013 0.286937 0.950275 + outer loop + vertex 1.02379 2.10893 2.55985 + vertex 1.02796 2.11175 2.55847 + vertex 1.02374 2.11314 2.55859 + endloop + endfacet + facet normal 0.13477 0.330233 0.934229 + outer loop + vertex 1.02796 2.11175 2.55847 + vertex 1.02657 2.11577 2.55725 + vertex 1.02374 2.11314 2.55859 + endloop + endfacet + facet normal 0.128573 0.276757 0.9523 + outer loop + vertex 1.02953 2.10727 2.55956 + vertex 1.02796 2.11175 2.55847 + vertex 1.02379 2.10893 2.55985 + endloop + endfacet + facet normal 0.125293 0.264733 0.956147 + outer loop + vertex 1.02379 2.10893 2.55985 + vertex 1.0254 2.10434 2.56091 + vertex 1.02953 2.10727 2.55956 + endloop + endfacet + facet normal 0.125984 0.263831 0.956306 + outer loop + vertex 1.0254 2.10434 2.56091 + vertex 1.02943 2.10318 2.5607 + vertex 1.02953 2.10727 2.55956 + endloop + endfacet + facet normal 0.127707 0.270166 0.954307 + outer loop + vertex 1.02943 2.10318 2.5607 + vertex 1.0254 2.10434 2.56091 + vertex 1.02695 2.0998 2.56199 + endloop + endfacet + facet normal 0.123034 0.268813 0.955302 + outer loop + vertex 1.02695 2.0998 2.56199 + vertex 1.0254 2.10434 2.56091 + vertex 1.02134 2.10141 2.56226 + endloop + endfacet + facet normal 0.124462 0.274085 0.953618 + outer loop + vertex 1.02289 2.09688 2.56336 + vertex 1.02695 2.0998 2.56199 + vertex 1.02134 2.10141 2.56226 + endloop + endfacet + facet normal 0.118828 0.272449 0.954804 + outer loop + vertex 1.02289 2.09688 2.56336 + vertex 1.02134 2.10141 2.56226 + vertex 1.01888 2.09797 2.56355 + endloop + endfacet + facet normal 0.119728 0.275941 0.953689 + outer loop + vertex 1.01881 2.09388 2.56474 + vertex 1.02289 2.09688 2.56336 + vertex 1.01888 2.09797 2.56355 + endloop + endfacet + facet normal 0.117659 0.276044 0.953916 + outer loop + vertex 1.01446 2.097 2.56438 + vertex 1.01881 2.09388 2.56474 + vertex 1.01888 2.09797 2.56355 + endloop + endfacet + facet normal 0.119183 0.270315 0.955367 + outer loop + vertex 1.01888 2.09797 2.56355 + vertex 1.0169 2.10054 2.56307 + vertex 1.01446 2.097 2.56438 + endloop + endfacet + facet normal 0.120816 0.269227 0.955469 + outer loop + vertex 1.01446 2.097 2.56438 + vertex 1.0169 2.10054 2.56307 + vertex 1.01281 2.10152 2.56331 + endloop + endfacet + facet normal 0.116768 0.274855 0.954369 + outer loop + vertex 1.01435 2.09296 2.56555 + vertex 1.01881 2.09388 2.56474 + vertex 1.01446 2.097 2.56438 + endloop + endfacet + facet normal 0.116721 0.275041 0.954321 + outer loop + vertex 1.01435 2.09296 2.56555 + vertex 1.01631 2.09042 2.56605 + vertex 1.01881 2.09388 2.56474 + endloop + endfacet + facet normal 0.117447 0.274539 0.954377 + outer loop + vertex 1.02035 2.08935 2.56586 + vertex 1.01881 2.09388 2.56474 + vertex 1.01631 2.09042 2.56605 + endloop + endfacet + facet normal 0.116439 0.270486 0.955656 + outer loop + vertex 1.01631 2.09042 2.56605 + vertex 1.01615 2.08622 2.56725 + vertex 1.02035 2.08935 2.56586 + endloop + endfacet + facet normal 0.114192 0.270638 0.955884 + outer loop + vertex 1.01631 2.09042 2.56605 + vertex 1.01191 2.08945 2.56685 + vertex 1.01615 2.08622 2.56725 + endloop + endfacet + facet normal 0.118865 0.274948 0.954083 + outer loop + vertex 1.01881 2.09388 2.56474 + vertex 1.02035 2.08935 2.56586 + vertex 1.02445 2.09234 2.56448 + endloop + endfacet + facet normal 0.119271 0.274434 0.954181 + outer loop + vertex 1.02035 2.08935 2.56586 + vertex 1.02441 2.08825 2.56566 + vertex 1.02445 2.09234 2.56448 + endloop + endfacet + facet normal 0.122846 0.274282 0.953771 + outer loop + vertex 1.02441 2.08825 2.56566 + vertex 1.02889 2.08902 2.56487 + vertex 1.02445 2.09234 2.56448 + endloop + endfacet + facet normal 0.123303 0.272192 0.95431 + outer loop + vertex 1.02441 2.08825 2.56566 + vertex 1.02643 2.08562 2.56615 + vertex 1.02889 2.08902 2.56487 + endloop + endfacet + facet normal 0.125237 0.270843 0.954442 + outer loop + vertex 1.03048 2.08446 2.56595 + vertex 1.02889 2.08902 2.56487 + vertex 1.02643 2.08562 2.56615 + endloop + endfacet + facet normal 0.123965 0.266135 0.955931 + outer loop + vertex 1.02643 2.08562 2.56615 + vertex 1.02639 2.0815 2.56731 + vertex 1.03048 2.08446 2.56595 + endloop + endfacet + facet normal 0.125755 0.263846 0.956332 + outer loop + vertex 1.03204 2.07989 2.56701 + vertex 1.03048 2.08446 2.56595 + vertex 1.02639 2.0815 2.56731 + endloop + endfacet + facet normal 0.125125 0.261503 0.957058 + outer loop + vertex 1.02792 2.07692 2.56836 + vertex 1.03204 2.07989 2.56701 + vertex 1.02639 2.0815 2.56731 + endloop + endfacet + facet normal 0.125798 0.261696 0.956917 + outer loop + vertex 1.02792 2.07692 2.56836 + vertex 1.02639 2.0815 2.56731 + vertex 1.0239 2.07805 2.56858 + endloop + endfacet + facet normal 0.124863 0.258143 0.958004 + outer loop + vertex 1.0238 2.07393 2.5697 + vertex 1.02792 2.07692 2.56836 + vertex 1.0239 2.07805 2.56858 + endloop + endfacet + facet normal 0.120255 0.258403 0.958523 + outer loop + vertex 1.01947 2.07709 2.56939 + vertex 1.0238 2.07393 2.5697 + vertex 1.0239 2.07805 2.56858 + endloop + endfacet + facet normal 0.119283 0.262138 0.95763 + outer loop + vertex 1.0239 2.07805 2.56858 + vertex 1.02191 2.08062 2.56812 + vertex 1.01947 2.07709 2.56939 + endloop + endfacet + facet normal 0.116118 0.264247 0.957439 + outer loop + vertex 1.01947 2.07709 2.56939 + vertex 1.02191 2.08062 2.56812 + vertex 1.01779 2.08156 2.56836 + endloop + endfacet + facet normal 0.114311 0.263653 0.957821 + outer loop + vertex 1.01947 2.07709 2.56939 + vertex 1.01779 2.08156 2.56836 + vertex 1.01419 2.0782 2.56972 + endloop + endfacet + facet normal 0.113714 0.260535 0.958744 + outer loop + vertex 1.01419 2.0782 2.56972 + vertex 1.01534 2.07391 2.57074 + vertex 1.01947 2.07709 2.56939 + endloop + endfacet + facet normal 0.113861 0.260356 0.958775 + outer loop + vertex 1.01534 2.07391 2.57074 + vertex 1.01936 2.07304 2.5705 + vertex 1.01947 2.07709 2.56939 + endloop + endfacet + facet normal 0.112902 0.255533 0.960185 + outer loop + vertex 1.01936 2.07304 2.5705 + vertex 1.01534 2.07391 2.57074 + vertex 1.01688 2.06948 2.57174 + endloop + endfacet + facet normal 0.116416 0.253167 0.960392 + outer loop + vertex 1.02128 2.07047 2.57095 + vertex 1.01936 2.07304 2.5705 + vertex 1.01688 2.06948 2.57174 + endloop + endfacet + facet normal 0.122087 0.2571 0.958642 + outer loop + vertex 1.01936 2.07304 2.5705 + vertex 1.02128 2.07047 2.57095 + vertex 1.0238 2.07393 2.5697 + endloop + endfacet + facet normal 0.108705 0.254259 0.961008 + outer loop + vertex 1.01688 2.06948 2.57174 + vertex 1.01534 2.07391 2.57074 + vertex 1.01163 2.07051 2.57206 + endloop + endfacet + facet normal 0.108285 0.25192 0.961671 + outer loop + vertex 1.01281 2.06629 2.57304 + vertex 1.01688 2.06948 2.57174 + vertex 1.01163 2.07051 2.57206 + endloop + endfacet + facet normal 0.10218 0.250447 0.962723 + outer loop + vertex 1.01281 2.06629 2.57304 + vertex 1.01163 2.07051 2.57206 + vertex 1.00793 2.06685 2.57341 + endloop + endfacet + facet normal 0.102104 0.249626 0.962944 + outer loop + vertex 1.00964 2.0622 2.57443 + vertex 1.01281 2.06629 2.57304 + vertex 1.00793 2.06685 2.57341 + endloop + endfacet + facet normal 0.0979599 0.248274 0.963724 + outer loop + vertex 1.00964 2.0622 2.57443 + vertex 1.00793 2.06685 2.57341 + vertex 1.00421 2.06321 2.57473 + endloop + endfacet + facet normal 0.0983497 0.250549 0.963095 + outer loop + vertex 1.00421 2.06321 2.57473 + vertex 1.0053 2.05888 2.57574 + vertex 1.00964 2.0622 2.57443 + endloop + endfacet + facet normal 0.0961855 0.253189 0.962623 + outer loop + vertex 1.0053 2.05888 2.57574 + vertex 1.00935 2.05804 2.57556 + vertex 1.00964 2.0622 2.57443 + endloop + endfacet + facet normal 0.098705 0.252961 0.962428 + outer loop + vertex 1.00935 2.05804 2.57556 + vertex 1.01392 2.05904 2.57482 + vertex 1.00964 2.0622 2.57443 + endloop + endfacet + facet normal 0.0996663 0.254211 0.962 + outer loop + vertex 1.00964 2.0622 2.57443 + vertex 1.01392 2.05904 2.57482 + vertex 1.01419 2.06307 2.57373 + endloop + endfacet + facet normal 0.107489 0.253503 0.961344 + outer loop + vertex 1.01392 2.05904 2.57482 + vertex 1.01805 2.0622 2.57353 + vertex 1.01419 2.06307 2.57373 + endloop + endfacet + facet normal 0.107253 0.252379 0.961666 + outer loop + vertex 1.01805 2.0622 2.57353 + vertex 1.01661 2.06549 2.57283 + vertex 1.01419 2.06307 2.57373 + endloop + endfacet + facet normal 0.106421 0.253167 0.961551 + outer loop + vertex 1.01419 2.06307 2.57373 + vertex 1.01661 2.06549 2.57283 + vertex 1.01281 2.06629 2.57304 + endloop + endfacet + facet normal 0.115277 0.255501 0.959912 + outer loop + vertex 1.01805 2.0622 2.57353 + vertex 1.0211 2.06622 2.57209 + vertex 1.01661 2.06549 2.57283 + endloop + endfacet + facet normal 0.115759 0.253106 0.960488 + outer loop + vertex 1.01688 2.06948 2.57174 + vertex 1.01661 2.06549 2.57283 + vertex 1.0211 2.06622 2.57209 + endloop + endfacet + facet normal 0.116265 0.253735 0.960261 + outer loop + vertex 1.02128 2.07047 2.57095 + vertex 1.01688 2.06948 2.57174 + vertex 1.0211 2.06622 2.57209 + endloop + endfacet + facet normal 0.124309 0.253153 0.959407 + outer loop + vertex 1.02128 2.07047 2.57095 + vertex 1.0211 2.06622 2.57209 + vertex 1.02526 2.06933 2.57073 + endloop + endfacet + facet normal 0.124847 0.255155 0.958806 + outer loop + vertex 1.02526 2.06933 2.57073 + vertex 1.0238 2.07393 2.5697 + vertex 1.02128 2.07047 2.57095 + endloop + endfacet + facet normal 0.122551 0.255351 0.95905 + outer loop + vertex 1.02676 2.06467 2.57178 + vertex 1.02526 2.06933 2.57073 + vertex 1.0211 2.06622 2.57209 + endloop + endfacet + facet normal 0.123336 0.258397 0.958133 + outer loop + vertex 1.02276 2.0616 2.57313 + vertex 1.02676 2.06467 2.57178 + vertex 1.0211 2.06622 2.57209 + endloop + endfacet + facet normal 0.121149 0.261054 0.957692 + outer loop + vertex 1.02662 2.06059 2.57291 + vertex 1.02676 2.06467 2.57178 + vertex 1.02276 2.0616 2.57313 + endloop + endfacet + facet normal 0.121629 0.263003 0.957098 + outer loop + vertex 1.02428 2.05825 2.57385 + vertex 1.02662 2.06059 2.57291 + vertex 1.02276 2.0616 2.57313 + endloop + endfacet + facet normal 0.115029 0.260346 0.958639 + outer loop + vertex 1.02428 2.05825 2.57385 + vertex 1.02276 2.0616 2.57313 + vertex 1.01972 2.05762 2.57457 + endloop + endfacet + facet normal 0.11459 0.262816 0.958017 + outer loop + vertex 1.01972 2.05762 2.57457 + vertex 1.02411 2.05424 2.57497 + vertex 1.02428 2.05825 2.57385 + endloop + endfacet + facet normal 0.121071 0.262356 0.957346 + outer loop + vertex 1.02411 2.05424 2.57497 + vertex 1.02814 2.05725 2.57364 + vertex 1.02428 2.05825 2.57385 + endloop + endfacet + facet normal 0.121426 0.261915 0.957422 + outer loop + vertex 1.02984 2.05268 2.57467 + vertex 1.02814 2.05725 2.57364 + vertex 1.02411 2.05424 2.57497 + endloop + endfacet + facet normal 0.120094 0.256719 0.958996 + outer loop + vertex 1.02411 2.05424 2.57497 + vertex 1.02563 2.0496 2.57603 + vertex 1.02984 2.05268 2.57467 + endloop + endfacet + facet normal 0.120734 0.255903 0.959133 + outer loop + vertex 1.02563 2.0496 2.57603 + vertex 1.02967 2.04848 2.57581 + vertex 1.02984 2.05268 2.57467 + endloop + endfacet + facet normal 0.124023 0.255674 0.958775 + outer loop + vertex 1.02967 2.04848 2.57581 + vertex 1.03413 2.04928 2.57502 + vertex 1.02984 2.05268 2.57467 + endloop + endfacet + facet normal 0.125689 0.2577 0.958015 + outer loop + vertex 1.02984 2.05268 2.57467 + vertex 1.03413 2.04928 2.57502 + vertex 1.03432 2.05326 2.57393 + endloop + endfacet + facet normal 0.124785 0.262934 0.95671 + outer loop + vertex 1.03432 2.05326 2.57393 + vertex 1.03281 2.05659 2.57321 + vertex 1.02984 2.05268 2.57467 + endloop + endfacet + facet normal 0.127709 0.264111 0.956 + outer loop + vertex 1.03432 2.05326 2.57393 + vertex 1.03663 2.05558 2.57298 + vertex 1.03281 2.05659 2.57321 + endloop + endfacet + facet normal 0.129148 0.262745 0.956183 + outer loop + vertex 1.03813 2.05226 2.57369 + vertex 1.03663 2.05558 2.57298 + vertex 1.03432 2.05326 2.57393 + endloop + endfacet + facet normal 0.127881 0.25753 0.957771 + outer loop + vertex 1.03413 2.04928 2.57502 + vertex 1.03813 2.05226 2.57369 + vertex 1.03432 2.05326 2.57393 + endloop + endfacet + facet normal 0.126757 0.258934 0.957542 + outer loop + vertex 1.03978 2.04773 2.5747 + vertex 1.03813 2.05226 2.57369 + vertex 1.03413 2.04928 2.57502 + endloop + endfacet + facet normal 0.124439 0.249907 0.96024 + outer loop + vertex 1.03413 2.04928 2.57502 + vertex 1.03556 2.04469 2.57604 + vertex 1.03978 2.04773 2.5747 + endloop + endfacet + facet normal 0.124066 0.249808 0.960314 + outer loop + vertex 1.03556 2.04469 2.57604 + vertex 1.03413 2.04928 2.57502 + vertex 1.03157 2.0458 2.57626 + endloop + endfacet + facet normal 0.121515 0.240158 0.963098 + outer loop + vertex 1.03157 2.0458 2.57626 + vertex 1.0313 2.0415 2.57737 + vertex 1.03556 2.04469 2.57604 + endloop + endfacet + facet normal 0.1191 0.240377 0.963345 + outer loop + vertex 1.03157 2.0458 2.57626 + vertex 1.02708 2.04491 2.57704 + vertex 1.0313 2.0415 2.57737 + endloop + endfacet + facet normal 0.11628 0.236996 0.964527 + outer loop + vertex 1.02708 2.04491 2.57704 + vertex 1.0268 2.04076 2.57809 + vertex 1.0313 2.0415 2.57737 + endloop + endfacet + facet normal 0.116269 0.237048 0.964515 + outer loop + vertex 1.02808 2.03747 2.57875 + vertex 1.0313 2.0415 2.57737 + vertex 1.0268 2.04076 2.57809 + endloop + endfacet + facet normal 0.112231 0.235639 0.965339 + outer loop + vertex 1.02808 2.03747 2.57875 + vertex 1.0268 2.04076 2.57809 + vertex 1.02433 2.03832 2.57897 + endloop + endfacet + facet normal 0.112909 0.238863 0.964467 + outer loop + vertex 1.02394 2.03435 2.58 + vertex 1.02808 2.03747 2.57875 + vertex 1.02433 2.03832 2.57897 + endloop + endfacet + facet normal 0.108297 0.239423 0.964857 + outer loop + vertex 1.01974 2.03757 2.57968 + vertex 1.02394 2.03435 2.58 + vertex 1.02433 2.03832 2.57897 + endloop + endfacet + facet normal 0.109449 0.233624 0.966147 + outer loop + vertex 1.02433 2.03832 2.57897 + vertex 1.02295 2.04166 2.57832 + vertex 1.01974 2.03757 2.57968 + endloop + endfacet + facet normal 0.109318 0.233724 0.966138 + outer loop + vertex 1.01974 2.03757 2.57968 + vertex 1.02295 2.04166 2.57832 + vertex 1.01818 2.04221 2.57873 + endloop + endfacet + facet normal 0.109508 0.235781 0.965616 + outer loop + vertex 1.02295 2.04166 2.57832 + vertex 1.02134 2.04638 2.57735 + vertex 1.01818 2.04221 2.57873 + endloop + endfacet + facet normal 0.109836 0.23554 0.965638 + outer loop + vertex 1.01818 2.04221 2.57873 + vertex 1.02134 2.04638 2.57735 + vertex 1.01673 2.04563 2.57806 + endloop + endfacet + facet normal 0.104416 0.233467 0.966742 + outer loop + vertex 1.01818 2.04221 2.57873 + vertex 1.01673 2.04563 2.57806 + vertex 1.01425 2.04317 2.57892 + endloop + endfacet + facet normal 0.107905 0.245317 0.963419 + outer loop + vertex 1.01695 2.04982 2.57697 + vertex 1.01673 2.04563 2.57806 + vertex 1.02134 2.04638 2.57735 + endloop + endfacet + facet normal 0.107333 0.244614 0.963662 + outer loop + vertex 1.02154 2.05073 2.57623 + vertex 1.01695 2.04982 2.57697 + vertex 1.02134 2.04638 2.57735 + endloop + endfacet + facet normal 0.114913 0.244068 0.962926 + outer loop + vertex 1.02154 2.05073 2.57623 + vertex 1.02134 2.04638 2.57735 + vertex 1.02563 2.0496 2.57603 + endloop + endfacet + facet normal 0.105429 0.252677 0.961789 + outer loop + vertex 1.02154 2.05073 2.57623 + vertex 1.01955 2.05342 2.57574 + vertex 1.01695 2.04982 2.57697 + endloop + endfacet + facet normal 0.10229 0.254865 0.961551 + outer loop + vertex 1.01955 2.05342 2.57574 + vertex 1.01541 2.05448 2.5759 + vertex 1.01695 2.04982 2.57697 + endloop + endfacet + facet normal 0.0993614 0.254022 0.962081 + outer loop + vertex 1.01695 2.04982 2.57697 + vertex 1.01541 2.05448 2.5759 + vertex 1.01112 2.05125 2.57719 + endloop + endfacet + facet normal 0.0982778 0.249398 0.963401 + outer loop + vertex 1.01279 2.0466 2.57823 + vertex 1.01695 2.04982 2.57697 + vertex 1.01112 2.05125 2.57719 + endloop + endfacet + facet normal 0.0974796 0.256346 0.961657 + outer loop + vertex 1.01129 2.05549 2.57604 + vertex 1.01112 2.05125 2.57719 + vertex 1.01541 2.05448 2.5759 + endloop + endfacet + facet normal 0.097899 0.258132 0.961137 + outer loop + vertex 1.01541 2.05448 2.5759 + vertex 1.01392 2.05904 2.57482 + vertex 1.01129 2.05549 2.57604 + endloop + endfacet + facet normal 0.105696 0.260359 0.959709 + outer loop + vertex 1.01392 2.05904 2.57482 + vertex 1.01541 2.05448 2.5759 + vertex 1.01972 2.05762 2.57457 + endloop + endfacet + facet normal 0.0958204 0.25645 0.961796 + outer loop + vertex 1.01129 2.05549 2.57604 + vertex 1.00684 2.05445 2.57677 + vertex 1.01112 2.05125 2.57719 + endloop + endfacet + facet normal 0.0962885 0.25705 0.961589 + outer loop + vertex 1.00684 2.05445 2.57677 + vertex 1.00658 2.05047 2.57786 + vertex 1.01112 2.05125 2.57719 + endloop + endfacet + facet normal 0.0977543 0.24998 0.963304 + outer loop + vertex 1.00802 2.04716 2.57857 + vertex 1.01112 2.05125 2.57719 + vertex 1.00658 2.05047 2.57786 + endloop + endfacet + facet normal 0.0967655 0.257009 0.961552 + outer loop + vertex 1.00658 2.05047 2.57786 + vertex 1.00684 2.05445 2.57677 + vertex 1.00278 2.0513 2.57802 + endloop + endfacet + facet normal 0.0963535 0.257503 0.961461 + outer loop + vertex 1.00278 2.0513 2.57802 + vertex 1.00684 2.05445 2.57677 + vertex 1.00157 2.0555 2.57701 + endloop + endfacet + facet normal 0.0955614 0.257397 0.961569 + outer loop + vertex 1.01129 2.05549 2.57604 + vertex 1.00935 2.05804 2.57556 + vertex 1.00684 2.05445 2.57677 + endloop + endfacet + facet normal 0.104135 0.262345 0.959339 + outer loop + vertex 1.01541 2.05448 2.5759 + vertex 1.01955 2.05342 2.57574 + vertex 1.01972 2.05762 2.57457 + endloop + endfacet + facet normal 0.114345 0.258797 0.95914 + outer loop + vertex 1.01955 2.05342 2.57574 + vertex 1.02154 2.05073 2.57623 + vertex 1.02411 2.05424 2.57497 + endloop + endfacet + facet normal 0.10123 0.245822 0.964014 + outer loop + vertex 1.01673 2.04563 2.57806 + vertex 1.01695 2.04982 2.57697 + vertex 1.01279 2.0466 2.57823 + endloop + endfacet + facet normal 0.113655 0.23704 0.964829 + outer loop + vertex 1.02295 2.04166 2.57832 + vertex 1.02708 2.04491 2.57704 + vertex 1.02134 2.04638 2.57735 + endloop + endfacet + facet normal 0.115251 0.243646 0.962992 + outer loop + vertex 1.02708 2.04491 2.57704 + vertex 1.02563 2.0496 2.57603 + vertex 1.02134 2.04638 2.57735 + endloop + endfacet + facet normal 0.108714 0.239948 0.964679 + outer loop + vertex 1.01945 2.03333 2.58076 + vertex 1.02394 2.03435 2.58 + vertex 1.01974 2.03757 2.57968 + endloop + endfacet + facet normal 0.102621 0.240498 0.96521 + outer loop + vertex 1.01538 2.03438 2.58094 + vertex 1.01945 2.03333 2.58076 + vertex 1.01974 2.03757 2.57968 + endloop + endfacet + facet normal 0.104519 0.23806 0.96561 + outer loop + vertex 1.01394 2.03905 2.57994 + vertex 1.01538 2.03438 2.58094 + vertex 1.01974 2.03757 2.57968 + endloop + endfacet + facet normal 0.103002 0.231832 0.967287 + outer loop + vertex 1.01974 2.03757 2.57968 + vertex 1.01818 2.04221 2.57873 + vertex 1.01394 2.03905 2.57994 + endloop + endfacet + facet normal 0.0986742 0.236473 0.966615 + outer loop + vertex 1.01538 2.03438 2.58094 + vertex 1.01394 2.03905 2.57994 + vertex 1.01127 2.03552 2.58108 + endloop + endfacet + facet normal 0.100887 0.244712 0.964333 + outer loop + vertex 1.01127 2.03552 2.58108 + vertex 1.0111 2.03123 2.58218 + vertex 1.01538 2.03438 2.58094 + endloop + endfacet + facet normal 0.0998231 0.246068 0.964098 + outer loop + vertex 1.01685 2.02974 2.58197 + vertex 1.01538 2.03438 2.58094 + vertex 1.0111 2.03123 2.58218 + endloop + endfacet + facet normal 0.100805 0.250023 0.962978 + outer loop + vertex 1.01276 2.02654 2.58323 + vertex 1.01685 2.02974 2.58197 + vertex 1.0111 2.03123 2.58218 + endloop + endfacet + facet normal 0.0974813 0.248982 0.96359 + outer loop + vertex 1.01276 2.02654 2.58323 + vertex 1.0111 2.03123 2.58218 + vertex 1.00803 2.02718 2.58354 + endloop + endfacet + facet normal 0.0968595 0.243775 0.964983 + outer loop + vertex 1.00964 2.02253 2.58455 + vertex 1.01276 2.02654 2.58323 + vertex 1.00803 2.02718 2.58354 + endloop + endfacet + facet normal 0.0973335 0.24392 0.964899 + outer loop + vertex 1.00964 2.02253 2.58455 + vertex 1.00803 2.02718 2.58354 + vertex 1.00392 2.02407 2.58474 + endloop + endfacet + facet normal 0.0951795 0.235661 0.967163 + outer loop + vertex 1.00392 2.02407 2.58474 + vertex 1.00534 2.01944 2.58573 + vertex 1.00964 2.02253 2.58455 + endloop + endfacet + facet normal 0.0973893 0.232763 0.967645 + outer loop + vertex 1.00534 2.01944 2.58573 + vertex 1.00938 2.0183 2.5856 + vertex 1.00964 2.02253 2.58455 + endloop + endfacet + facet normal 0.0987709 0.232651 0.967532 + outer loop + vertex 1.00938 2.0183 2.5856 + vertex 1.01394 2.01912 2.58493 + vertex 1.00964 2.02253 2.58455 + endloop + endfacet + facet normal 0.0984024 0.232202 0.967677 + outer loop + vertex 1.00964 2.02253 2.58455 + vertex 1.01394 2.01912 2.58493 + vertex 1.01421 2.02316 2.58394 + endloop + endfacet + facet normal 0.104238 0.231687 0.967189 + outer loop + vertex 1.01394 2.01912 2.58493 + vertex 1.0181 2.0223 2.58372 + vertex 1.01421 2.02316 2.58394 + endloop + endfacet + facet normal 0.105816 0.229736 0.967484 + outer loop + vertex 1.01975 2.01769 2.58464 + vertex 1.0181 2.0223 2.58372 + vertex 1.01394 2.01912 2.58493 + endloop + endfacet + facet normal 0.10482 0.225449 0.9686 + outer loop + vertex 1.01394 2.01912 2.58493 + vertex 1.01539 2.01447 2.58586 + vertex 1.01975 2.01769 2.58464 + endloop + endfacet + facet normal 0.104807 0.225467 0.968597 + outer loop + vertex 1.01539 2.01447 2.58586 + vertex 1.01947 2.01339 2.58567 + vertex 1.01975 2.01769 2.58464 + endloop + endfacet + facet normal 0.10909 0.225095 0.968211 + outer loop + vertex 1.01947 2.01339 2.58567 + vertex 1.02409 2.01425 2.58495 + vertex 1.01975 2.01769 2.58464 + endloop + endfacet + facet normal 0.110706 0.227074 0.967565 + outer loop + vertex 1.01975 2.01769 2.58464 + vertex 1.02409 2.01425 2.58495 + vertex 1.02455 2.01849 2.5839 + endloop + endfacet + facet normal 0.109803 0.231632 0.966587 + outer loop + vertex 1.02455 2.01849 2.5839 + vertex 1.02295 2.02197 2.58325 + vertex 1.01975 2.01769 2.58464 + endloop + endfacet + facet normal 0.11405 0.233404 0.965668 + outer loop + vertex 1.02455 2.01849 2.5839 + vertex 1.02764 2.02129 2.58286 + vertex 1.02295 2.02197 2.58325 + endloop + endfacet + facet normal 0.114698 0.238627 0.964314 + outer loop + vertex 1.02764 2.02129 2.58286 + vertex 1.02656 2.02552 2.58194 + vertex 1.02295 2.02197 2.58325 + endloop + endfacet + facet normal 0.112198 0.241048 0.964006 + outer loop + vertex 1.02295 2.02197 2.58325 + vertex 1.02656 2.02552 2.58194 + vertex 1.02114 2.02654 2.58232 + endloop + endfacet + facet normal 0.110798 0.24055 0.964292 + outer loop + vertex 1.02295 2.02197 2.58325 + vertex 1.02114 2.02654 2.58232 + vertex 1.0181 2.0223 2.58372 + endloop + endfacet + facet normal 0.109676 0.241331 0.964225 + outer loop + vertex 1.0181 2.0223 2.58372 + vertex 1.02114 2.02654 2.58232 + vertex 1.01663 2.02561 2.58306 + endloop + endfacet + facet normal 0.105906 0.239815 0.965025 + outer loop + vertex 1.0181 2.0223 2.58372 + vertex 1.01663 2.02561 2.58306 + vertex 1.01421 2.02316 2.58394 + endloop + endfacet + facet normal 0.0998918 0.24548 0.964241 + outer loop + vertex 1.01421 2.02316 2.58394 + vertex 1.01663 2.02561 2.58306 + vertex 1.01276 2.02654 2.58323 + endloop + endfacet + facet normal 0.1077 0.249396 0.962394 + outer loop + vertex 1.01685 2.02974 2.58197 + vertex 1.01663 2.02561 2.58306 + vertex 1.02114 2.02654 2.58232 + endloop + endfacet + facet normal 0.10573 0.246851 0.963268 + outer loop + vertex 1.02136 2.03076 2.58121 + vertex 1.01685 2.02974 2.58197 + vertex 1.02114 2.02654 2.58232 + endloop + endfacet + facet normal 0.110444 0.246485 0.962833 + outer loop + vertex 1.02136 2.03076 2.58121 + vertex 1.02114 2.02654 2.58232 + vertex 1.0254 2.02991 2.58096 + endloop + endfacet + facet normal 0.110082 0.244625 0.963349 + outer loop + vertex 1.0254 2.02991 2.58096 + vertex 1.02394 2.03435 2.58 + vertex 1.02136 2.03076 2.58121 + endloop + endfacet + facet normal 0.112783 0.245408 0.962837 + outer loop + vertex 1.02394 2.03435 2.58 + vertex 1.0254 2.02991 2.58096 + vertex 1.02916 2.03325 2.57967 + endloop + endfacet + facet normal 0.114094 0.24401 0.963038 + outer loop + vertex 1.0254 2.02991 2.58096 + vertex 1.0303 2.02887 2.58065 + vertex 1.02916 2.03325 2.57967 + endloop + endfacet + facet normal 0.114395 0.244077 0.962985 + outer loop + vertex 1.02916 2.03325 2.57967 + vertex 1.0303 2.02887 2.58065 + vertex 1.03454 2.03204 2.57934 + endloop + endfacet + facet normal 0.114797 0.243572 0.963065 + outer loop + vertex 1.0303 2.02887 2.58065 + vertex 1.03444 2.02781 2.58042 + vertex 1.03454 2.03204 2.57934 + endloop + endfacet + facet normal 0.115917 0.243518 0.962945 + outer loop + vertex 1.03444 2.02781 2.58042 + vertex 1.03937 2.02845 2.57967 + vertex 1.03454 2.03204 2.57934 + endloop + endfacet + facet normal 0.114867 0.242145 0.963417 + outer loop + vertex 1.03454 2.03204 2.57934 + vertex 1.03937 2.02845 2.57967 + vertex 1.03901 2.03305 2.57855 + endloop + endfacet + facet normal 0.114778 0.242481 0.963343 + outer loop + vertex 1.03901 2.03305 2.57855 + vertex 1.03692 2.03575 2.57812 + vertex 1.03454 2.03204 2.57934 + endloop + endfacet + facet normal 0.115308 0.242147 0.963363 + outer loop + vertex 1.03454 2.03204 2.57934 + vertex 1.03692 2.03575 2.57812 + vertex 1.03282 2.0367 2.57837 + endloop + endfacet + facet normal 0.113897 0.241687 0.963647 + outer loop + vertex 1.03454 2.03204 2.57934 + vertex 1.03282 2.0367 2.57837 + vertex 1.02916 2.03325 2.57967 + endloop + endfacet + facet normal 0.11468 0.240897 0.963752 + outer loop + vertex 1.02916 2.03325 2.57967 + vertex 1.03282 2.0367 2.57837 + vertex 1.02808 2.03747 2.57875 + endloop + endfacet + facet normal 0.115247 0.241866 0.963441 + outer loop + vertex 1.03692 2.03575 2.57812 + vertex 1.03699 2.04002 2.57704 + vertex 1.03282 2.0367 2.57837 + endloop + endfacet + facet normal 0.117225 0.241778 0.963225 + outer loop + vertex 1.03699 2.04002 2.57704 + vertex 1.03692 2.03575 2.57812 + vertex 1.04141 2.03669 2.57734 + endloop + endfacet + facet normal 0.118198 0.243027 0.962791 + outer loop + vertex 1.04148 2.04092 2.57626 + vertex 1.03699 2.04002 2.57704 + vertex 1.04141 2.03669 2.57734 + endloop + endfacet + facet normal 0.124008 0.242757 0.962128 + outer loop + vertex 1.04148 2.04092 2.57626 + vertex 1.04141 2.03669 2.57734 + vertex 1.04557 2.03969 2.57605 + endloop + endfacet + facet normal 0.128635 0.236732 0.963022 + outer loop + vertex 1.0471 2.03485 2.57703 + vertex 1.04557 2.03969 2.57605 + vertex 1.04141 2.03669 2.57734 + endloop + endfacet + facet normal 0.131405 0.245764 0.960382 + outer loop + vertex 1.043 2.0321 2.5783 + vertex 1.0471 2.03485 2.57703 + vertex 1.04141 2.03669 2.57734 + endloop + endfacet + facet normal 0.119413 0.242129 0.962868 + outer loop + vertex 1.043 2.0321 2.5783 + vertex 1.04141 2.03669 2.57734 + vertex 1.03901 2.03305 2.57855 + endloop + endfacet + facet normal 0.135749 0.239708 0.961308 + outer loop + vertex 1.04686 2.03073 2.57809 + vertex 1.0471 2.03485 2.57703 + vertex 1.043 2.0321 2.5783 + endloop + endfacet + facet normal 0.137024 0.243475 0.960179 + outer loop + vertex 1.04429 2.02863 2.57899 + vertex 1.04686 2.03073 2.57809 + vertex 1.043 2.0321 2.5783 + endloop + endfacet + facet normal 0.123081 0.238904 0.963211 + outer loop + vertex 1.04429 2.02863 2.57899 + vertex 1.043 2.0321 2.5783 + vertex 1.03937 2.02845 2.57967 + endloop + endfacet + facet normal 0.123515 0.232539 0.964712 + outer loop + vertex 1.03937 2.02845 2.57967 + vertex 1.04396 2.02457 2.58001 + vertex 1.04429 2.02863 2.57899 + endloop + endfacet + facet normal 0.132175 0.242455 0.961117 + outer loop + vertex 1.03949 2.02401 2.58077 + vertex 1.04396 2.02457 2.58001 + vertex 1.03937 2.02845 2.57967 + endloop + endfacet + facet normal 0.117203 0.242502 0.963045 + outer loop + vertex 1.03949 2.02401 2.58077 + vertex 1.03937 2.02845 2.57967 + vertex 1.03631 2.02508 2.58089 + endloop + endfacet + facet normal 0.115729 0.237989 0.964348 + outer loop + vertex 1.03631 2.02508 2.58089 + vertex 1.03641 2.02053 2.582 + vertex 1.03949 2.02401 2.58077 + endloop + endfacet + facet normal 0.119738 0.234562 0.964699 + outer loop + vertex 1.0413 2.02117 2.58124 + vertex 1.03949 2.02401 2.58077 + vertex 1.03641 2.02053 2.582 + endloop + endfacet + facet normal 0.120461 0.23019 0.965661 + outer loop + vertex 1.0413 2.02117 2.58124 + vertex 1.03641 2.02053 2.582 + vertex 1.04107 2.01675 2.58232 + endloop + endfacet + facet normal 0.146822 0.228014 0.962524 + outer loop + vertex 1.0413 2.02117 2.58124 + vertex 1.04107 2.01675 2.58232 + vertex 1.04529 2.01979 2.58095 + endloop + endfacet + facet normal 0.147548 0.230245 0.961882 + outer loop + vertex 1.04529 2.01979 2.58095 + vertex 1.04396 2.02457 2.58001 + vertex 1.0413 2.02117 2.58124 + endloop + endfacet + facet normal 0.174595 0.236589 0.955794 + outer loop + vertex 1.04396 2.02457 2.58001 + vertex 1.04529 2.01979 2.58095 + vertex 1.04951 2.02249 2.57952 + endloop + endfacet + facet normal 0.165029 0.209068 0.963876 + outer loop + vertex 1.04951 2.02249 2.57952 + vertex 1.04811 2.02722 2.57873 + vertex 1.04396 2.02457 2.58001 + endloop + endfacet + facet normal 0.151208 0.229512 0.961489 + outer loop + vertex 1.04396 2.02457 2.58001 + vertex 1.04811 2.02722 2.57873 + vertex 1.04429 2.02863 2.57899 + endloop + endfacet + facet normal 0.190153 0.215503 0.95781 + outer loop + vertex 1.04951 2.02249 2.57952 + vertex 1.05194 2.02601 2.57824 + vertex 1.04811 2.02722 2.57873 + endloop + endfacet + facet normal 0.190871 0.21808 0.957084 + outer loop + vertex 1.05194 2.02601 2.57824 + vertex 1.05163 2.03071 2.57723 + vertex 1.04811 2.02722 2.57873 + endloop + endfacet + facet normal 0.173837 0.234936 0.95634 + outer loop + vertex 1.04811 2.02722 2.57873 + vertex 1.05163 2.03071 2.57723 + vertex 1.04686 2.03073 2.57809 + endloop + endfacet + facet normal 0.225247 0.190384 0.95552 + outer loop + vertex 1.0539 2.02293 2.57839 + vertex 1.05194 2.02601 2.57824 + vertex 1.04951 2.02249 2.57952 + endloop + endfacet + facet normal 0.226117 0.184238 0.956518 + outer loop + vertex 1.04951 2.02249 2.57952 + vertex 1.05348 2.01845 2.57936 + vertex 1.0539 2.02293 2.57839 + endloop + endfacet + facet normal 0.18824 0.216447 0.957975 + outer loop + vertex 1.04529 2.01979 2.58095 + vertex 1.04914 2.01818 2.58056 + vertex 1.04951 2.02249 2.57952 + endloop + endfacet + facet normal 0.188902 0.21815 0.957458 + outer loop + vertex 1.04914 2.01818 2.58056 + vertex 1.04529 2.01979 2.58095 + vertex 1.04625 2.01533 2.58178 + endloop + endfacet + facet normal 0.158293 0.212828 0.964182 + outer loop + vertex 1.04625 2.01533 2.58178 + vertex 1.04529 2.01979 2.58095 + vertex 1.04107 2.01675 2.58232 + endloop + endfacet + facet normal 0.162245 0.228858 0.959844 + outer loop + vertex 1.04299 2.01184 2.58316 + vertex 1.04625 2.01533 2.58178 + vertex 1.04107 2.01675 2.58232 + endloop + endfacet + facet normal 0.143047 0.222137 0.964465 + outer loop + vertex 1.04299 2.01184 2.58316 + vertex 1.04107 2.01675 2.58232 + vertex 1.03818 2.01248 2.58373 + endloop + endfacet + facet normal 0.143401 0.225565 0.963616 + outer loop + vertex 1.03988 2.00765 2.58461 + vertex 1.04299 2.01184 2.58316 + vertex 1.03818 2.01248 2.58373 + endloop + endfacet + facet normal 0.165313 0.20936 0.963763 + outer loop + vertex 1.04447 2.00807 2.58373 + vertex 1.04299 2.01184 2.58316 + vertex 1.03988 2.00765 2.58461 + endloop + endfacet + facet normal 0.168323 0.185551 0.968111 + outer loop + vertex 1.03988 2.00765 2.58461 + vertex 1.04423 2.00349 2.58465 + vertex 1.04447 2.00807 2.58373 + endloop + endfacet + facet normal 0.197804 0.216228 0.956096 + outer loop + vertex 1.03957 2.00335 2.58564 + vertex 1.04423 2.00349 2.58465 + vertex 1.03988 2.00765 2.58461 + endloop + endfacet + facet normal 0.197845 0.215681 0.956211 + outer loop + vertex 1.03957 2.00335 2.58564 + vertex 1.04118 2.00048 2.58596 + vertex 1.04423 2.00349 2.58465 + endloop + endfacet + facet normal 0.233203 0.179692 0.955681 + outer loop + vertex 1.04411 1.99884 2.58555 + vertex 1.04423 2.00349 2.58465 + vertex 1.04118 2.00048 2.58596 + endloop + endfacet + facet normal 0.226805 0.167292 0.959465 + outer loop + vertex 1.04118 2.00048 2.58596 + vertex 1.04081 1.99609 2.58681 + vertex 1.04411 1.99884 2.58555 + endloop + endfacet + facet normal 0.159076 0.175373 0.971565 + outer loop + vertex 1.04118 2.00048 2.58596 + vertex 1.03682 1.99985 2.58678 + vertex 1.04081 1.99609 2.58681 + endloop + endfacet + facet normal 0.179301 0.196764 0.963917 + outer loop + vertex 1.03682 1.99985 2.58678 + vertex 1.03642 1.99546 2.58776 + vertex 1.04081 1.99609 2.58681 + endloop + endfacet + facet normal 0.18086 0.188138 0.965346 + outer loop + vertex 1.03804 1.99174 2.58818 + vertex 1.04081 1.99609 2.58681 + vertex 1.03642 1.99546 2.58776 + endloop + endfacet + facet normal 0.155927 0.193507 0.968629 + outer loop + vertex 1.04118 2.00048 2.58596 + vertex 1.03957 2.00335 2.58564 + vertex 1.03682 1.99985 2.58678 + endloop + endfacet + facet normal 0.202875 0.222584 0.953571 + outer loop + vertex 1.04447 2.00807 2.58373 + vertex 1.04786 2.01061 2.58242 + vertex 1.04299 2.01184 2.58316 + endloop + endfacet + facet normal 0.125532 0.233846 0.964136 + outer loop + vertex 1.03818 2.01248 2.58373 + vertex 1.04107 2.01675 2.58232 + vertex 1.03661 2.01595 2.58309 + endloop + endfacet + facet normal 0.117157 0.230392 0.96602 + outer loop + vertex 1.03818 2.01248 2.58373 + vertex 1.03661 2.01595 2.58309 + vertex 1.03432 2.01339 2.58398 + endloop + endfacet + facet normal 0.117034 0.229831 0.966168 + outer loop + vertex 1.03409 2.00932 2.58498 + vertex 1.03818 2.01248 2.58373 + vertex 1.03432 2.01339 2.58398 + endloop + endfacet + facet normal 0.109735 0.230414 0.966886 + outer loop + vertex 1.02981 2.01269 2.58466 + vertex 1.03409 2.00932 2.58498 + vertex 1.03432 2.01339 2.58398 + endloop + endfacet + facet normal 0.109288 0.232796 0.966366 + outer loop + vertex 1.03432 2.01339 2.58398 + vertex 1.03286 2.01664 2.58336 + vertex 1.02981 2.01269 2.58466 + endloop + endfacet + facet normal 0.11277 0.230178 0.966592 + outer loop + vertex 1.02981 2.01269 2.58466 + vertex 1.03286 2.01664 2.58336 + vertex 1.0284 2.01724 2.58374 + endloop + endfacet + facet normal 0.111291 0.229775 0.96686 + outer loop + vertex 1.02981 2.01269 2.58466 + vertex 1.0284 2.01724 2.58374 + vertex 1.02409 2.01425 2.58495 + endloop + endfacet + facet normal 0.109957 0.224643 0.968217 + outer loop + vertex 1.02409 2.01425 2.58495 + vertex 1.02547 2.00956 2.58588 + vertex 1.02981 2.01269 2.58466 + endloop + endfacet + facet normal 0.106974 0.228556 0.967636 + outer loop + vertex 1.02547 2.00956 2.58588 + vertex 1.02953 2.00847 2.58569 + vertex 1.02981 2.01269 2.58466 + endloop + endfacet + facet normal 0.105475 0.22273 0.969158 + outer loop + vertex 1.02953 2.00847 2.58569 + vertex 1.02547 2.00956 2.58588 + vertex 1.02687 2.00482 2.58682 + endloop + endfacet + facet normal 0.102144 0.225097 0.968968 + outer loop + vertex 1.03145 2.00579 2.58611 + vertex 1.02953 2.00847 2.58569 + vertex 1.02687 2.00482 2.58682 + endloop + endfacet + facet normal 0.103575 0.219216 0.970163 + outer loop + vertex 1.03145 2.00579 2.58611 + vertex 1.02687 2.00482 2.58682 + vertex 1.03116 2.00139 2.58713 + endloop + endfacet + facet normal 0.108686 0.21877 0.969705 + outer loop + vertex 1.03145 2.00579 2.58611 + vertex 1.03116 2.00139 2.58713 + vertex 1.03552 2.00465 2.58591 + endloop + endfacet + facet normal 0.110874 0.226958 0.967573 + outer loop + vertex 1.03552 2.00465 2.58591 + vertex 1.03409 2.00932 2.58498 + vertex 1.03145 2.00579 2.58611 + endloop + endfacet + facet normal 0.128345 0.231659 0.964293 + outer loop + vertex 1.03409 2.00932 2.58498 + vertex 1.03552 2.00465 2.58591 + vertex 1.03988 2.00765 2.58461 + endloop + endfacet + facet normal 0.134617 0.223047 0.965468 + outer loop + vertex 1.03552 2.00465 2.58591 + vertex 1.03957 2.00335 2.58564 + vertex 1.03988 2.00765 2.58461 + endloop + endfacet + facet normal 0.13145 0.212636 0.968249 + outer loop + vertex 1.03957 2.00335 2.58564 + vertex 1.03552 2.00465 2.58591 + vertex 1.03682 1.99985 2.58678 + endloop + endfacet + facet normal 0.116318 0.209028 0.970967 + outer loop + vertex 1.03682 1.99985 2.58678 + vertex 1.03552 2.00465 2.58591 + vertex 1.03116 2.00139 2.58713 + endloop + endfacet + facet normal 0.11819 0.21637 0.969131 + outer loop + vertex 1.03262 1.99668 2.58801 + vertex 1.03682 1.99985 2.58678 + vertex 1.03116 2.00139 2.58713 + endloop + endfacet + facet normal 0.104897 0.21268 0.971475 + outer loop + vertex 1.03262 1.99668 2.58801 + vertex 1.03116 2.00139 2.58713 + vertex 1.02802 1.99702 2.58843 + endloop + endfacet + facet normal 0.10476 0.210147 0.972041 + outer loop + vertex 1.02957 1.99362 2.589 + vertex 1.03262 1.99668 2.58801 + vertex 1.02802 1.99702 2.58843 + endloop + endfacet + facet normal 0.101725 0.208862 0.97264 + outer loop + vertex 1.02957 1.99362 2.589 + vertex 1.02802 1.99702 2.58843 + vertex 1.0248 1.99276 2.58968 + endloop + endfacet + facet normal 0.102916 0.203133 0.973727 + outer loop + vertex 1.0248 1.99276 2.58968 + vertex 1.02909 1.98929 2.58995 + vertex 1.02957 1.99362 2.589 + endloop + endfacet + facet normal 0.116435 0.201365 0.972571 + outer loop + vertex 1.02909 1.98929 2.58995 + vertex 1.03345 1.99242 2.58878 + vertex 1.02957 1.99362 2.589 + endloop + endfacet + facet normal 0.128554 0.185097 0.974276 + outer loop + vertex 1.03489 1.98751 2.58952 + vertex 1.03345 1.99242 2.58878 + vertex 1.02909 1.98929 2.58995 + endloop + endfacet + facet normal 0.13655 0.212856 0.967495 + outer loop + vertex 1.02909 1.98929 2.58995 + vertex 1.03046 1.98451 2.59081 + vertex 1.03489 1.98751 2.58952 + endloop + endfacet + facet normal 0.141917 0.205302 0.968355 + outer loop + vertex 1.03046 1.98451 2.59081 + vertex 1.0345 1.98315 2.59051 + vertex 1.03489 1.98751 2.58952 + endloop + endfacet + facet normal 0.143733 0.211024 0.966856 + outer loop + vertex 1.0345 1.98315 2.59051 + vertex 1.03046 1.98451 2.59081 + vertex 1.03174 1.97971 2.59167 + endloop + endfacet + facet normal 0.116714 0.204676 0.971847 + outer loop + vertex 1.03174 1.97971 2.59167 + vertex 1.03046 1.98451 2.59081 + vertex 1.0261 1.9813 2.59201 + endloop + endfacet + facet normal 0.121724 0.223523 0.967068 + outer loop + vertex 1.02762 1.97659 2.59291 + vertex 1.03174 1.97971 2.59167 + vertex 1.0261 1.9813 2.59201 + endloop + endfacet + facet normal 0.0979176 0.216679 0.97132 + outer loop + vertex 1.02762 1.97659 2.59291 + vertex 1.0261 1.9813 2.59201 + vertex 1.02302 1.97696 2.59329 + endloop + endfacet + facet normal 0.0982488 0.221982 0.970088 + outer loop + vertex 1.02461 1.97356 2.5939 + vertex 1.02762 1.97659 2.59291 + vertex 1.02302 1.97696 2.59329 + endloop + endfacet + facet normal 0.0906396 0.218698 0.971574 + outer loop + vertex 1.02461 1.97356 2.5939 + vertex 1.02302 1.97696 2.59329 + vertex 1.01979 1.97271 2.59455 + endloop + endfacet + facet normal 0.0919354 0.212376 0.972854 + outer loop + vertex 1.01979 1.97271 2.59455 + vertex 1.02408 1.96931 2.59488 + vertex 1.02461 1.97356 2.5939 + endloop + endfacet + facet normal 0.11206 0.209531 0.97136 + outer loop + vertex 1.02408 1.96931 2.59488 + vertex 1.02842 1.97242 2.59371 + vertex 1.02461 1.97356 2.5939 + endloop + endfacet + facet normal 0.0948856 0.215998 0.971772 + outer loop + vertex 1.01944 1.96842 2.59553 + vertex 1.02408 1.96931 2.59488 + vertex 1.01979 1.97271 2.59455 + endloop + endfacet + facet normal 0.0945197 0.217655 0.971438 + outer loop + vertex 1.01944 1.96842 2.59553 + vertex 1.02132 1.96577 2.59594 + vertex 1.02408 1.96931 2.59488 + endloop + endfacet + facet normal 0.0849102 0.211169 0.973755 + outer loop + vertex 1.02132 1.96577 2.59594 + vertex 1.01944 1.96842 2.59553 + vertex 1.01674 1.96476 2.59656 + endloop + endfacet + facet normal 0.0906825 0.218666 0.971577 + outer loop + vertex 1.01979 1.97271 2.59455 + vertex 1.02302 1.97696 2.59329 + vertex 1.01837 1.97733 2.59364 + endloop + endfacet + facet normal 0.0906035 0.217378 0.971873 + outer loop + vertex 1.02302 1.97696 2.59329 + vertex 1.02141 1.9804 2.59267 + vertex 1.01837 1.97733 2.59364 + endloop + endfacet + facet normal 0.0954748 0.212736 0.972434 + outer loop + vertex 1.01837 1.97733 2.59364 + vertex 1.02141 1.9804 2.59267 + vertex 1.01757 1.98154 2.5928 + endloop + endfacet + facet normal 0.0950321 0.212663 0.972493 + outer loop + vertex 1.01837 1.97733 2.59364 + vertex 1.01757 1.98154 2.5928 + vertex 1.01451 1.97843 2.59377 + endloop + endfacet + facet normal 0.101013 0.206979 0.973117 + outer loop + vertex 1.01451 1.97843 2.59377 + vertex 1.01757 1.98154 2.5928 + vertex 1.01299 1.98186 2.5932 + endloop + endfacet + facet normal 0.103094 0.207836 0.972716 + outer loop + vertex 1.01451 1.97843 2.59377 + vertex 1.01299 1.98186 2.5932 + vertex 1.00979 1.97745 2.59448 + endloop + endfacet + facet normal 0.10446 0.206864 0.972777 + outer loop + vertex 1.00979 1.97745 2.59448 + vertex 1.01299 1.98186 2.5932 + vertex 1.00833 1.98205 2.59366 + endloop + endfacet + facet normal 0.100794 0.20581 0.973387 + outer loop + vertex 1.00979 1.97745 2.59448 + vertex 1.00833 1.98205 2.59366 + vertex 1.00443 1.97848 2.59482 + endloop + endfacet + facet normal 0.101479 0.209653 0.972496 + outer loop + vertex 1.00443 1.97848 2.59482 + vertex 1.00536 1.97412 2.59566 + vertex 1.00979 1.97745 2.59448 + endloop + endfacet + facet normal 0.100637 0.210723 0.972352 + outer loop + vertex 1.00536 1.97412 2.59566 + vertex 1.00936 1.97321 2.59545 + vertex 1.00979 1.97745 2.59448 + endloop + endfacet + facet normal 0.0990304 0.210916 0.972475 + outer loop + vertex 1.00936 1.97321 2.59545 + vertex 1.01398 1.97415 2.59477 + vertex 1.00979 1.97745 2.59448 + endloop + endfacet + facet normal 0.101609 0.214103 0.971512 + outer loop + vertex 1.00979 1.97745 2.59448 + vertex 1.01398 1.97415 2.59477 + vertex 1.01451 1.97843 2.59377 + endloop + endfacet + facet normal 0.0956633 0.214944 0.97193 + outer loop + vertex 1.01398 1.97415 2.59477 + vertex 1.01837 1.97733 2.59364 + vertex 1.01451 1.97843 2.59377 + endloop + endfacet + facet normal 0.0924497 0.219155 0.9713 + outer loop + vertex 1.01979 1.97271 2.59455 + vertex 1.01837 1.97733 2.59364 + vertex 1.01398 1.97415 2.59477 + endloop + endfacet + facet normal 0.0909878 0.213025 0.972801 + outer loop + vertex 1.01398 1.97415 2.59477 + vertex 1.01533 1.9695 2.59567 + vertex 1.01979 1.97271 2.59455 + endloop + endfacet + facet normal 0.0882318 0.216663 0.972251 + outer loop + vertex 1.01533 1.9695 2.59567 + vertex 1.01944 1.96842 2.59553 + vertex 1.01979 1.97271 2.59455 + endloop + endfacet + facet normal 0.0865374 0.210001 0.973864 + outer loop + vertex 1.01944 1.96842 2.59553 + vertex 1.01533 1.9695 2.59567 + vertex 1.01674 1.96476 2.59656 + endloop + endfacet + facet normal 0.0992137 0.210126 0.972627 + outer loop + vertex 1.00936 1.97321 2.59545 + vertex 1.01125 1.97058 2.59582 + vertex 1.01398 1.97415 2.59477 + endloop + endfacet + facet normal 0.0942058 0.213869 0.972309 + outer loop + vertex 1.01533 1.9695 2.59567 + vertex 1.01398 1.97415 2.59477 + vertex 1.01125 1.97058 2.59582 + endloop + endfacet + facet normal 0.0928047 0.208388 0.973633 + outer loop + vertex 1.01125 1.97058 2.59582 + vertex 1.011 1.9662 2.59678 + vertex 1.01533 1.9695 2.59567 + endloop + endfacet + facet normal 0.0906361 0.211105 0.973252 + outer loop + vertex 1.01674 1.96476 2.59656 + vertex 1.01533 1.9695 2.59567 + vertex 1.011 1.9662 2.59678 + endloop + endfacet + facet normal 0.0886606 0.202885 0.97518 + outer loop + vertex 1.0124 1.96132 2.59767 + vertex 1.01674 1.96476 2.59656 + vertex 1.011 1.9662 2.59678 + endloop + endfacet + facet normal 0.094028 0.204276 0.974387 + outer loop + vertex 1.0124 1.96132 2.59767 + vertex 1.011 1.9662 2.59678 + vertex 1.0078 1.96183 2.59801 + endloop + endfacet + facet normal 0.0939564 0.203524 0.974551 + outer loop + vertex 1.00869 1.9576 2.59881 + vertex 1.0124 1.96132 2.59767 + vertex 1.0078 1.96183 2.59801 + endloop + endfacet + facet normal 0.0957732 0.20386 0.974304 + outer loop + vertex 1.00869 1.9576 2.59881 + vertex 1.0078 1.96183 2.59801 + vertex 1.00472 1.95859 2.59899 + endloop + endfacet + facet normal 0.0961113 0.205278 0.973973 + outer loop + vertex 1.00411 1.95429 2.59996 + vertex 1.00869 1.9576 2.59881 + vertex 1.00472 1.95859 2.59899 + endloop + endfacet + facet normal 0.0935346 0.205686 0.974138 + outer loop + vertex 0.999919 1.95755 2.59967 + vertex 1.00411 1.95429 2.59996 + vertex 1.00472 1.95859 2.59899 + endloop + endfacet + facet normal 0.09451 0.201675 0.974882 + outer loop + vertex 1.00472 1.95859 2.59899 + vertex 1.00332 1.96193 2.59843 + vertex 0.999919 1.95755 2.59967 + endloop + endfacet + facet normal 0.0920136 0.203568 0.974728 + outer loop + vertex 0.999919 1.95755 2.59967 + vertex 1.00332 1.96193 2.59843 + vertex 0.998566 1.96227 2.59881 + endloop + endfacet + facet normal 0.0848089 0.201693 0.97577 + outer loop + vertex 0.999919 1.95755 2.59967 + vertex 0.998566 1.96227 2.59881 + vertex 0.994449 1.95853 2.59994 + endloop + endfacet + facet normal 0.0853654 0.204982 0.975036 + outer loop + vertex 0.994449 1.95853 2.59994 + vertex 0.995421 1.95419 2.60077 + vertex 0.999919 1.95755 2.59967 + endloop + endfacet + facet normal 0.0844284 0.206182 0.974864 + outer loop + vertex 0.995421 1.95419 2.60077 + vertex 0.999459 1.95332 2.6006 + vertex 0.999919 1.95755 2.59967 + endloop + endfacet + facet normal 0.0838909 0.20357 0.97546 + outer loop + vertex 0.999459 1.95332 2.6006 + vertex 0.995421 1.95419 2.60077 + vertex 0.996897 1.94968 2.60158 + endloop + endfacet + facet normal 0.0865926 0.201711 0.97561 + outer loop + vertex 1.00136 1.95074 2.60097 + vertex 0.999459 1.95332 2.6006 + vertex 0.996897 1.94968 2.60158 + endloop + endfacet + facet normal 0.0864072 0.202418 0.97548 + outer loop + vertex 1.00136 1.95074 2.60097 + vertex 0.996897 1.94968 2.60158 + vertex 1.00111 1.94635 2.6019 + endloop + endfacet + facet normal 0.092386 0.201977 0.975023 + outer loop + vertex 1.00136 1.95074 2.60097 + vertex 1.00111 1.94635 2.6019 + vertex 1.00541 1.94966 2.60081 + endloop + endfacet + facet normal 0.0933498 0.205719 0.974149 + outer loop + vertex 1.00541 1.94966 2.60081 + vertex 1.00411 1.95429 2.59996 + vertex 1.00136 1.95074 2.60097 + endloop + endfacet + facet normal 0.0927664 0.205571 0.974236 + outer loop + vertex 1.00411 1.95429 2.59996 + vertex 1.00541 1.94966 2.60081 + vertex 1.00989 1.95284 2.59971 + endloop + endfacet + facet normal 0.0907301 0.208309 0.973846 + outer loop + vertex 1.00541 1.94966 2.60081 + vertex 1.00946 1.94857 2.60067 + vertex 1.00989 1.95284 2.59971 + endloop + endfacet + facet normal 0.0848673 0.208995 0.974227 + outer loop + vertex 1.00946 1.94857 2.60067 + vertex 1.01416 1.94945 2.60007 + vertex 1.00989 1.95284 2.59971 + endloop + endfacet + facet normal 0.0861828 0.2106 0.973766 + outer loop + vertex 1.00989 1.95284 2.59971 + vertex 1.01416 1.94945 2.60007 + vertex 1.01473 1.95371 2.5991 + endloop + endfacet + facet normal 0.0859177 0.211891 0.973509 + outer loop + vertex 1.01473 1.95371 2.5991 + vertex 1.01333 1.95706 2.59849 + vertex 1.00989 1.95284 2.59971 + endloop + endfacet + facet normal 0.0907443 0.208076 0.973894 + outer loop + vertex 1.00989 1.95284 2.59971 + vertex 1.01333 1.95706 2.59849 + vertex 1.00869 1.9576 2.59881 + endloop + endfacet + facet normal 0.0823702 0.210524 0.974112 + outer loop + vertex 1.01473 1.95371 2.5991 + vertex 1.0178 1.95693 2.59814 + vertex 1.01333 1.95706 2.59849 + endloop + endfacet + facet normal 0.0823563 0.209431 0.974349 + outer loop + vertex 1.0178 1.95693 2.59814 + vertex 1.01634 1.96032 2.59753 + vertex 1.01333 1.95706 2.59849 + endloop + endfacet + facet normal 0.0862909 0.205911 0.974759 + outer loop + vertex 1.01333 1.95706 2.59849 + vertex 1.01634 1.96032 2.59753 + vertex 1.0124 1.96132 2.59767 + endloop + endfacet + facet normal 0.0840225 0.210098 0.974063 + outer loop + vertex 1.0178 1.95693 2.59814 + vertex 1.02095 1.9614 2.5969 + vertex 1.01634 1.96032 2.59753 + endloop + endfacet + facet normal 0.0851118 0.205905 0.974864 + outer loop + vertex 1.01674 1.96476 2.59656 + vertex 1.01634 1.96032 2.59753 + vertex 1.02095 1.9614 2.5969 + endloop + endfacet + facet normal 0.0859524 0.206926 0.974574 + outer loop + vertex 1.02132 1.96577 2.59594 + vertex 1.01674 1.96476 2.59656 + vertex 1.02095 1.9614 2.5969 + endloop + endfacet + facet normal 0.104294 0.205045 0.97318 + outer loop + vertex 1.02132 1.96577 2.59594 + vertex 1.02095 1.9614 2.5969 + vertex 1.02526 1.96469 2.59575 + endloop + endfacet + facet normal 0.10543 0.209388 0.972132 + outer loop + vertex 1.02526 1.96469 2.59575 + vertex 1.02408 1.96931 2.59488 + vertex 1.02132 1.96577 2.59594 + endloop + endfacet + facet normal 0.092098 0.204534 0.974517 + outer loop + vertex 1.02247 1.9565 2.59779 + vertex 1.02095 1.9614 2.5969 + vertex 1.0178 1.95693 2.59814 + endloop + endfacet + facet normal 0.0926454 0.211838 0.972904 + outer loop + vertex 1.01872 1.9527 2.59897 + vertex 1.02247 1.9565 2.59779 + vertex 1.0178 1.95693 2.59814 + endloop + endfacet + facet normal 0.101905 0.203018 0.973858 + outer loop + vertex 1.02337 1.95201 2.59863 + vertex 1.02247 1.9565 2.59779 + vertex 1.01872 1.9527 2.59897 + endloop + endfacet + facet normal 0.101664 0.201207 0.974259 + outer loop + vertex 1.02006 1.9478 2.59984 + vertex 1.02337 1.95201 2.59863 + vertex 1.01872 1.9527 2.59897 + endloop + endfacet + facet normal 0.0922929 0.198888 0.975667 + outer loop + vertex 1.02006 1.9478 2.59984 + vertex 1.01872 1.9527 2.59897 + vertex 1.01416 1.94945 2.60007 + endloop + endfacet + facet normal 0.095172 0.209577 0.973149 + outer loop + vertex 1.01416 1.94945 2.60007 + vertex 1.01558 1.94475 2.60094 + vertex 1.02006 1.9478 2.59984 + endloop + endfacet + facet normal 0.103437 0.198013 0.974726 + outer loop + vertex 1.01558 1.94475 2.60094 + vertex 1.01983 1.94344 2.60076 + vertex 1.02006 1.9478 2.59984 + endloop + endfacet + facet normal 0.163455 0.193253 0.967438 + outer loop + vertex 1.01983 1.94344 2.60076 + vertex 1.02477 1.94366 2.59988 + vertex 1.02006 1.9478 2.59984 + endloop + endfacet + facet normal 0.12954 0.154796 0.979417 + outer loop + vertex 1.02006 1.9478 2.59984 + vertex 1.02477 1.94366 2.59988 + vertex 1.02461 1.94842 2.59915 + endloop + endfacet + facet normal 0.162338 0.207205 0.964734 + outer loop + vertex 1.01983 1.94344 2.60076 + vertex 1.02172 1.94049 2.60107 + vertex 1.02477 1.94366 2.59988 + endloop + endfacet + facet normal 0.192404 0.178396 0.964964 + outer loop + vertex 1.02488 1.939 2.60072 + vertex 1.02477 1.94366 2.59988 + vertex 1.02172 1.94049 2.60107 + endloop + endfacet + facet normal 0.189468 0.171779 0.966744 + outer loop + vertex 1.02172 1.94049 2.60107 + vertex 1.02167 1.9357 2.60193 + vertex 1.02488 1.939 2.60072 + endloop + endfacet + facet normal 0.125372 0.174326 0.976674 + outer loop + vertex 1.02172 1.94049 2.60107 + vertex 1.01712 1.93982 2.60178 + vertex 1.02167 1.9357 2.60193 + endloop + endfacet + facet normal 0.142411 0.192921 0.970825 + outer loop + vertex 1.01712 1.93982 2.60178 + vertex 1.01669 1.93529 2.60274 + vertex 1.02167 1.9357 2.60193 + endloop + endfacet + facet normal 0.141378 0.202059 0.969115 + outer loop + vertex 1.01794 1.93176 2.6033 + vertex 1.02167 1.9357 2.60193 + vertex 1.01669 1.93529 2.60274 + endloop + endfacet + facet normal 0.110702 0.192184 0.975095 + outer loop + vertex 1.01794 1.93176 2.6033 + vertex 1.01669 1.93529 2.60274 + vertex 1.01353 1.93216 2.60372 + endloop + endfacet + facet normal 0.111313 0.200771 0.973294 + outer loop + vertex 1.01489 1.92878 2.60426 + vertex 1.01794 1.93176 2.6033 + vertex 1.01353 1.93216 2.60372 + endloop + endfacet + facet normal 0.0965461 0.19527 0.975986 + outer loop + vertex 1.01489 1.92878 2.60426 + vertex 1.01353 1.93216 2.60372 + vertex 1.01008 1.928 2.60489 + endloop + endfacet + facet normal 0.0974722 0.190308 0.976874 + outer loop + vertex 1.01008 1.928 2.60489 + vertex 1.01426 1.9246 2.60514 + vertex 1.01489 1.92878 2.60426 + endloop + endfacet + facet normal 0.132652 0.184407 0.973857 + outer loop + vertex 1.01426 1.9246 2.60514 + vertex 1.01861 1.92763 2.60397 + vertex 1.01489 1.92878 2.60426 + endloop + endfacet + facet normal 0.150591 0.159362 0.975667 + outer loop + vertex 1.01972 1.92288 2.60458 + vertex 1.01861 1.92763 2.60397 + vertex 1.01426 1.9246 2.60514 + endloop + endfacet + facet normal 0.161223 0.195735 0.967313 + outer loop + vertex 1.01426 1.9246 2.60514 + vertex 1.01538 1.91998 2.60589 + vertex 1.01972 1.92288 2.60458 + endloop + endfacet + facet normal 0.175125 0.175518 0.968775 + outer loop + vertex 1.01538 1.91998 2.60589 + vertex 1.0191 1.91846 2.60549 + vertex 1.01972 1.92288 2.60458 + endloop + endfacet + facet normal 0.174806 0.174685 0.968983 + outer loop + vertex 1.0191 1.91846 2.60549 + vertex 1.01538 1.91998 2.60589 + vertex 1.01616 1.91544 2.60656 + endloop + endfacet + facet normal 0.128711 0.167986 0.977351 + outer loop + vertex 1.01616 1.91544 2.60656 + vertex 1.01538 1.91998 2.60589 + vertex 1.0111 1.91666 2.60702 + endloop + endfacet + facet normal 0.131861 0.182148 0.974389 + outer loop + vertex 1.01254 1.91154 2.60778 + vertex 1.01616 1.91544 2.60656 + vertex 1.0111 1.91666 2.60702 + endloop + endfacet + facet normal 0.104796 0.175235 0.978933 + outer loop + vertex 1.01254 1.91154 2.60778 + vertex 1.0111 1.91666 2.60702 + vertex 1.0077 1.91188 2.60824 + endloop + endfacet + facet normal 0.105226 0.183502 0.977371 + outer loop + vertex 1.00864 1.90738 2.60898 + vertex 1.01254 1.91154 2.60778 + vertex 1.0077 1.91188 2.60824 + endloop + endfacet + facet normal 0.0841188 0.179584 0.98014 + outer loop + vertex 1.00864 1.90738 2.60898 + vertex 1.0077 1.91188 2.60824 + vertex 1.00376 1.90796 2.6093 + endloop + endfacet + facet normal 0.084612 0.184242 0.979232 + outer loop + vertex 1.0045 1.90365 2.61004 + vertex 1.00864 1.90738 2.60898 + vertex 1.00376 1.90796 2.6093 + endloop + endfacet + facet normal 0.0743006 0.182681 0.980361 + outer loop + vertex 1.0045 1.90365 2.61004 + vertex 1.00376 1.90796 2.6093 + vertex 0.999119 1.90469 2.61026 + endloop + endfacet + facet normal 0.0742062 0.182174 0.980462 + outer loop + vertex 0.999119 1.90469 2.61026 + vertex 1.00057 1.90031 2.61096 + vertex 1.0045 1.90365 2.61004 + endloop + endfacet + facet normal 0.0759317 0.18021 0.980693 + outer loop + vertex 1.00057 1.90031 2.61096 + vertex 1.00552 1.89934 2.61076 + vertex 1.0045 1.90365 2.61004 + endloop + endfacet + facet normal 0.101955 0.185842 0.977276 + outer loop + vertex 1.0045 1.90365 2.61004 + vertex 1.00552 1.89934 2.61076 + vertex 1.01002 1.90251 2.60968 + endloop + endfacet + facet normal 0.105851 0.180511 0.977861 + outer loop + vertex 1.00552 1.89934 2.61076 + vertex 1.00958 1.89832 2.61051 + vertex 1.01002 1.90251 2.60968 + endloop + endfacet + facet normal 0.177849 0.171161 0.969058 + outer loop + vertex 1.00958 1.89832 2.61051 + vertex 1.0143 1.8987 2.60957 + vertex 1.01002 1.90251 2.60968 + endloop + endfacet + facet normal 0.152089 0.141984 0.978115 + outer loop + vertex 1.01002 1.90251 2.60968 + vertex 1.0143 1.8987 2.60957 + vertex 1.01455 1.90328 2.60887 + endloop + endfacet + facet normal 0.149872 0.153544 0.97671 + outer loop + vertex 1.01455 1.90328 2.60887 + vertex 1.01342 1.90687 2.60848 + vertex 1.01002 1.90251 2.60968 + endloop + endfacet + facet normal 0.122247 0.175173 0.976919 + outer loop + vertex 1.01002 1.90251 2.60968 + vertex 1.01342 1.90687 2.60848 + vertex 1.00864 1.90738 2.60898 + endloop + endfacet + facet normal 0.175206 0.194171 0.965195 + outer loop + vertex 1.00958 1.89832 2.61051 + vertex 1.01114 1.89565 2.61076 + vertex 1.0143 1.8987 2.60957 + endloop + endfacet + facet normal 0.206045 0.162237 0.965 + outer loop + vertex 1.01396 1.89414 2.61041 + vertex 1.0143 1.8987 2.60957 + vertex 1.01114 1.89565 2.61076 + endloop + endfacet + facet normal 0.199345 0.148827 0.968562 + outer loop + vertex 1.01114 1.89565 2.61076 + vertex 1.01058 1.89135 2.61154 + vertex 1.01396 1.89414 2.61041 + endloop + endfacet + facet normal 0.126177 0.16034 0.978964 + outer loop + vertex 1.01114 1.89565 2.61076 + vertex 1.00688 1.89482 2.61145 + vertex 1.01058 1.89135 2.61154 + endloop + endfacet + facet normal 0.134221 0.168841 0.976462 + outer loop + vertex 1.00688 1.89482 2.61145 + vertex 1.00627 1.8904 2.61229 + vertex 1.01058 1.89135 2.61154 + endloop + endfacet + facet normal 0.134246 0.168741 0.976476 + outer loop + vertex 1.00745 1.88665 2.61278 + vertex 1.01058 1.89135 2.61154 + vertex 1.00627 1.8904 2.61229 + endloop + endfacet + facet normal 0.098165 0.158165 0.982521 + outer loop + vertex 1.00745 1.88665 2.61278 + vertex 1.00627 1.8904 2.61229 + vertex 1.00296 1.88682 2.6132 + endloop + endfacet + facet normal 0.0984726 0.17292 0.980001 + outer loop + vertex 1.00372 1.88242 2.6139 + vertex 1.00745 1.88665 2.61278 + vertex 1.00296 1.88682 2.6132 + endloop + endfacet + facet normal 0.0749343 0.169271 0.982717 + outer loop + vertex 1.00372 1.88242 2.6139 + vertex 1.00296 1.88682 2.6132 + vertex 0.998863 1.88272 2.61422 + endloop + endfacet + facet normal 0.0752365 0.175198 0.981654 + outer loop + vertex 0.999996 1.87792 2.61499 + vertex 1.00372 1.88242 2.6139 + vertex 0.998863 1.88272 2.61422 + endloop + endfacet + facet normal 0.0676065 0.173534 0.982505 + outer loop + vertex 0.999996 1.87792 2.61499 + vertex 0.998863 1.88272 2.61422 + vertex 0.994033 1.87931 2.61515 + endloop + endfacet + facet normal 0.067344 0.172381 0.982726 + outer loop + vertex 0.994033 1.87931 2.61515 + vertex 0.995566 1.87482 2.61584 + vertex 0.999996 1.87792 2.61499 + endloop + endfacet + facet normal 0.0680535 0.171401 0.982848 + outer loop + vertex 0.995566 1.87482 2.61584 + vertex 0.999705 1.87377 2.61573 + vertex 0.999996 1.87792 2.61499 + endloop + endfacet + facet normal 0.101567 0.168627 0.980433 + outer loop + vertex 0.999705 1.87377 2.61573 + vertex 1.00424 1.87453 2.61513 + vertex 0.999996 1.87792 2.61499 + endloop + endfacet + facet normal 0.0933733 0.158496 0.982935 + outer loop + vertex 0.999996 1.87792 2.61499 + vertex 1.00424 1.87453 2.61513 + vertex 1.00491 1.87876 2.61439 + endloop + endfacet + facet normal 0.157689 0.147122 0.976468 + outer loop + vertex 1.00424 1.87453 2.61513 + vertex 1.00871 1.87743 2.61397 + vertex 1.00491 1.87876 2.61439 + endloop + endfacet + facet normal 0.156469 0.143404 0.977217 + outer loop + vertex 1.00871 1.87743 2.61397 + vertex 1.00834 1.88202 2.61336 + vertex 1.00491 1.87876 2.61439 + endloop + endfacet + facet normal 0.129307 0.171812 0.976606 + outer loop + vertex 1.00491 1.87876 2.61439 + vertex 1.00834 1.88202 2.61336 + vertex 1.00372 1.88242 2.6139 + endloop + endfacet + facet normal 0.168706 0.130345 0.97701 + outer loop + vertex 1.00951 1.87274 2.61446 + vertex 1.00871 1.87743 2.61397 + vertex 1.00424 1.87453 2.61513 + endloop + endfacet + facet normal 0.182183 0.173508 0.967835 + outer loop + vertex 1.00424 1.87453 2.61513 + vertex 1.00544 1.8701 2.6157 + vertex 1.00951 1.87274 2.61446 + endloop + endfacet + facet normal 0.19171 0.159087 0.968472 + outer loop + vertex 1.00544 1.8701 2.6157 + vertex 1.00898 1.86866 2.61524 + vertex 1.00951 1.87274 2.61446 + endloop + endfacet + facet normal 0.189321 0.152732 0.969964 + outer loop + vertex 1.00898 1.86866 2.61524 + vertex 1.00544 1.8701 2.6157 + vertex 1.00608 1.86583 2.61625 + endloop + endfacet + facet normal 0.122835 0.144313 0.981878 + outer loop + vertex 1.00608 1.86583 2.61625 + vertex 1.00544 1.8701 2.6157 + vertex 1.00131 1.86687 2.61669 + endloop + endfacet + facet normal 0.125447 0.157189 0.979569 + outer loop + vertex 1.00243 1.8618 2.61736 + vertex 1.00608 1.86583 2.61625 + vertex 1.00131 1.86687 2.61669 + endloop + endfacet + facet normal 0.122939 0.158904 0.97961 + outer loop + vertex 1.00544 1.8701 2.6157 + vertex 1.00424 1.87453 2.61513 + vertex 1.00168 1.87122 2.61599 + endloop + endfacet + facet normal 0.11987 0.148052 0.981688 + outer loop + vertex 1.00168 1.87122 2.61599 + vertex 1.00131 1.86687 2.61669 + vertex 1.00544 1.8701 2.6157 + endloop + endfacet + facet normal 0.0735532 0.152658 0.985538 + outer loop + vertex 1.00168 1.87122 2.61599 + vertex 0.997185 1.87023 2.61648 + vertex 1.00131 1.86687 2.61669 + endloop + endfacet + facet normal 0.0738902 0.153065 0.98545 + outer loop + vertex 0.997185 1.87023 2.61648 + vertex 0.996722 1.86563 2.61723 + vertex 1.00131 1.86687 2.61669 + endloop + endfacet + facet normal 0.0723981 0.158266 0.984739 + outer loop + vertex 0.997798 1.86184 2.61776 + vertex 1.00131 1.86687 2.61669 + vertex 0.996722 1.86563 2.61723 + endloop + endfacet + facet normal 0.0610674 0.155226 0.98599 + outer loop + vertex 0.997798 1.86184 2.61776 + vertex 0.996722 1.86563 2.61723 + vertex 0.993152 1.86177 2.61806 + endloop + endfacet + facet normal 0.0609722 0.159173 0.985366 + outer loop + vertex 0.993563 1.85725 2.61876 + vertex 0.997798 1.86184 2.61776 + vertex 0.993152 1.86177 2.61806 + endloop + endfacet + facet normal 0.0607231 0.159153 0.985385 + outer loop + vertex 0.993563 1.85725 2.61876 + vertex 0.993152 1.86177 2.61806 + vertex 0.988761 1.8573 2.61905 + endloop + endfacet + facet normal 0.0607239 0.16012 0.985228 + outer loop + vertex 0.989736 1.85363 2.61959 + vertex 0.993563 1.85725 2.61876 + vertex 0.988761 1.8573 2.61905 + endloop + endfacet + facet normal 0.0644482 0.161051 0.98484 + outer loop + vertex 0.989736 1.85363 2.61959 + vertex 0.988761 1.8573 2.61905 + vertex 0.984705 1.85277 2.62006 + endloop + endfacet + facet normal 0.0643076 0.161809 0.984725 + outer loop + vertex 0.984705 1.85277 2.62006 + vertex 0.989012 1.8494 2.62033 + vertex 0.989736 1.85363 2.61959 + endloop + endfacet + facet normal 0.0597057 0.162623 0.98488 + outer loop + vertex 0.989012 1.8494 2.62033 + vertex 0.993848 1.85274 2.61948 + vertex 0.989736 1.85363 2.61959 + endloop + endfacet + facet normal 0.0649258 0.155295 0.985732 + outer loop + vertex 0.99495 1.84797 2.62016 + vertex 0.993848 1.85274 2.61948 + vertex 0.989012 1.8494 2.62033 + endloop + endfacet + facet normal 0.0659318 0.159581 0.984981 + outer loop + vertex 0.989012 1.8494 2.62033 + vertex 0.990626 1.84499 2.62094 + vertex 0.99495 1.84797 2.62016 + endloop + endfacet + facet normal 0.0675685 0.157281 0.98524 + outer loop + vertex 0.990626 1.84499 2.62094 + vertex 0.99473 1.84389 2.62083 + vertex 0.99495 1.84797 2.62016 + endloop + endfacet + facet normal 0.108185 0.154579 0.982039 + outer loop + vertex 0.99473 1.84389 2.62083 + vertex 0.99919 1.84458 2.62023 + vertex 0.99495 1.84797 2.62016 + endloop + endfacet + facet normal 0.0966976 0.140284 0.985378 + outer loop + vertex 0.99495 1.84797 2.62016 + vertex 0.99919 1.84458 2.62023 + vertex 0.999812 1.84876 2.61957 + endloop + endfacet + facet normal 0.0965695 0.141005 0.985288 + outer loop + vertex 0.999812 1.84876 2.61957 + vertex 0.998744 1.85246 2.61915 + vertex 0.99495 1.84797 2.62016 + endloop + endfacet + facet normal 0.139115 0.152524 0.97846 + outer loop + vertex 0.999812 1.84876 2.61957 + vertex 1.00336 1.85205 2.61856 + vertex 0.998744 1.85246 2.61915 + endloop + endfacet + facet normal 0.13728 0.1258 0.982511 + outer loop + vertex 1.00336 1.85205 2.61856 + vertex 1.0029 1.85688 2.618 + vertex 0.998744 1.85246 2.61915 + endloop + endfacet + facet normal 0.107805 0.153489 0.982252 + outer loop + vertex 0.998744 1.85246 2.61915 + vertex 1.0029 1.85688 2.618 + vertex 0.99826 1.85712 2.61847 + endloop + endfacet + facet normal 0.0761768 0.1507 0.98564 + outer loop + vertex 0.998744 1.85246 2.61915 + vertex 0.99826 1.85712 2.61847 + vertex 0.993848 1.85274 2.61948 + endloop + endfacet + facet normal 0.0650279 0.161717 0.984692 + outer loop + vertex 0.993848 1.85274 2.61948 + vertex 0.99826 1.85712 2.61847 + vertex 0.993563 1.85725 2.61876 + endloop + endfacet + facet normal 0.107241 0.138264 0.984572 + outer loop + vertex 1.0029 1.85688 2.618 + vertex 1.00243 1.8618 2.61736 + vertex 0.99826 1.85712 2.61847 + endloop + endfacet + facet normal 0.0856273 0.157344 0.983825 + outer loop + vertex 0.99826 1.85712 2.61847 + vertex 1.00243 1.8618 2.61736 + vertex 0.997798 1.86184 2.61776 + endloop + endfacet + facet normal 0.16785 0.121507 0.978296 + outer loop + vertex 1.00361 1.84746 2.61908 + vertex 1.00336 1.85205 2.61856 + vertex 0.999812 1.84876 2.61957 + endloop + endfacet + facet normal 0.169958 0.128081 0.977092 + outer loop + vertex 0.99919 1.84458 2.62023 + vertex 1.00361 1.84746 2.61908 + vertex 0.999812 1.84876 2.61957 + endloop + endfacet + facet normal 0.18065 0.111677 0.977187 + outer loop + vertex 1.00448 1.84278 2.61946 + vertex 1.00361 1.84746 2.61908 + vertex 0.99919 1.84458 2.62023 + endloop + endfacet + facet normal 0.195473 0.159316 0.967682 + outer loop + vertex 0.99919 1.84458 2.62023 + vertex 1.00049 1.84018 2.62069 + vertex 1.00448 1.84278 2.61946 + endloop + endfacet + facet normal 0.134065 0.142561 0.980665 + outer loop + vertex 1.00049 1.84018 2.62069 + vertex 0.99919 1.84458 2.62023 + vertex 0.996742 1.84135 2.62103 + endloop + endfacet + facet normal 0.131148 0.132705 0.982441 + outer loop + vertex 0.996742 1.84135 2.62103 + vertex 0.996443 1.83701 2.62166 + vertex 1.00049 1.84018 2.62069 + endloop + endfacet + facet normal 0.0778924 0.137104 0.987489 + outer loop + vertex 0.996742 1.84135 2.62103 + vertex 0.992313 1.84043 2.62151 + vertex 0.996443 1.83701 2.62166 + endloop + endfacet + facet normal 0.0811476 0.141002 0.986678 + outer loop + vertex 0.992313 1.84043 2.62151 + vertex 0.991886 1.83581 2.62221 + vertex 0.996443 1.83701 2.62166 + endloop + endfacet + facet normal 0.0626428 0.142877 0.987756 + outer loop + vertex 0.991886 1.83581 2.62221 + vertex 0.992313 1.84043 2.62151 + vertex 0.987854 1.83668 2.62234 + endloop + endfacet + facet normal 0.062551 0.142442 0.987825 + outer loop + vertex 0.988247 1.83185 2.62301 + vertex 0.991886 1.83581 2.62221 + vertex 0.987854 1.83668 2.62234 + endloop + endfacet + facet normal 0.0611297 0.14234 0.987928 + outer loop + vertex 0.988247 1.83185 2.62301 + vertex 0.987854 1.83668 2.62234 + vertex 0.98343 1.83199 2.62328 + endloop + endfacet + facet normal 0.0611423 0.142916 0.987844 + outer loop + vertex 0.983633 1.82721 2.62396 + vertex 0.988247 1.83185 2.62301 + vertex 0.98343 1.83199 2.62328 + endloop + endfacet + facet normal 0.060122 0.142882 0.987912 + outer loop + vertex 0.983633 1.82721 2.62396 + vertex 0.98343 1.83199 2.62328 + vertex 0.978721 1.82729 2.62425 + endloop + endfacet + facet normal 0.0601258 0.143385 0.987839 + outer loop + vertex 0.97964 1.82356 2.62474 + vertex 0.983633 1.82721 2.62396 + vertex 0.978721 1.82729 2.62425 + endloop + endfacet + facet normal 0.0568156 0.142611 0.988147 + outer loop + vertex 0.97964 1.82356 2.62474 + vertex 0.978721 1.82729 2.62425 + vertex 0.97459 1.8227 2.62515 + endloop + endfacet + facet normal 0.0566967 0.143273 0.988058 + outer loop + vertex 0.97459 1.8227 2.62515 + vertex 0.97892 1.81939 2.62538 + vertex 0.97964 1.82356 2.62474 + endloop + endfacet + facet normal 0.057575 0.143117 0.98803 + outer loop + vertex 0.97892 1.81939 2.62538 + vertex 0.983802 1.82267 2.62462 + vertex 0.97964 1.82356 2.62474 + endloop + endfacet + facet normal 0.0568636 0.144151 0.987921 + outer loop + vertex 0.984791 1.81795 2.62526 + vertex 0.983802 1.82267 2.62462 + vertex 0.97892 1.81939 2.62538 + endloop + endfacet + facet normal 0.0602781 0.144826 0.987619 + outer loop + vertex 0.984791 1.81795 2.62526 + vertex 0.98877 1.82244 2.62435 + vertex 0.983802 1.82267 2.62462 + endloop + endfacet + facet normal 0.0602996 0.145418 0.987531 + outer loop + vertex 0.98877 1.82244 2.62435 + vertex 0.988469 1.82708 2.62369 + vertex 0.983802 1.82267 2.62462 + endloop + endfacet + facet normal 0.0601014 0.145623 0.987513 + outer loop + vertex 0.983802 1.82267 2.62462 + vertex 0.988469 1.82708 2.62369 + vertex 0.983633 1.82721 2.62396 + endloop + endfacet + facet normal 0.0708053 0.145986 0.98675 + outer loop + vertex 0.98877 1.82244 2.62435 + vertex 0.993292 1.82709 2.62334 + vertex 0.988469 1.82708 2.62369 + endloop + endfacet + facet normal 0.0708837 0.139401 0.987696 + outer loop + vertex 0.993292 1.82709 2.62334 + vertex 0.992927 1.83192 2.62269 + vertex 0.988469 1.82708 2.62369 + endloop + endfacet + facet normal 0.0656351 0.14417 0.987374 + outer loop + vertex 0.988469 1.82708 2.62369 + vertex 0.992927 1.83192 2.62269 + vertex 0.988247 1.83185 2.62301 + endloop + endfacet + facet normal 0.0963581 0.141001 0.985309 + outer loop + vertex 0.993292 1.82709 2.62334 + vertex 0.997551 1.83188 2.62224 + vertex 0.992927 1.83192 2.62269 + endloop + endfacet + facet normal 0.0963996 0.132331 0.986507 + outer loop + vertex 0.997551 1.83188 2.62224 + vertex 0.996443 1.83701 2.62166 + vertex 0.992927 1.83192 2.62269 + endloop + endfacet + facet normal 0.0805104 0.143294 0.9864 + outer loop + vertex 0.992927 1.83192 2.62269 + vertex 0.996443 1.83701 2.62166 + vertex 0.991886 1.83581 2.62221 + endloop + endfacet + facet normal 0.114953 0.124522 0.985535 + outer loop + vertex 0.997853 1.82694 2.62283 + vertex 0.997551 1.83188 2.62224 + vertex 0.993292 1.82709 2.62334 + endloop + endfacet + facet normal 0.115167 0.13661 0.983908 + outer loop + vertex 0.993474 1.8224 2.62397 + vertex 0.997853 1.82694 2.62283 + vertex 0.993292 1.82709 2.62334 + endloop + endfacet + facet normal 0.139952 0.112673 0.983727 + outer loop + vertex 0.997933 1.82204 2.62338 + vertex 0.997853 1.82694 2.62283 + vertex 0.993474 1.8224 2.62397 + endloop + endfacet + facet normal 0.140683 0.124367 0.982212 + outer loop + vertex 0.993726 1.81785 2.62451 + vertex 0.997933 1.82204 2.62338 + vertex 0.993474 1.8224 2.62397 + endloop + endfacet + facet normal 0.10294 0.12285 0.987072 + outer loop + vertex 0.993726 1.81785 2.62451 + vertex 0.993474 1.8224 2.62397 + vertex 0.989712 1.81882 2.62481 + endloop + endfacet + facet normal 0.103387 0.124797 0.986781 + outer loop + vertex 0.989067 1.8146 2.62541 + vertex 0.993726 1.81785 2.62451 + vertex 0.989712 1.81882 2.62481 + endloop + endfacet + facet normal 0.0665385 0.130775 0.989177 + outer loop + vertex 0.984791 1.81795 2.62526 + vertex 0.989067 1.8146 2.62541 + vertex 0.989712 1.81882 2.62481 + endloop + endfacet + facet normal 0.0720457 0.137755 0.987843 + outer loop + vertex 0.984535 1.81395 2.62583 + vertex 0.989067 1.8146 2.62541 + vertex 0.984791 1.81795 2.62526 + endloop + endfacet + facet normal 0.0552722 0.138961 0.988754 + outer loop + vertex 0.980536 1.81508 2.6259 + vertex 0.984535 1.81395 2.62583 + vertex 0.984791 1.81795 2.62526 + endloop + endfacet + facet normal 0.0525342 0.129224 0.990223 + outer loop + vertex 0.984535 1.81395 2.62583 + vertex 0.980536 1.81508 2.6259 + vertex 0.982291 1.81062 2.62639 + endloop + endfacet + facet normal 0.0558345 0.127017 0.990328 + outer loop + vertex 0.986616 1.81139 2.62604 + vertex 0.984535 1.81395 2.62583 + vertex 0.982291 1.81062 2.62639 + endloop + endfacet + facet normal 0.0569538 0.121075 0.991008 + outer loop + vertex 0.986616 1.81139 2.62604 + vertex 0.982291 1.81062 2.62639 + vertex 0.986623 1.80707 2.62657 + endloop + endfacet + facet normal 0.0826726 0.120895 0.989217 + outer loop + vertex 0.986616 1.81139 2.62604 + vertex 0.986623 1.80707 2.62657 + vertex 0.990657 1.81007 2.62587 + endloop + endfacet + facet normal 0.0853871 0.129382 0.987912 + outer loop + vertex 0.990657 1.81007 2.62587 + vertex 0.989067 1.8146 2.62541 + vertex 0.986616 1.81139 2.62604 + endloop + endfacet + facet normal 0.128368 0.143806 0.981245 + outer loop + vertex 0.989067 1.8146 2.62541 + vertex 0.990657 1.81007 2.62587 + vertex 0.994903 1.81282 2.62491 + endloop + endfacet + facet normal 0.132883 0.136944 0.981625 + outer loop + vertex 0.990657 1.81007 2.62587 + vertex 0.994654 1.80858 2.62553 + vertex 0.994903 1.81282 2.62491 + endloop + endfacet + facet normal 0.229828 0.128734 0.96468 + outer loop + vertex 0.994654 1.80858 2.62553 + vertex 0.99917 1.80847 2.62447 + vertex 0.994903 1.81282 2.62491 + endloop + endfacet + facet normal 0.206756 0.105299 0.97271 + outer loop + vertex 0.994903 1.81282 2.62491 + vertex 0.99917 1.80847 2.62447 + vertex 0.99962 1.81324 2.62386 + endloop + endfacet + facet normal 0.208873 0.085534 0.974195 + outer loop + vertex 0.99962 1.81324 2.62386 + vertex 0.998396 1.81727 2.62377 + vertex 0.994903 1.81282 2.62491 + endloop + endfacet + facet normal 0.229577 0.1553 0.960821 + outer loop + vertex 0.994654 1.80858 2.62553 + vertex 0.996282 1.80577 2.6256 + vertex 0.99917 1.80847 2.62447 + endloop + endfacet + facet normal 0.25763 0.124168 0.958232 + outer loop + vertex 0.998927 1.80415 2.6251 + vertex 0.99917 1.80847 2.62447 + vertex 0.996282 1.80577 2.6256 + endloop + endfacet + facet normal 0.243256 0.0986645 0.964931 + outer loop + vertex 0.996282 1.80577 2.6256 + vertex 0.99579 1.80164 2.62614 + vertex 0.998927 1.80415 2.6251 + endloop + endfacet + facet normal 0.154473 0.111469 0.981689 + outer loop + vertex 0.996282 1.80577 2.6256 + vertex 0.992173 1.80537 2.62629 + vertex 0.99579 1.80164 2.62614 + endloop + endfacet + facet normal 0.154395 0.112162 0.981622 + outer loop + vertex 0.996282 1.80577 2.6256 + vertex 0.994654 1.80858 2.62553 + vertex 0.992173 1.80537 2.62629 + endloop + endfacet + facet normal 0.130669 0.130784 0.982762 + outer loop + vertex 0.994654 1.80858 2.62553 + vertex 0.990657 1.81007 2.62587 + vertex 0.992173 1.80537 2.62629 + endloop + endfacet + facet normal 0.0856865 0.116898 0.989441 + outer loop + vertex 0.992173 1.80537 2.62629 + vertex 0.990657 1.81007 2.62587 + vertex 0.986623 1.80707 2.62657 + endloop + endfacet + facet normal 0.0889873 0.127927 0.987783 + outer loop + vertex 0.987914 1.8019 2.62712 + vertex 0.992173 1.80537 2.62629 + vertex 0.986623 1.80707 2.62657 + endloop + endfacet + facet normal 0.0624873 0.12161 0.990609 + outer loop + vertex 0.987914 1.8019 2.62712 + vertex 0.986623 1.80707 2.62657 + vertex 0.983162 1.80217 2.62739 + endloop + endfacet + facet normal 0.0625327 0.122521 0.990494 + outer loop + vertex 0.983513 1.79719 2.62798 + vertex 0.987914 1.8019 2.62712 + vertex 0.983162 1.80217 2.62739 + endloop + endfacet + facet normal 0.055369 0.122073 0.990975 + outer loop + vertex 0.983513 1.79719 2.62798 + vertex 0.983162 1.80217 2.62739 + vertex 0.97855 1.79715 2.62827 + endloop + endfacet + facet normal 0.0553602 0.122699 0.990899 + outer loop + vertex 0.978413 1.79212 2.6289 + vertex 0.983513 1.79719 2.62798 + vertex 0.97855 1.79715 2.62827 + endloop + endfacet + facet normal 0.0531995 0.122771 0.991008 + outer loop + vertex 0.978413 1.79212 2.6289 + vertex 0.97855 1.79715 2.62827 + vertex 0.973479 1.79221 2.62915 + endloop + endfacet + facet normal 0.0531879 0.121854 0.991122 + outer loop + vertex 0.973411 1.78769 2.62971 + vertex 0.978413 1.79212 2.6289 + vertex 0.973479 1.79221 2.62915 + endloop + endfacet + facet normal 0.0515973 0.121888 0.991202 + outer loop + vertex 0.973411 1.78769 2.62971 + vertex 0.973479 1.79221 2.62915 + vertex 0.969376 1.78847 2.62982 + endloop + endfacet + facet normal 0.0512639 0.120128 0.991434 + outer loop + vertex 0.968557 1.78438 2.63036 + vertex 0.973411 1.78769 2.62971 + vertex 0.969376 1.78847 2.62982 + endloop + endfacet + facet normal 0.0501039 0.120364 0.991465 + outer loop + vertex 0.96448 1.7874 2.6302 + vertex 0.968557 1.78438 2.63036 + vertex 0.969376 1.78847 2.62982 + endloop + endfacet + facet normal 0.0503347 0.119348 0.991576 + outer loop + vertex 0.969376 1.78847 2.62982 + vertex 0.968573 1.79212 2.62942 + vertex 0.96448 1.7874 2.6302 + endloop + endfacet + facet normal 0.0497976 0.119809 0.991547 + outer loop + vertex 0.96448 1.7874 2.6302 + vertex 0.968573 1.79212 2.62942 + vertex 0.963454 1.79217 2.62968 + endloop + endfacet + facet normal 0.045207 0.118858 0.991882 + outer loop + vertex 0.96448 1.7874 2.6302 + vertex 0.963454 1.79217 2.62968 + vertex 0.959005 1.78837 2.63033 + endloop + endfacet + facet normal 0.0453445 0.119653 0.99178 + outer loop + vertex 0.959005 1.78837 2.63033 + vertex 0.960219 1.7843 2.63077 + vertex 0.96448 1.7874 2.6302 + endloop + endfacet + facet normal 0.0455557 0.119367 0.991805 + outer loop + vertex 0.960219 1.7843 2.63077 + vertex 0.964169 1.78345 2.63069 + vertex 0.96448 1.7874 2.6302 + endloop + endfacet + facet normal 0.045263 0.118 0.991981 + outer loop + vertex 0.964169 1.78345 2.63069 + vertex 0.960219 1.7843 2.63077 + vertex 0.962025 1.78012 2.63118 + endloop + endfacet + facet normal 0.046823 0.117 0.992028 + outer loop + vertex 0.966196 1.78112 2.63087 + vertex 0.964169 1.78345 2.63069 + vertex 0.962025 1.78012 2.63118 + endloop + endfacet + facet normal 0.0475198 0.114179 0.992323 + outer loop + vertex 0.966196 1.78112 2.63087 + vertex 0.962025 1.78012 2.63118 + vertex 0.966274 1.77707 2.63133 + endloop + endfacet + facet normal 0.0468419 0.114169 0.992356 + outer loop + vertex 0.966196 1.78112 2.63087 + vertex 0.966274 1.77707 2.63133 + vertex 0.970171 1.78025 2.63078 + endloop + endfacet + facet normal 0.0480617 0.119786 0.991636 + outer loop + vertex 0.970171 1.78025 2.63078 + vertex 0.968557 1.78438 2.63036 + vertex 0.966196 1.78112 2.63087 + endloop + endfacet + facet normal 0.0477993 0.119686 0.991661 + outer loop + vertex 0.968557 1.78438 2.63036 + vertex 0.970171 1.78025 2.63078 + vertex 0.973925 1.78333 2.63023 + endloop + endfacet + facet normal 0.0454923 0.122451 0.991431 + outer loop + vertex 0.970171 1.78025 2.63078 + vertex 0.975094 1.77916 2.63069 + vertex 0.973925 1.78333 2.63023 + endloop + endfacet + facet normal 0.0481298 0.123167 0.991218 + outer loop + vertex 0.973925 1.78333 2.63023 + vertex 0.975094 1.77916 2.63069 + vertex 0.979645 1.78225 2.63009 + endloop + endfacet + facet normal 0.0485899 0.125634 0.990886 + outer loop + vertex 0.979645 1.78225 2.63009 + vertex 0.978515 1.78724 2.62951 + vertex 0.973925 1.78333 2.63023 + endloop + endfacet + facet normal 0.0499275 0.124087 0.991015 + outer loop + vertex 0.973925 1.78333 2.63023 + vertex 0.978515 1.78724 2.62951 + vertex 0.973411 1.78769 2.62971 + endloop + endfacet + facet normal 0.0558256 0.127205 0.990304 + outer loop + vertex 0.979645 1.78225 2.63009 + vertex 0.983711 1.78726 2.62921 + vertex 0.978515 1.78724 2.62951 + endloop + endfacet + facet normal 0.055852 0.124696 0.990622 + outer loop + vertex 0.983711 1.78726 2.62921 + vertex 0.983491 1.79211 2.62861 + vertex 0.978515 1.78724 2.62951 + endloop + endfacet + facet normal 0.055113 0.125441 0.990569 + outer loop + vertex 0.978515 1.78724 2.62951 + vertex 0.983491 1.79211 2.62861 + vertex 0.978413 1.79212 2.6289 + endloop + endfacet + facet normal 0.0743193 0.125372 0.989322 + outer loop + vertex 0.983711 1.78726 2.62921 + vertex 0.988377 1.79217 2.62824 + vertex 0.983491 1.79211 2.62861 + endloop + endfacet + facet normal 0.0745156 0.115619 0.990495 + outer loop + vertex 0.988377 1.79217 2.62824 + vertex 0.988233 1.79705 2.62768 + vertex 0.983491 1.79211 2.62861 + endloop + endfacet + facet normal 0.0669957 0.122787 0.990169 + outer loop + vertex 0.983491 1.79211 2.62861 + vertex 0.988233 1.79705 2.62768 + vertex 0.983513 1.79719 2.62798 + endloop + endfacet + facet normal 0.109215 0.116268 0.987195 + outer loop + vertex 0.988377 1.79217 2.62824 + vertex 0.992631 1.79694 2.62721 + vertex 0.988233 1.79705 2.62768 + endloop + endfacet + facet normal 0.109062 0.102756 0.98871 + outer loop + vertex 0.992631 1.79694 2.62721 + vertex 0.991705 1.80086 2.6269 + vertex 0.988233 1.79705 2.62768 + endloop + endfacet + facet normal 0.0903326 0.11979 0.988681 + outer loop + vertex 0.988233 1.79705 2.62768 + vertex 0.991705 1.80086 2.6269 + vertex 0.987914 1.8019 2.62712 + endloop + endfacet + facet normal 0.129788 0.0978354 0.986703 + outer loop + vertex 0.992893 1.79203 2.62766 + vertex 0.992631 1.79694 2.62721 + vertex 0.988377 1.79217 2.62824 + endloop + endfacet + facet normal 0.130066 0.114876 0.984828 + outer loop + vertex 0.9885 1.78735 2.62879 + vertex 0.992893 1.79203 2.62766 + vertex 0.988377 1.79217 2.62824 + endloop + endfacet + facet normal 0.152214 0.0938595 0.983881 + outer loop + vertex 0.992907 1.78703 2.62814 + vertex 0.992893 1.79203 2.62766 + vertex 0.9885 1.78735 2.62879 + endloop + endfacet + facet normal 0.153228 0.111903 0.981834 + outer loop + vertex 0.988719 1.78272 2.62928 + vertex 0.992907 1.78703 2.62814 + vertex 0.9885 1.78735 2.62879 + endloop + endfacet + facet normal 0.104001 0.110283 0.988444 + outer loop + vertex 0.988719 1.78272 2.62928 + vertex 0.9885 1.78735 2.62879 + vertex 0.984747 1.78341 2.62962 + endloop + endfacet + facet normal 0.104368 0.112539 0.988151 + outer loop + vertex 0.984433 1.77846 2.63022 + vertex 0.988719 1.78272 2.62928 + vertex 0.984747 1.78341 2.62962 + endloop + endfacet + facet normal 0.0640873 0.115461 0.991242 + outer loop + vertex 0.979645 1.78225 2.63009 + vertex 0.984433 1.77846 2.63022 + vertex 0.984747 1.78341 2.62962 + endloop + endfacet + facet normal 0.0701005 0.123008 0.989927 + outer loop + vertex 0.979279 1.77801 2.63064 + vertex 0.984433 1.77846 2.63022 + vertex 0.979645 1.78225 2.63009 + endloop + endfacet + facet normal 0.0694011 0.130328 0.989039 + outer loop + vertex 0.979279 1.77801 2.63064 + vertex 0.98129 1.77535 2.63085 + vertex 0.984433 1.77846 2.63022 + endloop + endfacet + facet normal 0.0791535 0.12056 0.989545 + outer loop + vertex 0.984557 1.77402 2.63075 + vertex 0.984433 1.77846 2.63022 + vertex 0.98129 1.77535 2.63085 + endloop + endfacet + facet normal 0.0692723 0.0959716 0.992971 + outer loop + vertex 0.98129 1.77535 2.63085 + vertex 0.981616 1.77098 2.63125 + vertex 0.984557 1.77402 2.63075 + endloop + endfacet + facet normal 0.0738068 0.0916029 0.993057 + outer loop + vertex 0.98623 1.77115 2.63089 + vertex 0.984557 1.77402 2.63075 + vertex 0.981616 1.77098 2.63125 + endloop + endfacet + facet normal 0.0744515 0.0766609 0.994274 + outer loop + vertex 0.98623 1.77115 2.63089 + vertex 0.981616 1.77098 2.63125 + vertex 0.985847 1.76692 2.63124 + endloop + endfacet + facet normal 0.13775 0.0704073 0.987961 + outer loop + vertex 0.98623 1.77115 2.63089 + vertex 0.985847 1.76692 2.63124 + vertex 0.989161 1.76941 2.6306 + endloop + endfacet + facet normal 0.159244 0.107772 0.981339 + outer loop + vertex 0.989161 1.76941 2.6306 + vertex 0.989356 1.77401 2.63007 + vertex 0.98623 1.77115 2.63089 + endloop + endfacet + facet normal 0.0765596 0.07886 0.993942 + outer loop + vertex 0.981616 1.77098 2.63125 + vertex 0.981707 1.76616 2.63162 + vertex 0.985847 1.76692 2.63124 + endloop + endfacet + facet normal 0.0792647 0.064674 0.994753 + outer loop + vertex 0.982869 1.76225 2.63178 + vertex 0.985847 1.76692 2.63124 + vertex 0.981707 1.76616 2.63162 + endloop + endfacet + facet normal 0.0555338 0.0576957 0.996788 + outer loop + vertex 0.982869 1.76225 2.63178 + vertex 0.981707 1.76616 2.63162 + vertex 0.978489 1.76236 2.63202 + endloop + endfacet + facet normal 0.0554862 0.0554167 0.99692 + outer loop + vertex 0.978747 1.75755 2.63228 + vertex 0.982869 1.76225 2.63178 + vertex 0.978489 1.76236 2.63202 + endloop + endfacet + facet normal 0.0498866 0.0551323 0.997232 + outer loop + vertex 0.978747 1.75755 2.63228 + vertex 0.978489 1.76236 2.63202 + vertex 0.973878 1.75748 2.63252 + endloop + endfacet + facet normal 0.0643651 0.0476237 0.996789 + outer loop + vertex 0.98332 1.75742 2.63199 + vertex 0.982869 1.76225 2.63178 + vertex 0.978747 1.75755 2.63228 + endloop + endfacet + facet normal 0.0644829 0.0524393 0.99654 + outer loop + vertex 0.978749 1.75254 2.63254 + vertex 0.98332 1.75742 2.63199 + vertex 0.978747 1.75755 2.63228 + endloop + endfacet + facet normal 0.0527847 0.0524713 0.997226 + outer loop + vertex 0.978749 1.75254 2.63254 + vertex 0.978747 1.75755 2.63228 + vertex 0.973774 1.75239 2.63281 + endloop + endfacet + facet normal 0.101066 0.0509145 0.993576 + outer loop + vertex 0.98332 1.75742 2.63199 + vertex 0.987075 1.76176 2.63138 + vertex 0.982869 1.76225 2.63178 + endloop + endfacet + facet normal 0.117166 0.0368109 0.99243 + outer loop + vertex 0.987505 1.75678 2.63152 + vertex 0.987075 1.76176 2.63138 + vertex 0.98332 1.75742 2.63199 + endloop + endfacet + facet normal 0.118217 0.043933 0.992015 + outer loop + vertex 0.983421 1.75239 2.6322 + vertex 0.987505 1.75678 2.63152 + vertex 0.98332 1.75742 2.63199 + endloop + endfacet + facet normal 0.0742904 0.0432293 0.996299 + outer loop + vertex 0.983421 1.75239 2.6322 + vertex 0.98332 1.75742 2.63199 + vertex 0.978749 1.75254 2.63254 + endloop + endfacet + facet normal 0.0746377 0.0555504 0.995662 + outer loop + vertex 0.978661 1.74744 2.63283 + vertex 0.983421 1.75239 2.6322 + vertex 0.978749 1.75254 2.63254 + endloop + endfacet + facet normal 0.0564559 0.0559305 0.996837 + outer loop + vertex 0.978661 1.74744 2.63283 + vertex 0.978749 1.75254 2.63254 + vertex 0.973602 1.74727 2.63313 + endloop + endfacet + facet normal 0.0819318 0.0485167 0.995456 + outer loop + vertex 0.983513 1.74723 2.63244 + vertex 0.983421 1.75239 2.6322 + vertex 0.978661 1.74744 2.63283 + endloop + endfacet + facet normal 0.0825584 0.0647948 0.994478 + outer loop + vertex 0.978563 1.74229 2.63317 + vertex 0.983513 1.74723 2.63244 + vertex 0.978661 1.74744 2.63283 + endloop + endfacet + facet normal 0.0588087 0.0653547 0.996128 + outer loop + vertex 0.978563 1.74229 2.63317 + vertex 0.978661 1.74744 2.63283 + vertex 0.973439 1.74214 2.63349 + endloop + endfacet + facet normal 0.0584133 0.076971 0.995321 + outer loop + vertex 0.973305 1.73704 2.63389 + vertex 0.978563 1.74229 2.63317 + vertex 0.973439 1.74214 2.63349 + endloop + endfacet + facet normal 0.0600255 0.0753598 0.995348 + outer loop + vertex 0.978434 1.73715 2.63357 + vertex 0.978563 1.74229 2.63317 + vertex 0.973305 1.73704 2.63389 + endloop + endfacet + facet normal 0.0597959 0.0837596 0.99469 + outer loop + vertex 0.973266 1.73206 2.63431 + vertex 0.978434 1.73715 2.63357 + vertex 0.973305 1.73704 2.63389 + endloop + endfacet + facet normal 0.0500077 0.0838814 0.99522 + outer loop + vertex 0.973266 1.73206 2.63431 + vertex 0.973305 1.73704 2.63389 + vertex 0.968266 1.73217 2.63455 + endloop + endfacet + facet normal 0.0500808 0.0880191 0.994859 + outer loop + vertex 0.968499 1.72761 2.63494 + vertex 0.973266 1.73206 2.63431 + vertex 0.968266 1.73217 2.63455 + endloop + endfacet + facet normal 0.0460826 0.0878334 0.995069 + outer loop + vertex 0.968499 1.72761 2.63494 + vertex 0.968266 1.73217 2.63455 + vertex 0.96436 1.7286 2.63505 + endloop + endfacet + facet normal 0.0461462 0.0881034 0.995042 + outer loop + vertex 0.963731 1.72441 2.63545 + vertex 0.968499 1.72761 2.63494 + vertex 0.96436 1.7286 2.63505 + endloop + endfacet + facet normal 0.0454006 0.0892021 0.994978 + outer loop + vertex 0.969637 1.72265 2.63534 + vertex 0.968499 1.72761 2.63494 + vertex 0.963731 1.72441 2.63545 + endloop + endfacet + facet normal 0.0497542 0.0901776 0.994682 + outer loop + vertex 0.969637 1.72265 2.63534 + vertex 0.973581 1.72729 2.63472 + vertex 0.968499 1.72761 2.63494 + endloop + endfacet + facet normal 0.0504282 0.0896066 0.9947 + outer loop + vertex 0.974681 1.72346 2.63501 + vertex 0.973581 1.72729 2.63472 + vertex 0.969637 1.72265 2.63534 + endloop + endfacet + facet normal 0.0507898 0.0874217 0.994876 + outer loop + vertex 0.969637 1.72265 2.63534 + vertex 0.974392 1.71873 2.63544 + vertex 0.974681 1.72346 2.63501 + endloop + endfacet + facet normal 0.0726928 0.0859731 0.993642 + outer loop + vertex 0.974392 1.71873 2.63544 + vertex 0.978792 1.72276 2.63477 + vertex 0.974681 1.72346 2.63501 + endloop + endfacet + facet normal 0.0726938 0.0859792 0.993641 + outer loop + vertex 0.978792 1.72276 2.63477 + vertex 0.978539 1.7273 2.63439 + vertex 0.974681 1.72346 2.63501 + endloop + endfacet + facet normal 0.104545 0.0875086 0.990663 + outer loop + vertex 0.978792 1.72276 2.63477 + vertex 0.983312 1.7272 2.6339 + vertex 0.978539 1.7273 2.63439 + endloop + endfacet + facet normal 0.10441 0.0762783 0.991605 + outer loop + vertex 0.983312 1.7272 2.6339 + vertex 0.983301 1.73219 2.63352 + vertex 0.978539 1.7273 2.63439 + endloop + endfacet + facet normal 0.0939566 0.0865008 0.991811 + outer loop + vertex 0.978539 1.7273 2.63439 + vertex 0.983301 1.73219 2.63352 + vertex 0.978381 1.73211 2.63399 + endloop + endfacet + facet normal 0.0650523 0.0857522 0.994191 + outer loop + vertex 0.978539 1.7273 2.63439 + vertex 0.978381 1.73211 2.63399 + vertex 0.973581 1.72729 2.63472 + endloop + endfacet + facet normal 0.0615798 0.0891985 0.994108 + outer loop + vertex 0.973581 1.72729 2.63472 + vertex 0.978381 1.73211 2.63399 + vertex 0.973266 1.73206 2.63431 + endloop + endfacet + facet normal 0.0942711 0.0729099 0.992873 + outer loop + vertex 0.983301 1.73219 2.63352 + vertex 0.983238 1.73711 2.63316 + vertex 0.978381 1.73211 2.63399 + endloop + endfacet + facet normal 0.0854965 0.0814565 0.993003 + outer loop + vertex 0.978381 1.73211 2.63399 + vertex 0.983238 1.73711 2.63316 + vertex 0.978434 1.73715 2.63357 + endloop + endfacet + facet normal 0.0854725 0.0733495 0.993637 + outer loop + vertex 0.983238 1.73711 2.63316 + vertex 0.983374 1.74205 2.63278 + vertex 0.978434 1.73715 2.63357 + endloop + endfacet + facet normal 0.127083 0.0718783 0.989284 + outer loop + vertex 0.983238 1.73711 2.63316 + vertex 0.987014 1.74113 2.63238 + vertex 0.983374 1.74205 2.63278 + endloop + endfacet + facet normal 0.128824 0.0791368 0.988505 + outer loop + vertex 0.987014 1.74113 2.63238 + vertex 0.988292 1.74612 2.63182 + vertex 0.983374 1.74205 2.63278 + endloop + endfacet + facet normal 0.143205 0.0615729 0.987776 + outer loop + vertex 0.983374 1.74205 2.63278 + vertex 0.988292 1.74612 2.63182 + vertex 0.983513 1.74723 2.63244 + endloop + endfacet + facet normal 0.139173 0.0433398 0.989319 + outer loop + vertex 0.988292 1.74612 2.63182 + vertex 0.987756 1.75166 2.63165 + vertex 0.983513 1.74723 2.63244 + endloop + endfacet + facet normal 0.143313 0.0564232 0.988068 + outer loop + vertex 0.987672 1.73708 2.63252 + vertex 0.987014 1.74113 2.63238 + vertex 0.983238 1.73711 2.63316 + endloop + endfacet + facet normal 0.143251 0.0731108 0.986982 + outer loop + vertex 0.983301 1.73219 2.63352 + vertex 0.987672 1.73708 2.63252 + vertex 0.983238 1.73711 2.63316 + endloop + endfacet + facet normal 0.157839 0.0758533 0.984547 + outer loop + vertex 0.983312 1.7272 2.6339 + vertex 0.987874 1.73209 2.63279 + vertex 0.983301 1.73219 2.63352 + endloop + endfacet + facet normal 0.157688 0.0599589 0.985667 + outer loop + vertex 0.987874 1.73209 2.63279 + vertex 0.987672 1.73708 2.63252 + vertex 0.983301 1.73219 2.63352 + endloop + endfacet + facet normal 0.172618 0.0617328 0.983052 + outer loop + vertex 0.987875 1.72701 2.63311 + vertex 0.987874 1.73209 2.63279 + vertex 0.983312 1.7272 2.6339 + endloop + endfacet + facet normal 0.173055 0.0772869 0.981875 + outer loop + vertex 0.983461 1.72247 2.63424 + vertex 0.987875 1.72701 2.63311 + vertex 0.983312 1.7272 2.6339 + endloop + endfacet + facet normal 0.189378 0.0609407 0.980011 + outer loop + vertex 0.987933 1.72207 2.6334 + vertex 0.987875 1.72701 2.63311 + vertex 0.983461 1.72247 2.63424 + endloop + endfacet + facet normal 0.190529 0.0763431 0.978709 + outer loop + vertex 0.983726 1.71793 2.63455 + vertex 0.987933 1.72207 2.6334 + vertex 0.983461 1.72247 2.63424 + endloop + endfacet + facet normal 0.203109 0.0631267 0.977119 + outer loop + vertex 0.988302 1.71739 2.63363 + vertex 0.987933 1.72207 2.6334 + vertex 0.983726 1.71793 2.63455 + endloop + endfacet + facet normal 0.20506 0.082833 0.975238 + outer loop + vertex 0.984619 1.71299 2.63478 + vertex 0.988302 1.71739 2.63363 + vertex 0.983726 1.71793 2.63455 + endloop + endfacet + facet normal 0.232423 0.0587459 0.970839 + outer loop + vertex 0.989156 1.71362 2.63365 + vertex 0.988302 1.71739 2.63363 + vertex 0.984619 1.71299 2.63478 + endloop + endfacet + facet normal 0.230195 0.0740647 0.970322 + outer loop + vertex 0.984619 1.71299 2.63478 + vertex 0.988131 1.70906 2.63425 + vertex 0.989156 1.71362 2.63365 + endloop + endfacet + facet normal 0.115681 0.076101 0.990367 + outer loop + vertex 0.983461 1.72247 2.63424 + vertex 0.983312 1.7272 2.6339 + vertex 0.978792 1.72276 2.63477 + endloop + endfacet + facet normal 0.116467 0.0912198 0.988997 + outer loop + vertex 0.979657 1.71906 2.63501 + vertex 0.983461 1.72247 2.63424 + vertex 0.978792 1.72276 2.63477 + endloop + endfacet + facet normal 0.132192 0.0735918 0.988488 + outer loop + vertex 0.983726 1.71793 2.63455 + vertex 0.983461 1.72247 2.63424 + vertex 0.979657 1.71906 2.63501 + endloop + endfacet + facet normal 0.132879 0.0761786 0.9882 + outer loop + vertex 0.978988 1.71484 2.63542 + vertex 0.983726 1.71793 2.63455 + vertex 0.979657 1.71906 2.63501 + endloop + endfacet + facet normal 0.0759818 0.0857049 0.993419 + outer loop + vertex 0.974392 1.71873 2.63544 + vertex 0.978988 1.71484 2.63542 + vertex 0.979657 1.71906 2.63501 + endloop + endfacet + facet normal 0.0804263 0.0909601 0.992602 + outer loop + vertex 0.974545 1.71441 2.63582 + vertex 0.978988 1.71484 2.63542 + vertex 0.974392 1.71873 2.63544 + endloop + endfacet + facet normal 0.052316 0.0901345 0.994555 + outer loop + vertex 0.974545 1.71441 2.63582 + vertex 0.974392 1.71873 2.63544 + vertex 0.971395 1.71569 2.63587 + endloop + endfacet + facet normal 0.0501091 0.0846622 0.995149 + outer loop + vertex 0.971395 1.71569 2.63587 + vertex 0.971771 1.71126 2.63623 + vertex 0.974545 1.71441 2.63582 + endloop + endfacet + facet normal 0.0533273 0.0818404 0.995218 + outer loop + vertex 0.97645 1.71164 2.63595 + vertex 0.974545 1.71441 2.63582 + vertex 0.971771 1.71126 2.63623 + endloop + endfacet + facet normal 0.0532232 0.0830487 0.995123 + outer loop + vertex 0.97645 1.71164 2.63595 + vertex 0.971771 1.71126 2.63623 + vertex 0.976268 1.70731 2.63632 + endloop + endfacet + facet normal 0.0870755 0.0814299 0.992868 + outer loop + vertex 0.97645 1.71164 2.63595 + vertex 0.976268 1.70731 2.63632 + vertex 0.980287 1.71023 2.63573 + endloop + endfacet + facet normal 0.090511 0.0909513 0.991734 + outer loop + vertex 0.980287 1.71023 2.63573 + vertex 0.978988 1.71484 2.63542 + vertex 0.97645 1.71164 2.63595 + endloop + endfacet + facet normal 0.147289 0.106404 0.983353 + outer loop + vertex 0.978988 1.71484 2.63542 + vertex 0.980287 1.71023 2.63573 + vertex 0.984619 1.71299 2.63478 + endloop + endfacet + facet normal 0.148077 0.105175 0.983367 + outer loop + vertex 0.980287 1.71023 2.63573 + vertex 0.983899 1.70868 2.63535 + vertex 0.984619 1.71299 2.63478 + endloop + endfacet + facet normal 0.143045 0.0929885 0.985338 + outer loop + vertex 0.983899 1.70868 2.63535 + vertex 0.980287 1.71023 2.63573 + vertex 0.981014 1.70597 2.63602 + endloop + endfacet + facet normal 0.0854357 0.0836753 0.992824 + outer loop + vertex 0.981014 1.70597 2.63602 + vertex 0.980287 1.71023 2.63573 + vertex 0.976268 1.70731 2.63632 + endloop + endfacet + facet normal 0.0868386 0.0887747 0.992259 + outer loop + vertex 0.977614 1.70225 2.63665 + vertex 0.981014 1.70597 2.63602 + vertex 0.976268 1.70731 2.63632 + endloop + endfacet + facet normal 0.0575296 0.0811587 0.99504 + outer loop + vertex 0.977614 1.70225 2.63665 + vertex 0.976268 1.70731 2.63632 + vertex 0.973108 1.70242 2.6369 + endloop + endfacet + facet normal 0.057591 0.0829949 0.994884 + outer loop + vertex 0.973625 1.69763 2.63727 + vertex 0.977614 1.70225 2.63665 + vertex 0.973108 1.70242 2.6369 + endloop + endfacet + facet normal 0.0474296 0.0819469 0.995507 + outer loop + vertex 0.973625 1.69763 2.63727 + vertex 0.973108 1.70242 2.6369 + vertex 0.968827 1.69757 2.6375 + endloop + endfacet + facet normal 0.0474357 0.0815981 0.995536 + outer loop + vertex 0.968815 1.69253 2.63792 + vertex 0.973625 1.69763 2.63727 + vertex 0.968827 1.69757 2.6375 + endloop + endfacet + facet normal 0.04646 0.0816041 0.995581 + outer loop + vertex 0.968815 1.69253 2.63792 + vertex 0.968827 1.69757 2.6375 + vertex 0.96374 1.69236 2.63817 + endloop + endfacet + facet normal 0.0465517 0.0791554 0.995775 + outer loop + vertex 0.963529 1.6872 2.63859 + vertex 0.968815 1.69253 2.63792 + vertex 0.96374 1.69236 2.63817 + endloop + endfacet + facet normal 0.0452443 0.0792133 0.99583 + outer loop + vertex 0.963529 1.6872 2.63859 + vertex 0.96374 1.69236 2.63817 + vertex 0.958385 1.68706 2.63883 + endloop + endfacet + facet normal 0.0453438 0.0760573 0.996072 + outer loop + vertex 0.958167 1.68194 2.63923 + vertex 0.963529 1.6872 2.63859 + vertex 0.958385 1.68706 2.63883 + endloop + endfacet + facet normal 0.0410865 0.0762522 0.996242 + outer loop + vertex 0.958167 1.68194 2.63923 + vertex 0.958385 1.68706 2.63883 + vertex 0.953138 1.68194 2.63944 + endloop + endfacet + facet normal 0.0410926 0.0730789 0.996479 + outer loop + vertex 0.953081 1.6771 2.6398 + vertex 0.958167 1.68194 2.63923 + vertex 0.953138 1.68194 2.63944 + endloop + endfacet + facet normal 0.0355304 0.0731601 0.996687 + outer loop + vertex 0.953081 1.6771 2.6398 + vertex 0.953138 1.68194 2.63944 + vertex 0.948328 1.6774 2.63995 + endloop + endfacet + facet normal 0.0354132 0.071194 0.996834 + outer loop + vertex 0.948496 1.67311 2.64025 + vertex 0.953081 1.6771 2.6398 + vertex 0.948328 1.6774 2.63995 + endloop + endfacet + facet normal 0.0301089 0.0709991 0.997022 + outer loop + vertex 0.948496 1.67311 2.64025 + vertex 0.948328 1.6774 2.63995 + vertex 0.944583 1.674 2.6403 + endloop + endfacet + facet normal 0.0297092 0.0692253 0.997159 + outer loop + vertex 0.943901 1.67003 2.6406 + vertex 0.948496 1.67311 2.64025 + vertex 0.944583 1.674 2.6403 + endloop + endfacet + facet normal 0.0213083 0.0706765 0.997272 + outer loop + vertex 0.939764 1.67292 2.64048 + vertex 0.943901 1.67003 2.6406 + vertex 0.944583 1.674 2.6403 + endloop + endfacet + facet normal 0.0221159 0.0718291 0.997172 + outer loop + vertex 0.939467 1.66904 2.64077 + vertex 0.943901 1.67003 2.6406 + vertex 0.939764 1.67292 2.64048 + endloop + endfacet + facet normal 0.0221882 0.0715105 0.997193 + outer loop + vertex 0.939467 1.66904 2.64077 + vertex 0.941528 1.66675 2.64088 + vertex 0.943901 1.67003 2.6406 + endloop + endfacet + facet normal 0.0269934 0.0680435 0.997317 + outer loop + vertex 0.945535 1.66589 2.64083 + vertex 0.943901 1.67003 2.6406 + vertex 0.941528 1.66675 2.64088 + endloop + endfacet + facet normal 0.0266975 0.0666636 0.997418 + outer loop + vertex 0.941528 1.66675 2.64088 + vertex 0.941532 1.66258 2.64116 + vertex 0.945535 1.66589 2.64083 + endloop + endfacet + facet normal 0.0278964 0.0652208 0.997481 + outer loop + vertex 0.946917 1.66164 2.64107 + vertex 0.945535 1.66589 2.64083 + vertex 0.941532 1.66258 2.64116 + endloop + endfacet + facet normal 0.0281657 0.0667808 0.99737 + outer loop + vertex 0.943121 1.65762 2.64145 + vertex 0.946917 1.66164 2.64107 + vertex 0.941532 1.66258 2.64116 + endloop + endfacet + facet normal 0.0204375 0.0643233 0.99772 + outer loop + vertex 0.943121 1.65762 2.64145 + vertex 0.941532 1.66258 2.64116 + vertex 0.938193 1.65759 2.64155 + endloop + endfacet + facet normal 0.0204352 0.0646629 0.997698 + outer loop + vertex 0.938774 1.65271 2.64186 + vertex 0.943121 1.65762 2.64145 + vertex 0.938193 1.65759 2.64155 + endloop + endfacet + facet normal 0.00445723 0.0627804 0.998017 + outer loop + vertex 0.938774 1.65271 2.64186 + vertex 0.938193 1.65759 2.64155 + vertex 0.933732 1.6526 2.64189 + endloop + endfacet + facet normal 0.00441722 0.0646783 0.997896 + outer loop + vertex 0.933731 1.64747 2.64222 + vertex 0.938774 1.65271 2.64186 + vertex 0.933732 1.6526 2.64189 + endloop + endfacet + facet normal -0.0178585 0.0646748 0.997747 + outer loop + vertex 0.933731 1.64747 2.64222 + vertex 0.933732 1.6526 2.64189 + vertex 0.928595 1.64734 2.64214 + endloop + endfacet + facet normal -0.0178624 0.0648334 0.997736 + outer loop + vertex 0.928453 1.64223 2.64247 + vertex 0.933731 1.64747 2.64222 + vertex 0.928595 1.64734 2.64214 + endloop + endfacet + facet normal -0.0156659 0.0626297 0.997914 + outer loop + vertex 0.93357 1.64233 2.64254 + vertex 0.933731 1.64747 2.64222 + vertex 0.928453 1.64223 2.64247 + endloop + endfacet + facet normal -0.0156169 0.0599592 0.998079 + outer loop + vertex 0.928356 1.63722 2.64277 + vertex 0.93357 1.64233 2.64254 + vertex 0.928453 1.64223 2.64247 + endloop + endfacet + facet normal -0.0143797 0.0587005 0.998172 + outer loop + vertex 0.933448 1.63728 2.64283 + vertex 0.93357 1.64233 2.64254 + vertex 0.928356 1.63722 2.64277 + endloop + endfacet + facet normal -0.0143276 0.0539325 0.998442 + outer loop + vertex 0.928358 1.63229 2.64303 + vertex 0.933448 1.63728 2.64283 + vertex 0.928356 1.63722 2.64277 + endloop + endfacet + facet normal -0.045373 0.0538694 0.997517 + outer loop + vertex 0.928358 1.63229 2.64303 + vertex 0.928356 1.63722 2.64277 + vertex 0.923311 1.63224 2.6428 + endloop + endfacet + facet normal -0.0453457 0.0500273 0.997718 + outer loop + vertex 0.923321 1.6273 2.64305 + vertex 0.928358 1.63229 2.64303 + vertex 0.923311 1.63224 2.6428 + endloop + endfacet + facet normal -0.0468061 0.0515026 0.997575 + outer loop + vertex 0.928413 1.62737 2.64329 + vertex 0.928358 1.63229 2.64303 + vertex 0.923321 1.6273 2.64305 + endloop + endfacet + facet normal -0.0468014 0.0510398 0.997599 + outer loop + vertex 0.923366 1.62235 2.64331 + vertex 0.928413 1.62737 2.64329 + vertex 0.923321 1.6273 2.64305 + endloop + endfacet + facet normal -0.0149009 0.0519094 0.998541 + outer loop + vertex 0.928413 1.62737 2.64329 + vertex 0.933424 1.63231 2.64311 + vertex 0.928358 1.63229 2.64303 + endloop + endfacet + facet normal -0.0141657 0.0511659 0.99859 + outer loop + vertex 0.933458 1.62737 2.64336 + vertex 0.933424 1.63231 2.64311 + vertex 0.928413 1.62737 2.64329 + endloop + endfacet + facet normal -0.0141659 0.0507425 0.998611 + outer loop + vertex 0.92847 1.62243 2.64354 + vertex 0.933458 1.62737 2.64336 + vertex 0.928413 1.62737 2.64329 + endloop + endfacet + facet normal -0.0460894 0.0503242 0.997669 + outer loop + vertex 0.92847 1.62243 2.64354 + vertex 0.928413 1.62737 2.64329 + vertex 0.923366 1.62235 2.64331 + endloop + endfacet + facet normal -0.0460983 0.0509871 0.997635 + outer loop + vertex 0.923401 1.61737 2.64356 + vertex 0.92847 1.62243 2.64354 + vertex 0.923366 1.62235 2.64331 + endloop + endfacet + facet normal -0.0922137 0.0505015 0.994458 + outer loop + vertex 0.923401 1.61737 2.64356 + vertex 0.923366 1.62235 2.64331 + vertex 0.918394 1.61725 2.64311 + endloop + endfacet + facet normal -0.0942001 0.0524504 0.994171 + outer loop + vertex 0.918394 1.61725 2.64311 + vertex 0.923366 1.62235 2.64331 + vertex 0.918311 1.62224 2.64283 + endloop + endfacet + facet normal -0.0941691 0.050444 0.994277 + outer loop + vertex 0.923366 1.62235 2.64331 + vertex 0.923321 1.6273 2.64305 + vertex 0.918311 1.62224 2.64283 + endloop + endfacet + facet normal -0.0920019 0.0482839 0.994588 + outer loop + vertex 0.918311 1.62224 2.64283 + vertex 0.923321 1.6273 2.64305 + vertex 0.918362 1.62732 2.64259 + endloop + endfacet + facet normal -0.0919913 0.049769 0.994515 + outer loop + vertex 0.923321 1.6273 2.64305 + vertex 0.923311 1.63224 2.6428 + vertex 0.918362 1.62732 2.64259 + endloop + endfacet + facet normal -0.0442522 0.0491364 0.997811 + outer loop + vertex 0.928501 1.61746 2.64379 + vertex 0.92847 1.62243 2.64354 + vertex 0.923401 1.61737 2.64356 + endloop + endfacet + facet normal -0.0442619 0.0497996 0.997778 + outer loop + vertex 0.923402 1.61238 2.64381 + vertex 0.928501 1.61746 2.64379 + vertex 0.923401 1.61737 2.64356 + endloop + endfacet + facet normal -0.0904968 0.049634 0.994659 + outer loop + vertex 0.923402 1.61238 2.64381 + vertex 0.923401 1.61737 2.64356 + vertex 0.918398 1.61225 2.64336 + endloop + endfacet + facet normal -0.0412009 0.0467295 0.998058 + outer loop + vertex 0.92851 1.61247 2.64402 + vertex 0.928501 1.61746 2.64379 + vertex 0.923402 1.61238 2.64381 + endloop + endfacet + facet normal -0.0412009 0.0467293 0.998058 + outer loop + vertex 0.923395 1.60738 2.64405 + vertex 0.92851 1.61247 2.64402 + vertex 0.923402 1.61238 2.64381 + endloop + endfacet + facet normal -0.0122595 0.0488218 0.998732 + outer loop + vertex 0.933504 1.62242 2.6436 + vertex 0.933458 1.62737 2.64336 + vertex 0.92847 1.62243 2.64354 + endloop + endfacet + facet normal -0.0122582 0.0493806 0.998705 + outer loop + vertex 0.928501 1.61746 2.64379 + vertex 0.933504 1.62242 2.6436 + vertex 0.92847 1.62243 2.64354 + endloop + endfacet + facet normal 0.00978248 0.0490255 0.99875 + outer loop + vertex 0.933504 1.62242 2.6436 + vertex 0.93843 1.62732 2.64331 + vertex 0.933458 1.62737 2.64336 + endloop + endfacet + facet normal 0.00979653 0.0504962 0.998676 + outer loop + vertex 0.93843 1.62732 2.64331 + vertex 0.938442 1.63229 2.64306 + vertex 0.933458 1.62737 2.64336 + endloop + endfacet + facet normal 0.0241917 0.050451 0.998434 + outer loop + vertex 0.93843 1.62732 2.64331 + vertex 0.943455 1.6323 2.64294 + vertex 0.938442 1.63229 2.64306 + endloop + endfacet + facet normal 0.0241838 0.0533652 0.998282 + outer loop + vertex 0.943455 1.6323 2.64294 + vertex 0.943581 1.63737 2.64267 + vertex 0.938442 1.63229 2.64306 + endloop + endfacet + facet normal 0.0239261 0.0536254 0.998274 + outer loop + vertex 0.938442 1.63229 2.64306 + vertex 0.943581 1.63737 2.64267 + vertex 0.938518 1.63732 2.64279 + endloop + endfacet + facet normal 0.00897507 0.0538652 0.998508 + outer loop + vertex 0.938442 1.63229 2.64306 + vertex 0.938518 1.63732 2.64279 + vertex 0.933424 1.63231 2.64311 + endloop + endfacet + facet normal 0.00843364 0.0544145 0.998483 + outer loop + vertex 0.933424 1.63231 2.64311 + vertex 0.938518 1.63732 2.64279 + vertex 0.933448 1.63728 2.64283 + endloop + endfacet + facet normal 0.00841059 0.0573938 0.998316 + outer loop + vertex 0.938518 1.63732 2.64279 + vertex 0.938669 1.64241 2.6425 + vertex 0.933448 1.63728 2.64283 + endloop + endfacet + facet normal 0.0235633 0.0569311 0.9981 + outer loop + vertex 0.938518 1.63732 2.64279 + vertex 0.943741 1.6425 2.64237 + vertex 0.938669 1.64241 2.6425 + endloop + endfacet + facet normal 0.0235064 0.0598685 0.997929 + outer loop + vertex 0.943741 1.6425 2.64237 + vertex 0.943846 1.64763 2.64206 + vertex 0.938669 1.64241 2.6425 + endloop + endfacet + facet normal 0.023071 0.060299 0.997914 + outer loop + vertex 0.938669 1.64241 2.6425 + vertex 0.943846 1.64763 2.64206 + vertex 0.93883 1.64757 2.64218 + endloop + endfacet + facet normal 0.0075976 0.0607937 0.998121 + outer loop + vertex 0.938669 1.64241 2.6425 + vertex 0.93883 1.64757 2.64218 + vertex 0.93357 1.64233 2.64254 + endloop + endfacet + facet normal 0.0230501 0.0618257 0.997821 + outer loop + vertex 0.943846 1.64763 2.64206 + vertex 0.943747 1.65269 2.64175 + vertex 0.93883 1.64757 2.64218 + endloop + endfacet + facet normal 0.0219278 0.0628985 0.997779 + outer loop + vertex 0.93883 1.64757 2.64218 + vertex 0.943747 1.65269 2.64175 + vertex 0.938774 1.65271 2.64186 + endloop + endfacet + facet normal 0.0316224 0.0619784 0.997576 + outer loop + vertex 0.943846 1.64763 2.64206 + vertex 0.94849 1.65249 2.64161 + vertex 0.943747 1.65269 2.64175 + endloop + endfacet + facet normal 0.031678 0.0633445 0.997489 + outer loop + vertex 0.94849 1.65249 2.64161 + vertex 0.947983 1.65712 2.64133 + vertex 0.943747 1.65269 2.64175 + endloop + endfacet + facet normal 0.0305478 0.0644238 0.997455 + outer loop + vertex 0.943747 1.65269 2.64175 + vertex 0.947983 1.65712 2.64133 + vertex 0.943121 1.65762 2.64145 + endloop + endfacet + facet normal 0.0360092 0.0638089 0.997312 + outer loop + vertex 0.94849 1.65249 2.64161 + vertex 0.951949 1.65607 2.64126 + vertex 0.947983 1.65712 2.64133 + endloop + endfacet + facet normal 0.0362138 0.0645917 0.997254 + outer loop + vertex 0.951949 1.65607 2.64126 + vertex 0.952175 1.66036 2.64097 + vertex 0.947983 1.65712 2.64133 + endloop + endfacet + facet normal 0.0353895 0.0656533 0.997215 + outer loop + vertex 0.947983 1.65712 2.64133 + vertex 0.952175 1.66036 2.64097 + vertex 0.946917 1.66164 2.64107 + endloop + endfacet + facet normal 0.035113 0.0645143 0.997299 + outer loop + vertex 0.952175 1.66036 2.64097 + vertex 0.950355 1.66479 2.64075 + vertex 0.946917 1.66164 2.64107 + endloop + endfacet + facet normal 0.0365951 0.0651187 0.997206 + outer loop + vertex 0.954375 1.66359 2.64068 + vertex 0.950355 1.66479 2.64075 + vertex 0.952175 1.66036 2.64097 + endloop + endfacet + facet normal 0.0384673 0.0638466 0.997218 + outer loop + vertex 0.956335 1.6609 2.64078 + vertex 0.954375 1.66359 2.64068 + vertex 0.952175 1.66036 2.64097 + endloop + endfacet + facet normal 0.0386412 0.0625424 0.997294 + outer loop + vertex 0.956335 1.6609 2.64078 + vertex 0.952175 1.66036 2.64097 + vertex 0.95682 1.65638 2.64104 + endloop + endfacet + facet normal 0.0394156 0.0626234 0.997259 + outer loop + vertex 0.956335 1.6609 2.64078 + vertex 0.95682 1.65638 2.64104 + vertex 0.959523 1.65943 2.64074 + endloop + endfacet + facet normal 0.0401692 0.0642551 0.997125 + outer loop + vertex 0.959523 1.65943 2.64074 + vertex 0.959289 1.66376 2.64047 + vertex 0.956335 1.6609 2.64078 + endloop + endfacet + facet normal 0.0404883 0.0642714 0.997111 + outer loop + vertex 0.959523 1.65943 2.64074 + vertex 0.964417 1.65911 2.64057 + vertex 0.959289 1.66376 2.64047 + endloop + endfacet + facet normal 0.0417601 0.0656686 0.996967 + outer loop + vertex 0.959289 1.66376 2.64047 + vertex 0.964417 1.65911 2.64057 + vertex 0.964507 1.66388 2.64025 + endloop + endfacet + facet normal 0.0416929 0.0684011 0.996786 + outer loop + vertex 0.964507 1.66388 2.64025 + vertex 0.963537 1.66773 2.64002 + vertex 0.959289 1.66376 2.64047 + endloop + endfacet + facet normal 0.0427713 0.0672512 0.996819 + outer loop + vertex 0.959289 1.66376 2.64047 + vertex 0.963537 1.66773 2.64002 + vertex 0.959485 1.66854 2.64014 + endloop + endfacet + facet normal 0.0402341 0.0673616 0.996917 + outer loop + vertex 0.954614 1.66766 2.6404 + vertex 0.959289 1.66376 2.64047 + vertex 0.959485 1.66854 2.64014 + endloop + endfacet + facet normal 0.0399146 0.0690981 0.996811 + outer loop + vertex 0.959485 1.66854 2.64014 + vertex 0.958386 1.67229 2.63993 + vertex 0.954614 1.66766 2.6404 + endloop + endfacet + facet normal 0.0401503 0.0689065 0.996815 + outer loop + vertex 0.954614 1.66766 2.6404 + vertex 0.958386 1.67229 2.63993 + vertex 0.953365 1.67247 2.64012 + endloop + endfacet + facet normal 0.0364906 0.0679682 0.99702 + outer loop + vertex 0.954614 1.66766 2.6404 + vertex 0.953365 1.67247 2.64012 + vertex 0.949161 1.66891 2.64051 + endloop + endfacet + facet normal 0.0364404 0.0677477 0.997037 + outer loop + vertex 0.949161 1.66891 2.64051 + vertex 0.950355 1.66479 2.64075 + vertex 0.954614 1.66766 2.6404 + endloop + endfacet + facet normal 0.0329389 0.0667446 0.997226 + outer loop + vertex 0.945535 1.66589 2.64083 + vertex 0.950355 1.66479 2.64075 + vertex 0.949161 1.66891 2.64051 + endloop + endfacet + facet normal 0.0355896 0.0690268 0.99698 + outer loop + vertex 0.949161 1.66891 2.64051 + vertex 0.953365 1.67247 2.64012 + vertex 0.948496 1.67311 2.64025 + endloop + endfacet + facet normal 0.040233 0.0713928 0.996637 + outer loop + vertex 0.958386 1.67229 2.63993 + vertex 0.958077 1.67698 2.6396 + vertex 0.953365 1.67247 2.64012 + endloop + endfacet + facet normal 0.0405933 0.0710177 0.996649 + outer loop + vertex 0.953365 1.67247 2.64012 + vertex 0.958077 1.67698 2.6396 + vertex 0.953081 1.6771 2.6398 + endloop + endfacet + facet normal 0.0435995 0.0716042 0.99648 + outer loop + vertex 0.958386 1.67229 2.63993 + vertex 0.963177 1.67704 2.63938 + vertex 0.958077 1.67698 2.6396 + endloop + endfacet + facet normal 0.0435559 0.0744022 0.996277 + outer loop + vertex 0.963177 1.67704 2.63938 + vertex 0.963302 1.68207 2.63899 + vertex 0.958077 1.67698 2.6396 + endloop + endfacet + facet normal 0.0444736 0.0734638 0.996306 + outer loop + vertex 0.958077 1.67698 2.6396 + vertex 0.963302 1.68207 2.63899 + vertex 0.958167 1.68194 2.63923 + endloop + endfacet + facet normal 0.0466486 0.0743152 0.996143 + outer loop + vertex 0.963177 1.67704 2.63938 + vertex 0.968482 1.68229 2.63874 + vertex 0.963302 1.68207 2.63899 + endloop + endfacet + facet normal 0.0465469 0.0765855 0.995976 + outer loop + vertex 0.968482 1.68229 2.63874 + vertex 0.96866 1.68742 2.63833 + vertex 0.963302 1.68207 2.63899 + endloop + endfacet + facet normal 0.0461671 0.0769643 0.995964 + outer loop + vertex 0.963302 1.68207 2.63899 + vertex 0.96866 1.68742 2.63833 + vertex 0.963529 1.6872 2.63859 + endloop + endfacet + facet normal 0.0537989 0.0763074 0.995632 + outer loop + vertex 0.968482 1.68229 2.63874 + vertex 0.973689 1.68757 2.63805 + vertex 0.96866 1.68742 2.63833 + endloop + endfacet + facet normal 0.053824 0.0755669 0.995687 + outer loop + vertex 0.973689 1.68757 2.63805 + vertex 0.973721 1.69266 2.63766 + vertex 0.96866 1.68742 2.63833 + endloop + endfacet + facet normal 0.0497057 0.0795363 0.995592 + outer loop + vertex 0.96866 1.68742 2.63833 + vertex 0.973721 1.69266 2.63766 + vertex 0.968815 1.69253 2.63792 + endloop + endfacet + facet normal 0.0751369 0.0753303 0.994324 + outer loop + vertex 0.973689 1.68757 2.63805 + vertex 0.978354 1.69249 2.63732 + vertex 0.973721 1.69266 2.63766 + endloop + endfacet + facet normal 0.0749801 0.0703306 0.994702 + outer loop + vertex 0.978354 1.69249 2.63732 + vertex 0.97814 1.69745 2.63699 + vertex 0.973721 1.69266 2.63766 + endloop + endfacet + facet normal 0.0648384 0.0796865 0.994709 + outer loop + vertex 0.973721 1.69266 2.63766 + vertex 0.97814 1.69745 2.63699 + vertex 0.973625 1.69763 2.63727 + endloop + endfacet + facet normal 0.121385 0.0720078 0.98999 + outer loop + vertex 0.978354 1.69249 2.63732 + vertex 0.982311 1.6968 2.63653 + vertex 0.97814 1.69745 2.63699 + endloop + endfacet + facet normal 0.120519 0.0660422 0.990512 + outer loop + vertex 0.982311 1.6968 2.63653 + vertex 0.981839 1.70154 2.63627 + vertex 0.97814 1.69745 2.63699 + endloop + endfacet + facet normal 0.104232 0.0809002 0.991257 + outer loop + vertex 0.97814 1.69745 2.63699 + vertex 0.981839 1.70154 2.63627 + vertex 0.977614 1.70225 2.63665 + endloop + endfacet + facet normal 0.134689 0.0596413 0.989091 + outer loop + vertex 0.982716 1.69178 2.63677 + vertex 0.982311 1.6968 2.63653 + vertex 0.978354 1.69249 2.63732 + endloop + endfacet + facet normal 0.135925 0.0677634 0.988399 + outer loop + vertex 0.978534 1.68733 2.63765 + vertex 0.982716 1.69178 2.63677 + vertex 0.978354 1.69249 2.63732 + endloop + endfacet + facet normal 0.148434 0.0557856 0.987348 + outer loop + vertex 0.983352 1.68623 2.63699 + vertex 0.982716 1.69178 2.63677 + vertex 0.978534 1.68733 2.63765 + endloop + endfacet + facet normal 0.151121 0.0682331 0.986158 + outer loop + vertex 0.978457 1.68217 2.63802 + vertex 0.983352 1.68623 2.63699 + vertex 0.978534 1.68733 2.63765 + endloop + endfacet + facet normal 0.0868893 0.0697418 0.993774 + outer loop + vertex 0.978457 1.68217 2.63802 + vertex 0.978534 1.68733 2.63765 + vertex 0.973612 1.68241 2.63843 + endloop + endfacet + facet normal 0.0868971 0.0699206 0.993761 + outer loop + vertex 0.973502 1.67726 2.6388 + vertex 0.978457 1.68217 2.63802 + vertex 0.973612 1.68241 2.63843 + endloop + endfacet + facet normal 0.0603045 0.0706293 0.995678 + outer loop + vertex 0.973502 1.67726 2.6388 + vertex 0.973612 1.68241 2.63843 + vertex 0.968347 1.67718 2.63912 + endloop + endfacet + facet normal 0.0603025 0.0707253 0.995671 + outer loop + vertex 0.968283 1.67217 2.63948 + vertex 0.973502 1.67726 2.6388 + vertex 0.968347 1.67718 2.63912 + endloop + endfacet + facet normal 0.0487164 0.0709187 0.996292 + outer loop + vertex 0.968283 1.67217 2.63948 + vertex 0.968347 1.67718 2.63912 + vertex 0.963295 1.67228 2.63971 + endloop + endfacet + facet normal 0.0487019 0.0701963 0.996344 + outer loop + vertex 0.963537 1.66773 2.64002 + vertex 0.968283 1.67217 2.63948 + vertex 0.963295 1.67228 2.63971 + endloop + endfacet + facet normal 0.0492269 0.0696359 0.996357 + outer loop + vertex 0.9684 1.66738 2.63981 + vertex 0.968283 1.67217 2.63948 + vertex 0.963537 1.66773 2.64002 + endloop + endfacet + facet normal 0.0635857 0.0699304 0.995523 + outer loop + vertex 0.9684 1.66738 2.63981 + vertex 0.973405 1.67217 2.63915 + vertex 0.968283 1.67217 2.63948 + endloop + endfacet + facet normal 0.0672999 0.0660515 0.995544 + outer loop + vertex 0.973367 1.66717 2.63949 + vertex 0.973405 1.67217 2.63915 + vertex 0.9684 1.66738 2.63981 + endloop + endfacet + facet normal 0.0674678 0.070511 0.995227 + outer loop + vertex 0.968678 1.66282 2.64011 + vertex 0.973367 1.66717 2.63949 + vertex 0.9684 1.66738 2.63981 + endloop + endfacet + facet normal 0.0499586 0.0695186 0.996329 + outer loop + vertex 0.968678 1.66282 2.64011 + vertex 0.9684 1.66738 2.63981 + vertex 0.964507 1.66388 2.64025 + endloop + endfacet + facet normal 0.0709894 0.066723 0.995243 + outer loop + vertex 0.973501 1.66241 2.63979 + vertex 0.973367 1.66717 2.63949 + vertex 0.968678 1.66282 2.64011 + endloop + endfacet + facet normal 0.0714781 0.07296 0.99477 + outer loop + vertex 0.969693 1.65894 2.64032 + vertex 0.973501 1.66241 2.63979 + vertex 0.968678 1.66282 2.64011 + endloop + endfacet + facet normal 0.047784 0.066847 0.996618 + outer loop + vertex 0.969693 1.65894 2.64032 + vertex 0.968678 1.66282 2.64011 + vertex 0.964417 1.65911 2.64057 + endloop + endfacet + facet normal 0.0476528 0.062053 0.996935 + outer loop + vertex 0.964417 1.65911 2.64057 + vertex 0.969661 1.65418 2.64062 + vertex 0.969693 1.65894 2.64032 + endloop + endfacet + facet normal 0.0754964 0.0617607 0.995232 + outer loop + vertex 0.969661 1.65418 2.64062 + vertex 0.973812 1.65788 2.64008 + vertex 0.969693 1.65894 2.64032 + endloop + endfacet + facet normal 0.0786481 0.0582217 0.995201 + outer loop + vertex 0.974881 1.65407 2.64021 + vertex 0.973812 1.65788 2.64008 + vertex 0.969661 1.65418 2.64062 + endloop + endfacet + facet normal 0.0786441 0.0579772 0.995215 + outer loop + vertex 0.969661 1.65418 2.64062 + vertex 0.974849 1.64929 2.6405 + vertex 0.974881 1.65407 2.64021 + endloop + endfacet + facet normal 0.141488 0.057149 0.988289 + outer loop + vertex 0.974849 1.64929 2.6405 + vertex 0.978858 1.65301 2.63971 + vertex 0.974881 1.65407 2.64021 + endloop + endfacet + facet normal 0.141391 0.0567683 0.988325 + outer loop + vertex 0.978858 1.65301 2.63971 + vertex 0.97845 1.65749 2.63951 + vertex 0.974881 1.65407 2.64021 + endloop + endfacet + facet normal 0.15024 0.0475345 0.987506 + outer loop + vertex 0.979898 1.64921 2.63973 + vertex 0.978858 1.65301 2.63971 + vertex 0.974849 1.64929 2.6405 + endloop + endfacet + facet normal 0.150334 0.0593549 0.986852 + outer loop + vertex 0.974849 1.64929 2.6405 + vertex 0.979603 1.64446 2.64006 + vertex 0.979898 1.64921 2.63973 + endloop + endfacet + facet normal 0.165157 0.0742236 0.98347 + outer loop + vertex 0.975043 1.64472 2.64081 + vertex 0.979603 1.64446 2.64006 + vertex 0.974849 1.64929 2.6405 + endloop + endfacet + facet normal 0.0912215 0.0717624 0.993242 + outer loop + vertex 0.975043 1.64472 2.64081 + vertex 0.974849 1.64929 2.6405 + vertex 0.971877 1.64645 2.64097 + endloop + endfacet + facet normal 0.0813368 0.053485 0.995251 + outer loop + vertex 0.971877 1.64645 2.64097 + vertex 0.971995 1.64167 2.64122 + vertex 0.975043 1.64472 2.64081 + endloop + endfacet + facet normal 0.0860385 0.0487579 0.995098 + outer loop + vertex 0.976544 1.64166 2.64083 + vertex 0.975043 1.64472 2.64081 + vertex 0.971995 1.64167 2.64122 + endloop + endfacet + facet normal 0.086032 0.0538007 0.994839 + outer loop + vertex 0.976544 1.64166 2.64083 + vertex 0.971995 1.64167 2.64122 + vertex 0.975992 1.63729 2.64111 + endloop + endfacet + facet normal 0.155119 0.044553 0.986891 + outer loop + vertex 0.976544 1.64166 2.64083 + vertex 0.975992 1.63729 2.64111 + vertex 0.979309 1.6398 2.64048 + endloop + endfacet + facet normal 0.175881 0.0764911 0.981435 + outer loop + vertex 0.979309 1.6398 2.64048 + vertex 0.979603 1.64446 2.64006 + vertex 0.976544 1.64166 2.64083 + endloop + endfacet + facet normal 0.0842712 0.0521901 0.995075 + outer loop + vertex 0.971995 1.64167 2.64122 + vertex 0.971876 1.63647 2.6415 + vertex 0.975992 1.63729 2.64111 + endloop + endfacet + facet normal 0.084178 0.052653 0.995059 + outer loop + vertex 0.972882 1.63245 2.64163 + vertex 0.975992 1.63729 2.64111 + vertex 0.971876 1.63647 2.6415 + endloop + endfacet + facet normal 0.0549882 0.0454405 0.997452 + outer loop + vertex 0.972882 1.63245 2.64163 + vertex 0.971876 1.63647 2.6415 + vertex 0.968512 1.63251 2.64187 + endloop + endfacet + facet normal 0.0550384 0.0499323 0.997235 + outer loop + vertex 0.968689 1.62765 2.6421 + vertex 0.972882 1.63245 2.64163 + vertex 0.968512 1.63251 2.64187 + endloop + endfacet + facet normal 0.0457677 0.0496177 0.997719 + outer loop + vertex 0.968689 1.62765 2.6421 + vertex 0.968512 1.63251 2.64187 + vertex 0.963798 1.62757 2.64233 + endloop + endfacet + facet normal 0.045765 0.0497607 0.997712 + outer loop + vertex 0.963702 1.62251 2.64259 + vertex 0.968689 1.62765 2.6421 + vertex 0.963798 1.62757 2.64233 + endloop + endfacet + facet normal 0.0450984 0.0497748 0.997742 + outer loop + vertex 0.963702 1.62251 2.64259 + vertex 0.963798 1.62757 2.64233 + vertex 0.958568 1.62238 2.64283 + endloop + endfacet + facet normal 0.0451536 0.047733 0.997839 + outer loop + vertex 0.958483 1.61734 2.64307 + vertex 0.963702 1.62251 2.64259 + vertex 0.958568 1.62238 2.64283 + endloop + endfacet + facet normal 0.0434144 0.0477661 0.997915 + outer loop + vertex 0.958483 1.61734 2.64307 + vertex 0.958568 1.62238 2.64283 + vertex 0.953375 1.61729 2.6433 + endloop + endfacet + facet normal 0.0434431 0.0453259 0.998027 + outer loop + vertex 0.953367 1.6123 2.64352 + vertex 0.958483 1.61734 2.64307 + vertex 0.953375 1.61729 2.6433 + endloop + endfacet + facet normal 0.0379879 0.0453452 0.998249 + outer loop + vertex 0.953367 1.6123 2.64352 + vertex 0.953375 1.61729 2.6433 + vertex 0.948366 1.61232 2.64371 + endloop + endfacet + facet normal 0.0379796 0.043115 0.998348 + outer loop + vertex 0.948395 1.60735 2.64393 + vertex 0.953367 1.6123 2.64352 + vertex 0.948366 1.61232 2.64371 + endloop + endfacet + facet normal 0.0310308 0.0430844 0.998589 + outer loop + vertex 0.948395 1.60735 2.64393 + vertex 0.948366 1.61232 2.64371 + vertex 0.943456 1.60739 2.64408 + endloop + endfacet + facet normal 0.0310113 0.0408002 0.998686 + outer loop + vertex 0.943485 1.60241 2.64428 + vertex 0.948395 1.60735 2.64393 + vertex 0.943456 1.60739 2.64408 + endloop + endfacet + facet normal 0.0243746 0.0407693 0.998871 + outer loop + vertex 0.943485 1.60241 2.64428 + vertex 0.943456 1.60739 2.64408 + vertex 0.938545 1.60246 2.6444 + endloop + endfacet + facet normal 0.0243613 0.0391218 0.998937 + outer loop + vertex 0.938568 1.59747 2.64459 + vertex 0.943485 1.60241 2.64428 + vertex 0.938545 1.60246 2.6444 + endloop + endfacet + facet normal 0.0150298 0.0390856 0.999123 + outer loop + vertex 0.938568 1.59747 2.64459 + vertex 0.938545 1.60246 2.6444 + vertex 0.933588 1.5975 2.64467 + endloop + endfacet + facet normal 0.0150235 0.0380003 0.999165 + outer loop + vertex 0.933605 1.59251 2.64486 + vertex 0.938568 1.59747 2.64459 + vertex 0.933588 1.5975 2.64467 + endloop + endfacet + facet normal -0.00266736 0.0379456 0.999276 + outer loop + vertex 0.933605 1.59251 2.64486 + vertex 0.933588 1.5975 2.64467 + vertex 0.928558 1.59249 2.64484 + endloop + endfacet + facet normal -0.00266394 0.0368127 0.999319 + outer loop + vertex 0.928553 1.5875 2.64503 + vertex 0.933605 1.59251 2.64486 + vertex 0.928558 1.59249 2.64484 + endloop + endfacet + facet normal -0.0344798 0.0368205 0.998727 + outer loop + vertex 0.928553 1.5875 2.64503 + vertex 0.928558 1.59249 2.64484 + vertex 0.923449 1.5874 2.64486 + endloop + endfacet + facet normal -0.0344594 0.0357552 0.998766 + outer loop + vertex 0.923414 1.58242 2.64503 + vertex 0.928553 1.5875 2.64503 + vertex 0.923449 1.5874 2.64486 + endloop + endfacet + facet normal -0.0341934 0.0354864 0.998785 + outer loop + vertex 0.928468 1.58251 2.6452 + vertex 0.928553 1.5875 2.64503 + vertex 0.923414 1.58242 2.64503 + endloop + endfacet + facet normal -0.0341527 0.0330919 0.998869 + outer loop + vertex 0.923313 1.57743 2.6452 + vertex 0.928468 1.58251 2.6452 + vertex 0.923414 1.58242 2.64503 + endloop + endfacet + facet normal -0.0334547 0.0323829 0.998915 + outer loop + vertex 0.928359 1.5775 2.64536 + vertex 0.928468 1.58251 2.6452 + vertex 0.923313 1.57743 2.6452 + endloop + endfacet + facet normal -0.0334355 0.0307383 0.998968 + outer loop + vertex 0.923292 1.57239 2.64535 + vertex 0.928359 1.5775 2.64536 + vertex 0.923313 1.57743 2.6452 + endloop + endfacet + facet normal -0.0306157 0.027941 0.999141 + outer loop + vertex 0.928544 1.5725 2.64551 + vertex 0.928359 1.5775 2.64536 + vertex 0.923292 1.57239 2.64535 + endloop + endfacet + facet normal -0.0306685 0.0305559 0.999062 + outer loop + vertex 0.923703 1.56702 2.64553 + vertex 0.928544 1.5725 2.64551 + vertex 0.923292 1.57239 2.64535 + endloop + endfacet + facet normal -0.0228373 0.0236423 0.99946 + outer loop + vertex 0.929726 1.56776 2.64565 + vertex 0.928544 1.5725 2.64551 + vertex 0.923703 1.56702 2.64553 + endloop + endfacet + facet normal -0.0258911 0.0487029 0.998478 + outer loop + vertex 0.923703 1.56702 2.64553 + vertex 0.926094 1.56399 2.64574 + vertex 0.929726 1.56776 2.64565 + endloop + endfacet + facet normal -0.00558841 0.0291368 0.99956 + outer loop + vertex 0.926094 1.56399 2.64574 + vertex 0.929461 1.56394 2.64576 + vertex 0.929726 1.56776 2.64565 + endloop + endfacet + facet normal 0.00800557 0.0281917 0.99957 + outer loop + vertex 0.929461 1.56394 2.64576 + vertex 0.933333 1.56499 2.6457 + vertex 0.929726 1.56776 2.64565 + endloop + endfacet + facet normal 0.00758061 0.0276379 0.999589 + outer loop + vertex 0.929726 1.56776 2.64565 + vertex 0.933333 1.56499 2.6457 + vertex 0.934706 1.56892 2.64558 + endloop + endfacet + facet normal 0.00828638 0.0246146 0.999663 + outer loop + vertex 0.934706 1.56892 2.64558 + vertex 0.933715 1.57269 2.64549 + vertex 0.929726 1.56776 2.64565 + endloop + endfacet + facet normal 0.0196653 0.0276 0.999426 + outer loop + vertex 0.934706 1.56892 2.64558 + vertex 0.938653 1.57249 2.6454 + vertex 0.933715 1.57269 2.64549 + endloop + endfacet + facet normal 0.0196468 0.0271251 0.999439 + outer loop + vertex 0.938653 1.57249 2.6454 + vertex 0.938373 1.57737 2.64527 + vertex 0.933715 1.57269 2.64549 + endloop + endfacet + facet normal 0.0183968 0.0283683 0.999428 + outer loop + vertex 0.933715 1.57269 2.64549 + vertex 0.938373 1.57737 2.64527 + vertex 0.933381 1.57747 2.64536 + endloop + endfacet + facet normal 0.00196256 0.027229 0.999627 + outer loop + vertex 0.933715 1.57269 2.64549 + vertex 0.933381 1.57747 2.64536 + vertex 0.928544 1.5725 2.64551 + endloop + endfacet + facet normal 0.0184175 0.0293938 0.999398 + outer loop + vertex 0.938373 1.57737 2.64527 + vertex 0.938395 1.58241 2.64512 + vertex 0.933381 1.57747 2.64536 + endloop + endfacet + facet normal 0.0175405 0.0302848 0.999387 + outer loop + vertex 0.933381 1.57747 2.64536 + vertex 0.938395 1.58241 2.64512 + vertex 0.933446 1.58249 2.64521 + endloop + endfacet + facet normal 5.28487e-05 0.0305136 0.999534 + outer loop + vertex 0.933381 1.57747 2.64536 + vertex 0.933446 1.58249 2.64521 + vertex 0.928359 1.5775 2.64536 + endloop + endfacet + facet normal -0.00110954 0.0316976 0.999497 + outer loop + vertex 0.928359 1.5775 2.64536 + vertex 0.933446 1.58249 2.64521 + vertex 0.928468 1.58251 2.6452 + endloop + endfacet + facet normal -0.00110154 0.033557 0.999436 + outer loop + vertex 0.933446 1.58249 2.64521 + vertex 0.933567 1.58751 2.64504 + vertex 0.928468 1.58251 2.6452 + endloop + endfacet + facet normal -0.00248424 0.0349647 0.999385 + outer loop + vertex 0.928468 1.58251 2.6452 + vertex 0.933567 1.58751 2.64504 + vertex 0.928553 1.5875 2.64503 + endloop + endfacet + facet normal 0.0167605 0.0331203 0.999311 + outer loop + vertex 0.933446 1.58249 2.64521 + vertex 0.938513 1.58746 2.64496 + vertex 0.933567 1.58751 2.64504 + endloop + endfacet + facet normal 0.0167795 0.0351345 0.999242 + outer loop + vertex 0.938513 1.58746 2.64496 + vertex 0.938574 1.59248 2.64478 + vertex 0.933567 1.58751 2.64504 + endloop + endfacet + facet normal 0.0154285 0.0364953 0.999215 + outer loop + vertex 0.933567 1.58751 2.64504 + vertex 0.938574 1.59248 2.64478 + vertex 0.933605 1.59251 2.64486 + endloop + endfacet + facet normal 0.0250025 0.0350273 0.999074 + outer loop + vertex 0.938513 1.58746 2.64496 + vertex 0.943514 1.59244 2.64466 + vertex 0.938574 1.59248 2.64478 + endloop + endfacet + facet normal 0.025014 0.036757 0.999011 + outer loop + vertex 0.943514 1.59244 2.64466 + vertex 0.943513 1.59743 2.64448 + vertex 0.938574 1.59248 2.64478 + endloop + endfacet + facet normal 0.024175 0.0375931 0.999001 + outer loop + vertex 0.938574 1.59248 2.64478 + vertex 0.943513 1.59743 2.64448 + vertex 0.938568 1.59747 2.64459 + endloop + endfacet + facet normal 0.0302918 0.0367518 0.998865 + outer loop + vertex 0.943514 1.59244 2.64466 + vertex 0.948457 1.5974 2.64433 + vertex 0.943513 1.59743 2.64448 + endloop + endfacet + facet normal 0.0303036 0.0390675 0.998777 + outer loop + vertex 0.948457 1.5974 2.64433 + vertex 0.948429 1.60237 2.64413 + vertex 0.943513 1.59743 2.64448 + endloop + endfacet + facet normal 0.0300468 0.0393228 0.998775 + outer loop + vertex 0.943513 1.59743 2.64448 + vertex 0.948429 1.60237 2.64413 + vertex 0.943485 1.60241 2.64428 + endloop + endfacet + facet normal 0.0356374 0.0390904 0.9986 + outer loop + vertex 0.948457 1.5974 2.64433 + vertex 0.953407 1.60236 2.64396 + vertex 0.948429 1.60237 2.64413 + endloop + endfacet + facet normal 0.0356414 0.0424675 0.998462 + outer loop + vertex 0.953407 1.60236 2.64396 + vertex 0.953383 1.60732 2.64375 + vertex 0.948429 1.60237 2.64413 + endloop + endfacet + facet normal 0.0363333 0.0417756 0.998466 + outer loop + vertex 0.948429 1.60237 2.64413 + vertex 0.953383 1.60732 2.64375 + vertex 0.948395 1.60735 2.64393 + endloop + endfacet + facet normal 0.0397828 0.0424811 0.998305 + outer loop + vertex 0.953407 1.60236 2.64396 + vertex 0.958433 1.60738 2.64354 + vertex 0.953383 1.60732 2.64375 + endloop + endfacet + facet normal 0.0397363 0.0461374 0.998144 + outer loop + vertex 0.958433 1.60738 2.64354 + vertex 0.95844 1.61234 2.64331 + vertex 0.953383 1.60732 2.64375 + endloop + endfacet + facet normal 0.0411003 0.0447647 0.998152 + outer loop + vertex 0.953383 1.60732 2.64375 + vertex 0.95844 1.61234 2.64331 + vertex 0.953367 1.6123 2.64352 + endloop + endfacet + facet normal 0.0418633 0.0461307 0.998058 + outer loop + vertex 0.958433 1.60738 2.64354 + vertex 0.963534 1.61249 2.64309 + vertex 0.95844 1.61234 2.64331 + endloop + endfacet + facet normal 0.041776 0.048929 0.997928 + outer loop + vertex 0.963534 1.61249 2.64309 + vertex 0.963594 1.61748 2.64285 + vertex 0.95844 1.61234 2.64331 + endloop + endfacet + facet normal 0.042987 0.0477143 0.997936 + outer loop + vertex 0.95844 1.61234 2.64331 + vertex 0.963594 1.61748 2.64285 + vertex 0.958483 1.61734 2.64307 + endloop + endfacet + facet normal 0.0461684 0.0488667 0.997738 + outer loop + vertex 0.963534 1.61249 2.64309 + vertex 0.968563 1.61762 2.64261 + vertex 0.963594 1.61748 2.64285 + endloop + endfacet + facet normal 0.0461519 0.0494153 0.997711 + outer loop + vertex 0.968563 1.61762 2.64261 + vertex 0.968652 1.62263 2.64236 + vertex 0.963594 1.61748 2.64285 + endloop + endfacet + facet normal 0.0456364 0.0499211 0.99771 + outer loop + vertex 0.963594 1.61748 2.64285 + vertex 0.968652 1.62263 2.64236 + vertex 0.963702 1.62251 2.64259 + endloop + endfacet + facet normal 0.0647481 0.0490337 0.996696 + outer loop + vertex 0.968563 1.61762 2.64261 + vertex 0.973248 1.62252 2.64206 + vertex 0.968652 1.62263 2.64236 + endloop + endfacet + facet normal 0.0646679 0.0453057 0.996878 + outer loop + vertex 0.973248 1.62252 2.64206 + vertex 0.973235 1.62754 2.64184 + vertex 0.968652 1.62263 2.64236 + endloop + endfacet + facet normal 0.059924 0.0497429 0.996963 + outer loop + vertex 0.968652 1.62263 2.64236 + vertex 0.973235 1.62754 2.64184 + vertex 0.968689 1.62765 2.6421 + endloop + endfacet + facet normal 0.11216 0.0452376 0.99266 + outer loop + vertex 0.973248 1.62252 2.64206 + vertex 0.977375 1.62694 2.6414 + vertex 0.973235 1.62754 2.64184 + endloop + endfacet + facet normal 0.111464 0.0402178 0.992954 + outer loop + vertex 0.977375 1.62694 2.6414 + vertex 0.977058 1.63198 2.64123 + vertex 0.973235 1.62754 2.64184 + endloop + endfacet + facet normal 0.101836 0.0486052 0.993613 + outer loop + vertex 0.973235 1.62754 2.64184 + vertex 0.977058 1.63198 2.64123 + vertex 0.972882 1.63245 2.64163 + endloop + endfacet + facet normal 0.118668 0.039092 0.992164 + outer loop + vertex 0.977425 1.62192 2.64159 + vertex 0.977375 1.62694 2.6414 + vertex 0.973248 1.62252 2.64206 + endloop + endfacet + facet normal 0.119317 0.0438768 0.991886 + outer loop + vertex 0.973225 1.61751 2.64229 + vertex 0.977425 1.62192 2.64159 + vertex 0.973248 1.62252 2.64206 + endloop + endfacet + facet normal 0.127878 0.0356235 0.99115 + outer loop + vertex 0.977498 1.61688 2.64176 + vertex 0.977425 1.62192 2.64159 + vertex 0.973225 1.61751 2.64229 + endloop + endfacet + facet normal 0.12835 0.0389831 0.990962 + outer loop + vertex 0.973292 1.61245 2.64248 + vertex 0.977498 1.61688 2.64176 + vertex 0.973225 1.61751 2.64229 + endloop + endfacet + facet normal 0.0770208 0.0385019 0.996286 + outer loop + vertex 0.973292 1.61245 2.64248 + vertex 0.973225 1.61751 2.64229 + vertex 0.968529 1.61262 2.64284 + endloop + endfacet + facet normal 0.0771155 0.0414419 0.996161 + outer loop + vertex 0.968582 1.60762 2.64304 + vertex 0.973292 1.61245 2.64248 + vertex 0.968529 1.61262 2.64284 + endloop + endfacet + facet normal 0.0534289 0.0412571 0.997719 + outer loop + vertex 0.968582 1.60762 2.64304 + vertex 0.968529 1.61262 2.64284 + vertex 0.963529 1.60753 2.64332 + endloop + endfacet + facet normal 0.0534481 0.0403221 0.997756 + outer loop + vertex 0.963557 1.60255 2.64352 + vertex 0.968582 1.60762 2.64304 + vertex 0.963529 1.60753 2.64332 + endloop + endfacet + facet normal 0.0446274 0.0402899 0.998191 + outer loop + vertex 0.963557 1.60255 2.64352 + vertex 0.963529 1.60753 2.64332 + vertex 0.958449 1.60242 2.64375 + endloop + endfacet + facet normal 0.0447043 0.03749 0.998297 + outer loop + vertex 0.958467 1.59745 2.64394 + vertex 0.963557 1.60255 2.64352 + vertex 0.958449 1.60242 2.64375 + endloop + endfacet + facet normal 0.0412805 0.0374833 0.998444 + outer loop + vertex 0.958467 1.59745 2.64394 + vertex 0.958449 1.60242 2.64375 + vertex 0.953428 1.5974 2.64415 + endloop + endfacet + facet normal 0.0413239 0.0341257 0.998563 + outer loop + vertex 0.953427 1.59242 2.64432 + vertex 0.958467 1.59745 2.64394 + vertex 0.953428 1.5974 2.64415 + endloop + endfacet + facet normal 0.0373518 0.0341311 0.998719 + outer loop + vertex 0.953427 1.59242 2.64432 + vertex 0.953428 1.5974 2.64415 + vertex 0.948455 1.59242 2.6445 + endloop + endfacet + facet normal 0.0373541 0.0321794 0.998784 + outer loop + vertex 0.948409 1.58738 2.64467 + vertex 0.953427 1.59242 2.64432 + vertex 0.948455 1.59242 2.6445 + endloop + endfacet + facet normal 0.0330346 0.0322236 0.998935 + outer loop + vertex 0.948409 1.58738 2.64467 + vertex 0.948455 1.59242 2.6445 + vertex 0.943452 1.58741 2.64483 + endloop + endfacet + facet normal 0.0330285 0.0308235 0.998979 + outer loop + vertex 0.943362 1.58233 2.64499 + vertex 0.948409 1.58738 2.64467 + vertex 0.943452 1.58741 2.64483 + endloop + endfacet + facet normal 0.02757 0.0309252 0.999141 + outer loop + vertex 0.943362 1.58233 2.64499 + vertex 0.943452 1.58741 2.64483 + vertex 0.938395 1.58241 2.64512 + endloop + endfacet + facet normal 0.0264241 0.0320825 0.999136 + outer loop + vertex 0.938395 1.58241 2.64512 + vertex 0.943452 1.58741 2.64483 + vertex 0.938513 1.58746 2.64496 + endloop + endfacet + facet normal 0.0343604 0.029493 0.998974 + outer loop + vertex 0.948353 1.58231 2.64482 + vertex 0.948409 1.58738 2.64467 + vertex 0.943362 1.58233 2.64499 + endloop + endfacet + facet normal 0.0343559 0.0283694 0.999007 + outer loop + vertex 0.943373 1.57727 2.64513 + vertex 0.948353 1.58231 2.64482 + vertex 0.943362 1.58233 2.64499 + endloop + endfacet + facet normal 0.0285262 0.0283619 0.999191 + outer loop + vertex 0.943373 1.57727 2.64513 + vertex 0.943362 1.58233 2.64499 + vertex 0.938373 1.57737 2.64527 + endloop + endfacet + facet normal 0.0346551 0.0280733 0.999005 + outer loop + vertex 0.948363 1.57726 2.64496 + vertex 0.948353 1.58231 2.64482 + vertex 0.943373 1.57727 2.64513 + endloop + endfacet + facet normal 0.0346546 0.0274482 0.999022 + outer loop + vertex 0.943618 1.57238 2.64526 + vertex 0.948363 1.57726 2.64496 + vertex 0.943373 1.57727 2.64513 + endloop + endfacet + facet normal 0.0289788 0.0271687 0.999211 + outer loop + vertex 0.943618 1.57238 2.64526 + vertex 0.943373 1.57727 2.64513 + vertex 0.938653 1.57249 2.6454 + endloop + endfacet + facet normal 0.0289611 0.0263672 0.999233 + outer loop + vertex 0.93905 1.56709 2.64553 + vertex 0.943618 1.57238 2.64526 + vertex 0.938653 1.57249 2.6454 + endloop + endfacet + facet normal 0.0295324 0.0258739 0.999229 + outer loop + vertex 0.944457 1.56856 2.64533 + vertex 0.943618 1.57238 2.64526 + vertex 0.93905 1.56709 2.64553 + endloop + endfacet + facet normal 0.02944 0.0262127 0.999223 + outer loop + vertex 0.93905 1.56709 2.64553 + vertex 0.943303 1.5639 2.64549 + vertex 0.944457 1.56856 2.64533 + endloop + endfacet + facet normal 0.0357288 0.0246496 0.999057 + outer loop + vertex 0.943303 1.5639 2.64549 + vertex 0.948408 1.56776 2.64521 + vertex 0.944457 1.56856 2.64533 + endloop + endfacet + facet normal 0.0359646 0.025821 0.999019 + outer loop + vertex 0.948408 1.56776 2.64521 + vertex 0.948493 1.57247 2.64509 + vertex 0.944457 1.56856 2.64533 + endloop + endfacet + facet normal 0.0371981 0.0257975 0.998975 + outer loop + vertex 0.948408 1.56776 2.64521 + vertex 0.953287 1.57229 2.64491 + vertex 0.948493 1.57247 2.64509 + endloop + endfacet + facet normal 0.0372703 0.0278468 0.998917 + outer loop + vertex 0.953287 1.57229 2.64491 + vertex 0.953342 1.57728 2.64477 + vertex 0.948493 1.57247 2.64509 + endloop + endfacet + facet normal 0.0377238 0.0273898 0.998913 + outer loop + vertex 0.948493 1.57247 2.64509 + vertex 0.953342 1.57728 2.64477 + vertex 0.948363 1.57726 2.64496 + endloop + endfacet + facet normal 0.0377171 0.0287234 0.998876 + outer loop + vertex 0.953342 1.57728 2.64477 + vertex 0.953363 1.58232 2.64463 + vertex 0.948363 1.57726 2.64496 + endloop + endfacet + facet normal 0.0396572 0.0287134 0.998801 + outer loop + vertex 0.953342 1.57728 2.64477 + vertex 0.958429 1.58237 2.64442 + vertex 0.953363 1.58232 2.64463 + endloop + endfacet + facet normal 0.0396339 0.0311124 0.99873 + outer loop + vertex 0.958429 1.58237 2.64442 + vertex 0.958458 1.58743 2.64427 + vertex 0.953363 1.58232 2.64463 + endloop + endfacet + facet normal 0.0411985 0.0295495 0.998714 + outer loop + vertex 0.953363 1.58232 2.64463 + vertex 0.958458 1.58743 2.64427 + vertex 0.953399 1.58739 2.64447 + endloop + endfacet + facet normal 0.0383647 0.0295734 0.998826 + outer loop + vertex 0.953363 1.58232 2.64463 + vertex 0.953399 1.58739 2.64447 + vertex 0.948353 1.58231 2.64482 + endloop + endfacet + facet normal 0.0411795 0.0316707 0.99865 + outer loop + vertex 0.958458 1.58743 2.64427 + vertex 0.958472 1.59246 2.6441 + vertex 0.953399 1.58739 2.64447 + endloop + endfacet + facet normal 0.0418301 0.0310197 0.998643 + outer loop + vertex 0.953399 1.58739 2.64447 + vertex 0.958472 1.59246 2.6441 + vertex 0.953427 1.59242 2.64432 + endloop + endfacet + facet normal 0.0459467 0.0316508 0.998442 + outer loop + vertex 0.958458 1.58743 2.64427 + vertex 0.963597 1.59255 2.64387 + vertex 0.958472 1.59246 2.6441 + endloop + endfacet + facet normal 0.0459049 0.0338886 0.998371 + outer loop + vertex 0.963597 1.59255 2.64387 + vertex 0.963584 1.59756 2.6437 + vertex 0.958472 1.59246 2.6441 + endloop + endfacet + facet normal 0.0461493 0.0336433 0.998368 + outer loop + vertex 0.958472 1.59246 2.6441 + vertex 0.963584 1.59756 2.6437 + vertex 0.958467 1.59745 2.64394 + endloop + endfacet + facet normal 0.0570054 0.0338981 0.997798 + outer loop + vertex 0.963597 1.59255 2.64387 + vertex 0.968661 1.59761 2.64341 + vertex 0.963584 1.59756 2.6437 + endloop + endfacet + facet normal 0.0569859 0.0356606 0.997738 + outer loop + vertex 0.968661 1.59761 2.64341 + vertex 0.968639 1.6026 2.64323 + vertex 0.963584 1.59756 2.6437 + endloop + endfacet + facet normal 0.0565102 0.0361388 0.997748 + outer loop + vertex 0.963584 1.59756 2.6437 + vertex 0.968639 1.6026 2.64323 + vertex 0.963557 1.60255 2.64352 + endloop + endfacet + facet normal 0.0837348 0.0357101 0.995848 + outer loop + vertex 0.968661 1.59761 2.64341 + vertex 0.973425 1.60226 2.64284 + vertex 0.968639 1.6026 2.64323 + endloop + endfacet + facet normal 0.0838607 0.0376181 0.995767 + outer loop + vertex 0.973425 1.60226 2.64284 + vertex 0.973472 1.60733 2.64264 + vertex 0.968639 1.6026 2.64323 + endloop + endfacet + facet normal 0.0839425 0.0375341 0.995763 + outer loop + vertex 0.968639 1.6026 2.64323 + vertex 0.973472 1.60733 2.64264 + vertex 0.968582 1.60762 2.64304 + endloop + endfacet + facet normal 0.145903 0.0367722 0.988615 + outer loop + vertex 0.973425 1.60226 2.64284 + vertex 0.978306 1.60619 2.64197 + vertex 0.973472 1.60733 2.64264 + endloop + endfacet + facet normal 0.144072 0.0287191 0.98915 + outer loop + vertex 0.978306 1.60619 2.64197 + vertex 0.977755 1.61173 2.64189 + vertex 0.973472 1.60733 2.64264 + endloop + endfacet + facet normal 0.136173 0.0365468 0.990011 + outer loop + vertex 0.973472 1.60733 2.64264 + vertex 0.977755 1.61173 2.64189 + vertex 0.973292 1.61245 2.64248 + endloop + endfacet + facet normal 0.132627 0.0535407 0.989719 + outer loop + vertex 0.977019 1.60129 2.64241 + vertex 0.978306 1.60619 2.64197 + vertex 0.973425 1.60226 2.64284 + endloop + endfacet + facet normal 0.127875 0.0354585 0.991156 + outer loop + vertex 0.973381 1.59747 2.64301 + vertex 0.977019 1.60129 2.64241 + vertex 0.973425 1.60226 2.64284 + endloop + endfacet + facet normal 0.142422 0.0213382 0.989576 + outer loop + vertex 0.977715 1.59736 2.64239 + vertex 0.977019 1.60129 2.64241 + vertex 0.973381 1.59747 2.64301 + endloop + endfacet + facet normal 0.142627 0.0306986 0.9893 + outer loop + vertex 0.97355 1.59269 2.64314 + vertex 0.977715 1.59736 2.64239 + vertex 0.973381 1.59747 2.64301 + endloop + endfacet + facet normal 0.150809 0.0232369 0.98829 + outer loop + vertex 0.978005 1.59254 2.64246 + vertex 0.977715 1.59736 2.64239 + vertex 0.97355 1.59269 2.64314 + endloop + endfacet + facet normal 0.150988 0.0293378 0.9881 + outer loop + vertex 0.973602 1.58772 2.64328 + vertex 0.978005 1.59254 2.64246 + vertex 0.97355 1.59269 2.64314 + endloop + endfacet + facet normal 0.157174 0.0235467 0.98729 + outer loop + vertex 0.978061 1.58757 2.64257 + vertex 0.978005 1.59254 2.64246 + vertex 0.973602 1.58772 2.64328 + endloop + endfacet + facet normal 0.157339 0.0291135 0.987115 + outer loop + vertex 0.97359 1.58271 2.64343 + vertex 0.978061 1.58757 2.64257 + vertex 0.973602 1.58772 2.64328 + endloop + endfacet + facet normal 0.162549 0.0241877 0.986404 + outer loop + vertex 0.978055 1.58258 2.6427 + vertex 0.978061 1.58757 2.64257 + vertex 0.97359 1.58271 2.64343 + endloop + endfacet + facet normal 0.162584 0.0255911 0.986363 + outer loop + vertex 0.973579 1.57772 2.64356 + vertex 0.978055 1.58258 2.6427 + vertex 0.97359 1.58271 2.64343 + endloop + endfacet + facet normal 0.168411 0.0200779 0.985512 + outer loop + vertex 0.978058 1.57759 2.6428 + vertex 0.978055 1.58258 2.6427 + vertex 0.973579 1.57772 2.64356 + endloop + endfacet + facet normal 0.168477 0.0228965 0.98544 + outer loop + vertex 0.973597 1.57273 2.64367 + vertex 0.978058 1.57759 2.6428 + vertex 0.973579 1.57772 2.64356 + endloop + endfacet + facet normal 0.172412 0.019175 0.984838 + outer loop + vertex 0.978104 1.57262 2.64289 + vertex 0.978058 1.57759 2.6428 + vertex 0.973597 1.57273 2.64367 + endloop + endfacet + facet normal 0.172436 0.0203737 0.98481 + outer loop + vertex 0.973617 1.56775 2.64377 + vertex 0.978104 1.57262 2.64289 + vertex 0.973597 1.57273 2.64367 + endloop + endfacet + facet normal 0.175264 0.0176901 0.984363 + outer loop + vertex 0.978153 1.56766 2.64297 + vertex 0.978104 1.57262 2.64289 + vertex 0.973617 1.56775 2.64377 + endloop + endfacet + facet normal 0.175281 0.0187652 0.98434 + outer loop + vertex 0.973609 1.56274 2.64387 + vertex 0.978153 1.56766 2.64297 + vertex 0.973617 1.56775 2.64377 + endloop + endfacet + facet normal 0.177796 0.0163687 0.983931 + outer loop + vertex 0.978177 1.56266 2.64304 + vertex 0.978153 1.56766 2.64297 + vertex 0.973609 1.56274 2.64387 + endloop + endfacet + facet normal 0.177803 0.0169758 0.98392 + outer loop + vertex 0.973572 1.55768 2.64396 + vertex 0.978177 1.56266 2.64304 + vertex 0.973609 1.56274 2.64387 + endloop + endfacet + facet normal 0.177856 0.0169256 0.983911 + outer loop + vertex 0.978194 1.55765 2.64313 + vertex 0.978177 1.56266 2.64304 + vertex 0.973572 1.55768 2.64396 + endloop + endfacet + facet normal 0.177851 0.0156673 0.983933 + outer loop + vertex 0.973535 1.5526 2.64405 + vertex 0.978194 1.55765 2.64313 + vertex 0.973572 1.55768 2.64396 + endloop + endfacet + facet normal 0.178292 0.015247 0.983859 + outer loop + vertex 0.978205 1.55261 2.6432 + vertex 0.978194 1.55765 2.64313 + vertex 0.973535 1.5526 2.64405 + endloop + endfacet + facet normal 0.178301 0.0129966 0.98389 + outer loop + vertex 0.973506 1.54753 2.64412 + vertex 0.978205 1.55261 2.6432 + vertex 0.973535 1.5526 2.64405 + endloop + endfacet + facet normal 0.178502 0.012805 0.983856 + outer loop + vertex 0.978215 1.54756 2.64327 + vertex 0.978205 1.55261 2.6432 + vertex 0.973506 1.54753 2.64412 + endloop + endfacet + facet normal 0.178512 0.0115434 0.98387 + outer loop + vertex 0.973483 1.5425 2.64419 + vertex 0.978215 1.54756 2.64327 + vertex 0.973506 1.54753 2.64412 + endloop + endfacet + facet normal 0.180082 0.0100291 0.9836 + outer loop + vertex 0.978219 1.54252 2.64332 + vertex 0.978215 1.54756 2.64327 + vertex 0.973483 1.5425 2.64419 + endloop + endfacet + facet normal 0.18009 0.00899204 0.983609 + outer loop + vertex 0.973458 1.53748 2.64424 + vertex 0.978219 1.54252 2.64332 + vertex 0.973483 1.5425 2.64419 + endloop + endfacet + facet normal 0.18052 0.00857255 0.983534 + outer loop + vertex 0.978222 1.5375 2.64336 + vertex 0.978219 1.54252 2.64332 + vertex 0.973458 1.53748 2.64424 + endloop + endfacet + facet normal 0.180523 0.00789062 0.983539 + outer loop + vertex 0.973444 1.53248 2.64428 + vertex 0.978222 1.5375 2.64336 + vertex 0.973458 1.53748 2.64424 + endloop + endfacet + facet normal 0.181297 0.00712841 0.983403 + outer loop + vertex 0.978227 1.5325 2.6434 + vertex 0.978222 1.5375 2.64336 + vertex 0.973444 1.53248 2.64428 + endloop + endfacet + facet normal 0.181292 0.00806301 0.983396 + outer loop + vertex 0.973452 1.52752 2.64432 + vertex 0.978227 1.5325 2.6434 + vertex 0.973444 1.53248 2.64428 + endloop + endfacet + facet normal 0.18178 0.00758011 0.98331 + outer loop + vertex 0.978245 1.52754 2.64343 + vertex 0.978227 1.5325 2.6434 + vertex 0.973452 1.52752 2.64432 + endloop + endfacet + facet normal 0.181777 0.00805018 0.983307 + outer loop + vertex 0.973475 1.52256 2.64435 + vertex 0.978245 1.52754 2.64343 + vertex 0.973452 1.52752 2.64432 + endloop + endfacet + facet normal 0.182154 0.00767696 0.98324 + outer loop + vertex 0.978272 1.52259 2.64347 + vertex 0.978245 1.52754 2.64343 + vertex 0.973475 1.52256 2.64435 + endloop + endfacet + facet normal 0.182171 0.00552898 0.983251 + outer loop + vertex 0.973486 1.5176 2.64438 + vertex 0.978272 1.52259 2.64347 + vertex 0.973475 1.52256 2.64435 + endloop + endfacet + facet normal 0.181265 0.00642676 0.983413 + outer loop + vertex 0.978289 1.51764 2.64349 + vertex 0.978272 1.52259 2.64347 + vertex 0.973486 1.5176 2.64438 + endloop + endfacet + facet normal 0.181275 0.00528595 0.983418 + outer loop + vertex 0.973483 1.51261 2.64441 + vertex 0.978289 1.51764 2.64349 + vertex 0.973486 1.5176 2.64438 + endloop + endfacet + facet normal 0.180071 0.0064754 0.983632 + outer loop + vertex 0.978312 1.51267 2.64352 + vertex 0.978289 1.51764 2.64349 + vertex 0.973483 1.51261 2.64441 + endloop + endfacet + facet normal 0.180107 0.00381955 0.98364 + outer loop + vertex 0.973481 1.50761 2.64443 + vertex 0.978312 1.51267 2.64352 + vertex 0.973483 1.51261 2.64441 + endloop + endfacet + facet normal 0.180836 0.00310085 0.983508 + outer loop + vertex 0.978324 1.50766 2.64354 + vertex 0.978312 1.51267 2.64352 + vertex 0.973481 1.50761 2.64443 + endloop + endfacet + facet normal 0.180856 0.0011788 0.983509 + outer loop + vertex 0.973486 1.50261 2.64443 + vertex 0.978324 1.50766 2.64354 + vertex 0.973481 1.50761 2.64443 + endloop + endfacet + facet normal 0.179764 0.00226013 0.983707 + outer loop + vertex 0.978345 1.50264 2.64354 + vertex 0.978324 1.50766 2.64354 + vertex 0.973486 1.50261 2.64443 + endloop + endfacet + facet normal 0.179775 0.000383202 0.983708 + outer loop + vertex 0.973502 1.49762 2.64443 + vertex 0.978345 1.50264 2.64354 + vertex 0.973486 1.50261 2.64443 + endloop + endfacet + facet normal 0.182219 -0.00205425 0.983256 + outer loop + vertex 0.978337 1.49761 2.64354 + vertex 0.978345 1.50264 2.64354 + vertex 0.973502 1.49762 2.64443 + endloop + endfacet + facet normal 0.182218 -0.00246129 0.983255 + outer loop + vertex 0.973515 1.49263 2.64442 + vertex 0.978337 1.49761 2.64354 + vertex 0.973502 1.49762 2.64443 + endloop + endfacet + facet normal 0.183258 -0.0035033 0.983059 + outer loop + vertex 0.978318 1.49261 2.64352 + vertex 0.978337 1.49761 2.64354 + vertex 0.973515 1.49263 2.64442 + endloop + endfacet + facet normal 0.183246 -0.00609757 0.983048 + outer loop + vertex 0.973523 1.48766 2.64438 + vertex 0.978318 1.49261 2.64352 + vertex 0.973515 1.49263 2.64442 + endloop + endfacet + facet normal 0.181365 -0.00421437 0.983407 + outer loop + vertex 0.978298 1.48765 2.6435 + vertex 0.978318 1.49261 2.64352 + vertex 0.973523 1.48766 2.64438 + endloop + endfacet + facet normal 0.181359 -0.00623172 0.983397 + outer loop + vertex 0.973538 1.48271 2.64435 + vertex 0.978298 1.48765 2.6435 + vertex 0.973523 1.48766 2.64438 + endloop + endfacet + facet normal 0.179717 -0.00459576 0.983708 + outer loop + vertex 0.97829 1.4827 2.64348 + vertex 0.978298 1.48765 2.6435 + vertex 0.973538 1.48271 2.64435 + endloop + endfacet + facet normal 0.179711 -0.00610009 0.983701 + outer loop + vertex 0.973561 1.47777 2.64432 + vertex 0.97829 1.4827 2.64348 + vertex 0.973538 1.48271 2.64435 + endloop + endfacet + facet normal 0.17763 -0.00403663 0.984089 + outer loop + vertex 0.978302 1.47773 2.64346 + vertex 0.97829 1.4827 2.64348 + vertex 0.973561 1.47777 2.64432 + endloop + endfacet + facet normal 0.177608 -0.00662087 0.984079 + outer loop + vertex 0.973587 1.47281 2.64428 + vertex 0.978302 1.47773 2.64346 + vertex 0.973561 1.47777 2.64432 + endloop + endfacet + facet normal 0.175922 -0.00495305 0.984392 + outer loop + vertex 0.978313 1.47275 2.64343 + vertex 0.978302 1.47773 2.64346 + vertex 0.973587 1.47281 2.64428 + endloop + endfacet + facet normal 0.175869 -0.00843766 0.984377 + outer loop + vertex 0.973605 1.46784 2.64423 + vertex 0.978313 1.47275 2.64343 + vertex 0.973587 1.47281 2.64428 + endloop + endfacet + facet normal 0.109277 -0.00876314 0.993973 + outer loop + vertex 0.973605 1.46784 2.64423 + vertex 0.973587 1.47281 2.64428 + vertex 0.968544 1.46766 2.64479 + endloop + endfacet + facet normal 0.109426 -0.0131051 0.993909 + outer loop + vertex 0.968573 1.46271 2.64472 + vertex 0.973605 1.46784 2.64423 + vertex 0.968544 1.46766 2.64479 + endloop + endfacet + facet normal 0.0641501 -0.0134207 0.99785 + outer loop + vertex 0.968573 1.46271 2.64472 + vertex 0.968544 1.46766 2.64479 + vertex 0.963411 1.46254 2.64505 + endloop + endfacet + facet normal 0.0642947 -0.0178582 0.997771 + outer loop + vertex 0.963442 1.45759 2.64496 + vertex 0.968573 1.46271 2.64472 + vertex 0.963411 1.46254 2.64505 + endloop + endfacet + facet normal 0.0413956 -0.0180257 0.99898 + outer loop + vertex 0.963442 1.45759 2.64496 + vertex 0.963411 1.46254 2.64505 + vertex 0.958342 1.45753 2.64517 + endloop + endfacet + facet normal 0.0414295 -0.0211454 0.998918 + outer loop + vertex 0.958361 1.45256 2.64506 + vertex 0.963442 1.45759 2.64496 + vertex 0.958342 1.45753 2.64517 + endloop + endfacet + facet normal 0.0348328 -0.0211764 0.999169 + outer loop + vertex 0.958361 1.45256 2.64506 + vertex 0.958342 1.45753 2.64517 + vertex 0.95336 1.45258 2.64524 + endloop + endfacet + facet normal 0.034825 -0.022771 0.999134 + outer loop + vertex 0.953352 1.4476 2.64512 + vertex 0.958361 1.45256 2.64506 + vertex 0.95336 1.45258 2.64524 + endloop + endfacet + facet normal 0.0347001 -0.0227709 0.999138 + outer loop + vertex 0.953352 1.4476 2.64512 + vertex 0.95336 1.45258 2.64524 + vertex 0.94842 1.44764 2.64529 + endloop + endfacet + facet normal 0.0346916 -0.0237836 0.999115 + outer loop + vertex 0.948389 1.44265 2.64518 + vertex 0.953352 1.4476 2.64512 + vertex 0.94842 1.44764 2.64529 + endloop + endfacet + facet normal 0.0345242 -0.0237827 0.999121 + outer loop + vertex 0.948389 1.44265 2.64518 + vertex 0.94842 1.44764 2.64529 + vertex 0.943478 1.44268 2.64535 + endloop + endfacet + facet normal 0.0345133 -0.0252493 0.999085 + outer loop + vertex 0.943447 1.43768 2.64522 + vertex 0.948389 1.44265 2.64518 + vertex 0.943478 1.44268 2.64535 + endloop + endfacet + facet normal 0.0300134 -0.0252252 0.999231 + outer loop + vertex 0.943447 1.43768 2.64522 + vertex 0.943478 1.44268 2.64535 + vertex 0.938524 1.43773 2.64537 + endloop + endfacet + facet normal 0.0299842 -0.0281251 0.999155 + outer loop + vertex 0.938506 1.43273 2.64523 + vertex 0.943447 1.43768 2.64522 + vertex 0.938524 1.43773 2.64537 + endloop + endfacet + facet normal 0.0169097 -0.0280857 0.999462 + outer loop + vertex 0.938506 1.43273 2.64523 + vertex 0.938524 1.43773 2.64537 + vertex 0.933524 1.43278 2.64532 + endloop + endfacet + facet normal 0.0168595 -0.0331856 0.999307 + outer loop + vertex 0.933513 1.42776 2.64515 + vertex 0.938506 1.43273 2.64523 + vertex 0.933524 1.43278 2.64532 + endloop + endfacet + facet normal -0.00870494 -0.0331333 0.999413 + outer loop + vertex 0.933513 1.42776 2.64515 + vertex 0.933524 1.43278 2.64532 + vertex 0.928426 1.42774 2.64511 + endloop + endfacet + facet normal -0.00868393 -0.0394198 0.999185 + outer loop + vertex 0.928418 1.42271 2.64491 + vertex 0.933513 1.42776 2.64515 + vertex 0.928426 1.42774 2.64511 + endloop + endfacet + facet normal -0.0469658 -0.0393189 0.998122 + outer loop + vertex 0.928418 1.42271 2.64491 + vertex 0.928426 1.42774 2.64511 + vertex 0.923276 1.4226 2.64466 + endloop + endfacet + facet normal -0.0468752 -0.0431929 0.997966 + outer loop + vertex 0.923303 1.41758 2.64444 + vertex 0.928418 1.42271 2.64491 + vertex 0.923276 1.4226 2.64466 + endloop + endfacet + facet normal -0.0433264 -0.0429602 0.998137 + outer loop + vertex 0.923276 1.4226 2.64466 + vertex 0.928426 1.42774 2.64511 + vertex 0.923318 1.42765 2.64488 + endloop + endfacet + facet normal -0.0434661 -0.0356777 0.998418 + outer loop + vertex 0.928426 1.42774 2.64511 + vertex 0.928504 1.43279 2.64529 + vertex 0.923318 1.42765 2.64488 + endloop + endfacet + facet normal -0.0412728 -0.0378954 0.998429 + outer loop + vertex 0.923318 1.42765 2.64488 + vertex 0.928504 1.43279 2.64529 + vertex 0.923443 1.43271 2.64508 + endloop + endfacet + facet normal -0.0413919 -0.0302924 0.998684 + outer loop + vertex 0.928504 1.43279 2.64529 + vertex 0.928639 1.43777 2.64545 + vertex 0.923443 1.43271 2.64508 + endloop + endfacet + facet normal -0.0398131 -0.0319146 0.998697 + outer loop + vertex 0.923443 1.43271 2.64508 + vertex 0.928639 1.43777 2.64545 + vertex 0.923529 1.43767 2.64524 + endloop + endfacet + facet normal -0.0399415 -0.0257697 0.99887 + outer loop + vertex 0.928639 1.43777 2.64545 + vertex 0.928618 1.44258 2.64557 + vertex 0.923529 1.43767 2.64524 + endloop + endfacet + facet normal -0.0394817 -0.0262473 0.998876 + outer loop + vertex 0.923529 1.43767 2.64524 + vertex 0.928618 1.44258 2.64557 + vertex 0.923262 1.44238 2.64535 + endloop + endfacet + facet normal -0.0393729 -0.0291919 0.998798 + outer loop + vertex 0.928618 1.44258 2.64557 + vertex 0.927921 1.44679 2.64566 + vertex 0.923262 1.44238 2.64535 + endloop + endfacet + facet normal -0.0433534 -0.0249854 0.998747 + outer loop + vertex 0.923262 1.44238 2.64535 + vertex 0.927921 1.44679 2.64566 + vertex 0.922278 1.44708 2.64543 + endloop + endfacet + facet normal -0.0440034 -0.0380402 0.998307 + outer loop + vertex 0.922278 1.44708 2.64543 + vertex 0.927921 1.44679 2.64566 + vertex 0.927007 1.45048 2.64576 + endloop + endfacet + facet normal -0.0381251 -0.0462175 0.998204 + outer loop + vertex 0.92319 1.45126 2.64566 + vertex 0.922278 1.44708 2.64543 + vertex 0.927007 1.45048 2.64576 + endloop + endfacet + facet normal -0.0354654 -0.0331178 0.998822 + outer loop + vertex 0.927007 1.45048 2.64576 + vertex 0.926134 1.45415 2.64586 + vertex 0.92319 1.45126 2.64566 + endloop + endfacet + facet normal -0.00418218 -0.0257041 0.999661 + outer loop + vertex 0.930497 1.45393 2.64587 + vertex 0.926134 1.45415 2.64586 + vertex 0.927007 1.45048 2.64576 + endloop + endfacet + facet normal -0.00396457 -0.0215289 0.99976 + outer loop + vertex 0.930497 1.45393 2.64587 + vertex 0.929577 1.45788 2.64595 + vertex 0.926134 1.45415 2.64586 + endloop + endfacet + facet normal -0.00787367 -0.0179196 0.999808 + outer loop + vertex 0.926134 1.45415 2.64586 + vertex 0.929577 1.45788 2.64595 + vertex 0.925184 1.45832 2.64592 + endloop + endfacet + facet normal -0.00804314 -0.0196116 0.999775 + outer loop + vertex 0.929577 1.45788 2.64595 + vertex 0.92892 1.46247 2.64603 + vertex 0.925184 1.45832 2.64592 + endloop + endfacet + facet normal -0.011548 -0.0164522 0.999798 + outer loop + vertex 0.925184 1.45832 2.64592 + vertex 0.92892 1.46247 2.64603 + vertex 0.924655 1.46308 2.646 + endloop + endfacet + facet normal -0.0114198 -0.0155655 0.999814 + outer loop + vertex 0.92892 1.46247 2.64603 + vertex 0.928658 1.46744 2.64611 + vertex 0.924655 1.46308 2.646 + endloop + endfacet + facet normal -0.0138374 -0.0133422 0.999815 + outer loop + vertex 0.924655 1.46308 2.646 + vertex 0.928658 1.46744 2.64611 + vertex 0.92451 1.46809 2.64606 + endloop + endfacet + facet normal -0.013349 -0.010257 0.999858 + outer loop + vertex 0.928658 1.46744 2.64611 + vertex 0.928657 1.4725 2.64616 + vertex 0.92451 1.46809 2.64606 + endloop + endfacet + facet normal -0.0146958 -0.00899083 0.999852 + outer loop + vertex 0.92451 1.46809 2.64606 + vertex 0.928657 1.4725 2.64616 + vertex 0.924483 1.47315 2.64611 + endloop + endfacet + facet normal -0.0142409 -0.00604473 0.99988 + outer loop + vertex 0.928657 1.4725 2.64616 + vertex 0.92865 1.47757 2.64619 + vertex 0.924483 1.47315 2.64611 + endloop + endfacet + facet normal -0.0154207 -0.00493175 0.999869 + outer loop + vertex 0.924483 1.47315 2.64611 + vertex 0.92865 1.47757 2.64619 + vertex 0.924288 1.47826 2.64613 + endloop + endfacet + facet normal -0.0153465 -0.00446042 0.999872 + outer loop + vertex 0.92865 1.47757 2.64619 + vertex 0.928503 1.48267 2.64621 + vertex 0.924288 1.47826 2.64613 + endloop + endfacet + facet normal -0.0152939 -0.00451073 0.999873 + outer loop + vertex 0.924288 1.47826 2.64613 + vertex 0.928503 1.48267 2.64621 + vertex 0.923716 1.48373 2.64614 + endloop + endfacet + facet normal -0.0155863 -0.00582864 0.999862 + outer loop + vertex 0.928503 1.48267 2.64621 + vertex 0.928519 1.4877 2.64624 + vertex 0.923716 1.48373 2.64614 + endloop + endfacet + facet normal -0.0101632 -0.0123946 0.999872 + outer loop + vertex 0.923716 1.48373 2.64614 + vertex 0.928519 1.4877 2.64624 + vertex 0.924922 1.48861 2.64622 + endloop + endfacet + facet normal -0.00885116 -0.00721036 0.999935 + outer loop + vertex 0.928519 1.4877 2.64624 + vertex 0.928514 1.49247 2.64628 + vertex 0.924922 1.48861 2.64622 + endloop + endfacet + facet normal -0.0132007 -0.00315852 0.999908 + outer loop + vertex 0.924922 1.48861 2.64622 + vertex 0.928514 1.49247 2.64628 + vertex 0.924208 1.49257 2.64622 + endloop + endfacet + facet normal -0.0132721 -0.00601613 0.999894 + outer loop + vertex 0.928514 1.49247 2.64628 + vertex 0.928339 1.49725 2.6463 + vertex 0.924208 1.49257 2.64622 + endloop + endfacet + facet normal -0.0146476 -0.00480125 0.999881 + outer loop + vertex 0.924208 1.49257 2.64622 + vertex 0.928339 1.49725 2.6463 + vertex 0.923899 1.49744 2.64624 + endloop + endfacet + facet normal -0.0146355 -0.00451694 0.999883 + outer loop + vertex 0.928339 1.49725 2.6463 + vertex 0.928287 1.50222 2.64632 + vertex 0.923899 1.49744 2.64624 + endloop + endfacet + facet normal -0.0156538 -0.00358238 0.999871 + outer loop + vertex 0.923899 1.49744 2.64624 + vertex 0.928287 1.50222 2.64632 + vertex 0.923848 1.50245 2.64626 + endloop + endfacet + facet normal -0.0155329 -0.00125429 0.999879 + outer loop + vertex 0.928287 1.50222 2.64632 + vertex 0.928326 1.50724 2.64633 + vertex 0.923848 1.50245 2.64626 + endloop + endfacet + facet normal -0.0150507 -0.00170525 0.999885 + outer loop + vertex 0.923848 1.50245 2.64626 + vertex 0.928326 1.50724 2.64633 + vertex 0.923882 1.50747 2.64626 + endloop + endfacet + facet normal -0.0148776 0.00173463 0.999888 + outer loop + vertex 0.928326 1.50724 2.64633 + vertex 0.928383 1.51226 2.64632 + vertex 0.923882 1.50747 2.64626 + endloop + endfacet + facet normal -0.0141149 0.00101872 0.9999 + outer loop + vertex 0.923882 1.50747 2.64626 + vertex 0.928383 1.51226 2.64632 + vertex 0.923905 1.51247 2.64626 + endloop + endfacet + facet normal -0.0140035 0.00348253 0.999896 + outer loop + vertex 0.928383 1.51226 2.64632 + vertex 0.928424 1.51729 2.64631 + vertex 0.923905 1.51247 2.64626 + endloop + endfacet + facet normal -0.0140584 0.00353399 0.999895 + outer loop + vertex 0.923905 1.51247 2.64626 + vertex 0.928424 1.51729 2.64631 + vertex 0.923909 1.51747 2.64624 + endloop + endfacet + facet normal -0.0139833 0.00538243 0.999888 + outer loop + vertex 0.928424 1.51729 2.64631 + vertex 0.92848 1.52235 2.64628 + vertex 0.923909 1.51747 2.64624 + endloop + endfacet + facet normal -0.0142083 0.00559329 0.999883 + outer loop + vertex 0.923909 1.51747 2.64624 + vertex 0.92848 1.52235 2.64628 + vertex 0.923922 1.52249 2.64621 + endloop + endfacet + facet normal -0.0141687 0.00684522 0.999876 + outer loop + vertex 0.92848 1.52235 2.64628 + vertex 0.928538 1.52742 2.64625 + vertex 0.923922 1.52249 2.64621 + endloop + endfacet + facet normal -0.0155461 0.00813697 0.999846 + outer loop + vertex 0.923922 1.52249 2.64621 + vertex 0.928538 1.52742 2.64625 + vertex 0.923974 1.52751 2.64617 + endloop + endfacet + facet normal -0.0155129 0.00968428 0.999833 + outer loop + vertex 0.928538 1.52742 2.64625 + vertex 0.928596 1.53248 2.6462 + vertex 0.923974 1.52751 2.64617 + endloop + endfacet + facet normal -0.015286 0.00947319 0.999838 + outer loop + vertex 0.923974 1.52751 2.64617 + vertex 0.928596 1.53248 2.6462 + vertex 0.92398 1.53248 2.64613 + endloop + endfacet + facet normal -0.0152858 0.0116103 0.999816 + outer loop + vertex 0.928596 1.53248 2.6462 + vertex 0.928586 1.53754 2.64614 + vertex 0.92398 1.53248 2.64613 + endloop + endfacet + facet normal -0.015596 0.0118928 0.999808 + outer loop + vertex 0.92398 1.53248 2.64613 + vertex 0.928586 1.53754 2.64614 + vertex 0.923606 1.5376 2.64606 + endloop + endfacet + facet normal -0.0155862 0.0126522 0.999798 + outer loop + vertex 0.928586 1.53754 2.64614 + vertex 0.928745 1.54269 2.64608 + vertex 0.923606 1.5376 2.64606 + endloop + endfacet + facet normal -0.0126778 0.00971398 0.999872 + outer loop + vertex 0.923606 1.5376 2.64606 + vertex 0.928745 1.54269 2.64608 + vertex 0.924567 1.54335 2.64602 + endloop + endfacet + facet normal -0.0121789 0.0128795 0.999843 + outer loop + vertex 0.928745 1.54269 2.64608 + vertex 0.928925 1.54784 2.64601 + vertex 0.924567 1.54335 2.64602 + endloop + endfacet + facet normal -0.0109242 0.011662 0.999872 + outer loop + vertex 0.924567 1.54335 2.64602 + vertex 0.928925 1.54784 2.64601 + vertex 0.924846 1.54845 2.64596 + endloop + endfacet + facet normal -0.0107203 0.0130137 0.999858 + outer loop + vertex 0.928925 1.54784 2.64601 + vertex 0.928565 1.55276 2.64594 + vertex 0.924846 1.54845 2.64596 + endloop + endfacet + facet normal -0.00966488 0.0121029 0.99988 + outer loop + vertex 0.924846 1.54845 2.64596 + vertex 0.928565 1.55276 2.64594 + vertex 0.92466 1.55321 2.6459 + endloop + endfacet + facet normal -0.0097767 0.0111275 0.99989 + outer loop + vertex 0.928565 1.55276 2.64594 + vertex 0.9275 1.5565 2.64589 + vertex 0.92466 1.55321 2.6459 + endloop + endfacet + facet normal -0.0128473 0.0137796 0.999823 + outer loop + vertex 0.92466 1.55321 2.6459 + vertex 0.9275 1.5565 2.64589 + vertex 0.924446 1.55758 2.64584 + endloop + endfacet + facet normal -0.0116747 0.0170963 0.999786 + outer loop + vertex 0.9275 1.5565 2.64589 + vertex 0.927772 1.56056 2.64583 + vertex 0.924446 1.55758 2.64584 + endloop + endfacet + facet normal -0.00998258 0.0152093 0.999834 + outer loop + vertex 0.924446 1.55758 2.64584 + vertex 0.927772 1.56056 2.64583 + vertex 0.924353 1.56098 2.64578 + endloop + endfacet + facet normal -0.00920325 0.021536 0.999726 + outer loop + vertex 0.927772 1.56056 2.64583 + vertex 0.926094 1.56399 2.64574 + vertex 0.924353 1.56098 2.64578 + endloop + endfacet + facet normal 0.00404553 0.0160447 0.999863 + outer loop + vertex 0.927772 1.56056 2.64583 + vertex 0.9275 1.5565 2.64589 + vertex 0.931937 1.55799 2.64585 + endloop + endfacet + facet normal 0.00413 0.0161818 0.999861 + outer loop + vertex 0.931188 1.56196 2.64579 + vertex 0.927772 1.56056 2.64583 + vertex 0.931937 1.55799 2.64585 + endloop + endfacet + facet normal 0.00928841 0.0171563 0.99981 + outer loop + vertex 0.931188 1.56196 2.64579 + vertex 0.931937 1.55799 2.64585 + vertex 0.933812 1.56184 2.64577 + endloop + endfacet + facet normal 0.00958063 0.0238578 0.999669 + outer loop + vertex 0.933812 1.56184 2.64577 + vertex 0.933333 1.56499 2.6457 + vertex 0.931188 1.56196 2.64579 + endloop + endfacet + facet normal 0.0135222 0.0244563 0.999609 + outer loop + vertex 0.936282 1.56346 2.64569 + vertex 0.933333 1.56499 2.6457 + vertex 0.933812 1.56184 2.64577 + endloop + endfacet + facet normal 0.0171696 0.0314726 0.999357 + outer loop + vertex 0.936282 1.56346 2.64569 + vertex 0.93905 1.56709 2.64553 + vertex 0.933333 1.56499 2.6457 + endloop + endfacet + facet normal 0.0224922 0.0274156 0.999371 + outer loop + vertex 0.936282 1.56346 2.64569 + vertex 0.93901 1.56292 2.64565 + vertex 0.93905 1.56709 2.64553 + endloop + endfacet + facet normal 0.021303 0.0213323 0.999545 + outer loop + vertex 0.93901 1.56292 2.64565 + vertex 0.936282 1.56346 2.64569 + vertex 0.936387 1.56049 2.64575 + endloop + endfacet + facet normal 0.0224322 0.0201129 0.999546 + outer loop + vertex 0.940172 1.55979 2.64568 + vertex 0.93901 1.56292 2.64565 + vertex 0.936387 1.56049 2.64575 + endloop + endfacet + facet normal 0.0221107 0.0183775 0.999587 + outer loop + vertex 0.936387 1.56049 2.64575 + vertex 0.936853 1.55646 2.64582 + vertex 0.940172 1.55979 2.64568 + endloop + endfacet + facet normal 0.0219083 0.0185791 0.999587 + outer loop + vertex 0.940172 1.55979 2.64568 + vertex 0.936853 1.55646 2.64582 + vertex 0.941126 1.55559 2.64574 + endloop + endfacet + facet normal 0.0321695 0.0209025 0.999264 + outer loop + vertex 0.941126 1.55559 2.64574 + vertex 0.944402 1.55904 2.64556 + vertex 0.940172 1.55979 2.64568 + endloop + endfacet + facet normal 0.0324368 0.0224084 0.999223 + outer loop + vertex 0.944402 1.55904 2.64556 + vertex 0.943303 1.5639 2.64549 + vertex 0.940172 1.55979 2.64568 + endloop + endfacet + facet normal 0.0311907 0.0233581 0.99924 + outer loop + vertex 0.93901 1.56292 2.64565 + vertex 0.940172 1.55979 2.64568 + vertex 0.943303 1.5639 2.64549 + endloop + endfacet + facet normal 0.0361211 0.0232385 0.999077 + outer loop + vertex 0.944402 1.55904 2.64556 + vertex 0.948395 1.56294 2.64533 + vertex 0.943303 1.5639 2.64549 + endloop + endfacet + facet normal 0.0375736 0.0217504 0.999057 + outer loop + vertex 0.948825 1.55821 2.64541 + vertex 0.948395 1.56294 2.64533 + vertex 0.944402 1.55904 2.64556 + endloop + endfacet + facet normal 0.0373445 0.0205208 0.999092 + outer loop + vertex 0.945431 1.55408 2.64563 + vertex 0.948825 1.55821 2.64541 + vertex 0.944402 1.55904 2.64556 + endloop + endfacet + facet normal 0.0378953 0.0200678 0.99908 + outer loop + vertex 0.949612 1.55429 2.64546 + vertex 0.948825 1.55821 2.64541 + vertex 0.945431 1.55408 2.64563 + endloop + endfacet + facet normal 0.0379065 0.0198496 0.999084 + outer loop + vertex 0.945431 1.55408 2.64563 + vertex 0.948711 1.54971 2.64559 + vertex 0.949612 1.55429 2.64546 + endloop + endfacet + facet normal 0.0362114 0.0201847 0.99914 + outer loop + vertex 0.948711 1.54971 2.64559 + vertex 0.953281 1.5529 2.64536 + vertex 0.949612 1.55429 2.64546 + endloop + endfacet + facet normal 0.0362436 0.0202699 0.999137 + outer loop + vertex 0.953281 1.5529 2.64536 + vertex 0.953303 1.55761 2.64526 + vertex 0.949612 1.55429 2.64546 + endloop + endfacet + facet normal 0.035539 0.0202737 0.999163 + outer loop + vertex 0.953281 1.5529 2.64536 + vertex 0.95809 1.55716 2.6451 + vertex 0.953303 1.55761 2.64526 + endloop + endfacet + facet normal 0.0356849 0.0218444 0.999124 + outer loop + vertex 0.95809 1.55716 2.6451 + vertex 0.958185 1.56215 2.64499 + vertex 0.953303 1.55761 2.64526 + endloop + endfacet + facet normal 0.0358872 0.0216268 0.999122 + outer loop + vertex 0.953303 1.55761 2.64526 + vertex 0.958185 1.56215 2.64499 + vertex 0.953202 1.56238 2.64516 + endloop + endfacet + facet normal 0.036893 0.0216472 0.999085 + outer loop + vertex 0.953303 1.55761 2.64526 + vertex 0.953202 1.56238 2.64516 + vertex 0.948825 1.55821 2.64541 + endloop + endfacet + facet normal 0.0359965 0.0240542 0.999062 + outer loop + vertex 0.958185 1.56215 2.64499 + vertex 0.958258 1.56718 2.64487 + vertex 0.953202 1.56238 2.64516 + endloop + endfacet + facet normal 0.0362964 0.0237382 0.999059 + outer loop + vertex 0.953202 1.56238 2.64516 + vertex 0.958258 1.56718 2.64487 + vertex 0.953209 1.56733 2.64505 + endloop + endfacet + facet normal 0.0370924 0.0237364 0.99903 + outer loop + vertex 0.953202 1.56238 2.64516 + vertex 0.953209 1.56733 2.64505 + vertex 0.948395 1.56294 2.64533 + endloop + endfacet + facet normal 0.0368978 0.02395 0.999032 + outer loop + vertex 0.948395 1.56294 2.64533 + vertex 0.953209 1.56733 2.64505 + vertex 0.948408 1.56776 2.64521 + endloop + endfacet + facet normal 0.0363718 0.0264697 0.998988 + outer loop + vertex 0.958258 1.56718 2.64487 + vertex 0.958328 1.57224 2.64473 + vertex 0.953209 1.56733 2.64505 + endloop + endfacet + facet normal 0.0368867 0.0259332 0.998983 + outer loop + vertex 0.953209 1.56733 2.64505 + vertex 0.958328 1.57224 2.64473 + vertex 0.953287 1.57229 2.64491 + endloop + endfacet + facet normal 0.0369135 0.0288415 0.998902 + outer loop + vertex 0.958328 1.57224 2.64473 + vertex 0.958388 1.5773 2.64458 + vertex 0.953287 1.57229 2.64491 + endloop + endfacet + facet normal 0.0416309 0.0287805 0.998718 + outer loop + vertex 0.958328 1.57224 2.64473 + vertex 0.963539 1.5774 2.64436 + vertex 0.958388 1.5773 2.64458 + endloop + endfacet + facet normal 0.0415713 0.0316199 0.998635 + outer loop + vertex 0.963539 1.5774 2.64436 + vertex 0.963571 1.58246 2.6442 + vertex 0.958388 1.5773 2.64458 + endloop + endfacet + facet normal 0.0427417 0.0304427 0.998622 + outer loop + vertex 0.958388 1.5773 2.64458 + vertex 0.963571 1.58246 2.6442 + vertex 0.958429 1.58237 2.64442 + endloop + endfacet + facet normal 0.0426941 0.0328835 0.998547 + outer loop + vertex 0.963571 1.58246 2.6442 + vertex 0.963593 1.58751 2.64403 + vertex 0.958429 1.58237 2.64442 + endloop + endfacet + facet normal 0.0574463 0.0327942 0.99781 + outer loop + vertex 0.963571 1.58246 2.6442 + vertex 0.96871 1.58764 2.64373 + vertex 0.963593 1.58751 2.64403 + endloop + endfacet + facet normal 0.0574366 0.0331596 0.997798 + outer loop + vertex 0.96871 1.58764 2.64373 + vertex 0.968686 1.59264 2.64357 + vertex 0.963593 1.58751 2.64403 + endloop + endfacet + facet normal 0.0574782 0.0331182 0.997797 + outer loop + vertex 0.963593 1.58751 2.64403 + vertex 0.968686 1.59264 2.64357 + vertex 0.963597 1.59255 2.64387 + endloop + endfacet + facet normal 0.0879672 0.0332342 0.995569 + outer loop + vertex 0.96871 1.58764 2.64373 + vertex 0.97355 1.59269 2.64314 + vertex 0.968686 1.59264 2.64357 + endloop + endfacet + facet normal 0.0880245 0.0289327 0.995698 + outer loop + vertex 0.97355 1.59269 2.64314 + vertex 0.973381 1.59747 2.64301 + vertex 0.968686 1.59264 2.64357 + endloop + endfacet + facet normal 0.0833509 0.0335027 0.995957 + outer loop + vertex 0.968686 1.59264 2.64357 + vertex 0.973381 1.59747 2.64301 + vertex 0.968661 1.59761 2.64341 + endloop + endfacet + facet normal 0.0924184 0.0289374 0.9953 + outer loop + vertex 0.973602 1.58772 2.64328 + vertex 0.97355 1.59269 2.64314 + vertex 0.96871 1.58764 2.64373 + endloop + endfacet + facet normal 0.0923435 0.0327624 0.995188 + outer loop + vertex 0.968695 1.58261 2.6439 + vertex 0.973602 1.58772 2.64328 + vertex 0.96871 1.58764 2.64373 + endloop + endfacet + facet normal 0.0957281 0.0294889 0.994971 + outer loop + vertex 0.97359 1.58271 2.64343 + vertex 0.973602 1.58772 2.64328 + vertex 0.968695 1.58261 2.6439 + endloop + endfacet + facet normal 0.0957084 0.0302813 0.994949 + outer loop + vertex 0.968676 1.57758 2.64406 + vertex 0.97359 1.58271 2.64343 + vertex 0.968695 1.58261 2.6439 + endloop + endfacet + facet normal 0.058318 0.0305093 0.997832 + outer loop + vertex 0.968676 1.57758 2.64406 + vertex 0.968695 1.58261 2.6439 + vertex 0.963539 1.5774 2.64436 + endloop + endfacet + facet normal 0.0583703 0.0290652 0.997872 + outer loop + vertex 0.963508 1.57235 2.64451 + vertex 0.968676 1.57758 2.64406 + vertex 0.963539 1.5774 2.64436 + endloop + endfacet + facet normal 0.0605035 0.0269516 0.997804 + outer loop + vertex 0.968672 1.57257 2.64419 + vertex 0.968676 1.57758 2.64406 + vertex 0.963508 1.57235 2.64451 + endloop + endfacet + facet normal 0.0605482 0.0259225 0.997829 + outer loop + vertex 0.963464 1.5673 2.64465 + vertex 0.968672 1.57257 2.64419 + vertex 0.963508 1.57235 2.64451 + endloop + endfacet + facet normal 0.0415593 0.0261133 0.998795 + outer loop + vertex 0.963464 1.5673 2.64465 + vertex 0.963508 1.57235 2.64451 + vertex 0.958258 1.56718 2.64487 + endloop + endfacet + facet normal 0.0626471 0.0238423 0.997751 + outer loop + vertex 0.96866 1.56755 2.64431 + vertex 0.968672 1.57257 2.64419 + vertex 0.963464 1.5673 2.64465 + endloop + endfacet + facet normal 0.0626911 0.0229667 0.997769 + outer loop + vertex 0.96338 1.56223 2.64477 + vertex 0.96866 1.56755 2.64431 + vertex 0.963464 1.5673 2.64465 + endloop + endfacet + facet normal 0.0422289 0.0233303 0.998836 + outer loop + vertex 0.96338 1.56223 2.64477 + vertex 0.963464 1.5673 2.64465 + vertex 0.958185 1.56215 2.64499 + endloop + endfacet + facet normal 0.0647319 0.0209332 0.997683 + outer loop + vertex 0.968606 1.5625 2.64442 + vertex 0.96866 1.56755 2.64431 + vertex 0.96338 1.56223 2.64477 + endloop + endfacet + facet normal 0.0647508 0.0205764 0.997689 + outer loop + vertex 0.963268 1.55715 2.64488 + vertex 0.968606 1.5625 2.64442 + vertex 0.96338 1.56223 2.64477 + endloop + endfacet + facet normal 0.042857 0.0210845 0.998859 + outer loop + vertex 0.963268 1.55715 2.64488 + vertex 0.96338 1.56223 2.64477 + vertex 0.95809 1.55716 2.6451 + endloop + endfacet + facet normal 0.0428557 0.0198119 0.998885 + outer loop + vertex 0.958071 1.55219 2.6452 + vertex 0.963268 1.55715 2.64488 + vertex 0.95809 1.55716 2.6451 + endloop + endfacet + facet normal 0.0438074 0.0188135 0.998863 + outer loop + vertex 0.963214 1.5521 2.64498 + vertex 0.963268 1.55715 2.64488 + vertex 0.958071 1.55219 2.6452 + endloop + endfacet + facet normal 0.0437996 0.01835 0.998872 + outer loop + vertex 0.95834 1.54741 2.64528 + vertex 0.963214 1.5521 2.64498 + vertex 0.958071 1.55219 2.6452 + endloop + endfacet + facet normal 0.036832 0.0179623 0.99916 + outer loop + vertex 0.95834 1.54741 2.64528 + vertex 0.958071 1.55219 2.6452 + vertex 0.953624 1.54805 2.64544 + endloop + endfacet + facet normal 0.0368103 0.0178015 0.999164 + outer loop + vertex 0.954808 1.54396 2.64547 + vertex 0.95834 1.54741 2.64528 + vertex 0.953624 1.54805 2.64544 + endloop + endfacet + facet normal 0.0379024 0.0166796 0.999142 + outer loop + vertex 0.958677 1.54286 2.64534 + vertex 0.95834 1.54741 2.64528 + vertex 0.954808 1.54396 2.64547 + endloop + endfacet + facet normal 0.0378481 0.0164897 0.999147 + outer loop + vertex 0.954448 1.53917 2.64556 + vertex 0.958677 1.54286 2.64534 + vertex 0.954808 1.54396 2.64547 + endloop + endfacet + facet normal 0.0394448 0.0146562 0.999114 + outer loop + vertex 0.959409 1.53905 2.64537 + vertex 0.958677 1.54286 2.64534 + vertex 0.954448 1.53917 2.64556 + endloop + endfacet + facet normal 0.039399 0.0127455 0.999142 + outer loop + vertex 0.954448 1.53917 2.64556 + vertex 0.958233 1.53455 2.64547 + vertex 0.959409 1.53905 2.64537 + endloop + endfacet + facet normal 0.0490269 0.0102179 0.998745 + outer loop + vertex 0.958233 1.53455 2.64547 + vertex 0.963394 1.53785 2.64518 + vertex 0.959409 1.53905 2.64537 + endloop + endfacet + facet normal 0.0497931 0.0127751 0.998678 + outer loop + vertex 0.963394 1.53785 2.64518 + vertex 0.963434 1.54247 2.64512 + vertex 0.959409 1.53905 2.64537 + endloop + endfacet + facet normal 0.0709477 0.0125761 0.997401 + outer loop + vertex 0.963394 1.53785 2.64518 + vertex 0.968421 1.54235 2.64477 + vertex 0.963434 1.54247 2.64512 + endloop + endfacet + facet normal 0.0709691 0.013558 0.997386 + outer loop + vertex 0.968421 1.54235 2.64477 + vertex 0.968432 1.54729 2.6447 + vertex 0.963434 1.54247 2.64512 + endloop + endfacet + facet normal 0.0687417 0.0158741 0.997508 + outer loop + vertex 0.963434 1.54247 2.64512 + vertex 0.968432 1.54729 2.6447 + vertex 0.963267 1.54716 2.64506 + endloop + endfacet + facet normal 0.0468932 0.0151159 0.998786 + outer loop + vertex 0.963434 1.54247 2.64512 + vertex 0.963267 1.54716 2.64506 + vertex 0.958677 1.54286 2.64534 + endloop + endfacet + facet normal 0.0687614 0.0151593 0.997518 + outer loop + vertex 0.968432 1.54729 2.6447 + vertex 0.968451 1.55232 2.64462 + vertex 0.963267 1.54716 2.64506 + endloop + endfacet + facet normal 0.0665678 0.0173703 0.997631 + outer loop + vertex 0.963267 1.54716 2.64506 + vertex 0.968451 1.55232 2.64462 + vertex 0.963214 1.5521 2.64498 + endloop + endfacet + facet normal 0.0665518 0.0177359 0.997625 + outer loop + vertex 0.968451 1.55232 2.64462 + vertex 0.968523 1.55742 2.64453 + vertex 0.963214 1.5521 2.64498 + endloop + endfacet + facet normal 0.110419 0.0170464 0.993739 + outer loop + vertex 0.968451 1.55232 2.64462 + vertex 0.973572 1.55768 2.64396 + vertex 0.968523 1.55742 2.64453 + endloop + endfacet + facet normal 0.110386 0.0176533 0.993732 + outer loop + vertex 0.973572 1.55768 2.64396 + vertex 0.973609 1.56274 2.64387 + vertex 0.968523 1.55742 2.64453 + endloop + endfacet + facet normal 0.109141 0.0188581 0.993847 + outer loop + vertex 0.968523 1.55742 2.64453 + vertex 0.973609 1.56274 2.64387 + vertex 0.968606 1.5625 2.64442 + endloop + endfacet + facet normal 0.109132 0.0190593 0.993845 + outer loop + vertex 0.973609 1.56274 2.64387 + vertex 0.973617 1.56775 2.64377 + vertex 0.968606 1.5625 2.64442 + endloop + endfacet + facet normal 0.111173 0.0163171 0.993667 + outer loop + vertex 0.973535 1.5526 2.64405 + vertex 0.973572 1.55768 2.64396 + vertex 0.968451 1.55232 2.64462 + endloop + endfacet + facet normal 0.11125 0.0149383 0.99368 + outer loop + vertex 0.968432 1.54729 2.6447 + vertex 0.973535 1.5526 2.64405 + vertex 0.968451 1.55232 2.64462 + endloop + endfacet + facet normal 0.112716 0.0135112 0.993535 + outer loop + vertex 0.973506 1.54753 2.64412 + vertex 0.973535 1.5526 2.64405 + vertex 0.968432 1.54729 2.6447 + endloop + endfacet + facet normal 0.112721 0.0134154 0.993536 + outer loop + vertex 0.968421 1.54235 2.64477 + vertex 0.973506 1.54753 2.64412 + vertex 0.968432 1.54729 2.6447 + endloop + endfacet + facet normal 0.114195 0.0119497 0.993386 + outer loop + vertex 0.973483 1.5425 2.64419 + vertex 0.973506 1.54753 2.64412 + vertex 0.968421 1.54235 2.64477 + endloop + endfacet + facet normal 0.114216 0.0112464 0.993392 + outer loop + vertex 0.968392 1.53743 2.64483 + vertex 0.973483 1.5425 2.64419 + vertex 0.968421 1.54235 2.64477 + endloop + endfacet + facet normal 0.116014 0.00941529 0.993203 + outer loop + vertex 0.973458 1.53748 2.64424 + vertex 0.973483 1.5425 2.64419 + vertex 0.968392 1.53743 2.64483 + endloop + endfacet + facet normal 0.116011 0.00974651 0.9932 + outer loop + vertex 0.968397 1.53249 2.64488 + vertex 0.973458 1.53748 2.64424 + vertex 0.968392 1.53743 2.64483 + endloop + endfacet + facet normal 0.0727797 0.00974247 0.9973 + outer loop + vertex 0.968397 1.53249 2.64488 + vertex 0.968392 1.53743 2.64483 + vertex 0.963371 1.533 2.64524 + endloop + endfacet + facet normal 0.0728903 0.0108311 0.997281 + outer loop + vertex 0.963562 1.52803 2.64528 + vertex 0.968397 1.53249 2.64488 + vertex 0.963371 1.533 2.64524 + endloop + endfacet + facet normal 0.0497921 0.00995812 0.99871 + outer loop + vertex 0.963562 1.52803 2.64528 + vertex 0.963371 1.533 2.64524 + vertex 0.959068 1.5292 2.64549 + endloop + endfacet + facet normal 0.0494202 0.00851618 0.998742 + outer loop + vertex 0.959372 1.52422 2.64552 + vertex 0.963562 1.52803 2.64528 + vertex 0.959068 1.5292 2.64549 + endloop + endfacet + facet normal 0.0405365 0.00797657 0.999146 + outer loop + vertex 0.959372 1.52422 2.64552 + vertex 0.959068 1.5292 2.64549 + vertex 0.95555 1.52566 2.64566 + endloop + endfacet + facet normal 0.0396259 0.00555727 0.999199 + outer loop + vertex 0.955729 1.5207 2.64568 + vertex 0.959372 1.52422 2.64552 + vertex 0.95555 1.52566 2.64566 + endloop + endfacet + facet normal 0.0374763 0.00548025 0.999282 + outer loop + vertex 0.95555 1.52566 2.64566 + vertex 0.952153 1.52199 2.64581 + vertex 0.955729 1.5207 2.64568 + endloop + endfacet + facet normal 0.0367654 0.00349408 0.999318 + outer loop + vertex 0.952153 1.52199 2.64581 + vertex 0.952174 1.51699 2.64583 + vertex 0.955729 1.5207 2.64568 + endloop + endfacet + facet normal 0.0369792 0.00328938 0.999311 + outer loop + vertex 0.955729 1.5207 2.64568 + vertex 0.952174 1.51699 2.64583 + vertex 0.95567 1.51571 2.6457 + endloop + endfacet + facet normal 0.0381705 0.00327519 0.999266 + outer loop + vertex 0.95567 1.51571 2.6457 + vertex 0.959413 1.51923 2.64555 + vertex 0.955729 1.5207 2.64568 + endloop + endfacet + facet normal 0.0384501 0.00297727 0.999256 + outer loop + vertex 0.95921 1.51408 2.64557 + vertex 0.959413 1.51923 2.64555 + vertex 0.95567 1.51571 2.6457 + endloop + endfacet + facet normal 0.0370655 -3.44404e-05 0.999313 + outer loop + vertex 0.955376 1.51083 2.64571 + vertex 0.95921 1.51408 2.64557 + vertex 0.95567 1.51571 2.6457 + endloop + endfacet + facet normal 0.0369824 -2.94266e-05 0.999316 + outer loop + vertex 0.95567 1.51571 2.6457 + vertex 0.952098 1.51208 2.64583 + vertex 0.955376 1.51083 2.64571 + endloop + endfacet + facet normal 0.0359803 -0.00267085 0.999349 + outer loop + vertex 0.952098 1.51208 2.64583 + vertex 0.952068 1.50758 2.64582 + vertex 0.955376 1.51083 2.64571 + endloop + endfacet + facet normal 0.0369632 -0.00366997 0.99931 + outer loop + vertex 0.955376 1.51083 2.64571 + vertex 0.952068 1.50758 2.64582 + vertex 0.954723 1.50698 2.64572 + endloop + endfacet + facet normal 0.0358252 -0.00347702 0.999352 + outer loop + vertex 0.954723 1.50698 2.64572 + vertex 0.958464 1.50832 2.64559 + vertex 0.955376 1.51083 2.64571 + endloop + endfacet + facet normal 0.036155 -0.0043959 0.999337 + outer loop + vertex 0.954723 1.50698 2.64572 + vertex 0.955214 1.50365 2.64569 + vertex 0.958464 1.50832 2.64559 + endloop + endfacet + facet normal 0.0337947 -0.00275229 0.999425 + outer loop + vertex 0.958464 1.50832 2.64559 + vertex 0.955214 1.50365 2.64569 + vertex 0.958905 1.503 2.64556 + endloop + endfacet + facet normal 0.0441824 -0.00189109 0.999022 + outer loop + vertex 0.958905 1.503 2.64556 + vertex 0.963316 1.50757 2.64538 + vertex 0.958464 1.50832 2.64559 + endloop + endfacet + facet normal 0.0445476 0.000459022 0.999007 + outer loop + vertex 0.963316 1.50757 2.64538 + vertex 0.963428 1.51285 2.64537 + vertex 0.958464 1.50832 2.64559 + endloop + endfacet + facet normal 0.0469184 -0.00214697 0.998896 + outer loop + vertex 0.958464 1.50832 2.64559 + vertex 0.963428 1.51285 2.64537 + vertex 0.95921 1.51408 2.64557 + endloop + endfacet + facet normal 0.0483353 0.00269343 0.998828 + outer loop + vertex 0.963428 1.51285 2.64537 + vertex 0.963615 1.51806 2.64535 + vertex 0.95921 1.51408 2.64557 + endloop + endfacet + facet normal 0.0748373 0.00173504 0.997194 + outer loop + vertex 0.963428 1.51285 2.64537 + vertex 0.968424 1.51756 2.64499 + vertex 0.963615 1.51806 2.64535 + endloop + endfacet + facet normal 0.0752558 0.00578352 0.997147 + outer loop + vertex 0.968424 1.51756 2.64499 + vertex 0.968443 1.52257 2.64495 + vertex 0.963615 1.51806 2.64535 + endloop + endfacet + facet normal 0.0753897 0.00563936 0.997138 + outer loop + vertex 0.963615 1.51806 2.64535 + vertex 0.968443 1.52257 2.64495 + vertex 0.96364 1.52308 2.64531 + endloop + endfacet + facet normal 0.0493214 0.00577887 0.998766 + outer loop + vertex 0.963615 1.51806 2.64535 + vertex 0.96364 1.52308 2.64531 + vertex 0.959413 1.51923 2.64555 + endloop + endfacet + facet normal 0.0490876 0.00603609 0.998776 + outer loop + vertex 0.959413 1.51923 2.64555 + vertex 0.96364 1.52308 2.64531 + vertex 0.959372 1.52422 2.64552 + endloop + endfacet + facet normal 0.0755458 0.00712818 0.997117 + outer loop + vertex 0.968443 1.52257 2.64495 + vertex 0.968425 1.52753 2.64492 + vertex 0.96364 1.52308 2.64531 + endloop + endfacet + facet normal 0.074173 0.00861361 0.997208 + outer loop + vertex 0.96364 1.52308 2.64531 + vertex 0.968425 1.52753 2.64492 + vertex 0.963562 1.52803 2.64528 + endloop + endfacet + facet normal 0.119053 0.00725328 0.992861 + outer loop + vertex 0.968443 1.52257 2.64495 + vertex 0.973452 1.52752 2.64432 + vertex 0.968425 1.52753 2.64492 + endloop + endfacet + facet normal 0.119055 0.00802694 0.992855 + outer loop + vertex 0.973452 1.52752 2.64432 + vertex 0.973444 1.53248 2.64428 + vertex 0.968425 1.52753 2.64492 + endloop + endfacet + facet normal 0.117563 0.00955941 0.993019 + outer loop + vertex 0.968425 1.52753 2.64492 + vertex 0.973444 1.53248 2.64428 + vertex 0.968397 1.53249 2.64488 + endloop + endfacet + facet normal 0.118485 0.00783782 0.992925 + outer loop + vertex 0.973475 1.52256 2.64435 + vertex 0.973452 1.52752 2.64432 + vertex 0.968443 1.52257 2.64495 + endloop + endfacet + facet normal 0.11848 0.00559292 0.992941 + outer loop + vertex 0.968424 1.51756 2.64499 + vertex 0.973475 1.52256 2.64435 + vertex 0.968443 1.52257 2.64495 + endloop + endfacet + facet normal 0.118639 0.00543036 0.992923 + outer loop + vertex 0.973486 1.5176 2.64438 + vertex 0.973475 1.52256 2.64435 + vertex 0.968424 1.51756 2.64499 + endloop + endfacet + facet normal 0.118657 0.00307273 0.992931 + outer loop + vertex 0.968372 1.51249 2.64501 + vertex 0.973486 1.5176 2.64438 + vertex 0.968424 1.51756 2.64499 + endloop + endfacet + facet normal 0.11638 0.0053823 0.99319 + outer loop + vertex 0.973483 1.51261 2.64441 + vertex 0.973486 1.5176 2.64438 + vertex 0.968372 1.51249 2.64501 + endloop + endfacet + facet normal 0.116462 0.00200755 0.993193 + outer loop + vertex 0.968337 1.5074 2.64502 + vertex 0.973483 1.51261 2.64441 + vertex 0.968372 1.51249 2.64501 + endloop + endfacet + facet normal 0.0704646 0.00233099 0.997512 + outer loop + vertex 0.968337 1.5074 2.64502 + vertex 0.968372 1.51249 2.64501 + vertex 0.963316 1.50757 2.64538 + endloop + endfacet + facet normal 0.0703805 -0.00027602 0.99752 + outer loop + vertex 0.963371 1.50244 2.64537 + vertex 0.968337 1.5074 2.64502 + vertex 0.963316 1.50757 2.64538 + endloop + endfacet + facet normal 0.0687047 0.00140938 0.997636 + outer loop + vertex 0.968346 1.50239 2.64503 + vertex 0.968337 1.5074 2.64502 + vertex 0.963371 1.50244 2.64537 + endloop + endfacet + facet normal 0.0686874 -0.00030699 0.997638 + outer loop + vertex 0.963467 1.49758 2.64536 + vertex 0.968346 1.50239 2.64503 + vertex 0.963371 1.50244 2.64537 + endloop + endfacet + facet normal 0.0411506 -0.000853753 0.999153 + outer loop + vertex 0.963467 1.49758 2.64536 + vertex 0.963371 1.50244 2.64537 + vertex 0.959123 1.49807 2.64554 + endloop + endfacet + facet normal 0.0411577 -0.00079022 0.999152 + outer loop + vertex 0.959623 1.49395 2.64552 + vertex 0.963467 1.49758 2.64536 + vertex 0.959123 1.49807 2.64554 + endloop + endfacet + facet normal 0.0318947 -0.0019143 0.999489 + outer loop + vertex 0.959623 1.49395 2.64552 + vertex 0.959123 1.49807 2.64554 + vertex 0.955593 1.49377 2.64565 + endloop + endfacet + facet normal 0.0319269 -0.0026694 0.999487 + outer loop + vertex 0.955593 1.49377 2.64565 + vertex 0.957829 1.48883 2.64556 + vertex 0.959623 1.49395 2.64552 + endloop + endfacet + facet normal 0.0420461 -0.00622083 0.999096 + outer loop + vertex 0.957829 1.48883 2.64556 + vertex 0.963305 1.49275 2.64536 + vertex 0.959623 1.49395 2.64552 + endloop + endfacet + facet normal 0.0409809 -0.00473149 0.999149 + outer loop + vertex 0.96321 1.48766 2.64534 + vertex 0.963305 1.49275 2.64536 + vertex 0.957829 1.48883 2.64556 + endloop + endfacet + facet normal 0.041251 -0.00349101 0.999143 + outer loop + vertex 0.958754 1.48318 2.6455 + vertex 0.96321 1.48766 2.64534 + vertex 0.957829 1.48883 2.64556 + endloop + endfacet + facet normal 0.0374393 -0.00411584 0.99929 + outer loop + vertex 0.957829 1.48883 2.64556 + vertex 0.954934 1.48385 2.64565 + vertex 0.958754 1.48318 2.6455 + endloop + endfacet + facet normal 0.0370055 -0.00656218 0.999294 + outer loop + vertex 0.955003 1.47923 2.64562 + vertex 0.958754 1.48318 2.6455 + vertex 0.954934 1.48385 2.64565 + endloop + endfacet + facet normal 0.0395333 -0.00652381 0.999197 + outer loop + vertex 0.955003 1.47923 2.64562 + vertex 0.954934 1.48385 2.64565 + vertex 0.951733 1.48066 2.64576 + endloop + endfacet + facet normal 0.0384505 -0.00899582 0.99922 + outer loop + vertex 0.951325 1.4759 2.64573 + vertex 0.955003 1.47923 2.64562 + vertex 0.951733 1.48066 2.64576 + endloop + endfacet + facet normal 0.0369935 -0.00887133 0.999276 + outer loop + vertex 0.951733 1.48066 2.64576 + vertex 0.94783 1.47723 2.64587 + vertex 0.951325 1.4759 2.64573 + endloop + endfacet + facet normal 0.0359367 -0.0116525 0.999286 + outer loop + vertex 0.94783 1.47723 2.64587 + vertex 0.947593 1.47247 2.64582 + vertex 0.951325 1.4759 2.64573 + endloop + endfacet + facet normal 0.036561 -0.0123323 0.999255 + outer loop + vertex 0.951325 1.4759 2.64573 + vertex 0.947593 1.47247 2.64582 + vertex 0.950734 1.47133 2.64569 + endloop + endfacet + facet normal 0.0388699 -0.0126298 0.999164 + outer loop + vertex 0.950734 1.47133 2.64569 + vertex 0.954595 1.47424 2.64558 + vertex 0.951325 1.4759 2.64573 + endloop + endfacet + facet normal 0.0406976 -0.015064 0.999058 + outer loop + vertex 0.953374 1.4685 2.64554 + vertex 0.954595 1.47424 2.64558 + vertex 0.950734 1.47133 2.64569 + endloop + endfacet + facet normal 0.0388485 -0.0167897 0.999104 + outer loop + vertex 0.949456 1.46764 2.64568 + vertex 0.953374 1.4685 2.64554 + vertex 0.950734 1.47133 2.64569 + endloop + endfacet + facet normal 0.0380221 -0.016504 0.999141 + outer loop + vertex 0.950734 1.47133 2.64569 + vertex 0.947715 1.4691 2.64577 + vertex 0.949456 1.46764 2.64568 + endloop + endfacet + facet normal 0.0352911 -0.019761 0.999182 + outer loop + vertex 0.949456 1.46764 2.64568 + vertex 0.947715 1.4691 2.64577 + vertex 0.946429 1.46575 2.64575 + endloop + endfacet + facet normal 0.0360327 -0.0209533 0.999131 + outer loop + vertex 0.949456 1.46764 2.64568 + vertex 0.946429 1.46575 2.64575 + vertex 0.948676 1.46329 2.64562 + endloop + endfacet + facet normal 0.034583 -0.0222807 0.999153 + outer loop + vertex 0.944944 1.46228 2.64572 + vertex 0.948676 1.46329 2.64562 + vertex 0.946429 1.46575 2.64575 + endloop + endfacet + facet normal 0.0287847 -0.0198011 0.999389 + outer loop + vertex 0.943294 1.46378 2.6458 + vertex 0.944944 1.46228 2.64572 + vertex 0.946429 1.46575 2.64575 + endloop + endfacet + facet normal 0.0277555 -0.0181618 0.99945 + outer loop + vertex 0.946429 1.46575 2.64575 + vertex 0.943813 1.4678 2.64586 + vertex 0.943294 1.46378 2.6458 + endloop + endfacet + facet normal 0.022819 -0.0175263 0.999586 + outer loop + vertex 0.943294 1.46378 2.6458 + vertex 0.943813 1.4678 2.64586 + vertex 0.939048 1.46243 2.64587 + endloop + endfacet + facet normal 0.0234449 -0.0194917 0.999535 + outer loop + vertex 0.943294 1.46378 2.6458 + vertex 0.939048 1.46243 2.64587 + vertex 0.941705 1.46014 2.64577 + endloop + endfacet + facet normal 0.0236493 -0.0192536 0.999535 + outer loop + vertex 0.939048 1.46243 2.64587 + vertex 0.937994 1.45754 2.64581 + vertex 0.941705 1.46014 2.64577 + endloop + endfacet + facet normal 0.0233367 -0.0188076 0.999551 + outer loop + vertex 0.941705 1.46014 2.64577 + vertex 0.937994 1.45754 2.64581 + vertex 0.940276 1.45657 2.64573 + endloop + endfacet + facet normal 0.027971 -0.0206597 0.999395 + outer loop + vertex 0.940276 1.45657 2.64573 + vertex 0.944029 1.45799 2.64566 + vertex 0.941705 1.46014 2.64577 + endloop + endfacet + facet normal 0.0274494 -0.0212215 0.999398 + outer loop + vertex 0.944029 1.45799 2.64566 + vertex 0.944944 1.46228 2.64572 + vertex 0.941705 1.46014 2.64577 + endloop + endfacet + facet normal 0.0275448 -0.0195262 0.99943 + outer loop + vertex 0.940276 1.45657 2.64573 + vertex 0.939297 1.45273 2.64569 + vertex 0.944029 1.45799 2.64566 + endloop + endfacet + facet normal 0.028418 -0.020312 0.99939 + outer loop + vertex 0.944029 1.45799 2.64566 + vertex 0.939297 1.45273 2.64569 + vertex 0.94389 1.45278 2.64556 + endloop + endfacet + facet normal 0.0325935 -0.0204213 0.99926 + outer loop + vertex 0.94389 1.45278 2.64556 + vertex 0.948675 1.45786 2.6455 + vertex 0.944029 1.45799 2.64566 + endloop + endfacet + facet normal 0.0325808 -0.0208963 0.999251 + outer loop + vertex 0.948675 1.45786 2.6455 + vertex 0.948676 1.46329 2.64562 + vertex 0.944029 1.45799 2.64566 + endloop + endfacet + facet normal 0.0356168 -0.0208949 0.999147 + outer loop + vertex 0.948675 1.45786 2.6455 + vertex 0.953431 1.46286 2.64544 + vertex 0.948676 1.46329 2.64562 + endloop + endfacet + facet normal 0.0358826 -0.0180059 0.999194 + outer loop + vertex 0.953374 1.4685 2.64554 + vertex 0.948676 1.46329 2.64562 + vertex 0.953431 1.46286 2.64544 + endloop + endfacet + facet normal 0.0369887 -0.0179939 0.999154 + outer loop + vertex 0.953431 1.46286 2.64544 + vertex 0.958327 1.46768 2.64534 + vertex 0.953374 1.4685 2.64554 + endloop + endfacet + facet normal 0.0376261 -0.0141477 0.999192 + outer loop + vertex 0.958327 1.46768 2.64534 + vertex 0.95855 1.47292 2.64541 + vertex 0.953374 1.4685 2.64554 + endloop + endfacet + facet normal 0.0447235 -0.0144458 0.998895 + outer loop + vertex 0.958327 1.46768 2.64534 + vertex 0.96337 1.4725 2.64519 + vertex 0.95855 1.47292 2.64541 + endloop + endfacet + facet normal 0.0449813 -0.0115302 0.998921 + outer loop + vertex 0.96337 1.4725 2.64519 + vertex 0.963416 1.47751 2.64524 + vertex 0.95855 1.47292 2.64541 + endloop + endfacet + facet normal 0.0453015 -0.0118705 0.998903 + outer loop + vertex 0.95855 1.47292 2.64541 + vertex 0.963416 1.47751 2.64524 + vertex 0.958834 1.47808 2.64546 + endloop + endfacet + facet normal 0.0388803 -0.0115192 0.999177 + outer loop + vertex 0.95855 1.47292 2.64541 + vertex 0.958834 1.47808 2.64546 + vertex 0.954595 1.47424 2.64558 + endloop + endfacet + facet normal 0.0379028 -0.0104395 0.999227 + outer loop + vertex 0.954595 1.47424 2.64558 + vertex 0.958834 1.47808 2.64546 + vertex 0.955003 1.47923 2.64562 + endloop + endfacet + facet normal 0.0456301 -0.00922898 0.998916 + outer loop + vertex 0.963416 1.47751 2.64524 + vertex 0.9634 1.48254 2.64529 + vertex 0.958834 1.47808 2.64546 + endloop + endfacet + facet normal 0.0444284 -0.00799606 0.998981 + outer loop + vertex 0.958834 1.47808 2.64546 + vertex 0.9634 1.48254 2.64529 + vertex 0.958754 1.48318 2.6455 + endloop + endfacet + facet normal 0.0691812 -0.00913894 0.997562 + outer loop + vertex 0.963416 1.47751 2.64524 + vertex 0.968448 1.48249 2.64494 + vertex 0.9634 1.48254 2.64529 + endloop + endfacet + facet normal 0.0691992 -0.00727251 0.997576 + outer loop + vertex 0.968448 1.48249 2.64494 + vertex 0.96839 1.48748 2.64498 + vertex 0.9634 1.48254 2.64529 + endloop + endfacet + facet normal 0.0678905 -0.0059436 0.997675 + outer loop + vertex 0.9634 1.48254 2.64529 + vertex 0.96839 1.48748 2.64498 + vertex 0.96321 1.48766 2.64534 + endloop + endfacet + facet normal 0.0679175 -0.005179 0.997677 + outer loop + vertex 0.96839 1.48748 2.64498 + vertex 0.968345 1.49248 2.64501 + vertex 0.96321 1.48766 2.64534 + endloop + endfacet + facet normal 0.0679603 -0.00522482 0.997674 + outer loop + vertex 0.96321 1.48766 2.64534 + vertex 0.968345 1.49248 2.64501 + vertex 0.963305 1.49275 2.64536 + endloop + endfacet + facet normal 0.0680793 -0.00305698 0.997675 + outer loop + vertex 0.968345 1.49248 2.64501 + vertex 0.968351 1.49744 2.64503 + vertex 0.963305 1.49275 2.64536 + endloop + endfacet + facet normal 0.0687022 -0.0037304 0.99763 + outer loop + vertex 0.963305 1.49275 2.64536 + vertex 0.968351 1.49744 2.64503 + vertex 0.963467 1.49758 2.64536 + endloop + endfacet + facet normal 0.114684 -0.0031041 0.993397 + outer loop + vertex 0.968345 1.49248 2.64501 + vertex 0.973502 1.49762 2.64443 + vertex 0.968351 1.49744 2.64503 + endloop + endfacet + facet normal 0.114574 0.000174181 0.993415 + outer loop + vertex 0.973502 1.49762 2.64443 + vertex 0.973486 1.50261 2.64443 + vertex 0.968351 1.49744 2.64503 + endloop + endfacet + facet normal 0.115119 -0.000374664 0.993352 + outer loop + vertex 0.968351 1.49744 2.64503 + vertex 0.973486 1.50261 2.64443 + vertex 0.968346 1.50239 2.64503 + endloop + endfacet + facet normal 0.115056 0.00111807 0.993358 + outer loop + vertex 0.973486 1.50261 2.64443 + vertex 0.973481 1.50761 2.64443 + vertex 0.968346 1.50239 2.64503 + endloop + endfacet + facet normal 0.114247 -0.00266047 0.993449 + outer loop + vertex 0.973515 1.49263 2.64442 + vertex 0.973502 1.49762 2.64443 + vertex 0.968345 1.49248 2.64501 + endloop + endfacet + facet normal 0.114308 -0.00472863 0.993434 + outer loop + vertex 0.96839 1.48748 2.64498 + vertex 0.973515 1.49263 2.64442 + vertex 0.968345 1.49248 2.64501 + endloop + endfacet + facet normal 0.115848 -0.00627965 0.993247 + outer loop + vertex 0.973523 1.48766 2.64438 + vertex 0.973515 1.49263 2.64442 + vertex 0.96839 1.48748 2.64498 + endloop + endfacet + facet normal 0.115862 -0.00670282 0.993243 + outer loop + vertex 0.968448 1.48249 2.64494 + vertex 0.973523 1.48766 2.64438 + vertex 0.96839 1.48748 2.64498 + endloop + endfacet + facet normal 0.115655 -0.0064968 0.993268 + outer loop + vertex 0.973538 1.48271 2.64435 + vertex 0.973523 1.48766 2.64438 + vertex 0.968448 1.48249 2.64494 + endloop + endfacet + facet normal 0.11578 -0.00947577 0.99323 + outer loop + vertex 0.968476 1.47755 2.64489 + vertex 0.973538 1.48271 2.64435 + vertex 0.968448 1.48249 2.64494 + endloop + endfacet + facet normal 0.11276 -0.00647824 0.993601 + outer loop + vertex 0.973561 1.47777 2.64432 + vertex 0.973538 1.48271 2.64435 + vertex 0.968476 1.47755 2.64489 + endloop + endfacet + facet normal 0.112882 -0.00934666 0.993564 + outer loop + vertex 0.968506 1.4726 2.64484 + vertex 0.973561 1.47777 2.64432 + vertex 0.968476 1.47755 2.64489 + endloop + endfacet + facet normal 0.0677788 -0.00965607 0.997654 + outer loop + vertex 0.968506 1.4726 2.64484 + vertex 0.968476 1.47755 2.64489 + vertex 0.96337 1.4725 2.64519 + endloop + endfacet + facet normal 0.0678512 -0.0133005 0.997607 + outer loop + vertex 0.963373 1.4675 2.64512 + vertex 0.968506 1.4726 2.64484 + vertex 0.96337 1.4725 2.64519 + endloop + endfacet + facet normal 0.0651438 -0.0105649 0.99782 + outer loop + vertex 0.968544 1.46766 2.64479 + vertex 0.968506 1.4726 2.64484 + vertex 0.963373 1.4675 2.64512 + endloop + endfacet + facet normal 0.110571 -0.00705649 0.993843 + outer loop + vertex 0.973587 1.47281 2.64428 + vertex 0.973561 1.47777 2.64432 + vertex 0.968506 1.4726 2.64484 + endloop + endfacet + facet normal 0.0698199 -0.00978703 0.997512 + outer loop + vertex 0.968476 1.47755 2.64489 + vertex 0.968448 1.48249 2.64494 + vertex 0.963416 1.47751 2.64524 + endloop + endfacet + facet normal 0.0698321 -0.0117424 0.99749 + outer loop + vertex 0.96337 1.4725 2.64519 + vertex 0.968476 1.47755 2.64489 + vertex 0.963416 1.47751 2.64524 + endloop + endfacet + facet normal 0.0436596 -0.0133295 0.998958 + outer loop + vertex 0.963373 1.4675 2.64512 + vertex 0.96337 1.4725 2.64519 + vertex 0.958327 1.46768 2.64534 + endloop + endfacet + facet normal 0.0435477 -0.0164181 0.998916 + outer loop + vertex 0.958326 1.46254 2.64526 + vertex 0.963373 1.4675 2.64512 + vertex 0.958327 1.46768 2.64534 + endloop + endfacet + facet normal 0.0418989 -0.0147373 0.999013 + outer loop + vertex 0.963411 1.46254 2.64505 + vertex 0.963373 1.4675 2.64512 + vertex 0.958326 1.46254 2.64526 + endloop + endfacet + facet normal 0.0354411 -0.0164209 0.999237 + outer loop + vertex 0.958326 1.46254 2.64526 + vertex 0.958327 1.46768 2.64534 + vertex 0.953431 1.46286 2.64544 + endloop + endfacet + facet normal 0.035251 -0.0193302 0.999192 + outer loop + vertex 0.953404 1.45763 2.64534 + vertex 0.958326 1.46254 2.64526 + vertex 0.953431 1.46286 2.64544 + endloop + endfacet + facet normal 0.0344804 -0.0185569 0.999233 + outer loop + vertex 0.958342 1.45753 2.64517 + vertex 0.958326 1.46254 2.64526 + vertex 0.953404 1.45763 2.64534 + endloop + endfacet + facet normal 0.0339687 -0.0193244 0.999236 + outer loop + vertex 0.953404 1.45763 2.64534 + vertex 0.953431 1.46286 2.64544 + vertex 0.948675 1.45786 2.6455 + endloop + endfacet + facet normal 0.0339021 -0.0206688 0.999211 + outer loop + vertex 0.948538 1.45268 2.6454 + vertex 0.953404 1.45763 2.64534 + vertex 0.948675 1.45786 2.6455 + endloop + endfacet + facet normal 0.0340026 -0.0207677 0.999206 + outer loop + vertex 0.95336 1.45258 2.64524 + vertex 0.953404 1.45763 2.64534 + vertex 0.948538 1.45268 2.6454 + endloop + endfacet + facet normal 0.032827 -0.0206412 0.999248 + outer loop + vertex 0.948538 1.45268 2.6454 + vertex 0.948675 1.45786 2.6455 + vertex 0.94389 1.45278 2.64556 + endloop + endfacet + facet normal 0.0328193 -0.0210002 0.999241 + outer loop + vertex 0.943636 1.4477 2.64546 + vertex 0.948538 1.45268 2.6454 + vertex 0.94389 1.45278 2.64556 + endloop + endfacet + facet normal 0.0291104 -0.0208173 0.999359 + outer loop + vertex 0.943636 1.4477 2.64546 + vertex 0.94389 1.45278 2.64556 + vertex 0.938912 1.44774 2.6456 + endloop + endfacet + facet normal 0.0290984 -0.0220307 0.999334 + outer loop + vertex 0.938662 1.44273 2.64549 + vertex 0.943636 1.4477 2.64546 + vertex 0.938912 1.44774 2.6456 + endloop + endfacet + facet normal 0.0192985 -0.0215477 0.999582 + outer loop + vertex 0.938662 1.44273 2.64549 + vertex 0.938912 1.44774 2.6456 + vertex 0.93379 1.44276 2.64559 + endloop + endfacet + facet normal 0.0192721 -0.0259342 0.999478 + outer loop + vertex 0.933625 1.43778 2.64546 + vertex 0.938662 1.44273 2.64549 + vertex 0.93379 1.44276 2.64559 + endloop + endfacet + facet normal -0.0032425 -0.0251922 0.999677 + outer loop + vertex 0.933625 1.43778 2.64546 + vertex 0.93379 1.44276 2.64559 + vertex 0.928639 1.43777 2.64545 + endloop + endfacet + facet normal -0.00322823 -0.0313502 0.999503 + outer loop + vertex 0.928504 1.43279 2.64529 + vertex 0.933625 1.43778 2.64546 + vertex 0.928639 1.43777 2.64545 + endloop + endfacet + facet normal -0.00556194 -0.0289618 0.999565 + outer loop + vertex 0.933524 1.43278 2.64532 + vertex 0.933625 1.43778 2.64546 + vertex 0.928504 1.43279 2.64529 + endloop + endfacet + facet normal 0.0183001 -0.0249447 0.999521 + outer loop + vertex 0.938524 1.43773 2.64537 + vertex 0.938662 1.44273 2.64549 + vertex 0.933625 1.43778 2.64546 + endloop + endfacet + facet normal 0.018965 -0.0212051 0.999595 + outer loop + vertex 0.93379 1.44276 2.64559 + vertex 0.938912 1.44774 2.6456 + vertex 0.933821 1.44783 2.6457 + endloop + endfacet + facet normal -0.00298545 -0.0210735 0.999773 + outer loop + vertex 0.93379 1.44276 2.64559 + vertex 0.933821 1.44783 2.6457 + vertex 0.928618 1.44258 2.64557 + endloop + endfacet + facet normal 0.018997 -0.0194067 0.999631 + outer loop + vertex 0.939297 1.45273 2.64569 + vertex 0.933821 1.44783 2.6457 + vertex 0.938912 1.44774 2.6456 + endloop + endfacet + facet normal 0.0252045 -0.0263534 0.999335 + outer loop + vertex 0.93557 1.45187 2.64576 + vertex 0.933821 1.44783 2.6457 + vertex 0.939297 1.45273 2.64569 + endloop + endfacet + facet normal 0.0236977 -0.0197513 0.999524 + outer loop + vertex 0.939297 1.45273 2.64569 + vertex 0.937695 1.4545 2.64576 + vertex 0.93557 1.45187 2.64576 + endloop + endfacet + facet normal 0.0205195 -0.0171756 0.999642 + outer loop + vertex 0.937695 1.4545 2.64576 + vertex 0.934665 1.45421 2.64582 + vertex 0.93557 1.45187 2.64576 + endloop + endfacet + facet normal 0.0138939 -0.0197482 0.999708 + outer loop + vertex 0.93557 1.45187 2.64576 + vertex 0.934665 1.45421 2.64582 + vertex 0.931684 1.45068 2.64579 + endloop + endfacet + facet normal 0.0137275 -0.0196073 0.999714 + outer loop + vertex 0.934665 1.45421 2.64582 + vertex 0.930497 1.45393 2.64587 + vertex 0.931684 1.45068 2.64579 + endloop + endfacet + facet normal -0.00384811 -0.0260421 0.999653 + outer loop + vertex 0.931684 1.45068 2.64579 + vertex 0.930497 1.45393 2.64587 + vertex 0.927007 1.45048 2.64576 + endloop + endfacet + facet normal 0.0136357 -0.0182368 0.999741 + outer loop + vertex 0.934665 1.45421 2.64582 + vertex 0.934173 1.45785 2.64589 + vertex 0.930497 1.45393 2.64587 + endloop + endfacet + facet normal 0.0204939 -0.0173097 0.99964 + outer loop + vertex 0.937994 1.45754 2.64581 + vertex 0.934173 1.45785 2.64589 + vertex 0.934665 1.45421 2.64582 + endloop + endfacet + facet normal 0.0205363 -0.0173521 0.999639 + outer loop + vertex 0.937695 1.4545 2.64576 + vertex 0.937994 1.45754 2.64581 + vertex 0.934665 1.45421 2.64582 + endloop + endfacet + facet normal 0.0144988 -0.0217262 0.999659 + outer loop + vertex 0.93557 1.45187 2.64576 + vertex 0.931684 1.45068 2.64579 + vertex 0.933821 1.44783 2.6457 + endloop + endfacet + facet normal 0.000499062 -0.0322123 0.999481 + outer loop + vertex 0.927921 1.44679 2.64566 + vertex 0.933821 1.44783 2.6457 + vertex 0.931684 1.45068 2.64579 + endloop + endfacet + facet normal 0.0300755 -0.0230091 0.999283 + outer loop + vertex 0.943478 1.44268 2.64535 + vertex 0.943636 1.4477 2.64546 + vertex 0.938662 1.44273 2.64549 + endloop + endfacet + facet normal 0.0338797 -0.0220439 0.999183 + outer loop + vertex 0.94842 1.44764 2.64529 + vertex 0.948538 1.45268 2.6454 + vertex 0.943636 1.4477 2.64546 + endloop + endfacet + facet normal 0.0284159 -0.0201308 0.999393 + outer loop + vertex 0.938912 1.44774 2.6456 + vertex 0.94389 1.45278 2.64556 + vertex 0.939297 1.45273 2.64569 + endloop + endfacet + facet normal 0.0247347 -0.018812 0.999517 + outer loop + vertex 0.940276 1.45657 2.64573 + vertex 0.937695 1.4545 2.64576 + vertex 0.939297 1.45273 2.64569 + endloop + endfacet + facet normal 0.0238191 -0.0176734 0.99956 + outer loop + vertex 0.940276 1.45657 2.64573 + vertex 0.937994 1.45754 2.64581 + vertex 0.937695 1.4545 2.64576 + endloop + endfacet + facet normal 0.0203931 -0.0185522 0.99962 + outer loop + vertex 0.937994 1.45754 2.64581 + vertex 0.939048 1.46243 2.64587 + vertex 0.934173 1.45785 2.64589 + endloop + endfacet + facet normal 0.0198954 -0.0180217 0.99964 + outer loop + vertex 0.934173 1.45785 2.64589 + vertex 0.939048 1.46243 2.64587 + vertex 0.933762 1.46241 2.64598 + endloop + endfacet + facet normal 0.0129451 -0.0186499 0.999742 + outer loop + vertex 0.934173 1.45785 2.64589 + vertex 0.933762 1.46241 2.64598 + vertex 0.929577 1.45788 2.64595 + endloop + endfacet + facet normal 0.0198967 -0.0185004 0.999631 + outer loop + vertex 0.939048 1.46243 2.64587 + vertex 0.938595 1.46758 2.64598 + vertex 0.933762 1.46241 2.64598 + endloop + endfacet + facet normal 0.0181323 -0.0168517 0.999694 + outer loop + vertex 0.933762 1.46241 2.64598 + vertex 0.938595 1.46758 2.64598 + vertex 0.933412 1.46737 2.64607 + endloop + endfacet + facet normal 0.0110208 -0.0173554 0.999789 + outer loop + vertex 0.933762 1.46241 2.64598 + vertex 0.933412 1.46737 2.64607 + vertex 0.92892 1.46247 2.64603 + endloop + endfacet + facet normal 0.0180636 -0.0151915 0.999721 + outer loop + vertex 0.938595 1.46758 2.64598 + vertex 0.938445 1.47267 2.64606 + vertex 0.933412 1.46737 2.64607 + endloop + endfacet + facet normal 0.0155944 -0.0128509 0.999796 + outer loop + vertex 0.933412 1.46737 2.64607 + vertex 0.938445 1.47267 2.64606 + vertex 0.933364 1.47244 2.64614 + endloop + endfacet + facet normal 0.00798182 -0.0129249 0.999885 + outer loop + vertex 0.933412 1.46737 2.64607 + vertex 0.933364 1.47244 2.64614 + vertex 0.928658 1.46744 2.64611 + endloop + endfacet + facet normal 0.0154727 -0.0101491 0.999829 + outer loop + vertex 0.938445 1.47267 2.64606 + vertex 0.938505 1.47775 2.64611 + vertex 0.933364 1.47244 2.64614 + endloop + endfacet + facet normal 0.0133567 -0.00809669 0.999878 + outer loop + vertex 0.933364 1.47244 2.64614 + vertex 0.938505 1.47775 2.64611 + vertex 0.933432 1.4775 2.64618 + endloop + endfacet + facet normal 0.00516604 -0.00798689 0.999955 + outer loop + vertex 0.933364 1.47244 2.64614 + vertex 0.933432 1.4775 2.64618 + vertex 0.928657 1.4725 2.64616 + endloop + endfacet + facet normal 0.0132371 -0.00558335 0.999897 + outer loop + vertex 0.938505 1.47775 2.64611 + vertex 0.938548 1.48272 2.64614 + vertex 0.933432 1.4775 2.64618 + endloop + endfacet + facet normal 0.0121421 -0.00450846 0.999916 + outer loop + vertex 0.933432 1.4775 2.64618 + vertex 0.938548 1.48272 2.64614 + vertex 0.93343 1.48252 2.6462 + endloop + endfacet + facet normal 0.0031297 -0.00451262 0.999985 + outer loop + vertex 0.933432 1.4775 2.64618 + vertex 0.93343 1.48252 2.6462 + vertex 0.92865 1.47757 2.64619 + endloop + endfacet + facet normal 0.0120907 -0.00315869 0.999922 + outer loop + vertex 0.938548 1.48272 2.64614 + vertex 0.938537 1.48766 2.64615 + vertex 0.93343 1.48252 2.6462 + endloop + endfacet + facet normal 0.020576 -0.00313951 0.999783 + outer loop + vertex 0.938548 1.48272 2.64614 + vertex 0.943479 1.48754 2.64605 + vertex 0.938537 1.48766 2.64615 + endloop + endfacet + facet normal 0.0206232 -0.00104766 0.999787 + outer loop + vertex 0.943479 1.48754 2.64605 + vertex 0.943581 1.49251 2.64605 + vertex 0.938537 1.48766 2.64615 + endloop + endfacet + facet normal 0.0229953 -0.00351165 0.999729 + outer loop + vertex 0.938537 1.48766 2.64615 + vertex 0.943581 1.49251 2.64605 + vertex 0.938513 1.49265 2.64617 + endloop + endfacet + facet normal 0.0230074 -0.00307025 0.999731 + outer loop + vertex 0.943581 1.49251 2.64605 + vertex 0.943641 1.4977 2.64607 + vertex 0.938513 1.49265 2.64617 + endloop + endfacet + facet normal 0.0248521 -0.00494562 0.999679 + outer loop + vertex 0.938513 1.49265 2.64617 + vertex 0.943641 1.4977 2.64607 + vertex 0.938504 1.49767 2.6462 + endloop + endfacet + facet normal 0.0149444 -0.00496272 0.999876 + outer loop + vertex 0.938513 1.49265 2.64617 + vertex 0.938504 1.49767 2.6462 + vertex 0.933319 1.49248 2.64625 + endloop + endfacet + facet normal 0.0149599 -0.00543269 0.999873 + outer loop + vertex 0.933366 1.48752 2.64622 + vertex 0.938513 1.49265 2.64617 + vertex 0.933319 1.49248 2.64625 + endloop + endfacet + facet normal 0.0041223 -0.0055352 0.999976 + outer loop + vertex 0.933366 1.48752 2.64622 + vertex 0.933319 1.49248 2.64625 + vertex 0.928519 1.4877 2.64624 + endloop + endfacet + facet normal 0.0130938 -0.00356132 0.999908 + outer loop + vertex 0.938537 1.48766 2.64615 + vertex 0.938513 1.49265 2.64617 + vertex 0.933366 1.48752 2.64622 + endloop + endfacet + facet normal 0.0131099 -0.00417266 0.999905 + outer loop + vertex 0.93343 1.48252 2.6462 + vertex 0.938537 1.48766 2.64615 + vertex 0.933366 1.48752 2.64622 + endloop + endfacet + facet normal 0.00253127 -0.00430851 0.999988 + outer loop + vertex 0.93343 1.48252 2.6462 + vertex 0.933366 1.48752 2.64622 + vertex 0.928503 1.48267 2.64621 + endloop + endfacet + facet normal 0.016263 -0.00628018 0.999848 + outer loop + vertex 0.933319 1.49248 2.64625 + vertex 0.938504 1.49767 2.6462 + vertex 0.933273 1.49741 2.64628 + endloop + endfacet + facet normal 0.00577404 -0.00637948 0.999963 + outer loop + vertex 0.933319 1.49248 2.64625 + vertex 0.933273 1.49741 2.64628 + vertex 0.928514 1.49247 2.64628 + endloop + endfacet + facet normal 0.0161979 -0.00497968 0.999856 + outer loop + vertex 0.938504 1.49767 2.6462 + vertex 0.938511 1.50267 2.64622 + vertex 0.933273 1.49741 2.64628 + endloop + endfacet + facet normal 0.016263 -0.00504447 0.999855 + outer loop + vertex 0.933273 1.49741 2.64628 + vertex 0.938511 1.50267 2.64622 + vertex 0.933259 1.50237 2.6463 + endloop + endfacet + facet normal 0.00470371 -0.00507686 0.999976 + outer loop + vertex 0.933273 1.49741 2.64628 + vertex 0.933259 1.50237 2.6463 + vertex 0.928339 1.49725 2.6463 + endloop + endfacet + facet normal 0.0161389 -0.00284561 0.999866 + outer loop + vertex 0.938511 1.50267 2.64622 + vertex 0.938551 1.50767 2.64623 + vertex 0.933259 1.50237 2.6463 + endloop + endfacet + facet normal 0.0153768 -0.00208417 0.99988 + outer loop + vertex 0.933259 1.50237 2.6463 + vertex 0.938551 1.50767 2.64623 + vertex 0.933302 1.50738 2.64631 + endloop + endfacet + facet normal 0.00384804 -0.00198491 0.999991 + outer loop + vertex 0.933259 1.50237 2.6463 + vertex 0.933302 1.50738 2.64631 + vertex 0.928287 1.50222 2.64632 + endloop + endfacet + facet normal 0.0152293 0.000600267 0.999884 + outer loop + vertex 0.938551 1.50767 2.64623 + vertex 0.938634 1.5127 2.64623 + vertex 0.933302 1.50738 2.64631 + endloop + endfacet + facet normal 0.0144124 0.00142008 0.999895 + outer loop + vertex 0.933302 1.50738 2.64631 + vertex 0.938634 1.5127 2.64623 + vertex 0.933385 1.51242 2.64631 + endloop + endfacet + facet normal 0.0031654 0.00160564 0.999994 + outer loop + vertex 0.933302 1.50738 2.64631 + vertex 0.933385 1.51242 2.64631 + vertex 0.928326 1.50724 2.64633 + endloop + endfacet + facet normal 0.0143012 0.00349918 0.999892 + outer loop + vertex 0.938634 1.5127 2.64623 + vertex 0.938732 1.51775 2.64621 + vertex 0.933385 1.51242 2.64631 + endloop + endfacet + facet normal 0.0142144 0.0035862 0.999893 + outer loop + vertex 0.933385 1.51242 2.64631 + vertex 0.938732 1.51775 2.64621 + vertex 0.93347 1.51747 2.64629 + endloop + endfacet + facet normal 0.00317394 0.00377095 0.999988 + outer loop + vertex 0.933385 1.51242 2.64631 + vertex 0.93347 1.51747 2.64629 + vertex 0.928383 1.51226 2.64632 + endloop + endfacet + facet normal 0.0141596 0.00460618 0.999889 + outer loop + vertex 0.938732 1.51775 2.64621 + vertex 0.938775 1.52279 2.64619 + vertex 0.93347 1.51747 2.64629 + endloop + endfacet + facet normal 0.0140086 0.00475667 0.999891 + outer loop + vertex 0.93347 1.51747 2.64629 + vertex 0.938775 1.52279 2.64619 + vertex 0.933536 1.52254 2.64626 + endloop + endfacet + facet normal 0.00356108 0.00489276 0.999982 + outer loop + vertex 0.93347 1.51747 2.64629 + vertex 0.933536 1.52254 2.64626 + vertex 0.928424 1.51729 2.64631 + endloop + endfacet + facet normal 0.0139871 0.0051979 0.999889 + outer loop + vertex 0.938775 1.52279 2.64619 + vertex 0.938713 1.52777 2.64616 + vertex 0.933536 1.52254 2.64626 + endloop + endfacet + facet normal 0.0137084 0.00547353 0.999891 + outer loop + vertex 0.933536 1.52254 2.64626 + vertex 0.938713 1.52777 2.64616 + vertex 0.933566 1.5276 2.64623 + endloop + endfacet + facet normal 0.00323943 0.005537 0.999979 + outer loop + vertex 0.933536 1.52254 2.64626 + vertex 0.933566 1.5276 2.64623 + vertex 0.92848 1.52235 2.64628 + endloop + endfacet + facet normal 0.0136745 0.00647166 0.999886 + outer loop + vertex 0.938713 1.52777 2.64616 + vertex 0.938514 1.53262 2.64613 + vertex 0.933566 1.5276 2.64623 + endloop + endfacet + facet normal 0.0123769 0.00775137 0.999893 + outer loop + vertex 0.933566 1.5276 2.64623 + vertex 0.938514 1.53262 2.64613 + vertex 0.933566 1.53264 2.64619 + endloop + endfacet + facet normal 0.00204299 0.00775219 0.999968 + outer loop + vertex 0.933566 1.5276 2.64623 + vertex 0.933566 1.53264 2.64619 + vertex 0.928538 1.52742 2.64625 + endloop + endfacet + facet normal 0.0123873 0.00972896 0.999876 + outer loop + vertex 0.938514 1.53262 2.64613 + vertex 0.938381 1.53749 2.64609 + vertex 0.933566 1.53264 2.64619 + endloop + endfacet + facet normal 0.0112629 0.0108462 0.999878 + outer loop + vertex 0.933566 1.53264 2.64619 + vertex 0.938381 1.53749 2.64609 + vertex 0.933489 1.53767 2.64614 + endloop + endfacet + facet normal 0.000181411 0.0106766 0.999943 + outer loop + vertex 0.933566 1.53264 2.64619 + vertex 0.933489 1.53767 2.64614 + vertex 0.928596 1.53248 2.6462 + endloop + endfacet + facet normal 0.0113156 0.0122881 0.99986 + outer loop + vertex 0.938381 1.53749 2.64609 + vertex 0.937946 1.54247 2.64603 + vertex 0.933489 1.53767 2.64614 + endloop + endfacet + facet normal 0.0107711 0.0127937 0.99986 + outer loop + vertex 0.933489 1.53767 2.64614 + vertex 0.937946 1.54247 2.64603 + vertex 0.933296 1.54254 2.64608 + endloop + endfacet + facet normal -0.000856707 0.012335 0.999924 + outer loop + vertex 0.933489 1.53767 2.64614 + vertex 0.933296 1.54254 2.64608 + vertex 0.928586 1.53754 2.64614 + endloop + endfacet + facet normal 0.010775 0.0130362 0.999857 + outer loop + vertex 0.937946 1.54247 2.64603 + vertex 0.936937 1.54652 2.64599 + vertex 0.933296 1.54254 2.64608 + endloop + endfacet + facet normal 0.00896587 0.0146929 0.999852 + outer loop + vertex 0.933296 1.54254 2.64608 + vertex 0.936937 1.54652 2.64599 + vertex 0.93329 1.5474 2.64601 + endloop + endfacet + facet normal -0.000628504 0.0146815 0.999892 + outer loop + vertex 0.933296 1.54254 2.64608 + vertex 0.93329 1.5474 2.64601 + vertex 0.928745 1.54269 2.64608 + endloop + endfacet + facet normal 0.0099325 0.0187057 0.999776 + outer loop + vertex 0.936937 1.54652 2.64599 + vertex 0.937926 1.55136 2.64589 + vertex 0.93329 1.5474 2.64601 + endloop + endfacet + facet normal 0.0120921 0.0161788 0.999796 + outer loop + vertex 0.93329 1.5474 2.64601 + vertex 0.937926 1.55136 2.64589 + vertex 0.933041 1.55245 2.64593 + endloop + endfacet + facet normal 0.00207476 0.0156853 0.999875 + outer loop + vertex 0.93329 1.5474 2.64601 + vertex 0.933041 1.55245 2.64593 + vertex 0.928925 1.54784 2.64601 + endloop + endfacet + facet normal 0.0121618 0.0164919 0.99979 + outer loop + vertex 0.937926 1.55136 2.64589 + vertex 0.936853 1.55646 2.64582 + vertex 0.933041 1.55245 2.64593 + endloop + endfacet + facet normal 0.0116936 0.0169368 0.999788 + outer loop + vertex 0.933041 1.55245 2.64593 + vertex 0.936853 1.55646 2.64582 + vertex 0.931937 1.55799 2.64585 + endloop + endfacet + facet normal 0.00396326 0.0153996 0.999874 + outer loop + vertex 0.933041 1.55245 2.64593 + vertex 0.931937 1.55799 2.64585 + vertex 0.928565 1.55276 2.64594 + endloop + endfacet + facet normal 0.020648 0.0165146 0.99965 + outer loop + vertex 0.937926 1.55136 2.64589 + vertex 0.936937 1.54652 2.64599 + vertex 0.941297 1.54735 2.64589 + endloop + endfacet + facet normal 0.0223405 0.0179364 0.99959 + outer loop + vertex 0.942056 1.55188 2.64579 + vertex 0.937926 1.55136 2.64589 + vertex 0.941297 1.54735 2.64589 + endloop + endfacet + facet normal 0.0310946 0.0164654 0.999381 + outer loop + vertex 0.942056 1.55188 2.64579 + vertex 0.941297 1.54735 2.64589 + vertex 0.944558 1.54988 2.64574 + endloop + endfacet + facet normal 0.0343234 0.0205281 0.9992 + outer loop + vertex 0.944558 1.54988 2.64574 + vertex 0.945431 1.55408 2.64563 + vertex 0.942056 1.55188 2.64579 + endloop + endfacet + facet normal 0.0339245 0.0211396 0.999201 + outer loop + vertex 0.942056 1.55188 2.64579 + vertex 0.945431 1.55408 2.64563 + vertex 0.941126 1.55559 2.64574 + endloop + endfacet + facet normal 0.0310958 0.016464 0.999381 + outer loop + vertex 0.945855 1.54576 2.64577 + vertex 0.944558 1.54988 2.64574 + vertex 0.941297 1.54735 2.64589 + endloop + endfacet + facet normal 0.0311986 0.0167595 0.999373 + outer loop + vertex 0.941297 1.54735 2.64589 + vertex 0.943076 1.5414 2.64593 + vertex 0.945855 1.54576 2.64577 + endloop + endfacet + facet normal 0.0313413 0.0166682 0.99937 + outer loop + vertex 0.945855 1.54576 2.64577 + vertex 0.943076 1.5414 2.64593 + vertex 0.947356 1.54161 2.64579 + endloop + endfacet + facet normal 0.0375307 0.0189044 0.999117 + outer loop + vertex 0.947356 1.54161 2.64579 + vertex 0.950486 1.54386 2.64563 + vertex 0.945855 1.54576 2.64577 + endloop + endfacet + facet normal 0.0374803 0.0187812 0.999121 + outer loop + vertex 0.950486 1.54386 2.64563 + vertex 0.948711 1.54971 2.64559 + vertex 0.945855 1.54576 2.64577 + endloop + endfacet + facet normal 0.038056 0.0181742 0.99911 + outer loop + vertex 0.950121 1.53959 2.64572 + vertex 0.950486 1.54386 2.64563 + vertex 0.947356 1.54161 2.64579 + endloop + endfacet + facet normal 0.0353331 0.0144318 0.999271 + outer loop + vertex 0.947356 1.54161 2.64579 + vertex 0.947115 1.53671 2.64587 + vertex 0.950121 1.53959 2.64572 + endloop + endfacet + facet normal 0.0357051 0.0140428 0.999264 + outer loop + vertex 0.951346 1.53651 2.64572 + vertex 0.950121 1.53959 2.64572 + vertex 0.947115 1.53671 2.64587 + endloop + endfacet + facet normal 0.0355789 0.0114074 0.999302 + outer loop + vertex 0.951346 1.53651 2.64572 + vertex 0.947115 1.53671 2.64587 + vertex 0.950784 1.53225 2.64579 + endloop + endfacet + facet normal 0.0378357 0.0111084 0.999222 + outer loop + vertex 0.951346 1.53651 2.64572 + vertex 0.950784 1.53225 2.64579 + vertex 0.953956 1.53457 2.64565 + endloop + endfacet + facet normal 0.0401214 0.0141876 0.999094 + outer loop + vertex 0.953956 1.53457 2.64565 + vertex 0.954448 1.53917 2.64556 + vertex 0.951346 1.53651 2.64572 + endloop + endfacet + facet normal 0.0347981 0.0107655 0.999336 + outer loop + vertex 0.947115 1.53671 2.64587 + vertex 0.946858 1.53161 2.64594 + vertex 0.950784 1.53225 2.64579 + endloop + endfacet + facet normal 0.0353435 0.00738432 0.999348 + outer loop + vertex 0.947855 1.52761 2.64593 + vertex 0.950784 1.53225 2.64579 + vertex 0.946858 1.53161 2.64594 + endloop + endfacet + facet normal 0.0293921 0.00589992 0.999551 + outer loop + vertex 0.947855 1.52761 2.64593 + vertex 0.946858 1.53161 2.64594 + vertex 0.943532 1.52775 2.64606 + endloop + endfacet + facet normal 0.0293677 0.00509787 0.999556 + outer loop + vertex 0.943768 1.52292 2.64607 + vertex 0.947855 1.52761 2.64593 + vertex 0.943532 1.52775 2.64606 + endloop + endfacet + facet normal 0.0225965 0.00476627 0.999733 + outer loop + vertex 0.943768 1.52292 2.64607 + vertex 0.943532 1.52775 2.64606 + vertex 0.938775 1.52279 2.64619 + endloop + endfacet + facet normal 0.0294834 0.00499697 0.999553 + outer loop + vertex 0.948246 1.52274 2.64594 + vertex 0.947855 1.52761 2.64593 + vertex 0.943768 1.52292 2.64607 + endloop + endfacet + facet normal 0.0294558 0.00433418 0.999557 + outer loop + vertex 0.943778 1.51791 2.6461 + vertex 0.948246 1.52274 2.64594 + vertex 0.943768 1.52292 2.64607 + endloop + endfacet + facet normal 0.0228186 0.00432222 0.99973 + outer loop + vertex 0.943778 1.51791 2.6461 + vertex 0.943768 1.52292 2.64607 + vertex 0.938732 1.51775 2.64621 + endloop + endfacet + facet normal 0.0300616 0.00377295 0.999541 + outer loop + vertex 0.948288 1.51772 2.64596 + vertex 0.948246 1.52274 2.64594 + vertex 0.943778 1.51791 2.6461 + endloop + endfacet + facet normal 0.0300067 0.00245988 0.999547 + outer loop + vertex 0.943698 1.51287 2.64611 + vertex 0.948288 1.51772 2.64596 + vertex 0.943778 1.51791 2.6461 + endloop + endfacet + facet normal 0.0236331 0.00256082 0.999717 + outer loop + vertex 0.943698 1.51287 2.64611 + vertex 0.943778 1.51791 2.6461 + vertex 0.938634 1.5127 2.64623 + endloop + endfacet + facet normal 0.030799 0.00170919 0.999524 + outer loop + vertex 0.948241 1.51272 2.64597 + vertex 0.948288 1.51772 2.64596 + vertex 0.943698 1.51287 2.64611 + endloop + endfacet + facet normal 0.0307283 -0.000418109 0.999528 + outer loop + vertex 0.943646 1.50787 2.64611 + vertex 0.948241 1.51272 2.64597 + vertex 0.943698 1.51287 2.64611 + endloop + endfacet + facet normal 0.0245255 -0.000352954 0.999699 + outer loop + vertex 0.943646 1.50787 2.64611 + vertex 0.943698 1.51287 2.64611 + vertex 0.938551 1.50767 2.64623 + endloop + endfacet + facet normal 0.0322125 -0.00182504 0.999479 + outer loop + vertex 0.948257 1.50778 2.64596 + vertex 0.948241 1.51272 2.64597 + vertex 0.943646 1.50787 2.64611 + endloop + endfacet + facet normal 0.0321781 -0.00365657 0.999475 + outer loop + vertex 0.943683 1.50285 2.64609 + vertex 0.948257 1.50778 2.64596 + vertex 0.943646 1.50787 2.64611 + endloop + endfacet + facet normal 0.025428 -0.00370729 0.99967 + outer loop + vertex 0.943683 1.50285 2.64609 + vertex 0.943646 1.50787 2.64611 + vertex 0.938511 1.50267 2.64622 + endloop + endfacet + facet normal 0.0332673 -0.00466798 0.999436 + outer loop + vertex 0.948735 1.50267 2.64592 + vertex 0.948257 1.50778 2.64596 + vertex 0.943683 1.50285 2.64609 + endloop + endfacet + facet normal 0.0332758 -0.00443489 0.999436 + outer loop + vertex 0.943641 1.4977 2.64607 + vertex 0.948735 1.50267 2.64592 + vertex 0.943683 1.50285 2.64609 + endloop + endfacet + facet normal 0.0323058 -0.00343872 0.999472 + outer loop + vertex 0.948138 1.49692 2.64592 + vertex 0.948735 1.50267 2.64592 + vertex 0.943641 1.4977 2.64607 + endloop + endfacet + facet normal 0.0375599 -0.00398448 0.999286 + outer loop + vertex 0.948735 1.50267 2.64592 + vertex 0.948138 1.49692 2.64592 + vertex 0.95197 1.50045 2.64579 + endloop + endfacet + facet normal 0.0372196 -0.00448186 0.999297 + outer loop + vertex 0.952574 1.50435 2.64579 + vertex 0.948735 1.50267 2.64592 + vertex 0.95197 1.50045 2.64579 + endloop + endfacet + facet normal 0.0355204 -0.00421862 0.99936 + outer loop + vertex 0.955214 1.50365 2.64569 + vertex 0.952574 1.50435 2.64579 + vertex 0.95197 1.50045 2.64579 + endloop + endfacet + facet normal 0.0350504 -0.00374133 0.999379 + outer loop + vertex 0.955283 1.49901 2.64567 + vertex 0.955214 1.50365 2.64569 + vertex 0.95197 1.50045 2.64579 + endloop + endfacet + facet normal 0.0353588 -0.00303061 0.99937 + outer loop + vertex 0.951922 1.49565 2.64578 + vertex 0.955283 1.49901 2.64567 + vertex 0.95197 1.50045 2.64579 + endloop + endfacet + facet normal 0.0346469 -0.00231798 0.999397 + outer loop + vertex 0.955593 1.49377 2.64565 + vertex 0.955283 1.49901 2.64567 + vertex 0.951922 1.49565 2.64578 + endloop + endfacet + facet normal 0.0350214 -0.00158451 0.999385 + outer loop + vertex 0.952259 1.49182 2.64576 + vertex 0.955593 1.49377 2.64565 + vertex 0.951922 1.49565 2.64578 + endloop + endfacet + facet normal 0.0373797 -0.00137691 0.9993 + outer loop + vertex 0.951922 1.49565 2.64578 + vertex 0.948385 1.4915 2.6459 + vertex 0.952259 1.49182 2.64576 + endloop + endfacet + facet normal 0.0372283 0.000481692 0.999307 + outer loop + vertex 0.952259 1.49182 2.64576 + vertex 0.948385 1.4915 2.6459 + vertex 0.9511 1.4879 2.6458 + endloop + endfacet + facet normal 0.0374345 0.000420574 0.999299 + outer loop + vertex 0.952259 1.49182 2.64576 + vertex 0.9511 1.4879 2.6458 + vertex 0.954159 1.48986 2.64569 + endloop + endfacet + facet normal 0.0380993 -0.000620243 0.999274 + outer loop + vertex 0.954081 1.487 2.64569 + vertex 0.954159 1.48986 2.64569 + vertex 0.9511 1.4879 2.6458 + endloop + endfacet + facet normal 0.0377562 -0.00176118 0.999285 + outer loop + vertex 0.954081 1.487 2.64569 + vertex 0.9511 1.4879 2.6458 + vertex 0.95218 1.48453 2.64576 + endloop + endfacet + facet normal 0.0388108 -0.00257381 0.999243 + outer loop + vertex 0.954081 1.487 2.64569 + vertex 0.95218 1.48453 2.64576 + vertex 0.954934 1.48385 2.64565 + endloop + endfacet + facet normal 0.0358628 -0.00236904 0.999354 + outer loop + vertex 0.95218 1.48453 2.64576 + vertex 0.9511 1.4879 2.6458 + vertex 0.948368 1.48274 2.64589 + endloop + endfacet + facet normal 0.0371137 -0.00503431 0.999298 + outer loop + vertex 0.95218 1.48453 2.64576 + vertex 0.948368 1.48274 2.64589 + vertex 0.951733 1.48066 2.64576 + endloop + endfacet + facet normal 0.0368551 -0.00289512 0.999316 + outer loop + vertex 0.9511 1.4879 2.6458 + vertex 0.947195 1.48674 2.64595 + vertex 0.948368 1.48274 2.64589 + endloop + endfacet + facet normal 0.0298482 -0.00494947 0.999542 + outer loop + vertex 0.948368 1.48274 2.64589 + vertex 0.947195 1.48674 2.64595 + vertex 0.943472 1.48278 2.64604 + endloop + endfacet + facet normal 0.0298332 -0.00681801 0.999532 + outer loop + vertex 0.943503 1.47785 2.646 + vertex 0.948368 1.48274 2.64589 + vertex 0.943472 1.48278 2.64604 + endloop + endfacet + facet normal 0.0216449 -0.00687084 0.999742 + outer loop + vertex 0.943503 1.47785 2.646 + vertex 0.943472 1.48278 2.64604 + vertex 0.938505 1.47775 2.64611 + endloop + endfacet + facet normal 0.0298152 -0.00680008 0.999532 + outer loop + vertex 0.94783 1.47723 2.64587 + vertex 0.948368 1.48274 2.64589 + vertex 0.943503 1.47785 2.646 + endloop + endfacet + facet normal 0.0291784 -0.0112745 0.999511 + outer loop + vertex 0.943404 1.47275 2.64595 + vertex 0.94783 1.47723 2.64587 + vertex 0.943503 1.47785 2.646 + endloop + endfacet + facet normal 0.0226595 -0.0111497 0.999681 + outer loop + vertex 0.943404 1.47275 2.64595 + vertex 0.943503 1.47785 2.646 + vertex 0.938445 1.47267 2.64606 + endloop + endfacet + facet normal 0.0277085 -0.00293911 0.999612 + outer loop + vertex 0.943472 1.48278 2.64604 + vertex 0.947195 1.48674 2.64595 + vertex 0.943479 1.48754 2.64605 + endloop + endfacet + facet normal 0.0203702 -0.00292926 0.999788 + outer loop + vertex 0.943472 1.48278 2.64604 + vertex 0.943479 1.48754 2.64605 + vertex 0.938548 1.48272 2.64614 + endloop + endfacet + facet normal 0.0286636 0.00149928 0.999588 + outer loop + vertex 0.947195 1.48674 2.64595 + vertex 0.948385 1.4915 2.6459 + vertex 0.943479 1.48754 2.64605 + endloop + endfacet + facet normal 0.0347106 -0.000527897 0.999397 + outer loop + vertex 0.954159 1.48986 2.64569 + vertex 0.954081 1.487 2.64569 + vertex 0.957829 1.48883 2.64556 + endloop + endfacet + facet normal 0.0361074 -0.000364961 0.999348 + outer loop + vertex 0.948385 1.4915 2.6459 + vertex 0.947195 1.48674 2.64595 + vertex 0.9511 1.4879 2.6458 + endloop + endfacet + facet normal 0.0372805 -0.00129218 0.999304 + outer loop + vertex 0.948138 1.49692 2.64592 + vertex 0.948385 1.4915 2.6459 + vertex 0.951922 1.49565 2.64578 + endloop + endfacet + facet normal 0.0308153 -0.00158726 0.999524 + outer loop + vertex 0.948385 1.4915 2.6459 + vertex 0.948138 1.49692 2.64592 + vertex 0.943581 1.49251 2.64605 + endloop + endfacet + facet normal 0.0351474 -0.00179932 0.999381 + outer loop + vertex 0.954159 1.48986 2.64569 + vertex 0.955593 1.49377 2.64565 + vertex 0.952259 1.49182 2.64576 + endloop + endfacet + facet normal 0.0375629 -0.00526462 0.99928 + outer loop + vertex 0.952574 1.50435 2.64579 + vertex 0.952068 1.50758 2.64582 + vertex 0.948735 1.50267 2.64592 + endloop + endfacet + facet normal 0.0366938 -0.00304372 0.999322 + outer loop + vertex 0.95197 1.50045 2.64579 + vertex 0.948138 1.49692 2.64592 + vertex 0.951922 1.49565 2.64578 + endloop + endfacet + facet normal 0.0362706 -0.00438637 0.999332 + outer loop + vertex 0.952068 1.50758 2.64582 + vertex 0.948257 1.50778 2.64596 + vertex 0.948735 1.50267 2.64592 + endloop + endfacet + facet normal 0.0354035 -0.00181444 0.999371 + outer loop + vertex 0.948257 1.50778 2.64596 + vertex 0.952098 1.51208 2.64583 + vertex 0.948241 1.51272 2.64597 + endloop + endfacet + facet normal 0.0358459 0.000850505 0.999357 + outer loop + vertex 0.952098 1.51208 2.64583 + vertex 0.952174 1.51699 2.64583 + vertex 0.948241 1.51272 2.64597 + endloop + endfacet + facet normal 0.0349591 0.00166938 0.999387 + outer loop + vertex 0.948241 1.51272 2.64597 + vertex 0.952174 1.51699 2.64583 + vertex 0.948288 1.51772 2.64596 + endloop + endfacet + facet normal 0.0349428 0.00381415 0.999382 + outer loop + vertex 0.948288 1.51772 2.64596 + vertex 0.952153 1.52199 2.64581 + vertex 0.948246 1.52274 2.64594 + endloop + endfacet + facet normal 0.0352117 0.00521672 0.999366 + outer loop + vertex 0.952153 1.52199 2.64581 + vertex 0.951825 1.52699 2.64579 + vertex 0.948246 1.52274 2.64594 + endloop + endfacet + facet normal 0.0349538 0.0054341 0.999374 + outer loop + vertex 0.948246 1.52274 2.64594 + vertex 0.951825 1.52699 2.64579 + vertex 0.947855 1.52761 2.64593 + endloop + endfacet + facet normal 0.0283955 0.0067576 0.999574 + outer loop + vertex 0.943532 1.52775 2.64606 + vertex 0.946858 1.53161 2.64594 + vertex 0.943196 1.53243 2.64603 + endloop + endfacet + facet normal 0.022049 0.00630454 0.999737 + outer loop + vertex 0.943532 1.52775 2.64606 + vertex 0.943196 1.53243 2.64603 + vertex 0.938713 1.52777 2.64616 + endloop + endfacet + facet normal 0.0352682 0.00743192 0.99935 + outer loop + vertex 0.951825 1.52699 2.64579 + vertex 0.950784 1.53225 2.64579 + vertex 0.947855 1.52761 2.64593 + endloop + endfacet + facet normal 0.0293538 0.0110424 0.999508 + outer loop + vertex 0.946858 1.53161 2.64594 + vertex 0.947115 1.53671 2.64587 + vertex 0.943196 1.53243 2.64603 + endloop + endfacet + facet normal 0.0301231 0.0103373 0.999493 + outer loop + vertex 0.943196 1.53243 2.64603 + vertex 0.947115 1.53671 2.64587 + vertex 0.942351 1.53644 2.64602 + endloop + endfacet + facet normal 0.0216057 0.00854182 0.99973 + outer loop + vertex 0.943196 1.53243 2.64603 + vertex 0.942351 1.53644 2.64602 + vertex 0.938514 1.53262 2.64613 + endloop + endfacet + facet normal 0.0299508 0.0133439 0.999462 + outer loop + vertex 0.943076 1.5414 2.64593 + vertex 0.942351 1.53644 2.64602 + vertex 0.947115 1.53671 2.64587 + endloop + endfacet + facet normal 0.0214361 0.0145917 0.999664 + outer loop + vertex 0.942351 1.53644 2.64602 + vertex 0.943076 1.5414 2.64593 + vertex 0.938381 1.53749 2.64609 + endloop + endfacet + facet normal 0.0390918 0.0153894 0.999117 + outer loop + vertex 0.950121 1.53959 2.64572 + vertex 0.951346 1.53651 2.64572 + vertex 0.954448 1.53917 2.64556 + endloop + endfacet + facet normal 0.0393498 0.0180623 0.999062 + outer loop + vertex 0.950121 1.53959 2.64572 + vertex 0.954448 1.53917 2.64556 + vertex 0.950486 1.54386 2.64563 + endloop + endfacet + facet normal 0.0375199 0.0165145 0.999159 + outer loop + vertex 0.950486 1.54386 2.64563 + vertex 0.954448 1.53917 2.64556 + vertex 0.954808 1.54396 2.64547 + endloop + endfacet + facet normal 0.0374828 0.0179965 0.999135 + outer loop + vertex 0.954808 1.54396 2.64547 + vertex 0.953624 1.54805 2.64544 + vertex 0.950486 1.54386 2.64563 + endloop + endfacet + facet normal 0.0367372 0.0185559 0.999153 + outer loop + vertex 0.950486 1.54386 2.64563 + vertex 0.953624 1.54805 2.64544 + vertex 0.948711 1.54971 2.64559 + endloop + endfacet + facet normal 0.0314382 0.0146255 0.999399 + outer loop + vertex 0.947356 1.54161 2.64579 + vertex 0.943076 1.5414 2.64593 + vertex 0.947115 1.53671 2.64587 + endloop + endfacet + facet normal 0.0227402 0.0142289 0.99964 + outer loop + vertex 0.943076 1.5414 2.64593 + vertex 0.941297 1.54735 2.64589 + vertex 0.937946 1.54247 2.64603 + endloop + endfacet + facet normal 0.0377823 0.0185627 0.999114 + outer loop + vertex 0.944558 1.54988 2.64574 + vertex 0.945855 1.54576 2.64577 + vertex 0.948711 1.54971 2.64559 + endloop + endfacet + facet normal 0.0223032 0.0182334 0.999585 + outer loop + vertex 0.941126 1.55559 2.64574 + vertex 0.937926 1.55136 2.64589 + vertex 0.942056 1.55188 2.64579 + endloop + endfacet + facet normal 0.0208334 0.0155389 0.999662 + outer loop + vertex 0.937946 1.54247 2.64603 + vertex 0.941297 1.54735 2.64589 + vertex 0.936937 1.54652 2.64599 + endloop + endfacet + facet normal 0.0225412 0.0132668 0.999658 + outer loop + vertex 0.938381 1.53749 2.64609 + vertex 0.943076 1.5414 2.64593 + vertex 0.937946 1.54247 2.64603 + endloop + endfacet + facet normal 0.0202121 0.00993976 0.999746 + outer loop + vertex 0.938514 1.53262 2.64613 + vertex 0.942351 1.53644 2.64602 + vertex 0.938381 1.53749 2.64609 + endloop + endfacet + facet normal 0.0215387 0.00679547 0.999745 + outer loop + vertex 0.938713 1.52777 2.64616 + vertex 0.943196 1.53243 2.64603 + vertex 0.938514 1.53262 2.64613 + endloop + endfacet + facet normal 0.0220436 0.00529722 0.999743 + outer loop + vertex 0.938775 1.52279 2.64619 + vertex 0.943532 1.52775 2.64606 + vertex 0.938713 1.52777 2.64616 + endloop + endfacet + facet normal 0.0226028 0.00453238 0.999734 + outer loop + vertex 0.938732 1.51775 2.64621 + vertex 0.943768 1.52292 2.64607 + vertex 0.938775 1.52279 2.64619 + endloop + endfacet + facet normal 0.0228502 0.00333378 0.999733 + outer loop + vertex 0.938634 1.5127 2.64623 + vertex 0.943778 1.51791 2.6461 + vertex 0.938732 1.51775 2.64621 + endloop + endfacet + facet normal 0.0237057 0.000458973 0.999719 + outer loop + vertex 0.938551 1.50767 2.64623 + vertex 0.943698 1.51287 2.64611 + vertex 0.938634 1.5127 2.64623 + endloop + endfacet + facet normal 0.0246241 -0.0029125 0.999693 + outer loop + vertex 0.938511 1.50267 2.64622 + vertex 0.943646 1.50787 2.64611 + vertex 0.938551 1.50767 2.64623 + endloop + endfacet + facet normal 0.0254725 -0.00499078 0.999663 + outer loop + vertex 0.938504 1.49767 2.6462 + vertex 0.943683 1.50285 2.64609 + vertex 0.938511 1.50267 2.64622 + endloop + endfacet + facet normal 0.024849 -0.00436707 0.999682 + outer loop + vertex 0.943641 1.4977 2.64607 + vertex 0.943683 1.50285 2.64609 + vertex 0.938504 1.49767 2.6462 + endloop + endfacet + facet normal 0.0323511 -0.00317788 0.999472 + outer loop + vertex 0.943581 1.49251 2.64605 + vertex 0.948138 1.49692 2.64592 + vertex 0.943641 1.4977 2.64607 + endloop + endfacet + facet normal 0.0308847 -0.00125847 0.999522 + outer loop + vertex 0.943479 1.48754 2.64605 + vertex 0.948385 1.4915 2.6459 + vertex 0.943581 1.49251 2.64605 + endloop + endfacet + facet normal 0.020404 -0.00564551 0.999776 + outer loop + vertex 0.938505 1.47775 2.64611 + vertex 0.943472 1.48278 2.64604 + vertex 0.938548 1.48272 2.64614 + endloop + endfacet + facet normal 0.0217112 -0.0102217 0.999712 + outer loop + vertex 0.938445 1.47267 2.64606 + vertex 0.943503 1.47785 2.646 + vertex 0.938505 1.47775 2.64611 + endloop + endfacet + facet normal 0.0227167 -0.0150526 0.999629 + outer loop + vertex 0.938595 1.46758 2.64598 + vertex 0.943404 1.47275 2.64595 + vertex 0.938445 1.47267 2.64606 + endloop + endfacet + facet normal 0.0234519 -0.0157369 0.999601 + outer loop + vertex 0.943813 1.4678 2.64586 + vertex 0.943404 1.47275 2.64595 + vertex 0.938595 1.46758 2.64598 + endloop + endfacet + facet normal 0.0289606 -0.0152784 0.999464 + outer loop + vertex 0.943813 1.4678 2.64586 + vertex 0.947593 1.47247 2.64582 + vertex 0.943404 1.47275 2.64595 + endloop + endfacet + facet normal 0.0275264 -0.0141169 0.999521 + outer loop + vertex 0.947715 1.4691 2.64577 + vertex 0.947593 1.47247 2.64582 + vertex 0.943813 1.4678 2.64586 + endloop + endfacet + facet normal 0.0235536 -0.0181776 0.999557 + outer loop + vertex 0.943813 1.4678 2.64586 + vertex 0.938595 1.46758 2.64598 + vertex 0.939048 1.46243 2.64587 + endloop + endfacet + facet normal 0.0285363 -0.0171659 0.999445 + outer loop + vertex 0.947715 1.4691 2.64577 + vertex 0.943813 1.4678 2.64586 + vertex 0.946429 1.46575 2.64575 + endloop + endfacet + facet normal 0.0274676 -0.0212491 0.999397 + outer loop + vertex 0.944944 1.46228 2.64572 + vertex 0.943294 1.46378 2.6458 + vertex 0.941705 1.46014 2.64577 + endloop + endfacet + facet normal 0.0347143 -0.0227653 0.999138 + outer loop + vertex 0.944029 1.45799 2.64566 + vertex 0.948676 1.46329 2.64562 + vertex 0.944944 1.46228 2.64572 + endloop + endfacet + facet normal 0.0399161 -0.0216481 0.998968 + outer loop + vertex 0.949456 1.46764 2.64568 + vertex 0.948676 1.46329 2.64562 + vertex 0.953374 1.4685 2.64554 + endloop + endfacet + facet normal 0.0379 -0.0144689 0.999177 + outer loop + vertex 0.953374 1.4685 2.64554 + vertex 0.95855 1.47292 2.64541 + vertex 0.954595 1.47424 2.64558 + endloop + endfacet + facet normal 0.0360269 -0.0138057 0.999255 + outer loop + vertex 0.947593 1.47247 2.64582 + vertex 0.947715 1.4691 2.64577 + vertex 0.950734 1.47133 2.64569 + endloop + endfacet + facet normal 0.0292247 -0.0113202 0.999509 + outer loop + vertex 0.947593 1.47247 2.64582 + vertex 0.94783 1.47723 2.64587 + vertex 0.943404 1.47275 2.64595 + endloop + endfacet + facet normal 0.0356744 -0.00737067 0.999336 + outer loop + vertex 0.948368 1.48274 2.64589 + vertex 0.94783 1.47723 2.64587 + vertex 0.951733 1.48066 2.64576 + endloop + endfacet + facet normal 0.0399021 -0.0106022 0.999147 + outer loop + vertex 0.954595 1.47424 2.64558 + vertex 0.955003 1.47923 2.64562 + vertex 0.951325 1.4759 2.64573 + endloop + endfacet + facet normal 0.0381744 -0.00515703 0.999258 + outer loop + vertex 0.954934 1.48385 2.64565 + vertex 0.95218 1.48453 2.64576 + vertex 0.951733 1.48066 2.64576 + endloop + endfacet + facet normal 0.0386092 -0.00808943 0.999222 + outer loop + vertex 0.958834 1.47808 2.64546 + vertex 0.958754 1.48318 2.6455 + vertex 0.955003 1.47923 2.64562 + endloop + endfacet + facet normal 0.0360689 -0.00331772 0.999344 + outer loop + vertex 0.954081 1.487 2.64569 + vertex 0.954934 1.48385 2.64565 + vertex 0.957829 1.48883 2.64556 + endloop + endfacet + facet normal 0.0445902 -0.00681709 0.998982 + outer loop + vertex 0.9634 1.48254 2.64529 + vertex 0.96321 1.48766 2.64534 + vertex 0.958754 1.48318 2.6455 + endloop + endfacet + facet normal 0.034429 -0.00153599 0.999406 + outer loop + vertex 0.954159 1.48986 2.64569 + vertex 0.957829 1.48883 2.64556 + vertex 0.955593 1.49377 2.64565 + endloop + endfacet + facet normal 0.0325375 -0.00244303 0.999468 + outer loop + vertex 0.955593 1.49377 2.64565 + vertex 0.959123 1.49807 2.64554 + vertex 0.955283 1.49901 2.64567 + endloop + endfacet + facet normal 0.0324696 -0.00272003 0.999469 + outer loop + vertex 0.959123 1.49807 2.64554 + vertex 0.958905 1.503 2.64556 + vertex 0.955283 1.49901 2.64567 + endloop + endfacet + facet normal 0.0431277 -0.00287549 0.999065 + outer loop + vertex 0.963305 1.49275 2.64536 + vertex 0.963467 1.49758 2.64536 + vertex 0.959623 1.49395 2.64552 + endloop + endfacet + facet normal 0.0426047 -0.00226885 0.999089 + outer loop + vertex 0.959123 1.49807 2.64554 + vertex 0.963371 1.50244 2.64537 + vertex 0.958905 1.503 2.64556 + endloop + endfacet + facet normal 0.0687969 -0.00041858 0.997631 + outer loop + vertex 0.968351 1.49744 2.64503 + vertex 0.968346 1.50239 2.64503 + vertex 0.963467 1.49758 2.64536 + endloop + endfacet + facet normal 0.114684 0.00148977 0.993401 + outer loop + vertex 0.968346 1.50239 2.64503 + vertex 0.973481 1.50761 2.64443 + vertex 0.968337 1.5074 2.64502 + endloop + endfacet + facet normal 0.114588 0.00388475 0.993405 + outer loop + vertex 0.973481 1.50761 2.64443 + vertex 0.973483 1.51261 2.64441 + vertex 0.968337 1.5074 2.64502 + endloop + endfacet + facet normal 0.0731252 0.00355894 0.997316 + outer loop + vertex 0.968372 1.51249 2.64501 + vertex 0.968424 1.51756 2.64499 + vertex 0.963428 1.51285 2.64537 + endloop + endfacet + facet normal 0.0728569 -0.000140277 0.997342 + outer loop + vertex 0.963316 1.50757 2.64538 + vertex 0.968372 1.51249 2.64501 + vertex 0.963428 1.51285 2.64537 + endloop + endfacet + facet normal 0.0428152 -0.000569325 0.999083 + outer loop + vertex 0.963371 1.50244 2.64537 + vertex 0.963316 1.50757 2.64538 + vertex 0.958905 1.503 2.64556 + endloop + endfacet + facet normal 0.0336157 -0.00376293 0.999428 + outer loop + vertex 0.955283 1.49901 2.64567 + vertex 0.958905 1.503 2.64556 + vertex 0.955214 1.50365 2.64569 + endloop + endfacet + facet normal 0.0354452 -0.00450102 0.999361 + outer loop + vertex 0.954723 1.50698 2.64572 + vertex 0.952574 1.50435 2.64579 + vertex 0.955214 1.50365 2.64569 + endloop + endfacet + facet normal 0.0365679 -0.00542117 0.999316 + outer loop + vertex 0.954723 1.50698 2.64572 + vertex 0.952068 1.50758 2.64582 + vertex 0.952574 1.50435 2.64579 + endloop + endfacet + facet normal 0.0363633 -0.00267334 0.999335 + outer loop + vertex 0.952068 1.50758 2.64582 + vertex 0.952098 1.51208 2.64583 + vertex 0.948257 1.50778 2.64596 + endloop + endfacet + facet normal 0.0378598 -0.000972859 0.999283 + outer loop + vertex 0.958464 1.50832 2.64559 + vertex 0.95921 1.51408 2.64557 + vertex 0.955376 1.51083 2.64571 + endloop + endfacet + facet normal 0.0484351 0.0025827 0.998823 + outer loop + vertex 0.95921 1.51408 2.64557 + vertex 0.963615 1.51806 2.64535 + vertex 0.959413 1.51923 2.64555 + endloop + endfacet + facet normal 0.0360921 0.000846662 0.999348 + outer loop + vertex 0.952174 1.51699 2.64583 + vertex 0.952098 1.51208 2.64583 + vertex 0.95567 1.51571 2.6457 + endloop + endfacet + facet normal 0.0353024 0.00348794 0.999371 + outer loop + vertex 0.952174 1.51699 2.64583 + vertex 0.952153 1.52199 2.64581 + vertex 0.948288 1.51772 2.64596 + endloop + endfacet + facet normal 0.0375925 0.00537271 0.999279 + outer loop + vertex 0.951825 1.52699 2.64579 + vertex 0.952153 1.52199 2.64581 + vertex 0.95555 1.52566 2.64566 + endloop + endfacet + facet normal 0.0383576 0.00752913 0.999236 + outer loop + vertex 0.954951 1.53055 2.64565 + vertex 0.951825 1.52699 2.64579 + vertex 0.95555 1.52566 2.64566 + endloop + endfacet + facet normal 0.0378801 0.0079487 0.999251 + outer loop + vertex 0.950784 1.53225 2.64579 + vertex 0.951825 1.52699 2.64579 + vertex 0.954951 1.53055 2.64565 + endloop + endfacet + facet normal 0.0386891 0.00994113 0.999202 + outer loop + vertex 0.954951 1.53055 2.64565 + vertex 0.953956 1.53457 2.64565 + vertex 0.950784 1.53225 2.64579 + endloop + endfacet + facet normal 0.0410244 0.0105197 0.999103 + outer loop + vertex 0.953956 1.53457 2.64565 + vertex 0.954951 1.53055 2.64565 + vertex 0.958233 1.53455 2.64547 + endloop + endfacet + facet normal 0.0414652 0.0101574 0.999088 + outer loop + vertex 0.959068 1.5292 2.64549 + vertex 0.958233 1.53455 2.64547 + vertex 0.954951 1.53055 2.64565 + endloop + endfacet + facet normal 0.0392401 0.00595738 0.999212 + outer loop + vertex 0.959413 1.51923 2.64555 + vertex 0.959372 1.52422 2.64552 + vertex 0.955729 1.5207 2.64568 + endloop + endfacet + facet normal 0.0406978 0.00781576 0.999141 + outer loop + vertex 0.95555 1.52566 2.64566 + vertex 0.959068 1.5292 2.64549 + vertex 0.954951 1.53055 2.64565 + endloop + endfacet + facet normal 0.0496727 0.00823805 0.998732 + outer loop + vertex 0.96364 1.52308 2.64531 + vertex 0.963562 1.52803 2.64528 + vertex 0.959372 1.52422 2.64552 + endloop + endfacet + facet normal 0.0486317 0.0112734 0.998753 + outer loop + vertex 0.959068 1.5292 2.64549 + vertex 0.963371 1.533 2.64524 + vertex 0.958233 1.53455 2.64547 + endloop + endfacet + facet normal 0.0742483 0.0093483 0.997196 + outer loop + vertex 0.968425 1.52753 2.64492 + vertex 0.968397 1.53249 2.64488 + vertex 0.963562 1.52803 2.64528 + endloop + endfacet + facet normal 0.0718056 0.0108527 0.99736 + outer loop + vertex 0.963371 1.533 2.64524 + vertex 0.968392 1.53743 2.64483 + vertex 0.963394 1.53785 2.64518 + endloop + endfacet + facet normal 0.117564 0.00815053 0.993032 + outer loop + vertex 0.973444 1.53248 2.64428 + vertex 0.973458 1.53748 2.64424 + vertex 0.968397 1.53249 2.64488 + endloop + endfacet + facet normal 0.0718633 0.0115488 0.997348 + outer loop + vertex 0.968392 1.53743 2.64483 + vertex 0.968421 1.54235 2.64477 + vertex 0.963394 1.53785 2.64518 + endloop + endfacet + facet normal 0.0485427 0.0109772 0.998761 + outer loop + vertex 0.963371 1.533 2.64524 + vertex 0.963394 1.53785 2.64518 + vertex 0.958233 1.53455 2.64547 + endloop + endfacet + facet normal 0.0410358 0.014089 0.999058 + outer loop + vertex 0.953956 1.53457 2.64565 + vertex 0.958233 1.53455 2.64547 + vertex 0.954448 1.53917 2.64556 + endloop + endfacet + facet normal 0.0469733 0.016102 0.998766 + outer loop + vertex 0.959409 1.53905 2.64537 + vertex 0.963434 1.54247 2.64512 + vertex 0.958677 1.54286 2.64534 + endloop + endfacet + facet normal 0.0449475 0.0171966 0.998841 + outer loop + vertex 0.958677 1.54286 2.64534 + vertex 0.963267 1.54716 2.64506 + vertex 0.95834 1.54741 2.64528 + endloop + endfacet + facet normal 0.0358046 0.0190663 0.999177 + outer loop + vertex 0.953624 1.54805 2.64544 + vertex 0.958071 1.55219 2.6452 + vertex 0.953281 1.5529 2.64536 + endloop + endfacet + facet normal 0.0449456 0.0171579 0.998842 + outer loop + vertex 0.963267 1.54716 2.64506 + vertex 0.963214 1.5521 2.64498 + vertex 0.95834 1.54741 2.64528 + endloop + endfacet + facet normal 0.0657336 0.0185557 0.997665 + outer loop + vertex 0.963214 1.5521 2.64498 + vertex 0.968523 1.55742 2.64453 + vertex 0.963268 1.55715 2.64488 + endloop + endfacet + facet normal 0.0656767 0.0196494 0.997647 + outer loop + vertex 0.968523 1.55742 2.64453 + vertex 0.968606 1.5625 2.64442 + vertex 0.963268 1.55715 2.64488 + endloop + endfacet + facet normal 0.107755 0.0203894 0.993968 + outer loop + vertex 0.968606 1.5625 2.64442 + vertex 0.973617 1.56775 2.64377 + vertex 0.96866 1.56755 2.64431 + endloop + endfacet + facet normal 0.107759 0.0203001 0.99397 + outer loop + vertex 0.973617 1.56775 2.64377 + vertex 0.973597 1.57273 2.64367 + vertex 0.96866 1.56755 2.64431 + endloop + endfacet + facet normal 0.104267 0.0236621 0.994268 + outer loop + vertex 0.96866 1.56755 2.64431 + vertex 0.973597 1.57273 2.64367 + vertex 0.968672 1.57257 2.64419 + endloop + endfacet + facet normal 0.104296 0.0228528 0.994284 + outer loop + vertex 0.973597 1.57273 2.64367 + vertex 0.973579 1.57772 2.64356 + vertex 0.968672 1.57257 2.64419 + endloop + endfacet + facet normal 0.100161 0.0268341 0.994609 + outer loop + vertex 0.968672 1.57257 2.64419 + vertex 0.973579 1.57772 2.64356 + vertex 0.968676 1.57758 2.64406 + endloop + endfacet + facet normal 0.100187 0.0259547 0.99463 + outer loop + vertex 0.973579 1.57772 2.64356 + vertex 0.97359 1.58271 2.64343 + vertex 0.968676 1.57758 2.64406 + endloop + endfacet + facet normal 0.0572803 0.0329592 0.997814 + outer loop + vertex 0.968695 1.58261 2.6439 + vertex 0.96871 1.58764 2.64373 + vertex 0.963571 1.58246 2.6442 + endloop + endfacet + facet normal 0.0573249 0.0314957 0.997859 + outer loop + vertex 0.963539 1.5774 2.64436 + vertex 0.968695 1.58261 2.6439 + vertex 0.963571 1.58246 2.6442 + endloop + endfacet + facet normal 0.0412186 0.0291972 0.998723 + outer loop + vertex 0.963508 1.57235 2.64451 + vertex 0.963539 1.5774 2.64436 + vertex 0.958328 1.57224 2.64473 + endloop + endfacet + facet normal 0.0412807 0.0263966 0.998799 + outer loop + vertex 0.958258 1.56718 2.64487 + vertex 0.963508 1.57235 2.64451 + vertex 0.958328 1.57224 2.64473 + endloop + endfacet + facet normal 0.0416083 0.0239678 0.998846 + outer loop + vertex 0.958185 1.56215 2.64499 + vertex 0.963464 1.5673 2.64465 + vertex 0.958258 1.56718 2.64487 + endloop + endfacet + facet normal 0.0422552 0.0217132 0.998871 + outer loop + vertex 0.95809 1.55716 2.6451 + vertex 0.96338 1.56223 2.64477 + vertex 0.958185 1.56215 2.64499 + endloop + endfacet + facet normal 0.0359195 0.0198439 0.999158 + outer loop + vertex 0.958071 1.55219 2.6452 + vertex 0.95809 1.55716 2.6451 + vertex 0.953281 1.5529 2.64536 + endloop + endfacet + facet normal 0.0369364 0.0191455 0.999134 + outer loop + vertex 0.953624 1.54805 2.64544 + vertex 0.953281 1.5529 2.64536 + vertex 0.948711 1.54971 2.64559 + endloop + endfacet + facet normal 0.0378332 0.0197945 0.999088 + outer loop + vertex 0.944558 1.54988 2.64574 + vertex 0.948711 1.54971 2.64559 + vertex 0.945431 1.55408 2.64563 + endloop + endfacet + facet normal 0.0366494 0.0198183 0.999132 + outer loop + vertex 0.949612 1.55429 2.64546 + vertex 0.953303 1.55761 2.64526 + vertex 0.948825 1.55821 2.64541 + endloop + endfacet + facet normal 0.0368564 0.0216857 0.999085 + outer loop + vertex 0.948825 1.55821 2.64541 + vertex 0.953202 1.56238 2.64516 + vertex 0.948395 1.56294 2.64533 + endloop + endfacet + facet normal 0.033424 0.0197097 0.999247 + outer loop + vertex 0.945431 1.55408 2.64563 + vertex 0.944402 1.55904 2.64556 + vertex 0.941126 1.55559 2.64574 + endloop + endfacet + facet normal 0.0219001 0.0185386 0.999588 + outer loop + vertex 0.936853 1.55646 2.64582 + vertex 0.937926 1.55136 2.64589 + vertex 0.941126 1.55559 2.64574 + endloop + endfacet + facet normal 0.0117718 0.0171871 0.999783 + outer loop + vertex 0.931937 1.55799 2.64585 + vertex 0.936853 1.55646 2.64582 + vertex 0.936387 1.56049 2.64575 + endloop + endfacet + facet normal 0.0156951 0.021137 0.999653 + outer loop + vertex 0.933812 1.56184 2.64577 + vertex 0.936387 1.56049 2.64575 + vertex 0.936282 1.56346 2.64569 + endloop + endfacet + facet normal 0.0127325 0.0154773 0.999799 + outer loop + vertex 0.933812 1.56184 2.64577 + vertex 0.931937 1.55799 2.64585 + vertex 0.936387 1.56049 2.64575 + endloop + endfacet + facet normal 0.003006 0.0189285 0.999816 + outer loop + vertex 0.931188 1.56196 2.64579 + vertex 0.929461 1.56394 2.64576 + vertex 0.927772 1.56056 2.64583 + endloop + endfacet + facet normal 0.00434655 0.0151526 0.999876 + outer loop + vertex 0.928565 1.55276 2.64594 + vertex 0.931937 1.55799 2.64585 + vertex 0.9275 1.5565 2.64589 + endloop + endfacet + facet normal 0.00387028 0.0140819 0.999893 + outer loop + vertex 0.928925 1.54784 2.64601 + vertex 0.933041 1.55245 2.64593 + vertex 0.928565 1.55276 2.64594 + endloop + endfacet + facet normal 0.00174249 0.0123932 0.999922 + outer loop + vertex 0.928745 1.54269 2.64608 + vertex 0.93329 1.5474 2.64601 + vertex 0.928925 1.54784 2.64601 + endloop + endfacet + facet normal -0.000708371 0.0121954 0.999925 + outer loop + vertex 0.928586 1.53754 2.64614 + vertex 0.933296 1.54254 2.64608 + vertex 0.928745 1.54269 2.64608 + endloop + endfacet + facet normal -0.000838545 0.0116387 0.999932 + outer loop + vertex 0.928596 1.53248 2.6462 + vertex 0.933489 1.53767 2.64614 + vertex 0.928586 1.53754 2.64614 + endloop + endfacet + facet normal 0.000219349 0.00950677 0.999955 + outer loop + vertex 0.928538 1.52742 2.64625 + vertex 0.933566 1.53264 2.64619 + vertex 0.928596 1.53248 2.6462 + endloop + endfacet + facet normal 0.00208259 0.00665813 0.999976 + outer loop + vertex 0.92848 1.52235 2.64628 + vertex 0.933566 1.5276 2.64623 + vertex 0.928538 1.52742 2.64625 + endloop + endfacet + facet normal 0.00325201 0.00519392 0.999981 + outer loop + vertex 0.928424 1.51729 2.64631 + vertex 0.933536 1.52254 2.64626 + vertex 0.92848 1.52235 2.64628 + endloop + endfacet + facet normal 0.00361566 0.00333905 0.999988 + outer loop + vertex 0.928383 1.51226 2.64632 + vertex 0.93347 1.51747 2.64629 + vertex 0.928424 1.51729 2.64631 + endloop + endfacet + facet normal 0.00324209 0.00153064 0.999994 + outer loop + vertex 0.928326 1.50724 2.64633 + vertex 0.933385 1.51242 2.64631 + vertex 0.928383 1.51226 2.64632 + endloop + endfacet + facet normal 0.00324944 -0.00140297 0.999994 + outer loop + vertex 0.928287 1.50222 2.64632 + vertex 0.933302 1.50738 2.64631 + vertex 0.928326 1.50724 2.64633 + endloop + endfacet + facet normal 0.00391886 -0.00432295 0.999983 + outer loop + vertex 0.928339 1.49725 2.6463 + vertex 0.933259 1.50237 2.6463 + vertex 0.928287 1.50222 2.64632 + endloop + endfacet + facet normal 0.00471263 -0.00535753 0.999975 + outer loop + vertex 0.928514 1.49247 2.64628 + vertex 0.933273 1.49741 2.64628 + vertex 0.928339 1.49725 2.6463 + endloop + endfacet + facet normal 0.00577636 -0.0071959 0.999957 + outer loop + vertex 0.928519 1.4877 2.64624 + vertex 0.933319 1.49248 2.64625 + vertex 0.928514 1.49247 2.64628 + endloop + endfacet + facet normal 0.00410904 -0.00589069 0.999974 + outer loop + vertex 0.928503 1.48267 2.64621 + vertex 0.933366 1.48752 2.64622 + vertex 0.928519 1.4877 2.64624 + endloop + endfacet + facet normal 0.00254226 -0.00394572 0.999989 + outer loop + vertex 0.92865 1.47757 2.64619 + vertex 0.93343 1.48252 2.6462 + vertex 0.928503 1.48267 2.64621 + endloop + endfacet + facet normal 0.00310917 -0.00602223 0.999977 + outer loop + vertex 0.928657 1.4725 2.64616 + vertex 0.933432 1.4775 2.64618 + vertex 0.92865 1.47757 2.64619 + endloop + endfacet + facet normal 0.00513706 -0.0102526 0.999934 + outer loop + vertex 0.928658 1.46744 2.64611 + vertex 0.933364 1.47244 2.64614 + vertex 0.928657 1.4725 2.64616 + endloop + endfacet + facet normal 0.00795756 -0.014547 0.999863 + outer loop + vertex 0.92892 1.46247 2.64603 + vertex 0.933412 1.46737 2.64607 + vertex 0.928658 1.46744 2.64611 + endloop + endfacet + facet normal 0.0110265 -0.016877 0.999797 + outer loop + vertex 0.929577 1.45788 2.64595 + vertex 0.933762 1.46241 2.64598 + vertex 0.92892 1.46247 2.64603 + endloop + endfacet + facet normal 0.0129524 -0.0175969 0.999761 + outer loop + vertex 0.930497 1.45393 2.64587 + vertex 0.934173 1.45785 2.64589 + vertex 0.929577 1.45788 2.64595 + endloop + endfacet + facet normal -0.00375729 -0.0280988 0.999598 + outer loop + vertex 0.927007 1.45048 2.64576 + vertex 0.927921 1.44679 2.64566 + vertex 0.931684 1.45068 2.64579 + endloop + endfacet + facet normal -0.00114137 -0.0228976 0.999737 + outer loop + vertex 0.928618 1.44258 2.64557 + vertex 0.933821 1.44783 2.6457 + vertex 0.927921 1.44679 2.64566 + endloop + endfacet + facet normal -0.00282362 -0.0256247 0.999668 + outer loop + vertex 0.928639 1.43777 2.64545 + vertex 0.93379 1.44276 2.64559 + vertex 0.928618 1.44258 2.64557 + endloop + endfacet + facet normal -0.0120812 -0.0359991 0.999279 + outer loop + vertex 0.933533 1.42275 2.64497 + vertex 0.933513 1.42776 2.64515 + vertex 0.928418 1.42271 2.64491 + endloop + endfacet + facet normal -0.0120418 -0.0403645 0.999112 + outer loop + vertex 0.928429 1.41768 2.6447 + vertex 0.933533 1.42275 2.64497 + vertex 0.928418 1.42271 2.64491 + endloop + endfacet + facet normal -0.0496743 -0.0403974 0.997948 + outer loop + vertex 0.928429 1.41768 2.6447 + vertex 0.928418 1.42271 2.64491 + vertex 0.923303 1.41758 2.64444 + endloop + endfacet + facet normal -0.0496193 -0.0429633 0.997844 + outer loop + vertex 0.923321 1.41259 2.64423 + vertex 0.928429 1.41768 2.6447 + vertex 0.923303 1.41758 2.64444 + endloop + endfacet + facet normal -0.0508059 -0.0417713 0.997835 + outer loop + vertex 0.928431 1.41266 2.64449 + vertex 0.928429 1.41768 2.6447 + vertex 0.923321 1.41259 2.64423 + endloop + endfacet + facet normal -0.0507799 -0.0434579 0.997764 + outer loop + vertex 0.923316 1.40757 2.64401 + vertex 0.928431 1.41266 2.64449 + vertex 0.923321 1.41259 2.64423 + endloop + endfacet + facet normal -0.0530298 -0.0411961 0.997743 + outer loop + vertex 0.928433 1.40765 2.64429 + vertex 0.928431 1.41266 2.64449 + vertex 0.923316 1.40757 2.64401 + endloop + endfacet + facet normal -0.0530436 -0.0403983 0.997775 + outer loop + vertex 0.923348 1.40251 2.64381 + vertex 0.928433 1.40765 2.64429 + vertex 0.923316 1.40757 2.64401 + endloop + endfacet + facet normal -0.0518375 -0.0415933 0.997789 + outer loop + vertex 0.928435 1.40265 2.64408 + vertex 0.928433 1.40765 2.64429 + vertex 0.923348 1.40251 2.64381 + endloop + endfacet + facet normal -0.0518017 -0.0427891 0.99774 + outer loop + vertex 0.923394 1.39748 2.6436 + vertex 0.928435 1.40265 2.64408 + vertex 0.923348 1.40251 2.64381 + endloop + endfacet + facet normal -0.0493218 -0.0452104 0.997759 + outer loop + vertex 0.928409 1.39766 2.64385 + vertex 0.928435 1.40265 2.64408 + vertex 0.923394 1.39748 2.6436 + endloop + endfacet + facet normal -0.0492 -0.0483866 0.997616 + outer loop + vertex 0.923374 1.39248 2.64335 + vertex 0.928409 1.39766 2.64385 + vertex 0.923394 1.39748 2.6436 + endloop + endfacet + facet normal -0.0473441 -0.0501895 0.997617 + outer loop + vertex 0.928346 1.39267 2.6436 + vertex 0.928409 1.39766 2.64385 + vertex 0.923374 1.39248 2.64335 + endloop + endfacet + facet normal -0.047117 -0.0558643 0.997326 + outer loop + vertex 0.923336 1.38749 2.64307 + vertex 0.928346 1.39267 2.6436 + vertex 0.923374 1.39248 2.64335 + endloop + endfacet + facet normal -0.0477286 -0.0552725 0.99733 + outer loop + vertex 0.92828 1.38765 2.64332 + vertex 0.928346 1.39267 2.6436 + vertex 0.923336 1.38749 2.64307 + endloop + endfacet + facet normal -0.0476361 -0.0580054 0.997179 + outer loop + vertex 0.92337 1.38254 2.64278 + vertex 0.92828 1.38765 2.64332 + vertex 0.923336 1.38749 2.64307 + endloop + endfacet + facet normal -0.0478604 -0.0577898 0.997181 + outer loop + vertex 0.928261 1.38263 2.64302 + vertex 0.92828 1.38765 2.64332 + vertex 0.92337 1.38254 2.64278 + endloop + endfacet + facet normal -0.0478661 -0.0575151 0.997196 + outer loop + vertex 0.923552 1.37775 2.64252 + vertex 0.928261 1.38263 2.64302 + vertex 0.92337 1.38254 2.64278 + endloop + endfacet + facet normal -0.0477522 -0.057625 0.997196 + outer loop + vertex 0.928267 1.37762 2.64273 + vertex 0.928261 1.38263 2.64302 + vertex 0.923552 1.37775 2.64252 + endloop + endfacet + facet normal -0.0477936 -0.0592122 0.997101 + outer loop + vertex 0.923607 1.37293 2.64223 + vertex 0.928267 1.37762 2.64273 + vertex 0.923552 1.37775 2.64252 + endloop + endfacet + facet normal -0.0493233 -0.0576936 0.997115 + outer loop + vertex 0.928321 1.3726 2.64245 + vertex 0.928267 1.37762 2.64273 + vertex 0.923607 1.37293 2.64223 + endloop + endfacet + facet normal -0.0492986 -0.0573266 0.997138 + outer loop + vertex 0.923885 1.36794 2.64196 + vertex 0.928321 1.3726 2.64245 + vertex 0.923607 1.37293 2.64223 + endloop + endfacet + facet normal -0.0485546 -0.0580353 0.997133 + outer loop + vertex 0.928482 1.3677 2.64217 + vertex 0.928321 1.3726 2.64245 + vertex 0.923885 1.36794 2.64196 + endloop + endfacet + facet normal -0.0482787 -0.0525943 0.997448 + outer loop + vertex 0.924818 1.36381 2.64179 + vertex 0.928482 1.3677 2.64217 + vertex 0.923885 1.36794 2.64196 + endloop + endfacet + facet normal -0.0392746 -0.0610774 0.99736 + outer loop + vertex 0.928529 1.36281 2.64187 + vertex 0.928482 1.3677 2.64217 + vertex 0.924818 1.36381 2.64179 + endloop + endfacet + facet normal -0.0414773 -0.0692396 0.996737 + outer loop + vertex 0.924008 1.35887 2.64141 + vertex 0.928529 1.36281 2.64187 + vertex 0.924818 1.36381 2.64179 + endloop + endfacet + facet normal -0.0458891 -0.0641908 0.996882 + outer loop + vertex 0.928967 1.35785 2.64157 + vertex 0.928529 1.36281 2.64187 + vertex 0.924008 1.35887 2.64141 + endloop + endfacet + facet normal -0.0447035 -0.0583374 0.997296 + outer loop + vertex 0.925967 1.35322 2.64117 + vertex 0.928967 1.35785 2.64157 + vertex 0.924008 1.35887 2.64141 + endloop + endfacet + facet normal -0.0356723 -0.0641902 0.9973 + outer loop + vertex 0.930257 1.35391 2.64137 + vertex 0.928967 1.35785 2.64157 + vertex 0.925967 1.35322 2.64117 + endloop + endfacet + facet normal -0.0360137 -0.0620908 0.997421 + outer loop + vertex 0.930008 1.34965 2.64109 + vertex 0.930257 1.35391 2.64137 + vertex 0.925967 1.35322 2.64117 + endloop + endfacet + facet normal -0.0396935 -0.0662392 0.997014 + outer loop + vertex 0.925774 1.349 2.64088 + vertex 0.930008 1.34965 2.64109 + vertex 0.925967 1.35322 2.64117 + endloop + endfacet + facet normal -0.083294 -0.0640768 0.994463 + outer loop + vertex 0.925774 1.349 2.64088 + vertex 0.925967 1.35322 2.64117 + vertex 0.922754 1.3506 2.64073 + endloop + endfacet + facet normal -0.0990412 -0.0941236 0.990622 + outer loop + vertex 0.922543 1.34604 2.64028 + vertex 0.925774 1.349 2.64088 + vertex 0.922754 1.3506 2.64073 + endloop + endfacet + facet normal -0.178036 -0.0894007 0.979954 + outer loop + vertex 0.922754 1.3506 2.64073 + vertex 0.918382 1.35071 2.63995 + vertex 0.922543 1.34604 2.64028 + endloop + endfacet + facet normal -0.184505 -0.0952901 0.978201 + outer loop + vertex 0.922543 1.34604 2.64028 + vertex 0.918382 1.35071 2.63995 + vertex 0.91747 1.34615 2.63933 + endloop + endfacet + facet normal -0.184372 -0.0684762 0.980468 + outer loop + vertex 0.918344 1.34212 2.63921 + vertex 0.922543 1.34604 2.64028 + vertex 0.91747 1.34615 2.63933 + endloop + endfacet + facet normal -0.18017 -0.0730927 0.980916 + outer loop + vertex 0.922101 1.34116 2.63983 + vertex 0.922543 1.34604 2.64028 + vertex 0.918344 1.34212 2.63921 + endloop + endfacet + facet normal -0.183585 -0.0875883 0.979094 + outer loop + vertex 0.918672 1.33755 2.63886 + vertex 0.922101 1.34116 2.63983 + vertex 0.918344 1.34212 2.63921 + endloop + endfacet + facet normal -0.0904559 -0.0822662 0.992497 + outer loop + vertex 0.927076 1.34221 2.64037 + vertex 0.922543 1.34604 2.64028 + vertex 0.922101 1.34116 2.63983 + endloop + endfacet + facet normal -0.0888177 -0.0897438 0.991997 + outer loop + vertex 0.923185 1.3374 2.63959 + vertex 0.927076 1.34221 2.64037 + vertex 0.922101 1.34116 2.63983 + endloop + endfacet + facet normal -0.0818401 -0.0953976 0.992069 + outer loop + vertex 0.928273 1.33742 2.64001 + vertex 0.927076 1.34221 2.64037 + vertex 0.923185 1.3374 2.63959 + endloop + endfacet + facet normal -0.0818955 -0.09103 0.992475 + outer loop + vertex 0.923576 1.33274 2.63919 + vertex 0.928273 1.33742 2.64001 + vertex 0.923185 1.3374 2.63959 + endloop + endfacet + facet normal -0.156473 -0.0964908 0.982958 + outer loop + vertex 0.923576 1.33274 2.63919 + vertex 0.923185 1.3374 2.63959 + vertex 0.918951 1.33283 2.63846 + endloop + endfacet + facet normal -0.156411 -0.0825663 0.984235 + outer loop + vertex 0.919189 1.32793 2.63809 + vertex 0.923576 1.33274 2.63919 + vertex 0.918951 1.33283 2.63846 + endloop + endfacet + facet normal -0.153812 -0.084986 0.984439 + outer loop + vertex 0.923651 1.32795 2.63879 + vertex 0.923576 1.33274 2.63919 + vertex 0.919189 1.32793 2.63809 + endloop + endfacet + facet normal -0.153988 -0.0730364 0.98537 + outer loop + vertex 0.919808 1.32388 2.63789 + vertex 0.923651 1.32795 2.63879 + vertex 0.919189 1.32793 2.63809 + endloop + endfacet + facet normal -0.140469 -0.0860278 0.98634 + outer loop + vertex 0.923452 1.32299 2.63833 + vertex 0.923651 1.32795 2.63879 + vertex 0.919808 1.32388 2.63789 + endloop + endfacet + facet normal -0.145598 -0.108407 0.983387 + outer loop + vertex 0.918529 1.31879 2.63714 + vertex 0.923452 1.32299 2.63833 + vertex 0.919808 1.32388 2.63789 + endloop + endfacet + facet normal -0.164576 -0.0859095 0.982616 + outer loop + vertex 0.923369 1.31777 2.63786 + vertex 0.923452 1.32299 2.63833 + vertex 0.918529 1.31879 2.63714 + endloop + endfacet + facet normal -0.164608 -0.0860737 0.982596 + outer loop + vertex 0.919329 1.31336 2.6368 + vertex 0.923369 1.31777 2.63786 + vertex 0.918529 1.31879 2.63714 + endloop + endfacet + facet normal -0.161226 -0.089237 0.982875 + outer loop + vertex 0.923727 1.31267 2.63745 + vertex 0.923369 1.31777 2.63786 + vertex 0.919329 1.31336 2.6368 + endloop + endfacet + facet normal -0.161091 -0.0882733 0.982984 + outer loop + vertex 0.920042 1.30851 2.63648 + vertex 0.923727 1.31267 2.63745 + vertex 0.919329 1.31336 2.6368 + endloop + endfacet + facet normal -0.147168 -0.100821 0.98396 + outer loop + vertex 0.924297 1.30785 2.63705 + vertex 0.923727 1.31267 2.63745 + vertex 0.920042 1.30851 2.63648 + endloop + endfacet + facet normal -0.146902 -0.0989079 0.984194 + outer loop + vertex 0.920818 1.30404 2.63614 + vertex 0.924297 1.30785 2.63705 + vertex 0.920042 1.30851 2.63648 + endloop + endfacet + facet normal -0.0814746 -0.0937689 0.992255 + outer loop + vertex 0.924297 1.30785 2.63705 + vertex 0.928422 1.31255 2.63783 + vertex 0.923727 1.31267 2.63745 + endloop + endfacet + facet normal -0.0814361 -0.0915788 0.992462 + outer loop + vertex 0.928422 1.31255 2.63783 + vertex 0.928232 1.31756 2.63828 + vertex 0.923727 1.31267 2.63745 + endloop + endfacet + facet normal -0.0462485 -0.0904562 0.994826 + outer loop + vertex 0.928422 1.31255 2.63783 + vertex 0.933248 1.31767 2.63852 + vertex 0.928232 1.31756 2.63828 + endloop + endfacet + facet normal -0.0463187 -0.0877755 0.995063 + outer loop + vertex 0.933248 1.31767 2.63852 + vertex 0.933288 1.32278 2.63897 + vertex 0.928232 1.31756 2.63828 + endloop + endfacet + facet normal -0.0771714 -0.097535 0.992236 + outer loop + vertex 0.928851 1.30779 2.63739 + vertex 0.928422 1.31255 2.63783 + vertex 0.924297 1.30785 2.63705 + endloop + endfacet + facet normal -0.0771822 -0.100383 0.991951 + outer loop + vertex 0.925263 1.30279 2.63661 + vertex 0.928851 1.30779 2.63739 + vertex 0.924297 1.30785 2.63705 + endloop + endfacet + facet normal -0.134181 -0.110662 0.984758 + outer loop + vertex 0.925263 1.30279 2.63661 + vertex 0.924297 1.30785 2.63705 + vertex 0.920818 1.30404 2.63614 + endloop + endfacet + facet normal -0.137222 -0.122197 0.982974 + outer loop + vertex 0.925263 1.30279 2.63661 + vertex 0.920818 1.30404 2.63614 + vertex 0.921224 1.29978 2.63567 + endloop + endfacet + facet normal -0.243199 -0.129907 0.961238 + outer loop + vertex 0.921224 1.29978 2.63567 + vertex 0.920818 1.30404 2.63614 + vertex 0.918126 1.30137 2.6351 + endloop + endfacet + facet normal -0.261657 -0.169884 0.950092 + outer loop + vertex 0.918126 1.30137 2.6351 + vertex 0.917542 1.29717 2.63419 + vertex 0.921224 1.29978 2.63567 + endloop + endfacet + facet normal -0.0886843 -0.0848974 0.992435 + outer loop + vertex 0.923727 1.31267 2.63745 + vertex 0.928232 1.31756 2.63828 + vertex 0.923369 1.31777 2.63786 + endloop + endfacet + facet normal -0.0887508 -0.0867566 0.992268 + outer loop + vertex 0.928232 1.31756 2.63828 + vertex 0.928237 1.32272 2.63873 + vertex 0.923369 1.31777 2.63786 + endloop + endfacet + facet normal -0.0470778 -0.0870431 0.995092 + outer loop + vertex 0.928232 1.31756 2.63828 + vertex 0.933288 1.32278 2.63897 + vertex 0.928237 1.32272 2.63873 + endloop + endfacet + facet normal -0.0471322 -0.0834731 0.995395 + outer loop + vertex 0.933288 1.32278 2.63897 + vertex 0.933447 1.3279 2.63941 + vertex 0.928237 1.32272 2.63873 + endloop + endfacet + facet normal -0.044807 -0.0857985 0.995304 + outer loop + vertex 0.928237 1.32272 2.63873 + vertex 0.933447 1.3279 2.63941 + vertex 0.928418 1.32786 2.63918 + endloop + endfacet + facet normal -0.0872829 -0.0840645 0.99263 + outer loop + vertex 0.928237 1.32272 2.63873 + vertex 0.928418 1.32786 2.63918 + vertex 0.923452 1.32299 2.63833 + endloop + endfacet + facet normal -0.044858 -0.0819956 0.995623 + outer loop + vertex 0.933447 1.3279 2.63941 + vertex 0.933637 1.33285 2.63982 + vertex 0.928418 1.32786 2.63918 + endloop + endfacet + facet normal -0.0874729 -0.0880149 0.992271 + outer loop + vertex 0.923369 1.31777 2.63786 + vertex 0.928237 1.32272 2.63873 + vertex 0.923452 1.32299 2.63833 + endloop + endfacet + facet normal -0.0825069 -0.0889326 0.992615 + outer loop + vertex 0.923452 1.32299 2.63833 + vertex 0.928418 1.32786 2.63918 + vertex 0.923651 1.32795 2.63879 + endloop + endfacet + facet normal -0.0824607 -0.0850049 0.992962 + outer loop + vertex 0.928418 1.32786 2.63918 + vertex 0.92855 1.33277 2.63961 + vertex 0.923651 1.32795 2.63879 + endloop + endfacet + facet normal -0.0828612 -0.0845986 0.992964 + outer loop + vertex 0.923651 1.32795 2.63879 + vertex 0.92855 1.33277 2.63961 + vertex 0.923576 1.33274 2.63919 + endloop + endfacet + facet normal -0.0827856 -0.090139 0.992483 + outer loop + vertex 0.92855 1.33277 2.63961 + vertex 0.928273 1.33742 2.64001 + vertex 0.923576 1.33274 2.63919 + endloop + endfacet + facet normal -0.0395707 -0.0850839 0.995588 + outer loop + vertex 0.928273 1.33742 2.64001 + vertex 0.932794 1.34151 2.64054 + vertex 0.927076 1.34221 2.64037 + endloop + endfacet + facet normal -0.0395747 -0.085117 0.995585 + outer loop + vertex 0.927076 1.34221 2.64037 + vertex 0.932794 1.34151 2.64054 + vertex 0.93169 1.34542 2.64083 + endloop + endfacet + facet normal -0.0354688 -0.0909706 0.995222 + outer loop + vertex 0.927533 1.34634 2.64076 + vertex 0.927076 1.34221 2.64037 + vertex 0.93169 1.34542 2.64083 + endloop + endfacet + facet normal -0.0318554 -0.0745253 0.99671 + outer loop + vertex 0.93169 1.34542 2.64083 + vertex 0.930008 1.34965 2.64109 + vertex 0.927533 1.34634 2.64076 + endloop + endfacet + facet normal -0.0106194 -0.0661366 0.997754 + outer loop + vertex 0.935253 1.34879 2.64109 + vertex 0.930008 1.34965 2.64109 + vertex 0.93169 1.34542 2.64083 + endloop + endfacet + facet normal -0.00773997 -0.0691632 0.997575 + outer loop + vertex 0.936746 1.34508 2.64084 + vertex 0.935253 1.34879 2.64109 + vertex 0.93169 1.34542 2.64083 + endloop + endfacet + facet normal -0.0102914 -0.0641199 0.997889 + outer loop + vertex 0.935253 1.34879 2.64109 + vertex 0.934167 1.35302 2.64135 + vertex 0.930008 1.34965 2.64109 + endloop + endfacet + facet normal 0.00327906 -0.0606467 0.998154 + outer loop + vertex 0.935253 1.34879 2.64109 + vertex 0.939057 1.35276 2.64132 + vertex 0.934167 1.35302 2.64135 + endloop + endfacet + facet normal 0.00315905 -0.0629086 0.998014 + outer loop + vertex 0.939057 1.35276 2.64132 + vertex 0.938311 1.35742 2.64161 + vertex 0.934167 1.35302 2.64135 + endloop + endfacet + facet normal 0.000742117 -0.0606442 0.998159 + outer loop + vertex 0.934167 1.35302 2.64135 + vertex 0.938311 1.35742 2.64161 + vertex 0.933545 1.35759 2.64163 + endloop + endfacet + facet normal -0.0103793 -0.0621469 0.998013 + outer loop + vertex 0.934167 1.35302 2.64135 + vertex 0.933545 1.35759 2.64163 + vertex 0.930257 1.35391 2.64137 + endloop + endfacet + facet normal -0.0107125 -0.0636023 0.997918 + outer loop + vertex 0.930008 1.34965 2.64109 + vertex 0.934167 1.35302 2.64135 + vertex 0.930257 1.35391 2.64137 + endloop + endfacet + facet normal 0.000682773 -0.0623068 0.998057 + outer loop + vertex 0.938311 1.35742 2.64161 + vertex 0.938096 1.36247 2.64193 + vertex 0.933545 1.35759 2.64163 + endloop + endfacet + facet normal -0.000291025 -0.0614023 0.998113 + outer loop + vertex 0.933545 1.35759 2.64163 + vertex 0.938096 1.36247 2.64193 + vertex 0.933203 1.36248 2.64193 + endloop + endfacet + facet normal -0.0157328 -0.0624687 0.997923 + outer loop + vertex 0.933545 1.35759 2.64163 + vertex 0.933203 1.36248 2.64193 + vertex 0.928967 1.35785 2.64157 + endloop + endfacet + facet normal -0.000292159 -0.0618839 0.998083 + outer loop + vertex 0.938096 1.36247 2.64193 + vertex 0.938195 1.36763 2.64225 + vertex 0.933203 1.36248 2.64193 + endloop + endfacet + facet normal 0.000316183 -0.0624723 0.998047 + outer loop + vertex 0.933203 1.36248 2.64193 + vertex 0.938195 1.36763 2.64225 + vertex 0.933213 1.36756 2.64225 + endloop + endfacet + facet normal -0.0166649 -0.0624322 0.99791 + outer loop + vertex 0.933203 1.36248 2.64193 + vertex 0.933213 1.36756 2.64225 + vertex 0.928529 1.36281 2.64187 + endloop + endfacet + facet normal 0.000297585 -0.0610949 0.998132 + outer loop + vertex 0.938195 1.36763 2.64225 + vertex 0.938367 1.37273 2.64256 + vertex 0.933213 1.36756 2.64225 + endloop + endfacet + facet normal -0.000224111 -0.0605768 0.998164 + outer loop + vertex 0.933213 1.36756 2.64225 + vertex 0.938367 1.37273 2.64256 + vertex 0.933296 1.37261 2.64255 + endloop + endfacet + facet normal -0.0181922 -0.0602719 0.998016 + outer loop + vertex 0.933213 1.36756 2.64225 + vertex 0.933296 1.37261 2.64255 + vertex 0.928482 1.3677 2.64217 + endloop + endfacet + facet normal -0.000279587 -0.0582927 0.998299 + outer loop + vertex 0.938367 1.37273 2.64256 + vertex 0.938468 1.37777 2.64286 + vertex 0.933296 1.37261 2.64255 + endloop + endfacet + facet normal -0.000352113 -0.0582203 0.998304 + outer loop + vertex 0.933296 1.37261 2.64255 + vertex 0.938468 1.37777 2.64286 + vertex 0.933332 1.37765 2.64285 + endloop + endfacet + facet normal -0.021333 -0.0580591 0.998085 + outer loop + vertex 0.933296 1.37261 2.64255 + vertex 0.933332 1.37765 2.64285 + vertex 0.928321 1.3726 2.64245 + endloop + endfacet + facet normal -0.000404423 -0.055916 0.998435 + outer loop + vertex 0.938468 1.37777 2.64286 + vertex 0.938503 1.38279 2.64314 + vertex 0.933332 1.37765 2.64285 + endloop + endfacet + facet normal 0.000413012 -0.0567359 0.998389 + outer loop + vertex 0.933332 1.37765 2.64285 + vertex 0.938503 1.38279 2.64314 + vertex 0.93336 1.38271 2.64314 + endloop + endfacet + facet normal -0.0219509 -0.0565965 0.998156 + outer loop + vertex 0.933332 1.37765 2.64285 + vertex 0.93336 1.38271 2.64314 + vertex 0.928267 1.37762 2.64273 + endloop + endfacet + facet normal 0.000361378 -0.0533967 0.998573 + outer loop + vertex 0.938503 1.38279 2.64314 + vertex 0.938519 1.38781 2.64341 + vertex 0.93336 1.38271 2.64314 + endloop + endfacet + facet normal 0.00267477 -0.0557277 0.998442 + outer loop + vertex 0.93336 1.38271 2.64314 + vertex 0.938519 1.38781 2.64341 + vertex 0.933397 1.38777 2.64342 + endloop + endfacet + facet normal -0.0209343 -0.0555456 0.998237 + outer loop + vertex 0.93336 1.38271 2.64314 + vertex 0.933397 1.38777 2.64342 + vertex 0.928261 1.38263 2.64302 + endloop + endfacet + facet normal -0.0185164 -0.0579575 0.998147 + outer loop + vertex 0.928261 1.38263 2.64302 + vertex 0.933397 1.38777 2.64342 + vertex 0.92828 1.38765 2.64332 + endloop + endfacet + facet normal -0.0186309 -0.0532362 0.998408 + outer loop + vertex 0.933397 1.38777 2.64342 + vertex 0.933444 1.3928 2.64369 + vertex 0.92828 1.38765 2.64332 + endloop + endfacet + facet normal 0.00525328 -0.0534666 0.998556 + outer loop + vertex 0.933397 1.38777 2.64342 + vertex 0.938535 1.39283 2.64366 + vertex 0.933444 1.3928 2.64369 + endloop + endfacet + facet normal 0.0052133 -0.0469859 0.998882 + outer loop + vertex 0.938535 1.39283 2.64366 + vertex 0.938546 1.39784 2.6439 + vertex 0.933444 1.3928 2.64369 + endloop + endfacet + facet normal 0.0235436 -0.0470143 0.998617 + outer loop + vertex 0.938535 1.39283 2.64366 + vertex 0.943538 1.3978 2.64378 + vertex 0.938546 1.39784 2.6439 + endloop + endfacet + facet normal 0.0235814 -0.0425447 0.998816 + outer loop + vertex 0.943538 1.3978 2.64378 + vertex 0.943528 1.40279 2.64399 + vertex 0.938546 1.39784 2.6439 + endloop + endfacet + facet normal 0.0246016 -0.0435702 0.998747 + outer loop + vertex 0.938546 1.39784 2.6439 + vertex 0.943528 1.40279 2.64399 + vertex 0.938552 1.40283 2.64411 + endloop + endfacet + facet normal 0.00768622 -0.0435621 0.999021 + outer loop + vertex 0.938546 1.39784 2.6439 + vertex 0.938552 1.40283 2.64411 + vertex 0.93349 1.39781 2.64393 + endloop + endfacet + facet normal 0.00771742 -0.0495168 0.998743 + outer loop + vertex 0.933444 1.3928 2.64369 + vertex 0.938546 1.39784 2.6439 + vertex 0.93349 1.39781 2.64393 + endloop + endfacet + facet normal -0.0162992 -0.0492927 0.998651 + outer loop + vertex 0.933444 1.3928 2.64369 + vertex 0.93349 1.39781 2.64393 + vertex 0.928346 1.39267 2.6436 + endloop + endfacet + facet normal -0.0149406 -0.0506483 0.998605 + outer loop + vertex 0.928346 1.39267 2.6436 + vertex 0.93349 1.39781 2.64393 + vertex 0.928409 1.39766 2.64385 + endloop + endfacet + facet normal -0.0151068 -0.0450364 0.998871 + outer loop + vertex 0.93349 1.39781 2.64393 + vertex 0.933519 1.40279 2.64416 + vertex 0.928409 1.39766 2.64385 + endloop + endfacet + facet normal -0.0146984 -0.0454426 0.998859 + outer loop + vertex 0.928409 1.39766 2.64385 + vertex 0.933519 1.40279 2.64416 + vertex 0.928435 1.40265 2.64408 + endloop + endfacet + facet normal -0.0147767 -0.042719 0.998978 + outer loop + vertex 0.933519 1.40279 2.64416 + vertex 0.933532 1.40777 2.64437 + vertex 0.928435 1.40265 2.64408 + endloop + endfacet + facet normal 0.0102807 -0.0427879 0.999031 + outer loop + vertex 0.933519 1.40279 2.64416 + vertex 0.938555 1.4078 2.64432 + vertex 0.933532 1.40777 2.64437 + endloop + endfacet + facet normal 0.0102645 -0.0405031 0.999127 + outer loop + vertex 0.938555 1.4078 2.64432 + vertex 0.938557 1.41278 2.64452 + vertex 0.933532 1.40777 2.64437 + endloop + endfacet + facet normal 0.0264332 -0.0404987 0.99883 + outer loop + vertex 0.938555 1.4078 2.64432 + vertex 0.943514 1.41276 2.64439 + vertex 0.938557 1.41278 2.64452 + endloop + endfacet + facet normal 0.0264426 -0.038801 0.998897 + outer loop + vertex 0.943514 1.41276 2.64439 + vertex 0.943516 1.41774 2.64459 + vertex 0.938557 1.41278 2.64452 + endloop + endfacet + facet normal 0.0272014 -0.0395586 0.998847 + outer loop + vertex 0.938557 1.41278 2.64452 + vertex 0.943516 1.41774 2.64459 + vertex 0.938562 1.41776 2.64472 + endloop + endfacet + facet normal 0.010505 -0.0395549 0.999162 + outer loop + vertex 0.938557 1.41278 2.64452 + vertex 0.938562 1.41776 2.64472 + vertex 0.933537 1.41275 2.64458 + endloop + endfacet + facet normal 0.0105122 -0.040751 0.999114 + outer loop + vertex 0.933532 1.40777 2.64437 + vertex 0.938557 1.41278 2.64452 + vertex 0.933537 1.41275 2.64458 + endloop + endfacet + facet normal -0.0158966 -0.0407257 0.999044 + outer loop + vertex 0.933532 1.40777 2.64437 + vertex 0.933537 1.41275 2.64458 + vertex 0.928433 1.40765 2.64429 + endloop + endfacet + facet normal 0.0109585 -0.0400087 0.999139 + outer loop + vertex 0.933537 1.41275 2.64458 + vertex 0.938562 1.41776 2.64472 + vertex 0.93354 1.41774 2.64478 + endloop + endfacet + facet normal -0.0154094 -0.0399897 0.999081 + outer loop + vertex 0.933537 1.41275 2.64458 + vertex 0.93354 1.41774 2.64478 + vertex 0.928431 1.41266 2.64449 + endloop + endfacet + facet normal 0.0109489 -0.0369773 0.999256 + outer loop + vertex 0.938562 1.41776 2.64472 + vertex 0.93856 1.42275 2.64491 + vertex 0.93354 1.41774 2.64478 + endloop + endfacet + facet normal 0.0126924 -0.038724 0.999169 + outer loop + vertex 0.93354 1.41774 2.64478 + vertex 0.93856 1.42275 2.64491 + vertex 0.933533 1.42275 2.64497 + endloop + endfacet + facet normal 0.0126956 -0.0341416 0.999336 + outer loop + vertex 0.93856 1.42275 2.64491 + vertex 0.938538 1.42774 2.64508 + vertex 0.933533 1.42275 2.64497 + endloop + endfacet + facet normal 0.0281871 -0.0340649 0.999022 + outer loop + vertex 0.93856 1.42275 2.64491 + vertex 0.943513 1.42771 2.64494 + vertex 0.938538 1.42774 2.64508 + endloop + endfacet + facet normal 0.02821 -0.029932 0.999154 + outer loop + vertex 0.943513 1.42771 2.64494 + vertex 0.943481 1.4327 2.64509 + vertex 0.938538 1.42774 2.64508 + endloop + endfacet + facet normal 0.0289622 -0.0306814 0.99911 + outer loop + vertex 0.938538 1.42774 2.64508 + vertex 0.943481 1.4327 2.64509 + vertex 0.938506 1.43273 2.64523 + endloop + endfacet + facet normal 0.0346291 -0.0298853 0.998953 + outer loop + vertex 0.943513 1.42771 2.64494 + vertex 0.948451 1.43268 2.64491 + vertex 0.943481 1.4327 2.64509 + endloop + endfacet + facet normal 0.0346423 -0.0271028 0.999032 + outer loop + vertex 0.948451 1.43268 2.64491 + vertex 0.948419 1.43766 2.64505 + vertex 0.943481 1.4327 2.64509 + endloop + endfacet + facet normal 0.0346274 -0.027088 0.999033 + outer loop + vertex 0.943481 1.4327 2.64509 + vertex 0.948419 1.43766 2.64505 + vertex 0.943447 1.43768 2.64522 + endloop + endfacet + facet normal 0.0346358 -0.0253714 0.999078 + outer loop + vertex 0.948419 1.43766 2.64505 + vertex 0.948389 1.44265 2.64518 + vertex 0.943447 1.43768 2.64522 + endloop + endfacet + facet normal 0.0353704 -0.0253663 0.999052 + outer loop + vertex 0.948419 1.43766 2.64505 + vertex 0.953379 1.44263 2.645 + vertex 0.948389 1.44265 2.64518 + endloop + endfacet + facet normal 0.0356571 -0.025653 0.999035 + outer loop + vertex 0.953407 1.43764 2.64487 + vertex 0.953379 1.44263 2.645 + vertex 0.948419 1.43766 2.64505 + endloop + endfacet + facet normal 0.0359012 -0.0256514 0.999026 + outer loop + vertex 0.953407 1.43764 2.64487 + vertex 0.958408 1.44262 2.64482 + vertex 0.953379 1.44263 2.645 + endloop + endfacet + facet normal 0.0359031 -0.0249964 0.999043 + outer loop + vertex 0.958408 1.44262 2.64482 + vertex 0.958386 1.4476 2.64494 + vertex 0.953379 1.44263 2.645 + endloop + endfacet + facet normal 0.0353789 -0.024468 0.999074 + outer loop + vertex 0.953379 1.44263 2.645 + vertex 0.958386 1.4476 2.64494 + vertex 0.953352 1.4476 2.64512 + endloop + endfacet + facet normal 0.041956 -0.0249639 0.998808 + outer loop + vertex 0.958408 1.44262 2.64482 + vertex 0.963476 1.44765 2.64473 + vertex 0.958386 1.4476 2.64494 + endloop + endfacet + facet normal 0.0419464 -0.0238001 0.998836 + outer loop + vertex 0.963476 1.44765 2.64473 + vertex 0.963464 1.45263 2.64485 + vertex 0.958386 1.4476 2.64494 + endloop + endfacet + facet normal 0.0414484 -0.0232964 0.998869 + outer loop + vertex 0.958386 1.4476 2.64494 + vertex 0.963464 1.45263 2.64485 + vertex 0.958361 1.45256 2.64506 + endloop + endfacet + facet normal 0.0631113 -0.0237196 0.997725 + outer loop + vertex 0.963476 1.44765 2.64473 + vertex 0.968584 1.45275 2.64453 + vertex 0.963464 1.45263 2.64485 + endloop + endfacet + facet normal 0.0630221 -0.0198639 0.997814 + outer loop + vertex 0.968584 1.45275 2.64453 + vertex 0.968582 1.45774 2.64463 + vertex 0.963464 1.45263 2.64485 + endloop + endfacet + facet normal 0.0641682 -0.0210155 0.997718 + outer loop + vertex 0.963464 1.45263 2.64485 + vertex 0.968582 1.45774 2.64463 + vertex 0.963442 1.45759 2.64496 + endloop + endfacet + facet normal 0.105782 -0.0197718 0.994193 + outer loop + vertex 0.968584 1.45275 2.64453 + vertex 0.973597 1.45786 2.6441 + vertex 0.968582 1.45774 2.64463 + endloop + endfacet + facet normal 0.105679 -0.0149567 0.994288 + outer loop + vertex 0.973597 1.45786 2.6441 + vertex 0.973606 1.46285 2.64417 + vertex 0.968582 1.45774 2.64463 + endloop + endfacet + facet normal 0.108221 -0.0174818 0.993973 + outer loop + vertex 0.968582 1.45774 2.64463 + vertex 0.973606 1.46285 2.64417 + vertex 0.968573 1.46271 2.64472 + endloop + endfacet + facet normal 0.172162 -0.0149475 0.984955 + outer loop + vertex 0.973597 1.45786 2.6441 + vertex 0.978301 1.46274 2.64335 + vertex 0.973606 1.46285 2.64417 + endloop + endfacet + facet normal 0.172277 -0.0105192 0.984992 + outer loop + vertex 0.978301 1.46274 2.64335 + vertex 0.978319 1.46775 2.6434 + vertex 0.973606 1.46285 2.64417 + endloop + endfacet + facet normal 0.173398 -0.0116315 0.984783 + outer loop + vertex 0.973606 1.46285 2.64417 + vertex 0.978319 1.46775 2.6434 + vertex 0.973605 1.46784 2.64423 + endloop + endfacet + facet normal 0.170259 -0.0130596 0.985313 + outer loop + vertex 0.978279 1.45774 2.64329 + vertex 0.978301 1.46274 2.64335 + vertex 0.973597 1.45786 2.6441 + endloop + endfacet + facet normal 0.170092 -0.0191413 0.985242 + outer loop + vertex 0.973579 1.45285 2.644 + vertex 0.978279 1.45774 2.64329 + vertex 0.973597 1.45786 2.6441 + endloop + endfacet + facet normal 0.16605 -0.0151417 0.986001 + outer loop + vertex 0.978255 1.45274 2.64321 + vertex 0.978279 1.45774 2.64329 + vertex 0.973579 1.45285 2.644 + endloop + endfacet + facet normal 0.165952 -0.0188593 0.985953 + outer loop + vertex 0.973571 1.44786 2.64391 + vertex 0.978255 1.45274 2.64321 + vertex 0.973579 1.45285 2.644 + endloop + endfacet + facet normal 0.16343 -0.0163729 0.986419 + outer loop + vertex 0.978231 1.44775 2.64314 + vertex 0.978255 1.45274 2.64321 + vertex 0.973571 1.44786 2.64391 + endloop + endfacet + facet normal 0.16333 -0.0201975 0.986365 + outer loop + vertex 0.973564 1.44286 2.64381 + vertex 0.978231 1.44775 2.64314 + vertex 0.973571 1.44786 2.64391 + endloop + endfacet + facet normal 0.0991062 -0.0202792 0.99487 + outer loop + vertex 0.973564 1.44286 2.64381 + vertex 0.973571 1.44786 2.64391 + vertex 0.968578 1.44276 2.6443 + endloop + endfacet + facet normal 0.0991724 -0.0237841 0.994786 + outer loop + vertex 0.968578 1.43776 2.64418 + vertex 0.973564 1.44286 2.64381 + vertex 0.968578 1.44276 2.6443 + endloop + endfacet + facet normal 0.0587269 -0.0238626 0.997989 + outer loop + vertex 0.968578 1.43776 2.64418 + vertex 0.968578 1.44276 2.6443 + vertex 0.963478 1.43765 2.64448 + endloop + endfacet + facet normal 0.0587902 -0.0270688 0.997903 + outer loop + vertex 0.963476 1.43266 2.64435 + vertex 0.968578 1.43776 2.64418 + vertex 0.963478 1.43765 2.64448 + endloop + endfacet + facet normal 0.041338 -0.027088 0.998778 + outer loop + vertex 0.963476 1.43266 2.64435 + vertex 0.963478 1.43765 2.64448 + vertex 0.95841 1.43263 2.64455 + endloop + endfacet + facet normal 0.0413533 -0.0301719 0.998689 + outer loop + vertex 0.958405 1.42763 2.6444 + vertex 0.963476 1.43266 2.64435 + vertex 0.95841 1.43263 2.64455 + endloop + endfacet + facet normal 0.036278 -0.0301724 0.998886 + outer loop + vertex 0.958405 1.42763 2.6444 + vertex 0.95841 1.43263 2.64455 + vertex 0.95341 1.42766 2.64459 + endloop + endfacet + facet normal 0.0362576 -0.033481 0.998781 + outer loop + vertex 0.953402 1.42266 2.64442 + vertex 0.958405 1.42763 2.6444 + vertex 0.95341 1.42766 2.64459 + endloop + endfacet + facet normal 0.036 -0.0334809 0.998791 + outer loop + vertex 0.953402 1.42266 2.64442 + vertex 0.95341 1.42766 2.64459 + vertex 0.948456 1.4227 2.6446 + endloop + endfacet + facet normal 0.0359741 -0.0364408 0.998688 + outer loop + vertex 0.94845 1.41771 2.64442 + vertex 0.953402 1.42266 2.64442 + vertex 0.948456 1.4227 2.6446 + endloop + endfacet + facet normal 0.0340092 -0.036441 0.998757 + outer loop + vertex 0.94845 1.41771 2.64442 + vertex 0.948456 1.4227 2.6446 + vertex 0.943516 1.41774 2.64459 + endloop + endfacet + facet normal 0.0343264 -0.036757 0.998735 + outer loop + vertex 0.943516 1.41774 2.64459 + vertex 0.948456 1.4227 2.6446 + vertex 0.94352 1.42273 2.64477 + endloop + endfacet + facet normal 0.0343507 -0.0333416 0.998854 + outer loop + vertex 0.948456 1.4227 2.6446 + vertex 0.948461 1.42769 2.64476 + vertex 0.94352 1.42273 2.64477 + endloop + endfacet + facet normal 0.0343047 -0.0332958 0.998857 + outer loop + vertex 0.94352 1.42273 2.64477 + vertex 0.948461 1.42769 2.64476 + vertex 0.943513 1.42771 2.64494 + endloop + endfacet + facet normal 0.0358605 -0.0333414 0.9988 + outer loop + vertex 0.948456 1.4227 2.6446 + vertex 0.95341 1.42766 2.64459 + vertex 0.948461 1.42769 2.64476 + endloop + endfacet + facet normal 0.0358886 -0.0297982 0.998911 + outer loop + vertex 0.95341 1.42766 2.64459 + vertex 0.953416 1.43265 2.64473 + vertex 0.948461 1.42769 2.64476 + endloop + endfacet + facet normal 0.0356703 -0.02958 0.998926 + outer loop + vertex 0.948461 1.42769 2.64476 + vertex 0.953416 1.43265 2.64473 + vertex 0.948451 1.43268 2.64491 + endloop + endfacet + facet normal 0.0356866 -0.0271319 0.998995 + outer loop + vertex 0.953416 1.43265 2.64473 + vertex 0.953407 1.43764 2.64487 + vertex 0.948451 1.43268 2.64491 + endloop + endfacet + facet normal 0.0358065 -0.0271316 0.99899 + outer loop + vertex 0.953416 1.43265 2.64473 + vertex 0.958414 1.43762 2.64469 + vertex 0.953407 1.43764 2.64487 + endloop + endfacet + facet normal 0.0359213 -0.027247 0.998983 + outer loop + vertex 0.95841 1.43263 2.64455 + vertex 0.958414 1.43762 2.64469 + vertex 0.953416 1.43265 2.64473 + endloop + endfacet + facet normal 0.0369309 -0.0341589 0.998734 + outer loop + vertex 0.958402 1.42264 2.64423 + vertex 0.958405 1.42763 2.6444 + vertex 0.953402 1.42266 2.64442 + endloop + endfacet + facet normal 0.0369136 -0.0369264 0.998636 + outer loop + vertex 0.953398 1.41767 2.64423 + vertex 0.958402 1.42264 2.64423 + vertex 0.953402 1.42266 2.64442 + endloop + endfacet + facet normal 0.0364601 -0.0369267 0.998653 + outer loop + vertex 0.953398 1.41767 2.64423 + vertex 0.953402 1.42266 2.64442 + vertex 0.94845 1.41771 2.64442 + endloop + endfacet + facet normal 0.0364417 -0.0388695 0.99858 + outer loop + vertex 0.948449 1.41272 2.64422 + vertex 0.953398 1.41767 2.64423 + vertex 0.94845 1.41771 2.64442 + endloop + endfacet + facet normal 0.0340675 -0.0388726 0.998663 + outer loop + vertex 0.948449 1.41272 2.64422 + vertex 0.94845 1.41771 2.64442 + vertex 0.943514 1.41276 2.64439 + endloop + endfacet + facet normal 0.0340573 -0.0399017 0.998623 + outer loop + vertex 0.943518 1.40777 2.64419 + vertex 0.948449 1.41272 2.64422 + vertex 0.943514 1.41276 2.64439 + endloop + endfacet + facet normal 0.0258531 -0.0399185 0.998868 + outer loop + vertex 0.943518 1.40777 2.64419 + vertex 0.943514 1.41276 2.64439 + vertex 0.938555 1.4078 2.64432 + endloop + endfacet + facet normal 0.0258396 -0.0417764 0.998793 + outer loop + vertex 0.938552 1.40283 2.64411 + vertex 0.943518 1.40777 2.64419 + vertex 0.938555 1.4078 2.64432 + endloop + endfacet + facet normal 0.00927502 -0.0417793 0.999084 + outer loop + vertex 0.938552 1.40283 2.64411 + vertex 0.938555 1.4078 2.64432 + vertex 0.933519 1.40279 2.64416 + endloop + endfacet + facet normal 0.0338609 -0.0397058 0.998638 + outer loop + vertex 0.948454 1.40772 2.64402 + vertex 0.948449 1.41272 2.64422 + vertex 0.943518 1.40777 2.64419 + endloop + endfacet + facet normal 0.0338517 -0.0405326 0.998605 + outer loop + vertex 0.943528 1.40279 2.64399 + vertex 0.948454 1.40772 2.64402 + vertex 0.943518 1.40777 2.64419 + endloop + endfacet + facet normal 0.0340679 -0.0407483 0.998588 + outer loop + vertex 0.948463 1.40274 2.64382 + vertex 0.948454 1.40772 2.64402 + vertex 0.943528 1.40279 2.64399 + endloop + endfacet + facet normal 0.0374372 -0.0407374 0.998468 + outer loop + vertex 0.948463 1.40274 2.64382 + vertex 0.953399 1.40768 2.64384 + vertex 0.948454 1.40772 2.64402 + endloop + endfacet + facet normal 0.0374404 -0.0404234 0.998481 + outer loop + vertex 0.953399 1.40768 2.64384 + vertex 0.953397 1.41267 2.64404 + vertex 0.948454 1.40772 2.64402 + endloop + endfacet + facet normal 0.0382496 -0.0404218 0.99845 + outer loop + vertex 0.953399 1.40768 2.64384 + vertex 0.958402 1.41265 2.64385 + vertex 0.953397 1.41267 2.64404 + endloop + endfacet + facet normal 0.0382529 -0.0398581 0.998473 + outer loop + vertex 0.958402 1.41265 2.64385 + vertex 0.958402 1.41764 2.64405 + vertex 0.953397 1.41267 2.64404 + endloop + endfacet + facet normal 0.0375468 -0.0391472 0.998528 + outer loop + vertex 0.953397 1.41267 2.64404 + vertex 0.958402 1.41764 2.64405 + vertex 0.953398 1.41767 2.64423 + endloop + endfacet + facet normal 0.0425033 -0.0398506 0.998301 + outer loop + vertex 0.958402 1.41265 2.64385 + vertex 0.963488 1.41768 2.64383 + vertex 0.958402 1.41764 2.64405 + endloop + endfacet + facet normal 0.042492 -0.0378774 0.998379 + outer loop + vertex 0.963488 1.41768 2.64383 + vertex 0.963483 1.42267 2.64402 + vertex 0.958402 1.41764 2.64405 + endloop + endfacet + facet normal 0.0421851 -0.0375671 0.998403 + outer loop + vertex 0.958402 1.41764 2.64405 + vertex 0.963483 1.42267 2.64402 + vertex 0.958402 1.42264 2.64423 + endloop + endfacet + facet normal 0.0421703 -0.0348287 0.998503 + outer loop + vertex 0.963483 1.42267 2.64402 + vertex 0.963479 1.42766 2.64419 + vertex 0.958402 1.42264 2.64423 + endloop + endfacet + facet normal 0.0586969 -0.0347846 0.99767 + outer loop + vertex 0.963483 1.42267 2.64402 + vertex 0.968588 1.42778 2.6439 + vertex 0.963479 1.42766 2.64419 + endloop + endfacet + facet normal 0.0586101 -0.0305427 0.997814 + outer loop + vertex 0.968588 1.42778 2.6439 + vertex 0.968583 1.43277 2.64405 + vertex 0.963479 1.42766 2.64419 + endloop + endfacet + facet normal 0.058339 -0.030271 0.997838 + outer loop + vertex 0.963479 1.42766 2.64419 + vertex 0.968583 1.43277 2.64405 + vertex 0.963476 1.43266 2.64435 + endloop + endfacet + facet normal 0.0951172 -0.0304202 0.995001 + outer loop + vertex 0.968588 1.42778 2.6439 + vertex 0.973562 1.43288 2.64358 + vertex 0.968583 1.43277 2.64405 + endloop + endfacet + facet normal 0.0949996 -0.0243807 0.995179 + outer loop + vertex 0.973562 1.43288 2.64358 + vertex 0.973561 1.43787 2.6437 + vertex 0.968583 1.43277 2.64405 + endloop + endfacet + facet normal 0.0970762 -0.0264245 0.994926 + outer loop + vertex 0.968583 1.43277 2.64405 + vertex 0.973561 1.43787 2.6437 + vertex 0.968578 1.43776 2.64418 + endloop + endfacet + facet normal 0.156328 -0.0241844 0.987409 + outer loop + vertex 0.973562 1.43288 2.64358 + vertex 0.978196 1.43776 2.64296 + vertex 0.973561 1.43787 2.6437 + endloop + endfacet + facet normal 0.15648 -0.018318 0.987511 + outer loop + vertex 0.978196 1.43776 2.64296 + vertex 0.978212 1.44275 2.64305 + vertex 0.973561 1.43787 2.6437 + endloop + endfacet + facet normal 0.159718 -0.0214794 0.986929 + outer loop + vertex 0.973561 1.43787 2.6437 + vertex 0.978212 1.44275 2.64305 + vertex 0.973564 1.44286 2.64381 + endloop + endfacet + facet normal 0.153383 -0.0213231 0.987937 + outer loop + vertex 0.978178 1.43277 2.64286 + vertex 0.978196 1.43776 2.64296 + vertex 0.973562 1.43288 2.64358 + endloop + endfacet + facet normal 0.153192 -0.0285107 0.987785 + outer loop + vertex 0.973555 1.42789 2.64344 + vertex 0.978178 1.43277 2.64286 + vertex 0.973562 1.43288 2.64358 + endloop + endfacet + facet normal 0.148719 -0.0241841 0.988584 + outer loop + vertex 0.978153 1.42778 2.64274 + vertex 0.978178 1.43277 2.64286 + vertex 0.973555 1.42789 2.64344 + endloop + endfacet + facet normal 0.148561 -0.0302523 0.98844 + outer loop + vertex 0.973551 1.4229 2.64328 + vertex 0.978153 1.42778 2.64274 + vertex 0.973555 1.42789 2.64344 + endloop + endfacet + facet normal 0.0898971 -0.0304273 0.995486 + outer loop + vertex 0.973551 1.4229 2.64328 + vertex 0.973555 1.42789 2.64344 + vertex 0.968592 1.42279 2.64373 + endloop + endfacet + facet normal 0.090019 -0.036655 0.995265 + outer loop + vertex 0.968595 1.4178 2.64354 + vertex 0.973551 1.4229 2.64328 + vertex 0.968592 1.42279 2.64373 + endloop + endfacet + facet normal 0.0569108 -0.0367658 0.997702 + outer loop + vertex 0.968595 1.4178 2.64354 + vertex 0.968592 1.42279 2.64373 + vertex 0.963488 1.41768 2.64383 + endloop + endfacet + facet normal 0.0569736 -0.0398308 0.997581 + outer loop + vertex 0.963492 1.41269 2.64363 + vertex 0.968595 1.4178 2.64354 + vertex 0.963488 1.41768 2.64383 + endloop + endfacet + facet normal 0.0550909 -0.0379468 0.99776 + outer loop + vertex 0.968601 1.4128 2.64335 + vertex 0.968595 1.4178 2.64354 + vertex 0.963492 1.41269 2.64363 + endloop + endfacet + facet normal 0.0551471 -0.0407428 0.997647 + outer loop + vertex 0.963497 1.40769 2.64343 + vertex 0.968601 1.4128 2.64335 + vertex 0.963492 1.41269 2.64363 + endloop + endfacet + facet normal 0.0422352 -0.0407805 0.998275 + outer loop + vertex 0.963497 1.40769 2.64343 + vertex 0.963492 1.41269 2.64363 + vertex 0.958403 1.40766 2.64364 + endloop + endfacet + facet normal 0.0422413 -0.0419968 0.998224 + outer loop + vertex 0.958405 1.40266 2.64343 + vertex 0.963497 1.40769 2.64343 + vertex 0.958403 1.40766 2.64364 + endloop + endfacet + facet normal 0.0394387 -0.0420027 0.998339 + outer loop + vertex 0.958405 1.40266 2.64343 + vertex 0.958403 1.40766 2.64364 + vertex 0.953402 1.40269 2.64363 + endloop + endfacet + facet normal 0.0394327 -0.0428209 0.998304 + outer loop + vertex 0.953408 1.3977 2.64341 + vertex 0.958405 1.40266 2.64343 + vertex 0.953402 1.40269 2.64363 + endloop + endfacet + facet normal 0.0385858 -0.0428234 0.998337 + outer loop + vertex 0.953408 1.3977 2.64341 + vertex 0.953402 1.40269 2.64363 + vertex 0.948475 1.39775 2.64361 + endloop + endfacet + facet normal 0.0385611 -0.0448637 0.998249 + outer loop + vertex 0.948492 1.39277 2.64338 + vertex 0.953408 1.3977 2.64341 + vertex 0.948475 1.39775 2.64361 + endloop + endfacet + facet normal 0.0332233 -0.0448906 0.998439 + outer loop + vertex 0.948492 1.39277 2.64338 + vertex 0.948475 1.39775 2.64361 + vertex 0.943549 1.39281 2.64355 + endloop + endfacet + facet normal 0.0331833 -0.0487698 0.998259 + outer loop + vertex 0.943561 1.38782 2.64331 + vertex 0.948492 1.39277 2.64338 + vertex 0.943549 1.39281 2.64355 + endloop + endfacet + facet normal 0.0200976 -0.0488181 0.998605 + outer loop + vertex 0.943561 1.38782 2.64331 + vertex 0.943549 1.39281 2.64355 + vertex 0.938519 1.38781 2.64341 + endloop + endfacet + facet normal 0.0221317 -0.0508615 0.99846 + outer loop + vertex 0.938519 1.38781 2.64341 + vertex 0.943549 1.39281 2.64355 + vertex 0.938535 1.39283 2.64366 + endloop + endfacet + facet normal 0.032172 -0.0477629 0.99834 + outer loop + vertex 0.94852 1.38779 2.64314 + vertex 0.948492 1.39277 2.64338 + vertex 0.943561 1.38782 2.64331 + endloop + endfacet + facet normal 0.0321435 -0.0516573 0.998147 + outer loop + vertex 0.943574 1.38284 2.64305 + vertex 0.94852 1.38779 2.64314 + vertex 0.943561 1.38782 2.64331 + endloop + endfacet + facet normal 0.0183681 -0.051711 0.998493 + outer loop + vertex 0.943574 1.38284 2.64305 + vertex 0.943561 1.38782 2.64331 + vertex 0.938503 1.38279 2.64314 + endloop + endfacet + facet normal 0.0312666 -0.050783 0.99822 + outer loop + vertex 0.948556 1.38284 2.64289 + vertex 0.94852 1.38779 2.64314 + vertex 0.943574 1.38284 2.64305 + endloop + endfacet + facet normal 0.0312581 -0.0547316 0.998012 + outer loop + vertex 0.943554 1.37787 2.64277 + vertex 0.948556 1.38284 2.64289 + vertex 0.943574 1.38284 2.64305 + endloop + endfacet + facet normal 0.0170673 -0.0546928 0.998357 + outer loop + vertex 0.943554 1.37787 2.64277 + vertex 0.943574 1.38284 2.64305 + vertex 0.938468 1.37777 2.64286 + endloop + endfacet + facet normal 0.0301086 -0.0535779 0.99811 + outer loop + vertex 0.948547 1.37789 2.64263 + vertex 0.948556 1.38284 2.64289 + vertex 0.943554 1.37787 2.64277 + endloop + endfacet + facet normal 0.0301194 -0.0577379 0.997877 + outer loop + vertex 0.943436 1.37285 2.64249 + vertex 0.948547 1.37789 2.64263 + vertex 0.943554 1.37787 2.64277 + endloop + endfacet + facet normal 0.0159427 -0.0574255 0.998222 + outer loop + vertex 0.943436 1.37285 2.64249 + vertex 0.943554 1.37787 2.64277 + vertex 0.938367 1.37273 2.64256 + endloop + endfacet + facet normal 0.0282085 -0.0558044 0.998043 + outer loop + vertex 0.948434 1.37287 2.64235 + vertex 0.948547 1.37789 2.64263 + vertex 0.943436 1.37285 2.64249 + endloop + endfacet + facet normal 0.0282217 -0.0601594 0.99779 + outer loop + vertex 0.943233 1.36772 2.64218 + vertex 0.948434 1.37287 2.64235 + vertex 0.943436 1.37285 2.64249 + endloop + endfacet + facet normal 0.0140368 -0.0596159 0.998123 + outer loop + vertex 0.943233 1.36772 2.64218 + vertex 0.943436 1.37285 2.64249 + vertex 0.938195 1.36763 2.64225 + endloop + endfacet + facet normal 0.0262434 -0.0581664 0.997962 + outer loop + vertex 0.948257 1.36773 2.64205 + vertex 0.948434 1.37287 2.64235 + vertex 0.943233 1.36772 2.64218 + endloop + endfacet + facet normal 0.0262465 -0.0612241 0.997779 + outer loop + vertex 0.943122 1.36253 2.64187 + vertex 0.948257 1.36773 2.64205 + vertex 0.943233 1.36772 2.64218 + endloop + endfacet + facet normal 0.0128567 -0.0609569 0.998058 + outer loop + vertex 0.943122 1.36253 2.64187 + vertex 0.943233 1.36772 2.64218 + vertex 0.938096 1.36247 2.64193 + endloop + endfacet + facet normal 0.0254221 -0.0604139 0.99785 + outer loop + vertex 0.948232 1.36257 2.64174 + vertex 0.948257 1.36773 2.64205 + vertex 0.943122 1.36253 2.64187 + endloop + endfacet + facet normal 0.0254329 -0.0619786 0.997753 + outer loop + vertex 0.943391 1.35747 2.64155 + vertex 0.948232 1.36257 2.64174 + vertex 0.943122 1.36253 2.64187 + endloop + endfacet + facet normal 0.0137463 -0.0626127 0.997943 + outer loop + vertex 0.943391 1.35747 2.64155 + vertex 0.943122 1.36253 2.64187 + vertex 0.938311 1.35742 2.64161 + endloop + endfacet + facet normal 0.0377215 -0.058539 0.997572 + outer loop + vertex 0.948257 1.36773 2.64205 + vertex 0.953399 1.37281 2.64216 + vertex 0.948434 1.37287 2.64235 + endloop + endfacet + facet normal 0.0377691 -0.0553283 0.997754 + outer loop + vertex 0.953399 1.37281 2.64216 + vertex 0.953491 1.37784 2.64243 + vertex 0.948434 1.37287 2.64235 + endloop + endfacet + facet normal 0.0437204 -0.0554231 0.997505 + outer loop + vertex 0.953399 1.37281 2.64216 + vertex 0.958475 1.3778 2.64221 + vertex 0.953491 1.37784 2.64243 + endloop + endfacet + facet normal 0.043734 -0.0541557 0.997574 + outer loop + vertex 0.958475 1.3778 2.64221 + vertex 0.95848 1.38277 2.64248 + vertex 0.953491 1.37784 2.64243 + endloop + endfacet + facet normal 0.0460055 -0.0541524 0.997472 + outer loop + vertex 0.958475 1.3778 2.64221 + vertex 0.963541 1.38282 2.64225 + vertex 0.95848 1.38277 2.64248 + endloop + endfacet + facet normal 0.0459954 -0.0528856 0.997541 + outer loop + vertex 0.963541 1.38282 2.64225 + vertex 0.963521 1.38777 2.64251 + vertex 0.95848 1.38277 2.64248 + endloop + endfacet + facet normal 0.0449521 -0.0518345 0.997643 + outer loop + vertex 0.95848 1.38277 2.64248 + vertex 0.963521 1.38777 2.64251 + vertex 0.958445 1.38771 2.64274 + endloop + endfacet + facet normal 0.042896 -0.0518536 0.997733 + outer loop + vertex 0.95848 1.38277 2.64248 + vertex 0.958445 1.38771 2.64274 + vertex 0.953496 1.38279 2.6427 + endloop + endfacet + facet normal 0.0428857 -0.053298 0.997657 + outer loop + vertex 0.953491 1.37784 2.64243 + vertex 0.95848 1.38277 2.64248 + vertex 0.953496 1.38279 2.6427 + endloop + endfacet + facet normal 0.0384776 -0.0533029 0.997837 + outer loop + vertex 0.953491 1.37784 2.64243 + vertex 0.953496 1.38279 2.6427 + vertex 0.948547 1.37789 2.64263 + endloop + endfacet + facet normal 0.0417453 -0.0506959 0.997841 + outer loop + vertex 0.953496 1.38279 2.6427 + vertex 0.958445 1.38771 2.64274 + vertex 0.953456 1.38774 2.64295 + endloop + endfacet + facet normal 0.0387812 -0.0507265 0.997959 + outer loop + vertex 0.953496 1.38279 2.6427 + vertex 0.953456 1.38774 2.64295 + vertex 0.948556 1.38284 2.64289 + endloop + endfacet + facet normal 0.0417599 -0.0488999 0.99793 + outer loop + vertex 0.958445 1.38771 2.64274 + vertex 0.958415 1.39267 2.64298 + vertex 0.953456 1.38774 2.64295 + endloop + endfacet + facet normal 0.0407362 -0.047871 0.998023 + outer loop + vertex 0.953456 1.38774 2.64295 + vertex 0.958415 1.39267 2.64298 + vertex 0.953422 1.39271 2.64319 + endloop + endfacet + facet normal 0.0388082 -0.0478876 0.998099 + outer loop + vertex 0.953456 1.38774 2.64295 + vertex 0.953422 1.39271 2.64319 + vertex 0.94852 1.38779 2.64314 + endloop + endfacet + facet normal 0.0407576 -0.0457366 0.998122 + outer loop + vertex 0.958415 1.39267 2.64298 + vertex 0.958406 1.39766 2.64321 + vertex 0.953422 1.39271 2.64319 + endloop + endfacet + facet normal 0.0399941 -0.0449685 0.998188 + outer loop + vertex 0.953422 1.39271 2.64319 + vertex 0.958406 1.39766 2.64321 + vertex 0.953408 1.3977 2.64341 + endloop + endfacet + facet normal 0.0426993 -0.0457292 0.998041 + outer loop + vertex 0.958415 1.39267 2.64298 + vertex 0.963493 1.39769 2.643 + vertex 0.958406 1.39766 2.64321 + endloop + endfacet + facet normal 0.0426927 -0.0436564 0.998134 + outer loop + vertex 0.963493 1.39769 2.643 + vertex 0.963496 1.40269 2.64321 + vertex 0.958406 1.39766 2.64321 + endloop + endfacet + facet normal 0.0424358 -0.0433961 0.998156 + outer loop + vertex 0.958406 1.39766 2.64321 + vertex 0.963496 1.40269 2.64321 + vertex 0.958405 1.40266 2.64343 + endloop + endfacet + facet normal 0.0528354 -0.043641 0.997649 + outer loop + vertex 0.963493 1.39769 2.643 + vertex 0.968597 1.40279 2.64295 + vertex 0.963496 1.40269 2.64321 + endloop + endfacet + facet normal 0.052787 -0.0409672 0.997765 + outer loop + vertex 0.968597 1.40279 2.64295 + vertex 0.968603 1.4078 2.64315 + vertex 0.963496 1.40269 2.64321 + endloop + endfacet + facet normal 0.0539871 -0.0421677 0.997651 + outer loop + vertex 0.963496 1.40269 2.64321 + vertex 0.968603 1.4078 2.64315 + vertex 0.963497 1.40769 2.64343 + endloop + endfacet + facet normal 0.0810788 -0.0409203 0.995867 + outer loop + vertex 0.968597 1.40279 2.64295 + vertex 0.973518 1.4079 2.64276 + vertex 0.968603 1.4078 2.64315 + endloop + endfacet + facet normal 0.0810104 -0.036718 0.996037 + outer loop + vertex 0.973518 1.4079 2.64276 + vertex 0.973533 1.41291 2.64294 + vertex 0.968603 1.4078 2.64315 + endloop + endfacet + facet normal 0.0838209 -0.0394446 0.9957 + outer loop + vertex 0.968603 1.4078 2.64315 + vertex 0.973533 1.41291 2.64294 + vertex 0.968601 1.4128 2.64335 + endloop + endfacet + facet normal 0.0837388 -0.034802 0.99588 + outer loop + vertex 0.973533 1.41291 2.64294 + vertex 0.973541 1.41791 2.64312 + vertex 0.968601 1.4128 2.64335 + endloop + endfacet + facet normal 0.140088 -0.0346812 0.989531 + outer loop + vertex 0.973533 1.41291 2.64294 + vertex 0.978083 1.4178 2.64247 + vertex 0.973541 1.41791 2.64312 + endloop + endfacet + facet normal 0.140261 -0.0285934 0.989702 + outer loop + vertex 0.978083 1.4178 2.64247 + vertex 0.978117 1.42279 2.64261 + vertex 0.973541 1.41791 2.64312 + endloop + endfacet + facet normal 0.145245 -0.0333522 0.988833 + outer loop + vertex 0.973541 1.41791 2.64312 + vertex 0.978117 1.42279 2.64261 + vertex 0.973551 1.4229 2.64328 + endloop + endfacet + facet normal 0.135989 -0.0307993 0.990232 + outer loop + vertex 0.978048 1.41279 2.64232 + vertex 0.978083 1.4178 2.64247 + vertex 0.973533 1.41291 2.64294 + endloop + endfacet + facet normal 0.135807 -0.0366567 0.990057 + outer loop + vertex 0.973518 1.4079 2.64276 + vertex 0.978048 1.41279 2.64232 + vertex 0.973533 1.41291 2.64294 + endloop + endfacet + facet normal 0.130503 -0.031664 0.990942 + outer loop + vertex 0.978017 1.40778 2.64216 + vertex 0.978048 1.41279 2.64232 + vertex 0.973518 1.4079 2.64276 + endloop + endfacet + facet normal 0.13032 -0.0380152 0.990743 + outer loop + vertex 0.973503 1.40291 2.64257 + vertex 0.978017 1.40778 2.64216 + vertex 0.973518 1.4079 2.64276 + endloop + endfacet + facet normal 0.124738 -0.0327757 0.991648 + outer loop + vertex 0.977986 1.40284 2.642 + vertex 0.978017 1.40778 2.64216 + vertex 0.973503 1.40291 2.64257 + endloop + endfacet + facet normal 0.124586 -0.040752 0.991372 + outer loop + vertex 0.973504 1.39796 2.64237 + vertex 0.977986 1.40284 2.642 + vertex 0.973503 1.40291 2.64257 + endloop + endfacet + facet normal 0.075739 -0.0409605 0.996286 + outer loop + vertex 0.973504 1.39796 2.64237 + vertex 0.973503 1.40291 2.64257 + vertex 0.968591 1.39781 2.64273 + endloop + endfacet + facet normal 0.0758966 -0.0468544 0.996014 + outer loop + vertex 0.968598 1.39286 2.6425 + vertex 0.973504 1.39796 2.64237 + vertex 0.968591 1.39781 2.64273 + endloop + endfacet + facet normal 0.0529037 -0.0469586 0.997495 + outer loop + vertex 0.968598 1.39286 2.6425 + vertex 0.968591 1.39781 2.64273 + vertex 0.9635 1.39271 2.64276 + endloop + endfacet + facet normal 0.0529848 -0.0500297 0.997341 + outer loop + vertex 0.963521 1.38777 2.64251 + vertex 0.968598 1.39286 2.6425 + vertex 0.9635 1.39271 2.64276 + endloop + endfacet + facet normal 0.05255 -0.049596 0.997386 + outer loop + vertex 0.968604 1.3879 2.64225 + vertex 0.968598 1.39286 2.6425 + vertex 0.963521 1.38777 2.64251 + endloop + endfacet + facet normal 0.0743033 -0.0495025 0.996006 + outer loop + vertex 0.968604 1.3879 2.64225 + vertex 0.973568 1.393 2.64214 + vertex 0.968598 1.39286 2.6425 + endloop + endfacet + facet normal 0.0691055 -0.0444295 0.99662 + outer loop + vertex 0.973509 1.38789 2.64191 + vertex 0.973568 1.393 2.64214 + vertex 0.968604 1.3879 2.64225 + endloop + endfacet + facet normal 0.0690728 -0.0510783 0.996303 + outer loop + vertex 0.968576 1.38289 2.642 + vertex 0.973509 1.38789 2.64191 + vertex 0.968604 1.3879 2.64225 + endloop + endfacet + facet normal 0.0508107 -0.0510332 0.997404 + outer loop + vertex 0.968576 1.38289 2.642 + vertex 0.968604 1.3879 2.64225 + vertex 0.963541 1.38282 2.64225 + endloop + endfacet + facet normal 0.0508519 -0.0547538 0.997204 + outer loop + vertex 0.963535 1.37782 2.64198 + vertex 0.968576 1.38289 2.642 + vertex 0.963541 1.38282 2.64225 + endloop + endfacet + facet normal 0.0487504 -0.0526645 0.997422 + outer loop + vertex 0.968543 1.37787 2.64173 + vertex 0.968576 1.38289 2.642 + vertex 0.963535 1.37782 2.64198 + endloop + endfacet + facet normal 0.0487736 -0.0566091 0.997204 + outer loop + vertex 0.963529 1.3728 2.64169 + vertex 0.968543 1.37787 2.64173 + vertex 0.963535 1.37782 2.64198 + endloop + endfacet + facet normal 0.0471591 -0.0566113 0.997282 + outer loop + vertex 0.963529 1.3728 2.64169 + vertex 0.963535 1.37782 2.64198 + vertex 0.958427 1.37275 2.64193 + endloop + endfacet + facet normal 0.0471713 -0.0585857 0.997167 + outer loop + vertex 0.95844 1.3677 2.64163 + vertex 0.963529 1.3728 2.64169 + vertex 0.958427 1.37275 2.64193 + endloop + endfacet + facet normal 0.0450156 -0.058597 0.997266 + outer loop + vertex 0.95844 1.3677 2.64163 + vertex 0.958427 1.37275 2.64193 + vertex 0.953305 1.36769 2.64186 + endloop + endfacet + facet normal 0.0450154 -0.0606809 0.997142 + outer loop + vertex 0.953425 1.36264 2.64155 + vertex 0.95844 1.3677 2.64163 + vertex 0.953305 1.36769 2.64186 + endloop + endfacet + facet normal 0.0373654 -0.0608827 0.997445 + outer loop + vertex 0.953425 1.36264 2.64155 + vertex 0.953305 1.36769 2.64186 + vertex 0.948232 1.36257 2.64174 + endloop + endfacet + facet normal 0.0369257 -0.0604481 0.997488 + outer loop + vertex 0.948232 1.36257 2.64174 + vertex 0.953305 1.36769 2.64186 + vertex 0.948257 1.36773 2.64205 + endloop + endfacet + facet normal 0.0453112 -0.0609736 0.99711 + outer loop + vertex 0.95868 1.36284 2.64132 + vertex 0.95844 1.3677 2.64163 + vertex 0.953425 1.36264 2.64155 + endloop + endfacet + facet normal 0.0453715 -0.0627494 0.996997 + outer loop + vertex 0.953914 1.35793 2.64123 + vertex 0.95868 1.36284 2.64132 + vertex 0.953425 1.36264 2.64155 + endloop + endfacet + facet normal 0.0384256 -0.0634859 0.997243 + outer loop + vertex 0.953914 1.35793 2.64123 + vertex 0.953425 1.36264 2.64155 + vertex 0.948616 1.35761 2.64142 + endloop + endfacet + facet normal 0.038436 -0.0636602 0.997231 + outer loop + vertex 0.949397 1.35287 2.64108 + vertex 0.953914 1.35793 2.64123 + vertex 0.948616 1.35761 2.64142 + endloop + endfacet + facet normal 0.0296445 -0.0651231 0.997437 + outer loop + vertex 0.949397 1.35287 2.64108 + vertex 0.948616 1.35761 2.64142 + vertex 0.944142 1.35288 2.64124 + endloop + endfacet + facet normal 0.0296592 -0.061998 0.997635 + outer loop + vertex 0.949397 1.35287 2.64108 + vertex 0.944142 1.35288 2.64124 + vertex 0.944875 1.34907 2.64098 + endloop + endfacet + facet normal 0.0303207 -0.0627847 0.997566 + outer loop + vertex 0.948127 1.34897 2.64088 + vertex 0.949397 1.35287 2.64108 + vertex 0.944875 1.34907 2.64098 + endloop + endfacet + facet normal 0.0302326 -0.065293 0.997408 + outer loop + vertex 0.948127 1.34897 2.64088 + vertex 0.944875 1.34907 2.64098 + vertex 0.94555 1.34646 2.64079 + endloop + endfacet + facet normal 0.0356473 -0.0708533 0.99685 + outer loop + vertex 0.948738 1.34647 2.64068 + vertex 0.948127 1.34897 2.64088 + vertex 0.94555 1.34646 2.64079 + endloop + endfacet + facet normal 0.0356388 -0.0767109 0.996416 + outer loop + vertex 0.94555 1.34646 2.64079 + vertex 0.943783 1.34264 2.64056 + vertex 0.948738 1.34647 2.64068 + endloop + endfacet + facet normal 0.0249843 -0.0718329 0.997104 + outer loop + vertex 0.94555 1.34646 2.64079 + vertex 0.941666 1.34548 2.64082 + vertex 0.943783 1.34264 2.64056 + endloop + endfacet + facet normal 0.0175245 -0.07736 0.996849 + outer loop + vertex 0.938082 1.34161 2.64058 + vertex 0.943783 1.34264 2.64056 + vertex 0.941666 1.34548 2.64082 + endloop + endfacet + facet normal 0.0113382 -0.0716596 0.997365 + outer loop + vertex 0.936746 1.34508 2.64084 + vertex 0.938082 1.34161 2.64058 + vertex 0.941666 1.34548 2.64082 + endloop + endfacet + facet normal 0.0110059 -0.0675888 0.997653 + outer loop + vertex 0.941666 1.34548 2.64082 + vertex 0.94026 1.34875 2.64105 + vertex 0.936746 1.34508 2.64084 + endloop + endfacet + facet normal 0.00662249 -0.0634172 0.997965 + outer loop + vertex 0.94026 1.34875 2.64105 + vertex 0.935253 1.34879 2.64109 + vertex 0.936746 1.34508 2.64084 + endloop + endfacet + facet normal 0.0200743 -0.0636988 0.997767 + outer loop + vertex 0.944875 1.34907 2.64098 + vertex 0.94026 1.34875 2.64105 + vertex 0.941666 1.34548 2.64082 + endloop + endfacet + facet normal -0.00635661 -0.078443 0.996898 + outer loop + vertex 0.932794 1.34151 2.64054 + vertex 0.938082 1.34161 2.64058 + vertex 0.936746 1.34508 2.64084 + endloop + endfacet + facet normal -0.00630341 -0.0810444 0.996691 + outer loop + vertex 0.933538 1.33739 2.64021 + vertex 0.938082 1.34161 2.64058 + vertex 0.932794 1.34151 2.64054 + endloop + endfacet + facet normal -0.00668755 -0.0806333 0.996721 + outer loop + vertex 0.938746 1.33766 2.64026 + vertex 0.938082 1.34161 2.64058 + vertex 0.933538 1.33739 2.64021 + endloop + endfacet + facet normal -0.00649974 -0.0842802 0.996421 + outer loop + vertex 0.933637 1.33285 2.63982 + vertex 0.938746 1.33766 2.64026 + vertex 0.933538 1.33739 2.64021 + endloop + endfacet + facet normal -0.0407 -0.0849536 0.995553 + outer loop + vertex 0.933637 1.33285 2.63982 + vertex 0.933538 1.33739 2.64021 + vertex 0.92855 1.33277 2.63961 + endloop + endfacet + facet normal -0.0406724 -0.0863413 0.995435 + outer loop + vertex 0.928418 1.32786 2.63918 + vertex 0.933637 1.33285 2.63982 + vertex 0.92855 1.33277 2.63961 + endloop + endfacet + facet normal -0.0381019 -0.087739 0.995415 + outer loop + vertex 0.92855 1.33277 2.63961 + vertex 0.933538 1.33739 2.64021 + vertex 0.928273 1.33742 2.64001 + endloop + endfacet + facet normal -0.0122591 -0.0781953 0.996863 + outer loop + vertex 0.938691 1.33299 2.6399 + vertex 0.938746 1.33766 2.64026 + vertex 0.933637 1.33285 2.63982 + endloop + endfacet + facet normal -0.0121195 -0.0833205 0.996449 + outer loop + vertex 0.933447 1.3279 2.63941 + vertex 0.938691 1.33299 2.6399 + vertex 0.933637 1.33285 2.63982 + endloop + endfacet + facet normal -0.0171343 -0.07818 0.996792 + outer loop + vertex 0.9385 1.32798 2.6395 + vertex 0.938691 1.33299 2.6399 + vertex 0.933447 1.3279 2.63941 + endloop + endfacet + facet normal -0.0170275 -0.084483 0.996279 + outer loop + vertex 0.933288 1.32278 2.63897 + vertex 0.9385 1.32798 2.6395 + vertex 0.933447 1.3279 2.63941 + endloop + endfacet + facet normal -0.0197601 -0.0817648 0.996456 + outer loop + vertex 0.938388 1.32288 2.63908 + vertex 0.9385 1.32798 2.6395 + vertex 0.933288 1.32278 2.63897 + endloop + endfacet + facet normal -0.0196199 -0.0880617 0.995922 + outer loop + vertex 0.933248 1.31767 2.63852 + vertex 0.938388 1.32288 2.63908 + vertex 0.933288 1.32278 2.63897 + endloop + endfacet + facet normal -0.0209273 -0.0867807 0.996008 + outer loop + vertex 0.938344 1.31781 2.63864 + vertex 0.938388 1.32288 2.63908 + vertex 0.933248 1.31767 2.63852 + endloop + endfacet + facet normal -0.0207727 -0.0919442 0.995547 + outer loop + vertex 0.933309 1.31269 2.63806 + vertex 0.938344 1.31781 2.63864 + vertex 0.933248 1.31767 2.63852 + endloop + endfacet + facet normal -0.0230914 -0.0896849 0.995702 + outer loop + vertex 0.938298 1.31279 2.63819 + vertex 0.938344 1.31781 2.63864 + vertex 0.933309 1.31269 2.63806 + endloop + endfacet + facet normal -0.0230206 -0.092716 0.995426 + outer loop + vertex 0.933466 1.30789 2.63762 + vertex 0.938298 1.31279 2.63819 + vertex 0.933309 1.31269 2.63806 + endloop + endfacet + facet normal -0.0245461 -0.0912252 0.995528 + outer loop + vertex 0.938217 1.30774 2.63772 + vertex 0.938298 1.31279 2.63819 + vertex 0.933466 1.30789 2.63762 + endloop + endfacet + facet normal -0.0245895 -0.0927311 0.995388 + outer loop + vertex 0.93353 1.30304 2.63717 + vertex 0.938217 1.30774 2.63772 + vertex 0.933466 1.30789 2.63762 + endloop + endfacet + facet normal -0.0280649 -0.0892915 0.99561 + outer loop + vertex 0.938222 1.30263 2.63726 + vertex 0.938217 1.30774 2.63772 + vertex 0.93353 1.30304 2.63717 + endloop + endfacet + facet normal -0.0279224 -0.0876083 0.995764 + outer loop + vertex 0.934021 1.29811 2.63675 + vertex 0.938222 1.30263 2.63726 + vertex 0.93353 1.30304 2.63717 + endloop + endfacet + facet normal -0.0284216 -0.0871482 0.99579 + outer loop + vertex 0.938595 1.29777 2.63685 + vertex 0.938222 1.30263 2.63726 + vertex 0.934021 1.29811 2.63675 + endloop + endfacet + facet normal -0.0280337 -0.0817365 0.99626 + outer loop + vertex 0.935356 1.29423 2.63647 + vertex 0.938595 1.29777 2.63685 + vertex 0.934021 1.29811 2.63675 + endloop + endfacet + facet normal -0.0210944 -0.0880426 0.995893 + outer loop + vertex 0.939219 1.29332 2.63647 + vertex 0.938595 1.29777 2.63685 + vertex 0.935356 1.29423 2.63647 + endloop + endfacet + facet normal -0.0230032 -0.0961282 0.995103 + outer loop + vertex 0.935116 1.29011 2.63606 + vertex 0.939219 1.29332 2.63647 + vertex 0.935356 1.29423 2.63647 + endloop + endfacet + facet normal -0.0236848 -0.0952646 0.99517 + outer loop + vertex 0.940272 1.28926 2.6361 + vertex 0.939219 1.29332 2.63647 + vertex 0.935116 1.29011 2.63606 + endloop + endfacet + facet normal -0.0242364 -0.0986329 0.994829 + outer loop + vertex 0.940272 1.28926 2.6361 + vertex 0.935116 1.29011 2.63606 + vertex 0.936728 1.28591 2.63569 + endloop + endfacet + facet normal -0.0192013 -0.103907 0.994402 + outer loop + vertex 0.941702 1.2856 2.63575 + vertex 0.940272 1.28926 2.6361 + vertex 0.936728 1.28591 2.63569 + endloop + endfacet + facet normal -0.019744 -0.11275 0.993427 + outer loop + vertex 0.936728 1.28591 2.63569 + vertex 0.937756 1.28192 2.63525 + vertex 0.941702 1.2856 2.63575 + endloop + endfacet + facet normal -0.0173632 -0.115269 0.993183 + outer loop + vertex 0.937756 1.28192 2.63525 + vertex 0.943003 1.28204 2.63536 + vertex 0.941702 1.2856 2.63575 + endloop + endfacet + facet normal 0.00982896 -0.105462 0.994375 + outer loop + vertex 0.941702 1.2856 2.63575 + vertex 0.943003 1.28204 2.63536 + vertex 0.946558 1.28597 2.63574 + endloop + endfacet + facet normal 0.00931034 -0.0987102 0.995073 + outer loop + vertex 0.946558 1.28597 2.63574 + vertex 0.945191 1.28921 2.63607 + vertex 0.941702 1.2856 2.63575 + endloop + endfacet + facet normal 0.0255256 -0.0919092 0.99544 + outer loop + vertex 0.949754 1.28948 2.63598 + vertex 0.945191 1.28921 2.63607 + vertex 0.946558 1.28597 2.63574 + endloop + endfacet + facet normal 0.0274755 -0.0936706 0.995224 + outer loop + vertex 0.950419 1.28688 2.63572 + vertex 0.949754 1.28948 2.63598 + vertex 0.946558 1.28597 2.63574 + endloop + endfacet + facet normal 0.0295531 -0.102511 0.994293 + outer loop + vertex 0.950419 1.28688 2.63572 + vertex 0.946558 1.28597 2.63574 + vertex 0.948689 1.283 2.63537 + endloop + endfacet + facet normal 0.041789 -0.107873 0.993286 + outer loop + vertex 0.950419 1.28688 2.63572 + vertex 0.948689 1.283 2.63537 + vertex 0.953649 1.28678 2.63557 + endloop + endfacet + facet normal 0.0422148 -0.0966782 0.99442 + outer loop + vertex 0.953649 1.28678 2.63557 + vertex 0.953002 1.2893 2.63584 + vertex 0.950419 1.28688 2.63572 + endloop + endfacet + facet normal 0.0455241 -0.0958248 0.994357 + outer loop + vertex 0.953002 1.2893 2.63584 + vertex 0.953649 1.28678 2.63557 + vertex 0.956673 1.2905 2.63579 + endloop + endfacet + facet normal 0.043446 -0.0894222 0.995046 + outer loop + vertex 0.956673 1.2905 2.63579 + vertex 0.954319 1.29311 2.63613 + vertex 0.953002 1.2893 2.63584 + endloop + endfacet + facet normal 0.037292 -0.0873284 0.995481 + outer loop + vertex 0.953002 1.2893 2.63584 + vertex 0.954319 1.29311 2.63613 + vertex 0.949754 1.28948 2.63598 + endloop + endfacet + facet normal 0.0436402 -0.0892481 0.995053 + outer loop + vertex 0.959615 1.29427 2.636 + vertex 0.954319 1.29311 2.63613 + vertex 0.956673 1.2905 2.63579 + endloop + endfacet + facet normal 0.0455987 -0.0907651 0.994828 + outer loop + vertex 0.960403 1.29175 2.63574 + vertex 0.959615 1.29427 2.636 + vertex 0.956673 1.2905 2.63579 + endloop + endfacet + facet normal 0.0471849 -0.0955046 0.99431 + outer loop + vertex 0.960403 1.29175 2.63574 + vertex 0.956673 1.2905 2.63579 + vertex 0.958732 1.28786 2.63544 + endloop + endfacet + facet normal 0.0500845 -0.0967294 0.99405 + outer loop + vertex 0.960403 1.29175 2.63574 + vertex 0.958732 1.28786 2.63544 + vertex 0.963602 1.29176 2.63558 + endloop + endfacet + facet normal 0.0500962 -0.0920081 0.994497 + outer loop + vertex 0.963602 1.29176 2.63558 + vertex 0.962983 1.29431 2.63584 + vertex 0.960403 1.29175 2.63574 + endloop + endfacet + facet normal 0.0515703 -0.0916459 0.994455 + outer loop + vertex 0.962983 1.29431 2.63584 + vertex 0.963602 1.29176 2.63558 + vertex 0.966642 1.2956 2.63577 + endloop + endfacet + facet normal 0.0506606 -0.0890509 0.994738 + outer loop + vertex 0.966642 1.2956 2.63577 + vertex 0.964333 1.29819 2.63612 + vertex 0.962983 1.29431 2.63584 + endloop + endfacet + facet normal 0.0480644 -0.0881635 0.994946 + outer loop + vertex 0.962983 1.29431 2.63584 + vertex 0.964333 1.29819 2.63612 + vertex 0.959615 1.29427 2.636 + endloop + endfacet + facet normal 0.0478846 -0.0879482 0.994973 + outer loop + vertex 0.964333 1.29819 2.63612 + vertex 0.958895 1.29805 2.63637 + vertex 0.959615 1.29427 2.636 + endloop + endfacet + facet normal 0.0479262 -0.0899324 0.994794 + outer loop + vertex 0.964333 1.29819 2.63612 + vertex 0.963664 1.30288 2.63658 + vertex 0.958895 1.29805 2.63637 + endloop + endfacet + facet normal 0.0466457 -0.0886736 0.994968 + outer loop + vertex 0.958895 1.29805 2.63637 + vertex 0.963664 1.30288 2.63658 + vertex 0.95838 1.30274 2.63681 + endloop + endfacet + facet normal 0.0425256 -0.0891406 0.995111 + outer loop + vertex 0.958895 1.29805 2.63637 + vertex 0.95838 1.30274 2.63681 + vertex 0.953567 1.29777 2.63657 + endloop + endfacet + facet normal 0.0424573 -0.0877891 0.995234 + outer loop + vertex 0.954319 1.29311 2.63613 + vertex 0.958895 1.29805 2.63637 + vertex 0.953567 1.29777 2.63657 + endloop + endfacet + facet normal 0.0362588 -0.0888046 0.995389 + outer loop + vertex 0.954319 1.29311 2.63613 + vertex 0.953567 1.29777 2.63657 + vertex 0.949072 1.29318 2.63633 + endloop + endfacet + facet normal 0.0363028 -0.0860899 0.995626 + outer loop + vertex 0.954319 1.29311 2.63613 + vertex 0.949072 1.29318 2.63633 + vertex 0.949754 1.28948 2.63598 + endloop + endfacet + facet normal 0.0418097 -0.0884523 0.995203 + outer loop + vertex 0.953567 1.29777 2.63657 + vertex 0.95838 1.30274 2.63681 + vertex 0.953209 1.30266 2.63702 + endloop + endfacet + facet normal 0.0341341 -0.0890369 0.995443 + outer loop + vertex 0.953567 1.29777 2.63657 + vertex 0.953209 1.30266 2.63702 + vertex 0.94836 1.29762 2.63674 + endloop + endfacet + facet normal 0.0340745 -0.0866785 0.995653 + outer loop + vertex 0.949072 1.29318 2.63633 + vertex 0.953567 1.29777 2.63657 + vertex 0.94836 1.29762 2.63674 + endloop + endfacet + facet normal 0.0230037 -0.0884675 0.995813 + outer loop + vertex 0.949072 1.29318 2.63633 + vertex 0.94836 1.29762 2.63674 + vertex 0.944044 1.29307 2.63643 + endloop + endfacet + facet normal 0.0229509 -0.0858401 0.996045 + outer loop + vertex 0.945191 1.28921 2.63607 + vertex 0.949072 1.29318 2.63633 + vertex 0.944044 1.29307 2.63643 + endloop + endfacet + facet normal 0.00501368 -0.0911594 0.995824 + outer loop + vertex 0.945191 1.28921 2.63607 + vertex 0.944044 1.29307 2.63643 + vertex 0.940272 1.28926 2.6361 + endloop + endfacet + facet normal 0.0331592 -0.0881048 0.995559 + outer loop + vertex 0.94836 1.29762 2.63674 + vertex 0.953209 1.30266 2.63702 + vertex 0.948119 1.30258 2.63718 + endloop + endfacet + facet normal 0.0198805 -0.088778 0.995853 + outer loop + vertex 0.94836 1.29762 2.63674 + vertex 0.948119 1.30258 2.63718 + vertex 0.943336 1.29757 2.63683 + endloop + endfacet + facet normal 0.0198551 -0.0855038 0.99614 + outer loop + vertex 0.944044 1.29307 2.63643 + vertex 0.94836 1.29762 2.63674 + vertex 0.943336 1.29757 2.63683 + endloop + endfacet + facet normal 0.0023986 -0.0882434 0.996096 + outer loop + vertex 0.944044 1.29307 2.63643 + vertex 0.943336 1.29757 2.63683 + vertex 0.939219 1.29332 2.63647 + endloop + endfacet + facet normal 0.0181833 -0.0871685 0.996028 + outer loop + vertex 0.943336 1.29757 2.63683 + vertex 0.948119 1.30258 2.63718 + vertex 0.943108 1.30253 2.63727 + endloop + endfacet + facet normal -0.000854473 -0.0880486 0.996116 + outer loop + vertex 0.943336 1.29757 2.63683 + vertex 0.943108 1.30253 2.63727 + vertex 0.938595 1.29777 2.63685 + endloop + endfacet + facet normal 0.0181976 -0.0890767 0.995859 + outer loop + vertex 0.948119 1.30258 2.63718 + vertex 0.948236 1.30775 2.63765 + vertex 0.943108 1.30253 2.63727 + endloop + endfacet + facet normal 0.0182556 -0.0891332 0.995852 + outer loop + vertex 0.943108 1.30253 2.63727 + vertex 0.948236 1.30775 2.63765 + vertex 0.943199 1.3077 2.63773 + endloop + endfacet + facet normal -0.00384389 -0.0887617 0.996045 + outer loop + vertex 0.943108 1.30253 2.63727 + vertex 0.943199 1.3077 2.63773 + vertex 0.938222 1.30263 2.63726 + endloop + endfacet + facet normal 0.0182533 -0.0888677 0.995876 + outer loop + vertex 0.948236 1.30775 2.63765 + vertex 0.948437 1.3129 2.6381 + vertex 0.943199 1.3077 2.63773 + endloop + endfacet + facet normal 0.0195335 -0.0901471 0.995737 + outer loop + vertex 0.943199 1.3077 2.63773 + vertex 0.948437 1.3129 2.6381 + vertex 0.943366 1.31285 2.6382 + endloop + endfacet + facet normal -0.00328897 -0.0894303 0.995988 + outer loop + vertex 0.943199 1.3077 2.63773 + vertex 0.943366 1.31285 2.6382 + vertex 0.938217 1.30774 2.63772 + endloop + endfacet + facet normal 0.0195024 -0.0870055 0.996017 + outer loop + vertex 0.948437 1.3129 2.6381 + vertex 0.948545 1.31794 2.63854 + vertex 0.943366 1.31285 2.6382 + endloop + endfacet + facet normal 0.0208662 -0.0883813 0.995868 + outer loop + vertex 0.943366 1.31285 2.6382 + vertex 0.948545 1.31794 2.63854 + vertex 0.943459 1.3179 2.63864 + endloop + endfacet + facet normal -0.00113455 -0.0879986 0.99612 + outer loop + vertex 0.943366 1.31285 2.6382 + vertex 0.943459 1.3179 2.63864 + vertex 0.938298 1.31279 2.63819 + endloop + endfacet + facet normal 0.0208214 -0.0822069 0.996398 + outer loop + vertex 0.948545 1.31794 2.63854 + vertex 0.948536 1.32292 2.63895 + vertex 0.943459 1.3179 2.63864 + endloop + endfacet + facet normal 0.0227636 -0.0841576 0.996192 + outer loop + vertex 0.943459 1.3179 2.63864 + vertex 0.948536 1.32292 2.63895 + vertex 0.943478 1.32292 2.63907 + endloop + endfacet + facet normal 0.000694277 -0.0840964 0.996457 + outer loop + vertex 0.943459 1.3179 2.63864 + vertex 0.943478 1.32292 2.63907 + vertex 0.938344 1.31781 2.63864 + endloop + endfacet + facet normal 0.0227794 -0.0779281 0.996699 + outer loop + vertex 0.948536 1.32292 2.63895 + vertex 0.948499 1.32793 2.63934 + vertex 0.943478 1.32292 2.63907 + endloop + endfacet + facet normal 0.0246582 -0.0798022 0.996506 + outer loop + vertex 0.943478 1.32292 2.63907 + vertex 0.948499 1.32793 2.63934 + vertex 0.943513 1.32799 2.63947 + endloop + endfacet + facet normal 0.00355326 -0.079683 0.996814 + outer loop + vertex 0.943478 1.32292 2.63907 + vertex 0.943513 1.32799 2.63947 + vertex 0.938388 1.32288 2.63908 + endloop + endfacet + facet normal 0.0247411 -0.0736943 0.996974 + outer loop + vertex 0.948499 1.32793 2.63934 + vertex 0.948539 1.33299 2.63972 + vertex 0.943513 1.32799 2.63947 + endloop + endfacet + facet normal 0.0268992 -0.0758531 0.996756 + outer loop + vertex 0.943513 1.32799 2.63947 + vertex 0.948539 1.33299 2.63972 + vertex 0.943646 1.33304 2.63985 + endloop + endfacet + facet normal 0.00622514 -0.0753379 0.997139 + outer loop + vertex 0.943513 1.32799 2.63947 + vertex 0.943646 1.33304 2.63985 + vertex 0.9385 1.32798 2.6395 + endloop + endfacet + facet normal 0.0269572 -0.0713816 0.997085 + outer loop + vertex 0.948539 1.33299 2.63972 + vertex 0.948694 1.33798 2.64007 + vertex 0.943646 1.33304 2.63985 + endloop + endfacet + facet normal 0.029801 -0.0742768 0.996792 + outer loop + vertex 0.943646 1.33304 2.63985 + vertex 0.948694 1.33798 2.64007 + vertex 0.94382 1.33792 2.64021 + endloop + endfacet + facet normal 0.0100028 -0.0736034 0.997237 + outer loop + vertex 0.943646 1.33304 2.63985 + vertex 0.94382 1.33792 2.64021 + vertex 0.938691 1.33299 2.6399 + endloop + endfacet + facet normal 0.0297707 -0.0712178 0.997016 + outer loop + vertex 0.948694 1.33798 2.64007 + vertex 0.948831 1.34267 2.6404 + vertex 0.94382 1.33792 2.64021 + endloop + endfacet + facet normal 0.0319796 -0.0735363 0.99678 + outer loop + vertex 0.94382 1.33792 2.64021 + vertex 0.948831 1.34267 2.6404 + vertex 0.943783 1.34264 2.64056 + endloop + endfacet + facet normal 0.0145063 -0.0737015 0.997175 + outer loop + vertex 0.94382 1.33792 2.64021 + vertex 0.943783 1.34264 2.64056 + vertex 0.938746 1.33766 2.64026 + endloop + endfacet + facet normal 0.031972 -0.0719837 0.996893 + outer loop + vertex 0.948738 1.34647 2.64068 + vertex 0.943783 1.34264 2.64056 + vertex 0.948831 1.34267 2.6404 + endloop + endfacet + facet normal 0.0411487 -0.0717361 0.996574 + outer loop + vertex 0.948831 1.34267 2.6404 + vertex 0.953716 1.34768 2.64056 + vertex 0.948738 1.34647 2.64068 + endloop + endfacet + facet normal 0.0409358 -0.0708525 0.996646 + outer loop + vertex 0.948738 1.34647 2.64068 + vertex 0.953716 1.34768 2.64056 + vertex 0.951726 1.35027 2.64082 + endloop + endfacet + facet normal 0.0431234 -0.069176 0.996672 + outer loop + vertex 0.955351 1.35161 2.64076 + vertex 0.951726 1.35027 2.64082 + vertex 0.953716 1.34768 2.64056 + endloop + endfacet + facet normal 0.0442535 -0.0696422 0.99659 + outer loop + vertex 0.955351 1.35161 2.64076 + vertex 0.953716 1.34768 2.64056 + vertex 0.958471 1.35168 2.64063 + endloop + endfacet + facet normal 0.0441561 -0.0648151 0.99692 + outer loop + vertex 0.958471 1.35168 2.64063 + vertex 0.957861 1.35422 2.64082 + vertex 0.955351 1.35161 2.64076 + endloop + endfacet + facet normal 0.0445731 -0.0652148 0.996875 + outer loop + vertex 0.957861 1.35422 2.64082 + vertex 0.954595 1.35412 2.64096 + vertex 0.955351 1.35161 2.64076 + endloop + endfacet + facet normal 0.044501 -0.0626292 0.997044 + outer loop + vertex 0.957861 1.35422 2.64082 + vertex 0.95922 1.35816 2.64101 + vertex 0.954595 1.35412 2.64096 + endloop + endfacet + facet normal 0.045285 -0.0635261 0.996952 + outer loop + vertex 0.95922 1.35816 2.64101 + vertex 0.953914 1.35793 2.64123 + vertex 0.954595 1.35412 2.64096 + endloop + endfacet + facet normal 0.0442651 -0.0625485 0.99706 + outer loop + vertex 0.96144 1.35563 2.64075 + vertex 0.95922 1.35816 2.64101 + vertex 0.957861 1.35422 2.64082 + endloop + endfacet + facet normal 0.0451067 -0.0618094 0.997068 + outer loop + vertex 0.964302 1.35962 2.64087 + vertex 0.95922 1.35816 2.64101 + vertex 0.96144 1.35563 2.64075 + endloop + endfacet + facet normal 0.040212 -0.0583134 0.997488 + outer loop + vertex 0.96514 1.35724 2.64069 + vertex 0.964302 1.35962 2.64087 + vertex 0.96144 1.35563 2.64075 + endloop + endfacet + facet normal 0.0403405 -0.0586102 0.997466 + outer loop + vertex 0.96514 1.35724 2.64069 + vertex 0.96144 1.35563 2.64075 + vertex 0.963518 1.35302 2.64051 + endloop + endfacet + facet normal 0.0400993 -0.058518 0.997481 + outer loop + vertex 0.96514 1.35724 2.64069 + vertex 0.963518 1.35302 2.64051 + vertex 0.968971 1.35799 2.64058 + endloop + endfacet + facet normal 0.0403246 -0.0596774 0.997403 + outer loop + vertex 0.968971 1.35799 2.64058 + vertex 0.967487 1.36005 2.64077 + vertex 0.96514 1.35724 2.64069 + endloop + endfacet + facet normal 0.0409634 -0.0592174 0.997404 + outer loop + vertex 0.970352 1.36187 2.64076 + vertex 0.967487 1.36005 2.64077 + vertex 0.968971 1.35799 2.64058 + endloop + endfacet + facet normal 0.0701272 -0.0694736 0.995116 + outer loop + vertex 0.970352 1.36187 2.64076 + vertex 0.968971 1.35799 2.64058 + vertex 0.974116 1.36295 2.64057 + endloop + endfacet + facet normal 0.0729331 -0.0794754 0.994165 + outer loop + vertex 0.974116 1.36295 2.64057 + vertex 0.972416 1.36477 2.64084 + vertex 0.970352 1.36187 2.64076 + endloop + endfacet + facet normal 0.0420787 -0.0575984 0.997453 + outer loop + vertex 0.972416 1.36477 2.64084 + vertex 0.968661 1.36372 2.64094 + vertex 0.970352 1.36187 2.64076 + endloop + endfacet + facet normal 0.0406243 -0.0523885 0.9978 + outer loop + vertex 0.972416 1.36477 2.64084 + vertex 0.973306 1.36848 2.641 + vertex 0.968661 1.36372 2.64094 + endloop + endfacet + facet normal 0.0456288 -0.0572662 0.997316 + outer loop + vertex 0.973306 1.36848 2.641 + vertex 0.968602 1.36819 2.64119 + vertex 0.968661 1.36372 2.64094 + endloop + endfacet + facet normal 0.0416168 -0.0573293 0.997488 + outer loop + vertex 0.968661 1.36372 2.64094 + vertex 0.968602 1.36819 2.64119 + vertex 0.963844 1.36331 2.64111 + endloop + endfacet + facet normal 0.0419472 -0.0613565 0.997234 + outer loop + vertex 0.968661 1.36372 2.64094 + vertex 0.963844 1.36331 2.64111 + vertex 0.964302 1.35962 2.64087 + endloop + endfacet + facet normal 0.039091 -0.0583219 0.997532 + outer loop + vertex 0.967487 1.36005 2.64077 + vertex 0.968661 1.36372 2.64094 + vertex 0.964302 1.35962 2.64087 + endloop + endfacet + facet normal 0.0446635 -0.0602966 0.997181 + outer loop + vertex 0.963844 1.36331 2.64111 + vertex 0.968602 1.36819 2.64119 + vertex 0.963608 1.36789 2.6414 + endloop + endfacet + facet normal 0.0463356 -0.0602059 0.99711 + outer loop + vertex 0.963844 1.36331 2.64111 + vertex 0.963608 1.36789 2.6414 + vertex 0.95868 1.36284 2.64132 + endloop + endfacet + facet normal 0.046539 -0.0624792 0.996961 + outer loop + vertex 0.95922 1.35816 2.64101 + vertex 0.963844 1.36331 2.64111 + vertex 0.95868 1.36284 2.64132 + endloop + endfacet + facet normal 0.0444206 -0.0560828 0.997437 + outer loop + vertex 0.968602 1.36819 2.64119 + vertex 0.968541 1.37292 2.64146 + vertex 0.963608 1.36789 2.6414 + endloop + endfacet + facet normal 0.0467534 -0.0583674 0.9972 + outer loop + vertex 0.963608 1.36789 2.6414 + vertex 0.968541 1.37292 2.64146 + vertex 0.963529 1.3728 2.64169 + endloop + endfacet + facet normal 0.0508233 -0.055984 0.997137 + outer loop + vertex 0.968602 1.36819 2.64119 + vertex 0.973171 1.37297 2.64123 + vertex 0.968541 1.37292 2.64146 + endloop + endfacet + facet normal 0.0507594 -0.0489029 0.997513 + outer loop + vertex 0.973171 1.37297 2.64123 + vertex 0.973229 1.37775 2.64146 + vertex 0.968541 1.37292 2.64146 + endloop + endfacet + facet normal 0.0565278 -0.0545054 0.996912 + outer loop + vertex 0.968541 1.37292 2.64146 + vertex 0.973229 1.37775 2.64146 + vertex 0.968543 1.37787 2.64173 + endloop + endfacet + facet normal 0.0567413 -0.0469723 0.997283 + outer loop + vertex 0.973229 1.37775 2.64146 + vertex 0.973323 1.38274 2.64169 + vertex 0.968543 1.37787 2.64173 + endloop + endfacet + facet normal 0.0944904 -0.0475458 0.99439 + outer loop + vertex 0.973229 1.37775 2.64146 + vertex 0.97754 1.38214 2.64126 + vertex 0.973323 1.38274 2.64169 + endloop + endfacet + facet normal 0.0958898 -0.0378295 0.994673 + outer loop + vertex 0.97754 1.38214 2.64126 + vertex 0.977803 1.38724 2.64143 + vertex 0.973323 1.38274 2.64169 + endloop + endfacet + facet normal 0.104325 -0.0462885 0.993465 + outer loop + vertex 0.973323 1.38274 2.64169 + vertex 0.977803 1.38724 2.64143 + vertex 0.973509 1.38789 2.64191 + endloop + endfacet + facet normal 0.106006 -0.0353502 0.993737 + outer loop + vertex 0.977803 1.38724 2.64143 + vertex 0.978543 1.39297 2.64156 + vertex 0.973509 1.38789 2.64191 + endloop + endfacet + facet normal 0.0871363 -0.0402928 0.995381 + outer loop + vertex 0.977329 1.37727 2.64108 + vertex 0.97754 1.38214 2.64126 + vertex 0.973229 1.37775 2.64146 + endloop + endfacet + facet normal 0.0860731 -0.0492157 0.995072 + outer loop + vertex 0.973171 1.37297 2.64123 + vertex 0.977329 1.37727 2.64108 + vertex 0.973229 1.37775 2.64146 + endloop + endfacet + facet normal 0.0743347 -0.0378091 0.996516 + outer loop + vertex 0.977047 1.37289 2.64094 + vertex 0.977329 1.37727 2.64108 + vertex 0.973171 1.37297 2.64123 + endloop + endfacet + facet normal 0.0740421 -0.0496998 0.996016 + outer loop + vertex 0.977047 1.37289 2.64094 + vertex 0.973171 1.37297 2.64123 + vertex 0.973306 1.36848 2.641 + endloop + endfacet + facet normal 0.0715415 -0.0475758 0.996302 + outer loop + vertex 0.977007 1.36976 2.64079 + vertex 0.977047 1.37289 2.64094 + vertex 0.973306 1.36848 2.641 + endloop + endfacet + facet normal 0.0728847 -0.0514884 0.99601 + outer loop + vertex 0.977007 1.36976 2.64079 + vertex 0.973306 1.36848 2.641 + vertex 0.975279 1.36685 2.64077 + endloop + endfacet + facet normal 0.155138 -0.100112 0.982807 + outer loop + vertex 0.978965 1.36813 2.64032 + vertex 0.977007 1.36976 2.64079 + vertex 0.975279 1.36685 2.64077 + endloop + endfacet + facet normal 0.153914 -0.0963988 0.983371 + outer loop + vertex 0.975279 1.36685 2.64077 + vertex 0.974116 1.36295 2.64057 + vertex 0.978965 1.36813 2.64032 + endloop + endfacet + facet normal 0.129516 -0.0733097 0.988864 + outer loop + vertex 0.978965 1.36813 2.64032 + vertex 0.974116 1.36295 2.64057 + vertex 0.978816 1.36305 2.63996 + endloop + endfacet + facet normal 0.129457 -0.0683736 0.989225 + outer loop + vertex 0.973743 1.35796 2.64027 + vertex 0.978816 1.36305 2.63996 + vertex 0.974116 1.36295 2.64057 + endloop + endfacet + facet normal 0.117202 -0.0560191 0.991527 + outer loop + vertex 0.978628 1.35797 2.63969 + vertex 0.978816 1.36305 2.63996 + vertex 0.973743 1.35796 2.64027 + endloop + endfacet + facet normal 0.117189 -0.0597177 0.991313 + outer loop + vertex 0.973514 1.35291 2.63999 + vertex 0.978628 1.35797 2.63969 + vertex 0.973743 1.35796 2.64027 + endloop + endfacet + facet normal 0.062575 -0.0575213 0.996381 + outer loop + vertex 0.973514 1.35291 2.63999 + vertex 0.973743 1.35796 2.64027 + vertex 0.968555 1.35293 2.64031 + endloop + endfacet + facet normal 0.0625382 -0.0629113 0.996058 + outer loop + vertex 0.968402 1.34786 2.64 + vertex 0.973514 1.35291 2.63999 + vertex 0.968555 1.35293 2.64031 + endloop + endfacet + facet normal 0.0397599 -0.0622995 0.997265 + outer loop + vertex 0.968402 1.34786 2.64 + vertex 0.968555 1.35293 2.64031 + vertex 0.963455 1.34789 2.6402 + endloop + endfacet + facet normal 0.0397114 -0.0675331 0.996926 + outer loop + vertex 0.963363 1.34283 2.63986 + vertex 0.968402 1.34786 2.64 + vertex 0.963455 1.34789 2.6402 + endloop + endfacet + facet normal 0.0363741 -0.0674815 0.997057 + outer loop + vertex 0.963363 1.34283 2.63986 + vertex 0.963455 1.34789 2.6402 + vertex 0.958481 1.34289 2.64004 + endloop + endfacet + facet normal 0.0363374 -0.0700803 0.996879 + outer loop + vertex 0.958384 1.33785 2.63969 + vertex 0.963363 1.34283 2.63986 + vertex 0.958481 1.34289 2.64004 + endloop + endfacet + facet normal 0.039022 -0.0701249 0.996775 + outer loop + vertex 0.958384 1.33785 2.63969 + vertex 0.958481 1.34289 2.64004 + vertex 0.953519 1.33795 2.63988 + endloop + endfacet + facet normal 0.038993 -0.0713766 0.996687 + outer loop + vertex 0.95344 1.33289 2.63953 + vertex 0.958384 1.33785 2.63969 + vertex 0.953519 1.33795 2.63988 + endloop + endfacet + facet normal 0.037196 -0.0713536 0.996757 + outer loop + vertex 0.95344 1.33289 2.63953 + vertex 0.953519 1.33795 2.63988 + vertex 0.948539 1.33299 2.63972 + endloop + endfacet + facet normal 0.0402032 -0.0725782 0.996552 + outer loop + vertex 0.95838 1.33279 2.63932 + vertex 0.958384 1.33785 2.63969 + vertex 0.95344 1.33289 2.63953 + endloop + endfacet + facet normal 0.0401798 -0.0736565 0.996474 + outer loop + vertex 0.953472 1.32786 2.63915 + vertex 0.95838 1.33279 2.63932 + vertex 0.95344 1.33289 2.63953 + endloop + endfacet + facet normal 0.0370614 -0.0736855 0.996593 + outer loop + vertex 0.953472 1.32786 2.63915 + vertex 0.95344 1.33289 2.63953 + vertex 0.948499 1.32793 2.63934 + endloop + endfacet + facet normal 0.0419475 -0.0754075 0.99627 + outer loop + vertex 0.958442 1.32781 2.63894 + vertex 0.95838 1.33279 2.63932 + vertex 0.953472 1.32786 2.63915 + endloop + endfacet + facet normal 0.0419188 -0.0775092 0.99611 + outer loop + vertex 0.953543 1.3229 2.63876 + vertex 0.958442 1.32781 2.63894 + vertex 0.953472 1.32786 2.63915 + endloop + endfacet + facet normal 0.0367985 -0.0775974 0.996305 + outer loop + vertex 0.953543 1.3229 2.63876 + vertex 0.953472 1.32786 2.63915 + vertex 0.948536 1.32292 2.63895 + endloop + endfacet + facet normal 0.0432322 -0.0788154 0.995951 + outer loop + vertex 0.958506 1.32288 2.63855 + vertex 0.958442 1.32781 2.63894 + vertex 0.953543 1.3229 2.63876 + endloop + endfacet + facet normal 0.0432062 -0.0818279 0.99571 + outer loop + vertex 0.953554 1.31796 2.63836 + vertex 0.958506 1.32288 2.63855 + vertex 0.953543 1.3229 2.63876 + endloop + endfacet + facet normal 0.0364959 -0.0818649 0.995975 + outer loop + vertex 0.953554 1.31796 2.63836 + vertex 0.953543 1.3229 2.63876 + vertex 0.948545 1.31794 2.63854 + endloop + endfacet + facet normal 0.0436502 -0.0822727 0.995653 + outer loop + vertex 0.958498 1.31793 2.63814 + vertex 0.958506 1.32288 2.63855 + vertex 0.953554 1.31796 2.63836 + endloop + endfacet + facet normal 0.0436169 -0.0860147 0.995339 + outer loop + vertex 0.95344 1.31294 2.63793 + vertex 0.958498 1.31793 2.63814 + vertex 0.953554 1.31796 2.63836 + endloop + endfacet + facet normal 0.0350306 -0.0858501 0.995692 + outer loop + vertex 0.95344 1.31294 2.63793 + vertex 0.953554 1.31796 2.63836 + vertex 0.948437 1.3129 2.6381 + endloop + endfacet + facet normal 0.0430503 -0.0854443 0.995412 + outer loop + vertex 0.958384 1.3129 2.63771 + vertex 0.958498 1.31793 2.63814 + vertex 0.95344 1.31294 2.63793 + endloop + endfacet + facet normal 0.0430165 -0.0883115 0.995164 + outer loop + vertex 0.95325 1.30779 2.63748 + vertex 0.958384 1.3129 2.63771 + vertex 0.95344 1.31294 2.63793 + endloop + endfacet + facet normal 0.0335557 -0.0879953 0.995556 + outer loop + vertex 0.95325 1.30779 2.63748 + vertex 0.95344 1.31294 2.63793 + vertex 0.948236 1.30775 2.63765 + endloop + endfacet + facet normal 0.0421107 -0.0874053 0.995282 + outer loop + vertex 0.958265 1.30778 2.63727 + vertex 0.958384 1.3129 2.63771 + vertex 0.95325 1.30779 2.63748 + endloop + endfacet + facet normal 0.0420983 -0.0890458 0.995137 + outer loop + vertex 0.953209 1.30266 2.63702 + vertex 0.958265 1.30778 2.63727 + vertex 0.95325 1.30779 2.63748 + endloop + endfacet + facet normal 0.0455427 -0.0874715 0.995125 + outer loop + vertex 0.958265 1.30778 2.63727 + vertex 0.963357 1.31282 2.63748 + vertex 0.958384 1.3129 2.63771 + endloop + endfacet + facet normal 0.0455801 -0.0854401 0.9953 + outer loop + vertex 0.963357 1.31282 2.63748 + vertex 0.963447 1.31788 2.63791 + vertex 0.958384 1.3129 2.63771 + endloop + endfacet + facet normal 0.0472115 -0.0854624 0.995222 + outer loop + vertex 0.963357 1.31282 2.63748 + vertex 0.968469 1.31787 2.63767 + vertex 0.963447 1.31788 2.63791 + endloop + endfacet + facet normal 0.0472277 -0.0830055 0.995429 + outer loop + vertex 0.968469 1.31787 2.63767 + vertex 0.968516 1.32288 2.63808 + vertex 0.963447 1.31788 2.63791 + endloop + endfacet + facet normal 0.0473068 -0.0830853 0.995419 + outer loop + vertex 0.963447 1.31788 2.63791 + vertex 0.968516 1.32288 2.63808 + vertex 0.963479 1.32285 2.63832 + endloop + endfacet + facet normal 0.0456678 -0.0830812 0.995496 + outer loop + vertex 0.963447 1.31788 2.63791 + vertex 0.963479 1.32285 2.63832 + vertex 0.958498 1.31793 2.63814 + endloop + endfacet + facet normal 0.0473041 -0.0810433 0.995587 + outer loop + vertex 0.968516 1.32288 2.63808 + vertex 0.968513 1.32784 2.63849 + vertex 0.963479 1.32285 2.63832 + endloop + endfacet + facet normal 0.0466543 -0.0803903 0.995671 + outer loop + vertex 0.963479 1.32285 2.63832 + vertex 0.968513 1.32784 2.63849 + vertex 0.963443 1.32779 2.63872 + endloop + endfacet + facet normal 0.0448784 -0.0804096 0.995751 + outer loop + vertex 0.963479 1.32285 2.63832 + vertex 0.963443 1.32779 2.63872 + vertex 0.958506 1.32288 2.63855 + endloop + endfacet + facet normal 0.0466454 -0.0789923 0.995783 + outer loop + vertex 0.968513 1.32784 2.63849 + vertex 0.968475 1.3328 2.63888 + vertex 0.963443 1.32779 2.63872 + endloop + endfacet + facet normal 0.0456006 -0.0779476 0.995914 + outer loop + vertex 0.963443 1.32779 2.63872 + vertex 0.968475 1.3328 2.63888 + vertex 0.963383 1.33275 2.63911 + endloop + endfacet + facet normal 0.0432895 -0.0779837 0.996014 + outer loop + vertex 0.963443 1.32779 2.63872 + vertex 0.963383 1.33275 2.63911 + vertex 0.958442 1.32781 2.63894 + endloop + endfacet + facet normal 0.0455959 -0.077241 0.995969 + outer loop + vertex 0.968475 1.3328 2.63888 + vertex 0.968422 1.33779 2.63927 + vertex 0.963383 1.33275 2.63911 + endloop + endfacet + facet normal 0.0434894 -0.0751419 0.996224 + outer loop + vertex 0.963383 1.33275 2.63911 + vertex 0.968422 1.33779 2.63927 + vertex 0.963343 1.33777 2.63949 + endloop + endfacet + facet normal 0.0407229 -0.0751724 0.996339 + outer loop + vertex 0.963383 1.33275 2.63911 + vertex 0.963343 1.33777 2.63949 + vertex 0.95838 1.33279 2.63932 + endloop + endfacet + facet normal 0.043489 -0.074194 0.996295 + outer loop + vertex 0.968422 1.33779 2.63927 + vertex 0.968379 1.34281 2.63965 + vertex 0.963343 1.33777 2.63949 + endloop + endfacet + facet normal 0.0411511 -0.071866 0.996565 + outer loop + vertex 0.963343 1.33777 2.63949 + vertex 0.968379 1.34281 2.63965 + vertex 0.963363 1.34283 2.63986 + endloop + endfacet + facet normal 0.0626077 -0.0739565 0.995294 + outer loop + vertex 0.968422 1.33779 2.63927 + vertex 0.973505 1.3429 2.63933 + vertex 0.968379 1.34281 2.63965 + endloop + endfacet + facet normal 0.0625545 -0.0697498 0.995601 + outer loop + vertex 0.973505 1.3429 2.63933 + vertex 0.97346 1.34789 2.63968 + vertex 0.968379 1.34281 2.63965 + endloop + endfacet + facet normal 0.061821 -0.069017 0.995698 + outer loop + vertex 0.968379 1.34281 2.63965 + vertex 0.97346 1.34789 2.63968 + vertex 0.968402 1.34786 2.64 + endloop + endfacet + facet normal 0.104899 -0.0691254 0.992078 + outer loop + vertex 0.973505 1.3429 2.63933 + vertex 0.978514 1.34796 2.63915 + vertex 0.97346 1.34789 2.63968 + endloop + endfacet + facet normal 0.10482 -0.0568878 0.992863 + outer loop + vertex 0.978514 1.34796 2.63915 + vertex 0.978519 1.35294 2.63944 + vertex 0.97346 1.34789 2.63968 + endloop + endfacet + facet normal 0.171453 -0.0564253 0.983575 + outer loop + vertex 0.978514 1.34796 2.63915 + vertex 0.983313 1.35278 2.63859 + vertex 0.978519 1.35294 2.63944 + endloop + endfacet + facet normal 0.172139 -0.0394878 0.984281 + outer loop + vertex 0.983313 1.35278 2.63859 + vertex 0.983485 1.35786 2.63877 + vertex 0.978519 1.35294 2.63944 + endloop + endfacet + facet normal 0.164067 -0.0488768 0.985238 + outer loop + vertex 0.983273 1.34784 2.63836 + vertex 0.983313 1.35278 2.63859 + vertex 0.978514 1.34796 2.63915 + endloop + endfacet + facet normal 0.163591 -0.0628963 0.984521 + outer loop + vertex 0.97856 1.34301 2.63883 + vertex 0.983273 1.34784 2.63836 + vertex 0.978514 1.34796 2.63915 + endloop + endfacet + facet normal 0.157726 -0.0570418 0.985834 + outer loop + vertex 0.983257 1.3429 2.63807 + vertex 0.983273 1.34784 2.63836 + vertex 0.97856 1.34301 2.63883 + endloop + endfacet + facet normal 0.157379 -0.0677145 0.985214 + outer loop + vertex 0.978583 1.33804 2.63849 + vertex 0.983257 1.3429 2.63807 + vertex 0.97856 1.34301 2.63883 + endloop + endfacet + facet normal 0.095721 -0.0685383 0.993046 + outer loop + vertex 0.978583 1.33804 2.63849 + vertex 0.97856 1.34301 2.63883 + vertex 0.973565 1.33792 2.63896 + endloop + endfacet + facet normal 0.0958381 -0.0749813 0.992569 + outer loop + vertex 0.9736 1.33294 2.63858 + vertex 0.978583 1.33804 2.63849 + vertex 0.973565 1.33792 2.63896 + endloop + endfacet + facet normal 0.0605127 -0.0754351 0.995313 + outer loop + vertex 0.9736 1.33294 2.63858 + vertex 0.973565 1.33792 2.63896 + vertex 0.968475 1.3328 2.63888 + endloop + endfacet + facet normal 0.089298 -0.0685715 0.993642 + outer loop + vertex 0.978573 1.33307 2.63814 + vertex 0.978583 1.33804 2.63849 + vertex 0.9736 1.33294 2.63858 + endloop + endfacet + facet normal 0.0894357 -0.0761738 0.993075 + outer loop + vertex 0.973605 1.32797 2.6382 + vertex 0.978573 1.33307 2.63814 + vertex 0.9736 1.33294 2.63858 + endloop + endfacet + facet normal 0.0581349 -0.0763851 0.995382 + outer loop + vertex 0.973605 1.32797 2.6382 + vertex 0.9736 1.33294 2.63858 + vertex 0.968513 1.32784 2.63849 + endloop + endfacet + facet normal 0.0821525 -0.0690612 0.994224 + outer loop + vertex 0.978537 1.32807 2.6378 + vertex 0.978573 1.33307 2.63814 + vertex 0.973605 1.32797 2.6382 + endloop + endfacet + facet normal 0.0822832 -0.0781259 0.993542 + outer loop + vertex 0.973576 1.32297 2.63781 + vertex 0.978537 1.32807 2.6378 + vertex 0.973605 1.32797 2.6382 + endloop + endfacet + facet normal 0.0553453 -0.0781143 0.995407 + outer loop + vertex 0.973576 1.32297 2.63781 + vertex 0.973605 1.32797 2.6382 + vertex 0.968516 1.32288 2.63808 + endloop + endfacet + facet normal 0.0770806 -0.0730643 0.994344 + outer loop + vertex 0.978481 1.32303 2.63743 + vertex 0.978537 1.32807 2.6378 + vertex 0.973576 1.32297 2.63781 + endloop + endfacet + facet normal 0.0771302 -0.0816259 0.993674 + outer loop + vertex 0.973523 1.31792 2.6374 + vertex 0.978481 1.32303 2.63743 + vertex 0.973576 1.32297 2.63781 + endloop + endfacet + facet normal 0.0538675 -0.0815078 0.995216 + outer loop + vertex 0.973523 1.31792 2.6374 + vertex 0.973576 1.32297 2.63781 + vertex 0.968469 1.31787 2.63767 + endloop + endfacet + facet normal 0.0538935 -0.0858357 0.994851 + outer loop + vertex 0.968428 1.31281 2.63723 + vertex 0.973523 1.31792 2.6374 + vertex 0.968469 1.31787 2.63767 + endloop + endfacet + facet normal 0.0529892 -0.0849377 0.994976 + outer loop + vertex 0.973518 1.31288 2.63697 + vertex 0.973523 1.31792 2.6374 + vertex 0.968428 1.31281 2.63723 + endloop + endfacet + facet normal 0.0530234 -0.0884319 0.99467 + outer loop + vertex 0.968549 1.30785 2.63679 + vertex 0.973518 1.31288 2.63697 + vertex 0.968428 1.31281 2.63723 + endloop + endfacet + facet normal 0.048256 -0.0885689 0.9949 + outer loop + vertex 0.968549 1.30785 2.63679 + vertex 0.968428 1.31281 2.63723 + vertex 0.96336 1.30776 2.63703 + endloop + endfacet + facet normal 0.0482655 -0.0892719 0.994837 + outer loop + vertex 0.963664 1.30288 2.63658 + vertex 0.968549 1.30785 2.63679 + vertex 0.96336 1.30776 2.63703 + endloop + endfacet + facet normal 0.0490342 -0.0900219 0.994732 + outer loop + vertex 0.968976 1.30323 2.63635 + vertex 0.968549 1.30785 2.63679 + vertex 0.963664 1.30288 2.63658 + endloop + endfacet + facet normal 0.05114 -0.0898193 0.994644 + outer loop + vertex 0.968976 1.30323 2.63635 + vertex 0.973691 1.30805 2.63654 + vertex 0.968549 1.30785 2.63679 + endloop + endfacet + facet normal 0.0478906 -0.0866584 0.995086 + outer loop + vertex 0.974175 1.30342 2.63611 + vertex 0.973691 1.30805 2.63654 + vertex 0.968976 1.30323 2.63635 + endloop + endfacet + facet normal 0.0480358 -0.0911245 0.99468 + outer loop + vertex 0.974175 1.30342 2.63611 + vertex 0.968976 1.30323 2.63635 + vertex 0.969585 1.29944 2.63597 + endloop + endfacet + facet normal 0.0459511 -0.088726 0.994996 + outer loop + vertex 0.972846 1.29951 2.63583 + vertex 0.974175 1.30342 2.63611 + vertex 0.969585 1.29944 2.63597 + endloop + endfacet + facet normal 0.0459673 -0.0896761 0.99491 + outer loop + vertex 0.972846 1.29951 2.63583 + vertex 0.969585 1.29944 2.63597 + vertex 0.970302 1.2969 2.63571 + endloop + endfacet + facet normal 0.043924 -0.0876992 0.995178 + outer loop + vertex 0.973441 1.29692 2.63557 + vertex 0.972846 1.29951 2.63583 + vertex 0.970302 1.2969 2.63571 + endloop + endfacet + facet normal 0.0439195 -0.0856672 0.995355 + outer loop + vertex 0.970302 1.2969 2.63571 + vertex 0.968611 1.29289 2.63544 + vertex 0.973441 1.29692 2.63557 + endloop + endfacet + facet normal 0.0457672 -0.0878754 0.99508 + outer loop + vertex 0.973441 1.29692 2.63557 + vertex 0.968611 1.29289 2.63544 + vertex 0.973554 1.29287 2.63521 + endloop + endfacet + facet normal 0.0608808 -0.0873849 0.994313 + outer loop + vertex 0.973554 1.29287 2.63521 + vertex 0.978543 1.29826 2.63538 + vertex 0.973441 1.29692 2.63557 + endloop + endfacet + facet normal 0.0647089 -0.102159 0.992661 + outer loop + vertex 0.973441 1.29692 2.63557 + vertex 0.978543 1.29826 2.63538 + vertex 0.976398 1.30089 2.63579 + endloop + endfacet + facet normal 0.0679811 -0.0994908 0.992714 + outer loop + vertex 0.980029 1.30249 2.6357 + vertex 0.976398 1.30089 2.63579 + vertex 0.978543 1.29826 2.63538 + endloop + endfacet + facet normal 0.142635 -0.124897 0.981864 + outer loop + vertex 0.980029 1.30249 2.6357 + vertex 0.978543 1.29826 2.63538 + vertex 0.983828 1.30337 2.63526 + endloop + endfacet + facet normal 0.144726 -0.134726 0.980257 + outer loop + vertex 0.983828 1.30337 2.63526 + vertex 0.982057 1.30525 2.63578 + vertex 0.980029 1.30249 2.6357 + endloop + endfacet + facet normal 0.0807556 -0.0880229 0.99284 + outer loop + vertex 0.982057 1.30525 2.63578 + vertex 0.978976 1.30475 2.63599 + vertex 0.980029 1.30249 2.6357 + endloop + endfacet + facet normal 0.0777777 -0.0687489 0.994598 + outer loop + vertex 0.982057 1.30525 2.63578 + vertex 0.982287 1.30829 2.63597 + vertex 0.978976 1.30475 2.63599 + endloop + endfacet + facet normal 0.080339 -0.0711491 0.994225 + outer loop + vertex 0.982287 1.30829 2.63597 + vertex 0.978458 1.30832 2.63628 + vertex 0.978976 1.30475 2.63599 + endloop + endfacet + facet normal 0.0476438 -0.0760332 0.995966 + outer loop + vertex 0.978976 1.30475 2.63599 + vertex 0.978458 1.30832 2.63628 + vertex 0.974175 1.30342 2.63611 + endloop + endfacet + facet normal 0.0499417 -0.0843556 0.995183 + outer loop + vertex 0.978976 1.30475 2.63599 + vertex 0.974175 1.30342 2.63611 + vertex 0.976398 1.30089 2.63579 + endloop + endfacet + facet normal 0.0805878 -0.0535494 0.995308 + outer loop + vertex 0.982287 1.30829 2.63597 + vertex 0.982774 1.31265 2.63617 + vertex 0.978458 1.30832 2.63628 + endloop + endfacet + facet normal 0.10267 -0.0756857 0.991832 + outer loop + vertex 0.978458 1.30832 2.63628 + vertex 0.982774 1.31265 2.63617 + vertex 0.978401 1.31293 2.63664 + endloop + endfacet + facet normal 0.0580652 -0.0765168 0.995376 + outer loop + vertex 0.978458 1.30832 2.63628 + vertex 0.978401 1.31293 2.63664 + vertex 0.973691 1.30805 2.63654 + endloop + endfacet + facet normal 0.0677173 -0.0857925 0.994009 + outer loop + vertex 0.973691 1.30805 2.63654 + vertex 0.978401 1.31293 2.63664 + vertex 0.973518 1.31288 2.63697 + endloop + endfacet + facet normal 0.0676922 -0.0796048 0.994525 + outer loop + vertex 0.978401 1.31293 2.63664 + vertex 0.978432 1.31794 2.63704 + vertex 0.973518 1.31288 2.63697 + endloop + endfacet + facet normal 0.114892 -0.0795559 0.990187 + outer loop + vertex 0.978401 1.31293 2.63664 + vertex 0.983044 1.31772 2.63649 + vertex 0.978432 1.31794 2.63704 + endloop + endfacet + facet normal 0.115183 -0.074362 0.990557 + outer loop + vertex 0.983044 1.31772 2.63649 + vertex 0.983042 1.32286 2.63687 + vertex 0.978432 1.31794 2.63704 + endloop + endfacet + facet normal 0.118852 -0.0778211 0.989858 + outer loop + vertex 0.978432 1.31794 2.63704 + vertex 0.983042 1.32286 2.63687 + vertex 0.978481 1.32303 2.63743 + endloop + endfacet + facet normal 0.119356 -0.0664419 0.990626 + outer loop + vertex 0.983042 1.32286 2.63687 + vertex 0.983089 1.32793 2.63721 + vertex 0.978481 1.32303 2.63743 + endloop + endfacet + facet normal 0.103213 -0.0681695 0.992321 + outer loop + vertex 0.982774 1.31265 2.63617 + vertex 0.983044 1.31772 2.63649 + vertex 0.978401 1.31293 2.63664 + endloop + endfacet + facet normal 0.11605 -0.0972473 0.988471 + outer loop + vertex 0.983828 1.30337 2.63526 + vertex 0.978543 1.29826 2.63538 + vertex 0.98366 1.29821 2.63477 + endloop + endfacet + facet normal 0.208614 -0.0987924 0.972996 + outer loop + vertex 0.98366 1.29821 2.63477 + vertex 0.988575 1.30329 2.63423 + vertex 0.983828 1.30337 2.63526 + endloop + endfacet + facet normal 0.209144 -0.0841142 0.974261 + outer loop + vertex 0.988618 1.30871 2.63469 + vertex 0.983828 1.30337 2.63526 + vertex 0.988575 1.30329 2.63423 + endloop + endfacet + facet normal 0.253288 -0.125352 0.959235 + outer loop + vertex 0.984697 1.3074 2.63556 + vertex 0.983828 1.30337 2.63526 + vertex 0.988618 1.30871 2.63469 + endloop + endfacet + facet normal 0.241835 -0.0861198 0.966488 + outer loop + vertex 0.984697 1.3074 2.63556 + vertex 0.988618 1.30871 2.63469 + vertex 0.986116 1.31137 2.63556 + endloop + endfacet + facet normal 0.150098 -0.0533351 0.987231 + outer loop + vertex 0.986116 1.31137 2.63556 + vertex 0.982287 1.30829 2.63597 + vertex 0.984697 1.3074 2.63556 + endloop + endfacet + facet normal 0.14277 -0.073191 0.987046 + outer loop + vertex 0.984697 1.3074 2.63556 + vertex 0.982287 1.30829 2.63597 + vertex 0.982057 1.30525 2.63578 + endloop + endfacet + facet normal 0.156612 -0.0616253 0.985736 + outer loop + vertex 0.982774 1.31265 2.63617 + vertex 0.982287 1.30829 2.63597 + vertex 0.986116 1.31137 2.63556 + endloop + endfacet + facet normal 0.164389 -0.041153 0.985537 + outer loop + vertex 0.98764 1.31706 2.63554 + vertex 0.982774 1.31265 2.63617 + vertex 0.986116 1.31137 2.63556 + endloop + endfacet + facet normal 0.248794 -0.0638234 0.966451 + outer loop + vertex 0.989865 1.31391 2.63476 + vertex 0.98764 1.31706 2.63554 + vertex 0.986116 1.31137 2.63556 + endloop + endfacet + facet normal 0.191518 -0.07201 0.978844 + outer loop + vertex 0.98764 1.31706 2.63554 + vertex 0.983044 1.31772 2.63649 + vertex 0.982774 1.31265 2.63617 + endloop + endfacet + facet normal 0.19104 -0.0751242 0.978703 + outer loop + vertex 0.98764 1.31706 2.63554 + vertex 0.987169 1.32236 2.63604 + vertex 0.983044 1.31772 2.63649 + endloop + endfacet + facet normal 0.25473 -0.0732804 0.964232 + outer loop + vertex 0.988618 1.30871 2.63469 + vertex 0.989865 1.31391 2.63476 + vertex 0.986116 1.31137 2.63556 + endloop + endfacet + facet normal 0.171454 -0.109165 0.979125 + outer loop + vertex 0.984697 1.3074 2.63556 + vertex 0.982057 1.30525 2.63578 + vertex 0.983828 1.30337 2.63526 + endloop + endfacet + facet normal 0.186809 -0.0770354 0.979371 + outer loop + vertex 0.988562 1.29814 2.63383 + vertex 0.988575 1.30329 2.63423 + vertex 0.98366 1.29821 2.63477 + endloop + endfacet + facet normal 0.186606 -0.0843316 0.978809 + outer loop + vertex 0.983574 1.29308 2.63435 + vertex 0.988562 1.29814 2.63383 + vertex 0.98366 1.29821 2.63477 + endloop + endfacet + facet normal 0.109613 -0.083999 0.990419 + outer loop + vertex 0.983574 1.29308 2.63435 + vertex 0.98366 1.29821 2.63477 + vertex 0.978554 1.29306 2.6349 + endloop + endfacet + facet normal 0.109584 -0.0899921 0.989895 + outer loop + vertex 0.978484 1.28799 2.63445 + vertex 0.983574 1.29308 2.63435 + vertex 0.978554 1.29306 2.6349 + endloop + endfacet + facet normal 0.0633549 -0.0897189 0.99395 + outer loop + vertex 0.978484 1.28799 2.63445 + vertex 0.978554 1.29306 2.6349 + vertex 0.973467 1.28796 2.63476 + endloop + endfacet + facet normal 0.0633585 -0.0963736 0.993327 + outer loop + vertex 0.973392 1.28292 2.63428 + vertex 0.978484 1.28799 2.63445 + vertex 0.973467 1.28796 2.63476 + endloop + endfacet + facet normal 0.046741 -0.0962172 0.994262 + outer loop + vertex 0.973392 1.28292 2.63428 + vertex 0.973467 1.28796 2.63476 + vertex 0.968418 1.28296 2.63452 + endloop + endfacet + facet normal 0.0466989 -0.0996845 0.993923 + outer loop + vertex 0.968371 1.27791 2.63401 + vertex 0.973392 1.28292 2.63428 + vertex 0.968418 1.28296 2.63452 + endloop + endfacet + facet normal 0.0454051 -0.0996787 0.993983 + outer loop + vertex 0.968371 1.27791 2.63401 + vertex 0.968418 1.28296 2.63452 + vertex 0.963434 1.27798 2.63425 + endloop + endfacet + facet normal 0.0454165 -0.0991274 0.994038 + outer loop + vertex 0.963442 1.27296 2.63374 + vertex 0.968371 1.27791 2.63401 + vertex 0.963434 1.27798 2.63425 + endloop + endfacet + facet normal 0.0467234 -0.0991195 0.993978 + outer loop + vertex 0.963442 1.27296 2.63374 + vertex 0.963434 1.27798 2.63425 + vertex 0.9585 1.27304 2.63398 + endloop + endfacet + facet normal 0.0467702 -0.0967401 0.99421 + outer loop + vertex 0.958511 1.26804 2.6335 + vertex 0.963442 1.27296 2.63374 + vertex 0.9585 1.27304 2.63398 + endloop + endfacet + facet normal 0.0416993 -0.0967721 0.994433 + outer loop + vertex 0.958511 1.26804 2.6335 + vertex 0.9585 1.27304 2.63398 + vertex 0.953497 1.26805 2.63371 + endloop + endfacet + facet normal 0.0417155 -0.0938773 0.994709 + outer loop + vertex 0.953425 1.263 2.63323 + vertex 0.958511 1.26804 2.6335 + vertex 0.953497 1.26805 2.63371 + endloop + endfacet + facet normal 0.0265887 -0.093711 0.995244 + outer loop + vertex 0.953425 1.263 2.63323 + vertex 0.953497 1.26805 2.63371 + vertex 0.948322 1.26291 2.63336 + endloop + endfacet + facet normal 0.0265283 -0.0895331 0.99563 + outer loop + vertex 0.948195 1.25779 2.63291 + vertex 0.953425 1.263 2.63323 + vertex 0.948322 1.26291 2.63336 + endloop + endfacet + facet normal 0.00305271 -0.0889865 0.996028 + outer loop + vertex 0.948195 1.25779 2.63291 + vertex 0.948322 1.26291 2.63336 + vertex 0.943146 1.25771 2.63291 + endloop + endfacet + facet normal 0.00296081 -0.0829125 0.996552 + outer loop + vertex 0.943203 1.25267 2.63249 + vertex 0.948195 1.25779 2.63291 + vertex 0.943146 1.25771 2.63291 + endloop + endfacet + facet normal -0.0243432 -0.0831949 0.996236 + outer loop + vertex 0.943203 1.25267 2.63249 + vertex 0.943146 1.25771 2.63291 + vertex 0.938504 1.25283 2.63239 + endloop + endfacet + facet normal -0.0242578 -0.0806736 0.996445 + outer loop + vertex 0.939005 1.24815 2.63203 + vertex 0.943203 1.25267 2.63249 + vertex 0.938504 1.25283 2.63239 + endloop + endfacet + facet normal -0.0259531 -0.0816713 0.996321 + outer loop + vertex 0.938504 1.25283 2.63239 + vertex 0.943146 1.25771 2.63291 + vertex 0.938211 1.25772 2.63279 + endloop + endfacet + facet normal -0.025955 -0.0892185 0.995674 + outer loop + vertex 0.943146 1.25771 2.63291 + vertex 0.943218 1.26281 2.63337 + vertex 0.938211 1.25772 2.63279 + endloop + endfacet + facet normal -0.0255029 -0.0896599 0.995646 + outer loop + vertex 0.938211 1.25772 2.63279 + vertex 0.943218 1.26281 2.63337 + vertex 0.938197 1.26277 2.63324 + endloop + endfacet + facet normal -0.0254452 -0.0950812 0.995144 + outer loop + vertex 0.943218 1.26281 2.63337 + vertex 0.943381 1.26795 2.63387 + vertex 0.938197 1.26277 2.63324 + endloop + endfacet + facet normal -0.0250627 -0.0954609 0.995118 + outer loop + vertex 0.938197 1.26277 2.63324 + vertex 0.943381 1.26795 2.63387 + vertex 0.93835 1.26787 2.63373 + endloop + endfacet + facet normal -0.0249915 -0.0993814 0.994736 + outer loop + vertex 0.943381 1.26795 2.63387 + vertex 0.943598 1.27305 2.63438 + vertex 0.93835 1.26787 2.63373 + endloop + endfacet + facet normal -0.0222878 -0.102096 0.994525 + outer loop + vertex 0.93835 1.26787 2.63373 + vertex 0.943598 1.27305 2.63438 + vertex 0.938532 1.27291 2.63425 + endloop + endfacet + facet normal -0.0222094 -0.104709 0.994255 + outer loop + vertex 0.943598 1.27305 2.63438 + vertex 0.943652 1.27789 2.63489 + vertex 0.938532 1.27291 2.63425 + endloop + endfacet + facet normal -0.0171537 -0.109845 0.993801 + outer loop + vertex 0.938532 1.27291 2.63425 + vertex 0.943652 1.27789 2.63489 + vertex 0.938453 1.27763 2.63478 + endloop + endfacet + facet normal -0.0169459 -0.113764 0.993363 + outer loop + vertex 0.943652 1.27789 2.63489 + vertex 0.943003 1.28204 2.63536 + vertex 0.938453 1.27763 2.63478 + endloop + endfacet + facet normal 0.0162239 -0.108645 0.993948 + outer loop + vertex 0.943652 1.27789 2.63489 + vertex 0.948689 1.283 2.63537 + vertex 0.943003 1.28204 2.63536 + endloop + endfacet + facet normal 0.011396 -0.103939 0.994518 + outer loop + vertex 0.948763 1.27811 2.63486 + vertex 0.948689 1.283 2.63537 + vertex 0.943652 1.27789 2.63489 + endloop + endfacet + facet normal 0.0360096 -0.103509 0.993976 + outer loop + vertex 0.948763 1.27811 2.63486 + vertex 0.953795 1.2829 2.63518 + vertex 0.948689 1.283 2.63537 + endloop + endfacet + facet normal 0.0321921 -0.0995374 0.994513 + outer loop + vertex 0.953702 1.27813 2.6347 + vertex 0.953795 1.2829 2.63518 + vertex 0.948763 1.27811 2.63486 + endloop + endfacet + facet normal 0.0321938 -0.101594 0.994305 + outer loop + vertex 0.948606 1.27312 2.63435 + vertex 0.953702 1.27813 2.6347 + vertex 0.948763 1.27811 2.63486 + endloop + endfacet + facet normal 0.0072494 -0.100866 0.994874 + outer loop + vertex 0.948606 1.27312 2.63435 + vertex 0.948763 1.27811 2.63486 + vertex 0.943598 1.27305 2.63438 + endloop + endfacet + facet normal 0.030029 -0.0994128 0.994593 + outer loop + vertex 0.953563 1.2731 2.6342 + vertex 0.953702 1.27813 2.6347 + vertex 0.948606 1.27312 2.63435 + endloop + endfacet + facet normal 0.0300298 -0.0992837 0.994606 + outer loop + vertex 0.948443 1.26802 2.63385 + vertex 0.953563 1.2731 2.6342 + vertex 0.948606 1.27312 2.63435 + endloop + endfacet + facet normal 0.00501828 -0.0985357 0.995121 + outer loop + vertex 0.948443 1.26802 2.63385 + vertex 0.948606 1.27312 2.63435 + vertex 0.943381 1.26795 2.63387 + endloop + endfacet + facet normal 0.0283482 -0.0976059 0.994821 + outer loop + vertex 0.953497 1.26805 2.63371 + vertex 0.953563 1.2731 2.6342 + vertex 0.948443 1.26802 2.63385 + endloop + endfacet + facet normal 0.0437599 -0.0997378 0.994051 + outer loop + vertex 0.953563 1.2731 2.6342 + vertex 0.958565 1.27808 2.63448 + vertex 0.953702 1.27813 2.6347 + endloop + endfacet + facet normal 0.0437762 -0.0986366 0.99416 + outer loop + vertex 0.958565 1.27808 2.63448 + vertex 0.958706 1.28304 2.63497 + vertex 0.953702 1.27813 2.6347 + endloop + endfacet + facet normal 0.0463271 -0.0986976 0.994039 + outer loop + vertex 0.958565 1.27808 2.63448 + vertex 0.963549 1.28302 2.63474 + vertex 0.958706 1.28304 2.63497 + endloop + endfacet + facet normal 0.0463524 -0.0960956 0.994292 + outer loop + vertex 0.963549 1.28302 2.63474 + vertex 0.963681 1.28783 2.6352 + vertex 0.958706 1.28304 2.63497 + endloop + endfacet + facet normal 0.0447513 -0.0960589 0.994369 + outer loop + vertex 0.963549 1.28302 2.63474 + vertex 0.968555 1.28797 2.63499 + vertex 0.963681 1.28783 2.6352 + endloop + endfacet + facet normal 0.0446188 -0.0904898 0.994897 + outer loop + vertex 0.968555 1.28797 2.63499 + vertex 0.968611 1.29289 2.63544 + vertex 0.963681 1.28783 2.6352 + endloop + endfacet + facet normal 0.0485728 -0.0943144 0.994357 + outer loop + vertex 0.963681 1.28783 2.6352 + vertex 0.968611 1.29289 2.63544 + vertex 0.963602 1.29176 2.63558 + endloop + endfacet + facet normal 0.044375 -0.0956812 0.994422 + outer loop + vertex 0.968418 1.28296 2.63452 + vertex 0.968555 1.28797 2.63499 + vertex 0.963549 1.28302 2.63474 + endloop + endfacet + facet normal 0.0462694 -0.0986398 0.994047 + outer loop + vertex 0.963434 1.27798 2.63425 + vertex 0.963549 1.28302 2.63474 + vertex 0.958565 1.27808 2.63448 + endloop + endfacet + facet normal 0.0426579 -0.0986397 0.994208 + outer loop + vertex 0.9585 1.27304 2.63398 + vertex 0.958565 1.27808 2.63448 + vertex 0.953563 1.2731 2.6342 + endloop + endfacet + facet normal 0.0448608 -0.0997335 0.994002 + outer loop + vertex 0.953702 1.27813 2.6347 + vertex 0.958706 1.28304 2.63497 + vertex 0.953795 1.2829 2.63518 + endloop + endfacet + facet normal 0.0448176 -0.0979091 0.994186 + outer loop + vertex 0.958706 1.28304 2.63497 + vertex 0.958732 1.28786 2.63544 + vertex 0.953795 1.2829 2.63518 + endloop + endfacet + facet normal 0.0469062 -0.0999742 0.993884 + outer loop + vertex 0.953795 1.2829 2.63518 + vertex 0.958732 1.28786 2.63544 + vertex 0.953649 1.28678 2.63557 + endloop + endfacet + facet normal 0.0481129 -0.0979114 0.994031 + outer loop + vertex 0.958706 1.28304 2.63497 + vertex 0.963681 1.28783 2.6352 + vertex 0.958732 1.28786 2.63544 + endloop + endfacet + facet normal 0.0114452 -0.1051 0.994396 + outer loop + vertex 0.943598 1.27305 2.63438 + vertex 0.948763 1.27811 2.63486 + vertex 0.943652 1.27789 2.63489 + endloop + endfacet + facet normal 0.00724801 -0.100767 0.994884 + outer loop + vertex 0.943381 1.26795 2.63387 + vertex 0.948606 1.27312 2.63435 + vertex 0.943598 1.27305 2.63438 + endloop + endfacet + facet normal 0.00498626 -0.0960704 0.995362 + outer loop + vertex 0.943218 1.26281 2.63337 + vertex 0.948443 1.26802 2.63385 + vertex 0.943381 1.26795 2.63387 + endloop + endfacet + facet normal 0.00383486 -0.0949248 0.995477 + outer loop + vertex 0.948322 1.26291 2.63336 + vertex 0.948443 1.26802 2.63385 + vertex 0.943218 1.26281 2.63337 + endloop + endfacet + facet normal 0.00272623 -0.0826854 0.996572 + outer loop + vertex 0.948126 1.25265 2.63248 + vertex 0.948195 1.25779 2.63291 + vertex 0.943203 1.25267 2.63249 + endloop + endfacet + facet normal 0.00274434 -0.0782121 0.996933 + outer loop + vertex 0.943533 1.24783 2.63211 + vertex 0.948126 1.25265 2.63248 + vertex 0.943203 1.25267 2.63249 + endloop + endfacet + facet normal -0.0249197 -0.0800615 0.996478 + outer loop + vertex 0.943533 1.24783 2.63211 + vertex 0.943203 1.25267 2.63249 + vertex 0.939005 1.24815 2.63203 + endloop + endfacet + facet normal -0.0249536 -0.0805557 0.996438 + outer loop + vertex 0.940083 1.24431 2.63174 + vertex 0.943533 1.24783 2.63211 + vertex 0.939005 1.24815 2.63203 + endloop + endfacet + facet normal -0.0191747 -0.0861735 0.996096 + outer loop + vertex 0.944109 1.2433 2.63173 + vertex 0.943533 1.24783 2.63211 + vertex 0.940083 1.24431 2.63174 + endloop + endfacet + facet normal -0.0234683 -0.103386 0.994364 + outer loop + vertex 0.939768 1.24001 2.63129 + vertex 0.944109 1.2433 2.63173 + vertex 0.940083 1.24431 2.63174 + endloop + endfacet + facet normal -0.022817 -0.104234 0.994291 + outer loop + vertex 0.945187 1.23911 2.63132 + vertex 0.944109 1.2433 2.63173 + vertex 0.939768 1.24001 2.63129 + endloop + endfacet + facet normal -0.0251621 -0.118378 0.99265 + outer loop + vertex 0.945187 1.23911 2.63132 + vertex 0.939768 1.24001 2.63129 + vertex 0.941562 1.23566 2.63082 + endloop + endfacet + facet normal -0.0186086 -0.125166 0.991961 + outer loop + vertex 0.946661 1.23531 2.63087 + vertex 0.945187 1.23911 2.63132 + vertex 0.941562 1.23566 2.63082 + endloop + endfacet + facet normal -0.0194861 -0.138436 0.99018 + outer loop + vertex 0.941562 1.23566 2.63082 + vertex 0.942713 1.23167 2.63028 + vertex 0.946661 1.23531 2.63087 + endloop + endfacet + facet normal -0.0196186 -0.138296 0.990197 + outer loop + vertex 0.942713 1.23167 2.63028 + vertex 0.947875 1.23168 2.63038 + vertex 0.946661 1.23531 2.63087 + endloop + endfacet + facet normal 0.0159316 -0.126625 0.991823 + outer loop + vertex 0.946661 1.23531 2.63087 + vertex 0.947875 1.23168 2.63038 + vertex 0.951657 1.23557 2.63082 + endloop + endfacet + facet normal 0.0155275 -0.118523 0.99283 + outer loop + vertex 0.951657 1.23557 2.63082 + vertex 0.95025 1.23905 2.63126 + vertex 0.946661 1.23531 2.63087 + endloop + endfacet + facet normal 0.0321844 -0.111846 0.993204 + outer loop + vertex 0.955147 1.23939 2.63114 + vertex 0.95025 1.23905 2.63126 + vertex 0.951657 1.23557 2.63082 + endloop + endfacet + facet normal 0.0349717 -0.114362 0.992823 + outer loop + vertex 0.956448 1.23619 2.63072 + vertex 0.955147 1.23939 2.63114 + vertex 0.951657 1.23557 2.63082 + endloop + endfacet + facet normal 0.0357303 -0.120312 0.992093 + outer loop + vertex 0.951657 1.23557 2.63082 + vertex 0.952947 1.23214 2.63036 + vertex 0.956448 1.23619 2.63072 + endloop + endfacet + facet normal 0.0377718 -0.12205 0.991805 + outer loop + vertex 0.952947 1.23214 2.63036 + vertex 0.958562 1.23319 2.63027 + vertex 0.956448 1.23619 2.63072 + endloop + endfacet + facet normal 0.0432911 -0.118201 0.992046 + outer loop + vertex 0.960273 1.23715 2.63067 + vertex 0.956448 1.23619 2.63072 + vertex 0.958562 1.23319 2.63027 + endloop + endfacet + facet normal 0.0481001 -0.120233 0.99158 + outer loop + vertex 0.960273 1.23715 2.63067 + vertex 0.958562 1.23319 2.63027 + vertex 0.963499 1.23697 2.63049 + endloop + endfacet + facet normal 0.0484119 -0.115124 0.992171 + outer loop + vertex 0.963499 1.23697 2.63049 + vertex 0.962877 1.23955 2.63082 + vertex 0.960273 1.23715 2.63067 + endloop + endfacet + facet normal 0.0442416 -0.110656 0.992874 + outer loop + vertex 0.962877 1.23955 2.63082 + vertex 0.959661 1.23976 2.63099 + vertex 0.960273 1.23715 2.63067 + endloop + endfacet + facet normal 0.0451754 -0.0974124 0.994218 + outer loop + vertex 0.962877 1.23955 2.63082 + vertex 0.964253 1.24333 2.63113 + vertex 0.959661 1.23976 2.63099 + endloop + endfacet + facet normal 0.0445102 -0.09656 0.994331 + outer loop + vertex 0.964253 1.24333 2.63113 + vertex 0.95906 1.24342 2.63137 + vertex 0.959661 1.23976 2.63099 + endloop + endfacet + facet normal 0.0407471 -0.0971887 0.994432 + outer loop + vertex 0.959661 1.23976 2.63099 + vertex 0.95906 1.24342 2.63137 + vertex 0.955147 1.23939 2.63114 + endloop + endfacet + facet normal 0.0394134 -0.0959053 0.99461 + outer loop + vertex 0.955147 1.23939 2.63114 + vertex 0.95906 1.24342 2.63137 + vertex 0.954047 1.24319 2.63155 + endloop + endfacet + facet normal 0.0390165 -0.0865969 0.995479 + outer loop + vertex 0.95906 1.24342 2.63137 + vertex 0.958406 1.24783 2.63178 + vertex 0.954047 1.24319 2.63155 + endloop + endfacet + facet normal 0.0366754 -0.0844085 0.995756 + outer loop + vertex 0.954047 1.24319 2.63155 + vertex 0.958406 1.24783 2.63178 + vertex 0.953346 1.2477 2.63196 + endloop + endfacet + facet normal 0.027313 -0.0858809 0.995931 + outer loop + vertex 0.954047 1.24319 2.63155 + vertex 0.953346 1.2477 2.63196 + vertex 0.949036 1.24305 2.63167 + endloop + endfacet + facet normal 0.027542 -0.0948539 0.99511 + outer loop + vertex 0.95025 1.23905 2.63126 + vertex 0.954047 1.24319 2.63155 + vertex 0.949036 1.24305 2.63167 + endloop + endfacet + facet normal 0.0108622 -0.0998981 0.994938 + outer loop + vertex 0.95025 1.23905 2.63126 + vertex 0.949036 1.24305 2.63167 + vertex 0.945187 1.23911 2.63132 + endloop + endfacet + facet normal 0.024443 -0.0832391 0.99623 + outer loop + vertex 0.949036 1.24305 2.63167 + vertex 0.953346 1.2477 2.63196 + vertex 0.948336 1.24765 2.63207 + endloop + endfacet + facet normal 0.00797734 -0.0857511 0.996285 + outer loop + vertex 0.949036 1.24305 2.63167 + vertex 0.948336 1.24765 2.63207 + vertex 0.944109 1.2433 2.63173 + endloop + endfacet + facet normal 0.0244248 -0.0809755 0.996417 + outer loop + vertex 0.953346 1.2477 2.63196 + vertex 0.953153 1.25271 2.63237 + vertex 0.948336 1.24765 2.63207 + endloop + endfacet + facet normal 0.0360763 -0.0805011 0.996101 + outer loop + vertex 0.953346 1.2477 2.63196 + vertex 0.958183 1.25276 2.63219 + vertex 0.953153 1.25271 2.63237 + endloop + endfacet + facet normal 0.0366026 -0.0810016 0.996042 + outer loop + vertex 0.958406 1.24783 2.63178 + vertex 0.958183 1.25276 2.63219 + vertex 0.953346 1.2477 2.63196 + endloop + endfacet + facet normal 0.0438944 -0.0806502 0.995775 + outer loop + vertex 0.958406 1.24783 2.63178 + vertex 0.963247 1.25277 2.63197 + vertex 0.958183 1.25276 2.63219 + endloop + endfacet + facet normal 0.0438939 -0.080834 0.995761 + outer loop + vertex 0.963247 1.25277 2.63197 + vertex 0.963275 1.25788 2.63238 + vertex 0.958183 1.25276 2.63219 + endloop + endfacet + facet normal 0.0442631 -0.0811998 0.995715 + outer loop + vertex 0.958183 1.25276 2.63219 + vertex 0.963275 1.25788 2.63238 + vertex 0.958295 1.25792 2.6326 + endloop + endfacet + facet normal 0.0360805 -0.0810501 0.996057 + outer loop + vertex 0.958183 1.25276 2.63219 + vertex 0.958295 1.25792 2.6326 + vertex 0.953153 1.25271 2.63237 + endloop + endfacet + facet normal 0.0372161 -0.082164 0.995924 + outer loop + vertex 0.953153 1.25271 2.63237 + vertex 0.958295 1.25792 2.6326 + vertex 0.953274 1.25788 2.63279 + endloop + endfacet + facet normal 0.0233039 -0.0818757 0.99637 + outer loop + vertex 0.953153 1.25271 2.63237 + vertex 0.953274 1.25788 2.63279 + vertex 0.948126 1.25265 2.63248 + endloop + endfacet + facet normal 0.0232834 -0.0798946 0.996531 + outer loop + vertex 0.948336 1.24765 2.63207 + vertex 0.953153 1.25271 2.63237 + vertex 0.948126 1.25265 2.63248 + endloop + endfacet + facet normal 0.0442221 -0.0843962 0.99545 + outer loop + vertex 0.963275 1.25788 2.63238 + vertex 0.963423 1.263 2.63281 + vertex 0.958295 1.25792 2.6326 + endloop + endfacet + facet normal 0.0455637 -0.0857449 0.995275 + outer loop + vertex 0.958295 1.25792 2.6326 + vertex 0.963423 1.263 2.63281 + vertex 0.95846 1.26303 2.63304 + endloop + endfacet + facet normal 0.0372326 -0.0855071 0.995642 + outer loop + vertex 0.958295 1.25792 2.6326 + vertex 0.95846 1.26303 2.63304 + vertex 0.953274 1.25788 2.63279 + endloop + endfacet + facet normal 0.0396134 -0.0878897 0.995342 + outer loop + vertex 0.953274 1.25788 2.63279 + vertex 0.95846 1.26303 2.63304 + vertex 0.953425 1.263 2.63323 + endloop + endfacet + facet normal 0.0483802 -0.0844995 0.995248 + outer loop + vertex 0.963275 1.25788 2.63238 + vertex 0.968395 1.26291 2.63256 + vertex 0.963423 1.263 2.63281 + endloop + endfacet + facet normal 0.0482437 -0.0910556 0.994677 + outer loop + vertex 0.968395 1.26291 2.63256 + vertex 0.968459 1.26796 2.63302 + vertex 0.963423 1.263 2.63281 + endloop + endfacet + facet normal 0.0480076 -0.0908174 0.99471 + outer loop + vertex 0.963423 1.263 2.63281 + vertex 0.968459 1.26796 2.63302 + vertex 0.963482 1.268 2.63326 + endloop + endfacet + facet normal 0.0455063 -0.0907988 0.994829 + outer loop + vertex 0.963423 1.263 2.63281 + vertex 0.963482 1.268 2.63326 + vertex 0.95846 1.26303 2.63304 + endloop + endfacet + facet normal 0.0465313 -0.0918282 0.994687 + outer loop + vertex 0.95846 1.26303 2.63304 + vertex 0.963482 1.268 2.63326 + vertex 0.958511 1.26804 2.6335 + endloop + endfacet + facet normal 0.0479183 -0.0973114 0.9941 + outer loop + vertex 0.968459 1.26796 2.63302 + vertex 0.968424 1.27292 2.6335 + vertex 0.963482 1.268 2.63326 + endloop + endfacet + facet normal 0.0470475 -0.0964426 0.994226 + outer loop + vertex 0.963482 1.268 2.63326 + vertex 0.968424 1.27292 2.6335 + vertex 0.963442 1.27296 2.63374 + endloop + endfacet + facet normal 0.049887 -0.0972882 0.994005 + outer loop + vertex 0.968459 1.26796 2.63302 + vertex 0.973487 1.27294 2.63325 + vertex 0.968424 1.27292 2.6335 + endloop + endfacet + facet normal 0.0498856 -0.101995 0.993533 + outer loop + vertex 0.973487 1.27294 2.63325 + vertex 0.973419 1.27791 2.63377 + vertex 0.968424 1.27292 2.6335 + endloop + endfacet + facet normal 0.0485412 -0.10066 0.993736 + outer loop + vertex 0.968424 1.27292 2.6335 + vertex 0.973419 1.27791 2.63377 + vertex 0.968371 1.27791 2.63401 + endloop + endfacet + facet normal 0.0616047 -0.101771 0.992899 + outer loop + vertex 0.973487 1.27294 2.63325 + vertex 0.978537 1.27802 2.63346 + vertex 0.973419 1.27791 2.63377 + endloop + endfacet + facet normal 0.0615813 -0.100121 0.993068 + outer loop + vertex 0.978537 1.27802 2.63346 + vertex 0.978479 1.28298 2.63396 + vertex 0.973419 1.27791 2.63377 + endloop + endfacet + facet normal 0.0628258 -0.101355 0.992865 + outer loop + vertex 0.973419 1.27791 2.63377 + vertex 0.978479 1.28298 2.63396 + vertex 0.973392 1.28292 2.63428 + endloop + endfacet + facet normal 0.0936239 -0.0995011 0.990623 + outer loop + vertex 0.978537 1.27802 2.63346 + vertex 0.983515 1.28307 2.6335 + vertex 0.978479 1.28298 2.63396 + endloop + endfacet + facet normal 0.0935209 -0.0877245 0.991745 + outer loop + vertex 0.983515 1.28307 2.6335 + vertex 0.983516 1.28804 2.63394 + vertex 0.978479 1.28298 2.63396 + endloop + endfacet + facet normal 0.101364 -0.0955403 0.990251 + outer loop + vertex 0.978479 1.28298 2.63396 + vertex 0.983516 1.28804 2.63394 + vertex 0.978484 1.28799 2.63445 + endloop + endfacet + facet normal 0.153608 -0.0870722 0.984288 + outer loop + vertex 0.983515 1.28307 2.6335 + vertex 0.988282 1.28791 2.63318 + vertex 0.983516 1.28804 2.63394 + endloop + endfacet + facet normal 0.154435 -0.0660021 0.985796 + outer loop + vertex 0.988282 1.28791 2.63318 + vertex 0.988461 1.29299 2.63349 + vertex 0.983516 1.28804 2.63394 + endloop + endfacet + facet normal 0.16988 -0.0817635 0.982067 + outer loop + vertex 0.983516 1.28804 2.63394 + vertex 0.988461 1.29299 2.63349 + vertex 0.983574 1.29308 2.63435 + endloop + endfacet + facet normal 0.14201 -0.0754689 0.986984 + outer loop + vertex 0.988225 1.28296 2.63281 + vertex 0.988282 1.28791 2.63318 + vertex 0.983515 1.28307 2.6335 + endloop + endfacet + facet normal 0.141413 -0.0920696 0.98566 + outer loop + vertex 0.983552 1.27812 2.63303 + vertex 0.988225 1.28296 2.63281 + vertex 0.983515 1.28307 2.6335 + endloop + endfacet + facet normal 0.131212 -0.0821109 0.987948 + outer loop + vertex 0.988196 1.278 2.6324 + vertex 0.988225 1.28296 2.63281 + vertex 0.983552 1.27812 2.63303 + endloop + endfacet + facet normal 0.130761 -0.0943734 0.986912 + outer loop + vertex 0.983552 1.27312 2.63255 + vertex 0.988196 1.278 2.6324 + vertex 0.983552 1.27812 2.63303 + endloop + endfacet + facet normal 0.0820021 -0.0948724 0.992106 + outer loop + vertex 0.983552 1.27312 2.63255 + vertex 0.983552 1.27812 2.63303 + vertex 0.978589 1.27304 2.63295 + endloop + endfacet + facet normal 0.082023 -0.0972033 0.991879 + outer loop + vertex 0.978578 1.26801 2.63246 + vertex 0.983552 1.27312 2.63255 + vertex 0.978589 1.27304 2.63295 + endloop + endfacet + facet normal 0.0593543 -0.0973113 0.993483 + outer loop + vertex 0.978578 1.26801 2.63246 + vertex 0.978589 1.27304 2.63295 + vertex 0.973502 1.26794 2.63276 + endloop + endfacet + facet normal 0.0593219 -0.092206 0.993971 + outer loop + vertex 0.973452 1.26287 2.63229 + vertex 0.978578 1.26801 2.63246 + vertex 0.973502 1.26794 2.63276 + endloop + endfacet + facet normal 0.0519276 -0.0921707 0.994388 + outer loop + vertex 0.973452 1.26287 2.63229 + vertex 0.973502 1.26794 2.63276 + vertex 0.968395 1.26291 2.63256 + endloop + endfacet + facet normal 0.0520161 -0.0851167 0.995012 + outer loop + vertex 0.968312 1.25781 2.63213 + vertex 0.973452 1.26287 2.63229 + vertex 0.968395 1.26291 2.63256 + endloop + endfacet + facet normal 0.0527218 -0.085829 0.994914 + outer loop + vertex 0.973449 1.25784 2.63186 + vertex 0.973452 1.26287 2.63229 + vertex 0.968312 1.25781 2.63213 + endloop + endfacet + facet normal 0.0527094 -0.0807889 0.995337 + outer loop + vertex 0.968419 1.25282 2.63172 + vertex 0.973449 1.25784 2.63186 + vertex 0.968312 1.25781 2.63213 + endloop + endfacet + facet normal 0.0490714 -0.080882 0.995515 + outer loop + vertex 0.968419 1.25282 2.63172 + vertex 0.968312 1.25781 2.63213 + vertex 0.963247 1.25277 2.63197 + endloop + endfacet + facet normal 0.0490701 -0.0806388 0.995535 + outer loop + vertex 0.963576 1.24793 2.63156 + vertex 0.968419 1.25282 2.63172 + vertex 0.963247 1.25277 2.63197 + endloop + endfacet + facet normal 0.0480935 -0.0796751 0.99566 + outer loop + vertex 0.968868 1.2482 2.63132 + vertex 0.968419 1.25282 2.63172 + vertex 0.963576 1.24793 2.63156 + endloop + endfacet + facet normal 0.0483789 -0.0856756 0.995148 + outer loop + vertex 0.964253 1.24333 2.63113 + vertex 0.968868 1.2482 2.63132 + vertex 0.963576 1.24793 2.63156 + endloop + endfacet + facet normal 0.0448769 -0.0823774 0.99559 + outer loop + vertex 0.969506 1.24443 2.63098 + vertex 0.968868 1.2482 2.63132 + vertex 0.964253 1.24333 2.63113 + endloop + endfacet + facet normal 0.0477316 -0.0962142 0.994216 + outer loop + vertex 0.969506 1.24443 2.63098 + vertex 0.964253 1.24333 2.63113 + vertex 0.966545 1.24068 2.63076 + endloop + endfacet + facet normal 0.0453798 -0.0943728 0.994502 + outer loop + vertex 0.97025 1.24189 2.63071 + vertex 0.969506 1.24443 2.63098 + vertex 0.966545 1.24068 2.63076 + endloop + endfacet + facet normal 0.0512468 -0.112415 0.992339 + outer loop + vertex 0.97025 1.24189 2.63071 + vertex 0.966545 1.24068 2.63076 + vertex 0.968576 1.23797 2.63035 + endloop + endfacet + facet normal 0.0541901 -0.113645 0.992042 + outer loop + vertex 0.97025 1.24189 2.63071 + vertex 0.968576 1.23797 2.63035 + vertex 0.973424 1.24192 2.63054 + endloop + endfacet + facet normal 0.054146 -0.0987627 0.993637 + outer loop + vertex 0.973424 1.24192 2.63054 + vertex 0.972819 1.24447 2.63083 + vertex 0.97025 1.24189 2.63071 + endloop + endfacet + facet normal 0.0570566 -0.0980628 0.993543 + outer loop + vertex 0.972819 1.24447 2.63083 + vertex 0.973424 1.24192 2.63054 + vertex 0.976427 1.2459 2.63076 + endloop + endfacet + facet normal 0.0501928 -0.0805976 0.995482 + outer loop + vertex 0.976427 1.2459 2.63076 + vertex 0.974184 1.24841 2.63108 + vertex 0.972819 1.24447 2.63083 + endloop + endfacet + facet normal 0.048573 -0.0800441 0.995607 + outer loop + vertex 0.972819 1.24447 2.63083 + vertex 0.974184 1.24841 2.63108 + vertex 0.969506 1.24443 2.63098 + endloop + endfacet + facet normal 0.0511103 -0.0797816 0.995501 + outer loop + vertex 0.979218 1.24993 2.63094 + vertex 0.974184 1.24841 2.63108 + vertex 0.976427 1.2459 2.63076 + endloop + endfacet + facet normal 0.0507092 -0.0795056 0.995544 + outer loop + vertex 0.980118 1.24756 2.6307 + vertex 0.979218 1.24993 2.63094 + vertex 0.976427 1.2459 2.63076 + endloop + endfacet + facet normal 0.0573054 -0.09424 0.993899 + outer loop + vertex 0.980118 1.24756 2.6307 + vertex 0.976427 1.2459 2.63076 + vertex 0.978525 1.24327 2.63039 + endloop + endfacet + facet normal 0.0790458 -0.102144 0.991624 + outer loop + vertex 0.980118 1.24756 2.6307 + vertex 0.978525 1.24327 2.63039 + vertex 0.98391 1.24835 2.63048 + endloop + endfacet + facet normal 0.0780602 -0.0972633 0.992193 + outer loop + vertex 0.98391 1.24835 2.63048 + vertex 0.982359 1.25041 2.63081 + vertex 0.980118 1.24756 2.6307 + endloop + endfacet + facet normal 0.0865677 -0.0908486 0.992095 + outer loop + vertex 0.985089 1.25228 2.63074 + vertex 0.982359 1.25041 2.63081 + vertex 0.98391 1.24835 2.63048 + endloop + endfacet + facet normal 0.141639 -0.106838 0.984136 + outer loop + vertex 0.985089 1.25228 2.63074 + vertex 0.98391 1.24835 2.63048 + vertex 0.988812 1.25344 2.63033 + endloop + endfacet + facet normal 0.141501 -0.106371 0.984207 + outer loop + vertex 0.988812 1.25344 2.63033 + vertex 0.986859 1.25513 2.63079 + vertex 0.985089 1.25228 2.63074 + endloop + endfacet + facet normal 0.0798891 -0.0683116 0.99446 + outer loop + vertex 0.986859 1.25513 2.63079 + vertex 0.983303 1.25399 2.631 + vertex 0.985089 1.25228 2.63074 + endloop + endfacet + facet normal 0.0787348 -0.0646695 0.994796 + outer loop + vertex 0.986859 1.25513 2.63079 + vertex 0.987174 1.25829 2.63097 + vertex 0.983303 1.25399 2.631 + endloop + endfacet + facet normal 0.0834978 -0.068952 0.99412 + outer loop + vertex 0.987174 1.25829 2.63097 + vertex 0.983336 1.25837 2.6313 + vertex 0.983303 1.25399 2.631 + endloop + endfacet + facet normal 0.0559312 -0.0688775 0.996056 + outer loop + vertex 0.983303 1.25399 2.631 + vertex 0.983336 1.25837 2.6313 + vertex 0.978728 1.25356 2.63123 + endloop + endfacet + facet normal 0.0561902 -0.0717541 0.995838 + outer loop + vertex 0.983303 1.25399 2.631 + vertex 0.978728 1.25356 2.63123 + vertex 0.979218 1.24993 2.63094 + endloop + endfacet + facet normal 0.0521955 -0.0677416 0.996337 + outer loop + vertex 0.982359 1.25041 2.63081 + vertex 0.983303 1.25399 2.631 + vertex 0.979218 1.24993 2.63094 + endloop + endfacet + facet normal 0.0490116 -0.072746 0.996146 + outer loop + vertex 0.979218 1.24993 2.63094 + vertex 0.978728 1.25356 2.63123 + vertex 0.974184 1.24841 2.63108 + endloop + endfacet + facet normal 0.0531786 -0.0764124 0.995657 + outer loop + vertex 0.974184 1.24841 2.63108 + vertex 0.978728 1.25356 2.63123 + vertex 0.97366 1.25303 2.63146 + endloop + endfacet + facet normal 0.0496695 -0.0768231 0.995807 + outer loop + vertex 0.974184 1.24841 2.63108 + vertex 0.97366 1.25303 2.63146 + vertex 0.968868 1.2482 2.63132 + endloop + endfacet + facet normal 0.0532318 -0.0769438 0.995613 + outer loop + vertex 0.978728 1.25356 2.63123 + vertex 0.978553 1.25807 2.63159 + vertex 0.97366 1.25303 2.63146 + endloop + endfacet + facet normal 0.0564462 -0.0800526 0.995191 + outer loop + vertex 0.97366 1.25303 2.63146 + vertex 0.978553 1.25807 2.63159 + vertex 0.973449 1.25784 2.63186 + endloop + endfacet + facet normal 0.0566187 -0.0842659 0.994833 + outer loop + vertex 0.978553 1.25807 2.63159 + vertex 0.978543 1.26297 2.632 + vertex 0.973449 1.25784 2.63186 + endloop + endfacet + facet normal 0.0709571 -0.0841589 0.993923 + outer loop + vertex 0.978553 1.25807 2.63159 + vertex 0.983489 1.26316 2.63166 + vertex 0.978543 1.26297 2.632 + endloop + endfacet + facet normal 0.071037 -0.0866351 0.993704 + outer loop + vertex 0.983489 1.26316 2.63166 + vertex 0.983517 1.26811 2.63209 + vertex 0.978543 1.26297 2.632 + endloop + endfacet + facet normal 0.0757177 -0.0911491 0.992955 + outer loop + vertex 0.978543 1.26297 2.632 + vertex 0.983517 1.26811 2.63209 + vertex 0.978578 1.26801 2.63246 + endloop + endfacet + facet normal 0.107519 -0.0865523 0.990428 + outer loop + vertex 0.983489 1.26316 2.63166 + vertex 0.988086 1.26814 2.6316 + vertex 0.983517 1.26811 2.63209 + endloop + endfacet + facet normal 0.107526 -0.0798526 0.99099 + outer loop + vertex 0.988086 1.26814 2.6316 + vertex 0.988129 1.27303 2.63199 + vertex 0.983517 1.26811 2.63209 + endloop + endfacet + facet normal 0.119373 -0.0910063 0.98867 + outer loop + vertex 0.983517 1.26811 2.63209 + vertex 0.988129 1.27303 2.63199 + vertex 0.983552 1.27312 2.63255 + endloop + endfacet + facet normal 0.0994171 -0.07907 0.991899 + outer loop + vertex 0.988336 1.26328 2.63119 + vertex 0.988086 1.26814 2.6316 + vertex 0.983489 1.26316 2.63166 + endloop + endfacet + facet normal 0.0994035 -0.0782715 0.991964 + outer loop + vertex 0.983336 1.25837 2.6313 + vertex 0.988336 1.26328 2.63119 + vertex 0.983489 1.26316 2.63166 + endloop + endfacet + facet normal 0.0639431 -0.0773626 0.99495 + outer loop + vertex 0.983336 1.25837 2.6313 + vertex 0.983489 1.26316 2.63166 + vertex 0.978553 1.25807 2.63159 + endloop + endfacet + facet normal 0.0638923 -0.0764818 0.995022 + outer loop + vertex 0.978728 1.25356 2.63123 + vertex 0.983336 1.25837 2.6313 + vertex 0.978553 1.25807 2.63159 + endloop + endfacet + facet normal 0.0836695 -0.0621743 0.994552 + outer loop + vertex 0.987174 1.25829 2.63097 + vertex 0.988336 1.26328 2.63119 + vertex 0.983336 1.25837 2.6313 + endloop + endfacet + facet normal 0.115899 -0.0818917 0.989879 + outer loop + vertex 0.988812 1.25344 2.63033 + vertex 0.98391 1.24835 2.63048 + vertex 0.988702 1.24829 2.62992 + endloop + endfacet + facet normal 0.115632 -0.0936395 0.988868 + outer loop + vertex 0.983609 1.24316 2.63003 + vertex 0.988702 1.24829 2.62992 + vertex 0.98391 1.24835 2.63048 + endloop + endfacet + facet normal 0.103048 -0.081083 0.991366 + outer loop + vertex 0.988582 1.24312 2.62951 + vertex 0.988702 1.24829 2.62992 + vertex 0.983609 1.24316 2.63003 + endloop + endfacet + facet normal 0.102701 -0.100916 0.98958 + outer loop + vertex 0.983482 1.23801 2.62951 + vertex 0.988582 1.24312 2.62951 + vertex 0.983609 1.24316 2.63003 + endloop + endfacet + facet normal 0.0646798 -0.100305 0.992852 + outer loop + vertex 0.983482 1.23801 2.62951 + vertex 0.983609 1.24316 2.63003 + vertex 0.97848 1.23805 2.62984 + endloop + endfacet + facet normal 0.0645094 -0.111923 0.991621 + outer loop + vertex 0.978396 1.23297 2.62928 + vertex 0.983482 1.23801 2.62951 + vertex 0.97848 1.23805 2.62984 + endloop + endfacet + facet normal 0.0505178 -0.111782 0.992448 + outer loop + vertex 0.978396 1.23297 2.62928 + vertex 0.97848 1.23805 2.62984 + vertex 0.973459 1.23303 2.62953 + endloop + endfacet + facet normal 0.0505658 -0.109017 0.992753 + outer loop + vertex 0.973391 1.22801 2.62899 + vertex 0.978396 1.23297 2.62928 + vertex 0.973459 1.23303 2.62953 + endloop + endfacet + facet normal 0.0483932 -0.108999 0.992863 + outer loop + vertex 0.973391 1.22801 2.62899 + vertex 0.973459 1.23303 2.62953 + vertex 0.968493 1.2281 2.62923 + endloop + endfacet + facet normal 0.0487735 -0.0932029 0.994452 + outer loop + vertex 0.968447 1.22307 2.62877 + vertex 0.973391 1.22801 2.62899 + vertex 0.968493 1.2281 2.62923 + endloop + endfacet + facet normal 0.0508716 -0.0952922 0.994149 + outer loop + vertex 0.97339 1.22301 2.62851 + vertex 0.973391 1.22801 2.62899 + vertex 0.968447 1.22307 2.62877 + endloop + endfacet + facet normal 0.0511814 -0.0772366 0.995698 + outer loop + vertex 0.968416 1.21806 2.62838 + vertex 0.97339 1.22301 2.62851 + vertex 0.968447 1.22307 2.62877 + endloop + endfacet + facet normal 0.0497828 -0.0772333 0.995769 + outer loop + vertex 0.968416 1.21806 2.62838 + vertex 0.968447 1.22307 2.62877 + vertex 0.963491 1.21812 2.62863 + endloop + endfacet + facet normal 0.0499063 -0.0773563 0.995754 + outer loop + vertex 0.963491 1.21812 2.62863 + vertex 0.968447 1.22307 2.62877 + vertex 0.963547 1.22316 2.62902 + endloop + endfacet + facet normal 0.0468925 -0.0773344 0.995902 + outer loop + vertex 0.963491 1.21812 2.62863 + vertex 0.963547 1.22316 2.62902 + vertex 0.958546 1.21817 2.62887 + endloop + endfacet + facet normal 0.0476402 -0.0780807 0.995808 + outer loop + vertex 0.958546 1.21817 2.62887 + vertex 0.963547 1.22316 2.62902 + vertex 0.958644 1.22324 2.62926 + endloop + endfacet + facet normal 0.0383396 -0.0779319 0.996221 + outer loop + vertex 0.958546 1.21817 2.62887 + vertex 0.958644 1.22324 2.62926 + vertex 0.953552 1.21819 2.62906 + endloop + endfacet + facet normal 0.0365414 -0.076128 0.996428 + outer loop + vertex 0.953552 1.21819 2.62906 + vertex 0.958644 1.22324 2.62926 + vertex 0.953686 1.22326 2.62944 + endloop + endfacet + facet normal 0.0162909 -0.0756366 0.997002 + outer loop + vertex 0.953552 1.21819 2.62906 + vertex 0.953686 1.22326 2.62944 + vertex 0.948498 1.21815 2.62914 + endloop + endfacet + facet normal 0.0114167 -0.0707092 0.997432 + outer loop + vertex 0.948498 1.21815 2.62914 + vertex 0.953686 1.22326 2.62944 + vertex 0.948673 1.22315 2.62949 + endloop + endfacet + facet normal 0.0118504 -0.0912427 0.995758 + outer loop + vertex 0.953686 1.22326 2.62944 + vertex 0.953648 1.22806 2.62988 + vertex 0.948673 1.22315 2.62949 + endloop + endfacet + facet normal 0.011414 -0.0908049 0.995803 + outer loop + vertex 0.948673 1.22315 2.62949 + vertex 0.953648 1.22806 2.62988 + vertex 0.948556 1.22771 2.62991 + endloop + endfacet + facet normal -0.0286701 -0.0917936 0.995365 + outer loop + vertex 0.948673 1.22315 2.62949 + vertex 0.948556 1.22771 2.62991 + vertex 0.943682 1.22303 2.62934 + endloop + endfacet + facet normal -0.0293518 -0.065296 0.997434 + outer loop + vertex 0.943428 1.21809 2.62901 + vertex 0.948673 1.22315 2.62949 + vertex 0.943682 1.22303 2.62934 + endloop + endfacet + facet normal -0.0841094 -0.0622873 0.994508 + outer loop + vertex 0.943428 1.21809 2.62901 + vertex 0.943682 1.22303 2.62934 + vertex 0.938527 1.21826 2.6286 + endloop + endfacet + facet normal -0.0785214 -0.0683327 0.994568 + outer loop + vertex 0.938527 1.21826 2.6286 + vertex 0.943682 1.22303 2.62934 + vertex 0.938906 1.22313 2.62897 + endloop + endfacet + facet normal -0.078982 -0.0981293 0.992035 + outer loop + vertex 0.943682 1.22303 2.62934 + vertex 0.943529 1.22753 2.62977 + vertex 0.938906 1.22313 2.62897 + endloop + endfacet + facet normal -0.0701292 -0.107392 0.99174 + outer loop + vertex 0.938906 1.22313 2.62897 + vertex 0.943529 1.22753 2.62977 + vertex 0.938443 1.22764 2.62942 + endloop + endfacet + facet normal -0.070542 -0.135525 0.98826 + outer loop + vertex 0.943529 1.22753 2.62977 + vertex 0.942713 1.23167 2.63028 + vertex 0.938443 1.22764 2.62942 + endloop + endfacet + facet normal -0.0681934 -0.137981 0.988085 + outer loop + vertex 0.938443 1.22764 2.62942 + vertex 0.942713 1.23167 2.63028 + vertex 0.937048 1.23241 2.62999 + endloop + endfacet + facet normal -0.0699746 -0.152404 0.985838 + outer loop + vertex 0.937048 1.23241 2.62999 + vertex 0.942713 1.23167 2.63028 + vertex 0.941562 1.23566 2.63082 + endloop + endfacet + facet normal -0.0638793 -0.160651 0.984942 + outer loop + vertex 0.937312 1.23657 2.63069 + vertex 0.937048 1.23241 2.62999 + vertex 0.941562 1.23566 2.63082 + endloop + endfacet + facet normal -0.0253679 -0.0694115 0.997266 + outer loop + vertex 0.948498 1.21815 2.62914 + vertex 0.948673 1.22315 2.62949 + vertex 0.943428 1.21809 2.62901 + endloop + endfacet + facet normal -0.0240667 -0.0965508 0.995037 + outer loop + vertex 0.943682 1.22303 2.62934 + vertex 0.948556 1.22771 2.62991 + vertex 0.943529 1.22753 2.62977 + endloop + endfacet + facet normal -0.0230634 -0.122469 0.992204 + outer loop + vertex 0.948556 1.22771 2.62991 + vertex 0.947875 1.23168 2.63038 + vertex 0.943529 1.22753 2.62977 + endloop + endfacet + facet normal 0.0157169 -0.115943 0.993132 + outer loop + vertex 0.948556 1.22771 2.62991 + vertex 0.952947 1.23214 2.63036 + vertex 0.947875 1.23168 2.63038 + endloop + endfacet + facet normal 0.0129802 -0.113268 0.99348 + outer loop + vertex 0.953648 1.22806 2.62988 + vertex 0.952947 1.23214 2.63036 + vertex 0.948556 1.22771 2.62991 + endloop + endfacet + facet normal 0.0351307 -0.0910113 0.99523 + outer loop + vertex 0.953686 1.22326 2.62944 + vertex 0.958708 1.22824 2.62972 + vertex 0.953648 1.22806 2.62988 + endloop + endfacet + facet normal 0.0357242 -0.10967 0.993326 + outer loop + vertex 0.958708 1.22824 2.62972 + vertex 0.958562 1.23319 2.63027 + vertex 0.953648 1.22806 2.62988 + endloop + endfacet + facet normal 0.0468057 -0.109297 0.992906 + outer loop + vertex 0.958708 1.22824 2.62972 + vertex 0.963662 1.23301 2.63001 + vertex 0.958562 1.23319 2.63027 + endloop + endfacet + facet normal 0.0364567 -0.0923372 0.99506 + outer loop + vertex 0.958644 1.22324 2.62926 + vertex 0.958708 1.22824 2.62972 + vertex 0.953686 1.22326 2.62944 + endloop + endfacet + facet normal 0.0466149 -0.0924265 0.994628 + outer loop + vertex 0.958644 1.22324 2.62926 + vertex 0.963627 1.22818 2.62948 + vertex 0.958708 1.22824 2.62972 + endloop + endfacet + facet normal 0.0463397 -0.108818 0.992981 + outer loop + vertex 0.963627 1.22818 2.62948 + vertex 0.963662 1.23301 2.63001 + vertex 0.958708 1.22824 2.62972 + endloop + endfacet + facet normal 0.0490365 -0.108823 0.992851 + outer loop + vertex 0.963627 1.22818 2.62948 + vertex 0.968586 1.23308 2.62978 + vertex 0.963662 1.23301 2.63001 + endloop + endfacet + facet normal 0.0491016 -0.116321 0.991997 + outer loop + vertex 0.968586 1.23308 2.62978 + vertex 0.968576 1.23797 2.63035 + vertex 0.963662 1.23301 2.63001 + endloop + endfacet + facet normal 0.0507133 -0.117901 0.99173 + outer loop + vertex 0.963662 1.23301 2.63001 + vertex 0.968576 1.23797 2.63035 + vertex 0.963499 1.23697 2.63049 + endloop + endfacet + facet normal 0.0512521 -0.116305 0.99189 + outer loop + vertex 0.968586 1.23308 2.62978 + vertex 0.973538 1.23792 2.63009 + vertex 0.968576 1.23797 2.63035 + endloop + endfacet + facet normal 0.0482515 -0.113264 0.992393 + outer loop + vertex 0.973459 1.23303 2.62953 + vertex 0.973538 1.23792 2.63009 + vertex 0.968586 1.23308 2.62978 + endloop + endfacet + facet normal 0.0491524 -0.108939 0.992832 + outer loop + vertex 0.968493 1.2281 2.62923 + vertex 0.968586 1.23308 2.62978 + vertex 0.963627 1.22818 2.62948 + endloop + endfacet + facet normal 0.0495059 -0.0931522 0.99442 + outer loop + vertex 0.963547 1.22316 2.62902 + vertex 0.968493 1.2281 2.62923 + vertex 0.963627 1.22818 2.62948 + endloop + endfacet + facet normal 0.0473138 -0.0931273 0.994529 + outer loop + vertex 0.963547 1.22316 2.62902 + vertex 0.963627 1.22818 2.62948 + vertex 0.958644 1.22324 2.62926 + endloop + endfacet + facet normal 0.0495604 -0.0932064 0.994413 + outer loop + vertex 0.968447 1.22307 2.62877 + vertex 0.968493 1.2281 2.62923 + vertex 0.963547 1.22316 2.62902 + endloop + endfacet + facet normal 0.0526874 -0.0787449 0.995502 + outer loop + vertex 0.973364 1.21801 2.62811 + vertex 0.97339 1.22301 2.62851 + vertex 0.968416 1.21806 2.62838 + endloop + endfacet + facet normal 0.0557291 -0.0787476 0.995336 + outer loop + vertex 0.973364 1.21801 2.62811 + vertex 0.978418 1.22301 2.62823 + vertex 0.97339 1.22301 2.62851 + endloop + endfacet + facet normal 0.0556281 -0.098405 0.99359 + outer loop + vertex 0.978418 1.22301 2.62823 + vertex 0.978389 1.22796 2.62872 + vertex 0.97339 1.22301 2.62851 + endloop + endfacet + facet normal 0.0663862 -0.0982786 0.992942 + outer loop + vertex 0.978418 1.22301 2.62823 + vertex 0.983493 1.22804 2.62838 + vertex 0.978389 1.22796 2.62872 + endloop + endfacet + facet normal 0.0664838 -0.112597 0.991414 + outer loop + vertex 0.983493 1.22804 2.62838 + vertex 0.983455 1.23298 2.62895 + vertex 0.978389 1.22796 2.62872 + endloop + endfacet + facet normal 0.0645795 -0.110687 0.991755 + outer loop + vertex 0.978389 1.22796 2.62872 + vertex 0.983455 1.23298 2.62895 + vertex 0.978396 1.23297 2.62928 + endloop + endfacet + facet normal 0.0943448 -0.11213 0.989205 + outer loop + vertex 0.983493 1.22804 2.62838 + vertex 0.988569 1.23311 2.62847 + vertex 0.983455 1.23298 2.62895 + endloop + endfacet + facet normal 0.0942911 -0.10863 0.9896 + outer loop + vertex 0.988569 1.23311 2.62847 + vertex 0.988541 1.23806 2.62902 + vertex 0.983455 1.23298 2.62895 + endloop + endfacet + facet normal 0.09753 -0.111861 0.988926 + outer loop + vertex 0.983455 1.23298 2.62895 + vertex 0.988541 1.23806 2.62902 + vertex 0.983482 1.23801 2.62951 + endloop + endfacet + facet normal 0.144705 -0.107689 0.983597 + outer loop + vertex 0.988569 1.23311 2.62847 + vertex 0.993485 1.23817 2.62831 + vertex 0.988541 1.23806 2.62902 + endloop + endfacet + facet normal 0.144528 -0.08706 0.985663 + outer loop + vertex 0.993485 1.23817 2.62831 + vertex 0.993472 1.24313 2.62875 + vertex 0.988541 1.23806 2.62902 + endloop + endfacet + facet normal 0.15313 -0.0955384 0.983577 + outer loop + vertex 0.988541 1.23806 2.62902 + vertex 0.993472 1.24313 2.62875 + vertex 0.988582 1.24312 2.62951 + endloop + endfacet + facet normal 0.153443 -0.0675116 0.985849 + outer loop + vertex 0.993472 1.24313 2.62875 + vertex 0.993493 1.2482 2.62909 + vertex 0.988582 1.24312 2.62951 + endloop + endfacet + facet normal 0.135313 -0.0984997 0.985895 + outer loop + vertex 0.993551 1.23324 2.6278 + vertex 0.993485 1.23817 2.62831 + vertex 0.988569 1.23311 2.62847 + endloop + endfacet + facet normal 0.135413 -0.106402 0.985059 + outer loop + vertex 0.988587 1.22818 2.62794 + vertex 0.993551 1.23324 2.6278 + vertex 0.988569 1.23311 2.62847 + endloop + endfacet + facet normal 0.120915 -0.0920942 0.988382 + outer loop + vertex 0.993436 1.22816 2.62734 + vertex 0.993551 1.23324 2.6278 + vertex 0.988587 1.22818 2.62794 + endloop + endfacet + facet normal 0.120904 -0.0927651 0.98832 + outer loop + vertex 0.988527 1.22318 2.62748 + vertex 0.993436 1.22816 2.62734 + vertex 0.988587 1.22818 2.62794 + endloop + endfacet + facet normal 0.0831368 -0.0926747 0.99222 + outer loop + vertex 0.988527 1.22318 2.62748 + vertex 0.988587 1.22818 2.62794 + vertex 0.983512 1.2231 2.62789 + endloop + endfacet + facet normal 0.0830322 -0.0824938 0.993127 + outer loop + vertex 0.983471 1.21807 2.62748 + vertex 0.988527 1.22318 2.62748 + vertex 0.983512 1.2231 2.62789 + endloop + endfacet + facet normal 0.067364 -0.0824654 0.994315 + outer loop + vertex 0.983471 1.21807 2.62748 + vertex 0.983512 1.2231 2.62789 + vertex 0.978388 1.21801 2.62782 + endloop + endfacet + facet normal 0.0668627 -0.081962 0.99439 + outer loop + vertex 0.978388 1.21801 2.62782 + vertex 0.983512 1.2231 2.62789 + vertex 0.978418 1.22301 2.62823 + endloop + endfacet + facet normal 0.0766838 -0.0762189 0.994138 + outer loop + vertex 0.988447 1.21812 2.6271 + vertex 0.988527 1.22318 2.62748 + vertex 0.983471 1.21807 2.62748 + endloop + endfacet + facet normal 0.104203 -0.0764628 0.991612 + outer loop + vertex 0.988447 1.21812 2.6271 + vertex 0.993178 1.22301 2.62698 + vertex 0.988527 1.22318 2.62748 + endloop + endfacet + facet normal 0.0906106 -0.0632624 0.993875 + outer loop + vertex 0.993049 1.21797 2.62667 + vertex 0.993178 1.22301 2.62698 + vertex 0.988447 1.21812 2.6271 + endloop + endfacet + facet normal 0.0891694 -0.0986863 0.991115 + outer loop + vertex 0.983512 1.2231 2.62789 + vertex 0.988587 1.22818 2.62794 + vertex 0.983493 1.22804 2.62838 + endloop + endfacet + facet normal 0.104215 -0.0762101 0.991631 + outer loop + vertex 0.993178 1.22301 2.62698 + vertex 0.993436 1.22816 2.62734 + vertex 0.988527 1.22318 2.62748 + endloop + endfacet + facet normal 0.0893302 -0.10713 0.990224 + outer loop + vertex 0.988587 1.22818 2.62794 + vertex 0.988569 1.23311 2.62847 + vertex 0.983493 1.22804 2.62838 + endloop + endfacet + facet normal 0.0670458 -0.0989413 0.992832 + outer loop + vertex 0.983512 1.2231 2.62789 + vertex 0.983493 1.22804 2.62838 + vertex 0.978418 1.22301 2.62823 + endloop + endfacet + facet normal 0.0589134 -0.0819568 0.994893 + outer loop + vertex 0.978388 1.21801 2.62782 + vertex 0.978418 1.22301 2.62823 + vertex 0.973364 1.21801 2.62811 + endloop + endfacet + facet normal 0.0525157 -0.0952844 0.994064 + outer loop + vertex 0.97339 1.22301 2.62851 + vertex 0.978389 1.22796 2.62872 + vertex 0.973391 1.22801 2.62899 + endloop + endfacet + facet normal 0.0483223 -0.108929 0.992874 + outer loop + vertex 0.968493 1.2281 2.62923 + vertex 0.973459 1.23303 2.62953 + vertex 0.968586 1.23308 2.62978 + endloop + endfacet + facet normal 0.0523034 -0.110751 0.992471 + outer loop + vertex 0.978389 1.22796 2.62872 + vertex 0.978396 1.23297 2.62928 + vertex 0.973391 1.22801 2.62899 + endloop + endfacet + facet normal 0.0520548 -0.113303 0.992196 + outer loop + vertex 0.973459 1.23303 2.62953 + vertex 0.97848 1.23805 2.62984 + vertex 0.973538 1.23792 2.63009 + endloop + endfacet + facet normal 0.0518567 -0.104028 0.993222 + outer loop + vertex 0.97848 1.23805 2.62984 + vertex 0.978525 1.24327 2.63039 + vertex 0.973538 1.23792 2.63009 + endloop + endfacet + facet normal 0.058268 -0.109949 0.992228 + outer loop + vertex 0.973538 1.23792 2.63009 + vertex 0.978525 1.24327 2.63039 + vertex 0.973424 1.24192 2.63054 + endloop + endfacet + facet normal 0.064571 -0.111984 0.99161 + outer loop + vertex 0.983455 1.23298 2.62895 + vertex 0.983482 1.23801 2.62951 + vertex 0.978396 1.23297 2.62928 + endloop + endfacet + facet normal 0.0684513 -0.104066 0.992212 + outer loop + vertex 0.97848 1.23805 2.62984 + vertex 0.983609 1.24316 2.63003 + vertex 0.978525 1.24327 2.63039 + endloop + endfacet + facet normal 0.0975421 -0.095766 0.990613 + outer loop + vertex 0.988541 1.23806 2.62902 + vertex 0.988582 1.24312 2.62951 + vertex 0.983482 1.23801 2.62951 + endloop + endfacet + facet normal 0.167997 -0.0818752 0.982382 + outer loop + vertex 0.988582 1.24312 2.62951 + vertex 0.993493 1.2482 2.62909 + vertex 0.988702 1.24829 2.62992 + endloop + endfacet + facet normal 0.168705 -0.0583041 0.983941 + outer loop + vertex 0.993493 1.2482 2.62909 + vertex 0.993541 1.2534 2.62939 + vertex 0.988702 1.24829 2.62992 + endloop + endfacet + facet normal 0.193653 -0.0825669 0.977589 + outer loop + vertex 0.988702 1.24829 2.62992 + vertex 0.993541 1.2534 2.62939 + vertex 0.988812 1.25344 2.63033 + endloop + endfacet + facet normal 0.19397 -0.0686696 0.978601 + outer loop + vertex 0.993556 1.25888 2.62977 + vertex 0.988812 1.25344 2.63033 + vertex 0.993541 1.2534 2.62939 + endloop + endfacet + facet normal 0.23475 -0.105472 0.966317 + outer loop + vertex 0.989588 1.25747 2.63058 + vertex 0.988812 1.25344 2.63033 + vertex 0.993556 1.25888 2.62977 + endloop + endfacet + facet normal 0.231881 -0.0964674 0.967949 + outer loop + vertex 0.989588 1.25747 2.63058 + vertex 0.993556 1.25888 2.62977 + vertex 0.991079 1.2613 2.63061 + endloop + endfacet + facet normal 0.140036 -0.0607988 0.988278 + outer loop + vertex 0.991079 1.2613 2.63061 + vertex 0.987174 1.25829 2.63097 + vertex 0.989588 1.25747 2.63058 + endloop + endfacet + facet normal 0.136857 -0.0700615 0.98811 + outer loop + vertex 0.989588 1.25747 2.63058 + vertex 0.987174 1.25829 2.63097 + vertex 0.986859 1.25513 2.63079 + endloop + endfacet + facet normal 0.246606 -0.0806102 0.965758 + outer loop + vertex 0.993556 1.25888 2.62977 + vertex 0.994814 1.26434 2.6299 + vertex 0.991079 1.2613 2.63061 + endloop + endfacet + facet normal 0.265359 -0.105377 0.958374 + outer loop + vertex 0.994814 1.26434 2.6299 + vertex 0.992312 1.26506 2.63068 + vertex 0.991079 1.2613 2.63061 + endloop + endfacet + facet normal 0.15806 -0.0707221 0.984894 + outer loop + vertex 0.992312 1.26506 2.63068 + vertex 0.988336 1.26328 2.63119 + vertex 0.991079 1.2613 2.63061 + endloop + endfacet + facet normal 0.152921 -0.0779319 0.985161 + outer loop + vertex 0.988336 1.26328 2.63119 + vertex 0.987174 1.25829 2.63097 + vertex 0.991079 1.2613 2.63061 + endloop + endfacet + facet normal 0.159091 -0.073117 0.984553 + outer loop + vertex 0.992312 1.26506 2.63068 + vertex 0.991984 1.26817 2.63096 + vertex 0.988336 1.26328 2.63119 + endloop + endfacet + facet normal 0.161832 -0.0751883 0.98395 + outer loop + vertex 0.991984 1.26817 2.63096 + vertex 0.988086 1.26814 2.6316 + vertex 0.988336 1.26328 2.63119 + endloop + endfacet + facet normal 0.16189 -0.0629817 0.984797 + outer loop + vertex 0.991984 1.26817 2.63096 + vertex 0.992128 1.27259 2.63122 + vertex 0.988086 1.26814 2.6316 + endloop + endfacet + facet normal 0.179808 -0.0796502 0.980472 + outer loop + vertex 0.988086 1.26814 2.6316 + vertex 0.992128 1.27259 2.63122 + vertex 0.988129 1.27303 2.63199 + endloop + endfacet + facet normal 0.181219 -0.0679079 0.981095 + outer loop + vertex 0.992128 1.27259 2.63122 + vertex 0.99229 1.27744 2.63153 + vertex 0.988129 1.27303 2.63199 + endloop + endfacet + facet normal 0.154595 -0.0911308 0.983766 + outer loop + vertex 0.989588 1.25747 2.63058 + vertex 0.986859 1.25513 2.63079 + vertex 0.988812 1.25344 2.63033 + endloop + endfacet + facet normal 0.0748249 -0.0736188 0.994475 + outer loop + vertex 0.985089 1.25228 2.63074 + vertex 0.983303 1.25399 2.631 + vertex 0.982359 1.25041 2.63081 + endloop + endfacet + facet normal 0.0688006 -0.0913207 0.993442 + outer loop + vertex 0.98391 1.24835 2.63048 + vertex 0.978525 1.24327 2.63039 + vertex 0.983609 1.24316 2.63003 + endloop + endfacet + facet normal 0.0537925 -0.0783276 0.995475 + outer loop + vertex 0.982359 1.25041 2.63081 + vertex 0.979218 1.24993 2.63094 + vertex 0.980118 1.24756 2.6307 + endloop + endfacet + facet normal 0.0547051 -0.0963062 0.993847 + outer loop + vertex 0.973424 1.24192 2.63054 + vertex 0.978525 1.24327 2.63039 + vertex 0.976427 1.2459 2.63076 + endloop + endfacet + facet normal 0.051353 -0.110186 0.992583 + outer loop + vertex 0.973424 1.24192 2.63054 + vertex 0.968576 1.23797 2.63035 + vertex 0.973538 1.23792 2.63009 + endloop + endfacet + facet normal 0.049854 -0.113453 0.992292 + outer loop + vertex 0.963499 1.23697 2.63049 + vertex 0.968576 1.23797 2.63035 + vertex 0.966545 1.24068 2.63076 + endloop + endfacet + facet normal 0.0487065 -0.0933906 0.994437 + outer loop + vertex 0.972819 1.24447 2.63083 + vertex 0.969506 1.24443 2.63098 + vertex 0.97025 1.24189 2.63071 + endloop + endfacet + facet normal 0.0498378 -0.0815242 0.995425 + outer loop + vertex 0.974184 1.24841 2.63108 + vertex 0.968868 1.2482 2.63132 + vertex 0.969506 1.24443 2.63098 + endloop + endfacet + facet normal 0.052141 -0.0792668 0.995489 + outer loop + vertex 0.968868 1.2482 2.63132 + vertex 0.97366 1.25303 2.63146 + vertex 0.968419 1.25282 2.63172 + endloop + endfacet + facet normal 0.0521774 -0.0802582 0.995408 + outer loop + vertex 0.97366 1.25303 2.63146 + vertex 0.973449 1.25784 2.63186 + vertex 0.968419 1.25282 2.63172 + endloop + endfacet + facet normal 0.0581751 -0.0858064 0.994612 + outer loop + vertex 0.973449 1.25784 2.63186 + vertex 0.978543 1.26297 2.632 + vertex 0.973452 1.26287 2.63229 + endloop + endfacet + facet normal 0.058243 -0.0911334 0.994134 + outer loop + vertex 0.978543 1.26297 2.632 + vertex 0.978578 1.26801 2.63246 + vertex 0.973452 1.26287 2.63229 + endloop + endfacet + facet normal 0.060163 -0.0981141 0.993355 + outer loop + vertex 0.973502 1.26794 2.63276 + vertex 0.978589 1.27304 2.63295 + vertex 0.973487 1.27294 2.63325 + endloop + endfacet + facet normal 0.0757169 -0.0910924 0.99296 + outer loop + vertex 0.983517 1.26811 2.63209 + vertex 0.983552 1.27312 2.63255 + vertex 0.978578 1.26801 2.63246 + endloop + endfacet + facet normal 0.0871527 -0.0998903 0.991174 + outer loop + vertex 0.978589 1.27304 2.63295 + vertex 0.983552 1.27812 2.63303 + vertex 0.978537 1.27802 2.63346 + endloop + endfacet + facet normal 0.119599 -0.0836759 0.98929 + outer loop + vertex 0.988129 1.27303 2.63199 + vertex 0.988196 1.278 2.6324 + vertex 0.983552 1.27312 2.63255 + endloop + endfacet + facet normal 0.08707 -0.093055 0.991847 + outer loop + vertex 0.983552 1.27812 2.63303 + vertex 0.983515 1.28307 2.6335 + vertex 0.978537 1.27802 2.63346 + endloop + endfacet + facet normal 0.0601915 -0.100373 0.993128 + outer loop + vertex 0.978589 1.27304 2.63295 + vertex 0.978537 1.27802 2.63346 + vertex 0.973487 1.27294 2.63325 + endloop + endfacet + facet normal 0.0507922 -0.0981944 0.99387 + outer loop + vertex 0.973502 1.26794 2.63276 + vertex 0.973487 1.27294 2.63325 + vertex 0.968459 1.26796 2.63302 + endloop + endfacet + facet normal 0.0508437 -0.0910765 0.994545 + outer loop + vertex 0.968395 1.26291 2.63256 + vertex 0.973502 1.26794 2.63276 + vertex 0.968459 1.26796 2.63302 + endloop + endfacet + facet normal 0.0489541 -0.0850801 0.995171 + outer loop + vertex 0.968312 1.25781 2.63213 + vertex 0.968395 1.26291 2.63256 + vertex 0.963275 1.25788 2.63238 + endloop + endfacet + facet normal 0.0490322 -0.0808429 0.99552 + outer loop + vertex 0.963247 1.25277 2.63197 + vertex 0.968312 1.25781 2.63213 + vertex 0.963275 1.25788 2.63238 + endloop + endfacet + facet normal 0.0442374 -0.0809845 0.995733 + outer loop + vertex 0.963576 1.24793 2.63156 + vertex 0.963247 1.25277 2.63197 + vertex 0.958406 1.24783 2.63178 + endloop + endfacet + facet normal 0.0443166 -0.0857956 0.995327 + outer loop + vertex 0.95906 1.24342 2.63137 + vertex 0.963576 1.24793 2.63156 + vertex 0.958406 1.24783 2.63178 + endloop + endfacet + facet normal 0.0447442 -0.0862218 0.995271 + outer loop + vertex 0.964253 1.24333 2.63113 + vertex 0.963576 1.24793 2.63156 + vertex 0.95906 1.24342 2.63137 + endloop + endfacet + facet normal 0.0459962 -0.0977063 0.994152 + outer loop + vertex 0.966545 1.24068 2.63076 + vertex 0.964253 1.24333 2.63113 + vertex 0.962877 1.23955 2.63082 + endloop + endfacet + facet normal 0.0511047 -0.114467 0.992112 + outer loop + vertex 0.962877 1.23955 2.63082 + vertex 0.963499 1.23697 2.63049 + vertex 0.966545 1.24068 2.63076 + endloop + endfacet + facet normal 0.0464496 -0.118098 0.991915 + outer loop + vertex 0.963499 1.23697 2.63049 + vertex 0.958562 1.23319 2.63027 + vertex 0.963662 1.23301 2.63001 + endloop + endfacet + facet normal 0.0415769 -0.111285 0.992918 + outer loop + vertex 0.960273 1.23715 2.63067 + vertex 0.959661 1.23976 2.63099 + vertex 0.956448 1.23619 2.63072 + endloop + endfacet + facet normal 0.0354333 -0.109394 0.993367 + outer loop + vertex 0.953648 1.22806 2.62988 + vertex 0.958562 1.23319 2.63027 + vertex 0.952947 1.23214 2.63036 + endloop + endfacet + facet normal 0.0418824 -0.111556 0.992875 + outer loop + vertex 0.959661 1.23976 2.63099 + vertex 0.955147 1.23939 2.63114 + vertex 0.956448 1.23619 2.63072 + endloop + endfacet + facet normal 0.0312892 -0.0982607 0.994669 + outer loop + vertex 0.955147 1.23939 2.63114 + vertex 0.954047 1.24319 2.63155 + vertex 0.95025 1.23905 2.63126 + endloop + endfacet + facet normal 0.0167464 -0.127405 0.991709 + outer loop + vertex 0.947875 1.23168 2.63038 + vertex 0.952947 1.23214 2.63036 + vertex 0.951657 1.23557 2.63082 + endloop + endfacet + facet normal -0.0196886 -0.125946 0.991842 + outer loop + vertex 0.943529 1.22753 2.62977 + vertex 0.947875 1.23168 2.63038 + vertex 0.942713 1.23167 2.63028 + endloop + endfacet + facet normal 0.0106983 -0.113951 0.993429 + outer loop + vertex 0.95025 1.23905 2.63126 + vertex 0.945187 1.23911 2.63132 + vertex 0.946661 1.23531 2.63087 + endloop + endfacet + facet normal -0.057783 -0.131504 0.98963 + outer loop + vertex 0.941562 1.23566 2.63082 + vertex 0.939768 1.24001 2.63129 + vertex 0.937312 1.23657 2.63069 + endloop + endfacet + facet normal 0.00741482 -0.0965682 0.995299 + outer loop + vertex 0.945187 1.23911 2.63132 + vertex 0.949036 1.24305 2.63167 + vertex 0.944109 1.2433 2.63173 + endloop + endfacet + facet normal 0.00523667 -0.0831059 0.996527 + outer loop + vertex 0.944109 1.2433 2.63173 + vertex 0.948336 1.24765 2.63207 + vertex 0.943533 1.24783 2.63211 + endloop + endfacet + facet normal 0.0053301 -0.080664 0.996727 + outer loop + vertex 0.948336 1.24765 2.63207 + vertex 0.948126 1.25265 2.63248 + vertex 0.943533 1.24783 2.63211 + endloop + endfacet + facet normal 0.0244019 -0.0829487 0.996255 + outer loop + vertex 0.948126 1.25265 2.63248 + vertex 0.953274 1.25788 2.63279 + vertex 0.948195 1.25779 2.63291 + endloop + endfacet + facet normal 0.00373402 -0.0896592 0.995966 + outer loop + vertex 0.943146 1.25771 2.63291 + vertex 0.948322 1.26291 2.63336 + vertex 0.943218 1.26281 2.63337 + endloop + endfacet + facet normal 0.0244768 -0.0874879 0.995865 + outer loop + vertex 0.953274 1.25788 2.63279 + vertex 0.953425 1.263 2.63323 + vertex 0.948195 1.25779 2.63291 + endloop + endfacet + facet normal 0.0283416 -0.0954633 0.995029 + outer loop + vertex 0.948322 1.26291 2.63336 + vertex 0.953497 1.26805 2.63371 + vertex 0.948443 1.26802 2.63385 + endloop + endfacet + facet normal 0.0396277 -0.0917857 0.99499 + outer loop + vertex 0.95846 1.26303 2.63304 + vertex 0.958511 1.26804 2.6335 + vertex 0.953425 1.263 2.63323 + endloop + endfacet + facet normal 0.0426734 -0.0977407 0.994297 + outer loop + vertex 0.953497 1.26805 2.63371 + vertex 0.9585 1.27304 2.63398 + vertex 0.953563 1.2731 2.6342 + endloop + endfacet + facet normal 0.0464779 -0.0964497 0.994252 + outer loop + vertex 0.963482 1.268 2.63326 + vertex 0.963442 1.27296 2.63374 + vertex 0.958511 1.26804 2.6335 + endloop + endfacet + facet normal 0.0462687 -0.0986693 0.994044 + outer loop + vertex 0.9585 1.27304 2.63398 + vertex 0.963434 1.27798 2.63425 + vertex 0.958565 1.27808 2.63448 + endloop + endfacet + facet normal 0.0469894 -0.100684 0.993808 + outer loop + vertex 0.968424 1.27292 2.6335 + vertex 0.968371 1.27791 2.63401 + vertex 0.963442 1.27296 2.63374 + endloop + endfacet + facet normal 0.0443251 -0.0986044 0.994139 + outer loop + vertex 0.963434 1.27798 2.63425 + vertex 0.968418 1.28296 2.63452 + vertex 0.963549 1.28302 2.63474 + endloop + endfacet + facet normal 0.0485378 -0.101512 0.99365 + outer loop + vertex 0.973419 1.27791 2.63377 + vertex 0.973392 1.28292 2.63428 + vertex 0.968371 1.27791 2.63401 + endloop + endfacet + facet normal 0.0462487 -0.095724 0.994333 + outer loop + vertex 0.968418 1.28296 2.63452 + vertex 0.973467 1.28796 2.63476 + vertex 0.968555 1.28797 2.63499 + endloop + endfacet + facet normal 0.0462756 -0.0910345 0.994772 + outer loop + vertex 0.973467 1.28796 2.63476 + vertex 0.973554 1.29287 2.63521 + vertex 0.968555 1.28797 2.63499 + endloop + endfacet + facet normal 0.0627911 -0.0958074 0.993417 + outer loop + vertex 0.978479 1.28298 2.63396 + vertex 0.978484 1.28799 2.63445 + vertex 0.973392 1.28292 2.63428 + endloop + endfacet + facet normal 0.0649131 -0.0912665 0.993709 + outer loop + vertex 0.973467 1.28796 2.63476 + vertex 0.978554 1.29306 2.6349 + vertex 0.973554 1.29287 2.63521 + endloop + endfacet + facet normal 0.101358 -0.0817378 0.991486 + outer loop + vertex 0.983516 1.28804 2.63394 + vertex 0.983574 1.29308 2.63435 + vertex 0.978484 1.28799 2.63445 + endloop + endfacet + facet normal 0.170317 -0.0678349 0.983052 + outer loop + vertex 0.988461 1.29299 2.63349 + vertex 0.988562 1.29814 2.63383 + vertex 0.983574 1.29308 2.63435 + endloop + endfacet + facet normal 0.116196 -0.0905655 0.989089 + outer loop + vertex 0.978554 1.29306 2.6349 + vertex 0.98366 1.29821 2.63477 + vertex 0.978543 1.29826 2.63538 + endloop + endfacet + facet normal 0.0659916 -0.0949603 0.993291 + outer loop + vertex 0.980029 1.30249 2.6357 + vertex 0.978976 1.30475 2.63599 + vertex 0.976398 1.30089 2.63579 + endloop + endfacet + facet normal 0.0649077 -0.0910951 0.993725 + outer loop + vertex 0.978554 1.29306 2.6349 + vertex 0.978543 1.29826 2.63538 + vertex 0.973554 1.29287 2.63521 + endloop + endfacet + facet normal 0.0457457 -0.0904979 0.994845 + outer loop + vertex 0.968555 1.28797 2.63499 + vertex 0.973554 1.29287 2.63521 + vertex 0.968611 1.29289 2.63544 + endloop + endfacet + facet normal 0.048241 -0.0874681 0.994999 + outer loop + vertex 0.970302 1.2969 2.63571 + vertex 0.966642 1.2956 2.63577 + vertex 0.968611 1.29289 2.63544 + endloop + endfacet + facet normal 0.0448423 -0.0874867 0.995156 + outer loop + vertex 0.972846 1.29951 2.63583 + vertex 0.973441 1.29692 2.63557 + vertex 0.976398 1.30089 2.63579 + endloop + endfacet + facet normal 0.0487435 -0.088887 0.994848 + outer loop + vertex 0.970302 1.2969 2.63571 + vertex 0.969585 1.29944 2.63597 + vertex 0.966642 1.2956 2.63577 + endloop + endfacet + facet normal 0.0452264 -0.0884833 0.99505 + outer loop + vertex 0.976398 1.30089 2.63579 + vertex 0.974175 1.30342 2.63611 + vertex 0.972846 1.29951 2.63583 + endloop + endfacet + facet normal 0.0501199 -0.0907814 0.994609 + outer loop + vertex 0.969585 1.29944 2.63597 + vertex 0.968976 1.30323 2.63635 + vertex 0.964333 1.29819 2.63612 + endloop + endfacet + facet normal 0.0585468 -0.0855029 0.994616 + outer loop + vertex 0.974175 1.30342 2.63611 + vertex 0.978458 1.30832 2.63628 + vertex 0.973691 1.30805 2.63654 + endloop + endfacet + facet normal 0.0475435 -0.087858 0.994998 + outer loop + vertex 0.96336 1.30776 2.63703 + vertex 0.968428 1.31281 2.63723 + vertex 0.963357 1.31282 2.63748 + endloop + endfacet + facet normal 0.051029 -0.0864718 0.994947 + outer loop + vertex 0.973691 1.30805 2.63654 + vertex 0.973518 1.31288 2.63697 + vertex 0.968549 1.30785 2.63679 + endloop + endfacet + facet normal 0.0730992 -0.0848472 0.993709 + outer loop + vertex 0.973518 1.31288 2.63697 + vertex 0.978432 1.31794 2.63704 + vertex 0.973523 1.31792 2.6374 + endloop + endfacet + facet normal 0.0731103 -0.0777288 0.99429 + outer loop + vertex 0.978432 1.31794 2.63704 + vertex 0.978481 1.32303 2.63743 + vertex 0.973523 1.31792 2.6374 + endloop + endfacet + facet normal 0.126535 -0.0732505 0.989254 + outer loop + vertex 0.978481 1.32303 2.63743 + vertex 0.983089 1.32793 2.63721 + vertex 0.978537 1.32807 2.6378 + endloop + endfacet + facet normal 0.127027 -0.0604956 0.990053 + outer loop + vertex 0.983089 1.32793 2.63721 + vertex 0.98316 1.33295 2.6375 + vertex 0.978537 1.32807 2.6378 + endloop + endfacet + facet normal 0.135927 -0.0690318 0.988311 + outer loop + vertex 0.978537 1.32807 2.6378 + vertex 0.98316 1.33295 2.6375 + vertex 0.978573 1.33307 2.63814 + endloop + endfacet + facet normal 0.136303 -0.0577355 0.988983 + outer loop + vertex 0.98316 1.33295 2.6375 + vertex 0.98322 1.33794 2.63779 + vertex 0.978573 1.33307 2.63814 + endloop + endfacet + facet normal 0.147115 -0.0682152 0.986764 + outer loop + vertex 0.978573 1.33307 2.63814 + vertex 0.98322 1.33794 2.63779 + vertex 0.978583 1.33804 2.63849 + endloop + endfacet + facet normal 0.0999196 -0.0726767 0.992338 + outer loop + vertex 0.973565 1.33792 2.63896 + vertex 0.97856 1.34301 2.63883 + vertex 0.973505 1.3429 2.63933 + endloop + endfacet + facet normal 0.0620098 -0.0733626 0.995376 + outer loop + vertex 0.973565 1.33792 2.63896 + vertex 0.973505 1.3429 2.63933 + vertex 0.968422 1.33779 2.63927 + endloop + endfacet + facet normal 0.147443 -0.0579659 0.98737 + outer loop + vertex 0.98322 1.33794 2.63779 + vertex 0.983257 1.3429 2.63807 + vertex 0.978583 1.33804 2.63849 + endloop + endfacet + facet normal 0.0997904 -0.0640376 0.992946 + outer loop + vertex 0.97856 1.34301 2.63883 + vertex 0.978514 1.34796 2.63915 + vertex 0.973505 1.3429 2.63933 + endloop + endfacet + facet normal 0.0620843 -0.0769958 0.995097 + outer loop + vertex 0.968475 1.3328 2.63888 + vertex 0.973565 1.33792 2.63896 + vertex 0.968422 1.33779 2.63927 + endloop + endfacet + facet normal 0.0605902 -0.0788269 0.995045 + outer loop + vertex 0.968513 1.32784 2.63849 + vertex 0.9736 1.33294 2.63858 + vertex 0.968475 1.3328 2.63888 + endloop + endfacet + facet normal 0.0582303 -0.0809889 0.995013 + outer loop + vertex 0.968516 1.32288 2.63808 + vertex 0.973605 1.32797 2.6382 + vertex 0.968513 1.32784 2.63849 + endloop + endfacet + facet normal 0.0554119 -0.0830471 0.995004 + outer loop + vertex 0.968469 1.31787 2.63767 + vertex 0.973576 1.32297 2.63781 + vertex 0.968516 1.32288 2.63808 + endloop + endfacet + facet normal 0.0475574 -0.0858113 0.995176 + outer loop + vertex 0.968428 1.31281 2.63723 + vertex 0.968469 1.31787 2.63767 + vertex 0.963357 1.31282 2.63748 + endloop + endfacet + facet normal 0.0459355 -0.0878655 0.995073 + outer loop + vertex 0.96336 1.30776 2.63703 + vertex 0.963357 1.31282 2.63748 + vertex 0.958265 1.30778 2.63727 + endloop + endfacet + facet normal 0.0459299 -0.0886571 0.995003 + outer loop + vertex 0.95838 1.30274 2.63681 + vertex 0.96336 1.30776 2.63703 + vertex 0.958265 1.30778 2.63727 + endloop + endfacet + facet normal 0.0456321 -0.0854927 0.995293 + outer loop + vertex 0.958384 1.3129 2.63771 + vertex 0.963447 1.31788 2.63791 + vertex 0.958498 1.31793 2.63814 + endloop + endfacet + facet normal 0.0448628 -0.0822702 0.9956 + outer loop + vertex 0.958498 1.31793 2.63814 + vertex 0.963479 1.32285 2.63832 + vertex 0.958506 1.32288 2.63855 + endloop + endfacet + facet normal 0.043284 -0.0788145 0.995949 + outer loop + vertex 0.958506 1.32288 2.63855 + vertex 0.963443 1.32779 2.63872 + vertex 0.958442 1.32781 2.63894 + endloop + endfacet + facet normal 0.04072 -0.0754265 0.99632 + outer loop + vertex 0.958442 1.32781 2.63894 + vertex 0.963383 1.33275 2.63911 + vertex 0.95838 1.33279 2.63932 + endloop + endfacet + facet normal 0.0381157 -0.0725824 0.996634 + outer loop + vertex 0.95838 1.33279 2.63932 + vertex 0.963343 1.33777 2.63949 + vertex 0.958384 1.33785 2.63969 + endloop + endfacet + facet normal 0.0388609 -0.0699638 0.996792 + outer loop + vertex 0.953519 1.33795 2.63988 + vertex 0.958481 1.34289 2.64004 + vertex 0.953673 1.34289 2.64023 + endloop + endfacet + facet normal 0.0375428 -0.0699263 0.996845 + outer loop + vertex 0.953519 1.33795 2.63988 + vertex 0.953673 1.34289 2.64023 + vertex 0.948694 1.33798 2.64007 + endloop + endfacet + facet normal 0.0388668 -0.0676407 0.996952 + outer loop + vertex 0.958481 1.34289 2.64004 + vertex 0.958583 1.34773 2.64036 + vertex 0.953673 1.34289 2.64023 + endloop + endfacet + facet normal 0.040851 -0.0696466 0.996735 + outer loop + vertex 0.953673 1.34289 2.64023 + vertex 0.958583 1.34773 2.64036 + vertex 0.953716 1.34768 2.64056 + endloop + endfacet + facet normal 0.0389888 -0.0696354 0.99681 + outer loop + vertex 0.953673 1.34289 2.64023 + vertex 0.953716 1.34768 2.64056 + vertex 0.948831 1.34267 2.6404 + endloop + endfacet + facet normal 0.0381289 -0.0718627 0.996685 + outer loop + vertex 0.963343 1.33777 2.63949 + vertex 0.963363 1.34283 2.63986 + vertex 0.958384 1.33785 2.63969 + endloop + endfacet + facet normal 0.0364904 -0.0675968 0.997045 + outer loop + vertex 0.958481 1.34289 2.64004 + vertex 0.963455 1.34789 2.6402 + vertex 0.958583 1.34773 2.64036 + endloop + endfacet + facet normal 0.0363153 -0.061905 0.997421 + outer loop + vertex 0.963455 1.34789 2.6402 + vertex 0.963518 1.35302 2.64051 + vertex 0.958583 1.34773 2.64036 + endloop + endfacet + facet normal 0.0411734 -0.0689946 0.996767 + outer loop + vertex 0.968379 1.34281 2.63965 + vertex 0.968402 1.34786 2.64 + vertex 0.963363 1.34283 2.63986 + endloop + endfacet + facet normal 0.0393996 -0.0619356 0.997302 + outer loop + vertex 0.963455 1.34789 2.6402 + vertex 0.968555 1.35293 2.64031 + vertex 0.963518 1.35302 2.64051 + endloop + endfacet + facet normal 0.0618061 -0.062171 0.99615 + outer loop + vertex 0.97346 1.34789 2.63968 + vertex 0.973514 1.35291 2.63999 + vertex 0.968402 1.34786 2.64 + endloop + endfacet + facet normal 0.110303 -0.0624315 0.991935 + outer loop + vertex 0.97346 1.34789 2.63968 + vertex 0.978519 1.35294 2.63944 + vertex 0.973514 1.35291 2.63999 + endloop + endfacet + facet normal 0.0648321 -0.059852 0.9961 + outer loop + vertex 0.968555 1.35293 2.64031 + vertex 0.973743 1.35796 2.64027 + vertex 0.968971 1.35799 2.64058 + endloop + endfacet + facet normal 0.110325 -0.0527109 0.992497 + outer loop + vertex 0.978519 1.35294 2.63944 + vertex 0.978628 1.35797 2.63969 + vertex 0.973514 1.35291 2.63999 + endloop + endfacet + facet normal 0.18586 -0.0537556 0.981105 + outer loop + vertex 0.978519 1.35294 2.63944 + vertex 0.983485 1.35786 2.63877 + vertex 0.978628 1.35797 2.63969 + endloop + endfacet + facet normal 0.186163 -0.0442337 0.981523 + outer loop + vertex 0.983485 1.35786 2.63877 + vertex 0.9836 1.36302 2.63898 + vertex 0.978628 1.35797 2.63969 + endloop + endfacet + facet normal 0.200028 -0.0583949 0.978048 + outer loop + vertex 0.978628 1.35797 2.63969 + vertex 0.9836 1.36302 2.63898 + vertex 0.978816 1.36305 2.63996 + endloop + endfacet + facet normal 0.200109 -0.0537615 0.978297 + outer loop + vertex 0.9836 1.36302 2.63898 + vertex 0.983592 1.36817 2.63926 + vertex 0.978816 1.36305 2.63996 + endloop + endfacet + facet normal 0.0452374 -0.0506541 0.997691 + outer loop + vertex 0.973306 1.36848 2.641 + vertex 0.973171 1.37297 2.64123 + vertex 0.968602 1.36819 2.64119 + endloop + endfacet + facet normal 0.0669734 -0.0586411 0.99603 + outer loop + vertex 0.975279 1.36685 2.64077 + vertex 0.973306 1.36848 2.641 + vertex 0.972416 1.36477 2.64084 + endloop + endfacet + facet normal 0.0783621 -0.0744194 0.994143 + outer loop + vertex 0.975279 1.36685 2.64077 + vertex 0.972416 1.36477 2.64084 + vertex 0.974116 1.36295 2.64057 + endloop + endfacet + facet normal 0.0647904 -0.0639365 0.995849 + outer loop + vertex 0.974116 1.36295 2.64057 + vertex 0.968971 1.35799 2.64058 + vertex 0.973743 1.35796 2.64027 + endloop + endfacet + facet normal 0.0407228 -0.0588396 0.997436 + outer loop + vertex 0.970352 1.36187 2.64076 + vertex 0.968661 1.36372 2.64094 + vertex 0.967487 1.36005 2.64077 + endloop + endfacet + facet normal 0.0394853 -0.0578444 0.997544 + outer loop + vertex 0.968971 1.35799 2.64058 + vertex 0.963518 1.35302 2.64051 + vertex 0.968555 1.35293 2.64031 + endloop + endfacet + facet normal 0.0387581 -0.05987 0.997453 + outer loop + vertex 0.958471 1.35168 2.64063 + vertex 0.963518 1.35302 2.64051 + vertex 0.96144 1.35563 2.64075 + endloop + endfacet + facet normal 0.0402702 -0.0655819 0.997034 + outer loop + vertex 0.958583 1.34773 2.64036 + vertex 0.963518 1.35302 2.64051 + vertex 0.958471 1.35168 2.64063 + endloop + endfacet + facet normal 0.0391397 -0.0586918 0.997509 + outer loop + vertex 0.967487 1.36005 2.64077 + vertex 0.964302 1.35962 2.64087 + vertex 0.96514 1.35724 2.64069 + endloop + endfacet + facet normal 0.044871 -0.0609869 0.997129 + outer loop + vertex 0.964302 1.35962 2.64087 + vertex 0.963844 1.36331 2.64111 + vertex 0.95922 1.35816 2.64101 + endloop + endfacet + facet normal 0.0450686 -0.0645936 0.996893 + outer loop + vertex 0.957861 1.35422 2.64082 + vertex 0.958471 1.35168 2.64063 + vertex 0.96144 1.35563 2.64075 + endloop + endfacet + facet normal 0.0408171 -0.065565 0.997013 + outer loop + vertex 0.958471 1.35168 2.64063 + vertex 0.953716 1.34768 2.64056 + vertex 0.958583 1.34773 2.64036 + endloop + endfacet + facet normal 0.0419602 -0.0660067 0.996937 + outer loop + vertex 0.955351 1.35161 2.64076 + vertex 0.954595 1.35412 2.64096 + vertex 0.951726 1.35027 2.64082 + endloop + endfacet + facet normal 0.0393455 -0.0640651 0.99717 + outer loop + vertex 0.954595 1.35412 2.64096 + vertex 0.949397 1.35287 2.64108 + vertex 0.951726 1.35027 2.64082 + endloop + endfacet + facet normal 0.0390658 -0.0714644 0.996678 + outer loop + vertex 0.948694 1.33798 2.64007 + vertex 0.953673 1.34289 2.64023 + vertex 0.948831 1.34267 2.6404 + endloop + endfacet + facet normal 0.037527 -0.0716846 0.996721 + outer loop + vertex 0.948539 1.33299 2.63972 + vertex 0.953519 1.33795 2.63988 + vertex 0.948694 1.33798 2.64007 + endloop + endfacet + facet normal 0.0371402 -0.0737637 0.996584 + outer loop + vertex 0.948499 1.32793 2.63934 + vertex 0.95344 1.33289 2.63953 + vertex 0.948539 1.33299 2.63972 + endloop + endfacet + facet normal 0.0369929 -0.0777907 0.996283 + outer loop + vertex 0.948536 1.32292 2.63895 + vertex 0.953472 1.32786 2.63915 + vertex 0.948499 1.32793 2.63934 + endloop + endfacet + facet normal 0.0367701 -0.0821397 0.995942 + outer loop + vertex 0.948545 1.31794 2.63854 + vertex 0.953543 1.3229 2.63876 + vertex 0.948536 1.32292 2.63895 + endloop + endfacet + facet normal 0.0364973 -0.0873256 0.995511 + outer loop + vertex 0.948437 1.3129 2.6381 + vertex 0.953554 1.31796 2.63836 + vertex 0.948545 1.31794 2.63854 + endloop + endfacet + facet normal 0.0350419 -0.0894781 0.995372 + outer loop + vertex 0.948236 1.30775 2.63765 + vertex 0.95344 1.31294 2.63793 + vertex 0.948437 1.3129 2.6381 + endloop + endfacet + facet normal 0.0335626 -0.0893884 0.995431 + outer loop + vertex 0.948119 1.30258 2.63718 + vertex 0.95325 1.30779 2.63748 + vertex 0.948236 1.30775 2.63765 + endloop + endfacet + facet normal 0.0331705 -0.0890054 0.995479 + outer loop + vertex 0.953209 1.30266 2.63702 + vertex 0.95325 1.30779 2.63748 + vertex 0.948119 1.30258 2.63718 + endloop + endfacet + facet normal 0.0418136 -0.0887663 0.995174 + outer loop + vertex 0.95838 1.30274 2.63681 + vertex 0.958265 1.30778 2.63727 + vertex 0.953209 1.30266 2.63702 + endloop + endfacet + facet normal 0.0466611 -0.0893781 0.994904 + outer loop + vertex 0.963664 1.30288 2.63658 + vertex 0.96336 1.30776 2.63703 + vertex 0.95838 1.30274 2.63681 + endloop + endfacet + facet normal 0.0490189 -0.0897727 0.994755 + outer loop + vertex 0.964333 1.29819 2.63612 + vertex 0.968976 1.30323 2.63635 + vertex 0.963664 1.30288 2.63658 + endloop + endfacet + facet normal 0.0498758 -0.0897463 0.994715 + outer loop + vertex 0.969585 1.29944 2.63597 + vertex 0.964333 1.29819 2.63612 + vertex 0.966642 1.2956 2.63577 + endloop + endfacet + facet normal 0.0472092 -0.0882177 0.994982 + outer loop + vertex 0.963602 1.29176 2.63558 + vertex 0.968611 1.29289 2.63544 + vertex 0.966642 1.2956 2.63577 + endloop + endfacet + facet normal 0.0481494 -0.0943249 0.994376 + outer loop + vertex 0.963602 1.29176 2.63558 + vertex 0.958732 1.28786 2.63544 + vertex 0.963681 1.28783 2.6352 + endloop + endfacet + facet normal 0.0480792 -0.0899823 0.994782 + outer loop + vertex 0.962983 1.29431 2.63584 + vertex 0.959615 1.29427 2.636 + vertex 0.960403 1.29175 2.63574 + endloop + endfacet + facet normal 0.0435404 -0.0887853 0.995099 + outer loop + vertex 0.959615 1.29427 2.636 + vertex 0.958895 1.29805 2.63637 + vertex 0.954319 1.29311 2.63613 + endloop + endfacet + facet normal 0.046137 -0.0963182 0.994281 + outer loop + vertex 0.953649 1.28678 2.63557 + vertex 0.958732 1.28786 2.63544 + vertex 0.956673 1.2905 2.63579 + endloop + endfacet + facet normal 0.03608 -0.100425 0.99429 + outer loop + vertex 0.953649 1.28678 2.63557 + vertex 0.948689 1.283 2.63537 + vertex 0.953795 1.2829 2.63518 + endloop + endfacet + facet normal 0.0370613 -0.0912098 0.995142 + outer loop + vertex 0.953002 1.2893 2.63584 + vertex 0.949754 1.28948 2.63598 + vertex 0.950419 1.28688 2.63572 + endloop + endfacet + facet normal 0.0253109 -0.0881339 0.995787 + outer loop + vertex 0.949754 1.28948 2.63598 + vertex 0.949072 1.29318 2.63633 + vertex 0.945191 1.28921 2.63607 + endloop + endfacet + facet normal 0.0167275 -0.111623 0.99361 + outer loop + vertex 0.943003 1.28204 2.63536 + vertex 0.948689 1.283 2.63537 + vertex 0.946558 1.28597 2.63574 + endloop + endfacet + facet normal -0.0174145 -0.113287 0.99341 + outer loop + vertex 0.938453 1.27763 2.63478 + vertex 0.943003 1.28204 2.63536 + vertex 0.937756 1.28192 2.63525 + endloop + endfacet + facet normal -0.054172 -0.12136 0.991129 + outer loop + vertex 0.932094 1.28256 2.63502 + vertex 0.937756 1.28192 2.63525 + vertex 0.936728 1.28591 2.63569 + endloop + endfacet + facet normal -0.0519943 -0.124318 0.990879 + outer loop + vertex 0.932634 1.28681 2.63558 + vertex 0.932094 1.28256 2.63502 + vertex 0.936728 1.28591 2.63569 + endloop + endfacet + facet normal -0.0534517 -0.114692 0.991962 + outer loop + vertex 0.933257 1.27764 2.63452 + vertex 0.937756 1.28192 2.63525 + vertex 0.932094 1.28256 2.63502 + endloop + endfacet + facet normal -0.0499053 -0.118382 0.991713 + outer loop + vertex 0.938453 1.27763 2.63478 + vertex 0.937756 1.28192 2.63525 + vertex 0.933257 1.27764 2.63452 + endloop + endfacet + facet normal -0.0499203 -0.113132 0.992325 + outer loop + vertex 0.933488 1.27286 2.63398 + vertex 0.938453 1.27763 2.63478 + vertex 0.933257 1.27764 2.63452 + endloop + endfacet + facet normal -0.0526769 -0.110291 0.992502 + outer loop + vertex 0.938532 1.27291 2.63425 + vertex 0.938453 1.27763 2.63478 + vertex 0.933488 1.27286 2.63398 + endloop + endfacet + facet normal -0.0527666 -0.104429 0.993132 + outer loop + vertex 0.933388 1.26786 2.63345 + vertex 0.938532 1.27291 2.63425 + vertex 0.933488 1.27286 2.63398 + endloop + endfacet + facet normal -0.0564188 -0.100739 0.993312 + outer loop + vertex 0.93835 1.26787 2.63373 + vertex 0.938532 1.27291 2.63425 + vertex 0.933388 1.26786 2.63345 + endloop + endfacet + facet normal -0.0564687 -0.0948271 0.993891 + outer loop + vertex 0.933432 1.26291 2.63298 + vertex 0.93835 1.26787 2.63373 + vertex 0.933388 1.26786 2.63345 + endloop + endfacet + facet normal -0.0569141 -0.0943878 0.993907 + outer loop + vertex 0.938197 1.26277 2.63324 + vertex 0.93835 1.26787 2.63373 + vertex 0.933432 1.26291 2.63298 + endloop + endfacet + facet normal -0.056823 -0.0906877 0.994257 + outer loop + vertex 0.933471 1.25802 2.63254 + vertex 0.938197 1.26277 2.63324 + vertex 0.933432 1.26291 2.63298 + endloop + endfacet + facet normal -0.0578882 -0.0896325 0.994291 + outer loop + vertex 0.938211 1.25772 2.63279 + vertex 0.938197 1.26277 2.63324 + vertex 0.933471 1.25802 2.63254 + endloop + endfacet + facet normal -0.0577189 -0.0867401 0.994558 + outer loop + vertex 0.933933 1.25309 2.63213 + vertex 0.938211 1.25772 2.63279 + vertex 0.933471 1.25802 2.63254 + endloop + endfacet + facet normal -0.0610881 -0.0836353 0.994622 + outer loop + vertex 0.938504 1.25283 2.63239 + vertex 0.938211 1.25772 2.63279 + vertex 0.933933 1.25309 2.63213 + endloop + endfacet + facet normal -0.0608497 -0.0790467 0.995012 + outer loop + vertex 0.935224 1.24901 2.63189 + vertex 0.938504 1.25283 2.63239 + vertex 0.933933 1.25309 2.63213 + endloop + endfacet + facet normal -0.055209 -0.0838704 0.994946 + outer loop + vertex 0.939005 1.24815 2.63203 + vertex 0.938504 1.25283 2.63239 + vertex 0.935224 1.24901 2.63189 + endloop + endfacet + facet normal -0.0583883 -0.0981826 0.993454 + outer loop + vertex 0.935228 1.24398 2.63139 + vertex 0.939005 1.24815 2.63203 + vertex 0.935224 1.24901 2.63189 + endloop + endfacet + facet normal 0.00497908 -0.0945689 0.995506 + outer loop + vertex 0.945191 1.28921 2.63607 + vertex 0.940272 1.28926 2.6361 + vertex 0.941702 1.2856 2.63575 + endloop + endfacet + facet normal -0.0484358 -0.107763 0.992996 + outer loop + vertex 0.936728 1.28591 2.63569 + vertex 0.935116 1.29011 2.63606 + vertex 0.932634 1.28681 2.63558 + endloop + endfacet + facet normal 0.00238146 -0.0885725 0.996067 + outer loop + vertex 0.940272 1.28926 2.6361 + vertex 0.944044 1.29307 2.63643 + vertex 0.939219 1.29332 2.63647 + endloop + endfacet + facet normal -0.000736762 -0.0852334 0.996361 + outer loop + vertex 0.939219 1.29332 2.63647 + vertex 0.943336 1.29757 2.63683 + vertex 0.938595 1.29777 2.63685 + endloop + endfacet + facet normal -0.00377238 -0.0853043 0.996348 + outer loop + vertex 0.938595 1.29777 2.63685 + vertex 0.943108 1.30253 2.63727 + vertex 0.938222 1.30263 2.63726 + endloop + endfacet + facet normal -0.00328805 -0.0893032 0.995999 + outer loop + vertex 0.938222 1.30263 2.63726 + vertex 0.943199 1.3077 2.63773 + vertex 0.938217 1.30774 2.63772 + endloop + endfacet + facet normal -0.00109566 -0.0916242 0.995793 + outer loop + vertex 0.938217 1.30774 2.63772 + vertex 0.943366 1.31285 2.6382 + vertex 0.938298 1.31279 2.63819 + endloop + endfacet + facet normal 0.000787828 -0.0899269 0.995948 + outer loop + vertex 0.938298 1.31279 2.63819 + vertex 0.943459 1.3179 2.63864 + vertex 0.938344 1.31781 2.63864 + endloop + endfacet + facet normal 0.00361203 -0.0870078 0.996201 + outer loop + vertex 0.938344 1.31781 2.63864 + vertex 0.943478 1.32292 2.63907 + vertex 0.938388 1.32288 2.63908 + endloop + endfacet + facet normal 0.00622721 -0.0823499 0.996584 + outer loop + vertex 0.938388 1.32288 2.63908 + vertex 0.943513 1.32799 2.63947 + vertex 0.9385 1.32798 2.6395 + endloop + endfacet + facet normal 0.010059 -0.0792153 0.996807 + outer loop + vertex 0.9385 1.32798 2.6395 + vertex 0.943646 1.33304 2.63985 + vertex 0.938691 1.33299 2.6399 + endloop + endfacet + facet normal 0.0147487 -0.0785115 0.996804 + outer loop + vertex 0.938691 1.33299 2.6399 + vertex 0.94382 1.33792 2.64021 + vertex 0.938746 1.33766 2.64026 + endloop + endfacet + facet normal 0.0173886 -0.0766018 0.99691 + outer loop + vertex 0.938746 1.33766 2.64026 + vertex 0.943783 1.34264 2.64056 + vertex 0.938082 1.34161 2.64058 + endloop + endfacet + facet normal 0.0396693 -0.0698621 0.996768 + outer loop + vertex 0.948127 1.34897 2.64088 + vertex 0.948738 1.34647 2.64068 + vertex 0.951726 1.35027 2.64082 + endloop + endfacet + facet normal 0.0237565 -0.0669747 0.997472 + outer loop + vertex 0.94555 1.34646 2.64079 + vertex 0.944875 1.34907 2.64098 + vertex 0.941666 1.34548 2.64082 + endloop + endfacet + facet normal 0.0380068 -0.0652635 0.997144 + outer loop + vertex 0.951726 1.35027 2.64082 + vertex 0.949397 1.35287 2.64108 + vertex 0.948127 1.34897 2.64088 + endloop + endfacet + facet normal 0.0200845 -0.0638483 0.997757 + outer loop + vertex 0.944875 1.34907 2.64098 + vertex 0.944142 1.35288 2.64124 + vertex 0.94026 1.34875 2.64105 + endloop + endfacet + facet normal 0.0168137 -0.0607828 0.998009 + outer loop + vertex 0.94026 1.34875 2.64105 + vertex 0.944142 1.35288 2.64124 + vertex 0.939057 1.35276 2.64132 + endloop + endfacet + facet normal 0.0168908 -0.0641097 0.9978 + outer loop + vertex 0.944142 1.35288 2.64124 + vertex 0.943391 1.35747 2.64155 + vertex 0.939057 1.35276 2.64132 + endloop + endfacet + facet normal 0.0268385 -0.0624751 0.997686 + outer loop + vertex 0.944142 1.35288 2.64124 + vertex 0.948616 1.35761 2.64142 + vertex 0.943391 1.35747 2.64155 + endloop + endfacet + facet normal 0.0268586 -0.0633284 0.997631 + outer loop + vertex 0.948616 1.35761 2.64142 + vertex 0.948232 1.36257 2.64174 + vertex 0.943391 1.35747 2.64155 + endloop + endfacet + facet normal 0.039468 -0.0645776 0.997132 + outer loop + vertex 0.954595 1.35412 2.64096 + vertex 0.953914 1.35793 2.64123 + vertex 0.949397 1.35287 2.64108 + endloop + endfacet + facet normal 0.0373849 -0.0624951 0.997345 + outer loop + vertex 0.948616 1.35761 2.64142 + vertex 0.953425 1.36264 2.64155 + vertex 0.948232 1.36257 2.64174 + endloop + endfacet + facet normal 0.0452497 -0.0626313 0.99701 + outer loop + vertex 0.95922 1.35816 2.64101 + vertex 0.95868 1.36284 2.64132 + vertex 0.953914 1.35793 2.64123 + endloop + endfacet + facet normal 0.0470322 -0.0608842 0.997036 + outer loop + vertex 0.95868 1.36284 2.64132 + vertex 0.963608 1.36789 2.6414 + vertex 0.95844 1.3677 2.64163 + endloop + endfacet + facet normal 0.0443081 -0.0578821 0.99734 + outer loop + vertex 0.953305 1.36769 2.64186 + vertex 0.958427 1.37275 2.64193 + vertex 0.953399 1.37281 2.64216 + endloop + endfacet + facet normal 0.0469488 -0.0583637 0.997191 + outer loop + vertex 0.963608 1.36789 2.6414 + vertex 0.963529 1.3728 2.64169 + vertex 0.95844 1.3677 2.64163 + endloop + endfacet + facet normal 0.0466122 -0.0560608 0.997339 + outer loop + vertex 0.958427 1.37275 2.64193 + vertex 0.963535 1.37782 2.64198 + vertex 0.958475 1.3778 2.64221 + endloop + endfacet + facet normal 0.0466709 -0.0545305 0.997421 + outer loop + vertex 0.968541 1.37292 2.64146 + vertex 0.968543 1.37787 2.64173 + vertex 0.963529 1.3728 2.64169 + endloop + endfacet + facet normal 0.0625915 -0.0527162 0.996646 + outer loop + vertex 0.968543 1.37787 2.64173 + vertex 0.973323 1.38274 2.64169 + vertex 0.968576 1.38289 2.642 + endloop + endfacet + facet normal 0.0628639 -0.044942 0.99701 + outer loop + vertex 0.973323 1.38274 2.64169 + vertex 0.973509 1.38789 2.64191 + vertex 0.968576 1.38289 2.642 + endloop + endfacet + facet normal 0.115407 -0.0447741 0.992309 + outer loop + vertex 0.973509 1.38789 2.64191 + vertex 0.978543 1.39297 2.64156 + vertex 0.973568 1.393 2.64214 + endloop + endfacet + facet normal 0.115443 -0.0416401 0.992441 + outer loop + vertex 0.978543 1.39297 2.64156 + vertex 0.978035 1.39798 2.64182 + vertex 0.973568 1.393 2.64214 + endloop + endfacet + facet normal 0.118539 -0.0444477 0.991954 + outer loop + vertex 0.973568 1.393 2.64214 + vertex 0.978035 1.39798 2.64182 + vertex 0.973504 1.39796 2.64237 + endloop + endfacet + facet normal 0.052688 -0.046743 0.997516 + outer loop + vertex 0.9635 1.39271 2.64276 + vertex 0.968591 1.39781 2.64273 + vertex 0.963493 1.39769 2.643 + endloop + endfacet + facet normal 0.074199 -0.0452155 0.996218 + outer loop + vertex 0.973568 1.393 2.64214 + vertex 0.973504 1.39796 2.64237 + vertex 0.968598 1.39286 2.6425 + endloop + endfacet + facet normal 0.0782383 -0.0433804 0.99599 + outer loop + vertex 0.968591 1.39781 2.64273 + vertex 0.973503 1.40291 2.64257 + vertex 0.968597 1.40279 2.64295 + endloop + endfacet + facet normal 0.11854 -0.0351281 0.992328 + outer loop + vertex 0.978035 1.39798 2.64182 + vertex 0.977986 1.40284 2.642 + vertex 0.973504 1.39796 2.64237 + endloop + endfacet + facet normal 0.0781345 -0.0380679 0.996216 + outer loop + vertex 0.973503 1.40291 2.64257 + vertex 0.973518 1.4079 2.64276 + vertex 0.968597 1.40279 2.64295 + endloop + endfacet + facet normal 0.0526154 -0.0434209 0.99767 + outer loop + vertex 0.968591 1.39781 2.64273 + vertex 0.968597 1.40279 2.64295 + vertex 0.963493 1.39769 2.643 + endloop + endfacet + facet normal 0.0437322 -0.0467744 0.997948 + outer loop + vertex 0.9635 1.39271 2.64276 + vertex 0.963493 1.39769 2.643 + vertex 0.958415 1.39267 2.64298 + endloop + endfacet + facet normal 0.0437457 -0.0488837 0.997846 + outer loop + vertex 0.958445 1.38771 2.64274 + vertex 0.9635 1.39271 2.64276 + vertex 0.958415 1.39267 2.64298 + endloop + endfacet + facet normal 0.0449352 -0.0500843 0.997734 + outer loop + vertex 0.963521 1.38777 2.64251 + vertex 0.9635 1.39271 2.64276 + vertex 0.958445 1.38771 2.64274 + endloop + endfacet + facet normal 0.0526247 -0.0528417 0.997215 + outer loop + vertex 0.963541 1.38282 2.64225 + vertex 0.968604 1.3879 2.64225 + vertex 0.963521 1.38777 2.64251 + endloop + endfacet + facet normal 0.0466091 -0.0547606 0.997411 + outer loop + vertex 0.963535 1.37782 2.64198 + vertex 0.963541 1.38282 2.64225 + vertex 0.958475 1.3778 2.64221 + endloop + endfacet + facet normal 0.0443325 -0.0560449 0.997444 + outer loop + vertex 0.958427 1.37275 2.64193 + vertex 0.958475 1.3778 2.64221 + vertex 0.953399 1.37281 2.64216 + endloop + endfacet + facet normal 0.0369551 -0.0577636 0.997646 + outer loop + vertex 0.953305 1.36769 2.64186 + vertex 0.953399 1.37281 2.64216 + vertex 0.948257 1.36773 2.64205 + endloop + endfacet + facet normal 0.0384464 -0.0560164 0.997689 + outer loop + vertex 0.948434 1.37287 2.64235 + vertex 0.953491 1.37784 2.64243 + vertex 0.948547 1.37789 2.64263 + endloop + endfacet + facet normal 0.0387492 -0.0535765 0.997812 + outer loop + vertex 0.948547 1.37789 2.64263 + vertex 0.953496 1.38279 2.6427 + vertex 0.948556 1.38284 2.64289 + endloop + endfacet + facet normal 0.038771 -0.0507162 0.99796 + outer loop + vertex 0.948556 1.38284 2.64289 + vertex 0.953456 1.38774 2.64295 + vertex 0.94852 1.38779 2.64314 + endloop + endfacet + facet normal 0.0386351 -0.0477153 0.998114 + outer loop + vertex 0.94852 1.38779 2.64314 + vertex 0.953422 1.39271 2.64319 + vertex 0.948492 1.39277 2.64338 + endloop + endfacet + facet normal 0.033919 -0.0455837 0.998385 + outer loop + vertex 0.943549 1.39281 2.64355 + vertex 0.948475 1.39775 2.64361 + vertex 0.943538 1.3978 2.64378 + endloop + endfacet + facet normal 0.0339559 -0.0424181 0.998523 + outer loop + vertex 0.948475 1.39775 2.64361 + vertex 0.948463 1.40274 2.64382 + vertex 0.943538 1.3978 2.64378 + endloop + endfacet + facet normal 0.0386722 -0.0449744 0.998239 + outer loop + vertex 0.953422 1.39271 2.64319 + vertex 0.953408 1.3977 2.64341 + vertex 0.948492 1.39277 2.64338 + endloop + endfacet + facet normal 0.0381625 -0.0424014 0.998372 + outer loop + vertex 0.948475 1.39775 2.64361 + vertex 0.953402 1.40269 2.64363 + vertex 0.948463 1.40274 2.64382 + endloop + endfacet + facet normal 0.0400088 -0.0434008 0.998256 + outer loop + vertex 0.958406 1.39766 2.64321 + vertex 0.958405 1.40266 2.64343 + vertex 0.953408 1.3977 2.64341 + endloop + endfacet + facet normal 0.0389091 -0.0414696 0.998382 + outer loop + vertex 0.953402 1.40269 2.64363 + vertex 0.958403 1.40766 2.64364 + vertex 0.953399 1.40768 2.64384 + endloop + endfacet + facet normal 0.0424317 -0.0421896 0.998208 + outer loop + vertex 0.963496 1.40269 2.64321 + vertex 0.963497 1.40769 2.64343 + vertex 0.958405 1.40266 2.64343 + endloop + endfacet + facet normal 0.0539382 -0.0395338 0.997761 + outer loop + vertex 0.968603 1.4078 2.64315 + vertex 0.968601 1.4128 2.64335 + vertex 0.963497 1.40769 2.64343 + endloop + endfacet + facet normal 0.0868398 -0.0378203 0.995504 + outer loop + vertex 0.968601 1.4128 2.64335 + vertex 0.973541 1.41791 2.64312 + vertex 0.968595 1.4178 2.64354 + endloop + endfacet + facet normal 0.0867556 -0.0334647 0.995667 + outer loop + vertex 0.973541 1.41791 2.64312 + vertex 0.973551 1.4229 2.64328 + vertex 0.968595 1.4178 2.64354 + endloop + endfacet + facet normal 0.0934045 -0.0338656 0.995052 + outer loop + vertex 0.968592 1.42279 2.64373 + vertex 0.973555 1.42789 2.64344 + vertex 0.968588 1.42778 2.6439 + endloop + endfacet + facet normal 0.145412 -0.0272227 0.988997 + outer loop + vertex 0.978117 1.42279 2.64261 + vertex 0.978153 1.42778 2.64274 + vertex 0.973551 1.4229 2.64328 + endloop + endfacet + facet normal 0.0933064 -0.0286409 0.995225 + outer loop + vertex 0.973555 1.42789 2.64344 + vertex 0.973562 1.43288 2.64358 + vertex 0.968588 1.42778 2.6439 + endloop + endfacet + facet normal 0.0578993 -0.0339854 0.997744 + outer loop + vertex 0.968592 1.42279 2.64373 + vertex 0.968588 1.42778 2.6439 + vertex 0.963483 1.42267 2.64402 + endloop + endfacet + facet normal 0.0579775 -0.0378341 0.997601 + outer loop + vertex 0.963488 1.41768 2.64383 + vertex 0.968592 1.42279 2.64373 + vertex 0.963483 1.42267 2.64402 + endloop + endfacet + facet normal 0.0425253 -0.0398728 0.998299 + outer loop + vertex 0.963492 1.41269 2.64363 + vertex 0.963488 1.41768 2.64383 + vertex 0.958402 1.41265 2.64385 + endloop + endfacet + facet normal 0.0425324 -0.0410811 0.99825 + outer loop + vertex 0.958403 1.40766 2.64364 + vertex 0.963492 1.41269 2.64363 + vertex 0.958402 1.41265 2.64385 + endloop + endfacet + facet normal 0.0389114 -0.041088 0.998398 + outer loop + vertex 0.958403 1.40766 2.64364 + vertex 0.958402 1.41265 2.64385 + vertex 0.953399 1.40768 2.64384 + endloop + endfacet + facet normal 0.0381727 -0.0414712 0.99841 + outer loop + vertex 0.953402 1.40269 2.64363 + vertex 0.953399 1.40768 2.64384 + vertex 0.948463 1.40274 2.64382 + endloop + endfacet + facet normal 0.0367151 -0.0396992 0.998537 + outer loop + vertex 0.948454 1.40772 2.64402 + vertex 0.953397 1.41267 2.64404 + vertex 0.948449 1.41272 2.64422 + endloop + endfacet + facet normal 0.0367206 -0.0391482 0.998558 + outer loop + vertex 0.953397 1.41267 2.64404 + vertex 0.953398 1.41767 2.64423 + vertex 0.948449 1.41272 2.64422 + endloop + endfacet + facet normal 0.0375565 -0.0375737 0.998588 + outer loop + vertex 0.958402 1.41764 2.64405 + vertex 0.958402 1.42264 2.64423 + vertex 0.953398 1.41767 2.64423 + endloop + endfacet + facet normal 0.0415039 -0.0341552 0.998554 + outer loop + vertex 0.958402 1.42264 2.64423 + vertex 0.963479 1.42766 2.64419 + vertex 0.958405 1.42763 2.6444 + endloop + endfacet + facet normal 0.0359061 -0.0297982 0.998911 + outer loop + vertex 0.95341 1.42766 2.64459 + vertex 0.95841 1.43263 2.64455 + vertex 0.953416 1.43265 2.64473 + endloop + endfacet + facet normal 0.0414847 -0.0303046 0.998679 + outer loop + vertex 0.963479 1.42766 2.64419 + vertex 0.963476 1.43266 2.64435 + vertex 0.958405 1.42763 2.6444 + endloop + endfacet + facet normal 0.0414943 -0.0272457 0.998767 + outer loop + vertex 0.95841 1.43263 2.64455 + vertex 0.963478 1.43765 2.64448 + vertex 0.958414 1.43762 2.64469 + endloop + endfacet + facet normal 0.041487 -0.0257007 0.998808 + outer loop + vertex 0.963478 1.43765 2.64448 + vertex 0.963479 1.44265 2.64461 + vertex 0.958414 1.43762 2.64469 + endloop + endfacet + facet normal 0.0413389 -0.0255513 0.998818 + outer loop + vertex 0.958414 1.43762 2.64469 + vertex 0.963479 1.44265 2.64461 + vertex 0.958408 1.44262 2.64482 + endloop + endfacet + facet normal 0.0582638 -0.0265412 0.997948 + outer loop + vertex 0.968583 1.43277 2.64405 + vertex 0.968578 1.43776 2.64418 + vertex 0.963476 1.43266 2.64435 + endloop + endfacet + facet normal 0.0605421 -0.025682 0.997835 + outer loop + vertex 0.963478 1.43765 2.64448 + vertex 0.968578 1.44276 2.6443 + vertex 0.963479 1.44265 2.64461 + endloop + endfacet + facet normal 0.0604802 -0.0224886 0.997916 + outer loop + vertex 0.968578 1.44276 2.6443 + vertex 0.96858 1.44775 2.64442 + vertex 0.963479 1.44265 2.64461 + endloop + endfacet + facet normal 0.0622829 -0.0242956 0.997763 + outer loop + vertex 0.963479 1.44265 2.64461 + vertex 0.96858 1.44775 2.64442 + vertex 0.963476 1.44765 2.64473 + endloop + endfacet + facet normal 0.0969829 -0.0216248 0.995051 + outer loop + vertex 0.973561 1.43787 2.6437 + vertex 0.973564 1.44286 2.64381 + vertex 0.968578 1.43776 2.64418 + endloop + endfacet + facet normal 0.101278 -0.0224262 0.994605 + outer loop + vertex 0.968578 1.44276 2.6443 + vertex 0.973571 1.44786 2.64391 + vertex 0.96858 1.44775 2.64442 + endloop + endfacet + facet normal 0.101215 -0.0189173 0.994685 + outer loop + vertex 0.973571 1.44786 2.64391 + vertex 0.973579 1.45285 2.644 + vertex 0.96858 1.44775 2.64442 + endloop + endfacet + facet normal 0.105153 -0.0228187 0.994194 + outer loop + vertex 0.96858 1.44775 2.64442 + vertex 0.973579 1.45285 2.644 + vertex 0.968584 1.45275 2.64453 + endloop + endfacet + facet normal 0.159839 -0.0167739 0.987001 + outer loop + vertex 0.978212 1.44275 2.64305 + vertex 0.978231 1.44775 2.64314 + vertex 0.973564 1.44286 2.64381 + endloop + endfacet + facet normal 0.105087 -0.0190822 0.99428 + outer loop + vertex 0.973579 1.45285 2.644 + vertex 0.973597 1.45786 2.6441 + vertex 0.968584 1.45275 2.64453 + endloop + endfacet + facet normal 0.0622545 -0.0228596 0.997798 + outer loop + vertex 0.96858 1.44775 2.64442 + vertex 0.968584 1.45275 2.64453 + vertex 0.963476 1.44765 2.64473 + endloop + endfacet + facet normal 0.0413325 -0.0243346 0.998849 + outer loop + vertex 0.963479 1.44265 2.64461 + vertex 0.963476 1.44765 2.64473 + vertex 0.958408 1.44262 2.64482 + endloop + endfacet + facet normal 0.0358143 -0.0255639 0.999031 + outer loop + vertex 0.958414 1.43762 2.64469 + vertex 0.958408 1.44262 2.64482 + vertex 0.953407 1.43764 2.64487 + endloop + endfacet + facet normal 0.0356498 -0.0270952 0.998997 + outer loop + vertex 0.948451 1.43268 2.64491 + vertex 0.953407 1.43764 2.64487 + vertex 0.948419 1.43766 2.64505 + endloop + endfacet + facet normal 0.0343262 -0.029584 0.998973 + outer loop + vertex 0.948461 1.42769 2.64476 + vertex 0.948451 1.43268 2.64491 + vertex 0.943513 1.42771 2.64494 + endloop + endfacet + facet normal 0.0274328 -0.0333128 0.999068 + outer loop + vertex 0.94352 1.42273 2.64477 + vertex 0.943513 1.42771 2.64494 + vertex 0.93856 1.42275 2.64491 + endloop + endfacet + facet normal 0.0274151 -0.0369586 0.998941 + outer loop + vertex 0.938562 1.41776 2.64472 + vertex 0.94352 1.42273 2.64477 + vertex 0.93856 1.42275 2.64491 + endloop + endfacet + facet normal 0.027215 -0.036759 0.998954 + outer loop + vertex 0.943516 1.41774 2.64459 + vertex 0.94352 1.42273 2.64477 + vertex 0.938562 1.41776 2.64472 + endloop + endfacet + facet normal 0.0339896 -0.0387949 0.998669 + outer loop + vertex 0.943514 1.41276 2.64439 + vertex 0.94845 1.41771 2.64442 + vertex 0.943516 1.41774 2.64459 + endloop + endfacet + facet normal 0.00929667 -0.0451844 0.998935 + outer loop + vertex 0.93349 1.39781 2.64393 + vertex 0.938552 1.40283 2.64411 + vertex 0.933519 1.40279 2.64416 + endloop + endfacet + facet normal 0.0246276 -0.040561 0.998874 + outer loop + vertex 0.943528 1.40279 2.64399 + vertex 0.943518 1.40777 2.64419 + vertex 0.938552 1.40283 2.64411 + endloop + endfacet + facet normal 0.034047 -0.042509 0.998516 + outer loop + vertex 0.943538 1.3978 2.64378 + vertex 0.948463 1.40274 2.64382 + vertex 0.943528 1.40279 2.64399 + endloop + endfacet + facet normal 0.0221609 -0.0456236 0.998713 + outer loop + vertex 0.943549 1.39281 2.64355 + vertex 0.943538 1.3978 2.64378 + vertex 0.938535 1.39283 2.64366 + endloop + endfacet + facet normal 0.00262797 -0.0508127 0.998705 + outer loop + vertex 0.938519 1.38781 2.64341 + vertex 0.938535 1.39283 2.64366 + vertex 0.933397 1.38777 2.64342 + endloop + endfacet + facet normal 0.0201001 -0.0534473 0.998368 + outer loop + vertex 0.938503 1.38279 2.64314 + vertex 0.943561 1.38782 2.64331 + vertex 0.938519 1.38781 2.64341 + endloop + endfacet + facet normal 0.0184081 -0.056038 0.998259 + outer loop + vertex 0.938468 1.37777 2.64286 + vertex 0.943574 1.38284 2.64305 + vertex 0.938503 1.38279 2.64314 + endloop + endfacet + facet normal 0.01714 -0.0586307 0.998133 + outer loop + vertex 0.938367 1.37273 2.64256 + vertex 0.943554 1.37787 2.64277 + vertex 0.938468 1.37777 2.64286 + endloop + endfacet + facet normal 0.0160368 -0.0616163 0.997971 + outer loop + vertex 0.938195 1.36763 2.64225 + vertex 0.943436 1.37285 2.64249 + vertex 0.938367 1.37273 2.64256 + endloop + endfacet + facet normal 0.0140833 -0.0621529 0.997967 + outer loop + vertex 0.938096 1.36247 2.64193 + vertex 0.943233 1.36772 2.64218 + vertex 0.938195 1.36763 2.64225 + endloop + endfacet + facet normal 0.0128648 -0.0617848 0.998007 + outer loop + vertex 0.938311 1.35742 2.64161 + vertex 0.943122 1.36253 2.64187 + vertex 0.938096 1.36247 2.64193 + endloop + endfacet + facet normal 0.0137334 -0.0612188 0.99803 + outer loop + vertex 0.939057 1.35276 2.64132 + vertex 0.943391 1.35747 2.64155 + vertex 0.938311 1.35742 2.64161 + endloop + endfacet + facet normal 0.00661894 -0.0638389 0.997938 + outer loop + vertex 0.94026 1.34875 2.64105 + vertex 0.939057 1.35276 2.64132 + vertex 0.935253 1.34879 2.64109 + endloop + endfacet + facet normal -0.00822722 -0.0763847 0.997044 + outer loop + vertex 0.93169 1.34542 2.64083 + vertex 0.932794 1.34151 2.64054 + vertex 0.936746 1.34508 2.64084 + endloop + endfacet + facet normal -0.0380994 -0.0867023 0.995505 + outer loop + vertex 0.933538 1.33739 2.64021 + vertex 0.932794 1.34151 2.64054 + vertex 0.928273 1.33742 2.64001 + endloop + endfacet + facet normal -0.0922392 -0.0843834 0.992155 + outer loop + vertex 0.927533 1.34634 2.64076 + vertex 0.922543 1.34604 2.64028 + vertex 0.927076 1.34221 2.64037 + endloop + endfacet + facet normal -0.178087 -0.0957669 0.979344 + outer loop + vertex 0.922754 1.3506 2.64073 + vertex 0.921152 1.35456 2.64082 + vertex 0.918382 1.35071 2.63995 + endloop + endfacet + facet normal -0.193601 -0.0841569 0.977464 + outer loop + vertex 0.916686 1.35624 2.64008 + vertex 0.918382 1.35071 2.63995 + vertex 0.921152 1.35456 2.64082 + endloop + endfacet + facet normal -0.200735 -0.104629 0.974042 + outer loop + vertex 0.919748 1.3585 2.64096 + vertex 0.916686 1.35624 2.64008 + vertex 0.921152 1.35456 2.64082 + endloop + endfacet + facet normal -0.0990163 -0.0691121 0.992683 + outer loop + vertex 0.921152 1.35456 2.64082 + vertex 0.924008 1.35887 2.64141 + vertex 0.919748 1.3585 2.64096 + endloop + endfacet + facet normal -0.0990652 -0.0685799 0.992715 + outer loop + vertex 0.919748 1.3585 2.64096 + vertex 0.924008 1.35887 2.64141 + vertex 0.920462 1.36309 2.64135 + endloop + endfacet + facet normal -0.17666 -0.0556481 0.982698 + outer loop + vertex 0.919748 1.3585 2.64096 + vertex 0.920462 1.36309 2.64135 + vertex 0.917153 1.3605 2.64061 + endloop + endfacet + facet normal -0.0901421 -0.061065 0.994055 + outer loop + vertex 0.924008 1.35887 2.64141 + vertex 0.924818 1.36381 2.64179 + vertex 0.920462 1.36309 2.64135 + endloop + endfacet + facet normal -0.0900036 -0.0618771 0.994017 + outer loop + vertex 0.924818 1.36381 2.64179 + vertex 0.923885 1.36794 2.64196 + vertex 0.920462 1.36309 2.64135 + endloop + endfacet + facet normal -0.100825 -0.0541696 0.993428 + outer loop + vertex 0.920462 1.36309 2.64135 + vertex 0.923885 1.36794 2.64196 + vertex 0.919042 1.36895 2.64152 + endloop + endfacet + facet normal -0.102002 -0.0600458 0.99297 + outer loop + vertex 0.923885 1.36794 2.64196 + vertex 0.923607 1.37293 2.64223 + vertex 0.919042 1.36895 2.64152 + endloop + endfacet + facet normal -0.0912559 -0.0743013 0.993052 + outer loop + vertex 0.925967 1.35322 2.64117 + vertex 0.924008 1.35887 2.64141 + vertex 0.921152 1.35456 2.64082 + endloop + endfacet + facet normal -0.206737 -0.096377 0.973638 + outer loop + vertex 0.916686 1.35624 2.64008 + vertex 0.919748 1.3585 2.64096 + vertex 0.917153 1.3605 2.64061 + endloop + endfacet + facet normal -0.0909851 -0.102908 0.990521 + outer loop + vertex 0.927533 1.34634 2.64076 + vertex 0.925774 1.349 2.64088 + vertex 0.922543 1.34604 2.64028 + endloop + endfacet + facet normal -0.0872005 -0.0592832 0.994425 + outer loop + vertex 0.922754 1.3506 2.64073 + vertex 0.925967 1.35322 2.64117 + vertex 0.921152 1.35456 2.64082 + endloop + endfacet + facet normal -0.0392645 -0.0689951 0.996844 + outer loop + vertex 0.927533 1.34634 2.64076 + vertex 0.930008 1.34965 2.64109 + vertex 0.925774 1.349 2.64088 + endloop + endfacet + facet normal -0.0154594 -0.0576248 0.998219 + outer loop + vertex 0.930257 1.35391 2.64137 + vertex 0.933545 1.35759 2.64163 + vertex 0.928967 1.35785 2.64157 + endloop + endfacet + facet normal -0.0166128 -0.0616663 0.997959 + outer loop + vertex 0.928967 1.35785 2.64157 + vertex 0.933203 1.36248 2.64193 + vertex 0.928529 1.36281 2.64187 + endloop + endfacet + facet normal -0.0182107 -0.0609138 0.997977 + outer loop + vertex 0.928529 1.36281 2.64187 + vertex 0.933213 1.36756 2.64225 + vertex 0.928482 1.3677 2.64217 + endloop + endfacet + facet normal -0.0213355 -0.0571975 0.998135 + outer loop + vertex 0.928482 1.3677 2.64217 + vertex 0.933296 1.37261 2.64255 + vertex 0.928321 1.3726 2.64245 + endloop + endfacet + facet normal -0.0219442 -0.0574546 0.998107 + outer loop + vertex 0.928321 1.3726 2.64245 + vertex 0.933332 1.37765 2.64285 + vertex 0.928267 1.37762 2.64273 + endloop + endfacet + facet normal -0.0208991 -0.0576454 0.998118 + outer loop + vertex 0.928267 1.37762 2.64273 + vertex 0.93336 1.38271 2.64314 + vertex 0.928261 1.38263 2.64302 + endloop + endfacet + facet normal -0.0161221 -0.0557428 0.998315 + outer loop + vertex 0.92828 1.38765 2.64332 + vertex 0.933444 1.3928 2.64369 + vertex 0.928346 1.39267 2.6436 + endloop + endfacet + facet normal -0.0158746 -0.0416269 0.999007 + outer loop + vertex 0.928435 1.40265 2.64408 + vertex 0.933532 1.40777 2.64437 + vertex 0.928433 1.40765 2.64429 + endloop + endfacet + facet normal -0.0153872 -0.0412345 0.999031 + outer loop + vertex 0.928433 1.40765 2.64429 + vertex 0.933537 1.41275 2.64458 + vertex 0.928431 1.41266 2.64449 + endloop + endfacet + facet normal -0.0135994 -0.041806 0.999033 + outer loop + vertex 0.928431 1.41266 2.64449 + vertex 0.93354 1.41774 2.64478 + vertex 0.928429 1.41768 2.6447 + endloop + endfacet + facet normal -0.0136391 -0.0387583 0.999156 + outer loop + vertex 0.93354 1.41774 2.64478 + vertex 0.933533 1.42275 2.64497 + vertex 0.928429 1.41768 2.6447 + endloop + endfacet + facet normal 0.0144421 -0.0358924 0.999251 + outer loop + vertex 0.933533 1.42275 2.64497 + vertex 0.938538 1.42774 2.64508 + vertex 0.933513 1.42776 2.64515 + endloop + endfacet + facet normal -0.00557456 -0.0363012 0.999325 + outer loop + vertex 0.928426 1.42774 2.64511 + vertex 0.933524 1.43278 2.64532 + vertex 0.928504 1.43279 2.64529 + endloop + endfacet + facet normal 0.0144673 -0.0307844 0.999421 + outer loop + vertex 0.938538 1.42774 2.64508 + vertex 0.938506 1.43273 2.64523 + vertex 0.933513 1.42776 2.64515 + endloop + endfacet + facet normal 0.0182475 -0.0294356 0.9994 + outer loop + vertex 0.933524 1.43278 2.64532 + vertex 0.938524 1.43773 2.64537 + vertex 0.933625 1.43778 2.64546 + endloop + endfacet + facet normal 0.0289879 -0.0271313 0.999211 + outer loop + vertex 0.943481 1.4327 2.64509 + vertex 0.943447 1.43768 2.64522 + vertex 0.938506 1.43273 2.64523 + endloop + endfacet + facet normal 0.0300493 -0.0252611 0.999229 + outer loop + vertex 0.938524 1.43773 2.64537 + vertex 0.943478 1.44268 2.64535 + vertex 0.938662 1.44273 2.64549 + endloop + endfacet + facet normal 0.0338651 -0.0231256 0.999159 + outer loop + vertex 0.943478 1.44268 2.64535 + vertex 0.94842 1.44764 2.64529 + vertex 0.943636 1.4477 2.64546 + endloop + endfacet + facet normal 0.0353746 -0.024468 0.999075 + outer loop + vertex 0.953379 1.44263 2.645 + vertex 0.953352 1.4476 2.64512 + vertex 0.948389 1.44265 2.64518 + endloop + endfacet + facet normal 0.0339751 -0.0220461 0.999179 + outer loop + vertex 0.94842 1.44764 2.64529 + vertex 0.95336 1.45258 2.64524 + vertex 0.948538 1.45268 2.6454 + endloop + endfacet + facet normal 0.0353805 -0.0233323 0.999102 + outer loop + vertex 0.958386 1.4476 2.64494 + vertex 0.958361 1.45256 2.64506 + vertex 0.953352 1.4476 2.64512 + endloop + endfacet + facet normal 0.034431 -0.0207711 0.999191 + outer loop + vertex 0.95336 1.45258 2.64524 + vertex 0.958342 1.45753 2.64517 + vertex 0.953404 1.45763 2.64534 + endloop + endfacet + facet normal 0.0414239 -0.0211398 0.998918 + outer loop + vertex 0.963464 1.45263 2.64485 + vertex 0.963442 1.45759 2.64496 + vertex 0.958361 1.45256 2.64506 + endloop + endfacet + facet normal 0.041891 -0.0185278 0.99895 + outer loop + vertex 0.958342 1.45753 2.64517 + vertex 0.963411 1.46254 2.64505 + vertex 0.958326 1.46254 2.64526 + endloop + endfacet + facet normal 0.0640722 -0.0176345 0.997789 + outer loop + vertex 0.968582 1.45774 2.64463 + vertex 0.968573 1.46271 2.64472 + vertex 0.963442 1.45759 2.64496 + endloop + endfacet + facet normal 0.0652622 -0.014539 0.997762 + outer loop + vertex 0.963411 1.46254 2.64505 + vertex 0.968544 1.46766 2.64479 + vertex 0.963373 1.4675 2.64512 + endloop + endfacet + facet normal 0.108067 -0.0117572 0.994074 + outer loop + vertex 0.973606 1.46285 2.64417 + vertex 0.973605 1.46784 2.64423 + vertex 0.968573 1.46271 2.64472 + endloop + endfacet + facet normal 0.110695 -0.0101678 0.993802 + outer loop + vertex 0.968544 1.46766 2.64479 + vertex 0.973587 1.47281 2.64428 + vertex 0.968506 1.4726 2.64484 + endloop + endfacet + facet normal 0.173512 -0.00610295 0.984813 + outer loop + vertex 0.978319 1.46775 2.6434 + vertex 0.978313 1.47275 2.64343 + vertex 0.973605 1.46784 2.64423 + endloop + endfacet + facet normal 0.0834158 0.0360382 0.995863 + outer loop + vertex 0.973381 1.59747 2.64301 + vertex 0.973425 1.60226 2.64284 + vertex 0.968661 1.59761 2.64341 + endloop + endfacet + facet normal 0.0574721 0.03343 0.997787 + outer loop + vertex 0.968686 1.59264 2.64357 + vertex 0.968661 1.59761 2.64341 + vertex 0.963597 1.59255 2.64387 + endloop + endfacet + facet normal 0.0444537 0.0331504 0.998461 + outer loop + vertex 0.963593 1.58751 2.64403 + vertex 0.963597 1.59255 2.64387 + vertex 0.958458 1.58743 2.64427 + endloop + endfacet + facet normal 0.0444913 0.0310787 0.998526 + outer loop + vertex 0.958429 1.58237 2.64442 + vertex 0.963593 1.58751 2.64403 + vertex 0.958458 1.58743 2.64427 + endloop + endfacet + facet normal 0.0378847 0.0304887 0.998817 + outer loop + vertex 0.958388 1.5773 2.64458 + vertex 0.958429 1.58237 2.64442 + vertex 0.953342 1.57728 2.64477 + endloop + endfacet + facet normal 0.0378972 0.0278393 0.998894 + outer loop + vertex 0.953287 1.57229 2.64491 + vertex 0.958388 1.5773 2.64458 + vertex 0.953342 1.57728 2.64477 + endloop + endfacet + facet normal 0.0370751 0.0259301 0.998976 + outer loop + vertex 0.953209 1.56733 2.64505 + vertex 0.953287 1.57229 2.64491 + vertex 0.948408 1.56776 2.64521 + endloop + endfacet + facet normal 0.0362557 0.0239523 0.999055 + outer loop + vertex 0.948395 1.56294 2.64533 + vertex 0.948408 1.56776 2.64521 + vertex 0.943303 1.5639 2.64549 + endloop + endfacet + facet normal 0.0302808 0.0273358 0.999168 + outer loop + vertex 0.93901 1.56292 2.64565 + vertex 0.943303 1.5639 2.64549 + vertex 0.93905 1.56709 2.64553 + endloop + endfacet + facet normal 0.0347987 0.0270261 0.999029 + outer loop + vertex 0.944457 1.56856 2.64533 + vertex 0.948493 1.57247 2.64509 + vertex 0.943618 1.57238 2.64526 + endloop + endfacet + facet normal 0.0347934 0.0273132 0.999021 + outer loop + vertex 0.948493 1.57247 2.64509 + vertex 0.948363 1.57726 2.64496 + vertex 0.943618 1.57238 2.64526 + endloop + endfacet + facet normal 0.038371 0.0280768 0.998869 + outer loop + vertex 0.948363 1.57726 2.64496 + vertex 0.953363 1.58232 2.64463 + vertex 0.948353 1.58231 2.64482 + endloop + endfacet + facet normal 0.0384961 0.0294428 0.998825 + outer loop + vertex 0.948353 1.58231 2.64482 + vertex 0.953399 1.58739 2.64447 + vertex 0.948409 1.58738 2.64467 + endloop + endfacet + facet normal 0.0317425 0.0335154 0.998934 + outer loop + vertex 0.943452 1.58741 2.64483 + vertex 0.948455 1.59242 2.6445 + vertex 0.943514 1.59244 2.64466 + endloop + endfacet + facet normal 0.0384934 0.0310424 0.998777 + outer loop + vertex 0.953399 1.58739 2.64447 + vertex 0.953427 1.59242 2.64432 + vertex 0.948409 1.58738 2.64467 + endloop + endfacet + facet normal 0.0361893 0.0352918 0.998722 + outer loop + vertex 0.948455 1.59242 2.6445 + vertex 0.953428 1.5974 2.64415 + vertex 0.948457 1.5974 2.64433 + endloop + endfacet + facet normal 0.0418035 0.0336457 0.998559 + outer loop + vertex 0.958472 1.59246 2.6441 + vertex 0.958467 1.59745 2.64394 + vertex 0.953427 1.59242 2.64432 + endloop + endfacet + facet normal 0.0402112 0.0385523 0.998447 + outer loop + vertex 0.953428 1.5974 2.64415 + vertex 0.958449 1.60242 2.64375 + vertex 0.953407 1.60236 2.64396 + endloop + endfacet + facet normal 0.0460949 0.0361008 0.998285 + outer loop + vertex 0.963584 1.59756 2.6437 + vertex 0.963557 1.60255 2.64352 + vertex 0.958467 1.59745 2.64394 + endloop + endfacet + facet normal 0.0428014 0.0421066 0.998196 + outer loop + vertex 0.958449 1.60242 2.64375 + vertex 0.963529 1.60753 2.64332 + vertex 0.958433 1.60738 2.64354 + endloop + endfacet + facet normal 0.0564978 0.0372935 0.997706 + outer loop + vertex 0.968639 1.6026 2.64323 + vertex 0.968582 1.60762 2.64304 + vertex 0.963557 1.60255 2.64352 + endloop + endfacet + facet normal 0.0493377 0.0452751 0.997755 + outer loop + vertex 0.963529 1.60753 2.64332 + vertex 0.968529 1.61262 2.64284 + vertex 0.963534 1.61249 2.64309 + endloop + endfacet + facet normal 0.0837947 0.0349002 0.995872 + outer loop + vertex 0.973472 1.60733 2.64264 + vertex 0.973292 1.61245 2.64248 + vertex 0.968582 1.60762 2.64304 + endloop + endfacet + facet normal 0.0696937 0.0455765 0.996527 + outer loop + vertex 0.968529 1.61262 2.64284 + vertex 0.973225 1.61751 2.64229 + vertex 0.968563 1.61762 2.64261 + endloop + endfacet + facet normal 0.135485 0.0320816 0.99026 + outer loop + vertex 0.977755 1.61173 2.64189 + vertex 0.977498 1.61688 2.64176 + vertex 0.973292 1.61245 2.64248 + endloop + endfacet + facet normal 0.0696675 0.0443187 0.996585 + outer loop + vertex 0.973225 1.61751 2.64229 + vertex 0.973248 1.62252 2.64206 + vertex 0.968563 1.61762 2.64261 + endloop + endfacet + facet normal 0.0493236 0.0457701 0.997734 + outer loop + vertex 0.968529 1.61262 2.64284 + vertex 0.968563 1.61762 2.64261 + vertex 0.963534 1.61249 2.64309 + endloop + endfacet + facet normal 0.0427013 0.0452955 0.998061 + outer loop + vertex 0.963529 1.60753 2.64332 + vertex 0.963534 1.61249 2.64309 + vertex 0.958433 1.60738 2.64354 + endloop + endfacet + facet normal 0.0401608 0.0421027 0.998306 + outer loop + vertex 0.958449 1.60242 2.64375 + vertex 0.958433 1.60738 2.64354 + vertex 0.953407 1.60236 2.64396 + endloop + endfacet + facet normal 0.0361871 0.0385417 0.998602 + outer loop + vertex 0.953428 1.5974 2.64415 + vertex 0.953407 1.60236 2.64396 + vertex 0.948457 1.5974 2.64433 + endloop + endfacet + facet normal 0.0317498 0.0352988 0.998872 + outer loop + vertex 0.948455 1.59242 2.6445 + vertex 0.948457 1.5974 2.64433 + vertex 0.943514 1.59244 2.64466 + endloop + endfacet + facet normal 0.0264383 0.0335858 0.999086 + outer loop + vertex 0.943452 1.58741 2.64483 + vertex 0.943514 1.59244 2.64466 + vertex 0.938513 1.58746 2.64496 + endloop + endfacet + facet normal 0.0175725 0.0322939 0.999324 + outer loop + vertex 0.938395 1.58241 2.64512 + vertex 0.938513 1.58746 2.64496 + vertex 0.933446 1.58249 2.64521 + endloop + endfacet + facet normal 0.0275473 0.0293465 0.99919 + outer loop + vertex 0.938373 1.57737 2.64527 + vertex 0.943362 1.58233 2.64499 + vertex 0.938395 1.58241 2.64512 + endloop + endfacet + facet normal 0.0285124 0.0276295 0.999212 + outer loop + vertex 0.938653 1.57249 2.6454 + vertex 0.943373 1.57727 2.64513 + vertex 0.938373 1.57737 2.64527 + endloop + endfacet + facet normal 0.0212886 0.0258089 0.99944 + outer loop + vertex 0.93905 1.56709 2.64553 + vertex 0.938653 1.57249 2.6454 + vertex 0.934706 1.56892 2.64558 + endloop + endfacet + facet normal 0.0202006 0.0232228 0.999526 + outer loop + vertex 0.933333 1.56499 2.6457 + vertex 0.93905 1.56709 2.64553 + vertex 0.934706 1.56892 2.64558 + endloop + endfacet + facet normal 0.0090851 0.024208 0.999666 + outer loop + vertex 0.929461 1.56394 2.64576 + vertex 0.931188 1.56196 2.64579 + vertex 0.933333 1.56499 2.6457 + endloop + endfacet + facet normal -0.00567569 0.0232596 0.999713 + outer loop + vertex 0.929461 1.56394 2.64576 + vertex 0.926094 1.56399 2.64574 + vertex 0.927772 1.56056 2.64583 + endloop + endfacet + facet normal 0.00186907 0.0298008 0.999554 + outer loop + vertex 0.929726 1.56776 2.64565 + vertex 0.933715 1.57269 2.64549 + vertex 0.928544 1.5725 2.64551 + endloop + endfacet + facet normal 4.596e-05 0.0290917 0.999577 + outer loop + vertex 0.928544 1.5725 2.64551 + vertex 0.933381 1.57747 2.64536 + vertex 0.928359 1.5775 2.64536 + endloop + endfacet + facet normal -0.0352534 0.0375962 0.998671 + outer loop + vertex 0.923449 1.5874 2.64486 + vertex 0.928558 1.59249 2.64484 + vertex 0.923429 1.59239 2.64467 + endloop + endfacet + facet normal -0.0352747 0.0387203 0.998627 + outer loop + vertex 0.928558 1.59249 2.64484 + vertex 0.928531 1.59749 2.64465 + vertex 0.923429 1.59239 2.64467 + endloop + endfacet + facet normal -0.0357409 0.0391869 0.998592 + outer loop + vertex 0.923429 1.59239 2.64467 + vertex 0.928531 1.59749 2.64465 + vertex 0.923403 1.59738 2.64447 + endloop + endfacet + facet normal -0.0357596 0.0402031 0.998551 + outer loop + vertex 0.928531 1.59749 2.64465 + vertex 0.928514 1.60248 2.64445 + vertex 0.923403 1.59738 2.64447 + endloop + endfacet + facet normal -0.0368544 0.0413006 0.998467 + outer loop + vertex 0.923403 1.59738 2.64447 + vertex 0.928514 1.60248 2.64445 + vertex 0.923393 1.60238 2.64426 + endloop + endfacet + facet normal -0.0368649 0.0418681 0.998443 + outer loop + vertex 0.928514 1.60248 2.64445 + vertex 0.928511 1.60748 2.64424 + vertex 0.923393 1.60238 2.64426 + endloop + endfacet + facet normal -0.0382565 0.0432646 0.998331 + outer loop + vertex 0.923393 1.60238 2.64426 + vertex 0.928511 1.60748 2.64424 + vertex 0.923395 1.60738 2.64405 + endloop + endfacet + facet normal -0.0382658 0.0437844 0.998308 + outer loop + vertex 0.928511 1.60748 2.64424 + vertex 0.92851 1.61247 2.64402 + vertex 0.923395 1.60738 2.64405 + endloop + endfacet + facet normal -0.00695162 0.0438217 0.999015 + outer loop + vertex 0.928511 1.60748 2.64424 + vertex 0.933555 1.61247 2.64405 + vertex 0.92851 1.61247 2.64402 + endloop + endfacet + facet normal -0.0069516 0.0441201 0.999002 + outer loop + vertex 0.933555 1.61247 2.64405 + vertex 0.933538 1.61745 2.64383 + vertex 0.92851 1.61247 2.64402 + endloop + endfacet + facet normal -0.00963431 0.0468224 0.998857 + outer loop + vertex 0.92851 1.61247 2.64402 + vertex 0.933538 1.61745 2.64383 + vertex 0.928501 1.61746 2.64379 + endloop + endfacet + facet normal -0.00963445 0.0467398 0.998861 + outer loop + vertex 0.933538 1.61745 2.64383 + vertex 0.933504 1.62242 2.6436 + vertex 0.928501 1.61746 2.64379 + endloop + endfacet + facet normal 0.0111223 0.0468803 0.998839 + outer loop + vertex 0.933538 1.61745 2.64383 + vertex 0.938454 1.62236 2.64355 + vertex 0.933504 1.62242 2.6436 + endloop + endfacet + facet normal 0.0126601 0.0453418 0.998891 + outer loop + vertex 0.938486 1.61739 2.64377 + vertex 0.938454 1.62236 2.64355 + vertex 0.933538 1.61745 2.64383 + endloop + endfacet + facet normal 0.0243961 0.0454075 0.998671 + outer loop + vertex 0.938486 1.61739 2.64377 + vertex 0.94338 1.62231 2.64343 + vertex 0.938454 1.62236 2.64355 + endloop + endfacet + facet normal 0.0244167 0.047638 0.998566 + outer loop + vertex 0.94338 1.62231 2.64343 + vertex 0.943392 1.62729 2.64319 + vertex 0.938454 1.62236 2.64355 + endloop + endfacet + facet normal 0.0243322 0.0477224 0.998564 + outer loop + vertex 0.938454 1.62236 2.64355 + vertex 0.943392 1.62729 2.64319 + vertex 0.93843 1.62732 2.64331 + endloop + endfacet + facet normal 0.032774 0.0476062 0.998328 + outer loop + vertex 0.94338 1.62231 2.64343 + vertex 0.948407 1.62731 2.64303 + vertex 0.943392 1.62729 2.64319 + endloop + endfacet + facet normal 0.0327565 0.0505344 0.998185 + outer loop + vertex 0.948407 1.62731 2.64303 + vertex 0.948519 1.63237 2.64277 + vertex 0.943392 1.62729 2.64319 + endloop + endfacet + facet normal 0.0331137 0.0501746 0.998191 + outer loop + vertex 0.943392 1.62729 2.64319 + vertex 0.948519 1.63237 2.64277 + vertex 0.943455 1.6323 2.64294 + endloop + endfacet + facet normal 0.033066 0.053331 0.998029 + outer loop + vertex 0.948519 1.63237 2.64277 + vertex 0.948668 1.63748 2.64249 + vertex 0.943455 1.6323 2.64294 + endloop + endfacet + facet normal 0.0398987 0.0531196 0.997791 + outer loop + vertex 0.948519 1.63237 2.64277 + vertex 0.953758 1.63758 2.64228 + vertex 0.948668 1.63748 2.64249 + endloop + endfacet + facet normal 0.0398411 0.0555663 0.99766 + outer loop + vertex 0.953758 1.63758 2.64228 + vertex 0.953761 1.64265 2.642 + vertex 0.948668 1.63748 2.64249 + endloop + endfacet + facet normal 0.0395095 0.0558922 0.997655 + outer loop + vertex 0.948668 1.63748 2.64249 + vertex 0.953761 1.64265 2.642 + vertex 0.948788 1.6426 2.6422 + endloop + endfacet + facet normal 0.033207 0.0560526 0.997875 + outer loop + vertex 0.948668 1.63748 2.64249 + vertex 0.948788 1.6426 2.6422 + vertex 0.943581 1.63737 2.64267 + endloop + endfacet + facet normal 0.0329502 0.056308 0.99787 + outer loop + vertex 0.943581 1.63737 2.64267 + vertex 0.948788 1.6426 2.6422 + vertex 0.943741 1.6425 2.64237 + endloop + endfacet + facet normal 0.0328897 0.0590481 0.997713 + outer loop + vertex 0.948788 1.6426 2.6422 + vertex 0.94877 1.64766 2.6419 + vertex 0.943741 1.6425 2.64237 + endloop + endfacet + facet normal 0.0380961 0.0590557 0.997527 + outer loop + vertex 0.948788 1.6426 2.6422 + vertex 0.953532 1.64756 2.64172 + vertex 0.94877 1.64766 2.6419 + endloop + endfacet + facet normal 0.0381283 0.060859 0.997418 + outer loop + vertex 0.953532 1.64756 2.64172 + vertex 0.953049 1.65225 2.64146 + vertex 0.94877 1.64766 2.6419 + endloop + endfacet + facet normal 0.037246 0.061679 0.997401 + outer loop + vertex 0.94877 1.64766 2.6419 + vertex 0.953049 1.65225 2.64146 + vertex 0.94849 1.65249 2.64161 + endloop + endfacet + facet normal 0.041196 0.0611668 0.997277 + outer loop + vertex 0.953532 1.64756 2.64172 + vertex 0.956996 1.65137 2.64135 + vertex 0.953049 1.65225 2.64146 + endloop + endfacet + facet normal 0.0414555 0.0623441 0.997193 + outer loop + vertex 0.956996 1.65137 2.64135 + vertex 0.95682 1.65638 2.64104 + vertex 0.953049 1.65225 2.64146 + endloop + endfacet + facet normal 0.0402726 0.0634237 0.997174 + outer loop + vertex 0.953049 1.65225 2.64146 + vertex 0.95682 1.65638 2.64104 + vertex 0.951949 1.65607 2.64126 + endloop + endfacet + facet normal 0.0423434 0.0623728 0.997154 + outer loop + vertex 0.95682 1.65638 2.64104 + vertex 0.956996 1.65137 2.64135 + vertex 0.961954 1.6516 2.64112 + endloop + endfacet + facet normal 0.0402152 0.0600879 0.997383 + outer loop + vertex 0.96146 1.65639 2.64085 + vertex 0.95682 1.65638 2.64104 + vertex 0.961954 1.6516 2.64112 + endloop + endfacet + facet normal 0.038642 0.0599298 0.997454 + outer loop + vertex 0.96146 1.65639 2.64085 + vertex 0.961954 1.6516 2.64112 + vertex 0.964754 1.6546 2.64083 + endloop + endfacet + facet normal 0.0399872 0.0624066 0.997249 + outer loop + vertex 0.964754 1.6546 2.64083 + vertex 0.964417 1.65911 2.64057 + vertex 0.96146 1.65639 2.64085 + endloop + endfacet + facet normal 0.0395288 0.0591034 0.997469 + outer loop + vertex 0.966714 1.65143 2.64094 + vertex 0.964754 1.6546 2.64083 + vertex 0.961954 1.6516 2.64112 + endloop + endfacet + facet normal 0.0394046 0.0554884 0.997681 + outer loop + vertex 0.966714 1.65143 2.64094 + vertex 0.961954 1.6516 2.64112 + vertex 0.9671 1.64658 2.6412 + endloop + endfacet + facet normal 0.0457003 0.0559738 0.997386 + outer loop + vertex 0.966714 1.65143 2.64094 + vertex 0.9671 1.64658 2.6412 + vertex 0.970013 1.64961 2.64089 + endloop + endfacet + facet normal 0.0498588 0.0635183 0.996734 + outer loop + vertex 0.970013 1.64961 2.64089 + vertex 0.969661 1.65418 2.64062 + vertex 0.966714 1.65143 2.64094 + endloop + endfacet + facet normal 0.0482345 0.0535348 0.9974 + outer loop + vertex 0.971877 1.64645 2.64097 + vertex 0.970013 1.64961 2.64089 + vertex 0.9671 1.64658 2.6412 + endloop + endfacet + facet normal 0.0415561 0.0576898 0.997469 + outer loop + vertex 0.961954 1.6516 2.64112 + vertex 0.96211 1.64638 2.64142 + vertex 0.9671 1.64658 2.6412 + endloop + endfacet + facet normal 0.0416748 0.0549243 0.99762 + outer loop + vertex 0.963209 1.64227 2.6416 + vertex 0.9671 1.64658 2.6412 + vertex 0.96211 1.64638 2.64142 + endloop + endfacet + facet normal 0.0451391 0.0558415 0.997419 + outer loop + vertex 0.963209 1.64227 2.6416 + vertex 0.96211 1.64638 2.64142 + vertex 0.958571 1.64254 2.64179 + endloop + endfacet + facet normal 0.045065 0.0545131 0.997496 + outer loop + vertex 0.958786 1.63763 2.64205 + vertex 0.963209 1.64227 2.6416 + vertex 0.958571 1.64254 2.64179 + endloop + endfacet + facet normal 0.0451063 0.0545148 0.997494 + outer loop + vertex 0.958786 1.63763 2.64205 + vertex 0.958571 1.64254 2.64179 + vertex 0.953758 1.63758 2.64228 + endloop + endfacet + facet normal 0.0451256 0.0526756 0.997592 + outer loop + vertex 0.953644 1.63248 2.64256 + vertex 0.958786 1.63763 2.64205 + vertex 0.953758 1.63758 2.64228 + endloop + endfacet + facet normal 0.0456238 0.0521784 0.997595 + outer loop + vertex 0.958778 1.63256 2.64232 + vertex 0.958786 1.63763 2.64205 + vertex 0.953644 1.63248 2.64256 + endloop + endfacet + facet normal 0.0456626 0.0501852 0.997696 + outer loop + vertex 0.953516 1.62738 2.64282 + vertex 0.958778 1.63256 2.64232 + vertex 0.953644 1.63248 2.64256 + endloop + endfacet + facet normal 0.0403 0.0503309 0.997919 + outer loop + vertex 0.953516 1.62738 2.64282 + vertex 0.953644 1.63248 2.64256 + vertex 0.948407 1.62731 2.64303 + endloop + endfacet + facet normal 0.0403438 0.0474996 0.998056 + outer loop + vertex 0.948356 1.62229 2.64327 + vertex 0.953516 1.62738 2.64282 + vertex 0.948407 1.62731 2.64303 + endloop + endfacet + facet normal 0.0402689 0.0475756 0.998056 + outer loop + vertex 0.953422 1.62232 2.64306 + vertex 0.953516 1.62738 2.64282 + vertex 0.948356 1.62229 2.64327 + endloop + endfacet + facet normal 0.0402843 0.0451422 0.998168 + outer loop + vertex 0.948347 1.6173 2.6435 + vertex 0.953422 1.62232 2.64306 + vertex 0.948356 1.62229 2.64327 + endloop + endfacet + facet normal 0.0328581 0.0451665 0.998439 + outer loop + vertex 0.948347 1.6173 2.6435 + vertex 0.948356 1.62229 2.64327 + vertex 0.9434 1.61734 2.64366 + endloop + endfacet + facet normal 0.0328463 0.0431759 0.998527 + outer loop + vertex 0.943429 1.61237 2.64387 + vertex 0.948347 1.6173 2.6435 + vertex 0.9434 1.61734 2.64366 + endloop + endfacet + facet normal 0.0248256 0.0431391 0.998761 + outer loop + vertex 0.943429 1.61237 2.64387 + vertex 0.9434 1.61734 2.64366 + vertex 0.938512 1.61242 2.64399 + endloop + endfacet + facet normal 0.0248142 0.0419767 0.99881 + outer loop + vertex 0.938529 1.60744 2.6442 + vertex 0.943429 1.61237 2.64387 + vertex 0.938512 1.61242 2.64399 + endloop + endfacet + facet normal 0.0139595 0.0419472 0.999022 + outer loop + vertex 0.938529 1.60744 2.6442 + vertex 0.938512 1.61242 2.64399 + vertex 0.933562 1.60749 2.64427 + endloop + endfacet + facet normal 0.0139513 0.0408638 0.999067 + outer loop + vertex 0.933569 1.60249 2.64447 + vertex 0.938529 1.60744 2.6442 + vertex 0.933562 1.60749 2.64427 + endloop + endfacet + facet normal -0.00447188 0.0408406 0.999156 + outer loop + vertex 0.933569 1.60249 2.64447 + vertex 0.933562 1.60749 2.64427 + vertex 0.928514 1.60248 2.64445 + endloop + endfacet + facet normal 0.0145608 0.0402542 0.999083 + outer loop + vertex 0.938545 1.60246 2.6444 + vertex 0.938529 1.60744 2.6442 + vertex 0.933569 1.60249 2.64447 + endloop + endfacet + facet normal 0.0134813 0.0424256 0.999009 + outer loop + vertex 0.933562 1.60749 2.64427 + vertex 0.938512 1.61242 2.64399 + vertex 0.933555 1.61247 2.64405 + endloop + endfacet + facet normal -0.00554103 0.0424003 0.999085 + outer loop + vertex 0.933562 1.60749 2.64427 + vertex 0.933555 1.61247 2.64405 + vertex 0.928511 1.60748 2.64424 + endloop + endfacet + facet normal 0.0134897 0.0433423 0.998969 + outer loop + vertex 0.938512 1.61242 2.64399 + vertex 0.938486 1.61739 2.64377 + vertex 0.933555 1.61247 2.64405 + endloop + endfacet + facet normal 0.0248838 0.0419076 0.998812 + outer loop + vertex 0.943456 1.60739 2.64408 + vertex 0.943429 1.61237 2.64387 + vertex 0.938529 1.60744 2.6442 + endloop + endfacet + facet normal 0.0245713 0.0433916 0.998756 + outer loop + vertex 0.938512 1.61242 2.64399 + vertex 0.9434 1.61734 2.64366 + vertex 0.938486 1.61739 2.64377 + endloop + endfacet + facet normal 0.0321975 0.0438225 0.99852 + outer loop + vertex 0.948366 1.61232 2.64371 + vertex 0.948347 1.6173 2.6435 + vertex 0.943429 1.61237 2.64387 + endloop + endfacet + facet normal 0.0327872 0.0452374 0.998438 + outer loop + vertex 0.9434 1.61734 2.64366 + vertex 0.948356 1.62229 2.64327 + vertex 0.94338 1.62231 2.64343 + endloop + endfacet + facet normal 0.0394841 0.0459518 0.998163 + outer loop + vertex 0.953375 1.61729 2.6433 + vertex 0.953422 1.62232 2.64306 + vertex 0.948347 1.6173 2.6435 + endloop + endfacet + facet normal 0.0460284 0.0474569 0.997812 + outer loop + vertex 0.953422 1.62232 2.64306 + vertex 0.958684 1.62747 2.64258 + vertex 0.953516 1.62738 2.64282 + endloop + endfacet + facet normal 0.0452217 0.0482803 0.99781 + outer loop + vertex 0.958568 1.62238 2.64283 + vertex 0.958684 1.62747 2.64258 + vertex 0.953422 1.62232 2.64306 + endloop + endfacet + facet normal 0.0459805 0.0498628 0.997697 + outer loop + vertex 0.958684 1.62747 2.64258 + vertex 0.958778 1.63256 2.64232 + vertex 0.953516 1.62738 2.64282 + endloop + endfacet + facet normal 0.0468979 0.0498438 0.997655 + outer loop + vertex 0.958684 1.62747 2.64258 + vertex 0.963805 1.63259 2.64208 + vertex 0.958778 1.63256 2.64232 + endloop + endfacet + facet normal 0.046883 0.0517258 0.99756 + outer loop + vertex 0.963805 1.63259 2.64208 + vertex 0.963607 1.63748 2.64183 + vertex 0.958778 1.63256 2.64232 + endloop + endfacet + facet normal 0.0441035 0.05162 0.997692 + outer loop + vertex 0.963805 1.63259 2.64208 + vertex 0.96817 1.63724 2.64165 + vertex 0.963607 1.63748 2.64183 + endloop + endfacet + facet normal 0.0441401 0.052362 0.997652 + outer loop + vertex 0.96817 1.63724 2.64165 + vertex 0.967163 1.64133 2.64148 + vertex 0.963607 1.63748 2.64183 + endloop + endfacet + facet normal 0.0435002 0.0529523 0.997649 + outer loop + vertex 0.963607 1.63748 2.64183 + vertex 0.967163 1.64133 2.64148 + vertex 0.963209 1.64227 2.6416 + endloop + endfacet + facet normal 0.0486892 0.0534718 0.997382 + outer loop + vertex 0.96817 1.63724 2.64165 + vertex 0.971995 1.64167 2.64122 + vertex 0.967163 1.64133 2.64148 + endloop + endfacet + facet normal 0.0487038 0.053271 0.997392 + outer loop + vertex 0.9671 1.64658 2.6412 + vertex 0.967163 1.64133 2.64148 + vertex 0.971995 1.64167 2.64122 + endloop + endfacet + facet normal 0.0451923 0.0505986 0.997696 + outer loop + vertex 0.968512 1.63251 2.64187 + vertex 0.96817 1.63724 2.64165 + vertex 0.963805 1.63259 2.64208 + endloop + endfacet + facet normal 0.0465733 0.0501682 0.997654 + outer loop + vertex 0.963798 1.62757 2.64233 + vertex 0.963805 1.63259 2.64208 + vertex 0.958684 1.62747 2.64258 + endloop + endfacet + facet normal 0.0464255 0.0521751 0.997558 + outer loop + vertex 0.958778 1.63256 2.64232 + vertex 0.963607 1.63748 2.64183 + vertex 0.958786 1.63763 2.64205 + endloop + endfacet + facet normal 0.0464537 0.0531903 0.997503 + outer loop + vertex 0.963607 1.63748 2.64183 + vertex 0.963209 1.64227 2.6416 + vertex 0.958786 1.63763 2.64205 + endloop + endfacet + facet normal 0.0440046 0.0568857 0.99741 + outer loop + vertex 0.958571 1.64254 2.64179 + vertex 0.96211 1.64638 2.64142 + vertex 0.958138 1.64733 2.64154 + endloop + endfacet + facet normal 0.0440647 0.056891 0.997407 + outer loop + vertex 0.958571 1.64254 2.64179 + vertex 0.958138 1.64733 2.64154 + vertex 0.953761 1.64265 2.642 + endloop + endfacet + facet normal 0.0430025 0.057884 0.997397 + outer loop + vertex 0.953761 1.64265 2.642 + vertex 0.958138 1.64733 2.64154 + vertex 0.953532 1.64756 2.64172 + endloop + endfacet + facet normal 0.0435635 0.0532222 0.997632 + outer loop + vertex 0.967163 1.64133 2.64148 + vertex 0.9671 1.64658 2.6412 + vertex 0.963209 1.64227 2.6416 + endloop + endfacet + facet normal 0.0442122 0.0577625 0.997351 + outer loop + vertex 0.96211 1.64638 2.64142 + vertex 0.961954 1.6516 2.64112 + vertex 0.958138 1.64733 2.64154 + endloop + endfacet + facet normal 0.0487091 0.0647466 0.996712 + outer loop + vertex 0.964754 1.6546 2.64083 + vertex 0.966714 1.65143 2.64094 + vertex 0.969661 1.65418 2.64062 + endloop + endfacet + facet normal 0.0424932 0.0592952 0.997336 + outer loop + vertex 0.958138 1.64733 2.64154 + vertex 0.961954 1.6516 2.64112 + vertex 0.956996 1.65137 2.64135 + endloop + endfacet + facet normal 0.0430787 0.0594589 0.997301 + outer loop + vertex 0.958138 1.64733 2.64154 + vertex 0.956996 1.65137 2.64135 + vertex 0.953532 1.64756 2.64172 + endloop + endfacet + facet normal 0.0394866 0.0577285 0.997551 + outer loop + vertex 0.953761 1.64265 2.642 + vertex 0.953532 1.64756 2.64172 + vertex 0.948788 1.6426 2.6422 + endloop + endfacet + facet normal 0.0440362 0.0555539 0.997484 + outer loop + vertex 0.953758 1.63758 2.64228 + vertex 0.958571 1.64254 2.64179 + vertex 0.953761 1.64265 2.642 + endloop + endfacet + facet normal 0.0402213 0.0527959 0.997795 + outer loop + vertex 0.953644 1.63248 2.64256 + vertex 0.953758 1.63758 2.64228 + vertex 0.948519 1.63237 2.64277 + endloop + endfacet + facet normal 0.0402771 0.0503541 0.997919 + outer loop + vertex 0.948407 1.62731 2.64303 + vertex 0.953644 1.63248 2.64256 + vertex 0.948519 1.63237 2.64277 + endloop + endfacet + facet normal 0.0327895 0.0475907 0.998329 + outer loop + vertex 0.948356 1.62229 2.64327 + vertex 0.948407 1.62731 2.64303 + vertex 0.94338 1.62231 2.64343 + endloop + endfacet + facet normal 0.0245899 0.0452146 0.998675 + outer loop + vertex 0.9434 1.61734 2.64366 + vertex 0.94338 1.62231 2.64343 + vertex 0.938486 1.61739 2.64377 + endloop + endfacet + facet normal 0.0126472 0.0441848 0.998943 + outer loop + vertex 0.933555 1.61247 2.64405 + vertex 0.938486 1.61739 2.64377 + vertex 0.933538 1.61745 2.64383 + endloop + endfacet + facet normal -0.00554033 0.0419168 0.999106 + outer loop + vertex 0.928514 1.60248 2.64445 + vertex 0.933562 1.60749 2.64427 + vertex 0.928511 1.60748 2.64424 + endloop + endfacet + facet normal -0.00447085 0.040331 0.999176 + outer loop + vertex 0.928531 1.59749 2.64465 + vertex 0.933569 1.60249 2.64447 + vertex 0.928514 1.60248 2.64445 + endloop + endfacet + facet normal -0.00363776 0.0394938 0.999213 + outer loop + vertex 0.933588 1.5975 2.64467 + vertex 0.933569 1.60249 2.64447 + vertex 0.928531 1.59749 2.64465 + endloop + endfacet + facet normal -0.002487 0.0366344 0.999326 + outer loop + vertex 0.933567 1.58751 2.64504 + vertex 0.933605 1.59251 2.64486 + vertex 0.928553 1.5875 2.64503 + endloop + endfacet + facet normal -0.00363631 0.0389178 0.999236 + outer loop + vertex 0.928558 1.59249 2.64484 + vertex 0.933588 1.5975 2.64467 + vertex 0.928531 1.59749 2.64465 + endloop + endfacet + facet normal 0.0154348 0.0375891 0.999174 + outer loop + vertex 0.938574 1.59248 2.64478 + vertex 0.938568 1.59747 2.64459 + vertex 0.933605 1.59251 2.64486 + endloop + endfacet + facet normal 0.0145561 0.0395587 0.999111 + outer loop + vertex 0.933588 1.5975 2.64467 + vertex 0.938545 1.60246 2.6444 + vertex 0.933569 1.60249 2.64447 + endloop + endfacet + facet normal 0.0241863 0.0392957 0.998935 + outer loop + vertex 0.943513 1.59743 2.64448 + vertex 0.943485 1.60241 2.64428 + vertex 0.938568 1.59747 2.64459 + endloop + endfacet + facet normal 0.0248689 0.0402781 0.998879 + outer loop + vertex 0.938545 1.60246 2.6444 + vertex 0.943456 1.60739 2.64408 + vertex 0.938529 1.60744 2.6442 + endloop + endfacet + facet normal 0.0300642 0.0417421 0.998676 + outer loop + vertex 0.948429 1.60237 2.64413 + vertex 0.948395 1.60735 2.64393 + vertex 0.943485 1.60241 2.64428 + endloop + endfacet + facet normal 0.032182 0.0419386 0.998602 + outer loop + vertex 0.943456 1.60739 2.64408 + vertex 0.948366 1.61232 2.64371 + vertex 0.943429 1.61237 2.64387 + endloop + endfacet + facet normal 0.0363429 0.0447575 0.998337 + outer loop + vertex 0.953383 1.60732 2.64375 + vertex 0.953367 1.6123 2.64352 + vertex 0.948395 1.60735 2.64393 + endloop + endfacet + facet normal 0.0394832 0.0438383 0.998258 + outer loop + vertex 0.948366 1.61232 2.64371 + vertex 0.953375 1.61729 2.6433 + vertex 0.948347 1.6173 2.6435 + endloop + endfacet + facet normal 0.041067 0.0477348 0.998015 + outer loop + vertex 0.95844 1.61234 2.64331 + vertex 0.958483 1.61734 2.64307 + vertex 0.953367 1.6123 2.64352 + endloop + endfacet + facet normal 0.0452585 0.0458862 0.997921 + outer loop + vertex 0.953375 1.61729 2.6433 + vertex 0.958568 1.62238 2.64283 + vertex 0.953422 1.62232 2.64306 + endloop + endfacet + facet normal 0.0429209 0.0499857 0.997827 + outer loop + vertex 0.963594 1.61748 2.64285 + vertex 0.963702 1.62251 2.64259 + vertex 0.958483 1.61734 2.64307 + endloop + endfacet + facet normal 0.0466145 0.0482455 0.997747 + outer loop + vertex 0.958568 1.62238 2.64283 + vertex 0.963798 1.62757 2.64233 + vertex 0.958684 1.62747 2.64258 + endloop + endfacet + facet normal 0.0456374 0.0498845 0.997712 + outer loop + vertex 0.968652 1.62263 2.64236 + vertex 0.968689 1.62765 2.6421 + vertex 0.963702 1.62251 2.64259 + endloop + endfacet + facet normal 0.0451855 0.0501733 0.997718 + outer loop + vertex 0.963798 1.62757 2.64233 + vertex 0.968512 1.63251 2.64187 + vertex 0.963805 1.63259 2.64208 + endloop + endfacet + facet normal 0.0598416 0.0457254 0.99716 + outer loop + vertex 0.973235 1.62754 2.64184 + vertex 0.972882 1.63245 2.64163 + vertex 0.968689 1.62765 2.6421 + endloop + endfacet + facet normal 0.0486324 0.0508381 0.997522 + outer loop + vertex 0.968512 1.63251 2.64187 + vertex 0.971876 1.63647 2.6415 + vertex 0.96817 1.63724 2.64165 + endloop + endfacet + facet normal 0.101097 0.0416713 0.994003 + outer loop + vertex 0.977058 1.63198 2.64123 + vertex 0.975992 1.63729 2.64111 + vertex 0.972882 1.63245 2.64163 + endloop + endfacet + facet normal 0.049101 0.0531161 0.99738 + outer loop + vertex 0.971876 1.63647 2.6415 + vertex 0.971995 1.64167 2.64122 + vertex 0.96817 1.63724 2.64165 + endloop + endfacet + facet normal 0.0482155 0.0527842 0.997441 + outer loop + vertex 0.971877 1.64645 2.64097 + vertex 0.9671 1.64658 2.6412 + vertex 0.971995 1.64167 2.64122 + endloop + endfacet + facet normal 0.0869206 0.0762619 0.993292 + outer loop + vertex 0.970013 1.64961 2.64089 + vertex 0.971877 1.64645 2.64097 + vertex 0.974849 1.64929 2.6405 + endloop + endfacet + facet normal 0.165739 0.0878052 0.982253 + outer loop + vertex 0.975043 1.64472 2.64081 + vertex 0.976544 1.64166 2.64083 + vertex 0.979603 1.64446 2.64006 + endloop + endfacet + facet normal 0.0863309 0.0661644 0.994067 + outer loop + vertex 0.970013 1.64961 2.64089 + vertex 0.974849 1.64929 2.6405 + vertex 0.969661 1.65418 2.64062 + endloop + endfacet + facet normal 0.127308 0.0716512 0.989272 + outer loop + vertex 0.974881 1.65407 2.64021 + vertex 0.97845 1.65749 2.63951 + vertex 0.973812 1.65788 2.64008 + endloop + endfacet + facet normal 0.126435 0.0599638 0.990161 + outer loop + vertex 0.97845 1.65749 2.63951 + vertex 0.978262 1.66221 2.63925 + vertex 0.973812 1.65788 2.64008 + endloop + endfacet + facet normal 0.117167 0.0695867 0.990671 + outer loop + vertex 0.973812 1.65788 2.64008 + vertex 0.978262 1.66221 2.63925 + vertex 0.973501 1.66241 2.63979 + endloop + endfacet + facet normal 0.116819 0.0594919 0.99137 + outer loop + vertex 0.978262 1.66221 2.63925 + vertex 0.978317 1.6672 2.63894 + vertex 0.973501 1.66241 2.63979 + endloop + endfacet + facet normal 0.0485663 0.0630248 0.99683 + outer loop + vertex 0.964754 1.6546 2.64083 + vertex 0.969661 1.65418 2.64062 + vertex 0.964417 1.65911 2.64057 + endloop + endfacet + facet normal 0.0768407 0.0670764 0.994785 + outer loop + vertex 0.973812 1.65788 2.64008 + vertex 0.973501 1.66241 2.63979 + vertex 0.969693 1.65894 2.64032 + endloop + endfacet + facet normal 0.10886 0.0675636 0.991758 + outer loop + vertex 0.973501 1.66241 2.63979 + vertex 0.978317 1.6672 2.63894 + vertex 0.973367 1.66717 2.63949 + endloop + endfacet + facet normal 0.108992 0.0574786 0.992379 + outer loop + vertex 0.978317 1.6672 2.63894 + vertex 0.978384 1.67229 2.63864 + vertex 0.973367 1.66717 2.63949 + endloop + endfacet + facet normal 0.100769 0.0656093 0.992744 + outer loop + vertex 0.973367 1.66717 2.63949 + vertex 0.978384 1.67229 2.63864 + vertex 0.973405 1.67217 2.63915 + endloop + endfacet + facet normal 0.101018 0.0569376 0.993254 + outer loop + vertex 0.978384 1.67229 2.63864 + vertex 0.978334 1.67722 2.63836 + vertex 0.973405 1.67217 2.63915 + endloop + endfacet + facet normal 0.0910821 0.0666878 0.993608 + outer loop + vertex 0.973405 1.67217 2.63915 + vertex 0.978334 1.67722 2.63836 + vertex 0.973502 1.67726 2.6388 + endloop + endfacet + facet normal 0.155454 0.0570919 0.986192 + outer loop + vertex 0.978384 1.67229 2.63864 + vertex 0.982777 1.67724 2.63766 + vertex 0.978334 1.67722 2.63836 + endloop + endfacet + facet normal 0.155576 0.0460565 0.98675 + outer loop + vertex 0.982777 1.67724 2.63766 + vertex 0.982101 1.68125 2.63758 + vertex 0.978334 1.67722 2.63836 + endloop + endfacet + facet normal 0.136541 0.0642017 0.988552 + outer loop + vertex 0.978334 1.67722 2.63836 + vertex 0.982101 1.68125 2.63758 + vertex 0.978457 1.68217 2.63802 + endloop + endfacet + facet normal 0.168305 0.0453939 0.984689 + outer loop + vertex 0.98299 1.67228 2.63785 + vertex 0.982777 1.67724 2.63766 + vertex 0.978384 1.67229 2.63864 + endloop + endfacet + facet normal 0.168224 0.0562122 0.984145 + outer loop + vertex 0.978317 1.6672 2.63894 + vertex 0.98299 1.67228 2.63785 + vertex 0.978384 1.67229 2.63864 + endloop + endfacet + facet normal 0.178403 0.0465644 0.982855 + outer loop + vertex 0.982941 1.66716 2.6381 + vertex 0.98299 1.67228 2.63785 + vertex 0.978317 1.6672 2.63894 + endloop + endfacet + facet normal 0.178393 0.0582457 0.982234 + outer loop + vertex 0.978262 1.66221 2.63925 + vertex 0.982941 1.66716 2.6381 + vertex 0.978317 1.6672 2.63894 + endloop + endfacet + facet normal 0.188959 0.0479332 0.980814 + outer loop + vertex 0.982846 1.66206 2.63837 + vertex 0.982941 1.66716 2.6381 + vertex 0.978262 1.66221 2.63925 + endloop + endfacet + facet normal 0.18925 0.0619026 0.979976 + outer loop + vertex 0.97845 1.65749 2.63951 + vertex 0.982846 1.66206 2.63837 + vertex 0.978262 1.66221 2.63925 + endloop + endfacet + facet normal 0.203546 0.0476394 0.977906 + outer loop + vertex 0.982895 1.6571 2.6386 + vertex 0.982846 1.66206 2.63837 + vertex 0.97845 1.65749 2.63951 + endloop + endfacet + facet normal 0.204593 0.0620089 0.976881 + outer loop + vertex 0.978858 1.65301 2.63971 + vertex 0.982895 1.6571 2.6386 + vertex 0.97845 1.65749 2.63951 + endloop + endfacet + facet normal 0.217427 0.0488199 0.974855 + outer loop + vertex 0.983204 1.65242 2.63877 + vertex 0.982895 1.6571 2.6386 + vertex 0.978858 1.65301 2.63971 + endloop + endfacet + facet normal 0.219459 0.0663998 0.97336 + outer loop + vertex 0.979898 1.64921 2.63973 + vertex 0.983204 1.65242 2.63877 + vertex 0.978858 1.65301 2.63971 + endloop + endfacet + facet normal 0.238041 0.0463199 0.97015 + outer loop + vertex 0.983582 1.64798 2.63889 + vertex 0.983204 1.65242 2.63877 + vertex 0.979898 1.64921 2.63973 + endloop + endfacet + facet normal 0.239947 0.0525822 0.969361 + outer loop + vertex 0.979603 1.64446 2.64006 + vertex 0.983582 1.64798 2.63889 + vertex 0.979898 1.64921 2.63973 + endloop + endfacet + facet normal 0.248697 0.0421467 0.967664 + outer loop + vertex 0.984316 1.64416 2.63886 + vertex 0.983582 1.64798 2.63889 + vertex 0.979603 1.64446 2.64006 + endloop + endfacet + facet normal 0.249371 0.0565122 0.966758 + outer loop + vertex 0.979603 1.64446 2.64006 + vertex 0.98338 1.63966 2.63937 + vertex 0.984316 1.64416 2.63886 + endloop + endfacet + facet normal 0.264527 0.0691559 0.961895 + outer loop + vertex 0.979309 1.6398 2.64048 + vertex 0.98338 1.63966 2.63937 + vertex 0.979603 1.64446 2.64006 + endloop + endfacet + facet normal 0.264343 0.057299 0.962725 + outer loop + vertex 0.979309 1.6398 2.64048 + vertex 0.980341 1.6357 2.64044 + vertex 0.98338 1.63966 2.63937 + endloop + endfacet + facet normal 0.282092 0.0425171 0.958445 + outer loop + vertex 0.984343 1.63406 2.63933 + vertex 0.98338 1.63966 2.63937 + vertex 0.980341 1.6357 2.64044 + endloop + endfacet + facet normal 0.284811 0.0499036 0.957284 + outer loop + vertex 0.980957 1.63072 2.64051 + vertex 0.984343 1.63406 2.63933 + vertex 0.980341 1.6357 2.64044 + endloop + endfacet + facet normal 0.191567 0.0387293 0.980715 + outer loop + vertex 0.980341 1.6357 2.64044 + vertex 0.977058 1.63198 2.64123 + vertex 0.980957 1.63072 2.64051 + endloop + endfacet + facet normal 0.19345 0.044952 0.98008 + outer loop + vertex 0.977058 1.63198 2.64123 + vertex 0.977375 1.62694 2.6414 + vertex 0.980957 1.63072 2.64051 + endloop + endfacet + facet normal 0.202163 0.0363731 0.978676 + outer loop + vertex 0.980957 1.63072 2.64051 + vertex 0.977375 1.62694 2.6414 + vertex 0.981131 1.62575 2.64066 + endloop + endfacet + facet normal 0.294008 0.0388765 0.955012 + outer loop + vertex 0.981131 1.62575 2.64066 + vertex 0.984558 1.62897 2.63948 + vertex 0.980957 1.63072 2.64051 + endloop + endfacet + facet normal 0.299246 0.0327957 0.953612 + outer loop + vertex 0.984562 1.62418 2.63964 + vertex 0.984558 1.62897 2.63948 + vertex 0.981131 1.62575 2.64066 + endloop + endfacet + facet normal 0.299516 0.0334568 0.953505 + outer loop + vertex 0.981214 1.62077 2.64081 + vertex 0.984562 1.62418 2.63964 + vertex 0.981131 1.62575 2.64066 + endloop + endfacet + facet normal 0.209752 0.0326556 0.977209 + outer loop + vertex 0.981131 1.62575 2.64066 + vertex 0.977425 1.62192 2.64159 + vertex 0.981214 1.62077 2.64081 + endloop + endfacet + facet normal 0.210795 0.0363254 0.976855 + outer loop + vertex 0.977425 1.62192 2.64159 + vertex 0.977498 1.61688 2.64176 + vertex 0.981214 1.62077 2.64081 + endloop + endfacet + facet normal 0.21798 0.0291498 0.975518 + outer loop + vertex 0.981214 1.62077 2.64081 + vertex 0.977498 1.61688 2.64176 + vertex 0.981422 1.61573 2.64092 + endloop + endfacet + facet normal 0.307589 0.0323301 0.95097 + outer loop + vertex 0.981422 1.61573 2.64092 + vertex 0.984796 1.61933 2.6397 + vertex 0.981214 1.62077 2.64081 + endloop + endfacet + facet normal 0.31122 0.028574 0.949908 + outer loop + vertex 0.98513 1.61428 2.63975 + vertex 0.984796 1.61933 2.6397 + vertex 0.981422 1.61573 2.64092 + endloop + endfacet + facet normal 0.314136 0.0370785 0.948654 + outer loop + vertex 0.981846 1.61068 2.64097 + vertex 0.98513 1.61428 2.63975 + vertex 0.981422 1.61573 2.64092 + endloop + endfacet + facet normal 0.225989 0.0299501 0.973669 + outer loop + vertex 0.981422 1.61573 2.64092 + vertex 0.977755 1.61173 2.64189 + vertex 0.981846 1.61068 2.64097 + endloop + endfacet + facet normal 0.22761 0.0367817 0.973058 + outer loop + vertex 0.977755 1.61173 2.64189 + vertex 0.978306 1.60619 2.64197 + vertex 0.981846 1.61068 2.64097 + endloop + endfacet + facet normal 0.230538 0.0343421 0.972457 + outer loop + vertex 0.981846 1.61068 2.64097 + vertex 0.978306 1.60619 2.64197 + vertex 0.982404 1.60661 2.64099 + endloop + endfacet + facet normal 0.330064 0.047879 0.942743 + outer loop + vertex 0.982404 1.60661 2.64099 + vertex 0.985719 1.60895 2.63971 + vertex 0.981846 1.61068 2.64097 + endloop + endfacet + facet normal 0.33212 0.0446648 0.942179 + outer loop + vertex 0.984557 1.6046 2.64032 + vertex 0.985719 1.60895 2.63971 + vertex 0.982404 1.60661 2.64099 + endloop + endfacet + facet normal 0.30897 0.0169483 0.950921 + outer loop + vertex 0.982404 1.60661 2.64099 + vertex 0.981148 1.6021 2.64147 + vertex 0.984557 1.6046 2.64032 + endloop + endfacet + facet normal 0.229797 0.0413263 0.972361 + outer loop + vertex 0.982404 1.60661 2.64099 + vertex 0.978306 1.60619 2.64197 + vertex 0.981148 1.6021 2.64147 + endloop + endfacet + facet normal 0.215112 0.0306625 0.976108 + outer loop + vertex 0.978306 1.60619 2.64197 + vertex 0.977019 1.60129 2.64241 + vertex 0.981148 1.6021 2.64147 + endloop + endfacet + facet normal 0.214433 0.0341538 0.976141 + outer loop + vertex 0.977715 1.59736 2.64239 + vertex 0.981148 1.6021 2.64147 + vertex 0.977019 1.60129 2.64241 + endloop + endfacet + facet normal 0.230923 0.021554 0.972733 + outer loop + vertex 0.981751 1.59689 2.64145 + vertex 0.981148 1.6021 2.64147 + vertex 0.977715 1.59736 2.64239 + endloop + endfacet + facet normal 0.231584 0.0278604 0.972416 + outer loop + vertex 0.978005 1.59254 2.64246 + vertex 0.981751 1.59689 2.64145 + vertex 0.977715 1.59736 2.64239 + endloop + endfacet + facet normal 0.240725 0.0195119 0.970397 + outer loop + vertex 0.981977 1.59193 2.64149 + vertex 0.981751 1.59689 2.64145 + vertex 0.978005 1.59254 2.64246 + endloop + endfacet + facet normal 0.241368 0.024117 0.970134 + outer loop + vertex 0.978061 1.58757 2.64257 + vertex 0.981977 1.59193 2.64149 + vertex 0.978005 1.59254 2.64246 + endloop + endfacet + facet normal 0.244773 0.0208679 0.969356 + outer loop + vertex 0.982029 1.58697 2.64158 + vertex 0.981977 1.59193 2.64149 + vertex 0.978061 1.58757 2.64257 + endloop + endfacet + facet normal 0.24515 0.0236616 0.969196 + outer loop + vertex 0.978055 1.58258 2.6427 + vertex 0.982029 1.58697 2.64158 + vertex 0.978061 1.58757 2.64257 + endloop + endfacet + facet normal 0.250595 0.0184128 0.967917 + outer loop + vertex 0.982032 1.58199 2.64168 + vertex 0.982029 1.58697 2.64158 + vertex 0.978055 1.58258 2.6427 + endloop + endfacet + facet normal 0.250778 0.019773 0.967843 + outer loop + vertex 0.978058 1.57759 2.6428 + vertex 0.982032 1.58199 2.64168 + vertex 0.978055 1.58258 2.6427 + endloop + endfacet + facet normal 0.253421 0.0172221 0.967203 + outer loop + vertex 0.982069 1.57701 2.64176 + vertex 0.982032 1.58199 2.64168 + vertex 0.978058 1.57759 2.6428 + endloop + endfacet + facet normal 0.253736 0.0196073 0.967075 + outer loop + vertex 0.978104 1.57262 2.64289 + vertex 0.982069 1.57701 2.64176 + vertex 0.978058 1.57759 2.6428 + endloop + endfacet + facet normal 0.258572 0.0149225 0.965877 + outer loop + vertex 0.982125 1.57202 2.64182 + vertex 0.982069 1.57701 2.64176 + vertex 0.978104 1.57262 2.64289 + endloop + endfacet + facet normal 0.259019 0.0182095 0.965701 + outer loop + vertex 0.978153 1.56766 2.64297 + vertex 0.982125 1.57202 2.64182 + vertex 0.978104 1.57262 2.64289 + endloop + endfacet + facet normal 0.260559 0.016705 0.965313 + outer loop + vertex 0.982194 1.56706 2.64189 + vertex 0.982125 1.57202 2.64182 + vertex 0.978153 1.56766 2.64297 + endloop + endfacet + facet normal 0.260529 0.0164765 0.965326 + outer loop + vertex 0.978177 1.56266 2.64304 + vertex 0.982194 1.56706 2.64189 + vertex 0.978153 1.56766 2.64297 + endloop + endfacet + facet normal 0.260762 0.0162473 0.965266 + outer loop + vertex 0.98225 1.56208 2.64195 + vertex 0.982194 1.56706 2.64189 + vertex 0.978177 1.56266 2.64304 + endloop + endfacet + facet normal 0.260846 0.0168958 0.965232 + outer loop + vertex 0.978194 1.55765 2.64313 + vertex 0.98225 1.56208 2.64195 + vertex 0.978177 1.56266 2.64304 + endloop + endfacet + facet normal 0.260758 0.0169826 0.965255 + outer loop + vertex 0.982307 1.55709 2.64203 + vertex 0.98225 1.56208 2.64195 + vertex 0.978194 1.55765 2.64313 + endloop + endfacet + facet normal 0.260533 0.0151514 0.965346 + outer loop + vertex 0.978205 1.55261 2.6432 + vertex 0.982307 1.55709 2.64203 + vertex 0.978194 1.55765 2.64313 + endloop + endfacet + facet normal 0.260494 0.0151902 0.965356 + outer loop + vertex 0.98236 1.55209 2.64209 + vertex 0.982307 1.55709 2.64203 + vertex 0.978205 1.55261 2.6432 + endloop + endfacet + facet normal 0.260214 0.0127314 0.965467 + outer loop + vertex 0.978215 1.54756 2.64327 + vertex 0.98236 1.55209 2.64209 + vertex 0.978205 1.55261 2.6432 + endloop + endfacet + facet normal 0.260485 0.0124645 0.965397 + outer loop + vertex 0.982408 1.54708 2.64214 + vertex 0.98236 1.55209 2.64209 + vertex 0.978215 1.54756 2.64327 + endloop + endfacet + facet normal 0.260217 0.00992149 0.965499 + outer loop + vertex 0.978219 1.54252 2.64332 + vertex 0.982408 1.54708 2.64214 + vertex 0.978215 1.54756 2.64327 + endloop + endfacet + facet normal 0.261269 0.00888232 0.965225 + outer loop + vertex 0.982439 1.54206 2.64218 + vertex 0.982408 1.54708 2.64214 + vertex 0.978219 1.54252 2.64332 + endloop + endfacet + facet normal 0.261225 0.00844901 0.965241 + outer loop + vertex 0.978222 1.5375 2.64336 + vertex 0.982439 1.54206 2.64218 + vertex 0.978219 1.54252 2.64332 + endloop + endfacet + facet normal 0.261281 0.00839376 0.965226 + outer loop + vertex 0.982466 1.53706 2.64222 + vertex 0.982439 1.54206 2.64218 + vertex 0.978222 1.5375 2.64336 + endloop + endfacet + facet normal 0.261157 0.00708037 0.96527 + outer loop + vertex 0.978227 1.5325 2.6434 + vertex 0.982466 1.53706 2.64222 + vertex 0.978222 1.5375 2.64336 + endloop + endfacet + facet normal 0.2599 0.00833516 0.9656 + outer loop + vertex 0.982486 1.53208 2.64225 + vertex 0.982466 1.53706 2.64222 + vertex 0.978227 1.5325 2.6434 + endloop + endfacet + facet normal 0.259848 0.00775126 0.965618 + outer loop + vertex 0.978245 1.52754 2.64343 + vertex 0.982486 1.53208 2.64225 + vertex 0.978227 1.5325 2.6434 + endloop + endfacet + facet normal 0.259342 0.00825751 0.96575 + outer loop + vertex 0.982502 1.52711 2.64229 + vertex 0.982486 1.53208 2.64225 + vertex 0.978245 1.52754 2.64343 + endloop + endfacet + facet normal 0.259316 0.00797854 0.965759 + outer loop + vertex 0.978272 1.52259 2.64347 + vertex 0.982502 1.52711 2.64229 + vertex 0.978245 1.52754 2.64343 + endloop + endfacet + facet normal 0.258532 0.00876479 0.965963 + outer loop + vertex 0.982527 1.52215 2.64233 + vertex 0.982502 1.52711 2.64229 + vertex 0.978272 1.52259 2.64347 + endloop + endfacet + facet normal 0.258326 0.00658162 0.966035 + outer loop + vertex 0.978289 1.51764 2.64349 + vertex 0.982527 1.52215 2.64233 + vertex 0.978272 1.52259 2.64347 + endloop + endfacet + facet normal 0.257119 0.00779485 0.966348 + outer loop + vertex 0.982558 1.51718 2.64236 + vertex 0.982527 1.52215 2.64233 + vertex 0.978289 1.51764 2.64349 + endloop + endfacet + facet normal 0.257017 0.00674257 0.966383 + outer loop + vertex 0.978312 1.51267 2.64352 + vertex 0.982558 1.51718 2.64236 + vertex 0.978289 1.51764 2.64349 + endloop + endfacet + facet normal 0.258901 0.00484283 0.965892 + outer loop + vertex 0.982592 1.51218 2.64238 + vertex 0.982558 1.51718 2.64236 + vertex 0.978312 1.51267 2.64352 + endloop + endfacet + facet normal 0.25873 0.00324033 0.965944 + outer loop + vertex 0.978324 1.50766 2.64354 + vertex 0.982592 1.51218 2.64238 + vertex 0.978312 1.51267 2.64352 + endloop + endfacet + facet normal 0.259135 0.00283037 0.965837 + outer loop + vertex 0.982622 1.50714 2.64239 + vertex 0.982592 1.51218 2.64238 + vertex 0.978324 1.50766 2.64354 + endloop + endfacet + facet normal 0.259104 0.00254949 0.965846 + outer loop + vertex 0.978345 1.50264 2.64354 + vertex 0.982622 1.50714 2.64239 + vertex 0.978324 1.50766 2.64354 + endloop + endfacet + facet normal 0.262596 -0.00101145 0.964905 + outer loop + vertex 0.982617 1.50208 2.64238 + vertex 0.982622 1.50714 2.64239 + vertex 0.978345 1.50264 2.64354 + endloop + endfacet + facet normal 0.262457 -0.00214584 0.964941 + outer loop + vertex 0.978337 1.49761 2.64354 + vertex 0.982617 1.50208 2.64238 + vertex 0.978345 1.50264 2.64354 + endloop + endfacet + facet normal 0.262986 -0.00269083 0.964796 + outer loop + vertex 0.982597 1.49705 2.64237 + vertex 0.982617 1.50208 2.64238 + vertex 0.978337 1.49761 2.64354 + endloop + endfacet + facet normal 0.262856 -0.00375022 0.964828 + outer loop + vertex 0.978318 1.49261 2.64352 + vertex 0.982597 1.49705 2.64237 + vertex 0.978337 1.49761 2.64354 + endloop + endfacet + facet normal 0.262427 -0.00330641 0.964946 + outer loop + vertex 0.982565 1.49206 2.64236 + vertex 0.982597 1.49705 2.64237 + vertex 0.978318 1.49261 2.64352 + endloop + endfacet + facet normal 0.262285 -0.00446955 0.96498 + outer loop + vertex 0.978298 1.48765 2.6435 + vertex 0.982565 1.49206 2.64236 + vertex 0.978318 1.49261 2.64352 + endloop + endfacet + facet normal 0.261181 -0.00332237 0.965284 + outer loop + vertex 0.98253 1.48709 2.64236 + vertex 0.982565 1.49206 2.64236 + vertex 0.978298 1.48765 2.6435 + endloop + endfacet + facet normal 0.261017 -0.00464534 0.965323 + outer loop + vertex 0.97829 1.4827 2.64348 + vertex 0.98253 1.48709 2.64236 + vertex 0.978298 1.48765 2.6435 + endloop + endfacet + facet normal 0.25795 -0.00147443 0.966157 + outer loop + vertex 0.98252 1.48213 2.64235 + vertex 0.98253 1.48709 2.64236 + vertex 0.97829 1.4827 2.64348 + endloop + endfacet + facet normal 0.257662 -0.00377238 0.966228 + outer loop + vertex 0.978302 1.47773 2.64346 + vertex 0.98252 1.48213 2.64235 + vertex 0.97829 1.4827 2.64348 + endloop + endfacet + facet normal 0.255727 -0.00178576 0.966747 + outer loop + vertex 0.982531 1.47715 2.64234 + vertex 0.98252 1.48213 2.64235 + vertex 0.978302 1.47773 2.64346 + endloop + endfacet + facet normal 0.255356 -0.00467128 0.966836 + outer loop + vertex 0.978313 1.47275 2.64343 + vertex 0.982531 1.47715 2.64234 + vertex 0.978302 1.47773 2.64346 + endloop + endfacet + facet normal 0.252803 -0.00206033 0.967516 + outer loop + vertex 0.982552 1.47217 2.64232 + vertex 0.982531 1.47715 2.64234 + vertex 0.978313 1.47275 2.64343 + endloop + endfacet + facet normal 0.252309 -0.0059047 0.967629 + outer loop + vertex 0.978319 1.46775 2.6434 + vertex 0.982552 1.47217 2.64232 + vertex 0.978313 1.47275 2.64343 + endloop + endfacet + facet normal 0.251669 -0.00525088 0.967799 + outer loop + vertex 0.982551 1.46717 2.6423 + vertex 0.982552 1.47217 2.64232 + vertex 0.978319 1.46775 2.6434 + endloop + endfacet + facet normal 0.250966 -0.0106353 0.967938 + outer loop + vertex 0.978301 1.46274 2.64335 + vertex 0.982551 1.46717 2.6423 + vertex 0.978319 1.46775 2.6434 + endloop + endfacet + facet normal 0.250166 -0.00981691 0.968153 + outer loop + vertex 0.982522 1.46216 2.64225 + vertex 0.982551 1.46717 2.6423 + vertex 0.978301 1.46274 2.64335 + endloop + endfacet + facet normal 0.249721 -0.0131994 0.968228 + outer loop + vertex 0.978279 1.45774 2.64329 + vertex 0.982522 1.46216 2.64225 + vertex 0.978301 1.46274 2.64335 + endloop + endfacet + facet normal 0.247934 -0.0113722 0.96871 + outer loop + vertex 0.98249 1.45717 2.6422 + vertex 0.982522 1.46216 2.64225 + vertex 0.978279 1.45774 2.64329 + endloop + endfacet + facet normal 0.247426 -0.0152804 0.968786 + outer loop + vertex 0.978255 1.45274 2.64321 + vertex 0.98249 1.45717 2.6422 + vertex 0.978279 1.45774 2.64329 + endloop + endfacet + facet normal 0.24593 -0.013758 0.96919 + outer loop + vertex 0.982446 1.45217 2.64214 + vertex 0.98249 1.45717 2.6422 + vertex 0.978255 1.45274 2.64321 + endloop + endfacet + facet normal 0.245571 -0.0164955 0.969238 + outer loop + vertex 0.978231 1.44775 2.64314 + vertex 0.982446 1.45217 2.64214 + vertex 0.978255 1.45274 2.64321 + endloop + endfacet + facet normal 0.24232 -0.0132036 0.970106 + outer loop + vertex 0.982409 1.44718 2.64208 + vertex 0.982446 1.45217 2.64214 + vertex 0.978231 1.44775 2.64314 + endloop + endfacet + facet normal 0.24185 -0.0168066 0.970168 + outer loop + vertex 0.978212 1.44275 2.64305 + vertex 0.982409 1.44718 2.64208 + vertex 0.978231 1.44775 2.64314 + endloop + endfacet + facet normal 0.238704 -0.0136427 0.970996 + outer loop + vertex 0.982375 1.44219 2.64202 + vertex 0.982409 1.44718 2.64208 + vertex 0.978212 1.44275 2.64305 + endloop + endfacet + facet normal 0.238096 -0.0182745 0.97107 + outer loop + vertex 0.978196 1.43776 2.64296 + vertex 0.982375 1.44219 2.64202 + vertex 0.978212 1.44275 2.64305 + endloop + endfacet + facet normal 0.234933 -0.0151139 0.971894 + outer loop + vertex 0.982342 1.4372 2.64195 + vertex 0.982375 1.44219 2.64202 + vertex 0.978196 1.43776 2.64296 + endloop + endfacet + facet normal 0.234117 -0.0212816 0.971975 + outer loop + vertex 0.978178 1.43277 2.64286 + vertex 0.982342 1.4372 2.64195 + vertex 0.978196 1.43776 2.64296 + endloop + endfacet + facet normal 0.231874 -0.0190536 0.972559 + outer loop + vertex 0.982295 1.43221 2.64187 + vertex 0.982342 1.4372 2.64195 + vertex 0.978178 1.43277 2.64286 + endloop + endfacet + facet normal 0.231176 -0.0242222 0.97261 + outer loop + vertex 0.978153 1.42778 2.64274 + vertex 0.982295 1.43221 2.64187 + vertex 0.978178 1.43277 2.64286 + endloop + endfacet + facet normal 0.228259 -0.021341 0.973367 + outer loop + vertex 0.982237 1.42722 2.64177 + vertex 0.982295 1.43221 2.64187 + vertex 0.978153 1.42778 2.64274 + endloop + endfacet + facet normal 0.227431 -0.0273979 0.973409 + outer loop + vertex 0.978117 1.42279 2.64261 + vertex 0.982237 1.42722 2.64177 + vertex 0.978153 1.42778 2.64274 + endloop + endfacet + facet normal 0.326003 -0.0100523 0.945315 + outer loop + vertex 0.982551 1.46717 2.6423 + vertex 0.982522 1.46216 2.64225 + vertex 0.986333 1.46604 2.64098 + endloop + endfacet + facet normal 0.327137 -0.00584646 0.944959 + outer loop + vertex 0.98634 1.47103 2.64101 + vertex 0.982551 1.46717 2.6423 + vertex 0.986333 1.46604 2.64098 + endloop + endfacet + facet normal 0.377053 -0.00581241 0.926173 + outer loop + vertex 0.986333 1.46604 2.64098 + vertex 0.98986 1.46948 2.63957 + vertex 0.98634 1.47103 2.64101 + endloop + endfacet + facet normal 0.378042 -0.00320264 0.925783 + outer loop + vertex 0.98986 1.46948 2.63957 + vertex 0.989842 1.47446 2.63959 + vertex 0.98634 1.47103 2.64101 + endloop + endfacet + facet normal 0.377222 -0.00222702 0.92612 + outer loop + vertex 0.98634 1.47103 2.64101 + vertex 0.989842 1.47446 2.63959 + vertex 0.986321 1.47602 2.64103 + endloop + endfacet + facet normal 0.327207 -0.00249354 0.944949 + outer loop + vertex 0.986321 1.47602 2.64103 + vertex 0.982552 1.47217 2.64232 + vertex 0.98634 1.47103 2.64101 + endloop + endfacet + facet normal 0.378518 0.00118976 0.925593 + outer loop + vertex 0.989842 1.47446 2.63959 + vertex 0.989804 1.47943 2.6396 + vertex 0.986321 1.47602 2.64103 + endloop + endfacet + facet normal 0.378339 0.00140261 0.925666 + outer loop + vertex 0.986321 1.47602 2.64103 + vertex 0.989804 1.47943 2.6396 + vertex 0.986292 1.48099 2.64103 + endloop + endfacet + facet normal 0.327211 0.00108144 0.944951 + outer loop + vertex 0.986292 1.48099 2.64103 + vertex 0.982531 1.47715 2.64234 + vertex 0.986321 1.47602 2.64103 + endloop + endfacet + facet normal 0.378739 0.00245815 0.9255 + outer loop + vertex 0.989804 1.47943 2.6396 + vertex 0.989823 1.48443 2.63958 + vertex 0.986292 1.48099 2.64103 + endloop + endfacet + facet normal 0.379915 0.00104992 0.925021 + outer loop + vertex 0.986292 1.48099 2.64103 + vertex 0.989823 1.48443 2.63958 + vertex 0.986307 1.48597 2.64102 + endloop + endfacet + facet normal 0.330378 0.00124671 0.943848 + outer loop + vertex 0.986307 1.48597 2.64102 + vertex 0.98252 1.48213 2.64235 + vertex 0.986292 1.48099 2.64103 + endloop + endfacet + facet normal 0.332941 -0.00159609 0.942946 + outer loop + vertex 0.98253 1.48709 2.64236 + vertex 0.98252 1.48213 2.64235 + vertex 0.986307 1.48597 2.64102 + endloop + endfacet + facet normal 0.333214 -0.000566127 0.942851 + outer loop + vertex 0.986353 1.49097 2.64101 + vertex 0.98253 1.48709 2.64236 + vertex 0.986307 1.48597 2.64102 + endloop + endfacet + facet normal 0.381609 -0.00105616 0.924323 + outer loop + vertex 0.986307 1.48597 2.64102 + vertex 0.98996 1.48954 2.63952 + vertex 0.986353 1.49097 2.64101 + endloop + endfacet + facet normal 0.381581 -0.00113944 0.924335 + outer loop + vertex 0.98996 1.48954 2.63952 + vertex 0.989993 1.49467 2.63951 + vertex 0.986353 1.49097 2.64101 + endloop + endfacet + facet normal 0.383479 -0.00332766 0.923544 + outer loop + vertex 0.986353 1.49097 2.64101 + vertex 0.989993 1.49467 2.63951 + vertex 0.986373 1.49597 2.64102 + endloop + endfacet + facet normal 0.336322 -0.00316357 0.941742 + outer loop + vertex 0.986373 1.49597 2.64102 + vertex 0.982565 1.49206 2.64236 + vertex 0.986353 1.49097 2.64101 + endloop + endfacet + facet normal 0.38363 -0.00283616 0.923483 + outer loop + vertex 0.989993 1.49467 2.63951 + vertex 0.989863 1.49965 2.63958 + vertex 0.986373 1.49597 2.64102 + endloop + endfacet + facet normal 0.383926 -0.00316542 0.923358 + outer loop + vertex 0.986373 1.49597 2.64102 + vertex 0.989863 1.49965 2.63958 + vertex 0.986363 1.50095 2.64104 + endloop + endfacet + facet normal 0.336939 -0.00334241 0.94152 + outer loop + vertex 0.986363 1.50095 2.64104 + vertex 0.982597 1.49705 2.64237 + vertex 0.986373 1.49597 2.64102 + endloop + endfacet + facet normal 0.38403 -0.00283932 0.923316 + outer loop + vertex 0.989863 1.49965 2.63958 + vertex 0.989758 1.50448 2.63964 + vertex 0.986363 1.50095 2.64104 + endloop + endfacet + facet normal 0.38322 -0.0019243 0.923655 + outer loop + vertex 0.986363 1.50095 2.64104 + vertex 0.989758 1.50448 2.63964 + vertex 0.986378 1.50596 2.64104 + endloop + endfacet + facet normal 0.336879 -0.00179648 0.941546 + outer loop + vertex 0.986378 1.50596 2.64104 + vertex 0.982617 1.50208 2.64238 + vertex 0.986363 1.50095 2.64104 + endloop + endfacet + facet normal 0.384116 0.000466971 0.923285 + outer loop + vertex 0.989758 1.50448 2.63964 + vertex 0.989924 1.50933 2.63957 + vertex 0.986378 1.50596 2.64104 + endloop + endfacet + facet normal 0.383802 0.000853923 0.923415 + outer loop + vertex 0.986378 1.50596 2.64104 + vertex 0.989924 1.50933 2.63957 + vertex 0.986387 1.51099 2.64103 + endloop + endfacet + facet normal 0.336785 0.000967027 0.941581 + outer loop + vertex 0.986387 1.51099 2.64103 + vertex 0.982622 1.50714 2.64239 + vertex 0.986378 1.50596 2.64104 + endloop + endfacet + facet normal 0.384316 0.00213775 0.923199 + outer loop + vertex 0.989924 1.50933 2.63957 + vertex 0.989952 1.51428 2.63954 + vertex 0.986387 1.51099 2.64103 + endloop + endfacet + facet normal 0.383006 0.00380416 0.923738 + outer loop + vertex 0.986387 1.51099 2.64103 + vertex 0.989952 1.51428 2.63954 + vertex 0.986341 1.51601 2.64103 + endloop + endfacet + facet normal 0.334744 0.00336972 0.942303 + outer loop + vertex 0.986341 1.51601 2.64103 + vertex 0.982592 1.51218 2.64238 + vertex 0.986387 1.51099 2.64103 + endloop + endfacet + facet normal 0.38309 0.00401079 0.923702 + outer loop + vertex 0.989952 1.51428 2.63954 + vertex 0.989858 1.5192 2.63956 + vertex 0.986341 1.51601 2.64103 + endloop + endfacet + facet normal 0.381412 0.00617235 0.924385 + outer loop + vertex 0.986341 1.51601 2.64103 + vertex 0.989858 1.5192 2.63956 + vertex 0.986299 1.52101 2.64102 + endloop + endfacet + facet normal 0.333168 0.00582384 0.942849 + outer loop + vertex 0.986299 1.52101 2.64102 + vertex 0.982558 1.51718 2.64236 + vertex 0.986341 1.51601 2.64103 + endloop + endfacet + facet normal 0.381691 0.00681689 0.924265 + outer loop + vertex 0.989858 1.5192 2.63956 + vertex 0.989862 1.52428 2.63952 + vertex 0.986299 1.52101 2.64102 + endloop + endfacet + facet normal 0.380224 0.00868384 0.924854 + outer loop + vertex 0.986299 1.52101 2.64102 + vertex 0.989862 1.52428 2.63952 + vertex 0.986268 1.52602 2.64098 + endloop + endfacet + facet normal 0.331185 0.00850855 0.943528 + outer loop + vertex 0.986268 1.52602 2.64098 + vertex 0.982527 1.52215 2.64233 + vertex 0.986299 1.52101 2.64102 + endloop + endfacet + facet normal 0.38008 0.00833541 0.924916 + outer loop + vertex 0.989862 1.52428 2.63952 + vertex 0.989739 1.52942 2.63953 + vertex 0.986268 1.52602 2.64098 + endloop + endfacet + facet normal 0.378882 0.00976324 0.925394 + outer loop + vertex 0.986268 1.52602 2.64098 + vertex 0.989739 1.52942 2.63953 + vertex 0.986238 1.53102 2.64094 + endloop + endfacet + facet normal 0.330946 0.00961798 0.943601 + outer loop + vertex 0.986238 1.53102 2.64094 + vertex 0.982502 1.52711 2.64229 + vertex 0.986268 1.52602 2.64098 + endloop + endfacet + facet normal 0.37932 0.0108902 0.925202 + outer loop + vertex 0.989739 1.52942 2.63953 + vertex 0.989698 1.53445 2.63948 + vertex 0.986238 1.53102 2.64094 + endloop + endfacet + facet normal 0.380254 0.00978766 0.92483 + outer loop + vertex 0.986238 1.53102 2.64094 + vertex 0.989698 1.53445 2.63948 + vertex 0.986223 1.536 2.6409 + endloop + endfacet + facet normal 0.332541 0.00981375 0.943038 + outer loop + vertex 0.986223 1.536 2.6409 + vertex 0.982486 1.53208 2.64225 + vertex 0.986238 1.53102 2.64094 + endloop + endfacet + facet normal 0.380497 0.0104279 0.924723 + outer loop + vertex 0.989698 1.53445 2.63948 + vertex 0.989691 1.53943 2.63943 + vertex 0.986223 1.536 2.6409 + endloop + endfacet + facet normal 0.381451 0.00929978 0.924342 + outer loop + vertex 0.986223 1.536 2.6409 + vertex 0.989691 1.53943 2.63943 + vertex 0.9862 1.54098 2.64085 + endloop + endfacet + facet normal 0.333986 0.00923391 0.942533 + outer loop + vertex 0.9862 1.54098 2.64085 + vertex 0.982466 1.53706 2.64222 + vertex 0.986223 1.536 2.6409 + endloop + endfacet + facet normal 0.334548 0.00863183 0.942339 + outer loop + vertex 0.982439 1.54206 2.64218 + vertex 0.982466 1.53706 2.64222 + vertex 0.9862 1.54098 2.64085 + endloop + endfacet + facet normal 0.334928 0.0101444 0.942189 + outer loop + vertex 0.986154 1.54596 2.64082 + vertex 0.982439 1.54206 2.64218 + vertex 0.9862 1.54098 2.64085 + endloop + endfacet + facet normal 0.3828 0.0104523 0.923772 + outer loop + vertex 0.9862 1.54098 2.64085 + vertex 0.98966 1.54439 2.63938 + vertex 0.986154 1.54596 2.64082 + endloop + endfacet + facet normal 0.383157 0.0113936 0.923613 + outer loop + vertex 0.98966 1.54439 2.63938 + vertex 0.989605 1.54938 2.63934 + vertex 0.986154 1.54596 2.64082 + endloop + endfacet + facet normal 0.382602 0.0120498 0.923835 + outer loop + vertex 0.986154 1.54596 2.64082 + vertex 0.989605 1.54938 2.63934 + vertex 0.986093 1.55096 2.64078 + endloop + endfacet + facet normal 0.336489 0.0116325 0.941615 + outer loop + vertex 0.986093 1.55096 2.64078 + vertex 0.982408 1.54708 2.64214 + vertex 0.986154 1.54596 2.64082 + endloop + endfacet + facet normal 0.383531 0.0144966 0.923414 + outer loop + vertex 0.989605 1.54938 2.63934 + vertex 0.989528 1.55437 2.6393 + vertex 0.986093 1.55096 2.64078 + endloop + endfacet + facet normal 0.382667 0.015515 0.923756 + outer loop + vertex 0.986093 1.55096 2.64078 + vertex 0.989528 1.55437 2.6393 + vertex 0.98602 1.55595 2.64072 + endloop + endfacet + facet normal 0.335813 0.0150188 0.941809 + outer loop + vertex 0.98602 1.55595 2.64072 + vertex 0.98236 1.55209 2.64209 + vertex 0.986093 1.55096 2.64078 + endloop + endfacet + facet normal 0.383475 0.0176431 0.923383 + outer loop + vertex 0.989528 1.55437 2.6393 + vertex 0.989442 1.55935 2.63924 + vertex 0.98602 1.55595 2.64072 + endloop + endfacet + facet normal 0.383486 0.0176291 0.923378 + outer loop + vertex 0.98602 1.55595 2.64072 + vertex 0.989442 1.55935 2.63924 + vertex 0.985943 1.56093 2.64066 + endloop + endfacet + facet normal 0.335576 0.0171301 0.941857 + outer loop + vertex 0.985943 1.56093 2.64066 + vertex 0.982307 1.55709 2.64203 + vertex 0.98602 1.55595 2.64072 + endloop + endfacet + facet normal 0.383812 0.0184851 0.923226 + outer loop + vertex 0.989442 1.55935 2.63924 + vertex 0.989356 1.56433 2.63917 + vertex 0.985943 1.56093 2.64066 + endloop + endfacet + facet normal 0.383632 0.0186966 0.923297 + outer loop + vertex 0.985943 1.56093 2.64066 + vertex 0.989356 1.56433 2.63917 + vertex 0.985863 1.5659 2.64059 + endloop + endfacet + facet normal 0.335422 0.0181682 0.941893 + outer loop + vertex 0.985863 1.5659 2.64059 + vertex 0.98225 1.56208 2.64195 + vertex 0.985943 1.56093 2.64066 + endloop + endfacet + facet normal 0.383128 0.0173643 0.923532 + outer loop + vertex 0.989356 1.56433 2.63917 + vertex 0.989273 1.56932 2.63911 + vertex 0.985863 1.5659 2.64059 + endloop + endfacet + facet normal 0.383593 0.0168204 0.923349 + outer loop + vertex 0.985863 1.5659 2.64059 + vertex 0.989273 1.56932 2.63911 + vertex 0.985787 1.57088 2.64053 + endloop + endfacet + facet normal 0.336606 0.0163137 0.941504 + outer loop + vertex 0.985787 1.57088 2.64053 + vertex 0.982194 1.56706 2.64189 + vertex 0.985863 1.5659 2.64059 + endloop + endfacet + facet normal 0.383473 0.0165009 0.923405 + outer loop + vertex 0.989273 1.56932 2.63911 + vertex 0.98919 1.5743 2.63906 + vertex 0.985787 1.57088 2.64053 + endloop + endfacet + facet normal 0.384232 0.0156163 0.923104 + outer loop + vertex 0.985787 1.57088 2.64053 + vertex 0.98919 1.5743 2.63906 + vertex 0.985713 1.57587 2.64048 + endloop + endfacet + facet normal 0.334916 0.0150903 0.942127 + outer loop + vertex 0.985713 1.57587 2.64048 + vertex 0.982125 1.57202 2.64182 + vertex 0.985787 1.57088 2.64053 + endloop + endfacet + facet normal 0.384554 0.016466 0.922956 + outer loop + vertex 0.98919 1.5743 2.63906 + vertex 0.989111 1.5793 2.639 + vertex 0.985713 1.57587 2.64048 + endloop + endfacet + facet normal 0.384639 0.0163674 0.922922 + outer loop + vertex 0.985713 1.57587 2.64048 + vertex 0.989111 1.5793 2.639 + vertex 0.98565 1.58086 2.64042 + endloop + endfacet + facet normal 0.334676 0.0159822 0.942198 + outer loop + vertex 0.98565 1.58086 2.64042 + vertex 0.982069 1.57701 2.64176 + vertex 0.985713 1.57587 2.64048 + endloop + endfacet + facet normal 0.38502 0.0173736 0.922744 + outer loop + vertex 0.989111 1.5793 2.639 + vertex 0.989044 1.5843 2.63894 + vertex 0.98565 1.58086 2.64042 + endloop + endfacet + facet normal 0.385343 0.0170007 0.922617 + outer loop + vertex 0.98565 1.58086 2.64042 + vertex 0.989044 1.5843 2.63894 + vertex 0.985614 1.58585 2.64034 + endloop + endfacet + facet normal 0.333168 0.016931 0.942715 + outer loop + vertex 0.985614 1.58585 2.64034 + vertex 0.982032 1.58199 2.64168 + vertex 0.98565 1.58086 2.64042 + endloop + endfacet + facet normal 0.386226 0.0193354 0.922201 + outer loop + vertex 0.989044 1.5843 2.63894 + vertex 0.988984 1.58927 2.63886 + vertex 0.985614 1.58585 2.64034 + endloop + endfacet + facet normal 0.387027 0.0184085 0.921885 + outer loop + vertex 0.985614 1.58585 2.64034 + vertex 0.988984 1.58927 2.63886 + vertex 0.985571 1.5908 2.64026 + endloop + endfacet + facet normal 0.332218 0.0182767 0.943026 + outer loop + vertex 0.985571 1.5908 2.64026 + vertex 0.982029 1.58697 2.64158 + vertex 0.985614 1.58585 2.64034 + endloop + endfacet + facet normal 0.329325 0.0212803 0.943977 + outer loop + vertex 0.981977 1.59193 2.64149 + vertex 0.982029 1.58697 2.64158 + vertex 0.985571 1.5908 2.64026 + endloop + endfacet + facet normal 0.32889 0.0196844 0.944163 + outer loop + vertex 0.985416 1.59571 2.64021 + vertex 0.981977 1.59193 2.64149 + vertex 0.985571 1.5908 2.64026 + endloop + endfacet + facet normal 0.386862 0.021294 0.921892 + outer loop + vertex 0.985571 1.5908 2.64026 + vertex 0.988877 1.59419 2.6388 + vertex 0.985416 1.59571 2.64021 + endloop + endfacet + facet normal 0.387195 0.0222025 0.921731 + outer loop + vertex 0.988877 1.59419 2.6388 + vertex 0.988633 1.59914 2.63878 + vertex 0.985416 1.59571 2.64021 + endloop + endfacet + facet normal 0.383669 0.0260844 0.923102 + outer loop + vertex 0.985416 1.59571 2.64021 + vertex 0.988633 1.59914 2.63878 + vertex 0.985039 1.60058 2.64023 + endloop + endfacet + facet normal 0.325026 0.0214563 0.945462 + outer loop + vertex 0.985039 1.60058 2.64023 + vertex 0.981751 1.59689 2.64145 + vertex 0.985416 1.59571 2.64021 + endloop + endfacet + facet normal 0.38294 0.0238896 0.923464 + outer loop + vertex 0.988633 1.59914 2.63878 + vertex 0.98817 1.60452 2.63883 + vertex 0.985039 1.60058 2.64023 + endloop + endfacet + facet normal 0.38155 0.0251843 0.924005 + outer loop + vertex 0.984557 1.6046 2.64032 + vertex 0.985039 1.60058 2.64023 + vertex 0.98817 1.60452 2.63883 + endloop + endfacet + facet normal 0.381579 0.0288679 0.923885 + outer loop + vertex 0.984557 1.6046 2.64032 + vertex 0.98817 1.60452 2.63883 + vertex 0.985719 1.60895 2.63971 + endloop + endfacet + facet normal 0.385963 0.0316717 0.921971 + outer loop + vertex 0.985719 1.60895 2.63971 + vertex 0.98817 1.60452 2.63883 + vertex 0.989294 1.60905 2.63821 + endloop + endfacet + facet normal 0.386113 0.0274547 0.922043 + outer loop + vertex 0.989294 1.60905 2.63821 + vertex 0.988708 1.61307 2.63833 + vertex 0.985719 1.60895 2.63971 + endloop + endfacet + facet normal 0.377535 0.0347847 0.925342 + outer loop + vertex 0.985719 1.60895 2.63971 + vertex 0.988708 1.61307 2.63833 + vertex 0.98513 1.61428 2.63975 + endloop + endfacet + facet normal 0.375842 0.0287449 0.926238 + outer loop + vertex 0.988708 1.61307 2.63833 + vertex 0.98835 1.61795 2.63832 + vertex 0.98513 1.61428 2.63975 + endloop + endfacet + facet normal 0.372242 0.032423 0.927569 + outer loop + vertex 0.98513 1.61428 2.63975 + vertex 0.98835 1.61795 2.63832 + vertex 0.984796 1.61933 2.6397 + endloop + endfacet + facet normal 0.370568 0.0272855 0.928404 + outer loop + vertex 0.98835 1.61795 2.63832 + vertex 0.987985 1.62285 2.63833 + vertex 0.984796 1.61933 2.6397 + endloop + endfacet + facet normal 0.368374 0.0295874 0.929207 + outer loop + vertex 0.984796 1.61933 2.6397 + vertex 0.987985 1.62285 2.63833 + vertex 0.984562 1.62418 2.63964 + endloop + endfacet + facet normal 0.366675 0.0244051 0.930029 + outer loop + vertex 0.987985 1.62285 2.63833 + vertex 0.987376 1.62695 2.63846 + vertex 0.984562 1.62418 2.63964 + endloop + endfacet + facet normal 0.360049 0.0321251 0.93238 + outer loop + vertex 0.984562 1.62418 2.63964 + vertex 0.987376 1.62695 2.63846 + vertex 0.984558 1.62897 2.63948 + endloop + endfacet + facet normal 0.364939 0.040063 0.930169 + outer loop + vertex 0.987376 1.62695 2.63846 + vertex 0.988501 1.63162 2.63782 + vertex 0.984558 1.62897 2.63948 + endloop + endfacet + facet normal 0.363966 0.0417096 0.930478 + outer loop + vertex 0.984558 1.62897 2.63948 + vertex 0.988501 1.63162 2.63782 + vertex 0.984343 1.63406 2.63933 + endloop + endfacet + facet normal 0.358827 0.0314599 0.932874 + outer loop + vertex 0.988501 1.63162 2.63782 + vertex 0.987846 1.63729 2.63788 + vertex 0.984343 1.63406 2.63933 + endloop + endfacet + facet normal 0.341411 0.0528336 0.938428 + outer loop + vertex 0.984343 1.63406 2.63933 + vertex 0.987846 1.63729 2.63788 + vertex 0.98338 1.63966 2.63937 + endloop + endfacet + facet normal 0.332674 0.0338667 0.942434 + outer loop + vertex 0.987846 1.63729 2.63788 + vertex 0.987597 1.64232 2.63778 + vertex 0.98338 1.63966 2.63937 + endloop + endfacet + facet normal 0.330979 0.0368467 0.942919 + outer loop + vertex 0.98338 1.63966 2.63937 + vertex 0.987597 1.64232 2.63778 + vertex 0.984316 1.64416 2.63886 + endloop + endfacet + facet normal 0.331341 0.0375846 0.942762 + outer loop + vertex 0.987597 1.64232 2.63778 + vertex 0.9875 1.64695 2.63763 + vertex 0.984316 1.64416 2.63886 + endloop + endfacet + facet normal 0.317218 0.055426 0.946732 + outer loop + vertex 0.984316 1.64416 2.63886 + vertex 0.9875 1.64695 2.63763 + vertex 0.983582 1.64798 2.63889 + endloop + endfacet + facet normal 0.313441 0.0385276 0.948826 + outer loop + vertex 0.9875 1.64695 2.63763 + vertex 0.987256 1.65161 2.63753 + vertex 0.983582 1.64798 2.63889 + endloop + endfacet + facet normal 0.302005 0.0512801 0.951926 + outer loop + vertex 0.983582 1.64798 2.63889 + vertex 0.987256 1.65161 2.63753 + vertex 0.983204 1.65242 2.63877 + endloop + endfacet + facet normal 0.299903 0.0389374 0.953175 + outer loop + vertex 0.987256 1.65161 2.63753 + vertex 0.9871 1.65652 2.63737 + vertex 0.983204 1.65242 2.63877 + endloop + endfacet + facet normal 0.286622 0.0527425 0.956591 + outer loop + vertex 0.983204 1.65242 2.63877 + vertex 0.9871 1.65652 2.63737 + vertex 0.982895 1.6571 2.6386 + endloop + endfacet + facet normal 0.284961 0.0383822 0.95777 + outer loop + vertex 0.9871 1.65652 2.63737 + vertex 0.987056 1.66159 2.63718 + vertex 0.982895 1.6571 2.6386 + endloop + endfacet + facet normal 0.275888 0.0475129 0.960015 + outer loop + vertex 0.982895 1.6571 2.6386 + vertex 0.987056 1.66159 2.63718 + vertex 0.982846 1.66206 2.63837 + endloop + endfacet + facet normal 0.274951 0.0374557 0.960728 + outer loop + vertex 0.987056 1.66159 2.63718 + vertex 0.987101 1.66672 2.63697 + vertex 0.982846 1.66206 2.63837 + endloop + endfacet + facet normal 0.266761 0.0455346 0.962686 + outer loop + vertex 0.982846 1.66206 2.63837 + vertex 0.987101 1.66672 2.63697 + vertex 0.982941 1.66716 2.6381 + endloop + endfacet + facet normal 0.265946 0.0364082 0.9633 + outer loop + vertex 0.987101 1.66672 2.63697 + vertex 0.987117 1.67182 2.63677 + vertex 0.982941 1.66716 2.6381 + endloop + endfacet + facet normal 0.257076 0.044949 0.965345 + outer loop + vertex 0.982941 1.66716 2.6381 + vertex 0.987117 1.67182 2.63677 + vertex 0.98299 1.67228 2.63785 + endloop + endfacet + facet normal 0.256569 0.0395342 0.965717 + outer loop + vertex 0.987117 1.67182 2.63677 + vertex 0.986897 1.67686 2.63663 + vertex 0.98299 1.67228 2.63785 + endloop + endfacet + facet normal 0.247154 0.0481221 0.96778 + outer loop + vertex 0.98299 1.67228 2.63785 + vertex 0.986897 1.67686 2.63663 + vertex 0.982777 1.67724 2.63766 + endloop + endfacet + facet normal 0.246861 0.0442348 0.968041 + outer loop + vertex 0.986897 1.67686 2.63663 + vertex 0.986253 1.68213 2.63655 + vertex 0.982777 1.67724 2.63766 + endloop + endfacet + facet normal 0.228617 0.058055 0.971784 + outer loop + vertex 0.982777 1.67724 2.63766 + vertex 0.986253 1.68213 2.63655 + vertex 0.982101 1.68125 2.63758 + endloop + endfacet + facet normal 0.228805 0.0571694 0.971792 + outer loop + vertex 0.983352 1.68623 2.63699 + vertex 0.982101 1.68125 2.63758 + vertex 0.986253 1.68213 2.63655 + endloop + endfacet + facet normal 0.23949 0.0650551 0.968717 + outer loop + vertex 0.987429 1.68666 2.63595 + vertex 0.983352 1.68623 2.63699 + vertex 0.986253 1.68213 2.63655 + endloop + endfacet + facet normal 0.320842 0.0410237 0.946244 + outer loop + vertex 0.987429 1.68666 2.63595 + vertex 0.986253 1.68213 2.63655 + vertex 0.989629 1.68463 2.6353 + endloop + endfacet + facet normal 0.342719 0.067712 0.936995 + outer loop + vertex 0.989629 1.68463 2.6353 + vertex 0.990621 1.68893 2.63462 + vertex 0.987429 1.68666 2.63595 + endloop + endfacet + facet normal 0.338723 0.0739198 0.937978 + outer loop + vertex 0.987429 1.68666 2.63595 + vertex 0.990621 1.68893 2.63462 + vertex 0.986742 1.6907 2.63588 + endloop + endfacet + facet normal 0.328234 0.0470092 0.943426 + outer loop + vertex 0.990621 1.68893 2.63462 + vertex 0.989754 1.69405 2.63467 + vertex 0.986742 1.6907 2.63588 + endloop + endfacet + facet normal 0.31311 0.0621415 0.947682 + outer loop + vertex 0.986742 1.6907 2.63588 + vertex 0.989754 1.69405 2.63467 + vertex 0.98617 1.69562 2.63575 + endloop + endfacet + facet normal 0.228861 0.0530181 0.972014 + outer loop + vertex 0.98617 1.69562 2.63575 + vertex 0.982716 1.69178 2.63677 + vertex 0.986742 1.6907 2.63588 + endloop + endfacet + facet normal 0.231688 0.0646655 0.970638 + outer loop + vertex 0.982716 1.69178 2.63677 + vertex 0.983352 1.68623 2.63699 + vertex 0.986742 1.6907 2.63588 + endloop + endfacet + facet normal 0.215704 0.065435 0.974264 + outer loop + vertex 0.982311 1.6968 2.63653 + vertex 0.982716 1.69178 2.63677 + vertex 0.98617 1.69562 2.63575 + endloop + endfacet + facet normal 0.213389 0.0572027 0.975291 + outer loop + vertex 0.985728 1.70046 2.63556 + vertex 0.982311 1.6968 2.63653 + vertex 0.98617 1.69562 2.63575 + endloop + endfacet + facet normal 0.299498 0.0641488 0.951938 + outer loop + vertex 0.98617 1.69562 2.63575 + vertex 0.989396 1.69884 2.63452 + vertex 0.985728 1.70046 2.63556 + endloop + endfacet + facet normal 0.297394 0.0587637 0.952945 + outer loop + vertex 0.989396 1.69884 2.63452 + vertex 0.989058 1.70378 2.63432 + vertex 0.985728 1.70046 2.63556 + endloop + endfacet + facet normal 0.281182 0.0764325 0.956606 + outer loop + vertex 0.985728 1.70046 2.63556 + vertex 0.989058 1.70378 2.63432 + vertex 0.98505 1.70504 2.6354 + endloop + endfacet + facet normal 0.194987 0.0644455 0.978686 + outer loop + vertex 0.98505 1.70504 2.6354 + vertex 0.981839 1.70154 2.63627 + vertex 0.985728 1.70046 2.63556 + endloop + endfacet + facet normal 0.197162 0.0729734 0.977651 + outer loop + vertex 0.981839 1.70154 2.63627 + vertex 0.982311 1.6968 2.63653 + vertex 0.985728 1.70046 2.63556 + endloop + endfacet + facet normal 0.309613 0.0530109 0.949384 + outer loop + vertex 0.989754 1.69405 2.63467 + vertex 0.989396 1.69884 2.63452 + vertex 0.98617 1.69562 2.63575 + endloop + endfacet + facet normal 0.240337 0.0576869 0.968974 + outer loop + vertex 0.986742 1.6907 2.63588 + vertex 0.983352 1.68623 2.63699 + vertex 0.987429 1.68666 2.63595 + endloop + endfacet + facet normal 0.34602 0.0358653 0.937541 + outer loop + vertex 0.987101 1.66672 2.63697 + vertex 0.987056 1.66159 2.63718 + vertex 0.99086 1.66572 2.63562 + endloop + endfacet + facet normal 0.345607 0.0340025 0.937763 + outer loop + vertex 0.990795 1.67075 2.63546 + vertex 0.987101 1.66672 2.63697 + vertex 0.99086 1.66572 2.63562 + endloop + endfacet + facet normal 0.401693 0.0340049 0.915143 + outer loop + vertex 0.99086 1.66572 2.63562 + vertex 0.994225 1.66922 2.63401 + vertex 0.990795 1.67075 2.63546 + endloop + endfacet + facet normal 0.40278 0.0369888 0.914549 + outer loop + vertex 0.994225 1.66922 2.63401 + vertex 0.994056 1.67415 2.63389 + vertex 0.990795 1.67075 2.63546 + endloop + endfacet + facet normal 0.401165 0.0388341 0.915182 + outer loop + vertex 0.990795 1.67075 2.63546 + vertex 0.994056 1.67415 2.63389 + vertex 0.990605 1.6757 2.63534 + endloop + endfacet + facet normal 0.344975 0.0372471 0.937873 + outer loop + vertex 0.990605 1.6757 2.63534 + vertex 0.987117 1.67182 2.63677 + vertex 0.990795 1.67075 2.63546 + endloop + endfacet + facet normal 0.339891 0.0424171 0.939508 + outer loop + vertex 0.986897 1.67686 2.63663 + vertex 0.987117 1.67182 2.63677 + vertex 0.990605 1.6757 2.63534 + endloop + endfacet + facet normal 0.339797 0.0420588 0.939558 + outer loop + vertex 0.99018 1.68059 2.63527 + vertex 0.986897 1.67686 2.63663 + vertex 0.990605 1.6757 2.63534 + endloop + endfacet + facet normal 0.397551 0.0467715 0.916387 + outer loop + vertex 0.990605 1.6757 2.63534 + vertex 0.993771 1.67911 2.63379 + vertex 0.99018 1.68059 2.63527 + endloop + endfacet + facet normal 0.397377 0.0462452 0.91649 + outer loop + vertex 0.993771 1.67911 2.63379 + vertex 0.993231 1.68449 2.63375 + vertex 0.99018 1.68059 2.63527 + endloop + endfacet + facet normal 0.395187 0.0482835 0.917331 + outer loop + vertex 0.989629 1.68463 2.6353 + vertex 0.99018 1.68059 2.63527 + vertex 0.993231 1.68449 2.63375 + endloop + endfacet + facet normal 0.395238 0.0524581 0.91708 + outer loop + vertex 0.989629 1.68463 2.6353 + vertex 0.993231 1.68449 2.63375 + vertex 0.990621 1.68893 2.63462 + endloop + endfacet + facet normal 0.396522 0.0533329 0.916475 + outer loop + vertex 0.990621 1.68893 2.63462 + vertex 0.993231 1.68449 2.63375 + vertex 0.994178 1.68898 2.63308 + endloop + endfacet + facet normal 0.396762 0.0459318 0.916772 + outer loop + vertex 0.994178 1.68898 2.63308 + vertex 0.993265 1.69289 2.63328 + vertex 0.990621 1.68893 2.63462 + endloop + endfacet + facet normal 0.383411 0.056556 0.921845 + outer loop + vertex 0.990621 1.68893 2.63462 + vertex 0.993265 1.69289 2.63328 + vertex 0.989754 1.69405 2.63467 + endloop + endfacet + facet normal 0.379858 0.0431284 0.924039 + outer loop + vertex 0.993265 1.69289 2.63328 + vertex 0.992325 1.69687 2.63348 + vertex 0.989754 1.69405 2.63467 + endloop + endfacet + facet normal 0.367062 0.0566438 0.92847 + outer loop + vertex 0.989754 1.69405 2.63467 + vertex 0.992325 1.69687 2.63348 + vertex 0.989396 1.69884 2.63452 + endloop + endfacet + facet normal 0.366868 0.0563031 0.928568 + outer loop + vertex 0.992325 1.69687 2.63348 + vertex 0.993294 1.70152 2.63282 + vertex 0.989396 1.69884 2.63452 + endloop + endfacet + facet normal 0.403074 0.0466765 0.913976 + outer loop + vertex 0.993294 1.70152 2.63282 + vertex 0.992325 1.69687 2.63348 + vertex 0.99601 1.69687 2.63186 + endloop + endfacet + facet normal 0.398956 0.0438716 0.91592 + outer loop + vertex 0.997166 1.70125 2.63114 + vertex 0.993294 1.70152 2.63282 + vertex 0.99601 1.69687 2.63186 + endloop + endfacet + facet normal 0.41743 0.0376876 0.907927 + outer loop + vertex 0.997166 1.70125 2.63114 + vertex 0.99601 1.69687 2.63186 + vertex 0.999408 1.69888 2.63021 + endloop + endfacet + facet normal 0.418307 0.0386924 0.907481 + outer loop + vertex 0.999408 1.69888 2.63021 + vertex 1.00055 1.70328 2.6295 + vertex 0.997166 1.70125 2.63114 + endloop + endfacet + facet normal 0.417103 0.041066 0.907931 + outer loop + vertex 0.997166 1.70125 2.63114 + vertex 1.00055 1.70328 2.6295 + vertex 0.996585 1.70548 2.63122 + endloop + endfacet + facet normal 0.414495 0.0352414 0.909369 + outer loop + vertex 1.00055 1.70328 2.6295 + vertex 0.999841 1.70881 2.6296 + vertex 0.996585 1.70548 2.63122 + endloop + endfacet + facet normal 0.409285 0.0413418 0.91147 + outer loop + vertex 0.996585 1.70548 2.63122 + vertex 0.999841 1.70881 2.6296 + vertex 0.996149 1.71054 2.63118 + endloop + endfacet + facet normal 0.384232 0.0392603 0.922401 + outer loop + vertex 0.996149 1.71054 2.63118 + vertex 0.992598 1.70713 2.63281 + vertex 0.996585 1.70548 2.63122 + endloop + endfacet + facet normal 0.387647 0.049308 0.920488 + outer loop + vertex 0.992598 1.70713 2.63281 + vertex 0.993294 1.70152 2.63282 + vertex 0.996585 1.70548 2.63122 + endloop + endfacet + facet normal 0.378411 0.0463145 0.924478 + outer loop + vertex 0.992397 1.71212 2.63264 + vertex 0.992598 1.70713 2.63281 + vertex 0.996149 1.71054 2.63118 + endloop + endfacet + facet normal 0.376612 0.0411512 0.925457 + outer loop + vertex 0.995965 1.71552 2.63104 + vertex 0.992397 1.71212 2.63264 + vertex 0.996149 1.71054 2.63118 + endloop + endfacet + facet normal 0.407028 0.0418945 0.912454 + outer loop + vertex 0.996149 1.71054 2.63118 + vertex 0.999525 1.71392 2.62952 + vertex 0.995965 1.71552 2.63104 + endloop + endfacet + facet normal 0.406824 0.041331 0.912571 + outer loop + vertex 0.999525 1.71392 2.62952 + vertex 0.999383 1.71897 2.62936 + vertex 0.995965 1.71552 2.63104 + endloop + endfacet + facet normal 0.405122 0.043341 0.913235 + outer loop + vertex 0.995965 1.71552 2.63104 + vertex 0.999383 1.71897 2.62936 + vertex 0.99586 1.72046 2.63085 + endloop + endfacet + facet normal 0.367931 0.04315 0.928851 + outer loop + vertex 0.99586 1.72046 2.63085 + vertex 0.992326 1.71678 2.63242 + vertex 0.995965 1.71552 2.63104 + endloop + endfacet + facet normal 0.358811 0.0531929 0.931893 + outer loop + vertex 0.992101 1.7215 2.63224 + vertex 0.992326 1.71678 2.63242 + vertex 0.99586 1.72046 2.63085 + endloop + endfacet + facet normal 0.35607 0.0409671 0.933561 + outer loop + vertex 0.995783 1.72548 2.63066 + vertex 0.992101 1.7215 2.63224 + vertex 0.99586 1.72046 2.63085 + endloop + endfacet + facet normal 0.402816 0.040952 0.914364 + outer loop + vertex 0.99586 1.72046 2.63085 + vertex 0.999289 1.72402 2.62918 + vertex 0.995783 1.72548 2.63066 + endloop + endfacet + facet normal 0.401066 0.0357487 0.915351 + outer loop + vertex 0.999289 1.72402 2.62918 + vertex 0.999204 1.72905 2.62902 + vertex 0.995783 1.72548 2.63066 + endloop + endfacet + facet normal 0.399275 0.037785 0.916052 + outer loop + vertex 0.995783 1.72548 2.63066 + vertex 0.999204 1.72905 2.62902 + vertex 0.995734 1.73053 2.63047 + endloop + endfacet + facet normal 0.346409 0.0380511 0.937311 + outer loop + vertex 0.995734 1.73053 2.63047 + vertex 0.992028 1.72649 2.63201 + vertex 0.995783 1.72548 2.63066 + endloop + endfacet + facet normal 0.33869 0.0460606 0.93977 + outer loop + vertex 0.992013 1.73158 2.63176 + vertex 0.992028 1.72649 2.63201 + vertex 0.995734 1.73053 2.63047 + endloop + endfacet + facet normal 0.337414 0.0406625 0.940478 + outer loop + vertex 0.995574 1.73553 2.63031 + vertex 0.992013 1.73158 2.63176 + vertex 0.995734 1.73053 2.63047 + endloop + endfacet + facet normal 0.392806 0.0417373 0.918674 + outer loop + vertex 0.995734 1.73053 2.63047 + vertex 0.999077 1.73402 2.62888 + vertex 0.995574 1.73553 2.63031 + endloop + endfacet + facet normal 0.393491 0.0436853 0.91829 + outer loop + vertex 0.999077 1.73402 2.62888 + vertex 0.998771 1.73897 2.62878 + vertex 0.995574 1.73553 2.63031 + endloop + endfacet + facet normal 0.385014 0.0529554 0.92139 + outer loop + vertex 0.995574 1.73553 2.63031 + vertex 0.998771 1.73897 2.62878 + vertex 0.995126 1.74044 2.63022 + endloop + endfacet + facet normal 0.325802 0.0479903 0.944219 + outer loop + vertex 0.995126 1.74044 2.63022 + vertex 0.991812 1.73667 2.63155 + vertex 0.995574 1.73553 2.63031 + endloop + endfacet + facet normal 0.312478 0.0610285 0.947963 + outer loop + vertex 0.991171 1.74199 2.63142 + vertex 0.991812 1.73667 2.63155 + vertex 0.995126 1.74044 2.63022 + endloop + endfacet + facet normal 0.307327 0.0459278 0.950495 + outer loop + vertex 0.995126 1.74044 2.63022 + vertex 0.994506 1.74446 2.63022 + vertex 0.991171 1.74199 2.63142 + endloop + endfacet + facet normal 0.382956 0.0576509 0.921966 + outer loop + vertex 0.994506 1.74446 2.63022 + vertex 0.995126 1.74044 2.63022 + vertex 0.998079 1.74429 2.62875 + endloop + endfacet + facet normal 0.382912 0.0553464 0.922125 + outer loop + vertex 0.994506 1.74446 2.63022 + vertex 0.998079 1.74429 2.62875 + vertex 0.995413 1.74859 2.6296 + endloop + endfacet + facet normal 0.393433 0.0628428 0.917203 + outer loop + vertex 0.995413 1.74859 2.6296 + vertex 0.998079 1.74429 2.62875 + vertex 0.998776 1.74864 2.62815 + endloop + endfacet + facet normal 0.394066 0.044106 0.918023 + outer loop + vertex 0.998776 1.74864 2.62815 + vertex 0.997692 1.75181 2.62847 + vertex 0.995413 1.74859 2.6296 + endloop + endfacet + facet normal 0.391845 0.0459802 0.918882 + outer loop + vertex 0.995413 1.74859 2.6296 + vertex 0.997692 1.75181 2.62847 + vertex 0.994874 1.75367 2.62958 + endloop + endfacet + facet normal 0.386559 0.0364096 0.921546 + outer loop + vertex 0.997692 1.75181 2.62847 + vertex 0.998585 1.75638 2.62791 + vertex 0.994874 1.75367 2.62958 + endloop + endfacet + facet normal 0.410108 0.0305895 0.911524 + outer loop + vertex 0.998585 1.75638 2.62791 + vertex 0.997692 1.75181 2.62847 + vertex 1.00114 1.75192 2.62691 + endloop + endfacet + facet normal 0.418707 0.0364457 0.90739 + outer loop + vertex 1.00222 1.75613 2.62624 + vertex 0.998585 1.75638 2.62791 + vertex 1.00114 1.75192 2.62691 + endloop + endfacet + facet normal 0.416688 0.0371097 0.908292 + outer loop + vertex 1.00222 1.75613 2.62624 + vertex 1.00114 1.75192 2.62691 + vertex 1.00432 1.75402 2.62537 + endloop + endfacet + facet normal 0.412523 0.0320787 0.910382 + outer loop + vertex 1.00432 1.75402 2.62537 + vertex 1.00549 1.75819 2.62469 + vertex 1.00222 1.75613 2.62624 + endloop + endfacet + facet normal 0.414254 0.0314654 0.909617 + outer loop + vertex 1.00432 1.75402 2.62537 + vertex 1.00783 1.75404 2.62377 + vertex 1.00549 1.75819 2.62469 + endloop + endfacet + facet normal 0.420306 0.0355334 0.906686 + outer loop + vertex 1.00549 1.75819 2.62469 + vertex 1.00783 1.75404 2.62377 + vertex 1.00837 1.75778 2.62337 + endloop + endfacet + facet normal 0.413904 0.0482672 0.90904 + outer loop + vertex 1.00432 1.75402 2.62537 + vertex 1.00487 1.7501 2.62533 + vertex 1.00783 1.75404 2.62377 + endloop + endfacet + facet normal 0.421841 0.0409839 0.905743 + outer loop + vertex 1.00853 1.74878 2.62368 + vertex 1.00783 1.75404 2.62377 + vertex 1.00487 1.7501 2.62533 + endloop + endfacet + facet normal 0.425185 0.0529634 0.903555 + outer loop + vertex 1.00534 1.74531 2.62538 + vertex 1.00853 1.74878 2.62368 + vertex 1.00487 1.7501 2.62533 + endloop + endfacet + facet normal 0.414635 0.0519707 0.908502 + outer loop + vertex 1.00487 1.7501 2.62533 + vertex 1.00172 1.74696 2.62694 + vertex 1.00534 1.74531 2.62538 + endloop + endfacet + facet normal 0.416628 0.0575231 0.907255 + outer loop + vertex 1.00172 1.74696 2.62694 + vertex 1.00202 1.74213 2.62711 + vertex 1.00534 1.74531 2.62538 + endloop + endfacet + facet normal 0.426955 0.0445285 0.903176 + outer loop + vertex 1.00534 1.74531 2.62538 + vertex 1.00202 1.74213 2.62711 + vertex 1.0056 1.74047 2.6255 + endloop + endfacet + facet normal 0.441477 0.0451089 0.896138 + outer loop + vertex 1.0056 1.74047 2.6255 + vertex 1.00885 1.74386 2.62373 + vertex 1.00534 1.74531 2.62538 + endloop + endfacet + facet normal 0.427848 0.0469818 0.902629 + outer loop + vertex 1.00202 1.74213 2.62711 + vertex 1.00231 1.73722 2.62723 + vertex 1.0056 1.74047 2.6255 + endloop + endfacet + facet normal 0.438637 0.0336308 0.898035 + outer loop + vertex 1.0056 1.74047 2.6255 + vertex 1.00231 1.73722 2.62723 + vertex 1.00572 1.73558 2.62562 + endloop + endfacet + facet normal 0.459719 0.0339062 0.887417 + outer loop + vertex 1.00572 1.73558 2.62562 + vertex 1.00895 1.73898 2.62382 + vertex 1.0056 1.74047 2.6255 + endloop + endfacet + facet normal 0.457149 0.0263281 0.889001 + outer loop + vertex 1.00895 1.73898 2.62382 + vertex 1.00885 1.74386 2.62373 + vertex 1.0056 1.74047 2.6255 + endloop + endfacet + facet normal 0.468477 0.0233119 0.883168 + outer loop + vertex 1.00901 1.73404 2.62392 + vertex 1.00895 1.73898 2.62382 + vertex 1.00572 1.73558 2.62562 + endloop + endfacet + facet normal 0.470895 0.0300951 0.881676 + outer loop + vertex 1.00582 1.73064 2.62574 + vertex 1.00901 1.73404 2.62392 + vertex 1.00572 1.73558 2.62562 + endloop + endfacet + facet normal 0.444998 0.0299148 0.895032 + outer loop + vertex 1.00572 1.73558 2.62562 + vertex 1.00247 1.73231 2.62735 + vertex 1.00582 1.73064 2.62574 + endloop + endfacet + facet normal 0.446509 0.0338101 0.89414 + outer loop + vertex 1.00247 1.73231 2.62735 + vertex 1.00258 1.72734 2.62748 + vertex 1.00582 1.73064 2.62574 + endloop + endfacet + facet normal 0.446575 0.0337307 0.89411 + outer loop + vertex 1.00582 1.73064 2.62574 + vertex 1.00258 1.72734 2.62748 + vertex 1.00594 1.72565 2.62587 + endloop + endfacet + facet normal 0.475169 0.0340352 0.879236 + outer loop + vertex 1.00594 1.72565 2.62587 + vertex 1.00911 1.72904 2.62403 + vertex 1.00582 1.73064 2.62574 + endloop + endfacet + facet normal 0.47553 0.0336004 0.879058 + outer loop + vertex 1.00924 1.72401 2.62415 + vertex 1.00911 1.72904 2.62403 + vertex 1.00594 1.72565 2.62587 + endloop + endfacet + facet normal 0.477156 0.0380061 0.877996 + outer loop + vertex 1.00605 1.72061 2.62602 + vertex 1.00924 1.72401 2.62415 + vertex 1.00594 1.72565 2.62587 + endloop + endfacet + facet normal 0.448316 0.0377941 0.893076 + outer loop + vertex 1.00594 1.72565 2.62587 + vertex 1.0027 1.72232 2.62764 + vertex 1.00605 1.72061 2.62602 + endloop + endfacet + facet normal 0.449408 0.0405824 0.892404 + outer loop + vertex 1.0027 1.72232 2.62764 + vertex 1.00281 1.71727 2.62781 + vertex 1.00605 1.72061 2.62602 + endloop + endfacet + facet normal 0.451401 0.0381692 0.891504 + outer loop + vertex 1.00605 1.72061 2.62602 + vertex 1.00281 1.71727 2.62781 + vertex 1.00615 1.71557 2.62619 + endloop + endfacet + facet normal 0.481481 0.0382123 0.875623 + outer loop + vertex 1.00615 1.71557 2.62619 + vertex 1.00933 1.71897 2.62429 + vertex 1.00605 1.72061 2.62602 + endloop + endfacet + facet normal 0.487532 0.0308533 0.87256 + outer loop + vertex 1.00939 1.71392 2.62444 + vertex 1.00933 1.71897 2.62429 + vertex 1.00615 1.71557 2.62619 + endloop + endfacet + facet normal 0.489376 0.0357855 0.871338 + outer loop + vertex 1.00629 1.71056 2.62632 + vertex 1.00939 1.71392 2.62444 + vertex 1.00615 1.71557 2.62619 + endloop + endfacet + facet normal 0.457614 0.0353044 0.88845 + outer loop + vertex 1.00615 1.71557 2.62619 + vertex 1.00298 1.71222 2.62796 + vertex 1.00629 1.71056 2.62632 + endloop + endfacet + facet normal 0.459085 0.0391423 0.887529 + outer loop + vertex 1.00298 1.71222 2.62796 + vertex 1.00336 1.70726 2.62798 + vertex 1.00629 1.71056 2.62632 + endloop + endfacet + facet normal 0.46548 0.0319259 0.884483 + outer loop + vertex 1.00629 1.71056 2.62632 + vertex 1.00336 1.70726 2.62798 + vertex 1.00658 1.70573 2.62634 + endloop + endfacet + facet normal 0.498002 0.0338101 0.866517 + outer loop + vertex 1.00658 1.70573 2.62634 + vertex 1.00948 1.70889 2.62455 + vertex 1.00629 1.71056 2.62632 + endloop + endfacet + facet normal 0.504825 0.0254751 0.862846 + outer loop + vertex 1.00971 1.70389 2.62456 + vertex 1.00948 1.70889 2.62455 + vertex 1.00658 1.70573 2.62634 + endloop + endfacet + facet normal 0.506518 0.0294379 0.861727 + outer loop + vertex 1.00684 1.70101 2.62635 + vertex 1.00971 1.70389 2.62456 + vertex 1.00658 1.70573 2.62634 + endloop + endfacet + facet normal 0.477213 0.0279026 0.878345 + outer loop + vertex 1.00658 1.70573 2.62634 + vertex 1.00412 1.70304 2.62776 + vertex 1.00684 1.70101 2.62635 + endloop + endfacet + facet normal 0.475226 0.0244358 0.879524 + outer loop + vertex 1.00412 1.70304 2.62776 + vertex 1.00338 1.698 2.6283 + vertex 1.00684 1.70101 2.62635 + endloop + endfacet + facet normal 0.472011 0.0291628 0.88111 + outer loop + vertex 1.00684 1.70101 2.62635 + vertex 1.00338 1.698 2.6283 + vertex 1.00716 1.69699 2.62631 + endloop + endfacet + facet normal 0.473474 0.0367437 0.880041 + outer loop + vertex 1.00716 1.69699 2.62631 + vertex 1.00338 1.698 2.6283 + vertex 1.00612 1.69281 2.62705 + endloop + endfacet + facet normal 0.504603 0.0259143 0.862962 + outer loop + vertex 1.00716 1.69699 2.62631 + vertex 1.00612 1.69281 2.62705 + vertex 1.00914 1.69453 2.62523 + endloop + endfacet + facet normal 0.471168 0.0352124 0.88134 + outer loop + vertex 1.00338 1.698 2.6283 + vertex 1.00267 1.69299 2.62888 + vertex 1.00612 1.69281 2.62705 + endloop + endfacet + facet normal 0.471274 0.0399896 0.88108 + outer loop + vertex 1.00343 1.68889 2.62866 + vertex 1.00612 1.69281 2.62705 + vertex 1.00267 1.69299 2.62888 + endloop + endfacet + facet normal 0.481366 0.0309745 0.875972 + outer loop + vertex 1.00677 1.68744 2.62688 + vertex 1.00612 1.69281 2.62705 + vertex 1.00343 1.68889 2.62866 + endloop + endfacet + facet normal 0.483286 0.0369648 0.874682 + outer loop + vertex 1.0038 1.68406 2.62866 + vertex 1.00677 1.68744 2.62688 + vertex 1.00343 1.68889 2.62866 + endloop + endfacet + facet normal 0.488171 0.0313429 0.872185 + outer loop + vertex 1.00709 1.68241 2.62688 + vertex 1.00677 1.68744 2.62688 + vertex 1.0038 1.68406 2.62866 + endloop + endfacet + facet normal 0.489793 0.0357409 0.871106 + outer loop + vertex 1.00396 1.67908 2.62878 + vertex 1.00709 1.68241 2.62688 + vertex 1.0038 1.68406 2.62866 + endloop + endfacet + facet normal 0.45813 0.0351112 0.888192 + outer loop + vertex 1.00396 1.67908 2.62878 + vertex 1.0038 1.68406 2.62866 + vertex 1.00057 1.68064 2.63046 + endloop + endfacet + facet normal 0.459327 0.0385412 0.887431 + outer loop + vertex 1.00069 1.67566 2.63062 + vertex 1.00396 1.67908 2.62878 + vertex 1.00057 1.68064 2.63046 + endloop + endfacet + facet normal 0.440049 0.0383822 0.897153 + outer loop + vertex 1.00057 1.68064 2.63046 + vertex 0.997265 1.67734 2.63223 + vertex 1.00069 1.67566 2.63062 + endloop + endfacet + facet normal 0.440635 0.0399177 0.896798 + outer loop + vertex 0.997265 1.67734 2.63223 + vertex 0.997432 1.6724 2.63236 + vertex 1.00069 1.67566 2.63062 + endloop + endfacet + facet normal 0.444383 0.0352939 0.895142 + outer loop + vertex 1.00069 1.67566 2.63062 + vertex 0.997432 1.6724 2.63236 + vertex 1.0008 1.67067 2.63076 + endloop + endfacet + facet normal 0.464386 0.0354497 0.884923 + outer loop + vertex 1.0008 1.67067 2.63076 + vertex 1.00404 1.67406 2.62892 + vertex 1.00069 1.67566 2.63062 + endloop + endfacet + facet normal 0.468523 0.0304005 0.882928 + outer loop + vertex 1.00413 1.66902 2.62905 + vertex 1.00404 1.67406 2.62892 + vertex 1.0008 1.67067 2.63076 + endloop + endfacet + facet normal 0.469334 0.0325649 0.88242 + outer loop + vertex 1.00092 1.66567 2.63088 + vertex 1.00413 1.66902 2.62905 + vertex 1.0008 1.67067 2.63076 + endloop + endfacet + facet normal 0.447765 0.0322894 0.893568 + outer loop + vertex 1.0008 1.67067 2.63076 + vertex 0.997583 1.66745 2.63249 + vertex 1.00092 1.66567 2.63088 + endloop + endfacet + facet normal 0.448255 0.033476 0.893279 + outer loop + vertex 0.997583 1.66745 2.63249 + vertex 0.99773 1.66246 2.6326 + vertex 1.00092 1.66567 2.63088 + endloop + endfacet + facet normal 0.451244 0.0297684 0.891904 + outer loop + vertex 1.00092 1.66567 2.63088 + vertex 0.99773 1.66246 2.6326 + vertex 1.00105 1.66068 2.63098 + endloop + endfacet + facet normal 0.474803 0.0300882 0.879578 + outer loop + vertex 1.00105 1.66068 2.63098 + vertex 1.00423 1.664 2.62915 + vertex 1.00092 1.66567 2.63088 + endloop + endfacet + facet normal 0.477919 0.0262418 0.878012 + outer loop + vertex 1.00431 1.65899 2.62926 + vertex 1.00423 1.664 2.62915 + vertex 1.00105 1.66068 2.63098 + endloop + endfacet + facet normal 0.478998 0.0290185 0.877336 + outer loop + vertex 1.00114 1.65569 2.6311 + vertex 1.00431 1.65899 2.62926 + vertex 1.00105 1.66068 2.63098 + endloop + endfacet + facet normal 0.45414 0.0288804 0.890462 + outer loop + vertex 1.00105 1.66068 2.63098 + vertex 0.997851 1.65745 2.63272 + vertex 1.00114 1.65569 2.6311 + endloop + endfacet + facet normal 0.454751 0.0303569 0.890101 + outer loop + vertex 0.997851 1.65745 2.63272 + vertex 0.997926 1.65242 2.63285 + vertex 1.00114 1.65569 2.6311 + endloop + endfacet + facet normal 0.455565 0.0293532 0.889718 + outer loop + vertex 1.00114 1.65569 2.6311 + vertex 0.997926 1.65242 2.63285 + vertex 1.00118 1.6507 2.63124 + endloop + endfacet + facet normal 0.482068 0.0292196 0.875646 + outer loop + vertex 1.00118 1.6507 2.63124 + vertex 1.00436 1.65399 2.62938 + vertex 1.00114 1.65569 2.6311 + endloop + endfacet + facet normal 0.483446 0.0274969 0.874942 + outer loop + vertex 1.00438 1.64899 2.62952 + vertex 1.00436 1.65399 2.62938 + vertex 1.00118 1.6507 2.63124 + endloop + endfacet + facet normal 0.484478 0.0300838 0.874286 + outer loop + vertex 1.00125 1.64569 2.63137 + vertex 1.00438 1.64899 2.62952 + vertex 1.00118 1.6507 2.63124 + endloop + endfacet + facet normal 0.457086 0.0301063 0.888913 + outer loop + vertex 1.00118 1.6507 2.63124 + vertex 0.997989 1.64739 2.63299 + vertex 1.00125 1.64569 2.63137 + endloop + endfacet + facet normal 0.457855 0.0320242 0.88845 + outer loop + vertex 0.997989 1.64739 2.63299 + vertex 0.998157 1.64235 2.63309 + vertex 1.00125 1.64569 2.63137 + endloop + endfacet + facet normal 0.459208 0.030441 0.887807 + outer loop + vertex 1.00125 1.64569 2.63137 + vertex 0.998157 1.64235 2.63309 + vertex 1.00147 1.64071 2.63143 + endloop + endfacet + facet normal 0.487197 0.0315049 0.872723 + outer loop + vertex 1.00147 1.64071 2.63143 + vertex 1.00446 1.64397 2.62965 + vertex 1.00125 1.64569 2.63137 + endloop + endfacet + facet normal 0.490104 0.0280193 0.871213 + outer loop + vertex 1.00471 1.63896 2.62966 + vertex 1.00446 1.64397 2.62965 + vertex 1.00147 1.64071 2.63143 + endloop + endfacet + facet normal 0.492256 0.0334436 0.869807 + outer loop + vertex 1.00196 1.6359 2.63134 + vertex 1.00471 1.63896 2.62966 + vertex 1.00147 1.64071 2.63143 + endloop + endfacet + facet normal 0.462588 0.0300986 0.886062 + outer loop + vertex 1.00147 1.64071 2.63143 + vertex 0.998599 1.63733 2.63304 + vertex 1.00196 1.6359 2.63134 + endloop + endfacet + facet normal 0.463887 0.0341531 0.885236 + outer loop + vertex 0.998599 1.63733 2.63304 + vertex 0.999551 1.63261 2.63273 + vertex 1.00196 1.6359 2.63134 + endloop + endfacet + facet normal 0.467127 0.0311034 0.883643 + outer loop + vertex 1.00196 1.6359 2.63134 + vertex 0.999551 1.63261 2.63273 + vertex 1.00246 1.63201 2.63121 + endloop + endfacet + facet normal 0.49948 0.0357894 0.865586 + outer loop + vertex 1.00246 1.63201 2.63121 + vertex 1.00527 1.63368 2.62952 + vertex 1.00196 1.6359 2.63134 + endloop + endfacet + facet normal 0.50091 0.0326666 0.864883 + outer loop + vertex 1.00429 1.62961 2.63024 + vertex 1.00527 1.63368 2.62952 + vertex 1.00246 1.63201 2.63121 + endloop + endfacet + facet normal 0.466816 0.02902 0.883878 + outer loop + vertex 1.00246 1.63201 2.63121 + vertex 0.999551 1.63261 2.63273 + vertex 1.00129 1.62797 2.63196 + endloop + endfacet + facet normal 0.488788 0.0204775 0.872162 + outer loop + vertex 1.00246 1.63201 2.63121 + vertex 1.00129 1.62797 2.63196 + vertex 1.00429 1.62961 2.63024 + endloop + endfacet + facet normal 0.486475 0.0258996 0.873311 + outer loop + vertex 1.00482 1.62539 2.63007 + vertex 1.00429 1.62961 2.63024 + vertex 1.00129 1.62797 2.63196 + endloop + endfacet + facet normal 0.48814 0.0289423 0.872286 + outer loop + vertex 1.00129 1.62797 2.63196 + vertex 1.00183 1.62256 2.63184 + vertex 1.00482 1.62539 2.63007 + endloop + endfacet + facet normal 0.48778 0.0294382 0.87247 + outer loop + vertex 1.00482 1.62539 2.63007 + vertex 1.00183 1.62256 2.63184 + vertex 1.00514 1.62044 2.63006 + endloop + endfacet + facet normal 0.493178 0.0297811 0.869419 + outer loop + vertex 1.00514 1.62044 2.63006 + vertex 1.00852 1.62252 2.62807 + vertex 1.00482 1.62539 2.63007 + endloop + endfacet + facet normal 0.494751 0.032499 0.868427 + outer loop + vertex 1.00852 1.62252 2.62807 + vertex 1.00765 1.62873 2.62833 + vertex 1.00482 1.62539 2.63007 + endloop + endfacet + facet normal 0.452638 0.0256053 0.891327 + outer loop + vertex 1.00765 1.62873 2.62833 + vertex 1.00852 1.62252 2.62807 + vertex 1.01151 1.62592 2.62646 + endloop + endfacet + facet normal 0.459991 0.0385488 0.887087 + outer loop + vertex 1.01126 1.63098 2.62636 + vertex 1.00765 1.62873 2.62833 + vertex 1.01151 1.62592 2.62646 + endloop + endfacet + facet normal 0.372215 0.0350691 0.927484 + outer loop + vertex 1.01151 1.62592 2.62646 + vertex 1.01502 1.62907 2.62493 + vertex 1.01126 1.63098 2.62636 + endloop + endfacet + facet normal 0.377439 0.0473948 0.924821 + outer loop + vertex 1.01502 1.62907 2.62493 + vertex 1.01481 1.63414 2.62475 + vertex 1.01126 1.63098 2.62636 + endloop + endfacet + facet normal 0.385951 0.0363495 0.921803 + outer loop + vertex 1.01126 1.63098 2.62636 + vertex 1.01481 1.63414 2.62475 + vertex 1.01123 1.63578 2.62619 + endloop + endfacet + facet normal 0.450612 0.0356705 0.892007 + outer loop + vertex 1.01123 1.63578 2.62619 + vertex 1.00852 1.63321 2.62766 + vertex 1.01126 1.63098 2.62636 + endloop + endfacet + facet normal 0.460364 0.0227179 0.887439 + outer loop + vertex 1.00795 1.63735 2.62785 + vertex 1.00852 1.63321 2.62766 + vertex 1.01123 1.63578 2.62619 + endloop + endfacet + facet normal 0.463514 0.0312758 0.885537 + outer loop + vertex 1.0111 1.64064 2.62608 + vertex 1.00795 1.63735 2.62785 + vertex 1.01123 1.63578 2.62619 + endloop + endfacet + facet normal 0.400711 0.0302235 0.915706 + outer loop + vertex 1.01123 1.63578 2.62619 + vertex 1.01474 1.63915 2.62454 + vertex 1.0111 1.64064 2.62608 + endloop + endfacet + facet normal 0.405975 0.0461399 0.912719 + outer loop + vertex 1.01474 1.63915 2.62454 + vertex 1.01463 1.64417 2.62434 + vertex 1.0111 1.64064 2.62608 + endloop + endfacet + facet normal 0.416455 0.0335961 0.908535 + outer loop + vertex 1.0111 1.64064 2.62608 + vertex 1.01463 1.64417 2.62434 + vertex 1.011 1.64566 2.62594 + endloop + endfacet + facet normal 0.471231 0.0338925 0.881358 + outer loop + vertex 1.011 1.64566 2.62594 + vertex 1.00771 1.64227 2.62784 + vertex 1.0111 1.64064 2.62608 + endloop + endfacet + facet normal 0.475725 0.0282854 0.879139 + outer loop + vertex 1.00762 1.64729 2.62772 + vertex 1.00771 1.64227 2.62784 + vertex 1.011 1.64566 2.62594 + endloop + endfacet + facet normal 0.478347 0.0355489 0.877451 + outer loop + vertex 1.01094 1.65067 2.62578 + vertex 1.00762 1.64729 2.62772 + vertex 1.011 1.64566 2.62594 + endloop + endfacet + facet normal 0.433496 0.0357225 0.900447 + outer loop + vertex 1.011 1.64566 2.62594 + vertex 1.01439 1.64908 2.62418 + vertex 1.01094 1.65067 2.62578 + endloop + endfacet + facet normal 0.437181 0.045927 0.8982 + outer loop + vertex 1.01439 1.64908 2.62418 + vertex 1.01432 1.6539 2.62397 + vertex 1.01094 1.65067 2.62578 + endloop + endfacet + facet normal 0.446419 0.034005 0.894178 + outer loop + vertex 1.01094 1.65067 2.62578 + vertex 1.01432 1.6539 2.62397 + vertex 1.01089 1.6557 2.62561 + endloop + endfacet + facet normal 0.486087 0.0336733 0.873261 + outer loop + vertex 1.01089 1.6557 2.62561 + vertex 1.0076 1.65233 2.62757 + vertex 1.01094 1.65067 2.62578 + endloop + endfacet + facet normal 0.491032 0.0273455 0.870712 + outer loop + vertex 1.00756 1.65736 2.62743 + vertex 1.0076 1.65233 2.62757 + vertex 1.01089 1.6557 2.62561 + endloop + endfacet + facet normal 0.493499 0.0340741 0.869078 + outer loop + vertex 1.01078 1.66075 2.62547 + vertex 1.00756 1.65736 2.62743 + vertex 1.01089 1.6557 2.62561 + endloop + endfacet + facet normal 0.459851 0.0337957 0.887353 + outer loop + vertex 1.01089 1.6557 2.62561 + vertex 1.01424 1.65894 2.62375 + vertex 1.01078 1.66075 2.62547 + endloop + endfacet + facet normal 0.466137 0.0495872 0.883322 + outer loop + vertex 1.01424 1.65894 2.62375 + vertex 1.01387 1.66404 2.62366 + vertex 1.01078 1.66075 2.62547 + endloop + endfacet + facet normal 0.479541 0.0334127 0.876883 + outer loop + vertex 1.01078 1.66075 2.62547 + vertex 1.01387 1.66404 2.62366 + vertex 1.01057 1.66577 2.6254 + endloop + endfacet + facet normal 0.502234 0.0341425 0.864057 + outer loop + vertex 1.01057 1.66577 2.6254 + vertex 1.00748 1.66239 2.62732 + vertex 1.01078 1.66075 2.62547 + endloop + endfacet + facet normal 0.50837 0.0266364 0.860727 + outer loop + vertex 1.00737 1.66741 2.62724 + vertex 1.00748 1.66239 2.62732 + vertex 1.01057 1.66577 2.6254 + endloop + endfacet + facet normal 0.510787 0.0332347 0.859065 + outer loop + vertex 1.01033 1.67061 2.62535 + vertex 1.00737 1.66741 2.62724 + vertex 1.01057 1.66577 2.6254 + endloop + endfacet + facet normal 0.497343 0.0326287 0.86694 + outer loop + vertex 1.01057 1.66577 2.6254 + vertex 1.01341 1.66898 2.62364 + vertex 1.01033 1.67061 2.62535 + endloop + endfacet + facet normal 0.502412 0.0458673 0.863411 + outer loop + vertex 1.01341 1.66898 2.62364 + vertex 1.01278 1.67312 2.6238 + vertex 1.01033 1.67061 2.62535 + endloop + endfacet + facet normal 0.513063 0.0319459 0.857756 + outer loop + vertex 1.01033 1.67061 2.62535 + vertex 1.01278 1.67312 2.6238 + vertex 1.0103 1.67535 2.62519 + endloop + endfacet + facet normal 0.516655 0.0318933 0.8556 + outer loop + vertex 1.0103 1.67535 2.62519 + vertex 1.00728 1.67239 2.62713 + vertex 1.01033 1.67061 2.62535 + endloop + endfacet + facet normal 0.517846 0.0302464 0.854939 + outer loop + vertex 1.00721 1.67738 2.62699 + vertex 1.00728 1.67239 2.62713 + vertex 1.0103 1.67535 2.62519 + endloop + endfacet + facet normal 0.518496 0.031627 0.854495 + outer loop + vertex 1.01029 1.68033 2.62501 + vertex 1.00721 1.67738 2.62699 + vertex 1.0103 1.67535 2.62519 + endloop + endfacet + facet normal 0.509072 0.031809 0.860136 + outer loop + vertex 1.0103 1.67535 2.62519 + vertex 1.01374 1.6775 2.62308 + vertex 1.01029 1.68033 2.62501 + endloop + endfacet + facet normal 0.51166 0.0361319 0.858428 + outer loop + vertex 1.01374 1.6775 2.62308 + vertex 1.01327 1.6831 2.62312 + vertex 1.01029 1.68033 2.62501 + endloop + endfacet + facet normal 0.515408 0.0307217 0.856394 + outer loop + vertex 1.01029 1.68033 2.62501 + vertex 1.01327 1.6831 2.62312 + vertex 1.01002 1.68543 2.62499 + endloop + endfacet + facet normal 0.517904 0.0308475 0.854882 + outer loop + vertex 1.01002 1.68543 2.62499 + vertex 1.00709 1.68241 2.62688 + vertex 1.01029 1.68033 2.62501 + endloop + endfacet + facet normal 0.516226 0.0330591 0.855814 + outer loop + vertex 1.00677 1.68744 2.62688 + vertex 1.00709 1.68241 2.62688 + vertex 1.01002 1.68543 2.62499 + endloop + endfacet + facet normal 0.514319 0.0287496 0.857117 + outer loop + vertex 1.00961 1.69043 2.62507 + vertex 1.00677 1.68744 2.62688 + vertex 1.01002 1.68543 2.62499 + endloop + endfacet + facet normal 0.517519 0.0290415 0.855179 + outer loop + vertex 1.01002 1.68543 2.62499 + vertex 1.01293 1.6883 2.62314 + vertex 1.00961 1.69043 2.62507 + endloop + endfacet + facet normal 0.51801 0.0301075 0.854845 + outer loop + vertex 1.01293 1.6883 2.62314 + vertex 1.01247 1.69382 2.62322 + vertex 1.00961 1.69043 2.62507 + endloop + endfacet + facet normal 0.520164 0.0276209 0.85362 + outer loop + vertex 1.00914 1.69453 2.62523 + vertex 1.00961 1.69043 2.62507 + vertex 1.01247 1.69382 2.62322 + endloop + endfacet + facet normal 0.520618 0.0308998 0.85323 + outer loop + vertex 1.00914 1.69453 2.62523 + vertex 1.01247 1.69382 2.62322 + vertex 1.0102 1.69861 2.62443 + endloop + endfacet + facet normal 0.512184 0.0340751 0.858199 + outer loop + vertex 1.00914 1.69453 2.62523 + vertex 1.0102 1.69861 2.62443 + vertex 1.00716 1.69699 2.62631 + endloop + endfacet + facet normal 0.512738 0.0327145 0.857922 + outer loop + vertex 1.00716 1.69699 2.62631 + vertex 1.0102 1.69861 2.62443 + vertex 1.00684 1.70101 2.62635 + endloop + endfacet + facet normal 0.522283 0.0319588 0.852173 + outer loop + vertex 1.0102 1.69861 2.62443 + vertex 1.01247 1.69382 2.62322 + vertex 1.0135 1.69821 2.62243 + endloop + endfacet + facet normal 0.522157 0.0302297 0.852313 + outer loop + vertex 1.0135 1.69821 2.62243 + vertex 1.01293 1.70229 2.62263 + vertex 1.0102 1.69861 2.62443 + endloop + endfacet + facet normal 0.524771 0.0275498 0.850798 + outer loop + vertex 1.0102 1.69861 2.62443 + vertex 1.01293 1.70229 2.62263 + vertex 1.00971 1.70389 2.62456 + endloop + endfacet + facet normal 0.524222 0.025972 0.851186 + outer loop + vertex 1.01293 1.70229 2.62263 + vertex 1.01267 1.70722 2.62264 + vertex 1.00971 1.70389 2.62456 + endloop + endfacet + facet normal 0.523935 0.0263216 0.851351 + outer loop + vertex 1.00971 1.70389 2.62456 + vertex 1.01267 1.70722 2.62264 + vertex 1.00948 1.70889 2.62455 + endloop + endfacet + facet normal 0.523571 0.0253342 0.851605 + outer loop + vertex 1.01267 1.70722 2.62264 + vertex 1.01256 1.71229 2.62255 + vertex 1.00948 1.70889 2.62455 + endloop + endfacet + facet normal 0.521282 0.0281802 0.852919 + outer loop + vertex 1.00948 1.70889 2.62455 + vertex 1.01256 1.71229 2.62255 + vertex 1.00939 1.71392 2.62444 + endloop + endfacet + facet normal 0.520639 0.0264088 0.853368 + outer loop + vertex 1.01256 1.71229 2.62255 + vertex 1.0125 1.71734 2.62244 + vertex 1.00939 1.71392 2.62444 + endloop + endfacet + facet normal 0.517214 0.0306663 0.855306 + outer loop + vertex 1.00939 1.71392 2.62444 + vertex 1.0125 1.71734 2.62244 + vertex 1.00933 1.71897 2.62429 + endloop + endfacet + facet normal 0.517271 0.0308204 0.855267 + outer loop + vertex 1.0125 1.71734 2.62244 + vertex 1.01242 1.72232 2.62231 + vertex 1.00933 1.71897 2.62429 + endloop + endfacet + facet normal 0.5143 0.0345349 0.856915 + outer loop + vertex 1.00933 1.71897 2.62429 + vertex 1.01242 1.72232 2.62231 + vertex 1.00924 1.72401 2.62415 + endloop + endfacet + facet normal 0.513884 0.0334332 0.857208 + outer loop + vertex 1.01242 1.72232 2.62231 + vertex 1.0123 1.72731 2.62218 + vertex 1.00924 1.72401 2.62415 + endloop + endfacet + facet normal 0.513385 0.0340599 0.857482 + outer loop + vertex 1.00924 1.72401 2.62415 + vertex 1.0123 1.72731 2.62218 + vertex 1.00911 1.72904 2.62403 + endloop + endfacet + facet normal 0.511673 0.0296163 0.85867 + outer loop + vertex 1.0123 1.72731 2.62218 + vertex 1.01217 1.73236 2.62209 + vertex 1.00911 1.72904 2.62403 + endloop + endfacet + facet normal 0.512915 0.0280696 0.857981 + outer loop + vertex 1.00911 1.72904 2.62403 + vertex 1.01217 1.73236 2.62209 + vertex 1.00901 1.73404 2.62392 + endloop + endfacet + facet normal 0.509571 0.0193367 0.860211 + outer loop + vertex 1.01217 1.73236 2.62209 + vertex 1.01209 1.73738 2.62202 + vertex 1.00901 1.73404 2.62392 + endloop + endfacet + facet normal 0.506395 0.0232805 0.861987 + outer loop + vertex 1.00901 1.73404 2.62392 + vertex 1.01209 1.73738 2.62202 + vertex 1.00895 1.73898 2.62382 + endloop + endfacet + facet normal 0.502193 0.0119964 0.864673 + outer loop + vertex 1.01209 1.73738 2.62202 + vertex 1.01208 1.74231 2.62196 + vertex 1.00895 1.73898 2.62382 + endloop + endfacet + facet normal 0.490395 0.0266472 0.871093 + outer loop + vertex 1.00895 1.73898 2.62382 + vertex 1.01208 1.74231 2.62196 + vertex 1.00885 1.74386 2.62373 + endloop + endfacet + facet normal 0.486574 0.0159283 0.873494 + outer loop + vertex 1.01208 1.74231 2.62196 + vertex 1.01198 1.7472 2.62192 + vertex 1.00885 1.74386 2.62373 + endloop + endfacet + facet normal 0.467395 0.0391015 0.883183 + outer loop + vertex 1.00885 1.74386 2.62373 + vertex 1.01198 1.7472 2.62192 + vertex 1.00853 1.74878 2.62368 + endloop + endfacet + facet normal 0.463115 0.0267348 0.885895 + outer loop + vertex 1.01198 1.7472 2.62192 + vertex 1.01163 1.75217 2.62196 + vertex 1.00853 1.74878 2.62368 + endloop + endfacet + facet normal 0.492852 0.0289293 0.869632 + outer loop + vertex 1.01163 1.75217 2.62196 + vertex 1.01198 1.7472 2.62192 + vertex 1.01501 1.75027 2.6201 + endloop + endfacet + facet normal 0.515711 0.0164365 0.856605 + outer loop + vertex 1.01198 1.7472 2.62192 + vertex 1.01208 1.74231 2.62196 + vertex 1.01512 1.74537 2.62007 + endloop + endfacet + facet normal 0.510908 0.00512008 0.85962 + outer loop + vertex 1.01501 1.75027 2.6201 + vertex 1.01198 1.7472 2.62192 + vertex 1.01512 1.74537 2.62007 + endloop + endfacet + facet normal 0.516662 0.00526791 0.856173 + outer loop + vertex 1.01512 1.74537 2.62007 + vertex 1.0182 1.7482 2.61819 + vertex 1.01501 1.75027 2.6201 + endloop + endfacet + facet normal 0.516777 0.00551093 0.856102 + outer loop + vertex 1.0182 1.7482 2.61819 + vertex 1.01806 1.75321 2.61825 + vertex 1.01501 1.75027 2.6201 + endloop + endfacet + facet normal 0.488532 0.00455113 0.872534 + outer loop + vertex 1.01806 1.75321 2.61825 + vertex 1.0182 1.7482 2.61819 + vertex 1.02146 1.75105 2.61635 + endloop + endfacet + facet normal 0.493012 -0.00219274 0.87002 + outer loop + vertex 1.02146 1.75105 2.61635 + vertex 1.0182 1.7482 2.61819 + vertex 1.02145 1.74604 2.61635 + endloop + endfacet + facet normal 0.430354 -0.00210499 0.902658 + outer loop + vertex 1.02145 1.74604 2.61635 + vertex 1.02499 1.74912 2.61466 + vertex 1.02146 1.75105 2.61635 + endloop + endfacet + facet normal 0.442742 0.0261684 0.896267 + outer loop + vertex 1.02499 1.74912 2.61466 + vertex 1.0248 1.7541 2.61461 + vertex 1.02146 1.75105 2.61635 + endloop + endfacet + facet normal 0.426903 0.00276867 0.904293 + outer loop + vertex 1.02493 1.74411 2.61471 + vertex 1.02499 1.74912 2.61466 + vertex 1.02145 1.74604 2.61635 + endloop + endfacet + facet normal 0.422425 -0.00709184 0.90637 + outer loop + vertex 1.02134 1.74101 2.61636 + vertex 1.02493 1.74411 2.61471 + vertex 1.02145 1.74604 2.61635 + endloop + endfacet + facet normal 0.489112 -0.0086315 0.872178 + outer loop + vertex 1.02145 1.74604 2.61635 + vertex 1.01814 1.74324 2.61817 + vertex 1.02134 1.74101 2.61636 + endloop + endfacet + facet normal 0.491431 -0.0042762 0.870906 + outer loop + vertex 1.01814 1.74324 2.61817 + vertex 1.01809 1.73821 2.61818 + vertex 1.02134 1.74101 2.61636 + endloop + endfacet + facet normal 0.483872 0.00721769 0.875109 + outer loop + vertex 1.02134 1.74101 2.61636 + vertex 1.01809 1.73821 2.61818 + vertex 1.02136 1.7359 2.61639 + endloop + endfacet + facet normal 0.415868 0.00710661 0.909397 + outer loop + vertex 1.02136 1.7359 2.61639 + vertex 1.02487 1.73909 2.61476 + vertex 1.02134 1.74101 2.61636 + endloop + endfacet + facet normal 0.414503 0.00405995 0.910039 + outer loop + vertex 1.02487 1.73909 2.61476 + vertex 1.02493 1.74411 2.61471 + vertex 1.02134 1.74101 2.61636 + endloop + endfacet + facet normal 0.402037 0.0253752 0.915272 + outer loop + vertex 1.02504 1.73399 2.61482 + vertex 1.02487 1.73909 2.61476 + vertex 1.02136 1.7359 2.61639 + endloop + endfacet + facet normal 0.401835 0.024902 0.915374 + outer loop + vertex 1.02166 1.73076 2.6164 + vertex 1.02504 1.73399 2.61482 + vertex 1.02136 1.7359 2.61639 + endloop + endfacet + facet normal 0.478545 0.0293601 0.877572 + outer loop + vertex 1.02136 1.7359 2.61639 + vertex 1.01825 1.73301 2.61818 + vertex 1.02166 1.73076 2.6164 + endloop + endfacet + facet normal 0.479082 0.0304396 0.877242 + outer loop + vertex 1.01825 1.73301 2.61818 + vertex 1.01871 1.72733 2.61813 + vertex 1.02166 1.73076 2.6164 + endloop + endfacet + facet normal 0.471297 0.0390925 0.881108 + outer loop + vertex 1.02166 1.73076 2.6164 + vertex 1.01871 1.72733 2.61813 + vertex 1.02211 1.72652 2.61635 + endloop + endfacet + facet normal 0.373704 0.0282769 0.927117 + outer loop + vertex 1.02211 1.72652 2.61635 + vertex 1.0256 1.72858 2.61487 + vertex 1.02166 1.73076 2.6164 + endloop + endfacet + facet normal 0.368233 0.0388512 0.928922 + outer loop + vertex 1.02428 1.72419 2.61558 + vertex 1.0256 1.72858 2.61487 + vertex 1.02211 1.72652 2.61635 + endloop + endfacet + facet normal 0.396137 0.0692599 0.915576 + outer loop + vertex 1.02211 1.72652 2.61635 + vertex 1.02107 1.72241 2.61711 + vertex 1.02428 1.72419 2.61558 + endloop + endfacet + facet normal 0.472057 0.0436294 0.880488 + outer loop + vertex 1.02211 1.72652 2.61635 + vertex 1.01871 1.72733 2.61813 + vertex 1.02107 1.72241 2.61711 + endloop + endfacet + facet normal 0.479011 0.0477952 0.876507 + outer loop + vertex 1.01871 1.72733 2.61813 + vertex 1.0178 1.72296 2.61886 + vertex 1.02107 1.72241 2.61711 + endloop + endfacet + facet normal 0.478184 0.0402769 0.877336 + outer loop + vertex 1.01844 1.71883 2.6187 + vertex 1.02107 1.72241 2.61711 + vertex 1.0178 1.72296 2.61886 + endloop + endfacet + facet normal 0.530496 0.0349238 0.846968 + outer loop + vertex 1.01871 1.72733 2.61813 + vertex 1.01825 1.73301 2.61818 + vertex 1.01529 1.73024 2.62015 + endloop + endfacet + facet normal 0.53009 0.0342505 0.84725 + outer loop + vertex 1.01535 1.72524 2.62031 + vertex 1.01871 1.72733 2.61813 + vertex 1.01529 1.73024 2.62015 + endloop + endfacet + facet normal 0.538891 0.0341766 0.841682 + outer loop + vertex 1.01529 1.73024 2.62015 + vertex 1.0123 1.72731 2.62218 + vertex 1.01535 1.72524 2.62031 + endloop + endfacet + facet normal 0.531113 0.0320259 0.846696 + outer loop + vertex 1.0178 1.72296 2.61886 + vertex 1.01871 1.72733 2.61813 + vertex 1.01535 1.72524 2.62031 + endloop + endfacet + facet normal 0.533329 0.0353808 0.845167 + outer loop + vertex 1.01541 1.72051 2.62047 + vertex 1.0178 1.72296 2.61886 + vertex 1.01535 1.72524 2.62031 + endloop + endfacet + facet normal 0.537398 0.0353476 0.842588 + outer loop + vertex 1.01535 1.72524 2.62031 + vertex 1.01242 1.72232 2.62231 + vertex 1.01541 1.72051 2.62047 + endloop + endfacet + facet normal 0.523719 0.048295 0.850521 + outer loop + vertex 1.01844 1.71883 2.6187 + vertex 1.0178 1.72296 2.61886 + vertex 1.01541 1.72051 2.62047 + endloop + endfacet + facet normal 0.517859 0.0332135 0.854821 + outer loop + vertex 1.01562 1.71567 2.62053 + vertex 1.01844 1.71883 2.6187 + vertex 1.01541 1.72051 2.62047 + endloop + endfacet + facet normal 0.533238 0.0337534 0.845292 + outer loop + vertex 1.01541 1.72051 2.62047 + vertex 1.0125 1.71734 2.62244 + vertex 1.01562 1.71567 2.62053 + endloop + endfacet + facet normal 0.504756 0.0489355 0.861874 + outer loop + vertex 1.01886 1.7139 2.61874 + vertex 1.01844 1.71883 2.6187 + vertex 1.01562 1.71567 2.62053 + endloop + endfacet + facet normal 0.498524 0.0330343 0.866246 + outer loop + vertex 1.01578 1.71061 2.62063 + vertex 1.01886 1.7139 2.61874 + vertex 1.01562 1.71567 2.62053 + endloop + endfacet + facet normal 0.524762 0.0335595 0.850587 + outer loop + vertex 1.01562 1.71567 2.62053 + vertex 1.01256 1.71229 2.62255 + vertex 1.01578 1.71061 2.62063 + endloop + endfacet + facet normal 0.483858 0.0509824 0.87366 + outer loop + vertex 1.01918 1.70878 2.61886 + vertex 1.01886 1.7139 2.61874 + vertex 1.01578 1.71061 2.62063 + endloop + endfacet + facet normal 0.476772 0.0332533 0.878398 + outer loop + vertex 1.01594 1.70555 2.62074 + vertex 1.01918 1.70878 2.61886 + vertex 1.01578 1.71061 2.62063 + endloop + endfacet + facet normal 0.51484 0.0339494 0.856614 + outer loop + vertex 1.01578 1.71061 2.62063 + vertex 1.01267 1.70722 2.62264 + vertex 1.01594 1.70555 2.62074 + endloop + endfacet + facet normal 0.465869 0.0472767 0.88359 + outer loop + vertex 1.01928 1.70374 2.61907 + vertex 1.01918 1.70878 2.61886 + vertex 1.01594 1.70555 2.62074 + endloop + endfacet + facet normal 0.460268 0.0336559 0.887142 + outer loop + vertex 1.01613 1.70074 2.62083 + vertex 1.01928 1.70374 2.61907 + vertex 1.01594 1.70555 2.62074 + endloop + endfacet + facet normal 0.503861 0.034949 0.863077 + outer loop + vertex 1.01594 1.70555 2.62074 + vertex 1.01293 1.70229 2.62263 + vertex 1.01613 1.70074 2.62083 + endloop + endfacet + facet normal 0.500965 0.0267024 0.865055 + outer loop + vertex 1.01293 1.70229 2.62263 + vertex 1.0135 1.69821 2.62243 + vertex 1.01613 1.70074 2.62083 + endloop + endfacet + facet normal 0.490434 0.0410833 0.870509 + outer loop + vertex 1.01613 1.70074 2.62083 + vertex 1.0135 1.69821 2.62243 + vertex 1.01614 1.69607 2.62104 + endloop + endfacet + facet normal 0.44137 0.0420684 0.896339 + outer loop + vertex 1.01614 1.69607 2.62104 + vertex 1.01939 1.69899 2.6193 + vertex 1.01613 1.70074 2.62083 + endloop + endfacet + facet normal 0.429227 0.0585284 0.901299 + outer loop + vertex 1.01964 1.69418 2.61949 + vertex 1.01939 1.69899 2.6193 + vertex 1.01614 1.69607 2.62104 + endloop + endfacet + facet normal 0.422537 0.0428774 0.905331 + outer loop + vertex 1.01614 1.69114 2.62127 + vertex 1.01964 1.69418 2.61949 + vertex 1.01614 1.69607 2.62104 + endloop + endfacet + facet normal 0.49182 0.0411909 0.869722 + outer loop + vertex 1.01614 1.69607 2.62104 + vertex 1.01247 1.69382 2.62322 + vertex 1.01614 1.69114 2.62127 + endloop + endfacet + facet normal 0.414236 0.0543151 0.908548 + outer loop + vertex 1.01982 1.68917 2.61971 + vertex 1.01964 1.69418 2.61949 + vertex 1.01614 1.69114 2.62127 + endloop + endfacet + facet normal 0.405995 0.0352302 0.913196 + outer loop + vertex 1.01637 1.68602 2.62137 + vertex 1.01982 1.68917 2.61971 + vertex 1.01614 1.69114 2.62127 + endloop + endfacet + facet normal 0.476754 0.0377026 0.878228 + outer loop + vertex 1.01614 1.69114 2.62127 + vertex 1.01293 1.6883 2.62314 + vertex 1.01637 1.68602 2.62137 + endloop + endfacet + facet normal 0.47209 0.0284447 0.881091 + outer loop + vertex 1.01293 1.6883 2.62314 + vertex 1.01327 1.6831 2.62312 + vertex 1.01637 1.68602 2.62137 + endloop + endfacet + facet normal 0.462888 0.0408757 0.885474 + outer loop + vertex 1.01637 1.68602 2.62137 + vertex 1.01327 1.6831 2.62312 + vertex 1.01673 1.68094 2.62141 + endloop + endfacet + facet normal 0.383984 0.0355784 0.922654 + outer loop + vertex 1.01673 1.68094 2.62141 + vertex 1.02011 1.68412 2.61988 + vertex 1.01637 1.68602 2.62137 + endloop + endfacet + facet normal 0.365494 0.0582308 0.92899 + outer loop + vertex 1.02069 1.67878 2.61999 + vertex 1.02011 1.68412 2.61988 + vertex 1.01673 1.68094 2.62141 + endloop + endfacet + facet normal 0.351872 0.0288888 0.935602 + outer loop + vertex 1.01716 1.67675 2.62138 + vertex 1.02069 1.67878 2.61999 + vertex 1.01673 1.68094 2.62141 + endloop + endfacet + facet normal 0.451322 0.0392633 0.891497 + outer loop + vertex 1.01673 1.68094 2.62141 + vertex 1.01374 1.6775 2.62308 + vertex 1.01716 1.67675 2.62138 + endloop + endfacet + facet normal 0.451542 0.0406531 0.891323 + outer loop + vertex 1.01716 1.67675 2.62138 + vertex 1.01374 1.6775 2.62308 + vertex 1.01608 1.67261 2.62211 + endloop + endfacet + facet normal 0.375363 0.0662552 0.924507 + outer loop + vertex 1.01716 1.67675 2.62138 + vertex 1.01608 1.67261 2.62211 + vertex 1.01932 1.67442 2.62067 + endloop + endfacet + facet normal 0.347774 0.0368604 0.936854 + outer loop + vertex 1.01932 1.67442 2.62067 + vertex 1.02069 1.67878 2.61999 + vertex 1.01716 1.67675 2.62138 + endloop + endfacet + facet normal 0.458381 0.0315125 0.888197 + outer loop + vertex 1.01327 1.6831 2.62312 + vertex 1.01374 1.6775 2.62308 + vertex 1.01673 1.68094 2.62141 + endloop + endfacet + facet normal 0.391582 0.0537804 0.91857 + outer loop + vertex 1.02011 1.68412 2.61988 + vertex 1.01982 1.68917 2.61971 + vertex 1.01637 1.68602 2.62137 + endloop + endfacet + facet normal 0.491235 0.0424112 0.869994 + outer loop + vertex 1.0135 1.69821 2.62243 + vertex 1.01247 1.69382 2.62322 + vertex 1.01614 1.69607 2.62104 + endloop + endfacet + facet normal 0.445775 0.0526656 0.893594 + outer loop + vertex 1.01939 1.69899 2.6193 + vertex 1.01928 1.70374 2.61907 + vertex 1.01613 1.70074 2.62083 + endloop + endfacet + facet normal 0.537629 0.0243652 0.84283 + outer loop + vertex 1.01529 1.73024 2.62015 + vertex 1.01825 1.73301 2.61818 + vertex 1.01512 1.73541 2.62011 + endloop + endfacet + facet normal 0.539092 0.0244073 0.841893 + outer loop + vertex 1.01512 1.73541 2.62011 + vertex 1.01217 1.73236 2.62209 + vertex 1.01529 1.73024 2.62015 + endloop + endfacet + facet normal 0.533641 0.0169865 0.84554 + outer loop + vertex 1.01825 1.73301 2.61818 + vertex 1.01809 1.73821 2.61818 + vertex 1.01512 1.73541 2.62011 + endloop + endfacet + facet normal 0.539742 0.00792977 0.841793 + outer loop + vertex 1.01512 1.73541 2.62011 + vertex 1.01809 1.73821 2.61818 + vertex 1.01509 1.74044 2.62008 + endloop + endfacet + facet normal 0.537362 0.00792552 0.843314 + outer loop + vertex 1.01509 1.74044 2.62008 + vertex 1.01209 1.73738 2.62202 + vertex 1.01512 1.73541 2.62011 + endloop + endfacet + facet normal 0.382963 0.0481842 0.922506 + outer loop + vertex 1.0256 1.72858 2.61487 + vertex 1.02504 1.73399 2.61482 + vertex 1.02166 1.73076 2.6164 + endloop + endfacet + facet normal 0.488375 0.0156407 0.872493 + outer loop + vertex 1.01809 1.73821 2.61818 + vertex 1.01825 1.73301 2.61818 + vertex 1.02136 1.7359 2.61639 + endloop + endfacet + facet normal 0.533004 -0.00477331 0.846099 + outer loop + vertex 1.01809 1.73821 2.61818 + vertex 1.01814 1.74324 2.61817 + vertex 1.01509 1.74044 2.62008 + endloop + endfacet + facet normal 0.530724 -0.00129254 0.847544 + outer loop + vertex 1.01509 1.74044 2.62008 + vertex 1.01814 1.74324 2.61817 + vertex 1.01512 1.74537 2.62007 + endloop + endfacet + facet normal 0.48947 -0.00918881 0.871972 + outer loop + vertex 1.0182 1.7482 2.61819 + vertex 1.01814 1.74324 2.61817 + vertex 1.02145 1.74604 2.61635 + endloop + endfacet + facet normal 0.526523 -0.00951687 0.850107 + outer loop + vertex 1.01814 1.74324 2.61817 + vertex 1.0182 1.7482 2.61819 + vertex 1.01512 1.74537 2.62007 + endloop + endfacet + facet normal 0.528706 -0.00127614 0.848804 + outer loop + vertex 1.01512 1.74537 2.62007 + vertex 1.01208 1.74231 2.62196 + vertex 1.01509 1.74044 2.62008 + endloop + endfacet + facet normal 0.534525 0.0118089 0.84507 + outer loop + vertex 1.01208 1.74231 2.62196 + vertex 1.01209 1.73738 2.62202 + vertex 1.01509 1.74044 2.62008 + endloop + endfacet + facet normal 0.542669 0.0195376 0.83972 + outer loop + vertex 1.01209 1.73738 2.62202 + vertex 1.01217 1.73236 2.62209 + vertex 1.01512 1.73541 2.62011 + endloop + endfacet + facet normal 0.541757 0.0300791 0.839996 + outer loop + vertex 1.01217 1.73236 2.62209 + vertex 1.0123 1.72731 2.62218 + vertex 1.01529 1.73024 2.62015 + endloop + endfacet + facet normal 0.53863 0.0336211 0.841872 + outer loop + vertex 1.0123 1.72731 2.62218 + vertex 1.01242 1.72232 2.62231 + vertex 1.01535 1.72524 2.62031 + endloop + endfacet + facet normal 0.535517 0.0308397 0.843961 + outer loop + vertex 1.01242 1.72232 2.62231 + vertex 1.0125 1.71734 2.62244 + vertex 1.01541 1.72051 2.62047 + endloop + endfacet + facet normal 0.530495 0.0263879 0.847277 + outer loop + vertex 1.0125 1.71734 2.62244 + vertex 1.01256 1.71229 2.62255 + vertex 1.01562 1.71567 2.62053 + endloop + endfacet + facet normal 0.521739 0.0253149 0.852729 + outer loop + vertex 1.01256 1.71229 2.62255 + vertex 1.01267 1.70722 2.62264 + vertex 1.01578 1.71061 2.62063 + endloop + endfacet + facet normal 0.511684 0.0252805 0.858801 + outer loop + vertex 1.01267 1.70722 2.62264 + vertex 1.01293 1.70229 2.62263 + vertex 1.01594 1.70555 2.62074 + endloop + endfacet + facet normal 0.504793 0.0254777 0.862865 + outer loop + vertex 1.00961 1.69043 2.62507 + vertex 1.00914 1.69453 2.62523 + vertex 1.00612 1.69281 2.62705 + endloop + endfacet + facet normal 0.484065 0.0270457 0.874614 + outer loop + vertex 1.01247 1.69382 2.62322 + vertex 1.01293 1.6883 2.62314 + vertex 1.01614 1.69114 2.62127 + endloop + endfacet + facet normal 0.515776 0.0314336 0.856147 + outer loop + vertex 1.01327 1.6831 2.62312 + vertex 1.01293 1.6883 2.62314 + vertex 1.01002 1.68543 2.62499 + endloop + endfacet + facet normal 0.518357 0.0318236 0.854572 + outer loop + vertex 1.00709 1.68241 2.62688 + vertex 1.00721 1.67738 2.62699 + vertex 1.01029 1.68033 2.62501 + endloop + endfacet + facet normal 0.496374 0.030328 0.867579 + outer loop + vertex 1.00728 1.67239 2.62713 + vertex 1.00721 1.67738 2.62699 + vertex 1.00404 1.67406 2.62892 + endloop + endfacet + facet normal 0.49643 0.0304757 0.867542 + outer loop + vertex 1.00413 1.66902 2.62905 + vertex 1.00728 1.67239 2.62713 + vertex 1.00404 1.67406 2.62892 + endloop + endfacet + facet normal 0.498544 0.0278557 0.866417 + outer loop + vertex 1.00737 1.66741 2.62724 + vertex 1.00728 1.67239 2.62713 + vertex 1.00413 1.66902 2.62905 + endloop + endfacet + facet normal 0.498381 0.0274074 0.866525 + outer loop + vertex 1.00423 1.664 2.62915 + vertex 1.00737 1.66741 2.62724 + vertex 1.00413 1.66902 2.62905 + endloop + endfacet + facet normal 0.493949 0.0333758 0.86885 + outer loop + vertex 1.00404 1.67406 2.62892 + vertex 1.00721 1.67738 2.62699 + vertex 1.00396 1.67908 2.62878 + endloop + endfacet + facet normal 0.510702 0.0283738 0.859289 + outer loop + vertex 1.01278 1.67312 2.6238 + vertex 1.01374 1.6775 2.62308 + vertex 1.0103 1.67535 2.62519 + endloop + endfacet + facet normal 0.515019 0.0279582 0.856723 + outer loop + vertex 1.00728 1.67239 2.62713 + vertex 1.00737 1.66741 2.62724 + vertex 1.01033 1.67061 2.62535 + endloop + endfacet + facet normal 0.499103 0.026523 0.866137 + outer loop + vertex 1.00748 1.66239 2.62732 + vertex 1.00737 1.66741 2.62724 + vertex 1.00423 1.664 2.62915 + endloop + endfacet + facet normal 0.484874 0.0471624 0.873312 + outer loop + vertex 1.01387 1.66404 2.62366 + vertex 1.01341 1.66898 2.62364 + vertex 1.01057 1.66577 2.6254 + endloop + endfacet + facet normal 0.499496 0.0265561 0.865909 + outer loop + vertex 1.00748 1.66239 2.62732 + vertex 1.00756 1.65736 2.62743 + vertex 1.01078 1.66075 2.62547 + endloop + endfacet + facet normal 0.498885 0.0265541 0.866261 + outer loop + vertex 1.00756 1.65736 2.62743 + vertex 1.00748 1.66239 2.62732 + vertex 1.00431 1.65899 2.62926 + endloop + endfacet + facet normal 0.498844 0.0264415 0.866289 + outer loop + vertex 1.00436 1.65399 2.62938 + vertex 1.00756 1.65736 2.62743 + vertex 1.00431 1.65899 2.62926 + endloop + endfacet + facet normal 0.49818 0.0272786 0.866645 + outer loop + vertex 1.0076 1.65233 2.62757 + vertex 1.00756 1.65736 2.62743 + vertex 1.00436 1.65399 2.62938 + endloop + endfacet + facet normal 0.45098 0.0452704 0.891385 + outer loop + vertex 1.01432 1.6539 2.62397 + vertex 1.01424 1.65894 2.62375 + vertex 1.01089 1.6557 2.62561 + endloop + endfacet + facet normal 0.484093 0.0282428 0.87456 + outer loop + vertex 1.0076 1.65233 2.62757 + vertex 1.00762 1.64729 2.62772 + vertex 1.01094 1.65067 2.62578 + endloop + endfacet + facet normal 0.497613 0.0280779 0.866944 + outer loop + vertex 1.00762 1.64729 2.62772 + vertex 1.0076 1.65233 2.62757 + vertex 1.00438 1.64899 2.62952 + endloop + endfacet + facet normal 0.497703 0.0283126 0.866885 + outer loop + vertex 1.00446 1.64397 2.62965 + vertex 1.00762 1.64729 2.62772 + vertex 1.00438 1.64899 2.62952 + endloop + endfacet + facet normal 0.497631 0.028403 0.866923 + outer loop + vertex 1.00771 1.64227 2.62784 + vertex 1.00762 1.64729 2.62772 + vertex 1.00446 1.64397 2.62965 + endloop + endfacet + facet normal 0.421731 0.0499059 0.905347 + outer loop + vertex 1.01463 1.64417 2.62434 + vertex 1.01439 1.64908 2.62418 + vertex 1.011 1.64566 2.62594 + endloop + endfacet + facet normal 0.468214 0.0255496 0.883245 + outer loop + vertex 1.00771 1.64227 2.62784 + vertex 1.00795 1.63735 2.62785 + vertex 1.0111 1.64064 2.62608 + endloop + endfacet + facet normal 0.498755 0.027028 0.866322 + outer loop + vertex 1.00795 1.63735 2.62785 + vertex 1.00771 1.64227 2.62784 + vertex 1.00471 1.63896 2.62966 + endloop + endfacet + facet normal 0.499592 0.0293424 0.865764 + outer loop + vertex 1.00527 1.63368 2.62952 + vertex 1.00795 1.63735 2.62785 + vertex 1.00471 1.63896 2.62966 + endloop + endfacet + facet normal 0.499863 0.0290781 0.865616 + outer loop + vertex 1.00852 1.63321 2.62766 + vertex 1.00795 1.63735 2.62785 + vertex 1.00527 1.63368 2.62952 + endloop + endfacet + facet normal 0.500247 0.0332318 0.865245 + outer loop + vertex 1.00527 1.63368 2.62952 + vertex 1.00765 1.62873 2.62833 + vertex 1.00852 1.63321 2.62766 + endloop + endfacet + facet normal 0.499898 0.0330141 0.865455 + outer loop + vertex 1.00429 1.62961 2.63024 + vertex 1.00765 1.62873 2.62833 + vertex 1.00527 1.63368 2.62952 + endloop + endfacet + facet normal 0.389024 0.0445262 0.920151 + outer loop + vertex 1.01481 1.63414 2.62475 + vertex 1.01474 1.63915 2.62454 + vertex 1.01123 1.63578 2.62619 + endloop + endfacet + facet normal 0.363198 0.0466156 0.930545 + outer loop + vertex 1.01559 1.62365 2.62498 + vertex 1.01502 1.62907 2.62493 + vertex 1.01151 1.62592 2.62646 + endloop + endfacet + facet normal 0.34887 0.0166841 0.937023 + outer loop + vertex 1.01202 1.6216 2.62634 + vertex 1.01559 1.62365 2.62498 + vertex 1.01151 1.62592 2.62646 + endloop + endfacet + facet normal 0.346405 0.0215221 0.937838 + outer loop + vertex 1.01422 1.61925 2.62559 + vertex 1.01559 1.62365 2.62498 + vertex 1.01202 1.6216 2.62634 + endloop + endfacet + facet normal 0.377601 0.0549441 0.924337 + outer loop + vertex 1.01202 1.6216 2.62634 + vertex 1.01099 1.61751 2.62701 + vertex 1.01422 1.61925 2.62559 + endloop + endfacet + facet normal 0.449217 0.0317265 0.892859 + outer loop + vertex 1.01202 1.6216 2.62634 + vertex 1.00852 1.62252 2.62807 + vertex 1.01099 1.61751 2.62701 + endloop + endfacet + facet normal 0.458563 0.0373877 0.887875 + outer loop + vertex 1.00852 1.62252 2.62807 + vertex 1.00771 1.61811 2.62867 + vertex 1.01099 1.61751 2.62701 + endloop + endfacet + facet normal 0.457682 0.0306026 0.888589 + outer loop + vertex 1.00835 1.61401 2.62849 + vertex 1.01099 1.61751 2.62701 + vertex 1.00771 1.61811 2.62867 + endloop + endfacet + facet normal 0.441715 0.0457753 0.895987 + outer loop + vertex 1.01164 1.61224 2.62696 + vertex 1.01099 1.61751 2.62701 + vertex 1.00835 1.61401 2.62849 + endloop + endfacet + facet normal 0.436826 0.034141 0.898898 + outer loop + vertex 1.00869 1.60915 2.62851 + vertex 1.01164 1.61224 2.62696 + vertex 1.00835 1.61401 2.62849 + endloop + endfacet + facet normal 0.426597 0.0460877 0.903267 + outer loop + vertex 1.01203 1.60727 2.62703 + vertex 1.01164 1.61224 2.62696 + vertex 1.00869 1.60915 2.62851 + endloop + endfacet + facet normal 0.422499 0.0369687 0.905609 + outer loop + vertex 1.00894 1.60414 2.6286 + vertex 1.01203 1.60727 2.62703 + vertex 1.00869 1.60915 2.62851 + endloop + endfacet + facet normal 0.410768 0.0509423 0.910316 + outer loop + vertex 1.01244 1.6022 2.62712 + vertex 1.01203 1.60727 2.62703 + vertex 1.00894 1.60414 2.6286 + endloop + endfacet + facet normal 0.405243 0.038673 0.913391 + outer loop + vertex 1.00919 1.59901 2.6287 + vertex 1.01244 1.6022 2.62712 + vertex 1.00894 1.60414 2.6286 + endloop + endfacet + facet normal 0.395222 0.0507463 0.917183 + outer loop + vertex 1.01307 1.59664 2.62716 + vertex 1.01244 1.6022 2.62712 + vertex 1.00919 1.59901 2.6287 + endloop + endfacet + facet normal 0.386475 0.0335362 0.92169 + outer loop + vertex 1.00923 1.59397 2.62887 + vertex 1.01307 1.59664 2.62716 + vertex 1.00919 1.59901 2.6287 + endloop + endfacet + facet normal 0.390186 0.0273138 0.920331 + outer loop + vertex 1.01209 1.59202 2.62771 + vertex 1.01307 1.59664 2.62716 + vertex 1.00923 1.59397 2.62887 + endloop + endfacet + facet normal 0.39256 0.0314688 0.919188 + outer loop + vertex 1.00928 1.58918 2.62901 + vertex 1.01209 1.59202 2.62771 + vertex 1.00923 1.59397 2.62887 + endloop + endfacet + facet normal 0.37569 0.0509688 0.925343 + outer loop + vertex 1.01287 1.58792 2.62762 + vertex 1.01209 1.59202 2.62771 + vertex 1.00928 1.58918 2.62901 + endloop + endfacet + facet normal 0.37065 0.0335179 0.928168 + outer loop + vertex 1.00955 1.58433 2.62908 + vertex 1.01287 1.58792 2.62762 + vertex 1.00928 1.58918 2.62901 + endloop + endfacet + facet normal 0.355564 0.049605 0.933335 + outer loop + vertex 1.01342 1.58292 2.62768 + vertex 1.01287 1.58792 2.62762 + vertex 1.00955 1.58433 2.62908 + endloop + endfacet + facet normal 0.349275 0.0291557 0.936567 + outer loop + vertex 1.0097 1.5793 2.62918 + vertex 1.01342 1.58292 2.62768 + vertex 1.00955 1.58433 2.62908 + endloop + endfacet + facet normal 0.342736 0.0367658 0.938712 + outer loop + vertex 1.01353 1.57787 2.62783 + vertex 1.01342 1.58292 2.62768 + vertex 1.0097 1.5793 2.62918 + endloop + endfacet + facet normal 0.339585 0.02692 0.94019 + outer loop + vertex 1.00974 1.57427 2.62931 + vertex 1.01353 1.57787 2.62783 + vertex 1.0097 1.5793 2.62918 + endloop + endfacet + facet normal 0.332836 0.0349062 0.942339 + outer loop + vertex 1.01356 1.57306 2.628 + vertex 1.01353 1.57787 2.62783 + vertex 1.00974 1.57427 2.62931 + endloop + endfacet + facet normal 0.330555 0.0265136 0.943414 + outer loop + vertex 1.00977 1.56928 2.62944 + vertex 1.01356 1.57306 2.628 + vertex 1.00974 1.57427 2.62931 + endloop + endfacet + facet normal 0.317979 0.0405319 0.947231 + outer loop + vertex 1.01381 1.56824 2.62813 + vertex 1.01356 1.57306 2.628 + vertex 1.00977 1.56928 2.62944 + endloop + endfacet + facet normal 0.314991 0.0269745 0.948711 + outer loop + vertex 1.00982 1.56426 2.62956 + vertex 1.01381 1.56824 2.62813 + vertex 1.00977 1.56928 2.62944 + endloop + endfacet + facet normal 0.306719 0.0361305 0.951114 + outer loop + vertex 1.01393 1.56323 2.62828 + vertex 1.01381 1.56824 2.62813 + vertex 1.00982 1.56426 2.62956 + endloop + endfacet + facet normal 0.303784 0.0227272 0.95247 + outer loop + vertex 1.00981 1.55921 2.62969 + vertex 1.01393 1.56323 2.62828 + vertex 1.00982 1.56426 2.62956 + endloop + endfacet + facet normal 0.29906 0.0280314 0.953823 + outer loop + vertex 1.01393 1.5582 2.62843 + vertex 1.01393 1.56323 2.62828 + vertex 1.00981 1.55921 2.62969 + endloop + endfacet + facet normal 0.297591 0.0212455 0.954457 + outer loop + vertex 1.0098 1.55417 2.6298 + vertex 1.01393 1.5582 2.62843 + vertex 1.00981 1.55921 2.62969 + endloop + endfacet + facet normal 0.292763 0.0266462 0.955814 + outer loop + vertex 1.01393 1.5532 2.62856 + vertex 1.01393 1.5582 2.62843 + vertex 1.0098 1.55417 2.6298 + endloop + endfacet + facet normal 0.29097 0.018075 0.956561 + outer loop + vertex 1.00979 1.54913 2.6299 + vertex 1.01393 1.5532 2.62856 + vertex 1.0098 1.55417 2.6298 + endloop + endfacet + facet normal 0.285718 0.0239033 0.958016 + outer loop + vertex 1.01393 1.54817 2.62869 + vertex 1.01393 1.5532 2.62856 + vertex 1.00979 1.54913 2.6299 + endloop + endfacet + facet normal 0.284435 0.0177138 0.958532 + outer loop + vertex 1.00978 1.54411 2.63 + vertex 1.01393 1.54817 2.62869 + vertex 1.00979 1.54913 2.6299 + endloop + endfacet + facet normal 0.282383 0.0199952 0.959093 + outer loop + vertex 1.0139 1.54311 2.62881 + vertex 1.01393 1.54817 2.62869 + vertex 1.00978 1.54411 2.63 + endloop + endfacet + facet normal 0.281401 0.0154797 0.959465 + outer loop + vertex 1.00976 1.53909 2.63008 + vertex 1.0139 1.54311 2.62881 + vertex 1.00978 1.54411 2.63 + endloop + endfacet + facet normal 0.279709 0.0173624 0.959928 + outer loop + vertex 1.01384 1.53806 2.62891 + vertex 1.0139 1.54311 2.62881 + vertex 1.00976 1.53909 2.63008 + endloop + endfacet + facet normal 0.278381 0.0115656 0.960401 + outer loop + vertex 1.00976 1.53405 2.63014 + vertex 1.01384 1.53806 2.62891 + vertex 1.00976 1.53909 2.63008 + endloop + endfacet + facet normal 0.277696 0.0123196 0.96059 + outer loop + vertex 1.01379 1.53297 2.62899 + vertex 1.01384 1.53806 2.62891 + vertex 1.00976 1.53405 2.63014 + endloop + endfacet + facet normal 0.27672 0.00830998 0.960915 + outer loop + vertex 1.0098 1.52901 2.63018 + vertex 1.01379 1.53297 2.62899 + vertex 1.00976 1.53405 2.63014 + endloop + endfacet + facet normal 0.274781 0.0104171 0.96145 + outer loop + vertex 1.01376 1.52789 2.62906 + vertex 1.01379 1.53297 2.62899 + vertex 1.0098 1.52901 2.63018 + endloop + endfacet + facet normal 0.274268 0.00842311 0.961617 + outer loop + vertex 1.00983 1.524 2.63021 + vertex 1.01376 1.52789 2.62906 + vertex 1.0098 1.52901 2.63018 + endloop + endfacet + facet normal 0.274053 0.00865643 0.961676 + outer loop + vertex 1.01375 1.52284 2.6291 + vertex 1.01376 1.52789 2.62906 + vertex 1.00983 1.524 2.63021 + endloop + endfacet + facet normal 0.274085 0.00877395 0.961665 + outer loop + vertex 1.00988 1.51905 2.63024 + vertex 1.01375 1.52284 2.6291 + vertex 1.00983 1.524 2.63021 + endloop + endfacet + facet normal 0.276946 0.0056066 0.960869 + outer loop + vertex 1.01377 1.51782 2.62913 + vertex 1.01375 1.52284 2.6291 + vertex 1.00988 1.51905 2.63024 + endloop + endfacet + facet normal 0.276104 0.00271119 0.961124 + outer loop + vertex 1.00995 1.51414 2.63023 + vertex 1.01377 1.51782 2.62913 + vertex 1.00988 1.51905 2.63024 + endloop + endfacet + facet normal 0.275634 0.00323815 0.961257 + outer loop + vertex 1.0138 1.51287 2.62914 + vertex 1.01377 1.51782 2.62913 + vertex 1.00995 1.51414 2.63023 + endloop + endfacet + facet normal 0.274702 0.000193974 0.961529 + outer loop + vertex 1.01 1.50925 2.63022 + vertex 1.0138 1.51287 2.62914 + vertex 1.00995 1.51414 2.63023 + endloop + endfacet + facet normal 0.274098 0.000880909 0.961701 + outer loop + vertex 1.01382 1.50794 2.62913 + vertex 1.0138 1.51287 2.62914 + vertex 1.01 1.50925 2.63022 + endloop + endfacet + facet normal 0.274389 0.00179696 0.961617 + outer loop + vertex 1.00998 1.50431 2.63024 + vertex 1.01382 1.50794 2.62913 + vertex 1.01 1.50925 2.63022 + endloop + endfacet + facet normal 0.27592 4.32935e-05 0.961181 + outer loop + vertex 1.01384 1.503 2.62913 + vertex 1.01382 1.50794 2.62913 + vertex 1.00998 1.50431 2.63024 + endloop + endfacet + facet normal 0.275327 -0.00185123 0.961349 + outer loop + vertex 1.00995 1.49927 2.63024 + vertex 1.01384 1.503 2.62913 + vertex 1.00998 1.50431 2.63024 + endloop + endfacet + facet normal 0.27667 -0.00336546 0.960959 + outer loop + vertex 1.01383 1.49803 2.62911 + vertex 1.01384 1.503 2.62913 + vertex 1.00995 1.49927 2.63024 + endloop + endfacet + facet normal 0.276611 -0.00356476 0.960975 + outer loop + vertex 1.00993 1.49422 2.63022 + vertex 1.01383 1.49803 2.62911 + vertex 1.00995 1.49927 2.63024 + endloop + endfacet + facet normal 0.277416 -0.00445782 0.96074 + outer loop + vertex 1.01383 1.49305 2.62909 + vertex 1.01383 1.49803 2.62911 + vertex 1.00993 1.49422 2.63022 + endloop + endfacet + facet normal 0.277449 -0.00434059 0.960731 + outer loop + vertex 1.00993 1.4892 2.6302 + vertex 1.01383 1.49305 2.62909 + vertex 1.00993 1.49422 2.63022 + endloop + endfacet + facet normal 0.277369 -0.0042531 0.960754 + outer loop + vertex 1.01383 1.48808 2.62907 + vertex 1.01383 1.49305 2.62909 + vertex 1.00993 1.4892 2.6302 + endloop + endfacet + facet normal 0.277534 -0.00362862 0.960709 + outer loop + vertex 1.00992 1.4842 2.63019 + vertex 1.01383 1.48808 2.62907 + vertex 1.00993 1.4892 2.6302 + endloop + endfacet + facet normal 0.281441 -0.00790574 0.959546 + outer loop + vertex 1.01382 1.4831 2.62903 + vertex 1.01383 1.48808 2.62907 + vertex 1.00992 1.4842 2.63019 + endloop + endfacet + facet normal 0.282358 -0.0043798 0.959299 + outer loop + vertex 1.00991 1.47922 2.63017 + vertex 1.01382 1.4831 2.62903 + vertex 1.00992 1.4842 2.63019 + endloop + endfacet + facet normal 0.288767 -0.0114191 0.957331 + outer loop + vertex 1.0138 1.47812 2.62898 + vertex 1.01382 1.4831 2.62903 + vertex 1.00991 1.47922 2.63017 + endloop + endfacet + facet normal 0.289312 -0.00933761 0.957189 + outer loop + vertex 1.00988 1.47423 2.63012 + vertex 1.0138 1.47812 2.62898 + vertex 1.00991 1.47922 2.63017 + endloop + endfacet + facet normal 0.294836 -0.0154372 0.955423 + outer loop + vertex 1.01379 1.47312 2.6289 + vertex 1.0138 1.47812 2.62898 + vertex 1.00988 1.47423 2.63012 + endloop + endfacet + facet normal 0.295289 -0.0137187 0.95531 + outer loop + vertex 1.00985 1.46924 2.63006 + vertex 1.01379 1.47312 2.6289 + vertex 1.00988 1.47423 2.63012 + endloop + endfacet + facet normal 0.301089 -0.0201735 0.953382 + outer loop + vertex 1.01376 1.46811 2.62881 + vertex 1.01379 1.47312 2.6289 + vertex 1.00985 1.46924 2.63006 + endloop + endfacet + facet normal 0.301928 -0.0170403 0.953178 + outer loop + vertex 1.0098 1.46423 2.62999 + vertex 1.01376 1.46811 2.62881 + vertex 1.00985 1.46924 2.63006 + endloop + endfacet + facet normal 0.307231 -0.0230029 0.951357 + outer loop + vertex 1.01373 1.46309 2.62869 + vertex 1.01376 1.46811 2.62881 + vertex 1.0098 1.46423 2.62999 + endloop + endfacet + facet normal 0.308394 -0.0186776 0.951075 + outer loop + vertex 1.00975 1.45922 2.62991 + vertex 1.01373 1.46309 2.62869 + vertex 1.0098 1.46423 2.62999 + endloop + endfacet + facet normal 0.311089 -0.0217394 0.950132 + outer loop + vertex 1.01373 1.4581 2.62858 + vertex 1.01373 1.46309 2.62869 + vertex 1.00975 1.45922 2.62991 + endloop + endfacet + facet normal 0.312216 -0.0174007 0.949852 + outer loop + vertex 1.00973 1.45422 2.62982 + vertex 1.01373 1.4581 2.62858 + vertex 1.00975 1.45922 2.62991 + endloop + endfacet + facet normal 0.317193 -0.0231077 0.94808 + outer loop + vertex 1.01374 1.45312 2.62845 + vertex 1.01373 1.4581 2.62858 + vertex 1.00973 1.45422 2.62982 + endloop + endfacet + facet normal 0.318292 -0.0187445 0.947808 + outer loop + vertex 1.00971 1.44923 2.62973 + vertex 1.01374 1.45312 2.62845 + vertex 1.00973 1.45422 2.62982 + endloop + endfacet + facet normal 0.320019 -0.0207385 0.947184 + outer loop + vertex 1.01378 1.44819 2.62833 + vertex 1.01374 1.45312 2.62845 + vertex 1.00971 1.44923 2.62973 + endloop + endfacet + facet normal 0.320865 -0.0171417 0.94697 + outer loop + vertex 1.00972 1.44427 2.62964 + vertex 1.01378 1.44819 2.62833 + vertex 1.00971 1.44923 2.62973 + endloop + endfacet + facet normal 0.326475 -0.023648 0.94491 + outer loop + vertex 1.0138 1.44325 2.6282 + vertex 1.01378 1.44819 2.62833 + vertex 1.00972 1.44427 2.62964 + endloop + endfacet + facet normal 0.327489 -0.0192395 0.944659 + outer loop + vertex 1.00972 1.43931 2.62954 + vertex 1.0138 1.44325 2.6282 + vertex 1.00972 1.44427 2.62964 + endloop + endfacet + facet normal 0.333808 -0.0266004 0.942266 + outer loop + vertex 1.01379 1.43832 2.62807 + vertex 1.0138 1.44325 2.6282 + vertex 1.00972 1.43931 2.62954 + endloop + endfacet + facet normal 0.335223 -0.0202944 0.94192 + outer loop + vertex 1.00973 1.43437 2.62943 + vertex 1.01379 1.43832 2.62807 + vertex 1.00972 1.43931 2.62954 + endloop + endfacet + facet normal 0.343205 -0.0295775 0.938795 + outer loop + vertex 1.0138 1.43339 2.62791 + vertex 1.01379 1.43832 2.62807 + vertex 1.00973 1.43437 2.62943 + endloop + endfacet + facet normal 0.344479 -0.0238091 0.938492 + outer loop + vertex 1.0097 1.42943 2.62931 + vertex 1.0138 1.43339 2.62791 + vertex 1.00973 1.43437 2.62943 + endloop + endfacet + facet normal 0.358596 -0.0405126 0.932613 + outer loop + vertex 1.01363 1.42839 2.62775 + vertex 1.0138 1.43339 2.62791 + vertex 1.0097 1.42943 2.62931 + endloop + endfacet + facet normal 0.361612 -0.0280871 0.931905 + outer loop + vertex 1.00964 1.42452 2.62919 + vertex 1.01363 1.42839 2.62775 + vertex 1.0097 1.42943 2.62931 + endloop + endfacet + facet normal 0.379978 -0.0501038 0.923638 + outer loop + vertex 1.01339 1.42344 2.62758 + vertex 1.01363 1.42839 2.62775 + vertex 1.00964 1.42452 2.62919 + endloop + endfacet + facet normal 0.384865 -0.0313388 0.922441 + outer loop + vertex 1.00961 1.41958 2.62903 + vertex 1.01339 1.42344 2.62758 + vertex 1.00964 1.42452 2.62919 + endloop + endfacet + facet normal 0.396801 -0.0451433 0.916794 + outer loop + vertex 1.01363 1.41833 2.62723 + vertex 1.01339 1.42344 2.62758 + vertex 1.00961 1.41958 2.62903 + endloop + endfacet + facet normal 0.400828 -0.0304495 0.915647 + outer loop + vertex 1.00947 1.41451 2.62892 + vertex 1.01363 1.41833 2.62723 + vertex 1.00961 1.41958 2.62903 + endloop + endfacet + facet normal 0.413628 -0.0472034 0.909221 + outer loop + vertex 1.01282 1.41275 2.62731 + vertex 1.01363 1.41833 2.62723 + vertex 1.00947 1.41451 2.62892 + endloop + endfacet + facet normal 0.421294 -0.0300467 0.906426 + outer loop + vertex 1.00923 1.4094 2.62887 + vertex 1.01282 1.41275 2.62731 + vertex 1.00947 1.41451 2.62892 + endloop + endfacet + facet normal 0.428911 -0.0400858 0.902457 + outer loop + vertex 1.01249 1.40763 2.62724 + vertex 1.01282 1.41275 2.62731 + vertex 1.00923 1.4094 2.62887 + endloop + endfacet + facet normal 0.434716 -0.0272801 0.900154 + outer loop + vertex 1.00908 1.40438 2.62879 + vertex 1.01249 1.40763 2.62724 + vertex 1.00923 1.4094 2.62887 + endloop + endfacet + facet normal 0.473887 -0.0281014 0.880137 + outer loop + vertex 1.00908 1.40438 2.62879 + vertex 1.00923 1.4094 2.62887 + vertex 1.00583 1.40609 2.63059 + endloop + endfacet + facet normal 0.476775 -0.021172 0.878771 + outer loop + vertex 1.00576 1.40111 2.63051 + vertex 1.00908 1.40438 2.62879 + vertex 1.00583 1.40609 2.63059 + endloop + endfacet + facet normal 0.481549 -0.0212008 0.876163 + outer loop + vertex 1.00583 1.40609 2.63059 + vertex 1.00252 1.40278 2.63233 + vertex 1.00576 1.40111 2.63051 + endloop + endfacet + facet normal 0.482024 -0.0200247 0.875929 + outer loop + vertex 1.00252 1.40278 2.63233 + vertex 1.00245 1.39782 2.63225 + vertex 1.00576 1.40111 2.63051 + endloop + endfacet + facet normal 0.484251 -0.022947 0.874628 + outer loop + vertex 1.00576 1.40111 2.63051 + vertex 1.00245 1.39782 2.63225 + vertex 1.00568 1.39615 2.63043 + endloop + endfacet + facet normal 0.484018 -0.0229451 0.874757 + outer loop + vertex 1.00568 1.39615 2.63043 + vertex 1.00897 1.3994 2.62869 + vertex 1.00576 1.40111 2.63051 + endloop + endfacet + facet normal 0.489175 -0.0298241 0.871676 + outer loop + vertex 1.00886 1.39447 2.62858 + vertex 1.00897 1.3994 2.62869 + vertex 1.00568 1.39615 2.63043 + endloop + endfacet + facet normal 0.491277 -0.0247418 0.870652 + outer loop + vertex 1.0056 1.39122 2.63033 + vertex 1.00886 1.39447 2.62858 + vertex 1.00568 1.39615 2.63043 + endloop + endfacet + facet normal 0.486984 -0.0247264 0.873061 + outer loop + vertex 1.00568 1.39615 2.63043 + vertex 1.00237 1.39287 2.63218 + vertex 1.0056 1.39122 2.63033 + endloop + endfacet + facet normal 0.488058 -0.0220265 0.872533 + outer loop + vertex 1.00237 1.39287 2.63218 + vertex 1.00231 1.38794 2.63209 + vertex 1.0056 1.39122 2.63033 + endloop + endfacet + facet normal 0.490652 -0.025467 0.870983 + outer loop + vertex 1.0056 1.39122 2.63033 + vertex 1.00231 1.38794 2.63209 + vertex 1.00559 1.38624 2.63019 + endloop + endfacet + facet normal 0.499608 -0.0253439 0.865881 + outer loop + vertex 1.00559 1.38624 2.63019 + vertex 1.00882 1.38957 2.62842 + vertex 1.0056 1.39122 2.63033 + endloop + endfacet + facet normal 0.504464 -0.0316492 0.862853 + outer loop + vertex 1.00914 1.38434 2.62805 + vertex 1.00882 1.38957 2.62842 + vertex 1.00559 1.38624 2.63019 + endloop + endfacet + facet normal 0.507392 -0.0244954 0.861367 + outer loop + vertex 1.00547 1.38114 2.63011 + vertex 1.00914 1.38434 2.62805 + vertex 1.00559 1.38624 2.63019 + endloop + endfacet + facet normal 0.493461 -0.0242856 0.869429 + outer loop + vertex 1.00559 1.38624 2.63019 + vertex 1.00224 1.38299 2.632 + vertex 1.00547 1.38114 2.63011 + endloop + endfacet + facet normal 0.493829 -0.0234541 0.869242 + outer loop + vertex 1.00224 1.38299 2.632 + vertex 1.0021 1.37795 2.63194 + vertex 1.00547 1.38114 2.63011 + endloop + endfacet + facet normal 0.494499 -0.0243971 0.868836 + outer loop + vertex 1.00547 1.38114 2.63011 + vertex 1.0021 1.37795 2.63194 + vertex 1.00524 1.37601 2.6301 + endloop + endfacet + facet normal 0.510042 -0.0250896 0.859784 + outer loop + vertex 1.00524 1.37601 2.6301 + vertex 1.00851 1.37886 2.62824 + vertex 1.00547 1.38114 2.63011 + endloop + endfacet + facet normal 0.510741 -0.0261862 0.859336 + outer loop + vertex 1.00827 1.37379 2.62823 + vertex 1.00851 1.37886 2.62824 + vertex 1.00524 1.37601 2.6301 + endloop + endfacet + facet normal 0.510717 -0.0262304 0.859349 + outer loop + vertex 1.0051 1.37093 2.63003 + vertex 1.00827 1.37379 2.62823 + vertex 1.00524 1.37601 2.6301 + endloop + endfacet + facet normal 0.492011 -0.0258635 0.870205 + outer loop + vertex 1.00524 1.37601 2.6301 + vertex 1.00187 1.37275 2.63191 + vertex 1.0051 1.37093 2.63003 + endloop + endfacet + facet normal 0.490983 -0.0282025 0.870712 + outer loop + vertex 1.00187 1.37275 2.63191 + vertex 1.0018 1.36756 2.63178 + vertex 1.0051 1.37093 2.63003 + endloop + endfacet + facet normal 0.4893 -0.0260267 0.871727 + outer loop + vertex 1.0051 1.37093 2.63003 + vertex 1.0018 1.36756 2.63178 + vertex 1.00505 1.366 2.62991 + endloop + endfacet + facet normal 0.50947 -0.02592 0.860098 + outer loop + vertex 1.00505 1.366 2.62991 + vertex 1.00817 1.36879 2.62815 + vertex 1.0051 1.37093 2.63003 + endloop + endfacet + facet normal 0.507843 -0.0234452 0.86113 + outer loop + vertex 1.00799 1.36382 2.62812 + vertex 1.00817 1.36879 2.62815 + vertex 1.00505 1.366 2.62991 + endloop + endfacet + facet normal 0.506611 -0.025645 0.861793 + outer loop + vertex 1.00502 1.36174 2.6298 + vertex 1.00799 1.36382 2.62812 + vertex 1.00505 1.366 2.62991 + endloop + endfacet + facet normal 0.487056 -0.0257889 0.87299 + outer loop + vertex 1.00505 1.366 2.62991 + vertex 1.002 1.36261 2.63151 + vertex 1.00502 1.36174 2.6298 + endloop + endfacet + facet normal 0.486514 -0.0281229 0.87322 + outer loop + vertex 1.002 1.36261 2.63151 + vertex 1.00266 1.35759 2.63098 + vertex 1.00502 1.36174 2.6298 + endloop + endfacet + facet normal 0.494035 -0.0336647 0.86879 + outer loop + vertex 1.00266 1.35759 2.63098 + vertex 1.00718 1.35826 2.62844 + vertex 1.00502 1.36174 2.6298 + endloop + endfacet + facet normal 0.492433 -0.0176996 0.87017 + outer loop + vertex 1.00266 1.35759 2.63098 + vertex 1.00436 1.35389 2.62995 + vertex 1.00718 1.35826 2.62844 + endloop + endfacet + facet normal 0.499079 -0.0233477 0.866242 + outer loop + vertex 1.00718 1.35826 2.62844 + vertex 1.00436 1.35389 2.62995 + vertex 1.00775 1.35283 2.62796 + endloop + endfacet + facet normal 0.497194 -0.0236415 0.867317 + outer loop + vertex 1.00718 1.35826 2.62844 + vertex 1.00775 1.35283 2.62796 + vertex 1.01112 1.35629 2.62612 + endloop + endfacet + facet normal 0.497021 -0.0240889 0.867404 + outer loop + vertex 1.01116 1.36144 2.62624 + vertex 1.00718 1.35826 2.62844 + vertex 1.01112 1.35629 2.62612 + endloop + endfacet + facet normal 0.455461 -0.0242773 0.889925 + outer loop + vertex 1.01112 1.35629 2.62612 + vertex 1.01479 1.35965 2.62434 + vertex 1.01116 1.36144 2.62624 + endloop + endfacet + facet normal 0.451381 -0.0343746 0.891669 + outer loop + vertex 1.01479 1.35965 2.62434 + vertex 1.01484 1.36461 2.6245 + vertex 1.01116 1.36144 2.62624 + endloop + endfacet + facet normal 0.443079 -0.022245 0.896207 + outer loop + vertex 1.01116 1.36144 2.62624 + vertex 1.01484 1.36461 2.6245 + vertex 1.01132 1.36652 2.62629 + endloop + endfacet + facet normal 0.495028 -0.0235754 0.868557 + outer loop + vertex 1.01132 1.36652 2.62629 + vertex 1.00799 1.36382 2.62812 + vertex 1.01116 1.36144 2.62624 + endloop + endfacet + facet normal 0.439073 -0.031239 0.897908 + outer loop + vertex 1.01484 1.36461 2.6245 + vertex 1.01485 1.36955 2.62467 + vertex 1.01132 1.36652 2.62629 + endloop + endfacet + facet normal 0.434909 -0.0252128 0.900121 + outer loop + vertex 1.01132 1.36652 2.62629 + vertex 1.01485 1.36955 2.62467 + vertex 1.01138 1.3715 2.6264 + endloop + endfacet + facet normal 0.493478 -0.0252255 0.869392 + outer loop + vertex 1.01138 1.3715 2.6264 + vertex 1.00817 1.36879 2.62815 + vertex 1.01132 1.36652 2.62629 + endloop + endfacet + facet normal 0.493238 -0.0248474 0.869539 + outer loop + vertex 1.00827 1.37379 2.62823 + vertex 1.00817 1.36879 2.62815 + vertex 1.01138 1.3715 2.6264 + endloop + endfacet + facet normal 0.492466 -0.0262135 0.869937 + outer loop + vertex 1.01148 1.37645 2.6265 + vertex 1.00827 1.37379 2.62823 + vertex 1.01138 1.3715 2.6264 + endloop + endfacet + facet normal 0.426978 -0.0255575 0.903901 + outer loop + vertex 1.01138 1.3715 2.6264 + vertex 1.01484 1.3745 2.62485 + vertex 1.01148 1.37645 2.6265 + endloop + endfacet + facet normal 0.423808 -0.0320914 0.905183 + outer loop + vertex 1.01484 1.3745 2.62485 + vertex 1.01488 1.3794 2.62501 + vertex 1.01148 1.37645 2.6265 + endloop + endfacet + facet normal 0.41714 -0.0226684 0.908559 + outer loop + vertex 1.01148 1.37645 2.6265 + vertex 1.01488 1.3794 2.62501 + vertex 1.01174 1.38125 2.6265 + endloop + endfacet + facet normal 0.491019 -0.0267621 0.870738 + outer loop + vertex 1.01174 1.38125 2.6265 + vertex 1.00851 1.37886 2.62824 + vertex 1.01148 1.37645 2.6265 + endloop + endfacet + facet normal 0.489688 -0.0243731 0.871557 + outer loop + vertex 1.00914 1.38434 2.62805 + vertex 1.00851 1.37886 2.62824 + vertex 1.01174 1.38125 2.6265 + endloop + endfacet + facet normal 0.48708 -0.0272658 0.872932 + outer loop + vertex 1.01228 1.38496 2.62631 + vertex 1.00914 1.38434 2.62805 + vertex 1.01174 1.38125 2.6265 + endloop + endfacet + facet normal 0.402121 -0.0127705 0.915498 + outer loop + vertex 1.01486 1.38395 2.62516 + vertex 1.01228 1.38496 2.62631 + vertex 1.01174 1.38125 2.6265 + endloop + endfacet + facet normal 0.488673 -0.0390232 0.871594 + outer loop + vertex 1.01228 1.38496 2.62631 + vertex 1.01186 1.38831 2.6267 + vertex 1.00914 1.38434 2.62805 + endloop + endfacet + facet normal 0.413898 -0.029184 0.909855 + outer loop + vertex 1.01488 1.3794 2.62501 + vertex 1.01486 1.38395 2.62516 + vertex 1.01174 1.38125 2.6265 + endloop + endfacet + facet normal 0.431653 -0.0322175 0.901464 + outer loop + vertex 1.01485 1.36955 2.62467 + vertex 1.01484 1.3745 2.62485 + vertex 1.01138 1.3715 2.6264 + endloop + endfacet + facet normal 0.463976 -0.0361163 0.885111 + outer loop + vertex 1.01477 1.35466 2.62414 + vertex 1.01479 1.35965 2.62434 + vertex 1.01112 1.35629 2.62612 + endloop + endfacet + facet normal 0.467162 -0.0273192 0.88375 + outer loop + vertex 1.01119 1.3512 2.62593 + vertex 1.01477 1.35466 2.62414 + vertex 1.01112 1.35629 2.62612 + endloop + endfacet + facet normal 0.47666 -0.0400511 0.878175 + outer loop + vertex 1.01461 1.34957 2.624 + vertex 1.01477 1.35466 2.62414 + vertex 1.01119 1.3512 2.62593 + endloop + endfacet + facet normal 0.480836 -0.0291079 0.876327 + outer loop + vertex 1.0111 1.34618 2.62581 + vertex 1.01461 1.34957 2.624 + vertex 1.01119 1.3512 2.62593 + endloop + endfacet + facet normal 0.502265 -0.0292081 0.86422 + outer loop + vertex 1.01119 1.3512 2.62593 + vertex 1.00786 1.34783 2.62775 + vertex 1.0111 1.34618 2.62581 + endloop + endfacet + facet normal 0.503417 -0.0262773 0.863644 + outer loop + vertex 1.00786 1.34783 2.62775 + vertex 1.00779 1.34283 2.62764 + vertex 1.0111 1.34618 2.62581 + endloop + endfacet + facet normal 0.50579 -0.0294424 0.862154 + outer loop + vertex 1.0111 1.34618 2.62581 + vertex 1.00779 1.34283 2.62764 + vertex 1.01095 1.34118 2.62573 + endloop + endfacet + facet normal 0.496129 -0.0292557 0.867756 + outer loop + vertex 1.01095 1.34118 2.62573 + vertex 1.0143 1.34449 2.62393 + vertex 1.0111 1.34618 2.62581 + endloop + endfacet + facet normal 0.502931 -0.0384735 0.86347 + outer loop + vertex 1.0141 1.33949 2.62382 + vertex 1.0143 1.34449 2.62393 + vertex 1.01095 1.34118 2.62573 + endloop + endfacet + facet normal 0.506795 -0.0291369 0.861574 + outer loop + vertex 1.01085 1.3362 2.62562 + vertex 1.0141 1.33949 2.62382 + vertex 1.01095 1.34118 2.62573 + endloop + endfacet + facet normal 0.508811 -0.0291507 0.860384 + outer loop + vertex 1.01095 1.34118 2.62573 + vertex 1.00768 1.33784 2.62755 + vertex 1.01085 1.3362 2.62562 + endloop + endfacet + facet normal 0.509266 -0.0280002 0.860153 + outer loop + vertex 1.00768 1.33784 2.62755 + vertex 1.0076 1.33287 2.62744 + vertex 1.01085 1.3362 2.62562 + endloop + endfacet + facet normal 0.511746 -0.0312971 0.858566 + outer loop + vertex 1.01085 1.3362 2.62562 + vertex 1.0076 1.33287 2.62744 + vertex 1.01082 1.33117 2.62545 + endloop + endfacet + facet normal 0.517977 -0.0312126 0.854825 + outer loop + vertex 1.01082 1.33117 2.62545 + vertex 1.01402 1.33452 2.62364 + vertex 1.01085 1.3362 2.62562 + endloop + endfacet + facet normal 0.524247 -0.0394555 0.850652 + outer loop + vertex 1.0143 1.32922 2.62322 + vertex 1.01402 1.33452 2.62364 + vertex 1.01082 1.33117 2.62545 + endloop + endfacet + facet normal 0.527724 -0.0311796 0.848844 + outer loop + vertex 1.01069 1.32609 2.62535 + vertex 1.0143 1.32922 2.62322 + vertex 1.01082 1.33117 2.62545 + endloop + endfacet + facet normal 0.514008 -0.0309791 0.857226 + outer loop + vertex 1.01082 1.33117 2.62545 + vertex 1.00752 1.32793 2.62732 + vertex 1.01069 1.32609 2.62535 + endloop + endfacet + facet normal 0.514687 -0.0294389 0.856873 + outer loop + vertex 1.00752 1.32793 2.62732 + vertex 1.00743 1.32301 2.6272 + vertex 1.01069 1.32609 2.62535 + endloop + endfacet + facet normal 0.514529 -0.0292094 0.856975 + outer loop + vertex 1.01069 1.32609 2.62535 + vertex 1.00743 1.32301 2.6272 + vertex 1.01047 1.32107 2.62531 + endloop + endfacet + facet normal 0.532351 -0.0298867 0.845996 + outer loop + vertex 1.01047 1.32107 2.62531 + vertex 1.01365 1.32379 2.62341 + vertex 1.01069 1.32609 2.62535 + endloop + endfacet + facet normal 0.531939 -0.0292085 0.846279 + outer loop + vertex 1.01341 1.31882 2.62339 + vertex 1.01365 1.32379 2.62341 + vertex 1.01047 1.32107 2.62531 + endloop + endfacet + facet normal 0.531862 -0.0293465 0.846322 + outer loop + vertex 1.01035 1.31612 2.62522 + vertex 1.01341 1.31882 2.62339 + vertex 1.01047 1.32107 2.62531 + endloop + endfacet + facet normal 0.512084 -0.0290713 0.858444 + outer loop + vertex 1.01047 1.32107 2.62531 + vertex 1.00732 1.31808 2.62709 + vertex 1.01035 1.31612 2.62522 + endloop + endfacet + facet normal 0.509552 -0.0342136 0.859759 + outer loop + vertex 1.00732 1.31808 2.62709 + vertex 1.00718 1.31307 2.62697 + vertex 1.01035 1.31612 2.62522 + endloop + endfacet + facet normal 0.507271 -0.0309923 0.861229 + outer loop + vertex 1.01035 1.31612 2.62522 + vertex 1.00718 1.31307 2.62697 + vertex 1.01023 1.3111 2.62511 + endloop + endfacet + facet normal 0.527689 -0.0312004 0.848864 + outer loop + vertex 1.01023 1.3111 2.62511 + vertex 1.01333 1.31389 2.62328 + vertex 1.01035 1.31612 2.62522 + endloop + endfacet + facet normal 0.524635 -0.0264555 0.850916 + outer loop + vertex 1.01325 1.30892 2.62317 + vertex 1.01333 1.31389 2.62328 + vertex 1.01023 1.3111 2.62511 + endloop + endfacet + facet normal 0.52175 -0.0318637 0.852503 + outer loop + vertex 1.01006 1.30607 2.62502 + vertex 1.01325 1.30892 2.62317 + vertex 1.01023 1.3111 2.62511 + endloop + endfacet + facet normal 0.497777 -0.0313107 0.86674 + outer loop + vertex 1.01023 1.3111 2.62511 + vertex 1.00692 1.3079 2.62689 + vertex 1.01006 1.30607 2.62502 + endloop + endfacet + facet normal 0.494955 -0.0375472 0.868107 + outer loop + vertex 1.00692 1.3079 2.62689 + vertex 1.00675 1.30282 2.62676 + vertex 1.01006 1.30607 2.62502 + endloop + endfacet + facet normal 0.489055 -0.0295965 0.871751 + outer loop + vertex 1.01006 1.30607 2.62502 + vertex 1.00675 1.30282 2.62676 + vertex 1.00979 1.30122 2.62501 + endloop + endfacet + facet normal 0.515956 -0.031024 0.856053 + outer loop + vertex 1.00979 1.30122 2.62501 + vertex 1.01305 1.30386 2.62314 + vertex 1.01006 1.30607 2.62502 + endloop + endfacet + facet normal 0.51347 -0.0267862 0.85769 + outer loop + vertex 1.01246 1.29831 2.62332 + vertex 1.01305 1.30386 2.62314 + vertex 1.00979 1.30122 2.62501 + endloop + endfacet + facet normal 0.509922 -0.0311674 0.859656 + outer loop + vertex 1.00927 1.29747 2.62518 + vertex 1.01246 1.29831 2.62332 + vertex 1.00979 1.30122 2.62501 + endloop + endfacet + facet normal 0.510265 -0.0330728 0.859381 + outer loop + vertex 1.00927 1.29747 2.62518 + vertex 1.00975 1.29413 2.62477 + vertex 1.01246 1.29831 2.62332 + endloop + endfacet + facet normal 0.506625 -0.0299254 0.861647 + outer loop + vertex 1.01246 1.29831 2.62332 + vertex 1.00975 1.29413 2.62477 + vertex 1.01283 1.29298 2.62291 + endloop + endfacet + facet normal 0.520825 -0.0282983 0.853194 + outer loop + vertex 1.01246 1.29831 2.62332 + vertex 1.01283 1.29298 2.62291 + vertex 1.01608 1.29645 2.62105 + endloop + endfacet + facet normal 0.52031 -0.0296316 0.853463 + outer loop + vertex 1.01622 1.30165 2.62115 + vertex 1.01246 1.29831 2.62332 + vertex 1.01608 1.29645 2.62105 + endloop + endfacet + facet normal 0.502091 -0.0293426 0.864317 + outer loop + vertex 1.01608 1.29645 2.62105 + vertex 1.01959 1.2998 2.61912 + vertex 1.01622 1.30165 2.62115 + endloop + endfacet + facet normal 0.496288 -0.0429688 0.867094 + outer loop + vertex 1.01959 1.2998 2.61912 + vertex 1.0198 1.30492 2.61926 + vertex 1.01622 1.30165 2.62115 + endloop + endfacet + facet normal 0.485811 -0.0277061 0.873625 + outer loop + vertex 1.01622 1.30165 2.62115 + vertex 1.0198 1.30492 2.61926 + vertex 1.01639 1.30674 2.62121 + endloop + endfacet + facet normal 0.518331 -0.0286067 0.854701 + outer loop + vertex 1.01639 1.30674 2.62121 + vertex 1.01305 1.30386 2.62314 + vertex 1.01622 1.30165 2.62115 + endloop + endfacet + facet normal 0.517063 -0.0265816 0.855535 + outer loop + vertex 1.01325 1.30892 2.62317 + vertex 1.01305 1.30386 2.62314 + vertex 1.01639 1.30674 2.62121 + endloop + endfacet + facet normal 0.516386 -0.0278904 0.855902 + outer loop + vertex 1.01645 1.31168 2.62134 + vertex 1.01325 1.30892 2.62317 + vertex 1.01639 1.30674 2.62121 + endloop + endfacet + facet normal 0.470662 -0.0280661 0.881867 + outer loop + vertex 1.01639 1.30674 2.62121 + vertex 1.01985 1.30985 2.61946 + vertex 1.01645 1.31168 2.62134 + endloop + endfacet + facet normal 0.464879 -0.0414353 0.884404 + outer loop + vertex 1.01985 1.30985 2.61946 + vertex 1.0199 1.31471 2.61966 + vertex 1.01645 1.31168 2.62134 + endloop + endfacet + facet normal 0.456154 -0.0287323 0.889437 + outer loop + vertex 1.01645 1.31168 2.62134 + vertex 1.0199 1.31471 2.61966 + vertex 1.01647 1.31657 2.62148 + endloop + endfacet + facet normal 0.514631 -0.0280382 0.856953 + outer loop + vertex 1.01647 1.31657 2.62148 + vertex 1.01333 1.31389 2.62328 + vertex 1.01645 1.31168 2.62134 + endloop + endfacet + facet normal 0.51374 -0.0266055 0.857534 + outer loop + vertex 1.01341 1.31882 2.62339 + vertex 1.01333 1.31389 2.62328 + vertex 1.01647 1.31657 2.62148 + endloop + endfacet + facet normal 0.512263 -0.0292846 0.858329 + outer loop + vertex 1.01657 1.32142 2.62159 + vertex 1.01341 1.31882 2.62339 + vertex 1.01647 1.31657 2.62148 + endloop + endfacet + facet normal 0.446748 -0.0287928 0.894197 + outer loop + vertex 1.01647 1.31657 2.62148 + vertex 1.01992 1.31957 2.61986 + vertex 1.01657 1.32142 2.62159 + endloop + endfacet + facet normal 0.44223 -0.0387027 0.896066 + outer loop + vertex 1.01992 1.31957 2.61986 + vertex 1.01997 1.32437 2.62004 + vertex 1.01657 1.32142 2.62159 + endloop + endfacet + facet normal 0.434137 -0.0270694 0.90044 + outer loop + vertex 1.01657 1.32142 2.62159 + vertex 1.01997 1.32437 2.62004 + vertex 1.01684 1.32613 2.6216 + endloop + endfacet + facet normal 0.509739 -0.0314929 0.859753 + outer loop + vertex 1.01684 1.32613 2.6216 + vertex 1.01365 1.32379 2.62341 + vertex 1.01657 1.32142 2.62159 + endloop + endfacet + facet normal 0.509818 -0.0316416 0.8597 + outer loop + vertex 1.0143 1.32922 2.62322 + vertex 1.01365 1.32379 2.62341 + vertex 1.01684 1.32613 2.6216 + endloop + endfacet + facet normal 0.505464 -0.0364703 0.862077 + outer loop + vertex 1.01741 1.3298 2.62142 + vertex 1.0143 1.32922 2.62322 + vertex 1.01684 1.32613 2.6216 + endloop + endfacet + facet normal 0.418813 -0.0208532 0.907833 + outer loop + vertex 1.01996 1.32884 2.62022 + vertex 1.01741 1.3298 2.62142 + vertex 1.01684 1.32613 2.6216 + endloop + endfacet + facet normal 0.50675 -0.0474631 0.860785 + outer loop + vertex 1.01741 1.3298 2.62142 + vertex 1.01702 1.33319 2.62184 + vertex 1.0143 1.32922 2.62322 + endloop + endfacet + facet normal 0.429803 -0.0363514 0.902191 + outer loop + vertex 1.01997 1.32437 2.62004 + vertex 1.01996 1.32884 2.62022 + vertex 1.01684 1.32613 2.6216 + endloop + endfacet + facet normal 0.452474 -0.0370976 0.891006 + outer loop + vertex 1.0199 1.31471 2.61966 + vertex 1.01992 1.31957 2.61986 + vertex 1.01647 1.31657 2.62148 + endloop + endfacet + facet normal 0.479946 -0.0415441 0.876314 + outer loop + vertex 1.0198 1.30492 2.61926 + vertex 1.01985 1.30985 2.61946 + vertex 1.01639 1.30674 2.62121 + endloop + endfacet + facet normal 0.510958 -0.0419512 0.858581 + outer loop + vertex 1.01931 1.29463 2.61904 + vertex 1.01959 1.2998 2.61912 + vertex 1.01608 1.29645 2.62105 + endloop + endfacet + facet normal 0.516173 -0.0297929 0.855966 + outer loop + vertex 1.01604 1.29132 2.6209 + vertex 1.01931 1.29463 2.61904 + vertex 1.01608 1.29645 2.62105 + endloop + endfacet + facet normal 0.523806 -0.0402074 0.850888 + outer loop + vertex 1.01914 1.28957 2.6189 + vertex 1.01931 1.29463 2.61904 + vertex 1.01604 1.29132 2.6209 + endloop + endfacet + facet normal 0.526993 -0.0326917 0.849241 + outer loop + vertex 1.01597 1.28629 2.62075 + vertex 1.01914 1.28957 2.6189 + vertex 1.01604 1.29132 2.6209 + endloop + endfacet + facet normal 0.523234 -0.0327086 0.851561 + outer loop + vertex 1.01604 1.29132 2.6209 + vertex 1.01283 1.28796 2.62274 + vertex 1.01597 1.28629 2.62075 + endloop + endfacet + facet normal 0.521697 -0.0365381 0.852348 + outer loop + vertex 1.01283 1.28796 2.62274 + vertex 1.01274 1.28297 2.62258 + vertex 1.01597 1.28629 2.62075 + endloop + endfacet + facet normal 0.524108 -0.0397812 0.850722 + outer loop + vertex 1.01597 1.28629 2.62075 + vertex 1.01274 1.28297 2.62258 + vertex 1.0159 1.28125 2.62055 + endloop + endfacet + facet normal 0.536445 -0.0396528 0.843003 + outer loop + vertex 1.0159 1.28125 2.62055 + vertex 1.01905 1.28458 2.6187 + vertex 1.01597 1.28629 2.62075 + endloop + endfacet + facet normal 0.540222 -0.0447194 0.840334 + outer loop + vertex 1.01929 1.2793 2.61827 + vertex 1.01905 1.28458 2.6187 + vertex 1.0159 1.28125 2.62055 + endloop + endfacet + facet normal 0.541719 -0.0411944 0.83955 + outer loop + vertex 1.01571 1.27617 2.62043 + vertex 1.01929 1.2793 2.61827 + vertex 1.0159 1.28125 2.62055 + endloop + endfacet + facet normal 0.521554 -0.0407517 0.852244 + outer loop + vertex 1.0159 1.28125 2.62055 + vertex 1.0126 1.27802 2.62242 + vertex 1.01571 1.27617 2.62043 + endloop + endfacet + facet normal 0.52126 -0.0414068 0.852393 + outer loop + vertex 1.0126 1.27802 2.62242 + vertex 1.01243 1.27309 2.62228 + vertex 1.01571 1.27617 2.62043 + endloop + endfacet + facet normal 0.512294 -0.0282935 0.858344 + outer loop + vertex 1.01571 1.27617 2.62043 + vertex 1.01243 1.27309 2.62228 + vertex 1.01549 1.27111 2.62039 + endloop + endfacet + facet normal 0.53689 -0.0292057 0.843146 + outer loop + vertex 1.01549 1.27111 2.62039 + vertex 1.01866 1.27387 2.61846 + vertex 1.01571 1.27617 2.62043 + endloop + endfacet + facet normal 0.524603 -0.00944295 0.851295 + outer loop + vertex 1.0186 1.26876 2.61844 + vertex 1.01866 1.27387 2.61846 + vertex 1.01549 1.27111 2.62039 + endloop + endfacet + facet normal 0.525574 -0.00767594 0.850713 + outer loop + vertex 1.01548 1.266 2.62035 + vertex 1.0186 1.26876 2.61844 + vertex 1.01549 1.27111 2.62039 + endloop + endfacet + facet normal 0.499458 -0.00775399 0.866304 + outer loop + vertex 1.01549 1.27111 2.62039 + vertex 1.01232 1.26814 2.62219 + vertex 1.01548 1.266 2.62035 + endloop + endfacet + facet normal 0.50056 -0.00558183 0.865684 + outer loop + vertex 1.01232 1.26814 2.62219 + vertex 1.01229 1.26315 2.62218 + vertex 1.01548 1.266 2.62035 + endloop + endfacet + facet normal 0.488822 0.0118222 0.872303 + outer loop + vertex 1.01548 1.266 2.62035 + vertex 1.01229 1.26315 2.62218 + vertex 1.01541 1.26101 2.62045 + endloop + endfacet + facet normal 0.512004 0.0111961 0.85891 + outer loop + vertex 1.01541 1.26101 2.62045 + vertex 1.01896 1.26317 2.61831 + vertex 1.01548 1.266 2.62035 + endloop + endfacet + facet normal 0.512663 0.0122978 0.858502 + outer loop + vertex 1.01896 1.26317 2.61831 + vertex 1.0186 1.26876 2.61844 + vertex 1.01548 1.266 2.62035 + endloop + endfacet + facet normal 0.508883 0.0119996 0.860752 + outer loop + vertex 1.0186 1.26876 2.61844 + vertex 1.01896 1.26317 2.61831 + vertex 1.02194 1.26662 2.6165 + endloop + endfacet + facet normal 0.505964 0.00582592 0.862535 + outer loop + vertex 1.02169 1.27154 2.61661 + vertex 1.0186 1.26876 2.61844 + vertex 1.02194 1.26662 2.6165 + endloop + endfacet + facet normal 0.457385 0.00275617 0.889265 + outer loop + vertex 1.02194 1.26662 2.6165 + vertex 1.02517 1.26971 2.61483 + vertex 1.02169 1.27154 2.61661 + endloop + endfacet + facet normal 0.452003 -0.0100856 0.891959 + outer loop + vertex 1.02517 1.26971 2.61483 + vertex 1.02499 1.27454 2.61497 + vertex 1.02169 1.27154 2.61661 + endloop + endfacet + facet normal 0.455781 0.00486963 0.890078 + outer loop + vertex 1.02567 1.26446 2.6146 + vertex 1.02517 1.26971 2.61483 + vertex 1.02194 1.26662 2.6165 + endloop + endfacet + facet normal 0.45828 0.0103372 0.888748 + outer loop + vertex 1.02238 1.26249 2.61632 + vertex 1.02567 1.26446 2.6146 + vertex 1.02194 1.26662 2.6165 + endloop + endfacet + facet normal 0.505093 0.0163968 0.862909 + outer loop + vertex 1.02194 1.26662 2.6165 + vertex 1.01896 1.26317 2.61831 + vertex 1.02238 1.26249 2.61632 + endloop + endfacet + facet normal 0.505526 0.0253443 0.862439 + outer loop + vertex 1.01795 1.25872 2.61903 + vertex 1.01896 1.26317 2.61831 + vertex 1.01541 1.26101 2.62045 + endloop + endfacet + facet normal 0.499891 0.0169402 0.865923 + outer loop + vertex 1.0154 1.25625 2.62055 + vertex 1.01795 1.25872 2.61903 + vertex 1.01541 1.26101 2.62045 + endloop + endfacet + facet normal 0.481755 0.0171863 0.876137 + outer loop + vertex 1.01541 1.26101 2.62045 + vertex 1.0123 1.25817 2.62222 + vertex 1.0154 1.25625 2.62055 + endloop + endfacet + facet normal 0.476816 0.00676901 0.878977 + outer loop + vertex 1.0123 1.25817 2.62222 + vertex 1.01234 1.25319 2.62224 + vertex 1.0154 1.25625 2.62055 + endloop + endfacet + facet normal 0.478813 0.00417416 0.877907 + outer loop + vertex 1.0154 1.25625 2.62055 + vertex 1.01234 1.25319 2.62224 + vertex 1.01558 1.25141 2.62048 + endloop + endfacet + facet normal 0.496902 0.00500844 0.867792 + outer loop + vertex 1.01558 1.25141 2.62048 + vertex 1.01854 1.2546 2.61877 + vertex 1.0154 1.25625 2.62055 + endloop + endfacet + facet normal 0.50097 0.0154615 0.865327 + outer loop + vertex 1.01854 1.2546 2.61877 + vertex 1.01795 1.25872 2.61903 + vertex 1.0154 1.25625 2.62055 + endloop + endfacet + facet normal 0.508233 0.0167792 0.861056 + outer loop + vertex 1.01854 1.2546 2.61877 + vertex 1.02128 1.25833 2.61707 + vertex 1.01795 1.25872 2.61903 + endloop + endfacet + facet normal 0.510239 0.0147783 0.859906 + outer loop + vertex 1.02181 1.2531 2.61685 + vertex 1.02128 1.25833 2.61707 + vertex 1.01854 1.2546 2.61877 + endloop + endfacet + facet normal 0.505922 0.00197114 0.862577 + outer loop + vertex 1.0189 1.24977 2.61857 + vertex 1.02181 1.2531 2.61685 + vertex 1.01854 1.2546 2.61877 + endloop + endfacet + facet normal 0.49985 0.0013768 0.866111 + outer loop + vertex 1.0189 1.24977 2.61857 + vertex 1.01854 1.2546 2.61877 + vertex 1.01558 1.25141 2.62048 + endloop + endfacet + facet normal 0.494633 -0.0124962 0.869012 + outer loop + vertex 1.0157 1.24635 2.62034 + vertex 1.0189 1.24977 2.61857 + vertex 1.01558 1.25141 2.62048 + endloop + endfacet + facet normal 0.475704 -0.0132099 0.879506 + outer loop + vertex 1.01558 1.25141 2.62048 + vertex 1.0123 1.24812 2.6222 + vertex 1.0157 1.24635 2.62034 + endloop + endfacet + facet normal 0.469698 -0.0277536 0.882391 + outer loop + vertex 1.0123 1.24812 2.6222 + vertex 1.01211 1.24289 2.62214 + vertex 1.0157 1.24635 2.62034 + endloop + endfacet + facet normal 0.467882 -0.0253349 0.883428 + outer loop + vertex 1.0157 1.24635 2.62034 + vertex 1.01211 1.24289 2.62214 + vertex 1.01562 1.24115 2.62023 + endloop + endfacet + facet normal 0.493628 -0.0254527 0.869301 + outer loop + vertex 1.01562 1.24115 2.62023 + vertex 1.01943 1.24458 2.61817 + vertex 1.0157 1.24635 2.62034 + endloop + endfacet + facet normal 0.489591 -0.0195012 0.871734 + outer loop + vertex 1.01886 1.23911 2.61836 + vertex 1.01943 1.24458 2.61817 + vertex 1.01562 1.24115 2.62023 + endloop + endfacet + facet normal 0.484474 -0.0300008 0.874291 + outer loop + vertex 1.01538 1.23598 2.62019 + vertex 1.01886 1.23911 2.61836 + vertex 1.01562 1.24115 2.62023 + endloop + endfacet + facet normal 0.455244 -0.028786 0.889901 + outer loop + vertex 1.01562 1.24115 2.62023 + vertex 1.01194 1.2376 2.622 + vertex 1.01538 1.23598 2.62019 + endloop + endfacet + facet normal 0.45085 -0.0400517 0.891701 + outer loop + vertex 1.01194 1.2376 2.622 + vertex 1.01188 1.23257 2.6218 + vertex 1.01538 1.23598 2.62019 + endloop + endfacet + facet normal 0.442534 -0.0293604 0.896271 + outer loop + vertex 1.01538 1.23598 2.62019 + vertex 1.01188 1.23257 2.6218 + vertex 1.01498 1.23101 2.62022 + endloop + endfacet + facet normal 0.474649 -0.0320046 0.879593 + outer loop + vertex 1.01498 1.23101 2.62022 + vertex 1.01847 1.2339 2.61844 + vertex 1.01538 1.23598 2.62019 + endloop + endfacet + facet normal 0.469641 -0.0241764 0.882527 + outer loop + vertex 1.01755 1.22801 2.61877 + vertex 1.01847 1.2339 2.61844 + vertex 1.01498 1.23101 2.62022 + endloop + endfacet + facet normal 0.461099 -0.0335197 0.886715 + outer loop + vertex 1.0141 1.22706 2.62053 + vertex 1.01755 1.22801 2.61877 + vertex 1.01498 1.23101 2.62022 + endloop + endfacet + facet normal 0.430859 -0.0254827 0.90206 + outer loop + vertex 1.01498 1.23101 2.62022 + vertex 1.01184 1.22813 2.62164 + vertex 1.0141 1.22706 2.62053 + endloop + endfacet + facet normal 0.429221 -0.0296268 0.902714 + outer loop + vertex 1.0141 1.22706 2.62053 + vertex 1.01184 1.22813 2.62164 + vertex 1.01217 1.22543 2.62139 + endloop + endfacet + facet normal 0.399542 -0.034498 0.916065 + outer loop + vertex 1.01217 1.22543 2.62139 + vertex 1.01184 1.22813 2.62164 + vertex 1.00909 1.22398 2.62268 + endloop + endfacet + facet normal 0.405784 -0.050849 0.912553 + outer loop + vertex 1.01217 1.22543 2.62139 + vertex 1.00909 1.22398 2.62268 + vertex 1.0134 1.22263 2.62069 + endloop + endfacet + facet normal 0.408481 -0.0411812 0.911837 + outer loop + vertex 1.00909 1.22398 2.62268 + vertex 1.00835 1.21825 2.62275 + vertex 1.0134 1.22263 2.62069 + endloop + endfacet + facet normal 0.395545 -0.0232943 0.918151 + outer loop + vertex 1.0134 1.22263 2.62069 + vertex 1.00835 1.21825 2.62275 + vertex 1.01192 1.2165 2.62117 + endloop + endfacet + facet normal 0.418765 -0.0297249 0.907608 + outer loop + vertex 1.01192 1.2165 2.62117 + vertex 1.01542 1.21894 2.61964 + vertex 1.0134 1.22263 2.62069 + endloop + endfacet + facet normal 0.443058 -0.0132404 0.896395 + outer loop + vertex 1.01542 1.21894 2.61964 + vertex 1.01805 1.22263 2.61839 + vertex 1.0134 1.22263 2.62069 + endloop + endfacet + facet normal 0.442996 -0.0219063 0.896256 + outer loop + vertex 1.01755 1.22801 2.61877 + vertex 1.0134 1.22263 2.62069 + vertex 1.01805 1.22263 2.61839 + endloop + endfacet + facet normal 0.486554 -0.0162923 0.873498 + outer loop + vertex 1.01755 1.22801 2.61877 + vertex 1.01805 1.22263 2.61839 + vertex 1.02144 1.22647 2.61658 + endloop + endfacet + facet normal 0.487596 -0.012913 0.872974 + outer loop + vertex 1.02155 1.23175 2.61659 + vertex 1.01755 1.22801 2.61877 + vertex 1.02144 1.22647 2.61658 + endloop + endfacet + facet normal 0.52364 -0.0136046 0.851831 + outer loop + vertex 1.02144 1.22647 2.61658 + vertex 1.02467 1.22981 2.61464 + vertex 1.02155 1.23175 2.61659 + endloop + endfacet + facet normal 0.517526 -0.00547469 0.85565 + outer loop + vertex 1.02465 1.22474 2.61462 + vertex 1.02467 1.22981 2.61464 + vertex 1.02144 1.22647 2.61658 + endloop + endfacet + facet normal 0.515219 -0.0112829 0.856984 + outer loop + vertex 1.02151 1.22137 2.61647 + vertex 1.02465 1.22474 2.61462 + vertex 1.02144 1.22647 2.61658 + endloop + endfacet + facet normal 0.526491 -0.00549882 0.850163 + outer loop + vertex 1.02465 1.22474 2.61462 + vertex 1.02772 1.22794 2.61274 + vertex 1.02467 1.22981 2.61464 + endloop + endfacet + facet normal 0.525004 -0.00882627 0.851054 + outer loop + vertex 1.02772 1.22794 2.61274 + vertex 1.02774 1.23291 2.61278 + vertex 1.02467 1.22981 2.61464 + endloop + endfacet + facet normal 0.524069 -0.00228097 0.851673 + outer loop + vertex 1.02772 1.22297 2.61273 + vertex 1.02772 1.22794 2.61274 + vertex 1.02465 1.22474 2.61462 + endloop + endfacet + facet normal 0.494649 -0.00230642 0.86909 + outer loop + vertex 1.02772 1.22794 2.61274 + vertex 1.02772 1.22297 2.61273 + vertex 1.03095 1.22626 2.6109 + endloop + endfacet + facet normal 0.490509 -0.0127172 0.871343 + outer loop + vertex 1.03093 1.23117 2.61098 + vertex 1.02772 1.22794 2.61274 + vertex 1.03095 1.22626 2.6109 + endloop + endfacet + facet normal 0.428251 -0.0134039 0.90356 + outer loop + vertex 1.03095 1.22626 2.6109 + vertex 1.03448 1.22977 2.60928 + vertex 1.03093 1.23117 2.61098 + endloop + endfacet + facet normal 0.439144 -0.0269325 0.898013 + outer loop + vertex 1.03451 1.22484 2.60912 + vertex 1.03448 1.22977 2.60928 + vertex 1.03095 1.22626 2.6109 + endloop + endfacet + facet normal 0.445068 -0.00887367 0.895453 + outer loop + vertex 1.03095 1.22133 2.61085 + vertex 1.03451 1.22484 2.60912 + vertex 1.03095 1.22626 2.6109 + endloop + endfacet + facet normal 0.458643 -0.0262313 0.888233 + outer loop + vertex 1.03441 1.21977 2.60902 + vertex 1.03451 1.22484 2.60912 + vertex 1.03095 1.22133 2.61085 + endloop + endfacet + facet normal 0.4876 -0.00891475 0.873022 + outer loop + vertex 1.02774 1.23291 2.61278 + vertex 1.02772 1.22794 2.61274 + vertex 1.03093 1.23117 2.61098 + endloop + endfacet + facet normal 0.481274 -0.0239069 0.876244 + outer loop + vertex 1.03097 1.2361 2.6111 + vertex 1.02774 1.23291 2.61278 + vertex 1.03093 1.23117 2.61098 + endloop + endfacet + facet normal 0.41005 -0.0242676 0.91174 + outer loop + vertex 1.03093 1.23117 2.61098 + vertex 1.03453 1.23469 2.60946 + vertex 1.03097 1.2361 2.6111 + endloop + endfacet + facet normal 0.40311 -0.0445577 0.914066 + outer loop + vertex 1.03453 1.23469 2.60946 + vertex 1.0346 1.23962 2.60966 + vertex 1.03097 1.2361 2.6111 + endloop + endfacet + facet normal 0.397152 -0.0372029 0.916998 + outer loop + vertex 1.03097 1.2361 2.6111 + vertex 1.0346 1.23962 2.60966 + vertex 1.03111 1.24106 2.61124 + endloop + endfacet + facet normal 0.471971 -0.0383503 0.88078 + outer loop + vertex 1.03111 1.24106 2.61124 + vertex 1.02782 1.23787 2.61286 + vertex 1.03097 1.2361 2.6111 + endloop + endfacet + facet normal 0.469704 -0.0353251 0.882117 + outer loop + vertex 1.02801 1.24289 2.61296 + vertex 1.02782 1.23787 2.61286 + vertex 1.03111 1.24106 2.61124 + endloop + endfacet + facet normal 0.462258 -0.0509126 0.885283 + outer loop + vertex 1.03142 1.24595 2.61136 + vertex 1.02801 1.24289 2.61296 + vertex 1.03111 1.24106 2.61124 + endloop + endfacet + facet normal 0.382591 -0.0468093 0.922731 + outer loop + vertex 1.03111 1.24106 2.61124 + vertex 1.03475 1.24452 2.6099 + vertex 1.03142 1.24595 2.61136 + endloop + endfacet + facet normal 0.377381 -0.0603114 0.924092 + outer loop + vertex 1.03475 1.24452 2.6099 + vertex 1.03486 1.2491 2.61015 + vertex 1.03142 1.24595 2.61136 + endloop + endfacet + facet normal 0.364168 -0.0434706 0.930318 + outer loop + vertex 1.03486 1.2491 2.61015 + vertex 1.0321 1.24986 2.61127 + vertex 1.03142 1.24595 2.61136 + endloop + endfacet + facet normal 0.446878 -0.05885 0.892657 + outer loop + vertex 1.0321 1.24986 2.61127 + vertex 1.02826 1.24868 2.61312 + vertex 1.03142 1.24595 2.61136 + endloop + endfacet + facet normal 0.446318 -0.056323 0.8931 + outer loop + vertex 1.0321 1.24986 2.61127 + vertex 1.03171 1.25326 2.61168 + vertex 1.02826 1.24868 2.61312 + endloop + endfacet + facet normal 0.390216 -0.0562487 0.919004 + outer loop + vertex 1.0346 1.23962 2.60966 + vertex 1.03475 1.24452 2.6099 + vertex 1.03111 1.24106 2.61124 + endloop + endfacet + facet normal 0.420391 -0.0370694 0.906585 + outer loop + vertex 1.03448 1.22977 2.60928 + vertex 1.03453 1.23469 2.60946 + vertex 1.03093 1.23117 2.61098 + endloop + endfacet + facet normal 0.479476 -0.021535 0.877291 + outer loop + vertex 1.02782 1.23787 2.61286 + vertex 1.02774 1.23291 2.61278 + vertex 1.03097 1.2361 2.6111 + endloop + endfacet + facet normal 0.499448 -0.00857147 0.866301 + outer loop + vertex 1.03095 1.22626 2.6109 + vertex 1.02772 1.22297 2.61273 + vertex 1.03095 1.22133 2.61085 + endloop + endfacet + facet normal 0.482946 -0.0121254 0.875566 + outer loop + vertex 1.02144 1.22647 2.61658 + vertex 1.01805 1.22263 2.61839 + vertex 1.02151 1.22137 2.61647 + endloop + endfacet + facet normal 0.454673 -0.0235547 0.890347 + outer loop + vertex 1.01835 1.21793 2.61811 + vertex 1.01805 1.22263 2.61839 + vertex 1.01542 1.21894 2.61964 + endloop + endfacet + facet normal 0.423445 -0.0379876 0.905125 + outer loop + vertex 1.01505 1.2147 2.61964 + vertex 1.01542 1.21894 2.61964 + vertex 1.01192 1.2165 2.62117 + endloop + endfacet + facet normal 0.449843 -0.0403091 0.892197 + outer loop + vertex 1.01505 1.2147 2.61964 + vertex 1.01835 1.21793 2.61811 + vertex 1.01542 1.21894 2.61964 + endloop + endfacet + facet normal 0.454288 -0.0460543 0.889664 + outer loop + vertex 1.01818 1.21313 2.61795 + vertex 1.01835 1.21793 2.61811 + vertex 1.01505 1.2147 2.61964 + endloop + endfacet + facet normal 0.387464 -0.0422664 0.920915 + outer loop + vertex 1.00835 1.21825 2.62275 + vertex 1.00769 1.2127 2.62278 + vertex 1.01192 1.2165 2.62117 + endloop + endfacet + facet normal 0.388098 -0.0431017 0.92061 + outer loop + vertex 1.01192 1.2165 2.62117 + vertex 1.00769 1.2127 2.62278 + vertex 1.01138 1.2114 2.62116 + endloop + endfacet + facet normal 0.419355 -0.0463794 0.906637 + outer loop + vertex 1.01138 1.2114 2.62116 + vertex 1.01505 1.2147 2.61964 + vertex 1.01192 1.2165 2.62117 + endloop + endfacet + facet normal 0.383769 -0.0567476 0.921684 + outer loop + vertex 1.00769 1.2127 2.62278 + vertex 1.00745 1.20755 2.62256 + vertex 1.01138 1.2114 2.62116 + endloop + endfacet + facet normal 0.324834 -0.0549499 0.944173 + outer loop + vertex 1.00745 1.20755 2.62256 + vertex 1.00769 1.2127 2.62278 + vertex 1.00335 1.20821 2.62401 + endloop + endfacet + facet normal 0.320322 -0.0821183 0.943743 + outer loop + vertex 1.00323 1.20314 2.62361 + vertex 1.00745 1.20755 2.62256 + vertex 1.00335 1.20821 2.62401 + endloop + endfacet + facet normal 0.344055 -0.036993 0.93822 + outer loop + vertex 1.00769 1.2127 2.62278 + vertex 1.00835 1.21825 2.62275 + vertex 1.00335 1.21376 2.62441 + endloop + endfacet + facet normal 0.356786 -0.0532422 0.932668 + outer loop + vertex 1.00335 1.21376 2.62441 + vertex 1.00835 1.21825 2.62275 + vertex 1.00452 1.21979 2.62431 + endloop + endfacet + facet normal 0.363375 -0.0351177 0.930981 + outer loop + vertex 1.00835 1.21825 2.62275 + vertex 1.00909 1.22398 2.62268 + vertex 1.00452 1.21979 2.62431 + endloop + endfacet + facet normal 0.407283 -0.0405319 0.912402 + outer loop + vertex 1.01184 1.22813 2.62164 + vertex 1.00848 1.22885 2.62317 + vertex 1.00909 1.22398 2.62268 + endloop + endfacet + facet normal 0.370046 -0.0467949 0.927834 + outer loop + vertex 1.00909 1.22398 2.62268 + vertex 1.00848 1.22885 2.62317 + vertex 1.00483 1.225 2.62443 + endloop + endfacet + facet normal 0.370609 -0.0442667 0.927734 + outer loop + vertex 1.00452 1.21979 2.62431 + vertex 1.00909 1.22398 2.62268 + vertex 1.00483 1.225 2.62443 + endloop + endfacet + facet normal 0.37751 -0.0549922 0.924371 + outer loop + vertex 1.00483 1.225 2.62443 + vertex 1.00848 1.22885 2.62317 + vertex 1.0049 1.2299 2.6247 + endloop + endfacet + facet normal 0.37858 -0.0510553 0.924159 + outer loop + vertex 1.00848 1.22885 2.62317 + vertex 1.00838 1.23373 2.62348 + vertex 1.0049 1.2299 2.6247 + endloop + endfacet + facet normal 0.392465 -0.065779 0.917412 + outer loop + vertex 1.0049 1.2299 2.6247 + vertex 1.00838 1.23373 2.62348 + vertex 1.005 1.23446 2.62498 + endloop + endfacet + facet normal 0.394766 -0.0545999 0.917158 + outer loop + vertex 1.00804 1.23901 2.62394 + vertex 1.005 1.23446 2.62498 + vertex 1.00838 1.23373 2.62348 + endloop + endfacet + facet normal 0.404909 -0.0625053 0.912218 + outer loop + vertex 1.00458 1.23773 2.62539 + vertex 1.005 1.23446 2.62498 + vertex 1.00804 1.23901 2.62394 + endloop + endfacet + facet normal 0.401811 -0.0518405 0.914254 + outer loop + vertex 1.00458 1.23773 2.62539 + vertex 1.00804 1.23901 2.62394 + vertex 1.00525 1.24155 2.62531 + endloop + endfacet + facet normal 0.329015 -0.0386619 0.943533 + outer loop + vertex 1.00525 1.24155 2.62531 + vertex 1.00191 1.23817 2.62634 + vertex 1.00458 1.23773 2.62539 + endloop + endfacet + facet normal 0.326218 -0.0559531 0.943637 + outer loop + vertex 1.00458 1.23773 2.62539 + vertex 1.00191 1.23817 2.62634 + vertex 1.00239 1.23503 2.62599 + endloop + endfacet + facet normal 0.342995 -0.0542163 0.937771 + outer loop + vertex 1.00197 1.2426 2.62657 + vertex 1.00191 1.23817 2.62634 + vertex 1.00525 1.24155 2.62531 + endloop + endfacet + facet normal 0.348659 -0.0351589 0.93659 + outer loop + vertex 1.00559 1.24639 2.62537 + vertex 1.00197 1.2426 2.62657 + vertex 1.00525 1.24155 2.62531 + endloop + endfacet + facet normal 0.409131 -0.0391691 0.911635 + outer loop + vertex 1.00525 1.24155 2.62531 + vertex 1.00878 1.24472 2.62386 + vertex 1.00559 1.24639 2.62537 + endloop + endfacet + facet normal 0.415946 -0.0237764 0.909079 + outer loop + vertex 1.00878 1.24472 2.62386 + vertex 1.00904 1.24988 2.62388 + vertex 1.00559 1.24639 2.62537 + endloop + endfacet + facet normal 0.413749 -0.02115 0.910145 + outer loop + vertex 1.00559 1.24639 2.62537 + vertex 1.00904 1.24988 2.62388 + vertex 1.00571 1.25136 2.62543 + endloop + endfacet + facet normal 0.361613 -0.020082 0.932112 + outer loop + vertex 1.00571 1.25136 2.62543 + vertex 1.00207 1.24744 2.62676 + vertex 1.00559 1.24639 2.62537 + endloop + endfacet + facet normal 0.364041 -0.0226781 0.931107 + outer loop + vertex 1.00208 1.2524 2.62687 + vertex 1.00207 1.24744 2.62676 + vertex 1.00571 1.25136 2.62543 + endloop + endfacet + facet normal 0.295195 -0.0230287 0.955159 + outer loop + vertex 1.00207 1.24744 2.62676 + vertex 1.00208 1.2524 2.62687 + vertex 0.998025 1.24798 2.62802 + endloop + endfacet + facet normal 0.29109 -0.0538939 0.955176 + outer loop + vertex 0.998014 1.24303 2.62774 + vertex 1.00207 1.24744 2.62676 + vertex 0.998025 1.24798 2.62802 + endloop + endfacet + facet normal 0.279218 -0.0420584 0.959306 + outer loop + vertex 1.00197 1.2426 2.62657 + vertex 1.00207 1.24744 2.62676 + vertex 0.998014 1.24303 2.62774 + endloop + endfacet + facet normal 0.275973 -0.0701923 0.958599 + outer loop + vertex 0.998057 1.23819 2.62738 + vertex 1.00197 1.2426 2.62657 + vertex 0.998014 1.24303 2.62774 + endloop + endfacet + facet normal 0.259361 -0.0544409 0.964245 + outer loop + vertex 1.00191 1.23817 2.62634 + vertex 1.00197 1.2426 2.62657 + vertex 0.998057 1.23819 2.62738 + endloop + endfacet + facet normal 0.307735 -0.0356771 0.950803 + outer loop + vertex 0.998025 1.24798 2.62802 + vertex 1.00208 1.2524 2.62687 + vertex 0.998021 1.25303 2.62821 + endloop + endfacet + facet normal 0.42005 -0.00430469 0.907491 + outer loop + vertex 1.00904 1.24988 2.62388 + vertex 1.00909 1.25492 2.62388 + vertex 1.00571 1.25136 2.62543 + endloop + endfacet + facet normal 0.446692 -0.0252459 0.894331 + outer loop + vertex 1.00878 1.24472 2.62386 + vertex 1.0123 1.24812 2.6222 + vertex 1.00904 1.24988 2.62388 + endloop + endfacet + facet normal 0.453481 -0.00960992 0.891214 + outer loop + vertex 1.0123 1.24812 2.6222 + vertex 1.01234 1.25319 2.62224 + vertex 1.00904 1.24988 2.62388 + endloop + endfacet + facet normal 0.449458 -0.00458032 0.89329 + outer loop + vertex 1.00904 1.24988 2.62388 + vertex 1.01234 1.25319 2.62224 + vertex 1.00909 1.25492 2.62388 + endloop + endfacet + facet normal 0.44809 -0.0270588 0.893579 + outer loop + vertex 1.01211 1.24289 2.62214 + vertex 1.0123 1.24812 2.6222 + vertex 1.00878 1.24472 2.62386 + endloop + endfacet + facet normal 0.439998 -0.044788 0.896881 + outer loop + vertex 1.00804 1.23901 2.62394 + vertex 1.01211 1.24289 2.62214 + vertex 1.00878 1.24472 2.62386 + endloop + endfacet + facet normal 0.434808 -0.0380211 0.89972 + outer loop + vertex 1.01194 1.2376 2.622 + vertex 1.01211 1.24289 2.62214 + vertex 1.00804 1.23901 2.62394 + endloop + endfacet + facet normal 0.430778 -0.0509456 0.901019 + outer loop + vertex 1.00838 1.23373 2.62348 + vertex 1.01194 1.2376 2.622 + vertex 1.00804 1.23901 2.62394 + endloop + endfacet + facet normal 0.421286 -0.0402755 0.906033 + outer loop + vertex 1.01188 1.23257 2.6218 + vertex 1.01194 1.2376 2.622 + vertex 1.00838 1.23373 2.62348 + endloop + endfacet + facet normal 0.418714 -0.0491022 0.90679 + outer loop + vertex 1.00848 1.22885 2.62317 + vertex 1.01188 1.23257 2.6218 + vertex 1.00838 1.23373 2.62348 + endloop + endfacet + facet normal 0.355503 -0.0426175 0.933703 + outer loop + vertex 1.00207 1.24744 2.62676 + vertex 1.00197 1.2426 2.62657 + vertex 1.00559 1.24639 2.62537 + endloop + endfacet + facet normal 0.410293 -0.0407374 0.911043 + outer loop + vertex 1.00804 1.23901 2.62394 + vertex 1.00878 1.24472 2.62386 + vertex 1.00525 1.24155 2.62531 + endloop + endfacet + facet normal 0.345164 -0.0730807 0.935693 + outer loop + vertex 1.00458 1.23773 2.62539 + vertex 1.00239 1.23503 2.62599 + vertex 1.005 1.23446 2.62498 + endloop + endfacet + facet normal 0.407924 -0.0372124 0.912257 + outer loop + vertex 1.01184 1.22813 2.62164 + vertex 1.01188 1.23257 2.6218 + vertex 1.00848 1.22885 2.62317 + endloop + endfacet + facet normal 0.462538 -0.0407778 0.885661 + outer loop + vertex 1.0141 1.22706 2.62053 + vertex 1.0134 1.22263 2.62069 + vertex 1.01755 1.22801 2.61877 + endloop + endfacet + facet normal 0.499472 -0.0297431 0.865819 + outer loop + vertex 1.01847 1.2339 2.61844 + vertex 1.01755 1.22801 2.61877 + vertex 1.02155 1.23175 2.61659 + endloop + endfacet + facet normal 0.505355 -0.0186577 0.86271 + outer loop + vertex 1.02182 1.23691 2.61654 + vertex 1.01847 1.2339 2.61844 + vertex 1.02155 1.23175 2.61659 + endloop + endfacet + facet normal 0.509761 -0.0253025 0.859944 + outer loop + vertex 1.01886 1.23911 2.61836 + vertex 1.01847 1.2339 2.61844 + vertex 1.02182 1.23691 2.61654 + endloop + endfacet + facet normal 0.512237 -0.0208506 0.858591 + outer loop + vertex 1.02211 1.24168 2.61649 + vertex 1.01886 1.23911 2.61836 + vertex 1.02182 1.23691 2.61654 + endloop + endfacet + facet normal 0.529579 -0.0220327 0.847974 + outer loop + vertex 1.02182 1.23691 2.61654 + vertex 1.02489 1.23975 2.6147 + vertex 1.02211 1.24168 2.61649 + endloop + endfacet + facet normal 0.52549 -0.0300234 0.85027 + outer loop + vertex 1.02489 1.23975 2.6147 + vertex 1.02504 1.24429 2.61477 + vertex 1.02211 1.24168 2.61649 + endloop + endfacet + facet normal 0.520319 -0.0219521 0.85369 + outer loop + vertex 1.02504 1.24429 2.61477 + vertex 1.02263 1.24532 2.61626 + vertex 1.02211 1.24168 2.61649 + endloop + endfacet + facet normal 0.514419 -0.0208904 0.857284 + outer loop + vertex 1.02263 1.24532 2.61626 + vertex 1.01943 1.24458 2.61817 + vertex 1.02211 1.24168 2.61649 + endloop + endfacet + facet normal 0.514056 -0.0186123 0.857555 + outer loop + vertex 1.02263 1.24532 2.61626 + vertex 1.02207 1.24859 2.61667 + vertex 1.01943 1.24458 2.61817 + endloop + endfacet + facet normal 0.50883 -0.0139679 0.860754 + outer loop + vertex 1.02207 1.24859 2.61667 + vertex 1.0189 1.24977 2.61857 + vertex 1.01943 1.24458 2.61817 + endloop + endfacet + facet normal 0.512089 -0.0190929 0.85872 + outer loop + vertex 1.02459 1.2476 2.61515 + vertex 1.02207 1.24859 2.61667 + vertex 1.02263 1.24532 2.61626 + endloop + endfacet + facet normal 0.51138 -0.0214786 0.859086 + outer loop + vertex 1.02501 1.25139 2.61499 + vertex 1.02207 1.24859 2.61667 + vertex 1.02459 1.2476 2.61515 + endloop + endfacet + facet normal 0.488033 -0.0183547 0.872632 + outer loop + vertex 1.02459 1.2476 2.61515 + vertex 1.02826 1.24868 2.61312 + vertex 1.02501 1.25139 2.61499 + endloop + endfacet + facet normal 0.478547 -0.0330762 0.877439 + outer loop + vertex 1.02826 1.24868 2.61312 + vertex 1.02833 1.25452 2.6133 + vertex 1.02501 1.25139 2.61499 + endloop + endfacet + facet normal 0.459271 -0.00670998 0.888271 + outer loop + vertex 1.02501 1.25139 2.61499 + vertex 1.02833 1.25452 2.6133 + vertex 1.02485 1.25618 2.61511 + endloop + endfacet + facet normal 0.500325 -0.0047752 0.865824 + outer loop + vertex 1.02485 1.25618 2.61511 + vertex 1.02181 1.2531 2.61685 + vertex 1.02501 1.25139 2.61499 + endloop + endfacet + facet normal 0.456718 -0.013408 0.88951 + outer loop + vertex 1.02833 1.25452 2.6133 + vertex 1.0281 1.25998 2.6135 + vertex 1.02485 1.25618 2.61511 + endloop + endfacet + facet normal 0.491024 -0.0324831 0.87054 + outer loop + vertex 1.02459 1.2476 2.61515 + vertex 1.02504 1.24429 2.61477 + vertex 1.02826 1.24868 2.61312 + endloop + endfacet + facet normal 0.504221 -0.0452128 0.86239 + outer loop + vertex 1.02826 1.24868 2.61312 + vertex 1.02504 1.24429 2.61477 + vertex 1.02801 1.24289 2.61296 + endloop + endfacet + facet normal 0.500039 -0.00548405 0.865986 + outer loop + vertex 1.02181 1.2531 2.61685 + vertex 1.02207 1.24859 2.61667 + vertex 1.02501 1.25139 2.61499 + endloop + endfacet + facet normal 0.518736 -0.026853 0.854513 + outer loop + vertex 1.02459 1.2476 2.61515 + vertex 1.02263 1.24532 2.61626 + vertex 1.02504 1.24429 2.61477 + endloop + endfacet + facet normal 0.509943 -0.0296398 0.859697 + outer loop + vertex 1.02489 1.23975 2.6147 + vertex 1.02801 1.24289 2.61296 + vertex 1.02504 1.24429 2.61477 + endloop + endfacet + facet normal 0.515061 -0.0365687 0.856373 + outer loop + vertex 1.02782 1.23787 2.61286 + vertex 1.02801 1.24289 2.61296 + vertex 1.02489 1.23975 2.6147 + endloop + endfacet + facet normal 0.522382 -0.0213001 0.852446 + outer loop + vertex 1.02475 1.23486 2.61467 + vertex 1.02782 1.23787 2.61286 + vertex 1.02489 1.23975 2.6147 + endloop + endfacet + facet normal 0.522774 -0.0218513 0.852191 + outer loop + vertex 1.02774 1.23291 2.61278 + vertex 1.02782 1.23787 2.61286 + vertex 1.02475 1.23486 2.61467 + endloop + endfacet + facet normal 0.527426 -0.0121425 0.849514 + outer loop + vertex 1.02467 1.22981 2.61464 + vertex 1.02774 1.23291 2.61278 + vertex 1.02475 1.23486 2.61467 + endloop + endfacet + facet normal 0.529204 -0.0214645 0.848223 + outer loop + vertex 1.02475 1.23486 2.61467 + vertex 1.02489 1.23975 2.6147 + vertex 1.02182 1.23691 2.61654 + endloop + endfacet + facet normal 0.439343 -0.0369925 0.897558 + outer loop + vertex 1.01188 1.23257 2.6218 + vertex 1.01184 1.22813 2.62164 + vertex 1.01498 1.23101 2.62022 + endloop + endfacet + facet normal 0.47951 -0.0227725 0.877241 + outer loop + vertex 1.01847 1.2339 2.61844 + vertex 1.01886 1.23911 2.61836 + vertex 1.01538 1.23598 2.62019 + endloop + endfacet + facet normal 0.513165 -0.02246 0.857996 + outer loop + vertex 1.01943 1.24458 2.61817 + vertex 1.01886 1.23911 2.61836 + vertex 1.02211 1.24168 2.61649 + endloop + endfacet + facet normal 0.462618 -0.0385114 0.885721 + outer loop + vertex 1.01211 1.24289 2.62214 + vertex 1.01194 1.2376 2.622 + vertex 1.01562 1.24115 2.62023 + endloop + endfacet + facet normal 0.472942 -0.00965094 0.881041 + outer loop + vertex 1.01234 1.25319 2.62224 + vertex 1.0123 1.24812 2.6222 + vertex 1.01558 1.25141 2.62048 + endloop + endfacet + facet normal 0.4972 -0.0156916 0.867494 + outer loop + vertex 1.01943 1.24458 2.61817 + vertex 1.0189 1.24977 2.61857 + vertex 1.0157 1.24635 2.62034 + endloop + endfacet + facet normal 0.511459 -0.00455304 0.859295 + outer loop + vertex 1.02207 1.24859 2.61667 + vertex 1.02181 1.2531 2.61685 + vertex 1.0189 1.24977 2.61857 + endloop + endfacet + facet normal 0.508812 0.0242879 0.860535 + outer loop + vertex 1.01896 1.26317 2.61831 + vertex 1.01795 1.25872 2.61903 + vertex 1.02128 1.25833 2.61707 + endloop + endfacet + facet normal 0.487412 0.0091027 0.873125 + outer loop + vertex 1.01229 1.26315 2.62218 + vertex 1.0123 1.25817 2.62222 + vertex 1.01541 1.26101 2.62045 + endloop + endfacet + facet normal 0.516067 -0.00935773 0.856497 + outer loop + vertex 1.01866 1.27387 2.61846 + vertex 1.0186 1.26876 2.61844 + vertex 1.02169 1.27154 2.61661 + endloop + endfacet + facet normal 0.514211 -0.0126182 0.857571 + outer loop + vertex 1.02183 1.27625 2.6166 + vertex 1.01866 1.27387 2.61846 + vertex 1.02169 1.27154 2.61661 + endloop + endfacet + facet normal 0.45244 -0.0106921 0.891731 + outer loop + vertex 1.02169 1.27154 2.61661 + vertex 1.02499 1.27454 2.61497 + vertex 1.02183 1.27625 2.6166 + endloop + endfacet + facet normal 0.446979 -0.0232201 0.894243 + outer loop + vertex 1.02499 1.27454 2.61497 + vertex 1.02492 1.27895 2.61513 + vertex 1.02183 1.27625 2.6166 + endloop + endfacet + facet normal 0.440489 -0.0139497 0.89765 + outer loop + vertex 1.02492 1.27895 2.61513 + vertex 1.02236 1.27987 2.6164 + vertex 1.02183 1.27625 2.6166 + endloop + endfacet + facet normal 0.52423 -0.0287517 0.851091 + outer loop + vertex 1.02236 1.27987 2.6164 + vertex 1.01929 1.2793 2.61827 + vertex 1.02183 1.27625 2.6166 + endloop + endfacet + facet normal 0.526694 -0.0503332 0.848563 + outer loop + vertex 1.02236 1.27987 2.6164 + vertex 1.02198 1.28324 2.61683 + vertex 1.01929 1.2793 2.61827 + endloop + endfacet + facet normal 0.523442 -0.0296523 0.851545 + outer loop + vertex 1.01929 1.2793 2.61827 + vertex 1.01866 1.27387 2.61846 + vertex 1.02183 1.27625 2.6166 + endloop + endfacet + facet normal 0.512867 -0.0271153 0.85804 + outer loop + vertex 1.01243 1.27309 2.62228 + vertex 1.01232 1.26814 2.62219 + vertex 1.01549 1.27111 2.62039 + endloop + endfacet + facet normal 0.535688 -0.0313405 0.843834 + outer loop + vertex 1.01866 1.27387 2.61846 + vertex 1.01929 1.2793 2.61827 + vertex 1.01571 1.27617 2.62043 + endloop + endfacet + facet normal 0.522499 -0.0464357 0.851375 + outer loop + vertex 1.02198 1.28324 2.61683 + vertex 1.01905 1.28458 2.6187 + vertex 1.01929 1.2793 2.61827 + endloop + endfacet + facet normal 0.518132 -0.058654 0.853287 + outer loop + vertex 1.02198 1.28324 2.61683 + vertex 1.02214 1.28783 2.61705 + vertex 1.01905 1.28458 2.6187 + endloop + endfacet + facet normal 0.506503 -0.0436019 0.861135 + outer loop + vertex 1.01905 1.28458 2.6187 + vertex 1.02214 1.28783 2.61705 + vertex 1.01914 1.28957 2.6189 + endloop + endfacet + facet normal 0.50142 -0.0548448 0.863464 + outer loop + vertex 1.02214 1.28783 2.61705 + vertex 1.0224 1.2928 2.61722 + vertex 1.01914 1.28957 2.6189 + endloop + endfacet + facet normal 0.522915 -0.0426739 0.851316 + outer loop + vertex 1.01274 1.28297 2.62258 + vertex 1.0126 1.27802 2.62242 + vertex 1.0159 1.28125 2.62055 + endloop + endfacet + facet normal 0.521612 -0.0305736 0.852635 + outer loop + vertex 1.01283 1.29298 2.62291 + vertex 1.01283 1.28796 2.62274 + vertex 1.01604 1.29132 2.6209 + endloop + endfacet + facet normal 0.500024 -0.0310103 0.865456 + outer loop + vertex 1.01283 1.28796 2.62274 + vertex 1.01283 1.29298 2.62291 + vertex 1.0097 1.28953 2.6246 + endloop + endfacet + facet normal 0.497021 -0.0387097 0.866875 + outer loop + vertex 1.00956 1.28459 2.62446 + vertex 1.01283 1.28796 2.62274 + vertex 1.0097 1.28953 2.6246 + endloop + endfacet + facet normal 0.495351 -0.0365506 0.867924 + outer loop + vertex 1.01274 1.28297 2.62258 + vertex 1.01283 1.28796 2.62274 + vertex 1.00956 1.28459 2.62446 + endloop + endfacet + facet normal 0.492496 -0.0436518 0.869219 + outer loop + vertex 1.00942 1.27964 2.62429 + vertex 1.01274 1.28297 2.62258 + vertex 1.00956 1.28459 2.62446 + endloop + endfacet + facet normal 0.491551 -0.0424044 0.869816 + outer loop + vertex 1.0126 1.27802 2.62242 + vertex 1.01274 1.28297 2.62258 + vertex 1.00942 1.27964 2.62429 + endloop + endfacet + facet normal 0.489646 -0.0470884 0.870649 + outer loop + vertex 1.00928 1.27473 2.62411 + vertex 1.0126 1.27802 2.62242 + vertex 1.00942 1.27964 2.62429 + endloop + endfacet + facet normal 0.484879 -0.0407385 0.873632 + outer loop + vertex 1.01243 1.27309 2.62228 + vertex 1.0126 1.27802 2.62242 + vertex 1.00928 1.27473 2.62411 + endloop + endfacet + facet normal 0.485146 -0.0400948 0.873514 + outer loop + vertex 1.00915 1.26983 2.62395 + vertex 1.01243 1.27309 2.62228 + vertex 1.00928 1.27473 2.62411 + endloop + endfacet + facet normal 0.450171 -0.0397451 0.892057 + outer loop + vertex 1.00915 1.26983 2.62395 + vertex 1.00928 1.27473 2.62411 + vertex 1.00585 1.27131 2.62568 + endloop + endfacet + facet normal 0.451431 -0.0363591 0.891565 + outer loop + vertex 1.00574 1.26632 2.62553 + vertex 1.00915 1.26983 2.62395 + vertex 1.00585 1.27131 2.62568 + endloop + endfacet + facet normal 0.417354 -0.036116 0.908026 + outer loop + vertex 1.00585 1.27131 2.62568 + vertex 1.00219 1.26763 2.62722 + vertex 1.00574 1.26632 2.62553 + endloop + endfacet + facet normal 0.416868 -0.0376484 0.908187 + outer loop + vertex 1.00219 1.26763 2.62722 + vertex 1.00211 1.26249 2.62704 + vertex 1.00574 1.26632 2.62553 + endloop + endfacet + facet normal 0.398263 -0.0164777 0.917123 + outer loop + vertex 1.00574 1.26632 2.62553 + vertex 1.00211 1.26249 2.62704 + vertex 1.00571 1.26134 2.62546 + endloop + endfacet + facet normal 0.441218 -0.0164983 0.897248 + outer loop + vertex 1.00571 1.26134 2.62546 + vertex 1.00907 1.26489 2.62387 + vertex 1.00574 1.26632 2.62553 + endloop + endfacet + facet normal 0.428359 -0.00144324 0.903608 + outer loop + vertex 1.00907 1.25992 2.62386 + vertex 1.00907 1.26489 2.62387 + vertex 1.00571 1.26134 2.62546 + endloop + endfacet + facet normal 0.465715 -0.00143338 0.884934 + outer loop + vertex 1.00907 1.25992 2.62386 + vertex 1.01229 1.26315 2.62218 + vertex 1.00907 1.26489 2.62387 + endloop + endfacet + facet normal 0.464021 -0.00541335 0.885808 + outer loop + vertex 1.01229 1.26315 2.62218 + vertex 1.01232 1.26814 2.62219 + vertex 1.00907 1.26489 2.62387 + endloop + endfacet + facet normal 0.47689 -0.0219407 0.878689 + outer loop + vertex 1.00907 1.26489 2.62387 + vertex 1.01232 1.26814 2.62219 + vertex 1.00915 1.26983 2.62395 + endloop + endfacet + facet normal 0.457341 0.00916128 0.889244 + outer loop + vertex 1.0123 1.25817 2.62222 + vertex 1.01229 1.26315 2.62218 + vertex 1.00907 1.25992 2.62386 + endloop + endfacet + facet normal 0.455553 0.00497246 0.890195 + outer loop + vertex 1.00909 1.25492 2.62388 + vertex 1.0123 1.25817 2.62222 + vertex 1.00907 1.25992 2.62386 + endloop + endfacet + facet normal 0.454202 0.00665057 0.890874 + outer loop + vertex 1.01234 1.25319 2.62224 + vertex 1.0123 1.25817 2.62222 + vertex 1.00909 1.25492 2.62388 + endloop + endfacet + facet normal 0.397335 -0.0198374 0.917459 + outer loop + vertex 1.00211 1.26249 2.62704 + vertex 1.00208 1.25742 2.62695 + vertex 1.00571 1.26134 2.62546 + endloop + endfacet + facet normal 0.381268 -0.00229291 0.924462 + outer loop + vertex 1.00571 1.26134 2.62546 + vertex 1.00208 1.25742 2.62695 + vertex 1.00572 1.25635 2.62544 + endloop + endfacet + facet normal 0.428119 -0.00213823 0.90372 + outer loop + vertex 1.00572 1.25635 2.62544 + vertex 1.00907 1.25992 2.62386 + vertex 1.00571 1.26134 2.62546 + endloop + endfacet + facet normal 0.335416 -0.0198861 0.94186 + outer loop + vertex 1.00208 1.25742 2.62695 + vertex 1.00211 1.26249 2.62704 + vertex 0.998058 1.25822 2.6284 + endloop + endfacet + facet normal 0.332433 -0.0360213 0.942439 + outer loop + vertex 0.998021 1.25303 2.62821 + vertex 1.00208 1.25742 2.62695 + vertex 0.998058 1.25822 2.6284 + endloop + endfacet + facet normal 0.364261 -0.0509956 0.9299 + outer loop + vertex 0.998058 1.25822 2.6284 + vertex 1.00211 1.26249 2.62704 + vertex 0.998269 1.2635 2.6286 + endloop + endfacet + facet normal 0.285291 -0.0489034 0.957193 + outer loop + vertex 0.998058 1.25822 2.6284 + vertex 0.998269 1.2635 2.6286 + vertex 0.993556 1.25888 2.62977 + endloop + endfacet + facet normal 0.282462 -0.0674036 0.956908 + outer loop + vertex 0.993541 1.2534 2.62939 + vertex 0.998058 1.25822 2.6284 + vertex 0.993556 1.25888 2.62977 + endloop + endfacet + facet normal 0.329982 -0.0991912 0.938762 + outer loop + vertex 0.993556 1.25888 2.62977 + vertex 0.998269 1.2635 2.6286 + vertex 0.994814 1.26434 2.6299 + endloop + endfacet + facet normal 0.337947 -0.066315 0.938826 + outer loop + vertex 0.998233 1.26896 2.629 + vertex 0.994814 1.26434 2.6299 + vertex 0.998269 1.2635 2.6286 + endloop + endfacet + facet normal 0.391704 -0.0644274 0.917833 + outer loop + vertex 0.998269 1.2635 2.6286 + vertex 1.00219 1.26763 2.62722 + vertex 0.998233 1.26896 2.629 + endloop + endfacet + facet normal 0.395912 -0.0507338 0.916886 + outer loop + vertex 1.00219 1.26763 2.62722 + vertex 1.00241 1.27283 2.62741 + vertex 0.998233 1.26896 2.629 + endloop + endfacet + facet normal 0.407531 -0.0657904 0.910818 + outer loop + vertex 0.998233 1.26896 2.629 + vertex 1.00241 1.27283 2.62741 + vertex 0.999098 1.27464 2.62902 + endloop + endfacet + facet normal 0.357782 -0.058293 0.931984 + outer loop + vertex 0.998233 1.26896 2.629 + vertex 0.999098 1.27464 2.62902 + vertex 0.995454 1.27152 2.63023 + endloop + endfacet + facet normal 0.351258 -0.0663093 0.933928 + outer loop + vertex 0.994687 1.26772 2.63025 + vertex 0.998233 1.26896 2.629 + vertex 0.995454 1.27152 2.63023 + endloop + endfacet + facet normal 0.248342 -0.0453782 0.967609 + outer loop + vertex 0.995454 1.27152 2.63023 + vertex 0.991984 1.26817 2.63096 + vertex 0.994687 1.26772 2.63025 + endloop + endfacet + facet normal 0.245443 -0.0624702 0.967396 + outer loop + vertex 0.994687 1.26772 2.63025 + vertex 0.991984 1.26817 2.63096 + vertex 0.992312 1.26506 2.63068 + endloop + endfacet + facet normal 0.270892 -0.0865866 0.958708 + outer loop + vertex 0.994687 1.26772 2.63025 + vertex 0.992312 1.26506 2.63068 + vertex 0.994814 1.26434 2.6299 + endloop + endfacet + facet normal 0.266081 -0.0650177 0.961756 + outer loop + vertex 0.992128 1.27259 2.63122 + vertex 0.991984 1.26817 2.63096 + vertex 0.995454 1.27152 2.63023 + endloop + endfacet + facet normal 0.268713 -0.0566072 0.961555 + outer loop + vertex 0.995863 1.27634 2.6304 + vertex 0.992128 1.27259 2.63122 + vertex 0.995454 1.27152 2.63023 + endloop + endfacet + facet normal 0.280926 -0.069722 0.957193 + outer loop + vertex 0.99229 1.27744 2.63153 + vertex 0.992128 1.27259 2.63122 + vertex 0.995863 1.27634 2.6304 + endloop + endfacet + facet normal 0.28386 -0.0599963 0.956987 + outer loop + vertex 0.996087 1.2813 2.63064 + vertex 0.99229 1.27744 2.63153 + vertex 0.995863 1.27634 2.6304 + endloop + endfacet + facet normal 0.370882 -0.062423 0.92658 + outer loop + vertex 0.995863 1.27634 2.6304 + vertex 0.999442 1.27974 2.62919 + vertex 0.996087 1.2813 2.63064 + endloop + endfacet + facet normal 0.374825 -0.0530363 0.925577 + outer loop + vertex 0.999442 1.27974 2.62919 + vertex 0.999683 1.28478 2.62939 + vertex 0.996087 1.2813 2.63064 + endloop + endfacet + facet normal 0.379084 -0.0581774 0.923532 + outer loop + vertex 0.996087 1.2813 2.63064 + vertex 0.999683 1.28478 2.62939 + vertex 0.996266 1.28628 2.63088 + endloop + endfacet + facet normal 0.299049 -0.056705 0.952551 + outer loop + vertex 0.996266 1.28628 2.63088 + vertex 0.99241 1.2824 2.63186 + vertex 0.996087 1.2813 2.63064 + endloop + endfacet + facet normal 0.306793 -0.0651643 0.949543 + outer loop + vertex 0.992525 1.28734 2.63216 + vertex 0.99241 1.2824 2.63186 + vertex 0.996266 1.28628 2.63088 + endloop + endfacet + facet normal 0.310538 -0.0515193 0.949164 + outer loop + vertex 0.996482 1.29123 2.63108 + vertex 0.992525 1.28734 2.63216 + vertex 0.996266 1.28628 2.63088 + endloop + endfacet + facet normal 0.386812 -0.053708 0.920593 + outer loop + vertex 0.996266 1.28628 2.63088 + vertex 0.999983 1.2899 2.62953 + vertex 0.996482 1.29123 2.63108 + endloop + endfacet + facet normal 0.389314 -0.0463551 0.919938 + outer loop + vertex 0.999983 1.2899 2.62953 + vertex 1.00017 1.29491 2.6297 + vertex 0.996482 1.29123 2.63108 + endloop + endfacet + facet normal 0.395715 -0.0539419 0.916788 + outer loop + vertex 0.996482 1.29123 2.63108 + vertex 1.00017 1.29491 2.6297 + vertex 0.996829 1.29603 2.63121 + endloop + endfacet + facet normal 0.319375 -0.0492514 0.946348 + outer loop + vertex 0.996829 1.29603 2.63121 + vertex 0.992779 1.29236 2.63239 + vertex 0.996482 1.29123 2.63108 + endloop + endfacet + facet normal 0.325924 -0.0573309 0.943656 + outer loop + vertex 0.993539 1.29799 2.63247 + vertex 0.992779 1.29236 2.63239 + vertex 0.996829 1.29603 2.63121 + endloop + endfacet + facet normal 0.332455 -0.0453179 0.94203 + outer loop + vertex 0.997491 1.29985 2.63116 + vertex 0.993539 1.29799 2.63247 + vertex 0.996829 1.29603 2.63121 + endloop + endfacet + facet normal 0.403574 -0.0580001 0.913107 + outer loop + vertex 1.00016 1.29943 2.62996 + vertex 0.997491 1.29985 2.63116 + vertex 0.996829 1.29603 2.63121 + endloop + endfacet + facet normal 0.40466 -0.0510268 0.913042 + outer loop + vertex 0.999654 1.30258 2.63036 + vertex 0.997491 1.29985 2.63116 + vertex 1.00016 1.29943 2.62996 + endloop + endfacet + facet normal 0.439797 -0.0433192 0.897052 + outer loop + vertex 0.999654 1.30258 2.63036 + vertex 1.00016 1.29943 2.62996 + vertex 1.00307 1.30402 2.62875 + endloop + endfacet + facet normal 0.439625 -0.0427874 0.897162 + outer loop + vertex 0.999654 1.30258 2.63036 + vertex 1.00307 1.30402 2.62875 + vertex 1.00026 1.30639 2.63024 + endloop + endfacet + facet normal 0.392903 -0.0346122 0.918928 + outer loop + vertex 1.00026 1.30639 2.63024 + vertex 0.996933 1.30295 2.63153 + vertex 0.999654 1.30258 2.63036 + endloop + endfacet + facet normal 0.401456 -0.0444663 0.914798 + outer loop + vertex 0.996969 1.30742 2.63174 + vertex 0.996933 1.30295 2.63153 + vertex 1.00026 1.30639 2.63024 + endloop + endfacet + facet normal 0.40274 -0.0398515 0.914447 + outer loop + vertex 1.0006 1.31122 2.6303 + vertex 0.996969 1.30742 2.63174 + vertex 1.00026 1.30639 2.63024 + endloop + endfacet + facet normal 0.442823 -0.0424047 0.895606 + outer loop + vertex 1.00026 1.30639 2.63024 + vertex 1.00377 1.30967 2.62866 + vertex 1.0006 1.31122 2.6303 + endloop + endfacet + facet normal 0.444567 -0.0381387 0.894933 + outer loop + vertex 1.00377 1.30967 2.62866 + vertex 1.00405 1.31477 2.62874 + vertex 1.0006 1.31122 2.6303 + endloop + endfacet + facet normal 0.446059 -0.0399506 0.894112 + outer loop + vertex 1.0006 1.31122 2.6303 + vertex 1.00405 1.31477 2.62874 + vertex 1.00075 1.31621 2.63045 + endloop + endfacet + facet normal 0.412074 -0.0393799 0.910299 + outer loop + vertex 1.00075 1.31621 2.63045 + vertex 0.997107 1.31236 2.63193 + vertex 1.0006 1.31122 2.6303 + endloop + endfacet + facet normal 0.415891 -0.0437403 0.908362 + outer loop + vertex 0.997144 1.3175 2.63216 + vertex 0.997107 1.31236 2.63193 + vertex 1.00075 1.31621 2.63045 + endloop + endfacet + facet normal 0.418181 -0.0363432 0.907636 + outer loop + vertex 1.00082 1.32123 2.63062 + vertex 0.997144 1.3175 2.63216 + vertex 1.00075 1.31621 2.63045 + endloop + endfacet + facet normal 0.448753 -0.0362729 0.892919 + outer loop + vertex 1.00075 1.31621 2.63045 + vertex 1.00417 1.31974 2.62888 + vertex 1.00082 1.32123 2.63062 + endloop + endfacet + facet normal 0.450424 -0.0317155 0.892251 + outer loop + vertex 1.00417 1.31974 2.62888 + vertex 1.00423 1.32465 2.62902 + vertex 1.00082 1.32123 2.63062 + endloop + endfacet + facet normal 0.452667 -0.034521 0.891011 + outer loop + vertex 1.00082 1.32123 2.63062 + vertex 1.00423 1.32465 2.62902 + vertex 1.00091 1.32622 2.63077 + endloop + endfacet + facet normal 0.425835 -0.0344548 0.904145 + outer loop + vertex 1.00091 1.32622 2.63077 + vertex 0.997295 1.32276 2.63234 + vertex 1.00082 1.32123 2.63062 + endloop + endfacet + facet normal 0.430721 -0.0407307 0.901565 + outer loop + vertex 0.997554 1.32792 2.63245 + vertex 0.997295 1.32276 2.63234 + vertex 1.00091 1.32622 2.63077 + endloop + endfacet + facet normal 0.434002 -0.0330107 0.900307 + outer loop + vertex 1.00101 1.33118 2.6309 + vertex 0.997554 1.32792 2.63245 + vertex 1.00091 1.32622 2.63077 + endloop + endfacet + facet normal 0.455415 -0.0331528 0.889662 + outer loop + vertex 1.00091 1.32622 2.63077 + vertex 1.0043 1.32956 2.62916 + vertex 1.00101 1.33118 2.6309 + endloop + endfacet + facet normal 0.456654 -0.0300874 0.889136 + outer loop + vertex 1.0043 1.32956 2.62916 + vertex 1.00438 1.33449 2.62928 + vertex 1.00101 1.33118 2.6309 + endloop + endfacet + facet normal 0.458688 -0.0327177 0.887995 + outer loop + vertex 1.00101 1.33118 2.6309 + vertex 1.00438 1.33449 2.62928 + vertex 1.00111 1.33616 2.63103 + endloop + endfacet + facet normal 0.43721 -0.0325431 0.89877 + outer loop + vertex 1.00111 1.33616 2.63103 + vertex 0.997694 1.33292 2.63258 + vertex 1.00101 1.33118 2.6309 + endloop + endfacet + facet normal 0.439296 -0.0352854 0.897649 + outer loop + vertex 0.997822 1.33792 2.63271 + vertex 0.997694 1.33292 2.63258 + vertex 1.00111 1.33616 2.63103 + endloop + endfacet + facet normal 0.440524 -0.0325246 0.897152 + outer loop + vertex 1.00125 1.34118 2.63115 + vertex 0.997822 1.33792 2.63271 + vertex 1.00111 1.33616 2.63103 + endloop + endfacet + facet normal 0.462976 -0.0328637 0.885761 + outer loop + vertex 1.00111 1.33616 2.63103 + vertex 1.00448 1.33948 2.62939 + vertex 1.00125 1.34118 2.63115 + endloop + endfacet + facet normal 0.464617 -0.0289937 0.885037 + outer loop + vertex 1.00448 1.33948 2.62939 + vertex 1.0046 1.34449 2.62949 + vertex 1.00125 1.34118 2.63115 + endloop + endfacet + facet normal 0.468519 -0.0340628 0.882796 + outer loop + vertex 1.00125 1.34118 2.63115 + vertex 1.0046 1.34449 2.62949 + vertex 1.00143 1.34617 2.63124 + endloop + endfacet + facet normal 0.444327 -0.0334453 0.89524 + outer loop + vertex 1.00143 1.34617 2.63124 + vertex 0.998 1.34296 2.63282 + vertex 1.00125 1.34118 2.63115 + endloop + endfacet + facet normal 0.447019 -0.0370532 0.893757 + outer loop + vertex 0.998311 1.34803 2.63288 + vertex 0.998 1.34296 2.63282 + vertex 1.00143 1.34617 2.63124 + endloop + endfacet + facet normal 0.448417 -0.0341999 0.89317 + outer loop + vertex 1.00166 1.35088 2.63131 + vertex 0.998311 1.34803 2.63288 + vertex 1.00143 1.34617 2.63124 + endloop + endfacet + facet normal 0.474318 -0.0352879 0.879646 + outer loop + vertex 1.00143 1.34617 2.63124 + vertex 1.00465 1.34939 2.62964 + vertex 1.00166 1.35088 2.63131 + endloop + endfacet + facet normal 0.476569 -0.0296269 0.878638 + outer loop + vertex 1.00465 1.34939 2.62964 + vertex 1.00436 1.35389 2.62995 + vertex 1.00166 1.35088 2.63131 + endloop + endfacet + facet normal 0.481828 -0.0357311 0.875537 + outer loop + vertex 1.00436 1.35389 2.62995 + vertex 1.00197 1.35402 2.63126 + vertex 1.00166 1.35088 2.63131 + endloop + endfacet + facet normal 0.451143 -0.0324602 0.891861 + outer loop + vertex 1.00197 1.35402 2.63126 + vertex 0.999081 1.35346 2.63271 + vertex 1.00166 1.35088 2.63131 + endloop + endfacet + facet normal 0.449024 -0.035103 0.89283 + outer loop + vertex 0.999081 1.35346 2.63271 + vertex 0.998311 1.34803 2.63288 + vertex 1.00166 1.35088 2.63131 + endloop + endfacet + facet normal 0.428793 -0.0319063 0.902839 + outer loop + vertex 0.998311 1.34803 2.63288 + vertex 0.999081 1.35346 2.63271 + vertex 0.995004 1.34982 2.63451 + endloop + endfacet + facet normal 0.426034 -0.0380032 0.903909 + outer loop + vertex 0.994714 1.34473 2.63444 + vertex 0.998311 1.34803 2.63288 + vertex 0.995004 1.34982 2.63451 + endloop + endfacet + facet normal 0.38773 -0.036082 0.921067 + outer loop + vertex 0.994714 1.34473 2.63444 + vertex 0.995004 1.34982 2.63451 + vertex 0.991271 1.34624 2.63594 + endloop + endfacet + facet normal 0.38524 -0.0425569 0.921835 + outer loop + vertex 0.991113 1.34124 2.63578 + vertex 0.994714 1.34473 2.63444 + vertex 0.991271 1.34624 2.63594 + endloop + endfacet + facet normal 0.316381 -0.0412293 0.947736 + outer loop + vertex 0.991271 1.34624 2.63594 + vertex 0.987434 1.34235 2.63706 + vertex 0.991113 1.34124 2.63578 + endloop + endfacet + facet normal 0.313839 -0.0501375 0.948151 + outer loop + vertex 0.987434 1.34235 2.63706 + vertex 0.987327 1.33736 2.63683 + vertex 0.991113 1.34124 2.63578 + endloop + endfacet + facet normal 0.305136 -0.0407529 0.951437 + outer loop + vertex 0.991113 1.34124 2.63578 + vertex 0.987327 1.33736 2.63683 + vertex 0.990978 1.33625 2.63561 + endloop + endfacet + facet normal 0.379387 -0.041831 0.924292 + outer loop + vertex 0.990978 1.33625 2.63561 + vertex 0.994515 1.3397 2.63431 + vertex 0.991113 1.34124 2.63578 + endloop + endfacet + facet normal 0.375839 -0.0375822 0.925922 + outer loop + vertex 0.994372 1.33469 2.63417 + vertex 0.994515 1.3397 2.63431 + vertex 0.990978 1.33625 2.63561 + endloop + endfacet + facet normal 0.373882 -0.0423859 0.926507 + outer loop + vertex 0.990864 1.33126 2.63543 + vertex 0.994372 1.33469 2.63417 + vertex 0.990978 1.33625 2.63561 + endloop + endfacet + facet normal 0.296152 -0.0416112 0.954234 + outer loop + vertex 0.990978 1.33625 2.63561 + vertex 0.987231 1.33237 2.6366 + vertex 0.990864 1.33126 2.63543 + endloop + endfacet + facet normal 0.293145 -0.0519224 0.954657 + outer loop + vertex 0.987231 1.33237 2.6366 + vertex 0.987158 1.32737 2.63635 + vertex 0.990864 1.33126 2.63543 + endloop + endfacet + facet normal 0.285823 -0.0443349 0.957256 + outer loop + vertex 0.990864 1.33126 2.63543 + vertex 0.987158 1.32737 2.63635 + vertex 0.990756 1.32636 2.63523 + endloop + endfacet + facet normal 0.365987 -0.0449909 0.929532 + outer loop + vertex 0.990756 1.32636 2.63523 + vertex 0.99424 1.32971 2.63402 + vertex 0.990864 1.33126 2.63543 + endloop + endfacet + facet normal 0.362503 -0.0408014 0.931089 + outer loop + vertex 0.993972 1.32467 2.63391 + vertex 0.99424 1.32971 2.63402 + vertex 0.990756 1.32636 2.63523 + endloop + endfacet + facet normal 0.356534 -0.0534419 0.932753 + outer loop + vertex 0.990607 1.32197 2.63504 + vertex 0.993972 1.32467 2.63391 + vertex 0.990756 1.32636 2.63523 + endloop + endfacet + facet normal 0.27326 -0.0518368 0.960543 + outer loop + vertex 0.990756 1.32636 2.63523 + vertex 0.987169 1.32236 2.63604 + vertex 0.990607 1.32197 2.63504 + endloop + endfacet + facet normal 0.271504 -0.0662328 0.960155 + outer loop + vertex 0.987169 1.32236 2.63604 + vertex 0.98764 1.31706 2.63554 + vertex 0.990607 1.32197 2.63504 + endloop + endfacet + facet normal 0.311193 -0.0916611 0.945916 + outer loop + vertex 0.98764 1.31706 2.63554 + vertex 0.992942 1.31881 2.63396 + vertex 0.990607 1.32197 2.63504 + endloop + endfacet + facet normal 0.293517 -0.0294948 0.955499 + outer loop + vertex 0.98764 1.31706 2.63554 + vertex 0.989865 1.31391 2.63476 + vertex 0.992942 1.31881 2.63396 + endloop + endfacet + facet normal 0.331111 -0.0552991 0.94197 + outer loop + vertex 0.992942 1.31881 2.63396 + vertex 0.989865 1.31391 2.63476 + vertex 0.993267 1.31329 2.63353 + endloop + endfacet + facet normal 0.37983 -0.0509773 0.92365 + outer loop + vertex 0.993267 1.31329 2.63353 + vertex 0.997144 1.3175 2.63216 + vertex 0.992942 1.31881 2.63396 + endloop + endfacet + facet normal 0.3825 -0.0415496 0.923021 + outer loop + vertex 0.997144 1.3175 2.63216 + vertex 0.997295 1.32276 2.63234 + vertex 0.992942 1.31881 2.63396 + endloop + endfacet + facet normal 0.397311 -0.0609095 0.91566 + outer loop + vertex 0.992942 1.31881 2.63396 + vertex 0.997295 1.32276 2.63234 + vertex 0.993972 1.32467 2.63391 + endloop + endfacet + facet normal 0.324674 -0.0897552 0.941558 + outer loop + vertex 0.988618 1.30871 2.63469 + vertex 0.993267 1.31329 2.63353 + vertex 0.989865 1.31391 2.63476 + endloop + endfacet + facet normal 0.29923 -0.0612433 0.952214 + outer loop + vertex 0.993075 1.30808 2.63325 + vertex 0.993267 1.31329 2.63353 + vertex 0.988618 1.30871 2.63469 + endloop + endfacet + facet normal 0.295981 -0.0828845 0.951591 + outer loop + vertex 0.988575 1.30329 2.63423 + vertex 0.993075 1.30808 2.63325 + vertex 0.988618 1.30871 2.63469 + endloop + endfacet + facet normal 0.275268 -0.0618263 0.959377 + outer loop + vertex 0.993061 1.30304 2.63293 + vertex 0.993075 1.30808 2.63325 + vertex 0.988575 1.30329 2.63423 + endloop + endfacet + facet normal 0.274302 -0.0756312 0.958665 + outer loop + vertex 0.988562 1.29814 2.63383 + vertex 0.993061 1.30304 2.63293 + vertex 0.988575 1.30329 2.63423 + endloop + endfacet + facet normal 0.261678 -0.0632311 0.963082 + outer loop + vertex 0.993539 1.29799 2.63247 + vertex 0.993061 1.30304 2.63293 + vertex 0.988562 1.29814 2.63383 + endloop + endfacet + facet normal 0.261444 -0.0683034 0.962799 + outer loop + vertex 0.988461 1.29299 2.63349 + vertex 0.993539 1.29799 2.63247 + vertex 0.988562 1.29814 2.63383 + endloop + endfacet + facet normal 0.241082 -0.0462554 0.969402 + outer loop + vertex 0.992779 1.29236 2.63239 + vertex 0.993539 1.29799 2.63247 + vertex 0.988461 1.29299 2.63349 + endloop + endfacet + facet normal 0.237779 -0.0679002 0.968943 + outer loop + vertex 0.988282 1.28791 2.63318 + vertex 0.992779 1.29236 2.63239 + vertex 0.988461 1.29299 2.63349 + endloop + endfacet + facet normal 0.225693 -0.0550202 0.972644 + outer loop + vertex 0.992525 1.28734 2.63216 + vertex 0.992779 1.29236 2.63239 + vertex 0.988282 1.28791 2.63318 + endloop + endfacet + facet normal 0.222812 -0.075273 0.971951 + outer loop + vertex 0.988225 1.28296 2.63281 + vertex 0.992525 1.28734 2.63216 + vertex 0.988282 1.28791 2.63318 + endloop + endfacet + facet normal 0.212321 -0.0645217 0.975068 + outer loop + vertex 0.99241 1.2824 2.63186 + vertex 0.992525 1.28734 2.63216 + vertex 0.988225 1.28296 2.63281 + endloop + endfacet + facet normal 0.209901 -0.0814511 0.974324 + outer loop + vertex 0.988196 1.278 2.6324 + vertex 0.99241 1.2824 2.63186 + vertex 0.988225 1.28296 2.63281 + endloop + endfacet + facet normal 0.199336 -0.0709548 0.977359 + outer loop + vertex 0.99229 1.27744 2.63153 + vertex 0.99241 1.2824 2.63186 + vertex 0.988196 1.278 2.6324 + endloop + endfacet + facet normal 0.197468 -0.0836814 0.976731 + outer loop + vertex 0.988129 1.27303 2.63199 + vertex 0.99229 1.27744 2.63153 + vertex 0.988196 1.278 2.6324 + endloop + endfacet + facet normal 0.369381 -0.0625074 0.927174 + outer loop + vertex 0.993075 1.30808 2.63325 + vertex 0.997107 1.31236 2.63193 + vertex 0.993267 1.31329 2.63353 + endloop + endfacet + facet normal 0.355169 -0.0471464 0.933612 + outer loop + vertex 0.996969 1.30742 2.63174 + vertex 0.997107 1.31236 2.63193 + vertex 0.993075 1.30808 2.63325 + endloop + endfacet + facet normal 0.352945 -0.0604136 0.933692 + outer loop + vertex 0.993061 1.30304 2.63293 + vertex 0.996969 1.30742 2.63174 + vertex 0.993075 1.30808 2.63325 + endloop + endfacet + facet normal 0.356637 -0.0535916 0.932705 + outer loop + vertex 0.992942 1.31881 2.63396 + vertex 0.993972 1.32467 2.63391 + vertex 0.990607 1.32197 2.63504 + endloop + endfacet + facet normal 0.410094 -0.042873 0.911035 + outer loop + vertex 0.993972 1.32467 2.63391 + vertex 0.997554 1.32792 2.63245 + vertex 0.99424 1.32971 2.63402 + endloop + endfacet + facet normal 0.413644 -0.0351653 0.909759 + outer loop + vertex 0.997554 1.32792 2.63245 + vertex 0.997694 1.33292 2.63258 + vertex 0.99424 1.32971 2.63402 + endloop + endfacet + facet normal 0.415501 -0.0375841 0.908816 + outer loop + vertex 0.99424 1.32971 2.63402 + vertex 0.997694 1.33292 2.63258 + vertex 0.994372 1.33469 2.63417 + endloop + endfacet + facet normal 0.281582 -0.0598871 0.957667 + outer loop + vertex 0.987158 1.32737 2.63635 + vertex 0.987169 1.32236 2.63604 + vertex 0.990756 1.32636 2.63523 + endloop + endfacet + facet normal 0.369306 -0.0369336 0.928574 + outer loop + vertex 0.99424 1.32971 2.63402 + vertex 0.994372 1.33469 2.63417 + vertex 0.990864 1.33126 2.63543 + endloop + endfacet + facet normal 0.419197 -0.0382699 0.907088 + outer loop + vertex 0.994372 1.33469 2.63417 + vertex 0.997822 1.33792 2.63271 + vertex 0.994515 1.3397 2.63431 + endloop + endfacet + facet normal 0.420479 -0.0354443 0.90661 + outer loop + vertex 0.997822 1.33792 2.63271 + vertex 0.998 1.34296 2.63282 + vertex 0.994515 1.3397 2.63431 + endloop + endfacet + facet normal 0.423023 -0.0387594 0.905289 + outer loop + vertex 0.994515 1.3397 2.63431 + vertex 0.998 1.34296 2.63282 + vertex 0.994714 1.34473 2.63444 + endloop + endfacet + facet normal 0.302826 -0.0486941 0.951801 + outer loop + vertex 0.987327 1.33736 2.63683 + vertex 0.987231 1.33237 2.6366 + vertex 0.990978 1.33625 2.63561 + endloop + endfacet + facet normal 0.32192 -0.0473143 0.945584 + outer loop + vertex 0.987514 1.34729 2.63728 + vertex 0.987434 1.34235 2.63706 + vertex 0.991271 1.34624 2.63594 + endloop + endfacet + facet normal 0.323694 -0.040616 0.945289 + outer loop + vertex 0.991422 1.3512 2.63611 + vertex 0.987514 1.34729 2.63728 + vertex 0.991271 1.34624 2.63594 + endloop + endfacet + facet normal 0.326839 -0.0441338 0.944049 + outer loop + vertex 0.987604 1.3522 2.63747 + vertex 0.987514 1.34729 2.63728 + vertex 0.991422 1.3512 2.63611 + endloop + endfacet + facet normal 0.328696 -0.0366414 0.943725 + outer loop + vertex 0.991568 1.35609 2.63624 + vertex 0.987604 1.3522 2.63747 + vertex 0.991422 1.3512 2.63611 + endloop + endfacet + facet normal 0.395354 -0.0379025 0.917746 + outer loop + vertex 0.991422 1.3512 2.63611 + vertex 0.995176 1.35487 2.63464 + vertex 0.991568 1.35609 2.63624 + endloop + endfacet + facet normal 0.395693 -0.0367614 0.917647 + outer loop + vertex 0.995176 1.35487 2.63464 + vertex 0.995185 1.35975 2.63483 + vertex 0.991568 1.35609 2.63624 + endloop + endfacet + facet normal 0.395992 -0.0371113 0.917504 + outer loop + vertex 0.991568 1.35609 2.63624 + vertex 0.995185 1.35975 2.63483 + vertex 0.991864 1.36085 2.63631 + endloop + endfacet + facet normal 0.331643 -0.0334639 0.942811 + outer loop + vertex 0.991864 1.36085 2.63631 + vertex 0.987831 1.3572 2.6376 + vertex 0.991568 1.35609 2.63624 + endloop + endfacet + facet normal 0.333526 -0.0358102 0.942061 + outer loop + vertex 0.988561 1.36283 2.63755 + vertex 0.987831 1.3572 2.6376 + vertex 0.991864 1.36085 2.63631 + endloop + endfacet + facet normal 0.337366 -0.028718 0.940935 + outer loop + vertex 0.992506 1.36468 2.6362 + vertex 0.988561 1.36283 2.63755 + vertex 0.991864 1.36085 2.63631 + endloop + endfacet + facet normal 0.401429 -0.040219 0.915007 + outer loop + vertex 0.995157 1.36423 2.63501 + vertex 0.992506 1.36468 2.6362 + vertex 0.991864 1.36085 2.63631 + endloop + endfacet + facet normal 0.402201 -0.0353308 0.914869 + outer loop + vertex 0.994633 1.36742 2.63537 + vertex 0.992506 1.36468 2.6362 + vertex 0.995157 1.36423 2.63501 + endloop + endfacet + facet normal 0.43336 -0.0286506 0.900765 + outer loop + vertex 0.994633 1.36742 2.63537 + vertex 0.995157 1.36423 2.63501 + vertex 0.998022 1.36884 2.63378 + endloop + endfacet + facet normal 0.432812 -0.0269922 0.90108 + outer loop + vertex 0.994633 1.36742 2.63537 + vertex 0.998022 1.36884 2.63378 + vertex 0.995187 1.37125 2.63522 + endloop + endfacet + facet normal 0.388992 -0.0198685 0.921027 + outer loop + vertex 0.995187 1.37125 2.63522 + vertex 0.991914 1.36781 2.63652 + vertex 0.994633 1.36742 2.63537 + endloop + endfacet + facet normal 0.395335 -0.0269991 0.91814 + outer loop + vertex 0.991883 1.3723 2.63667 + vertex 0.991914 1.36781 2.63652 + vertex 0.995187 1.37125 2.63522 + endloop + endfacet + facet normal 0.396249 -0.023698 0.917837 + outer loop + vertex 0.995448 1.37609 2.63523 + vertex 0.991883 1.3723 2.63667 + vertex 0.995187 1.37125 2.63522 + endloop + endfacet + facet normal 0.432725 -0.0256204 0.901162 + outer loop + vertex 0.995187 1.37125 2.63522 + vertex 0.99865 1.37452 2.63365 + vertex 0.995448 1.37609 2.63523 + endloop + endfacet + facet normal 0.433157 -0.0245596 0.900984 + outer loop + vertex 0.99865 1.37452 2.63365 + vertex 0.998884 1.37964 2.63367 + vertex 0.995448 1.37609 2.63523 + endloop + endfacet + facet normal 0.432207 -0.0234239 0.90147 + outer loop + vertex 0.995448 1.37609 2.63523 + vertex 0.998884 1.37964 2.63367 + vertex 0.995554 1.38104 2.63531 + endloop + endfacet + facet normal 0.401843 -0.0229934 0.91542 + outer loop + vertex 0.995554 1.38104 2.63531 + vertex 0.99196 1.37722 2.63679 + vertex 0.995448 1.37609 2.63523 + endloop + endfacet + facet normal 0.405244 -0.026819 0.913815 + outer loop + vertex 0.992048 1.38223 2.6369 + vertex 0.99196 1.37722 2.63679 + vertex 0.995554 1.38104 2.63531 + endloop + endfacet + facet normal 0.406755 -0.0216729 0.91328 + outer loop + vertex 0.995602 1.38597 2.6354 + vertex 0.992048 1.38223 2.6369 + vertex 0.995554 1.38104 2.63531 + endloop + endfacet + facet normal 0.433187 -0.0216948 0.901043 + outer loop + vertex 0.995554 1.38104 2.63531 + vertex 0.998967 1.38458 2.63375 + vertex 0.995602 1.38597 2.6354 + endloop + endfacet + facet normal 0.433486 -0.0208231 0.90092 + outer loop + vertex 0.998967 1.38458 2.63375 + vertex 0.999021 1.3895 2.63384 + vertex 0.995602 1.38597 2.6354 + endloop + endfacet + facet normal 0.434037 -0.021482 0.900639 + outer loop + vertex 0.995602 1.38597 2.6354 + vertex 0.999021 1.3895 2.63384 + vertex 0.995649 1.39092 2.6355 + endloop + endfacet + facet normal 0.409566 -0.0214718 0.912028 + outer loop + vertex 0.995649 1.39092 2.6355 + vertex 0.992113 1.38723 2.637 + vertex 0.995602 1.38597 2.6354 + endloop + endfacet + facet normal 0.411736 -0.0239746 0.910988 + outer loop + vertex 0.992145 1.39225 2.63712 + vertex 0.992113 1.38723 2.637 + vertex 0.995649 1.39092 2.6355 + endloop + endfacet + facet normal 0.412158 -0.0226671 0.91083 + outer loop + vertex 0.995708 1.39593 2.63559 + vertex 0.992145 1.39225 2.63712 + vertex 0.995649 1.39092 2.6355 + endloop + endfacet + facet normal 0.434412 -0.0227277 0.900427 + outer loop + vertex 0.995649 1.39092 2.6355 + vertex 0.999096 1.39444 2.63392 + vertex 0.995708 1.39593 2.63559 + endloop + endfacet + facet normal 0.434974 -0.0211813 0.900194 + outer loop + vertex 0.999096 1.39444 2.63392 + vertex 0.999178 1.39943 2.634 + vertex 0.995708 1.39593 2.63559 + endloop + endfacet + facet normal 0.435965 -0.0223962 0.899685 + outer loop + vertex 0.995708 1.39593 2.63559 + vertex 0.999178 1.39943 2.634 + vertex 0.995783 1.40099 2.63568 + endloop + endfacet + facet normal 0.414603 -0.0222596 0.90973 + outer loop + vertex 0.995783 1.40099 2.63568 + vertex 0.992131 1.39736 2.63726 + vertex 0.995708 1.39593 2.63559 + endloop + endfacet + facet normal 0.415955 -0.0239071 0.909071 + outer loop + vertex 0.992243 1.4026 2.63735 + vertex 0.992131 1.39736 2.63726 + vertex 0.995783 1.40099 2.63568 + endloop + endfacet + facet normal 0.417402 -0.0201337 0.908499 + outer loop + vertex 0.995874 1.40606 2.63576 + vertex 0.992243 1.4026 2.63735 + vertex 0.995783 1.40099 2.63568 + endloop + endfacet + facet normal 0.437868 -0.0203681 0.898809 + outer loop + vertex 0.995783 1.40099 2.63568 + vertex 0.999243 1.40442 2.63408 + vertex 0.995874 1.40606 2.63576 + endloop + endfacet + facet normal 0.439049 -0.0174184 0.898294 + outer loop + vertex 0.999243 1.40442 2.63408 + vertex 0.999287 1.40939 2.63415 + vertex 0.995874 1.40606 2.63576 + endloop + endfacet + facet normal 0.440199 -0.0188837 0.897702 + outer loop + vertex 0.995874 1.40606 2.63576 + vertex 0.999287 1.40939 2.63415 + vertex 0.995952 1.41108 2.63582 + endloop + endfacet + facet normal 0.420338 -0.0187036 0.907175 + outer loop + vertex 0.995952 1.41108 2.63582 + vertex 0.992454 1.40779 2.63738 + vertex 0.995874 1.40606 2.63576 + endloop + endfacet + facet normal 0.421075 -0.0196581 0.906813 + outer loop + vertex 0.992564 1.41283 2.63743 + vertex 0.992454 1.40779 2.63738 + vertex 0.995952 1.41108 2.63582 + endloop + endfacet + facet normal 0.421372 -0.0189722 0.90669 + outer loop + vertex 0.996012 1.41606 2.6359 + vertex 0.992564 1.41283 2.63743 + vertex 0.995952 1.41108 2.63582 + endloop + endfacet + facet normal 0.442605 -0.0190753 0.896514 + outer loop + vertex 0.995952 1.41108 2.63582 + vertex 0.999323 1.41434 2.63423 + vertex 0.996012 1.41606 2.6359 + endloop + endfacet + facet normal 0.442592 -0.0191057 0.89652 + outer loop + vertex 0.999323 1.41434 2.63423 + vertex 0.999374 1.4193 2.63431 + vertex 0.996012 1.41606 2.6359 + endloop + endfacet + facet normal 0.444121 -0.0210857 0.895719 + outer loop + vertex 0.996012 1.41606 2.6359 + vertex 0.999374 1.4193 2.63431 + vertex 0.996088 1.42104 2.63598 + endloop + endfacet + facet normal 0.422528 -0.0209224 0.906108 + outer loop + vertex 0.996088 1.42104 2.63598 + vertex 0.992641 1.41783 2.63751 + vertex 0.996012 1.41606 2.6359 + endloop + endfacet + facet normal 0.423194 -0.0217959 0.905777 + outer loop + vertex 0.992729 1.42282 2.63759 + vertex 0.992641 1.41783 2.63751 + vertex 0.996088 1.42104 2.63598 + endloop + endfacet + facet normal 0.423164 -0.0218638 0.905789 + outer loop + vertex 0.996184 1.42604 2.63605 + vertex 0.992729 1.42282 2.63759 + vertex 0.996088 1.42104 2.63598 + endloop + endfacet + facet normal 0.445936 -0.0221342 0.894791 + outer loop + vertex 0.996088 1.42104 2.63598 + vertex 0.999448 1.42428 2.63438 + vertex 0.996184 1.42604 2.63605 + endloop + endfacet + facet normal 0.446757 -0.0202653 0.894426 + outer loop + vertex 0.999448 1.42428 2.63438 + vertex 0.999534 1.42928 2.63445 + vertex 0.996184 1.42604 2.63605 + endloop + endfacet + facet normal 0.447542 -0.0212808 0.894009 + outer loop + vertex 0.996184 1.42604 2.63605 + vertex 0.999534 1.42928 2.63445 + vertex 0.996282 1.43104 2.63612 + endloop + endfacet + facet normal 0.424165 -0.0209818 0.905342 + outer loop + vertex 0.996282 1.43104 2.63612 + vertex 0.992832 1.42781 2.63767 + vertex 0.996184 1.42604 2.63605 + endloop + endfacet + facet normal 0.423364 -0.0199362 0.90574 + outer loop + vertex 0.992925 1.43281 2.63773 + vertex 0.992832 1.42781 2.63767 + vertex 0.996282 1.43104 2.63612 + endloop + endfacet + facet normal 0.424225 -0.0179641 0.905378 + outer loop + vertex 0.996364 1.43605 2.63619 + vertex 0.992925 1.43281 2.63773 + vertex 0.996282 1.43104 2.63612 + endloop + endfacet + facet normal 0.448185 -0.0182131 0.893755 + outer loop + vertex 0.996282 1.43104 2.63612 + vertex 0.999617 1.4343 2.63452 + vertex 0.996364 1.43605 2.63619 + endloop + endfacet + facet normal 0.448809 -0.016782 0.89347 + outer loop + vertex 0.999617 1.4343 2.63452 + vertex 0.999692 1.43931 2.63457 + vertex 0.996364 1.43605 2.63619 + endloop + endfacet + facet normal 0.446992 -0.0144584 0.894421 + outer loop + vertex 0.996364 1.43605 2.63619 + vertex 0.999692 1.43931 2.63457 + vertex 0.996425 1.44104 2.63624 + endloop + endfacet + facet normal 0.423747 -0.0142852 0.905668 + outer loop + vertex 0.996425 1.44104 2.63624 + vertex 0.992996 1.4378 2.63779 + vertex 0.996364 1.43605 2.63619 + endloop + endfacet + facet normal 0.422515 -0.0126966 0.906267 + outer loop + vertex 0.993048 1.44279 2.63783 + vertex 0.992996 1.4378 2.63779 + vertex 0.996425 1.44104 2.63624 + endloop + endfacet + facet normal 0.422817 -0.0119912 0.906136 + outer loop + vertex 0.996476 1.44604 2.63628 + vertex 0.993048 1.44279 2.63783 + vertex 0.996425 1.44104 2.63624 + endloop + endfacet + facet normal 0.44594 -0.012128 0.894981 + outer loop + vertex 0.996425 1.44104 2.63624 + vertex 0.999753 1.44431 2.63462 + vertex 0.996476 1.44604 2.63628 + endloop + endfacet + facet normal 0.446036 -0.0119009 0.894936 + outer loop + vertex 0.999753 1.44431 2.63462 + vertex 0.999806 1.44931 2.63466 + vertex 0.996476 1.44604 2.63628 + endloop + endfacet + facet normal 0.445234 -0.0108802 0.895348 + outer loop + vertex 0.996476 1.44604 2.63628 + vertex 0.999806 1.44931 2.63466 + vertex 0.996521 1.45103 2.63632 + endloop + endfacet + facet normal 0.421854 -0.0107543 0.9066 + outer loop + vertex 0.996521 1.45103 2.63632 + vertex 0.993093 1.44778 2.63787 + vertex 0.996476 1.44604 2.63628 + endloop + endfacet + facet normal 0.422003 -0.0109459 0.906528 + outer loop + vertex 0.993139 1.45277 2.63791 + vertex 0.993093 1.44778 2.63787 + vertex 0.996521 1.45103 2.63632 + endloop + endfacet + facet normal 0.421878 -0.0112375 0.906583 + outer loop + vertex 0.996567 1.45602 2.63636 + vertex 0.993139 1.45277 2.63791 + vertex 0.996521 1.45103 2.63632 + endloop + endfacet + facet normal 0.444317 -0.0113587 0.895798 + outer loop + vertex 0.996521 1.45103 2.63632 + vertex 0.99986 1.4543 2.6347 + vertex 0.996567 1.45602 2.63636 + endloop + endfacet + facet normal 0.444273 -0.0114639 0.895818 + outer loop + vertex 0.99986 1.4543 2.6347 + vertex 0.999912 1.45929 2.63474 + vertex 0.996567 1.45602 2.63636 + endloop + endfacet + facet normal 0.444858 -0.0122101 0.895518 + outer loop + vertex 0.996567 1.45602 2.63636 + vertex 0.999912 1.45929 2.63474 + vertex 0.996617 1.46101 2.6364 + endloop + endfacet + facet normal 0.422716 -0.0120802 0.906182 + outer loop + vertex 0.996617 1.46101 2.6364 + vertex 0.99319 1.45776 2.63795 + vertex 0.996567 1.45602 2.63636 + endloop + endfacet + facet normal 0.422738 -0.0121089 0.906171 + outer loop + vertex 0.99324 1.46275 2.638 + vertex 0.99319 1.45776 2.63795 + vertex 0.996617 1.46101 2.6364 + endloop + endfacet + facet normal 0.423493 -0.0103412 0.90584 + outer loop + vertex 0.996658 1.466 2.63644 + vertex 0.99324 1.46275 2.638 + vertex 0.996617 1.46101 2.6364 + endloop + endfacet + facet normal 0.444656 -0.0104366 0.895641 + outer loop + vertex 0.996617 1.46101 2.6364 + vertex 0.999962 1.46428 2.63478 + vertex 0.996658 1.466 2.63644 + endloop + endfacet + facet normal 0.445524 -0.00836612 0.895231 + outer loop + vertex 0.999962 1.46428 2.63478 + vertex 0.999996 1.46927 2.63481 + vertex 0.996658 1.466 2.63644 + endloop + endfacet + facet normal 0.444539 -0.00711323 0.895731 + outer loop + vertex 0.996658 1.466 2.63644 + vertex 0.999996 1.46927 2.63481 + vertex 0.996677 1.47099 2.63647 + endloop + endfacet + facet normal 0.424136 -0.00709593 0.905571 + outer loop + vertex 0.996677 1.47099 2.63647 + vertex 0.993273 1.46774 2.63804 + vertex 0.996658 1.466 2.63644 + endloop + endfacet + facet normal 0.422772 -0.00535342 0.90622 + outer loop + vertex 0.993272 1.47272 2.63807 + vertex 0.993273 1.46774 2.63804 + vertex 0.996677 1.47099 2.63647 + endloop + endfacet + facet normal 0.423978 -0.00248427 0.905669 + outer loop + vertex 0.996663 1.47597 2.63649 + vertex 0.993272 1.47272 2.63807 + vertex 0.996677 1.47099 2.63647 + endloop + endfacet + facet normal 0.443932 -0.00238893 0.896057 + outer loop + vertex 0.996677 1.47099 2.63647 + vertex 1.00001 1.47426 2.63483 + vertex 0.996663 1.47597 2.63649 + endloop + endfacet + facet normal 0.422494 -0.000597627 0.906366 + outer loop + vertex 0.99324 1.4777 2.63808 + vertex 0.993272 1.47272 2.63807 + vertex 0.996663 1.47597 2.63649 + endloop + endfacet + facet normal 0.423095 0.000851235 0.906085 + outer loop + vertex 0.99664 1.48096 2.63649 + vertex 0.99324 1.4777 2.63808 + vertex 0.996663 1.47597 2.63649 + endloop + endfacet + facet normal 0.42222 0.00196236 0.906491 + outer loop + vertex 0.993237 1.4827 2.63808 + vertex 0.99324 1.4777 2.63808 + vertex 0.99664 1.48096 2.63649 + endloop + endfacet + facet normal 0.421848 0.0010725 0.906666 + outer loop + vertex 0.996687 1.48595 2.63647 + vertex 0.993237 1.4827 2.63808 + vertex 0.99664 1.48096 2.63649 + endloop + endfacet + facet normal 0.422299 0.000490444 0.906456 + outer loop + vertex 0.993392 1.48778 2.638 + vertex 0.993237 1.4827 2.63808 + vertex 0.996687 1.48595 2.63647 + endloop + endfacet + facet normal 0.420952 -0.00244726 0.90708 + outer loop + vertex 0.996912 1.49082 2.63637 + vertex 0.993392 1.48778 2.638 + vertex 0.996687 1.48595 2.63647 + endloop + endfacet + facet normal 0.44438 -0.00374148 0.895831 + outer loop + vertex 0.996687 1.48595 2.63647 + vertex 1.00001 1.4892 2.63483 + vertex 0.996912 1.49082 2.63637 + endloop + endfacet + facet normal 0.443454 -0.00594265 0.896277 + outer loop + vertex 1.00001 1.4892 2.63483 + vertex 0.999984 1.4938 2.63487 + vertex 0.996912 1.49082 2.63637 + endloop + endfacet + facet normal 0.446092 -0.00933474 0.894939 + outer loop + vertex 0.999984 1.4938 2.63487 + vertex 0.997451 1.49466 2.63615 + vertex 0.996912 1.49082 2.63637 + endloop + endfacet + facet normal 0.419407 -0.00482317 0.907785 + outer loop + vertex 0.997451 1.49466 2.63615 + vertex 0.993974 1.4934 2.63775 + vertex 0.996912 1.49082 2.63637 + endloop + endfacet + facet normal 0.418766 -0.00266633 0.90809 + outer loop + vertex 0.997451 1.49466 2.63615 + vertex 0.996833 1.49788 2.63644 + vertex 0.993974 1.4934 2.63775 + endloop + endfacet + facet normal 0.43709 0.00164655 0.899416 + outer loop + vertex 0.999431 1.49713 2.63518 + vertex 0.996833 1.49788 2.63644 + vertex 0.997451 1.49466 2.63615 + endloop + endfacet + facet normal 0.437528 0.00353863 0.899198 + outer loop + vertex 0.99985 1.50086 2.63496 + vertex 0.996833 1.49788 2.63644 + vertex 0.999431 1.49713 2.63518 + endloop + endfacet + facet normal 0.458788 0.000528905 0.888545 + outer loop + vertex 0.999431 1.49713 2.63518 + vertex 1.00268 1.49794 2.6335 + vertex 0.99985 1.50086 2.63496 + endloop + endfacet + facet normal 0.456757 -0.00196092 0.88959 + outer loop + vertex 1.00268 1.49794 2.6335 + vertex 1.00312 1.50357 2.63329 + vertex 0.99985 1.50086 2.63496 + endloop + endfacet + facet normal 0.455638 -0.000256094 0.890165 + outer loop + vertex 0.99985 1.50086 2.63496 + vertex 1.00312 1.50357 2.63329 + vertex 0.999822 1.50561 2.63498 + endloop + endfacet + facet normal 0.438164 -0.000388352 0.898895 + outer loop + vertex 0.999822 1.50561 2.63498 + vertex 0.996624 1.50236 2.63653 + vertex 0.99985 1.50086 2.63496 + endloop + endfacet + facet normal 0.438204 -0.000437545 0.898875 + outer loop + vertex 0.996291 1.50752 2.6367 + vertex 0.996624 1.50236 2.63653 + vertex 0.999822 1.50561 2.63498 + endloop + endfacet + facet normal 0.436262 -0.00485752 0.899807 + outer loop + vertex 0.999822 1.50561 2.63498 + vertex 0.999458 1.50952 2.63517 + vertex 0.996291 1.50752 2.6367 + endloop + endfacet + facet normal 0.437372 -0.00703797 0.899253 + outer loop + vertex 0.997579 1.51141 2.6361 + vertex 0.996291 1.50752 2.6367 + vertex 0.999458 1.50952 2.63517 + endloop + endfacet + facet normal 0.418424 0.000617077 0.908252 + outer loop + vertex 0.997579 1.51141 2.6361 + vertex 0.994256 1.51234 2.63763 + vertex 0.996291 1.50752 2.6367 + endloop + endfacet + facet normal 0.416262 -0.000489051 0.909245 + outer loop + vertex 0.994256 1.51234 2.63763 + vertex 0.992687 1.50744 2.63835 + vertex 0.996291 1.50752 2.6367 + endloop + endfacet + facet normal 0.416267 -0.0007505 0.909242 + outer loop + vertex 0.993129 1.50334 2.63814 + vertex 0.996291 1.50752 2.6367 + vertex 0.992687 1.50744 2.63835 + endloop + endfacet + facet normal 0.404616 -0.00226838 0.914484 + outer loop + vertex 0.993129 1.50334 2.63814 + vertex 0.992687 1.50744 2.63835 + vertex 0.989758 1.50448 2.63964 + endloop + endfacet + facet normal 0.405263 0.00375543 0.914193 + outer loop + vertex 0.992687 1.50744 2.63835 + vertex 0.994256 1.51234 2.63763 + vertex 0.989924 1.50933 2.63957 + endloop + endfacet + facet normal 0.418887 0.00262876 0.908034 + outer loop + vertex 0.997343 1.51371 2.63621 + vertex 0.994256 1.51234 2.63763 + vertex 0.997579 1.51141 2.6361 + endloop + endfacet + facet normal 0.416061 0.0103187 0.909278 + outer loop + vertex 0.997343 1.51371 2.63621 + vertex 0.997214 1.51738 2.63622 + vertex 0.994256 1.51234 2.63763 + endloop + endfacet + facet normal 0.42155 0.0063932 0.906782 + outer loop + vertex 0.997214 1.51738 2.63622 + vertex 0.992987 1.51708 2.63819 + vertex 0.994256 1.51234 2.63763 + endloop + endfacet + facet normal 0.406094 0.00142268 0.91383 + outer loop + vertex 0.994256 1.51234 2.63763 + vertex 0.992987 1.51708 2.63819 + vertex 0.989952 1.51428 2.63954 + endloop + endfacet + facet normal 0.421758 0.00295686 0.906704 + outer loop + vertex 0.993894 1.52187 2.63775 + vertex 0.992987 1.51708 2.63819 + vertex 0.997214 1.51738 2.63622 + endloop + endfacet + facet normal 0.420157 0.00152148 0.90745 + outer loop + vertex 0.997543 1.52175 2.63606 + vertex 0.993894 1.52187 2.63775 + vertex 0.997214 1.51738 2.63622 + endloop + endfacet + facet normal 0.420298 0.00711377 0.907358 + outer loop + vertex 0.996935 1.52575 2.63631 + vertex 0.993894 1.52187 2.63775 + vertex 0.997543 1.52175 2.63606 + endloop + endfacet + facet normal 0.446125 0.0118178 0.894892 + outer loop + vertex 0.997543 1.52175 2.63606 + vertex 1.00046 1.52363 2.63458 + vertex 0.996935 1.52575 2.63631 + endloop + endfacet + facet normal 0.446434 0.0112219 0.894746 + outer loop + vertex 0.999359 1.52027 2.63518 + vertex 1.00046 1.52363 2.63458 + vertex 0.997543 1.52175 2.63606 + endloop + endfacet + facet normal 0.419617 0.00776293 0.907668 + outer loop + vertex 0.993301 1.5275 2.63798 + vertex 0.993894 1.52187 2.63775 + vertex 0.996935 1.52575 2.63631 + endloop + endfacet + facet normal 0.41987 0.00840671 0.907545 + outer loop + vertex 0.996606 1.53083 2.63642 + vertex 0.993301 1.5275 2.63798 + vertex 0.996935 1.52575 2.63631 + endloop + endfacet + facet normal 0.441912 0.0100494 0.897002 + outer loop + vertex 0.996935 1.52575 2.63631 + vertex 1.00005 1.529 2.63474 + vertex 0.996606 1.53083 2.63642 + endloop + endfacet + facet normal 0.441719 0.00959396 0.897102 + outer loop + vertex 1.00005 1.529 2.63474 + vertex 0.999867 1.53413 2.63478 + vertex 0.996606 1.53083 2.63642 + endloop + endfacet + facet normal 0.440644 0.0109103 0.897615 + outer loop + vertex 0.996606 1.53083 2.63642 + vertex 0.999867 1.53413 2.63478 + vertex 0.996507 1.53591 2.6364 + endloop + endfacet + facet normal 0.418419 0.0105043 0.908193 + outer loop + vertex 0.996507 1.53591 2.6364 + vertex 0.993128 1.53266 2.638 + vertex 0.996606 1.53083 2.63642 + endloop + endfacet + facet normal 0.417944 0.0111012 0.908405 + outer loop + vertex 0.9931 1.53768 2.63795 + vertex 0.993128 1.53266 2.638 + vertex 0.996507 1.53591 2.6364 + endloop + endfacet + facet normal 0.418405 0.0121886 0.908179 + outer loop + vertex 0.996493 1.5409 2.63634 + vertex 0.9931 1.53768 2.63795 + vertex 0.996507 1.53591 2.6364 + endloop + endfacet + facet normal 0.440857 0.0121223 0.897496 + outer loop + vertex 0.996507 1.53591 2.6364 + vertex 0.999812 1.53917 2.63474 + vertex 0.996493 1.5409 2.63634 + endloop + endfacet + facet normal 0.441461 0.0135717 0.897178 + outer loop + vertex 0.999812 1.53917 2.63474 + vertex 0.999782 1.54414 2.63468 + vertex 0.996493 1.5409 2.63634 + endloop + endfacet + facet normal 0.442109 0.0127549 0.896871 + outer loop + vertex 0.996493 1.5409 2.63634 + vertex 0.999782 1.54414 2.63468 + vertex 0.996468 1.54587 2.63629 + endloop + endfacet + facet normal 0.419362 0.0127666 0.907729 + outer loop + vertex 0.996468 1.54587 2.63629 + vertex 0.993093 1.54265 2.63789 + vertex 0.996493 1.5409 2.63634 + endloop + endfacet + facet normal 0.419913 0.0120675 0.907484 + outer loop + vertex 0.993054 1.54762 2.63784 + vertex 0.993093 1.54265 2.63789 + vertex 0.996468 1.54587 2.63629 + endloop + endfacet + facet normal 0.420611 0.0137386 0.907137 + outer loop + vertex 0.996408 1.55084 2.63624 + vertex 0.993054 1.54762 2.63784 + vertex 0.996468 1.54587 2.63629 + endloop + endfacet + facet normal 0.4434 0.0139128 0.896216 + outer loop + vertex 0.996468 1.54587 2.63629 + vertex 0.999726 1.5491 2.63462 + vertex 0.996408 1.55084 2.63624 + endloop + endfacet + facet normal 0.444237 0.0159257 0.895768 + outer loop + vertex 0.999726 1.5491 2.63462 + vertex 0.999642 1.55408 2.63458 + vertex 0.996408 1.55084 2.63624 + endloop + endfacet + facet normal 0.444094 0.0161036 0.895836 + outer loop + vertex 0.996408 1.55084 2.63624 + vertex 0.999642 1.55408 2.63458 + vertex 0.996323 1.55583 2.63619 + endloop + endfacet + facet normal 0.420903 0.0158138 0.906968 + outer loop + vertex 0.996323 1.55583 2.63619 + vertex 0.992984 1.5526 2.6378 + vertex 0.996408 1.55084 2.63624 + endloop + endfacet + facet normal 0.420448 0.0163851 0.907168 + outer loop + vertex 0.9929 1.55759 2.63775 + vertex 0.992984 1.5526 2.6378 + vertex 0.996323 1.55583 2.63619 + endloop + endfacet + facet normal 0.421189 0.0181518 0.906791 + outer loop + vertex 0.996229 1.56081 2.63614 + vertex 0.9929 1.55759 2.63775 + vertex 0.996323 1.55583 2.63619 + endloop + endfacet + facet normal 0.443526 0.0184508 0.896071 + outer loop + vertex 0.996323 1.55583 2.63619 + vertex 0.999553 1.55906 2.63453 + vertex 0.996229 1.56081 2.63614 + endloop + endfacet + facet normal 0.44361 0.0186513 0.896026 + outer loop + vertex 0.999553 1.55906 2.63453 + vertex 0.999465 1.56405 2.63447 + vertex 0.996229 1.56081 2.63614 + endloop + endfacet + facet normal 0.443116 0.019265 0.896257 + outer loop + vertex 0.996229 1.56081 2.63614 + vertex 0.999465 1.56405 2.63447 + vertex 0.996136 1.56579 2.63607 + endloop + endfacet + facet normal 0.420593 0.0189787 0.907051 + outer loop + vertex 0.996136 1.56579 2.63607 + vertex 0.992809 1.56258 2.63768 + vertex 0.996229 1.56081 2.63614 + endloop + endfacet + facet normal 0.420551 0.0190304 0.907069 + outer loop + vertex 0.99272 1.56756 2.63762 + vertex 0.992809 1.56258 2.63768 + vertex 0.996136 1.56579 2.63607 + endloop + endfacet + facet normal 0.420378 0.0186179 0.907158 + outer loop + vertex 0.996047 1.57078 2.63601 + vertex 0.99272 1.56756 2.63762 + vertex 0.996136 1.56579 2.63607 + endloop + endfacet + facet normal 0.44282 0.0188867 0.896411 + outer loop + vertex 0.996136 1.56579 2.63607 + vertex 0.999384 1.56904 2.6344 + vertex 0.996047 1.57078 2.63601 + endloop + endfacet + facet normal 0.442407 0.0178869 0.896636 + outer loop + vertex 0.999384 1.56904 2.6344 + vertex 0.999312 1.57403 2.63434 + vertex 0.996047 1.57078 2.63601 + endloop + endfacet + facet normal 0.442121 0.018243 0.89677 + outer loop + vertex 0.996047 1.57078 2.63601 + vertex 0.999312 1.57403 2.63434 + vertex 0.995963 1.57576 2.63595 + endloop + endfacet + facet normal 0.421182 0.0180093 0.906797 + outer loop + vertex 0.995963 1.57576 2.63595 + vertex 0.992634 1.57255 2.63756 + vertex 0.996047 1.57078 2.63601 + endloop + endfacet + facet normal 0.421556 0.0175396 0.906633 + outer loop + vertex 0.992547 1.57754 2.63751 + vertex 0.992634 1.57255 2.63756 + vertex 0.995963 1.57576 2.63595 + endloop + endfacet + facet normal 0.421899 0.0183525 0.906457 + outer loop + vertex 0.995881 1.58075 2.63589 + vertex 0.992547 1.57754 2.63751 + vertex 0.995963 1.57576 2.63595 + endloop + endfacet + facet normal 0.441107 0.018552 0.897263 + outer loop + vertex 0.995963 1.57576 2.63595 + vertex 0.999248 1.57903 2.63427 + vertex 0.995881 1.58075 2.63589 + endloop + endfacet + facet normal 0.44107 0.0184594 0.897283 + outer loop + vertex 0.999248 1.57903 2.63427 + vertex 0.999184 1.58404 2.6342 + vertex 0.995881 1.58075 2.63589 + endloop + endfacet + facet normal 0.439668 0.0202025 0.897933 + outer loop + vertex 0.995881 1.58075 2.63589 + vertex 0.999184 1.58404 2.6342 + vertex 0.9958 1.58575 2.63582 + endloop + endfacet + facet normal 0.422055 0.0200387 0.906349 + outer loop + vertex 0.9958 1.58575 2.63582 + vertex 0.992463 1.58254 2.63744 + vertex 0.995881 1.58075 2.63589 + endloop + endfacet + facet normal 0.421886 0.0202509 0.906423 + outer loop + vertex 0.992385 1.58752 2.63737 + vertex 0.992463 1.58254 2.63744 + vertex 0.9958 1.58575 2.63582 + endloop + endfacet + facet normal 0.422475 0.021656 0.906116 + outer loop + vertex 0.995715 1.59074 2.63574 + vertex 0.992385 1.58752 2.63737 + vertex 0.9958 1.58575 2.63582 + endloop + endfacet + facet normal 0.438365 0.0218053 0.898533 + outer loop + vertex 0.9958 1.58575 2.63582 + vertex 0.999113 1.58906 2.63412 + vertex 0.995715 1.59074 2.63574 + endloop + endfacet + facet normal 0.438279 0.0215869 0.89858 + outer loop + vertex 0.999113 1.58906 2.63412 + vertex 0.999034 1.59406 2.63404 + vertex 0.995715 1.59074 2.63574 + endloop + endfacet + facet normal 0.437623 0.0223957 0.898879 + outer loop + vertex 0.995715 1.59074 2.63574 + vertex 0.999034 1.59406 2.63404 + vertex 0.995615 1.5957 2.63566 + endloop + endfacet + facet normal 0.422373 0.0221995 0.90615 + outer loop + vertex 0.995615 1.5957 2.63566 + vertex 0.992294 1.59248 2.63729 + vertex 0.995715 1.59074 2.63574 + endloop + endfacet + facet normal 0.42208 0.0225652 0.906278 + outer loop + vertex 0.992154 1.5974 2.63723 + vertex 0.992294 1.59248 2.63729 + vertex 0.995615 1.5957 2.63566 + endloop + endfacet + facet normal 0.421915 0.0221487 0.906365 + outer loop + vertex 0.995505 1.60066 2.63559 + vertex 0.992154 1.5974 2.63723 + vertex 0.995615 1.5957 2.63566 + endloop + endfacet + facet normal 0.437106 0.0223862 0.899131 + outer loop + vertex 0.995615 1.5957 2.63566 + vertex 0.998952 1.59906 2.63396 + vertex 0.995505 1.60066 2.63559 + endloop + endfacet + facet normal 0.436649 0.0211447 0.899383 + outer loop + vertex 0.998952 1.59906 2.63396 + vertex 0.998893 1.60407 2.63387 + vertex 0.995505 1.60066 2.63559 + endloop + endfacet + facet normal 0.435917 0.0220405 0.899717 + outer loop + vertex 0.995505 1.60066 2.63559 + vertex 0.998893 1.60407 2.63387 + vertex 0.995447 1.60562 2.6355 + endloop + endfacet + facet normal 0.420557 0.0219996 0.906999 + outer loop + vertex 0.995447 1.60562 2.6355 + vertex 0.991976 1.60237 2.63719 + vertex 0.995505 1.60066 2.63559 + endloop + endfacet + facet normal 0.419037 0.023962 0.907653 + outer loop + vertex 0.992037 1.60726 2.63703 + vertex 0.991976 1.60237 2.63719 + vertex 0.995447 1.60562 2.6355 + endloop + endfacet + facet normal 0.418644 0.0229527 0.90786 + outer loop + vertex 0.995456 1.61057 2.63537 + vertex 0.992037 1.60726 2.63703 + vertex 0.995447 1.60562 2.6355 + endloop + endfacet + facet normal 0.435002 0.0227216 0.900143 + outer loop + vertex 0.995447 1.60562 2.6355 + vertex 0.998875 1.60911 2.63375 + vertex 0.995456 1.61057 2.63537 + endloop + endfacet + facet normal 0.434993 0.0226961 0.900148 + outer loop + vertex 0.998875 1.60911 2.63375 + vertex 0.998858 1.61415 2.63364 + vertex 0.995456 1.61057 2.63537 + endloop + endfacet + facet normal 0.432724 0.0253513 0.90117 + outer loop + vertex 0.995456 1.61057 2.63537 + vertex 0.998858 1.61415 2.63364 + vertex 0.99541 1.61551 2.63525 + endloop + endfacet + facet normal 0.416407 0.0253792 0.908824 + outer loop + vertex 0.99541 1.61551 2.63525 + vertex 0.992104 1.61195 2.63687 + vertex 0.995456 1.61057 2.63537 + endloop + endfacet + facet normal 0.413924 0.028166 0.909875 + outer loop + vertex 0.991904 1.61672 2.63681 + vertex 0.992104 1.61195 2.63687 + vertex 0.99541 1.61551 2.63525 + endloop + endfacet + facet normal 0.413746 0.0275212 0.909976 + outer loop + vertex 0.995185 1.62043 2.63521 + vertex 0.991904 1.61672 2.63681 + vertex 0.99541 1.61551 2.63525 + endloop + endfacet + facet normal 0.430794 0.0282241 0.902009 + outer loop + vertex 0.99541 1.61551 2.63525 + vertex 0.998713 1.61915 2.63356 + vertex 0.995185 1.62043 2.63521 + endloop + endfacet + facet normal 0.430472 0.0270962 0.902197 + outer loop + vertex 0.998713 1.61915 2.63356 + vertex 0.998285 1.62411 2.63362 + vertex 0.995185 1.62043 2.63521 + endloop + endfacet + facet normal 0.428331 0.0293102 0.903146 + outer loop + vertex 0.995185 1.62043 2.63521 + vertex 0.998285 1.62411 2.63362 + vertex 0.994712 1.62523 2.63528 + endloop + endfacet + facet normal 0.411535 0.0275465 0.910978 + outer loop + vertex 0.994712 1.62523 2.63528 + vertex 0.991581 1.62168 2.6368 + vertex 0.995185 1.62043 2.63521 + endloop + endfacet + facet normal 0.427253 0.0249186 0.903789 + outer loop + vertex 0.998285 1.62411 2.63362 + vertex 0.997354 1.62881 2.63393 + vertex 0.994712 1.62523 2.63528 + endloop + endfacet + facet normal 0.423581 0.0282474 0.905418 + outer loop + vertex 0.994262 1.62918 2.63536 + vertex 0.994712 1.62523 2.63528 + vertex 0.997354 1.62881 2.63393 + endloop + endfacet + facet normal 0.423466 0.0269252 0.905512 + outer loop + vertex 0.994262 1.62918 2.63536 + vertex 0.997354 1.62881 2.63393 + vertex 0.995574 1.63341 2.63462 + endloop + endfacet + facet normal 0.413221 0.0309103 0.910106 + outer loop + vertex 0.994262 1.62918 2.63536 + vertex 0.995574 1.63341 2.63462 + vertex 0.992275 1.63135 2.63619 + endloop + endfacet + facet normal 0.41346 0.0304553 0.910013 + outer loop + vertex 0.992275 1.63135 2.63619 + vertex 0.995574 1.63341 2.63462 + vertex 0.991776 1.63553 2.63628 + endloop + endfacet + facet normal 0.397101 0.0283495 0.917337 + outer loop + vertex 0.991776 1.63553 2.63628 + vertex 0.988501 1.63162 2.63782 + vertex 0.992275 1.63135 2.63619 + endloop + endfacet + facet normal 0.397231 0.0311339 0.91719 + outer loop + vertex 0.992275 1.63135 2.63619 + vertex 0.988501 1.63162 2.63782 + vertex 0.991024 1.62699 2.63688 + endloop + endfacet + facet normal 0.412341 0.0279969 0.910599 + outer loop + vertex 0.995574 1.63341 2.63462 + vertex 0.995023 1.63888 2.6347 + vertex 0.991776 1.63553 2.63628 + endloop + endfacet + facet normal 0.409831 0.030917 0.911637 + outer loop + vertex 0.991776 1.63553 2.63628 + vertex 0.995023 1.63888 2.6347 + vertex 0.991356 1.64059 2.6363 + endloop + endfacet + facet normal 0.387904 0.0290621 0.921241 + outer loop + vertex 0.991356 1.64059 2.6363 + vertex 0.987846 1.63729 2.63788 + vertex 0.991776 1.63553 2.63628 + endloop + endfacet + facet normal 0.409333 0.0296012 0.911905 + outer loop + vertex 0.995023 1.63888 2.6347 + vertex 0.994723 1.64399 2.63467 + vertex 0.991356 1.64059 2.6363 + endloop + endfacet + facet normal 0.407542 0.0317233 0.912635 + outer loop + vertex 0.991356 1.64059 2.6363 + vertex 0.994723 1.64399 2.63467 + vertex 0.991162 1.64556 2.63621 + endloop + endfacet + facet normal 0.380384 0.0308681 0.924313 + outer loop + vertex 0.991162 1.64556 2.63621 + vertex 0.987597 1.64232 2.63778 + vertex 0.991356 1.64059 2.6363 + endloop + endfacet + facet normal 0.40743 0.0314107 0.912696 + outer loop + vertex 0.994723 1.64399 2.63467 + vertex 0.994609 1.64903 2.63455 + vertex 0.991162 1.64556 2.63621 + endloop + endfacet + facet normal 0.40582 0.0333189 0.913345 + outer loop + vertex 0.991162 1.64556 2.63621 + vertex 0.994609 1.64903 2.63455 + vertex 0.991059 1.65049 2.63608 + endloop + endfacet + facet normal 0.373258 0.0330124 0.92714 + outer loop + vertex 0.991059 1.65049 2.63608 + vertex 0.9875 1.64695 2.63763 + vertex 0.991162 1.64556 2.63621 + endloop + endfacet + facet normal 0.366502 0.0408579 0.92952 + outer loop + vertex 0.987256 1.65161 2.63753 + vertex 0.9875 1.64695 2.63763 + vertex 0.991059 1.65049 2.63608 + endloop + endfacet + facet normal 0.364595 0.0330002 0.930581 + outer loop + vertex 0.990964 1.6555 2.63593 + vertex 0.987256 1.65161 2.63753 + vertex 0.991059 1.65049 2.63608 + endloop + endfacet + facet normal 0.403054 0.0332784 0.914571 + outer loop + vertex 0.991059 1.65049 2.63608 + vertex 0.994544 1.65408 2.63441 + vertex 0.990964 1.6555 2.63593 + endloop + endfacet + facet normal 0.402214 0.0306684 0.915032 + outer loop + vertex 0.994544 1.65408 2.63441 + vertex 0.994462 1.65916 2.63427 + vertex 0.990964 1.6555 2.63593 + endloop + endfacet + facet normal 0.400819 0.0322561 0.915589 + outer loop + vertex 0.990964 1.6555 2.63593 + vertex 0.994462 1.65916 2.63427 + vertex 0.990898 1.66061 2.63578 + endloop + endfacet + facet normal 0.356322 0.032223 0.933808 + outer loop + vertex 0.990898 1.66061 2.63578 + vertex 0.9871 1.65652 2.63737 + vertex 0.990964 1.6555 2.63593 + endloop + endfacet + facet normal 0.400791 0.0321732 0.915604 + outer loop + vertex 0.994462 1.65916 2.63427 + vertex 0.994351 1.66422 2.63415 + vertex 0.990898 1.66061 2.63578 + endloop + endfacet + facet normal 0.400979 0.0319597 0.91553 + outer loop + vertex 0.990898 1.66061 2.63578 + vertex 0.994351 1.66422 2.63415 + vertex 0.99086 1.66572 2.63562 + endloop + endfacet + facet normal 0.429444 0.032466 0.902509 + outer loop + vertex 0.994462 1.65916 2.63427 + vertex 0.99773 1.66246 2.6326 + vertex 0.994351 1.66422 2.63415 + endloop + endfacet + facet normal 0.430431 0.0312715 0.902082 + outer loop + vertex 0.997851 1.65745 2.63272 + vertex 0.99773 1.66246 2.6326 + vertex 0.994462 1.65916 2.63427 + endloop + endfacet + facet normal 0.430235 0.0307844 0.902192 + outer loop + vertex 0.994544 1.65408 2.63441 + vertex 0.997851 1.65745 2.63272 + vertex 0.994462 1.65916 2.63427 + endloop + endfacet + facet normal 0.430628 0.0303119 0.90202 + outer loop + vertex 0.997926 1.65242 2.63285 + vertex 0.997851 1.65745 2.63272 + vertex 0.994544 1.65408 2.63441 + endloop + endfacet + facet normal 0.430886 0.0309733 0.901875 + outer loop + vertex 0.994609 1.64903 2.63455 + vertex 0.997926 1.65242 2.63285 + vertex 0.994544 1.65408 2.63441 + endloop + endfacet + facet normal 0.430753 0.0311325 0.901933 + outer loop + vertex 0.997989 1.64739 2.63299 + vertex 0.997926 1.65242 2.63285 + vertex 0.994609 1.64903 2.63455 + endloop + endfacet + facet normal 0.405043 0.0309785 0.913773 + outer loop + vertex 0.994609 1.64903 2.63455 + vertex 0.994544 1.65408 2.63441 + vertex 0.991059 1.65049 2.63608 + endloop + endfacet + facet normal 0.430963 0.0316764 0.901814 + outer loop + vertex 0.994723 1.64399 2.63467 + vertex 0.997989 1.64739 2.63299 + vertex 0.994609 1.64903 2.63455 + endloop + endfacet + facet normal 0.431206 0.0313895 0.901707 + outer loop + vertex 0.998157 1.64235 2.63309 + vertex 0.997989 1.64739 2.63299 + vertex 0.994723 1.64399 2.63467 + endloop + endfacet + facet normal 0.430987 0.0308108 0.901832 + outer loop + vertex 0.995023 1.63888 2.6347 + vertex 0.998157 1.64235 2.63309 + vertex 0.994723 1.64399 2.63467 + endloop + endfacet + facet normal 0.431584 0.0301495 0.901569 + outer loop + vertex 0.998599 1.63733 2.63304 + vertex 0.998157 1.64235 2.63309 + vertex 0.995023 1.63888 2.6347 + endloop + endfacet + facet normal 0.431555 0.0300658 0.901585 + outer loop + vertex 0.995574 1.63341 2.63462 + vertex 0.998599 1.63733 2.63304 + vertex 0.995023 1.63888 2.6347 + endloop + endfacet + facet normal 0.434538 0.0272247 0.900242 + outer loop + vertex 0.999551 1.63261 2.63273 + vertex 0.998599 1.63733 2.63304 + vertex 0.995574 1.63341 2.63462 + endloop + endfacet + facet normal 0.435309 0.0323914 0.899698 + outer loop + vertex 0.995574 1.63341 2.63462 + vertex 0.997354 1.62881 2.63393 + vertex 0.999551 1.63261 2.63273 + endloop + endfacet + facet normal 0.412033 0.029345 0.910696 + outer loop + vertex 0.991581 1.62168 2.6368 + vertex 0.991904 1.61672 2.63681 + vertex 0.995185 1.62043 2.63521 + endloop + endfacet + facet normal 0.400088 0.0285812 0.916031 + outer loop + vertex 0.991904 1.61672 2.63681 + vertex 0.991581 1.62168 2.6368 + vertex 0.98835 1.61795 2.63832 + endloop + endfacet + facet normal 0.403293 0.0277775 0.914649 + outer loop + vertex 0.992104 1.61195 2.63687 + vertex 0.991904 1.61672 2.63681 + vertex 0.988708 1.61307 2.63833 + endloop + endfacet + facet normal 0.432891 0.0258912 0.901074 + outer loop + vertex 0.998858 1.61415 2.63364 + vertex 0.998713 1.61915 2.63356 + vertex 0.99541 1.61551 2.63525 + endloop + endfacet + facet normal 0.416493 0.0256365 0.908778 + outer loop + vertex 0.992104 1.61195 2.63687 + vertex 0.992037 1.60726 2.63703 + vertex 0.995456 1.61057 2.63537 + endloop + endfacet + facet normal 0.407762 0.0258978 0.912721 + outer loop + vertex 0.992037 1.60726 2.63703 + vertex 0.992104 1.61195 2.63687 + vertex 0.989294 1.60905 2.63821 + endloop + endfacet + facet normal 0.407858 0.0242649 0.912723 + outer loop + vertex 0.991976 1.60237 2.63719 + vertex 0.992037 1.60726 2.63703 + vertex 0.98817 1.60452 2.63883 + endloop + endfacet + facet normal 0.435811 0.0217423 0.899776 + outer loop + vertex 0.998893 1.60407 2.63387 + vertex 0.998875 1.60911 2.63375 + vertex 0.995447 1.60562 2.6355 + endloop + endfacet + facet normal 0.421042 0.0232372 0.906743 + outer loop + vertex 0.991976 1.60237 2.63719 + vertex 0.992154 1.5974 2.63723 + vertex 0.995505 1.60066 2.63559 + endloop + endfacet + facet normal 0.411416 0.0229326 0.911159 + outer loop + vertex 0.992154 1.5974 2.63723 + vertex 0.991976 1.60237 2.63719 + vertex 0.988633 1.59914 2.63878 + endloop + endfacet + facet normal 0.412425 0.0223426 0.910718 + outer loop + vertex 0.992294 1.59248 2.63729 + vertex 0.992154 1.5974 2.63723 + vertex 0.988877 1.59419 2.6388 + endloop + endfacet + facet normal 0.411741 0.0206799 0.911066 + outer loop + vertex 0.988984 1.58927 2.63886 + vertex 0.992294 1.59248 2.63729 + vertex 0.988877 1.59419 2.6388 + endloop + endfacet + facet normal 0.41084 0.0217972 0.911447 + outer loop + vertex 0.992385 1.58752 2.63737 + vertex 0.992294 1.59248 2.63729 + vertex 0.988984 1.58927 2.63886 + endloop + endfacet + facet normal 0.437456 0.0219568 0.898972 + outer loop + vertex 0.999034 1.59406 2.63404 + vertex 0.998952 1.59906 2.63396 + vertex 0.995615 1.5957 2.63566 + endloop + endfacet + facet normal 0.422261 0.0219248 0.906209 + outer loop + vertex 0.992294 1.59248 2.63729 + vertex 0.992385 1.58752 2.63737 + vertex 0.995715 1.59074 2.63574 + endloop + endfacet + facet normal 0.409313 0.0201391 0.912172 + outer loop + vertex 0.992463 1.58254 2.63744 + vertex 0.992385 1.58752 2.63737 + vertex 0.989044 1.5843 2.63894 + endloop + endfacet + facet normal 0.439665 0.0201932 0.897935 + outer loop + vertex 0.999184 1.58404 2.6342 + vertex 0.999113 1.58906 2.63412 + vertex 0.9958 1.58575 2.63582 + endloop + endfacet + facet normal 0.456387 0.0185459 0.889588 + outer loop + vertex 0.999248 1.57903 2.63427 + vertex 1.00255 1.58238 2.63251 + vertex 0.999184 1.58404 2.6342 + endloop + endfacet + facet normal 0.456701 0.0193659 0.88941 + outer loop + vertex 1.00255 1.58238 2.63251 + vertex 1.0025 1.58741 2.63242 + vertex 0.999184 1.58404 2.6342 + endloop + endfacet + facet normal 0.455951 0.0202953 0.889774 + outer loop + vertex 0.999184 1.58404 2.6342 + vertex 1.0025 1.58741 2.63242 + vertex 0.999113 1.58906 2.63412 + endloop + endfacet + facet normal 0.456289 0.0211898 0.889579 + outer loop + vertex 1.0025 1.58741 2.63242 + vertex 1.00243 1.59243 2.63234 + vertex 0.999113 1.58906 2.63412 + endloop + endfacet + facet normal 0.455858 0.0217225 0.889787 + outer loop + vertex 0.999113 1.58906 2.63412 + vertex 1.00243 1.59243 2.63234 + vertex 0.999034 1.59406 2.63404 + endloop + endfacet + facet normal 0.456175 0.0225754 0.889604 + outer loop + vertex 1.00243 1.59243 2.63234 + vertex 1.00236 1.59747 2.63225 + vertex 0.999034 1.59406 2.63404 + endloop + endfacet + facet normal 0.456551 0.0221123 0.889422 + outer loop + vertex 0.999034 1.59406 2.63404 + vertex 1.00236 1.59747 2.63225 + vertex 0.998952 1.59906 2.63396 + endloop + endfacet + facet normal 0.456967 0.0232638 0.889179 + outer loop + vertex 1.00236 1.59747 2.63225 + vertex 1.00229 1.60251 2.63215 + vertex 0.998952 1.59906 2.63396 + endloop + endfacet + facet normal 0.458649 0.0212077 0.888364 + outer loop + vertex 0.998952 1.59906 2.63396 + vertex 1.00229 1.60251 2.63215 + vertex 0.998893 1.60407 2.63387 + endloop + endfacet + facet normal 0.45909 0.0224512 0.888106 + outer loop + vertex 1.00229 1.60251 2.63215 + vertex 1.00225 1.60756 2.63204 + vertex 0.998893 1.60407 2.63387 + endloop + endfacet + facet normal 0.459826 0.0215554 0.887747 + outer loop + vertex 0.998893 1.60407 2.63387 + vertex 1.00225 1.60756 2.63204 + vertex 0.998875 1.60911 2.63375 + endloop + endfacet + facet normal 0.460281 0.0228425 0.887479 + outer loop + vertex 1.00225 1.60756 2.63204 + vertex 1.00221 1.61259 2.63194 + vertex 0.998875 1.60911 2.63375 + endloop + endfacet + facet normal 0.460576 0.0224847 0.887335 + outer loop + vertex 0.998875 1.60911 2.63375 + vertex 1.00221 1.61259 2.63194 + vertex 0.998858 1.61415 2.63364 + endloop + endfacet + facet normal 0.461441 0.0249086 0.886821 + outer loop + vertex 1.00221 1.61259 2.63194 + vertex 1.00211 1.61757 2.63185 + vertex 0.998858 1.61415 2.63364 + endloop + endfacet + facet normal 0.460143 0.0264723 0.88745 + outer loop + vertex 0.998858 1.61415 2.63364 + vertex 1.00211 1.61757 2.63185 + vertex 0.998713 1.61915 2.63356 + endloop + endfacet + facet normal 0.460469 0.0273813 0.887253 + outer loop + vertex 1.00211 1.61757 2.63185 + vertex 1.00183 1.62256 2.63184 + vertex 0.998713 1.61915 2.63356 + endloop + endfacet + facet normal 0.458488 0.0296704 0.888205 + outer loop + vertex 0.998713 1.61915 2.63356 + vertex 1.00183 1.62256 2.63184 + vertex 0.998285 1.62411 2.63362 + endloop + endfacet + facet normal 0.485509 0.0251636 0.873869 + outer loop + vertex 1.00211 1.61757 2.63185 + vertex 1.00221 1.61259 2.63194 + vertex 1.00526 1.61572 2.63015 + endloop + endfacet + facet normal 0.487268 0.0291953 0.872764 + outer loop + vertex 1.00514 1.62044 2.63006 + vertex 1.00211 1.61757 2.63185 + vertex 1.00526 1.61572 2.63015 + endloop + endfacet + facet normal 0.494521 0.0293151 0.868671 + outer loop + vertex 1.00526 1.61572 2.63015 + vertex 1.00771 1.61811 2.62867 + vertex 1.00514 1.62044 2.63006 + endloop + endfacet + facet normal 0.489362 0.036247 0.871327 + outer loop + vertex 1.00835 1.61401 2.62849 + vertex 1.00771 1.61811 2.62867 + vertex 1.00526 1.61572 2.63015 + endloop + endfacet + facet normal 0.48586 0.0277599 0.873596 + outer loop + vertex 1.00546 1.61091 2.6302 + vertex 1.00835 1.61401 2.62849 + vertex 1.00526 1.61572 2.63015 + endloop + endfacet + facet normal 0.478232 0.0370055 0.877454 + outer loop + vertex 1.00869 1.60915 2.62851 + vertex 1.00835 1.61401 2.62849 + vertex 1.00546 1.61091 2.6302 + endloop + endfacet + facet normal 0.474434 0.0277319 0.879854 + outer loop + vertex 1.00558 1.60592 2.63029 + vertex 1.00869 1.60915 2.62851 + vertex 1.00546 1.61091 2.6302 + endloop + endfacet + facet normal 0.477591 0.0277778 0.878143 + outer loop + vertex 1.00546 1.61091 2.6302 + vertex 1.00225 1.60756 2.63204 + vertex 1.00558 1.60592 2.63029 + endloop + endfacet + facet normal 0.47559 0.0224066 0.879381 + outer loop + vertex 1.00225 1.60756 2.63204 + vertex 1.00229 1.60251 2.63215 + vertex 1.00558 1.60592 2.63029 + endloop + endfacet + facet normal 0.470431 0.0287932 0.881967 + outer loop + vertex 1.00558 1.60592 2.63029 + vertex 1.00229 1.60251 2.63215 + vertex 1.00569 1.60086 2.63039 + endloop + endfacet + facet normal 0.461481 0.0286836 0.886686 + outer loop + vertex 1.00569 1.60086 2.63039 + vertex 1.00894 1.60414 2.6286 + vertex 1.00558 1.60592 2.63029 + endloop + endfacet + facet normal 0.451924 0.040564 0.891134 + outer loop + vertex 1.00919 1.59901 2.6287 + vertex 1.00894 1.60414 2.6286 + vertex 1.00569 1.60086 2.63039 + endloop + endfacet + facet normal 0.446817 0.0281221 0.894183 + outer loop + vertex 1.00579 1.5958 2.6305 + vertex 1.00919 1.59901 2.6287 + vertex 1.00569 1.60086 2.63039 + endloop + endfacet + facet normal 0.464443 0.0282655 0.885152 + outer loop + vertex 1.00569 1.60086 2.63039 + vertex 1.00236 1.59747 2.63225 + vertex 1.00579 1.5958 2.6305 + endloop + endfacet + facet normal 0.443017 0.0331128 0.895902 + outer loop + vertex 1.00923 1.59397 2.62887 + vertex 1.00919 1.59901 2.6287 + vertex 1.00579 1.5958 2.6305 + endloop + endfacet + facet normal 0.439903 0.0256522 0.897679 + outer loop + vertex 1.00586 1.59079 2.63061 + vertex 1.00923 1.59397 2.62887 + vertex 1.00579 1.5958 2.6305 + endloop + endfacet + facet normal 0.459901 0.0256852 0.887599 + outer loop + vertex 1.00579 1.5958 2.6305 + vertex 1.00243 1.59243 2.63234 + vertex 1.00586 1.59079 2.63061 + endloop + endfacet + facet normal 0.43557 0.0313062 0.89961 + outer loop + vertex 1.00928 1.58918 2.62901 + vertex 1.00923 1.59397 2.62887 + vertex 1.00586 1.59079 2.63061 + endloop + endfacet + facet normal 0.432799 0.0238316 0.901175 + outer loop + vertex 1.00594 1.58581 2.6307 + vertex 1.00928 1.58918 2.62901 + vertex 1.00586 1.59079 2.63061 + endloop + endfacet + facet normal 0.456001 0.023998 0.889656 + outer loop + vertex 1.00586 1.59079 2.63061 + vertex 1.0025 1.58741 2.63242 + vertex 1.00594 1.58581 2.6307 + endloop + endfacet + facet normal 0.422693 0.0360366 0.905556 + outer loop + vertex 1.00955 1.58433 2.62908 + vertex 1.00928 1.58918 2.62901 + vertex 1.00594 1.58581 2.6307 + endloop + endfacet + facet normal 0.418269 0.0224649 0.908045 + outer loop + vertex 1.00602 1.58079 2.63079 + vertex 1.00955 1.58433 2.62908 + vertex 1.00594 1.58581 2.6307 + endloop + endfacet + facet normal 0.451614 0.0227215 0.891924 + outer loop + vertex 1.00594 1.58581 2.6307 + vertex 1.00255 1.58238 2.63251 + vertex 1.00602 1.58079 2.63079 + endloop + endfacet + facet normal 0.449791 0.0176371 0.89296 + outer loop + vertex 1.00255 1.58238 2.63251 + vertex 1.00259 1.57735 2.63258 + vertex 1.00602 1.58079 2.63079 + endloop + endfacet + facet normal 0.447392 0.0206197 0.8941 + outer loop + vertex 1.00602 1.58079 2.63079 + vertex 1.00259 1.57735 2.63258 + vertex 1.00605 1.57573 2.63089 + endloop + endfacet + facet normal 0.408295 0.0206964 0.912615 + outer loop + vertex 1.00605 1.57573 2.63089 + vertex 1.0097 1.5793 2.62918 + vertex 1.00602 1.58079 2.63079 + endloop + endfacet + facet normal 0.403331 0.0267474 0.914663 + outer loop + vertex 1.00974 1.57427 2.62931 + vertex 1.0097 1.5793 2.62918 + vertex 1.00605 1.57573 2.63089 + endloop + endfacet + facet normal 0.401008 0.0196031 0.915865 + outer loop + vertex 1.00607 1.57069 2.63099 + vertex 1.00974 1.57427 2.62931 + vertex 1.00605 1.57573 2.63089 + endloop + endfacet + facet normal 0.444932 0.0193353 0.895356 + outer loop + vertex 1.00605 1.57573 2.63089 + vertex 1.00263 1.57232 2.63266 + vertex 1.00607 1.57069 2.63099 + endloop + endfacet + facet normal 0.444265 0.0175568 0.895723 + outer loop + vertex 1.00263 1.57232 2.63266 + vertex 1.00268 1.56731 2.63274 + vertex 1.00607 1.57069 2.63099 + endloop + endfacet + facet normal 0.442453 0.0198139 0.896573 + outer loop + vertex 1.00607 1.57069 2.63099 + vertex 1.00268 1.56731 2.63274 + vertex 1.00609 1.56566 2.63109 + endloop + endfacet + facet normal 0.393508 0.02005 0.919103 + outer loop + vertex 1.00609 1.56566 2.63109 + vertex 1.00977 1.56928 2.62944 + vertex 1.00607 1.57069 2.63099 + endloop + endfacet + facet normal 0.387745 0.0269463 0.921373 + outer loop + vertex 1.00982 1.56426 2.62956 + vertex 1.00977 1.56928 2.62944 + vertex 1.00609 1.56566 2.63109 + endloop + endfacet + facet normal 0.385175 0.0186807 0.922654 + outer loop + vertex 1.00611 1.56063 2.63118 + vertex 1.00982 1.56426 2.62956 + vertex 1.00609 1.56566 2.63109 + endloop + endfacet + facet normal 0.441366 0.0184317 0.897138 + outer loop + vertex 1.00609 1.56566 2.63109 + vertex 1.00273 1.5623 2.63281 + vertex 1.00611 1.56063 2.63118 + endloop + endfacet + facet normal 0.441146 0.0178695 0.897258 + outer loop + vertex 1.00273 1.5623 2.63281 + vertex 1.0028 1.5573 2.63288 + vertex 1.00611 1.56063 2.63118 + endloop + endfacet + facet normal 0.441649 0.0172483 0.897022 + outer loop + vertex 1.00611 1.56063 2.63118 + vertex 1.0028 1.5573 2.63288 + vertex 1.00614 1.5556 2.63127 + endloop + endfacet + facet normal 0.380951 0.0174515 0.924431 + outer loop + vertex 1.00614 1.5556 2.63127 + vertex 1.00981 1.55921 2.62969 + vertex 1.00611 1.56063 2.63118 + endloop + endfacet + facet normal 0.378458 0.0204156 0.925393 + outer loop + vertex 1.0098 1.55417 2.6298 + vertex 1.00981 1.55921 2.62969 + vertex 1.00614 1.5556 2.63127 + endloop + endfacet + facet normal 0.376999 0.0159743 0.926076 + outer loop + vertex 1.00616 1.55059 2.63134 + vertex 1.0098 1.55417 2.6298 + vertex 1.00614 1.5556 2.63127 + endloop + endfacet + facet normal 0.441444 0.0159251 0.897147 + outer loop + vertex 1.00614 1.5556 2.63127 + vertex 1.00287 1.55231 2.63294 + vertex 1.00616 1.55059 2.63134 + endloop + endfacet + facet normal 0.441356 0.0157108 0.897195 + outer loop + vertex 1.00287 1.55231 2.63294 + vertex 1.00293 1.54734 2.63299 + vertex 1.00616 1.55059 2.63134 + endloop + endfacet + facet normal 0.441279 0.0158048 0.897231 + outer loop + vertex 1.00616 1.55059 2.63134 + vertex 1.00293 1.54734 2.63299 + vertex 1.0062 1.5456 2.63142 + endloop + endfacet + facet normal 0.375488 0.0158194 0.926692 + outer loop + vertex 1.0062 1.5456 2.63142 + vertex 1.00979 1.54913 2.6299 + vertex 1.00616 1.55059 2.63134 + endloop + endfacet + facet normal 0.374564 0.0169124 0.927047 + outer loop + vertex 1.00978 1.54411 2.63 + vertex 1.00979 1.54913 2.6299 + vertex 1.0062 1.5456 2.63142 + endloop + endfacet + facet normal 0.373561 0.0140739 0.927499 + outer loop + vertex 1.00622 1.54061 2.63148 + vertex 1.00978 1.54411 2.63 + vertex 1.0062 1.5456 2.63142 + endloop + endfacet + facet normal 0.441979 0.0139415 0.896917 + outer loop + vertex 1.0062 1.5456 2.63142 + vertex 1.00298 1.54237 2.63305 + vertex 1.00622 1.54061 2.63148 + endloop + endfacet + facet normal 0.441637 0.013155 0.897097 + outer loop + vertex 1.00298 1.54237 2.63305 + vertex 1.00302 1.53738 2.6331 + vertex 1.00622 1.54061 2.63148 + endloop + endfacet + facet normal 0.442046 0.012653 0.896903 + outer loop + vertex 1.00622 1.54061 2.63148 + vertex 1.00302 1.53738 2.6331 + vertex 1.00626 1.5356 2.63153 + endloop + endfacet + facet normal 0.37222 0.0123813 0.928062 + outer loop + vertex 1.00626 1.5356 2.63153 + vertex 1.00976 1.53909 2.63008 + vertex 1.00622 1.54061 2.63148 + endloop + endfacet + facet normal 0.37322 0.0112159 0.927675 + outer loop + vertex 1.00976 1.53405 2.63014 + vertex 1.00976 1.53909 2.63008 + vertex 1.00626 1.5356 2.63153 + endloop + endfacet + facet normal 0.372514 0.00934741 0.927979 + outer loop + vertex 1.00636 1.53058 2.63154 + vertex 1.00976 1.53405 2.63014 + vertex 1.00626 1.5356 2.63153 + endloop + endfacet + facet normal 0.441738 0.0106786 0.897081 + outer loop + vertex 1.00626 1.5356 2.63153 + vertex 1.00313 1.53234 2.63312 + vertex 1.00636 1.53058 2.63154 + endloop + endfacet + facet normal 0.440736 0.00837067 0.897598 + outer loop + vertex 1.00313 1.53234 2.63312 + vertex 1.00335 1.52735 2.63305 + vertex 1.00636 1.53058 2.63154 + endloop + endfacet + facet normal 0.440319 0.00885103 0.897798 + outer loop + vertex 1.00636 1.53058 2.63154 + vertex 1.00335 1.52735 2.63305 + vertex 1.00649 1.52569 2.63153 + endloop + endfacet + facet normal 0.372209 0.00685457 0.928124 + outer loop + vertex 1.00649 1.52569 2.63153 + vertex 1.0098 1.52901 2.63018 + vertex 1.00636 1.53058 2.63154 + endloop + endfacet + facet normal 0.370554 0.00876936 0.928769 + outer loop + vertex 1.00983 1.524 2.63021 + vertex 1.0098 1.52901 2.63018 + vertex 1.00649 1.52569 2.63153 + endloop + endfacet + facet normal 0.371863 0.0117827 0.928213 + outer loop + vertex 1.00637 1.5209 2.63164 + vertex 1.00983 1.524 2.63021 + vertex 1.00649 1.52569 2.63153 + endloop + endfacet + facet normal 0.434721 0.00955192 0.900514 + outer loop + vertex 1.00649 1.52569 2.63153 + vertex 1.00377 1.52311 2.63287 + vertex 1.00637 1.5209 2.63164 + endloop + endfacet + facet normal 0.438928 0.0156887 0.898385 + outer loop + vertex 1.00377 1.52311 2.63287 + vertex 1.00221 1.51848 2.63371 + vertex 1.00637 1.5209 2.63164 + endloop + endfacet + facet normal 0.443093 0.00686285 0.896449 + outer loop + vertex 1.00637 1.5209 2.63164 + vertex 1.00221 1.51848 2.63371 + vertex 1.00642 1.51607 2.63165 + endloop + endfacet + facet normal 0.372269 0.00625805 0.928104 + outer loop + vertex 1.00642 1.51607 2.63165 + vertex 1.00988 1.51905 2.63024 + vertex 1.00637 1.5209 2.63164 + endloop + endfacet + facet normal 0.373709 0.00432241 0.927536 + outer loop + vertex 1.00995 1.51414 2.63023 + vertex 1.00988 1.51905 2.63024 + vertex 1.00642 1.51607 2.63165 + endloop + endfacet + facet normal 0.372315 0.00134816 0.928105 + outer loop + vertex 1.00657 1.51128 2.63159 + vertex 1.00995 1.51414 2.63023 + vertex 1.00642 1.51607 2.63165 + endloop + endfacet + facet normal 0.434996 0.00369236 0.900425 + outer loop + vertex 1.00642 1.51607 2.63165 + vertex 1.00371 1.51361 2.63297 + vertex 1.00657 1.51128 2.63159 + endloop + endfacet + facet normal 0.438204 0.00859405 0.898834 + outer loop + vertex 1.00371 1.51361 2.63297 + vertex 1.00286 1.50909 2.63343 + vertex 1.00657 1.51128 2.63159 + endloop + endfacet + facet normal 0.441633 0.00142796 0.897195 + outer loop + vertex 1.00657 1.51128 2.63159 + vertex 1.00286 1.50909 2.63343 + vertex 1.0065 1.50636 2.63164 + endloop + endfacet + facet normal 0.373289 0.00270777 0.927711 + outer loop + vertex 1.0065 1.50636 2.63164 + vertex 1.01 1.50925 2.63022 + vertex 1.00657 1.51128 2.63159 + endloop + endfacet + facet normal 0.37421 0.00141303 0.927343 + outer loop + vertex 1.00998 1.50431 2.63024 + vertex 1.01 1.50925 2.63022 + vertex 1.0065 1.50636 2.63164 + endloop + endfacet + facet normal 0.373034 -0.00090588 0.927817 + outer loop + vertex 1.00643 1.50117 2.63166 + vertex 1.00998 1.50431 2.63024 + vertex 1.0065 1.50636 2.63164 + endloop + endfacet + facet normal 0.439805 -0.00202162 0.898091 + outer loop + vertex 1.0065 1.50636 2.63164 + vertex 1.00312 1.50357 2.63329 + vertex 1.00643 1.50117 2.63166 + endloop + endfacet + facet normal 0.374242 -0.00249833 0.927328 + outer loop + vertex 1.00995 1.49927 2.63024 + vertex 1.00998 1.50431 2.63024 + vertex 1.00643 1.50117 2.63166 + endloop + endfacet + facet normal 0.373749 -0.00356031 0.927523 + outer loop + vertex 1.0064 1.49594 2.63166 + vertex 1.00995 1.49927 2.63024 + vertex 1.00643 1.50117 2.63166 + endloop + endfacet + facet normal 0.44318 -0.00392492 0.896424 + outer loop + vertex 1.00643 1.50117 2.63166 + vertex 1.00268 1.49794 2.6335 + vertex 1.0064 1.49594 2.63166 + endloop + endfacet + facet normal 0.441825 -0.00704584 0.897074 + outer loop + vertex 1.00268 1.49794 2.6335 + vertex 1.00315 1.49258 2.63323 + vertex 1.0064 1.49594 2.63166 + endloop + endfacet + facet normal 0.439396 -0.00413851 0.898284 + outer loop + vertex 1.0064 1.49594 2.63166 + vertex 1.00315 1.49258 2.63323 + vertex 1.00646 1.49081 2.6316 + endloop + endfacet + facet normal 0.37326 -0.00527503 0.927712 + outer loop + vertex 1.00646 1.49081 2.6316 + vertex 1.00993 1.49422 2.63022 + vertex 1.0064 1.49594 2.63166 + endloop + endfacet + facet normal 0.372465 -0.00433411 0.928036 + outer loop + vertex 1.00993 1.4892 2.6302 + vertex 1.00993 1.49422 2.63022 + vertex 1.00646 1.49081 2.6316 + endloop + endfacet + facet normal 0.373242 -0.00239971 0.927731 + outer loop + vertex 1.00647 1.48577 2.63158 + vertex 1.00993 1.4892 2.6302 + vertex 1.00646 1.49081 2.6316 + endloop + endfacet + facet normal 0.438249 -0.00216012 0.898851 + outer loop + vertex 1.00646 1.49081 2.6316 + vertex 1.00322 1.48753 2.63317 + vertex 1.00647 1.48577 2.63158 + endloop + endfacet + facet normal 0.439076 -0.000275414 0.89845 + outer loop + vertex 1.00322 1.48753 2.63317 + vertex 1.00323 1.48251 2.63316 + vertex 1.00647 1.48577 2.63158 + endloop + endfacet + facet normal 0.440023 -0.00144223 0.897985 + outer loop + vertex 1.00647 1.48577 2.63158 + vertex 1.00323 1.48251 2.63316 + vertex 1.00646 1.48076 2.63158 + endloop + endfacet + facet normal 0.375345 -0.0013835 0.926884 + outer loop + vertex 1.00646 1.48076 2.63158 + vertex 1.00992 1.4842 2.63019 + vertex 1.00647 1.48577 2.63158 + endloop + endfacet + facet normal 0.377956 -0.00443896 0.925813 + outer loop + vertex 1.00991 1.47922 2.63017 + vertex 1.00992 1.4842 2.63019 + vertex 1.00646 1.48076 2.63158 + endloop + endfacet + facet normal 0.378072 -0.00413617 0.925767 + outer loop + vertex 1.00645 1.47577 2.63156 + vertex 1.00991 1.47922 2.63017 + vertex 1.00646 1.48076 2.63158 + endloop + endfacet + facet normal 0.44393 -0.00424554 0.896051 + outer loop + vertex 1.00646 1.48076 2.63158 + vertex 1.00324 1.47751 2.63316 + vertex 1.00645 1.47577 2.63156 + endloop + endfacet + facet normal 0.44446 -0.00303165 0.895794 + outer loop + vertex 1.00324 1.47751 2.63316 + vertex 1.00323 1.47252 2.63315 + vertex 1.00645 1.47577 2.63156 + endloop + endfacet + facet normal 0.447851 -0.00723089 0.894079 + outer loop + vertex 1.00645 1.47577 2.63156 + vertex 1.00323 1.47252 2.63315 + vertex 1.00642 1.47079 2.63154 + endloop + endfacet + facet normal 0.38357 -0.00706059 0.923485 + outer loop + vertex 1.00642 1.47079 2.63154 + vertex 1.00988 1.47423 2.63012 + vertex 1.00645 1.47577 2.63156 + endloop + endfacet + facet normal 0.389421 -0.0139677 0.920954 + outer loop + vertex 1.00985 1.46924 2.63006 + vertex 1.00988 1.47423 2.63012 + vertex 1.00642 1.47079 2.63154 + endloop + endfacet + facet normal 0.390454 -0.0113004 0.920553 + outer loop + vertex 1.00638 1.4658 2.63149 + vertex 1.00985 1.46924 2.63006 + vertex 1.00642 1.47079 2.63154 + endloop + endfacet + facet normal 0.450976 -0.0115751 0.892461 + outer loop + vertex 1.00642 1.47079 2.63154 + vertex 1.00319 1.46753 2.63312 + vertex 1.00638 1.4658 2.63149 + endloop + endfacet + facet normal 0.451494 -0.0103921 0.892214 + outer loop + vertex 1.00319 1.46753 2.63312 + vertex 1.00315 1.46254 2.63309 + vertex 1.00638 1.4658 2.63149 + endloop + endfacet + facet normal 0.454513 -0.0141728 0.890628 + outer loop + vertex 1.00638 1.4658 2.63149 + vertex 1.00315 1.46254 2.63309 + vertex 1.00632 1.4608 2.63144 + endloop + endfacet + facet normal 0.396948 -0.0138193 0.917737 + outer loop + vertex 1.00632 1.4608 2.63144 + vertex 1.0098 1.46423 2.62999 + vertex 1.00638 1.4658 2.63149 + endloop + endfacet + facet normal 0.401241 -0.0189936 0.915776 + outer loop + vertex 1.00975 1.45922 2.62991 + vertex 1.0098 1.46423 2.62999 + vertex 1.00632 1.4608 2.63144 + endloop + endfacet + facet normal 0.40254 -0.0156821 0.915268 + outer loop + vertex 1.00626 1.45579 2.63138 + vertex 1.00975 1.45922 2.62991 + vertex 1.00632 1.4608 2.63144 + endloop + endfacet + facet normal 0.457495 -0.0160671 0.889067 + outer loop + vertex 1.00632 1.4608 2.63144 + vertex 1.00309 1.45755 2.63305 + vertex 1.00626 1.45579 2.63138 + endloop + endfacet + facet normal 0.458804 -0.0131088 0.888441 + outer loop + vertex 1.00309 1.45755 2.63305 + vertex 1.00303 1.45255 2.63301 + vertex 1.00626 1.45579 2.63138 + endloop + endfacet + facet normal 0.460744 -0.0155682 0.887397 + outer loop + vertex 1.00626 1.45579 2.63138 + vertex 1.00303 1.45255 2.63301 + vertex 1.00621 1.45079 2.63132 + endloop + endfacet + facet normal 0.404635 -0.015293 0.91435 + outer loop + vertex 1.00621 1.45079 2.63132 + vertex 1.00973 1.45422 2.62982 + vertex 1.00626 1.45579 2.63138 + endloop + endfacet + facet normal 0.407191 -0.0184314 0.913157 + outer loop + vertex 1.00971 1.44923 2.62973 + vertex 1.00973 1.45422 2.62982 + vertex 1.00621 1.45079 2.63132 + endloop + endfacet + facet normal 0.408356 -0.015338 0.912694 + outer loop + vertex 1.00616 1.44578 2.63126 + vertex 1.00971 1.44923 2.62973 + vertex 1.00621 1.45079 2.63132 + endloop + endfacet + facet normal 0.463091 -0.0154781 0.886176 + outer loop + vertex 1.00621 1.45079 2.63132 + vertex 1.00297 1.44755 2.63296 + vertex 1.00616 1.44578 2.63126 + endloop + endfacet + facet normal 0.463642 -0.0142194 0.885908 + outer loop + vertex 1.00297 1.44755 2.63296 + vertex 1.00291 1.44254 2.63291 + vertex 1.00616 1.44578 2.63126 + endloop + endfacet + facet normal 0.464359 -0.0151393 0.885517 + outer loop + vertex 1.00616 1.44578 2.63126 + vertex 1.00291 1.44254 2.63291 + vertex 1.00613 1.44079 2.63119 + endloop + endfacet + facet normal 0.409574 -0.0151694 0.912151 + outer loop + vertex 1.00613 1.44079 2.63119 + vertex 1.00972 1.44427 2.62964 + vertex 1.00616 1.44578 2.63126 + endloop + endfacet + facet normal 0.412236 -0.0184775 0.91089 + outer loop + vertex 1.00972 1.43931 2.62954 + vertex 1.00972 1.44427 2.62964 + vertex 1.00613 1.44079 2.63119 + endloop + endfacet + facet normal 0.413046 -0.0161582 0.910567 + outer loop + vertex 1.00611 1.43581 2.63111 + vertex 1.00972 1.43931 2.62954 + vertex 1.00613 1.44079 2.63119 + endloop + endfacet + facet normal 0.464515 -0.0160368 0.88542 + outer loop + vertex 1.00613 1.44079 2.63119 + vertex 1.00285 1.43753 2.63285 + vertex 1.00611 1.43581 2.63111 + endloop + endfacet + facet normal 0.464236 -0.0166993 0.885554 + outer loop + vertex 1.00285 1.43753 2.63285 + vertex 1.00279 1.43253 2.63279 + vertex 1.00611 1.43581 2.63111 + endloop + endfacet + facet normal 0.464779 -0.0174018 0.885255 + outer loop + vertex 1.00611 1.43581 2.63111 + vertex 1.00279 1.43253 2.63279 + vertex 1.00608 1.43083 2.63103 + endloop + endfacet + facet normal 0.416359 -0.0175187 0.909031 + outer loop + vertex 1.00608 1.43083 2.63103 + vertex 1.00973 1.43437 2.62943 + vertex 1.00611 1.43581 2.63111 + endloop + endfacet + facet normal 0.421111 -0.0234804 0.906705 + outer loop + vertex 1.0097 1.42943 2.62931 + vertex 1.00973 1.43437 2.62943 + vertex 1.00608 1.43083 2.63103 + endloop + endfacet + facet normal 0.422421 -0.0194672 0.906191 + outer loop + vertex 1.00604 1.42589 2.63094 + vertex 1.0097 1.42943 2.62931 + vertex 1.00608 1.43083 2.63103 + endloop + endfacet + facet normal 0.465093 -0.0193926 0.885049 + outer loop + vertex 1.00608 1.43083 2.63103 + vertex 1.00273 1.42753 2.63272 + vertex 1.00604 1.42589 2.63094 + endloop + endfacet + facet normal 0.465285 -0.0189086 0.884959 + outer loop + vertex 1.00273 1.42753 2.63272 + vertex 1.00267 1.42256 2.63264 + vertex 1.00604 1.42589 2.63094 + endloop + endfacet + facet normal 0.466285 -0.0202056 0.884404 + outer loop + vertex 1.00604 1.42589 2.63094 + vertex 1.00267 1.42256 2.63264 + vertex 1.00602 1.42096 2.63084 + endloop + endfacet + facet normal 0.431856 -0.0203626 0.901713 + outer loop + vertex 1.00602 1.42096 2.63084 + vertex 1.00964 1.42452 2.62919 + vertex 1.00604 1.42589 2.63094 + endloop + endfacet + facet normal 0.440203 -0.0308853 0.897367 + outer loop + vertex 1.00961 1.41958 2.62903 + vertex 1.00964 1.42452 2.62919 + vertex 1.00602 1.42096 2.63084 + endloop + endfacet + facet normal 0.443459 -0.0207491 0.896055 + outer loop + vertex 1.00598 1.41603 2.63075 + vertex 1.00961 1.41958 2.62903 + vertex 1.00602 1.42096 2.63084 + endloop + endfacet + facet normal 0.468952 -0.0206842 0.882981 + outer loop + vertex 1.00602 1.42096 2.63084 + vertex 1.00263 1.41761 2.63256 + vertex 1.00598 1.41603 2.63075 + endloop + endfacet + facet normal 0.47022 -0.0173046 0.882379 + outer loop + vertex 1.00263 1.41761 2.63256 + vertex 1.0026 1.41268 2.63248 + vertex 1.00598 1.41603 2.63075 + endloop + endfacet + facet normal 0.47299 -0.0209076 0.88082 + outer loop + vertex 1.00598 1.41603 2.63075 + vertex 1.0026 1.41268 2.63248 + vertex 1.00591 1.41106 2.63066 + endloop + endfacet + facet normal 0.455466 -0.0208157 0.89001 + outer loop + vertex 1.00591 1.41106 2.63066 + vertex 1.00947 1.41451 2.62892 + vertex 1.00598 1.41603 2.63075 + endloop + endfacet + facet normal 0.463836 -0.0318236 0.885349 + outer loop + vertex 1.00923 1.4094 2.62887 + vertex 1.00947 1.41451 2.62892 + vertex 1.00591 1.41106 2.63066 + endloop + endfacet + facet normal 0.474566 -0.0168189 0.880059 + outer loop + vertex 1.0026 1.41268 2.63248 + vertex 1.00257 1.40774 2.6324 + vertex 1.00591 1.41106 2.63066 + endloop + endfacet + facet normal 0.477618 -0.0207961 0.878322 + outer loop + vertex 1.00591 1.41106 2.63066 + vertex 1.00257 1.40774 2.6324 + vertex 1.00583 1.40609 2.63059 + endloop + endfacet + facet normal 0.463522 -0.0168446 0.885925 + outer loop + vertex 1.00257 1.40774 2.6324 + vertex 1.0026 1.41268 2.63248 + vertex 0.999287 1.40939 2.63415 + endloop + endfacet + facet normal 0.463281 -0.0174483 0.88604 + outer loop + vertex 0.999243 1.40442 2.63408 + vertex 1.00257 1.40774 2.6324 + vertex 0.999287 1.40939 2.63415 + endloop + endfacet + facet normal 0.463457 -0.0176736 0.885943 + outer loop + vertex 1.00252 1.40278 2.63233 + vertex 1.00257 1.40774 2.6324 + vertex 0.999243 1.40442 2.63408 + endloop + endfacet + facet normal 0.46271 -0.0195505 0.886294 + outer loop + vertex 0.999178 1.39943 2.634 + vertex 1.00252 1.40278 2.63233 + vertex 0.999243 1.40442 2.63408 + endloop + endfacet + facet normal 0.463624 -0.0169752 0.885869 + outer loop + vertex 0.999287 1.40939 2.63415 + vertex 1.0026 1.41268 2.63248 + vertex 0.999323 1.41434 2.63423 + endloop + endfacet + facet normal 0.463484 -0.0173213 0.885936 + outer loop + vertex 1.0026 1.41268 2.63248 + vertex 1.00263 1.41761 2.63256 + vertex 0.999323 1.41434 2.63423 + endloop + endfacet + facet normal 0.451709 -0.0313336 0.891615 + outer loop + vertex 1.00947 1.41451 2.62892 + vertex 1.00961 1.41958 2.62903 + vertex 1.00598 1.41603 2.63075 + endloop + endfacet + facet normal 0.467042 -0.0182077 0.884047 + outer loop + vertex 1.00267 1.42256 2.63264 + vertex 1.00263 1.41761 2.63256 + vertex 1.00602 1.42096 2.63084 + endloop + endfacet + facet normal 0.429351 -0.028216 0.902697 + outer loop + vertex 1.00964 1.42452 2.62919 + vertex 1.0097 1.42943 2.62931 + vertex 1.00604 1.42589 2.63094 + endloop + endfacet + facet normal 0.464356 -0.0184362 0.885457 + outer loop + vertex 1.00279 1.43253 2.63279 + vertex 1.00273 1.42753 2.63272 + vertex 1.00608 1.43083 2.63103 + endloop + endfacet + facet normal 0.469723 -0.0184648 0.882621 + outer loop + vertex 1.00273 1.42753 2.63272 + vertex 1.00279 1.43253 2.63279 + vertex 0.999534 1.42928 2.63445 + endloop + endfacet + facet normal 0.468839 -0.0204885 0.883046 + outer loop + vertex 0.999448 1.42428 2.63438 + vertex 1.00273 1.42753 2.63272 + vertex 0.999534 1.42928 2.63445 + endloop + endfacet + facet normal 0.467625 -0.0189156 0.883724 + outer loop + vertex 1.00267 1.42256 2.63264 + vertex 1.00273 1.42753 2.63272 + vertex 0.999448 1.42428 2.63438 + endloop + endfacet + facet normal 0.466991 -0.0204066 0.884026 + outer loop + vertex 0.999374 1.4193 2.63431 + vertex 1.00267 1.42256 2.63264 + vertex 0.999448 1.42428 2.63438 + endloop + endfacet + facet normal 0.465293 -0.0182083 0.884969 + outer loop + vertex 1.00263 1.41761 2.63256 + vertex 1.00267 1.42256 2.63264 + vertex 0.999374 1.4193 2.63431 + endloop + endfacet + facet normal 0.470142 -0.0190055 0.882386 + outer loop + vertex 0.999534 1.42928 2.63445 + vertex 1.00279 1.43253 2.63279 + vertex 0.999617 1.4343 2.63452 + endloop + endfacet + facet normal 0.471145 -0.0167329 0.881897 + outer loop + vertex 1.00279 1.43253 2.63279 + vertex 1.00285 1.43753 2.63285 + vertex 0.999617 1.4343 2.63452 + endloop + endfacet + facet normal 0.415703 -0.0194737 0.909292 + outer loop + vertex 1.00973 1.43437 2.62943 + vertex 1.00972 1.43931 2.62954 + vertex 1.00611 1.43581 2.63111 + endloop + endfacet + facet normal 0.464166 -0.0155883 0.885611 + outer loop + vertex 1.00291 1.44254 2.63291 + vertex 1.00285 1.43753 2.63285 + vertex 1.00613 1.44079 2.63119 + endloop + endfacet + facet normal 0.471939 -0.0156337 0.881492 + outer loop + vertex 1.00285 1.43753 2.63285 + vertex 1.00291 1.44254 2.63291 + vertex 0.999692 1.43931 2.63457 + endloop + endfacet + facet normal 0.470658 -0.0139923 0.882205 + outer loop + vertex 0.999692 1.43931 2.63457 + vertex 1.00291 1.44254 2.63291 + vertex 0.999753 1.44431 2.63462 + endloop + endfacet + facet normal 0.470538 -0.0142642 0.882265 + outer loop + vertex 1.00291 1.44254 2.63291 + vertex 1.00297 1.44755 2.63296 + vertex 0.999753 1.44431 2.63462 + endloop + endfacet + facet normal 0.468803 -0.0120511 0.88322 + outer loop + vertex 0.999753 1.44431 2.63462 + vertex 1.00297 1.44755 2.63296 + vertex 0.999806 1.44931 2.63466 + endloop + endfacet + facet normal 0.468102 -0.013644 0.883569 + outer loop + vertex 1.00297 1.44755 2.63296 + vertex 1.00303 1.45255 2.63301 + vertex 0.999806 1.44931 2.63466 + endloop + endfacet + facet normal 0.466888 -0.012098 0.884234 + outer loop + vertex 0.999806 1.44931 2.63466 + vertex 1.00303 1.45255 2.63301 + vertex 0.99986 1.4543 2.6347 + endloop + endfacet + facet normal 0.409156 -0.016327 0.912318 + outer loop + vertex 1.00972 1.44427 2.62964 + vertex 1.00971 1.44923 2.62973 + vertex 1.00616 1.44578 2.63126 + endloop + endfacet + facet normal 0.461615 -0.0135959 0.886976 + outer loop + vertex 1.00303 1.45255 2.63301 + vertex 1.00297 1.44755 2.63296 + vertex 1.00621 1.45079 2.63132 + endloop + endfacet + facet normal 0.46642 -0.0131666 0.884465 + outer loop + vertex 1.00303 1.45255 2.63301 + vertex 1.00309 1.45755 2.63305 + vertex 0.99986 1.4543 2.6347 + endloop + endfacet + facet normal 0.403865 -0.0172951 0.914655 + outer loop + vertex 1.00973 1.45422 2.62982 + vertex 1.00975 1.45922 2.62991 + vertex 1.00626 1.45579 2.63138 + endloop + endfacet + facet normal 0.455041 -0.0129737 0.890376 + outer loop + vertex 1.00315 1.46254 2.63309 + vertex 1.00309 1.45755 2.63305 + vertex 1.00632 1.4608 2.63144 + endloop + endfacet + facet normal 0.463582 -0.0104645 0.885992 + outer loop + vertex 1.00315 1.46254 2.63309 + vertex 1.00319 1.46753 2.63312 + vertex 0.999962 1.46428 2.63478 + endloop + endfacet + facet normal 0.463206 -0.0113339 0.886178 + outer loop + vertex 0.999912 1.45929 2.63474 + vertex 1.00315 1.46254 2.63309 + vertex 0.999962 1.46428 2.63478 + endloop + endfacet + facet normal 0.464555 -0.013046 0.885448 + outer loop + vertex 1.00309 1.45755 2.63305 + vertex 1.00315 1.46254 2.63309 + vertex 0.999912 1.45929 2.63474 + endloop + endfacet + facet normal 0.395555 -0.0173834 0.918278 + outer loop + vertex 1.0098 1.46423 2.62999 + vertex 1.00985 1.46924 2.63006 + vertex 1.00638 1.4658 2.63149 + endloop + endfacet + facet normal 0.447722 -0.00752568 0.894141 + outer loop + vertex 1.00323 1.47252 2.63315 + vertex 1.00319 1.46753 2.63312 + vertex 1.00642 1.47079 2.63154 + endloop + endfacet + facet normal 0.462342 -0.00758039 0.886669 + outer loop + vertex 1.00319 1.46753 2.63312 + vertex 1.00323 1.47252 2.63315 + vertex 0.999996 1.46927 2.63481 + endloop + endfacet + facet normal 0.459926 -0.00452809 0.887946 + outer loop + vertex 0.999996 1.46927 2.63481 + vertex 1.00323 1.47252 2.63315 + vertex 1.00001 1.47426 2.63483 + endloop + endfacet + facet normal 0.46056 -0.00304444 0.887623 + outer loop + vertex 1.00323 1.47252 2.63315 + vertex 1.00324 1.47751 2.63316 + vertex 1.00001 1.47426 2.63483 + endloop + endfacet + facet normal 0.45855 -0.000512066 0.888668 + outer loop + vertex 1.00001 1.47426 2.63483 + vertex 1.00324 1.47751 2.63316 + vertex 0.999995 1.47926 2.63484 + endloop + endfacet + facet normal 0.458716 -0.000122919 0.888583 + outer loop + vertex 1.00324 1.47751 2.63316 + vertex 1.00323 1.48251 2.63316 + vertex 0.999995 1.47926 2.63484 + endloop + endfacet + facet normal 0.457837 0.000982435 0.889035 + outer loop + vertex 0.999995 1.47926 2.63484 + vertex 1.00323 1.48251 2.63316 + vertex 0.999989 1.48425 2.63483 + endloop + endfacet + facet normal 0.382637 -0.00948703 0.92385 + outer loop + vertex 1.00988 1.47423 2.63012 + vertex 1.00991 1.47922 2.63017 + vertex 1.00645 1.47577 2.63156 + endloop + endfacet + facet normal 0.440597 -0.000130708 0.897705 + outer loop + vertex 1.00323 1.48251 2.63316 + vertex 1.00324 1.47751 2.63316 + vertex 1.00646 1.48076 2.63158 + endloop + endfacet + facet normal 0.457324 -0.000229432 0.8893 + outer loop + vertex 1.00323 1.48251 2.63316 + vertex 1.00322 1.48753 2.63317 + vertex 0.999989 1.48425 2.63483 + endloop + endfacet + facet normal 0.458439 -0.00162188 0.888725 + outer loop + vertex 0.999989 1.48425 2.63483 + vertex 1.00322 1.48753 2.63317 + vertex 1.00001 1.4892 2.63483 + endloop + endfacet + facet normal 0.457713 -0.00338822 0.889093 + outer loop + vertex 1.00322 1.48753 2.63317 + vertex 1.00315 1.49258 2.63323 + vertex 1.00001 1.4892 2.63483 + endloop + endfacet + facet normal 0.37441 -0.00376913 0.927256 + outer loop + vertex 1.00992 1.4842 2.63019 + vertex 1.00993 1.4892 2.6302 + vertex 1.00647 1.48577 2.63158 + endloop + endfacet + facet normal 0.439559 -0.00376154 0.898206 + outer loop + vertex 1.00315 1.49258 2.63323 + vertex 1.00322 1.48753 2.63317 + vertex 1.00646 1.49081 2.6316 + endloop + endfacet + facet normal 0.459954 -0.00500547 0.887929 + outer loop + vertex 1.00268 1.49794 2.6335 + vertex 0.999984 1.4938 2.63487 + vertex 1.00315 1.49258 2.63323 + endloop + endfacet + facet normal 0.3739 -0.00374846 0.927461 + outer loop + vertex 1.00993 1.49422 2.63022 + vertex 1.00995 1.49927 2.63024 + vertex 1.0064 1.49594 2.63166 + endloop + endfacet + facet normal 0.439671 -0.0018202 0.898157 + outer loop + vertex 1.00286 1.50909 2.63343 + vertex 1.00312 1.50357 2.63329 + vertex 1.0065 1.50636 2.63164 + endloop + endfacet + facet normal 0.457959 0.00390406 0.888965 + outer loop + vertex 1.00014 1.51338 2.63481 + vertex 1.00286 1.50909 2.63343 + vertex 1.00371 1.51361 2.63297 + endloop + endfacet + facet normal 0.45788 0.00536907 0.888998 + outer loop + vertex 1.00221 1.51848 2.63371 + vertex 1.00014 1.51338 2.63481 + vertex 1.00371 1.51361 2.63297 + endloop + endfacet + facet normal 0.447073 0.0109079 0.894431 + outer loop + vertex 0.997214 1.51738 2.63622 + vertex 1.00014 1.51338 2.63481 + vertex 1.00221 1.51848 2.63371 + endloop + endfacet + facet normal 0.450982 -0.0113401 0.892461 + outer loop + vertex 0.999359 1.52027 2.63518 + vertex 0.997214 1.51738 2.63622 + vertex 1.00221 1.51848 2.63371 + endloop + endfacet + facet normal 0.459546 0.00577177 0.888135 + outer loop + vertex 0.999359 1.52027 2.63518 + vertex 1.00221 1.51848 2.63371 + vertex 1.00046 1.52363 2.63458 + endloop + endfacet + facet normal 0.457323 0.00339482 0.889294 + outer loop + vertex 0.999458 1.50952 2.63517 + vertex 1.00286 1.50909 2.63343 + vertex 1.00014 1.51338 2.63481 + endloop + endfacet + facet normal 0.372479 0.00112374 0.92804 + outer loop + vertex 1.01 1.50925 2.63022 + vertex 1.00995 1.51414 2.63023 + vertex 1.00657 1.51128 2.63159 + endloop + endfacet + facet normal 0.439081 -0.00187483 0.898446 + outer loop + vertex 1.00221 1.51848 2.63371 + vertex 1.00371 1.51361 2.63297 + vertex 1.00642 1.51607 2.63165 + endloop + endfacet + facet normal 0.460849 0.00632859 0.887456 + outer loop + vertex 1.00046 1.52363 2.63458 + vertex 1.00221 1.51848 2.63371 + vertex 1.00377 1.52311 2.63287 + endloop + endfacet + facet normal 0.46096 0.00725385 0.887391 + outer loop + vertex 1.00377 1.52311 2.63287 + vertex 1.00335 1.52735 2.63305 + vertex 1.00046 1.52363 2.63458 + endloop + endfacet + facet normal 0.459316 0.0088796 0.888229 + outer loop + vertex 1.00046 1.52363 2.63458 + vertex 1.00335 1.52735 2.63305 + vertex 1.00005 1.529 2.63474 + endloop + endfacet + facet normal 0.373696 0.00941281 0.927504 + outer loop + vertex 1.00988 1.51905 2.63024 + vertex 1.00983 1.524 2.63021 + vertex 1.00637 1.5209 2.63164 + endloop + endfacet + facet normal 0.43852 0.0045911 0.89871 + outer loop + vertex 1.00335 1.52735 2.63305 + vertex 1.00377 1.52311 2.63287 + vertex 1.00649 1.52569 2.63153 + endloop + endfacet + facet normal 0.459501 0.00935141 0.888128 + outer loop + vertex 1.00335 1.52735 2.63305 + vertex 1.00313 1.53234 2.63312 + vertex 1.00005 1.529 2.63474 + endloop + endfacet + facet normal 0.372977 0.00881943 0.927799 + outer loop + vertex 1.0098 1.52901 2.63018 + vertex 1.00976 1.53405 2.63014 + vertex 1.00636 1.53058 2.63154 + endloop + endfacet + facet normal 0.441371 0.0111157 0.897256 + outer loop + vertex 1.00302 1.53738 2.6331 + vertex 1.00313 1.53234 2.63312 + vertex 1.00626 1.5356 2.63153 + endloop + endfacet + facet normal 0.459227 0.0114497 0.888245 + outer loop + vertex 1.00313 1.53234 2.63312 + vertex 1.00302 1.53738 2.6331 + vertex 0.999867 1.53413 2.63478 + endloop + endfacet + facet normal 0.45878 0.0120006 0.888469 + outer loop + vertex 0.999867 1.53413 2.63478 + vertex 1.00302 1.53738 2.6331 + vertex 0.999812 1.53917 2.63474 + endloop + endfacet + facet normal 0.459307 0.0132106 0.888179 + outer loop + vertex 1.00302 1.53738 2.6331 + vertex 1.00298 1.54237 2.63305 + vertex 0.999812 1.53917 2.63474 + endloop + endfacet + facet normal 0.373057 0.0146699 0.927693 + outer loop + vertex 1.00976 1.53909 2.63008 + vertex 1.00978 1.54411 2.63 + vertex 1.00622 1.54061 2.63148 + endloop + endfacet + facet normal 0.441001 0.0151487 0.897379 + outer loop + vertex 1.00293 1.54734 2.63299 + vertex 1.00298 1.54237 2.63305 + vertex 1.0062 1.5456 2.63142 + endloop + endfacet + facet normal 0.459732 0.015221 0.887927 + outer loop + vertex 1.00298 1.54237 2.63305 + vertex 1.00293 1.54734 2.63299 + vertex 0.999782 1.54414 2.63468 + endloop + endfacet + facet normal 0.460163 0.0146838 0.887713 + outer loop + vertex 0.999782 1.54414 2.63468 + vertex 1.00293 1.54734 2.63299 + vertex 0.999726 1.5491 2.63462 + endloop + endfacet + facet normal 0.460666 0.0158577 0.887432 + outer loop + vertex 1.00293 1.54734 2.63299 + vertex 1.00287 1.55231 2.63294 + vertex 0.999726 1.5491 2.63462 + endloop + endfacet + facet normal 0.460456 0.0161187 0.887536 + outer loop + vertex 0.999726 1.5491 2.63462 + vertex 1.00287 1.55231 2.63294 + vertex 0.999642 1.55408 2.63458 + endloop + endfacet + facet normal 0.460554 0.0163493 0.887481 + outer loop + vertex 1.00287 1.55231 2.63294 + vertex 1.0028 1.5573 2.63288 + vertex 0.999642 1.55408 2.63458 + endloop + endfacet + facet normal 0.459723 0.0173795 0.887892 + outer loop + vertex 0.999642 1.55408 2.63458 + vertex 1.0028 1.5573 2.63288 + vertex 0.999553 1.55906 2.63453 + endloop + endfacet + facet normal 0.37596 0.0172036 0.926476 + outer loop + vertex 1.00979 1.54913 2.6299 + vertex 1.0098 1.55417 2.6298 + vertex 1.00616 1.55059 2.63134 + endloop + endfacet + facet normal 0.441223 0.0161977 0.897251 + outer loop + vertex 1.0028 1.5573 2.63288 + vertex 1.00287 1.55231 2.63294 + vertex 1.00614 1.5556 2.63127 + endloop + endfacet + facet normal 0.459983 0.0179959 0.887746 + outer loop + vertex 1.0028 1.5573 2.63288 + vertex 1.00273 1.5623 2.63281 + vertex 0.999553 1.55906 2.63453 + endloop + endfacet + facet normal 0.382403 0.0219856 0.923734 + outer loop + vertex 1.00981 1.55921 2.62969 + vertex 1.00982 1.56426 2.62956 + vertex 1.00611 1.56063 2.63118 + endloop + endfacet + facet normal 0.441746 0.0179614 0.896961 + outer loop + vertex 1.00268 1.56731 2.63274 + vertex 1.00273 1.5623 2.63281 + vertex 1.00609 1.56566 2.63109 + endloop + endfacet + facet normal 0.458974 0.0180234 0.888267 + outer loop + vertex 1.00273 1.5623 2.63281 + vertex 1.00268 1.56731 2.63274 + vertex 0.999465 1.56405 2.63447 + endloop + endfacet + facet normal 0.458252 0.0189229 0.888621 + outer loop + vertex 0.999465 1.56405 2.63447 + vertex 1.00268 1.56731 2.63274 + vertex 0.999384 1.56904 2.6344 + endloop + endfacet + facet normal 0.457699 0.0175695 0.888934 + outer loop + vertex 1.00268 1.56731 2.63274 + vertex 1.00263 1.57232 2.63266 + vertex 0.999384 1.56904 2.6344 + endloop + endfacet + facet normal 0.45735 0.0180051 0.889105 + outer loop + vertex 0.999384 1.56904 2.6344 + vertex 1.00263 1.57232 2.63266 + vertex 0.999312 1.57403 2.63434 + endloop + endfacet + facet normal 0.457201 0.0176329 0.889188 + outer loop + vertex 1.00263 1.57232 2.63266 + vertex 1.00259 1.57735 2.63258 + vertex 0.999312 1.57403 2.63434 + endloop + endfacet + facet normal 0.457143 0.0177058 0.889217 + outer loop + vertex 0.999312 1.57403 2.63434 + vertex 1.00259 1.57735 2.63258 + vertex 0.999248 1.57903 2.63427 + endloop + endfacet + facet normal 0.395477 0.0263129 0.918099 + outer loop + vertex 1.00977 1.56928 2.62944 + vertex 1.00974 1.57427 2.62931 + vertex 1.00607 1.57069 2.63099 + endloop + endfacet + facet normal 0.446298 0.0176309 0.894711 + outer loop + vertex 1.00259 1.57735 2.63258 + vertex 1.00263 1.57232 2.63266 + vertex 1.00605 1.57573 2.63089 + endloop + endfacet + facet normal 0.411516 0.0305549 0.91089 + outer loop + vertex 1.0097 1.5793 2.62918 + vertex 1.00955 1.58433 2.62908 + vertex 1.00602 1.58079 2.63079 + endloop + endfacet + facet normal 0.468413 0.0233014 0.883202 + outer loop + vertex 1.00229 1.60251 2.63215 + vertex 1.00236 1.59747 2.63225 + vertex 1.00569 1.60086 2.63039 + endloop + endfacet + facet normal 0.465516 0.0387088 0.884193 + outer loop + vertex 1.00894 1.60414 2.6286 + vertex 1.00869 1.60915 2.62851 + vertex 1.00558 1.60592 2.63029 + endloop + endfacet + facet normal 0.483528 0.0276788 0.874891 + outer loop + vertex 1.00526 1.61572 2.63015 + vertex 1.00221 1.61259 2.63194 + vertex 1.00546 1.61091 2.6302 + endloop + endfacet + facet normal 0.481629 0.0227759 0.876079 + outer loop + vertex 1.00221 1.61259 2.63194 + vertex 1.00225 1.60756 2.63204 + vertex 1.00546 1.61091 2.6302 + endloop + endfacet + facet normal 0.462338 0.0226073 0.886416 + outer loop + vertex 1.00236 1.59747 2.63225 + vertex 1.00243 1.59243 2.63234 + vertex 1.00579 1.5958 2.6305 + endloop + endfacet + facet normal 0.458237 0.0211974 0.888577 + outer loop + vertex 1.00243 1.59243 2.63234 + vertex 1.0025 1.58741 2.63242 + vertex 1.00586 1.59079 2.63061 + endloop + endfacet + facet normal 0.454328 0.0193591 0.890624 + outer loop + vertex 1.0025 1.58741 2.63242 + vertex 1.00255 1.58238 2.63251 + vertex 1.00594 1.58581 2.6307 + endloop + endfacet + facet normal 0.457117 0.0176387 0.889232 + outer loop + vertex 1.00259 1.57735 2.63258 + vertex 1.00255 1.58238 2.63251 + vertex 0.999248 1.57903 2.63427 + endloop + endfacet + facet normal 0.421536 0.0188095 0.906617 + outer loop + vertex 0.992463 1.58254 2.63744 + vertex 0.992547 1.57754 2.63751 + vertex 0.995881 1.58075 2.63589 + endloop + endfacet + facet normal 0.407321 0.0186542 0.913095 + outer loop + vertex 0.992547 1.57754 2.63751 + vertex 0.992463 1.58254 2.63744 + vertex 0.989111 1.5793 2.639 + endloop + endfacet + facet normal 0.405983 0.0173491 0.913716 + outer loop + vertex 0.992634 1.57255 2.63756 + vertex 0.992547 1.57754 2.63751 + vertex 0.98919 1.5743 2.63906 + endloop + endfacet + facet normal 0.441862 0.0176116 0.89691 + outer loop + vertex 0.999312 1.57403 2.63434 + vertex 0.999248 1.57903 2.63427 + vertex 0.995963 1.57576 2.63595 + endloop + endfacet + facet normal 0.421072 0.0177473 0.906854 + outer loop + vertex 0.992634 1.57255 2.63756 + vertex 0.99272 1.56756 2.63762 + vertex 0.996047 1.57078 2.63601 + endloop + endfacet + facet normal 0.405104 0.0175543 0.914102 + outer loop + vertex 0.99272 1.56756 2.63762 + vertex 0.992634 1.57255 2.63756 + vertex 0.989273 1.56932 2.63911 + endloop + endfacet + facet normal 0.404154 0.018831 0.914497 + outer loop + vertex 0.992809 1.56258 2.63768 + vertex 0.99272 1.56756 2.63762 + vertex 0.989356 1.56433 2.63917 + endloop + endfacet + facet normal 0.442912 0.0187734 0.896369 + outer loop + vertex 0.999465 1.56405 2.63447 + vertex 0.999384 1.56904 2.6344 + vertex 0.996136 1.56579 2.63607 + endloop + endfacet + facet normal 0.45931 0.0188316 0.888076 + outer loop + vertex 0.999553 1.55906 2.63453 + vertex 1.00273 1.5623 2.63281 + vertex 0.999465 1.56405 2.63447 + endloop + endfacet + facet normal 0.420571 0.0189267 0.907062 + outer loop + vertex 0.992809 1.56258 2.63768 + vertex 0.9929 1.55759 2.63775 + vertex 0.996229 1.56081 2.63614 + endloop + endfacet + facet normal 0.405116 0.0161969 0.914122 + outer loop + vertex 0.992984 1.5526 2.6378 + vertex 0.9929 1.55759 2.63775 + vertex 0.989528 1.55437 2.6393 + endloop + endfacet + facet normal 0.444545 0.0171864 0.895592 + outer loop + vertex 0.999642 1.55408 2.63458 + vertex 0.999553 1.55906 2.63453 + vertex 0.996323 1.55583 2.63619 + endloop + endfacet + facet normal 0.420234 0.014214 0.907305 + outer loop + vertex 0.992984 1.5526 2.6378 + vertex 0.993054 1.54762 2.63784 + vertex 0.996408 1.55084 2.63624 + endloop + endfacet + facet normal 0.405035 0.0140625 0.914193 + outer loop + vertex 0.993054 1.54762 2.63784 + vertex 0.992984 1.5526 2.6378 + vertex 0.989605 1.54938 2.63934 + endloop + endfacet + facet normal 0.442866 0.0145813 0.896469 + outer loop + vertex 0.999782 1.54414 2.63468 + vertex 0.999726 1.5491 2.63462 + vertex 0.996468 1.54587 2.63629 + endloop + endfacet + facet normal 0.45902 0.0135691 0.888322 + outer loop + vertex 0.999812 1.53917 2.63474 + vertex 1.00298 1.54237 2.63305 + vertex 0.999782 1.54414 2.63468 + endloop + endfacet + facet normal 0.418872 0.0115949 0.907971 + outer loop + vertex 0.993093 1.54265 2.63789 + vertex 0.9931 1.53768 2.63795 + vertex 0.996493 1.5409 2.63634 + endloop + endfacet + facet normal 0.401832 0.0110826 0.915646 + outer loop + vertex 0.993128 1.53266 2.638 + vertex 0.9931 1.53768 2.63795 + vertex 0.989698 1.53445 2.63948 + endloop + endfacet + facet normal 0.441052 0.0118769 0.897403 + outer loop + vertex 0.999867 1.53413 2.63478 + vertex 0.999812 1.53917 2.63474 + vertex 0.996507 1.53591 2.6364 + endloop + endfacet + facet normal 0.458717 0.0102677 0.888523 + outer loop + vertex 1.00005 1.529 2.63474 + vertex 1.00313 1.53234 2.63312 + vertex 0.999867 1.53413 2.63478 + endloop + endfacet + facet normal 0.44405 0.00750044 0.89597 + outer loop + vertex 1.00046 1.52363 2.63458 + vertex 1.00005 1.529 2.63474 + vertex 0.996935 1.52575 2.63631 + endloop + endfacet + facet normal 0.418318 0.0102693 0.908243 + outer loop + vertex 0.993128 1.53266 2.638 + vertex 0.993301 1.5275 2.63798 + vertex 0.996606 1.53083 2.63642 + endloop + endfacet + facet normal 0.40281 0.00972136 0.915232 + outer loop + vertex 0.993301 1.5275 2.63798 + vertex 0.993128 1.53266 2.638 + vertex 0.989739 1.52942 2.63953 + endloop + endfacet + facet normal 0.404747 0.00592201 0.914409 + outer loop + vertex 0.993894 1.52187 2.63775 + vertex 0.993301 1.5275 2.63798 + vertex 0.989862 1.52428 2.63952 + endloop + endfacet + facet normal 0.405103 0.00679517 0.914246 + outer loop + vertex 0.992987 1.51708 2.63819 + vertex 0.993894 1.52187 2.63775 + vertex 0.989858 1.5192 2.63956 + endloop + endfacet + facet normal 0.456733 -0.00244098 0.8896 + outer loop + vertex 0.999458 1.50952 2.63517 + vertex 0.999822 1.50561 2.63498 + vertex 1.00286 1.50909 2.63343 + endloop + endfacet + facet normal 0.417705 -0.00206586 0.90858 + outer loop + vertex 0.996624 1.50236 2.63653 + vertex 0.996291 1.50752 2.6367 + vertex 0.993129 1.50334 2.63814 + endloop + endfacet + facet normal 0.417968 -0.000933768 0.908461 + outer loop + vertex 0.99341 1.49854 2.63801 + vertex 0.996624 1.50236 2.63653 + vertex 0.993129 1.50334 2.63814 + endloop + endfacet + facet normal 0.404256 -0.00190674 0.914644 + outer loop + vertex 0.99341 1.49854 2.63801 + vertex 0.993129 1.50334 2.63814 + vertex 0.989863 1.49965 2.63958 + endloop + endfacet + facet normal 0.41658 0.000477502 0.909099 + outer loop + vertex 0.996833 1.49788 2.63644 + vertex 0.996624 1.50236 2.63653 + vertex 0.99341 1.49854 2.63801 + endloop + endfacet + facet normal 0.416375 -0.000820194 0.909193 + outer loop + vertex 0.996833 1.49788 2.63644 + vertex 0.99341 1.49854 2.63801 + vertex 0.993974 1.4934 2.63775 + endloop + endfacet + facet normal 0.404408 -0.00241171 0.914576 + outer loop + vertex 0.993974 1.4934 2.63775 + vertex 0.99341 1.49854 2.63801 + vertex 0.989993 1.49467 2.63951 + endloop + endfacet + facet normal 0.455327 -0.000889806 0.890324 + outer loop + vertex 1.00312 1.50357 2.63329 + vertex 1.00286 1.50909 2.63343 + vertex 0.999822 1.50561 2.63498 + endloop + endfacet + facet normal 0.440744 -0.000418921 0.897633 + outer loop + vertex 1.00312 1.50357 2.63329 + vertex 1.00268 1.49794 2.6335 + vertex 1.00643 1.50117 2.63166 + endloop + endfacet + facet normal 0.459846 -0.00491647 0.887985 + outer loop + vertex 0.999431 1.49713 2.63518 + vertex 0.999984 1.4938 2.63487 + vertex 1.00268 1.49794 2.6335 + endloop + endfacet + facet normal 0.438963 0.00174296 0.898503 + outer loop + vertex 0.996624 1.50236 2.63653 + vertex 0.996833 1.49788 2.63644 + vertex 0.99985 1.50086 2.63496 + endloop + endfacet + facet normal 0.446531 -0.00774212 0.894734 + outer loop + vertex 0.999431 1.49713 2.63518 + vertex 0.997451 1.49466 2.63615 + vertex 0.999984 1.4938 2.63487 + endloop + endfacet + facet normal 0.459725 -0.0057536 0.888043 + outer loop + vertex 1.00001 1.4892 2.63483 + vertex 1.00315 1.49258 2.63323 + vertex 0.999984 1.4938 2.63487 + endloop + endfacet + facet normal 0.442648 -0.00153253 0.896694 + outer loop + vertex 0.999989 1.48425 2.63483 + vertex 1.00001 1.4892 2.63483 + vertex 0.996687 1.48595 2.63647 + endloop + endfacet + facet normal 0.421039 -0.00257076 0.907039 + outer loop + vertex 0.993974 1.4934 2.63775 + vertex 0.993392 1.48778 2.638 + vertex 0.996912 1.49082 2.63637 + endloop + endfacet + facet normal 0.445616 -0.00452392 0.895213 + outer loop + vertex 0.999996 1.46927 2.63481 + vertex 1.00001 1.47426 2.63483 + vertex 0.996677 1.47099 2.63647 + endloop + endfacet + facet normal 0.461976 -0.0084295 0.886852 + outer loop + vertex 0.999962 1.46428 2.63478 + vertex 1.00319 1.46753 2.63312 + vertex 0.999996 1.46927 2.63481 + endloop + endfacet + facet normal 0.423017 -0.00972959 0.90607 + outer loop + vertex 0.993273 1.46774 2.63804 + vertex 0.99324 1.46275 2.638 + vertex 0.996658 1.466 2.63644 + endloop + endfacet + facet normal 0.406665 -0.0096782 0.913526 + outer loop + vertex 0.99324 1.46275 2.638 + vertex 0.993273 1.46774 2.63804 + vertex 0.989837 1.46449 2.63953 + endloop + endfacet + facet normal 0.406041 -0.0111293 0.913787 + outer loop + vertex 0.989792 1.4595 2.63949 + vertex 0.99324 1.46275 2.638 + vertex 0.989837 1.46449 2.63953 + endloop + endfacet + facet normal 0.379505 -0.0109792 0.925125 + outer loop + vertex 0.989792 1.4595 2.63949 + vertex 0.989837 1.46449 2.63953 + vertex 0.986299 1.46104 2.64094 + endloop + endfacet + facet normal 0.378807 -0.0128025 0.925387 + outer loop + vertex 0.986247 1.45605 2.64089 + vertex 0.989792 1.4595 2.63949 + vertex 0.986299 1.46104 2.64094 + endloop + endfacet + facet normal 0.325591 -0.0124363 0.945429 + outer loop + vertex 0.986299 1.46104 2.64094 + vertex 0.98249 1.45717 2.6422 + vertex 0.986247 1.45605 2.64089 + endloop + endfacet + facet normal 0.325123 -0.0141675 0.945566 + outer loop + vertex 0.98249 1.45717 2.6422 + vertex 0.982446 1.45217 2.64214 + vertex 0.986247 1.45605 2.64089 + endloop + endfacet + facet normal 0.323394 -0.0122741 0.946185 + outer loop + vertex 0.986247 1.45605 2.64089 + vertex 0.982446 1.45217 2.64214 + vertex 0.986194 1.45106 2.64085 + endloop + endfacet + facet normal 0.378797 -0.0126644 0.925393 + outer loop + vertex 0.986194 1.45106 2.64085 + vertex 0.989734 1.4545 2.63945 + vertex 0.986247 1.45605 2.64089 + endloop + endfacet + facet normal 0.377985 -0.0116892 0.925738 + outer loop + vertex 0.989681 1.44951 2.6394 + vertex 0.989734 1.4545 2.63945 + vertex 0.986194 1.45106 2.64085 + endloop + endfacet + facet normal 0.377831 -0.0120911 0.925796 + outer loop + vertex 0.986146 1.44607 2.6408 + vertex 0.989681 1.44951 2.6394 + vertex 0.986194 1.45106 2.64085 + endloop + endfacet + facet normal 0.321421 -0.0117396 0.946864 + outer loop + vertex 0.986194 1.45106 2.64085 + vertex 0.982409 1.44718 2.64208 + vertex 0.986146 1.44607 2.6408 + endloop + endfacet + facet normal 0.320833 -0.0139063 0.947034 + outer loop + vertex 0.982409 1.44718 2.64208 + vertex 0.982375 1.44219 2.64202 + vertex 0.986146 1.44607 2.6408 + endloop + endfacet + facet normal 0.318811 -0.0117145 0.947746 + outer loop + vertex 0.986146 1.44607 2.6408 + vertex 0.982375 1.44219 2.64202 + vertex 0.986101 1.44108 2.64076 + endloop + endfacet + facet normal 0.375976 -0.0120247 0.926551 + outer loop + vertex 0.986101 1.44108 2.64076 + vertex 0.989634 1.44453 2.63937 + vertex 0.986146 1.44607 2.6408 + endloop + endfacet + facet normal 0.375811 -0.0118282 0.926621 + outer loop + vertex 0.989584 1.43953 2.63932 + vertex 0.989634 1.44453 2.63937 + vertex 0.986101 1.44108 2.64076 + endloop + endfacet + facet normal 0.374674 -0.0147801 0.927039 + outer loop + vertex 0.986048 1.43609 2.6407 + vertex 0.989584 1.43953 2.63932 + vertex 0.986101 1.44108 2.64076 + endloop + endfacet + facet normal 0.31698 -0.0144152 0.948323 + outer loop + vertex 0.986101 1.44108 2.64076 + vertex 0.982342 1.4372 2.64195 + vertex 0.986048 1.43609 2.6407 + endloop + endfacet + facet normal 0.315593 -0.0194363 0.948696 + outer loop + vertex 0.982342 1.4372 2.64195 + vertex 0.982295 1.43221 2.64187 + vertex 0.986048 1.43609 2.6407 + endloop + endfacet + facet normal 0.31293 -0.0165773 0.949632 + outer loop + vertex 0.986048 1.43609 2.6407 + vertex 0.982295 1.43221 2.64187 + vertex 0.985984 1.4311 2.64063 + endloop + endfacet + facet normal 0.373763 -0.0170678 0.927367 + outer loop + vertex 0.985984 1.4311 2.64063 + vertex 0.989521 1.43454 2.63927 + vertex 0.986048 1.43609 2.6407 + endloop + endfacet + facet normal 0.374699 -0.0181888 0.926968 + outer loop + vertex 0.989437 1.42956 2.63921 + vertex 0.989521 1.43454 2.63927 + vertex 0.985984 1.4311 2.64063 + endloop + endfacet + facet normal 0.373412 -0.0214731 0.927417 + outer loop + vertex 0.985897 1.42611 2.64055 + vertex 0.989437 1.42956 2.63921 + vertex 0.985984 1.4311 2.64063 + endloop + endfacet + facet normal 0.310441 -0.0207485 0.950366 + outer loop + vertex 0.985984 1.4311 2.64063 + vertex 0.982237 1.42722 2.64177 + vertex 0.985897 1.42611 2.64055 + endloop + endfacet + facet normal 0.309499 -0.0241165 0.950594 + outer loop + vertex 0.982237 1.42722 2.64177 + vertex 0.982171 1.42223 2.64167 + vertex 0.985897 1.42611 2.64055 + endloop + endfacet + facet normal 0.307572 -0.0220743 0.951269 + outer loop + vertex 0.985897 1.42611 2.64055 + vertex 0.982171 1.42223 2.64167 + vertex 0.98581 1.42112 2.64046 + endloop + endfacet + facet normal 0.372423 -0.022801 0.927783 + outer loop + vertex 0.98581 1.42112 2.64046 + vertex 0.989338 1.42457 2.63913 + vertex 0.985897 1.42611 2.64055 + endloop + endfacet + facet normal 0.371638 -0.0218668 0.92812 + outer loop + vertex 0.989245 1.41958 2.63905 + vertex 0.989338 1.42457 2.63913 + vertex 0.98581 1.42112 2.64046 + endloop + endfacet + facet normal 0.371354 -0.0225841 0.928217 + outer loop + vertex 0.985738 1.41613 2.64037 + vertex 0.989245 1.41958 2.63905 + vertex 0.98581 1.42112 2.64046 + endloop + endfacet + facet normal 0.303449 -0.0220573 0.952592 + outer loop + vertex 0.98581 1.42112 2.64046 + vertex 0.982111 1.41723 2.64155 + vertex 0.985738 1.41613 2.64037 + endloop + endfacet + facet normal 0.30229 -0.0261511 0.952857 + outer loop + vertex 0.982111 1.41723 2.64155 + vertex 0.982059 1.41222 2.64143 + vertex 0.985738 1.41613 2.64037 + endloop + endfacet + facet normal 0.298406 -0.022131 0.954182 + outer loop + vertex 0.985738 1.41613 2.64037 + vertex 0.982059 1.41222 2.64143 + vertex 0.985663 1.41112 2.64028 + endloop + endfacet + facet normal 0.369441 -0.0227315 0.928976 + outer loop + vertex 0.985663 1.41112 2.64028 + vertex 0.989167 1.41458 2.63897 + vertex 0.985738 1.41613 2.64037 + endloop + endfacet + facet normal 0.367341 -0.0202647 0.929865 + outer loop + vertex 0.989063 1.40956 2.6389 + vertex 0.989167 1.41458 2.63897 + vertex 0.985663 1.41112 2.64028 + endloop + endfacet + facet normal 0.365935 -0.0237368 0.930338 + outer loop + vertex 0.98552 1.40614 2.64021 + vertex 0.989063 1.40956 2.6389 + vertex 0.985663 1.41112 2.64028 + endloop + endfacet + facet normal 0.293721 -0.022023 0.955637 + outer loop + vertex 0.985663 1.41112 2.64028 + vertex 0.981997 1.40725 2.64132 + vertex 0.98552 1.40614 2.64021 + endloop + endfacet + facet normal 0.292184 -0.0272513 0.955974 + outer loop + vertex 0.981997 1.40725 2.64132 + vertex 0.981898 1.4024 2.64121 + vertex 0.98552 1.40614 2.64021 + endloop + endfacet + facet normal 0.282266 -0.0168027 0.959189 + outer loop + vertex 0.98552 1.40614 2.64021 + vertex 0.981898 1.4024 2.64121 + vertex 0.985218 1.40133 2.64021 + endloop + endfacet + facet normal 0.361664 -0.0218085 0.932053 + outer loop + vertex 0.985218 1.40133 2.64021 + vertex 0.988817 1.40444 2.63889 + vertex 0.98552 1.40614 2.64021 + endloop + endfacet + facet normal 0.362188 -0.0225086 0.931833 + outer loop + vertex 0.988131 1.39877 2.63902 + vertex 0.988817 1.40444 2.63889 + vertex 0.985218 1.40133 2.64021 + endloop + endfacet + facet normal 0.359936 -0.0254452 0.93263 + outer loop + vertex 0.984613 1.39754 2.64034 + vertex 0.988131 1.39877 2.63902 + vertex 0.985218 1.40133 2.64021 + endloop + endfacet + facet normal 0.361664 -0.0312838 0.931783 + outer loop + vertex 0.984613 1.39754 2.64034 + vertex 0.985132 1.39428 2.64003 + vertex 0.988131 1.39877 2.63902 + endloop + endfacet + facet normal 0.360613 -0.0304849 0.932217 + outer loop + vertex 0.988131 1.39877 2.63902 + vertex 0.985132 1.39428 2.64003 + vertex 0.988546 1.39349 2.63868 + endloop + endfacet + facet normal 0.394093 -0.027002 0.918674 + outer loop + vertex 0.988546 1.39349 2.63868 + vertex 0.992131 1.39736 2.63726 + vertex 0.988131 1.39877 2.63902 + endloop + endfacet + facet normal 0.395134 -0.0236124 0.91832 + outer loop + vertex 0.992131 1.39736 2.63726 + vertex 0.992243 1.4026 2.63735 + vertex 0.988131 1.39877 2.63902 + endloop + endfacet + facet normal 0.392195 -0.0249256 0.919544 + outer loop + vertex 0.992145 1.39225 2.63712 + vertex 0.992131 1.39736 2.63726 + vertex 0.988546 1.39349 2.63868 + endloop + endfacet + facet normal 0.391141 -0.028417 0.919892 + outer loop + vertex 0.988569 1.38848 2.63852 + vertex 0.992145 1.39225 2.63712 + vertex 0.988546 1.39349 2.63868 + endloop + endfacet + facet normal 0.349063 -0.0291626 0.936645 + outer loop + vertex 0.988569 1.38848 2.63852 + vertex 0.988546 1.39349 2.63868 + vertex 0.9851 1.3897 2.63985 + endloop + endfacet + facet normal 0.347125 -0.0352178 0.937157 + outer loop + vertex 0.984955 1.38475 2.63972 + vertex 0.988569 1.38848 2.63852 + vertex 0.9851 1.3897 2.63985 + endloop + endfacet + facet normal 0.34143 -0.0289543 0.939461 + outer loop + vertex 0.988464 1.38343 2.6384 + vertex 0.988569 1.38848 2.63852 + vertex 0.984955 1.38475 2.63972 + endloop + endfacet + facet normal 0.338039 -0.0388484 0.94033 + outer loop + vertex 0.984614 1.3796 2.63963 + vertex 0.988464 1.38343 2.6384 + vertex 0.984955 1.38475 2.63972 + endloop + endfacet + facet normal 0.333338 -0.0335234 0.942211 + outer loop + vertex 0.988197 1.37823 2.63831 + vertex 0.988464 1.38343 2.6384 + vertex 0.984614 1.3796 2.63963 + endloop + endfacet + facet normal 0.324213 -0.0592612 0.944126 + outer loop + vertex 0.983519 1.37369 2.63963 + vertex 0.988197 1.37823 2.63831 + vertex 0.984614 1.3796 2.63963 + endloop + endfacet + facet normal 0.307208 -0.0397971 0.95081 + outer loop + vertex 0.987985 1.37298 2.63816 + vertex 0.988197 1.37823 2.63831 + vertex 0.983519 1.37369 2.63963 + endloop + endfacet + facet normal 0.30405 -0.059613 0.950789 + outer loop + vertex 0.983592 1.36817 2.63926 + vertex 0.987985 1.37298 2.63816 + vertex 0.983519 1.37369 2.63963 + endloop + endfacet + facet normal 0.285151 -0.040776 0.957615 + outer loop + vertex 0.988039 1.36792 2.63793 + vertex 0.987985 1.37298 2.63816 + vertex 0.983592 1.36817 2.63926 + endloop + endfacet + facet normal 0.28438 -0.0524793 0.957274 + outer loop + vertex 0.9836 1.36302 2.63898 + vertex 0.988039 1.36792 2.63793 + vertex 0.983592 1.36817 2.63926 + endloop + endfacet + facet normal 0.274231 -0.0425513 0.960722 + outer loop + vertex 0.988561 1.36283 2.63755 + vertex 0.988039 1.36792 2.63793 + vertex 0.9836 1.36302 2.63898 + endloop + endfacet + facet normal 0.274102 -0.0453282 0.960632 + outer loop + vertex 0.983485 1.35786 2.63877 + vertex 0.988561 1.36283 2.63755 + vertex 0.9836 1.36302 2.63898 + endloop + endfacet + facet normal 0.256113 -0.0255866 0.966308 + outer loop + vertex 0.987831 1.3572 2.6376 + vertex 0.988561 1.36283 2.63755 + vertex 0.983485 1.35786 2.63877 + endloop + endfacet + facet normal 0.253695 -0.0416413 0.966388 + outer loop + vertex 0.983313 1.35278 2.63859 + vertex 0.987831 1.3572 2.6376 + vertex 0.983485 1.35786 2.63877 + endloop + endfacet + facet normal 0.247894 -0.0353218 0.968143 + outer loop + vertex 0.987604 1.3522 2.63747 + vertex 0.987831 1.3572 2.6376 + vertex 0.983313 1.35278 2.63859 + endloop + endfacet + facet normal 0.246072 -0.0487081 0.968027 + outer loop + vertex 0.983273 1.34784 2.63836 + vertex 0.987604 1.3522 2.63747 + vertex 0.983313 1.35278 2.63859 + endloop + endfacet + facet normal 0.24121 -0.0435882 0.969494 + outer loop + vertex 0.987514 1.34729 2.63728 + vertex 0.987604 1.3522 2.63747 + vertex 0.983273 1.34784 2.63836 + endloop + endfacet + facet normal 0.239505 -0.056365 0.969258 + outer loop + vertex 0.983257 1.3429 2.63807 + vertex 0.987514 1.34729 2.63728 + vertex 0.983273 1.34784 2.63836 + endloop + endfacet + facet normal 0.230366 -0.0470127 0.971968 + outer loop + vertex 0.987434 1.34235 2.63706 + vertex 0.987514 1.34729 2.63728 + vertex 0.983257 1.3429 2.63807 + endloop + endfacet + facet normal 0.228909 -0.0576643 0.971738 + outer loop + vertex 0.98322 1.33794 2.63779 + vertex 0.987434 1.34235 2.63706 + vertex 0.983257 1.3429 2.63807 + endloop + endfacet + facet normal 0.220595 -0.0493308 0.974117 + outer loop + vertex 0.987327 1.33736 2.63683 + vertex 0.987434 1.34235 2.63706 + vertex 0.98322 1.33794 2.63779 + endloop + endfacet + facet normal 0.219354 -0.0578814 0.973927 + outer loop + vertex 0.98316 1.33295 2.6375 + vertex 0.987327 1.33736 2.63683 + vertex 0.98322 1.33794 2.63779 + endloop + endfacet + facet normal 0.209343 -0.0480042 0.976663 + outer loop + vertex 0.987231 1.33237 2.6366 + vertex 0.987327 1.33736 2.63683 + vertex 0.98316 1.33295 2.6375 + endloop + endfacet + facet normal 0.207449 -0.0608172 0.976353 + outer loop + vertex 0.983089 1.32793 2.63721 + vertex 0.987231 1.33237 2.6366 + vertex 0.98316 1.33295 2.6375 + endloop + endfacet + facet normal 0.198082 -0.0517417 0.978819 + outer loop + vertex 0.987158 1.32737 2.63635 + vertex 0.987231 1.33237 2.6366 + vertex 0.983089 1.32793 2.63721 + endloop + endfacet + facet normal 0.195963 -0.0663558 0.978364 + outer loop + vertex 0.983042 1.32286 2.63687 + vertex 0.987158 1.32737 2.63635 + vertex 0.983089 1.32793 2.63721 + endloop + endfacet + facet normal 0.190796 -0.0614817 0.979703 + outer loop + vertex 0.987169 1.32236 2.63604 + vertex 0.987158 1.32737 2.63635 + vertex 0.983042 1.32286 2.63687 + endloop + endfacet + facet normal 0.189235 -0.0734738 0.979179 + outer loop + vertex 0.983044 1.31772 2.63649 + vertex 0.987169 1.32236 2.63604 + vertex 0.983042 1.32286 2.63687 + endloop + endfacet + facet normal 0.339789 -0.0342873 0.939876 + outer loop + vertex 0.991914 1.36781 2.63652 + vertex 0.988039 1.36792 2.63793 + vertex 0.988561 1.36283 2.63755 + endloop + endfacet + facet normal 0.351055 -0.039067 0.935539 + outer loop + vertex 0.988039 1.36792 2.63793 + vertex 0.991883 1.3723 2.63667 + vertex 0.987985 1.37298 2.63816 + endloop + endfacet + facet normal 0.352878 -0.0280076 0.93525 + outer loop + vertex 0.991883 1.3723 2.63667 + vertex 0.99196 1.37722 2.63679 + vertex 0.987985 1.37298 2.63816 + endloop + endfacet + facet normal 0.365462 -0.0415418 0.929899 + outer loop + vertex 0.987985 1.37298 2.63816 + vertex 0.99196 1.37722 2.63679 + vertex 0.988197 1.37823 2.63831 + endloop + endfacet + facet normal 0.377154 -0.0354801 0.925471 + outer loop + vertex 0.988197 1.37823 2.63831 + vertex 0.992048 1.38223 2.6369 + vertex 0.988464 1.38343 2.6384 + endloop + endfacet + facet normal 0.380602 -0.0238751 0.924431 + outer loop + vertex 0.992048 1.38223 2.6369 + vertex 0.992113 1.38723 2.637 + vertex 0.988464 1.38343 2.6384 + endloop + endfacet + facet normal 0.385579 -0.0294787 0.922204 + outer loop + vertex 0.988464 1.38343 2.6384 + vertex 0.992113 1.38723 2.637 + vertex 0.988569 1.38848 2.63852 + endloop + endfacet + facet normal 0.358749 -0.0392126 0.93261 + outer loop + vertex 0.9851 1.3897 2.63985 + vertex 0.988546 1.39349 2.63868 + vertex 0.985132 1.39428 2.64003 + endloop + endfacet + facet normal 0.296785 -0.0437206 0.953943 + outer loop + vertex 0.984613 1.39754 2.64034 + vertex 0.982457 1.39485 2.64089 + vertex 0.985132 1.39428 2.64003 + endloop + endfacet + facet normal 0.397918 -0.0271716 0.917019 + outer loop + vertex 0.988131 1.39877 2.63902 + vertex 0.992243 1.4026 2.63735 + vertex 0.988817 1.40444 2.63889 + endloop + endfacet + facet normal 0.400586 -0.0213618 0.91601 + outer loop + vertex 0.992243 1.4026 2.63735 + vertex 0.992454 1.40779 2.63738 + vertex 0.988817 1.40444 2.63889 + endloop + endfacet + facet normal 0.400719 -0.0215345 0.915948 + outer loop + vertex 0.988817 1.40444 2.63889 + vertex 0.992454 1.40779 2.63738 + vertex 0.989063 1.40956 2.6389 + endloop + endfacet + facet normal 0.280666 -0.022116 0.959551 + outer loop + vertex 0.981898 1.4024 2.64121 + vertex 0.981889 1.39798 2.64111 + vertex 0.985218 1.40133 2.64021 + endloop + endfacet + facet normal 0.362602 -0.019745 0.931735 + outer loop + vertex 0.988817 1.40444 2.63889 + vertex 0.989063 1.40956 2.6389 + vertex 0.98552 1.40614 2.64021 + endloop + endfacet + facet normal 0.297364 -0.0257982 0.954415 + outer loop + vertex 0.982059 1.41222 2.64143 + vertex 0.981997 1.40725 2.64132 + vertex 0.985663 1.41112 2.64028 + endloop + endfacet + facet normal 0.37009 -0.0210928 0.928756 + outer loop + vertex 0.989167 1.41458 2.63897 + vertex 0.989245 1.41958 2.63905 + vertex 0.985738 1.41613 2.64037 + endloop + endfacet + facet normal 0.403686 -0.0213825 0.914648 + outer loop + vertex 0.989167 1.41458 2.63897 + vertex 0.992641 1.41783 2.63751 + vertex 0.989245 1.41958 2.63905 + endloop + endfacet + facet normal 0.403596 -0.0215884 0.914683 + outer loop + vertex 0.992641 1.41783 2.63751 + vertex 0.992729 1.42282 2.63759 + vertex 0.989245 1.41958 2.63905 + endloop + endfacet + facet normal 0.404111 -0.0222515 0.914439 + outer loop + vertex 0.989245 1.41958 2.63905 + vertex 0.992729 1.42282 2.63759 + vertex 0.989338 1.42457 2.63913 + endloop + endfacet + facet normal 0.404174 -0.0221089 0.914415 + outer loop + vertex 0.992729 1.42282 2.63759 + vertex 0.992832 1.42781 2.63767 + vertex 0.989338 1.42457 2.63913 + endloop + endfacet + facet normal 0.403709 -0.0215098 0.914634 + outer loop + vertex 0.989338 1.42457 2.63913 + vertex 0.992832 1.42781 2.63767 + vertex 0.989437 1.42956 2.63921 + endloop + endfacet + facet normal 0.306635 -0.0253925 0.951488 + outer loop + vertex 0.982171 1.42223 2.64167 + vertex 0.982111 1.41723 2.64155 + vertex 0.98581 1.42112 2.64046 + endloop + endfacet + facet normal 0.373095 -0.0210938 0.927553 + outer loop + vertex 0.989338 1.42457 2.63913 + vertex 0.989437 1.42956 2.63921 + vertex 0.985897 1.42611 2.64055 + endloop + endfacet + facet normal 0.403583 -0.018519 0.914756 + outer loop + vertex 0.989437 1.42956 2.63921 + vertex 0.992925 1.43281 2.63773 + vertex 0.989521 1.43454 2.63927 + endloop + endfacet + facet normal 0.404638 -0.0160801 0.914335 + outer loop + vertex 0.992925 1.43281 2.63773 + vertex 0.992996 1.4378 2.63779 + vertex 0.989521 1.43454 2.63927 + endloop + endfacet + facet normal 0.403791 -0.0149957 0.914729 + outer loop + vertex 0.989521 1.43454 2.63927 + vertex 0.992996 1.4378 2.63779 + vertex 0.989584 1.43953 2.63932 + endloop + endfacet + facet normal 0.311476 -0.0218537 0.950003 + outer loop + vertex 0.982295 1.43221 2.64187 + vertex 0.982237 1.42722 2.64177 + vertex 0.985984 1.4311 2.64063 + endloop + endfacet + facet normal 0.374656 -0.0147592 0.927046 + outer loop + vertex 0.989521 1.43454 2.63927 + vertex 0.989584 1.43953 2.63932 + vertex 0.986048 1.43609 2.6407 + endloop + endfacet + facet normal 0.404377 -0.0120098 0.914513 + outer loop + vertex 0.989584 1.43953 2.63932 + vertex 0.993048 1.44279 2.63783 + vertex 0.989634 1.44453 2.63937 + endloop + endfacet + facet normal 0.404956 -0.0106633 0.914274 + outer loop + vertex 0.993048 1.44279 2.63783 + vertex 0.993093 1.44778 2.63787 + vertex 0.989634 1.44453 2.63937 + endloop + endfacet + facet normal 0.405004 -0.0107244 0.914252 + outer loop + vertex 0.989634 1.44453 2.63937 + vertex 0.993093 1.44778 2.63787 + vertex 0.989681 1.44951 2.6394 + endloop + endfacet + facet normal 0.317826 -0.0153284 0.948025 + outer loop + vertex 0.982375 1.44219 2.64202 + vertex 0.982342 1.4372 2.64195 + vertex 0.986101 1.44108 2.64076 + endloop + endfacet + facet normal 0.376542 -0.0105473 0.92634 + outer loop + vertex 0.989634 1.44453 2.63937 + vertex 0.989681 1.44951 2.6394 + vertex 0.986146 1.44607 2.6408 + endloop + endfacet + facet normal 0.405768 -0.0118881 0.913899 + outer loop + vertex 0.989681 1.44951 2.6394 + vertex 0.993139 1.45277 2.63791 + vertex 0.989734 1.4545 2.63945 + endloop + endfacet + facet normal 0.405666 -0.0121236 0.913941 + outer loop + vertex 0.993139 1.45277 2.63791 + vertex 0.99319 1.45776 2.63795 + vertex 0.989734 1.4545 2.63945 + endloop + endfacet + facet normal 0.406324 -0.0129617 0.913637 + outer loop + vertex 0.989734 1.4545 2.63945 + vertex 0.99319 1.45776 2.63795 + vertex 0.989792 1.4595 2.63949 + endloop + endfacet + facet normal 0.323057 -0.0135226 0.946283 + outer loop + vertex 0.982446 1.45217 2.64214 + vertex 0.982409 1.44718 2.64208 + vertex 0.986194 1.45106 2.64085 + endloop + endfacet + facet normal 0.324866 -0.0116399 0.945688 + outer loop + vertex 0.982522 1.46216 2.64225 + vertex 0.98249 1.45717 2.6422 + vertex 0.986299 1.46104 2.64094 + endloop + endfacet + facet normal 0.378764 -0.0127514 0.925405 + outer loop + vertex 0.989734 1.4545 2.63945 + vertex 0.989792 1.4595 2.63949 + vertex 0.986247 1.45605 2.64089 + endloop + endfacet + facet normal 0.378403 -0.00965622 0.925591 + outer loop + vertex 0.986299 1.46104 2.64094 + vertex 0.989837 1.46449 2.63953 + vertex 0.986333 1.46604 2.64098 + endloop + endfacet + facet normal 0.40547 -0.00816333 0.914072 + outer loop + vertex 0.989837 1.46449 2.63953 + vertex 0.993273 1.46774 2.63804 + vertex 0.98986 1.46948 2.63957 + endloop + endfacet + facet normal 0.406653 -0.00540173 0.913567 + outer loop + vertex 0.993273 1.46774 2.63804 + vertex 0.993272 1.47272 2.63807 + vertex 0.98986 1.46948 2.63957 + endloop + endfacet + facet normal 0.406734 -0.0120121 0.913468 + outer loop + vertex 0.99319 1.45776 2.63795 + vertex 0.99324 1.46275 2.638 + vertex 0.989792 1.4595 2.63949 + endloop + endfacet + facet normal 0.445274 -0.0112232 0.895324 + outer loop + vertex 0.999912 1.45929 2.63474 + vertex 0.999962 1.46428 2.63478 + vertex 0.996617 1.46101 2.6364 + endloop + endfacet + facet normal 0.465185 -0.011597 0.885137 + outer loop + vertex 0.99986 1.4543 2.6347 + vertex 1.00309 1.45755 2.63305 + vertex 0.999912 1.45929 2.63474 + endloop + endfacet + facet normal 0.422652 -0.0122312 0.90621 + outer loop + vertex 0.99319 1.45776 2.63795 + vertex 0.993139 1.45277 2.63791 + vertex 0.996567 1.45602 2.63636 + endloop + endfacet + facet normal 0.404951 -0.0108471 0.914274 + outer loop + vertex 0.993093 1.44778 2.63787 + vertex 0.993139 1.45277 2.63791 + vertex 0.989681 1.44951 2.6394 + endloop + endfacet + facet normal 0.444781 -0.0119493 0.89556 + outer loop + vertex 0.999806 1.44931 2.63466 + vertex 0.99986 1.4543 2.6347 + vertex 0.996521 1.45103 2.63632 + endloop + endfacet + facet normal 0.421854 -0.0107535 0.9066 + outer loop + vertex 0.993093 1.44778 2.63787 + vertex 0.993048 1.44279 2.63783 + vertex 0.996476 1.44604 2.63628 + endloop + endfacet + facet normal 0.404828 -0.0125847 0.914306 + outer loop + vertex 0.992996 1.4378 2.63779 + vertex 0.993048 1.44279 2.63783 + vertex 0.989584 1.43953 2.63932 + endloop + endfacet + facet normal 0.447267 -0.0138193 0.894294 + outer loop + vertex 0.999692 1.43931 2.63457 + vertex 0.999753 1.44431 2.63462 + vertex 0.996425 1.44104 2.63624 + endloop + endfacet + facet normal 0.47134 -0.0169842 0.881788 + outer loop + vertex 0.999617 1.4343 2.63452 + vertex 1.00285 1.43753 2.63285 + vertex 0.999692 1.43931 2.63457 + endloop + endfacet + facet normal 0.4229 -0.0162471 0.906031 + outer loop + vertex 0.992996 1.4378 2.63779 + vertex 0.992925 1.43281 2.63773 + vertex 0.996364 1.43605 2.63619 + endloop + endfacet + facet normal 0.4045 -0.0196975 0.914326 + outer loop + vertex 0.992832 1.42781 2.63767 + vertex 0.992925 1.43281 2.63773 + vertex 0.989437 1.42956 2.63921 + endloop + endfacet + facet normal 0.448636 -0.0187924 0.893517 + outer loop + vertex 0.999534 1.42928 2.63445 + vertex 0.999617 1.4343 2.63452 + vertex 0.996282 1.43104 2.63612 + endloop + endfacet + facet normal 0.423552 -0.022372 0.905596 + outer loop + vertex 0.992832 1.42781 2.63767 + vertex 0.992729 1.42282 2.63759 + vertex 0.996184 1.42604 2.63605 + endloop + endfacet + facet normal 0.444483 -0.0202493 0.895558 + outer loop + vertex 0.999374 1.4193 2.63431 + vertex 0.999448 1.42428 2.63438 + vertex 0.996088 1.42104 2.63598 + endloop + endfacet + facet normal 0.464904 -0.0191522 0.885154 + outer loop + vertex 0.999323 1.41434 2.63423 + vertex 1.00263 1.41761 2.63256 + vertex 0.999374 1.4193 2.63431 + endloop + endfacet + facet normal 0.422651 -0.0206414 0.906057 + outer loop + vertex 0.992641 1.41783 2.63751 + vertex 0.992564 1.41283 2.63743 + vertex 0.996012 1.41606 2.6359 + endloop + endfacet + facet normal 0.402982 -0.0204805 0.914979 + outer loop + vertex 0.992564 1.41283 2.63743 + vertex 0.992641 1.41783 2.63751 + vertex 0.989167 1.41458 2.63897 + endloop + endfacet + facet normal 0.402841 -0.0208013 0.915033 + outer loop + vertex 0.989063 1.40956 2.6389 + vertex 0.992564 1.41283 2.63743 + vertex 0.989167 1.41458 2.63897 + endloop + endfacet + facet normal 0.401696 -0.0193359 0.915569 + outer loop + vertex 0.992454 1.40779 2.63738 + vertex 0.992564 1.41283 2.63743 + vertex 0.989063 1.40956 2.6389 + endloop + endfacet + facet normal 0.440984 -0.0169897 0.897354 + outer loop + vertex 0.999287 1.40939 2.63415 + vertex 0.999323 1.41434 2.63423 + vertex 0.995952 1.41108 2.63582 + endloop + endfacet + facet normal 0.418914 -0.0220626 0.907758 + outer loop + vertex 0.992454 1.40779 2.63738 + vertex 0.992243 1.4026 2.63735 + vertex 0.995874 1.40606 2.63576 + endloop + endfacet + facet normal 0.437102 -0.0194099 0.899202 + outer loop + vertex 0.999178 1.39943 2.634 + vertex 0.999243 1.40442 2.63408 + vertex 0.995783 1.40099 2.63568 + endloop + endfacet + facet normal 0.413808 -0.0245936 0.910032 + outer loop + vertex 0.992131 1.39736 2.63726 + vertex 0.992145 1.39225 2.63712 + vertex 0.995708 1.39593 2.63559 + endloop + endfacet + facet normal 0.387248 -0.0240656 0.921661 + outer loop + vertex 0.992113 1.38723 2.637 + vertex 0.992145 1.39225 2.63712 + vertex 0.988569 1.38848 2.63852 + endloop + endfacet + facet normal 0.433842 -0.0220394 0.900719 + outer loop + vertex 0.999021 1.3895 2.63384 + vertex 0.999096 1.39444 2.63392 + vertex 0.995649 1.39092 2.6355 + endloop + endfacet + facet normal 0.408788 -0.0239909 0.912314 + outer loop + vertex 0.992113 1.38723 2.637 + vertex 0.992048 1.38223 2.6369 + vertex 0.995602 1.38597 2.6354 + endloop + endfacet + facet normal 0.369138 -0.0265115 0.928997 + outer loop + vertex 0.99196 1.37722 2.63679 + vertex 0.992048 1.38223 2.6369 + vertex 0.988197 1.37823 2.63831 + endloop + endfacet + facet normal 0.432923 -0.0213814 0.901178 + outer loop + vertex 0.998884 1.37964 2.63367 + vertex 0.998967 1.38458 2.63375 + vertex 0.995554 1.38104 2.63531 + endloop + endfacet + facet normal 0.400357 -0.0282868 0.915923 + outer loop + vertex 0.99196 1.37722 2.63679 + vertex 0.991883 1.3723 2.63667 + vertex 0.995448 1.37609 2.63523 + endloop + endfacet + facet normal 0.340011 -0.0280906 0.940002 + outer loop + vertex 0.991914 1.36781 2.63652 + vertex 0.991883 1.3723 2.63667 + vertex 0.988039 1.36792 2.63793 + endloop + endfacet + facet normal 0.433271 -0.0263339 0.900879 + outer loop + vertex 0.998022 1.36884 2.63378 + vertex 0.99865 1.37452 2.63365 + vertex 0.995187 1.37125 2.63522 + endloop + endfacet + facet normal 0.436679 -0.0311627 0.899078 + outer loop + vertex 0.998022 1.36884 2.63378 + vertex 0.995157 1.36423 2.63501 + vertex 0.998504 1.36365 2.63337 + endloop + endfacet + facet normal 0.436282 -0.0337415 0.899177 + outer loop + vertex 0.995185 1.35975 2.63483 + vertex 0.998504 1.36365 2.63337 + vertex 0.995157 1.36423 2.63501 + endloop + endfacet + facet normal 0.436307 -0.0337676 0.899164 + outer loop + vertex 0.998768 1.35869 2.63305 + vertex 0.998504 1.36365 2.63337 + vertex 0.995185 1.35975 2.63483 + endloop + endfacet + facet normal 0.461505 -0.0316265 0.886574 + outer loop + vertex 0.998768 1.35869 2.63305 + vertex 1.002 1.36261 2.63151 + vertex 0.998504 1.36365 2.63337 + endloop + endfacet + facet normal 0.462016 -0.0295591 0.886379 + outer loop + vertex 1.002 1.36261 2.63151 + vertex 1.0018 1.36756 2.63178 + vertex 0.998504 1.36365 2.63337 + endloop + endfacet + facet normal 0.460554 -0.0279984 0.88719 + outer loop + vertex 0.998504 1.36365 2.63337 + vertex 1.0018 1.36756 2.63178 + vertex 0.998022 1.36884 2.63378 + endloop + endfacet + facet normal 0.462461 -0.0326229 0.886039 + outer loop + vertex 1.00266 1.35759 2.63098 + vertex 1.002 1.36261 2.63151 + vertex 0.998768 1.35869 2.63305 + endloop + endfacet + facet normal 0.462791 -0.0312243 0.885917 + outer loop + vertex 1.00266 1.35759 2.63098 + vertex 0.998768 1.35869 2.63305 + vertex 0.999081 1.35346 2.63271 + endloop + endfacet + facet normal 0.3886 -0.0228709 0.921123 + outer loop + vertex 0.994633 1.36742 2.63537 + vertex 0.991914 1.36781 2.63652 + vertex 0.992506 1.36468 2.6362 + endloop + endfacet + facet normal 0.339556 -0.0341113 0.939967 + outer loop + vertex 0.992506 1.36468 2.6362 + vertex 0.991914 1.36781 2.63652 + vertex 0.988561 1.36283 2.63755 + endloop + endfacet + facet normal 0.396689 -0.0347217 0.917296 + outer loop + vertex 0.995185 1.35975 2.63483 + vertex 0.995157 1.36423 2.63501 + vertex 0.991864 1.36085 2.63631 + endloop + endfacet + facet normal 0.435708 -0.0361144 0.899363 + outer loop + vertex 0.995176 1.35487 2.63464 + vertex 0.998768 1.35869 2.63305 + vertex 0.995185 1.35975 2.63483 + endloop + endfacet + facet normal 0.433818 -0.0339178 0.900362 + outer loop + vertex 0.999081 1.35346 2.63271 + vertex 0.998768 1.35869 2.63305 + vertex 0.995176 1.35487 2.63464 + endloop + endfacet + facet normal 0.394206 -0.0365099 0.918297 + outer loop + vertex 0.995004 1.34982 2.63451 + vertex 0.995176 1.35487 2.63464 + vertex 0.991422 1.3512 2.63611 + endloop + endfacet + facet normal 0.330266 -0.0384405 0.943105 + outer loop + vertex 0.987831 1.3572 2.6376 + vertex 0.987604 1.3522 2.63747 + vertex 0.991568 1.35609 2.63624 + endloop + endfacet + facet normal 0.381106 -0.0375504 0.923768 + outer loop + vertex 0.994515 1.3397 2.63431 + vertex 0.994714 1.34473 2.63444 + vertex 0.991113 1.34124 2.63578 + endloop + endfacet + facet normal 0.392397 -0.0418363 0.918844 + outer loop + vertex 0.991271 1.34624 2.63594 + vertex 0.995004 1.34982 2.63451 + vertex 0.991422 1.3512 2.63611 + endloop + endfacet + facet normal 0.424375 -0.0357851 0.904779 + outer loop + vertex 0.998 1.34296 2.63282 + vertex 0.998311 1.34803 2.63288 + vertex 0.994714 1.34473 2.63444 + endloop + endfacet + facet normal 0.432747 -0.0373817 0.90074 + outer loop + vertex 0.995004 1.34982 2.63451 + vertex 0.999081 1.35346 2.63271 + vertex 0.995176 1.35487 2.63464 + endloop + endfacet + facet normal 0.470242 -0.0300196 0.882027 + outer loop + vertex 1.0046 1.34449 2.62949 + vertex 1.00465 1.34939 2.62964 + vertex 1.00143 1.34617 2.63124 + endloop + endfacet + facet normal 0.443167 -0.0360014 0.895716 + outer loop + vertex 0.998 1.34296 2.63282 + vertex 0.997822 1.33792 2.63271 + vertex 1.00125 1.34118 2.63115 + endloop + endfacet + facet normal 0.41667 -0.0349941 0.908384 + outer loop + vertex 0.997694 1.33292 2.63258 + vertex 0.997822 1.33792 2.63271 + vertex 0.994372 1.33469 2.63417 + endloop + endfacet + facet normal 0.460146 -0.0292022 0.887363 + outer loop + vertex 1.00438 1.33449 2.62928 + vertex 1.00448 1.33948 2.62939 + vertex 1.00111 1.33616 2.63103 + endloop + endfacet + facet normal 0.485439 -0.030175 0.873749 + outer loop + vertex 1.0043 1.32956 2.62916 + vertex 1.0076 1.33287 2.62744 + vertex 1.00438 1.33449 2.62928 + endloop + endfacet + facet normal 0.486325 -0.0279303 0.873331 + outer loop + vertex 1.0076 1.33287 2.62744 + vertex 1.00768 1.33784 2.62755 + vertex 1.00438 1.33449 2.62928 + endloop + endfacet + facet normal 0.487502 -0.0294542 0.872625 + outer loop + vertex 1.00438 1.33449 2.62928 + vertex 1.00768 1.33784 2.62755 + vertex 1.00448 1.33948 2.62939 + endloop + endfacet + facet normal 0.488711 -0.0264385 0.872045 + outer loop + vertex 1.00768 1.33784 2.62755 + vertex 1.00779 1.34283 2.62764 + vertex 1.00448 1.33948 2.62939 + endloop + endfacet + facet normal 0.490925 -0.0293133 0.870709 + outer loop + vertex 1.00448 1.33948 2.62939 + vertex 1.00779 1.34283 2.62764 + vertex 1.0046 1.34449 2.62949 + endloop + endfacet + facet normal 0.484569 -0.0290378 0.874271 + outer loop + vertex 1.00752 1.32793 2.62732 + vertex 1.0076 1.33287 2.62744 + vertex 1.0043 1.32956 2.62916 + endloop + endfacet + facet normal 0.4837 -0.0312232 0.874677 + outer loop + vertex 1.00423 1.32465 2.62902 + vertex 1.00752 1.32793 2.62732 + vertex 1.0043 1.32956 2.62916 + endloop + endfacet + facet normal 0.482181 -0.029225 0.875584 + outer loop + vertex 1.00743 1.32301 2.6272 + vertex 1.00752 1.32793 2.62732 + vertex 1.00423 1.32465 2.62902 + endloop + endfacet + facet normal 0.435912 -0.0355171 0.899288 + outer loop + vertex 0.997694 1.33292 2.63258 + vertex 0.997554 1.32792 2.63245 + vertex 1.00101 1.33118 2.6309 + endloop + endfacet + facet normal 0.40779 -0.0398086 0.912208 + outer loop + vertex 0.997295 1.32276 2.63234 + vertex 0.997554 1.32792 2.63245 + vertex 0.993972 1.32467 2.63391 + endloop + endfacet + facet normal 0.453935 -0.0312521 0.890487 + outer loop + vertex 1.00423 1.32465 2.62902 + vertex 1.0043 1.32956 2.62916 + vertex 1.00091 1.32622 2.63077 + endloop + endfacet + facet normal 0.481208 -0.0316256 0.876036 + outer loop + vertex 1.00417 1.31974 2.62888 + vertex 1.00743 1.32301 2.6272 + vertex 1.00423 1.32465 2.62902 + endloop + endfacet + facet normal 0.480698 -0.0309616 0.87634 + outer loop + vertex 1.00732 1.31808 2.62709 + vertex 1.00743 1.32301 2.6272 + vertex 1.00417 1.31974 2.62888 + endloop + endfacet + facet normal 0.47884 -0.0354039 0.877188 + outer loop + vertex 1.00405 1.31477 2.62874 + vertex 1.00732 1.31808 2.62709 + vertex 1.00417 1.31974 2.62888 + endloop + endfacet + facet normal 0.422991 -0.042128 0.905154 + outer loop + vertex 0.997295 1.32276 2.63234 + vertex 0.997144 1.3175 2.63216 + vertex 1.00082 1.32123 2.63062 + endloop + endfacet + facet normal 0.373547 -0.0442514 0.926555 + outer loop + vertex 0.997107 1.31236 2.63193 + vertex 0.997144 1.3175 2.63216 + vertex 0.993267 1.31329 2.63353 + endloop + endfacet + facet normal 0.447814 -0.0351356 0.893436 + outer loop + vertex 1.00405 1.31477 2.62874 + vertex 1.00417 1.31974 2.62888 + vertex 1.00075 1.31621 2.63045 + endloop + endfacet + facet normal 0.475002 -0.0395469 0.879096 + outer loop + vertex 1.00377 1.30967 2.62866 + vertex 1.00718 1.31307 2.62697 + vertex 1.00405 1.31477 2.62874 + endloop + endfacet + facet normal 0.47753 -0.0337207 0.877968 + outer loop + vertex 1.00718 1.31307 2.62697 + vertex 1.00732 1.31808 2.62709 + vertex 1.00405 1.31477 2.62874 + endloop + endfacet + facet normal 0.473616 -0.0377514 0.879922 + outer loop + vertex 1.00692 1.3079 2.62689 + vertex 1.00718 1.31307 2.62697 + vertex 1.00377 1.30967 2.62866 + endloop + endfacet + facet normal 0.470671 -0.0442679 0.881198 + outer loop + vertex 1.00307 1.30402 2.62875 + vertex 1.00692 1.3079 2.62689 + vertex 1.00377 1.30967 2.62866 + endloop + endfacet + facet normal 0.464962 -0.0369914 0.884557 + outer loop + vertex 1.00675 1.30282 2.62676 + vertex 1.00692 1.3079 2.62689 + vertex 1.00307 1.30402 2.62875 + endloop + endfacet + facet normal 0.464011 -0.0404638 0.884905 + outer loop + vertex 1.00352 1.29891 2.62828 + vertex 1.00675 1.30282 2.62676 + vertex 1.00307 1.30402 2.62875 + endloop + endfacet + facet normal 0.459343 -0.0355713 0.887546 + outer loop + vertex 1.00681 1.29827 2.62655 + vertex 1.00675 1.30282 2.62676 + vertex 1.00352 1.29891 2.62828 + endloop + endfacet + facet normal 0.458327 -0.0415009 0.887814 + outer loop + vertex 1.00681 1.29827 2.62655 + vertex 1.00352 1.29891 2.62828 + vertex 1.00397 1.29378 2.62781 + endloop + endfacet + facet normal 0.454733 -0.0386771 0.889788 + outer loop + vertex 1.00733 1.29501 2.62615 + vertex 1.00681 1.29827 2.62655 + vertex 1.00397 1.29378 2.62781 + endloop + endfacet + facet normal 0.455305 -0.040752 0.889403 + outer loop + vertex 1.00733 1.29501 2.62615 + vertex 1.00397 1.29378 2.62781 + vertex 1.00674 1.29115 2.62627 + endloop + endfacet + facet normal 0.482264 -0.0454134 0.874848 + outer loop + vertex 1.00975 1.29413 2.62477 + vertex 1.00733 1.29501 2.62615 + vertex 1.00674 1.29115 2.62627 + endloop + endfacet + facet normal 0.475816 -0.0368865 0.878771 + outer loop + vertex 1.0097 1.28953 2.6246 + vertex 1.00975 1.29413 2.62477 + vertex 1.00674 1.29115 2.62627 + endloop + endfacet + facet normal 0.472661 -0.0440373 0.880143 + outer loop + vertex 1.00639 1.28626 2.62621 + vertex 1.0097 1.28953 2.6246 + vertex 1.00674 1.29115 2.62627 + endloop + endfacet + facet normal 0.44982 -0.0425842 0.892103 + outer loop + vertex 1.00674 1.29115 2.62627 + vertex 1.00327 1.28814 2.62788 + vertex 1.00639 1.28626 2.62621 + endloop + endfacet + facet normal 0.446881 -0.0485056 0.893277 + outer loop + vertex 1.00327 1.28814 2.62788 + vertex 1.00295 1.28302 2.62776 + vertex 1.00639 1.28626 2.62621 + endloop + endfacet + facet normal 0.444759 -0.0456729 0.894485 + outer loop + vertex 1.00639 1.28626 2.62621 + vertex 1.00295 1.28302 2.62776 + vertex 1.00619 1.28127 2.62606 + endloop + endfacet + facet normal 0.464967 -0.0461967 0.884122 + outer loop + vertex 1.00619 1.28127 2.62606 + vertex 1.00956 1.28459 2.62446 + vertex 1.00639 1.28626 2.62621 + endloop + endfacet + facet normal 0.462809 -0.0433919 0.885395 + outer loop + vertex 1.00942 1.27964 2.62429 + vertex 1.00956 1.28459 2.62446 + vertex 1.00619 1.28127 2.62606 + endloop + endfacet + facet normal 0.460262 -0.0495534 0.886399 + outer loop + vertex 1.00601 1.27629 2.62587 + vertex 1.00942 1.27964 2.62429 + vertex 1.00619 1.28127 2.62606 + endloop + endfacet + facet normal 0.439424 -0.049237 0.89693 + outer loop + vertex 1.00619 1.28127 2.62606 + vertex 1.00271 1.27797 2.62758 + vertex 1.00601 1.27629 2.62587 + endloop + endfacet + facet normal 0.436758 -0.0554299 0.89787 + outer loop + vertex 1.00271 1.27797 2.62758 + vertex 1.00241 1.27283 2.62741 + vertex 1.00601 1.27629 2.62587 + endloop + endfacet + facet normal 0.431322 -0.0484212 0.900898 + outer loop + vertex 1.00601 1.27629 2.62587 + vertex 1.00241 1.27283 2.62741 + vertex 1.00585 1.27131 2.62568 + endloop + endfacet + facet normal 0.458117 -0.0467799 0.88766 + outer loop + vertex 1.00928 1.27473 2.62411 + vertex 1.00942 1.27964 2.62429 + vertex 1.00601 1.27629 2.62587 + endloop + endfacet + facet normal 0.441763 -0.0523082 0.895606 + outer loop + vertex 1.00295 1.28302 2.62776 + vertex 1.00271 1.27797 2.62758 + vertex 1.00619 1.28127 2.62606 + endloop + endfacet + facet normal 0.418926 -0.0516387 0.906551 + outer loop + vertex 1.00271 1.27797 2.62758 + vertex 1.00295 1.28302 2.62776 + vertex 0.999442 1.27974 2.62919 + endloop + endfacet + facet normal 0.415851 -0.0582506 0.907565 + outer loop + vertex 0.999098 1.27464 2.62902 + vertex 1.00271 1.27797 2.62758 + vertex 0.999442 1.27974 2.62919 + endloop + endfacet + facet normal 0.424395 -0.0473346 0.904239 + outer loop + vertex 1.00295 1.28302 2.62776 + vertex 1.00327 1.28814 2.62788 + vertex 0.999683 1.28478 2.62939 + endloop + endfacet + facet normal 0.427078 -0.0508464 0.902784 + outer loop + vertex 0.999683 1.28478 2.62939 + vertex 1.00327 1.28814 2.62788 + vertex 0.999983 1.2899 2.62953 + endloop + endfacet + facet normal 0.430773 -0.0426554 0.901452 + outer loop + vertex 1.00327 1.28814 2.62788 + vertex 1.00397 1.29378 2.62781 + vertex 0.999983 1.2899 2.62953 + endloop + endfacet + facet normal 0.468323 -0.0383671 0.882724 + outer loop + vertex 1.00956 1.28459 2.62446 + vertex 1.0097 1.28953 2.6246 + vertex 1.00639 1.28626 2.62621 + endloop + endfacet + facet normal 0.484303 -0.0385796 0.874049 + outer loop + vertex 1.00927 1.29747 2.62518 + vertex 1.00733 1.29501 2.62615 + vertex 1.00975 1.29413 2.62477 + endloop + endfacet + facet normal 0.451757 -0.0454126 0.890984 + outer loop + vertex 1.00397 1.29378 2.62781 + vertex 1.00327 1.28814 2.62788 + vertex 1.00674 1.29115 2.62627 + endloop + endfacet + facet normal 0.479059 -0.0332084 0.877154 + outer loop + vertex 1.00927 1.29747 2.62518 + vertex 1.00681 1.29827 2.62655 + vertex 1.00733 1.29501 2.62615 + endloop + endfacet + facet normal 0.480858 -0.0263792 0.876402 + outer loop + vertex 1.00979 1.30122 2.62501 + vertex 1.00681 1.29827 2.62655 + vertex 1.00927 1.29747 2.62518 + endloop + endfacet + facet normal 0.435192 -0.0446166 0.899231 + outer loop + vertex 1.00397 1.29378 2.62781 + vertex 1.00352 1.29891 2.62828 + vertex 1.00017 1.29491 2.6297 + endloop + endfacet + facet normal 0.439427 -0.0489721 0.896943 + outer loop + vertex 1.00017 1.29491 2.6297 + vertex 1.00352 1.29891 2.62828 + vertex 1.00016 1.29943 2.62996 + endloop + endfacet + facet normal 0.409665 -0.047765 0.910985 + outer loop + vertex 0.997107 1.31236 2.63193 + vertex 0.996969 1.30742 2.63174 + vertex 1.0006 1.31122 2.6303 + endloop + endfacet + facet normal 0.337771 -0.0450944 0.940148 + outer loop + vertex 0.996933 1.30295 2.63153 + vertex 0.996969 1.30742 2.63174 + vertex 0.993061 1.30304 2.63293 + endloop + endfacet + facet normal 0.337438 -0.0539359 0.939801 + outer loop + vertex 0.996933 1.30295 2.63153 + vertex 0.993061 1.30304 2.63293 + vertex 0.993539 1.29799 2.63247 + endloop + endfacet + facet normal 0.441294 -0.0403592 0.896455 + outer loop + vertex 1.00307 1.30402 2.62875 + vertex 1.00377 1.30967 2.62866 + vertex 1.00026 1.30639 2.63024 + endloop + endfacet + facet normal 0.440201 -0.0436305 0.896838 + outer loop + vertex 1.00307 1.30402 2.62875 + vertex 1.00016 1.29943 2.62996 + vertex 1.00352 1.29891 2.62828 + endloop + endfacet + facet normal 0.392279 -0.0394563 0.919 + outer loop + vertex 0.999654 1.30258 2.63036 + vertex 0.996933 1.30295 2.63153 + vertex 0.997491 1.29985 2.63116 + endloop + endfacet + facet normal 0.335308 -0.0523186 0.940655 + outer loop + vertex 0.997491 1.29985 2.63116 + vertex 0.996933 1.30295 2.63153 + vertex 0.993539 1.29799 2.63247 + endloop + endfacet + facet normal 0.396859 -0.0501505 0.916509 + outer loop + vertex 1.00017 1.29491 2.6297 + vertex 1.00016 1.29943 2.62996 + vertex 0.996829 1.29603 2.63121 + endloop + endfacet + facet normal 0.434476 -0.0473595 0.899438 + outer loop + vertex 0.999983 1.2899 2.62953 + vertex 1.00397 1.29378 2.62781 + vertex 1.00017 1.29491 2.6297 + endloop + endfacet + facet normal 0.316694 -0.0584677 0.946724 + outer loop + vertex 0.992779 1.29236 2.63239 + vertex 0.992525 1.28734 2.63216 + vertex 0.996482 1.29123 2.63108 + endloop + endfacet + facet normal 0.382758 -0.0488117 0.922558 + outer loop + vertex 0.999683 1.28478 2.62939 + vertex 0.999983 1.2899 2.62953 + vertex 0.996266 1.28628 2.63088 + endloop + endfacet + facet normal 0.421107 -0.0544788 0.905374 + outer loop + vertex 0.999442 1.27974 2.62919 + vertex 1.00295 1.28302 2.62776 + vertex 0.999683 1.28478 2.62939 + endloop + endfacet + facet normal 0.365264 -0.0555605 0.929245 + outer loop + vertex 0.999098 1.27464 2.62902 + vertex 0.999442 1.27974 2.62919 + vertex 0.995863 1.27634 2.6304 + endloop + endfacet + facet normal 0.294716 -0.0716175 0.952897 + outer loop + vertex 0.99241 1.2824 2.63186 + vertex 0.99229 1.27744 2.63153 + vertex 0.996087 1.2813 2.63064 + endloop + endfacet + facet normal 0.361545 -0.0633883 0.930197 + outer loop + vertex 0.995454 1.27152 2.63023 + vertex 0.999098 1.27464 2.62902 + vertex 0.995863 1.27634 2.6304 + endloop + endfacet + facet normal 0.412932 -0.0544063 0.909136 + outer loop + vertex 1.00241 1.27283 2.62741 + vertex 1.00271 1.27797 2.62758 + vertex 0.999098 1.27464 2.62902 + endloop + endfacet + facet normal 0.355343 -0.0806454 0.93125 + outer loop + vertex 0.994687 1.26772 2.63025 + vertex 0.994814 1.26434 2.6299 + vertex 0.998233 1.26896 2.629 + endloop + endfacet + facet normal 0.367512 -0.0376282 0.929257 + outer loop + vertex 1.00211 1.26249 2.62704 + vertex 1.00219 1.26763 2.62722 + vertex 0.998269 1.2635 2.6286 + endloop + endfacet + facet normal 0.430105 -0.0516271 0.901301 + outer loop + vertex 1.00241 1.27283 2.62741 + vertex 1.00219 1.26763 2.62722 + vertex 1.00585 1.27131 2.62568 + endloop + endfacet + facet normal 0.439367 -0.0217226 0.898045 + outer loop + vertex 1.00907 1.26489 2.62387 + vertex 1.00915 1.26983 2.62395 + vertex 1.00574 1.26632 2.62553 + endloop + endfacet + facet normal 0.457324 -0.0487826 0.887961 + outer loop + vertex 1.00585 1.27131 2.62568 + vertex 1.00928 1.27473 2.62411 + vertex 1.00601 1.27629 2.62587 + endloop + endfacet + facet normal 0.474905 -0.026649 0.879633 + outer loop + vertex 1.01232 1.26814 2.62219 + vertex 1.01243 1.27309 2.62228 + vertex 1.00915 1.26983 2.62395 + endloop + endfacet + facet normal 0.534899 -0.0433895 0.843801 + outer loop + vertex 1.01905 1.28458 2.6187 + vertex 1.01914 1.28957 2.6189 + vertex 1.01597 1.28629 2.62075 + endloop + endfacet + facet normal 0.49007 -0.0395646 0.870785 + outer loop + vertex 1.01914 1.28957 2.6189 + vertex 1.0224 1.2928 2.61722 + vertex 1.01931 1.29463 2.61904 + endloop + endfacet + facet normal 0.481956 -0.0568061 0.874352 + outer loop + vertex 1.0224 1.2928 2.61722 + vertex 1.02279 1.29793 2.61733 + vertex 1.01931 1.29463 2.61904 + endloop + endfacet + facet normal 0.469779 -0.0400838 0.881874 + outer loop + vertex 1.01931 1.29463 2.61904 + vertex 1.02279 1.29793 2.61733 + vertex 1.01959 1.2998 2.61912 + endloop + endfacet + facet normal 0.457646 -0.0654097 0.886725 + outer loop + vertex 1.02279 1.29793 2.61733 + vertex 1.02364 1.30351 2.61731 + vertex 1.01959 1.2998 2.61912 + endloop + endfacet + facet normal 0.440343 -0.0415472 0.896868 + outer loop + vertex 1.01959 1.2998 2.61912 + vertex 1.02364 1.30351 2.61731 + vertex 1.0198 1.30492 2.61926 + endloop + endfacet + facet normal 0.433843 -0.0619595 0.898855 + outer loop + vertex 1.02364 1.30351 2.61731 + vertex 1.02345 1.30854 2.61774 + vertex 1.0198 1.30492 2.61926 + endloop + endfacet + facet normal 0.41778 -0.0421049 0.907572 + outer loop + vertex 1.0198 1.30492 2.61926 + vertex 1.02345 1.30854 2.61774 + vertex 1.01985 1.30985 2.61946 + endloop + endfacet + facet normal 0.408753 -0.0702 0.909941 + outer loop + vertex 1.02345 1.30854 2.61774 + vertex 1.02371 1.31342 2.618 + vertex 1.01985 1.30985 2.61946 + endloop + endfacet + facet normal 0.518919 -0.027476 0.854382 + outer loop + vertex 1.01305 1.30386 2.62314 + vertex 1.01246 1.29831 2.62332 + vertex 1.01622 1.30165 2.62115 + endloop + endfacet + facet normal 0.52194 -0.0297327 0.852464 + outer loop + vertex 1.01608 1.29645 2.62105 + vertex 1.01283 1.29298 2.62291 + vertex 1.01604 1.29132 2.6209 + endloop + endfacet + facet normal 0.504663 -0.0366449 0.862538 + outer loop + vertex 1.0097 1.28953 2.6246 + vertex 1.01283 1.29298 2.62291 + vertex 1.00975 1.29413 2.62477 + endloop + endfacet + facet normal 0.487023 -0.0345292 0.872707 + outer loop + vertex 1.00675 1.30282 2.62676 + vertex 1.00681 1.29827 2.62655 + vertex 1.00979 1.30122 2.62501 + endloop + endfacet + facet normal 0.518375 -0.026628 0.854738 + outer loop + vertex 1.01305 1.30386 2.62314 + vertex 1.01325 1.30892 2.62317 + vertex 1.01006 1.30607 2.62502 + endloop + endfacet + facet normal 0.515476 -0.0264428 0.856496 + outer loop + vertex 1.01333 1.31389 2.62328 + vertex 1.01325 1.30892 2.62317 + vertex 1.01645 1.31168 2.62134 + endloop + endfacet + facet normal 0.50331 -0.0389953 0.863226 + outer loop + vertex 1.00718 1.31307 2.62697 + vertex 1.00692 1.3079 2.62689 + vertex 1.01023 1.3111 2.62511 + endloop + endfacet + facet normal 0.530178 -0.0266613 0.847467 + outer loop + vertex 1.01333 1.31389 2.62328 + vertex 1.01341 1.31882 2.62339 + vertex 1.01035 1.31612 2.62522 + endloop + endfacet + facet normal 0.511672 -0.0283037 0.858714 + outer loop + vertex 1.01365 1.32379 2.62341 + vertex 1.01341 1.31882 2.62339 + vertex 1.01657 1.32142 2.62159 + endloop + endfacet + facet normal 0.513568 -0.0312084 0.857481 + outer loop + vertex 1.00743 1.32301 2.6272 + vertex 1.00732 1.31808 2.62709 + vertex 1.01047 1.32107 2.62531 + endloop + endfacet + facet normal 0.529751 -0.0344603 0.847453 + outer loop + vertex 1.01365 1.32379 2.62341 + vertex 1.0143 1.32922 2.62322 + vertex 1.01069 1.32609 2.62535 + endloop + endfacet + facet normal 0.500509 -0.0418111 0.864721 + outer loop + vertex 1.01702 1.33319 2.62184 + vertex 1.01402 1.33452 2.62364 + vertex 1.0143 1.32922 2.62322 + endloop + endfacet + facet normal 0.495318 -0.0564512 0.866875 + outer loop + vertex 1.01702 1.33319 2.62184 + vertex 1.01717 1.33779 2.62205 + vertex 1.01402 1.33452 2.62364 + endloop + endfacet + facet normal 0.482159 -0.0397674 0.875181 + outer loop + vertex 1.01402 1.33452 2.62364 + vertex 1.01717 1.33779 2.62205 + vertex 1.0141 1.33949 2.62382 + endloop + endfacet + facet normal 0.476154 -0.0532785 0.877747 + outer loop + vertex 1.01717 1.33779 2.62205 + vertex 1.01744 1.34273 2.62221 + vertex 1.0141 1.33949 2.62382 + endloop + endfacet + facet normal 0.464212 -0.0373385 0.884937 + outer loop + vertex 1.0141 1.33949 2.62382 + vertex 1.01744 1.34273 2.62221 + vertex 1.0143 1.34449 2.62393 + endloop + endfacet + facet normal 0.456109 -0.0550046 0.888222 + outer loop + vertex 1.01744 1.34273 2.62221 + vertex 1.01785 1.34778 2.62231 + vertex 1.0143 1.34449 2.62393 + endloop + endfacet + facet normal 0.445122 -0.0400426 0.894574 + outer loop + vertex 1.0143 1.34449 2.62393 + vertex 1.01785 1.34778 2.62231 + vertex 1.01461 1.34957 2.624 + endloop + endfacet + facet normal 0.43479 -0.0623637 0.89837 + outer loop + vertex 1.01785 1.34778 2.62231 + vertex 1.01871 1.35331 2.62227 + vertex 1.01461 1.34957 2.624 + endloop + endfacet + facet normal 0.417478 -0.0389798 0.907851 + outer loop + vertex 1.01461 1.34957 2.624 + vertex 1.01871 1.35331 2.62227 + vertex 1.01477 1.35466 2.62414 + endloop + endfacet + facet normal 0.412938 -0.0540897 0.909152 + outer loop + vertex 1.01871 1.35331 2.62227 + vertex 1.0185 1.35839 2.62267 + vertex 1.01477 1.35466 2.62414 + endloop + endfacet + facet normal 0.512641 -0.0290762 0.85811 + outer loop + vertex 1.0076 1.33287 2.62744 + vertex 1.00752 1.32793 2.62732 + vertex 1.01082 1.33117 2.62545 + endloop + endfacet + facet normal 0.514599 -0.0395641 0.856517 + outer loop + vertex 1.01402 1.33452 2.62364 + vertex 1.0141 1.33949 2.62382 + vertex 1.01085 1.3362 2.62562 + endloop + endfacet + facet normal 0.506913 -0.0266339 0.861586 + outer loop + vertex 1.00779 1.34283 2.62764 + vertex 1.00768 1.33784 2.62755 + vertex 1.01095 1.34118 2.62573 + endloop + endfacet + facet normal 0.492165 -0.0262455 0.870106 + outer loop + vertex 1.00779 1.34283 2.62764 + vertex 1.00786 1.34783 2.62775 + vertex 1.0046 1.34449 2.62949 + endloop + endfacet + facet normal 0.494972 -0.0298738 0.868395 + outer loop + vertex 1.0046 1.34449 2.62949 + vertex 1.00786 1.34783 2.62775 + vertex 1.00465 1.34939 2.62964 + endloop + endfacet + facet normal 0.496579 -0.0256088 0.867614 + outer loop + vertex 1.00786 1.34783 2.62775 + vertex 1.00775 1.35283 2.62796 + vertex 1.00465 1.34939 2.62964 + endloop + endfacet + facet normal 0.499443 -0.0254764 0.865972 + outer loop + vertex 1.00775 1.35283 2.62796 + vertex 1.00786 1.34783 2.62775 + vertex 1.01119 1.3512 2.62593 + endloop + endfacet + facet normal 0.49065 -0.0424669 0.870322 + outer loop + vertex 1.0143 1.34449 2.62393 + vertex 1.01461 1.34957 2.624 + vertex 1.0111 1.34618 2.62581 + endloop + endfacet + facet normal 0.495855 -0.0221312 0.868123 + outer loop + vertex 1.00799 1.36382 2.62812 + vertex 1.00718 1.35826 2.62844 + vertex 1.01116 1.36144 2.62624 + endloop + endfacet + facet normal 0.499172 -0.0262136 0.866106 + outer loop + vertex 1.01112 1.35629 2.62612 + vertex 1.00775 1.35283 2.62796 + vertex 1.01119 1.3512 2.62593 + endloop + endfacet + facet normal 0.49808 -0.0274066 0.866698 + outer loop + vertex 1.00465 1.34939 2.62964 + vertex 1.00775 1.35283 2.62796 + vertex 1.00436 1.35389 2.62995 + endloop + endfacet + facet normal 0.505719 -0.023905 0.862367 + outer loop + vertex 1.00718 1.35826 2.62844 + vertex 1.00799 1.36382 2.62812 + vertex 1.00502 1.36174 2.6298 + endloop + endfacet + facet normal 0.494693 -0.0230233 0.868763 + outer loop + vertex 1.00817 1.36879 2.62815 + vertex 1.00799 1.36382 2.62812 + vertex 1.01132 1.36652 2.62629 + endloop + endfacet + facet normal 0.488673 -0.0276989 0.872027 + outer loop + vertex 1.0018 1.36756 2.63178 + vertex 1.002 1.36261 2.63151 + vertex 1.00505 1.366 2.62991 + endloop + endfacet + facet normal 0.460494 -0.0282136 0.887214 + outer loop + vertex 1.0018 1.36756 2.63178 + vertex 1.00187 1.37275 2.63191 + vertex 0.998022 1.36884 2.63378 + endloop + endfacet + facet normal 0.461786 -0.0298288 0.88649 + outer loop + vertex 0.998022 1.36884 2.63378 + vertex 1.00187 1.37275 2.63191 + vertex 0.99865 1.37452 2.63365 + endloop + endfacet + facet normal 0.463427 -0.0261207 0.88575 + outer loop + vertex 1.00187 1.37275 2.63191 + vertex 1.0021 1.37795 2.63194 + vertex 0.99865 1.37452 2.63365 + endloop + endfacet + facet normal 0.463223 -0.0258587 0.885864 + outer loop + vertex 0.99865 1.37452 2.63365 + vertex 1.0021 1.37795 2.63194 + vertex 0.998884 1.37964 2.63367 + endloop + endfacet + facet normal 0.509931 -0.0250409 0.859851 + outer loop + vertex 1.00817 1.36879 2.62815 + vertex 1.00827 1.37379 2.62823 + vertex 1.0051 1.37093 2.63003 + endloop + endfacet + facet normal 0.491911 -0.025327 0.870277 + outer loop + vertex 1.00851 1.37886 2.62824 + vertex 1.00827 1.37379 2.62823 + vertex 1.01148 1.37645 2.6265 + endloop + endfacet + facet normal 0.493089 -0.0273449 0.869549 + outer loop + vertex 1.0021 1.37795 2.63194 + vertex 1.00187 1.37275 2.63191 + vertex 1.00524 1.37601 2.6301 + endloop + endfacet + facet normal 0.464502 -0.0228106 0.885278 + outer loop + vertex 1.0021 1.37795 2.63194 + vertex 1.00224 1.38299 2.632 + vertex 0.998884 1.37964 2.63367 + endloop + endfacet + facet normal 0.463594 -0.0216516 0.885783 + outer loop + vertex 0.998884 1.37964 2.63367 + vertex 1.00224 1.38299 2.632 + vertex 0.998967 1.38458 2.63375 + endloop + endfacet + facet normal 0.463412 -0.0221171 0.885867 + outer loop + vertex 1.00224 1.38299 2.632 + vertex 1.00231 1.38794 2.63209 + vertex 0.998967 1.38458 2.63375 + endloop + endfacet + facet normal 0.462438 -0.0208807 0.886406 + outer loop + vertex 0.998967 1.38458 2.63375 + vertex 1.00231 1.38794 2.63209 + vertex 0.999021 1.3895 2.63384 + endloop + endfacet + facet normal 0.508982 -0.0269688 0.860354 + outer loop + vertex 1.00851 1.37886 2.62824 + vertex 1.00914 1.38434 2.62805 + vertex 1.00547 1.38114 2.63011 + endloop + endfacet + facet normal 0.482847 -0.0338478 0.87505 + outer loop + vertex 1.01186 1.38831 2.6267 + vertex 1.00882 1.38957 2.62842 + vertex 1.00914 1.38434 2.62805 + endloop + endfacet + facet normal 0.47848 -0.0468824 0.876846 + outer loop + vertex 1.01186 1.38831 2.6267 + vertex 1.01198 1.39281 2.62687 + vertex 1.00882 1.38957 2.62842 + endloop + endfacet + facet normal 0.467041 -0.0324888 0.883638 + outer loop + vertex 1.00882 1.38957 2.62842 + vertex 1.01198 1.39281 2.62687 + vertex 1.00886 1.39447 2.62858 + endloop + endfacet + facet normal 0.463704 -0.0402565 0.885075 + outer loop + vertex 1.01198 1.39281 2.62687 + vertex 1.01215 1.39766 2.627 + vertex 1.00886 1.39447 2.62858 + endloop + endfacet + facet normal 0.491958 -0.0222266 0.870335 + outer loop + vertex 1.00231 1.38794 2.63209 + vertex 1.00224 1.38299 2.632 + vertex 1.00559 1.38624 2.63019 + endloop + endfacet + facet normal 0.462032 -0.0219458 0.886592 + outer loop + vertex 1.00231 1.38794 2.63209 + vertex 1.00237 1.39287 2.63218 + vertex 0.999021 1.3895 2.63384 + endloop + endfacet + facet normal 0.462253 -0.0222259 0.88647 + outer loop + vertex 0.999021 1.3895 2.63384 + vertex 1.00237 1.39287 2.63218 + vertex 0.999096 1.39444 2.63392 + endloop + endfacet + facet normal 0.462509 -0.0215636 0.886352 + outer loop + vertex 1.00237 1.39287 2.63218 + vertex 1.00245 1.39782 2.63225 + vertex 0.999096 1.39444 2.63392 + endloop + endfacet + facet normal 0.462393 -0.0214161 0.886416 + outer loop + vertex 0.999096 1.39444 2.63392 + vertex 1.00245 1.39782 2.63225 + vertex 0.999178 1.39943 2.634 + endloop + endfacet + facet normal 0.496882 -0.032202 0.867221 + outer loop + vertex 1.00882 1.38957 2.62842 + vertex 1.00886 1.39447 2.62858 + vertex 1.0056 1.39122 2.63033 + endloop + endfacet + facet normal 0.455503 -0.0294693 0.889747 + outer loop + vertex 1.00886 1.39447 2.62858 + vertex 1.01215 1.39766 2.627 + vertex 1.00897 1.3994 2.62869 + endloop + endfacet + facet normal 0.452037 -0.0372302 0.891222 + outer loop + vertex 1.01215 1.39766 2.627 + vertex 1.01231 1.40261 2.62713 + vertex 1.00897 1.3994 2.62869 + endloop + endfacet + facet normal 0.444578 -0.0274953 0.895318 + outer loop + vertex 1.00897 1.3994 2.62869 + vertex 1.01231 1.40261 2.62713 + vertex 1.00908 1.40438 2.62879 + endloop + endfacet + facet normal 0.484733 -0.0217538 0.874392 + outer loop + vertex 1.00245 1.39782 2.63225 + vertex 1.00237 1.39287 2.63218 + vertex 1.00568 1.39615 2.63043 + endloop + endfacet + facet normal 0.462989 -0.0199049 0.886141 + outer loop + vertex 1.00245 1.39782 2.63225 + vertex 1.00252 1.40278 2.63233 + vertex 0.999178 1.39943 2.634 + endloop + endfacet + facet normal 0.478855 -0.0176848 0.877716 + outer loop + vertex 1.00257 1.40774 2.6324 + vertex 1.00252 1.40278 2.63233 + vertex 1.00583 1.40609 2.63059 + endloop + endfacet + facet normal 0.481908 -0.0279678 0.875775 + outer loop + vertex 1.00897 1.3994 2.62869 + vertex 1.00908 1.40438 2.62879 + vertex 1.00576 1.40111 2.63051 + endloop + endfacet + facet normal 0.4683 -0.0207298 0.883326 + outer loop + vertex 1.00583 1.40609 2.63059 + vertex 1.00923 1.4094 2.62887 + vertex 1.00591 1.41106 2.63066 + endloop + endfacet + facet normal 0.440997 -0.0354426 0.896808 + outer loop + vertex 1.01231 1.40261 2.62713 + vertex 1.01249 1.40763 2.62724 + vertex 1.00908 1.40438 2.62879 + endloop + endfacet + facet normal 0.45666 0.0451321 0.888496 + outer loop + vertex 1.00852 1.63321 2.62766 + vertex 1.00765 1.62873 2.62833 + vertex 1.01126 1.63098 2.62636 + endloop + endfacet + facet normal 0.448836 0.0297953 0.893117 + outer loop + vertex 1.01151 1.62592 2.62646 + vertex 1.00852 1.62252 2.62807 + vertex 1.01202 1.6216 2.62634 + endloop + endfacet + facet normal 0.493864 0.028342 0.869077 + outer loop + vertex 1.00771 1.61811 2.62867 + vertex 1.00852 1.62252 2.62807 + vertex 1.00514 1.62044 2.63006 + endloop + endfacet + facet normal 0.487506 0.0288681 0.872642 + outer loop + vertex 1.00183 1.62256 2.63184 + vertex 1.00211 1.61757 2.63185 + vertex 1.00514 1.62044 2.63006 + endloop + endfacet + facet normal 0.457072 0.0254474 0.889065 + outer loop + vertex 1.00183 1.62256 2.63184 + vertex 1.00129 1.62797 2.63196 + vertex 0.998285 1.62411 2.63362 + endloop + endfacet + facet normal 0.451839 0.0306032 0.891574 + outer loop + vertex 0.998285 1.62411 2.63362 + vertex 1.00129 1.62797 2.63196 + vertex 0.997354 1.62881 2.63393 + endloop + endfacet + facet normal 0.49894 0.0277822 0.866191 + outer loop + vertex 1.00429 1.62961 2.63024 + vertex 1.00482 1.62539 2.63007 + vertex 1.00765 1.62873 2.62833 + endloop + endfacet + facet normal 0.450381 0.0214474 0.892579 + outer loop + vertex 0.999551 1.63261 2.63273 + vertex 0.997354 1.62881 2.63393 + vertex 1.00129 1.62797 2.63196 + endloop + endfacet + facet normal 0.496074 0.0289135 0.867798 + outer loop + vertex 1.00527 1.63368 2.62952 + vertex 1.00471 1.63896 2.62966 + vertex 1.00196 1.6359 2.63134 + endloop + endfacet + facet normal 0.497625 0.0283871 0.866927 + outer loop + vertex 1.00471 1.63896 2.62966 + vertex 1.00771 1.64227 2.62784 + vertex 1.00446 1.64397 2.62965 + endloop + endfacet + facet normal 0.460098 0.0327906 0.887263 + outer loop + vertex 0.998157 1.64235 2.63309 + vertex 0.998599 1.63733 2.63304 + vertex 1.00147 1.64071 2.63143 + endloop + endfacet + facet normal 0.485921 0.0282975 0.873545 + outer loop + vertex 1.00446 1.64397 2.62965 + vertex 1.00438 1.64899 2.62952 + vertex 1.00125 1.64569 2.63137 + endloop + endfacet + facet normal 0.4982 0.0273325 0.866631 + outer loop + vertex 1.00438 1.64899 2.62952 + vertex 1.0076 1.65233 2.62757 + vertex 1.00436 1.65399 2.62938 + endloop + endfacet + facet normal 0.456276 0.0310922 0.889295 + outer loop + vertex 0.997926 1.65242 2.63285 + vertex 0.997989 1.64739 2.63299 + vertex 1.00118 1.6507 2.63124 + endloop + endfacet + facet normal 0.481003 0.0265207 0.876317 + outer loop + vertex 1.00436 1.65399 2.62938 + vertex 1.00431 1.65899 2.62926 + vertex 1.00114 1.65569 2.6311 + endloop + endfacet + facet normal 0.499043 0.0263578 0.866176 + outer loop + vertex 1.00431 1.65899 2.62926 + vertex 1.00748 1.66239 2.62732 + vertex 1.00423 1.664 2.62915 + endloop + endfacet + facet normal 0.451986 0.0315482 0.891467 + outer loop + vertex 0.99773 1.66246 2.6326 + vertex 0.997851 1.65745 2.63272 + vertex 1.00105 1.66068 2.63098 + endloop + endfacet + facet normal 0.429723 0.0331387 0.902352 + outer loop + vertex 0.99773 1.66246 2.6326 + vertex 0.997583 1.66745 2.63249 + vertex 0.994351 1.66422 2.63415 + endloop + endfacet + facet normal 0.428722 0.0343617 0.902783 + outer loop + vertex 0.994351 1.66422 2.63415 + vertex 0.997583 1.66745 2.63249 + vertex 0.994225 1.66922 2.63401 + endloop + endfacet + facet normal 0.429327 0.0358071 0.902439 + outer loop + vertex 0.997583 1.66745 2.63249 + vertex 0.997432 1.6724 2.63236 + vertex 0.994225 1.66922 2.63401 + endloop + endfacet + facet normal 0.473702 0.0272094 0.880265 + outer loop + vertex 1.00423 1.664 2.62915 + vertex 1.00413 1.66902 2.62905 + vertex 1.00092 1.66567 2.63088 + endloop + endfacet + facet normal 0.4447 0.0360888 0.894952 + outer loop + vertex 0.997432 1.6724 2.63236 + vertex 0.997583 1.66745 2.63249 + vertex 1.0008 1.67067 2.63076 + endloop + endfacet + facet normal 0.42877 0.0396765 0.902542 + outer loop + vertex 0.997432 1.6724 2.63236 + vertex 0.997265 1.67734 2.63223 + vertex 0.994056 1.67415 2.63389 + endloop + endfacet + facet normal 0.426213 0.0428043 0.903609 + outer loop + vertex 0.994056 1.67415 2.63389 + vertex 0.997265 1.67734 2.63223 + vertex 0.993771 1.67911 2.63379 + endloop + endfacet + facet normal 0.426231 0.0428468 0.903599 + outer loop + vertex 0.997265 1.67734 2.63223 + vertex 0.997061 1.68231 2.63209 + vertex 0.993771 1.67911 2.63379 + endloop + endfacet + facet normal 0.436204 0.0431213 0.898814 + outer loop + vertex 0.997061 1.68231 2.63209 + vertex 0.997265 1.67734 2.63223 + vertex 1.00057 1.68064 2.63046 + endloop + endfacet + facet normal 0.435035 0.0399867 0.899525 + outer loop + vertex 1.0004 1.68553 2.63033 + vertex 0.997061 1.68231 2.63209 + vertex 1.00057 1.68064 2.63046 + endloop + endfacet + facet normal 0.43108 0.0450127 0.90119 + outer loop + vertex 0.996993 1.68715 2.63188 + vertex 0.997061 1.68231 2.63209 + vertex 1.0004 1.68553 2.63033 + endloop + endfacet + facet normal 0.42933 0.0403268 0.902247 + outer loop + vertex 1.0001 1.69019 2.63026 + vertex 0.996993 1.68715 2.63188 + vertex 1.0004 1.68553 2.63033 + endloop + endfacet + facet normal 0.445861 0.0412946 0.894149 + outer loop + vertex 1.0004 1.68553 2.63033 + vertex 1.00343 1.68889 2.62866 + vertex 1.0001 1.69019 2.63026 + endloop + endfacet + facet normal 0.443717 0.0340699 0.895519 + outer loop + vertex 1.00343 1.68889 2.62866 + vertex 1.00267 1.69299 2.62888 + vertex 1.0001 1.69019 2.63026 + endloop + endfacet + facet normal 0.437411 0.0412537 0.898315 + outer loop + vertex 1.0001 1.69019 2.63026 + vertex 1.00267 1.69299 2.62888 + vertex 0.999789 1.6948 2.6302 + endloop + endfacet + facet normal 0.423692 0.040427 0.904904 + outer loop + vertex 0.999789 1.6948 2.6302 + vertex 0.996756 1.69177 2.63176 + vertex 1.0001 1.69019 2.63026 + endloop + endfacet + facet normal 0.420702 0.044052 0.906129 + outer loop + vertex 0.99601 1.69687 2.63186 + vertex 0.996756 1.69177 2.63176 + vertex 0.999789 1.6948 2.6302 + endloop + endfacet + facet normal 0.417684 0.0371786 0.907832 + outer loop + vertex 0.999789 1.6948 2.6302 + vertex 0.999408 1.69888 2.63021 + vertex 0.99601 1.69687 2.63186 + endloop + endfacet + facet normal 0.439613 0.0392496 0.89733 + outer loop + vertex 0.999408 1.69888 2.63021 + vertex 0.999789 1.6948 2.6302 + vertex 1.00338 1.698 2.6283 + endloop + endfacet + facet normal 0.437713 0.0418614 0.89814 + outer loop + vertex 1.00267 1.69299 2.62888 + vertex 1.00338 1.698 2.6283 + vertex 0.999789 1.6948 2.6302 + endloop + endfacet + facet normal 0.451802 0.034604 0.891447 + outer loop + vertex 1.0038 1.68406 2.62866 + vertex 1.00343 1.68889 2.62866 + vertex 1.0004 1.68553 2.63033 + endloop + endfacet + facet normal 0.425457 0.0451335 0.903852 + outer loop + vertex 0.996756 1.69177 2.63176 + vertex 0.996993 1.68715 2.63188 + vertex 1.0001 1.69019 2.63026 + endloop + endfacet + facet normal 0.417483 0.0448223 0.907579 + outer loop + vertex 0.996993 1.68715 2.63188 + vertex 0.996756 1.69177 2.63176 + vertex 0.994178 1.68898 2.63308 + endloop + endfacet + facet normal 0.419997 0.0450821 0.906405 + outer loop + vertex 0.997061 1.68231 2.63209 + vertex 0.996993 1.68715 2.63188 + vertex 0.993231 1.68449 2.63375 + endloop + endfacet + facet normal 0.46362 0.0333426 0.885406 + outer loop + vertex 1.00404 1.67406 2.62892 + vertex 1.00396 1.67908 2.62878 + vertex 1.00069 1.67566 2.63062 + endloop + endfacet + facet normal 0.453702 0.0403709 0.890239 + outer loop + vertex 1.00057 1.68064 2.63046 + vertex 1.0038 1.68406 2.62866 + vertex 1.0004 1.68553 2.63033 + endloop + endfacet + facet normal 0.493232 0.0314967 0.869328 + outer loop + vertex 1.00721 1.67738 2.62699 + vertex 1.00709 1.68241 2.62688 + vertex 1.00396 1.67908 2.62878 + endloop + endfacet + facet normal 0.509478 0.0349393 0.859774 + outer loop + vertex 1.00612 1.69281 2.62705 + vertex 1.00677 1.68744 2.62688 + vertex 1.00961 1.69043 2.62507 + endloop + endfacet + facet normal 0.50919 0.0258665 0.860266 + outer loop + vertex 1.0102 1.69861 2.62443 + vertex 1.00971 1.70389 2.62456 + vertex 1.00684 1.70101 2.62635 + endloop + endfacet + facet normal 0.467951 0.0388127 0.882902 + outer loop + vertex 1.00336 1.70726 2.62798 + vertex 1.00412 1.70304 2.62776 + vertex 1.00658 1.70573 2.62634 + endloop + endfacet + facet normal 0.432394 0.0371477 0.900919 + outer loop + vertex 1.00336 1.70726 2.62798 + vertex 1.00298 1.71222 2.62796 + vertex 0.999841 1.70881 2.6296 + endloop + endfacet + facet normal 0.429007 0.0409674 0.902371 + outer loop + vertex 0.999841 1.70881 2.6296 + vertex 1.00298 1.71222 2.62796 + vertex 0.999525 1.71392 2.62952 + endloop + endfacet + facet normal 0.42894 0.0407943 0.902411 + outer loop + vertex 1.00298 1.71222 2.62796 + vertex 1.00281 1.71727 2.62781 + vertex 0.999525 1.71392 2.62952 + endloop + endfacet + facet normal 0.495788 0.028018 0.867992 + outer loop + vertex 1.00948 1.70889 2.62455 + vertex 1.00939 1.71392 2.62444 + vertex 1.00629 1.71056 2.62632 + endloop + endfacet + facet normal 0.452611 0.0412597 0.890753 + outer loop + vertex 1.00281 1.71727 2.62781 + vertex 1.00298 1.71222 2.62796 + vertex 1.00615 1.71557 2.62619 + endloop + endfacet + facet normal 0.427807 0.0404564 0.902964 + outer loop + vertex 1.00281 1.71727 2.62781 + vertex 1.0027 1.72232 2.62764 + vertex 0.999383 1.71897 2.62936 + endloop + endfacet + facet normal 0.428363 0.0397863 0.90273 + outer loop + vertex 0.999383 1.71897 2.62936 + vertex 1.0027 1.72232 2.62764 + vertex 0.999289 1.72402 2.62918 + endloop + endfacet + facet normal 0.427562 0.037758 0.903197 + outer loop + vertex 1.0027 1.72232 2.62764 + vertex 1.00258 1.72734 2.62748 + vertex 0.999289 1.72402 2.62918 + endloop + endfacet + facet normal 0.480089 0.0344566 0.876543 + outer loop + vertex 1.00933 1.71897 2.62429 + vertex 1.00924 1.72401 2.62415 + vertex 1.00605 1.72061 2.62602 + endloop + endfacet + facet normal 0.448215 0.0379157 0.893121 + outer loop + vertex 1.00258 1.72734 2.62748 + vertex 1.0027 1.72232 2.62764 + vertex 1.00594 1.72565 2.62587 + endloop + endfacet + facet normal 0.428295 0.0336282 0.903013 + outer loop + vertex 1.00258 1.72734 2.62748 + vertex 1.00247 1.73231 2.62735 + vertex 0.999204 1.72905 2.62902 + endloop + endfacet + facet normal 0.426574 0.0357273 0.903747 + outer loop + vertex 0.999204 1.72905 2.62902 + vertex 1.00247 1.73231 2.62735 + vertex 0.999077 1.73402 2.62888 + endloop + endfacet + facet normal 0.426755 0.0361816 0.903643 + outer loop + vertex 1.00247 1.73231 2.62735 + vertex 1.00231 1.73722 2.62723 + vertex 0.999077 1.73402 2.62888 + endloop + endfacet + facet normal 0.472859 0.0277266 0.880702 + outer loop + vertex 1.00911 1.72904 2.62403 + vertex 1.00901 1.73404 2.62392 + vertex 1.00582 1.73064 2.62574 + endloop + endfacet + facet normal 0.439692 0.0364467 0.897409 + outer loop + vertex 1.00231 1.73722 2.62723 + vertex 1.00247 1.73231 2.62735 + vertex 1.00572 1.73558 2.62562 + endloop + endfacet + facet normal 0.420122 0.0466097 0.90627 + outer loop + vertex 1.00231 1.73722 2.62723 + vertex 1.00202 1.74213 2.62711 + vertex 0.998771 1.73897 2.62878 + endloop + endfacet + facet normal 0.41061 0.0583193 0.909944 + outer loop + vertex 0.998771 1.73897 2.62878 + vertex 1.00202 1.74213 2.62711 + vertex 0.998079 1.74429 2.62875 + endloop + endfacet + facet normal 0.410134 0.0572347 0.910228 + outer loop + vertex 1.00202 1.74213 2.62711 + vertex 1.00172 1.74696 2.62694 + vertex 0.998079 1.74429 2.62875 + endloop + endfacet + facet normal 0.413066 0.0538533 0.909107 + outer loop + vertex 1.00114 1.75192 2.62691 + vertex 1.00172 1.74696 2.62694 + vertex 1.00487 1.7501 2.62533 + endloop + endfacet + facet normal 0.405738 0.0530084 0.912451 + outer loop + vertex 1.00172 1.74696 2.62694 + vertex 1.00114 1.75192 2.62691 + vertex 0.998776 1.74864 2.62815 + endloop + endfacet + facet normal 0.439013 0.0373681 0.897703 + outer loop + vertex 1.00885 1.74386 2.62373 + vertex 1.00853 1.74878 2.62368 + vertex 1.00534 1.74531 2.62538 + endloop + endfacet + facet normal 0.410709 0.0478052 0.910512 + outer loop + vertex 1.00487 1.7501 2.62533 + vertex 1.00432 1.75402 2.62537 + vertex 1.00114 1.75192 2.62691 + endloop + endfacet + facet normal 0.409228 0.0499783 0.911062 + outer loop + vertex 0.998776 1.74864 2.62815 + vertex 1.00114 1.75192 2.62691 + vertex 0.997692 1.75181 2.62847 + endloop + endfacet + facet normal 0.408711 0.0595052 0.910722 + outer loop + vertex 0.998079 1.74429 2.62875 + vertex 1.00172 1.74696 2.62694 + vertex 0.998776 1.74864 2.62815 + endloop + endfacet + facet normal 0.385728 0.0551383 0.920964 + outer loop + vertex 0.998771 1.73897 2.62878 + vertex 0.998079 1.74429 2.62875 + vertex 0.995126 1.74044 2.63022 + endloop + endfacet + facet normal 0.419507 0.0450473 0.906634 + outer loop + vertex 0.999077 1.73402 2.62888 + vertex 1.00231 1.73722 2.62723 + vertex 0.998771 1.73897 2.62878 + endloop + endfacet + facet normal 0.326703 0.0514986 0.943723 + outer loop + vertex 0.991812 1.73667 2.63155 + vertex 0.992013 1.73158 2.63176 + vertex 0.995574 1.73553 2.63031 + endloop + endfacet + facet normal 0.262014 0.0469933 0.963919 + outer loop + vertex 0.992028 1.72649 2.63201 + vertex 0.992013 1.73158 2.63176 + vertex 0.987875 1.72701 2.63311 + endloop + endfacet + facet normal 0.263451 0.0607761 0.962756 + outer loop + vertex 0.987933 1.72207 2.6334 + vertex 0.992028 1.72649 2.63201 + vertex 0.987875 1.72701 2.63311 + endloop + endfacet + facet normal 0.275546 0.0487051 0.960053 + outer loop + vertex 0.992101 1.7215 2.63224 + vertex 0.992028 1.72649 2.63201 + vertex 0.987933 1.72207 2.6334 + endloop + endfacet + facet normal 0.277707 0.0680968 0.958249 + outer loop + vertex 0.988302 1.71739 2.63363 + vertex 0.992101 1.7215 2.63224 + vertex 0.987933 1.72207 2.6334 + endloop + endfacet + facet normal 0.29472 0.0510009 0.954222 + outer loop + vertex 0.992326 1.71678 2.63242 + vertex 0.992101 1.7215 2.63224 + vertex 0.988302 1.71739 2.63363 + endloop + endfacet + facet normal 0.297404 0.0733351 0.951931 + outer loop + vertex 0.989156 1.71362 2.63365 + vertex 0.992326 1.71678 2.63242 + vertex 0.988302 1.71739 2.63363 + endloop + endfacet + facet normal 0.318961 0.0496062 0.946469 + outer loop + vertex 0.992397 1.71212 2.63264 + vertex 0.992326 1.71678 2.63242 + vertex 0.989156 1.71362 2.63365 + endloop + endfacet + facet normal 0.319464 0.0508588 0.946233 + outer loop + vertex 0.988131 1.70906 2.63425 + vertex 0.992397 1.71212 2.63264 + vertex 0.989156 1.71362 2.63365 + endloop + endfacet + facet normal 0.32343 0.0447915 0.945191 + outer loop + vertex 0.992598 1.70713 2.63281 + vertex 0.992397 1.71212 2.63264 + vertex 0.988131 1.70906 2.63425 + endloop + endfacet + facet normal 0.333374 0.0716589 0.940067 + outer loop + vertex 0.989058 1.70378 2.63432 + vertex 0.992598 1.70713 2.63281 + vertex 0.988131 1.70906 2.63425 + endloop + endfacet + facet normal 0.24782 0.0607377 0.9669 + outer loop + vertex 0.987875 1.72701 2.63311 + vertex 0.992013 1.73158 2.63176 + vertex 0.987874 1.73209 2.63279 + endloop + endfacet + facet normal 0.246638 0.0493234 0.967852 + outer loop + vertex 0.992013 1.73158 2.63176 + vertex 0.991812 1.73667 2.63155 + vertex 0.987874 1.73209 2.63279 + endloop + endfacet + facet normal 0.232555 0.0621702 0.970594 + outer loop + vertex 0.987874 1.73209 2.63279 + vertex 0.991812 1.73667 2.63155 + vertex 0.987672 1.73708 2.63252 + endloop + endfacet + facet normal 0.231722 0.0518834 0.971398 + outer loop + vertex 0.991812 1.73667 2.63155 + vertex 0.991171 1.74199 2.63142 + vertex 0.987672 1.73708 2.63252 + endloop + endfacet + facet normal 0.211557 0.0670717 0.975062 + outer loop + vertex 0.987672 1.73708 2.63252 + vertex 0.991171 1.74199 2.63142 + vertex 0.987014 1.74113 2.63238 + endloop + endfacet + facet normal 0.21393 0.0558032 0.975254 + outer loop + vertex 0.988292 1.74612 2.63182 + vertex 0.987014 1.74113 2.63238 + vertex 0.991171 1.74199 2.63142 + endloop + endfacet + facet normal 0.229194 0.0668586 0.971082 + outer loop + vertex 0.992312 1.7465 2.63084 + vertex 0.988292 1.74612 2.63182 + vertex 0.991171 1.74199 2.63142 + endloop + endfacet + facet normal 0.308602 0.0440427 0.950171 + outer loop + vertex 0.992312 1.7465 2.63084 + vertex 0.991171 1.74199 2.63142 + vertex 0.994506 1.74446 2.63022 + endloop + endfacet + facet normal 0.330118 0.0698488 0.941352 + outer loop + vertex 0.994506 1.74446 2.63022 + vertex 0.995413 1.74859 2.6296 + vertex 0.992312 1.7465 2.63084 + endloop + endfacet + facet normal 0.334155 0.0632852 0.940391 + outer loop + vertex 0.992312 1.7465 2.63084 + vertex 0.995413 1.74859 2.6296 + vertex 0.991712 1.75051 2.63079 + endloop + endfacet + facet normal 0.323072 0.0388268 0.945578 + outer loop + vertex 0.995413 1.74859 2.6296 + vertex 0.994874 1.75367 2.62958 + vertex 0.991712 1.75051 2.63079 + endloop + endfacet + facet normal 0.231094 0.0483445 0.971729 + outer loop + vertex 0.991712 1.75051 2.63079 + vertex 0.988292 1.74612 2.63182 + vertex 0.992312 1.7465 2.63084 + endloop + endfacet + facet normal 0.227421 0.0513697 0.972441 + outer loop + vertex 0.987756 1.75166 2.63165 + vertex 0.988292 1.74612 2.63182 + vertex 0.991712 1.75051 2.63079 + endloop + endfacet + facet normal 0.221958 0.0309305 0.974565 + outer loop + vertex 0.991329 1.7555 2.63071 + vertex 0.987756 1.75166 2.63165 + vertex 0.991712 1.75051 2.63079 + endloop + endfacet + facet normal 0.323527 0.0383196 0.945443 + outer loop + vertex 0.991712 1.75051 2.63079 + vertex 0.994874 1.75367 2.62958 + vertex 0.991329 1.7555 2.63071 + endloop + endfacet + facet normal 0.398435 0.0353583 0.916515 + outer loop + vertex 0.999204 1.72905 2.62902 + vertex 0.999077 1.73402 2.62888 + vertex 0.995734 1.73053 2.63047 + endloop + endfacet + facet normal 0.429172 0.0358138 0.902512 + outer loop + vertex 0.999289 1.72402 2.62918 + vertex 1.00258 1.72734 2.62748 + vertex 0.999204 1.72905 2.62902 + endloop + endfacet + facet normal 0.348769 0.0486653 0.935944 + outer loop + vertex 0.992028 1.72649 2.63201 + vertex 0.992101 1.7215 2.63224 + vertex 0.995783 1.72548 2.63066 + endloop + endfacet + facet normal 0.403888 0.039722 0.913946 + outer loop + vertex 0.999383 1.71897 2.62936 + vertex 0.999289 1.72402 2.62918 + vertex 0.99586 1.72046 2.63085 + endloop + endfacet + facet normal 0.428259 0.0416089 0.902697 + outer loop + vertex 0.999525 1.71392 2.62952 + vertex 1.00281 1.71727 2.62781 + vertex 0.999383 1.71897 2.62936 + endloop + endfacet + facet normal 0.369736 0.0494914 0.927818 + outer loop + vertex 0.992326 1.71678 2.63242 + vertex 0.992397 1.71212 2.63264 + vertex 0.995965 1.71552 2.63104 + endloop + endfacet + facet normal 0.408729 0.0398666 0.911785 + outer loop + vertex 0.999841 1.70881 2.6296 + vertex 0.999525 1.71392 2.62952 + vertex 0.996149 1.71054 2.63118 + endloop + endfacet + facet normal 0.432591 0.0377197 0.900801 + outer loop + vertex 1.00055 1.70328 2.6295 + vertex 1.00336 1.70726 2.62798 + vertex 0.999841 1.70881 2.6296 + endloop + endfacet + facet normal 0.438333 0.0326807 0.898218 + outer loop + vertex 1.00412 1.70304 2.62776 + vertex 1.00336 1.70726 2.62798 + vertex 1.00055 1.70328 2.6295 + endloop + endfacet + facet normal 0.438303 0.0318993 0.898261 + outer loop + vertex 1.00055 1.70328 2.6295 + vertex 1.00338 1.698 2.6283 + vertex 1.00412 1.70304 2.62776 + endloop + endfacet + facet normal 0.438425 0.0319785 0.898199 + outer loop + vertex 0.999408 1.69888 2.63021 + vertex 1.00338 1.698 2.6283 + vertex 1.00055 1.70328 2.6295 + endloop + endfacet + facet normal 0.398719 0.0383861 0.916269 + outer loop + vertex 0.996585 1.70548 2.63122 + vertex 0.993294 1.70152 2.63282 + vertex 0.997166 1.70125 2.63114 + endloop + endfacet + facet normal 0.403028 0.0491104 0.913869 + outer loop + vertex 0.993265 1.69289 2.63328 + vertex 0.99601 1.69687 2.63186 + vertex 0.992325 1.69687 2.63348 + endloop + endfacet + facet normal 0.410913 0.0425294 0.910682 + outer loop + vertex 0.996756 1.69177 2.63176 + vertex 0.99601 1.69687 2.63186 + vertex 0.993265 1.69289 2.63328 + endloop + endfacet + facet normal 0.412786 0.0500473 0.909452 + outer loop + vertex 0.994178 1.68898 2.63308 + vertex 0.996756 1.69177 2.63176 + vertex 0.993265 1.69289 2.63328 + endloop + endfacet + facet normal 0.418737 0.0472057 0.90688 + outer loop + vertex 0.993231 1.68449 2.63375 + vertex 0.996993 1.68715 2.63188 + vertex 0.994178 1.68898 2.63308 + endloop + endfacet + facet normal 0.322718 0.0382352 0.945722 + outer loop + vertex 0.99018 1.68059 2.63527 + vertex 0.989629 1.68463 2.6353 + vertex 0.986253 1.68213 2.63655 + endloop + endfacet + facet normal 0.421597 0.0485992 0.90548 + outer loop + vertex 0.993771 1.67911 2.63379 + vertex 0.997061 1.68231 2.63209 + vertex 0.993231 1.68449 2.63375 + endloop + endfacet + facet normal 0.327967 0.0537721 0.943157 + outer loop + vertex 0.986253 1.68213 2.63655 + vertex 0.986897 1.67686 2.63663 + vertex 0.99018 1.68059 2.63527 + endloop + endfacet + facet normal 0.402191 0.0416481 0.914608 + outer loop + vertex 0.994056 1.67415 2.63389 + vertex 0.993771 1.67911 2.63379 + vertex 0.990605 1.6757 2.63534 + endloop + endfacet + facet normal 0.4279 0.0375598 0.903045 + outer loop + vertex 0.994225 1.66922 2.63401 + vertex 0.997432 1.6724 2.63236 + vertex 0.994056 1.67415 2.63389 + endloop + endfacet + facet normal 0.401694 0.0340034 0.915142 + outer loop + vertex 0.994351 1.66422 2.63415 + vertex 0.994225 1.66922 2.63401 + vertex 0.99086 1.66572 2.63562 + endloop + endfacet + facet normal 0.344471 0.0351816 0.938138 + outer loop + vertex 0.987117 1.67182 2.63677 + vertex 0.987101 1.66672 2.63697 + vertex 0.990795 1.67075 2.63546 + endloop + endfacet + facet normal 0.349497 0.0322275 0.936383 + outer loop + vertex 0.99086 1.66572 2.63562 + vertex 0.987056 1.66159 2.63718 + vertex 0.990898 1.66061 2.63578 + endloop + endfacet + facet normal 0.350746 0.0381295 0.935694 + outer loop + vertex 0.987056 1.66159 2.63718 + vertex 0.9871 1.65652 2.63737 + vertex 0.990898 1.66061 2.63578 + endloop + endfacet + facet normal 0.358043 0.0401599 0.932841 + outer loop + vertex 0.9871 1.65652 2.63737 + vertex 0.987256 1.65161 2.63753 + vertex 0.990964 1.6555 2.63593 + endloop + endfacet + facet normal 0.37482 0.0379603 0.92632 + outer loop + vertex 0.9875 1.64695 2.63763 + vertex 0.987597 1.64232 2.63778 + vertex 0.991162 1.64556 2.63621 + endloop + endfacet + facet normal 0.382339 0.0359754 0.923322 + outer loop + vertex 0.987597 1.64232 2.63778 + vertex 0.987846 1.63729 2.63788 + vertex 0.991356 1.64059 2.6363 + endloop + endfacet + facet normal 0.390181 0.0352158 0.920065 + outer loop + vertex 0.987846 1.63729 2.63788 + vertex 0.988501 1.63162 2.63782 + vertex 0.991776 1.63553 2.63628 + endloop + endfacet + facet normal 0.396538 0.0306921 0.917505 + outer loop + vertex 0.988501 1.63162 2.63782 + vertex 0.987376 1.62695 2.63846 + vertex 0.991024 1.62699 2.63688 + endloop + endfacet + facet normal 0.396567 0.0292408 0.91754 + outer loop + vertex 0.987985 1.62285 2.63833 + vertex 0.991024 1.62699 2.63688 + vertex 0.987376 1.62695 2.63846 + endloop + endfacet + facet normal 0.398718 0.0273563 0.916665 + outer loop + vertex 0.991581 1.62168 2.6368 + vertex 0.991024 1.62699 2.63688 + vertex 0.987985 1.62285 2.63833 + endloop + endfacet + facet normal 0.399263 0.029431 0.916364 + outer loop + vertex 0.98835 1.61795 2.63832 + vertex 0.991581 1.62168 2.6368 + vertex 0.987985 1.62285 2.63833 + endloop + endfacet + facet normal 0.400638 0.0305503 0.915727 + outer loop + vertex 0.988708 1.61307 2.63833 + vertex 0.991904 1.61672 2.63681 + vertex 0.98835 1.61795 2.63832 + endloop + endfacet + facet normal 0.403962 0.030301 0.914274 + outer loop + vertex 0.989294 1.60905 2.63821 + vertex 0.992104 1.61195 2.63687 + vertex 0.988708 1.61307 2.63833 + endloop + endfacet + facet normal 0.407345 0.0251235 0.912929 + outer loop + vertex 0.98817 1.60452 2.63883 + vertex 0.992037 1.60726 2.63703 + vertex 0.989294 1.60905 2.63821 + endloop + endfacet + facet normal 0.309628 0.0159612 0.950724 + outer loop + vertex 0.985039 1.60058 2.64023 + vertex 0.984557 1.6046 2.64032 + vertex 0.981148 1.6021 2.64147 + endloop + endfacet + facet normal 0.408764 0.0262203 0.912263 + outer loop + vertex 0.988633 1.59914 2.63878 + vertex 0.991976 1.60237 2.63719 + vertex 0.98817 1.60452 2.63883 + endloop + endfacet + facet normal 0.411591 0.0233663 0.911069 + outer loop + vertex 0.988877 1.59419 2.6388 + vertex 0.992154 1.5974 2.63723 + vertex 0.988633 1.59914 2.63878 + endloop + endfacet + facet normal 0.325497 0.0231372 0.94526 + outer loop + vertex 0.981751 1.59689 2.64145 + vertex 0.981977 1.59193 2.64149 + vertex 0.985416 1.59571 2.64021 + endloop + endfacet + facet normal 0.387736 0.0202931 0.921547 + outer loop + vertex 0.988984 1.58927 2.63886 + vertex 0.988877 1.59419 2.6388 + vertex 0.985571 1.5908 2.64026 + endloop + endfacet + facet normal 0.409858 0.0194621 0.911942 + outer loop + vertex 0.989044 1.5843 2.63894 + vertex 0.992385 1.58752 2.63737 + vertex 0.988984 1.58927 2.63886 + endloop + endfacet + facet normal 0.408213 0.0175474 0.912718 + outer loop + vertex 0.989111 1.5793 2.639 + vertex 0.992463 1.58254 2.63744 + vertex 0.989044 1.5843 2.63894 + endloop + endfacet + facet normal 0.406498 0.0167091 0.913499 + outer loop + vertex 0.98919 1.5743 2.63906 + vertex 0.992547 1.57754 2.63751 + vertex 0.989111 1.5793 2.639 + endloop + endfacet + facet normal 0.405738 0.0167671 0.913836 + outer loop + vertex 0.989273 1.56932 2.63911 + vertex 0.992634 1.57255 2.63756 + vertex 0.98919 1.5743 2.63906 + endloop + endfacet + facet normal 0.405131 0.0176173 0.914089 + outer loop + vertex 0.989356 1.56433 2.63917 + vertex 0.99272 1.56756 2.63762 + vertex 0.989273 1.56932 2.63911 + endloop + endfacet + facet normal 0.404108 0.0187218 0.914519 + outer loop + vertex 0.989442 1.55935 2.63924 + vertex 0.992809 1.56258 2.63768 + vertex 0.989356 1.56433 2.63917 + endloop + endfacet + facet normal 0.404108 0.018722 0.91452 + outer loop + vertex 0.9929 1.55759 2.63775 + vertex 0.992809 1.56258 2.63768 + vertex 0.989442 1.55935 2.63924 + endloop + endfacet + facet normal 0.403759 0.0178908 0.91469 + outer loop + vertex 0.989528 1.55437 2.6393 + vertex 0.9929 1.55759 2.63775 + vertex 0.989442 1.55935 2.63924 + endloop + endfacet + facet normal 0.404498 0.0147349 0.91442 + outer loop + vertex 0.989605 1.54938 2.63934 + vertex 0.992984 1.5526 2.6378 + vertex 0.989528 1.55437 2.6393 + endloop + endfacet + facet normal 0.403972 0.011555 0.914698 + outer loop + vertex 0.98966 1.54439 2.63938 + vertex 0.993054 1.54762 2.63784 + vertex 0.989605 1.54938 2.63934 + endloop + endfacet + facet normal 0.403609 0.0120118 0.914853 + outer loop + vertex 0.993093 1.54265 2.63789 + vertex 0.993054 1.54762 2.63784 + vertex 0.98966 1.54439 2.63938 + endloop + endfacet + facet normal 0.403286 0.0112488 0.915005 + outer loop + vertex 0.989691 1.53943 2.63943 + vertex 0.993093 1.54265 2.63789 + vertex 0.98966 1.54439 2.63938 + endloop + endfacet + facet normal 0.402962 0.0116581 0.915143 + outer loop + vertex 0.9931 1.53768 2.63795 + vertex 0.993093 1.54265 2.63789 + vertex 0.989691 1.53943 2.63943 + endloop + endfacet + facet normal 0.382166 0.0112039 0.924026 + outer loop + vertex 0.989691 1.53943 2.63943 + vertex 0.98966 1.54439 2.63938 + vertex 0.9862 1.54098 2.64085 + endloop + endfacet + facet normal 0.402407 0.0103604 0.915402 + outer loop + vertex 0.989698 1.53445 2.63948 + vertex 0.9931 1.53768 2.63795 + vertex 0.989691 1.53943 2.63943 + endloop + endfacet + facet normal 0.401793 0.010992 0.915665 + outer loop + vertex 0.989739 1.52942 2.63953 + vertex 0.993128 1.53266 2.638 + vertex 0.989698 1.53445 2.63948 + endloop + endfacet + facet normal 0.40243 0.00887885 0.915408 + outer loop + vertex 0.989862 1.52428 2.63952 + vertex 0.993301 1.5275 2.63798 + vertex 0.989739 1.52942 2.63953 + endloop + endfacet + facet normal 0.405144 0.00672116 0.914228 + outer loop + vertex 0.989858 1.5192 2.63956 + vertex 0.993894 1.52187 2.63775 + vertex 0.989862 1.52428 2.63952 + endloop + endfacet + facet normal 0.403767 0.00443752 0.914851 + outer loop + vertex 0.989952 1.51428 2.63954 + vertex 0.992987 1.51708 2.63819 + vertex 0.989858 1.5192 2.63956 + endloop + endfacet + facet normal 0.4063 0.00197178 0.913738 + outer loop + vertex 0.989924 1.50933 2.63957 + vertex 0.994256 1.51234 2.63763 + vertex 0.989952 1.51428 2.63954 + endloop + endfacet + facet normal 0.402946 -0.000298439 0.915224 + outer loop + vertex 0.989758 1.50448 2.63964 + vertex 0.992687 1.50744 2.63835 + vertex 0.989924 1.50933 2.63957 + endloop + endfacet + facet normal 0.404612 -0.00228301 0.914486 + outer loop + vertex 0.989863 1.49965 2.63958 + vertex 0.993129 1.50334 2.63814 + vertex 0.989758 1.50448 2.63964 + endloop + endfacet + facet normal 0.404185 -0.00217649 0.914675 + outer loop + vertex 0.989993 1.49467 2.63951 + vertex 0.99341 1.49854 2.63801 + vertex 0.989863 1.49965 2.63958 + endloop + endfacet + facet normal 0.404704 -0.00130357 0.914447 + outer loop + vertex 0.98996 1.48954 2.63952 + vertex 0.993974 1.4934 2.63775 + vertex 0.989993 1.49467 2.63951 + endloop + endfacet + facet normal 0.404025 -0.000458647 0.914748 + outer loop + vertex 0.993392 1.48778 2.638 + vertex 0.993974 1.4934 2.63775 + vertex 0.98996 1.48954 2.63952 + endloop + endfacet + facet normal 0.404312 0.000210436 0.914621 + outer loop + vertex 0.989823 1.48443 2.63958 + vertex 0.993392 1.48778 2.638 + vertex 0.98996 1.48954 2.63952 + endloop + endfacet + facet normal 0.403541 0.00119069 0.914961 + outer loop + vertex 0.993237 1.4827 2.63808 + vertex 0.993392 1.48778 2.638 + vertex 0.989823 1.48443 2.63958 + endloop + endfacet + facet normal 0.379894 0.000993501 0.92503 + outer loop + vertex 0.989823 1.48443 2.63958 + vertex 0.98996 1.48954 2.63952 + vertex 0.986307 1.48597 2.64102 + endloop + endfacet + facet normal 0.404021 0.0023213 0.914747 + outer loop + vertex 0.989804 1.47943 2.6396 + vertex 0.993237 1.4827 2.63808 + vertex 0.989823 1.48443 2.63958 + endloop + endfacet + facet normal 0.404306 0.00196364 0.914622 + outer loop + vertex 0.99324 1.4777 2.63808 + vertex 0.993237 1.4827 2.63808 + vertex 0.989804 1.47943 2.6396 + endloop + endfacet + facet normal 0.404069 0.00140026 0.914727 + outer loop + vertex 0.989842 1.47446 2.63959 + vertex 0.99324 1.4777 2.63808 + vertex 0.989804 1.47943 2.6396 + endloop + endfacet + facet normal 0.40577 -0.000732228 0.913975 + outer loop + vertex 0.993272 1.47272 2.63807 + vertex 0.99324 1.4777 2.63808 + vertex 0.989842 1.47446 2.63959 + endloop + endfacet + facet normal 0.404787 -0.00305021 0.914406 + outer loop + vertex 0.98986 1.46948 2.63957 + vertex 0.993272 1.47272 2.63807 + vertex 0.989842 1.47446 2.63959 + endloop + endfacet + facet normal 0.378987 -0.00812509 0.925366 + outer loop + vertex 0.989837 1.46449 2.63953 + vertex 0.98986 1.46948 2.63957 + vertex 0.986333 1.46604 2.64098 + endloop + endfacet + facet normal 0.325452 -0.00944684 0.945511 + outer loop + vertex 0.986333 1.46604 2.64098 + vertex 0.982522 1.46216 2.64225 + vertex 0.986299 1.46104 2.64094 + endloop + endfacet + facet normal 0.326494 -0.00513974 0.945185 + outer loop + vertex 0.982552 1.47217 2.64232 + vertex 0.982551 1.46717 2.6423 + vertex 0.98634 1.47103 2.64101 + endloop + endfacet + facet normal 0.32647 -0.00168587 0.945206 + outer loop + vertex 0.982531 1.47715 2.64234 + vertex 0.982552 1.47217 2.64232 + vertex 0.986321 1.47602 2.64103 + endloop + endfacet + facet normal 0.329617 -0.00156414 0.944113 + outer loop + vertex 0.98252 1.48213 2.64235 + vertex 0.982531 1.47715 2.64234 + vertex 0.986292 1.48099 2.64103 + endloop + endfacet + facet normal 0.336151 -0.0038289 0.9418 + outer loop + vertex 0.982565 1.49206 2.64236 + vertex 0.98253 1.48709 2.64236 + vertex 0.986353 1.49097 2.64101 + endloop + endfacet + facet normal 0.33684 -0.00373294 0.941555 + outer loop + vertex 0.982597 1.49705 2.64237 + vertex 0.982565 1.49206 2.64236 + vertex 0.986373 1.49597 2.64102 + endloop + endfacet + facet normal 0.336573 -0.00294351 0.941653 + outer loop + vertex 0.982617 1.50208 2.64238 + vertex 0.982597 1.49705 2.64237 + vertex 0.986363 1.50095 2.64104 + endloop + endfacet + facet normal 0.336217 -0.00107377 0.941784 + outer loop + vertex 0.982622 1.50714 2.64239 + vertex 0.982617 1.50208 2.64238 + vertex 0.986378 1.50596 2.64104 + endloop + endfacet + facet normal 0.334711 0.00325152 0.942315 + outer loop + vertex 0.982592 1.51218 2.64238 + vertex 0.982622 1.50714 2.64239 + vertex 0.986387 1.51099 2.64103 + endloop + endfacet + facet normal 0.333017 0.00527342 0.942906 + outer loop + vertex 0.982558 1.51718 2.64236 + vertex 0.982592 1.51218 2.64238 + vertex 0.986341 1.51601 2.64103 + endloop + endfacet + facet normal 0.33108 0.00811789 0.943568 + outer loop + vertex 0.982527 1.52215 2.64233 + vertex 0.982558 1.51718 2.64236 + vertex 0.986299 1.52101 2.64102 + endloop + endfacet + facet normal 0.330776 0.00895253 0.943667 + outer loop + vertex 0.982502 1.52711 2.64229 + vertex 0.982527 1.52215 2.64233 + vertex 0.986268 1.52602 2.64098 + endloop + endfacet + facet normal 0.332167 0.00830768 0.943184 + outer loop + vertex 0.982486 1.53208 2.64225 + vertex 0.982502 1.52711 2.64229 + vertex 0.986238 1.53102 2.64094 + endloop + endfacet + facet normal 0.333796 0.0084667 0.942607 + outer loop + vertex 0.982466 1.53706 2.64222 + vertex 0.982486 1.53208 2.64225 + vertex 0.986223 1.536 2.6409 + endloop + endfacet + facet normal 0.335846 0.00916108 0.941872 + outer loop + vertex 0.982408 1.54708 2.64214 + vertex 0.982439 1.54206 2.64218 + vertex 0.986154 1.54596 2.64082 + endloop + endfacet + facet normal 0.335266 0.0129402 0.942035 + outer loop + vertex 0.98236 1.55209 2.64209 + vertex 0.982408 1.54708 2.64214 + vertex 0.986093 1.55096 2.64078 + endloop + endfacet + facet normal 0.33519 0.0156838 0.94202 + outer loop + vertex 0.982307 1.55709 2.64203 + vertex 0.98236 1.55209 2.64209 + vertex 0.98602 1.55595 2.64072 + endloop + endfacet + facet normal 0.335239 0.0174889 0.941971 + outer loop + vertex 0.98225 1.56208 2.64195 + vertex 0.982307 1.55709 2.64203 + vertex 0.985943 1.56093 2.64066 + endloop + endfacet + facet normal 0.336732 0.0167746 0.941451 + outer loop + vertex 0.982194 1.56706 2.64189 + vertex 0.98225 1.56208 2.64195 + vertex 0.985863 1.5659 2.64059 + endloop + endfacet + facet normal 0.335551 0.0174312 0.941861 + outer loop + vertex 0.982125 1.57202 2.64182 + vertex 0.982194 1.56706 2.64189 + vertex 0.985787 1.57088 2.64053 + endloop + endfacet + facet normal 0.33454 0.0154844 0.942254 + outer loop + vertex 0.982069 1.57701 2.64176 + vertex 0.982125 1.57202 2.64182 + vertex 0.985713 1.57587 2.64048 + endloop + endfacet + facet normal 0.333301 0.0174189 0.94266 + outer loop + vertex 0.982032 1.58199 2.64168 + vertex 0.982069 1.57701 2.64176 + vertex 0.98565 1.58086 2.64042 + endloop + endfacet + facet normal 0.332142 0.0180009 0.943058 + outer loop + vertex 0.982029 1.58697 2.64158 + vertex 0.982032 1.58199 2.64168 + vertex 0.985614 1.58585 2.64034 + endloop + endfacet + facet normal 0.31499 0.0314256 0.948575 + outer loop + vertex 0.981148 1.6021 2.64147 + vertex 0.981751 1.59689 2.64145 + vertex 0.985039 1.60058 2.64023 + endloop + endfacet + facet normal 0.322542 0.0285486 0.946124 + outer loop + vertex 0.985719 1.60895 2.63971 + vertex 0.98513 1.61428 2.63975 + vertex 0.981846 1.61068 2.64097 + endloop + endfacet + facet normal 0.219824 0.0359093 0.974878 + outer loop + vertex 0.977498 1.61688 2.64176 + vertex 0.977755 1.61173 2.64189 + vertex 0.981422 1.61573 2.64092 + endloop + endfacet + facet normal 0.305629 0.0268506 0.951772 + outer loop + vertex 0.984796 1.61933 2.6397 + vertex 0.984562 1.62418 2.63964 + vertex 0.981214 1.62077 2.64081 + endloop + endfacet + facet normal 0.20307 0.0394122 0.978371 + outer loop + vertex 0.977375 1.62694 2.6414 + vertex 0.977425 1.62192 2.64159 + vertex 0.981131 1.62575 2.64066 + endloop + endfacet + facet normal 0.172804 0.055834 0.983372 + outer loop + vertex 0.975992 1.63729 2.64111 + vertex 0.977058 1.63198 2.64123 + vertex 0.980341 1.6357 2.64044 + endloop + endfacet + facet normal 0.29426 0.0394536 0.954911 + outer loop + vertex 0.984558 1.62897 2.63948 + vertex 0.984343 1.63406 2.63933 + vertex 0.980957 1.63072 2.64051 + endloop + endfacet + facet normal 0.164482 0.0319412 0.985863 + outer loop + vertex 0.980341 1.6357 2.64044 + vertex 0.979309 1.6398 2.64048 + vertex 0.975992 1.63729 2.64111 + endloop + endfacet + facet normal 0.0475506 0.0721187 0.996262 + outer loop + vertex 0.963295 1.67228 2.63971 + vertex 0.968347 1.67718 2.63912 + vertex 0.963177 1.67704 2.63938 + endloop + endfacet + facet normal 0.0635999 0.0673522 0.9957 + outer loop + vertex 0.973405 1.67217 2.63915 + vertex 0.973502 1.67726 2.6388 + vertex 0.968283 1.67217 2.63948 + endloop + endfacet + facet normal 0.0578118 0.0731335 0.995645 + outer loop + vertex 0.968347 1.67718 2.63912 + vertex 0.973612 1.68241 2.63843 + vertex 0.968482 1.68229 2.63874 + endloop + endfacet + facet normal 0.0910801 0.0656815 0.993675 + outer loop + vertex 0.978334 1.67722 2.63836 + vertex 0.978457 1.68217 2.63802 + vertex 0.973502 1.67726 2.6388 + endloop + endfacet + facet normal 0.0848365 0.0717982 0.993805 + outer loop + vertex 0.973612 1.68241 2.63843 + vertex 0.978534 1.68733 2.63765 + vertex 0.973689 1.68757 2.63805 + endloop + endfacet + facet normal 0.140563 0.0811023 0.986744 + outer loop + vertex 0.982101 1.68125 2.63758 + vertex 0.983352 1.68623 2.63699 + vertex 0.978457 1.68217 2.63802 + endloop + endfacet + facet normal 0.0845984 0.0663334 0.994205 + outer loop + vertex 0.978534 1.68733 2.63765 + vertex 0.978354 1.69249 2.63732 + vertex 0.973689 1.68757 2.63805 + endloop + endfacet + facet normal 0.057834 0.0723424 0.995702 + outer loop + vertex 0.973612 1.68241 2.63843 + vertex 0.973689 1.68757 2.63805 + vertex 0.968482 1.68229 2.63874 + endloop + endfacet + facet normal 0.0475121 0.0734443 0.996167 + outer loop + vertex 0.968347 1.67718 2.63912 + vertex 0.968482 1.68229 2.63874 + vertex 0.963177 1.67704 2.63938 + endloop + endfacet + facet normal 0.0431803 0.0720252 0.996468 + outer loop + vertex 0.963295 1.67228 2.63971 + vertex 0.963177 1.67704 2.63938 + vertex 0.958386 1.67229 2.63993 + endloop + endfacet + facet normal 0.0431835 0.0700435 0.996609 + outer loop + vertex 0.959485 1.66854 2.64014 + vertex 0.963295 1.67228 2.63971 + vertex 0.958386 1.67229 2.63993 + endloop + endfacet + facet normal 0.039628 0.0666359 0.99699 + outer loop + vertex 0.954375 1.66359 2.64068 + vertex 0.959289 1.66376 2.64047 + vertex 0.954614 1.66766 2.6404 + endloop + endfacet + facet normal 0.043298 0.0699273 0.996612 + outer loop + vertex 0.963537 1.66773 2.64002 + vertex 0.963295 1.67228 2.63971 + vertex 0.959485 1.66854 2.64014 + endloop + endfacet + facet normal 0.0492711 0.0702794 0.99631 + outer loop + vertex 0.964507 1.66388 2.64025 + vertex 0.9684 1.66738 2.63981 + vertex 0.963537 1.66773 2.64002 + endloop + endfacet + facet normal 0.0489507 0.0655113 0.99665 + outer loop + vertex 0.964417 1.65911 2.64057 + vertex 0.968678 1.66282 2.64011 + vertex 0.964507 1.66388 2.64025 + endloop + endfacet + facet normal 0.0403463 0.0620161 0.997259 + outer loop + vertex 0.959523 1.65943 2.64074 + vertex 0.96146 1.65639 2.64085 + vertex 0.964417 1.65911 2.64057 + endloop + endfacet + facet normal 0.040204 0.0619256 0.997271 + outer loop + vertex 0.96146 1.65639 2.64085 + vertex 0.959523 1.65943 2.64074 + vertex 0.95682 1.65638 2.64104 + endloop + endfacet + facet normal 0.0396988 0.0647392 0.997112 + outer loop + vertex 0.954375 1.66359 2.64068 + vertex 0.956335 1.6609 2.64078 + vertex 0.959289 1.66376 2.64047 + endloop + endfacet + facet normal 0.0370892 0.066791 0.997077 + outer loop + vertex 0.950355 1.66479 2.64075 + vertex 0.954375 1.66359 2.64068 + vertex 0.954614 1.66766 2.6404 + endloop + endfacet + facet normal 0.0402111 0.0643715 0.997116 + outer loop + vertex 0.952175 1.66036 2.64097 + vertex 0.951949 1.65607 2.64126 + vertex 0.95682 1.65638 2.64104 + endloop + endfacet + facet normal 0.0372911 0.062574 0.997343 + outer loop + vertex 0.953049 1.65225 2.64146 + vertex 0.951949 1.65607 2.64126 + vertex 0.94849 1.65249 2.64161 + endloop + endfacet + facet normal 0.0322305 0.0613995 0.997593 + outer loop + vertex 0.94877 1.64766 2.6419 + vertex 0.94849 1.65249 2.64161 + vertex 0.943846 1.64763 2.64206 + endloop + endfacet + facet normal 0.0322445 0.0596755 0.997697 + outer loop + vertex 0.943741 1.6425 2.64237 + vertex 0.94877 1.64766 2.6419 + vertex 0.943846 1.64763 2.64206 + endloop + endfacet + facet normal 0.0238882 0.0566044 0.998111 + outer loop + vertex 0.943581 1.63737 2.64267 + vertex 0.943741 1.6425 2.64237 + vertex 0.938518 1.63732 2.64279 + endloop + endfacet + facet normal 0.0332713 0.0531245 0.998033 + outer loop + vertex 0.943455 1.6323 2.64294 + vertex 0.948668 1.63748 2.64249 + vertex 0.943581 1.63737 2.64267 + endloop + endfacet + facet normal 0.0243449 0.0502969 0.998438 + outer loop + vertex 0.943392 1.62729 2.64319 + vertex 0.943455 1.6323 2.64294 + vertex 0.93843 1.62732 2.64331 + endloop + endfacet + facet normal 0.0111318 0.0476715 0.998801 + outer loop + vertex 0.938454 1.62236 2.64355 + vertex 0.93843 1.62732 2.64331 + vertex 0.933504 1.62242 2.6436 + endloop + endfacet + facet normal 0.00896914 0.0513309 0.998641 + outer loop + vertex 0.933458 1.62737 2.64336 + vertex 0.938442 1.63229 2.64306 + vertex 0.933424 1.63231 2.64311 + endloop + endfacet + facet normal -0.045771 0.0542721 0.997477 + outer loop + vertex 0.923311 1.63224 2.6428 + vertex 0.928356 1.63722 2.64277 + vertex 0.923351 1.63716 2.64254 + endloop + endfacet + facet normal -0.0458267 0.0604903 0.997116 + outer loop + vertex 0.928356 1.63722 2.64277 + vertex 0.928453 1.64223 2.64247 + vertex 0.923351 1.63716 2.64254 + endloop + endfacet + facet normal -0.0149108 0.0545254 0.998401 + outer loop + vertex 0.933424 1.63231 2.64311 + vertex 0.933448 1.63728 2.64283 + vertex 0.928358 1.63229 2.64303 + endloop + endfacet + facet normal 0.0076395 0.0581763 0.998277 + outer loop + vertex 0.933448 1.63728 2.64283 + vertex 0.938669 1.64241 2.6425 + vertex 0.93357 1.64233 2.64254 + endloop + endfacet + facet normal 0.00644688 0.0619451 0.998059 + outer loop + vertex 0.93357 1.64233 2.64254 + vertex 0.93883 1.64757 2.64218 + vertex 0.933731 1.64747 2.64222 + endloop + endfacet + facet normal -0.0210055 0.0677345 0.997482 + outer loop + vertex 0.928595 1.64734 2.64214 + vertex 0.933732 1.6526 2.64189 + vertex 0.928642 1.65247 2.64179 + endloop + endfacet + facet normal -0.0209198 0.0642594 0.997714 + outer loop + vertex 0.933732 1.6526 2.64189 + vertex 0.93335 1.65742 2.64157 + vertex 0.928642 1.65247 2.64179 + endloop + endfacet + facet normal -0.0231692 0.0663906 0.997525 + outer loop + vertex 0.928642 1.65247 2.64179 + vertex 0.93335 1.65742 2.64157 + vertex 0.928437 1.65745 2.64145 + endloop + endfacet + facet normal -0.0509009 0.0651867 0.996574 + outer loop + vertex 0.928642 1.65247 2.64179 + vertex 0.928437 1.65745 2.64145 + vertex 0.923644 1.65236 2.64154 + endloop + endfacet + facet normal -0.0509575 0.068156 0.996372 + outer loop + vertex 0.923522 1.6472 2.64189 + vertex 0.928642 1.65247 2.64179 + vertex 0.923644 1.65236 2.64154 + endloop + endfacet + facet normal -0.0507258 0.0679316 0.9964 + outer loop + vertex 0.928595 1.64734 2.64214 + vertex 0.928642 1.65247 2.64179 + vertex 0.923522 1.6472 2.64189 + endloop + endfacet + facet normal -0.0507632 0.0694294 0.996294 + outer loop + vertex 0.923437 1.64212 2.64224 + vertex 0.928595 1.64734 2.64214 + vertex 0.923522 1.6472 2.64189 + endloop + endfacet + facet normal -0.0468576 0.0655752 0.996747 + outer loop + vertex 0.928453 1.64223 2.64247 + vertex 0.928595 1.64734 2.64214 + vertex 0.923437 1.64212 2.64224 + endloop + endfacet + facet normal -0.0467832 0.0614518 0.997013 + outer loop + vertex 0.923351 1.63716 2.64254 + vertex 0.928453 1.64223 2.64247 + vertex 0.923437 1.64212 2.64224 + endloop + endfacet + facet normal -0.0486664 0.0630858 0.996821 + outer loop + vertex 0.923644 1.65236 2.64154 + vertex 0.928437 1.65745 2.64145 + vertex 0.923379 1.65748 2.6412 + endloop + endfacet + facet normal -0.0487109 0.0585518 0.997095 + outer loop + vertex 0.928437 1.65745 2.64145 + vertex 0.928105 1.66206 2.64117 + vertex 0.923379 1.65748 2.6412 + endloop + endfacet + facet normal -0.0402086 0.049788 0.99795 + outer loop + vertex 0.923379 1.65748 2.6412 + vertex 0.928105 1.66206 2.64117 + vertex 0.92427 1.66244 2.64099 + endloop + endfacet + facet normal -0.0398032 0.0538211 0.997757 + outer loop + vertex 0.92427 1.66244 2.64099 + vertex 0.928105 1.66206 2.64117 + vertex 0.927579 1.66581 2.64094 + endloop + endfacet + facet normal -0.0381319 0.0521849 0.997909 + outer loop + vertex 0.924513 1.66558 2.64084 + vertex 0.92427 1.66244 2.64099 + vertex 0.927579 1.66581 2.64094 + endloop + endfacet + facet normal -0.0388748 0.0619862 0.99732 + outer loop + vertex 0.924513 1.66558 2.64084 + vertex 0.927579 1.66581 2.64094 + vertex 0.926604 1.66823 2.64075 + endloop + endfacet + facet normal -0.0833616 0.096912 0.991796 + outer loop + vertex 0.926604 1.66823 2.64075 + vertex 0.92282 1.66728 2.64053 + vertex 0.924513 1.66558 2.64084 + endloop + endfacet + facet normal -0.0838784 0.0990317 0.991543 + outer loop + vertex 0.926604 1.66823 2.64075 + vertex 0.928292 1.67227 2.64049 + vertex 0.92282 1.66728 2.64053 + endloop + endfacet + facet normal -0.0628714 0.0760229 0.995122 + outer loop + vertex 0.92282 1.66728 2.64053 + vertex 0.928292 1.67227 2.64049 + vertex 0.923123 1.67224 2.64017 + endloop + endfacet + facet normal -0.0628679 0.0729791 0.99535 + outer loop + vertex 0.928292 1.67227 2.64049 + vertex 0.928286 1.67736 2.64012 + vertex 0.923123 1.67224 2.64017 + endloop + endfacet + facet normal -0.0676883 0.0778296 0.994666 + outer loop + vertex 0.923123 1.67224 2.64017 + vertex 0.928286 1.67736 2.64012 + vertex 0.923302 1.6772 2.63979 + endloop + endfacet + facet normal -0.0677243 0.0792061 0.994555 + outer loop + vertex 0.928286 1.67736 2.64012 + vertex 0.928424 1.68231 2.63973 + vertex 0.923302 1.6772 2.63979 + endloop + endfacet + facet normal -0.0756118 0.0871074 0.993325 + outer loop + vertex 0.923302 1.6772 2.63979 + vertex 0.928424 1.68231 2.63973 + vertex 0.923395 1.68215 2.63937 + endloop + endfacet + facet normal -0.154134 0.0877901 0.984142 + outer loop + vertex 0.923302 1.6772 2.63979 + vertex 0.923395 1.68215 2.63937 + vertex 0.918316 1.67705 2.63903 + endloop + endfacet + facet normal -0.155724 0.0893987 0.983747 + outer loop + vertex 0.918316 1.67705 2.63903 + vertex 0.923395 1.68215 2.63937 + vertex 0.918388 1.68209 2.63858 + endloop + endfacet + facet normal -0.0755974 0.0865201 0.993378 + outer loop + vertex 0.928424 1.68231 2.63973 + vertex 0.928474 1.68725 2.63931 + vertex 0.923395 1.68215 2.63937 + endloop + endfacet + facet normal -0.0797174 0.0906173 0.99269 + outer loop + vertex 0.923395 1.68215 2.63937 + vertex 0.928474 1.68725 2.63931 + vertex 0.92341 1.6871 2.63891 + endloop + endfacet + facet normal -0.0258252 0.0751295 0.996839 + outer loop + vertex 0.926604 1.66823 2.64075 + vertex 0.930535 1.66936 2.64077 + vertex 0.928292 1.67227 2.64049 + endloop + endfacet + facet normal -0.0238031 0.0680855 0.997395 + outer loop + vertex 0.930535 1.66936 2.64077 + vertex 0.926604 1.66823 2.64075 + vertex 0.927579 1.66581 2.64094 + endloop + endfacet + facet normal -0.0231887 0.0635985 0.997706 + outer loop + vertex 0.93335 1.65742 2.64157 + vertex 0.932818 1.66189 2.64127 + vertex 0.928437 1.65745 2.64145 + endloop + endfacet + facet normal -0.0201929 0.0606578 0.997954 + outer loop + vertex 0.928437 1.65745 2.64145 + vertex 0.932818 1.66189 2.64127 + vertex 0.928105 1.66206 2.64117 + endloop + endfacet + facet normal -0.0201631 0.0614604 0.997906 + outer loop + vertex 0.932818 1.66189 2.64127 + vertex 0.93194 1.66594 2.641 + vertex 0.928105 1.66206 2.64117 + endloop + endfacet + facet normal -0.0158445 0.0572089 0.998236 + outer loop + vertex 0.928105 1.66206 2.64117 + vertex 0.93194 1.66594 2.641 + vertex 0.927579 1.66581 2.64094 + endloop + endfacet + facet normal -0.0159713 0.061576 0.997975 + outer loop + vertex 0.93194 1.66594 2.641 + vertex 0.930535 1.66936 2.64077 + vertex 0.927579 1.66581 2.64094 + endloop + endfacet + facet normal -0.000236008 0.0657743 0.997834 + outer loop + vertex 0.932818 1.66189 2.64127 + vertex 0.937176 1.66553 2.64103 + vertex 0.93194 1.66594 2.641 + endloop + endfacet + facet normal -0.000339574 0.0644629 0.99792 + outer loop + vertex 0.937176 1.66553 2.64103 + vertex 0.935408 1.66949 2.64078 + vertex 0.93194 1.66594 2.641 + endloop + endfacet + facet normal 0.0100738 0.0690853 0.99756 + outer loop + vertex 0.939467 1.66904 2.64077 + vertex 0.935408 1.66949 2.64078 + vertex 0.937176 1.66553 2.64103 + endloop + endfacet + facet normal -0.00275405 0.0687756 0.997628 + outer loop + vertex 0.936868 1.66127 2.64132 + vertex 0.937176 1.66553 2.64103 + vertex 0.932818 1.66189 2.64127 + endloop + endfacet + facet normal 0.0157321 0.0674384 0.997599 + outer loop + vertex 0.937176 1.66553 2.64103 + vertex 0.936868 1.66127 2.64132 + vertex 0.941532 1.66258 2.64116 + endloop + endfacet + facet normal -0.00318359 0.0659832 0.997816 + outer loop + vertex 0.93335 1.65742 2.64157 + vertex 0.936868 1.66127 2.64132 + vertex 0.932818 1.66189 2.64127 + endloop + endfacet + facet normal 0.000981448 0.0621969 0.998063 + outer loop + vertex 0.938193 1.65759 2.64155 + vertex 0.936868 1.66127 2.64132 + vertex 0.93335 1.65742 2.64157 + endloop + endfacet + facet normal 0.0064315 0.0627458 0.998009 + outer loop + vertex 0.93883 1.64757 2.64218 + vertex 0.938774 1.65271 2.64186 + vertex 0.933731 1.64747 2.64222 + endloop + endfacet + facet normal 0.000845548 0.0659959 0.99782 + outer loop + vertex 0.933732 1.6526 2.64189 + vertex 0.938193 1.65759 2.64155 + vertex 0.93335 1.65742 2.64157 + endloop + endfacet + facet normal 0.0219284 0.0633462 0.997751 + outer loop + vertex 0.943747 1.65269 2.64175 + vertex 0.943121 1.65762 2.64145 + vertex 0.938774 1.65271 2.64186 + endloop + endfacet + facet normal 0.0157229 0.0674711 0.997597 + outer loop + vertex 0.938193 1.65759 2.64155 + vertex 0.941532 1.66258 2.64116 + vertex 0.936868 1.66127 2.64132 + endloop + endfacet + facet normal 0.0305586 0.0645293 0.997448 + outer loop + vertex 0.947983 1.65712 2.64133 + vertex 0.946917 1.66164 2.64107 + vertex 0.943121 1.65762 2.64145 + endloop + endfacet + facet normal 0.0329639 0.0668547 0.997218 + outer loop + vertex 0.950355 1.66479 2.64075 + vertex 0.945535 1.66589 2.64083 + vertex 0.946917 1.66164 2.64107 + endloop + endfacet + facet normal 0.0152082 0.0666691 0.997659 + outer loop + vertex 0.941528 1.66675 2.64088 + vertex 0.937176 1.66553 2.64103 + vertex 0.941532 1.66258 2.64116 + endloop + endfacet + facet normal 0.0306546 0.0694754 0.997113 + outer loop + vertex 0.943901 1.67003 2.6406 + vertex 0.945535 1.66589 2.64083 + vertex 0.949161 1.66891 2.64051 + endloop + endfacet + facet normal 0.0155291 0.0655321 0.99773 + outer loop + vertex 0.941528 1.66675 2.64088 + vertex 0.939467 1.66904 2.64077 + vertex 0.937176 1.66553 2.64103 + endloop + endfacet + facet normal 0.0303878 0.0682186 0.997208 + outer loop + vertex 0.949161 1.66891 2.64051 + vertex 0.948496 1.67311 2.64025 + vertex 0.943901 1.67003 2.6406 + endloop + endfacet + facet normal 0.0279502 0.0733654 0.996913 + outer loop + vertex 0.944583 1.674 2.6403 + vertex 0.948328 1.6774 2.63995 + vertex 0.943603 1.6775 2.64007 + endloop + endfacet + facet normal 0.0279564 0.0736784 0.99689 + outer loop + vertex 0.948328 1.6774 2.63995 + vertex 0.948197 1.68203 2.63961 + vertex 0.943603 1.6775 2.64007 + endloop + endfacet + facet normal 0.0358114 0.0707388 0.996852 + outer loop + vertex 0.953365 1.67247 2.64012 + vertex 0.953081 1.6771 2.6398 + vertex 0.948496 1.67311 2.64025 + endloop + endfacet + facet normal 0.0348694 0.0738568 0.996659 + outer loop + vertex 0.948328 1.6774 2.63995 + vertex 0.953138 1.68194 2.63944 + vertex 0.948197 1.68203 2.63961 + endloop + endfacet + facet normal 0.0348953 0.0756511 0.996524 + outer loop + vertex 0.953138 1.68194 2.63944 + vertex 0.953286 1.68701 2.63905 + vertex 0.948197 1.68203 2.63961 + endloop + endfacet + facet normal 0.0346783 0.0758716 0.996514 + outer loop + vertex 0.948197 1.68203 2.63961 + vertex 0.953286 1.68701 2.63905 + vertex 0.948254 1.68704 2.63922 + endloop + endfacet + facet normal 0.0269996 0.0759766 0.996744 + outer loop + vertex 0.948197 1.68203 2.63961 + vertex 0.948254 1.68704 2.63922 + vertex 0.943272 1.68215 2.63973 + endloop + endfacet + facet normal 0.0346835 0.0778601 0.996361 + outer loop + vertex 0.953286 1.68701 2.63905 + vertex 0.953455 1.69218 2.63864 + vertex 0.948254 1.68704 2.63922 + endloop + endfacet + facet normal 0.0344038 0.0781416 0.996348 + outer loop + vertex 0.948254 1.68704 2.63922 + vertex 0.953455 1.69218 2.63864 + vertex 0.948385 1.69215 2.63882 + endloop + endfacet + facet normal 0.0269411 0.0783488 0.996562 + outer loop + vertex 0.948254 1.68704 2.63922 + vertex 0.948385 1.69215 2.63882 + vertex 0.943293 1.68712 2.63935 + endloop + endfacet + facet normal 0.0343896 0.0799201 0.996208 + outer loop + vertex 0.953455 1.69218 2.63864 + vertex 0.95362 1.69735 2.63822 + vertex 0.948385 1.69215 2.63882 + endloop + endfacet + facet normal 0.0341008 0.0802096 0.996195 + outer loop + vertex 0.948385 1.69215 2.63882 + vertex 0.95362 1.69735 2.63822 + vertex 0.948529 1.69726 2.6384 + endloop + endfacet + facet normal 0.0269031 0.0804296 0.996397 + outer loop + vertex 0.948385 1.69215 2.63882 + vertex 0.948529 1.69726 2.6384 + vertex 0.943395 1.69218 2.63895 + endloop + endfacet + facet normal 0.0340607 0.0822331 0.996031 + outer loop + vertex 0.95362 1.69735 2.63822 + vertex 0.95375 1.70248 2.63779 + vertex 0.948529 1.69726 2.6384 + endloop + endfacet + facet normal 0.0410892 0.0820337 0.995782 + outer loop + vertex 0.95362 1.69735 2.63822 + vertex 0.958822 1.70256 2.63758 + vertex 0.95375 1.70248 2.63779 + endloop + endfacet + facet normal 0.0418901 0.0812385 0.995814 + outer loop + vertex 0.958752 1.69743 2.638 + vertex 0.958822 1.70256 2.63758 + vertex 0.95362 1.69735 2.63822 + endloop + endfacet + facet normal 0.0476703 0.0811389 0.995562 + outer loop + vertex 0.958752 1.69743 2.638 + vertex 0.963804 1.70253 2.63734 + vertex 0.958822 1.70256 2.63758 + endloop + endfacet + facet normal 0.0476731 0.082407 0.995458 + outer loop + vertex 0.963804 1.70253 2.63734 + vertex 0.963479 1.70735 2.63696 + vertex 0.958822 1.70256 2.63758 + endloop + endfacet + facet normal 0.0462817 0.0837531 0.995411 + outer loop + vertex 0.958822 1.70256 2.63758 + vertex 0.963479 1.70735 2.63696 + vertex 0.958689 1.70758 2.63716 + endloop + endfacet + facet normal 0.0488218 0.0824794 0.995396 + outer loop + vertex 0.963804 1.70253 2.63734 + vertex 0.968048 1.70704 2.63676 + vertex 0.963479 1.70735 2.63696 + endloop + endfacet + facet normal 0.0489171 0.0839334 0.99527 + outer loop + vertex 0.968048 1.70704 2.63676 + vertex 0.96695 1.7109 2.63649 + vertex 0.963479 1.70735 2.63696 + endloop + endfacet + facet normal 0.0473777 0.0854355 0.995217 + outer loop + vertex 0.963479 1.70735 2.63696 + vertex 0.96695 1.7109 2.63649 + vertex 0.962899 1.71205 2.63658 + endloop + endfacet + facet normal 0.0475259 0.0859608 0.995164 + outer loop + vertex 0.96695 1.7109 2.63649 + vertex 0.967125 1.71526 2.6361 + vertex 0.962899 1.71205 2.63658 + endloop + endfacet + facet normal 0.0467731 0.0859939 0.995197 + outer loop + vertex 0.967125 1.71526 2.6361 + vertex 0.96695 1.7109 2.63649 + vertex 0.971771 1.71126 2.63623 + endloop + endfacet + facet normal 0.0469804 0.0833919 0.995409 + outer loop + vertex 0.968048 1.70704 2.63676 + vertex 0.971771 1.71126 2.63623 + vertex 0.96695 1.7109 2.63649 + endloop + endfacet + facet normal 0.0477207 0.0827412 0.995428 + outer loop + vertex 0.971891 1.70631 2.63663 + vertex 0.971771 1.71126 2.63623 + vertex 0.968048 1.70704 2.63676 + endloop + endfacet + facet normal 0.0476169 0.0821826 0.995479 + outer loop + vertex 0.968544 1.7024 2.63712 + vertex 0.971891 1.70631 2.63663 + vertex 0.968048 1.70704 2.63676 + endloop + endfacet + facet normal 0.047166 0.0825667 0.995469 + outer loop + vertex 0.973108 1.70242 2.6369 + vertex 0.971891 1.70631 2.63663 + vertex 0.968544 1.7024 2.63712 + endloop + endfacet + facet normal 0.0489885 0.082323 0.995401 + outer loop + vertex 0.968544 1.7024 2.63712 + vertex 0.968048 1.70704 2.63676 + vertex 0.963804 1.70253 2.63734 + endloop + endfacet + facet normal 0.0489595 0.0811663 0.995497 + outer loop + vertex 0.963851 1.69749 2.63775 + vertex 0.968544 1.7024 2.63712 + vertex 0.963804 1.70253 2.63734 + endloop + endfacet + facet normal 0.0478605 0.0822133 0.995465 + outer loop + vertex 0.968827 1.69757 2.6375 + vertex 0.968544 1.7024 2.63712 + vertex 0.963851 1.69749 2.63775 + endloop + endfacet + facet normal 0.0476498 0.0811592 0.995561 + outer loop + vertex 0.963851 1.69749 2.63775 + vertex 0.963804 1.70253 2.63734 + vertex 0.958752 1.69743 2.638 + endloop + endfacet + facet normal 0.0476779 0.079288 0.995711 + outer loop + vertex 0.958591 1.69224 2.63842 + vertex 0.963851 1.69749 2.63775 + vertex 0.958752 1.69743 2.638 + endloop + endfacet + facet normal 0.0420977 0.0794806 0.995947 + outer loop + vertex 0.958591 1.69224 2.63842 + vertex 0.958752 1.69743 2.638 + vertex 0.953455 1.69218 2.63864 + endloop + endfacet + facet normal 0.0467315 0.0802332 0.99568 + outer loop + vertex 0.96374 1.69236 2.63817 + vertex 0.963851 1.69749 2.63775 + vertex 0.958591 1.69224 2.63842 + endloop + endfacet + facet normal 0.0419212 0.0796579 0.99594 + outer loop + vertex 0.953455 1.69218 2.63864 + vertex 0.958752 1.69743 2.638 + vertex 0.95362 1.69735 2.63822 + endloop + endfacet + facet normal 0.0421275 0.0775964 0.996094 + outer loop + vertex 0.953286 1.68701 2.63905 + vertex 0.958591 1.69224 2.63842 + vertex 0.953455 1.69218 2.63864 + endloop + endfacet + facet normal 0.0418645 0.0778619 0.996085 + outer loop + vertex 0.958385 1.68706 2.63883 + vertex 0.958591 1.69224 2.63842 + vertex 0.953286 1.68701 2.63905 + endloop + endfacet + facet normal 0.0406478 0.0735451 0.996463 + outer loop + vertex 0.958077 1.67698 2.6396 + vertex 0.958167 1.68194 2.63923 + vertex 0.953081 1.6771 2.6398 + endloop + endfacet + facet normal 0.0418944 0.0754269 0.996271 + outer loop + vertex 0.953138 1.68194 2.63944 + vertex 0.958385 1.68706 2.63883 + vertex 0.953286 1.68701 2.63905 + endloop + endfacet + facet normal 0.0443652 0.0770499 0.99604 + outer loop + vertex 0.963302 1.68207 2.63899 + vertex 0.963529 1.6872 2.63859 + vertex 0.958167 1.68194 2.63923 + endloop + endfacet + facet normal 0.0467985 0.0776501 0.995882 + outer loop + vertex 0.958385 1.68706 2.63883 + vertex 0.96374 1.69236 2.63817 + vertex 0.958591 1.69224 2.63842 + endloop + endfacet + facet normal 0.0460394 0.0796616 0.995758 + outer loop + vertex 0.96866 1.68742 2.63833 + vertex 0.968815 1.69253 2.63792 + vertex 0.963529 1.6872 2.63859 + endloop + endfacet + facet normal 0.0478995 0.0802035 0.995627 + outer loop + vertex 0.96374 1.69236 2.63817 + vertex 0.968827 1.69757 2.6375 + vertex 0.963851 1.69749 2.63775 + endloop + endfacet + facet normal 0.049708 0.0794638 0.995598 + outer loop + vertex 0.973721 1.69266 2.63766 + vertex 0.973625 1.69763 2.63727 + vertex 0.968815 1.69253 2.63792 + endloop + endfacet + facet normal 0.0471695 0.0821756 0.995501 + outer loop + vertex 0.968827 1.69757 2.6375 + vertex 0.973108 1.70242 2.6369 + vertex 0.968544 1.7024 2.63712 + endloop + endfacet + facet normal 0.0647387 0.0768263 0.994941 + outer loop + vertex 0.97814 1.69745 2.63699 + vertex 0.977614 1.70225 2.63665 + vertex 0.973625 1.69763 2.63727 + endloop + endfacet + facet normal 0.0527154 0.0842722 0.995047 + outer loop + vertex 0.973108 1.70242 2.6369 + vertex 0.976268 1.70731 2.63632 + vertex 0.971891 1.70631 2.63663 + endloop + endfacet + facet normal 0.103114 0.0738401 0.991925 + outer loop + vertex 0.981839 1.70154 2.63627 + vertex 0.981014 1.70597 2.63602 + vertex 0.977614 1.70225 2.63665 + endloop + endfacet + facet normal 0.0530458 0.0828475 0.995149 + outer loop + vertex 0.971771 1.71126 2.63623 + vertex 0.971891 1.70631 2.63663 + vertex 0.976268 1.70731 2.63632 + endloop + endfacet + facet normal 0.0452865 0.0842742 0.995413 + outer loop + vertex 0.971395 1.71569 2.63587 + vertex 0.967125 1.71526 2.6361 + vertex 0.971771 1.71126 2.63623 + endloop + endfacet + facet normal 0.0450102 0.086912 0.995199 + outer loop + vertex 0.971395 1.71569 2.63587 + vertex 0.969412 1.71846 2.63572 + vertex 0.967125 1.71526 2.6361 + endloop + endfacet + facet normal 0.0445625 0.0872313 0.995191 + outer loop + vertex 0.969412 1.71846 2.63572 + vertex 0.965338 1.71991 2.63577 + vertex 0.967125 1.71526 2.6361 + endloop + endfacet + facet normal 0.044997 0.0884522 0.995064 + outer loop + vertex 0.965338 1.71991 2.63577 + vertex 0.969412 1.71846 2.63572 + vertex 0.969637 1.72265 2.63534 + endloop + endfacet + facet normal 0.0511539 0.0912745 0.994511 + outer loop + vertex 0.969412 1.71846 2.63572 + vertex 0.971395 1.71569 2.63587 + vertex 0.974392 1.71873 2.63544 + endloop + endfacet + facet normal 0.0795241 0.0996909 0.991835 + outer loop + vertex 0.974545 1.71441 2.63582 + vertex 0.97645 1.71164 2.63595 + vertex 0.978988 1.71484 2.63542 + endloop + endfacet + facet normal 0.136249 0.0709949 0.988128 + outer loop + vertex 0.984619 1.71299 2.63478 + vertex 0.983726 1.71793 2.63455 + vertex 0.978988 1.71484 2.63542 + endloop + endfacet + facet normal 0.0762319 0.0821278 0.993702 + outer loop + vertex 0.979657 1.71906 2.63501 + vertex 0.978792 1.72276 2.63477 + vertex 0.974392 1.71873 2.63544 + endloop + endfacet + facet normal 0.051342 0.0880881 0.994789 + outer loop + vertex 0.969412 1.71846 2.63572 + vertex 0.974392 1.71873 2.63544 + vertex 0.969637 1.72265 2.63534 + endloop + endfacet + facet normal 0.0649912 0.0936965 0.993477 + outer loop + vertex 0.974681 1.72346 2.63501 + vertex 0.978539 1.7273 2.63439 + vertex 0.973581 1.72729 2.63472 + endloop + endfacet + facet normal 0.04689 0.086957 0.995108 + outer loop + vertex 0.96436 1.7286 2.63505 + vertex 0.968266 1.73217 2.63455 + vertex 0.963385 1.73225 2.63477 + endloop + endfacet + facet normal 0.0453343 0.08655 0.995216 + outer loop + vertex 0.96436 1.7286 2.63505 + vertex 0.963385 1.73225 2.63477 + vertex 0.959499 1.72785 2.63533 + endloop + endfacet + facet normal 0.0496534 0.088474 0.99484 + outer loop + vertex 0.973581 1.72729 2.63472 + vertex 0.973266 1.73206 2.63431 + vertex 0.968499 1.72761 2.63494 + endloop + endfacet + facet normal 0.0498685 0.0840249 0.995215 + outer loop + vertex 0.968266 1.73217 2.63455 + vertex 0.973305 1.73704 2.63389 + vertex 0.968163 1.73691 2.63416 + endloop + endfacet + facet normal 0.0616836 0.0818493 0.994734 + outer loop + vertex 0.978381 1.73211 2.63399 + vertex 0.978434 1.73715 2.63357 + vertex 0.973266 1.73206 2.63431 + endloop + endfacet + facet normal 0.0842149 0.0746203 0.99365 + outer loop + vertex 0.978434 1.73715 2.63357 + vertex 0.983374 1.74205 2.63278 + vertex 0.978563 1.74229 2.63317 + endloop + endfacet + facet normal 0.0837352 0.0636121 0.994456 + outer loop + vertex 0.983374 1.74205 2.63278 + vertex 0.983513 1.74723 2.63244 + vertex 0.978563 1.74229 2.63317 + endloop + endfacet + facet normal 0.133187 0.0491666 0.989871 + outer loop + vertex 0.983513 1.74723 2.63244 + vertex 0.987756 1.75166 2.63165 + vertex 0.983421 1.75239 2.6322 + endloop + endfacet + facet normal 0.130482 0.0323432 0.990923 + outer loop + vertex 0.987756 1.75166 2.63165 + vertex 0.987505 1.75678 2.63152 + vertex 0.983421 1.75239 2.6322 + endloop + endfacet + facet normal 0.046468 0.0653794 0.996778 + outer loop + vertex 0.978489 1.76236 2.63202 + vertex 0.981707 1.76616 2.63162 + vertex 0.977979 1.76694 2.63175 + endloop + endfacet + facet normal 0.0468262 0.0654181 0.996759 + outer loop + vertex 0.978489 1.76236 2.63202 + vertex 0.977979 1.76694 2.63175 + vertex 0.973814 1.76249 2.63223 + endloop + endfacet + facet normal 0.0439674 0.0680881 0.99671 + outer loop + vertex 0.973814 1.76249 2.63223 + vertex 0.977979 1.76694 2.63175 + vertex 0.97343 1.76723 2.63193 + endloop + endfacet + facet normal 0.101037 0.0506526 0.993592 + outer loop + vertex 0.987075 1.76176 2.63138 + vertex 0.985847 1.76692 2.63124 + vertex 0.982869 1.76225 2.63178 + endloop + endfacet + facet normal 0.0491786 0.0784776 0.995702 + outer loop + vertex 0.981707 1.76616 2.63162 + vertex 0.981616 1.77098 2.63125 + vertex 0.977979 1.76694 2.63175 + endloop + endfacet + facet normal 0.0477711 0.0797398 0.99567 + outer loop + vertex 0.977979 1.76694 2.63175 + vertex 0.981616 1.77098 2.63125 + vertex 0.976826 1.77066 2.6315 + endloop + endfacet + facet normal 0.0446119 0.0787749 0.995894 + outer loop + vertex 0.977979 1.76694 2.63175 + vertex 0.976826 1.77066 2.6315 + vertex 0.97343 1.76723 2.63193 + endloop + endfacet + facet normal 0.0406033 0.0827247 0.995745 + outer loop + vertex 0.97343 1.76723 2.63193 + vertex 0.976826 1.77066 2.6315 + vertex 0.972812 1.77173 2.63158 + endloop + endfacet + facet normal 0.0479982 0.0837079 0.995334 + outer loop + vertex 0.97343 1.76723 2.63193 + vertex 0.972812 1.77173 2.63158 + vertex 0.968642 1.76748 2.63214 + endloop + endfacet + facet normal 0.0448952 0.0867372 0.995219 + outer loop + vertex 0.968642 1.76748 2.63214 + vertex 0.972812 1.77173 2.63158 + vertex 0.967923 1.77227 2.63175 + endloop + endfacet + facet normal 0.0498339 0.0874542 0.994921 + outer loop + vertex 0.968642 1.76748 2.63214 + vertex 0.967923 1.77227 2.63175 + vertex 0.963672 1.76749 2.63238 + endloop + endfacet + facet normal 0.0486458 0.088507 0.994887 + outer loop + vertex 0.963672 1.76749 2.63238 + vertex 0.967923 1.77227 2.63175 + vertex 0.963065 1.77226 2.63199 + endloop + endfacet + facet normal 0.0467589 0.0882754 0.994998 + outer loop + vertex 0.963672 1.76749 2.63238 + vertex 0.963065 1.77226 2.63199 + vertex 0.958716 1.76739 2.63263 + endloop + endfacet + facet normal 0.0470998 0.0744265 0.996114 + outer loop + vertex 0.958718 1.76233 2.633 + vertex 0.963672 1.76749 2.63238 + vertex 0.958716 1.76739 2.63263 + endloop + endfacet + facet normal 0.0485367 0.10349 0.993446 + outer loop + vertex 0.967923 1.77227 2.63175 + vertex 0.966274 1.77707 2.63133 + vertex 0.963065 1.77226 2.63199 + endloop + endfacet + facet normal 0.0499343 0.102562 0.993473 + outer loop + vertex 0.963065 1.77226 2.63199 + vertex 0.966274 1.77707 2.63133 + vertex 0.961808 1.77591 2.63168 + endloop + endfacet + facet normal 0.044735 0.100809 0.9939 + outer loop + vertex 0.963065 1.77226 2.63199 + vertex 0.961808 1.77591 2.63168 + vertex 0.958423 1.77218 2.63221 + endloop + endfacet + facet normal 0.0397219 0.105321 0.993645 + outer loop + vertex 0.958423 1.77218 2.63221 + vertex 0.961808 1.77591 2.63168 + vertex 0.957894 1.77672 2.63175 + endloop + endfacet + facet normal 0.0359581 0.104901 0.993832 + outer loop + vertex 0.958423 1.77218 2.63221 + vertex 0.957894 1.77672 2.63175 + vertex 0.953679 1.77236 2.63236 + endloop + endfacet + facet normal 0.0414482 0.113794 0.992639 + outer loop + vertex 0.961808 1.77591 2.63168 + vertex 0.962025 1.78012 2.63118 + vertex 0.957894 1.77672 2.63175 + endloop + endfacet + facet normal 0.0404581 0.114978 0.992544 + outer loop + vertex 0.957894 1.77672 2.63175 + vertex 0.962025 1.78012 2.63118 + vertex 0.956809 1.78114 2.63128 + endloop + endfacet + facet normal 0.0344748 0.113552 0.992934 + outer loop + vertex 0.957894 1.77672 2.63175 + vertex 0.956809 1.78114 2.63128 + vertex 0.953063 1.77724 2.63186 + endloop + endfacet + facet normal 0.03133 0.116536 0.992692 + outer loop + vertex 0.953063 1.77724 2.63186 + vertex 0.956809 1.78114 2.63128 + vertex 0.951405 1.78207 2.63134 + endloop + endfacet + facet normal 0.0310546 0.11492 0.992889 + outer loop + vertex 0.956809 1.78114 2.63128 + vertex 0.95534 1.78527 2.63085 + vertex 0.951405 1.78207 2.63134 + endloop + endfacet + facet normal 0.0304571 0.115644 0.992824 + outer loop + vertex 0.951295 1.7861 2.63087 + vertex 0.951405 1.78207 2.63134 + vertex 0.95534 1.78527 2.63085 + endloop + endfacet + facet normal 0.030919 0.117904 0.992544 + outer loop + vertex 0.95534 1.78527 2.63085 + vertex 0.953632 1.78937 2.63041 + vertex 0.951295 1.7861 2.63087 + endloop + endfacet + facet normal 0.0266608 0.120918 0.992304 + outer loop + vertex 0.9492 1.78835 2.63066 + vertex 0.951295 1.7861 2.63087 + vertex 0.953632 1.78937 2.63041 + endloop + endfacet + facet normal 0.0263614 0.122191 0.992157 + outer loop + vertex 0.9492 1.78835 2.63066 + vertex 0.953632 1.78937 2.63041 + vertex 0.949518 1.79229 2.63016 + endloop + endfacet + facet normal 0.0156864 0.123066 0.992274 + outer loop + vertex 0.945224 1.78895 2.63064 + vertex 0.9492 1.78835 2.63066 + vertex 0.949518 1.79229 2.63016 + endloop + endfacet + facet normal 0.0176476 0.120586 0.992546 + outer loop + vertex 0.94411 1.79285 2.63019 + vertex 0.945224 1.78895 2.63064 + vertex 0.949518 1.79229 2.63016 + endloop + endfacet + facet normal 0.0180447 0.12446 0.992061 + outer loop + vertex 0.949518 1.79229 2.63016 + vertex 0.948509 1.79706 2.62958 + vertex 0.94411 1.79285 2.63019 + endloop + endfacet + facet normal 0.0193371 0.12313 0.992202 + outer loop + vertex 0.94411 1.79285 2.63019 + vertex 0.948509 1.79706 2.62958 + vertex 0.943445 1.7972 2.62966 + endloop + endfacet + facet normal 0.00629253 0.121188 0.99261 + outer loop + vertex 0.94411 1.79285 2.63019 + vertex 0.943445 1.7972 2.62966 + vertex 0.939027 1.79283 2.63023 + endloop + endfacet + facet normal 0.00630602 0.118682 0.992912 + outer loop + vertex 0.939027 1.79283 2.63023 + vertex 0.940361 1.78923 2.63065 + vertex 0.94411 1.79285 2.63019 + endloop + endfacet + facet normal -0.00541538 0.11439 0.993421 + outer loop + vertex 0.935585 1.78886 2.63066 + vertex 0.940361 1.78923 2.63065 + vertex 0.939027 1.79283 2.63023 + endloop + endfacet + facet normal -0.0267461 0.1326 0.990809 + outer loop + vertex 0.93332 1.79174 2.63022 + vertex 0.935585 1.78886 2.63066 + vertex 0.939027 1.79283 2.63023 + endloop + endfacet + facet normal 0.00480638 0.122666 0.992436 + outer loop + vertex 0.939027 1.79283 2.63023 + vertex 0.943445 1.7972 2.62966 + vertex 0.938378 1.7971 2.6297 + endloop + endfacet + facet normal 0.00474997 0.125243 0.992115 + outer loop + vertex 0.943445 1.7972 2.62966 + vertex 0.943473 1.8021 2.62905 + vertex 0.938378 1.7971 2.6297 + endloop + endfacet + facet normal 0.0214541 0.125122 0.991909 + outer loop + vertex 0.943445 1.7972 2.62966 + vertex 0.948456 1.80203 2.62895 + vertex 0.943473 1.8021 2.62905 + endloop + endfacet + facet normal 0.0214886 0.128114 0.991527 + outer loop + vertex 0.948456 1.80203 2.62895 + vertex 0.948718 1.80726 2.62827 + vertex 0.943473 1.8021 2.62905 + endloop + endfacet + facet normal 0.0206718 0.128931 0.991438 + outer loop + vertex 0.943473 1.8021 2.62905 + vertex 0.948718 1.80726 2.62827 + vertex 0.943728 1.80732 2.62836 + endloop + endfacet + facet normal 0.0206844 0.130127 0.991282 + outer loop + vertex 0.948718 1.80726 2.62827 + vertex 0.948688 1.81242 2.62759 + vertex 0.943728 1.80732 2.62836 + endloop + endfacet + facet normal 0.0284711 0.130146 0.991086 + outer loop + vertex 0.948718 1.80726 2.62827 + vertex 0.953642 1.8123 2.62746 + vertex 0.948688 1.81242 2.62759 + endloop + endfacet + facet normal 0.0284997 0.131549 0.9909 + outer loop + vertex 0.953642 1.8123 2.62746 + vertex 0.952983 1.81698 2.62686 + vertex 0.948688 1.81242 2.62759 + endloop + endfacet + facet normal 0.0328849 0.132139 0.990686 + outer loop + vertex 0.953642 1.8123 2.62746 + vertex 0.957822 1.81661 2.62675 + vertex 0.952983 1.81698 2.62686 + endloop + endfacet + facet normal 0.033031 0.134166 0.990408 + outer loop + vertex 0.957822 1.81661 2.62675 + vertex 0.956659 1.82074 2.62623 + vertex 0.952983 1.81698 2.62686 + endloop + endfacet + facet normal 0.0303187 0.136773 0.990138 + outer loop + vertex 0.952983 1.81698 2.62686 + vertex 0.956659 1.82074 2.62623 + vertex 0.951679 1.82113 2.62633 + endloop + endfacet + facet normal 0.0247965 0.13509 0.990523 + outer loop + vertex 0.952983 1.81698 2.62686 + vertex 0.951679 1.82113 2.62633 + vertex 0.947989 1.81715 2.62696 + endloop + endfacet + facet normal 0.024793 0.134981 0.990538 + outer loop + vertex 0.948688 1.81242 2.62759 + vertex 0.952983 1.81698 2.62686 + vertex 0.947989 1.81715 2.62696 + endloop + endfacet + facet normal 0.0160958 0.133744 0.990885 + outer loop + vertex 0.948688 1.81242 2.62759 + vertex 0.947989 1.81715 2.62696 + vertex 0.943634 1.81246 2.62766 + endloop + endfacet + facet normal 0.0304183 0.138071 0.989955 + outer loop + vertex 0.956659 1.82074 2.62623 + vertex 0.955105 1.82454 2.62574 + vertex 0.951679 1.82113 2.62633 + endloop + endfacet + facet normal 0.0270645 0.141376 0.989586 + outer loop + vertex 0.955105 1.82454 2.62574 + vertex 0.950139 1.82484 2.62584 + vertex 0.951679 1.82113 2.62633 + endloop + endfacet + facet normal 0.0197247 0.138409 0.990179 + outer loop + vertex 0.951679 1.82113 2.62633 + vertex 0.950139 1.82484 2.62584 + vertex 0.946684 1.82129 2.6264 + endloop + endfacet + facet normal 0.0197619 0.139677 0.99 + outer loop + vertex 0.947989 1.81715 2.62696 + vertex 0.951679 1.82113 2.62633 + vertex 0.946684 1.82129 2.6264 + endloop + endfacet + facet normal 0.00988507 0.136638 0.990572 + outer loop + vertex 0.947989 1.81715 2.62696 + vertex 0.946684 1.82129 2.6264 + vertex 0.942923 1.81717 2.62701 + endloop + endfacet + facet normal 0.0098909 0.139401 0.990187 + outer loop + vertex 0.943634 1.81246 2.62766 + vertex 0.947989 1.81715 2.62696 + vertex 0.942923 1.81717 2.62701 + endloop + endfacet + facet normal 0.0270882 0.141785 0.989527 + outer loop + vertex 0.950139 1.82484 2.62584 + vertex 0.955105 1.82454 2.62574 + vertex 0.953921 1.82831 2.62524 + endloop + endfacet + facet normal 0.0254377 0.143549 0.989316 + outer loop + vertex 0.948969 1.82848 2.62534 + vertex 0.950139 1.82484 2.62584 + vertex 0.953921 1.82831 2.62524 + endloop + endfacet + facet normal 0.0254325 0.143378 0.989341 + outer loop + vertex 0.953921 1.82831 2.62524 + vertex 0.953429 1.83244 2.62465 + vertex 0.948969 1.82848 2.62534 + endloop + endfacet + facet normal 0.0259706 0.142786 0.989413 + outer loop + vertex 0.948969 1.82848 2.62534 + vertex 0.953429 1.83244 2.62465 + vertex 0.948479 1.83249 2.62477 + endloop + endfacet + facet normal 0.0259829 0.144525 0.98916 + outer loop + vertex 0.953429 1.83244 2.62465 + vertex 0.953496 1.83711 2.62397 + vertex 0.948479 1.83249 2.62477 + endloop + endfacet + facet normal 0.0329572 0.144397 0.988971 + outer loop + vertex 0.953429 1.83244 2.62465 + vertex 0.958486 1.8371 2.6238 + vertex 0.953496 1.83711 2.62397 + endloop + endfacet + facet normal 0.0329499 0.147099 0.988573 + outer loop + vertex 0.958486 1.8371 2.6238 + vertex 0.958547 1.84213 2.62305 + vertex 0.953496 1.83711 2.62397 + endloop + endfacet + facet normal 0.0367204 0.147035 0.988449 + outer loop + vertex 0.958486 1.8371 2.6238 + vertex 0.963504 1.84208 2.62287 + vertex 0.958547 1.84213 2.62305 + endloop + endfacet + facet normal 0.0367317 0.150017 0.988001 + outer loop + vertex 0.963504 1.84208 2.62287 + vertex 0.963009 1.84689 2.62216 + vertex 0.958547 1.84213 2.62305 + endloop + endfacet + facet normal 0.0358146 0.15086 0.987906 + outer loop + vertex 0.958547 1.84213 2.62305 + vertex 0.963009 1.84689 2.62216 + vertex 0.958035 1.84712 2.62231 + endloop + endfacet + facet normal 0.0333601 0.150626 0.988028 + outer loop + vertex 0.958547 1.84213 2.62305 + vertex 0.958035 1.84712 2.62231 + vertex 0.95361 1.84216 2.62321 + endloop + endfacet + facet normal 0.0333569 0.146698 0.988619 + outer loop + vertex 0.953496 1.83711 2.62397 + vertex 0.958547 1.84213 2.62305 + vertex 0.95361 1.84216 2.62321 + endloop + endfacet + facet normal 0.0267351 0.146873 0.988794 + outer loop + vertex 0.953496 1.83711 2.62397 + vertex 0.95361 1.84216 2.62321 + vertex 0.948557 1.83714 2.6241 + endloop + endfacet + facet normal 0.0313967 0.152342 0.987829 + outer loop + vertex 0.95361 1.84216 2.62321 + vertex 0.958035 1.84712 2.62231 + vertex 0.953154 1.84708 2.62247 + endloop + endfacet + facet normal 0.0246037 0.151757 0.988112 + outer loop + vertex 0.95361 1.84216 2.62321 + vertex 0.953154 1.84708 2.62247 + vertex 0.948705 1.8422 2.62333 + endloop + endfacet + facet normal 0.0313548 0.155866 0.98728 + outer loop + vertex 0.958035 1.84712 2.62231 + vertex 0.956414 1.85199 2.62159 + vertex 0.953154 1.84708 2.62247 + endloop + endfacet + facet normal 0.0333564 0.156507 0.987113 + outer loop + vertex 0.958035 1.84712 2.62231 + vertex 0.961784 1.85133 2.62151 + vertex 0.956414 1.85199 2.62159 + endloop + endfacet + facet normal 0.0359546 0.154244 0.987378 + outer loop + vertex 0.963009 1.84689 2.62216 + vertex 0.961784 1.85133 2.62151 + vertex 0.958035 1.84712 2.62231 + endloop + endfacet + facet normal 0.0378814 0.154753 0.987227 + outer loop + vertex 0.963009 1.84689 2.62216 + vertex 0.96679 1.8508 2.6214 + vertex 0.961784 1.85133 2.62151 + endloop + endfacet + facet normal 0.0380392 0.156318 0.986974 + outer loop + vertex 0.96679 1.8508 2.6214 + vertex 0.965263 1.85472 2.62084 + vertex 0.961784 1.85133 2.62151 + endloop + endfacet + facet normal 0.0364731 0.157884 0.986784 + outer loop + vertex 0.965263 1.85472 2.62084 + vertex 0.960349 1.85535 2.62092 + vertex 0.961784 1.85133 2.62151 + endloop + endfacet + facet normal 0.0415068 0.157619 0.986627 + outer loop + vertex 0.970195 1.8541 2.62074 + vertex 0.965263 1.85472 2.62084 + vertex 0.96679 1.8508 2.6214 + endloop + endfacet + facet normal 0.0444275 0.154669 0.986967 + outer loop + vertex 0.972003 1.85 2.6213 + vertex 0.970195 1.8541 2.62074 + vertex 0.96679 1.8508 2.6214 + endloop + endfacet + facet normal 0.0443612 0.154229 0.987039 + outer loop + vertex 0.967834 1.84654 2.62202 + vertex 0.972003 1.85 2.6213 + vertex 0.96679 1.8508 2.6214 + endloop + endfacet + facet normal 0.0456291 0.152738 0.987213 + outer loop + vertex 0.971796 1.84579 2.62196 + vertex 0.972003 1.85 2.6213 + vertex 0.967834 1.84654 2.62202 + endloop + endfacet + facet normal 0.0449543 0.1491 0.9878 + outer loop + vertex 0.968294 1.84198 2.62269 + vertex 0.971796 1.84579 2.62196 + vertex 0.967834 1.84654 2.62202 + endloop + endfacet + facet normal 0.0410321 0.148737 0.988025 + outer loop + vertex 0.968294 1.84198 2.62269 + vertex 0.967834 1.84654 2.62202 + vertex 0.963504 1.84208 2.62287 + endloop + endfacet + facet normal 0.0409952 0.146512 0.988359 + outer loop + vertex 0.963518 1.8371 2.62361 + vertex 0.968294 1.84198 2.62269 + vertex 0.963504 1.84208 2.62287 + endloop + endfacet + facet normal 0.0424995 0.145067 0.988509 + outer loop + vertex 0.968521 1.83712 2.62339 + vertex 0.968294 1.84198 2.62269 + vertex 0.963518 1.8371 2.62361 + endloop + endfacet + facet normal 0.042506 0.144468 0.988596 + outer loop + vertex 0.963606 1.83218 2.62433 + vertex 0.968521 1.83712 2.62339 + vertex 0.963518 1.8371 2.62361 + endloop + endfacet + facet normal 0.0377085 0.144412 0.988799 + outer loop + vertex 0.963606 1.83218 2.62433 + vertex 0.963518 1.8371 2.62361 + vertex 0.958464 1.83234 2.6245 + endloop + endfacet + facet normal 0.037703 0.144208 0.988829 + outer loop + vertex 0.958995 1.82797 2.62512 + vertex 0.963606 1.83218 2.62433 + vertex 0.958464 1.83234 2.6245 + endloop + endfacet + facet normal 0.0328987 0.14366 0.98908 + outer loop + vertex 0.958995 1.82797 2.62512 + vertex 0.958464 1.83234 2.6245 + vertex 0.953921 1.82831 2.62524 + endloop + endfacet + facet normal 0.0393119 0.14248 0.989017 + outer loop + vertex 0.964508 1.82728 2.625 + vertex 0.963606 1.83218 2.62433 + vertex 0.958995 1.82797 2.62512 + endloop + endfacet + facet normal 0.0393315 0.142642 0.988993 + outer loop + vertex 0.958995 1.82797 2.62512 + vertex 0.96003 1.82397 2.62565 + vertex 0.964508 1.82728 2.625 + endloop + endfacet + facet normal 0.0399034 0.141885 0.989079 + outer loop + vertex 0.96003 1.82397 2.62565 + vertex 0.964034 1.82322 2.6256 + vertex 0.964508 1.82728 2.625 + endloop + endfacet + facet normal 0.045185 0.14125 0.988942 + outer loop + vertex 0.964034 1.82322 2.6256 + vertex 0.968655 1.82411 2.62526 + vertex 0.964508 1.82728 2.625 + endloop + endfacet + facet normal 0.0450329 0.141054 0.988977 + outer loop + vertex 0.964508 1.82728 2.625 + vertex 0.968655 1.82411 2.62526 + vertex 0.969536 1.82845 2.6246 + endloop + endfacet + facet normal 0.0447668 0.142153 0.988832 + outer loop + vertex 0.969536 1.82845 2.6246 + vertex 0.968736 1.83225 2.62409 + vertex 0.964508 1.82728 2.625 + endloop + endfacet + facet normal 0.050652 0.143331 0.988378 + outer loop + vertex 0.969536 1.82845 2.6246 + vertex 0.973608 1.83227 2.62384 + vertex 0.968736 1.83225 2.62409 + endloop + endfacet + facet normal 0.0506609 0.142595 0.988484 + outer loop + vertex 0.973608 1.83227 2.62384 + vertex 0.973464 1.83712 2.62315 + vertex 0.968736 1.83225 2.62409 + endloop + endfacet + facet normal 0.0494782 0.143722 0.98838 + outer loop + vertex 0.968736 1.83225 2.62409 + vertex 0.973464 1.83712 2.62315 + vertex 0.968521 1.83712 2.62339 + endloop + endfacet + facet normal 0.0494735 0.144309 0.988295 + outer loop + vertex 0.973464 1.83712 2.62315 + vertex 0.972983 1.842 2.62246 + vertex 0.968521 1.83712 2.62339 + endloop + endfacet + facet normal 0.05618 0.144907 0.987849 + outer loop + vertex 0.973464 1.83712 2.62315 + vertex 0.977792 1.84177 2.62222 + vertex 0.972983 1.842 2.62246 + endloop + endfacet + facet normal 0.0563036 0.148012 0.987382 + outer loop + vertex 0.977792 1.84177 2.62222 + vertex 0.976359 1.8468 2.62155 + vertex 0.972983 1.842 2.62246 + endloop + endfacet + facet normal 0.0559014 0.148291 0.987363 + outer loop + vertex 0.972983 1.842 2.62246 + vertex 0.976359 1.8468 2.62155 + vertex 0.971796 1.84579 2.62196 + endloop + endfacet + facet normal 0.0614846 0.149419 0.98686 + outer loop + vertex 0.977792 1.84177 2.62222 + vertex 0.982096 1.84534 2.62141 + vertex 0.976359 1.8468 2.62155 + endloop + endfacet + facet normal 0.0624279 0.153198 0.986222 + outer loop + vertex 0.982096 1.84534 2.62141 + vertex 0.980337 1.84985 2.62082 + vertex 0.976359 1.8468 2.62155 + endloop + endfacet + facet normal 0.0635051 0.15183 0.986364 + outer loop + vertex 0.976261 1.85096 2.62091 + vertex 0.976359 1.8468 2.62155 + vertex 0.980337 1.84985 2.62082 + endloop + endfacet + facet normal 0.0648137 0.156705 0.985517 + outer loop + vertex 0.980337 1.84985 2.62082 + vertex 0.978818 1.85424 2.62022 + vertex 0.976261 1.85096 2.62091 + endloop + endfacet + facet normal 0.0613001 0.159405 0.985308 + outer loop + vertex 0.974198 1.85336 2.62065 + vertex 0.976261 1.85096 2.62091 + vertex 0.978818 1.85424 2.62022 + endloop + endfacet + facet normal 0.0615699 0.158087 0.985504 + outer loop + vertex 0.974198 1.85336 2.62065 + vertex 0.978818 1.85424 2.62022 + vertex 0.974663 1.85741 2.61997 + endloop + endfacet + facet normal 0.0496666 0.15953 0.985943 + outer loop + vertex 0.970195 1.8541 2.62074 + vertex 0.974198 1.85336 2.62065 + vertex 0.974663 1.85741 2.61997 + endloop + endfacet + facet normal 0.0494384 0.159829 0.985906 + outer loop + vertex 0.969129 1.85809 2.62014 + vertex 0.970195 1.8541 2.62074 + vertex 0.974663 1.85741 2.61997 + endloop + endfacet + facet normal 0.0489415 0.155639 0.986601 + outer loop + vertex 0.974663 1.85741 2.61997 + vertex 0.973679 1.86224 2.61926 + vertex 0.969129 1.85809 2.62014 + endloop + endfacet + facet normal 0.0469211 0.157802 0.986355 + outer loop + vertex 0.969129 1.85809 2.62014 + vertex 0.973679 1.86224 2.61926 + vertex 0.968521 1.86243 2.61948 + endloop + endfacet + facet normal 0.040426 0.156955 0.986778 + outer loop + vertex 0.969129 1.85809 2.62014 + vertex 0.968521 1.86243 2.61948 + vertex 0.964009 1.8586 2.62027 + endloop + endfacet + facet normal 0.0406062 0.158857 0.986466 + outer loop + vertex 0.964009 1.8586 2.62027 + vertex 0.965263 1.85472 2.62084 + vertex 0.969129 1.85809 2.62014 + endloop + endfacet + facet normal 0.0468543 0.155559 0.986715 + outer loop + vertex 0.973679 1.86224 2.61926 + vertex 0.973423 1.86707 2.61851 + vertex 0.968521 1.86243 2.61948 + endloop + endfacet + facet normal 0.0459269 0.156516 0.986607 + outer loop + vertex 0.968521 1.86243 2.61948 + vertex 0.973423 1.86707 2.61851 + vertex 0.968452 1.86711 2.61874 + endloop + endfacet + facet normal 0.0401483 0.156472 0.986866 + outer loop + vertex 0.968521 1.86243 2.61948 + vertex 0.968452 1.86711 2.61874 + vertex 0.963605 1.86277 2.61962 + endloop + endfacet + facet normal 0.0401877 0.156429 0.986871 + outer loop + vertex 0.963605 1.86277 2.61962 + vertex 0.968452 1.86711 2.61874 + vertex 0.963642 1.86723 2.61891 + endloop + endfacet + facet normal 0.0459267 0.155572 0.986756 + outer loop + vertex 0.973423 1.86707 2.61851 + vertex 0.973165 1.87183 2.61777 + vertex 0.968452 1.86711 2.61874 + endloop + endfacet + facet normal 0.0438068 0.15764 0.986525 + outer loop + vertex 0.968452 1.86711 2.61874 + vertex 0.973165 1.87183 2.61777 + vertex 0.968371 1.87194 2.61797 + endloop + endfacet + facet normal 0.0438349 0.15939 0.986242 + outer loop + vertex 0.973165 1.87183 2.61777 + vertex 0.972695 1.87636 2.61706 + vertex 0.968371 1.87194 2.61797 + endloop + endfacet + facet normal 0.0490045 0.159877 0.98592 + outer loop + vertex 0.973165 1.87183 2.61777 + vertex 0.976675 1.87562 2.61698 + vertex 0.972695 1.87636 2.61706 + endloop + endfacet + facet normal 0.0499444 0.165032 0.985023 + outer loop + vertex 0.976675 1.87562 2.61698 + vertex 0.976944 1.87985 2.61626 + vertex 0.972695 1.87636 2.61706 + endloop + endfacet + facet normal 0.048083 0.167232 0.984744 + outer loop + vertex 0.972695 1.87636 2.61706 + vertex 0.976944 1.87985 2.61626 + vertex 0.971686 1.8806 2.61639 + endloop + endfacet + facet normal 0.0412451 0.165693 0.985314 + outer loop + vertex 0.972695 1.87636 2.61706 + vertex 0.971686 1.8806 2.61639 + vertex 0.967813 1.87664 2.61722 + endloop + endfacet + facet normal 0.0483742 0.169361 0.984366 + outer loop + vertex 0.976944 1.87985 2.61626 + vertex 0.975239 1.88402 2.61563 + vertex 0.971686 1.8806 2.61639 + endloop + endfacet + facet normal 0.0443653 0.173402 0.983851 + outer loop + vertex 0.975239 1.88402 2.61563 + vertex 0.970258 1.8845 2.61577 + vertex 0.971686 1.8806 2.61639 + endloop + endfacet + facet normal 0.0386922 0.17142 0.984438 + outer loop + vertex 0.971686 1.8806 2.61639 + vertex 0.970258 1.8845 2.61577 + vertex 0.966663 1.88093 2.61653 + endloop + endfacet + facet normal 0.0363836 0.17368 0.98413 + outer loop + vertex 0.970258 1.8845 2.61577 + vertex 0.965247 1.88482 2.6159 + vertex 0.966663 1.88093 2.61653 + endloop + endfacet + facet normal 0.0364916 0.175477 0.983807 + outer loop + vertex 0.965247 1.88482 2.6159 + vertex 0.970258 1.8845 2.61577 + vertex 0.969128 1.88834 2.61512 + endloop + endfacet + facet normal 0.036481 0.175488 0.983805 + outer loop + vertex 0.964079 1.88866 2.61526 + vertex 0.965247 1.88482 2.6159 + vertex 0.969128 1.88834 2.61512 + endloop + endfacet + facet normal 0.0364858 0.175571 0.98379 + outer loop + vertex 0.969128 1.88834 2.61512 + vertex 0.96857 1.89253 2.6144 + vertex 0.964079 1.88866 2.61526 + endloop + endfacet + facet normal 0.0432294 0.177352 0.983198 + outer loop + vertex 0.969128 1.88834 2.61512 + vertex 0.970258 1.8845 2.61577 + vertex 0.974267 1.88807 2.61495 + endloop + endfacet + facet normal 0.0431475 0.175597 0.983516 + outer loop + vertex 0.974267 1.88807 2.61495 + vertex 0.973608 1.8924 2.6142 + vertex 0.969128 1.88834 2.61512 + endloop + endfacet + facet normal 0.0424839 0.176307 0.983418 + outer loop + vertex 0.969128 1.88834 2.61512 + vertex 0.973608 1.8924 2.6142 + vertex 0.96857 1.89253 2.6144 + endloop + endfacet + facet normal 0.0424685 0.175445 0.983573 + outer loop + vertex 0.973608 1.8924 2.6142 + vertex 0.973287 1.897 2.6134 + vertex 0.96857 1.89253 2.6144 + endloop + endfacet + facet normal 0.0431894 0.174706 0.983673 + outer loop + vertex 0.96857 1.89253 2.6144 + vertex 0.973287 1.897 2.6134 + vertex 0.96836 1.8971 2.6136 + endloop + endfacet + facet normal 0.0432162 0.176527 0.983347 + outer loop + vertex 0.973287 1.897 2.6134 + vertex 0.972742 1.90176 2.61257 + vertex 0.96836 1.8971 2.6136 + endloop + endfacet + facet normal 0.0442946 0.175541 0.983475 + outer loop + vertex 0.96836 1.8971 2.6136 + vertex 0.972742 1.90176 2.61257 + vertex 0.967855 1.90177 2.61279 + endloop + endfacet + facet normal 0.0411766 0.175236 0.983665 + outer loop + vertex 0.96836 1.8971 2.6136 + vertex 0.967855 1.90177 2.61279 + vertex 0.963669 1.89726 2.61376 + endloop + endfacet + facet normal 0.0410869 0.171972 0.984245 + outer loop + vertex 0.963716 1.89282 2.61454 + vertex 0.96836 1.8971 2.6136 + vertex 0.963669 1.89726 2.61376 + endloop + endfacet + facet normal 0.0386519 0.174536 0.983892 + outer loop + vertex 0.96857 1.89253 2.6144 + vertex 0.96836 1.8971 2.6136 + vertex 0.963716 1.89282 2.61454 + endloop + endfacet + facet normal 0.0416215 0.174834 0.983718 + outer loop + vertex 0.963669 1.89726 2.61376 + vertex 0.967855 1.90177 2.61279 + vertex 0.963239 1.90176 2.61298 + endloop + endfacet + facet normal 0.0361469 0.174363 0.984018 + outer loop + vertex 0.963669 1.89726 2.61376 + vertex 0.963239 1.90176 2.61298 + vertex 0.958948 1.89723 2.61394 + endloop + endfacet + facet normal 0.0324467 0.177761 0.983539 + outer loop + vertex 0.958948 1.89723 2.61394 + vertex 0.963239 1.90176 2.61298 + vertex 0.958475 1.90199 2.6131 + endloop + endfacet + facet normal 0.0325689 0.18059 0.983019 + outer loop + vertex 0.963239 1.90176 2.61298 + vertex 0.962684 1.90622 2.61218 + vertex 0.958475 1.90199 2.6131 + endloop + endfacet + facet normal 0.0265983 0.186334 0.982126 + outer loop + vertex 0.958475 1.90199 2.6131 + vertex 0.962684 1.90622 2.61218 + vertex 0.957804 1.90663 2.61224 + endloop + endfacet + facet normal 0.0106114 0.184154 0.98284 + outer loop + vertex 0.958475 1.90199 2.6131 + vertex 0.957804 1.90663 2.61224 + vertex 0.953395 1.90212 2.61313 + endloop + endfacet + facet normal 0.0265983 0.186335 0.982126 + outer loop + vertex 0.962684 1.90622 2.61218 + vertex 0.9617 1.91042 2.61141 + vertex 0.957804 1.90663 2.61224 + endloop + endfacet + facet normal 0.0213208 0.191567 0.981248 + outer loop + vertex 0.957804 1.90663 2.61224 + vertex 0.9617 1.91042 2.61141 + vertex 0.956684 1.91074 2.61146 + endloop + endfacet + facet normal 0.0209942 0.186258 0.982276 + outer loop + vertex 0.9617 1.91042 2.61141 + vertex 0.960356 1.91429 2.61071 + vertex 0.956684 1.91074 2.61146 + endloop + endfacet + facet normal 0.0309416 0.189552 0.981383 + outer loop + vertex 0.965301 1.91381 2.61064 + vertex 0.960356 1.91429 2.61071 + vertex 0.9617 1.91042 2.61141 + endloop + endfacet + facet normal 0.0347249 0.185666 0.981999 + outer loop + vertex 0.966961 1.90967 2.61137 + vertex 0.965301 1.91381 2.61064 + vertex 0.9617 1.91042 2.61141 + endloop + endfacet + facet normal 0.0381661 0.186982 0.981622 + outer loop + vertex 0.969319 1.91317 2.61061 + vertex 0.965301 1.91381 2.61064 + vertex 0.966961 1.90967 2.61137 + endloop + endfacet + facet normal 0.0420812 0.184413 0.981948 + outer loop + vertex 0.971324 1.91085 2.61096 + vertex 0.969319 1.91317 2.61061 + vertex 0.966961 1.90967 2.61137 + endloop + endfacet + facet normal 0.0425742 0.18269 0.982248 + outer loop + vertex 0.971324 1.91085 2.61096 + vertex 0.966961 1.90967 2.61137 + vertex 0.971249 1.90667 2.61174 + endloop + endfacet + facet normal 0.0484355 0.182541 0.982005 + outer loop + vertex 0.971324 1.91085 2.61096 + vertex 0.971249 1.90667 2.61174 + vertex 0.975441 1.91012 2.61089 + endloop + endfacet + facet normal 0.049102 0.186386 0.981249 + outer loop + vertex 0.975441 1.91012 2.61089 + vertex 0.973924 1.91436 2.61016 + vertex 0.971324 1.91085 2.61096 + endloop + endfacet + facet normal 0.0553167 0.188488 0.980516 + outer loop + vertex 0.973924 1.91436 2.61016 + vertex 0.975441 1.91012 2.61089 + vertex 0.979354 1.91348 2.61002 + endloop + endfacet + facet normal 0.0551584 0.187475 0.980719 + outer loop + vertex 0.979354 1.91348 2.61002 + vertex 0.978747 1.91781 2.60923 + vertex 0.973924 1.91436 2.61016 + endloop + endfacet + facet normal 0.0560238 0.186315 0.980891 + outer loop + vertex 0.973924 1.91436 2.61016 + vertex 0.978747 1.91781 2.60923 + vertex 0.974778 1.91859 2.60931 + endloop + endfacet + facet normal 0.0471038 0.188137 0.981013 + outer loop + vertex 0.969821 1.91731 2.60979 + vertex 0.973924 1.91436 2.61016 + vertex 0.974778 1.91859 2.60931 + endloop + endfacet + facet normal 0.0471827 0.18785 0.981064 + outer loop + vertex 0.974778 1.91859 2.60931 + vertex 0.973663 1.92218 2.60868 + vertex 0.969821 1.91731 2.60979 + endloop + endfacet + facet normal 0.0465225 0.188357 0.980998 + outer loop + vertex 0.969821 1.91731 2.60979 + vertex 0.973663 1.92218 2.60868 + vertex 0.968645 1.92215 2.60892 + endloop + endfacet + facet normal 0.0465122 0.189092 0.980857 + outer loop + vertex 0.973663 1.92218 2.60868 + vertex 0.972727 1.92679 2.60783 + vertex 0.968645 1.92215 2.60892 + endloop + endfacet + facet normal 0.0468965 0.188764 0.980902 + outer loop + vertex 0.968645 1.92215 2.60892 + vertex 0.972727 1.92679 2.60783 + vertex 0.967833 1.92681 2.60806 + endloop + endfacet + facet normal 0.046879 0.191807 0.980313 + outer loop + vertex 0.972727 1.92679 2.60783 + vertex 0.971253 1.93171 2.60694 + vertex 0.967833 1.92681 2.60806 + endloop + endfacet + facet normal 0.0460816 0.192347 0.980244 + outer loop + vertex 0.967833 1.92681 2.60806 + vertex 0.971253 1.93171 2.60694 + vertex 0.966636 1.93048 2.6074 + endloop + endfacet + facet normal 0.0447364 0.197072 0.979368 + outer loop + vertex 0.967071 1.93475 2.60652 + vertex 0.966636 1.93048 2.6074 + vertex 0.971253 1.93171 2.60694 + endloop + endfacet + facet normal 0.0437419 0.195746 0.979679 + outer loop + vertex 0.971481 1.93596 2.60608 + vertex 0.967071 1.93475 2.60652 + vertex 0.971253 1.93171 2.60694 + endloop + endfacet + facet normal 0.0521509 0.195233 0.979369 + outer loop + vertex 0.971481 1.93596 2.60608 + vertex 0.971253 1.93171 2.60694 + vertex 0.9755 1.93527 2.606 + endloop + endfacet + facet normal 0.0527272 0.198697 0.978642 + outer loop + vertex 0.9755 1.93527 2.606 + vertex 0.974093 1.93949 2.60522 + vertex 0.971481 1.93596 2.60608 + endloop + endfacet + facet normal 0.0490932 0.201298 0.978299 + outer loop + vertex 0.969539 1.93832 2.60569 + vertex 0.971481 1.93596 2.60608 + vertex 0.974093 1.93949 2.60522 + endloop + endfacet + facet normal 0.0495379 0.199698 0.978604 + outer loop + vertex 0.969539 1.93832 2.60569 + vertex 0.974093 1.93949 2.60522 + vertex 0.970013 1.94246 2.60482 + endloop + endfacet + facet normal 0.038419 0.201017 0.978834 + outer loop + vertex 0.965467 1.93893 2.60573 + vertex 0.969539 1.93832 2.60569 + vertex 0.970013 1.94246 2.60482 + endloop + endfacet + facet normal 0.0385627 0.20084 0.978865 + outer loop + vertex 0.964465 1.94304 2.60492 + vertex 0.965467 1.93893 2.60573 + vertex 0.970013 1.94246 2.60482 + endloop + endfacet + facet normal 0.0380073 0.195351 0.979997 + outer loop + vertex 0.970013 1.94246 2.60482 + vertex 0.968742 1.94728 2.60391 + vertex 0.964465 1.94304 2.60492 + endloop + endfacet + facet normal 0.0348029 0.198464 0.97949 + outer loop + vertex 0.964465 1.94304 2.60492 + vertex 0.968742 1.94728 2.60391 + vertex 0.963654 1.94743 2.60406 + endloop + endfacet + facet normal 0.0144107 0.194933 0.980711 + outer loop + vertex 0.964465 1.94304 2.60492 + vertex 0.963654 1.94743 2.60406 + vertex 0.959187 1.943 2.60501 + endloop + endfacet + facet normal 0.0347048 0.194248 0.980338 + outer loop + vertex 0.968742 1.94728 2.60391 + vertex 0.967821 1.95188 2.60303 + vertex 0.963654 1.94743 2.60406 + endloop + endfacet + facet normal 0.0291366 0.199265 0.979512 + outer loop + vertex 0.963654 1.94743 2.60406 + vertex 0.967821 1.95188 2.60303 + vertex 0.96309 1.95186 2.60318 + endloop + endfacet + facet normal 0.0291747 0.196121 0.980146 + outer loop + vertex 0.967821 1.95188 2.60303 + vertex 0.966569 1.95547 2.60235 + vertex 0.96309 1.95186 2.60318 + endloop + endfacet + facet normal 0.0179492 0.206494 0.978283 + outer loop + vertex 0.96309 1.95186 2.60318 + vertex 0.966569 1.95547 2.60235 + vertex 0.962633 1.95611 2.60229 + endloop + endfacet + facet normal 0.0185656 0.210237 0.977474 + outer loop + vertex 0.966569 1.95547 2.60235 + vertex 0.967046 1.95964 2.60145 + vertex 0.962633 1.95611 2.60229 + endloop + endfacet + facet normal 0.0163568 0.21287 0.976944 + outer loop + vertex 0.962633 1.95611 2.60229 + vertex 0.967046 1.95964 2.60145 + vertex 0.961908 1.96008 2.60143 + endloop + endfacet + facet normal 0.0440122 0.207283 0.97729 + outer loop + vertex 0.967046 1.95964 2.60145 + vertex 0.966569 1.95547 2.60235 + vertex 0.971211 1.95666 2.60189 + endloop + endfacet + facet normal 0.0419765 0.204537 0.977958 + outer loop + vertex 0.971423 1.9609 2.60099 + vertex 0.967046 1.95964 2.60145 + vertex 0.971211 1.95666 2.60189 + endloop + endfacet + facet normal 0.0552684 0.203768 0.977458 + outer loop + vertex 0.971423 1.9609 2.60099 + vertex 0.971211 1.95666 2.60189 + vertex 0.975488 1.9601 2.60093 + endloop + endfacet + facet normal 0.0562329 0.208775 0.976346 + outer loop + vertex 0.975488 1.9601 2.60093 + vertex 0.974066 1.96445 2.60008 + vertex 0.971423 1.9609 2.60099 + endloop + endfacet + facet normal 0.0502774 0.213057 0.975745 + outer loop + vertex 0.969526 1.96325 2.60058 + vertex 0.971423 1.9609 2.60099 + vertex 0.974066 1.96445 2.60008 + endloop + endfacet + facet normal 0.0498697 0.21448 0.975454 + outer loop + vertex 0.969526 1.96325 2.60058 + vertex 0.974066 1.96445 2.60008 + vertex 0.969989 1.96738 2.59965 + endloop + endfacet + facet normal 0.0303096 0.21674 0.975759 + outer loop + vertex 0.965547 1.96369 2.6006 + vertex 0.969526 1.96325 2.60058 + vertex 0.969989 1.96738 2.59965 + endloop + endfacet + facet normal 0.0299882 0.213844 0.976407 + outer loop + vertex 0.969526 1.96325 2.60058 + vertex 0.965547 1.96369 2.6006 + vertex 0.967046 1.95964 2.60145 + endloop + endfacet + facet normal 0.0160169 0.208968 0.977791 + outer loop + vertex 0.967046 1.95964 2.60145 + vertex 0.965547 1.96369 2.6006 + vertex 0.961908 1.96008 2.60143 + endloop + endfacet + facet normal 0.047935 0.211893 0.976117 + outer loop + vertex 0.969989 1.96738 2.59965 + vertex 0.974066 1.96445 2.60008 + vertex 0.974777 1.96865 2.59914 + endloop + endfacet + facet normal 0.0489416 0.208381 0.976822 + outer loop + vertex 0.974777 1.96865 2.59914 + vertex 0.973452 1.97199 2.59849 + vertex 0.969989 1.96738 2.59965 + endloop + endfacet + facet normal 0.0402773 0.214649 0.975861 + outer loop + vertex 0.969989 1.96738 2.59965 + vertex 0.973452 1.97199 2.59849 + vertex 0.968625 1.97209 2.59867 + endloop + endfacet + facet normal 0.0573871 0.211512 0.975689 + outer loop + vertex 0.974777 1.96865 2.59914 + vertex 0.977917 1.97202 2.59822 + vertex 0.973452 1.97199 2.59849 + endloop + endfacet + facet normal 0.0574561 0.207852 0.976471 + outer loop + vertex 0.977917 1.97202 2.59822 + vertex 0.97649 1.9754 2.59758 + vertex 0.973452 1.97199 2.59849 + endloop + endfacet + facet normal 0.0540176 0.210801 0.976035 + outer loop + vertex 0.973452 1.97199 2.59849 + vertex 0.97649 1.9754 2.59758 + vertex 0.972552 1.97621 2.59763 + endloop + endfacet + facet normal 0.0624896 0.209838 0.975737 + outer loop + vertex 0.977917 1.97202 2.59822 + vertex 0.981102 1.97655 2.59704 + vertex 0.97649 1.9754 2.59758 + endloop + endfacet + facet normal 0.062496 0.209833 0.975738 + outer loop + vertex 0.982647 1.97172 2.59798 + vertex 0.981102 1.97655 2.59704 + vertex 0.977917 1.97202 2.59822 + endloop + endfacet + facet normal 0.0625261 0.210423 0.975609 + outer loop + vertex 0.978688 1.96782 2.59908 + vertex 0.982647 1.97172 2.59798 + vertex 0.977917 1.97202 2.59822 + endloop + endfacet + facet normal 0.0624603 0.210487 0.975599 + outer loop + vertex 0.983608 1.96719 2.5989 + vertex 0.982647 1.97172 2.59798 + vertex 0.978688 1.96782 2.59908 + endloop + endfacet + facet normal 0.0624175 0.210128 0.975679 + outer loop + vertex 0.979431 1.96346 2.59997 + vertex 0.983608 1.96719 2.5989 + vertex 0.978688 1.96782 2.59908 + endloop + endfacet + facet normal 0.059424 0.209676 0.975963 + outer loop + vertex 0.979431 1.96346 2.59997 + vertex 0.978688 1.96782 2.59908 + vertex 0.974066 1.96445 2.60008 + endloop + endfacet + facet normal 0.0636918 0.208762 0.97589 + outer loop + vertex 0.984962 1.96253 2.59981 + vertex 0.983608 1.96719 2.5989 + vertex 0.979431 1.96346 2.59997 + endloop + endfacet + facet normal 0.0635376 0.207808 0.976104 + outer loop + vertex 0.979431 1.96346 2.59997 + vertex 0.980452 1.95917 2.60082 + vertex 0.984962 1.96253 2.59981 + endloop + endfacet + facet normal 0.0645417 0.206523 0.976311 + outer loop + vertex 0.980452 1.95917 2.60082 + vertex 0.984525 1.95838 2.60071 + vertex 0.984962 1.96253 2.59981 + endloop + endfacet + facet normal 0.0684698 0.206073 0.976138 + outer loop + vertex 0.984525 1.95838 2.60071 + vertex 0.989105 1.95951 2.60015 + vertex 0.984962 1.96253 2.59981 + endloop + endfacet + facet normal 0.067492 0.20477 0.976481 + outer loop + vertex 0.984962 1.96253 2.59981 + vertex 0.989105 1.95951 2.60015 + vertex 0.989792 1.96367 2.59923 + endloop + endfacet + facet normal 0.0744323 0.203568 0.976227 + outer loop + vertex 0.989105 1.95951 2.60015 + vertex 0.993714 1.96288 2.5991 + vertex 0.989792 1.96367 2.59923 + endloop + endfacet + facet normal 0.0745472 0.20416 0.976095 + outer loop + vertex 0.993714 1.96288 2.5991 + vertex 0.992952 1.96701 2.59829 + vertex 0.989792 1.96367 2.59923 + endloop + endfacet + facet normal 0.0701376 0.208189 0.975571 + outer loop + vertex 0.989792 1.96367 2.59923 + vertex 0.992952 1.96701 2.59829 + vertex 0.988441 1.96693 2.59864 + endloop + endfacet + facet normal 0.066927 0.206946 0.976061 + outer loop + vertex 0.989792 1.96367 2.59923 + vertex 0.988441 1.96693 2.59864 + vertex 0.984962 1.96253 2.59981 + endloop + endfacet + facet normal 0.0701731 0.207151 0.975789 + outer loop + vertex 0.992952 1.96701 2.59829 + vertex 0.991546 1.97031 2.59769 + vertex 0.988441 1.96693 2.59864 + endloop + endfacet + facet normal 0.0665809 0.210327 0.975361 + outer loop + vertex 0.988441 1.96693 2.59864 + vertex 0.991546 1.97031 2.59769 + vertex 0.987569 1.97111 2.59779 + endloop + endfacet + facet normal 0.0643733 0.209914 0.975598 + outer loop + vertex 0.988441 1.96693 2.59864 + vertex 0.987569 1.97111 2.59779 + vertex 0.983608 1.96719 2.5989 + endloop + endfacet + facet normal 0.0667065 0.210973 0.975213 + outer loop + vertex 0.991546 1.97031 2.59769 + vertex 0.991994 1.97466 2.59672 + vertex 0.987569 1.97111 2.59779 + endloop + endfacet + facet normal 0.0663063 0.211448 0.975137 + outer loop + vertex 0.987569 1.97111 2.59779 + vertex 0.991994 1.97466 2.59672 + vertex 0.986602 1.97561 2.59688 + endloop + endfacet + facet normal 0.063592 0.210924 0.975432 + outer loop + vertex 0.987569 1.97111 2.59779 + vertex 0.986602 1.97561 2.59688 + vertex 0.982647 1.97172 2.59798 + endloop + endfacet + facet normal 0.075579 0.209296 0.974927 + outer loop + vertex 0.992952 1.96701 2.59829 + vertex 0.996186 1.97157 2.59706 + vertex 0.991546 1.97031 2.59769 + endloop + endfacet + facet normal 0.0806567 0.205788 0.975267 + outer loop + vertex 0.997633 1.96678 2.59796 + vertex 0.996186 1.97157 2.59706 + vertex 0.992952 1.96701 2.59829 + endloop + endfacet + facet normal 0.0869777 0.207526 0.974355 + outer loop + vertex 0.997633 1.96678 2.59796 + vertex 1.00154 1.97064 2.59678 + vertex 0.996186 1.97157 2.59706 + endloop + endfacet + facet normal 0.0899303 0.204639 0.974698 + outer loop + vertex 1.00244 1.96614 2.59765 + vertex 1.00154 1.97064 2.59678 + vertex 0.997633 1.96678 2.59796 + endloop + endfacet + facet normal 0.089847 0.203941 0.974852 + outer loop + vertex 0.998566 1.96227 2.59881 + vertex 1.00244 1.96614 2.59765 + vertex 0.997633 1.96678 2.59796 + endloop + endfacet + facet normal 0.0831407 0.202715 0.975702 + outer loop + vertex 0.998566 1.96227 2.59881 + vertex 0.997633 1.96678 2.59796 + vertex 0.993714 1.96288 2.5991 + endloop + endfacet + facet normal 0.0962179 0.20573 0.973867 + outer loop + vertex 1.00244 1.96614 2.59765 + vertex 1.00678 1.96955 2.5965 + vertex 1.00154 1.97064 2.59678 + endloop + endfacet + facet normal 0.0965239 0.207296 0.973505 + outer loop + vertex 1.00678 1.96955 2.5965 + vertex 1.00536 1.97412 2.59566 + vertex 1.00154 1.97064 2.59678 + endloop + endfacet + facet normal 0.0955177 0.208358 0.973377 + outer loop + vertex 1.00536 1.97412 2.59566 + vertex 1.00052 1.97509 2.59593 + vertex 1.00154 1.97064 2.59678 + endloop + endfacet + facet normal 0.0968114 0.205006 0.973961 + outer loop + vertex 1.00635 1.96522 2.59745 + vertex 1.00678 1.96955 2.5965 + vertex 1.00244 1.96614 2.59765 + endloop + endfacet + facet normal 0.0963024 0.202734 0.974487 + outer loop + vertex 1.00332 1.96193 2.59843 + vertex 1.00635 1.96522 2.59745 + vertex 1.00244 1.96614 2.59765 + endloop + endfacet + facet normal 0.097063 0.202052 0.974553 + outer loop + vertex 1.0078 1.96183 2.59801 + vertex 1.00635 1.96522 2.59745 + vertex 1.00332 1.96193 2.59843 + endloop + endfacet + facet normal 0.0963919 0.205055 0.973992 + outer loop + vertex 1.00678 1.96955 2.5965 + vertex 1.00635 1.96522 2.59745 + vertex 1.011 1.9662 2.59678 + endloop + endfacet + facet normal 0.0806348 0.205149 0.975403 + outer loop + vertex 0.993714 1.96288 2.5991 + vertex 0.997633 1.96678 2.59796 + vertex 0.992952 1.96701 2.59829 + endloop + endfacet + facet normal 0.075448 0.202241 0.976425 + outer loop + vertex 0.994449 1.95853 2.59994 + vertex 0.993714 1.96288 2.5991 + vertex 0.989105 1.95951 2.60015 + endloop + endfacet + facet normal 0.0757689 0.204075 0.976019 + outer loop + vertex 0.989105 1.95951 2.60015 + vertex 0.99051 1.95512 2.60096 + vertex 0.994449 1.95853 2.59994 + endloop + endfacet + facet normal 0.0711312 0.20271 0.976652 + outer loop + vertex 0.99051 1.95512 2.60096 + vertex 0.989105 1.95951 2.60015 + vertex 0.986449 1.95592 2.60109 + endloop + endfacet + facet normal 0.070643 0.200136 0.977218 + outer loop + vertex 0.986449 1.95592 2.60109 + vertex 0.986165 1.95157 2.602 + vertex 0.99051 1.95512 2.60096 + endloop + endfacet + facet normal 0.0700912 0.200785 0.977125 + outer loop + vertex 0.991599 1.9507 2.60179 + vertex 0.99051 1.95512 2.60096 + vertex 0.986165 1.95157 2.602 + endloop + endfacet + facet normal 0.0700568 0.20056 0.977173 + outer loop + vertex 0.987611 1.94671 2.6029 + vertex 0.991599 1.9507 2.60179 + vertex 0.986165 1.95157 2.602 + endloop + endfacet + facet normal 0.0659528 0.199435 0.977689 + outer loop + vertex 0.987611 1.94671 2.6029 + vertex 0.986165 1.95157 2.602 + vertex 0.982735 1.94681 2.60321 + endloop + endfacet + facet normal 0.0659555 0.19975 0.977624 + outer loop + vertex 0.983533 1.94249 2.60403 + vertex 0.987611 1.94671 2.6029 + vertex 0.982735 1.94681 2.60321 + endloop + endfacet + facet normal 0.0621779 0.199125 0.978 + outer loop + vertex 0.983533 1.94249 2.60403 + vertex 0.982735 1.94681 2.60321 + vertex 0.978757 1.94287 2.60426 + endloop + endfacet + facet normal 0.06223 0.199871 0.977844 + outer loop + vertex 0.979329 1.93872 2.60507 + vertex 0.983533 1.94249 2.60403 + vertex 0.978757 1.94287 2.60426 + endloop + endfacet + facet normal 0.0572149 0.199265 0.978274 + outer loop + vertex 0.979329 1.93872 2.60507 + vertex 0.978757 1.94287 2.60426 + vertex 0.974093 1.93949 2.60522 + endloop + endfacet + facet normal 0.0575187 0.198864 0.978338 + outer loop + vertex 0.974093 1.93949 2.60522 + vertex 0.978757 1.94287 2.60426 + vertex 0.974901 1.94364 2.60433 + endloop + endfacet + facet normal 0.0575101 0.19882 0.978347 + outer loop + vertex 0.978757 1.94287 2.60426 + vertex 0.978279 1.94694 2.60346 + vertex 0.974901 1.94364 2.60433 + endloop + endfacet + facet normal 0.0570947 0.199229 0.978288 + outer loop + vertex 0.974901 1.94364 2.60433 + vertex 0.978279 1.94694 2.60346 + vertex 0.97374 1.94716 2.60368 + endloop + endfacet + facet normal 0.0508207 0.197294 0.979026 + outer loop + vertex 0.974901 1.94364 2.60433 + vertex 0.97374 1.94716 2.60368 + vertex 0.970013 1.94246 2.60482 + endloop + endfacet + facet normal 0.057063 0.198371 0.978464 + outer loop + vertex 0.978279 1.94694 2.60346 + vertex 0.97762 1.95118 2.60264 + vertex 0.97374 1.94716 2.60368 + endloop + endfacet + facet normal 0.057265 0.198183 0.978491 + outer loop + vertex 0.97374 1.94716 2.60368 + vertex 0.97762 1.95118 2.60264 + vertex 0.972749 1.95174 2.60281 + endloop + endfacet + facet normal 0.0496078 0.196666 0.979215 + outer loop + vertex 0.97374 1.94716 2.60368 + vertex 0.972749 1.95174 2.60281 + vertex 0.968742 1.94728 2.60391 + endloop + endfacet + facet normal 0.0574122 0.199539 0.978207 + outer loop + vertex 0.97762 1.95118 2.60264 + vertex 0.976661 1.95571 2.60177 + vertex 0.972749 1.95174 2.60281 + endloop + endfacet + facet normal 0.0559807 0.200897 0.978011 + outer loop + vertex 0.972749 1.95174 2.60281 + vertex 0.976661 1.95571 2.60177 + vertex 0.971211 1.95666 2.60189 + endloop + endfacet + facet normal 0.0493259 0.198959 0.978766 + outer loop + vertex 0.972749 1.95174 2.60281 + vertex 0.971211 1.95666 2.60189 + vertex 0.967821 1.95188 2.60303 + endloop + endfacet + facet normal 0.0619377 0.200409 0.977752 + outer loop + vertex 0.97762 1.95118 2.60264 + vertex 0.981985 1.95471 2.60164 + vertex 0.976661 1.95571 2.60177 + endloop + endfacet + facet normal 0.0622737 0.202246 0.977353 + outer loop + vertex 0.981985 1.95471 2.60164 + vertex 0.980452 1.95917 2.60082 + vertex 0.976661 1.95571 2.60177 + endloop + endfacet + facet normal 0.0608788 0.203717 0.977135 + outer loop + vertex 0.980452 1.95917 2.60082 + vertex 0.975488 1.9601 2.60093 + vertex 0.976661 1.95571 2.60177 + endloop + endfacet + facet normal 0.0618433 0.200521 0.977736 + outer loop + vertex 0.981509 1.95032 2.60257 + vertex 0.981985 1.95471 2.60164 + vertex 0.97762 1.95118 2.60264 + endloop + endfacet + facet normal 0.065467 0.200096 0.977587 + outer loop + vertex 0.981985 1.95471 2.60164 + vertex 0.981509 1.95032 2.60257 + vertex 0.986165 1.95157 2.602 + endloop + endfacet + facet normal 0.0615115 0.198987 0.97807 + outer loop + vertex 0.978279 1.94694 2.60346 + vertex 0.981509 1.95032 2.60257 + vertex 0.97762 1.95118 2.60264 + endloop + endfacet + facet normal 0.0620081 0.198528 0.978132 + outer loop + vertex 0.982735 1.94681 2.60321 + vertex 0.981509 1.95032 2.60257 + vertex 0.978279 1.94694 2.60346 + endloop + endfacet + facet normal 0.0627262 0.199339 0.977921 + outer loop + vertex 0.984374 1.93817 2.60486 + vertex 0.983533 1.94249 2.60403 + vertex 0.979329 1.93872 2.60507 + endloop + endfacet + facet normal 0.062761 0.19969 0.977847 + outer loop + vertex 0.979329 1.93872 2.60507 + vertex 0.980397 1.93463 2.60584 + vertex 0.984374 1.93817 2.60486 + endloop + endfacet + facet normal 0.0637036 0.198672 0.977993 + outer loop + vertex 0.980397 1.93463 2.60584 + vertex 0.985309 1.93399 2.60565 + vertex 0.984374 1.93817 2.60486 + endloop + endfacet + facet normal 0.067167 0.199375 0.977619 + outer loop + vertex 0.984374 1.93817 2.60486 + vertex 0.985309 1.93399 2.60565 + vertex 0.989832 1.93745 2.60463 + endloop + endfacet + facet normal 0.0671385 0.199145 0.977667 + outer loop + vertex 0.989832 1.93745 2.60463 + vertex 0.988535 1.94215 2.60377 + vertex 0.984374 1.93817 2.60486 + endloop + endfacet + facet normal 0.0709209 0.200104 0.977204 + outer loop + vertex 0.989832 1.93745 2.60463 + vertex 0.993353 1.94196 2.60345 + vertex 0.988535 1.94215 2.60377 + endloop + endfacet + facet normal 0.0709088 0.199615 0.977305 + outer loop + vertex 0.993353 1.94196 2.60345 + vertex 0.99252 1.9462 2.60265 + vertex 0.988535 1.94215 2.60377 + endloop + endfacet + facet normal 0.0703233 0.200172 0.977234 + outer loop + vertex 0.988535 1.94215 2.60377 + vertex 0.99252 1.9462 2.60265 + vertex 0.987611 1.94671 2.6029 + endloop + endfacet + facet normal 0.0762215 0.200548 0.976714 + outer loop + vertex 0.993353 1.94196 2.60345 + vertex 0.996463 1.94534 2.60252 + vertex 0.99252 1.9462 2.60265 + endloop + endfacet + facet normal 0.0765429 0.202085 0.976372 + outer loop + vertex 0.996463 1.94534 2.60252 + vertex 0.996897 1.94968 2.60158 + vertex 0.99252 1.9462 2.60265 + endloop + endfacet + facet normal 0.0770151 0.201516 0.976453 + outer loop + vertex 0.99252 1.9462 2.60265 + vertex 0.996897 1.94968 2.60158 + vertex 0.991599 1.9507 2.60179 + endloop + endfacet + facet normal 0.0783156 0.19868 0.97693 + outer loop + vertex 0.997861 1.94193 2.6031 + vertex 0.996463 1.94534 2.60252 + vertex 0.993353 1.94196 2.60345 + endloop + endfacet + facet normal 0.0782998 0.200872 0.976483 + outer loop + vertex 0.994695 1.9386 2.60404 + vertex 0.997861 1.94193 2.6031 + vertex 0.993353 1.94196 2.60345 + endloop + endfacet + facet normal 0.0800451 0.199263 0.976671 + outer loop + vertex 0.998677 1.93764 2.60391 + vertex 0.997861 1.94193 2.6031 + vertex 0.994695 1.9386 2.60404 + endloop + endfacet + facet normal 0.0797585 0.198038 0.976944 + outer loop + vertex 0.994027 1.93429 2.60497 + vertex 0.998677 1.93764 2.60391 + vertex 0.994695 1.9386 2.60404 + endloop + endfacet + facet normal 0.0725567 0.199223 0.977264 + outer loop + vertex 0.989832 1.93745 2.60463 + vertex 0.994027 1.93429 2.60497 + vertex 0.994695 1.9386 2.60404 + endloop + endfacet + facet normal 0.0722413 0.198815 0.977371 + outer loop + vertex 0.989334 1.93327 2.60552 + vertex 0.994027 1.93429 2.60497 + vertex 0.989832 1.93745 2.60463 + endloop + endfacet + facet normal 0.0723936 0.198178 0.977489 + outer loop + vertex 0.989334 1.93327 2.60552 + vertex 0.99128 1.93077 2.60588 + vertex 0.994027 1.93429 2.60497 + endloop + endfacet + facet normal 0.0743112 0.196721 0.977639 + outer loop + vertex 0.995399 1.92971 2.60578 + vertex 0.994027 1.93429 2.60497 + vertex 0.99128 1.93077 2.60588 + endloop + endfacet + facet normal 0.0727505 0.19049 0.97899 + outer loop + vertex 0.99128 1.93077 2.60588 + vertex 0.991098 1.92639 2.60675 + vertex 0.995399 1.92971 2.60578 + endloop + endfacet + facet normal 0.0731816 0.189952 0.979062 + outer loop + vertex 0.996923 1.925 2.60658 + vertex 0.995399 1.92971 2.60578 + vertex 0.991098 1.92639 2.60675 + endloop + endfacet + facet normal 0.0726148 0.187518 0.979573 + outer loop + vertex 0.99251 1.92142 2.60759 + vertex 0.996923 1.925 2.60658 + vertex 0.991098 1.92639 2.60675 + endloop + endfacet + facet normal 0.0713808 0.187194 0.979726 + outer loop + vertex 0.99251 1.92142 2.60759 + vertex 0.991098 1.92639 2.60675 + vertex 0.98767 1.92168 2.6079 + endloop + endfacet + facet normal 0.0713741 0.187029 0.979758 + outer loop + vertex 0.988661 1.91725 2.60867 + vertex 0.99251 1.92142 2.60759 + vertex 0.98767 1.92168 2.6079 + endloop + endfacet + facet normal 0.0688787 0.186519 0.980034 + outer loop + vertex 0.988661 1.91725 2.60867 + vertex 0.98767 1.92168 2.6079 + vertex 0.983665 1.91735 2.609 + endloop + endfacet + facet normal 0.0688957 0.188864 0.979583 + outer loop + vertex 0.984931 1.91259 2.60983 + vertex 0.988661 1.91725 2.60867 + vertex 0.983665 1.91735 2.609 + endloop + endfacet + facet normal 0.0636059 0.187564 0.980191 + outer loop + vertex 0.984931 1.91259 2.60983 + vertex 0.983665 1.91735 2.609 + vertex 0.979354 1.91348 2.61002 + endloop + endfacet + facet normal 0.0639786 0.19 0.979697 + outer loop + vertex 0.979354 1.91348 2.61002 + vertex 0.980425 1.90928 2.61077 + vertex 0.984931 1.91259 2.60983 + endloop + endfacet + facet normal 0.0637687 0.190275 0.979658 + outer loop + vertex 0.980425 1.90928 2.61077 + vertex 0.984509 1.90844 2.61067 + vertex 0.984931 1.91259 2.60983 + endloop + endfacet + facet normal 0.0732157 0.189223 0.979201 + outer loop + vertex 0.984509 1.90844 2.61067 + vertex 0.989167 1.90935 2.61014 + vertex 0.984931 1.91259 2.60983 + endloop + endfacet + facet normal 0.071918 0.187565 0.979616 + outer loop + vertex 0.984931 1.91259 2.60983 + vertex 0.989167 1.90935 2.61014 + vertex 0.989884 1.91366 2.60926 + endloop + endfacet + facet normal 0.0761816 0.186819 0.979436 + outer loop + vertex 0.989167 1.90935 2.61014 + vertex 0.993911 1.91271 2.60913 + vertex 0.989884 1.91366 2.60926 + endloop + endfacet + facet normal 0.0757718 0.185037 0.979806 + outer loop + vertex 0.993911 1.91271 2.60913 + vertex 0.993286 1.91702 2.60837 + vertex 0.989884 1.91366 2.60926 + endloop + endfacet + facet normal 0.0739589 0.186816 0.979607 + outer loop + vertex 0.989884 1.91366 2.60926 + vertex 0.993286 1.91702 2.60837 + vertex 0.988661 1.91725 2.60867 + endloop + endfacet + facet normal 0.0756933 0.185027 0.979814 + outer loop + vertex 0.993911 1.91271 2.60913 + vertex 0.997825 1.91673 2.60807 + vertex 0.993286 1.91702 2.60837 + endloop + endfacet + facet normal 0.0756132 0.18347 0.980113 + outer loop + vertex 0.997825 1.91673 2.60807 + vertex 0.996531 1.92045 2.60747 + vertex 0.993286 1.91702 2.60837 + endloop + endfacet + facet normal 0.0741527 0.184817 0.979971 + outer loop + vertex 0.993286 1.91702 2.60837 + vertex 0.996531 1.92045 2.60747 + vertex 0.99251 1.92142 2.60759 + endloop + endfacet + facet normal 0.0757987 0.183531 0.980087 + outer loop + vertex 0.997825 1.91673 2.60807 + vertex 1.00127 1.92147 2.60692 + vertex 0.996531 1.92045 2.60747 + endloop + endfacet + facet normal 0.0753597 0.185397 0.97977 + outer loop + vertex 0.996923 1.925 2.60658 + vertex 0.996531 1.92045 2.60747 + vertex 1.00127 1.92147 2.60692 + endloop + endfacet + facet normal 0.0769406 0.187295 0.979286 + outer loop + vertex 1.00151 1.92595 2.60604 + vertex 0.996923 1.925 2.60658 + vertex 1.00127 1.92147 2.60692 + endloop + endfacet + facet normal 0.0791014 0.187151 0.979141 + outer loop + vertex 1.00151 1.92595 2.60604 + vertex 1.00127 1.92147 2.60692 + vertex 1.00562 1.92484 2.60592 + endloop + endfacet + facet normal 0.0815052 0.196231 0.977164 + outer loop + vertex 1.00562 1.92484 2.60592 + vertex 1.00421 1.92947 2.60511 + vertex 1.00151 1.92595 2.60604 + endloop + endfacet + facet normal 0.0830922 0.195039 0.977269 + outer loop + vertex 0.999515 1.92862 2.60568 + vertex 1.00151 1.92595 2.60604 + vertex 1.00421 1.92947 2.60511 + endloop + endfacet + facet normal 0.0823351 0.198759 0.976584 + outer loop + vertex 0.999515 1.92862 2.60568 + vertex 1.00421 1.92947 2.60511 + vertex 0.999885 1.93286 2.60478 + endloop + endfacet + facet normal 0.0842294 0.201117 0.975939 + outer loop + vertex 0.999885 1.93286 2.60478 + vertex 1.00421 1.92947 2.60511 + vertex 1.00476 1.93373 2.60418 + endloop + endfacet + facet normal 0.0842368 0.20108 0.975946 + outer loop + vertex 1.00476 1.93373 2.60418 + vertex 1.00336 1.93712 2.60361 + vertex 0.999885 1.93286 2.60478 + endloop + endfacet + facet normal 0.0850495 0.200436 0.976008 + outer loop + vertex 0.999885 1.93286 2.60478 + vertex 1.00336 1.93712 2.60361 + vertex 0.998677 1.93764 2.60391 + endloop + endfacet + facet normal 0.0850886 0.200841 0.975922 + outer loop + vertex 1.00336 1.93712 2.60361 + vertex 1.00245 1.94144 2.6028 + vertex 0.998677 1.93764 2.60391 + endloop + endfacet + facet normal 0.0857348 0.20022 0.975993 + outer loop + vertex 0.998677 1.93764 2.60391 + vertex 1.00245 1.94144 2.6028 + vertex 0.997861 1.94193 2.6031 + endloop + endfacet + facet normal 0.085802 0.200955 0.975836 + outer loop + vertex 1.00245 1.94144 2.6028 + vertex 1.00111 1.94635 2.6019 + vertex 0.997861 1.94193 2.6031 + endloop + endfacet + facet normal 0.089002 0.20175 0.975385 + outer loop + vertex 1.00245 1.94144 2.6028 + vertex 1.00681 1.94492 2.60168 + vertex 1.00111 1.94635 2.6019 + endloop + endfacet + facet normal 0.0879446 0.203021 0.975217 + outer loop + vertex 1.00643 1.94043 2.60265 + vertex 1.00681 1.94492 2.60168 + vertex 1.00245 1.94144 2.6028 + endloop + endfacet + facet normal 0.0859336 0.203225 0.975354 + outer loop + vertex 1.00681 1.94492 2.60168 + vertex 1.00643 1.94043 2.60265 + vertex 1.01118 1.94144 2.60202 + endloop + endfacet + facet normal 0.0865879 0.204023 0.975129 + outer loop + vertex 1.0114 1.9459 2.60106 + vertex 1.00681 1.94492 2.60168 + vertex 1.01118 1.94144 2.60202 + endloop + endfacet + facet normal 0.0853713 0.204103 0.97522 + outer loop + vertex 1.0114 1.9459 2.60106 + vertex 1.01118 1.94144 2.60202 + vertex 1.01558 1.94475 2.60094 + endloop + endfacet + facet normal 0.0922835 0.195284 0.976395 + outer loop + vertex 1.01712 1.93982 2.60178 + vertex 1.01558 1.94475 2.60094 + vertex 1.01118 1.94144 2.60202 + endloop + endfacet + facet normal 0.0945407 0.203857 0.974425 + outer loop + vertex 1.01261 1.93647 2.60292 + vertex 1.01712 1.93982 2.60178 + vertex 1.01118 1.94144 2.60202 + endloop + endfacet + facet normal 0.0867957 0.201838 0.975566 + outer loop + vertex 1.01261 1.93647 2.60292 + vertex 1.01118 1.94144 2.60202 + vertex 1.00789 1.93698 2.60323 + endloop + endfacet + facet normal 0.0868694 0.202623 0.975396 + outer loop + vertex 1.00881 1.93273 2.60403 + vertex 1.01261 1.93647 2.60292 + vertex 1.00789 1.93698 2.60323 + endloop + endfacet + facet normal 0.0857502 0.202409 0.97554 + outer loop + vertex 1.00881 1.93273 2.60403 + vertex 1.00789 1.93698 2.60323 + vertex 1.00476 1.93373 2.60418 + endloop + endfacet + facet normal 0.0893424 0.200193 0.975674 + outer loop + vertex 1.01353 1.93216 2.60372 + vertex 1.01261 1.93647 2.60292 + vertex 1.00881 1.93273 2.60403 + endloop + endfacet + facet normal 0.0855696 0.208266 0.974322 + outer loop + vertex 1.0114 1.9459 2.60106 + vertex 1.00946 1.94857 2.60067 + vertex 1.00681 1.94492 2.60168 + endloop + endfacet + facet normal 0.0861517 0.202301 0.975527 + outer loop + vertex 1.00789 1.93698 2.60323 + vertex 1.01118 1.94144 2.60202 + vertex 1.00643 1.94043 2.60265 + endloop + endfacet + facet normal 0.0863237 0.202369 0.975497 + outer loop + vertex 1.00789 1.93698 2.60323 + vertex 1.00643 1.94043 2.60265 + vertex 1.00336 1.93712 2.60361 + endloop + endfacet + facet normal 0.0875217 0.201293 0.975613 + outer loop + vertex 1.00336 1.93712 2.60361 + vertex 1.00643 1.94043 2.60265 + vertex 1.00245 1.94144 2.6028 + endloop + endfacet + facet normal 0.0863164 0.201882 0.975599 + outer loop + vertex 1.00476 1.93373 2.60418 + vertex 1.00789 1.93698 2.60323 + vertex 1.00336 1.93712 2.60361 + endloop + endfacet + facet normal 0.0854034 0.20095 0.975872 + outer loop + vertex 1.00421 1.92947 2.60511 + vertex 1.00881 1.93273 2.60403 + vertex 1.00476 1.93373 2.60418 + endloop + endfacet + facet normal 0.0859689 0.200189 0.975978 + outer loop + vertex 1.01008 1.928 2.60489 + vertex 1.00881 1.93273 2.60403 + vertex 1.00421 1.92947 2.60511 + endloop + endfacet + facet normal 0.0852626 0.197279 0.976633 + outer loop + vertex 1.00421 1.92947 2.60511 + vertex 1.00562 1.92484 2.60592 + vertex 1.01008 1.928 2.60489 + endloop + endfacet + facet normal 0.0835426 0.199601 0.976309 + outer loop + vertex 1.00562 1.92484 2.60592 + vertex 1.00969 1.92378 2.60579 + vertex 1.01008 1.928 2.60489 + endloop + endfacet + facet normal 0.0815339 0.191655 0.97807 + outer loop + vertex 1.00969 1.92378 2.60579 + vertex 1.00562 1.92484 2.60592 + vertex 1.00701 1.92009 2.60673 + endloop + endfacet + facet normal 0.0845658 0.189491 0.978234 + outer loop + vertex 1.01154 1.92113 2.60614 + vertex 1.00969 1.92378 2.60579 + vertex 1.00701 1.92009 2.60673 + endloop + endfacet + facet normal 0.0859621 0.183952 0.979169 + outer loop + vertex 1.01154 1.92113 2.60614 + vertex 1.00701 1.92009 2.60673 + vertex 1.0111 1.91666 2.60702 + endloop + endfacet + facet normal 0.0875671 0.185821 0.978674 + outer loop + vertex 1.00701 1.92009 2.60673 + vertex 1.00648 1.9155 2.60766 + vertex 1.0111 1.91666 2.60702 + endloop + endfacet + facet normal 0.0732912 0.187663 0.979495 + outer loop + vertex 1.00648 1.9155 2.60766 + vertex 1.00701 1.92009 2.60673 + vertex 1.00256 1.9164 2.60778 + endloop + endfacet + facet normal 0.0730649 0.186655 0.979705 + outer loop + vertex 1.00323 1.91207 2.60855 + vertex 1.00648 1.9155 2.60766 + vertex 1.00256 1.9164 2.60778 + endloop + endfacet + facet normal 0.071906 0.186498 0.97982 + outer loop + vertex 1.00323 1.91207 2.60855 + vertex 1.00256 1.9164 2.60778 + vertex 0.998721 1.91231 2.60884 + endloop + endfacet + facet normal 0.0719188 0.186803 0.979761 + outer loop + vertex 0.999861 1.90881 2.60942 + vertex 1.00323 1.91207 2.60855 + vertex 0.998721 1.91231 2.60884 + endloop + endfacet + facet normal 0.0739993 0.187434 0.979486 + outer loop + vertex 0.999861 1.90881 2.60942 + vertex 0.998721 1.91231 2.60884 + vertex 0.994988 1.90792 2.60996 + endloop + endfacet + facet normal 0.0742833 0.186035 0.979731 + outer loop + vertex 0.994988 1.90792 2.60996 + vertex 0.999119 1.90469 2.61026 + vertex 0.999861 1.90881 2.60942 + endloop + endfacet + facet normal 0.0726957 0.184048 0.980225 + outer loop + vertex 0.99457 1.90374 2.61077 + vertex 0.999119 1.90469 2.61026 + vertex 0.994988 1.90792 2.60996 + endloop + endfacet + facet normal 0.0768397 0.183588 0.979995 + outer loop + vertex 0.990559 1.90482 2.61089 + vertex 0.99457 1.90374 2.61077 + vertex 0.994988 1.90792 2.60996 + endloop + endfacet + facet normal 0.0762563 0.18439 0.97989 + outer loop + vertex 0.989167 1.90935 2.61014 + vertex 0.990559 1.90482 2.61089 + vertex 0.994988 1.90792 2.60996 + endloop + endfacet + facet normal 0.0772394 0.184671 0.979761 + outer loop + vertex 0.990559 1.90482 2.61089 + vertex 0.989167 1.90935 2.61014 + vertex 0.986504 1.90592 2.611 + endloop + endfacet + facet normal 0.0754304 0.177894 0.981154 + outer loop + vertex 0.986504 1.90592 2.611 + vertex 0.986351 1.90158 2.6118 + vertex 0.990559 1.90482 2.61089 + endloop + endfacet + facet normal 0.075868 0.177344 0.98122 + outer loop + vertex 0.992042 1.90016 2.61161 + vertex 0.990559 1.90482 2.61089 + vertex 0.986351 1.90158 2.6118 + endloop + endfacet + facet normal 0.0749861 0.173707 0.981938 + outer loop + vertex 0.987656 1.89653 2.61259 + vertex 0.992042 1.90016 2.61161 + vertex 0.986351 1.90158 2.6118 + endloop + endfacet + facet normal 0.0723144 0.173066 0.982252 + outer loop + vertex 0.987656 1.89653 2.61259 + vertex 0.986351 1.90158 2.6118 + vertex 0.982879 1.89681 2.61289 + endloop + endfacet + facet normal 0.0722897 0.172531 0.982348 + outer loop + vertex 0.983698 1.89226 2.61363 + vertex 0.987656 1.89653 2.61259 + vertex 0.982879 1.89681 2.61289 + endloop + endfacet + facet normal 0.0645817 0.171268 0.983106 + outer loop + vertex 0.983698 1.89226 2.61363 + vertex 0.982879 1.89681 2.61289 + vertex 0.978703 1.89227 2.61396 + endloop + endfacet + facet normal 0.064547 0.175163 0.982421 + outer loop + vertex 0.979796 1.88744 2.61475 + vertex 0.983698 1.89226 2.61363 + vertex 0.978703 1.89227 2.61396 + endloop + endfacet + facet normal 0.0553818 0.173234 0.983322 + outer loop + vertex 0.979796 1.88744 2.61475 + vertex 0.978703 1.89227 2.61396 + vertex 0.974267 1.88807 2.61495 + endloop + endfacet + facet normal 0.0559395 0.178427 0.982362 + outer loop + vertex 0.974267 1.88807 2.61495 + vertex 0.975239 1.88402 2.61563 + vertex 0.979796 1.88744 2.61475 + endloop + endfacet + facet normal 0.0562865 0.17798 0.982423 + outer loop + vertex 0.975239 1.88402 2.61563 + vertex 0.979267 1.8833 2.61553 + vertex 0.979796 1.88744 2.61475 + endloop + endfacet + facet normal 0.0704335 0.176066 0.981855 + outer loop + vertex 0.979267 1.8833 2.61553 + vertex 0.98392 1.88421 2.61503 + vertex 0.979796 1.88744 2.61475 + endloop + endfacet + facet normal 0.0691145 0.17442 0.982243 + outer loop + vertex 0.979796 1.88744 2.61475 + vertex 0.98392 1.88421 2.61503 + vertex 0.984764 1.88857 2.6142 + endloop + endfacet + facet normal 0.0766165 0.172914 0.981953 + outer loop + vertex 0.98392 1.88421 2.61503 + vertex 0.988751 1.88762 2.61405 + vertex 0.984764 1.88857 2.6142 + endloop + endfacet + facet normal 0.0761773 0.171024 0.982318 + outer loop + vertex 0.988751 1.88762 2.61405 + vertex 0.988279 1.89204 2.61332 + vertex 0.984764 1.88857 2.6142 + endloop + endfacet + facet normal 0.0749965 0.172194 0.982204 + outer loop + vertex 0.984764 1.88857 2.6142 + vertex 0.988279 1.89204 2.61332 + vertex 0.983698 1.89226 2.61363 + endloop + endfacet + facet normal 0.0760929 0.171016 0.982326 + outer loop + vertex 0.988751 1.88762 2.61405 + vertex 0.99279 1.89184 2.61301 + vertex 0.988279 1.89204 2.61332 + endloop + endfacet + facet normal 0.0760782 0.170556 0.982407 + outer loop + vertex 0.99279 1.89184 2.61301 + vertex 0.991594 1.89558 2.61245 + vertex 0.988279 1.89204 2.61332 + endloop + endfacet + facet normal 0.0763355 0.17032 0.982428 + outer loop + vertex 0.988279 1.89204 2.61332 + vertex 0.991594 1.89558 2.61245 + vertex 0.987656 1.89653 2.61259 + endloop + endfacet + facet normal 0.0732675 0.169711 0.982767 + outer loop + vertex 0.99279 1.89184 2.61301 + vertex 0.996252 1.89679 2.61189 + vertex 0.991594 1.89558 2.61245 + endloop + endfacet + facet normal 0.0725817 0.172177 0.982388 + outer loop + vertex 0.992042 1.90016 2.61161 + vertex 0.991594 1.89558 2.61245 + vertex 0.996252 1.89679 2.61189 + endloop + endfacet + facet normal 0.0741803 0.174132 0.981924 + outer loop + vertex 0.996511 1.90119 2.61109 + vertex 0.992042 1.90016 2.61161 + vertex 0.996252 1.89679 2.61189 + endloop + endfacet + facet normal 0.069582 0.174453 0.982204 + outer loop + vertex 0.996511 1.90119 2.61109 + vertex 0.996252 1.89679 2.61189 + vertex 1.00057 1.90031 2.61096 + endloop + endfacet + facet normal 0.0684548 0.175794 0.982044 + outer loop + vertex 1.00168 1.89588 2.61168 + vertex 1.00057 1.90031 2.61096 + vertex 0.996252 1.89679 2.61189 + endloop + endfacet + facet normal 0.0678253 0.171859 0.982784 + outer loop + vertex 0.997669 1.89177 2.61267 + vertex 1.00168 1.89588 2.61168 + vertex 0.996252 1.89679 2.61189 + endloop + endfacet + facet normal 0.0651212 0.174432 0.982513 + outer loop + vertex 1.00248 1.89128 2.61244 + vertex 1.00168 1.89588 2.61168 + vertex 0.997669 1.89177 2.61267 + endloop + endfacet + facet normal 0.065152 0.17477 0.982451 + outer loop + vertex 0.99841 1.88718 2.61344 + vertex 1.00248 1.89128 2.61244 + vertex 0.997669 1.89177 2.61267 + endloop + endfacet + facet normal 0.0659642 0.174889 0.982376 + outer loop + vertex 0.99841 1.88718 2.61344 + vertex 0.997669 1.89177 2.61267 + vertex 0.993632 1.88731 2.61374 + endloop + endfacet + facet normal 0.0659735 0.175499 0.982267 + outer loop + vertex 0.994764 1.88363 2.61432 + vertex 0.99841 1.88718 2.61344 + vertex 0.993632 1.88731 2.61374 + endloop + endfacet + facet normal 0.0710826 0.176971 0.981646 + outer loop + vertex 0.994764 1.88363 2.61432 + vertex 0.993632 1.88731 2.61374 + vertex 0.989744 1.88271 2.61485 + endloop + endfacet + facet normal 0.0709874 0.177448 0.981567 + outer loop + vertex 0.989744 1.88271 2.61485 + vertex 0.994033 1.87931 2.61515 + vertex 0.994764 1.88363 2.61432 + endloop + endfacet + facet normal 0.0685696 0.174463 0.982273 + outer loop + vertex 0.989351 1.87852 2.61562 + vertex 0.994033 1.87931 2.61515 + vertex 0.989744 1.88271 2.61485 + endloop + endfacet + facet normal 0.0746089 0.173834 0.981945 + outer loop + vertex 0.985313 1.8797 2.61572 + vertex 0.989351 1.87852 2.61562 + vertex 0.989744 1.88271 2.61485 + endloop + endfacet + facet normal 0.0752234 0.172961 0.982052 + outer loop + vertex 0.98392 1.88421 2.61503 + vertex 0.985313 1.8797 2.61572 + vertex 0.989744 1.88271 2.61485 + endloop + endfacet + facet normal 0.0744418 0.172735 0.982151 + outer loop + vertex 0.985313 1.8797 2.61572 + vertex 0.98392 1.88421 2.61503 + vertex 0.981262 1.88084 2.61582 + endloop + endfacet + facet normal 0.0721693 0.164522 0.98373 + outer loop + vertex 0.981262 1.88084 2.61582 + vertex 0.981267 1.87663 2.61653 + vertex 0.985313 1.8797 2.61572 + endloop + endfacet + facet normal 0.0710828 0.165913 0.983575 + outer loop + vertex 0.986973 1.87514 2.61637 + vertex 0.985313 1.8797 2.61572 + vertex 0.981267 1.87663 2.61653 + endloop + endfacet + facet normal 0.0694285 0.159459 0.98476 + outer loop + vertex 0.982655 1.8716 2.61725 + vertex 0.986973 1.87514 2.61637 + vertex 0.981267 1.87663 2.61653 + endloop + endfacet + facet normal 0.0637912 0.157991 0.985378 + outer loop + vertex 0.982655 1.8716 2.61725 + vertex 0.981267 1.87663 2.61653 + vertex 0.977868 1.87185 2.61751 + endloop + endfacet + facet normal 0.063673 0.155303 0.985813 + outer loop + vertex 0.9784 1.86705 2.61824 + vertex 0.982655 1.8716 2.61725 + vertex 0.977868 1.87185 2.61751 + endloop + endfacet + facet normal 0.0550508 0.154446 0.986466 + outer loop + vertex 0.9784 1.86705 2.61824 + vertex 0.977868 1.87185 2.61751 + vertex 0.973423 1.86707 2.61851 + endloop + endfacet + facet normal 0.0647895 0.154278 0.985901 + outer loop + vertex 0.983185 1.86688 2.61795 + vertex 0.982655 1.8716 2.61725 + vertex 0.9784 1.86705 2.61824 + endloop + endfacet + facet normal 0.0647952 0.154504 0.985865 + outer loop + vertex 0.978784 1.86229 2.61896 + vertex 0.983185 1.86688 2.61795 + vertex 0.9784 1.86705 2.61824 + endloop + endfacet + facet normal 0.0570748 0.153966 0.986426 + outer loop + vertex 0.978784 1.86229 2.61896 + vertex 0.9784 1.86705 2.61824 + vertex 0.973679 1.86224 2.61926 + endloop + endfacet + facet normal 0.0671931 0.152247 0.986056 + outer loop + vertex 0.983601 1.86228 2.61863 + vertex 0.983185 1.86688 2.61795 + vertex 0.978784 1.86229 2.61896 + endloop + endfacet + facet normal 0.06717 0.15501 0.985627 + outer loop + vertex 0.979692 1.85857 2.61948 + vertex 0.983601 1.86228 2.61863 + vertex 0.978784 1.86229 2.61896 + endloop + endfacet + facet normal 0.0612693 0.153654 0.986223 + outer loop + vertex 0.979692 1.85857 2.61948 + vertex 0.978784 1.86229 2.61896 + vertex 0.974663 1.85741 2.61997 + endloop + endfacet + facet normal 0.0687147 0.153415 0.98577 + outer loop + vertex 0.983795 1.85766 2.61934 + vertex 0.983601 1.86228 2.61863 + vertex 0.979692 1.85857 2.61948 + endloop + endfacet + facet normal 0.069049 0.154954 0.985506 + outer loop + vertex 0.978818 1.85424 2.62022 + vertex 0.983795 1.85766 2.61934 + vertex 0.979692 1.85857 2.61948 + endloop + endfacet + facet normal 0.0672998 0.15743 0.985234 + outer loop + vertex 0.984705 1.85277 2.62006 + vertex 0.983795 1.85766 2.61934 + vertex 0.978818 1.85424 2.62022 + endloop + endfacet + facet normal 0.0702928 0.153463 0.985651 + outer loop + vertex 0.983795 1.85766 2.61934 + vertex 0.988383 1.86201 2.61833 + vertex 0.983601 1.86228 2.61863 + endloop + endfacet + facet normal 0.0702496 0.152541 0.985797 + outer loop + vertex 0.988383 1.86201 2.61833 + vertex 0.987871 1.86679 2.61763 + vertex 0.983601 1.86228 2.61863 + endloop + endfacet + facet normal 0.066983 0.152231 0.986073 + outer loop + vertex 0.988383 1.86201 2.61833 + vertex 0.992701 1.8665 2.61735 + vertex 0.987871 1.86679 2.61763 + endloop + endfacet + facet normal 0.0671111 0.154785 0.985666 + outer loop + vertex 0.992701 1.8665 2.61735 + vertex 0.991369 1.87162 2.61663 + vertex 0.987871 1.86679 2.61763 + endloop + endfacet + facet normal 0.0693585 0.153178 0.985762 + outer loop + vertex 0.987871 1.86679 2.61763 + vertex 0.991369 1.87162 2.61663 + vertex 0.986672 1.87064 2.61712 + endloop + endfacet + facet normal 0.0703117 0.15346 0.98565 + outer loop + vertex 0.987871 1.86679 2.61763 + vertex 0.986672 1.87064 2.61712 + vertex 0.983185 1.86688 2.61795 + endloop + endfacet + facet normal 0.0680511 0.159006 0.98493 + outer loop + vertex 0.986973 1.87514 2.61637 + vertex 0.986672 1.87064 2.61712 + vertex 0.991369 1.87162 2.61663 + endloop + endfacet + facet normal 0.0702863 0.161758 0.984324 + outer loop + vertex 0.991408 1.87593 2.61592 + vertex 0.986973 1.87514 2.61637 + vertex 0.991369 1.87162 2.61663 + endloop + endfacet + facet normal 0.0634109 0.161893 0.984769 + outer loop + vertex 0.991408 1.87593 2.61592 + vertex 0.991369 1.87162 2.61663 + vertex 0.995566 1.87482 2.61584 + endloop + endfacet + facet normal 0.0643642 0.160676 0.984906 + outer loop + vertex 0.997185 1.87023 2.61648 + vertex 0.995566 1.87482 2.61584 + vertex 0.991369 1.87162 2.61663 + endloop + endfacet + facet normal 0.0689022 0.168866 0.983228 + outer loop + vertex 0.991408 1.87593 2.61592 + vertex 0.989351 1.87852 2.61562 + vertex 0.986973 1.87514 2.61637 + endloop + endfacet + facet normal 0.0627315 0.15371 0.986123 + outer loop + vertex 0.992701 1.8665 2.61735 + vertex 0.997185 1.87023 2.61648 + vertex 0.991369 1.87162 2.61663 + endloop + endfacet + facet normal 0.0646503 0.154431 0.985886 + outer loop + vertex 0.993152 1.86177 2.61806 + vertex 0.992701 1.8665 2.61735 + vertex 0.988383 1.86201 2.61833 + endloop + endfacet + facet normal 0.0682421 0.155581 0.985463 + outer loop + vertex 0.988761 1.8573 2.61905 + vertex 0.988383 1.86201 2.61833 + vertex 0.983795 1.85766 2.61934 + endloop + endfacet + facet normal 0.0703034 0.152491 0.985801 + outer loop + vertex 0.983601 1.86228 2.61863 + vertex 0.987871 1.86679 2.61763 + vertex 0.983185 1.86688 2.61795 + endloop + endfacet + facet normal 0.0689579 0.154695 0.985553 + outer loop + vertex 0.983185 1.86688 2.61795 + vertex 0.986672 1.87064 2.61712 + vertex 0.982655 1.8716 2.61725 + endloop + endfacet + facet normal 0.0628119 0.158678 0.98533 + outer loop + vertex 0.977868 1.87185 2.61751 + vertex 0.981267 1.87663 2.61653 + vertex 0.976675 1.87562 2.61698 + endloop + endfacet + facet normal 0.06993 0.158862 0.984821 + outer loop + vertex 0.986672 1.87064 2.61712 + vertex 0.986973 1.87514 2.61637 + vertex 0.982655 1.8716 2.61725 + endloop + endfacet + facet normal 0.0618303 0.164624 0.984417 + outer loop + vertex 0.981262 1.88084 2.61582 + vertex 0.976944 1.87985 2.61626 + vertex 0.981267 1.87663 2.61653 + endloop + endfacet + facet normal 0.0609342 0.168287 0.983853 + outer loop + vertex 0.981262 1.88084 2.61582 + vertex 0.979267 1.8833 2.61553 + vertex 0.976944 1.87985 2.61626 + endloop + endfacet + facet normal 0.0724757 0.166394 0.983392 + outer loop + vertex 0.989351 1.87852 2.61562 + vertex 0.985313 1.8797 2.61572 + vertex 0.986973 1.87514 2.61637 + endloop + endfacet + facet normal 0.069515 0.169339 0.983103 + outer loop + vertex 0.989351 1.87852 2.61562 + vertex 0.991408 1.87593 2.61592 + vertex 0.994033 1.87931 2.61515 + endloop + endfacet + facet normal 0.0744933 0.174147 0.981898 + outer loop + vertex 0.989744 1.88271 2.61485 + vertex 0.993632 1.88731 2.61374 + vertex 0.988751 1.88762 2.61405 + endloop + endfacet + facet normal 0.0636284 0.177838 0.982001 + outer loop + vertex 0.998863 1.88272 2.61422 + vertex 0.99841 1.88718 2.61344 + vertex 0.994764 1.88363 2.61432 + endloop + endfacet + facet normal 0.0695027 0.171758 0.982684 + outer loop + vertex 0.993632 1.88731 2.61374 + vertex 0.997669 1.89177 2.61267 + vertex 0.99279 1.89184 2.61301 + endloop + endfacet + facet normal 0.065675 0.174265 0.982506 + outer loop + vertex 1.00296 1.88682 2.6132 + vertex 1.00248 1.89128 2.61244 + vertex 0.99841 1.88718 2.61344 + endloop + endfacet + facet normal 0.079923 0.176737 0.981008 + outer loop + vertex 1.00248 1.89128 2.61244 + vertex 1.00688 1.89482 2.61145 + vertex 1.00168 1.89588 2.61168 + endloop + endfacet + facet normal 0.079243 0.173263 0.981683 + outer loop + vertex 1.00688 1.89482 2.61145 + vertex 1.00552 1.89934 2.61076 + vertex 1.00168 1.89588 2.61168 + endloop + endfacet + facet normal 0.0730768 0.178567 0.98121 + outer loop + vertex 0.996511 1.90119 2.61109 + vertex 0.99457 1.90374 2.61077 + vertex 0.992042 1.90016 2.61161 + endloop + endfacet + facet normal 0.0695042 0.172302 0.982589 + outer loop + vertex 0.997669 1.89177 2.61267 + vertex 0.996252 1.89679 2.61189 + vertex 0.99279 1.89184 2.61301 + endloop + endfacet + facet normal 0.0744118 0.17259 0.982179 + outer loop + vertex 0.993632 1.88731 2.61374 + vertex 0.99279 1.89184 2.61301 + vertex 0.988751 1.88762 2.61405 + endloop + endfacet + facet normal 0.0755697 0.174345 0.98178 + outer loop + vertex 0.989744 1.88271 2.61485 + vertex 0.988751 1.88762 2.61405 + vertex 0.98392 1.88421 2.61503 + endloop + endfacet + facet normal 0.0704906 0.175797 0.981899 + outer loop + vertex 0.979267 1.8833 2.61553 + vertex 0.981262 1.88084 2.61582 + vertex 0.98392 1.88421 2.61503 + endloop + endfacet + facet normal 0.0699942 0.170838 0.98281 + outer loop + vertex 0.984764 1.88857 2.6142 + vertex 0.983698 1.89226 2.61363 + vertex 0.979796 1.88744 2.61475 + endloop + endfacet + facet normal 0.0610194 0.174468 0.98277 + outer loop + vertex 0.978703 1.89227 2.61396 + vertex 0.982879 1.89681 2.61289 + vertex 0.978127 1.89682 2.61319 + endloop + endfacet + facet normal 0.051834 0.173428 0.983482 + outer loop + vertex 0.978703 1.89227 2.61396 + vertex 0.978127 1.89682 2.61319 + vertex 0.973608 1.8924 2.6142 + endloop + endfacet + facet normal 0.0610339 0.172487 0.983119 + outer loop + vertex 0.982879 1.89681 2.61289 + vertex 0.98166 1.90053 2.61232 + vertex 0.978127 1.89682 2.61319 + endloop + endfacet + facet normal 0.0564794 0.176717 0.98264 + outer loop + vertex 0.978127 1.89682 2.61319 + vertex 0.98166 1.90053 2.61232 + vertex 0.977668 1.90135 2.6124 + endloop + endfacet + facet normal 0.0493943 0.176084 0.983135 + outer loop + vertex 0.978127 1.89682 2.61319 + vertex 0.977668 1.90135 2.6124 + vertex 0.973287 1.897 2.6134 + endloop + endfacet + facet normal 0.0571365 0.179986 0.982008 + outer loop + vertex 0.98166 1.90053 2.61232 + vertex 0.982087 1.90491 2.61149 + vertex 0.977668 1.90135 2.6124 + endloop + endfacet + facet normal 0.0563808 0.18089 0.981886 + outer loop + vertex 0.977668 1.90135 2.6124 + vertex 0.982087 1.90491 2.61149 + vertex 0.976735 1.90587 2.61162 + endloop + endfacet + facet normal 0.0485786 0.179399 0.982576 + outer loop + vertex 0.977668 1.90135 2.6124 + vertex 0.976735 1.90587 2.61162 + vertex 0.972742 1.90176 2.61257 + endloop + endfacet + facet normal 0.0477585 0.180173 0.982475 + outer loop + vertex 0.972742 1.90176 2.61257 + vertex 0.976735 1.90587 2.61162 + vertex 0.971249 1.90667 2.61174 + endloop + endfacet + facet normal 0.0567852 0.183219 0.981431 + outer loop + vertex 0.982087 1.90491 2.61149 + vertex 0.980425 1.90928 2.61077 + vertex 0.976735 1.90587 2.61162 + endloop + endfacet + facet normal 0.0551866 0.184895 0.981208 + outer loop + vertex 0.980425 1.90928 2.61077 + vertex 0.975441 1.91012 2.61089 + vertex 0.976735 1.90587 2.61162 + endloop + endfacet + facet normal 0.0685815 0.178775 0.981497 + outer loop + vertex 0.982087 1.90491 2.61149 + vertex 0.98166 1.90053 2.61232 + vertex 0.986351 1.90158 2.6118 + endloop + endfacet + facet normal 0.0749233 0.170147 0.982566 + outer loop + vertex 0.988279 1.89204 2.61332 + vertex 0.987656 1.89653 2.61259 + vertex 0.983698 1.89226 2.61363 + endloop + endfacet + facet normal 0.0694747 0.175095 0.982097 + outer loop + vertex 0.982879 1.89681 2.61289 + vertex 0.986351 1.90158 2.6118 + vertex 0.98166 1.90053 2.61232 + endloop + endfacet + facet normal 0.076668 0.171735 0.982155 + outer loop + vertex 0.991594 1.89558 2.61245 + vertex 0.992042 1.90016 2.61161 + vertex 0.987656 1.89653 2.61259 + endloop + endfacet + facet normal 0.068151 0.178236 0.981625 + outer loop + vertex 0.986504 1.90592 2.611 + vertex 0.982087 1.90491 2.61149 + vertex 0.986351 1.90158 2.6118 + endloop + endfacet + facet normal 0.0671035 0.182476 0.980918 + outer loop + vertex 0.986504 1.90592 2.611 + vertex 0.984509 1.90844 2.61067 + vertex 0.982087 1.90491 2.61149 + endloop + endfacet + facet normal 0.075147 0.177129 0.981315 + outer loop + vertex 0.99457 1.90374 2.61077 + vertex 0.990559 1.90482 2.61089 + vertex 0.992042 1.90016 2.61161 + endloop + endfacet + facet normal 0.0738203 0.179113 0.981055 + outer loop + vertex 0.99457 1.90374 2.61077 + vertex 0.996511 1.90119 2.61109 + vertex 0.999119 1.90469 2.61026 + endloop + endfacet + facet normal 0.075776 0.185962 0.979631 + outer loop + vertex 0.994988 1.90792 2.60996 + vertex 0.998721 1.91231 2.60884 + vertex 0.993911 1.91271 2.60913 + endloop + endfacet + facet normal 0.0715837 0.187139 0.979722 + outer loop + vertex 1.00376 1.90796 2.6093 + vertex 1.00323 1.91207 2.60855 + vertex 0.999861 1.90881 2.60942 + endloop + endfacet + facet normal 0.0738962 0.184679 0.980017 + outer loop + vertex 0.998721 1.91231 2.60884 + vertex 1.00256 1.9164 2.60778 + vertex 0.997825 1.91673 2.60807 + endloop + endfacet + facet normal 0.0757985 0.184137 0.979974 + outer loop + vertex 1.0077 1.91188 2.60824 + vertex 1.00648 1.9155 2.60766 + vertex 1.00323 1.91207 2.60855 + endloop + endfacet + facet normal 0.0753833 0.185225 0.9798 + outer loop + vertex 1.00256 1.9164 2.60778 + vertex 1.00701 1.92009 2.60673 + vertex 1.00127 1.92147 2.60692 + endloop + endfacet + facet normal 0.102563 0.201546 0.974094 + outer loop + vertex 1.00969 1.92378 2.60579 + vertex 1.01154 1.92113 2.60614 + vertex 1.01426 1.9246 2.60514 + endloop + endfacet + facet normal 0.0765671 0.190308 0.978734 + outer loop + vertex 1.00701 1.92009 2.60673 + vertex 1.00562 1.92484 2.60592 + vertex 1.00127 1.92147 2.60692 + endloop + endfacet + facet normal 0.0762889 0.190165 0.978784 + outer loop + vertex 1.00151 1.92595 2.60604 + vertex 0.999515 1.92862 2.60568 + vertex 0.996923 1.925 2.60658 + endloop + endfacet + facet normal 0.0739078 0.184879 0.979978 + outer loop + vertex 1.00256 1.9164 2.60778 + vertex 1.00127 1.92147 2.60692 + vertex 0.997825 1.91673 2.60807 + endloop + endfacet + facet normal 0.0757098 0.185011 0.979816 + outer loop + vertex 0.998721 1.91231 2.60884 + vertex 0.997825 1.91673 2.60807 + vertex 0.993911 1.91271 2.60913 + endloop + endfacet + facet normal 0.0766765 0.186147 0.979525 + outer loop + vertex 0.994988 1.90792 2.60996 + vertex 0.993911 1.91271 2.60913 + vertex 0.989167 1.90935 2.61014 + endloop + endfacet + facet normal 0.0735993 0.18744 0.979515 + outer loop + vertex 0.984509 1.90844 2.61067 + vertex 0.986504 1.90592 2.611 + vertex 0.989167 1.90935 2.61014 + endloop + endfacet + facet normal 0.0627904 0.185379 0.980659 + outer loop + vertex 0.984509 1.90844 2.61067 + vertex 0.980425 1.90928 2.61077 + vertex 0.982087 1.90491 2.61149 + endloop + endfacet + facet normal 0.0722253 0.186264 0.979841 + outer loop + vertex 0.989884 1.91366 2.60926 + vertex 0.988661 1.91725 2.60867 + vertex 0.984931 1.91259 2.60983 + endloop + endfacet + facet normal 0.0670274 0.188184 0.979844 + outer loop + vertex 0.983665 1.91735 2.609 + vertex 0.98767 1.92168 2.6079 + vertex 0.982971 1.92177 2.6082 + endloop + endfacet + facet normal 0.0627309 0.187582 0.980244 + outer loop + vertex 0.983665 1.91735 2.609 + vertex 0.982971 1.92177 2.6082 + vertex 0.978747 1.91781 2.60923 + endloop + endfacet + facet normal 0.0619003 0.18844 0.980132 + outer loop + vertex 0.978747 1.91781 2.60923 + vertex 0.982971 1.92177 2.6082 + vertex 0.978416 1.92214 2.60842 + endloop + endfacet + facet normal 0.061942 0.18903 0.980016 + outer loop + vertex 0.982971 1.92177 2.6082 + vertex 0.982454 1.92612 2.6074 + vertex 0.978416 1.92214 2.60842 + endloop + endfacet + facet normal 0.0603426 0.190598 0.979812 + outer loop + vertex 0.978416 1.92214 2.60842 + vertex 0.982454 1.92612 2.6074 + vertex 0.977691 1.92653 2.60761 + endloop + endfacet + facet normal 0.0544661 0.189725 0.980325 + outer loop + vertex 0.978416 1.92214 2.60842 + vertex 0.977691 1.92653 2.60761 + vertex 0.973663 1.92218 2.60868 + endloop + endfacet + facet normal 0.0604571 0.192069 0.979518 + outer loop + vertex 0.982454 1.92612 2.6074 + vertex 0.98161 1.93046 2.6066 + vertex 0.977691 1.92653 2.60761 + endloop + endfacet + facet normal 0.059336 0.19315 0.979373 + outer loop + vertex 0.977691 1.92653 2.60761 + vertex 0.98161 1.93046 2.6066 + vertex 0.976616 1.93101 2.60679 + endloop + endfacet + facet normal 0.0537421 0.191911 0.97994 + outer loop + vertex 0.977691 1.92653 2.60761 + vertex 0.976616 1.93101 2.60679 + vertex 0.972727 1.92679 2.60783 + endloop + endfacet + facet normal 0.0595496 0.195235 0.978947 + outer loop + vertex 0.98161 1.93046 2.6066 + vertex 0.980397 1.93463 2.60584 + vertex 0.976616 1.93101 2.60679 + endloop + endfacet + facet normal 0.0583874 0.196407 0.978783 + outer loop + vertex 0.980397 1.93463 2.60584 + vertex 0.9755 1.93527 2.606 + vertex 0.976616 1.93101 2.60679 + endloop + endfacet + facet normal 0.0645335 0.192787 0.979116 + outer loop + vertex 0.982454 1.92612 2.6074 + vertex 0.986823 1.92964 2.60641 + vertex 0.98161 1.93046 2.6066 + endloop + endfacet + facet normal 0.0648407 0.194828 0.978692 + outer loop + vertex 0.986823 1.92964 2.60641 + vertex 0.985309 1.93399 2.60565 + vertex 0.98161 1.93046 2.6066 + endloop + endfacet + facet normal 0.0663695 0.195325 0.97849 + outer loop + vertex 0.989334 1.93327 2.60552 + vertex 0.985309 1.93399 2.60565 + vertex 0.986823 1.92964 2.60641 + endloop + endfacet + facet normal 0.0655958 0.191519 0.979295 + outer loop + vertex 0.986365 1.9253 2.60729 + vertex 0.986823 1.92964 2.60641 + vertex 0.982454 1.92612 2.6074 + endloop + endfacet + facet normal 0.068903 0.191138 0.979142 + outer loop + vertex 0.986823 1.92964 2.60641 + vertex 0.986365 1.9253 2.60729 + vertex 0.991098 1.92639 2.60675 + endloop + endfacet + facet normal 0.0651564 0.189361 0.979743 + outer loop + vertex 0.982971 1.92177 2.6082 + vertex 0.986365 1.9253 2.60729 + vertex 0.982454 1.92612 2.6074 + endloop + endfacet + facet normal 0.0670234 0.187622 0.979952 + outer loop + vertex 0.98767 1.92168 2.6079 + vertex 0.986365 1.9253 2.60729 + vertex 0.982971 1.92177 2.6082 + endloop + endfacet + facet normal 0.0738853 0.184775 0.98 + outer loop + vertex 0.993286 1.91702 2.60837 + vertex 0.99251 1.92142 2.60759 + vertex 0.988661 1.91725 2.60867 + endloop + endfacet + facet normal 0.0695698 0.188482 0.979609 + outer loop + vertex 0.98767 1.92168 2.6079 + vertex 0.991098 1.92639 2.60675 + vertex 0.986365 1.9253 2.60729 + endloop + endfacet + facet normal 0.0743131 0.185499 0.97983 + outer loop + vertex 0.996531 1.92045 2.60747 + vertex 0.996923 1.925 2.60658 + vertex 0.99251 1.92142 2.60759 + endloop + endfacet + facet normal 0.07557 0.19067 0.978741 + outer loop + vertex 0.999515 1.92862 2.60568 + vertex 0.995399 1.92971 2.60578 + vertex 0.996923 1.925 2.60658 + endloop + endfacet + facet normal 0.0777983 0.199213 0.976863 + outer loop + vertex 0.995399 1.92971 2.60578 + vertex 0.999515 1.92862 2.60568 + vertex 0.999885 1.93286 2.60478 + endloop + endfacet + facet normal 0.0685729 0.190714 0.979248 + outer loop + vertex 0.99128 1.93077 2.60588 + vertex 0.986823 1.92964 2.60641 + vertex 0.991098 1.92639 2.60675 + endloop + endfacet + facet normal 0.0787311 0.197941 0.977047 + outer loop + vertex 0.994027 1.93429 2.60497 + vertex 0.995399 1.92971 2.60578 + vertex 0.999885 1.93286 2.60478 + endloop + endfacet + facet normal 0.0675223 0.194546 0.978567 + outer loop + vertex 0.99128 1.93077 2.60588 + vertex 0.989334 1.93327 2.60552 + vertex 0.986823 1.92964 2.60641 + endloop + endfacet + facet normal 0.0789948 0.199052 0.9768 + outer loop + vertex 0.999885 1.93286 2.60478 + vertex 0.998677 1.93764 2.60391 + vertex 0.994027 1.93429 2.60497 + endloop + endfacet + facet normal 0.0852745 0.201333 0.975804 + outer loop + vertex 0.997861 1.94193 2.6031 + vertex 1.00111 1.94635 2.6019 + vertex 0.996463 1.94534 2.60252 + endloop + endfacet + facet normal 0.0726725 0.198776 0.977347 + outer loop + vertex 0.994695 1.9386 2.60404 + vertex 0.993353 1.94196 2.60345 + vertex 0.989832 1.93745 2.60463 + endloop + endfacet + facet normal 0.0670833 0.19948 0.977603 + outer loop + vertex 0.985309 1.93399 2.60565 + vertex 0.989334 1.93327 2.60552 + vertex 0.989832 1.93745 2.60463 + endloop + endfacet + facet normal 0.06341 0.196276 0.978496 + outer loop + vertex 0.985309 1.93399 2.60565 + vertex 0.980397 1.93463 2.60584 + vertex 0.98161 1.93046 2.6066 + endloop + endfacet + facet normal 0.0586728 0.198706 0.978301 + outer loop + vertex 0.9755 1.93527 2.606 + vertex 0.980397 1.93463 2.60584 + vertex 0.979329 1.93872 2.60507 + endloop + endfacet + facet normal 0.0663211 0.19997 0.977555 + outer loop + vertex 0.984374 1.93817 2.60486 + vertex 0.988535 1.94215 2.60377 + vertex 0.983533 1.94249 2.60403 + endloop + endfacet + facet normal 0.0620214 0.199278 0.977978 + outer loop + vertex 0.978757 1.94287 2.60426 + vertex 0.982735 1.94681 2.60321 + vertex 0.978279 1.94694 2.60346 + endloop + endfacet + facet normal 0.0662905 0.199437 0.977666 + outer loop + vertex 0.988535 1.94215 2.60377 + vertex 0.987611 1.94671 2.6029 + vertex 0.983533 1.94249 2.60403 + endloop + endfacet + facet normal 0.0655848 0.199693 0.977661 + outer loop + vertex 0.982735 1.94681 2.60321 + vertex 0.986165 1.95157 2.602 + vertex 0.981509 1.95032 2.60257 + endloop + endfacet + facet normal 0.0703345 0.200292 0.977208 + outer loop + vertex 0.99252 1.9462 2.60265 + vertex 0.991599 1.9507 2.60179 + vertex 0.987611 1.94671 2.6029 + endloop + endfacet + facet normal 0.0763606 0.202187 0.976365 + outer loop + vertex 0.995421 1.95419 2.60077 + vertex 0.99051 1.95512 2.60096 + vertex 0.991599 1.9507 2.60179 + endloop + endfacet + facet normal 0.0657862 0.200509 0.977481 + outer loop + vertex 0.986449 1.95592 2.60109 + vertex 0.981985 1.95471 2.60164 + vertex 0.986165 1.95157 2.602 + endloop + endfacet + facet normal 0.0654533 0.201646 0.977269 + outer loop + vertex 0.986449 1.95592 2.60109 + vertex 0.984525 1.95838 2.60071 + vertex 0.981985 1.95471 2.60164 + endloop + endfacet + facet normal 0.0689604 0.204268 0.976483 + outer loop + vertex 0.984525 1.95838 2.60071 + vertex 0.986449 1.95592 2.60109 + vertex 0.989105 1.95951 2.60015 + endloop + endfacet + facet normal 0.0638269 0.202743 0.97715 + outer loop + vertex 0.984525 1.95838 2.60071 + vertex 0.980452 1.95917 2.60082 + vertex 0.981985 1.95471 2.60164 + endloop + endfacet + facet normal 0.0615466 0.207377 0.976323 + outer loop + vertex 0.975488 1.9601 2.60093 + vertex 0.980452 1.95917 2.60082 + vertex 0.979431 1.96346 2.59997 + endloop + endfacet + facet normal 0.0643314 0.208933 0.975812 + outer loop + vertex 0.984962 1.96253 2.59981 + vertex 0.988441 1.96693 2.59864 + vertex 0.983608 1.96719 2.5989 + endloop + endfacet + facet normal 0.0635657 0.210698 0.975482 + outer loop + vertex 0.983608 1.96719 2.5989 + vertex 0.987569 1.97111 2.59779 + vertex 0.982647 1.97172 2.59798 + endloop + endfacet + facet normal 0.0641954 0.210334 0.97552 + outer loop + vertex 0.982647 1.97172 2.59798 + vertex 0.986602 1.97561 2.59688 + vertex 0.981102 1.97655 2.59704 + endloop + endfacet + facet normal 0.064061 0.209524 0.975703 + outer loop + vertex 0.986602 1.97561 2.59688 + vertex 0.985452 1.98003 2.59601 + vertex 0.981102 1.97655 2.59704 + endloop + endfacet + facet normal 0.0650172 0.208381 0.975884 + outer loop + vertex 0.981308 1.98086 2.59611 + vertex 0.981102 1.97655 2.59704 + vertex 0.985452 1.98003 2.59601 + endloop + endfacet + facet normal 0.0627473 0.208515 0.976004 + outer loop + vertex 0.981308 1.98086 2.59611 + vertex 0.976849 1.97969 2.59665 + vertex 0.981102 1.97655 2.59704 + endloop + endfacet + facet normal 0.0628235 0.208616 0.975978 + outer loop + vertex 0.976849 1.97969 2.59665 + vertex 0.97649 1.9754 2.59758 + vertex 0.981102 1.97655 2.59704 + endloop + endfacet + facet normal 0.0537432 0.209455 0.97634 + outer loop + vertex 0.97649 1.9754 2.59758 + vertex 0.976849 1.97969 2.59665 + vertex 0.972552 1.97621 2.59763 + endloop + endfacet + facet normal 0.0592067 0.20988 0.975933 + outer loop + vertex 0.978688 1.96782 2.59908 + vertex 0.977917 1.97202 2.59822 + vertex 0.974777 1.96865 2.59914 + endloop + endfacet + facet normal 0.0592197 0.209943 0.975919 + outer loop + vertex 0.974066 1.96445 2.60008 + vertex 0.978688 1.96782 2.59908 + vertex 0.974777 1.96865 2.59914 + endloop + endfacet + facet normal 0.0594363 0.209745 0.975948 + outer loop + vertex 0.974066 1.96445 2.60008 + vertex 0.975488 1.9601 2.60093 + vertex 0.979431 1.96346 2.59997 + endloop + endfacet + facet normal 0.056265 0.202582 0.977648 + outer loop + vertex 0.976661 1.95571 2.60177 + vertex 0.975488 1.9601 2.60093 + vertex 0.971211 1.95666 2.60189 + endloop + endfacet + facet normal 0.0414466 0.206259 0.977619 + outer loop + vertex 0.971423 1.9609 2.60099 + vertex 0.969526 1.96325 2.60058 + vertex 0.967046 1.95964 2.60145 + endloop + endfacet + facet normal 0.0455971 0.201524 0.978422 + outer loop + vertex 0.967821 1.95188 2.60303 + vertex 0.971211 1.95666 2.60189 + vertex 0.966569 1.95547 2.60235 + endloop + endfacet + facet normal 0.0492858 0.196945 0.979175 + outer loop + vertex 0.968742 1.94728 2.60391 + vertex 0.972749 1.95174 2.60281 + vertex 0.967821 1.95188 2.60303 + endloop + endfacet + facet normal 0.049632 0.198207 0.978903 + outer loop + vertex 0.970013 1.94246 2.60482 + vertex 0.97374 1.94716 2.60368 + vertex 0.968742 1.94728 2.60391 + endloop + endfacet + facet normal 0.0500263 0.200349 0.978447 + outer loop + vertex 0.970013 1.94246 2.60482 + vertex 0.974093 1.93949 2.60522 + vertex 0.974901 1.94364 2.60433 + endloop + endfacet + facet normal 0.0573381 0.200133 0.97809 + outer loop + vertex 0.974093 1.93949 2.60522 + vertex 0.9755 1.93527 2.606 + vertex 0.979329 1.93872 2.60507 + endloop + endfacet + facet normal 0.0523951 0.194953 0.979412 + outer loop + vertex 0.976616 1.93101 2.60679 + vertex 0.9755 1.93527 2.606 + vertex 0.971253 1.93171 2.60694 + endloop + endfacet + facet normal 0.0434258 0.196829 0.979476 + outer loop + vertex 0.971481 1.93596 2.60608 + vertex 0.969539 1.93832 2.60569 + vertex 0.967071 1.93475 2.60652 + endloop + endfacet + facet normal 0.0521886 0.193295 0.979752 + outer loop + vertex 0.972727 1.92679 2.60783 + vertex 0.976616 1.93101 2.60679 + vertex 0.971253 1.93171 2.60694 + endloop + endfacet + facet normal 0.0536783 0.190431 0.980232 + outer loop + vertex 0.973663 1.92218 2.60868 + vertex 0.977691 1.92653 2.60761 + vertex 0.972727 1.92679 2.60783 + endloop + endfacet + facet normal 0.0544658 0.189976 0.980277 + outer loop + vertex 0.974778 1.91859 2.60931 + vertex 0.978416 1.92214 2.60842 + vertex 0.973663 1.92218 2.60868 + endloop + endfacet + facet normal 0.0467522 0.187662 0.98112 + outer loop + vertex 0.969319 1.91317 2.61061 + vertex 0.973924 1.91436 2.61016 + vertex 0.969821 1.91731 2.60979 + endloop + endfacet + facet normal 0.0563642 0.188091 0.980533 + outer loop + vertex 0.978747 1.91781 2.60923 + vertex 0.978416 1.92214 2.60842 + vertex 0.974778 1.91859 2.60931 + endloop + endfacet + facet normal 0.0628032 0.188428 0.980077 + outer loop + vertex 0.979354 1.91348 2.61002 + vertex 0.983665 1.91735 2.609 + vertex 0.978747 1.91781 2.60923 + endloop + endfacet + facet normal 0.0557075 0.188048 0.980579 + outer loop + vertex 0.975441 1.91012 2.61089 + vertex 0.980425 1.90928 2.61077 + vertex 0.979354 1.91348 2.61002 + endloop + endfacet + facet normal 0.0481443 0.182882 0.981955 + outer loop + vertex 0.976735 1.90587 2.61162 + vertex 0.975441 1.91012 2.61089 + vertex 0.971249 1.90667 2.61174 + endloop + endfacet + facet normal 0.0433539 0.183775 0.982012 + outer loop + vertex 0.966961 1.90967 2.61137 + vertex 0.966639 1.90544 2.61217 + vertex 0.971249 1.90667 2.61174 + endloop + endfacet + facet normal 0.0447532 0.178845 0.982859 + outer loop + vertex 0.967855 1.90177 2.61279 + vertex 0.971249 1.90667 2.61174 + vertex 0.966639 1.90544 2.61217 + endloop + endfacet + facet normal 0.0384612 0.184171 0.982141 + outer loop + vertex 0.966639 1.90544 2.61217 + vertex 0.966961 1.90967 2.61137 + vertex 0.962684 1.90622 2.61218 + endloop + endfacet + facet normal 0.0466084 0.188186 0.981027 + outer loop + vertex 0.969319 1.91317 2.61061 + vertex 0.971324 1.91085 2.61096 + vertex 0.973924 1.91436 2.61016 + endloop + endfacet + facet normal 0.038435 0.188703 0.981282 + outer loop + vertex 0.965301 1.91381 2.61064 + vertex 0.969319 1.91317 2.61061 + vertex 0.969821 1.91731 2.60979 + endloop + endfacet + facet normal 0.0391648 0.187797 0.981427 + outer loop + vertex 0.96436 1.91792 2.60989 + vertex 0.965301 1.91381 2.61064 + vertex 0.969821 1.91731 2.60979 + endloop + endfacet + facet normal 0.0390413 0.186656 0.981649 + outer loop + vertex 0.969821 1.91731 2.60979 + vertex 0.968645 1.92215 2.60892 + vertex 0.96436 1.91792 2.60989 + endloop + endfacet + facet normal 0.0391745 0.186526 0.981669 + outer loop + vertex 0.96436 1.91792 2.60989 + vertex 0.968645 1.92215 2.60892 + vertex 0.963677 1.92237 2.60908 + endloop + endfacet + facet normal 0.0392117 0.18753 0.981476 + outer loop + vertex 0.968645 1.92215 2.60892 + vertex 0.967833 1.92681 2.60806 + vertex 0.963677 1.92237 2.60908 + endloop + endfacet + facet normal 0.0383371 0.188322 0.981359 + outer loop + vertex 0.963677 1.92237 2.60908 + vertex 0.967833 1.92681 2.60806 + vertex 0.963186 1.92688 2.60823 + endloop + endfacet + facet normal 0.0383496 0.189973 0.98104 + outer loop + vertex 0.967833 1.92681 2.60806 + vertex 0.966636 1.93048 2.6074 + vertex 0.963186 1.92688 2.60823 + endloop + endfacet + facet normal 0.0330378 0.194875 0.980271 + outer loop + vertex 0.963186 1.92688 2.60823 + vertex 0.966636 1.93048 2.6074 + vertex 0.962699 1.93128 2.60737 + endloop + endfacet + facet normal 0.0337175 0.198237 0.979574 + outer loop + vertex 0.966636 1.93048 2.6074 + vertex 0.967071 1.93475 2.60652 + vertex 0.962699 1.93128 2.60737 + endloop + endfacet + facet normal 0.0350821 0.188208 0.981503 + outer loop + vertex 0.962684 1.90622 2.61218 + vertex 0.966961 1.90967 2.61137 + vertex 0.9617 1.91042 2.61141 + endloop + endfacet + facet normal 0.0378734 0.181195 0.982718 + outer loop + vertex 0.963239 1.90176 2.61298 + vertex 0.966639 1.90544 2.61217 + vertex 0.962684 1.90622 2.61218 + endloop + endfacet + facet normal 0.0415961 0.177853 0.983178 + outer loop + vertex 0.967855 1.90177 2.61279 + vertex 0.966639 1.90544 2.61217 + vertex 0.963239 1.90176 2.61298 + endloop + endfacet + facet normal 0.0442694 0.179172 0.982821 + outer loop + vertex 0.972742 1.90176 2.61257 + vertex 0.971249 1.90667 2.61174 + vertex 0.967855 1.90177 2.61279 + endloop + endfacet + facet normal 0.0483958 0.177061 0.983009 + outer loop + vertex 0.973287 1.897 2.6134 + vertex 0.977668 1.90135 2.6124 + vertex 0.972742 1.90176 2.61257 + endloop + endfacet + facet normal 0.049388 0.175858 0.983176 + outer loop + vertex 0.973608 1.8924 2.6142 + vertex 0.978127 1.89682 2.61319 + vertex 0.973287 1.897 2.6134 + endloop + endfacet + facet normal 0.0518932 0.176818 0.982875 + outer loop + vertex 0.974267 1.88807 2.61495 + vertex 0.978703 1.89227 2.61396 + vertex 0.973608 1.8924 2.6142 + endloop + endfacet + facet normal 0.0445885 0.175875 0.983402 + outer loop + vertex 0.970258 1.8845 2.61577 + vertex 0.975239 1.88402 2.61563 + vertex 0.974267 1.88807 2.61495 + endloop + endfacet + facet normal 0.055252 0.172046 0.983538 + outer loop + vertex 0.979267 1.8833 2.61553 + vertex 0.975239 1.88402 2.61563 + vertex 0.976944 1.87985 2.61626 + endloop + endfacet + facet normal 0.061514 0.164207 0.984506 + outer loop + vertex 0.976944 1.87985 2.61626 + vertex 0.976675 1.87562 2.61698 + vertex 0.981267 1.87663 2.61653 + endloop + endfacet + facet normal 0.0534421 0.155851 0.986334 + outer loop + vertex 0.977868 1.87185 2.61751 + vertex 0.976675 1.87562 2.61698 + vertex 0.973165 1.87183 2.61777 + endloop + endfacet + facet normal 0.0534413 0.155913 0.986324 + outer loop + vertex 0.973423 1.86707 2.61851 + vertex 0.977868 1.87185 2.61751 + vertex 0.973165 1.87183 2.61777 + endloop + endfacet + facet normal 0.0550448 0.155918 0.986235 + outer loop + vertex 0.973679 1.86224 2.61926 + vertex 0.9784 1.86705 2.61824 + vertex 0.973423 1.86707 2.61851 + endloop + endfacet + facet normal 0.0570111 0.157182 0.985923 + outer loop + vertex 0.974663 1.85741 2.61997 + vertex 0.978784 1.86229 2.61896 + vertex 0.973679 1.86224 2.61926 + endloop + endfacet + facet normal 0.0605137 0.156724 0.985787 + outer loop + vertex 0.974663 1.85741 2.61997 + vertex 0.978818 1.85424 2.62022 + vertex 0.979692 1.85857 2.61948 + endloop + endfacet + facet normal 0.0541966 0.153422 0.986673 + outer loop + vertex 0.976261 1.85096 2.62091 + vertex 0.974198 1.85336 2.62065 + vertex 0.972003 1.85 2.6213 + endloop + endfacet + facet normal 0.0673254 0.157534 0.985216 + outer loop + vertex 0.978818 1.85424 2.62022 + vertex 0.980337 1.84985 2.62082 + vertex 0.984705 1.85277 2.62006 + endloop + endfacet + facet normal 0.0662387 0.159118 0.985035 + outer loop + vertex 0.980337 1.84985 2.62082 + vertex 0.984383 1.84869 2.62074 + vertex 0.984705 1.85277 2.62006 + endloop + endfacet + facet normal 0.0546078 0.151705 0.986916 + outer loop + vertex 0.976261 1.85096 2.62091 + vertex 0.972003 1.85 2.6213 + vertex 0.976359 1.8468 2.62155 + endloop + endfacet + facet normal 0.0648053 0.154087 0.98593 + outer loop + vertex 0.984383 1.84869 2.62074 + vertex 0.980337 1.84985 2.62082 + vertex 0.982096 1.84534 2.62141 + endloop + endfacet + facet normal 0.0621928 0.155853 0.98582 + outer loop + vertex 0.986498 1.84613 2.62101 + vertex 0.984383 1.84869 2.62074 + vertex 0.982096 1.84534 2.62141 + endloop + endfacet + facet normal 0.0631237 0.151003 0.986516 + outer loop + vertex 0.986498 1.84613 2.62101 + vertex 0.982096 1.84534 2.62141 + vertex 0.986526 1.84185 2.62166 + endloop + endfacet + facet normal 0.0591668 0.151014 0.986759 + outer loop + vertex 0.986498 1.84613 2.62101 + vertex 0.986526 1.84185 2.62166 + vertex 0.990626 1.84499 2.62094 + endloop + endfacet + facet normal 0.0619414 0.147474 0.987124 + outer loop + vertex 0.992313 1.84043 2.62151 + vertex 0.990626 1.84499 2.62094 + vertex 0.986526 1.84185 2.62166 + endloop + endfacet + facet normal 0.0617288 0.149261 0.986869 + outer loop + vertex 0.982096 1.84534 2.62141 + vertex 0.981828 1.84083 2.62211 + vertex 0.986526 1.84185 2.62166 + endloop + endfacet + facet normal 0.0629593 0.143895 0.987588 + outer loop + vertex 0.982984 1.8369 2.62261 + vertex 0.986526 1.84185 2.62166 + vertex 0.981828 1.84083 2.62211 + endloop + endfacet + facet normal 0.0617777 0.143562 0.987711 + outer loop + vertex 0.982984 1.8369 2.62261 + vertex 0.981828 1.84083 2.62211 + vertex 0.978231 1.83694 2.6229 + endloop + endfacet + facet normal 0.0617775 0.141686 0.987982 + outer loop + vertex 0.978455 1.83209 2.62358 + vertex 0.982984 1.8369 2.62261 + vertex 0.978231 1.83694 2.6229 + endloop + endfacet + facet normal 0.0579346 0.141545 0.988235 + outer loop + vertex 0.978455 1.83209 2.62358 + vertex 0.978231 1.83694 2.6229 + vertex 0.973608 1.83227 2.62384 + endloop + endfacet + facet normal 0.0579252 0.141234 0.98828 + outer loop + vertex 0.973671 1.82757 2.62451 + vertex 0.978455 1.83209 2.62358 + vertex 0.973608 1.83227 2.62384 + endloop + endfacet + facet normal 0.0579888 0.141168 0.988286 + outer loop + vertex 0.978721 1.82729 2.62425 + vertex 0.978455 1.83209 2.62358 + vertex 0.973671 1.82757 2.62451 + endloop + endfacet + facet normal 0.0616932 0.141764 0.987976 + outer loop + vertex 0.98343 1.83199 2.62328 + vertex 0.982984 1.8369 2.62261 + vertex 0.978455 1.83209 2.62358 + endloop + endfacet + facet normal 0.060558 0.144674 0.987625 + outer loop + vertex 0.978231 1.83694 2.6229 + vertex 0.981828 1.84083 2.62211 + vertex 0.977792 1.84177 2.62222 + endloop + endfacet + facet normal 0.061855 0.144677 0.987544 + outer loop + vertex 0.987854 1.83668 2.62234 + vertex 0.986526 1.84185 2.62166 + vertex 0.982984 1.8369 2.62261 + endloop + endfacet + facet normal 0.0629327 0.15645 0.985679 + outer loop + vertex 0.984383 1.84869 2.62074 + vertex 0.986498 1.84613 2.62101 + vertex 0.989012 1.8494 2.62033 + endloop + endfacet + facet normal 0.0616124 0.149269 0.986875 + outer loop + vertex 0.981828 1.84083 2.62211 + vertex 0.982096 1.84534 2.62141 + vertex 0.977792 1.84177 2.62222 + endloop + endfacet + facet normal 0.0567693 0.144368 0.987894 + outer loop + vertex 0.978231 1.83694 2.6229 + vertex 0.977792 1.84177 2.62222 + vertex 0.973464 1.83712 2.62315 + endloop + endfacet + facet normal 0.05672 0.142726 0.988136 + outer loop + vertex 0.973608 1.83227 2.62384 + vertex 0.978231 1.83694 2.6229 + vertex 0.973464 1.83712 2.62315 + endloop + endfacet + facet normal 0.0526849 0.141206 0.988577 + outer loop + vertex 0.973671 1.82757 2.62451 + vertex 0.973608 1.83227 2.62384 + vertex 0.969536 1.82845 2.6246 + endloop + endfacet + facet normal 0.0523405 0.139548 0.988831 + outer loop + vertex 0.968655 1.82411 2.62526 + vertex 0.973671 1.82757 2.62451 + vertex 0.969536 1.82845 2.6246 + endloop + endfacet + facet normal 0.0517147 0.140434 0.988739 + outer loop + vertex 0.97459 1.8227 2.62515 + vertex 0.973671 1.82757 2.62451 + vertex 0.968655 1.82411 2.62526 + endloop + endfacet + facet normal 0.0516227 0.14004 0.988799 + outer loop + vertex 0.968655 1.82411 2.62526 + vertex 0.97026 1.81981 2.62579 + vertex 0.97459 1.8227 2.62515 + endloop + endfacet + facet normal 0.0511423 0.140741 0.988725 + outer loop + vertex 0.97026 1.81981 2.62579 + vertex 0.974339 1.8187 2.62573 + vertex 0.97459 1.8227 2.62515 + endloop + endfacet + facet normal 0.0493354 0.134034 0.989748 + outer loop + vertex 0.974339 1.8187 2.62573 + vertex 0.97026 1.81981 2.62579 + vertex 0.97215 1.81545 2.62628 + endloop + endfacet + facet normal 0.050386 0.133333 0.98979 + outer loop + vertex 0.976487 1.81622 2.62596 + vertex 0.974339 1.8187 2.62573 + vertex 0.97215 1.81545 2.62628 + endloop + endfacet + facet normal 0.0509558 0.130282 0.990167 + outer loop + vertex 0.976487 1.81622 2.62596 + vertex 0.97215 1.81545 2.62628 + vertex 0.97661 1.81207 2.6265 + endloop + endfacet + facet normal 0.0518949 0.130303 0.990115 + outer loop + vertex 0.976487 1.81622 2.62596 + vertex 0.97661 1.81207 2.6265 + vertex 0.980536 1.81508 2.6259 + endloop + endfacet + facet normal 0.0512861 0.130712 0.990093 + outer loop + vertex 0.97215 1.81545 2.62628 + vertex 0.97203 1.81108 2.62687 + vertex 0.97661 1.81207 2.6265 + endloop + endfacet + facet normal 0.0519784 0.127643 0.990457 + outer loop + vertex 0.973217 1.80719 2.62731 + vertex 0.97661 1.81207 2.6265 + vertex 0.97203 1.81108 2.62687 + endloop + endfacet + facet normal 0.0502665 0.127138 0.990611 + outer loop + vertex 0.973217 1.80719 2.62731 + vertex 0.97203 1.81108 2.62687 + vertex 0.968473 1.80715 2.62755 + endloop + endfacet + facet normal 0.0502693 0.126938 0.990636 + outer loop + vertex 0.968601 1.80214 2.62819 + vertex 0.973217 1.80719 2.62731 + vertex 0.968473 1.80715 2.62755 + endloop + endfacet + facet normal 0.046462 0.126866 0.990831 + outer loop + vertex 0.968601 1.80214 2.62819 + vertex 0.968473 1.80715 2.62755 + vertex 0.963567 1.80209 2.62843 + endloop + endfacet + facet normal 0.0464752 0.126042 0.990936 + outer loop + vertex 0.963351 1.797 2.62909 + vertex 0.968601 1.80214 2.62819 + vertex 0.963567 1.80209 2.62843 + endloop + endfacet + facet normal 0.0418591 0.12626 0.991114 + outer loop + vertex 0.963351 1.797 2.62909 + vertex 0.963567 1.80209 2.62843 + vertex 0.958422 1.79715 2.62927 + endloop + endfacet + facet normal 0.0418093 0.124394 0.991352 + outer loop + vertex 0.9584 1.79265 2.62984 + vertex 0.963351 1.797 2.62909 + vertex 0.958422 1.79715 2.62927 + endloop + endfacet + facet normal 0.0367804 0.124442 0.991545 + outer loop + vertex 0.9584 1.79265 2.62984 + vertex 0.958422 1.79715 2.62927 + vertex 0.954366 1.79344 2.62989 + endloop + endfacet + facet normal 0.0360335 0.120613 0.992045 + outer loop + vertex 0.953632 1.78937 2.63041 + vertex 0.9584 1.79265 2.62984 + vertex 0.954366 1.79344 2.62989 + endloop + endfacet + facet normal 0.0368094 0.119503 0.992151 + outer loop + vertex 0.959005 1.78837 2.63033 + vertex 0.9584 1.79265 2.62984 + vertex 0.953632 1.78937 2.63041 + endloop + endfacet + facet normal 0.0334467 0.128029 0.991206 + outer loop + vertex 0.954366 1.79344 2.62989 + vertex 0.958422 1.79715 2.62927 + vertex 0.953545 1.7971 2.62945 + endloop + endfacet + facet normal 0.0255105 0.1263 0.991664 + outer loop + vertex 0.954366 1.79344 2.62989 + vertex 0.953545 1.7971 2.62945 + vertex 0.949518 1.79229 2.63016 + endloop + endfacet + facet normal 0.0334346 0.128764 0.991111 + outer loop + vertex 0.958422 1.79715 2.62927 + vertex 0.958531 1.80205 2.62864 + vertex 0.953545 1.7971 2.62945 + endloop + endfacet + facet normal 0.0330373 0.129158 0.991074 + outer loop + vertex 0.953545 1.7971 2.62945 + vertex 0.958531 1.80205 2.62864 + vertex 0.953478 1.80199 2.62881 + endloop + endfacet + facet normal 0.0257758 0.129087 0.991298 + outer loop + vertex 0.953545 1.7971 2.62945 + vertex 0.953478 1.80199 2.62881 + vertex 0.948509 1.79706 2.62958 + endloop + endfacet + facet normal 0.0276388 0.12724 0.991487 + outer loop + vertex 0.948509 1.79706 2.62958 + vertex 0.953478 1.80199 2.62881 + vertex 0.948456 1.80203 2.62895 + endloop + endfacet + facet normal 0.0276475 0.129462 0.991199 + outer loop + vertex 0.953478 1.80199 2.62881 + vertex 0.953684 1.80721 2.62812 + vertex 0.948456 1.80203 2.62895 + endloop + endfacet + facet normal 0.0338021 0.129198 0.991043 + outer loop + vertex 0.953478 1.80199 2.62881 + vertex 0.958649 1.80723 2.62795 + vertex 0.953684 1.80721 2.62812 + endloop + endfacet + facet normal 0.0337982 0.129678 0.99098 + outer loop + vertex 0.958649 1.80723 2.62795 + vertex 0.958409 1.81213 2.62732 + vertex 0.953684 1.80721 2.62812 + endloop + endfacet + facet normal 0.0342609 0.129241 0.991021 + outer loop + vertex 0.953684 1.80721 2.62812 + vertex 0.958409 1.81213 2.62732 + vertex 0.953642 1.8123 2.62746 + endloop + endfacet + facet normal 0.034308 0.130783 0.990817 + outer loop + vertex 0.958409 1.81213 2.62732 + vertex 0.957822 1.81661 2.62675 + vertex 0.953642 1.8123 2.62746 + endloop + endfacet + facet normal 0.0376863 0.131203 0.990639 + outer loop + vertex 0.958409 1.81213 2.62732 + vertex 0.961792 1.81584 2.6267 + vertex 0.957822 1.81661 2.62675 + endloop + endfacet + facet normal 0.0381787 0.133754 0.990279 + outer loop + vertex 0.961792 1.81584 2.6267 + vertex 0.961888 1.81992 2.62614 + vertex 0.957822 1.81661 2.62675 + endloop + endfacet + facet normal 0.0420349 0.133644 0.990138 + outer loop + vertex 0.961888 1.81992 2.62614 + vertex 0.961792 1.81584 2.6267 + vertex 0.966354 1.81682 2.62637 + endloop + endfacet + facet normal 0.0420043 0.133601 0.990145 + outer loop + vertex 0.966143 1.82085 2.62584 + vertex 0.961888 1.81992 2.62614 + vertex 0.966354 1.81682 2.62637 + endloop + endfacet + facet normal 0.0461743 0.133792 0.989933 + outer loop + vertex 0.966143 1.82085 2.62584 + vertex 0.966354 1.81682 2.62637 + vertex 0.97026 1.81981 2.62579 + endloop + endfacet + facet normal 0.0413702 0.136392 0.989791 + outer loop + vertex 0.966143 1.82085 2.62584 + vertex 0.964034 1.82322 2.6256 + vertex 0.961888 1.81992 2.62614 + endloop + endfacet + facet normal 0.0425023 0.131558 0.990397 + outer loop + vertex 0.963108 1.81214 2.62713 + vertex 0.966354 1.81682 2.62637 + vertex 0.961792 1.81584 2.6267 + endloop + endfacet + facet normal 0.0433085 0.131005 0.990435 + outer loop + vertex 0.967941 1.81193 2.62695 + vertex 0.966354 1.81682 2.62637 + vertex 0.963108 1.81214 2.62713 + endloop + endfacet + facet normal 0.0432851 0.130393 0.990517 + outer loop + vertex 0.963623 1.80725 2.62776 + vertex 0.967941 1.81193 2.62695 + vertex 0.963108 1.81214 2.62713 + endloop + endfacet + facet normal 0.038687 0.129941 0.990767 + outer loop + vertex 0.963623 1.80725 2.62776 + vertex 0.963108 1.81214 2.62713 + vertex 0.958649 1.80723 2.62795 + endloop + endfacet + facet normal 0.0386884 0.1298 0.990785 + outer loop + vertex 0.958531 1.80205 2.62864 + vertex 0.963623 1.80725 2.62776 + vertex 0.958649 1.80723 2.62795 + endloop + endfacet + facet normal 0.0395759 0.128944 0.990862 + outer loop + vertex 0.963567 1.80209 2.62843 + vertex 0.963623 1.80725 2.62776 + vertex 0.958531 1.80205 2.62864 + endloop + endfacet + facet normal 0.0443754 0.129403 0.990599 + outer loop + vertex 0.968473 1.80715 2.62755 + vertex 0.967941 1.81193 2.62695 + vertex 0.963623 1.80725 2.62776 + endloop + endfacet + facet normal 0.0465959 0.132038 0.990149 + outer loop + vertex 0.967941 1.81193 2.62695 + vertex 0.97215 1.81545 2.62628 + vertex 0.966354 1.81682 2.62637 + endloop + endfacet + facet normal 0.0387386 0.130256 0.990723 + outer loop + vertex 0.963108 1.81214 2.62713 + vertex 0.961792 1.81584 2.6267 + vertex 0.958409 1.81213 2.62732 + endloop + endfacet + facet normal 0.0387413 0.129893 0.990771 + outer loop + vertex 0.958649 1.80723 2.62795 + vertex 0.963108 1.81214 2.62713 + vertex 0.958409 1.81213 2.62732 + endloop + endfacet + facet normal 0.0330252 0.129953 0.99097 + outer loop + vertex 0.958531 1.80205 2.62864 + vertex 0.958649 1.80723 2.62795 + vertex 0.953478 1.80199 2.62881 + endloop + endfacet + facet normal 0.0439678 0.121973 0.991559 + outer loop + vertex 0.963454 1.79217 2.62968 + vertex 0.963351 1.797 2.62909 + vertex 0.9584 1.79265 2.62984 + endloop + endfacet + facet normal 0.048762 0.122047 0.991326 + outer loop + vertex 0.963454 1.79217 2.62968 + vertex 0.968473 1.79698 2.62884 + vertex 0.963351 1.797 2.62909 + endloop + endfacet + facet normal 0.0395805 0.128601 0.990906 + outer loop + vertex 0.958422 1.79715 2.62927 + vertex 0.963567 1.80209 2.62843 + vertex 0.958531 1.80205 2.62864 + endloop + endfacet + facet normal 0.0487593 0.12374 0.991116 + outer loop + vertex 0.968473 1.79698 2.62884 + vertex 0.968601 1.80214 2.62819 + vertex 0.963351 1.797 2.62909 + endloop + endfacet + facet normal 0.0523904 0.123628 0.990945 + outer loop + vertex 0.968473 1.79698 2.62884 + vertex 0.973612 1.8022 2.62791 + vertex 0.968601 1.80214 2.62819 + endloop + endfacet + facet normal 0.0534434 0.122605 0.991016 + outer loop + vertex 0.973551 1.79706 2.62855 + vertex 0.973612 1.8022 2.62791 + vertex 0.968473 1.79698 2.62884 + endloop + endfacet + facet normal 0.0534801 0.121029 0.991207 + outer loop + vertex 0.968573 1.79212 2.62942 + vertex 0.973551 1.79706 2.62855 + vertex 0.968473 1.79698 2.62884 + endloop + endfacet + facet normal 0.0533234 0.121185 0.991197 + outer loop + vertex 0.973479 1.79221 2.62915 + vertex 0.973551 1.79706 2.62855 + vertex 0.968573 1.79212 2.62942 + endloop + endfacet + facet normal 0.0547644 0.12258 0.990946 + outer loop + vertex 0.973551 1.79706 2.62855 + vertex 0.978438 1.80214 2.62765 + vertex 0.973612 1.8022 2.62791 + endloop + endfacet + facet normal 0.054771 0.123754 0.9908 + outer loop + vertex 0.978438 1.80214 2.62765 + vertex 0.978028 1.80701 2.62707 + vertex 0.973612 1.8022 2.62791 + endloop + endfacet + facet normal 0.0532744 0.125112 0.990711 + outer loop + vertex 0.973612 1.8022 2.62791 + vertex 0.978028 1.80701 2.62707 + vertex 0.973217 1.80719 2.62731 + endloop + endfacet + facet normal 0.0536965 0.123672 0.990869 + outer loop + vertex 0.978438 1.80214 2.62765 + vertex 0.98203 1.80611 2.62696 + vertex 0.978028 1.80701 2.62707 + endloop + endfacet + facet normal 0.0538094 0.124182 0.990799 + outer loop + vertex 0.98203 1.80611 2.62696 + vertex 0.982291 1.81062 2.62639 + vertex 0.978028 1.80701 2.62707 + endloop + endfacet + facet normal 0.0548032 0.122683 0.990932 + outer loop + vertex 0.983162 1.80217 2.62739 + vertex 0.98203 1.80611 2.62696 + vertex 0.978438 1.80214 2.62765 + endloop + endfacet + facet normal 0.0547589 0.122586 0.990946 + outer loop + vertex 0.97855 1.79715 2.62827 + vertex 0.978438 1.80214 2.62765 + vertex 0.973551 1.79706 2.62855 + endloop + endfacet + facet normal 0.0443679 0.128866 0.990669 + outer loop + vertex 0.963567 1.80209 2.62843 + vertex 0.968473 1.80715 2.62755 + vertex 0.963623 1.80725 2.62776 + endloop + endfacet + facet normal 0.0523636 0.125046 0.990768 + outer loop + vertex 0.973612 1.8022 2.62791 + vertex 0.973217 1.80719 2.62731 + vertex 0.968601 1.80214 2.62819 + endloop + endfacet + facet normal 0.0473865 0.129715 0.990418 + outer loop + vertex 0.968473 1.80715 2.62755 + vertex 0.97203 1.81108 2.62687 + vertex 0.967941 1.81193 2.62695 + endloop + endfacet + facet normal 0.0533223 0.126716 0.990505 + outer loop + vertex 0.978028 1.80701 2.62707 + vertex 0.97661 1.81207 2.6265 + vertex 0.973217 1.80719 2.62731 + endloop + endfacet + facet normal 0.0519513 0.126345 0.990625 + outer loop + vertex 0.978028 1.80701 2.62707 + vertex 0.982291 1.81062 2.62639 + vertex 0.97661 1.81207 2.6265 + endloop + endfacet + facet normal 0.0476184 0.130835 0.99026 + outer loop + vertex 0.97203 1.81108 2.62687 + vertex 0.97215 1.81545 2.62628 + vertex 0.967941 1.81193 2.62695 + endloop + endfacet + facet normal 0.046814 0.13297 0.990014 + outer loop + vertex 0.97215 1.81545 2.62628 + vertex 0.97026 1.81981 2.62579 + vertex 0.966354 1.81682 2.62637 + endloop + endfacet + facet normal 0.0473618 0.138503 0.989229 + outer loop + vertex 0.97026 1.81981 2.62579 + vertex 0.968655 1.82411 2.62526 + vertex 0.966143 1.82085 2.62584 + endloop + endfacet + facet normal 0.0454472 0.139959 0.989114 + outer loop + vertex 0.964034 1.82322 2.6256 + vertex 0.966143 1.82085 2.62584 + vertex 0.968655 1.82411 2.62526 + endloop + endfacet + facet normal 0.0391453 0.137825 0.989683 + outer loop + vertex 0.964034 1.82322 2.6256 + vertex 0.96003 1.82397 2.62565 + vertex 0.961888 1.81992 2.62614 + endloop + endfacet + facet normal 0.0372142 0.136961 0.989877 + outer loop + vertex 0.961888 1.81992 2.62614 + vertex 0.96003 1.82397 2.62565 + vertex 0.956659 1.82074 2.62623 + endloop + endfacet + facet normal 0.0347366 0.141498 0.989329 + outer loop + vertex 0.955105 1.82454 2.62574 + vertex 0.96003 1.82397 2.62565 + vertex 0.958995 1.82797 2.62512 + endloop + endfacet + facet normal 0.0435008 0.143213 0.988735 + outer loop + vertex 0.964508 1.82728 2.625 + vertex 0.968736 1.83225 2.62409 + vertex 0.963606 1.83218 2.62433 + endloop + endfacet + facet normal 0.0372483 0.144891 0.988746 + outer loop + vertex 0.958464 1.83234 2.6245 + vertex 0.963518 1.8371 2.62361 + vertex 0.958486 1.8371 2.6238 + endloop + endfacet + facet normal 0.0434949 0.143503 0.988694 + outer loop + vertex 0.968736 1.83225 2.62409 + vertex 0.968521 1.83712 2.62339 + vertex 0.963606 1.83218 2.62433 + endloop + endfacet + facet normal 0.0483737 0.145297 0.988205 + outer loop + vertex 0.968521 1.83712 2.62339 + vertex 0.972983 1.842 2.62246 + vertex 0.968294 1.84198 2.62269 + endloop + endfacet + facet normal 0.0483645 0.146029 0.988097 + outer loop + vertex 0.972983 1.842 2.62246 + vertex 0.971796 1.84579 2.62196 + vertex 0.968294 1.84198 2.62269 + endloop + endfacet + facet normal 0.0549878 0.152215 0.986817 + outer loop + vertex 0.972003 1.85 2.6213 + vertex 0.971796 1.84579 2.62196 + vertex 0.976359 1.8468 2.62155 + endloop + endfacet + facet normal 0.0491473 0.156676 0.986427 + outer loop + vertex 0.974198 1.85336 2.62065 + vertex 0.970195 1.8541 2.62074 + vertex 0.972003 1.85 2.6213 + endloop + endfacet + facet normal 0.0415317 0.15782 0.986594 + outer loop + vertex 0.965263 1.85472 2.62084 + vertex 0.970195 1.8541 2.62074 + vertex 0.969129 1.85809 2.62014 + endloop + endfacet + facet normal 0.0396104 0.153121 0.987413 + outer loop + vertex 0.967834 1.84654 2.62202 + vertex 0.96679 1.8508 2.6214 + vertex 0.963009 1.84689 2.62216 + endloop + endfacet + facet normal 0.0394183 0.150273 0.987858 + outer loop + vertex 0.963504 1.84208 2.62287 + vertex 0.967834 1.84654 2.62202 + vertex 0.963009 1.84689 2.62216 + endloop + endfacet + facet normal 0.0372393 0.146523 0.988506 + outer loop + vertex 0.963518 1.8371 2.62361 + vertex 0.963504 1.84208 2.62287 + vertex 0.958486 1.8371 2.6238 + endloop + endfacet + facet normal 0.0324494 0.144937 0.988909 + outer loop + vertex 0.958464 1.83234 2.6245 + vertex 0.958486 1.8371 2.6238 + vertex 0.953429 1.83244 2.62465 + endloop + endfacet + facet normal 0.0324377 0.144169 0.989021 + outer loop + vertex 0.953921 1.82831 2.62524 + vertex 0.958464 1.83234 2.6245 + vertex 0.953429 1.83244 2.62465 + endloop + endfacet + facet normal 0.0161916 0.140654 0.989926 + outer loop + vertex 0.945207 1.82493 2.62591 + vertex 0.950139 1.82484 2.62584 + vertex 0.948969 1.82848 2.62534 + endloop + endfacet + facet normal 0.0328917 0.143549 0.989096 + outer loop + vertex 0.953921 1.82831 2.62524 + vertex 0.955105 1.82454 2.62574 + vertex 0.958995 1.82797 2.62512 + endloop + endfacet + facet normal 0.034533 0.139704 0.989591 + outer loop + vertex 0.96003 1.82397 2.62565 + vertex 0.955105 1.82454 2.62574 + vertex 0.956659 1.82074 2.62623 + endloop + endfacet + facet normal 0.0369499 0.135235 0.990124 + outer loop + vertex 0.957822 1.81661 2.62675 + vertex 0.961888 1.81992 2.62614 + vertex 0.956659 1.82074 2.62623 + endloop + endfacet + facet normal 0.0294323 0.129222 0.991179 + outer loop + vertex 0.953684 1.80721 2.62812 + vertex 0.953642 1.8123 2.62746 + vertex 0.948718 1.80726 2.62827 + endloop + endfacet + facet normal 0.0294225 0.127698 0.991377 + outer loop + vertex 0.948456 1.80203 2.62895 + vertex 0.953684 1.80721 2.62812 + vertex 0.948718 1.80726 2.62827 + endloop + endfacet + facet normal 0.0194425 0.127178 0.991689 + outer loop + vertex 0.948509 1.79706 2.62958 + vertex 0.948456 1.80203 2.62895 + vertex 0.943445 1.7972 2.62966 + endloop + endfacet + facet normal 0.025807 0.126055 0.991688 + outer loop + vertex 0.949518 1.79229 2.63016 + vertex 0.953545 1.7971 2.62945 + vertex 0.948509 1.79706 2.62958 + endloop + endfacet + facet normal 0.0264748 0.122348 0.992134 + outer loop + vertex 0.949518 1.79229 2.63016 + vertex 0.953632 1.78937 2.63041 + vertex 0.954366 1.79344 2.62989 + endloop + endfacet + facet normal 0.019665 0.114496 0.993229 + outer loop + vertex 0.951295 1.7861 2.63087 + vertex 0.9492 1.78835 2.63066 + vertex 0.94705 1.78501 2.63108 + endloop + endfacet + facet normal 0.0369707 0.120376 0.99204 + outer loop + vertex 0.953632 1.78937 2.63041 + vertex 0.95534 1.78527 2.63085 + vertex 0.959005 1.78837 2.63033 + endloop + endfacet + facet normal 0.0194317 0.115378 0.993132 + outer loop + vertex 0.951295 1.7861 2.63087 + vertex 0.94705 1.78501 2.63108 + vertex 0.951405 1.78207 2.63134 + endloop + endfacet + facet normal 0.0391062 0.117717 0.992277 + outer loop + vertex 0.960219 1.7843 2.63077 + vertex 0.95534 1.78527 2.63085 + vertex 0.956809 1.78114 2.63128 + endloop + endfacet + facet normal 0.0447742 0.102224 0.993753 + outer loop + vertex 0.967923 1.77227 2.63175 + vertex 0.97163 1.7761 2.63119 + vertex 0.966274 1.77707 2.63133 + endloop + endfacet + facet normal 0.0463909 0.100672 0.993838 + outer loop + vertex 0.972812 1.77173 2.63158 + vertex 0.97163 1.7761 2.63119 + vertex 0.967923 1.77227 2.63175 + endloop + endfacet + facet normal 0.0405962 0.0991405 0.994245 + outer loop + vertex 0.972812 1.77173 2.63158 + vertex 0.976983 1.77479 2.6311 + vertex 0.97163 1.7761 2.63119 + endloop + endfacet + facet normal 0.0438279 0.112454 0.99269 + outer loop + vertex 0.976983 1.77479 2.6311 + vertex 0.975094 1.77916 2.63069 + vertex 0.97163 1.7761 2.63119 + endloop + endfacet + facet normal 0.0432057 0.112191 0.992747 + outer loop + vertex 0.979279 1.77801 2.63064 + vertex 0.975094 1.77916 2.63069 + vertex 0.976983 1.77479 2.6311 + endloop + endfacet + facet normal 0.0438081 0.0948114 0.994531 + outer loop + vertex 0.976826 1.77066 2.6315 + vertex 0.976983 1.77479 2.6311 + vertex 0.972812 1.77173 2.63158 + endloop + endfacet + facet normal 0.0466898 0.0946907 0.994411 + outer loop + vertex 0.976983 1.77479 2.6311 + vertex 0.976826 1.77066 2.6315 + vertex 0.981616 1.77098 2.63125 + endloop + endfacet + facet normal 0.139624 0.129373 0.981717 + outer loop + vertex 0.984557 1.77402 2.63075 + vertex 0.98623 1.77115 2.63089 + vertex 0.989356 1.77401 2.63007 + endloop + endfacet + facet normal 0.0464557 0.0944073 0.994449 + outer loop + vertex 0.98129 1.77535 2.63085 + vertex 0.976983 1.77479 2.6311 + vertex 0.981616 1.77098 2.63125 + endloop + endfacet + facet normal 0.139735 0.121434 0.982715 + outer loop + vertex 0.984557 1.77402 2.63075 + vertex 0.989356 1.77401 2.63007 + vertex 0.984433 1.77846 2.63022 + endloop + endfacet + facet normal 0.119227 0.0985669 0.987962 + outer loop + vertex 0.984433 1.77846 2.63022 + vertex 0.989356 1.77401 2.63007 + vertex 0.989666 1.77885 2.62955 + endloop + endfacet + facet normal 0.20419 0.0916936 0.974627 + outer loop + vertex 0.989356 1.77401 2.63007 + vertex 0.993464 1.7777 2.62886 + vertex 0.989666 1.77885 2.62955 + endloop + endfacet + facet normal 0.202051 0.0839316 0.975772 + outer loop + vertex 0.993464 1.7777 2.62886 + vertex 0.993105 1.78225 2.62854 + vertex 0.989666 1.77885 2.62955 + endloop + endfacet + facet normal 0.176243 0.110737 0.978098 + outer loop + vertex 0.989666 1.77885 2.62955 + vertex 0.993105 1.78225 2.62854 + vertex 0.988719 1.78272 2.62928 + endloop + endfacet + facet normal 0.0441306 0.111537 0.99278 + outer loop + vertex 0.98129 1.77535 2.63085 + vertex 0.979279 1.77801 2.63064 + vertex 0.976983 1.77479 2.6311 + endloop + endfacet + facet normal 0.119319 0.097504 0.988057 + outer loop + vertex 0.989666 1.77885 2.62955 + vertex 0.988719 1.78272 2.62928 + vertex 0.984433 1.77846 2.63022 + endloop + endfacet + facet normal 0.0856401 0.127715 0.988107 + outer loop + vertex 0.984747 1.78341 2.62962 + vertex 0.9885 1.78735 2.62879 + vertex 0.983711 1.78726 2.62921 + endloop + endfacet + facet normal 0.174474 0.0908686 0.98046 + outer loop + vertex 0.993105 1.78225 2.62854 + vertex 0.992907 1.78703 2.62814 + vertex 0.988719 1.78272 2.62928 + endloop + endfacet + facet normal 0.0860419 0.114309 0.989712 + outer loop + vertex 0.9885 1.78735 2.62879 + vertex 0.988377 1.79217 2.62824 + vertex 0.983711 1.78726 2.62921 + endloop + endfacet + facet normal 0.0625857 0.121768 0.990583 + outer loop + vertex 0.984747 1.78341 2.62962 + vertex 0.983711 1.78726 2.62921 + vertex 0.979645 1.78225 2.63009 + endloop + endfacet + facet normal 0.0467443 0.125174 0.991033 + outer loop + vertex 0.975094 1.77916 2.63069 + vertex 0.979279 1.77801 2.63064 + vertex 0.979645 1.78225 2.63009 + endloop + endfacet + facet normal 0.0434126 0.112919 0.992655 + outer loop + vertex 0.975094 1.77916 2.63069 + vertex 0.970171 1.78025 2.63078 + vertex 0.97163 1.7761 2.63119 + endloop + endfacet + facet normal 0.0468887 0.114113 0.992361 + outer loop + vertex 0.97163 1.7761 2.63119 + vertex 0.970171 1.78025 2.63078 + vertex 0.966274 1.77707 2.63133 + endloop + endfacet + facet normal 0.0470158 0.113483 0.992427 + outer loop + vertex 0.962025 1.78012 2.63118 + vertex 0.961808 1.77591 2.63168 + vertex 0.966274 1.77707 2.63133 + endloop + endfacet + facet normal 0.0491507 0.119003 0.991677 + outer loop + vertex 0.964169 1.78345 2.63069 + vertex 0.966196 1.78112 2.63087 + vertex 0.968557 1.78438 2.63036 + endloop + endfacet + facet normal 0.0406655 0.116055 0.99241 + outer loop + vertex 0.962025 1.78012 2.63118 + vertex 0.960219 1.7843 2.63077 + vertex 0.956809 1.78114 2.63128 + endloop + endfacet + facet normal 0.0391322 0.117849 0.99226 + outer loop + vertex 0.95534 1.78527 2.63085 + vertex 0.960219 1.7843 2.63077 + vertex 0.959005 1.78837 2.63033 + endloop + endfacet + facet normal 0.0438286 0.120449 0.991752 + outer loop + vertex 0.959005 1.78837 2.63033 + vertex 0.963454 1.79217 2.62968 + vertex 0.9584 1.79265 2.62984 + endloop + endfacet + facet normal 0.0498006 0.120977 0.991405 + outer loop + vertex 0.968573 1.79212 2.62942 + vertex 0.968473 1.79698 2.62884 + vertex 0.963454 1.79217 2.62968 + endloop + endfacet + facet normal 0.0491362 0.119069 0.991669 + outer loop + vertex 0.964169 1.78345 2.63069 + vertex 0.968557 1.78438 2.63036 + vertex 0.96448 1.7874 2.6302 + endloop + endfacet + facet normal 0.0486175 0.123942 0.991098 + outer loop + vertex 0.973925 1.78333 2.63023 + vertex 0.973411 1.78769 2.62971 + vertex 0.968557 1.78438 2.63036 + endloop + endfacet + facet normal 0.0533529 0.119987 0.991341 + outer loop + vertex 0.969376 1.78847 2.62982 + vertex 0.973479 1.79221 2.62915 + vertex 0.968573 1.79212 2.62942 + endloop + endfacet + facet normal 0.0500346 0.125369 0.990848 + outer loop + vertex 0.978515 1.78724 2.62951 + vertex 0.978413 1.79212 2.6289 + vertex 0.973411 1.78769 2.62971 + endloop + endfacet + facet normal 0.0547962 0.121154 0.99112 + outer loop + vertex 0.973479 1.79221 2.62915 + vertex 0.97855 1.79715 2.62827 + vertex 0.973551 1.79706 2.62855 + endloop + endfacet + facet normal 0.0551294 0.122928 0.990883 + outer loop + vertex 0.983491 1.79211 2.62861 + vertex 0.983513 1.79719 2.62798 + vertex 0.978413 1.79212 2.6289 + endloop + endfacet + facet normal 0.0548046 0.122586 0.990944 + outer loop + vertex 0.97855 1.79715 2.62827 + vertex 0.983162 1.80217 2.62739 + vertex 0.978438 1.80214 2.62765 + endloop + endfacet + facet normal 0.0668991 0.118483 0.9907 + outer loop + vertex 0.988233 1.79705 2.62768 + vertex 0.987914 1.8019 2.62712 + vertex 0.983513 1.79719 2.62798 + endloop + endfacet + facet normal 0.0592173 0.123907 0.990525 + outer loop + vertex 0.983162 1.80217 2.62739 + vertex 0.986623 1.80707 2.62657 + vertex 0.98203 1.80611 2.62696 + endloop + endfacet + facet normal 0.0916404 0.124708 0.987952 + outer loop + vertex 0.991705 1.80086 2.6269 + vertex 0.992173 1.80537 2.62629 + vertex 0.987914 1.8019 2.62712 + endloop + endfacet + facet normal 0.059233 0.123835 0.990533 + outer loop + vertex 0.982291 1.81062 2.62639 + vertex 0.98203 1.80611 2.62696 + vertex 0.986623 1.80707 2.62657 + endloop + endfacet + facet normal 0.0526912 0.129284 0.990207 + outer loop + vertex 0.982291 1.81062 2.62639 + vertex 0.980536 1.81508 2.6259 + vertex 0.97661 1.81207 2.6265 + endloop + endfacet + facet normal 0.0717332 0.139756 0.987584 + outer loop + vertex 0.984535 1.81395 2.62583 + vertex 0.986616 1.81139 2.62604 + vertex 0.989067 1.8146 2.62541 + endloop + endfacet + facet normal 0.11713 0.105298 0.987519 + outer loop + vertex 0.994903 1.81282 2.62491 + vertex 0.993726 1.81785 2.62451 + vertex 0.989067 1.8146 2.62541 + endloop + endfacet + facet normal 0.170138 0.116975 0.978453 + outer loop + vertex 0.994903 1.81282 2.62491 + vertex 0.998396 1.81727 2.62377 + vertex 0.993726 1.81785 2.62451 + endloop + endfacet + facet normal 0.081433 0.145191 0.986047 + outer loop + vertex 0.989712 1.81882 2.62481 + vertex 0.993474 1.8224 2.62397 + vertex 0.98877 1.82244 2.62435 + endloop + endfacet + facet normal 0.168031 0.0966097 0.981036 + outer loop + vertex 0.998396 1.81727 2.62377 + vertex 0.997933 1.82204 2.62338 + vertex 0.993726 1.81785 2.62451 + endloop + endfacet + facet normal 0.0814494 0.135766 0.987387 + outer loop + vertex 0.993474 1.8224 2.62397 + vertex 0.993292 1.82709 2.62334 + vertex 0.98877 1.82244 2.62435 + endloop + endfacet + facet normal 0.0646046 0.141054 0.987892 + outer loop + vertex 0.989712 1.81882 2.62481 + vertex 0.98877 1.82244 2.62435 + vertex 0.984791 1.81795 2.62526 + endloop + endfacet + facet normal 0.0545514 0.140507 0.988576 + outer loop + vertex 0.974339 1.8187 2.62573 + vertex 0.97892 1.81939 2.62538 + vertex 0.97459 1.8227 2.62515 + endloop + endfacet + facet normal 0.0580074 0.141554 0.988229 + outer loop + vertex 0.97459 1.8227 2.62515 + vertex 0.978721 1.82729 2.62425 + vertex 0.973671 1.82757 2.62451 + endloop + endfacet + facet normal 0.0580889 0.145567 0.987642 + outer loop + vertex 0.983802 1.82267 2.62462 + vertex 0.983633 1.82721 2.62396 + vertex 0.97964 1.82356 2.62474 + endloop + endfacet + facet normal 0.061689 0.141339 0.988037 + outer loop + vertex 0.978721 1.82729 2.62425 + vertex 0.98343 1.83199 2.62328 + vertex 0.978455 1.83209 2.62358 + endloop + endfacet + facet normal 0.0600707 0.143965 0.987758 + outer loop + vertex 0.988469 1.82708 2.62369 + vertex 0.988247 1.83185 2.62301 + vertex 0.983633 1.82721 2.62396 + endloop + endfacet + facet normal 0.0617444 0.141768 0.987972 + outer loop + vertex 0.98343 1.83199 2.62328 + vertex 0.987854 1.83668 2.62234 + vertex 0.982984 1.8369 2.62261 + endloop + endfacet + facet normal 0.0657532 0.13954 0.988031 + outer loop + vertex 0.992927 1.83192 2.62269 + vertex 0.991886 1.83581 2.62221 + vertex 0.988247 1.83185 2.62301 + endloop + endfacet + facet normal 0.0612298 0.144524 0.987605 + outer loop + vertex 0.987854 1.83668 2.62234 + vertex 0.992313 1.84043 2.62151 + vertex 0.986526 1.84185 2.62166 + endloop + endfacet + facet normal 0.0771421 0.140494 0.987072 + outer loop + vertex 0.996742 1.84135 2.62103 + vertex 0.99473 1.84389 2.62083 + vertex 0.992313 1.84043 2.62151 + endloop + endfacet + facet normal 0.106664 0.163324 0.98079 + outer loop + vertex 0.99473 1.84389 2.62083 + vertex 0.996742 1.84135 2.62103 + vertex 0.99919 1.84458 2.62023 + endloop + endfacet + facet normal 0.0653156 0.148673 0.986727 + outer loop + vertex 0.99473 1.84389 2.62083 + vertex 0.990626 1.84499 2.62094 + vertex 0.992313 1.84043 2.62151 + endloop + endfacet + facet normal 0.0610499 0.157877 0.98557 + outer loop + vertex 0.990626 1.84499 2.62094 + vertex 0.989012 1.8494 2.62033 + vertex 0.986498 1.84613 2.62101 + endloop + endfacet + facet normal 0.0765104 0.157796 0.984503 + outer loop + vertex 0.99495 1.84797 2.62016 + vertex 0.998744 1.85246 2.61915 + vertex 0.993848 1.85274 2.61948 + endloop + endfacet + facet normal 0.0624322 0.159451 0.98523 + outer loop + vertex 0.984383 1.84869 2.62074 + vertex 0.989012 1.8494 2.62033 + vertex 0.984705 1.85277 2.62006 + endloop + endfacet + facet normal 0.0683676 0.157613 0.985131 + outer loop + vertex 0.984705 1.85277 2.62006 + vertex 0.988761 1.8573 2.61905 + vertex 0.983795 1.85766 2.61934 + endloop + endfacet + facet normal 0.0594544 0.161429 0.985092 + outer loop + vertex 0.993848 1.85274 2.61948 + vertex 0.993563 1.85725 2.61876 + vertex 0.989736 1.85363 2.61959 + endloop + endfacet + facet normal 0.0646869 0.155338 0.985741 + outer loop + vertex 0.988761 1.8573 2.61905 + vertex 0.993152 1.86177 2.61806 + vertex 0.988383 1.86201 2.61833 + endloop + endfacet + facet normal 0.0649186 0.155597 0.985685 + outer loop + vertex 0.99826 1.85712 2.61847 + vertex 0.997798 1.86184 2.61776 + vertex 0.993563 1.85725 2.61876 + endloop + endfacet + facet normal 0.0621709 0.154223 0.986078 + outer loop + vertex 0.993152 1.86177 2.61806 + vertex 0.996722 1.86563 2.61723 + vertex 0.992701 1.8665 2.61735 + endloop + endfacet + facet normal 0.0856774 0.14909 0.985105 + outer loop + vertex 1.00243 1.8618 2.61736 + vertex 1.00131 1.86687 2.61669 + vertex 0.997798 1.86184 2.61776 + endloop + endfacet + facet normal 0.0621955 0.154339 0.986058 + outer loop + vertex 0.996722 1.86563 2.61723 + vertex 0.997185 1.87023 2.61648 + vertex 0.992701 1.8665 2.61735 + endloop + endfacet + facet normal 0.0727982 0.155879 0.98509 + outer loop + vertex 1.00168 1.87122 2.61599 + vertex 0.999705 1.87377 2.61573 + vertex 0.997185 1.87023 2.61648 + endloop + endfacet + facet normal 0.10009 0.176454 0.979207 + outer loop + vertex 0.999705 1.87377 2.61573 + vertex 1.00168 1.87122 2.61599 + vertex 1.00424 1.87453 2.61513 + endloop + endfacet + facet normal 0.0654637 0.161045 0.984774 + outer loop + vertex 0.999705 1.87377 2.61573 + vertex 0.995566 1.87482 2.61584 + vertex 0.997185 1.87023 2.61648 + endloop + endfacet + facet normal 0.066064 0.171968 0.982885 + outer loop + vertex 0.995566 1.87482 2.61584 + vertex 0.994033 1.87931 2.61515 + vertex 0.991408 1.87593 2.61592 + endloop + endfacet + facet normal 0.0638171 0.178714 0.981829 + outer loop + vertex 0.994033 1.87931 2.61515 + vertex 0.998863 1.88272 2.61422 + vertex 0.994764 1.88363 2.61432 + endloop + endfacet + facet normal 0.0929455 0.160765 0.982607 + outer loop + vertex 1.00491 1.87876 2.61439 + vertex 1.00372 1.88242 2.6139 + vertex 0.999996 1.87792 2.61499 + endloop + endfacet + facet normal 0.0659417 0.17804 0.981811 + outer loop + vertex 0.998863 1.88272 2.61422 + vertex 1.00296 1.88682 2.6132 + vertex 0.99841 1.88718 2.61344 + endloop + endfacet + facet normal 0.127693 0.147387 0.980801 + outer loop + vertex 1.00834 1.88202 2.61336 + vertex 1.00745 1.88665 2.61278 + vertex 1.00372 1.88242 2.6139 + endloop + endfacet + facet normal 0.0790843 0.175503 0.981297 + outer loop + vertex 1.00296 1.88682 2.6132 + vertex 1.00627 1.8904 2.61229 + vertex 1.00248 1.89128 2.61244 + endloop + endfacet + facet normal 0.0794838 0.177267 0.980948 + outer loop + vertex 1.00627 1.8904 2.61229 + vertex 1.00688 1.89482 2.61145 + vertex 1.00248 1.89128 2.61244 + endloop + endfacet + facet normal 0.124938 0.166053 0.97817 + outer loop + vertex 1.01114 1.89565 2.61076 + vertex 1.00958 1.89832 2.61051 + vertex 1.00688 1.89482 2.61145 + endloop + endfacet + facet normal 0.105886 0.180658 0.97783 + outer loop + vertex 1.00958 1.89832 2.61051 + vertex 1.00552 1.89934 2.61076 + vertex 1.00688 1.89482 2.61145 + endloop + endfacet + facet normal 0.0754048 0.177403 0.981245 + outer loop + vertex 1.00552 1.89934 2.61076 + vertex 1.00057 1.90031 2.61096 + vertex 1.00168 1.89588 2.61168 + endloop + endfacet + facet normal 0.070997 0.181176 0.980885 + outer loop + vertex 1.00057 1.90031 2.61096 + vertex 0.999119 1.90469 2.61026 + vertex 0.996511 1.90119 2.61109 + endloop + endfacet + facet normal 0.0714618 0.186565 0.97984 + outer loop + vertex 0.999119 1.90469 2.61026 + vertex 1.00376 1.90796 2.6093 + vertex 0.999861 1.90881 2.60942 + endloop + endfacet + facet normal 0.0987162 0.169 0.98066 + outer loop + vertex 1.01002 1.90251 2.60968 + vertex 1.00864 1.90738 2.60898 + vertex 1.0045 1.90365 2.61004 + endloop + endfacet + facet normal 0.0759017 0.187625 0.979304 + outer loop + vertex 1.00376 1.90796 2.6093 + vertex 1.0077 1.91188 2.60824 + vertex 1.00323 1.91207 2.60855 + endloop + endfacet + facet normal 0.121648 0.168328 0.978196 + outer loop + vertex 1.01342 1.90687 2.60848 + vertex 1.01254 1.91154 2.60778 + vertex 1.00864 1.90738 2.60898 + endloop + endfacet + facet normal 0.0870536 0.187698 0.978361 + outer loop + vertex 1.0077 1.91188 2.60824 + vertex 1.0111 1.91666 2.60702 + vertex 1.00648 1.9155 2.60766 + endloop + endfacet + facet normal 0.118992 0.180152 0.976415 + outer loop + vertex 1.01154 1.92113 2.60614 + vertex 1.0111 1.91666 2.60702 + vertex 1.01538 1.91998 2.60589 + endloop + endfacet + facet normal 0.121028 0.187277 0.974823 + outer loop + vertex 1.01538 1.91998 2.60589 + vertex 1.01426 1.9246 2.60514 + vertex 1.01154 1.92113 2.60614 + endloop + endfacet + facet normal 0.193408 0.168168 0.966599 + outer loop + vertex 1.01972 1.92288 2.60458 + vertex 1.0229 1.92711 2.6032 + vertex 1.01861 1.92763 2.60397 + endloop + endfacet + facet normal 0.19216 0.154224 0.969169 + outer loop + vertex 1.0229 1.92711 2.6032 + vertex 1.02154 1.93078 2.60289 + vertex 1.01861 1.92763 2.60397 + endloop + endfacet + facet normal 0.15997 0.184368 0.969751 + outer loop + vertex 1.01861 1.92763 2.60397 + vertex 1.02154 1.93078 2.60289 + vertex 1.01794 1.93176 2.6033 + endloop + endfacet + facet normal 0.160031 0.184616 0.969694 + outer loop + vertex 1.02154 1.93078 2.60289 + vertex 1.02167 1.9357 2.60193 + vertex 1.01794 1.93176 2.6033 + endloop + endfacet + facet normal 0.103406 0.197471 0.97484 + outer loop + vertex 1.00969 1.92378 2.60579 + vertex 1.01426 1.9246 2.60514 + vertex 1.01008 1.928 2.60489 + endloop + endfacet + facet normal 0.0894322 0.201033 0.975494 + outer loop + vertex 1.01008 1.928 2.60489 + vertex 1.01353 1.93216 2.60372 + vertex 1.00881 1.93273 2.60403 + endloop + endfacet + facet normal 0.131524 0.180521 0.974738 + outer loop + vertex 1.01861 1.92763 2.60397 + vertex 1.01794 1.93176 2.6033 + vertex 1.01489 1.92878 2.60426 + endloop + endfacet + facet normal 0.100409 0.202294 0.974164 + outer loop + vertex 1.01353 1.93216 2.60372 + vertex 1.01669 1.93529 2.60274 + vertex 1.01261 1.93647 2.60292 + endloop + endfacet + facet normal 0.0991762 0.197878 0.975197 + outer loop + vertex 1.01669 1.93529 2.60274 + vertex 1.01712 1.93982 2.60178 + vertex 1.01261 1.93647 2.60292 + endloop + endfacet + facet normal 0.123798 0.183506 0.975192 + outer loop + vertex 1.02172 1.94049 2.60107 + vertex 1.01983 1.94344 2.60076 + vertex 1.01712 1.93982 2.60178 + endloop + endfacet + facet normal 0.103582 0.198497 0.974613 + outer loop + vertex 1.01983 1.94344 2.60076 + vertex 1.01558 1.94475 2.60094 + vertex 1.01712 1.93982 2.60178 + endloop + endfacet + facet normal 0.0861814 0.207107 0.974515 + outer loop + vertex 1.01558 1.94475 2.60094 + vertex 1.01416 1.94945 2.60007 + vertex 1.0114 1.9459 2.60106 + endloop + endfacet + facet normal 0.125003 0.183098 0.975115 + outer loop + vertex 1.02461 1.94842 2.59915 + vertex 1.02337 1.95201 2.59863 + vertex 1.02006 1.9478 2.59984 + endloop + endfacet + facet normal 0.142906 0.210002 0.967201 + outer loop + vertex 1.02337 1.95201 2.59863 + vertex 1.02754 1.9554 2.59728 + vertex 1.02247 1.9565 2.59779 + endloop + endfacet + facet normal 0.138406 0.186831 0.972593 + outer loop + vertex 1.02754 1.9554 2.59728 + vertex 1.02608 1.96027 2.59655 + vertex 1.02247 1.9565 2.59779 + endloop + endfacet + facet normal 0.113245 0.210468 0.971019 + outer loop + vertex 1.02247 1.9565 2.59779 + vertex 1.02608 1.96027 2.59655 + vertex 1.02095 1.9614 2.5969 + endloop + endfacet + facet normal 0.110541 0.197205 0.97411 + outer loop + vertex 1.02608 1.96027 2.59655 + vertex 1.02526 1.96469 2.59575 + vertex 1.02095 1.9614 2.5969 + endloop + endfacet + facet normal 0.145882 0.202716 0.96831 + outer loop + vertex 1.02912 1.96328 2.59546 + vertex 1.02526 1.96469 2.59575 + vertex 1.02608 1.96027 2.59655 + endloop + endfacet + facet normal 0.175551 0.173129 0.969128 + outer loop + vertex 1.03063 1.95961 2.59584 + vertex 1.02912 1.96328 2.59546 + vertex 1.02608 1.96027 2.59655 + endloop + endfacet + facet normal 0.178249 0.197518 0.963957 + outer loop + vertex 1.02608 1.96027 2.59655 + vertex 1.02754 1.9554 2.59728 + vertex 1.03063 1.95961 2.59584 + endloop + endfacet + facet normal 0.222278 0.191065 0.956079 + outer loop + vertex 1.02912 1.96328 2.59546 + vertex 1.03063 1.95961 2.59584 + vertex 1.03357 1.96362 2.59436 + endloop + endfacet + facet normal 0.222422 0.189849 0.956287 + outer loop + vertex 1.02912 1.96328 2.59546 + vertex 1.03357 1.96362 2.59436 + vertex 1.0297 1.96767 2.59446 + endloop + endfacet + facet normal 0.200269 0.168494 0.965144 + outer loop + vertex 1.0297 1.96767 2.59446 + vertex 1.03357 1.96362 2.59436 + vertex 1.03435 1.96815 2.59341 + endloop + endfacet + facet normal 0.201033 0.16289 0.965946 + outer loop + vertex 1.03435 1.96815 2.59341 + vertex 1.03283 1.97189 2.59309 + vertex 1.0297 1.96767 2.59446 + endloop + endfacet + facet normal 0.158956 0.194686 0.9679 + outer loop + vertex 1.0297 1.96767 2.59446 + vertex 1.03283 1.97189 2.59309 + vertex 1.02842 1.97242 2.59371 + endloop + endfacet + facet normal 0.128537 0.187396 0.973838 + outer loop + vertex 1.0297 1.96767 2.59446 + vertex 1.02842 1.97242 2.59371 + vertex 1.02408 1.96931 2.59488 + endloop + endfacet + facet normal 0.13646 0.21631 0.966741 + outer loop + vertex 1.02408 1.96931 2.59488 + vertex 1.02526 1.96469 2.59575 + vertex 1.0297 1.96767 2.59446 + endloop + endfacet + facet normal 0.157978 0.183738 0.970198 + outer loop + vertex 1.03283 1.97189 2.59309 + vertex 1.03134 1.97541 2.59267 + vertex 1.02842 1.97242 2.59371 + endloop + endfacet + facet normal 0.128833 0.211635 0.96882 + outer loop + vertex 1.02842 1.97242 2.59371 + vertex 1.03134 1.97541 2.59267 + vertex 1.02762 1.97659 2.59291 + endloop + endfacet + facet normal 0.145923 0.202836 0.968279 + outer loop + vertex 1.02526 1.96469 2.59575 + vertex 1.02912 1.96328 2.59546 + vertex 1.0297 1.96767 2.59446 + endloop + endfacet + facet normal 0.082955 0.209985 0.974179 + outer loop + vertex 1.01872 1.9527 2.59897 + vertex 1.0178 1.95693 2.59814 + vertex 1.01473 1.95371 2.5991 + endloop + endfacet + facet normal 0.0832121 0.211033 0.973931 + outer loop + vertex 1.01416 1.94945 2.60007 + vertex 1.01872 1.9527 2.59897 + vertex 1.01473 1.95371 2.5991 + endloop + endfacet + facet normal 0.0850905 0.207934 0.974435 + outer loop + vertex 1.00946 1.94857 2.60067 + vertex 1.0114 1.9459 2.60106 + vertex 1.01416 1.94945 2.60007 + endloop + endfacet + facet normal 0.0899213 0.20519 0.974583 + outer loop + vertex 1.00946 1.94857 2.60067 + vertex 1.00541 1.94966 2.60081 + vertex 1.00681 1.94492 2.60168 + endloop + endfacet + facet normal 0.0898286 0.205165 0.974596 + outer loop + vertex 1.00681 1.94492 2.60168 + vertex 1.00541 1.94966 2.60081 + vertex 1.00111 1.94635 2.6019 + endloop + endfacet + facet normal 0.0853325 0.201094 0.975848 + outer loop + vertex 0.996897 1.94968 2.60158 + vertex 0.996463 1.94534 2.60252 + vertex 1.00111 1.94635 2.6019 + endloop + endfacet + facet normal 0.0928509 0.206095 0.974117 + outer loop + vertex 0.999459 1.95332 2.6006 + vertex 1.00136 1.95074 2.60097 + vertex 1.00411 1.95429 2.59996 + endloop + endfacet + facet normal 0.0770123 0.201501 0.976456 + outer loop + vertex 0.996897 1.94968 2.60158 + vertex 0.995421 1.95419 2.60077 + vertex 0.991599 1.9507 2.60179 + endloop + endfacet + facet normal 0.0765451 0.203215 0.976138 + outer loop + vertex 0.99051 1.95512 2.60096 + vertex 0.995421 1.95419 2.60077 + vertex 0.994449 1.95853 2.59994 + endloop + endfacet + facet normal 0.083217 0.203384 0.975556 + outer loop + vertex 0.994449 1.95853 2.59994 + vertex 0.998566 1.96227 2.59881 + vertex 0.993714 1.96288 2.5991 + endloop + endfacet + facet normal 0.0919266 0.201927 0.975077 + outer loop + vertex 1.00332 1.96193 2.59843 + vertex 1.00244 1.96614 2.59765 + vertex 0.998566 1.96227 2.59881 + endloop + endfacet + facet normal 0.0930804 0.205116 0.974302 + outer loop + vertex 0.999459 1.95332 2.6006 + vertex 1.00411 1.95429 2.59996 + vertex 0.999919 1.95755 2.59967 + endloop + endfacet + facet normal 0.09352 0.208703 0.973497 + outer loop + vertex 1.00989 1.95284 2.59971 + vertex 1.00869 1.9576 2.59881 + vertex 1.00411 1.95429 2.59996 + endloop + endfacet + facet normal 0.0970652 0.20267 0.974425 + outer loop + vertex 1.00472 1.95859 2.59899 + vertex 1.0078 1.96183 2.59801 + vertex 1.00332 1.96193 2.59843 + endloop + endfacet + facet normal 0.0906114 0.206749 0.974189 + outer loop + vertex 1.01333 1.95706 2.59849 + vertex 1.0124 1.96132 2.59767 + vertex 1.00869 1.9576 2.59881 + endloop + endfacet + facet normal 0.0971007 0.202067 0.974546 + outer loop + vertex 1.0078 1.96183 2.59801 + vertex 1.011 1.9662 2.59678 + vertex 1.00635 1.96522 2.59745 + endloop + endfacet + facet normal 0.0862603 0.205786 0.974788 + outer loop + vertex 1.01634 1.96032 2.59753 + vertex 1.01674 1.96476 2.59656 + vertex 1.0124 1.96132 2.59767 + endloop + endfacet + facet normal 0.0987507 0.207951 0.973142 + outer loop + vertex 1.01125 1.97058 2.59582 + vertex 1.00678 1.96955 2.5965 + vertex 1.011 1.9662 2.59678 + endloop + endfacet + facet normal 0.0983412 0.209529 0.972845 + outer loop + vertex 1.01125 1.97058 2.59582 + vertex 1.00936 1.97321 2.59545 + vertex 1.00678 1.96955 2.5965 + endloop + endfacet + facet normal 0.100113 0.208305 0.972927 + outer loop + vertex 1.00936 1.97321 2.59545 + vertex 1.00536 1.97412 2.59566 + vertex 1.00678 1.96955 2.5965 + endloop + endfacet + facet normal 0.10435 0.20131 0.973954 + outer loop + vertex 1.01299 1.98186 2.5932 + vertex 1.01145 1.98534 2.59265 + vertex 1.00833 1.98205 2.59366 + endloop + endfacet + facet normal 0.105431 0.200315 0.974042 + outer loop + vertex 1.00833 1.98205 2.59366 + vertex 1.01145 1.98534 2.59265 + vertex 1.00752 1.98643 2.59285 + endloop + endfacet + facet normal 0.10026 0.199483 0.974759 + outer loop + vertex 1.00833 1.98205 2.59366 + vertex 1.00752 1.98643 2.59285 + vertex 1.00371 1.98281 2.59398 + endloop + endfacet + facet normal 0.0991233 0.20064 0.974637 + outer loop + vertex 1.00371 1.98281 2.59398 + vertex 1.00752 1.98643 2.59285 + vertex 1.00296 1.98695 2.59321 + endloop + endfacet + facet normal 0.0988095 0.197444 0.975322 + outer loop + vertex 1.00752 1.98643 2.59285 + vertex 1.00622 1.99135 2.59199 + vertex 1.00296 1.98695 2.59321 + endloop + endfacet + facet normal 0.094198 0.200787 0.975095 + outer loop + vertex 1.00296 1.98695 2.59321 + vertex 1.00622 1.99135 2.59199 + vertex 1.00153 1.99035 2.59264 + endloop + endfacet + facet normal 0.0873715 0.198093 0.976281 + outer loop + vertex 1.00296 1.98695 2.59321 + vertex 1.00153 1.99035 2.59264 + vertex 0.998465 1.98699 2.5936 + endloop + endfacet + facet normal 0.103974 0.198669 0.974536 + outer loop + vertex 1.00752 1.98643 2.59285 + vertex 1.01189 1.98983 2.59169 + vertex 1.00622 1.99135 2.59199 + endloop + endfacet + facet normal 0.104041 0.198927 0.974476 + outer loop + vertex 1.01189 1.98983 2.59169 + vertex 1.01054 1.99463 2.59085 + vertex 1.00622 1.99135 2.59199 + endloop + endfacet + facet normal 0.102415 0.200986 0.974226 + outer loop + vertex 1.0065 1.9958 2.59104 + vertex 1.00622 1.99135 2.59199 + vertex 1.01054 1.99463 2.59085 + endloop + endfacet + facet normal 0.105241 0.211165 0.971768 + outer loop + vertex 1.01054 1.99463 2.59085 + vertex 1.00917 1.99931 2.58999 + vertex 1.0065 1.9958 2.59104 + endloop + endfacet + facet normal 0.0996063 0.215357 0.971442 + outer loop + vertex 1.00455 1.99849 2.59064 + vertex 1.0065 1.9958 2.59104 + vertex 1.00917 1.99931 2.58999 + endloop + endfacet + facet normal 0.0978129 0.224011 0.969666 + outer loop + vertex 1.00455 1.99849 2.59064 + vertex 1.00917 1.99931 2.58999 + vertex 1.00484 2.00272 2.58963 + endloop + endfacet + facet normal 0.096054 0.221847 0.970339 + outer loop + vertex 1.00484 2.00272 2.58963 + vertex 1.00917 1.99931 2.58999 + vertex 1.00962 2.00352 2.58898 + endloop + endfacet + facet normal 0.0953192 0.22559 0.969548 + outer loop + vertex 1.00962 2.00352 2.58898 + vertex 1.00802 2.00692 2.58835 + vertex 1.00484 2.00272 2.58963 + endloop + endfacet + facet normal 0.0932144 0.227134 0.969392 + outer loop + vertex 1.00484 2.00272 2.58963 + vertex 1.00802 2.00692 2.58835 + vertex 1.00338 2.0073 2.5887 + endloop + endfacet + facet normal 0.088092 0.225667 0.970214 + outer loop + vertex 1.00484 2.00272 2.58963 + vertex 1.00338 2.0073 2.5887 + vertex 0.999017 2.00411 2.58984 + endloop + endfacet + facet normal 0.0878274 0.224516 0.970504 + outer loop + vertex 0.999017 2.00411 2.58984 + vertex 1.00043 1.99954 2.59077 + vertex 1.00484 2.00272 2.58963 + endloop + endfacet + facet normal 0.0875282 0.224908 0.970441 + outer loop + vertex 1.00043 1.99954 2.59077 + vertex 1.00455 1.99849 2.59064 + vertex 1.00484 2.00272 2.58963 + endloop + endfacet + facet normal 0.0846058 0.213077 0.973365 + outer loop + vertex 1.00455 1.99849 2.59064 + vertex 1.00043 1.99954 2.59077 + vertex 1.0019 1.99482 2.59167 + endloop + endfacet + facet normal 0.0803155 0.211861 0.973994 + outer loop + vertex 1.0019 1.99482 2.59167 + vertex 1.00043 1.99954 2.59077 + vertex 0.996072 1.99615 2.59187 + endloop + endfacet + facet normal 0.079425 0.207833 0.974934 + outer loop + vertex 0.997481 1.99126 2.59279 + vertex 1.0019 1.99482 2.59167 + vertex 0.996072 1.99615 2.59187 + endloop + endfacet + facet normal 0.0820598 0.204704 0.975378 + outer loop + vertex 1.00153 1.99035 2.59264 + vertex 1.0019 1.99482 2.59167 + vertex 0.997481 1.99126 2.59279 + endloop + endfacet + facet normal 0.0935316 0.203565 0.974584 + outer loop + vertex 1.0019 1.99482 2.59167 + vertex 1.00153 1.99035 2.59264 + vertex 1.00622 1.99135 2.59199 + endloop + endfacet + facet normal 0.0795005 0.212863 0.973842 + outer loop + vertex 0.996318 2.00054 2.59089 + vertex 0.996072 1.99615 2.59187 + vertex 1.00043 1.99954 2.59077 + endloop + endfacet + facet normal 0.0750539 0.213175 0.974127 + outer loop + vertex 0.996318 2.00054 2.59089 + vertex 0.991811 1.99943 2.59148 + vertex 0.996072 1.99615 2.59187 + endloop + endfacet + facet normal 0.0722989 0.209707 0.975088 + outer loop + vertex 0.991811 1.99943 2.59148 + vertex 0.991348 1.9951 2.59244 + vertex 0.996072 1.99615 2.59187 + endloop + endfacet + facet normal 0.0737937 0.217804 0.973199 + outer loop + vertex 0.996318 2.00054 2.59089 + vertex 0.99437 2.00309 2.59046 + vertex 0.991811 1.99943 2.59148 + endloop + endfacet + facet normal 0.0760746 0.216257 0.973368 + outer loop + vertex 0.99437 2.00309 2.59046 + vertex 0.990295 2.00394 2.59059 + vertex 0.991811 1.99943 2.59148 + endloop + endfacet + facet normal 0.073396 0.215432 0.973757 + outer loop + vertex 0.991811 1.99943 2.59148 + vertex 0.990295 2.00394 2.59059 + vertex 0.986497 2.00047 2.59165 + endloop + endfacet + facet normal 0.0720386 0.208206 0.975428 + outer loop + vertex 0.987451 1.996 2.59253 + vertex 0.991811 1.99943 2.59148 + vertex 0.986497 2.00047 2.59165 + endloop + endfacet + facet normal 0.0709291 0.207994 0.975555 + outer loop + vertex 0.987451 1.996 2.59253 + vertex 0.986497 2.00047 2.59165 + vertex 0.982608 1.99657 2.59276 + endloop + endfacet + facet normal 0.0703732 0.202815 0.976685 + outer loop + vertex 0.983627 1.99212 2.59361 + vertex 0.987451 1.996 2.59253 + vertex 0.982608 1.99657 2.59276 + endloop + endfacet + facet normal 0.0700933 0.208797 0.975444 + outer loop + vertex 0.982608 1.99657 2.59276 + vertex 0.986497 2.00047 2.59165 + vertex 0.981072 2.0014 2.59184 + endloop + endfacet + facet normal 0.0645075 0.207161 0.976178 + outer loop + vertex 0.982608 1.99657 2.59276 + vertex 0.981072 2.0014 2.59184 + vertex 0.977687 1.99672 2.59306 + endloop + endfacet + facet normal 0.0644604 0.204389 0.976765 + outer loop + vertex 0.978664 1.99227 2.59392 + vertex 0.982608 1.99657 2.59276 + vertex 0.977687 1.99672 2.59306 + endloop + endfacet + facet normal 0.0706418 0.209902 0.975167 + outer loop + vertex 0.991348 1.9951 2.59244 + vertex 0.991811 1.99943 2.59148 + vertex 0.987451 1.996 2.59253 + endloop + endfacet + facet normal 0.0754199 0.21331 0.974069 + outer loop + vertex 0.990295 2.00394 2.59059 + vertex 0.985369 2.00488 2.59077 + vertex 0.986497 2.00047 2.59165 + endloop + endfacet + facet normal 0.076245 0.21783 0.973004 + outer loop + vertex 0.985369 2.00488 2.59077 + vertex 0.990295 2.00394 2.59059 + vertex 0.989267 2.00826 2.58971 + endloop + endfacet + facet normal 0.0804362 0.218717 0.972468 + outer loop + vertex 0.989267 2.00826 2.58971 + vertex 0.990295 2.00394 2.59059 + vertex 0.994734 2.0073 2.58947 + endloop + endfacet + facet normal 0.080498 0.219091 0.972378 + outer loop + vertex 0.994734 2.0073 2.58947 + vertex 0.993189 2.01182 2.58858 + vertex 0.989267 2.00826 2.58971 + endloop + endfacet + facet normal 0.0808123 0.21876 0.972427 + outer loop + vertex 0.989267 2.00826 2.58971 + vertex 0.993189 2.01182 2.58858 + vertex 0.988499 2.01257 2.5888 + endloop + endfacet + facet normal 0.074696 0.217818 0.973127 + outer loop + vertex 0.989267 2.00826 2.58971 + vertex 0.988499 2.01257 2.5888 + vertex 0.983941 2.00927 2.58989 + endloop + endfacet + facet normal 0.0722702 0.22099 0.972595 + outer loop + vertex 0.983941 2.00927 2.58989 + vertex 0.988499 2.01257 2.5888 + vertex 0.984544 2.0135 2.58888 + endloop + endfacet + facet normal 0.0727475 0.223066 0.972085 + outer loop + vertex 0.988499 2.01257 2.5888 + vertex 0.987791 2.01672 2.5879 + vertex 0.984544 2.0135 2.58888 + endloop + endfacet + facet normal 0.0637127 0.231738 0.97069 + outer loop + vertex 0.984544 2.0135 2.58888 + vertex 0.987791 2.01672 2.5879 + vertex 0.982955 2.01693 2.58817 + endloop + endfacet + facet normal 0.0637023 0.231392 0.970773 + outer loop + vertex 0.987791 2.01672 2.5879 + vertex 0.9866 2.02089 2.58699 + vertex 0.982955 2.01693 2.58817 + endloop + endfacet + facet normal 0.0719954 0.233524 0.969682 + outer loop + vertex 0.987791 2.01672 2.5879 + vertex 0.991582 2.02029 2.58676 + vertex 0.9866 2.02089 2.58699 + endloop + endfacet + facet normal 0.077416 0.22375 0.971567 + outer loop + vertex 0.988499 2.01257 2.5888 + vertex 0.992401 2.01603 2.58769 + vertex 0.987791 2.01672 2.5879 + endloop + endfacet + facet normal 0.0779449 0.227513 0.970651 + outer loop + vertex 0.992401 2.01603 2.58769 + vertex 0.991582 2.02029 2.58676 + vertex 0.987791 2.01672 2.5879 + endloop + endfacet + facet normal 0.0810996 0.228034 0.97027 + outer loop + vertex 0.992401 2.01603 2.58769 + vertex 0.996795 2.01939 2.58654 + vertex 0.991582 2.02029 2.58676 + endloop + endfacet + facet normal 0.082117 0.234303 0.968689 + outer loop + vertex 0.996795 2.01939 2.58654 + vertex 0.995346 2.02383 2.58559 + vertex 0.991582 2.02029 2.58676 + endloop + endfacet + facet normal 0.0785465 0.237911 0.968106 + outer loop + vertex 0.995346 2.02383 2.58559 + vertex 0.990427 2.02449 2.58582 + vertex 0.991582 2.02029 2.58676 + endloop + endfacet + facet normal 0.0723059 0.236385 0.968965 + outer loop + vertex 0.991582 2.02029 2.58676 + vertex 0.990427 2.02449 2.58582 + vertex 0.9866 2.02089 2.58699 + endloop + endfacet + facet normal 0.069001 0.239716 0.968388 + outer loop + vertex 0.990427 2.02449 2.58582 + vertex 0.9855 2.02508 2.58603 + vertex 0.9866 2.02089 2.58699 + endloop + endfacet + facet normal 0.0689813 0.239538 0.968433 + outer loop + vertex 0.9855 2.02508 2.58603 + vertex 0.990427 2.02449 2.58582 + vertex 0.989328 2.02859 2.58489 + endloop + endfacet + facet normal 0.0788935 0.241885 0.967092 + outer loop + vertex 0.989328 2.02859 2.58489 + vertex 0.990427 2.02449 2.58582 + vertex 0.994308 2.02802 2.58462 + endloop + endfacet + facet normal 0.0783968 0.236973 0.968348 + outer loop + vertex 0.994308 2.02802 2.58462 + vertex 0.99321 2.03209 2.58372 + vertex 0.989328 2.02859 2.58489 + endloop + endfacet + facet normal 0.0796745 0.23563 0.968571 + outer loop + vertex 0.989328 2.02859 2.58489 + vertex 0.99321 2.03209 2.58372 + vertex 0.9886 2.03272 2.58394 + endloop + endfacet + facet normal 0.0625933 0.233049 0.970449 + outer loop + vertex 0.989328 2.02859 2.58489 + vertex 0.9886 2.03272 2.58394 + vertex 0.984013 2.02923 2.58508 + endloop + endfacet + facet normal 0.0789251 0.229634 0.970072 + outer loop + vertex 0.99321 2.03209 2.58372 + vertex 0.992483 2.0362 2.5828 + vertex 0.9886 2.03272 2.58394 + endloop + endfacet + facet normal 0.0904032 0.231352 0.968661 + outer loop + vertex 0.99321 2.03209 2.58372 + vertex 0.996366 2.03519 2.58268 + vertex 0.992483 2.0362 2.5828 + endloop + endfacet + facet normal 0.0883135 0.233382 0.968367 + outer loop + vertex 0.997921 2.03175 2.58337 + vertex 0.996366 2.03519 2.58268 + vertex 0.99321 2.03209 2.58372 + endloop + endfacet + facet normal 0.0951946 0.236221 0.967025 + outer loop + vertex 0.997921 2.03175 2.58337 + vertex 1.00105 2.03614 2.58199 + vertex 0.996366 2.03519 2.58268 + endloop + endfacet + facet normal 0.0937948 0.237187 0.966926 + outer loop + vertex 1.00272 2.03148 2.58297 + vertex 1.00105 2.03614 2.58199 + vertex 0.997921 2.03175 2.58337 + endloop + endfacet + facet normal 0.0940404 0.244552 0.965065 + outer loop + vertex 0.999674 2.02725 2.58434 + vertex 1.00272 2.03148 2.58297 + vertex 0.997921 2.03175 2.58337 + endloop + endfacet + facet normal 0.086092 0.241762 0.966509 + outer loop + vertex 0.999674 2.02725 2.58434 + vertex 0.997921 2.03175 2.58337 + vertex 0.994308 2.02802 2.58462 + endloop + endfacet + facet normal 0.0862949 0.243331 0.966097 + outer loop + vertex 0.994308 2.02802 2.58462 + vertex 0.995346 2.02383 2.58559 + vertex 0.999674 2.02725 2.58434 + endloop + endfacet + facet normal 0.0845545 0.245397 0.965728 + outer loop + vertex 0.995346 2.02383 2.58559 + vertex 0.999386 2.0231 2.58542 + vertex 0.999674 2.02725 2.58434 + endloop + endfacet + facet normal 0.0919475 0.24475 0.965217 + outer loop + vertex 0.999386 2.0231 2.58542 + vertex 1.00392 2.02407 2.58474 + vertex 0.999674 2.02725 2.58434 + endloop + endfacet + facet normal 0.0928772 0.245941 0.964825 + outer loop + vertex 0.999674 2.02725 2.58434 + vertex 1.00392 2.02407 2.58474 + vertex 1.00419 2.02815 2.58367 + endloop + endfacet + facet normal 0.093737 0.237511 0.966851 + outer loop + vertex 0.999386 2.0231 2.58542 + vertex 1.00129 2.02053 2.58586 + vertex 1.00392 2.02407 2.58474 + endloop + endfacet + facet normal 0.086102 0.2322 0.96885 + outer loop + vertex 1.00129 2.02053 2.58586 + vertex 0.999386 2.0231 2.58542 + vertex 0.996795 2.01939 2.58654 + endloop + endfacet + facet normal 0.0883934 0.224151 0.970537 + outer loop + vertex 1.00129 2.02053 2.58586 + vertex 0.996795 2.01939 2.58654 + vertex 1.00104 2.01614 2.5869 + endloop + endfacet + facet normal 0.0928686 0.223811 0.970198 + outer loop + vertex 1.00129 2.02053 2.58586 + vertex 1.00104 2.01614 2.5869 + vertex 1.00534 2.01944 2.58573 + endloop + endfacet + facet normal 0.0934874 0.223049 0.970314 + outer loop + vertex 1.00676 2.0147 2.58668 + vertex 1.00534 2.01944 2.58573 + vertex 1.00104 2.01614 2.5869 + endloop + endfacet + facet normal 0.0930281 0.221144 0.970794 + outer loop + vertex 1.00254 2.01146 2.58782 + vertex 1.00676 2.0147 2.58668 + vertex 1.00104 2.01614 2.5869 + endloop + endfacet + facet normal 0.0892908 0.22006 0.971391 + outer loop + vertex 1.00254 2.01146 2.58782 + vertex 1.00104 2.01614 2.5869 + vertex 0.997914 2.01172 2.58819 + endloop + endfacet + facet normal 0.0893795 0.222423 0.970845 + outer loop + vertex 0.9995 2.00836 2.58881 + vertex 1.00254 2.01146 2.58782 + vertex 0.997914 2.01172 2.58819 + endloop + endfacet + facet normal 0.0850567 0.220533 0.971664 + outer loop + vertex 0.9995 2.00836 2.58881 + vertex 0.997914 2.01172 2.58819 + vertex 0.994734 2.0073 2.58947 + endloop + endfacet + facet normal 0.0839005 0.225156 0.970704 + outer loop + vertex 0.994734 2.0073 2.58947 + vertex 0.999017 2.00411 2.58984 + vertex 0.9995 2.00836 2.58881 + endloop + endfacet + facet normal 0.081596 0.222165 0.971589 + outer loop + vertex 0.99437 2.00309 2.59046 + vertex 0.999017 2.00411 2.58984 + vertex 0.994734 2.0073 2.58947 + endloop + endfacet + facet normal 0.088625 0.223133 0.970751 + outer loop + vertex 1.00338 2.0073 2.5887 + vertex 1.00254 2.01146 2.58782 + vertex 0.9995 2.00836 2.58881 + endloop + endfacet + facet normal 0.0932704 0.223939 0.97013 + outer loop + vertex 1.00338 2.0073 2.5887 + vertex 1.00641 2.01034 2.58771 + vertex 1.00254 2.01146 2.58782 + endloop + endfacet + facet normal 0.0889686 0.220282 0.97137 + outer loop + vertex 0.997914 2.01172 2.58819 + vertex 1.00104 2.01614 2.5869 + vertex 0.996322 2.01509 2.58757 + endloop + endfacet + facet normal 0.0850734 0.218576 0.972104 + outer loop + vertex 0.997914 2.01172 2.58819 + vertex 0.996322 2.01509 2.58757 + vertex 0.993189 2.01182 2.58858 + endloop + endfacet + facet normal 0.083231 0.220275 0.97188 + outer loop + vertex 0.993189 2.01182 2.58858 + vertex 0.996322 2.01509 2.58757 + vertex 0.992401 2.01603 2.58769 + endloop + endfacet + facet normal 0.092624 0.221644 0.970719 + outer loop + vertex 1.00641 2.01034 2.58771 + vertex 1.00676 2.0147 2.58668 + vertex 1.00254 2.01146 2.58782 + endloop + endfacet + facet normal 0.0962514 0.221284 0.970448 + outer loop + vertex 1.00676 2.0147 2.58668 + vertex 1.00641 2.01034 2.58771 + vertex 1.01109 2.01122 2.58705 + endloop + endfacet + facet normal 0.0962482 0.22128 0.970449 + outer loop + vertex 1.01131 2.01559 2.58603 + vertex 1.00676 2.0147 2.58668 + vertex 1.01109 2.01122 2.58705 + endloop + endfacet + facet normal 0.100663 0.22097 0.970072 + outer loop + vertex 1.01131 2.01559 2.58603 + vertex 1.01109 2.01122 2.58705 + vertex 1.01539 2.01447 2.58586 + endloop + endfacet + facet normal 0.100413 0.221282 0.970026 + outer loop + vertex 1.01684 2.00974 2.58679 + vertex 1.01539 2.01447 2.58586 + vertex 1.01109 2.01122 2.58705 + endloop + endfacet + facet normal 0.101188 0.224443 0.969219 + outer loop + vertex 1.01263 2.00651 2.58797 + vertex 1.01684 2.00974 2.58679 + vertex 1.01109 2.01122 2.58705 + endloop + endfacet + facet normal 0.0978927 0.223471 0.969782 + outer loop + vertex 1.01263 2.00651 2.58797 + vertex 1.01109 2.01122 2.58705 + vertex 1.00802 2.00692 2.58835 + endloop + endfacet + facet normal 0.102706 0.222563 0.969493 + outer loop + vertex 1.01649 2.00537 2.58783 + vertex 1.01684 2.00974 2.58679 + vertex 1.01263 2.00651 2.58797 + endloop + endfacet + facet normal 0.102796 0.222875 0.969412 + outer loop + vertex 1.01349 2.00236 2.58884 + vertex 1.01649 2.00537 2.58783 + vertex 1.01263 2.00651 2.58797 + endloop + endfacet + facet normal 0.102291 0.222786 0.969486 + outer loop + vertex 1.01349 2.00236 2.58884 + vertex 1.01263 2.00651 2.58797 + vertex 1.00962 2.00352 2.58898 + endloop + endfacet + facet normal 0.106861 0.218971 0.969862 + outer loop + vertex 1.01807 2.00193 2.58843 + vertex 1.01649 2.00537 2.58783 + vertex 1.01349 2.00236 2.58884 + endloop + endfacet + facet normal 0.106562 0.214897 0.970806 + outer loop + vertex 1.0149 1.99774 2.5897 + vertex 1.01807 2.00193 2.58843 + vertex 1.01349 2.00236 2.58884 + endloop + endfacet + facet normal 0.106466 0.21487 0.970822 + outer loop + vertex 1.0149 1.99774 2.5897 + vertex 1.01349 2.00236 2.58884 + vertex 1.00917 1.99931 2.58999 + endloop + endfacet + facet normal 0.107109 0.219076 0.969811 + outer loop + vertex 1.01807 2.00193 2.58843 + vertex 1.02115 2.00626 2.58711 + vertex 1.01649 2.00537 2.58783 + endloop + endfacet + facet normal 0.108128 0.218367 0.969858 + outer loop + vertex 1.02263 2.00153 2.58801 + vertex 1.02115 2.00626 2.58711 + vertex 1.01807 2.00193 2.58843 + endloop + endfacet + facet normal 0.107808 0.213522 0.970971 + outer loop + vertex 1.01961 1.9985 2.58901 + vertex 1.02263 2.00153 2.58801 + vertex 1.01807 2.00193 2.58843 + endloop + endfacet + facet normal 0.107881 0.213452 0.970979 + outer loop + vertex 1.02343 1.99736 2.58884 + vertex 1.02263 2.00153 2.58801 + vertex 1.01961 1.9985 2.58901 + endloop + endfacet + facet normal 0.106441 0.208445 0.972225 + outer loop + vertex 1.0191 1.99426 2.58998 + vertex 1.02343 1.99736 2.58884 + vertex 1.01961 1.9985 2.58901 + endloop + endfacet + facet normal 0.105844 0.20924 0.972119 + outer loop + vertex 1.0248 1.99276 2.58968 + vertex 1.02343 1.99736 2.58884 + vertex 1.0191 1.99426 2.58998 + endloop + endfacet + facet normal 0.104336 0.203254 0.973551 + outer loop + vertex 1.0191 1.99426 2.58998 + vertex 1.0204 1.98957 2.59082 + vertex 1.0248 1.99276 2.58968 + endloop + endfacet + facet normal 0.102008 0.206324 0.973152 + outer loop + vertex 1.0204 1.98957 2.59082 + vertex 1.02443 1.98844 2.59063 + vertex 1.0248 1.99276 2.58968 + endloop + endfacet + facet normal 0.10192 0.205997 0.97323 + outer loop + vertex 1.02443 1.98844 2.59063 + vertex 1.0204 1.98957 2.59082 + vertex 1.02178 1.9848 2.59168 + endloop + endfacet + facet normal 0.0990258 0.208059 0.973091 + outer loop + vertex 1.02635 1.98572 2.59102 + vertex 1.02443 1.98844 2.59063 + vertex 1.02178 1.9848 2.59168 + endloop + endfacet + facet normal 0.104118 0.211475 0.971822 + outer loop + vertex 1.02443 1.98844 2.59063 + vertex 1.02635 1.98572 2.59102 + vertex 1.02909 1.98929 2.58995 + endloop + endfacet + facet normal 0.100751 0.205691 0.973417 + outer loop + vertex 1.02178 1.9848 2.59168 + vertex 1.0204 1.98957 2.59082 + vertex 1.01611 1.9863 2.59195 + endloop + endfacet + facet normal 0.10011 0.203152 0.974016 + outer loop + vertex 1.01757 1.98154 2.5928 + vertex 1.02178 1.9848 2.59168 + vertex 1.01611 1.9863 2.59195 + endloop + endfacet + facet normal 0.105037 0.200302 0.974088 + outer loop + vertex 1.0164 1.99072 2.59101 + vertex 1.01611 1.9863 2.59195 + vertex 1.0204 1.98957 2.59082 + endloop + endfacet + facet normal 0.106868 0.200148 0.97392 + outer loop + vertex 1.0164 1.99072 2.59101 + vertex 1.01189 1.98983 2.59169 + vertex 1.01611 1.9863 2.59195 + endloop + endfacet + facet normal 0.104789 0.197712 0.974643 + outer loop + vertex 1.01189 1.98983 2.59169 + vertex 1.01145 1.98534 2.59265 + vertex 1.01611 1.9863 2.59195 + endloop + endfacet + facet normal 0.107049 0.199345 0.974065 + outer loop + vertex 1.0164 1.99072 2.59101 + vertex 1.01454 1.99346 2.59066 + vertex 1.01189 1.98983 2.59169 + endloop + endfacet + facet normal 0.109556 0.200968 0.973452 + outer loop + vertex 1.01454 1.99346 2.59066 + vertex 1.0164 1.99072 2.59101 + vertex 1.0191 1.99426 2.58998 + endloop + endfacet + facet normal 0.108334 0.206949 0.972335 + outer loop + vertex 1.01454 1.99346 2.59066 + vertex 1.0191 1.99426 2.58998 + vertex 1.0149 1.99774 2.5897 + endloop + endfacet + facet normal 0.108755 0.206905 0.972298 + outer loop + vertex 1.01054 1.99463 2.59085 + vertex 1.01454 1.99346 2.59066 + vertex 1.0149 1.99774 2.5897 + endloop + endfacet + facet normal 0.109269 0.208052 0.971995 + outer loop + vertex 1.0149 1.99774 2.5897 + vertex 1.0191 1.99426 2.58998 + vertex 1.01961 1.9985 2.58901 + endloop + endfacet + facet normal 0.108198 0.213684 0.970893 + outer loop + vertex 1.01961 1.9985 2.58901 + vertex 1.01807 2.00193 2.58843 + vertex 1.0149 1.99774 2.5897 + endloop + endfacet + facet normal 0.10597 0.203659 0.97329 + outer loop + vertex 1.0204 1.98957 2.59082 + vertex 1.0191 1.99426 2.58998 + vertex 1.0164 1.99072 2.59101 + endloop + endfacet + facet normal 0.104898 0.217462 0.970416 + outer loop + vertex 1.02263 2.00153 2.58801 + vertex 1.02687 2.00482 2.58682 + vertex 1.02115 2.00626 2.58711 + endloop + endfacet + facet normal 0.105045 0.217282 0.97044 + outer loop + vertex 1.02646 2.00043 2.58784 + vertex 1.02687 2.00482 2.58682 + vertex 1.02263 2.00153 2.58801 + endloop + endfacet + facet normal 0.103799 0.212794 0.971568 + outer loop + vertex 1.02343 1.99736 2.58884 + vertex 1.02646 2.00043 2.58784 + vertex 1.02263 2.00153 2.58801 + endloop + endfacet + facet normal 0.102743 0.213804 0.971459 + outer loop + vertex 1.02802 1.99702 2.58843 + vertex 1.02646 2.00043 2.58784 + vertex 1.02343 1.99736 2.58884 + endloop + endfacet + facet normal 0.106411 0.222194 0.969178 + outer loop + vertex 1.01684 2.00974 2.58679 + vertex 1.01649 2.00537 2.58783 + vertex 1.02115 2.00626 2.58711 + endloop + endfacet + facet normal 0.105685 0.221318 0.969458 + outer loop + vertex 1.02141 2.01068 2.58607 + vertex 1.01684 2.00974 2.58679 + vertex 1.02115 2.00626 2.58711 + endloop + endfacet + facet normal 0.107616 0.221166 0.96928 + outer loop + vertex 1.02141 2.01068 2.58607 + vertex 1.02115 2.00626 2.58711 + vertex 1.02547 2.00956 2.58588 + endloop + endfacet + facet normal 0.105757 0.221014 0.96952 + outer loop + vertex 1.02141 2.01068 2.58607 + vertex 1.01947 2.01339 2.58567 + vertex 1.01684 2.00974 2.58679 + endloop + endfacet + facet normal 0.095949 0.222608 0.970175 + outer loop + vertex 1.01131 2.01559 2.58603 + vertex 1.00938 2.0183 2.5856 + vertex 1.00676 2.0147 2.58668 + endloop + endfacet + facet normal 0.0954054 0.225203 0.969629 + outer loop + vertex 1.00802 2.00692 2.58835 + vertex 1.01109 2.01122 2.58705 + vertex 1.00641 2.01034 2.58771 + endloop + endfacet + facet normal 0.088091 0.22377 0.970653 + outer loop + vertex 0.996795 2.01939 2.58654 + vertex 0.996322 2.01509 2.58757 + vertex 1.00104 2.01614 2.5869 + endloop + endfacet + facet normal 0.0930386 0.245247 0.964986 + outer loop + vertex 1.00419 2.02815 2.58367 + vertex 1.00272 2.03148 2.58297 + vertex 0.999674 2.02725 2.58434 + endloop + endfacet + facet normal 0.0976924 0.247101 0.964052 + outer loop + vertex 1.00419 2.02815 2.58367 + vertex 1.00658 2.03058 2.58281 + vertex 1.00272 2.03148 2.58297 + endloop + endfacet + facet normal 0.0969229 0.24365 0.965008 + outer loop + vertex 1.00658 2.03058 2.58281 + vertex 1.00676 2.0347 2.58175 + vertex 1.00272 2.03148 2.58297 + endloop + endfacet + facet normal 0.0987757 0.243529 0.964851 + outer loop + vertex 1.00676 2.0347 2.58175 + vertex 1.00658 2.03058 2.58281 + vertex 1.0111 2.03123 2.58218 + endloop + endfacet + facet normal 0.0965225 0.248193 0.96389 + outer loop + vertex 1.00803 2.02718 2.58354 + vertex 1.00658 2.03058 2.58281 + vertex 1.00419 2.02815 2.58367 + endloop + endfacet + facet normal 0.100553 0.23935 0.965712 + outer loop + vertex 1.00272 2.03148 2.58297 + vertex 1.00676 2.0347 2.58175 + vertex 1.00105 2.03614 2.58199 + endloop + endfacet + facet normal 0.0886433 0.239407 0.966864 + outer loop + vertex 0.994308 2.02802 2.58462 + vertex 0.997921 2.03175 2.58337 + vertex 0.99321 2.03209 2.58372 + endloop + endfacet + facet normal 0.0790133 0.241761 0.967114 + outer loop + vertex 0.990427 2.02449 2.58582 + vertex 0.995346 2.02383 2.58559 + vertex 0.994308 2.02802 2.58462 + endloop + endfacet + facet normal 0.0827216 0.23448 0.968595 + outer loop + vertex 0.999386 2.0231 2.58542 + vertex 0.995346 2.02383 2.58559 + vertex 0.996795 2.01939 2.58654 + endloop + endfacet + facet normal 0.0841528 0.22426 0.970889 + outer loop + vertex 0.996322 2.01509 2.58757 + vertex 0.996795 2.01939 2.58654 + vertex 0.992401 2.01603 2.58769 + endloop + endfacet + facet normal 0.0809829 0.219911 0.972153 + outer loop + vertex 0.993189 2.01182 2.58858 + vertex 0.992401 2.01603 2.58769 + vertex 0.988499 2.01257 2.5888 + endloop + endfacet + facet normal 0.0850796 0.220517 0.971665 + outer loop + vertex 0.994734 2.0073 2.58947 + vertex 0.997914 2.01172 2.58819 + vertex 0.993189 2.01182 2.58858 + endloop + endfacet + facet normal 0.0773361 0.222592 0.971839 + outer loop + vertex 0.990295 2.00394 2.59059 + vertex 0.99437 2.00309 2.59046 + vertex 0.994734 2.0073 2.58947 + endloop + endfacet + facet normal 0.0813277 0.223248 0.971363 + outer loop + vertex 0.99437 2.00309 2.59046 + vertex 0.996318 2.00054 2.59089 + vertex 0.999017 2.00411 2.58984 + endloop + endfacet + facet normal 0.0818657 0.222855 0.971408 + outer loop + vertex 1.00043 1.99954 2.59077 + vertex 0.999017 2.00411 2.58984 + vertex 0.996318 2.00054 2.59089 + endloop + endfacet + facet normal 0.0889896 0.224504 0.970401 + outer loop + vertex 0.999017 2.00411 2.58984 + vertex 1.00338 2.0073 2.5887 + vertex 0.9995 2.00836 2.58881 + endloop + endfacet + facet normal 0.0930262 0.224171 0.9701 + outer loop + vertex 1.00802 2.00692 2.58835 + vertex 1.00641 2.01034 2.58771 + vertex 1.00338 2.0073 2.5887 + endloop + endfacet + facet normal 0.0981212 0.226811 0.968984 + outer loop + vertex 1.00962 2.00352 2.58898 + vertex 1.01263 2.00651 2.58797 + vertex 1.00802 2.00692 2.58835 + endloop + endfacet + facet normal 0.101808 0.22113 0.969916 + outer loop + vertex 1.00917 1.99931 2.58999 + vertex 1.01349 2.00236 2.58884 + vertex 1.00962 2.00352 2.58898 + endloop + endfacet + facet normal 0.0903793 0.209013 0.973727 + outer loop + vertex 1.0065 1.9958 2.59104 + vertex 1.00455 1.99849 2.59064 + vertex 1.0019 1.99482 2.59167 + endloop + endfacet + facet normal 0.105513 0.211237 0.971723 + outer loop + vertex 1.00917 1.99931 2.58999 + vertex 1.01054 1.99463 2.59085 + vertex 1.0149 1.99774 2.5897 + endloop + endfacet + facet normal 0.0920962 0.201824 0.975082 + outer loop + vertex 1.0065 1.9958 2.59104 + vertex 1.0019 1.99482 2.59167 + vertex 1.00622 1.99135 2.59199 + endloop + endfacet + facet normal 0.1067 0.199596 0.974052 + outer loop + vertex 1.01454 1.99346 2.59066 + vertex 1.01054 1.99463 2.59085 + vertex 1.01189 1.98983 2.59169 + endloop + endfacet + facet normal 0.104744 0.197717 0.974647 + outer loop + vertex 1.01145 1.98534 2.59265 + vertex 1.01189 1.98983 2.59169 + vertex 1.00752 1.98643 2.59285 + endloop + endfacet + facet normal 0.10399 0.201161 0.974023 + outer loop + vertex 1.01299 1.98186 2.5932 + vertex 1.01611 1.9863 2.59195 + vertex 1.01145 1.98534 2.59265 + endloop + endfacet + facet normal 0.100827 0.20335 0.973901 + outer loop + vertex 1.01757 1.98154 2.5928 + vertex 1.01611 1.9863 2.59195 + vertex 1.01299 1.98186 2.5932 + endloop + endfacet + facet normal 0.094659 0.209884 0.973133 + outer loop + vertex 1.02141 1.9804 2.59267 + vertex 1.02178 1.9848 2.59168 + vertex 1.01757 1.98154 2.5928 + endloop + endfacet + facet normal 0.0965448 0.209693 0.972989 + outer loop + vertex 1.02178 1.9848 2.59168 + vertex 1.02141 1.9804 2.59267 + vertex 1.0261 1.9813 2.59201 + endloop + endfacet + facet normal 0.0982009 0.211678 0.972393 + outer loop + vertex 1.02635 1.98572 2.59102 + vertex 1.02178 1.9848 2.59168 + vertex 1.0261 1.9813 2.59201 + endloop + endfacet + facet normal 0.111876 0.208891 0.971519 + outer loop + vertex 1.02842 1.97242 2.59371 + vertex 1.02762 1.97659 2.59291 + vertex 1.02461 1.97356 2.5939 + endloop + endfacet + facet normal 0.0944974 0.219057 0.971125 + outer loop + vertex 1.02302 1.97696 2.59329 + vertex 1.0261 1.9813 2.59201 + vertex 1.02141 1.9804 2.59267 + endloop + endfacet + facet normal 0.129473 0.213774 0.968265 + outer loop + vertex 1.03134 1.97541 2.59267 + vertex 1.03174 1.97971 2.59167 + vertex 1.02762 1.97659 2.59291 + endloop + endfacet + facet normal 0.112129 0.210617 0.971117 + outer loop + vertex 1.02635 1.98572 2.59102 + vertex 1.0261 1.9813 2.59201 + vertex 1.03046 1.98451 2.59081 + endloop + endfacet + facet normal 0.110931 0.206358 0.972168 + outer loop + vertex 1.03046 1.98451 2.59081 + vertex 1.02909 1.98929 2.58995 + vertex 1.02635 1.98572 2.59102 + endloop + endfacet + facet normal 0.155575 0.192221 0.968941 + outer loop + vertex 1.03489 1.98751 2.58952 + vertex 1.03804 1.99174 2.58818 + vertex 1.03345 1.99242 2.58878 + endloop + endfacet + facet normal 0.153755 0.177061 0.972116 + outer loop + vertex 1.03804 1.99174 2.58818 + vertex 1.03642 1.99546 2.58776 + vertex 1.03345 1.99242 2.58878 + endloop + endfacet + facet normal 0.128357 0.201514 0.971039 + outer loop + vertex 1.03345 1.99242 2.58878 + vertex 1.03642 1.99546 2.58776 + vertex 1.03262 1.99668 2.58801 + endloop + endfacet + facet normal 0.184417 0.170388 0.967966 + outer loop + vertex 1.03949 1.98793 2.58857 + vertex 1.03804 1.99174 2.58818 + vertex 1.03489 1.98751 2.58952 + endloop + endfacet + facet normal 0.18454 0.169386 0.968119 + outer loop + vertex 1.03489 1.98751 2.58952 + vertex 1.0391 1.98331 2.58945 + vertex 1.03949 1.98793 2.58857 + endloop + endfacet + facet normal 0.105272 0.205978 0.972878 + outer loop + vertex 1.02443 1.98844 2.59063 + vertex 1.02909 1.98929 2.58995 + vertex 1.0248 1.99276 2.58968 + endloop + endfacet + facet normal 0.102449 0.208328 0.972679 + outer loop + vertex 1.0248 1.99276 2.58968 + vertex 1.02802 1.99702 2.58843 + vertex 1.02343 1.99736 2.58884 + endloop + endfacet + facet normal 0.115863 0.199434 0.973037 + outer loop + vertex 1.03345 1.99242 2.58878 + vertex 1.03262 1.99668 2.58801 + vertex 1.02957 1.99362 2.589 + endloop + endfacet + facet normal 0.103094 0.213952 0.971389 + outer loop + vertex 1.02802 1.99702 2.58843 + vertex 1.03116 2.00139 2.58713 + vertex 1.02646 2.00043 2.58784 + endloop + endfacet + facet normal 0.128787 0.202917 0.97069 + outer loop + vertex 1.03642 1.99546 2.58776 + vertex 1.03682 1.99985 2.58678 + vertex 1.03262 1.99668 2.58801 + endloop + endfacet + facet normal 0.10224 0.217597 0.970669 + outer loop + vertex 1.02687 2.00482 2.58682 + vertex 1.02646 2.00043 2.58784 + vertex 1.03116 2.00139 2.58713 + endloop + endfacet + facet normal 0.108012 0.22905 0.967403 + outer loop + vertex 1.02953 2.00847 2.58569 + vertex 1.03145 2.00579 2.58611 + vertex 1.03409 2.00932 2.58498 + endloop + endfacet + facet normal 0.106204 0.222921 0.969034 + outer loop + vertex 1.02687 2.00482 2.58682 + vertex 1.02547 2.00956 2.58588 + vertex 1.02115 2.00626 2.58711 + endloop + endfacet + facet normal 0.108422 0.224244 0.968483 + outer loop + vertex 1.02547 2.00956 2.58588 + vertex 1.02409 2.01425 2.58495 + vertex 1.02141 2.01068 2.58607 + endloop + endfacet + facet normal 0.113145 0.233492 0.965754 + outer loop + vertex 1.03286 2.01664 2.58336 + vertex 1.03146 2.02003 2.58271 + vertex 1.0284 2.01724 2.58374 + endloop + endfacet + facet normal 0.114537 0.232035 0.965941 + outer loop + vertex 1.0284 2.01724 2.58374 + vertex 1.03146 2.02003 2.58271 + vertex 1.02764 2.02129 2.58286 + endloop + endfacet + facet normal 0.11611 0.236974 0.964553 + outer loop + vertex 1.03146 2.02003 2.58271 + vertex 1.03188 2.02425 2.58162 + vertex 1.02764 2.02129 2.58286 + endloop + endfacet + facet normal 0.1143 0.237194 0.964715 + outer loop + vertex 1.03188 2.02425 2.58162 + vertex 1.03146 2.02003 2.58271 + vertex 1.03641 2.02053 2.582 + endloop + endfacet + facet normal 0.114715 0.234075 0.965427 + outer loop + vertex 1.03286 2.01664 2.58336 + vertex 1.03641 2.02053 2.582 + vertex 1.03146 2.02003 2.58271 + endloop + endfacet + facet normal 0.112969 0.23561 0.96526 + outer loop + vertex 1.03661 2.01595 2.58309 + vertex 1.03641 2.02053 2.582 + vertex 1.03286 2.01664 2.58336 + endloop + endfacet + facet normal 0.108142 0.228452 0.96753 + outer loop + vertex 1.02953 2.00847 2.58569 + vertex 1.03409 2.00932 2.58498 + vertex 1.02981 2.01269 2.58466 + endloop + endfacet + facet normal 0.125138 0.219848 0.967475 + outer loop + vertex 1.03988 2.00765 2.58461 + vertex 1.03818 2.01248 2.58373 + vertex 1.03409 2.00932 2.58498 + endloop + endfacet + facet normal 0.112738 0.234207 0.965628 + outer loop + vertex 1.03432 2.01339 2.58398 + vertex 1.03661 2.01595 2.58309 + vertex 1.03286 2.01664 2.58336 + endloop + endfacet + facet normal 0.125115 0.235769 0.963722 + outer loop + vertex 1.03641 2.02053 2.582 + vertex 1.03661 2.01595 2.58309 + vertex 1.04107 2.01675 2.58232 + endloop + endfacet + facet normal 0.114979 0.237994 0.964437 + outer loop + vertex 1.03631 2.02508 2.58089 + vertex 1.03188 2.02425 2.58162 + vertex 1.03641 2.02053 2.582 + endloop + endfacet + facet normal 0.113977 0.242421 0.963453 + outer loop + vertex 1.03631 2.02508 2.58089 + vertex 1.03444 2.02781 2.58042 + vertex 1.03188 2.02425 2.58162 + endloop + endfacet + facet normal 0.114444 0.242094 0.96348 + outer loop + vertex 1.03444 2.02781 2.58042 + vertex 1.0303 2.02887 2.58065 + vertex 1.03188 2.02425 2.58162 + endloop + endfacet + facet normal 0.132254 0.24197 0.961228 + outer loop + vertex 1.03949 2.02401 2.58077 + vertex 1.0413 2.02117 2.58124 + vertex 1.04396 2.02457 2.58001 + endloop + endfacet + facet normal 0.150575 0.227701 0.962018 + outer loop + vertex 1.04811 2.02722 2.57873 + vertex 1.04686 2.03073 2.57809 + vertex 1.04429 2.02863 2.57899 + endloop + endfacet + facet normal 0.173791 0.236115 0.956058 + outer loop + vertex 1.0471 2.03485 2.57703 + vertex 1.04686 2.03073 2.57809 + vertex 1.05163 2.03071 2.57723 + endloop + endfacet + facet normal 0.155476 0.216458 0.963833 + outer loop + vertex 1.05155 2.03531 2.57621 + vertex 1.0471 2.03485 2.57703 + vertex 1.05163 2.03071 2.57723 + endloop + endfacet + facet normal 0.195306 0.215526 0.956768 + outer loop + vertex 1.05155 2.03531 2.57621 + vertex 1.05163 2.03071 2.57723 + vertex 1.05468 2.03384 2.5759 + endloop + endfacet + facet normal 0.197231 0.219917 0.955372 + outer loop + vertex 1.05468 2.03384 2.5759 + vertex 1.05461 2.03845 2.57486 + vertex 1.05155 2.03531 2.57621 + endloop + endfacet + facet normal 0.175852 0.240411 0.954609 + outer loop + vertex 1.04971 2.03827 2.57581 + vertex 1.05155 2.03531 2.57621 + vertex 1.05461 2.03845 2.57486 + endloop + endfacet + facet normal 0.176017 0.23843 0.955075 + outer loop + vertex 1.04971 2.03827 2.57581 + vertex 1.05461 2.03845 2.57486 + vertex 1.04986 2.04262 2.57469 + endloop + endfacet + facet normal 0.138909 0.241104 0.960507 + outer loop + vertex 1.04557 2.03969 2.57605 + vertex 1.04971 2.03827 2.57581 + vertex 1.04986 2.04262 2.57469 + endloop + endfacet + facet normal 0.132658 0.249652 0.959206 + outer loop + vertex 1.04406 2.04435 2.57504 + vertex 1.04557 2.03969 2.57605 + vertex 1.04986 2.04262 2.57469 + endloop + endfacet + facet normal 0.131574 0.245784 0.960353 + outer loop + vertex 1.04986 2.04262 2.57469 + vertex 1.0481 2.04736 2.57372 + vertex 1.04406 2.04435 2.57504 + endloop + endfacet + facet normal 0.124213 0.255042 0.958919 + outer loop + vertex 1.04406 2.04435 2.57504 + vertex 1.0481 2.04736 2.57372 + vertex 1.04426 2.04834 2.57396 + endloop + endfacet + facet normal 0.123786 0.255076 0.958965 + outer loop + vertex 1.03978 2.04773 2.5747 + vertex 1.04406 2.04435 2.57504 + vertex 1.04426 2.04834 2.57396 + endloop + endfacet + facet normal 0.122601 0.261808 0.957301 + outer loop + vertex 1.04426 2.04834 2.57396 + vertex 1.04278 2.05164 2.57324 + vertex 1.03978 2.04773 2.5747 + endloop + endfacet + facet normal 0.122989 0.261963 0.957209 + outer loop + vertex 1.04426 2.04834 2.57396 + vertex 1.0466 2.05068 2.57302 + vertex 1.04278 2.05164 2.57324 + endloop + endfacet + facet normal 0.123679 0.264925 0.956305 + outer loop + vertex 1.0466 2.05068 2.57302 + vertex 1.04676 2.05472 2.57188 + vertex 1.04278 2.05164 2.57324 + endloop + endfacet + facet normal 0.12476 0.263625 0.956523 + outer loop + vertex 1.04278 2.05164 2.57324 + vertex 1.04676 2.05472 2.57188 + vertex 1.04108 2.05621 2.5722 + endloop + endfacet + facet normal 0.127152 0.264391 0.955997 + outer loop + vertex 1.04278 2.05164 2.57324 + vertex 1.04108 2.05621 2.5722 + vertex 1.03813 2.05226 2.57369 + endloop + endfacet + facet normal 0.129328 0.262817 0.956139 + outer loop + vertex 1.03813 2.05226 2.57369 + vertex 1.04108 2.05621 2.5722 + vertex 1.03663 2.05558 2.57298 + endloop + endfacet + facet normal 0.128865 0.265294 0.955517 + outer loop + vertex 1.03676 2.05963 2.57184 + vertex 1.03663 2.05558 2.57298 + vertex 1.04108 2.05621 2.5722 + endloop + endfacet + facet normal 0.12909 0.265568 0.955411 + outer loop + vertex 1.04122 2.06043 2.57101 + vertex 1.03676 2.05963 2.57184 + vertex 1.04108 2.05621 2.5722 + endloop + endfacet + facet normal 0.127019 0.2657 0.955651 + outer loop + vertex 1.04122 2.06043 2.57101 + vertex 1.04108 2.05621 2.5722 + vertex 1.04523 2.0593 2.57079 + endloop + endfacet + facet normal 0.126763 0.264731 0.955954 + outer loop + vertex 1.04523 2.0593 2.57079 + vertex 1.04373 2.06391 2.56972 + vertex 1.04122 2.06043 2.57101 + endloop + endfacet + facet normal 0.128862 0.263259 0.95608 + outer loop + vertex 1.03926 2.06311 2.57054 + vertex 1.04122 2.06043 2.57101 + vertex 1.04373 2.06391 2.56972 + endloop + endfacet + facet normal 0.129518 0.26033 0.956793 + outer loop + vertex 1.03926 2.06311 2.57054 + vertex 1.04373 2.06391 2.56972 + vertex 1.03937 2.06727 2.56939 + endloop + endfacet + facet normal 0.128856 0.26037 0.956872 + outer loop + vertex 1.03523 2.06427 2.57077 + vertex 1.03926 2.06311 2.57054 + vertex 1.03937 2.06727 2.56939 + endloop + endfacet + facet normal 0.129721 0.263555 0.955882 + outer loop + vertex 1.03926 2.06311 2.57054 + vertex 1.03523 2.06427 2.57077 + vertex 1.03676 2.05963 2.57184 + endloop + endfacet + facet normal 0.127322 0.262881 0.956391 + outer loop + vertex 1.03676 2.05963 2.57184 + vertex 1.03523 2.06427 2.57077 + vertex 1.03108 2.06121 2.57216 + endloop + endfacet + facet normal 0.127976 0.265395 0.955609 + outer loop + vertex 1.03281 2.05659 2.57321 + vertex 1.03676 2.05963 2.57184 + vertex 1.03108 2.06121 2.57216 + endloop + endfacet + facet normal 0.130668 0.261769 0.956244 + outer loop + vertex 1.03937 2.06727 2.56939 + vertex 1.04373 2.06391 2.56972 + vertex 1.04384 2.06804 2.56857 + endloop + endfacet + facet normal 0.131618 0.257411 0.957296 + outer loop + vertex 1.04384 2.06804 2.56857 + vertex 1.04191 2.07071 2.56812 + vertex 1.03937 2.06727 2.56939 + endloop + endfacet + facet normal 0.132378 0.256867 0.957338 + outer loop + vertex 1.03937 2.06727 2.56939 + vertex 1.04191 2.07071 2.56812 + vertex 1.0379 2.0719 2.56836 + endloop + endfacet + facet normal 0.129218 0.256009 0.957999 + outer loop + vertex 1.03937 2.06727 2.56939 + vertex 1.0379 2.0719 2.56836 + vertex 1.03374 2.06892 2.56971 + endloop + endfacet + facet normal 0.130015 0.25888 0.957119 + outer loop + vertex 1.03374 2.06892 2.56971 + vertex 1.03523 2.06427 2.57077 + vertex 1.03937 2.06727 2.56939 + endloop + endfacet + facet normal 0.127149 0.258099 0.957715 + outer loop + vertex 1.03523 2.06427 2.57077 + vertex 1.03374 2.06892 2.56971 + vertex 1.03121 2.06546 2.57098 + endloop + endfacet + facet normal 0.128178 0.261803 0.956572 + outer loop + vertex 1.03121 2.06546 2.57098 + vertex 1.03108 2.06121 2.57216 + vertex 1.03523 2.06427 2.57077 + endloop + endfacet + facet normal 0.12621 0.261926 0.9568 + outer loop + vertex 1.03121 2.06546 2.57098 + vertex 1.02676 2.06467 2.57178 + vertex 1.03108 2.06121 2.57216 + endloop + endfacet + facet normal 0.127249 0.257228 0.957936 + outer loop + vertex 1.03121 2.06546 2.57098 + vertex 1.02927 2.06815 2.57051 + vertex 1.02676 2.06467 2.57178 + endloop + endfacet + facet normal 0.127831 0.257615 0.957755 + outer loop + vertex 1.02927 2.06815 2.57051 + vertex 1.03121 2.06546 2.57098 + vertex 1.03374 2.06892 2.56971 + endloop + endfacet + facet normal 0.128424 0.25485 0.958415 + outer loop + vertex 1.02927 2.06815 2.57051 + vertex 1.03374 2.06892 2.56971 + vertex 1.0294 2.07231 2.56939 + endloop + endfacet + facet normal 0.12831 0.254709 0.958468 + outer loop + vertex 1.0294 2.07231 2.56939 + vertex 1.03374 2.06892 2.56971 + vertex 1.03389 2.07308 2.56859 + endloop + endfacet + facet normal 0.128382 0.25437 0.958548 + outer loop + vertex 1.03389 2.07308 2.56859 + vertex 1.03194 2.07575 2.56814 + vertex 1.0294 2.07231 2.56939 + endloop + endfacet + facet normal 0.126579 0.255668 0.958442 + outer loop + vertex 1.0294 2.07231 2.56939 + vertex 1.03194 2.07575 2.56814 + vertex 1.02792 2.07692 2.56836 + endloop + endfacet + facet normal 0.130319 0.254577 0.958232 + outer loop + vertex 1.03374 2.06892 2.56971 + vertex 1.0379 2.0719 2.56836 + vertex 1.03389 2.07308 2.56859 + endloop + endfacet + facet normal 0.130402 0.254879 0.95814 + outer loop + vertex 1.0379 2.0719 2.56836 + vertex 1.03642 2.07652 2.56733 + vertex 1.03389 2.07308 2.56859 + endloop + endfacet + facet normal 0.129787 0.255318 0.958106 + outer loop + vertex 1.03389 2.07308 2.56859 + vertex 1.03642 2.07652 2.56733 + vertex 1.03194 2.07575 2.56814 + endloop + endfacet + facet normal 0.129098 0.258491 0.957348 + outer loop + vertex 1.03204 2.07989 2.56701 + vertex 1.03194 2.07575 2.56814 + vertex 1.03642 2.07652 2.56733 + endloop + endfacet + facet normal 0.131897 0.255287 0.957826 + outer loop + vertex 1.0379 2.0719 2.56836 + vertex 1.04201 2.07487 2.567 + vertex 1.03642 2.07652 2.56733 + endloop + endfacet + facet normal 0.132345 0.256897 0.957334 + outer loop + vertex 1.04201 2.07487 2.567 + vertex 1.0405 2.07949 2.56597 + vertex 1.03642 2.07652 2.56733 + endloop + endfacet + facet normal 0.131875 0.257501 0.957237 + outer loop + vertex 1.03651 2.08067 2.5662 + vertex 1.03642 2.07652 2.56733 + vertex 1.0405 2.07949 2.56597 + endloop + endfacet + facet normal 0.133679 0.264005 0.955213 + outer loop + vertex 1.0405 2.07949 2.56597 + vertex 1.03895 2.08406 2.56492 + vertex 1.03651 2.08067 2.5662 + endloop + endfacet + facet normal 0.131955 0.265212 0.955118 + outer loop + vertex 1.03452 2.0833 2.56574 + vertex 1.03651 2.08067 2.5662 + vertex 1.03895 2.08406 2.56492 + endloop + endfacet + facet normal 0.130837 0.27035 0.95383 + outer loop + vertex 1.03452 2.0833 2.56574 + vertex 1.03895 2.08406 2.56492 + vertex 1.03454 2.08738 2.56458 + endloop + endfacet + facet normal 0.127083 0.270501 0.954295 + outer loop + vertex 1.03048 2.08446 2.56595 + vertex 1.03452 2.0833 2.56574 + vertex 1.03454 2.08738 2.56458 + endloop + endfacet + facet normal 0.131249 0.270875 0.953625 + outer loop + vertex 1.03454 2.08738 2.56458 + vertex 1.03895 2.08406 2.56492 + vertex 1.03897 2.08814 2.56376 + endloop + endfacet + facet normal 0.130387 0.274815 0.952615 + outer loop + vertex 1.03897 2.08814 2.56376 + vertex 1.03697 2.09076 2.56328 + vertex 1.03454 2.08738 2.56458 + endloop + endfacet + facet normal 0.129687 0.2753 0.952571 + outer loop + vertex 1.03454 2.08738 2.56458 + vertex 1.03697 2.09076 2.56328 + vertex 1.03294 2.09193 2.56349 + endloop + endfacet + facet normal 0.12745 0.274631 0.953066 + outer loop + vertex 1.03454 2.08738 2.56458 + vertex 1.03294 2.09193 2.56349 + vertex 1.02889 2.08902 2.56487 + endloop + endfacet + facet normal 0.127375 0.274727 0.953048 + outer loop + vertex 1.02889 2.08902 2.56487 + vertex 1.03294 2.09193 2.56349 + vertex 1.02891 2.0931 2.56369 + endloop + endfacet + facet normal 0.12332 0.274888 0.953535 + outer loop + vertex 1.02445 2.09234 2.56448 + vertex 1.02889 2.08902 2.56487 + vertex 1.02891 2.0931 2.56369 + endloop + endfacet + facet normal 0.122958 0.276552 0.9531 + outer loop + vertex 1.02891 2.0931 2.56369 + vertex 1.02691 2.09573 2.56318 + vertex 1.02445 2.09234 2.56448 + endloop + endfacet + facet normal 0.121904 0.277285 0.953023 + outer loop + vertex 1.02445 2.09234 2.56448 + vertex 1.02691 2.09573 2.56318 + vertex 1.02289 2.09688 2.56336 + endloop + endfacet + facet normal 0.126639 0.279122 0.951868 + outer loop + vertex 1.02891 2.0931 2.56369 + vertex 1.03135 2.09648 2.56237 + vertex 1.02691 2.09573 2.56318 + endloop + endfacet + facet normal 0.127079 0.277101 0.9524 + outer loop + vertex 1.02695 2.0998 2.56199 + vertex 1.02691 2.09573 2.56318 + vertex 1.03135 2.09648 2.56237 + endloop + endfacet + facet normal 0.128271 0.277991 0.951981 + outer loop + vertex 1.03294 2.09193 2.56349 + vertex 1.03135 2.09648 2.56237 + vertex 1.02891 2.0931 2.56369 + endloop + endfacet + facet normal 0.130993 0.278796 0.951375 + outer loop + vertex 1.03294 2.09193 2.56349 + vertex 1.03697 2.09485 2.56208 + vertex 1.03135 2.09648 2.56237 + endloop + endfacet + facet normal 0.130375 0.27653 0.952121 + outer loop + vertex 1.03697 2.09485 2.56208 + vertex 1.03541 2.09941 2.56096 + vertex 1.03135 2.09648 2.56237 + endloop + endfacet + facet normal 0.13064 0.276191 0.952183 + outer loop + vertex 1.03139 2.10057 2.56118 + vertex 1.03135 2.09648 2.56237 + vertex 1.03541 2.09941 2.56096 + endloop + endfacet + facet normal 0.12845 0.268115 0.954785 + outer loop + vertex 1.03541 2.09941 2.56096 + vertex 1.03392 2.10397 2.55988 + vertex 1.03139 2.10057 2.56118 + endloop + endfacet + facet normal 0.126826 0.269278 0.954675 + outer loop + vertex 1.02943 2.10318 2.5607 + vertex 1.03139 2.10057 2.56118 + vertex 1.03392 2.10397 2.55988 + endloop + endfacet + facet normal 0.128055 0.263709 0.956065 + outer loop + vertex 1.02943 2.10318 2.5607 + vertex 1.03392 2.10397 2.55988 + vertex 1.02953 2.10727 2.55956 + endloop + endfacet + facet normal 0.126561 0.261794 0.95679 + outer loop + vertex 1.02953 2.10727 2.55956 + vertex 1.03392 2.10397 2.55988 + vertex 1.03405 2.10809 2.55874 + endloop + endfacet + facet normal 0.124776 0.269671 0.954834 + outer loop + vertex 1.03405 2.10809 2.55874 + vertex 1.03204 2.11067 2.55827 + vertex 1.02953 2.10727 2.55956 + endloop + endfacet + facet normal 0.118856 0.273868 0.954395 + outer loop + vertex 1.02953 2.10727 2.55956 + vertex 1.03204 2.11067 2.55827 + vertex 1.02796 2.11175 2.55847 + endloop + endfacet + facet normal 0.128084 0.311102 0.941706 + outer loop + vertex 1.03204 2.11067 2.55827 + vertex 1.03189 2.1146 2.557 + vertex 1.02796 2.11175 2.55847 + endloop + endfacet + facet normal 0.116611 0.325195 0.93843 + outer loop + vertex 1.02796 2.11175 2.55847 + vertex 1.03189 2.1146 2.557 + vertex 1.02657 2.11577 2.55725 + endloop + endfacet + facet normal 0.123888 0.311116 0.942263 + outer loop + vertex 1.03189 2.1146 2.557 + vertex 1.03204 2.11067 2.55827 + vertex 1.03646 2.11152 2.55741 + endloop + endfacet + facet normal 0.128432 0.317478 0.939528 + outer loop + vertex 1.03621 2.11549 2.55611 + vertex 1.03189 2.1146 2.557 + vertex 1.03646 2.11152 2.55741 + endloop + endfacet + facet normal 0.131793 0.317531 0.939045 + outer loop + vertex 1.03621 2.11549 2.55611 + vertex 1.03646 2.11152 2.55741 + vertex 1.04027 2.11439 2.55591 + endloop + endfacet + facet normal 0.156286 0.416268 0.89571 + outer loop + vertex 1.04027 2.11439 2.55591 + vertex 1.03817 2.11844 2.55439 + vertex 1.03621 2.11549 2.55611 + endloop + endfacet + facet normal 0.127808 0.405108 0.905291 + outer loop + vertex 1.03817 2.11844 2.55439 + vertex 1.04027 2.11439 2.55591 + vertex 1.04394 2.11694 2.55425 + endloop + endfacet + facet normal 0.145396 0.38402 0.911805 + outer loop + vertex 1.04027 2.11439 2.55591 + vertex 1.04427 2.1133 2.55573 + vertex 1.04394 2.11694 2.55425 + endloop + endfacet + facet normal 0.124693 0.303116 0.94476 + outer loop + vertex 1.04427 2.1133 2.55573 + vertex 1.04027 2.11439 2.55591 + vertex 1.04208 2.10995 2.55709 + endloop + endfacet + facet normal 0.134138 0.297186 0.94535 + outer loop + vertex 1.04638 2.11072 2.55624 + vertex 1.04427 2.1133 2.55573 + vertex 1.04208 2.10995 2.55709 + endloop + endfacet + facet normal 0.140608 0.269354 0.952721 + outer loop + vertex 1.04638 2.11072 2.55624 + vertex 1.04208 2.10995 2.55709 + vertex 1.04648 2.10657 2.5574 + endloop + endfacet + facet normal 0.152899 0.269132 0.950889 + outer loop + vertex 1.04638 2.11072 2.55624 + vertex 1.04648 2.10657 2.5574 + vertex 1.05033 2.10949 2.55595 + endloop + endfacet + facet normal 0.165964 0.314812 0.934532 + outer loop + vertex 1.05033 2.10949 2.55595 + vertex 1.04831 2.11396 2.55481 + vertex 1.04638 2.11072 2.55624 + endloop + endfacet + facet normal 0.15484 0.310613 0.93784 + outer loop + vertex 1.04831 2.11396 2.55481 + vertex 1.05033 2.10949 2.55595 + vertex 1.05407 2.11236 2.55439 + endloop + endfacet + facet normal 0.17237 0.38155 0.908135 + outer loop + vertex 1.05407 2.11236 2.55439 + vertex 1.05132 2.11712 2.55291 + vertex 1.04831 2.11396 2.55481 + endloop + endfacet + facet normal 0.160049 0.304447 0.938987 + outer loop + vertex 1.05033 2.10949 2.55595 + vertex 1.05434 2.10821 2.55568 + vertex 1.05407 2.11236 2.55439 + endloop + endfacet + facet normal 0.14829 0.3043 0.940963 + outer loop + vertex 1.05434 2.10821 2.55568 + vertex 1.0586 2.10877 2.55483 + vertex 1.05407 2.11236 2.55439 + endloop + endfacet + facet normal 0.149438 0.305674 0.940336 + outer loop + vertex 1.05407 2.11236 2.55439 + vertex 1.0586 2.10877 2.55483 + vertex 1.05867 2.11262 2.55357 + endloop + endfacet + facet normal 0.142754 0.36285 0.920848 + outer loop + vertex 1.05867 2.11262 2.55357 + vertex 1.0567 2.11592 2.55258 + vertex 1.05407 2.11236 2.55439 + endloop + endfacet + facet normal 0.140798 0.306212 0.941494 + outer loop + vertex 1.0586 2.10877 2.55483 + vertex 1.06197 2.11107 2.55358 + vertex 1.05867 2.11262 2.55357 + endloop + endfacet + facet normal 0.145648 0.299819 0.942812 + outer loop + vertex 1.06417 2.10733 2.55443 + vertex 1.06197 2.11107 2.55358 + vertex 1.0586 2.10877 2.55483 + endloop + endfacet + facet normal 0.141746 0.28322 0.948522 + outer loop + vertex 1.0586 2.10877 2.55483 + vertex 1.06032 2.10432 2.5559 + vertex 1.06417 2.10733 2.55443 + endloop + endfacet + facet normal 0.13908 0.286363 0.947973 + outer loop + vertex 1.06032 2.10432 2.5559 + vertex 1.0643 2.10321 2.55566 + vertex 1.06417 2.10733 2.55443 + endloop + endfacet + facet normal 0.132048 0.286434 0.948957 + outer loop + vertex 1.0643 2.10321 2.55566 + vertex 1.06873 2.10401 2.5548 + vertex 1.06417 2.10733 2.55443 + endloop + endfacet + facet normal 0.131755 0.2877 0.948615 + outer loop + vertex 1.0643 2.10321 2.55566 + vertex 1.06632 2.10064 2.55616 + vertex 1.06873 2.10401 2.5548 + endloop + endfacet + facet normal 0.131849 0.287635 0.948621 + outer loop + vertex 1.07036 2.09947 2.55595 + vertex 1.06873 2.10401 2.5548 + vertex 1.06632 2.10064 2.55616 + endloop + endfacet + facet normal 0.132021 0.288274 0.948403 + outer loop + vertex 1.06632 2.10064 2.55616 + vertex 1.06633 2.09659 2.55738 + vertex 1.07036 2.09947 2.55595 + endloop + endfacet + facet normal 0.13658 0.28246 0.949506 + outer loop + vertex 1.07204 2.09483 2.55709 + vertex 1.07036 2.09947 2.55595 + vertex 1.06633 2.09659 2.55738 + endloop + endfacet + facet normal 0.137705 0.286342 0.94818 + outer loop + vertex 1.06796 2.09206 2.55852 + vertex 1.07204 2.09483 2.55709 + vertex 1.06633 2.09659 2.55738 + endloop + endfacet + facet normal 0.133415 0.285051 0.949182 + outer loop + vertex 1.06796 2.09206 2.55852 + vertex 1.06633 2.09659 2.55738 + vertex 1.06392 2.09323 2.55873 + endloop + endfacet + facet normal 0.132551 0.281873 0.950251 + outer loop + vertex 1.06392 2.08918 2.55993 + vertex 1.06796 2.09206 2.55852 + vertex 1.06392 2.09323 2.55873 + endloop + endfacet + facet normal 0.131698 0.281906 0.95036 + outer loop + vertex 1.05951 2.09243 2.55958 + vertex 1.06392 2.08918 2.55993 + vertex 1.06392 2.09323 2.55873 + endloop + endfacet + facet normal 0.130649 0.286381 0.949166 + outer loop + vertex 1.06392 2.09323 2.55873 + vertex 1.06193 2.09579 2.55823 + vertex 1.05951 2.09243 2.55958 + endloop + endfacet + facet normal 0.133758 0.284231 0.94938 + outer loop + vertex 1.05951 2.09243 2.55958 + vertex 1.06193 2.09579 2.55823 + vertex 1.05794 2.0969 2.55846 + endloop + endfacet + facet normal 0.134585 0.284473 0.94919 + outer loop + vertex 1.05951 2.09243 2.55958 + vertex 1.05794 2.0969 2.55846 + vertex 1.05389 2.094 2.55991 + endloop + endfacet + facet normal 0.133441 0.280099 0.950651 + outer loop + vertex 1.05389 2.094 2.55991 + vertex 1.05547 2.08949 2.56101 + vertex 1.05951 2.09243 2.55958 + endloop + endfacet + facet normal 0.132397 0.281415 0.950409 + outer loop + vertex 1.05547 2.08949 2.56101 + vertex 1.05949 2.08839 2.56078 + vertex 1.05951 2.09243 2.55958 + endloop + endfacet + facet normal 0.130738 0.274919 0.952537 + outer loop + vertex 1.05949 2.08839 2.56078 + vertex 1.05547 2.08949 2.56101 + vertex 1.05704 2.08497 2.5621 + endloop + endfacet + facet normal 0.130322 0.275207 0.952511 + outer loop + vertex 1.06148 2.08581 2.56125 + vertex 1.05949 2.08839 2.56078 + vertex 1.05704 2.08497 2.5621 + endloop + endfacet + facet normal 0.132379 0.266563 0.954683 + outer loop + vertex 1.06148 2.08581 2.56125 + vertex 1.05704 2.08497 2.5621 + vertex 1.06142 2.08168 2.56241 + endloop + endfacet + facet normal 0.133886 0.266489 0.954494 + outer loop + vertex 1.06148 2.08581 2.56125 + vertex 1.06142 2.08168 2.56241 + vertex 1.06552 2.08463 2.56102 + endloop + endfacet + facet normal 0.139946 0.25866 0.955777 + outer loop + vertex 1.06713 2.07991 2.56206 + vertex 1.06552 2.08463 2.56102 + vertex 1.06142 2.08168 2.56241 + endloop + endfacet + facet normal 0.140443 0.260364 0.955242 + outer loop + vertex 1.06293 2.07706 2.56345 + vertex 1.06713 2.07991 2.56206 + vertex 1.06142 2.08168 2.56241 + endloop + endfacet + facet normal 0.137452 0.259533 0.955902 + outer loop + vertex 1.06293 2.07706 2.56345 + vertex 1.06142 2.08168 2.56241 + vertex 1.0589 2.07824 2.56371 + endloop + endfacet + facet normal 0.137219 0.258676 0.956168 + outer loop + vertex 1.05877 2.0741 2.56485 + vertex 1.06293 2.07706 2.56345 + vertex 1.0589 2.07824 2.56371 + endloop + endfacet + facet normal 0.133856 0.258893 0.956586 + outer loop + vertex 1.05446 2.07741 2.56456 + vertex 1.05877 2.0741 2.56485 + vertex 1.0589 2.07824 2.56371 + endloop + endfacet + facet normal 0.133268 0.26143 0.955978 + outer loop + vertex 1.0589 2.07824 2.56371 + vertex 1.05696 2.08085 2.56327 + vertex 1.05446 2.07741 2.56456 + endloop + endfacet + facet normal 0.132877 0.261707 0.955957 + outer loop + vertex 1.05446 2.07741 2.56456 + vertex 1.05696 2.08085 2.56327 + vertex 1.05297 2.08198 2.56351 + endloop + endfacet + facet normal 0.135881 0.26254 0.955306 + outer loop + vertex 1.05446 2.07741 2.56456 + vertex 1.05297 2.08198 2.56351 + vertex 1.0489 2.07904 2.5649 + endloop + endfacet + facet normal 0.134852 0.258769 0.95648 + outer loop + vertex 1.0489 2.07904 2.5649 + vertex 1.05039 2.07445 2.56593 + vertex 1.05446 2.07741 2.56456 + endloop + endfacet + facet normal 0.134113 0.259711 0.956328 + outer loop + vertex 1.05039 2.07445 2.56593 + vertex 1.05434 2.0733 2.56569 + vertex 1.05446 2.07741 2.56456 + endloop + endfacet + facet normal 0.134506 0.261156 0.955879 + outer loop + vertex 1.05434 2.0733 2.56569 + vertex 1.05039 2.07445 2.56593 + vertex 1.05187 2.06987 2.56697 + endloop + endfacet + facet normal 0.132512 0.26255 0.955776 + outer loop + vertex 1.05626 2.07069 2.56614 + vertex 1.05434 2.0733 2.56569 + vertex 1.05187 2.06987 2.56697 + endloop + endfacet + facet normal 0.131876 0.26529 0.955107 + outer loop + vertex 1.05626 2.07069 2.56614 + vertex 1.05187 2.06987 2.56697 + vertex 1.05622 2.06657 2.56729 + endloop + endfacet + facet normal 0.137746 0.265012 0.954355 + outer loop + vertex 1.05626 2.07069 2.56614 + vertex 1.05622 2.06657 2.56729 + vertex 1.06028 2.06949 2.56589 + endloop + endfacet + facet normal 0.136679 0.261175 0.955566 + outer loop + vertex 1.06028 2.06949 2.56589 + vertex 1.05877 2.0741 2.56485 + vertex 1.05626 2.07069 2.56614 + endloop + endfacet + facet normal 0.145338 0.263566 0.95363 + outer loop + vertex 1.05877 2.0741 2.56485 + vertex 1.06028 2.06949 2.56589 + vertex 1.06446 2.0723 2.56448 + endloop + endfacet + facet normal 0.150233 0.256809 0.954714 + outer loop + vertex 1.06028 2.06949 2.56589 + vertex 1.06438 2.0681 2.56562 + vertex 1.06446 2.0723 2.56448 + endloop + endfacet + facet normal 0.178663 0.25504 0.950281 + outer loop + vertex 1.06438 2.0681 2.56562 + vertex 1.06924 2.06819 2.56468 + vertex 1.06446 2.0723 2.56448 + endloop + endfacet + facet normal 0.160438 0.234279 0.958839 + outer loop + vertex 1.06446 2.0723 2.56448 + vertex 1.06924 2.06819 2.56468 + vertex 1.06893 2.07278 2.56361 + endloop + endfacet + facet normal 0.158991 0.243853 0.956691 + outer loop + vertex 1.06893 2.07278 2.56361 + vertex 1.06705 2.0757 2.56318 + vertex 1.06446 2.0723 2.56448 + endloop + endfacet + facet normal 0.146079 0.253493 0.956244 + outer loop + vertex 1.06446 2.0723 2.56448 + vertex 1.06705 2.0757 2.56318 + vertex 1.06293 2.07706 2.56345 + endloop + endfacet + facet normal 0.169615 0.250227 0.953214 + outer loop + vertex 1.06893 2.07278 2.56361 + vertex 1.07189 2.07584 2.56228 + vertex 1.06705 2.0757 2.56318 + endloop + endfacet + facet normal 0.16952 0.251476 0.952902 + outer loop + vertex 1.06713 2.07991 2.56206 + vertex 1.06705 2.0757 2.56318 + vertex 1.07189 2.07584 2.56228 + endloop + endfacet + facet normal 0.15569 0.235667 0.959282 + outer loop + vertex 1.07158 2.08038 2.56122 + vertex 1.06713 2.07991 2.56206 + vertex 1.07189 2.07584 2.56228 + endloop + endfacet + facet normal 0.179117 0.236279 0.955034 + outer loop + vertex 1.07158 2.08038 2.56122 + vertex 1.07189 2.07584 2.56228 + vertex 1.07482 2.0789 2.56098 + endloop + endfacet + facet normal 0.183796 0.247047 0.951413 + outer loop + vertex 1.07482 2.0789 2.56098 + vertex 1.07445 2.08335 2.5599 + vertex 1.07158 2.08038 2.56122 + endloop + endfacet + facet normal 0.183412 0.234811 0.954581 + outer loop + vertex 1.06924 2.06819 2.56468 + vertex 1.07216 2.0713 2.56336 + vertex 1.06893 2.07278 2.56361 + endloop + endfacet + facet normal 0.178667 0.254983 0.950295 + outer loop + vertex 1.06438 2.0681 2.56562 + vertex 1.06634 2.06518 2.56604 + vertex 1.06924 2.06819 2.56468 + endloop + endfacet + facet normal 0.197464 0.237262 0.951165 + outer loop + vertex 1.06961 2.06364 2.56574 + vertex 1.06924 2.06819 2.56468 + vertex 1.06634 2.06518 2.56604 + endloop + endfacet + facet normal 0.196887 0.235949 0.951611 + outer loop + vertex 1.06634 2.06518 2.56604 + vertex 1.06677 2.06063 2.56708 + vertex 1.06961 2.06364 2.56574 + endloop + endfacet + facet normal 0.169169 0.234626 0.957253 + outer loop + vertex 1.06634 2.06518 2.56604 + vertex 1.06193 2.06475 2.56692 + vertex 1.06677 2.06063 2.56708 + endloop + endfacet + facet normal 0.167262 0.247902 0.954237 + outer loop + vertex 1.06634 2.06518 2.56604 + vertex 1.06438 2.0681 2.56562 + vertex 1.06193 2.06475 2.56692 + endloop + endfacet + facet normal 0.151116 0.259577 0.953826 + outer loop + vertex 1.06438 2.0681 2.56562 + vertex 1.06028 2.06949 2.56589 + vertex 1.06193 2.06475 2.56692 + endloop + endfacet + facet normal 0.143661 0.257371 0.955574 + outer loop + vertex 1.06193 2.06475 2.56692 + vertex 1.06028 2.06949 2.56589 + vertex 1.05622 2.06657 2.56729 + endloop + endfacet + facet normal 0.147416 0.269949 0.951523 + outer loop + vertex 1.05783 2.06198 2.56834 + vertex 1.06193 2.06475 2.56692 + vertex 1.05622 2.06657 2.56729 + endloop + endfacet + facet normal 0.13562 0.266436 0.954264 + outer loop + vertex 1.05783 2.06198 2.56834 + vertex 1.05622 2.06657 2.56729 + vertex 1.05377 2.06317 2.56859 + endloop + endfacet + facet normal 0.135703 0.266735 0.954168 + outer loop + vertex 1.05374 2.05905 2.56974 + vertex 1.05783 2.06198 2.56834 + vertex 1.05377 2.06317 2.56859 + endloop + endfacet + facet normal 0.12676 0.267113 0.955292 + outer loop + vertex 1.04933 2.06233 2.56941 + vertex 1.05374 2.05905 2.56974 + vertex 1.05377 2.06317 2.56859 + endloop + endfacet + facet normal 0.126588 0.267848 0.955109 + outer loop + vertex 1.05377 2.06317 2.56859 + vertex 1.05179 2.06577 2.56812 + vertex 1.04933 2.06233 2.56941 + endloop + endfacet + facet normal 0.129013 0.266163 0.955255 + outer loop + vertex 1.04933 2.06233 2.56941 + vertex 1.05179 2.06577 2.56812 + vertex 1.04782 2.06689 2.56834 + endloop + endfacet + facet normal 0.127048 0.265611 0.955672 + outer loop + vertex 1.04933 2.06233 2.56941 + vertex 1.04782 2.06689 2.56834 + vertex 1.04373 2.06391 2.56972 + endloop + endfacet + facet normal 0.128654 0.264806 0.955681 + outer loop + vertex 1.05179 2.06577 2.56812 + vertex 1.05187 2.06987 2.56697 + vertex 1.04782 2.06689 2.56834 + endloop + endfacet + facet normal 0.132158 0.260392 0.956415 + outer loop + vertex 1.04782 2.06689 2.56834 + vertex 1.05187 2.06987 2.56697 + vertex 1.04634 2.07149 2.5673 + endloop + endfacet + facet normal 0.129445 0.259647 0.956989 + outer loop + vertex 1.04782 2.06689 2.56834 + vertex 1.04634 2.07149 2.5673 + vertex 1.04384 2.06804 2.56857 + endloop + endfacet + facet normal 0.143866 0.256128 0.955877 + outer loop + vertex 1.05949 2.05724 2.56936 + vertex 1.05783 2.06198 2.56834 + vertex 1.05374 2.05905 2.56974 + endloop + endfacet + facet normal 0.147407 0.268173 0.952027 + outer loop + vertex 1.05374 2.05905 2.56974 + vertex 1.05529 2.05442 2.57081 + vertex 1.05949 2.05724 2.56936 + endloop + endfacet + facet normal 0.156603 0.255511 0.954039 + outer loop + vertex 1.05529 2.05442 2.57081 + vertex 1.05939 2.05306 2.5705 + vertex 1.05949 2.05724 2.56936 + endloop + endfacet + facet normal 0.155278 0.251225 0.955392 + outer loop + vertex 1.05939 2.05306 2.5705 + vertex 1.05529 2.05442 2.57081 + vertex 1.05674 2.0497 2.57181 + endloop + endfacet + facet normal 0.144477 0.248427 0.957815 + outer loop + vertex 1.05674 2.0497 2.57181 + vertex 1.05529 2.05442 2.57081 + vertex 1.05108 2.05136 2.57224 + endloop + endfacet + facet normal 0.147271 0.25882 0.954633 + outer loop + vertex 1.05279 2.04669 2.57324 + vertex 1.05674 2.0497 2.57181 + vertex 1.05108 2.05136 2.57224 + endloop + endfacet + facet normal 0.134554 0.254799 0.957587 + outer loop + vertex 1.05279 2.04669 2.57324 + vertex 1.05108 2.05136 2.57224 + vertex 1.0481 2.04736 2.57372 + endloop + endfacet + facet normal 0.126878 0.260363 0.957138 + outer loop + vertex 1.0481 2.04736 2.57372 + vertex 1.05108 2.05136 2.57224 + vertex 1.0466 2.05068 2.57302 + endloop + endfacet + facet normal 0.16109 0.241782 0.956866 + outer loop + vertex 1.05657 2.04559 2.57288 + vertex 1.05674 2.0497 2.57181 + vertex 1.05279 2.04669 2.57324 + endloop + endfacet + facet normal 0.160373 0.239062 0.957669 + outer loop + vertex 1.05438 2.04314 2.57386 + vertex 1.05657 2.04559 2.57288 + vertex 1.05279 2.04669 2.57324 + endloop + endfacet + facet normal 0.133998 0.261855 0.95576 + outer loop + vertex 1.05123 2.0556 2.57105 + vertex 1.05108 2.05136 2.57224 + vertex 1.05529 2.05442 2.57081 + endloop + endfacet + facet normal 0.134732 0.264573 0.954908 + outer loop + vertex 1.05529 2.05442 2.57081 + vertex 1.05374 2.05905 2.56974 + vertex 1.05123 2.0556 2.57105 + endloop + endfacet + facet normal 0.12675 0.270191 0.954427 + outer loop + vertex 1.04926 2.05822 2.57057 + vertex 1.05123 2.0556 2.57105 + vertex 1.05374 2.05905 2.56974 + endloop + endfacet + facet normal 0.127302 0.267812 0.955024 + outer loop + vertex 1.04926 2.05822 2.57057 + vertex 1.05374 2.05905 2.56974 + vertex 1.04933 2.06233 2.56941 + endloop + endfacet + facet normal 0.122973 0.267576 0.955657 + outer loop + vertex 1.05123 2.0556 2.57105 + vertex 1.04926 2.05822 2.57057 + vertex 1.04676 2.05472 2.57188 + endloop + endfacet + facet normal 0.124201 0.262511 0.956902 + outer loop + vertex 1.05123 2.0556 2.57105 + vertex 1.04676 2.05472 2.57188 + vertex 1.05108 2.05136 2.57224 + endloop + endfacet + facet normal 0.153504 0.259007 0.9536 + outer loop + vertex 1.05949 2.05724 2.56936 + vertex 1.06198 2.06057 2.56806 + vertex 1.05783 2.06198 2.56834 + endloop + endfacet + facet normal 0.173879 0.243934 0.954077 + outer loop + vertex 1.06393 2.05766 2.56845 + vertex 1.06198 2.06057 2.56806 + vertex 1.05949 2.05724 2.56936 + endloop + endfacet + facet normal 0.17637 0.226188 0.957984 + outer loop + vertex 1.05949 2.05724 2.56936 + vertex 1.06409 2.05317 2.56948 + vertex 1.06393 2.05766 2.56845 + endloop + endfacet + facet normal 0.191123 0.254679 0.947951 + outer loop + vertex 1.06393 2.05766 2.56845 + vertex 1.06677 2.06063 2.56708 + vertex 1.06198 2.06057 2.56806 + endloop + endfacet + facet normal 0.190804 0.259625 0.946672 + outer loop + vertex 1.06193 2.06475 2.56692 + vertex 1.06198 2.06057 2.56806 + vertex 1.06677 2.06063 2.56708 + endloop + endfacet + facet normal 0.212979 0.234093 0.948599 + outer loop + vertex 1.06711 2.05613 2.56811 + vertex 1.06677 2.06063 2.56708 + vertex 1.06393 2.05766 2.56845 + endloop + endfacet + facet normal 0.209318 0.225848 0.951409 + outer loop + vertex 1.06409 2.05317 2.56948 + vertex 1.06711 2.05613 2.56811 + vertex 1.06393 2.05766 2.56845 + endloop + endfacet + facet normal 0.228953 0.20585 0.951423 + outer loop + vertex 1.06867 2.05303 2.5684 + vertex 1.06711 2.05613 2.56811 + vertex 1.06409 2.05317 2.56948 + endloop + endfacet + facet normal 0.229221 0.190254 0.9546 + outer loop + vertex 1.06409 2.05317 2.56948 + vertex 1.06827 2.04872 2.56936 + vertex 1.06867 2.05303 2.5684 + endloop + endfacet + facet normal 0.259663 0.185876 0.947642 + outer loop + vertex 1.06827 2.04872 2.56936 + vertex 1.07157 2.05118 2.56797 + vertex 1.06867 2.05303 2.5684 + endloop + endfacet + facet normal 0.264652 0.194441 0.944538 + outer loop + vertex 1.07157 2.05118 2.56797 + vertex 1.07162 2.05583 2.567 + vertex 1.06867 2.05303 2.5684 + endloop + endfacet + facet normal 0.290831 0.192673 0.937174 + outer loop + vertex 1.07162 2.05583 2.567 + vertex 1.07157 2.05118 2.56797 + vertex 1.07555 2.05122 2.56673 + endloop + endfacet + facet normal 0.265286 0.17017 0.949034 + outer loop + vertex 1.0761 2.0554 2.56583 + vertex 1.07162 2.05583 2.567 + vertex 1.07555 2.05122 2.56673 + endloop + endfacet + facet normal 0.308771 0.161906 0.937255 + outer loop + vertex 1.0761 2.0554 2.56583 + vertex 1.07555 2.05122 2.56673 + vertex 1.07878 2.0535 2.56527 + endloop + endfacet + facet normal 0.31522 0.172176 0.933269 + outer loop + vertex 1.07878 2.0535 2.56527 + vertex 1.07905 2.05813 2.56433 + vertex 1.0761 2.0554 2.56583 + endloop + endfacet + facet normal 0.294006 0.196319 0.935425 + outer loop + vertex 1.07463 2.05861 2.56562 + vertex 1.0761 2.0554 2.56583 + vertex 1.07905 2.05813 2.56433 + endloop + endfacet + facet normal 0.294491 0.207958 0.932753 + outer loop + vertex 1.07463 2.05861 2.56562 + vertex 1.07905 2.05813 2.56433 + vertex 1.07432 2.06333 2.56466 + endloop + endfacet + facet normal 0.25865 0.174258 0.950123 + outer loop + vertex 1.07432 2.06333 2.56466 + vertex 1.07905 2.05813 2.56433 + vertex 1.07903 2.06299 2.56344 + endloop + endfacet + facet normal 0.258796 0.181299 0.948765 + outer loop + vertex 1.07903 2.06299 2.56344 + vertex 1.07711 2.0664 2.56331 + vertex 1.07432 2.06333 2.56466 + endloop + endfacet + facet normal 0.232995 0.205537 0.950509 + outer loop + vertex 1.07432 2.06333 2.56466 + vertex 1.07711 2.0664 2.56331 + vertex 1.07395 2.06811 2.56372 + endloop + endfacet + facet normal 0.235474 0.210492 0.948812 + outer loop + vertex 1.07711 2.0664 2.56331 + vertex 1.0768 2.07111 2.56235 + vertex 1.07395 2.06811 2.56372 + endloop + endfacet + facet normal 0.277657 0.210898 0.937245 + outer loop + vertex 1.0768 2.07111 2.56235 + vertex 1.07711 2.0664 2.56331 + vertex 1.08111 2.06646 2.56211 + endloop + endfacet + facet normal 0.248724 0.183352 0.951062 + outer loop + vertex 1.08131 2.07073 2.56124 + vertex 1.0768 2.07111 2.56235 + vertex 1.08111 2.06646 2.56211 + endloop + endfacet + facet normal 0.303048 0.177712 0.936259 + outer loop + vertex 1.08131 2.07073 2.56124 + vertex 1.08111 2.06646 2.56211 + vertex 1.08417 2.06874 2.56069 + endloop + endfacet + facet normal 0.308481 0.186454 0.932778 + outer loop + vertex 1.08417 2.06874 2.56069 + vertex 1.08425 2.07344 2.55972 + vertex 1.08131 2.07073 2.56124 + endloop + endfacet + facet normal 0.286762 0.210911 0.934497 + outer loop + vertex 1.07977 2.07395 2.56099 + vertex 1.08131 2.07073 2.56124 + vertex 1.08425 2.07344 2.55972 + endloop + endfacet + facet normal 0.287211 0.221158 0.931987 + outer loop + vertex 1.07977 2.07395 2.56099 + vertex 1.08425 2.07344 2.55972 + vertex 1.0795 2.07859 2.55997 + endloop + endfacet + facet normal 0.252382 0.188201 0.949149 + outer loop + vertex 1.0795 2.07859 2.55997 + vertex 1.08425 2.07344 2.55972 + vertex 1.08421 2.07827 2.55878 + endloop + endfacet + facet normal 0.252507 0.196247 0.947485 + outer loop + vertex 1.08421 2.07827 2.55878 + vertex 1.08228 2.08158 2.55861 + vertex 1.0795 2.07859 2.55997 + endloop + endfacet + facet normal 0.226395 0.221135 0.948601 + outer loop + vertex 1.0795 2.07859 2.55997 + vertex 1.08228 2.08158 2.55861 + vertex 1.07912 2.08325 2.55897 + endloop + endfacet + facet normal 0.232509 0.23375 0.944087 + outer loop + vertex 1.08228 2.08158 2.55861 + vertex 1.08191 2.08616 2.55756 + vertex 1.07912 2.08325 2.55897 + endloop + endfacet + facet normal 0.215596 0.249926 0.943957 + outer loop + vertex 1.07912 2.08325 2.55897 + vertex 1.08191 2.08616 2.55756 + vertex 1.07728 2.08636 2.55857 + endloop + endfacet + facet normal 0.192937 0.237604 0.952008 + outer loop + vertex 1.07912 2.08325 2.55897 + vertex 1.07728 2.08636 2.55857 + vertex 1.07445 2.08335 2.5599 + endloop + endfacet + facet normal 0.193381 0.220044 0.95613 + outer loop + vertex 1.07445 2.08335 2.5599 + vertex 1.0795 2.07859 2.55997 + vertex 1.07912 2.08325 2.55897 + endloop + endfacet + facet normal 0.219995 0.248134 0.943415 + outer loop + vertex 1.07482 2.0789 2.56098 + vertex 1.0795 2.07859 2.55997 + vertex 1.07445 2.08335 2.5599 + endloop + endfacet + facet normal 0.219909 0.237818 0.946088 + outer loop + vertex 1.07482 2.0789 2.56098 + vertex 1.0766 2.07575 2.56136 + vertex 1.0795 2.07859 2.55997 + endloop + endfacet + facet normal 0.236247 0.22123 0.946174 + outer loop + vertex 1.07977 2.07395 2.56099 + vertex 1.0795 2.07859 2.55997 + vertex 1.0766 2.07575 2.56136 + endloop + endfacet + facet normal 0.231642 0.212488 0.949311 + outer loop + vertex 1.0766 2.07575 2.56136 + vertex 1.0768 2.07111 2.56235 + vertex 1.07977 2.07395 2.56099 + endloop + endfacet + facet normal 0.192924 0.212692 0.957884 + outer loop + vertex 1.0766 2.07575 2.56136 + vertex 1.07189 2.07584 2.56228 + vertex 1.0768 2.07111 2.56235 + endloop + endfacet + facet normal 0.216345 0.236849 0.947152 + outer loop + vertex 1.07189 2.07584 2.56228 + vertex 1.07216 2.0713 2.56336 + vertex 1.0768 2.07111 2.56235 + endloop + endfacet + facet normal 0.216439 0.228747 0.94912 + outer loop + vertex 1.07395 2.06811 2.56372 + vertex 1.0768 2.07111 2.56235 + vertex 1.07216 2.0713 2.56336 + endloop + endfacet + facet normal 0.199447 0.219869 0.954923 + outer loop + vertex 1.07395 2.06811 2.56372 + vertex 1.07216 2.0713 2.56336 + vertex 1.06924 2.06819 2.56468 + endloop + endfacet + facet normal 0.199871 0.204518 0.95824 + outer loop + vertex 1.06924 2.06819 2.56468 + vertex 1.07432 2.06333 2.56466 + vertex 1.07395 2.06811 2.56372 + endloop + endfacet + facet normal 0.232116 0.238237 0.943062 + outer loop + vertex 1.06961 2.06364 2.56574 + vertex 1.07432 2.06333 2.56466 + vertex 1.06924 2.06819 2.56468 + endloop + endfacet + facet normal 0.232019 0.228017 0.945608 + outer loop + vertex 1.06961 2.06364 2.56574 + vertex 1.07145 2.06045 2.56606 + vertex 1.07432 2.06333 2.56466 + endloop + endfacet + facet normal 0.215036 0.218876 0.951763 + outer loop + vertex 1.07145 2.06045 2.56606 + vertex 1.06961 2.06364 2.56574 + vertex 1.06677 2.06063 2.56708 + endloop + endfacet + facet normal 0.192652 0.223492 0.955477 + outer loop + vertex 1.0766 2.07575 2.56136 + vertex 1.07482 2.0789 2.56098 + vertex 1.07189 2.07584 2.56228 + endloop + endfacet + facet normal 0.215387 0.263557 0.94029 + outer loop + vertex 1.07689 2.09081 2.55741 + vertex 1.07728 2.08636 2.55857 + vertex 1.08191 2.08616 2.55756 + endloop + endfacet + facet normal 0.192806 0.239535 0.951551 + outer loop + vertex 1.08162 2.0907 2.55648 + vertex 1.07689 2.09081 2.55741 + vertex 1.08191 2.08616 2.55756 + endloop + endfacet + facet normal 0.22425 0.239904 0.944541 + outer loop + vertex 1.08162 2.0907 2.55648 + vertex 1.08191 2.08616 2.55756 + vertex 1.08486 2.08895 2.55615 + endloop + endfacet + facet normal 0.228744 0.24886 0.94114 + outer loop + vertex 1.08486 2.08895 2.55615 + vertex 1.0845 2.09352 2.55504 + vertex 1.08162 2.0907 2.55648 + endloop + endfacet + facet normal 0.214078 0.263617 0.940573 + outer loop + vertex 1.07976 2.09381 2.55603 + vertex 1.08162 2.0907 2.55648 + vertex 1.0845 2.09352 2.55504 + endloop + endfacet + facet normal 0.214098 0.272073 0.938157 + outer loop + vertex 1.07976 2.09381 2.55603 + vertex 1.0845 2.09352 2.55504 + vertex 1.07933 2.09824 2.55484 + endloop + endfacet + facet normal 0.273082 0.249391 0.929102 + outer loop + vertex 1.08486 2.08895 2.55615 + vertex 1.08936 2.08857 2.55494 + vertex 1.0845 2.09352 2.55504 + endloop + endfacet + facet normal 0.236944 0.213534 0.947766 + outer loop + vertex 1.0845 2.09352 2.55504 + vertex 1.08936 2.08857 2.55494 + vertex 1.08918 2.09314 2.55395 + endloop + endfacet + facet normal 0.237409 0.23292 0.943072 + outer loop + vertex 1.08918 2.09314 2.55395 + vertex 1.08739 2.09635 2.55361 + vertex 1.0845 2.09352 2.55504 + endloop + endfacet + facet normal 0.221617 0.248873 0.94284 + outer loop + vertex 1.0845 2.09352 2.55504 + vertex 1.08739 2.09635 2.55361 + vertex 1.08408 2.09813 2.55392 + endloop + endfacet + facet normal 0.191482 0.247808 0.949698 + outer loop + vertex 1.07933 2.09824 2.55484 + vertex 1.0845 2.09352 2.55504 + vertex 1.08408 2.09813 2.55392 + endloop + endfacet + facet normal 0.191203 0.258331 0.946946 + outer loop + vertex 1.08408 2.09813 2.55392 + vertex 1.08218 2.10124 2.55345 + vertex 1.07933 2.09824 2.55484 + endloop + endfacet + facet normal 0.1787 0.269841 0.946177 + outer loop + vertex 1.07933 2.09824 2.55484 + vertex 1.08218 2.10124 2.55345 + vertex 1.07889 2.1027 2.55366 + endloop + endfacet + facet normal 0.18037 0.273816 0.944718 + outer loop + vertex 1.08218 2.10124 2.55345 + vertex 1.08174 2.10566 2.55225 + vertex 1.07889 2.1027 2.55366 + endloop + endfacet + facet normal 0.166718 0.286346 0.94351 + outer loop + vertex 1.07889 2.1027 2.55366 + vertex 1.08174 2.10566 2.55225 + vertex 1.07695 2.10548 2.55316 + endloop + endfacet + facet normal 0.152973 0.277621 0.948433 + outer loop + vertex 1.07889 2.1027 2.55366 + vertex 1.07695 2.10548 2.55316 + vertex 1.07448 2.10222 2.55451 + endloop + endfacet + facet normal 0.154386 0.268674 0.950778 + outer loop + vertex 1.07448 2.10222 2.55451 + vertex 1.07933 2.09824 2.55484 + vertex 1.07889 2.1027 2.55366 + endloop + endfacet + facet normal 0.167043 0.283564 0.944292 + outer loop + vertex 1.07449 2.09813 2.55573 + vertex 1.07933 2.09824 2.55484 + vertex 1.07448 2.10222 2.55451 + endloop + endfacet + facet normal 0.14133 0.284621 0.948165 + outer loop + vertex 1.07036 2.09947 2.55595 + vertex 1.07449 2.09813 2.55573 + vertex 1.07448 2.10222 2.55451 + endloop + endfacet + facet normal 0.166966 0.284574 0.944002 + outer loop + vertex 1.07449 2.09813 2.55573 + vertex 1.07647 2.09529 2.55624 + vertex 1.07933 2.09824 2.55484 + endloop + endfacet + facet normal 0.181713 0.27087 0.945309 + outer loop + vertex 1.07976 2.09381 2.55603 + vertex 1.07933 2.09824 2.55484 + vertex 1.07647 2.09529 2.55624 + endloop + endfacet + facet normal 0.178954 0.264418 0.94766 + outer loop + vertex 1.07647 2.09529 2.55624 + vertex 1.07689 2.09081 2.55741 + vertex 1.07976 2.09381 2.55603 + endloop + endfacet + facet normal 0.154538 0.263342 0.952244 + outer loop + vertex 1.07647 2.09529 2.55624 + vertex 1.07204 2.09483 2.55709 + vertex 1.07689 2.09081 2.55741 + endloop + endfacet + facet normal 0.167652 0.278612 0.945658 + outer loop + vertex 1.07204 2.09483 2.55709 + vertex 1.07208 2.09069 2.5583 + vertex 1.07689 2.09081 2.55741 + endloop + endfacet + facet normal 0.167868 0.275787 0.946447 + outer loop + vertex 1.07404 2.08783 2.55879 + vertex 1.07689 2.09081 2.55741 + vertex 1.07208 2.09069 2.5583 + endloop + endfacet + facet normal 0.153249 0.26663 0.951537 + outer loop + vertex 1.07404 2.08783 2.55879 + vertex 1.07208 2.09069 2.5583 + vertex 1.06963 2.08739 2.55962 + endloop + endfacet + facet normal 0.155571 0.250728 0.955475 + outer loop + vertex 1.06963 2.08739 2.55962 + vertex 1.07445 2.08335 2.5599 + vertex 1.07404 2.08783 2.55879 + endloop + endfacet + facet normal 0.177645 0.251716 0.951358 + outer loop + vertex 1.07445 2.08335 2.5599 + vertex 1.07728 2.08636 2.55857 + vertex 1.07404 2.08783 2.55879 + endloop + endfacet + facet normal 0.169033 0.266313 0.94895 + outer loop + vertex 1.06964 2.08326 2.56078 + vertex 1.07445 2.08335 2.5599 + vertex 1.06963 2.08739 2.55962 + endloop + endfacet + facet normal 0.16942 0.260555 0.950478 + outer loop + vertex 1.06964 2.08326 2.56078 + vertex 1.07158 2.08038 2.56122 + vertex 1.07445 2.08335 2.5599 + endloop + endfacet + facet normal 0.153437 0.250614 0.95585 + outer loop + vertex 1.07158 2.08038 2.56122 + vertex 1.06964 2.08326 2.56078 + vertex 1.06713 2.07991 2.56206 + endloop + endfacet + facet normal 0.141394 0.275185 0.950937 + outer loop + vertex 1.06963 2.08739 2.55962 + vertex 1.07208 2.09069 2.5583 + vertex 1.06796 2.09206 2.55852 + endloop + endfacet + facet normal 0.182288 0.262516 0.947553 + outer loop + vertex 1.07728 2.08636 2.55857 + vertex 1.07689 2.09081 2.55741 + vertex 1.07404 2.08783 2.55879 + endloop + endfacet + facet normal 0.152655 0.275514 0.949099 + outer loop + vertex 1.07647 2.09529 2.55624 + vertex 1.07449 2.09813 2.55573 + vertex 1.07204 2.09483 2.55709 + endloop + endfacet + facet normal 0.142042 0.285619 0.947758 + outer loop + vertex 1.07448 2.10222 2.55451 + vertex 1.07695 2.10548 2.55316 + vertex 1.07289 2.10678 2.55337 + endloop + endfacet + facet normal 0.136185 0.283921 0.949127 + outer loop + vertex 1.07448 2.10222 2.55451 + vertex 1.07289 2.10678 2.55337 + vertex 1.06873 2.10401 2.5548 + endloop + endfacet + facet normal 0.132097 0.289481 0.948025 + outer loop + vertex 1.06873 2.10401 2.5548 + vertex 1.07289 2.10678 2.55337 + vertex 1.06876 2.10818 2.55352 + endloop + endfacet + facet normal 0.134289 0.289381 0.947747 + outer loop + vertex 1.06417 2.10733 2.55443 + vertex 1.06873 2.10401 2.5548 + vertex 1.06876 2.10818 2.55352 + endloop + endfacet + facet normal 0.130387 0.305567 0.943201 + outer loop + vertex 1.06876 2.10818 2.55352 + vertex 1.06637 2.11183 2.55267 + vertex 1.06417 2.10733 2.55443 + endloop + endfacet + facet normal 0.129804 0.305228 0.943391 + outer loop + vertex 1.06876 2.10818 2.55352 + vertex 1.07165 2.11087 2.55225 + vertex 1.06637 2.11183 2.55267 + endloop + endfacet + facet normal 0.135416 0.299668 0.944384 + outer loop + vertex 1.07289 2.10678 2.55337 + vertex 1.07165 2.11087 2.55225 + vertex 1.06876 2.10818 2.55352 + endloop + endfacet + facet normal 0.136766 0.299994 0.944086 + outer loop + vertex 1.07289 2.10678 2.55337 + vertex 1.07692 2.10947 2.55193 + vertex 1.07165 2.11087 2.55225 + endloop + endfacet + facet normal 0.143598 0.290782 0.945952 + outer loop + vertex 1.07695 2.10548 2.55316 + vertex 1.07692 2.10947 2.55193 + vertex 1.07289 2.10678 2.55337 + endloop + endfacet + facet normal 0.166393 0.289892 0.942484 + outer loop + vertex 1.07692 2.10947 2.55193 + vertex 1.07695 2.10548 2.55316 + vertex 1.08174 2.10566 2.55225 + endloop + endfacet + facet normal 0.155871 0.277065 0.948124 + outer loop + vertex 1.08121 2.1101 2.55105 + vertex 1.07692 2.10947 2.55193 + vertex 1.08174 2.10566 2.55225 + endloop + endfacet + facet normal 0.177845 0.278524 0.94382 + outer loop + vertex 1.08121 2.1101 2.55105 + vertex 1.08174 2.10566 2.55225 + vertex 1.0845 2.10871 2.55083 + endloop + endfacet + facet normal 0.190732 0.311144 0.931027 + outer loop + vertex 1.0845 2.10871 2.55083 + vertex 1.08381 2.11306 2.54952 + vertex 1.08121 2.1101 2.55105 + endloop + endfacet + facet normal 0.207745 0.312572 0.926899 + outer loop + vertex 1.0845 2.10871 2.55083 + vertex 1.08929 2.10844 2.54985 + vertex 1.08381 2.11306 2.54952 + endloop + endfacet + facet normal 0.183245 0.284581 0.940976 + outer loop + vertex 1.08381 2.11306 2.54952 + vertex 1.08929 2.10844 2.54985 + vertex 1.08874 2.11304 2.54857 + endloop + endfacet + facet normal 0.192582 0.285126 0.938944 + outer loop + vertex 1.08929 2.10844 2.54985 + vertex 1.09221 2.11114 2.54843 + vertex 1.08874 2.11304 2.54857 + endloop + endfacet + facet normal 0.208132 0.314439 0.92618 + outer loop + vertex 1.09221 2.11114 2.54843 + vertex 1.09204 2.11496 2.54717 + vertex 1.08874 2.11304 2.54857 + endloop + endfacet + facet normal 0.208026 0.279167 0.937439 + outer loop + vertex 1.0845 2.10871 2.55083 + vertex 1.08646 2.10562 2.55132 + vertex 1.08929 2.10844 2.54985 + endloop + endfacet + facet normal 0.22365 0.263983 0.93824 + outer loop + vertex 1.08981 2.10384 2.55102 + vertex 1.08929 2.10844 2.54985 + vertex 1.08646 2.10562 2.55132 + endloop + endfacet + facet normal 0.21865 0.253885 0.942196 + outer loop + vertex 1.08646 2.10562 2.55132 + vertex 1.08694 2.10097 2.55246 + vertex 1.08981 2.10384 2.55102 + endloop + endfacet + facet normal 0.190062 0.252585 0.948724 + outer loop + vertex 1.08646 2.10562 2.55132 + vertex 1.08174 2.10566 2.55225 + vertex 1.08694 2.10097 2.55246 + endloop + endfacet + facet normal 0.189373 0.268415 0.944506 + outer loop + vertex 1.08646 2.10562 2.55132 + vertex 1.0845 2.10871 2.55083 + vertex 1.08174 2.10566 2.55225 + endloop + endfacet + facet normal 0.210738 0.275048 0.93805 + outer loop + vertex 1.08174 2.10566 2.55225 + vertex 1.08218 2.10124 2.55345 + vertex 1.08694 2.10097 2.55246 + endloop + endfacet + facet normal 0.210758 0.269208 0.939738 + outer loop + vertex 1.08408 2.09813 2.55392 + vertex 1.08694 2.10097 2.55246 + vertex 1.08218 2.10124 2.55345 + endloop + endfacet + facet normal 0.224864 0.25537 0.940331 + outer loop + vertex 1.08739 2.09635 2.55361 + vertex 1.08694 2.10097 2.55246 + vertex 1.08408 2.09813 2.55392 + endloop + endfacet + facet normal 0.260886 0.256498 0.93067 + outer loop + vertex 1.08694 2.10097 2.55246 + vertex 1.08739 2.09635 2.55361 + vertex 1.0919 2.09601 2.55244 + endloop + endfacet + facet normal 0.232561 0.228093 0.945457 + outer loop + vertex 1.09167 2.10059 2.55139 + vertex 1.08694 2.10097 2.55246 + vertex 1.0919 2.09601 2.55244 + endloop + endfacet + facet normal 0.273649 0.227664 0.934497 + outer loop + vertex 1.09167 2.10059 2.55139 + vertex 1.0919 2.09601 2.55244 + vertex 1.09481 2.09873 2.55092 + endloop + endfacet + facet normal 0.275265 0.230703 0.933277 + outer loop + vertex 1.09481 2.09873 2.55092 + vertex 1.09445 2.10342 2.54987 + vertex 1.09167 2.10059 2.55139 + endloop + endfacet + facet normal 0.254601 0.251285 0.933828 + outer loop + vertex 1.08981 2.10384 2.55102 + vertex 1.09167 2.10059 2.55139 + vertex 1.09445 2.10342 2.54987 + endloop + endfacet + facet normal 0.25489 0.265409 0.929833 + outer loop + vertex 1.08981 2.10384 2.55102 + vertex 1.09445 2.10342 2.54987 + vertex 1.08929 2.10844 2.54985 + endloop + endfacet + facet normal 0.216623 0.226062 0.949721 + outer loop + vertex 1.08929 2.10844 2.54985 + vertex 1.09445 2.10342 2.54987 + vertex 1.09405 2.10806 2.54886 + endloop + endfacet + facet normal 0.217475 0.259242 0.941009 + outer loop + vertex 1.09405 2.10806 2.54886 + vertex 1.09221 2.11114 2.54843 + vertex 1.08929 2.10844 2.54985 + endloop + endfacet + facet normal 0.232686 0.267518 0.935036 + outer loop + vertex 1.09405 2.10806 2.54886 + vertex 1.09674 2.11082 2.5474 + vertex 1.09221 2.11114 2.54843 + endloop + endfacet + facet normal 0.257865 0.242997 0.935124 + outer loop + vertex 1.09715 2.10638 2.54844 + vertex 1.09674 2.11082 2.5474 + vertex 1.09405 2.10806 2.54886 + endloop + endfacet + facet normal 0.291569 0.243701 0.924985 + outer loop + vertex 1.09674 2.11082 2.5474 + vertex 1.09715 2.10638 2.54844 + vertex 1.10094 2.10652 2.54721 + endloop + endfacet + facet normal 0.295468 0.206989 0.93266 + outer loop + vertex 1.09897 2.10319 2.54857 + vertex 1.10094 2.10652 2.54721 + vertex 1.09715 2.10638 2.54844 + endloop + endfacet + facet normal 0.280256 0.198597 0.939157 + outer loop + vertex 1.09897 2.10319 2.54857 + vertex 1.09715 2.10638 2.54844 + vertex 1.09445 2.10342 2.54987 + endloop + endfacet + facet normal 0.28033 0.186789 0.941555 + outer loop + vertex 1.09445 2.10342 2.54987 + vertex 1.09911 2.09823 2.54951 + vertex 1.09897 2.10319 2.54857 + endloop + endfacet + facet normal 0.335755 0.185021 0.923599 + outer loop + vertex 1.09911 2.09823 2.54951 + vertex 1.10256 2.10156 2.54759 + vertex 1.09897 2.10319 2.54857 + endloop + endfacet + facet normal 0.334267 0.180909 0.924952 + outer loop + vertex 1.10256 2.10156 2.54759 + vertex 1.10094 2.10652 2.54721 + vertex 1.09897 2.10319 2.54857 + endloop + endfacet + facet normal 0.250076 0.22711 0.941214 + outer loop + vertex 1.09445 2.10342 2.54987 + vertex 1.09715 2.10638 2.54844 + vertex 1.09405 2.10806 2.54886 + endloop + endfacet + facet normal 0.327502 0.230815 0.916224 + outer loop + vertex 1.09481 2.09873 2.55092 + vertex 1.09911 2.09823 2.54951 + vertex 1.09445 2.10342 2.54987 + endloop + endfacet + facet normal 0.327135 0.219707 0.919082 + outer loop + vertex 1.09481 2.09873 2.55092 + vertex 1.09624 2.09558 2.55117 + vertex 1.09911 2.09823 2.54951 + endloop + endfacet + facet normal 0.351977 0.191024 0.916309 + outer loop + vertex 1.09876 2.09358 2.55062 + vertex 1.09911 2.09823 2.54951 + vertex 1.09624 2.09558 2.55117 + endloop + endfacet + facet normal 0.346544 0.183152 0.91998 + outer loop + vertex 1.09624 2.09558 2.55117 + vertex 1.09582 2.09155 2.55213 + vertex 1.09876 2.09358 2.55062 + endloop + endfacet + facet normal 0.293296 0.192594 0.936421 + outer loop + vertex 1.09624 2.09558 2.55117 + vertex 1.0919 2.09601 2.55244 + vertex 1.09582 2.09155 2.55213 + endloop + endfacet + facet normal 0.293739 0.205665 0.933498 + outer loop + vertex 1.09624 2.09558 2.55117 + vertex 1.09481 2.09873 2.55092 + vertex 1.0919 2.09601 2.55244 + endloop + endfacet + facet normal 0.232842 0.239828 0.942479 + outer loop + vertex 1.09167 2.10059 2.55139 + vertex 1.08981 2.10384 2.55102 + vertex 1.08694 2.10097 2.55246 + endloop + endfacet + facet normal 0.260811 0.244953 0.933796 + outer loop + vertex 1.08918 2.09314 2.55395 + vertex 1.0919 2.09601 2.55244 + vertex 1.08739 2.09635 2.55361 + endloop + endfacet + facet normal 0.280927 0.225347 0.932898 + outer loop + vertex 1.09216 2.09145 2.55346 + vertex 1.0919 2.09601 2.55244 + vertex 1.08918 2.09314 2.55395 + endloop + endfacet + facet normal 0.27464 0.212838 0.937695 + outer loop + vertex 1.08936 2.08857 2.55494 + vertex 1.09216 2.09145 2.55346 + vertex 1.08918 2.09314 2.55395 + endloop + endfacet + facet normal 0.307015 0.179772 0.934571 + outer loop + vertex 1.09372 2.08834 2.55355 + vertex 1.09216 2.09145 2.55346 + vertex 1.08936 2.08857 2.55494 + endloop + endfacet + facet normal 0.3071 0.162584 0.937687 + outer loop + vertex 1.08936 2.08857 2.55494 + vertex 1.09345 2.08381 2.55442 + vertex 1.09372 2.08834 2.55355 + endloop + endfacet + facet normal 0.370736 0.154571 0.915785 + outer loop + vertex 1.09345 2.08381 2.55442 + vertex 1.09702 2.08661 2.5525 + vertex 1.09372 2.08834 2.55355 + endloop + endfacet + facet normal 0.372974 0.159962 0.913949 + outer loop + vertex 1.09702 2.08661 2.5525 + vertex 1.09582 2.09155 2.55213 + vertex 1.09372 2.08834 2.55355 + endloop + endfacet + facet normal 0.350977 0.20288 0.914142 + outer loop + vertex 1.08942 2.0839 2.55595 + vertex 1.09345 2.08381 2.55442 + vertex 1.08936 2.08857 2.55494 + endloop + endfacet + facet normal 0.352243 0.176574 0.919101 + outer loop + vertex 1.08942 2.0839 2.55595 + vertex 1.09086 2.07988 2.55617 + vertex 1.09345 2.08381 2.55442 + endloop + endfacet + facet normal 0.319062 0.16552 0.933168 + outer loop + vertex 1.09086 2.07988 2.55617 + vertex 1.08942 2.0839 2.55595 + vertex 1.08631 2.08166 2.55741 + endloop + endfacet + facet normal 0.331285 0.191665 0.923859 + outer loop + vertex 1.09372 2.08834 2.55355 + vertex 1.09582 2.09155 2.55213 + vertex 1.09216 2.09145 2.55346 + endloop + endfacet + facet normal 0.328158 0.224547 0.917546 + outer loop + vertex 1.0919 2.09601 2.55244 + vertex 1.09216 2.09145 2.55346 + vertex 1.09582 2.09155 2.55213 + endloop + endfacet + facet normal 0.272881 0.234397 0.933056 + outer loop + vertex 1.08486 2.08895 2.55615 + vertex 1.08648 2.08581 2.55647 + vertex 1.08936 2.08857 2.55494 + endloop + endfacet + facet normal 0.299463 0.205921 0.931621 + outer loop + vertex 1.08942 2.0839 2.55595 + vertex 1.08936 2.08857 2.55494 + vertex 1.08648 2.08581 2.55647 + endloop + endfacet + facet normal 0.295455 0.199001 0.934401 + outer loop + vertex 1.08648 2.08581 2.55647 + vertex 1.08631 2.08166 2.55741 + vertex 1.08942 2.0839 2.55595 + endloop + endfacet + facet normal 0.242752 0.204335 0.948324 + outer loop + vertex 1.08648 2.08581 2.55647 + vertex 1.08191 2.08616 2.55756 + vertex 1.08631 2.08166 2.55741 + endloop + endfacet + facet normal 0.243072 0.22012 0.944703 + outer loop + vertex 1.08648 2.08581 2.55647 + vertex 1.08486 2.08895 2.55615 + vertex 1.08191 2.08616 2.55756 + endloop + endfacet + facet normal 0.192468 0.251842 0.948436 + outer loop + vertex 1.08162 2.0907 2.55648 + vertex 1.07976 2.09381 2.55603 + vertex 1.07689 2.09081 2.55741 + endloop + endfacet + facet normal 0.273095 0.234536 0.932959 + outer loop + vertex 1.08191 2.08616 2.55756 + vertex 1.08228 2.08158 2.55861 + vertex 1.08631 2.08166 2.55741 + endloop + endfacet + facet normal 0.275193 0.209008 0.938395 + outer loop + vertex 1.08421 2.07827 2.55878 + vertex 1.08631 2.08166 2.55741 + vertex 1.08228 2.08158 2.55861 + endloop + endfacet + facet normal 0.314814 0.185126 0.930924 + outer loop + vertex 1.08425 2.07344 2.55972 + vertex 1.08822 2.07622 2.55783 + vertex 1.08421 2.07827 2.55878 + endloop + endfacet + facet normal 0.324503 0.170864 0.930324 + outer loop + vertex 1.08801 2.07254 2.55858 + vertex 1.08822 2.07622 2.55783 + vertex 1.08425 2.07344 2.55972 + endloop + endfacet + facet normal 0.319672 0.142456 0.936758 + outer loop + vertex 1.08425 2.07344 2.55972 + vertex 1.08799 2.06864 2.55918 + vertex 1.08801 2.07254 2.55858 + endloop + endfacet + facet normal 0.366045 0.181278 0.91277 + outer loop + vertex 1.08417 2.06874 2.56069 + vertex 1.08799 2.06864 2.55918 + vertex 1.08425 2.07344 2.55972 + endloop + endfacet + facet normal 0.367025 0.158114 0.916675 + outer loop + vertex 1.08417 2.06874 2.56069 + vertex 1.0856 2.06461 2.56083 + vertex 1.08799 2.06864 2.55918 + endloop + endfacet + facet normal 0.326655 0.144658 0.934008 + outer loop + vertex 1.0856 2.06461 2.56083 + vertex 1.08417 2.06874 2.56069 + vertex 1.08111 2.06646 2.56211 + endloop + endfacet + facet normal 0.335443 0.171377 0.926341 + outer loop + vertex 1.08111 2.06646 2.56211 + vertex 1.08304 2.06089 2.56245 + vertex 1.0856 2.06461 2.56083 + endloop + endfacet + facet normal 0.318434 0.165914 0.933312 + outer loop + vertex 1.08304 2.06089 2.56245 + vertex 1.08111 2.06646 2.56211 + vertex 1.07903 2.06299 2.56344 + endloop + endfacet + facet normal 0.249078 0.193992 0.948856 + outer loop + vertex 1.08131 2.07073 2.56124 + vertex 1.07977 2.07395 2.56099 + vertex 1.0768 2.07111 2.56235 + endloop + endfacet + facet normal 0.279015 0.192442 0.940806 + outer loop + vertex 1.07903 2.06299 2.56344 + vertex 1.08111 2.06646 2.56211 + vertex 1.07711 2.0664 2.56331 + endloop + endfacet + facet normal 0.320723 0.171074 0.931596 + outer loop + vertex 1.07905 2.05813 2.56433 + vertex 1.08304 2.06089 2.56245 + vertex 1.07903 2.06299 2.56344 + endloop + endfacet + facet normal 0.329254 0.158267 0.930883 + outer loop + vertex 1.08278 2.05723 2.56316 + vertex 1.08304 2.06089 2.56245 + vertex 1.07905 2.05813 2.56433 + endloop + endfacet + facet normal 0.324984 0.133349 0.936271 + outer loop + vertex 1.07905 2.05813 2.56433 + vertex 1.0825 2.05352 2.56379 + vertex 1.08278 2.05723 2.56316 + endloop + endfacet + facet normal 0.2659 0.184135 0.946251 + outer loop + vertex 1.0761 2.0554 2.56583 + vertex 1.07463 2.05861 2.56562 + vertex 1.07162 2.05583 2.567 + endloop + endfacet + facet normal 0.292432 0.167717 0.941464 + outer loop + vertex 1.07291 2.04726 2.56826 + vertex 1.07555 2.05122 2.56673 + vertex 1.07157 2.05118 2.56797 + endloop + endfacet + facet normal 0.276669 0.162752 0.947083 + outer loop + vertex 1.07291 2.04726 2.56826 + vertex 1.07157 2.05118 2.56797 + vertex 1.06827 2.04872 2.56936 + endloop + endfacet + facet normal 0.277836 0.167308 0.945947 + outer loop + vertex 1.07017 2.04313 2.56979 + vertex 1.07291 2.04726 2.56826 + vertex 1.06827 2.04872 2.56936 + endloop + endfacet + facet normal 0.284687 0.169437 0.943528 + outer loop + vertex 1.07017 2.04313 2.56979 + vertex 1.06827 2.04872 2.56936 + vertex 1.06554 2.04465 2.57091 + endloop + endfacet + facet normal 0.2868 0.177379 0.941426 + outer loop + vertex 1.06683 2.04073 2.57126 + vertex 1.07017 2.04313 2.56979 + vertex 1.06554 2.04465 2.57091 + endloop + endfacet + facet normal 0.273929 0.173569 0.945958 + outer loop + vertex 1.06554 2.04465 2.57091 + vertex 1.06274 2.04068 2.57245 + vertex 1.06683 2.04073 2.57126 + endloop + endfacet + facet normal 0.274562 0.16293 0.947665 + outer loop + vertex 1.06683 2.04073 2.57126 + vertex 1.06274 2.04068 2.57245 + vertex 1.06608 2.03658 2.57219 + endloop + endfacet + facet normal 0.303662 0.155962 0.939928 + outer loop + vertex 1.06683 2.04073 2.57126 + vertex 1.06608 2.03658 2.57219 + vertex 1.06939 2.03873 2.57076 + endloop + endfacet + facet normal 0.293588 0.178973 0.939029 + outer loop + vertex 1.06274 2.04068 2.57245 + vertex 1.06225 2.03648 2.57341 + vertex 1.06608 2.03658 2.57219 + endloop + endfacet + facet normal 0.294509 0.166804 0.940979 + outer loop + vertex 1.06367 2.03337 2.57351 + vertex 1.06608 2.03658 2.57219 + vertex 1.06225 2.03648 2.57341 + endloop + endfacet + facet normal 0.277949 0.159437 0.947272 + outer loop + vertex 1.06367 2.03337 2.57351 + vertex 1.06225 2.03648 2.57341 + vertex 1.05923 2.03362 2.57478 + endloop + endfacet + facet normal 0.277926 0.15677 0.947724 + outer loop + vertex 1.05923 2.03362 2.57478 + vertex 1.06344 2.02875 2.57435 + vertex 1.06367 2.03337 2.57351 + endloop + endfacet + facet normal 0.320252 0.152298 0.93501 + outer loop + vertex 1.06344 2.02875 2.57435 + vertex 1.06724 2.03156 2.57259 + vertex 1.06367 2.03337 2.57351 + endloop + endfacet + facet normal 0.335911 0.129769 0.932911 + outer loop + vertex 1.06845 2.02618 2.5729 + vertex 1.06724 2.03156 2.57259 + vertex 1.06344 2.02875 2.57435 + endloop + endfacet + facet normal 0.344625 0.150337 0.926624 + outer loop + vertex 1.06509 2.02289 2.57468 + vertex 1.06845 2.02618 2.5729 + vertex 1.06344 2.02875 2.57435 + endloop + endfacet + facet normal 0.335294 0.147916 0.930429 + outer loop + vertex 1.06509 2.02289 2.57468 + vertex 1.06344 2.02875 2.57435 + vertex 1.06071 2.02481 2.57596 + endloop + endfacet + facet normal 0.339481 0.159764 0.926946 + outer loop + vertex 1.06196 2.02082 2.57619 + vertex 1.06509 2.02289 2.57468 + vertex 1.06071 2.02481 2.57596 + endloop + endfacet + facet normal 0.3182 0.153631 0.935492 + outer loop + vertex 1.06071 2.02481 2.57596 + vertex 1.05792 2.02099 2.57753 + vertex 1.06196 2.02082 2.57619 + endloop + endfacet + facet normal 0.318294 0.1436 0.937053 + outer loop + vertex 1.06196 2.02082 2.57619 + vertex 1.05792 2.02099 2.57753 + vertex 1.06118 2.01672 2.57708 + endloop + endfacet + facet normal 0.349568 0.135495 0.927062 + outer loop + vertex 1.06196 2.02082 2.57619 + vertex 1.06118 2.01672 2.57708 + vertex 1.06434 2.01876 2.57559 + endloop + endfacet + facet normal 0.361637 0.115348 0.925156 + outer loop + vertex 1.06509 2.01484 2.57578 + vertex 1.06434 2.01876 2.57559 + vertex 1.06118 2.01672 2.57708 + endloop + endfacet + facet normal 0.366578 0.128147 0.92152 + outer loop + vertex 1.06118 2.01672 2.57708 + vertex 1.06205 2.01174 2.57742 + vertex 1.06509 2.01484 2.57578 + endloop + endfacet + facet normal 0.389015 0.102974 0.915458 + outer loop + vertex 1.06509 2.01484 2.57578 + vertex 1.06205 2.01174 2.57742 + vertex 1.06581 2.00997 2.57603 + endloop + endfacet + facet normal 0.410691 0.105662 0.905631 + outer loop + vertex 1.06581 2.00997 2.57603 + vertex 1.06879 2.01336 2.57428 + vertex 1.06509 2.01484 2.57578 + endloop + endfacet + facet normal 0.408705 0.0990345 0.907277 + outer loop + vertex 1.06879 2.01336 2.57428 + vertex 1.06788 2.01869 2.57411 + vertex 1.06509 2.01484 2.57578 + endloop + endfacet + facet normal 0.435655 0.0790726 0.896634 + outer loop + vertex 1.06941 2.00831 2.57442 + vertex 1.06879 2.01336 2.57428 + vertex 1.06581 2.00997 2.57603 + endloop + endfacet + facet normal 0.438508 0.087345 0.894473 + outer loop + vertex 1.06649 2.00502 2.57618 + vertex 1.06941 2.00831 2.57442 + vertex 1.06581 2.00997 2.57603 + endloop + endfacet + facet normal 0.410306 0.0838557 0.908084 + outer loop + vertex 1.06581 2.00997 2.57603 + vertex 1.06267 2.00666 2.57775 + vertex 1.06649 2.00502 2.57618 + endloop + endfacet + facet normal 0.412351 0.0900731 0.906561 + outer loop + vertex 1.06267 2.00666 2.57775 + vertex 1.06366 2.00117 2.57785 + vertex 1.06649 2.00502 2.57618 + endloop + endfacet + facet normal 0.436954 0.0678337 0.896922 + outer loop + vertex 1.06649 2.00502 2.57618 + vertex 1.06366 2.00117 2.57785 + vertex 1.0671 2.00103 2.57618 + endloop + endfacet + facet normal 0.474408 0.0734921 0.877232 + outer loop + vertex 1.0671 2.00103 2.57618 + vertex 1.07007 2.00304 2.5744 + vertex 1.06649 2.00502 2.57618 + endloop + endfacet + facet normal 0.467075 0.0555605 0.88247 + outer loop + vertex 1.07007 2.00304 2.5744 + vertex 1.06941 2.00831 2.57442 + vertex 1.06649 2.00502 2.57618 + endloop + endfacet + facet normal 0.487739 0.048725 0.871629 + outer loop + vertex 1.06903 1.99889 2.57522 + vertex 1.07007 2.00304 2.5744 + vertex 1.0671 2.00103 2.57618 + endloop + endfacet + facet normal 0.481827 0.0417366 0.875272 + outer loop + vertex 1.0671 2.00103 2.57618 + vertex 1.06604 1.99702 2.57696 + vertex 1.06903 1.99889 2.57522 + endloop + endfacet + facet normal 0.436908 0.0578962 0.897641 + outer loop + vertex 1.0671 2.00103 2.57618 + vertex 1.06366 2.00117 2.57785 + vertex 1.06604 1.99702 2.57696 + endloop + endfacet + facet normal 0.393288 0.086782 0.915311 + outer loop + vertex 1.06366 2.00117 2.57785 + vertex 1.06267 2.00666 2.57775 + vertex 1.05946 2.00323 2.57946 + endloop + endfacet + facet normal 0.395425 0.0922967 0.913849 + outer loop + vertex 1.06031 1.99784 2.57963 + vertex 1.06366 2.00117 2.57785 + vertex 1.05946 2.00323 2.57946 + endloop + endfacet + facet normal 0.406122 0.0796455 0.910341 + outer loop + vertex 1.06326 1.99744 2.57835 + vertex 1.06366 2.00117 2.57785 + vertex 1.06031 1.99784 2.57963 + endloop + endfacet + facet normal 0.404593 0.0620872 0.912387 + outer loop + vertex 1.06031 1.99784 2.57963 + vertex 1.06278 1.99376 2.57882 + vertex 1.06326 1.99744 2.57835 + endloop + endfacet + facet normal 0.421298 0.0738628 0.903909 + outer loop + vertex 1.05931 1.99378 2.58043 + vertex 1.06278 1.99376 2.57882 + vertex 1.06031 1.99784 2.57963 + endloop + endfacet + facet normal 0.39328 0.0831268 0.915653 + outer loop + vertex 1.05931 1.99378 2.58043 + vertex 1.06031 1.99784 2.57963 + vertex 1.05712 1.99585 2.58119 + endloop + endfacet + facet normal 0.397031 0.087854 0.913591 + outer loop + vertex 1.05712 1.99585 2.58119 + vertex 1.05611 1.99183 2.58201 + vertex 1.05931 1.99378 2.58043 + endloop + endfacet + facet normal 0.403697 0.0754616 0.911775 + outer loop + vertex 1.05991 1.9899 2.58049 + vertex 1.05931 1.99378 2.58043 + vertex 1.05611 1.99183 2.58201 + endloop + endfacet + facet normal 0.410243 0.091786 0.907346 + outer loop + vertex 1.05611 1.99183 2.58201 + vertex 1.05676 1.98667 2.58224 + vertex 1.05991 1.9899 2.58049 + endloop + endfacet + facet normal 0.424156 0.0755576 0.902432 + outer loop + vertex 1.05991 1.9899 2.58049 + vertex 1.05676 1.98667 2.58224 + vertex 1.06044 1.98505 2.58064 + endloop + endfacet + facet normal 0.446788 0.0776456 0.891264 + outer loop + vertex 1.06044 1.98505 2.58064 + vertex 1.06352 1.98852 2.5788 + vertex 1.05991 1.9899 2.58049 + endloop + endfacet + facet normal 0.441646 0.0592484 0.895231 + outer loop + vertex 1.06352 1.98852 2.5788 + vertex 1.06278 1.99376 2.57882 + vertex 1.05991 1.9899 2.58049 + endloop + endfacet + facet normal 0.428871 0.0897321 0.898898 + outer loop + vertex 1.05676 1.98667 2.58224 + vertex 1.05725 1.98166 2.5825 + vertex 1.06044 1.98505 2.58064 + endloop + endfacet + facet normal 0.443894 0.0724492 0.893146 + outer loop + vertex 1.06044 1.98505 2.58064 + vertex 1.05725 1.98166 2.5825 + vertex 1.06073 1.98011 2.5809 + endloop + endfacet + facet normal 0.468051 0.0732417 0.880661 + outer loop + vertex 1.06073 1.98011 2.5809 + vertex 1.06389 1.98354 2.57893 + vertex 1.06044 1.98505 2.58064 + endloop + endfacet + facet normal 0.463532 0.058964 0.884116 + outer loop + vertex 1.06389 1.98354 2.57893 + vertex 1.06352 1.98852 2.5788 + vertex 1.06044 1.98505 2.58064 + endloop + endfacet + facet normal 0.416353 0.0888332 0.904853 + outer loop + vertex 1.05725 1.98166 2.5825 + vertex 1.05676 1.98667 2.58224 + vertex 1.0536 1.98328 2.58403 + endloop + endfacet + facet normal 0.406014 0.100343 0.908341 + outer loop + vertex 1.0536 1.98328 2.58403 + vertex 1.05676 1.98667 2.58224 + vertex 1.05276 1.98858 2.58381 + endloop + endfacet + facet normal 0.399475 0.0994329 0.911336 + outer loop + vertex 1.0536 1.98328 2.58403 + vertex 1.05276 1.98858 2.58381 + vertex 1.04988 1.98474 2.5855 + endloop + endfacet + facet normal 0.401269 0.105468 0.909868 + outer loop + vertex 1.05044 1.97995 2.5858 + vertex 1.0536 1.98328 2.58403 + vertex 1.04988 1.98474 2.5855 + endloop + endfacet + facet normal 0.386622 0.104161 0.916337 + outer loop + vertex 1.04988 1.98474 2.5855 + vertex 1.04671 1.98168 2.58718 + vertex 1.05044 1.97995 2.5858 + endloop + endfacet + facet normal 0.390045 0.113602 0.913761 + outer loop + vertex 1.04671 1.98168 2.58718 + vertex 1.04721 1.97679 2.58757 + vertex 1.05044 1.97995 2.5858 + endloop + endfacet + facet normal 0.400873 0.100759 0.910576 + outer loop + vertex 1.05044 1.97995 2.5858 + vertex 1.04721 1.97679 2.58757 + vertex 1.05097 1.97509 2.58611 + endloop + endfacet + facet normal 0.411909 0.101652 0.905537 + outer loop + vertex 1.05097 1.97509 2.58611 + vertex 1.05407 1.97833 2.58433 + vertex 1.05044 1.97995 2.5858 + endloop + endfacet + facet normal 0.422702 0.0893155 0.901857 + outer loop + vertex 1.05455 1.97342 2.5846 + vertex 1.05407 1.97833 2.58433 + vertex 1.05097 1.97509 2.58611 + endloop + endfacet + facet normal 0.424766 0.0951369 0.90029 + outer loop + vertex 1.05169 1.97034 2.58627 + vertex 1.05455 1.97342 2.5846 + vertex 1.05097 1.97509 2.58611 + endloop + endfacet + facet normal 0.418031 0.0942277 0.903532 + outer loop + vertex 1.05097 1.97509 2.58611 + vertex 1.04806 1.97178 2.5878 + vertex 1.05169 1.97034 2.58627 + endloop + endfacet + facet normal 0.419385 0.0988387 0.902412 + outer loop + vertex 1.04806 1.97178 2.5878 + vertex 1.04928 1.96704 2.58775 + vertex 1.05169 1.97034 2.58627 + endloop + endfacet + facet normal 0.431022 0.0883307 0.898008 + outer loop + vertex 1.05169 1.97034 2.58627 + vertex 1.04928 1.96704 2.58775 + vertex 1.05233 1.96643 2.58635 + endloop + endfacet + facet normal 0.447248 0.0908249 0.889787 + outer loop + vertex 1.05233 1.96643 2.58635 + vertex 1.05529 1.9682 2.58468 + vertex 1.05169 1.97034 2.58627 + endloop + endfacet + facet normal 0.440924 0.0769033 0.894244 + outer loop + vertex 1.05529 1.9682 2.58468 + vertex 1.05455 1.97342 2.5846 + vertex 1.05169 1.97034 2.58627 + endloop + endfacet + facet normal 0.450435 0.0781762 0.88938 + outer loop + vertex 1.05529 1.9682 2.58468 + vertex 1.05797 1.97193 2.58299 + vertex 1.05455 1.97342 2.5846 + endloop + endfacet + facet normal 0.448512 0.0721539 0.89086 + outer loop + vertex 1.05797 1.97193 2.58299 + vertex 1.05758 1.97674 2.5828 + vertex 1.05455 1.97342 2.5846 + endloop + endfacet + facet normal 0.468633 0.0734032 0.880338 + outer loop + vertex 1.05758 1.97674 2.5828 + vertex 1.05797 1.97193 2.58299 + vertex 1.06091 1.97518 2.58116 + endloop + endfacet + facet normal 0.465214 0.0633256 0.88293 + outer loop + vertex 1.06073 1.98011 2.5809 + vertex 1.05758 1.97674 2.5828 + vertex 1.06091 1.97518 2.58116 + endloop + endfacet + facet normal 0.488272 0.0635288 0.870376 + outer loop + vertex 1.06091 1.97518 2.58116 + vertex 1.06403 1.97856 2.57916 + vertex 1.06073 1.98011 2.5809 + endloop + endfacet + facet normal 0.48486 0.053373 0.872962 + outer loop + vertex 1.06403 1.97856 2.57916 + vertex 1.06389 1.98354 2.57893 + vertex 1.06073 1.98011 2.5809 + endloop + endfacet + facet normal 0.447671 0.0838858 0.890255 + outer loop + vertex 1.05725 1.98166 2.5825 + vertex 1.05758 1.97674 2.5828 + vertex 1.06073 1.98011 2.5809 + endloop + endfacet + facet normal 0.430314 0.083264 0.898831 + outer loop + vertex 1.05758 1.97674 2.5828 + vertex 1.05725 1.98166 2.5825 + vertex 1.05407 1.97833 2.58433 + endloop + endfacet + facet normal 0.418888 0.0963966 0.902907 + outer loop + vertex 1.05407 1.97833 2.58433 + vertex 1.05725 1.98166 2.5825 + vertex 1.0536 1.98328 2.58403 + endloop + endfacet + facet normal 0.471303 0.058925 0.880001 + outer loop + vertex 1.05866 1.96787 2.5829 + vertex 1.05797 1.97193 2.58299 + vertex 1.05529 1.9682 2.58468 + endloop + endfacet + facet normal 0.471073 0.0542913 0.880422 + outer loop + vertex 1.05529 1.9682 2.58468 + vertex 1.05785 1.96334 2.58361 + vertex 1.05866 1.96787 2.5829 + endloop + endfacet + facet normal 0.45582 0.0738653 0.887002 + outer loop + vertex 1.05433 1.96407 2.58552 + vertex 1.05529 1.9682 2.58468 + vertex 1.05233 1.96643 2.58635 + endloop + endfacet + facet normal 0.456182 0.0742462 0.886784 + outer loop + vertex 1.05233 1.96643 2.58635 + vertex 1.05124 1.96234 2.58725 + vertex 1.05433 1.96407 2.58552 + endloop + endfacet + facet normal 0.462233 0.0612289 0.884642 + outer loop + vertex 1.05496 1.95982 2.58548 + vertex 1.05433 1.96407 2.58552 + vertex 1.05124 1.96234 2.58725 + endloop + endfacet + facet normal 0.472196 0.0807353 0.877789 + outer loop + vertex 1.05124 1.96234 2.58725 + vertex 1.05195 1.95687 2.58737 + vertex 1.05496 1.95982 2.58548 + endloop + endfacet + facet normal 0.486509 0.0620346 0.87147 + outer loop + vertex 1.05496 1.95982 2.58548 + vertex 1.05195 1.95687 2.58737 + vertex 1.05534 1.95478 2.58563 + endloop + endfacet + facet normal 0.506862 0.0632285 0.859705 + outer loop + vertex 1.05534 1.95478 2.58563 + vertex 1.05881 1.95713 2.58341 + vertex 1.05496 1.95982 2.58548 + endloop + endfacet + facet normal 0.49994 0.0494885 0.864645 + outer loop + vertex 1.05881 1.95713 2.58341 + vertex 1.05785 1.96334 2.58361 + vertex 1.05496 1.95982 2.58548 + endloop + endfacet + facet normal 0.512867 0.0517331 0.856908 + outer loop + vertex 1.05799 1.95256 2.58418 + vertex 1.05881 1.95713 2.58341 + vertex 1.05534 1.95478 2.58563 + endloop + endfacet + facet normal 0.515018 0.0552924 0.855394 + outer loop + vertex 1.05556 1.95004 2.5858 + vertex 1.05799 1.95256 2.58418 + vertex 1.05534 1.95478 2.58563 + endloop + endfacet + facet normal 0.504736 0.0550352 0.861518 + outer loop + vertex 1.05534 1.95478 2.58563 + vertex 1.05241 1.95183 2.58753 + vertex 1.05556 1.95004 2.5858 + endloop + endfacet + facet normal 0.507483 0.0618808 0.859437 + outer loop + vertex 1.05241 1.95183 2.58753 + vertex 1.05285 1.94699 2.58762 + vertex 1.05556 1.95004 2.5858 + endloop + endfacet + facet normal 0.520404 0.0463653 0.852661 + outer loop + vertex 1.05556 1.95004 2.5858 + vertex 1.05285 1.94699 2.58762 + vertex 1.05592 1.94543 2.58583 + endloop + endfacet + facet normal 0.521889 0.0464753 0.851747 + outer loop + vertex 1.05592 1.94543 2.58583 + vertex 1.05865 1.94844 2.584 + vertex 1.05556 1.95004 2.5858 + endloop + endfacet + facet normal 0.520872 0.0477339 0.852299 + outer loop + vertex 1.05901 1.94355 2.58405 + vertex 1.05865 1.94844 2.584 + vertex 1.05592 1.94543 2.58583 + endloop + endfacet + facet normal 0.519493 0.0445113 0.853314 + outer loop + vertex 1.05601 1.94073 2.58603 + vertex 1.05901 1.94355 2.58405 + vertex 1.05592 1.94543 2.58583 + endloop + endfacet + facet normal 0.528432 0.0444404 0.847812 + outer loop + vertex 1.05592 1.94543 2.58583 + vertex 1.05347 1.94293 2.58749 + vertex 1.05601 1.94073 2.58603 + endloop + endfacet + facet normal 0.528875 0.0451596 0.847497 + outer loop + vertex 1.05347 1.94293 2.58749 + vertex 1.05248 1.9385 2.58834 + vertex 1.05601 1.94073 2.58603 + endloop + endfacet + facet normal 0.529071 0.0447473 0.847397 + outer loop + vertex 1.05601 1.94073 2.58603 + vertex 1.05248 1.9385 2.58834 + vertex 1.05602 1.93577 2.58628 + endloop + endfacet + facet normal 0.506945 0.045345 0.860785 + outer loop + vertex 1.05602 1.93577 2.58628 + vertex 1.05925 1.93847 2.58424 + vertex 1.05601 1.94073 2.58603 + endloop + endfacet + facet normal 0.49946 0.0570525 0.864456 + outer loop + vertex 1.05931 1.93344 2.58453 + vertex 1.05925 1.93847 2.58424 + vertex 1.05602 1.93577 2.58628 + endloop + endfacet + facet normal 0.494649 0.0478044 0.867777 + outer loop + vertex 1.05629 1.93071 2.5864 + vertex 1.05931 1.93344 2.58453 + vertex 1.05602 1.93577 2.58628 + endloop + endfacet + facet normal 0.525882 0.0490216 0.849143 + outer loop + vertex 1.05602 1.93577 2.58628 + vertex 1.05297 1.93298 2.58833 + vertex 1.05629 1.93071 2.5864 + endloop + endfacet + facet normal 0.523467 0.0439978 0.850909 + outer loop + vertex 1.05297 1.93298 2.58833 + vertex 1.05337 1.9278 2.58835 + vertex 1.05629 1.93071 2.5864 + endloop + endfacet + facet normal 0.51162 0.060058 0.85711 + outer loop + vertex 1.05629 1.93071 2.5864 + vertex 1.05337 1.9278 2.58835 + vertex 1.05676 1.9257 2.58647 + endloop + endfacet + facet normal 0.46923 0.0564327 0.881271 + outer loop + vertex 1.05676 1.9257 2.58647 + vertex 1.05961 1.92861 2.58477 + vertex 1.05629 1.93071 2.5864 + endloop + endfacet + facet normal 0.434671 0.0985141 0.895185 + outer loop + vertex 1.06052 1.92345 2.5849 + vertex 1.05961 1.92861 2.58477 + vertex 1.05676 1.9257 2.58647 + endloop + endfacet + facet normal 0.416511 0.0598271 0.90716 + outer loop + vertex 1.05736 1.92151 2.58648 + vertex 1.06052 1.92345 2.5849 + vertex 1.05676 1.9257 2.58647 + endloop + endfacet + facet normal 0.487828 0.0699506 0.870133 + outer loop + vertex 1.05676 1.9257 2.58647 + vertex 1.05394 1.92217 2.58834 + vertex 1.05736 1.92151 2.58648 + endloop + endfacet + facet normal 0.506999 0.0495518 0.860521 + outer loop + vertex 1.05337 1.9278 2.58835 + vertex 1.05394 1.92217 2.58834 + vertex 1.05676 1.9257 2.58647 + endloop + endfacet + facet normal 0.535768 0.0449219 0.843169 + outer loop + vertex 1.05337 1.9278 2.58835 + vertex 1.05297 1.93298 2.58833 + vertex 1.05007 1.93001 2.59033 + endloop + endfacet + facet normal 0.537095 0.0478107 0.842166 + outer loop + vertex 1.05044 1.92493 2.59038 + vertex 1.05337 1.9278 2.58835 + vertex 1.05007 1.93001 2.59033 + endloop + endfacet + facet normal 0.52921 0.0472856 0.847172 + outer loop + vertex 1.05007 1.93001 2.59033 + vertex 1.04719 1.92693 2.5923 + vertex 1.05044 1.92493 2.59038 + endloop + endfacet + facet normal 0.533314 0.0569565 0.843997 + outer loop + vertex 1.04719 1.92693 2.5923 + vertex 1.04762 1.922 2.59236 + vertex 1.05044 1.92493 2.59038 + endloop + endfacet + facet normal 0.540877 0.046823 0.839798 + outer loop + vertex 1.05044 1.92493 2.59038 + vertex 1.04762 1.922 2.59236 + vertex 1.05061 1.92011 2.59054 + endloop + endfacet + facet normal 0.530842 0.046691 0.846183 + outer loop + vertex 1.05061 1.92011 2.59054 + vertex 1.05394 1.92217 2.58834 + vertex 1.05044 1.92493 2.59038 + endloop + endfacet + facet normal 0.530922 0.0465191 0.846143 + outer loop + vertex 1.05304 1.91772 2.58915 + vertex 1.05394 1.92217 2.58834 + vertex 1.05061 1.92011 2.59054 + endloop + endfacet + facet normal 0.532743 0.04913 0.84485 + outer loop + vertex 1.05061 1.91558 2.5908 + vertex 1.05304 1.91772 2.58915 + vertex 1.05061 1.92011 2.59054 + endloop + endfacet + facet normal 0.545421 0.0486827 0.836747 + outer loop + vertex 1.05061 1.92011 2.59054 + vertex 1.04822 1.91789 2.59223 + vertex 1.05061 1.91558 2.5908 + endloop + endfacet + facet normal 0.543067 0.0451786 0.838473 + outer loop + vertex 1.04822 1.91789 2.59223 + vertex 1.04731 1.91345 2.59306 + vertex 1.05061 1.91558 2.5908 + endloop + endfacet + facet normal 0.541478 0.0485294 0.839313 + outer loop + vertex 1.05061 1.91558 2.5908 + vertex 1.04731 1.91345 2.59306 + vertex 1.05079 1.91077 2.59097 + endloop + endfacet + facet normal 0.510198 0.0480328 0.858715 + outer loop + vertex 1.05079 1.91077 2.59097 + vertex 1.05378 1.91346 2.58904 + vertex 1.05061 1.91558 2.5908 + endloop + endfacet + facet normal 0.499993 0.0629384 0.863739 + outer loop + vertex 1.0541 1.90848 2.58922 + vertex 1.05378 1.91346 2.58904 + vertex 1.05079 1.91077 2.59097 + endloop + endfacet + facet normal 0.490923 0.0449643 0.870042 + outer loop + vertex 1.05106 1.90576 2.59107 + vertex 1.0541 1.90848 2.58922 + vertex 1.05079 1.91077 2.59097 + endloop + endfacet + facet normal 0.531926 0.0466472 0.845505 + outer loop + vertex 1.05079 1.91077 2.59097 + vertex 1.04781 1.90798 2.593 + vertex 1.05106 1.90576 2.59107 + endloop + endfacet + facet normal 0.526851 0.0360541 0.849193 + outer loop + vertex 1.04781 1.90798 2.593 + vertex 1.04809 1.90297 2.59304 + vertex 1.05106 1.90576 2.59107 + endloop + endfacet + facet normal 0.513389 0.0554568 0.856362 + outer loop + vertex 1.05106 1.90576 2.59107 + vertex 1.04809 1.90297 2.59304 + vertex 1.05132 1.90081 2.59124 + endloop + endfacet + facet normal 0.464224 0.053823 0.884081 + outer loop + vertex 1.05132 1.90081 2.59124 + vertex 1.05433 1.90368 2.58948 + vertex 1.05106 1.90576 2.59107 + endloop + endfacet + facet normal 0.472523 0.0712429 0.878434 + outer loop + vertex 1.05433 1.90368 2.58948 + vertex 1.0541 1.90848 2.58922 + vertex 1.05106 1.90576 2.59107 + endloop + endfacet + facet normal 0.433405 0.0937102 0.896314 + outer loop + vertex 1.05483 1.89886 2.58975 + vertex 1.05433 1.90368 2.58948 + vertex 1.05132 1.90081 2.59124 + endloop + endfacet + facet normal 0.420487 0.0638215 0.905051 + outer loop + vertex 1.05172 1.89585 2.59141 + vertex 1.05483 1.89886 2.58975 + vertex 1.05132 1.90081 2.59124 + endloop + endfacet + facet normal 0.486165 0.0679498 0.871221 + outer loop + vertex 1.05132 1.90081 2.59124 + vertex 1.04833 1.89791 2.59313 + vertex 1.05172 1.89585 2.59141 + endloop + endfacet + facet normal 0.478805 0.0514653 0.876411 + outer loop + vertex 1.04833 1.89791 2.59313 + vertex 1.04878 1.89232 2.59321 + vertex 1.05172 1.89585 2.59141 + endloop + endfacet + facet normal 0.384846 0.107191 0.916735 + outer loop + vertex 1.0556 1.89365 2.59003 + vertex 1.05483 1.89886 2.58975 + vertex 1.05172 1.89585 2.59141 + endloop + endfacet + facet normal 0.365518 0.0657689 0.928478 + outer loop + vertex 1.05224 1.89171 2.59149 + vertex 1.0556 1.89365 2.59003 + vertex 1.05172 1.89585 2.59141 + endloop + endfacet + facet normal 0.455343 0.0763916 0.887033 + outer loop + vertex 1.05172 1.89585 2.59141 + vertex 1.04878 1.89232 2.59321 + vertex 1.05224 1.89171 2.59149 + endloop + endfacet + facet normal 0.456013 0.0827275 0.88612 + outer loop + vertex 1.05224 1.89171 2.59149 + vertex 1.04878 1.89232 2.59321 + vertex 1.05139 1.88739 2.59233 + endloop + endfacet + facet normal 0.434108 0.06902 0.898213 + outer loop + vertex 1.04878 1.89232 2.59321 + vertex 1.04783 1.88782 2.59402 + vertex 1.05139 1.88739 2.59233 + endloop + endfacet + facet normal 0.43381 0.064709 0.898678 + outer loop + vertex 1.04862 1.88351 2.59395 + vertex 1.05139 1.88739 2.59233 + vertex 1.04783 1.88782 2.59402 + endloop + endfacet + facet normal 0.352379 0.0906754 0.931454 + outer loop + vertex 1.05455 1.88942 2.59084 + vertex 1.0556 1.89365 2.59003 + vertex 1.05224 1.89171 2.59149 + endloop + endfacet + facet normal 0.367219 0.107733 0.923874 + outer loop + vertex 1.05224 1.89171 2.59149 + vertex 1.05139 1.88739 2.59233 + vertex 1.05455 1.88942 2.59084 + endloop + endfacet + facet normal 0.506362 0.0407411 0.861358 + outer loop + vertex 1.04809 1.90297 2.59304 + vertex 1.04833 1.89791 2.59313 + vertex 1.05132 1.90081 2.59124 + endloop + endfacet + facet normal 0.53611 0.0418211 0.843111 + outer loop + vertex 1.04833 1.89791 2.59313 + vertex 1.04809 1.90297 2.59304 + vertex 1.04514 1.9001 2.59505 + endloop + endfacet + facet normal 0.534088 0.0375824 0.844593 + outer loop + vertex 1.04531 1.89501 2.59517 + vertex 1.04833 1.89791 2.59313 + vertex 1.04514 1.9001 2.59505 + endloop + endfacet + facet normal 0.537415 0.0376427 0.842477 + outer loop + vertex 1.04514 1.9001 2.59505 + vertex 1.04215 1.89703 2.5971 + vertex 1.04531 1.89501 2.59517 + endloop + endfacet + facet normal 0.538123 0.039252 0.841952 + outer loop + vertex 1.04215 1.89703 2.5971 + vertex 1.04224 1.892 2.59727 + vertex 1.04531 1.89501 2.59517 + endloop + endfacet + facet normal 0.539002 0.0380036 0.841447 + outer loop + vertex 1.04531 1.89501 2.59517 + vertex 1.04224 1.892 2.59727 + vertex 1.04528 1.89001 2.59542 + endloop + endfacet + facet normal 0.513391 0.0389247 0.857272 + outer loop + vertex 1.04528 1.89001 2.59542 + vertex 1.04878 1.89232 2.59321 + vertex 1.04531 1.89501 2.59517 + endloop + endfacet + facet normal 0.509916 0.0458436 0.859002 + outer loop + vertex 1.04783 1.88782 2.59402 + vertex 1.04878 1.89232 2.59321 + vertex 1.04528 1.89001 2.59542 + endloop + endfacet + facet normal 0.508337 0.0433384 0.860067 + outer loop + vertex 1.04533 1.88521 2.59563 + vertex 1.04783 1.88782 2.59402 + vertex 1.04528 1.89001 2.59542 + endloop + endfacet + facet normal 0.483709 0.074348 0.872065 + outer loop + vertex 1.04862 1.88351 2.59395 + vertex 1.04783 1.88782 2.59402 + vertex 1.04533 1.88521 2.59563 + endloop + endfacet + facet normal 0.473822 0.0480014 0.879312 + outer loop + vertex 1.04566 1.8803 2.59572 + vertex 1.04862 1.88351 2.59395 + vertex 1.04533 1.88521 2.59563 + endloop + endfacet + facet normal 0.516372 0.0504078 0.85488 + outer loop + vertex 1.04533 1.88521 2.59563 + vertex 1.04245 1.88201 2.59756 + vertex 1.04566 1.8803 2.59572 + endloop + endfacet + facet normal 0.511081 0.0362737 0.858767 + outer loop + vertex 1.04245 1.88201 2.59756 + vertex 1.04284 1.87699 2.59754 + vertex 1.04566 1.8803 2.59572 + endloop + endfacet + facet normal 0.49186 0.0581152 0.868733 + outer loop + vertex 1.04566 1.8803 2.59572 + vertex 1.04284 1.87699 2.59754 + vertex 1.04607 1.87537 2.59582 + endloop + endfacet + facet normal 0.438984 0.0542283 0.896857 + outer loop + vertex 1.04607 1.87537 2.59582 + vertex 1.04908 1.87843 2.59416 + vertex 1.04566 1.8803 2.59572 + endloop + endfacet + facet normal 0.411392 0.0870051 0.907296 + outer loop + vertex 1.04952 1.87351 2.59443 + vertex 1.04908 1.87843 2.59416 + vertex 1.04607 1.87537 2.59582 + endloop + endfacet + facet normal 0.404524 0.0709301 0.911773 + outer loop + vertex 1.04645 1.87052 2.59603 + vertex 1.04952 1.87351 2.59443 + vertex 1.04607 1.87537 2.59582 + endloop + endfacet + facet normal 0.375776 0.10531 0.920707 + outer loop + vertex 1.05041 1.86832 2.59466 + vertex 1.04952 1.87351 2.59443 + vertex 1.04645 1.87052 2.59603 + endloop + endfacet + facet normal 0.360594 0.0722938 0.929917 + outer loop + vertex 1.04687 1.86637 2.59619 + vertex 1.05041 1.86832 2.59466 + vertex 1.04645 1.87052 2.59603 + endloop + endfacet + facet normal 0.447728 0.0796177 0.890618 + outer loop + vertex 1.04645 1.87052 2.59603 + vertex 1.04295 1.86759 2.59805 + vertex 1.04687 1.86637 2.59619 + endloop + endfacet + facet normal 0.445034 0.0673123 0.89298 + outer loop + vertex 1.04687 1.86637 2.59619 + vertex 1.04295 1.86759 2.59805 + vertex 1.04584 1.86219 2.59702 + endloop + endfacet + facet normal 0.361146 0.0948496 0.927673 + outer loop + vertex 1.04687 1.86637 2.59619 + vertex 1.04584 1.86219 2.59702 + vertex 1.04924 1.86402 2.5955 + endloop + endfacet + facet normal 0.455166 0.0687786 0.887746 + outer loop + vertex 1.04359 1.87264 2.59733 + vertex 1.04295 1.86759 2.59805 + vertex 1.04645 1.87052 2.59603 + endloop + endfacet + facet normal 0.458144 0.0739977 0.885793 + outer loop + vertex 1.04607 1.87537 2.59582 + vertex 1.04359 1.87264 2.59733 + vertex 1.04645 1.87052 2.59603 + endloop + endfacet + facet normal 0.353598 0.0861534 0.931421 + outer loop + vertex 1.04924 1.86402 2.5955 + vertex 1.05041 1.86832 2.59466 + vertex 1.04687 1.86637 2.59619 + endloop + endfacet + facet normal 0.485882 0.041655 0.873031 + outer loop + vertex 1.04284 1.87699 2.59754 + vertex 1.04359 1.87264 2.59733 + vertex 1.04607 1.87537 2.59582 + endloop + endfacet + facet normal 0.529479 0.0342944 0.847629 + outer loop + vertex 1.0423 1.887 2.59745 + vertex 1.04245 1.88201 2.59756 + vertex 1.04533 1.88521 2.59563 + endloop + endfacet + facet normal 0.533003 0.0428878 0.845026 + outer loop + vertex 1.04528 1.89001 2.59542 + vertex 1.0423 1.887 2.59745 + vertex 1.04533 1.88521 2.59563 + endloop + endfacet + facet normal 0.536107 0.0344131 0.843448 + outer loop + vertex 1.04245 1.88201 2.59756 + vertex 1.0423 1.887 2.59745 + vertex 1.0393 1.88379 2.59949 + endloop + endfacet + facet normal 0.536073 0.0343261 0.843473 + outer loop + vertex 1.03959 1.87869 2.59951 + vertex 1.04245 1.88201 2.59756 + vertex 1.0393 1.88379 2.59949 + endloop + endfacet + facet normal 0.533028 0.0379991 0.845244 + outer loop + vertex 1.04284 1.87699 2.59754 + vertex 1.04245 1.88201 2.59756 + vertex 1.03959 1.87869 2.59951 + endloop + endfacet + facet normal 0.532798 0.0373595 0.845418 + outer loop + vertex 1.04027 1.87312 2.59933 + vertex 1.04284 1.87699 2.59754 + vertex 1.03959 1.87869 2.59951 + endloop + endfacet + facet normal 0.533699 0.0374872 0.844843 + outer loop + vertex 1.04027 1.87312 2.59933 + vertex 1.03959 1.87869 2.59951 + vertex 1.03678 1.8757 2.60142 + endloop + endfacet + facet normal 0.535746 0.041449 0.843361 + outer loop + vertex 1.03734 1.87153 2.60127 + vertex 1.04027 1.87312 2.59933 + vertex 1.03678 1.8757 2.60142 + endloop + endfacet + facet normal 0.525044 0.0397672 0.850146 + outer loop + vertex 1.03678 1.8757 2.60142 + vertex 1.034 1.87226 2.6033 + vertex 1.03734 1.87153 2.60127 + endloop + endfacet + facet normal 0.525576 0.0436493 0.849626 + outer loop + vertex 1.03734 1.87153 2.60127 + vertex 1.034 1.87226 2.6033 + vertex 1.03633 1.8674 2.6021 + endloop + endfacet + facet normal 0.530779 0.0469864 0.846207 + outer loop + vertex 1.034 1.87226 2.6033 + vertex 1.0331 1.86786 2.60411 + vertex 1.03633 1.8674 2.6021 + endloop + endfacet + facet normal 0.530572 0.0443615 0.846478 + outer loop + vertex 1.03369 1.86372 2.60395 + vertex 1.03633 1.8674 2.6021 + vertex 1.0331 1.86786 2.60411 + endloop + endfacet + facet normal 0.537776 0.0370758 0.842272 + outer loop + vertex 1.03686 1.86205 2.602 + vertex 1.03633 1.8674 2.6021 + vertex 1.03369 1.86372 2.60395 + endloop + endfacet + facet normal 0.538206 0.0382805 0.841944 + outer loop + vertex 1.034 1.85873 2.60398 + vertex 1.03686 1.86205 2.602 + vertex 1.03369 1.86372 2.60395 + endloop + endfacet + facet normal 0.540298 0.035743 0.840714 + outer loop + vertex 1.03714 1.85704 2.60204 + vertex 1.03686 1.86205 2.602 + vertex 1.034 1.85873 2.60398 + endloop + endfacet + facet normal 0.539936 0.0347551 0.840988 + outer loop + vertex 1.03416 1.85369 2.60409 + vertex 1.03714 1.85704 2.60204 + vertex 1.034 1.85873 2.60398 + endloop + endfacet + facet normal 0.536813 0.0386525 0.842815 + outer loop + vertex 1.03728 1.85204 2.60218 + vertex 1.03714 1.85704 2.60204 + vertex 1.03416 1.85369 2.60409 + endloop + endfacet + facet normal 0.534401 0.0320092 0.844625 + outer loop + vertex 1.03421 1.84874 2.60424 + vertex 1.03728 1.85204 2.60218 + vertex 1.03416 1.85369 2.60409 + endloop + endfacet + facet normal 0.527337 0.0410892 0.848662 + outer loop + vertex 1.03734 1.84702 2.60238 + vertex 1.03728 1.85204 2.60218 + vertex 1.03421 1.84874 2.60424 + endloop + endfacet + facet normal 0.52411 0.0326845 0.851023 + outer loop + vertex 1.03424 1.8438 2.60441 + vertex 1.03734 1.84702 2.60238 + vertex 1.03421 1.84874 2.60424 + endloop + endfacet + facet normal 0.538475 0.0324683 0.842016 + outer loop + vertex 1.03424 1.8438 2.60441 + vertex 1.03421 1.84874 2.60424 + vertex 1.03118 1.84582 2.60629 + endloop + endfacet + facet normal 0.537511 0.0303691 0.84271 + outer loop + vertex 1.03118 1.84095 2.60647 + vertex 1.03424 1.8438 2.60441 + vertex 1.03118 1.84582 2.60629 + endloop + endfacet + facet normal 0.52322 0.0306945 0.851644 + outer loop + vertex 1.03118 1.84582 2.60629 + vertex 1.02767 1.84361 2.60853 + vertex 1.03118 1.84095 2.60647 + endloop + endfacet + facet normal 0.528091 0.0397459 0.848257 + outer loop + vertex 1.02767 1.84361 2.60853 + vertex 1.0282 1.83816 2.60845 + vertex 1.03118 1.84095 2.60647 + endloop + endfacet + facet normal 0.531833 0.0342431 0.846156 + outer loop + vertex 1.03118 1.84095 2.60647 + vertex 1.0282 1.83816 2.60845 + vertex 1.03151 1.83585 2.60647 + endloop + endfacet + facet normal 0.531561 0.0342257 0.846328 + outer loop + vertex 1.03151 1.83585 2.60647 + vertex 1.03443 1.83875 2.60452 + vertex 1.03118 1.84095 2.60647 + endloop + endfacet + facet normal 0.524435 0.0440791 0.850309 + outer loop + vertex 1.03485 1.83354 2.60453 + vertex 1.03443 1.83875 2.60452 + vertex 1.03151 1.83585 2.60647 + endloop + endfacet + facet normal 0.519446 0.0339185 0.85383 + outer loop + vertex 1.03194 1.83074 2.60641 + vertex 1.03485 1.83354 2.60453 + vertex 1.03151 1.83585 2.60647 + endloop + endfacet + facet normal 0.534297 0.0352903 0.84456 + outer loop + vertex 1.03151 1.83585 2.60647 + vertex 1.02862 1.83297 2.60842 + vertex 1.03194 1.83074 2.60641 + endloop + endfacet + facet normal 0.53374 0.0341032 0.844961 + outer loop + vertex 1.02862 1.83297 2.60842 + vertex 1.02908 1.8273 2.60835 + vertex 1.03194 1.83074 2.60641 + endloop + endfacet + facet normal 0.533279 0.0346391 0.84523 + outer loop + vertex 1.03194 1.83074 2.60641 + vertex 1.02908 1.8273 2.60835 + vertex 1.03239 1.82654 2.6063 + endloop + endfacet + facet normal 0.499516 0.0304806 0.865768 + outer loop + vertex 1.03239 1.82654 2.6063 + vertex 1.03537 1.82817 2.60452 + vertex 1.03194 1.83074 2.60641 + endloop + endfacet + facet normal 0.49577 0.0393079 0.867564 + outer loop + vertex 1.03432 1.82416 2.6053 + vertex 1.03537 1.82817 2.60452 + vertex 1.03239 1.82654 2.6063 + endloop + endfacet + facet normal 0.502943 0.0470148 0.86304 + outer loop + vertex 1.03239 1.82654 2.6063 + vertex 1.03131 1.82237 2.60715 + vertex 1.03432 1.82416 2.6053 + endloop + endfacet + facet normal 0.533398 0.0354601 0.845121 + outer loop + vertex 1.03239 1.82654 2.6063 + vertex 1.02908 1.8273 2.60835 + vertex 1.03131 1.82237 2.60715 + endloop + endfacet + facet normal 0.533293 0.0353962 0.845189 + outer loop + vertex 1.02908 1.8273 2.60835 + vertex 1.02807 1.82279 2.60918 + vertex 1.03131 1.82237 2.60715 + endloop + endfacet + facet normal 0.532775 0.0284025 0.84578 + outer loop + vertex 1.02863 1.81863 2.60897 + vertex 1.03131 1.82237 2.60715 + vertex 1.02807 1.82279 2.60918 + endloop + endfacet + facet normal 0.523199 0.0379809 0.851364 + outer loop + vertex 1.03183 1.817 2.60707 + vertex 1.03131 1.82237 2.60715 + vertex 1.02863 1.81863 2.60897 + endloop + endfacet + facet normal 0.519938 0.0288838 0.853716 + outer loop + vertex 1.02893 1.81377 2.60895 + vertex 1.03183 1.817 2.60707 + vertex 1.02863 1.81863 2.60897 + endloop + endfacet + facet normal 0.538685 0.0301003 0.841969 + outer loop + vertex 1.02893 1.81377 2.60895 + vertex 1.02863 1.81863 2.60897 + vertex 1.02593 1.81557 2.6108 + endloop + endfacet + facet normal 0.53868 0.0300875 0.841973 + outer loop + vertex 1.026 1.81087 2.61093 + vertex 1.02893 1.81377 2.60895 + vertex 1.02593 1.81557 2.6108 + endloop + endfacet + facet normal 0.53425 0.0300934 0.844791 + outer loop + vertex 1.02593 1.81557 2.6108 + vertex 1.02349 1.81298 2.61244 + vertex 1.026 1.81087 2.61093 + endloop + endfacet + facet normal 0.534242 0.0300815 0.844796 + outer loop + vertex 1.02349 1.81298 2.61244 + vertex 1.0225 1.80852 2.61322 + vertex 1.026 1.81087 2.61093 + endloop + endfacet + facet normal 0.532759 0.0331004 0.84562 + outer loop + vertex 1.026 1.81087 2.61093 + vertex 1.0225 1.80852 2.61322 + vertex 1.02602 1.80595 2.61111 + endloop + endfacet + facet normal 0.53275 0.0331006 0.845625 + outer loop + vertex 1.02602 1.80595 2.61111 + vertex 1.02911 1.8088 2.60905 + vertex 1.026 1.81087 2.61093 + endloop + endfacet + facet normal 0.525441 0.0439581 0.849694 + outer loop + vertex 1.02933 1.8037 2.60918 + vertex 1.02911 1.8088 2.60905 + vertex 1.02602 1.80595 2.61111 + endloop + endfacet + facet normal 0.521155 0.0350492 0.852742 + outer loop + vertex 1.02621 1.80094 2.6112 + vertex 1.02933 1.8037 2.60918 + vertex 1.02602 1.80595 2.61111 + endloop + endfacet + facet normal 0.535058 0.0354142 0.844073 + outer loop + vertex 1.02602 1.80595 2.61111 + vertex 1.02296 1.80312 2.61317 + vertex 1.02621 1.80094 2.6112 + endloop + endfacet + facet normal 0.533765 0.032645 0.845002 + outer loop + vertex 1.02296 1.80312 2.61317 + vertex 1.0232 1.79819 2.61321 + vertex 1.02621 1.80094 2.6112 + endloop + endfacet + facet normal 0.532304 0.0348566 0.845835 + outer loop + vertex 1.02621 1.80094 2.6112 + vertex 1.0232 1.79819 2.61321 + vertex 1.02636 1.796 2.61131 + endloop + endfacet + facet normal 0.510844 0.0345145 0.85898 + outer loop + vertex 1.02636 1.796 2.61131 + vertex 1.02939 1.79867 2.6094 + vertex 1.02621 1.80094 2.6112 + endloop + endfacet + facet normal 0.499624 0.0513404 0.86472 + outer loop + vertex 1.02954 1.79385 2.6096 + vertex 1.02939 1.79867 2.6094 + vertex 1.02636 1.796 2.61131 + endloop + endfacet + facet normal 0.490903 0.0338108 0.870558 + outer loop + vertex 1.02657 1.79099 2.61138 + vertex 1.02954 1.79385 2.6096 + vertex 1.02636 1.796 2.61131 + endloop + endfacet + facet normal 0.523901 0.0349047 0.851064 + outer loop + vertex 1.02636 1.796 2.61131 + vertex 1.02334 1.79323 2.61328 + vertex 1.02657 1.79099 2.61138 + endloop + endfacet + facet normal 0.518087 0.0232313 0.855013 + outer loop + vertex 1.02334 1.79323 2.61328 + vertex 1.02354 1.78805 2.6133 + vertex 1.02657 1.79099 2.61138 + endloop + endfacet + facet normal 0.510743 0.033475 0.859081 + outer loop + vertex 1.02657 1.79099 2.61138 + vertex 1.02354 1.78805 2.6133 + vertex 1.02691 1.78585 2.61138 + endloop + endfacet + facet normal 0.46019 0.0300566 0.887311 + outer loop + vertex 1.02691 1.78585 2.61138 + vertex 1.03001 1.78891 2.60967 + vertex 1.02657 1.79099 2.61138 + endloop + endfacet + facet normal 0.438644 0.057204 0.896839 + outer loop + vertex 1.03066 1.78355 2.60969 + vertex 1.03001 1.78891 2.60967 + vertex 1.02691 1.78585 2.61138 + endloop + endfacet + facet normal 0.420651 0.0204761 0.906992 + outer loop + vertex 1.0273 1.78156 2.6113 + vertex 1.03066 1.78355 2.60969 + vertex 1.02691 1.78585 2.61138 + endloop + endfacet + facet normal 0.497178 0.0280512 0.867195 + outer loop + vertex 1.02691 1.78585 2.61138 + vertex 1.02389 1.78232 2.61322 + vertex 1.0273 1.78156 2.6113 + endloop + endfacet + facet normal 0.497932 0.0330002 0.866588 + outer loop + vertex 1.0273 1.78156 2.6113 + vertex 1.02389 1.78232 2.61322 + vertex 1.02617 1.77732 2.61211 + endloop + endfacet + facet normal 0.496464 0.0321354 0.867462 + outer loop + vertex 1.02389 1.78232 2.61322 + vertex 1.02285 1.77784 2.61399 + vertex 1.02617 1.77732 2.61211 + endloop + endfacet + facet normal 0.496976 0.0372232 0.866965 + outer loop + vertex 1.02348 1.77362 2.61381 + vertex 1.02617 1.77732 2.61211 + vertex 1.02285 1.77784 2.61399 + endloop + endfacet + facet normal 0.412435 0.0370091 0.910235 + outer loop + vertex 1.02939 1.77921 2.61044 + vertex 1.03066 1.78355 2.60969 + vertex 1.0273 1.78156 2.6113 + endloop + endfacet + facet normal 0.504299 0.0199256 0.863299 + outer loop + vertex 1.02354 1.78805 2.6133 + vertex 1.02389 1.78232 2.61322 + vertex 1.02691 1.78585 2.61138 + endloop + endfacet + facet normal 0.535817 0.0221325 0.844044 + outer loop + vertex 1.02389 1.78232 2.61322 + vertex 1.02354 1.78805 2.6133 + vertex 1.02046 1.78518 2.61533 + endloop + endfacet + facet normal 0.536224 0.0228243 0.843767 + outer loop + vertex 1.02042 1.78015 2.61549 + vertex 1.02389 1.78232 2.61322 + vertex 1.02046 1.78518 2.61533 + endloop + endfacet + facet normal 0.537916 0.0227733 0.84269 + outer loop + vertex 1.02046 1.78518 2.61533 + vertex 1.01737 1.78222 2.61738 + vertex 1.02042 1.78015 2.61549 + endloop + endfacet + facet normal 0.540938 0.0291486 0.840557 + outer loop + vertex 1.01737 1.78222 2.61738 + vertex 1.01744 1.77723 2.61751 + vertex 1.02042 1.78015 2.61549 + endloop + endfacet + facet normal 0.542138 0.027429 0.839841 + outer loop + vertex 1.02042 1.78015 2.61549 + vertex 1.01744 1.77723 2.61751 + vertex 1.02043 1.77537 2.61564 + endloop + endfacet + facet normal 0.544485 0.0273857 0.838324 + outer loop + vertex 1.02043 1.77537 2.61564 + vertex 1.02285 1.77784 2.61399 + vertex 1.02042 1.78015 2.61549 + endloop + endfacet + facet normal 0.532762 0.0434842 0.845147 + outer loop + vertex 1.02348 1.77362 2.61381 + vertex 1.02285 1.77784 2.61399 + vertex 1.02043 1.77537 2.61564 + endloop + endfacet + facet normal 0.531915 0.0413309 0.845789 + outer loop + vertex 1.02074 1.77053 2.61568 + vertex 1.02348 1.77362 2.61381 + vertex 1.02043 1.77537 2.61564 + endloop + endfacet + facet normal 0.537487 0.0416613 0.842242 + outer loop + vertex 1.02043 1.77537 2.61564 + vertex 1.0176 1.77225 2.6176 + vertex 1.02074 1.77053 2.61568 + endloop + endfacet + facet normal 0.537731 0.042313 0.842054 + outer loop + vertex 1.0176 1.77225 2.6176 + vertex 1.01796 1.76732 2.61762 + vertex 1.02074 1.77053 2.61568 + endloop + endfacet + facet normal 0.526444 0.0559046 0.84837 + outer loop + vertex 1.02074 1.77053 2.61568 + vertex 1.01796 1.76732 2.61762 + vertex 1.02109 1.76569 2.61578 + endloop + endfacet + facet normal 0.509379 0.054885 0.85879 + outer loop + vertex 1.02109 1.76569 2.61578 + vertex 1.024 1.76858 2.61387 + vertex 1.02074 1.77053 2.61568 + endloop + endfacet + facet normal 0.524617 0.0507455 0.849825 + outer loop + vertex 1.01796 1.76732 2.61762 + vertex 1.01859 1.76318 2.61748 + vertex 1.02109 1.76569 2.61578 + endloop + endfacet + facet normal 0.513199 0.0639846 0.855881 + outer loop + vertex 1.024 1.76858 2.61387 + vertex 1.02348 1.77362 2.61381 + vertex 1.02074 1.77053 2.61568 + endloop + endfacet + facet normal 0.544436 0.0328067 0.838161 + outer loop + vertex 1.01744 1.77723 2.61751 + vertex 1.0176 1.77225 2.6176 + vertex 1.02043 1.77537 2.61564 + endloop + endfacet + facet normal 0.531761 0.0317264 0.8463 + outer loop + vertex 1.01728 1.78725 2.61725 + vertex 1.01737 1.78222 2.61738 + vertex 1.02046 1.78518 2.61533 + endloop + endfacet + facet normal 0.528252 0.0240781 0.848746 + outer loop + vertex 1.02033 1.79034 2.61527 + vertex 1.01728 1.78725 2.61725 + vertex 1.02046 1.78518 2.61533 + endloop + endfacet + facet normal 0.52021 0.0349583 0.853323 + outer loop + vertex 1.01717 1.79224 2.61711 + vertex 1.01728 1.78725 2.61725 + vertex 1.02033 1.79034 2.61527 + endloop + endfacet + facet normal 0.517254 0.0280463 0.855372 + outer loop + vertex 1.0202 1.79533 2.61518 + vertex 1.01717 1.79224 2.61711 + vertex 1.02033 1.79034 2.61527 + endloop + endfacet + facet normal 0.531133 0.0282517 0.846817 + outer loop + vertex 1.02033 1.79034 2.61527 + vertex 1.02334 1.79323 2.61328 + vertex 1.0202 1.79533 2.61518 + endloop + endfacet + facet normal 0.530864 0.0276777 0.847005 + outer loop + vertex 1.02334 1.79323 2.61328 + vertex 1.0232 1.79819 2.61321 + vertex 1.0202 1.79533 2.61518 + endloop + endfacet + facet normal 0.526651 0.0337363 0.849412 + outer loop + vertex 1.0202 1.79533 2.61518 + vertex 1.0232 1.79819 2.61321 + vertex 1.02001 1.80018 2.61511 + endloop + endfacet + facet normal 0.507503 0.0331402 0.861012 + outer loop + vertex 1.02001 1.80018 2.61511 + vertex 1.01703 1.79713 2.61698 + vertex 1.0202 1.79533 2.61518 + endloop + endfacet + facet normal 0.49967 0.0433351 0.865131 + outer loop + vertex 1.01672 1.80201 2.61691 + vertex 1.01703 1.79713 2.61698 + vertex 1.02001 1.80018 2.61511 + endloop + endfacet + facet normal 0.497483 0.0379331 0.866644 + outer loop + vertex 1.01962 1.805 2.61511 + vertex 1.01672 1.80201 2.61691 + vertex 1.02001 1.80018 2.61511 + endloop + endfacet + facet normal 0.520569 0.0397841 0.852892 + outer loop + vertex 1.02001 1.80018 2.61511 + vertex 1.02296 1.80312 2.61317 + vertex 1.01962 1.805 2.61511 + endloop + endfacet + facet normal 0.51864 0.034925 0.854279 + outer loop + vertex 1.02296 1.80312 2.61317 + vertex 1.0225 1.80852 2.61322 + vertex 1.01962 1.805 2.61511 + endloop + endfacet + facet normal 0.512473 0.0417973 0.857686 + outer loop + vertex 1.01915 1.809 2.6152 + vertex 1.01962 1.805 2.61511 + vertex 1.0225 1.80852 2.61322 + endloop + endfacet + facet normal 0.512319 0.0400173 0.857862 + outer loop + vertex 1.01915 1.809 2.6152 + vertex 1.0225 1.80852 2.61322 + vertex 1.02019 1.81321 2.61439 + endloop + endfacet + facet normal 0.509489 0.0381855 0.859629 + outer loop + vertex 1.02019 1.81321 2.61439 + vertex 1.0225 1.80852 2.61322 + vertex 1.02349 1.81298 2.61244 + endloop + endfacet + facet normal 0.509374 0.0346168 0.859849 + outer loop + vertex 1.02349 1.81298 2.61244 + vertex 1.02287 1.81709 2.61264 + vertex 1.02019 1.81321 2.61439 + endloop + endfacet + facet normal 0.49686 0.0462643 0.866596 + outer loop + vertex 1.02019 1.81321 2.61439 + vertex 1.02287 1.81709 2.61264 + vertex 1.01956 1.81864 2.61446 + endloop + endfacet + facet normal 0.480071 0.0441759 0.876117 + outer loop + vertex 1.02019 1.81321 2.61439 + vertex 1.01956 1.81864 2.61446 + vertex 1.01673 1.81539 2.61617 + endloop + endfacet + facet normal 0.484831 0.0543299 0.872919 + outer loop + vertex 1.01728 1.81133 2.61612 + vertex 1.02019 1.81321 2.61439 + vertex 1.01673 1.81539 2.61617 + endloop + endfacet + facet normal 0.466216 0.0516762 0.88316 + outer loop + vertex 1.01673 1.81539 2.61617 + vertex 1.01433 1.81206 2.61763 + vertex 1.01728 1.81133 2.61612 + endloop + endfacet + facet normal 0.465938 0.0500491 0.883401 + outer loop + vertex 1.01728 1.81133 2.61612 + vertex 1.01433 1.81206 2.61763 + vertex 1.01614 1.80731 2.61695 + endloop + endfacet + facet normal 0.482615 0.0435038 0.874751 + outer loop + vertex 1.01728 1.81133 2.61612 + vertex 1.01614 1.80731 2.61695 + vertex 1.01915 1.809 2.6152 + endloop + endfacet + facet normal 0.463865 0.0490966 0.884545 + outer loop + vertex 1.01433 1.81206 2.61763 + vertex 1.01226 1.80835 2.61893 + vertex 1.01614 1.80731 2.61695 + endloop + endfacet + facet normal 0.46447 0.052305 0.884043 + outer loop + vertex 1.01327 1.80363 2.61867 + vertex 1.01614 1.80731 2.61695 + vertex 1.01226 1.80835 2.61893 + endloop + endfacet + facet normal 0.45432 0.0498363 0.889443 + outer loop + vertex 1.01327 1.80363 2.61867 + vertex 1.01226 1.80835 2.61893 + vertex 1.00977 1.80507 2.62038 + endloop + endfacet + facet normal 0.455337 0.0531346 0.888732 + outer loop + vertex 1.01036 1.80034 2.62036 + vertex 1.01327 1.80363 2.61867 + vertex 1.00977 1.80507 2.62038 + endloop + endfacet + facet normal 0.443834 0.0516811 0.894617 + outer loop + vertex 1.00977 1.80507 2.62038 + vertex 1.00675 1.80211 2.62205 + vertex 1.01036 1.80034 2.62036 + endloop + endfacet + facet normal 0.446257 0.0581564 0.893013 + outer loop + vertex 1.00675 1.80211 2.62205 + vertex 1.00727 1.79716 2.62211 + vertex 1.01036 1.80034 2.62036 + endloop + endfacet + facet normal 0.453947 0.048862 0.889688 + outer loop + vertex 1.01036 1.80034 2.62036 + vertex 1.00727 1.79716 2.62211 + vertex 1.01066 1.79547 2.62047 + endloop + endfacet + facet normal 0.460704 0.0492053 0.886189 + outer loop + vertex 1.01066 1.79547 2.62047 + vertex 1.01375 1.79875 2.61868 + vertex 1.01036 1.80034 2.62036 + endloop + endfacet + facet normal 0.463966 0.0453119 0.884693 + outer loop + vertex 1.01395 1.79388 2.61883 + vertex 1.01375 1.79875 2.61868 + vertex 1.01066 1.79547 2.62047 + endloop + endfacet + facet normal 0.464845 0.0477342 0.884104 + outer loop + vertex 1.01079 1.79055 2.62067 + vertex 1.01395 1.79388 2.61883 + vertex 1.01066 1.79547 2.62047 + endloop + endfacet + facet normal 0.456073 0.0476931 0.888664 + outer loop + vertex 1.01066 1.79547 2.62047 + vertex 1.00748 1.79223 2.62228 + vertex 1.01079 1.79055 2.62067 + endloop + endfacet + facet normal 0.45648 0.0487526 0.888397 + outer loop + vertex 1.00748 1.79223 2.62228 + vertex 1.00759 1.78724 2.6225 + vertex 1.01079 1.79055 2.62067 + endloop + endfacet + facet normal 0.456603 0.0486039 0.888342 + outer loop + vertex 1.01079 1.79055 2.62067 + vertex 1.00759 1.78724 2.6225 + vertex 1.0109 1.78558 2.62089 + endloop + endfacet + facet normal 0.46892 0.0486009 0.881902 + outer loop + vertex 1.0109 1.78558 2.62089 + vertex 1.01406 1.78895 2.61902 + vertex 1.01079 1.79055 2.62067 + endloop + endfacet + facet normal 0.474407 0.0420141 0.879302 + outer loop + vertex 1.01417 1.78396 2.6192 + vertex 1.01406 1.78895 2.61902 + vertex 1.0109 1.78558 2.62089 + endloop + endfacet + facet normal 0.476042 0.0464747 0.878194 + outer loop + vertex 1.01103 1.78057 2.62108 + vertex 1.01417 1.78396 2.6192 + vertex 1.0109 1.78558 2.62089 + endloop + endfacet + facet normal 0.459924 0.0463894 0.886745 + outer loop + vertex 1.0109 1.78558 2.62089 + vertex 1.00772 1.78222 2.62271 + vertex 1.01103 1.78057 2.62108 + endloop + endfacet + facet normal 0.459821 0.0461123 0.886814 + outer loop + vertex 1.00772 1.78222 2.62271 + vertex 1.00785 1.77719 2.6229 + vertex 1.01103 1.78057 2.62108 + endloop + endfacet + facet normal 0.464344 0.0407388 0.884718 + outer loop + vertex 1.01103 1.78057 2.62108 + vertex 1.00785 1.77719 2.6229 + vertex 1.01116 1.77555 2.62125 + endloop + endfacet + facet normal 0.483494 0.0408856 0.874392 + outer loop + vertex 1.01116 1.77555 2.62125 + vertex 1.01429 1.77895 2.61936 + vertex 1.01103 1.78057 2.62108 + endloop + endfacet + facet normal 0.48885 0.0344478 0.871687 + outer loop + vertex 1.01441 1.77391 2.61949 + vertex 1.01429 1.77895 2.61936 + vertex 1.01116 1.77555 2.62125 + endloop + endfacet + facet normal 0.489641 0.0365936 0.871156 + outer loop + vertex 1.01135 1.77049 2.62135 + vertex 1.01441 1.77391 2.61949 + vertex 1.01116 1.77555 2.62125 + endloop + endfacet + facet normal 0.464607 0.0359285 0.884788 + outer loop + vertex 1.01116 1.77555 2.62125 + vertex 1.008 1.77215 2.62304 + vertex 1.01135 1.77049 2.62135 + endloop + endfacet + facet normal 0.463027 0.0317295 0.885776 + outer loop + vertex 1.008 1.77215 2.62304 + vertex 1.00828 1.76701 2.62308 + vertex 1.01135 1.77049 2.62135 + endloop + endfacet + facet normal 0.459264 0.0359385 0.887572 + outer loop + vertex 1.01135 1.77049 2.62135 + vertex 1.00828 1.76701 2.62308 + vertex 1.01174 1.76544 2.62135 + endloop + endfacet + facet normal 0.491077 0.0384204 0.870269 + outer loop + vertex 1.01174 1.76544 2.62135 + vertex 1.01468 1.76881 2.61955 + vertex 1.01135 1.77049 2.62135 + endloop + endfacet + facet normal 0.48888 0.0409359 0.87139 + outer loop + vertex 1.01526 1.76341 2.61948 + vertex 1.01468 1.76881 2.61955 + vertex 1.01174 1.76544 2.62135 + endloop + endfacet + facet normal 0.490982 0.0458895 0.86996 + outer loop + vertex 1.01224 1.76138 2.62129 + vertex 1.01526 1.76341 2.61948 + vertex 1.01174 1.76544 2.62135 + endloop + endfacet + facet normal 0.451097 0.0406567 0.891548 + outer loop + vertex 1.01174 1.76544 2.62135 + vertex 1.0089 1.76154 2.62297 + vertex 1.01224 1.76138 2.62129 + endloop + endfacet + facet normal 0.451079 0.0397398 0.891599 + outer loop + vertex 1.01224 1.76138 2.62129 + vertex 1.0089 1.76154 2.62297 + vertex 1.01117 1.75733 2.62201 + endloop + endfacet + facet normal 0.474023 0.0315692 0.879946 + outer loop + vertex 1.01224 1.76138 2.62129 + vertex 1.01117 1.75733 2.62201 + vertex 1.0142 1.75918 2.62031 + endloop + endfacet + facet normal 0.441909 0.0336938 0.896427 + outer loop + vertex 1.0089 1.76154 2.62297 + vertex 1.00837 1.75778 2.62337 + vertex 1.01117 1.75733 2.62201 + endloop + endfacet + facet normal 0.489227 0.0492147 0.870767 + outer loop + vertex 1.0142 1.75918 2.62031 + vertex 1.01526 1.76341 2.61948 + vertex 1.01224 1.76138 2.62129 + endloop + endfacet + facet normal 0.507577 0.0426138 0.860552 + outer loop + vertex 1.0142 1.75918 2.62031 + vertex 1.01761 1.7587 2.61832 + vertex 1.01526 1.76341 2.61948 + endloop + endfacet + facet normal 0.516284 0.0483016 0.855054 + outer loop + vertex 1.01526 1.76341 2.61948 + vertex 1.01761 1.7587 2.61832 + vertex 1.01859 1.76318 2.61748 + endloop + endfacet + facet normal 0.51631 0.0493019 0.854981 + outer loop + vertex 1.01859 1.76318 2.61748 + vertex 1.01796 1.76732 2.61762 + vertex 1.01526 1.76341 2.61948 + endloop + endfacet + facet normal 0.508132 0.0509832 0.859769 + outer loop + vertex 1.01859 1.76318 2.61748 + vertex 1.01761 1.7587 2.61832 + vertex 1.02119 1.76097 2.61607 + endloop + endfacet + facet normal 0.515519 0.0629988 0.854559 + outer loop + vertex 1.02109 1.76569 2.61578 + vertex 1.01859 1.76318 2.61748 + vertex 1.02119 1.76097 2.61607 + endloop + endfacet + facet normal 0.488954 0.0633628 0.870005 + outer loop + vertex 1.02119 1.76097 2.61607 + vertex 1.02423 1.76361 2.61417 + vertex 1.02109 1.76569 2.61578 + endloop + endfacet + facet normal 0.494418 0.0746977 0.866009 + outer loop + vertex 1.02423 1.76361 2.61417 + vertex 1.024 1.76858 2.61387 + vertex 1.02109 1.76569 2.61578 + endloop + endfacet + facet normal 0.479293 0.0774975 0.874227 + outer loop + vertex 1.02442 1.7589 2.61449 + vertex 1.02423 1.76361 2.61417 + vertex 1.02119 1.76097 2.61607 + endloop + endfacet + facet normal 0.507672 0.051924 0.859985 + outer loop + vertex 1.02119 1.76097 2.61607 + vertex 1.01761 1.7587 2.61832 + vertex 1.02127 1.75608 2.61632 + endloop + endfacet + facet normal 0.467304 0.0524566 0.882539 + outer loop + vertex 1.02127 1.75608 2.61632 + vertex 1.02442 1.7589 2.61449 + vertex 1.02119 1.76097 2.61607 + endloop + endfacet + facet normal 0.461475 0.0606074 0.885081 + outer loop + vertex 1.0248 1.7541 2.61461 + vertex 1.02442 1.7589 2.61449 + vertex 1.02127 1.75608 2.61632 + endloop + endfacet + facet normal 0.445235 0.0227877 0.895124 + outer loop + vertex 1.02146 1.75105 2.61635 + vertex 1.0248 1.7541 2.61461 + vertex 1.02127 1.75608 2.61632 + endloop + endfacet + facet normal 0.49808 0.0245672 0.866783 + outer loop + vertex 1.02127 1.75608 2.61632 + vertex 1.01806 1.75321 2.61825 + vertex 1.02146 1.75105 2.61635 + endloop + endfacet + facet normal 0.495403 0.0285133 0.868195 + outer loop + vertex 1.01761 1.7587 2.61832 + vertex 1.01806 1.75321 2.61825 + vertex 1.02127 1.75608 2.61632 + endloop + endfacet + facet normal 0.509037 0.0297548 0.86023 + outer loop + vertex 1.01806 1.75321 2.61825 + vertex 1.01761 1.7587 2.61832 + vertex 1.01467 1.75515 2.62019 + endloop + endfacet + facet normal 0.505509 0.0212562 0.86256 + outer loop + vertex 1.01501 1.75027 2.6201 + vertex 1.01806 1.75321 2.61825 + vertex 1.01467 1.75515 2.62019 + endloop + endfacet + facet normal 0.489103 0.0199247 0.871999 + outer loop + vertex 1.01467 1.75515 2.62019 + vertex 1.01163 1.75217 2.62196 + vertex 1.01501 1.75027 2.6201 + endloop + endfacet + facet normal 0.478383 0.0340767 0.87749 + outer loop + vertex 1.01117 1.75733 2.62201 + vertex 1.01163 1.75217 2.62196 + vertex 1.01467 1.75515 2.62019 + endloop + endfacet + facet normal 0.475633 0.0282381 0.87919 + outer loop + vertex 1.01467 1.75515 2.62019 + vertex 1.0142 1.75918 2.62031 + vertex 1.01117 1.75733 2.62201 + endloop + endfacet + facet normal 0.442246 0.0306222 0.896371 + outer loop + vertex 1.01163 1.75217 2.62196 + vertex 1.01117 1.75733 2.62201 + vertex 1.00783 1.75404 2.62377 + endloop + endfacet + facet normal 0.447608 0.044611 0.893116 + outer loop + vertex 1.00853 1.74878 2.62368 + vertex 1.01163 1.75217 2.62196 + vertex 1.00783 1.75404 2.62377 + endloop + endfacet + facet normal 0.441642 0.0313787 0.896642 + outer loop + vertex 1.00783 1.75404 2.62377 + vertex 1.01117 1.75733 2.62201 + vertex 1.00837 1.75778 2.62337 + endloop + endfacet + facet normal 0.506684 0.032385 0.861523 + outer loop + vertex 1.0142 1.75918 2.62031 + vertex 1.01467 1.75515 2.62019 + vertex 1.01761 1.7587 2.61832 + endloop + endfacet + facet normal 0.521208 0.0446181 0.852263 + outer loop + vertex 1.01526 1.76341 2.61948 + vertex 1.01796 1.76732 2.61762 + vertex 1.01468 1.76881 2.61955 + endloop + endfacet + facet normal 0.520097 0.0410842 0.853119 + outer loop + vertex 1.01796 1.76732 2.61762 + vertex 1.0176 1.77225 2.6176 + vertex 1.01468 1.76881 2.61955 + endloop + endfacet + facet normal 0.523197 0.0374683 0.851388 + outer loop + vertex 1.01468 1.76881 2.61955 + vertex 1.0176 1.77225 2.6176 + vertex 1.01441 1.77391 2.61949 + endloop + endfacet + facet normal 0.521323 0.0323272 0.852747 + outer loop + vertex 1.0176 1.77225 2.6176 + vertex 1.01744 1.77723 2.61751 + vertex 1.01441 1.77391 2.61949 + endloop + endfacet + facet normal 0.458528 0.0337907 0.888038 + outer loop + vertex 1.00828 1.76701 2.62308 + vertex 1.0089 1.76154 2.62297 + vertex 1.01174 1.76544 2.62135 + endloop + endfacet + facet normal 0.490175 0.0359663 0.870882 + outer loop + vertex 1.01468 1.76881 2.61955 + vertex 1.01441 1.77391 2.61949 + vertex 1.01135 1.77049 2.62135 + endloop + endfacet + facet normal 0.519368 0.0347674 0.853843 + outer loop + vertex 1.01441 1.77391 2.61949 + vertex 1.01744 1.77723 2.61751 + vertex 1.01429 1.77895 2.61936 + endloop + endfacet + facet normal 0.51722 0.029195 0.855355 + outer loop + vertex 1.01744 1.77723 2.61751 + vertex 1.01737 1.78222 2.61738 + vertex 1.01429 1.77895 2.61936 + endloop + endfacet + facet normal 0.509788 0.038663 0.859431 + outer loop + vertex 1.01429 1.77895 2.61936 + vertex 1.01737 1.78222 2.61738 + vertex 1.01417 1.78396 2.6192 + endloop + endfacet + facet normal 0.507062 0.0316508 0.861328 + outer loop + vertex 1.01737 1.78222 2.61738 + vertex 1.01728 1.78725 2.61725 + vertex 1.01417 1.78396 2.6192 + endloop + endfacet + facet normal 0.463172 0.0376191 0.88547 + outer loop + vertex 1.00785 1.77719 2.6229 + vertex 1.008 1.77215 2.62304 + vertex 1.01116 1.77555 2.62125 + endloop + endfacet + facet normal 0.447682 0.0460131 0.893008 + outer loop + vertex 1.00785 1.77719 2.6229 + vertex 1.00772 1.78222 2.62271 + vertex 1.00448 1.7788 2.62451 + endloop + endfacet + facet normal 0.446241 0.0420739 0.893923 + outer loop + vertex 1.00462 1.77379 2.62468 + vertex 1.00785 1.77719 2.6229 + vertex 1.00448 1.7788 2.62451 + endloop + endfacet + facet normal 0.42973 0.0419006 0.901985 + outer loop + vertex 1.00462 1.77379 2.62468 + vertex 1.00448 1.7788 2.62451 + vertex 1.00112 1.77533 2.62628 + endloop + endfacet + facet normal 0.428188 0.037429 0.902914 + outer loop + vertex 1.00125 1.77042 2.62642 + vertex 1.00462 1.77379 2.62468 + vertex 1.00112 1.77533 2.62628 + endloop + endfacet + facet normal 0.396243 0.0370391 0.917398 + outer loop + vertex 1.00112 1.77533 2.62628 + vertex 0.997578 1.77208 2.62794 + vertex 1.00125 1.77042 2.62642 + endloop + endfacet + facet normal 0.396383 0.0374213 0.917322 + outer loop + vertex 0.997578 1.77208 2.62794 + vertex 0.997701 1.7672 2.62808 + vertex 1.00125 1.77042 2.62642 + endloop + endfacet + facet normal 0.408947 0.0210095 0.912316 + outer loop + vertex 1.00125 1.77042 2.62642 + vertex 0.997701 1.7672 2.62808 + vertex 1.00144 1.76539 2.62645 + endloop + endfacet + facet normal 0.431864 0.0218178 0.901675 + outer loop + vertex 1.00144 1.76539 2.62645 + vertex 1.00478 1.76875 2.62477 + vertex 1.00125 1.77042 2.62642 + endloop + endfacet + facet normal 0.33124 0.0365461 0.942839 + outer loop + vertex 0.997701 1.7672 2.62808 + vertex 0.997578 1.77208 2.62794 + vertex 0.993318 1.76938 2.62954 + endloop + endfacet + facet normal 0.321122 0.0540944 0.945492 + outer loop + vertex 0.993318 1.76938 2.62954 + vertex 0.997578 1.77208 2.62794 + vertex 0.994257 1.77385 2.62896 + endloop + endfacet + facet normal 0.321679 0.0552899 0.945233 + outer loop + vertex 0.997578 1.77208 2.62794 + vertex 0.997465 1.77669 2.62771 + vertex 0.994257 1.77385 2.62896 + endloop + endfacet + facet normal 0.296334 0.0865298 0.951157 + outer loop + vertex 0.994257 1.77385 2.62896 + vertex 0.997465 1.77669 2.62771 + vertex 0.993464 1.7777 2.62886 + endloop + endfacet + facet normal 0.292502 0.0683427 0.95382 + outer loop + vertex 0.997465 1.77669 2.62771 + vertex 0.997169 1.7814 2.62746 + vertex 0.993464 1.7777 2.62886 + endloop + endfacet + facet normal 0.273979 0.0883525 0.957669 + outer loop + vertex 0.993464 1.7777 2.62886 + vertex 0.997169 1.7814 2.62746 + vertex 0.993105 1.78225 2.62854 + endloop + endfacet + facet normal 0.270833 0.0701716 0.960065 + outer loop + vertex 0.997169 1.7814 2.62746 + vertex 0.997035 1.78636 2.62713 + vertex 0.993105 1.78225 2.62854 + endloop + endfacet + facet normal 0.381638 0.0556313 0.922636 + outer loop + vertex 0.997465 1.77669 2.62771 + vertex 0.997578 1.77208 2.62794 + vertex 1.00112 1.77533 2.62628 + endloop + endfacet + facet normal 0.380329 0.0512755 0.923429 + outer loop + vertex 1.00096 1.78025 2.62607 + vertex 0.997465 1.77669 2.62771 + vertex 1.00112 1.77533 2.62628 + endloop + endfacet + facet normal 0.362487 0.0714536 0.929246 + outer loop + vertex 0.997169 1.7814 2.62746 + vertex 0.997465 1.77669 2.62771 + vertex 1.00096 1.78025 2.62607 + endloop + endfacet + facet normal 0.358781 0.0562402 0.931726 + outer loop + vertex 1.00082 1.78528 2.62582 + vertex 0.997169 1.7814 2.62746 + vertex 1.00096 1.78025 2.62607 + endloop + endfacet + facet normal 0.414009 0.0565942 0.908512 + outer loop + vertex 1.00096 1.78025 2.62607 + vertex 1.00434 1.78384 2.6243 + vertex 1.00082 1.78528 2.62582 + endloop + endfacet + facet normal 0.412008 0.0503536 0.909788 + outer loop + vertex 1.00434 1.78384 2.6243 + vertex 1.00424 1.78891 2.62407 + vertex 1.00082 1.78528 2.62582 + endloop + endfacet + facet normal 0.407219 0.0557582 0.911627 + outer loop + vertex 1.00082 1.78528 2.62582 + vertex 1.00424 1.78891 2.62407 + vertex 1.00076 1.79037 2.62553 + endloop + endfacet + facet normal 0.342075 0.0564867 0.937973 + outer loop + vertex 1.00076 1.79037 2.62553 + vertex 0.997035 1.78636 2.62713 + vertex 1.00082 1.78528 2.62582 + endloop + endfacet + facet normal 0.32916 0.0699819 0.941677 + outer loop + vertex 0.997011 1.79145 2.62676 + vertex 0.997035 1.78636 2.62713 + vertex 1.00076 1.79037 2.62553 + endloop + endfacet + facet normal 0.326621 0.0592553 0.943296 + outer loop + vertex 1.00059 1.7954 2.62528 + vertex 0.997011 1.79145 2.62676 + vertex 1.00076 1.79037 2.62553 + endloop + endfacet + facet normal 0.396525 0.0602257 0.916046 + outer loop + vertex 1.00076 1.79037 2.62553 + vertex 1.00412 1.79392 2.62385 + vertex 1.00059 1.7954 2.62528 + endloop + endfacet + facet normal 0.395635 0.0575717 0.916602 + outer loop + vertex 1.00412 1.79392 2.62385 + vertex 1.0037 1.79889 2.62371 + vertex 1.00059 1.7954 2.62528 + endloop + endfacet + facet normal 0.376247 0.0778392 0.923244 + outer loop + vertex 1.00059 1.7954 2.62528 + vertex 1.0037 1.79889 2.62371 + vertex 0.999966 1.80026 2.62512 + endloop + endfacet + facet normal 0.30396 0.0693853 0.950155 + outer loop + vertex 0.999966 1.80026 2.62512 + vertex 0.996774 1.79651 2.62642 + vertex 1.00059 1.7954 2.62528 + endloop + endfacet + facet normal 0.374893 0.0732067 0.924173 + outer loop + vertex 1.0037 1.79889 2.62371 + vertex 1.00261 1.80412 2.62374 + vertex 0.999966 1.80026 2.62512 + endloop + endfacet + facet normal 0.344076 0.0977829 0.933836 + outer loop + vertex 0.998927 1.80415 2.6251 + vertex 0.999966 1.80026 2.62512 + vertex 1.00261 1.80412 2.62374 + endloop + endfacet + facet normal 0.343529 0.115541 0.932008 + outer loop + vertex 0.998927 1.80415 2.6251 + vertex 1.00261 1.80412 2.62374 + vertex 0.99917 1.80847 2.62447 + endloop + endfacet + facet normal 0.309522 0.0860877 0.946987 + outer loop + vertex 0.99917 1.80847 2.62447 + vertex 1.00261 1.80412 2.62374 + vertex 1.00286 1.80774 2.62333 + endloop + endfacet + facet normal 0.310751 0.0942433 0.945808 + outer loop + vertex 1.00286 1.80774 2.62333 + vertex 1.00344 1.81135 2.62278 + vertex 0.99917 1.80847 2.62447 + endloop + endfacet + facet normal 0.312249 0.0918758 0.945547 + outer loop + vertex 0.99917 1.80847 2.62447 + vertex 1.00344 1.81135 2.62278 + vertex 0.99962 1.81324 2.62386 + endloop + endfacet + facet normal 0.302446 0.0691672 0.950654 + outer loop + vertex 1.00344 1.81135 2.62278 + vertex 1.00266 1.8165 2.62266 + vertex 0.99962 1.81324 2.62386 + endloop + endfacet + facet normal 0.390222 0.0772965 0.917471 + outer loop + vertex 1.00344 1.81135 2.62278 + vertex 1.00286 1.80774 2.62333 + vertex 1.00606 1.80719 2.62202 + endloop + endfacet + facet normal 0.382963 0.0720848 0.920947 + outer loop + vertex 1.00717 1.81119 2.62124 + vertex 1.00344 1.81135 2.62278 + vertex 1.00606 1.80719 2.62202 + endloop + endfacet + facet normal 0.424089 0.0573124 0.903805 + outer loop + vertex 1.00717 1.81119 2.62124 + vertex 1.00606 1.80719 2.62202 + vertex 1.00921 1.80898 2.62042 + endloop + endfacet + facet normal 0.429386 0.0632949 0.9009 + outer loop + vertex 1.00921 1.80898 2.62042 + vertex 1.01037 1.8131 2.61958 + vertex 1.00717 1.81119 2.62124 + endloop + endfacet + facet normal 0.427205 0.0675789 0.901626 + outer loop + vertex 1.00717 1.81119 2.62124 + vertex 1.01037 1.8131 2.61958 + vertex 1.00656 1.81524 2.62123 + endloop + endfacet + facet normal 0.420537 0.0525542 0.905752 + outer loop + vertex 1.01037 1.8131 2.61958 + vertex 1.0097 1.81869 2.61957 + vertex 1.00656 1.81524 2.62123 + endloop + endfacet + facet normal 0.411995 0.0619446 0.909078 + outer loop + vertex 1.00656 1.81524 2.62123 + vertex 1.0097 1.81869 2.61957 + vertex 1.00605 1.8203 2.62111 + endloop + endfacet + facet normal 0.359227 0.0571277 0.9315 + outer loop + vertex 1.00605 1.8203 2.62111 + vertex 1.00266 1.8165 2.62266 + vertex 1.00656 1.81524 2.62123 + endloop + endfacet + facet normal 0.36464 0.0780053 0.927875 + outer loop + vertex 1.00266 1.8165 2.62266 + vertex 1.00344 1.81135 2.62278 + vertex 1.00656 1.81524 2.62123 + endloop + endfacet + facet normal 0.337719 0.078949 0.93793 + outer loop + vertex 1.00217 1.82141 2.62242 + vertex 1.00266 1.8165 2.62266 + vertex 1.00605 1.8203 2.62111 + endloop + endfacet + facet normal 0.333677 0.061559 0.940675 + outer loop + vertex 1.00584 1.82538 2.62086 + vertex 1.00217 1.82141 2.62242 + vertex 1.00605 1.8203 2.62111 + endloop + endfacet + facet normal 0.3996 0.0630187 0.914521 + outer loop + vertex 1.00605 1.8203 2.62111 + vertex 1.00936 1.82389 2.61942 + vertex 1.00584 1.82538 2.62086 + endloop + endfacet + facet normal 0.398016 0.0582799 0.915525 + outer loop + vertex 1.00936 1.82389 2.61942 + vertex 1.00921 1.82895 2.61916 + vertex 1.00584 1.82538 2.62086 + endloop + endfacet + facet normal 0.383911 0.0739363 0.920405 + outer loop + vertex 1.00584 1.82538 2.62086 + vertex 1.00921 1.82895 2.61916 + vertex 1.00568 1.83034 2.62053 + endloop + endfacet + facet normal 0.309285 0.073407 0.948132 + outer loop + vertex 1.00568 1.83034 2.62053 + vertex 1.00203 1.82639 2.62202 + vertex 1.00584 1.82538 2.62086 + endloop + endfacet + facet normal 0.283067 0.0997815 0.953896 + outer loop + vertex 1.00184 1.8313 2.62156 + vertex 1.00203 1.82639 2.62202 + vertex 1.00568 1.83034 2.62053 + endloop + endfacet + facet normal 0.28041 0.0868845 0.95594 + outer loop + vertex 1.00517 1.83504 2.62025 + vertex 1.00184 1.8313 2.62156 + vertex 1.00568 1.83034 2.62053 + endloop + endfacet + facet normal 0.361318 0.0940176 0.927691 + outer loop + vertex 1.00568 1.83034 2.62053 + vertex 1.0089 1.83388 2.61891 + vertex 1.00517 1.83504 2.62025 + endloop + endfacet + facet normal 0.359816 0.0878063 0.928882 + outer loop + vertex 1.0089 1.83388 2.61891 + vertex 1.00799 1.83901 2.61878 + vertex 1.00517 1.83504 2.62025 + endloop + endfacet + facet normal 0.31558 0.123668 0.940806 + outer loop + vertex 1.00403 1.8387 2.62015 + vertex 1.00517 1.83504 2.62025 + vertex 1.00799 1.83901 2.61878 + endloop + endfacet + facet normal 0.315463 0.124719 0.940706 + outer loop + vertex 1.00403 1.8387 2.62015 + vertex 1.00799 1.83901 2.61878 + vertex 1.00448 1.84278 2.61946 + endloop + endfacet + facet normal 0.29121 0.100234 0.951394 + outer loop + vertex 1.00448 1.84278 2.61946 + vertex 1.00799 1.83901 2.61878 + vertex 1.00856 1.84331 2.61815 + endloop + endfacet + facet normal 0.293452 0.0848559 0.9522 + outer loop + vertex 1.00856 1.84331 2.61815 + vertex 1.00716 1.84619 2.61833 + vertex 1.00448 1.84278 2.61946 + endloop + endfacet + facet normal 0.241167 0.10133 0.965179 + outer loop + vertex 1.00517 1.83504 2.62025 + vertex 1.00403 1.8387 2.62015 + vertex 1.0012 1.8359 2.62115 + endloop + endfacet + facet normal 0.244697 0.120794 0.962046 + outer loop + vertex 1.0012 1.8359 2.62115 + vertex 1.00184 1.8313 2.62156 + vertex 1.00517 1.83504 2.62025 + endloop + endfacet + facet normal 0.383039 0.0711562 0.920988 + outer loop + vertex 1.00921 1.82895 2.61916 + vertex 1.0089 1.83388 2.61891 + vertex 1.00568 1.83034 2.62053 + endloop + endfacet + facet normal 0.429892 0.0730276 0.899922 + outer loop + vertex 1.00921 1.82895 2.61916 + vertex 1.01243 1.83222 2.61736 + vertex 1.0089 1.83388 2.61891 + endloop + endfacet + facet normal 0.427745 0.0670544 0.901409 + outer loop + vertex 1.01243 1.83222 2.61736 + vertex 1.0121 1.83711 2.61715 + vertex 1.0089 1.83388 2.61891 + endloop + endfacet + facet normal 0.403998 0.0951555 0.909797 + outer loop + vertex 1.0089 1.83388 2.61891 + vertex 1.0121 1.83711 2.61715 + vertex 1.00799 1.83901 2.61878 + endloop + endfacet + facet normal 0.394619 0.0694256 0.916218 + outer loop + vertex 1.0121 1.83711 2.61715 + vertex 1.01174 1.84184 2.61695 + vertex 1.00799 1.83901 2.61878 + endloop + endfacet + facet normal 0.385733 0.082904 0.918878 + outer loop + vertex 1.00799 1.83901 2.61878 + vertex 1.01174 1.84184 2.61695 + vertex 1.00856 1.84331 2.61815 + endloop + endfacet + facet normal 0.383212 0.0761039 0.92052 + outer loop + vertex 1.01174 1.84184 2.61695 + vertex 1.01104 1.84668 2.61684 + vertex 1.00856 1.84331 2.61815 + endloop + endfacet + facet normal 0.343157 0.110209 0.93279 + outer loop + vertex 1.00856 1.84331 2.61815 + vertex 1.01104 1.84668 2.61684 + vertex 1.00716 1.84619 2.61833 + endloop + endfacet + facet normal 0.345273 0.0961222 0.933567 + outer loop + vertex 1.00801 1.85073 2.61754 + vertex 1.00716 1.84619 2.61833 + vertex 1.01104 1.84668 2.61684 + endloop + endfacet + facet normal 0.337023 0.0893143 0.93725 + outer loop + vertex 1.01208 1.85099 2.61606 + vertex 1.00801 1.85073 2.61754 + vertex 1.01104 1.84668 2.61684 + endloop + endfacet + facet normal 0.337966 0.0783906 0.937888 + outer loop + vertex 1.01138 1.85514 2.61596 + vertex 1.00801 1.85073 2.61754 + vertex 1.01208 1.85099 2.61606 + endloop + endfacet + facet normal 0.407378 0.089259 0.908887 + outer loop + vertex 1.01208 1.85099 2.61606 + vertex 1.01535 1.85313 2.61438 + vertex 1.01138 1.85514 2.61596 + endloop + endfacet + facet normal 0.399169 0.0688328 0.91429 + outer loop + vertex 1.01535 1.85313 2.61438 + vertex 1.0145 1.8587 2.61433 + vertex 1.01138 1.85514 2.61596 + endloop + endfacet + facet normal 0.378748 0.0898385 0.921129 + outer loop + vertex 1.01138 1.85514 2.61596 + vertex 1.0145 1.8587 2.61433 + vertex 1.01078 1.8602 2.61572 + endloop + endfacet + facet normal 0.306463 0.0824891 0.948302 + outer loop + vertex 1.01078 1.8602 2.61572 + vertex 1.0073 1.85618 2.61719 + vertex 1.01138 1.85514 2.61596 + endloop + endfacet + facet normal 0.273749 0.113326 0.955101 + outer loop + vertex 1.0068 1.86121 2.61674 + vertex 1.0073 1.85618 2.61719 + vertex 1.01078 1.8602 2.61572 + endloop + endfacet + facet normal 0.27091 0.0997374 0.957424 + outer loop + vertex 1.01009 1.86497 2.61541 + vertex 1.0068 1.86121 2.61674 + vertex 1.01078 1.8602 2.61572 + endloop + endfacet + facet normal 0.346788 0.108962 0.931593 + outer loop + vertex 1.01078 1.8602 2.61572 + vertex 1.01389 1.86379 2.61414 + vertex 1.01009 1.86497 2.61541 + endloop + endfacet + facet normal 0.344826 0.100916 0.933226 + outer loop + vertex 1.01389 1.86379 2.61414 + vertex 1.01296 1.86897 2.61392 + vertex 1.01009 1.86497 2.61541 + endloop + endfacet + facet normal 0.300953 0.136303 0.943848 + outer loop + vertex 1.00898 1.86866 2.61524 + vertex 1.01009 1.86497 2.61541 + vertex 1.01296 1.86897 2.61392 + endloop + endfacet + facet normal 0.300521 0.140076 0.943433 + outer loop + vertex 1.00898 1.86866 2.61524 + vertex 1.01296 1.86897 2.61392 + vertex 1.00951 1.87274 2.61446 + endloop + endfacet + facet normal 0.225655 0.114679 0.967434 + outer loop + vertex 1.01009 1.86497 2.61541 + vertex 1.00898 1.86866 2.61524 + vertex 1.00608 1.86583 2.61625 + endloop + endfacet + facet normal 0.375659 0.0802322 0.923279 + outer loop + vertex 1.0145 1.8587 2.61433 + vertex 1.01389 1.86379 2.61414 + vertex 1.01078 1.8602 2.61572 + endloop + endfacet + facet normal 0.229732 0.137827 0.963445 + outer loop + vertex 1.00608 1.86583 2.61625 + vertex 1.0068 1.86121 2.61674 + vertex 1.01009 1.86497 2.61541 + endloop + endfacet + facet normal 0.433204 0.0739288 0.898259 + outer loop + vertex 1.01535 1.85313 2.61438 + vertex 1.018 1.85712 2.61277 + vertex 1.0145 1.8587 2.61433 + endloop + endfacet + facet normal 0.431911 0.0701277 0.899186 + outer loop + vertex 1.018 1.85712 2.61277 + vertex 1.01749 1.8621 2.61263 + vertex 1.0145 1.8587 2.61433 + endloop + endfacet + facet normal 0.418451 0.0845525 0.904295 + outer loop + vertex 1.0145 1.8587 2.61433 + vertex 1.01749 1.8621 2.61263 + vertex 1.01389 1.86379 2.61414 + endloop + endfacet + facet normal 0.415884 0.0774702 0.906112 + outer loop + vertex 1.01749 1.8621 2.61263 + vertex 1.01709 1.86708 2.61239 + vertex 1.01389 1.86379 2.61414 + endloop + endfacet + facet normal 0.389072 0.10814 0.914838 + outer loop + vertex 1.01389 1.86379 2.61414 + vertex 1.01709 1.86708 2.61239 + vertex 1.01296 1.86897 2.61392 + endloop + endfacet + facet normal 0.378408 0.0788029 0.922278 + outer loop + vertex 1.01709 1.86708 2.61239 + vertex 1.0168 1.8719 2.6121 + vertex 1.01296 1.86897 2.61392 + endloop + endfacet + facet normal 0.36728 0.0952647 0.925219 + outer loop + vertex 1.01296 1.86897 2.61392 + vertex 1.0168 1.8719 2.6121 + vertex 1.01362 1.87328 2.61322 + endloop + endfacet + facet normal 0.364262 0.0866806 0.927254 + outer loop + vertex 1.0168 1.8719 2.6121 + vertex 1.01615 1.87672 2.6119 + vertex 1.01362 1.87328 2.61322 + endloop + endfacet + facet normal 0.323313 0.121099 0.938511 + outer loop + vertex 1.01362 1.87328 2.61322 + vertex 1.01615 1.87672 2.6119 + vertex 1.01227 1.87614 2.61331 + endloop + endfacet + facet normal 0.323798 0.118308 0.9387 + outer loop + vertex 1.01308 1.88067 2.61246 + vertex 1.01227 1.87614 2.61331 + vertex 1.01615 1.87672 2.6119 + endloop + endfacet + facet normal 0.30922 0.106066 0.945057 + outer loop + vertex 1.01718 1.88096 2.61109 + vertex 1.01308 1.88067 2.61246 + vertex 1.01615 1.87672 2.6119 + endloop + endfacet + facet normal 0.379565 0.0843918 0.921308 + outer loop + vertex 1.01718 1.88096 2.61109 + vertex 1.01615 1.87672 2.6119 + vertex 1.01942 1.87899 2.61035 + endloop + endfacet + facet normal 0.388001 0.0956851 0.916679 + outer loop + vertex 1.01942 1.87899 2.61035 + vertex 1.02037 1.8831 2.60951 + vertex 1.01718 1.88096 2.61109 + endloop + endfacet + facet normal 0.37465 0.117813 0.919651 + outer loop + vertex 1.01718 1.88096 2.61109 + vertex 1.02037 1.8831 2.60951 + vertex 1.01632 1.88502 2.61092 + endloop + endfacet + facet normal 0.366781 0.0971338 0.925223 + outer loop + vertex 1.02037 1.8831 2.60951 + vertex 1.01943 1.88849 2.60932 + vertex 1.01632 1.88502 2.61092 + endloop + endfacet + facet normal 0.336174 0.128085 0.93305 + outer loop + vertex 1.01632 1.88502 2.61092 + vertex 1.01943 1.88849 2.60932 + vertex 1.01519 1.89004 2.61064 + endloop + endfacet + facet normal 0.27353 0.115139 0.954947 + outer loop + vertex 1.01519 1.89004 2.61064 + vertex 1.01197 1.88611 2.61203 + vertex 1.01632 1.88502 2.61092 + endloop + endfacet + facet normal 0.276876 0.131612 0.95185 + outer loop + vertex 1.01197 1.88611 2.61203 + vertex 1.01308 1.88067 2.61246 + vertex 1.01632 1.88502 2.61092 + endloop + endfacet + facet normal 0.230726 0.152326 0.961021 + outer loop + vertex 1.01058 1.89135 2.61154 + vertex 1.01197 1.88611 2.61203 + vertex 1.01519 1.89004 2.61064 + endloop + endfacet + facet normal 0.222842 0.119954 0.967446 + outer loop + vertex 1.01519 1.89004 2.61064 + vertex 1.01396 1.89414 2.61041 + vertex 1.01058 1.89135 2.61154 + endloop + endfacet + facet normal 0.294161 0.140043 0.94544 + outer loop + vertex 1.01396 1.89414 2.61041 + vertex 1.01519 1.89004 2.61064 + vertex 1.01812 1.89418 2.60911 + endloop + endfacet + facet normal 0.293565 0.151806 0.943809 + outer loop + vertex 1.01396 1.89414 2.61041 + vertex 1.01812 1.89418 2.60911 + vertex 1.0143 1.8987 2.60957 + endloop + endfacet + facet normal 0.426725 0.0834236 0.900526 + outer loop + vertex 1.01942 1.87899 2.61035 + vertex 1.02284 1.87894 2.60873 + vertex 1.02037 1.8831 2.60951 + endloop + endfacet + facet normal 0.416295 0.0761921 0.906032 + outer loop + vertex 1.02037 1.8831 2.60951 + vertex 1.02284 1.87894 2.60873 + vertex 1.02325 1.88261 2.60823 + endloop + endfacet + facet normal 0.417451 0.0869671 0.904528 + outer loop + vertex 1.02325 1.88261 2.60823 + vertex 1.02359 1.88632 2.60772 + vertex 1.02037 1.8831 2.60951 + endloop + endfacet + facet normal 0.403867 0.103062 0.908994 + outer loop + vertex 1.02037 1.8831 2.60951 + vertex 1.02359 1.88632 2.60772 + vertex 1.01943 1.88849 2.60932 + endloop + endfacet + facet normal 0.39779 0.0883164 0.913216 + outer loop + vertex 1.02359 1.88632 2.60772 + vertex 1.02258 1.89184 2.60763 + vertex 1.01943 1.88849 2.60932 + endloop + endfacet + facet normal 0.369564 0.11905 0.921548 + outer loop + vertex 1.01943 1.88849 2.60932 + vertex 1.02258 1.89184 2.60763 + vertex 1.01812 1.89418 2.60911 + endloop + endfacet + facet normal 0.356441 0.0884878 0.930118 + outer loop + vertex 1.02258 1.89184 2.60763 + vertex 1.02211 1.89689 2.60733 + vertex 1.01812 1.89418 2.60911 + endloop + endfacet + facet normal 0.347455 0.102956 0.932028 + outer loop + vertex 1.01812 1.89418 2.60911 + vertex 1.02211 1.89689 2.60733 + vertex 1.01889 1.89873 2.60832 + endloop + endfacet + facet normal 0.342257 0.092268 0.935065 + outer loop + vertex 1.02211 1.89689 2.60733 + vertex 1.02171 1.90154 2.60701 + vertex 1.01889 1.89873 2.60832 + endloop + endfacet + facet normal 0.317113 0.12018 0.940742 + outer loop + vertex 1.01889 1.89873 2.60832 + vertex 1.02171 1.90154 2.60701 + vertex 1.01794 1.90243 2.60817 + endloop + endfacet + facet normal 0.314187 0.10397 0.943651 + outer loop + vertex 1.02171 1.90154 2.60701 + vertex 1.02078 1.90641 2.60679 + vertex 1.01794 1.90243 2.60817 + endloop + endfacet + facet normal 0.27535 0.134456 0.951895 + outer loop + vertex 1.01794 1.90243 2.60817 + vertex 1.02078 1.90641 2.60679 + vertex 1.01695 1.90591 2.60796 + endloop + endfacet + facet normal 0.386558 0.0948356 0.917376 + outer loop + vertex 1.02171 1.90154 2.60701 + vertex 1.02211 1.89689 2.60733 + vertex 1.0253 1.90004 2.60565 + endloop + endfacet + facet normal 0.382845 0.0835146 0.92003 + outer loop + vertex 1.02466 1.90479 2.60549 + vertex 1.02171 1.90154 2.60701 + vertex 1.0253 1.90004 2.60565 + endloop + endfacet + facet normal 0.415255 0.0874082 0.905496 + outer loop + vertex 1.0253 1.90004 2.60565 + vertex 1.02834 1.90351 2.60392 + vertex 1.02466 1.90479 2.60549 + endloop + endfacet + facet normal 0.414059 0.0827347 0.906482 + outer loop + vertex 1.02834 1.90351 2.60392 + vertex 1.02725 1.90834 2.60398 + vertex 1.02466 1.90479 2.60549 + endloop + endfacet + facet normal 0.400232 0.094925 0.911484 + outer loop + vertex 1.02397 1.90873 2.60538 + vertex 1.02466 1.90479 2.60549 + vertex 1.02725 1.90834 2.60398 + endloop + endfacet + facet normal 0.401092 0.109597 0.909458 + outer loop + vertex 1.02397 1.90873 2.60538 + vertex 1.02725 1.90834 2.60398 + vertex 1.02495 1.91301 2.60444 + endloop + endfacet + facet normal 0.398137 0.107996 0.910947 + outer loop + vertex 1.02495 1.91301 2.60444 + vertex 1.02725 1.90834 2.60398 + vertex 1.0296 1.91239 2.60248 + endloop + endfacet + facet normal 0.39678 0.0895544 0.913535 + outer loop + vertex 1.0296 1.91239 2.60248 + vertex 1.02791 1.91705 2.60275 + vertex 1.02495 1.91301 2.60444 + endloop + endfacet + facet normal 0.353238 0.126994 0.926874 + outer loop + vertex 1.02495 1.91301 2.60444 + vertex 1.02791 1.91705 2.60275 + vertex 1.0234 1.91879 2.60423 + endloop + endfacet + facet normal 0.342628 0.0925711 0.934899 + outer loop + vertex 1.02791 1.91705 2.60275 + vertex 1.02734 1.92182 2.60249 + vertex 1.0234 1.91879 2.60423 + endloop + endfacet + facet normal 0.328774 0.11217 0.937723 + outer loop + vertex 1.0234 1.91879 2.60423 + vertex 1.02734 1.92182 2.60249 + vertex 1.02412 1.9234 2.60343 + endloop + endfacet + facet normal 0.327799 0.109814 0.938344 + outer loop + vertex 1.02734 1.92182 2.60249 + vertex 1.02691 1.92646 2.6021 + vertex 1.02412 1.9234 2.60343 + endloop + endfacet + facet normal 0.286074 0.151351 0.946179 + outer loop + vertex 1.02412 1.9234 2.60343 + vertex 1.02691 1.92646 2.6021 + vertex 1.0229 1.92711 2.6032 + endloop + endfacet + facet normal 0.284359 0.135857 0.949043 + outer loop + vertex 1.02691 1.92646 2.6021 + vertex 1.0257 1.93146 2.60174 + vertex 1.0229 1.92711 2.6032 + endloop + endfacet + facet normal 0.324748 0.144629 0.934677 + outer loop + vertex 1.0257 1.93146 2.60174 + vertex 1.02691 1.92646 2.6021 + vertex 1.02997 1.9299 2.6005 + endloop + endfacet + facet normal 0.31515 0.11226 0.942379 + outer loop + vertex 1.02997 1.9299 2.6005 + vertex 1.02903 1.93399 2.60033 + vertex 1.0257 1.93146 2.60174 + endloop + endfacet + facet normal 0.373051 0.12472 0.91939 + outer loop + vertex 1.02903 1.93399 2.60033 + vertex 1.02997 1.9299 2.6005 + vertex 1.03271 1.93387 2.59885 + endloop + endfacet + facet normal 0.372578 0.144948 0.916611 + outer loop + vertex 1.02903 1.93399 2.60033 + vertex 1.03271 1.93387 2.59885 + vertex 1.02933 1.93861 2.59947 + endloop + endfacet + facet normal 0.335635 0.116216 0.934796 + outer loop + vertex 1.02933 1.93861 2.59947 + vertex 1.03271 1.93387 2.59885 + vertex 1.03299 1.9376 2.59829 + endloop + endfacet + facet normal 0.337055 0.122952 0.933422 + outer loop + vertex 1.03299 1.9376 2.59829 + vertex 1.03343 1.94122 2.59765 + vertex 1.02933 1.93861 2.59947 + endloop + endfacet + facet normal 0.333632 0.128652 0.933884 + outer loop + vertex 1.02933 1.93861 2.59947 + vertex 1.03343 1.94122 2.59765 + vertex 1.02961 1.9435 2.5987 + endloop + endfacet + facet normal 0.324058 0.109968 0.939624 + outer loop + vertex 1.03343 1.94122 2.59765 + vertex 1.03231 1.94648 2.59742 + vertex 1.02961 1.9435 2.5987 + endloop + endfacet + facet normal 0.291955 0.141766 0.945867 + outer loop + vertex 1.02961 1.9435 2.5987 + vertex 1.03231 1.94648 2.59742 + vertex 1.02818 1.94749 2.59854 + endloop + endfacet + facet normal 0.289388 0.128254 0.948581 + outer loop + vertex 1.03231 1.94648 2.59742 + vertex 1.03098 1.95159 2.59714 + vertex 1.02818 1.94749 2.59854 + endloop + endfacet + facet normal 0.323038 0.136337 0.936514 + outer loop + vertex 1.03098 1.95159 2.59714 + vertex 1.03231 1.94648 2.59742 + vertex 1.03529 1.95 2.59588 + endloop + endfacet + facet normal 0.356957 0.104032 0.92831 + outer loop + vertex 1.03529 1.95 2.59588 + vertex 1.03231 1.94648 2.59742 + vertex 1.03629 1.94494 2.59607 + endloop + endfacet + facet normal 0.386221 0.109327 0.915905 + outer loop + vertex 1.03629 1.94494 2.59607 + vertex 1.03928 1.94842 2.59439 + vertex 1.03529 1.95 2.59588 + endloop + endfacet + facet normal 0.384702 0.104358 0.917122 + outer loop + vertex 1.03928 1.94842 2.59439 + vertex 1.03823 1.95408 2.59419 + vertex 1.03529 1.95 2.59588 + endloop + endfacet + facet normal 0.401776 0.107247 0.909436 + outer loop + vertex 1.03928 1.94842 2.59439 + vertex 1.04237 1.95191 2.59261 + vertex 1.03823 1.95408 2.59419 + endloop + endfacet + facet normal 0.398549 0.0994376 0.911741 + outer loop + vertex 1.04237 1.95191 2.59261 + vertex 1.04188 1.9569 2.59228 + vertex 1.03823 1.95408 2.59419 + endloop + endfacet + facet normal 0.390444 0.111363 0.913866 + outer loop + vertex 1.03823 1.95408 2.59419 + vertex 1.04188 1.9569 2.59228 + vertex 1.03883 1.95859 2.59338 + endloop + endfacet + facet normal 0.342709 0.120928 0.931626 + outer loop + vertex 1.03508 1.95833 2.59479 + vertex 1.03823 1.95408 2.59419 + vertex 1.03883 1.95859 2.59338 + endloop + endfacet + facet normal 0.342267 0.1252 0.931224 + outer loop + vertex 1.03883 1.95859 2.59338 + vertex 1.03743 1.96172 2.59347 + vertex 1.03508 1.95833 2.59479 + endloop + endfacet + facet normal 0.296018 0.161361 0.941454 + outer loop + vertex 1.03508 1.95833 2.59479 + vertex 1.03743 1.96172 2.59347 + vertex 1.03357 1.96362 2.59436 + endloop + endfacet + facet normal 0.290363 0.148033 0.945397 + outer loop + vertex 1.03743 1.96172 2.59347 + vertex 1.03818 1.96609 2.59256 + vertex 1.03357 1.96362 2.59436 + endloop + endfacet + facet normal 0.361438 0.131214 0.923117 + outer loop + vertex 1.03818 1.96609 2.59256 + vertex 1.03743 1.96172 2.59347 + vertex 1.04112 1.96183 2.59201 + endloop + endfacet + facet normal 0.347726 0.120917 0.929767 + outer loop + vertex 1.04203 1.96591 2.59114 + vertex 1.03818 1.96609 2.59256 + vertex 1.04112 1.96183 2.59201 + endloop + endfacet + facet normal 0.390847 0.107936 0.914105 + outer loop + vertex 1.04203 1.96591 2.59114 + vertex 1.04112 1.96183 2.59201 + vertex 1.04414 1.96376 2.59049 + endloop + endfacet + facet normal 0.394302 0.111914 0.912141 + outer loop + vertex 1.04414 1.96376 2.59049 + vertex 1.04518 1.9679 2.58953 + vertex 1.04203 1.96591 2.59114 + endloop + endfacet + facet normal 0.385208 0.127823 0.913934 + outer loop + vertex 1.04203 1.96591 2.59114 + vertex 1.04518 1.9679 2.58953 + vertex 1.04117 1.96993 2.59094 + endloop + endfacet + facet normal 0.378725 0.111734 0.91874 + outer loop + vertex 1.04518 1.9679 2.58953 + vertex 1.04413 1.97338 2.5893 + vertex 1.04117 1.96993 2.59094 + endloop + endfacet + facet normal 0.350808 0.139057 0.926065 + outer loop + vertex 1.04117 1.96993 2.59094 + vertex 1.04413 1.97338 2.5893 + vertex 1.04002 1.97479 2.59064 + endloop + endfacet + facet normal 0.317269 0.131913 0.939116 + outer loop + vertex 1.04002 1.97479 2.59064 + vertex 1.0371 1.97123 2.59213 + vertex 1.04117 1.96993 2.59094 + endloop + endfacet + facet normal 0.320446 0.144574 0.936169 + outer loop + vertex 1.0371 1.97123 2.59213 + vertex 1.03818 1.96609 2.59256 + vertex 1.04117 1.96993 2.59094 + endloop + endfacet + facet normal 0.284773 0.13814 0.948589 + outer loop + vertex 1.03818 1.96609 2.59256 + vertex 1.0371 1.97123 2.59213 + vertex 1.03435 1.96815 2.59341 + endloop + endfacet + facet normal 0.289883 0.148935 0.945403 + outer loop + vertex 1.03357 1.96362 2.59436 + vertex 1.03818 1.96609 2.59256 + vertex 1.03435 1.96815 2.59341 + endloop + endfacet + facet normal 0.271592 0.17253 0.946822 + outer loop + vertex 1.03553 1.97611 2.59169 + vertex 1.0371 1.97123 2.59213 + vertex 1.04002 1.97479 2.59064 + endloop + endfacet + facet normal 0.264543 0.143083 0.9537 + outer loop + vertex 1.04002 1.97479 2.59064 + vertex 1.03881 1.97876 2.59039 + vertex 1.03553 1.97611 2.59169 + endloop + endfacet + facet normal 0.312454 0.15671 0.936918 + outer loop + vertex 1.03881 1.97876 2.59039 + vertex 1.04002 1.97479 2.59064 + vertex 1.04285 1.97889 2.58902 + endloop + endfacet + facet normal 0.311274 0.171197 0.934773 + outer loop + vertex 1.03881 1.97876 2.59039 + vertex 1.04285 1.97889 2.58902 + vertex 1.0391 1.98331 2.58945 + endloop + endfacet + facet normal 0.3481 0.128785 0.928569 + outer loop + vertex 1.04413 1.97338 2.5893 + vertex 1.04285 1.97889 2.58902 + vertex 1.04002 1.97479 2.59064 + endloop + endfacet + facet normal 0.368332 0.133036 0.920126 + outer loop + vertex 1.04413 1.97338 2.5893 + vertex 1.04721 1.97679 2.58757 + vertex 1.04285 1.97889 2.58902 + endloop + endfacet + facet normal 0.392675 0.107539 0.913368 + outer loop + vertex 1.04806 1.97178 2.5878 + vertex 1.04721 1.97679 2.58757 + vertex 1.04413 1.97338 2.5893 + endloop + endfacet + facet normal 0.394851 0.114535 0.911578 + outer loop + vertex 1.04518 1.9679 2.58953 + vertex 1.04806 1.97178 2.5878 + vertex 1.04413 1.97338 2.5893 + endloop + endfacet + facet normal 0.347726 0.120657 0.9298 + outer loop + vertex 1.04117 1.96993 2.59094 + vertex 1.03818 1.96609 2.59256 + vertex 1.04203 1.96591 2.59114 + endloop + endfacet + facet normal 0.361236 0.133912 0.922809 + outer loop + vertex 1.03883 1.95859 2.59338 + vertex 1.04112 1.96183 2.59201 + vertex 1.03743 1.96172 2.59347 + endloop + endfacet + facet normal 0.36377 0.13801 0.921208 + outer loop + vertex 1.03437 1.95411 2.5957 + vertex 1.03823 1.95408 2.59419 + vertex 1.03508 1.95833 2.59479 + endloop + endfacet + facet normal 0.364465 0.12145 0.923263 + outer loop + vertex 1.03437 1.95411 2.5957 + vertex 1.03529 1.95 2.59588 + vertex 1.03823 1.95408 2.59419 + endloop + endfacet + facet normal 0.315479 0.111309 0.942382 + outer loop + vertex 1.03529 1.95 2.59588 + vertex 1.03437 1.95411 2.5957 + vertex 1.03098 1.95159 2.59714 + endloop + endfacet + facet normal 0.389885 0.110101 0.914258 + outer loop + vertex 1.04188 1.9569 2.59228 + vertex 1.04112 1.96183 2.59201 + vertex 1.03883 1.95859 2.59338 + endloop + endfacet + facet normal 0.418238 0.100794 0.902728 + outer loop + vertex 1.04188 1.9569 2.59228 + vertex 1.04237 1.95191 2.59261 + vertex 1.04546 1.95515 2.59082 + endloop + endfacet + facet normal 0.416526 0.0961873 0.904021 + outer loop + vertex 1.04478 1.9599 2.59063 + vertex 1.04188 1.9569 2.59228 + vertex 1.04546 1.95515 2.59082 + endloop + endfacet + facet normal 0.429506 0.0978088 0.897751 + outer loop + vertex 1.04546 1.95515 2.59082 + vertex 1.04835 1.95854 2.58907 + vertex 1.04478 1.9599 2.59063 + endloop + endfacet + facet normal 0.427712 0.0913207 0.89929 + outer loop + vertex 1.04835 1.95854 2.58907 + vertex 1.04722 1.96327 2.58912 + vertex 1.04478 1.9599 2.59063 + endloop + endfacet + facet normal 0.417509 0.100415 0.903107 + outer loop + vertex 1.04414 1.96376 2.59049 + vertex 1.04478 1.9599 2.59063 + vertex 1.04722 1.96327 2.58912 + endloop + endfacet + facet normal 0.41781 0.103762 0.90259 + outer loop + vertex 1.04414 1.96376 2.59049 + vertex 1.04722 1.96327 2.58912 + vertex 1.04518 1.9679 2.58953 + endloop + endfacet + facet normal 0.414637 0.102219 0.904228 + outer loop + vertex 1.04518 1.9679 2.58953 + vertex 1.04722 1.96327 2.58912 + vertex 1.04928 1.96704 2.58775 + endloop + endfacet + facet normal 0.436865 0.0868386 0.895326 + outer loop + vertex 1.04928 1.96704 2.58775 + vertex 1.04722 1.96327 2.58912 + vertex 1.05124 1.96234 2.58725 + endloop + endfacet + facet normal 0.396911 0.0973328 0.912682 + outer loop + vertex 1.04478 1.9599 2.59063 + vertex 1.04414 1.96376 2.59049 + vertex 1.04112 1.96183 2.59201 + endloop + endfacet + facet normal 0.437912 0.093814 0.89411 + outer loop + vertex 1.04835 1.95854 2.58907 + vertex 1.05124 1.96234 2.58725 + vertex 1.04722 1.96327 2.58912 + endloop + endfacet + facet normal 0.440736 0.0860447 0.893503 + outer loop + vertex 1.049 1.95354 2.58922 + vertex 1.04835 1.95854 2.58907 + vertex 1.04546 1.95515 2.59082 + endloop + endfacet + facet normal 0.442609 0.091608 0.892023 + outer loop + vertex 1.04604 1.95017 2.59104 + vertex 1.049 1.95354 2.58922 + vertex 1.04546 1.95515 2.59082 + endloop + endfacet + facet normal 0.455624 0.0773303 0.886807 + outer loop + vertex 1.04953 1.9485 2.58939 + vertex 1.049 1.95354 2.58922 + vertex 1.04604 1.95017 2.59104 + endloop + endfacet + facet normal 0.458412 0.0852777 0.884639 + outer loop + vertex 1.04671 1.94527 2.59117 + vertex 1.04953 1.9485 2.58939 + vertex 1.04604 1.95017 2.59104 + endloop + endfacet + facet normal 0.439442 0.0829384 0.894434 + outer loop + vertex 1.04604 1.95017 2.59104 + vertex 1.04314 1.94672 2.59279 + vertex 1.04671 1.94527 2.59117 + endloop + endfacet + facet normal 0.440684 0.0871362 0.893423 + outer loop + vertex 1.04314 1.94672 2.59279 + vertex 1.04426 1.94188 2.5927 + vertex 1.04671 1.94527 2.59117 + endloop + endfacet + facet normal 0.451285 0.0774849 0.88901 + outer loop + vertex 1.04671 1.94527 2.59117 + vertex 1.04426 1.94188 2.5927 + vertex 1.04727 1.9413 2.59123 + endloop + endfacet + facet normal 0.482753 0.0816246 0.871944 + outer loop + vertex 1.04727 1.9413 2.59123 + vertex 1.05019 1.94319 2.58944 + vertex 1.04671 1.94527 2.59117 + endloop + endfacet + facet normal 0.489965 0.0677616 0.869104 + outer loop + vertex 1.04914 1.93903 2.59035 + vertex 1.05019 1.94319 2.58944 + vertex 1.04727 1.9413 2.59123 + endloop + endfacet + facet normal 0.482454 0.0597305 0.873882 + outer loop + vertex 1.04727 1.9413 2.59123 + vertex 1.0461 1.93725 2.59215 + vertex 1.04914 1.93903 2.59035 + endloop + endfacet + facet normal 0.450684 0.0725204 0.889733 + outer loop + vertex 1.04727 1.9413 2.59123 + vertex 1.04426 1.94188 2.5927 + vertex 1.0461 1.93725 2.59215 + endloop + endfacet + facet normal 0.449311 0.0718874 0.890479 + outer loop + vertex 1.04426 1.94188 2.5927 + vertex 1.04216 1.93811 2.59407 + vertex 1.0461 1.93725 2.59215 + endloop + endfacet + facet normal 0.4509 0.083239 0.888685 + outer loop + vertex 1.04324 1.93349 2.59395 + vertex 1.0461 1.93725 2.59215 + vertex 1.04216 1.93811 2.59407 + endloop + endfacet + facet normal 0.469079 0.0656698 0.880711 + outer loop + vertex 1.04673 1.93194 2.59221 + vertex 1.0461 1.93725 2.59215 + vertex 1.04324 1.93349 2.59395 + endloop + endfacet + facet normal 0.473203 0.0786862 0.877432 + outer loop + vertex 1.04386 1.9286 2.59406 + vertex 1.04673 1.93194 2.59221 + vertex 1.04324 1.93349 2.59395 + endloop + endfacet + facet normal 0.489448 0.0605738 0.869926 + outer loop + vertex 1.04719 1.92693 2.5923 + vertex 1.04673 1.93194 2.59221 + vertex 1.04386 1.9286 2.59406 + endloop + endfacet + facet normal 0.493346 0.071628 0.866879 + outer loop + vertex 1.04434 1.92356 2.5942 + vertex 1.04719 1.92693 2.5923 + vertex 1.04386 1.9286 2.59406 + endloop + endfacet + facet normal 0.508133 0.0549872 0.859522 + outer loop + vertex 1.04762 1.922 2.59236 + vertex 1.04719 1.92693 2.5923 + vertex 1.04434 1.92356 2.5942 + endloop + endfacet + facet normal 0.511426 0.065051 0.856862 + outer loop + vertex 1.045 1.91816 2.59422 + vertex 1.04762 1.922 2.59236 + vertex 1.04434 1.92356 2.5942 + endloop + endfacet + facet normal 0.482735 0.0616133 0.873597 + outer loop + vertex 1.045 1.91816 2.59422 + vertex 1.04434 1.92356 2.5942 + vertex 1.04143 1.92014 2.59605 + endloop + endfacet + facet normal 0.489161 0.0776787 0.868728 + outer loop + vertex 1.042 1.91605 2.59609 + vertex 1.045 1.91816 2.59422 + vertex 1.04143 1.92014 2.59605 + endloop + endfacet + facet normal 0.453824 0.0729243 0.888102 + outer loop + vertex 1.04143 1.92014 2.59605 + vertex 1.03847 1.91613 2.59789 + vertex 1.042 1.91605 2.59609 + endloop + endfacet + facet normal 0.453917 0.066689 0.888545 + outer loop + vertex 1.042 1.91605 2.59609 + vertex 1.03847 1.91613 2.59789 + vertex 1.04095 1.91198 2.59694 + endloop + endfacet + facet normal 0.461632 0.0723291 0.884118 + outer loop + vertex 1.03847 1.91613 2.59789 + vertex 1.03795 1.91231 2.59848 + vertex 1.04095 1.91198 2.59694 + endloop + endfacet + facet normal 0.461241 0.0651093 0.884883 + outer loop + vertex 1.03769 1.9087 2.59888 + vertex 1.04095 1.91198 2.59694 + vertex 1.03795 1.91231 2.59848 + endloop + endfacet + facet normal 0.436637 0.0682273 0.897047 + outer loop + vertex 1.03451 1.91246 2.60014 + vertex 1.03769 1.9087 2.59888 + vertex 1.03795 1.91231 2.59848 + endloop + endfacet + facet normal 0.471027 0.0528323 0.880535 + outer loop + vertex 1.04152 1.90692 2.59694 + vertex 1.04095 1.91198 2.59694 + vertex 1.03769 1.9087 2.59888 + endloop + endfacet + facet normal 0.475963 0.0674678 0.876873 + outer loop + vertex 1.03853 1.90367 2.59881 + vertex 1.04152 1.90692 2.59694 + vertex 1.03769 1.9087 2.59888 + endloop + endfacet + facet normal 0.457605 0.0642682 0.88683 + outer loop + vertex 1.03853 1.90367 2.59881 + vertex 1.03769 1.9087 2.59888 + vertex 1.03508 1.90509 2.60048 + endloop + endfacet + facet normal 0.447486 0.0735496 0.891261 + outer loop + vertex 1.03478 1.90842 2.60036 + vertex 1.03508 1.90509 2.60048 + vertex 1.03769 1.9087 2.59888 + endloop + endfacet + facet normal 0.437892 0.0728533 0.896071 + outer loop + vertex 1.03508 1.90509 2.60048 + vertex 1.03478 1.90842 2.60036 + vertex 1.03167 1.90745 2.60196 + endloop + endfacet + facet normal 0.440823 0.0782771 0.894175 + outer loop + vertex 1.03167 1.90745 2.60196 + vertex 1.03201 1.90195 2.60228 + vertex 1.03508 1.90509 2.60048 + endloop + endfacet + facet normal 0.447265 0.070493 0.891619 + outer loop + vertex 1.03508 1.90509 2.60048 + vertex 1.03201 1.90195 2.60228 + vertex 1.0355 1.90029 2.60065 + endloop + endfacet + facet normal 0.459727 0.0713483 0.88519 + outer loop + vertex 1.0355 1.90029 2.60065 + vertex 1.03853 1.90367 2.59881 + vertex 1.03508 1.90509 2.60048 + endloop + endfacet + facet normal 0.471382 0.0580664 0.880015 + outer loop + vertex 1.0389 1.89872 2.59894 + vertex 1.03853 1.90367 2.59881 + vertex 1.0355 1.90029 2.60065 + endloop + endfacet + facet normal 0.474394 0.0670849 0.877753 + outer loop + vertex 1.03582 1.89532 2.60086 + vertex 1.0389 1.89872 2.59894 + vertex 1.0355 1.90029 2.60065 + endloop + endfacet + facet normal 0.456536 0.0663308 0.887229 + outer loop + vertex 1.0355 1.90029 2.60065 + vertex 1.0324 1.89687 2.60251 + vertex 1.03582 1.89532 2.60086 + endloop + endfacet + facet normal 0.45862 0.0725786 0.885664 + outer loop + vertex 1.0324 1.89687 2.60251 + vertex 1.03285 1.89192 2.60268 + vertex 1.03582 1.89532 2.60086 + endloop + endfacet + facet normal 0.468822 0.0612751 0.881165 + outer loop + vertex 1.03582 1.89532 2.60086 + vertex 1.03285 1.89192 2.60268 + vertex 1.0361 1.89048 2.60105 + endloop + endfacet + facet normal 0.489903 0.0620223 0.869568 + outer loop + vertex 1.0361 1.89048 2.60105 + vertex 1.0391 1.89373 2.59913 + vertex 1.03582 1.89532 2.60086 + endloop + endfacet + facet normal 0.503389 0.0456104 0.862855 + outer loop + vertex 1.0392 1.88876 2.59933 + vertex 1.0391 1.89373 2.59913 + vertex 1.0361 1.89048 2.60105 + endloop + endfacet + facet normal 0.505546 0.0510678 0.861287 + outer loop + vertex 1.03614 1.88574 2.60131 + vertex 1.0392 1.88876 2.59933 + vertex 1.0361 1.89048 2.60105 + endloop + endfacet + facet normal 0.484874 0.0515032 0.873066 + outer loop + vertex 1.0361 1.89048 2.60105 + vertex 1.03352 1.8878 2.60264 + vertex 1.03614 1.88574 2.60131 + endloop + endfacet + facet normal 0.485643 0.0528106 0.87256 + outer loop + vertex 1.03352 1.8878 2.60264 + vertex 1.03257 1.88333 2.60344 + vertex 1.03614 1.88574 2.60131 + endloop + endfacet + facet normal 0.490688 0.0432919 0.870259 + outer loop + vertex 1.03614 1.88574 2.60131 + vertex 1.03257 1.88333 2.60344 + vertex 1.03626 1.88079 2.60148 + endloop + endfacet + facet normal 0.518503 0.0433699 0.853975 + outer loop + vertex 1.03626 1.88079 2.60148 + vertex 1.0393 1.88379 2.59949 + vertex 1.03614 1.88574 2.60131 + endloop + endfacet + facet normal 0.525462 0.0337484 0.850147 + outer loop + vertex 1.03959 1.87869 2.59951 + vertex 1.0393 1.88379 2.59949 + vertex 1.03626 1.88079 2.60148 + endloop + endfacet + facet normal 0.497417 0.056621 0.865662 + outer loop + vertex 1.03257 1.88333 2.60344 + vertex 1.03329 1.87781 2.60339 + vertex 1.03626 1.88079 2.60148 + endloop + endfacet + facet normal 0.509436 0.0407354 0.859544 + outer loop + vertex 1.03626 1.88079 2.60148 + vertex 1.03329 1.87781 2.60339 + vertex 1.03678 1.8757 2.60142 + endloop + endfacet + facet normal 0.476553 0.053793 0.877499 + outer loop + vertex 1.03329 1.87781 2.60339 + vertex 1.03257 1.88333 2.60344 + vertex 1.02968 1.8798 2.60522 + endloop + endfacet + facet normal 0.480087 0.062478 0.874993 + outer loop + vertex 1.03028 1.87487 2.60525 + vertex 1.03329 1.87781 2.60339 + vertex 1.02968 1.8798 2.60522 + endloop + endfacet + facet normal 0.459562 0.0600484 0.886114 + outer loop + vertex 1.02968 1.8798 2.60522 + vertex 1.02667 1.87692 2.60698 + vertex 1.03028 1.87487 2.60525 + endloop + endfacet + facet normal 0.461568 0.0647431 0.884739 + outer loop + vertex 1.02667 1.87692 2.60698 + vertex 1.02713 1.87194 2.6071 + vertex 1.03028 1.87487 2.60525 + endloop + endfacet + facet normal 0.465414 0.0595575 0.883087 + outer loop + vertex 1.03028 1.87487 2.60525 + vertex 1.02713 1.87194 2.6071 + vertex 1.03049 1.87 2.60547 + endloop + endfacet + facet normal 0.496594 0.0601129 0.865899 + outer loop + vertex 1.03049 1.87 2.60547 + vertex 1.034 1.87226 2.6033 + vertex 1.03028 1.87487 2.60525 + endloop + endfacet + facet normal 0.498074 0.0571886 0.865247 + outer loop + vertex 1.0331 1.86786 2.60411 + vertex 1.034 1.87226 2.6033 + vertex 1.03049 1.87 2.60547 + endloop + endfacet + facet normal 0.496769 0.0550265 0.866137 + outer loop + vertex 1.03055 1.86527 2.60573 + vertex 1.0331 1.86786 2.60411 + vertex 1.03049 1.87 2.60547 + endloop + endfacet + facet normal 0.471783 0.0554502 0.879969 + outer loop + vertex 1.03049 1.87 2.60547 + vertex 1.02734 1.86702 2.60734 + vertex 1.03055 1.86527 2.60573 + endloop + endfacet + facet normal 0.473384 0.0594328 0.878849 + outer loop + vertex 1.02734 1.86702 2.60734 + vertex 1.02748 1.86202 2.60761 + vertex 1.03055 1.86527 2.60573 + endloop + endfacet + facet normal 0.482925 0.0478235 0.874355 + outer loop + vertex 1.03055 1.86527 2.60573 + vertex 1.02748 1.86202 2.60761 + vertex 1.03078 1.86037 2.60587 + endloop + endfacet + facet normal 0.510631 0.0486353 0.858423 + outer loop + vertex 1.03078 1.86037 2.60587 + vertex 1.03369 1.86372 2.60395 + vertex 1.03055 1.86527 2.60573 + endloop + endfacet + facet normal 0.520294 0.0372337 0.853175 + outer loop + vertex 1.034 1.85873 2.60398 + vertex 1.03369 1.86372 2.60395 + vertex 1.03078 1.86037 2.60587 + endloop + endfacet + facet normal 0.522967 0.0447987 0.851175 + outer loop + vertex 1.031 1.85532 2.606 + vertex 1.034 1.85873 2.60398 + vertex 1.03078 1.86037 2.60587 + endloop + endfacet + facet normal 0.496638 0.0440532 0.866839 + outer loop + vertex 1.03078 1.86037 2.60587 + vertex 1.0277 1.85695 2.60781 + vertex 1.031 1.85532 2.606 + endloop + endfacet + facet normal 0.499741 0.0529044 0.864557 + outer loop + vertex 1.0277 1.85695 2.60781 + vertex 1.02807 1.852 2.6079 + vertex 1.031 1.85532 2.606 + endloop + endfacet + facet normal 0.511488 0.0390206 0.858404 + outer loop + vertex 1.031 1.85532 2.606 + vertex 1.02807 1.852 2.6079 + vertex 1.03121 1.85049 2.6061 + endloop + endfacet + facet normal 0.533188 0.0397047 0.845065 + outer loop + vertex 1.03121 1.85049 2.6061 + vertex 1.03416 1.85369 2.60409 + vertex 1.031 1.85532 2.606 + endloop + endfacet + facet normal 0.539214 0.0319662 0.841562 + outer loop + vertex 1.03421 1.84874 2.60424 + vertex 1.03416 1.85369 2.60409 + vertex 1.03121 1.85049 2.6061 + endloop + endfacet + facet normal 0.514223 0.0471192 0.856361 + outer loop + vertex 1.02807 1.852 2.6079 + vertex 1.02868 1.84794 2.60776 + vertex 1.03121 1.85049 2.6061 + endloop + endfacet + facet normal 0.525381 0.0320436 0.850264 + outer loop + vertex 1.03121 1.85049 2.6061 + vertex 1.02868 1.84794 2.60776 + vertex 1.03118 1.84582 2.60629 + endloop + endfacet + facet normal 0.531375 0.0345957 0.84643 + outer loop + vertex 1.03416 1.85369 2.60409 + vertex 1.034 1.85873 2.60398 + vertex 1.031 1.85532 2.606 + endloop + endfacet + facet normal 0.486081 0.0565278 0.872084 + outer loop + vertex 1.02748 1.86202 2.60761 + vertex 1.0277 1.85695 2.60781 + vertex 1.03078 1.86037 2.60587 + endloop + endfacet + facet normal 0.50783 0.0406194 0.860499 + outer loop + vertex 1.03369 1.86372 2.60395 + vertex 1.0331 1.86786 2.60411 + vertex 1.03055 1.86527 2.60573 + endloop + endfacet + facet normal 0.466621 0.0623406 0.882257 + outer loop + vertex 1.02713 1.87194 2.6071 + vertex 1.02734 1.86702 2.60734 + vertex 1.03049 1.87 2.60547 + endloop + endfacet + facet normal 0.452679 0.0690132 0.888999 + outer loop + vertex 1.02604 1.88205 2.6069 + vertex 1.02667 1.87692 2.60698 + vertex 1.02968 1.8798 2.60522 + endloop + endfacet + facet normal 0.450264 0.0638944 0.890607 + outer loop + vertex 1.02968 1.8798 2.60522 + vertex 1.02907 1.88379 2.60525 + vertex 1.02604 1.88205 2.6069 + endloop + endfacet + facet normal 0.446141 0.0723864 0.89203 + outer loop + vertex 1.02701 1.88601 2.6061 + vertex 1.02604 1.88205 2.6069 + vertex 1.02907 1.88379 2.60525 + endloop + endfacet + facet normal 0.446929 0.0733006 0.891561 + outer loop + vertex 1.02907 1.88379 2.60525 + vertex 1.03007 1.88799 2.6044 + vertex 1.02701 1.88601 2.6061 + endloop + endfacet + facet normal 0.443155 0.0802518 0.892846 + outer loop + vertex 1.02701 1.88601 2.6061 + vertex 1.03007 1.88799 2.6044 + vertex 1.02637 1.89007 2.60605 + endloop + endfacet + facet normal 0.432748 0.078682 0.898075 + outer loop + vertex 1.02637 1.89007 2.60605 + vertex 1.02359 1.88632 2.60772 + vertex 1.02701 1.88601 2.6061 + endloop + endfacet + facet normal 0.440188 0.0733693 0.894903 + outer loop + vertex 1.03007 1.88799 2.6044 + vertex 1.02936 1.89337 2.60431 + vertex 1.02637 1.89007 2.60605 + endloop + endfacet + facet normal 0.433089 0.0812775 0.897679 + outer loop + vertex 1.02637 1.89007 2.60605 + vertex 1.02936 1.89337 2.60431 + vertex 1.02577 1.8951 2.60589 + endloop + endfacet + facet normal 0.413674 0.0792701 0.906968 + outer loop + vertex 1.02577 1.8951 2.60589 + vertex 1.02258 1.89184 2.60763 + vertex 1.02637 1.89007 2.60605 + endloop + endfacet + facet normal 0.431237 0.0762018 0.899015 + outer loop + vertex 1.02936 1.89337 2.60431 + vertex 1.02887 1.89847 2.60411 + vertex 1.02577 1.8951 2.60589 + endloop + endfacet + facet normal 0.42568 0.0824215 0.901112 + outer loop + vertex 1.02577 1.8951 2.60589 + vertex 1.02887 1.89847 2.60411 + vertex 1.0253 1.90004 2.60565 + endloop + endfacet + facet normal 0.447328 0.0742496 0.891283 + outer loop + vertex 1.03007 1.88799 2.6044 + vertex 1.03285 1.89192 2.60268 + vertex 1.02936 1.89337 2.60431 + endloop + endfacet + facet normal 0.456452 0.0660495 0.887293 + outer loop + vertex 1.03352 1.8878 2.60264 + vertex 1.03285 1.89192 2.60268 + vertex 1.03007 1.88799 2.6044 + endloop + endfacet + facet normal 0.456397 0.0617283 0.887632 + outer loop + vertex 1.03007 1.88799 2.6044 + vertex 1.03257 1.88333 2.60344 + vertex 1.03352 1.8878 2.60264 + endloop + endfacet + facet normal 0.464834 0.0672417 0.882841 + outer loop + vertex 1.02907 1.88379 2.60525 + vertex 1.03257 1.88333 2.60344 + vertex 1.03007 1.88799 2.6044 + endloop + endfacet + facet normal 0.432677 0.0769352 0.89826 + outer loop + vertex 1.02701 1.88601 2.6061 + vertex 1.02359 1.88632 2.60772 + vertex 1.02604 1.88205 2.6069 + endloop + endfacet + facet normal 0.443596 0.0679744 0.893646 + outer loop + vertex 1.02667 1.87692 2.60698 + vertex 1.02604 1.88205 2.6069 + vertex 1.02284 1.87894 2.60873 + endloop + endfacet + facet normal 0.443603 0.0679931 0.89364 + outer loop + vertex 1.02359 1.87367 2.60876 + vertex 1.02667 1.87692 2.60698 + vertex 1.02284 1.87894 2.60873 + endloop + endfacet + facet normal 0.432937 0.0665185 0.898966 + outer loop + vertex 1.02359 1.87367 2.60876 + vertex 1.02284 1.87894 2.60873 + vertex 1.01997 1.87509 2.6104 + endloop + endfacet + facet normal 0.434153 0.0706704 0.898063 + outer loop + vertex 1.02042 1.87029 2.61056 + vertex 1.02359 1.87367 2.60876 + vertex 1.01997 1.87509 2.6104 + endloop + endfacet + facet normal 0.416291 0.0692942 0.906587 + outer loop + vertex 1.01997 1.87509 2.6104 + vertex 1.0168 1.8719 2.6121 + vertex 1.02042 1.87029 2.61056 + endloop + endfacet + facet normal 0.43951 0.0645111 0.895918 + outer loop + vertex 1.02393 1.86869 2.60895 + vertex 1.02359 1.87367 2.60876 + vertex 1.02042 1.87029 2.61056 + endloop + endfacet + facet normal 0.440802 0.068272 0.895004 + outer loop + vertex 1.02067 1.86536 2.61081 + vertex 1.02393 1.86869 2.60895 + vertex 1.02042 1.87029 2.61056 + endloop + endfacet + facet normal 0.429795 0.0679957 0.900363 + outer loop + vertex 1.02042 1.87029 2.61056 + vertex 1.01709 1.86708 2.61239 + vertex 1.02067 1.86536 2.61081 + endloop + endfacet + facet normal 0.444142 0.0642393 0.893651 + outer loop + vertex 1.0241 1.86369 2.60922 + vertex 1.02393 1.86869 2.60895 + vertex 1.02067 1.86536 2.61081 + endloop + endfacet + facet normal 0.445377 0.0675952 0.892788 + outer loop + vertex 1.02091 1.86037 2.61107 + vertex 1.0241 1.86369 2.60922 + vertex 1.02067 1.86536 2.61081 + endloop + endfacet + facet normal 0.44285 0.0675345 0.894049 + outer loop + vertex 1.02067 1.86536 2.61081 + vertex 1.01749 1.8621 2.61263 + vertex 1.02091 1.86037 2.61107 + endloop + endfacet + facet normal 0.448566 0.0637972 0.89147 + outer loop + vertex 1.0243 1.85864 2.60948 + vertex 1.0241 1.86369 2.60922 + vertex 1.02091 1.86037 2.61107 + endloop + endfacet + facet normal 0.449451 0.0660893 0.890857 + outer loop + vertex 1.02131 1.8555 2.61123 + vertex 1.0243 1.85864 2.60948 + vertex 1.02091 1.86037 2.61107 + endloop + endfacet + facet normal 0.448881 0.0660521 0.891147 + outer loop + vertex 1.02091 1.86037 2.61107 + vertex 1.018 1.85712 2.61277 + vertex 1.02131 1.8555 2.61123 + endloop + endfacet + facet normal 0.449259 0.0670766 0.89088 + outer loop + vertex 1.018 1.85712 2.61277 + vertex 1.01886 1.85285 2.61266 + vertex 1.02131 1.8555 2.61123 + endloop + endfacet + facet normal 0.452446 0.0633982 0.889535 + outer loop + vertex 1.02131 1.8555 2.61123 + vertex 1.01886 1.85285 2.61266 + vertex 1.02171 1.85074 2.61136 + endloop + endfacet + facet normal 0.454887 0.063564 0.888278 + outer loop + vertex 1.02171 1.85074 2.61136 + vertex 1.02467 1.85361 2.60964 + vertex 1.02131 1.8555 2.61123 + endloop + endfacet + facet normal 0.462108 0.0542395 0.885163 + outer loop + vertex 1.02529 1.84832 2.60964 + vertex 1.02467 1.85361 2.60964 + vertex 1.02171 1.85074 2.61136 + endloop + endfacet + facet normal 0.465573 0.0609839 0.882906 + outer loop + vertex 1.02215 1.8467 2.61141 + vertex 1.02529 1.84832 2.60964 + vertex 1.02171 1.85074 2.61136 + endloop + endfacet + facet normal 0.454567 0.0598475 0.8887 + outer loop + vertex 1.02171 1.85074 2.61136 + vertex 1.01829 1.84779 2.61331 + vertex 1.02215 1.8467 2.61141 + endloop + endfacet + facet normal 0.453949 0.0567748 0.889217 + outer loop + vertex 1.02215 1.8467 2.61141 + vertex 1.01829 1.84779 2.61331 + vertex 1.02117 1.84254 2.61218 + endloop + endfacet + facet normal 0.467102 0.0524555 0.882646 + outer loop + vertex 1.02215 1.8467 2.61141 + vertex 1.02117 1.84254 2.61218 + vertex 1.02425 1.84425 2.61045 + endloop + endfacet + facet normal 0.470672 0.0445463 0.881183 + outer loop + vertex 1.02481 1.8402 2.61035 + vertex 1.02425 1.84425 2.61045 + vertex 1.02117 1.84254 2.61218 + endloop + endfacet + facet normal 0.476092 0.0557529 0.877626 + outer loop + vertex 1.02117 1.84254 2.61218 + vertex 1.02192 1.83718 2.61211 + vertex 1.02481 1.8402 2.61035 + endloop + endfacet + facet normal 0.485015 0.0447208 0.873362 + outer loop + vertex 1.02481 1.8402 2.61035 + vertex 1.02192 1.83718 2.61211 + vertex 1.02529 1.83523 2.61034 + endloop + endfacet + facet normal 0.508922 0.0470754 0.859524 + outer loop + vertex 1.02529 1.83523 2.61034 + vertex 1.0282 1.83816 2.60845 + vertex 1.02481 1.8402 2.61035 + endloop + endfacet + facet normal 0.517522 0.0355916 0.85493 + outer loop + vertex 1.02862 1.83297 2.60842 + vertex 1.0282 1.83816 2.60845 + vertex 1.02529 1.83523 2.61034 + endloop + endfacet + facet normal 0.520909 0.0426117 0.852548 + outer loop + vertex 1.02557 1.83009 2.61042 + vertex 1.02862 1.83297 2.60842 + vertex 1.02529 1.83523 2.61034 + endloop + endfacet + facet normal 0.497297 0.0415337 0.866585 + outer loop + vertex 1.02529 1.83523 2.61034 + vertex 1.02226 1.83217 2.61222 + vertex 1.02557 1.83009 2.61042 + endloop + endfacet + facet normal 0.500458 0.0484839 0.864402 + outer loop + vertex 1.02226 1.83217 2.61222 + vertex 1.02239 1.8271 2.61243 + vertex 1.02557 1.83009 2.61042 + endloop + endfacet + facet normal 0.506299 0.040261 0.861418 + outer loop + vertex 1.02557 1.83009 2.61042 + vertex 1.02239 1.8271 2.61243 + vertex 1.02557 1.82504 2.61066 + endloop + endfacet + facet normal 0.530602 0.0395164 0.8467 + outer loop + vertex 1.02557 1.82504 2.61066 + vertex 1.02908 1.8273 2.60835 + vertex 1.02557 1.83009 2.61042 + endloop + endfacet + facet normal 0.53242 0.035692 0.845727 + outer loop + vertex 1.02807 1.82279 2.60918 + vertex 1.02908 1.8273 2.60835 + vertex 1.02557 1.82504 2.61066 + endloop + endfacet + facet normal 0.532179 0.0353128 0.845895 + outer loop + vertex 1.02561 1.82024 2.61083 + vertex 1.02807 1.82279 2.60918 + vertex 1.02557 1.82504 2.61066 + endloop + endfacet + facet normal 0.514498 0.0355285 0.856755 + outer loop + vertex 1.02557 1.82504 2.61066 + vertex 1.02252 1.82204 2.61261 + vertex 1.02561 1.82024 2.61083 + endloop + endfacet + facet normal 0.51676 0.0410126 0.855147 + outer loop + vertex 1.02252 1.82204 2.61261 + vertex 1.02287 1.81709 2.61264 + vertex 1.02561 1.82024 2.61083 + endloop + endfacet + facet normal 0.525551 0.0305008 0.850215 + outer loop + vertex 1.02561 1.82024 2.61083 + vertex 1.02287 1.81709 2.61264 + vertex 1.02593 1.81557 2.6108 + endloop + endfacet + facet normal 0.53682 0.0290874 0.843195 + outer loop + vertex 1.02863 1.81863 2.60897 + vertex 1.02807 1.82279 2.60918 + vertex 1.02561 1.82024 2.61083 + endloop + endfacet + facet normal 0.508139 0.0441805 0.860141 + outer loop + vertex 1.02239 1.8271 2.61243 + vertex 1.02252 1.82204 2.61261 + vertex 1.02557 1.82504 2.61066 + endloop + endfacet + facet normal 0.485037 0.0440515 0.873383 + outer loop + vertex 1.02252 1.82204 2.61261 + vertex 1.02239 1.8271 2.61243 + vertex 1.01923 1.82379 2.61436 + endloop + endfacet + facet normal 0.48679 0.0485476 0.872169 + outer loop + vertex 1.01956 1.81864 2.61446 + vertex 1.02252 1.82204 2.61261 + vertex 1.01923 1.82379 2.61436 + endloop + endfacet + facet normal 0.470803 0.047699 0.880948 + outer loop + vertex 1.01956 1.81864 2.61446 + vertex 1.01923 1.82379 2.61436 + vertex 1.01616 1.8204 2.61618 + endloop + endfacet + facet normal 0.465956 0.053293 0.883201 + outer loop + vertex 1.01616 1.8204 2.61618 + vertex 1.01923 1.82379 2.61436 + vertex 1.01589 1.82551 2.61601 + endloop + endfacet + facet normal 0.459033 0.0530483 0.886834 + outer loop + vertex 1.01589 1.82551 2.61601 + vertex 1.01277 1.82215 2.61783 + vertex 1.01616 1.8204 2.61618 + endloop + endfacet + facet normal 0.459427 0.0540597 0.886569 + outer loop + vertex 1.01277 1.82215 2.61783 + vertex 1.01328 1.81698 2.61788 + vertex 1.01616 1.8204 2.61618 + endloop + endfacet + facet normal 0.462029 0.0512843 0.885381 + outer loop + vertex 1.01616 1.8204 2.61618 + vertex 1.01328 1.81698 2.61788 + vertex 1.01673 1.81539 2.61617 + endloop + endfacet + facet normal 0.447086 0.0528924 0.892926 + outer loop + vertex 1.01328 1.81698 2.61788 + vertex 1.01277 1.82215 2.61783 + vertex 1.0097 1.81869 2.61957 + endloop + endfacet + facet normal 0.445356 0.0548 0.893675 + outer loop + vertex 1.0097 1.81869 2.61957 + vertex 1.01277 1.82215 2.61783 + vertex 1.00936 1.82389 2.61942 + endloop + endfacet + facet normal 0.445058 0.0540388 0.89387 + outer loop + vertex 1.01277 1.82215 2.61783 + vertex 1.01257 1.82725 2.61762 + vertex 1.00936 1.82389 2.61942 + endloop + endfacet + facet normal 0.457988 0.0542722 0.8873 + outer loop + vertex 1.01257 1.82725 2.61762 + vertex 1.01277 1.82215 2.61783 + vertex 1.01589 1.82551 2.61601 + endloop + endfacet + facet normal 0.458519 0.0556182 0.886942 + outer loop + vertex 1.01579 1.83054 2.61575 + vertex 1.01257 1.82725 2.61762 + vertex 1.01589 1.82551 2.61601 + endloop + endfacet + facet normal 0.462366 0.0555962 0.884944 + outer loop + vertex 1.01589 1.82551 2.61601 + vertex 1.0191 1.82888 2.61413 + vertex 1.01579 1.83054 2.61575 + endloop + endfacet + facet normal 0.462311 0.055449 0.884982 + outer loop + vertex 1.0191 1.82888 2.61413 + vertex 1.01894 1.83386 2.61389 + vertex 1.01579 1.83054 2.61575 + endloop + endfacet + facet normal 0.459439 0.0588909 0.886255 + outer loop + vertex 1.01579 1.83054 2.61575 + vertex 1.01894 1.83386 2.61389 + vertex 1.0156 1.83543 2.61552 + endloop + endfacet + facet normal 0.455574 0.0588344 0.888252 + outer loop + vertex 1.0156 1.83543 2.61552 + vertex 1.01243 1.83222 2.61736 + vertex 1.01579 1.83054 2.61575 + endloop + endfacet + facet normal 0.458853 0.0572112 0.886669 + outer loop + vertex 1.01894 1.83386 2.61389 + vertex 1.01854 1.83869 2.61379 + vertex 1.0156 1.83543 2.61552 + endloop + endfacet + facet normal 0.455663 0.0608376 0.888071 + outer loop + vertex 1.0156 1.83543 2.61552 + vertex 1.01854 1.83869 2.61379 + vertex 1.01521 1.84011 2.6154 + endloop + endfacet + facet normal 0.445248 0.0601306 0.893386 + outer loop + vertex 1.01521 1.84011 2.6154 + vertex 1.0121 1.83711 2.61715 + vertex 1.0156 1.83543 2.61552 + endloop + endfacet + facet normal 0.454593 0.0574756 0.888843 + outer loop + vertex 1.01854 1.83869 2.61379 + vertex 1.01771 1.8428 2.61395 + vertex 1.01521 1.84011 2.6154 + endloop + endfacet + facet normal 0.449144 0.0638099 0.891178 + outer loop + vertex 1.01521 1.84011 2.6154 + vertex 1.01771 1.8428 2.61395 + vertex 1.01483 1.8447 2.61527 + endloop + endfacet + facet normal 0.432576 0.0626422 0.899419 + outer loop + vertex 1.01483 1.8447 2.61527 + vertex 1.01174 1.84184 2.61695 + vertex 1.01521 1.84011 2.6154 + endloop + endfacet + facet normal 0.448214 0.0619853 0.891775 + outer loop + vertex 1.01771 1.8428 2.61395 + vertex 1.01829 1.84779 2.61331 + vertex 1.01483 1.8447 2.61527 + endloop + endfacet + facet normal 0.446498 0.0643456 0.892468 + outer loop + vertex 1.01437 1.84874 2.6152 + vertex 1.01483 1.8447 2.61527 + vertex 1.01829 1.84779 2.61331 + endloop + endfacet + facet normal 0.447002 0.0673989 0.89199 + outer loop + vertex 1.01437 1.84874 2.6152 + vertex 1.01829 1.84779 2.61331 + vertex 1.01535 1.85313 2.61438 + endloop + endfacet + facet normal 0.442993 0.0647487 0.894184 + outer loop + vertex 1.01535 1.85313 2.61438 + vertex 1.01829 1.84779 2.61331 + vertex 1.01886 1.85285 2.61266 + endloop + endfacet + facet normal 0.458835 0.0584092 0.8866 + outer loop + vertex 1.01854 1.83869 2.61379 + vertex 1.02117 1.84254 2.61218 + vertex 1.01771 1.8428 2.61395 + endloop + endfacet + facet normal 0.465129 0.0576728 0.883362 + outer loop + vertex 1.01894 1.83386 2.61389 + vertex 1.02192 1.83718 2.61211 + vertex 1.01854 1.83869 2.61379 + endloop + endfacet + facet normal 0.470185 0.0518973 0.88104 + outer loop + vertex 1.02226 1.83217 2.61222 + vertex 1.02192 1.83718 2.61211 + vertex 1.01894 1.83386 2.61389 + endloop + endfacet + facet normal 0.471549 0.0555064 0.880091 + outer loop + vertex 1.0191 1.82888 2.61413 + vertex 1.02226 1.83217 2.61222 + vertex 1.01894 1.83386 2.61389 + endloop + endfacet + facet normal 0.455676 0.0591035 0.888181 + outer loop + vertex 1.01243 1.83222 2.61736 + vertex 1.01257 1.82725 2.61762 + vertex 1.01579 1.83054 2.61575 + endloop + endfacet + facet normal 0.465424 0.0519113 0.883564 + outer loop + vertex 1.01923 1.82379 2.61436 + vertex 1.0191 1.82888 2.61413 + vertex 1.01589 1.82551 2.61601 + endloop + endfacet + facet normal 0.478673 0.0519239 0.876457 + outer loop + vertex 1.01923 1.82379 2.61436 + vertex 1.02239 1.8271 2.61243 + vertex 1.0191 1.82888 2.61413 + endloop + endfacet + facet normal 0.477283 0.0484343 0.877414 + outer loop + vertex 1.02239 1.8271 2.61243 + vertex 1.02226 1.83217 2.61222 + vertex 1.0191 1.82888 2.61413 + endloop + endfacet + facet normal 0.527218 0.0335216 0.849069 + outer loop + vertex 1.02908 1.8273 2.60835 + vertex 1.02862 1.83297 2.60842 + vertex 1.02557 1.83009 2.61042 + endloop + endfacet + facet normal 0.488502 0.0529128 0.870957 + outer loop + vertex 1.02192 1.83718 2.61211 + vertex 1.02226 1.83217 2.61222 + vertex 1.02529 1.83523 2.61034 + endloop + endfacet + facet normal 0.463913 0.0539514 0.884236 + outer loop + vertex 1.02192 1.83718 2.61211 + vertex 1.02117 1.84254 2.61218 + vertex 1.01854 1.83869 2.61379 + endloop + endfacet + facet normal 0.494877 0.0482088 0.867625 + outer loop + vertex 1.02425 1.84425 2.61045 + vertex 1.02481 1.8402 2.61035 + vertex 1.02767 1.84361 2.60853 + endloop + endfacet + facet normal 0.494456 0.0446695 0.868054 + outer loop + vertex 1.02425 1.84425 2.61045 + vertex 1.02767 1.84361 2.60853 + vertex 1.02529 1.84832 2.60964 + endloop + endfacet + facet normal 0.488945 0.0411128 0.871345 + outer loop + vertex 1.02529 1.84832 2.60964 + vertex 1.02767 1.84361 2.60853 + vertex 1.02868 1.84794 2.60776 + endloop + endfacet + facet normal 0.48906 0.0428565 0.871197 + outer loop + vertex 1.02868 1.84794 2.60776 + vertex 1.02807 1.852 2.6079 + vertex 1.02529 1.84832 2.60964 + endloop + endfacet + facet normal 0.504696 0.0372457 0.862493 + outer loop + vertex 1.0282 1.83816 2.60845 + vertex 1.02767 1.84361 2.60853 + vertex 1.02481 1.8402 2.61035 + endloop + endfacet + facet normal 0.458888 0.0600699 0.886461 + outer loop + vertex 1.01829 1.84779 2.61331 + vertex 1.01771 1.8428 2.61395 + vertex 1.02117 1.84254 2.61218 + endloop + endfacet + facet normal 0.468539 0.0540243 0.881789 + outer loop + vertex 1.02425 1.84425 2.61045 + vertex 1.02529 1.84832 2.60964 + vertex 1.02215 1.8467 2.61141 + endloop + endfacet + facet normal 0.4759 0.0558675 0.877723 + outer loop + vertex 1.02529 1.84832 2.60964 + vertex 1.02807 1.852 2.6079 + vertex 1.02467 1.85361 2.60964 + endloop + endfacet + facet normal 0.474313 0.0512611 0.878863 + outer loop + vertex 1.02807 1.852 2.6079 + vertex 1.0277 1.85695 2.60781 + vertex 1.02467 1.85361 2.60964 + endloop + endfacet + facet normal 0.465381 0.0616114 0.882963 + outer loop + vertex 1.02467 1.85361 2.60964 + vertex 1.0277 1.85695 2.60781 + vertex 1.0243 1.85864 2.60948 + endloop + endfacet + facet normal 0.463316 0.0560382 0.884419 + outer loop + vertex 1.0277 1.85695 2.60781 + vertex 1.02748 1.86202 2.60761 + vertex 1.0243 1.85864 2.60948 + endloop + endfacet + facet normal 0.452284 0.0631163 0.889638 + outer loop + vertex 1.01886 1.85285 2.61266 + vertex 1.01829 1.84779 2.61331 + vertex 1.02171 1.85074 2.61136 + endloop + endfacet + facet normal 0.453775 0.0609631 0.889029 + outer loop + vertex 1.02467 1.85361 2.60964 + vertex 1.0243 1.85864 2.60948 + vertex 1.02131 1.8555 2.61123 + endloop + endfacet + facet normal 0.456673 0.0639089 0.887336 + outer loop + vertex 1.0243 1.85864 2.60948 + vertex 1.02748 1.86202 2.60761 + vertex 1.0241 1.86369 2.60922 + endloop + endfacet + facet normal 0.455014 0.0594349 0.888498 + outer loop + vertex 1.02748 1.86202 2.60761 + vertex 1.02734 1.86702 2.60734 + vertex 1.0241 1.86369 2.60922 + endloop + endfacet + facet normal 0.451025 0.0642799 0.890194 + outer loop + vertex 1.0241 1.86369 2.60922 + vertex 1.02734 1.86702 2.60734 + vertex 1.02393 1.86869 2.60895 + endloop + endfacet + facet normal 0.4502 0.0620545 0.890769 + outer loop + vertex 1.02734 1.86702 2.60734 + vertex 1.02713 1.87194 2.6071 + vertex 1.02393 1.86869 2.60895 + endloop + endfacet + facet normal 0.447841 0.0649368 0.891752 + outer loop + vertex 1.02393 1.86869 2.60895 + vertex 1.02713 1.87194 2.6071 + vertex 1.02359 1.87367 2.60876 + endloop + endfacet + facet normal 0.447347 0.0635953 0.892097 + outer loop + vertex 1.02713 1.87194 2.6071 + vertex 1.02667 1.87692 2.60698 + vertex 1.02359 1.87367 2.60876 + endloop + endfacet + facet normal 0.490633 0.0485453 0.870013 + outer loop + vertex 1.034 1.87226 2.6033 + vertex 1.03329 1.87781 2.60339 + vertex 1.03028 1.87487 2.60525 + endloop + endfacet + facet normal 0.464756 0.0661873 0.882961 + outer loop + vertex 1.02907 1.88379 2.60525 + vertex 1.02968 1.8798 2.60522 + vertex 1.03257 1.88333 2.60344 + endloop + endfacet + facet normal 0.515781 0.0371735 0.855914 + outer loop + vertex 1.0393 1.88379 2.59949 + vertex 1.0392 1.88876 2.59933 + vertex 1.03614 1.88574 2.60131 + endloop + endfacet + facet normal 0.52613 0.0455232 0.849185 + outer loop + vertex 1.0392 1.88876 2.59933 + vertex 1.04224 1.892 2.59727 + vertex 1.0391 1.89373 2.59913 + endloop + endfacet + facet normal 0.471134 0.0685035 0.879398 + outer loop + vertex 1.03285 1.89192 2.60268 + vertex 1.03352 1.8878 2.60264 + vertex 1.0361 1.89048 2.60105 + endloop + endfacet + facet normal 0.446545 0.0716977 0.891884 + outer loop + vertex 1.03285 1.89192 2.60268 + vertex 1.0324 1.89687 2.60251 + vertex 1.02936 1.89337 2.60431 + endloop + endfacet + facet normal 0.441635 0.0769912 0.893886 + outer loop + vertex 1.02936 1.89337 2.60431 + vertex 1.0324 1.89687 2.60251 + vertex 1.02887 1.89847 2.60411 + endloop + endfacet + facet normal 0.440821 0.074585 0.894491 + outer loop + vertex 1.0324 1.89687 2.60251 + vertex 1.03201 1.90195 2.60228 + vertex 1.02887 1.89847 2.60411 + endloop + endfacet + facet normal 0.436772 0.0790661 0.896091 + outer loop + vertex 1.02887 1.89847 2.60411 + vertex 1.03201 1.90195 2.60228 + vertex 1.02834 1.90351 2.60392 + endloop + endfacet + facet normal 0.486671 0.0527057 0.871994 + outer loop + vertex 1.0391 1.89373 2.59913 + vertex 1.0389 1.89872 2.59894 + vertex 1.03582 1.89532 2.60086 + endloop + endfacet + facet normal 0.512767 0.0531519 0.856881 + outer loop + vertex 1.0391 1.89373 2.59913 + vertex 1.04215 1.89703 2.5971 + vertex 1.0389 1.89872 2.59894 + endloop + endfacet + facet normal 0.509146 0.0432761 0.859591 + outer loop + vertex 1.04215 1.89703 2.5971 + vertex 1.04194 1.902 2.59697 + vertex 1.0389 1.89872 2.59894 + endloop + endfacet + facet normal 0.495943 0.0595443 0.866311 + outer loop + vertex 1.0389 1.89872 2.59894 + vertex 1.04194 1.902 2.59697 + vertex 1.03853 1.90367 2.59881 + endloop + endfacet + facet normal 0.448876 0.0750295 0.890439 + outer loop + vertex 1.03201 1.90195 2.60228 + vertex 1.0324 1.89687 2.60251 + vertex 1.0355 1.90029 2.60065 + endloop + endfacet + facet normal 0.436478 0.0781379 0.896316 + outer loop + vertex 1.03201 1.90195 2.60228 + vertex 1.03167 1.90745 2.60196 + vertex 1.02834 1.90351 2.60392 + endloop + endfacet + facet normal 0.428771 0.0861513 0.899296 + outer loop + vertex 1.02834 1.90351 2.60392 + vertex 1.03167 1.90745 2.60196 + vertex 1.02725 1.90834 2.60398 + endloop + endfacet + facet normal 0.428745 0.0859464 0.899328 + outer loop + vertex 1.0296 1.91239 2.60248 + vertex 1.02725 1.90834 2.60398 + vertex 1.03167 1.90745 2.60196 + endloop + endfacet + facet normal 0.501342 0.0562638 0.863418 + outer loop + vertex 1.04095 1.91198 2.59694 + vertex 1.04152 1.90692 2.59694 + vertex 1.04449 1.90989 2.59502 + endloop + endfacet + facet normal 0.494368 0.0399391 0.868334 + outer loop + vertex 1.04449 1.90989 2.59502 + vertex 1.04401 1.9139 2.59511 + vertex 1.04095 1.91198 2.59694 + endloop + endfacet + facet normal 0.43667 0.0775529 0.896273 + outer loop + vertex 1.03795 1.91231 2.59848 + vertex 1.03847 1.91613 2.59789 + vertex 1.03451 1.91246 2.60014 + endloop + endfacet + facet normal 0.434748 0.0800592 0.896986 + outer loop + vertex 1.03451 1.91246 2.60014 + vertex 1.03847 1.91613 2.59789 + vertex 1.03453 1.91833 2.5996 + endloop + endfacet + facet normal 0.427242 0.0804091 0.900554 + outer loop + vertex 1.03451 1.91246 2.60014 + vertex 1.03453 1.91833 2.5996 + vertex 1.03144 1.91608 2.60127 + endloop + endfacet + facet normal 0.427254 0.0804208 0.900548 + outer loop + vertex 1.03144 1.91608 2.60127 + vertex 1.0296 1.91239 2.60248 + vertex 1.03451 1.91246 2.60014 + endloop + endfacet + facet normal 0.427034 0.0851343 0.900219 + outer loop + vertex 1.03451 1.91246 2.60014 + vertex 1.0296 1.91239 2.60248 + vertex 1.03167 1.90745 2.60196 + endloop + endfacet + facet normal 0.406687 0.0934222 0.908778 + outer loop + vertex 1.02791 1.91705 2.60275 + vertex 1.0296 1.91239 2.60248 + vertex 1.03144 1.91608 2.60127 + endloop + endfacet + facet normal 0.404685 0.0833437 0.91065 + outer loop + vertex 1.03097 1.92027 2.6011 + vertex 1.02791 1.91705 2.60275 + vertex 1.03144 1.91608 2.60127 + endloop + endfacet + facet normal 0.4243 0.0851559 0.901509 + outer loop + vertex 1.03144 1.91608 2.60127 + vertex 1.03453 1.91833 2.5996 + vertex 1.03097 1.92027 2.6011 + endloop + endfacet + facet normal 0.422921 0.0819041 0.902457 + outer loop + vertex 1.03453 1.91833 2.5996 + vertex 1.03419 1.92343 2.5993 + vertex 1.03097 1.92027 2.6011 + endloop + endfacet + facet normal 0.416255 0.090026 0.90478 + outer loop + vertex 1.03097 1.92027 2.6011 + vertex 1.03419 1.92343 2.5993 + vertex 1.0306 1.92505 2.60079 + endloop + endfacet + facet normal 0.389276 0.0886997 0.916841 + outer loop + vertex 1.0306 1.92505 2.60079 + vertex 1.02734 1.92182 2.60249 + vertex 1.03097 1.92027 2.6011 + endloop + endfacet + facet normal 0.415913 0.0890345 0.905035 + outer loop + vertex 1.03419 1.92343 2.5993 + vertex 1.03372 1.92847 2.59902 + vertex 1.0306 1.92505 2.60079 + endloop + endfacet + facet normal 0.399707 0.106636 0.910419 + outer loop + vertex 1.0306 1.92505 2.60079 + vertex 1.03372 1.92847 2.59902 + vertex 1.02997 1.9299 2.6005 + endloop + endfacet + facet normal 0.426034 0.0897148 0.900248 + outer loop + vertex 1.03419 1.92343 2.5993 + vertex 1.03737 1.92678 2.59746 + vertex 1.03372 1.92847 2.59902 + endloop + endfacet + facet normal 0.425935 0.0894313 0.900323 + outer loop + vertex 1.03737 1.92678 2.59746 + vertex 1.03679 1.93179 2.59724 + vertex 1.03372 1.92847 2.59902 + endloop + endfacet + facet normal 0.431659 0.0832601 0.898186 + outer loop + vertex 1.03782 1.92168 2.59772 + vertex 1.03737 1.92678 2.59746 + vertex 1.03419 1.92343 2.5993 + endloop + endfacet + facet normal 0.438725 0.0837084 0.894714 + outer loop + vertex 1.03737 1.92678 2.59746 + vertex 1.03782 1.92168 2.59772 + vertex 1.0409 1.92518 2.59588 + endloop + endfacet + facet normal 0.438099 0.0818567 0.895192 + outer loop + vertex 1.0404 1.93012 2.59568 + vertex 1.03737 1.92678 2.59746 + vertex 1.0409 1.92518 2.59588 + endloop + endfacet + facet normal 0.451561 0.0829494 0.888376 + outer loop + vertex 1.0409 1.92518 2.59588 + vertex 1.04386 1.9286 2.59406 + vertex 1.0404 1.93012 2.59568 + endloop + endfacet + facet normal 0.449318 0.0759653 0.890136 + outer loop + vertex 1.04386 1.9286 2.59406 + vertex 1.04324 1.93349 2.59395 + vertex 1.0404 1.93012 2.59568 + endloop + endfacet + facet normal 0.438609 0.0872105 0.894437 + outer loop + vertex 1.0404 1.93012 2.59568 + vertex 1.04324 1.93349 2.59395 + vertex 1.03972 1.9348 2.59555 + endloop + endfacet + facet normal 0.429513 0.0860243 0.898954 + outer loop + vertex 1.03972 1.9348 2.59555 + vertex 1.03679 1.93179 2.59724 + vertex 1.0404 1.93012 2.59568 + endloop + endfacet + facet normal 0.420683 0.0964077 0.902071 + outer loop + vertex 1.03607 1.93689 2.59703 + vertex 1.03679 1.93179 2.59724 + vertex 1.03972 1.9348 2.59555 + endloop + endfacet + facet normal 0.416147 0.0862921 0.905193 + outer loop + vertex 1.03972 1.9348 2.59555 + vertex 1.03911 1.93862 2.59547 + vertex 1.03607 1.93689 2.59703 + endloop + endfacet + facet normal 0.427511 0.0879985 0.899717 + outer loop + vertex 1.03911 1.93862 2.59547 + vertex 1.03972 1.9348 2.59555 + vertex 1.04216 1.93811 2.59407 + endloop + endfacet + facet normal 0.427362 0.0865113 0.899932 + outer loop + vertex 1.03911 1.93862 2.59547 + vertex 1.04216 1.93811 2.59407 + vertex 1.04021 1.94276 2.59455 + endloop + endfacet + facet normal 0.412135 0.091999 0.906466 + outer loop + vertex 1.03911 1.93862 2.59547 + vertex 1.04021 1.94276 2.59455 + vertex 1.03706 1.94083 2.59618 + endloop + endfacet + facet normal 0.412881 0.0928256 0.906042 + outer loop + vertex 1.03706 1.94083 2.59618 + vertex 1.03607 1.93689 2.59703 + vertex 1.03911 1.93862 2.59547 + endloop + endfacet + facet normal 0.383804 0.102726 0.917683 + outer loop + vertex 1.03706 1.94083 2.59618 + vertex 1.03343 1.94122 2.59765 + vertex 1.03607 1.93689 2.59703 + endloop + endfacet + facet normal 0.428186 0.0869025 0.899503 + outer loop + vertex 1.04021 1.94276 2.59455 + vertex 1.04216 1.93811 2.59407 + vertex 1.04426 1.94188 2.5927 + endloop + endfacet + facet normal 0.427776 0.0840131 0.899972 + outer loop + vertex 1.04426 1.94188 2.5927 + vertex 1.04314 1.94672 2.59279 + vertex 1.04021 1.94276 2.59455 + endloop + endfacet + facet normal 0.416622 0.0941276 0.904194 + outer loop + vertex 1.04021 1.94276 2.59455 + vertex 1.04314 1.94672 2.59279 + vertex 1.03928 1.94842 2.59439 + endloop + endfacet + facet normal 0.436578 0.0797085 0.896128 + outer loop + vertex 1.04324 1.93349 2.59395 + vertex 1.04216 1.93811 2.59407 + vertex 1.03972 1.9348 2.59555 + endloop + endfacet + facet normal 0.406881 0.0947332 0.908556 + outer loop + vertex 1.03679 1.93179 2.59724 + vertex 1.03607 1.93689 2.59703 + vertex 1.03271 1.93387 2.59885 + endloop + endfacet + facet normal 0.411226 0.10569 0.905385 + outer loop + vertex 1.03372 1.92847 2.59902 + vertex 1.03679 1.93179 2.59724 + vertex 1.03271 1.93387 2.59885 + endloop + endfacet + facet normal 0.396547 0.108069 0.911631 + outer loop + vertex 1.03271 1.93387 2.59885 + vertex 1.03607 1.93689 2.59703 + vertex 1.03299 1.9376 2.59829 + endloop + endfacet + facet normal 0.39712 0.111812 0.91093 + outer loop + vertex 1.03343 1.94122 2.59765 + vertex 1.03299 1.9376 2.59829 + vertex 1.03607 1.93689 2.59703 + endloop + endfacet + facet normal 0.464119 0.0692516 0.883062 + outer loop + vertex 1.04434 1.92356 2.5942 + vertex 1.04386 1.9286 2.59406 + vertex 1.0409 1.92518 2.59588 + endloop + endfacet + facet normal 0.430866 0.0898996 0.897927 + outer loop + vertex 1.03679 1.93179 2.59724 + vertex 1.03737 1.92678 2.59746 + vertex 1.0404 1.93012 2.59568 + endloop + endfacet + facet normal 0.445213 0.0766466 0.892138 + outer loop + vertex 1.0409 1.92518 2.59588 + vertex 1.03782 1.92168 2.59772 + vertex 1.04143 1.92014 2.59605 + endloop + endfacet + facet normal 0.43128 0.082227 0.898463 + outer loop + vertex 1.03453 1.91833 2.5996 + vertex 1.03782 1.92168 2.59772 + vertex 1.03419 1.92343 2.5993 + endloop + endfacet + facet normal 0.43419 0.07876 0.897372 + outer loop + vertex 1.03847 1.91613 2.59789 + vertex 1.03782 1.92168 2.59772 + vertex 1.03453 1.91833 2.5996 + endloop + endfacet + facet normal 0.446255 0.0799847 0.891324 + outer loop + vertex 1.03782 1.92168 2.59772 + vertex 1.03847 1.91613 2.59789 + vertex 1.04143 1.92014 2.59605 + endloop + endfacet + facet normal 0.495986 0.0654028 0.865864 + outer loop + vertex 1.04401 1.9139 2.59511 + vertex 1.045 1.91816 2.59422 + vertex 1.042 1.91605 2.59609 + endloop + endfacet + facet normal 0.467302 0.0785738 0.880599 + outer loop + vertex 1.04143 1.92014 2.59605 + vertex 1.04434 1.92356 2.5942 + vertex 1.0409 1.92518 2.59588 + endloop + endfacet + facet normal 0.428834 0.0939168 0.898488 + outer loop + vertex 1.04237 1.95191 2.59261 + vertex 1.04314 1.94672 2.59279 + vertex 1.04604 1.95017 2.59104 + endloop + endfacet + facet normal 0.475859 0.0658613 0.877052 + outer loop + vertex 1.05019 1.94319 2.58944 + vertex 1.04953 1.9485 2.58939 + vertex 1.04671 1.94527 2.59117 + endloop + endfacet + facet normal 0.493532 0.067969 0.867068 + outer loop + vertex 1.05019 1.94319 2.58944 + vertex 1.05285 1.94699 2.58762 + vertex 1.04953 1.9485 2.58939 + endloop + endfacet + facet normal 0.511913 0.0505359 0.857549 + outer loop + vertex 1.05347 1.94293 2.58749 + vertex 1.05285 1.94699 2.58762 + vertex 1.05019 1.94319 2.58944 + endloop + endfacet + facet normal 0.511924 0.0508835 0.857522 + outer loop + vertex 1.05019 1.94319 2.58944 + vertex 1.05248 1.9385 2.58834 + vertex 1.05347 1.94293 2.58749 + endloop + endfacet + facet normal 0.474811 0.0789914 0.876536 + outer loop + vertex 1.04953 1.9485 2.58939 + vertex 1.05241 1.95183 2.58753 + vertex 1.049 1.95354 2.58922 + endloop + endfacet + facet normal 0.471992 0.0711795 0.878725 + outer loop + vertex 1.05241 1.95183 2.58753 + vertex 1.05195 1.95687 2.58737 + vertex 1.049 1.95354 2.58922 + endloop + endfacet + facet normal 0.457042 0.0879178 0.885089 + outer loop + vertex 1.049 1.95354 2.58922 + vertex 1.05195 1.95687 2.58737 + vertex 1.04835 1.95854 2.58907 + endloop + endfacet + facet normal 0.402896 0.111786 0.908393 + outer loop + vertex 1.04112 1.96183 2.59201 + vertex 1.04188 1.9569 2.59228 + vertex 1.04478 1.9599 2.59063 + endloop + endfacet + facet normal 0.427509 0.0901886 0.899501 + outer loop + vertex 1.04546 1.95515 2.59082 + vertex 1.04237 1.95191 2.59261 + vertex 1.04604 1.95017 2.59104 + endloop + endfacet + facet normal 0.415991 0.0922307 0.90468 + outer loop + vertex 1.04314 1.94672 2.59279 + vertex 1.04237 1.95191 2.59261 + vertex 1.03928 1.94842 2.59439 + endloop + endfacet + facet normal 0.403187 0.0920986 0.910471 + outer loop + vertex 1.04021 1.94276 2.59455 + vertex 1.03928 1.94842 2.59439 + vertex 1.03629 1.94494 2.59607 + endloop + endfacet + facet normal 0.407173 0.101152 0.907733 + outer loop + vertex 1.03706 1.94083 2.59618 + vertex 1.04021 1.94276 2.59455 + vertex 1.03629 1.94494 2.59607 + endloop + endfacet + facet normal 0.383485 0.0969684 0.918442 + outer loop + vertex 1.03629 1.94494 2.59607 + vertex 1.03343 1.94122 2.59765 + vertex 1.03706 1.94083 2.59618 + endloop + endfacet + facet normal 0.360968 0.117164 0.925189 + outer loop + vertex 1.03231 1.94648 2.59742 + vertex 1.03343 1.94122 2.59765 + vertex 1.03629 1.94494 2.59607 + endloop + endfacet + facet normal 0.398819 0.10355 0.911165 + outer loop + vertex 1.03372 1.92847 2.59902 + vertex 1.03271 1.93387 2.59885 + vertex 1.02997 1.9299 2.6005 + endloop + endfacet + facet normal 0.366213 0.103157 0.924795 + outer loop + vertex 1.02997 1.9299 2.6005 + vertex 1.02691 1.92646 2.6021 + vertex 1.0306 1.92505 2.60079 + endloop + endfacet + facet normal 0.368939 0.112293 0.922645 + outer loop + vertex 1.02691 1.92646 2.6021 + vertex 1.02734 1.92182 2.60249 + vertex 1.0306 1.92505 2.60079 + endloop + endfacet + facet normal 0.39216 0.0973589 0.91473 + outer loop + vertex 1.02734 1.92182 2.60249 + vertex 1.02791 1.91705 2.60275 + vertex 1.03097 1.92027 2.6011 + endloop + endfacet + facet normal 0.424191 0.0779582 0.902211 + outer loop + vertex 1.02887 1.89847 2.60411 + vertex 1.02834 1.90351 2.60392 + vertex 1.0253 1.90004 2.60565 + endloop + endfacet + facet normal 0.398721 0.080465 0.913535 + outer loop + vertex 1.0253 1.90004 2.60565 + vertex 1.02211 1.89689 2.60733 + vertex 1.02577 1.8951 2.60589 + endloop + endfacet + facet normal 0.403034 0.0916523 0.910584 + outer loop + vertex 1.02211 1.89689 2.60733 + vertex 1.02258 1.89184 2.60763 + vertex 1.02577 1.8951 2.60589 + endloop + endfacet + facet normal 0.41821 0.0919111 0.903689 + outer loop + vertex 1.02258 1.89184 2.60763 + vertex 1.02359 1.88632 2.60772 + vertex 1.02637 1.89007 2.60605 + endloop + endfacet + facet normal 0.441874 0.0831781 0.893213 + outer loop + vertex 1.02359 1.88632 2.60772 + vertex 1.02325 1.88261 2.60823 + vertex 1.02604 1.88205 2.6069 + endloop + endfacet + facet normal 0.440417 0.0719803 0.894903 + outer loop + vertex 1.02284 1.87894 2.60873 + vertex 1.02604 1.88205 2.6069 + vertex 1.02325 1.88261 2.60823 + endloop + endfacet + facet normal 0.426957 0.0720258 0.901399 + outer loop + vertex 1.01942 1.87899 2.61035 + vertex 1.01997 1.87509 2.6104 + vertex 1.02284 1.87894 2.60873 + endloop + endfacet + facet normal 0.390197 0.0670127 0.91829 + outer loop + vertex 1.01997 1.87509 2.6104 + vertex 1.01942 1.87899 2.61035 + vertex 1.01615 1.87672 2.6119 + endloop + endfacet + facet normal 0.309324 0.104998 0.945142 + outer loop + vertex 1.01632 1.88502 2.61092 + vertex 1.01308 1.88067 2.61246 + vertex 1.01718 1.88096 2.61109 + endloop + endfacet + facet normal 0.39817 0.0906453 0.912822 + outer loop + vertex 1.01615 1.87672 2.6119 + vertex 1.0168 1.8719 2.6121 + vertex 1.01997 1.87509 2.6104 + endloop + endfacet + facet normal 0.420006 0.0802036 0.90397 + outer loop + vertex 1.0168 1.8719 2.6121 + vertex 1.01709 1.86708 2.61239 + vertex 1.02042 1.87029 2.61056 + endloop + endfacet + facet normal 0.433646 0.0784958 0.897658 + outer loop + vertex 1.01709 1.86708 2.61239 + vertex 1.01749 1.8621 2.61263 + vertex 1.02067 1.86536 2.61081 + endloop + endfacet + facet normal 0.444254 0.0712105 0.893067 + outer loop + vertex 1.01749 1.8621 2.61263 + vertex 1.018 1.85712 2.61277 + vertex 1.02091 1.86037 2.61107 + endloop + endfacet + facet normal 0.443028 0.0657329 0.894095 + outer loop + vertex 1.01886 1.85285 2.61266 + vertex 1.018 1.85712 2.61277 + vertex 1.01535 1.85313 2.61438 + endloop + endfacet + facet normal 0.414051 0.0775225 0.906947 + outer loop + vertex 1.01437 1.84874 2.6152 + vertex 1.01535 1.85313 2.61438 + vertex 1.01208 1.85099 2.61606 + endloop + endfacet + facet normal 0.310449 0.101988 0.945103 + outer loop + vertex 1.0073 1.85618 2.61719 + vertex 1.00801 1.85073 2.61754 + vertex 1.01138 1.85514 2.61596 + endloop + endfacet + facet normal 0.436067 0.0717791 0.897047 + outer loop + vertex 1.01174 1.84184 2.61695 + vertex 1.0121 1.83711 2.61715 + vertex 1.01521 1.84011 2.6154 + endloop + endfacet + facet normal 0.448099 0.0680082 0.891393 + outer loop + vertex 1.0121 1.83711 2.61715 + vertex 1.01243 1.83222 2.61736 + vertex 1.0156 1.83543 2.61552 + endloop + endfacet + facet normal 0.441502 0.0590844 0.895313 + outer loop + vertex 1.01257 1.82725 2.61762 + vertex 1.01243 1.83222 2.61736 + vertex 1.00921 1.82895 2.61916 + endloop + endfacet + facet normal 0.441279 0.0585089 0.895461 + outer loop + vertex 1.00936 1.82389 2.61942 + vertex 1.01257 1.82725 2.61762 + vertex 1.00921 1.82895 2.61916 + endloop + endfacet + facet normal 0.311657 0.0841826 0.946458 + outer loop + vertex 1.00203 1.82639 2.62202 + vertex 1.00217 1.82141 2.62242 + vertex 1.00584 1.82538 2.62086 + endloop + endfacet + facet normal 0.408843 0.0528864 0.911071 + outer loop + vertex 1.0097 1.81869 2.61957 + vertex 1.00936 1.82389 2.61942 + vertex 1.00605 1.8203 2.62111 + endloop + endfacet + facet normal 0.44816 0.0558474 0.892207 + outer loop + vertex 1.01037 1.8131 2.61958 + vertex 1.01328 1.81698 2.61788 + vertex 1.0097 1.81869 2.61957 + endloop + endfacet + facet normal 0.452298 0.0519292 0.890354 + outer loop + vertex 1.01433 1.81206 2.61763 + vertex 1.01328 1.81698 2.61788 + vertex 1.01037 1.8131 2.61958 + endloop + endfacet + facet normal 0.450237 0.0554296 0.891187 + outer loop + vertex 1.00921 1.80898 2.62042 + vertex 1.01226 1.80835 2.61893 + vertex 1.01037 1.8131 2.61958 + endloop + endfacet + facet normal 0.427321 0.0506019 0.902683 + outer loop + vertex 1.00977 1.80507 2.62038 + vertex 1.00921 1.80898 2.62042 + vertex 1.00606 1.80719 2.62202 + endloop + endfacet + facet normal 0.382821 0.0609926 0.921807 + outer loop + vertex 1.00656 1.81524 2.62123 + vertex 1.00344 1.81135 2.62278 + vertex 1.00717 1.81119 2.62124 + endloop + endfacet + facet normal 0.390201 0.0771172 0.917495 + outer loop + vertex 1.00261 1.80412 2.62374 + vertex 1.00606 1.80719 2.62202 + vertex 1.00286 1.80774 2.62333 + endloop + endfacet + facet normal 0.402936 0.0604289 0.913231 + outer loop + vertex 1.00675 1.80211 2.62205 + vertex 1.00606 1.80719 2.62202 + vertex 1.00261 1.80412 2.62374 + endloop + endfacet + facet normal 0.410775 0.0807799 0.908151 + outer loop + vertex 1.0037 1.79889 2.62371 + vertex 1.00675 1.80211 2.62205 + vertex 1.00261 1.80412 2.62374 + endloop + endfacet + facet normal 0.433144 0.0602248 0.899311 + outer loop + vertex 1.00412 1.79392 2.62385 + vertex 1.00727 1.79716 2.62211 + vertex 1.0037 1.79889 2.62371 + endloop + endfacet + facet normal 0.442081 0.0495362 0.895606 + outer loop + vertex 1.00748 1.79223 2.62228 + vertex 1.00727 1.79716 2.62211 + vertex 1.00412 1.79392 2.62385 + endloop + endfacet + facet normal 0.442427 0.0504322 0.895385 + outer loop + vertex 1.00424 1.78891 2.62407 + vertex 1.00748 1.79223 2.62228 + vertex 1.00412 1.79392 2.62385 + endloop + endfacet + facet normal 0.443809 0.048765 0.894794 + outer loop + vertex 1.00759 1.78724 2.6225 + vertex 1.00748 1.79223 2.62228 + vertex 1.00424 1.78891 2.62407 + endloop + endfacet + facet normal 0.306429 0.0795243 0.948566 + outer loop + vertex 0.996774 1.79651 2.62642 + vertex 0.997011 1.79145 2.62676 + vertex 1.00059 1.7954 2.62528 + endloop + endfacet + facet normal 0.405392 0.0502822 0.912759 + outer loop + vertex 1.00424 1.78891 2.62407 + vertex 1.00412 1.79392 2.62385 + vertex 1.00076 1.79037 2.62553 + endloop + endfacet + facet normal 0.444391 0.0502866 0.89442 + outer loop + vertex 1.00434 1.78384 2.6243 + vertex 1.00759 1.78724 2.6225 + vertex 1.00424 1.78891 2.62407 + endloop + endfacet + facet normal 0.444837 0.0497592 0.894228 + outer loop + vertex 1.00772 1.78222 2.62271 + vertex 1.00759 1.78724 2.6225 + vertex 1.00434 1.78384 2.6243 + endloop + endfacet + facet normal 0.420441 0.0492982 0.905979 + outer loop + vertex 1.00448 1.7788 2.62451 + vertex 1.00434 1.78384 2.6243 + vertex 1.00096 1.78025 2.62607 + endloop + endfacet + facet normal 0.345356 0.0705915 0.935813 + outer loop + vertex 0.997035 1.78636 2.62713 + vertex 0.997169 1.7814 2.62746 + vertex 1.00082 1.78528 2.62582 + endloop + endfacet + facet normal 0.434731 0.029422 0.90008 + outer loop + vertex 1.00478 1.76875 2.62477 + vertex 1.00462 1.77379 2.62468 + vertex 1.00125 1.77042 2.62642 + endloop + endfacet + facet normal 0.447247 0.0297113 0.893917 + outer loop + vertex 1.00478 1.76875 2.62477 + vertex 1.008 1.77215 2.62304 + vertex 1.00462 1.77379 2.62468 + endloop + endfacet + facet normal 0.44625 0.0308893 0.894375 + outer loop + vertex 1.00828 1.76701 2.62308 + vertex 1.008 1.77215 2.62304 + vertex 1.00478 1.76875 2.62477 + endloop + endfacet + facet normal 0.421266 0.0518633 0.905453 + outer loop + vertex 1.00112 1.77533 2.62628 + vertex 1.00448 1.7788 2.62451 + vertex 1.00096 1.78025 2.62607 + endloop + endfacet + facet normal 0.450151 0.0374279 0.892168 + outer loop + vertex 1.008 1.77215 2.62304 + vertex 1.00785 1.77719 2.6229 + vertex 1.00462 1.77379 2.62468 + endloop + endfacet + facet normal 0.444734 0.0494816 0.894295 + outer loop + vertex 1.00448 1.7788 2.62451 + vertex 1.00772 1.78222 2.62271 + vertex 1.00434 1.78384 2.6243 + endloop + endfacet + facet normal 0.482637 0.038553 0.874971 + outer loop + vertex 1.01429 1.77895 2.61936 + vertex 1.01417 1.78396 2.6192 + vertex 1.01103 1.78057 2.62108 + endloop + endfacet + facet normal 0.498742 0.0420863 0.865728 + outer loop + vertex 1.01417 1.78396 2.6192 + vertex 1.01728 1.78725 2.61725 + vertex 1.01406 1.78895 2.61902 + endloop + endfacet + facet normal 0.45706 0.0498046 0.888041 + outer loop + vertex 1.00759 1.78724 2.6225 + vertex 1.00772 1.78222 2.62271 + vertex 1.0109 1.78558 2.62089 + endloop + endfacet + facet normal 0.467451 0.0445845 0.882894 + outer loop + vertex 1.01406 1.78895 2.61902 + vertex 1.01395 1.79388 2.61883 + vertex 1.01079 1.79055 2.62067 + endloop + endfacet + facet normal 0.479224 0.0456837 0.876503 + outer loop + vertex 1.01395 1.79388 2.61883 + vertex 1.01703 1.79713 2.61698 + vertex 1.01375 1.79875 2.61868 + endloop + endfacet + facet normal 0.477928 0.0421269 0.877388 + outer loop + vertex 1.01703 1.79713 2.61698 + vertex 1.01672 1.80201 2.61691 + vertex 1.01375 1.79875 2.61868 + endloop + endfacet + facet normal 0.47214 0.0488901 0.880167 + outer loop + vertex 1.01375 1.79875 2.61868 + vertex 1.01672 1.80201 2.61691 + vertex 1.01327 1.80363 2.61867 + endloop + endfacet + facet normal 0.485556 0.0379269 0.873383 + outer loop + vertex 1.01717 1.79224 2.61711 + vertex 1.01703 1.79713 2.61698 + vertex 1.01395 1.79388 2.61883 + endloop + endfacet + facet normal 0.488043 0.0446051 0.871679 + outer loop + vertex 1.01406 1.78895 2.61902 + vertex 1.01717 1.79224 2.61711 + vertex 1.01395 1.79388 2.61883 + endloop + endfacet + facet normal 0.454319 0.0498463 0.889443 + outer loop + vertex 1.00727 1.79716 2.62211 + vertex 1.00748 1.79223 2.62228 + vertex 1.01066 1.79547 2.62047 + endloop + endfacet + facet normal 0.431832 0.0567178 0.900169 + outer loop + vertex 1.00727 1.79716 2.62211 + vertex 1.00675 1.80211 2.62205 + vertex 1.0037 1.79889 2.62371 + endloop + endfacet + facet normal 0.433553 0.0644981 0.898817 + outer loop + vertex 1.00606 1.80719 2.62202 + vertex 1.00675 1.80211 2.62205 + vertex 1.00977 1.80507 2.62038 + endloop + endfacet + facet normal 0.460182 0.0477164 0.886541 + outer loop + vertex 1.01375 1.79875 2.61868 + vertex 1.01327 1.80363 2.61867 + vertex 1.01036 1.80034 2.62036 + endloop + endfacet + facet normal 0.450029 0.0539532 0.891383 + outer loop + vertex 1.00921 1.80898 2.62042 + vertex 1.00977 1.80507 2.62038 + vertex 1.01226 1.80835 2.61893 + endloop + endfacet + facet normal 0.471047 0.0457278 0.880922 + outer loop + vertex 1.01672 1.80201 2.61691 + vertex 1.01614 1.80731 2.61695 + vertex 1.01327 1.80363 2.61867 + endloop + endfacet + facet normal 0.45321 0.0568277 0.889591 + outer loop + vertex 1.01037 1.8131 2.61958 + vertex 1.01226 1.80835 2.61893 + vertex 1.01433 1.81206 2.61763 + endloop + endfacet + facet normal 0.463135 0.0545284 0.884609 + outer loop + vertex 1.01328 1.81698 2.61788 + vertex 1.01433 1.81206 2.61763 + vertex 1.01673 1.81539 2.61617 + endloop + endfacet + facet normal 0.48767 0.0487806 0.871664 + outer loop + vertex 1.01915 1.809 2.6152 + vertex 1.02019 1.81321 2.61439 + vertex 1.01728 1.81133 2.61612 + endloop + endfacet + facet normal 0.47266 0.052509 0.879679 + outer loop + vertex 1.01673 1.81539 2.61617 + vertex 1.01956 1.81864 2.61446 + vertex 1.01616 1.8204 2.61618 + endloop + endfacet + facet normal 0.494619 0.0395646 0.868209 + outer loop + vertex 1.02287 1.81709 2.61264 + vertex 1.02252 1.82204 2.61261 + vertex 1.01956 1.81864 2.61446 + endloop + endfacet + facet normal 0.484975 0.0382103 0.873693 + outer loop + vertex 1.01962 1.805 2.61511 + vertex 1.01915 1.809 2.6152 + vertex 1.01614 1.80731 2.61695 + endloop + endfacet + facet normal 0.489718 0.0478521 0.870567 + outer loop + vertex 1.01614 1.80731 2.61695 + vertex 1.01672 1.80201 2.61691 + vertex 1.01962 1.805 2.61511 + endloop + endfacet + facet normal 0.509584 0.0382299 0.859571 + outer loop + vertex 1.01703 1.79713 2.61698 + vertex 1.01717 1.79224 2.61711 + vertex 1.0202 1.79533 2.61518 + endloop + endfacet + facet normal 0.495964 0.0348052 0.867645 + outer loop + vertex 1.01728 1.78725 2.61725 + vertex 1.01717 1.79224 2.61711 + vertex 1.01406 1.78895 2.61902 + endloop + endfacet + facet normal 0.538334 0.0181632 0.842536 + outer loop + vertex 1.02285 1.77784 2.61399 + vertex 1.02389 1.78232 2.61322 + vertex 1.02042 1.78015 2.61549 + endloop + endfacet + facet normal 0.534427 0.0241972 0.844868 + outer loop + vertex 1.02046 1.78518 2.61533 + vertex 1.02354 1.78805 2.6133 + vertex 1.02033 1.79034 2.61527 + endloop + endfacet + facet normal 0.53422 0.0237844 0.845011 + outer loop + vertex 1.02354 1.78805 2.6133 + vertex 1.02334 1.79323 2.61328 + vertex 1.02033 1.79034 2.61527 + endloop + endfacet + facet normal 0.47291 0.0578584 0.879209 + outer loop + vertex 1.03001 1.78891 2.60967 + vertex 1.02954 1.79385 2.6096 + vertex 1.02657 1.79099 2.61138 + endloop + endfacet + facet normal 0.528788 0.0276335 0.848304 + outer loop + vertex 1.0232 1.79819 2.61321 + vertex 1.02334 1.79323 2.61328 + vertex 1.02636 1.796 2.61131 + endloop + endfacet + facet normal 0.526027 0.032309 0.849854 + outer loop + vertex 1.0232 1.79819 2.61321 + vertex 1.02296 1.80312 2.61317 + vertex 1.02001 1.80018 2.61511 + endloop + endfacet + facet normal 0.515522 0.0436191 0.855765 + outer loop + vertex 1.02939 1.79867 2.6094 + vertex 1.02933 1.8037 2.60918 + vertex 1.02621 1.80094 2.6112 + endloop + endfacet + facet normal 0.484349 0.0428991 0.873823 + outer loop + vertex 1.02933 1.8037 2.60918 + vertex 1.03245 1.80682 2.60729 + vertex 1.02911 1.8088 2.60905 + endloop + endfacet + facet normal 0.489854 0.0555017 0.870036 + outer loop + vertex 1.03245 1.80682 2.60729 + vertex 1.03214 1.81195 2.60714 + vertex 1.02911 1.8088 2.60905 + endloop + endfacet + facet normal 0.505528 0.0356384 0.862074 + outer loop + vertex 1.02911 1.8088 2.60905 + vertex 1.03214 1.81195 2.60714 + vertex 1.02893 1.81377 2.60895 + endloop + endfacet + facet normal 0.466244 0.0661162 0.882182 + outer loop + vertex 1.03301 1.80114 2.60742 + vertex 1.03245 1.80682 2.60729 + vertex 1.02933 1.8037 2.60918 + endloop + endfacet + facet normal 0.454664 0.0443609 0.889557 + outer loop + vertex 1.02939 1.79867 2.6094 + vertex 1.03301 1.80114 2.60742 + vertex 1.02933 1.8037 2.60918 + endloop + endfacet + facet normal 0.534426 0.0363617 0.844433 + outer loop + vertex 1.0225 1.80852 2.61322 + vertex 1.02296 1.80312 2.61317 + vertex 1.02602 1.80595 2.61111 + endloop + endfacet + facet normal 0.528151 0.0380586 0.848297 + outer loop + vertex 1.02287 1.81709 2.61264 + vertex 1.02349 1.81298 2.61244 + vertex 1.02593 1.81557 2.6108 + endloop + endfacet + facet normal 0.534243 0.0363287 0.84455 + outer loop + vertex 1.02911 1.8088 2.60905 + vertex 1.02893 1.81377 2.60895 + vertex 1.026 1.81087 2.61093 + endloop + endfacet + facet normal 0.537656 0.0313742 0.842581 + outer loop + vertex 1.02593 1.81557 2.6108 + vertex 1.02863 1.81863 2.60897 + vertex 1.02561 1.82024 2.61083 + endloop + endfacet + facet normal 0.508465 0.0428455 0.860016 + outer loop + vertex 1.03214 1.81195 2.60714 + vertex 1.03183 1.817 2.60707 + vertex 1.02893 1.81377 2.60895 + endloop + endfacet + facet normal 0.50923 0.0481797 0.859281 + outer loop + vertex 1.03537 1.82817 2.60452 + vertex 1.03485 1.83354 2.60453 + vertex 1.03194 1.83074 2.60641 + endloop + endfacet + facet normal 0.484659 0.0409088 0.873746 + outer loop + vertex 1.03485 1.83354 2.60453 + vertex 1.03782 1.83677 2.60273 + vertex 1.03443 1.83875 2.60452 + endloop + endfacet + facet normal 0.4916 0.0571068 0.868947 + outer loop + vertex 1.03782 1.83677 2.60273 + vertex 1.03746 1.84194 2.60259 + vertex 1.03443 1.83875 2.60452 + endloop + endfacet + facet normal 0.507944 0.0365734 0.860613 + outer loop + vertex 1.03443 1.83875 2.60452 + vertex 1.03746 1.84194 2.60259 + vertex 1.03424 1.8438 2.60441 + endloop + endfacet + facet normal 0.533138 0.0369036 0.845223 + outer loop + vertex 1.0282 1.83816 2.60845 + vertex 1.02862 1.83297 2.60842 + vertex 1.03151 1.83585 2.60647 + endloop + endfacet + facet normal 0.523808 0.0294408 0.851328 + outer loop + vertex 1.02868 1.84794 2.60776 + vertex 1.02767 1.84361 2.60853 + vertex 1.03118 1.84582 2.60629 + endloop + endfacet + facet normal 0.532951 0.0371597 0.845329 + outer loop + vertex 1.03443 1.83875 2.60452 + vertex 1.03424 1.8438 2.60441 + vertex 1.03118 1.84095 2.60647 + endloop + endfacet + facet normal 0.53907 0.0316056 0.841668 + outer loop + vertex 1.03118 1.84582 2.60629 + vertex 1.03421 1.84874 2.60424 + vertex 1.03121 1.85049 2.6061 + endloop + endfacet + facet normal 0.512537 0.0477672 0.857335 + outer loop + vertex 1.03746 1.84194 2.60259 + vertex 1.03734 1.84702 2.60238 + vertex 1.03424 1.8438 2.60441 + endloop + endfacet + facet normal 0.514165 0.0518009 0.856126 + outer loop + vertex 1.03329 1.87781 2.60339 + vertex 1.034 1.87226 2.6033 + vertex 1.03678 1.8757 2.60142 + endloop + endfacet + facet normal 0.536538 0.0394972 0.842952 + outer loop + vertex 1.03929 1.86891 2.60015 + vertex 1.04027 1.87312 2.59933 + vertex 1.03734 1.87153 2.60127 + endloop + endfacet + facet normal 0.536622 0.0395848 0.842894 + outer loop + vertex 1.03734 1.87153 2.60127 + vertex 1.03633 1.8674 2.6021 + vertex 1.03929 1.86891 2.60015 + endloop + endfacet + facet normal 0.536895 0.0388698 0.842753 + outer loop + vertex 1.03963 1.86483 2.60012 + vertex 1.03929 1.86891 2.60015 + vertex 1.03633 1.8674 2.6021 + endloop + endfacet + facet normal 0.535801 0.0368573 0.84354 + outer loop + vertex 1.03633 1.8674 2.6021 + vertex 1.03686 1.86205 2.602 + vertex 1.03963 1.86483 2.60012 + endloop + endfacet + facet normal 0.532575 0.0413264 0.845373 + outer loop + vertex 1.03963 1.86483 2.60012 + vertex 1.03686 1.86205 2.602 + vertex 1.03994 1.86013 2.60016 + endloop + endfacet + facet normal 0.502674 0.0395322 0.863572 + outer loop + vertex 1.03994 1.86013 2.60016 + vertex 1.04229 1.86265 2.59867 + vertex 1.03963 1.86483 2.60012 + endloop + endfacet + facet normal 0.503984 0.0417007 0.862706 + outer loop + vertex 1.04229 1.86265 2.59867 + vertex 1.04295 1.86759 2.59805 + vertex 1.03963 1.86483 2.60012 + endloop + endfacet + facet normal 0.529919 0.035209 0.847317 + outer loop + vertex 1.03686 1.86205 2.602 + vertex 1.03714 1.85704 2.60204 + vertex 1.03994 1.86013 2.60016 + endloop + endfacet + facet normal 0.516638 0.0517393 0.854639 + outer loop + vertex 1.03994 1.86013 2.60016 + vertex 1.03714 1.85704 2.60204 + vertex 1.04031 1.85534 2.60022 + endloop + endfacet + facet normal 0.473663 0.048714 0.879358 + outer loop + vertex 1.04031 1.85534 2.60022 + vertex 1.04316 1.85848 2.59851 + vertex 1.03994 1.86013 2.60016 + endloop + endfacet + facet normal 0.480424 0.0667533 0.874492 + outer loop + vertex 1.04316 1.85848 2.59851 + vertex 1.04229 1.86265 2.59867 + vertex 1.03994 1.86013 2.60016 + endloop + endfacet + facet normal 0.443864 0.0827406 0.892266 + outer loop + vertex 1.04378 1.85354 2.59866 + vertex 1.04316 1.85848 2.59851 + vertex 1.04031 1.85534 2.60022 + endloop + endfacet + facet normal 0.434079 0.058054 0.899002 + outer loop + vertex 1.04052 1.85037 2.60044 + vertex 1.04378 1.85354 2.59866 + vertex 1.04031 1.85534 2.60022 + endloop + endfacet + facet normal 0.494669 0.0591776 0.867065 + outer loop + vertex 1.04031 1.85534 2.60022 + vertex 1.03728 1.85204 2.60218 + vertex 1.04052 1.85037 2.60044 + endloop + endfacet + facet normal 0.488133 0.0415702 0.871779 + outer loop + vertex 1.03728 1.85204 2.60218 + vertex 1.03734 1.84702 2.60238 + vertex 1.04052 1.85037 2.60044 + endloop + endfacet + facet normal 0.511609 0.0384007 0.85836 + outer loop + vertex 1.03714 1.85704 2.60204 + vertex 1.03728 1.85204 2.60218 + vertex 1.04031 1.85534 2.60022 + endloop + endfacet + facet normal 0.507394 0.0362823 0.86095 + outer loop + vertex 1.03929 1.86891 2.60015 + vertex 1.03963 1.86483 2.60012 + vertex 1.04295 1.86759 2.59805 + endloop + endfacet + facet normal 0.510462 0.0485645 0.858528 + outer loop + vertex 1.03929 1.86891 2.60015 + vertex 1.04295 1.86759 2.59805 + vertex 1.04027 1.87312 2.59933 + endloop + endfacet + facet normal 0.521174 0.0553501 0.851654 + outer loop + vertex 1.04027 1.87312 2.59933 + vertex 1.04295 1.86759 2.59805 + vertex 1.04359 1.87264 2.59733 + endloop + endfacet + facet normal 0.529514 0.042943 0.847214 + outer loop + vertex 1.03678 1.8757 2.60142 + vertex 1.03959 1.87869 2.59951 + vertex 1.03626 1.88079 2.60148 + endloop + endfacet + facet normal 0.520649 0.0486401 0.852384 + outer loop + vertex 1.04359 1.87264 2.59733 + vertex 1.04284 1.87699 2.59754 + vertex 1.04027 1.87312 2.59933 + endloop + endfacet + facet normal 0.533967 0.03719 0.844687 + outer loop + vertex 1.0393 1.88379 2.59949 + vertex 1.0423 1.887 2.59745 + vertex 1.0392 1.88876 2.59933 + endloop + endfacet + facet normal 0.533491 0.0359715 0.845041 + outer loop + vertex 1.0423 1.887 2.59745 + vertex 1.04224 1.892 2.59727 + vertex 1.0392 1.88876 2.59933 + endloop + endfacet + facet normal 0.448631 0.0773571 0.890363 + outer loop + vertex 1.04908 1.87843 2.59416 + vertex 1.04862 1.88351 2.59395 + vertex 1.04566 1.8803 2.59572 + endloop + endfacet + facet normal 0.538062 0.0359166 0.842139 + outer loop + vertex 1.04224 1.892 2.59727 + vertex 1.0423 1.887 2.59745 + vertex 1.04528 1.89001 2.59542 + endloop + endfacet + facet normal 0.523751 0.0393075 0.850964 + outer loop + vertex 1.04224 1.892 2.59727 + vertex 1.04215 1.89703 2.5971 + vertex 1.0391 1.89373 2.59913 + endloop + endfacet + facet normal 0.53278 0.043912 0.845114 + outer loop + vertex 1.04194 1.902 2.59697 + vertex 1.04215 1.89703 2.5971 + vertex 1.04514 1.9001 2.59505 + endloop + endfacet + facet normal 0.529655 0.0363261 0.847435 + outer loop + vertex 1.0449 1.90504 2.59499 + vertex 1.04194 1.902 2.59697 + vertex 1.04514 1.9001 2.59505 + endloop + endfacet + facet normal 0.518992 0.05052 0.853285 + outer loop + vertex 1.04152 1.90692 2.59694 + vertex 1.04194 1.902 2.59697 + vertex 1.0449 1.90504 2.59499 + endloop + endfacet + facet normal 0.514402 0.0388056 0.856671 + outer loop + vertex 1.04449 1.90989 2.59502 + vertex 1.04152 1.90692 2.59694 + vertex 1.0449 1.90504 2.59499 + endloop + endfacet + facet normal 0.536707 0.0407364 0.842785 + outer loop + vertex 1.0449 1.90504 2.59499 + vertex 1.04781 1.90798 2.593 + vertex 1.04449 1.90989 2.59502 + endloop + endfacet + facet normal 0.5221 0.0546511 0.851132 + outer loop + vertex 1.04878 1.89232 2.59321 + vertex 1.04833 1.89791 2.59313 + vertex 1.04531 1.89501 2.59517 + endloop + endfacet + facet normal 0.539673 0.0367443 0.841072 + outer loop + vertex 1.04514 1.9001 2.59505 + vertex 1.04809 1.90297 2.59304 + vertex 1.0449 1.90504 2.59499 + endloop + endfacet + facet normal 0.539646 0.0366839 0.841092 + outer loop + vertex 1.04809 1.90297 2.59304 + vertex 1.04781 1.90798 2.593 + vertex 1.0449 1.90504 2.59499 + endloop + endfacet + facet normal 0.536709 0.0395854 0.842838 + outer loop + vertex 1.04731 1.91345 2.59306 + vertex 1.04781 1.90798 2.593 + vertex 1.05079 1.91077 2.59097 + endloop + endfacet + facet normal 0.536236 0.0395383 0.843142 + outer loop + vertex 1.04781 1.90798 2.593 + vertex 1.04731 1.91345 2.59306 + vertex 1.04449 1.90989 2.59502 + endloop + endfacet + facet normal 0.519975 0.0686554 0.851418 + outer loop + vertex 1.05378 1.91346 2.58904 + vertex 1.05304 1.91772 2.58915 + vertex 1.05061 1.91558 2.5908 + endloop + endfacet + facet normal 0.543144 0.0521014 0.838022 + outer loop + vertex 1.04762 1.922 2.59236 + vertex 1.04822 1.91789 2.59223 + vertex 1.05061 1.92011 2.59054 + endloop + endfacet + facet normal 0.517009 0.0628415 0.85367 + outer loop + vertex 1.04673 1.93194 2.59221 + vertex 1.04719 1.92693 2.5923 + vertex 1.05007 1.93001 2.59033 + endloop + endfacet + facet normal 0.511692 0.0496916 0.857731 + outer loop + vertex 1.04961 1.93499 2.59032 + vertex 1.04673 1.93194 2.59221 + vertex 1.05007 1.93001 2.59033 + endloop + endfacet + facet normal 0.496506 0.068777 0.865304 + outer loop + vertex 1.0461 1.93725 2.59215 + vertex 1.04673 1.93194 2.59221 + vertex 1.04961 1.93499 2.59032 + endloop + endfacet + facet normal 0.487336 0.0493033 0.871822 + outer loop + vertex 1.04961 1.93499 2.59032 + vertex 1.04914 1.93903 2.59035 + vertex 1.0461 1.93725 2.59215 + endloop + endfacet + facet normal 0.52015 0.0533315 0.852408 + outer loop + vertex 1.04914 1.93903 2.59035 + vertex 1.04961 1.93499 2.59032 + vertex 1.05248 1.9385 2.58834 + endloop + endfacet + facet normal 0.520416 0.0563044 0.852054 + outer loop + vertex 1.04914 1.93903 2.59035 + vertex 1.05248 1.9385 2.58834 + vertex 1.05019 1.94319 2.58944 + endloop + endfacet + facet normal 0.533924 0.0522835 0.843915 + outer loop + vertex 1.05394 1.92217 2.58834 + vertex 1.05337 1.9278 2.58835 + vertex 1.05044 1.92493 2.59038 + endloop + endfacet + facet normal 0.530948 0.0514283 0.845842 + outer loop + vertex 1.05007 1.93001 2.59033 + vertex 1.05297 1.93298 2.58833 + vertex 1.04961 1.93499 2.59032 + endloop + endfacet + facet normal 0.528067 0.044404 0.848041 + outer loop + vertex 1.05297 1.93298 2.58833 + vertex 1.05248 1.9385 2.58834 + vertex 1.04961 1.93499 2.59032 + endloop + endfacet + facet normal 0.477 0.0728799 0.875876 + outer loop + vertex 1.05961 1.92861 2.58477 + vertex 1.05931 1.93344 2.58453 + vertex 1.05629 1.93071 2.5864 + endloop + endfacet + facet normal 0.528928 0.0444821 0.8475 + outer loop + vertex 1.05248 1.9385 2.58834 + vertex 1.05297 1.93298 2.58833 + vertex 1.05602 1.93577 2.58628 + endloop + endfacet + facet normal 0.511945 0.0553234 0.857235 + outer loop + vertex 1.05925 1.93847 2.58424 + vertex 1.05901 1.94355 2.58405 + vertex 1.05601 1.94073 2.58603 + endloop + endfacet + facet normal 0.496053 0.0460294 0.867071 + outer loop + vertex 1.05901 1.94355 2.58405 + vertex 1.06197 1.94679 2.58218 + vertex 1.05865 1.94844 2.584 + endloop + endfacet + facet normal 0.500125 0.0575885 0.864036 + outer loop + vertex 1.06197 1.94679 2.58218 + vertex 1.06131 1.95219 2.58221 + vertex 1.05865 1.94844 2.584 + endloop + endfacet + facet normal 0.51338 0.0448033 0.856991 + outer loop + vertex 1.05865 1.94844 2.584 + vertex 1.06131 1.95219 2.58221 + vertex 1.05799 1.95256 2.58418 + endloop + endfacet + facet normal 0.51377 0.0514812 0.856382 + outer loop + vertex 1.05881 1.95713 2.58341 + vertex 1.05799 1.95256 2.58418 + vertex 1.06131 1.95219 2.58221 + endloop + endfacet + facet normal 0.512712 0.0507808 0.857058 + outer loop + vertex 1.06231 1.95638 2.58136 + vertex 1.05881 1.95713 2.58341 + vertex 1.06131 1.95219 2.58221 + endloop + endfacet + facet normal 0.489443 0.0589083 0.870044 + outer loop + vertex 1.06231 1.95638 2.58136 + vertex 1.06131 1.95219 2.58221 + vertex 1.06433 1.95399 2.58038 + endloop + endfacet + facet normal 0.483846 0.0526974 0.873565 + outer loop + vertex 1.06433 1.95399 2.58038 + vertex 1.06533 1.95796 2.57959 + vertex 1.06231 1.95638 2.58136 + endloop + endfacet + facet normal 0.488087 0.042585 0.871755 + outer loop + vertex 1.06231 1.95638 2.58136 + vertex 1.06533 1.95796 2.57959 + vertex 1.06169 1.96062 2.5815 + endloop + endfacet + facet normal 0.496203 0.0576008 0.866293 + outer loop + vertex 1.06533 1.95796 2.57959 + vertex 1.06472 1.96335 2.57959 + vertex 1.06169 1.96062 2.5815 + endloop + endfacet + facet normal 0.505561 0.0439683 0.86167 + outer loop + vertex 1.06169 1.96062 2.5815 + vertex 1.06472 1.96335 2.57959 + vertex 1.06133 1.96565 2.58146 + endloop + endfacet + facet normal 0.504578 0.0439014 0.862249 + outer loop + vertex 1.06133 1.96565 2.58146 + vertex 1.05785 1.96334 2.58361 + vertex 1.06169 1.96062 2.5815 + endloop + endfacet + facet normal 0.50818 0.0509246 0.859744 + outer loop + vertex 1.05785 1.96334 2.58361 + vertex 1.05881 1.95713 2.58341 + vertex 1.06169 1.96062 2.5815 + endloop + endfacet + facet normal 0.503682 0.0456595 0.862682 + outer loop + vertex 1.05866 1.96787 2.5829 + vertex 1.05785 1.96334 2.58361 + vertex 1.06133 1.96565 2.58146 + endloop + endfacet + facet normal 0.502978 0.0445113 0.863152 + outer loop + vertex 1.06115 1.9704 2.58132 + vertex 1.05866 1.96787 2.5829 + vertex 1.06133 1.96565 2.58146 + endloop + endfacet + facet normal 0.512892 0.0447027 0.857288 + outer loop + vertex 1.06133 1.96565 2.58146 + vertex 1.06428 1.96852 2.57954 + vertex 1.06115 1.9704 2.58132 + endloop + endfacet + facet normal 0.512483 0.0437413 0.857582 + outer loop + vertex 1.06428 1.96852 2.57954 + vertex 1.06411 1.97356 2.57938 + vertex 1.06115 1.9704 2.58132 + endloop + endfacet + facet normal 0.504652 0.0535975 0.861658 + outer loop + vertex 1.06115 1.9704 2.58132 + vertex 1.06411 1.97356 2.57938 + vertex 1.06091 1.97518 2.58116 + endloop + endfacet + facet normal 0.486122 0.0530413 0.87228 + outer loop + vertex 1.06091 1.97518 2.58116 + vertex 1.05797 1.97193 2.58299 + vertex 1.06115 1.9704 2.58132 + endloop + endfacet + facet normal 0.489276 0.0621942 0.869908 + outer loop + vertex 1.05797 1.97193 2.58299 + vertex 1.05866 1.96787 2.5829 + vertex 1.06115 1.9704 2.58132 + endloop + endfacet + facet normal 0.508722 0.0504337 0.859452 + outer loop + vertex 1.06472 1.96335 2.57959 + vertex 1.06428 1.96852 2.57954 + vertex 1.06133 1.96565 2.58146 + endloop + endfacet + facet normal 0.454583 0.0529004 0.889132 + outer loop + vertex 1.06533 1.95796 2.57959 + vertex 1.06861 1.96094 2.57774 + vertex 1.06472 1.96335 2.57959 + endloop + endfacet + facet normal 0.466301 0.0779268 0.881187 + outer loop + vertex 1.06861 1.96094 2.57774 + vertex 1.06769 1.9666 2.57772 + vertex 1.06472 1.96335 2.57959 + endloop + endfacet + facet normal 0.490829 0.049036 0.869875 + outer loop + vertex 1.06472 1.96335 2.57959 + vertex 1.06769 1.9666 2.57772 + vertex 1.06428 1.96852 2.57954 + endloop + endfacet + facet normal 0.494891 0.059004 0.866949 + outer loop + vertex 1.06769 1.9666 2.57772 + vertex 1.06733 1.97184 2.57757 + vertex 1.06428 1.96852 2.57954 + endloop + endfacet + facet normal 0.507456 0.0436613 0.860571 + outer loop + vertex 1.06428 1.96852 2.57954 + vertex 1.06733 1.97184 2.57757 + vertex 1.06411 1.97356 2.57938 + endloop + endfacet + facet normal 0.509065 0.0479226 0.859393 + outer loop + vertex 1.06733 1.97184 2.57757 + vertex 1.06722 1.97693 2.57736 + vertex 1.06411 1.97356 2.57938 + endloop + endfacet + facet normal 0.510144 0.0465871 0.858826 + outer loop + vertex 1.06411 1.97356 2.57938 + vertex 1.06722 1.97693 2.57736 + vertex 1.06403 1.97856 2.57916 + endloop + endfacet + facet normal 0.50983 0.0457164 0.859059 + outer loop + vertex 1.06722 1.97693 2.57736 + vertex 1.06715 1.98191 2.57713 + vertex 1.06403 1.97856 2.57916 + endloop + endfacet + facet normal 0.500295 0.0458386 0.864641 + outer loop + vertex 1.06715 1.98191 2.57713 + vertex 1.06722 1.97693 2.57736 + vertex 1.07027 1.9801 2.57542 + endloop + endfacet + facet normal 0.50224 0.0505008 0.863253 + outer loop + vertex 1.07022 1.98486 2.57517 + vertex 1.06715 1.98191 2.57713 + vertex 1.07027 1.9801 2.57542 + endloop + endfacet + facet normal 0.470771 0.0511136 0.880774 + outer loop + vertex 1.07027 1.9801 2.57542 + vertex 1.07295 1.98254 2.57385 + vertex 1.07022 1.98486 2.57517 + endloop + endfacet + facet normal 0.45316 0.0753337 0.888241 + outer loop + vertex 1.0735 1.97836 2.57392 + vertex 1.07295 1.98254 2.57385 + vertex 1.07027 1.9801 2.57542 + endloop + endfacet + facet normal 0.446598 0.0592729 0.892769 + outer loop + vertex 1.07046 1.97523 2.57565 + vertex 1.0735 1.97836 2.57392 + vertex 1.07027 1.9801 2.57542 + endloop + endfacet + facet normal 0.419062 0.0918579 0.903299 + outer loop + vertex 1.07387 1.97353 2.57424 + vertex 1.0735 1.97836 2.57392 + vertex 1.07046 1.97523 2.57565 + endloop + endfacet + facet normal 0.411272 0.0717212 0.908687 + outer loop + vertex 1.07076 1.97013 2.57592 + vertex 1.07387 1.97353 2.57424 + vertex 1.07046 1.97523 2.57565 + endloop + endfacet + facet normal 0.489191 0.0598392 0.870121 + outer loop + vertex 1.07027 1.9801 2.57542 + vertex 1.06722 1.97693 2.57736 + vertex 1.07046 1.97523 2.57565 + endloop + endfacet + facet normal 0.484678 0.0479759 0.873376 + outer loop + vertex 1.06722 1.97693 2.57736 + vertex 1.06733 1.97184 2.57757 + vertex 1.07046 1.97523 2.57565 + endloop + endfacet + facet normal 0.463115 0.0734509 0.883249 + outer loop + vertex 1.07046 1.97523 2.57565 + vertex 1.06733 1.97184 2.57757 + vertex 1.07076 1.97013 2.57592 + endloop + endfacet + facet normal 0.457032 0.0569897 0.887623 + outer loop + vertex 1.06733 1.97184 2.57757 + vertex 1.06769 1.9666 2.57772 + vertex 1.07076 1.97013 2.57592 + endloop + endfacet + facet normal 0.512132 0.0465129 0.857647 + outer loop + vertex 1.06169 1.96062 2.5815 + vertex 1.05881 1.95713 2.58341 + vertex 1.06231 1.95638 2.58136 + endloop + endfacet + facet normal 0.522501 0.0523839 0.851028 + outer loop + vertex 1.05285 1.94699 2.58762 + vertex 1.05347 1.94293 2.58749 + vertex 1.05592 1.94543 2.58583 + endloop + endfacet + facet normal 0.491177 0.0605941 0.86895 + outer loop + vertex 1.05285 1.94699 2.58762 + vertex 1.05241 1.95183 2.58753 + vertex 1.04953 1.9485 2.58939 + endloop + endfacet + facet normal 0.521857 0.0463867 0.851771 + outer loop + vertex 1.05865 1.94844 2.584 + vertex 1.05799 1.95256 2.58418 + vertex 1.05556 1.95004 2.5858 + endloop + endfacet + facet normal 0.49125 0.0726138 0.867987 + outer loop + vertex 1.05195 1.95687 2.58737 + vertex 1.05241 1.95183 2.58753 + vertex 1.05534 1.95478 2.58563 + endloop + endfacet + facet normal 0.453887 0.0785605 0.887589 + outer loop + vertex 1.05195 1.95687 2.58737 + vertex 1.05124 1.96234 2.58725 + vertex 1.04835 1.95854 2.58907 + endloop + endfacet + facet normal 0.485758 0.0648397 0.871685 + outer loop + vertex 1.05433 1.96407 2.58552 + vertex 1.05496 1.95982 2.58548 + vertex 1.05785 1.96334 2.58361 + endloop + endfacet + facet normal 0.485635 0.0638698 0.871825 + outer loop + vertex 1.05433 1.96407 2.58552 + vertex 1.05785 1.96334 2.58361 + vertex 1.05529 1.9682 2.58468 + endloop + endfacet + facet normal 0.430444 0.0838076 0.898718 + outer loop + vertex 1.05233 1.96643 2.58635 + vertex 1.04928 1.96704 2.58775 + vertex 1.05124 1.96234 2.58725 + endloop + endfacet + facet normal 0.413996 0.0974225 0.90505 + outer loop + vertex 1.04928 1.96704 2.58775 + vertex 1.04806 1.97178 2.5878 + vertex 1.04518 1.9679 2.58953 + endloop + endfacet + facet normal 0.432611 0.0900206 0.897075 + outer loop + vertex 1.05455 1.97342 2.5846 + vertex 1.05758 1.97674 2.5828 + vertex 1.05407 1.97833 2.58433 + endloop + endfacet + facet normal 0.403798 0.109187 0.908309 + outer loop + vertex 1.04721 1.97679 2.58757 + vertex 1.04806 1.97178 2.5878 + vertex 1.05097 1.97509 2.58611 + endloop + endfacet + facet normal 0.360033 0.111548 0.926247 + outer loop + vertex 1.04721 1.97679 2.58757 + vertex 1.04671 1.98168 2.58718 + vertex 1.04285 1.97889 2.58902 + endloop + endfacet + facet normal 0.349355 0.12765 0.928255 + outer loop + vertex 1.04285 1.97889 2.58902 + vertex 1.04671 1.98168 2.58718 + vertex 1.04347 1.98334 2.58817 + endloop + endfacet + facet normal 0.346354 0.12053 0.930329 + outer loop + vertex 1.04671 1.98168 2.58718 + vertex 1.04599 1.98656 2.58682 + vertex 1.04347 1.98334 2.58817 + endloop + endfacet + facet normal 0.318382 0.145115 0.936789 + outer loop + vertex 1.04347 1.98334 2.58817 + vertex 1.04599 1.98656 2.58682 + vertex 1.04226 1.98635 2.58812 + endloop + endfacet + facet normal 0.317729 0.151595 0.935985 + outer loop + vertex 1.04282 1.99063 2.58723 + vertex 1.04226 1.98635 2.58812 + vertex 1.04599 1.98656 2.58682 + endloop + endfacet + facet normal 0.299079 0.13618 0.944461 + outer loop + vertex 1.04684 1.9907 2.58595 + vertex 1.04282 1.99063 2.58723 + vertex 1.04599 1.98656 2.58682 + endloop + endfacet + facet normal 0.352992 0.121629 0.927687 + outer loop + vertex 1.04684 1.9907 2.58595 + vertex 1.04599 1.98656 2.58682 + vertex 1.04921 1.98866 2.58532 + endloop + endfacet + facet normal 0.356504 0.126325 0.925714 + outer loop + vertex 1.04921 1.98866 2.58532 + vertex 1.04998 1.99285 2.58445 + vertex 1.04684 1.9907 2.58595 + endloop + endfacet + facet normal 0.341398 0.149942 0.927882 + outer loop + vertex 1.04684 1.9907 2.58595 + vertex 1.04998 1.99285 2.58445 + vertex 1.04559 1.99473 2.58576 + endloop + endfacet + facet normal 0.333997 0.128563 0.933765 + outer loop + vertex 1.04998 1.99285 2.58445 + vertex 1.04836 1.9988 2.58421 + vertex 1.04559 1.99473 2.58576 + endloop + endfacet + facet normal 0.352227 0.133244 0.926381 + outer loop + vertex 1.04998 1.99285 2.58445 + vertex 1.05336 1.99615 2.58269 + vertex 1.04836 1.9988 2.58421 + endloop + endfacet + facet normal 0.34066 0.106987 0.93408 + outer loop + vertex 1.05336 1.99615 2.58269 + vertex 1.0522 2.00169 2.58247 + vertex 1.04836 1.9988 2.58421 + endloop + endfacet + facet normal 0.324726 0.12986 0.936851 + outer loop + vertex 1.04836 1.9988 2.58421 + vertex 1.0522 2.00169 2.58247 + vertex 1.04866 2.0035 2.58345 + endloop + endfacet + facet normal 0.324475 0.129279 0.937018 + outer loop + vertex 1.0522 2.00169 2.58247 + vertex 1.05111 2.00677 2.58215 + vertex 1.04866 2.0035 2.58345 + endloop + endfacet + facet normal 0.290268 0.157641 0.943872 + outer loop + vertex 1.04866 2.0035 2.58345 + vertex 1.05111 2.00677 2.58215 + vertex 1.04729 2.00653 2.58337 + endloop + endfacet + facet normal 0.257737 0.14326 0.955536 + outer loop + vertex 1.04866 2.0035 2.58345 + vertex 1.04729 2.00653 2.58337 + vertex 1.04423 2.00349 2.58465 + endloop + endfacet + facet normal 0.257974 0.137313 0.956344 + outer loop + vertex 1.04423 2.00349 2.58465 + vertex 1.04836 1.9988 2.58421 + vertex 1.04866 2.0035 2.58345 + endloop + endfacet + facet normal 0.287924 0.179368 0.940706 + outer loop + vertex 1.04786 2.01061 2.58242 + vertex 1.04729 2.00653 2.58337 + vertex 1.05111 2.00677 2.58215 + endloop + endfacet + facet normal 0.334879 0.131269 0.933073 + outer loop + vertex 1.05111 2.00677 2.58215 + vertex 1.0522 2.00169 2.58247 + vertex 1.05531 2.00493 2.5809 + endloop + endfacet + facet normal 0.33036 0.118732 0.936357 + outer loop + vertex 1.05531 2.00493 2.5809 + vertex 1.05438 2.00897 2.58072 + vertex 1.05111 2.00677 2.58215 + endloop + endfacet + facet normal 0.350223 0.122982 0.928558 + outer loop + vertex 1.05438 2.00897 2.58072 + vertex 1.05531 2.00493 2.5809 + vertex 1.0583 2.00889 2.57925 + endloop + endfacet + facet normal 0.349591 0.144289 0.925725 + outer loop + vertex 1.05438 2.00897 2.58072 + vertex 1.0583 2.00889 2.57925 + vertex 1.05507 2.01315 2.57981 + endloop + endfacet + facet normal 0.329659 0.127901 0.935396 + outer loop + vertex 1.05507 2.01315 2.57981 + vertex 1.0583 2.00889 2.57925 + vertex 1.05887 2.01343 2.57843 + endloop + endfacet + facet normal 0.327954 0.143221 0.933774 + outer loop + vertex 1.05887 2.01343 2.57843 + vertex 1.0574 2.01657 2.57847 + vertex 1.05507 2.01315 2.57981 + endloop + endfacet + facet normal 0.294257 0.168833 0.940696 + outer loop + vertex 1.05507 2.01315 2.57981 + vertex 1.0574 2.01657 2.57847 + vertex 1.05348 2.01845 2.57936 + endloop + endfacet + facet normal 0.29243 0.164378 0.942053 + outer loop + vertex 1.0574 2.01657 2.57847 + vertex 1.05792 2.02099 2.57753 + vertex 1.05348 2.01845 2.57936 + endloop + endfacet + facet normal 0.286095 0.175443 0.942003 + outer loop + vertex 1.05348 2.01845 2.57936 + vertex 1.05792 2.02099 2.57753 + vertex 1.0539 2.02293 2.57839 + endloop + endfacet + facet normal 0.285901 0.174976 0.942149 + outer loop + vertex 1.05792 2.02099 2.57753 + vertex 1.05604 2.02649 2.57708 + vertex 1.0539 2.02293 2.57839 + endloop + endfacet + facet normal 0.244445 0.202239 0.948339 + outer loop + vertex 1.0539 2.02293 2.57839 + vertex 1.05604 2.02649 2.57708 + vertex 1.05194 2.02601 2.57824 + endloop + endfacet + facet normal 0.335257 0.146683 0.930638 + outer loop + vertex 1.05887 2.01343 2.57843 + vertex 1.06118 2.01672 2.57708 + vertex 1.0574 2.01657 2.57847 + endloop + endfacet + facet normal 0.357623 0.122649 0.925777 + outer loop + vertex 1.0583 2.00889 2.57925 + vertex 1.06205 2.01174 2.57742 + vertex 1.05887 2.01343 2.57843 + endloop + endfacet + facet normal 0.370198 0.10437 0.923071 + outer loop + vertex 1.06267 2.00666 2.57775 + vertex 1.06205 2.01174 2.57742 + vertex 1.0583 2.00889 2.57925 + endloop + endfacet + facet normal 0.366862 0.108499 0.923926 + outer loop + vertex 1.05946 2.00323 2.57946 + vertex 1.0583 2.00889 2.57925 + vertex 1.05531 2.00493 2.5809 + endloop + endfacet + facet normal 0.358061 0.106344 0.927622 + outer loop + vertex 1.05531 2.00493 2.5809 + vertex 1.0522 2.00169 2.58247 + vertex 1.05631 1.99992 2.58109 + endloop + endfacet + facet normal 0.366677 0.107927 0.924067 + outer loop + vertex 1.05631 1.99992 2.58109 + vertex 1.05946 2.00323 2.57946 + vertex 1.05531 2.00493 2.5809 + endloop + endfacet + facet normal 0.382636 0.090442 0.919462 + outer loop + vertex 1.06031 1.99784 2.57963 + vertex 1.05946 2.00323 2.57946 + vertex 1.05631 1.99992 2.58109 + endloop + endfacet + facet normal 0.359541 0.110624 0.926549 + outer loop + vertex 1.0522 2.00169 2.58247 + vertex 1.05336 1.99615 2.58269 + vertex 1.05631 1.99992 2.58109 + endloop + endfacet + facet normal 0.376228 0.0954558 0.921597 + outer loop + vertex 1.05631 1.99992 2.58109 + vertex 1.05336 1.99615 2.58269 + vertex 1.05712 1.99585 2.58119 + endloop + endfacet + facet normal 0.372585 0.109825 0.921476 + outer loop + vertex 1.05313 1.99231 2.58324 + vertex 1.05336 1.99615 2.58269 + vertex 1.04998 1.99285 2.58445 + endloop + endfacet + facet normal 0.372106 0.105448 0.922181 + outer loop + vertex 1.04998 1.99285 2.58445 + vertex 1.05276 1.98858 2.58381 + vertex 1.05313 1.99231 2.58324 + endloop + endfacet + facet normal 0.393301 0.102078 0.913726 + outer loop + vertex 1.05276 1.98858 2.58381 + vertex 1.05611 1.99183 2.58201 + vertex 1.05313 1.99231 2.58324 + endloop + endfacet + facet normal 0.393805 0.107325 0.912907 + outer loop + vertex 1.05336 1.99615 2.58269 + vertex 1.05313 1.99231 2.58324 + vertex 1.05611 1.99183 2.58201 + endloop + endfacet + facet normal 0.38916 0.11781 0.913606 + outer loop + vertex 1.04921 1.98866 2.58532 + vertex 1.05276 1.98858 2.58381 + vertex 1.04998 1.99285 2.58445 + endloop + endfacet + facet normal 0.298996 0.137598 0.944282 + outer loop + vertex 1.04559 1.99473 2.58576 + vertex 1.04282 1.99063 2.58723 + vertex 1.04684 1.9907 2.58595 + endloop + endfacet + facet normal 0.257477 0.168241 0.951525 + outer loop + vertex 1.04081 1.99609 2.58681 + vertex 1.04282 1.99063 2.58723 + vertex 1.04559 1.99473 2.58576 + endloop + endfacet + facet normal 0.250434 0.138347 0.958198 + outer loop + vertex 1.04559 1.99473 2.58576 + vertex 1.04411 1.99884 2.58555 + vertex 1.04081 1.99609 2.58681 + endloop + endfacet + facet normal 0.299284 0.155092 0.941475 + outer loop + vertex 1.04411 1.99884 2.58555 + vertex 1.04559 1.99473 2.58576 + vertex 1.04836 1.9988 2.58421 + endloop + endfacet + facet normal 0.298467 0.174703 0.938294 + outer loop + vertex 1.04411 1.99884 2.58555 + vertex 1.04836 1.9988 2.58421 + vertex 1.04423 2.00349 2.58465 + endloop + endfacet + facet normal 0.370339 0.123372 0.920668 + outer loop + vertex 1.04599 1.98656 2.58682 + vertex 1.04671 1.98168 2.58718 + vertex 1.04988 1.98474 2.5855 + endloop + endfacet + facet normal 0.36326 0.104527 0.925806 + outer loop + vertex 1.04988 1.98474 2.5855 + vertex 1.04921 1.98866 2.58532 + vertex 1.04599 1.98656 2.58682 + endloop + endfacet + facet normal 0.409911 0.0957951 0.907081 + outer loop + vertex 1.05407 1.97833 2.58433 + vertex 1.0536 1.98328 2.58403 + vertex 1.05044 1.97995 2.5858 + endloop + endfacet + facet normal 0.389384 0.108475 0.914666 + outer loop + vertex 1.04921 1.98866 2.58532 + vertex 1.04988 1.98474 2.5855 + vertex 1.05276 1.98858 2.58381 + endloop + endfacet + facet normal 0.402546 0.0909729 0.910868 + outer loop + vertex 1.05676 1.98667 2.58224 + vertex 1.05611 1.99183 2.58201 + vertex 1.05276 1.98858 2.58381 + endloop + endfacet + facet normal 0.376203 0.0947015 0.921685 + outer loop + vertex 1.05712 1.99585 2.58119 + vertex 1.05336 1.99615 2.58269 + vertex 1.05611 1.99183 2.58201 + endloop + endfacet + facet normal 0.385462 0.0971893 0.917591 + outer loop + vertex 1.05712 1.99585 2.58119 + vertex 1.06031 1.99784 2.57963 + vertex 1.05631 1.99992 2.58109 + endloop + endfacet + facet normal 0.421186 0.0780693 0.903608 + outer loop + vertex 1.05931 1.99378 2.58043 + vertex 1.05991 1.9899 2.58049 + vertex 1.06278 1.99376 2.57882 + endloop + endfacet + facet normal 0.372328 0.109528 0.921616 + outer loop + vertex 1.05946 2.00323 2.57946 + vertex 1.06267 2.00666 2.57775 + vertex 1.0583 2.00889 2.57925 + endloop + endfacet + facet normal 0.390233 0.10626 0.914564 + outer loop + vertex 1.06205 2.01174 2.57742 + vertex 1.06267 2.00666 2.57775 + vertex 1.06581 2.00997 2.57603 + endloop + endfacet + facet normal 0.359562 0.127117 0.924422 + outer loop + vertex 1.06205 2.01174 2.57742 + vertex 1.06118 2.01672 2.57708 + vertex 1.05887 2.01343 2.57843 + endloop + endfacet + facet normal 0.385355 0.119381 0.915013 + outer loop + vertex 1.06434 2.01876 2.57559 + vertex 1.06509 2.01484 2.57578 + vertex 1.06788 2.01869 2.57411 + endloop + endfacet + facet normal 0.385 0.130678 0.913618 + outer loop + vertex 1.06434 2.01876 2.57559 + vertex 1.06788 2.01869 2.57411 + vertex 1.06509 2.02289 2.57468 + endloop + endfacet + facet normal 0.362177 0.113945 0.925118 + outer loop + vertex 1.06509 2.02289 2.57468 + vertex 1.06788 2.01869 2.57411 + vertex 1.06824 2.0224 2.57351 + endloop + endfacet + facet normal 0.334378 0.156708 0.929319 + outer loop + vertex 1.05792 2.02099 2.57753 + vertex 1.0574 2.01657 2.57847 + vertex 1.06118 2.01672 2.57708 + endloop + endfacet + facet normal 0.290067 0.176273 0.940632 + outer loop + vertex 1.05604 2.02649 2.57708 + vertex 1.05792 2.02099 2.57753 + vertex 1.06071 2.02481 2.57596 + endloop + endfacet + facet normal 0.352359 0.139198 0.925455 + outer loop + vertex 1.06434 2.01876 2.57559 + vertex 1.06509 2.02289 2.57468 + vertex 1.06196 2.02082 2.57619 + endloop + endfacet + facet normal 0.363552 0.128895 0.922614 + outer loop + vertex 1.06824 2.0224 2.57351 + vertex 1.06845 2.02618 2.5729 + vertex 1.06509 2.02289 2.57468 + endloop + endfacet + facet normal 0.309091 0.184982 0.932869 + outer loop + vertex 1.05921 2.02891 2.57571 + vertex 1.06344 2.02875 2.57435 + vertex 1.05923 2.03362 2.57478 + endloop + endfacet + facet normal 0.268778 0.187484 0.94478 + outer loop + vertex 1.05921 2.02891 2.57571 + vertex 1.05923 2.03362 2.57478 + vertex 1.05624 2.03077 2.57619 + endloop + endfacet + facet normal 0.266916 0.184192 0.945954 + outer loop + vertex 1.05624 2.03077 2.57619 + vertex 1.05604 2.02649 2.57708 + vertex 1.05921 2.02891 2.57571 + endloop + endfacet + facet normal 0.285206 0.15976 0.945058 + outer loop + vertex 1.06071 2.02481 2.57596 + vertex 1.05921 2.02891 2.57571 + vertex 1.05604 2.02649 2.57708 + endloop + endfacet + facet normal 0.213635 0.189175 0.958422 + outer loop + vertex 1.05624 2.03077 2.57619 + vertex 1.05163 2.03071 2.57723 + vertex 1.05604 2.02649 2.57708 + endloop + endfacet + facet normal 0.24165 0.218951 0.945339 + outer loop + vertex 1.05163 2.03071 2.57723 + vertex 1.05194 2.02601 2.57824 + vertex 1.05604 2.02649 2.57708 + endloop + endfacet + facet normal 0.309436 0.168072 0.935949 + outer loop + vertex 1.05921 2.02891 2.57571 + vertex 1.06071 2.02481 2.57596 + vertex 1.06344 2.02875 2.57435 + endloop + endfacet + facet normal 0.255385 0.184134 0.949143 + outer loop + vertex 1.05923 2.03362 2.57478 + vertex 1.06225 2.03648 2.57341 + vertex 1.0594 2.03827 2.57383 + endloop + endfacet + facet normal 0.318104 0.147292 0.936544 + outer loop + vertex 1.06724 2.03156 2.57259 + vertex 1.06608 2.03658 2.57219 + vertex 1.06367 2.03337 2.57351 + endloop + endfacet + facet normal 0.2562 0.185549 0.948648 + outer loop + vertex 1.06225 2.03648 2.57341 + vertex 1.06274 2.04068 2.57245 + vertex 1.0594 2.03827 2.57383 + endloop + endfacet + facet normal 0.244768 0.195578 0.949651 + outer loop + vertex 1.06074 2.04599 2.57188 + vertex 1.06274 2.04068 2.57245 + vertex 1.06554 2.04465 2.57091 + endloop + endfacet + facet normal 0.242243 0.184412 0.952529 + outer loop + vertex 1.06554 2.04465 2.57091 + vertex 1.06404 2.0486 2.57053 + vertex 1.06074 2.04599 2.57188 + endloop + endfacet + facet normal 0.257015 0.189569 0.947632 + outer loop + vertex 1.06404 2.0486 2.57053 + vertex 1.06554 2.04465 2.57091 + vertex 1.06827 2.04872 2.56936 + endloop + endfacet + facet normal 0.240701 0.19419 0.950975 + outer loop + vertex 1.06274 2.04068 2.57245 + vertex 1.06074 2.04599 2.57188 + vertex 1.05809 2.04206 2.57335 + endloop + endfacet + facet normal 0.243019 0.203661 0.948401 + outer loop + vertex 1.0594 2.03827 2.57383 + vertex 1.06274 2.04068 2.57245 + vertex 1.05809 2.04206 2.57335 + endloop + endfacet + facet normal 0.208886 0.21665 0.95364 + outer loop + vertex 1.05809 2.04206 2.57335 + vertex 1.06074 2.04599 2.57188 + vertex 1.05657 2.04559 2.57288 + endloop + endfacet + facet normal 0.192781 0.210335 0.958433 + outer loop + vertex 1.05809 2.04206 2.57335 + vertex 1.05657 2.04559 2.57288 + vertex 1.05438 2.04314 2.57386 + endloop + endfacet + facet normal 0.193555 0.213375 0.957605 + outer loop + vertex 1.05461 2.03845 2.57486 + vertex 1.05809 2.04206 2.57335 + vertex 1.05438 2.04314 2.57386 + endloop + endfacet + facet normal 0.213115 0.194473 0.957477 + outer loop + vertex 1.0594 2.03827 2.57383 + vertex 1.05809 2.04206 2.57335 + vertex 1.05461 2.03845 2.57486 + endloop + endfacet + facet normal 0.21315 0.187695 0.958821 + outer loop + vertex 1.05461 2.03845 2.57486 + vertex 1.05923 2.03362 2.57478 + vertex 1.0594 2.03827 2.57383 + endloop + endfacet + facet normal 0.20578 0.23797 0.949223 + outer loop + vertex 1.05674 2.0497 2.57181 + vertex 1.05657 2.04559 2.57288 + vertex 1.06074 2.04599 2.57188 + endloop + endfacet + facet normal 0.302707 0.154605 0.94046 + outer loop + vertex 1.06939 2.03873 2.57076 + vertex 1.07017 2.04313 2.56979 + vertex 1.06683 2.04073 2.57126 + endloop + endfacet + facet normal 0.30671 0.146103 0.940523 + outer loop + vertex 1.07425 2.04331 2.56843 + vertex 1.07291 2.04726 2.56826 + vertex 1.07017 2.04313 2.56979 + endloop + endfacet + facet normal 0.308167 0.129029 0.942541 + outer loop + vertex 1.07017 2.04313 2.56979 + vertex 1.07346 2.03863 2.56933 + vertex 1.07425 2.04331 2.56843 + endloop + endfacet + facet normal 0.349822 0.119472 0.929167 + outer loop + vertex 1.07346 2.03863 2.56933 + vertex 1.07745 2.04147 2.56746 + vertex 1.07425 2.04331 2.56843 + endloop + endfacet + facet normal 0.34984 0.119509 0.929155 + outer loop + vertex 1.07745 2.04147 2.56746 + vertex 1.07686 2.04623 2.56707 + vertex 1.07425 2.04331 2.56843 + endloop + endfacet + facet normal 0.362944 0.0993234 0.926502 + outer loop + vertex 1.07813 2.03601 2.56778 + vertex 1.07745 2.04147 2.56746 + vertex 1.07346 2.03863 2.56933 + endloop + endfacet + facet normal 0.372462 0.119996 0.920257 + outer loop + vertex 1.07436 2.03312 2.56968 + vertex 1.07813 2.03601 2.56778 + vertex 1.07346 2.03863 2.56933 + endloop + endfacet + facet normal 0.353848 0.117438 0.927901 + outer loop + vertex 1.07436 2.03312 2.56968 + vertex 1.07346 2.03863 2.56933 + vertex 1.07032 2.03473 2.57102 + endloop + endfacet + facet normal 0.356208 0.124948 0.926015 + outer loop + vertex 1.07133 2.02992 2.57128 + vertex 1.07436 2.03312 2.56968 + vertex 1.07032 2.03473 2.57102 + endloop + endfacet + facet normal 0.345902 0.122998 0.930174 + outer loop + vertex 1.07032 2.03473 2.57102 + vertex 1.06724 2.03156 2.57259 + vertex 1.07133 2.02992 2.57128 + endloop + endfacet + facet normal 0.34889 0.13239 0.927765 + outer loop + vertex 1.06724 2.03156 2.57259 + vertex 1.06845 2.02618 2.5729 + vertex 1.07133 2.02992 2.57128 + endloop + endfacet + facet normal 0.322414 0.148159 0.934932 + outer loop + vertex 1.06608 2.03658 2.57219 + vertex 1.06724 2.03156 2.57259 + vertex 1.07032 2.03473 2.57102 + endloop + endfacet + facet normal 0.317347 0.134113 0.938778 + outer loop + vertex 1.07032 2.03473 2.57102 + vertex 1.06939 2.03873 2.57076 + vertex 1.06608 2.03658 2.57219 + endloop + endfacet + facet normal 0.332176 0.137185 0.933188 + outer loop + vertex 1.06939 2.03873 2.57076 + vertex 1.07032 2.03473 2.57102 + vertex 1.07346 2.03863 2.56933 + endloop + endfacet + facet normal 0.33191 0.147546 0.9317 + outer loop + vertex 1.06939 2.03873 2.57076 + vertex 1.07346 2.03863 2.56933 + vertex 1.07017 2.04313 2.56979 + endloop + endfacet + facet normal 0.31915 0.150104 0.935741 + outer loop + vertex 1.07425 2.04331 2.56843 + vertex 1.07686 2.04623 2.56707 + vertex 1.07291 2.04726 2.56826 + endloop + endfacet + facet normal 0.318778 0.148166 0.936177 + outer loop + vertex 1.07686 2.04623 2.56707 + vertex 1.07555 2.05122 2.56673 + vertex 1.07291 2.04726 2.56826 + endloop + endfacet + facet normal 0.335335 0.152096 0.92974 + outer loop + vertex 1.07555 2.05122 2.56673 + vertex 1.07686 2.04623 2.56707 + vertex 1.07977 2.04955 2.56548 + endloop + endfacet + facet normal 0.371497 0.116275 0.921124 + outer loop + vertex 1.07977 2.04955 2.56548 + vertex 1.07686 2.04623 2.56707 + vertex 1.08056 2.04478 2.56576 + endloop + endfacet + facet normal 0.402926 0.120649 0.907246 + outer loop + vertex 1.08056 2.04478 2.56576 + vertex 1.08353 2.04825 2.56399 + vertex 1.07977 2.04955 2.56548 + endloop + endfacet + facet normal 0.400902 0.112602 0.909175 + outer loop + vertex 1.08353 2.04825 2.56399 + vertex 1.0825 2.05352 2.56379 + vertex 1.07977 2.04955 2.56548 + endloop + endfacet + facet normal 0.428682 0.0941648 0.898535 + outer loop + vertex 1.08418 2.04325 2.5642 + vertex 1.08353 2.04825 2.56399 + vertex 1.08056 2.04478 2.56576 + endloop + endfacet + facet normal 0.430734 0.100723 0.89684 + outer loop + vertex 1.0812 2.03988 2.56601 + vertex 1.08418 2.04325 2.5642 + vertex 1.08056 2.04478 2.56576 + endloop + endfacet + facet normal 0.395694 0.0969812 0.913248 + outer loop + vertex 1.08056 2.04478 2.56576 + vertex 1.07745 2.04147 2.56746 + vertex 1.0812 2.03988 2.56601 + endloop + endfacet + facet normal 0.397596 0.102814 0.911782 + outer loop + vertex 1.07745 2.04147 2.56746 + vertex 1.07813 2.03601 2.56778 + vertex 1.0812 2.03988 2.56601 + endloop + endfacet + facet normal 0.413808 0.0874004 0.906159 + outer loop + vertex 1.0812 2.03988 2.56601 + vertex 1.07813 2.03601 2.56778 + vertex 1.08187 2.03579 2.5661 + endloop + endfacet + facet normal 0.447195 0.092519 0.889639 + outer loop + vertex 1.08187 2.03579 2.5661 + vertex 1.08503 2.03779 2.5643 + vertex 1.0812 2.03988 2.56601 + endloop + endfacet + facet normal 0.444445 0.0858282 0.891685 + outer loop + vertex 1.08503 2.03779 2.5643 + vertex 1.08418 2.04325 2.5642 + vertex 1.0812 2.03988 2.56601 + endloop + endfacet + facet normal 0.373106 0.121592 0.919787 + outer loop + vertex 1.07686 2.04623 2.56707 + vertex 1.07745 2.04147 2.56746 + vertex 1.08056 2.04478 2.56576 + endloop + endfacet + facet normal 0.254971 0.21478 0.942793 + outer loop + vertex 1.06404 2.0486 2.57053 + vertex 1.06827 2.04872 2.56936 + vertex 1.06409 2.05317 2.56948 + endloop + endfacet + facet normal 0.246351 0.214 0.945259 + outer loop + vertex 1.06867 2.05303 2.5684 + vertex 1.07162 2.05583 2.567 + vertex 1.06711 2.05613 2.56811 + endloop + endfacet + facet normal 0.246522 0.234783 0.940268 + outer loop + vertex 1.06677 2.06063 2.56708 + vertex 1.06711 2.05613 2.56811 + vertex 1.07162 2.05583 2.567 + endloop + endfacet + facet normal 0.215187 0.202859 0.955271 + outer loop + vertex 1.07145 2.06045 2.56606 + vertex 1.06677 2.06063 2.56708 + vertex 1.07162 2.05583 2.567 + endloop + endfacet + facet normal 0.249416 0.202401 0.947009 + outer loop + vertex 1.07145 2.06045 2.56606 + vertex 1.07162 2.05583 2.567 + vertex 1.07463 2.05861 2.56562 + endloop + endfacet + facet normal 0.252216 0.207685 0.945121 + outer loop + vertex 1.07463 2.05861 2.56562 + vertex 1.07432 2.06333 2.56466 + vertex 1.07145 2.06045 2.56606 + endloop + endfacet + facet normal 0.130091 0.270299 0.953947 + outer loop + vertex 1.05377 2.06317 2.56859 + vertex 1.05622 2.06657 2.56729 + vertex 1.05179 2.06577 2.56812 + endloop + endfacet + facet normal 0.154088 0.260856 0.953001 + outer loop + vertex 1.06198 2.06057 2.56806 + vertex 1.06193 2.06475 2.56692 + vertex 1.05783 2.06198 2.56834 + endloop + endfacet + facet normal 0.131381 0.264661 0.95535 + outer loop + vertex 1.05187 2.06987 2.56697 + vertex 1.05179 2.06577 2.56812 + vertex 1.05622 2.06657 2.56729 + endloop + endfacet + facet normal 0.13366 0.263332 0.955401 + outer loop + vertex 1.05434 2.0733 2.56569 + vertex 1.05626 2.07069 2.56614 + vertex 1.05877 2.0741 2.56485 + endloop + endfacet + facet normal 0.132193 0.26052 0.956376 + outer loop + vertex 1.05187 2.06987 2.56697 + vertex 1.05039 2.07445 2.56593 + vertex 1.04634 2.07149 2.5673 + endloop + endfacet + facet normal 0.135085 0.256835 0.956968 + outer loop + vertex 1.04644 2.07563 2.56617 + vertex 1.04634 2.07149 2.5673 + vertex 1.05039 2.07445 2.56593 + endloop + endfacet + facet normal 0.13406 0.256894 0.957096 + outer loop + vertex 1.04644 2.07563 2.56617 + vertex 1.04201 2.07487 2.567 + vertex 1.04634 2.07149 2.5673 + endloop + endfacet + facet normal 0.132692 0.255202 0.957739 + outer loop + vertex 1.04201 2.07487 2.567 + vertex 1.04191 2.07071 2.56812 + vertex 1.04634 2.07149 2.5673 + endloop + endfacet + facet normal 0.134075 0.25682 0.957114 + outer loop + vertex 1.04644 2.07563 2.56617 + vertex 1.04449 2.0783 2.56573 + vertex 1.04201 2.07487 2.567 + endloop + endfacet + facet normal 0.13648 0.258446 0.956336 + outer loop + vertex 1.04449 2.0783 2.56573 + vertex 1.04644 2.07563 2.56617 + vertex 1.0489 2.07904 2.5649 + endloop + endfacet + facet normal 0.13569 0.262145 0.955441 + outer loop + vertex 1.04449 2.0783 2.56573 + vertex 1.0489 2.07904 2.5649 + vertex 1.04455 2.0824 2.56459 + endloop + endfacet + facet normal 0.134892 0.262185 0.955543 + outer loop + vertex 1.0405 2.07949 2.56597 + vertex 1.04449 2.0783 2.56573 + vertex 1.04455 2.0824 2.56459 + endloop + endfacet + facet normal 0.136532 0.263198 0.955032 + outer loop + vertex 1.04455 2.0824 2.56459 + vertex 1.0489 2.07904 2.5649 + vertex 1.04897 2.08314 2.56376 + endloop + endfacet + facet normal 0.135365 0.268657 0.953677 + outer loop + vertex 1.04897 2.08314 2.56376 + vertex 1.04699 2.08579 2.56329 + vertex 1.04455 2.0824 2.56459 + endloop + endfacet + facet normal 0.134441 0.269304 0.953625 + outer loop + vertex 1.04455 2.0824 2.56459 + vertex 1.04699 2.08579 2.56329 + vertex 1.04298 2.08697 2.56353 + endloop + endfacet + facet normal 0.135048 0.26948 0.95349 + outer loop + vertex 1.04455 2.0824 2.56459 + vertex 1.04298 2.08697 2.56353 + vertex 1.03895 2.08406 2.56492 + endloop + endfacet + facet normal 0.136247 0.275839 0.951499 + outer loop + vertex 1.04699 2.08579 2.56329 + vertex 1.04701 2.08988 2.5621 + vertex 1.04298 2.08697 2.56353 + endloop + endfacet + facet normal 0.135515 0.27677 0.951333 + outer loop + vertex 1.04298 2.08697 2.56353 + vertex 1.04701 2.08988 2.5621 + vertex 1.04138 2.09152 2.56243 + endloop + endfacet + facet normal 0.135707 0.276826 0.951289 + outer loop + vertex 1.04298 2.08697 2.56353 + vertex 1.04138 2.09152 2.56243 + vertex 1.03897 2.08814 2.56376 + endloop + endfacet + facet normal 0.136161 0.279136 0.950549 + outer loop + vertex 1.04701 2.08988 2.5621 + vertex 1.04542 2.09444 2.56099 + vertex 1.04138 2.09152 2.56243 + endloop + endfacet + facet normal 0.136079 0.279241 0.95053 + outer loop + vertex 1.0414 2.09561 2.56122 + vertex 1.04138 2.09152 2.56243 + vertex 1.04542 2.09444 2.56099 + endloop + endfacet + facet normal 0.13542 0.276826 0.95133 + outer loop + vertex 1.04542 2.09444 2.56099 + vertex 1.04388 2.099 2.55989 + vertex 1.0414 2.09561 2.56122 + endloop + endfacet + facet normal 0.134551 0.277442 0.951274 + outer loop + vertex 1.03942 2.09824 2.56074 + vertex 1.0414 2.09561 2.56122 + vertex 1.04388 2.099 2.55989 + endloop + endfacet + facet normal 0.136099 0.270355 0.953092 + outer loop + vertex 1.03942 2.09824 2.56074 + vertex 1.04388 2.099 2.55989 + vertex 1.03954 2.10235 2.55955 + endloop + endfacet + facet normal 0.132654 0.270578 0.953515 + outer loop + vertex 1.03541 2.09941 2.56096 + vertex 1.03942 2.09824 2.56074 + vertex 1.03954 2.10235 2.55955 + endloop + endfacet + facet normal 0.135066 0.269069 0.953603 + outer loop + vertex 1.03954 2.10235 2.55955 + vertex 1.04388 2.099 2.55989 + vertex 1.04401 2.10312 2.5587 + endloop + endfacet + facet normal 0.136878 0.260802 0.955639 + outer loop + vertex 1.04401 2.10312 2.5587 + vertex 1.04208 2.1058 2.55825 + vertex 1.03954 2.10235 2.55955 + endloop + endfacet + facet normal 0.134878 0.262235 0.955532 + outer loop + vertex 1.03954 2.10235 2.55955 + vertex 1.04208 2.1058 2.55825 + vertex 1.03807 2.10696 2.5585 + endloop + endfacet + facet normal 0.131259 0.261258 0.956303 + outer loop + vertex 1.03954 2.10235 2.55955 + vertex 1.03807 2.10696 2.5585 + vertex 1.03392 2.10397 2.55988 + endloop + endfacet + facet normal 0.13594 0.266162 0.954295 + outer loop + vertex 1.04208 2.1058 2.55825 + vertex 1.04208 2.10995 2.55709 + vertex 1.03807 2.10696 2.5585 + endloop + endfacet + facet normal 0.130478 0.272959 0.953136 + outer loop + vertex 1.03807 2.10696 2.5585 + vertex 1.04208 2.10995 2.55709 + vertex 1.03646 2.11152 2.55741 + endloop + endfacet + facet normal 0.13888 0.262135 0.954986 + outer loop + vertex 1.04401 2.10312 2.5587 + vertex 1.04648 2.10657 2.5574 + vertex 1.04208 2.1058 2.55825 + endloop + endfacet + facet normal 0.137385 0.263178 0.954915 + outer loop + vertex 1.048 2.10192 2.55846 + vertex 1.04648 2.10657 2.5574 + vertex 1.04401 2.10312 2.5587 + endloop + endfacet + facet normal 0.145952 0.265539 0.952988 + outer loop + vertex 1.048 2.10192 2.55846 + vertex 1.05203 2.10484 2.55703 + vertex 1.04648 2.10657 2.5574 + endloop + endfacet + facet normal 0.141419 0.271346 0.952036 + outer loop + vertex 1.05199 2.1007 2.55822 + vertex 1.05203 2.10484 2.55703 + vertex 1.048 2.10192 2.55846 + endloop + endfacet + facet normal 0.14218 0.274014 0.951158 + outer loop + vertex 1.0495 2.09733 2.55956 + vertex 1.05199 2.1007 2.55822 + vertex 1.048 2.10192 2.55846 + endloop + endfacet + facet normal 0.13622 0.272382 0.952498 + outer loop + vertex 1.0495 2.09733 2.55956 + vertex 1.048 2.10192 2.55846 + vertex 1.04388 2.099 2.55989 + endloop + endfacet + facet normal 0.139509 0.275922 0.951002 + outer loop + vertex 1.05395 2.09805 2.5587 + vertex 1.05199 2.1007 2.55822 + vertex 1.0495 2.09733 2.55956 + endloop + endfacet + facet normal 0.13837 0.281255 0.949605 + outer loop + vertex 1.0495 2.09733 2.55956 + vertex 1.05389 2.094 2.55991 + vertex 1.05395 2.09805 2.5587 + endloop + endfacet + facet normal 0.136694 0.279135 0.950473 + outer loop + vertex 1.04944 2.09326 2.56076 + vertex 1.05389 2.094 2.55991 + vertex 1.0495 2.09733 2.55956 + endloop + endfacet + facet normal 0.136308 0.279155 0.950522 + outer loop + vertex 1.04542 2.09444 2.56099 + vertex 1.04944 2.09326 2.56076 + vertex 1.0495 2.09733 2.55956 + endloop + endfacet + facet normal 0.136538 0.27985 0.950285 + outer loop + vertex 1.04944 2.09326 2.56076 + vertex 1.05144 2.09063 2.56125 + vertex 1.05389 2.094 2.55991 + endloop + endfacet + facet normal 0.135947 0.279437 0.950491 + outer loop + vertex 1.05144 2.09063 2.56125 + vertex 1.04944 2.09326 2.56076 + vertex 1.04701 2.08988 2.5621 + endloop + endfacet + facet normal 0.136555 0.276671 0.951213 + outer loop + vertex 1.05144 2.09063 2.56125 + vertex 1.04701 2.08988 2.5621 + vertex 1.05142 2.08655 2.56244 + endloop + endfacet + facet normal 0.134339 0.276769 0.9515 + outer loop + vertex 1.05144 2.09063 2.56125 + vertex 1.05142 2.08655 2.56244 + vertex 1.05547 2.08949 2.56101 + endloop + endfacet + facet normal 0.141291 0.277129 0.950388 + outer loop + vertex 1.05395 2.09805 2.5587 + vertex 1.05639 2.10143 2.55735 + vertex 1.05199 2.1007 2.55822 + endloop + endfacet + facet normal 0.13677 0.280292 0.950121 + outer loop + vertex 1.05794 2.0969 2.55846 + vertex 1.05639 2.10143 2.55735 + vertex 1.05395 2.09805 2.5587 + endloop + endfacet + facet normal 0.1384 0.280758 0.949747 + outer loop + vertex 1.05794 2.0969 2.55846 + vertex 1.06194 2.09983 2.55702 + vertex 1.05639 2.10143 2.55735 + endloop + endfacet + facet normal 0.139483 0.284785 0.948389 + outer loop + vertex 1.06194 2.09983 2.55702 + vertex 1.06032 2.10432 2.5559 + vertex 1.05639 2.10143 2.55735 + endloop + endfacet + facet normal 0.144941 0.277963 0.949594 + outer loop + vertex 1.05638 2.10551 2.55616 + vertex 1.05639 2.10143 2.55735 + vertex 1.06032 2.10432 2.5559 + endloop + endfacet + facet normal 0.147877 0.277844 0.949176 + outer loop + vertex 1.05638 2.10551 2.55616 + vertex 1.05203 2.10484 2.55703 + vertex 1.05639 2.10143 2.55735 + endloop + endfacet + facet normal 0.147891 0.277777 0.949193 + outer loop + vertex 1.05638 2.10551 2.55616 + vertex 1.05434 2.10821 2.55568 + vertex 1.05203 2.10484 2.55703 + endloop + endfacet + facet normal 0.142553 0.27129 0.951883 + outer loop + vertex 1.05203 2.10484 2.55703 + vertex 1.05199 2.1007 2.55822 + vertex 1.05639 2.10143 2.55735 + endloop + endfacet + facet normal 0.138973 0.268808 0.953115 + outer loop + vertex 1.04388 2.099 2.55989 + vertex 1.048 2.10192 2.55846 + vertex 1.04401 2.10312 2.5587 + endloop + endfacet + facet normal 0.134799 0.277613 0.951189 + outer loop + vertex 1.0414 2.09561 2.56122 + vertex 1.03942 2.09824 2.56074 + vertex 1.03697 2.09485 2.56208 + endloop + endfacet + facet normal 0.137626 0.277448 0.950832 + outer loop + vertex 1.04388 2.099 2.55989 + vertex 1.04542 2.09444 2.56099 + vertex 1.0495 2.09733 2.55956 + endloop + endfacet + facet normal 0.134421 0.27931 0.950745 + outer loop + vertex 1.0414 2.09561 2.56122 + vertex 1.03697 2.09485 2.56208 + vertex 1.04138 2.09152 2.56243 + endloop + endfacet + facet normal 0.134175 0.278996 0.950872 + outer loop + vertex 1.03697 2.09485 2.56208 + vertex 1.03697 2.09076 2.56328 + vertex 1.04138 2.09152 2.56243 + endloop + endfacet + facet normal 0.136315 0.279181 0.950514 + outer loop + vertex 1.04944 2.09326 2.56076 + vertex 1.04542 2.09444 2.56099 + vertex 1.04701 2.08988 2.5621 + endloop + endfacet + facet normal 0.13591 0.275853 0.951543 + outer loop + vertex 1.04701 2.08988 2.5621 + vertex 1.04699 2.08579 2.56329 + vertex 1.05142 2.08655 2.56244 + endloop + endfacet + facet normal 0.137216 0.269933 0.953052 + outer loop + vertex 1.04897 2.08314 2.56376 + vertex 1.05142 2.08655 2.56244 + vertex 1.04699 2.08579 2.56329 + endloop + endfacet + facet normal 0.137145 0.269983 0.953048 + outer loop + vertex 1.05297 2.08198 2.56351 + vertex 1.05142 2.08655 2.56244 + vertex 1.04897 2.08314 2.56376 + endloop + endfacet + facet normal 0.132928 0.268775 0.953986 + outer loop + vertex 1.05297 2.08198 2.56351 + vertex 1.05704 2.08497 2.5621 + vertex 1.05142 2.08655 2.56244 + endloop + endfacet + facet normal 0.135692 0.259002 0.956298 + outer loop + vertex 1.05039 2.07445 2.56593 + vertex 1.0489 2.07904 2.5649 + vertex 1.04644 2.07563 2.56617 + endloop + endfacet + facet normal 0.135319 0.263262 0.955187 + outer loop + vertex 1.0489 2.07904 2.5649 + vertex 1.05297 2.08198 2.56351 + vertex 1.04897 2.08314 2.56376 + endloop + endfacet + facet normal 0.134282 0.267068 0.954276 + outer loop + vertex 1.05696 2.08085 2.56327 + vertex 1.05704 2.08497 2.5621 + vertex 1.05297 2.08198 2.56351 + endloop + endfacet + facet normal 0.134485 0.259688 0.956282 + outer loop + vertex 1.05434 2.0733 2.56569 + vertex 1.05877 2.0741 2.56485 + vertex 1.05446 2.07741 2.56456 + endloop + endfacet + facet normal 0.142019 0.252382 0.957149 + outer loop + vertex 1.06446 2.0723 2.56448 + vertex 1.06293 2.07706 2.56345 + vertex 1.05877 2.0741 2.56485 + endloop + endfacet + facet normal 0.134042 0.261961 0.955724 + outer loop + vertex 1.0589 2.07824 2.56371 + vertex 1.06142 2.08168 2.56241 + vertex 1.05696 2.08085 2.56327 + endloop + endfacet + facet normal 0.145896 0.252905 0.956427 + outer loop + vertex 1.06705 2.0757 2.56318 + vertex 1.06713 2.07991 2.56206 + vertex 1.06293 2.07706 2.56345 + endloop + endfacet + facet normal 0.141745 0.259184 0.95537 + outer loop + vertex 1.06964 2.08326 2.56078 + vertex 1.06552 2.08463 2.56102 + vertex 1.06713 2.07991 2.56206 + endloop + endfacet + facet normal 0.144299 0.267306 0.952746 + outer loop + vertex 1.06552 2.08463 2.56102 + vertex 1.06964 2.08326 2.56078 + vertex 1.06963 2.08739 2.55962 + endloop + endfacet + facet normal 0.138651 0.275021 0.951388 + outer loop + vertex 1.06392 2.08918 2.55993 + vertex 1.06552 2.08463 2.56102 + vertex 1.06963 2.08739 2.55962 + endloop + endfacet + facet normal 0.138435 0.274291 0.95163 + outer loop + vertex 1.06963 2.08739 2.55962 + vertex 1.06796 2.09206 2.55852 + vertex 1.06392 2.08918 2.55993 + endloop + endfacet + facet normal 0.135997 0.274231 0.951999 + outer loop + vertex 1.06552 2.08463 2.56102 + vertex 1.06392 2.08918 2.55993 + vertex 1.06148 2.08581 2.56125 + endloop + endfacet + facet normal 0.132832 0.267146 0.954457 + outer loop + vertex 1.05704 2.08497 2.5621 + vertex 1.05696 2.08085 2.56327 + vertex 1.06142 2.08168 2.56241 + endloop + endfacet + facet normal 0.132446 0.276714 0.951781 + outer loop + vertex 1.05949 2.08839 2.56078 + vertex 1.06148 2.08581 2.56125 + vertex 1.06392 2.08918 2.55993 + endloop + endfacet + facet normal 0.13485 0.276122 0.951615 + outer loop + vertex 1.05704 2.08497 2.5621 + vertex 1.05547 2.08949 2.56101 + vertex 1.05142 2.08655 2.56244 + endloop + endfacet + facet normal 0.135372 0.280667 0.950211 + outer loop + vertex 1.05547 2.08949 2.56101 + vertex 1.05389 2.094 2.55991 + vertex 1.05144 2.09063 2.56125 + endloop + endfacet + facet normal 0.137048 0.281324 0.949776 + outer loop + vertex 1.05389 2.094 2.55991 + vertex 1.05794 2.0969 2.55846 + vertex 1.05395 2.09805 2.5587 + endloop + endfacet + facet normal 0.134217 0.286 0.948783 + outer loop + vertex 1.06193 2.09579 2.55823 + vertex 1.06194 2.09983 2.55702 + vertex 1.05794 2.0969 2.55846 + endloop + endfacet + facet normal 0.131195 0.286124 0.949168 + outer loop + vertex 1.06194 2.09983 2.55702 + vertex 1.06193 2.09579 2.55823 + vertex 1.06633 2.09659 2.55738 + endloop + endfacet + facet normal 0.131356 0.28146 0.95054 + outer loop + vertex 1.05949 2.08839 2.56078 + vertex 1.06392 2.08918 2.55993 + vertex 1.05951 2.09243 2.55958 + endloop + endfacet + facet normal 0.131067 0.286677 0.949019 + outer loop + vertex 1.06392 2.09323 2.55873 + vertex 1.06633 2.09659 2.55738 + vertex 1.06193 2.09579 2.55823 + endloop + endfacet + facet normal 0.142764 0.279535 0.949462 + outer loop + vertex 1.07208 2.09069 2.5583 + vertex 1.07204 2.09483 2.55709 + vertex 1.06796 2.09206 2.55852 + endloop + endfacet + facet normal 0.141086 0.283829 0.948439 + outer loop + vertex 1.07449 2.09813 2.55573 + vertex 1.07036 2.09947 2.55595 + vertex 1.07204 2.09483 2.55709 + endloop + endfacet + facet normal 0.132832 0.288246 0.948299 + outer loop + vertex 1.06632 2.10064 2.55616 + vertex 1.06194 2.09983 2.55702 + vertex 1.06633 2.09659 2.55738 + endloop + endfacet + facet normal 0.137797 0.289421 0.947231 + outer loop + vertex 1.06873 2.10401 2.5548 + vertex 1.07036 2.09947 2.55595 + vertex 1.07448 2.10222 2.55451 + endloop + endfacet + facet normal 0.132786 0.288437 0.948247 + outer loop + vertex 1.06632 2.10064 2.55616 + vertex 1.0643 2.10321 2.55566 + vertex 1.06194 2.09983 2.55702 + endloop + endfacet + facet normal 0.138603 0.28452 0.948598 + outer loop + vertex 1.0643 2.10321 2.55566 + vertex 1.06032 2.10432 2.5559 + vertex 1.06194 2.09983 2.55702 + endloop + endfacet + facet normal 0.146873 0.284896 0.947239 + outer loop + vertex 1.06032 2.10432 2.5559 + vertex 1.0586 2.10877 2.55483 + vertex 1.05638 2.10551 2.55616 + endloop + endfacet + facet normal 0.144003 0.29897 0.943335 + outer loop + vertex 1.06417 2.10733 2.55443 + vertex 1.06637 2.11183 2.55267 + vertex 1.06197 2.11107 2.55358 + endloop + endfacet + facet normal 0.152645 0.281068 0.94747 + outer loop + vertex 1.05434 2.10821 2.55568 + vertex 1.05638 2.10551 2.55616 + vertex 1.0586 2.10877 2.55483 + endloop + endfacet + facet normal 0.151483 0.275376 0.949327 + outer loop + vertex 1.05434 2.10821 2.55568 + vertex 1.05033 2.10949 2.55595 + vertex 1.05203 2.10484 2.55703 + endloop + endfacet + facet normal 0.148544 0.27447 0.950053 + outer loop + vertex 1.05203 2.10484 2.55703 + vertex 1.05033 2.10949 2.55595 + vertex 1.04648 2.10657 2.5574 + endloop + endfacet + facet normal 0.138002 0.266084 0.95402 + outer loop + vertex 1.04208 2.10995 2.55709 + vertex 1.04208 2.1058 2.55825 + vertex 1.04648 2.10657 2.5574 + endloop + endfacet + facet normal 0.161472 0.317441 0.934429 + outer loop + vertex 1.04427 2.1133 2.55573 + vertex 1.04638 2.11072 2.55624 + vertex 1.04831 2.11396 2.55481 + endloop + endfacet + facet normal 0.145389 0.38402 0.911807 + outer loop + vertex 1.04427 2.1133 2.55573 + vertex 1.04831 2.11396 2.55481 + vertex 1.04394 2.11694 2.55425 + endloop + endfacet + facet normal 0.139262 0.37587 0.916149 + outer loop + vertex 1.04394 2.11694 2.55425 + vertex 1.04831 2.11396 2.55481 + vertex 1.04761 2.11708 2.55363 + endloop + endfacet + facet normal 0.139603 0.308221 0.941016 + outer loop + vertex 1.04208 2.10995 2.55709 + vertex 1.04027 2.11439 2.55591 + vertex 1.03646 2.11152 2.55741 + endloop + endfacet + facet normal 0.132645 0.275301 0.952163 + outer loop + vertex 1.03405 2.10809 2.55874 + vertex 1.03646 2.11152 2.55741 + vertex 1.03204 2.11067 2.55827 + endloop + endfacet + facet normal 0.134366 0.274129 0.95226 + outer loop + vertex 1.03807 2.10696 2.5585 + vertex 1.03646 2.11152 2.55741 + vertex 1.03405 2.10809 2.55874 + endloop + endfacet + facet normal 0.131069 0.261502 0.956262 + outer loop + vertex 1.03392 2.10397 2.55988 + vertex 1.03807 2.10696 2.5585 + vertex 1.03405 2.10809 2.55874 + endloop + endfacet + facet normal 0.127907 0.270024 0.95432 + outer loop + vertex 1.03139 2.10057 2.56118 + vertex 1.02943 2.10318 2.5607 + vertex 1.02695 2.0998 2.56199 + endloop + endfacet + facet normal 0.133482 0.269507 0.953702 + outer loop + vertex 1.03392 2.10397 2.55988 + vertex 1.03541 2.09941 2.56096 + vertex 1.03954 2.10235 2.55955 + endloop + endfacet + facet normal 0.126512 0.276382 0.952685 + outer loop + vertex 1.03139 2.10057 2.56118 + vertex 1.02695 2.0998 2.56199 + vertex 1.03135 2.09648 2.56237 + endloop + endfacet + facet normal 0.134606 0.277747 0.951177 + outer loop + vertex 1.03942 2.09824 2.56074 + vertex 1.03541 2.09941 2.56096 + vertex 1.03697 2.09485 2.56208 + endloop + endfacet + facet normal 0.13073 0.279129 0.951313 + outer loop + vertex 1.03697 2.09076 2.56328 + vertex 1.03697 2.09485 2.56208 + vertex 1.03294 2.09193 2.56349 + endloop + endfacet + facet normal 0.134468 0.27768 0.951216 + outer loop + vertex 1.03897 2.08814 2.56376 + vertex 1.04138 2.09152 2.56243 + vertex 1.03697 2.09076 2.56328 + endloop + endfacet + facet normal 0.134047 0.270759 0.953269 + outer loop + vertex 1.03895 2.08406 2.56492 + vertex 1.04298 2.08697 2.56353 + vertex 1.03897 2.08814 2.56376 + endloop + endfacet + facet normal 0.127492 0.262108 0.95658 + outer loop + vertex 1.03651 2.08067 2.5662 + vertex 1.03452 2.0833 2.56574 + vertex 1.03204 2.07989 2.56701 + endloop + endfacet + facet normal 0.133514 0.263958 0.955249 + outer loop + vertex 1.03895 2.08406 2.56492 + vertex 1.0405 2.07949 2.56597 + vertex 1.04455 2.0824 2.56459 + endloop + endfacet + facet normal 0.128459 0.257687 0.957651 + outer loop + vertex 1.03651 2.08067 2.5662 + vertex 1.03204 2.07989 2.56701 + vertex 1.03642 2.07652 2.56733 + endloop + endfacet + facet normal 0.133505 0.257222 0.957086 + outer loop + vertex 1.04449 2.0783 2.56573 + vertex 1.0405 2.07949 2.56597 + vertex 1.04201 2.07487 2.567 + endloop + endfacet + facet normal 0.131928 0.255247 0.957833 + outer loop + vertex 1.04191 2.07071 2.56812 + vertex 1.04201 2.07487 2.567 + vertex 1.0379 2.0719 2.56836 + endloop + endfacet + facet normal 0.132131 0.257756 0.957133 + outer loop + vertex 1.04384 2.06804 2.56857 + vertex 1.04634 2.07149 2.5673 + vertex 1.04191 2.07071 2.56812 + endloop + endfacet + facet normal 0.130034 0.261808 0.95632 + outer loop + vertex 1.04373 2.06391 2.56972 + vertex 1.04782 2.06689 2.56834 + vertex 1.04384 2.06804 2.56857 + endloop + endfacet + facet normal 0.126821 0.264747 0.955942 + outer loop + vertex 1.04373 2.06391 2.56972 + vertex 1.04523 2.0593 2.57079 + vertex 1.04933 2.06233 2.56941 + endloop + endfacet + facet normal 0.124249 0.267969 0.955382 + outer loop + vertex 1.04523 2.0593 2.57079 + vertex 1.04926 2.05822 2.57057 + vertex 1.04933 2.06233 2.56941 + endloop + endfacet + facet normal 0.123976 0.266885 0.955721 + outer loop + vertex 1.04926 2.05822 2.57057 + vertex 1.04523 2.0593 2.57079 + vertex 1.04676 2.05472 2.57188 + endloop + endfacet + facet normal 0.129514 0.263699 0.955871 + outer loop + vertex 1.04122 2.06043 2.57101 + vertex 1.03926 2.06311 2.57054 + vertex 1.03676 2.05963 2.57184 + endloop + endfacet + facet normal 0.128014 0.265349 0.955616 + outer loop + vertex 1.03663 2.05558 2.57298 + vertex 1.03676 2.05963 2.57184 + vertex 1.03281 2.05659 2.57321 + endloop + endfacet + facet normal 0.125678 0.267368 0.955363 + outer loop + vertex 1.04676 2.05472 2.57188 + vertex 1.04523 2.0593 2.57079 + vertex 1.04108 2.05621 2.5722 + endloop + endfacet + facet normal 0.126021 0.264759 0.956045 + outer loop + vertex 1.04676 2.05472 2.57188 + vertex 1.0466 2.05068 2.57302 + vertex 1.05108 2.05136 2.57224 + endloop + endfacet + facet normal 0.125325 0.259741 0.957512 + outer loop + vertex 1.0481 2.04736 2.57372 + vertex 1.0466 2.05068 2.57302 + vertex 1.04426 2.04834 2.57396 + endloop + endfacet + facet normal 0.133593 0.246443 0.959905 + outer loop + vertex 1.04986 2.04262 2.57469 + vertex 1.05279 2.04669 2.57324 + vertex 1.0481 2.04736 2.57372 + endloop + endfacet + facet normal 0.1533 0.212953 0.964961 + outer loop + vertex 1.04986 2.04262 2.57469 + vertex 1.05461 2.03845 2.57486 + vertex 1.05438 2.04314 2.57386 + endloop + endfacet + facet normal 0.153894 0.227691 0.961495 + outer loop + vertex 1.05155 2.03531 2.57621 + vertex 1.04971 2.03827 2.57581 + vertex 1.0471 2.03485 2.57703 + endloop + endfacet + facet normal 0.138356 0.239404 0.961012 + outer loop + vertex 1.04971 2.03827 2.57581 + vertex 1.04557 2.03969 2.57605 + vertex 1.0471 2.03485 2.57703 + endloop + endfacet + facet normal 0.116705 0.243878 0.962758 + outer loop + vertex 1.03901 2.03305 2.57855 + vertex 1.04141 2.03669 2.57734 + vertex 1.03692 2.03575 2.57812 + endloop + endfacet + facet normal 0.119462 0.242353 0.962805 + outer loop + vertex 1.03937 2.02845 2.57967 + vertex 1.043 2.0321 2.5783 + vertex 1.03901 2.03305 2.57855 + endloop + endfacet + facet normal 0.115896 0.243641 0.962916 + outer loop + vertex 1.03444 2.02781 2.58042 + vertex 1.03631 2.02508 2.58089 + vertex 1.03937 2.02845 2.57967 + endloop + endfacet + facet normal 0.114123 0.24416 0.962996 + outer loop + vertex 1.0303 2.02887 2.58065 + vertex 1.0254 2.02991 2.58096 + vertex 1.02656 2.02552 2.58194 + endloop + endfacet + facet normal 0.11571 0.242473 0.963233 + outer loop + vertex 1.03188 2.02425 2.58162 + vertex 1.0303 2.02887 2.58065 + vertex 1.02656 2.02552 2.58194 + endloop + endfacet + facet normal 0.105907 0.246182 0.96342 + outer loop + vertex 1.02136 2.03076 2.58121 + vertex 1.01945 2.03333 2.58076 + vertex 1.01685 2.02974 2.58197 + endloop + endfacet + facet normal 0.112669 0.243835 0.96325 + outer loop + vertex 1.02656 2.02552 2.58194 + vertex 1.0254 2.02991 2.58096 + vertex 1.02114 2.02654 2.58232 + endloop + endfacet + facet normal 0.114856 0.238661 0.964287 + outer loop + vertex 1.02764 2.02129 2.58286 + vertex 1.03188 2.02425 2.58162 + vertex 1.02656 2.02552 2.58194 + endloop + endfacet + facet normal 0.115247 0.232144 0.96583 + outer loop + vertex 1.0284 2.01724 2.58374 + vertex 1.02764 2.02129 2.58286 + vertex 1.02455 2.01849 2.5839 + endloop + endfacet + facet normal 0.113547 0.226707 0.967322 + outer loop + vertex 1.02409 2.01425 2.58495 + vertex 1.0284 2.01724 2.58374 + vertex 1.02455 2.01849 2.5839 + endloop + endfacet + facet normal 0.10944 0.223497 0.968541 + outer loop + vertex 1.01947 2.01339 2.58567 + vertex 1.02141 2.01068 2.58607 + vertex 1.02409 2.01425 2.58495 + endloop + endfacet + facet normal 0.103992 0.22226 0.969426 + outer loop + vertex 1.01947 2.01339 2.58567 + vertex 1.01539 2.01447 2.58586 + vertex 1.01684 2.00974 2.58679 + endloop + endfacet + facet normal 0.101605 0.224557 0.969149 + outer loop + vertex 1.01539 2.01447 2.58586 + vertex 1.01394 2.01912 2.58493 + vertex 1.01131 2.01559 2.58603 + endloop + endfacet + facet normal 0.110391 0.231204 0.966622 + outer loop + vertex 1.01975 2.01769 2.58464 + vertex 1.02295 2.02197 2.58325 + vertex 1.0181 2.0223 2.58372 + endloop + endfacet + facet normal 0.100281 0.225518 0.969064 + outer loop + vertex 1.00938 2.0183 2.5856 + vertex 1.01131 2.01559 2.58603 + vertex 1.01394 2.01912 2.58493 + endloop + endfacet + facet normal 0.0948205 0.223407 0.970102 + outer loop + vertex 1.00938 2.0183 2.5856 + vertex 1.00534 2.01944 2.58573 + vertex 1.00676 2.0147 2.58668 + endloop + endfacet + facet normal 0.0960084 0.235885 0.967027 + outer loop + vertex 1.00534 2.01944 2.58573 + vertex 1.00392 2.02407 2.58474 + vertex 1.00129 2.02053 2.58586 + endloop + endfacet + facet normal 0.0959171 0.245677 0.964595 + outer loop + vertex 1.00392 2.02407 2.58474 + vertex 1.00803 2.02718 2.58354 + vertex 1.00419 2.02815 2.58367 + endloop + endfacet + facet normal 0.0963967 0.244122 0.964942 + outer loop + vertex 1.01421 2.02316 2.58394 + vertex 1.01276 2.02654 2.58323 + vertex 1.00964 2.02253 2.58455 + endloop + endfacet + facet normal 0.097858 0.248708 0.963622 + outer loop + vertex 1.00803 2.02718 2.58354 + vertex 1.0111 2.03123 2.58218 + vertex 1.00658 2.03058 2.58281 + endloop + endfacet + facet normal 0.1009 0.249909 0.962998 + outer loop + vertex 1.01663 2.02561 2.58306 + vertex 1.01685 2.02974 2.58197 + vertex 1.01276 2.02654 2.58323 + endloop + endfacet + facet normal 0.0998171 0.24478 0.964427 + outer loop + vertex 1.01127 2.03552 2.58108 + vertex 1.00676 2.0347 2.58175 + vertex 1.0111 2.03123 2.58218 + endloop + endfacet + facet normal 0.104296 0.247314 0.963306 + outer loop + vertex 1.01945 2.03333 2.58076 + vertex 1.01538 2.03438 2.58094 + vertex 1.01685 2.02974 2.58197 + endloop + endfacet + facet normal 0.106875 0.246855 0.963141 + outer loop + vertex 1.01945 2.03333 2.58076 + vertex 1.02136 2.03076 2.58121 + vertex 1.02394 2.03435 2.58 + endloop + endfacet + facet normal 0.111787 0.240263 0.96425 + outer loop + vertex 1.02916 2.03325 2.57967 + vertex 1.02808 2.03747 2.57875 + vertex 1.02394 2.03435 2.58 + endloop + endfacet + facet normal 0.112964 0.23493 0.965426 + outer loop + vertex 1.02433 2.03832 2.57897 + vertex 1.0268 2.04076 2.57809 + vertex 1.02295 2.04166 2.57832 + endloop + endfacet + facet normal 0.114347 0.238536 0.964378 + outer loop + vertex 1.03282 2.0367 2.57837 + vertex 1.0313 2.0415 2.57737 + vertex 1.02808 2.03747 2.57875 + endloop + endfacet + facet normal 0.113474 0.237259 0.964796 + outer loop + vertex 1.0268 2.04076 2.57809 + vertex 1.02708 2.04491 2.57704 + vertex 1.02295 2.04166 2.57832 + endloop + endfacet + facet normal 0.118253 0.243926 0.962557 + outer loop + vertex 1.03157 2.0458 2.57626 + vertex 1.02967 2.04848 2.57581 + vertex 1.02708 2.04491 2.57704 + endloop + endfacet + facet normal 0.126558 0.258871 0.957585 + outer loop + vertex 1.03978 2.04773 2.5747 + vertex 1.04278 2.05164 2.57324 + vertex 1.03813 2.05226 2.57369 + endloop + endfacet + facet normal 0.125553 0.248742 0.960398 + outer loop + vertex 1.02967 2.04848 2.57581 + vertex 1.03157 2.0458 2.57626 + vertex 1.03413 2.04928 2.57502 + endloop + endfacet + facet normal 0.117712 0.244308 0.962527 + outer loop + vertex 1.02967 2.04848 2.57581 + vertex 1.02563 2.0496 2.57603 + vertex 1.02708 2.04491 2.57704 + endloop + endfacet + facet normal 0.118083 0.256152 0.959397 + outer loop + vertex 1.02563 2.0496 2.57603 + vertex 1.02411 2.05424 2.57497 + vertex 1.02154 2.05073 2.57623 + endloop + endfacet + facet normal 0.124719 0.262982 0.956705 + outer loop + vertex 1.02984 2.05268 2.57467 + vertex 1.03281 2.05659 2.57321 + vertex 1.02814 2.05725 2.57364 + endloop + endfacet + facet normal 0.124881 0.264394 0.956295 + outer loop + vertex 1.03281 2.05659 2.57321 + vertex 1.03108 2.06121 2.57216 + vertex 1.02814 2.05725 2.57364 + endloop + endfacet + facet normal 0.124563 0.264623 0.956273 + outer loop + vertex 1.02814 2.05725 2.57364 + vertex 1.03108 2.06121 2.57216 + vertex 1.02662 2.06059 2.57291 + endloop + endfacet + facet normal 0.113701 0.261711 0.958426 + outer loop + vertex 1.01955 2.05342 2.57574 + vertex 1.02411 2.05424 2.57497 + vertex 1.01972 2.05762 2.57457 + endloop + endfacet + facet normal 0.115378 0.260089 0.958667 + outer loop + vertex 1.01972 2.05762 2.57457 + vertex 1.02276 2.0616 2.57313 + vertex 1.01805 2.0622 2.57353 + endloop + endfacet + facet normal 0.121303 0.263311 0.957054 + outer loop + vertex 1.02814 2.05725 2.57364 + vertex 1.02662 2.06059 2.57291 + vertex 1.02428 2.05825 2.57385 + endloop + endfacet + facet normal 0.125257 0.260784 0.957237 + outer loop + vertex 1.02676 2.06467 2.57178 + vertex 1.02662 2.06059 2.57291 + vertex 1.03108 2.06121 2.57216 + endloop + endfacet + facet normal 0.127849 0.256809 0.957969 + outer loop + vertex 1.02927 2.06815 2.57051 + vertex 1.02526 2.06933 2.57073 + vertex 1.02676 2.06467 2.57178 + endloop + endfacet + facet normal 0.127324 0.25492 0.958543 + outer loop + vertex 1.02526 2.06933 2.57073 + vertex 1.02927 2.06815 2.57051 + vertex 1.0294 2.07231 2.56939 + endloop + endfacet + facet normal 0.126742 0.255672 0.95842 + outer loop + vertex 1.0238 2.07393 2.5697 + vertex 1.02526 2.06933 2.57073 + vertex 1.0294 2.07231 2.56939 + endloop + endfacet + facet normal 0.126754 0.255716 0.958406 + outer loop + vertex 1.0294 2.07231 2.56939 + vertex 1.02792 2.07692 2.56836 + vertex 1.0238 2.07393 2.5697 + endloop + endfacet + facet normal 0.114931 0.255754 0.959886 + outer loop + vertex 1.02276 2.0616 2.57313 + vertex 1.0211 2.06622 2.57209 + vertex 1.01805 2.0622 2.57353 + endloop + endfacet + facet normal 0.104853 0.256718 0.960782 + outer loop + vertex 1.01972 2.05762 2.57457 + vertex 1.01805 2.0622 2.57353 + vertex 1.01392 2.05904 2.57482 + endloop + endfacet + facet normal 0.0972489 0.258593 0.961079 + outer loop + vertex 1.00935 2.05804 2.57556 + vertex 1.01129 2.05549 2.57604 + vertex 1.01392 2.05904 2.57482 + endloop + endfacet + facet normal 0.0968376 0.256537 0.961671 + outer loop + vertex 1.00935 2.05804 2.57556 + vertex 1.0053 2.05888 2.57574 + vertex 1.00684 2.05445 2.57677 + endloop + endfacet + facet normal 0.0961324 0.256323 0.961799 + outer loop + vertex 1.00684 2.05445 2.57677 + vertex 1.0053 2.05888 2.57574 + vertex 1.00157 2.0555 2.57701 + endloop + endfacet + facet normal 0.0976655 0.254727 0.962069 + outer loop + vertex 1.0053 2.05888 2.57574 + vertex 1.00044 2.05985 2.57598 + vertex 1.00157 2.0555 2.57701 + endloop + endfacet + facet normal 0.0968297 0.25022 0.963335 + outer loop + vertex 1.00044 2.05985 2.57598 + vertex 1.0053 2.05888 2.57574 + vertex 1.00421 2.06321 2.57473 + endloop + endfacet + facet normal 0.100692 0.245621 0.964122 + outer loop + vertex 1.00421 2.06321 2.57473 + vertex 1.00793 2.06685 2.57341 + vertex 1.00308 2.06741 2.57377 + endloop + endfacet + facet normal 0.0964627 0.244646 0.964802 + outer loop + vertex 1.00421 2.06321 2.57473 + vertex 1.00308 2.06741 2.57377 + vertex 0.998979 2.06425 2.57498 + endloop + endfacet + facet normal 0.100852 0.247269 0.963684 + outer loop + vertex 1.00793 2.06685 2.57341 + vertex 1.00622 2.07155 2.57238 + vertex 1.00308 2.06741 2.57377 + endloop + endfacet + facet normal 0.100426 0.250876 0.962796 + outer loop + vertex 1.01419 2.06307 2.57373 + vertex 1.01281 2.06629 2.57304 + vertex 1.00964 2.0622 2.57443 + endloop + endfacet + facet normal 0.10433 0.248393 0.963025 + outer loop + vertex 1.00793 2.06685 2.57341 + vertex 1.01163 2.07051 2.57206 + vertex 1.00622 2.07155 2.57238 + endloop + endfacet + facet normal 0.106575 0.253964 0.961324 + outer loop + vertex 1.01661 2.06549 2.57283 + vertex 1.01688 2.06948 2.57174 + vertex 1.01281 2.06629 2.57304 + endloop + endfacet + facet normal 0.108902 0.254056 0.961039 + outer loop + vertex 1.01534 2.07391 2.57074 + vertex 1.01048 2.07489 2.57104 + vertex 1.01163 2.07051 2.57206 + endloop + endfacet + facet normal 0.105173 0.253231 0.961672 + outer loop + vertex 1.01163 2.07051 2.57206 + vertex 1.01048 2.07489 2.57104 + vertex 1.00622 2.07155 2.57238 + endloop + endfacet + facet normal 0.107024 0.251018 0.962048 + outer loop + vertex 1.00647 2.07578 2.57125 + vertex 1.00622 2.07155 2.57238 + vertex 1.01048 2.07489 2.57104 + endloop + endfacet + facet normal 0.108618 0.258658 0.959843 + outer loop + vertex 1.01048 2.07489 2.57104 + vertex 1.00898 2.07933 2.57001 + vertex 1.00647 2.07578 2.57125 + endloop + endfacet + facet normal 0.1104 0.259183 0.959498 + outer loop + vertex 1.00898 2.07933 2.57001 + vertex 1.01048 2.07489 2.57104 + vertex 1.01419 2.0782 2.56972 + endloop + endfacet + facet normal 0.101431 0.251479 0.962533 + outer loop + vertex 1.00647 2.07578 2.57125 + vertex 1.002 2.07481 2.57198 + vertex 1.00622 2.07155 2.57238 + endloop + endfacet + facet normal 0.10095 0.253349 0.962093 + outer loop + vertex 1.00647 2.07578 2.57125 + vertex 1.00456 2.07839 2.57076 + vertex 1.002 2.07481 2.57198 + endloop + endfacet + facet normal 0.095572 0.25705 0.961661 + outer loop + vertex 1.00456 2.07839 2.57076 + vertex 1.00053 2.07943 2.57089 + vertex 1.002 2.07481 2.57198 + endloop + endfacet + facet normal 0.1087 0.258602 0.959849 + outer loop + vertex 1.00456 2.07839 2.57076 + vertex 1.00647 2.07578 2.57125 + vertex 1.00898 2.07933 2.57001 + endloop + endfacet + facet normal 0.10716 0.264673 0.958366 + outer loop + vertex 1.00456 2.07839 2.57076 + vertex 1.00898 2.07933 2.57001 + vertex 1.00476 2.08256 2.56959 + endloop + endfacet + facet normal 0.106543 0.263907 0.958646 + outer loop + vertex 1.00476 2.08256 2.56959 + vertex 1.00898 2.07933 2.57001 + vertex 1.00928 2.08321 2.56891 + endloop + endfacet + facet normal 0.106032 0.266718 0.957924 + outer loop + vertex 1.00928 2.08321 2.56891 + vertex 1.00791 2.08643 2.56816 + vertex 1.00476 2.08256 2.56959 + endloop + endfacet + facet normal 0.11042 0.268374 0.956965 + outer loop + vertex 1.00928 2.08321 2.56891 + vertex 1.01167 2.08552 2.56799 + vertex 1.00791 2.08643 2.56816 + endloop + endfacet + facet normal 0.110916 0.270565 0.956291 + outer loop + vertex 1.01167 2.08552 2.56799 + vertex 1.01191 2.08945 2.56685 + vertex 1.00791 2.08643 2.56816 + endloop + endfacet + facet normal 0.108727 0.273247 0.955779 + outer loop + vertex 1.00791 2.08643 2.56816 + vertex 1.01191 2.08945 2.56685 + vertex 1.00667 2.0906 2.56711 + endloop + endfacet + facet normal 0.101766 0.271507 0.957041 + outer loop + vertex 1.00791 2.08643 2.56816 + vertex 1.00667 2.0906 2.56711 + vertex 1.00308 2.08722 2.56845 + endloop + endfacet + facet normal 0.108595 0.272599 0.95598 + outer loop + vertex 1.01191 2.08945 2.56685 + vertex 1.01033 2.09385 2.56577 + vertex 1.00667 2.0906 2.56711 + endloop + endfacet + facet normal 0.105183 0.276167 0.955337 + outer loop + vertex 1.01033 2.09385 2.56577 + vertex 1.00547 2.09487 2.56601 + vertex 1.00667 2.0906 2.56711 + endloop + endfacet + facet normal 0.112259 0.273737 0.955231 + outer loop + vertex 1.01435 2.09296 2.56555 + vertex 1.01033 2.09385 2.56577 + vertex 1.01191 2.08945 2.56685 + endloop + endfacet + facet normal 0.112539 0.275096 0.954807 + outer loop + vertex 1.01033 2.09385 2.56577 + vertex 1.01435 2.09296 2.56555 + vertex 1.01446 2.097 2.56438 + endloop + endfacet + facet normal 0.113181 0.274318 0.954955 + outer loop + vertex 1.00917 2.09814 2.56468 + vertex 1.01033 2.09385 2.56577 + vertex 1.01446 2.097 2.56438 + endloop + endfacet + facet normal 0.111604 0.26632 0.957402 + outer loop + vertex 1.01446 2.097 2.56438 + vertex 1.01281 2.10152 2.56331 + vertex 1.00917 2.09814 2.56468 + endloop + endfacet + facet normal 0.113921 0.270298 0.956013 + outer loop + vertex 1.01191 2.08945 2.56685 + vertex 1.01167 2.08552 2.56799 + vertex 1.01615 2.08622 2.56725 + endloop + endfacet + facet normal 0.112414 0.266434 0.957275 + outer loop + vertex 1.01302 2.08233 2.56871 + vertex 1.01167 2.08552 2.56799 + vertex 1.00928 2.08321 2.56891 + endloop + endfacet + facet normal 0.114532 0.267225 0.956804 + outer loop + vertex 1.01302 2.08233 2.56871 + vertex 1.01615 2.08622 2.56725 + vertex 1.01167 2.08552 2.56799 + endloop + endfacet + facet normal 0.111742 0.263375 0.9582 + outer loop + vertex 1.00898 2.07933 2.57001 + vertex 1.01302 2.08233 2.56871 + vertex 1.00928 2.08321 2.56891 + endloop + endfacet + facet normal 0.111339 0.263878 0.958109 + outer loop + vertex 1.01419 2.0782 2.56972 + vertex 1.01302 2.08233 2.56871 + vertex 1.00898 2.07933 2.57001 + endloop + endfacet + facet normal 0.10993 0.259677 0.959418 + outer loop + vertex 1.01048 2.07489 2.57104 + vertex 1.01534 2.07391 2.57074 + vertex 1.01419 2.0782 2.56972 + endloop + endfacet + facet normal 0.113562 0.264406 0.957702 + outer loop + vertex 1.01419 2.0782 2.56972 + vertex 1.01779 2.08156 2.56836 + vertex 1.01302 2.08233 2.56871 + endloop + endfacet + facet normal 0.114013 0.267624 0.956754 + outer loop + vertex 1.01779 2.08156 2.56836 + vertex 1.01615 2.08622 2.56725 + vertex 1.01302 2.08233 2.56871 + endloop + endfacet + facet normal 0.116285 0.268311 0.956288 + outer loop + vertex 1.01779 2.08156 2.56836 + vertex 1.02193 2.08476 2.56696 + vertex 1.01615 2.08622 2.56725 + endloop + endfacet + facet normal 0.116717 0.270141 0.95572 + outer loop + vertex 1.02193 2.08476 2.56696 + vertex 1.02035 2.08935 2.56586 + vertex 1.01615 2.08622 2.56725 + endloop + endfacet + facet normal 0.116832 0.267656 0.956405 + outer loop + vertex 1.02191 2.08062 2.56812 + vertex 1.02193 2.08476 2.56696 + vertex 1.01779 2.08156 2.56836 + endloop + endfacet + facet normal 0.121395 0.267485 0.955884 + outer loop + vertex 1.02193 2.08476 2.56696 + vertex 1.02191 2.08062 2.56812 + vertex 1.02639 2.0815 2.56731 + endloop + endfacet + facet normal 0.121401 0.259919 0.957969 + outer loop + vertex 1.01936 2.07304 2.5705 + vertex 1.0238 2.07393 2.5697 + vertex 1.01947 2.07709 2.56939 + endloop + endfacet + facet normal 0.12218 0.264217 0.956693 + outer loop + vertex 1.0239 2.07805 2.56858 + vertex 1.02639 2.0815 2.56731 + vertex 1.02191 2.08062 2.56812 + endloop + endfacet + facet normal 0.127382 0.258588 0.957552 + outer loop + vertex 1.03194 2.07575 2.56814 + vertex 1.03204 2.07989 2.56701 + vertex 1.02792 2.07692 2.56836 + endloop + endfacet + facet normal 0.125236 0.263694 0.956442 + outer loop + vertex 1.03452 2.0833 2.56574 + vertex 1.03048 2.08446 2.56595 + vertex 1.03204 2.07989 2.56701 + endloop + endfacet + facet normal 0.120482 0.266286 0.956335 + outer loop + vertex 1.02643 2.08562 2.56615 + vertex 1.02193 2.08476 2.56696 + vertex 1.02639 2.0815 2.56731 + endloop + endfacet + facet normal 0.126519 0.271225 0.954165 + outer loop + vertex 1.02889 2.08902 2.56487 + vertex 1.03048 2.08446 2.56595 + vertex 1.03454 2.08738 2.56458 + endloop + endfacet + facet normal 0.119692 0.269639 0.955494 + outer loop + vertex 1.02643 2.08562 2.56615 + vertex 1.02441 2.08825 2.56566 + vertex 1.02193 2.08476 2.56696 + endloop + endfacet + facet normal 0.118289 0.270605 0.955396 + outer loop + vertex 1.02441 2.08825 2.56566 + vertex 1.02035 2.08935 2.56586 + vertex 1.02193 2.08476 2.56696 + endloop + endfacet + facet normal 0.113607 0.272836 0.955329 + outer loop + vertex 1.01631 2.09042 2.56605 + vertex 1.01435 2.09296 2.56555 + vertex 1.01191 2.08945 2.56685 + endloop + endfacet + facet normal 0.11927 0.276515 0.95358 + outer loop + vertex 1.02445 2.09234 2.56448 + vertex 1.02289 2.09688 2.56336 + vertex 1.01881 2.09388 2.56474 + endloop + endfacet + facet normal 0.120533 0.271274 0.954925 + outer loop + vertex 1.01888 2.09797 2.56355 + vertex 1.02134 2.10141 2.56226 + vertex 1.0169 2.10054 2.56307 + endloop + endfacet + facet normal 0.122802 0.261826 0.95727 + outer loop + vertex 1.01693 2.10471 2.56193 + vertex 1.0169 2.10054 2.56307 + vertex 1.02134 2.10141 2.56226 + endloop + endfacet + facet normal 0.125295 0.265035 0.956063 + outer loop + vertex 1.02138 2.10551 2.56112 + vertex 1.01693 2.10471 2.56193 + vertex 1.02134 2.10141 2.56226 + endloop + endfacet + facet normal 0.12638 0.260223 0.957242 + outer loop + vertex 1.02138 2.10551 2.56112 + vertex 1.01932 2.10818 2.56067 + vertex 1.01693 2.10471 2.56193 + endloop + endfacet + facet normal 0.121916 0.277331 0.953008 + outer loop + vertex 1.02691 2.09573 2.56318 + vertex 1.02695 2.0998 2.56199 + vertex 1.02289 2.09688 2.56336 + endloop + endfacet + facet normal 0.126013 0.265005 0.955977 + outer loop + vertex 1.02138 2.10551 2.56112 + vertex 1.02134 2.10141 2.56226 + vertex 1.0254 2.10434 2.56091 + endloop + endfacet + facet normal 0.125996 0.264945 0.955996 + outer loop + vertex 1.0254 2.10434 2.56091 + vertex 1.02379 2.10893 2.55985 + vertex 1.02138 2.10551 2.56112 + endloop + endfacet + facet normal 0.129563 0.262495 0.956196 + outer loop + vertex 1.01932 2.10818 2.56067 + vertex 1.02138 2.10551 2.56112 + vertex 1.02379 2.10893 2.55985 + endloop + endfacet + facet normal 0.0991352 0.255593 0.961688 + outer loop + vertex 1.0113 2.11052 2.56109 + vertex 1.00695 2.10954 2.5618 + vertex 1.0112 2.10628 2.56222 + endloop + endfacet + facet normal 0.127656 0.259366 0.957305 + outer loop + vertex 1.01932 2.10818 2.56067 + vertex 1.01527 2.10936 2.56089 + vertex 1.01693 2.10471 2.56193 + endloop + endfacet + facet normal 0.119209 0.261964 0.957687 + outer loop + vertex 1.0169 2.10054 2.56307 + vertex 1.01693 2.10471 2.56193 + vertex 1.01281 2.10152 2.56331 + endloop + endfacet + facet normal 0.111511 0.266413 0.957387 + outer loop + vertex 1.00917 2.09814 2.56468 + vertex 1.01281 2.10152 2.56331 + vertex 1.00806 2.10233 2.56364 + endloop + endfacet + facet normal 0.104439 0.272363 0.95651 + outer loop + vertex 1.00547 2.09487 2.56601 + vertex 1.01033 2.09385 2.56577 + vertex 1.00917 2.09814 2.56468 + endloop + endfacet + facet normal 0.0918845 0.273026 0.957609 + outer loop + vertex 1.00667 2.0906 2.56711 + vertex 1.00547 2.09487 2.56601 + vertex 1.00134 2.09165 2.56732 + endloop + endfacet + facet normal 0.0547295 0.277558 0.959149 + outer loop + vertex 1.00146 2.09568 2.56614 + vertex 0.999545 2.09804 2.56557 + vertex 0.997046 2.09438 2.56677 + endloop + endfacet + facet normal 0.0931763 0.280024 0.95546 + outer loop + vertex 1.00308 2.08722 2.56845 + vertex 1.00667 2.0906 2.56711 + vertex 1.00134 2.09165 2.56732 + endloop + endfacet + facet normal 0.10157 0.270174 0.957439 + outer loop + vertex 1.00476 2.08256 2.56959 + vertex 1.00791 2.08643 2.56816 + vertex 1.00308 2.08722 2.56845 + endloop + endfacet + facet normal 0.0976331 0.265353 0.959195 + outer loop + vertex 1.00053 2.07943 2.57089 + vertex 1.00456 2.07839 2.57076 + vertex 1.00476 2.08256 2.56959 + endloop + endfacet + facet normal 0.0827272 0.25348 0.963797 + outer loop + vertex 1.002 2.07481 2.57198 + vertex 1.00053 2.07943 2.57089 + vertex 0.996305 2.07617 2.57211 + endloop + endfacet + facet normal 0.083984 0.258861 0.962256 + outer loop + vertex 0.99791 2.07152 2.57322 + vertex 1.002 2.07481 2.57198 + vertex 0.996305 2.07617 2.57211 + endloop + endfacet + facet normal 0.0898965 0.251984 0.963547 + outer loop + vertex 1.00175 2.07068 2.57308 + vertex 1.002 2.07481 2.57198 + vertex 0.99791 2.07152 2.57322 + endloop + endfacet + facet normal 0.0895759 0.250457 0.963975 + outer loop + vertex 0.999334 2.06821 2.57395 + vertex 1.00175 2.07068 2.57308 + vertex 0.99791 2.07152 2.57322 + endloop + endfacet + facet normal 0.0963864 0.244136 0.964939 + outer loop + vertex 1.00308 2.06741 2.57377 + vertex 1.00175 2.07068 2.57308 + vertex 0.999334 2.06821 2.57395 + endloop + endfacet + facet normal 0.102211 0.246276 0.963795 + outer loop + vertex 1.00308 2.06741 2.57377 + vertex 1.00622 2.07155 2.57238 + vertex 1.00175 2.07068 2.57308 + endloop + endfacet + facet normal 0.101104 0.251073 0.962674 + outer loop + vertex 1.002 2.07481 2.57198 + vertex 1.00175 2.07068 2.57308 + vertex 1.00622 2.07155 2.57238 + endloop + endfacet + facet normal 0.096483 0.244621 0.964806 + outer loop + vertex 0.998979 2.06425 2.57498 + vertex 1.00308 2.06741 2.57377 + vertex 0.999334 2.06821 2.57395 + endloop + endfacet + facet normal 0.0973852 0.249633 0.963431 + outer loop + vertex 0.998979 2.06425 2.57498 + vertex 1.00044 2.05985 2.57598 + vertex 1.00421 2.06321 2.57473 + endloop + endfacet + facet normal 0.0945652 0.254035 0.962561 + outer loop + vertex 1.00157 2.0555 2.57701 + vertex 1.00044 2.05985 2.57598 + vertex 0.996188 2.05655 2.57726 + endloop + endfacet + facet normal 0.0954138 0.258701 0.961234 + outer loop + vertex 0.997916 2.05192 2.57834 + vertex 1.00157 2.0555 2.57701 + vertex 0.996188 2.05655 2.57726 + endloop + endfacet + facet normal 0.0909386 0.257224 0.962064 + outer loop + vertex 0.997916 2.05192 2.57834 + vertex 0.996188 2.05655 2.57726 + vertex 0.993049 2.05248 2.57865 + endloop + endfacet + facet normal 0.0801069 0.249433 0.965073 + outer loop + vertex 0.996442 2.0607 2.57615 + vertex 0.994552 2.06317 2.57566 + vertex 0.992019 2.05955 2.57681 + endloop + endfacet + facet normal 0.0833389 0.262799 0.961245 + outer loop + vertex 0.993049 2.05248 2.57865 + vertex 0.996188 2.05655 2.57726 + vertex 0.9917 2.05563 2.57791 + endloop + endfacet + facet normal 0.0910098 0.25796 0.96186 + outer loop + vertex 0.994231 2.04833 2.57965 + vertex 0.997916 2.05192 2.57834 + vertex 0.993049 2.05248 2.57865 + endloop + endfacet + facet normal 0.0965973 0.257564 0.961421 + outer loop + vertex 1.00278 2.0513 2.57802 + vertex 1.00157 2.0555 2.57701 + vertex 0.997916 2.05192 2.57834 + endloop + endfacet + facet normal 0.0960731 0.253648 0.962514 + outer loop + vertex 1.00417 2.04806 2.57873 + vertex 1.00658 2.05047 2.57786 + vertex 1.00278 2.0513 2.57802 + endloop + endfacet + facet normal 0.100076 0.245302 0.964267 + outer loop + vertex 0.999387 2.04311 2.58048 + vertex 1.00388 2.04403 2.57978 + vertex 0.999656 2.04727 2.57939 + endloop + endfacet + facet normal 0.0993023 0.250585 0.962988 + outer loop + vertex 1.00802 2.04716 2.57857 + vertex 1.00658 2.05047 2.57786 + vertex 1.00417 2.04806 2.57873 + endloop + endfacet + facet normal 0.0984673 0.249458 0.963366 + outer loop + vertex 1.01279 2.0466 2.57823 + vertex 1.01112 2.05125 2.57719 + vertex 1.00802 2.04716 2.57857 + endloop + endfacet + facet normal 0.0994638 0.238247 0.966098 + outer loop + vertex 1.01425 2.04317 2.57892 + vertex 1.01673 2.04563 2.57806 + vertex 1.01279 2.0466 2.57823 + endloop + endfacet + facet normal 0.103802 0.230818 0.967444 + outer loop + vertex 1.01394 2.03905 2.57994 + vertex 1.01818 2.04221 2.57873 + vertex 1.01425 2.04317 2.57892 + endloop + endfacet + facet normal 0.0994836 0.235882 0.966676 + outer loop + vertex 1.00933 2.03824 2.58061 + vertex 1.01127 2.03552 2.58108 + vertex 1.01394 2.03905 2.57994 + endloop + endfacet + facet normal 0.101456 0.237196 0.966149 + outer loop + vertex 1.01127 2.03552 2.58108 + vertex 1.00933 2.03824 2.58061 + vertex 1.00676 2.0347 2.58175 + endloop + endfacet + facet normal 0.102893 0.236186 0.966245 + outer loop + vertex 1.00933 2.03824 2.58061 + vertex 1.00529 2.0394 2.58076 + vertex 1.00676 2.0347 2.58175 + endloop + endfacet + facet normal 0.0995656 0.235267 0.966817 + outer loop + vertex 1.00676 2.0347 2.58175 + vertex 1.00529 2.0394 2.58076 + vertex 1.00105 2.03614 2.58199 + endloop + endfacet + facet normal 0.0966397 0.230082 0.968361 + outer loop + vertex 0.996833 2.03947 2.58162 + vertex 0.996366 2.03519 2.58268 + vertex 1.00105 2.03614 2.58199 + endloop + endfacet + facet normal 0.102351 0.235794 0.966398 + outer loop + vertex 0.999387 2.04311 2.58048 + vertex 1.00128 2.0405 2.58092 + vertex 1.00388 2.04403 2.57978 + endloop + endfacet + facet normal 0.0972337 0.245546 0.964496 + outer loop + vertex 0.995372 2.044 2.58066 + vertex 0.999387 2.04311 2.58048 + vertex 0.999656 2.04727 2.57939 + endloop + endfacet + facet normal 0.0902851 0.230882 0.968784 + outer loop + vertex 0.996366 2.03519 2.58268 + vertex 0.996833 2.03947 2.58162 + vertex 0.992483 2.0362 2.5828 + endloop + endfacet + facet normal 0.085787 0.238577 0.967327 + outer loop + vertex 0.995372 2.044 2.58066 + vertex 0.990509 2.04492 2.58086 + vertex 0.991603 2.04056 2.58184 + endloop + endfacet + facet normal 0.0312442 0.247978 0.968262 + outer loop + vertex 0.986594 2.0456 2.58097 + vertex 0.984764 2.04771 2.58049 + vertex 0.982498 2.0443 2.58144 + endloop + endfacet + facet normal 0.0319292 0.242281 0.969681 + outer loop + vertex 0.982901 2.03673 2.5833 + vertex 0.986254 2.04142 2.58202 + vertex 0.981441 2.04018 2.58248 + endloop + endfacet + facet normal 0.0485832 0.239168 0.969762 + outer loop + vertex 0.98452 2.03342 2.58403 + vertex 0.987811 2.03688 2.58301 + vertex 0.982901 2.03673 2.5833 + endloop + endfacet + facet normal 0.0616103 0.234265 0.970219 + outer loop + vertex 0.984013 2.02923 2.58508 + vertex 0.9886 2.03272 2.58394 + vertex 0.98452 2.03342 2.58403 + endloop + endfacet + facet normal 0.0638954 0.244775 0.967472 + outer loop + vertex 0.984013 2.02923 2.58508 + vertex 0.9855 2.02508 2.58603 + vertex 0.989328 2.02859 2.58489 + endloop + endfacet + facet normal 0.05404 0.236205 0.970199 + outer loop + vertex 0.9866 2.02089 2.58699 + vertex 0.9855 2.02508 2.58603 + vertex 0.9812 2.02149 2.58714 + endloop + endfacet + facet normal 0.02546 0.236714 0.971246 + outer loop + vertex 0.98154 2.02563 2.58611 + vertex 0.979704 2.0277 2.58565 + vertex 0.977405 2.02432 2.58654 + endloop + endfacet + facet normal 0.0543882 0.23955 0.96936 + outer loop + vertex 0.982955 2.01693 2.58817 + vertex 0.9866 2.02089 2.58699 + vertex 0.9812 2.02149 2.58714 + endloop + endfacet + facet normal 0.0524036 0.226883 0.972511 + outer loop + vertex 0.984544 2.0135 2.58888 + vertex 0.982955 2.01693 2.58817 + vertex 0.979622 2.01208 2.58948 + endloop + endfacet + facet normal 0.0533637 0.22382 0.973168 + outer loop + vertex 0.979622 2.01208 2.58948 + vertex 0.983941 2.00927 2.58989 + vertex 0.984544 2.0135 2.58888 + endloop + endfacet + facet normal 0.0749538 0.219248 0.972786 + outer loop + vertex 0.983941 2.00927 2.58989 + vertex 0.985369 2.00488 2.59077 + vertex 0.989267 2.00826 2.58971 + endloop + endfacet + facet normal 0.0706532 0.212209 0.974667 + outer loop + vertex 0.986497 2.00047 2.59165 + vertex 0.985369 2.00488 2.59077 + vertex 0.981072 2.0014 2.59184 + endloop + endfacet + facet normal 0.0507225 0.215856 0.975107 + outer loop + vertex 0.981329 2.00566 2.59089 + vertex 0.979419 2.00799 2.59048 + vertex 0.976955 2.00434 2.59141 + endloop + endfacet + facet normal 0.0333505 0.227132 0.973293 + outer loop + vertex 0.979419 2.00799 2.59048 + vertex 0.975501 2.00825 2.59055 + vertex 0.976955 2.00434 2.59141 + endloop + endfacet + facet normal 0.0567035 0.212621 0.975488 + outer loop + vertex 0.977687 1.99672 2.59306 + vertex 0.981072 2.0014 2.59184 + vertex 0.97639 2.00021 2.59237 + endloop + endfacet + facet normal 0.0527892 0.202059 0.97795 + outer loop + vertex 0.978664 1.99227 2.59392 + vertex 0.977687 1.99672 2.59306 + vertex 0.97365 1.99251 2.59414 + endloop + endfacet + facet normal 0.0670236 0.202121 0.977064 + outer loop + vertex 0.983627 1.99212 2.59361 + vertex 0.982608 1.99657 2.59276 + vertex 0.978664 1.99227 2.59392 + endloop + endfacet + facet normal 0.0688823 0.204229 0.976497 + outer loop + vertex 0.988165 1.99186 2.59335 + vertex 0.987451 1.996 2.59253 + vertex 0.983627 1.99212 2.59361 + endloop + endfacet + facet normal 0.0689642 0.204694 0.976394 + outer loop + vertex 0.992655 1.99159 2.59309 + vertex 0.991348 1.9951 2.59244 + vertex 0.988165 1.99186 2.59335 + endloop + endfacet + facet normal 0.0693755 0.204304 0.976446 + outer loop + vertex 0.988165 1.99186 2.59335 + vertex 0.991348 1.9951 2.59244 + vertex 0.987451 1.996 2.59253 + endloop + endfacet + facet normal 0.0731329 0.206184 0.975777 + outer loop + vertex 0.997481 1.99126 2.59279 + vertex 0.996072 1.99615 2.59187 + vertex 0.992655 1.99159 2.59309 + endloop + endfacet + facet normal 0.0731772 0.206151 0.97578 + outer loop + vertex 0.992655 1.99159 2.59309 + vertex 0.996072 1.99615 2.59187 + vertex 0.991348 1.9951 2.59244 + endloop + endfacet + facet normal 0.0817136 0.2031 0.975742 + outer loop + vertex 0.998465 1.98699 2.5936 + vertex 1.00153 1.99035 2.59264 + vertex 0.997481 1.99126 2.59279 + endloop + endfacet + facet normal 0.0873263 0.203336 0.975207 + outer loop + vertex 0.999854 1.98371 2.59416 + vertex 1.00296 1.98695 2.59321 + vertex 0.998465 1.98699 2.5936 + endloop + endfacet + facet normal 0.0816107 0.208643 0.974581 + outer loop + vertex 0.99459 1.97838 2.59573 + vertex 0.999174 1.97953 2.5951 + vertex 0.995029 1.98257 2.5948 + endloop + endfacet + facet normal 0.091515 0.199446 0.975626 + outer loop + vertex 1.00371 1.98281 2.59398 + vertex 1.00296 1.98695 2.59321 + vertex 0.999854 1.98371 2.59416 + endloop + endfacet + facet normal 0.101155 0.205428 0.973431 + outer loop + vertex 1.00443 1.97848 2.59482 + vertex 1.00833 1.98205 2.59366 + vertex 1.00371 1.98281 2.59398 + endloop + endfacet + facet normal 0.0955521 0.208541 0.973335 + outer loop + vertex 1.00052 1.97509 2.59593 + vertex 1.00536 1.97412 2.59566 + vertex 1.00443 1.97848 2.59482 + endloop + endfacet + facet normal 0.0868256 0.20659 0.974568 + outer loop + vertex 1.00154 1.97064 2.59678 + vertex 1.00052 1.97509 2.59593 + vertex 0.996186 1.97157 2.59706 + endloop + endfacet + facet normal 0.0753737 0.209986 0.974795 + outer loop + vertex 0.991994 1.97466 2.59672 + vertex 0.991546 1.97031 2.59769 + vertex 0.996186 1.97157 2.59706 + endloop + endfacet + facet normal 0.0804288 0.212886 0.973761 + outer loop + vertex 0.99459 1.97838 2.59573 + vertex 0.996496 1.97591 2.59611 + vertex 0.999174 1.97953 2.5951 + endloop + endfacet + facet normal 0.0660589 0.209977 0.975472 + outer loop + vertex 0.991994 1.97466 2.59672 + vertex 0.990481 1.97913 2.59586 + vertex 0.986602 1.97561 2.59688 + endloop + endfacet + facet normal 0.0660428 0.209994 0.97547 + outer loop + vertex 0.990481 1.97913 2.59586 + vertex 0.985452 1.98003 2.59601 + vertex 0.986602 1.97561 2.59688 + endloop + endfacet + facet normal 0.0645182 0.205812 0.976462 + outer loop + vertex 0.985452 1.98003 2.59601 + vertex 0.984029 1.98445 2.59517 + vertex 0.981308 1.98086 2.59611 + endloop + endfacet + facet normal 0.06898 0.204602 0.976412 + outer loop + vertex 0.989465 1.98346 2.59501 + vertex 0.993637 1.98723 2.59392 + vertex 0.988748 1.98779 2.59415 + endloop + endfacet + facet normal 0.0608091 0.20316 0.977256 + outer loop + vertex 0.975337 1.98404 2.59582 + vertex 0.979375 1.98333 2.59572 + vertex 0.979929 1.98752 2.59481 + endloop + endfacet + facet normal 0.0452647 0.201289 0.978486 + outer loop + vertex 0.970378 1.98455 2.59595 + vertex 0.975337 1.98404 2.59582 + vertex 0.974449 1.98822 2.595 + endloop + endfacet + facet normal 0.0530432 0.210281 0.976201 + outer loop + vertex 0.972552 1.97621 2.59763 + vertex 0.976849 1.97969 2.59665 + vertex 0.97159 1.98051 2.59675 + endloop + endfacet + facet normal 0.0401981 0.20811 0.977279 + outer loop + vertex 0.973452 1.97199 2.59849 + vertex 0.972552 1.97621 2.59763 + vertex 0.968625 1.97209 2.59867 + endloop + endfacet + facet normal 0.0221199 0.20973 0.977509 + outer loop + vertex 0.969989 1.96738 2.59965 + vertex 0.968625 1.97209 2.59867 + vertex 0.964417 1.96767 2.59971 + endloop + endfacet + facet normal 0.0228927 0.225226 0.974038 + outer loop + vertex 0.964417 1.96767 2.59971 + vertex 0.965547 1.96369 2.6006 + vertex 0.969989 1.96738 2.59965 + endloop + endfacet + facet normal -0.0417303 0.248623 0.967701 + outer loop + vertex 0.956753 1.96278 2.60068 + vertex 0.960693 1.96361 2.60064 + vertex 0.958537 1.96686 2.59971 + endloop + endfacet + facet normal -0.0374035 0.228477 0.972831 + outer loop + vertex 0.960693 1.96361 2.60064 + vertex 0.956753 1.96278 2.60068 + vertex 0.957347 1.96003 2.60135 + endloop + endfacet + facet normal -0.0209442 0.209956 0.977486 + outer loop + vertex 0.957808 1.95625 2.60217 + vertex 0.961908 1.96008 2.60143 + vertex 0.957347 1.96003 2.60135 + endloop + endfacet + facet normal -0.0178407 0.209929 0.977554 + outer loop + vertex 0.958232 1.95187 2.60312 + vertex 0.962633 1.95611 2.60229 + vertex 0.957808 1.95625 2.60217 + endloop + endfacet + facet normal -0.0113715 0.203491 0.979011 + outer loop + vertex 0.96309 1.95186 2.60318 + vertex 0.962633 1.95611 2.60229 + vertex 0.958232 1.95187 2.60312 + endloop + endfacet + facet normal -0.0113389 0.208929 0.977865 + outer loop + vertex 0.9585 1.94726 2.60411 + vertex 0.96309 1.95186 2.60318 + vertex 0.958232 1.95187 2.60312 + endloop + endfacet + facet normal 0.00212114 0.19604 0.980594 + outer loop + vertex 0.963654 1.94743 2.60406 + vertex 0.96309 1.95186 2.60318 + vertex 0.9585 1.94726 2.60411 + endloop + endfacet + facet normal 0.00173344 0.207208 0.978295 + outer loop + vertex 0.959187 1.943 2.60501 + vertex 0.963654 1.94743 2.60406 + vertex 0.9585 1.94726 2.60411 + endloop + endfacet + facet normal 0.0142744 0.20761 0.978107 + outer loop + vertex 0.959187 1.943 2.60501 + vertex 0.960407 1.93925 2.60579 + vertex 0.964465 1.94304 2.60492 + endloop + endfacet + facet normal 0.0240946 0.197534 0.98 + outer loop + vertex 0.960407 1.93925 2.60579 + vertex 0.965467 1.93893 2.60573 + vertex 0.964465 1.94304 2.60492 + endloop + endfacet + facet normal 0.038306 0.200261 0.978993 + outer loop + vertex 0.969539 1.93832 2.60569 + vertex 0.965467 1.93893 2.60573 + vertex 0.967071 1.93475 2.60652 + endloop + endfacet + facet normal 0.0305979 0.185958 0.982081 + outer loop + vertex 0.960356 1.91429 2.61071 + vertex 0.965301 1.91381 2.61064 + vertex 0.96436 1.91792 2.60989 + endloop + endfacet + facet normal 0.00245414 0.186649 0.982424 + outer loop + vertex 0.957804 1.90663 2.61224 + vertex 0.956684 1.91074 2.61146 + vertex 0.952761 1.90673 2.61223 + endloop + endfacet + facet normal 0.00255797 0.191746 0.981441 + outer loop + vertex 0.953395 1.90212 2.61313 + vertex 0.957804 1.90663 2.61224 + vertex 0.952761 1.90673 2.61223 + endloop + endfacet + facet normal 0.0105849 0.183046 0.983047 + outer loop + vertex 0.953769 1.89708 2.61406 + vertex 0.958475 1.90199 2.6131 + vertex 0.953395 1.90212 2.61313 + endloop + endfacet + facet normal 0.0177412 0.17641 0.984157 + outer loop + vertex 0.958948 1.89723 2.61394 + vertex 0.958475 1.90199 2.6131 + vertex 0.953769 1.89708 2.61406 + endloop + endfacet + facet normal 0.0361754 0.172368 0.984368 + outer loop + vertex 0.95982 1.89354 2.61456 + vertex 0.963669 1.89726 2.61376 + vertex 0.958948 1.89723 2.61394 + endloop + endfacet + facet normal 0.0257069 0.172503 0.984673 + outer loop + vertex 0.95437 1.88807 2.61565 + vertex 0.958836 1.88932 2.61532 + vertex 0.954807 1.8921 2.61493 + endloop + endfacet + facet normal 0.0365856 0.171956 0.984425 + outer loop + vertex 0.963716 1.89282 2.61454 + vertex 0.963669 1.89726 2.61376 + vertex 0.95982 1.89354 2.61456 + endloop + endfacet + facet normal 0.0385778 0.173216 0.984128 + outer loop + vertex 0.964079 1.88866 2.61526 + vertex 0.96857 1.89253 2.6144 + vertex 0.963716 1.89282 2.61454 + endloop + endfacet + facet normal 0.032379 0.174299 0.98416 + outer loop + vertex 0.960314 1.8853 2.61597 + vertex 0.965247 1.88482 2.6159 + vertex 0.964079 1.88866 2.61526 + endloop + endfacet + facet normal 0.0323499 0.173993 0.984215 + outer loop + vertex 0.965247 1.88482 2.6159 + vertex 0.960314 1.8853 2.61597 + vertex 0.961634 1.88127 2.61664 + endloop + endfacet + facet normal 0.0289677 0.172935 0.984507 + outer loop + vertex 0.961634 1.88127 2.61664 + vertex 0.960314 1.8853 2.61597 + vertex 0.956283 1.88191 2.61669 + endloop + endfacet + facet normal 0.0255063 0.173187 0.984559 + outer loop + vertex 0.95437 1.88807 2.61565 + vertex 0.956317 1.8859 2.61598 + vertex 0.958836 1.88932 2.61532 + endloop + endfacet + facet normal 0.0106165 0.174138 0.984664 + outer loop + vertex 0.950531 1.88834 2.61565 + vertex 0.95437 1.88807 2.61565 + vertex 0.954807 1.8921 2.61493 + endloop + endfacet + facet normal 0.0190586 0.176552 0.984107 + outer loop + vertex 0.952109 1.88468 2.61627 + vertex 0.951744 1.8807 2.61699 + vertex 0.956283 1.88191 2.61669 + endloop + endfacet + facet normal 0.0188792 0.177199 0.983994 + outer loop + vertex 0.952971 1.87708 2.61762 + vertex 0.956283 1.88191 2.61669 + vertex 0.951744 1.8807 2.61699 + endloop + endfacet + facet normal 0.00390819 0.172303 0.985036 + outer loop + vertex 0.952971 1.87708 2.61762 + vertex 0.951744 1.8807 2.61699 + vertex 0.948272 1.87701 2.61765 + endloop + endfacet + facet normal 0.0170518 0.15959 0.987036 + outer loop + vertex 0.953812 1.86715 2.61926 + vertex 0.953507 1.8722 2.61844 + vertex 0.948631 1.8672 2.61934 + endloop + endfacet + facet normal 0.00385384 0.175324 0.984503 + outer loop + vertex 0.948569 1.87224 2.6185 + vertex 0.952971 1.87708 2.61762 + vertex 0.948272 1.87701 2.61765 + endloop + endfacet + facet normal 0.025793 0.172579 0.984658 + outer loop + vertex 0.957826 1.87704 2.6175 + vertex 0.956283 1.88191 2.61669 + vertex 0.952971 1.87708 2.61762 + endloop + endfacet + facet normal 0.0351899 0.163868 0.985854 + outer loop + vertex 0.963431 1.87199 2.61815 + vertex 0.962826 1.8768 2.61738 + vertex 0.958465 1.87207 2.61832 + endloop + endfacet + facet normal 0.0290418 0.173565 0.984394 + outer loop + vertex 0.957826 1.87704 2.6175 + vertex 0.961634 1.88127 2.61664 + vertex 0.956283 1.88191 2.61669 + endloop + endfacet + facet normal 0.033635 0.172723 0.984396 + outer loop + vertex 0.966663 1.88093 2.61653 + vertex 0.965247 1.88482 2.6159 + vertex 0.961634 1.88127 2.61664 + endloop + endfacet + facet normal 0.0385002 0.168308 0.984982 + outer loop + vertex 0.967813 1.87664 2.61722 + vertex 0.971686 1.8806 2.61639 + vertex 0.966663 1.88093 2.61653 + endloop + endfacet + facet normal 0.0410581 0.162043 0.985929 + outer loop + vertex 0.968371 1.87194 2.61797 + vertex 0.972695 1.87636 2.61706 + vertex 0.967813 1.87664 2.61722 + endloop + endfacet + facet normal 0.0402108 0.157605 0.986683 + outer loop + vertex 0.968452 1.86711 2.61874 + vertex 0.968371 1.87194 2.61797 + vertex 0.963642 1.86723 2.61891 + endloop + endfacet + facet normal 0.0300969 0.156299 0.987251 + outer loop + vertex 0.954291 1.85823 2.62065 + vertex 0.95875 1.85935 2.62034 + vertex 0.954751 1.86224 2.62 + endloop + endfacet + facet normal 0.0367104 0.156478 0.986999 + outer loop + vertex 0.963605 1.86277 2.61962 + vertex 0.963642 1.86723 2.61891 + vertex 0.959659 1.86348 2.61966 + endloop + endfacet + facet normal 0.040197 0.157218 0.986745 + outer loop + vertex 0.964009 1.8586 2.62027 + vertex 0.968521 1.86243 2.61948 + vertex 0.963605 1.86277 2.61962 + endloop + endfacet + facet normal 0.0364329 0.15756 0.986837 + outer loop + vertex 0.960349 1.85535 2.62092 + vertex 0.965263 1.85472 2.62084 + vertex 0.964009 1.8586 2.62027 + endloop + endfacet + facet normal 0.0333951 0.156826 0.987061 + outer loop + vertex 0.961784 1.85133 2.62151 + vertex 0.960349 1.85535 2.62092 + vertex 0.956414 1.85199 2.62159 + endloop + endfacet + facet normal 0.0264096 0.161476 0.986523 + outer loop + vertex 0.952082 1.85486 2.62124 + vertex 0.95189 1.85079 2.62191 + vertex 0.956414 1.85199 2.62159 + endloop + endfacet + facet normal 0.0272167 0.15856 0.986974 + outer loop + vertex 0.953154 1.84708 2.62247 + vertex 0.956414 1.85199 2.62159 + vertex 0.95189 1.85079 2.62191 + endloop + endfacet + facet normal 0.0191965 0.155915 0.987584 + outer loop + vertex 0.953154 1.84708 2.62247 + vertex 0.95189 1.85079 2.62191 + vertex 0.94845 1.84707 2.62256 + endloop + endfacet + facet normal 0.0106326 0.162246 0.986693 + outer loop + vertex 0.95189 1.85079 2.62191 + vertex 0.952082 1.85486 2.62124 + vertex 0.94785 1.85147 2.62184 + endloop + endfacet + facet normal 0.0294059 0.158934 0.986851 + outer loop + vertex 0.954291 1.85823 2.62065 + vertex 0.956328 1.85601 2.62095 + vertex 0.95875 1.85935 2.62034 + endloop + endfacet + facet normal 0.0194385 0.157533 0.987322 + outer loop + vertex 0.950328 1.85875 2.62065 + vertex 0.954291 1.85823 2.62065 + vertex 0.954751 1.86224 2.62 + endloop + endfacet + facet normal 0.00596913 0.152992 0.988209 + outer loop + vertex 0.945483 1.85881 2.62067 + vertex 0.950328 1.85875 2.62065 + vertex 0.949226 1.86264 2.62005 + endloop + endfacet + facet normal 0.00987233 0.163169 0.986549 + outer loop + vertex 0.94785 1.85147 2.62184 + vertex 0.952082 1.85486 2.62124 + vertex 0.946852 1.85539 2.6212 + endloop + endfacet + facet normal 0.0108423 0.163464 0.98649 + outer loop + vertex 0.94845 1.84707 2.62256 + vertex 0.95189 1.85079 2.62191 + vertex 0.94785 1.85147 2.62184 + endloop + endfacet + facet normal 0.0191934 0.156572 0.98748 + outer loop + vertex 0.948705 1.8422 2.62333 + vertex 0.953154 1.84708 2.62247 + vertex 0.94845 1.84707 2.62256 + endloop + endfacet + facet normal 0.0245916 0.148986 0.988534 + outer loop + vertex 0.948557 1.83714 2.6241 + vertex 0.95361 1.84216 2.62321 + vertex 0.948705 1.8422 2.62333 + endloop + endfacet + facet normal 0.0267287 0.143731 0.989256 + outer loop + vertex 0.948479 1.83249 2.62477 + vertex 0.953496 1.83711 2.62397 + vertex 0.948557 1.83714 2.6241 + endloop + endfacet + facet normal 0.0144196 0.141437 0.989842 + outer loop + vertex 0.948969 1.82848 2.62534 + vertex 0.948479 1.83249 2.62477 + vertex 0.944053 1.82846 2.62541 + endloop + endfacet + facet normal -0.0327624 0.142601 0.989238 + outer loop + vertex 0.93552 1.82398 2.62588 + vertex 0.940307 1.82472 2.62594 + vertex 0.939033 1.82806 2.62541 + endloop + endfacet + facet normal 0.0144146 0.142501 0.98969 + outer loop + vertex 0.944053 1.82846 2.62541 + vertex 0.945207 1.82493 2.62591 + vertex 0.948969 1.82848 2.62534 + endloop + endfacet + facet normal 0.0162084 0.141761 0.989768 + outer loop + vertex 0.950139 1.82484 2.62584 + vertex 0.945207 1.82493 2.62591 + vertex 0.946684 1.82129 2.6264 + endloop + endfacet + facet normal -0.00900977 0.136599 0.990585 + outer loop + vertex 0.943634 1.81246 2.62766 + vertex 0.942923 1.81717 2.62701 + vertex 0.938512 1.81237 2.62763 + endloop + endfacet + facet normal 0.0161016 0.134515 0.990781 + outer loop + vertex 0.943728 1.80732 2.62836 + vertex 0.948688 1.81242 2.62759 + vertex 0.943634 1.81246 2.62766 + endloop + endfacet + facet normal 0.00332414 0.129791 0.991536 + outer loop + vertex 0.943473 1.8021 2.62905 + vertex 0.943728 1.80732 2.62836 + vertex 0.938484 1.8021 2.62906 + endloop + endfacet + facet normal 0.00332299 0.126674 0.991939 + outer loop + vertex 0.938378 1.7971 2.6297 + vertex 0.943473 1.8021 2.62905 + vertex 0.938484 1.8021 2.62906 + endloop + endfacet + facet normal -0.0240192 0.118316 0.992685 + outer loop + vertex 0.939027 1.79283 2.63023 + vertex 0.938378 1.7971 2.6297 + vertex 0.93332 1.79174 2.63022 + endloop + endfacet + facet normal -0.0352181 0.126026 0.991402 + outer loop + vertex 0.931691 1.78766 2.63068 + vertex 0.935585 1.78886 2.63066 + vertex 0.93332 1.79174 2.63022 + endloop + endfacet + facet normal -0.0335152 0.120512 0.992146 + outer loop + vertex 0.935585 1.78886 2.63066 + vertex 0.931691 1.78766 2.63068 + vertex 0.93254 1.78524 2.631 + endloop + endfacet + facet normal -0.0198354 0.11476 0.993195 + outer loop + vertex 0.93307 1.78165 2.63143 + vertex 0.936939 1.78563 2.63104 + vertex 0.93254 1.78524 2.631 + endloop + endfacet + facet normal -0.0193022 0.108719 0.993885 + outer loop + vertex 0.936939 1.78563 2.63104 + vertex 0.935585 1.78886 2.63066 + vertex 0.93254 1.78524 2.631 + endloop + endfacet + facet normal -0.00542306 0.114488 0.99341 + outer loop + vertex 0.940361 1.78923 2.63065 + vertex 0.935585 1.78886 2.63066 + vertex 0.936939 1.78563 2.63104 + endloop + endfacet + facet normal 0.00728637 0.11768 0.993025 + outer loop + vertex 0.940361 1.78923 2.63065 + vertex 0.945224 1.78895 2.63064 + vertex 0.94411 1.79285 2.63019 + endloop + endfacet + facet normal 0.0148584 0.117548 0.992956 + outer loop + vertex 0.9492 1.78835 2.63066 + vertex 0.945224 1.78895 2.63064 + vertex 0.94705 1.78501 2.63108 + endloop + endfacet + facet normal 0.0218864 0.118979 0.992656 + outer loop + vertex 0.94705 1.78501 2.63108 + vertex 0.946867 1.78093 2.63158 + vertex 0.951405 1.78207 2.63134 + endloop + endfacet + facet normal 0.0221779 0.117844 0.992784 + outer loop + vertex 0.948181 1.7773 2.63198 + vertex 0.951405 1.78207 2.63134 + vertex 0.946867 1.78093 2.63158 + endloop + endfacet + facet normal 0.0265386 0.114926 0.993019 + outer loop + vertex 0.953063 1.77724 2.63186 + vertex 0.951405 1.78207 2.63134 + vertex 0.948181 1.7773 2.63198 + endloop + endfacet + facet normal 0.0337794 0.106991 0.993686 + outer loop + vertex 0.953679 1.77236 2.63236 + vertex 0.957894 1.77672 2.63175 + vertex 0.953063 1.77724 2.63186 + endloop + endfacet + facet normal 0.0355288 0.0929081 0.995041 + outer loop + vertex 0.953786 1.76735 2.63282 + vertex 0.958423 1.77218 2.63221 + vertex 0.953679 1.77236 2.63236 + endloop + endfacet + facet normal 0.0277094 0.0764238 0.99669 + outer loop + vertex 0.953677 1.76225 2.63322 + vertex 0.953786 1.76735 2.63282 + vertex 0.948645 1.76222 2.63336 + endloop + endfacet + facet normal 0.0392318 0.0761508 0.996324 + outer loop + vertex 0.953677 1.76225 2.63322 + vertex 0.958716 1.76739 2.63263 + vertex 0.953786 1.76735 2.63282 + endloop + endfacet + facet normal 0.0390721 0.0895284 0.995218 + outer loop + vertex 0.958716 1.76739 2.63263 + vertex 0.958423 1.77218 2.63221 + vertex 0.953786 1.76735 2.63282 + endloop + endfacet + facet normal 0.0449708 0.0898652 0.994938 + outer loop + vertex 0.958716 1.76739 2.63263 + vertex 0.963065 1.77226 2.63199 + vertex 0.958423 1.77218 2.63221 + endloop + endfacet + facet normal 0.0409795 0.0744451 0.996383 + outer loop + vertex 0.958718 1.76233 2.633 + vertex 0.958716 1.76739 2.63263 + vertex 0.953677 1.76225 2.63322 + endloop + endfacet + facet normal 0.0488401 0.0727626 0.996153 + outer loop + vertex 0.963785 1.76243 2.63275 + vertex 0.963672 1.76749 2.63238 + vertex 0.958718 1.76233 2.633 + endloop + endfacet + facet normal 0.0498441 0.0727812 0.996102 + outer loop + vertex 0.963785 1.76243 2.63275 + vertex 0.968642 1.76748 2.63214 + vertex 0.963672 1.76749 2.63238 + endloop + endfacet + facet normal 0.05161 0.0710856 0.996134 + outer loop + vertex 0.968849 1.7625 2.63248 + vertex 0.968642 1.76748 2.63214 + vertex 0.963785 1.76243 2.63275 + endloop + endfacet + facet normal 0.0473731 0.0709246 0.996356 + outer loop + vertex 0.968849 1.7625 2.63248 + vertex 0.97343 1.76723 2.63193 + vertex 0.968642 1.76748 2.63214 + endloop + endfacet + facet normal 0.0498383 0.0685428 0.996403 + outer loop + vertex 0.973814 1.76249 2.63223 + vertex 0.97343 1.76723 2.63193 + vertex 0.968849 1.7625 2.63248 + endloop + endfacet + facet normal 0.0466493 0.0581916 0.997215 + outer loop + vertex 0.973878 1.75748 2.63252 + vertex 0.978489 1.76236 2.63202 + vertex 0.973814 1.76249 2.63223 + endloop + endfacet + facet normal 0.0498844 0.0552682 0.997225 + outer loop + vertex 0.973774 1.75239 2.63281 + vertex 0.978747 1.75755 2.63228 + vertex 0.973878 1.75748 2.63252 + endloop + endfacet + facet normal 0.0525471 0.0597464 0.99683 + outer loop + vertex 0.973602 1.74727 2.63313 + vertex 0.978749 1.75254 2.63254 + vertex 0.973774 1.75239 2.63281 + endloop + endfacet + facet normal 0.0560113 0.0681074 0.996104 + outer loop + vertex 0.973439 1.74214 2.63349 + vertex 0.978661 1.74744 2.63283 + vertex 0.973602 1.74727 2.63313 + endloop + endfacet + facet normal 0.0500737 0.0772239 0.995756 + outer loop + vertex 0.973305 1.73704 2.63389 + vertex 0.973439 1.74214 2.63349 + vertex 0.968163 1.73691 2.63416 + endloop + endfacet + facet normal 0.0468538 0.0839718 0.995366 + outer loop + vertex 0.968266 1.73217 2.63455 + vertex 0.968163 1.73691 2.63416 + vertex 0.963385 1.73225 2.63477 + endloop + endfacet + facet normal 0.0482423 0.0767598 0.995882 + outer loop + vertex 0.963102 1.73691 2.6344 + vertex 0.96826 1.74193 2.63376 + vertex 0.963147 1.74185 2.63402 + endloop + endfacet + facet normal 0.049925 0.0671355 0.996494 + outer loop + vertex 0.963147 1.74185 2.63402 + vertex 0.968442 1.74706 2.6334 + vertex 0.963295 1.74694 2.63366 + endloop + endfacet + facet normal 0.051718 0.0579465 0.996979 + outer loop + vertex 0.963295 1.74694 2.63366 + vertex 0.968636 1.75222 2.63308 + vertex 0.963482 1.7521 2.63335 + endloop + endfacet + facet normal 0.0425918 0.0656812 0.996931 + outer loop + vertex 0.958133 1.74189 2.63425 + vertex 0.958219 1.74693 2.63391 + vertex 0.953166 1.74199 2.63445 + endloop + endfacet + facet normal 0.0298741 0.0574528 0.997901 + outer loop + vertex 0.953218 1.74697 2.63413 + vertex 0.953367 1.75205 2.63383 + vertex 0.948289 1.74705 2.63427 + endloop + endfacet + facet normal 0.0422412 0.0552358 0.997579 + outer loop + vertex 0.953367 1.75205 2.63383 + vertex 0.958568 1.75719 2.63332 + vertex 0.95352 1.75714 2.63354 + endloop + endfacet + facet normal 0.00368645 0.0619779 0.998071 + outer loop + vertex 0.943392 1.74714 2.63429 + vertex 0.948401 1.75208 2.63397 + vertex 0.943444 1.75213 2.63398 + endloop + endfacet + facet normal -0.0221178 0.0736732 0.997037 + outer loop + vertex 0.943322 1.7422 2.63465 + vertex 0.943392 1.74714 2.63429 + vertex 0.938419 1.74222 2.63454 + endloop + endfacet + facet normal -0.02203 0.0913487 0.995575 + outer loop + vertex 0.938461 1.73739 2.63499 + vertex 0.943322 1.7422 2.63465 + vertex 0.938419 1.74222 2.63454 + endloop + endfacet + facet normal -0.0115964 0.0808798 0.996656 + outer loop + vertex 0.943489 1.73755 2.63503 + vertex 0.943322 1.7422 2.63465 + vertex 0.938461 1.73739 2.63499 + endloop + endfacet + facet normal 0.016929 0.0760477 0.99696 + outer loop + vertex 0.948482 1.73737 2.63496 + vertex 0.948222 1.74211 2.63461 + vertex 0.943489 1.73755 2.63503 + endloop + endfacet + facet normal 0.0345416 0.0746353 0.996612 + outer loop + vertex 0.953462 1.73728 2.6348 + vertex 0.953166 1.74199 2.63445 + vertex 0.948482 1.73737 2.63496 + endloop + endfacet + facet normal 0.0426609 0.0821579 0.995706 + outer loop + vertex 0.954442 1.73363 2.63506 + vertex 0.958261 1.73716 2.6346 + vertex 0.953462 1.73728 2.6348 + endloop + endfacet + facet normal 0.0384223 0.0877716 0.995399 + outer loop + vertex 0.949248 1.72863 2.63569 + vertex 0.953759 1.72941 2.63545 + vertex 0.949589 1.73263 2.63532 + endloop + endfacet + facet normal 0.0382328 0.0888324 0.995313 + outer loop + vertex 0.949248 1.72863 2.63569 + vertex 0.951311 1.72617 2.63583 + vertex 0.953759 1.72941 2.63545 + endloop + endfacet + facet normal 0.0323666 0.0839349 0.995945 + outer loop + vertex 0.951311 1.72617 2.63583 + vertex 0.949248 1.72863 2.63569 + vertex 0.947026 1.72524 2.63605 + endloop + endfacet + facet normal 0.0317274 0.0867991 0.99572 + outer loop + vertex 0.951311 1.72617 2.63583 + vertex 0.947026 1.72524 2.63605 + vertex 0.951397 1.72201 2.63619 + endloop + endfacet + facet normal 0.040684 0.0869548 0.995381 + outer loop + vertex 0.951311 1.72617 2.63583 + vertex 0.951397 1.72201 2.63619 + vertex 0.955323 1.72502 2.63577 + endloop + endfacet + facet normal 0.0404597 0.0872446 0.995365 + outer loop + vertex 0.957048 1.72052 2.63609 + vertex 0.955323 1.72502 2.63577 + vertex 0.951397 1.72201 2.63619 + endloop + endfacet + facet normal 0.0424584 0.0823753 0.995697 + outer loop + vertex 0.958473 1.73263 2.63497 + vertex 0.958261 1.73716 2.6346 + vertex 0.954442 1.73363 2.63506 + endloop + endfacet + facet normal 0.0455004 0.086404 0.995221 + outer loop + vertex 0.959499 1.72785 2.63533 + vertex 0.963385 1.73225 2.63477 + vertex 0.958473 1.73263 2.63497 + endloop + endfacet + facet normal 0.0406918 0.086982 0.995378 + outer loop + vertex 0.955323 1.72502 2.63577 + vertex 0.953759 1.72941 2.63545 + vertex 0.951311 1.72617 2.63583 + endloop + endfacet + facet normal 0.0437064 0.0884726 0.995119 + outer loop + vertex 0.959268 1.72382 2.6357 + vertex 0.955323 1.72502 2.63577 + vertex 0.957048 1.72052 2.63609 + endloop + endfacet + facet normal 0.0450621 0.0882693 0.995077 + outer loop + vertex 0.959499 1.72785 2.63533 + vertex 0.963731 1.72441 2.63545 + vertex 0.96436 1.7286 2.63505 + endloop + endfacet + facet normal 0.0451221 0.0882578 0.995075 + outer loop + vertex 0.963731 1.72441 2.63545 + vertex 0.965338 1.71991 2.63577 + vertex 0.969637 1.72265 2.63534 + endloop + endfacet + facet normal 0.0458605 0.0877227 0.995089 + outer loop + vertex 0.967125 1.71526 2.6361 + vertex 0.965338 1.71991 2.63577 + vertex 0.961407 1.71704 2.63621 + endloop + endfacet + facet normal 0.0441898 0.0881483 0.995127 + outer loop + vertex 0.961318 1.72125 2.63584 + vertex 0.959268 1.72382 2.6357 + vertex 0.957048 1.72052 2.63609 + endloop + endfacet + facet normal 0.0399076 0.0891818 0.995216 + outer loop + vertex 0.956854 1.71613 2.63649 + vertex 0.957048 1.72052 2.63609 + vertex 0.952883 1.71704 2.63657 + endloop + endfacet + facet normal 0.0459514 0.088017 0.995059 + outer loop + vertex 0.962899 1.71205 2.63658 + vertex 0.967125 1.71526 2.6361 + vertex 0.961407 1.71704 2.63621 + endloop + endfacet + facet normal 0.046349 0.0853131 0.995276 + outer loop + vertex 0.963479 1.70735 2.63696 + vertex 0.962899 1.71205 2.63658 + vertex 0.958689 1.70758 2.63716 + endloop + endfacet + facet normal 0.0410588 0.0836339 0.99565 + outer loop + vertex 0.958822 1.70256 2.63758 + vertex 0.958689 1.70758 2.63716 + vertex 0.95375 1.70248 2.63779 + endloop + endfacet + facet normal 0.0400094 0.0862937 0.995466 + outer loop + vertex 0.953754 1.70754 2.63736 + vertex 0.958118 1.71237 2.63677 + vertex 0.953456 1.71236 2.63696 + endloop + endfacet + facet normal 0.039521 0.087495 0.995381 + outer loop + vertex 0.953456 1.71236 2.63696 + vertex 0.956854 1.71613 2.63649 + vertex 0.952883 1.71704 2.63657 + endloop + endfacet + facet normal 0.0407148 0.0882226 0.995268 + outer loop + vertex 0.952883 1.71704 2.63657 + vertex 0.957048 1.72052 2.63609 + vertex 0.951397 1.72201 2.63619 + endloop + endfacet + facet normal 0.0330146 0.0885322 0.995526 + outer loop + vertex 0.947026 1.72524 2.63605 + vertex 0.946843 1.72107 2.63642 + vertex 0.951397 1.72201 2.63619 + endloop + endfacet + facet normal 0.0257167 0.0882707 0.995764 + outer loop + vertex 0.949248 1.72863 2.63569 + vertex 0.945255 1.72936 2.63573 + vertex 0.947026 1.72524 2.63605 + endloop + endfacet + facet normal 0.00712827 0.0863221 0.996242 + outer loop + vertex 0.940395 1.72963 2.63574 + vertex 0.945255 1.72936 2.63573 + vertex 0.944195 1.73329 2.63539 + endloop + endfacet + facet normal -0.0180107 0.089435 0.99583 + outer loop + vertex 0.935638 1.72913 2.6357 + vertex 0.940395 1.72963 2.63574 + vertex 0.93914 1.73321 2.63539 + endloop + endfacet + facet normal -0.00946507 0.0907101 0.995832 + outer loop + vertex 0.937913 1.722 2.63638 + vertex 0.941779 1.72593 2.63606 + vertex 0.93691 1.72588 2.63602 + endloop + endfacet + facet normal -0.00440342 0.0919451 0.995754 + outer loop + vertex 0.938568 1.7175 2.6368 + vertex 0.942815 1.72183 2.63642 + vertex 0.937913 1.722 2.63638 + endloop + endfacet + facet normal 0.000553895 0.087118 0.996198 + outer loop + vertex 0.94345 1.71738 2.63681 + vertex 0.942815 1.72183 2.63642 + vertex 0.938568 1.7175 2.6368 + endloop + endfacet + facet normal 0.0224142 0.0878464 0.995882 + outer loop + vertex 0.943837 1.71255 2.63723 + vertex 0.948146 1.71732 2.63671 + vertex 0.94345 1.71738 2.63681 + endloop + endfacet + facet normal 0.0252415 0.0860914 0.995967 + outer loop + vertex 0.943822 1.70742 2.63767 + vertex 0.948725 1.7125 2.63711 + vertex 0.943837 1.71255 2.63723 + endloop + endfacet + facet normal 0.026028 0.0846232 0.996073 + outer loop + vertex 0.943649 1.70229 2.63811 + vertex 0.948805 1.70746 2.63754 + vertex 0.943822 1.70742 2.63767 + endloop + endfacet + facet normal 0.0261485 0.0845037 0.99608 + outer loop + vertex 0.948686 1.70236 2.63797 + vertex 0.948805 1.70746 2.63754 + vertex 0.943649 1.70229 2.63811 + endloop + endfacet + facet normal 0.0338781 0.0824147 0.996022 + outer loop + vertex 0.948529 1.69726 2.6384 + vertex 0.95375 1.70248 2.63779 + vertex 0.948686 1.70236 2.63797 + endloop + endfacet + facet normal 0.0268989 0.0783914 0.99656 + outer loop + vertex 0.943293 1.68712 2.63935 + vertex 0.948385 1.69215 2.63882 + vertex 0.943395 1.69218 2.63895 + endloop + endfacet + facet normal 0.026906 0.0760715 0.996739 + outer loop + vertex 0.943272 1.68215 2.63973 + vertex 0.948254 1.68704 2.63922 + vertex 0.943293 1.68712 2.63935 + endloop + endfacet + facet normal 0.0269702 0.0746751 0.996843 + outer loop + vertex 0.943603 1.6775 2.64007 + vertex 0.948197 1.68203 2.63961 + vertex 0.943272 1.68215 2.63973 + endloop + endfacet + facet normal 0.0211275 0.0714765 0.997219 + outer loop + vertex 0.944583 1.674 2.6403 + vertex 0.943603 1.6775 2.64007 + vertex 0.939764 1.67292 2.64048 + endloop + endfacet + facet normal 0.010484 0.0727288 0.997297 + outer loop + vertex 0.935408 1.66949 2.64078 + vertex 0.939467 1.66904 2.64077 + vertex 0.939764 1.67292 2.64048 + endloop + endfacet + facet normal -0.00289401 0.0669475 0.997752 + outer loop + vertex 0.935408 1.66949 2.64078 + vertex 0.930535 1.66936 2.64077 + vertex 0.93194 1.66594 2.641 + endloop + endfacet + facet normal 0.00663643 0.0731802 0.997297 + outer loop + vertex 0.934165 1.67323 2.64051 + vertex 0.938594 1.67753 2.64017 + vertex 0.9334 1.67752 2.6402 + endloop + endfacet + facet normal 0.00575054 0.0744384 0.997209 + outer loop + vertex 0.9334 1.67752 2.6402 + vertex 0.938321 1.68228 2.63982 + vertex 0.933378 1.68235 2.63984 + endloop + endfacet + facet normal 0.00326232 0.0793793 0.996839 + outer loop + vertex 0.933378 1.68235 2.63984 + vertex 0.938384 1.68724 2.63943 + vertex 0.933473 1.6873 2.63945 + endloop + endfacet + facet normal -0.000932011 0.084513 0.996422 + outer loop + vertex 0.933473 1.6873 2.63945 + vertex 0.938453 1.69223 2.63903 + vertex 0.933478 1.69226 2.63903 + endloop + endfacet + facet normal -0.00600326 0.0881901 0.996086 + outer loop + vertex 0.933478 1.69226 2.63903 + vertex 0.938497 1.69722 2.63862 + vertex 0.933456 1.69721 2.63859 + endloop + endfacet + facet normal -0.010612 0.0905877 0.995832 + outer loop + vertex 0.933456 1.69721 2.63859 + vertex 0.938607 1.70227 2.63818 + vertex 0.93351 1.70224 2.63813 + endloop + endfacet + facet normal -0.0151589 0.0930052 0.99555 + outer loop + vertex 0.93351 1.70224 2.63813 + vertex 0.938774 1.70741 2.63773 + vertex 0.933627 1.70738 2.63765 + endloop + endfacet + facet normal -0.0202542 0.095513 0.995222 + outer loop + vertex 0.933627 1.70738 2.63765 + vertex 0.938825 1.71256 2.63726 + vertex 0.933658 1.71251 2.63716 + endloop + endfacet + facet normal -0.0791346 0.0960916 0.992222 + outer loop + vertex 0.928422 1.70731 2.63741 + vertex 0.928448 1.71238 2.63692 + vertex 0.923356 1.70725 2.63701 + endloop + endfacet + facet normal -0.079116 0.0910851 0.992695 + outer loop + vertex 0.923259 1.70213 2.63748 + vertex 0.928422 1.70731 2.63741 + vertex 0.923356 1.70725 2.63701 + endloop + endfacet + facet normal -0.0850601 0.0970049 0.991642 + outer loop + vertex 0.928356 1.70219 2.63791 + vertex 0.928422 1.70731 2.63741 + vertex 0.923259 1.70213 2.63748 + endloop + endfacet + facet normal -0.0850564 0.0953358 0.991805 + outer loop + vertex 0.923308 1.69706 2.63797 + vertex 0.928356 1.70219 2.63791 + vertex 0.923259 1.70213 2.63748 + endloop + endfacet + facet normal -0.0844404 0.0947301 0.991915 + outer loop + vertex 0.928353 1.69715 2.63839 + vertex 0.928356 1.70219 2.63791 + vertex 0.923308 1.69706 2.63797 + endloop + endfacet + facet normal -0.0797026 0.089914 0.992755 + outer loop + vertex 0.928474 1.68725 2.63931 + vertex 0.928417 1.69218 2.63886 + vertex 0.92341 1.6871 2.63891 + endloop + endfacet + facet normal -0.155723 0.0900228 0.98369 + outer loop + vertex 0.923395 1.68215 2.63937 + vertex 0.92341 1.6871 2.63891 + vertex 0.918388 1.68209 2.63858 + endloop + endfacet + facet normal -0.154194 0.0912924 0.983814 + outer loop + vertex 0.918324 1.67207 2.63949 + vertex 0.923302 1.6772 2.63979 + vertex 0.918316 1.67705 2.63903 + endloop + endfacet + facet normal -0.142622 0.079918 0.986546 + outer loop + vertex 0.923123 1.67224 2.64017 + vertex 0.923302 1.6772 2.63979 + vertex 0.918324 1.67207 2.63949 + endloop + endfacet + facet normal -0.14251 0.0752355 0.98693 + outer loop + vertex 0.918171 1.66703 2.63985 + vertex 0.923123 1.67224 2.64017 + vertex 0.918324 1.67207 2.63949 + endloop + endfacet + facet normal -0.148009 0.080543 0.985701 + outer loop + vertex 0.92282 1.66728 2.64053 + vertex 0.923123 1.67224 2.64017 + vertex 0.918171 1.66703 2.63985 + endloop + endfacet + facet normal -0.287162 0.0983382 0.952821 + outer loop + vertex 0.91674 1.65623 2.6404 + vertex 0.918029 1.66171 2.64023 + vertex 0.913283 1.65676 2.63931 + endloop + endfacet + facet normal -0.0902599 0.058624 0.994191 + outer loop + vertex 0.923379 1.65748 2.6412 + vertex 0.92427 1.66244 2.64099 + vertex 0.920529 1.6595 2.64083 + endloop + endfacet + facet normal -0.0957083 0.073912 0.992662 + outer loop + vertex 0.918743 1.64208 2.64181 + vertex 0.923522 1.6472 2.64189 + vertex 0.918474 1.64708 2.64141 + endloop + endfacet + facet normal -0.0956259 0.0689847 0.993024 + outer loop + vertex 0.923522 1.6472 2.64189 + vertex 0.923644 1.65236 2.64154 + vertex 0.918474 1.64708 2.64141 + endloop + endfacet + facet normal -0.0914369 0.0699083 0.993354 + outer loop + vertex 0.923437 1.64212 2.64224 + vertex 0.923522 1.6472 2.64189 + vertex 0.918743 1.64208 2.64181 + endloop + endfacet + facet normal -0.091421 0.0637667 0.993769 + outer loop + vertex 0.918665 1.63723 2.64211 + vertex 0.923437 1.64212 2.64224 + vertex 0.918743 1.64208 2.64181 + endloop + endfacet + facet normal -0.0896313 0.0620148 0.994042 + outer loop + vertex 0.923351 1.63716 2.64254 + vertex 0.923437 1.64212 2.64224 + vertex 0.918665 1.63723 2.64211 + endloop + endfacet + facet normal -0.0897799 0.0544894 0.99447 + outer loop + vertex 0.918547 1.63234 2.64237 + vertex 0.923351 1.63716 2.64254 + vertex 0.918665 1.63723 2.64211 + endloop + endfacet + facet normal -0.0897561 0.0544655 0.994473 + outer loop + vertex 0.923311 1.63224 2.6428 + vertex 0.923351 1.63716 2.64254 + vertex 0.918547 1.63234 2.64237 + endloop + endfacet + facet normal -0.0899379 0.047692 0.994805 + outer loop + vertex 0.918362 1.62732 2.64259 + vertex 0.923311 1.63224 2.6428 + vertex 0.918547 1.63234 2.64237 + endloop + endfacet + facet normal -0.0922302 0.0513366 0.994413 + outer loop + vertex 0.918398 1.61225 2.64336 + vertex 0.923401 1.61737 2.64356 + vertex 0.918394 1.61725 2.64311 + endloop + endfacet + facet normal -0.0904948 0.049539 0.994664 + outer loop + vertex 0.918373 1.60724 2.64361 + vertex 0.923402 1.61238 2.64381 + vertex 0.918398 1.61225 2.64336 + endloop + endfacet + facet normal -0.0875568 0.0466496 0.995067 + outer loop + vertex 0.923395 1.60738 2.64405 + vertex 0.923402 1.61238 2.64381 + vertex 0.918373 1.60724 2.64361 + endloop + endfacet + facet normal -0.0874935 0.0439997 0.995193 + outer loop + vertex 0.918361 1.60223 2.64383 + vertex 0.923395 1.60738 2.64405 + vertex 0.918373 1.60724 2.64361 + endloop + endfacet + facet normal -0.0866308 0.0431503 0.995306 + outer loop + vertex 0.923393 1.60238 2.64426 + vertex 0.923395 1.60738 2.64405 + vertex 0.918361 1.60223 2.64383 + endloop + endfacet + facet normal -0.0865881 0.0414358 0.995382 + outer loop + vertex 0.918352 1.59724 2.64404 + vertex 0.923393 1.60238 2.64426 + vertex 0.918361 1.60223 2.64383 + endloop + endfacet + facet normal -0.0862272 0.0410798 0.995428 + outer loop + vertex 0.923403 1.59738 2.64447 + vertex 0.923393 1.60238 2.64426 + vertex 0.918352 1.59724 2.64404 + endloop + endfacet + facet normal -0.0861875 0.0394971 0.995496 + outer loop + vertex 0.918354 1.59224 2.64424 + vertex 0.923403 1.59738 2.64447 + vertex 0.918352 1.59724 2.64404 + endloop + endfacet + facet normal -0.0854955 0.0388135 0.995582 + outer loop + vertex 0.923429 1.59239 2.64467 + vertex 0.923403 1.59738 2.64447 + vertex 0.918354 1.59224 2.64424 + endloop + endfacet + facet normal -0.0854534 0.0371408 0.99565 + outer loop + vertex 0.918366 1.58725 2.64442 + vertex 0.923429 1.59239 2.64467 + vertex 0.918354 1.59224 2.64424 + endloop + endfacet + facet normal -0.085589 0.0372752 0.995633 + outer loop + vertex 0.923449 1.5874 2.64486 + vertex 0.923429 1.59239 2.64467 + vertex 0.918366 1.58725 2.64442 + endloop + endfacet + facet normal -0.0855025 0.0339863 0.995758 + outer loop + vertex 0.918363 1.58227 2.64459 + vertex 0.923449 1.5874 2.64486 + vertex 0.918366 1.58725 2.64442 + endloop + endfacet + facet normal -0.0875343 0.0360121 0.99551 + outer loop + vertex 0.923414 1.58242 2.64503 + vertex 0.923449 1.5874 2.64486 + vertex 0.918363 1.58227 2.64459 + endloop + endfacet + facet normal -0.0874836 0.0341122 0.995582 + outer loop + vertex 0.9183 1.5773 2.64476 + vertex 0.923414 1.58242 2.64503 + vertex 0.918363 1.58227 2.64459 + endloop + endfacet + facet normal -0.0874322 0.0340606 0.995588 + outer loop + vertex 0.923313 1.57743 2.6452 + vertex 0.923414 1.58242 2.64503 + vertex 0.9183 1.5773 2.64476 + endloop + endfacet + facet normal -0.0873588 0.0310698 0.995692 + outer loop + vertex 0.918223 1.57232 2.64491 + vertex 0.923313 1.57743 2.6452 + vertex 0.9183 1.5773 2.64476 + endloop + endfacet + facet normal -0.0871535 0.030864 0.995717 + outer loop + vertex 0.923292 1.57239 2.64535 + vertex 0.923313 1.57743 2.6452 + vertex 0.918223 1.57232 2.64491 + endloop + endfacet + facet normal -0.0871258 0.0283951 0.995793 + outer loop + vertex 0.918273 1.56722 2.64506 + vertex 0.923292 1.57239 2.64535 + vertex 0.918223 1.57232 2.64491 + endloop + endfacet + facet normal -0.08499 0.0263067 0.996034 + outer loop + vertex 0.923703 1.56702 2.64553 + vertex 0.923292 1.57239 2.64535 + vertex 0.918273 1.56722 2.64506 + endloop + endfacet + facet normal -0.0847803 0.0315431 0.9959 + outer loop + vertex 0.918496 1.56173 2.64525 + vertex 0.923703 1.56702 2.64553 + vertex 0.918273 1.56722 2.64506 + endloop + endfacet + facet normal -0.110806 0.0573407 0.992186 + outer loop + vertex 0.922658 1.56275 2.64566 + vertex 0.923703 1.56702 2.64553 + vertex 0.918496 1.56173 2.64525 + endloop + endfacet + facet normal -0.106284 0.0383451 0.993596 + outer loop + vertex 0.922658 1.56275 2.64566 + vertex 0.918496 1.56173 2.64525 + vertex 0.921373 1.55906 2.64566 + endloop + endfacet + facet normal -0.054392 0.0202881 0.998314 + outer loop + vertex 0.921373 1.55906 2.64566 + vertex 0.924353 1.56098 2.64578 + vertex 0.922658 1.56275 2.64566 + endloop + endfacet + facet normal -0.0366233 0.0373634 0.99863 + outer loop + vertex 0.926094 1.56399 2.64574 + vertex 0.922658 1.56275 2.64566 + vertex 0.924353 1.56098 2.64578 + endloop + endfacet + facet normal -0.0504042 0.0140919 0.998629 + outer loop + vertex 0.924446 1.55758 2.64584 + vertex 0.924353 1.56098 2.64578 + vertex 0.921373 1.55906 2.64566 + endloop + endfacet + facet normal -0.0502633 0.0143848 0.998632 + outer loop + vertex 0.921108 1.55441 2.64572 + vertex 0.924446 1.55758 2.64584 + vertex 0.921373 1.55906 2.64566 + endloop + endfacet + facet normal -0.112211 0.0178581 0.993524 + outer loop + vertex 0.921373 1.55906 2.64566 + vertex 0.917466 1.5559 2.64528 + vertex 0.921108 1.55441 2.64572 + endloop + endfacet + facet normal -0.0480372 0.0120368 0.998773 + outer loop + vertex 0.92466 1.55321 2.6459 + vertex 0.924446 1.55758 2.64584 + vertex 0.921108 1.55441 2.64572 + endloop + endfacet + facet normal -0.0476415 0.0132136 0.998777 + outer loop + vertex 0.921076 1.54948 2.64578 + vertex 0.92466 1.55321 2.6459 + vertex 0.921108 1.55441 2.64572 + endloop + endfacet + facet normal -0.109683 0.0135481 0.993874 + outer loop + vertex 0.921108 1.55441 2.64572 + vertex 0.917246 1.55071 2.64534 + vertex 0.921076 1.54948 2.64578 + endloop + endfacet + facet normal -0.0450402 0.0107096 0.998928 + outer loop + vertex 0.924846 1.54845 2.64596 + vertex 0.92466 1.55321 2.6459 + vertex 0.921076 1.54948 2.64578 + endloop + endfacet + facet normal -0.0440559 0.0143263 0.998926 + outer loop + vertex 0.920867 1.5445 2.64584 + vertex 0.924846 1.54845 2.64596 + vertex 0.921076 1.54948 2.64578 + endloop + endfacet + facet normal -0.110244 0.0170445 0.993758 + outer loop + vertex 0.921076 1.54948 2.64578 + vertex 0.917092 1.54563 2.6454 + vertex 0.920867 1.5445 2.64584 + endloop + endfacet + facet normal -0.0431499 0.0134138 0.998979 + outer loop + vertex 0.924567 1.54335 2.64602 + vertex 0.924846 1.54845 2.64596 + vertex 0.920867 1.5445 2.64584 + endloop + endfacet + facet normal -0.0429784 0.0139661 0.998978 + outer loop + vertex 0.920347 1.53964 2.64589 + vertex 0.924567 1.54335 2.64602 + vertex 0.920867 1.5445 2.64584 + endloop + endfacet + facet normal -0.111734 0.0212768 0.99351 + outer loop + vertex 0.920867 1.5445 2.64584 + vertex 0.916862 1.54072 2.64547 + vertex 0.920347 1.53964 2.64589 + endloop + endfacet + facet normal -0.110879 0.0240494 0.993543 + outer loop + vertex 0.916862 1.54072 2.64547 + vertex 0.916708 1.53623 2.64556 + vertex 0.920347 1.53964 2.64589 + endloop + endfacet + facet normal -0.116753 0.0303976 0.992696 + outer loop + vertex 0.920347 1.53964 2.64589 + vertex 0.916708 1.53623 2.64556 + vertex 0.919516 1.53576 2.64591 + endloop + endfacet + facet normal -0.0438731 0.0148119 0.998927 + outer loop + vertex 0.919516 1.53576 2.64591 + vertex 0.923606 1.5376 2.64606 + vertex 0.920347 1.53964 2.64589 + endloop + endfacet + facet normal -0.0424176 0.0115663 0.999033 + outer loop + vertex 0.919516 1.53576 2.64591 + vertex 0.920025 1.53258 2.64597 + vertex 0.923606 1.5376 2.64606 + endloop + endfacet + facet normal -0.0403369 0.0100798 0.999135 + outer loop + vertex 0.920025 1.53258 2.64597 + vertex 0.92398 1.53248 2.64613 + vertex 0.923606 1.5376 2.64606 + endloop + endfacet + facet normal -0.0404566 0.0055566 0.999166 + outer loop + vertex 0.919974 1.52806 2.64599 + vertex 0.92398 1.53248 2.64613 + vertex 0.920025 1.53258 2.64597 + endloop + endfacet + facet normal -0.0448047 0.00950022 0.998951 + outer loop + vertex 0.923974 1.52751 2.64617 + vertex 0.92398 1.53248 2.64613 + vertex 0.919974 1.52806 2.64599 + endloop + endfacet + facet normal -0.0451735 0.00678879 0.998956 + outer loop + vertex 0.919906 1.52314 2.64602 + vertex 0.923974 1.52751 2.64617 + vertex 0.919974 1.52806 2.64599 + endloop + endfacet + facet normal -0.0469558 0.00845133 0.998861 + outer loop + vertex 0.923922 1.52249 2.64621 + vertex 0.923974 1.52751 2.64617 + vertex 0.919906 1.52314 2.64602 + endloop + endfacet + facet normal -0.0473122 0.00625027 0.998861 + outer loop + vertex 0.919906 1.51815 2.64605 + vertex 0.923922 1.52249 2.64621 + vertex 0.919906 1.52314 2.64602 + endloop + endfacet + facet normal -0.0466916 0.00567494 0.998893 + outer loop + vertex 0.923909 1.51747 2.64624 + vertex 0.923922 1.52249 2.64621 + vertex 0.919906 1.51815 2.64605 + endloop + endfacet + facet normal -0.047077 0.00340059 0.998885 + outer loop + vertex 0.91994 1.51316 2.64607 + vertex 0.923909 1.51747 2.64624 + vertex 0.919906 1.51815 2.64605 + endloop + endfacet + facet normal -0.0472433 0.00355411 0.998877 + outer loop + vertex 0.923905 1.51247 2.64626 + vertex 0.923909 1.51747 2.64624 + vertex 0.91994 1.51316 2.64607 + endloop + endfacet + facet normal -0.0477422 0.00070451 0.998859 + outer loop + vertex 0.919946 1.50817 2.64607 + vertex 0.923905 1.51247 2.64626 + vertex 0.91994 1.51316 2.64607 + endloop + endfacet + facet normal -0.048251 0.00117481 0.998835 + outer loop + vertex 0.923882 1.50747 2.64626 + vertex 0.923905 1.51247 2.64626 + vertex 0.919946 1.50817 2.64607 + endloop + endfacet + facet normal -0.0490163 -0.00310353 0.998793 + outer loop + vertex 0.919917 1.50318 2.64606 + vertex 0.923882 1.50747 2.64626 + vertex 0.919946 1.50817 2.64607 + endloop + endfacet + facet normal -0.0507871 -0.00146136 0.998708 + outer loop + vertex 0.923848 1.50245 2.64626 + vertex 0.923882 1.50747 2.64626 + vertex 0.919917 1.50318 2.64606 + endloop + endfacet + facet normal -0.0512876 -0.00417749 0.998675 + outer loop + vertex 0.919939 1.49818 2.64604 + vertex 0.923848 1.50245 2.64626 + vertex 0.919917 1.50318 2.64606 + endloop + endfacet + facet normal -0.114338 -0.00443761 0.993432 + outer loop + vertex 0.919939 1.49818 2.64604 + vertex 0.919917 1.50318 2.64606 + vertex 0.916224 1.49932 2.64561 + endloop + endfacet + facet normal -0.114613 -0.00534532 0.993396 + outer loop + vertex 0.916376 1.49438 2.6456 + vertex 0.919939 1.49818 2.64604 + vertex 0.916224 1.49932 2.64561 + endloop + endfacet + facet normal -0.206559 -0.00814294 0.9784 + outer loop + vertex 0.916224 1.49932 2.64561 + vertex 0.912625 1.49566 2.64482 + vertex 0.916376 1.49438 2.6456 + endloop + endfacet + facet normal -0.207619 -0.0070529 0.978184 + outer loop + vertex 0.912525 1.50055 2.64484 + vertex 0.912625 1.49566 2.64482 + vertex 0.916224 1.49932 2.64561 + endloop + endfacet + facet normal -0.206686 -0.00412449 0.978399 + outer loop + vertex 0.916233 1.50429 2.64564 + vertex 0.912525 1.50055 2.64484 + vertex 0.916224 1.49932 2.64561 + endloop + endfacet + facet normal -0.112026 -0.00780761 0.993675 + outer loop + vertex 0.92018 1.49315 2.64602 + vertex 0.919939 1.49818 2.64604 + vertex 0.916376 1.49438 2.6456 + endloop + endfacet + facet normal -0.111933 -0.0075186 0.993687 + outer loop + vertex 0.916787 1.48949 2.64561 + vertex 0.92018 1.49315 2.64602 + vertex 0.916376 1.49438 2.6456 + endloop + endfacet + facet normal -0.196421 -0.0146429 0.98041 + outer loop + vertex 0.916376 1.49438 2.6456 + vertex 0.912972 1.49086 2.64487 + vertex 0.916787 1.48949 2.64561 + endloop + endfacet + facet normal -0.1971 -0.0166152 0.980243 + outer loop + vertex 0.912972 1.49086 2.64487 + vertex 0.913366 1.48561 2.64486 + vertex 0.916787 1.48949 2.64561 + endloop + endfacet + facet normal -0.200141 -0.0138235 0.97967 + outer loop + vertex 0.917353 1.48542 2.64567 + vertex 0.916787 1.48949 2.64561 + vertex 0.913366 1.48561 2.64486 + endloop + endfacet + facet normal -0.199752 -0.00498151 0.979834 + outer loop + vertex 0.917353 1.48542 2.64567 + vertex 0.913366 1.48561 2.64486 + vertex 0.916108 1.48106 2.6454 + endloop + endfacet + facet normal -0.129031 -0.0259125 0.991302 + outer loop + vertex 0.916108 1.48106 2.6454 + vertex 0.919645 1.48335 2.64592 + vertex 0.917353 1.48542 2.64567 + endloop + endfacet + facet normal -0.104671 0.00153045 0.994506 + outer loop + vertex 0.919645 1.48335 2.64592 + vertex 0.920841 1.48786 2.64604 + vertex 0.917353 1.48542 2.64567 + endloop + endfacet + facet normal -0.0544355 -0.0119079 0.998446 + outer loop + vertex 0.919645 1.48335 2.64592 + vertex 0.923716 1.48373 2.64614 + vertex 0.920841 1.48786 2.64604 + endloop + endfacet + facet normal -0.0433593 -0.00417605 0.999051 + outer loop + vertex 0.923716 1.48373 2.64614 + vertex 0.924922 1.48861 2.64622 + vertex 0.920841 1.48786 2.64604 + endloop + endfacet + facet normal -0.0425743 -0.00844653 0.999058 + outer loop + vertex 0.924922 1.48861 2.64622 + vertex 0.924208 1.49257 2.64622 + vertex 0.920841 1.48786 2.64604 + endloop + endfacet + facet normal -0.0489105 -0.00391134 0.998796 + outer loop + vertex 0.920841 1.48786 2.64604 + vertex 0.924208 1.49257 2.64622 + vertex 0.92018 1.49315 2.64602 + endloop + endfacet + facet normal -0.0493515 -0.00700372 0.998757 + outer loop + vertex 0.924208 1.49257 2.64622 + vertex 0.923899 1.49744 2.64624 + vertex 0.92018 1.49315 2.64602 + endloop + endfacet + facet normal -0.0546968 -0.00911668 0.998461 + outer loop + vertex 0.920234 1.4793 2.64591 + vertex 0.923716 1.48373 2.64614 + vertex 0.919645 1.48335 2.64592 + endloop + endfacet + facet normal -0.0552586 -0.00867401 0.998434 + outer loop + vertex 0.924288 1.47826 2.64613 + vertex 0.923716 1.48373 2.64614 + vertex 0.920234 1.4793 2.64591 + endloop + endfacet + facet normal -0.054583 -0.00603672 0.998491 + outer loop + vertex 0.92065 1.47431 2.6459 + vertex 0.924288 1.47826 2.64613 + vertex 0.920234 1.4793 2.64591 + endloop + endfacet + facet normal -0.12379 -0.0118042 0.992238 + outer loop + vertex 0.920234 1.4793 2.64591 + vertex 0.916799 1.47572 2.64544 + vertex 0.92065 1.47431 2.6459 + endloop + endfacet + facet normal -0.124265 -0.0131303 0.992162 + outer loop + vertex 0.916799 1.47572 2.64544 + vertex 0.917063 1.47068 2.64541 + vertex 0.92065 1.47431 2.6459 + endloop + endfacet + facet normal -0.125486 -0.0119073 0.992024 + outer loop + vertex 0.92065 1.47431 2.6459 + vertex 0.917063 1.47068 2.64541 + vertex 0.920776 1.46929 2.64586 + endloop + endfacet + facet normal -0.0553294 -0.0101999 0.998416 + outer loop + vertex 0.920776 1.46929 2.64586 + vertex 0.924483 1.47315 2.64611 + vertex 0.92065 1.47431 2.6459 + endloop + endfacet + facet normal -0.0563628 -0.00920502 0.998368 + outer loop + vertex 0.92451 1.46809 2.64606 + vertex 0.924483 1.47315 2.64611 + vertex 0.920776 1.46929 2.64586 + endloop + endfacet + facet normal -0.0577101 -0.0134375 0.998243 + outer loop + vertex 0.920832 1.46425 2.6458 + vertex 0.92451 1.46809 2.64606 + vertex 0.920776 1.46929 2.64586 + endloop + endfacet + facet normal -0.126731 -0.0141148 0.991837 + outer loop + vertex 0.920776 1.46929 2.64586 + vertex 0.917112 1.46565 2.64534 + vertex 0.920832 1.46425 2.6458 + endloop + endfacet + facet normal -0.12873 -0.0195582 0.991487 + outer loop + vertex 0.917112 1.46565 2.64534 + vertex 0.91721 1.46063 2.64525 + vertex 0.920832 1.46425 2.6458 + endloop + endfacet + facet normal -0.126679 -0.0216404 0.991708 + outer loop + vertex 0.920832 1.46425 2.6458 + vertex 0.91721 1.46063 2.64525 + vertex 0.921132 1.45931 2.64573 + endloop + endfacet + facet normal -0.0574413 -0.017521 0.998195 + outer loop + vertex 0.921132 1.45931 2.64573 + vertex 0.924655 1.46308 2.646 + vertex 0.920832 1.46425 2.6458 + endloop + endfacet + facet normal -0.0536223 -0.0211002 0.998338 + outer loop + vertex 0.925184 1.45832 2.64592 + vertex 0.924655 1.46308 2.646 + vertex 0.921132 1.45931 2.64573 + endloop + endfacet + facet normal -0.0538161 -0.0218982 0.998311 + outer loop + vertex 0.9219 1.45472 2.64567 + vertex 0.925184 1.45832 2.64592 + vertex 0.921132 1.45931 2.64573 + endloop + endfacet + facet normal -0.120671 -0.0329933 0.992144 + outer loop + vertex 0.921132 1.45931 2.64573 + vertex 0.917603 1.45566 2.64518 + vertex 0.9219 1.45472 2.64567 + endloop + endfacet + facet normal -0.1197 -0.0284044 0.992404 + outer loop + vertex 0.917603 1.45566 2.64518 + vertex 0.918512 1.45051 2.64514 + vertex 0.9219 1.45472 2.64567 + endloop + endfacet + facet normal -0.103221 -0.0418384 0.993778 + outer loop + vertex 0.92319 1.45126 2.64566 + vertex 0.9219 1.45472 2.64567 + vertex 0.918512 1.45051 2.64514 + endloop + endfacet + facet normal -0.104914 -0.0314005 0.993985 + outer loop + vertex 0.92319 1.45126 2.64566 + vertex 0.918512 1.45051 2.64514 + vertex 0.922278 1.44708 2.64543 + endloop + endfacet + facet normal -0.108358 -0.035227 0.993488 + outer loop + vertex 0.922278 1.44708 2.64543 + vertex 0.918512 1.45051 2.64514 + vertex 0.917249 1.4459 2.64484 + endloop + endfacet + facet normal -0.110465 -0.0262667 0.993533 + outer loop + vertex 0.918126 1.44222 2.64484 + vertex 0.922278 1.44708 2.64543 + vertex 0.917249 1.4459 2.64484 + endloop + endfacet + facet normal -0.189914 -0.0451585 0.980762 + outer loop + vertex 0.918126 1.44222 2.64484 + vertex 0.917249 1.4459 2.64484 + vertex 0.913586 1.44236 2.64396 + endloop + endfacet + facet normal -0.18954 -0.0284405 0.981461 + outer loop + vertex 0.913764 1.43764 2.64386 + vertex 0.918126 1.44222 2.64484 + vertex 0.913586 1.44236 2.64396 + endloop + endfacet + facet normal -0.183376 -0.0345171 0.982437 + outer loop + vertex 0.918468 1.43756 2.64474 + vertex 0.918126 1.44222 2.64484 + vertex 0.913764 1.43764 2.64386 + endloop + endfacet + facet normal -0.183351 -0.0317359 0.982535 + outer loop + vertex 0.913807 1.43266 2.64371 + vertex 0.918468 1.43756 2.64474 + vertex 0.913764 1.43764 2.64386 + endloop + endfacet + facet normal -0.185279 -0.0298387 0.982233 + outer loop + vertex 0.91846 1.43261 2.64458 + vertex 0.918468 1.43756 2.64474 + vertex 0.913807 1.43266 2.64371 + endloop + endfacet + facet normal -0.185297 -0.03296 0.98213 + outer loop + vertex 0.913738 1.42759 2.64353 + vertex 0.91846 1.43261 2.64458 + vertex 0.913807 1.43266 2.64371 + endloop + endfacet + facet normal -0.184355 -0.0338777 0.982276 + outer loop + vertex 0.918337 1.42754 2.64439 + vertex 0.91846 1.43261 2.64458 + vertex 0.913738 1.42759 2.64353 + endloop + endfacet + facet normal -0.184383 -0.0400058 0.98204 + outer loop + vertex 0.913689 1.42252 2.64331 + vertex 0.918337 1.42754 2.64439 + vertex 0.913738 1.42759 2.64353 + endloop + endfacet + facet normal -0.182619 -0.0416979 0.982299 + outer loop + vertex 0.918275 1.42247 2.64416 + vertex 0.918337 1.42754 2.64439 + vertex 0.913689 1.42252 2.64331 + endloop + endfacet + facet normal -0.18262 -0.0420719 0.982283 + outer loop + vertex 0.913749 1.4175 2.64311 + vertex 0.918275 1.42247 2.64416 + vertex 0.913689 1.42252 2.64331 + endloop + endfacet + facet normal -0.179533 -0.0449768 0.982723 + outer loop + vertex 0.918337 1.41746 2.64394 + vertex 0.918275 1.42247 2.64416 + vertex 0.913749 1.4175 2.64311 + endloop + endfacet + facet normal -0.179537 -0.0414279 0.982878 + outer loop + vertex 0.914053 1.41263 2.64296 + vertex 0.918337 1.41746 2.64394 + vertex 0.913749 1.4175 2.64311 + endloop + endfacet + facet normal -0.177891 -0.0429344 0.983113 + outer loop + vertex 0.918497 1.41264 2.64376 + vertex 0.918337 1.41746 2.64394 + vertex 0.914053 1.41263 2.64296 + endloop + endfacet + facet normal -0.178003 -0.0316221 0.983522 + outer loop + vertex 0.91474 1.40867 2.64295 + vertex 0.918497 1.41264 2.64376 + vertex 0.914053 1.41263 2.64296 + endloop + endfacet + facet normal -0.161848 -0.0473183 0.985681 + outer loop + vertex 0.918436 1.4078 2.64352 + vertex 0.918497 1.41264 2.64376 + vertex 0.91474 1.40867 2.64295 + endloop + endfacet + facet normal -0.167548 -0.0734404 0.983125 + outer loop + vertex 0.913455 1.40369 2.64236 + vertex 0.918436 1.4078 2.64352 + vertex 0.91474 1.40867 2.64295 + endloop + endfacet + facet normal -0.190639 -0.0447785 0.980638 + outer loop + vertex 0.918375 1.4027 2.64327 + vertex 0.918436 1.4078 2.64352 + vertex 0.913455 1.40369 2.64236 + endloop + endfacet + facet normal -0.190058 -0.041665 0.980888 + outer loop + vertex 0.914084 1.39825 2.64225 + vertex 0.918375 1.4027 2.64327 + vertex 0.913455 1.40369 2.64236 + endloop + endfacet + facet normal -0.189749 -0.0419737 0.980935 + outer loop + vertex 0.918571 1.39756 2.64309 + vertex 0.918375 1.4027 2.64327 + vertex 0.914084 1.39825 2.64225 + endloop + endfacet + facet normal -0.190377 -0.0464852 0.98061 + outer loop + vertex 0.914404 1.39316 2.64207 + vertex 0.918571 1.39756 2.64309 + vertex 0.914084 1.39825 2.64225 + endloop + endfacet + facet normal -0.19147 -0.045413 0.980447 + outer loop + vertex 0.918684 1.39251 2.64288 + vertex 0.918571 1.39756 2.64309 + vertex 0.914404 1.39316 2.64207 + endloop + endfacet + facet normal -0.191989 -0.0491902 0.980164 + outer loop + vertex 0.914585 1.3881 2.64186 + vertex 0.918684 1.39251 2.64288 + vertex 0.914404 1.39316 2.64207 + endloop + endfacet + facet normal -0.188568 -0.0524847 0.980657 + outer loop + vertex 0.918734 1.38752 2.64262 + vertex 0.918684 1.39251 2.64288 + vertex 0.914585 1.3881 2.64186 + endloop + endfacet + facet normal -0.188762 -0.0540312 0.980535 + outer loop + vertex 0.91478 1.38313 2.64162 + vertex 0.918734 1.38752 2.64262 + vertex 0.914585 1.3881 2.64186 + endloop + endfacet + facet normal -0.18526 -0.0572961 0.981018 + outer loop + vertex 0.91884 1.38259 2.64235 + vertex 0.918734 1.38752 2.64262 + vertex 0.91478 1.38313 2.64162 + endloop + endfacet + facet normal -0.185165 -0.0564969 0.981082 + outer loop + vertex 0.915144 1.37822 2.64141 + vertex 0.91884 1.38259 2.64235 + vertex 0.91478 1.38313 2.64162 + endloop + endfacet + facet normal -0.179156 -0.0617583 0.98188 + outer loop + vertex 0.919189 1.37781 2.64212 + vertex 0.91884 1.38259 2.64235 + vertex 0.915144 1.37822 2.64141 + endloop + endfacet + facet normal -0.17864 -0.0559898 0.98232 + outer loop + vertex 0.915928 1.37305 2.64125 + vertex 0.919189 1.37781 2.64212 + vertex 0.915144 1.37822 2.64141 + endloop + endfacet + facet normal -0.164513 -0.0660165 0.984163 + outer loop + vertex 0.919982 1.37388 2.64199 + vertex 0.919189 1.37781 2.64212 + vertex 0.915928 1.37305 2.64125 + endloop + endfacet + facet normal -0.165577 -0.0609446 0.984312 + outer loop + vertex 0.919042 1.36895 2.64152 + vertex 0.919982 1.37388 2.64199 + vertex 0.915928 1.37305 2.64125 + endloop + endfacet + facet normal -0.0875636 -0.0766483 0.993206 + outer loop + vertex 0.919042 1.36895 2.64152 + vertex 0.923607 1.37293 2.64223 + vertex 0.919982 1.37388 2.64199 + endloop + endfacet + facet normal -0.0831433 -0.0594732 0.994761 + outer loop + vertex 0.923607 1.37293 2.64223 + vertex 0.923552 1.37775 2.64252 + vertex 0.919982 1.37388 2.64199 + endloop + endfacet + facet normal -0.0916117 -0.0516214 0.994456 + outer loop + vertex 0.919982 1.37388 2.64199 + vertex 0.923552 1.37775 2.64252 + vertex 0.919189 1.37781 2.64212 + endloop + endfacet + facet normal -0.0916661 -0.0590083 0.99404 + outer loop + vertex 0.923552 1.37775 2.64252 + vertex 0.92337 1.38254 2.64278 + vertex 0.919189 1.37781 2.64212 + endloop + endfacet + facet normal -0.0948315 -0.0561948 0.993906 + outer loop + vertex 0.919189 1.37781 2.64212 + vertex 0.92337 1.38254 2.64278 + vertex 0.91884 1.38259 2.64235 + endloop + endfacet + facet normal -0.0948403 -0.0581251 0.993794 + outer loop + vertex 0.92337 1.38254 2.64278 + vertex 0.923336 1.38749 2.64307 + vertex 0.91884 1.38259 2.64235 + endloop + endfacet + facet normal -0.0970409 -0.0560934 0.993698 + outer loop + vertex 0.91884 1.38259 2.64235 + vertex 0.923336 1.38749 2.64307 + vertex 0.918734 1.38752 2.64262 + endloop + endfacet + facet normal -0.0970407 -0.0552894 0.993744 + outer loop + vertex 0.923336 1.38749 2.64307 + vertex 0.923374 1.39248 2.64335 + vertex 0.918734 1.38752 2.64262 + endloop + endfacet + facet normal -0.100248 -0.0522669 0.993589 + outer loop + vertex 0.918734 1.38752 2.64262 + vertex 0.923374 1.39248 2.64335 + vertex 0.918684 1.39251 2.64288 + endloop + endfacet + facet normal -0.100242 -0.0479899 0.993805 + outer loop + vertex 0.923374 1.39248 2.64335 + vertex 0.923394 1.39748 2.6436 + vertex 0.918684 1.39251 2.64288 + endloop + endfacet + facet normal -0.104399 -0.0440175 0.993561 + outer loop + vertex 0.918684 1.39251 2.64288 + vertex 0.923394 1.39748 2.6436 + vertex 0.918571 1.39756 2.64309 + endloop + endfacet + facet normal -0.104388 -0.0430939 0.993603 + outer loop + vertex 0.923394 1.39748 2.6436 + vertex 0.923348 1.40251 2.64381 + vertex 0.918571 1.39756 2.64309 + endloop + endfacet + facet normal -0.108272 -0.0393049 0.993344 + outer loop + vertex 0.918571 1.39756 2.64309 + vertex 0.923348 1.40251 2.64381 + vertex 0.918375 1.4027 2.64327 + endloop + endfacet + facet normal -0.108315 -0.0405711 0.993288 + outer loop + vertex 0.923348 1.40251 2.64381 + vertex 0.923316 1.40757 2.64401 + vertex 0.918375 1.4027 2.64327 + endloop + endfacet + facet normal -0.102575 -0.0464503 0.99364 + outer loop + vertex 0.918375 1.4027 2.64327 + vertex 0.923316 1.40757 2.64401 + vertex 0.918436 1.4078 2.64352 + endloop + endfacet + facet normal -0.102436 -0.0432323 0.9938 + outer loop + vertex 0.923316 1.40757 2.64401 + vertex 0.923321 1.41259 2.64423 + vertex 0.918436 1.4078 2.64352 + endloop + endfacet + facet normal -0.0982365 -0.044477 0.994169 + outer loop + vertex 0.918337 1.41746 2.64394 + vertex 0.923276 1.4226 2.64466 + vertex 0.918275 1.42247 2.64416 + endloop + endfacet + facet normal -0.0983009 -0.0423345 0.994256 + outer loop + vertex 0.923276 1.4226 2.64466 + vertex 0.923318 1.42765 2.64488 + vertex 0.918275 1.42247 2.64416 + endloop + endfacet + facet normal -0.0994412 -0.0433077 0.994101 + outer loop + vertex 0.923303 1.41758 2.64444 + vertex 0.923276 1.4226 2.64466 + vertex 0.918337 1.41746 2.64394 + endloop + endfacet + facet normal -0.0995119 -0.0407389 0.994202 + outer loop + vertex 0.918497 1.41264 2.64376 + vertex 0.923303 1.41758 2.64444 + vertex 0.918337 1.41746 2.64394 + endloop + endfacet + facet normal -0.0972194 -0.0429885 0.994334 + outer loop + vertex 0.923321 1.41259 2.64423 + vertex 0.923303 1.41758 2.64444 + vertex 0.918497 1.41264 2.64376 + endloop + endfacet + facet normal -0.0972532 -0.0485596 0.994074 + outer loop + vertex 0.918436 1.4078 2.64352 + vertex 0.923321 1.41259 2.64423 + vertex 0.918497 1.41264 2.64376 + endloop + endfacet + facet normal -0.0973379 -0.0432778 0.99431 + outer loop + vertex 0.918275 1.42247 2.64416 + vertex 0.923318 1.42765 2.64488 + vertex 0.918337 1.42754 2.64439 + endloop + endfacet + facet normal -0.0975296 -0.0363563 0.994568 + outer loop + vertex 0.923318 1.42765 2.64488 + vertex 0.923443 1.43271 2.64508 + vertex 0.918337 1.42754 2.64439 + endloop + endfacet + facet normal -0.0974318 -0.0364536 0.994574 + outer loop + vertex 0.918337 1.42754 2.64439 + vertex 0.923443 1.43271 2.64508 + vertex 0.91846 1.43261 2.64458 + endloop + endfacet + facet normal -0.0975703 -0.0307869 0.994752 + outer loop + vertex 0.923443 1.43271 2.64508 + vertex 0.923529 1.43767 2.64524 + vertex 0.91846 1.43261 2.64458 + endloop + endfacet + facet normal -0.0979862 -0.030367 0.994724 + outer loop + vertex 0.91846 1.43261 2.64458 + vertex 0.923529 1.43767 2.64524 + vertex 0.918468 1.43756 2.64474 + endloop + endfacet + facet normal -0.0980083 -0.029457 0.99475 + outer loop + vertex 0.923529 1.43767 2.64524 + vertex 0.923262 1.44238 2.64535 + vertex 0.918468 1.43756 2.64474 + endloop + endfacet + facet normal -0.0988942 -0.0285677 0.994688 + outer loop + vertex 0.918468 1.43756 2.64474 + vertex 0.923262 1.44238 2.64535 + vertex 0.918126 1.44222 2.64484 + endloop + endfacet + facet normal -0.0986169 -0.0364906 0.994456 + outer loop + vertex 0.923262 1.44238 2.64535 + vertex 0.922278 1.44708 2.64543 + vertex 0.918126 1.44222 2.64484 + endloop + endfacet + facet normal -0.203948 -0.00806332 0.978949 + outer loop + vertex 0.917249 1.4459 2.64484 + vertex 0.918512 1.45051 2.64514 + vertex 0.913625 1.44701 2.64409 + endloop + endfacet + facet normal -0.208804 -0.0248913 0.977641 + outer loop + vertex 0.913586 1.44236 2.64396 + vertex 0.917249 1.4459 2.64484 + vertex 0.913625 1.44701 2.64409 + endloop + endfacet + facet normal -0.0473461 -0.0210231 0.998657 + outer loop + vertex 0.92319 1.45126 2.64566 + vertex 0.926134 1.45415 2.64586 + vertex 0.9219 1.45472 2.64567 + endloop + endfacet + facet normal -0.0481475 -0.0270775 0.998473 + outer loop + vertex 0.926134 1.45415 2.64586 + vertex 0.925184 1.45832 2.64592 + vertex 0.9219 1.45472 2.64567 + endloop + endfacet + facet normal -0.128033 -0.0257822 0.991435 + outer loop + vertex 0.91721 1.46063 2.64525 + vertex 0.917603 1.45566 2.64518 + vertex 0.921132 1.45931 2.64573 + endloop + endfacet + facet normal -0.209676 -0.0320201 0.977246 + outer loop + vertex 0.917603 1.45566 2.64518 + vertex 0.91721 1.46063 2.64525 + vertex 0.913382 1.4569 2.64431 + endloop + endfacet + facet normal -0.20875 -0.0286704 0.977549 + outer loop + vertex 0.913632 1.4519 2.64422 + vertex 0.917603 1.45566 2.64518 + vertex 0.913382 1.4569 2.64431 + endloop + endfacet + facet normal -0.196702 -0.0419093 0.979567 + outer loop + vertex 0.918512 1.45051 2.64514 + vertex 0.917603 1.45566 2.64518 + vertex 0.913632 1.4519 2.64422 + endloop + endfacet + facet normal -0.192201 -0.0250779 0.981035 + outer loop + vertex 0.913625 1.44701 2.64409 + vertex 0.918512 1.45051 2.64514 + vertex 0.913632 1.4519 2.64422 + endloop + endfacet + facet normal -0.216338 -0.0248568 0.976002 + outer loop + vertex 0.913382 1.4569 2.64431 + vertex 0.91721 1.46063 2.64525 + vertex 0.913279 1.46192 2.64442 + endloop + endfacet + facet normal -0.215139 -0.020982 0.976358 + outer loop + vertex 0.91721 1.46063 2.64525 + vertex 0.917112 1.46565 2.64534 + vertex 0.913279 1.46192 2.64442 + endloop + endfacet + facet normal -0.217253 -0.018702 0.975936 + outer loop + vertex 0.913279 1.46192 2.64442 + vertex 0.917112 1.46565 2.64534 + vertex 0.913276 1.46695 2.64451 + endloop + endfacet + facet normal -0.216101 -0.015105 0.976254 + outer loop + vertex 0.917112 1.46565 2.64534 + vertex 0.917063 1.47068 2.64541 + vertex 0.913276 1.46695 2.64451 + endloop + endfacet + facet normal -0.215055 -0.0162178 0.976467 + outer loop + vertex 0.913276 1.46695 2.64451 + vertex 0.917063 1.47068 2.64541 + vertex 0.913178 1.47196 2.64457 + endloop + endfacet + facet normal -0.0565425 -0.0145586 0.998294 + outer loop + vertex 0.924655 1.46308 2.646 + vertex 0.92451 1.46809 2.64606 + vertex 0.920832 1.46425 2.6458 + endloop + endfacet + facet normal -0.126415 -0.0144377 0.991872 + outer loop + vertex 0.917063 1.47068 2.64541 + vertex 0.917112 1.46565 2.64534 + vertex 0.920776 1.46929 2.64586 + endloop + endfacet + facet normal -0.215554 -0.0178132 0.976329 + outer loop + vertex 0.917063 1.47068 2.64541 + vertex 0.916799 1.47572 2.64544 + vertex 0.913178 1.47196 2.64457 + endloop + endfacet + facet normal -0.216842 -0.0165114 0.976067 + outer loop + vertex 0.913178 1.47196 2.64457 + vertex 0.916799 1.47572 2.64544 + vertex 0.912786 1.47688 2.64457 + endloop + endfacet + facet normal -0.217803 -0.0200539 0.975787 + outer loop + vertex 0.916799 1.47572 2.64544 + vertex 0.916108 1.48106 2.6454 + vertex 0.912786 1.47688 2.64457 + endloop + endfacet + facet normal -0.230338 -0.00954532 0.973064 + outer loop + vertex 0.912786 1.47688 2.64457 + vertex 0.916108 1.48106 2.6454 + vertex 0.911965 1.48102 2.64442 + endloop + endfacet + facet normal -0.127463 -0.00821921 0.991809 + outer loop + vertex 0.916108 1.48106 2.6454 + vertex 0.916799 1.47572 2.64544 + vertex 0.920234 1.4793 2.64591 + endloop + endfacet + facet normal -0.0541822 -0.0064078 0.998511 + outer loop + vertex 0.924483 1.47315 2.64611 + vertex 0.924288 1.47826 2.64613 + vertex 0.92065 1.47431 2.6459 + endloop + endfacet + facet normal -0.132553 -0.0204133 0.990966 + outer loop + vertex 0.919645 1.48335 2.64592 + vertex 0.916108 1.48106 2.6454 + vertex 0.920234 1.4793 2.64591 + endloop + endfacet + facet normal -0.230156 -0.0241217 0.972855 + outer loop + vertex 0.916108 1.48106 2.6454 + vertex 0.913366 1.48561 2.64486 + vertex 0.911965 1.48102 2.64442 + endloop + endfacet + facet normal -0.103491 -0.00017257 0.99463 + outer loop + vertex 0.917353 1.48542 2.64567 + vertex 0.920841 1.48786 2.64604 + vertex 0.916787 1.48949 2.64561 + endloop + endfacet + facet normal -0.107899 -0.0112984 0.994098 + outer loop + vertex 0.920841 1.48786 2.64604 + vertex 0.92018 1.49315 2.64602 + vertex 0.916787 1.48949 2.64561 + endloop + endfacet + facet normal -0.051729 -0.004937 0.998649 + outer loop + vertex 0.92018 1.49315 2.64602 + vertex 0.923899 1.49744 2.64624 + vertex 0.919939 1.49818 2.64604 + endloop + endfacet + facet normal -0.114414 -0.00436413 0.993424 + outer loop + vertex 0.916224 1.49932 2.64561 + vertex 0.919917 1.50318 2.64606 + vertex 0.916233 1.50429 2.64564 + endloop + endfacet + facet normal -0.113924 -0.00271045 0.993486 + outer loop + vertex 0.919917 1.50318 2.64606 + vertex 0.919946 1.50817 2.64607 + vertex 0.916233 1.50429 2.64564 + endloop + endfacet + facet normal -0.112149 -0.00442834 0.993682 + outer loop + vertex 0.916233 1.50429 2.64564 + vertex 0.919946 1.50817 2.64607 + vertex 0.916254 1.50927 2.64566 + endloop + endfacet + facet normal -0.206778 -0.0039554 0.97838 + outer loop + vertex 0.916254 1.50927 2.64566 + vertex 0.912545 1.50551 2.64486 + vertex 0.916233 1.50429 2.64564 + endloop + endfacet + facet normal -0.11067 0.000622487 0.993857 + outer loop + vertex 0.919946 1.50817 2.64607 + vertex 0.91994 1.51316 2.64607 + vertex 0.916254 1.50927 2.64566 + endloop + endfacet + facet normal -0.1107 0.0006508 0.993854 + outer loop + vertex 0.916254 1.50927 2.64566 + vertex 0.91994 1.51316 2.64607 + vertex 0.916224 1.51425 2.64565 + endloop + endfacet + facet normal -0.206915 3.85378e-05 0.978359 + outer loop + vertex 0.916224 1.51425 2.64565 + vertex 0.912547 1.51048 2.64488 + vertex 0.916254 1.50927 2.64566 + endloop + endfacet + facet normal -0.110032 0.00295119 0.993924 + outer loop + vertex 0.91994 1.51316 2.64607 + vertex 0.919906 1.51815 2.64605 + vertex 0.916224 1.51425 2.64565 + endloop + endfacet + facet normal -0.110068 0.00298533 0.99392 + outer loop + vertex 0.916224 1.51425 2.64565 + vertex 0.919906 1.51815 2.64605 + vertex 0.916185 1.51924 2.64564 + endloop + endfacet + facet normal -0.204047 0.00219365 0.978959 + outer loop + vertex 0.916185 1.51924 2.64564 + vertex 0.912508 1.51547 2.64488 + vertex 0.916224 1.51425 2.64565 + endloop + endfacet + facet normal -0.109127 0.00622139 0.994008 + outer loop + vertex 0.919906 1.51815 2.64605 + vertex 0.919906 1.52314 2.64602 + vertex 0.916185 1.51924 2.64564 + endloop + endfacet + facet normal -0.108388 0.00550779 0.994093 + outer loop + vertex 0.916185 1.51924 2.64564 + vertex 0.919906 1.52314 2.64602 + vertex 0.91624 1.52425 2.64561 + endloop + endfacet + facet normal -0.204168 0.00650063 0.978914 + outer loop + vertex 0.91624 1.52425 2.64561 + vertex 0.912502 1.52049 2.64486 + vertex 0.916185 1.51924 2.64564 + endloop + endfacet + facet normal -0.107753 0.00763526 0.994148 + outer loop + vertex 0.919906 1.52314 2.64602 + vertex 0.919974 1.52806 2.64599 + vertex 0.91624 1.52425 2.64561 + endloop + endfacet + facet normal -0.104154 0.00406651 0.994553 + outer loop + vertex 0.91624 1.52425 2.64561 + vertex 0.919974 1.52806 2.64599 + vertex 0.916522 1.52915 2.64562 + endloop + endfacet + facet normal -0.202282 0.00975139 0.979279 + outer loop + vertex 0.916522 1.52915 2.64562 + vertex 0.912686 1.52566 2.64487 + vertex 0.91624 1.52425 2.64561 + endloop + endfacet + facet normal -0.103474 0.00623778 0.994613 + outer loop + vertex 0.919974 1.52806 2.64599 + vertex 0.920025 1.53258 2.64597 + vertex 0.916522 1.52915 2.64562 + endloop + endfacet + facet normal -0.0937915 -0.00373064 0.995585 + outer loop + vertex 0.916522 1.52915 2.64562 + vertex 0.920025 1.53258 2.64597 + vertex 0.917188 1.53303 2.6457 + endloop + endfacet + facet normal -0.199974 0.014779 0.97969 + outer loop + vertex 0.917188 1.53303 2.6457 + vertex 0.913399 1.53142 2.64495 + vertex 0.916522 1.52915 2.64562 + endloop + endfacet + facet normal -0.0926645 0.00346579 0.995691 + outer loop + vertex 0.919516 1.53576 2.64591 + vertex 0.917188 1.53303 2.6457 + vertex 0.920025 1.53258 2.64597 + endloop + endfacet + facet normal -0.117652 0.0249904 0.99274 + outer loop + vertex 0.917188 1.53303 2.6457 + vertex 0.919516 1.53576 2.64591 + vertex 0.916708 1.53623 2.64556 + endloop + endfacet + facet normal -0.0515448 -0.00394182 0.998663 + outer loop + vertex 0.923899 1.49744 2.64624 + vertex 0.923848 1.50245 2.64626 + vertex 0.919939 1.49818 2.64604 + endloop + endfacet + facet normal -0.0438097 0.0149136 0.998929 + outer loop + vertex 0.923606 1.5376 2.64606 + vertex 0.924567 1.54335 2.64602 + vertex 0.920347 1.53964 2.64589 + endloop + endfacet + facet normal -0.0374265 0.0395854 0.998515 + outer loop + vertex 0.922658 1.56275 2.64566 + vertex 0.926094 1.56399 2.64574 + vertex 0.923703 1.56702 2.64553 + endloop + endfacet + facet normal -0.118194 0.025367 0.992666 + outer loop + vertex 0.918496 1.56173 2.64525 + vertex 0.917466 1.5559 2.64528 + vertex 0.921373 1.55906 2.64566 + endloop + endfacet + facet normal -0.112677 0.0167126 0.993491 + outer loop + vertex 0.917466 1.5559 2.64528 + vertex 0.917246 1.55071 2.64534 + vertex 0.921108 1.55441 2.64572 + endloop + endfacet + facet normal -0.108989 0.0157306 0.993918 + outer loop + vertex 0.917246 1.55071 2.64534 + vertex 0.917092 1.54563 2.6454 + vertex 0.921076 1.54948 2.64578 + endloop + endfacet + facet normal -0.10965 0.0190395 0.993788 + outer loop + vertex 0.917092 1.54563 2.6454 + vertex 0.916862 1.54072 2.64547 + vertex 0.920867 1.5445 2.64584 + endloop + endfacet + facet normal -0.198939 0.0122331 0.979936 + outer loop + vertex 0.917188 1.53303 2.6457 + vertex 0.916708 1.53623 2.64556 + vertex 0.913399 1.53142 2.64495 + endloop + endfacet + facet normal -0.202951 0.0105191 0.979132 + outer loop + vertex 0.913399 1.53142 2.64495 + vertex 0.912686 1.52566 2.64487 + vertex 0.916522 1.52915 2.64562 + endloop + endfacet + facet normal -0.203708 0.00602267 0.979013 + outer loop + vertex 0.912686 1.52566 2.64487 + vertex 0.912502 1.52049 2.64486 + vertex 0.91624 1.52425 2.64561 + endloop + endfacet + facet normal -0.205192 0.00335647 0.978716 + outer loop + vertex 0.912502 1.52049 2.64486 + vertex 0.912508 1.51547 2.64488 + vertex 0.916185 1.51924 2.64564 + endloop + endfacet + facet normal -0.205253 -0.00165465 0.978708 + outer loop + vertex 0.912508 1.51547 2.64488 + vertex 0.912547 1.51048 2.64488 + vertex 0.916224 1.51425 2.64565 + endloop + endfacet + facet normal -0.207827 -0.00287399 0.978161 + outer loop + vertex 0.912547 1.51048 2.64488 + vertex 0.912545 1.50551 2.64486 + vertex 0.916254 1.50927 2.64566 + endloop + endfacet + facet normal -0.206795 -0.00401098 0.978376 + outer loop + vertex 0.912545 1.50551 2.64486 + vertex 0.912525 1.50055 2.64484 + vertex 0.916233 1.50429 2.64564 + endloop + endfacet + facet normal -0.205649 -0.00534316 0.978611 + outer loop + vertex 0.912625 1.49566 2.64482 + vertex 0.912972 1.49086 2.64487 + vertex 0.916376 1.49438 2.6456 + endloop + endfacet +endsolid diff --git a/noether_examples/meshes/outputsBackDoor/output_5.stl b/noether_examples/meshes/outputsBackDoor/output_5.stl new file mode 100644 index 00000000..36b49b1f --- /dev/null +++ b/noether_examples/meshes/outputsBackDoor/output_5.stl @@ -0,0 +1,15703 @@ +solid ascii + facet normal -0.112863 -0.0397027 0.992817 + outer loop + vertex 0.938137 1.20776 2.62816 + vertex 0.938063 1.21297 2.62836 + vertex 0.933392 1.20794 2.62763 + endloop + endfacet + facet normal -0.0712906 -0.0392616 0.996683 + outer loop + vertex 0.938137 1.20776 2.62816 + vertex 0.943173 1.21292 2.62872 + vertex 0.938063 1.21297 2.62836 + endloop + endfacet + facet normal -0.0421254 -0.0677533 0.996812 + outer loop + vertex 0.94308 1.20775 2.62837 + vertex 0.943173 1.21292 2.62872 + vertex 0.938137 1.20776 2.62816 + endloop + endfacet + facet normal -0.0421089 -0.0780201 0.996062 + outer loop + vertex 0.938483 1.20289 2.62779 + vertex 0.94308 1.20775 2.62837 + vertex 0.938137 1.20776 2.62816 + endloop + endfacet + facet normal -0.0171171 -0.101463 0.994692 + outer loop + vertex 0.943191 1.20273 2.62786 + vertex 0.94308 1.20775 2.62837 + vertex 0.938483 1.20289 2.62779 + endloop + endfacet + facet normal -0.0176867 -0.119772 0.992644 + outer loop + vertex 0.939032 1.19831 2.62725 + vertex 0.943191 1.20273 2.62786 + vertex 0.938483 1.20289 2.62779 + endloop + endfacet + facet normal -0.0109268 -0.126029 0.991966 + outer loop + vertex 0.943597 1.19804 2.62727 + vertex 0.943191 1.20273 2.62786 + vertex 0.939032 1.19831 2.62725 + endloop + endfacet + facet normal -0.0115356 -0.136706 0.990544 + outer loop + vertex 0.940161 1.19465 2.62676 + vertex 0.943597 1.19804 2.62727 + vertex 0.939032 1.19831 2.62725 + endloop + endfacet + facet normal -0.00751504 -0.140695 0.990024 + outer loop + vertex 0.944179 1.19378 2.62667 + vertex 0.943597 1.19804 2.62727 + vertex 0.940161 1.19465 2.62676 + endloop + endfacet + facet normal -0.0108138 -0.155706 0.987744 + outer loop + vertex 0.939833 1.1906 2.62612 + vertex 0.944179 1.19378 2.62667 + vertex 0.940161 1.19465 2.62676 + endloop + endfacet + facet normal -0.0167172 -0.147825 0.988872 + outer loop + vertex 0.945058 1.18988 2.6261 + vertex 0.944179 1.19378 2.62667 + vertex 0.939833 1.1906 2.62612 + endloop + endfacet + facet normal -0.0172433 -0.151626 0.988287 + outer loop + vertex 0.945058 1.18988 2.6261 + vertex 0.939833 1.1906 2.62612 + vertex 0.941458 1.18645 2.62551 + endloop + endfacet + facet normal -0.0152244 -0.153698 0.988001 + outer loop + vertex 0.946308 1.18644 2.62558 + vertex 0.945058 1.18988 2.6261 + vertex 0.941458 1.18645 2.62551 + endloop + endfacet + facet normal -0.0152256 -0.157662 0.987376 + outer loop + vertex 0.941458 1.18645 2.62551 + vertex 0.942553 1.18247 2.62489 + vertex 0.946308 1.18644 2.62558 + endloop + endfacet + facet normal -0.00927359 -0.163154 0.986557 + outer loop + vertex 0.942553 1.18247 2.62489 + vertex 0.948328 1.18317 2.62506 + vertex 0.946308 1.18644 2.62558 + endloop + endfacet + facet normal 0.0109423 -0.150981 0.988476 + outer loop + vertex 0.950231 1.18713 2.62564 + vertex 0.946308 1.18644 2.62558 + vertex 0.948328 1.18317 2.62506 + endloop + endfacet + facet normal 0.0219414 -0.156114 0.987495 + outer loop + vertex 0.950231 1.18713 2.62564 + vertex 0.948328 1.18317 2.62506 + vertex 0.953417 1.18671 2.62551 + endloop + endfacet + facet normal 0.023649 -0.143915 0.989307 + outer loop + vertex 0.953417 1.18671 2.62551 + vertex 0.952931 1.18939 2.62591 + vertex 0.950231 1.18713 2.62564 + endloop + endfacet + facet normal 0.0223643 -0.142407 0.989555 + outer loop + vertex 0.952931 1.18939 2.62591 + vertex 0.949657 1.1898 2.62604 + vertex 0.950231 1.18713 2.62564 + endloop + endfacet + facet normal 0.0228104 -0.139027 0.990026 + outer loop + vertex 0.952931 1.18939 2.62591 + vertex 0.954321 1.19315 2.6264 + vertex 0.949657 1.1898 2.62604 + endloop + endfacet + facet normal 0.022623 -0.13877 0.990066 + outer loop + vertex 0.954321 1.19315 2.6264 + vertex 0.949058 1.19349 2.62657 + vertex 0.949657 1.1898 2.62604 + endloop + endfacet + facet normal 0.00974334 -0.140847 0.989983 + outer loop + vertex 0.949657 1.1898 2.62604 + vertex 0.949058 1.19349 2.62657 + vertex 0.945058 1.18988 2.6261 + endloop + endfacet + facet normal 0.0227664 -0.136728 0.990347 + outer loop + vertex 0.954321 1.19315 2.6264 + vertex 0.95352 1.19786 2.62707 + vertex 0.949058 1.19349 2.62657 + endloop + endfacet + facet normal 0.0215612 -0.135518 0.99054 + outer loop + vertex 0.949058 1.19349 2.62657 + vertex 0.95352 1.19786 2.62707 + vertex 0.948423 1.19787 2.62719 + endloop + endfacet + facet normal 0.0109099 -0.137059 0.990503 + outer loop + vertex 0.949058 1.19349 2.62657 + vertex 0.948423 1.19787 2.62719 + vertex 0.944179 1.19378 2.62667 + endloop + endfacet + facet normal 0.021631 -0.123567 0.9921 + outer loop + vertex 0.95352 1.19786 2.62707 + vertex 0.953205 1.20275 2.62769 + vertex 0.948423 1.19787 2.62719 + endloop + endfacet + facet normal 0.0238974 -0.125755 0.991773 + outer loop + vertex 0.948423 1.19787 2.62719 + vertex 0.953205 1.20275 2.62769 + vertex 0.948138 1.2027 2.6278 + endloop + endfacet + facet normal 0.0123573 -0.12645 0.991896 + outer loop + vertex 0.948423 1.19787 2.62719 + vertex 0.948138 1.2027 2.6278 + vertex 0.943597 1.19804 2.62727 + endloop + endfacet + facet normal 0.010057 -0.124242 0.992201 + outer loop + vertex 0.943597 1.19804 2.62727 + vertex 0.948138 1.2027 2.6278 + vertex 0.943191 1.20273 2.62786 + endloop + endfacet + facet normal 0.0101895 -0.106987 0.994208 + outer loop + vertex 0.948138 1.2027 2.6278 + vertex 0.948151 1.20781 2.62835 + vertex 0.943191 1.20273 2.62786 + endloop + endfacet + facet normal 0.0245351 -0.106996 0.993957 + outer loop + vertex 0.948138 1.2027 2.6278 + vertex 0.95324 1.20787 2.62824 + vertex 0.948151 1.20781 2.62835 + endloop + endfacet + facet normal 0.0237539 -0.106234 0.994057 + outer loop + vertex 0.953205 1.20275 2.62769 + vertex 0.95324 1.20787 2.62824 + vertex 0.948138 1.2027 2.6278 + endloop + endfacet + facet normal 0.0343858 -0.106274 0.993742 + outer loop + vertex 0.953205 1.20275 2.62769 + vertex 0.958288 1.20792 2.62807 + vertex 0.95324 1.20787 2.62824 + endloop + endfacet + facet normal 0.0290926 -0.101125 0.994448 + outer loop + vertex 0.958295 1.20283 2.62755 + vertex 0.958288 1.20792 2.62807 + vertex 0.953205 1.20275 2.62769 + endloop + endfacet + facet normal 0.0391858 -0.101075 0.994107 + outer loop + vertex 0.958295 1.20283 2.62755 + vertex 0.963272 1.20793 2.62787 + vertex 0.958288 1.20792 2.62807 + endloop + endfacet + facet normal 0.0346485 -0.096683 0.994712 + outer loop + vertex 0.963372 1.20291 2.62738 + vertex 0.963272 1.20793 2.62787 + vertex 0.958295 1.20283 2.62755 + endloop + endfacet + facet normal 0.0349337 -0.120193 0.992136 + outer loop + vertex 0.958788 1.19807 2.62695 + vertex 0.963372 1.20291 2.62738 + vertex 0.958295 1.20283 2.62755 + endloop + endfacet + facet normal 0.0272157 -0.121009 0.992278 + outer loop + vertex 0.958788 1.19807 2.62695 + vertex 0.958295 1.20283 2.62755 + vertex 0.95352 1.19786 2.62707 + endloop + endfacet + facet normal 0.0318235 -0.11729 0.992588 + outer loop + vertex 0.964001 1.19836 2.62682 + vertex 0.963372 1.20291 2.62738 + vertex 0.958788 1.19807 2.62695 + endloop + endfacet + facet normal 0.032689 -0.133917 0.990453 + outer loop + vertex 0.960049 1.19407 2.62637 + vertex 0.964001 1.19836 2.62682 + vertex 0.958788 1.19807 2.62695 + endloop + endfacet + facet normal 0.0274192 -0.13557 0.990388 + outer loop + vertex 0.960049 1.19407 2.62637 + vertex 0.958788 1.19807 2.62695 + vertex 0.954321 1.19315 2.6264 + endloop + endfacet + facet normal 0.0281593 -0.140194 0.989724 + outer loop + vertex 0.960049 1.19407 2.62637 + vertex 0.954321 1.19315 2.6264 + vertex 0.956777 1.19017 2.62591 + endloop + endfacet + facet normal 0.0309824 -0.142517 0.989307 + outer loop + vertex 0.961658 1.19074 2.62584 + vertex 0.960049 1.19407 2.62637 + vertex 0.956777 1.19017 2.62591 + endloop + endfacet + facet normal 0.0308095 -0.140998 0.98953 + outer loop + vertex 0.956777 1.19017 2.62591 + vertex 0.957962 1.18692 2.62541 + vertex 0.961658 1.19074 2.62584 + endloop + endfacet + facet normal 0.0332509 -0.143316 0.989118 + outer loop + vertex 0.957962 1.18692 2.62541 + vertex 0.963 1.18736 2.62531 + vertex 0.961658 1.19074 2.62584 + endloop + endfacet + facet normal 0.0366712 -0.141969 0.989192 + outer loop + vertex 0.961658 1.19074 2.62584 + vertex 0.963 1.18736 2.62531 + vertex 0.966532 1.19131 2.62574 + endloop + endfacet + facet normal 0.0368364 -0.143411 0.988977 + outer loop + vertex 0.966532 1.19131 2.62574 + vertex 0.965139 1.19453 2.62626 + vertex 0.961658 1.19074 2.62584 + endloop + endfacet + facet normal 0.0422893 -0.141067 0.989096 + outer loop + vertex 0.969731 1.19478 2.6261 + vertex 0.965139 1.19453 2.62626 + vertex 0.966532 1.19131 2.62574 + endloop + endfacet + facet normal 0.0437546 -0.142393 0.988843 + outer loop + vertex 0.970379 1.19214 2.62569 + vertex 0.969731 1.19478 2.6261 + vertex 0.966532 1.19131 2.62574 + endloop + endfacet + facet normal 0.0442161 -0.144568 0.988507 + outer loop + vertex 0.970379 1.19214 2.62569 + vertex 0.966532 1.19131 2.62574 + vertex 0.968654 1.18827 2.6252 + endloop + endfacet + facet normal 0.0528626 -0.148304 0.987528 + outer loop + vertex 0.970379 1.19214 2.62569 + vertex 0.968654 1.18827 2.6252 + vertex 0.973461 1.19179 2.62547 + endloop + endfacet + facet normal 0.0533486 -0.144314 0.988093 + outer loop + vertex 0.973461 1.19179 2.62547 + vertex 0.972943 1.19444 2.62589 + vertex 0.970379 1.19214 2.62569 + endloop + endfacet + facet normal 0.0596142 -0.14306 0.987917 + outer loop + vertex 0.972943 1.19444 2.62589 + vertex 0.973461 1.19179 2.62547 + vertex 0.976612 1.19537 2.6258 + endloop + endfacet + facet normal 0.0564721 -0.13057 0.989829 + outer loop + vertex 0.976612 1.19537 2.6258 + vertex 0.974297 1.19825 2.62631 + vertex 0.972943 1.19444 2.62589 + endloop + endfacet + facet normal 0.0515234 -0.128867 0.990322 + outer loop + vertex 0.972943 1.19444 2.62589 + vertex 0.974297 1.19825 2.62631 + vertex 0.969731 1.19478 2.6261 + endloop + endfacet + facet normal 0.0522034 -0.129752 0.990171 + outer loop + vertex 0.974297 1.19825 2.62631 + vertex 0.969076 1.19849 2.62662 + vertex 0.969731 1.19478 2.6261 + endloop + endfacet + facet normal 0.0530544 -0.113557 0.992114 + outer loop + vertex 0.974297 1.19825 2.62631 + vertex 0.97357 1.20295 2.62689 + vertex 0.969076 1.19849 2.62662 + endloop + endfacet + facet normal 0.0531678 -0.11367 0.992095 + outer loop + vertex 0.969076 1.19849 2.62662 + vertex 0.97357 1.20295 2.62689 + vertex 0.968426 1.20294 2.62717 + endloop + endfacet + facet normal 0.0420148 -0.115341 0.992437 + outer loop + vertex 0.969076 1.19849 2.62662 + vertex 0.968426 1.20294 2.62717 + vertex 0.964001 1.19836 2.62682 + endloop + endfacet + facet normal 0.0423686 -0.132161 0.990322 + outer loop + vertex 0.965139 1.19453 2.62626 + vertex 0.969076 1.19849 2.62662 + vertex 0.964001 1.19836 2.62682 + endloop + endfacet + facet normal 0.0532385 -0.0932581 0.994218 + outer loop + vertex 0.97357 1.20295 2.62689 + vertex 0.973246 1.20782 2.62737 + vertex 0.968426 1.20294 2.62717 + endloop + endfacet + facet normal 0.053177 -0.0931978 0.994227 + outer loop + vertex 0.968426 1.20294 2.62717 + vertex 0.973246 1.20782 2.62737 + vertex 0.968229 1.20788 2.62764 + endloop + endfacet + facet normal 0.0424637 -0.0936698 0.994697 + outer loop + vertex 0.968426 1.20294 2.62717 + vertex 0.968229 1.20788 2.62764 + vertex 0.963372 1.20291 2.62738 + endloop + endfacet + facet normal 0.0612122 -0.0926895 0.993812 + outer loop + vertex 0.97357 1.20295 2.62689 + vertex 0.978399 1.20788 2.62705 + vertex 0.973246 1.20782 2.62737 + endloop + endfacet + facet normal 0.0592535 -0.0907794 0.994107 + outer loop + vertex 0.978839 1.20322 2.6266 + vertex 0.978399 1.20788 2.62705 + vertex 0.97357 1.20295 2.62689 + endloop + endfacet + facet normal 0.0647708 -0.0902305 0.993812 + outer loop + vertex 0.978839 1.20322 2.6266 + vertex 0.983593 1.2081 2.62673 + vertex 0.978399 1.20788 2.62705 + endloop + endfacet + facet normal 0.0589287 -0.0845601 0.994674 + outer loop + vertex 0.983965 1.20369 2.62634 + vertex 0.983593 1.2081 2.62673 + vertex 0.978839 1.20322 2.6266 + endloop + endfacet + facet normal 0.0609146 -0.107363 0.992352 + outer loop + vertex 0.979818 1.19938 2.62613 + vertex 0.983965 1.20369 2.62634 + vertex 0.978839 1.20322 2.6266 + endloop + endfacet + facet normal 0.0560443 -0.108622 0.992502 + outer loop + vertex 0.979818 1.19938 2.62613 + vertex 0.978839 1.20322 2.6266 + vertex 0.974297 1.19825 2.62631 + endloop + endfacet + facet normal 0.0551551 -0.101877 0.993267 + outer loop + vertex 0.984362 1.20008 2.62595 + vertex 0.983965 1.20369 2.62634 + vertex 0.979818 1.19938 2.62613 + endloop + endfacet + facet normal 0.0574987 -0.101608 0.993161 + outer loop + vertex 0.988752 1.20387 2.62608 + vertex 0.983965 1.20369 2.62634 + vertex 0.984362 1.20008 2.62595 + endloop + endfacet + facet normal 0.0547098 -0.0983921 0.993643 + outer loop + vertex 0.987549 1.20026 2.62579 + vertex 0.988752 1.20387 2.62608 + vertex 0.984362 1.20008 2.62595 + endloop + endfacet + facet normal 0.0558819 -0.121012 0.991077 + outer loop + vertex 0.987549 1.20026 2.62579 + vertex 0.984362 1.20008 2.62595 + vertex 0.985088 1.19762 2.6256 + endloop + endfacet + facet normal 0.0705369 -0.134448 0.988407 + outer loop + vertex 0.989052 1.19823 2.6254 + vertex 0.987549 1.20026 2.62579 + vertex 0.985088 1.19762 2.6256 + endloop + endfacet + facet normal 0.0711632 -0.138667 0.987779 + outer loop + vertex 0.985088 1.19762 2.6256 + vertex 0.983391 1.19345 2.62514 + vertex 0.989052 1.19823 2.6254 + endloop + endfacet + facet normal 0.0648749 -0.13131 0.989216 + outer loop + vertex 0.989052 1.19823 2.6254 + vertex 0.983391 1.19345 2.62514 + vertex 0.988612 1.19326 2.62477 + endloop + endfacet + facet normal 0.101314 -0.134098 0.985776 + outer loop + vertex 0.988612 1.19326 2.62477 + vertex 0.993865 1.19824 2.62491 + vertex 0.989052 1.19823 2.6254 + endloop + endfacet + facet normal 0.101408 -0.126072 0.986824 + outer loop + vertex 0.994272 1.20309 2.62549 + vertex 0.989052 1.19823 2.6254 + vertex 0.993865 1.19824 2.62491 + endloop + endfacet + facet normal 0.173693 -0.130859 0.976067 + outer loop + vertex 0.993865 1.19824 2.62491 + vertex 0.99882 1.20327 2.6247 + vertex 0.994272 1.20309 2.62549 + endloop + endfacet + facet normal 0.173313 -0.109297 0.978783 + outer loop + vertex 0.99897 1.20826 2.62523 + vertex 0.994272 1.20309 2.62549 + vertex 0.99882 1.20327 2.6247 + endloop + endfacet + facet normal 0.210711 -0.143869 0.966904 + outer loop + vertex 0.995408 1.20692 2.62581 + vertex 0.994272 1.20309 2.62549 + vertex 0.99897 1.20826 2.62523 + endloop + endfacet + facet normal 0.127873 -0.120774 0.98441 + outer loop + vertex 0.995408 1.20692 2.62581 + vertex 0.992581 1.20483 2.62592 + vertex 0.994272 1.20309 2.62549 + endloop + endfacet + facet normal 0.115629 -0.132679 0.984391 + outer loop + vertex 0.994272 1.20309 2.62549 + vertex 0.992581 1.20483 2.62592 + vertex 0.990494 1.20198 2.62578 + endloop + endfacet + facet normal 0.0648052 -0.0958742 0.993282 + outer loop + vertex 0.992581 1.20483 2.62592 + vertex 0.988752 1.20387 2.62608 + vertex 0.990494 1.20198 2.62578 + endloop + endfacet + facet normal 0.0580875 -0.0686502 0.995948 + outer loop + vertex 0.992581 1.20483 2.62592 + vertex 0.993363 1.20856 2.62613 + vertex 0.988752 1.20387 2.62608 + endloop + endfacet + facet normal 0.0669326 -0.0773319 0.994756 + outer loop + vertex 0.993363 1.20856 2.62613 + vertex 0.988609 1.20834 2.62644 + vertex 0.988752 1.20387 2.62608 + endloop + endfacet + facet normal 0.0952473 -0.0762452 0.992529 + outer loop + vertex 0.995408 1.20692 2.62581 + vertex 0.993363 1.20856 2.62613 + vertex 0.992581 1.20483 2.62592 + endloop + endfacet + facet normal 0.149948 -0.107168 0.982869 + outer loop + vertex 0.998596 1.19829 2.6242 + vertex 0.99882 1.20327 2.6247 + vertex 0.993865 1.19824 2.62491 + endloop + endfacet + facet normal 0.149819 -0.126255 0.980619 + outer loop + vertex 0.993572 1.19324 2.62431 + vertex 0.998596 1.19829 2.6242 + vertex 0.993865 1.19824 2.62491 + endloop + endfacet + facet normal 0.136663 -0.113096 0.98414 + outer loop + vertex 0.998427 1.19326 2.62364 + vertex 0.998596 1.19829 2.6242 + vertex 0.993572 1.19324 2.62431 + endloop + endfacet + facet normal 0.136429 -0.13124 0.981918 + outer loop + vertex 0.99342 1.18814 2.62365 + vertex 0.998427 1.19326 2.62364 + vertex 0.993572 1.19324 2.62431 + endloop + endfacet + facet normal 0.0866445 -0.130495 0.987656 + outer loop + vertex 0.99342 1.18814 2.62365 + vertex 0.993572 1.19324 2.62431 + vertex 0.988401 1.18814 2.62409 + endloop + endfacet + facet normal 0.0864797 -0.14256 0.986001 + outer loop + vertex 0.988309 1.18299 2.62335 + vertex 0.99342 1.18814 2.62365 + vertex 0.988401 1.18814 2.62409 + endloop + endfacet + facet normal 0.0644271 -0.142409 0.987709 + outer loop + vertex 0.988309 1.18299 2.62335 + vertex 0.988401 1.18814 2.62409 + vertex 0.983282 1.18305 2.62369 + endloop + endfacet + facet normal 0.0642994 -0.147919 0.986907 + outer loop + vertex 0.98325 1.17791 2.62292 + vertex 0.988309 1.18299 2.62335 + vertex 0.983282 1.18305 2.62369 + endloop + endfacet + facet normal 0.0588996 -0.147936 0.987241 + outer loop + vertex 0.98325 1.17791 2.62292 + vertex 0.983282 1.18305 2.62369 + vertex 0.978212 1.17797 2.62323 + endloop + endfacet + facet normal 0.0588521 -0.150235 0.986897 + outer loop + vertex 0.978274 1.17294 2.62246 + vertex 0.98325 1.17791 2.62292 + vertex 0.978212 1.17797 2.62323 + endloop + endfacet + facet normal 0.0558261 -0.150297 0.987063 + outer loop + vertex 0.978274 1.17294 2.62246 + vertex 0.978212 1.17797 2.62323 + vertex 0.973181 1.17291 2.62275 + endloop + endfacet + facet normal 0.055825 -0.150641 0.987011 + outer loop + vertex 0.973448 1.16811 2.622 + vertex 0.978274 1.17294 2.62246 + vertex 0.973181 1.17291 2.62275 + endloop + endfacet + facet normal 0.049964 -0.151006 0.987269 + outer loop + vertex 0.973448 1.16811 2.622 + vertex 0.973181 1.17291 2.62275 + vertex 0.968352 1.16802 2.62224 + endloop + endfacet + facet normal 0.0499428 -0.148955 0.987582 + outer loop + vertex 0.968954 1.1637 2.62156 + vertex 0.973448 1.16811 2.622 + vertex 0.968352 1.16802 2.62224 + endloop + endfacet + facet normal 0.0436876 -0.149853 0.987743 + outer loop + vertex 0.968954 1.1637 2.62156 + vertex 0.968352 1.16802 2.62224 + vertex 0.964026 1.16349 2.62175 + endloop + endfacet + facet normal 0.0436023 -0.147424 0.988112 + outer loop + vertex 0.965107 1.15981 2.62115 + vertex 0.968954 1.1637 2.62156 + vertex 0.964026 1.16349 2.62175 + endloop + endfacet + facet normal 0.0396978 -0.148568 0.988105 + outer loop + vertex 0.965107 1.15981 2.62115 + vertex 0.964026 1.16349 2.62175 + vertex 0.960296 1.15943 2.62129 + endloop + endfacet + facet normal 0.039903 -0.151355 0.987674 + outer loop + vertex 0.965107 1.15981 2.62115 + vertex 0.960296 1.15943 2.62129 + vertex 0.961646 1.15604 2.62071 + endloop + endfacet + facet normal 0.0418498 -0.153105 0.987323 + outer loop + vertex 0.966364 1.15663 2.6206 + vertex 0.965107 1.15981 2.62115 + vertex 0.961646 1.15604 2.62071 + endloop + endfacet + facet normal 0.0427752 -0.160799 0.98606 + outer loop + vertex 0.961646 1.15604 2.62071 + vertex 0.962803 1.15252 2.62009 + vertex 0.966364 1.15663 2.6206 + endloop + endfacet + facet normal 0.0451775 -0.162825 0.98562 + outer loop + vertex 0.962803 1.15252 2.62009 + vertex 0.968392 1.15351 2.62 + vertex 0.966364 1.15663 2.6206 + endloop + endfacet + facet normal 0.0480972 -0.160956 0.985789 + outer loop + vertex 0.970142 1.15753 2.62057 + vertex 0.966364 1.15663 2.6206 + vertex 0.968392 1.15351 2.62 + endloop + endfacet + facet normal 0.0560563 -0.164282 0.984819 + outer loop + vertex 0.970142 1.15753 2.62057 + vertex 0.968392 1.15351 2.62 + vertex 0.973366 1.15734 2.62035 + endloop + endfacet + facet normal 0.0565817 -0.157019 0.985973 + outer loop + vertex 0.973366 1.15734 2.62035 + vertex 0.97272 1.15991 2.6208 + vertex 0.970142 1.15753 2.62057 + endloop + endfacet + facet normal 0.0512947 -0.151382 0.987143 + outer loop + vertex 0.97272 1.15991 2.6208 + vertex 0.969535 1.16012 2.621 + vertex 0.970142 1.15753 2.62057 + endloop + endfacet + facet normal 0.0516795 -0.146444 0.987868 + outer loop + vertex 0.97272 1.15991 2.6208 + vertex 0.974095 1.1636 2.62127 + vertex 0.969535 1.16012 2.621 + endloop + endfacet + facet normal 0.05251 -0.147517 0.987665 + outer loop + vertex 0.974095 1.1636 2.62127 + vertex 0.968954 1.1637 2.62156 + vertex 0.969535 1.16012 2.621 + endloop + endfacet + facet normal 0.0602729 -0.149518 0.98692 + outer loop + vertex 0.976414 1.16102 2.62074 + vertex 0.974095 1.1636 2.62127 + vertex 0.97272 1.15991 2.6208 + endloop + endfacet + facet normal 0.0615927 -0.14835 0.987015 + outer loop + vertex 0.979407 1.16468 2.6211 + vertex 0.974095 1.1636 2.62127 + vertex 0.976414 1.16102 2.62074 + endloop + endfacet + facet normal 0.0646071 -0.150763 0.986456 + outer loop + vertex 0.980208 1.16221 2.62067 + vertex 0.979407 1.16468 2.6211 + vertex 0.976414 1.16102 2.62074 + endloop + endfacet + facet normal 0.065114 -0.152392 0.986173 + outer loop + vertex 0.980208 1.16221 2.62067 + vertex 0.976414 1.16102 2.62074 + vertex 0.978532 1.15831 2.62018 + endloop + endfacet + facet normal 0.0631337 -0.151574 0.986428 + outer loop + vertex 0.980208 1.16221 2.62067 + vertex 0.978532 1.15831 2.62018 + vertex 0.983521 1.16212 2.62045 + endloop + endfacet + facet normal 0.0601664 -0.147742 0.987194 + outer loop + vertex 0.983521 1.16212 2.62045 + vertex 0.978532 1.15831 2.62018 + vertex 0.983602 1.15815 2.61985 + endloop + endfacet + facet normal 0.0568925 -0.147835 0.987374 + outer loop + vertex 0.983602 1.15815 2.61985 + vertex 0.988711 1.16307 2.62029 + vertex 0.983521 1.16212 2.62045 + endloop + endfacet + facet normal 0.0560782 -0.143281 0.988092 + outer loop + vertex 0.983521 1.16212 2.62045 + vertex 0.988711 1.16307 2.62029 + vertex 0.986655 1.16579 2.6208 + endloop + endfacet + facet normal 0.0556744 -0.143582 0.988071 + outer loop + vertex 0.990478 1.16691 2.62075 + vertex 0.986655 1.16579 2.6208 + vertex 0.988711 1.16307 2.62029 + endloop + endfacet + facet normal 0.0542818 -0.142961 0.988239 + outer loop + vertex 0.990478 1.16691 2.62075 + vertex 0.988711 1.16307 2.62029 + vertex 0.993737 1.16688 2.62057 + endloop + endfacet + facet normal 0.0541804 -0.148161 0.987478 + outer loop + vertex 0.993737 1.16688 2.62057 + vertex 0.993115 1.16938 2.62098 + vertex 0.990478 1.16691 2.62075 + endloop + endfacet + facet normal 0.0554177 -0.14946 0.987214 + outer loop + vertex 0.993115 1.16938 2.62098 + vertex 0.989693 1.16945 2.62118 + vertex 0.990478 1.16691 2.62075 + endloop + endfacet + facet normal 0.0555985 -0.14312 0.988142 + outer loop + vertex 0.993115 1.16938 2.62098 + vertex 0.994425 1.17328 2.62147 + vertex 0.989693 1.16945 2.62118 + endloop + endfacet + facet normal 0.0640447 -0.153401 0.986086 + outer loop + vertex 0.994425 1.17328 2.62147 + vertex 0.988988 1.17326 2.62182 + vertex 0.989693 1.16945 2.62118 + endloop + endfacet + facet normal 0.0627673 -0.153644 0.986131 + outer loop + vertex 0.989693 1.16945 2.62118 + vertex 0.988988 1.17326 2.62182 + vertex 0.984246 1.1684 2.62136 + endloop + endfacet + facet normal 0.0627151 -0.153364 0.986178 + outer loop + vertex 0.989693 1.16945 2.62118 + vertex 0.984246 1.1684 2.62136 + vertex 0.986655 1.16579 2.6208 + endloop + endfacet + facet normal 0.0653979 -0.156159 0.985565 + outer loop + vertex 0.984246 1.1684 2.62136 + vertex 0.988988 1.17326 2.62182 + vertex 0.98356 1.17303 2.62214 + endloop + endfacet + facet normal 0.0652184 -0.156186 0.985572 + outer loop + vertex 0.984246 1.1684 2.62136 + vertex 0.98356 1.17303 2.62214 + vertex 0.978735 1.16835 2.62172 + endloop + endfacet + facet normal 0.0652206 -0.153102 0.986056 + outer loop + vertex 0.984246 1.1684 2.62136 + vertex 0.978735 1.16835 2.62172 + vertex 0.979407 1.16468 2.6211 + endloop + endfacet + facet normal 0.0660862 -0.15421 0.985826 + outer loop + vertex 0.982855 1.16467 2.62087 + vertex 0.984246 1.1684 2.62136 + vertex 0.979407 1.16468 2.6211 + endloop + endfacet + facet normal 0.0661367 -0.150262 0.986432 + outer loop + vertex 0.982855 1.16467 2.62087 + vertex 0.979407 1.16468 2.6211 + vertex 0.980208 1.16221 2.62067 + endloop + endfacet + facet normal 0.0632982 -0.147252 0.987072 + outer loop + vertex 0.983521 1.16212 2.62045 + vertex 0.982855 1.16467 2.62087 + vertex 0.980208 1.16221 2.62067 + endloop + endfacet + facet normal 0.0614254 -0.147749 0.987116 + outer loop + vertex 0.982855 1.16467 2.62087 + vertex 0.983521 1.16212 2.62045 + vertex 0.986655 1.16579 2.6208 + endloop + endfacet + facet normal 0.0629969 -0.153108 0.986199 + outer loop + vertex 0.986655 1.16579 2.6208 + vertex 0.984246 1.1684 2.62136 + vertex 0.982855 1.16467 2.62087 + endloop + endfacet + facet normal 0.0652948 -0.153022 0.986063 + outer loop + vertex 0.988988 1.17326 2.62182 + vertex 0.988473 1.17796 2.62258 + vertex 0.98356 1.17303 2.62214 + endloop + endfacet + facet normal 0.0662099 -0.153918 0.985863 + outer loop + vertex 0.98356 1.17303 2.62214 + vertex 0.988473 1.17796 2.62258 + vertex 0.98325 1.17791 2.62292 + endloop + endfacet + facet normal 0.0743846 -0.151947 0.985586 + outer loop + vertex 0.988988 1.17326 2.62182 + vertex 0.993777 1.17807 2.6222 + vertex 0.988473 1.17796 2.62258 + endloop + endfacet + facet normal 0.0742737 -0.141621 0.987131 + outer loop + vertex 0.993777 1.17807 2.6222 + vertex 0.993461 1.18303 2.62293 + vertex 0.988473 1.17796 2.62258 + endloop + endfacet + facet normal 0.082017 -0.149114 0.985413 + outer loop + vertex 0.988473 1.17796 2.62258 + vertex 0.993461 1.18303 2.62293 + vertex 0.988309 1.18299 2.62335 + endloop + endfacet + facet normal 0.107265 -0.139123 0.984449 + outer loop + vertex 0.993777 1.17807 2.6222 + vertex 0.998565 1.18313 2.62239 + vertex 0.993461 1.18303 2.62293 + endloop + endfacet + facet normal 0.107156 -0.122478 0.98667 + outer loop + vertex 0.998565 1.18313 2.62239 + vertex 0.998386 1.18818 2.62304 + vertex 0.993461 1.18303 2.62293 + endloop + endfacet + facet normal 0.122769 -0.13732 0.982889 + outer loop + vertex 0.993461 1.18303 2.62293 + vertex 0.998386 1.18818 2.62304 + vertex 0.99342 1.18814 2.62365 + endloop + endfacet + facet normal 0.0880319 -0.121105 0.988728 + outer loop + vertex 0.998828 1.17831 2.62178 + vertex 0.998565 1.18313 2.62239 + vertex 0.993777 1.17807 2.6222 + endloop + endfacet + facet normal 0.0886652 -0.138366 0.986404 + outer loop + vertex 0.994425 1.17328 2.62147 + vertex 0.998828 1.17831 2.62178 + vertex 0.993777 1.17807 2.6222 + endloop + endfacet + facet normal 0.0670634 -0.119722 0.99054 + outer loop + vertex 0.999427 1.17452 2.62128 + vertex 0.998828 1.17831 2.62178 + vertex 0.994425 1.17328 2.62147 + endloop + endfacet + facet normal 0.0706368 -0.134468 0.988397 + outer loop + vertex 0.999427 1.17452 2.62128 + vertex 0.994425 1.17328 2.62147 + vertex 0.996798 1.17068 2.62094 + endloop + endfacet + facet normal 0.0899496 -0.147403 0.984978 + outer loop + vertex 1.00051 1.17227 2.62084 + vertex 0.999427 1.17452 2.62128 + vertex 0.996798 1.17068 2.62094 + endloop + endfacet + facet normal 0.0956961 -0.161006 0.982303 + outer loop + vertex 1.00051 1.17227 2.62084 + vertex 0.996798 1.17068 2.62094 + vertex 0.998904 1.16824 2.62034 + endloop + endfacet + facet normal 0.200722 -0.199927 0.959031 + outer loop + vertex 1.00051 1.17227 2.62084 + vertex 0.998904 1.16824 2.62034 + vertex 1.00418 1.17326 2.62028 + endloop + endfacet + facet normal 0.200359 -0.19836 0.959432 + outer loop + vertex 1.00418 1.17326 2.62028 + vertex 1.00255 1.17501 2.62098 + vertex 1.00051 1.17227 2.62084 + endloop + endfacet + facet normal 0.151336 -0.147854 0.977362 + outer loop + vertex 1.00418 1.17326 2.62028 + vertex 0.998904 1.16824 2.62034 + vertex 1.00382 1.16832 2.61959 + endloop + endfacet + facet normal 0.151317 -0.150681 0.976933 + outer loop + vertex 0.998714 1.16325 2.6196 + vertex 1.00382 1.16832 2.61959 + vertex 0.998904 1.16824 2.62034 + endloop + endfacet + facet normal 0.0853703 -0.149378 0.985088 + outer loop + vertex 0.998714 1.16325 2.6196 + vertex 0.998904 1.16824 2.62034 + vertex 0.993753 1.16301 2.61999 + endloop + endfacet + facet normal 0.0853774 -0.149569 0.985058 + outer loop + vertex 0.993478 1.15816 2.61928 + vertex 0.998714 1.16325 2.6196 + vertex 0.993753 1.16301 2.61999 + endloop + endfacet + facet normal 0.0595039 -0.148408 0.987134 + outer loop + vertex 0.993478 1.15816 2.61928 + vertex 0.993753 1.16301 2.61999 + vertex 0.988553 1.15819 2.61958 + endloop + endfacet + facet normal 0.0594034 -0.155211 0.986094 + outer loop + vertex 0.988261 1.1531 2.6188 + vertex 0.993478 1.15816 2.61928 + vertex 0.988553 1.15819 2.61958 + endloop + endfacet + facet normal 0.0563822 -0.155068 0.986294 + outer loop + vertex 0.988261 1.1531 2.6188 + vertex 0.988553 1.15819 2.61958 + vertex 0.983366 1.15321 2.61909 + endloop + endfacet + facet normal 0.0562066 -0.160498 0.985434 + outer loop + vertex 0.983193 1.14803 2.61826 + vertex 0.988261 1.1531 2.6188 + vertex 0.983366 1.15321 2.61909 + endloop + endfacet + facet normal 0.0584625 -0.160551 0.985295 + outer loop + vertex 0.983193 1.14803 2.61826 + vertex 0.983366 1.15321 2.61909 + vertex 0.978257 1.14813 2.61857 + endloop + endfacet + facet normal 0.0583976 -0.162583 0.984965 + outer loop + vertex 0.978355 1.14302 2.61772 + vertex 0.983193 1.14803 2.61826 + vertex 0.978257 1.14813 2.61857 + endloop + endfacet + facet normal 0.055942 -0.162652 0.985096 + outer loop + vertex 0.978355 1.14302 2.61772 + vertex 0.978257 1.14813 2.61857 + vertex 0.973294 1.143 2.61801 + endloop + endfacet + facet normal 0.0559518 -0.161286 0.98532 + outer loop + vertex 0.973823 1.13813 2.61718 + vertex 0.978355 1.14302 2.61772 + vertex 0.973294 1.143 2.61801 + endloop + endfacet + facet normal 0.0487477 -0.16211 0.985568 + outer loop + vertex 0.973823 1.13813 2.61718 + vertex 0.973294 1.143 2.61801 + vertex 0.968578 1.13796 2.61741 + endloop + endfacet + facet normal 0.0486745 -0.15935 0.986021 + outer loop + vertex 0.969491 1.13315 2.61659 + vertex 0.973823 1.13813 2.61718 + vertex 0.968578 1.13796 2.61741 + endloop + endfacet + facet normal 0.0407547 -0.160874 0.986133 + outer loop + vertex 0.969491 1.13315 2.61659 + vertex 0.968578 1.13796 2.61741 + vertex 0.964179 1.13341 2.61685 + endloop + endfacet + facet normal 0.0408126 -0.159846 0.986298 + outer loop + vertex 0.969491 1.13315 2.61659 + vertex 0.964179 1.13341 2.61685 + vertex 0.964937 1.12969 2.61621 + endloop + endfacet + facet normal 0.0395403 -0.158205 0.986614 + outer loop + vertex 0.968229 1.12935 2.61603 + vertex 0.969491 1.13315 2.61659 + vertex 0.964937 1.12969 2.61621 + endloop + endfacet + facet normal 0.0385381 -0.167123 0.985183 + outer loop + vertex 0.968229 1.12935 2.61603 + vertex 0.964937 1.12969 2.61621 + vertex 0.965568 1.12706 2.61574 + endloop + endfacet + facet normal 0.0444667 -0.173831 0.983771 + outer loop + vertex 0.968681 1.12671 2.61554 + vertex 0.968229 1.12935 2.61603 + vertex 0.965568 1.12706 2.61574 + endloop + endfacet + facet normal 0.0429073 -0.186523 0.981513 + outer loop + vertex 0.965568 1.12706 2.61574 + vertex 0.963564 1.1231 2.61508 + vertex 0.968681 1.12671 2.61554 + endloop + endfacet + facet normal 0.0390724 -0.181242 0.982662 + outer loop + vertex 0.968681 1.12671 2.61554 + vertex 0.963564 1.1231 2.61508 + vertex 0.968575 1.12284 2.61483 + endloop + endfacet + facet normal 0.0528909 -0.181492 0.981969 + outer loop + vertex 0.968575 1.12284 2.61483 + vertex 0.973163 1.12714 2.61538 + vertex 0.968681 1.12671 2.61554 + endloop + endfacet + facet normal 0.0522024 -0.173679 0.983418 + outer loop + vertex 0.968681 1.12671 2.61554 + vertex 0.973163 1.12714 2.61538 + vertex 0.971973 1.13026 2.61599 + endloop + endfacet + facet normal 0.0578983 -0.171518 0.983478 + outer loop + vertex 0.971973 1.13026 2.61599 + vertex 0.973163 1.12714 2.61538 + vertex 0.976641 1.1311 2.61586 + endloop + endfacet + facet normal 0.0564917 -0.163524 0.984921 + outer loop + vertex 0.976641 1.1311 2.61586 + vertex 0.975093 1.13418 2.61646 + vertex 0.971973 1.13026 2.61599 + endloop + endfacet + facet normal 0.0506412 -0.158997 0.985979 + outer loop + vertex 0.975093 1.13418 2.61646 + vertex 0.969491 1.13315 2.61659 + vertex 0.971973 1.13026 2.61599 + endloop + endfacet + facet normal 0.061278 -0.161136 0.985028 + outer loop + vertex 0.979797 1.13469 2.61626 + vertex 0.975093 1.13418 2.61646 + vertex 0.976641 1.1311 2.61586 + endloop + endfacet + facet normal 0.0628766 -0.175756 0.982424 + outer loop + vertex 0.973163 1.12714 2.61538 + vertex 0.978649 1.12819 2.61522 + vertex 0.976641 1.1311 2.61586 + endloop + endfacet + facet normal 0.0636638 -0.179981 0.981608 + outer loop + vertex 0.973522 1.12308 2.61461 + vertex 0.978649 1.12819 2.61522 + vertex 0.973163 1.12714 2.61538 + endloop + endfacet + facet normal 0.0616187 -0.177987 0.982102 + outer loop + vertex 0.978512 1.12325 2.61433 + vertex 0.978649 1.12819 2.61522 + vertex 0.973522 1.12308 2.61461 + endloop + endfacet + facet normal 0.0617165 -0.182232 0.981317 + outer loop + vertex 0.97334 1.11817 2.61371 + vertex 0.978512 1.12325 2.61433 + vertex 0.973522 1.12308 2.61461 + endloop + endfacet + facet normal 0.0521986 -0.181988 0.981914 + outer loop + vertex 0.97334 1.11817 2.61371 + vertex 0.973522 1.12308 2.61461 + vertex 0.968399 1.1181 2.61396 + endloop + endfacet + facet normal 0.0521884 -0.180123 0.982259 + outer loop + vertex 0.968422 1.11309 2.61304 + vertex 0.97334 1.11817 2.61371 + vertex 0.968399 1.1181 2.61396 + endloop + endfacet + facet normal 0.0416677 -0.180259 0.982736 + outer loop + vertex 0.968422 1.11309 2.61304 + vertex 0.968399 1.1181 2.61396 + vertex 0.963456 1.11302 2.61324 + endloop + endfacet + facet normal 0.0416122 -0.173817 0.983898 + outer loop + vertex 0.964047 1.10827 2.61237 + vertex 0.968422 1.11309 2.61304 + vertex 0.963456 1.11302 2.61324 + endloop + endfacet + facet normal 0.0261131 -0.175782 0.984083 + outer loop + vertex 0.964047 1.10827 2.61237 + vertex 0.963456 1.11302 2.61324 + vertex 0.959019 1.1082 2.6125 + endloop + endfacet + facet normal 0.0260693 -0.171015 0.984924 + outer loop + vertex 0.960172 1.10393 2.61172 + vertex 0.964047 1.10827 2.61237 + vertex 0.959019 1.1082 2.6125 + endloop + endfacet + facet normal -0.00270198 -0.178596 0.983919 + outer loop + vertex 0.960172 1.10393 2.61172 + vertex 0.959019 1.1082 2.6125 + vertex 0.955025 1.10406 2.61173 + endloop + endfacet + facet normal -0.0027767 -0.181447 0.983397 + outer loop + vertex 0.960172 1.10393 2.61172 + vertex 0.955025 1.10406 2.61173 + vertex 0.956453 1.10008 2.611 + endloop + endfacet + facet normal 0.00520604 -0.188891 0.981984 + outer loop + vertex 0.961552 1.10024 2.61101 + vertex 0.960172 1.10393 2.61172 + vertex 0.956453 1.10008 2.611 + endloop + endfacet + facet normal 0.00542561 -0.195895 0.98061 + outer loop + vertex 0.956453 1.10008 2.611 + vertex 0.957616 1.09638 2.61026 + vertex 0.961552 1.10024 2.61101 + endloop + endfacet + facet normal 0.0110895 -0.201444 0.979437 + outer loop + vertex 0.957616 1.09638 2.61026 + vertex 0.962625 1.09667 2.61026 + vertex 0.961552 1.10024 2.61101 + endloop + endfacet + facet normal 0.0397482 -0.19302 0.980389 + outer loop + vertex 0.961552 1.10024 2.61101 + vertex 0.962625 1.09667 2.61026 + vertex 0.966586 1.10072 2.6109 + endloop + endfacet + facet normal 0.0389153 -0.183942 0.982166 + outer loop + vertex 0.966586 1.10072 2.6109 + vertex 0.965234 1.10421 2.6116 + vertex 0.961552 1.10024 2.61101 + endloop + endfacet + facet normal 0.0520653 -0.17891 0.982487 + outer loop + vertex 0.970179 1.10462 2.61142 + vertex 0.965234 1.10421 2.6116 + vertex 0.966586 1.10072 2.6109 + endloop + endfacet + facet normal 0.053414 -0.180114 0.982194 + outer loop + vertex 0.971471 1.10139 2.61075 + vertex 0.970179 1.10462 2.61142 + vertex 0.966586 1.10072 2.6109 + endloop + endfacet + facet normal 0.0545692 -0.188868 0.980485 + outer loop + vertex 0.966586 1.10072 2.6109 + vertex 0.967737 1.09723 2.61016 + vertex 0.971471 1.10139 2.61075 + endloop + endfacet + facet normal 0.0529223 -0.187443 0.980849 + outer loop + vertex 0.967737 1.09723 2.61016 + vertex 0.973436 1.09828 2.61005 + vertex 0.971471 1.10139 2.61075 + endloop + endfacet + facet normal 0.058888 -0.183752 0.981207 + outer loop + vertex 0.975364 1.1023 2.61069 + vertex 0.971471 1.10139 2.61075 + vertex 0.973436 1.09828 2.61005 + endloop + endfacet + facet normal 0.0586314 -0.183635 0.981244 + outer loop + vertex 0.975364 1.1023 2.61069 + vertex 0.973436 1.09828 2.61005 + vertex 0.978453 1.10195 2.61044 + endloop + endfacet + facet normal 0.0594622 -0.177226 0.982372 + outer loop + vertex 0.978453 1.10195 2.61044 + vertex 0.978002 1.10462 2.61095 + vertex 0.975364 1.1023 2.61069 + endloop + endfacet + facet normal 0.0590173 -0.176733 0.982488 + outer loop + vertex 0.978002 1.10462 2.61095 + vertex 0.974755 1.10494 2.6112 + vertex 0.975364 1.1023 2.61069 + endloop + endfacet + facet normal 0.0589801 -0.177072 0.982429 + outer loop + vertex 0.978002 1.10462 2.61095 + vertex 0.979317 1.1084 2.61155 + vertex 0.974755 1.10494 2.6112 + endloop + endfacet + facet normal 0.0592512 -0.177421 0.98235 + outer loop + vertex 0.979317 1.1084 2.61155 + vertex 0.97406 1.10863 2.61191 + vertex 0.974755 1.10494 2.6112 + endloop + endfacet + facet normal 0.0584232 -0.17758 0.982371 + outer loop + vertex 0.974755 1.10494 2.6112 + vertex 0.97406 1.10863 2.61191 + vertex 0.970179 1.10462 2.61142 + endloop + endfacet + facet normal 0.0568355 -0.17609 0.982732 + outer loop + vertex 0.970179 1.10462 2.61142 + vertex 0.97406 1.10863 2.61191 + vertex 0.969049 1.10847 2.61217 + endloop + endfacet + facet normal 0.0569265 -0.180138 0.981993 + outer loop + vertex 0.97406 1.10863 2.61191 + vertex 0.973416 1.11316 2.61278 + vertex 0.969049 1.10847 2.61217 + endloop + endfacet + facet normal 0.0540283 -0.177524 0.982632 + outer loop + vertex 0.969049 1.10847 2.61217 + vertex 0.973416 1.11316 2.61278 + vertex 0.968422 1.11309 2.61304 + endloop + endfacet + facet normal 0.0591428 -0.17981 0.981922 + outer loop + vertex 0.97406 1.10863 2.61191 + vertex 0.978504 1.11316 2.61247 + vertex 0.973416 1.11316 2.61278 + endloop + endfacet + facet normal 0.0591282 -0.181116 0.981683 + outer loop + vertex 0.978504 1.11316 2.61247 + vertex 0.978301 1.11817 2.61341 + vertex 0.973416 1.11316 2.61278 + endloop + endfacet + facet normal 0.0597703 -0.181724 0.981531 + outer loop + vertex 0.973416 1.11316 2.61278 + vertex 0.978301 1.11817 2.61341 + vertex 0.97334 1.11817 2.61371 + endloop + endfacet + facet normal 0.0617665 -0.180983 0.981545 + outer loop + vertex 0.978504 1.11316 2.61247 + vertex 0.983291 1.11813 2.61309 + vertex 0.978301 1.11817 2.61341 + endloop + endfacet + facet normal 0.0618335 -0.177525 0.982172 + outer loop + vertex 0.983291 1.11813 2.61309 + vertex 0.983392 1.12323 2.614 + vertex 0.978301 1.11817 2.61341 + endloop + endfacet + facet normal 0.0648464 -0.180472 0.98144 + outer loop + vertex 0.978301 1.11817 2.61341 + vertex 0.983392 1.12323 2.614 + vertex 0.978512 1.12325 2.61433 + endloop + endfacet + facet normal 0.0649593 -0.173906 0.982617 + outer loop + vertex 0.983392 1.12323 2.614 + vertex 0.983549 1.12798 2.61483 + vertex 0.978512 1.12325 2.61433 + endloop + endfacet + facet normal 0.0671656 -0.173951 0.982461 + outer loop + vertex 0.983392 1.12323 2.614 + vertex 0.988381 1.12816 2.61454 + vertex 0.983549 1.12798 2.61483 + endloop + endfacet + facet normal 0.0669343 -0.165302 0.983969 + outer loop + vertex 0.988381 1.12816 2.61454 + vertex 0.987952 1.13231 2.61526 + vertex 0.983549 1.12798 2.61483 + endloop + endfacet + facet normal 0.0721431 -0.170475 0.982718 + outer loop + vertex 0.983549 1.12798 2.61483 + vertex 0.987952 1.13231 2.61526 + vertex 0.983564 1.13185 2.6155 + endloop + endfacet + facet normal 0.0694298 -0.170497 0.982909 + outer loop + vertex 0.983564 1.13185 2.6155 + vertex 0.978649 1.12819 2.61522 + vertex 0.983549 1.12798 2.61483 + endloop + endfacet + facet normal 0.071533 -0.164085 0.983849 + outer loop + vertex 0.983564 1.13185 2.6155 + vertex 0.987952 1.13231 2.61526 + vertex 0.986759 1.13547 2.61588 + endloop + endfacet + facet normal 0.0747914 -0.166886 0.983135 + outer loop + vertex 0.983074 1.13448 2.61599 + vertex 0.983564 1.13185 2.6155 + vertex 0.986759 1.13547 2.61588 + endloop + endfacet + facet normal 0.074404 -0.165417 0.983413 + outer loop + vertex 0.986759 1.13547 2.61588 + vertex 0.984339 1.1383 2.61653 + vertex 0.983074 1.13448 2.61599 + endloop + endfacet + facet normal 0.070157 -0.164087 0.983948 + outer loop + vertex 0.983074 1.13448 2.61599 + vertex 0.984339 1.1383 2.61653 + vertex 0.979797 1.13469 2.61626 + endloop + endfacet + facet normal 0.0702365 -0.163058 0.984113 + outer loop + vertex 0.983074 1.13448 2.61599 + vertex 0.979797 1.13469 2.61626 + vertex 0.98048 1.1321 2.61578 + endloop + endfacet + facet normal 0.0651201 -0.16443 0.984237 + outer loop + vertex 0.98048 1.1321 2.61578 + vertex 0.979797 1.13469 2.61626 + vertex 0.976641 1.1311 2.61586 + endloop + endfacet + facet normal 0.0672544 -0.17279 0.98266 + outer loop + vertex 0.98048 1.1321 2.61578 + vertex 0.976641 1.1311 2.61586 + vertex 0.978649 1.12819 2.61522 + endloop + endfacet + facet normal 0.0731727 -0.175435 0.981768 + outer loop + vertex 0.98048 1.1321 2.61578 + vertex 0.978649 1.12819 2.61522 + vertex 0.983564 1.13185 2.6155 + endloop + endfacet + facet normal 0.0706809 -0.168543 0.983157 + outer loop + vertex 0.989897 1.13942 2.61633 + vertex 0.984339 1.1383 2.61653 + vertex 0.986759 1.13547 2.61588 + endloop + endfacet + facet normal 0.0703314 -0.168273 0.983228 + outer loop + vertex 0.99132 1.13634 2.6157 + vertex 0.989897 1.13942 2.61633 + vertex 0.986759 1.13547 2.61588 + endloop + endfacet + facet normal 0.066514 -0.170029 0.983192 + outer loop + vertex 0.994527 1.13995 2.61611 + vertex 0.989897 1.13942 2.61633 + vertex 0.99132 1.13634 2.6157 + endloop + endfacet + facet normal 0.0638082 -0.167692 0.983772 + outer loop + vertex 0.995107 1.13734 2.61562 + vertex 0.994527 1.13995 2.61611 + vertex 0.99132 1.13634 2.6157 + endloop + endfacet + facet normal 0.0620218 -0.160815 0.985034 + outer loop + vertex 0.995107 1.13734 2.61562 + vertex 0.99132 1.13634 2.6157 + vertex 0.993344 1.13334 2.61508 + endloop + endfacet + facet normal 0.0589908 -0.159534 0.985428 + outer loop + vertex 0.995107 1.13734 2.61562 + vertex 0.993344 1.13334 2.61508 + vertex 0.998344 1.13718 2.6154 + endloop + endfacet + facet normal 0.0585515 -0.166881 0.984237 + outer loop + vertex 0.998344 1.13718 2.6154 + vertex 0.99775 1.13976 2.61588 + vertex 0.995107 1.13734 2.61562 + endloop + endfacet + facet normal 0.0636672 -0.165684 0.984122 + outer loop + vertex 0.99775 1.13976 2.61588 + vertex 0.998344 1.13718 2.6154 + vertex 1.00144 1.14096 2.61584 + endloop + endfacet + facet normal 0.0639241 -0.16648 0.983971 + outer loop + vertex 1.00144 1.14096 2.61584 + vertex 0.99917 1.14356 2.61643 + vertex 0.99775 1.13976 2.61588 + endloop + endfacet + facet normal 0.0603356 -0.165201 0.984413 + outer loop + vertex 0.99775 1.13976 2.61588 + vertex 0.99917 1.14356 2.61643 + vertex 0.994527 1.13995 2.61611 + endloop + endfacet + facet normal 0.0673712 -0.174085 0.982423 + outer loop + vertex 0.99917 1.14356 2.61643 + vertex 0.993966 1.14362 2.61679 + vertex 0.994527 1.13995 2.61611 + endloop + endfacet + facet normal 0.0676019 -0.16412 0.984121 + outer loop + vertex 0.99917 1.14356 2.61643 + vertex 0.998631 1.1482 2.61724 + vertex 0.993966 1.14362 2.61679 + endloop + endfacet + facet normal 0.0755116 -0.17198 0.982202 + outer loop + vertex 0.993966 1.14362 2.61679 + vertex 0.998631 1.1482 2.61724 + vertex 0.993395 1.14807 2.61762 + endloop + endfacet + facet normal 0.0669926 -0.173147 0.982615 + outer loop + vertex 0.993966 1.14362 2.61679 + vertex 0.993395 1.14807 2.61762 + vertex 0.988746 1.14327 2.61709 + endloop + endfacet + facet normal 0.0670534 -0.174247 0.982416 + outer loop + vertex 0.989897 1.13942 2.61633 + vertex 0.993966 1.14362 2.61679 + vertex 0.988746 1.14327 2.61709 + endloop + endfacet + facet normal 0.0652483 -0.171502 0.983021 + outer loop + vertex 0.988746 1.14327 2.61709 + vertex 0.993395 1.14807 2.61762 + vertex 0.988224 1.14799 2.61795 + endloop + endfacet + facet normal 0.0659371 -0.17142 0.982989 + outer loop + vertex 0.988746 1.14327 2.61709 + vertex 0.988224 1.14799 2.61795 + vertex 0.983484 1.14304 2.6174 + endloop + endfacet + facet normal 0.0658175 -0.167976 0.983591 + outer loop + vertex 0.984339 1.1383 2.61653 + vertex 0.988746 1.14327 2.61709 + vertex 0.983484 1.14304 2.6174 + endloop + endfacet + facet normal 0.0671113 -0.167734 0.983545 + outer loop + vertex 0.984339 1.1383 2.61653 + vertex 0.983484 1.14304 2.6174 + vertex 0.979031 1.13842 2.61692 + endloop + endfacet + facet normal 0.0673526 -0.160618 0.984716 + outer loop + vertex 0.984339 1.1383 2.61653 + vertex 0.979031 1.13842 2.61692 + vertex 0.979797 1.13469 2.61626 + endloop + endfacet + facet normal 0.0613537 -0.161885 0.984901 + outer loop + vertex 0.979797 1.13469 2.61626 + vertex 0.979031 1.13842 2.61692 + vertex 0.975093 1.13418 2.61646 + endloop + endfacet + facet normal 0.0582495 -0.159069 0.985548 + outer loop + vertex 0.975093 1.13418 2.61646 + vertex 0.979031 1.13842 2.61692 + vertex 0.973823 1.13813 2.61718 + endloop + endfacet + facet normal 0.0620758 -0.162998 0.984672 + outer loop + vertex 0.979031 1.13842 2.61692 + vertex 0.983484 1.14304 2.6174 + vertex 0.978355 1.14302 2.61772 + endloop + endfacet + facet normal 0.0602865 -0.166149 0.984256 + outer loop + vertex 0.983484 1.14304 2.6174 + vertex 0.988224 1.14799 2.61795 + vertex 0.983193 1.14803 2.61826 + endloop + endfacet + facet normal 0.0652253 -0.167591 0.983697 + outer loop + vertex 0.993395 1.14807 2.61762 + vertex 0.993257 1.15305 2.61847 + vertex 0.988224 1.14799 2.61795 + endloop + endfacet + facet normal 0.0620472 -0.164506 0.984423 + outer loop + vertex 0.988224 1.14799 2.61795 + vertex 0.993257 1.15305 2.61847 + vertex 0.988261 1.1531 2.6188 + endloop + endfacet + facet normal 0.0804382 -0.166994 0.982671 + outer loop + vertex 0.993395 1.14807 2.61762 + vertex 0.998384 1.15309 2.61806 + vertex 0.993257 1.15305 2.61847 + endloop + endfacet + facet normal 0.0804944 -0.155542 0.984544 + outer loop + vertex 0.998384 1.15309 2.61806 + vertex 0.998451 1.1582 2.61886 + vertex 0.993257 1.15305 2.61847 + endloop + endfacet + facet normal 0.0836537 -0.158671 0.983781 + outer loop + vertex 0.993257 1.15305 2.61847 + vertex 0.998451 1.1582 2.61886 + vertex 0.993478 1.15816 2.61928 + endloop + endfacet + facet normal 0.075391 -0.162081 0.983893 + outer loop + vertex 0.998631 1.1482 2.61724 + vertex 0.998384 1.15309 2.61806 + vertex 0.993395 1.14807 2.61762 + endloop + endfacet + facet normal 0.0921877 -0.161009 0.982638 + outer loop + vertex 0.99917 1.14356 2.61643 + vertex 1.00368 1.14841 2.6168 + vertex 0.998631 1.1482 2.61724 + endloop + endfacet + facet normal 0.0916556 -0.142025 0.985611 + outer loop + vertex 1.00368 1.14841 2.6168 + vertex 1.00351 1.15317 2.6175 + vertex 0.998631 1.1482 2.61724 + endloop + endfacet + facet normal 0.11004 -0.159838 0.980991 + outer loop + vertex 0.998631 1.1482 2.61724 + vertex 1.00351 1.15317 2.6175 + vertex 0.998384 1.15309 2.61806 + endloop + endfacet + facet normal 0.110064 -0.144079 0.983426 + outer loop + vertex 1.00351 1.15317 2.6175 + vertex 1.00341 1.15823 2.61825 + vertex 0.998384 1.15309 2.61806 + endloop + endfacet + facet normal 0.121774 -0.155423 0.980314 + outer loop + vertex 0.998384 1.15309 2.61806 + vertex 1.00341 1.15823 2.61825 + vertex 0.998451 1.1582 2.61886 + endloop + endfacet + facet normal 0.121989 -0.137611 0.982946 + outer loop + vertex 1.00341 1.15823 2.61825 + vertex 1.00356 1.16332 2.61895 + vertex 0.998451 1.1582 2.61886 + endloop + endfacet + facet normal 0.134131 -0.149646 0.979599 + outer loop + vertex 0.998451 1.1582 2.61886 + vertex 1.00356 1.16332 2.61895 + vertex 0.998714 1.16325 2.6196 + endloop + endfacet + facet normal 0.194588 -0.138044 0.971123 + outer loop + vertex 1.00341 1.15823 2.61825 + vertex 1.00814 1.16317 2.61801 + vertex 1.00356 1.16332 2.61895 + endloop + endfacet + facet normal 0.195978 -0.113427 0.974026 + outer loop + vertex 1.00814 1.16317 2.61801 + vertex 1.00831 1.16818 2.61856 + vertex 1.00356 1.16332 2.61895 + endloop + endfacet + facet normal 0.218289 -0.135882 0.966378 + outer loop + vertex 1.00356 1.16332 2.61895 + vertex 1.00831 1.16818 2.61856 + vertex 1.00382 1.16832 2.61959 + endloop + endfacet + facet normal 0.219641 -0.112 0.96913 + outer loop + vertex 1.00831 1.16818 2.61856 + vertex 1.00858 1.17318 2.61907 + vertex 1.00382 1.16832 2.61959 + endloop + endfacet + facet normal 0.172722 -0.116823 0.978018 + outer loop + vertex 1.00813 1.15816 2.61741 + vertex 1.00814 1.16317 2.61801 + vertex 1.00341 1.15823 2.61825 + endloop + endfacet + facet normal 0.171817 -0.141627 0.974895 + outer loop + vertex 1.00351 1.15317 2.6175 + vertex 1.00813 1.15816 2.61741 + vertex 1.00341 1.15823 2.61825 + endloop + endfacet + facet normal 0.149988 -0.121283 0.981221 + outer loop + vertex 1.00859 1.15315 2.61672 + vertex 1.00813 1.15816 2.61741 + vertex 1.00351 1.15317 2.6175 + endloop + endfacet + facet normal 0.149555 -0.138956 0.978941 + outer loop + vertex 1.00368 1.14841 2.6168 + vertex 1.00859 1.15315 2.61672 + vertex 1.00351 1.15317 2.6175 + endloop + endfacet + facet normal 0.119804 -0.107942 0.986912 + outer loop + vertex 1.00767 1.14823 2.61629 + vertex 1.00859 1.15315 2.61672 + vertex 1.00368 1.14841 2.6168 + endloop + endfacet + facet normal 0.118158 -0.135611 0.983691 + outer loop + vertex 1.00767 1.14823 2.61629 + vertex 1.00368 1.14841 2.6168 + vertex 1.00418 1.14471 2.61623 + endloop + endfacet + facet normal 0.110434 -0.128 0.985607 + outer loop + vertex 1.00736 1.14515 2.61593 + vertex 1.00767 1.14823 2.61629 + vertex 1.00418 1.14471 2.61623 + endloop + endfacet + facet normal 0.114138 -0.157746 0.980861 + outer loop + vertex 1.00736 1.14515 2.61593 + vertex 1.00418 1.14471 2.61623 + vertex 1.00523 1.14247 2.61574 + endloop + endfacet + facet normal 0.186099 -0.213387 0.959079 + outer loop + vertex 1.00905 1.1434 2.61521 + vertex 1.00736 1.14515 2.61593 + vertex 1.00523 1.14247 2.61574 + endloop + endfacet + facet normal 0.18567 -0.211323 0.959619 + outer loop + vertex 1.00523 1.14247 2.61574 + vertex 1.0036 1.1384 2.61516 + vertex 1.00905 1.1434 2.61521 + endloop + endfacet + facet normal 0.141962 -0.163866 0.976214 + outer loop + vertex 1.00905 1.1434 2.61521 + vertex 1.0036 1.1384 2.61516 + vertex 1.0087 1.13837 2.61442 + endloop + endfacet + facet normal 0.141906 -0.165711 0.975911 + outer loop + vertex 1.00348 1.13326 2.61431 + vertex 1.0087 1.13837 2.61442 + vertex 1.0036 1.1384 2.61516 + endloop + endfacet + facet normal 0.0851431 -0.165546 0.98252 + outer loop + vertex 1.00348 1.13326 2.61431 + vertex 1.0036 1.1384 2.61516 + vertex 0.998434 1.13314 2.61473 + endloop + endfacet + facet normal 0.0851421 -0.165452 0.982536 + outer loop + vertex 0.998318 1.12815 2.6139 + vertex 1.00348 1.13326 2.61431 + vertex 0.998434 1.13314 2.61473 + endloop + endfacet + facet normal 0.0647407 -0.165241 0.984126 + outer loop + vertex 0.998318 1.12815 2.6139 + vertex 0.998434 1.13314 2.61473 + vertex 0.99333 1.12823 2.61424 + endloop + endfacet + facet normal 0.0646041 -0.170224 0.983285 + outer loop + vertex 0.993251 1.12309 2.61335 + vertex 0.998318 1.12815 2.6139 + vertex 0.99333 1.12823 2.61424 + endloop + endfacet + facet normal 0.061572 -0.170212 0.983482 + outer loop + vertex 0.993251 1.12309 2.61335 + vertex 0.99333 1.12823 2.61424 + vertex 0.988275 1.12318 2.61368 + endloop + endfacet + facet normal 0.0614125 -0.175939 0.982484 + outer loop + vertex 0.988356 1.11812 2.61277 + vertex 0.993251 1.12309 2.61335 + vertex 0.988275 1.12318 2.61368 + endloop + endfacet + facet normal 0.0614802 -0.175937 0.98248 + outer loop + vertex 0.988356 1.11812 2.61277 + vertex 0.988275 1.12318 2.61368 + vertex 0.983291 1.11813 2.61309 + endloop + endfacet + facet normal 0.0614359 -0.179543 0.98183 + outer loop + vertex 0.983738 1.11332 2.61218 + vertex 0.988356 1.11812 2.61277 + vertex 0.983291 1.11813 2.61309 + endloop + endfacet + facet normal 0.0619853 -0.180055 0.981702 + outer loop + vertex 0.988969 1.11358 2.6119 + vertex 0.988356 1.11812 2.61277 + vertex 0.983738 1.11332 2.61218 + endloop + endfacet + facet normal 0.0619424 -0.178975 0.981902 + outer loop + vertex 0.984916 1.1094 2.61139 + vertex 0.988969 1.11358 2.6119 + vertex 0.983738 1.11332 2.61218 + endloop + endfacet + facet normal 0.0602458 -0.179487 0.981914 + outer loop + vertex 0.984916 1.1094 2.61139 + vertex 0.983738 1.11332 2.61218 + vertex 0.979317 1.1084 2.61155 + endloop + endfacet + facet normal 0.0598118 -0.176977 0.982396 + outer loop + vertex 0.984916 1.1094 2.61139 + vertex 0.979317 1.1084 2.61155 + vertex 0.981733 1.10551 2.61088 + endloop + endfacet + facet normal 0.0614957 -0.178311 0.982051 + outer loop + vertex 0.986398 1.10632 2.61074 + vertex 0.984916 1.1094 2.61139 + vertex 0.981733 1.10551 2.61088 + endloop + endfacet + facet normal 0.0614774 -0.1782 0.982072 + outer loop + vertex 0.981733 1.10551 2.61088 + vertex 0.98291 1.10232 2.61023 + vertex 0.986398 1.10632 2.61074 + endloop + endfacet + facet normal 0.065551 -0.18164 0.981178 + outer loop + vertex 0.98291 1.10232 2.61023 + vertex 0.988438 1.10334 2.61005 + vertex 0.986398 1.10632 2.61074 + endloop + endfacet + facet normal 0.0658504 -0.181439 0.981195 + outer loop + vertex 0.990296 1.10732 2.61066 + vertex 0.986398 1.10632 2.61074 + vertex 0.988438 1.10334 2.61005 + endloop + endfacet + facet normal 0.0708416 -0.183654 0.980435 + outer loop + vertex 0.990296 1.10732 2.61066 + vertex 0.988438 1.10334 2.61005 + vertex 0.993555 1.10716 2.6104 + endloop + endfacet + facet normal 0.0709139 -0.182527 0.98064 + outer loop + vertex 0.993555 1.10716 2.6104 + vertex 0.992976 1.10972 2.61092 + vertex 0.990296 1.10732 2.61066 + endloop + endfacet + facet normal 0.0679013 -0.17926 0.981456 + outer loop + vertex 0.992976 1.10972 2.61092 + vertex 0.989647 1.1099 2.61118 + vertex 0.990296 1.10732 2.61066 + endloop + endfacet + facet normal 0.0678134 -0.180596 0.981217 + outer loop + vertex 0.992976 1.10972 2.61092 + vertex 0.994322 1.11348 2.61151 + vertex 0.989647 1.1099 2.61118 + endloop + endfacet + facet normal 0.0668728 -0.179396 0.981501 + outer loop + vertex 0.994322 1.11348 2.61151 + vertex 0.988969 1.11358 2.6119 + vertex 0.989647 1.1099 2.61118 + endloop + endfacet + facet normal 0.0667693 -0.182676 0.980903 + outer loop + vertex 0.994322 1.11348 2.61151 + vertex 0.99356 1.11815 2.61244 + vertex 0.988969 1.11358 2.6119 + endloop + endfacet + facet normal 0.0700071 -0.182123 0.98078 + outer loop + vertex 0.994322 1.11348 2.61151 + vertex 0.998935 1.11835 2.61209 + vertex 0.99356 1.11815 2.61244 + endloop + endfacet + facet normal 0.0699648 -0.18045 0.981093 + outer loop + vertex 0.998935 1.11835 2.61209 + vertex 0.998395 1.12309 2.613 + vertex 0.99356 1.11815 2.61244 + endloop + endfacet + facet normal 0.0673834 -0.177995 0.981722 + outer loop + vertex 0.99356 1.11815 2.61244 + vertex 0.998395 1.12309 2.613 + vertex 0.993251 1.12309 2.61335 + endloop + endfacet + facet normal 0.0813972 -0.179026 0.980471 + outer loop + vertex 0.998935 1.11835 2.61209 + vertex 1.00368 1.12319 2.61258 + vertex 0.998395 1.12309 2.613 + endloop + endfacet + facet normal 0.0813477 -0.170836 0.981936 + outer loop + vertex 1.00368 1.12319 2.61258 + vertex 1.00339 1.12816 2.61347 + vertex 0.998395 1.12309 2.613 + endloop + endfacet + facet normal 0.0831468 -0.172567 0.981482 + outer loop + vertex 0.998395 1.12309 2.613 + vertex 1.00339 1.12816 2.61347 + vertex 0.998318 1.12815 2.6139 + endloop + endfacet + facet normal 0.112278 -0.16856 0.979276 + outer loop + vertex 1.00368 1.12319 2.61258 + vertex 1.00843 1.12822 2.6129 + vertex 1.00339 1.12816 2.61347 + endloop + endfacet + facet normal 0.112398 -0.150995 0.982124 + outer loop + vertex 1.00843 1.12822 2.6129 + vertex 1.00844 1.13325 2.61367 + vertex 1.00339 1.12816 2.61347 + endloop + endfacet + facet normal 0.125264 -0.163609 0.97854 + outer loop + vertex 1.00339 1.12816 2.61347 + vertex 1.00844 1.13325 2.61367 + vertex 1.00348 1.13326 2.61431 + endloop + endfacet + facet normal 0.171535 -0.149804 0.973722 + outer loop + vertex 1.00843 1.12822 2.6129 + vertex 1.01311 1.13308 2.61282 + vertex 1.00844 1.13325 2.61367 + endloop + endfacet + facet normal 0.173222 -0.122208 0.977271 + outer loop + vertex 1.01311 1.13308 2.61282 + vertex 1.01343 1.13823 2.61341 + vertex 1.00844 1.13325 2.61367 + endloop + endfacet + facet normal 0.201446 -0.150995 0.967791 + outer loop + vertex 1.00844 1.13325 2.61367 + vertex 1.01343 1.13823 2.61341 + vertex 1.0087 1.13837 2.61442 + endloop + endfacet + facet normal 0.149046 -0.128074 0.980501 + outer loop + vertex 1.01315 1.12821 2.61218 + vertex 1.01311 1.13308 2.61282 + vertex 1.00843 1.12822 2.6129 + endloop + endfacet + facet normal 0.09986 -0.157021 0.982534 + outer loop + vertex 1.0089 1.12348 2.61209 + vertex 1.00843 1.12822 2.6129 + vertex 1.00368 1.12319 2.61258 + endloop + endfacet + facet normal 0.100417 -0.171537 0.980047 + outer loop + vertex 1.00444 1.11837 2.61166 + vertex 1.0089 1.12348 2.61209 + vertex 1.00368 1.12319 2.61258 + endloop + endfacet + facet normal 0.0852753 -0.158629 0.983649 + outer loop + vertex 1.00979 1.1195 2.61138 + vertex 1.0089 1.12348 2.61209 + vertex 1.00444 1.11837 2.61166 + endloop + endfacet + facet normal 0.0875032 -0.16965 0.981612 + outer loop + vertex 1.00979 1.1195 2.61138 + vertex 1.00444 1.11837 2.61166 + vertex 1.00678 1.1155 2.61095 + endloop + endfacet + facet normal 0.0974159 -0.176877 0.9794 + outer loop + vertex 1.01107 1.11649 2.6107 + vertex 1.00979 1.1195 2.61138 + vertex 1.00678 1.1155 2.61095 + endloop + endfacet + facet normal 0.0992325 -0.185235 0.977671 + outer loop + vertex 1.00678 1.1155 2.61095 + vertex 1.00791 1.11232 2.61024 + vertex 1.01107 1.11649 2.6107 + endloop + endfacet + facet normal 0.13818 -0.213606 0.967098 + outer loop + vertex 1.00791 1.11232 2.61024 + vertex 1.01334 1.11373 2.60977 + vertex 1.01107 1.11649 2.6107 + endloop + endfacet + facet normal 0.131392 -0.185247 0.973868 + outer loop + vertex 1.00839 1.10814 2.60938 + vertex 1.01334 1.11373 2.60977 + vertex 1.00791 1.11232 2.61024 + endloop + endfacet + facet normal 0.0911147 -0.190582 0.977434 + outer loop + vertex 1.00839 1.10814 2.60938 + vertex 1.00791 1.11232 2.61024 + vertex 1.00349 1.10788 2.60978 + endloop + endfacet + facet normal 0.0909502 -0.186169 0.978299 + outer loop + vertex 1.00338 1.10314 2.60889 + vertex 1.00839 1.10814 2.60938 + vertex 1.00349 1.10788 2.60978 + endloop + endfacet + facet normal 0.076869 -0.186059 0.979527 + outer loop + vertex 1.00338 1.10314 2.60889 + vertex 1.00349 1.10788 2.60978 + vertex 0.998468 1.10318 2.60928 + endloop + endfacet + facet normal 0.0768485 -0.186936 0.979362 + outer loop + vertex 0.998356 1.09817 2.60833 + vertex 1.00338 1.10314 2.60889 + vertex 0.998468 1.10318 2.60928 + endloop + endfacet + facet normal 0.0744828 -0.186918 0.979548 + outer loop + vertex 0.998356 1.09817 2.60833 + vertex 0.998468 1.10318 2.60928 + vertex 0.99336 1.0982 2.60872 + endloop + endfacet + facet normal 0.0744383 -0.188946 0.979162 + outer loop + vertex 0.993553 1.0932 2.60774 + vertex 0.998356 1.09817 2.60833 + vertex 0.99336 1.0982 2.60872 + endloop + endfacet + facet normal 0.0715948 -0.189092 0.979346 + outer loop + vertex 0.993553 1.0932 2.60774 + vertex 0.99336 1.0982 2.60872 + vertex 0.988434 1.09321 2.60812 + endloop + endfacet + facet normal 0.0715516 -0.191501 0.978881 + outer loop + vertex 0.989048 1.08855 2.60716 + vertex 0.993553 1.0932 2.60774 + vertex 0.988434 1.09321 2.60812 + endloop + endfacet + facet normal 0.0658955 -0.192295 0.979122 + outer loop + vertex 0.989048 1.08855 2.60716 + vertex 0.988434 1.09321 2.60812 + vertex 0.983841 1.08834 2.60747 + endloop + endfacet + facet normal 0.0659645 -0.19474 0.978634 + outer loop + vertex 0.985077 1.08432 2.60659 + vertex 0.989048 1.08855 2.60716 + vertex 0.983841 1.08834 2.60747 + endloop + endfacet + facet normal 0.0605733 -0.1964 0.978651 + outer loop + vertex 0.985077 1.08432 2.60659 + vertex 0.983841 1.08834 2.60747 + vertex 0.979452 1.08336 2.60674 + endloop + endfacet + facet normal 0.0607382 -0.197401 0.97844 + outer loop + vertex 0.985077 1.08432 2.60659 + vertex 0.979452 1.08336 2.60674 + vertex 0.981915 1.0804 2.60599 + endloop + endfacet + facet normal 0.0602727 -0.197041 0.978541 + outer loop + vertex 0.986615 1.08118 2.60586 + vertex 0.985077 1.08432 2.60659 + vertex 0.981915 1.0804 2.60599 + endloop + endfacet + facet normal 0.0602983 -0.197201 0.978507 + outer loop + vertex 0.981915 1.0804 2.60599 + vertex 0.983098 1.0772 2.60528 + vertex 0.986615 1.08118 2.60586 + endloop + endfacet + facet normal 0.063021 -0.199514 0.977866 + outer loop + vertex 0.983098 1.0772 2.60528 + vertex 0.988613 1.07819 2.60512 + vertex 0.986615 1.08118 2.60586 + endloop + endfacet + facet normal 0.0644292 -0.198596 0.977961 + outer loop + vertex 0.990486 1.08212 2.6058 + vertex 0.986615 1.08118 2.60586 + vertex 0.988613 1.07819 2.60512 + endloop + endfacet + facet normal 0.0729222 -0.202412 0.976582 + outer loop + vertex 0.990486 1.08212 2.6058 + vertex 0.988613 1.07819 2.60512 + vertex 0.993557 1.08182 2.6055 + endloop + endfacet + facet normal 0.0634611 -0.194533 0.978841 + outer loop + vertex 0.990486 1.08212 2.6058 + vertex 0.989805 1.08475 2.60636 + vertex 0.986615 1.08118 2.60586 + endloop + endfacet + facet normal 0.0689638 -0.193094 0.978754 + outer loop + vertex 0.99309 1.08447 2.60608 + vertex 0.989805 1.08475 2.60636 + vertex 0.990486 1.08212 2.6058 + endloop + endfacet + facet normal 0.0734487 -0.197892 0.977468 + outer loop + vertex 0.993557 1.08182 2.6055 + vertex 0.99309 1.08447 2.60608 + vertex 0.990486 1.08212 2.6058 + endloop + endfacet + facet normal 0.0795445 -0.196769 0.977218 + outer loop + vertex 0.99309 1.08447 2.60608 + vertex 0.993557 1.08182 2.6055 + vertex 0.996764 1.08543 2.60597 + endloop + endfacet + facet normal 0.0693944 -0.188847 0.979551 + outer loop + vertex 0.99309 1.08447 2.60608 + vertex 0.994354 1.08834 2.60673 + vertex 0.989805 1.08475 2.60636 + endloop + endfacet + facet normal 0.0714841 -0.191429 0.9789 + outer loop + vertex 0.994354 1.08834 2.60673 + vertex 0.989048 1.08855 2.60716 + vertex 0.989805 1.08475 2.60636 + endloop + endfacet + facet normal 0.0782088 -0.191527 0.978366 + outer loop + vertex 0.996764 1.08543 2.60597 + vertex 0.994354 1.08834 2.60673 + vertex 0.99309 1.08447 2.60608 + endloop + endfacet + facet normal 0.0785792 -0.191228 0.978395 + outer loop + vertex 0.999897 1.08942 2.6065 + vertex 0.994354 1.08834 2.60673 + vertex 0.996764 1.08543 2.60597 + endloop + endfacet + facet normal 0.0818992 -0.193737 0.977629 + outer loop + vertex 1.00132 1.0863 2.60576 + vertex 0.999897 1.08942 2.6065 + vertex 0.996764 1.08543 2.60597 + endloop + endfacet + facet normal 0.0822133 -0.195479 0.977256 + outer loop + vertex 0.996764 1.08543 2.60597 + vertex 0.997919 1.08224 2.60524 + vertex 1.00132 1.0863 2.60576 + endloop + endfacet + facet normal 0.0800764 -0.193757 0.977776 + outer loop + vertex 0.997919 1.08224 2.60524 + vertex 1.0033 1.08328 2.605 + vertex 1.00132 1.0863 2.60576 + endloop + endfacet + facet normal 0.0808759 -0.19324 0.977813 + outer loop + vertex 1.0051 1.08732 2.60565 + vertex 1.00132 1.0863 2.60576 + vertex 1.0033 1.08328 2.605 + endloop + endfacet + facet normal 0.0771832 -0.191688 0.978416 + outer loop + vertex 1.0051 1.08732 2.60565 + vertex 1.0033 1.08328 2.605 + vertex 1.00833 1.08717 2.60537 + endloop + endfacet + facet normal 0.0771358 -0.192417 0.978277 + outer loop + vertex 1.00833 1.08717 2.60537 + vertex 1.00776 1.08977 2.60592 + vertex 1.0051 1.08732 2.60565 + endloop + endfacet + facet normal 0.0785129 -0.193866 0.977881 + outer loop + vertex 1.00776 1.08977 2.60592 + vertex 1.00453 1.08995 2.60622 + vertex 1.0051 1.08732 2.60565 + endloop + endfacet + facet normal 0.0787668 -0.190386 0.978544 + outer loop + vertex 1.00776 1.08977 2.60592 + vertex 1.00921 1.09361 2.60655 + vertex 1.00453 1.08995 2.60622 + endloop + endfacet + facet normal 0.0817701 -0.19414 0.97756 + outer loop + vertex 1.00921 1.09361 2.60655 + vertex 1.00396 1.09367 2.607 + vertex 1.00453 1.08995 2.60622 + endloop + endfacet + facet normal 0.0815929 -0.194169 0.977569 + outer loop + vertex 1.00453 1.08995 2.60622 + vertex 1.00396 1.09367 2.607 + vertex 0.999897 1.08942 2.6065 + endloop + endfacet + facet normal 0.0801676 -0.192851 0.977948 + outer loop + vertex 0.999897 1.08942 2.6065 + vertex 1.00396 1.09367 2.607 + vertex 0.998763 1.09336 2.60737 + endloop + endfacet + facet normal 0.0801135 -0.191647 0.978189 + outer loop + vertex 1.00396 1.09367 2.607 + vertex 1.00344 1.0982 2.60793 + vertex 0.998763 1.09336 2.60737 + endloop + endfacet + facet normal 0.0784625 -0.190103 0.978624 + outer loop + vertex 0.998763 1.09336 2.60737 + vertex 1.00344 1.0982 2.60793 + vertex 0.998356 1.09817 2.60833 + endloop + endfacet + facet normal 0.0857379 -0.190934 0.977851 + outer loop + vertex 1.00396 1.09367 2.607 + vertex 1.00863 1.09829 2.6075 + vertex 1.00344 1.0982 2.60793 + endloop + endfacet + facet normal 0.0857374 -0.184748 0.979039 + outer loop + vertex 1.00863 1.09829 2.6075 + vertex 1.00842 1.10319 2.60844 + vertex 1.00344 1.0982 2.60793 + endloop + endfacet + facet normal 0.0893112 -0.188217 0.978058 + outer loop + vertex 1.00344 1.0982 2.60793 + vertex 1.00842 1.10319 2.60844 + vertex 1.00338 1.10314 2.60889 + endloop + endfacet + facet normal 0.111195 -0.183186 0.976769 + outer loop + vertex 1.00863 1.09829 2.6075 + vertex 1.01351 1.10324 2.60787 + vertex 1.00842 1.10319 2.60844 + endloop + endfacet + facet normal 0.111314 -0.169625 0.979202 + outer loop + vertex 1.01351 1.10324 2.60787 + vertex 1.01348 1.10835 2.60876 + vertex 1.00842 1.10319 2.60844 + endloop + endfacet + facet normal 0.125899 -0.183658 0.974894 + outer loop + vertex 1.00842 1.10319 2.60844 + vertex 1.01348 1.10835 2.60876 + vertex 1.00839 1.10814 2.60938 + endloop + endfacet + facet normal 0.167757 -0.167935 0.971419 + outer loop + vertex 1.01351 1.10324 2.60787 + vertex 1.01841 1.10821 2.60788 + vertex 1.01348 1.10835 2.60876 + endloop + endfacet + facet normal 0.16891 -0.146501 0.974683 + outer loop + vertex 1.01841 1.10821 2.60788 + vertex 1.01852 1.11354 2.60866 + vertex 1.01348 1.10835 2.60876 + endloop + endfacet + facet normal 0.199472 -0.176394 0.963896 + outer loop + vertex 1.01348 1.10835 2.60876 + vertex 1.01852 1.11354 2.60866 + vertex 1.01334 1.11373 2.60977 + endloop + endfacet + facet normal 0.200559 -0.161187 0.966331 + outer loop + vertex 1.0186 1.11906 2.60957 + vertex 1.01334 1.11373 2.60977 + vertex 1.01852 1.11354 2.60866 + endloop + endfacet + facet normal 0.139503 -0.140081 0.980263 + outer loop + vertex 1.01828 1.10322 2.60719 + vertex 1.01841 1.10821 2.60788 + vertex 1.01351 1.10324 2.60787 + endloop + endfacet + facet normal 0.138823 -0.165931 0.976317 + outer loop + vertex 1.0138 1.09856 2.60703 + vertex 1.01828 1.10322 2.60719 + vertex 1.01351 1.10324 2.60787 + endloop + endfacet + facet normal 0.117084 -0.145217 0.982448 + outer loop + vertex 1.01859 1.0988 2.6065 + vertex 1.01828 1.10322 2.60719 + vertex 1.0138 1.09856 2.60703 + endloop + endfacet + facet normal 0.117752 -0.166382 0.979005 + outer loop + vertex 1.01859 1.0988 2.6065 + vertex 1.0138 1.09856 2.60703 + vertex 1.01444 1.09485 2.60632 + endloop + endfacet + facet normal 0.105773 -0.153947 0.982401 + outer loop + vertex 1.01775 1.09524 2.60603 + vertex 1.01859 1.0988 2.6065 + vertex 1.01444 1.09485 2.60632 + endloop + endfacet + facet normal 0.108601 -0.181497 0.977376 + outer loop + vertex 1.01775 1.09524 2.60603 + vertex 1.01444 1.09485 2.60632 + vertex 1.01538 1.09249 2.60578 + endloop + endfacet + facet normal 0.158219 -0.222653 0.961973 + outer loop + vertex 1.01922 1.09331 2.60534 + vertex 1.01775 1.09524 2.60603 + vertex 1.01538 1.09249 2.60578 + endloop + endfacet + facet normal 0.158286 -0.223021 0.961877 + outer loop + vertex 1.01538 1.09249 2.60578 + vertex 1.01361 1.08836 2.60512 + vertex 1.01922 1.09331 2.60534 + endloop + endfacet + facet normal 0.130378 -0.191798 0.972736 + outer loop + vertex 1.01922 1.09331 2.60534 + vertex 1.01361 1.08836 2.60512 + vertex 1.01871 1.08831 2.60442 + endloop + endfacet + facet normal 0.130274 -0.194581 0.972197 + outer loop + vertex 1.01344 1.08323 2.60411 + vertex 1.01871 1.08831 2.60442 + vertex 1.01361 1.08836 2.60512 + endloop + endfacet + facet normal 0.0904638 -0.194187 0.976784 + outer loop + vertex 1.01344 1.08323 2.60411 + vertex 1.01361 1.08836 2.60512 + vertex 1.00837 1.0831 2.60456 + endloop + endfacet + facet normal 0.0904918 -0.198264 0.975962 + outer loop + vertex 1.0083 1.07819 2.60356 + vertex 1.01344 1.08323 2.60411 + vertex 1.00837 1.0831 2.60456 + endloop + endfacet + facet normal 0.0799381 -0.198294 0.976877 + outer loop + vertex 1.0083 1.07819 2.60356 + vertex 1.00837 1.0831 2.60456 + vertex 1.0033 1.07821 2.60398 + endloop + endfacet + facet normal 0.0798483 -0.202307 0.976061 + outer loop + vertex 1.00339 1.07329 2.60295 + vertex 1.0083 1.07819 2.60356 + vertex 1.0033 1.07821 2.60398 + endloop + endfacet + facet normal 0.0801677 -0.202296 0.976038 + outer loop + vertex 1.00339 1.07329 2.60295 + vertex 1.0033 1.07821 2.60398 + vertex 0.998374 1.07324 2.60335 + endloop + endfacet + facet normal 0.0801646 -0.202796 0.975934 + outer loop + vertex 0.998774 1.06852 2.60234 + vertex 1.00339 1.07329 2.60295 + vertex 0.998374 1.07324 2.60335 + endloop + endfacet + facet normal 0.0789831 -0.202912 0.976006 + outer loop + vertex 0.998774 1.06852 2.60234 + vertex 0.998374 1.07324 2.60335 + vertex 0.993615 1.06834 2.60272 + endloop + endfacet + facet normal 0.0789503 -0.201218 0.97636 + outer loop + vertex 0.994319 1.06357 2.60168 + vertex 0.998774 1.06852 2.60234 + vertex 0.993615 1.06834 2.60272 + endloop + endfacet + facet normal 0.0734076 -0.202091 0.976612 + outer loop + vertex 0.994319 1.06357 2.60168 + vertex 0.993615 1.06834 2.60272 + vertex 0.989051 1.06378 2.60212 + endloop + endfacet + facet normal 0.0734409 -0.201491 0.976733 + outer loop + vertex 0.994319 1.06357 2.60168 + vertex 0.989051 1.06378 2.60212 + vertex 0.989684 1.06004 2.6013 + endloop + endfacet + facet normal 0.0714153 -0.19891 0.977412 + outer loop + vertex 0.992941 1.05973 2.601 + vertex 0.994319 1.06357 2.60168 + vertex 0.989684 1.06004 2.6013 + endloop + endfacet + facet normal 0.0708048 -0.204333 0.976337 + outer loop + vertex 0.992941 1.05973 2.601 + vertex 0.989684 1.06004 2.6013 + vertex 0.990274 1.05736 2.6007 + endloop + endfacet + facet normal 0.0748963 -0.208788 0.975089 + outer loop + vertex 0.993356 1.05699 2.60038 + vertex 0.992941 1.05973 2.601 + vertex 0.990274 1.05736 2.6007 + endloop + endfacet + facet normal 0.0740235 -0.214976 0.97381 + outer loop + vertex 0.990274 1.05736 2.6007 + vertex 0.988383 1.05332 2.59995 + vertex 0.993356 1.05699 2.60038 + endloop + endfacet + facet normal 0.0734976 -0.214286 0.974002 + outer loop + vertex 0.993356 1.05699 2.60038 + vertex 0.988383 1.05332 2.59995 + vertex 0.993343 1.05299 2.5995 + endloop + endfacet + facet normal 0.0821943 -0.214169 0.973332 + outer loop + vertex 0.993343 1.05299 2.5995 + vertex 0.997768 1.05737 2.60009 + vertex 0.993356 1.05699 2.60038 + endloop + endfacet + facet normal 0.0818164 -0.208827 0.974524 + outer loop + vertex 0.993356 1.05699 2.60038 + vertex 0.997768 1.05737 2.60009 + vertex 0.996647 1.06064 2.60089 + endloop + endfacet + facet normal 0.0859264 -0.207406 0.974474 + outer loop + vertex 0.996647 1.06064 2.60089 + vertex 0.997768 1.05737 2.60009 + vertex 1.00122 1.0615 2.60067 + endloop + endfacet + facet normal 0.0852617 -0.203626 0.975329 + outer loop + vertex 1.00122 1.0615 2.60067 + vertex 0.999849 1.06463 2.60144 + vertex 0.996647 1.06064 2.60089 + endloop + endfacet + facet normal 0.0808163 -0.200205 0.976415 + outer loop + vertex 0.999849 1.06463 2.60144 + vertex 0.994319 1.06357 2.60168 + vertex 0.996647 1.06064 2.60089 + endloop + endfacet + facet normal 0.0861278 -0.203247 0.975332 + outer loop + vertex 1.00446 1.06518 2.60115 + vertex 0.999849 1.06463 2.60144 + vertex 1.00122 1.0615 2.60067 + endloop + endfacet + facet normal 0.0882972 -0.205078 0.974755 + outer loop + vertex 1.00502 1.06255 2.60054 + vertex 1.00446 1.06518 2.60115 + vertex 1.00122 1.0615 2.60067 + endloop + endfacet + facet normal 0.0886742 -0.20648 0.974424 + outer loop + vertex 1.00502 1.06255 2.60054 + vertex 1.00122 1.0615 2.60067 + vertex 1.00321 1.05842 2.59983 + endloop + endfacet + facet normal 0.0860543 -0.20541 0.974885 + outer loop + vertex 1.00502 1.06255 2.60054 + vertex 1.00321 1.05842 2.59983 + vertex 1.00821 1.06234 2.60022 + endloop + endfacet + facet normal 0.0861761 -0.203982 0.975174 + outer loop + vertex 1.00821 1.06234 2.60022 + vertex 1.00767 1.06502 2.60082 + vertex 1.00502 1.06255 2.60054 + endloop + endfacet + facet normal 0.0837683 -0.204493 0.975277 + outer loop + vertex 1.00767 1.06502 2.60082 + vertex 1.00821 1.06234 2.60022 + vertex 1.01135 1.06613 2.60074 + endloop + endfacet + facet normal 0.0847316 -0.20775 0.974505 + outer loop + vertex 1.01135 1.06613 2.60074 + vertex 1.00912 1.06879 2.6015 + vertex 1.00767 1.06502 2.60082 + endloop + endfacet + facet normal 0.0871811 -0.208617 0.974104 + outer loop + vertex 1.00767 1.06502 2.60082 + vertex 1.00912 1.06879 2.6015 + vertex 1.00446 1.06518 2.60115 + endloop + endfacet + facet normal 0.0851997 -0.206127 0.974809 + outer loop + vertex 1.00912 1.06879 2.6015 + vertex 1.0039 1.06883 2.60197 + vertex 1.00446 1.06518 2.60115 + endloop + endfacet + facet normal 0.085135 -0.20843 0.974325 + outer loop + vertex 1.00912 1.06879 2.6015 + vertex 1.00853 1.07338 2.60254 + vertex 1.0039 1.06883 2.60197 + endloop + endfacet + facet normal 0.0823935 -0.205739 0.975132 + outer loop + vertex 1.0039 1.06883 2.60197 + vertex 1.00853 1.07338 2.60254 + vertex 1.00339 1.07329 2.60295 + endloop + endfacet + facet normal 0.0872518 -0.20813 0.974202 + outer loop + vertex 1.00912 1.06879 2.6015 + vertex 1.0138 1.07363 2.60212 + vertex 1.00853 1.07338 2.60254 + endloop + endfacet + facet normal 0.08709 -0.202965 0.975305 + outer loop + vertex 1.0138 1.07363 2.60212 + vertex 1.01343 1.07825 2.60311 + vertex 1.00853 1.07338 2.60254 + endloop + endfacet + facet normal 0.0885563 -0.204386 0.974876 + outer loop + vertex 1.00853 1.07338 2.60254 + vertex 1.01343 1.07825 2.60311 + vertex 1.0083 1.07819 2.60356 + endloop + endfacet + facet normal 0.10645 -0.201078 0.973774 + outer loop + vertex 1.0138 1.07363 2.60212 + vertex 1.01858 1.07837 2.60257 + vertex 1.01343 1.07825 2.60311 + endloop + endfacet + facet normal 0.106425 -0.185202 0.976921 + outer loop + vertex 1.01858 1.07837 2.60257 + vertex 1.01849 1.08324 2.60351 + vertex 1.01343 1.07825 2.60311 + endloop + endfacet + facet normal 0.117203 -0.195878 0.973599 + outer loop + vertex 1.01343 1.07825 2.60311 + vertex 1.01849 1.08324 2.60351 + vertex 1.01344 1.08323 2.60411 + endloop + endfacet + facet normal 0.154561 -0.183127 0.970863 + outer loop + vertex 1.01858 1.07837 2.60257 + vertex 1.02341 1.08319 2.60272 + vertex 1.01849 1.08324 2.60351 + endloop + endfacet + facet normal 0.155546 -0.157283 0.975227 + outer loop + vertex 1.02341 1.08319 2.60272 + vertex 1.02357 1.08828 2.60351 + vertex 1.01849 1.08324 2.60351 + endloop + endfacet + facet normal 0.180552 -0.182521 0.966482 + outer loop + vertex 1.01849 1.08324 2.60351 + vertex 1.02357 1.08828 2.60351 + vertex 1.01871 1.08831 2.60442 + endloop + endfacet + facet normal 0.128852 -0.157641 0.979054 + outer loop + vertex 1.02341 1.07855 2.60197 + vertex 1.02341 1.08319 2.60272 + vertex 1.01858 1.07837 2.60257 + endloop + endfacet + facet normal 0.12926 -0.186544 0.973906 + outer loop + vertex 1.0191 1.07374 2.60162 + vertex 1.02341 1.07855 2.60197 + vertex 1.01858 1.07837 2.60257 + endloop + endfacet + facet normal 0.111521 -0.171004 0.978939 + outer loop + vertex 1.02401 1.07503 2.60128 + vertex 1.02341 1.07855 2.60197 + vertex 1.0191 1.07374 2.60162 + endloop + endfacet + facet normal 0.115852 -0.188429 0.97523 + outer loop + vertex 1.02401 1.07503 2.60128 + vertex 1.0191 1.07374 2.60162 + vertex 1.02139 1.07121 2.60086 + endloop + endfacet + facet normal 0.141245 -0.205073 0.968501 + outer loop + vertex 1.02509 1.07281 2.60066 + vertex 1.02401 1.07503 2.60128 + vertex 1.02139 1.07121 2.60086 + endloop + endfacet + facet normal 0.14674 -0.218245 0.964799 + outer loop + vertex 1.02509 1.07281 2.60066 + vertex 1.02139 1.07121 2.60086 + vertex 1.02351 1.06857 2.59994 + endloop + endfacet + facet normal 0.239756 -0.248559 0.938475 + outer loop + vertex 1.02509 1.07281 2.60066 + vertex 1.02351 1.06857 2.59994 + vertex 1.02882 1.0737 2.59994 + endloop + endfacet + facet normal 0.186019 -0.192893 0.963426 + outer loop + vertex 1.02882 1.0737 2.59994 + vertex 1.02351 1.06857 2.59994 + vertex 1.02856 1.06846 2.59894 + endloop + endfacet + facet normal 0.185492 -0.201878 0.961685 + outer loop + vertex 1.02352 1.06332 2.59883 + vertex 1.02856 1.06846 2.59894 + vertex 1.02351 1.06857 2.59994 + endloop + endfacet + facet normal 0.122521 -0.204036 0.971266 + outer loop + vertex 1.02352 1.06332 2.59883 + vertex 1.02351 1.06857 2.59994 + vertex 1.01841 1.06316 2.59945 + endloop + endfacet + facet normal 0.12253 -0.205911 0.970869 + outer loop + vertex 1.01851 1.05827 2.59839 + vertex 1.02352 1.06332 2.59883 + vertex 1.01841 1.06316 2.59945 + endloop + endfacet + facet normal 0.0954374 -0.207032 0.973668 + outer loop + vertex 1.01851 1.05827 2.59839 + vertex 1.01841 1.06316 2.59945 + vertex 1.01336 1.05825 2.59889 + endloop + endfacet + facet normal 0.0953647 -0.211374 0.972742 + outer loop + vertex 1.0136 1.05335 2.59781 + vertex 1.01851 1.05827 2.59839 + vertex 1.01336 1.05825 2.59889 + endloop + endfacet + facet normal 0.0882944 -0.211845 0.973307 + outer loop + vertex 1.0136 1.05335 2.59781 + vertex 1.01336 1.05825 2.59889 + vertex 1.00839 1.0533 2.59827 + endloop + endfacet + facet normal 0.0882635 -0.214876 0.972645 + outer loop + vertex 1.0088 1.04862 2.5972 + vertex 1.0136 1.05335 2.59781 + vertex 1.00839 1.0533 2.59827 + endloop + endfacet + facet normal 0.0871205 -0.214994 0.972722 + outer loop + vertex 1.0088 1.04862 2.5972 + vertex 1.00839 1.0533 2.59827 + vertex 1.00355 1.04845 2.59763 + endloop + endfacet + facet normal 0.0871487 -0.216952 0.972284 + outer loop + vertex 1.00413 1.04382 2.59654 + vertex 1.0088 1.04862 2.5972 + vertex 1.00355 1.04845 2.59763 + endloop + endfacet + facet normal 0.0847119 -0.217289 0.972424 + outer loop + vertex 1.00413 1.04382 2.59654 + vertex 1.00355 1.04845 2.59763 + vertex 0.998986 1.04398 2.59703 + endloop + endfacet + facet normal 0.0846541 -0.218413 0.972178 + outer loop + vertex 1.00413 1.04382 2.59654 + vertex 0.998986 1.04398 2.59703 + vertex 0.999466 1.04028 2.59616 + endloop + endfacet + facet normal 0.0845371 -0.218264 0.972221 + outer loop + vertex 1.00267 1.04004 2.59582 + vertex 1.00413 1.04382 2.59654 + vertex 0.999466 1.04028 2.59616 + endloop + endfacet + facet normal 0.0842597 -0.221101 0.971604 + outer loop + vertex 1.00267 1.04004 2.59582 + vertex 0.999466 1.04028 2.59616 + vertex 0.999995 1.03761 2.5955 + endloop + endfacet + facet normal 0.0873524 -0.224364 0.970583 + outer loop + vertex 1.00323 1.03737 2.59516 + vertex 1.00267 1.04004 2.59582 + vertex 0.999995 1.03761 2.5955 + endloop + endfacet + facet normal 0.0872251 -0.225676 0.97029 + outer loop + vertex 0.999995 1.03761 2.5955 + vertex 0.998199 1.0335 2.59471 + vertex 1.00323 1.03737 2.59516 + endloop + endfacet + facet normal 0.0866113 -0.224906 0.970523 + outer loop + vertex 1.00323 1.03737 2.59516 + vertex 0.998199 1.0335 2.59471 + vertex 1.0034 1.03326 2.59419 + endloop + endfacet + facet normal 0.0910452 -0.224638 0.97018 + outer loop + vertex 1.0034 1.03326 2.59419 + vertex 1.0084 1.03831 2.59489 + vertex 1.00323 1.03737 2.59516 + endloop + endfacet + facet normal 0.0910743 -0.224812 0.970137 + outer loop + vertex 1.00323 1.03737 2.59516 + vertex 1.0084 1.03831 2.59489 + vertex 1.00638 1.04113 2.59573 + endloop + endfacet + facet normal 0.0911233 -0.224712 0.970155 + outer loop + vertex 1.00849 1.03335 2.59373 + vertex 1.0084 1.03831 2.59489 + vertex 1.0034 1.03326 2.59419 + endloop + endfacet + facet normal 0.0911297 -0.223062 0.970535 + outer loop + vertex 1.00368 1.02842 2.59305 + vertex 1.00849 1.03335 2.59373 + vertex 1.0034 1.03326 2.59419 + endloop + endfacet + facet normal 0.0875341 -0.223329 0.970805 + outer loop + vertex 1.00368 1.02842 2.59305 + vertex 1.0034 1.03326 2.59419 + vertex 0.998472 1.02841 2.59352 + endloop + endfacet + facet normal 0.0875663 -0.221535 0.971213 + outer loop + vertex 0.998941 1.02366 2.59239 + vertex 1.00368 1.02842 2.59305 + vertex 0.998472 1.02841 2.59352 + endloop + endfacet + facet normal 0.0829604 -0.222058 0.971498 + outer loop + vertex 0.998941 1.02366 2.59239 + vertex 0.998472 1.02841 2.59352 + vertex 0.993682 1.02351 2.59281 + endloop + endfacet + facet normal 0.0829525 -0.221398 0.971649 + outer loop + vertex 0.994286 1.01882 2.59169 + vertex 0.998941 1.02366 2.59239 + vertex 0.993682 1.02351 2.59281 + endloop + endfacet + facet normal 0.0779926 -0.222097 0.9719 + outer loop + vertex 0.994286 1.01882 2.59169 + vertex 0.993682 1.02351 2.59281 + vertex 0.989109 1.019 2.59214 + endloop + endfacet + facet normal 0.0779178 -0.223466 0.971592 + outer loop + vertex 0.994286 1.01882 2.59169 + vertex 0.989109 1.019 2.59214 + vertex 0.989567 1.01523 2.59124 + endloop + endfacet + facet normal 0.0782698 -0.223913 0.971461 + outer loop + vertex 0.992797 1.01499 2.59092 + vertex 0.994286 1.01882 2.59169 + vertex 0.989567 1.01523 2.59124 + endloop + endfacet + facet normal 0.0776013 -0.230789 0.969904 + outer loop + vertex 0.992797 1.01499 2.59092 + vertex 0.989567 1.01523 2.59124 + vertex 0.990063 1.0125 2.59055 + endloop + endfacet + facet normal 0.0825211 -0.235954 0.968254 + outer loop + vertex 0.993318 1.01229 2.59022 + vertex 0.992797 1.01499 2.59092 + vertex 0.990063 1.0125 2.59055 + endloop + endfacet + facet normal 0.0818098 -0.24383 0.966361 + outer loop + vertex 0.990063 1.0125 2.59055 + vertex 0.988224 1.00838 2.58966 + vertex 0.993318 1.01229 2.59022 + endloop + endfacet + facet normal 0.0782422 -0.239384 0.967767 + outer loop + vertex 0.993318 1.01229 2.59022 + vertex 0.988224 1.00838 2.58966 + vertex 0.993469 1.00822 2.5892 + endloop + endfacet + facet normal 0.0863964 -0.238934 0.967185 + outer loop + vertex 0.993469 1.00822 2.5892 + vertex 0.998494 1.01322 2.58999 + vertex 0.993318 1.01229 2.59022 + endloop + endfacet + facet normal 0.0857355 -0.234995 0.968208 + outer loop + vertex 0.993318 1.01229 2.59022 + vertex 0.998494 1.01322 2.58999 + vertex 0.996529 1.01607 2.59086 + endloop + endfacet + facet normal 0.0870768 -0.234101 0.968305 + outer loop + vertex 1.00029 1.01717 2.59078 + vertex 0.996529 1.01607 2.59086 + vertex 0.998494 1.01322 2.58999 + endloop + endfacet + facet normal 0.0904849 -0.235517 0.967649 + outer loop + vertex 1.00029 1.01717 2.59078 + vertex 0.998494 1.01322 2.58999 + vertex 1.00337 1.0169 2.59043 + endloop + endfacet + facet normal 0.0911934 -0.229331 0.969067 + outer loop + vertex 1.00337 1.0169 2.59043 + vertex 1.00294 1.01962 2.59111 + vertex 1.00029 1.01717 2.59078 + endloop + endfacet + facet normal 0.0870559 -0.225037 0.970453 + outer loop + vertex 1.00294 1.01962 2.59111 + vertex 0.999588 1.01978 2.59145 + vertex 1.00029 1.01717 2.59078 + endloop + endfacet + facet normal 0.0874102 -0.220133 0.971546 + outer loop + vertex 1.00294 1.01962 2.59111 + vertex 1.00435 1.02356 2.59188 + vertex 0.999588 1.01978 2.59145 + endloop + endfacet + facet normal 0.0881123 -0.220989 0.971288 + outer loop + vertex 1.00435 1.02356 2.59188 + vertex 0.998941 1.02366 2.59239 + vertex 0.999588 1.01978 2.59145 + endloop + endfacet + facet normal 0.0930932 -0.22198 0.970597 + outer loop + vertex 1.00666 1.02061 2.59098 + vertex 1.00435 1.02356 2.59188 + vertex 1.00294 1.01962 2.59111 + endloop + endfacet + facet normal 0.0941571 -0.221171 0.970679 + outer loop + vertex 1.00989 1.02468 2.5916 + vertex 1.00435 1.02356 2.59188 + vertex 1.00666 1.02061 2.59098 + endloop + endfacet + facet normal 0.0990367 -0.224848 0.969348 + outer loop + vertex 1.01122 1.0215 2.59072 + vertex 1.00989 1.02468 2.5916 + vertex 1.00666 1.02061 2.59098 + endloop + endfacet + facet normal 0.0996902 -0.228467 0.968434 + outer loop + vertex 1.00666 1.02061 2.59098 + vertex 1.00779 1.01734 2.5901 + vertex 1.01122 1.0215 2.59072 + endloop + endfacet + facet normal 0.101924 -0.230213 0.967788 + outer loop + vertex 1.00779 1.01734 2.5901 + vertex 1.01322 1.01845 2.58979 + vertex 1.01122 1.0215 2.59072 + endloop + endfacet + facet normal 0.10234 -0.232422 0.967216 + outer loop + vertex 1.00842 1.01322 2.58904 + vertex 1.01322 1.01845 2.58979 + vertex 1.00779 1.01734 2.5901 + endloop + endfacet + facet normal 0.0952103 -0.233633 0.967652 + outer loop + vertex 1.00842 1.01322 2.58904 + vertex 1.00779 1.01734 2.5901 + vertex 1.00343 1.01297 2.58947 + endloop + endfacet + facet normal 0.0952999 -0.236589 0.966925 + outer loop + vertex 1.00375 1.00837 2.58831 + vertex 1.00842 1.01322 2.58904 + vertex 1.00343 1.01297 2.58947 + endloop + endfacet + facet normal 0.0893002 -0.237115 0.967369 + outer loop + vertex 1.00375 1.00837 2.58831 + vertex 1.00343 1.01297 2.58947 + vertex 0.998607 1.00834 2.58878 + endloop + endfacet + facet normal 0.0892684 -0.239079 0.966888 + outer loop + vertex 0.999012 1.00367 2.58759 + vertex 1.00375 1.00837 2.58831 + vertex 0.998607 1.00834 2.58878 + endloop + endfacet + facet normal 0.0863031 -0.239385 0.967081 + outer loop + vertex 0.999012 1.00367 2.58759 + vertex 0.998607 1.00834 2.58878 + vertex 0.993755 1.00352 2.58802 + endloop + endfacet + facet normal 0.0862999 -0.239013 0.967174 + outer loop + vertex 0.99432 0.998802 2.5868 + vertex 0.999012 1.00367 2.58759 + vertex 0.993755 1.00352 2.58802 + endloop + endfacet + facet normal 0.0816442 -0.239635 0.967424 + outer loop + vertex 0.99432 0.998802 2.5868 + vertex 0.993755 1.00352 2.58802 + vertex 0.989107 0.998985 2.58729 + endloop + endfacet + facet normal 0.0818391 -0.236244 0.968241 + outer loop + vertex 0.99432 0.998802 2.5868 + vertex 0.989107 0.998985 2.58729 + vertex 0.989555 0.995151 2.58631 + endloop + endfacet + facet normal 0.0834962 -0.238319 0.967591 + outer loop + vertex 0.992815 0.994921 2.58598 + vertex 0.99432 0.998802 2.5868 + vertex 0.989555 0.995151 2.58631 + endloop + endfacet + facet normal 0.083171 -0.241735 0.966771 + outer loop + vertex 0.992815 0.994921 2.58598 + vertex 0.989555 0.995151 2.58631 + vertex 0.990061 0.992397 2.58558 + endloop + endfacet + facet normal 0.0873635 -0.246079 0.965304 + outer loop + vertex 0.993338 0.992218 2.58524 + vertex 0.992815 0.994921 2.58598 + vertex 0.990061 0.992397 2.58558 + endloop + endfacet + facet normal 0.0865618 -0.255987 0.962797 + outer loop + vertex 0.990061 0.992397 2.58558 + vertex 0.988248 0.988309 2.58466 + vertex 0.993338 0.992218 2.58524 + endloop + endfacet + facet normal 0.0789841 -0.246582 0.965898 + outer loop + vertex 0.993338 0.992218 2.58524 + vertex 0.988248 0.988309 2.58466 + vertex 0.993477 0.988194 2.5842 + endloop + endfacet + facet normal 0.0895148 -0.246019 0.965123 + outer loop + vertex 0.993477 0.988194 2.5842 + vertex 0.998526 0.993172 2.585 + vertex 0.993338 0.992218 2.58524 + endloop + endfacet + facet normal 0.0890576 -0.243353 0.96584 + outer loop + vertex 0.993338 0.992218 2.58524 + vertex 0.998526 0.993172 2.585 + vertex 0.996563 0.996036 2.5859 + endloop + endfacet + facet normal 0.0897174 -0.242917 0.965889 + outer loop + vertex 1.00033 0.997127 2.58583 + vertex 0.996563 0.996036 2.5859 + vertex 0.998526 0.993172 2.585 + endloop + endfacet + facet normal 0.0870797 -0.241823 0.966405 + outer loop + vertex 1.00033 0.997127 2.58583 + vertex 0.998526 0.993172 2.585 + vertex 1.00343 0.99682 2.58547 + endloop + endfacet + facet normal 0.0886672 -0.24387 0.965746 + outer loop + vertex 1.00343 0.99682 2.58547 + vertex 0.998526 0.993172 2.585 + vertex 1.00348 0.992929 2.58449 + endloop + endfacet + facet normal 0.0887122 -0.243268 0.965894 + outer loop + vertex 0.998624 0.988354 2.58378 + vertex 1.00348 0.992929 2.58449 + vertex 0.998526 0.993172 2.585 + endloop + endfacet + facet normal 0.0908137 -0.245386 0.965162 + outer loop + vertex 1.00377 0.988427 2.58331 + vertex 1.00348 0.992929 2.58449 + vertex 0.998624 0.988354 2.58378 + endloop + endfacet + facet normal 0.0908355 -0.242866 0.965798 + outer loop + vertex 0.999001 0.98374 2.58258 + vertex 1.00377 0.988427 2.58331 + vertex 0.998624 0.988354 2.58378 + endloop + endfacet + facet normal 0.0871848 -0.243227 0.966043 + outer loop + vertex 0.999001 0.98374 2.58258 + vertex 0.998624 0.988354 2.58378 + vertex 0.993724 0.98355 2.58301 + endloop + endfacet + facet normal 0.087142 -0.240475 0.966736 + outer loop + vertex 0.994232 0.978825 2.58179 + vertex 0.999001 0.98374 2.58258 + vertex 0.993724 0.98355 2.58301 + endloop + endfacet + facet normal 0.0744406 -0.242016 0.967412 + outer loop + vertex 0.994232 0.978825 2.58179 + vertex 0.993724 0.98355 2.58301 + vertex 0.989019 0.979078 2.58225 + endloop + endfacet + facet normal 0.0743964 -0.242645 0.967258 + outer loop + vertex 0.994232 0.978825 2.58179 + vertex 0.989019 0.979078 2.58225 + vertex 0.989403 0.975173 2.58125 + endloop + endfacet + facet normal 0.0695255 -0.236487 0.969144 + outer loop + vertex 0.992691 0.974858 2.58093 + vertex 0.994232 0.978825 2.58179 + vertex 0.989403 0.975173 2.58125 + endloop + endfacet + facet normal 0.067931 -0.249881 0.965891 + outer loop + vertex 0.992691 0.974858 2.58093 + vertex 0.989403 0.975173 2.58125 + vertex 0.989966 0.972342 2.58047 + endloop + endfacet + facet normal 0.0777893 -0.259937 0.962487 + outer loop + vertex 0.993309 0.972146 2.58015 + vertex 0.992691 0.974858 2.58093 + vertex 0.989966 0.972342 2.58047 + endloop + endfacet + facet normal 0.075973 -0.281194 0.956639 + outer loop + vertex 0.989966 0.972342 2.58047 + vertex 0.988401 0.968397 2.57944 + vertex 0.993309 0.972146 2.58015 + endloop + endfacet + facet normal 0.0603219 -0.261949 0.963195 + outer loop + vertex 0.993309 0.972146 2.58015 + vertex 0.988401 0.968397 2.57944 + vertex 0.993673 0.968212 2.57906 + endloop + endfacet + facet normal 0.0896764 -0.258831 0.961751 + outer loop + vertex 0.993673 0.968212 2.57906 + vertex 0.998509 0.973163 2.57994 + vertex 0.993309 0.972146 2.58015 + endloop + endfacet + facet normal 0.0888353 -0.254264 0.963046 + outer loop + vertex 0.993309 0.972146 2.58015 + vertex 0.998509 0.973163 2.57994 + vertex 0.996491 0.97602 2.58088 + endloop + endfacet + facet normal 0.0958959 -0.249466 0.963624 + outer loop + vertex 1.00029 0.977187 2.5808 + vertex 0.996491 0.97602 2.58088 + vertex 0.998509 0.973163 2.57994 + endloop + endfacet + facet normal 0.0971126 -0.24995 0.963376 + outer loop + vertex 1.00029 0.977187 2.5808 + vertex 0.998509 0.973163 2.57994 + vertex 1.00337 0.976906 2.58042 + endloop + endfacet + facet normal 0.0976079 -0.245877 0.964374 + outer loop + vertex 1.00337 0.976906 2.58042 + vertex 1.00295 0.979691 2.58117 + vertex 1.00029 0.977187 2.5808 + endloop + endfacet + facet normal 0.0961002 -0.24435 0.964913 + outer loop + vertex 1.00295 0.979691 2.58117 + vertex 0.999596 0.979852 2.58155 + vertex 1.00029 0.977187 2.5808 + endloop + endfacet + facet normal 0.0960516 -0.244994 0.964755 + outer loop + vertex 1.00295 0.979691 2.58117 + vertex 1.0044 0.983664 2.58204 + vertex 0.999596 0.979852 2.58155 + endloop + endfacet + facet normal 0.094132 -0.242674 0.96553 + outer loop + vertex 1.0044 0.983664 2.58204 + vertex 0.999001 0.98374 2.58258 + vertex 0.999596 0.979852 2.58155 + endloop + endfacet + facet normal 0.0977972 -0.245561 0.964435 + outer loop + vertex 1.00668 0.98066 2.58104 + vertex 1.0044 0.983664 2.58204 + vertex 1.00295 0.979691 2.58117 + endloop + endfacet + facet normal 0.098025 -0.245395 0.964455 + outer loop + vertex 1.00994 0.984745 2.58175 + vertex 1.0044 0.983664 2.58204 + vertex 1.00668 0.98066 2.58104 + endloop + endfacet + facet normal 0.0998769 -0.24678 0.963911 + outer loop + vertex 1.01124 0.98148 2.58078 + vertex 1.00994 0.984745 2.58175 + vertex 1.00668 0.98066 2.58104 + endloop + endfacet + facet normal 0.099734 -0.245909 0.964148 + outer loop + vertex 1.00668 0.98066 2.58104 + vertex 1.00778 0.97733 2.58008 + vertex 1.01124 0.98148 2.58078 + endloop + endfacet + facet normal 0.102535 -0.248095 0.963294 + outer loop + vertex 1.00778 0.97733 2.58008 + vertex 1.01326 0.978401 2.57977 + vertex 1.01124 0.98148 2.58078 + endloop + endfacet + facet normal 0.103605 -0.247412 0.963355 + outer loop + vertex 1.01503 0.982483 2.58063 + vertex 1.01124 0.98148 2.58078 + vertex 1.01326 0.978401 2.57977 + endloop + endfacet + facet normal 0.109457 -0.249686 0.962121 + outer loop + vertex 1.01503 0.982483 2.58063 + vertex 1.01326 0.978401 2.57977 + vertex 1.01824 0.982287 2.58021 + endloop + endfacet + facet normal 0.109619 -0.247948 0.962552 + outer loop + vertex 1.01824 0.982287 2.58021 + vertex 1.01768 0.984989 2.58097 + vertex 1.01503 0.982483 2.58063 + endloop + endfacet + facet normal 0.107199 -0.245504 0.96345 + outer loop + vertex 1.01768 0.984989 2.58097 + vertex 1.0145 0.985223 2.58139 + vertex 1.01503 0.982483 2.58063 + endloop + endfacet + facet normal 0.107262 -0.244903 0.963596 + outer loop + vertex 1.01768 0.984989 2.58097 + vertex 1.01916 0.988888 2.5818 + vertex 1.0145 0.985223 2.58139 + endloop + endfacet + facet normal 0.108436 -0.24634 0.963098 + outer loop + vertex 1.01916 0.988888 2.5818 + vertex 1.01404 0.989023 2.58241 + vertex 1.0145 0.985223 2.58139 + endloop + endfacet + facet normal 0.102702 -0.247142 0.963521 + outer loop + vertex 1.0145 0.985223 2.58139 + vertex 1.01404 0.989023 2.58241 + vertex 1.00994 0.984745 2.58175 + endloop + endfacet + facet normal 0.102294 -0.246771 0.96366 + outer loop + vertex 1.00994 0.984745 2.58175 + vertex 1.01404 0.989023 2.58241 + vertex 1.00896 0.988705 2.58287 + endloop + endfacet + facet normal 0.102381 -0.249012 0.963074 + outer loop + vertex 1.01404 0.989023 2.58241 + vertex 1.01359 0.99346 2.58361 + vertex 1.00896 0.988705 2.58287 + endloop + endfacet + facet normal 0.100744 -0.247505 0.963635 + outer loop + vertex 1.00896 0.988705 2.58287 + vertex 1.01359 0.99346 2.58361 + vertex 1.00849 0.993188 2.58407 + endloop + endfacet + facet normal 0.0960302 -0.248089 0.963966 + outer loop + vertex 1.00896 0.988705 2.58287 + vertex 1.00849 0.993188 2.58407 + vertex 1.00377 0.988427 2.58331 + endloop + endfacet + facet normal 0.0959532 -0.245636 0.964601 + outer loop + vertex 1.0044 0.983664 2.58204 + vertex 1.00896 0.988705 2.58287 + vertex 1.00377 0.988427 2.58331 + endloop + endfacet + facet normal 0.100792 -0.249133 0.96321 + outer loop + vertex 1.01359 0.99346 2.58361 + vertex 1.01337 0.99828 2.58487 + vertex 1.00849 0.993188 2.58407 + endloop + endfacet + facet normal 0.0977145 -0.246345 0.964244 + outer loop + vertex 1.00849 0.993188 2.58407 + vertex 1.01337 0.99828 2.58487 + vertex 1.00788 0.997217 2.58516 + endloop + endfacet + facet normal 0.0930101 -0.247124 0.96451 + outer loop + vertex 1.00849 0.993188 2.58407 + vertex 1.00788 0.997217 2.58516 + vertex 1.00348 0.992929 2.58449 + endloop + endfacet + facet normal 0.0979494 -0.247654 0.963884 + outer loop + vertex 1.00788 0.997217 2.58516 + vertex 1.01337 0.99828 2.58487 + vertex 1.01137 1.0013 2.58585 + endloop + endfacet + facet normal 0.091939 -0.24283 0.965702 + outer loop + vertex 1.00675 1.0005 2.58609 + vertex 1.00788 0.997217 2.58516 + vertex 1.01137 1.0013 2.58585 + endloop + endfacet + facet normal 0.0912888 -0.238771 0.966775 + outer loop + vertex 1.01137 1.0013 2.58585 + vertex 1.01002 1.00456 2.58679 + vertex 1.00675 1.0005 2.58609 + endloop + endfacet + facet normal 0.0902229 -0.237963 0.967075 + outer loop + vertex 1.01002 1.00456 2.58679 + vertex 1.00442 1.00353 2.58705 + vertex 1.00675 1.0005 2.58609 + endloop + endfacet + facet normal 0.0897552 -0.235253 0.967781 + outer loop + vertex 1.01002 1.00456 2.58679 + vertex 1.00896 1.00861 2.58787 + vertex 1.00442 1.00353 2.58705 + endloop + endfacet + facet normal 0.0928757 -0.23789 0.966842 + outer loop + vertex 1.00442 1.00353 2.58705 + vertex 1.00896 1.00861 2.58787 + vertex 1.00375 1.00837 2.58831 + endloop + endfacet + facet normal 0.0973933 -0.233189 0.967542 + outer loop + vertex 1.01002 1.00456 2.58679 + vertex 1.01411 1.00888 2.58742 + vertex 1.00896 1.00861 2.58787 + endloop + endfacet + facet normal 0.0973279 -0.231158 0.968036 + outer loop + vertex 1.01411 1.00888 2.58742 + vertex 1.01354 1.01346 2.58857 + vertex 1.00896 1.00861 2.58787 + endloop + endfacet + facet normal 0.0997697 -0.233349 0.967261 + outer loop + vertex 1.00896 1.00861 2.58787 + vertex 1.01354 1.01346 2.58857 + vertex 1.00842 1.01322 2.58904 + endloop + endfacet + facet normal 0.103153 -0.230334 0.967629 + outer loop + vertex 1.01411 1.00888 2.58742 + vertex 1.01866 1.01349 2.58803 + vertex 1.01354 1.01346 2.58857 + endloop + endfacet + facet normal 0.103185 -0.228573 0.968043 + outer loop + vertex 1.01866 1.01349 2.58803 + vertex 1.01833 1.01827 2.58919 + vertex 1.01354 1.01346 2.58857 + endloop + endfacet + facet normal 0.104379 -0.22971 0.967646 + outer loop + vertex 1.01354 1.01346 2.58857 + vertex 1.01833 1.01827 2.58919 + vertex 1.01322 1.01845 2.58979 + endloop + endfacet + facet normal 0.104555 -0.226851 0.968301 + outer loop + vertex 1.01814 1.02238 2.59018 + vertex 1.01322 1.01845 2.58979 + vertex 1.01833 1.01827 2.58919 + endloop + endfacet + facet normal 0.102968 -0.226958 0.968446 + outer loop + vertex 1.01833 1.01827 2.58919 + vertex 1.02324 1.02332 2.58985 + vertex 1.01814 1.02238 2.59018 + endloop + endfacet + facet normal 0.103243 -0.227214 0.968357 + outer loop + vertex 1.02343 1.01835 2.58867 + vertex 1.02324 1.02332 2.58985 + vertex 1.01833 1.01827 2.58919 + endloop + endfacet + facet normal 0.103998 -0.227167 0.968287 + outer loop + vertex 1.02343 1.01835 2.58867 + vertex 1.02837 1.02315 2.58926 + vertex 1.02324 1.02332 2.58985 + endloop + endfacet + facet normal 0.103771 -0.230963 0.967413 + outer loop + vertex 1.02819 1.02723 2.59026 + vertex 1.02324 1.02332 2.58985 + vertex 1.02837 1.02315 2.58926 + endloop + endfacet + facet normal 0.122057 -0.229703 0.965577 + outer loop + vertex 1.02837 1.02315 2.58926 + vertex 1.03349 1.02844 2.58988 + vertex 1.02819 1.02723 2.59026 + endloop + endfacet + facet normal 0.125397 -0.24562 0.961221 + outer loop + vertex 1.02819 1.02723 2.59026 + vertex 1.03349 1.02844 2.58988 + vertex 1.03135 1.03113 2.59084 + endloop + endfacet + facet normal 0.108524 -0.232754 0.966462 + outer loop + vertex 1.02761 1.02987 2.59096 + vertex 1.02819 1.02723 2.59026 + vertex 1.03135 1.03113 2.59084 + endloop + endfacet + facet normal 0.107083 -0.228369 0.967668 + outer loop + vertex 1.03135 1.03113 2.59084 + vertex 1.02908 1.03376 2.59171 + vertex 1.02761 1.02987 2.59096 + endloop + endfacet + facet normal 0.101269 -0.226379 0.968761 + outer loop + vertex 1.02761 1.02987 2.59096 + vertex 1.02908 1.03376 2.59171 + vertex 1.02429 1.02993 2.59132 + endloop + endfacet + facet normal 0.100934 -0.234351 0.966898 + outer loop + vertex 1.02761 1.02987 2.59096 + vertex 1.02429 1.02993 2.59132 + vertex 1.02495 1.02735 2.59062 + endloop + endfacet + facet normal 0.102744 -0.233865 0.966825 + outer loop + vertex 1.02495 1.02735 2.59062 + vertex 1.02429 1.02993 2.59132 + vertex 1.02125 1.02619 2.59074 + endloop + endfacet + facet normal 0.100944 -0.227943 0.968428 + outer loop + vertex 1.02495 1.02735 2.59062 + vertex 1.02125 1.02619 2.59074 + vertex 1.02324 1.02332 2.58985 + endloop + endfacet + facet normal 0.102909 -0.226612 0.968533 + outer loop + vertex 1.01814 1.02238 2.59018 + vertex 1.02324 1.02332 2.58985 + vertex 1.02125 1.02619 2.59074 + endloop + endfacet + facet normal 0.104361 -0.227734 0.968115 + outer loop + vertex 1.01761 1.02507 2.59087 + vertex 1.01814 1.02238 2.59018 + vertex 1.02125 1.02619 2.59074 + endloop + endfacet + facet normal 0.105609 -0.231913 0.966987 + outer loop + vertex 1.02125 1.02619 2.59074 + vertex 1.01908 1.02887 2.59162 + vertex 1.01761 1.02507 2.59087 + endloop + endfacet + facet normal 0.105716 -0.23195 0.966966 + outer loop + vertex 1.01761 1.02507 2.59087 + vertex 1.01908 1.02887 2.59162 + vertex 1.01445 1.02524 2.59125 + endloop + endfacet + facet normal 0.106114 -0.226993 0.968098 + outer loop + vertex 1.01761 1.02507 2.59087 + vertex 1.01445 1.02524 2.59125 + vertex 1.01498 1.02257 2.59057 + endloop + endfacet + facet normal 0.104523 -0.227331 0.968192 + outer loop + vertex 1.01498 1.02257 2.59057 + vertex 1.01445 1.02524 2.59125 + vertex 1.01122 1.0215 2.59072 + endloop + endfacet + facet normal 0.104804 -0.228362 0.967919 + outer loop + vertex 1.01498 1.02257 2.59057 + vertex 1.01122 1.0215 2.59072 + vertex 1.01322 1.01845 2.58979 + endloop + endfacet + facet normal 0.106274 -0.228932 0.967624 + outer loop + vertex 1.01498 1.02257 2.59057 + vertex 1.01322 1.01845 2.58979 + vertex 1.01814 1.02238 2.59018 + endloop + endfacet + facet normal 0.106417 -0.227299 0.967993 + outer loop + vertex 1.01814 1.02238 2.59018 + vertex 1.01761 1.02507 2.59087 + vertex 1.01498 1.02257 2.59057 + endloop + endfacet + facet normal 0.10293 -0.234008 0.966771 + outer loop + vertex 1.02429 1.02993 2.59132 + vertex 1.01908 1.02887 2.59162 + vertex 1.02125 1.02619 2.59074 + endloop + endfacet + facet normal 0.102953 -0.234132 0.966738 + outer loop + vertex 1.02429 1.02993 2.59132 + vertex 1.02376 1.03369 2.59228 + vertex 1.01908 1.02887 2.59162 + endloop + endfacet + facet normal 0.100836 -0.232167 0.967435 + outer loop + vertex 1.01908 1.02887 2.59162 + vertex 1.02376 1.03369 2.59228 + vertex 1.01857 1.03347 2.59277 + endloop + endfacet + facet normal 0.101277 -0.23211 0.967403 + outer loop + vertex 1.01908 1.02887 2.59162 + vertex 1.01857 1.03347 2.59277 + vertex 1.01396 1.02895 2.59217 + endloop + endfacet + facet normal 0.10149 -0.226745 0.968652 + outer loop + vertex 1.01908 1.02887 2.59162 + vertex 1.01396 1.02895 2.59217 + vertex 1.01445 1.02524 2.59125 + endloop + endfacet + facet normal 0.100953 -0.226825 0.968689 + outer loop + vertex 1.01445 1.02524 2.59125 + vertex 1.01396 1.02895 2.59217 + vertex 1.00989 1.02468 2.5916 + endloop + endfacet + facet normal 0.0966128 -0.222872 0.970048 + outer loop + vertex 1.00989 1.02468 2.5916 + vertex 1.01396 1.02895 2.59217 + vertex 1.00888 1.02863 2.5926 + endloop + endfacet + facet normal 0.096781 -0.226914 0.969094 + outer loop + vertex 1.01396 1.02895 2.59217 + vertex 1.01351 1.03339 2.59326 + vertex 1.00888 1.02863 2.5926 + endloop + endfacet + facet normal 0.0936259 -0.223982 0.970086 + outer loop + vertex 1.00888 1.02863 2.5926 + vertex 1.01351 1.03339 2.59326 + vertex 1.00849 1.03335 2.59373 + endloop + endfacet + facet normal 0.0936087 -0.225386 0.969762 + outer loop + vertex 1.01351 1.03339 2.59326 + vertex 1.01343 1.03813 2.59437 + vertex 1.00849 1.03335 2.59373 + endloop + endfacet + facet normal 0.0933551 -0.225396 0.969784 + outer loop + vertex 1.01351 1.03339 2.59326 + vertex 1.01841 1.03822 2.59391 + vertex 1.01343 1.03813 2.59437 + endloop + endfacet + facet normal 0.0933602 -0.22415 0.970072 + outer loop + vertex 1.01841 1.03822 2.59391 + vertex 1.01848 1.04315 2.59504 + vertex 1.01343 1.03813 2.59437 + endloop + endfacet + facet normal 0.0933424 -0.224133 0.970078 + outer loop + vertex 1.01343 1.03813 2.59437 + vertex 1.01848 1.04315 2.59504 + vertex 1.01339 1.04217 2.5953 + endloop + endfacet + facet normal 0.0928912 -0.224147 0.970118 + outer loop + vertex 1.01339 1.04217 2.5953 + vertex 1.0084 1.03831 2.59489 + vertex 1.01343 1.03813 2.59437 + endloop + endfacet + facet normal 0.093014 -0.222303 0.970531 + outer loop + vertex 1.01339 1.04217 2.5953 + vertex 1.01848 1.04315 2.59504 + vertex 1.01654 1.04596 2.59587 + endloop + endfacet + facet normal 0.0933689 -0.222583 0.970432 + outer loop + vertex 1.01282 1.0448 2.59596 + vertex 1.01339 1.04217 2.5953 + vertex 1.01654 1.04596 2.59587 + endloop + endfacet + facet normal 0.092633 -0.220185 0.97105 + outer loop + vertex 1.01654 1.04596 2.59587 + vertex 1.01423 1.04863 2.59669 + vertex 1.01282 1.0448 2.59596 + endloop + endfacet + facet normal 0.0929141 -0.21995 0.971076 + outer loop + vertex 1.01957 1.04972 2.59643 + vertex 1.01423 1.04863 2.59669 + vertex 1.01654 1.04596 2.59587 + endloop + endfacet + facet normal 0.0914597 -0.218837 0.971466 + outer loop + vertex 1.02029 1.04715 2.59578 + vertex 1.01957 1.04972 2.59643 + vertex 1.01654 1.04596 2.59587 + endloop + endfacet + facet normal 0.0933667 -0.218292 0.971407 + outer loop + vertex 1.02292 1.04969 2.5961 + vertex 1.01957 1.04972 2.59643 + vertex 1.02029 1.04715 2.59578 + endloop + endfacet + facet normal 0.0986044 -0.2235 0.969704 + outer loop + vertex 1.02348 1.04708 2.59544 + vertex 1.02292 1.04969 2.5961 + vertex 1.02029 1.04715 2.59578 + endloop + endfacet + facet normal 0.0985363 -0.225031 0.969356 + outer loop + vertex 1.02029 1.04715 2.59578 + vertex 1.01848 1.04315 2.59504 + vertex 1.02348 1.04708 2.59544 + endloop + endfacet + facet normal 0.0987656 -0.225314 0.969267 + outer loop + vertex 1.02348 1.04708 2.59544 + vertex 1.01848 1.04315 2.59504 + vertex 1.02349 1.04305 2.59451 + endloop + endfacet + facet normal 0.127463 -0.224472 0.966108 + outer loop + vertex 1.02349 1.04305 2.59451 + vertex 1.02865 1.04837 2.59506 + vertex 1.02348 1.04708 2.59544 + endloop + endfacet + facet normal 0.130566 -0.237961 0.962459 + outer loop + vertex 1.02348 1.04708 2.59544 + vertex 1.02865 1.04837 2.59506 + vertex 1.02658 1.05097 2.59599 + endloop + endfacet + facet normal 0.142187 -0.228893 0.963011 + outer loop + vertex 1.03031 1.05253 2.5958 + vertex 1.02658 1.05097 2.59599 + vertex 1.02865 1.04837 2.59506 + endloop + endfacet + facet normal 0.229985 -0.259465 0.937969 + outer loop + vertex 1.03031 1.05253 2.5958 + vertex 1.02865 1.04837 2.59506 + vertex 1.03405 1.05347 2.59515 + endloop + endfacet + facet normal 0.227498 -0.246804 0.941983 + outer loop + vertex 1.03405 1.05347 2.59515 + vertex 1.0324 1.05524 2.59601 + vertex 1.03031 1.05253 2.5958 + endloop + endfacet + facet normal 0.159105 -0.195987 0.967613 + outer loop + vertex 1.0324 1.05524 2.59601 + vertex 1.02927 1.0548 2.59644 + vertex 1.03031 1.05253 2.5958 + endloop + endfacet + facet normal 0.154646 -0.157582 0.975322 + outer loop + vertex 1.0324 1.05524 2.59601 + vertex 1.03269 1.05833 2.59646 + vertex 1.02927 1.0548 2.59644 + endloop + endfacet + facet normal 0.180147 -0.207016 0.961609 + outer loop + vertex 1.03405 1.05347 2.59515 + vertex 1.02865 1.04837 2.59506 + vertex 1.03367 1.0484 2.59413 + endloop + endfacet + facet normal 0.179763 -0.21836 0.959168 + outer loop + vertex 1.02853 1.04326 2.59392 + vertex 1.03367 1.0484 2.59413 + vertex 1.02865 1.04837 2.59506 + endloop + endfacet + facet normal 0.156162 -0.195152 0.968261 + outer loop + vertex 1.0335 1.04342 2.59315 + vertex 1.03367 1.0484 2.59413 + vertex 1.02853 1.04326 2.59392 + endloop + endfacet + facet normal 0.156146 -0.215102 0.964028 + outer loop + vertex 1.02861 1.03843 2.59283 + vertex 1.0335 1.04342 2.59315 + vertex 1.02853 1.04326 2.59392 + endloop + endfacet + facet normal 0.11455 -0.217015 0.969424 + outer loop + vertex 1.02861 1.03843 2.59283 + vertex 1.02853 1.04326 2.59392 + vertex 1.02346 1.03827 2.5934 + endloop + endfacet + facet normal 0.114611 -0.228247 0.966834 + outer loop + vertex 1.02376 1.03369 2.59228 + vertex 1.02861 1.03843 2.59283 + vertex 1.02346 1.03827 2.5934 + endloop + endfacet + facet normal 0.107276 -0.221034 0.969348 + outer loop + vertex 1.02908 1.03376 2.59171 + vertex 1.02861 1.03843 2.59283 + vertex 1.02376 1.03369 2.59228 + endloop + endfacet + facet normal 0.135535 -0.217528 0.966598 + outer loop + vertex 1.02908 1.03376 2.59171 + vertex 1.03369 1.03881 2.5922 + vertex 1.02861 1.03843 2.59283 + endloop + endfacet + facet normal 0.115909 -0.200215 0.972871 + outer loop + vertex 1.03428 1.03508 2.59137 + vertex 1.03369 1.03881 2.5922 + vertex 1.02908 1.03376 2.59171 + endloop + endfacet + facet normal 0.134438 -0.194335 0.971679 + outer loop + vertex 1.03369 1.03881 2.5922 + vertex 1.0335 1.04342 2.59315 + vertex 1.02861 1.03843 2.59283 + endloop + endfacet + facet normal 0.133776 -0.207983 0.968941 + outer loop + vertex 1.03031 1.05253 2.5958 + vertex 1.02927 1.0548 2.59644 + vertex 1.02658 1.05097 2.59599 + endloop + endfacet + facet normal 0.1156 -0.195758 0.973815 + outer loop + vertex 1.02927 1.0548 2.59644 + vertex 1.02427 1.05359 2.59678 + vertex 1.02658 1.05097 2.59599 + endloop + endfacet + facet normal 0.103282 -0.206368 0.973008 + outer loop + vertex 1.02658 1.05097 2.59599 + vertex 1.02427 1.05359 2.59678 + vertex 1.02292 1.04969 2.5961 + endloop + endfacet + facet normal 0.110276 -0.172324 0.978848 + outer loop + vertex 1.02927 1.0548 2.59644 + vertex 1.02873 1.05852 2.59715 + vertex 1.02427 1.05359 2.59678 + endloop + endfacet + facet normal 0.13372 -0.192952 0.972054 + outer loop + vertex 1.02427 1.05359 2.59678 + vertex 1.02873 1.05852 2.59715 + vertex 1.02371 1.05835 2.59781 + endloop + endfacet + facet normal 0.101972 -0.197326 0.97502 + outer loop + vertex 1.02427 1.05359 2.59678 + vertex 1.02371 1.05835 2.59781 + vertex 1.01893 1.05356 2.59734 + endloop + endfacet + facet normal 0.10172 -0.212701 0.971808 + outer loop + vertex 1.02427 1.05359 2.59678 + vertex 1.01893 1.05356 2.59734 + vertex 1.01957 1.04972 2.59643 + endloop + endfacet + facet normal 0.112945 -0.207952 0.971596 + outer loop + vertex 1.01893 1.05356 2.59734 + vertex 1.02371 1.05835 2.59781 + vertex 1.01851 1.05827 2.59839 + endloop + endfacet + facet normal 0.133468 -0.1695 0.976451 + outer loop + vertex 1.02873 1.05852 2.59715 + vertex 1.02856 1.06332 2.59801 + vertex 1.02371 1.05835 2.59781 + endloop + endfacet + facet normal 0.158694 -0.19377 0.968127 + outer loop + vertex 1.02371 1.05835 2.59781 + vertex 1.02856 1.06332 2.59801 + vertex 1.02352 1.06332 2.59883 + endloop + endfacet + facet normal 0.161168 -0.163869 0.973228 + outer loop + vertex 1.03269 1.05833 2.59646 + vertex 1.02873 1.05852 2.59715 + vertex 1.02927 1.0548 2.59644 + endloop + endfacet + facet normal 0.121613 -0.219015 0.968113 + outer loop + vertex 1.02853 1.04326 2.59392 + vertex 1.02865 1.04837 2.59506 + vertex 1.02349 1.04305 2.59451 + endloop + endfacet + facet normal 0.121687 -0.224008 0.966961 + outer loop + vertex 1.02346 1.03827 2.5934 + vertex 1.02853 1.04326 2.59392 + vertex 1.02349 1.04305 2.59451 + endloop + endfacet + facet normal 0.0991534 -0.224436 0.969431 + outer loop + vertex 1.02346 1.03827 2.5934 + vertex 1.02349 1.04305 2.59451 + vertex 1.01841 1.03822 2.59391 + endloop + endfacet + facet normal 0.0991072 -0.227832 0.968644 + outer loop + vertex 1.01857 1.03347 2.59277 + vertex 1.02346 1.03827 2.5934 + vertex 1.01841 1.03822 2.59391 + endloop + endfacet + facet normal 0.108399 -0.221256 0.969172 + outer loop + vertex 1.02292 1.04969 2.5961 + vertex 1.02348 1.04708 2.59544 + vertex 1.02658 1.05097 2.59599 + endloop + endfacet + facet normal 0.0938383 -0.203356 0.974598 + outer loop + vertex 1.02292 1.04969 2.5961 + vertex 1.02427 1.05359 2.59678 + vertex 1.01957 1.04972 2.59643 + endloop + endfacet + facet normal 0.0918589 -0.214482 0.972399 + outer loop + vertex 1.01957 1.04972 2.59643 + vertex 1.01893 1.05356 2.59734 + vertex 1.01423 1.04863 2.59669 + endloop + endfacet + facet normal 0.0940686 -0.216502 0.97174 + outer loop + vertex 1.01423 1.04863 2.59669 + vertex 1.01893 1.05356 2.59734 + vertex 1.0136 1.05335 2.59781 + endloop + endfacet + facet normal 0.0926191 -0.222569 0.970507 + outer loop + vertex 1.02029 1.04715 2.59578 + vertex 1.01654 1.04596 2.59587 + vertex 1.01848 1.04315 2.59504 + endloop + endfacet + facet normal 0.0988203 -0.2241 0.969543 + outer loop + vertex 1.01841 1.03822 2.59391 + vertex 1.02349 1.04305 2.59451 + vertex 1.01848 1.04315 2.59504 + endloop + endfacet + facet normal 0.0960289 -0.227996 0.968915 + outer loop + vertex 1.01857 1.03347 2.59277 + vertex 1.01841 1.03822 2.59391 + vertex 1.01351 1.03339 2.59326 + endloop + endfacet + facet normal 0.0960366 -0.227003 0.969147 + outer loop + vertex 1.01396 1.02895 2.59217 + vertex 1.01857 1.03347 2.59277 + vertex 1.01351 1.03339 2.59326 + endloop + endfacet + facet normal 0.100783 -0.229467 0.968085 + outer loop + vertex 1.02376 1.03369 2.59228 + vertex 1.02346 1.03827 2.5934 + vertex 1.01857 1.03347 2.59277 + endloop + endfacet + facet normal 0.107136 -0.233474 0.966443 + outer loop + vertex 1.02908 1.03376 2.59171 + vertex 1.02376 1.03369 2.59228 + vertex 1.02429 1.02993 2.59132 + endloop + endfacet + facet normal 0.120033 -0.217528 0.968645 + outer loop + vertex 1.03428 1.03508 2.59137 + vertex 1.02908 1.03376 2.59171 + vertex 1.03135 1.03113 2.59084 + endloop + endfacet + facet normal 0.101079 -0.234497 0.966848 + outer loop + vertex 1.02819 1.02723 2.59026 + vertex 1.02761 1.02987 2.59096 + vertex 1.02495 1.02735 2.59062 + endloop + endfacet + facet normal 0.134399 -0.238658 0.961758 + outer loop + vertex 1.03521 1.03267 2.59068 + vertex 1.03135 1.03113 2.59084 + vertex 1.03349 1.02844 2.58988 + endloop + endfacet + facet normal 0.205654 -0.26401 0.94234 + outer loop + vertex 1.03521 1.03267 2.59068 + vertex 1.03349 1.02844 2.58988 + vertex 1.03903 1.03349 2.59008 + endloop + endfacet + facet normal 0.204086 -0.254612 0.945263 + outer loop + vertex 1.03903 1.03349 2.59008 + vertex 1.03755 1.0355 2.59094 + vertex 1.03521 1.03267 2.59068 + endloop + endfacet + facet normal 0.152624 -0.213892 0.964861 + outer loop + vertex 1.03755 1.0355 2.59094 + vertex 1.03428 1.03508 2.59137 + vertex 1.03521 1.03267 2.59068 + endloop + endfacet + facet normal 0.148852 -0.17576 0.973114 + outer loop + vertex 1.03755 1.0355 2.59094 + vertex 1.03839 1.03914 2.59147 + vertex 1.03428 1.03508 2.59137 + endloop + endfacet + facet normal 0.164379 -0.191363 0.967657 + outer loop + vertex 1.03839 1.03914 2.59147 + vertex 1.03369 1.03881 2.5922 + vertex 1.03428 1.03508 2.59137 + endloop + endfacet + facet normal 0.163355 -0.16627 0.972455 + outer loop + vertex 1.03839 1.03914 2.59147 + vertex 1.03813 1.04354 2.59227 + vertex 1.03369 1.03881 2.5922 + endloop + endfacet + facet normal 0.12857 -0.223527 0.966181 + outer loop + vertex 1.03521 1.03267 2.59068 + vertex 1.03428 1.03508 2.59137 + vertex 1.03135 1.03113 2.59084 + endloop + endfacet + facet normal 0.120265 -0.228042 0.966195 + outer loop + vertex 1.03356 1.02333 2.58866 + vertex 1.03349 1.02844 2.58988 + vertex 1.02837 1.02315 2.58926 + endloop + endfacet + facet normal 0.120264 -0.227911 0.966226 + outer loop + vertex 1.02865 1.01837 2.5881 + vertex 1.03356 1.02333 2.58866 + vertex 1.02837 1.02315 2.58926 + endloop + endfacet + facet normal 0.115033 -0.222931 0.968023 + outer loop + vertex 1.03392 1.01861 2.58753 + vertex 1.03356 1.02333 2.58866 + vertex 1.02865 1.01837 2.5881 + endloop + endfacet + facet normal 0.146771 -0.219635 0.964478 + outer loop + vertex 1.03392 1.01861 2.58753 + vertex 1.03867 1.02349 2.58792 + vertex 1.03356 1.02333 2.58866 + endloop + endfacet + facet normal 0.129921 -0.203707 0.970373 + outer loop + vertex 1.03913 1.01874 2.58686 + vertex 1.03867 1.02349 2.58792 + vertex 1.03392 1.01861 2.58753 + endloop + endfacet + facet normal 0.129896 -0.220045 0.966803 + outer loop + vertex 1.03913 1.01874 2.58686 + vertex 1.03392 1.01861 2.58753 + vertex 1.03452 1.01473 2.58657 + endloop + endfacet + facet normal 0.11581 -0.204266 0.972041 + outer loop + vertex 1.0378 1.01475 2.58618 + vertex 1.03913 1.01874 2.58686 + vertex 1.03452 1.01473 2.58657 + endloop + endfacet + facet normal 0.115289 -0.228303 0.96674 + outer loop + vertex 1.0378 1.01475 2.58618 + vertex 1.03452 1.01473 2.58657 + vertex 1.03523 1.01213 2.58587 + endloop + endfacet + facet normal 0.128602 -0.240841 0.962007 + outer loop + vertex 1.03839 1.01217 2.58545 + vertex 1.0378 1.01475 2.58618 + vertex 1.03523 1.01213 2.58587 + endloop + endfacet + facet normal 0.12842 -0.248801 0.960003 + outer loop + vertex 1.03523 1.01213 2.58587 + vertex 1.03349 1.00816 2.58507 + vertex 1.03839 1.01217 2.58545 + endloop + endfacet + facet normal 0.124753 -0.24447 0.961598 + outer loop + vertex 1.03839 1.01217 2.58545 + vertex 1.03349 1.00816 2.58507 + vertex 1.03854 1.00821 2.58443 + endloop + endfacet + facet normal 0.169644 -0.241152 0.955545 + outer loop + vertex 1.03854 1.00821 2.58443 + vertex 1.04349 1.01362 2.58491 + vertex 1.03839 1.01217 2.58545 + endloop + endfacet + facet normal 0.172266 -0.251556 0.952388 + outer loop + vertex 1.03839 1.01217 2.58545 + vertex 1.04349 1.01362 2.58491 + vertex 1.04136 1.01619 2.58598 + endloop + endfacet + facet normal 0.154279 -0.227619 0.961451 + outer loop + vertex 1.04362 1.00851 2.58368 + vertex 1.04349 1.01362 2.58491 + vertex 1.03854 1.00821 2.58443 + endloop + endfacet + facet normal 0.154515 -0.237365 0.959053 + outer loop + vertex 1.03875 1.00352 2.58324 + vertex 1.04362 1.00851 2.58368 + vertex 1.03854 1.00821 2.58443 + endloop + endfacet + facet normal 0.121093 -0.239916 0.963212 + outer loop + vertex 1.03875 1.00352 2.58324 + vertex 1.03854 1.00821 2.58443 + vertex 1.03358 1.00335 2.58384 + endloop + endfacet + facet normal 0.121121 -0.247764 0.961219 + outer loop + vertex 1.03391 0.998754 2.58262 + vertex 1.03875 1.00352 2.58324 + vertex 1.03358 1.00335 2.58384 + endloop + endfacet + facet normal 0.113342 -0.248526 0.961971 + outer loop + vertex 1.03391 0.998754 2.58262 + vertex 1.03358 1.00335 2.58384 + vertex 1.02866 0.99849 2.58317 + endloop + endfacet + facet normal 0.113406 -0.251353 0.961229 + outer loop + vertex 1.02917 0.993792 2.58188 + vertex 1.03391 0.998754 2.58262 + vertex 1.02866 0.99849 2.58317 + endloop + endfacet + facet normal 0.114885 -0.251158 0.961104 + outer loop + vertex 1.02917 0.993792 2.58188 + vertex 1.02866 0.99849 2.58317 + vertex 1.02384 0.993782 2.58251 + endloop + endfacet + facet normal 0.114956 -0.248691 0.961737 + outer loop + vertex 1.02917 0.993792 2.58188 + vertex 1.02384 0.993782 2.58251 + vertex 1.0244 0.989938 2.58145 + endloop + endfacet + facet normal 0.117107 -0.251254 0.960811 + outer loop + vertex 1.02774 0.989883 2.58103 + vertex 1.02917 0.993792 2.58188 + vertex 1.0244 0.989938 2.58145 + endloop + endfacet + facet normal 0.117274 -0.247812 0.961684 + outer loop + vertex 1.02774 0.989883 2.58103 + vertex 1.0244 0.989938 2.58145 + vertex 1.02512 0.987324 2.58069 + endloop + endfacet + facet normal 0.117892 -0.248416 0.961452 + outer loop + vertex 1.02834 0.987228 2.58027 + vertex 1.02774 0.989883 2.58103 + vertex 1.02512 0.987324 2.58069 + endloop + endfacet + facet normal 0.117887 -0.248504 0.96143 + outer loop + vertex 1.02512 0.987324 2.58069 + vertex 1.0234 0.983309 2.57986 + vertex 1.02834 0.987228 2.58027 + endloop + endfacet + facet normal 0.117559 -0.248105 0.961574 + outer loop + vertex 1.02834 0.987228 2.58027 + vertex 1.0234 0.983309 2.57986 + vertex 1.02848 0.98324 2.57922 + endloop + endfacet + facet normal 0.116401 -0.248178 0.961696 + outer loop + vertex 1.02848 0.98324 2.57922 + vertex 1.03346 0.988278 2.57992 + vertex 1.02834 0.987228 2.58027 + endloop + endfacet + facet normal 0.116336 -0.247825 0.961795 + outer loop + vertex 1.02834 0.987228 2.58027 + vertex 1.03346 0.988278 2.57992 + vertex 1.03144 0.991079 2.58089 + endloop + endfacet + facet normal 0.11504 -0.24873 0.961717 + outer loop + vertex 1.03517 0.992289 2.58075 + vertex 1.03144 0.991079 2.58089 + vertex 1.03346 0.988278 2.57992 + endloop + endfacet + facet normal 0.112158 -0.247624 0.962342 + outer loop + vertex 1.03517 0.992289 2.58075 + vertex 1.03346 0.988278 2.57992 + vertex 1.03839 0.992207 2.58036 + endloop + endfacet + facet normal 0.111865 -0.252767 0.961038 + outer loop + vertex 1.03839 0.992207 2.58036 + vertex 1.03782 0.994866 2.58112 + vertex 1.03517 0.992289 2.58075 + endloop + endfacet + facet normal 0.113829 -0.254676 0.960304 + outer loop + vertex 1.03782 0.994866 2.58112 + vertex 1.03447 0.994906 2.58153 + vertex 1.03517 0.992289 2.58075 + endloop + endfacet + facet normal 0.114013 -0.250426 0.961399 + outer loop + vertex 1.03782 0.994866 2.58112 + vertex 1.03927 0.998812 2.58198 + vertex 1.03447 0.994906 2.58153 + endloop + endfacet + facet normal 0.116766 -0.253672 0.960217 + outer loop + vertex 1.03927 0.998812 2.58198 + vertex 1.03391 0.998754 2.58262 + vertex 1.03447 0.994906 2.58153 + endloop + endfacet + facet normal 0.112857 -0.250052 0.961633 + outer loop + vertex 1.04152 0.996104 2.58101 + vertex 1.03927 0.998812 2.58198 + vertex 1.03782 0.994866 2.58112 + endloop + endfacet + facet normal 0.122303 -0.242471 0.962419 + outer loop + vertex 1.04448 0.999972 2.58161 + vertex 1.03927 0.998812 2.58198 + vertex 1.04152 0.996104 2.58101 + endloop + endfacet + facet normal 0.121714 -0.242049 0.962599 + outer loop + vertex 1.0452 0.997371 2.58086 + vertex 1.04448 0.999972 2.58161 + vertex 1.04152 0.996104 2.58101 + endloop + endfacet + facet normal 0.126747 -0.2572 0.95801 + outer loop + vertex 1.0452 0.997371 2.58086 + vertex 1.04152 0.996104 2.58101 + vertex 1.04349 0.993299 2.58 + endloop + endfacet + facet normal 0.166757 -0.271836 0.947786 + outer loop + vertex 1.0452 0.997371 2.58086 + vertex 1.04349 0.993299 2.58 + vertex 1.04829 0.997343 2.58031 + endloop + endfacet + facet normal 0.167472 -0.259351 0.951152 + outer loop + vertex 1.04829 0.997343 2.58031 + vertex 1.04766 0.999969 2.58114 + vertex 1.0452 0.997371 2.58086 + endloop + endfacet + facet normal 0.157177 -0.260851 0.952498 + outer loop + vertex 1.04829 0.997343 2.58031 + vertex 1.04349 0.993299 2.58 + vertex 1.04851 0.993289 2.57917 + endloop + endfacet + facet normal 0.220034 -0.254342 0.941751 + outer loop + vertex 1.04851 0.993289 2.57917 + vertex 1.05329 0.998732 2.57952 + vertex 1.04829 0.997343 2.58031 + endloop + endfacet + facet normal 0.221838 -0.262334 0.939132 + outer loop + vertex 1.04829 0.997343 2.58031 + vertex 1.05329 0.998732 2.57952 + vertex 1.05092 1.00126 2.58078 + endloop + endfacet + facet normal 0.19207 -0.230582 0.953908 + outer loop + vertex 1.05357 0.993514 2.5782 + vertex 1.05329 0.998732 2.57952 + vertex 1.04851 0.993289 2.57917 + endloop + endfacet + facet normal 0.192054 -0.237696 0.952164 + outer loop + vertex 1.04868 0.988575 2.57795 + vertex 1.05357 0.993514 2.5782 + vertex 1.04851 0.993289 2.57917 + endloop + endfacet + facet normal 0.147447 -0.241155 0.95922 + outer loop + vertex 1.04868 0.988575 2.57795 + vertex 1.04851 0.993289 2.57917 + vertex 1.0436 0.988434 2.5787 + endloop + endfacet + facet normal 0.147408 -0.245431 0.958141 + outer loop + vertex 1.04387 0.983862 2.57749 + vertex 1.04868 0.988575 2.57795 + vertex 1.0436 0.988434 2.5787 + endloop + endfacet + facet normal 0.13511 -0.233359 0.962958 + outer loop + vertex 1.04905 0.983923 2.57677 + vertex 1.04868 0.988575 2.57795 + vertex 1.04387 0.983862 2.57749 + endloop + endfacet + facet normal 0.134869 -0.244294 0.960277 + outer loop + vertex 1.04905 0.983923 2.57677 + vertex 1.04387 0.983862 2.57749 + vertex 1.04434 0.980047 2.57645 + endloop + endfacet + facet normal 0.123759 -0.231169 0.96501 + outer loop + vertex 1.04762 0.980002 2.57602 + vertex 1.04905 0.983923 2.57677 + vertex 1.04434 0.980047 2.57645 + endloop + endfacet + facet normal 0.12291 -0.24972 0.960486 + outer loop + vertex 1.04762 0.980002 2.57602 + vertex 1.04434 0.980047 2.57645 + vertex 1.04499 0.97742 2.57568 + endloop + endfacet + facet normal 0.13215 -0.258633 0.956893 + outer loop + vertex 1.0482 0.977338 2.57522 + vertex 1.04762 0.980002 2.57602 + vertex 1.04499 0.97742 2.57568 + endloop + endfacet + facet normal 0.131771 -0.264586 0.955317 + outer loop + vertex 1.04499 0.97742 2.57568 + vertex 1.04333 0.973394 2.5748 + vertex 1.0482 0.977338 2.57522 + endloop + endfacet + facet normal 0.129238 -0.261586 0.956489 + outer loop + vertex 1.0482 0.977338 2.57522 + vertex 1.04333 0.973394 2.5748 + vertex 1.0485 0.973307 2.57408 + endloop + endfacet + facet normal 0.152444 -0.259051 0.953757 + outer loop + vertex 1.0485 0.973307 2.57408 + vertex 1.05336 0.978591 2.57473 + vertex 1.0482 0.977338 2.57522 + endloop + endfacet + facet normal 0.152265 -0.258215 0.954013 + outer loop + vertex 1.0482 0.977338 2.57522 + vertex 1.05336 0.978591 2.57473 + vertex 1.05121 0.981299 2.57581 + endloop + endfacet + facet normal 0.141266 -0.249315 0.958064 + outer loop + vertex 1.05369 0.973498 2.57336 + vertex 1.05336 0.978591 2.57473 + vertex 1.0485 0.973307 2.57408 + endloop + endfacet + facet normal 0.141269 -0.256789 0.956087 + outer loop + vertex 1.04897 0.968715 2.57277 + vertex 1.05369 0.973498 2.57336 + vertex 1.0485 0.973307 2.57408 + endloop + endfacet + facet normal 0.129915 -0.258277 0.957296 + outer loop + vertex 1.04897 0.968715 2.57277 + vertex 1.0485 0.973307 2.57408 + vertex 1.04372 0.96853 2.57344 + endloop + endfacet + facet normal 0.129916 -0.258852 0.95714 + outer loop + vertex 1.04431 0.963766 2.57207 + vertex 1.04897 0.968715 2.57277 + vertex 1.04372 0.96853 2.57344 + endloop + endfacet + facet normal 0.125684 -0.259488 0.957533 + outer loop + vertex 1.04431 0.963766 2.57207 + vertex 1.04372 0.96853 2.57344 + vertex 1.03897 0.963799 2.57278 + endloop + endfacet + facet normal 0.12572 -0.258613 0.957765 + outer loop + vertex 1.04431 0.963766 2.57207 + vertex 1.03897 0.963799 2.57278 + vertex 1.03953 0.959887 2.57165 + endloop + endfacet + facet normal 0.127673 -0.26092 0.956881 + outer loop + vertex 1.04285 0.959816 2.57119 + vertex 1.04431 0.963766 2.57207 + vertex 1.03953 0.959887 2.57165 + endloop + endfacet + facet normal 0.127528 -0.263421 0.956215 + outer loop + vertex 1.04285 0.959816 2.57119 + vertex 1.03953 0.959887 2.57165 + vertex 1.0402 0.957246 2.57083 + endloop + endfacet + facet normal 0.1306 -0.266411 0.954971 + outer loop + vertex 1.0434 0.957174 2.57037 + vertex 1.04285 0.959816 2.57119 + vertex 1.0402 0.957246 2.57083 + endloop + endfacet + facet normal 0.130423 -0.269284 0.954189 + outer loop + vertex 1.0402 0.957246 2.57083 + vertex 1.03849 0.95327 2.56994 + vertex 1.0434 0.957174 2.57037 + endloop + endfacet + facet normal 0.129872 -0.268619 0.954451 + outer loop + vertex 1.0434 0.957174 2.57037 + vertex 1.03849 0.95327 2.56994 + vertex 1.04357 0.953279 2.56925 + endloop + endfacet + facet normal 0.130051 -0.268605 0.954431 + outer loop + vertex 1.04357 0.953279 2.56925 + vertex 1.04849 0.958266 2.56999 + vertex 1.0434 0.957174 2.57037 + endloop + endfacet + facet normal 0.129229 -0.264313 0.95574 + outer loop + vertex 1.0434 0.957174 2.57037 + vertex 1.04849 0.958266 2.56999 + vertex 1.04653 0.961028 2.57102 + endloop + endfacet + facet normal 0.130746 -0.263266 0.955822 + outer loop + vertex 1.05024 0.962247 2.57084 + vertex 1.04653 0.961028 2.57102 + vertex 1.04849 0.958266 2.56999 + endloop + endfacet + facet normal 0.126611 -0.26167 0.956817 + outer loop + vertex 1.05024 0.962247 2.57084 + vertex 1.04849 0.958266 2.56999 + vertex 1.05339 0.962163 2.5704 + endloop + endfacet + facet normal 0.12689 -0.257263 0.957974 + outer loop + vertex 1.05339 0.962163 2.5704 + vertex 1.05284 0.964798 2.57118 + vertex 1.05024 0.962247 2.57084 + endloop + endfacet + facet normal 0.130688 -0.260944 0.956467 + outer loop + vertex 1.05284 0.964798 2.57118 + vertex 1.04956 0.96485 2.57165 + vertex 1.05024 0.962247 2.57084 + endloop + endfacet + facet normal 0.131039 -0.254285 0.958211 + outer loop + vertex 1.05284 0.964798 2.57118 + vertex 1.05426 0.96871 2.57203 + vertex 1.04956 0.96485 2.57165 + endloop + endfacet + facet normal 0.134461 -0.258302 0.956661 + outer loop + vertex 1.05426 0.96871 2.57203 + vertex 1.04897 0.968715 2.57277 + vertex 1.04956 0.96485 2.57165 + endloop + endfacet + facet normal 0.126789 -0.252945 0.959137 + outer loop + vertex 1.05647 0.965998 2.57102 + vertex 1.05426 0.96871 2.57203 + vertex 1.05284 0.964798 2.57118 + endloop + endfacet + facet normal 0.133568 -0.247608 0.959609 + outer loop + vertex 1.05943 0.969832 2.5716 + vertex 1.05426 0.96871 2.57203 + vertex 1.05647 0.965998 2.57102 + endloop + endfacet + facet normal 0.123886 -0.240582 0.96269 + outer loop + vertex 1.06011 0.967234 2.57086 + vertex 1.05943 0.969832 2.5716 + vertex 1.05647 0.965998 2.57102 + endloop + endfacet + facet normal 0.126634 -0.24901 0.960186 + outer loop + vertex 1.06011 0.967234 2.57086 + vertex 1.05647 0.965998 2.57102 + vertex 1.05844 0.963228 2.57004 + endloop + endfacet + facet normal 0.136417 -0.252611 0.957903 + outer loop + vertex 1.06011 0.967234 2.57086 + vertex 1.05844 0.963228 2.57004 + vertex 1.06329 0.967256 2.57042 + endloop + endfacet + facet normal 0.136703 -0.242718 0.960417 + outer loop + vertex 1.06329 0.967256 2.57042 + vertex 1.06268 0.969853 2.57116 + vertex 1.06011 0.967234 2.57086 + endloop + endfacet + facet normal 0.153107 -0.238456 0.959008 + outer loop + vertex 1.06268 0.969853 2.57116 + vertex 1.06329 0.967256 2.57042 + vertex 1.06628 0.971278 2.57094 + endloop + endfacet + facet normal 0.146512 -0.220978 0.964211 + outer loop + vertex 1.06628 0.971278 2.57094 + vertex 1.06405 0.973831 2.57186 + vertex 1.06268 0.969853 2.57116 + endloop + endfacet + facet normal 0.132549 -0.216677 0.967203 + outer loop + vertex 1.06268 0.969853 2.57116 + vertex 1.06405 0.973831 2.57186 + vertex 1.05943 0.969832 2.5716 + endloop + endfacet + facet normal 0.160118 -0.209275 0.964659 + outer loop + vertex 1.06892 0.975245 2.57136 + vertex 1.06405 0.973831 2.57186 + vertex 1.06628 0.971278 2.57094 + endloop + endfacet + facet normal 0.15428 -0.187241 0.970123 + outer loop + vertex 1.06892 0.975245 2.57136 + vertex 1.06847 0.978923 2.57214 + vertex 1.06405 0.973831 2.57186 + endloop + endfacet + facet normal 0.177376 -0.206837 0.962162 + outer loop + vertex 1.06405 0.973831 2.57186 + vertex 1.06847 0.978923 2.57214 + vertex 1.0636 0.978586 2.57297 + endloop + endfacet + facet normal 0.147084 -0.210703 0.966421 + outer loop + vertex 1.06405 0.973831 2.57186 + vertex 1.0636 0.978586 2.57297 + vertex 1.05889 0.973714 2.57262 + endloop + endfacet + facet normal 0.176475 -0.180417 0.967629 + outer loop + vertex 1.06847 0.978923 2.57214 + vertex 1.06839 0.983631 2.57303 + vertex 1.0636 0.978586 2.57297 + endloop + endfacet + facet normal 0.198069 -0.200782 0.959404 + outer loop + vertex 1.0636 0.978586 2.57297 + vertex 1.06839 0.983631 2.57303 + vertex 1.06351 0.983588 2.57403 + endloop + endfacet + facet normal 0.198912 -0.172282 0.964755 + outer loop + vertex 1.06839 0.983631 2.57303 + vertex 1.06844 0.988668 2.57392 + vertex 1.06351 0.983588 2.57403 + endloop + endfacet + facet normal 0.218368 -0.191349 0.956923 + outer loop + vertex 1.06351 0.983588 2.57403 + vertex 1.06844 0.988668 2.57392 + vertex 1.06369 0.988921 2.57506 + endloop + endfacet + facet normal 0.220964 -0.163215 0.961528 + outer loop + vertex 1.06844 0.988668 2.57392 + vertex 1.06897 0.993766 2.57467 + vertex 1.06369 0.988921 2.57506 + endloop + endfacet + facet normal 0.243345 -0.188402 0.951466 + outer loop + vertex 1.06369 0.988921 2.57506 + vertex 1.06897 0.993766 2.57467 + vertex 1.06543 0.99411 2.57564 + endloop + endfacet + facet normal 0.246491 -0.16569 0.954876 + outer loop + vertex 1.06946 0.998621 2.57538 + vertex 1.06543 0.99411 2.57564 + vertex 1.06897 0.993766 2.57467 + endloop + endfacet + facet normal 0.265075 -0.182772 0.946747 + outer loop + vertex 1.06592 0.9973 2.57612 + vertex 1.06543 0.99411 2.57564 + vertex 1.06946 0.998621 2.57538 + endloop + endfacet + facet normal 0.265914 -0.185441 0.945992 + outer loop + vertex 1.06946 0.998621 2.57538 + vertex 1.06766 1.00022 2.5762 + vertex 1.06592 0.9973 2.57612 + endloop + endfacet + facet normal 0.229799 -0.164299 0.95927 + outer loop + vertex 1.06766 1.00022 2.5762 + vertex 1.06374 0.998833 2.5769 + vertex 1.06592 0.9973 2.57612 + endloop + endfacet + facet normal 0.223254 -0.173573 0.959182 + outer loop + vertex 1.06592 0.9973 2.57612 + vertex 1.06374 0.998833 2.5769 + vertex 1.06306 0.994921 2.57635 + endloop + endfacet + facet normal 0.220761 -0.135333 0.965893 + outer loop + vertex 1.06766 1.00022 2.5762 + vertex 1.06827 1.00398 2.57659 + vertex 1.06374 0.998833 2.5769 + endloop + endfacet + facet normal 0.248587 -0.160495 0.95522 + outer loop + vertex 1.06827 1.00398 2.57659 + vertex 1.06352 1.00379 2.57779 + vertex 1.06374 0.998833 2.5769 + endloop + endfacet + facet normal 0.248483 -0.115378 0.96174 + outer loop + vertex 1.06827 1.00398 2.57659 + vertex 1.06796 1.0086 2.57722 + vertex 1.06352 1.00379 2.57779 + endloop + endfacet + facet normal 0.227167 -0.178471 0.957363 + outer loop + vertex 1.06592 0.9973 2.57612 + vertex 1.06306 0.994921 2.57635 + vertex 1.06543 0.99411 2.57564 + endloop + endfacet + facet normal 0.170182 -0.250386 0.953071 + outer loop + vertex 1.06329 0.967256 2.57042 + vertex 1.06846 0.968685 2.56987 + vertex 1.06628 0.971278 2.57094 + endloop + endfacet + facet normal 0.167726 -0.240331 0.95609 + outer loop + vertex 1.06355 0.963256 2.56936 + vertex 1.06846 0.968685 2.56987 + vertex 1.06329 0.967256 2.57042 + endloop + endfacet + facet normal 0.15411 -0.22849 0.961271 + outer loop + vertex 1.06864 0.96358 2.56862 + vertex 1.06846 0.968685 2.56987 + vertex 1.06355 0.963256 2.56936 + endloop + endfacet + facet normal 0.129152 -0.24417 0.961094 + outer loop + vertex 1.06329 0.967256 2.57042 + vertex 1.05844 0.963228 2.57004 + vertex 1.06355 0.963256 2.56936 + endloop + endfacet + facet normal 0.121858 -0.252335 0.959936 + outer loop + vertex 1.05339 0.962163 2.5704 + vertex 1.05844 0.963228 2.57004 + vertex 1.05647 0.965998 2.57102 + endloop + endfacet + facet normal 0.12277 -0.257138 0.958545 + outer loop + vertex 1.05353 0.958203 2.56932 + vertex 1.05844 0.963228 2.57004 + vertex 1.05339 0.962163 2.5704 + endloop + endfacet + facet normal 0.115715 -0.25061 0.961148 + outer loop + vertex 1.05867 0.958338 2.56874 + vertex 1.05844 0.963228 2.57004 + vertex 1.05353 0.958203 2.56932 + endloop + endfacet + facet normal 0.115668 -0.262334 0.95802 + outer loop + vertex 1.05372 0.953577 2.56803 + vertex 1.05867 0.958338 2.56874 + vertex 1.05353 0.958203 2.56932 + endloop + endfacet + facet normal 0.118932 -0.262108 0.957682 + outer loop + vertex 1.05372 0.953577 2.56803 + vertex 1.05353 0.958203 2.56932 + vertex 1.04862 0.95355 2.56866 + endloop + endfacet + facet normal 0.118669 -0.271339 0.95514 + outer loop + vertex 1.04894 0.949208 2.56739 + vertex 1.05372 0.953577 2.56803 + vertex 1.04862 0.95355 2.56866 + endloop + endfacet + facet normal 0.126544 -0.270528 0.954359 + outer loop + vertex 1.04894 0.949208 2.56739 + vertex 1.04862 0.95355 2.56866 + vertex 1.04389 0.94885 2.56795 + endloop + endfacet + facet normal 0.126692 -0.274402 0.953233 + outer loop + vertex 1.04477 0.944958 2.56672 + vertex 1.04894 0.949208 2.56739 + vertex 1.04389 0.94885 2.56795 + endloop + endfacet + facet normal 0.130084 -0.27357 0.953015 + outer loop + vertex 1.04477 0.944958 2.56672 + vertex 1.04389 0.94885 2.56795 + vertex 1.03925 0.943797 2.56714 + endloop + endfacet + facet normal 0.13012 -0.273765 0.952954 + outer loop + vertex 1.04477 0.944958 2.56672 + vertex 1.03925 0.943797 2.56714 + vertex 1.04145 0.940808 2.56598 + endloop + endfacet + facet normal 0.13162 -0.274872 0.952429 + outer loop + vertex 1.04607 0.941764 2.56562 + vertex 1.04477 0.944958 2.56672 + vertex 1.04145 0.940808 2.56598 + endloop + endfacet + facet normal 0.131181 -0.272459 0.953183 + outer loop + vertex 1.04145 0.940808 2.56598 + vertex 1.04263 0.937517 2.56488 + vertex 1.04607 0.941764 2.56562 + endloop + endfacet + facet normal 0.128413 -0.270385 0.95415 + outer loop + vertex 1.04263 0.937517 2.56488 + vertex 1.04827 0.938788 2.56448 + vertex 1.04607 0.941764 2.56562 + endloop + endfacet + facet normal 0.127806 -0.270818 0.954109 + outer loop + vertex 1.05002 0.942991 2.56544 + vertex 1.04607 0.941764 2.56562 + vertex 1.04827 0.938788 2.56448 + endloop + endfacet + facet normal 0.113698 -0.2657 0.957328 + outer loop + vertex 1.05002 0.942991 2.56544 + vertex 1.04827 0.938788 2.56448 + vertex 1.05381 0.943213 2.56505 + endloop + endfacet + facet normal 0.113733 -0.266902 0.956989 + outer loop + vertex 1.05381 0.943213 2.56505 + vertex 1.05249 0.945536 2.56585 + vertex 1.05002 0.942991 2.56544 + endloop + endfacet + facet normal 0.124695 -0.27686 0.952785 + outer loop + vertex 1.05249 0.945536 2.56585 + vertex 1.04933 0.94556 2.56627 + vertex 1.05002 0.942991 2.56544 + endloop + endfacet + facet normal 0.124362 -0.284072 0.950704 + outer loop + vertex 1.05249 0.945536 2.56585 + vertex 1.05379 0.949014 2.56672 + vertex 1.04933 0.94556 2.56627 + endloop + endfacet + facet normal 0.119738 -0.278391 0.952975 + outer loop + vertex 1.05379 0.949014 2.56672 + vertex 1.04894 0.949208 2.56739 + vertex 1.04933 0.94556 2.56627 + endloop + endfacet + facet normal 0.111275 -0.279876 0.953565 + outer loop + vertex 1.05529 0.946763 2.56589 + vertex 1.05379 0.949014 2.56672 + vertex 1.05249 0.945536 2.56585 + endloop + endfacet + facet normal 0.105741 -0.283394 0.953156 + outer loop + vertex 1.05767 0.949214 2.56635 + vertex 1.05379 0.949014 2.56672 + vertex 1.05529 0.946763 2.56589 + endloop + endfacet + facet normal 0.105437 -0.27046 0.95694 + outer loop + vertex 1.05767 0.949214 2.56635 + vertex 1.05915 0.953318 2.56735 + vertex 1.05379 0.949014 2.56672 + endloop + endfacet + facet normal 0.107986 -0.273465 0.955801 + outer loop + vertex 1.05915 0.953318 2.56735 + vertex 1.05372 0.953577 2.56803 + vertex 1.05379 0.949014 2.56672 + endloop + endfacet + facet normal 0.10715 -0.270555 0.956723 + outer loop + vertex 1.05529 0.946763 2.56589 + vertex 1.05249 0.945536 2.56585 + vertex 1.05381 0.943213 2.56505 + endloop + endfacet + facet normal 0.116962 -0.269593 0.955845 + outer loop + vertex 1.05381 0.943213 2.56505 + vertex 1.04827 0.938788 2.56448 + vertex 1.05354 0.938577 2.56377 + endloop + endfacet + facet normal 0.0990538 -0.26914 0.957994 + outer loop + vertex 1.05354 0.938577 2.56377 + vertex 1.05844 0.942892 2.56448 + vertex 1.05381 0.943213 2.56505 + endloop + endfacet + facet normal 0.0989068 -0.270571 0.957606 + outer loop + vertex 1.05833 0.946619 2.56554 + vertex 1.05381 0.943213 2.56505 + vertex 1.05844 0.942892 2.56448 + endloop + endfacet + facet normal 0.101669 -0.271934 0.95693 + outer loop + vertex 1.05865 0.938563 2.56323 + vertex 1.05844 0.942892 2.56448 + vertex 1.05354 0.938577 2.56377 + endloop + endfacet + facet normal 0.10158 -0.274637 0.956167 + outer loop + vertex 1.05374 0.934078 2.56246 + vertex 1.05865 0.938563 2.56323 + vertex 1.05354 0.938577 2.56377 + endloop + endfacet + facet normal 0.118028 -0.273457 0.954615 + outer loop + vertex 1.05374 0.934078 2.56246 + vertex 1.05354 0.938577 2.56377 + vertex 1.04855 0.933884 2.56305 + endloop + endfacet + facet normal 0.118035 -0.274796 0.95423 + outer loop + vertex 1.04892 0.929249 2.56166 + vertex 1.05374 0.934078 2.56246 + vertex 1.04855 0.933884 2.56305 + endloop + endfacet + facet normal 0.132614 -0.273197 0.952773 + outer loop + vertex 1.04892 0.929249 2.56166 + vertex 1.04855 0.933884 2.56305 + vertex 1.0439 0.929269 2.56237 + endloop + endfacet + facet normal 0.128855 -0.269633 0.954303 + outer loop + vertex 1.0439 0.929269 2.56237 + vertex 1.04855 0.933884 2.56305 + vertex 1.0434 0.933543 2.56364 + endloop + endfacet + facet normal 0.131598 -0.269232 0.954042 + outer loop + vertex 1.0439 0.929269 2.56237 + vertex 1.0434 0.933543 2.56364 + vertex 1.03891 0.928834 2.56294 + endloop + endfacet + facet normal 0.131415 -0.265855 0.955014 + outer loop + vertex 1.03983 0.924944 2.56173 + vertex 1.0439 0.929269 2.56237 + vertex 1.03891 0.928834 2.56294 + endloop + endfacet + facet normal 0.127088 -0.266964 0.95529 + outer loop + vertex 1.03983 0.924944 2.56173 + vertex 1.03891 0.928834 2.56294 + vertex 1.03438 0.923804 2.56213 + endloop + endfacet + facet normal 0.126578 -0.264236 0.956116 + outer loop + vertex 1.03983 0.924944 2.56173 + vertex 1.03438 0.923804 2.56213 + vertex 1.03659 0.920792 2.56101 + endloop + endfacet + facet normal 0.131807 -0.268001 0.954359 + outer loop + vertex 1.0411 0.921712 2.56064 + vertex 1.03983 0.924944 2.56173 + vertex 1.03659 0.920792 2.56101 + endloop + endfacet + facet normal 0.132264 -0.270542 0.953579 + outer loop + vertex 1.03659 0.920792 2.56101 + vertex 1.03782 0.917518 2.55991 + vertex 1.0411 0.921712 2.56064 + endloop + endfacet + facet normal 0.136452 -0.273554 0.952129 + outer loop + vertex 1.03782 0.917518 2.55991 + vertex 1.04329 0.918737 2.55947 + vertex 1.0411 0.921712 2.56064 + endloop + endfacet + facet normal 0.139287 -0.27153 0.952297 + outer loop + vertex 1.04478 0.922803 2.56041 + vertex 1.0411 0.921712 2.56064 + vertex 1.04329 0.918737 2.55947 + endloop + endfacet + facet normal 0.137542 -0.270984 0.952707 + outer loop + vertex 1.04478 0.922803 2.56041 + vertex 1.04329 0.918737 2.55947 + vertex 1.04801 0.922658 2.55991 + endloop + endfacet + facet normal 0.134636 -0.267632 0.954068 + outer loop + vertex 1.04801 0.922658 2.55991 + vertex 1.04329 0.918737 2.55947 + vertex 1.04856 0.918672 2.55871 + endloop + endfacet + facet normal 0.123623 -0.269451 0.955046 + outer loop + vertex 1.04856 0.918672 2.55871 + vertex 1.05324 0.923681 2.55952 + vertex 1.04801 0.922658 2.55991 + endloop + endfacet + facet normal 0.122638 -0.263772 0.956757 + outer loop + vertex 1.04801 0.922658 2.55991 + vertex 1.05324 0.923681 2.55952 + vertex 1.05103 0.926517 2.56058 + endloop + endfacet + facet normal 0.131372 -0.270088 0.953831 + outer loop + vertex 1.04736 0.925353 2.56076 + vertex 1.04801 0.922658 2.55991 + vertex 1.05103 0.926517 2.56058 + endloop + endfacet + facet normal 0.13263 -0.274264 0.952464 + outer loop + vertex 1.05103 0.926517 2.56058 + vertex 1.04892 0.929249 2.56166 + vertex 1.04736 0.925353 2.56076 + endloop + endfacet + facet normal 0.138996 -0.276459 0.950921 + outer loop + vertex 1.04736 0.925353 2.56076 + vertex 1.04892 0.929249 2.56166 + vertex 1.04427 0.925521 2.56126 + endloop + endfacet + facet normal 0.139616 -0.270162 0.952638 + outer loop + vertex 1.04736 0.925353 2.56076 + vertex 1.04427 0.925521 2.56126 + vertex 1.04478 0.922803 2.56041 + endloop + endfacet + facet normal 0.137768 -0.2684 0.953405 + outer loop + vertex 1.04801 0.922658 2.55991 + vertex 1.04736 0.925353 2.56076 + vertex 1.04478 0.922803 2.56041 + endloop + endfacet + facet normal 0.132792 -0.269039 0.953931 + outer loop + vertex 1.04892 0.929249 2.56166 + vertex 1.0439 0.929269 2.56237 + vertex 1.04427 0.925521 2.56126 + endloop + endfacet + facet normal 0.11709 -0.267918 0.9563 + outer loop + vertex 1.05479 0.927688 2.56045 + vertex 1.05103 0.926517 2.56058 + vertex 1.05324 0.923681 2.55952 + endloop + endfacet + facet normal 0.0962056 -0.260846 0.960575 + outer loop + vertex 1.05479 0.927688 2.56045 + vertex 1.05324 0.923681 2.55952 + vertex 1.05814 0.92749 2.56006 + endloop + endfacet + facet normal 0.0951779 -0.272245 0.957509 + outer loop + vertex 1.05814 0.92749 2.56006 + vertex 1.05749 0.93018 2.56089 + vertex 1.05479 0.927688 2.56045 + endloop + endfacet + facet normal 0.103485 -0.26975 0.957353 + outer loop + vertex 1.05814 0.92749 2.56006 + vertex 1.05324 0.923681 2.55952 + vertex 1.05853 0.923538 2.55891 + endloop + endfacet + facet normal 0.103578 -0.268166 0.957788 + outer loop + vertex 1.05384 0.918938 2.55813 + vertex 1.05853 0.923538 2.55891 + vertex 1.05324 0.923681 2.55952 + endloop + endfacet + facet normal 0.119456 -0.265813 0.956595 + outer loop + vertex 1.05384 0.918938 2.55813 + vertex 1.05324 0.923681 2.55952 + vertex 1.04856 0.918672 2.55871 + endloop + endfacet + facet normal 0.119602 -0.273466 0.954417 + outer loop + vertex 1.04923 0.913858 2.55725 + vertex 1.05384 0.918938 2.55813 + vertex 1.04856 0.918672 2.55871 + endloop + endfacet + facet normal 0.128419 -0.27202 0.953684 + outer loop + vertex 1.04923 0.913858 2.55725 + vertex 1.04856 0.918672 2.55871 + vertex 1.04401 0.914094 2.55802 + endloop + endfacet + facet normal 0.126182 -0.297523 0.946339 + outer loop + vertex 1.04923 0.913858 2.55725 + vertex 1.04401 0.914094 2.55802 + vertex 1.04452 0.910143 2.55671 + endloop + endfacet + facet normal 0.123191 -0.293951 0.947848 + outer loop + vertex 1.04774 0.909797 2.55618 + vertex 1.04923 0.913858 2.55725 + vertex 1.04452 0.910143 2.55671 + endloop + endfacet + facet normal 0.114587 -0.347816 0.930534 + outer loop + vertex 1.04774 0.909797 2.55618 + vertex 1.04452 0.910143 2.55671 + vertex 1.04517 0.907333 2.55558 + endloop + endfacet + facet normal 0.127731 -0.359963 0.924182 + outer loop + vertex 1.04851 0.907143 2.55504 + vertex 1.04774 0.909797 2.55618 + vertex 1.04517 0.907333 2.55558 + endloop + endfacet + facet normal 0.131559 -0.358822 0.924088 + outer loop + vertex 1.04774 0.909797 2.55618 + vertex 1.04851 0.907143 2.55504 + vertex 1.05153 0.910775 2.55602 + endloop + endfacet + facet normal 0.111271 -0.344143 0.9323 + outer loop + vertex 1.04851 0.907143 2.55504 + vertex 1.0532 0.907758 2.55471 + vertex 1.05153 0.910775 2.55602 + endloop + endfacet + facet normal 0.115251 -0.2915 0.949603 + outer loop + vertex 1.05153 0.910775 2.55602 + vertex 1.04923 0.913858 2.55725 + vertex 1.04774 0.909797 2.55618 + endloop + endfacet + facet normal 0.115658 -0.291212 0.949641 + outer loop + vertex 1.05478 0.914857 2.55688 + vertex 1.04923 0.913858 2.55725 + vertex 1.05153 0.910775 2.55602 + endloop + endfacet + facet normal 0.126743 -0.297435 0.946292 + outer loop + vertex 1.04452 0.910143 2.55671 + vertex 1.04401 0.914094 2.55802 + vertex 1.03987 0.909681 2.55719 + endloop + endfacet + facet normal 0.134587 -0.304194 0.943055 + outer loop + vertex 1.03987 0.909681 2.55719 + vertex 1.04401 0.914094 2.55802 + vertex 1.0388 0.913612 2.55861 + endloop + endfacet + facet normal 0.125904 -0.306702 0.943442 + outer loop + vertex 1.03987 0.909681 2.55719 + vertex 1.0388 0.913612 2.55861 + vertex 1.03424 0.908603 2.55759 + endloop + endfacet + facet normal 0.131588 -0.311399 0.941124 + outer loop + vertex 1.03424 0.908603 2.55759 + vertex 1.0388 0.913612 2.55861 + vertex 1.03365 0.91317 2.55918 + endloop + endfacet + facet normal 0.1302 -0.283673 0.950041 + outer loop + vertex 1.0388 0.913612 2.55861 + vertex 1.03782 0.917518 2.55991 + vertex 1.03365 0.91317 2.55918 + endloop + endfacet + facet normal 0.129285 -0.282857 0.950409 + outer loop + vertex 1.03365 0.91317 2.55918 + vertex 1.03782 0.917518 2.55991 + vertex 1.03337 0.917016 2.56036 + endloop + endfacet + facet normal 0.128402 -0.272027 0.953684 + outer loop + vertex 1.03337 0.917016 2.56036 + vertex 1.03782 0.917518 2.55991 + vertex 1.03659 0.920792 2.56101 + endloop + endfacet + facet normal 0.124544 -0.268962 0.955065 + outer loop + vertex 1.03289 0.919788 2.56121 + vertex 1.03337 0.917016 2.56036 + vertex 1.03659 0.920792 2.56101 + endloop + endfacet + facet normal 0.133072 -0.277534 0.951455 + outer loop + vertex 1.04401 0.914094 2.55802 + vertex 1.04329 0.918737 2.55947 + vertex 1.0388 0.913612 2.55861 + endloop + endfacet + facet normal 0.111781 -0.266866 0.957229 + outer loop + vertex 1.05478 0.914857 2.55688 + vertex 1.05384 0.918938 2.55813 + vertex 1.04923 0.913858 2.55725 + endloop + endfacet + facet normal 0.134124 -0.277341 0.951364 + outer loop + vertex 1.04401 0.914094 2.55802 + vertex 1.04856 0.918672 2.55871 + vertex 1.04329 0.918737 2.55947 + endloop + endfacet + facet normal 0.13895 -0.270307 0.952695 + outer loop + vertex 1.04478 0.922803 2.56041 + vertex 1.04427 0.925521 2.56126 + vertex 1.0411 0.921712 2.56064 + endloop + endfacet + facet normal 0.138036 -0.281565 0.949561 + outer loop + vertex 1.0388 0.913612 2.55861 + vertex 1.04329 0.918737 2.55947 + vertex 1.03782 0.917518 2.55991 + endloop + endfacet + facet normal 0.134546 -0.266901 0.954286 + outer loop + vertex 1.04427 0.925521 2.56126 + vertex 1.03983 0.924944 2.56173 + vertex 1.0411 0.921712 2.56064 + endloop + endfacet + facet normal 0.123836 -0.266182 0.955935 + outer loop + vertex 1.03659 0.920792 2.56101 + vertex 1.03438 0.923804 2.56213 + vertex 1.03289 0.919788 2.56121 + endloop + endfacet + facet normal 0.127357 -0.267191 0.955191 + outer loop + vertex 1.03438 0.923804 2.56213 + vertex 1.03891 0.928834 2.56294 + vertex 1.03381 0.928559 2.56354 + endloop + endfacet + facet normal 0.123209 -0.267797 0.955565 + outer loop + vertex 1.03438 0.923804 2.56213 + vertex 1.03381 0.928559 2.56354 + vertex 1.02908 0.923888 2.56284 + endloop + endfacet + facet normal 0.123161 -0.268731 0.955309 + outer loop + vertex 1.03438 0.923804 2.56213 + vertex 1.02908 0.923888 2.56284 + vertex 1.02959 0.91999 2.56168 + endloop + endfacet + facet normal 0.120015 -0.264956 0.956763 + outer loop + vertex 1.03289 0.919788 2.56121 + vertex 1.03438 0.923804 2.56213 + vertex 1.02959 0.91999 2.56168 + endloop + endfacet + facet normal 0.119694 -0.268204 0.955897 + outer loop + vertex 1.03289 0.919788 2.56121 + vertex 1.02959 0.91999 2.56168 + vertex 1.03026 0.917301 2.56084 + endloop + endfacet + facet normal 0.121113 -0.269623 0.955319 + outer loop + vertex 1.03337 0.917016 2.56036 + vertex 1.03289 0.919788 2.56121 + vertex 1.03026 0.917301 2.56084 + endloop + endfacet + facet normal 0.119924 -0.278581 0.952896 + outer loop + vertex 1.03026 0.917301 2.56084 + vertex 1.02863 0.913405 2.5599 + vertex 1.03337 0.917016 2.56036 + endloop + endfacet + facet normal 0.12381 -0.283436 0.950965 + outer loop + vertex 1.03337 0.917016 2.56036 + vertex 1.02863 0.913405 2.5599 + vertex 1.03365 0.91317 2.55918 + endloop + endfacet + facet normal 0.121505 -0.309003 0.943267 + outer loop + vertex 1.02908 0.908941 2.55838 + vertex 1.03365 0.91317 2.55918 + vertex 1.02863 0.913405 2.5599 + endloop + endfacet + facet normal 0.119497 -0.309268 0.943437 + outer loop + vertex 1.02908 0.908941 2.55838 + vertex 1.02863 0.913405 2.5599 + vertex 1.02402 0.908768 2.55897 + endloop + endfacet + facet normal 0.129146 -0.318001 0.939253 + outer loop + vertex 1.02402 0.908768 2.55897 + vertex 1.02863 0.913405 2.5599 + vertex 1.02341 0.912405 2.56028 + endloop + endfacet + facet normal 0.126404 -0.318529 0.939447 + outer loop + vertex 1.02341 0.912405 2.56028 + vertex 1.01867 0.908572 2.55962 + vertex 1.02402 0.908768 2.55897 + endloop + endfacet + facet normal 0.125767 -0.3851 0.914265 + outer loop + vertex 1.01994 0.90458 2.55777 + vertex 1.02402 0.908768 2.55897 + vertex 1.01867 0.908572 2.55962 + endloop + endfacet + facet normal 0.129428 -0.322 0.937851 + outer loop + vertex 1.02006 0.912442 2.56076 + vertex 1.01867 0.908572 2.55962 + vertex 1.02341 0.912405 2.56028 + endloop + endfacet + facet normal 0.131551 -0.283649 0.949862 + outer loop + vertex 1.02341 0.912405 2.56028 + vertex 1.02272 0.915018 2.56116 + vertex 1.02006 0.912442 2.56076 + endloop + endfacet + facet normal 0.129292 -0.281466 0.950821 + outer loop + vertex 1.02272 0.915018 2.56116 + vertex 1.01935 0.915051 2.56163 + vertex 1.02006 0.912442 2.56076 + endloop + endfacet + facet normal 0.129012 -0.281546 0.950835 + outer loop + vertex 1.02006 0.912442 2.56076 + vertex 1.01935 0.915051 2.56163 + vertex 1.01629 0.911176 2.56089 + endloop + endfacet + facet normal 0.127643 -0.280554 0.951313 + outer loop + vertex 1.01935 0.915051 2.56163 + vertex 1.0141 0.913927 2.562 + vertex 1.01629 0.911176 2.56089 + endloop + endfacet + facet normal 0.129441 -0.279187 0.951472 + outer loop + vertex 1.01629 0.911176 2.56089 + vertex 1.0141 0.913927 2.562 + vertex 1.01255 0.909938 2.56104 + endloop + endfacet + facet normal 0.149243 -0.341694 0.927886 + outer loop + vertex 1.01255 0.909938 2.56104 + vertex 1.01333 0.907355 2.55996 + vertex 1.01629 0.911176 2.56089 + endloop + endfacet + facet normal 0.135653 -0.332483 0.933303 + outer loop + vertex 1.01333 0.907355 2.55996 + vertex 1.01867 0.908572 2.55962 + vertex 1.01629 0.911176 2.56089 + endloop + endfacet + facet normal 0.134302 -0.346405 0.928422 + outer loop + vertex 1.01333 0.907355 2.55996 + vertex 1.01255 0.909938 2.56104 + vertex 1.00998 0.907481 2.5605 + endloop + endfacet + facet normal 0.126547 -0.422313 0.897573 + outer loop + vertex 1.00998 0.907481 2.5605 + vertex 1.00875 0.903907 2.55899 + vertex 1.01333 0.907355 2.55996 + endloop + endfacet + facet normal 0.096043 -0.414901 0.904783 + outer loop + vertex 1.00998 0.907481 2.5605 + vertex 1.00619 0.90664 2.56051 + vertex 1.00875 0.903907 2.55899 + endloop + endfacet + facet normal 0.0751687 -0.320103 0.944396 + outer loop + vertex 1.00998 0.907481 2.5605 + vertex 1.00937 0.910202 2.56147 + vertex 1.00619 0.90664 2.56051 + endloop + endfacet + facet normal 0.100433 -0.314343 0.943982 + outer loop + vertex 1.01255 0.909938 2.56104 + vertex 1.00937 0.910202 2.56147 + vertex 1.00998 0.907481 2.5605 + endloop + endfacet + facet normal 0.105716 -0.271238 0.956689 + outer loop + vertex 1.01255 0.909938 2.56104 + vertex 1.0141 0.913927 2.562 + vertex 1.00937 0.910202 2.56147 + endloop + endfacet + facet normal 0.107199 -0.273023 0.956016 + outer loop + vertex 1.0141 0.913927 2.562 + vertex 1.00898 0.914079 2.56262 + vertex 1.00937 0.910202 2.56147 + endloop + endfacet + facet normal 0.107519 -0.267931 0.95742 + outer loop + vertex 1.0141 0.913927 2.562 + vertex 1.01369 0.918647 2.56337 + vertex 1.00898 0.914079 2.56262 + endloop + endfacet + facet normal 0.108439 -0.268821 0.957066 + outer loop + vertex 1.00898 0.914079 2.56262 + vertex 1.01369 0.918647 2.56337 + vertex 1.00848 0.918447 2.5639 + endloop + endfacet + facet normal 0.0815509 -0.272382 0.958727 + outer loop + vertex 1.00898 0.914079 2.56262 + vertex 1.00848 0.918447 2.5639 + vertex 1.00396 0.914034 2.56303 + endloop + endfacet + facet normal 0.081422 -0.281019 0.956242 + outer loop + vertex 1.00487 0.910009 2.56177 + vertex 1.00898 0.914079 2.56262 + vertex 1.00396 0.914034 2.56303 + endloop + endfacet + facet normal 0.076748 -0.276637 0.957905 + outer loop + vertex 1.00937 0.910202 2.56147 + vertex 1.00898 0.914079 2.56262 + vertex 1.00487 0.910009 2.56177 + endloop + endfacet + facet normal 0.0777128 -0.322137 0.943498 + outer loop + vertex 1.00937 0.910202 2.56147 + vertex 1.00487 0.910009 2.56177 + vertex 1.00619 0.90664 2.56051 + endloop + endfacet + facet normal 0.0882738 -0.278797 0.956284 + outer loop + vertex 1.00396 0.914034 2.56303 + vertex 1.00848 0.918447 2.5639 + vertex 1.00322 0.918583 2.56443 + endloop + endfacet + facet normal 0.0881606 -0.280866 0.955689 + outer loop + vertex 1.00809 0.922359 2.56509 + vertex 1.00322 0.918583 2.56443 + vertex 1.00848 0.918447 2.5639 + endloop + endfacet + facet normal 0.113448 -0.277808 0.953914 + outer loop + vertex 1.00848 0.918447 2.5639 + vertex 1.01338 0.923397 2.56476 + vertex 1.00809 0.922359 2.56509 + endloop + endfacet + facet normal 0.113734 -0.279421 0.953409 + outer loop + vertex 1.00809 0.922359 2.56509 + vertex 1.01338 0.923397 2.56476 + vertex 1.0113 0.926212 2.56583 + endloop + endfacet + facet normal 0.11439 -0.279922 0.953183 + outer loop + vertex 1.00752 0.925065 2.56595 + vertex 1.00809 0.922359 2.56509 + vertex 1.0113 0.926212 2.56583 + endloop + endfacet + facet normal 0.111008 -0.268428 0.956882 + outer loop + vertex 1.0113 0.926212 2.56583 + vertex 1.00915 0.929007 2.56687 + vertex 1.00752 0.925065 2.56595 + endloop + endfacet + facet normal 0.0950016 -0.262587 0.96022 + outer loop + vertex 1.00752 0.925065 2.56595 + vertex 1.00915 0.929007 2.56687 + vertex 1.00435 0.925315 2.56633 + endloop + endfacet + facet normal 0.0977293 -0.265964 0.959016 + outer loop + vertex 1.00915 0.929007 2.56687 + vertex 1.00403 0.929126 2.56742 + vertex 1.00435 0.925315 2.56633 + endloop + endfacet + facet normal 0.0712359 -0.268635 0.960604 + outer loop + vertex 1.00435 0.925315 2.56633 + vertex 1.00403 0.929126 2.56742 + vertex 0.999877 0.925032 2.56658 + endloop + endfacet + facet normal 0.0719301 -0.269291 0.960369 + outer loop + vertex 0.999877 0.925032 2.56658 + vertex 1.00403 0.929126 2.56742 + vertex 0.999045 0.928991 2.56776 + endloop + endfacet + facet normal 0.0719104 -0.266867 0.961047 + outer loop + vertex 1.00403 0.929126 2.56742 + vertex 1.00343 0.933396 2.56865 + vertex 0.999045 0.928991 2.56776 + endloop + endfacet + facet normal 0.07326 -0.268119 0.960596 + outer loop + vertex 0.999045 0.928991 2.56776 + vertex 1.00343 0.933396 2.56865 + vertex 0.998281 0.933213 2.56899 + endloop + endfacet + facet normal 0.0732943 -0.270139 0.960027 + outer loop + vertex 1.00343 0.933396 2.56865 + vertex 1.00255 0.937376 2.56984 + vertex 0.998281 0.933213 2.56899 + endloop + endfacet + facet normal 0.0800627 -0.276596 0.957645 + outer loop + vertex 0.998281 0.933213 2.56899 + vertex 1.00255 0.937376 2.56984 + vertex 0.997918 0.937099 2.57015 + endloop + endfacet + facet normal 0.0367729 -0.281039 0.958992 + outer loop + vertex 0.997918 0.937099 2.57015 + vertex 0.992849 0.933959 2.56942 + vertex 0.998281 0.933213 2.56899 + endloop + endfacet + facet normal 0.0799233 -0.273148 0.958646 + outer loop + vertex 0.997918 0.937099 2.57015 + vertex 1.00255 0.937376 2.56984 + vertex 1.00137 0.940773 2.57091 + endloop + endfacet + facet normal 0.0857195 -0.278192 0.956693 + outer loop + vertex 0.997539 0.940034 2.57103 + vertex 0.997918 0.937099 2.57015 + vertex 1.00137 0.940773 2.57091 + endloop + endfacet + facet normal 0.0835714 -0.266437 0.960222 + outer loop + vertex 1.00137 0.940773 2.57091 + vertex 0.999389 0.944077 2.57199 + vertex 0.997539 0.940034 2.57103 + endloop + endfacet + facet normal 0.0593089 -0.25641 0.964747 + outer loop + vertex 0.997539 0.940034 2.57103 + vertex 0.999389 0.944077 2.57199 + vertex 0.994209 0.940929 2.57148 + endloop + endfacet + facet normal 0.054935 -0.270858 0.961051 + outer loop + vertex 0.997539 0.940034 2.57103 + vertex 0.994209 0.940929 2.57148 + vertex 0.994893 0.937789 2.57055 + endloop + endfacet + facet normal 0.0269636 -0.276801 0.960549 + outer loop + vertex 0.994893 0.937789 2.57055 + vertex 0.994209 0.940929 2.57148 + vertex 0.992006 0.937486 2.57055 + endloop + endfacet + facet normal 0.0291523 -0.297544 0.954263 + outer loop + vertex 0.994893 0.937789 2.57055 + vertex 0.992006 0.937486 2.57055 + vertex 0.992849 0.933959 2.56942 + endloop + endfacet + facet normal 0.0565071 -0.310556 0.948874 + outer loop + vertex 0.994893 0.937789 2.57055 + vertex 0.992849 0.933959 2.56942 + vertex 0.997918 0.937099 2.57015 + endloop + endfacet + facet normal 0.0713873 -0.275287 0.958708 + outer loop + vertex 0.999389 0.944077 2.57199 + vertex 0.995342 0.945023 2.57257 + vertex 0.994209 0.940929 2.57148 + endloop + endfacet + facet normal 0.0732507 -0.26841 0.960516 + outer loop + vertex 0.999389 0.944077 2.57199 + vertex 0.999005 0.948736 2.57333 + vertex 0.995342 0.945023 2.57257 + endloop + endfacet + facet normal 0.0688551 -0.264368 0.961961 + outer loop + vertex 0.995342 0.945023 2.57257 + vertex 0.999005 0.948736 2.57333 + vertex 0.994083 0.948389 2.57358 + endloop + endfacet + facet normal 0.0692739 -0.271889 0.959832 + outer loop + vertex 0.999005 0.948736 2.57333 + vertex 0.998361 0.953325 2.57467 + vertex 0.994083 0.948389 2.57358 + endloop + endfacet + facet normal 0.0672999 -0.270308 0.960419 + outer loop + vertex 0.994083 0.948389 2.57358 + vertex 0.998361 0.953325 2.57467 + vertex 0.992735 0.952222 2.57476 + endloop + endfacet + facet normal 0.0690916 -0.279657 0.957611 + outer loop + vertex 0.992735 0.952222 2.57476 + vertex 0.998361 0.953325 2.57467 + vertex 0.996171 0.956421 2.57573 + endloop + endfacet + facet normal 0.05699 -0.270548 0.961018 + outer loop + vertex 0.991321 0.955802 2.57585 + vertex 0.992735 0.952222 2.57476 + vertex 0.996171 0.956421 2.57573 + endloop + endfacet + facet normal 0.056524 -0.266698 0.962121 + outer loop + vertex 0.996171 0.956421 2.57573 + vertex 0.995028 0.959856 2.57675 + vertex 0.991321 0.955802 2.57585 + endloop + endfacet + facet normal 0.0525602 -0.263331 0.963273 + outer loop + vertex 0.995028 0.959856 2.57675 + vertex 0.990127 0.959554 2.57694 + vertex 0.991321 0.955802 2.57585 + endloop + endfacet + facet normal 0.0145997 -0.274865 0.961372 + outer loop + vertex 0.991321 0.955802 2.57585 + vertex 0.990127 0.959554 2.57694 + vertex 0.986386 0.955645 2.57588 + endloop + endfacet + facet normal 0.0146162 -0.275411 0.961215 + outer loop + vertex 0.986386 0.955645 2.57588 + vertex 0.98768 0.951864 2.57477 + vertex 0.991321 0.955802 2.57585 + endloop + endfacet + facet normal 0.0235963 -0.28306 0.958812 + outer loop + vertex 0.98768 0.951864 2.57477 + vertex 0.992735 0.952222 2.57476 + vertex 0.991321 0.955802 2.57585 + endloop + endfacet + facet normal 0.0233508 -0.279535 0.959852 + outer loop + vertex 0.988974 0.947952 2.5736 + vertex 0.992735 0.952222 2.57476 + vertex 0.98768 0.951864 2.57477 + endloop + endfacet + facet normal 0.0282228 -0.283479 0.958563 + outer loop + vertex 0.994083 0.948389 2.57358 + vertex 0.992735 0.952222 2.57476 + vertex 0.988974 0.947952 2.5736 + endloop + endfacet + facet normal 0.0274636 -0.274473 0.961203 + outer loop + vertex 0.990528 0.943551 2.5723 + vertex 0.994083 0.948389 2.57358 + vertex 0.988974 0.947952 2.5736 + endloop + endfacet + facet normal 0.0522975 -0.258219 0.96467 + outer loop + vertex 0.995028 0.959856 2.57675 + vertex 0.994214 0.963837 2.57786 + vertex 0.990127 0.959554 2.57694 + endloop + endfacet + facet normal 0.0528778 -0.258736 0.9645 + outer loop + vertex 0.990127 0.959554 2.57694 + vertex 0.994214 0.963837 2.57786 + vertex 0.989187 0.963737 2.57811 + endloop + endfacet + facet normal 0.0528659 -0.256972 0.964972 + outer loop + vertex 0.994214 0.963837 2.57786 + vertex 0.993673 0.968212 2.57906 + vertex 0.989187 0.963737 2.57811 + endloop + endfacet + facet normal 0.0807593 -0.253263 0.964021 + outer loop + vertex 0.994214 0.963837 2.57786 + vertex 0.998718 0.968414 2.57869 + vertex 0.993673 0.968212 2.57906 + endloop + endfacet + facet normal 0.0781458 -0.250844 0.964868 + outer loop + vertex 0.999169 0.96402 2.57751 + vertex 0.998718 0.968414 2.57869 + vertex 0.994214 0.963837 2.57786 + endloop + endfacet + facet normal 0.0927935 -0.249113 0.964019 + outer loop + vertex 0.999169 0.96402 2.57751 + vertex 1.00374 0.968509 2.57823 + vertex 0.998718 0.968414 2.57869 + endloop + endfacet + facet normal 0.0927986 -0.248045 0.964293 + outer loop + vertex 1.00374 0.968509 2.57823 + vertex 1.00343 0.972969 2.57941 + vertex 0.998718 0.968414 2.57869 + endloop + endfacet + facet normal 0.0945076 -0.249718 0.963696 + outer loop + vertex 0.998718 0.968414 2.57869 + vertex 1.00343 0.972969 2.57941 + vertex 0.998509 0.973163 2.57994 + endloop + endfacet + facet normal 0.0988383 -0.247504 0.963832 + outer loop + vertex 1.00374 0.968509 2.57823 + vertex 1.0084 0.97326 2.57897 + vertex 1.00343 0.972969 2.57941 + endloop + endfacet + facet normal 0.0988237 -0.247097 0.963938 + outer loop + vertex 1.0084 0.97326 2.57897 + vertex 1.00778 0.97733 2.58008 + vertex 1.00343 0.972969 2.57941 + endloop + endfacet + facet normal 0.0985044 -0.246795 0.964048 + outer loop + vertex 1.00343 0.972969 2.57941 + vertex 1.00778 0.97733 2.58008 + vertex 1.00337 0.976906 2.58042 + endloop + endfacet + facet normal 0.0943918 -0.250651 0.963465 + outer loop + vertex 1.0043 0.963817 2.57695 + vertex 1.00374 0.968509 2.57823 + vertex 0.999169 0.96402 2.57751 + endloop + endfacet + facet normal 0.0943828 -0.250785 0.963431 + outer loop + vertex 1.0043 0.963817 2.57695 + vertex 0.999169 0.96402 2.57751 + vertex 0.999561 0.960183 2.57647 + endloop + endfacet + facet normal 0.0951023 -0.251682 0.963126 + outer loop + vertex 1.00274 0.959851 2.57607 + vertex 1.0043 0.963817 2.57695 + vertex 0.999561 0.960183 2.57647 + endloop + endfacet + facet normal 0.0941043 -0.259014 0.961278 + outer loop + vertex 1.00274 0.959851 2.57607 + vertex 0.999561 0.960183 2.57647 + vertex 1.00004 0.957381 2.57567 + endloop + endfacet + facet normal 0.100752 -0.265874 0.958728 + outer loop + vertex 1.00316 0.95703 2.57525 + vertex 1.00274 0.959851 2.57607 + vertex 1.00004 0.957381 2.57567 + endloop + endfacet + facet normal 0.0991881 -0.27637 0.955919 + outer loop + vertex 1.00004 0.957381 2.57567 + vertex 0.998361 0.953325 2.57467 + vertex 1.00316 0.95703 2.57525 + endloop + endfacet + facet normal 0.0937867 -0.269756 0.958351 + outer loop + vertex 1.00316 0.95703 2.57525 + vertex 0.998361 0.953325 2.57467 + vertex 1.0034 0.953138 2.57413 + endloop + endfacet + facet normal 0.107029 -0.268633 0.957278 + outer loop + vertex 1.0034 0.953138 2.57413 + vertex 1.00764 0.957467 2.57487 + vertex 1.00316 0.95703 2.57525 + endloop + endfacet + facet normal 0.106734 -0.264596 0.958435 + outer loop + vertex 1.00316 0.95703 2.57525 + vertex 1.00764 0.957467 2.57487 + vertex 1.00648 0.960792 2.57591 + endloop + endfacet + facet normal 0.108878 -0.263838 0.958402 + outer loop + vertex 1.00648 0.960792 2.57591 + vertex 1.00764 0.957467 2.57487 + vertex 1.01107 0.961643 2.57563 + endloop + endfacet + facet normal 0.107959 -0.258351 0.96 + outer loop + vertex 1.01107 0.961643 2.57563 + vertex 1.0098 0.964888 2.57664 + vertex 1.00648 0.960792 2.57591 + endloop + endfacet + facet normal 0.104085 -0.255424 0.96121 + outer loop + vertex 1.0098 0.964888 2.57664 + vertex 1.0043 0.963817 2.57695 + vertex 1.00648 0.960792 2.57591 + endloop + endfacet + facet normal 0.103588 -0.252639 0.962 + outer loop + vertex 1.0098 0.964888 2.57664 + vertex 1.00887 0.968802 2.57777 + vertex 1.0043 0.963817 2.57695 + endloop + endfacet + facet normal 0.106571 -0.251895 0.961869 + outer loop + vertex 1.0098 0.964888 2.57664 + vertex 1.01396 0.969155 2.5773 + vertex 1.00887 0.968802 2.57777 + endloop + endfacet + facet normal 0.10651 -0.250532 0.962231 + outer loop + vertex 1.01396 0.969155 2.5773 + vertex 1.01353 0.973551 2.57849 + vertex 1.00887 0.968802 2.57777 + endloop + endfacet + facet normal 0.104198 -0.248388 0.96304 + outer loop + vertex 1.00887 0.968802 2.57777 + vertex 1.01353 0.973551 2.57849 + vertex 1.0084 0.97326 2.57897 + endloop + endfacet + facet normal 0.100312 -0.248873 0.963327 + outer loop + vertex 1.00887 0.968802 2.57777 + vertex 1.0084 0.97326 2.57897 + vertex 1.00374 0.968509 2.57823 + endloop + endfacet + facet normal 0.104194 -0.248251 0.963076 + outer loop + vertex 1.01353 0.973551 2.57849 + vertex 1.01326 0.978401 2.57977 + vertex 1.0084 0.97326 2.57897 + endloop + endfacet + facet normal 0.108851 -0.247881 0.962656 + outer loop + vertex 1.01353 0.973551 2.57849 + vertex 1.01842 0.978276 2.57916 + vertex 1.01326 0.978401 2.57977 + endloop + endfacet + facet normal 0.110861 -0.249856 0.961916 + outer loop + vertex 1.01863 0.973678 2.57794 + vertex 1.01842 0.978276 2.57916 + vertex 1.01353 0.973551 2.57849 + endloop + endfacet + facet normal 0.115343 -0.249536 0.961472 + outer loop + vertex 1.01863 0.973678 2.57794 + vertex 1.02351 0.978479 2.5786 + vertex 1.01842 0.978276 2.57916 + endloop + endfacet + facet normal 0.115339 -0.249153 0.961572 + outer loop + vertex 1.02351 0.978479 2.5786 + vertex 1.0234 0.983309 2.57986 + vertex 1.01842 0.978276 2.57916 + endloop + endfacet + facet normal 0.114609 -0.248467 0.961836 + outer loop + vertex 1.01842 0.978276 2.57916 + vertex 1.0234 0.983309 2.57986 + vertex 1.01824 0.982287 2.58021 + endloop + endfacet + facet normal 0.114659 -0.248744 0.961759 + outer loop + vertex 1.01824 0.982287 2.58021 + vertex 1.0234 0.983309 2.57986 + vertex 1.02137 0.986127 2.58083 + endloop + endfacet + facet normal 0.116764 -0.250908 0.960943 + outer loop + vertex 1.02376 0.973936 2.57738 + vertex 1.02351 0.978479 2.5786 + vertex 1.01863 0.973678 2.57794 + endloop + endfacet + facet normal 0.116773 -0.25132 0.960834 + outer loop + vertex 1.01902 0.96907 2.57668 + vertex 1.02376 0.973936 2.57738 + vertex 1.01863 0.973678 2.57794 + endloop + endfacet + facet normal 0.112659 -0.251776 0.961206 + outer loop + vertex 1.01902 0.96907 2.57668 + vertex 1.01863 0.973678 2.57794 + vertex 1.01396 0.969155 2.5773 + endloop + endfacet + facet normal 0.112597 -0.253061 0.960876 + outer loop + vertex 1.01902 0.96907 2.57668 + vertex 1.01396 0.969155 2.5773 + vertex 1.01434 0.965405 2.57627 + endloop + endfacet + facet normal 0.112649 -0.253125 0.960853 + outer loop + vertex 1.01749 0.965198 2.57584 + vertex 1.01902 0.96907 2.57668 + vertex 1.01434 0.965405 2.57627 + endloop + endfacet + facet normal 0.112131 -0.258303 0.959534 + outer loop + vertex 1.01749 0.965198 2.57584 + vertex 1.01434 0.965405 2.57627 + vertex 1.01485 0.96268 2.57547 + endloop + endfacet + facet normal 0.115423 -0.261573 0.958257 + outer loop + vertex 1.01807 0.962492 2.57504 + vertex 1.01749 0.965198 2.57584 + vertex 1.01485 0.96268 2.57547 + endloop + endfacet + facet normal 0.11502 -0.265842 0.95713 + outer loop + vertex 1.01485 0.96268 2.57547 + vertex 1.01316 0.958579 2.57454 + vertex 1.01807 0.962492 2.57504 + endloop + endfacet + facet normal 0.113665 -0.26422 0.957741 + outer loop + vertex 1.01807 0.962492 2.57504 + vertex 1.01316 0.958579 2.57454 + vertex 1.01842 0.958481 2.57389 + endloop + endfacet + facet normal 0.118677 -0.263651 0.95729 + outer loop + vertex 1.01842 0.958481 2.57389 + vertex 1.02324 0.963517 2.57468 + vertex 1.01807 0.962492 2.57504 + endloop + endfacet + facet normal 0.118097 -0.26038 0.958256 + outer loop + vertex 1.01807 0.962492 2.57504 + vertex 1.02324 0.963517 2.57468 + vertex 1.02115 0.966343 2.5757 + endloop + endfacet + facet normal 0.120611 -0.25858 0.958431 + outer loop + vertex 1.02484 0.967552 2.57556 + vertex 1.02115 0.966343 2.5757 + vertex 1.02324 0.963517 2.57468 + endloop + endfacet + facet normal 0.12245 -0.25922 0.958025 + outer loop + vertex 1.02484 0.967552 2.57556 + vertex 1.02324 0.963517 2.57468 + vertex 1.02809 0.967457 2.57512 + endloop + endfacet + facet normal 0.122731 -0.254848 0.959161 + outer loop + vertex 1.02809 0.967457 2.57512 + vertex 1.02746 0.97012 2.57591 + vertex 1.02484 0.967552 2.57556 + endloop + endfacet + facet normal 0.121571 -0.253724 0.959607 + outer loop + vertex 1.02746 0.97012 2.57591 + vertex 1.02418 0.970152 2.57633 + vertex 1.02484 0.967552 2.57556 + endloop + endfacet + facet normal 0.121593 -0.253204 0.959741 + outer loop + vertex 1.02746 0.97012 2.57591 + vertex 1.02899 0.974 2.57674 + vertex 1.02418 0.970152 2.57633 + endloop + endfacet + facet normal 0.120649 -0.252069 0.960159 + outer loop + vertex 1.02899 0.974 2.57674 + vertex 1.02376 0.973936 2.57738 + vertex 1.02418 0.970152 2.57633 + endloop + endfacet + facet normal 0.120634 -0.252838 0.959959 + outer loop + vertex 1.02899 0.974 2.57674 + vertex 1.02862 0.978627 2.57801 + vertex 1.02376 0.973936 2.57738 + endloop + endfacet + facet normal 0.118699 -0.253045 0.960145 + outer loop + vertex 1.02899 0.974 2.57674 + vertex 1.03379 0.978913 2.57744 + vertex 1.02862 0.978627 2.57801 + endloop + endfacet + facet normal 0.118676 -0.252161 0.960381 + outer loop + vertex 1.03379 0.978913 2.57744 + vertex 1.03355 0.983458 2.57867 + vertex 1.02862 0.978627 2.57801 + endloop + endfacet + facet normal 0.116613 -0.250162 0.961156 + outer loop + vertex 1.02862 0.978627 2.57801 + vertex 1.03355 0.983458 2.57867 + vertex 1.02848 0.98324 2.57922 + endloop + endfacet + facet normal 0.116422 -0.252343 0.960609 + outer loop + vertex 1.03379 0.978913 2.57744 + vertex 1.03868 0.983592 2.57808 + vertex 1.03355 0.983458 2.57867 + endloop + endfacet + facet normal 0.116429 -0.250476 0.961096 + outer loop + vertex 1.03868 0.983592 2.57808 + vertex 1.03852 0.988213 2.5793 + vertex 1.03355 0.983458 2.57867 + endloop + endfacet + facet normal 0.114399 -0.248456 0.961864 + outer loop + vertex 1.03355 0.983458 2.57867 + vertex 1.03852 0.988213 2.5793 + vertex 1.03346 0.988278 2.57992 + endloop + endfacet + facet normal 0.124694 -0.249963 0.960193 + outer loop + vertex 1.03868 0.983592 2.57808 + vertex 1.0436 0.988434 2.5787 + vertex 1.03852 0.988213 2.5793 + endloop + endfacet + facet normal 0.124731 -0.252932 0.95941 + outer loop + vertex 1.0436 0.988434 2.5787 + vertex 1.04349 0.993299 2.58 + vertex 1.03852 0.988213 2.5793 + endloop + endfacet + facet normal 0.121366 -0.249815 0.960657 + outer loop + vertex 1.03852 0.988213 2.5793 + vertex 1.04349 0.993299 2.58 + vertex 1.03839 0.992207 2.58036 + endloop + endfacet + facet normal 0.117579 -0.25349 0.960166 + outer loop + vertex 1.03908 0.978952 2.57681 + vertex 1.03868 0.983592 2.57808 + vertex 1.03379 0.978913 2.57744 + endloop + endfacet + facet normal 0.117503 -0.256643 0.959337 + outer loop + vertex 1.03908 0.978952 2.57681 + vertex 1.03379 0.978913 2.57744 + vertex 1.03423 0.975134 2.57638 + endloop + endfacet + facet normal 0.121923 -0.256025 0.95895 + outer loop + vertex 1.03423 0.975134 2.57638 + vertex 1.03379 0.978913 2.57744 + vertex 1.02899 0.974 2.57674 + endloop + endfacet + facet normal 0.121772 -0.255256 0.959175 + outer loop + vertex 1.03423 0.975134 2.57638 + vertex 1.02899 0.974 2.57674 + vertex 1.03116 0.971326 2.57575 + endloop + endfacet + facet normal 0.122532 -0.255826 0.958926 + outer loop + vertex 1.03489 0.972538 2.5756 + vertex 1.03423 0.975134 2.57638 + vertex 1.03116 0.971326 2.57575 + endloop + endfacet + facet normal 0.121584 -0.252799 0.959849 + outer loop + vertex 1.03489 0.972538 2.5756 + vertex 1.03116 0.971326 2.57575 + vertex 1.03327 0.968499 2.57474 + endloop + endfacet + facet normal 0.116699 -0.251075 0.960907 + outer loop + vertex 1.03489 0.972538 2.5756 + vertex 1.03327 0.968499 2.57474 + vertex 1.03814 0.972406 2.57517 + endloop + endfacet + facet normal 0.116451 -0.254417 0.960058 + outer loop + vertex 1.03814 0.972406 2.57517 + vertex 1.03753 0.975082 2.57595 + vertex 1.03489 0.972538 2.5756 + endloop + endfacet + facet normal 0.113817 -0.25506 0.960203 + outer loop + vertex 1.03753 0.975082 2.57595 + vertex 1.03814 0.972406 2.57517 + vertex 1.04126 0.976238 2.57582 + endloop + endfacet + facet normal 0.114293 -0.256648 0.959723 + outer loop + vertex 1.04126 0.976238 2.57582 + vertex 1.03908 0.978952 2.57681 + vertex 1.03753 0.975082 2.57595 + endloop + endfacet + facet normal 0.118807 -0.258234 0.958749 + outer loop + vertex 1.03753 0.975082 2.57595 + vertex 1.03908 0.978952 2.57681 + vertex 1.03423 0.975134 2.57638 + endloop + endfacet + facet normal 0.119052 -0.253893 0.959878 + outer loop + vertex 1.03814 0.972406 2.57517 + vertex 1.03327 0.968499 2.57474 + vertex 1.03849 0.968386 2.57406 + endloop + endfacet + facet normal 0.117271 -0.254094 0.960044 + outer loop + vertex 1.03849 0.968386 2.57406 + vertex 1.04333 0.973394 2.5748 + vertex 1.03814 0.972406 2.57517 + endloop + endfacet + facet normal 0.117971 -0.258211 0.958859 + outer loop + vertex 1.03814 0.972406 2.57517 + vertex 1.04333 0.973394 2.5748 + vertex 1.04126 0.976238 2.57582 + endloop + endfacet + facet normal 0.122218 -0.258606 0.95822 + outer loop + vertex 1.04372 0.96853 2.57344 + vertex 1.04333 0.973394 2.5748 + vertex 1.03849 0.968386 2.57406 + endloop + endfacet + facet normal 0.11904 -0.254099 0.959824 + outer loop + vertex 1.0337 0.96362 2.5734 + vertex 1.03849 0.968386 2.57406 + vertex 1.03327 0.968499 2.57474 + endloop + endfacet + facet normal 0.119891 -0.254003 0.959744 + outer loop + vertex 1.0337 0.96362 2.5734 + vertex 1.03327 0.968499 2.57474 + vertex 1.02846 0.963444 2.574 + endloop + endfacet + facet normal 0.1199 -0.257566 0.958793 + outer loop + vertex 1.02893 0.958856 2.57271 + vertex 1.0337 0.96362 2.5734 + vertex 1.02846 0.963444 2.574 + endloop + endfacet + facet normal 0.117004 -0.257932 0.959052 + outer loop + vertex 1.02893 0.958856 2.57271 + vertex 1.02846 0.963444 2.574 + vertex 1.02365 0.958662 2.5733 + endloop + endfacet + facet normal 0.117029 -0.261811 0.957998 + outer loop + vertex 1.02418 0.953899 2.57194 + vertex 1.02893 0.958856 2.57271 + vertex 1.02365 0.958662 2.5733 + endloop + endfacet + facet normal 0.113574 -0.262276 0.958286 + outer loop + vertex 1.02418 0.953899 2.57194 + vertex 1.02365 0.958662 2.5733 + vertex 1.01887 0.953945 2.57258 + endloop + endfacet + facet normal 0.113467 -0.264859 0.957588 + outer loop + vertex 1.02418 0.953899 2.57194 + vertex 1.01887 0.953945 2.57258 + vertex 1.01936 0.950088 2.57146 + endloop + endfacet + facet normal 0.112258 -0.263398 0.958133 + outer loop + vertex 1.02266 0.949972 2.57104 + vertex 1.02418 0.953899 2.57194 + vertex 1.01936 0.950088 2.57146 + endloop + endfacet + facet normal 0.11214 -0.265101 0.957677 + outer loop + vertex 1.02266 0.949972 2.57104 + vertex 1.01936 0.950088 2.57146 + vertex 1.02001 0.94745 2.57065 + endloop + endfacet + facet normal 0.113783 -0.26673 0.957031 + outer loop + vertex 1.02325 0.947313 2.57023 + vertex 1.02266 0.949972 2.57104 + vertex 1.02001 0.94745 2.57065 + endloop + endfacet + facet normal 0.11395 -0.264572 0.95761 + outer loop + vertex 1.02001 0.94745 2.57065 + vertex 1.01836 0.943464 2.56974 + vertex 1.02325 0.947313 2.57023 + endloop + endfacet + facet normal 0.116197 -0.2673 0.956582 + outer loop + vertex 1.02325 0.947313 2.57023 + vertex 1.01836 0.943464 2.56974 + vertex 1.02356 0.943378 2.56909 + endloop + endfacet + facet normal 0.117971 -0.267113 0.956417 + outer loop + vertex 1.02356 0.943378 2.56909 + vertex 1.02844 0.948331 2.56987 + vertex 1.02325 0.947313 2.57023 + endloop + endfacet + facet normal 0.118327 -0.269138 0.955805 + outer loop + vertex 1.02325 0.947313 2.57023 + vertex 1.02844 0.948331 2.56987 + vertex 1.02638 0.951122 2.57091 + endloop + endfacet + facet normal 0.11847 -0.269037 0.955816 + outer loop + vertex 1.03012 0.952293 2.57078 + vertex 1.02638 0.951122 2.57091 + vertex 1.02844 0.948331 2.56987 + endloop + endfacet + facet normal 0.124026 -0.271103 0.954527 + outer loop + vertex 1.03012 0.952293 2.57078 + vertex 1.02844 0.948331 2.56987 + vertex 1.03335 0.952198 2.57033 + endloop + endfacet + facet normal 0.124245 -0.267841 0.955418 + outer loop + vertex 1.03335 0.952198 2.57033 + vertex 1.03277 0.954848 2.57115 + vertex 1.03012 0.952293 2.57078 + endloop + endfacet + facet normal 0.119549 -0.26324 0.957295 + outer loop + vertex 1.03277 0.954848 2.57115 + vertex 1.02946 0.95494 2.57159 + vertex 1.03012 0.952293 2.57078 + endloop + endfacet + facet normal 0.11979 -0.259406 0.958311 + outer loop + vertex 1.03277 0.954848 2.57115 + vertex 1.03426 0.958819 2.57204 + vertex 1.02946 0.95494 2.57159 + endloop + endfacet + facet normal 0.119693 -0.259291 0.958354 + outer loop + vertex 1.03426 0.958819 2.57204 + vertex 1.02893 0.958856 2.57271 + vertex 1.02946 0.95494 2.57159 + endloop + endfacet + facet normal 0.124519 -0.260949 0.957288 + outer loop + vertex 1.03647 0.956042 2.57099 + vertex 1.03426 0.958819 2.57204 + vertex 1.03277 0.954848 2.57115 + endloop + endfacet + facet normal 0.123832 -0.261476 0.957234 + outer loop + vertex 1.03953 0.959887 2.57165 + vertex 1.03426 0.958819 2.57204 + vertex 1.03647 0.956042 2.57099 + endloop + endfacet + facet normal 0.126487 -0.267311 0.955273 + outer loop + vertex 1.03277 0.954848 2.57115 + vertex 1.03335 0.952198 2.57033 + vertex 1.03647 0.956042 2.57099 + endloop + endfacet + facet normal 0.128121 -0.268544 0.954709 + outer loop + vertex 1.03335 0.952198 2.57033 + vertex 1.03849 0.95327 2.56994 + vertex 1.03647 0.956042 2.57099 + endloop + endfacet + facet normal 0.128632 -0.271306 0.953859 + outer loop + vertex 1.03359 0.948298 2.56919 + vertex 1.03849 0.95327 2.56994 + vertex 1.03335 0.952198 2.57033 + endloop + endfacet + facet normal 0.128464 -0.27115 0.953926 + outer loop + vertex 1.03874 0.94854 2.56856 + vertex 1.03849 0.95327 2.56994 + vertex 1.03359 0.948298 2.56919 + endloop + endfacet + facet normal 0.128472 -0.271818 0.953735 + outer loop + vertex 1.03397 0.94383 2.56786 + vertex 1.03874 0.94854 2.56856 + vertex 1.03359 0.948298 2.56919 + endloop + endfacet + facet normal 0.126458 -0.272048 0.953938 + outer loop + vertex 1.03397 0.94383 2.56786 + vertex 1.03359 0.948298 2.56919 + vertex 1.02876 0.943591 2.56849 + endloop + endfacet + facet normal 0.126443 -0.27071 0.954321 + outer loop + vertex 1.02928 0.938894 2.56709 + vertex 1.03397 0.94383 2.56786 + vertex 1.02876 0.943591 2.56849 + endloop + endfacet + facet normal 0.125371 -0.270858 0.95442 + outer loop + vertex 1.02928 0.938894 2.56709 + vertex 1.02876 0.943591 2.56849 + vertex 1.02399 0.938878 2.56778 + endloop + endfacet + facet normal 0.125471 -0.267828 0.955262 + outer loop + vertex 1.02928 0.938894 2.56709 + vertex 1.02399 0.938878 2.56778 + vertex 1.02452 0.935004 2.56662 + endloop + endfacet + facet normal 0.127793 -0.27054 0.954189 + outer loop + vertex 1.02782 0.934949 2.56616 + vertex 1.02928 0.938894 2.56709 + vertex 1.02452 0.935004 2.56662 + endloop + endfacet + facet normal 0.127797 -0.270478 0.954206 + outer loop + vertex 1.02782 0.934949 2.56616 + vertex 1.02452 0.935004 2.56662 + vertex 1.02521 0.93237 2.56578 + endloop + endfacet + facet normal 0.129998 -0.272578 0.953311 + outer loop + vertex 1.02842 0.932294 2.56532 + vertex 1.02782 0.934949 2.56616 + vertex 1.02521 0.93237 2.56578 + endloop + endfacet + facet normal 0.129883 -0.274387 0.952808 + outer loop + vertex 1.02521 0.93237 2.56578 + vertex 1.02355 0.928389 2.56486 + vertex 1.02842 0.932294 2.56532 + endloop + endfacet + facet normal 0.128447 -0.272673 0.953494 + outer loop + vertex 1.02842 0.932294 2.56532 + vertex 1.02355 0.928389 2.56486 + vertex 1.0287 0.928376 2.56416 + endloop + endfacet + facet normal 0.129429 -0.272572 0.95339 + outer loop + vertex 1.0287 0.928376 2.56416 + vertex 1.03349 0.933305 2.56492 + vertex 1.02842 0.932294 2.56532 + endloop + endfacet + facet normal 0.129259 -0.271601 0.95369 + outer loop + vertex 1.02842 0.932294 2.56532 + vertex 1.03349 0.933305 2.56492 + vertex 1.03149 0.936148 2.566 + endloop + endfacet + facet normal 0.129608 -0.271363 0.953711 + outer loop + vertex 1.03514 0.937294 2.56583 + vertex 1.03149 0.936148 2.566 + vertex 1.03349 0.933305 2.56492 + endloop + endfacet + facet normal 0.129581 -0.271353 0.953717 + outer loop + vertex 1.03514 0.937294 2.56583 + vertex 1.03349 0.933305 2.56492 + vertex 1.03819 0.937015 2.56534 + endloop + endfacet + facet normal 0.129412 -0.272612 0.953381 + outer loop + vertex 1.03819 0.937015 2.56534 + vertex 1.03774 0.939797 2.5662 + vertex 1.03514 0.937294 2.56583 + endloop + endfacet + facet normal 0.129728 -0.272921 0.95325 + outer loop + vertex 1.03774 0.939797 2.5662 + vertex 1.03449 0.939966 2.56669 + vertex 1.03514 0.937294 2.56583 + endloop + endfacet + facet normal 0.129683 -0.273403 0.953118 + outer loop + vertex 1.03774 0.939797 2.5662 + vertex 1.03925 0.943797 2.56714 + vertex 1.03449 0.939966 2.56669 + endloop + endfacet + facet normal 0.129444 -0.27312 0.953231 + outer loop + vertex 1.03925 0.943797 2.56714 + vertex 1.03397 0.94383 2.56786 + vertex 1.03449 0.939966 2.56669 + endloop + endfacet + facet normal 0.130049 -0.272493 0.953328 + outer loop + vertex 1.03774 0.939797 2.5662 + vertex 1.03819 0.937015 2.56534 + vertex 1.04145 0.940808 2.56598 + endloop + endfacet + facet normal 0.128815 -0.270425 0.954084 + outer loop + vertex 1.03819 0.937015 2.56534 + vertex 1.03349 0.933305 2.56492 + vertex 1.0384 0.933138 2.56421 + endloop + endfacet + facet normal 0.130178 -0.270305 0.953933 + outer loop + vertex 1.0384 0.933138 2.56421 + vertex 1.04263 0.937517 2.56488 + vertex 1.03819 0.937015 2.56534 + endloop + endfacet + facet normal 0.130281 -0.270399 0.953893 + outer loop + vertex 1.0434 0.933543 2.56364 + vertex 1.04263 0.937517 2.56488 + vertex 1.0384 0.933138 2.56421 + endloop + endfacet + facet normal 0.128865 -0.26975 0.954269 + outer loop + vertex 1.03381 0.928559 2.56354 + vertex 1.0384 0.933138 2.56421 + vertex 1.03349 0.933305 2.56492 + endloop + endfacet + facet normal 0.127381 -0.268351 0.954862 + outer loop + vertex 1.03891 0.928834 2.56294 + vertex 1.0384 0.933138 2.56421 + vertex 1.03381 0.928559 2.56354 + endloop + endfacet + facet normal 0.130048 -0.272837 0.95323 + outer loop + vertex 1.03514 0.937294 2.56583 + vertex 1.03449 0.939966 2.56669 + vertex 1.03149 0.936148 2.566 + endloop + endfacet + facet normal 0.129 -0.272078 0.953589 + outer loop + vertex 1.03449 0.939966 2.56669 + vertex 1.02928 0.938894 2.56709 + vertex 1.03149 0.936148 2.566 + endloop + endfacet + facet normal 0.126579 -0.269976 0.954511 + outer loop + vertex 1.03381 0.928559 2.56354 + vertex 1.03349 0.933305 2.56492 + vertex 1.0287 0.928376 2.56416 + endloop + endfacet + facet normal 0.12658 -0.27101 0.954218 + outer loop + vertex 1.02908 0.923888 2.56284 + vertex 1.03381 0.928559 2.56354 + vertex 1.0287 0.928376 2.56416 + endloop + endfacet + facet normal 0.125805 -0.271098 0.954295 + outer loop + vertex 1.02908 0.923888 2.56284 + vertex 1.0287 0.928376 2.56416 + vertex 1.02383 0.923659 2.56347 + endloop + endfacet + facet normal 0.125803 -0.270907 0.95435 + outer loop + vertex 1.02427 0.918955 2.56207 + vertex 1.02908 0.923888 2.56284 + vertex 1.02383 0.923659 2.56347 + endloop + endfacet + facet normal 0.127044 -0.270755 0.954228 + outer loop + vertex 1.02427 0.918955 2.56207 + vertex 1.02383 0.923659 2.56347 + vertex 1.01893 0.918915 2.56277 + endloop + endfacet + facet normal 0.127094 -0.269051 0.954703 + outer loop + vertex 1.02427 0.918955 2.56207 + vertex 1.01893 0.918915 2.56277 + vertex 1.01935 0.915051 2.56163 + endloop + endfacet + facet normal 0.126997 -0.270708 0.954248 + outer loop + vertex 1.01893 0.918915 2.56277 + vertex 1.02383 0.923659 2.56347 + vertex 1.01861 0.923391 2.56408 + endloop + endfacet + facet normal 0.122279 -0.271184 0.954729 + outer loop + vertex 1.01893 0.918915 2.56277 + vertex 1.01861 0.923391 2.56408 + vertex 1.01369 0.918647 2.56337 + endloop + endfacet + facet normal 0.122983 -0.27187 0.954443 + outer loop + vertex 1.01369 0.918647 2.56337 + vertex 1.01861 0.923391 2.56408 + vertex 1.01338 0.923397 2.56476 + endloop + endfacet + facet normal 0.122859 -0.27516 0.953516 + outer loop + vertex 1.01836 0.927301 2.56524 + vertex 1.01338 0.923397 2.56476 + vertex 1.01861 0.923391 2.56408 + endloop + endfacet + facet normal 0.128039 -0.274669 0.952976 + outer loop + vertex 1.01861 0.923391 2.56408 + vertex 1.02355 0.928389 2.56486 + vertex 1.01836 0.927301 2.56524 + endloop + endfacet + facet normal 0.127925 -0.274059 0.953167 + outer loop + vertex 1.01836 0.927301 2.56524 + vertex 1.02355 0.928389 2.56486 + vertex 1.02149 0.931154 2.56593 + endloop + endfacet + facet normal 0.12677 -0.273193 0.95357 + outer loop + vertex 1.01778 0.929959 2.56608 + vertex 1.01836 0.927301 2.56524 + vertex 1.02149 0.931154 2.56593 + endloop + endfacet + facet normal 0.125041 -0.267594 0.955384 + outer loop + vertex 1.02149 0.931154 2.56593 + vertex 1.01927 0.933915 2.567 + vertex 1.01778 0.929959 2.56608 + endloop + endfacet + facet normal 0.120899 -0.266243 0.956294 + outer loop + vertex 1.01778 0.929959 2.56608 + vertex 1.01927 0.933915 2.567 + vertex 1.01444 0.930049 2.56653 + endloop + endfacet + facet normal 0.120728 -0.26895 0.955558 + outer loop + vertex 1.01778 0.929959 2.56608 + vertex 1.01444 0.930049 2.56653 + vertex 1.0151 0.927396 2.5657 + endloop + endfacet + facet normal 0.117369 -0.269837 0.955726 + outer loop + vertex 1.0151 0.927396 2.5657 + vertex 1.01444 0.930049 2.56653 + vertex 1.0113 0.926212 2.56583 + endloop + endfacet + facet normal 0.118741 -0.263667 0.957278 + outer loop + vertex 1.01927 0.933915 2.567 + vertex 1.01393 0.933927 2.56766 + vertex 1.01444 0.930049 2.56653 + endloop + endfacet + facet normal 0.112908 -0.264562 0.957736 + outer loop + vertex 1.01444 0.930049 2.56653 + vertex 1.01393 0.933927 2.56766 + vertex 1.00915 0.929007 2.56687 + endloop + endfacet + facet normal 0.110749 -0.262593 0.95853 + outer loop + vertex 1.00915 0.929007 2.56687 + vertex 1.01393 0.933927 2.56766 + vertex 1.00867 0.933689 2.5682 + endloop + endfacet + facet normal 0.110746 -0.26246 0.958567 + outer loop + vertex 1.01393 0.933927 2.56766 + vertex 1.01349 0.938455 2.56895 + vertex 1.00867 0.933689 2.5682 + endloop + endfacet + facet normal 0.109391 -0.261169 0.959075 + outer loop + vertex 1.00867 0.933689 2.5682 + vertex 1.01349 0.938455 2.56895 + vertex 1.00819 0.938513 2.56957 + endloop + endfacet + facet normal 0.0966295 -0.262711 0.960024 + outer loop + vertex 1.00867 0.933689 2.5682 + vertex 1.00819 0.938513 2.56957 + vertex 1.00343 0.933396 2.56865 + endloop + endfacet + facet normal 0.0966413 -0.263077 0.959922 + outer loop + vertex 1.00403 0.929126 2.56742 + vertex 1.00867 0.933689 2.5682 + vertex 1.00343 0.933396 2.56865 + endloop + endfacet + facet normal 0.109371 -0.261637 0.958949 + outer loop + vertex 1.01316 0.942469 2.57009 + vertex 1.00819 0.938513 2.56957 + vertex 1.01349 0.938455 2.56895 + endloop + endfacet + facet normal 0.11282 -0.261269 0.95865 + outer loop + vertex 1.01349 0.938455 2.56895 + vertex 1.01836 0.943464 2.56974 + vertex 1.01316 0.942469 2.57009 + endloop + endfacet + facet normal 0.113151 -0.263192 0.958085 + outer loop + vertex 1.01316 0.942469 2.57009 + vertex 1.01836 0.943464 2.56974 + vertex 1.01629 0.946311 2.57077 + endloop + endfacet + facet normal 0.11198 -0.262306 0.958465 + outer loop + vertex 1.0126 0.945198 2.5709 + vertex 1.01316 0.942469 2.57009 + vertex 1.01629 0.946311 2.57077 + endloop + endfacet + facet normal 0.112558 -0.264289 0.957853 + outer loop + vertex 1.01629 0.946311 2.57077 + vertex 1.01415 0.949087 2.57179 + vertex 1.0126 0.945198 2.5709 + endloop + endfacet + facet normal 0.110714 -0.263647 0.958245 + outer loop + vertex 1.0126 0.945198 2.5709 + vertex 1.01415 0.949087 2.57179 + vertex 1.00942 0.945402 2.57132 + endloop + endfacet + facet normal 0.110908 -0.261696 0.958757 + outer loop + vertex 1.0126 0.945198 2.5709 + vertex 1.00942 0.945402 2.57132 + vertex 1.00991 0.942652 2.57051 + endloop + endfacet + facet normal 0.106995 -0.262471 0.95899 + outer loop + vertex 1.00991 0.942652 2.57051 + vertex 1.00942 0.945402 2.57132 + vertex 1.00605 0.941579 2.57065 + endloop + endfacet + facet normal 0.107 -0.262489 0.958984 + outer loop + vertex 1.00991 0.942652 2.57051 + vertex 1.00605 0.941579 2.57065 + vertex 1.00819 0.938513 2.56957 + endloop + endfacet + facet normal 0.0991635 -0.267727 0.958378 + outer loop + vertex 1.00255 0.937376 2.56984 + vertex 1.00819 0.938513 2.56957 + vertex 1.00605 0.941579 2.57065 + endloop + endfacet + facet normal 0.105688 -0.2614 0.959427 + outer loop + vertex 1.00942 0.945402 2.57132 + vertex 1.00482 0.944902 2.57169 + vertex 1.00605 0.941579 2.57065 + endloop + endfacet + facet normal 0.0976779 -0.26439 0.959457 + outer loop + vertex 1.00605 0.941579 2.57065 + vertex 1.00482 0.944902 2.57169 + vertex 1.00137 0.940773 2.57091 + endloop + endfacet + facet normal 0.105922 -0.264119 0.958656 + outer loop + vertex 1.00942 0.945402 2.57132 + vertex 1.00901 0.949178 2.57241 + vertex 1.00482 0.944902 2.57169 + endloop + endfacet + facet normal 0.105116 -0.263379 0.958948 + outer loop + vertex 1.00482 0.944902 2.57169 + vertex 1.00901 0.949178 2.57241 + vertex 1.00393 0.948847 2.57287 + endloop + endfacet + facet normal 0.0938663 -0.266032 0.959383 + outer loop + vertex 1.00482 0.944902 2.57169 + vertex 1.00393 0.948847 2.57287 + vertex 0.999389 0.944077 2.57199 + endloop + endfacet + facet normal 0.105233 -0.266337 0.958118 + outer loop + vertex 1.00901 0.949178 2.57241 + vertex 1.00842 0.953464 2.57366 + vertex 1.00393 0.948847 2.57287 + endloop + endfacet + facet normal 0.105686 -0.266749 0.957954 + outer loop + vertex 1.00393 0.948847 2.57287 + vertex 1.00842 0.953464 2.57366 + vertex 1.0034 0.953138 2.57413 + endloop + endfacet + facet normal 0.0941916 -0.268407 0.95869 + outer loop + vertex 1.00393 0.948847 2.57287 + vertex 1.0034 0.953138 2.57413 + vertex 0.999005 0.948736 2.57333 + endloop + endfacet + facet normal 0.110313 -0.265542 0.957768 + outer loop + vertex 1.00901 0.949178 2.57241 + vertex 1.01363 0.953748 2.57314 + vertex 1.00842 0.953464 2.57366 + endloop + endfacet + facet normal 0.110327 -0.266065 0.957621 + outer loop + vertex 1.01363 0.953748 2.57314 + vertex 1.01316 0.958579 2.57454 + vertex 1.00842 0.953464 2.57366 + endloop + endfacet + facet normal 0.110679 -0.26637 0.957495 + outer loop + vertex 1.00842 0.953464 2.57366 + vertex 1.01316 0.958579 2.57454 + vertex 1.00764 0.957467 2.57487 + endloop + endfacet + facet normal 0.110492 -0.265711 0.9577 + outer loop + vertex 1.01415 0.949087 2.57179 + vertex 1.01363 0.953748 2.57314 + vertex 1.00901 0.949178 2.57241 + endloop + endfacet + facet normal 0.112496 -0.265443 0.957541 + outer loop + vertex 1.01415 0.949087 2.57179 + vertex 1.01887 0.953945 2.57258 + vertex 1.01363 0.953748 2.57314 + endloop + endfacet + facet normal 0.11249 -0.264624 0.957768 + outer loop + vertex 1.01887 0.953945 2.57258 + vertex 1.01842 0.958481 2.57389 + vertex 1.01363 0.953748 2.57314 + endloop + endfacet + facet normal 0.110602 -0.26351 0.958295 + outer loop + vertex 1.01415 0.949087 2.57179 + vertex 1.00901 0.949178 2.57241 + vertex 1.00942 0.945402 2.57132 + endloop + endfacet + facet normal 0.112018 -0.264689 0.957806 + outer loop + vertex 1.01936 0.950088 2.57146 + vertex 1.01415 0.949087 2.57179 + vertex 1.01629 0.946311 2.57077 + endloop + endfacet + facet normal 0.111602 -0.26239 0.958487 + outer loop + vertex 1.01316 0.942469 2.57009 + vertex 1.0126 0.945198 2.5709 + vertex 1.00991 0.942652 2.57051 + endloop + endfacet + facet normal 0.115539 -0.263753 0.957646 + outer loop + vertex 1.01873 0.938656 2.56838 + vertex 1.01836 0.943464 2.56974 + vertex 1.01349 0.938455 2.56895 + endloop + endfacet + facet normal 0.111445 -0.264124 0.958029 + outer loop + vertex 1.00991 0.942652 2.57051 + vertex 1.00819 0.938513 2.56957 + vertex 1.01316 0.942469 2.57009 + endloop + endfacet + facet normal 0.115524 -0.261878 0.958162 + outer loop + vertex 1.01393 0.933927 2.56766 + vertex 1.01873 0.938656 2.56838 + vertex 1.01349 0.938455 2.56895 + endloop + endfacet + facet normal 0.118696 -0.264914 0.956939 + outer loop + vertex 1.01927 0.933915 2.567 + vertex 1.01873 0.938656 2.56838 + vertex 1.01393 0.933927 2.56766 + endloop + endfacet + facet normal 0.120286 -0.264695 0.956801 + outer loop + vertex 1.01927 0.933915 2.567 + vertex 1.02399 0.938878 2.56778 + vertex 1.01873 0.938656 2.56838 + endloop + endfacet + facet normal 0.120314 -0.267453 0.95603 + outer loop + vertex 1.02399 0.938878 2.56778 + vertex 1.02356 0.943378 2.56909 + vertex 1.01873 0.938656 2.56838 + endloop + endfacet + facet normal 0.124107 -0.268314 0.955304 + outer loop + vertex 1.02452 0.935004 2.56662 + vertex 1.01927 0.933915 2.567 + vertex 1.02149 0.931154 2.56593 + endloop + endfacet + facet normal 0.125374 -0.273526 0.953659 + outer loop + vertex 1.01836 0.927301 2.56524 + vertex 1.01778 0.929959 2.56608 + vertex 1.0151 0.927396 2.5657 + endloop + endfacet + facet normal 0.125077 -0.277858 0.952445 + outer loop + vertex 1.0151 0.927396 2.5657 + vertex 1.01338 0.923397 2.56476 + vertex 1.01836 0.927301 2.56524 + endloop + endfacet + facet normal 0.127049 -0.273753 0.953372 + outer loop + vertex 1.02383 0.923659 2.56347 + vertex 1.02355 0.928389 2.56486 + vertex 1.01861 0.923391 2.56408 + endloop + endfacet + facet normal 0.128408 -0.273627 0.953226 + outer loop + vertex 1.02383 0.923659 2.56347 + vertex 1.0287 0.928376 2.56416 + vertex 1.02355 0.928389 2.56486 + endloop + endfacet + facet normal 0.128278 -0.273806 0.953192 + outer loop + vertex 1.02521 0.93237 2.56578 + vertex 1.02149 0.931154 2.56593 + vertex 1.02355 0.928389 2.56486 + endloop + endfacet + facet normal 0.130441 -0.272468 0.953282 + outer loop + vertex 1.02782 0.934949 2.56616 + vertex 1.02842 0.932294 2.56532 + vertex 1.03149 0.936148 2.566 + endloop + endfacet + facet normal 0.12728 -0.270622 0.954235 + outer loop + vertex 1.02521 0.93237 2.56578 + vertex 1.02452 0.935004 2.56662 + vertex 1.02149 0.931154 2.56593 + endloop + endfacet + facet normal 0.130062 -0.271259 0.953678 + outer loop + vertex 1.03149 0.936148 2.566 + vertex 1.02928 0.938894 2.56709 + vertex 1.02782 0.934949 2.56616 + endloop + endfacet + facet normal 0.12406 -0.268059 0.955381 + outer loop + vertex 1.02452 0.935004 2.56662 + vertex 1.02399 0.938878 2.56778 + vertex 1.01927 0.933915 2.567 + endloop + endfacet + facet normal 0.121632 -0.267294 0.955908 + outer loop + vertex 1.02399 0.938878 2.56778 + vertex 1.02876 0.943591 2.56849 + vertex 1.02356 0.943378 2.56909 + endloop + endfacet + facet normal 0.129197 -0.273159 0.953253 + outer loop + vertex 1.03449 0.939966 2.56669 + vertex 1.03397 0.94383 2.56786 + vertex 1.02928 0.938894 2.56709 + endloop + endfacet + facet normal 0.124578 -0.270231 0.954702 + outer loop + vertex 1.02876 0.943591 2.56849 + vertex 1.03359 0.948298 2.56919 + vertex 1.02844 0.948331 2.56987 + endloop + endfacet + facet normal 0.12946 -0.272758 0.953333 + outer loop + vertex 1.03925 0.943797 2.56714 + vertex 1.03874 0.94854 2.56856 + vertex 1.03397 0.94383 2.56786 + endloop + endfacet + facet normal 0.124515 -0.271696 0.954294 + outer loop + vertex 1.03335 0.952198 2.57033 + vertex 1.02844 0.948331 2.56987 + vertex 1.03359 0.948298 2.56919 + endloop + endfacet + facet normal 0.116931 -0.263935 0.957427 + outer loop + vertex 1.03012 0.952293 2.57078 + vertex 1.02946 0.95494 2.57159 + vertex 1.02638 0.951122 2.57091 + endloop + endfacet + facet normal 0.115561 -0.26291 0.957875 + outer loop + vertex 1.02946 0.95494 2.57159 + vertex 1.02418 0.953899 2.57194 + vertex 1.02638 0.951122 2.57091 + endloop + endfacet + facet normal 0.114098 -0.264021 0.957744 + outer loop + vertex 1.02638 0.951122 2.57091 + vertex 1.02418 0.953899 2.57194 + vertex 1.02266 0.949972 2.57104 + endloop + endfacet + facet normal 0.114832 -0.266479 0.956976 + outer loop + vertex 1.02266 0.949972 2.57104 + vertex 1.02325 0.947313 2.57023 + vertex 1.02638 0.951122 2.57091 + endloop + endfacet + facet normal 0.121658 -0.270518 0.954997 + outer loop + vertex 1.02876 0.943591 2.56849 + vertex 1.02844 0.948331 2.56987 + vertex 1.02356 0.943378 2.56909 + endloop + endfacet + facet normal 0.116381 -0.263665 0.957568 + outer loop + vertex 1.01873 0.938656 2.56838 + vertex 1.02356 0.943378 2.56909 + vertex 1.01836 0.943464 2.56974 + endloop + endfacet + facet normal 0.112127 -0.263908 0.958008 + outer loop + vertex 1.02001 0.94745 2.57065 + vertex 1.01629 0.946311 2.57077 + vertex 1.01836 0.943464 2.56974 + endloop + endfacet + facet normal 0.112456 -0.265019 0.957663 + outer loop + vertex 1.02001 0.94745 2.57065 + vertex 1.01936 0.950088 2.57146 + vertex 1.01629 0.946311 2.57077 + endloop + endfacet + facet normal 0.112083 -0.265067 0.957694 + outer loop + vertex 1.01936 0.950088 2.57146 + vertex 1.01887 0.953945 2.57258 + vertex 1.01415 0.949087 2.57179 + endloop + endfacet + facet normal 0.115626 -0.264238 0.957501 + outer loop + vertex 1.01887 0.953945 2.57258 + vertex 1.02365 0.958662 2.5733 + vertex 1.01842 0.958481 2.57389 + endloop + endfacet + facet normal 0.115049 -0.260029 0.958723 + outer loop + vertex 1.02946 0.95494 2.57159 + vertex 1.02893 0.958856 2.57271 + vertex 1.02418 0.953899 2.57194 + endloop + endfacet + facet normal 0.11965 -0.260444 0.958046 + outer loop + vertex 1.02365 0.958662 2.5733 + vertex 1.02846 0.963444 2.574 + vertex 1.02324 0.963517 2.57468 + endloop + endfacet + facet normal 0.119768 -0.257441 0.958843 + outer loop + vertex 1.03426 0.958819 2.57204 + vertex 1.0337 0.96362 2.5734 + vertex 1.02893 0.958856 2.57271 + endloop + endfacet + facet normal 0.12137 -0.257213 0.958703 + outer loop + vertex 1.03426 0.958819 2.57204 + vertex 1.03897 0.963799 2.57278 + vertex 1.0337 0.96362 2.5734 + endloop + endfacet + facet normal 0.122004 -0.255904 0.958972 + outer loop + vertex 1.02846 0.963444 2.574 + vertex 1.03327 0.968499 2.57474 + vertex 1.02809 0.967457 2.57512 + endloop + endfacet + facet normal 0.121368 -0.256318 0.958943 + outer loop + vertex 1.03897 0.963799 2.57278 + vertex 1.03849 0.968386 2.57406 + vertex 1.0337 0.96362 2.5734 + endloop + endfacet + facet normal 0.121462 -0.252887 0.959841 + outer loop + vertex 1.02809 0.967457 2.57512 + vertex 1.03327 0.968499 2.57474 + vertex 1.03116 0.971326 2.57575 + endloop + endfacet + facet normal 0.123755 -0.254588 0.959098 + outer loop + vertex 1.02746 0.97012 2.57591 + vertex 1.02809 0.967457 2.57512 + vertex 1.03116 0.971326 2.57575 + endloop + endfacet + facet normal 0.118878 -0.256812 0.959122 + outer loop + vertex 1.03753 0.975082 2.57595 + vertex 1.03423 0.975134 2.57638 + vertex 1.03489 0.972538 2.5756 + endloop + endfacet + facet normal 0.123532 -0.253877 0.959315 + outer loop + vertex 1.03116 0.971326 2.57575 + vertex 1.02899 0.974 2.57674 + vertex 1.02746 0.97012 2.57591 + endloop + endfacet + facet normal 0.119855 -0.256159 0.959175 + outer loop + vertex 1.02809 0.967457 2.57512 + vertex 1.02324 0.963517 2.57468 + vertex 1.02846 0.963444 2.574 + endloop + endfacet + facet normal 0.119273 -0.254342 0.959731 + outer loop + vertex 1.02484 0.967552 2.57556 + vertex 1.02418 0.970152 2.57633 + vertex 1.02115 0.966343 2.5757 + endloop + endfacet + facet normal 0.118196 -0.25354 0.960077 + outer loop + vertex 1.02418 0.970152 2.57633 + vertex 1.01902 0.96907 2.57668 + vertex 1.02115 0.966343 2.5757 + endloop + endfacet + facet normal 0.115612 -0.260892 0.95842 + outer loop + vertex 1.02365 0.958662 2.5733 + vertex 1.02324 0.963517 2.57468 + vertex 1.01842 0.958481 2.57389 + endloop + endfacet + facet normal 0.113589 -0.26567 0.957349 + outer loop + vertex 1.01363 0.953748 2.57314 + vertex 1.01842 0.958481 2.57389 + vertex 1.01316 0.958579 2.57454 + endloop + endfacet + facet normal 0.111252 -0.26448 0.957953 + outer loop + vertex 1.01485 0.96268 2.57547 + vertex 1.01107 0.961643 2.57563 + vertex 1.01316 0.958579 2.57454 + endloop + endfacet + facet normal 0.118689 -0.260821 0.958063 + outer loop + vertex 1.01749 0.965198 2.57584 + vertex 1.01807 0.962492 2.57504 + vertex 1.02115 0.966343 2.5757 + endloop + endfacet + facet normal 0.109759 -0.258782 0.959679 + outer loop + vertex 1.01485 0.96268 2.57547 + vertex 1.01434 0.965405 2.57627 + vertex 1.01107 0.961643 2.57563 + endloop + endfacet + facet normal 0.11681 -0.254581 0.959971 + outer loop + vertex 1.02115 0.966343 2.5757 + vertex 1.01902 0.96907 2.57668 + vertex 1.01749 0.965198 2.57584 + endloop + endfacet + facet normal 0.117986 -0.252436 0.960393 + outer loop + vertex 1.02418 0.970152 2.57633 + vertex 1.02376 0.973936 2.57738 + vertex 1.01902 0.96907 2.57668 + endloop + endfacet + facet normal 0.118531 -0.250765 0.960764 + outer loop + vertex 1.02376 0.973936 2.57738 + vertex 1.02862 0.978627 2.57801 + vertex 1.02351 0.978479 2.5786 + endloop + endfacet + facet normal 0.118532 -0.250051 0.96095 + outer loop + vertex 1.02862 0.978627 2.57801 + vertex 1.02848 0.98324 2.57922 + vertex 1.02351 0.978479 2.5786 + endloop + endfacet + facet normal 0.11086 -0.250014 0.961875 + outer loop + vertex 1.01396 0.969155 2.5773 + vertex 1.01863 0.973678 2.57794 + vertex 1.01353 0.973551 2.57849 + endloop + endfacet + facet normal 0.108414 -0.253589 0.961217 + outer loop + vertex 1.01434 0.965405 2.57627 + vertex 1.01396 0.969155 2.5773 + vertex 1.0098 0.964888 2.57664 + endloop + endfacet + facet normal 0.108817 -0.258015 0.959993 + outer loop + vertex 1.01434 0.965405 2.57627 + vertex 1.0098 0.964888 2.57664 + vertex 1.01107 0.961643 2.57563 + endloop + endfacet + facet normal 0.110432 -0.265022 0.957898 + outer loop + vertex 1.00764 0.957467 2.57487 + vertex 1.01316 0.958579 2.57454 + vertex 1.01107 0.961643 2.57563 + endloop + endfacet + facet normal 0.105712 -0.267425 0.957762 + outer loop + vertex 1.00842 0.953464 2.57366 + vertex 1.00764 0.957467 2.57487 + vertex 1.0034 0.953138 2.57413 + endloop + endfacet + facet normal 0.107031 -0.264841 0.958334 + outer loop + vertex 1.00274 0.959851 2.57607 + vertex 1.00316 0.95703 2.57525 + vertex 1.00648 0.960792 2.57591 + endloop + endfacet + facet normal 0.0807213 -0.261462 0.961832 + outer loop + vertex 1.00004 0.957381 2.57567 + vertex 0.999561 0.960183 2.57647 + vertex 0.996171 0.956421 2.57573 + endloop + endfacet + facet normal 0.104678 -0.255012 0.961255 + outer loop + vertex 1.00648 0.960792 2.57591 + vertex 1.0043 0.963817 2.57695 + vertex 1.00274 0.959851 2.57607 + endloop + endfacet + facet normal 0.0780461 -0.252713 0.964388 + outer loop + vertex 0.999561 0.960183 2.57647 + vertex 0.999169 0.96402 2.57751 + vertex 0.995028 0.959856 2.57675 + endloop + endfacet + facet normal 0.100344 -0.249836 0.963075 + outer loop + vertex 1.0043 0.963817 2.57695 + vertex 1.00887 0.968802 2.57777 + vertex 1.00374 0.968509 2.57823 + endloop + endfacet + facet normal 0.0781819 -0.25284 0.964344 + outer loop + vertex 0.995028 0.959856 2.57675 + vertex 0.999169 0.96402 2.57751 + vertex 0.994214 0.963837 2.57786 + endloop + endfacet + facet normal 0.0784242 -0.259532 0.962545 + outer loop + vertex 0.999561 0.960183 2.57647 + vertex 0.995028 0.959856 2.57675 + vertex 0.996171 0.956421 2.57573 + endloop + endfacet + facet normal 0.0828995 -0.270423 0.959166 + outer loop + vertex 1.00004 0.957381 2.57567 + vertex 0.996171 0.956421 2.57573 + vertex 0.998361 0.953325 2.57467 + endloop + endfacet + facet normal 0.0938953 -0.26813 0.958796 + outer loop + vertex 0.999005 0.948736 2.57333 + vertex 1.0034 0.953138 2.57413 + vertex 0.998361 0.953325 2.57467 + endloop + endfacet + facet normal 0.0941978 -0.266327 0.959269 + outer loop + vertex 0.999389 0.944077 2.57199 + vertex 1.00393 0.948847 2.57287 + vertex 0.999005 0.948736 2.57333 + endloop + endfacet + facet normal 0.0931672 -0.260892 0.960862 + outer loop + vertex 1.00482 0.944902 2.57169 + vertex 0.999389 0.944077 2.57199 + vertex 1.00137 0.940773 2.57091 + endloop + endfacet + facet normal 0.0643553 -0.281194 0.957491 + outer loop + vertex 0.997918 0.937099 2.57015 + vertex 0.997539 0.940034 2.57103 + vertex 0.994893 0.937789 2.57055 + endloop + endfacet + facet normal 0.0980671 -0.26688 0.958727 + outer loop + vertex 1.00137 0.940773 2.57091 + vertex 1.00255 0.937376 2.56984 + vertex 1.00605 0.941579 2.57065 + endloop + endfacet + facet normal 0.0985326 -0.264365 0.959376 + outer loop + vertex 1.00343 0.933396 2.56865 + vertex 1.00819 0.938513 2.56957 + vertex 1.00255 0.937376 2.56984 + endloop + endfacet + facet normal 0.0978217 -0.264204 0.959493 + outer loop + vertex 1.00915 0.929007 2.56687 + vertex 1.00867 0.933689 2.5682 + vertex 1.00403 0.929126 2.56742 + endloop + endfacet + facet normal 0.113297 -0.266747 0.957084 + outer loop + vertex 1.01444 0.930049 2.56653 + vertex 1.00915 0.929007 2.56687 + vertex 1.0113 0.926212 2.56583 + endloop + endfacet + facet normal 0.102203 -0.282677 0.953755 + outer loop + vertex 1.00809 0.922359 2.56509 + vertex 1.00752 0.925065 2.56595 + vertex 1.00479 0.922539 2.56549 + endloop + endfacet + facet normal 0.119105 -0.275622 0.953859 + outer loop + vertex 1.0151 0.927396 2.5657 + vertex 1.0113 0.926212 2.56583 + vertex 1.01338 0.923397 2.56476 + endloop + endfacet + facet normal 0.100958 -0.296362 0.949725 + outer loop + vertex 1.00479 0.922539 2.56549 + vertex 1.00322 0.918583 2.56443 + vertex 1.00809 0.922359 2.56509 + endloop + endfacet + facet normal 0.0748615 -0.287348 0.954896 + outer loop + vertex 1.00479 0.922539 2.56549 + vertex 1.00099 0.921609 2.56551 + vertex 1.00322 0.918583 2.56443 + endloop + endfacet + facet normal 0.0552393 -0.300798 0.952087 + outer loop + vertex 0.997798 0.917718 2.56447 + vertex 1.00322 0.918583 2.56443 + vertex 1.00099 0.921609 2.56551 + endloop + endfacet + facet normal 0.0389674 -0.288687 0.95663 + outer loop + vertex 0.996296 0.921166 2.56557 + vertex 0.997798 0.917718 2.56447 + vertex 1.00099 0.921609 2.56551 + endloop + endfacet + facet normal 0.0388404 -0.287285 0.957057 + outer loop + vertex 1.00099 0.921609 2.56551 + vertex 0.999877 0.925032 2.56658 + vertex 0.996296 0.921166 2.56557 + endloop + endfacet + facet normal 0.10848 -0.273227 0.955813 + outer loop + vertex 1.01369 0.918647 2.56337 + vertex 1.01338 0.923397 2.56476 + vertex 1.00848 0.918447 2.5639 + endloop + endfacet + facet normal 0.122187 -0.266282 0.956119 + outer loop + vertex 1.0141 0.913927 2.562 + vertex 1.01893 0.918915 2.56277 + vertex 1.01369 0.918647 2.56337 + endloop + endfacet + facet normal 0.125481 -0.269274 0.954854 + outer loop + vertex 1.01935 0.915051 2.56163 + vertex 1.01893 0.918915 2.56277 + vertex 1.0141 0.913927 2.562 + endloop + endfacet + facet normal 0.129748 -0.272251 0.953438 + outer loop + vertex 1.02272 0.915018 2.56116 + vertex 1.02427 0.918955 2.56207 + vertex 1.01935 0.915051 2.56163 + endloop + endfacet + facet normal 0.124749 -0.270543 0.954591 + outer loop + vertex 1.02651 0.916194 2.561 + vertex 1.02427 0.918955 2.56207 + vertex 1.02272 0.915018 2.56116 + endloop + endfacet + facet normal 0.123826 -0.271258 0.954508 + outer loop + vertex 1.02959 0.91999 2.56168 + vertex 1.02427 0.918955 2.56207 + vertex 1.02651 0.916194 2.561 + endloop + endfacet + facet normal 0.128859 -0.284415 0.950002 + outer loop + vertex 1.02272 0.915018 2.56116 + vertex 1.02341 0.912405 2.56028 + vertex 1.02651 0.916194 2.561 + endloop + endfacet + facet normal 0.143358 -0.326008 0.934434 + outer loop + vertex 1.02006 0.912442 2.56076 + vertex 1.01629 0.911176 2.56089 + vertex 1.01867 0.908572 2.55962 + endloop + endfacet + facet normal 0.122766 -0.279849 0.952162 + outer loop + vertex 1.02341 0.912405 2.56028 + vertex 1.02863 0.913405 2.5599 + vertex 1.02651 0.916194 2.561 + endloop + endfacet + facet normal 0.124967 -0.312445 0.94168 + outer loop + vertex 1.03424 0.908603 2.55759 + vertex 1.03365 0.91317 2.55918 + vertex 1.02908 0.908941 2.55838 + endloop + endfacet + facet normal 0.11904 -0.362183 0.924474 + outer loop + vertex 1.03424 0.908603 2.55759 + vertex 1.02908 0.908941 2.55838 + vertex 1.02951 0.905135 2.55684 + endloop + endfacet + facet normal 0.106521 -0.363936 0.925313 + outer loop + vertex 1.02951 0.905135 2.55684 + vertex 1.02908 0.908941 2.55838 + vertex 1.025 0.904999 2.5573 + endloop + endfacet + facet normal 0.122983 -0.279692 0.952181 + outer loop + vertex 1.03026 0.917301 2.56084 + vertex 1.02651 0.916194 2.561 + vertex 1.02863 0.913405 2.5599 + endloop + endfacet + facet normal 0.119748 -0.26819 0.955895 + outer loop + vertex 1.03026 0.917301 2.56084 + vertex 1.02959 0.91999 2.56168 + vertex 1.02651 0.916194 2.561 + endloop + endfacet + facet normal 0.123387 -0.268696 0.95529 + outer loop + vertex 1.02959 0.91999 2.56168 + vertex 1.02908 0.923888 2.56284 + vertex 1.02427 0.918955 2.56207 + endloop + endfacet + facet normal 0.134733 -0.268789 0.953729 + outer loop + vertex 1.04427 0.925521 2.56126 + vertex 1.0439 0.929269 2.56237 + vertex 1.03983 0.924944 2.56173 + endloop + endfacet + facet normal 0.130163 -0.267947 0.9546 + outer loop + vertex 1.03891 0.928834 2.56294 + vertex 1.0434 0.933543 2.56364 + vertex 1.0384 0.933138 2.56421 + endloop + endfacet + facet normal 0.128904 -0.27114 0.953869 + outer loop + vertex 1.04855 0.933884 2.56305 + vertex 1.04827 0.938788 2.56448 + vertex 1.0434 0.933543 2.56364 + endloop + endfacet + facet normal 0.123454 -0.279848 0.952074 + outer loop + vertex 1.05413 0.9303 2.5613 + vertex 1.05374 0.934078 2.56246 + vertex 1.04892 0.929249 2.56166 + endloop + endfacet + facet normal 0.102052 -0.275121 0.955978 + outer loop + vertex 1.05907 0.933997 2.56187 + vertex 1.05865 0.938563 2.56323 + vertex 1.05374 0.934078 2.56246 + endloop + endfacet + facet normal 0.101697 -0.282624 0.953825 + outer loop + vertex 1.05907 0.933997 2.56187 + vertex 1.05374 0.934078 2.56246 + vertex 1.05413 0.9303 2.5613 + endloop + endfacet + facet normal 0.10482 -0.286569 0.952308 + outer loop + vertex 1.05749 0.93018 2.56089 + vertex 1.05907 0.933997 2.56187 + vertex 1.05413 0.9303 2.5613 + endloop + endfacet + facet normal 0.116763 -0.272191 0.955133 + outer loop + vertex 1.04855 0.933884 2.56305 + vertex 1.05354 0.938577 2.56377 + vertex 1.04827 0.938788 2.56448 + endloop + endfacet + facet normal 0.129217 -0.275577 0.952555 + outer loop + vertex 1.05002 0.942991 2.56544 + vertex 1.04933 0.94556 2.56627 + vertex 1.04607 0.941764 2.56562 + endloop + endfacet + facet normal 0.128494 -0.270783 0.954026 + outer loop + vertex 1.0434 0.933543 2.56364 + vertex 1.04827 0.938788 2.56448 + vertex 1.04263 0.937517 2.56488 + endloop + endfacet + facet normal 0.130379 -0.272756 0.953208 + outer loop + vertex 1.03819 0.937015 2.56534 + vertex 1.04263 0.937517 2.56488 + vertex 1.04145 0.940808 2.56598 + endloop + endfacet + facet normal 0.129457 -0.275768 0.952467 + outer loop + vertex 1.04933 0.94556 2.56627 + vertex 1.04477 0.944958 2.56672 + vertex 1.04607 0.941764 2.56562 + endloop + endfacet + facet normal 0.130333 -0.273614 0.952968 + outer loop + vertex 1.04145 0.940808 2.56598 + vertex 1.03925 0.943797 2.56714 + vertex 1.03774 0.939797 2.5662 + endloop + endfacet + facet normal 0.129182 -0.272796 0.953359 + outer loop + vertex 1.03925 0.943797 2.56714 + vertex 1.04389 0.94885 2.56795 + vertex 1.03874 0.94854 2.56856 + endloop + endfacet + facet normal 0.129119 -0.270398 0.954051 + outer loop + vertex 1.04389 0.94885 2.56795 + vertex 1.04357 0.953279 2.56925 + vertex 1.03874 0.94854 2.56856 + endloop + endfacet + facet normal 0.12959 -0.277065 0.952072 + outer loop + vertex 1.04933 0.94556 2.56627 + vertex 1.04894 0.949208 2.56739 + vertex 1.04477 0.944958 2.56672 + endloop + endfacet + facet normal 0.126676 -0.270652 0.954306 + outer loop + vertex 1.04389 0.94885 2.56795 + vertex 1.04862 0.95355 2.56866 + vertex 1.04357 0.953279 2.56925 + endloop + endfacet + facet normal 0.120168 -0.272885 0.954512 + outer loop + vertex 1.05379 0.949014 2.56672 + vertex 1.05372 0.953577 2.56803 + vertex 1.04894 0.949208 2.56739 + endloop + endfacet + facet normal 0.122448 -0.265615 0.956271 + outer loop + vertex 1.04862 0.95355 2.56866 + vertex 1.05353 0.958203 2.56932 + vertex 1.04849 0.958266 2.56999 + endloop + endfacet + facet normal 0.109395 -0.256163 0.960424 + outer loop + vertex 1.05915 0.953318 2.56735 + vertex 1.05867 0.958338 2.56874 + vertex 1.05372 0.953577 2.56803 + endloop + endfacet + facet normal 0.132004 -0.238311 0.962176 + outer loop + vertex 1.06268 0.969853 2.57116 + vertex 1.05943 0.969832 2.5716 + vertex 1.06011 0.967234 2.57086 + endloop + endfacet + facet normal 0.131208 -0.235435 0.962993 + outer loop + vertex 1.05943 0.969832 2.5716 + vertex 1.05889 0.973714 2.57262 + vertex 1.05426 0.96871 2.57203 + endloop + endfacet + facet normal 0.14684 -0.232815 0.961372 + outer loop + vertex 1.06405 0.973831 2.57186 + vertex 1.05889 0.973714 2.57262 + vertex 1.05943 0.969832 2.5716 + endloop + endfacet + facet normal 0.128074 -0.256993 0.957889 + outer loop + vertex 1.05284 0.964798 2.57118 + vertex 1.05339 0.962163 2.5704 + vertex 1.05647 0.965998 2.57102 + endloop + endfacet + facet normal 0.122853 -0.257133 0.958535 + outer loop + vertex 1.05339 0.962163 2.5704 + vertex 1.04849 0.958266 2.56999 + vertex 1.05353 0.958203 2.56932 + endloop + endfacet + facet normal 0.13007 -0.261116 0.956504 + outer loop + vertex 1.05024 0.962247 2.57084 + vertex 1.04956 0.96485 2.57165 + vertex 1.04653 0.961028 2.57102 + endloop + endfacet + facet normal 0.130608 -0.261512 0.956323 + outer loop + vertex 1.04956 0.96485 2.57165 + vertex 1.04431 0.963766 2.57207 + vertex 1.04653 0.961028 2.57102 + endloop + endfacet + facet normal 0.126568 -0.26537 0.955803 + outer loop + vertex 1.04862 0.95355 2.56866 + vertex 1.04849 0.958266 2.56999 + vertex 1.04357 0.953279 2.56925 + endloop + endfacet + facet normal 0.129785 -0.271038 0.953779 + outer loop + vertex 1.03874 0.94854 2.56856 + vertex 1.04357 0.953279 2.56925 + vertex 1.03849 0.95327 2.56994 + endloop + endfacet + facet normal 0.12824 -0.26846 0.954717 + outer loop + vertex 1.0402 0.957246 2.57083 + vertex 1.03647 0.956042 2.57099 + vertex 1.03849 0.95327 2.56994 + endloop + endfacet + facet normal 0.131678 -0.266161 0.954892 + outer loop + vertex 1.04285 0.959816 2.57119 + vertex 1.0434 0.957174 2.57037 + vertex 1.04653 0.961028 2.57102 + endloop + endfacet + facet normal 0.126749 -0.263632 0.95626 + outer loop + vertex 1.0402 0.957246 2.57083 + vertex 1.03953 0.959887 2.57165 + vertex 1.03647 0.956042 2.57099 + endloop + endfacet + facet normal 0.130294 -0.261757 0.956298 + outer loop + vertex 1.04653 0.961028 2.57102 + vertex 1.04431 0.963766 2.57207 + vertex 1.04285 0.959816 2.57119 + endloop + endfacet + facet normal 0.123386 -0.259007 0.957962 + outer loop + vertex 1.03953 0.959887 2.57165 + vertex 1.03897 0.963799 2.57278 + vertex 1.03426 0.958819 2.57204 + endloop + endfacet + facet normal 0.122229 -0.256206 0.958863 + outer loop + vertex 1.03897 0.963799 2.57278 + vertex 1.04372 0.96853 2.57344 + vertex 1.03849 0.968386 2.57406 + endloop + endfacet + facet normal 0.130162 -0.25907 0.957048 + outer loop + vertex 1.04956 0.96485 2.57165 + vertex 1.04897 0.968715 2.57277 + vertex 1.04431 0.963766 2.57207 + endloop + endfacet + facet normal 0.134748 -0.250661 0.958651 + outer loop + vertex 1.05426 0.96871 2.57203 + vertex 1.05369 0.973498 2.57336 + vertex 1.04897 0.968715 2.57277 + endloop + endfacet + facet normal 0.146507 -0.248912 0.957381 + outer loop + vertex 1.05426 0.96871 2.57203 + vertex 1.05889 0.973714 2.57262 + vertex 1.05369 0.973498 2.57336 + endloop + endfacet + facet normal 0.146401 -0.231151 0.96184 + outer loop + vertex 1.05889 0.973714 2.57262 + vertex 1.05855 0.9785 2.57382 + vertex 1.05369 0.973498 2.57336 + endloop + endfacet + facet normal 0.163445 -0.247073 0.955113 + outer loop + vertex 1.05369 0.973498 2.57336 + vertex 1.05855 0.9785 2.57382 + vertex 1.05336 0.978591 2.57473 + endloop + endfacet + facet normal 0.12944 -0.257825 0.957482 + outer loop + vertex 1.04372 0.96853 2.57344 + vertex 1.0485 0.973307 2.57408 + vertex 1.04333 0.973394 2.5748 + endloop + endfacet + facet normal 0.11669 -0.259112 0.958772 + outer loop + vertex 1.04499 0.97742 2.57568 + vertex 1.04126 0.976238 2.57582 + vertex 1.04333 0.973394 2.5748 + endloop + endfacet + facet normal 0.147567 -0.254888 0.955644 + outer loop + vertex 1.04762 0.980002 2.57602 + vertex 1.0482 0.977338 2.57522 + vertex 1.05121 0.981299 2.57581 + endloop + endfacet + facet normal 0.114505 -0.251957 0.96094 + outer loop + vertex 1.04499 0.97742 2.57568 + vertex 1.04434 0.980047 2.57645 + vertex 1.04126 0.976238 2.57582 + endloop + endfacet + facet normal 0.141396 -0.236898 0.96119 + outer loop + vertex 1.05121 0.981299 2.57581 + vertex 1.04905 0.983923 2.57677 + vertex 1.04762 0.980002 2.57602 + endloop + endfacet + facet normal 0.15419 -0.226578 0.961711 + outer loop + vertex 1.05388 0.985151 2.57629 + vertex 1.04905 0.983923 2.57677 + vertex 1.05121 0.981299 2.57581 + endloop + endfacet + facet normal 0.150578 -0.210762 0.965871 + outer loop + vertex 1.05388 0.985151 2.57629 + vertex 1.05357 0.988809 2.57714 + vertex 1.04905 0.983923 2.57677 + endloop + endfacet + facet normal 0.171231 -0.229276 0.958182 + outer loop + vertex 1.04905 0.983923 2.57677 + vertex 1.05357 0.988809 2.57714 + vertex 1.04868 0.988575 2.57795 + endloop + endfacet + facet normal 0.171127 -0.217404 0.960964 + outer loop + vertex 1.05357 0.988809 2.57714 + vertex 1.05357 0.993514 2.5782 + vertex 1.04868 0.988575 2.57795 + endloop + endfacet + facet normal 0.157621 -0.251043 0.955057 + outer loop + vertex 1.0436 0.988434 2.5787 + vertex 1.04851 0.993289 2.57917 + vertex 1.04349 0.993299 2.58 + endloop + endfacet + facet normal 0.123259 -0.259583 0.957822 + outer loop + vertex 1.03839 0.992207 2.58036 + vertex 1.04349 0.993299 2.58 + vertex 1.04152 0.996104 2.58101 + endloop + endfacet + facet normal 0.141755 -0.2361 0.961333 + outer loop + vertex 1.04766 0.999969 2.58114 + vertex 1.04448 0.999972 2.58161 + vertex 1.0452 0.997371 2.58086 + endloop + endfacet + facet normal 0.142973 -0.199919 0.969325 + outer loop + vertex 1.04766 0.999969 2.58114 + vertex 1.04877 1.00373 2.58175 + vertex 1.04448 0.999972 2.58161 + endloop + endfacet + facet normal 0.158935 -0.217889 0.962946 + outer loop + vertex 1.04877 1.00373 2.58175 + vertex 1.04392 1.00381 2.58257 + vertex 1.04448 0.999972 2.58161 + endloop + endfacet + facet normal 0.160339 -0.189623 0.968677 + outer loop + vertex 1.04877 1.00373 2.58175 + vertex 1.04854 1.00848 2.58272 + vertex 1.04392 1.00381 2.58257 + endloop + endfacet + facet normal 0.186724 -0.215426 0.958502 + outer loop + vertex 1.04392 1.00381 2.58257 + vertex 1.04854 1.00848 2.58272 + vertex 1.04362 1.00851 2.58368 + endloop + endfacet + facet normal 0.187849 -0.190829 0.963482 + outer loop + vertex 1.04854 1.00848 2.58272 + vertex 1.04855 1.01356 2.58372 + vertex 1.04362 1.00851 2.58368 + endloop + endfacet + facet normal 0.220946 -0.223018 0.949445 + outer loop + vertex 1.04362 1.00851 2.58368 + vertex 1.04855 1.01356 2.58372 + vertex 1.04349 1.01362 2.58491 + endloop + endfacet + facet normal 0.118711 -0.224838 0.967138 + outer loop + vertex 1.04448 0.999972 2.58161 + vertex 1.04392 1.00381 2.58257 + vertex 1.03927 0.998812 2.58198 + endloop + endfacet + facet normal 0.136922 -0.241023 0.960812 + outer loop + vertex 1.03927 0.998812 2.58198 + vertex 1.04392 1.00381 2.58257 + vertex 1.03875 1.00352 2.58324 + endloop + endfacet + facet normal 0.113608 -0.252362 0.960941 + outer loop + vertex 1.03782 0.994866 2.58112 + vertex 1.03839 0.992207 2.58036 + vertex 1.04152 0.996104 2.58101 + endloop + endfacet + facet normal 0.11432 -0.250239 0.961411 + outer loop + vertex 1.03839 0.992207 2.58036 + vertex 1.03346 0.988278 2.57992 + vertex 1.03852 0.988213 2.5793 + endloop + endfacet + facet normal 0.116654 -0.253877 0.960176 + outer loop + vertex 1.03517 0.992289 2.58075 + vertex 1.03447 0.994906 2.58153 + vertex 1.03144 0.991079 2.58089 + endloop + endfacet + facet normal 0.116032 -0.253418 0.960373 + outer loop + vertex 1.03447 0.994906 2.58153 + vertex 1.02917 0.993792 2.58188 + vertex 1.03144 0.991079 2.58089 + endloop + endfacet + facet normal 0.116587 -0.248352 0.961628 + outer loop + vertex 1.03355 0.983458 2.57867 + vertex 1.03346 0.988278 2.57992 + vertex 1.02848 0.98324 2.57922 + endloop + endfacet + facet normal 0.117516 -0.249041 0.961337 + outer loop + vertex 1.02351 0.978479 2.5786 + vertex 1.02848 0.98324 2.57922 + vertex 1.0234 0.983309 2.57986 + endloop + endfacet + facet normal 0.116023 -0.247791 0.961841 + outer loop + vertex 1.02512 0.987324 2.58069 + vertex 1.02137 0.986127 2.58083 + vertex 1.0234 0.983309 2.57986 + endloop + endfacet + facet normal 0.117308 -0.248558 0.961487 + outer loop + vertex 1.02774 0.989883 2.58103 + vertex 1.02834 0.987228 2.58027 + vertex 1.03144 0.991079 2.58089 + endloop + endfacet + facet normal 0.116131 -0.248142 0.961738 + outer loop + vertex 1.02512 0.987324 2.58069 + vertex 1.0244 0.989938 2.58145 + vertex 1.02137 0.986127 2.58083 + endloop + endfacet + facet normal 0.113338 -0.246065 0.962604 + outer loop + vertex 1.0244 0.989938 2.58145 + vertex 1.01916 0.988888 2.5818 + vertex 1.02137 0.986127 2.58083 + endloop + endfacet + facet normal 0.118264 -0.251625 0.960572 + outer loop + vertex 1.03144 0.991079 2.58089 + vertex 1.02917 0.993792 2.58188 + vertex 1.02774 0.989883 2.58103 + endloop + endfacet + facet normal 0.113849 -0.248874 0.961821 + outer loop + vertex 1.0244 0.989938 2.58145 + vertex 1.02384 0.993782 2.58251 + vertex 1.01916 0.988888 2.5818 + endloop + endfacet + facet normal 0.112534 -0.247684 0.962283 + outer loop + vertex 1.01916 0.988888 2.5818 + vertex 1.02384 0.993782 2.58251 + vertex 1.01867 0.993564 2.58306 + endloop + endfacet + facet normal 0.112546 -0.248481 0.962076 + outer loop + vertex 1.02384 0.993782 2.58251 + vertex 1.02353 0.998378 2.58373 + vertex 1.01867 0.993564 2.58306 + endloop + endfacet + facet normal 0.112394 -0.248335 0.962132 + outer loop + vertex 1.01867 0.993564 2.58306 + vertex 1.02353 0.998378 2.58373 + vertex 1.01848 0.998181 2.58427 + endloop + endfacet + facet normal 0.108385 -0.248605 0.962522 + outer loop + vertex 1.01867 0.993564 2.58306 + vertex 1.01848 0.998181 2.58427 + vertex 1.01359 0.99346 2.58361 + endloop + endfacet + facet normal 0.112361 -0.245483 0.962867 + outer loop + vertex 1.02353 0.998378 2.58373 + vertex 1.02348 1.0032 2.58497 + vertex 1.01848 0.998181 2.58427 + endloop + endfacet + facet normal 0.110812 -0.245543 0.963031 + outer loop + vertex 1.02353 0.998378 2.58373 + vertex 1.02851 1.00314 2.58438 + vertex 1.02348 1.0032 2.58497 + endloop + endfacet + facet normal 0.110987 -0.241422 0.964053 + outer loop + vertex 1.02842 1.00711 2.58538 + vertex 1.02348 1.0032 2.58497 + vertex 1.02851 1.00314 2.58438 + endloop + endfacet + facet normal 0.108883 -0.241521 0.964268 + outer loop + vertex 1.02851 1.00314 2.58438 + vertex 1.03349 1.00816 2.58507 + vertex 1.02842 1.00711 2.58538 + endloop + endfacet + facet normal 0.108775 -0.240959 0.964421 + outer loop + vertex 1.02842 1.00711 2.58538 + vertex 1.03349 1.00816 2.58507 + vertex 1.03154 1.01092 2.58598 + endloop + endfacet + facet normal 0.106786 -0.239429 0.965024 + outer loop + vertex 1.02787 1.00973 2.58609 + vertex 1.02842 1.00711 2.58538 + vertex 1.03154 1.01092 2.58598 + endloop + endfacet + facet normal 0.105943 -0.236744 0.965779 + outer loop + vertex 1.03154 1.01092 2.58598 + vertex 1.02927 1.01362 2.58689 + vertex 1.02787 1.00973 2.58609 + endloop + endfacet + facet normal 0.109896 -0.238011 0.965025 + outer loop + vertex 1.02787 1.00973 2.58609 + vertex 1.02927 1.01362 2.58689 + vertex 1.02453 1.00978 2.58648 + endloop + endfacet + facet normal 0.109841 -0.239262 0.964722 + outer loop + vertex 1.02787 1.00973 2.58609 + vertex 1.02453 1.00978 2.58648 + vertex 1.02524 1.00719 2.58576 + endloop + endfacet + facet normal 0.112878 -0.238389 0.964588 + outer loop + vertex 1.02524 1.00719 2.58576 + vertex 1.02453 1.00978 2.58648 + vertex 1.02152 1.00598 2.5859 + endloop + endfacet + facet normal 0.11377 -0.241207 0.963782 + outer loop + vertex 1.02524 1.00719 2.58576 + vertex 1.02152 1.00598 2.5859 + vertex 1.02348 1.0032 2.58497 + endloop + endfacet + facet normal 0.113606 -0.241319 0.963773 + outer loop + vertex 1.01838 1.00215 2.58531 + vertex 1.02348 1.0032 2.58497 + vertex 1.02152 1.00598 2.5859 + endloop + endfacet + facet normal 0.114718 -0.242177 0.963426 + outer loop + vertex 1.01786 1.00481 2.58604 + vertex 1.01838 1.00215 2.58531 + vertex 1.02152 1.00598 2.5859 + endloop + endfacet + facet normal 0.112253 -0.234197 0.965687 + outer loop + vertex 1.02152 1.00598 2.5859 + vertex 1.01929 1.00873 2.58682 + vertex 1.01786 1.00481 2.58604 + endloop + endfacet + facet normal 0.11483 -0.247818 0.961977 + outer loop + vertex 1.01848 0.998181 2.58427 + vertex 1.02348 1.0032 2.58497 + vertex 1.01838 1.00215 2.58531 + endloop + endfacet + facet normal 0.10841 -0.24815 0.962636 + outer loop + vertex 1.01838 1.00215 2.58531 + vertex 1.01337 0.99828 2.58487 + vertex 1.01848 0.998181 2.58427 + endloop + endfacet + facet normal 0.10982 -0.236109 0.965501 + outer loop + vertex 1.02453 1.00978 2.58648 + vertex 1.01929 1.00873 2.58682 + vertex 1.02152 1.00598 2.5859 + endloop + endfacet + facet normal 0.109584 -0.234827 0.96584 + outer loop + vertex 1.02453 1.00978 2.58648 + vertex 1.02389 1.01365 2.5875 + vertex 1.01929 1.00873 2.58682 + endloop + endfacet + facet normal 0.105265 -0.230978 0.967248 + outer loop + vertex 1.01929 1.00873 2.58682 + vertex 1.02389 1.01365 2.5875 + vertex 1.01866 1.01349 2.58803 + endloop + endfacet + facet normal 0.105263 -0.230475 0.967368 + outer loop + vertex 1.02389 1.01365 2.5875 + vertex 1.02343 1.01835 2.58867 + vertex 1.01866 1.01349 2.58803 + endloop + endfacet + facet normal 0.105913 -0.230399 0.967315 + outer loop + vertex 1.02389 1.01365 2.5875 + vertex 1.02865 1.01837 2.5881 + vertex 1.02343 1.01835 2.58867 + endloop + endfacet + facet normal 0.107636 -0.232058 0.966728 + outer loop + vertex 1.02927 1.01362 2.58689 + vertex 1.02865 1.01837 2.5881 + vertex 1.02389 1.01365 2.5875 + endloop + endfacet + facet normal 0.115185 -0.230927 0.966129 + outer loop + vertex 1.02927 1.01362 2.58689 + vertex 1.03392 1.01861 2.58753 + vertex 1.02865 1.01837 2.5881 + endloop + endfacet + facet normal 0.107413 -0.223991 0.968654 + outer loop + vertex 1.03452 1.01473 2.58657 + vertex 1.03392 1.01861 2.58753 + vertex 1.02927 1.01362 2.58689 + endloop + endfacet + facet normal 0.107537 -0.235203 0.965979 + outer loop + vertex 1.02927 1.01362 2.58689 + vertex 1.02389 1.01365 2.5875 + vertex 1.02453 1.00978 2.58648 + endloop + endfacet + facet normal 0.109362 -0.233973 0.966073 + outer loop + vertex 1.03452 1.01473 2.58657 + vertex 1.02927 1.01362 2.58689 + vertex 1.03154 1.01092 2.58598 + endloop + endfacet + facet normal 0.109409 -0.238836 0.964877 + outer loop + vertex 1.02842 1.00711 2.58538 + vertex 1.02787 1.00973 2.58609 + vertex 1.02524 1.00719 2.58576 + endloop + endfacet + facet normal 0.111638 -0.244119 0.963298 + outer loop + vertex 1.03358 1.00335 2.58384 + vertex 1.03349 1.00816 2.58507 + vertex 1.02851 1.00314 2.58438 + endloop + endfacet + facet normal 0.109374 -0.23945 0.964728 + outer loop + vertex 1.02524 1.00719 2.58576 + vertex 1.02348 1.0032 2.58497 + vertex 1.02842 1.00711 2.58538 + endloop + endfacet + facet normal 0.112178 -0.246903 0.962525 + outer loop + vertex 1.02866 0.99849 2.58317 + vertex 1.02851 1.00314 2.58438 + vertex 1.02353 0.998378 2.58373 + endloop + endfacet + facet normal 0.112167 -0.248516 0.962111 + outer loop + vertex 1.02384 0.993782 2.58251 + vertex 1.02866 0.99849 2.58317 + vertex 1.02353 0.998378 2.58373 + endloop + endfacet + facet normal 0.116102 -0.253784 0.960268 + outer loop + vertex 1.03447 0.994906 2.58153 + vertex 1.03391 0.998754 2.58262 + vertex 1.02917 0.993792 2.58188 + endloop + endfacet + facet normal 0.111682 -0.246933 0.962575 + outer loop + vertex 1.02866 0.99849 2.58317 + vertex 1.03358 1.00335 2.58384 + vertex 1.02851 1.00314 2.58438 + endloop + endfacet + facet normal 0.11696 -0.243742 0.962762 + outer loop + vertex 1.03927 0.998812 2.58198 + vertex 1.03875 1.00352 2.58324 + vertex 1.03391 0.998754 2.58262 + endloop + endfacet + facet normal 0.136424 -0.22029 0.965847 + outer loop + vertex 1.04392 1.00381 2.58257 + vertex 1.04362 1.00851 2.58368 + vertex 1.03875 1.00352 2.58324 + endloop + endfacet + facet normal 0.124776 -0.243517 0.961837 + outer loop + vertex 1.03358 1.00335 2.58384 + vertex 1.03854 1.00821 2.58443 + vertex 1.03349 1.00816 2.58507 + endloop + endfacet + facet normal 0.108657 -0.24104 0.964413 + outer loop + vertex 1.03523 1.01213 2.58587 + vertex 1.03154 1.01092 2.58598 + vertex 1.03349 1.00816 2.58507 + endloop + endfacet + facet normal 0.149369 -0.235649 0.960291 + outer loop + vertex 1.0378 1.01475 2.58618 + vertex 1.03839 1.01217 2.58545 + vertex 1.04136 1.01619 2.58598 + endloop + endfacet + facet normal 0.105466 -0.231096 0.967198 + outer loop + vertex 1.03523 1.01213 2.58587 + vertex 1.03452 1.01473 2.58657 + vertex 1.03154 1.01092 2.58598 + endloop + endfacet + facet normal 0.139988 -0.211486 0.967304 + outer loop + vertex 1.04136 1.01619 2.58598 + vertex 1.03913 1.01874 2.58686 + vertex 1.0378 1.01475 2.58618 + endloop + endfacet + facet normal 0.156621 -0.197143 0.967783 + outer loop + vertex 1.04393 1.02018 2.58638 + vertex 1.03913 1.01874 2.58686 + vertex 1.04136 1.01619 2.58598 + endloop + endfacet + facet normal 0.151007 -0.176781 0.972597 + outer loop + vertex 1.04393 1.02018 2.58638 + vertex 1.04349 1.02388 2.58712 + vertex 1.03913 1.01874 2.58686 + endloop + endfacet + facet normal 0.176334 -0.197903 0.964231 + outer loop + vertex 1.03913 1.01874 2.58686 + vertex 1.04349 1.02388 2.58712 + vertex 1.03867 1.02349 2.58792 + endloop + endfacet + facet normal 0.175332 -0.176245 0.968605 + outer loop + vertex 1.04349 1.02388 2.58712 + vertex 1.04348 1.02857 2.58797 + vertex 1.03867 1.02349 2.58792 + endloop + endfacet + facet normal 0.165685 -0.225923 0.959952 + outer loop + vertex 1.03356 1.02333 2.58866 + vertex 1.03864 1.02842 2.58898 + vertex 1.03349 1.02844 2.58988 + endloop + endfacet + facet normal 0.165902 -0.22107 0.961044 + outer loop + vertex 1.03903 1.03349 2.59008 + vertex 1.03349 1.02844 2.58988 + vertex 1.03864 1.02842 2.58898 + endloop + endfacet + facet normal 0.146768 -0.207477 0.967167 + outer loop + vertex 1.03867 1.02349 2.58792 + vertex 1.03864 1.02842 2.58898 + vertex 1.03356 1.02333 2.58866 + endloop + endfacet + facet normal 0.101482 -0.228152 0.968322 + outer loop + vertex 1.02495 1.02735 2.59062 + vertex 1.02324 1.02332 2.58985 + vertex 1.02819 1.02723 2.59026 + endloop + endfacet + facet normal 0.105941 -0.229083 0.967625 + outer loop + vertex 1.02865 1.01837 2.5881 + vertex 1.02837 1.02315 2.58926 + vertex 1.02343 1.01835 2.58867 + endloop + endfacet + facet normal 0.103232 -0.228568 0.968039 + outer loop + vertex 1.01866 1.01349 2.58803 + vertex 1.02343 1.01835 2.58867 + vertex 1.01833 1.01827 2.58919 + endloop + endfacet + facet normal 0.104031 -0.231163 0.967337 + outer loop + vertex 1.01929 1.00873 2.58682 + vertex 1.01866 1.01349 2.58803 + vertex 1.01411 1.00888 2.58742 + endloop + endfacet + facet normal 0.104052 -0.230785 0.967425 + outer loop + vertex 1.01929 1.00873 2.58682 + vertex 1.01411 1.00888 2.58742 + vertex 1.01465 1.00503 2.58644 + endloop + endfacet + facet normal 0.0961105 -0.232036 0.967947 + outer loop + vertex 1.01465 1.00503 2.58644 + vertex 1.01411 1.00888 2.58742 + vertex 1.01002 1.00456 2.58679 + endloop + endfacet + facet normal 0.0964855 -0.236636 0.966796 + outer loop + vertex 1.01465 1.00503 2.58644 + vertex 1.01002 1.00456 2.58679 + vertex 1.01137 1.0013 2.58585 + endloop + endfacet + facet normal 0.0980637 -0.237951 0.966314 + outer loop + vertex 1.01519 1.0023 2.58571 + vertex 1.01465 1.00503 2.58644 + vertex 1.01137 1.0013 2.58585 + endloop + endfacet + facet normal 0.100154 -0.246236 0.964021 + outer loop + vertex 1.01519 1.0023 2.58571 + vertex 1.01137 1.0013 2.58585 + vertex 1.01337 0.99828 2.58487 + endloop + endfacet + facet normal 0.110142 -0.250308 0.961881 + outer loop + vertex 1.01519 1.0023 2.58571 + vertex 1.01337 0.99828 2.58487 + vertex 1.01838 1.00215 2.58531 + endloop + endfacet + facet normal 0.110726 -0.243027 0.963679 + outer loop + vertex 1.01838 1.00215 2.58531 + vertex 1.01786 1.00481 2.58604 + vertex 1.01519 1.0023 2.58571 + endloop + endfacet + facet normal 0.104416 -0.236599 0.96598 + outer loop + vertex 1.01786 1.00481 2.58604 + vertex 1.01465 1.00503 2.58644 + vertex 1.01519 1.0023 2.58571 + endloop + endfacet + facet normal 0.104883 -0.231791 0.967095 + outer loop + vertex 1.01786 1.00481 2.58604 + vertex 1.01929 1.00873 2.58682 + vertex 1.01465 1.00503 2.58644 + endloop + endfacet + facet normal 0.108387 -0.248607 0.962521 + outer loop + vertex 1.01359 0.99346 2.58361 + vertex 1.01848 0.998181 2.58427 + vertex 1.01337 0.99828 2.58487 + endloop + endfacet + facet normal 0.108388 -0.248274 0.962607 + outer loop + vertex 1.01404 0.989023 2.58241 + vertex 1.01867 0.993564 2.58306 + vertex 1.01359 0.99346 2.58361 + endloop + endfacet + facet normal 0.10833 -0.248218 0.962628 + outer loop + vertex 1.01916 0.988888 2.5818 + vertex 1.01867 0.993564 2.58306 + vertex 1.01404 0.989023 2.58241 + endloop + endfacet + facet normal 0.112543 -0.246679 0.96254 + outer loop + vertex 1.02137 0.986127 2.58083 + vertex 1.01916 0.988888 2.5818 + vertex 1.01768 0.984989 2.58097 + endloop + endfacet + facet normal 0.112715 -0.247258 0.962371 + outer loop + vertex 1.01768 0.984989 2.58097 + vertex 1.01824 0.982287 2.58021 + vertex 1.02137 0.986127 2.58083 + endloop + endfacet + facet normal 0.108797 -0.248873 0.962406 + outer loop + vertex 1.01824 0.982287 2.58021 + vertex 1.01326 0.978401 2.57977 + vertex 1.01842 0.978276 2.57916 + endloop + endfacet + facet normal 0.103326 -0.246312 0.963667 + outer loop + vertex 1.01503 0.982483 2.58063 + vertex 1.0145 0.985223 2.58139 + vertex 1.01124 0.98148 2.58078 + endloop + endfacet + facet normal 0.102251 -0.246518 0.963729 + outer loop + vertex 1.0084 0.97326 2.57897 + vertex 1.01326 0.978401 2.57977 + vertex 1.00778 0.97733 2.58008 + endloop + endfacet + facet normal 0.0984698 -0.246336 0.964169 + outer loop + vertex 1.00337 0.976906 2.58042 + vertex 1.00778 0.97733 2.58008 + vertex 1.00668 0.98066 2.58104 + endloop + endfacet + facet normal 0.102582 -0.245702 0.963902 + outer loop + vertex 1.0145 0.985223 2.58139 + vertex 1.00994 0.984745 2.58175 + vertex 1.01124 0.98148 2.58078 + endloop + endfacet + facet normal 0.0984539 -0.247765 0.963805 + outer loop + vertex 1.00994 0.984745 2.58175 + vertex 1.00896 0.988705 2.58287 + vertex 1.0044 0.983664 2.58204 + endloop + endfacet + facet normal 0.0978657 -0.245835 0.964359 + outer loop + vertex 1.00295 0.979691 2.58117 + vertex 1.00337 0.976906 2.58042 + vertex 1.00668 0.98066 2.58104 + endloop + endfacet + facet normal 0.0946929 -0.24694 0.964393 + outer loop + vertex 1.00337 0.976906 2.58042 + vertex 0.998509 0.973163 2.57994 + vertex 1.00343 0.972969 2.57941 + endloop + endfacet + facet normal 0.0944825 -0.244783 0.964963 + outer loop + vertex 1.00029 0.977187 2.5808 + vertex 0.999596 0.979852 2.58155 + vertex 0.996491 0.97602 2.58088 + endloop + endfacet + facet normal 0.0898781 -0.241282 0.966284 + outer loop + vertex 0.999596 0.979852 2.58155 + vertex 0.994232 0.978825 2.58179 + vertex 0.996491 0.97602 2.58088 + endloop + endfacet + facet normal 0.0807039 -0.250596 0.964722 + outer loop + vertex 0.998718 0.968414 2.57869 + vertex 0.998509 0.973163 2.57994 + vertex 0.993673 0.968212 2.57906 + endloop + endfacet + facet normal 0.0602181 -0.263857 0.96268 + outer loop + vertex 0.989187 0.963737 2.57811 + vertex 0.993673 0.968212 2.57906 + vertex 0.988401 0.968397 2.57944 + endloop + endfacet + facet normal 0.0458016 -0.270534 0.96162 + outer loop + vertex 0.989966 0.972342 2.58047 + vertex 0.986049 0.971565 2.58044 + vertex 0.988401 0.968397 2.57944 + endloop + endfacet + facet normal 0.0919102 -0.256617 0.962133 + outer loop + vertex 0.992691 0.974858 2.58093 + vertex 0.993309 0.972146 2.58015 + vertex 0.996491 0.97602 2.58088 + endloop + endfacet + facet normal 0.0426732 -0.254938 0.966015 + outer loop + vertex 0.989966 0.972342 2.58047 + vertex 0.989403 0.975173 2.58125 + vertex 0.986049 0.971565 2.58044 + endloop + endfacet + facet normal 0.0877714 -0.242909 0.96607 + outer loop + vertex 0.996491 0.97602 2.58088 + vertex 0.994232 0.978825 2.58179 + vertex 0.992691 0.974858 2.58093 + endloop + endfacet + facet normal 0.075991 -0.243561 0.966904 + outer loop + vertex 0.989019 0.979078 2.58225 + vertex 0.993724 0.98355 2.58301 + vertex 0.988596 0.983515 2.58341 + endloop + endfacet + facet normal 0.0516726 -0.246127 0.967859 + outer loop + vertex 0.989019 0.979078 2.58225 + vertex 0.988596 0.983515 2.58341 + vertex 0.984172 0.9792 2.58254 + endloop + endfacet + facet normal 0.0514094 -0.252618 0.966199 + outer loop + vertex 0.984808 0.97514 2.58145 + vertex 0.989019 0.979078 2.58225 + vertex 0.984172 0.9792 2.58254 + endloop + endfacet + facet normal 0.0446719 -0.245837 0.968281 + outer loop + vertex 0.989403 0.975173 2.58125 + vertex 0.989019 0.979078 2.58225 + vertex 0.984808 0.97514 2.58145 + endloop + endfacet + facet normal 0.0446255 -0.256633 0.965478 + outer loop + vertex 0.989403 0.975173 2.58125 + vertex 0.984808 0.97514 2.58145 + vertex 0.986049 0.971565 2.58044 + endloop + endfacet + facet normal 0.0086529 -0.268495 0.963242 + outer loop + vertex 0.986049 0.971565 2.58044 + vertex 0.984808 0.97514 2.58145 + vertex 0.981253 0.971491 2.58046 + endloop + endfacet + facet normal 0.00879839 -0.27879 0.960312 + outer loop + vertex 0.981253 0.971491 2.58046 + vertex 0.982771 0.967834 2.57939 + vertex 0.986049 0.971565 2.58044 + endloop + endfacet + facet normal 0.0203363 -0.288099 0.957385 + outer loop + vertex 0.982771 0.967834 2.57939 + vertex 0.988401 0.968397 2.57944 + vertex 0.986049 0.971565 2.58044 + endloop + endfacet + facet normal 0.0189577 -0.274664 0.961353 + outer loop + vertex 0.984077 0.963882 2.57823 + vertex 0.988401 0.968397 2.57944 + vertex 0.982771 0.967834 2.57939 + endloop + endfacet + facet normal 0.0152229 -0.271355 0.962359 + outer loop + vertex 0.989187 0.963737 2.57811 + vertex 0.988401 0.968397 2.57944 + vertex 0.984077 0.963882 2.57823 + endloop + endfacet + facet normal 0.0151748 -0.272727 0.961972 + outer loop + vertex 0.985093 0.959636 2.57701 + vertex 0.989187 0.963737 2.57811 + vertex 0.984077 0.963882 2.57823 + endloop + endfacet + facet normal 0.00570315 -0.265827 0.964004 + outer loop + vertex 0.984808 0.97514 2.58145 + vertex 0.979698 0.975539 2.58159 + vertex 0.981253 0.971491 2.58046 + endloop + endfacet + facet normal -0.0403068 -0.282001 0.958567 + outer loop + vertex 0.981253 0.971491 2.58046 + vertex 0.979698 0.975539 2.58159 + vertex 0.977312 0.971943 2.58043 + endloop + endfacet + facet normal -0.0430896 -0.306861 0.950779 + outer loop + vertex 0.977312 0.971943 2.58043 + vertex 0.977447 0.968218 2.57924 + vertex 0.981253 0.971491 2.58046 + endloop + endfacet + facet normal -0.0491005 -0.300521 0.952511 + outer loop + vertex 0.977447 0.968218 2.57924 + vertex 0.982771 0.967834 2.57939 + vertex 0.981253 0.971491 2.58046 + endloop + endfacet + facet normal -0.0478602 -0.280963 0.958524 + outer loop + vertex 0.979674 0.964661 2.5783 + vertex 0.982771 0.967834 2.57939 + vertex 0.977447 0.968218 2.57924 + endloop + endfacet + facet normal -0.0363184 -0.291343 0.955929 + outer loop + vertex 0.984077 0.963882 2.57823 + vertex 0.982771 0.967834 2.57939 + vertex 0.979674 0.964661 2.5783 + endloop + endfacet + facet normal 0.00623878 -0.259561 0.965706 + outer loop + vertex 0.984808 0.97514 2.58145 + vertex 0.984172 0.9792 2.58254 + vertex 0.979698 0.975539 2.58159 + endloop + endfacet + facet normal 0.0169815 -0.271778 0.96221 + outer loop + vertex 0.979698 0.975539 2.58159 + vertex 0.984172 0.9792 2.58254 + vertex 0.980263 0.979731 2.58276 + endloop + endfacet + facet normal 0.0196902 -0.253822 0.96705 + outer loop + vertex 0.984172 0.9792 2.58254 + vertex 0.983677 0.983378 2.58365 + vertex 0.980263 0.979731 2.58276 + endloop + endfacet + facet normal 0.0100686 -0.245383 0.969374 + outer loop + vertex 0.980263 0.979731 2.58276 + vertex 0.983677 0.983378 2.58365 + vertex 0.978855 0.98304 2.58362 + endloop + endfacet + facet normal 0.0110527 -0.259041 0.965803 + outer loop + vertex 0.983677 0.983378 2.58365 + vertex 0.982579 0.987259 2.5847 + vertex 0.978855 0.98304 2.58362 + endloop + endfacet + facet normal 0.00503187 -0.254079 0.967171 + outer loop + vertex 0.978855 0.98304 2.58362 + vertex 0.982579 0.987259 2.5847 + vertex 0.977474 0.987069 2.58468 + endloop + endfacet + facet normal 0.00542541 -0.264363 0.964408 + outer loop + vertex 0.977474 0.987069 2.58468 + vertex 0.982579 0.987259 2.5847 + vertex 0.981203 0.990938 2.58572 + endloop + endfacet + facet normal 0.00121486 -0.260584 0.96545 + outer loop + vertex 0.976242 0.991077 2.58576 + vertex 0.977474 0.987069 2.58468 + vertex 0.981203 0.990938 2.58572 + endloop + endfacet + facet normal 0.00132891 -0.256817 0.966459 + outer loop + vertex 0.981203 0.990938 2.58572 + vertex 0.979956 0.994805 2.58675 + vertex 0.976242 0.991077 2.58576 + endloop + endfacet + facet normal 0.0397536 -0.245017 0.968704 + outer loop + vertex 0.984942 0.994873 2.58656 + vertex 0.979956 0.994805 2.58675 + vertex 0.981203 0.990938 2.58572 + endloop + endfacet + facet normal 0.0397414 -0.242128 0.96943 + outer loop + vertex 0.984942 0.994873 2.58656 + vertex 0.98407 0.998888 2.5876 + vertex 0.979956 0.994805 2.58675 + endloop + endfacet + facet normal 0.0387955 -0.241229 0.969692 + outer loop + vertex 0.979956 0.994805 2.58675 + vertex 0.98407 0.998888 2.5876 + vertex 0.979184 0.998985 2.58782 + endloop + endfacet + facet normal 0.038813 -0.240665 0.969832 + outer loop + vertex 0.98407 0.998888 2.5876 + vertex 0.983435 1.00326 2.58871 + vertex 0.979184 0.998985 2.58782 + endloop + endfacet + facet normal 0.0392755 -0.241099 0.969706 + outer loop + vertex 0.979184 0.998985 2.58782 + vertex 0.983435 1.00326 2.58871 + vertex 0.978542 1.00308 2.58887 + endloop + endfacet + facet normal 0.0393786 -0.244651 0.968811 + outer loop + vertex 0.983435 1.00326 2.58871 + vertex 0.982531 1.00732 2.58977 + vertex 0.978542 1.00308 2.58887 + endloop + endfacet + facet normal 0.0353408 -0.24108 0.969862 + outer loop + vertex 0.978542 1.00308 2.58887 + vertex 0.982531 1.00732 2.58977 + vertex 0.977485 1.00693 2.58986 + endloop + endfacet + facet normal 0.0357551 -0.2468 0.968406 + outer loop + vertex 0.977485 1.00693 2.58986 + vertex 0.982531 1.00732 2.58977 + vertex 0.981265 1.01094 2.59074 + endloop + endfacet + facet normal 0.0319853 -0.243459 0.969384 + outer loop + vertex 0.976221 1.01074 2.59086 + vertex 0.977485 1.00693 2.58986 + vertex 0.981265 1.01094 2.59074 + endloop + endfacet + facet normal 0.0319185 -0.241524 0.96987 + outer loop + vertex 0.981265 1.01094 2.59074 + vertex 0.980035 1.01466 2.59171 + vertex 0.976221 1.01074 2.59086 + endloop + endfacet + facet normal 0.0300408 -0.239803 0.970357 + outer loop + vertex 0.980035 1.01466 2.59171 + vertex 0.974933 1.01468 2.59187 + vertex 0.976221 1.01074 2.59086 + endloop + endfacet + facet normal -0.00866125 -0.251774 0.967747 + outer loop + vertex 0.976221 1.01074 2.59086 + vertex 0.974933 1.01468 2.59187 + vertex 0.971181 1.01096 2.59087 + endloop + endfacet + facet normal -0.00882838 -0.255579 0.966748 + outer loop + vertex 0.971181 1.01096 2.59087 + vertex 0.972446 1.00697 2.58983 + vertex 0.976221 1.01074 2.59086 + endloop + endfacet + facet normal 0.0301303 -0.232358 0.972163 + outer loop + vertex 0.980035 1.01466 2.59171 + vertex 0.979105 1.0188 2.59273 + vertex 0.974933 1.01468 2.59187 + endloop + endfacet + facet normal 0.0327278 -0.234846 0.971481 + outer loop + vertex 0.974933 1.01468 2.59187 + vertex 0.979105 1.0188 2.59273 + vertex 0.974194 1.01893 2.59293 + endloop + endfacet + facet normal 0.0329881 -0.227748 0.973161 + outer loop + vertex 0.979105 1.0188 2.59273 + vertex 0.97866 1.0233 2.5938 + vertex 0.974194 1.01893 2.59293 + endloop + endfacet + facet normal 0.0369852 -0.231623 0.972102 + outer loop + vertex 0.974194 1.01893 2.59293 + vertex 0.97866 1.0233 2.5938 + vertex 0.973749 1.02318 2.59396 + endloop + endfacet + facet normal 0.0369162 -0.22751 0.973076 + outer loop + vertex 0.97866 1.0233 2.5938 + vertex 0.978461 1.02809 2.59492 + vertex 0.973749 1.02318 2.59396 + endloop + endfacet + facet normal 0.0368038 -0.227407 0.973104 + outer loop + vertex 0.973749 1.02318 2.59396 + vertex 0.978461 1.02809 2.59492 + vertex 0.972752 1.02705 2.5949 + endloop + endfacet + facet normal 0.0391641 -0.240251 0.96992 + outer loop + vertex 0.972752 1.02705 2.5949 + vertex 0.978461 1.02809 2.59492 + vertex 0.976396 1.03117 2.59577 + endloop + endfacet + facet normal 0.0279686 -0.230912 0.972573 + outer loop + vertex 0.97141 1.03067 2.59579 + vertex 0.972752 1.02705 2.5949 + vertex 0.976396 1.03117 2.59577 + endloop + endfacet + facet normal 0.0278105 -0.229314 0.972955 + outer loop + vertex 0.976396 1.03117 2.59577 + vertex 0.975149 1.03458 2.59661 + vertex 0.97141 1.03067 2.59579 + endloop + endfacet + facet normal 0.0212468 -0.223357 0.974505 + outer loop + vertex 0.975149 1.03458 2.59661 + vertex 0.970104 1.03454 2.59671 + vertex 0.97141 1.03067 2.59579 + endloop + endfacet + facet normal -0.0236514 -0.237694 0.971052 + outer loop + vertex 0.97141 1.03067 2.59579 + vertex 0.970104 1.03454 2.59671 + vertex 0.966374 1.0309 2.59573 + endloop + endfacet + facet normal -0.0237561 -0.240194 0.970434 + outer loop + vertex 0.966374 1.0309 2.59573 + vertex 0.967582 1.02686 2.59476 + vertex 0.97141 1.03067 2.59579 + endloop + endfacet + facet normal -0.016916 -0.246662 0.968954 + outer loop + vertex 0.967582 1.02686 2.59476 + vertex 0.972752 1.02705 2.5949 + vertex 0.97141 1.03067 2.59579 + endloop + endfacet + facet normal 0.0212435 -0.22232 0.974742 + outer loop + vertex 0.975149 1.03458 2.59661 + vertex 0.974181 1.03862 2.59755 + vertex 0.970104 1.03454 2.59671 + endloop + endfacet + facet normal 0.0182325 -0.219458 0.975452 + outer loop + vertex 0.970104 1.03454 2.59671 + vertex 0.974181 1.03862 2.59755 + vertex 0.969254 1.03883 2.59769 + endloop + endfacet + facet normal 0.0183399 -0.217317 0.975929 + outer loop + vertex 0.974181 1.03862 2.59755 + vertex 0.97361 1.04321 2.59859 + vertex 0.969254 1.03883 2.59769 + endloop + endfacet + facet normal 0.0171351 -0.216174 0.976204 + outer loop + vertex 0.969254 1.03883 2.59769 + vertex 0.97361 1.04321 2.59859 + vertex 0.96868 1.04331 2.59869 + endloop + endfacet + facet normal 0.0170592 -0.219132 0.975546 + outer loop + vertex 0.97361 1.04321 2.59859 + vertex 0.973271 1.04819 2.59971 + vertex 0.96868 1.04331 2.59869 + endloop + endfacet + facet normal 0.0168577 -0.218952 0.97559 + outer loop + vertex 0.96868 1.04331 2.59869 + vertex 0.973271 1.04819 2.59971 + vertex 0.967547 1.04749 2.59965 + endloop + endfacet + facet normal 0.0188971 -0.235234 0.971755 + outer loop + vertex 0.967547 1.04749 2.59965 + vertex 0.973271 1.04819 2.59971 + vertex 0.971149 1.05147 2.60054 + endloop + endfacet + facet normal 0.0139834 -0.231029 0.972846 + outer loop + vertex 0.966241 1.05132 2.60058 + vertex 0.967547 1.04749 2.59965 + vertex 0.971149 1.05147 2.60054 + endloop + endfacet + facet normal 0.0138383 -0.225829 0.974069 + outer loop + vertex 0.971149 1.05147 2.60054 + vertex 0.969866 1.05497 2.60138 + vertex 0.966241 1.05132 2.60058 + endloop + endfacet + facet normal 0.0111346 -0.223281 0.974691 + outer loop + vertex 0.969866 1.05497 2.60138 + vertex 0.964578 1.05536 2.60152 + vertex 0.966241 1.05132 2.60058 + endloop + endfacet + facet normal -0.0224787 -0.23637 0.971403 + outer loop + vertex 0.966241 1.05132 2.60058 + vertex 0.964578 1.05536 2.60152 + vertex 0.962177 1.05172 2.60058 + endloop + endfacet + facet normal -0.0242168 -0.254167 0.966857 + outer loop + vertex 0.962177 1.05172 2.60058 + vertex 0.962151 1.04784 2.59956 + vertex 0.966241 1.05132 2.60058 + endloop + endfacet + facet normal 0.011742 -0.215537 0.976425 + outer loop + vertex 0.969866 1.05497 2.60138 + vertex 0.969082 1.05902 2.60228 + vertex 0.964578 1.05536 2.60152 + endloop + endfacet + facet normal 0.0156156 -0.220081 0.975356 + outer loop + vertex 0.964578 1.05536 2.60152 + vertex 0.969082 1.05902 2.60228 + vertex 0.965102 1.05966 2.60249 + endloop + endfacet + facet normal 0.0181401 -0.205457 0.978498 + outer loop + vertex 0.969082 1.05902 2.60228 + vertex 0.968689 1.06342 2.60321 + vertex 0.965102 1.05966 2.60249 + endloop + endfacet + facet normal 0.0128339 -0.2006 0.979589 + outer loop + vertex 0.965102 1.05966 2.60249 + vertex 0.968689 1.06342 2.60321 + vertex 0.963978 1.06329 2.60324 + endloop + endfacet + facet normal 0.0128224 -0.200158 0.97968 + outer loop + vertex 0.968689 1.06342 2.60321 + vertex 0.968372 1.06799 2.60415 + vertex 0.963978 1.06329 2.60324 + endloop + endfacet + facet normal 0.0397138 -0.210206 0.97685 + outer loop + vertex 0.969866 1.05497 2.60138 + vertex 0.974004 1.05884 2.60204 + vertex 0.969082 1.05902 2.60228 + endloop + endfacet + facet normal 0.0399969 -0.204097 0.978133 + outer loop + vertex 0.974004 1.05884 2.60204 + vertex 0.973496 1.06333 2.603 + vertex 0.969082 1.05902 2.60228 + endloop + endfacet + facet normal 0.0394022 -0.203512 0.978279 + outer loop + vertex 0.969082 1.05902 2.60228 + vertex 0.973496 1.06333 2.603 + vertex 0.968689 1.06342 2.60321 + endloop + endfacet + facet normal 0.0395121 -0.199344 0.979133 + outer loop + vertex 0.973496 1.06333 2.603 + vertex 0.973412 1.06816 2.60398 + vertex 0.968689 1.06342 2.60321 + endloop + endfacet + facet normal 0.0384417 -0.198321 0.979383 + outer loop + vertex 0.968689 1.06342 2.60321 + vertex 0.973412 1.06816 2.60398 + vertex 0.968372 1.06799 2.60415 + endloop + endfacet + facet normal 0.0384583 -0.198902 0.979265 + outer loop + vertex 0.973412 1.06816 2.60398 + vertex 0.973458 1.07317 2.605 + vertex 0.968372 1.06799 2.60415 + endloop + endfacet + facet normal 0.041698 -0.201955 0.978507 + outer loop + vertex 0.968372 1.06799 2.60415 + vertex 0.973458 1.07317 2.605 + vertex 0.967707 1.07216 2.60504 + endloop + endfacet + facet normal 0.016478 -0.20596 0.978422 + outer loop + vertex 0.968372 1.06799 2.60415 + vertex 0.967707 1.07216 2.60504 + vertex 0.963356 1.0677 2.60417 + endloop + endfacet + facet normal 0.0173117 -0.206739 0.978243 + outer loop + vertex 0.963356 1.0677 2.60417 + vertex 0.967707 1.07216 2.60504 + vertex 0.962594 1.07176 2.60504 + endloop + endfacet + facet normal 0.0178828 -0.213999 0.97667 + outer loop + vertex 0.962594 1.07176 2.60504 + vertex 0.967707 1.07216 2.60504 + vertex 0.966513 1.07573 2.60584 + endloop + endfacet + facet normal 0.0137237 -0.210081 0.977588 + outer loop + vertex 0.96142 1.07551 2.60586 + vertex 0.962594 1.07176 2.60504 + vertex 0.966513 1.07573 2.60584 + endloop + endfacet + facet normal 0.0138075 -0.212095 0.977152 + outer loop + vertex 0.966513 1.07573 2.60584 + vertex 0.965173 1.07936 2.60665 + vertex 0.96142 1.07551 2.60586 + endloop + endfacet + facet normal 0.0382172 -0.203359 0.978358 + outer loop + vertex 0.970198 1.07962 2.6065 + vertex 0.965173 1.07936 2.60665 + vertex 0.966513 1.07573 2.60584 + endloop + endfacet + facet normal 0.0411758 -0.206043 0.977676 + outer loop + vertex 0.971473 1.07631 2.60575 + vertex 0.970198 1.07962 2.6065 + vertex 0.966513 1.07573 2.60584 + endloop + endfacet + facet normal 0.0527669 -0.201663 0.978032 + outer loop + vertex 0.974841 1.07987 2.60631 + vertex 0.970198 1.07962 2.6065 + vertex 0.971473 1.07631 2.60575 + endloop + endfacet + facet normal 0.0529311 -0.201812 0.977993 + outer loop + vertex 0.975441 1.07719 2.60572 + vertex 0.974841 1.07987 2.60631 + vertex 0.971473 1.07631 2.60575 + endloop + endfacet + facet normal 0.052853 -0.201459 0.97807 + outer loop + vertex 0.975441 1.07719 2.60572 + vertex 0.971473 1.07631 2.60575 + vertex 0.973458 1.07317 2.605 + endloop + endfacet + facet normal 0.0558406 -0.202851 0.977616 + outer loop + vertex 0.975441 1.07719 2.60572 + vertex 0.973458 1.07317 2.605 + vertex 0.978579 1.07682 2.60546 + endloop + endfacet + facet normal 0.0563198 -0.199259 0.978327 + outer loop + vertex 0.978579 1.07682 2.60546 + vertex 0.978138 1.07952 2.60604 + vertex 0.975441 1.07719 2.60572 + endloop + endfacet + facet normal 0.0584584 -0.198898 0.978275 + outer loop + vertex 0.978138 1.07952 2.60604 + vertex 0.978579 1.07682 2.60546 + vertex 0.981915 1.0804 2.60599 + endloop + endfacet + facet normal 0.0521254 -0.1978 0.978855 + outer loop + vertex 0.978579 1.07682 2.60546 + vertex 0.973458 1.07317 2.605 + vertex 0.97848 1.07288 2.60467 + endloop + endfacet + facet normal 0.0576275 -0.197874 0.978532 + outer loop + vertex 0.97848 1.07288 2.60467 + vertex 0.983098 1.0772 2.60528 + vertex 0.978579 1.07682 2.60546 + endloop + endfacet + facet normal 0.0581705 -0.198433 0.978387 + outer loop + vertex 0.983477 1.07309 2.60442 + vertex 0.983098 1.0772 2.60528 + vertex 0.97848 1.07288 2.60467 + endloop + endfacet + facet normal 0.058169 -0.198386 0.978396 + outer loop + vertex 0.978398 1.06816 2.60372 + vertex 0.983477 1.07309 2.60442 + vertex 0.97848 1.07288 2.60467 + endloop + endfacet + facet normal 0.0515127 -0.198347 0.978777 + outer loop + vertex 0.978398 1.06816 2.60372 + vertex 0.97848 1.07288 2.60467 + vertex 0.973412 1.06816 2.60398 + endloop + endfacet + facet normal 0.0596608 -0.19987 0.978004 + outer loop + vertex 0.983448 1.06824 2.60343 + vertex 0.983477 1.07309 2.60442 + vertex 0.978398 1.06816 2.60372 + endloop + endfacet + facet normal 0.0596634 -0.200555 0.977864 + outer loop + vertex 0.978581 1.06331 2.60271 + vertex 0.983448 1.06824 2.60343 + vertex 0.978398 1.06816 2.60372 + endloop + endfacet + facet normal 0.0533707 -0.200855 0.978166 + outer loop + vertex 0.978581 1.06331 2.60271 + vertex 0.978398 1.06816 2.60372 + vertex 0.973496 1.06333 2.603 + endloop + endfacet + facet normal 0.0619037 -0.20268 0.977286 + outer loop + vertex 0.983841 1.06351 2.60242 + vertex 0.983448 1.06824 2.60343 + vertex 0.978581 1.06331 2.60271 + endloop + endfacet + facet normal 0.0619161 -0.203136 0.977191 + outer loop + vertex 0.979302 1.05855 2.60168 + vertex 0.983841 1.06351 2.60242 + vertex 0.978581 1.06331 2.60271 + endloop + endfacet + facet normal 0.0550617 -0.204214 0.977377 + outer loop + vertex 0.979302 1.05855 2.60168 + vertex 0.978581 1.06331 2.60271 + vertex 0.974004 1.05884 2.60204 + endloop + endfacet + facet normal 0.0549434 -0.205924 0.977024 + outer loop + vertex 0.979302 1.05855 2.60168 + vertex 0.974004 1.05884 2.60204 + vertex 0.974562 1.05503 2.6012 + endloop + endfacet + facet normal 0.053304 -0.203789 0.977563 + outer loop + vertex 0.977869 1.05467 2.60095 + vertex 0.979302 1.05855 2.60168 + vertex 0.974562 1.05503 2.6012 + endloop + endfacet + facet normal 0.052242 -0.212426 0.97578 + outer loop + vertex 0.977869 1.05467 2.60095 + vertex 0.974562 1.05503 2.6012 + vertex 0.975126 1.05226 2.60057 + endloop + endfacet + facet normal 0.0571246 -0.21775 0.974331 + outer loop + vertex 0.97828 1.0519 2.60031 + vertex 0.977869 1.05467 2.60095 + vertex 0.975126 1.05226 2.60057 + endloop + endfacet + facet normal 0.0553481 -0.230939 0.971393 + outer loop + vertex 0.975126 1.05226 2.60057 + vertex 0.973271 1.04819 2.59971 + vertex 0.97828 1.0519 2.60031 + endloop + endfacet + facet normal 0.0459271 -0.21872 0.974706 + outer loop + vertex 0.97828 1.0519 2.60031 + vertex 0.973271 1.04819 2.59971 + vertex 0.978325 1.04787 2.5994 + endloop + endfacet + facet normal 0.0620435 -0.218355 0.973895 + outer loop + vertex 0.978325 1.04787 2.5994 + vertex 0.982824 1.05232 2.60011 + vertex 0.97828 1.0519 2.60031 + endloop + endfacet + facet normal 0.0616953 -0.214146 0.974851 + outer loop + vertex 0.97828 1.0519 2.60031 + vertex 0.982824 1.05232 2.60011 + vertex 0.981677 1.05561 2.60091 + endloop + endfacet + facet normal 0.066058 -0.212636 0.974896 + outer loop + vertex 0.981677 1.05561 2.60091 + vertex 0.982824 1.05232 2.60011 + vertex 0.986392 1.05643 2.60076 + endloop + endfacet + facet normal 0.0651265 -0.207054 0.976159 + outer loop + vertex 0.986392 1.05643 2.60076 + vertex 0.984963 1.05958 2.60153 + vertex 0.981677 1.05561 2.60091 + endloop + endfacet + facet normal 0.0635076 -0.205775 0.976536 + outer loop + vertex 0.984963 1.05958 2.60153 + vertex 0.979302 1.05855 2.60168 + vertex 0.981677 1.05561 2.60091 + endloop + endfacet + facet normal 0.0673802 -0.206049 0.976219 + outer loop + vertex 0.989684 1.06004 2.6013 + vertex 0.984963 1.05958 2.60153 + vertex 0.986392 1.05643 2.60076 + endloop + endfacet + facet normal 0.066855 -0.213296 0.974697 + outer loop + vertex 0.982824 1.05232 2.60011 + vertex 0.988383 1.05332 2.59995 + vertex 0.986392 1.05643 2.60076 + endloop + endfacet + facet normal 0.0672463 -0.215542 0.974176 + outer loop + vertex 0.983371 1.04811 2.59914 + vertex 0.988383 1.05332 2.59995 + vertex 0.982824 1.05232 2.60011 + endloop + endfacet + facet normal 0.067674 -0.215935 0.97406 + outer loop + vertex 0.988497 1.04829 2.59883 + vertex 0.988383 1.05332 2.59995 + vertex 0.983371 1.04811 2.59914 + endloop + endfacet + facet normal 0.0676912 -0.216738 0.97388 + outer loop + vertex 0.983742 1.04333 2.59805 + vertex 0.988497 1.04829 2.59883 + vertex 0.983371 1.04811 2.59914 + endloop + endfacet + facet normal 0.0617755 -0.21726 0.974157 + outer loop + vertex 0.983742 1.04333 2.59805 + vertex 0.983371 1.04811 2.59914 + vertex 0.978618 1.04322 2.59835 + endloop + endfacet + facet normal 0.0617622 -0.215325 0.974587 + outer loop + vertex 0.979228 1.0387 2.59732 + vertex 0.983742 1.04333 2.59805 + vertex 0.978618 1.04322 2.59835 + endloop + endfacet + facet normal 0.0492558 -0.217084 0.974909 + outer loop + vertex 0.979228 1.0387 2.59732 + vertex 0.978618 1.04322 2.59835 + vertex 0.974181 1.03862 2.59755 + endloop + endfacet + facet normal 0.0655859 -0.218892 0.973542 + outer loop + vertex 0.984498 1.03848 2.59691 + vertex 0.983742 1.04333 2.59805 + vertex 0.979228 1.0387 2.59732 + endloop + endfacet + facet normal 0.0657221 -0.216626 0.97404 + outer loop + vertex 0.984498 1.03848 2.59691 + vertex 0.979228 1.0387 2.59732 + vertex 0.979825 1.03487 2.59642 + endloop + endfacet + facet normal 0.066763 -0.217926 0.973679 + outer loop + vertex 0.983112 1.03455 2.59613 + vertex 0.984498 1.03848 2.59691 + vertex 0.979825 1.03487 2.59642 + endloop + endfacet + facet normal 0.0664364 -0.220772 0.97306 + outer loop + vertex 0.983112 1.03455 2.59613 + vertex 0.979825 1.03487 2.59642 + vertex 0.98038 1.03213 2.59576 + endloop + endfacet + facet normal 0.0554327 -0.223041 0.973232 + outer loop + vertex 0.98038 1.03213 2.59576 + vertex 0.979825 1.03487 2.59642 + vertex 0.976396 1.03117 2.59577 + endloop + endfacet + facet normal 0.0721873 -0.219686 0.972896 + outer loop + vertex 0.986827 1.03542 2.59605 + vertex 0.984498 1.03848 2.59691 + vertex 0.983112 1.03455 2.59613 + endloop + endfacet + facet normal 0.0719068 -0.219893 0.97287 + outer loop + vertex 0.990076 1.03945 2.59672 + vertex 0.984498 1.03848 2.59691 + vertex 0.986827 1.03542 2.59605 + endloop + endfacet + facet normal 0.0738103 -0.221346 0.972398 + outer loop + vertex 0.991467 1.03602 2.59583 + vertex 0.990076 1.03945 2.59672 + vertex 0.986827 1.03542 2.59605 + endloop + endfacet + facet normal 0.0737862 -0.221144 0.972446 + outer loop + vertex 0.986827 1.03542 2.59605 + vertex 0.987787 1.03202 2.5952 + vertex 0.991467 1.03602 2.59583 + endloop + endfacet + facet normal 0.0745973 -0.221854 0.972222 + outer loop + vertex 0.987787 1.03202 2.5952 + vertex 0.992594 1.03248 2.59494 + vertex 0.991467 1.03602 2.59583 + endloop + endfacet + facet normal 0.0767601 -0.221163 0.972211 + outer loop + vertex 0.991467 1.03602 2.59583 + vertex 0.992594 1.03248 2.59494 + vertex 0.996164 1.03667 2.59561 + endloop + endfacet + facet normal 0.0768341 -0.221752 0.972071 + outer loop + vertex 0.996164 1.03667 2.59561 + vertex 0.99498 1.03995 2.59645 + vertex 0.991467 1.03602 2.59583 + endloop + endfacet + facet normal 0.0798689 -0.220658 0.972076 + outer loop + vertex 0.999466 1.04028 2.59616 + vertex 0.99498 1.03995 2.59645 + vertex 0.996164 1.03667 2.59561 + endloop + endfacet + facet normal 0.0803746 -0.224093 0.971248 + outer loop + vertex 0.992594 1.03248 2.59494 + vertex 0.998199 1.0335 2.59471 + vertex 0.996164 1.03667 2.59561 + endloop + endfacet + facet normal 0.0798737 -0.221164 0.97196 + outer loop + vertex 0.993265 1.02823 2.59391 + vertex 0.998199 1.0335 2.59471 + vertex 0.992594 1.03248 2.59494 + endloop + endfacet + facet normal 0.0755306 -0.221893 0.972141 + outer loop + vertex 0.993265 1.02823 2.59391 + vertex 0.992594 1.03248 2.59494 + vertex 0.988223 1.02794 2.59424 + endloop + endfacet + facet normal 0.0754669 -0.220396 0.972487 + outer loop + vertex 0.988567 1.02341 2.59319 + vertex 0.993265 1.02823 2.59391 + vertex 0.988223 1.02794 2.59424 + endloop + endfacet + facet normal 0.0818497 -0.222928 0.971393 + outer loop + vertex 0.998472 1.02841 2.59352 + vertex 0.998199 1.0335 2.59471 + vertex 0.993265 1.02823 2.59391 + endloop + endfacet + facet normal 0.0745226 -0.220968 0.97243 + outer loop + vertex 0.988223 1.02794 2.59424 + vertex 0.992594 1.03248 2.59494 + vertex 0.987787 1.03202 2.5952 + endloop + endfacet + facet normal 0.0690585 -0.221613 0.972686 + outer loop + vertex 0.988223 1.02794 2.59424 + vertex 0.987787 1.03202 2.5952 + vertex 0.983418 1.02781 2.59455 + endloop + endfacet + facet normal 0.0690627 -0.222012 0.972595 + outer loop + vertex 0.983592 1.0233 2.59351 + vertex 0.988223 1.02794 2.59424 + vertex 0.983418 1.02781 2.59455 + endloop + endfacet + facet normal 0.0565819 -0.222647 0.973256 + outer loop + vertex 0.983592 1.0233 2.59351 + vertex 0.983418 1.02781 2.59455 + vertex 0.97866 1.0233 2.5938 + endloop + endfacet + facet normal 0.0680566 -0.221051 0.972885 + outer loop + vertex 0.988567 1.02341 2.59319 + vertex 0.988223 1.02794 2.59424 + vertex 0.983592 1.0233 2.59351 + endloop + endfacet + facet normal 0.0680584 -0.221397 0.972806 + outer loop + vertex 0.984112 1.01887 2.59246 + vertex 0.988567 1.02341 2.59319 + vertex 0.983592 1.0233 2.59351 + endloop + endfacet + facet normal 0.0542586 -0.223126 0.973278 + outer loop + vertex 0.984112 1.01887 2.59246 + vertex 0.983592 1.0233 2.59351 + vertex 0.979105 1.0188 2.59273 + endloop + endfacet + facet normal 0.0685841 -0.221889 0.972657 + outer loop + vertex 0.989109 1.019 2.59214 + vertex 0.988567 1.02341 2.59319 + vertex 0.984112 1.01887 2.59246 + endloop + endfacet + facet normal 0.0686119 -0.224257 0.972112 + outer loop + vertex 0.985001 1.01492 2.59149 + vertex 0.989109 1.019 2.59214 + vertex 0.984112 1.01887 2.59246 + endloop + endfacet + facet normal 0.0547242 -0.22742 0.972258 + outer loop + vertex 0.985001 1.01492 2.59149 + vertex 0.984112 1.01887 2.59246 + vertex 0.980035 1.01466 2.59171 + endloop + endfacet + facet normal 0.0690141 -0.224643 0.971994 + outer loop + vertex 0.989567 1.01523 2.59124 + vertex 0.989109 1.019 2.59214 + vertex 0.985001 1.01492 2.59149 + endloop + endfacet + facet normal 0.0694052 -0.23167 0.970315 + outer loop + vertex 0.989567 1.01523 2.59124 + vertex 0.985001 1.01492 2.59149 + vertex 0.986145 1.01152 2.5906 + endloop + endfacet + facet normal 0.0569394 -0.235821 0.970127 + outer loop + vertex 0.986145 1.01152 2.5906 + vertex 0.985001 1.01492 2.59149 + vertex 0.981265 1.01094 2.59074 + endloop + endfacet + facet normal 0.071263 -0.223803 0.972026 + outer loop + vertex 0.983418 1.02781 2.59455 + vertex 0.987787 1.03202 2.5952 + vertex 0.983478 1.03177 2.59546 + endloop + endfacet + facet normal 0.0604299 -0.223804 0.972759 + outer loop + vertex 0.983478 1.03177 2.59546 + vertex 0.978461 1.02809 2.59492 + vertex 0.983418 1.02781 2.59455 + endloop + endfacet + facet normal 0.0681129 -0.233866 0.96988 + outer loop + vertex 0.98038 1.03213 2.59576 + vertex 0.978461 1.02809 2.59492 + vertex 0.983478 1.03177 2.59546 + endloop + endfacet + facet normal 0.0711802 -0.221886 0.972471 + outer loop + vertex 0.983478 1.03177 2.59546 + vertex 0.987787 1.03202 2.5952 + vertex 0.986827 1.03542 2.59605 + endloop + endfacet + facet normal 0.0755417 -0.22065 0.972423 + outer loop + vertex 0.99498 1.03995 2.59645 + vertex 0.990076 1.03945 2.59672 + vertex 0.991467 1.03602 2.59583 + endloop + endfacet + facet normal 0.0754952 -0.220119 0.972547 + outer loop + vertex 0.99498 1.03995 2.59645 + vertex 0.994027 1.04381 2.5974 + vertex 0.990076 1.03945 2.59672 + endloop + endfacet + facet normal 0.0748172 -0.219533 0.972732 + outer loop + vertex 0.990076 1.03945 2.59672 + vertex 0.994027 1.04381 2.5974 + vertex 0.988936 1.04352 2.59772 + endloop + endfacet + facet normal 0.0747769 -0.218551 0.972956 + outer loop + vertex 0.994027 1.04381 2.5974 + vertex 0.993504 1.04833 2.59845 + vertex 0.988936 1.04352 2.59772 + endloop + endfacet + facet normal 0.0802156 -0.217857 0.972679 + outer loop + vertex 0.994027 1.04381 2.5974 + vertex 0.998486 1.04841 2.59806 + vertex 0.993504 1.04833 2.59845 + endloop + endfacet + facet normal 0.0802171 -0.215158 0.973279 + outer loop + vertex 0.998486 1.04841 2.59806 + vertex 0.998265 1.05317 2.59913 + vertex 0.993504 1.04833 2.59845 + endloop + endfacet + facet normal 0.0811919 -0.216076 0.972995 + outer loop + vertex 0.993504 1.04833 2.59845 + vertex 0.998265 1.05317 2.59913 + vertex 0.993343 1.05299 2.5995 + endloop + endfacet + facet normal 0.0740889 -0.216432 0.973482 + outer loop + vertex 0.993504 1.04833 2.59845 + vertex 0.993343 1.05299 2.5995 + vertex 0.988497 1.04829 2.59883 + endloop + endfacet + facet normal 0.074075 -0.217913 0.973153 + outer loop + vertex 0.988936 1.04352 2.59772 + vertex 0.993504 1.04833 2.59845 + vertex 0.988497 1.04829 2.59883 + endloop + endfacet + facet normal 0.0849878 -0.21486 0.97294 + outer loop + vertex 0.998486 1.04841 2.59806 + vertex 1.0033 1.0533 2.59872 + vertex 0.998265 1.05317 2.59913 + endloop + endfacet + facet normal 0.0849455 -0.210192 0.973963 + outer loop + vertex 1.0033 1.0533 2.59872 + vertex 1.00321 1.05842 2.59983 + vertex 0.998265 1.05317 2.59913 + endloop + endfacet + facet normal 0.0873112 -0.21233 0.97329 + outer loop + vertex 0.998265 1.05317 2.59913 + vertex 1.00321 1.05842 2.59983 + vertex 0.997768 1.05737 2.60009 + endloop + endfacet + facet normal 0.086021 -0.210154 0.973877 + outer loop + vertex 1.0033 1.0533 2.59872 + vertex 1.0083 1.05819 2.59933 + vertex 1.00321 1.05842 2.59983 + endloop + endfacet + facet normal 0.0861877 -0.210318 0.973826 + outer loop + vertex 1.00839 1.0533 2.59827 + vertex 1.0083 1.05819 2.59933 + vertex 1.0033 1.0533 2.59872 + endloop + endfacet + facet normal 0.0842423 -0.214155 0.97316 + outer loop + vertex 1.00355 1.04845 2.59763 + vertex 1.0033 1.0533 2.59872 + vertex 0.998486 1.04841 2.59806 + endloop + endfacet + facet normal 0.0796888 -0.217368 0.972831 + outer loop + vertex 0.998986 1.04398 2.59703 + vertex 0.998486 1.04841 2.59806 + vertex 0.994027 1.04381 2.5974 + endloop + endfacet + facet normal 0.079718 -0.219054 0.972451 + outer loop + vertex 0.99498 1.03995 2.59645 + vertex 0.998986 1.04398 2.59703 + vertex 0.994027 1.04381 2.5974 + endloop + endfacet + facet normal 0.0719809 -0.220336 0.972765 + outer loop + vertex 0.990076 1.03945 2.59672 + vertex 0.988936 1.04352 2.59772 + vertex 0.984498 1.03848 2.59691 + endloop + endfacet + facet normal 0.0524712 -0.218766 0.974365 + outer loop + vertex 0.979825 1.03487 2.59642 + vertex 0.979228 1.0387 2.59732 + vertex 0.975149 1.03458 2.59661 + endloop + endfacet + facet normal 0.0694915 -0.218253 0.973415 + outer loop + vertex 0.984498 1.03848 2.59691 + vertex 0.988936 1.04352 2.59772 + vertex 0.983742 1.04333 2.59805 + endloop + endfacet + facet normal 0.0601164 -0.215718 0.974603 + outer loop + vertex 0.978618 1.04322 2.59835 + vertex 0.983371 1.04811 2.59914 + vertex 0.978325 1.04787 2.5994 + endloop + endfacet + facet normal 0.0457441 -0.216749 0.975155 + outer loop + vertex 0.978618 1.04322 2.59835 + vertex 0.978325 1.04787 2.5994 + vertex 0.97361 1.04321 2.59859 + endloop + endfacet + facet normal 0.0694947 -0.218389 0.973384 + outer loop + vertex 0.988936 1.04352 2.59772 + vertex 0.988497 1.04829 2.59883 + vertex 0.983742 1.04333 2.59805 + endloop + endfacet + facet normal 0.0601461 -0.216521 0.974423 + outer loop + vertex 0.983371 1.04811 2.59914 + vertex 0.982824 1.05232 2.60011 + vertex 0.978325 1.04787 2.5994 + endloop + endfacet + facet normal 0.0378572 -0.223505 0.973967 + outer loop + vertex 0.975126 1.05226 2.60057 + vertex 0.971149 1.05147 2.60054 + vertex 0.973271 1.04819 2.59971 + endloop + endfacet + facet normal 0.064514 -0.216609 0.974125 + outer loop + vertex 0.977869 1.05467 2.60095 + vertex 0.97828 1.0519 2.60031 + vertex 0.981677 1.05561 2.60091 + endloop + endfacet + facet normal 0.0362869 -0.215682 0.975789 + outer loop + vertex 0.975126 1.05226 2.60057 + vertex 0.974562 1.05503 2.6012 + vertex 0.971149 1.05147 2.60054 + endloop + endfacet + facet normal 0.0621453 -0.206839 0.976399 + outer loop + vertex 0.981677 1.05561 2.60091 + vertex 0.979302 1.05855 2.60168 + vertex 0.977869 1.05467 2.60095 + endloop + endfacet + facet normal 0.0632473 -0.204303 0.976862 + outer loop + vertex 0.984963 1.05958 2.60153 + vertex 0.983841 1.06351 2.60242 + vertex 0.979302 1.05855 2.60168 + endloop + endfacet + facet normal 0.0675644 -0.203063 0.976832 + outer loop + vertex 0.984963 1.05958 2.60153 + vertex 0.989051 1.06378 2.60212 + vertex 0.983841 1.06351 2.60242 + endloop + endfacet + facet normal 0.0675542 -0.202798 0.976888 + outer loop + vertex 0.989051 1.06378 2.60212 + vertex 0.98853 1.06833 2.6031 + vertex 0.983841 1.06351 2.60242 + endloop + endfacet + facet normal 0.0669303 -0.202213 0.977052 + outer loop + vertex 0.983841 1.06351 2.60242 + vertex 0.98853 1.06833 2.6031 + vertex 0.983448 1.06824 2.60343 + endloop + endfacet + facet normal 0.0669288 -0.20174 0.97715 + outer loop + vertex 0.98853 1.06833 2.6031 + vertex 0.98851 1.07323 2.60411 + vertex 0.983448 1.06824 2.60343 + endloop + endfacet + facet normal 0.0726912 -0.201636 0.976759 + outer loop + vertex 0.98853 1.06833 2.6031 + vertex 0.993433 1.07322 2.60374 + vertex 0.98851 1.07323 2.60411 + endloop + endfacet + facet normal 0.0726957 -0.201399 0.976808 + outer loop + vertex 0.993433 1.07322 2.60374 + vertex 0.993501 1.07792 2.60471 + vertex 0.98851 1.07323 2.60411 + endloop + endfacet + facet normal 0.0782172 -0.201392 0.976383 + outer loop + vertex 0.993433 1.07322 2.60374 + vertex 0.998336 1.0781 2.60436 + vertex 0.993501 1.07792 2.60471 + endloop + endfacet + facet normal 0.0781647 -0.199053 0.976867 + outer loop + vertex 0.998336 1.0781 2.60436 + vertex 0.997919 1.08224 2.60524 + vertex 0.993501 1.07792 2.60471 + endloop + endfacet + facet normal 0.0796207 -0.20049 0.976455 + outer loop + vertex 0.993501 1.07792 2.60471 + vertex 0.997919 1.08224 2.60524 + vertex 0.993557 1.08182 2.6055 + endloop + endfacet + facet normal 0.071484 -0.200502 0.977082 + outer loop + vertex 0.993557 1.08182 2.6055 + vertex 0.988613 1.07819 2.60512 + vertex 0.993501 1.07792 2.60471 + endloop + endfacet + facet normal 0.0715075 -0.200177 0.977147 + outer loop + vertex 0.98851 1.07323 2.60411 + vertex 0.993501 1.07792 2.60471 + vertex 0.988613 1.07819 2.60512 + endloop + endfacet + facet normal 0.0649852 -0.200136 0.977611 + outer loop + vertex 0.98851 1.07323 2.60411 + vertex 0.988613 1.07819 2.60512 + vertex 0.983477 1.07309 2.60442 + endloop + endfacet + facet normal 0.0780879 -0.201267 0.976419 + outer loop + vertex 0.998374 1.07324 2.60335 + vertex 0.998336 1.0781 2.60436 + vertex 0.993433 1.07322 2.60374 + endloop + endfacet + facet normal 0.0733847 -0.202306 0.976569 + outer loop + vertex 0.993615 1.06834 2.60272 + vertex 0.993433 1.07322 2.60374 + vertex 0.98853 1.06833 2.6031 + endloop + endfacet + facet normal 0.0649802 -0.199835 0.977673 + outer loop + vertex 0.983448 1.06824 2.60343 + vertex 0.98851 1.07323 2.60411 + vertex 0.983477 1.07309 2.60442 + endloop + endfacet + facet normal 0.0576491 -0.200745 0.977946 + outer loop + vertex 0.978138 1.07952 2.60604 + vertex 0.974841 1.07987 2.60631 + vertex 0.975441 1.07719 2.60572 + endloop + endfacet + facet normal 0.0578661 -0.198974 0.978295 + outer loop + vertex 0.978138 1.07952 2.60604 + vertex 0.979452 1.08336 2.60674 + vertex 0.974841 1.07987 2.60631 + endloop + endfacet + facet normal 0.0586565 -0.199987 0.978041 + outer loop + vertex 0.979452 1.08336 2.60674 + vertex 0.974168 1.08366 2.60712 + vertex 0.974841 1.07987 2.60631 + endloop + endfacet + facet normal 0.0587469 -0.198695 0.978299 + outer loop + vertex 0.979452 1.08336 2.60674 + vertex 0.978619 1.08821 2.60778 + vertex 0.974168 1.08366 2.60712 + endloop + endfacet + facet normal 0.0527398 -0.201065 0.978157 + outer loop + vertex 0.974841 1.07987 2.60631 + vertex 0.974168 1.08366 2.60712 + vertex 0.970198 1.07962 2.6065 + endloop + endfacet + facet normal 0.0512585 -0.199663 0.978523 + outer loop + vertex 0.970198 1.07962 2.6065 + vertex 0.974168 1.08366 2.60712 + vertex 0.969119 1.08357 2.60737 + endloop + endfacet + facet normal 0.0512518 -0.198797 0.9787 + outer loop + vertex 0.974168 1.08366 2.60712 + vertex 0.973533 1.08823 2.60808 + vertex 0.969119 1.08357 2.60737 + endloop + endfacet + facet normal 0.0578442 -0.197846 0.978525 + outer loop + vertex 0.974168 1.08366 2.60712 + vertex 0.978619 1.08821 2.60778 + vertex 0.973533 1.08823 2.60808 + endloop + endfacet + facet normal 0.0578948 -0.194658 0.979161 + outer loop + vertex 0.978619 1.08821 2.60778 + vertex 0.978366 1.09318 2.60878 + vertex 0.973533 1.08823 2.60808 + endloop + endfacet + facet normal 0.0570219 -0.193836 0.979375 + outer loop + vertex 0.973533 1.08823 2.60808 + vertex 0.978366 1.09318 2.60878 + vertex 0.973394 1.0932 2.60907 + endloop + endfacet + facet normal 0.048701 -0.194147 0.979763 + outer loop + vertex 0.973533 1.08823 2.60808 + vertex 0.973394 1.0932 2.60907 + vertex 0.968506 1.08818 2.60832 + endloop + endfacet + facet normal 0.0487023 -0.196478 0.979298 + outer loop + vertex 0.969119 1.08357 2.60737 + vertex 0.973533 1.08823 2.60808 + vertex 0.968506 1.08818 2.60832 + endloop + endfacet + facet normal 0.0341133 -0.198459 0.979515 + outer loop + vertex 0.969119 1.08357 2.60737 + vertex 0.968506 1.08818 2.60832 + vertex 0.964071 1.08352 2.60753 + endloop + endfacet + facet normal 0.0341157 -0.199517 0.9793 + outer loop + vertex 0.965173 1.07936 2.60665 + vertex 0.969119 1.08357 2.60737 + vertex 0.964071 1.08352 2.60753 + endloop + endfacet + facet normal 0.0337133 -0.198093 0.979603 + outer loop + vertex 0.964071 1.08352 2.60753 + vertex 0.968506 1.08818 2.60832 + vertex 0.963496 1.08813 2.60848 + endloop + endfacet + facet normal 0.00733291 -0.201357 0.97949 + outer loop + vertex 0.964071 1.08352 2.60753 + vertex 0.963496 1.08813 2.60848 + vertex 0.959121 1.08379 2.60763 + endloop + endfacet + facet normal 0.00716827 -0.204143 0.978915 + outer loop + vertex 0.96003 1.07944 2.60671 + vertex 0.964071 1.08352 2.60753 + vertex 0.959121 1.08379 2.60763 + endloop + endfacet + facet normal 0.00910187 -0.205977 0.978515 + outer loop + vertex 0.965173 1.07936 2.60665 + vertex 0.964071 1.08352 2.60753 + vertex 0.96003 1.07944 2.60671 + endloop + endfacet + facet normal 0.00907134 -0.207681 0.978155 + outer loop + vertex 0.965173 1.07936 2.60665 + vertex 0.96003 1.07944 2.60671 + vertex 0.96142 1.07551 2.60586 + endloop + endfacet + facet normal -0.034792 -0.222375 0.97434 + outer loop + vertex 0.96142 1.07551 2.60586 + vertex 0.96003 1.07944 2.60671 + vertex 0.956351 1.07586 2.60576 + endloop + endfacet + facet normal -0.0346695 -0.220488 0.974773 + outer loop + vertex 0.956351 1.07586 2.60576 + vertex 0.957555 1.07183 2.60489 + vertex 0.96142 1.07551 2.60586 + endloop + endfacet + facet normal -0.0316332 -0.22352 0.974186 + outer loop + vertex 0.957555 1.07183 2.60489 + vertex 0.962594 1.07176 2.60504 + vertex 0.96142 1.07551 2.60586 + endloop + endfacet + facet normal -0.0315135 -0.208989 0.97741 + outer loop + vertex 0.958605 1.06777 2.60406 + vertex 0.962594 1.07176 2.60504 + vertex 0.957555 1.07183 2.60489 + endloop + endfacet + facet normal -0.104146 -0.225954 0.968555 + outer loop + vertex 0.958605 1.06777 2.60406 + vertex 0.957555 1.07183 2.60489 + vertex 0.953881 1.06808 2.60362 + endloop + endfacet + facet normal -0.103059 -0.201768 0.973996 + outer loop + vertex 0.955349 1.06439 2.60302 + vertex 0.958605 1.06777 2.60406 + vertex 0.953881 1.06808 2.60362 + endloop + endfacet + facet normal -0.0852207 -0.218386 0.972134 + outer loop + vertex 0.959226 1.06342 2.60314 + vertex 0.958605 1.06777 2.60406 + vertex 0.955349 1.06439 2.60302 + endloop + endfacet + facet normal -0.0908099 -0.241436 0.966159 + outer loop + vertex 0.954843 1.05994 2.60186 + vertex 0.959226 1.06342 2.60314 + vertex 0.955349 1.06439 2.60302 + endloop + endfacet + facet normal -0.0994308 -0.23118 0.967817 + outer loop + vertex 0.960382 1.05847 2.60207 + vertex 0.959226 1.06342 2.60314 + vertex 0.954843 1.05994 2.60186 + endloop + endfacet + facet normal -0.100276 -0.234478 0.966936 + outer loop + vertex 0.960382 1.05847 2.60207 + vertex 0.954843 1.05994 2.60186 + vertex 0.95623 1.05521 2.60085 + endloop + endfacet + facet normal -0.112407 -0.219793 0.969049 + outer loop + vertex 0.960151 1.05409 2.60105 + vertex 0.960382 1.05847 2.60207 + vertex 0.95623 1.05521 2.60085 + endloop + endfacet + facet normal -0.122213 -0.255783 0.958978 + outer loop + vertex 0.957928 1.05083 2.5999 + vertex 0.960151 1.05409 2.60105 + vertex 0.95623 1.05521 2.60085 + endloop + endfacet + facet normal -0.220943 -0.288128 0.931754 + outer loop + vertex 0.952554 1.0527 2.59921 + vertex 0.957928 1.05083 2.5999 + vertex 0.95623 1.05521 2.60085 + endloop + endfacet + facet normal -0.207571 -0.306004 0.929127 + outer loop + vertex 0.952423 1.0567 2.60049 + vertex 0.952554 1.0527 2.59921 + vertex 0.95623 1.05521 2.60085 + endloop + endfacet + facet normal -0.206531 -0.240615 0.948393 + outer loop + vertex 0.954748 1.04842 2.5986 + vertex 0.957928 1.05083 2.5999 + vertex 0.952554 1.0527 2.59921 + endloop + endfacet + facet normal -0.0966243 -0.272631 0.957254 + outer loop + vertex 0.962177 1.05172 2.60058 + vertex 0.960151 1.05409 2.60105 + vertex 0.957928 1.05083 2.5999 + endloop + endfacet + facet normal -0.101649 -0.252438 0.962259 + outer loop + vertex 0.962177 1.05172 2.60058 + vertex 0.957928 1.05083 2.5999 + vertex 0.962151 1.04784 2.59956 + endloop + endfacet + facet normal -0.104471 -0.256274 0.960942 + outer loop + vertex 0.962151 1.04784 2.59956 + vertex 0.957928 1.05083 2.5999 + vertex 0.957854 1.04689 2.59884 + endloop + endfacet + facet normal -0.109039 -0.238729 0.964945 + outer loop + vertex 0.959693 1.0441 2.59836 + vertex 0.962151 1.04784 2.59956 + vertex 0.957854 1.04689 2.59884 + endloop + endfacet + facet normal -0.0916982 -0.249811 0.963943 + outer loop + vertex 0.96379 1.04344 2.59858 + vertex 0.962151 1.04784 2.59956 + vertex 0.959693 1.0441 2.59836 + endloop + endfacet + facet normal -0.0917411 -0.250104 0.963863 + outer loop + vertex 0.960038 1.03928 2.59714 + vertex 0.96379 1.04344 2.59858 + vertex 0.959693 1.0441 2.59836 + endloop + endfacet + facet normal -0.198353 -0.250888 0.947476 + outer loop + vertex 0.957854 1.04689 2.59884 + vertex 0.957928 1.05083 2.5999 + vertex 0.954748 1.04842 2.5986 + endloop + endfacet + facet normal -0.0386297 -0.226203 0.973314 + outer loop + vertex 0.962177 1.05172 2.60058 + vertex 0.964578 1.05536 2.60152 + vertex 0.960151 1.05409 2.60105 + endloop + endfacet + facet normal -0.0390857 -0.22473 0.973637 + outer loop + vertex 0.960151 1.05409 2.60105 + vertex 0.964578 1.05536 2.60152 + vertex 0.960382 1.05847 2.60207 + endloop + endfacet + facet normal -0.19009 -0.256717 0.947609 + outer loop + vertex 0.95623 1.05521 2.60085 + vertex 0.954843 1.05994 2.60186 + vertex 0.952423 1.0567 2.60049 + endloop + endfacet + facet normal -0.0278676 -0.216242 0.975942 + outer loop + vertex 0.960382 1.05847 2.60207 + vertex 0.963978 1.06329 2.60324 + vertex 0.959226 1.06342 2.60314 + endloop + endfacet + facet normal -0.0277022 -0.20919 0.977482 + outer loop + vertex 0.963978 1.06329 2.60324 + vertex 0.963356 1.0677 2.60417 + vertex 0.959226 1.06342 2.60314 + endloop + endfacet + facet normal -0.0314664 -0.213668 0.976399 + outer loop + vertex 0.965102 1.05966 2.60249 + vertex 0.963978 1.06329 2.60324 + vertex 0.960382 1.05847 2.60207 + endloop + endfacet + facet normal -0.0312213 -0.214571 0.976209 + outer loop + vertex 0.964578 1.05536 2.60152 + vertex 0.965102 1.05966 2.60249 + vertex 0.960382 1.05847 2.60207 + endloop + endfacet + facet normal -0.0257811 -0.210965 0.977154 + outer loop + vertex 0.959226 1.06342 2.60314 + vertex 0.963356 1.0677 2.60417 + vertex 0.958605 1.06777 2.60406 + endloop + endfacet + facet normal -0.114525 -0.216142 0.969622 + outer loop + vertex 0.953881 1.06808 2.60362 + vertex 0.957555 1.07183 2.60489 + vertex 0.952208 1.07279 2.60448 + endloop + endfacet + facet normal -0.0258142 -0.214445 0.976395 + outer loop + vertex 0.963356 1.0677 2.60417 + vertex 0.962594 1.07176 2.60504 + vertex 0.958605 1.06777 2.60406 + endloop + endfacet + facet normal -0.118838 -0.24303 0.962712 + outer loop + vertex 0.952208 1.07279 2.60448 + vertex 0.957555 1.07183 2.60489 + vertex 0.956351 1.07586 2.60576 + endloop + endfacet + facet normal -0.107447 -0.257402 0.960312 + outer loop + vertex 0.952228 1.07676 2.60554 + vertex 0.952208 1.07279 2.60448 + vertex 0.956351 1.07586 2.60576 + endloop + endfacet + facet normal -0.103443 -0.237535 0.965855 + outer loop + vertex 0.956351 1.07586 2.60576 + vertex 0.954612 1.08028 2.60666 + vertex 0.952228 1.07676 2.60554 + endloop + endfacet + facet normal -0.124549 -0.223527 0.966707 + outer loop + vertex 0.952228 1.07676 2.60554 + vertex 0.954612 1.08028 2.60666 + vertex 0.950321 1.07949 2.60593 + endloop + endfacet + facet normal -0.236308 -0.295535 0.925644 + outer loop + vertex 0.952228 1.07676 2.60554 + vertex 0.950321 1.07949 2.60593 + vertex 0.947804 1.07674 2.60441 + endloop + endfacet + facet normal -0.256371 -0.27736 0.925929 + outer loop + vertex 0.947804 1.07674 2.60441 + vertex 0.950321 1.07949 2.60593 + vertex 0.947396 1.08106 2.60559 + endloop + endfacet + facet normal -0.227603 -0.218433 0.948938 + outer loop + vertex 0.950321 1.07949 2.60593 + vertex 0.95025 1.08419 2.60699 + vertex 0.947396 1.08106 2.60559 + endloop + endfacet + facet normal -0.125097 -0.221007 0.967216 + outer loop + vertex 0.950321 1.07949 2.60593 + vertex 0.954612 1.08028 2.60666 + vertex 0.95025 1.08419 2.60699 + endloop + endfacet + facet normal -0.115425 -0.210527 0.97075 + outer loop + vertex 0.954612 1.08028 2.60666 + vertex 0.955122 1.08473 2.60769 + vertex 0.95025 1.08419 2.60699 + endloop + endfacet + facet normal -0.11391 -0.221455 0.968495 + outer loop + vertex 0.955122 1.08473 2.60769 + vertex 0.954187 1.08839 2.60842 + vertex 0.95025 1.08419 2.60699 + endloop + endfacet + facet normal -0.10524 -0.229296 0.967651 + outer loop + vertex 0.95025 1.08419 2.60699 + vertex 0.954187 1.08839 2.60842 + vertex 0.950393 1.08912 2.60818 + endloop + endfacet + facet normal -0.102756 -0.215102 0.971171 + outer loop + vertex 0.954187 1.08839 2.60842 + vertex 0.953603 1.09254 2.60927 + vertex 0.950393 1.08912 2.60818 + endloop + endfacet + facet normal -0.126612 -0.193289 0.972938 + outer loop + vertex 0.950393 1.08912 2.60818 + vertex 0.953603 1.09254 2.60927 + vertex 0.948888 1.09289 2.60873 + endloop + endfacet + facet normal -0.127925 -0.219877 0.967104 + outer loop + vertex 0.953603 1.09254 2.60927 + vertex 0.952577 1.09652 2.61004 + vertex 0.948888 1.09289 2.60873 + endloop + endfacet + facet normal -0.138286 -0.209658 0.967946 + outer loop + vertex 0.948888 1.09289 2.60873 + vertex 0.952577 1.09652 2.61004 + vertex 0.947213 1.09763 2.60952 + endloop + endfacet + facet normal -0.142228 -0.231456 0.962393 + outer loop + vertex 0.947213 1.09763 2.60952 + vertex 0.952577 1.09652 2.61004 + vertex 0.951362 1.10053 2.61083 + endloop + endfacet + facet normal -0.132463 -0.24457 0.960541 + outer loop + vertex 0.947225 1.10157 2.61052 + vertex 0.947213 1.09763 2.60952 + vertex 0.951362 1.10053 2.61083 + endloop + endfacet + facet normal -0.124906 -0.211753 0.969309 + outer loop + vertex 0.951362 1.10053 2.61083 + vertex 0.949603 1.10506 2.61159 + vertex 0.947225 1.10157 2.61052 + endloop + endfacet + facet normal -0.144583 -0.198382 0.969402 + outer loop + vertex 0.947225 1.10157 2.61052 + vertex 0.949603 1.10506 2.61159 + vertex 0.945319 1.10441 2.61082 + endloop + endfacet + facet normal -0.265387 -0.274559 0.924222 + outer loop + vertex 0.947225 1.10157 2.61052 + vertex 0.945319 1.10441 2.61082 + vertex 0.942829 1.10173 2.60931 + endloop + endfacet + facet normal -0.278821 -0.261936 0.923931 + outer loop + vertex 0.942829 1.10173 2.60931 + vertex 0.945319 1.10441 2.61082 + vertex 0.942434 1.10607 2.61042 + endloop + endfacet + facet normal -0.243579 -0.19439 0.950201 + outer loop + vertex 0.945319 1.10441 2.61082 + vertex 0.945267 1.10919 2.61178 + vertex 0.942434 1.10607 2.61042 + endloop + endfacet + facet normal -0.144791 -0.19724 0.969604 + outer loop + vertex 0.945319 1.10441 2.61082 + vertex 0.949603 1.10506 2.61159 + vertex 0.945267 1.10919 2.61178 + endloop + endfacet + facet normal -0.130985 -0.182971 0.974353 + outer loop + vertex 0.949603 1.10506 2.61159 + vertex 0.950088 1.1096 2.61251 + vertex 0.945267 1.10919 2.61178 + endloop + endfacet + facet normal -0.12982 -0.193289 0.972515 + outer loop + vertex 0.950088 1.1096 2.61251 + vertex 0.949153 1.11349 2.61316 + vertex 0.945267 1.10919 2.61178 + endloop + endfacet + facet normal -0.115527 -0.205957 0.971718 + outer loop + vertex 0.945267 1.10919 2.61178 + vertex 0.949153 1.11349 2.61316 + vertex 0.945403 1.11426 2.61287 + endloop + endfacet + facet normal -0.11356 -0.195525 0.974102 + outer loop + vertex 0.949153 1.11349 2.61316 + vertex 0.948483 1.11792 2.61397 + vertex 0.945403 1.11426 2.61287 + endloop + endfacet + facet normal -0.132474 -0.179821 0.974738 + outer loop + vertex 0.945403 1.11426 2.61287 + vertex 0.948483 1.11792 2.61397 + vertex 0.943943 1.11798 2.61336 + endloop + endfacet + facet normal -0.132068 -0.209531 0.968842 + outer loop + vertex 0.948483 1.11792 2.61397 + vertex 0.946948 1.12254 2.61476 + vertex 0.943943 1.11798 2.61336 + endloop + endfacet + facet normal -0.160309 -0.190806 0.968449 + outer loop + vertex 0.943943 1.11798 2.61336 + vertex 0.946948 1.12254 2.61476 + vertex 0.942309 1.1217 2.61383 + endloop + endfacet + facet normal -0.155095 -0.214931 0.964236 + outer loop + vertex 0.946948 1.12254 2.61476 + vertex 0.942298 1.12641 2.61487 + vertex 0.942309 1.1217 2.61383 + endloop + endfacet + facet normal -0.155212 -0.21507 0.964186 + outer loop + vertex 0.947138 1.12663 2.6157 + vertex 0.942298 1.12641 2.61487 + vertex 0.946948 1.12254 2.61476 + endloop + endfacet + facet normal -0.152769 -0.244328 0.957583 + outer loop + vertex 0.947138 1.12663 2.6157 + vertex 0.945103 1.12928 2.61605 + vertex 0.942298 1.12641 2.61487 + endloop + endfacet + facet normal -0.171431 -0.226597 0.958783 + outer loop + vertex 0.942298 1.12641 2.61487 + vertex 0.945103 1.12928 2.61605 + vertex 0.941885 1.13069 2.61581 + endloop + endfacet + facet normal -0.149802 -0.174792 0.973143 + outer loop + vertex 0.945103 1.12928 2.61605 + vertex 0.94481 1.13404 2.61686 + vertex 0.941885 1.13069 2.61581 + endloop + endfacet + facet normal -0.0661388 -0.171328 0.982991 + outer loop + vertex 0.945103 1.12928 2.61605 + vertex 0.949564 1.13015 2.6165 + vertex 0.94481 1.13404 2.61686 + endloop + endfacet + facet normal -0.0632508 -0.167875 0.983777 + outer loop + vertex 0.949564 1.13015 2.6165 + vertex 0.94991 1.13449 2.61727 + vertex 0.94481 1.13404 2.61686 + endloop + endfacet + facet normal -0.062887 -0.171506 0.983174 + outer loop + vertex 0.94991 1.13449 2.61727 + vertex 0.948925 1.13843 2.61789 + vertex 0.94481 1.13404 2.61686 + endloop + endfacet + facet normal -0.0580659 -0.17592 0.98269 + outer loop + vertex 0.94481 1.13404 2.61686 + vertex 0.948925 1.13843 2.61789 + vertex 0.944994 1.13934 2.61782 + endloop + endfacet + facet normal -0.0565468 -0.169272 0.983946 + outer loop + vertex 0.948925 1.13843 2.61789 + vertex 0.948655 1.14314 2.61869 + vertex 0.944994 1.13934 2.61782 + endloop + endfacet + facet normal -0.0600036 -0.166021 0.984295 + outer loop + vertex 0.944994 1.13934 2.61782 + vertex 0.948655 1.14314 2.61869 + vertex 0.944089 1.14337 2.61845 + endloop + endfacet + facet normal -0.0603763 -0.175172 0.982685 + outer loop + vertex 0.948655 1.14314 2.61869 + vertex 0.94833 1.14759 2.61946 + vertex 0.944089 1.14337 2.61845 + endloop + endfacet + facet normal -0.0588065 -0.176705 0.982505 + outer loop + vertex 0.944089 1.14337 2.61845 + vertex 0.94833 1.14759 2.61946 + vertex 0.943483 1.14779 2.61921 + endloop + endfacet + facet normal -0.0590489 -0.184336 0.981088 + outer loop + vertex 0.94833 1.14759 2.61946 + vertex 0.947588 1.15172 2.62019 + vertex 0.943483 1.14779 2.61921 + endloop + endfacet + facet normal -0.0702059 -0.173021 0.982413 + outer loop + vertex 0.943483 1.14779 2.61921 + vertex 0.947588 1.15172 2.62019 + vertex 0.941977 1.15237 2.6199 + endloop + endfacet + facet normal -0.0723579 -0.193256 0.978477 + outer loop + vertex 0.941977 1.15237 2.6199 + vertex 0.947588 1.15172 2.62019 + vertex 0.946466 1.15563 2.62088 + endloop + endfacet + facet normal -0.0618397 -0.207112 0.976361 + outer loop + vertex 0.942184 1.15643 2.62078 + vertex 0.941977 1.15237 2.6199 + vertex 0.946466 1.15563 2.62088 + endloop + endfacet + facet normal -0.0562678 -0.176289 0.982729 + outer loop + vertex 0.946466 1.15563 2.62088 + vertex 0.944592 1.1599 2.62154 + vertex 0.942184 1.15643 2.62078 + endloop + endfacet + facet normal -0.0157707 -0.159184 0.987123 + outer loop + vertex 0.950148 1.15912 2.6215 + vertex 0.944592 1.1599 2.62154 + vertex 0.946466 1.15563 2.62088 + endloop + endfacet + facet normal -0.0148314 -0.152514 0.98819 + outer loop + vertex 0.950148 1.15912 2.6215 + vertex 0.949026 1.16334 2.62214 + vertex 0.944592 1.1599 2.62154 + endloop + endfacet + facet normal -0.0131112 -0.154679 0.987878 + outer loop + vertex 0.944592 1.1599 2.62154 + vertex 0.949026 1.16334 2.62214 + vertex 0.944871 1.16426 2.62222 + endloop + endfacet + facet normal -0.0698381 -0.150759 0.986101 + outer loop + vertex 0.944592 1.1599 2.62154 + vertex 0.944871 1.16426 2.62222 + vertex 0.93983 1.16386 2.62181 + endloop + endfacet + facet normal -0.0696051 -0.153313 0.985723 + outer loop + vertex 0.944871 1.16426 2.62222 + vertex 0.943829 1.16825 2.62277 + vertex 0.93983 1.16386 2.62181 + endloop + endfacet + facet normal -0.0630015 -0.159218 0.985231 + outer loop + vertex 0.93983 1.16386 2.62181 + vertex 0.943829 1.16825 2.62277 + vertex 0.939921 1.16918 2.62267 + endloop + endfacet + facet normal -0.0603505 -0.147791 0.987176 + outer loop + vertex 0.943829 1.16825 2.62277 + vertex 0.943537 1.17315 2.62349 + vertex 0.939921 1.16918 2.62267 + endloop + endfacet + facet normal -0.0618546 -0.146443 0.987283 + outer loop + vertex 0.939921 1.16918 2.62267 + vertex 0.943537 1.17315 2.62349 + vertex 0.939011 1.17335 2.62323 + endloop + endfacet + facet normal -0.0619783 -0.149843 0.986765 + outer loop + vertex 0.943537 1.17315 2.62349 + vertex 0.943296 1.17801 2.62421 + vertex 0.939011 1.17335 2.62323 + endloop + endfacet + facet normal -0.0570768 -0.154272 0.986378 + outer loop + vertex 0.939011 1.17335 2.62323 + vertex 0.943296 1.17801 2.62421 + vertex 0.938443 1.17804 2.62393 + endloop + endfacet + facet normal -0.0570639 -0.159513 0.985545 + outer loop + vertex 0.943296 1.17801 2.62421 + vertex 0.942553 1.18247 2.62489 + vertex 0.938443 1.17804 2.62393 + endloop + endfacet + facet normal -0.0702756 -0.147487 0.986564 + outer loop + vertex 0.938443 1.17804 2.62393 + vertex 0.942553 1.18247 2.62489 + vertex 0.937063 1.18291 2.62457 + endloop + endfacet + facet normal -0.0720375 -0.172527 0.982367 + outer loop + vertex 0.937063 1.18291 2.62457 + vertex 0.942553 1.18247 2.62489 + vertex 0.941458 1.18645 2.62551 + endloop + endfacet + facet normal -0.0111013 -0.145722 0.989263 + outer loop + vertex 0.949026 1.16334 2.62214 + vertex 0.948478 1.16797 2.62281 + vertex 0.944871 1.16426 2.62222 + endloop + endfacet + facet normal -0.0169531 -0.140157 0.989984 + outer loop + vertex 0.944871 1.16426 2.62222 + vertex 0.948478 1.16797 2.62281 + vertex 0.943829 1.16825 2.62277 + endloop + endfacet + facet normal -0.0172296 -0.144885 0.989298 + outer loop + vertex 0.948478 1.16797 2.62281 + vertex 0.948262 1.17296 2.62354 + vertex 0.943829 1.16825 2.62277 + endloop + endfacet + facet normal -0.0165829 -0.145482 0.989222 + outer loop + vertex 0.943829 1.16825 2.62277 + vertex 0.948262 1.17296 2.62354 + vertex 0.943537 1.17315 2.62349 + endloop + endfacet + facet normal -0.0165841 -0.145512 0.989217 + outer loop + vertex 0.948262 1.17296 2.62354 + vertex 0.948346 1.17807 2.62429 + vertex 0.943537 1.17315 2.62349 + endloop + endfacet + facet normal -0.0141988 -0.147793 0.988916 + outer loop + vertex 0.943537 1.17315 2.62349 + vertex 0.948346 1.17807 2.62429 + vertex 0.943296 1.17801 2.62421 + endloop + endfacet + facet normal -0.0141831 -0.148833 0.988761 + outer loop + vertex 0.948346 1.17807 2.62429 + vertex 0.948328 1.18317 2.62506 + vertex 0.943296 1.17801 2.62421 + endloop + endfacet + facet normal 0.0135234 -0.14874 0.988784 + outer loop + vertex 0.948346 1.17807 2.62429 + vertex 0.953455 1.18281 2.62494 + vertex 0.948328 1.18317 2.62506 + endloop + endfacet + facet normal 0.00972698 -0.144733 0.989423 + outer loop + vertex 0.953384 1.17807 2.62424 + vertex 0.953455 1.18281 2.62494 + vertex 0.948346 1.17807 2.62429 + endloop + endfacet + facet normal 0.0253103 -0.144923 0.989119 + outer loop + vertex 0.953384 1.17807 2.62424 + vertex 0.958478 1.18294 2.62483 + vertex 0.953455 1.18281 2.62494 + endloop + endfacet + facet normal 0.0252539 -0.14237 0.989491 + outer loop + vertex 0.958478 1.18294 2.62483 + vertex 0.957962 1.18692 2.62541 + vertex 0.953455 1.18281 2.62494 + endloop + endfacet + facet normal 0.0272496 -0.144514 0.989128 + outer loop + vertex 0.953455 1.18281 2.62494 + vertex 0.957962 1.18692 2.62541 + vertex 0.953417 1.18671 2.62551 + endloop + endfacet + facet normal 0.0242695 -0.143854 0.989301 + outer loop + vertex 0.958455 1.17816 2.62413 + vertex 0.958478 1.18294 2.62483 + vertex 0.953384 1.17807 2.62424 + endloop + endfacet + facet normal 0.0242977 -0.145757 0.989022 + outer loop + vertex 0.953213 1.17292 2.62349 + vertex 0.958455 1.17816 2.62413 + vertex 0.953384 1.17807 2.62424 + endloop + endfacet + facet normal 0.00906507 -0.145299 0.989346 + outer loop + vertex 0.953213 1.17292 2.62349 + vertex 0.953384 1.17807 2.62424 + vertex 0.948262 1.17296 2.62354 + endloop + endfacet + facet normal 0.0244735 -0.145929 0.988992 + outer loop + vertex 0.958235 1.17294 2.62337 + vertex 0.958455 1.17816 2.62413 + vertex 0.953213 1.17292 2.62349 + endloop + endfacet + facet normal 0.0244728 -0.145401 0.98907 + outer loop + vertex 0.953317 1.16778 2.62273 + vertex 0.958235 1.17294 2.62337 + vertex 0.953213 1.17292 2.62349 + endloop + endfacet + facet normal 0.0111212 -0.145698 0.989267 + outer loop + vertex 0.953317 1.16778 2.62273 + vertex 0.953213 1.17292 2.62349 + vertex 0.948478 1.16797 2.62281 + endloop + endfacet + facet normal 0.0112277 -0.143136 0.989639 + outer loop + vertex 0.949026 1.16334 2.62214 + vertex 0.953317 1.16778 2.62273 + vertex 0.948478 1.16797 2.62281 + endloop + endfacet + facet normal 0.0144645 -0.146194 0.98915 + outer loop + vertex 0.954022 1.16312 2.62203 + vertex 0.953317 1.16778 2.62273 + vertex 0.949026 1.16334 2.62214 + endloop + endfacet + facet normal 0.0145263 -0.144876 0.989343 + outer loop + vertex 0.950148 1.15912 2.6215 + vertex 0.954022 1.16312 2.62203 + vertex 0.949026 1.16334 2.62214 + endloop + endfacet + facet normal 0.0183569 -0.14851 0.988741 + outer loop + vertex 0.955311 1.15914 2.62141 + vertex 0.954022 1.16312 2.62203 + vertex 0.950148 1.15912 2.6215 + endloop + endfacet + facet normal 0.018355 -0.154401 0.987838 + outer loop + vertex 0.955311 1.15914 2.62141 + vertex 0.950148 1.15912 2.6215 + vertex 0.951648 1.1554 2.62089 + endloop + endfacet + facet normal 0.020521 -0.156473 0.987469 + outer loop + vertex 0.956731 1.15562 2.62082 + vertex 0.955311 1.15914 2.62141 + vertex 0.951648 1.1554 2.62089 + endloop + endfacet + facet normal 0.020994 -0.167695 0.985615 + outer loop + vertex 0.951648 1.1554 2.62089 + vertex 0.952752 1.15174 2.62025 + vertex 0.956731 1.15562 2.62082 + endloop + endfacet + facet normal 0.0207394 -0.167441 0.985664 + outer loop + vertex 0.952752 1.15174 2.62025 + vertex 0.957782 1.15204 2.62019 + vertex 0.956731 1.15562 2.62082 + endloop + endfacet + facet normal 0.0357385 -0.163098 0.985962 + outer loop + vertex 0.956731 1.15562 2.62082 + vertex 0.957782 1.15204 2.62019 + vertex 0.961646 1.15604 2.62071 + endloop + endfacet + facet normal 0.0210641 -0.17306 0.984686 + outer loop + vertex 0.953274 1.14765 2.61952 + vertex 0.957782 1.15204 2.62019 + vertex 0.952752 1.15174 2.62025 + endloop + endfacet + facet normal -0.00916507 -0.176834 0.984198 + outer loop + vertex 0.953274 1.14765 2.61952 + vertex 0.952752 1.15174 2.62025 + vertex 0.94833 1.14759 2.61946 + endloop + endfacet + facet normal -0.00923794 -0.171855 0.985079 + outer loop + vertex 0.948655 1.14314 2.61869 + vertex 0.953274 1.14765 2.61952 + vertex 0.94833 1.14759 2.61946 + endloop + endfacet + facet normal -0.0096943 -0.171401 0.985154 + outer loop + vertex 0.953379 1.14299 2.61871 + vertex 0.953274 1.14765 2.61952 + vertex 0.948655 1.14314 2.61869 + endloop + endfacet + facet normal -0.00955288 -0.166907 0.985926 + outer loop + vertex 0.948925 1.13843 2.61789 + vertex 0.953379 1.14299 2.61871 + vertex 0.948655 1.14314 2.61869 + endloop + endfacet + facet normal -0.0109075 -0.16562 0.986129 + outer loop + vertex 0.953583 1.13816 2.6179 + vertex 0.953379 1.14299 2.61871 + vertex 0.948925 1.13843 2.61789 + endloop + endfacet + facet normal -0.0105366 -0.159052 0.987214 + outer loop + vertex 0.94991 1.13449 2.61727 + vertex 0.953583 1.13816 2.6179 + vertex 0.948925 1.13843 2.61789 + endloop + endfacet + facet normal -0.00569779 -0.163764 0.986483 + outer loop + vertex 0.954066 1.13359 2.61714 + vertex 0.953583 1.13816 2.6179 + vertex 0.94991 1.13449 2.61727 + endloop + endfacet + facet normal -0.00764473 -0.17253 0.984975 + outer loop + vertex 0.949564 1.13015 2.6165 + vertex 0.954066 1.13359 2.61714 + vertex 0.94991 1.13449 2.61727 + endloop + endfacet + facet normal -0.00916063 -0.170603 0.985297 + outer loop + vertex 0.955125 1.12944 2.61643 + vertex 0.954066 1.13359 2.61714 + vertex 0.949564 1.13015 2.6165 + endloop + endfacet + facet normal -0.00993567 -0.1766 0.984233 + outer loop + vertex 0.955125 1.12944 2.61643 + vertex 0.949564 1.13015 2.6165 + vertex 0.951407 1.12591 2.61576 + endloop + endfacet + facet normal -0.0464415 -0.191791 0.980336 + outer loop + vertex 0.951407 1.12591 2.61576 + vertex 0.949564 1.13015 2.6165 + vertex 0.947138 1.12663 2.6157 + endloop + endfacet + facet normal -0.0514402 -0.222081 0.97367 + outer loop + vertex 0.947138 1.12663 2.6157 + vertex 0.946948 1.12254 2.61476 + vertex 0.951407 1.12591 2.61576 + endloop + endfacet + facet normal -0.0615206 -0.209393 0.975894 + outer loop + vertex 0.946948 1.12254 2.61476 + vertex 0.952522 1.12198 2.61499 + vertex 0.951407 1.12591 2.61576 + endloop + endfacet + facet normal -0.0594839 -0.187401 0.980481 + outer loop + vertex 0.948483 1.11792 2.61397 + vertex 0.952522 1.12198 2.61499 + vertex 0.946948 1.12254 2.61476 + endloop + endfacet + facet normal -0.049352 -0.19715 0.97913 + outer loop + vertex 0.953292 1.11775 2.61418 + vertex 0.952522 1.12198 2.61499 + vertex 0.948483 1.11792 2.61397 + endloop + endfacet + facet normal -0.049074 -0.187079 0.981118 + outer loop + vertex 0.949153 1.11349 2.61316 + vertex 0.953292 1.11775 2.61418 + vertex 0.948483 1.11792 2.61397 + endloop + endfacet + facet normal -0.0521679 -0.184169 0.981509 + outer loop + vertex 0.953704 1.11322 2.61335 + vertex 0.953292 1.11775 2.61418 + vertex 0.949153 1.11349 2.61316 + endloop + endfacet + facet normal -0.0517657 -0.176234 0.982986 + outer loop + vertex 0.950088 1.1096 2.61251 + vertex 0.953704 1.11322 2.61335 + vertex 0.949153 1.11349 2.61316 + endloop + endfacet + facet normal -0.050115 -0.177837 0.982783 + outer loop + vertex 0.954085 1.10855 2.61252 + vertex 0.953704 1.11322 2.61335 + vertex 0.950088 1.1096 2.61251 + endloop + endfacet + facet normal -0.0539415 -0.192311 0.97985 + outer loop + vertex 0.949603 1.10506 2.61159 + vertex 0.954085 1.10855 2.61252 + vertex 0.950088 1.1096 2.61251 + endloop + endfacet + facet normal -0.0597464 -0.185126 0.980897 + outer loop + vertex 0.955025 1.10406 2.61173 + vertex 0.954085 1.10855 2.61252 + vertex 0.949603 1.10506 2.61159 + endloop + endfacet + facet normal 0.0172912 -0.164446 0.986234 + outer loop + vertex 0.953583 1.13816 2.6179 + vertex 0.958285 1.143 2.61862 + vertex 0.953379 1.14299 2.61871 + endloop + endfacet + facet normal 0.0172924 -0.168743 0.985508 + outer loop + vertex 0.958285 1.143 2.61862 + vertex 0.958246 1.14785 2.61945 + vertex 0.953379 1.14299 2.61871 + endloop + endfacet + facet normal 0.0346392 -0.168531 0.985088 + outer loop + vertex 0.958285 1.143 2.61862 + vertex 0.963311 1.14816 2.61933 + vertex 0.958246 1.14785 2.61945 + endloop + endfacet + facet normal 0.0346008 -0.167837 0.985207 + outer loop + vertex 0.963311 1.14816 2.61933 + vertex 0.962803 1.15252 2.62009 + vertex 0.958246 1.14785 2.61945 + endloop + endfacet + facet normal 0.0363198 -0.16947 0.984866 + outer loop + vertex 0.958246 1.14785 2.61945 + vertex 0.962803 1.15252 2.62009 + vertex 0.957782 1.15204 2.62019 + endloop + endfacet + facet normal 0.032251 -0.166266 0.985553 + outer loop + vertex 0.963265 1.14304 2.61847 + vertex 0.963311 1.14816 2.61933 + vertex 0.958285 1.143 2.61862 + endloop + endfacet + facet normal 0.0322438 -0.164152 0.985908 + outer loop + vertex 0.958416 1.13798 2.61778 + vertex 0.963265 1.14304 2.61847 + vertex 0.958285 1.143 2.61862 + endloop + endfacet + facet normal 0.0314569 -0.163419 0.986055 + outer loop + vertex 0.96344 1.13795 2.61762 + vertex 0.963265 1.14304 2.61847 + vertex 0.958416 1.13798 2.61778 + endloop + endfacet + facet normal 0.0314836 -0.16087 0.986473 + outer loop + vertex 0.959084 1.13337 2.61701 + vertex 0.96344 1.13795 2.61762 + vertex 0.958416 1.13798 2.61778 + endloop + endfacet + facet normal 0.0189642 -0.162688 0.986495 + outer loop + vertex 0.959084 1.13337 2.61701 + vertex 0.958416 1.13798 2.61778 + vertex 0.954066 1.13359 2.61714 + endloop + endfacet + facet normal 0.0189214 -0.163604 0.986345 + outer loop + vertex 0.955125 1.12944 2.61643 + vertex 0.959084 1.13337 2.61701 + vertex 0.954066 1.13359 2.61714 + endloop + endfacet + facet normal 0.0205945 -0.165245 0.986038 + outer loop + vertex 0.960256 1.12949 2.61633 + vertex 0.959084 1.13337 2.61701 + vertex 0.955125 1.12944 2.61643 + endloop + endfacet + facet normal 0.0206383 -0.174348 0.984468 + outer loop + vertex 0.960256 1.12949 2.61633 + vertex 0.955125 1.12944 2.61643 + vertex 0.956573 1.12579 2.61576 + endloop + endfacet + facet normal -0.00315224 -0.183505 0.983014 + outer loop + vertex 0.956573 1.12579 2.61576 + vertex 0.955125 1.12944 2.61643 + vertex 0.951407 1.12591 2.61576 + endloop + endfacet + facet normal -0.00340046 -0.193918 0.981012 + outer loop + vertex 0.951407 1.12591 2.61576 + vertex 0.952522 1.12198 2.61499 + vertex 0.956573 1.12579 2.61576 + endloop + endfacet + facet normal -0.00318895 -0.194135 0.98097 + outer loop + vertex 0.952522 1.12198 2.61499 + vertex 0.957778 1.12217 2.61504 + vertex 0.956573 1.12579 2.61576 + endloop + endfacet + facet normal 0.0223429 -0.1859 0.982315 + outer loop + vertex 0.956573 1.12579 2.61576 + vertex 0.957778 1.12217 2.61504 + vertex 0.961592 1.12622 2.61572 + endloop + endfacet + facet normal 0.0214274 -0.17511 0.984316 + outer loop + vertex 0.961592 1.12622 2.61572 + vertex 0.960256 1.12949 2.61633 + vertex 0.956573 1.12579 2.61576 + endloop + endfacet + facet normal 0.0326009 -0.170628 0.984796 + outer loop + vertex 0.964937 1.12969 2.61621 + vertex 0.960256 1.12949 2.61633 + vertex 0.961592 1.12622 2.61572 + endloop + endfacet + facet normal 0.0243264 -0.187702 0.981925 + outer loop + vertex 0.957778 1.12217 2.61504 + vertex 0.963564 1.1231 2.61508 + vertex 0.961592 1.12622 2.61572 + endloop + endfacet + facet normal 0.0238138 -0.184533 0.982538 + outer loop + vertex 0.958356 1.1179 2.61423 + vertex 0.963564 1.1231 2.61508 + vertex 0.957778 1.12217 2.61504 + endloop + endfacet + facet normal -0.00442397 -0.188279 0.982106 + outer loop + vertex 0.958356 1.1179 2.61423 + vertex 0.957778 1.12217 2.61504 + vertex 0.953292 1.11775 2.61418 + endloop + endfacet + facet normal -0.00468521 -0.180234 0.983613 + outer loop + vertex 0.953704 1.11322 2.61335 + vertex 0.958356 1.1179 2.61423 + vertex 0.953292 1.11775 2.61418 + endloop + endfacet + facet normal -0.00682982 -0.178173 0.983976 + outer loop + vertex 0.958495 1.11302 2.61335 + vertex 0.958356 1.1179 2.61423 + vertex 0.953704 1.11322 2.61335 + endloop + endfacet + facet normal -0.00668363 -0.174622 0.984613 + outer loop + vertex 0.954085 1.10855 2.61252 + vertex 0.958495 1.11302 2.61335 + vertex 0.953704 1.11322 2.61335 + endloop + endfacet + facet normal -0.00685593 -0.174457 0.984641 + outer loop + vertex 0.959019 1.1082 2.6125 + vertex 0.958495 1.11302 2.61335 + vertex 0.954085 1.10855 2.61252 + endloop + endfacet + facet normal 0.0206609 -0.177381 0.983925 + outer loop + vertex 0.958495 1.11302 2.61335 + vertex 0.963442 1.11805 2.61415 + vertex 0.958356 1.1179 2.61423 + endloop + endfacet + facet normal 0.0212421 -0.177935 0.983813 + outer loop + vertex 0.963456 1.11302 2.61324 + vertex 0.963442 1.11805 2.61415 + vertex 0.958495 1.11302 2.61335 + endloop + endfacet + facet normal 0.0207687 -0.181581 0.983157 + outer loop + vertex 0.963442 1.11805 2.61415 + vertex 0.963564 1.1231 2.61508 + vertex 0.958356 1.1179 2.61423 + endloop + endfacet + facet normal -0.00337276 -0.189308 0.981912 + outer loop + vertex 0.953292 1.11775 2.61418 + vertex 0.957778 1.12217 2.61504 + vertex 0.952522 1.12198 2.61499 + endloop + endfacet + facet normal 0.0323846 -0.161735 0.986303 + outer loop + vertex 0.960256 1.12949 2.61633 + vertex 0.964179 1.13341 2.61685 + vertex 0.959084 1.13337 2.61701 + endloop + endfacet + facet normal 0.017577 -0.16135 0.986741 + outer loop + vertex 0.954066 1.13359 2.61714 + vertex 0.958416 1.13798 2.61778 + vertex 0.953583 1.13816 2.6179 + endloop + endfacet + facet normal 0.0323846 -0.161705 0.986308 + outer loop + vertex 0.964179 1.13341 2.61685 + vertex 0.96344 1.13795 2.61762 + vertex 0.959084 1.13337 2.61701 + endloop + endfacet + facet normal 0.0409043 -0.163045 0.98577 + outer loop + vertex 0.96344 1.13795 2.61762 + vertex 0.968268 1.14303 2.61826 + vertex 0.963265 1.14304 2.61847 + endloop + endfacet + facet normal 0.0408968 -0.163896 0.98563 + outer loop + vertex 0.968268 1.14303 2.61826 + vertex 0.968381 1.1483 2.61913 + vertex 0.963265 1.14304 2.61847 + endloop + endfacet + facet normal 0.0504073 -0.164024 0.985168 + outer loop + vertex 0.968268 1.14303 2.61826 + vertex 0.973339 1.14823 2.61886 + vertex 0.968381 1.1483 2.61913 + endloop + endfacet + facet normal 0.0504674 -0.161467 0.985587 + outer loop + vertex 0.973339 1.14823 2.61886 + vertex 0.9735 1.15329 2.61968 + vertex 0.968381 1.1483 2.61913 + endloop + endfacet + facet normal 0.0531766 -0.164183 0.984996 + outer loop + vertex 0.968381 1.1483 2.61913 + vertex 0.9735 1.15329 2.61968 + vertex 0.968392 1.15351 2.62 + endloop + endfacet + facet normal 0.0433831 -0.16424 0.985466 + outer loop + vertex 0.968381 1.1483 2.61913 + vertex 0.968392 1.15351 2.62 + vertex 0.963311 1.14816 2.61933 + endloop + endfacet + facet normal 0.0578391 -0.161632 0.985155 + outer loop + vertex 0.973339 1.14823 2.61886 + vertex 0.978472 1.15332 2.6194 + vertex 0.9735 1.15329 2.61968 + endloop + endfacet + facet normal 0.0578581 -0.155909 0.986076 + outer loop + vertex 0.978472 1.15332 2.6194 + vertex 0.978532 1.15831 2.62018 + vertex 0.9735 1.15329 2.61968 + endloop + endfacet + facet normal 0.0625001 -0.160457 0.985062 + outer loop + vertex 0.9735 1.15329 2.61968 + vertex 0.978532 1.15831 2.62018 + vertex 0.973366 1.15734 2.62035 + endloop + endfacet + facet normal 0.0555545 -0.15938 0.985653 + outer loop + vertex 0.978257 1.14813 2.61857 + vertex 0.978472 1.15332 2.6194 + vertex 0.973339 1.14823 2.61886 + endloop + endfacet + facet normal 0.0485024 -0.16221 0.985564 + outer loop + vertex 0.973294 1.143 2.61801 + vertex 0.973339 1.14823 2.61886 + vertex 0.968268 1.14303 2.61826 + endloop + endfacet + facet normal 0.0402526 -0.162442 0.985897 + outer loop + vertex 0.968578 1.13796 2.61741 + vertex 0.968268 1.14303 2.61826 + vertex 0.96344 1.13795 2.61762 + endloop + endfacet + facet normal 0.0434281 -0.166295 0.985119 + outer loop + vertex 0.963265 1.14304 2.61847 + vertex 0.968381 1.1483 2.61913 + vertex 0.963311 1.14816 2.61933 + endloop + endfacet + facet normal 0.0174412 -0.164588 0.986208 + outer loop + vertex 0.958416 1.13798 2.61778 + vertex 0.958285 1.143 2.61862 + vertex 0.953583 1.13816 2.6179 + endloop + endfacet + facet normal 0.0193485 -0.17074 0.985126 + outer loop + vertex 0.953379 1.14299 2.61871 + vertex 0.958246 1.14785 2.61945 + vertex 0.953274 1.14765 2.61952 + endloop + endfacet + facet normal -0.0098893 -0.176087 0.984325 + outer loop + vertex 0.94833 1.14759 2.61946 + vertex 0.952752 1.15174 2.62025 + vertex 0.947588 1.15172 2.62019 + endloop + endfacet + facet normal 0.019373 -0.171374 0.985016 + outer loop + vertex 0.958246 1.14785 2.61945 + vertex 0.957782 1.15204 2.62019 + vertex 0.953274 1.14765 2.61952 + endloop + endfacet + facet normal -0.0098857 -0.176756 0.984205 + outer loop + vertex 0.947588 1.15172 2.62019 + vertex 0.952752 1.15174 2.62025 + vertex 0.951648 1.1554 2.62089 + endloop + endfacet + facet normal -0.0101855 -0.176435 0.98426 + outer loop + vertex 0.946466 1.15563 2.62088 + vertex 0.947588 1.15172 2.62019 + vertex 0.951648 1.1554 2.62089 + endloop + endfacet + facet normal 0.0329679 -0.151511 0.987906 + outer loop + vertex 0.960296 1.15943 2.62129 + vertex 0.955311 1.15914 2.62141 + vertex 0.956731 1.15562 2.62082 + endloop + endfacet + facet normal 0.0327558 -0.147686 0.988492 + outer loop + vertex 0.960296 1.15943 2.62129 + vertex 0.959064 1.16327 2.6219 + vertex 0.955311 1.15914 2.62141 + endloop + endfacet + facet normal -0.00969272 -0.165426 0.986175 + outer loop + vertex 0.951648 1.1554 2.62089 + vertex 0.950148 1.15912 2.6215 + vertex 0.946466 1.15563 2.62088 + endloop + endfacet + facet normal 0.0296269 -0.144904 0.989002 + outer loop + vertex 0.955311 1.15914 2.62141 + vertex 0.959064 1.16327 2.6219 + vertex 0.954022 1.16312 2.62203 + endloop + endfacet + facet normal 0.0296858 -0.147224 0.988658 + outer loop + vertex 0.959064 1.16327 2.6219 + vertex 0.958339 1.16782 2.6226 + vertex 0.954022 1.16312 2.62203 + endloop + endfacet + facet normal 0.034872 -0.146391 0.988612 + outer loop + vertex 0.959064 1.16327 2.6219 + vertex 0.963349 1.16792 2.62244 + vertex 0.958339 1.16782 2.6226 + endloop + endfacet + facet normal 0.0348967 -0.148047 0.988364 + outer loop + vertex 0.963349 1.16792 2.62244 + vertex 0.963244 1.17297 2.6232 + vertex 0.958339 1.16782 2.6226 + endloop + endfacet + facet normal 0.0339216 -0.147137 0.988534 + outer loop + vertex 0.958339 1.16782 2.6226 + vertex 0.963244 1.17297 2.6232 + vertex 0.958235 1.17294 2.62337 + endloop + endfacet + facet normal 0.0339222 -0.146175 0.988677 + outer loop + vertex 0.963244 1.17297 2.6232 + vertex 0.963499 1.17823 2.62397 + vertex 0.958235 1.17294 2.62337 + endloop + endfacet + facet normal 0.0411502 -0.146478 0.988358 + outer loop + vertex 0.963244 1.17297 2.6232 + vertex 0.968447 1.17819 2.62376 + vertex 0.963499 1.17823 2.62397 + endloop + endfacet + facet normal 0.0411983 -0.142965 0.98887 + outer loop + vertex 0.968447 1.17819 2.62376 + vertex 0.968708 1.18332 2.62449 + vertex 0.963499 1.17823 2.62397 + endloop + endfacet + facet normal 0.0420416 -0.143811 0.988712 + outer loop + vertex 0.963499 1.17823 2.62397 + vertex 0.968708 1.18332 2.62449 + vertex 0.963635 1.18321 2.62469 + endloop + endfacet + facet normal 0.0340125 -0.14364 0.989045 + outer loop + vertex 0.963499 1.17823 2.62397 + vertex 0.963635 1.18321 2.62469 + vertex 0.958455 1.17816 2.62413 + endloop + endfacet + facet normal 0.0420208 -0.142498 0.988903 + outer loop + vertex 0.968708 1.18332 2.62449 + vertex 0.968654 1.18827 2.6252 + vertex 0.963635 1.18321 2.62469 + endloop + endfacet + facet normal 0.0408688 -0.141377 0.989112 + outer loop + vertex 0.963635 1.18321 2.62469 + vertex 0.968654 1.18827 2.6252 + vertex 0.963 1.18736 2.62531 + endloop + endfacet + facet normal 0.034158 -0.14242 0.989217 + outer loop + vertex 0.963635 1.18321 2.62469 + vertex 0.963 1.18736 2.62531 + vertex 0.958478 1.18294 2.62483 + endloop + endfacet + facet normal 0.0493398 -0.142371 0.988583 + outer loop + vertex 0.968708 1.18332 2.62449 + vertex 0.973594 1.18795 2.62491 + vertex 0.968654 1.18827 2.6252 + endloop + endfacet + facet normal 0.0476826 -0.140653 0.98891 + outer loop + vertex 0.973573 1.18325 2.62424 + vertex 0.973594 1.18795 2.62491 + vertex 0.968708 1.18332 2.62449 + endloop + endfacet + facet normal 0.0521118 -0.14064 0.988688 + outer loop + vertex 0.973573 1.18325 2.62424 + vertex 0.978446 1.18813 2.62468 + vertex 0.973594 1.18795 2.62491 + endloop + endfacet + facet normal 0.0520724 -0.139329 0.988876 + outer loop + vertex 0.978446 1.18813 2.62468 + vertex 0.977858 1.19223 2.62529 + vertex 0.973594 1.18795 2.62491 + endloop + endfacet + facet normal 0.0559964 -0.143175 0.988112 + outer loop + vertex 0.973594 1.18795 2.62491 + vertex 0.977858 1.19223 2.62529 + vertex 0.973461 1.19179 2.62547 + endloop + endfacet + facet normal 0.0568856 -0.138615 0.988711 + outer loop + vertex 0.978446 1.18813 2.62468 + vertex 0.983391 1.19345 2.62514 + vertex 0.977858 1.19223 2.62529 + endloop + endfacet + facet normal 0.0562621 -0.135725 0.989148 + outer loop + vertex 0.977858 1.19223 2.62529 + vertex 0.983391 1.19345 2.62514 + vertex 0.981179 1.19632 2.62566 + endloop + endfacet + facet normal 0.0593541 -0.13819 0.988626 + outer loop + vertex 0.976612 1.19537 2.6258 + vertex 0.977858 1.19223 2.62529 + vertex 0.981179 1.19632 2.62566 + endloop + endfacet + facet normal 0.0567712 -0.125405 0.99048 + outer loop + vertex 0.981179 1.19632 2.62566 + vertex 0.979818 1.19938 2.62613 + vertex 0.976612 1.19537 2.6258 + endloop + endfacet + facet normal 0.0585714 -0.124603 0.990476 + outer loop + vertex 0.984362 1.20008 2.62595 + vertex 0.979818 1.19938 2.62613 + vertex 0.981179 1.19632 2.62566 + endloop + endfacet + facet normal 0.0540382 -0.13601 0.989233 + outer loop + vertex 0.98342 1.18823 2.62442 + vertex 0.983391 1.19345 2.62514 + vertex 0.978446 1.18813 2.62468 + endloop + endfacet + facet normal 0.0540822 -0.139639 0.988725 + outer loop + vertex 0.978389 1.18316 2.62398 + vertex 0.98342 1.18823 2.62442 + vertex 0.978446 1.18813 2.62468 + endloop + endfacet + facet normal 0.0552438 -0.140773 0.988499 + outer loop + vertex 0.983282 1.18305 2.62369 + vertex 0.98342 1.18823 2.62442 + vertex 0.978389 1.18316 2.62398 + endloop + endfacet + facet normal 0.0510779 -0.139627 0.988886 + outer loop + vertex 0.978389 1.18316 2.62398 + vertex 0.978446 1.18813 2.62468 + vertex 0.973573 1.18325 2.62424 + endloop + endfacet + facet normal 0.0510025 -0.14268 0.988454 + outer loop + vertex 0.973317 1.17808 2.62351 + vertex 0.978389 1.18316 2.62398 + vertex 0.973573 1.18325 2.62424 + endloop + endfacet + facet normal 0.046882 -0.142508 0.988683 + outer loop + vertex 0.973317 1.17808 2.62351 + vertex 0.973573 1.18325 2.62424 + vertex 0.968447 1.17819 2.62376 + endloop + endfacet + facet normal 0.0467792 -0.145985 0.98818 + outer loop + vertex 0.968202 1.17294 2.62299 + vertex 0.973317 1.17808 2.62351 + vertex 0.968447 1.17819 2.62376 + endloop + endfacet + facet normal 0.0477366 -0.146919 0.987996 + outer loop + vertex 0.973181 1.17291 2.62275 + vertex 0.973317 1.17808 2.62351 + vertex 0.968202 1.17294 2.62299 + endloop + endfacet + facet normal 0.0525379 -0.144185 0.988155 + outer loop + vertex 0.978212 1.17797 2.62323 + vertex 0.978389 1.18316 2.62398 + vertex 0.973317 1.17808 2.62351 + endloop + endfacet + facet normal 0.0476219 -0.143245 0.988541 + outer loop + vertex 0.968447 1.17819 2.62376 + vertex 0.973573 1.18325 2.62424 + vertex 0.968708 1.18332 2.62449 + endloop + endfacet + facet normal 0.0403869 -0.145733 0.988499 + outer loop + vertex 0.968202 1.17294 2.62299 + vertex 0.968447 1.17819 2.62376 + vertex 0.963244 1.17297 2.6232 + endloop + endfacet + facet normal 0.0403634 -0.147905 0.988178 + outer loop + vertex 0.963349 1.16792 2.62244 + vertex 0.968202 1.17294 2.62299 + vertex 0.963244 1.17297 2.6232 + endloop + endfacet + facet normal 0.0415776 -0.149053 0.987955 + outer loop + vertex 0.968352 1.16802 2.62224 + vertex 0.968202 1.17294 2.62299 + vertex 0.963349 1.16792 2.62244 + endloop + endfacet + facet normal 0.0372466 -0.148532 0.988206 + outer loop + vertex 0.964026 1.16349 2.62175 + vertex 0.963349 1.16792 2.62244 + vertex 0.959064 1.16327 2.6219 + endloop + endfacet + facet normal 0.0265159 -0.144375 0.989168 + outer loop + vertex 0.954022 1.16312 2.62203 + vertex 0.958339 1.16782 2.6226 + vertex 0.953317 1.16778 2.62273 + endloop + endfacet + facet normal 0.0265255 -0.147317 0.988734 + outer loop + vertex 0.958339 1.16782 2.6226 + vertex 0.958235 1.17294 2.62337 + vertex 0.953317 1.16778 2.62273 + endloop + endfacet + facet normal 0.0340329 -0.146283 0.988657 + outer loop + vertex 0.958235 1.17294 2.62337 + vertex 0.963499 1.17823 2.62397 + vertex 0.958455 1.17816 2.62413 + endloop + endfacet + facet normal 0.03423 -0.143858 0.989006 + outer loop + vertex 0.958455 1.17816 2.62413 + vertex 0.963635 1.18321 2.62469 + vertex 0.958478 1.18294 2.62483 + endloop + endfacet + facet normal 0.00972593 -0.145947 0.989245 + outer loop + vertex 0.948262 1.17296 2.62354 + vertex 0.953384 1.17807 2.62424 + vertex 0.948346 1.17807 2.62429 + endloop + endfacet + facet normal 0.00907913 -0.143784 0.989567 + outer loop + vertex 0.948478 1.16797 2.62281 + vertex 0.953213 1.17292 2.62349 + vertex 0.948262 1.17296 2.62354 + endloop + endfacet + facet normal -0.064363 -0.179739 0.981606 + outer loop + vertex 0.947138 1.12663 2.6157 + vertex 0.949564 1.13015 2.6165 + vertex 0.945103 1.12928 2.61605 + endloop + endfacet + facet normal -0.0603487 -0.188498 0.980218 + outer loop + vertex 0.955025 1.10406 2.61173 + vertex 0.949603 1.10506 2.61159 + vertex 0.951362 1.10053 2.61083 + endloop + endfacet + facet normal -0.266756 -0.237407 0.934066 + outer loop + vertex 0.947225 1.10157 2.61052 + vertex 0.942829 1.10173 2.60931 + vertex 0.947213 1.09763 2.60952 + endloop + endfacet + facet normal -0.247578 -0.216369 0.944399 + outer loop + vertex 0.947213 1.09763 2.60952 + vertex 0.942829 1.10173 2.60931 + vertex 0.943587 1.09767 2.60858 + endloop + endfacet + facet normal -0.245779 -0.253479 0.935597 + outer loop + vertex 0.943924 1.09402 2.60768 + vertex 0.947213 1.09763 2.60952 + vertex 0.943587 1.09767 2.60858 + endloop + endfacet + facet normal -0.239634 -0.250741 0.937926 + outer loop + vertex 0.952228 1.07676 2.60554 + vertex 0.947804 1.07674 2.60441 + vertex 0.952208 1.07279 2.60448 + endloop + endfacet + facet normal -0.0419713 -0.215331 0.975639 + outer loop + vertex 0.96003 1.07944 2.60671 + vertex 0.954612 1.08028 2.60666 + vertex 0.956351 1.07586 2.60576 + endloop + endfacet + facet normal -0.0417266 -0.213734 0.976 + outer loop + vertex 0.96003 1.07944 2.60671 + vertex 0.959121 1.08379 2.60763 + vertex 0.954612 1.08028 2.60666 + endloop + endfacet + facet normal -0.0361614 -0.220524 0.974711 + outer loop + vertex 0.954612 1.08028 2.60666 + vertex 0.959121 1.08379 2.60763 + vertex 0.955122 1.08473 2.60769 + endloop + endfacet + facet normal 0.00857811 -0.202562 0.979232 + outer loop + vertex 0.959121 1.08379 2.60763 + vertex 0.963496 1.08813 2.60848 + vertex 0.958723 1.08825 2.60855 + endloop + endfacet + facet normal 0.00862418 -0.200847 0.979585 + outer loop + vertex 0.963496 1.08813 2.60848 + vertex 0.963194 1.09267 2.60942 + vertex 0.958723 1.08825 2.60855 + endloop + endfacet + facet normal 0.0114875 -0.203623 0.978982 + outer loop + vertex 0.958723 1.08825 2.60855 + vertex 0.963194 1.09267 2.60942 + vertex 0.958296 1.09247 2.60944 + endloop + endfacet + facet normal 0.0115105 -0.204206 0.97886 + outer loop + vertex 0.963194 1.09267 2.60942 + vertex 0.962625 1.09667 2.61026 + vertex 0.958296 1.09247 2.60944 + endloop + endfacet + facet normal 0.0409753 -0.200032 0.978932 + outer loop + vertex 0.963194 1.09267 2.60942 + vertex 0.967737 1.09723 2.61016 + vertex 0.962625 1.09667 2.61026 + endloop + endfacet + facet normal 0.0368914 -0.196118 0.979886 + outer loop + vertex 0.968296 1.09301 2.60929 + vertex 0.967737 1.09723 2.61016 + vertex 0.963194 1.09267 2.60942 + endloop + endfacet + facet normal 0.037063 -0.198899 0.979319 + outer loop + vertex 0.963496 1.08813 2.60848 + vertex 0.968296 1.09301 2.60929 + vertex 0.963194 1.09267 2.60942 + endloop + endfacet + facet normal 0.033704 -0.195721 0.98008 + outer loop + vertex 0.968506 1.08818 2.60832 + vertex 0.968296 1.09301 2.60929 + vertex 0.963496 1.08813 2.60848 + endloop + endfacet + facet normal 0.0495319 -0.194927 0.979566 + outer loop + vertex 0.968506 1.08818 2.60832 + vertex 0.973394 1.0932 2.60907 + vertex 0.968296 1.09301 2.60929 + endloop + endfacet + facet normal 0.0493751 -0.189359 0.980666 + outer loop + vertex 0.973394 1.0932 2.60907 + vertex 0.973436 1.09828 2.61005 + vertex 0.968296 1.09301 2.60929 + endloop + endfacet + facet normal 0.0574951 -0.189341 0.980227 + outer loop + vertex 0.973394 1.0932 2.60907 + vertex 0.978397 1.09798 2.6097 + vertex 0.973436 1.09828 2.61005 + endloop + endfacet + facet normal 0.0570931 -0.188934 0.980329 + outer loop + vertex 0.978366 1.09318 2.60878 + vertex 0.978397 1.09798 2.6097 + vertex 0.973394 1.0932 2.60907 + endloop + endfacet + facet normal 0.0623201 -0.188908 0.980015 + outer loop + vertex 0.978366 1.09318 2.60878 + vertex 0.983335 1.09815 2.60942 + vertex 0.978397 1.09798 2.6097 + endloop + endfacet + facet normal 0.0621998 -0.183826 0.980989 + outer loop + vertex 0.983335 1.09815 2.60942 + vertex 0.98291 1.10232 2.61023 + vertex 0.978397 1.09798 2.6097 + endloop + endfacet + facet normal 0.0611668 -0.182784 0.981249 + outer loop + vertex 0.978397 1.09798 2.6097 + vertex 0.98291 1.10232 2.61023 + vertex 0.978453 1.10195 2.61044 + endloop + endfacet + facet normal 0.0627295 -0.189304 0.979913 + outer loop + vertex 0.98337 1.0932 2.60846 + vertex 0.983335 1.09815 2.60942 + vertex 0.978366 1.09318 2.60878 + endloop + endfacet + facet normal 0.0675791 -0.189212 0.979608 + outer loop + vertex 0.98337 1.0932 2.60846 + vertex 0.988377 1.09826 2.6091 + vertex 0.983335 1.09815 2.60942 + endloop + endfacet + facet normal 0.0675356 -0.18501 0.980413 + outer loop + vertex 0.988377 1.09826 2.6091 + vertex 0.988438 1.10334 2.61005 + vertex 0.983335 1.09815 2.60942 + endloop + endfacet + facet normal 0.0708109 -0.185006 0.980183 + outer loop + vertex 0.988377 1.09826 2.6091 + vertex 0.993535 1.10314 2.60965 + vertex 0.988438 1.10334 2.61005 + endloop + endfacet + facet normal 0.0715303 -0.185744 0.979991 + outer loop + vertex 0.99336 1.0982 2.60872 + vertex 0.993535 1.10314 2.60965 + vertex 0.988377 1.09826 2.6091 + endloop + endfacet + facet normal 0.0674072 -0.189047 0.979652 + outer loop + vertex 0.988434 1.09321 2.60812 + vertex 0.988377 1.09826 2.6091 + vertex 0.98337 1.0932 2.60846 + endloop + endfacet + facet normal 0.0626837 -0.194366 0.978924 + outer loop + vertex 0.978619 1.08821 2.60778 + vertex 0.98337 1.0932 2.60846 + vertex 0.978366 1.09318 2.60878 + endloop + endfacet + facet normal 0.0624489 -0.19415 0.978982 + outer loop + vertex 0.983841 1.08834 2.60747 + vertex 0.98337 1.0932 2.60846 + vertex 0.978619 1.08821 2.60778 + endloop + endfacet + facet normal 0.03821 -0.203203 0.978391 + outer loop + vertex 0.970198 1.07962 2.6065 + vertex 0.969119 1.08357 2.60737 + vertex 0.965173 1.07936 2.60665 + endloop + endfacet + facet normal 0.0412165 -0.206403 0.977599 + outer loop + vertex 0.966513 1.07573 2.60584 + vertex 0.967707 1.07216 2.60504 + vertex 0.971473 1.07631 2.60575 + endloop + endfacet + facet normal 0.0426993 -0.207691 0.977262 + outer loop + vertex 0.967707 1.07216 2.60504 + vertex 0.973458 1.07317 2.605 + vertex 0.971473 1.07631 2.60575 + endloop + endfacet + facet normal 0.0520466 -0.198901 0.978637 + outer loop + vertex 0.973412 1.06816 2.60398 + vertex 0.97848 1.07288 2.60467 + vertex 0.973458 1.07317 2.605 + endloop + endfacet + facet normal 0.0515055 -0.199034 0.978638 + outer loop + vertex 0.973496 1.06333 2.603 + vertex 0.978398 1.06816 2.60372 + vertex 0.973412 1.06816 2.60398 + endloop + endfacet + facet normal 0.0533436 -0.202521 0.977824 + outer loop + vertex 0.974004 1.05884 2.60204 + vertex 0.978581 1.06331 2.60271 + vertex 0.973496 1.06333 2.603 + endloop + endfacet + facet normal 0.0380106 -0.208459 0.977292 + outer loop + vertex 0.974562 1.05503 2.6012 + vertex 0.974004 1.05884 2.60204 + vertex 0.969866 1.05497 2.60138 + endloop + endfacet + facet normal 0.0380391 -0.217285 0.975367 + outer loop + vertex 0.974562 1.05503 2.6012 + vertex 0.969866 1.05497 2.60138 + vertex 0.971149 1.05147 2.60054 + endloop + endfacet + facet normal -0.0319152 -0.245699 0.968821 + outer loop + vertex 0.962151 1.04784 2.59956 + vertex 0.967547 1.04749 2.59965 + vertex 0.966241 1.05132 2.60058 + endloop + endfacet + facet normal -0.0309129 -0.229176 0.972894 + outer loop + vertex 0.96379 1.04344 2.59858 + vertex 0.967547 1.04749 2.59965 + vertex 0.962151 1.04784 2.59956 + endloop + endfacet + facet normal 0.0460584 -0.217053 0.975073 + outer loop + vertex 0.97361 1.04321 2.59859 + vertex 0.978325 1.04787 2.5994 + vertex 0.973271 1.04819 2.59971 + endloop + endfacet + facet normal 0.0457652 -0.213874 0.975789 + outer loop + vertex 0.974181 1.03862 2.59755 + vertex 0.978618 1.04322 2.59835 + vertex 0.97361 1.04321 2.59859 + endloop + endfacet + facet normal 0.0492474 -0.215724 0.975212 + outer loop + vertex 0.975149 1.03458 2.59661 + vertex 0.979228 1.0387 2.59732 + vertex 0.974181 1.03862 2.59755 + endloop + endfacet + facet normal 0.052563 -0.220509 0.973968 + outer loop + vertex 0.979825 1.03487 2.59642 + vertex 0.975149 1.03458 2.59661 + vertex 0.976396 1.03117 2.59577 + endloop + endfacet + facet normal 0.0568391 -0.228902 0.971789 + outer loop + vertex 0.98038 1.03213 2.59576 + vertex 0.976396 1.03117 2.59577 + vertex 0.978461 1.02809 2.59492 + endloop + endfacet + facet normal 0.0602455 -0.226332 0.972185 + outer loop + vertex 0.97866 1.0233 2.5938 + vertex 0.983418 1.02781 2.59455 + vertex 0.978461 1.02809 2.59492 + endloop + endfacet + facet normal 0.0565475 -0.225297 0.972648 + outer loop + vertex 0.979105 1.0188 2.59273 + vertex 0.983592 1.0233 2.59351 + vertex 0.97866 1.0233 2.5938 + endloop + endfacet + facet normal 0.054261 -0.226994 0.972383 + outer loop + vertex 0.980035 1.01466 2.59171 + vertex 0.984112 1.01887 2.59246 + vertex 0.979105 1.0188 2.59273 + endloop + endfacet + facet normal 0.0549993 -0.234097 0.970656 + outer loop + vertex 0.985001 1.01492 2.59149 + vertex 0.980035 1.01466 2.59171 + vertex 0.981265 1.01094 2.59074 + endloop + endfacet + facet normal -0.00826125 -0.25611 0.966612 + outer loop + vertex 0.972446 1.00697 2.58983 + vertex 0.977485 1.00693 2.58986 + vertex 0.976221 1.01074 2.59086 + endloop + endfacet + facet normal 0.0573455 -0.23946 0.969211 + outer loop + vertex 0.981265 1.01094 2.59074 + vertex 0.982531 1.00732 2.58977 + vertex 0.986145 1.01152 2.5906 + endloop + endfacet + facet normal 0.0639865 -0.24483 0.967452 + outer loop + vertex 0.982531 1.00732 2.58977 + vertex 0.988224 1.00838 2.58966 + vertex 0.986145 1.01152 2.5906 + endloop + endfacet + facet normal 0.0630098 -0.239404 0.968873 + outer loop + vertex 0.983435 1.00326 2.58871 + vertex 0.988224 1.00838 2.58966 + vertex 0.982531 1.00732 2.58977 + endloop + endfacet + facet normal 0.0635093 -0.239846 0.968731 + outer loop + vertex 0.988576 1.00346 2.58842 + vertex 0.988224 1.00838 2.58966 + vertex 0.983435 1.00326 2.58871 + endloop + endfacet + facet normal 0.063439 -0.236991 0.969438 + outer loop + vertex 0.98407 0.998888 2.5876 + vertex 0.988576 1.00346 2.58842 + vertex 0.983435 1.00326 2.58871 + endloop + endfacet + facet normal 0.0650887 -0.23853 0.968952 + outer loop + vertex 0.989107 0.998985 2.58729 + vertex 0.988576 1.00346 2.58842 + vertex 0.98407 0.998888 2.5876 + endloop + endfacet + facet normal 0.0650812 -0.23662 0.96942 + outer loop + vertex 0.984942 0.994873 2.58656 + vertex 0.989107 0.998985 2.58729 + vertex 0.98407 0.998888 2.5876 + endloop + endfacet + facet normal 0.0552154 -0.249545 0.966788 + outer loop + vertex 0.984172 0.9792 2.58254 + vertex 0.988596 0.983515 2.58341 + vertex 0.983677 0.983378 2.58365 + endloop + endfacet + facet normal 0.0552 -0.248516 0.967054 + outer loop + vertex 0.988596 0.983515 2.58341 + vertex 0.988248 0.988309 2.58466 + vertex 0.983677 0.983378 2.58365 + endloop + endfacet + facet normal 0.0538755 -0.247364 0.967424 + outer loop + vertex 0.983677 0.983378 2.58365 + vertex 0.988248 0.988309 2.58466 + vertex 0.982579 0.987259 2.5847 + endloop + endfacet + facet normal 0.0561468 -0.259777 0.964035 + outer loop + vertex 0.982579 0.987259 2.5847 + vertex 0.988248 0.988309 2.58466 + vertex 0.986112 0.991413 2.58562 + endloop + endfacet + facet normal 0.0444618 -0.250512 0.967092 + outer loop + vertex 0.981203 0.990938 2.58572 + vertex 0.982579 0.987259 2.5847 + vertex 0.986112 0.991413 2.58562 + endloop + endfacet + facet normal 0.0443333 -0.249103 0.967462 + outer loop + vertex 0.986112 0.991413 2.58562 + vertex 0.984942 0.994873 2.58656 + vertex 0.981203 0.990938 2.58572 + endloop + endfacet + facet normal 0.0668732 -0.241649 0.968057 + outer loop + vertex 0.989555 0.995151 2.58631 + vertex 0.984942 0.994873 2.58656 + vertex 0.986112 0.991413 2.58562 + endloop + endfacet + facet normal 0.0759913 -0.243538 0.96691 + outer loop + vertex 0.993724 0.98355 2.58301 + vertex 0.993477 0.988194 2.5842 + vertex 0.988596 0.983515 2.58341 + endloop + endfacet + facet normal 0.0902444 -0.243324 0.965738 + outer loop + vertex 0.999596 0.979852 2.58155 + vertex 0.999001 0.98374 2.58258 + vertex 0.994232 0.978825 2.58179 + endloop + endfacet + facet normal 0.0867289 -0.242786 0.966195 + outer loop + vertex 0.993724 0.98355 2.58301 + vertex 0.998624 0.988354 2.58378 + vertex 0.993477 0.988194 2.5842 + endloop + endfacet + facet normal 0.0940042 -0.245925 0.96472 + outer loop + vertex 1.0044 0.983664 2.58204 + vertex 1.00377 0.988427 2.58331 + vertex 0.999001 0.98374 2.58258 + endloop + endfacet + facet normal 0.0929518 -0.245207 0.965004 + outer loop + vertex 1.00377 0.988427 2.58331 + vertex 1.00849 0.993188 2.58407 + vertex 1.00348 0.992929 2.58449 + endloop + endfacet + facet normal 0.0895308 -0.24226 0.966072 + outer loop + vertex 1.00033 0.997127 2.58583 + vertex 0.999632 0.999769 2.58656 + vertex 0.996563 0.996036 2.5859 + endloop + endfacet + facet normal 0.0887609 -0.241666 0.966291 + outer loop + vertex 0.999632 0.999769 2.58656 + vertex 0.99432 0.998802 2.5868 + vertex 0.996563 0.996036 2.5859 + endloop + endfacet + facet normal 0.0876251 -0.242775 0.966117 + outer loop + vertex 1.00299 0.999562 2.5862 + vertex 0.999632 0.999769 2.58656 + vertex 1.00033 0.997127 2.58583 + endloop + endfacet + facet normal 0.0870366 -0.242163 0.966324 + outer loop + vertex 1.00343 0.99682 2.58547 + vertex 1.00299 0.999562 2.5862 + vertex 1.00033 0.997127 2.58583 + endloop + endfacet + facet normal 0.087738 -0.242043 0.966291 + outer loop + vertex 1.00299 0.999562 2.5862 + vertex 1.00343 0.99682 2.58547 + vertex 1.00675 1.0005 2.58609 + endloop + endfacet + facet normal 0.0872784 -0.240138 0.966807 + outer loop + vertex 1.00675 1.0005 2.58609 + vertex 1.00442 1.00353 2.58705 + vertex 1.00299 0.999562 2.5862 + endloop + endfacet + facet normal 0.0878392 -0.24032 0.966711 + outer loop + vertex 1.00299 0.999562 2.5862 + vertex 1.00442 1.00353 2.58705 + vertex 0.999632 0.999769 2.58656 + endloop + endfacet + facet normal 0.0885636 -0.241206 0.966424 + outer loop + vertex 1.00442 1.00353 2.58705 + vertex 0.999012 1.00367 2.58759 + vertex 0.999632 0.999769 2.58656 + endloop + endfacet + facet normal 0.0867346 -0.243348 0.966053 + outer loop + vertex 0.998624 0.988354 2.58378 + vertex 0.998526 0.993172 2.585 + vertex 0.993477 0.988194 2.5842 + endloop + endfacet + facet normal 0.0789878 -0.246496 0.96592 + outer loop + vertex 0.988596 0.983515 2.58341 + vertex 0.993477 0.988194 2.5842 + vertex 0.988248 0.988309 2.58466 + endloop + endfacet + facet normal 0.0712831 -0.249858 0.965655 + outer loop + vertex 0.990061 0.992397 2.58558 + vertex 0.986112 0.991413 2.58562 + vertex 0.988248 0.988309 2.58466 + endloop + endfacet + facet normal 0.0914422 -0.245245 0.965139 + outer loop + vertex 0.992815 0.994921 2.58598 + vertex 0.993338 0.992218 2.58524 + vertex 0.996563 0.996036 2.5859 + endloop + endfacet + facet normal 0.0699082 -0.244282 0.967181 + outer loop + vertex 0.990061 0.992397 2.58558 + vertex 0.989555 0.995151 2.58631 + vertex 0.986112 0.991413 2.58562 + endloop + endfacet + facet normal 0.0900935 -0.240629 0.966427 + outer loop + vertex 0.996563 0.996036 2.5859 + vertex 0.99432 0.998802 2.5868 + vertex 0.992815 0.994921 2.58598 + endloop + endfacet + facet normal 0.0667119 -0.238184 0.968926 + outer loop + vertex 0.989555 0.995151 2.58631 + vertex 0.989107 0.998985 2.58729 + vertex 0.984942 0.994873 2.58656 + endloop + endfacet + facet normal 0.078699 -0.236768 0.968374 + outer loop + vertex 0.989107 0.998985 2.58729 + vertex 0.993755 1.00352 2.58802 + vertex 0.988576 1.00346 2.58842 + endloop + endfacet + facet normal 0.0786811 -0.238981 0.967831 + outer loop + vertex 0.993755 1.00352 2.58802 + vertex 0.993469 1.00822 2.5892 + vertex 0.988576 1.00346 2.58842 + endloop + endfacet + facet normal 0.0886795 -0.241186 0.966419 + outer loop + vertex 0.999632 0.999769 2.58656 + vertex 0.999012 1.00367 2.58759 + vertex 0.99432 0.998802 2.5868 + endloop + endfacet + facet normal 0.0853403 -0.238466 0.967394 + outer loop + vertex 0.993755 1.00352 2.58802 + vertex 0.998607 1.00834 2.58878 + vertex 0.993469 1.00822 2.5892 + endloop + endfacet + facet normal 0.0886979 -0.238534 0.967075 + outer loop + vertex 1.00442 1.00353 2.58705 + vertex 1.00375 1.00837 2.58831 + vertex 0.999012 1.00367 2.58759 + endloop + endfacet + facet normal 0.0899174 -0.237727 0.967161 + outer loop + vertex 0.998607 1.00834 2.58878 + vertex 1.00343 1.01297 2.58947 + vertex 0.998494 1.01322 2.58999 + endloop + endfacet + facet normal 0.0927878 -0.234288 0.967729 + outer loop + vertex 1.00896 1.00861 2.58787 + vertex 1.00842 1.01322 2.58904 + vertex 1.00375 1.00837 2.58831 + endloop + endfacet + facet normal 0.0964697 -0.234828 0.967238 + outer loop + vertex 1.00343 1.01297 2.58947 + vertex 1.00779 1.01734 2.5901 + vertex 1.00337 1.0169 2.59043 + endloop + endfacet + facet normal 0.0996915 -0.230105 0.968046 + outer loop + vertex 1.01354 1.01346 2.58857 + vertex 1.01322 1.01845 2.58979 + vertex 1.00842 1.01322 2.58904 + endloop + endfacet + facet normal 0.0960555 -0.229734 0.968502 + outer loop + vertex 1.00337 1.0169 2.59043 + vertex 1.00779 1.01734 2.5901 + vertex 1.00666 1.02061 2.59098 + endloop + endfacet + facet normal 0.100676 -0.224163 0.969338 + outer loop + vertex 1.01445 1.02524 2.59125 + vertex 1.00989 1.02468 2.5916 + vertex 1.01122 1.0215 2.59072 + endloop + endfacet + facet normal 0.0945808 -0.223413 0.970124 + outer loop + vertex 1.00989 1.02468 2.5916 + vertex 1.00888 1.02863 2.5926 + vertex 1.00435 1.02356 2.59188 + endloop + endfacet + facet normal 0.0922039 -0.221388 0.970817 + outer loop + vertex 1.00435 1.02356 2.59188 + vertex 1.00888 1.02863 2.5926 + vertex 1.00368 1.02842 2.59305 + endloop + endfacet + facet normal 0.0948254 -0.228699 0.968868 + outer loop + vertex 1.00294 1.01962 2.59111 + vertex 1.00337 1.0169 2.59043 + vertex 1.00666 1.02061 2.59098 + endloop + endfacet + facet normal 0.0901199 -0.235052 0.967796 + outer loop + vertex 1.00337 1.0169 2.59043 + vertex 0.998494 1.01322 2.58999 + vertex 1.00343 1.01297 2.58947 + endloop + endfacet + facet normal 0.084665 -0.225696 0.970512 + outer loop + vertex 1.00029 1.01717 2.59078 + vertex 0.999588 1.01978 2.59145 + vertex 0.996529 1.01607 2.59086 + endloop + endfacet + facet normal 0.0839923 -0.225171 0.970692 + outer loop + vertex 0.999588 1.01978 2.59145 + vertex 0.994286 1.01882 2.59169 + vertex 0.996529 1.01607 2.59086 + endloop + endfacet + facet normal 0.0853385 -0.237924 0.967527 + outer loop + vertex 0.998607 1.00834 2.58878 + vertex 0.998494 1.01322 2.58999 + vertex 0.993469 1.00822 2.5892 + endloop + endfacet + facet normal 0.0782827 -0.238592 0.967959 + outer loop + vertex 0.988576 1.00346 2.58842 + vertex 0.993469 1.00822 2.5892 + vertex 0.988224 1.00838 2.58966 + endloop + endfacet + facet normal 0.0719101 -0.239803 0.968155 + outer loop + vertex 0.990063 1.0125 2.59055 + vertex 0.986145 1.01152 2.5906 + vertex 0.988224 1.00838 2.58966 + endloop + endfacet + facet normal 0.0860422 -0.23524 0.968121 + outer loop + vertex 0.992797 1.01499 2.59092 + vertex 0.993318 1.01229 2.59022 + vertex 0.996529 1.01607 2.59086 + endloop + endfacet + facet normal 0.0700374 -0.232222 0.970138 + outer loop + vertex 0.990063 1.0125 2.59055 + vertex 0.989567 1.01523 2.59124 + vertex 0.986145 1.01152 2.5906 + endloop + endfacet + facet normal 0.0833124 -0.225706 0.970626 + outer loop + vertex 0.996529 1.01607 2.59086 + vertex 0.994286 1.01882 2.59169 + vertex 0.992797 1.01499 2.59092 + endloop + endfacet + facet normal 0.0766658 -0.22081 0.972299 + outer loop + vertex 0.989109 1.019 2.59214 + vertex 0.993682 1.02351 2.59281 + vertex 0.988567 1.02341 2.59319 + endloop + endfacet + facet normal 0.0766677 -0.221514 0.972139 + outer loop + vertex 0.993682 1.02351 2.59281 + vertex 0.993265 1.02823 2.59391 + vertex 0.988567 1.02341 2.59319 + endloop + endfacet + facet normal 0.0834189 -0.221826 0.971511 + outer loop + vertex 0.999588 1.01978 2.59145 + vertex 0.998941 1.02366 2.59239 + vertex 0.994286 1.01882 2.59169 + endloop + endfacet + facet normal 0.081816 -0.220989 0.971838 + outer loop + vertex 0.993682 1.02351 2.59281 + vertex 0.998472 1.02841 2.59352 + vertex 0.993265 1.02823 2.59391 + endloop + endfacet + facet normal 0.0880709 -0.222016 0.971057 + outer loop + vertex 1.00435 1.02356 2.59188 + vertex 1.00368 1.02842 2.59305 + vertex 0.998941 1.02366 2.59239 + endloop + endfacet + facet normal 0.0922614 -0.224119 0.970185 + outer loop + vertex 1.00888 1.02863 2.5926 + vertex 1.00849 1.03335 2.59373 + vertex 1.00368 1.02842 2.59305 + endloop + endfacet + facet normal 0.0928619 -0.224647 0.970005 + outer loop + vertex 1.00849 1.03335 2.59373 + vertex 1.01343 1.03813 2.59437 + vertex 1.0084 1.03831 2.59489 + endloop + endfacet + facet normal 0.0867682 -0.222583 0.971045 + outer loop + vertex 0.998472 1.02841 2.59352 + vertex 1.0034 1.03326 2.59419 + vertex 0.998199 1.0335 2.59471 + endloop + endfacet + facet normal 0.0815147 -0.223381 0.971317 + outer loop + vertex 0.999995 1.03761 2.5955 + vertex 0.996164 1.03667 2.59561 + vertex 0.998199 1.0335 2.59471 + endloop + endfacet + facet normal 0.0898266 -0.223818 0.970483 + outer loop + vertex 1.00267 1.04004 2.59582 + vertex 1.00323 1.03737 2.59516 + vertex 1.00638 1.04113 2.59573 + endloop + endfacet + facet normal 0.0811245 -0.22175 0.971723 + outer loop + vertex 0.999995 1.03761 2.5955 + vertex 0.999466 1.04028 2.59616 + vertex 0.996164 1.03667 2.59561 + endloop + endfacet + facet normal 0.0886546 -0.219726 0.971525 + outer loop + vertex 1.00638 1.04113 2.59573 + vertex 1.00413 1.04382 2.59654 + vertex 1.00267 1.04004 2.59582 + endloop + endfacet + facet normal 0.0888168 -0.219595 0.97154 + outer loop + vertex 1.00944 1.04484 2.59629 + vertex 1.00413 1.04382 2.59654 + vertex 1.00638 1.04113 2.59573 + endloop + endfacet + facet normal 0.0797758 -0.219109 0.972434 + outer loop + vertex 0.999466 1.04028 2.59616 + vertex 0.998986 1.04398 2.59703 + vertex 0.99498 1.03995 2.59645 + endloop + endfacet + facet normal 0.084213 -0.2168 0.972577 + outer loop + vertex 0.998986 1.04398 2.59703 + vertex 1.00355 1.04845 2.59763 + vertex 0.998486 1.04841 2.59806 + endloop + endfacet + facet normal 0.0885789 -0.218284 0.971857 + outer loop + vertex 1.00944 1.04484 2.59629 + vertex 1.0088 1.04862 2.5972 + vertex 1.00413 1.04382 2.59654 + endloop + endfacet + facet normal 0.0904547 -0.217945 0.97176 + outer loop + vertex 1.01423 1.04863 2.59669 + vertex 1.0088 1.04862 2.5972 + vertex 1.00944 1.04484 2.59629 + endloop + endfacet + facet normal 0.086113 -0.214029 0.973024 + outer loop + vertex 1.00355 1.04845 2.59763 + vertex 1.00839 1.0533 2.59827 + vertex 1.0033 1.0533 2.59872 + endloop + endfacet + facet normal 0.0904721 -0.217033 0.971963 + outer loop + vertex 1.01423 1.04863 2.59669 + vertex 1.0136 1.05335 2.59781 + vertex 1.0088 1.04862 2.5972 + endloop + endfacet + facet normal 0.0866969 -0.2103 0.973785 + outer loop + vertex 1.00839 1.0533 2.59827 + vertex 1.01336 1.05825 2.59889 + vertex 1.0083 1.05819 2.59933 + endloop + endfacet + facet normal 0.0867196 -0.207516 0.97438 + outer loop + vertex 1.01336 1.05825 2.59889 + vertex 1.01333 1.06329 2.59997 + vertex 1.0083 1.05819 2.59933 + endloop + endfacet + facet normal 0.0848982 -0.205782 0.974908 + outer loop + vertex 1.0083 1.05819 2.59933 + vertex 1.01333 1.06329 2.59997 + vertex 1.00821 1.06234 2.60022 + endloop + endfacet + facet normal 0.0939371 -0.210003 0.973178 + outer loop + vertex 1.01893 1.05356 2.59734 + vertex 1.01851 1.05827 2.59839 + vertex 1.0136 1.05335 2.59781 + endloop + endfacet + facet normal 0.0956957 -0.207288 0.973588 + outer loop + vertex 1.01336 1.05825 2.59889 + vertex 1.01841 1.06316 2.59945 + vertex 1.01333 1.06329 2.59997 + endloop + endfacet + facet normal 0.0954935 -0.21168 0.972663 + outer loop + vertex 1.01832 1.06726 2.60035 + vertex 1.01333 1.06329 2.59997 + vertex 1.01841 1.06316 2.59945 + endloop + endfacet + facet normal 0.113032 -0.196757 0.973915 + outer loop + vertex 1.02371 1.05835 2.59781 + vertex 1.02352 1.06332 2.59883 + vertex 1.01851 1.05827 2.59839 + endloop + endfacet + facet normal 0.129163 -0.2101 0.96911 + outer loop + vertex 1.01841 1.06316 2.59945 + vertex 1.02351 1.06857 2.59994 + vertex 1.01832 1.06726 2.60035 + endloop + endfacet + facet normal 0.159217 -0.176344 0.971367 + outer loop + vertex 1.02856 1.06332 2.59801 + vertex 1.02856 1.06846 2.59894 + vertex 1.02352 1.06332 2.59883 + endloop + endfacet + facet normal 0.133458 -0.228696 0.964307 + outer loop + vertex 1.01832 1.06726 2.60035 + vertex 1.02351 1.06857 2.59994 + vertex 1.02139 1.07121 2.60086 + endloop + endfacet + facet normal 0.107616 -0.20953 0.971862 + outer loop + vertex 1.01774 1.06987 2.60097 + vertex 1.01832 1.06726 2.60035 + vertex 1.02139 1.07121 2.60086 + endloop + endfacet + facet normal 0.0945012 -0.212608 0.972557 + outer loop + vertex 1.01832 1.06726 2.60035 + vertex 1.01774 1.06987 2.60097 + vertex 1.0151 1.06731 2.60067 + endloop + endfacet + facet normal 0.0945746 -0.210559 0.972996 + outer loop + vertex 1.0151 1.06731 2.60067 + vertex 1.01333 1.06329 2.59997 + vertex 1.01832 1.06726 2.60035 + endloop + endfacet + facet normal 0.0836737 -0.20611 0.974945 + outer loop + vertex 1.0151 1.06731 2.60067 + vertex 1.01135 1.06613 2.60074 + vertex 1.01333 1.06329 2.59997 + endloop + endfacet + facet normal 0.0836802 -0.206131 0.97494 + outer loop + vertex 1.0151 1.06731 2.60067 + vertex 1.01439 1.06987 2.60127 + vertex 1.01135 1.06613 2.60074 + endloop + endfacet + facet normal 0.0870382 -0.205189 0.974845 + outer loop + vertex 1.01774 1.06987 2.60097 + vertex 1.01439 1.06987 2.60127 + vertex 1.0151 1.06731 2.60067 + endloop + endfacet + facet normal 0.0872456 -0.193683 0.977177 + outer loop + vertex 1.01774 1.06987 2.60097 + vertex 1.0191 1.07374 2.60162 + vertex 1.01439 1.06987 2.60127 + endloop + endfacet + facet normal 0.096044 -0.204113 0.974224 + outer loop + vertex 1.0191 1.07374 2.60162 + vertex 1.0138 1.07363 2.60212 + vertex 1.01439 1.06987 2.60127 + endloop + endfacet + facet normal 0.103874 -0.199069 0.974465 + outer loop + vertex 1.02139 1.07121 2.60086 + vertex 1.0191 1.07374 2.60162 + vertex 1.01774 1.06987 2.60097 + endloop + endfacet + facet normal 0.0960209 -0.190851 0.976911 + outer loop + vertex 1.0191 1.07374 2.60162 + vertex 1.01858 1.07837 2.60257 + vertex 1.0138 1.07363 2.60212 + endloop + endfacet + facet normal 0.0849758 -0.206013 0.974853 + outer loop + vertex 1.01439 1.06987 2.60127 + vertex 1.0138 1.07363 2.60212 + vertex 1.00912 1.06879 2.6015 + endloop + endfacet + facet normal 0.0852353 -0.207339 0.974549 + outer loop + vertex 1.01439 1.06987 2.60127 + vertex 1.00912 1.06879 2.6015 + vertex 1.01135 1.06613 2.60074 + endloop + endfacet + facet normal 0.0848195 -0.205329 0.975011 + outer loop + vertex 1.00821 1.06234 2.60022 + vertex 1.01333 1.06329 2.59997 + vertex 1.01135 1.06613 2.60074 + endloop + endfacet + facet normal 0.0863113 -0.205729 0.974795 + outer loop + vertex 1.00821 1.06234 2.60022 + vertex 1.00321 1.05842 2.59983 + vertex 1.0083 1.05819 2.59933 + endloop + endfacet + facet normal 0.0874211 -0.205275 0.974792 + outer loop + vertex 1.00767 1.06502 2.60082 + vertex 1.00446 1.06518 2.60115 + vertex 1.00502 1.06255 2.60054 + endloop + endfacet + facet normal 0.0864122 -0.205928 0.974744 + outer loop + vertex 1.00446 1.06518 2.60115 + vertex 1.0039 1.06883 2.60197 + vertex 0.999849 1.06463 2.60144 + endloop + endfacet + facet normal 0.0830853 -0.202839 0.975681 + outer loop + vertex 0.999849 1.06463 2.60144 + vertex 1.0039 1.06883 2.60197 + vertex 0.998774 1.06852 2.60234 + endloop + endfacet + facet normal 0.0864966 -0.207863 0.974326 + outer loop + vertex 0.997768 1.05737 2.60009 + vertex 1.00321 1.05842 2.59983 + vertex 1.00122 1.0615 2.60067 + endloop + endfacet + facet normal 0.081135 -0.213141 0.973647 + outer loop + vertex 0.998265 1.05317 2.59913 + vertex 0.997768 1.05737 2.60009 + vertex 0.993343 1.05299 2.5995 + endloop + endfacet + facet normal 0.0733738 -0.215725 0.973693 + outer loop + vertex 0.988497 1.04829 2.59883 + vertex 0.993343 1.05299 2.5995 + vertex 0.988383 1.05332 2.59995 + endloop + endfacet + facet normal 0.0682216 -0.212443 0.974789 + outer loop + vertex 0.990274 1.05736 2.6007 + vertex 0.986392 1.05643 2.60076 + vertex 0.988383 1.05332 2.59995 + endloop + endfacet + facet normal 0.0806855 -0.207849 0.974828 + outer loop + vertex 0.992941 1.05973 2.601 + vertex 0.993356 1.05699 2.60038 + vertex 0.996647 1.06064 2.60089 + endloop + endfacet + facet normal 0.0665238 -0.2053 0.976436 + outer loop + vertex 0.990274 1.05736 2.6007 + vertex 0.989684 1.06004 2.6013 + vertex 0.986392 1.05643 2.60076 + endloop + endfacet + facet normal 0.07916 -0.201487 0.976287 + outer loop + vertex 0.996647 1.06064 2.60089 + vertex 0.994319 1.06357 2.60168 + vertex 0.992941 1.05973 2.601 + endloop + endfacet + facet normal 0.0670862 -0.202615 0.976958 + outer loop + vertex 0.989684 1.06004 2.6013 + vertex 0.989051 1.06378 2.60212 + vertex 0.984963 1.05958 2.60153 + endloop + endfacet + facet normal 0.0733877 -0.202071 0.976617 + outer loop + vertex 0.989051 1.06378 2.60212 + vertex 0.993615 1.06834 2.60272 + vertex 0.98853 1.06833 2.6031 + endloop + endfacet + facet normal 0.0813801 -0.20332 0.975724 + outer loop + vertex 0.999849 1.06463 2.60144 + vertex 0.998774 1.06852 2.60234 + vertex 0.994319 1.06357 2.60168 + endloop + endfacet + facet normal 0.078079 -0.202066 0.976255 + outer loop + vertex 0.993615 1.06834 2.60272 + vertex 0.998374 1.07324 2.60335 + vertex 0.993433 1.07322 2.60374 + endloop + endfacet + facet normal 0.0832121 -0.205634 0.975085 + outer loop + vertex 1.0039 1.06883 2.60197 + vertex 1.00339 1.07329 2.60295 + vertex 0.998774 1.06852 2.60234 + endloop + endfacet + facet normal 0.0790649 -0.201244 0.976345 + outer loop + vertex 0.998374 1.07324 2.60335 + vertex 1.0033 1.07821 2.60398 + vertex 0.998336 1.0781 2.60436 + endloop + endfacet + facet normal 0.0790345 -0.196923 0.977228 + outer loop + vertex 1.0033 1.07821 2.60398 + vertex 1.0033 1.08328 2.605 + vertex 0.998336 1.0781 2.60436 + endloop + endfacet + facet normal 0.0823945 -0.204774 0.975335 + outer loop + vertex 1.00853 1.07338 2.60254 + vertex 1.0083 1.07819 2.60356 + vertex 1.00339 1.07329 2.60295 + endloop + endfacet + facet normal 0.0785814 -0.19693 0.977263 + outer loop + vertex 1.0033 1.07821 2.60398 + vertex 1.00837 1.0831 2.60456 + vertex 1.0033 1.08328 2.605 + endloop + endfacet + facet normal 0.0885951 -0.19639 0.976515 + outer loop + vertex 1.01343 1.07825 2.60311 + vertex 1.01344 1.08323 2.60411 + vertex 1.0083 1.07819 2.60356 + endloop + endfacet + facet normal 0.089623 -0.193376 0.977023 + outer loop + vertex 1.00837 1.0831 2.60456 + vertex 1.01361 1.08836 2.60512 + vertex 1.00833 1.08717 2.60537 + endloop + endfacet + facet normal 0.0915258 -0.20216 0.975066 + outer loop + vertex 1.00833 1.08717 2.60537 + vertex 1.01361 1.08836 2.60512 + vertex 1.0115 1.09099 2.60586 + endloop + endfacet + facet normal 0.117475 -0.181559 0.976338 + outer loop + vertex 1.01849 1.08324 2.60351 + vertex 1.01871 1.08831 2.60442 + vertex 1.01344 1.08323 2.60411 + endloop + endfacet + facet normal 0.0962772 -0.198432 0.975375 + outer loop + vertex 1.01538 1.09249 2.60578 + vertex 1.0115 1.09099 2.60586 + vertex 1.01361 1.08836 2.60512 + endloop + endfacet + facet normal 0.0923496 -0.188129 0.977793 + outer loop + vertex 1.01538 1.09249 2.60578 + vertex 1.01444 1.09485 2.60632 + vertex 1.0115 1.09099 2.60586 + endloop + endfacet + facet normal 0.0860717 -0.183527 0.979239 + outer loop + vertex 1.01444 1.09485 2.60632 + vertex 1.00921 1.09361 2.60655 + vertex 1.0115 1.09099 2.60586 + endloop + endfacet + facet normal 0.0836068 -0.17271 0.981418 + outer loop + vertex 1.01444 1.09485 2.60632 + vertex 1.0138 1.09856 2.60703 + vertex 1.00921 1.09361 2.60655 + endloop + endfacet + facet normal 0.0973799 -0.185134 0.977877 + outer loop + vertex 1.00921 1.09361 2.60655 + vertex 1.0138 1.09856 2.60703 + vertex 1.00863 1.09829 2.6075 + endloop + endfacet + facet normal 0.0968092 -0.169342 0.980791 + outer loop + vertex 1.0138 1.09856 2.60703 + vertex 1.01351 1.10324 2.60787 + vertex 1.00863 1.09829 2.6075 + endloop + endfacet + facet normal 0.0819641 -0.187228 0.978891 + outer loop + vertex 1.00921 1.09361 2.60655 + vertex 1.00863 1.09829 2.6075 + vertex 1.00396 1.09367 2.607 + endloop + endfacet + facet normal 0.0782507 -0.190204 0.978621 + outer loop + vertex 1.0115 1.09099 2.60586 + vertex 1.00921 1.09361 2.60655 + vertex 1.00776 1.08977 2.60592 + endloop + endfacet + facet normal 0.0788389 -0.192035 0.978216 + outer loop + vertex 1.00776 1.08977 2.60592 + vertex 1.00833 1.08717 2.60537 + vertex 1.0115 1.09099 2.60586 + endloop + endfacet + facet normal 0.0787553 -0.193675 0.9779 + outer loop + vertex 1.00833 1.08717 2.60537 + vertex 1.0033 1.08328 2.605 + vertex 1.00837 1.0831 2.60456 + endloop + endfacet + facet normal 0.0808981 -0.193324 0.977794 + outer loop + vertex 1.0051 1.08732 2.60565 + vertex 1.00453 1.08995 2.60622 + vertex 1.00132 1.0863 2.60576 + endloop + endfacet + facet normal 0.0809915 -0.198733 0.976701 + outer loop + vertex 0.998336 1.0781 2.60436 + vertex 1.0033 1.08328 2.605 + vertex 0.997919 1.08224 2.60524 + endloop + endfacet + facet normal 0.0792842 -0.196546 0.977284 + outer loop + vertex 0.993557 1.08182 2.6055 + vertex 0.997919 1.08224 2.60524 + vertex 0.996764 1.08543 2.60597 + endloop + endfacet + facet normal 0.0815643 -0.193889 0.977627 + outer loop + vertex 1.00453 1.08995 2.60622 + vertex 0.999897 1.08942 2.6065 + vertex 1.00132 1.0863 2.60576 + endloop + endfacet + facet normal 0.078946 -0.193208 0.977977 + outer loop + vertex 0.999897 1.08942 2.6065 + vertex 0.998763 1.09336 2.60737 + vertex 0.994354 1.08834 2.60673 + endloop + endfacet + facet normal 0.0759425 -0.190663 0.978714 + outer loop + vertex 0.994354 1.08834 2.60673 + vertex 0.998763 1.09336 2.60737 + vertex 0.993553 1.0932 2.60774 + endloop + endfacet + facet normal 0.0627534 -0.197971 0.978197 + outer loop + vertex 0.983477 1.07309 2.60442 + vertex 0.988613 1.07819 2.60512 + vertex 0.983098 1.0772 2.60528 + endloop + endfacet + facet normal 0.0576499 -0.198172 0.97847 + outer loop + vertex 0.978579 1.07682 2.60546 + vertex 0.983098 1.0772 2.60528 + vertex 0.981915 1.0804 2.60599 + endloop + endfacet + facet normal 0.0641848 -0.195155 0.97867 + outer loop + vertex 0.989805 1.08475 2.60636 + vertex 0.985077 1.08432 2.60659 + vertex 0.986615 1.08118 2.60586 + endloop + endfacet + facet normal 0.058524 -0.199184 0.978213 + outer loop + vertex 0.981915 1.0804 2.60599 + vertex 0.979452 1.08336 2.60674 + vertex 0.978138 1.07952 2.60604 + endloop + endfacet + facet normal 0.0624985 -0.198031 0.978201 + outer loop + vertex 0.979452 1.08336 2.60674 + vertex 0.983841 1.08834 2.60747 + vertex 0.978619 1.08821 2.60778 + endloop + endfacet + facet normal 0.0640052 -0.192966 0.979116 + outer loop + vertex 0.989805 1.08475 2.60636 + vertex 0.989048 1.08855 2.60716 + vertex 0.985077 1.08432 2.60659 + endloop + endfacet + facet normal 0.0673605 -0.193628 0.97876 + outer loop + vertex 0.983841 1.08834 2.60747 + vertex 0.988434 1.09321 2.60812 + vertex 0.98337 1.0932 2.60846 + endloop + endfacet + facet normal 0.0714837 -0.191438 0.978898 + outer loop + vertex 0.994354 1.08834 2.60673 + vertex 0.993553 1.0932 2.60774 + vertex 0.989048 1.08855 2.60716 + endloop + endfacet + facet normal 0.0714463 -0.18895 0.979384 + outer loop + vertex 0.988434 1.09321 2.60812 + vertex 0.99336 1.0982 2.60872 + vertex 0.988377 1.09826 2.6091 + endloop + endfacet + facet normal 0.0759368 -0.190348 0.978775 + outer loop + vertex 0.998763 1.09336 2.60737 + vertex 0.998356 1.09817 2.60833 + vertex 0.993553 1.0932 2.60774 + endloop + endfacet + facet normal 0.0733411 -0.185782 0.97985 + outer loop + vertex 0.99336 1.0982 2.60872 + vertex 0.998468 1.10318 2.60928 + vertex 0.993535 1.10314 2.60965 + endloop + endfacet + facet normal 0.0733527 -0.183643 0.980252 + outer loop + vertex 0.998468 1.10318 2.60928 + vertex 0.998676 1.10811 2.61019 + vertex 0.993535 1.10314 2.60965 + endloop + endfacet + facet normal 0.0733918 -0.183682 0.980242 + outer loop + vertex 0.993535 1.10314 2.60965 + vertex 0.998676 1.10811 2.61019 + vertex 0.993555 1.10716 2.6104 + endloop + endfacet + facet normal 0.0731708 -0.182443 0.98049 + outer loop + vertex 0.993555 1.10716 2.6104 + vertex 0.998676 1.10811 2.61019 + vertex 0.996717 1.11085 2.61085 + endloop + endfacet + facet normal 0.0729855 -0.182573 0.98048 + outer loop + vertex 1.0005 1.112 2.61078 + vertex 0.996717 1.11085 2.61085 + vertex 0.998676 1.10811 2.61019 + endloop + endfacet + facet normal 0.0730231 -0.18259 0.980474 + outer loop + vertex 1.0005 1.112 2.61078 + vertex 0.998676 1.10811 2.61019 + vertex 1.00357 1.1118 2.61051 + endloop + endfacet + facet normal 0.0728837 -0.184266 0.98017 + outer loop + vertex 1.00357 1.1118 2.61051 + vertex 1.00312 1.11446 2.61105 + vertex 1.0005 1.112 2.61078 + endloop + endfacet + facet normal 0.0729196 -0.184303 0.980161 + outer loop + vertex 1.00312 1.11446 2.61105 + vertex 0.999717 1.11454 2.61132 + vertex 1.0005 1.112 2.61078 + endloop + endfacet + facet normal 0.0731709 -0.177786 0.981345 + outer loop + vertex 1.00312 1.11446 2.61105 + vertex 1.00444 1.11837 2.61166 + vertex 0.999717 1.11454 2.61132 + endloop + endfacet + facet normal 0.0775169 -0.183032 0.980046 + outer loop + vertex 1.00444 1.11837 2.61166 + vertex 0.998935 1.11835 2.61209 + vertex 0.999717 1.11454 2.61132 + endloop + endfacet + facet normal 0.0774684 -0.183459 0.97997 + outer loop + vertex 1.00312 1.11446 2.61105 + vertex 1.00357 1.1118 2.61051 + vertex 1.00678 1.1155 2.61095 + endloop + endfacet + facet normal 0.074524 -0.184538 0.979996 + outer loop + vertex 1.00357 1.1118 2.61051 + vertex 0.998676 1.10811 2.61019 + vertex 1.00349 1.10788 2.60978 + endloop + endfacet + facet normal 0.0734563 -0.184136 0.980152 + outer loop + vertex 1.0005 1.112 2.61078 + vertex 0.999717 1.11454 2.61132 + vertex 0.996717 1.11085 2.61085 + endloop + endfacet + facet normal 0.0720031 -0.182996 0.980473 + outer loop + vertex 0.999717 1.11454 2.61132 + vertex 0.994322 1.11348 2.61151 + vertex 0.996717 1.11085 2.61085 + endloop + endfacet + facet normal 0.0784746 -0.188527 0.978928 + outer loop + vertex 1.00344 1.0982 2.60793 + vertex 1.00338 1.10314 2.60889 + vertex 0.998356 1.09817 2.60833 + endloop + endfacet + facet normal 0.074578 -0.183676 0.980154 + outer loop + vertex 0.998468 1.10318 2.60928 + vertex 1.00349 1.10788 2.60978 + vertex 0.998676 1.10811 2.61019 + endloop + endfacet + facet normal 0.0893422 -0.184602 0.978744 + outer loop + vertex 1.00842 1.10319 2.60844 + vertex 1.00839 1.10814 2.60938 + vertex 1.00338 1.10314 2.60889 + endloop + endfacet + facet normal 0.0849109 -0.184578 0.979143 + outer loop + vertex 1.00349 1.10788 2.60978 + vertex 1.00791 1.11232 2.61024 + vertex 1.00357 1.1118 2.61051 + endloop + endfacet + facet normal 0.125845 -0.180445 0.975501 + outer loop + vertex 1.01348 1.10835 2.60876 + vertex 1.01334 1.11373 2.60977 + vertex 1.00839 1.10814 2.60938 + endloop + endfacet + facet normal 0.0855149 -0.190201 0.978014 + outer loop + vertex 1.00357 1.1118 2.61051 + vertex 1.00791 1.11232 2.61024 + vertex 1.00678 1.1155 2.61095 + endloop + endfacet + facet normal 0.0761453 -0.178728 0.980948 + outer loop + vertex 1.00678 1.1155 2.61095 + vertex 1.00444 1.11837 2.61166 + vertex 1.00312 1.11446 2.61105 + endloop + endfacet + facet normal 0.130674 -0.147859 0.980338 + outer loop + vertex 1.00979 1.1195 2.61138 + vertex 1.0138 1.12366 2.61147 + vertex 1.0089 1.12348 2.61209 + endloop + endfacet + facet normal 0.130435 -0.135215 0.982193 + outer loop + vertex 1.0138 1.12366 2.61147 + vertex 1.01315 1.12821 2.61218 + vertex 1.0089 1.12348 2.61209 + endloop + endfacet + facet normal 0.112424 -0.130337 0.985075 + outer loop + vertex 1.01325 1.11982 2.61102 + vertex 1.0138 1.12366 2.61147 + vertex 1.00979 1.1195 2.61138 + endloop + endfacet + facet normal 0.115382 -0.169099 0.978822 + outer loop + vertex 1.01325 1.11982 2.61102 + vertex 1.00979 1.1195 2.61138 + vertex 1.01107 1.11649 2.6107 + endloop + endfacet + facet normal 0.160069 -0.19708 0.967232 + outer loop + vertex 1.01464 1.11811 2.61044 + vertex 1.01325 1.11982 2.61102 + vertex 1.01107 1.11649 2.6107 + endloop + endfacet + facet normal 0.200487 -0.163649 0.965932 + outer loop + vertex 1.0164 1.12163 2.61068 + vertex 1.01325 1.11982 2.61102 + vertex 1.01464 1.11811 2.61044 + endloop + endfacet + facet normal 0.148529 -0.151364 0.977255 + outer loop + vertex 1.0089 1.12348 2.61209 + vertex 1.01315 1.12821 2.61218 + vertex 1.00843 1.12822 2.6129 + endloop + endfacet + facet normal 0.0775943 -0.175399 0.981435 + outer loop + vertex 1.00444 1.11837 2.61166 + vertex 1.00368 1.12319 2.61258 + vertex 0.998935 1.11835 2.61209 + endloop + endfacet + facet normal 0.0722233 -0.184159 0.980239 + outer loop + vertex 0.999717 1.11454 2.61132 + vertex 0.998935 1.11835 2.61209 + vertex 0.994322 1.11348 2.61151 + endloop + endfacet + facet normal 0.0728097 -0.18228 0.980547 + outer loop + vertex 0.996717 1.11085 2.61085 + vertex 0.994322 1.11348 2.61151 + vertex 0.992976 1.10972 2.61092 + endloop + endfacet + facet normal 0.0727562 -0.1821 0.980585 + outer loop + vertex 0.992976 1.10972 2.61092 + vertex 0.993555 1.10716 2.6104 + vertex 0.996717 1.11085 2.61085 + endloop + endfacet + facet normal 0.0708795 -0.183703 0.980423 + outer loop + vertex 0.993555 1.10716 2.6104 + vertex 0.988438 1.10334 2.61005 + vertex 0.993535 1.10314 2.60965 + endloop + endfacet + facet normal 0.0654584 -0.179885 0.981507 + outer loop + vertex 0.990296 1.10732 2.61066 + vertex 0.989647 1.1099 2.61118 + vertex 0.986398 1.10632 2.61074 + endloop + endfacet + facet normal 0.0658674 -0.18342 0.980826 + outer loop + vertex 0.983335 1.09815 2.60942 + vertex 0.988438 1.10334 2.61005 + vertex 0.98291 1.10232 2.61023 + endloop + endfacet + facet normal 0.0608439 -0.178433 0.982069 + outer loop + vertex 0.978453 1.10195 2.61044 + vertex 0.98291 1.10232 2.61023 + vertex 0.981733 1.10551 2.61088 + endloop + endfacet + facet normal 0.0629074 -0.177639 0.982083 + outer loop + vertex 0.989647 1.1099 2.61118 + vertex 0.984916 1.1094 2.61139 + vertex 0.986398 1.10632 2.61074 + endloop + endfacet + facet normal 0.060343 -0.179572 0.981892 + outer loop + vertex 0.979317 1.1084 2.61155 + vertex 0.983738 1.11332 2.61218 + vertex 0.978504 1.11316 2.61247 + endloop + endfacet + facet normal 0.0631441 -0.180106 0.981618 + outer loop + vertex 0.989647 1.1099 2.61118 + vertex 0.988969 1.11358 2.6119 + vertex 0.984916 1.1094 2.61139 + endloop + endfacet + facet normal 0.0638182 -0.179795 0.981632 + outer loop + vertex 0.988969 1.11358 2.6119 + vertex 0.99356 1.11815 2.61244 + vertex 0.988356 1.11812 2.61277 + endloop + endfacet + facet normal 0.0638293 -0.178252 0.981912 + outer loop + vertex 0.99356 1.11815 2.61244 + vertex 0.993251 1.12309 2.61335 + vertex 0.988356 1.11812 2.61277 + endloop + endfacet + facet normal 0.0614913 -0.170133 0.983501 + outer loop + vertex 0.988275 1.12318 2.61368 + vertex 0.99333 1.12823 2.61424 + vertex 0.988381 1.12816 2.61454 + endloop + endfacet + facet normal 0.0614614 -0.162603 0.984776 + outer loop + vertex 0.99333 1.12823 2.61424 + vertex 0.993344 1.13334 2.61508 + vertex 0.988381 1.12816 2.61454 + endloop + endfacet + facet normal 0.0674525 -0.173004 0.982609 + outer loop + vertex 0.998395 1.12309 2.613 + vertex 0.998318 1.12815 2.6139 + vertex 0.993251 1.12309 2.61335 + endloop + endfacet + facet normal 0.0621404 -0.162598 0.984734 + outer loop + vertex 0.99333 1.12823 2.61424 + vertex 0.998434 1.13314 2.61473 + vertex 0.993344 1.13334 2.61508 + endloop + endfacet + facet normal 0.0832661 -0.163593 0.983008 + outer loop + vertex 1.00339 1.12816 2.61347 + vertex 1.00348 1.13326 2.61431 + vertex 0.998318 1.12815 2.6139 + endloop + endfacet + facet normal 0.0823069 -0.162819 0.983217 + outer loop + vertex 0.998434 1.13314 2.61473 + vertex 1.0036 1.1384 2.61516 + vertex 0.998344 1.13718 2.6154 + endloop + endfacet + facet normal 0.125586 -0.149148 0.980807 + outer loop + vertex 1.00844 1.13325 2.61367 + vertex 1.0087 1.13837 2.61442 + vertex 1.00348 1.13326 2.61431 + endloop + endfacet + facet normal 0.0950327 -0.177767 0.979473 + outer loop + vertex 1.00523 1.14247 2.61574 + vertex 1.00144 1.14096 2.61584 + vertex 1.0036 1.1384 2.61516 + endloop + endfacet + facet normal 0.0914157 -0.168564 0.981442 + outer loop + vertex 1.00523 1.14247 2.61574 + vertex 1.00418 1.14471 2.61623 + vertex 1.00144 1.14096 2.61584 + endloop + endfacet + facet normal 0.0717749 -0.142398 0.987204 + outer loop + vertex 1.00418 1.14471 2.61623 + vertex 1.00368 1.14841 2.6168 + vertex 0.99917 1.14356 2.61643 + endloop + endfacet + facet normal 0.0750201 -0.156941 0.984754 + outer loop + vertex 1.00418 1.14471 2.61623 + vertex 0.99917 1.14356 2.61643 + vertex 1.00144 1.14096 2.61584 + endloop + endfacet + facet normal 0.0871094 -0.184311 0.979 + outer loop + vertex 0.998344 1.13718 2.6154 + vertex 1.0036 1.1384 2.61516 + vertex 1.00144 1.14096 2.61584 + endloop + endfacet + facet normal 0.062096 -0.1635 0.984587 + outer loop + vertex 0.998344 1.13718 2.6154 + vertex 0.993344 1.13334 2.61508 + vertex 0.998434 1.13314 2.61473 + endloop + endfacet + facet normal 0.0635613 -0.159792 0.985102 + outer loop + vertex 0.987952 1.13231 2.61526 + vertex 0.993344 1.13334 2.61508 + vertex 0.99132 1.13634 2.6157 + endloop + endfacet + facet normal 0.0601006 -0.16853 0.983863 + outer loop + vertex 0.99775 1.13976 2.61588 + vertex 0.994527 1.13995 2.61611 + vertex 0.995107 1.13734 2.61562 + endloop + endfacet + facet normal 0.066953 -0.174153 0.98244 + outer loop + vertex 0.994527 1.13995 2.61611 + vertex 0.993966 1.14362 2.61679 + vertex 0.989897 1.13942 2.61633 + endloop + endfacet + facet normal 0.0715272 -0.172895 0.98234 + outer loop + vertex 0.989897 1.13942 2.61633 + vertex 0.988746 1.14327 2.61709 + vertex 0.984339 1.1383 2.61653 + endloop + endfacet + facet normal 0.0739719 -0.167045 0.98317 + outer loop + vertex 0.983564 1.13185 2.6155 + vertex 0.983074 1.13448 2.61599 + vertex 0.98048 1.1321 2.61578 + endloop + endfacet + facet normal 0.0696917 -0.164783 0.983865 + outer loop + vertex 0.986759 1.13547 2.61588 + vertex 0.987952 1.13231 2.61526 + vertex 0.99132 1.13634 2.6157 + endloop + endfacet + facet normal 0.0646201 -0.165561 0.98408 + outer loop + vertex 0.988381 1.12816 2.61454 + vertex 0.993344 1.13334 2.61508 + vertex 0.987952 1.13231 2.61526 + endloop + endfacet + facet normal 0.0633058 -0.170151 0.983382 + outer loop + vertex 0.988275 1.12318 2.61368 + vertex 0.988381 1.12816 2.61454 + vertex 0.983392 1.12323 2.614 + endloop + endfacet + facet normal 0.063146 -0.177536 0.982086 + outer loop + vertex 0.983291 1.11813 2.61309 + vertex 0.988275 1.12318 2.61368 + vertex 0.983392 1.12323 2.614 + endloop + endfacet + facet normal 0.0603446 -0.179653 0.981877 + outer loop + vertex 0.983738 1.11332 2.61218 + vertex 0.983291 1.11813 2.61309 + vertex 0.978504 1.11316 2.61247 + endloop + endfacet + facet normal 0.0591194 -0.179787 0.981927 + outer loop + vertex 0.979317 1.1084 2.61155 + vertex 0.978504 1.11316 2.61247 + vertex 0.97406 1.10863 2.61191 + endloop + endfacet + facet normal 0.0594906 -0.17724 0.982368 + outer loop + vertex 0.981733 1.10551 2.61088 + vertex 0.979317 1.1084 2.61155 + vertex 0.978002 1.10462 2.61095 + endloop + endfacet + facet normal 0.0594863 -0.177222 0.982372 + outer loop + vertex 0.978002 1.10462 2.61095 + vertex 0.978453 1.10195 2.61044 + vertex 0.981733 1.10551 2.61088 + endloop + endfacet + facet normal 0.0579882 -0.182775 0.981443 + outer loop + vertex 0.978453 1.10195 2.61044 + vertex 0.973436 1.09828 2.61005 + vertex 0.978397 1.09798 2.6097 + endloop + endfacet + facet normal 0.0573547 -0.177123 0.982516 + outer loop + vertex 0.975364 1.1023 2.61069 + vertex 0.974755 1.10494 2.6112 + vertex 0.971471 1.10139 2.61075 + endloop + endfacet + facet normal 0.054069 -0.193774 0.979555 + outer loop + vertex 0.968296 1.09301 2.60929 + vertex 0.973436 1.09828 2.61005 + vertex 0.967737 1.09723 2.61016 + endloop + endfacet + facet normal 0.0584558 -0.178112 0.982272 + outer loop + vertex 0.974755 1.10494 2.6112 + vertex 0.970179 1.10462 2.61142 + vertex 0.971471 1.10139 2.61075 + endloop + endfacet + facet normal 0.0519596 -0.177521 0.982744 + outer loop + vertex 0.970179 1.10462 2.61142 + vertex 0.969049 1.10847 2.61217 + vertex 0.965234 1.10421 2.6116 + endloop + endfacet + facet normal 0.0467806 -0.17303 0.983805 + outer loop + vertex 0.965234 1.10421 2.6116 + vertex 0.969049 1.10847 2.61217 + vertex 0.964047 1.10827 2.61237 + endloop + endfacet + facet normal 0.0402899 -0.193531 0.980267 + outer loop + vertex 0.962625 1.09667 2.61026 + vertex 0.967737 1.09723 2.61016 + vertex 0.966586 1.10072 2.6109 + endloop + endfacet + facet normal 0.0112362 -0.203935 0.97892 + outer loop + vertex 0.958296 1.09247 2.60944 + vertex 0.962625 1.09667 2.61026 + vertex 0.957616 1.09638 2.61026 + endloop + endfacet + facet normal -0.0364977 -0.211775 0.976637 + outer loop + vertex 0.958296 1.09247 2.60944 + vertex 0.957616 1.09638 2.61026 + vertex 0.953603 1.09254 2.60927 + endloop + endfacet + facet normal -0.036467 -0.207109 0.977638 + outer loop + vertex 0.954187 1.08839 2.60842 + vertex 0.958296 1.09247 2.60944 + vertex 0.953603 1.09254 2.60927 + endloop + endfacet + facet normal -0.035492 -0.20805 0.977474 + outer loop + vertex 0.958723 1.08825 2.60855 + vertex 0.958296 1.09247 2.60944 + vertex 0.954187 1.08839 2.60842 + endloop + endfacet + facet normal -0.0353686 -0.20341 0.978455 + outer loop + vertex 0.955122 1.08473 2.60769 + vertex 0.958723 1.08825 2.60855 + vertex 0.954187 1.08839 2.60842 + endloop + endfacet + facet normal -0.0327234 -0.206007 0.978003 + outer loop + vertex 0.959121 1.08379 2.60763 + vertex 0.958723 1.08825 2.60855 + vertex 0.955122 1.08473 2.60769 + endloop + endfacet + facet normal -0.0470292 -0.201215 0.978417 + outer loop + vertex 0.953603 1.09254 2.60927 + vertex 0.957616 1.09638 2.61026 + vertex 0.952577 1.09652 2.61004 + endloop + endfacet + facet normal -0.0472389 -0.211559 0.976223 + outer loop + vertex 0.952577 1.09652 2.61004 + vertex 0.957616 1.09638 2.61026 + vertex 0.956453 1.10008 2.611 + endloop + endfacet + facet normal -0.0517117 -0.206889 0.976997 + outer loop + vertex 0.951362 1.10053 2.61083 + vertex 0.952577 1.09652 2.61004 + vertex 0.956453 1.10008 2.611 + endloop + endfacet + facet normal 0.0331008 -0.178727 0.983342 + outer loop + vertex 0.965234 1.10421 2.6116 + vertex 0.960172 1.10393 2.61172 + vertex 0.961552 1.10024 2.61101 + endloop + endfacet + facet normal -0.050972 -0.19789 0.978898 + outer loop + vertex 0.956453 1.10008 2.611 + vertex 0.955025 1.10406 2.61173 + vertex 0.951362 1.10053 2.61083 + endloop + endfacet + facet normal -0.00687287 -0.174698 0.984598 + outer loop + vertex 0.955025 1.10406 2.61173 + vertex 0.959019 1.1082 2.6125 + vertex 0.954085 1.10855 2.61252 + endloop + endfacet + facet normal 0.0330147 -0.177023 0.983653 + outer loop + vertex 0.965234 1.10421 2.6116 + vertex 0.964047 1.10827 2.61237 + vertex 0.960172 1.10393 2.61172 + endloop + endfacet + facet normal 0.0212771 -0.171459 0.984961 + outer loop + vertex 0.959019 1.1082 2.6125 + vertex 0.963456 1.11302 2.61324 + vertex 0.958495 1.11302 2.61335 + endloop + endfacet + facet normal 0.0469601 -0.178518 0.982815 + outer loop + vertex 0.969049 1.10847 2.61217 + vertex 0.968422 1.11309 2.61304 + vertex 0.964047 1.10827 2.61237 + endloop + endfacet + facet normal 0.0390499 -0.177792 0.983293 + outer loop + vertex 0.963456 1.11302 2.61324 + vertex 0.968399 1.1181 2.61396 + vertex 0.963442 1.11805 2.61415 + endloop + endfacet + facet normal 0.0390604 -0.181941 0.982533 + outer loop + vertex 0.968399 1.1181 2.61396 + vertex 0.968575 1.12284 2.61483 + vertex 0.963442 1.11805 2.61415 + endloop + endfacet + facet normal 0.0540472 -0.181869 0.981836 + outer loop + vertex 0.973416 1.11316 2.61278 + vertex 0.97334 1.11817 2.61371 + vertex 0.968422 1.11309 2.61304 + endloop + endfacet + facet normal 0.0525256 -0.182314 0.981836 + outer loop + vertex 0.968399 1.1181 2.61396 + vertex 0.973522 1.12308 2.61461 + vertex 0.968575 1.12284 2.61483 + endloop + endfacet + facet normal 0.0597867 -0.180325 0.981788 + outer loop + vertex 0.978301 1.11817 2.61341 + vertex 0.978512 1.12325 2.61433 + vertex 0.97334 1.11817 2.61371 + endloop + endfacet + facet normal 0.0690025 -0.1781 0.98159 + outer loop + vertex 0.978512 1.12325 2.61433 + vertex 0.983549 1.12798 2.61483 + vertex 0.978649 1.12819 2.61522 + endloop + endfacet + facet normal 0.0524745 -0.18106 0.982071 + outer loop + vertex 0.973522 1.12308 2.61461 + vertex 0.973163 1.12714 2.61538 + vertex 0.968575 1.12284 2.61483 + endloop + endfacet + facet normal 0.039032 -0.181911 0.98254 + outer loop + vertex 0.963442 1.11805 2.61415 + vertex 0.968575 1.12284 2.61483 + vertex 0.963564 1.1231 2.61508 + endloop + endfacet + facet normal 0.0335917 -0.182015 0.982722 + outer loop + vertex 0.965568 1.12706 2.61574 + vertex 0.961592 1.12622 2.61572 + vertex 0.963564 1.1231 2.61508 + endloop + endfacet + facet normal 0.0510877 -0.172674 0.983653 + outer loop + vertex 0.968229 1.12935 2.61603 + vertex 0.968681 1.12671 2.61554 + vertex 0.971973 1.13026 2.61599 + endloop + endfacet + facet normal 0.0308249 -0.168965 0.98514 + outer loop + vertex 0.965568 1.12706 2.61574 + vertex 0.964937 1.12969 2.61621 + vertex 0.961592 1.12622 2.61572 + endloop + endfacet + facet normal 0.0482768 -0.160984 0.985776 + outer loop + vertex 0.971973 1.13026 2.61599 + vertex 0.969491 1.13315 2.61659 + vertex 0.968229 1.12935 2.61603 + endloop + endfacet + facet normal 0.0322447 -0.161598 0.98633 + outer loop + vertex 0.964937 1.12969 2.61621 + vertex 0.964179 1.13341 2.61685 + vertex 0.960256 1.12949 2.61633 + endloop + endfacet + facet normal 0.0402645 -0.160411 0.986229 + outer loop + vertex 0.964179 1.13341 2.61685 + vertex 0.968578 1.13796 2.61741 + vertex 0.96344 1.13795 2.61762 + endloop + endfacet + facet normal 0.0510697 -0.161379 0.98557 + outer loop + vertex 0.975093 1.13418 2.61646 + vertex 0.973823 1.13813 2.61718 + vertex 0.969491 1.13315 2.61659 + endloop + endfacet + facet normal 0.0485069 -0.16189 0.985616 + outer loop + vertex 0.968578 1.13796 2.61741 + vertex 0.973294 1.143 2.61801 + vertex 0.968268 1.14303 2.61826 + endloop + endfacet + facet normal 0.0584561 -0.163553 0.984801 + outer loop + vertex 0.979031 1.13842 2.61692 + vertex 0.978355 1.14302 2.61772 + vertex 0.973823 1.13813 2.61718 + endloop + endfacet + facet normal 0.0554735 -0.162209 0.985196 + outer loop + vertex 0.973294 1.143 2.61801 + vertex 0.978257 1.14813 2.61857 + vertex 0.973339 1.14823 2.61886 + endloop + endfacet + facet normal 0.0620572 -0.16603 0.984166 + outer loop + vertex 0.983484 1.14304 2.6174 + vertex 0.983193 1.14803 2.61826 + vertex 0.978355 1.14302 2.61772 + endloop + endfacet + facet normal 0.0573296 -0.159436 0.985542 + outer loop + vertex 0.978257 1.14813 2.61857 + vertex 0.983366 1.15321 2.61909 + vertex 0.978472 1.15332 2.6194 + endloop + endfacet + facet normal 0.0575186 -0.15352 0.98647 + outer loop + vertex 0.983366 1.15321 2.61909 + vertex 0.983602 1.15815 2.61985 + vertex 0.978472 1.15332 2.6194 + endloop + endfacet + facet normal 0.0603163 -0.164511 0.984529 + outer loop + vertex 0.988224 1.14799 2.61795 + vertex 0.988261 1.1531 2.6188 + vertex 0.983193 1.14803 2.61826 + endloop + endfacet + facet normal 0.0547633 -0.153415 0.986643 + outer loop + vertex 0.983366 1.15321 2.61909 + vertex 0.988553 1.15819 2.61958 + vertex 0.983602 1.15815 2.61985 + endloop + endfacet + facet normal 0.062179 -0.158012 0.985478 + outer loop + vertex 0.993257 1.15305 2.61847 + vertex 0.993478 1.15816 2.61928 + vertex 0.988261 1.1531 2.6188 + endloop + endfacet + facet normal 0.056968 -0.145721 0.987684 + outer loop + vertex 0.988553 1.15819 2.61958 + vertex 0.993753 1.16301 2.61999 + vertex 0.988711 1.16307 2.62029 + endloop + endfacet + facet normal 0.0569524 -0.146443 0.987578 + outer loop + vertex 0.993737 1.16688 2.62057 + vertex 0.988711 1.16307 2.62029 + vertex 0.993753 1.16301 2.61999 + endloop + endfacet + facet normal 0.0837113 -0.147882 0.985456 + outer loop + vertex 0.998451 1.1582 2.61886 + vertex 0.998714 1.16325 2.6196 + vertex 0.993478 1.15816 2.61928 + endloop + endfacet + facet normal 0.0819741 -0.146084 0.98587 + outer loop + vertex 0.993753 1.16301 2.61999 + vertex 0.998904 1.16824 2.62034 + vertex 0.993737 1.16688 2.62057 + endloop + endfacet + facet normal 0.134218 -0.133426 0.981928 + outer loop + vertex 1.00356 1.16332 2.61895 + vertex 1.00382 1.16832 2.61959 + vertex 0.998714 1.16325 2.6196 + endloop + endfacet + facet normal 0.0875472 -0.167927 0.981904 + outer loop + vertex 0.993737 1.16688 2.62057 + vertex 0.998904 1.16824 2.62034 + vertex 0.996798 1.17068 2.62094 + endloop + endfacet + facet normal 0.11418 -0.135568 0.984167 + outer loop + vertex 1.00255 1.17501 2.62098 + vertex 0.999427 1.17452 2.62128 + vertex 1.00051 1.17227 2.62084 + endloop + endfacet + facet normal 0.11015 -0.107715 0.988061 + outer loop + vertex 1.00255 1.17501 2.62098 + vertex 1.00278 1.17816 2.6213 + vertex 0.999427 1.17452 2.62128 + endloop + endfacet + facet normal 0.114557 -0.111773 0.987109 + outer loop + vertex 1.00278 1.17816 2.6213 + vertex 0.998828 1.17831 2.62178 + vertex 0.999427 1.17452 2.62128 + endloop + endfacet + facet normal 0.115937 -0.0844517 0.98966 + outer loop + vertex 1.00278 1.17816 2.6213 + vertex 1.00357 1.18316 2.62164 + vertex 0.998828 1.17831 2.62178 + endloop + endfacet + facet normal 0.148905 -0.116921 0.981915 + outer loop + vertex 0.998828 1.17831 2.62178 + vertex 1.00357 1.18316 2.62164 + vertex 0.998565 1.18313 2.62239 + endloop + endfacet + facet normal 0.149107 -0.100529 0.983698 + outer loop + vertex 1.00357 1.18316 2.62164 + vertex 1.00305 1.18816 2.62222 + vertex 0.998565 1.18313 2.62239 + endloop + endfacet + facet normal 0.169797 -0.119177 0.978246 + outer loop + vertex 0.998565 1.18313 2.62239 + vertex 1.00305 1.18816 2.62222 + vertex 0.998386 1.18818 2.62304 + endloop + endfacet + facet normal 0.170336 -0.0953881 0.980758 + outer loop + vertex 1.00305 1.18816 2.62222 + vertex 1.003 1.19314 2.62272 + vertex 0.998386 1.18818 2.62304 + endloop + endfacet + facet normal 0.193301 -0.117235 0.97411 + outer loop + vertex 0.998386 1.18818 2.62304 + vertex 1.003 1.19314 2.62272 + vertex 0.998427 1.19326 2.62364 + endloop + endfacet + facet normal 0.194417 -0.0936102 0.976442 + outer loop + vertex 1.003 1.19314 2.62272 + vertex 1.0031 1.19814 2.62318 + vertex 0.998427 1.19326 2.62364 + endloop + endfacet + facet normal 0.0641229 -0.141898 0.987802 + outer loop + vertex 0.994425 1.17328 2.62147 + vertex 0.993777 1.17807 2.6222 + vertex 0.988988 1.17326 2.62182 + endloop + endfacet + facet normal 0.0596063 -0.144414 0.987721 + outer loop + vertex 0.996798 1.17068 2.62094 + vertex 0.994425 1.17328 2.62147 + vertex 0.993115 1.16938 2.62098 + endloop + endfacet + facet normal 0.0603766 -0.146602 0.987351 + outer loop + vertex 0.993115 1.16938 2.62098 + vertex 0.993737 1.16688 2.62057 + vertex 0.996798 1.17068 2.62094 + endloop + endfacet + facet normal 0.0572197 -0.148899 0.987196 + outer loop + vertex 0.990478 1.16691 2.62075 + vertex 0.989693 1.16945 2.62118 + vertex 0.986655 1.16579 2.6208 + endloop + endfacet + facet normal 0.0547652 -0.145669 0.987816 + outer loop + vertex 0.988553 1.15819 2.61958 + vertex 0.988711 1.16307 2.62029 + vertex 0.983602 1.15815 2.61985 + endloop + endfacet + facet normal 0.0598175 -0.155914 0.985958 + outer loop + vertex 0.978472 1.15332 2.6194 + vertex 0.983602 1.15815 2.61985 + vertex 0.978532 1.15831 2.62018 + endloop + endfacet + facet normal 0.061528 -0.155153 0.985972 + outer loop + vertex 0.973366 1.15734 2.62035 + vertex 0.978532 1.15831 2.62018 + vertex 0.976414 1.16102 2.62074 + endloop + endfacet + facet normal 0.0626267 -0.153591 0.986148 + outer loop + vertex 0.979407 1.16468 2.6211 + vertex 0.978735 1.16835 2.62172 + vertex 0.974095 1.1636 2.62127 + endloop + endfacet + facet normal 0.0592812 -0.15039 0.986848 + outer loop + vertex 0.974095 1.1636 2.62127 + vertex 0.978735 1.16835 2.62172 + vertex 0.973448 1.16811 2.622 + endloop + endfacet + facet normal 0.0620986 -0.155614 0.985864 + outer loop + vertex 0.97272 1.15991 2.6208 + vertex 0.973366 1.15734 2.62035 + vertex 0.976414 1.16102 2.62074 + endloop + endfacet + facet normal 0.0533592 -0.160837 0.985537 + outer loop + vertex 0.973366 1.15734 2.62035 + vertex 0.968392 1.15351 2.62 + vertex 0.9735 1.15329 2.61968 + endloop + endfacet + facet normal 0.0461098 -0.152607 0.987211 + outer loop + vertex 0.970142 1.15753 2.62057 + vertex 0.969535 1.16012 2.621 + vertex 0.966364 1.15663 2.6206 + endloop + endfacet + facet normal 0.0458205 -0.16649 0.984978 + outer loop + vertex 0.963311 1.14816 2.61933 + vertex 0.968392 1.15351 2.62 + vertex 0.962803 1.15252 2.62009 + endloop + endfacet + facet normal 0.035734 -0.163093 0.985963 + outer loop + vertex 0.957782 1.15204 2.62019 + vertex 0.962803 1.15252 2.62009 + vertex 0.961646 1.15604 2.62071 + endloop + endfacet + facet normal 0.045192 -0.151793 0.987379 + outer loop + vertex 0.969535 1.16012 2.621 + vertex 0.965107 1.15981 2.62115 + vertex 0.966364 1.15663 2.6206 + endloop + endfacet + facet normal 0.0349384 -0.153314 0.98756 + outer loop + vertex 0.961646 1.15604 2.62071 + vertex 0.960296 1.15943 2.62129 + vertex 0.956731 1.15562 2.62082 + endloop + endfacet + facet normal 0.0371539 -0.146282 0.988545 + outer loop + vertex 0.960296 1.15943 2.62129 + vertex 0.964026 1.16349 2.62175 + vertex 0.959064 1.16327 2.6219 + endloop + endfacet + facet normal 0.0449911 -0.14877 0.987848 + outer loop + vertex 0.969535 1.16012 2.621 + vertex 0.968954 1.1637 2.62156 + vertex 0.965107 1.15981 2.62115 + endloop + endfacet + facet normal 0.0415616 -0.147861 0.988135 + outer loop + vertex 0.964026 1.16349 2.62175 + vertex 0.968352 1.16802 2.62224 + vertex 0.963349 1.16792 2.62244 + endloop + endfacet + facet normal 0.0524051 -0.151415 0.98708 + outer loop + vertex 0.974095 1.1636 2.62127 + vertex 0.973448 1.16811 2.622 + vertex 0.968954 1.1637 2.62156 + endloop + endfacet + facet normal 0.0477115 -0.14883 0.987711 + outer loop + vertex 0.968352 1.16802 2.62224 + vertex 0.973181 1.17291 2.62275 + vertex 0.968202 1.17294 2.62299 + endloop + endfacet + facet normal 0.0594266 -0.154163 0.986257 + outer loop + vertex 0.978735 1.16835 2.62172 + vertex 0.978274 1.17294 2.62246 + vertex 0.973448 1.16811 2.622 + endloop + endfacet + facet normal 0.062851 -0.153794 0.986102 + outer loop + vertex 0.978735 1.16835 2.62172 + vertex 0.98356 1.17303 2.62214 + vertex 0.978274 1.17294 2.62246 + endloop + endfacet + facet normal 0.0524504 -0.147005 0.987744 + outer loop + vertex 0.973181 1.17291 2.62275 + vertex 0.978212 1.17797 2.62323 + vertex 0.973317 1.17808 2.62351 + endloop + endfacet + facet normal 0.0628539 -0.15416 0.986045 + outer loop + vertex 0.98356 1.17303 2.62214 + vertex 0.98325 1.17791 2.62292 + vertex 0.978274 1.17294 2.62246 + endloop + endfacet + facet normal 0.0551369 -0.144252 0.988004 + outer loop + vertex 0.978212 1.17797 2.62323 + vertex 0.983282 1.18305 2.62369 + vertex 0.978389 1.18316 2.62398 + endloop + endfacet + facet normal 0.0662189 -0.149798 0.986497 + outer loop + vertex 0.988473 1.17796 2.62258 + vertex 0.988309 1.18299 2.62335 + vertex 0.98325 1.17791 2.62292 + endloop + endfacet + facet normal 0.0629128 -0.14091 0.988021 + outer loop + vertex 0.983282 1.18305 2.62369 + vertex 0.988401 1.18814 2.62409 + vertex 0.98342 1.18823 2.62442 + endloop + endfacet + facet normal 0.0630885 -0.134258 0.988936 + outer loop + vertex 0.988401 1.18814 2.62409 + vertex 0.988612 1.19326 2.62477 + vertex 0.98342 1.18823 2.62442 + endloop + endfacet + facet normal 0.0820579 -0.138228 0.986995 + outer loop + vertex 0.993461 1.18303 2.62293 + vertex 0.99342 1.18814 2.62365 + vertex 0.988309 1.18299 2.62335 + endloop + endfacet + facet normal 0.0912385 -0.135111 0.986621 + outer loop + vertex 0.988401 1.18814 2.62409 + vertex 0.993572 1.19324 2.62431 + vertex 0.988612 1.19326 2.62477 + endloop + endfacet + facet normal 0.122892 -0.118007 0.985379 + outer loop + vertex 0.998386 1.18818 2.62304 + vertex 0.998427 1.19326 2.62364 + vertex 0.99342 1.18814 2.62365 + endloop + endfacet + facet normal 0.119077 -0.144987 0.982242 + outer loop + vertex 0.990494 1.20198 2.62578 + vertex 0.989052 1.19823 2.6254 + vertex 0.994272 1.20309 2.62549 + endloop + endfacet + facet normal 0.0914162 -0.12373 0.988096 + outer loop + vertex 0.993572 1.19324 2.62431 + vertex 0.993865 1.19824 2.62491 + vertex 0.988612 1.19326 2.62477 + endloop + endfacet + facet normal 0.064668 -0.135866 0.988614 + outer loop + vertex 0.98342 1.18823 2.62442 + vertex 0.988612 1.19326 2.62477 + vertex 0.983391 1.19345 2.62514 + endloop + endfacet + facet normal 0.0587912 -0.133797 0.989263 + outer loop + vertex 0.985088 1.19762 2.6256 + vertex 0.981179 1.19632 2.62566 + vertex 0.983391 1.19345 2.62514 + endloop + endfacet + facet normal 0.0772317 -0.12952 0.988565 + outer loop + vertex 0.990494 1.20198 2.62578 + vertex 0.987549 1.20026 2.62579 + vertex 0.989052 1.19823 2.6254 + endloop + endfacet + facet normal 0.0546899 -0.121367 0.9911 + outer loop + vertex 0.985088 1.19762 2.6256 + vertex 0.984362 1.20008 2.62595 + vertex 0.981179 1.19632 2.62566 + endloop + endfacet + facet normal 0.060134 -0.100163 0.993152 + outer loop + vertex 0.990494 1.20198 2.62578 + vertex 0.988752 1.20387 2.62608 + vertex 0.987549 1.20026 2.62579 + endloop + endfacet + facet normal 0.0567501 -0.0777067 0.99536 + outer loop + vertex 0.988752 1.20387 2.62608 + vertex 0.988609 1.20834 2.62644 + vertex 0.983965 1.20369 2.62634 + endloop + endfacet + facet normal 0.063242 -0.0841755 0.994442 + outer loop + vertex 0.983965 1.20369 2.62634 + vertex 0.988609 1.20834 2.62644 + vertex 0.983593 1.2081 2.62673 + endloop + endfacet + facet normal 0.0602353 -0.112413 0.991834 + outer loop + vertex 0.974297 1.19825 2.62631 + vertex 0.978839 1.20322 2.6266 + vertex 0.97357 1.20295 2.62689 + endloop + endfacet + facet normal 0.0598789 -0.127855 0.989984 + outer loop + vertex 0.979818 1.19938 2.62613 + vertex 0.974297 1.19825 2.62631 + vertex 0.976612 1.19537 2.6258 + endloop + endfacet + facet normal 0.0556688 -0.139653 0.988634 + outer loop + vertex 0.973461 1.19179 2.62547 + vertex 0.977858 1.19223 2.62529 + vertex 0.976612 1.19537 2.6258 + endloop + endfacet + facet normal 0.0492607 -0.143455 0.98843 + outer loop + vertex 0.973461 1.19179 2.62547 + vertex 0.968654 1.18827 2.6252 + vertex 0.973594 1.18795 2.62491 + endloop + endfacet + facet normal 0.0501538 -0.14081 0.988765 + outer loop + vertex 0.972943 1.19444 2.62589 + vertex 0.969731 1.19478 2.6261 + vertex 0.970379 1.19214 2.62569 + endloop + endfacet + facet normal 0.0418149 -0.13162 0.990418 + outer loop + vertex 0.969731 1.19478 2.6261 + vertex 0.969076 1.19849 2.62662 + vertex 0.965139 1.19453 2.62626 + endloop + endfacet + facet normal 0.0416555 -0.146329 0.988359 + outer loop + vertex 0.963 1.18736 2.62531 + vertex 0.968654 1.18827 2.6252 + vertex 0.966532 1.19131 2.62574 + endloop + endfacet + facet normal 0.0330867 -0.141345 0.989407 + outer loop + vertex 0.958478 1.18294 2.62483 + vertex 0.963 1.18736 2.62531 + vertex 0.957962 1.18692 2.62541 + endloop + endfacet + facet normal 0.0271521 -0.142319 0.989448 + outer loop + vertex 0.953417 1.18671 2.62551 + vertex 0.957962 1.18692 2.62541 + vertex 0.956777 1.19017 2.62591 + endloop + endfacet + facet normal 0.0341608 -0.140999 0.98942 + outer loop + vertex 0.965139 1.19453 2.62626 + vertex 0.960049 1.19407 2.62637 + vertex 0.961658 1.19074 2.62584 + endloop + endfacet + facet normal 0.03362 -0.13476 0.990308 + outer loop + vertex 0.965139 1.19453 2.62626 + vertex 0.964001 1.19836 2.62682 + vertex 0.960049 1.19407 2.62637 + endloop + endfacet + facet normal 0.0424874 -0.115791 0.992364 + outer loop + vertex 0.964001 1.19836 2.62682 + vertex 0.968426 1.20294 2.62717 + vertex 0.963372 1.20291 2.62738 + endloop + endfacet + facet normal 0.0453097 -0.0964313 0.994308 + outer loop + vertex 0.963372 1.20291 2.62738 + vertex 0.968229 1.20788 2.62764 + vertex 0.963272 1.20793 2.62787 + endloop + endfacet + facet normal 0.0293742 -0.123051 0.991966 + outer loop + vertex 0.95352 1.19786 2.62707 + vertex 0.958295 1.20283 2.62755 + vertex 0.953205 1.20275 2.62769 + endloop + endfacet + facet normal 0.0277626 -0.135876 0.990337 + outer loop + vertex 0.954321 1.19315 2.6264 + vertex 0.958788 1.19807 2.62695 + vertex 0.95352 1.19786 2.62707 + endloop + endfacet + facet normal 0.0275109 -0.14072 0.989667 + outer loop + vertex 0.956777 1.19017 2.62591 + vertex 0.954321 1.19315 2.6264 + vertex 0.952931 1.18939 2.62591 + endloop + endfacet + facet normal 0.0280017 -0.143126 0.989308 + outer loop + vertex 0.952931 1.18939 2.62591 + vertex 0.953417 1.18671 2.62551 + vertex 0.956777 1.19017 2.62591 + endloop + endfacet + facet normal 0.0138211 -0.144683 0.989382 + outer loop + vertex 0.953417 1.18671 2.62551 + vertex 0.948328 1.18317 2.62506 + vertex 0.953455 1.18281 2.62494 + endloop + endfacet + facet normal 0.00988075 -0.145068 0.989372 + outer loop + vertex 0.950231 1.18713 2.62564 + vertex 0.949657 1.1898 2.62604 + vertex 0.946308 1.18644 2.62558 + endloop + endfacet + facet normal -0.0106393 -0.152211 0.988291 + outer loop + vertex 0.943296 1.17801 2.62421 + vertex 0.948328 1.18317 2.62506 + vertex 0.942553 1.18247 2.62489 + endloop + endfacet + facet normal 0.00967019 -0.144863 0.989405 + outer loop + vertex 0.949657 1.1898 2.62604 + vertex 0.945058 1.18988 2.6261 + vertex 0.946308 1.18644 2.62558 + endloop + endfacet + facet normal 0.0106216 -0.1418 0.989838 + outer loop + vertex 0.945058 1.18988 2.6261 + vertex 0.949058 1.19349 2.62657 + vertex 0.944179 1.19378 2.62667 + endloop + endfacet + facet normal 0.0119215 -0.138087 0.990348 + outer loop + vertex 0.944179 1.19378 2.62667 + vertex 0.948423 1.19787 2.62719 + vertex 0.943597 1.19804 2.62727 + endloop + endfacet + facet normal 0.00401095 -0.101015 0.994877 + outer loop + vertex 0.943191 1.20273 2.62786 + vertex 0.948151 1.20781 2.62835 + vertex 0.94308 1.20775 2.62837 + endloop + endfacet + facet normal -0.0118245 -0.0683552 0.997591 + outer loop + vertex 0.94308 1.20775 2.62837 + vertex 0.948297 1.21299 2.62879 + vertex 0.943173 1.21292 2.62872 + endloop + endfacet + facet normal 0.00382679 -0.0838515 0.996471 + outer loop + vertex 0.948151 1.20781 2.62835 + vertex 0.948297 1.21299 2.62879 + vertex 0.94308 1.20775 2.62837 + endloop + endfacet + facet normal 0.0222259 -0.0843444 0.996189 + outer loop + vertex 0.948151 1.20781 2.62835 + vertex 0.953395 1.21305 2.62868 + vertex 0.948297 1.21299 2.62879 + endloop + endfacet + facet normal 0.0221318 -0.0743318 0.996988 + outer loop + vertex 0.953395 1.21305 2.62868 + vertex 0.953552 1.21819 2.62906 + vertex 0.948297 1.21299 2.62879 + endloop + endfacet + facet normal 0.0162389 -0.0684049 0.997525 + outer loop + vertex 0.948297 1.21299 2.62879 + vertex 0.953552 1.21819 2.62906 + vertex 0.948498 1.21815 2.62914 + endloop + endfacet + facet normal -0.0118404 -0.0673182 0.997661 + outer loop + vertex 0.948297 1.21299 2.62879 + vertex 0.948498 1.21815 2.62914 + vertex 0.943173 1.21292 2.62872 + endloop + endfacet + facet normal 0.0383643 -0.0747887 0.996461 + outer loop + vertex 0.953395 1.21305 2.62868 + vertex 0.958546 1.21817 2.62887 + vertex 0.953552 1.21819 2.62906 + endloop + endfacet + facet normal 0.0373404 -0.0737629 0.996577 + outer loop + vertex 0.95843 1.21307 2.62849 + vertex 0.958546 1.21817 2.62887 + vertex 0.953395 1.21305 2.62868 + endloop + endfacet + facet normal 0.0373535 -0.0867757 0.995527 + outer loop + vertex 0.95324 1.20787 2.62824 + vertex 0.95843 1.21307 2.62849 + vertex 0.953395 1.21305 2.62868 + endloop + endfacet + facet normal 0.0342326 -0.0836756 0.995905 + outer loop + vertex 0.958288 1.20792 2.62807 + vertex 0.95843 1.21307 2.62849 + vertex 0.95324 1.20787 2.62824 + endloop + endfacet + facet normal 0.0441827 -0.0839171 0.995493 + outer loop + vertex 0.958288 1.20792 2.62807 + vertex 0.963394 1.21305 2.62827 + vertex 0.95843 1.21307 2.62849 + endloop + endfacet + facet normal 0.0442696 -0.0712825 0.996473 + outer loop + vertex 0.963394 1.21305 2.62827 + vertex 0.963491 1.21812 2.62863 + vertex 0.95843 1.21307 2.62849 + endloop + endfacet + facet normal 0.0498718 -0.0713709 0.996202 + outer loop + vertex 0.963394 1.21305 2.62827 + vertex 0.968416 1.21806 2.62838 + vertex 0.963491 1.21812 2.62863 + endloop + endfacet + facet normal 0.0482483 -0.0697477 0.996397 + outer loop + vertex 0.968316 1.213 2.62803 + vertex 0.968416 1.21806 2.62838 + vertex 0.963394 1.21305 2.62827 + endloop + endfacet + facet normal 0.0481074 -0.0792001 0.995697 + outer loop + vertex 0.963272 1.20793 2.62787 + vertex 0.968316 1.213 2.62803 + vertex 0.963394 1.21305 2.62827 + endloop + endfacet + facet normal 0.0455798 -0.0766933 0.996012 + outer loop + vertex 0.968229 1.20788 2.62764 + vertex 0.968316 1.213 2.62803 + vertex 0.963272 1.20793 2.62787 + endloop + endfacet + facet normal 0.0539036 -0.0768022 0.995588 + outer loop + vertex 0.968229 1.20788 2.62764 + vertex 0.973268 1.21293 2.62776 + vertex 0.968316 1.213 2.62803 + endloop + endfacet + facet normal 0.0540082 -0.0710217 0.996012 + outer loop + vertex 0.973268 1.21293 2.62776 + vertex 0.973364 1.21801 2.62811 + vertex 0.968316 1.213 2.62803 + endloop + endfacet + facet normal 0.0589759 -0.0710954 0.995725 + outer loop + vertex 0.973268 1.21293 2.62776 + vertex 0.978388 1.21801 2.62782 + vertex 0.973364 1.21801 2.62811 + endloop + endfacet + facet normal 0.060912 -0.0730443 0.995467 + outer loop + vertex 0.978322 1.21291 2.62745 + vertex 0.978388 1.21801 2.62782 + vertex 0.973268 1.21293 2.62776 + endloop + endfacet + facet normal 0.0608864 -0.0763461 0.995221 + outer loop + vertex 0.973246 1.20782 2.62737 + vertex 0.978322 1.21291 2.62745 + vertex 0.973268 1.21293 2.62776 + endloop + endfacet + facet normal 0.0611261 -0.0765848 0.995188 + outer loop + vertex 0.978399 1.20788 2.62705 + vertex 0.978322 1.21291 2.62745 + vertex 0.973246 1.20782 2.62737 + endloop + endfacet + facet normal 0.0669076 -0.0764674 0.994825 + outer loop + vertex 0.978399 1.20788 2.62705 + vertex 0.983449 1.21299 2.62711 + vertex 0.978322 1.21291 2.62745 + endloop + endfacet + facet normal 0.0668639 -0.0726679 0.995112 + outer loop + vertex 0.983449 1.21299 2.62711 + vertex 0.983471 1.21807 2.62748 + vertex 0.978322 1.21291 2.62745 + endloop + endfacet + facet normal 0.0766668 -0.0726599 0.994406 + outer loop + vertex 0.983449 1.21299 2.62711 + vertex 0.988447 1.21812 2.6271 + vertex 0.983471 1.21807 2.62748 + endloop + endfacet + facet normal 0.0701889 -0.0663428 0.995325 + outer loop + vertex 0.988454 1.21311 2.62676 + vertex 0.988447 1.21812 2.6271 + vertex 0.983449 1.21299 2.62711 + endloop + endfacet + facet normal 0.0703199 -0.073546 0.99481 + outer loop + vertex 0.983593 1.2081 2.62673 + vertex 0.988454 1.21311 2.62676 + vertex 0.983449 1.21299 2.62711 + endloop + endfacet + facet normal 0.0624464 -0.0659157 0.995869 + outer loop + vertex 0.988609 1.20834 2.62644 + vertex 0.988454 1.21311 2.62676 + vertex 0.983593 1.2081 2.62673 + endloop + endfacet + facet normal 0.0768684 -0.0653799 0.994895 + outer loop + vertex 0.988609 1.20834 2.62644 + vertex 0.99307 1.21312 2.62641 + vertex 0.988454 1.21311 2.62676 + endloop + endfacet + facet normal 0.0768864 -0.0533019 0.995614 + outer loop + vertex 0.99307 1.21312 2.62641 + vertex 0.993049 1.21797 2.62667 + vertex 0.988454 1.21311 2.62676 + endloop + endfacet + facet normal 0.121366 -0.0528747 0.991199 + outer loop + vertex 0.99307 1.21312 2.62641 + vertex 0.997094 1.21746 2.62614 + vertex 0.993049 1.21797 2.62667 + endloop + endfacet + facet normal 0.122339 -0.0453862 0.99145 + outer loop + vertex 0.997094 1.21746 2.62614 + vertex 0.997272 1.22237 2.62635 + vertex 0.993049 1.21797 2.62667 + endloop + endfacet + facet normal 0.141654 -0.0641962 0.987832 + outer loop + vertex 0.993049 1.21797 2.62667 + vertex 0.997272 1.22237 2.62635 + vertex 0.993178 1.22301 2.62698 + endloop + endfacet + facet normal 0.14225 -0.0605593 0.987977 + outer loop + vertex 0.997272 1.22237 2.62635 + vertex 0.997621 1.22748 2.62661 + vertex 0.993178 1.22301 2.62698 + endloop + endfacet + facet normal 0.159911 -0.0784579 0.984009 + outer loop + vertex 0.993178 1.22301 2.62698 + vertex 0.997621 1.22748 2.62661 + vertex 0.993436 1.22816 2.62734 + endloop + endfacet + facet normal 0.161675 -0.0681366 0.984489 + outer loop + vertex 0.997621 1.22748 2.62661 + vertex 0.998482 1.23318 2.62686 + vertex 0.993436 1.22816 2.62734 + endloop + endfacet + facet normal 0.185445 -0.0926356 0.978279 + outer loop + vertex 0.993436 1.22816 2.62734 + vertex 0.998482 1.23318 2.62686 + vertex 0.993551 1.23324 2.6278 + endloop + endfacet + facet normal 0.18568 -0.0845377 0.978967 + outer loop + vertex 0.998482 1.23318 2.62686 + vertex 0.998057 1.23819 2.62738 + vertex 0.993551 1.23324 2.6278 + endloop + endfacet + facet normal 0.103954 -0.036561 0.99391 + outer loop + vertex 0.996933 1.21302 2.626 + vertex 0.997094 1.21746 2.62614 + vertex 0.99307 1.21312 2.62641 + endloop + endfacet + facet normal 0.103445 -0.0526795 0.993239 + outer loop + vertex 0.996933 1.21302 2.626 + vertex 0.99307 1.21312 2.62641 + vertex 0.993363 1.20856 2.62613 + endloop + endfacet + facet normal 0.0966199 -0.0471894 0.994202 + outer loop + vertex 0.997032 1.20986 2.62584 + vertex 0.996933 1.21302 2.626 + vertex 0.993363 1.20856 2.62613 + endloop + endfacet + facet normal 0.103252 -0.0662339 0.992448 + outer loop + vertex 0.997032 1.20986 2.62584 + vertex 0.993363 1.20856 2.62613 + vertex 0.995408 1.20692 2.62581 + endloop + endfacet + facet normal 0.202902 -0.12104 0.971689 + outer loop + vertex 0.99897 1.20826 2.62523 + vertex 0.997032 1.20986 2.62584 + vertex 0.995408 1.20692 2.62581 + endloop + endfacet + facet normal 0.066025 -0.0552601 0.996287 + outer loop + vertex 0.993363 1.20856 2.62613 + vertex 0.99307 1.21312 2.62641 + vertex 0.988609 1.20834 2.62644 + endloop + endfacet + facet normal 0.0904974 -0.0662071 0.993694 + outer loop + vertex 0.988454 1.21311 2.62676 + vertex 0.993049 1.21797 2.62667 + vertex 0.988447 1.21812 2.6271 + endloop + endfacet + facet normal 0.0641586 -0.0737583 0.99521 + outer loop + vertex 0.983593 1.2081 2.62673 + vertex 0.983449 1.21299 2.62711 + vertex 0.978399 1.20788 2.62705 + endloop + endfacet + facet normal 0.0672949 -0.0730977 0.995052 + outer loop + vertex 0.978322 1.21291 2.62745 + vertex 0.983471 1.21807 2.62748 + vertex 0.978388 1.21801 2.62782 + endloop + endfacet + facet normal 0.0534468 -0.0763473 0.995648 + outer loop + vertex 0.973246 1.20782 2.62737 + vertex 0.973268 1.21293 2.62776 + vertex 0.968229 1.20788 2.62764 + endloop + endfacet + facet normal 0.0528129 -0.0698212 0.996161 + outer loop + vertex 0.968316 1.213 2.62803 + vertex 0.973364 1.21801 2.62811 + vertex 0.968416 1.21806 2.62838 + endloop + endfacet + facet normal 0.0392425 -0.0790208 0.9961 + outer loop + vertex 0.963272 1.20793 2.62787 + vertex 0.963394 1.21305 2.62827 + vertex 0.958288 1.20792 2.62807 + endloop + endfacet + facet normal 0.0469389 -0.0739494 0.996157 + outer loop + vertex 0.95843 1.21307 2.62849 + vertex 0.963491 1.21812 2.62863 + vertex 0.958546 1.21817 2.62887 + endloop + endfacet + facet normal 0.0243148 -0.0864208 0.995962 + outer loop + vertex 0.95324 1.20787 2.62824 + vertex 0.953395 1.21305 2.62868 + vertex 0.948151 1.20781 2.62835 + endloop + endfacet +endsolid diff --git a/noether_examples/meshes/outputsBackDoor/output_6.stl b/noether_examples/meshes/outputsBackDoor/output_6.stl new file mode 100644 index 00000000..4f9888a3 --- /dev/null +++ b/noether_examples/meshes/outputsBackDoor/output_6.stl @@ -0,0 +1,5343 @@ +solid ascii + facet normal 0.36512 -0.0722967 0.928149 + outer loop + vertex 1.01296 1.17758 2.61795 + vertex 1.01384 1.18335 2.61805 + vertex 1.00885 1.17859 2.61965 + endloop + endfacet + facet normal 0.402751 -0.118664 0.907585 + outer loop + vertex 1.00885 1.17859 2.61965 + vertex 1.01384 1.18335 2.61805 + vertex 1.01003 1.18416 2.61985 + endloop + endfacet + facet normal 0.412556 -0.0733909 0.907971 + outer loop + vertex 1.01322 1.18898 2.61879 + vertex 1.01003 1.18416 2.61985 + vertex 1.01384 1.18335 2.61805 + endloop + endfacet + facet normal 0.44628 -0.0675765 0.892338 + outer loop + vertex 1.01696 1.18813 2.61686 + vertex 1.01322 1.18898 2.61879 + vertex 1.01384 1.18335 2.61805 + endloop + endfacet + facet normal 0.430202 -0.0549124 0.901061 + outer loop + vertex 1.01754 1.18482 2.61638 + vertex 1.01696 1.18813 2.61686 + vertex 1.01384 1.18335 2.61805 + endloop + endfacet + facet normal 0.430082 -0.0545174 0.901142 + outer loop + vertex 1.01754 1.18482 2.61638 + vertex 1.01384 1.18335 2.61805 + vertex 1.01691 1.18104 2.61645 + endloop + endfacet + facet normal 0.45868 -0.0479135 0.887309 + outer loop + vertex 1.01963 1.18749 2.61544 + vertex 1.01696 1.18813 2.61686 + vertex 1.01754 1.18482 2.61638 + endloop + endfacet + facet normal 0.460016 -0.0415242 0.886939 + outer loop + vertex 1.0202 1.19141 2.61533 + vertex 1.01696 1.18813 2.61686 + vertex 1.01963 1.18749 2.61544 + endloop + endfacet + facet normal 0.474611 -0.0438552 0.879102 + outer loop + vertex 1.01963 1.18749 2.61544 + vertex 1.02306 1.18905 2.61367 + vertex 1.0202 1.19141 2.61533 + endloop + endfacet + facet normal 0.476566 -0.0408328 0.87819 + outer loop + vertex 1.02306 1.18905 2.61367 + vertex 1.02364 1.19466 2.61362 + vertex 1.0202 1.19141 2.61533 + endloop + endfacet + facet normal 0.48276 -0.0493972 0.874358 + outer loop + vertex 1.0202 1.19141 2.61533 + vertex 1.02364 1.19466 2.61362 + vertex 1.02056 1.19636 2.61541 + endloop + endfacet + facet normal 0.467914 -0.0484364 0.882446 + outer loop + vertex 1.02056 1.19636 2.61541 + vertex 1.01709 1.19294 2.61706 + vertex 1.0202 1.19141 2.61533 + endloop + endfacet + facet normal 0.480778 -0.0538499 0.875187 + outer loop + vertex 1.02364 1.19466 2.61362 + vertex 1.02396 1.19976 2.61375 + vertex 1.02056 1.19636 2.61541 + endloop + endfacet + facet normal 0.486548 -0.0614331 0.871491 + outer loop + vertex 1.02056 1.19636 2.61541 + vertex 1.02396 1.19976 2.61375 + vertex 1.02084 1.20142 2.61561 + endloop + endfacet + facet normal 0.470393 -0.0608806 0.880355 + outer loop + vertex 1.02084 1.20142 2.61561 + vertex 1.01744 1.19809 2.6172 + vertex 1.02056 1.19636 2.61541 + endloop + endfacet + facet normal 0.473009 -0.0550986 0.879333 + outer loop + vertex 1.01744 1.19809 2.6172 + vertex 1.01709 1.19294 2.61706 + vertex 1.02056 1.19636 2.61541 + endloop + endfacet + facet normal 0.458075 -0.0543116 0.887253 + outer loop + vertex 1.01709 1.19294 2.61706 + vertex 1.01744 1.19809 2.6172 + vertex 1.01393 1.19473 2.6188 + endloop + endfacet + facet normal 0.45624 -0.0582387 0.887949 + outer loop + vertex 1.01322 1.18898 2.61879 + vertex 1.01709 1.19294 2.61706 + vertex 1.01393 1.19473 2.6188 + endloop + endfacet + facet normal 0.424061 -0.0542585 0.904007 + outer loop + vertex 1.01322 1.18898 2.61879 + vertex 1.01393 1.19473 2.6188 + vertex 1.0104 1.19157 2.62027 + endloop + endfacet + facet normal 0.419408 -0.0603431 0.90579 + outer loop + vertex 1.00974 1.18766 2.62032 + vertex 1.01322 1.18898 2.61879 + vertex 1.0104 1.19157 2.62027 + endloop + endfacet + facet normal 0.32247 -0.0435707 0.945576 + outer loop + vertex 1.0104 1.19157 2.62027 + vertex 1.00701 1.18814 2.62127 + vertex 1.00974 1.18766 2.62032 + endloop + endfacet + facet normal 0.342962 -0.0662963 0.937007 + outer loop + vertex 1.00705 1.19267 2.62157 + vertex 1.00701 1.18814 2.62127 + vertex 1.0104 1.19157 2.62027 + endloop + endfacet + facet normal 0.347232 -0.052532 0.936307 + outer loop + vertex 1.01075 1.19647 2.62041 + vertex 1.00705 1.19267 2.62157 + vertex 1.0104 1.19157 2.62027 + endloop + endfacet + facet normal 0.363014 -0.0701103 0.929142 + outer loop + vertex 1.00718 1.19759 2.62189 + vertex 1.00705 1.19267 2.62157 + vertex 1.01075 1.19647 2.62041 + endloop + endfacet + facet normal 0.365647 -0.0611969 0.92874 + outer loop + vertex 1.01097 1.20147 2.62066 + vertex 1.00718 1.19759 2.62189 + vertex 1.01075 1.19647 2.62041 + endloop + endfacet + facet normal 0.430836 -0.0626549 0.900253 + outer loop + vertex 1.01075 1.19647 2.62041 + vertex 1.01428 1.1999 2.61896 + vertex 1.01097 1.20147 2.62066 + endloop + endfacet + facet normal 0.429822 -0.0651272 0.900562 + outer loop + vertex 1.01428 1.1999 2.61896 + vertex 1.01452 1.20492 2.61922 + vertex 1.01097 1.20147 2.62066 + endloop + endfacet + facet normal 0.430539 -0.0660333 0.900153 + outer loop + vertex 1.01097 1.20147 2.62066 + vertex 1.01452 1.20492 2.61922 + vertex 1.01114 1.20643 2.62094 + endloop + endfacet + facet normal 0.378187 -0.0655432 0.923406 + outer loop + vertex 1.01114 1.20643 2.62094 + vertex 1.00731 1.20256 2.62223 + vertex 1.01097 1.20147 2.62066 + endloop + endfacet + facet normal 0.382804 -0.0708773 0.921107 + outer loop + vertex 1.00745 1.20755 2.62256 + vertex 1.00731 1.20256 2.62223 + vertex 1.01114 1.20643 2.62094 + endloop + endfacet + facet normal 0.430153 -0.0670247 0.900265 + outer loop + vertex 1.01452 1.20492 2.61922 + vertex 1.01474 1.20988 2.61948 + vertex 1.01114 1.20643 2.62094 + endloop + endfacet + facet normal 0.453395 -0.0674826 0.888751 + outer loop + vertex 1.01452 1.20492 2.61922 + vertex 1.01795 1.20818 2.61771 + vertex 1.01474 1.20988 2.61948 + endloop + endfacet + facet normal 0.456686 -0.0718794 0.88672 + outer loop + vertex 1.01771 1.20317 2.61743 + vertex 1.01795 1.20818 2.61771 + vertex 1.01452 1.20492 2.61922 + endloop + endfacet + facet normal 0.471726 -0.0721427 0.878789 + outer loop + vertex 1.01795 1.20818 2.61771 + vertex 1.01771 1.20317 2.61743 + vertex 1.02107 1.20644 2.61589 + endloop + endfacet + facet normal 0.473744 -0.0677627 0.878051 + outer loop + vertex 1.02128 1.21143 2.61616 + vertex 1.01795 1.20818 2.61771 + vertex 1.02107 1.20644 2.61589 + endloop + endfacet + facet normal 0.48952 -0.0679516 0.869341 + outer loop + vertex 1.02107 1.20644 2.61589 + vertex 1.02437 1.20973 2.61429 + vertex 1.02128 1.21143 2.61616 + endloop + endfacet + facet normal 0.489094 -0.0673888 0.869624 + outer loop + vertex 1.02419 1.20476 2.61401 + vertex 1.02437 1.20973 2.61429 + vertex 1.02107 1.20644 2.61589 + endloop + endfacet + facet normal 0.487389 -0.0712858 0.87027 + outer loop + vertex 1.02084 1.20142 2.61561 + vertex 1.02419 1.20476 2.61401 + vertex 1.02107 1.20644 2.61589 + endloop + endfacet + facet normal 0.470894 -0.0710324 0.879325 + outer loop + vertex 1.02107 1.20644 2.61589 + vertex 1.01771 1.20317 2.61743 + vertex 1.02084 1.20142 2.61561 + endloop + endfacet + facet normal 0.459499 -0.0657578 0.885741 + outer loop + vertex 1.01428 1.1999 2.61896 + vertex 1.01771 1.20317 2.61743 + vertex 1.01452 1.20492 2.61922 + endloop + endfacet + facet normal 0.458712 -0.0647094 0.886226 + outer loop + vertex 1.01744 1.19809 2.6172 + vertex 1.01771 1.20317 2.61743 + vertex 1.01428 1.1999 2.61896 + endloop + endfacet + facet normal 0.426367 -0.0569912 0.902753 + outer loop + vertex 1.01393 1.19473 2.6188 + vertex 1.01428 1.1999 2.61896 + vertex 1.01075 1.19647 2.62041 + endloop + endfacet + facet normal 0.376087 -0.0729975 0.923704 + outer loop + vertex 1.00731 1.20256 2.62223 + vertex 1.00718 1.19759 2.62189 + vertex 1.01097 1.20147 2.62066 + endloop + endfacet + facet normal 0.426241 -0.0572607 0.902796 + outer loop + vertex 1.0104 1.19157 2.62027 + vertex 1.01393 1.19473 2.6188 + vertex 1.01075 1.19647 2.62041 + endloop + endfacet + facet normal 0.461487 -0.0588451 0.885193 + outer loop + vertex 1.01393 1.19473 2.6188 + vertex 1.01744 1.19809 2.6172 + vertex 1.01428 1.1999 2.61896 + endloop + endfacet + facet normal 0.473608 -0.0651457 0.878323 + outer loop + vertex 1.01771 1.20317 2.61743 + vertex 1.01744 1.19809 2.6172 + vertex 1.02084 1.20142 2.61561 + endloop + endfacet + facet normal 0.484142 -0.0670037 0.87242 + outer loop + vertex 1.02396 1.19976 2.61375 + vertex 1.02419 1.20476 2.61401 + vertex 1.02084 1.20142 2.61561 + endloop + endfacet + facet normal 0.474331 -0.0430237 0.879295 + outer loop + vertex 1.01963 1.18749 2.61544 + vertex 1.02023 1.1843 2.61496 + vertex 1.02306 1.18905 2.61367 + endloop + endfacet + facet normal 0.47097 -0.0404992 0.881219 + outer loop + vertex 1.02306 1.18905 2.61367 + vertex 1.02023 1.1843 2.61496 + vertex 1.02396 1.18382 2.61295 + endloop + endfacet + facet normal 0.469878 -0.0493534 0.88135 + outer loop + vertex 1.02015 1.17979 2.61475 + vertex 1.02396 1.18382 2.61295 + vertex 1.02023 1.1843 2.61496 + endloop + endfacet + facet normal 0.465832 -0.0444473 0.883756 + outer loop + vertex 1.02335 1.17828 2.61299 + vertex 1.02396 1.18382 2.61295 + vertex 1.02015 1.17979 2.61475 + endloop + endfacet + facet normal 0.461925 -0.0544714 0.885245 + outer loop + vertex 1.01984 1.1749 2.61461 + vertex 1.02335 1.17828 2.61299 + vertex 1.02015 1.17979 2.61475 + endloop + endfacet + facet normal 0.43521 -0.0531945 0.898756 + outer loop + vertex 1.01984 1.1749 2.61461 + vertex 1.02015 1.17979 2.61475 + vertex 1.0165 1.1763 2.61631 + endloop + endfacet + facet normal 0.430078 -0.067287 0.900281 + outer loop + vertex 1.01625 1.17144 2.61607 + vertex 1.01984 1.1749 2.61461 + vertex 1.0165 1.1763 2.61631 + endloop + endfacet + facet normal 0.378932 -0.0657228 0.923088 + outer loop + vertex 1.0165 1.1763 2.61631 + vertex 1.01261 1.17254 2.61764 + vertex 1.01625 1.17144 2.61607 + endloop + endfacet + facet normal 0.372398 -0.0884654 0.923847 + outer loop + vertex 1.01261 1.17254 2.61764 + vertex 1.01239 1.1676 2.61726 + vertex 1.01625 1.17144 2.61607 + endloop + endfacet + facet normal 0.355917 -0.0694312 0.931935 + outer loop + vertex 1.01625 1.17144 2.61607 + vertex 1.01239 1.1676 2.61726 + vertex 1.01602 1.1665 2.61579 + endloop + endfacet + facet normal 0.418834 -0.0707246 0.905304 + outer loop + vertex 1.01602 1.1665 2.61579 + vertex 1.0196 1.16995 2.6144 + vertex 1.01625 1.17144 2.61607 + endloop + endfacet + facet normal 0.412899 -0.0632454 0.908578 + outer loop + vertex 1.01926 1.1648 2.6142 + vertex 1.0196 1.16995 2.6144 + vertex 1.01602 1.1665 2.61579 + endloop + endfacet + facet normal 0.408022 -0.0738523 0.90998 + outer loop + vertex 1.01566 1.16159 2.61555 + vertex 1.01926 1.1648 2.6142 + vertex 1.01602 1.1665 2.61579 + endloop + endfacet + facet normal 0.332776 -0.0697074 0.940426 + outer loop + vertex 1.01602 1.1665 2.61579 + vertex 1.01224 1.16268 2.61684 + vertex 1.01566 1.16159 2.61555 + endloop + endfacet + facet normal 0.327357 -0.0871728 0.940871 + outer loop + vertex 1.01224 1.16268 2.61684 + vertex 1.01218 1.15811 2.61644 + vertex 1.01566 1.16159 2.61555 + endloop + endfacet + facet normal 0.306382 -0.0639539 0.949758 + outer loop + vertex 1.01566 1.16159 2.61555 + vertex 1.01218 1.15811 2.61644 + vertex 1.01495 1.15764 2.61552 + endloop + endfacet + facet normal 0.395952 -0.0798373 0.914794 + outer loop + vertex 1.01495 1.15764 2.61552 + vertex 1.01843 1.159 2.61413 + vertex 1.01566 1.16159 2.61555 + endloop + endfacet + facet normal 0.402809 -0.102728 0.909501 + outer loop + vertex 1.01495 1.15764 2.61552 + vertex 1.01509 1.15419 2.61506 + vertex 1.01843 1.159 2.61413 + endloop + endfacet + facet normal 0.385225 -0.0887889 0.918541 + outer loop + vertex 1.01843 1.159 2.61413 + vertex 1.01509 1.15419 2.61506 + vertex 1.01843 1.15351 2.6136 + endloop + endfacet + facet normal 0.424042 -0.087125 0.901442 + outer loop + vertex 1.01843 1.15351 2.6136 + vertex 1.02224 1.15773 2.61221 + vertex 1.01843 1.159 2.61413 + endloop + endfacet + facet normal 0.430916 -0.0644031 0.900091 + outer loop + vertex 1.02224 1.15773 2.61221 + vertex 1.02251 1.163 2.61246 + vertex 1.01843 1.159 2.61413 + endloop + endfacet + facet normal 0.438344 -0.0737793 0.895774 + outer loop + vertex 1.01843 1.159 2.61413 + vertex 1.02251 1.163 2.61246 + vertex 1.01926 1.1648 2.6142 + endloop + endfacet + facet normal 0.444874 -0.059909 0.893587 + outer loop + vertex 1.02251 1.163 2.61246 + vertex 1.02281 1.16821 2.61266 + vertex 1.01926 1.1648 2.6142 + endloop + endfacet + facet normal 0.406354 -0.0679644 0.911185 + outer loop + vertex 1.02205 1.15269 2.61192 + vertex 1.02224 1.15773 2.61221 + vertex 1.01843 1.15351 2.6136 + endloop + endfacet + facet normal 0.400113 -0.0959979 0.911424 + outer loop + vertex 1.0182 1.14836 2.61316 + vertex 1.02205 1.15269 2.61192 + vertex 1.01843 1.15351 2.6136 + endloop + endfacet + facet normal 0.374067 -0.0690085 0.924831 + outer loop + vertex 1.02195 1.14819 2.61163 + vertex 1.02205 1.15269 2.61192 + vertex 1.0182 1.14836 2.61316 + endloop + endfacet + facet normal 0.443659 -0.068387 0.893583 + outer loop + vertex 1.02224 1.15773 2.61221 + vertex 1.02205 1.15269 2.61192 + vertex 1.02562 1.15644 2.61044 + endloop + endfacet + facet normal 0.447588 -0.0565804 0.892448 + outer loop + vertex 1.02585 1.16147 2.61064 + vertex 1.02224 1.15773 2.61221 + vertex 1.02562 1.15644 2.61044 + endloop + endfacet + facet normal 0.470693 -0.0571351 0.880445 + outer loop + vertex 1.02562 1.15644 2.61044 + vertex 1.02906 1.15994 2.60883 + vertex 1.02585 1.16147 2.61064 + endloop + endfacet + facet normal 0.474015 -0.0486195 0.879173 + outer loop + vertex 1.02906 1.15994 2.60883 + vertex 1.02921 1.1649 2.60902 + vertex 1.02585 1.16147 2.61064 + endloop + endfacet + facet normal 0.478652 -0.0545032 0.876311 + outer loop + vertex 1.02585 1.16147 2.61064 + vertex 1.02921 1.1649 2.60902 + vertex 1.02602 1.16651 2.61086 + endloop + endfacet + facet normal 0.458709 -0.0543143 0.886925 + outer loop + vertex 1.02602 1.16651 2.61086 + vertex 1.02251 1.163 2.61246 + vertex 1.02585 1.16147 2.61064 + endloop + endfacet + facet normal 0.463648 -0.0606088 0.883944 + outer loop + vertex 1.02281 1.16821 2.61266 + vertex 1.02251 1.163 2.61246 + vertex 1.02602 1.16651 2.61086 + endloop + endfacet + facet normal 0.467944 -0.0507407 0.8823 + outer loop + vertex 1.02617 1.17151 2.61107 + vertex 1.02281 1.16821 2.61266 + vertex 1.02602 1.16651 2.61086 + endloop + endfacet + facet normal 0.486937 -0.0508883 0.871954 + outer loop + vertex 1.02602 1.16651 2.61086 + vertex 1.02931 1.16984 2.60922 + vertex 1.02617 1.17151 2.61107 + endloop + endfacet + facet normal 0.49069 -0.0420259 0.87032 + outer loop + vertex 1.02931 1.16984 2.60922 + vertex 1.02942 1.17479 2.6094 + vertex 1.02617 1.17151 2.61107 + endloop + endfacet + facet normal 0.496021 -0.0490553 0.866924 + outer loop + vertex 1.02617 1.17151 2.61107 + vertex 1.02942 1.17479 2.6094 + vertex 1.02637 1.17648 2.61123 + endloop + endfacet + facet normal 0.475555 -0.0485794 0.878343 + outer loop + vertex 1.02637 1.17648 2.61123 + vertex 1.02303 1.17325 2.61286 + vertex 1.02617 1.17151 2.61107 + endloop + endfacet + facet normal 0.478246 -0.0521932 0.876673 + outer loop + vertex 1.02335 1.17828 2.61299 + vertex 1.02303 1.17325 2.61286 + vertex 1.02637 1.17648 2.61123 + endloop + endfacet + facet normal 0.481281 -0.0458049 0.875369 + outer loop + vertex 1.02671 1.18135 2.6113 + vertex 1.02335 1.17828 2.61299 + vertex 1.02637 1.17648 2.61123 + endloop + endfacet + facet normal 0.505033 -0.0472671 0.861805 + outer loop + vertex 1.02637 1.17648 2.61123 + vertex 1.02957 1.17971 2.60954 + vertex 1.02671 1.18135 2.6113 + endloop + endfacet + facet normal 0.508661 -0.0390865 0.860079 + outer loop + vertex 1.02957 1.17971 2.60954 + vertex 1.02963 1.18434 2.60971 + vertex 1.02671 1.18135 2.6113 + endloop + endfacet + facet normal 0.513475 -0.0454729 0.856899 + outer loop + vertex 1.02963 1.18434 2.60971 + vertex 1.02728 1.18523 2.61117 + vertex 1.02671 1.18135 2.6113 + endloop + endfacet + facet normal 0.485355 -0.0407914 0.873365 + outer loop + vertex 1.02728 1.18523 2.61117 + vertex 1.02396 1.18382 2.61295 + vertex 1.02671 1.18135 2.6113 + endloop + endfacet + facet normal 0.4829 -0.0329015 0.875057 + outer loop + vertex 1.02728 1.18523 2.61117 + vertex 1.0267 1.18849 2.61161 + vertex 1.02396 1.18382 2.61295 + endloop + endfacet + facet normal 0.487582 -0.036429 0.872317 + outer loop + vertex 1.0267 1.18849 2.61161 + vertex 1.02306 1.18905 2.61367 + vertex 1.02396 1.18382 2.61295 + endloop + endfacet + facet normal 0.488156 -0.0321245 0.872165 + outer loop + vertex 1.0267 1.18849 2.61161 + vertex 1.02674 1.19311 2.61176 + vertex 1.02306 1.18905 2.61367 + endloop + endfacet + facet normal 0.497296 -0.0430841 0.86651 + outer loop + vertex 1.02306 1.18905 2.61367 + vertex 1.02674 1.19311 2.61176 + vertex 1.02364 1.19466 2.61362 + endloop + endfacet + facet normal 0.50832 -0.0264107 0.860763 + outer loop + vertex 1.02916 1.18772 2.61014 + vertex 1.0267 1.18849 2.61161 + vertex 1.02728 1.18523 2.61117 + endloop + endfacet + facet normal 0.509175 -0.0229454 0.860357 + outer loop + vertex 1.02966 1.19145 2.60994 + vertex 1.0267 1.18849 2.61161 + vertex 1.02916 1.18772 2.61014 + endloop + endfacet + facet normal 0.526818 -0.0259145 0.849583 + outer loop + vertex 1.02916 1.18772 2.61014 + vertex 1.03227 1.18846 2.60823 + vertex 1.02966 1.19145 2.60994 + endloop + endfacet + facet normal 0.520048 -0.0340225 0.853459 + outer loop + vertex 1.03227 1.18846 2.60823 + vertex 1.03291 1.19396 2.60805 + vertex 1.02966 1.19145 2.60994 + endloop + endfacet + facet normal 0.522622 -0.0386974 0.851686 + outer loop + vertex 1.02966 1.19145 2.60994 + vertex 1.03291 1.19396 2.60805 + vertex 1.03004 1.19626 2.60992 + endloop + endfacet + facet normal 0.513092 -0.0379409 0.857495 + outer loop + vertex 1.03004 1.19626 2.60992 + vertex 1.02674 1.19311 2.61176 + vertex 1.02966 1.19145 2.60994 + endloop + endfacet + facet normal 0.519443 -0.0470919 0.853207 + outer loop + vertex 1.02705 1.19812 2.61185 + vertex 1.02674 1.19311 2.61176 + vertex 1.03004 1.19626 2.60992 + endloop + endfacet + facet normal 0.513112 -0.0603526 0.856197 + outer loop + vertex 1.03045 1.20128 2.61003 + vertex 1.02705 1.19812 2.61185 + vertex 1.03004 1.19626 2.60992 + endloop + endfacet + facet normal 0.514857 -0.0604739 0.85514 + outer loop + vertex 1.03004 1.19626 2.60992 + vertex 1.03341 1.19899 2.60809 + vertex 1.03045 1.20128 2.61003 + endloop + endfacet + facet normal 0.503659 -0.0793032 0.860255 + outer loop + vertex 1.03341 1.19899 2.60809 + vertex 1.03426 1.2044 2.60809 + vertex 1.03045 1.20128 2.61003 + endloop + endfacet + facet normal 0.514898 -0.0629974 0.854934 + outer loop + vertex 1.02732 1.20311 2.61205 + vertex 1.02705 1.19812 2.61185 + vertex 1.03045 1.20128 2.61003 + endloop + endfacet + facet normal 0.496191 -0.0458799 0.867 + outer loop + vertex 1.02674 1.19311 2.61176 + vertex 1.02705 1.19812 2.61185 + vertex 1.02364 1.19466 2.61362 + endloop + endfacet + facet normal 0.50303 -0.0549331 0.862521 + outer loop + vertex 1.02364 1.19466 2.61362 + vertex 1.02705 1.19812 2.61185 + vertex 1.02396 1.19976 2.61375 + endloop + endfacet + facet normal 0.499807 -0.0625563 0.863875 + outer loop + vertex 1.02705 1.19812 2.61185 + vertex 1.02732 1.20311 2.61205 + vertex 1.02396 1.19976 2.61375 + endloop + endfacet + facet normal 0.503336 -0.067316 0.861465 + outer loop + vertex 1.02396 1.19976 2.61375 + vertex 1.02732 1.20311 2.61205 + vertex 1.02419 1.20476 2.61401 + endloop + endfacet + facet normal 0.512248 -0.0560046 0.857009 + outer loop + vertex 1.03291 1.19396 2.60805 + vertex 1.03341 1.19899 2.60809 + vertex 1.03004 1.19626 2.60992 + endloop + endfacet + facet normal 0.527853 -0.0324544 0.848715 + outer loop + vertex 1.02916 1.18772 2.61014 + vertex 1.02963 1.18434 2.60971 + vertex 1.03227 1.18846 2.60823 + endloop + endfacet + facet normal 0.526164 -0.0309751 0.849819 + outer loop + vertex 1.03227 1.18846 2.60823 + vertex 1.02963 1.18434 2.60971 + vertex 1.03264 1.18312 2.60781 + endloop + endfacet + facet normal 0.507358 -0.0331589 0.861097 + outer loop + vertex 1.03227 1.18846 2.60823 + vertex 1.03264 1.18312 2.60781 + vertex 1.03594 1.18657 2.60599 + endloop + endfacet + facet normal 0.504895 -0.0393478 0.862283 + outer loop + vertex 1.03605 1.19168 2.60616 + vertex 1.03227 1.18846 2.60823 + vertex 1.03594 1.18657 2.60599 + endloop + endfacet + facet normal 0.448921 -0.0391264 0.892714 + outer loop + vertex 1.03594 1.18657 2.60599 + vertex 1.03961 1.18997 2.6043 + vertex 1.03605 1.19168 2.60616 + endloop + endfacet + facet normal 0.438409 -0.0650925 0.896415 + outer loop + vertex 1.03961 1.18997 2.6043 + vertex 1.03979 1.19486 2.60456 + vertex 1.03605 1.19168 2.60616 + endloop + endfacet + facet normal 0.428368 -0.0503675 0.902199 + outer loop + vertex 1.03605 1.19168 2.60616 + vertex 1.03979 1.19486 2.60456 + vertex 1.03637 1.19665 2.60629 + endloop + endfacet + facet normal 0.487353 -0.0534007 0.87157 + outer loop + vertex 1.03637 1.19665 2.60629 + vertex 1.03291 1.19396 2.60805 + vertex 1.03605 1.19168 2.60616 + endloop + endfacet + facet normal 0.416972 -0.0756669 0.905764 + outer loop + vertex 1.03979 1.19486 2.60456 + vertex 1.04 1.19962 2.60487 + vertex 1.03637 1.19665 2.60629 + endloop + endfacet + facet normal 0.412651 -0.0692001 0.908257 + outer loop + vertex 1.03637 1.19665 2.60629 + vertex 1.04 1.19962 2.60487 + vertex 1.03682 1.20133 2.60644 + endloop + endfacet + facet normal 0.460001 -0.054327 0.886255 + outer loop + vertex 1.03952 1.18501 2.60404 + vertex 1.03961 1.18997 2.6043 + vertex 1.03594 1.18657 2.60599 + endloop + endfacet + facet normal 0.46599 -0.0377698 0.883983 + outer loop + vertex 1.03592 1.18148 2.60579 + vertex 1.03952 1.18501 2.60404 + vertex 1.03594 1.18657 2.60599 + endloop + endfacet + facet normal 0.480743 -0.0573255 0.874986 + outer loop + vertex 1.03929 1.17989 2.60383 + vertex 1.03952 1.18501 2.60404 + vertex 1.03592 1.18148 2.60579 + endloop + endfacet + facet normal 0.487719 -0.0390174 0.872128 + outer loop + vertex 1.0358 1.17643 2.60563 + vertex 1.03929 1.17989 2.60383 + vertex 1.03592 1.18148 2.60579 + endloop + endfacet + facet normal 0.515755 -0.0391313 0.855842 + outer loop + vertex 1.03592 1.18148 2.60579 + vertex 1.03262 1.1781 2.60762 + vertex 1.0358 1.17643 2.60563 + endloop + endfacet + facet normal 0.517139 -0.0356704 0.855158 + outer loop + vertex 1.03262 1.1781 2.60762 + vertex 1.03253 1.17312 2.60746 + vertex 1.0358 1.17643 2.60563 + endloop + endfacet + facet normal 0.520905 -0.0407841 0.85264 + outer loop + vertex 1.0358 1.17643 2.60563 + vertex 1.03253 1.17312 2.60746 + vertex 1.03572 1.17137 2.60543 + endloop + endfacet + facet normal 0.510395 -0.0408515 0.858969 + outer loop + vertex 1.03572 1.17137 2.60543 + vertex 1.03901 1.17475 2.60364 + vertex 1.0358 1.17643 2.60563 + endloop + endfacet + facet normal 0.519263 -0.0526435 0.852992 + outer loop + vertex 1.03919 1.16941 2.6032 + vertex 1.03901 1.17475 2.60364 + vertex 1.03572 1.17137 2.60543 + endloop + endfacet + facet normal 0.525278 -0.0386486 0.850052 + outer loop + vertex 1.03558 1.1663 2.60529 + vertex 1.03919 1.16941 2.6032 + vertex 1.03572 1.17137 2.60543 + endloop + endfacet + facet normal 0.522404 -0.0386188 0.851823 + outer loop + vertex 1.03572 1.17137 2.60543 + vertex 1.03245 1.16817 2.60729 + vertex 1.03558 1.1663 2.60529 + endloop + endfacet + facet normal 0.521557 -0.0404988 0.852255 + outer loop + vertex 1.03245 1.16817 2.60729 + vertex 1.03233 1.16323 2.60713 + vertex 1.03558 1.1663 2.60529 + endloop + endfacet + facet normal 0.519397 -0.0373349 0.853717 + outer loop + vertex 1.03558 1.1663 2.60529 + vertex 1.03233 1.16323 2.60713 + vertex 1.03535 1.1613 2.60521 + endloop + endfacet + facet normal 0.528807 -0.0376761 0.847906 + outer loop + vertex 1.03535 1.1613 2.60521 + vertex 1.03855 1.16402 2.60334 + vertex 1.03558 1.1663 2.60529 + endloop + endfacet + facet normal 0.527333 -0.0352305 0.848928 + outer loop + vertex 1.0383 1.1591 2.60329 + vertex 1.03855 1.16402 2.60334 + vertex 1.03535 1.1613 2.60521 + endloop + endfacet + facet normal 0.525131 -0.0392055 0.850118 + outer loop + vertex 1.03512 1.15638 2.60513 + vertex 1.0383 1.1591 2.60329 + vertex 1.03535 1.1613 2.60521 + endloop + endfacet + facet normal 0.512344 -0.0387434 0.857906 + outer loop + vertex 1.03535 1.1613 2.60521 + vertex 1.03214 1.15828 2.60699 + vertex 1.03512 1.15638 2.60513 + endloop + endfacet + facet normal 0.507729 -0.048196 0.860168 + outer loop + vertex 1.03214 1.15828 2.60699 + vertex 1.03185 1.15329 2.60688 + vertex 1.03512 1.15638 2.60513 + endloop + endfacet + facet normal 0.501679 -0.0395215 0.864151 + outer loop + vertex 1.03512 1.15638 2.60513 + vertex 1.03185 1.15329 2.60688 + vertex 1.0348 1.15158 2.6051 + endloop + endfacet + facet normal 0.519296 -0.0406458 0.853627 + outer loop + vertex 1.0348 1.15158 2.6051 + vertex 1.03804 1.15411 2.60324 + vertex 1.03512 1.15638 2.60513 + endloop + endfacet + facet normal 0.517155 -0.0368237 0.855099 + outer loop + vertex 1.03743 1.14859 2.60337 + vertex 1.03804 1.15411 2.60324 + vertex 1.0348 1.15158 2.6051 + endloop + endfacet + facet normal 0.512766 -0.0420794 0.857497 + outer loop + vertex 1.03425 1.14782 2.60524 + vertex 1.03743 1.14859 2.60337 + vertex 1.0348 1.15158 2.6051 + endloop + endfacet + facet normal 0.513349 -0.0458051 0.856957 + outer loop + vertex 1.03425 1.14782 2.60524 + vertex 1.03472 1.14446 2.60478 + vertex 1.03743 1.14859 2.60337 + endloop + endfacet + facet normal 0.508124 -0.041236 0.860296 + outer loop + vertex 1.03743 1.14859 2.60337 + vertex 1.03472 1.14446 2.60478 + vertex 1.03779 1.14326 2.60291 + endloop + endfacet + facet normal 0.505206 -0.0506173 0.861513 + outer loop + vertex 1.03465 1.13987 2.60455 + vertex 1.03779 1.14326 2.60291 + vertex 1.03472 1.14446 2.60478 + endloop + endfacet + facet normal 0.482175 -0.0509331 0.874593 + outer loop + vertex 1.03465 1.13987 2.60455 + vertex 1.03472 1.14446 2.60478 + vertex 1.03171 1.1415 2.60626 + endloop + endfacet + facet normal 0.477246 -0.0619247 0.876585 + outer loop + vertex 1.03131 1.13658 2.60613 + vertex 1.03465 1.13987 2.60455 + vertex 1.03171 1.1415 2.60626 + endloop + endfacet + facet normal 0.457143 -0.060614 0.887325 + outer loop + vertex 1.03171 1.1415 2.60626 + vertex 1.0282 1.13838 2.60786 + vertex 1.03131 1.13658 2.60613 + endloop + endfacet + facet normal 0.450758 -0.0738251 0.889588 + outer loop + vertex 1.0282 1.13838 2.60786 + vertex 1.02766 1.13306 2.60769 + vertex 1.03131 1.13658 2.60613 + endloop + endfacet + facet normal 0.444095 -0.0651313 0.893609 + outer loop + vertex 1.03131 1.13658 2.60613 + vertex 1.02766 1.13306 2.60769 + vertex 1.03102 1.1315 2.60591 + endloop + endfacet + facet normal 0.466757 -0.0659346 0.881924 + outer loop + vertex 1.03102 1.1315 2.60591 + vertex 1.03448 1.13494 2.60433 + vertex 1.03131 1.13658 2.60613 + endloop + endfacet + facet normal 0.461458 -0.0590991 0.885191 + outer loop + vertex 1.03426 1.12993 2.60411 + vertex 1.03448 1.13494 2.60433 + vertex 1.03102 1.1315 2.60591 + endloop + endfacet + facet normal 0.457011 -0.0700116 0.886701 + outer loop + vertex 1.03075 1.12647 2.60565 + vertex 1.03426 1.12993 2.60411 + vertex 1.03102 1.1315 2.60591 + endloop + endfacet + facet normal 0.428793 -0.0691957 0.900749 + outer loop + vertex 1.03102 1.1315 2.60591 + vertex 1.0273 1.12778 2.60739 + vertex 1.03075 1.12647 2.60565 + endloop + endfacet + facet normal 0.422825 -0.0865544 0.902069 + outer loop + vertex 1.0273 1.12778 2.60739 + vertex 1.02709 1.12275 2.60701 + vertex 1.03075 1.12647 2.60565 + endloop + endfacet + facet normal 0.409157 -0.0703015 0.909752 + outer loop + vertex 1.03075 1.12647 2.60565 + vertex 1.02709 1.12275 2.60701 + vertex 1.03036 1.12164 2.60545 + endloop + endfacet + facet normal 0.447244 -0.0725601 0.891464 + outer loop + vertex 1.03036 1.12164 2.60545 + vertex 1.03392 1.12485 2.60393 + vertex 1.03075 1.12647 2.60565 + endloop + endfacet + facet normal 0.44181 -0.0649868 0.894752 + outer loop + vertex 1.03317 1.11927 2.60389 + vertex 1.03392 1.12485 2.60393 + vertex 1.03036 1.12164 2.60545 + endloop + endfacet + facet normal 0.469511 -0.06863 0.880255 + outer loop + vertex 1.03317 1.11927 2.60389 + vertex 1.03709 1.12312 2.6021 + vertex 1.03392 1.12485 2.60393 + endloop + endfacet + facet normal 0.474648 -0.0571852 0.878316 + outer loop + vertex 1.03709 1.12312 2.6021 + vertex 1.03743 1.12825 2.60225 + vertex 1.03392 1.12485 2.60393 + endloop + endfacet + facet normal 0.479896 -0.0642482 0.87497 + outer loop + vertex 1.03392 1.12485 2.60393 + vertex 1.03743 1.12825 2.60225 + vertex 1.03426 1.12993 2.60411 + endloop + endfacet + facet normal 0.483945 -0.0548408 0.873378 + outer loop + vertex 1.03743 1.12825 2.60225 + vertex 1.03764 1.13329 2.60245 + vertex 1.03426 1.12993 2.60411 + endloop + endfacet + facet normal 0.46044 -0.0567505 0.885875 + outer loop + vertex 1.03687 1.11808 2.60189 + vertex 1.03709 1.12312 2.6021 + vertex 1.03317 1.11927 2.60389 + endloop + endfacet + facet normal 0.456906 -0.0693199 0.88681 + outer loop + vertex 1.03353 1.11415 2.60331 + vertex 1.03687 1.11808 2.60189 + vertex 1.03317 1.11927 2.60389 + endloop + endfacet + facet normal 0.429931 -0.0727136 0.899929 + outer loop + vertex 1.03317 1.11927 2.60389 + vertex 1.03017 1.11467 2.60495 + vertex 1.03353 1.11415 2.60331 + endloop + endfacet + facet normal 0.426587 -0.0931393 0.899638 + outer loop + vertex 1.0299 1.10998 2.6046 + vertex 1.03353 1.11415 2.60331 + vertex 1.03017 1.11467 2.60495 + endloop + endfacet + facet normal 0.377282 -0.0918837 0.921529 + outer loop + vertex 1.0299 1.10998 2.6046 + vertex 1.03017 1.11467 2.60495 + vertex 1.02672 1.11125 2.60602 + endloop + endfacet + facet normal 0.371144 -0.107976 0.922276 + outer loop + vertex 1.02596 1.10645 2.60577 + vertex 1.0299 1.10998 2.6046 + vertex 1.02672 1.11125 2.60602 + endloop + endfacet + facet normal 0.28304 -0.0956054 0.954331 + outer loop + vertex 1.02672 1.11125 2.60602 + vertex 1.02264 1.10762 2.60687 + vertex 1.02596 1.10645 2.60577 + endloop + endfacet + facet normal 0.276103 -0.115256 0.954192 + outer loop + vertex 1.02264 1.10762 2.60687 + vertex 1.02223 1.10309 2.60644 + vertex 1.02596 1.10645 2.60577 + endloop + endfacet + facet normal 0.265168 -0.102219 0.958769 + outer loop + vertex 1.02596 1.10645 2.60577 + vertex 1.02223 1.10309 2.60644 + vertex 1.02478 1.10242 2.60566 + endloop + endfacet + facet normal 0.353653 -0.127148 0.926695 + outer loop + vertex 1.02478 1.10242 2.60566 + vertex 1.02865 1.104 2.6044 + vertex 1.02596 1.10645 2.60577 + endloop + endfacet + facet normal 0.369589 -0.178089 0.91197 + outer loop + vertex 1.02478 1.10242 2.60566 + vertex 1.02409 1.0984 2.60516 + vertex 1.02865 1.104 2.6044 + endloop + endfacet + facet normal 0.297038 -0.169004 0.93979 + outer loop + vertex 1.02478 1.10242 2.60566 + vertex 1.02221 1.09996 2.60604 + vertex 1.02409 1.0984 2.60516 + endloop + endfacet + facet normal 0.258597 -0.126123 0.957716 + outer loop + vertex 1.02478 1.10242 2.60566 + vertex 1.02223 1.10309 2.60644 + vertex 1.02221 1.09996 2.60604 + endloop + endfacet + facet normal 0.299639 -0.115981 0.946977 + outer loop + vertex 1.02353 1.11326 2.60728 + vertex 1.02264 1.10762 2.60687 + vertex 1.02672 1.11125 2.60602 + endloop + endfacet + facet normal 0.313795 -0.0922517 0.944998 + outer loop + vertex 1.02752 1.11513 2.60614 + vertex 1.02353 1.11326 2.60728 + vertex 1.02672 1.11125 2.60602 + endloop + endfacet + facet normal 0.314579 -0.0942085 0.944545 + outer loop + vertex 1.02752 1.11513 2.60614 + vertex 1.027 1.11824 2.60662 + vertex 1.02353 1.11326 2.60728 + endloop + endfacet + facet normal 0.338479 -0.112199 0.934261 + outer loop + vertex 1.027 1.11824 2.60662 + vertex 1.02313 1.11845 2.60805 + vertex 1.02353 1.11326 2.60728 + endloop + endfacet + facet normal 0.340536 -0.0870708 0.936191 + outer loop + vertex 1.027 1.11824 2.60662 + vertex 1.02709 1.12275 2.60701 + vertex 1.02313 1.11845 2.60805 + endloop + endfacet + facet normal 0.370917 -0.118703 0.921048 + outer loop + vertex 1.02313 1.11845 2.60805 + vertex 1.02709 1.12275 2.60701 + vertex 1.02336 1.1236 2.60862 + endloop + endfacet + facet normal 0.404149 -0.0862026 0.910622 + outer loop + vertex 1.02709 1.12275 2.60701 + vertex 1.027 1.11824 2.60662 + vertex 1.03036 1.12164 2.60545 + endloop + endfacet + facet normal 0.385705 -0.0645446 0.920362 + outer loop + vertex 1.03036 1.12164 2.60545 + vertex 1.027 1.11824 2.60662 + vertex 1.02973 1.11786 2.60545 + endloop + endfacet + facet normal 0.4362 -0.0730309 0.896881 + outer loop + vertex 1.02973 1.11786 2.60545 + vertex 1.03317 1.11927 2.60389 + vertex 1.03036 1.12164 2.60545 + endloop + endfacet + facet normal 0.383586 -0.0787934 0.920138 + outer loop + vertex 1.02973 1.11786 2.60545 + vertex 1.027 1.11824 2.60662 + vertex 1.02752 1.11513 2.60614 + endloop + endfacet + facet normal 0.393701 -0.0882479 0.914993 + outer loop + vertex 1.02973 1.11786 2.60545 + vertex 1.02752 1.11513 2.60614 + vertex 1.03017 1.11467 2.60495 + endloop + endfacet + facet normal 0.370232 -0.106788 0.922781 + outer loop + vertex 1.02865 1.104 2.6044 + vertex 1.0299 1.10998 2.6046 + vertex 1.02596 1.10645 2.60577 + endloop + endfacet + facet normal 0.408024 -0.114097 0.905813 + outer loop + vertex 1.02865 1.104 2.6044 + vertex 1.03377 1.10887 2.60271 + vertex 1.0299 1.10998 2.6046 + endloop + endfacet + facet normal 0.387647 -0.0886163 0.917539 + outer loop + vertex 1.03276 1.10292 2.60257 + vertex 1.03377 1.10887 2.60271 + vertex 1.02865 1.104 2.6044 + endloop + endfacet + facet normal 0.377323 -0.127508 0.917262 + outer loop + vertex 1.02842 1.09836 2.60372 + vertex 1.03276 1.10292 2.60257 + vertex 1.02865 1.104 2.6044 + endloop + endfacet + facet normal 0.349635 -0.0974631 0.931803 + outer loop + vertex 1.03231 1.09772 2.60219 + vertex 1.03276 1.10292 2.60257 + vertex 1.02842 1.09836 2.60372 + endloop + endfacet + facet normal 0.343612 -0.129918 0.930082 + outer loop + vertex 1.02822 1.09324 2.60308 + vertex 1.03231 1.09772 2.60219 + vertex 1.02842 1.09836 2.60372 + endloop + endfacet + facet normal 0.313786 -0.0999064 0.944223 + outer loop + vertex 1.03213 1.09311 2.60176 + vertex 1.03231 1.09772 2.60219 + vertex 1.02822 1.09324 2.60308 + endloop + endfacet + facet normal 0.31213 -0.125274 0.941744 + outer loop + vertex 1.03213 1.09311 2.60176 + vertex 1.02822 1.09324 2.60308 + vertex 1.02856 1.08811 2.60228 + endloop + endfacet + facet normal 0.288663 -0.107534 0.951373 + outer loop + vertex 1.03261 1.08993 2.60126 + vertex 1.03213 1.09311 2.60176 + vertex 1.02856 1.08811 2.60228 + endloop + endfacet + facet normal 0.289314 -0.109207 0.950984 + outer loop + vertex 1.03261 1.08993 2.60126 + vertex 1.02856 1.08811 2.60228 + vertex 1.03173 1.08609 2.60108 + endloop + endfacet + facet normal 0.27549 -0.131685 0.952242 + outer loop + vertex 1.02856 1.08811 2.60228 + vertex 1.02764 1.08265 2.60179 + vertex 1.03173 1.08609 2.60108 + endloop + endfacet + facet normal 0.263889 -0.116831 0.957451 + outer loop + vertex 1.03173 1.08609 2.60108 + vertex 1.02764 1.08265 2.60179 + vertex 1.03091 1.08149 2.60075 + endloop + endfacet + facet normal 0.347217 -0.129609 0.928785 + outer loop + vertex 1.03091 1.08149 2.60075 + vertex 1.03481 1.08484 2.59976 + vertex 1.03173 1.08609 2.60108 + endloop + endfacet + facet normal 0.350088 -0.133427 0.927165 + outer loop + vertex 1.03359 1.07915 2.5994 + vertex 1.03481 1.08484 2.59976 + vertex 1.03091 1.08149 2.60075 + endloop + endfacet + facet normal 0.384603 -0.139911 0.912417 + outer loop + vertex 1.03359 1.07915 2.5994 + vertex 1.03827 1.0839 2.59816 + vertex 1.03481 1.08484 2.59976 + endloop + endfacet + facet normal 0.397005 -0.0953101 0.912854 + outer loop + vertex 1.03827 1.0839 2.59816 + vertex 1.03852 1.08888 2.59857 + vertex 1.03481 1.08484 2.59976 + endloop + endfacet + facet normal 0.412109 -0.111715 0.90426 + outer loop + vertex 1.03481 1.08484 2.59976 + vertex 1.03852 1.08888 2.59857 + vertex 1.03524 1.08944 2.60013 + endloop + endfacet + facet normal 0.358574 -0.110435 0.926946 + outer loop + vertex 1.03844 1.07866 2.59747 + vertex 1.03827 1.0839 2.59816 + vertex 1.03359 1.07915 2.5994 + endloop + endfacet + facet normal 0.352967 -0.151213 0.923336 + outer loop + vertex 1.03345 1.07357 2.59854 + vertex 1.03844 1.07866 2.59747 + vertex 1.03359 1.07915 2.5994 + endloop + endfacet + facet normal 0.313413 -0.108143 0.943439 + outer loop + vertex 1.03753 1.07289 2.59711 + vertex 1.03844 1.07866 2.59747 + vertex 1.03345 1.07357 2.59854 + endloop + endfacet + facet normal 0.306227 -0.145485 0.940776 + outer loop + vertex 1.03322 1.0683 2.5978 + vertex 1.03753 1.07289 2.59711 + vertex 1.03345 1.07357 2.59854 + endloop + endfacet + facet normal 0.272466 -0.111529 0.95568 + outer loop + vertex 1.03722 1.06817 2.59664 + vertex 1.03753 1.07289 2.59711 + vertex 1.03322 1.0683 2.5978 + endloop + endfacet + facet normal 0.270863 -0.136671 0.952866 + outer loop + vertex 1.03722 1.06817 2.59664 + vertex 1.03322 1.0683 2.5978 + vertex 1.03358 1.06323 2.59697 + endloop + endfacet + facet normal 0.404952 -0.106473 0.908118 + outer loop + vertex 1.04182 1.08353 2.59653 + vertex 1.03827 1.0839 2.59816 + vertex 1.03844 1.07866 2.59747 + endloop + endfacet + facet normal 0.378732 -0.0857159 0.921529 + outer loop + vertex 1.04229 1.0804 2.59605 + vertex 1.04182 1.08353 2.59653 + vertex 1.03844 1.07866 2.59747 + endloop + endfacet + facet normal 0.381281 -0.0927844 0.919791 + outer loop + vertex 1.04229 1.0804 2.59605 + vertex 1.03844 1.07866 2.59747 + vertex 1.04149 1.07648 2.59598 + endloop + endfacet + facet normal 0.428265 -0.101959 0.897883 + outer loop + vertex 1.04483 1.07964 2.59475 + vertex 1.04229 1.0804 2.59605 + vertex 1.04149 1.07648 2.59598 + endloop + endfacet + facet normal 0.416923 -0.0872639 0.904743 + outer loop + vertex 1.04449 1.07489 2.59445 + vertex 1.04483 1.07964 2.59475 + vertex 1.04149 1.07648 2.59598 + endloop + endfacet + facet normal 0.409309 -0.103248 0.906535 + outer loop + vertex 1.04081 1.07165 2.59574 + vertex 1.04449 1.07489 2.59445 + vertex 1.04149 1.07648 2.59598 + endloop + endfacet + facet normal 0.352012 -0.0964107 0.931017 + outer loop + vertex 1.04149 1.07648 2.59598 + vertex 1.03753 1.07289 2.59711 + vertex 1.04081 1.07165 2.59574 + endloop + endfacet + facet normal 0.345534 -0.114017 0.931454 + outer loop + vertex 1.03753 1.07289 2.59711 + vertex 1.03722 1.06817 2.59664 + vertex 1.04081 1.07165 2.59574 + endloop + endfacet + facet normal 0.326768 -0.092239 0.940593 + outer loop + vertex 1.04081 1.07165 2.59574 + vertex 1.03722 1.06817 2.59664 + vertex 1.03997 1.06771 2.59564 + endloop + endfacet + facet normal 0.393672 -0.105942 0.913126 + outer loop + vertex 1.03997 1.06771 2.59564 + vertex 1.04353 1.06916 2.59428 + vertex 1.04081 1.07165 2.59574 + endloop + endfacet + facet normal 0.39862 -0.122055 0.908958 + outer loop + vertex 1.03997 1.06771 2.59564 + vertex 1.0401 1.06432 2.59513 + vertex 1.04353 1.06916 2.59428 + endloop + endfacet + facet normal 0.384934 -0.111077 0.916235 + outer loop + vertex 1.04353 1.06916 2.59428 + vertex 1.0401 1.06432 2.59513 + vertex 1.04347 1.06375 2.59364 + endloop + endfacet + facet normal 0.419504 -0.109678 0.901103 + outer loop + vertex 1.04347 1.06375 2.59364 + vertex 1.04736 1.06799 2.59235 + vertex 1.04353 1.06916 2.59428 + endloop + endfacet + facet normal 0.426253 -0.0865973 0.90045 + outer loop + vertex 1.04736 1.06799 2.59235 + vertex 1.04769 1.07324 2.5927 + vertex 1.04353 1.06916 2.59428 + endloop + endfacet + facet normal 0.405946 -0.0948543 0.908961 + outer loop + vertex 1.04709 1.06299 2.59195 + vertex 1.04736 1.06799 2.59235 + vertex 1.04347 1.06375 2.59364 + endloop + endfacet + facet normal 0.399202 -0.125487 0.908235 + outer loop + vertex 1.04317 1.05866 2.59308 + vertex 1.04709 1.06299 2.59195 + vertex 1.04347 1.06375 2.59364 + endloop + endfacet + facet normal 0.347676 -0.124762 0.929277 + outer loop + vertex 1.04317 1.05866 2.59308 + vertex 1.04347 1.06375 2.59364 + vertex 1.03883 1.05893 2.59473 + endloop + endfacet + facet normal 0.372651 -0.0976928 0.922815 + outer loop + vertex 1.04692 1.05856 2.59155 + vertex 1.04709 1.06299 2.59195 + vertex 1.04317 1.05866 2.59308 + endloop + endfacet + facet normal 0.370838 -0.125818 0.920135 + outer loop + vertex 1.04692 1.05856 2.59155 + vertex 1.04317 1.05866 2.59308 + vertex 1.04343 1.05359 2.59228 + endloop + endfacet + facet normal 0.345395 -0.106135 0.932436 + outer loop + vertex 1.04736 1.05546 2.59103 + vertex 1.04692 1.05856 2.59155 + vertex 1.04343 1.05359 2.59228 + endloop + endfacet + facet normal 0.344783 -0.104576 0.932839 + outer loop + vertex 1.04736 1.05546 2.59103 + vertex 1.04343 1.05359 2.59228 + vertex 1.04649 1.05157 2.59092 + endloop + endfacet + facet normal 0.407085 -0.117886 0.905751 + outer loop + vertex 1.04999 1.05474 2.58976 + vertex 1.04736 1.05546 2.59103 + vertex 1.04649 1.05157 2.59092 + endloop + endfacet + facet normal 0.391188 -0.0967807 0.915208 + outer loop + vertex 1.04949 1.04996 2.58947 + vertex 1.04999 1.05474 2.58976 + vertex 1.04649 1.05157 2.59092 + endloop + endfacet + facet normal 0.379217 -0.12102 0.917359 + outer loop + vertex 1.04567 1.04679 2.59063 + vertex 1.04949 1.04996 2.58947 + vertex 1.04649 1.05157 2.59092 + endloop + endfacet + facet normal 0.313985 -0.111419 0.942868 + outer loop + vertex 1.04649 1.05157 2.59092 + vertex 1.04245 1.048 2.59184 + vertex 1.04567 1.04679 2.59063 + endloop + endfacet + facet normal 0.305005 -0.13519 0.942706 + outer loop + vertex 1.04245 1.048 2.59184 + vertex 1.04199 1.0435 2.59135 + vertex 1.04567 1.04679 2.59063 + endloop + endfacet + facet normal 0.292593 -0.120044 0.948672 + outer loop + vertex 1.04567 1.04679 2.59063 + vertex 1.04199 1.0435 2.59135 + vertex 1.04452 1.04279 2.59047 + endloop + endfacet + facet normal 0.36062 -0.138484 0.922375 + outer loop + vertex 1.04452 1.04279 2.59047 + vertex 1.04827 1.04414 2.58921 + vertex 1.04567 1.04679 2.59063 + endloop + endfacet + facet normal 0.377957 -0.119224 0.918114 + outer loop + vertex 1.04827 1.04414 2.58921 + vertex 1.04949 1.04996 2.58947 + vertex 1.04567 1.04679 2.59063 + endloop + endfacet + facet normal 0.409673 -0.125226 0.903596 + outer loop + vertex 1.04827 1.04414 2.58921 + vertex 1.05273 1.04825 2.58776 + vertex 1.04949 1.04996 2.58947 + endloop + endfacet + facet normal 0.428268 -0.0859249 0.899557 + outer loop + vertex 1.05273 1.04825 2.58776 + vertex 1.05316 1.05343 2.58805 + vertex 1.04949 1.04996 2.58947 + endloop + endfacet + facet normal 0.391573 -0.101772 0.914501 + outer loop + vertex 1.05235 1.04302 2.58734 + vertex 1.05273 1.04825 2.58776 + vertex 1.04827 1.04414 2.58921 + endloop + endfacet + facet normal 0.38001 -0.143101 0.913846 + outer loop + vertex 1.04819 1.03859 2.58838 + vertex 1.05235 1.04302 2.58734 + vertex 1.04827 1.04414 2.58921 + endloop + endfacet + facet normal 0.353933 -0.115252 0.928143 + outer loop + vertex 1.0521 1.03803 2.58682 + vertex 1.05235 1.04302 2.58734 + vertex 1.04819 1.03859 2.58838 + endloop + endfacet + facet normal 0.347561 -0.151665 0.92531 + outer loop + vertex 1.04803 1.03357 2.58762 + vertex 1.0521 1.03803 2.58682 + vertex 1.04819 1.03859 2.58838 + endloop + endfacet + facet normal 0.319017 -0.123044 0.939728 + outer loop + vertex 1.05188 1.0336 2.58631 + vertex 1.0521 1.03803 2.58682 + vertex 1.04803 1.03357 2.58762 + endloop + endfacet + facet normal 0.317999 -0.149445 0.936239 + outer loop + vertex 1.05188 1.0336 2.58631 + vertex 1.04803 1.03357 2.58762 + vertex 1.04827 1.02872 2.58676 + endloop + endfacet + facet normal 0.298726 -0.134391 0.944829 + outer loop + vertex 1.0522 1.0305 2.58577 + vertex 1.05188 1.0336 2.58631 + vertex 1.04827 1.02872 2.58676 + endloop + endfacet + facet normal 0.299785 -0.13714 0.944098 + outer loop + vertex 1.0522 1.0305 2.58577 + vertex 1.04827 1.02872 2.58676 + vertex 1.05101 1.02673 2.5856 + endloop + endfacet + facet normal 0.374967 -0.159631 0.913191 + outer loop + vertex 1.05476 1.02972 2.58458 + vertex 1.0522 1.0305 2.58577 + vertex 1.05101 1.02673 2.5856 + endloop + endfacet + facet normal 0.369444 -0.151482 0.916823 + outer loop + vertex 1.05342 1.02414 2.5842 + vertex 1.05476 1.02972 2.58458 + vertex 1.05101 1.02673 2.5856 + endloop + endfacet + facet normal 0.351268 -0.170473 0.920625 + outer loop + vertex 1.04956 1.02291 2.58545 + vertex 1.05342 1.02414 2.5842 + vertex 1.05101 1.02673 2.5856 + endloop + endfacet + facet normal 0.286081 -0.146801 0.946894 + outer loop + vertex 1.05101 1.02673 2.5856 + vertex 1.04728 1.02387 2.58628 + vertex 1.04956 1.02291 2.58545 + endloop + endfacet + facet normal 0.277756 -0.165985 0.946203 + outer loop + vertex 1.04956 1.02291 2.58545 + vertex 1.04728 1.02387 2.58628 + vertex 1.04697 1.02075 2.58583 + endloop + endfacet + facet normal 0.309683 -0.20743 0.927938 + outer loop + vertex 1.04956 1.02291 2.58545 + vertex 1.04697 1.02075 2.58583 + vertex 1.04868 1.01881 2.58482 + endloop + endfacet + facet normal 0.361197 -0.215405 0.907269 + outer loop + vertex 1.04956 1.02291 2.58545 + vertex 1.04868 1.01881 2.58482 + vertex 1.05342 1.02414 2.5842 + endloop + endfacet + facet normal 0.307099 -0.163658 0.9375 + outer loop + vertex 1.05342 1.02414 2.5842 + vertex 1.04868 1.01881 2.58482 + vertex 1.0532 1.01853 2.58329 + endloop + endfacet + facet normal 0.302611 -0.202494 0.931355 + outer loop + vertex 1.04855 1.01356 2.58372 + vertex 1.0532 1.01853 2.58329 + vertex 1.04868 1.01881 2.58482 + endloop + endfacet + facet normal 0.262859 -0.163678 0.95085 + outer loop + vertex 1.0535 1.01328 2.58231 + vertex 1.0532 1.01853 2.58329 + vertex 1.04855 1.01356 2.58372 + endloop + endfacet + facet normal 0.381443 -0.139313 0.913834 + outer loop + vertex 1.05459 1.03316 2.58518 + vertex 1.0522 1.0305 2.58577 + vertex 1.05476 1.02972 2.58458 + endloop + endfacet + facet normal 0.289552 -0.151785 0.945051 + outer loop + vertex 1.04827 1.02872 2.58676 + vertex 1.04728 1.02387 2.58628 + vertex 1.05101 1.02673 2.5856 + endloop + endfacet + facet normal 0.410339 -0.115694 0.904564 + outer loop + vertex 1.05235 1.04302 2.58734 + vertex 1.0521 1.03803 2.58682 + vertex 1.05584 1.04174 2.5856 + endloop + endfacet + facet normal 0.4207 -0.0857436 0.903139 + outer loop + vertex 1.05612 1.0467 2.58593 + vertex 1.05235 1.04302 2.58734 + vertex 1.05584 1.04174 2.5856 + endloop + endfacet + facet normal 0.451245 -0.0864878 0.888199 + outer loop + vertex 1.05584 1.04174 2.5856 + vertex 1.05932 1.04504 2.58415 + vertex 1.05612 1.0467 2.58593 + endloop + endfacet + facet normal 0.444766 -0.0778795 0.892254 + outer loop + vertex 1.05895 1.04 2.58389 + vertex 1.05932 1.04504 2.58415 + vertex 1.05584 1.04174 2.5856 + endloop + endfacet + facet normal 0.433998 -0.10016 0.895329 + outer loop + vertex 1.05538 1.03694 2.58528 + vertex 1.05895 1.04 2.58389 + vertex 1.05584 1.04174 2.5856 + endloop + endfacet + facet normal 0.431323 -0.0962499 0.897049 + outer loop + vertex 1.05813 1.0344 2.58369 + vertex 1.05895 1.04 2.58389 + vertex 1.05538 1.03694 2.58528 + endloop + endfacet + facet normal 0.41903 -0.112055 0.901031 + outer loop + vertex 1.05459 1.03316 2.58518 + vertex 1.05813 1.0344 2.58369 + vertex 1.05538 1.03694 2.58528 + endloop + endfacet + facet normal 0.369749 -0.102381 0.923474 + outer loop + vertex 1.05538 1.03694 2.58528 + vertex 1.05188 1.0336 2.58631 + vertex 1.05459 1.03316 2.58518 + endloop + endfacet + facet normal 0.386962 -0.123363 0.913806 + outer loop + vertex 1.0521 1.03803 2.58682 + vertex 1.05188 1.0336 2.58631 + vertex 1.05538 1.03694 2.58528 + endloop + endfacet + facet normal 0.424389 -0.134008 0.895509 + outer loop + vertex 1.05459 1.03316 2.58518 + vertex 1.05476 1.02972 2.58458 + vertex 1.05813 1.0344 2.58369 + endloop + endfacet + facet normal 0.421492 -0.0949824 0.901844 + outer loop + vertex 1.05813 1.0344 2.58369 + vertex 1.06211 1.03819 2.58223 + vertex 1.05895 1.04 2.58389 + endloop + endfacet + facet normal 0.4317 -0.0744522 0.898939 + outer loop + vertex 1.06211 1.03819 2.58223 + vertex 1.06245 1.04324 2.58248 + vertex 1.05895 1.04 2.58389 + endloop + endfacet + facet normal 0.386634 -0.072369 0.919389 + outer loop + vertex 1.06245 1.04324 2.58248 + vertex 1.06211 1.03819 2.58223 + vertex 1.06573 1.04151 2.58096 + endloop + endfacet + facet normal 0.390503 -0.0641656 0.918363 + outer loop + vertex 1.06598 1.04652 2.58121 + vertex 1.06245 1.04324 2.58248 + vertex 1.06573 1.04151 2.58096 + endloop + endfacet + facet normal 0.332139 -0.0624062 0.941164 + outer loop + vertex 1.06573 1.04151 2.58096 + vertex 1.06957 1.04505 2.57984 + vertex 1.06598 1.04652 2.58121 + endloop + endfacet + facet normal 0.32963 -0.0689482 0.941589 + outer loop + vertex 1.06957 1.04505 2.57984 + vertex 1.06975 1.05006 2.58015 + vertex 1.06598 1.04652 2.58121 + endloop + endfacet + facet normal 0.321221 -0.0589439 0.945168 + outer loop + vertex 1.06598 1.04652 2.58121 + vertex 1.06975 1.05006 2.58015 + vertex 1.06623 1.05141 2.58143 + endloop + endfacet + facet normal 0.387972 -0.0611932 0.919638 + outer loop + vertex 1.06623 1.05141 2.58143 + vertex 1.06272 1.04823 2.5827 + vertex 1.06598 1.04652 2.58121 + endloop + endfacet + facet normal 0.389619 -0.0633503 0.918795 + outer loop + vertex 1.06313 1.05317 2.58287 + vertex 1.06272 1.04823 2.5827 + vertex 1.06623 1.05141 2.58143 + endloop + endfacet + facet normal 0.384425 -0.0736392 0.920215 + outer loop + vertex 1.06673 1.05593 2.58158 + vertex 1.06313 1.05317 2.58287 + vertex 1.06623 1.05141 2.58143 + endloop + endfacet + facet normal 0.391256 -0.0843217 0.916411 + outer loop + vertex 1.06416 1.05862 2.58292 + vertex 1.06313 1.05317 2.58287 + vertex 1.06673 1.05593 2.58158 + endloop + endfacet + facet normal 0.367917 -0.110021 0.923327 + outer loop + vertex 1.06796 1.05953 2.58152 + vertex 1.06416 1.05862 2.58292 + vertex 1.06673 1.05593 2.58158 + endloop + endfacet + facet normal 0.315178 -0.0915901 0.944603 + outer loop + vertex 1.06974 1.05814 2.58079 + vertex 1.06796 1.05953 2.58152 + vertex 1.06673 1.05593 2.58158 + endloop + endfacet + facet normal 0.306738 -0.0786845 0.948536 + outer loop + vertex 1.06985 1.05476 2.58047 + vertex 1.06974 1.05814 2.58079 + vertex 1.06673 1.05593 2.58158 + endloop + endfacet + facet normal 0.311111 -0.0665473 0.948041 + outer loop + vertex 1.06623 1.05141 2.58143 + vertex 1.06985 1.05476 2.58047 + vertex 1.06673 1.05593 2.58158 + endloop + endfacet + facet normal 0.372274 -0.136589 0.918017 + outer loop + vertex 1.06796 1.05953 2.58152 + vertex 1.06851 1.06355 2.58189 + vertex 1.06416 1.05862 2.58292 + endloop + endfacet + facet normal 0.330645 -0.0954181 0.938919 + outer loop + vertex 1.06851 1.06355 2.58189 + vertex 1.06345 1.06409 2.58373 + vertex 1.06416 1.05862 2.58292 + endloop + endfacet + facet normal 0.330597 -0.0957894 0.938898 + outer loop + vertex 1.06851 1.06355 2.58189 + vertex 1.06836 1.06873 2.58248 + vertex 1.06345 1.06409 2.58373 + endloop + endfacet + facet normal 0.301061 -0.061139 0.951643 + outer loop + vertex 1.06345 1.06409 2.58373 + vertex 1.06836 1.06873 2.58248 + vertex 1.06413 1.06981 2.58388 + endloop + endfacet + facet normal 0.29776 -0.0741394 0.951758 + outer loop + vertex 1.06836 1.06873 2.58248 + vertex 1.06852 1.07391 2.58283 + vertex 1.06413 1.06981 2.58388 + endloop + endfacet + facet normal 0.283548 -0.0574814 0.957234 + outer loop + vertex 1.06413 1.06981 2.58388 + vertex 1.06852 1.07391 2.58283 + vertex 1.06434 1.07491 2.58413 + endloop + endfacet + facet normal 0.280818 -0.068975 0.957279 + outer loop + vertex 1.06852 1.07391 2.58283 + vertex 1.06853 1.07889 2.58319 + vertex 1.06434 1.07491 2.58413 + endloop + endfacet + facet normal 0.276266 -0.0637873 0.958962 + outer loop + vertex 1.06434 1.07491 2.58413 + vertex 1.06853 1.07889 2.58319 + vertex 1.06442 1.07987 2.58443 + endloop + endfacet + facet normal 0.27277 -0.078415 0.958878 + outer loop + vertex 1.06853 1.07889 2.58319 + vertex 1.0686 1.08382 2.58357 + vertex 1.06442 1.07987 2.58443 + endloop + endfacet + facet normal 0.266094 -0.0708212 0.961342 + outer loop + vertex 1.06442 1.07987 2.58443 + vertex 1.0686 1.08382 2.58357 + vertex 1.06454 1.0848 2.58476 + endloop + endfacet + facet normal 0.261992 -0.0874275 0.961102 + outer loop + vertex 1.0686 1.08382 2.58357 + vertex 1.06869 1.08875 2.58399 + vertex 1.06454 1.0848 2.58476 + endloop + endfacet + facet normal 0.248313 -0.0721284 0.965991 + outer loop + vertex 1.06454 1.0848 2.58476 + vertex 1.06869 1.08875 2.58399 + vertex 1.06473 1.08971 2.58508 + endloop + endfacet + facet normal 0.243803 -0.0903571 0.965606 + outer loop + vertex 1.06869 1.08875 2.58399 + vertex 1.06875 1.09373 2.58444 + vertex 1.06473 1.08971 2.58508 + endloop + endfacet + facet normal 0.226875 -0.07256 0.971217 + outer loop + vertex 1.06473 1.08971 2.58508 + vertex 1.06875 1.09373 2.58444 + vertex 1.06491 1.09431 2.58538 + endloop + endfacet + facet normal 0.223245 -0.094633 0.970158 + outer loop + vertex 1.06848 1.09894 2.58501 + vertex 1.06491 1.09431 2.58538 + vertex 1.06875 1.09373 2.58444 + endloop + endfacet + facet normal 0.215162 -0.0881964 0.972588 + outer loop + vertex 1.06453 1.09763 2.58577 + vertex 1.06491 1.09431 2.58538 + vertex 1.06848 1.09894 2.58501 + endloop + endfacet + facet normal 0.21913 -0.10139 0.970413 + outer loop + vertex 1.06453 1.09763 2.58577 + vertex 1.06848 1.09894 2.58501 + vertex 1.06552 1.10133 2.58593 + endloop + endfacet + facet normal 0.335614 -0.130537 0.932911 + outer loop + vertex 1.06552 1.10133 2.58593 + vertex 1.06191 1.09851 2.58684 + vertex 1.06453 1.09763 2.58577 + endloop + endfacet + facet normal 0.345711 -0.10063 0.93293 + outer loop + vertex 1.06453 1.09763 2.58577 + vertex 1.06191 1.09851 2.58684 + vertex 1.06216 1.09512 2.58638 + endloop + endfacet + facet normal 0.317372 -0.104094 0.942571 + outer loop + vertex 1.06253 1.10309 2.58713 + vertex 1.06191 1.09851 2.58684 + vertex 1.06552 1.10133 2.58593 + endloop + endfacet + facet normal 0.304625 -0.126749 0.944001 + outer loop + vertex 1.06646 1.10561 2.5862 + vertex 1.06253 1.10309 2.58713 + vertex 1.06552 1.10133 2.58593 + endloop + endfacet + facet normal 0.207609 -0.107064 0.972335 + outer loop + vertex 1.06552 1.10133 2.58593 + vertex 1.0695 1.10424 2.5854 + vertex 1.06646 1.10561 2.5862 + endloop + endfacet + facet normal 0.203779 -0.115483 0.972182 + outer loop + vertex 1.0695 1.10424 2.5854 + vertex 1.06977 1.10765 2.58575 + vertex 1.06646 1.10561 2.5862 + endloop + endfacet + facet normal 0.20902 -0.124452 0.96996 + outer loop + vertex 1.06977 1.10765 2.58575 + vertex 1.06801 1.1091 2.58632 + vertex 1.06646 1.10561 2.5862 + endloop + endfacet + facet normal 0.266344 -0.149259 0.952251 + outer loop + vertex 1.06801 1.1091 2.58632 + vertex 1.06389 1.10841 2.58736 + vertex 1.06646 1.10561 2.5862 + endloop + endfacet + facet normal 0.267966 -0.163213 0.949503 + outer loop + vertex 1.06801 1.1091 2.58632 + vertex 1.06885 1.11324 2.58679 + vertex 1.06389 1.10841 2.58736 + endloop + endfacet + facet normal 0.2262 -0.118224 0.96688 + outer loop + vertex 1.06885 1.11324 2.58679 + vertex 1.06372 1.11369 2.58804 + vertex 1.06389 1.10841 2.58736 + endloop + endfacet + facet normal 0.320509 -0.111797 0.940625 + outer loop + vertex 1.06389 1.10841 2.58736 + vertex 1.06372 1.11369 2.58804 + vertex 1.05941 1.10984 2.58906 + endloop + endfacet + facet normal 0.329233 -0.0841198 0.940494 + outer loop + vertex 1.05914 1.10484 2.5887 + vertex 1.06389 1.10841 2.58736 + vertex 1.05941 1.10984 2.58906 + endloop + endfacet + facet normal 0.360177 -0.131655 0.923547 + outer loop + vertex 1.06253 1.10309 2.58713 + vertex 1.06389 1.10841 2.58736 + vertex 1.05914 1.10484 2.5887 + endloop + endfacet + facet normal 0.38374 -0.0826495 0.919735 + outer loop + vertex 1.05867 1.09981 2.58845 + vertex 1.06253 1.10309 2.58713 + vertex 1.05914 1.10484 2.5887 + endloop + endfacet + facet normal 0.405808 -0.113842 0.906841 + outer loop + vertex 1.06191 1.09851 2.58684 + vertex 1.06253 1.10309 2.58713 + vertex 1.05867 1.09981 2.58845 + endloop + endfacet + facet normal 0.421459 -0.0714068 0.904032 + outer loop + vertex 1.06191 1.09851 2.58684 + vertex 1.05867 1.09981 2.58845 + vertex 1.05829 1.09402 2.58817 + endloop + endfacet + facet normal 0.439007 -0.0884885 0.894115 + outer loop + vertex 1.06216 1.09512 2.58638 + vertex 1.06191 1.09851 2.58684 + vertex 1.05829 1.09402 2.58817 + endloop + endfacet + facet normal 0.436704 -0.0767978 0.896321 + outer loop + vertex 1.06216 1.09512 2.58638 + vertex 1.05829 1.09402 2.58817 + vertex 1.06142 1.09121 2.5864 + endloop + endfacet + facet normal 0.324817 -0.0555129 0.944146 + outer loop + vertex 1.06491 1.09431 2.58538 + vertex 1.06216 1.09512 2.58638 + vertex 1.06142 1.09121 2.5864 + endloop + endfacet + facet normal 0.339888 -0.0746423 0.937499 + outer loop + vertex 1.06473 1.08971 2.58508 + vertex 1.06491 1.09431 2.58538 + vertex 1.06142 1.09121 2.5864 + endloop + endfacet + facet normal 0.344244 -0.0643578 0.936672 + outer loop + vertex 1.06106 1.0863 2.58619 + vertex 1.06473 1.08971 2.58508 + vertex 1.06142 1.09121 2.5864 + endloop + endfacet + facet normal 0.447129 -0.0700124 0.891725 + outer loop + vertex 1.06142 1.09121 2.5864 + vertex 1.05795 1.08817 2.5879 + vertex 1.06106 1.0863 2.58619 + endloop + endfacet + facet normal 0.452235 -0.0598391 0.889889 + outer loop + vertex 1.05795 1.08817 2.5879 + vertex 1.05768 1.08311 2.5877 + vertex 1.06106 1.0863 2.58619 + endloop + endfacet + facet normal 0.455848 -0.0647048 0.887703 + outer loop + vertex 1.06106 1.0863 2.58619 + vertex 1.05768 1.08311 2.5877 + vertex 1.06084 1.08133 2.58595 + endloop + endfacet + facet normal 0.356652 -0.0625342 0.932142 + outer loop + vertex 1.06084 1.08133 2.58595 + vertex 1.06454 1.0848 2.58476 + vertex 1.06106 1.0863 2.58619 + endloop + endfacet + facet normal 0.36357 -0.0710297 0.928855 + outer loop + vertex 1.06442 1.07987 2.58443 + vertex 1.06454 1.0848 2.58476 + vertex 1.06084 1.08133 2.58595 + endloop + endfacet + facet normal 0.367766 -0.0598661 0.92799 + outer loop + vertex 1.0607 1.07637 2.58568 + vertex 1.06442 1.07987 2.58443 + vertex 1.06084 1.08133 2.58595 + endloop + endfacet + facet normal 0.460868 -0.0604324 0.885409 + outer loop + vertex 1.06084 1.08133 2.58595 + vertex 1.05749 1.07812 2.58747 + vertex 1.0607 1.07637 2.58568 + endloop + endfacet + facet normal 0.462249 -0.0573878 0.884891 + outer loop + vertex 1.05749 1.07812 2.58747 + vertex 1.05731 1.07313 2.58724 + vertex 1.0607 1.07637 2.58568 + endloop + endfacet + facet normal 0.462834 -0.0581723 0.884534 + outer loop + vertex 1.0607 1.07637 2.58568 + vertex 1.05731 1.07313 2.58724 + vertex 1.06051 1.07138 2.58546 + endloop + endfacet + facet normal 0.373129 -0.0566605 0.926048 + outer loop + vertex 1.06051 1.07138 2.58546 + vertex 1.06434 1.07491 2.58413 + vertex 1.0607 1.07637 2.58568 + endloop + endfacet + facet normal 0.375553 -0.0597349 0.924874 + outer loop + vertex 1.06413 1.06981 2.58388 + vertex 1.06434 1.07491 2.58413 + vertex 1.06051 1.07138 2.58546 + endloop + endfacet + facet normal 0.377455 -0.054872 0.924401 + outer loop + vertex 1.06014 1.0665 2.58532 + vertex 1.06413 1.06981 2.58388 + vertex 1.06051 1.07138 2.58546 + endloop + endfacet + facet normal 0.46188 -0.0600561 0.884907 + outer loop + vertex 1.06051 1.07138 2.58546 + vertex 1.05706 1.06818 2.58704 + vertex 1.06014 1.0665 2.58532 + endloop + endfacet + facet normal 0.460167 -0.0638443 0.885534 + outer loop + vertex 1.05706 1.06818 2.58704 + vertex 1.05679 1.06351 2.58684 + vertex 1.06014 1.0665 2.58532 + endloop + endfacet + facet normal 0.464814 -0.0705571 0.882593 + outer loop + vertex 1.06014 1.0665 2.58532 + vertex 1.05679 1.06351 2.58684 + vertex 1.05944 1.06262 2.58537 + endloop + endfacet + facet normal 0.396509 -0.0577483 0.916213 + outer loop + vertex 1.05944 1.06262 2.58537 + vertex 1.06345 1.06409 2.58373 + vertex 1.06014 1.0665 2.58532 + endloop + endfacet + facet normal 0.400241 -0.0707802 0.913672 + outer loop + vertex 1.05944 1.06262 2.58537 + vertex 1.06005 1.05938 2.58485 + vertex 1.06345 1.06409 2.58373 + endloop + endfacet + facet normal 0.411578 -0.0803689 0.907824 + outer loop + vertex 1.06345 1.06409 2.58373 + vertex 1.06005 1.05938 2.58485 + vertex 1.06416 1.05862 2.58292 + endloop + endfacet + facet normal 0.414202 -0.0660881 0.907783 + outer loop + vertex 1.05993 1.05486 2.58458 + vertex 1.06416 1.05862 2.58292 + vertex 1.06005 1.05938 2.58485 + endloop + endfacet + facet normal 0.432966 -0.092032 0.8967 + outer loop + vertex 1.06313 1.05317 2.58287 + vertex 1.06416 1.05862 2.58292 + vertex 1.05993 1.05486 2.58458 + endloop + endfacet + facet normal 0.444249 -0.0672819 0.893373 + outer loop + vertex 1.05958 1.04998 2.58439 + vertex 1.06313 1.05317 2.58287 + vertex 1.05993 1.05486 2.58458 + endloop + endfacet + facet normal 0.467447 -0.0684575 0.881366 + outer loop + vertex 1.05958 1.04998 2.58439 + vertex 1.05993 1.05486 2.58458 + vertex 1.05638 1.05165 2.58621 + endloop + endfacet + facet normal 0.464884 -0.0743386 0.882245 + outer loop + vertex 1.05612 1.0467 2.58593 + vertex 1.05958 1.04998 2.58439 + vertex 1.05638 1.05165 2.58621 + endloop + endfacet + facet normal 0.446478 -0.0739081 0.891737 + outer loop + vertex 1.05638 1.05165 2.58621 + vertex 1.05273 1.04825 2.58776 + vertex 1.05612 1.0467 2.58593 + endloop + endfacet + facet normal 0.456403 -0.0874539 0.885465 + outer loop + vertex 1.05316 1.05343 2.58805 + vertex 1.05273 1.04825 2.58776 + vertex 1.05638 1.05165 2.58621 + endloop + endfacet + facet normal 0.466658 -0.0653423 0.882021 + outer loop + vertex 1.05666 1.05642 2.58642 + vertex 1.05316 1.05343 2.58805 + vertex 1.05638 1.05165 2.58621 + endloop + endfacet + facet normal 0.471584 -0.0728866 0.878804 + outer loop + vertex 1.05345 1.05915 2.58837 + vertex 1.05316 1.05343 2.58805 + vertex 1.05666 1.05642 2.58642 + endloop + endfacet + facet normal 0.481102 -0.0587952 0.874691 + outer loop + vertex 1.05722 1.06014 2.58636 + vertex 1.05345 1.05915 2.58837 + vertex 1.05666 1.05642 2.58642 + endloop + endfacet + facet normal 0.457613 -0.0551266 0.887441 + outer loop + vertex 1.06005 1.05938 2.58485 + vertex 1.05722 1.06014 2.58636 + vertex 1.05666 1.05642 2.58642 + endloop + endfacet + facet normal 0.464971 -0.0659439 0.882867 + outer loop + vertex 1.05993 1.05486 2.58458 + vertex 1.06005 1.05938 2.58485 + vertex 1.05666 1.05642 2.58642 + endloop + endfacet + facet normal 0.48177 -0.0626128 0.874058 + outer loop + vertex 1.05722 1.06014 2.58636 + vertex 1.05679 1.06351 2.58684 + vertex 1.05345 1.05915 2.58837 + endloop + endfacet + facet normal 0.491722 -0.0724546 0.867733 + outer loop + vertex 1.05679 1.06351 2.58684 + vertex 1.05376 1.06488 2.58868 + vertex 1.05345 1.05915 2.58837 + endloop + endfacet + facet normal 0.472751 -0.0720162 0.878248 + outer loop + vertex 1.05345 1.05915 2.58837 + vertex 1.05376 1.06488 2.58868 + vertex 1.05033 1.0618 2.59027 + endloop + endfacet + facet normal 0.464311 -0.0844153 0.88164 + outer loop + vertex 1.04966 1.05806 2.59026 + vertex 1.05345 1.05915 2.58837 + vertex 1.05033 1.0618 2.59027 + endloop + endfacet + facet normal 0.464818 -0.0870946 0.881112 + outer loop + vertex 1.04966 1.05806 2.59026 + vertex 1.04999 1.05474 2.58976 + vertex 1.05345 1.05915 2.58837 + endloop + endfacet + facet normal 0.449701 -0.0723843 0.890241 + outer loop + vertex 1.05345 1.05915 2.58837 + vertex 1.04999 1.05474 2.58976 + vertex 1.05316 1.05343 2.58805 + endloop + endfacet + facet normal 0.41305 -0.0959096 0.905644 + outer loop + vertex 1.04966 1.05806 2.59026 + vertex 1.04736 1.05546 2.59103 + vertex 1.04999 1.05474 2.58976 + endloop + endfacet + facet normal 0.479421 -0.0817452 0.87377 + outer loop + vertex 1.05033 1.0618 2.59027 + vertex 1.05376 1.06488 2.58868 + vertex 1.05068 1.06661 2.59052 + endloop + endfacet + facet normal 0.436384 -0.0797716 0.896217 + outer loop + vertex 1.05068 1.06661 2.59052 + vertex 1.04709 1.06299 2.59195 + vertex 1.05033 1.0618 2.59027 + endloop + endfacet + facet normal 0.449141 -0.0955325 0.888339 + outer loop + vertex 1.04736 1.06799 2.59235 + vertex 1.04709 1.06299 2.59195 + vertex 1.05068 1.06661 2.59052 + endloop + endfacet + facet normal 0.455897 -0.0769991 0.886696 + outer loop + vertex 1.05097 1.07165 2.59081 + vertex 1.04736 1.06799 2.59235 + vertex 1.05068 1.06661 2.59052 + endloop + endfacet + facet normal 0.491863 -0.077956 0.867176 + outer loop + vertex 1.05068 1.06661 2.59052 + vertex 1.05405 1.06993 2.58891 + vertex 1.05097 1.07165 2.59081 + endloop + endfacet + facet normal 0.497637 -0.0651284 0.864937 + outer loop + vertex 1.05405 1.06993 2.58891 + vertex 1.05428 1.07496 2.58915 + vertex 1.05097 1.07165 2.59081 + endloop + endfacet + facet normal 0.502313 -0.0714079 0.861732 + outer loop + vertex 1.05097 1.07165 2.59081 + vertex 1.05428 1.07496 2.58915 + vertex 1.0512 1.07676 2.5911 + endloop + endfacet + facet normal 0.471385 -0.0710068 0.879065 + outer loop + vertex 1.0512 1.07676 2.5911 + vertex 1.04769 1.07324 2.5927 + vertex 1.05097 1.07165 2.59081 + endloop + endfacet + facet normal 0.477878 -0.0793979 0.874831 + outer loop + vertex 1.04798 1.07847 2.59302 + vertex 1.04769 1.07324 2.5927 + vertex 1.0512 1.07676 2.5911 + endloop + endfacet + facet normal 0.485466 -0.0620018 0.872054 + outer loop + vertex 1.05135 1.08186 2.59138 + vertex 1.04798 1.07847 2.59302 + vertex 1.0512 1.07676 2.5911 + endloop + endfacet + facet normal 0.508881 -0.0619828 0.858603 + outer loop + vertex 1.0512 1.07676 2.5911 + vertex 1.05446 1.07998 2.5894 + vertex 1.05135 1.08186 2.59138 + endloop + endfacet + facet normal 0.511606 -0.0561704 0.857382 + outer loop + vertex 1.05446 1.07998 2.5894 + vertex 1.05467 1.08494 2.5896 + vertex 1.05135 1.08186 2.59138 + endloop + endfacet + facet normal 0.510781 -0.0549517 0.857953 + outer loop + vertex 1.05135 1.08186 2.59138 + vertex 1.05467 1.08494 2.5896 + vertex 1.05172 1.08681 2.59148 + endloop + endfacet + facet normal 0.492016 -0.0537909 0.868923 + outer loop + vertex 1.05172 1.08681 2.59148 + vertex 1.04784 1.08384 2.59349 + vertex 1.05135 1.08186 2.59138 + endloop + endfacet + facet normal 0.492535 -0.0547058 0.868572 + outer loop + vertex 1.04907 1.08983 2.59317 + vertex 1.04784 1.08384 2.59349 + vertex 1.05172 1.08681 2.59148 + endloop + endfacet + facet normal 0.498041 -0.0483023 0.865807 + outer loop + vertex 1.05242 1.09064 2.59129 + vertex 1.04907 1.08983 2.59317 + vertex 1.05172 1.08681 2.59148 + endloop + endfacet + facet normal 0.507429 -0.0503014 0.860224 + outer loop + vertex 1.05491 1.0896 2.58976 + vertex 1.05242 1.09064 2.59129 + vertex 1.05172 1.08681 2.59148 + endloop + endfacet + facet normal 0.507058 -0.0514045 0.860377 + outer loop + vertex 1.05451 1.09299 2.5902 + vertex 1.05242 1.09064 2.59129 + vertex 1.05491 1.0896 2.58976 + endloop + endfacet + facet normal 0.484129 -0.055726 0.87322 + outer loop + vertex 1.05451 1.09299 2.5902 + vertex 1.05491 1.0896 2.58976 + vertex 1.05829 1.09402 2.58817 + endloop + endfacet + facet normal 0.483266 -0.0510353 0.873985 + outer loop + vertex 1.05451 1.09299 2.5902 + vertex 1.05829 1.09402 2.58817 + vertex 1.0551 1.09679 2.59009 + endloop + endfacet + facet normal 0.500487 -0.0539982 0.864058 + outer loop + vertex 1.0551 1.09679 2.59009 + vertex 1.05198 1.09396 2.59173 + vertex 1.05451 1.09299 2.5902 + endloop + endfacet + facet normal 0.495894 -0.0471838 0.8671 + outer loop + vertex 1.05204 1.09842 2.59193 + vertex 1.05198 1.09396 2.59173 + vertex 1.0551 1.09679 2.59009 + endloop + endfacet + facet normal 0.491006 -0.0587333 0.869174 + outer loop + vertex 1.05538 1.10158 2.59026 + vertex 1.05204 1.09842 2.59193 + vertex 1.0551 1.09679 2.59009 + endloop + endfacet + facet normal 0.457441 -0.0574159 0.887384 + outer loop + vertex 1.0551 1.09679 2.59009 + vertex 1.05867 1.09981 2.58845 + vertex 1.05538 1.10158 2.59026 + endloop + endfacet + facet normal 0.444057 -0.0867887 0.891785 + outer loop + vertex 1.05867 1.09981 2.58845 + vertex 1.05914 1.10484 2.5887 + vertex 1.05538 1.10158 2.59026 + endloop + endfacet + facet normal 0.425288 -0.0597694 0.903082 + outer loop + vertex 1.05538 1.10158 2.59026 + vertex 1.05914 1.10484 2.5887 + vertex 1.05558 1.10645 2.59049 + endloop + endfacet + facet normal 0.478854 -0.060582 0.875802 + outer loop + vertex 1.05558 1.10645 2.59049 + vertex 1.05217 1.10323 2.59213 + vertex 1.05538 1.10158 2.59026 + endloop + endfacet + facet normal 0.470833 -0.0495825 0.880828 + outer loop + vertex 1.05231 1.10811 2.59233 + vertex 1.05217 1.10323 2.59213 + vertex 1.05558 1.10645 2.59049 + endloop + endfacet + facet normal 0.466044 -0.0610477 0.882653 + outer loop + vertex 1.05571 1.11133 2.59076 + vertex 1.05231 1.10811 2.59233 + vertex 1.05558 1.10645 2.59049 + endloop + endfacet + facet normal 0.39611 -0.0609485 0.916178 + outer loop + vertex 1.05558 1.10645 2.59049 + vertex 1.05941 1.10984 2.58906 + vertex 1.05571 1.11133 2.59076 + endloop + endfacet + facet normal 0.414647 -0.0863421 0.905877 + outer loop + vertex 1.05914 1.10484 2.5887 + vertex 1.05941 1.10984 2.58906 + vertex 1.05558 1.10645 2.59049 + endloop + endfacet + facet normal 0.483808 -0.0486463 0.873821 + outer loop + vertex 1.05217 1.10323 2.59213 + vertex 1.05204 1.09842 2.59193 + vertex 1.05538 1.10158 2.59026 + endloop + endfacet + facet normal 0.498993 -0.0471442 0.865323 + outer loop + vertex 1.05198 1.09396 2.59173 + vertex 1.05204 1.09842 2.59193 + vertex 1.04885 1.09505 2.59359 + endloop + endfacet + facet normal 0.498707 -0.0481456 0.865432 + outer loop + vertex 1.05198 1.09396 2.59173 + vertex 1.04885 1.09505 2.59359 + vertex 1.04907 1.08983 2.59317 + endloop + endfacet + facet normal 0.500582 -0.0491544 0.864292 + outer loop + vertex 1.04885 1.09505 2.59359 + vertex 1.05204 1.09842 2.59193 + vertex 1.04893 1.09996 2.59382 + endloop + endfacet + facet normal 0.49149 -0.0492499 0.869489 + outer loop + vertex 1.04885 1.09505 2.59359 + vertex 1.04893 1.09996 2.59382 + vertex 1.04561 1.09653 2.5955 + endloop + endfacet + facet normal 0.488962 -0.0560769 0.870501 + outer loop + vertex 1.04547 1.09154 2.59526 + vertex 1.04885 1.09505 2.59359 + vertex 1.04561 1.09653 2.5955 + endloop + endfacet + facet normal 0.467529 -0.0560569 0.882199 + outer loop + vertex 1.04561 1.09653 2.5955 + vertex 1.04209 1.09288 2.59714 + vertex 1.04547 1.09154 2.59526 + endloop + endfacet + facet normal 0.463451 -0.0681753 0.883496 + outer loop + vertex 1.04209 1.09288 2.59714 + vertex 1.04194 1.08797 2.59684 + vertex 1.04547 1.09154 2.59526 + endloop + endfacet + facet normal 0.452913 -0.0549229 0.889861 + outer loop + vertex 1.04547 1.09154 2.59526 + vertex 1.04194 1.08797 2.59684 + vertex 1.04514 1.0867 2.59513 + endloop + endfacet + facet normal 0.480972 -0.0564852 0.874914 + outer loop + vertex 1.04514 1.0867 2.59513 + vertex 1.04907 1.08983 2.59317 + vertex 1.04547 1.09154 2.59526 + endloop + endfacet + facet normal 0.446438 -0.0737892 0.891767 + outer loop + vertex 1.04194 1.08797 2.59684 + vertex 1.04182 1.08353 2.59653 + vertex 1.04514 1.0867 2.59513 + endloop + endfacet + facet normal 0.477081 -0.0679326 0.87623 + outer loop + vertex 1.04235 1.09806 2.5974 + vertex 1.04209 1.09288 2.59714 + vertex 1.04561 1.09653 2.5955 + endloop + endfacet + facet normal 0.481102 -0.0575581 0.874773 + outer loop + vertex 1.04582 1.10158 2.59572 + vertex 1.04235 1.09806 2.5974 + vertex 1.04561 1.09653 2.5955 + endloop + endfacet + facet normal 0.4902 -0.069339 0.868848 + outer loop + vertex 1.04271 1.10328 2.59761 + vertex 1.04235 1.09806 2.5974 + vertex 1.04582 1.10158 2.59572 + endloop + endfacet + facet normal 0.495692 -0.0568318 0.866637 + outer loop + vertex 1.04601 1.10665 2.59595 + vertex 1.04271 1.10328 2.59761 + vertex 1.04582 1.10158 2.59572 + endloop + endfacet + facet normal 0.506682 -0.056955 0.86025 + outer loop + vertex 1.04582 1.10158 2.59572 + vertex 1.04908 1.1049 2.59402 + vertex 1.04601 1.10665 2.59595 + endloop + endfacet + facet normal 0.510194 -0.0490285 0.858661 + outer loop + vertex 1.04908 1.1049 2.59402 + vertex 1.04922 1.10988 2.59422 + vertex 1.04601 1.10665 2.59595 + endloop + endfacet + facet normal 0.512864 -0.0526507 0.856854 + outer loop + vertex 1.04601 1.10665 2.59595 + vertex 1.04922 1.10988 2.59422 + vertex 1.04609 1.11174 2.59621 + endloop + endfacet + facet normal 0.50736 -0.0527291 0.86012 + outer loop + vertex 1.04609 1.11174 2.59621 + vertex 1.04287 1.10835 2.5979 + vertex 1.04601 1.10665 2.59595 + endloop + endfacet + facet normal 0.509906 -0.0559996 0.858406 + outer loop + vertex 1.04256 1.11364 2.59843 + vertex 1.04287 1.10835 2.5979 + vertex 1.04609 1.11174 2.59621 + endloop + endfacet + facet normal 0.513299 -0.0478933 0.856872 + outer loop + vertex 1.04627 1.11691 2.59639 + vertex 1.04256 1.11364 2.59843 + vertex 1.04609 1.11174 2.59621 + endloop + endfacet + facet normal 0.512342 -0.0478796 0.857446 + outer loop + vertex 1.04609 1.11174 2.59621 + vertex 1.04942 1.1149 2.59439 + vertex 1.04627 1.11691 2.59639 + endloop + endfacet + facet normal 0.508404 -0.0559113 0.859302 + outer loop + vertex 1.04942 1.1149 2.59439 + vertex 1.04977 1.12002 2.59452 + vertex 1.04627 1.11691 2.59639 + endloop + endfacet + facet normal 0.500385 -0.0436473 0.864702 + outer loop + vertex 1.04627 1.11691 2.59639 + vertex 1.04977 1.12002 2.59452 + vertex 1.04658 1.12199 2.59646 + endloop + endfacet + facet normal 0.515196 -0.044429 0.85592 + outer loop + vertex 1.04658 1.12199 2.59646 + vertex 1.04322 1.11916 2.59834 + vertex 1.04627 1.11691 2.59639 + endloop + endfacet + facet normal 0.513334 -0.0413661 0.857192 + outer loop + vertex 1.04361 1.12424 2.59835 + vertex 1.04322 1.11916 2.59834 + vertex 1.04658 1.12199 2.59646 + endloop + endfacet + facet normal 0.51393 -0.0403241 0.856884 + outer loop + vertex 1.04689 1.12674 2.59651 + vertex 1.04361 1.12424 2.59835 + vertex 1.04658 1.12199 2.59646 + endloop + endfacet + facet normal 0.482895 -0.0385182 0.874831 + outer loop + vertex 1.04658 1.12199 2.59646 + vertex 1.05001 1.12502 2.5947 + vertex 1.04689 1.12674 2.59651 + endloop + endfacet + facet normal 0.477421 -0.050972 0.877195 + outer loop + vertex 1.05001 1.12502 2.5947 + vertex 1.04997 1.12952 2.59499 + vertex 1.04689 1.12674 2.59651 + endloop + endfacet + facet normal 0.462132 -0.0290075 0.886337 + outer loop + vertex 1.04997 1.12952 2.59499 + vertex 1.04737 1.13037 2.59637 + vertex 1.04689 1.12674 2.59651 + endloop + endfacet + facet normal 0.515328 -0.0371868 0.856186 + outer loop + vertex 1.04737 1.13037 2.59637 + vertex 1.04426 1.12968 2.59822 + vertex 1.04689 1.12674 2.59651 + endloop + endfacet + facet normal 0.516582 -0.0461035 0.854996 + outer loop + vertex 1.04737 1.13037 2.59637 + vertex 1.04691 1.13364 2.59683 + vertex 1.04426 1.12968 2.59822 + endloop + endfacet + facet normal 0.516714 -0.0462218 0.85491 + outer loop + vertex 1.04691 1.13364 2.59683 + vertex 1.04395 1.13489 2.59868 + vertex 1.04426 1.12968 2.59822 + endloop + endfacet + facet normal 0.525853 -0.0451929 0.849374 + outer loop + vertex 1.04426 1.12968 2.59822 + vertex 1.04395 1.13489 2.59868 + vertex 1.0408 1.13155 2.60045 + endloop + endfacet + facet normal 0.524336 -0.0488756 0.850107 + outer loop + vertex 1.04059 1.12642 2.60029 + vertex 1.04426 1.12968 2.59822 + vertex 1.0408 1.13155 2.60045 + endloop + endfacet + facet normal 0.506116 -0.0484792 0.861102 + outer loop + vertex 1.0408 1.13155 2.60045 + vertex 1.03743 1.12825 2.60225 + vertex 1.04059 1.12642 2.60029 + endloop + endfacet + facet normal 0.501558 -0.0585224 0.863142 + outer loop + vertex 1.03743 1.12825 2.60225 + vertex 1.03709 1.12312 2.6021 + vertex 1.04059 1.12642 2.60029 + endloop + endfacet + facet normal 0.493383 -0.0469092 0.868546 + outer loop + vertex 1.04059 1.12642 2.60029 + vertex 1.03709 1.12312 2.6021 + vertex 1.04025 1.12134 2.60021 + endloop + endfacet + facet normal 0.51445 -0.0481237 0.856169 + outer loop + vertex 1.04025 1.12134 2.60021 + vertex 1.04361 1.12424 2.59835 + vertex 1.04059 1.12642 2.60029 + endloop + endfacet + facet normal 0.488691 -0.057392 0.870567 + outer loop + vertex 1.03709 1.12312 2.6021 + vertex 1.03687 1.11808 2.60189 + vertex 1.04025 1.12134 2.60021 + endloop + endfacet + facet normal 0.481239 -0.0471814 0.875319 + outer loop + vertex 1.04025 1.12134 2.60021 + vertex 1.03687 1.11808 2.60189 + vertex 1.03992 1.11652 2.60013 + endloop + endfacet + facet normal 0.50581 -0.0486742 0.86127 + outer loop + vertex 1.03992 1.11652 2.60013 + vertex 1.04322 1.11916 2.59834 + vertex 1.04025 1.12134 2.60021 + endloop + endfacet + facet normal 0.5047 -0.0467692 0.862027 + outer loop + vertex 1.04256 1.11364 2.59843 + vertex 1.04322 1.11916 2.59834 + vertex 1.03992 1.11652 2.60013 + endloop + endfacet + facet normal 0.499792 -0.0527618 0.864537 + outer loop + vertex 1.03939 1.11282 2.60021 + vertex 1.04256 1.11364 2.59843 + vertex 1.03992 1.11652 2.60013 + endloop + endfacet + facet normal 0.468938 -0.0479615 0.881928 + outer loop + vertex 1.03992 1.11652 2.60013 + vertex 1.03688 1.11356 2.60159 + vertex 1.03939 1.11282 2.60021 + endloop + endfacet + facet normal 0.465166 -0.0626432 0.883004 + outer loop + vertex 1.03939 1.11282 2.60021 + vertex 1.03688 1.11356 2.60159 + vertex 1.03738 1.11034 2.60109 + endloop + endfacet + facet normal 0.471804 -0.0694555 0.878964 + outer loop + vertex 1.03939 1.11282 2.60021 + vertex 1.03738 1.11034 2.60109 + vertex 1.03983 1.10951 2.59972 + endloop + endfacet + facet normal 0.50151 -0.0630304 0.862853 + outer loop + vertex 1.03939 1.11282 2.60021 + vertex 1.03983 1.10951 2.59972 + vertex 1.04256 1.11364 2.59843 + endloop + endfacet + facet normal 0.476658 -0.0582193 0.877159 + outer loop + vertex 1.03687 1.11808 2.60189 + vertex 1.03688 1.11356 2.60159 + vertex 1.03992 1.11652 2.60013 + endloop + endfacet + facet normal 0.51105 -0.0553422 0.857768 + outer loop + vertex 1.03764 1.13329 2.60245 + vertex 1.03743 1.12825 2.60225 + vertex 1.0408 1.13155 2.60045 + endloop + endfacet + facet normal 0.518775 -0.0401699 0.853966 + outer loop + vertex 1.04361 1.12424 2.59835 + vertex 1.04426 1.12968 2.59822 + vertex 1.04059 1.12642 2.60029 + endloop + endfacet + facet normal 0.527246 -0.0470201 0.848411 + outer loop + vertex 1.0408 1.13155 2.60045 + vertex 1.04395 1.13489 2.59868 + vertex 1.04088 1.13657 2.60069 + endloop + endfacet + facet normal 0.51452 -0.0471993 0.856178 + outer loop + vertex 1.04088 1.13657 2.60069 + vertex 1.03764 1.13329 2.60245 + vertex 1.0408 1.13155 2.60045 + endloop + endfacet + facet normal 0.516051 -0.0492637 0.85514 + outer loop + vertex 1.03776 1.13827 2.60266 + vertex 1.03764 1.13329 2.60245 + vertex 1.04088 1.13657 2.60069 + endloop + endfacet + facet normal 0.518497 -0.0434176 0.853977 + outer loop + vertex 1.04097 1.14156 2.60088 + vertex 1.03776 1.13827 2.60266 + vertex 1.04088 1.13657 2.60069 + endloop + endfacet + facet normal 0.524527 -0.0433881 0.850287 + outer loop + vertex 1.04088 1.13657 2.60069 + vertex 1.04404 1.1398 2.5989 + vertex 1.04097 1.14156 2.60088 + endloop + endfacet + facet normal 0.521831 -0.0495721 0.851607 + outer loop + vertex 1.04404 1.1398 2.5989 + vertex 1.04425 1.14479 2.59906 + vertex 1.04097 1.14156 2.60088 + endloop + endfacet + facet normal 0.516133 -0.0415951 0.855498 + outer loop + vertex 1.04097 1.14156 2.60088 + vertex 1.04425 1.14479 2.59906 + vertex 1.04104 1.14666 2.60109 + endloop + endfacet + facet normal 0.520026 -0.041549 0.853139 + outer loop + vertex 1.04104 1.14666 2.60109 + vertex 1.03779 1.14326 2.60291 + vertex 1.04097 1.14156 2.60088 + endloop + endfacet + facet normal 0.51882 -0.0399632 0.853949 + outer loop + vertex 1.03743 1.14859 2.60337 + vertex 1.03779 1.14326 2.60291 + vertex 1.04104 1.14666 2.60109 + endloop + endfacet + facet normal 0.518446 -0.0408787 0.854133 + outer loop + vertex 1.04119 1.15184 2.60125 + vertex 1.03743 1.14859 2.60337 + vertex 1.04104 1.14666 2.60109 + endloop + endfacet + facet normal 0.498355 -0.0406473 0.86602 + outer loop + vertex 1.04104 1.14666 2.60109 + vertex 1.04457 1.14992 2.59921 + vertex 1.04119 1.15184 2.60125 + endloop + endfacet + facet normal 0.489992 -0.05924 0.869712 + outer loop + vertex 1.04457 1.14992 2.59921 + vertex 1.04482 1.15503 2.59942 + vertex 1.04119 1.15184 2.60125 + endloop + endfacet + facet normal 0.475762 -0.0378348 0.87876 + outer loop + vertex 1.04119 1.15184 2.60125 + vertex 1.04482 1.15503 2.59942 + vertex 1.04138 1.15689 2.60136 + endloop + endfacet + facet normal 0.514609 -0.0388454 0.856545 + outer loop + vertex 1.04138 1.15689 2.60136 + vertex 1.03804 1.15411 2.60324 + vertex 1.04119 1.15184 2.60125 + endloop + endfacet + facet normal 0.512003 -0.034528 0.85829 + outer loop + vertex 1.0383 1.1591 2.60329 + vertex 1.03804 1.15411 2.60324 + vertex 1.04138 1.15689 2.60136 + endloop + endfacet + facet normal 0.510047 -0.0381447 0.8593 + outer loop + vertex 1.04152 1.16171 2.60149 + vertex 1.0383 1.1591 2.60329 + vertex 1.04138 1.15689 2.60136 + endloop + endfacet + facet normal 0.455863 -0.0374454 0.889262 + outer loop + vertex 1.04138 1.15689 2.60136 + vertex 1.04489 1.15992 2.59969 + vertex 1.04152 1.16171 2.60149 + endloop + endfacet + facet normal 0.448932 -0.0532636 0.891977 + outer loop + vertex 1.04489 1.15992 2.59969 + vertex 1.04494 1.16463 2.59995 + vertex 1.04152 1.16171 2.60149 + endloop + endfacet + facet normal 0.436641 -0.0351702 0.898948 + outer loop + vertex 1.04152 1.16171 2.60149 + vertex 1.04494 1.16463 2.59995 + vertex 1.04176 1.16633 2.60155 + endloop + endfacet + facet normal 0.505449 -0.0383069 0.862006 + outer loop + vertex 1.04176 1.16633 2.60155 + vertex 1.03855 1.16402 2.60334 + vertex 1.04152 1.16171 2.60149 + endloop + endfacet + facet normal 0.505449 -0.0383075 0.862006 + outer loop + vertex 1.03919 1.16941 2.6032 + vertex 1.03855 1.16402 2.60334 + vertex 1.04176 1.16633 2.60155 + endloop + endfacet + facet normal 0.49922 -0.0452647 0.865292 + outer loop + vertex 1.04231 1.16997 2.60143 + vertex 1.03919 1.16941 2.6032 + vertex 1.04176 1.16633 2.60155 + endloop + endfacet + facet normal 0.415418 -0.0310223 0.909101 + outer loop + vertex 1.04491 1.16902 2.60021 + vertex 1.04231 1.16997 2.60143 + vertex 1.04176 1.16633 2.60155 + endloop + endfacet + facet normal 0.501498 -0.0667242 0.862582 + outer loop + vertex 1.04231 1.16997 2.60143 + vertex 1.042 1.1734 2.60187 + vertex 1.03919 1.16941 2.6032 + endloop + endfacet + facet normal 0.429457 -0.0511277 0.901639 + outer loop + vertex 1.04494 1.16463 2.59995 + vertex 1.04491 1.16902 2.60021 + vertex 1.04176 1.16633 2.60155 + endloop + endfacet + facet normal 0.468014 -0.0555126 0.881976 + outer loop + vertex 1.04482 1.15503 2.59942 + vertex 1.04489 1.15992 2.59969 + vertex 1.04138 1.15689 2.60136 + endloop + endfacet + facet normal 0.515797 -0.0366541 0.855926 + outer loop + vertex 1.03804 1.15411 2.60324 + vertex 1.03743 1.14859 2.60337 + vertex 1.04119 1.15184 2.60125 + endloop + endfacet + facet normal 0.509319 -0.0567683 0.858703 + outer loop + vertex 1.04425 1.14479 2.59906 + vertex 1.04457 1.14992 2.59921 + vertex 1.04104 1.14666 2.60109 + endloop + endfacet + facet normal 0.473301 -0.0550637 0.879178 + outer loop + vertex 1.04425 1.14479 2.59906 + vertex 1.04774 1.14799 2.59738 + vertex 1.04457 1.14992 2.59921 + endloop + endfacet + facet normal 0.483608 -0.0698218 0.872496 + outer loop + vertex 1.0473 1.14297 2.59723 + vertex 1.04774 1.14799 2.59738 + vertex 1.04425 1.14479 2.59906 + endloop + endfacet + facet normal 0.493532 -0.0489293 0.86835 + outer loop + vertex 1.04404 1.1398 2.5989 + vertex 1.0473 1.14297 2.59723 + vertex 1.04425 1.14479 2.59906 + endloop + endfacet + facet normal 0.501134 -0.0593976 0.863329 + outer loop + vertex 1.04703 1.13812 2.59705 + vertex 1.0473 1.14297 2.59723 + vertex 1.04404 1.1398 2.5989 + endloop + endfacet + facet normal 0.506469 -0.0472737 0.860961 + outer loop + vertex 1.04395 1.13489 2.59868 + vertex 1.04703 1.13812 2.59705 + vertex 1.04404 1.1398 2.5989 + endloop + endfacet + facet normal 0.518991 -0.0440803 0.853642 + outer loop + vertex 1.03779 1.14326 2.60291 + vertex 1.03776 1.13827 2.60266 + vertex 1.04097 1.14156 2.60088 + endloop + endfacet + facet normal 0.527227 -0.0470655 0.84842 + outer loop + vertex 1.04395 1.13489 2.59868 + vertex 1.04404 1.1398 2.5989 + vertex 1.04088 1.13657 2.60069 + endloop + endfacet + facet normal 0.513392 -0.0561844 0.856313 + outer loop + vertex 1.04691 1.13364 2.59683 + vertex 1.04703 1.13812 2.59705 + vertex 1.04395 1.13489 2.59868 + endloop + endfacet + facet normal 0.513452 -0.0394566 0.85721 + outer loop + vertex 1.04426 1.12968 2.59822 + vertex 1.04361 1.12424 2.59835 + vertex 1.04689 1.12674 2.59651 + endloop + endfacet + facet normal 0.510042 -0.0411145 0.859166 + outer loop + vertex 1.04322 1.11916 2.59834 + vertex 1.04361 1.12424 2.59835 + vertex 1.04025 1.12134 2.60021 + endloop + endfacet + facet normal 0.494465 -0.055882 0.8674 + outer loop + vertex 1.04977 1.12002 2.59452 + vertex 1.05001 1.12502 2.5947 + vertex 1.04658 1.12199 2.59646 + endloop + endfacet + facet normal 0.485791 -0.0547015 0.872361 + outer loop + vertex 1.04942 1.1149 2.59439 + vertex 1.05287 1.11805 2.59267 + vertex 1.04977 1.12002 2.59452 + endloop + endfacet + facet normal 0.471994 -0.0815621 0.877821 + outer loop + vertex 1.05287 1.11805 2.59267 + vertex 1.05379 1.12361 2.59269 + vertex 1.04977 1.12002 2.59452 + endloop + endfacet + facet normal 0.491741 -0.0633991 0.86843 + outer loop + vertex 1.05249 1.11303 2.59252 + vertex 1.05287 1.11805 2.59267 + vertex 1.04942 1.1149 2.59439 + endloop + endfacet + facet normal 0.49824 -0.0499404 0.8656 + outer loop + vertex 1.04922 1.10988 2.59422 + vertex 1.05249 1.11303 2.59252 + vertex 1.04942 1.1149 2.59439 + endloop + endfacet + facet normal 0.499808 -0.0521224 0.864566 + outer loop + vertex 1.05231 1.10811 2.59233 + vertex 1.05249 1.11303 2.59252 + vertex 1.04922 1.10988 2.59422 + endloop + endfacet + facet normal 0.513283 -0.0478675 0.856884 + outer loop + vertex 1.04322 1.11916 2.59834 + vertex 1.04256 1.11364 2.59843 + vertex 1.04627 1.11691 2.59639 + endloop + endfacet + facet normal 0.513973 -0.0502346 0.856334 + outer loop + vertex 1.04922 1.10988 2.59422 + vertex 1.04942 1.1149 2.59439 + vertex 1.04609 1.11174 2.59621 + endloop + endfacet + facet normal 0.501219 -0.0489779 0.863933 + outer loop + vertex 1.04908 1.1049 2.59402 + vertex 1.05231 1.10811 2.59233 + vertex 1.04922 1.10988 2.59422 + endloop + endfacet + facet normal 0.501784 -0.049742 0.863561 + outer loop + vertex 1.05217 1.10323 2.59213 + vertex 1.05231 1.10811 2.59233 + vertex 1.04908 1.1049 2.59402 + endloop + endfacet + facet normal 0.501681 -0.0499847 0.863607 + outer loop + vertex 1.04893 1.09996 2.59382 + vertex 1.05217 1.10323 2.59213 + vertex 1.04908 1.1049 2.59402 + endloop + endfacet + facet normal 0.501419 -0.0499829 0.863759 + outer loop + vertex 1.04893 1.09996 2.59382 + vertex 1.04908 1.1049 2.59402 + vertex 1.04582 1.10158 2.59572 + endloop + endfacet + facet normal 0.502027 -0.0651205 0.862397 + outer loop + vertex 1.04287 1.10835 2.5979 + vertex 1.04271 1.10328 2.59761 + vertex 1.04601 1.10665 2.59595 + endloop + endfacet + facet normal 0.483696 -0.0494437 0.873838 + outer loop + vertex 1.04907 1.08983 2.59317 + vertex 1.04885 1.09505 2.59359 + vertex 1.04547 1.09154 2.59526 + endloop + endfacet + facet normal 0.498161 -0.0578378 0.865154 + outer loop + vertex 1.04561 1.09653 2.5955 + vertex 1.04893 1.09996 2.59382 + vertex 1.04582 1.10158 2.59572 + endloop + endfacet + facet normal 0.500745 -0.0487372 0.864222 + outer loop + vertex 1.05204 1.09842 2.59193 + vertex 1.05217 1.10323 2.59213 + vertex 1.04893 1.09996 2.59382 + endloop + endfacet + facet normal 0.467879 -0.0733749 0.880741 + outer loop + vertex 1.05829 1.09402 2.58817 + vertex 1.05867 1.09981 2.58845 + vertex 1.0551 1.09679 2.59009 + endloop + endfacet + facet normal 0.496447 -0.067945 0.865404 + outer loop + vertex 1.05829 1.09402 2.58817 + vertex 1.05491 1.0896 2.58976 + vertex 1.05795 1.08817 2.5879 + endloop + endfacet + facet normal 0.50134 -0.0550261 0.863499 + outer loop + vertex 1.05467 1.08494 2.5896 + vertex 1.05795 1.08817 2.5879 + vertex 1.05491 1.0896 2.58976 + endloop + endfacet + facet normal 0.506051 -0.0614684 0.860311 + outer loop + vertex 1.05768 1.08311 2.5877 + vertex 1.05795 1.08817 2.5879 + vertex 1.05467 1.08494 2.5896 + endloop + endfacet + facet normal 0.502828 -0.0463612 0.863142 + outer loop + vertex 1.05451 1.09299 2.5902 + vertex 1.05198 1.09396 2.59173 + vertex 1.05242 1.09064 2.59129 + endloop + endfacet + facet normal 0.497895 -0.0473951 0.865941 + outer loop + vertex 1.05242 1.09064 2.59129 + vertex 1.05198 1.09396 2.59173 + vertex 1.04907 1.08983 2.59317 + endloop + endfacet + facet normal 0.477807 -0.0512293 0.87697 + outer loop + vertex 1.04784 1.08384 2.59349 + vertex 1.04907 1.08983 2.59317 + vertex 1.04514 1.0867 2.59513 + endloop + endfacet + facet normal 0.469349 -0.06145 0.880872 + outer loop + vertex 1.04445 1.08295 2.59524 + vertex 1.04784 1.08384 2.59349 + vertex 1.04514 1.0867 2.59513 + endloop + endfacet + facet normal 0.431173 -0.0538358 0.900662 + outer loop + vertex 1.04514 1.0867 2.59513 + vertex 1.04182 1.08353 2.59653 + vertex 1.04445 1.08295 2.59524 + endloop + endfacet + facet normal 0.426689 -0.0754515 0.901246 + outer loop + vertex 1.04445 1.08295 2.59524 + vertex 1.04182 1.08353 2.59653 + vertex 1.04229 1.0804 2.59605 + endloop + endfacet + facet normal 0.433714 -0.0826415 0.897253 + outer loop + vertex 1.04445 1.08295 2.59524 + vertex 1.04229 1.0804 2.59605 + vertex 1.04483 1.07964 2.59475 + endloop + endfacet + facet normal 0.471779 -0.0754644 0.878481 + outer loop + vertex 1.04445 1.08295 2.59524 + vertex 1.04483 1.07964 2.59475 + vertex 1.04784 1.08384 2.59349 + endloop + endfacet + facet normal 0.461482 -0.0662613 0.884671 + outer loop + vertex 1.04784 1.08384 2.59349 + vertex 1.04483 1.07964 2.59475 + vertex 1.04798 1.07847 2.59302 + endloop + endfacet + facet normal 0.454132 -0.0888114 0.886497 + outer loop + vertex 1.04449 1.07489 2.59445 + vertex 1.04798 1.07847 2.59302 + vertex 1.04483 1.07964 2.59475 + endloop + endfacet + facet normal 0.510609 -0.0553022 0.858033 + outer loop + vertex 1.05467 1.08494 2.5896 + vertex 1.05491 1.0896 2.58976 + vertex 1.05172 1.08681 2.59148 + endloop + endfacet + facet normal 0.508583 -0.0561139 0.859182 + outer loop + vertex 1.05446 1.07998 2.5894 + vertex 1.05768 1.08311 2.5877 + vertex 1.05467 1.08494 2.5896 + endloop + endfacet + facet normal 0.510374 -0.0586267 0.857952 + outer loop + vertex 1.05749 1.07812 2.58747 + vertex 1.05768 1.08311 2.5877 + vertex 1.05446 1.07998 2.5894 + endloop + endfacet + facet normal 0.509659 -0.0601235 0.858273 + outer loop + vertex 1.05428 1.07496 2.58915 + vertex 1.05749 1.07812 2.58747 + vertex 1.05446 1.07998 2.5894 + endloop + endfacet + facet normal 0.48725 -0.0643431 0.870889 + outer loop + vertex 1.04784 1.08384 2.59349 + vertex 1.04798 1.07847 2.59302 + vertex 1.05135 1.08186 2.59138 + endloop + endfacet + facet normal 0.445834 -0.0786649 0.891652 + outer loop + vertex 1.04769 1.07324 2.5927 + vertex 1.04798 1.07847 2.59302 + vertex 1.04449 1.07489 2.59445 + endloop + endfacet + facet normal 0.507519 -0.060109 0.859541 + outer loop + vertex 1.05428 1.07496 2.58915 + vertex 1.05446 1.07998 2.5894 + vertex 1.0512 1.07676 2.5911 + endloop + endfacet + facet normal 0.464481 -0.0877719 0.881223 + outer loop + vertex 1.04769 1.07324 2.5927 + vertex 1.04736 1.06799 2.59235 + vertex 1.05097 1.07165 2.59081 + endloop + endfacet + facet normal 0.485258 -0.0690702 0.871639 + outer loop + vertex 1.05376 1.06488 2.58868 + vertex 1.05405 1.06993 2.58891 + vertex 1.05068 1.06661 2.59052 + endloop + endfacet + facet normal 0.497864 -0.0694776 0.864468 + outer loop + vertex 1.05376 1.06488 2.58868 + vertex 1.05706 1.06818 2.58704 + vertex 1.05405 1.06993 2.58891 + endloop + endfacet + facet normal 0.501661 -0.0612844 0.862891 + outer loop + vertex 1.05706 1.06818 2.58704 + vertex 1.05731 1.07313 2.58724 + vertex 1.05405 1.06993 2.58891 + endloop + endfacet + facet normal 0.504547 -0.065251 0.860915 + outer loop + vertex 1.05405 1.06993 2.58891 + vertex 1.05731 1.07313 2.58724 + vertex 1.05428 1.07496 2.58915 + endloop + endfacet + facet normal 0.459705 -0.0673195 0.885516 + outer loop + vertex 1.05932 1.04504 2.58415 + vertex 1.05958 1.04998 2.58439 + vertex 1.05612 1.0467 2.58593 + endloop + endfacet + facet normal 0.444088 -0.0668701 0.893484 + outer loop + vertex 1.05932 1.04504 2.58415 + vertex 1.06272 1.04823 2.5827 + vertex 1.05958 1.04998 2.58439 + endloop + endfacet + facet normal 0.440998 -0.0627484 0.895312 + outer loop + vertex 1.06245 1.04324 2.58248 + vertex 1.06272 1.04823 2.5827 + vertex 1.05932 1.04504 2.58415 + endloop + endfacet + facet normal 0.465231 -0.0652912 0.882778 + outer loop + vertex 1.05638 1.05165 2.58621 + vertex 1.05993 1.05486 2.58458 + vertex 1.05666 1.05642 2.58642 + endloop + endfacet + facet normal 0.444035 -0.0669829 0.893502 + outer loop + vertex 1.06272 1.04823 2.5827 + vertex 1.06313 1.05317 2.58287 + vertex 1.05958 1.04998 2.58439 + endloop + endfacet + facet normal 0.45747 -0.0557299 0.887477 + outer loop + vertex 1.05944 1.06262 2.58537 + vertex 1.05722 1.06014 2.58636 + vertex 1.06005 1.05938 2.58485 + endloop + endfacet + facet normal 0.466237 -0.0657151 0.882216 + outer loop + vertex 1.05944 1.06262 2.58537 + vertex 1.05679 1.06351 2.58684 + vertex 1.05722 1.06014 2.58636 + endloop + endfacet + facet normal 0.494503 -0.0649772 0.866744 + outer loop + vertex 1.05679 1.06351 2.58684 + vertex 1.05706 1.06818 2.58704 + vertex 1.05376 1.06488 2.58868 + endloop + endfacet + facet normal 0.388453 -0.0705192 0.918766 + outer loop + vertex 1.06345 1.06409 2.58373 + vertex 1.06413 1.06981 2.58388 + vertex 1.06014 1.0665 2.58532 + endloop + endfacet + facet normal 0.461943 -0.0601441 0.884868 + outer loop + vertex 1.05731 1.07313 2.58724 + vertex 1.05706 1.06818 2.58704 + vertex 1.06051 1.07138 2.58546 + endloop + endfacet + facet normal 0.508037 -0.0578848 0.859388 + outer loop + vertex 1.05731 1.07313 2.58724 + vertex 1.05749 1.07812 2.58747 + vertex 1.05428 1.07496 2.58915 + endloop + endfacet + facet normal 0.370658 -0.0634401 0.9266 + outer loop + vertex 1.06434 1.07491 2.58413 + vertex 1.06442 1.07987 2.58443 + vertex 1.0607 1.07637 2.58568 + endloop + endfacet + facet normal 0.459007 -0.0579499 0.886541 + outer loop + vertex 1.05768 1.08311 2.5877 + vertex 1.05749 1.07812 2.58747 + vertex 1.06084 1.08133 2.58595 + endloop + endfacet + facet normal 0.444491 -0.0662085 0.893333 + outer loop + vertex 1.05829 1.09402 2.58817 + vertex 1.05795 1.08817 2.5879 + vertex 1.06142 1.09121 2.5864 + endloop + endfacet + facet normal 0.352093 -0.0739878 0.933036 + outer loop + vertex 1.06454 1.0848 2.58476 + vertex 1.06473 1.08971 2.58508 + vertex 1.06106 1.0863 2.58619 + endloop + endfacet + facet normal 0.296204 -0.081741 0.951621 + outer loop + vertex 1.05941 1.10984 2.58906 + vertex 1.06372 1.11369 2.58804 + vertex 1.05944 1.11475 2.58947 + endloop + endfacet + facet normal 0.290836 -0.102868 0.951227 + outer loop + vertex 1.06372 1.11369 2.58804 + vertex 1.0636 1.11864 2.58862 + vertex 1.05944 1.11475 2.58947 + endloop + endfacet + facet normal 0.277302 -0.0871775 0.95682 + outer loop + vertex 1.05944 1.11475 2.58947 + vertex 1.0636 1.11864 2.58862 + vertex 1.05962 1.1196 2.58986 + endloop + endfacet + facet normal 0.225388 -0.125427 0.966162 + outer loop + vertex 1.06885 1.11324 2.58679 + vertex 1.06832 1.11816 2.58755 + vertex 1.06372 1.11369 2.58804 + endloop + endfacet + facet normal 0.299122 -0.11707 0.947006 + outer loop + vertex 1.06389 1.10841 2.58736 + vertex 1.06253 1.10309 2.58713 + vertex 1.06646 1.10561 2.5862 + endloop + endfacet + facet normal 0.210914 -0.111824 0.971087 + outer loop + vertex 1.06848 1.09894 2.58501 + vertex 1.0695 1.10424 2.5854 + vertex 1.06552 1.10133 2.58593 + endloop + endfacet + facet normal 0.319795 -0.0731951 0.944655 + outer loop + vertex 1.06453 1.09763 2.58577 + vertex 1.06216 1.09512 2.58638 + vertex 1.06491 1.09431 2.58538 + endloop + endfacet + facet normal 0.316232 -0.0726941 0.945893 + outer loop + vertex 1.06975 1.05006 2.58015 + vertex 1.06985 1.05476 2.58047 + vertex 1.06623 1.05141 2.58143 + endloop + endfacet + facet normal 0.339133 -0.0709661 0.938058 + outer loop + vertex 1.06925 1.03991 2.57957 + vertex 1.06957 1.04505 2.57984 + vertex 1.06573 1.04151 2.58096 + endloop + endfacet + facet normal 0.338799 -0.0717536 0.938119 + outer loop + vertex 1.06534 1.03659 2.58073 + vertex 1.06925 1.03991 2.57957 + vertex 1.06573 1.04151 2.58096 + endloop + endfacet + facet normal 0.343623 -0.0782375 0.935843 + outer loop + vertex 1.0685 1.0342 2.57937 + vertex 1.06925 1.03991 2.57957 + vertex 1.06534 1.03659 2.58073 + endloop + endfacet + facet normal 0.341613 -0.0811651 0.936329 + outer loop + vertex 1.06465 1.03271 2.58064 + vertex 1.0685 1.0342 2.57937 + vertex 1.06534 1.03659 2.58073 + endloop + endfacet + facet normal 0.38097 -0.0878331 0.920406 + outer loop + vertex 1.06534 1.03659 2.58073 + vertex 1.0619 1.03345 2.58185 + vertex 1.06465 1.03271 2.58064 + endloop + endfacet + facet normal 0.382025 -0.0891905 0.919838 + outer loop + vertex 1.06211 1.03819 2.58223 + vertex 1.0619 1.03345 2.58185 + vertex 1.06534 1.03659 2.58073 + endloop + endfacet + facet normal 0.417206 -0.0895116 0.904393 + outer loop + vertex 1.0619 1.03345 2.58185 + vertex 1.06211 1.03819 2.58223 + vertex 1.05813 1.0344 2.58369 + endloop + endfacet + facet normal 0.410577 -0.115949 0.904424 + outer loop + vertex 1.0619 1.03345 2.58185 + vertex 1.05813 1.0344 2.58369 + vertex 1.05859 1.02876 2.58275 + endloop + endfacet + facet normal 0.38601 -0.0960849 0.917477 + outer loop + vertex 1.06239 1.03011 2.5813 + vertex 1.0619 1.03345 2.58185 + vertex 1.05859 1.02876 2.58275 + endloop + endfacet + facet normal 0.386922 -0.0994546 0.916734 + outer loop + vertex 1.06239 1.03011 2.5813 + vertex 1.05859 1.02876 2.58275 + vertex 1.06155 1.02627 2.58123 + endloop + endfacet + facet normal 0.35942 -0.0936704 0.928463 + outer loop + vertex 1.0651 1.02947 2.58018 + vertex 1.06239 1.03011 2.5813 + vertex 1.06155 1.02627 2.58123 + endloop + endfacet + facet normal 0.355106 -0.0881486 0.930661 + outer loop + vertex 1.06472 1.02483 2.57989 + vertex 1.0651 1.02947 2.58018 + vertex 1.06155 1.02627 2.58123 + endloop + endfacet + facet normal 0.347364 -0.106075 0.931711 + outer loop + vertex 1.06078 1.02152 2.58098 + vertex 1.06472 1.02483 2.57989 + vertex 1.06155 1.02627 2.58123 + endloop + endfacet + facet normal 0.358512 -0.107648 0.927298 + outer loop + vertex 1.06155 1.02627 2.58123 + vertex 1.05751 1.02294 2.58241 + vertex 1.06078 1.02152 2.58098 + endloop + endfacet + facet normal 0.348292 -0.131934 0.928055 + outer loop + vertex 1.05751 1.02294 2.58241 + vertex 1.05711 1.01817 2.58188 + vertex 1.06078 1.02152 2.58098 + endloop + endfacet + facet normal 0.33398 -0.114194 0.935637 + outer loop + vertex 1.06078 1.02152 2.58098 + vertex 1.05711 1.01817 2.58188 + vertex 1.05989 1.01765 2.58083 + endloop + endfacet + facet normal 0.330589 -0.11346 0.93693 + outer loop + vertex 1.05989 1.01765 2.58083 + vertex 1.06371 1.01921 2.57967 + vertex 1.06078 1.02152 2.58098 + endloop + endfacet + facet normal 0.33269 -0.119739 0.935404 + outer loop + vertex 1.05989 1.01765 2.58083 + vertex 1.06024 1.01444 2.58029 + vertex 1.06371 1.01921 2.57967 + endloop + endfacet + facet normal 0.312496 -0.103877 0.944222 + outer loop + vertex 1.06371 1.01921 2.57967 + vertex 1.06024 1.01444 2.58029 + vertex 1.06391 1.01402 2.57903 + endloop + endfacet + facet normal 0.309149 -0.127478 0.942431 + outer loop + vertex 1.05979 1.00987 2.57982 + vertex 1.06391 1.01402 2.57903 + vertex 1.06024 1.01444 2.58029 + endloop + endfacet + facet normal 0.310868 -0.127586 0.941851 + outer loop + vertex 1.05979 1.00987 2.57982 + vertex 1.06024 1.01444 2.58029 + vertex 1.05661 1.0112 2.58105 + endloop + endfacet + facet normal 0.30154 -0.149681 0.941631 + outer loop + vertex 1.05578 1.00679 2.58061 + vertex 1.05979 1.00987 2.57982 + vertex 1.05661 1.0112 2.58105 + endloop + endfacet + facet normal 0.271646 -0.145057 0.951403 + outer loop + vertex 1.05661 1.0112 2.58105 + vertex 1.05269 1.00801 2.58168 + vertex 1.05578 1.00679 2.58061 + endloop + endfacet + facet normal 0.264153 -0.163347 0.950548 + outer loop + vertex 1.05269 1.00801 2.58168 + vertex 1.05258 1.00458 2.58112 + vertex 1.05578 1.00679 2.58061 + endloop + endfacet + facet normal 0.275313 -0.180993 0.944163 + outer loop + vertex 1.05578 1.00679 2.58061 + vertex 1.05258 1.00458 2.58112 + vertex 1.05428 1.00309 2.58034 + endloop + endfacet + facet normal 0.287913 -0.185747 0.93947 + outer loop + vertex 1.05428 1.00309 2.58034 + vertex 1.05846 1.0042 2.57928 + vertex 1.05578 1.00679 2.58061 + endloop + endfacet + facet normal 0.243351 -0.21814 0.94509 + outer loop + vertex 1.05428 1.00309 2.58034 + vertex 1.05258 1.00458 2.58112 + vertex 1.05092 1.00126 2.58078 + endloop + endfacet + facet normal 0.251495 -0.234529 0.939014 + outer loop + vertex 1.05428 1.00309 2.58034 + vertex 1.05092 1.00126 2.58078 + vertex 1.05329 0.998732 2.57952 + endloop + endfacet + facet normal 0.298758 -0.242316 0.923053 + outer loop + vertex 1.05428 1.00309 2.58034 + vertex 1.05329 0.998732 2.57952 + vertex 1.05846 1.0042 2.57928 + endloop + endfacet + facet normal 0.279236 -0.155137 0.947607 + outer loop + vertex 1.0535 1.01328 2.58231 + vertex 1.05269 1.00801 2.58168 + vertex 1.05661 1.0112 2.58105 + endloop + endfacet + facet normal 0.293783 -0.132848 0.946596 + outer loop + vertex 1.05749 1.01494 2.5813 + vertex 1.0535 1.01328 2.58231 + vertex 1.05661 1.0112 2.58105 + endloop + endfacet + facet normal 0.294641 -0.135284 0.945984 + outer loop + vertex 1.05749 1.01494 2.5813 + vertex 1.05711 1.01817 2.58188 + vertex 1.0535 1.01328 2.58231 + endloop + endfacet + facet normal 0.322533 -0.15699 0.933449 + outer loop + vertex 1.05711 1.01817 2.58188 + vertex 1.0532 1.01853 2.58329 + vertex 1.0535 1.01328 2.58231 + endloop + endfacet + facet normal 0.309875 -0.161775 0.936913 + outer loop + vertex 1.05846 1.0042 2.57928 + vertex 1.05979 1.00987 2.57982 + vertex 1.05578 1.00679 2.58061 + endloop + endfacet + facet normal 0.286367 -0.157014 0.945167 + outer loop + vertex 1.05846 1.0042 2.57928 + vertex 1.06365 1.00893 2.57849 + vertex 1.05979 1.00987 2.57982 + endloop + endfacet + facet normal 0.269191 -0.136766 0.953326 + outer loop + vertex 1.06352 1.00379 2.57779 + vertex 1.06365 1.00893 2.57849 + vertex 1.05846 1.0042 2.57928 + endloop + endfacet + facet normal 0.26301 -0.188094 0.94628 + outer loop + vertex 1.05859 0.998667 2.57815 + vertex 1.06352 1.00379 2.57779 + vertex 1.05846 1.0042 2.57928 + endloop + endfacet + facet normal 0.24418 -0.18952 0.95103 + outer loop + vertex 1.05846 1.0042 2.57928 + vertex 1.05329 0.998732 2.57952 + vertex 1.05859 0.998667 2.57815 + endloop + endfacet + facet normal 0.236284 -0.16157 0.958157 + outer loop + vertex 1.06374 0.998833 2.5769 + vertex 1.06352 1.00379 2.57779 + vertex 1.05859 0.998667 2.57815 + endloop + endfacet + facet normal 0.235893 -0.19438 0.95214 + outer loop + vertex 1.06374 0.998833 2.5769 + vertex 1.05859 0.998667 2.57815 + vertex 1.05876 0.993437 2.57704 + endloop + endfacet + facet normal 0.211892 -0.171985 0.962041 + outer loop + vertex 1.06306 0.994921 2.57635 + vertex 1.06374 0.998833 2.5769 + vertex 1.05876 0.993437 2.57704 + endloop + endfacet + facet normal 0.214656 -0.181033 0.959766 + outer loop + vertex 1.06306 0.994921 2.57635 + vertex 1.05876 0.993437 2.57704 + vertex 1.06132 0.991224 2.57604 + endloop + endfacet + facet normal 0.22458 -0.185421 0.956652 + outer loop + vertex 1.06543 0.99411 2.57564 + vertex 1.06306 0.994921 2.57635 + vertex 1.06132 0.991224 2.57604 + endloop + endfacet + facet normal 0.222358 -0.1821 0.957808 + outer loop + vertex 1.06369 0.988921 2.57506 + vertex 1.06543 0.99411 2.57564 + vertex 1.06132 0.991224 2.57604 + endloop + endfacet + facet normal 0.212475 -0.19237 0.958044 + outer loop + vertex 1.05959 0.987572 2.57569 + vertex 1.06369 0.988921 2.57506 + vertex 1.06132 0.991224 2.57604 + endloop + endfacet + facet normal 0.202617 -0.187992 0.961044 + outer loop + vertex 1.06132 0.991224 2.57604 + vertex 1.05737 0.988596 2.57636 + vertex 1.05959 0.987572 2.57569 + endloop + endfacet + facet normal 0.197018 -0.199425 0.959903 + outer loop + vertex 1.05959 0.987572 2.57569 + vertex 1.05737 0.988596 2.57636 + vertex 1.0569 0.98555 2.57583 + endloop + endfacet + facet normal 0.209813 -0.216925 0.953374 + outer loop + vertex 1.05959 0.987572 2.57569 + vertex 1.0569 0.98555 2.57583 + vertex 1.05862 0.983621 2.57501 + endloop + endfacet + facet normal 0.22007 -0.218964 0.950591 + outer loop + vertex 1.05959 0.987572 2.57569 + vertex 1.05862 0.983621 2.57501 + vertex 1.06369 0.988921 2.57506 + endloop + endfacet + facet normal 0.205169 -0.191998 0.95971 + outer loop + vertex 1.05876 0.993437 2.57704 + vertex 1.05737 0.988596 2.57636 + vertex 1.06132 0.991224 2.57604 + endloop + endfacet + facet normal 0.31954 -0.138328 0.937422 + outer loop + vertex 1.06024 1.01444 2.58029 + vertex 1.05749 1.01494 2.5813 + vertex 1.05661 1.0112 2.58105 + endloop + endfacet + facet normal 0.297521 -0.114919 0.947774 + outer loop + vertex 1.06365 1.00893 2.57849 + vertex 1.06391 1.01402 2.57903 + vertex 1.05979 1.00987 2.57982 + endloop + endfacet + facet normal 0.323048 -0.121329 0.938573 + outer loop + vertex 1.05989 1.01765 2.58083 + vertex 1.05749 1.01494 2.5813 + vertex 1.06024 1.01444 2.58029 + endloop + endfacet + facet normal 0.330916 -0.128947 0.934809 + outer loop + vertex 1.05989 1.01765 2.58083 + vertex 1.05711 1.01817 2.58188 + vertex 1.05749 1.01494 2.5813 + endloop + endfacet + facet normal 0.325971 -0.130978 0.936263 + outer loop + vertex 1.05711 1.01817 2.58188 + vertex 1.05751 1.02294 2.58241 + vertex 1.0532 1.01853 2.58329 + endloop + endfacet + facet normal 0.355323 -0.162836 0.920451 + outer loop + vertex 1.0532 1.01853 2.58329 + vertex 1.05751 1.02294 2.58241 + vertex 1.05342 1.02414 2.5842 + endloop + endfacet + facet normal 0.367658 -0.122738 0.921826 + outer loop + vertex 1.05751 1.02294 2.58241 + vertex 1.05859 1.02876 2.58275 + vertex 1.05342 1.02414 2.5842 + endloop + endfacet + facet normal 0.393404 -0.156471 0.905953 + outer loop + vertex 1.05342 1.02414 2.5842 + vertex 1.05859 1.02876 2.58275 + vertex 1.05476 1.02972 2.58458 + endloop + endfacet + facet normal 0.341592 -0.0982155 0.934702 + outer loop + vertex 1.06371 1.01921 2.57967 + vertex 1.06472 1.02483 2.57989 + vertex 1.06078 1.02152 2.58098 + endloop + endfacet + facet normal 0.362275 -0.0816809 0.928485 + outer loop + vertex 1.06465 1.03271 2.58064 + vertex 1.06239 1.03011 2.5813 + vertex 1.0651 1.02947 2.58018 + endloop + endfacet + facet normal 0.369359 -0.123013 0.921109 + outer loop + vertex 1.05859 1.02876 2.58275 + vertex 1.05751 1.02294 2.58241 + vertex 1.06155 1.02627 2.58123 + endloop + endfacet + facet normal 0.378358 -0.0977037 0.920489 + outer loop + vertex 1.06465 1.03271 2.58064 + vertex 1.0619 1.03345 2.58185 + vertex 1.06239 1.03011 2.5813 + endloop + endfacet + facet normal 0.403902 -0.116971 0.907293 + outer loop + vertex 1.05813 1.0344 2.58369 + vertex 1.05476 1.02972 2.58458 + vertex 1.05859 1.02876 2.58275 + endloop + endfacet + facet normal 0.342954 -0.0853779 0.935464 + outer loop + vertex 1.06465 1.03271 2.58064 + vertex 1.0651 1.02947 2.58018 + vertex 1.0685 1.0342 2.57937 + endloop + endfacet + facet normal 0.388046 -0.0610329 0.919617 + outer loop + vertex 1.06272 1.04823 2.5827 + vertex 1.06245 1.04324 2.58248 + vertex 1.06598 1.04652 2.58121 + endloop + endfacet + facet normal 0.38849 -0.0747706 0.918414 + outer loop + vertex 1.06573 1.04151 2.58096 + vertex 1.06211 1.03819 2.58223 + vertex 1.06534 1.03659 2.58073 + endloop + endfacet + facet normal 0.433871 -0.0773549 0.897648 + outer loop + vertex 1.05895 1.04 2.58389 + vertex 1.06245 1.04324 2.58248 + vertex 1.05932 1.04504 2.58415 + endloop + endfacet + facet normal 0.434638 -0.103273 0.894664 + outer loop + vertex 1.05273 1.04825 2.58776 + vertex 1.05235 1.04302 2.58734 + vertex 1.05612 1.0467 2.58593 + endloop + endfacet + facet normal 0.395307 -0.0976278 0.913346 + outer loop + vertex 1.05584 1.04174 2.5856 + vertex 1.0521 1.03803 2.58682 + vertex 1.05538 1.03694 2.58528 + endloop + endfacet + facet normal 0.439391 -0.100502 0.892656 + outer loop + vertex 1.04949 1.04996 2.58947 + vertex 1.05316 1.05343 2.58805 + vertex 1.04999 1.05474 2.58976 + endloop + endfacet + facet normal 0.328949 -0.130303 0.935315 + outer loop + vertex 1.04343 1.05359 2.59228 + vertex 1.04245 1.048 2.59184 + vertex 1.04649 1.05157 2.59092 + endloop + endfacet + facet normal 0.26386 -0.120563 0.956997 + outer loop + vertex 1.04245 1.048 2.59184 + vertex 1.04343 1.05359 2.59228 + vertex 1.03837 1.04845 2.59303 + endloop + endfacet + facet normal 0.258302 -0.159914 0.952737 + outer loop + vertex 1.03813 1.04354 2.59227 + vertex 1.04245 1.048 2.59184 + vertex 1.03837 1.04845 2.59303 + endloop + endfacet + facet normal 0.306072 -0.164971 0.937606 + outer loop + vertex 1.03837 1.04845 2.59303 + vertex 1.04343 1.05359 2.59228 + vertex 1.03867 1.05362 2.59383 + endloop + endfacet + facet normal 0.307775 -0.132506 0.942187 + outer loop + vertex 1.04343 1.05359 2.59228 + vertex 1.04317 1.05866 2.59308 + vertex 1.03867 1.05362 2.59383 + endloop + endfacet + facet normal 0.343155 -0.166747 0.924359 + outer loop + vertex 1.03867 1.05362 2.59383 + vertex 1.04317 1.05866 2.59308 + vertex 1.03883 1.05893 2.59473 + endloop + endfacet + facet normal 0.430431 -0.0975666 0.897335 + outer loop + vertex 1.04709 1.06299 2.59195 + vertex 1.04692 1.05856 2.59155 + vertex 1.05033 1.0618 2.59027 + endloop + endfacet + facet normal 0.376118 -0.155766 0.913385 + outer loop + vertex 1.03883 1.05893 2.59473 + vertex 1.04347 1.06375 2.59364 + vertex 1.0401 1.06432 2.59513 + endloop + endfacet + facet normal 0.341732 -0.127606 0.931094 + outer loop + vertex 1.03997 1.06771 2.59564 + vertex 1.03758 1.06494 2.59614 + vertex 1.0401 1.06432 2.59513 + endloop + endfacet + facet normal 0.323463 -0.110272 0.939793 + outer loop + vertex 1.03997 1.06771 2.59564 + vertex 1.03722 1.06817 2.59664 + vertex 1.03758 1.06494 2.59614 + endloop + endfacet + facet normal 0.40283 -0.0943509 0.910399 + outer loop + vertex 1.04353 1.06916 2.59428 + vertex 1.04449 1.07489 2.59445 + vertex 1.04081 1.07165 2.59574 + endloop + endfacet + facet normal 0.43652 -0.0994998 0.894176 + outer loop + vertex 1.04353 1.06916 2.59428 + vertex 1.04769 1.07324 2.5927 + vertex 1.04449 1.07489 2.59445 + endloop + endfacet + facet normal 0.366875 -0.115282 0.923099 + outer loop + vertex 1.03844 1.07866 2.59747 + vertex 1.03753 1.07289 2.59711 + vertex 1.04149 1.07648 2.59598 + endloop + endfacet + facet normal 0.408937 -0.0740042 0.909557 + outer loop + vertex 1.04182 1.08353 2.59653 + vertex 1.04194 1.08797 2.59684 + vertex 1.03827 1.0839 2.59816 + endloop + endfacet + facet normal 0.428931 -0.0957052 0.898253 + outer loop + vertex 1.03827 1.0839 2.59816 + vertex 1.04194 1.08797 2.59684 + vertex 1.03852 1.08888 2.59857 + endloop + endfacet + facet normal 0.435865 -0.0681937 0.897425 + outer loop + vertex 1.04194 1.08797 2.59684 + vertex 1.04209 1.09288 2.59714 + vertex 1.03852 1.08888 2.59857 + endloop + endfacet + facet normal 0.448815 -0.0824837 0.88981 + outer loop + vertex 1.03852 1.08888 2.59857 + vertex 1.04209 1.09288 2.59714 + vertex 1.03835 1.09409 2.59914 + endloop + endfacet + facet normal 0.453203 -0.0673524 0.888859 + outer loop + vertex 1.04209 1.09288 2.59714 + vertex 1.04235 1.09806 2.5974 + vertex 1.03835 1.09409 2.59914 + endloop + endfacet + facet normal 0.463705 -0.0808062 0.882297 + outer loop + vertex 1.03835 1.09409 2.59914 + vertex 1.04235 1.09806 2.5974 + vertex 1.03921 1.0998 2.59921 + endloop + endfacet + facet normal 0.46945 -0.0683594 0.880309 + outer loop + vertex 1.04235 1.09806 2.5974 + vertex 1.04271 1.10328 2.59761 + vertex 1.03921 1.0998 2.59921 + endloop + endfacet + facet normal 0.477276 -0.078599 0.875231 + outer loop + vertex 1.03921 1.0998 2.59921 + vertex 1.04271 1.10328 2.59761 + vertex 1.03965 1.10491 2.59943 + endloop + endfacet + facet normal 0.483165 -0.0651471 0.873102 + outer loop + vertex 1.04271 1.10328 2.59761 + vertex 1.04287 1.10835 2.5979 + vertex 1.03965 1.10491 2.59943 + endloop + endfacet + facet normal 0.490193 -0.0737716 0.868486 + outer loop + vertex 1.03965 1.10491 2.59943 + vertex 1.04287 1.10835 2.5979 + vertex 1.03983 1.10951 2.59972 + endloop + endfacet + facet normal 0.495318 -0.0576959 0.866794 + outer loop + vertex 1.04256 1.11364 2.59843 + vertex 1.03983 1.10951 2.59972 + vertex 1.04287 1.10835 2.5979 + endloop + endfacet + facet normal 0.256235 -0.137688 0.956758 + outer loop + vertex 1.02764 1.08265 2.60179 + vertex 1.02725 1.07848 2.60129 + vertex 1.03091 1.08149 2.60075 + endloop + endfacet + facet normal 0.386276 -0.100283 0.916915 + outer loop + vertex 1.03231 1.09772 2.60219 + vertex 1.03213 1.09311 2.60176 + vertex 1.03559 1.09657 2.60068 + endloop + endfacet + facet normal 0.392097 -0.0828354 0.916187 + outer loop + vertex 1.03612 1.1015 2.6009 + vertex 1.03231 1.09772 2.60219 + vertex 1.03559 1.09657 2.60068 + endloop + endfacet + facet normal 0.44187 -0.0871571 0.892835 + outer loop + vertex 1.03559 1.09657 2.60068 + vertex 1.03921 1.0998 2.59921 + vertex 1.03612 1.1015 2.6009 + endloop + endfacet + facet normal 0.446832 -0.0766387 0.891329 + outer loop + vertex 1.03921 1.0998 2.59921 + vertex 1.03965 1.10491 2.59943 + vertex 1.03612 1.1015 2.6009 + endloop + endfacet + facet normal 0.43429 -0.0765738 0.897512 + outer loop + vertex 1.03835 1.09409 2.59914 + vertex 1.03921 1.0998 2.59921 + vertex 1.03559 1.09657 2.60068 + endloop + endfacet + facet normal 0.426134 -0.0874499 0.900424 + outer loop + vertex 1.03488 1.09268 2.60064 + vertex 1.03835 1.09409 2.59914 + vertex 1.03559 1.09657 2.60068 + endloop + endfacet + facet normal 0.428086 -0.0939396 0.898842 + outer loop + vertex 1.03488 1.09268 2.60064 + vertex 1.03524 1.08944 2.60013 + vertex 1.03835 1.09409 2.59914 + endloop + endfacet + facet normal 0.416957 -0.0852029 0.904924 + outer loop + vertex 1.03835 1.09409 2.59914 + vertex 1.03524 1.08944 2.60013 + vertex 1.03852 1.08888 2.59857 + endloop + endfacet + facet normal 0.366039 -0.0766467 0.927438 + outer loop + vertex 1.03559 1.09657 2.60068 + vertex 1.03213 1.09311 2.60176 + vertex 1.03488 1.09268 2.60064 + endloop + endfacet + facet normal 0.363371 -0.0923818 0.927053 + outer loop + vertex 1.03488 1.09268 2.60064 + vertex 1.03213 1.09311 2.60176 + vertex 1.03261 1.08993 2.60126 + endloop + endfacet + facet normal 0.406932 -0.100646 0.907897 + outer loop + vertex 1.03276 1.10292 2.60257 + vertex 1.03231 1.09772 2.60219 + vertex 1.03612 1.1015 2.6009 + endloop + endfacet + facet normal 0.41382 -0.0827907 0.906586 + outer loop + vertex 1.03667 1.10645 2.6011 + vertex 1.03276 1.10292 2.60257 + vertex 1.03612 1.1015 2.6009 + endloop + endfacet + facet normal 0.454336 -0.0864332 0.886627 + outer loop + vertex 1.03612 1.1015 2.6009 + vertex 1.03965 1.10491 2.59943 + vertex 1.03667 1.10645 2.6011 + endloop + endfacet + facet normal 0.459964 -0.0736292 0.88488 + outer loop + vertex 1.03965 1.10491 2.59943 + vertex 1.03983 1.10951 2.59972 + vertex 1.03667 1.10645 2.6011 + endloop + endfacet + facet normal 0.467578 -0.0836911 0.879981 + outer loop + vertex 1.03983 1.10951 2.59972 + vertex 1.03738 1.11034 2.60109 + vertex 1.03667 1.10645 2.6011 + endloop + endfacet + facet normal 0.433809 -0.0774726 0.897668 + outer loop + vertex 1.03738 1.11034 2.60109 + vertex 1.03377 1.10887 2.60271 + vertex 1.03667 1.10645 2.6011 + endloop + endfacet + facet normal 0.43164 -0.0703625 0.899298 + outer loop + vertex 1.03738 1.11034 2.60109 + vertex 1.03688 1.11356 2.60159 + vertex 1.03377 1.10887 2.60271 + endloop + endfacet + facet normal 0.443908 -0.0801316 0.892482 + outer loop + vertex 1.03688 1.11356 2.60159 + vertex 1.03353 1.11415 2.60331 + vertex 1.03377 1.10887 2.60271 + endloop + endfacet + facet normal 0.422153 -0.0940935 0.901628 + outer loop + vertex 1.03377 1.10887 2.60271 + vertex 1.03276 1.10292 2.60257 + vertex 1.03667 1.10645 2.6011 + endloop + endfacet + facet normal 0.390239 -0.107152 0.914457 + outer loop + vertex 1.03017 1.11467 2.60495 + vertex 1.02752 1.11513 2.60614 + vertex 1.02672 1.11125 2.60602 + endloop + endfacet + facet normal 0.416713 -0.0828097 0.905259 + outer loop + vertex 1.03377 1.10887 2.60271 + vertex 1.03353 1.11415 2.60331 + vertex 1.0299 1.10998 2.6046 + endloop + endfacet + facet normal 0.438024 -0.0790117 0.895484 + outer loop + vertex 1.02973 1.11786 2.60545 + vertex 1.03017 1.11467 2.60495 + vertex 1.03317 1.11927 2.60389 + endloop + endfacet + facet normal 0.44748 -0.0593324 0.892324 + outer loop + vertex 1.03688 1.11356 2.60159 + vertex 1.03687 1.11808 2.60189 + vertex 1.03353 1.11415 2.60331 + endloop + endfacet + facet normal 0.378512 -0.086176 0.921576 + outer loop + vertex 1.02709 1.12275 2.60701 + vertex 1.0273 1.12778 2.60739 + vertex 1.02336 1.1236 2.60862 + endloop + endfacet + facet normal 0.398501 -0.108203 0.910763 + outer loop + vertex 1.02336 1.1236 2.60862 + vertex 1.0273 1.12778 2.60739 + vertex 1.02339 1.12901 2.60925 + endloop + endfacet + facet normal 0.4072 -0.079189 0.9099 + outer loop + vertex 1.0273 1.12778 2.60739 + vertex 1.02766 1.13306 2.60769 + vertex 1.02339 1.12901 2.60925 + endloop + endfacet + facet normal 0.418927 -0.0941443 0.903126 + outer loop + vertex 1.02339 1.12901 2.60925 + vertex 1.02766 1.13306 2.60769 + vertex 1.02441 1.1348 2.60938 + endloop + endfacet + facet normal 0.378936 -0.0875628 0.921271 + outer loop + vertex 1.02339 1.12901 2.60925 + vertex 1.02441 1.1348 2.60938 + vertex 1.02061 1.1315 2.61063 + endloop + endfacet + facet normal 0.369674 -0.0993107 0.923839 + outer loop + vertex 1.01982 1.12765 2.61053 + vertex 1.02339 1.12901 2.60925 + vertex 1.02061 1.1315 2.61063 + endloop + endfacet + facet normal 0.277962 -0.0812119 0.957153 + outer loop + vertex 1.02061 1.1315 2.61063 + vertex 1.01711 1.12814 2.61136 + vertex 1.01982 1.12765 2.61053 + endloop + endfacet + facet normal 0.273778 -0.102513 0.956314 + outer loop + vertex 1.01982 1.12765 2.61053 + vertex 1.01711 1.12814 2.61136 + vertex 1.01751 1.12507 2.61092 + endloop + endfacet + facet normal 0.304306 -0.1318 0.943412 + outer loop + vertex 1.01982 1.12765 2.61053 + vertex 1.01751 1.12507 2.61092 + vertex 1.01996 1.12434 2.61002 + endloop + endfacet + facet normal 0.296818 -0.102584 0.949408 + outer loop + vertex 1.01722 1.13257 2.6118 + vertex 1.01711 1.12814 2.61136 + vertex 1.02061 1.1315 2.61063 + endloop + endfacet + facet normal 0.302241 -0.0853599 0.949402 + outer loop + vertex 1.02118 1.13638 2.61089 + vertex 1.01722 1.13257 2.6118 + vertex 1.02061 1.1315 2.61063 + endloop + endfacet + facet normal 0.317725 -0.103099 0.942561 + outer loop + vertex 1.01762 1.13756 2.61221 + vertex 1.01722 1.13257 2.6118 + vertex 1.02118 1.13638 2.61089 + endloop + endfacet + facet normal 0.32414 -0.0834465 0.942322 + outer loop + vertex 1.02174 1.14124 2.61112 + vertex 1.01762 1.13756 2.61221 + vertex 1.02118 1.13638 2.61089 + endloop + endfacet + facet normal 0.402244 -0.0908876 0.91101 + outer loop + vertex 1.02118 1.13638 2.61089 + vertex 1.02499 1.13999 2.60956 + vertex 1.02174 1.14124 2.61112 + endloop + endfacet + facet normal 0.407779 -0.0751917 0.909979 + outer loop + vertex 1.02499 1.13999 2.60956 + vertex 1.0252 1.14465 2.60985 + vertex 1.02174 1.14124 2.61112 + endloop + endfacet + facet normal 0.421627 -0.0922104 0.902068 + outer loop + vertex 1.0252 1.14465 2.60985 + vertex 1.02249 1.14509 2.61117 + vertex 1.02174 1.14124 2.61112 + endloop + endfacet + facet normal 0.352264 -0.079102 0.932552 + outer loop + vertex 1.02249 1.14509 2.61117 + vertex 1.01854 1.14324 2.6125 + vertex 1.02174 1.14124 2.61112 + endloop + endfacet + facet normal 0.351551 -0.0772783 0.932974 + outer loop + vertex 1.02249 1.14509 2.61117 + vertex 1.02195 1.14819 2.61163 + vertex 1.01854 1.14324 2.6125 + endloop + endfacet + facet normal 0.372354 -0.0932973 0.923389 + outer loop + vertex 1.02195 1.14819 2.61163 + vertex 1.0182 1.14836 2.61316 + vertex 1.01854 1.14324 2.6125 + endloop + endfacet + facet normal 0.412729 -0.0630477 0.908669 + outer loop + vertex 1.02467 1.14782 2.61037 + vertex 1.02195 1.14819 2.61163 + vertex 1.02249 1.14509 2.61117 + endloop + endfacet + facet normal 0.41426 -0.051659 0.908692 + outer loop + vertex 1.02527 1.15161 2.61031 + vertex 1.02195 1.14819 2.61163 + vertex 1.02467 1.14782 2.61037 + endloop + endfacet + facet normal 0.457461 -0.058925 0.887275 + outer loop + vertex 1.02467 1.14782 2.61037 + vertex 1.02812 1.14935 2.60869 + vertex 1.02527 1.15161 2.61031 + endloop + endfacet + facet normal 0.461161 -0.0531572 0.885723 + outer loop + vertex 1.02812 1.14935 2.60869 + vertex 1.02875 1.15489 2.60869 + vertex 1.02527 1.15161 2.61031 + endloop + endfacet + facet normal 0.464175 -0.0572575 0.883891 + outer loop + vertex 1.02527 1.15161 2.61031 + vertex 1.02875 1.15489 2.60869 + vertex 1.02562 1.15644 2.61044 + endloop + endfacet + facet normal 0.481694 -0.0554936 0.874581 + outer loop + vertex 1.02812 1.14935 2.60869 + vertex 1.03185 1.15329 2.60688 + vertex 1.02875 1.15489 2.60869 + endloop + endfacet + facet normal 0.475559 -0.0479615 0.878375 + outer loop + vertex 1.03176 1.14867 2.60668 + vertex 1.03185 1.15329 2.60688 + vertex 1.02812 1.14935 2.60869 + endloop + endfacet + facet normal 0.473856 -0.0579768 0.878692 + outer loop + vertex 1.03176 1.14867 2.60668 + vertex 1.02812 1.14935 2.60869 + vertex 1.02893 1.14405 2.6079 + endloop + endfacet + facet normal 0.466862 -0.0526093 0.882764 + outer loop + vertex 1.03231 1.14537 2.60619 + vertex 1.03176 1.14867 2.60668 + vertex 1.02893 1.14405 2.6079 + endloop + endfacet + facet normal 0.467968 -0.0564932 0.881938 + outer loop + vertex 1.03231 1.14537 2.60619 + vertex 1.02893 1.14405 2.6079 + vertex 1.03171 1.1415 2.60626 + endloop + endfacet + facet normal 0.459695 -0.0657885 0.885637 + outer loop + vertex 1.02467 1.14782 2.61037 + vertex 1.0252 1.14465 2.60985 + vertex 1.02812 1.14935 2.60869 + endloop + endfacet + facet normal 0.455067 -0.0622579 0.888278 + outer loop + vertex 1.02812 1.14935 2.60869 + vertex 1.0252 1.14465 2.60985 + vertex 1.02893 1.14405 2.6079 + endloop + endfacet + facet normal 0.428681 -0.0686762 0.900842 + outer loop + vertex 1.02205 1.15269 2.61192 + vertex 1.02195 1.14819 2.61163 + vertex 1.02527 1.15161 2.61031 + endloop + endfacet + facet normal 0.424632 -0.0744067 0.902303 + outer loop + vertex 1.02467 1.14782 2.61037 + vertex 1.02249 1.14509 2.61117 + vertex 1.0252 1.14465 2.60985 + endloop + endfacet + facet normal 0.452891 -0.0758996 0.888329 + outer loop + vertex 1.02499 1.13999 2.60956 + vertex 1.02893 1.14405 2.6079 + vertex 1.0252 1.14465 2.60985 + endloop + endfacet + facet normal 0.442996 -0.0638599 0.894246 + outer loop + vertex 1.0282 1.13838 2.60786 + vertex 1.02893 1.14405 2.6079 + vertex 1.02499 1.13999 2.60956 + endloop + endfacet + facet normal 0.435799 -0.0805307 0.896434 + outer loop + vertex 1.02441 1.1348 2.60938 + vertex 1.0282 1.13838 2.60786 + vertex 1.02499 1.13999 2.60956 + endloop + endfacet + facet normal 0.390557 -0.0762141 0.917418 + outer loop + vertex 1.02441 1.1348 2.60938 + vertex 1.02499 1.13999 2.60956 + vertex 1.02118 1.13638 2.61089 + endloop + endfacet + facet normal 0.338994 -0.102168 0.935225 + outer loop + vertex 1.01854 1.14324 2.6125 + vertex 1.01762 1.13756 2.61221 + vertex 1.02174 1.14124 2.61112 + endloop + endfacet + facet normal 0.377202 -0.124843 0.917678 + outer loop + vertex 1.01982 1.12765 2.61053 + vertex 1.01996 1.12434 2.61002 + vertex 1.02339 1.12901 2.60925 + endloop + endfacet + facet normal 0.35886 -0.109808 0.92691 + outer loop + vertex 1.02339 1.12901 2.60925 + vertex 1.01996 1.12434 2.61002 + vertex 1.02336 1.1236 2.60862 + endloop + endfacet + facet normal 0.38303 -0.0931157 0.919031 + outer loop + vertex 1.02061 1.1315 2.61063 + vertex 1.02441 1.1348 2.60938 + vertex 1.02118 1.13638 2.61089 + endloop + endfacet + facet normal 0.451442 -0.062855 0.890084 + outer loop + vertex 1.03392 1.12485 2.60393 + vertex 1.03426 1.12993 2.60411 + vertex 1.03075 1.12647 2.60565 + endloop + endfacet + facet normal 0.487528 -0.0595848 0.871072 + outer loop + vertex 1.03426 1.12993 2.60411 + vertex 1.03764 1.13329 2.60245 + vertex 1.03448 1.13494 2.60433 + endloop + endfacet + facet normal 0.437935 -0.0804554 0.895399 + outer loop + vertex 1.02766 1.13306 2.60769 + vertex 1.0273 1.12778 2.60739 + vertex 1.03102 1.1315 2.60591 + endloop + endfacet + facet normal 0.429291 -0.0720112 0.900291 + outer loop + vertex 1.02766 1.13306 2.60769 + vertex 1.0282 1.13838 2.60786 + vertex 1.02441 1.1348 2.60938 + endloop + endfacet + facet normal 0.460948 -0.0661067 0.884961 + outer loop + vertex 1.02893 1.14405 2.6079 + vertex 1.0282 1.13838 2.60786 + vertex 1.03171 1.1415 2.60626 + endloop + endfacet + facet normal 0.471642 -0.0545383 0.880102 + outer loop + vertex 1.03448 1.13494 2.60433 + vertex 1.03465 1.13987 2.60455 + vertex 1.03131 1.13658 2.60613 + endloop + endfacet + facet normal 0.496074 -0.0548215 0.866548 + outer loop + vertex 1.03448 1.13494 2.60433 + vertex 1.03776 1.13827 2.60266 + vertex 1.03465 1.13987 2.60455 + endloop + endfacet + facet normal 0.488899 -0.059955 0.870277 + outer loop + vertex 1.03472 1.14446 2.60478 + vertex 1.03231 1.14537 2.60619 + vertex 1.03171 1.1415 2.60626 + endloop + endfacet + facet normal 0.500277 -0.0445127 0.864721 + outer loop + vertex 1.03776 1.13827 2.60266 + vertex 1.03779 1.14326 2.60291 + vertex 1.03465 1.13987 2.60455 + endloop + endfacet + facet normal 0.491846 -0.0505022 0.869216 + outer loop + vertex 1.03425 1.14782 2.60524 + vertex 1.03231 1.14537 2.60619 + vertex 1.03472 1.14446 2.60478 + endloop + endfacet + facet normal 0.497907 -0.047837 0.86591 + outer loop + vertex 1.03185 1.15329 2.60688 + vertex 1.03176 1.14867 2.60668 + vertex 1.0348 1.15158 2.6051 + endloop + endfacet + facet normal 0.485171 -0.0471434 0.873148 + outer loop + vertex 1.03185 1.15329 2.60688 + vertex 1.03214 1.15828 2.60699 + vertex 1.02875 1.15489 2.60869 + endloop + endfacet + facet normal 0.489473 -0.0528147 0.870417 + outer loop + vertex 1.02875 1.15489 2.60869 + vertex 1.03214 1.15828 2.60699 + vertex 1.02906 1.15994 2.60883 + endloop + endfacet + facet normal 0.493377 -0.0436852 0.868718 + outer loop + vertex 1.03214 1.15828 2.60699 + vertex 1.03233 1.16323 2.60713 + vertex 1.02906 1.15994 2.60883 + endloop + endfacet + facet normal 0.522557 -0.0350001 0.851885 + outer loop + vertex 1.03804 1.15411 2.60324 + vertex 1.0383 1.1591 2.60329 + vertex 1.03512 1.15638 2.60513 + endloop + endfacet + facet normal 0.507791 -0.0343302 0.860796 + outer loop + vertex 1.03855 1.16402 2.60334 + vertex 1.0383 1.1591 2.60329 + vertex 1.04152 1.16171 2.60149 + endloop + endfacet + facet normal 0.516085 -0.0441909 0.855396 + outer loop + vertex 1.03233 1.16323 2.60713 + vertex 1.03214 1.15828 2.60699 + vertex 1.03535 1.1613 2.60521 + endloop + endfacet + facet normal 0.500788 -0.0404165 0.864626 + outer loop + vertex 1.03233 1.16323 2.60713 + vertex 1.03245 1.16817 2.60729 + vertex 1.02921 1.1649 2.60902 + endloop + endfacet + facet normal 0.504238 -0.045026 0.86239 + outer loop + vertex 1.02921 1.1649 2.60902 + vertex 1.03245 1.16817 2.60729 + vertex 1.02931 1.16984 2.60922 + endloop + endfacet + facet normal 0.507085 -0.038149 0.861051 + outer loop + vertex 1.03245 1.16817 2.60729 + vertex 1.03253 1.17312 2.60746 + vertex 1.02931 1.16984 2.60922 + endloop + endfacet + facet normal 0.510015 -0.0420616 0.859136 + outer loop + vertex 1.02931 1.16984 2.60922 + vertex 1.03253 1.17312 2.60746 + vertex 1.02942 1.17479 2.6094 + endloop + endfacet + facet normal 0.526828 -0.0411709 0.848974 + outer loop + vertex 1.03855 1.16402 2.60334 + vertex 1.03919 1.16941 2.6032 + vertex 1.03558 1.1663 2.60529 + endloop + endfacet + facet normal 0.48885 -0.0551423 0.870623 + outer loop + vertex 1.042 1.1734 2.60187 + vertex 1.03901 1.17475 2.60364 + vertex 1.03919 1.16941 2.6032 + endloop + endfacet + facet normal 0.522026 -0.0380856 0.852079 + outer loop + vertex 1.03253 1.17312 2.60746 + vertex 1.03245 1.16817 2.60729 + vertex 1.03572 1.17137 2.60543 + endloop + endfacet + facet normal 0.51265 -0.0356747 0.857856 + outer loop + vertex 1.03253 1.17312 2.60746 + vertex 1.03262 1.1781 2.60762 + vertex 1.02942 1.17479 2.6094 + endloop + endfacet + facet normal 0.516337 -0.0405475 0.855425 + outer loop + vertex 1.02942 1.17479 2.6094 + vertex 1.03262 1.1781 2.60762 + vertex 1.02957 1.17971 2.60954 + endloop + endfacet + facet normal 0.519209 -0.0334096 0.853994 + outer loop + vertex 1.03262 1.1781 2.60762 + vertex 1.03264 1.18312 2.60781 + vertex 1.02957 1.17971 2.60954 + endloop + endfacet + facet normal 0.511562 -0.0335575 0.858591 + outer loop + vertex 1.03264 1.18312 2.60781 + vertex 1.03262 1.1781 2.60762 + vertex 1.03592 1.18148 2.60579 + endloop + endfacet + facet normal 0.502808 -0.0593179 0.86236 + outer loop + vertex 1.03901 1.17475 2.60364 + vertex 1.03929 1.17989 2.60383 + vertex 1.0358 1.17643 2.60563 + endloop + endfacet + facet normal 0.499806 -0.0312667 0.865573 + outer loop + vertex 1.03291 1.19396 2.60805 + vertex 1.03227 1.18846 2.60823 + vertex 1.03605 1.19168 2.60616 + endloop + endfacet + facet normal 0.510269 -0.0369239 0.859222 + outer loop + vertex 1.03594 1.18657 2.60599 + vertex 1.03264 1.18312 2.60781 + vertex 1.03592 1.18148 2.60579 + endloop + endfacet + facet normal 0.523688 -0.0389605 0.851019 + outer loop + vertex 1.02957 1.17971 2.60954 + vertex 1.03264 1.18312 2.60781 + vertex 1.02963 1.18434 2.60971 + endloop + endfacet + facet normal 0.516634 -0.034879 0.855495 + outer loop + vertex 1.02916 1.18772 2.61014 + vertex 1.02728 1.18523 2.61117 + vertex 1.02963 1.18434 2.60971 + endloop + endfacet + facet normal 0.515708 -0.0318617 0.856172 + outer loop + vertex 1.02674 1.19311 2.61176 + vertex 1.0267 1.18849 2.61161 + vertex 1.02966 1.19145 2.60994 + endloop + endfacet + facet normal 0.481577 -0.046231 0.875184 + outer loop + vertex 1.02396 1.18382 2.61295 + vertex 1.02335 1.17828 2.61299 + vertex 1.02671 1.18135 2.6113 + endloop + endfacet + facet normal 0.499824 -0.0403453 0.865187 + outer loop + vertex 1.02942 1.17479 2.6094 + vertex 1.02957 1.17971 2.60954 + vertex 1.02637 1.17648 2.61123 + endloop + endfacet + facet normal 0.472125 -0.0562278 0.879737 + outer loop + vertex 1.02303 1.17325 2.61286 + vertex 1.02281 1.16821 2.61266 + vertex 1.02617 1.17151 2.61107 + endloop + endfacet + facet normal 0.482477 -0.0451029 0.874747 + outer loop + vertex 1.02921 1.1649 2.60902 + vertex 1.02931 1.16984 2.60922 + vertex 1.02602 1.16651 2.61086 + endloop + endfacet + facet normal 0.497253 -0.0488272 0.866231 + outer loop + vertex 1.02906 1.15994 2.60883 + vertex 1.03233 1.16323 2.60713 + vertex 1.02921 1.1649 2.60902 + endloop + endfacet + facet normal 0.466424 -0.0517527 0.883046 + outer loop + vertex 1.02875 1.15489 2.60869 + vertex 1.02906 1.15994 2.60883 + vertex 1.02562 1.15644 2.61044 + endloop + endfacet + facet normal 0.454549 -0.0650347 0.888344 + outer loop + vertex 1.02251 1.163 2.61246 + vertex 1.02224 1.15773 2.61221 + vertex 1.02585 1.16147 2.61064 + endloop + endfacet + facet normal 0.43263 -0.0553943 0.899868 + outer loop + vertex 1.02562 1.15644 2.61044 + vertex 1.02205 1.15269 2.61192 + vertex 1.02527 1.15161 2.61031 + endloop + endfacet + facet normal 0.374685 -0.136889 0.916991 + outer loop + vertex 1.01385 1.14877 2.61476 + vertex 1.01843 1.15351 2.6136 + vertex 1.01509 1.15419 2.61506 + endloop + endfacet + facet normal 0.329458 -0.109642 0.937783 + outer loop + vertex 1.01495 1.15764 2.61552 + vertex 1.01261 1.15488 2.61602 + vertex 1.01509 1.15419 2.61506 + endloop + endfacet + facet normal 0.302676 -0.0848878 0.949306 + outer loop + vertex 1.01495 1.15764 2.61552 + vertex 1.01218 1.15811 2.61644 + vertex 1.01261 1.15488 2.61602 + endloop + endfacet + facet normal 0.404501 -0.0690891 0.911924 + outer loop + vertex 1.01843 1.159 2.61413 + vertex 1.01926 1.1648 2.6142 + vertex 1.01566 1.16159 2.61555 + endloop + endfacet + facet normal 0.44867 -0.0648713 0.89134 + outer loop + vertex 1.01926 1.1648 2.6142 + vertex 1.02281 1.16821 2.61266 + vertex 1.0196 1.16995 2.6144 + endloop + endfacet + facet normal 0.452806 -0.0557524 0.889864 + outer loop + vertex 1.02281 1.16821 2.61266 + vertex 1.02303 1.17325 2.61286 + vertex 1.0196 1.16995 2.6144 + endloop + endfacet + facet normal 0.455854 -0.0597769 0.888045 + outer loop + vertex 1.0196 1.16995 2.6144 + vertex 1.02303 1.17325 2.61286 + vertex 1.01984 1.1749 2.61461 + endloop + endfacet + facet normal 0.350167 -0.0891122 0.932439 + outer loop + vertex 1.01239 1.1676 2.61726 + vertex 1.01224 1.16268 2.61684 + vertex 1.01602 1.1665 2.61579 + endloop + endfacet + facet normal 0.393502 -0.0834851 0.915525 + outer loop + vertex 1.01296 1.17758 2.61795 + vertex 1.01261 1.17254 2.61764 + vertex 1.0165 1.1763 2.61631 + endloop + endfacet + facet normal 0.400915 -0.061099 0.914076 + outer loop + vertex 1.01691 1.18104 2.61645 + vertex 1.01296 1.17758 2.61795 + vertex 1.0165 1.1763 2.61631 + endloop + endfacet + facet normal 0.423476 -0.0588558 0.903993 + outer loop + vertex 1.0196 1.16995 2.6144 + vertex 1.01984 1.1749 2.61461 + vertex 1.01625 1.17144 2.61607 + endloop + endfacet + facet normal 0.443631 -0.0641474 0.893911 + outer loop + vertex 1.0165 1.1763 2.61631 + vertex 1.02015 1.17979 2.61475 + vertex 1.01691 1.18104 2.61645 + endloop + endfacet + facet normal 0.459513 -0.0512747 0.88669 + outer loop + vertex 1.02303 1.17325 2.61286 + vertex 1.02335 1.17828 2.61299 + vertex 1.01984 1.1749 2.61461 + endloop + endfacet + facet normal 0.467096 -0.0504518 0.882766 + outer loop + vertex 1.01709 1.19294 2.61706 + vertex 1.01696 1.18813 2.61686 + vertex 1.0202 1.19141 2.61533 + endloop + endfacet + facet normal 0.449863 -0.0503637 0.891677 + outer loop + vertex 1.01696 1.18813 2.61686 + vertex 1.01709 1.19294 2.61706 + vertex 1.01322 1.18898 2.61879 + endloop + endfacet + facet normal 0.414191 -0.0794393 0.906717 + outer loop + vertex 1.01384 1.18335 2.61805 + vertex 1.01296 1.17758 2.61795 + vertex 1.01691 1.18104 2.61645 + endloop + endfacet +endsolid diff --git a/noether_examples/meshes/outputsBackDoor/output_7.stl b/noether_examples/meshes/outputsBackDoor/output_7.stl new file mode 100644 index 00000000..0566a21d --- /dev/null +++ b/noether_examples/meshes/outputsBackDoor/output_7.stl @@ -0,0 +1,159728 @@ +solid ascii + facet normal 0.398816 -0.0371719 0.916277 + outer loop + vertex 1.01477 1.35466 2.62414 + vertex 1.0185 1.35839 2.62267 + vertex 1.01479 1.35965 2.62434 + endloop + endfacet + facet normal 0.392502 -0.0579461 0.917924 + outer loop + vertex 1.0185 1.35839 2.62267 + vertex 1.01872 1.36331 2.62289 + vertex 1.01479 1.35965 2.62434 + endloop + endfacet + facet normal 0.374055 -0.0346584 0.926759 + outer loop + vertex 1.01479 1.35965 2.62434 + vertex 1.01872 1.36331 2.62289 + vertex 1.01484 1.36461 2.6245 + endloop + endfacet + facet normal 0.368682 -0.0523697 0.928079 + outer loop + vertex 1.01872 1.36331 2.62289 + vertex 1.01886 1.36831 2.62311 + vertex 1.01484 1.36461 2.6245 + endloop + endfacet + facet normal 0.35275 -0.0323887 0.935157 + outer loop + vertex 1.01484 1.36461 2.6245 + vertex 1.01886 1.36831 2.62311 + vertex 1.01485 1.36955 2.62467 + endloop + endfacet + facet normal 0.348797 -0.0462815 0.936055 + outer loop + vertex 1.01886 1.36831 2.62311 + vertex 1.01883 1.37326 2.62337 + vertex 1.01485 1.36955 2.62467 + endloop + endfacet + facet normal 0.338554 -0.0337739 0.94034 + outer loop + vertex 1.01485 1.36955 2.62467 + vertex 1.01883 1.37326 2.62337 + vertex 1.01484 1.3745 2.62485 + endloop + endfacet + facet normal 0.335801 -0.0433327 0.940936 + outer loop + vertex 1.01883 1.37326 2.62337 + vertex 1.01879 1.3782 2.62361 + vertex 1.01484 1.3745 2.62485 + endloop + endfacet + facet normal 0.326843 -0.0325817 0.944517 + outer loop + vertex 1.01484 1.3745 2.62485 + vertex 1.01879 1.3782 2.62361 + vertex 1.01488 1.3794 2.62501 + endloop + endfacet + facet normal 0.32374 -0.0434536 0.945148 + outer loop + vertex 1.01879 1.3782 2.62361 + vertex 1.01869 1.38319 2.62388 + vertex 1.01488 1.3794 2.62501 + endloop + endfacet + facet normal 0.312514 -0.0309213 0.94941 + outer loop + vertex 1.01488 1.3794 2.62501 + vertex 1.01869 1.38319 2.62388 + vertex 1.01486 1.38395 2.62516 + endloop + endfacet + facet normal 0.30992 -0.0445198 0.94972 + outer loop + vertex 1.01818 1.38848 2.62429 + vertex 1.01486 1.38395 2.62516 + vertex 1.01869 1.38319 2.62388 + endloop + endfacet + facet normal 0.308126 -0.043078 0.95037 + outer loop + vertex 1.01432 1.38727 2.62549 + vertex 1.01486 1.38395 2.62516 + vertex 1.01818 1.38848 2.62429 + endloop + endfacet + facet normal 0.308883 -0.0458598 0.949994 + outer loop + vertex 1.01432 1.38727 2.62549 + vertex 1.01818 1.38848 2.62429 + vertex 1.01502 1.39109 2.62544 + endloop + endfacet + facet normal 0.416916 -0.0661222 0.906537 + outer loop + vertex 1.01502 1.39109 2.62544 + vertex 1.01186 1.38831 2.6267 + vertex 1.01432 1.38727 2.62549 + endloop + endfacet + facet normal 0.422465 -0.0511854 0.904933 + outer loop + vertex 1.01432 1.38727 2.62549 + vertex 1.01186 1.38831 2.6267 + vertex 1.01228 1.38496 2.62631 + endloop + endfacet + facet normal 0.303575 -0.052905 0.951338 + outer loop + vertex 1.01818 1.38848 2.62429 + vertex 1.01896 1.39419 2.62436 + vertex 1.01502 1.39109 2.62544 + endloop + endfacet + facet normal 0.298766 -0.0461533 0.95321 + outer loop + vertex 1.01502 1.39109 2.62544 + vertex 1.01896 1.39419 2.62436 + vertex 1.01541 1.39592 2.62556 + endloop + endfacet + facet normal 0.399182 -0.0534302 0.915313 + outer loop + vertex 1.01541 1.39592 2.62556 + vertex 1.01198 1.39281 2.62687 + vertex 1.01502 1.39109 2.62544 + endloop + endfacet + facet normal 0.402631 -0.0464112 0.914185 + outer loop + vertex 1.01198 1.39281 2.62687 + vertex 1.01186 1.38831 2.6267 + vertex 1.01502 1.39109 2.62544 + endloop + endfacet + facet normal 0.38779 -0.0384512 0.920946 + outer loop + vertex 1.01215 1.39766 2.627 + vertex 1.01198 1.39281 2.62687 + vertex 1.01541 1.39592 2.62556 + endloop + endfacet + facet normal 0.384343 -0.0458397 0.922051 + outer loop + vertex 1.01563 1.40088 2.62571 + vertex 1.01215 1.39766 2.627 + vertex 1.01541 1.39592 2.62556 + endloop + endfacet + facet normal 0.287579 -0.0426916 0.956805 + outer loop + vertex 1.01541 1.39592 2.62556 + vertex 1.01926 1.39932 2.62455 + vertex 1.01563 1.40088 2.62571 + endloop + endfacet + facet normal 0.284377 -0.0506037 0.957376 + outer loop + vertex 1.01926 1.39932 2.62455 + vertex 1.01941 1.40434 2.62477 + vertex 1.01563 1.40088 2.62571 + endloop + endfacet + facet normal 0.276458 -0.0411884 0.960143 + outer loop + vertex 1.01563 1.40088 2.62571 + vertex 1.01941 1.40434 2.62477 + vertex 1.0158 1.40587 2.62588 + endloop + endfacet + facet normal 0.372859 -0.0433461 0.926875 + outer loop + vertex 1.0158 1.40587 2.62588 + vertex 1.01231 1.40261 2.62713 + vertex 1.01563 1.40088 2.62571 + endloop + endfacet + facet normal 0.364938 -0.0334985 0.930429 + outer loop + vertex 1.01249 1.40763 2.62724 + vertex 1.01231 1.40261 2.62713 + vertex 1.0158 1.40587 2.62588 + endloop + endfacet + facet normal 0.360782 -0.0423024 0.93169 + outer loop + vertex 1.01604 1.41089 2.62601 + vertex 1.01249 1.40763 2.62724 + vertex 1.0158 1.40587 2.62588 + endloop + endfacet + facet normal 0.265198 -0.0386303 0.96342 + outer loop + vertex 1.0158 1.40587 2.62588 + vertex 1.01955 1.40935 2.62498 + vertex 1.01604 1.41089 2.62601 + endloop + endfacet + facet normal 0.261641 -0.0471281 0.964014 + outer loop + vertex 1.01955 1.40935 2.62498 + vertex 1.01975 1.41432 2.62517 + vertex 1.01604 1.41089 2.62601 + endloop + endfacet + facet normal 0.251753 -0.0356321 0.967135 + outer loop + vertex 1.01604 1.41089 2.62601 + vertex 1.01975 1.41432 2.62517 + vertex 1.01647 1.41577 2.62608 + endloop + endfacet + facet normal 0.351241 -0.0439698 0.935252 + outer loop + vertex 1.01647 1.41577 2.62608 + vertex 1.01282 1.41275 2.62731 + vertex 1.01604 1.41089 2.62601 + endloop + endfacet + facet normal 0.346242 -0.0370687 0.937413 + outer loop + vertex 1.01363 1.41833 2.62723 + vertex 1.01282 1.41275 2.62731 + vertex 1.01647 1.41577 2.62608 + endloop + endfacet + facet normal 0.337443 -0.0480253 0.94012 + outer loop + vertex 1.01721 1.41959 2.62601 + vertex 1.01363 1.41833 2.62723 + vertex 1.01647 1.41577 2.62608 + endloop + endfacet + facet normal 0.237011 -0.0278972 0.971106 + outer loop + vertex 1.01991 1.41891 2.62533 + vertex 1.01721 1.41959 2.62601 + vertex 1.01647 1.41577 2.62608 + endloop + endfacet + facet normal 0.340274 -0.0575915 0.938561 + outer loop + vertex 1.01721 1.41959 2.62601 + vertex 1.01687 1.42279 2.62633 + vertex 1.01363 1.41833 2.62723 + endloop + endfacet + facet normal 0.330878 -0.0499857 0.942349 + outer loop + vertex 1.01687 1.42279 2.62633 + vertex 1.01339 1.42344 2.62758 + vertex 1.01363 1.41833 2.62723 + endloop + endfacet + facet normal 0.327134 -0.0702035 0.942367 + outer loop + vertex 1.01687 1.42279 2.62633 + vertex 1.01731 1.4273 2.62651 + vertex 1.01339 1.42344 2.62758 + endloop + endfacet + facet normal 0.306968 -0.0474763 0.950535 + outer loop + vertex 1.01339 1.42344 2.62758 + vertex 1.01731 1.4273 2.62651 + vertex 1.01363 1.42839 2.62775 + endloop + endfacet + facet normal 0.301303 -0.0673348 0.951148 + outer loop + vertex 1.01731 1.4273 2.62651 + vertex 1.01833 1.43275 2.62657 + vertex 1.01363 1.42839 2.62775 + endloop + endfacet + facet normal 0.276931 -0.0386542 0.960112 + outer loop + vertex 1.01363 1.42839 2.62775 + vertex 1.01833 1.43275 2.62657 + vertex 1.0138 1.43339 2.62791 + endloop + endfacet + facet normal 0.276419 -0.0422983 0.960106 + outer loop + vertex 1.01833 1.43275 2.62657 + vertex 1.01805 1.43774 2.62687 + vertex 1.0138 1.43339 2.62791 + endloop + endfacet + facet normal 0.265269 -0.0305324 0.963691 + outer loop + vertex 1.0138 1.43339 2.62791 + vertex 1.01805 1.43774 2.62687 + vertex 1.01379 1.43832 2.62807 + endloop + endfacet + facet normal 0.263783 -0.0414732 0.96369 + outer loop + vertex 1.01805 1.43774 2.62687 + vertex 1.01823 1.44268 2.62704 + vertex 1.01379 1.43832 2.62807 + endloop + endfacet + facet normal 0.250576 -0.0270713 0.967718 + outer loop + vertex 1.01379 1.43832 2.62807 + vertex 1.01823 1.44268 2.62704 + vertex 1.0138 1.44325 2.6282 + endloop + endfacet + facet normal 0.249553 -0.0351396 0.967723 + outer loop + vertex 1.01823 1.44268 2.62704 + vertex 1.01837 1.44771 2.62718 + vertex 1.0138 1.44325 2.6282 + endloop + endfacet + facet normal 0.239887 -0.0246128 0.970489 + outer loop + vertex 1.0138 1.44325 2.6282 + vertex 1.01837 1.44771 2.62718 + vertex 1.01378 1.44819 2.62833 + endloop + endfacet + facet normal 0.239286 -0.0303745 0.970474 + outer loop + vertex 1.01837 1.44771 2.62718 + vertex 1.01835 1.45267 2.62735 + vertex 1.01378 1.44819 2.62833 + endloop + endfacet + facet normal 0.231632 -0.0221204 0.972552 + outer loop + vertex 1.01378 1.44819 2.62833 + vertex 1.01835 1.45267 2.62735 + vertex 1.01374 1.45312 2.62845 + endloop + endfacet + facet normal 0.231038 -0.028056 0.97254 + outer loop + vertex 1.01835 1.45267 2.62735 + vertex 1.01831 1.45759 2.6275 + vertex 1.01374 1.45312 2.62845 + endloop + endfacet + facet normal 0.227243 -0.0239595 0.973543 + outer loop + vertex 1.01374 1.45312 2.62845 + vertex 1.01831 1.45759 2.6275 + vertex 1.01373 1.4581 2.62858 + endloop + endfacet + facet normal 0.226836 -0.0276148 0.973541 + outer loop + vertex 1.01831 1.45759 2.6275 + vertex 1.01827 1.46253 2.62765 + vertex 1.01373 1.4581 2.62858 + endloop + endfacet + facet normal 0.22193 -0.0223318 0.974807 + outer loop + vertex 1.01373 1.4581 2.62858 + vertex 1.01827 1.46253 2.62765 + vertex 1.01373 1.46309 2.62869 + endloop + endfacet + facet normal 0.221504 -0.0258309 0.974817 + outer loop + vertex 1.01827 1.46253 2.62765 + vertex 1.01823 1.46751 2.62779 + vertex 1.01373 1.46309 2.62869 + endloop + endfacet + facet normal 0.218918 -0.0230611 0.975471 + outer loop + vertex 1.01373 1.46309 2.62869 + vertex 1.01823 1.46751 2.62779 + vertex 1.01376 1.46811 2.62881 + endloop + endfacet + facet normal 0.218541 -0.0259037 0.975484 + outer loop + vertex 1.01823 1.46751 2.62779 + vertex 1.01824 1.47253 2.62792 + vertex 1.01376 1.46811 2.62881 + endloop + endfacet + facet normal 0.213091 -0.0201093 0.976825 + outer loop + vertex 1.01376 1.46811 2.62881 + vertex 1.01824 1.47253 2.62792 + vertex 1.01379 1.47312 2.6289 + endloop + endfacet + facet normal 0.212944 -0.0212249 0.976834 + outer loop + vertex 1.01824 1.47253 2.62792 + vertex 1.01825 1.47754 2.62803 + vertex 1.01379 1.47312 2.6289 + endloop + endfacet + facet normal 0.207458 -0.0154323 0.978122 + outer loop + vertex 1.01379 1.47312 2.6289 + vertex 1.01825 1.47754 2.62803 + vertex 1.0138 1.47812 2.62898 + endloop + endfacet + facet normal 0.20718 -0.0176144 0.978144 + outer loop + vertex 1.01825 1.47754 2.62803 + vertex 1.01826 1.48255 2.62811 + vertex 1.0138 1.47812 2.62898 + endloop + endfacet + facet normal 0.201229 -0.0113634 0.979478 + outer loop + vertex 1.0138 1.47812 2.62898 + vertex 1.01826 1.48255 2.62811 + vertex 1.01382 1.4831 2.62903 + endloop + endfacet + facet normal 0.201193 -0.0116541 0.979482 + outer loop + vertex 1.01826 1.48255 2.62811 + vertex 1.01826 1.48753 2.62817 + vertex 1.01382 1.4831 2.62903 + endloop + endfacet + facet normal 0.197562 -0.00785462 0.980259 + outer loop + vertex 1.01382 1.4831 2.62903 + vertex 1.01826 1.48753 2.62817 + vertex 1.01383 1.48808 2.62907 + endloop + endfacet + facet normal 0.197335 -0.00969877 0.980288 + outer loop + vertex 1.01826 1.48753 2.62817 + vertex 1.01826 1.4925 2.62822 + vertex 1.01383 1.48808 2.62907 + endloop + endfacet + facet normal 0.192238 -0.00438573 0.981339 + outer loop + vertex 1.01383 1.48808 2.62907 + vertex 1.01826 1.4925 2.62822 + vertex 1.01383 1.49305 2.62909 + endloop + endfacet + facet normal 0.192029 -0.00611803 0.98137 + outer loop + vertex 1.01826 1.4925 2.62822 + vertex 1.01825 1.49746 2.62826 + vertex 1.01383 1.49305 2.62909 + endloop + endfacet + facet normal 0.190482 -0.00451045 0.98168 + outer loop + vertex 1.01383 1.49305 2.62909 + vertex 1.01825 1.49746 2.62826 + vertex 1.01383 1.49803 2.62911 + endloop + endfacet + facet normal 0.190404 -0.00512965 0.981692 + outer loop + vertex 1.01825 1.49746 2.62826 + vertex 1.01823 1.50242 2.62828 + vertex 1.01383 1.49803 2.62911 + endloop + endfacet + facet normal 0.188747 -0.00340766 0.98202 + outer loop + vertex 1.01383 1.49803 2.62911 + vertex 1.01823 1.50242 2.62828 + vertex 1.01384 1.503 2.62913 + endloop + endfacet + facet normal 0.188942 -0.0019027 0.981986 + outer loop + vertex 1.01823 1.50242 2.62828 + vertex 1.0182 1.50736 2.6283 + vertex 1.01384 1.503 2.62913 + endloop + endfacet + facet normal 0.187312 -0.000209671 0.982301 + outer loop + vertex 1.01384 1.503 2.62913 + vertex 1.0182 1.50736 2.6283 + vertex 1.01382 1.50794 2.62913 + endloop + endfacet + facet normal 0.187357 0.000149196 0.982292 + outer loop + vertex 1.0182 1.50736 2.6283 + vertex 1.01819 1.51231 2.6283 + vertex 1.01382 1.50794 2.62913 + endloop + endfacet + facet normal 0.187027 0.000490639 0.982355 + outer loop + vertex 1.01382 1.50794 2.62913 + vertex 1.01819 1.51231 2.6283 + vertex 1.0138 1.51287 2.62914 + endloop + endfacet + facet normal 0.187351 0.0031652 0.982288 + outer loop + vertex 1.01819 1.51231 2.6283 + vertex 1.0182 1.51729 2.62828 + vertex 1.0138 1.51287 2.62914 + endloop + endfacet + facet normal 0.187839 0.00266324 0.982196 + outer loop + vertex 1.0138 1.51287 2.62914 + vertex 1.0182 1.51729 2.62828 + vertex 1.01377 1.51782 2.62913 + endloop + endfacet + facet normal 0.188304 0.00675403 0.982088 + outer loop + vertex 1.0182 1.51729 2.62828 + vertex 1.01823 1.52232 2.62824 + vertex 1.01377 1.51782 2.62913 + endloop + endfacet + facet normal 0.189611 0.00540939 0.981844 + outer loop + vertex 1.01377 1.51782 2.62913 + vertex 1.01823 1.52232 2.62824 + vertex 1.01375 1.52284 2.6291 + endloop + endfacet + facet normal 0.190105 0.00992817 0.981714 + outer loop + vertex 1.01823 1.52232 2.62824 + vertex 1.0183 1.52739 2.62818 + vertex 1.01375 1.52284 2.6291 + endloop + endfacet + facet normal 0.191033 0.0089669 0.981543 + outer loop + vertex 1.01375 1.52284 2.6291 + vertex 1.0183 1.52739 2.62818 + vertex 1.01376 1.52789 2.62906 + endloop + endfacet + facet normal 0.19145 0.0129592 0.981417 + outer loop + vertex 1.0183 1.52739 2.62818 + vertex 1.01839 1.53249 2.62809 + vertex 1.01376 1.52789 2.62906 + endloop + endfacet + facet normal 0.193181 0.0111479 0.9811 + outer loop + vertex 1.01376 1.52789 2.62906 + vertex 1.01839 1.53249 2.62809 + vertex 1.01379 1.53297 2.62899 + endloop + endfacet + facet normal 0.193759 0.0169953 0.980902 + outer loop + vertex 1.01839 1.53249 2.62809 + vertex 1.01848 1.53759 2.62799 + vertex 1.01379 1.53297 2.62899 + endloop + endfacet + facet normal 0.197061 0.0135059 0.980298 + outer loop + vertex 1.01379 1.53297 2.62899 + vertex 1.01848 1.53759 2.62799 + vertex 1.01384 1.53806 2.62891 + endloop + endfacet + facet normal 0.197778 0.0210954 0.98002 + outer loop + vertex 1.01848 1.53759 2.62799 + vertex 1.01853 1.54266 2.62787 + vertex 1.01384 1.53806 2.62891 + endloop + endfacet + facet normal 0.200116 0.018619 0.979595 + outer loop + vertex 1.01384 1.53806 2.62891 + vertex 1.01853 1.54266 2.62787 + vertex 1.0139 1.54311 2.62881 + endloop + endfacet + facet normal 0.200862 0.0268611 0.979251 + outer loop + vertex 1.01853 1.54266 2.62787 + vertex 1.01853 1.54768 2.62773 + vertex 1.0139 1.54311 2.62881 + endloop + endfacet + facet normal 0.20639 0.021022 0.978244 + outer loop + vertex 1.0139 1.54311 2.62881 + vertex 1.01853 1.54768 2.62773 + vertex 1.01393 1.54817 2.62869 + endloop + endfacet + facet normal 0.207239 0.0298743 0.977834 + outer loop + vertex 1.01853 1.54768 2.62773 + vertex 1.01845 1.55269 2.62759 + vertex 1.01393 1.54817 2.62869 + endloop + endfacet + facet normal 0.212555 0.0243208 0.976846 + outer loop + vertex 1.01393 1.54817 2.62869 + vertex 1.01845 1.55269 2.62759 + vertex 1.01393 1.5532 2.62856 + endloop + endfacet + facet normal 0.213717 0.0357671 0.976241 + outer loop + vertex 1.01845 1.55269 2.62759 + vertex 1.01824 1.55754 2.62746 + vertex 1.01393 1.5532 2.62856 + endloop + endfacet + facet normal 0.222001 0.0271354 0.974669 + outer loop + vertex 1.01393 1.5532 2.62856 + vertex 1.01824 1.55754 2.62746 + vertex 1.01393 1.5582 2.62843 + endloop + endfacet + facet normal 0.223024 0.0344338 0.974205 + outer loop + vertex 1.01824 1.55754 2.62746 + vertex 1.01823 1.56238 2.62729 + vertex 1.01393 1.5582 2.62843 + endloop + endfacet + facet normal 0.228423 0.0285865 0.973142 + outer loop + vertex 1.01393 1.5582 2.62843 + vertex 1.01823 1.56238 2.62729 + vertex 1.01393 1.56323 2.62828 + endloop + endfacet + facet normal 0.230309 0.0389938 0.972336 + outer loop + vertex 1.01823 1.56238 2.62729 + vertex 1.01813 1.56742 2.62711 + vertex 1.01393 1.56323 2.62828 + endloop + endfacet + facet normal 0.23408 0.034997 0.971587 + outer loop + vertex 1.01393 1.56323 2.62828 + vertex 1.01813 1.56742 2.62711 + vertex 1.01381 1.56824 2.62813 + endloop + endfacet + facet normal 0.23668 0.0501913 0.97029 + outer loop + vertex 1.01813 1.56742 2.62711 + vertex 1.01758 1.57236 2.62699 + vertex 1.01381 1.56824 2.62813 + endloop + endfacet + facet normal 0.249653 0.0375584 0.967607 + outer loop + vertex 1.01381 1.56824 2.62813 + vertex 1.01758 1.57236 2.62699 + vertex 1.01356 1.57306 2.628 + endloop + endfacet + facet normal 0.252173 0.0538518 0.966183 + outer loop + vertex 1.01758 1.57236 2.62699 + vertex 1.01674 1.57635 2.62699 + vertex 1.01356 1.57306 2.628 + endloop + endfacet + facet normal 0.270171 0.0352367 0.962167 + outer loop + vertex 1.01356 1.57306 2.628 + vertex 1.01674 1.57635 2.62699 + vertex 1.01353 1.57787 2.62783 + endloop + endfacet + facet normal 0.267872 0.029936 0.962989 + outer loop + vertex 1.01674 1.57635 2.62699 + vertex 1.01776 1.58114 2.62656 + vertex 1.01353 1.57787 2.62783 + endloop + endfacet + facet normal 0.263677 0.0357547 0.963948 + outer loop + vertex 1.01353 1.57787 2.62783 + vertex 1.01776 1.58114 2.62656 + vertex 1.01342 1.58292 2.62768 + endloop + endfacet + facet normal 0.271467 0.0567084 0.960776 + outer loop + vertex 1.01776 1.58114 2.62656 + vertex 1.0168 1.58664 2.6265 + vertex 1.01342 1.58292 2.62768 + endloop + endfacet + facet normal 0.286107 0.0422946 0.957264 + outer loop + vertex 1.01342 1.58292 2.62768 + vertex 1.0168 1.58664 2.6265 + vertex 1.01287 1.58792 2.62762 + endloop + endfacet + facet normal 0.290435 0.0574345 0.955169 + outer loop + vertex 1.0168 1.58664 2.6265 + vertex 1.01578 1.59203 2.62649 + vertex 1.01287 1.58792 2.62762 + endloop + endfacet + facet normal 0.314266 0.0387311 0.948545 + outer loop + vertex 1.01287 1.58792 2.62762 + vertex 1.01578 1.59203 2.62649 + vertex 1.01209 1.59202 2.62771 + endloop + endfacet + facet normal 0.314137 0.0468779 0.94822 + outer loop + vertex 1.01307 1.59664 2.62716 + vertex 1.01209 1.59202 2.62771 + vertex 1.01578 1.59203 2.62649 + endloop + endfacet + facet normal 0.309453 0.0438735 0.949902 + outer loop + vertex 1.01674 1.59635 2.62598 + vertex 1.01307 1.59664 2.62716 + vertex 1.01578 1.59203 2.62649 + endloop + endfacet + facet normal 0.233146 0.0632826 0.97038 + outer loop + vertex 1.01674 1.59635 2.62598 + vertex 1.01578 1.59203 2.62649 + vertex 1.01904 1.59419 2.62557 + endloop + endfacet + facet normal 0.212715 0.0404525 0.976277 + outer loop + vertex 1.01904 1.59419 2.62557 + vertex 1.02018 1.59851 2.62514 + vertex 1.01674 1.59635 2.62598 + endloop + endfacet + facet normal 0.215953 0.0351139 0.975772 + outer loop + vertex 1.01674 1.59635 2.62598 + vertex 1.02018 1.59851 2.62514 + vertex 1.01612 1.60045 2.62597 + endloop + endfacet + facet normal 0.225092 0.0556077 0.972749 + outer loop + vertex 1.02018 1.59851 2.62514 + vertex 1.01951 1.60381 2.62499 + vertex 1.01612 1.60045 2.62597 + endloop + endfacet + facet normal 0.23455 0.0455689 0.971035 + outer loop + vertex 1.01612 1.60045 2.62597 + vertex 1.01951 1.60381 2.62499 + vertex 1.0156 1.60542 2.62586 + endloop + endfacet + facet normal 0.322955 0.0543515 0.944852 + outer loop + vertex 1.0156 1.60542 2.62586 + vertex 1.01244 1.6022 2.62712 + vertex 1.01612 1.60045 2.62597 + endloop + endfacet + facet normal 0.317867 0.0421075 0.9472 + outer loop + vertex 1.01244 1.6022 2.62712 + vertex 1.01307 1.59664 2.62716 + vertex 1.01612 1.60045 2.62597 + endloop + endfacet + facet normal 0.331346 0.0451637 0.942428 + outer loop + vertex 1.01203 1.60727 2.62703 + vertex 1.01244 1.6022 2.62712 + vertex 1.0156 1.60542 2.62586 + endloop + endfacet + facet normal 0.334528 0.0522209 0.940938 + outer loop + vertex 1.01522 1.61037 2.62572 + vertex 1.01203 1.60727 2.62703 + vertex 1.0156 1.60542 2.62586 + endloop + endfacet + facet normal 0.243928 0.0461981 0.968692 + outer loop + vertex 1.0156 1.60542 2.62586 + vertex 1.01921 1.60885 2.62479 + vertex 1.01522 1.61037 2.62572 + endloop + endfacet + facet normal 0.246047 0.0522652 0.967848 + outer loop + vertex 1.01921 1.60885 2.62479 + vertex 1.01897 1.61391 2.62457 + vertex 1.01522 1.61037 2.62572 + endloop + endfacet + facet normal 0.255262 0.0418992 0.965964 + outer loop + vertex 1.01522 1.61037 2.62572 + vertex 1.01897 1.61391 2.62457 + vertex 1.01479 1.61527 2.62562 + endloop + endfacet + facet normal 0.349195 0.0496009 0.935736 + outer loop + vertex 1.01479 1.61527 2.62562 + vertex 1.01164 1.61224 2.62696 + vertex 1.01522 1.61037 2.62572 + endloop + endfacet + facet normal 0.361076 0.0355159 0.93186 + outer loop + vertex 1.01099 1.61751 2.62701 + vertex 1.01164 1.61224 2.62696 + vertex 1.01479 1.61527 2.62562 + endloop + endfacet + facet normal 0.374267 0.061894 0.925253 + outer loop + vertex 1.01479 1.61527 2.62562 + vertex 1.01422 1.61925 2.62559 + vertex 1.01099 1.61751 2.62701 + endloop + endfacet + facet normal 0.266938 0.0467537 0.962579 + outer loop + vertex 1.01422 1.61925 2.62559 + vertex 1.01479 1.61527 2.62562 + vertex 1.0185 1.61933 2.62439 + endloop + endfacet + facet normal 0.266845 0.0497182 0.962456 + outer loop + vertex 1.01422 1.61925 2.62559 + vertex 1.0185 1.61933 2.62439 + vertex 1.01559 1.62365 2.62498 + endloop + endfacet + facet normal 0.261964 0.0462163 0.96397 + outer loop + vertex 1.01559 1.62365 2.62498 + vertex 1.0185 1.61933 2.62439 + vertex 1.01994 1.62407 2.62378 + endloop + endfacet + facet normal 0.26067 0.0585675 0.96365 + outer loop + vertex 1.01994 1.62407 2.62378 + vertex 1.01922 1.62805 2.62373 + vertex 1.01559 1.62365 2.62498 + endloop + endfacet + facet normal 0.283103 0.0385578 0.958314 + outer loop + vertex 1.01559 1.62365 2.62498 + vertex 1.01922 1.62805 2.62373 + vertex 1.01502 1.62907 2.62493 + endloop + endfacet + facet normal 0.287063 0.0573666 0.956192 + outer loop + vertex 1.01922 1.62805 2.62373 + vertex 1.01886 1.63298 2.62354 + vertex 1.01502 1.62907 2.62493 + endloop + endfacet + facet normal 0.298617 0.0449956 0.953312 + outer loop + vertex 1.01502 1.62907 2.62493 + vertex 1.01886 1.63298 2.62354 + vertex 1.01481 1.63414 2.62475 + endloop + endfacet + facet normal 0.302754 0.0617002 0.95107 + outer loop + vertex 1.01886 1.63298 2.62354 + vertex 1.01858 1.6379 2.62331 + vertex 1.01481 1.63414 2.62475 + endloop + endfacet + facet normal 0.318139 0.0446836 0.94699 + outer loop + vertex 1.01481 1.63414 2.62475 + vertex 1.01858 1.6379 2.62331 + vertex 1.01474 1.63915 2.62454 + endloop + endfacet + facet normal 0.322002 0.0585606 0.944926 + outer loop + vertex 1.01858 1.6379 2.62331 + vertex 1.01847 1.6428 2.62304 + vertex 1.01474 1.63915 2.62454 + endloop + endfacet + facet normal 0.33327 0.0457295 0.941722 + outer loop + vertex 1.01474 1.63915 2.62454 + vertex 1.01847 1.6428 2.62304 + vertex 1.01463 1.64417 2.62434 + endloop + endfacet + facet normal 0.338112 0.0618122 0.939074 + outer loop + vertex 1.01847 1.6428 2.62304 + vertex 1.01813 1.6478 2.62284 + vertex 1.01463 1.64417 2.62434 + endloop + endfacet + facet normal 0.351237 0.0474794 0.935082 + outer loop + vertex 1.01463 1.64417 2.62434 + vertex 1.01813 1.6478 2.62284 + vertex 1.01439 1.64908 2.62418 + endloop + endfacet + facet normal 0.358395 0.0731103 0.930703 + outer loop + vertex 1.01813 1.6478 2.62284 + vertex 1.01726 1.65199 2.62284 + vertex 1.01439 1.64908 2.62418 + endloop + endfacet + facet normal 0.382151 0.046182 0.922945 + outer loop + vertex 1.01439 1.64908 2.62418 + vertex 1.01726 1.65199 2.62284 + vertex 1.01432 1.6539 2.62397 + endloop + endfacet + facet normal 0.380418 0.0430049 0.923814 + outer loop + vertex 1.01726 1.65199 2.62284 + vertex 1.01818 1.65662 2.62225 + vertex 1.01432 1.6539 2.62397 + endloop + endfacet + facet normal 0.378893 0.0454902 0.924322 + outer loop + vertex 1.01432 1.6539 2.62397 + vertex 1.01818 1.65662 2.62225 + vertex 1.01424 1.65894 2.62375 + endloop + endfacet + facet normal 0.389075 0.066418 0.918809 + outer loop + vertex 1.01818 1.65662 2.62225 + vertex 1.01741 1.66214 2.62217 + vertex 1.01424 1.65894 2.62375 + endloop + endfacet + facet normal 0.406598 0.0458861 0.912454 + outer loop + vertex 1.01424 1.65894 2.62375 + vertex 1.01741 1.66214 2.62217 + vertex 1.01387 1.66404 2.62366 + endloop + endfacet + facet normal 0.413496 0.0618907 0.9084 + outer loop + vertex 1.01741 1.66214 2.62217 + vertex 1.01681 1.66725 2.6221 + vertex 1.01387 1.66404 2.62366 + endloop + endfacet + facet normal 0.431144 0.0422434 0.901294 + outer loop + vertex 1.01387 1.66404 2.62366 + vertex 1.01681 1.66725 2.6221 + vertex 1.01341 1.66898 2.62364 + endloop + endfacet + facet normal 0.436999 0.0569883 0.897655 + outer loop + vertex 1.01681 1.66725 2.6221 + vertex 1.01608 1.67261 2.62211 + vertex 1.01341 1.66898 2.62364 + endloop + endfacet + facet normal 0.457472 0.0380272 0.88841 + outer loop + vertex 1.01341 1.66898 2.62364 + vertex 1.01608 1.67261 2.62211 + vertex 1.01278 1.67312 2.6238 + endloop + endfacet + facet normal 0.458148 0.0445241 0.88776 + outer loop + vertex 1.01374 1.6775 2.62308 + vertex 1.01278 1.67312 2.6238 + vertex 1.01608 1.67261 2.62211 + endloop + endfacet + facet normal 0.258965 0.0545577 0.964345 + outer loop + vertex 1.01897 1.61391 2.62457 + vertex 1.0185 1.61933 2.62439 + vertex 1.01479 1.61527 2.62562 + endloop + endfacet + facet normal 0.344955 0.0401412 0.937761 + outer loop + vertex 1.01164 1.61224 2.62696 + vertex 1.01203 1.60727 2.62703 + vertex 1.01522 1.61037 2.62572 + endloop + endfacet + facet normal 0.237501 0.0533449 0.969921 + outer loop + vertex 1.01951 1.60381 2.62499 + vertex 1.01921 1.60885 2.62479 + vertex 1.0156 1.60542 2.62586 + endloop + endfacet + facet normal 0.309764 0.0493203 0.949534 + outer loop + vertex 1.01612 1.60045 2.62597 + vertex 1.01307 1.59664 2.62716 + vertex 1.01674 1.59635 2.62598 + endloop + endfacet + facet normal 0.159599 0.0337274 0.986606 + outer loop + vertex 1.01845 1.55269 2.62759 + vertex 1.02273 1.55719 2.62675 + vertex 1.01824 1.55754 2.62746 + endloop + endfacet + facet normal 0.160453 0.0461511 0.985964 + outer loop + vertex 1.02273 1.55719 2.62675 + vertex 1.02179 1.56125 2.62671 + vertex 1.01824 1.55754 2.62746 + endloop + endfacet + facet normal 0.172173 0.0346403 0.984457 + outer loop + vertex 1.01824 1.55754 2.62746 + vertex 1.02179 1.56125 2.62671 + vertex 1.01823 1.56238 2.62729 + endloop + endfacet + facet normal 0.171362 0.0319559 0.98469 + outer loop + vertex 1.02179 1.56125 2.62671 + vertex 1.02285 1.56615 2.62637 + vertex 1.01823 1.56238 2.62729 + endloop + endfacet + facet normal 0.166359 0.038245 0.985323 + outer loop + vertex 1.01823 1.56238 2.62729 + vertex 1.02285 1.56615 2.62637 + vertex 1.01813 1.56742 2.62711 + endloop + endfacet + facet normal 0.169604 0.0510181 0.984191 + outer loop + vertex 1.02285 1.56615 2.62637 + vertex 1.02183 1.5716 2.62626 + vertex 1.01813 1.56742 2.62711 + endloop + endfacet + facet normal 0.177467 0.0438415 0.98315 + outer loop + vertex 1.01813 1.56742 2.62711 + vertex 1.02183 1.5716 2.62626 + vertex 1.01758 1.57236 2.62699 + endloop + endfacet + facet normal 0.179053 0.0534721 0.982385 + outer loop + vertex 1.02183 1.5716 2.62626 + vertex 1.02077 1.57689 2.62617 + vertex 1.01758 1.57236 2.62699 + endloop + endfacet + facet normal 0.194959 0.0418421 0.979918 + outer loop + vertex 1.01758 1.57236 2.62699 + vertex 1.02077 1.57689 2.62617 + vertex 1.01674 1.57635 2.62699 + endloop + endfacet + facet normal 0.194209 0.0472883 0.97982 + outer loop + vertex 1.01776 1.58114 2.62656 + vertex 1.01674 1.57635 2.62699 + vertex 1.02077 1.57689 2.62617 + endloop + endfacet + facet normal 0.191391 0.0452333 0.980471 + outer loop + vertex 1.02175 1.58132 2.62577 + vertex 1.01776 1.58114 2.62656 + vertex 1.02077 1.57689 2.62617 + endloop + endfacet + facet normal 0.139737 0.0573848 0.988524 + outer loop + vertex 1.02175 1.58132 2.62577 + vertex 1.02077 1.57689 2.62617 + vertex 1.02416 1.57934 2.62554 + endloop + endfacet + facet normal 0.130429 0.045793 0.9904 + outer loop + vertex 1.02416 1.57934 2.62554 + vertex 1.02518 1.58362 2.62521 + vertex 1.02175 1.58132 2.62577 + endloop + endfacet + facet normal 0.133814 0.040672 0.990172 + outer loop + vertex 1.02175 1.58132 2.62577 + vertex 1.02518 1.58362 2.62521 + vertex 1.02088 1.58529 2.62572 + endloop + endfacet + facet normal 0.139744 0.0563687 0.988582 + outer loop + vertex 1.02518 1.58362 2.62521 + vertex 1.02413 1.58883 2.62506 + vertex 1.02088 1.58529 2.62572 + endloop + endfacet + facet normal 0.149311 0.04738 0.987654 + outer loop + vertex 1.02088 1.58529 2.62572 + vertex 1.02413 1.58883 2.62506 + vertex 1.01989 1.59016 2.62564 + endloop + endfacet + facet normal 0.206027 0.0587235 0.976783 + outer loop + vertex 1.01989 1.59016 2.62564 + vertex 1.0168 1.58664 2.6265 + vertex 1.02088 1.58529 2.62572 + endloop + endfacet + facet normal 0.201694 0.0446871 0.978429 + outer loop + vertex 1.0168 1.58664 2.6265 + vertex 1.01776 1.58114 2.62656 + vertex 1.02088 1.58529 2.62572 + endloop + endfacet + facet normal 0.221534 0.0444825 0.974138 + outer loop + vertex 1.01578 1.59203 2.62649 + vertex 1.0168 1.58664 2.6265 + vertex 1.01989 1.59016 2.62564 + endloop + endfacet + facet normal 0.230953 0.0667167 0.970675 + outer loop + vertex 1.01989 1.59016 2.62564 + vertex 1.01904 1.59419 2.62557 + vertex 1.01578 1.59203 2.62649 + endloop + endfacet + facet normal 0.158331 0.0516615 0.986034 + outer loop + vertex 1.01904 1.59419 2.62557 + vertex 1.01989 1.59016 2.62564 + vertex 1.02321 1.59423 2.62489 + endloop + endfacet + facet normal 0.158259 0.0558404 0.985817 + outer loop + vertex 1.01904 1.59419 2.62557 + vertex 1.02321 1.59423 2.62489 + vertex 1.02018 1.59851 2.62514 + endloop + endfacet + facet normal 0.152754 0.0518924 0.986901 + outer loop + vertex 1.02018 1.59851 2.62514 + vertex 1.02321 1.59423 2.62489 + vertex 1.02449 1.59889 2.62445 + endloop + endfacet + facet normal 0.152152 0.0582367 0.98664 + outer loop + vertex 1.02449 1.59889 2.62445 + vertex 1.02384 1.6029 2.62431 + vertex 1.02018 1.59851 2.62514 + endloop + endfacet + facet normal 0.163932 0.0481683 0.985295 + outer loop + vertex 1.02018 1.59851 2.62514 + vertex 1.02384 1.6029 2.62431 + vertex 1.01951 1.60381 2.62499 + endloop + endfacet + facet normal 0.165819 0.0577815 0.984462 + outer loop + vertex 1.02384 1.6029 2.62431 + vertex 1.02364 1.60784 2.62406 + vertex 1.01951 1.60381 2.62499 + endloop + endfacet + facet normal 0.173192 0.0500459 0.983616 + outer loop + vertex 1.01951 1.60381 2.62499 + vertex 1.02364 1.60784 2.62406 + vertex 1.01921 1.60885 2.62479 + endloop + endfacet + facet normal 0.174943 0.0583279 0.982849 + outer loop + vertex 1.02364 1.60784 2.62406 + vertex 1.0236 1.61293 2.62376 + vertex 1.01921 1.60885 2.62479 + endloop + endfacet + facet normal 0.182566 0.0499014 0.981926 + outer loop + vertex 1.01921 1.60885 2.62479 + vertex 1.0236 1.61293 2.62376 + vertex 1.01897 1.61391 2.62457 + endloop + endfacet + facet normal 0.184433 0.0594651 0.981044 + outer loop + vertex 1.0236 1.61293 2.62376 + vertex 1.0235 1.61803 2.62347 + vertex 1.01897 1.61391 2.62457 + endloop + endfacet + facet normal 0.193328 0.049367 0.979891 + outer loop + vertex 1.01897 1.61391 2.62457 + vertex 1.0235 1.61803 2.62347 + vertex 1.0185 1.61933 2.62439 + endloop + endfacet + facet normal 0.196771 0.0636022 0.978384 + outer loop + vertex 1.0235 1.61803 2.62347 + vertex 1.02355 1.62295 2.62314 + vertex 1.0185 1.61933 2.62439 + endloop + endfacet + facet normal 0.192908 0.0691366 0.978778 + outer loop + vertex 1.0185 1.61933 2.62439 + vertex 1.02355 1.62295 2.62314 + vertex 1.01994 1.62407 2.62378 + endloop + endfacet + facet normal 0.192268 0.0669153 0.979058 + outer loop + vertex 1.02355 1.62295 2.62314 + vertex 1.02344 1.62749 2.62285 + vertex 1.01994 1.62407 2.62378 + endloop + endfacet + facet normal 0.208829 0.0493353 0.976707 + outer loop + vertex 1.01994 1.62407 2.62378 + vertex 1.02344 1.62749 2.62285 + vertex 1.01922 1.62805 2.62373 + endloop + endfacet + facet normal 0.210709 0.0656451 0.975342 + outer loop + vertex 1.02344 1.62749 2.62285 + vertex 1.02317 1.63213 2.6226 + vertex 1.01922 1.62805 2.62373 + endloop + endfacet + facet normal 0.222853 0.0533494 0.973391 + outer loop + vertex 1.01922 1.62805 2.62373 + vertex 1.02317 1.63213 2.6226 + vertex 1.01886 1.63298 2.62354 + endloop + endfacet + facet normal 0.225868 0.0706363 0.971594 + outer loop + vertex 1.02317 1.63213 2.6226 + vertex 1.02273 1.63712 2.62234 + vertex 1.01886 1.63298 2.62354 + endloop + endfacet + facet normal 0.237848 0.0588225 0.96952 + outer loop + vertex 1.01886 1.63298 2.62354 + vertex 1.02273 1.63712 2.62234 + vertex 1.01858 1.6379 2.62331 + endloop + endfacet + facet normal 0.240983 0.0780884 0.967383 + outer loop + vertex 1.02273 1.63712 2.62234 + vertex 1.02176 1.64129 2.62224 + vertex 1.01858 1.6379 2.62331 + endloop + endfacet + facet normal 0.260876 0.0582138 0.963616 + outer loop + vertex 1.01858 1.6379 2.62331 + vertex 1.02176 1.64129 2.62224 + vertex 1.01847 1.6428 2.62304 + endloop + endfacet + facet normal 0.26092 0.0583216 0.963597 + outer loop + vertex 1.02176 1.64129 2.62224 + vertex 1.02257 1.6462 2.62173 + vertex 1.01847 1.6428 2.62304 + endloop + endfacet + facet normal 0.261397 0.0577104 0.963505 + outer loop + vertex 1.01847 1.6428 2.62304 + vertex 1.02257 1.6462 2.62173 + vertex 1.01813 1.6478 2.62284 + endloop + endfacet + facet normal 0.268159 0.078784 0.960148 + outer loop + vertex 1.02257 1.6462 2.62173 + vertex 1.02111 1.65204 2.62166 + vertex 1.01813 1.6478 2.62284 + endloop + endfacet + facet normal 0.29322 0.059486 0.954193 + outer loop + vertex 1.01813 1.6478 2.62284 + vertex 1.02111 1.65204 2.62166 + vertex 1.01726 1.65199 2.62284 + endloop + endfacet + facet normal 0.293085 0.0641475 0.953932 + outer loop + vertex 1.01818 1.65662 2.62225 + vertex 1.01726 1.65199 2.62284 + vertex 1.02111 1.65204 2.62166 + endloop + endfacet + facet normal 0.295671 0.0659233 0.953013 + outer loop + vertex 1.02192 1.6564 2.6211 + vertex 1.01818 1.65662 2.62225 + vertex 1.02111 1.65204 2.62166 + endloop + endfacet + facet normal 0.223983 0.0815115 0.971178 + outer loop + vertex 1.02192 1.6564 2.6211 + vertex 1.02111 1.65204 2.62166 + vertex 1.02436 1.65431 2.62072 + endloop + endfacet + facet normal 0.209352 0.0636776 0.975765 + outer loop + vertex 1.02436 1.65431 2.62072 + vertex 1.02542 1.65861 2.62021 + vertex 1.02192 1.6564 2.6211 + endloop + endfacet + facet normal 0.21488 0.0546693 0.975109 + outer loop + vertex 1.02192 1.6564 2.6211 + vertex 1.02542 1.65861 2.62021 + vertex 1.02121 1.66045 2.62103 + endloop + endfacet + facet normal 0.223278 0.0754189 0.971833 + outer loop + vertex 1.02542 1.65861 2.62021 + vertex 1.02466 1.66387 2.61998 + vertex 1.02121 1.66045 2.62103 + endloop + endfacet + facet normal 0.237874 0.0599765 0.969443 + outer loop + vertex 1.02121 1.66045 2.62103 + vertex 1.02466 1.66387 2.61998 + vertex 1.02056 1.6654 2.62089 + endloop + endfacet + facet normal 0.315477 0.0695042 0.946384 + outer loop + vertex 1.02056 1.6654 2.62089 + vertex 1.01741 1.66214 2.62217 + vertex 1.02121 1.66045 2.62103 + endloop + endfacet + facet normal 0.31023 0.0559337 0.949015 + outer loop + vertex 1.01741 1.66214 2.62217 + vertex 1.01818 1.65662 2.62225 + vertex 1.02121 1.66045 2.62103 + endloop + endfacet + facet normal 0.331157 0.0527011 0.942103 + outer loop + vertex 1.01681 1.66725 2.6221 + vertex 1.01741 1.66214 2.62217 + vertex 1.02056 1.6654 2.62089 + endloop + endfacet + facet normal 0.337122 0.0667584 0.939091 + outer loop + vertex 1.01995 1.67037 2.62075 + vertex 1.01681 1.66725 2.6221 + vertex 1.02056 1.6654 2.62089 + endloop + endfacet + facet normal 0.254362 0.057314 0.965409 + outer loop + vertex 1.02056 1.6654 2.62089 + vertex 1.02418 1.66898 2.61972 + vertex 1.01995 1.67037 2.62075 + endloop + endfacet + facet normal 0.258395 0.0710168 0.963425 + outer loop + vertex 1.02418 1.66898 2.61972 + vertex 1.02358 1.67445 2.61948 + vertex 1.01995 1.67037 2.62075 + endloop + endfacet + facet normal 0.268801 0.0610581 0.961259 + outer loop + vertex 1.01932 1.67442 2.62067 + vertex 1.01995 1.67037 2.62075 + vertex 1.02358 1.67445 2.61948 + endloop + endfacet + facet normal 0.268699 0.0654713 0.960997 + outer loop + vertex 1.01932 1.67442 2.62067 + vertex 1.02358 1.67445 2.61948 + vertex 1.02069 1.67878 2.61999 + endloop + endfacet + facet normal 0.265914 0.0635091 0.961903 + outer loop + vertex 1.02069 1.67878 2.61999 + vertex 1.02358 1.67445 2.61948 + vertex 1.02496 1.67913 2.61879 + endloop + endfacet + facet normal 0.264976 0.0734882 0.96145 + outer loop + vertex 1.02496 1.67913 2.61879 + vertex 1.0242 1.68307 2.6187 + vertex 1.02069 1.67878 2.61999 + endloop + endfacet + facet normal 0.290796 0.0505789 0.955447 + outer loop + vertex 1.02069 1.67878 2.61999 + vertex 1.0242 1.68307 2.6187 + vertex 1.02011 1.68412 2.61988 + endloop + endfacet + facet normal 0.295827 0.0735694 0.952404 + outer loop + vertex 1.0242 1.68307 2.6187 + vertex 1.02366 1.68777 2.6185 + vertex 1.02011 1.68412 2.61988 + endloop + endfacet + facet normal 0.317375 0.0504896 0.946955 + outer loop + vertex 1.02011 1.68412 2.61988 + vertex 1.02366 1.68777 2.6185 + vertex 1.01982 1.68917 2.61971 + endloop + endfacet + facet normal 0.323187 0.0690953 0.943809 + outer loop + vertex 1.02366 1.68777 2.6185 + vertex 1.02343 1.69261 2.61823 + vertex 1.01982 1.68917 2.61971 + endloop + endfacet + facet normal 0.336996 0.0529379 0.940017 + outer loop + vertex 1.01982 1.68917 2.61971 + vertex 1.02343 1.69261 2.61823 + vertex 1.01964 1.69418 2.61949 + endloop + endfacet + facet normal 0.343162 0.0705709 0.936621 + outer loop + vertex 1.02343 1.69261 2.61823 + vertex 1.02306 1.6976 2.61799 + vertex 1.01964 1.69418 2.61949 + endloop + endfacet + facet normal 0.35604 0.0560103 0.932791 + outer loop + vertex 1.01964 1.69418 2.61949 + vertex 1.02306 1.6976 2.61799 + vertex 1.01939 1.69899 2.6193 + endloop + endfacet + facet normal 0.363763 0.0808994 0.927972 + outer loop + vertex 1.02306 1.6976 2.61799 + vertex 1.02218 1.70179 2.61796 + vertex 1.01939 1.69899 2.6193 + endloop + endfacet + facet normal 0.38834 0.0526576 0.92001 + outer loop + vertex 1.01939 1.69899 2.6193 + vertex 1.02218 1.70179 2.61796 + vertex 1.01928 1.70374 2.61907 + endloop + endfacet + facet normal 0.386871 0.0500522 0.920774 + outer loop + vertex 1.02218 1.70179 2.61796 + vertex 1.0231 1.70647 2.61732 + vertex 1.01928 1.70374 2.61907 + endloop + endfacet + facet normal 0.388582 0.0472937 0.9202 + outer loop + vertex 1.01928 1.70374 2.61907 + vertex 1.0231 1.70647 2.61732 + vertex 1.01918 1.70878 2.61886 + endloop + endfacet + facet normal 0.40087 0.0728291 0.913235 + outer loop + vertex 1.0231 1.70647 2.61732 + vertex 1.02237 1.71202 2.6172 + vertex 1.01918 1.70878 2.61886 + endloop + endfacet + facet normal 0.422234 0.0477634 0.905228 + outer loop + vertex 1.01918 1.70878 2.61886 + vertex 1.02237 1.71202 2.6172 + vertex 1.01886 1.7139 2.61874 + endloop + endfacet + facet normal 0.430097 0.0664613 0.900333 + outer loop + vertex 1.02237 1.71202 2.6172 + vertex 1.0218 1.71711 2.6171 + vertex 1.01886 1.7139 2.61874 + endloop + endfacet + facet normal 0.44945 0.0444728 0.892198 + outer loop + vertex 1.01886 1.7139 2.61874 + vertex 1.0218 1.71711 2.6171 + vertex 1.01844 1.71883 2.6187 + endloop + endfacet + facet normal 0.456022 0.0613109 0.887854 + outer loop + vertex 1.0218 1.71711 2.6171 + vertex 1.02107 1.72241 2.61711 + vertex 1.01844 1.71883 2.6187 + endloop + endfacet + facet normal 0.370414 0.07608 0.925746 + outer loop + vertex 1.01995 1.67037 2.62075 + vertex 1.01932 1.67442 2.62067 + vertex 1.01608 1.67261 2.62211 + endloop + endfacet + facet normal 0.35563 0.0457993 0.933504 + outer loop + vertex 1.01608 1.67261 2.62211 + vertex 1.01681 1.66725 2.6221 + vertex 1.01995 1.67037 2.62075 + endloop + endfacet + facet normal 0.2416 0.0710037 0.967775 + outer loop + vertex 1.02466 1.66387 2.61998 + vertex 1.02418 1.66898 2.61972 + vertex 1.02056 1.6654 2.62089 + endloop + endfacet + facet normal 0.295762 0.0685958 0.952796 + outer loop + vertex 1.02121 1.66045 2.62103 + vertex 1.01818 1.65662 2.62225 + vertex 1.02192 1.6564 2.6211 + endloop + endfacet + facet normal 0.213203 0.0652558 0.974826 + outer loop + vertex 1.02111 1.65204 2.62166 + vertex 1.02257 1.6462 2.62173 + vertex 1.02545 1.65034 2.62082 + endloop + endfacet + facet normal 0.220778 0.0862201 0.971506 + outer loop + vertex 1.02545 1.65034 2.62082 + vertex 1.02436 1.65431 2.62072 + vertex 1.02111 1.65204 2.62166 + endloop + endfacet + facet normal 0.165616 0.0712728 0.983611 + outer loop + vertex 1.02436 1.65431 2.62072 + vertex 1.02545 1.65034 2.62082 + vertex 1.02864 1.65436 2.61999 + endloop + endfacet + facet normal 0.165514 0.0754299 0.983319 + outer loop + vertex 1.02436 1.65431 2.62072 + vertex 1.02864 1.65436 2.61999 + vertex 1.02542 1.65861 2.62021 + endloop + endfacet + facet normal 0.16378 0.0740987 0.98371 + outer loop + vertex 1.02542 1.65861 2.62021 + vertex 1.02864 1.65436 2.61999 + vertex 1.02981 1.65905 2.61944 + endloop + endfacet + facet normal 0.16312 0.0800658 0.983352 + outer loop + vertex 1.02981 1.65905 2.61944 + vertex 1.02911 1.66305 2.61923 + vertex 1.02542 1.65861 2.62021 + endloop + endfacet + facet normal 0.176067 0.0690098 0.981956 + outer loop + vertex 1.02542 1.65861 2.62021 + vertex 1.02911 1.66305 2.61923 + vertex 1.02466 1.66387 2.61998 + endloop + endfacet + facet normal 0.177807 0.0794406 0.980854 + outer loop + vertex 1.02911 1.66305 2.61923 + vertex 1.02875 1.66794 2.6189 + vertex 1.02466 1.66387 2.61998 + endloop + endfacet + facet normal 0.190077 0.066757 0.979497 + outer loop + vertex 1.02466 1.66387 2.61998 + vertex 1.02875 1.66794 2.6189 + vertex 1.02418 1.66898 2.61972 + endloop + endfacet + facet normal 0.192456 0.0783529 0.978172 + outer loop + vertex 1.02875 1.66794 2.6189 + vertex 1.02845 1.67298 2.61856 + vertex 1.02418 1.66898 2.61972 + endloop + endfacet + facet normal 0.203977 0.0656556 0.976772 + outer loop + vertex 1.02418 1.66898 2.61972 + vertex 1.02845 1.67298 2.61856 + vertex 1.02358 1.67445 2.61948 + endloop + endfacet + facet normal 0.208204 0.0809869 0.974727 + outer loop + vertex 1.02845 1.67298 2.61856 + vertex 1.02836 1.67778 2.61818 + vertex 1.02358 1.67445 2.61948 + endloop + endfacet + facet normal 0.207004 0.0827532 0.974834 + outer loop + vertex 1.02358 1.67445 2.61948 + vertex 1.02836 1.67778 2.61818 + vertex 1.02496 1.67913 2.61879 + endloop + endfacet + facet normal 0.205975 0.0799644 0.975285 + outer loop + vertex 1.02836 1.67778 2.61818 + vertex 1.02836 1.68232 2.61781 + vertex 1.02496 1.67913 2.61879 + endloop + endfacet + facet normal 0.219552 0.0649641 0.973435 + outer loop + vertex 1.02496 1.67913 2.61879 + vertex 1.02836 1.68232 2.61781 + vertex 1.0242 1.68307 2.6187 + endloop + endfacet + facet normal 0.222257 0.0823056 0.971508 + outer loop + vertex 1.02836 1.68232 2.61781 + vertex 1.02779 1.68701 2.61754 + vertex 1.0242 1.68307 2.6187 + endloop + endfacet + facet normal 0.237541 0.0676189 0.969021 + outer loop + vertex 1.0242 1.68307 2.6187 + vertex 1.02779 1.68701 2.61754 + vertex 1.02366 1.68777 2.6185 + endloop + endfacet + facet normal 0.240688 0.0878828 0.966616 + outer loop + vertex 1.02779 1.68701 2.61754 + vertex 1.02671 1.69107 2.61744 + vertex 1.02366 1.68777 2.6185 + endloop + endfacet + facet normal 0.261709 0.0672002 0.962805 + outer loop + vertex 1.02366 1.68777 2.6185 + vertex 1.02671 1.69107 2.61744 + vertex 1.02343 1.69261 2.61823 + endloop + endfacet + facet normal 0.263422 0.0712403 0.962047 + outer loop + vertex 1.02671 1.69107 2.61744 + vertex 1.02747 1.69598 2.61687 + vertex 1.02343 1.69261 2.61823 + endloop + endfacet + facet normal 0.267433 0.0661248 0.961305 + outer loop + vertex 1.02343 1.69261 2.61823 + vertex 1.02747 1.69598 2.61687 + vertex 1.02306 1.6976 2.61799 + endloop + endfacet + facet normal 0.27453 0.0881004 0.957534 + outer loop + vertex 1.02747 1.69598 2.61687 + vertex 1.02602 1.70186 2.61674 + vertex 1.02306 1.6976 2.61799 + endloop + endfacet + facet normal 0.30099 0.0678461 0.951211 + outer loop + vertex 1.02306 1.6976 2.61799 + vertex 1.02602 1.70186 2.61674 + vertex 1.02218 1.70179 2.61796 + endloop + endfacet + facet normal 0.300861 0.0711811 0.951008 + outer loop + vertex 1.0231 1.70647 2.61732 + vertex 1.02218 1.70179 2.61796 + vertex 1.02602 1.70186 2.61674 + endloop + endfacet + facet normal 0.30504 0.0740262 0.949458 + outer loop + vertex 1.02689 1.70632 2.61612 + vertex 1.0231 1.70647 2.61732 + vertex 1.02602 1.70186 2.61674 + endloop + endfacet + facet normal 0.237941 0.0895259 0.967145 + outer loop + vertex 1.02689 1.70632 2.61612 + vertex 1.02602 1.70186 2.61674 + vertex 1.02935 1.70424 2.6157 + endloop + endfacet + facet normal 0.225565 0.0740782 0.971408 + outer loop + vertex 1.02935 1.70424 2.6157 + vertex 1.03051 1.70865 2.6151 + vertex 1.02689 1.70632 2.61612 + endloop + endfacet + facet normal 0.230233 0.0665935 0.970854 + outer loop + vertex 1.02689 1.70632 2.61612 + vertex 1.03051 1.70865 2.6151 + vertex 1.02619 1.7104 2.616 + endloop + endfacet + facet normal 0.237506 0.0862485 0.96755 + outer loop + vertex 1.03051 1.70865 2.6151 + vertex 1.0297 1.71389 2.61483 + vertex 1.02619 1.7104 2.616 + endloop + endfacet + facet normal 0.253975 0.0688046 0.96476 + outer loop + vertex 1.02619 1.7104 2.616 + vertex 1.0297 1.71389 2.61483 + vertex 1.02555 1.71533 2.61582 + endloop + endfacet + facet normal 0.327951 0.0775911 0.941503 + outer loop + vertex 1.02555 1.71533 2.61582 + vertex 1.02237 1.71202 2.6172 + vertex 1.02619 1.7104 2.616 + endloop + endfacet + facet normal 0.322763 0.0632462 0.944364 + outer loop + vertex 1.02237 1.71202 2.6172 + vertex 1.0231 1.70647 2.61732 + vertex 1.02619 1.7104 2.616 + endloop + endfacet + facet normal 0.346251 0.0578112 0.936359 + outer loop + vertex 1.0218 1.71711 2.6171 + vertex 1.02237 1.71202 2.6172 + vertex 1.02555 1.71533 2.61582 + endloop + endfacet + facet normal 0.352833 0.0742773 0.932733 + outer loop + vertex 1.02492 1.72022 2.61567 + vertex 1.0218 1.71711 2.6171 + vertex 1.02555 1.71533 2.61582 + endloop + endfacet + facet normal 0.274041 0.0649796 0.95952 + outer loop + vertex 1.02555 1.71533 2.61582 + vertex 1.02912 1.71888 2.61456 + vertex 1.02492 1.72022 2.61567 + endloop + endfacet + facet normal 0.278164 0.0798874 0.957206 + outer loop + vertex 1.02912 1.71888 2.61456 + vertex 1.02846 1.72424 2.6143 + vertex 1.02492 1.72022 2.61567 + endloop + endfacet + facet normal 0.291126 0.0675046 0.9543 + outer loop + vertex 1.02428 1.72419 2.61558 + vertex 1.02492 1.72022 2.61567 + vertex 1.02846 1.72424 2.6143 + endloop + endfacet + facet normal 0.291161 0.0663059 0.954373 + outer loop + vertex 1.02428 1.72419 2.61558 + vertex 1.02846 1.72424 2.6143 + vertex 1.0256 1.72858 2.61487 + endloop + endfacet + facet normal 0.389437 0.0827658 0.917327 + outer loop + vertex 1.02492 1.72022 2.61567 + vertex 1.02428 1.72419 2.61558 + vertex 1.02107 1.72241 2.61711 + endloop + endfacet + facet normal 0.227072 0.0742632 0.971042 + outer loop + vertex 1.02912 1.71888 2.61456 + vertex 1.03311 1.72265 2.61334 + vertex 1.02846 1.72424 2.6143 + endloop + endfacet + facet normal 0.230379 0.0849729 0.969384 + outer loop + vertex 1.03311 1.72265 2.61334 + vertex 1.03316 1.72745 2.61291 + vertex 1.02846 1.72424 2.6143 + endloop + endfacet + facet normal 0.23088 0.0842172 0.969331 + outer loop + vertex 1.02846 1.72424 2.6143 + vertex 1.03316 1.72745 2.61291 + vertex 1.02981 1.72895 2.61357 + endloop + endfacet + facet normal 0.22673 0.0741497 0.971131 + outer loop + vertex 1.03316 1.72745 2.61291 + vertex 1.0332 1.73227 2.61253 + vertex 1.02981 1.72895 2.61357 + endloop + endfacet + facet normal 0.245541 0.053942 0.967884 + outer loop + vertex 1.02981 1.72895 2.61357 + vertex 1.0332 1.73227 2.61253 + vertex 1.0291 1.73298 2.61353 + endloop + endfacet + facet normal 0.24591 0.0564143 0.96765 + outer loop + vertex 1.0332 1.73227 2.61253 + vertex 1.03275 1.73714 2.61236 + vertex 1.0291 1.73298 2.61353 + endloop + endfacet + facet normal 0.264322 0.039108 0.963641 + outer loop + vertex 1.0291 1.73298 2.61353 + vertex 1.03275 1.73714 2.61236 + vertex 1.02874 1.73785 2.61343 + endloop + endfacet + facet normal 0.219368 0.0541811 0.974137 + outer loop + vertex 1.0332 1.73227 2.61253 + vertex 1.03678 1.73628 2.6115 + vertex 1.03275 1.73714 2.61236 + endloop + endfacet + facet normal 0.217817 0.0460741 0.974902 + outer loop + vertex 1.03678 1.73628 2.6115 + vertex 1.03623 1.74131 2.61138 + vertex 1.03275 1.73714 2.61236 + endloop + endfacet + facet normal 0.23146 0.0340557 0.972248 + outer loop + vertex 1.03275 1.73714 2.61236 + vertex 1.03623 1.74131 2.61138 + vertex 1.03235 1.74195 2.61229 + endloop + endfacet + facet normal 0.263932 0.036622 0.963846 + outer loop + vertex 1.03275 1.73714 2.61236 + vertex 1.03235 1.74195 2.61229 + vertex 1.02874 1.73785 2.61343 + endloop + endfacet + facet normal 0.279387 0.0218925 0.959929 + outer loop + vertex 1.02874 1.73785 2.61343 + vertex 1.03235 1.74195 2.61229 + vertex 1.02857 1.74266 2.61337 + endloop + endfacet + facet normal 0.280256 0.0270668 0.959544 + outer loop + vertex 1.03235 1.74195 2.61229 + vertex 1.03172 1.74591 2.61236 + vertex 1.02857 1.74266 2.61337 + endloop + endfacet + facet normal 0.293823 0.0127568 0.955775 + outer loop + vertex 1.02857 1.74266 2.61337 + vertex 1.03172 1.74591 2.61236 + vertex 1.02867 1.74746 2.61327 + endloop + endfacet + facet normal 0.295674 0.0167511 0.955142 + outer loop + vertex 1.03172 1.74591 2.61236 + vertex 1.03283 1.75069 2.61193 + vertex 1.02867 1.74746 2.61327 + endloop + endfacet + facet normal 0.288538 0.0267358 0.957095 + outer loop + vertex 1.02867 1.74746 2.61327 + vertex 1.03283 1.75069 2.61193 + vertex 1.02857 1.75248 2.61316 + endloop + endfacet + facet normal 0.241068 0.0307062 0.970022 + outer loop + vertex 1.03283 1.75069 2.61193 + vertex 1.03172 1.74591 2.61236 + vertex 1.03559 1.74652 2.61138 + endloop + endfacet + facet normal 0.242582 0.0208951 0.969906 + outer loop + vertex 1.03235 1.74195 2.61229 + vertex 1.03559 1.74652 2.61138 + vertex 1.03172 1.74591 2.61236 + endloop + endfacet + facet normal 0.230826 0.0297701 0.972539 + outer loop + vertex 1.03623 1.74131 2.61138 + vertex 1.03559 1.74652 2.61138 + vertex 1.03235 1.74195 2.61229 + endloop + endfacet + facet normal 0.208832 0.0270856 0.977576 + outer loop + vertex 1.03559 1.74652 2.61138 + vertex 1.03623 1.74131 2.61138 + vertex 1.03963 1.74507 2.61055 + endloop + endfacet + facet normal 0.211113 0.0338296 0.976876 + outer loop + vertex 1.03963 1.74507 2.61055 + vertex 1.03912 1.74905 2.61053 + vertex 1.03559 1.74652 2.61138 + endloop + endfacet + facet normal 0.20897 0.0369265 0.977225 + outer loop + vertex 1.0368 1.75097 2.61095 + vertex 1.03559 1.74652 2.61138 + vertex 1.03912 1.74905 2.61053 + endloop + endfacet + facet normal 0.213037 0.0420819 0.976138 + outer loop + vertex 1.03912 1.74905 2.61053 + vertex 1.04046 1.75345 2.61004 + vertex 1.0368 1.75097 2.61095 + endloop + endfacet + facet normal 0.204977 0.0543455 0.977257 + outer loop + vertex 1.0368 1.75097 2.61095 + vertex 1.04046 1.75345 2.61004 + vertex 1.03602 1.75496 2.61089 + endloop + endfacet + facet normal 0.235461 0.0601951 0.970018 + outer loop + vertex 1.03602 1.75496 2.61089 + vertex 1.03283 1.75069 2.61193 + vertex 1.0368 1.75097 2.61095 + endloop + endfacet + facet normal 0.24156 0.0553263 0.968807 + outer loop + vertex 1.03184 1.75617 2.61186 + vertex 1.03283 1.75069 2.61193 + vertex 1.03602 1.75496 2.61089 + endloop + endfacet + facet normal 0.303259 0.0661988 0.950606 + outer loop + vertex 1.03283 1.75069 2.61193 + vertex 1.03184 1.75617 2.61186 + vertex 1.02857 1.75248 2.61316 + endloop + endfacet + facet normal 0.310119 0.0595085 0.948834 + outer loop + vertex 1.02857 1.75248 2.61316 + vertex 1.03184 1.75617 2.61186 + vertex 1.02791 1.75743 2.61307 + endloop + endfacet + facet normal 0.212774 0.0791112 0.973894 + outer loop + vertex 1.04046 1.75345 2.61004 + vertex 1.03952 1.75876 2.60982 + vertex 1.03602 1.75496 2.61089 + endloop + endfacet + facet normal 0.179919 0.073607 0.980924 + outer loop + vertex 1.04046 1.75345 2.61004 + vertex 1.04418 1.75797 2.60902 + vertex 1.03952 1.75876 2.60982 + endloop + endfacet + facet normal 0.181153 0.0725546 0.980775 + outer loop + vertex 1.04497 1.75401 2.60917 + vertex 1.04418 1.75797 2.60902 + vertex 1.04046 1.75345 2.61004 + endloop + endfacet + facet normal 0.184358 0.0483071 0.981671 + outer loop + vertex 1.04046 1.75345 2.61004 + vertex 1.04341 1.74929 2.60969 + vertex 1.04497 1.75401 2.60917 + endloop + endfacet + facet normal 0.187282 0.0504385 0.98101 + outer loop + vertex 1.03912 1.74905 2.61053 + vertex 1.04341 1.74929 2.60969 + vertex 1.04046 1.75345 2.61004 + endloop + endfacet + facet normal 0.237862 0.0284662 0.970882 + outer loop + vertex 1.0368 1.75097 2.61095 + vertex 1.03283 1.75069 2.61193 + vertex 1.03559 1.74652 2.61138 + endloop + endfacet + facet normal 0.188485 0.0309432 0.981589 + outer loop + vertex 1.03912 1.74905 2.61053 + vertex 1.03963 1.74507 2.61055 + vertex 1.04341 1.74929 2.60969 + endloop + endfacet + facet normal 0.179117 0.039602 0.98303 + outer loop + vertex 1.04378 1.74386 2.60984 + vertex 1.04341 1.74929 2.60969 + vertex 1.03963 1.74507 2.61055 + endloop + endfacet + facet normal 0.177916 0.0352333 0.983415 + outer loop + vertex 1.04011 1.74015 2.61064 + vertex 1.04378 1.74386 2.60984 + vertex 1.03963 1.74507 2.61055 + endloop + endfacet + facet normal 0.198215 0.0371163 0.979456 + outer loop + vertex 1.03963 1.74507 2.61055 + vertex 1.03623 1.74131 2.61138 + vertex 1.04011 1.74015 2.61064 + endloop + endfacet + facet normal 0.200205 0.0442356 0.978755 + outer loop + vertex 1.03623 1.74131 2.61138 + vertex 1.03678 1.73628 2.6115 + vertex 1.04011 1.74015 2.61064 + endloop + endfacet + facet normal 0.18731 0.0557505 0.980717 + outer loop + vertex 1.04011 1.74015 2.61064 + vertex 1.03678 1.73628 2.6115 + vertex 1.04081 1.73519 2.61079 + endloop + endfacet + facet normal 0.168179 0.0531527 0.984322 + outer loop + vertex 1.04081 1.73519 2.61079 + vertex 1.04417 1.73876 2.61002 + vertex 1.04011 1.74015 2.61064 + endloop + endfacet + facet normal 0.166221 0.047163 0.98496 + outer loop + vertex 1.04417 1.73876 2.61002 + vertex 1.04378 1.74386 2.60984 + vertex 1.04011 1.74015 2.61064 + endloop + endfacet + facet normal 0.154161 0.0666555 0.985795 + outer loop + vertex 1.04518 1.73341 2.61023 + vertex 1.04417 1.73876 2.61002 + vertex 1.04081 1.73519 2.61079 + endloop + endfacet + facet normal 0.155254 0.069449 0.98543 + outer loop + vertex 1.04185 1.73107 2.61092 + vertex 1.04518 1.73341 2.61023 + vertex 1.04081 1.73519 2.61079 + endloop + endfacet + facet normal 0.182009 0.076091 0.980348 + outer loop + vertex 1.04081 1.73519 2.61079 + vertex 1.03772 1.73076 2.61171 + vertex 1.04185 1.73107 2.61092 + endloop + endfacet + facet normal 0.180258 0.0958279 0.97894 + outer loop + vertex 1.04185 1.73107 2.61092 + vertex 1.03772 1.73076 2.61171 + vertex 1.0416 1.72603 2.61146 + endloop + endfacet + facet normal 0.160263 0.097182 0.982279 + outer loop + vertex 1.04185 1.73107 2.61092 + vertex 1.0416 1.72603 2.61146 + vertex 1.04458 1.72913 2.61066 + endloop + endfacet + facet normal 0.171623 0.0886311 0.981168 + outer loop + vertex 1.03772 1.73076 2.61171 + vertex 1.03671 1.72588 2.61233 + vertex 1.0416 1.72603 2.61146 + endloop + endfacet + facet normal 0.17145 0.0923976 0.98085 + outer loop + vertex 1.03756 1.72185 2.61256 + vertex 1.0416 1.72603 2.61146 + vertex 1.03671 1.72588 2.61233 + endloop + endfacet + facet normal 0.188758 0.0958489 0.977335 + outer loop + vertex 1.03756 1.72185 2.61256 + vertex 1.03671 1.72588 2.61233 + vertex 1.03311 1.72265 2.61334 + endloop + endfacet + facet normal 0.187404 0.0873056 0.978395 + outer loop + vertex 1.03361 1.71786 2.61367 + vertex 1.03756 1.72185 2.61256 + vertex 1.03311 1.72265 2.61334 + endloop + endfacet + facet normal 0.177478 0.0973721 0.979296 + outer loop + vertex 1.03812 1.71721 2.61292 + vertex 1.03756 1.72185 2.61256 + vertex 1.03361 1.71786 2.61367 + endloop + endfacet + facet normal 0.176338 0.0881671 0.980373 + outer loop + vertex 1.03416 1.7131 2.614 + vertex 1.03812 1.71721 2.61292 + vertex 1.03361 1.71786 2.61367 + endloop + endfacet + facet normal 0.197881 0.0903563 0.976053 + outer loop + vertex 1.03416 1.7131 2.614 + vertex 1.03361 1.71786 2.61367 + vertex 1.0297 1.71389 2.61483 + endloop + endfacet + facet normal 0.210667 0.0772898 0.974498 + outer loop + vertex 1.0297 1.71389 2.61483 + vertex 1.03361 1.71786 2.61367 + vertex 1.02912 1.71888 2.61456 + endloop + endfacet + facet normal 0.167448 0.0969222 0.981105 + outer loop + vertex 1.03864 1.71266 2.61328 + vertex 1.03812 1.71721 2.61292 + vertex 1.03416 1.7131 2.614 + endloop + endfacet + facet normal 0.166705 0.0879182 0.982079 + outer loop + vertex 1.03498 1.70916 2.61421 + vertex 1.03864 1.71266 2.61328 + vertex 1.03416 1.7131 2.614 + endloop + endfacet + facet normal 0.183531 0.0912633 0.978768 + outer loop + vertex 1.03498 1.70916 2.61421 + vertex 1.03416 1.7131 2.614 + vertex 1.03051 1.70865 2.6151 + endloop + endfacet + facet normal 0.184213 0.0858913 0.979126 + outer loop + vertex 1.03051 1.70865 2.6151 + vertex 1.03376 1.7044 2.61486 + vertex 1.03498 1.70916 2.61421 + endloop + endfacet + facet normal 0.159012 0.0928543 0.9829 + outer loop + vertex 1.03376 1.7044 2.61486 + vertex 1.03872 1.70797 2.61372 + vertex 1.03498 1.70916 2.61421 + endloop + endfacet + facet normal 0.158823 0.0931181 0.982906 + outer loop + vertex 1.03885 1.70309 2.61416 + vertex 1.03872 1.70797 2.61372 + vertex 1.03376 1.7044 2.61486 + endloop + endfacet + facet normal 0.156995 0.0854422 0.983896 + outer loop + vertex 1.03505 1.69864 2.61515 + vertex 1.03885 1.70309 2.61416 + vertex 1.03376 1.7044 2.61486 + endloop + endfacet + facet normal 0.177447 0.0898355 0.980021 + outer loop + vertex 1.03505 1.69864 2.61515 + vertex 1.03376 1.7044 2.61486 + vertex 1.03042 1.70021 2.61585 + endloop + endfacet + facet normal 0.174009 0.0790016 0.98157 + outer loop + vertex 1.03154 1.6962 2.61597 + vertex 1.03505 1.69864 2.61515 + vertex 1.03042 1.70021 2.61585 + endloop + endfacet + facet normal 0.209588 0.0886735 0.973761 + outer loop + vertex 1.03042 1.70021 2.61585 + vertex 1.02747 1.69598 2.61687 + vertex 1.03154 1.6962 2.61597 + endloop + endfacet + facet normal 0.209858 0.0849089 0.974038 + outer loop + vertex 1.03154 1.6962 2.61597 + vertex 1.02747 1.69598 2.61687 + vertex 1.03086 1.69165 2.61652 + endloop + endfacet + facet normal 0.174806 0.0908788 0.9804 + outer loop + vertex 1.03154 1.6962 2.61597 + vertex 1.03086 1.69165 2.61652 + vertex 1.03416 1.69423 2.61569 + endloop + endfacet + facet normal 0.170658 0.096247 0.980618 + outer loop + vertex 1.03546 1.69023 2.61585 + vertex 1.03416 1.69423 2.61569 + vertex 1.03086 1.69165 2.61652 + endloop + endfacet + facet normal 0.16763 0.0857054 0.982118 + outer loop + vertex 1.03086 1.69165 2.61652 + vertex 1.03266 1.68586 2.61671 + vertex 1.03546 1.69023 2.61585 + endloop + endfacet + facet normal 0.157908 0.0921192 0.983148 + outer loop + vertex 1.03546 1.69023 2.61585 + vertex 1.03266 1.68586 2.61671 + vertex 1.03694 1.68624 2.61599 + endloop + endfacet + facet normal 0.136252 0.0842339 0.987087 + outer loop + vertex 1.03694 1.68624 2.61599 + vertex 1.04019 1.68861 2.61534 + vertex 1.03546 1.69023 2.61585 + endloop + endfacet + facet normal 0.139452 0.0940177 0.985755 + outer loop + vertex 1.04019 1.68861 2.61534 + vertex 1.03854 1.69433 2.61503 + vertex 1.03546 1.69023 2.61585 + endloop + endfacet + facet normal 0.124856 0.0899232 0.988092 + outer loop + vertex 1.04019 1.68861 2.61534 + vertex 1.04364 1.69296 2.61451 + vertex 1.03854 1.69433 2.61503 + endloop + endfacet + facet normal 0.126942 0.0980385 0.987053 + outer loop + vertex 1.04364 1.69296 2.61451 + vertex 1.04351 1.69784 2.61404 + vertex 1.03854 1.69433 2.61503 + endloop + endfacet + facet normal 0.128026 0.0965051 0.987064 + outer loop + vertex 1.03854 1.69433 2.61503 + vertex 1.04351 1.69784 2.61404 + vertex 1.03966 1.69903 2.61442 + endloop + endfacet + facet normal 0.148391 0.0913419 0.984701 + outer loop + vertex 1.03505 1.69864 2.61515 + vertex 1.03854 1.69433 2.61503 + vertex 1.03966 1.69903 2.61442 + endloop + endfacet + facet normal 0.146466 0.0897729 0.985134 + outer loop + vertex 1.03416 1.69423 2.61569 + vertex 1.03854 1.69433 2.61503 + vertex 1.03505 1.69864 2.61515 + endloop + endfacet + facet normal 0.128589 0.0984048 0.986804 + outer loop + vertex 1.04351 1.69784 2.61404 + vertex 1.04361 1.7026 2.61355 + vertex 1.03966 1.69903 2.61442 + endloop + endfacet + facet normal 0.135541 0.0906772 0.986614 + outer loop + vertex 1.03966 1.69903 2.61442 + vertex 1.04361 1.7026 2.61355 + vertex 1.03885 1.70309 2.61416 + endloop + endfacet + facet normal 0.136234 0.098368 0.985781 + outer loop + vertex 1.04361 1.7026 2.61355 + vertex 1.04344 1.70738 2.6131 + vertex 1.03885 1.70309 2.61416 + endloop + endfacet + facet normal 0.122255 0.0980411 0.987644 + outer loop + vertex 1.04361 1.7026 2.61355 + vertex 1.04818 1.70707 2.61254 + vertex 1.04344 1.70738 2.6131 + endloop + endfacet + facet normal 0.122591 0.104549 0.986935 + outer loop + vertex 1.04818 1.70707 2.61254 + vertex 1.0477 1.71176 2.61211 + vertex 1.04344 1.70738 2.6131 + endloop + endfacet + facet normal 0.127627 0.0996158 0.986807 + outer loop + vertex 1.04344 1.70738 2.6131 + vertex 1.0477 1.71176 2.61211 + vertex 1.04312 1.71212 2.61266 + endloop + endfacet + facet normal 0.142155 0.100381 0.984741 + outer loop + vertex 1.04344 1.70738 2.6131 + vertex 1.04312 1.71212 2.61266 + vertex 1.03872 1.70797 2.61372 + endloop + endfacet + facet normal 0.146886 0.0953098 0.984551 + outer loop + vertex 1.03872 1.70797 2.61372 + vertex 1.04312 1.71212 2.61266 + vertex 1.03864 1.71266 2.61328 + endloop + endfacet + facet normal 0.147572 0.10198 0.98378 + outer loop + vertex 1.04312 1.71212 2.61266 + vertex 1.0426 1.71676 2.61226 + vertex 1.03864 1.71266 2.61328 + endloop + endfacet + facet normal 0.134655 0.100696 0.985763 + outer loop + vertex 1.04312 1.71212 2.61266 + vertex 1.04655 1.7158 2.61182 + vertex 1.0426 1.71676 2.61226 + endloop + endfacet + facet normal 0.135647 0.105062 0.985171 + outer loop + vertex 1.04655 1.7158 2.61182 + vertex 1.04639 1.72103 2.61128 + vertex 1.0426 1.71676 2.61226 + endloop + endfacet + facet normal 0.141657 0.0996562 0.984887 + outer loop + vertex 1.0426 1.71676 2.61226 + vertex 1.04639 1.72103 2.61128 + vertex 1.04145 1.72078 2.61202 + endloop + endfacet + facet normal 0.154772 0.103261 0.982539 + outer loop + vertex 1.0426 1.71676 2.61226 + vertex 1.04145 1.72078 2.61202 + vertex 1.03812 1.71721 2.61292 + endloop + endfacet + facet normal 0.14157 0.101033 0.984759 + outer loop + vertex 1.0416 1.72603 2.61146 + vertex 1.04145 1.72078 2.61202 + vertex 1.04639 1.72103 2.61128 + endloop + endfacet + facet normal 0.151225 0.11035 0.982321 + outer loop + vertex 1.04609 1.72592 2.61078 + vertex 1.0416 1.72603 2.61146 + vertex 1.04639 1.72103 2.61128 + endloop + endfacet + facet normal 0.126561 0.109189 0.985931 + outer loop + vertex 1.04609 1.72592 2.61078 + vertex 1.04639 1.72103 2.61128 + vertex 1.04918 1.72407 2.61059 + endloop + endfacet + facet normal 0.11933 0.0968889 0.988116 + outer loop + vertex 1.04918 1.72407 2.61059 + vertex 1.04916 1.72872 2.61013 + vertex 1.04609 1.72592 2.61078 + endloop + endfacet + facet normal 0.122866 0.0929834 0.988058 + outer loop + vertex 1.04458 1.72913 2.61066 + vertex 1.04609 1.72592 2.61078 + vertex 1.04916 1.72872 2.61013 + endloop + endfacet + facet normal 0.12212 0.0836327 0.988985 + outer loop + vertex 1.04458 1.72913 2.61066 + vertex 1.04916 1.72872 2.61013 + vertex 1.04518 1.73341 2.61023 + endloop + endfacet + facet normal 0.126727 0.0875625 0.988065 + outer loop + vertex 1.04518 1.73341 2.61023 + vertex 1.04916 1.72872 2.61013 + vertex 1.04948 1.73366 2.60965 + endloop + endfacet + facet normal 0.127713 0.0728276 0.989134 + outer loop + vertex 1.04948 1.73366 2.60965 + vertex 1.04858 1.73775 2.60947 + vertex 1.04518 1.73341 2.61023 + endloop + endfacet + facet normal 0.138955 0.0638722 0.988237 + outer loop + vertex 1.04518 1.73341 2.61023 + vertex 1.04858 1.73775 2.60947 + vertex 1.04417 1.73876 2.61002 + endloop + endfacet + facet normal 0.137776 0.0584379 0.988738 + outer loop + vertex 1.04858 1.73775 2.60947 + vertex 1.04833 1.74273 2.60921 + vertex 1.04417 1.73876 2.61002 + endloop + endfacet + facet normal 0.149428 0.0460018 0.987702 + outer loop + vertex 1.04417 1.73876 2.61002 + vertex 1.04833 1.74273 2.60921 + vertex 1.04378 1.74386 2.60984 + endloop + endfacet + facet normal 0.150288 0.0496441 0.987395 + outer loop + vertex 1.04833 1.74273 2.60921 + vertex 1.04836 1.74786 2.60895 + vertex 1.04378 1.74386 2.60984 + endloop + endfacet + facet normal 0.15994 0.0383619 0.986381 + outer loop + vertex 1.04378 1.74386 2.60984 + vertex 1.04836 1.74786 2.60895 + vertex 1.04341 1.74929 2.60969 + endloop + endfacet + facet normal 0.163864 0.0526131 0.985079 + outer loop + vertex 1.04836 1.74786 2.60895 + vertex 1.04866 1.75285 2.60863 + vertex 1.04341 1.74929 2.60969 + endloop + endfacet + facet normal 0.161418 0.0562795 0.98528 + outer loop + vertex 1.04341 1.74929 2.60969 + vertex 1.04866 1.75285 2.60863 + vertex 1.04497 1.75401 2.60917 + endloop + endfacet + facet normal 0.164521 0.066724 0.984114 + outer loop + vertex 1.04866 1.75285 2.60863 + vertex 1.04875 1.75755 2.6083 + vertex 1.04497 1.75401 2.60917 + endloop + endfacet + facet normal 0.162442 0.0689921 0.984303 + outer loop + vertex 1.04497 1.75401 2.60917 + vertex 1.04875 1.75755 2.6083 + vertex 1.04418 1.75797 2.60902 + endloop + endfacet + facet normal 0.163741 0.0859667 0.982751 + outer loop + vertex 1.04875 1.75755 2.6083 + vertex 1.04826 1.76216 2.60798 + vertex 1.04418 1.75797 2.60902 + endloop + endfacet + facet normal 0.158201 0.0914504 0.983163 + outer loop + vertex 1.04418 1.75797 2.60902 + vertex 1.04826 1.76216 2.60798 + vertex 1.04359 1.76287 2.60866 + endloop + endfacet + facet normal 0.159813 0.103502 0.981706 + outer loop + vertex 1.04826 1.76216 2.60798 + vertex 1.04769 1.76689 2.60757 + vertex 1.04359 1.76287 2.60866 + endloop + endfacet + facet normal 0.151964 0.111617 0.982064 + outer loop + vertex 1.04359 1.76287 2.60866 + vertex 1.04769 1.76689 2.60757 + vertex 1.04326 1.76768 2.60817 + endloop + endfacet + facet normal 0.152682 0.116144 0.981427 + outer loop + vertex 1.04769 1.76689 2.60757 + vertex 1.04662 1.77094 2.60726 + vertex 1.04326 1.76768 2.60817 + endloop + endfacet + facet normal 0.151197 0.117691 0.981473 + outer loop + vertex 1.04326 1.76768 2.60817 + vertex 1.04662 1.77094 2.60726 + vertex 1.0429 1.7721 2.60769 + endloop + endfacet + facet normal 0.150164 0.114188 0.982045 + outer loop + vertex 1.04662 1.77094 2.60726 + vertex 1.04676 1.77605 2.60664 + vertex 1.0429 1.7721 2.60769 + endloop + endfacet + facet normal 0.153552 0.110831 0.981906 + outer loop + vertex 1.0429 1.7721 2.60769 + vertex 1.04676 1.77605 2.60664 + vertex 1.04184 1.77587 2.60743 + endloop + endfacet + facet normal 0.176529 0.117013 0.977315 + outer loop + vertex 1.0429 1.7721 2.60769 + vertex 1.04184 1.77587 2.60743 + vertex 1.03865 1.77271 2.60839 + endloop + endfacet + facet normal 0.175804 0.110943 0.978154 + outer loop + vertex 1.0397 1.76897 2.60862 + vertex 1.0429 1.7721 2.60769 + vertex 1.03865 1.77271 2.60839 + endloop + endfacet + facet normal 0.203331 0.118252 0.971943 + outer loop + vertex 1.0397 1.76897 2.60862 + vertex 1.03865 1.77271 2.60839 + vertex 1.03523 1.76841 2.60962 + endloop + endfacet + facet normal 0.223937 0.101123 0.969343 + outer loop + vertex 1.03523 1.76841 2.60962 + vertex 1.03865 1.77271 2.60839 + vertex 1.03426 1.7737 2.6093 + endloop + endfacet + facet normal 0.224836 0.105748 0.968641 + outer loop + vertex 1.03865 1.77271 2.60839 + vertex 1.03804 1.77737 2.60802 + vertex 1.03426 1.7737 2.6093 + endloop + endfacet + facet normal 0.245671 0.0832622 0.965771 + outer loop + vertex 1.03426 1.7737 2.6093 + vertex 1.03804 1.77737 2.60802 + vertex 1.03342 1.77914 2.60904 + endloop + endfacet + facet normal 0.25309 0.104977 0.96173 + outer loop + vertex 1.03804 1.77737 2.60802 + vertex 1.03763 1.78218 2.6076 + vertex 1.03342 1.77914 2.60904 + endloop + endfacet + facet normal 0.257349 0.0988618 0.961248 + outer loop + vertex 1.03342 1.77914 2.60904 + vertex 1.03763 1.78218 2.6076 + vertex 1.03441 1.78359 2.60832 + endloop + endfacet + facet normal 0.25979 0.10512 0.959926 + outer loop + vertex 1.03763 1.78218 2.6076 + vertex 1.03673 1.786 2.60743 + vertex 1.03441 1.78359 2.60832 + endloop + endfacet + facet normal 0.291776 0.0721121 0.953764 + outer loop + vertex 1.03441 1.78359 2.60832 + vertex 1.03673 1.786 2.60743 + vertex 1.03367 1.7874 2.60826 + endloop + endfacet + facet normal 0.295176 0.0805344 0.952043 + outer loop + vertex 1.03673 1.786 2.60743 + vertex 1.03728 1.79053 2.60687 + vertex 1.03367 1.7874 2.60826 + endloop + endfacet + facet normal 0.304944 0.0683001 0.949918 + outer loop + vertex 1.03367 1.7874 2.60826 + vertex 1.03728 1.79053 2.60687 + vertex 1.03302 1.79222 2.60812 + endloop + endfacet + facet normal 0.316122 0.101423 0.943282 + outer loop + vertex 1.03728 1.79053 2.60687 + vertex 1.0358 1.79638 2.60674 + vertex 1.03302 1.79222 2.60812 + endloop + endfacet + facet normal 0.357251 0.0699598 0.931385 + outer loop + vertex 1.03302 1.79222 2.60812 + vertex 1.0358 1.79638 2.60674 + vertex 1.03209 1.79644 2.60816 + endloop + endfacet + facet normal 0.357186 0.0756013 0.930969 + outer loop + vertex 1.03301 1.80114 2.60742 + vertex 1.03209 1.79644 2.60816 + vertex 1.0358 1.79638 2.60674 + endloop + endfacet + facet normal 0.220267 0.0919741 0.971094 + outer loop + vertex 1.03728 1.79053 2.60687 + vertex 1.03673 1.786 2.60743 + vertex 1.04063 1.78631 2.60651 + endloop + endfacet + facet normal 0.233806 0.10308 0.966804 + outer loop + vertex 1.0413 1.79074 2.60588 + vertex 1.03728 1.79053 2.60687 + vertex 1.04063 1.78631 2.60651 + endloop + endfacet + facet normal 0.18295 0.112237 0.976694 + outer loop + vertex 1.0413 1.79074 2.60588 + vertex 1.04063 1.78631 2.60651 + vertex 1.04403 1.78887 2.60558 + endloop + endfacet + facet normal 0.178746 0.105842 0.978186 + outer loop + vertex 1.04403 1.78887 2.60558 + vertex 1.04505 1.79339 2.60491 + vertex 1.0413 1.79074 2.60588 + endloop + endfacet + facet normal 0.186275 0.0951042 0.977884 + outer loop + vertex 1.0413 1.79074 2.60588 + vertex 1.04505 1.79339 2.60491 + vertex 1.04022 1.79476 2.60569 + endloop + endfacet + facet normal 0.191225 0.114352 0.974863 + outer loop + vertex 1.04505 1.79339 2.60491 + vertex 1.04367 1.79915 2.6045 + vertex 1.04022 1.79476 2.60569 + endloop + endfacet + facet normal 0.206514 0.101864 0.973127 + outer loop + vertex 1.03916 1.79885 2.60549 + vertex 1.04022 1.79476 2.60569 + vertex 1.04367 1.79915 2.6045 + endloop + endfacet + facet normal 0.20633 0.104012 0.972939 + outer loop + vertex 1.03916 1.79885 2.60549 + vertex 1.04367 1.79915 2.6045 + vertex 1.04034 1.80344 2.60475 + endloop + endfacet + facet normal 0.211896 0.108431 0.971258 + outer loop + vertex 1.04034 1.80344 2.60475 + vertex 1.04367 1.79915 2.6045 + vertex 1.04468 1.80393 2.60375 + endloop + endfacet + facet normal 0.210841 0.116425 0.970562 + outer loop + vertex 1.04468 1.80393 2.60375 + vertex 1.04357 1.80775 2.60353 + vertex 1.04034 1.80344 2.60475 + endloop + endfacet + facet normal 0.236226 0.0962951 0.966915 + outer loop + vertex 1.04034 1.80344 2.60475 + vertex 1.04357 1.80775 2.60353 + vertex 1.03945 1.80875 2.60444 + endloop + endfacet + facet normal 0.239636 0.112609 0.96431 + outer loop + vertex 1.04357 1.80775 2.60353 + vertex 1.04288 1.81233 2.60317 + vertex 1.03945 1.80875 2.60444 + endloop + endfacet + facet normal 0.26219 0.0897524 0.960834 + outer loop + vertex 1.03945 1.80875 2.60444 + vertex 1.04288 1.81233 2.60317 + vertex 1.03888 1.8136 2.60414 + endloop + endfacet + facet normal 0.26741 0.10893 0.957406 + outer loop + vertex 1.04288 1.81233 2.60317 + vertex 1.04201 1.81645 2.60294 + vertex 1.03888 1.8136 2.60414 + endloop + endfacet + facet normal 0.294202 0.0775887 0.952589 + outer loop + vertex 1.03888 1.8136 2.60414 + vertex 1.04201 1.81645 2.60294 + vertex 1.03857 1.81844 2.60384 + endloop + endfacet + facet normal 0.297995 0.0849557 0.95078 + outer loop + vertex 1.04201 1.81645 2.60294 + vertex 1.04295 1.82147 2.6022 + vertex 1.03857 1.81844 2.60384 + endloop + endfacet + facet normal 0.306636 0.0715525 0.949134 + outer loop + vertex 1.03857 1.81844 2.60384 + vertex 1.04295 1.82147 2.6022 + vertex 1.03783 1.8238 2.60368 + endloop + endfacet + facet normal 0.326957 0.124011 0.936867 + outer loop + vertex 1.04295 1.82147 2.6022 + vertex 1.04116 1.8271 2.60208 + vertex 1.03783 1.8238 2.60368 + endloop + endfacet + facet normal 0.27846 0.108974 0.954246 + outer loop + vertex 1.04116 1.8271 2.60208 + vertex 1.04295 1.82147 2.6022 + vertex 1.0452 1.82586 2.60104 + endloop + endfacet + facet normal 0.282835 0.126035 0.950852 + outer loop + vertex 1.0452 1.82586 2.60104 + vertex 1.04439 1.82927 2.60083 + vertex 1.04116 1.8271 2.60208 + endloop + endfacet + facet normal 0.224358 0.113224 0.967907 + outer loop + vertex 1.04439 1.82927 2.60083 + vertex 1.0452 1.82586 2.60104 + vertex 1.04874 1.8293 2.59982 + endloop + endfacet + facet normal 0.224508 0.108378 0.968427 + outer loop + vertex 1.04439 1.82927 2.60083 + vertex 1.04874 1.8293 2.59982 + vertex 1.04561 1.83355 2.60007 + endloop + endfacet + facet normal 0.23355 0.115197 0.965497 + outer loop + vertex 1.04561 1.83355 2.60007 + vertex 1.04874 1.8293 2.59982 + vertex 1.04988 1.834 2.59898 + endloop + endfacet + facet normal 0.23291 0.120186 0.965043 + outer loop + vertex 1.04988 1.834 2.59898 + vertex 1.04879 1.83779 2.59877 + vertex 1.04561 1.83355 2.60007 + endloop + endfacet + facet normal 0.261841 0.0969585 0.960228 + outer loop + vertex 1.04561 1.83355 2.60007 + vertex 1.04879 1.83779 2.59877 + vertex 1.04475 1.83881 2.59977 + endloop + endfacet + facet normal 0.209234 0.113763 0.971226 + outer loop + vertex 1.04988 1.834 2.59898 + vertex 1.05288 1.83704 2.59798 + vertex 1.04879 1.83779 2.59877 + endloop + endfacet + facet normal 0.211857 0.130845 0.968502 + outer loop + vertex 1.05288 1.83704 2.59798 + vertex 1.05162 1.84093 2.59773 + vertex 1.04879 1.83779 2.59877 + endloop + endfacet + facet normal 0.229139 0.114698 0.966613 + outer loop + vertex 1.04879 1.83779 2.59877 + vertex 1.05162 1.84093 2.59773 + vertex 1.04801 1.84239 2.59841 + endloop + endfacet + facet normal 0.266703 0.120288 0.956243 + outer loop + vertex 1.04879 1.83779 2.59877 + vertex 1.04801 1.84239 2.59841 + vertex 1.04475 1.83881 2.59977 + endloop + endfacet + facet normal 0.233302 0.126133 0.964189 + outer loop + vertex 1.05162 1.84093 2.59773 + vertex 1.05174 1.84609 2.59703 + vertex 1.04801 1.84239 2.59841 + endloop + endfacet + facet normal 0.248831 0.109799 0.962303 + outer loop + vertex 1.04801 1.84239 2.59841 + vertex 1.05174 1.84609 2.59703 + vertex 1.04713 1.84652 2.59817 + endloop + endfacet + facet normal 0.249265 0.117206 0.961317 + outer loop + vertex 1.048 1.85119 2.59737 + vertex 1.04713 1.84652 2.59817 + vertex 1.05174 1.84609 2.59703 + endloop + endfacet + facet normal 0.188381 0.12846 0.973658 + outer loop + vertex 1.05174 1.84609 2.59703 + vertex 1.05162 1.84093 2.59773 + vertex 1.05647 1.8409 2.59679 + endloop + endfacet + facet normal 0.205568 0.144371 0.967935 + outer loop + vertex 1.05631 1.84586 2.59609 + vertex 1.05174 1.84609 2.59703 + vertex 1.05647 1.8409 2.59679 + endloop + endfacet + facet normal 0.167977 0.144165 0.975192 + outer loop + vertex 1.05631 1.84586 2.59609 + vertex 1.05647 1.8409 2.59679 + vertex 1.05953 1.84407 2.5958 + endloop + endfacet + facet normal 0.165556 0.13962 0.976267 + outer loop + vertex 1.05953 1.84407 2.5958 + vertex 1.05974 1.84892 2.59507 + vertex 1.05631 1.84586 2.59609 + endloop + endfacet + facet normal 0.170724 0.1338 0.976192 + outer loop + vertex 1.05488 1.84908 2.5959 + vertex 1.05631 1.84586 2.59609 + vertex 1.05974 1.84892 2.59507 + endloop + endfacet + facet normal 0.170727 0.134106 0.97615 + outer loop + vertex 1.05488 1.84908 2.5959 + vertex 1.05974 1.84892 2.59507 + vertex 1.05568 1.85346 2.59516 + endloop + endfacet + facet normal 0.207273 0.126389 0.970084 + outer loop + vertex 1.05488 1.84908 2.5959 + vertex 1.05568 1.85346 2.59516 + vertex 1.05207 1.85103 2.59624 + endloop + endfacet + facet normal 0.215221 0.138423 0.966705 + outer loop + vertex 1.05207 1.85103 2.59624 + vertex 1.05174 1.84609 2.59703 + vertex 1.05488 1.84908 2.5959 + endloop + endfacet + facet normal 0.269627 0.13265 0.953785 + outer loop + vertex 1.05207 1.85103 2.59624 + vertex 1.048 1.85119 2.59737 + vertex 1.05174 1.84609 2.59703 + endloop + endfacet + facet normal 0.177815 0.140495 0.973983 + outer loop + vertex 1.05568 1.85346 2.59516 + vertex 1.05974 1.84892 2.59507 + vertex 1.06012 1.85395 2.59427 + endloop + endfacet + facet normal 0.177957 0.139436 0.974109 + outer loop + vertex 1.06012 1.85395 2.59427 + vertex 1.05895 1.85782 2.59393 + vertex 1.05568 1.85346 2.59516 + endloop + endfacet + facet normal 0.195281 0.126032 0.972616 + outer loop + vertex 1.05568 1.85346 2.59516 + vertex 1.05895 1.85782 2.59393 + vertex 1.05445 1.85872 2.59472 + endloop + endfacet + facet normal 0.222815 0.131939 0.965891 + outer loop + vertex 1.05568 1.85346 2.59516 + vertex 1.05445 1.85872 2.59472 + vertex 1.05103 1.85516 2.596 + endloop + endfacet + facet normal 0.216425 0.112621 0.969782 + outer loop + vertex 1.05207 1.85103 2.59624 + vertex 1.05568 1.85346 2.59516 + vertex 1.05103 1.85516 2.596 + endloop + endfacet + facet normal 0.269623 0.125223 0.954789 + outer loop + vertex 1.05103 1.85516 2.596 + vertex 1.048 1.85119 2.59737 + vertex 1.05207 1.85103 2.59624 + endloop + endfacet + facet normal 0.296649 0.102781 0.949439 + outer loop + vertex 1.04689 1.85677 2.59711 + vertex 1.048 1.85119 2.59737 + vertex 1.05103 1.85516 2.596 + endloop + endfacet + facet normal 0.301526 0.117604 0.946177 + outer loop + vertex 1.05004 1.86003 2.59571 + vertex 1.04689 1.85677 2.59711 + vertex 1.05103 1.85516 2.596 + endloop + endfacet + facet normal 0.334728 0.0822458 0.938719 + outer loop + vertex 1.04584 1.86219 2.59702 + vertex 1.04689 1.85677 2.59711 + vertex 1.05004 1.86003 2.59571 + endloop + endfacet + facet normal 0.34981 0.117283 0.92945 + outer loop + vertex 1.05004 1.86003 2.59571 + vertex 1.04924 1.86402 2.5955 + vertex 1.04584 1.86219 2.59702 + endloop + endfacet + facet normal 0.277853 0.104064 0.95497 + outer loop + vertex 1.04924 1.86402 2.5955 + vertex 1.05004 1.86003 2.59571 + vertex 1.05345 1.86402 2.59428 + endloop + endfacet + facet normal 0.27764 0.111263 0.954221 + outer loop + vertex 1.04924 1.86402 2.5955 + vertex 1.05345 1.86402 2.59428 + vertex 1.05041 1.86832 2.59466 + endloop + endfacet + facet normal 0.287891 0.11887 0.950257 + outer loop + vertex 1.05041 1.86832 2.59466 + vertex 1.05345 1.86402 2.59428 + vertex 1.05436 1.86846 2.59345 + endloop + endfacet + facet normal 0.287555 0.123877 0.949719 + outer loop + vertex 1.05436 1.86846 2.59345 + vertex 1.05334 1.87225 2.59326 + vertex 1.05041 1.86832 2.59466 + endloop + endfacet + facet normal 0.252145 0.127547 0.959247 + outer loop + vertex 1.05445 1.85872 2.59472 + vertex 1.05345 1.86402 2.59428 + vertex 1.05004 1.86003 2.59571 + endloop + endfacet + facet normal 0.214125 0.121249 0.969252 + outer loop + vertex 1.05445 1.85872 2.59472 + vertex 1.0581 1.86242 2.59345 + vertex 1.05345 1.86402 2.59428 + endloop + endfacet + facet normal 0.220152 0.140788 0.965252 + outer loop + vertex 1.0581 1.86242 2.59345 + vertex 1.05764 1.86702 2.59289 + vertex 1.05345 1.86402 2.59428 + endloop + endfacet + facet normal 0.224486 0.134681 0.965125 + outer loop + vertex 1.05345 1.86402 2.59428 + vertex 1.05764 1.86702 2.59289 + vertex 1.05436 1.86846 2.59345 + endloop + endfacet + facet normal 0.225312 0.136753 0.964641 + outer loop + vertex 1.05764 1.86702 2.59289 + vertex 1.05674 1.87092 2.59254 + vertex 1.05436 1.86846 2.59345 + endloop + endfacet + facet normal 0.248109 0.113812 0.962023 + outer loop + vertex 1.05436 1.86846 2.59345 + vertex 1.05674 1.87092 2.59254 + vertex 1.05334 1.87225 2.59326 + endloop + endfacet + facet normal 0.250622 0.121074 0.960484 + outer loop + vertex 1.05674 1.87092 2.59254 + vertex 1.05677 1.87596 2.5919 + vertex 1.05334 1.87225 2.59326 + endloop + endfacet + facet normal 0.271071 0.100983 0.957247 + outer loop + vertex 1.05334 1.87225 2.59326 + vertex 1.05677 1.87596 2.5919 + vertex 1.05226 1.87633 2.59314 + endloop + endfacet + facet normal 0.271334 0.106342 0.956592 + outer loop + vertex 1.05286 1.88122 2.59242 + vertex 1.05226 1.87633 2.59314 + vertex 1.05677 1.87596 2.5919 + endloop + endfacet + facet normal 0.298169 0.127336 0.945981 + outer loop + vertex 1.05697 1.88103 2.59116 + vertex 1.05286 1.88122 2.59242 + vertex 1.05677 1.87596 2.5919 + endloop + endfacet + facet normal 0.23481 0.132326 0.962992 + outer loop + vertex 1.05697 1.88103 2.59116 + vertex 1.05677 1.87596 2.5919 + vertex 1.05987 1.87899 2.59073 + endloop + endfacet + facet normal 0.228729 0.123098 0.965676 + outer loop + vertex 1.05987 1.87899 2.59073 + vertex 1.06045 1.88349 2.59002 + vertex 1.05697 1.88103 2.59116 + endloop + endfacet + facet normal 0.240447 0.106135 0.964842 + outer loop + vertex 1.05697 1.88103 2.59116 + vertex 1.06045 1.88349 2.59002 + vertex 1.05566 1.8853 2.59101 + endloop + endfacet + facet normal 0.24981 0.134219 0.958948 + outer loop + vertex 1.06045 1.88349 2.59002 + vertex 1.05871 1.88926 2.58966 + vertex 1.05566 1.8853 2.59101 + endloop + endfacet + facet normal 0.274832 0.113529 0.954766 + outer loop + vertex 1.05455 1.88942 2.59084 + vertex 1.05566 1.8853 2.59101 + vertex 1.05871 1.88926 2.58966 + endloop + endfacet + facet normal 0.274835 0.114314 0.954672 + outer loop + vertex 1.05455 1.88942 2.59084 + vertex 1.05871 1.88926 2.58966 + vertex 1.0556 1.89365 2.59003 + endloop + endfacet + facet normal 0.352064 0.133249 0.926443 + outer loop + vertex 1.05566 1.8853 2.59101 + vertex 1.05455 1.88942 2.59084 + vertex 1.05139 1.88739 2.59233 + endloop + endfacet + facet normal 0.336109 0.0938194 0.937138 + outer loop + vertex 1.05139 1.88739 2.59233 + vertex 1.05286 1.88122 2.59242 + vertex 1.05566 1.8853 2.59101 + endloop + endfacet + facet normal 0.217896 0.125117 0.967919 + outer loop + vertex 1.06045 1.88349 2.59002 + vertex 1.06345 1.88766 2.5888 + vertex 1.05871 1.88926 2.58966 + endloop + endfacet + facet normal 0.222796 0.14145 0.964549 + outer loop + vertex 1.06345 1.88766 2.5888 + vertex 1.06274 1.89214 2.58831 + vertex 1.05871 1.88926 2.58966 + endloop + endfacet + facet normal 0.225817 0.137187 0.964462 + outer loop + vertex 1.05871 1.88926 2.58966 + vertex 1.06274 1.89214 2.58831 + vertex 1.05945 1.89362 2.58887 + endloop + endfacet + facet normal 0.28785 0.123969 0.949618 + outer loop + vertex 1.0556 1.89365 2.59003 + vertex 1.05871 1.88926 2.58966 + vertex 1.05945 1.89362 2.58887 + endloop + endfacet + facet normal 0.287734 0.128017 0.949116 + outer loop + vertex 1.05945 1.89362 2.58887 + vertex 1.05866 1.89741 2.5886 + vertex 1.0556 1.89365 2.59003 + endloop + endfacet + facet normal 0.320014 0.0990745 0.942218 + outer loop + vertex 1.0556 1.89365 2.59003 + vertex 1.05866 1.89741 2.5886 + vertex 1.05483 1.89886 2.58975 + endloop + endfacet + facet normal 0.327116 0.121858 0.937094 + outer loop + vertex 1.05866 1.89741 2.5886 + vertex 1.05799 1.90217 2.58821 + vertex 1.05483 1.89886 2.58975 + endloop + endfacet + facet normal 0.24666 0.120359 0.961599 + outer loop + vertex 1.05945 1.89362 2.58887 + vertex 1.06197 1.8959 2.58794 + vertex 1.05866 1.89741 2.5886 + endloop + endfacet + facet normal 0.250807 0.130504 0.9592 + outer loop + vertex 1.06197 1.8959 2.58794 + vertex 1.0626 1.90051 2.58715 + vertex 1.05866 1.89741 2.5886 + endloop + endfacet + facet normal 0.262892 0.114596 0.957996 + outer loop + vertex 1.05866 1.89741 2.5886 + vertex 1.0626 1.90051 2.58715 + vertex 1.05799 1.90217 2.58821 + endloop + endfacet + facet normal 0.26939 0.135499 0.953451 + outer loop + vertex 1.0626 1.90051 2.58715 + vertex 1.06092 1.90642 2.58678 + vertex 1.05799 1.90217 2.58821 + endloop + endfacet + facet normal 0.312079 0.103062 0.94445 + outer loop + vertex 1.05799 1.90217 2.58821 + vertex 1.06092 1.90642 2.58678 + vertex 1.05699 1.90634 2.58809 + endloop + endfacet + facet normal 0.312451 0.0954957 0.945122 + outer loop + vertex 1.05775 1.9111 2.58736 + vertex 1.05699 1.90634 2.58809 + vertex 1.06092 1.90642 2.58678 + endloop + endfacet + facet normal 0.205958 0.138266 0.968744 + outer loop + vertex 1.0626 1.90051 2.58715 + vertex 1.06197 1.8959 2.58794 + vertex 1.06663 1.89574 2.58697 + endloop + endfacet + facet normal 0.205957 0.137992 0.968783 + outer loop + vertex 1.06274 1.89214 2.58831 + vertex 1.06663 1.89574 2.58697 + vertex 1.06197 1.8959 2.58794 + endloop + endfacet + facet normal 0.198983 0.145667 0.969117 + outer loop + vertex 1.06642 1.89065 2.58778 + vertex 1.06663 1.89574 2.58697 + vertex 1.06274 1.89214 2.58831 + endloop + endfacet + facet normal 0.227745 0.141933 0.963321 + outer loop + vertex 1.06274 1.89214 2.58831 + vertex 1.06197 1.8959 2.58794 + vertex 1.05945 1.89362 2.58887 + endloop + endfacet + facet normal 0.196081 0.137883 0.970845 + outer loop + vertex 1.06345 1.88766 2.5888 + vertex 1.06642 1.89065 2.58778 + vertex 1.06274 1.89214 2.58831 + endloop + endfacet + facet normal 0.189318 0.144709 0.971194 + outer loop + vertex 1.06774 1.8868 2.58809 + vertex 1.06642 1.89065 2.58778 + vertex 1.06345 1.88766 2.5888 + endloop + endfacet + facet normal 0.187594 0.134687 0.972969 + outer loop + vertex 1.06491 1.88377 2.58906 + vertex 1.06774 1.8868 2.58809 + vertex 1.06345 1.88766 2.5888 + endloop + endfacet + facet normal 0.178013 0.143831 0.97346 + outer loop + vertex 1.06854 1.88247 2.58859 + vertex 1.06774 1.8868 2.58809 + vertex 1.06491 1.88377 2.58906 + endloop + endfacet + facet normal 0.177161 0.141257 0.973992 + outer loop + vertex 1.06467 1.87876 2.58983 + vertex 1.06854 1.88247 2.58859 + vertex 1.06491 1.88377 2.58906 + endloop + endfacet + facet normal 0.169995 0.148764 0.974151 + outer loop + vertex 1.06969 1.87868 2.58896 + vertex 1.06854 1.88247 2.58859 + vertex 1.06467 1.87876 2.58983 + endloop + endfacet + facet normal 0.169959 0.151905 0.973673 + outer loop + vertex 1.06467 1.87876 2.58983 + vertex 1.06942 1.87367 2.58979 + vertex 1.06969 1.87868 2.58896 + endloop + endfacet + facet normal 0.149804 0.153507 0.976726 + outer loop + vertex 1.06942 1.87367 2.58979 + vertex 1.07343 1.87746 2.58858 + vertex 1.06969 1.87868 2.58896 + endloop + endfacet + facet normal 0.150094 0.154453 0.976533 + outer loop + vertex 1.07343 1.87746 2.58858 + vertex 1.07272 1.88173 2.58802 + vertex 1.06969 1.87868 2.58896 + endloop + endfacet + facet normal 0.139508 0.152934 0.97834 + outer loop + vertex 1.07343 1.87746 2.58858 + vertex 1.07639 1.88072 2.58765 + vertex 1.07272 1.88173 2.58802 + endloop + endfacet + facet normal 0.139658 0.153524 0.978226 + outer loop + vertex 1.07639 1.88072 2.58765 + vertex 1.07636 1.88587 2.58685 + vertex 1.07272 1.88173 2.58802 + endloop + endfacet + facet normal 0.14751 0.1466 0.978136 + outer loop + vertex 1.07272 1.88173 2.58802 + vertex 1.07636 1.88587 2.58685 + vertex 1.07146 1.88552 2.58764 + endloop + endfacet + facet normal 0.159682 0.150393 0.975645 + outer loop + vertex 1.07272 1.88173 2.58802 + vertex 1.07146 1.88552 2.58764 + vertex 1.06854 1.88247 2.58859 + endloop + endfacet + facet normal 0.14734 0.148408 0.977889 + outer loop + vertex 1.0714 1.89068 2.58686 + vertex 1.07146 1.88552 2.58764 + vertex 1.07636 1.88587 2.58685 + endloop + endfacet + facet normal 0.158448 0.159868 0.974339 + outer loop + vertex 1.07627 1.89076 2.58606 + vertex 1.0714 1.89068 2.58686 + vertex 1.07636 1.88587 2.58685 + endloop + endfacet + facet normal 0.135714 0.160005 0.977742 + outer loop + vertex 1.07627 1.89076 2.58606 + vertex 1.07636 1.88587 2.58685 + vertex 1.07949 1.88931 2.58585 + endloop + endfacet + facet normal 0.135565 0.159663 0.977819 + outer loop + vertex 1.07949 1.88931 2.58585 + vertex 1.07958 1.89402 2.58507 + vertex 1.07627 1.89076 2.58606 + endloop + endfacet + facet normal 0.140836 0.154363 0.977925 + outer loop + vertex 1.07461 1.89397 2.58579 + vertex 1.07627 1.89076 2.58606 + vertex 1.07958 1.89402 2.58507 + endloop + endfacet + facet normal 0.140652 0.159909 0.97706 + outer loop + vertex 1.07461 1.89397 2.58579 + vertex 1.07958 1.89402 2.58507 + vertex 1.07479 1.89881 2.58497 + endloop + endfacet + facet normal 0.164853 0.158391 0.973517 + outer loop + vertex 1.07461 1.89397 2.58579 + vertex 1.07479 1.89881 2.58497 + vertex 1.07138 1.89567 2.58606 + endloop + endfacet + facet normal 0.16428 0.157259 0.973797 + outer loop + vertex 1.07138 1.89567 2.58606 + vertex 1.0714 1.89068 2.58686 + vertex 1.07461 1.89397 2.58579 + endloop + endfacet + facet normal 0.187372 0.156689 0.969711 + outer loop + vertex 1.07138 1.89567 2.58606 + vertex 1.06663 1.89574 2.58697 + vertex 1.0714 1.89068 2.58686 + endloop + endfacet + facet normal 0.177367 0.147178 0.973077 + outer loop + vertex 1.06663 1.89574 2.58697 + vertex 1.06642 1.89065 2.58778 + vertex 1.0714 1.89068 2.58686 + endloop + endfacet + facet normal 0.187328 0.15932 0.969291 + outer loop + vertex 1.07138 1.89567 2.58606 + vertex 1.06992 1.89892 2.58581 + vertex 1.06663 1.89574 2.58697 + endloop + endfacet + facet normal 0.170623 0.152124 0.973523 + outer loop + vertex 1.06992 1.89892 2.58581 + vertex 1.07138 1.89567 2.58606 + vertex 1.07479 1.89881 2.58497 + endloop + endfacet + facet normal 0.170607 0.156129 0.972891 + outer loop + vertex 1.06992 1.89892 2.58581 + vertex 1.07479 1.89881 2.58497 + vertex 1.07051 1.90339 2.58499 + endloop + endfacet + facet normal 0.179661 0.164591 0.969862 + outer loop + vertex 1.07051 1.90339 2.58499 + vertex 1.07479 1.89881 2.58497 + vertex 1.07498 1.90373 2.5841 + endloop + endfacet + facet normal 0.180069 0.160763 0.970428 + outer loop + vertex 1.07498 1.90373 2.5841 + vertex 1.07354 1.90759 2.58373 + vertex 1.07051 1.90339 2.58499 + endloop + endfacet + facet normal 0.194166 0.150279 0.969389 + outer loop + vertex 1.07051 1.90339 2.58499 + vertex 1.07354 1.90759 2.58373 + vertex 1.06868 1.90911 2.58447 + endloop + endfacet + facet normal 0.195913 0.156512 0.968051 + outer loop + vertex 1.07354 1.90759 2.58373 + vertex 1.07275 1.9121 2.58316 + vertex 1.06868 1.90911 2.58447 + endloop + endfacet + facet normal 0.2003 0.150558 0.968097 + outer loop + vertex 1.06868 1.90911 2.58447 + vertex 1.07275 1.9121 2.58316 + vertex 1.06928 1.91356 2.58365 + endloop + endfacet + facet normal 0.233508 0.144928 0.961494 + outer loop + vertex 1.06511 1.91338 2.58469 + vertex 1.06868 1.90911 2.58447 + vertex 1.06928 1.91356 2.58365 + endloop + endfacet + facet normal 0.233384 0.146569 0.961275 + outer loop + vertex 1.06928 1.91356 2.58365 + vertex 1.06803 1.9173 2.58339 + vertex 1.06511 1.91338 2.58469 + endloop + endfacet + facet normal 0.258849 0.126385 0.957614 + outer loop + vertex 1.06511 1.91338 2.58469 + vertex 1.06803 1.9173 2.58339 + vertex 1.06352 1.91894 2.58439 + endloop + endfacet + facet normal 0.290071 0.134803 0.947463 + outer loop + vertex 1.06511 1.91338 2.58469 + vertex 1.06352 1.91894 2.58439 + vertex 1.06062 1.91508 2.58583 + endloop + endfacet + facet normal 0.279249 0.101112 0.95488 + outer loop + vertex 1.06167 1.91096 2.58595 + vertex 1.06511 1.91338 2.58469 + vertex 1.06062 1.91508 2.58583 + endloop + endfacet + facet normal 0.337572 0.115464 0.934191 + outer loop + vertex 1.06062 1.91508 2.58583 + vertex 1.05775 1.9111 2.58736 + vertex 1.06167 1.91096 2.58595 + endloop + endfacet + facet normal 0.337583 0.11381 0.93439 + outer loop + vertex 1.06167 1.91096 2.58595 + vertex 1.05775 1.9111 2.58736 + vertex 1.06092 1.90642 2.58678 + endloop + endfacet + facet normal 0.26651 0.129394 0.955107 + outer loop + vertex 1.06167 1.91096 2.58595 + vertex 1.06092 1.90642 2.58678 + vertex 1.06432 1.90894 2.58549 + endloop + endfacet + facet normal 0.263233 0.124742 0.956634 + outer loop + vertex 1.06432 1.90894 2.58549 + vertex 1.06511 1.91338 2.58469 + vertex 1.06167 1.91096 2.58595 + endloop + endfacet + facet normal 0.252065 0.14934 0.956118 + outer loop + vertex 1.06556 1.90488 2.5858 + vertex 1.06432 1.90894 2.58549 + vertex 1.06092 1.90642 2.58678 + endloop + endfacet + facet normal 0.246412 0.129408 0.960487 + outer loop + vertex 1.06092 1.90642 2.58678 + vertex 1.0626 1.90051 2.58715 + vertex 1.06556 1.90488 2.5858 + endloop + endfacet + facet normal 0.220352 0.14819 0.964098 + outer loop + vertex 1.06556 1.90488 2.5858 + vertex 1.0626 1.90051 2.58715 + vertex 1.06693 1.90076 2.58612 + endloop + endfacet + facet normal 0.200765 0.142095 0.969279 + outer loop + vertex 1.06693 1.90076 2.58612 + vertex 1.07051 1.90339 2.58499 + vertex 1.06556 1.90488 2.5858 + endloop + endfacet + facet normal 0.203716 0.153117 0.966982 + outer loop + vertex 1.07051 1.90339 2.58499 + vertex 1.06868 1.90911 2.58447 + vertex 1.06556 1.90488 2.5858 + endloop + endfacet + facet normal 0.193152 0.152459 0.969252 + outer loop + vertex 1.06992 1.89892 2.58581 + vertex 1.07051 1.90339 2.58499 + vertex 1.06693 1.90076 2.58612 + endloop + endfacet + facet normal 0.193438 0.152946 0.969118 + outer loop + vertex 1.06693 1.90076 2.58612 + vertex 1.06663 1.89574 2.58697 + vertex 1.06992 1.89892 2.58581 + endloop + endfacet + facet normal 0.220149 0.150447 0.963795 + outer loop + vertex 1.06693 1.90076 2.58612 + vertex 1.0626 1.90051 2.58715 + vertex 1.06663 1.89574 2.58697 + endloop + endfacet + facet normal 0.220343 0.140301 0.96528 + outer loop + vertex 1.06432 1.90894 2.58549 + vertex 1.06556 1.90488 2.5858 + vertex 1.06868 1.90911 2.58447 + endloop + endfacet + facet normal 0.377842 0.0818446 0.922246 + outer loop + vertex 1.0565 1.91716 2.58733 + vertex 1.05775 1.9111 2.58736 + vertex 1.06062 1.91508 2.58583 + endloop + endfacet + facet normal 0.395592 0.125895 0.909757 + outer loop + vertex 1.06062 1.91508 2.58583 + vertex 1.0596 1.91918 2.5857 + vertex 1.0565 1.91716 2.58733 + endloop + endfacet + facet normal 0.321735 0.108459 0.940597 + outer loop + vertex 1.0596 1.91918 2.5857 + vertex 1.06062 1.91508 2.58583 + vertex 1.06352 1.91894 2.58439 + endloop + endfacet + facet normal 0.32173 0.108213 0.940627 + outer loop + vertex 1.0596 1.91918 2.5857 + vertex 1.06352 1.91894 2.58439 + vertex 1.06052 1.92345 2.5849 + endloop + endfacet + facet normal 0.340523 0.121624 0.932337 + outer loop + vertex 1.06052 1.92345 2.5849 + vertex 1.06352 1.91894 2.58439 + vertex 1.06428 1.92327 2.58355 + endloop + endfacet + facet normal 0.340524 0.123231 0.932125 + outer loop + vertex 1.06428 1.92327 2.58355 + vertex 1.06323 1.92725 2.5834 + vertex 1.06052 1.92345 2.5849 + endloop + endfacet + facet normal 0.287268 0.109867 0.951528 + outer loop + vertex 1.06428 1.92327 2.58355 + vertex 1.06764 1.92565 2.58226 + vertex 1.06323 1.92725 2.5834 + endloop + endfacet + facet normal 0.295063 0.135326 0.945846 + outer loop + vertex 1.06764 1.92565 2.58226 + vertex 1.06591 1.9314 2.58198 + vertex 1.06323 1.92725 2.5834 + endloop + endfacet + facet normal 0.341949 0.101044 0.93427 + outer loop + vertex 1.06323 1.92725 2.5834 + vertex 1.06591 1.9314 2.58198 + vertex 1.06211 1.9313 2.58338 + endloop + endfacet + facet normal 0.342196 0.0966337 0.934646 + outer loop + vertex 1.06302 1.93599 2.58256 + vertex 1.06211 1.9313 2.58338 + vertex 1.06591 1.9314 2.58198 + endloop + endfacet + facet normal 0.362789 0.110736 0.925269 + outer loop + vertex 1.06678 1.93592 2.58109 + vertex 1.06302 1.93599 2.58256 + vertex 1.06591 1.9314 2.58198 + endloop + endfacet + facet normal 0.293495 0.128427 0.947295 + outer loop + vertex 1.06678 1.93592 2.58109 + vertex 1.06591 1.9314 2.58198 + vertex 1.06923 1.93391 2.58061 + endloop + endfacet + facet normal 0.286684 0.119351 0.950562 + outer loop + vertex 1.06923 1.93391 2.58061 + vertex 1.07033 1.93834 2.57972 + vertex 1.06678 1.93592 2.58109 + endloop + endfacet + facet normal 0.300343 0.0983268 0.94875 + outer loop + vertex 1.06678 1.93592 2.58109 + vertex 1.07033 1.93834 2.57972 + vertex 1.06616 1.94006 2.58086 + endloop + endfacet + facet normal 0.362887 0.106371 0.925742 + outer loop + vertex 1.06616 1.94006 2.58086 + vertex 1.06302 1.93599 2.58256 + vertex 1.06678 1.93592 2.58109 + endloop + endfacet + facet normal 0.270977 0.128462 0.953975 + outer loop + vertex 1.06591 1.9314 2.58198 + vertex 1.06764 1.92565 2.58226 + vertex 1.07042 1.92985 2.5809 + endloop + endfacet + facet normal 0.277343 0.150616 0.948892 + outer loop + vertex 1.07042 1.92985 2.5809 + vertex 1.06923 1.93391 2.58061 + vertex 1.06591 1.9314 2.58198 + endloop + endfacet + facet normal 0.236431 0.1395 0.961582 + outer loop + vertex 1.06923 1.93391 2.58061 + vertex 1.07042 1.92985 2.5809 + vertex 1.07356 1.9341 2.57952 + endloop + endfacet + facet normal 0.236832 0.134103 0.962251 + outer loop + vertex 1.06923 1.93391 2.58061 + vertex 1.07356 1.9341 2.57952 + vertex 1.07033 1.93834 2.57972 + endloop + endfacet + facet normal 0.247586 0.142459 0.958335 + outer loop + vertex 1.07033 1.93834 2.57972 + vertex 1.07356 1.9341 2.57952 + vertex 1.07434 1.93857 2.57865 + endloop + endfacet + facet normal 0.217895 0.153904 0.963761 + outer loop + vertex 1.07538 1.92834 2.58002 + vertex 1.07356 1.9341 2.57952 + vertex 1.07042 1.92985 2.5809 + endloop + endfacet + facet normal 0.213897 0.138923 0.966927 + outer loop + vertex 1.07184 1.92572 2.58118 + vertex 1.07538 1.92834 2.58002 + vertex 1.07042 1.92985 2.5809 + endloop + endfacet + facet normal 0.203128 0.153484 0.967048 + outer loop + vertex 1.07488 1.92385 2.58084 + vertex 1.07538 1.92834 2.58002 + vertex 1.07184 1.92572 2.58118 + endloop + endfacet + facet normal 0.205718 0.157937 0.965783 + outer loop + vertex 1.07184 1.92572 2.58118 + vertex 1.07168 1.92078 2.58202 + vertex 1.07488 1.92385 2.58084 + endloop + endfacet + facet normal 0.24272 0.155372 0.957573 + outer loop + vertex 1.07184 1.92572 2.58118 + vertex 1.06764 1.92565 2.58226 + vertex 1.07168 1.92078 2.58202 + endloop + endfacet + facet normal 0.227354 0.142313 0.963357 + outer loop + vertex 1.06764 1.92565 2.58226 + vertex 1.06697 1.92119 2.58308 + vertex 1.07168 1.92078 2.58202 + endloop + endfacet + facet normal 0.227202 0.139334 0.963828 + outer loop + vertex 1.06803 1.9173 2.58339 + vertex 1.07168 1.92078 2.58202 + vertex 1.06697 1.92119 2.58308 + endloop + endfacet + facet normal 0.217332 0.149958 0.96451 + outer loop + vertex 1.07169 1.91592 2.58278 + vertex 1.07168 1.92078 2.58202 + vertex 1.06803 1.9173 2.58339 + endloop + endfacet + facet normal 0.205672 0.150319 0.967007 + outer loop + vertex 1.07538 1.92834 2.58002 + vertex 1.07834 1.93257 2.57873 + vertex 1.07356 1.9341 2.57952 + endloop + endfacet + facet normal 0.207636 0.15725 0.965484 + outer loop + vertex 1.07834 1.93257 2.57873 + vertex 1.07764 1.93708 2.57815 + vertex 1.07356 1.9341 2.57952 + endloop + endfacet + facet normal 0.212954 0.149957 0.965486 + outer loop + vertex 1.07356 1.9341 2.57952 + vertex 1.07764 1.93708 2.57815 + vertex 1.07434 1.93857 2.57865 + endloop + endfacet + facet normal 0.213159 0.150452 0.965364 + outer loop + vertex 1.07764 1.93708 2.57815 + vertex 1.07689 1.94084 2.57773 + vertex 1.07434 1.93857 2.57865 + endloop + endfacet + facet normal 0.225973 0.135799 0.964622 + outer loop + vertex 1.07434 1.93857 2.57865 + vertex 1.07689 1.94084 2.57773 + vertex 1.07349 1.94232 2.57832 + endloop + endfacet + facet normal 0.247784 0.140234 0.958612 + outer loop + vertex 1.07434 1.93857 2.57865 + vertex 1.07349 1.94232 2.57832 + vertex 1.07033 1.93834 2.57972 + endloop + endfacet + facet normal 0.27082 0.120635 0.955041 + outer loop + vertex 1.07033 1.93834 2.57972 + vertex 1.07349 1.94232 2.57832 + vertex 1.06943 1.94354 2.57932 + endloop + endfacet + facet normal 0.274629 0.135854 0.951905 + outer loop + vertex 1.07349 1.94232 2.57832 + vertex 1.07259 1.94704 2.5779 + vertex 1.06943 1.94354 2.57932 + endloop + endfacet + facet normal 0.302015 0.109109 0.947039 + outer loop + vertex 1.06943 1.94354 2.57932 + vertex 1.07259 1.94704 2.5779 + vertex 1.06858 1.9484 2.57903 + endloop + endfacet + facet normal 0.308424 0.13211 0.94203 + outer loop + vertex 1.07259 1.94704 2.5779 + vertex 1.07119 1.95125 2.57777 + vertex 1.06858 1.9484 2.57903 + endloop + endfacet + facet normal 0.271926 0.120338 0.954764 + outer loop + vertex 1.07259 1.94704 2.5779 + vertex 1.07534 1.95121 2.5766 + vertex 1.07119 1.95125 2.57777 + endloop + endfacet + facet normal 0.271975 0.11818 0.95502 + outer loop + vertex 1.07166 1.9561 2.57704 + vertex 1.07119 1.95125 2.57777 + vertex 1.07534 1.95121 2.5766 + endloop + endfacet + facet normal 0.240215 0.14295 0.960136 + outer loop + vertex 1.07741 1.94534 2.57695 + vertex 1.07534 1.95121 2.5766 + vertex 1.07259 1.94704 2.5779 + endloop + endfacet + facet normal 0.227574 0.138733 0.963827 + outer loop + vertex 1.07534 1.95121 2.5766 + vertex 1.07741 1.94534 2.57695 + vertex 1.0802 1.94958 2.57568 + endloop + endfacet + facet normal 0.231606 0.152493 0.960783 + outer loop + vertex 1.0802 1.94958 2.57568 + vertex 1.07868 1.95364 2.57541 + vertex 1.07534 1.95121 2.5766 + endloop + endfacet + facet normal 0.212977 0.145844 0.966111 + outer loop + vertex 1.07868 1.95364 2.57541 + vertex 1.0802 1.94958 2.57568 + vertex 1.08307 1.95374 2.57442 + endloop + endfacet + facet normal 0.213324 0.139253 0.967006 + outer loop + vertex 1.07868 1.95364 2.57541 + vertex 1.08307 1.95374 2.57442 + vertex 1.0792 1.95843 2.5746 + endloop + endfacet + facet normal 0.200768 0.154622 0.967359 + outer loop + vertex 1.08521 1.94815 2.57487 + vertex 1.08307 1.95374 2.57442 + vertex 1.0802 1.94958 2.57568 + endloop + endfacet + facet normal 0.198856 0.147035 0.968936 + outer loop + vertex 1.08178 1.94551 2.57598 + vertex 1.08521 1.94815 2.57487 + vertex 1.0802 1.94958 2.57568 + endloop + endfacet + facet normal 0.190908 0.157345 0.968915 + outer loop + vertex 1.0848 1.94371 2.57567 + vertex 1.08521 1.94815 2.57487 + vertex 1.08178 1.94551 2.57598 + endloop + endfacet + facet normal 0.190995 0.1575 0.968873 + outer loop + vertex 1.08178 1.94551 2.57598 + vertex 1.08153 1.94057 2.57683 + vertex 1.0848 1.94371 2.57567 + endloop + endfacet + facet normal 0.209532 0.155958 0.965284 + outer loop + vertex 1.08178 1.94551 2.57598 + vertex 1.07741 1.94534 2.57695 + vertex 1.08153 1.94057 2.57683 + endloop + endfacet + facet normal 0.196963 0.144969 0.969634 + outer loop + vertex 1.07741 1.94534 2.57695 + vertex 1.07689 1.94084 2.57773 + vertex 1.08153 1.94057 2.57683 + endloop + endfacet + facet normal 0.202808 0.155363 0.966815 + outer loop + vertex 1.08521 1.94815 2.57487 + vertex 1.08799 1.95247 2.5736 + vertex 1.08307 1.95374 2.57442 + endloop + endfacet + facet normal 0.204117 0.161227 0.965579 + outer loop + vertex 1.08799 1.95247 2.5736 + vertex 1.08669 1.95629 2.57323 + vertex 1.08307 1.95374 2.57442 + endloop + endfacet + facet normal 0.211545 0.150706 0.965679 + outer loop + vertex 1.08307 1.95374 2.57442 + vertex 1.08669 1.95629 2.57323 + vertex 1.08385 1.95815 2.57356 + endloop + endfacet + facet normal 0.214578 0.155593 0.964234 + outer loop + vertex 1.08669 1.95629 2.57323 + vertex 1.08753 1.96075 2.57232 + vertex 1.08385 1.95815 2.57356 + endloop + endfacet + facet normal 0.200301 0.158786 0.966781 + outer loop + vertex 1.08753 1.96075 2.57232 + vertex 1.08669 1.95629 2.57323 + vertex 1.09119 1.95667 2.57224 + endloop + endfacet + facet normal 0.212836 0.170125 0.962163 + outer loop + vertex 1.09185 1.96126 2.57128 + vertex 1.08753 1.96075 2.57232 + vertex 1.09119 1.95667 2.57224 + endloop + endfacet + facet normal 0.19022 0.174225 0.966158 + outer loop + vertex 1.09185 1.96126 2.57128 + vertex 1.09119 1.95667 2.57224 + vertex 1.09553 1.95962 2.57085 + endloop + endfacet + facet normal 0.191465 0.177214 0.965369 + outer loop + vertex 1.09553 1.95962 2.57085 + vertex 1.09489 1.9642 2.57014 + vertex 1.09185 1.96126 2.57128 + endloop + endfacet + facet normal 0.174938 0.175444 0.968822 + outer loop + vertex 1.09489 1.9642 2.57014 + vertex 1.09553 1.95962 2.57085 + vertex 1.09988 1.96254 2.56954 + endloop + endfacet + facet normal 0.178447 0.186994 0.966018 + outer loop + vertex 1.09988 1.96254 2.56954 + vertex 1.09839 1.96752 2.56885 + vertex 1.09489 1.9642 2.57014 + endloop + endfacet + facet normal 0.195983 0.168503 0.966022 + outer loop + vertex 1.09489 1.9642 2.57014 + vertex 1.09839 1.96752 2.56885 + vertex 1.09363 1.96913 2.56953 + endloop + endfacet + facet normal 0.20762 0.171127 0.963125 + outer loop + vertex 1.09489 1.9642 2.57014 + vertex 1.09363 1.96913 2.56953 + vertex 1.0905 1.96503 2.57094 + endloop + endfacet + facet normal 0.206222 0.161814 0.965033 + outer loop + vertex 1.09185 1.96126 2.57128 + vertex 1.09489 1.9642 2.57014 + vertex 1.0905 1.96503 2.57094 + endloop + endfacet + facet normal 0.223323 0.158662 0.961745 + outer loop + vertex 1.08938 1.96877 2.57058 + vertex 1.0905 1.96503 2.57094 + vertex 1.09363 1.96913 2.56953 + endloop + endfacet + facet normal 0.223235 0.159405 0.961643 + outer loop + vertex 1.08938 1.96877 2.57058 + vertex 1.09363 1.96913 2.56953 + vertex 1.09014 1.97315 2.56968 + endloop + endfacet + facet normal 0.234931 0.156894 0.959266 + outer loop + vertex 1.08938 1.96877 2.57058 + vertex 1.09014 1.97315 2.56968 + vertex 1.08667 1.97058 2.57095 + endloop + endfacet + facet normal 0.232697 0.153307 0.96039 + outer loop + vertex 1.08667 1.97058 2.57095 + vertex 1.08588 1.96614 2.57185 + vertex 1.08938 1.96877 2.57058 + endloop + endfacet + facet normal 0.240682 0.151555 0.958699 + outer loop + vertex 1.08667 1.97058 2.57095 + vertex 1.08237 1.97038 2.57206 + vertex 1.08588 1.96614 2.57185 + endloop + endfacet + facet normal 0.232327 0.144471 0.961848 + outer loop + vertex 1.08237 1.97038 2.57206 + vertex 1.08182 1.96574 2.57289 + vertex 1.08588 1.96614 2.57185 + endloop + endfacet + facet normal 0.232142 0.145897 0.961678 + outer loop + vertex 1.08293 1.962 2.57318 + vertex 1.08588 1.96614 2.57185 + vertex 1.08182 1.96574 2.57289 + endloop + endfacet + facet normal 0.232693 0.146049 0.961522 + outer loop + vertex 1.08293 1.962 2.57318 + vertex 1.08182 1.96574 2.57289 + vertex 1.07953 1.96322 2.57382 + endloop + endfacet + facet normal 0.230862 0.140233 0.962828 + outer loop + vertex 1.0792 1.95843 2.5746 + vertex 1.08293 1.962 2.57318 + vertex 1.07953 1.96322 2.57382 + endloop + endfacet + facet normal 0.223822 0.1478 0.963358 + outer loop + vertex 1.08385 1.95815 2.57356 + vertex 1.08293 1.962 2.57318 + vertex 1.0792 1.95843 2.5746 + endloop + endfacet + facet normal 0.223828 0.148064 0.963316 + outer loop + vertex 1.0792 1.95843 2.5746 + vertex 1.08307 1.95374 2.57442 + vertex 1.08385 1.95815 2.57356 + endloop + endfacet + facet normal 0.220563 0.147108 0.964215 + outer loop + vertex 1.08385 1.95815 2.57356 + vertex 1.08753 1.96075 2.57232 + vertex 1.08293 1.962 2.57318 + endloop + endfacet + facet normal 0.243888 0.135438 0.9603 + outer loop + vertex 1.07953 1.96322 2.57382 + vertex 1.08182 1.96574 2.57289 + vertex 1.07852 1.96714 2.57353 + endloop + endfacet + facet normal 0.222051 0.153482 0.962879 + outer loop + vertex 1.08753 1.96075 2.57232 + vertex 1.08588 1.96614 2.57185 + vertex 1.08293 1.962 2.57318 + endloop + endfacet + facet normal 0.226779 0.154809 0.961564 + outer loop + vertex 1.08588 1.96614 2.57185 + vertex 1.08753 1.96075 2.57232 + vertex 1.0905 1.96503 2.57094 + endloop + endfacet + facet normal 0.246462 0.14222 0.95866 + outer loop + vertex 1.08182 1.96574 2.57289 + vertex 1.08237 1.97038 2.57206 + vertex 1.07852 1.96714 2.57353 + endloop + endfacet + facet normal 0.258018 0.127982 0.957626 + outer loop + vertex 1.07852 1.96714 2.57353 + vertex 1.08237 1.97038 2.57206 + vertex 1.07771 1.9721 2.57308 + endloop + endfacet + facet normal 0.261981 0.140381 0.954809 + outer loop + vertex 1.08237 1.97038 2.57206 + vertex 1.08057 1.97641 2.57167 + vertex 1.07771 1.9721 2.57308 + endloop + endfacet + facet normal 0.293647 0.117365 0.948682 + outer loop + vertex 1.07771 1.9721 2.57308 + vertex 1.08057 1.97641 2.57167 + vertex 1.07652 1.97647 2.57291 + endloop + endfacet + facet normal 0.293877 0.105695 0.949981 + outer loop + vertex 1.07694 1.98158 2.57221 + vertex 1.07652 1.97647 2.57291 + vertex 1.08057 1.97641 2.57167 + endloop + endfacet + facet normal 0.369548 0.0959873 0.924241 + outer loop + vertex 1.07652 1.97647 2.57291 + vertex 1.07694 1.98158 2.57221 + vertex 1.0735 1.97836 2.57392 + endloop + endfacet + facet normal 0.257504 0.139132 0.956208 + outer loop + vertex 1.08057 1.97641 2.57167 + vertex 1.08237 1.97038 2.57206 + vertex 1.08535 1.97463 2.57064 + endloop + endfacet + facet normal 0.240666 0.151739 0.958674 + outer loop + vertex 1.08535 1.97463 2.57064 + vertex 1.08237 1.97038 2.57206 + vertex 1.08667 1.97058 2.57095 + endloop + endfacet + facet normal 0.239069 0.151257 0.959149 + outer loop + vertex 1.08667 1.97058 2.57095 + vertex 1.09014 1.97315 2.56968 + vertex 1.08535 1.97463 2.57064 + endloop + endfacet + facet normal 0.240342 0.156072 0.958059 + outer loop + vertex 1.09014 1.97315 2.56968 + vertex 1.08814 1.97873 2.56927 + vertex 1.08535 1.97463 2.57064 + endloop + endfacet + facet normal 0.239809 0.155894 0.958222 + outer loop + vertex 1.09014 1.97315 2.56968 + vertex 1.09297 1.97712 2.56832 + vertex 1.08814 1.97873 2.56927 + endloop + endfacet + facet normal 0.241557 0.161967 0.956774 + outer loop + vertex 1.09297 1.97712 2.56832 + vertex 1.09158 1.98113 2.56799 + vertex 1.08814 1.97873 2.56927 + endloop + endfacet + facet normal 0.244311 0.157985 0.956741 + outer loop + vertex 1.08814 1.97873 2.56927 + vertex 1.09158 1.98113 2.56799 + vertex 1.08851 1.98312 2.56845 + endloop + endfacet + facet normal 0.231444 0.158717 0.959814 + outer loop + vertex 1.09297 1.97712 2.56832 + vertex 1.09643 1.98068 2.5669 + vertex 1.09158 1.98113 2.56799 + endloop + endfacet + facet normal 0.231732 0.16441 0.958785 + outer loop + vertex 1.0916 1.98599 2.56715 + vertex 1.09158 1.98113 2.56799 + vertex 1.09643 1.98068 2.5669 + endloop + endfacet + facet normal 0.245554 0.17725 0.95304 + outer loop + vertex 1.09626 1.98566 2.56602 + vertex 1.0916 1.98599 2.56715 + vertex 1.09643 1.98068 2.5669 + endloop + endfacet + facet normal 0.221238 0.177488 0.958933 + outer loop + vertex 1.09626 1.98566 2.56602 + vertex 1.09643 1.98068 2.5669 + vertex 1.09952 1.98379 2.56561 + endloop + endfacet + facet normal 0.221775 0.178489 0.958623 + outer loop + vertex 1.09952 1.98379 2.56561 + vertex 1.09943 1.98867 2.56472 + vertex 1.09626 1.98566 2.56602 + endloop + endfacet + facet normal 0.231587 0.167986 0.958201 + outer loop + vertex 1.0946 1.98898 2.56583 + vertex 1.09626 1.98566 2.56602 + vertex 1.09943 1.98867 2.56472 + endloop + endfacet + facet normal 0.231422 0.161499 0.959355 + outer loop + vertex 1.0946 1.98898 2.56583 + vertex 1.09943 1.98867 2.56472 + vertex 1.09466 1.99365 2.56503 + endloop + endfacet + facet normal 0.249542 0.160514 0.954968 + outer loop + vertex 1.0946 1.98898 2.56583 + vertex 1.09466 1.99365 2.56503 + vertex 1.09154 1.99073 2.56634 + endloop + endfacet + facet normal 0.252898 0.166986 0.952973 + outer loop + vertex 1.09154 1.99073 2.56634 + vertex 1.0916 1.98599 2.56715 + vertex 1.0946 1.98898 2.56583 + endloop + endfacet + facet normal 0.275674 0.166234 0.946768 + outer loop + vertex 1.09154 1.99073 2.56634 + vertex 1.08725 1.99102 2.56754 + vertex 1.0916 1.98599 2.56715 + endloop + endfacet + facet normal 0.253802 0.146606 0.956081 + outer loop + vertex 1.08725 1.99102 2.56754 + vertex 1.08706 1.98633 2.56831 + vertex 1.0916 1.98599 2.56715 + endloop + endfacet + facet normal 0.254127 0.156561 0.954415 + outer loop + vertex 1.08851 1.98312 2.56845 + vertex 1.0916 1.98599 2.56715 + vertex 1.08706 1.98633 2.56831 + endloop + endfacet + facet normal 0.271246 0.145151 0.951502 + outer loop + vertex 1.08706 1.98633 2.56831 + vertex 1.08725 1.99102 2.56754 + vertex 1.08423 1.98806 2.56885 + endloop + endfacet + facet normal 0.292581 0.122075 0.948417 + outer loop + vertex 1.08423 1.98806 2.56885 + vertex 1.08725 1.99102 2.56754 + vertex 1.08293 1.99139 2.56883 + endloop + endfacet + facet normal 0.291861 0.105647 0.950608 + outer loop + vertex 1.08387 1.99634 2.56799 + vertex 1.08293 1.99139 2.56883 + vertex 1.08725 1.99102 2.56754 + endloop + endfacet + facet normal 0.192799 0.179054 0.964763 + outer loop + vertex 1.09952 1.98379 2.56561 + vertex 1.10445 1.98351 2.56468 + vertex 1.09943 1.98867 2.56472 + endloop + endfacet + facet normal 0.213221 0.199038 0.956515 + outer loop + vertex 1.09943 1.98867 2.56472 + vertex 1.10445 1.98351 2.56468 + vertex 1.10426 1.98828 2.56373 + endloop + endfacet + facet normal 0.212996 0.19265 0.957872 + outer loop + vertex 1.10426 1.98828 2.56373 + vertex 1.10287 1.99202 2.56328 + vertex 1.09943 1.98867 2.56472 + endloop + endfacet + facet normal 0.223976 0.181242 0.957594 + outer loop + vertex 1.09943 1.98867 2.56472 + vertex 1.10287 1.99202 2.56328 + vertex 1.09924 1.99347 2.56386 + endloop + endfacet + facet normal 0.221509 0.174296 0.959456 + outer loop + vertex 1.10287 1.99202 2.56328 + vertex 1.10154 1.99576 2.56291 + vertex 1.09924 1.99347 2.56386 + endloop + endfacet + facet normal 0.191834 0.185521 0.963733 + outer loop + vertex 1.10426 1.98828 2.56373 + vertex 1.10656 1.99062 2.56282 + vertex 1.10287 1.99202 2.56328 + endloop + endfacet + facet normal 0.190406 0.181419 0.964797 + outer loop + vertex 1.10656 1.99062 2.56282 + vertex 1.10629 1.99549 2.56196 + vertex 1.10287 1.99202 2.56328 + endloop + endfacet + facet normal 0.203519 0.168388 0.964482 + outer loop + vertex 1.10287 1.99202 2.56328 + vertex 1.10629 1.99549 2.56196 + vertex 1.10154 1.99576 2.56291 + endloop + endfacet + facet normal 0.203138 0.152281 0.967236 + outer loop + vertex 1.10157 2.00063 2.56214 + vertex 1.10154 1.99576 2.56291 + vertex 1.10629 1.99549 2.56196 + endloop + endfacet + facet normal 0.161559 0.18077 0.970165 + outer loop + vertex 1.10629 1.99549 2.56196 + vertex 1.10656 1.99062 2.56282 + vertex 1.1113 1.99067 2.56202 + endloop + endfacet + facet normal 0.178383 0.19815 0.963803 + outer loop + vertex 1.11114 1.99545 2.56107 + vertex 1.10629 1.99549 2.56196 + vertex 1.1113 1.99067 2.56202 + endloop + endfacet + facet normal 0.153254 0.198196 0.968107 + outer loop + vertex 1.11114 1.99545 2.56107 + vertex 1.1113 1.99067 2.56202 + vertex 1.11441 1.99402 2.56084 + endloop + endfacet + facet normal 0.150192 0.190864 0.970059 + outer loop + vertex 1.11441 1.99402 2.56084 + vertex 1.11447 1.9988 2.55989 + vertex 1.11114 1.99545 2.56107 + endloop + endfacet + facet normal 0.157823 0.183372 0.970292 + outer loop + vertex 1.10945 1.99868 2.56073 + vertex 1.11114 1.99545 2.56107 + vertex 1.11447 1.9988 2.55989 + endloop + endfacet + facet normal 0.15834 0.173724 0.971982 + outer loop + vertex 1.10945 1.99868 2.56073 + vertex 1.11447 1.9988 2.55989 + vertex 1.10963 2.00359 2.55982 + endloop + endfacet + facet normal 0.187162 0.171801 0.967189 + outer loop + vertex 1.10945 1.99868 2.56073 + vertex 1.10963 2.00359 2.55982 + vertex 1.10622 2.00039 2.56105 + endloop + endfacet + facet normal 0.191602 0.180635 0.964707 + outer loop + vertex 1.10622 2.00039 2.56105 + vertex 1.10629 1.99549 2.56196 + vertex 1.10945 1.99868 2.56073 + endloop + endfacet + facet normal 0.232486 0.179622 0.955869 + outer loop + vertex 1.10622 2.00039 2.56105 + vertex 1.10157 2.00063 2.56214 + vertex 1.10629 1.99549 2.56196 + endloop + endfacet + facet normal 0.171312 0.186746 0.967356 + outer loop + vertex 1.10963 2.00359 2.55982 + vertex 1.11447 1.9988 2.55989 + vertex 1.1146 2.00362 2.55894 + endloop + endfacet + facet normal 0.171338 0.186061 0.967484 + outer loop + vertex 1.1146 2.00362 2.55894 + vertex 1.11329 2.00728 2.55847 + vertex 1.10963 2.00359 2.55982 + endloop + endfacet + facet normal 0.18334 0.174146 0.967502 + outer loop + vertex 1.10963 2.00359 2.55982 + vertex 1.11329 2.00728 2.55847 + vertex 1.10971 2.00858 2.55891 + endloop + endfacet + facet normal 0.22477 0.17194 0.959122 + outer loop + vertex 1.10549 2.00816 2.55997 + vertex 1.10963 2.00359 2.55982 + vertex 1.10971 2.00858 2.55891 + endloop + endfacet + facet normal 0.226344 0.160317 0.960764 + outer loop + vertex 1.10971 2.00858 2.55891 + vertex 1.10821 2.01245 2.55862 + vertex 1.10549 2.00816 2.55997 + endloop + endfacet + facet normal 0.259109 0.138032 0.955934 + outer loop + vertex 1.10549 2.00816 2.55997 + vertex 1.10821 2.01245 2.55862 + vertex 1.10404 2.01338 2.55961 + endloop + endfacet + facet normal 0.261266 0.150313 0.953491 + outer loop + vertex 1.10821 2.01245 2.55862 + vertex 1.10678 2.0164 2.55839 + vertex 1.10404 2.01338 2.55961 + endloop + endfacet + facet normal 0.28503 0.127363 0.950019 + outer loop + vertex 1.10404 2.01338 2.55961 + vertex 1.10678 2.0164 2.55839 + vertex 1.10305 2.01862 2.55921 + endloop + endfacet + facet normal 0.238406 0.142487 0.960656 + outer loop + vertex 1.10821 2.01245 2.55862 + vertex 1.11121 2.01665 2.55725 + vertex 1.10678 2.0164 2.55839 + endloop + endfacet + facet normal 0.20782 0.165471 0.96407 + outer loop + vertex 1.11248 2.01159 2.55785 + vertex 1.11121 2.01665 2.55725 + vertex 1.10821 2.01245 2.55862 + endloop + endfacet + facet normal 0.182818 0.159925 0.970052 + outer loop + vertex 1.11248 2.01159 2.55785 + vertex 1.11663 2.01448 2.55659 + vertex 1.11121 2.01665 2.55725 + endloop + endfacet + facet normal 0.193728 0.189434 0.962592 + outer loop + vertex 1.11663 2.01448 2.55659 + vertex 1.11545 2.01948 2.55584 + vertex 1.11121 2.01665 2.55725 + endloop + endfacet + facet normal 0.171605 0.184981 0.967643 + outer loop + vertex 1.1193 2.01801 2.55544 + vertex 1.11545 2.01948 2.55584 + vertex 1.11663 2.01448 2.55659 + endloop + endfacet + facet normal 0.160963 0.193134 0.967879 + outer loop + vertex 1.12103 2.01501 2.55575 + vertex 1.1193 2.01801 2.55544 + vertex 1.11663 2.01448 2.55659 + endloop + endfacet + facet normal 0.16207 0.185852 0.969119 + outer loop + vertex 1.12103 2.01501 2.55575 + vertex 1.11663 2.01448 2.55659 + vertex 1.1211 2.01015 2.55667 + endloop + endfacet + facet normal 0.161124 0.185868 0.969274 + outer loop + vertex 1.12103 2.01501 2.55575 + vertex 1.1211 2.01015 2.55667 + vertex 1.12425 2.01357 2.55549 + endloop + endfacet + facet normal 0.164772 0.194443 0.966976 + outer loop + vertex 1.12425 2.01357 2.55549 + vertex 1.12421 2.0183 2.55455 + vertex 1.12103 2.01501 2.55575 + endloop + endfacet + facet normal 0.175724 0.194172 0.9651 + outer loop + vertex 1.12425 2.01357 2.55549 + vertex 1.1292 2.01354 2.55459 + vertex 1.12421 2.0183 2.55455 + endloop + endfacet + facet normal 0.17168 0.189943 0.966668 + outer loop + vertex 1.12421 2.0183 2.55455 + vertex 1.1292 2.01354 2.55459 + vertex 1.12903 2.01832 2.55368 + endloop + endfacet + facet normal 0.171427 0.19627 0.965449 + outer loop + vertex 1.12903 2.01832 2.55368 + vertex 1.12769 2.02193 2.55319 + vertex 1.12421 2.0183 2.55455 + endloop + endfacet + facet normal 0.169845 0.197776 0.965421 + outer loop + vertex 1.12421 2.0183 2.55455 + vertex 1.12769 2.02193 2.55319 + vertex 1.12406 2.02301 2.55361 + endloop + endfacet + facet normal 0.168232 0.197779 0.965703 + outer loop + vertex 1.11967 2.02244 2.55449 + vertex 1.12421 2.0183 2.55455 + vertex 1.12406 2.02301 2.55361 + endloop + endfacet + facet normal 0.167565 0.201779 0.964991 + outer loop + vertex 1.12406 2.02301 2.55361 + vertex 1.12263 2.02666 2.55309 + vertex 1.11967 2.02244 2.55449 + endloop + endfacet + facet normal 0.180714 0.1924 0.964533 + outer loop + vertex 1.11967 2.02244 2.55449 + vertex 1.12263 2.02666 2.55309 + vertex 1.11801 2.02745 2.5538 + endloop + endfacet + facet normal 0.187904 0.194528 0.962731 + outer loop + vertex 1.11967 2.02244 2.55449 + vertex 1.11801 2.02745 2.5538 + vertex 1.11469 2.02401 2.55514 + endloop + endfacet + facet normal 0.183631 0.179459 0.966475 + outer loop + vertex 1.11469 2.02401 2.55514 + vertex 1.11545 2.01948 2.55584 + vertex 1.11967 2.02244 2.55449 + endloop + endfacet + facet normal 0.181466 0.197859 0.963287 + outer loop + vertex 1.12263 2.02666 2.55309 + vertex 1.12131 2.03165 2.55232 + vertex 1.11801 2.02745 2.5538 + endloop + endfacet + facet normal 0.198251 0.184457 0.962638 + outer loop + vertex 1.11801 2.02745 2.5538 + vertex 1.12131 2.03165 2.55232 + vertex 1.11688 2.03129 2.5533 + endloop + endfacet + facet normal 0.219951 0.190079 0.956813 + outer loop + vertex 1.11801 2.02745 2.5538 + vertex 1.11688 2.03129 2.5533 + vertex 1.11335 2.02885 2.55459 + endloop + endfacet + facet normal 0.214424 0.168654 0.96207 + outer loop + vertex 1.11469 2.02401 2.55514 + vertex 1.11801 2.02745 2.5538 + vertex 1.11335 2.02885 2.55459 + endloop + endfacet + facet normal 0.234843 0.16882 0.957261 + outer loop + vertex 1.11335 2.02885 2.55459 + vertex 1.11688 2.03129 2.5533 + vertex 1.11424 2.0331 2.55363 + endloop + endfacet + facet normal 0.234629 0.168486 0.957372 + outer loop + vertex 1.11688 2.03129 2.5533 + vertex 1.11766 2.03573 2.55233 + vertex 1.11424 2.0331 2.55363 + endloop + endfacet + facet normal 0.250643 0.147412 0.95679 + outer loop + vertex 1.11424 2.0331 2.55363 + vertex 1.11766 2.03573 2.55233 + vertex 1.11308 2.03702 2.55333 + endloop + endfacet + facet normal 0.255515 0.168274 0.952048 + outer loop + vertex 1.11766 2.03573 2.55233 + vertex 1.11567 2.0413 2.55188 + vertex 1.11308 2.03702 2.55333 + endloop + endfacet + facet normal 0.286135 0.147938 0.9467 + outer loop + vertex 1.11308 2.03702 2.55333 + vertex 1.11567 2.0413 2.55188 + vertex 1.1115 2.04119 2.55315 + endloop + endfacet + facet normal 0.285915 0.151186 0.946253 + outer loop + vertex 1.11182 2.04615 2.55226 + vertex 1.1115 2.04119 2.55315 + vertex 1.11567 2.0413 2.55188 + endloop + endfacet + facet normal 0.250057 0.166467 0.953814 + outer loop + vertex 1.11567 2.0413 2.55188 + vertex 1.11766 2.03573 2.55233 + vertex 1.12037 2.03992 2.55088 + endloop + endfacet + facet normal 0.255398 0.188785 0.948226 + outer loop + vertex 1.12037 2.03992 2.55088 + vertex 1.11889 2.04376 2.55052 + vertex 1.11567 2.0413 2.55188 + endloop + endfacet + facet normal 0.269257 0.170438 0.947867 + outer loop + vertex 1.11608 2.04563 2.55098 + vertex 1.11567 2.0413 2.55188 + vertex 1.11889 2.04376 2.55052 + endloop + endfacet + facet normal 0.270897 0.173136 0.94691 + outer loop + vertex 1.11889 2.04376 2.55052 + vertex 1.11908 2.04837 2.54962 + vertex 1.11608 2.04563 2.55098 + endloop + endfacet + facet normal 0.28488 0.157179 0.945589 + outer loop + vertex 1.11488 2.04876 2.55082 + vertex 1.11608 2.04563 2.55098 + vertex 1.11908 2.04837 2.54962 + endloop + endfacet + facet normal 0.28482 0.15578 0.945838 + outer loop + vertex 1.11488 2.04876 2.55082 + vertex 1.11908 2.04837 2.54962 + vertex 1.11536 2.05289 2.54999 + endloop + endfacet + facet normal 0.307921 0.175607 0.935065 + outer loop + vertex 1.11536 2.05289 2.54999 + vertex 1.11908 2.04837 2.54962 + vertex 1.11909 2.05295 2.54876 + endloop + endfacet + facet normal 0.308897 0.161169 0.937341 + outer loop + vertex 1.11909 2.05295 2.54876 + vertex 1.11759 2.05621 2.54869 + vertex 1.11536 2.05289 2.54999 + endloop + endfacet + facet normal 0.27844 0.177403 0.943928 + outer loop + vertex 1.11908 2.04837 2.54962 + vertex 1.12194 2.05122 2.54824 + vertex 1.11909 2.05295 2.54876 + endloop + endfacet + facet normal 0.278769 0.178007 0.943717 + outer loop + vertex 1.12194 2.05122 2.54824 + vertex 1.12191 2.05593 2.54736 + vertex 1.11909 2.05295 2.54876 + endloop + endfacet + facet normal 0.260664 0.195958 0.945333 + outer loop + vertex 1.12342 2.04804 2.54849 + vertex 1.12194 2.05122 2.54824 + vertex 1.11908 2.04837 2.54962 + endloop + endfacet + facet normal 0.260673 0.196387 0.945242 + outer loop + vertex 1.11908 2.04837 2.54962 + vertex 1.12303 2.04386 2.54947 + vertex 1.12342 2.04804 2.54849 + endloop + endfacet + facet normal 0.242025 0.187847 0.951913 + outer loop + vertex 1.12342 2.04804 2.54849 + vertex 1.12647 2.05083 2.54716 + vertex 1.12194 2.05122 2.54824 + endloop + endfacet + facet normal 0.241717 0.179549 0.953591 + outer loop + vertex 1.12191 2.05593 2.54736 + vertex 1.12194 2.05122 2.54824 + vertex 1.12647 2.05083 2.54716 + endloop + endfacet + facet normal 0.22656 0.204928 0.952195 + outer loop + vertex 1.1265 2.04608 2.54818 + vertex 1.12647 2.05083 2.54716 + vertex 1.12342 2.04804 2.54849 + endloop + endfacet + facet normal 0.224553 0.20158 0.953384 + outer loop + vertex 1.12303 2.04386 2.54947 + vertex 1.1265 2.04608 2.54818 + vertex 1.12342 2.04804 2.54849 + endloop + endfacet + facet normal 0.215269 0.215523 0.952475 + outer loop + vertex 1.12792 2.04212 2.54876 + vertex 1.1265 2.04608 2.54818 + vertex 1.12303 2.04386 2.54947 + endloop + endfacet + facet normal 0.20984 0.198314 0.957413 + outer loop + vertex 1.12476 2.03899 2.5501 + vertex 1.12792 2.04212 2.54876 + vertex 1.12303 2.04386 2.54947 + endloop + endfacet + facet normal 0.213535 0.199489 0.956351 + outer loop + vertex 1.12476 2.03899 2.5501 + vertex 1.12303 2.04386 2.54947 + vertex 1.12037 2.03992 2.55088 + endloop + endfacet + facet normal 0.194378 0.213909 0.957319 + outer loop + vertex 1.12963 2.03725 2.5495 + vertex 1.12792 2.04212 2.54876 + vertex 1.12476 2.03899 2.5501 + endloop + endfacet + facet normal 0.191086 0.203721 0.9602 + outer loop + vertex 1.12476 2.03899 2.5501 + vertex 1.12558 2.03454 2.55088 + vertex 1.12963 2.03725 2.5495 + endloop + endfacet + facet normal 0.184556 0.213065 0.959449 + outer loop + vertex 1.12558 2.03454 2.55088 + vertex 1.12935 2.03305 2.55048 + vertex 1.12963 2.03725 2.5495 + endloop + endfacet + facet normal 0.187867 0.212715 0.958884 + outer loop + vertex 1.12935 2.03305 2.55048 + vertex 1.13406 2.03311 2.54955 + vertex 1.12963 2.03725 2.5495 + endloop + endfacet + facet normal 0.189108 0.214035 0.958346 + outer loop + vertex 1.12963 2.03725 2.5495 + vertex 1.13406 2.03311 2.54955 + vertex 1.13387 2.03768 2.54856 + endloop + endfacet + facet normal 0.188666 0.217113 0.957741 + outer loop + vertex 1.13387 2.03768 2.54856 + vertex 1.13195 2.04075 2.54825 + vertex 1.12963 2.03725 2.5495 + endloop + endfacet + facet normal 0.189933 0.217865 0.957319 + outer loop + vertex 1.13387 2.03768 2.54856 + vertex 1.13673 2.04082 2.54728 + vertex 1.13195 2.04075 2.54825 + endloop + endfacet + facet normal 0.189926 0.217988 0.957293 + outer loop + vertex 1.13149 2.04567 2.54722 + vertex 1.13195 2.04075 2.54825 + vertex 1.13673 2.04082 2.54728 + endloop + endfacet + facet normal 0.191456 0.219635 0.956611 + outer loop + vertex 1.13644 2.04552 2.54626 + vertex 1.13149 2.04567 2.54722 + vertex 1.13673 2.04082 2.54728 + endloop + endfacet + facet normal 0.185485 0.219526 0.957812 + outer loop + vertex 1.13644 2.04552 2.54626 + vertex 1.13673 2.04082 2.54728 + vertex 1.13978 2.04386 2.54599 + endloop + endfacet + facet normal 0.185808 0.22021 0.957592 + outer loop + vertex 1.13978 2.04386 2.54599 + vertex 1.13955 2.04859 2.54495 + vertex 1.13644 2.04552 2.54626 + endloop + endfacet + facet normal 0.184117 0.221894 0.95753 + outer loop + vertex 1.13459 2.04874 2.54587 + vertex 1.13644 2.04552 2.54626 + vertex 1.13955 2.04859 2.54495 + endloop + endfacet + facet normal 0.184147 0.219504 0.958075 + outer loop + vertex 1.13459 2.04874 2.54587 + vertex 1.13955 2.04859 2.54495 + vertex 1.13435 2.05355 2.54481 + endloop + endfacet + facet normal 0.192768 0.219571 0.956362 + outer loop + vertex 1.13459 2.04874 2.54587 + vertex 1.13435 2.05355 2.54481 + vertex 1.13122 2.05049 2.54615 + endloop + endfacet + facet normal 0.194351 0.222792 0.955296 + outer loop + vertex 1.13122 2.05049 2.54615 + vertex 1.13149 2.04567 2.54722 + vertex 1.13459 2.04874 2.54587 + endloop + endfacet + facet normal 0.219406 0.222953 0.949817 + outer loop + vertex 1.13122 2.05049 2.54615 + vertex 1.12647 2.05083 2.54716 + vertex 1.13149 2.04567 2.54722 + endloop + endfacet + facet normal 0.219409 0.223127 0.949776 + outer loop + vertex 1.13122 2.05049 2.54615 + vertex 1.12944 2.05377 2.54579 + vertex 1.12647 2.05083 2.54716 + endloop + endfacet + facet normal 0.199323 0.212954 0.956515 + outer loop + vertex 1.12944 2.05377 2.54579 + vertex 1.13122 2.05049 2.54615 + vertex 1.13435 2.05355 2.54481 + endloop + endfacet + facet normal 0.199318 0.206455 0.95794 + outer loop + vertex 1.12944 2.05377 2.54579 + vertex 1.13435 2.05355 2.54481 + vertex 1.12936 2.05852 2.54478 + endloop + endfacet + facet normal 0.214281 0.221431 0.951342 + outer loop + vertex 1.12936 2.05852 2.54478 + vertex 1.13435 2.05355 2.54481 + vertex 1.13405 2.05829 2.54378 + endloop + endfacet + facet normal 0.214282 0.219758 0.95173 + outer loop + vertex 1.13405 2.05829 2.54378 + vertex 1.13273 2.06204 2.54321 + vertex 1.12936 2.05852 2.54478 + endloop + endfacet + facet normal 0.197164 0.214488 0.95662 + outer loop + vertex 1.13405 2.05829 2.54378 + vertex 1.13643 2.06047 2.5428 + vertex 1.13273 2.06204 2.54321 + endloop + endfacet + facet normal 0.198647 0.218307 0.955448 + outer loop + vertex 1.13643 2.06047 2.5428 + vertex 1.13672 2.06466 2.54178 + vertex 1.13273 2.06204 2.54321 + endloop + endfacet + facet normal 0.208406 0.204069 0.956516 + outer loop + vertex 1.13273 2.06204 2.54321 + vertex 1.13672 2.06466 2.54178 + vertex 1.13142 2.0669 2.54246 + endloop + endfacet + facet normal 0.226187 0.20811 0.951593 + outer loop + vertex 1.13273 2.06204 2.54321 + vertex 1.13142 2.0669 2.54246 + vertex 1.12907 2.06336 2.54379 + endloop + endfacet + facet normal 0.255656 0.187385 0.948434 + outer loop + vertex 1.12907 2.06336 2.54379 + vertex 1.13142 2.0669 2.54246 + vertex 1.12731 2.06644 2.54366 + endloop + endfacet + facet normal 0.271794 0.196353 0.942111 + outer loop + vertex 1.12907 2.06336 2.54379 + vertex 1.12731 2.06644 2.54366 + vertex 1.12519 2.06296 2.54499 + endloop + endfacet + facet normal 0.269924 0.208443 0.940049 + outer loop + vertex 1.12519 2.06296 2.54499 + vertex 1.12936 2.05852 2.54478 + vertex 1.12907 2.06336 2.54379 + endloop + endfacet + facet normal 0.226219 0.208211 0.951564 + outer loop + vertex 1.12936 2.05852 2.54478 + vertex 1.13273 2.06204 2.54321 + vertex 1.12907 2.06336 2.54379 + endloop + endfacet + facet normal 0.24566 0.185121 0.951515 + outer loop + vertex 1.1248 2.05876 2.54591 + vertex 1.12936 2.05852 2.54478 + vertex 1.12519 2.06296 2.54499 + endloop + endfacet + facet normal 0.24567 0.188957 0.950758 + outer loop + vertex 1.1248 2.05876 2.54591 + vertex 1.12626 2.05556 2.54617 + vertex 1.12936 2.05852 2.54478 + endloop + endfacet + facet normal 0.274357 0.201272 0.940328 + outer loop + vertex 1.12626 2.05556 2.54617 + vertex 1.1248 2.05876 2.54591 + vertex 1.12191 2.05593 2.54736 + endloop + endfacet + facet normal 0.308531 0.171565 0.935614 + outer loop + vertex 1.12519 2.06296 2.54499 + vertex 1.12731 2.06644 2.54366 + vertex 1.12385 2.06804 2.54451 + endloop + endfacet + facet normal 0.310172 0.175817 0.934281 + outer loop + vertex 1.12731 2.06644 2.54366 + vertex 1.12756 2.07106 2.54271 + vertex 1.12385 2.06804 2.54451 + endloop + endfacet + facet normal 0.256513 0.181885 0.949273 + outer loop + vertex 1.12756 2.07106 2.54271 + vertex 1.12731 2.06644 2.54366 + vertex 1.13142 2.0669 2.54246 + endloop + endfacet + facet normal 0.282676 0.20693 0.936629 + outer loop + vertex 1.13179 2.07127 2.54138 + vertex 1.12756 2.07106 2.54271 + vertex 1.13142 2.0669 2.54246 + endloop + endfacet + facet normal 0.227743 0.21486 0.94972 + outer loop + vertex 1.13179 2.07127 2.54138 + vertex 1.13142 2.0669 2.54246 + vertex 1.13547 2.06952 2.5409 + endloop + endfacet + facet normal 0.23167 0.223975 0.946659 + outer loop + vertex 1.13547 2.06952 2.5409 + vertex 1.13459 2.07397 2.54006 + vertex 1.13179 2.07127 2.54138 + endloop + endfacet + facet normal 0.257809 0.19657 0.945989 + outer loop + vertex 1.13179 2.07127 2.54138 + vertex 1.13459 2.07397 2.54006 + vertex 1.13033 2.07502 2.541 + endloop + endfacet + facet normal 0.209329 0.220676 0.952619 + outer loop + vertex 1.13459 2.07397 2.54006 + vertex 1.13547 2.06952 2.5409 + vertex 1.13945 2.07216 2.53941 + endloop + endfacet + facet normal 0.200773 0.232975 0.951532 + outer loop + vertex 1.13547 2.06952 2.5409 + vertex 1.13927 2.06796 2.54048 + vertex 1.13945 2.07216 2.53941 + endloop + endfacet + facet normal 0.188767 0.23405 0.953723 + outer loop + vertex 1.13927 2.06796 2.54048 + vertex 1.144 2.06801 2.53953 + vertex 1.13945 2.07216 2.53941 + endloop + endfacet + facet normal 0.193289 0.238934 0.951604 + outer loop + vertex 1.13945 2.07216 2.53941 + vertex 1.144 2.06801 2.53953 + vertex 1.1437 2.07255 2.53845 + endloop + endfacet + facet normal 0.193094 0.24032 0.951294 + outer loop + vertex 1.1437 2.07255 2.53845 + vertex 1.14171 2.07563 2.53807 + vertex 1.13945 2.07216 2.53941 + endloop + endfacet + facet normal 0.193181 0.240372 0.951264 + outer loop + vertex 1.1437 2.07255 2.53845 + vertex 1.14649 2.07562 2.53711 + vertex 1.14171 2.07563 2.53807 + endloop + endfacet + facet normal 0.193601 0.230877 0.953527 + outer loop + vertex 1.14126 2.08053 2.53698 + vertex 1.14171 2.07563 2.53807 + vertex 1.14649 2.07562 2.53711 + endloop + endfacet + facet normal 0.204666 0.242509 0.948315 + outer loop + vertex 1.1461 2.08025 2.53601 + vertex 1.14126 2.08053 2.53698 + vertex 1.14649 2.07562 2.53711 + endloop + endfacet + facet normal 0.195252 0.242198 0.950377 + outer loop + vertex 1.1461 2.08025 2.53601 + vertex 1.14649 2.07562 2.53711 + vertex 1.14942 2.07852 2.53576 + endloop + endfacet + facet normal 0.194028 0.239724 0.951255 + outer loop + vertex 1.14942 2.07852 2.53576 + vertex 1.14907 2.08313 2.53467 + vertex 1.1461 2.08025 2.53601 + endloop + endfacet + facet normal 0.19681 0.236909 0.951388 + outer loop + vertex 1.14427 2.08348 2.53558 + vertex 1.1461 2.08025 2.53601 + vertex 1.14907 2.08313 2.53467 + endloop + endfacet + facet normal 0.196487 0.224135 0.954545 + outer loop + vertex 1.14427 2.08348 2.53558 + vertex 1.14907 2.08313 2.53467 + vertex 1.14406 2.0881 2.53454 + endloop + endfacet + facet normal 0.21179 0.224068 0.951283 + outer loop + vertex 1.14427 2.08348 2.53558 + vertex 1.14406 2.0881 2.53454 + vertex 1.14106 2.08529 2.53587 + endloop + endfacet + facet normal 0.215181 0.230414 0.949003 + outer loop + vertex 1.14106 2.08529 2.53587 + vertex 1.14126 2.08053 2.53698 + vertex 1.14427 2.08348 2.53558 + endloop + endfacet + facet normal 0.250329 0.229882 0.940473 + outer loop + vertex 1.14106 2.08529 2.53587 + vertex 1.13659 2.08568 2.53696 + vertex 1.14126 2.08053 2.53698 + endloop + endfacet + facet normal 0.217147 0.199804 0.955471 + outer loop + vertex 1.13659 2.08568 2.53696 + vertex 1.13642 2.08099 2.53798 + vertex 1.14126 2.08053 2.53698 + endloop + endfacet + facet normal 0.218053 0.218861 0.95108 + outer loop + vertex 1.13772 2.07704 2.53859 + vertex 1.14126 2.08053 2.53698 + vertex 1.13642 2.08099 2.53798 + endloop + endfacet + facet normal 0.245284 0.226545 0.94261 + outer loop + vertex 1.13772 2.07704 2.53859 + vertex 1.13642 2.08099 2.53798 + vertex 1.13308 2.07875 2.53939 + endloop + endfacet + facet normal 0.239495 0.208152 0.948322 + outer loop + vertex 1.13459 2.07397 2.54006 + vertex 1.13772 2.07704 2.53859 + vertex 1.13308 2.07875 2.53939 + endloop + endfacet + facet normal 0.261521 0.203037 0.943601 + outer loop + vertex 1.13308 2.07875 2.53939 + vertex 1.13642 2.08099 2.53798 + vertex 1.13362 2.08284 2.53836 + endloop + endfacet + facet normal 0.257403 0.196268 0.946162 + outer loop + vertex 1.13642 2.08099 2.53798 + vertex 1.13659 2.08568 2.53696 + vertex 1.13362 2.08284 2.53836 + endloop + endfacet + facet normal 0.28661 0.164583 0.943805 + outer loop + vertex 1.13362 2.08284 2.53836 + vertex 1.13659 2.08568 2.53696 + vertex 1.13226 2.08595 2.53823 + endloop + endfacet + facet normal 0.250142 0.222649 0.942261 + outer loop + vertex 1.14106 2.08529 2.53587 + vertex 1.13951 2.08848 2.53553 + vertex 1.13659 2.08568 2.53696 + endloop + endfacet + facet normal 0.224143 0.210963 0.951449 + outer loop + vertex 1.13951 2.08848 2.53553 + vertex 1.14106 2.08529 2.53587 + vertex 1.14406 2.0881 2.53454 + endloop + endfacet + facet normal 0.223722 0.19878 0.954167 + outer loop + vertex 1.13951 2.08848 2.53553 + vertex 1.14406 2.0881 2.53454 + vertex 1.1397 2.0927 2.5346 + endloop + endfacet + facet normal 0.246391 0.220408 0.943775 + outer loop + vertex 1.1397 2.0927 2.5346 + vertex 1.14406 2.0881 2.53454 + vertex 1.14373 2.09279 2.53353 + endloop + endfacet + facet normal 0.195552 0.239764 0.950932 + outer loop + vertex 1.14942 2.07852 2.53576 + vertex 1.15409 2.07842 2.53483 + vertex 1.14907 2.08313 2.53467 + endloop + endfacet + facet normal 0.196848 0.241126 0.950321 + outer loop + vertex 1.14907 2.08313 2.53467 + vertex 1.15409 2.07842 2.53483 + vertex 1.15381 2.08288 2.53375 + endloop + endfacet + facet normal 0.196833 0.236426 0.951504 + outer loop + vertex 1.15381 2.08288 2.53375 + vertex 1.15202 2.08602 2.53335 + vertex 1.14907 2.08313 2.53467 + endloop + endfacet + facet normal 0.197022 0.236526 0.95144 + outer loop + vertex 1.15381 2.08288 2.53375 + vertex 1.15667 2.08597 2.53239 + vertex 1.15202 2.08602 2.53335 + endloop + endfacet + facet normal 0.197295 0.229542 0.953093 + outer loop + vertex 1.15167 2.09072 2.53229 + vertex 1.15202 2.08602 2.53335 + vertex 1.15667 2.08597 2.53239 + endloop + endfacet + facet normal 0.196145 0.229511 0.953337 + outer loop + vertex 1.15202 2.08602 2.53335 + vertex 1.15167 2.09072 2.53229 + vertex 1.14874 2.08777 2.5336 + endloop + endfacet + facet normal 0.1987 0.234551 0.95158 + outer loop + vertex 1.14907 2.08313 2.53467 + vertex 1.15202 2.08602 2.53335 + vertex 1.14874 2.08777 2.5336 + endloop + endfacet + facet normal 0.207124 0.234724 0.949739 + outer loop + vertex 1.14406 2.0881 2.53454 + vertex 1.14907 2.08313 2.53467 + vertex 1.14874 2.08777 2.5336 + endloop + endfacet + facet normal 0.197319 0.241132 0.950221 + outer loop + vertex 1.15409 2.07842 2.53483 + vertex 1.15697 2.08142 2.53347 + vertex 1.15381 2.08288 2.53375 + endloop + endfacet + facet normal 0.195803 0.237641 0.951414 + outer loop + vertex 1.15697 2.08142 2.53347 + vertex 1.15667 2.08597 2.53239 + vertex 1.15381 2.08288 2.53375 + endloop + endfacet + facet normal 0.196193 0.237647 0.951332 + outer loop + vertex 1.15667 2.08597 2.53239 + vertex 1.15697 2.08142 2.53347 + vertex 1.16124 2.08184 2.53249 + endloop + endfacet + facet normal 0.199038 0.24076 0.949957 + outer loop + vertex 1.16134 2.0861 2.53138 + vertex 1.15667 2.08597 2.53239 + vertex 1.16124 2.08184 2.53249 + endloop + endfacet + facet normal 0.195308 0.241026 0.950663 + outer loop + vertex 1.16134 2.0861 2.53138 + vertex 1.16124 2.08184 2.53249 + vertex 1.16528 2.08454 2.53097 + endloop + endfacet + facet normal 0.194391 0.238487 0.951492 + outer loop + vertex 1.16528 2.08454 2.53097 + vertex 1.16383 2.0894 2.53005 + vertex 1.16134 2.0861 2.53138 + endloop + endfacet + facet normal 0.19899 0.234982 0.951413 + outer loop + vertex 1.15956 2.08904 2.53103 + vertex 1.16134 2.0861 2.53138 + vertex 1.16383 2.0894 2.53005 + endloop + endfacet + facet normal 0.199539 0.230885 0.952301 + outer loop + vertex 1.15956 2.08904 2.53103 + vertex 1.16383 2.0894 2.53005 + vertex 1.15936 2.09365 2.52996 + endloop + endfacet + facet normal 0.201008 0.230878 0.951993 + outer loop + vertex 1.15956 2.08904 2.53103 + vertex 1.15936 2.09365 2.52996 + vertex 1.15642 2.09052 2.53134 + endloop + endfacet + facet normal 0.20192 0.232961 0.951292 + outer loop + vertex 1.15642 2.09052 2.53134 + vertex 1.15667 2.08597 2.53239 + vertex 1.15956 2.08904 2.53103 + endloop + endfacet + facet normal 0.200569 0.232953 0.95158 + outer loop + vertex 1.15642 2.09052 2.53134 + vertex 1.15167 2.09072 2.53229 + vertex 1.15667 2.08597 2.53239 + endloop + endfacet + facet normal 0.200592 0.228869 0.952566 + outer loop + vertex 1.15642 2.09052 2.53134 + vertex 1.15463 2.09366 2.53096 + vertex 1.15167 2.09072 2.53229 + endloop + endfacet + facet normal 0.202676 0.226796 0.952621 + outer loop + vertex 1.15131 2.09541 2.53125 + vertex 1.15167 2.09072 2.53229 + vertex 1.15463 2.09366 2.53096 + endloop + endfacet + facet normal 0.204085 0.229628 0.951641 + outer loop + vertex 1.15463 2.09366 2.53096 + vertex 1.15424 2.09834 2.52991 + vertex 1.15131 2.09541 2.53125 + endloop + endfacet + facet normal 0.205919 0.227817 0.951681 + outer loop + vertex 1.14948 2.09865 2.53087 + vertex 1.15131 2.09541 2.53125 + vertex 1.15424 2.09834 2.52991 + endloop + endfacet + facet normal 0.205971 0.230974 0.950909 + outer loop + vertex 1.14948 2.09865 2.53087 + vertex 1.15424 2.09834 2.52991 + vertex 1.14921 2.10321 2.52982 + endloop + endfacet + facet normal 0.221574 0.231084 0.947368 + outer loop + vertex 1.14948 2.09865 2.53087 + vertex 1.14921 2.10321 2.52982 + vertex 1.14625 2.1005 2.53117 + endloop + endfacet + facet normal 0.217715 0.223887 0.949987 + outer loop + vertex 1.14625 2.1005 2.53117 + vertex 1.14656 2.0958 2.53221 + vertex 1.14948 2.09865 2.53087 + endloop + endfacet + facet normal 0.251577 0.224231 0.941504 + outer loop + vertex 1.14625 2.1005 2.53117 + vertex 1.14169 2.10099 2.53227 + vertex 1.14656 2.0958 2.53221 + endloop + endfacet + facet normal 0.230291 0.204143 0.951468 + outer loop + vertex 1.14169 2.10099 2.53227 + vertex 1.14179 2.09615 2.53329 + vertex 1.14656 2.0958 2.53221 + endloop + endfacet + facet normal 0.230234 0.201614 0.952021 + outer loop + vertex 1.14373 2.09279 2.53353 + vertex 1.14656 2.0958 2.53221 + vertex 1.14179 2.09615 2.53329 + endloop + endfacet + facet normal 0.24712 0.210951 0.945744 + outer loop + vertex 1.14373 2.09279 2.53353 + vertex 1.14179 2.09615 2.53329 + vertex 1.1397 2.0927 2.5346 + endloop + endfacet + facet normal 0.277609 0.190856 0.941545 + outer loop + vertex 1.1397 2.0927 2.5346 + vertex 1.14179 2.09615 2.53329 + vertex 1.1377 2.09821 2.53408 + endloop + endfacet + facet normal 0.214866 0.216187 0.952416 + outer loop + vertex 1.14692 2.09104 2.53321 + vertex 1.14656 2.0958 2.53221 + vertex 1.14373 2.09279 2.53353 + endloop + endfacet + facet normal 0.216785 0.219911 0.951128 + outer loop + vertex 1.14406 2.0881 2.53454 + vertex 1.14692 2.09104 2.53321 + vertex 1.14373 2.09279 2.53353 + endloop + endfacet + facet normal 0.252098 0.235342 0.938648 + outer loop + vertex 1.14625 2.1005 2.53117 + vertex 1.14464 2.10365 2.53081 + vertex 1.14169 2.10099 2.53227 + endloop + endfacet + facet normal 0.228049 0.224068 0.947516 + outer loop + vertex 1.14464 2.10365 2.53081 + vertex 1.14625 2.1005 2.53117 + vertex 1.14921 2.10321 2.52982 + endloop + endfacet + facet normal 0.228116 0.225606 0.947135 + outer loop + vertex 1.14464 2.10365 2.53081 + vertex 1.14921 2.10321 2.52982 + vertex 1.1448 2.10775 2.5298 + endloop + endfacet + facet normal 0.245229 0.242217 0.938719 + outer loop + vertex 1.1448 2.10775 2.5298 + vertex 1.14921 2.10321 2.52982 + vertex 1.14883 2.10777 2.52874 + endloop + endfacet + facet normal 0.245379 0.240043 0.939238 + outer loop + vertex 1.14883 2.10777 2.52874 + vertex 1.14685 2.11108 2.52841 + vertex 1.1448 2.10775 2.5298 + endloop + endfacet + facet normal 0.278642 0.217932 0.935342 + outer loop + vertex 1.1448 2.10775 2.5298 + vertex 1.14685 2.11108 2.52841 + vertex 1.14276 2.11319 2.52914 + endloop + endfacet + facet normal 0.281419 0.224128 0.933044 + outer loop + vertex 1.14685 2.11108 2.52841 + vertex 1.14672 2.1159 2.52729 + vertex 1.14276 2.11319 2.52914 + endloop + endfacet + facet normal 0.232322 0.225828 0.946059 + outer loop + vertex 1.14672 2.1159 2.52729 + vertex 1.14685 2.11108 2.52841 + vertex 1.15159 2.11074 2.52733 + endloop + endfacet + facet normal 0.261399 0.253188 0.931432 + outer loop + vertex 1.15126 2.11535 2.52617 + vertex 1.14672 2.1159 2.52729 + vertex 1.15159 2.11074 2.52733 + endloop + endfacet + facet normal 0.220712 0.252893 0.941983 + outer loop + vertex 1.15126 2.11535 2.52617 + vertex 1.15159 2.11074 2.52733 + vertex 1.15448 2.11356 2.52589 + endloop + endfacet + facet normal 0.218238 0.248146 0.94382 + outer loop + vertex 1.15448 2.11356 2.52589 + vertex 1.15421 2.1181 2.52476 + vertex 1.15126 2.11535 2.52617 + endloop + endfacet + facet normal 0.231288 0.234385 0.944229 + outer loop + vertex 1.14966 2.11853 2.52577 + vertex 1.15126 2.11535 2.52617 + vertex 1.15421 2.1181 2.52476 + endloop + endfacet + facet normal 0.230401 0.212227 0.949671 + outer loop + vertex 1.14966 2.11853 2.52577 + vertex 1.15421 2.1181 2.52476 + vertex 1.14986 2.12275 2.52478 + endloop + endfacet + facet normal 0.260692 0.24058 0.934966 + outer loop + vertex 1.14986 2.12275 2.52478 + vertex 1.15421 2.1181 2.52476 + vertex 1.15386 2.12272 2.52367 + endloop + endfacet + facet normal 0.262128 0.21485 0.940813 + outer loop + vertex 1.15386 2.12272 2.52367 + vertex 1.15195 2.12617 2.52342 + vertex 1.14986 2.12275 2.52478 + endloop + endfacet + facet normal 0.245817 0.206265 0.947116 + outer loop + vertex 1.15386 2.12272 2.52367 + vertex 1.15664 2.12576 2.52229 + vertex 1.15195 2.12617 2.52342 + endloop + endfacet + facet normal 0.245239 0.190233 0.950615 + outer loop + vertex 1.15191 2.13113 2.52244 + vertex 1.15195 2.12617 2.52342 + vertex 1.15664 2.12576 2.52229 + endloop + endfacet + facet normal 0.285583 0.226279 0.931257 + outer loop + vertex 1.15639 2.1305 2.52121 + vertex 1.15191 2.13113 2.52244 + vertex 1.15664 2.12576 2.52229 + endloop + endfacet + facet normal 0.243601 0.22674 0.942999 + outer loop + vertex 1.15639 2.1305 2.52121 + vertex 1.15664 2.12576 2.52229 + vertex 1.15951 2.12859 2.52087 + endloop + endfacet + facet normal 0.239976 0.220365 0.945437 + outer loop + vertex 1.15951 2.12859 2.52087 + vertex 1.15933 2.13323 2.51983 + vertex 1.15639 2.1305 2.52121 + endloop + endfacet + facet normal 0.21558 0.220702 0.951218 + outer loop + vertex 1.15951 2.12859 2.52087 + vertex 1.1641 2.12837 2.51988 + vertex 1.15933 2.13323 2.51983 + endloop + endfacet + facet normal 0.238392 0.242983 0.940281 + outer loop + vertex 1.15933 2.13323 2.51983 + vertex 1.1641 2.12837 2.51988 + vertex 1.16384 2.13287 2.51878 + endloop + endfacet + facet normal 0.238164 0.231908 0.943131 + outer loop + vertex 1.16384 2.13287 2.51878 + vertex 1.16212 2.1361 2.51842 + vertex 1.15933 2.13323 2.51983 + endloop + endfacet + facet normal 0.255201 0.215114 0.942655 + outer loop + vertex 1.15933 2.13323 2.51983 + vertex 1.16212 2.1361 2.51842 + vertex 1.15904 2.1379 2.51884 + endloop + endfacet + facet normal 0.281756 0.215149 0.935053 + outer loop + vertex 1.15503 2.13794 2.52004 + vertex 1.15933 2.13323 2.51983 + vertex 1.15904 2.1379 2.51884 + endloop + endfacet + facet normal 0.281849 0.213473 0.935409 + outer loop + vertex 1.15904 2.1379 2.51884 + vertex 1.1571 2.1412 2.51868 + vertex 1.15503 2.13794 2.52004 + endloop + endfacet + facet normal 0.264659 0.22533 0.937647 + outer loop + vertex 1.15503 2.13794 2.52004 + vertex 1.1571 2.1412 2.51868 + vertex 1.15263 2.14316 2.51946 + endloop + endfacet + facet normal 0.273422 0.248622 0.929208 + outer loop + vertex 1.1571 2.1412 2.51868 + vertex 1.15707 2.14538 2.51757 + vertex 1.15263 2.14316 2.51946 + endloop + endfacet + facet normal 0.268345 0.248953 0.930598 + outer loop + vertex 1.15707 2.14538 2.51757 + vertex 1.1571 2.1412 2.51868 + vertex 1.16173 2.14082 2.51744 + endloop + endfacet + facet normal 0.259073 0.239345 0.935732 + outer loop + vertex 1.16118 2.14541 2.51642 + vertex 1.15707 2.14538 2.51757 + vertex 1.16173 2.14082 2.51744 + endloop + endfacet + facet normal 0.248347 0.238738 0.938791 + outer loop + vertex 1.16118 2.14541 2.51642 + vertex 1.16173 2.14082 2.51744 + vertex 1.16438 2.14373 2.516 + endloop + endfacet + facet normal 0.271617 0.288003 0.918302 + outer loop + vertex 1.16438 2.14373 2.516 + vertex 1.16366 2.14816 2.51482 + vertex 1.16118 2.14541 2.51642 + endloop + endfacet + facet normal 0.264188 0.294745 0.91833 + outer loop + vertex 1.15916 2.14821 2.5161 + vertex 1.16118 2.14541 2.51642 + vertex 1.16366 2.14816 2.51482 + endloop + endfacet + facet normal 0.251542 0.428176 0.867981 + outer loop + vertex 1.15916 2.14821 2.5161 + vertex 1.16366 2.14816 2.51482 + vertex 1.1586 2.15125 2.51477 + endloop + endfacet + facet normal 0.225117 0.284085 0.931997 + outer loop + vertex 1.16438 2.14373 2.516 + vertex 1.16904 2.1435 2.51494 + vertex 1.16366 2.14816 2.51482 + endloop + endfacet + facet normal 0.210919 0.267904 0.940075 + outer loop + vertex 1.16366 2.14816 2.51482 + vertex 1.16904 2.1435 2.51494 + vertex 1.16864 2.14791 2.51378 + endloop + endfacet + facet normal 0.208849 0.363372 0.907933 + outer loop + vertex 1.16864 2.14791 2.51378 + vertex 1.16668 2.15135 2.51285 + vertex 1.16366 2.14816 2.51482 + endloop + endfacet + facet normal 0.166653 0.39933 0.901533 + outer loop + vertex 1.16366 2.14816 2.51482 + vertex 1.16668 2.15135 2.51285 + vertex 1.16197 2.15278 2.51309 + endloop + endfacet + facet normal 0.183757 0.351714 0.917895 + outer loop + vertex 1.16864 2.14791 2.51378 + vertex 1.17182 2.14997 2.51235 + vertex 1.16668 2.15135 2.51285 + endloop + endfacet + facet normal 0.212512 0.312821 0.925733 + outer loop + vertex 1.17197 2.1463 2.51356 + vertex 1.17182 2.14997 2.51235 + vertex 1.16864 2.14791 2.51378 + endloop + endfacet + facet normal 0.201651 0.313141 0.928051 + outer loop + vertex 1.17182 2.14997 2.51235 + vertex 1.17197 2.1463 2.51356 + vertex 1.17619 2.14657 2.51255 + endloop + endfacet + facet normal 0.193363 0.302808 0.93323 + outer loop + vertex 1.17594 2.15047 2.51134 + vertex 1.17182 2.14997 2.51235 + vertex 1.17619 2.14657 2.51255 + endloop + endfacet + facet normal 0.198361 0.3028 0.932183 + outer loop + vertex 1.17594 2.15047 2.51134 + vertex 1.17619 2.14657 2.51255 + vertex 1.17983 2.14907 2.51097 + endloop + endfacet + facet normal 0.22628 0.391061 0.892115 + outer loop + vertex 1.17983 2.14907 2.51097 + vertex 1.17796 2.15328 2.50959 + vertex 1.17594 2.15047 2.51134 + endloop + endfacet + facet normal 0.187835 0.378635 0.906285 + outer loop + vertex 1.17796 2.15328 2.50959 + vertex 1.17983 2.14907 2.51097 + vertex 1.1832 2.15126 2.50935 + endloop + endfacet + facet normal 0.216939 0.340176 0.914996 + outer loop + vertex 1.17983 2.14907 2.51097 + vertex 1.18378 2.14764 2.51056 + vertex 1.1832 2.15126 2.50935 + endloop + endfacet + facet normal 0.217596 0.340222 0.914823 + outer loop + vertex 1.18378 2.14764 2.51056 + vertex 1.18839 2.14793 2.50935 + vertex 1.1832 2.15126 2.50935 + endloop + endfacet + facet normal 0.225553 0.352606 0.908182 + outer loop + vertex 1.1832 2.15126 2.50935 + vertex 1.18839 2.14793 2.50935 + vertex 1.18703 2.15316 2.50766 + endloop + endfacet + facet normal 0.17937 0.34482 0.921371 + outer loop + vertex 1.18839 2.14793 2.50935 + vertex 1.19159 2.15138 2.50744 + vertex 1.18703 2.15316 2.50766 + endloop + endfacet + facet normal 0.203343 0.324079 0.923918 + outer loop + vertex 1.19338 2.14767 2.50835 + vertex 1.19159 2.15138 2.50744 + vertex 1.18839 2.14793 2.50935 + endloop + endfacet + facet normal 0.204051 0.261399 0.943416 + outer loop + vertex 1.18839 2.14793 2.50935 + vertex 1.19376 2.14307 2.50954 + vertex 1.19338 2.14767 2.50835 + endloop + endfacet + facet normal 0.201181 0.26133 0.944051 + outer loop + vertex 1.19376 2.14307 2.50954 + vertex 1.19677 2.14576 2.50815 + vertex 1.19338 2.14767 2.50835 + endloop + endfacet + facet normal 0.217411 0.291414 0.931563 + outer loop + vertex 1.19677 2.14576 2.50815 + vertex 1.19666 2.14965 2.50696 + vertex 1.19338 2.14767 2.50835 + endloop + endfacet + facet normal 0.213392 0.291576 0.932442 + outer loop + vertex 1.19666 2.14965 2.50696 + vertex 1.19677 2.14576 2.50815 + vertex 1.20146 2.14545 2.50718 + endloop + endfacet + facet normal 0.205614 0.28291 0.936849 + outer loop + vertex 1.20079 2.14986 2.50599 + vertex 1.19666 2.14965 2.50696 + vertex 1.20146 2.14545 2.50718 + endloop + endfacet + facet normal 0.201191 0.282525 0.937924 + outer loop + vertex 1.20079 2.14986 2.50599 + vertex 1.20146 2.14545 2.50718 + vertex 1.20406 2.14839 2.50573 + endloop + endfacet + facet normal 0.234058 0.361749 0.902416 + outer loop + vertex 1.20406 2.14839 2.50573 + vertex 1.20328 2.15253 2.50428 + vertex 1.20079 2.14986 2.50599 + endloop + endfacet + facet normal 0.211614 0.359714 0.908749 + outer loop + vertex 1.20406 2.14839 2.50573 + vertex 1.20855 2.14835 2.5047 + vertex 1.20328 2.15253 2.50428 + endloop + endfacet + facet normal 0.187172 0.330545 0.925044 + outer loop + vertex 1.20328 2.15253 2.50428 + vertex 1.20855 2.14835 2.5047 + vertex 1.20748 2.15214 2.50356 + endloop + endfacet + facet normal 0.21235 0.335421 0.917824 + outer loop + vertex 1.20855 2.14835 2.5047 + vertex 1.21126 2.152 2.50274 + vertex 1.20748 2.15214 2.50356 + endloop + endfacet + facet normal 0.20269 0.342407 0.917428 + outer loop + vertex 1.21342 2.14811 2.50372 + vertex 1.21126 2.152 2.50274 + vertex 1.20855 2.14835 2.5047 + endloop + endfacet + facet normal 0.203852 0.275023 0.939578 + outer loop + vertex 1.20855 2.14835 2.5047 + vertex 1.21337 2.14401 2.50493 + vertex 1.21342 2.14811 2.50372 + endloop + endfacet + facet normal 0.198932 0.275361 0.940533 + outer loop + vertex 1.21337 2.14401 2.50493 + vertex 1.2169 2.14599 2.5036 + vertex 1.21342 2.14811 2.50372 + endloop + endfacet + facet normal 0.205876 0.26414 0.942255 + outer loop + vertex 1.21895 2.14179 2.50433 + vertex 1.2169 2.14599 2.5036 + vertex 1.21337 2.14401 2.50493 + endloop + endfacet + facet normal 0.202551 0.254881 0.94552 + outer loop + vertex 1.21337 2.14401 2.50493 + vertex 1.21507 2.1392 2.50586 + vertex 1.21895 2.14179 2.50433 + endloop + endfacet + facet normal 0.19979 0.258737 0.945061 + outer loop + vertex 1.21507 2.1392 2.50586 + vertex 1.21904 2.13763 2.50545 + vertex 1.21895 2.14179 2.50433 + endloop + endfacet + facet normal 0.197267 0.258817 0.945568 + outer loop + vertex 1.21904 2.13763 2.50545 + vertex 1.22367 2.13782 2.50443 + vertex 1.21895 2.14179 2.50433 + endloop + endfacet + facet normal 0.201076 0.263289 0.943529 + outer loop + vertex 1.21895 2.14179 2.50433 + vertex 1.22367 2.13782 2.50443 + vertex 1.22271 2.1419 2.5035 + endloop + endfacet + facet normal 0.200489 0.270082 0.941732 + outer loop + vertex 1.22271 2.1419 2.5035 + vertex 1.22168 2.1459 2.50257 + vertex 1.21895 2.14179 2.50433 + endloop + endfacet + facet normal 0.200415 0.270068 0.941752 + outer loop + vertex 1.22168 2.1459 2.50257 + vertex 1.22271 2.1419 2.5035 + vertex 1.22644 2.14199 2.50268 + endloop + endfacet + facet normal 0.201525 0.271401 0.941132 + outer loop + vertex 1.22614 2.14616 2.50154 + vertex 1.22168 2.1459 2.50257 + vertex 1.22644 2.14199 2.50268 + endloop + endfacet + facet normal 0.204679 0.271436 0.940441 + outer loop + vertex 1.22614 2.14616 2.50154 + vertex 1.22644 2.14199 2.50268 + vertex 1.23017 2.14457 2.50112 + endloop + endfacet + facet normal 0.221114 0.317967 0.921958 + outer loop + vertex 1.23017 2.14457 2.50112 + vertex 1.22803 2.14925 2.50002 + vertex 1.22614 2.14616 2.50154 + endloop + endfacet + facet normal 0.217295 0.320348 0.922041 + outer loop + vertex 1.22408 2.14891 2.50107 + vertex 1.22614 2.14616 2.50154 + vertex 1.22803 2.14925 2.50002 + endloop + endfacet + facet normal 0.20223 0.404632 0.891838 + outer loop + vertex 1.22408 2.14891 2.50107 + vertex 1.22803 2.14925 2.50002 + vertex 1.22327 2.15272 2.49953 + endloop + endfacet + facet normal 0.227564 0.407079 0.884591 + outer loop + vertex 1.22408 2.14891 2.50107 + vertex 1.22327 2.15272 2.49953 + vertex 1.22096 2.15015 2.5013 + endloop + endfacet + facet normal 0.192626 0.310365 0.930897 + outer loop + vertex 1.22096 2.15015 2.5013 + vertex 1.22168 2.1459 2.50257 + vertex 1.22408 2.14891 2.50107 + endloop + endfacet + facet normal 0.207734 0.311812 0.927157 + outer loop + vertex 1.22096 2.15015 2.5013 + vertex 1.21683 2.14994 2.5023 + vertex 1.22168 2.1459 2.50257 + endloop + endfacet + facet normal 0.205912 0.309703 0.92827 + outer loop + vertex 1.21683 2.14994 2.5023 + vertex 1.2169 2.14599 2.5036 + vertex 1.22168 2.1459 2.50257 + endloop + endfacet + facet normal 0.218971 0.309019 0.925505 + outer loop + vertex 1.2169 2.14599 2.5036 + vertex 1.21683 2.14994 2.5023 + vertex 1.21342 2.14811 2.50372 + endloop + endfacet + facet normal 0.183587 0.381081 0.906131 + outer loop + vertex 1.22327 2.15272 2.49953 + vertex 1.22803 2.14925 2.50002 + vertex 1.22731 2.15243 2.49883 + endloop + endfacet + facet normal 0.216664 0.385232 0.897024 + outer loop + vertex 1.22803 2.14925 2.50002 + vertex 1.23113 2.15222 2.498 + vertex 1.22731 2.15243 2.49883 + endloop + endfacet + facet normal 0.204143 0.272155 0.94035 + outer loop + vertex 1.23198 2.13979 2.50211 + vertex 1.23017 2.14457 2.50112 + vertex 1.22644 2.14199 2.50268 + endloop + endfacet + facet normal 0.201488 0.264772 0.943026 + outer loop + vertex 1.22853 2.13772 2.50343 + vertex 1.23198 2.13979 2.50211 + vertex 1.22644 2.14199 2.50268 + endloop + endfacet + facet normal 0.199815 0.264051 0.943584 + outer loop + vertex 1.22853 2.13772 2.50343 + vertex 1.22644 2.14199 2.50268 + vertex 1.22367 2.13782 2.50443 + endloop + endfacet + facet normal 0.199447 0.274044 0.940809 + outer loop + vertex 1.22367 2.13782 2.50443 + vertex 1.22874 2.13322 2.5047 + vertex 1.22853 2.13772 2.50343 + endloop + endfacet + facet normal 0.200976 0.274026 0.940488 + outer loop + vertex 1.22874 2.13322 2.5047 + vertex 1.23182 2.13583 2.50328 + vertex 1.22853 2.13772 2.50343 + endloop + endfacet + facet normal 0.197009 0.278455 0.940027 + outer loop + vertex 1.23342 2.13294 2.5038 + vertex 1.23182 2.13583 2.50328 + vertex 1.22874 2.13322 2.5047 + endloop + endfacet + facet normal 0.197018 0.28403 0.938355 + outer loop + vertex 1.22874 2.13322 2.5047 + vertex 1.23333 2.12903 2.505 + vertex 1.23342 2.13294 2.5038 + endloop + endfacet + facet normal 0.193732 0.284289 0.938961 + outer loop + vertex 1.23333 2.12903 2.505 + vertex 1.23669 2.1312 2.50365 + vertex 1.23342 2.13294 2.5038 + endloop + endfacet + facet normal 0.192403 0.281702 0.940013 + outer loop + vertex 1.23669 2.1312 2.50365 + vertex 1.23644 2.13568 2.50236 + vertex 1.23342 2.13294 2.5038 + endloop + endfacet + facet normal 0.192609 0.281701 0.939971 + outer loop + vertex 1.23644 2.13568 2.50236 + vertex 1.23669 2.1312 2.50365 + vertex 1.2412 2.13159 2.50261 + endloop + endfacet + facet normal 0.195862 0.285373 0.93819 + outer loop + vertex 1.24104 2.13581 2.50136 + vertex 1.23644 2.13568 2.50236 + vertex 1.2412 2.13159 2.50261 + endloop + endfacet + facet normal 0.191534 0.285471 0.939053 + outer loop + vertex 1.24104 2.13581 2.50136 + vertex 1.2412 2.13159 2.50261 + vertex 1.24501 2.13438 2.50099 + endloop + endfacet + facet normal 0.189239 0.278418 0.941633 + outer loop + vertex 1.24501 2.13438 2.50099 + vertex 1.24334 2.13902 2.49995 + vertex 1.24104 2.13581 2.50136 + endloop + endfacet + facet normal 0.193048 0.275706 0.941657 + outer loop + vertex 1.23918 2.13866 2.50091 + vertex 1.24104 2.13581 2.50136 + vertex 1.24334 2.13902 2.49995 + endloop + endfacet + facet normal 0.193509 0.272574 0.942474 + outer loop + vertex 1.23918 2.13866 2.50091 + vertex 1.24334 2.13902 2.49995 + vertex 1.23889 2.143 2.49971 + endloop + endfacet + facet normal 0.199517 0.272633 0.941204 + outer loop + vertex 1.23918 2.13866 2.50091 + vertex 1.23889 2.143 2.49971 + vertex 1.23615 2.13998 2.50117 + endloop + endfacet + facet normal 0.200255 0.27446 0.940515 + outer loop + vertex 1.23615 2.13998 2.50117 + vertex 1.23644 2.13568 2.50236 + vertex 1.23918 2.13866 2.50091 + endloop + endfacet + facet normal 0.200744 0.274464 0.94041 + outer loop + vertex 1.23615 2.13998 2.50117 + vertex 1.23198 2.13979 2.50211 + vertex 1.23644 2.13568 2.50236 + endloop + endfacet + facet normal 0.19617 0.26964 0.942768 + outer loop + vertex 1.23198 2.13979 2.50211 + vertex 1.23182 2.13583 2.50328 + vertex 1.23644 2.13568 2.50236 + endloop + endfacet + facet normal 0.201033 0.271752 0.941136 + outer loop + vertex 1.23615 2.13998 2.50117 + vertex 1.23425 2.14291 2.50073 + vertex 1.23198 2.13979 2.50211 + endloop + endfacet + facet normal 0.200721 0.271567 0.941256 + outer loop + vertex 1.23425 2.14291 2.50073 + vertex 1.23615 2.13998 2.50117 + vertex 1.23889 2.143 2.49971 + endloop + endfacet + facet normal 0.198759 0.295947 0.934297 + outer loop + vertex 1.23425 2.14291 2.50073 + vertex 1.23889 2.143 2.49971 + vertex 1.23396 2.14722 2.49942 + endloop + endfacet + facet normal 0.194899 0.274086 0.941749 + outer loop + vertex 1.23889 2.143 2.49971 + vertex 1.24334 2.13902 2.49995 + vertex 1.24349 2.14298 2.49877 + endloop + endfacet + facet normal 0.194316 0.284429 0.938798 + outer loop + vertex 1.24349 2.14298 2.49877 + vertex 1.24186 2.14577 2.49826 + vertex 1.23889 2.143 2.49971 + endloop + endfacet + facet normal 0.187609 0.291239 0.938074 + outer loop + vertex 1.23889 2.143 2.49971 + vertex 1.24186 2.14577 2.49826 + vertex 1.23862 2.14735 2.49842 + endloop + endfacet + facet normal 0.207593 0.334301 0.919319 + outer loop + vertex 1.24186 2.14577 2.49826 + vertex 1.24165 2.14945 2.49697 + vertex 1.23862 2.14735 2.49842 + endloop + endfacet + facet normal 0.196453 0.334498 0.921693 + outer loop + vertex 1.24165 2.14945 2.49697 + vertex 1.24186 2.14577 2.49826 + vertex 1.24632 2.14576 2.49731 + endloop + endfacet + facet normal 0.199509 0.287104 0.936892 + outer loop + vertex 1.24349 2.14298 2.49877 + vertex 1.24632 2.14576 2.49731 + vertex 1.24186 2.14577 2.49826 + endloop + endfacet + facet normal 0.198646 0.287946 0.936817 + outer loop + vertex 1.2467 2.14134 2.49859 + vertex 1.24632 2.14576 2.49731 + vertex 1.24349 2.14298 2.49877 + endloop + endfacet + facet normal 0.18761 0.287682 0.939171 + outer loop + vertex 1.24632 2.14576 2.49731 + vertex 1.2467 2.14134 2.49859 + vertex 1.25119 2.14171 2.49758 + endloop + endfacet + facet normal 0.196606 0.298168 0.934046 + outer loop + vertex 1.25082 2.14591 2.49632 + vertex 1.24632 2.14576 2.49731 + vertex 1.25119 2.14171 2.49758 + endloop + endfacet + facet normal 0.197078 0.298178 0.933943 + outer loop + vertex 1.25082 2.14591 2.49632 + vertex 1.25119 2.14171 2.49758 + vertex 1.25493 2.1443 2.49596 + endloop + endfacet + facet normal 0.223212 0.372011 0.900991 + outer loop + vertex 1.25493 2.1443 2.49596 + vertex 1.25261 2.14886 2.49465 + vertex 1.25082 2.14591 2.49632 + endloop + endfacet + facet normal 0.233104 0.365992 0.900951 + outer loop + vertex 1.2486 2.14858 2.49581 + vertex 1.25082 2.14591 2.49632 + vertex 1.25261 2.14886 2.49465 + endloop + endfacet + facet normal 0.216833 0.45226 0.865127 + outer loop + vertex 1.2486 2.14858 2.49581 + vertex 1.25261 2.14886 2.49465 + vertex 1.24727 2.15202 2.49434 + endloop + endfacet + facet normal 0.24129 0.490875 0.837151 + outer loop + vertex 1.24727 2.15202 2.49434 + vertex 1.25261 2.14886 2.49465 + vertex 1.25134 2.15293 2.49264 + endloop + endfacet + facet normal 0.213492 0.487032 0.846889 + outer loop + vertex 1.25261 2.14886 2.49465 + vertex 1.25636 2.15103 2.49246 + vertex 1.25134 2.15293 2.49264 + endloop + endfacet + facet normal 0.200285 0.362937 0.910035 + outer loop + vertex 1.25261 2.14886 2.49465 + vertex 1.25493 2.1443 2.49596 + vertex 1.25873 2.14657 2.49422 + endloop + endfacet + facet normal 0.205621 0.355377 0.911827 + outer loop + vertex 1.25493 2.1443 2.49596 + vertex 1.25904 2.14271 2.49566 + vertex 1.25873 2.14657 2.49422 + endloop + endfacet + facet normal 0.193861 0.35537 0.914402 + outer loop + vertex 1.25904 2.14271 2.49566 + vertex 1.26346 2.1428 2.49468 + vertex 1.25873 2.14657 2.49422 + endloop + endfacet + facet normal 0.195061 0.35678 0.913597 + outer loop + vertex 1.25873 2.14657 2.49422 + vertex 1.26346 2.1428 2.49468 + vertex 1.26266 2.1463 2.49349 + endloop + endfacet + facet normal 0.201707 0.357694 0.911795 + outer loop + vertex 1.26346 2.1428 2.49468 + vertex 1.26652 2.14609 2.49272 + vertex 1.26266 2.1463 2.49349 + endloop + endfacet + facet normal 0.190885 0.366962 0.910441 + outer loop + vertex 1.26733 2.14267 2.49393 + vertex 1.26652 2.14609 2.49272 + vertex 1.26346 2.1428 2.49468 + endloop + endfacet + facet normal 0.19267 0.318391 0.928173 + outer loop + vertex 1.26346 2.1428 2.49468 + vertex 1.26805 2.13921 2.49496 + vertex 1.26733 2.14267 2.49393 + endloop + endfacet + facet normal 0.197889 0.319075 0.926839 + outer loop + vertex 1.26805 2.13921 2.49496 + vertex 1.27114 2.14254 2.49316 + vertex 1.26733 2.14267 2.49393 + endloop + endfacet + facet normal 0.193254 0.323141 0.926409 + outer loop + vertex 1.27382 2.13737 2.4944 + vertex 1.27114 2.14254 2.49316 + vertex 1.26805 2.13921 2.49496 + endloop + endfacet + facet normal 0.187134 0.301279 0.934993 + outer loop + vertex 1.26805 2.13921 2.49496 + vertex 1.27002 2.13458 2.49606 + vertex 1.27382 2.13737 2.4944 + endloop + endfacet + facet normal 0.18678 0.301719 0.934922 + outer loop + vertex 1.27002 2.13458 2.49606 + vertex 1.27397 2.1332 2.49572 + vertex 1.27382 2.13737 2.4944 + endloop + endfacet + facet normal 0.181246 0.301859 0.935966 + outer loop + vertex 1.27397 2.1332 2.49572 + vertex 1.27823 2.13362 2.49476 + vertex 1.27382 2.13737 2.4944 + endloop + endfacet + facet normal 0.182043 0.302751 0.935523 + outer loop + vertex 1.27382 2.13737 2.4944 + vertex 1.27823 2.13362 2.49476 + vertex 1.27846 2.13749 2.49346 + endloop + endfacet + facet normal 0.180509 0.319795 0.930133 + outer loop + vertex 1.27846 2.13749 2.49346 + vertex 1.27658 2.14102 2.49261 + vertex 1.27382 2.13737 2.4944 + endloop + endfacet + facet normal 0.179321 0.319259 0.930547 + outer loop + vertex 1.27846 2.13749 2.49346 + vertex 1.28175 2.13954 2.49212 + vertex 1.27658 2.14102 2.49261 + endloop + endfacet + facet normal 0.183156 0.313824 0.931648 + outer loop + vertex 1.28176 2.13568 2.49342 + vertex 1.28175 2.13954 2.49212 + vertex 1.27846 2.13749 2.49346 + endloop + endfacet + facet normal 0.176244 0.314223 0.932846 + outer loop + vertex 1.28175 2.13954 2.49212 + vertex 1.28176 2.13568 2.49342 + vertex 1.28651 2.13571 2.49251 + endloop + endfacet + facet normal 0.177145 0.300903 0.937057 + outer loop + vertex 1.28374 2.13173 2.49431 + vertex 1.28651 2.13571 2.49251 + vertex 1.28176 2.13568 2.49342 + endloop + endfacet + facet normal 0.17856 0.301511 0.936594 + outer loop + vertex 1.28374 2.13173 2.49431 + vertex 1.28176 2.13568 2.49342 + vertex 1.27823 2.13362 2.49476 + endloop + endfacet + facet normal 0.177793 0.29905 0.937528 + outer loop + vertex 1.27823 2.13362 2.49476 + vertex 1.2799 2.12914 2.49587 + vertex 1.28374 2.13173 2.49431 + endloop + endfacet + facet normal 0.177846 0.298978 0.937541 + outer loop + vertex 1.2799 2.12914 2.49587 + vertex 1.2839 2.12774 2.49556 + vertex 1.28374 2.13173 2.49431 + endloop + endfacet + facet normal 0.176265 0.299005 0.937831 + outer loop + vertex 1.2839 2.12774 2.49556 + vertex 1.28848 2.12801 2.49461 + vertex 1.28374 2.13173 2.49431 + endloop + endfacet + facet normal 0.176194 0.298919 0.937872 + outer loop + vertex 1.28374 2.13173 2.49431 + vertex 1.28848 2.12801 2.49461 + vertex 1.28752 2.13188 2.49356 + endloop + endfacet + facet normal 0.175766 0.298841 0.937977 + outer loop + vertex 1.28848 2.12801 2.49461 + vertex 1.29129 2.13202 2.49281 + vertex 1.28752 2.13188 2.49356 + endloop + endfacet + facet normal 0.175497 0.301668 0.937122 + outer loop + vertex 1.28651 2.13571 2.49251 + vertex 1.28752 2.13188 2.49356 + vertex 1.29129 2.13202 2.49281 + endloop + endfacet + facet normal 0.177289 0.303897 0.936064 + outer loop + vertex 1.29101 2.13599 2.49157 + vertex 1.28651 2.13571 2.49251 + vertex 1.29129 2.13202 2.49281 + endloop + endfacet + facet normal 0.178728 0.303909 0.935786 + outer loop + vertex 1.29101 2.13599 2.49157 + vertex 1.29129 2.13202 2.49281 + vertex 1.29505 2.13458 2.49126 + endloop + endfacet + facet normal 0.186967 0.329704 0.925386 + outer loop + vertex 1.29505 2.13458 2.49126 + vertex 1.29298 2.13913 2.49005 + vertex 1.29101 2.13599 2.49157 + endloop + endfacet + facet normal 0.189481 0.328146 0.925428 + outer loop + vertex 1.28894 2.13871 2.49103 + vertex 1.29101 2.13599 2.49157 + vertex 1.29298 2.13913 2.49005 + endloop + endfacet + facet normal 0.181552 0.370478 0.910925 + outer loop + vertex 1.28894 2.13871 2.49103 + vertex 1.29298 2.13913 2.49005 + vertex 1.28813 2.14279 2.48953 + endloop + endfacet + facet normal 0.195835 0.371996 0.907341 + outer loop + vertex 1.28894 2.13871 2.49103 + vertex 1.28813 2.14279 2.48953 + vertex 1.28582 2.13994 2.4912 + endloop + endfacet + facet normal 0.176091 0.318128 0.931551 + outer loop + vertex 1.28582 2.13994 2.4912 + vertex 1.28651 2.13571 2.49251 + vertex 1.28894 2.13871 2.49103 + endloop + endfacet + facet normal 0.179849 0.318486 0.93071 + outer loop + vertex 1.28582 2.13994 2.4912 + vertex 1.28175 2.13954 2.49212 + vertex 1.28651 2.13571 2.49251 + endloop + endfacet + facet normal 0.182251 0.371334 0.910437 + outer loop + vertex 1.28813 2.14279 2.48953 + vertex 1.29298 2.13913 2.49005 + vertex 1.29233 2.14244 2.48883 + endloop + endfacet + facet normal 0.179521 0.326968 0.927828 + outer loop + vertex 1.29298 2.13913 2.49005 + vertex 1.29505 2.13458 2.49126 + vertex 1.29883 2.13734 2.48955 + endloop + endfacet + facet normal 0.195117 0.384933 0.902084 + outer loop + vertex 1.29883 2.13734 2.48955 + vertex 1.29628 2.14234 2.48797 + vertex 1.29298 2.13913 2.49005 + endloop + endfacet + facet normal 0.169264 0.374713 0.911559 + outer loop + vertex 1.29883 2.13734 2.48955 + vertex 1.30152 2.14091 2.48758 + vertex 1.29628 2.14234 2.48797 + endloop + endfacet + facet normal 0.165892 0.377056 0.911213 + outer loop + vertex 1.30339 2.13759 2.48862 + vertex 1.30152 2.14091 2.48758 + vertex 1.29883 2.13734 2.48955 + endloop + endfacet + facet normal 0.167965 0.377984 0.910448 + outer loop + vertex 1.30339 2.13759 2.48862 + vertex 1.30648 2.13975 2.48715 + vertex 1.30152 2.14091 2.48758 + endloop + endfacet + facet normal 0.181232 0.36179 0.914474 + outer loop + vertex 1.30665 2.13601 2.4886 + vertex 1.30648 2.13975 2.48715 + vertex 1.30339 2.13759 2.48862 + endloop + endfacet + facet normal 0.167007 0.362117 0.917049 + outer loop + vertex 1.30648 2.13975 2.48715 + vertex 1.30665 2.13601 2.4886 + vertex 1.311 2.13653 2.4876 + endloop + endfacet + facet normal 0.174542 0.323631 0.929945 + outer loop + vertex 1.30883 2.13223 2.4895 + vertex 1.311 2.13653 2.4876 + vertex 1.30665 2.13601 2.4886 + endloop + endfacet + facet normal 0.171182 0.321982 0.931141 + outer loop + vertex 1.30883 2.13223 2.4895 + vertex 1.30665 2.13601 2.4886 + vertex 1.30331 2.13376 2.48999 + endloop + endfacet + facet normal 0.167635 0.307385 0.936703 + outer loop + vertex 1.30331 2.13376 2.48999 + vertex 1.30503 2.12941 2.49111 + vertex 1.30883 2.13223 2.4895 + endloop + endfacet + facet normal 0.1691 0.3056 0.937024 + outer loop + vertex 1.30503 2.12941 2.49111 + vertex 1.30895 2.12823 2.49079 + vertex 1.30883 2.13223 2.4895 + endloop + endfacet + facet normal 0.165597 0.305686 0.937621 + outer loop + vertex 1.30895 2.12823 2.49079 + vertex 1.31323 2.12878 2.48985 + vertex 1.30883 2.13223 2.4895 + endloop + endfacet + facet normal 0.166171 0.306385 0.937291 + outer loop + vertex 1.30883 2.13223 2.4895 + vertex 1.31323 2.12878 2.48985 + vertex 1.31335 2.13274 2.48854 + endloop + endfacet + facet normal 0.162155 0.306702 0.937891 + outer loop + vertex 1.31323 2.12878 2.48985 + vertex 1.31669 2.13104 2.48851 + vertex 1.31335 2.13274 2.48854 + endloop + endfacet + facet normal 0.170085 0.322401 0.931198 + outer loop + vertex 1.31669 2.13104 2.48851 + vertex 1.31661 2.13497 2.48717 + vertex 1.31335 2.13274 2.48854 + endloop + endfacet + facet normal 0.164014 0.322623 0.932209 + outer loop + vertex 1.31661 2.13497 2.48717 + vertex 1.31669 2.13104 2.48851 + vertex 1.32115 2.13146 2.48758 + endloop + endfacet + facet normal 0.170554 0.330587 0.928237 + outer loop + vertex 1.32077 2.13542 2.48624 + vertex 1.31661 2.13497 2.48717 + vertex 1.32115 2.13146 2.48758 + endloop + endfacet + facet normal 0.168575 0.330527 0.92862 + outer loop + vertex 1.32077 2.13542 2.48624 + vertex 1.32115 2.13146 2.48758 + vertex 1.32466 2.13406 2.48602 + endloop + endfacet + facet normal 0.189962 0.396536 0.89815 + outer loop + vertex 1.32466 2.13406 2.48602 + vertex 1.32256 2.13842 2.48454 + vertex 1.32077 2.13542 2.48624 + endloop + endfacet + facet normal 0.172201 0.390156 0.904503 + outer loop + vertex 1.32256 2.13842 2.48454 + vertex 1.32466 2.13406 2.48602 + vertex 1.32782 2.13629 2.48446 + endloop + endfacet + facet normal 0.17833 0.382832 0.906443 + outer loop + vertex 1.32466 2.13406 2.48602 + vertex 1.32856 2.13285 2.48576 + vertex 1.32782 2.13629 2.48446 + endloop + endfacet + facet normal 0.17099 0.381944 0.90823 + outer loop + vertex 1.32856 2.13285 2.48576 + vertex 1.33264 2.1336 2.48468 + vertex 1.32782 2.13629 2.48446 + endloop + endfacet + facet normal 0.193825 0.421034 0.886094 + outer loop + vertex 1.32782 2.13629 2.48446 + vertex 1.33264 2.1336 2.48468 + vertex 1.33161 2.13808 2.48278 + endloop + endfacet + facet normal 0.15497 0.416247 0.895948 + outer loop + vertex 1.33264 2.1336 2.48468 + vertex 1.33638 2.13627 2.4828 + vertex 1.33161 2.13808 2.48278 + endloop + endfacet + facet normal 0.182489 0.339927 0.922576 + outer loop + vertex 1.32856 2.13285 2.48576 + vertex 1.33077 2.13041 2.48622 + vertex 1.33264 2.1336 2.48468 + endloop + endfacet + facet normal 0.174596 0.344488 0.922412 + outer loop + vertex 1.33475 2.12923 2.48591 + vertex 1.33264 2.1336 2.48468 + vertex 1.33077 2.13041 2.48622 + endloop + endfacet + facet normal 0.164378 0.30596 0.937746 + outer loop + vertex 1.33077 2.13041 2.48622 + vertex 1.33104 2.12644 2.48747 + vertex 1.33475 2.12923 2.48591 + endloop + endfacet + facet normal 0.163896 0.306541 0.937641 + outer loop + vertex 1.33657 2.12487 2.48702 + vertex 1.33475 2.12923 2.48591 + vertex 1.33104 2.12644 2.48747 + endloop + endfacet + facet normal 0.156715 0.304052 0.939677 + outer loop + vertex 1.33875 2.12804 2.48563 + vertex 1.33475 2.12923 2.48591 + vertex 1.33657 2.12487 2.48702 + endloop + endfacet + facet normal 0.157825 0.30331 0.939731 + outer loop + vertex 1.34082 2.12544 2.48612 + vertex 1.33875 2.12804 2.48563 + vertex 1.33657 2.12487 2.48702 + endloop + endfacet + facet normal 0.158882 0.297837 0.941302 + outer loop + vertex 1.34082 2.12544 2.48612 + vertex 1.33657 2.12487 2.48702 + vertex 1.34095 2.12139 2.48738 + endloop + endfacet + facet normal 0.158672 0.297841 0.941336 + outer loop + vertex 1.34082 2.12544 2.48612 + vertex 1.34095 2.12139 2.48738 + vertex 1.34475 2.12419 2.48586 + endloop + endfacet + facet normal 0.161037 0.305947 0.93833 + outer loop + vertex 1.34475 2.12419 2.48586 + vertex 1.34291 2.12863 2.48472 + vertex 1.34082 2.12544 2.48612 + endloop + endfacet + facet normal 0.157524 0.304738 0.939319 + outer loop + vertex 1.34291 2.12863 2.48472 + vertex 1.34475 2.12419 2.48586 + vertex 1.34857 2.12692 2.48433 + endloop + endfacet + facet normal 0.159099 0.302746 0.939698 + outer loop + vertex 1.34475 2.12419 2.48586 + vertex 1.34866 2.12296 2.48559 + vertex 1.34857 2.12692 2.48433 + endloop + endfacet + facet normal 0.154002 0.302887 0.940501 + outer loop + vertex 1.34866 2.12296 2.48559 + vertex 1.35283 2.12362 2.48469 + vertex 1.34857 2.12692 2.48433 + endloop + endfacet + facet normal 0.154262 0.303206 0.940356 + outer loop + vertex 1.34857 2.12692 2.48433 + vertex 1.35283 2.12362 2.48469 + vertex 1.35244 2.12694 2.48369 + endloop + endfacet + facet normal 0.157266 0.303394 0.939798 + outer loop + vertex 1.35283 2.12362 2.48469 + vertex 1.35621 2.12705 2.48302 + vertex 1.35244 2.12694 2.48369 + endloop + endfacet + facet normal 0.150147 0.309942 0.938825 + outer loop + vertex 1.35858 2.12208 2.48428 + vertex 1.35621 2.12705 2.48302 + vertex 1.35283 2.12362 2.48469 + endloop + endfacet + facet normal 0.147417 0.298674 0.942901 + outer loop + vertex 1.35283 2.12362 2.48469 + vertex 1.35461 2.11918 2.48582 + vertex 1.35858 2.12208 2.48428 + endloop + endfacet + facet normal 0.14563 0.300887 0.942475 + outer loop + vertex 1.35461 2.11918 2.48582 + vertex 1.35862 2.11797 2.48559 + vertex 1.35858 2.12208 2.48428 + endloop + endfacet + facet normal 0.131874 0.301352 0.94435 + outer loop + vertex 1.35862 2.11797 2.48559 + vertex 1.36301 2.11859 2.48478 + vertex 1.35858 2.12208 2.48428 + endloop + endfacet + facet normal 0.135217 0.305347 0.942592 + outer loop + vertex 1.35858 2.12208 2.48428 + vertex 1.36301 2.11859 2.48478 + vertex 1.36328 2.12246 2.48349 + endloop + endfacet + facet normal 0.13443 0.311288 0.94076 + outer loop + vertex 1.36328 2.12246 2.48349 + vertex 1.36158 2.12583 2.48261 + vertex 1.35858 2.12208 2.48428 + endloop + endfacet + facet normal 0.126487 0.307854 0.942988 + outer loop + vertex 1.36328 2.12246 2.48349 + vertex 1.36668 2.12482 2.48226 + vertex 1.36158 2.12583 2.48261 + endloop + endfacet + facet normal 0.12516 0.309562 0.942606 + outer loop + vertex 1.36657 2.12099 2.48353 + vertex 1.36668 2.12482 2.48226 + vertex 1.36328 2.12246 2.48349 + endloop + endfacet + facet normal 0.119126 0.309951 0.94326 + outer loop + vertex 1.36668 2.12482 2.48226 + vertex 1.36657 2.12099 2.48353 + vertex 1.37109 2.12184 2.48268 + endloop + endfacet + facet normal 0.126058 0.319615 0.939125 + outer loop + vertex 1.37079 2.12574 2.48139 + vertex 1.36668 2.12482 2.48226 + vertex 1.37109 2.12184 2.48268 + endloop + endfacet + facet normal 0.13407 0.319831 0.937941 + outer loop + vertex 1.37079 2.12574 2.48139 + vertex 1.37109 2.12184 2.48268 + vertex 1.3748 2.12483 2.48113 + endloop + endfacet + facet normal 0.144109 0.369679 0.917916 + outer loop + vertex 1.3748 2.12483 2.48113 + vertex 1.37256 2.12889 2.47985 + vertex 1.37079 2.12574 2.48139 + endloop + endfacet + facet normal 0.140136 0.36791 0.919241 + outer loop + vertex 1.37256 2.12889 2.47985 + vertex 1.3748 2.12483 2.48113 + vertex 1.37807 2.12759 2.47953 + endloop + endfacet + facet normal 0.140906 0.367114 0.919442 + outer loop + vertex 1.3748 2.12483 2.48113 + vertex 1.37956 2.12364 2.48088 + vertex 1.37807 2.12759 2.47953 + endloop + endfacet + facet normal 0.132626 0.330875 0.934308 + outer loop + vertex 1.37956 2.12364 2.48088 + vertex 1.3748 2.12483 2.48113 + vertex 1.37631 2.12085 2.48233 + endloop + endfacet + facet normal 0.125965 0.328843 0.935946 + outer loop + vertex 1.37631 2.12085 2.48233 + vertex 1.3748 2.12483 2.48113 + vertex 1.37109 2.12184 2.48268 + endloop + endfacet + facet normal 0.124062 0.317302 0.940174 + outer loop + vertex 1.37338 2.11819 2.48361 + vertex 1.37631 2.12085 2.48233 + vertex 1.37109 2.12184 2.48268 + endloop + endfacet + facet normal 0.116453 0.313126 0.942545 + outer loop + vertex 1.37338 2.11819 2.48361 + vertex 1.37109 2.12184 2.48268 + vertex 1.36873 2.11727 2.48449 + endloop + endfacet + facet normal 0.114972 0.318952 0.940772 + outer loop + vertex 1.36873 2.11727 2.48449 + vertex 1.37323 2.11413 2.48501 + vertex 1.37338 2.11819 2.48361 + endloop + endfacet + facet normal 0.117835 0.318748 0.940486 + outer loop + vertex 1.37323 2.11413 2.48501 + vertex 1.37731 2.11689 2.48356 + vertex 1.37338 2.11819 2.48361 + endloop + endfacet + facet normal 0.111757 0.326683 0.938503 + outer loop + vertex 1.37823 2.11301 2.4848 + vertex 1.37731 2.11689 2.48356 + vertex 1.37323 2.11413 2.48501 + endloop + endfacet + facet normal 0.111206 0.326584 0.938603 + outer loop + vertex 1.37823 2.11301 2.4848 + vertex 1.38113 2.11566 2.48354 + vertex 1.37731 2.11689 2.48356 + endloop + endfacet + facet normal 0.113249 0.332962 0.936115 + outer loop + vertex 1.38113 2.11566 2.48354 + vertex 1.38134 2.11954 2.48213 + vertex 1.37731 2.11689 2.48356 + endloop + endfacet + facet normal 0.120909 0.322718 0.938741 + outer loop + vertex 1.37731 2.11689 2.48356 + vertex 1.38134 2.11954 2.48213 + vertex 1.37631 2.12085 2.48233 + endloop + endfacet + facet normal 0.100513 0.337096 0.936089 + outer loop + vertex 1.38294 2.11241 2.48451 + vertex 1.38113 2.11566 2.48354 + vertex 1.37823 2.11301 2.4848 + endloop + endfacet + facet normal 0.0996166 0.328438 0.939258 + outer loop + vertex 1.37823 2.11301 2.4848 + vertex 1.3797 2.10917 2.48599 + vertex 1.38294 2.11241 2.48451 + endloop + endfacet + facet normal 0.0886619 0.338272 0.936862 + outer loop + vertex 1.3797 2.10917 2.48599 + vertex 1.38445 2.10849 2.48578 + vertex 1.38294 2.11241 2.48451 + endloop + endfacet + facet normal 0.0738383 0.33354 0.93984 + outer loop + vertex 1.38294 2.11241 2.48451 + vertex 1.38445 2.10849 2.48578 + vertex 1.38838 2.11184 2.48429 + endloop + endfacet + facet normal 0.0749505 0.345873 0.935283 + outer loop + vertex 1.38838 2.11184 2.48429 + vertex 1.38575 2.11649 2.48278 + vertex 1.38294 2.11241 2.48451 + endloop + endfacet + facet normal 0.064957 0.341037 0.937803 + outer loop + vertex 1.38838 2.11184 2.48429 + vertex 1.39125 2.11597 2.48259 + vertex 1.38575 2.11649 2.48278 + endloop + endfacet + facet normal 0.0520578 0.349097 0.93564 + outer loop + vertex 1.39314 2.11291 2.48362 + vertex 1.39125 2.11597 2.48259 + vertex 1.38838 2.11184 2.48429 + endloop + endfacet + facet normal 0.0534095 0.344166 0.937388 + outer loop + vertex 1.38838 2.11184 2.48429 + vertex 1.39288 2.1091 2.48504 + vertex 1.39314 2.11291 2.48362 + endloop + endfacet + facet normal 0.050779 0.340279 0.938952 + outer loop + vertex 1.38843 2.10786 2.48572 + vertex 1.39288 2.1091 2.48504 + vertex 1.38838 2.11184 2.48429 + endloop + endfacet + facet normal 0.0496965 0.34355 0.937818 + outer loop + vertex 1.38843 2.10786 2.48572 + vertex 1.39048 2.10564 2.48643 + vertex 1.39288 2.1091 2.48504 + endloop + endfacet + facet normal 0.0493415 0.343772 0.937756 + outer loop + vertex 1.39461 2.10511 2.48641 + vertex 1.39288 2.1091 2.48504 + vertex 1.39048 2.10564 2.48643 + endloop + endfacet + facet normal 0.0494626 0.344737 0.937395 + outer loop + vertex 1.39048 2.10564 2.48643 + vertex 1.39056 2.10176 2.48785 + vertex 1.39461 2.10511 2.48641 + endloop + endfacet + facet normal 0.0549344 0.338896 0.939219 + outer loop + vertex 1.3962 2.10113 2.48775 + vertex 1.39461 2.10511 2.48641 + vertex 1.39056 2.10176 2.48785 + endloop + endfacet + facet normal 0.0554348 0.343611 0.937474 + outer loop + vertex 1.39283 2.09753 2.48927 + vertex 1.3962 2.10113 2.48775 + vertex 1.39056 2.10176 2.48785 + endloop + endfacet + facet normal 0.0683766 0.332743 0.940535 + outer loop + vertex 1.39843 2.09679 2.48913 + vertex 1.3962 2.10113 2.48775 + vertex 1.39283 2.09753 2.48927 + endloop + endfacet + facet normal 0.0692854 0.340084 0.937839 + outer loop + vertex 1.39283 2.09753 2.48927 + vertex 1.39443 2.09354 2.4906 + vertex 1.39843 2.09679 2.48913 + endloop + endfacet + facet normal 0.0781779 0.330408 0.940595 + outer loop + vertex 1.39443 2.09354 2.4906 + vertex 1.39849 2.09288 2.49049 + vertex 1.39843 2.09679 2.48913 + endloop + endfacet + facet normal 0.0967403 0.330147 0.938959 + outer loop + vertex 1.39849 2.09288 2.49049 + vertex 1.40274 2.09378 2.48974 + vertex 1.39843 2.09679 2.48913 + endloop + endfacet + facet normal 0.0898533 0.321061 0.942786 + outer loop + vertex 1.39843 2.09679 2.48913 + vertex 1.40274 2.09378 2.48974 + vertex 1.40303 2.0975 2.48844 + endloop + endfacet + facet normal 0.0889105 0.325731 0.941273 + outer loop + vertex 1.40303 2.0975 2.48844 + vertex 1.40138 2.10069 2.4875 + vertex 1.39843 2.09679 2.48913 + endloop + endfacet + facet normal 0.0954515 0.328624 0.939625 + outer loop + vertex 1.40303 2.0975 2.48844 + vertex 1.40653 2.09989 2.48725 + vertex 1.40138 2.10069 2.4875 + endloop + endfacet + facet normal 0.0948833 0.3245 0.941115 + outer loop + vertex 1.40653 2.09989 2.48725 + vertex 1.40467 2.10392 2.48605 + vertex 1.40138 2.10069 2.4875 + endloop + endfacet + facet normal 0.0842466 0.334242 0.938715 + outer loop + vertex 1.40467 2.10392 2.48605 + vertex 1.39966 2.10455 2.48627 + vertex 1.40138 2.10069 2.4875 + endloop + endfacet + facet normal 0.0744056 0.330543 0.940853 + outer loop + vertex 1.40138 2.10069 2.4875 + vertex 1.39966 2.10455 2.48627 + vertex 1.3962 2.10113 2.48775 + endloop + endfacet + facet normal 0.0838216 0.330379 0.940119 + outer loop + vertex 1.39966 2.10455 2.48627 + vertex 1.40467 2.10392 2.48605 + vertex 1.40319 2.10773 2.48484 + endloop + endfacet + facet normal 0.073694 0.340406 0.937386 + outer loop + vertex 1.39821 2.10838 2.485 + vertex 1.39966 2.10455 2.48627 + vertex 1.40319 2.10773 2.48484 + endloop + endfacet + facet normal 0.072775 0.332728 0.940211 + outer loop + vertex 1.40319 2.10773 2.48484 + vertex 1.40197 2.11148 2.48361 + vertex 1.39821 2.10838 2.485 + endloop + endfacet + facet normal 0.0639824 0.342171 0.937457 + outer loop + vertex 1.39821 2.10838 2.485 + vertex 1.40197 2.11148 2.48361 + vertex 1.39718 2.11214 2.4837 + endloop + endfacet + facet normal 0.062848 0.333562 0.940631 + outer loop + vertex 1.40197 2.11148 2.48361 + vertex 1.40091 2.11528 2.48234 + vertex 1.39718 2.11214 2.4837 + endloop + endfacet + facet normal 0.0784429 0.337118 0.938189 + outer loop + vertex 1.40197 2.11148 2.48361 + vertex 1.40623 2.11452 2.48216 + vertex 1.40091 2.11528 2.48234 + endloop + endfacet + facet normal 0.0769812 0.325936 0.942252 + outer loop + vertex 1.40623 2.11452 2.48216 + vertex 1.40447 2.11859 2.4809 + vertex 1.40091 2.11528 2.48234 + endloop + endfacet + facet normal 0.0854945 0.329064 0.940429 + outer loop + vertex 1.40861 2.11799 2.48073 + vertex 1.40447 2.11859 2.4809 + vertex 1.40623 2.11452 2.48216 + endloop + endfacet + facet normal 0.0979447 0.321174 0.941942 + outer loop + vertex 1.41071 2.11565 2.48131 + vertex 1.40861 2.11799 2.48073 + vertex 1.40623 2.11452 2.48216 + endloop + endfacet + facet normal 0.096672 0.325252 0.940673 + outer loop + vertex 1.41071 2.11565 2.48131 + vertex 1.40623 2.11452 2.48216 + vertex 1.41085 2.1117 2.48266 + endloop + endfacet + facet normal 0.102775 0.325253 0.940025 + outer loop + vertex 1.41071 2.11565 2.48131 + vertex 1.41085 2.1117 2.48266 + vertex 1.41482 2.11483 2.48115 + endloop + endfacet + facet normal 0.102338 0.322886 0.940889 + outer loop + vertex 1.41482 2.11483 2.48115 + vertex 1.41311 2.11902 2.4799 + vertex 1.41071 2.11565 2.48131 + endloop + endfacet + facet normal 0.100192 0.322153 0.941371 + outer loop + vertex 1.41311 2.11902 2.4799 + vertex 1.41482 2.11483 2.48115 + vertex 1.41839 2.11785 2.47973 + endloop + endfacet + facet normal 0.101621 0.326562 0.939697 + outer loop + vertex 1.41622 2.11086 2.48237 + vertex 1.41482 2.11483 2.48115 + vertex 1.41085 2.1117 2.48266 + endloop + endfacet + facet normal 0.10212 0.330183 0.938377 + outer loop + vertex 1.41323 2.10818 2.48364 + vertex 1.41622 2.11086 2.48237 + vertex 1.41085 2.1117 2.48266 + endloop + endfacet + facet normal 0.100046 0.332255 0.937868 + outer loop + vertex 1.41725 2.10697 2.48364 + vertex 1.41622 2.11086 2.48237 + vertex 1.41323 2.10818 2.48364 + endloop + endfacet + facet normal 0.0995363 0.330569 0.938518 + outer loop + vertex 1.41314 2.10421 2.48505 + vertex 1.41725 2.10697 2.48364 + vertex 1.41323 2.10818 2.48364 + endloop + endfacet + facet normal 0.101737 0.330451 0.938324 + outer loop + vertex 1.40859 2.10711 2.48452 + vertex 1.41314 2.10421 2.48505 + vertex 1.41323 2.10818 2.48364 + endloop + endfacet + facet normal 0.101859 0.330029 0.938459 + outer loop + vertex 1.41323 2.10818 2.48364 + vertex 1.41085 2.1117 2.48266 + vertex 1.40859 2.10711 2.48452 + endloop + endfacet + facet normal 0.0988771 0.331429 0.938285 + outer loop + vertex 1.40859 2.10711 2.48452 + vertex 1.41085 2.1117 2.48266 + vertex 1.40617 2.11056 2.48356 + endloop + endfacet + facet normal 0.0936335 0.328216 0.939951 + outer loop + vertex 1.40859 2.10711 2.48452 + vertex 1.40617 2.11056 2.48356 + vertex 1.40319 2.10773 2.48484 + endloop + endfacet + facet normal 0.101034 0.329427 0.93876 + outer loop + vertex 1.40877 2.10322 2.48587 + vertex 1.41314 2.10421 2.48505 + vertex 1.40859 2.10711 2.48452 + endloop + endfacet + facet normal 0.0980747 0.329398 0.939084 + outer loop + vertex 1.40467 2.10392 2.48605 + vertex 1.40877 2.10322 2.48587 + vertex 1.40859 2.10711 2.48452 + endloop + endfacet + facet normal 0.0992719 0.330915 0.938424 + outer loop + vertex 1.4182 2.10315 2.48489 + vertex 1.41725 2.10697 2.48364 + vertex 1.41314 2.10421 2.48505 + endloop + endfacet + facet normal 0.097102 0.330497 0.938799 + outer loop + vertex 1.4182 2.10315 2.48489 + vertex 1.42114 2.1058 2.48365 + vertex 1.41725 2.10697 2.48364 + endloop + endfacet + facet normal 0.0979289 0.333244 0.937741 + outer loop + vertex 1.42114 2.1058 2.48365 + vertex 1.4214 2.10967 2.48225 + vertex 1.41725 2.10697 2.48364 + endloop + endfacet + facet normal 0.0978129 0.333255 0.937749 + outer loop + vertex 1.4214 2.10967 2.48225 + vertex 1.42114 2.1058 2.48365 + vertex 1.42583 2.10666 2.48286 + endloop + endfacet + facet normal 0.0976125 0.332984 0.937867 + outer loop + vertex 1.42581 2.11065 2.48144 + vertex 1.4214 2.10967 2.48225 + vertex 1.42583 2.10666 2.48286 + endloop + endfacet + facet normal 0.0969604 0.333002 0.937928 + outer loop + vertex 1.42581 2.11065 2.48144 + vertex 1.42583 2.10666 2.48286 + vertex 1.42982 2.10994 2.48128 + endloop + endfacet + facet normal 0.0960188 0.327172 0.940074 + outer loop + vertex 1.42982 2.10994 2.48128 + vertex 1.42819 2.11407 2.48001 + vertex 1.42581 2.11065 2.48144 + endloop + endfacet + facet normal 0.0960375 0.32716 0.940076 + outer loop + vertex 1.42379 2.11302 2.48082 + vertex 1.42581 2.11065 2.48144 + vertex 1.42819 2.11407 2.48001 + endloop + endfacet + facet normal 0.0973015 0.322884 0.941424 + outer loop + vertex 1.42379 2.11302 2.48082 + vertex 1.42819 2.11407 2.48001 + vertex 1.42374 2.117 2.47946 + endloop + endfacet + facet normal 0.0979269 0.322871 0.941363 + outer loop + vertex 1.41973 2.11385 2.48096 + vertex 1.42379 2.11302 2.48082 + vertex 1.42374 2.117 2.47946 + endloop + endfacet + facet normal 0.0984121 0.322318 0.941502 + outer loop + vertex 1.41839 2.11785 2.47973 + vertex 1.41973 2.11385 2.48096 + vertex 1.42374 2.117 2.47946 + endloop + endfacet + facet normal 0.0995231 0.330306 0.938612 + outer loop + vertex 1.42374 2.117 2.47946 + vertex 1.42142 2.12056 2.47846 + vertex 1.41839 2.11785 2.47973 + endloop + endfacet + facet normal 0.0955191 0.334301 0.937613 + outer loop + vertex 1.41839 2.11785 2.47973 + vertex 1.42142 2.12056 2.47846 + vertex 1.41733 2.12174 2.47845 + endloop + endfacet + facet normal 0.103084 0.335907 0.936237 + outer loop + vertex 1.41839 2.11785 2.47973 + vertex 1.41733 2.12174 2.47845 + vertex 1.41311 2.11902 2.4799 + endloop + endfacet + facet normal 0.0982356 0.342425 0.934396 + outer loop + vertex 1.41311 2.11902 2.4799 + vertex 1.41733 2.12174 2.47845 + vertex 1.4133 2.12285 2.47847 + endloop + endfacet + facet normal 0.0974357 0.342488 0.934456 + outer loop + vertex 1.40857 2.12188 2.47932 + vertex 1.41311 2.11902 2.4799 + vertex 1.4133 2.12285 2.47847 + endloop + endfacet + facet normal 0.083345 0.394538 0.915092 + outer loop + vertex 1.4133 2.12285 2.47847 + vertex 1.41122 2.12576 2.4774 + vertex 1.40857 2.12188 2.47932 + endloop + endfacet + facet normal 0.0899941 0.390538 0.916178 + outer loop + vertex 1.40857 2.12188 2.47932 + vertex 1.41122 2.12576 2.4774 + vertex 1.40616 2.12588 2.47785 + endloop + endfacet + facet normal 0.0819258 0.386584 0.918608 + outer loop + vertex 1.40857 2.12188 2.47932 + vertex 1.40616 2.12588 2.47785 + vertex 1.40297 2.12245 2.47958 + endloop + endfacet + facet normal 0.0788606 0.349827 0.933489 + outer loop + vertex 1.40297 2.12245 2.47958 + vertex 1.40447 2.11859 2.4809 + vertex 1.40857 2.12188 2.47932 + endloop + endfacet + facet normal 0.065835 0.399434 0.914395 + outer loop + vertex 1.40297 2.12245 2.47958 + vertex 1.40616 2.12588 2.47785 + vertex 1.40106 2.12611 2.47812 + endloop + endfacet + facet normal 0.100363 0.404492 0.909018 + outer loop + vertex 1.4133 2.12285 2.47847 + vertex 1.41606 2.12538 2.47704 + vertex 1.41122 2.12576 2.4774 + endloop + endfacet + facet normal 0.0962041 0.340695 0.935239 + outer loop + vertex 1.40861 2.11799 2.48073 + vertex 1.41311 2.11902 2.4799 + vertex 1.40857 2.12188 2.47932 + endloop + endfacet + facet normal 0.112169 0.393597 0.912414 + outer loop + vertex 1.41733 2.12174 2.47845 + vertex 1.41606 2.12538 2.47704 + vertex 1.4133 2.12285 2.47847 + endloop + endfacet + facet normal 0.0968528 0.389607 0.915874 + outer loop + vertex 1.41733 2.12174 2.47845 + vertex 1.42122 2.1244 2.47691 + vertex 1.41606 2.12538 2.47704 + endloop + endfacet + facet normal 0.107661 0.376301 0.920221 + outer loop + vertex 1.42142 2.12056 2.47846 + vertex 1.42122 2.1244 2.47691 + vertex 1.41733 2.12174 2.47845 + endloop + endfacet + facet normal 0.0960231 0.376225 0.921539 + outer loop + vertex 1.42122 2.1244 2.47691 + vertex 1.42142 2.12056 2.47846 + vertex 1.42589 2.12159 2.47757 + endloop + endfacet + facet normal 0.10704 0.392631 0.913446 + outer loop + vertex 1.42523 2.12528 2.47606 + vertex 1.42122 2.1244 2.47691 + vertex 1.42589 2.12159 2.47757 + endloop + endfacet + facet normal 0.129252 0.395041 0.909526 + outer loop + vertex 1.42523 2.12528 2.47606 + vertex 1.42589 2.12159 2.47757 + vertex 1.42909 2.12454 2.47583 + endloop + endfacet + facet normal 0.149549 0.523715 0.838664 + outer loop + vertex 1.42909 2.12454 2.47583 + vertex 1.42624 2.12773 2.47435 + vertex 1.42523 2.12528 2.47606 + endloop + endfacet + facet normal 0.113892 0.409192 0.905312 + outer loop + vertex 1.43113 2.12076 2.47729 + vertex 1.42909 2.12454 2.47583 + vertex 1.42589 2.12159 2.47757 + endloop + endfacet + facet normal 0.105874 0.349477 0.930944 + outer loop + vertex 1.42836 2.11807 2.47861 + vertex 1.43113 2.12076 2.47729 + vertex 1.42589 2.12159 2.47757 + endloop + endfacet + facet normal 0.0933273 0.341891 0.935094 + outer loop + vertex 1.42836 2.11807 2.47861 + vertex 1.42589 2.12159 2.47757 + vertex 1.42374 2.117 2.47946 + endloop + endfacet + facet normal 0.106773 0.348656 0.931149 + outer loop + vertex 1.43231 2.11688 2.47861 + vertex 1.43113 2.12076 2.47729 + vertex 1.42836 2.11807 2.47861 + endloop + endfacet + facet normal 0.0994451 0.32436 0.940692 + outer loop + vertex 1.42819 2.11407 2.48001 + vertex 1.43231 2.11688 2.47861 + vertex 1.42836 2.11807 2.47861 + endloop + endfacet + facet normal 0.0971902 0.327281 0.939916 + outer loop + vertex 1.43321 2.11305 2.47984 + vertex 1.43231 2.11688 2.47861 + vertex 1.42819 2.11407 2.48001 + endloop + endfacet + facet normal 0.095458 0.326968 0.940202 + outer loop + vertex 1.43321 2.11305 2.47984 + vertex 1.43617 2.11574 2.47861 + vertex 1.43231 2.11688 2.47861 + endloop + endfacet + facet normal 0.101506 0.347429 0.932196 + outer loop + vertex 1.43617 2.11574 2.47861 + vertex 1.43626 2.1196 2.47716 + vertex 1.43231 2.11688 2.47861 + endloop + endfacet + facet normal 0.0895995 0.348078 0.933174 + outer loop + vertex 1.43626 2.1196 2.47716 + vertex 1.43617 2.11574 2.47861 + vertex 1.44081 2.11664 2.47783 + endloop + endfacet + facet normal 0.10341 0.367339 0.924321 + outer loop + vertex 1.4405 2.12054 2.47631 + vertex 1.43626 2.1196 2.47716 + vertex 1.44081 2.11664 2.47783 + endloop + endfacet + facet normal 0.0952293 0.367079 0.925302 + outer loop + vertex 1.4405 2.12054 2.47631 + vertex 1.44081 2.11664 2.47783 + vertex 1.44451 2.11984 2.47618 + endloop + endfacet + facet normal 0.110134 0.46105 0.880513 + outer loop + vertex 1.44451 2.11984 2.47618 + vertex 1.4423 2.12355 2.47451 + vertex 1.4405 2.12054 2.47631 + endloop + endfacet + facet normal 0.0966104 0.455085 0.885192 + outer loop + vertex 1.4423 2.12355 2.47451 + vertex 1.44451 2.11984 2.47618 + vertex 1.44754 2.12254 2.47446 + endloop + endfacet + facet normal 0.099933 0.452101 0.886351 + outer loop + vertex 1.44451 2.11984 2.47618 + vertex 1.44923 2.11913 2.47601 + vertex 1.44754 2.12254 2.47446 + endloop + endfacet + facet normal 0.0924624 0.449405 0.88853 + outer loop + vertex 1.44754 2.12254 2.47446 + vertex 1.44923 2.11913 2.47601 + vertex 1.45175 2.1215 2.47455 + endloop + endfacet + facet normal 0.112086 0.432381 0.894697 + outer loop + vertex 1.44923 2.11913 2.47601 + vertex 1.45385 2.11853 2.47572 + vertex 1.45175 2.1215 2.47455 + endloop + endfacet + facet normal 0.105472 0.367281 0.92411 + outer loop + vertex 1.45385 2.11853 2.47572 + vertex 1.44923 2.11913 2.47601 + vertex 1.45105 2.11555 2.47722 + endloop + endfacet + facet normal 0.110228 0.363318 0.925121 + outer loop + vertex 1.4561 2.11452 2.47702 + vertex 1.45385 2.11853 2.47572 + vertex 1.45105 2.11555 2.47722 + endloop + endfacet + facet normal 0.103305 0.32617 0.939649 + outer loop + vertex 1.45215 2.11171 2.47843 + vertex 1.4561 2.11452 2.47702 + vertex 1.45105 2.11555 2.47722 + endloop + endfacet + facet normal 0.101425 0.325739 0.940004 + outer loop + vertex 1.45215 2.11171 2.47843 + vertex 1.45105 2.11555 2.47722 + vertex 1.44823 2.11288 2.47845 + endloop + endfacet + facet normal 0.0992117 0.318232 0.942807 + outer loop + vertex 1.44797 2.10893 2.47982 + vertex 1.45215 2.11171 2.47843 + vertex 1.44823 2.11288 2.47845 + endloop + endfacet + facet normal 0.0925717 0.318831 0.94328 + outer loop + vertex 1.44348 2.11196 2.47923 + vertex 1.44797 2.10893 2.47982 + vertex 1.44823 2.11288 2.47845 + endloop + endfacet + facet normal 0.0896792 0.3306 0.939501 + outer loop + vertex 1.44823 2.11288 2.47845 + vertex 1.44628 2.11606 2.47752 + vertex 1.44348 2.11196 2.47923 + endloop + endfacet + facet normal 0.0880091 0.331652 0.939288 + outer loop + vertex 1.44348 2.11196 2.47923 + vertex 1.44628 2.11606 2.47752 + vertex 1.44081 2.11664 2.47783 + endloop + endfacet + facet normal 0.0904898 0.332865 0.938623 + outer loop + vertex 1.44348 2.11196 2.47923 + vertex 1.44081 2.11664 2.47783 + vertex 1.43797 2.11254 2.47955 + endloop + endfacet + facet normal 0.0901052 0.32836 0.940245 + outer loop + vertex 1.43797 2.11254 2.47955 + vertex 1.43946 2.10862 2.48078 + vertex 1.44348 2.11196 2.47923 + endloop + endfacet + facet normal 0.0933722 0.324848 0.941146 + outer loop + vertex 1.43946 2.10862 2.48078 + vertex 1.44352 2.10791 2.48062 + vertex 1.44348 2.11196 2.47923 + endloop + endfacet + facet normal 0.0940322 0.32898 0.939644 + outer loop + vertex 1.44352 2.10791 2.48062 + vertex 1.43946 2.10862 2.48078 + vertex 1.44119 2.10449 2.48205 + endloop + endfacet + facet normal 0.0989527 0.325873 0.940221 + outer loop + vertex 1.44559 2.10553 2.48123 + vertex 1.44352 2.10791 2.48062 + vertex 1.44119 2.10449 2.48205 + endloop + endfacet + facet normal 0.0990167 0.325655 0.94029 + outer loop + vertex 1.44559 2.10553 2.48123 + vertex 1.44119 2.10449 2.48205 + vertex 1.44571 2.10159 2.48258 + endloop + endfacet + facet normal 0.10335 0.325637 0.939829 + outer loop + vertex 1.44559 2.10553 2.48123 + vertex 1.44571 2.10159 2.48258 + vertex 1.44964 2.1047 2.48107 + endloop + endfacet + facet normal 0.102445 0.320837 0.941578 + outer loop + vertex 1.44964 2.1047 2.48107 + vertex 1.44797 2.10893 2.47982 + vertex 1.44559 2.10553 2.48123 + endloop + endfacet + facet normal 0.103027 0.321029 0.941449 + outer loop + vertex 1.44797 2.10893 2.47982 + vertex 1.44964 2.1047 2.48107 + vertex 1.45314 2.10774 2.47965 + endloop + endfacet + facet normal 0.105084 0.318888 0.941949 + outer loop + vertex 1.44964 2.1047 2.48107 + vertex 1.45447 2.10375 2.48086 + vertex 1.45314 2.10774 2.47965 + endloop + endfacet + facet normal 0.104373 0.318696 0.942093 + outer loop + vertex 1.45314 2.10774 2.47965 + vertex 1.45447 2.10375 2.48086 + vertex 1.45843 2.1069 2.47935 + endloop + endfacet + facet normal 0.10385 0.314933 0.943415 + outer loop + vertex 1.45843 2.1069 2.47935 + vertex 1.45616 2.1105 2.4784 + vertex 1.45314 2.10774 2.47965 + endloop + endfacet + facet normal 0.103513 0.315268 0.94334 + outer loop + vertex 1.45314 2.10774 2.47965 + vertex 1.45616 2.1105 2.4784 + vertex 1.45215 2.11171 2.47843 + endloop + endfacet + facet normal 0.104059 0.315049 0.943354 + outer loop + vertex 1.45843 2.1069 2.47935 + vertex 1.46073 2.11155 2.47754 + vertex 1.45616 2.1105 2.4784 + endloop + endfacet + facet normal 0.101735 0.323106 0.940879 + outer loop + vertex 1.4561 2.11452 2.47702 + vertex 1.45616 2.1105 2.4784 + vertex 1.46073 2.11155 2.47754 + endloop + endfacet + facet normal 0.108622 0.333071 0.936624 + outer loop + vertex 1.46036 2.11553 2.47617 + vertex 1.4561 2.11452 2.47702 + vertex 1.46073 2.11155 2.47754 + endloop + endfacet + facet normal 0.106811 0.332985 0.936863 + outer loop + vertex 1.46036 2.11553 2.47617 + vertex 1.46073 2.11155 2.47754 + vertex 1.46447 2.11461 2.47603 + endloop + endfacet + facet normal 0.120549 0.398303 0.909298 + outer loop + vertex 1.46447 2.11461 2.47603 + vertex 1.46218 2.11873 2.47453 + vertex 1.46036 2.11553 2.47617 + endloop + endfacet + facet normal 0.112043 0.394562 0.912013 + outer loop + vertex 1.46218 2.11873 2.47453 + vertex 1.46447 2.11461 2.47603 + vertex 1.46779 2.11737 2.47443 + endloop + endfacet + facet normal 0.112487 0.394111 0.912153 + outer loop + vertex 1.46447 2.11461 2.47603 + vertex 1.4693 2.1135 2.47591 + vertex 1.46779 2.11737 2.47443 + endloop + endfacet + facet normal 0.102768 0.391235 0.914535 + outer loop + vertex 1.46779 2.11737 2.47443 + vertex 1.4693 2.1135 2.47591 + vertex 1.47264 2.11593 2.4745 + endloop + endfacet + facet normal 0.105546 0.388028 0.915584 + outer loop + vertex 1.4693 2.1135 2.47591 + vertex 1.47324 2.1127 2.4758 + vertex 1.47264 2.11593 2.4745 + endloop + endfacet + facet normal 0.110271 0.388588 0.91479 + outer loop + vertex 1.47324 2.1127 2.4758 + vertex 1.47729 2.11381 2.47484 + vertex 1.47264 2.11593 2.4745 + endloop + endfacet + facet normal 0.130617 0.429826 0.893414 + outer loop + vertex 1.47264 2.11593 2.4745 + vertex 1.47729 2.11381 2.47484 + vertex 1.47629 2.11788 2.47303 + endloop + endfacet + facet normal 0.118671 0.428009 0.895949 + outer loop + vertex 1.47729 2.11381 2.47484 + vertex 1.48094 2.11663 2.47301 + vertex 1.47629 2.11788 2.47303 + endloop + endfacet + facet normal 0.126105 0.420147 0.898651 + outer loop + vertex 1.4828 2.1128 2.47454 + vertex 1.48094 2.11663 2.47301 + vertex 1.47729 2.11381 2.47484 + endloop + endfacet + facet normal 0.115745 0.355348 0.92754 + outer loop + vertex 1.47729 2.11381 2.47484 + vertex 1.47951 2.10979 2.4761 + vertex 1.4828 2.1128 2.47454 + endloop + endfacet + facet normal 0.118207 0.352972 0.928137 + outer loop + vertex 1.47951 2.10979 2.4761 + vertex 1.48444 2.10881 2.47585 + vertex 1.4828 2.1128 2.47454 + endloop + endfacet + facet normal 0.112093 0.35096 0.929657 + outer loop + vertex 1.4828 2.1128 2.47454 + vertex 1.48444 2.10881 2.47585 + vertex 1.48837 2.11162 2.47431 + endloop + endfacet + facet normal 0.124827 0.416617 0.900471 + outer loop + vertex 1.48837 2.11162 2.47431 + vertex 1.48608 2.11569 2.47275 + vertex 1.4828 2.1128 2.47454 + endloop + endfacet + facet normal 0.109315 0.409852 0.905578 + outer loop + vertex 1.48837 2.11162 2.47431 + vertex 1.49147 2.11486 2.47247 + vertex 1.48608 2.11569 2.47275 + endloop + endfacet + facet normal 0.103654 0.41446 0.904145 + outer loop + vertex 1.49222 2.11193 2.47373 + vertex 1.49147 2.11486 2.47247 + vertex 1.48837 2.11162 2.47431 + endloop + endfacet + facet normal 0.132142 0.419168 0.898241 + outer loop + vertex 1.49147 2.11486 2.47247 + vertex 1.49222 2.11193 2.47373 + vertex 1.49593 2.11215 2.47308 + endloop + endfacet + facet normal 0.118238 0.34346 0.931695 + outer loop + vertex 1.48444 2.10881 2.47585 + vertex 1.48849 2.1079 2.47567 + vertex 1.48837 2.11162 2.47431 + endloop + endfacet + facet normal 0.116261 0.343485 0.931934 + outer loop + vertex 1.48849 2.1079 2.47567 + vertex 1.49273 2.10873 2.47483 + vertex 1.48837 2.11162 2.47431 + endloop + endfacet + facet normal 0.114061 0.340414 0.933332 + outer loop + vertex 1.48837 2.11162 2.47431 + vertex 1.49273 2.10873 2.47483 + vertex 1.49222 2.11193 2.47373 + endloop + endfacet + facet normal 0.142004 0.343216 0.92846 + outer loop + vertex 1.49273 2.10873 2.47483 + vertex 1.49593 2.11215 2.47308 + vertex 1.49222 2.11193 2.47373 + endloop + endfacet + facet normal 0.131316 0.35228 0.926637 + outer loop + vertex 1.49853 2.10735 2.47454 + vertex 1.49593 2.11215 2.47308 + vertex 1.49273 2.10873 2.47483 + endloop + endfacet + facet normal 0.124087 0.319381 0.939467 + outer loop + vertex 1.49273 2.10873 2.47483 + vertex 1.49461 2.10439 2.47606 + vertex 1.49853 2.10735 2.47454 + endloop + endfacet + facet normal 0.123216 0.320411 0.939231 + outer loop + vertex 1.49461 2.10439 2.47606 + vertex 1.49863 2.10329 2.47591 + vertex 1.49853 2.10735 2.47454 + endloop + endfacet + facet normal 0.11937 0.320475 0.939706 + outer loop + vertex 1.49863 2.10329 2.47591 + vertex 1.50287 2.10401 2.47513 + vertex 1.49853 2.10735 2.47454 + endloop + endfacet + facet normal 0.120134 0.317083 0.940758 + outer loop + vertex 1.49863 2.10329 2.47591 + vertex 1.50066 2.10077 2.4765 + vertex 1.50287 2.10401 2.47513 + endloop + endfacet + facet normal 0.116624 0.319341 0.940436 + outer loop + vertex 1.50466 2.09984 2.47632 + vertex 1.50287 2.10401 2.47513 + vertex 1.50066 2.10077 2.4765 + endloop + endfacet + facet normal 0.117179 0.321927 0.939485 + outer loop + vertex 1.50066 2.10077 2.4765 + vertex 1.50073 2.09678 2.47786 + vertex 1.50466 2.09984 2.47632 + endloop + endfacet + facet normal 0.118162 0.321906 0.939369 + outer loop + vertex 1.50066 2.10077 2.4765 + vertex 1.49635 2.10007 2.47728 + vertex 1.50073 2.09678 2.47786 + endloop + endfacet + facet normal 0.116228 0.319515 0.940426 + outer loop + vertex 1.49635 2.10007 2.47728 + vertex 1.49611 2.09626 2.47861 + vertex 1.50073 2.09678 2.47786 + endloop + endfacet + facet normal 0.115485 0.323998 0.938983 + outer loop + vertex 1.49781 2.0929 2.47955 + vertex 1.50073 2.09678 2.47786 + vertex 1.49611 2.09626 2.47861 + endloop + endfacet + facet normal 0.115079 0.323823 0.939093 + outer loop + vertex 1.49781 2.0929 2.47955 + vertex 1.49611 2.09626 2.47861 + vertex 1.49269 2.09386 2.47985 + endloop + endfacet + facet normal 0.114901 0.322749 0.939484 + outer loop + vertex 1.49269 2.09386 2.47985 + vertex 1.49454 2.08976 2.48103 + vertex 1.49781 2.0929 2.47955 + endloop + endfacet + facet normal 0.114095 0.323511 0.93932 + outer loop + vertex 1.49454 2.08976 2.48103 + vertex 1.49938 2.08883 2.48077 + vertex 1.49781 2.0929 2.47955 + endloop + endfacet + facet normal 0.114147 0.323528 0.939308 + outer loop + vertex 1.49781 2.0929 2.47955 + vertex 1.49938 2.08883 2.48077 + vertex 1.50331 2.09192 2.47922 + endloop + endfacet + facet normal 0.11436 0.323285 0.939366 + outer loop + vertex 1.49938 2.08883 2.48077 + vertex 1.5034 2.08792 2.48059 + vertex 1.50331 2.09192 2.47922 + endloop + endfacet + facet normal 0.117569 0.323233 0.938988 + outer loop + vertex 1.5034 2.08792 2.48059 + vertex 1.50771 2.08867 2.47979 + vertex 1.50331 2.09192 2.47922 + endloop + endfacet + facet normal 0.116098 0.321387 0.939804 + outer loop + vertex 1.50331 2.09192 2.47922 + vertex 1.50771 2.08867 2.47979 + vertex 1.50792 2.09246 2.47847 + endloop + endfacet + facet normal 0.115434 0.325328 0.938529 + outer loop + vertex 1.50792 2.09246 2.47847 + vertex 1.50622 2.09579 2.47753 + vertex 1.50331 2.09192 2.47922 + endloop + endfacet + facet normal 0.115468 0.325304 0.938533 + outer loop + vertex 1.50331 2.09192 2.47922 + vertex 1.50622 2.09579 2.47753 + vertex 1.50073 2.09678 2.47786 + endloop + endfacet + facet normal 0.115277 0.324103 0.938972 + outer loop + vertex 1.50622 2.09579 2.47753 + vertex 1.50466 2.09984 2.47632 + vertex 1.50073 2.09678 2.47786 + endloop + endfacet + facet normal 0.115701 0.324238 0.938873 + outer loop + vertex 1.50951 2.09891 2.47604 + vertex 1.50466 2.09984 2.47632 + vertex 1.50622 2.09579 2.47753 + endloop + endfacet + facet normal 0.116072 0.323883 0.93895 + outer loop + vertex 1.51133 2.09481 2.47723 + vertex 1.50951 2.09891 2.47604 + vertex 1.50622 2.09579 2.47753 + endloop + endfacet + facet normal 0.114749 0.323392 0.939282 + outer loop + vertex 1.51352 2.09807 2.47584 + vertex 1.50951 2.09891 2.47604 + vertex 1.51133 2.09481 2.47723 + endloop + endfacet + facet normal 0.117331 0.321762 0.939523 + outer loop + vertex 1.51555 2.09568 2.47641 + vertex 1.51352 2.09807 2.47584 + vertex 1.51133 2.09481 2.47723 + endloop + endfacet + facet normal 0.118367 0.317845 0.940725 + outer loop + vertex 1.51555 2.09568 2.47641 + vertex 1.51133 2.09481 2.47723 + vertex 1.51567 2.09178 2.47771 + endloop + endfacet + facet normal 0.120777 0.317819 0.940428 + outer loop + vertex 1.51555 2.09568 2.47641 + vertex 1.51567 2.09178 2.47771 + vertex 1.51954 2.09483 2.47618 + endloop + endfacet + facet normal 0.120767 0.317769 0.940446 + outer loop + vertex 1.51954 2.09483 2.47618 + vertex 1.5178 2.09893 2.47502 + vertex 1.51555 2.09568 2.47641 + endloop + endfacet + facet normal 0.121013 0.317856 0.940385 + outer loop + vertex 1.5178 2.09893 2.47502 + vertex 1.51954 2.09483 2.47618 + vertex 1.52292 2.09797 2.47469 + endloop + endfacet + facet normal 0.125148 0.313794 0.941207 + outer loop + vertex 1.51954 2.09483 2.47618 + vertex 1.52439 2.09385 2.47586 + vertex 1.52292 2.09797 2.47469 + endloop + endfacet + facet normal 0.127712 0.314541 0.940613 + outer loop + vertex 1.52292 2.09797 2.47469 + vertex 1.52439 2.09385 2.47586 + vertex 1.5284 2.09697 2.47427 + endloop + endfacet + facet normal 0.129014 0.323004 0.937563 + outer loop + vertex 1.5284 2.09697 2.47427 + vertex 1.52586 2.10184 2.47295 + vertex 1.52292 2.09797 2.47469 + endloop + endfacet + facet normal 0.130273 0.322109 0.937696 + outer loop + vertex 1.52292 2.09797 2.47469 + vertex 1.52586 2.10184 2.47295 + vertex 1.52132 2.1013 2.47376 + endloop + endfacet + facet normal 0.121102 0.318391 0.940192 + outer loop + vertex 1.52292 2.09797 2.47469 + vertex 1.52132 2.1013 2.47376 + vertex 1.5178 2.09893 2.47502 + endloop + endfacet + facet normal 0.116434 0.324529 0.938682 + outer loop + vertex 1.5178 2.09893 2.47502 + vertex 1.52132 2.1013 2.47376 + vertex 1.51814 2.10266 2.47369 + endloop + endfacet + facet normal 0.114417 0.324772 0.938846 + outer loop + vertex 1.51346 2.10204 2.47447 + vertex 1.5178 2.09893 2.47502 + vertex 1.51814 2.10266 2.47369 + endloop + endfacet + facet normal 0.110408 0.346154 0.931659 + outer loop + vertex 1.51814 2.10266 2.47369 + vertex 1.5163 2.10591 2.4727 + vertex 1.51346 2.10204 2.47447 + endloop + endfacet + facet normal 0.119627 0.339929 0.932812 + outer loop + vertex 1.51346 2.10204 2.47447 + vertex 1.5163 2.10591 2.4727 + vertex 1.5108 2.10683 2.47307 + endloop + endfacet + facet normal 0.118296 0.339304 0.933209 + outer loop + vertex 1.51346 2.10204 2.47447 + vertex 1.5108 2.10683 2.47307 + vertex 1.50795 2.10297 2.47483 + endloop + endfacet + facet normal 0.116132 0.324245 0.938818 + outer loop + vertex 1.50795 2.10297 2.47483 + vertex 1.50951 2.09891 2.47604 + vertex 1.51346 2.10204 2.47447 + endloop + endfacet + facet normal 0.129629 0.331529 0.934497 + outer loop + vertex 1.50795 2.10297 2.47483 + vertex 1.5108 2.10683 2.47307 + vertex 1.50628 2.10629 2.47389 + endloop + endfacet + facet normal 0.120913 0.327858 0.936957 + outer loop + vertex 1.50795 2.10297 2.47483 + vertex 1.50628 2.10629 2.47389 + vertex 1.50287 2.10401 2.47513 + endloop + endfacet + facet normal 0.119553 0.320393 0.93971 + outer loop + vertex 1.50287 2.10401 2.47513 + vertex 1.50466 2.09984 2.47632 + vertex 1.50795 2.10297 2.47483 + endloop + endfacet + facet normal 0.120863 0.327923 0.936941 + outer loop + vertex 1.50287 2.10401 2.47513 + vertex 1.50628 2.10629 2.47389 + vertex 1.50314 2.10773 2.47379 + endloop + endfacet + facet normal 0.125172 0.327457 0.936538 + outer loop + vertex 1.49853 2.10735 2.47454 + vertex 1.50287 2.10401 2.47513 + vertex 1.50314 2.10773 2.47379 + endloop + endfacet + facet normal 0.120593 0.360183 0.925054 + outer loop + vertex 1.50314 2.10773 2.47379 + vertex 1.5013 2.11105 2.47273 + vertex 1.49853 2.10735 2.47454 + endloop + endfacet + facet normal 0.124495 0.35971 0.924721 + outer loop + vertex 1.50639 2.10997 2.47244 + vertex 1.50628 2.10629 2.47389 + vertex 1.5108 2.10683 2.47307 + endloop + endfacet + facet normal 0.135479 0.358921 0.923483 + outer loop + vertex 1.50628 2.10629 2.47389 + vertex 1.50639 2.10997 2.47244 + vertex 1.50314 2.10773 2.47379 + endloop + endfacet + facet normal 0.13074 0.36481 0.921857 + outer loop + vertex 1.50314 2.10773 2.47379 + vertex 1.50639 2.10997 2.47244 + vertex 1.5013 2.11105 2.47273 + endloop + endfacet + facet normal 0.120894 0.351144 0.928484 + outer loop + vertex 1.51814 2.10266 2.47369 + vertex 1.52145 2.10499 2.47237 + vertex 1.5163 2.10591 2.4727 + endloop + endfacet + facet normal 0.114886 0.325379 0.938578 + outer loop + vertex 1.51352 2.09807 2.47584 + vertex 1.5178 2.09893 2.47502 + vertex 1.51346 2.10204 2.47447 + endloop + endfacet + facet normal 0.125579 0.34537 0.930027 + outer loop + vertex 1.52132 2.1013 2.47376 + vertex 1.52145 2.10499 2.47237 + vertex 1.51814 2.10266 2.47369 + endloop + endfacet + facet normal 0.126104 0.345329 0.929971 + outer loop + vertex 1.52145 2.10499 2.47237 + vertex 1.52132 2.1013 2.47376 + vertex 1.52586 2.10184 2.47295 + endloop + endfacet + facet normal 0.135077 0.356829 0.924352 + outer loop + vertex 1.52555 2.10578 2.47147 + vertex 1.52145 2.10499 2.47237 + vertex 1.52586 2.10184 2.47295 + endloop + endfacet + facet normal 0.13986 0.356921 0.923605 + outer loop + vertex 1.52555 2.10578 2.47147 + vertex 1.52586 2.10184 2.47295 + vertex 1.5294 2.10477 2.47128 + endloop + endfacet + facet normal 0.159153 0.437265 0.885138 + outer loop + vertex 1.5294 2.10477 2.47128 + vertex 1.52723 2.10877 2.46969 + vertex 1.52555 2.10578 2.47147 + endloop + endfacet + facet normal 0.149724 0.433548 0.888605 + outer loop + vertex 1.52723 2.10877 2.46969 + vertex 1.5294 2.10477 2.47128 + vertex 1.53185 2.10715 2.4697 + endloop + endfacet + facet normal 0.158578 0.425854 0.890787 + outer loop + vertex 1.5294 2.10477 2.47128 + vertex 1.53399 2.10387 2.47089 + vertex 1.53185 2.10715 2.4697 + endloop + endfacet + facet normal 0.148835 0.363869 0.919482 + outer loop + vertex 1.53399 2.10387 2.47089 + vertex 1.5294 2.10477 2.47128 + vertex 1.53123 2.10083 2.47254 + endloop + endfacet + facet normal 0.13733 0.359605 0.922943 + outer loop + vertex 1.53123 2.10083 2.47254 + vertex 1.5294 2.10477 2.47128 + vertex 1.52586 2.10184 2.47295 + endloop + endfacet + facet normal 0.131742 0.324213 0.936766 + outer loop + vertex 1.5284 2.09697 2.47427 + vertex 1.53123 2.10083 2.47254 + vertex 1.52586 2.10184 2.47295 + endloop + endfacet + facet normal 0.128081 0.326731 0.936399 + outer loop + vertex 1.53302 2.0975 2.47346 + vertex 1.53123 2.10083 2.47254 + vertex 1.5284 2.09697 2.47427 + endloop + endfacet + facet normal 0.130698 0.31133 0.941271 + outer loop + vertex 1.5284 2.09697 2.47427 + vertex 1.53277 2.09367 2.47476 + vertex 1.53302 2.0975 2.47346 + endloop + endfacet + facet normal 0.131699 0.311227 0.941166 + outer loop + vertex 1.53277 2.09367 2.47476 + vertex 1.53626 2.096 2.4735 + vertex 1.53302 2.0975 2.47346 + endloop + endfacet + facet normal 0.138537 0.325867 0.93521 + outer loop + vertex 1.53626 2.096 2.4735 + vertex 1.53628 2.09981 2.47217 + vertex 1.53302 2.0975 2.47346 + endloop + endfacet + facet normal 0.133061 0.326136 0.935911 + outer loop + vertex 1.53628 2.09981 2.47217 + vertex 1.53626 2.096 2.4735 + vertex 1.54077 2.09659 2.47265 + endloop + endfacet + facet normal 0.140629 0.336 0.931304 + outer loop + vertex 1.54038 2.10056 2.47128 + vertex 1.53628 2.09981 2.47217 + vertex 1.54077 2.09659 2.47265 + endloop + endfacet + facet normal 0.136921 0.335848 0.931912 + outer loop + vertex 1.54038 2.10056 2.47128 + vertex 1.54077 2.09659 2.47265 + vertex 1.54449 2.0994 2.4711 + endloop + endfacet + facet normal 0.153196 0.397467 0.904738 + outer loop + vertex 1.54449 2.0994 2.4711 + vertex 1.54222 2.10372 2.46958 + vertex 1.54038 2.10056 2.47128 + endloop + endfacet + facet normal 0.13253 0.389063 0.911628 + outer loop + vertex 1.54222 2.10372 2.46958 + vertex 1.54449 2.0994 2.4711 + vertex 1.54827 2.10195 2.46946 + endloop + endfacet + facet normal 0.14092 0.378629 0.914758 + outer loop + vertex 1.54449 2.0994 2.4711 + vertex 1.54859 2.09824 2.47094 + vertex 1.54827 2.10195 2.46946 + endloop + endfacet + facet normal 0.13588 0.378508 0.91557 + outer loop + vertex 1.54859 2.09824 2.47094 + vertex 1.55278 2.09889 2.47005 + vertex 1.54827 2.10195 2.46946 + endloop + endfacet + facet normal 0.145127 0.338526 0.929698 + outer loop + vertex 1.54859 2.09824 2.47094 + vertex 1.55074 2.09571 2.47153 + vertex 1.55278 2.09889 2.47005 + endloop + endfacet + facet normal 0.147102 0.337318 0.929826 + outer loop + vertex 1.55473 2.09456 2.47132 + vertex 1.55278 2.09889 2.47005 + vertex 1.55074 2.09571 2.47153 + endloop + endfacet + facet normal 0.139852 0.310329 0.940286 + outer loop + vertex 1.55074 2.09571 2.47153 + vertex 1.5509 2.09169 2.47283 + vertex 1.55473 2.09456 2.47132 + endloop + endfacet + facet normal 0.139704 0.310509 0.940249 + outer loop + vertex 1.55644 2.09022 2.47249 + vertex 1.55473 2.09456 2.47132 + vertex 1.5509 2.09169 2.47283 + endloop + endfacet + facet normal 0.13874 0.306546 0.94169 + outer loop + vertex 1.55299 2.08786 2.47377 + vertex 1.55644 2.09022 2.47249 + vertex 1.5509 2.09169 2.47283 + endloop + endfacet + facet normal 0.13696 0.305704 0.942225 + outer loop + vertex 1.55299 2.08786 2.47377 + vertex 1.5509 2.09169 2.47283 + vertex 1.54845 2.08731 2.47461 + endloop + endfacet + facet normal 0.138322 0.310059 0.940601 + outer loop + vertex 1.55869 2.09343 2.4711 + vertex 1.55473 2.09456 2.47132 + vertex 1.55644 2.09022 2.47249 + endloop + endfacet + facet normal 0.144176 0.332292 0.932092 + outer loop + vertex 1.55473 2.09456 2.47132 + vertex 1.55869 2.09343 2.4711 + vertex 1.55856 2.09743 2.4697 + endloop + endfacet + facet normal 0.135991 0.310355 0.940843 + outer loop + vertex 1.55074 2.09571 2.47153 + vertex 1.54643 2.09511 2.47235 + vertex 1.5509 2.09169 2.47283 + endloop + endfacet + facet normal 0.134718 0.308787 0.941542 + outer loop + vertex 1.54643 2.09511 2.47235 + vertex 1.54633 2.09116 2.47366 + vertex 1.5509 2.09169 2.47283 + endloop + endfacet + facet normal 0.135071 0.306732 0.942163 + outer loop + vertex 1.54845 2.08731 2.47461 + vertex 1.5509 2.09169 2.47283 + vertex 1.54633 2.09116 2.47366 + endloop + endfacet + facet normal 0.134047 0.306243 0.942468 + outer loop + vertex 1.54845 2.08731 2.47461 + vertex 1.54633 2.09116 2.47366 + vertex 1.54283 2.08885 2.47491 + endloop + endfacet + facet normal 0.134625 0.308523 0.941642 + outer loop + vertex 1.54283 2.08885 2.47491 + vertex 1.54459 2.08446 2.47609 + vertex 1.54845 2.08731 2.47461 + endloop + endfacet + facet normal 0.134605 0.308548 0.941637 + outer loop + vertex 1.54459 2.08446 2.47609 + vertex 1.54858 2.0833 2.4759 + vertex 1.54845 2.08731 2.47461 + endloop + endfacet + facet normal 0.138068 0.308503 0.94115 + outer loop + vertex 1.54858 2.0833 2.4759 + vertex 1.55286 2.08391 2.47508 + vertex 1.54845 2.08731 2.47461 + endloop + endfacet + facet normal 0.136751 0.306894 0.941868 + outer loop + vertex 1.54845 2.08731 2.47461 + vertex 1.55286 2.08391 2.47508 + vertex 1.55299 2.08786 2.47377 + endloop + endfacet + facet normal 0.140621 0.306602 0.941393 + outer loop + vertex 1.55286 2.08391 2.47508 + vertex 1.55629 2.08628 2.47379 + vertex 1.55299 2.08786 2.47377 + endloop + endfacet + facet normal 0.139877 0.305061 0.942004 + outer loop + vertex 1.55629 2.08628 2.47379 + vertex 1.55644 2.09022 2.47249 + vertex 1.55299 2.08786 2.47377 + endloop + endfacet + facet normal 0.143738 0.304754 0.941522 + outer loop + vertex 1.55644 2.09022 2.47249 + vertex 1.55629 2.08628 2.47379 + vertex 1.56074 2.08702 2.47287 + endloop + endfacet + facet normal 0.141982 0.302517 0.94251 + outer loop + vertex 1.56067 2.09093 2.47163 + vertex 1.55644 2.09022 2.47249 + vertex 1.56074 2.08702 2.47287 + endloop + endfacet + facet normal 0.148205 0.302347 0.941606 + outer loop + vertex 1.56067 2.09093 2.47163 + vertex 1.56074 2.08702 2.47287 + vertex 1.56456 2.08999 2.47132 + endloop + endfacet + facet normal 0.149708 0.309382 0.93908 + outer loop + vertex 1.56456 2.08999 2.47132 + vertex 1.56287 2.09413 2.47022 + vertex 1.56067 2.09093 2.47163 + endloop + endfacet + facet normal 0.14563 0.312087 0.938826 + outer loop + vertex 1.55869 2.09343 2.4711 + vertex 1.56067 2.09093 2.47163 + vertex 1.56287 2.09413 2.47022 + endloop + endfacet + facet normal 0.140944 0.332357 0.932563 + outer loop + vertex 1.55869 2.09343 2.4711 + vertex 1.56287 2.09413 2.47022 + vertex 1.55856 2.09743 2.4697 + endloop + endfacet + facet normal 0.143984 0.336035 0.930779 + outer loop + vertex 1.55856 2.09743 2.4697 + vertex 1.56287 2.09413 2.47022 + vertex 1.56315 2.09779 2.46886 + endloop + endfacet + facet normal 0.136064 0.390576 0.91046 + outer loop + vertex 1.56315 2.09779 2.46886 + vertex 1.56124 2.10103 2.46775 + vertex 1.55856 2.09743 2.4697 + endloop + endfacet + facet normal 0.145061 0.384537 0.911641 + outer loop + vertex 1.55856 2.09743 2.4697 + vertex 1.56124 2.10103 2.46775 + vertex 1.55584 2.10215 2.46814 + endloop + endfacet + facet normal 0.154462 0.399156 0.903779 + outer loop + vertex 1.56315 2.09779 2.46886 + vertex 1.56626 2.09992 2.46739 + vertex 1.56124 2.10103 2.46775 + endloop + endfacet + facet normal 0.169166 0.381249 0.908863 + outer loop + vertex 1.56625 2.09635 2.46889 + vertex 1.56626 2.09992 2.46739 + vertex 1.56315 2.09779 2.46886 + endloop + endfacet + facet normal 0.1669 0.381405 0.909216 + outer loop + vertex 1.56626 2.09992 2.46739 + vertex 1.56625 2.09635 2.46889 + vertex 1.57061 2.09678 2.46791 + endloop + endfacet + facet normal 0.175605 0.332839 0.926489 + outer loop + vertex 1.56787 2.09302 2.46978 + vertex 1.57061 2.09678 2.46791 + vertex 1.56625 2.09635 2.46889 + endloop + endfacet + facet normal 0.155761 0.324863 0.932846 + outer loop + vertex 1.56787 2.09302 2.46978 + vertex 1.56625 2.09635 2.46889 + vertex 1.56287 2.09413 2.47022 + endloop + endfacet + facet normal 0.164033 0.340869 0.92569 + outer loop + vertex 1.57339 2.09184 2.46923 + vertex 1.57061 2.09678 2.46791 + vertex 1.56787 2.09302 2.46978 + endloop + endfacet + facet normal 0.158532 0.309753 0.937508 + outer loop + vertex 1.56787 2.09302 2.46978 + vertex 1.56936 2.08886 2.4709 + vertex 1.57339 2.09184 2.46923 + endloop + endfacet + facet normal 0.15815 0.310221 0.937417 + outer loop + vertex 1.56936 2.08886 2.4709 + vertex 1.57346 2.0877 2.47059 + vertex 1.57339 2.09184 2.46923 + endloop + endfacet + facet normal 0.155288 0.310318 0.937864 + outer loop + vertex 1.57346 2.0877 2.47059 + vertex 1.57826 2.0881 2.46966 + vertex 1.57339 2.09184 2.46923 + endloop + endfacet + facet normal 0.15499 0.309948 0.938035 + outer loop + vertex 1.57339 2.09184 2.46923 + vertex 1.57826 2.0881 2.46966 + vertex 1.57803 2.09232 2.46831 + endloop + endfacet + facet normal 0.148444 0.348551 0.92546 + outer loop + vertex 1.57803 2.09232 2.46831 + vertex 1.57599 2.09573 2.46735 + vertex 1.57339 2.09184 2.46923 + endloop + endfacet + facet normal 0.149961 0.349312 0.924928 + outer loop + vertex 1.57803 2.09232 2.46831 + vertex 1.58105 2.09466 2.46694 + vertex 1.57599 2.09573 2.46735 + endloop + endfacet + facet normal 0.158552 0.339521 0.927139 + outer loop + vertex 1.58122 2.09103 2.46823 + vertex 1.58105 2.09466 2.46694 + vertex 1.57803 2.09232 2.46831 + endloop + endfacet + facet normal 0.154096 0.339576 0.92787 + outer loop + vertex 1.58105 2.09466 2.46694 + vertex 1.58122 2.09103 2.46823 + vertex 1.58541 2.09148 2.46737 + endloop + endfacet + facet normal 0.157246 0.343617 0.925852 + outer loop + vertex 1.58491 2.09524 2.46606 + vertex 1.58105 2.09466 2.46694 + vertex 1.58541 2.09148 2.46737 + endloop + endfacet + facet normal 0.16764 0.344277 0.92378 + outer loop + vertex 1.58491 2.09524 2.46606 + vertex 1.58541 2.09148 2.46737 + vertex 1.58883 2.09412 2.46577 + endloop + endfacet + facet normal 0.187406 0.423828 0.886143 + outer loop + vertex 1.58883 2.09412 2.46577 + vertex 1.58626 2.09783 2.46454 + vertex 1.58491 2.09524 2.46606 + endloop + endfacet + facet normal 0.16854 0.343242 0.924002 + outer loop + vertex 1.59108 2.08955 2.46706 + vertex 1.58883 2.09412 2.46577 + vertex 1.58541 2.09148 2.46737 + endloop + endfacet + facet normal 0.156143 0.30415 0.93974 + outer loop + vertex 1.58714 2.08697 2.46855 + vertex 1.59108 2.08955 2.46706 + vertex 1.58541 2.09148 2.46737 + endloop + endfacet + facet normal 0.16166 0.305877 0.938246 + outer loop + vertex 1.58714 2.08697 2.46855 + vertex 1.58541 2.09148 2.46737 + vertex 1.58304 2.08841 2.46878 + endloop + endfacet + facet normal 0.157151 0.292257 0.94334 + outer loop + vertex 1.58299 2.08437 2.47004 + vertex 1.58714 2.08697 2.46855 + vertex 1.58304 2.08841 2.46878 + endloop + endfacet + facet normal 0.154915 0.292389 0.943668 + outer loop + vertex 1.57826 2.0881 2.46966 + vertex 1.58299 2.08437 2.47004 + vertex 1.58304 2.08841 2.46878 + endloop + endfacet + facet normal 0.15358 0.303651 0.940324 + outer loop + vertex 1.58304 2.08841 2.46878 + vertex 1.58122 2.09103 2.46823 + vertex 1.57826 2.0881 2.46966 + endloop + endfacet + facet normal 0.158474 0.296699 0.94173 + outer loop + vertex 1.57856 2.0839 2.47094 + vertex 1.58299 2.08437 2.47004 + vertex 1.57826 2.0881 2.46966 + endloop + endfacet + facet normal 0.159211 0.296714 0.941601 + outer loop + vertex 1.57856 2.0839 2.47094 + vertex 1.57826 2.0881 2.46966 + vertex 1.57539 2.08502 2.47112 + endloop + endfacet + facet normal 0.159303 0.296989 0.941499 + outer loop + vertex 1.57539 2.08502 2.47112 + vertex 1.57578 2.08078 2.47239 + vertex 1.57856 2.0839 2.47094 + endloop + endfacet + facet normal 0.160825 0.295698 0.941646 + outer loop + vertex 1.58052 2.08113 2.47147 + vertex 1.57856 2.0839 2.47094 + vertex 1.57578 2.08078 2.47239 + endloop + endfacet + facet normal 0.160702 0.29664 0.941371 + outer loop + vertex 1.58052 2.08113 2.47147 + vertex 1.57578 2.08078 2.47239 + vertex 1.58066 2.07691 2.47278 + endloop + endfacet + facet normal 0.16115 0.296632 0.941297 + outer loop + vertex 1.58052 2.08113 2.47147 + vertex 1.58066 2.07691 2.47278 + vertex 1.58464 2.07972 2.47121 + endloop + endfacet + facet normal 0.160321 0.297696 0.941103 + outer loop + vertex 1.58632 2.07519 2.47235 + vertex 1.58464 2.07972 2.47121 + vertex 1.58066 2.07691 2.47278 + endloop + endfacet + facet normal 0.160244 0.297414 0.941205 + outer loop + vertex 1.58285 2.07286 2.47368 + vertex 1.58632 2.07519 2.47235 + vertex 1.58066 2.07691 2.47278 + endloop + endfacet + facet normal 0.159146 0.296899 0.941554 + outer loop + vertex 1.58285 2.07286 2.47368 + vertex 1.58066 2.07691 2.47278 + vertex 1.57833 2.07234 2.47461 + endloop + endfacet + facet normal 0.159298 0.296017 0.941806 + outer loop + vertex 1.57833 2.07234 2.47461 + vertex 1.58271 2.06881 2.47498 + vertex 1.58285 2.07286 2.47368 + endloop + endfacet + facet normal 0.157595 0.296154 0.942049 + outer loop + vertex 1.58271 2.06881 2.47498 + vertex 1.58617 2.07114 2.47367 + vertex 1.58285 2.07286 2.47368 + endloop + endfacet + facet normal 0.15677 0.29726 0.941838 + outer loop + vertex 1.58824 2.06723 2.47456 + vertex 1.58617 2.07114 2.47367 + vertex 1.58271 2.06881 2.47498 + endloop + endfacet + facet normal 0.156266 0.295311 0.942535 + outer loop + vertex 1.58271 2.06881 2.47498 + vertex 1.58445 2.06443 2.47606 + vertex 1.58824 2.06723 2.47456 + endloop + endfacet + facet normal 0.155658 0.296063 0.9424 + outer loop + vertex 1.58445 2.06443 2.47606 + vertex 1.58837 2.06317 2.47581 + vertex 1.58824 2.06723 2.47456 + endloop + endfacet + facet normal 0.155333 0.294978 0.942794 + outer loop + vertex 1.58837 2.06317 2.47581 + vertex 1.58445 2.06443 2.47606 + vertex 1.58628 2.06011 2.47712 + endloop + endfacet + facet normal 0.158477 0.296092 0.941921 + outer loop + vertex 1.58628 2.06011 2.47712 + vertex 1.58445 2.06443 2.47606 + vertex 1.58079 2.06183 2.4775 + endloop + endfacet + facet normal 0.158847 0.29737 0.941456 + outer loop + vertex 1.5832 2.05798 2.47831 + vertex 1.58628 2.06011 2.47712 + vertex 1.58079 2.06183 2.4775 + endloop + endfacet + facet normal 0.182995 0.310645 0.932745 + outer loop + vertex 1.5832 2.05798 2.47831 + vertex 1.58079 2.06183 2.4775 + vertex 1.57872 2.05766 2.47929 + endloop + endfacet + facet normal 0.182685 0.31286 0.932065 + outer loop + vertex 1.57872 2.05766 2.47929 + vertex 1.58373 2.05368 2.47965 + vertex 1.5832 2.05798 2.47831 + endloop + endfacet + facet normal 0.168513 0.312035 0.935007 + outer loop + vertex 1.58373 2.05368 2.47965 + vertex 1.58641 2.0564 2.47825 + vertex 1.5832 2.05798 2.47831 + endloop + endfacet + facet normal 0.177865 0.303416 0.93611 + outer loop + vertex 1.58826 2.05366 2.47879 + vertex 1.58641 2.0564 2.47825 + vertex 1.58373 2.05368 2.47965 + endloop + endfacet + facet normal 0.178636 0.288837 0.940565 + outer loop + vertex 1.58373 2.05368 2.47965 + vertex 1.58838 2.04961 2.48001 + vertex 1.58826 2.05366 2.47879 + endloop + endfacet + facet normal 0.161804 0.289193 0.943497 + outer loop + vertex 1.58838 2.04961 2.48001 + vertex 1.5921 2.05205 2.47863 + vertex 1.58826 2.05366 2.47879 + endloop + endfacet + facet normal 0.162468 0.290848 0.942874 + outer loop + vertex 1.5921 2.05205 2.47863 + vertex 1.5905 2.05662 2.47749 + vertex 1.58826 2.05366 2.47879 + endloop + endfacet + facet normal 0.161552 0.290587 0.943112 + outer loop + vertex 1.5921 2.05205 2.47863 + vertex 1.59594 2.0547 2.47715 + vertex 1.5905 2.05662 2.47749 + endloop + endfacet + facet normal 0.161715 0.291083 0.942931 + outer loop + vertex 1.59594 2.0547 2.47715 + vertex 1.59431 2.05925 2.47603 + vertex 1.5905 2.05662 2.47749 + endloop + endfacet + facet normal 0.162392 0.291281 0.942754 + outer loop + vertex 1.59829 2.05802 2.47572 + vertex 1.59431 2.05925 2.47603 + vertex 1.59594 2.0547 2.47715 + endloop + endfacet + facet normal 0.158124 0.294229 0.942564 + outer loop + vertex 1.60031 2.05543 2.47619 + vertex 1.59829 2.05802 2.47572 + vertex 1.59594 2.0547 2.47715 + endloop + endfacet + facet normal 0.15793 0.295081 0.94233 + outer loop + vertex 1.60031 2.05543 2.47619 + vertex 1.59594 2.0547 2.47715 + vertex 1.60028 2.05145 2.47744 + endloop + endfacet + facet normal 0.132084 0.296396 0.945888 + outer loop + vertex 1.60031 2.05543 2.47619 + vertex 1.60028 2.05145 2.47744 + vertex 1.60434 2.05457 2.4759 + endloop + endfacet + facet normal 0.133047 0.301489 0.944141 + outer loop + vertex 1.60434 2.05457 2.4759 + vertex 1.60269 2.05886 2.47476 + vertex 1.60031 2.05543 2.47619 + endloop + endfacet + facet normal 0.15373 0.289682 0.944696 + outer loop + vertex 1.59594 2.0547 2.47715 + vertex 1.59593 2.05064 2.4784 + vertex 1.60028 2.05145 2.47744 + endloop + endfacet + facet normal 0.155264 0.283405 0.946348 + outer loop + vertex 1.59792 2.04802 2.47886 + vertex 1.60028 2.05145 2.47744 + vertex 1.59593 2.05064 2.4784 + endloop + endfacet + facet normal 0.159626 0.286422 0.944713 + outer loop + vertex 1.59792 2.04802 2.47886 + vertex 1.59593 2.05064 2.4784 + vertex 1.59367 2.04744 2.47975 + endloop + endfacet + facet normal 0.160016 0.284411 0.945254 + outer loop + vertex 1.59367 2.04744 2.47975 + vertex 1.59795 2.04398 2.48007 + vertex 1.59792 2.04802 2.47886 + endloop + endfacet + facet normal 0.141488 0.285108 0.947995 + outer loop + vertex 1.59795 2.04398 2.48007 + vertex 1.60205 2.04705 2.47853 + vertex 1.59792 2.04802 2.47886 + endloop + endfacet + facet normal 0.134279 0.293924 0.94635 + outer loop + vertex 1.60373 2.04248 2.47971 + vertex 1.60205 2.04705 2.47853 + vertex 1.59795 2.04398 2.48007 + endloop + endfacet + facet normal 0.129564 0.274176 0.952912 + outer loop + vertex 1.59795 2.04398 2.48007 + vertex 1.59949 2.03941 2.48117 + vertex 1.60373 2.04248 2.47971 + endloop + endfacet + facet normal 0.12562 0.279194 0.951982 + outer loop + vertex 1.59949 2.03941 2.48117 + vertex 1.60345 2.03832 2.48097 + vertex 1.60373 2.04248 2.47971 + endloop + endfacet + facet normal 0.0726685 0.283991 0.956069 + outer loop + vertex 1.60345 2.03832 2.48097 + vertex 1.60787 2.03946 2.48029 + vertex 1.60373 2.04248 2.47971 + endloop + endfacet + facet normal 0.0820846 0.296075 0.951631 + outer loop + vertex 1.60373 2.04248 2.47971 + vertex 1.60787 2.03946 2.48029 + vertex 1.60858 2.04339 2.47901 + endloop + endfacet + facet normal 0.0810366 0.300611 0.950298 + outer loop + vertex 1.60858 2.04339 2.47901 + vertex 1.60707 2.04656 2.47814 + vertex 1.60373 2.04248 2.47971 + endloop + endfacet + facet normal 0.0492676 0.287177 0.95661 + outer loop + vertex 1.60858 2.04339 2.47901 + vertex 1.61186 2.04639 2.47794 + vertex 1.60707 2.04656 2.47814 + endloop + endfacet + facet normal 0.0496599 0.30562 0.950858 + outer loop + vertex 1.61186 2.04639 2.47794 + vertex 1.61065 2.05015 2.4768 + vertex 1.60707 2.04656 2.47814 + endloop + endfacet + facet normal 0.0680187 0.288904 0.954939 + outer loop + vertex 1.60707 2.04656 2.47814 + vertex 1.61065 2.05015 2.4768 + vertex 1.60561 2.05052 2.47705 + endloop + endfacet + facet normal 0.0694227 0.31405 0.946865 + outer loop + vertex 1.61065 2.05015 2.4768 + vertex 1.60926 2.05399 2.47562 + vertex 1.60561 2.05052 2.47705 + endloop + endfacet + facet normal 0.0878087 0.296467 0.950998 + outer loop + vertex 1.60926 2.05399 2.47562 + vertex 1.60434 2.05457 2.4759 + vertex 1.60561 2.05052 2.47705 + endloop + endfacet + facet normal 0.124097 0.305858 0.943955 + outer loop + vertex 1.60561 2.05052 2.47705 + vertex 1.60434 2.05457 2.4759 + vertex 1.60028 2.05145 2.47744 + endloop + endfacet + facet normal 0.120806 0.284104 0.951152 + outer loop + vertex 1.60205 2.04705 2.47853 + vertex 1.60561 2.05052 2.47705 + vertex 1.60028 2.05145 2.47744 + endloop + endfacet + facet normal 0.103826 0.300241 0.948196 + outer loop + vertex 1.60707 2.04656 2.47814 + vertex 1.60561 2.05052 2.47705 + vertex 1.60205 2.04705 2.47853 + endloop + endfacet + facet normal 0.0898321 0.317127 0.944119 + outer loop + vertex 1.60434 2.05457 2.4759 + vertex 1.60926 2.05399 2.47562 + vertex 1.60782 2.0578 2.47448 + endloop + endfacet + facet normal 0.112444 0.294856 0.948902 + outer loop + vertex 1.60269 2.05886 2.47476 + vertex 1.60434 2.05457 2.4759 + vertex 1.60782 2.0578 2.47448 + endloop + endfacet + facet normal 0.116296 0.315282 0.941845 + outer loop + vertex 1.60782 2.0578 2.47448 + vertex 1.60688 2.06165 2.47331 + vertex 1.60269 2.05886 2.47476 + endloop + endfacet + facet normal 0.12647 0.301664 0.944989 + outer loop + vertex 1.60269 2.05886 2.47476 + vertex 1.60688 2.06165 2.47331 + vertex 1.60288 2.06294 2.47343 + endloop + endfacet + facet normal 0.155515 0.299213 0.941428 + outer loop + vertex 1.59823 2.0622 2.47444 + vertex 1.60269 2.05886 2.47476 + vertex 1.60288 2.06294 2.47343 + endloop + endfacet + facet normal 0.155666 0.298533 0.941619 + outer loop + vertex 1.60288 2.06294 2.47343 + vertex 1.60063 2.06673 2.4726 + vertex 1.59823 2.0622 2.47444 + endloop + endfacet + facet normal 0.163125 0.294584 0.9416 + outer loop + vertex 1.59823 2.0622 2.47444 + vertex 1.60063 2.06673 2.4726 + vertex 1.59611 2.0661 2.47358 + endloop + endfacet + facet normal 0.16219 0.29924 0.940293 + outer loop + vertex 1.59626 2.07012 2.47228 + vertex 1.59611 2.0661 2.47358 + vertex 1.60063 2.06673 2.4726 + endloop + endfacet + facet normal 0.162874 0.299182 0.940193 + outer loop + vertex 1.59611 2.0661 2.47358 + vertex 1.59626 2.07012 2.47228 + vertex 1.59278 2.06777 2.47363 + endloop + endfacet + facet normal 0.161037 0.295484 0.941677 + outer loop + vertex 1.59262 2.06373 2.47492 + vertex 1.59611 2.0661 2.47358 + vertex 1.59278 2.06777 2.47363 + endloop + endfacet + facet normal 0.157673 0.295771 0.942157 + outer loop + vertex 1.58824 2.06723 2.47456 + vertex 1.59262 2.06373 2.47492 + vertex 1.59278 2.06777 2.47363 + endloop + endfacet + facet normal 0.157054 0.299247 0.941162 + outer loop + vertex 1.59278 2.06777 2.47363 + vertex 1.5907 2.07168 2.47273 + vertex 1.58824 2.06723 2.47456 + endloop + endfacet + facet normal 0.161344 0.301224 0.939804 + outer loop + vertex 1.59278 2.06777 2.47363 + vertex 1.59626 2.07012 2.47228 + vertex 1.5907 2.07168 2.47273 + endloop + endfacet + facet normal 0.161401 0.301451 0.939722 + outer loop + vertex 1.59626 2.07012 2.47228 + vertex 1.59456 2.07454 2.47115 + vertex 1.5907 2.07168 2.47273 + endloop + endfacet + facet normal 0.161497 0.301332 0.939743 + outer loop + vertex 1.59062 2.07575 2.47144 + vertex 1.5907 2.07168 2.47273 + vertex 1.59456 2.07454 2.47115 + endloop + endfacet + facet normal 0.160903 0.29921 0.940523 + outer loop + vertex 1.59456 2.07454 2.47115 + vertex 1.59291 2.07894 2.47003 + vertex 1.59062 2.07575 2.47144 + endloop + endfacet + facet normal 0.160807 0.299277 0.940518 + outer loop + vertex 1.58864 2.07839 2.47094 + vertex 1.59062 2.07575 2.47144 + vertex 1.59291 2.07894 2.47003 + endloop + endfacet + facet normal 0.162026 0.292839 0.942334 + outer loop + vertex 1.58864 2.07839 2.47094 + vertex 1.59291 2.07894 2.47003 + vertex 1.58869 2.08238 2.46969 + endloop + endfacet + facet normal 0.160917 0.292906 0.942503 + outer loop + vertex 1.58464 2.07972 2.47121 + vertex 1.58864 2.07839 2.47094 + vertex 1.58869 2.08238 2.46969 + endloop + endfacet + facet normal 0.160432 0.293572 0.942378 + outer loop + vertex 1.58299 2.08437 2.47004 + vertex 1.58464 2.07972 2.47121 + vertex 1.58869 2.08238 2.46969 + endloop + endfacet + facet normal 0.160143 0.293488 0.942454 + outer loop + vertex 1.58464 2.07972 2.47121 + vertex 1.58299 2.08437 2.47004 + vertex 1.58052 2.08113 2.47147 + endloop + endfacet + facet normal 0.160277 0.290786 0.943268 + outer loop + vertex 1.58869 2.08238 2.46969 + vertex 1.59291 2.07894 2.47003 + vertex 1.59307 2.08279 2.46882 + endloop + endfacet + facet normal 0.160875 0.286751 0.944401 + outer loop + vertex 1.59307 2.08279 2.46882 + vertex 1.59126 2.0855 2.46831 + vertex 1.58869 2.08238 2.46969 + endloop + endfacet + facet normal 0.157874 0.289127 0.944183 + outer loop + vertex 1.58869 2.08238 2.46969 + vertex 1.59126 2.0855 2.46831 + vertex 1.58714 2.08697 2.46855 + endloop + endfacet + facet normal 0.161313 0.287015 0.944246 + outer loop + vertex 1.59307 2.08279 2.46882 + vertex 1.59594 2.08572 2.46744 + vertex 1.59126 2.0855 2.46831 + endloop + endfacet + facet normal 0.161586 0.286761 0.944276 + outer loop + vertex 1.59628 2.08134 2.46871 + vertex 1.59594 2.08572 2.46744 + vertex 1.59307 2.08279 2.46882 + endloop + endfacet + facet normal 0.164363 0.286829 0.943776 + outer loop + vertex 1.59594 2.08572 2.46744 + vertex 1.59628 2.08134 2.46871 + vertex 1.60078 2.08181 2.46779 + endloop + endfacet + facet normal 0.165584 0.288283 0.94312 + outer loop + vertex 1.60055 2.08596 2.46656 + vertex 1.59594 2.08572 2.46744 + vertex 1.60078 2.08181 2.46779 + endloop + endfacet + facet normal 0.167778 0.288289 0.94273 + outer loop + vertex 1.60055 2.08596 2.46656 + vertex 1.60078 2.08181 2.46779 + vertex 1.60457 2.08452 2.46628 + endloop + endfacet + facet normal 0.17698 0.31613 0.932062 + outer loop + vertex 1.60457 2.08452 2.46628 + vertex 1.60249 2.08917 2.4651 + vertex 1.60055 2.08596 2.46656 + endloop + endfacet + facet normal 0.181552 0.313381 0.932111 + outer loop + vertex 1.59847 2.08873 2.46603 + vertex 1.60055 2.08596 2.46656 + vertex 1.60249 2.08917 2.4651 + endloop + endfacet + facet normal 0.173145 0.359245 0.917041 + outer loop + vertex 1.59847 2.08873 2.46603 + vertex 1.60249 2.08917 2.4651 + vertex 1.59766 2.09293 2.46454 + endloop + endfacet + facet normal 0.174263 0.36057 0.916309 + outer loop + vertex 1.59766 2.09293 2.46454 + vertex 1.60249 2.08917 2.4651 + vertex 1.60178 2.09255 2.4639 + endloop + endfacet + facet normal 0.196556 0.363252 0.910721 + outer loop + vertex 1.60249 2.08917 2.4651 + vertex 1.60576 2.09245 2.46309 + vertex 1.60178 2.09255 2.4639 + endloop + endfacet + facet normal 0.159429 0.309615 0.937401 + outer loop + vertex 1.60249 2.08917 2.4651 + vertex 1.60457 2.08452 2.46628 + vertex 1.60837 2.08734 2.4647 + endloop + endfacet + facet normal 0.178982 0.379032 0.90791 + outer loop + vertex 1.60837 2.08734 2.4647 + vertex 1.60576 2.09245 2.46309 + vertex 1.60249 2.08917 2.4651 + endloop + endfacet + facet normal 0.145651 0.365584 0.919312 + outer loop + vertex 1.60837 2.08734 2.4647 + vertex 1.61118 2.09098 2.46281 + vertex 1.60576 2.09245 2.46309 + endloop + endfacet + facet normal 0.123854 0.380813 0.91632 + outer loop + vertex 1.61307 2.08766 2.46394 + vertex 1.61118 2.09098 2.46281 + vertex 1.60837 2.08734 2.4647 + endloop + endfacet + facet normal 0.115609 0.37703 0.918958 + outer loop + vertex 1.61307 2.08766 2.46394 + vertex 1.61635 2.09002 2.46256 + vertex 1.61118 2.09098 2.46281 + endloop + endfacet + facet normal 0.107402 0.386646 0.915953 + outer loop + vertex 1.61636 2.08644 2.46407 + vertex 1.61635 2.09002 2.46256 + vertex 1.61307 2.08766 2.46394 + endloop + endfacet + facet normal 0.0631722 0.387963 0.919508 + outer loop + vertex 1.61635 2.09002 2.46256 + vertex 1.61636 2.08644 2.46407 + vertex 1.62127 2.08771 2.46319 + endloop + endfacet + facet normal 0.0748712 0.352129 0.932952 + outer loop + vertex 1.6179 2.0834 2.46509 + vertex 1.62127 2.08771 2.46319 + vertex 1.61636 2.08644 2.46407 + endloop + endfacet + facet normal 0.0745538 0.351994 0.933028 + outer loop + vertex 1.6179 2.0834 2.46509 + vertex 1.61636 2.08644 2.46407 + vertex 1.61278 2.08397 2.46528 + endloop + endfacet + facet normal 0.0705407 0.310955 0.947803 + outer loop + vertex 1.61278 2.08397 2.46528 + vertex 1.61448 2.07996 2.46647 + vertex 1.6179 2.0834 2.46509 + endloop + endfacet + facet normal 0.042822 0.335755 0.940976 + outer loop + vertex 1.61448 2.07996 2.46647 + vertex 1.61934 2.07963 2.46637 + vertex 1.6179 2.0834 2.46509 + endloop + endfacet + facet normal 0.035101 0.33321 0.942199 + outer loop + vertex 1.6179 2.0834 2.46509 + vertex 1.61934 2.07963 2.46637 + vertex 1.62292 2.08328 2.46494 + endloop + endfacet + facet normal 0.0356514 0.379099 0.924669 + outer loop + vertex 1.62292 2.08328 2.46494 + vertex 1.62127 2.08771 2.46319 + vertex 1.6179 2.0834 2.46509 + endloop + endfacet + facet normal 0.0418735 0.319941 0.946512 + outer loop + vertex 1.61934 2.07963 2.46637 + vertex 1.61448 2.07996 2.46647 + vertex 1.61594 2.07608 2.46772 + endloop + endfacet + facet normal 0.0716161 0.329472 0.941445 + outer loop + vertex 1.61594 2.07608 2.46772 + vertex 1.61448 2.07996 2.46647 + vertex 1.61055 2.07671 2.46791 + endloop + endfacet + facet normal 0.0700082 0.31407 0.946815 + outer loop + vertex 1.61301 2.07193 2.46931 + vertex 1.61594 2.07608 2.46772 + vertex 1.61055 2.07671 2.46791 + endloop + endfacet + facet normal 0.0939972 0.324726 0.941126 + outer loop + vertex 1.61301 2.07193 2.46931 + vertex 1.61055 2.07671 2.46791 + vertex 1.60765 2.07278 2.46955 + endloop + endfacet + facet normal 0.0911963 0.305108 0.947941 + outer loop + vertex 1.60765 2.07278 2.46955 + vertex 1.60918 2.06866 2.47073 + vertex 1.61301 2.07193 2.46931 + endloop + endfacet + facet normal 0.126773 0.316087 0.940222 + outer loop + vertex 1.60444 2.06968 2.47103 + vertex 1.60918 2.06866 2.47073 + vertex 1.60765 2.07278 2.46955 + endloop + endfacet + facet normal 0.141767 0.301742 0.94279 + outer loop + vertex 1.60266 2.07396 2.46993 + vertex 1.60444 2.06968 2.47103 + vertex 1.60765 2.07278 2.46955 + endloop + endfacet + facet normal 0.145033 0.317423 0.937128 + outer loop + vertex 1.60765 2.07278 2.46955 + vertex 1.60604 2.0762 2.46865 + vertex 1.60266 2.07396 2.46993 + endloop + endfacet + facet normal 0.155929 0.302792 0.940214 + outer loop + vertex 1.60266 2.07396 2.46993 + vertex 1.60604 2.0762 2.46865 + vertex 1.60288 2.07785 2.46864 + endloop + endfacet + facet normal 0.164658 0.301891 0.939015 + outer loop + vertex 1.5984 2.07739 2.46957 + vertex 1.60266 2.07396 2.46993 + vertex 1.60288 2.07785 2.46864 + endloop + endfacet + facet normal 0.16642 0.291056 0.942121 + outer loop + vertex 1.60288 2.07785 2.46864 + vertex 1.60078 2.08181 2.46779 + vertex 1.5984 2.07739 2.46957 + endloop + endfacet + facet normal 0.15947 0.287834 0.94431 + outer loop + vertex 1.60288 2.07785 2.46864 + vertex 1.60631 2.08006 2.46739 + vertex 1.60078 2.08181 2.46779 + endloop + endfacet + facet normal 0.163738 0.300803 0.939525 + outer loop + vertex 1.59849 2.07333 2.47085 + vertex 1.60266 2.07396 2.46993 + vertex 1.5984 2.07739 2.46957 + endloop + endfacet + facet normal 0.163623 0.300807 0.939544 + outer loop + vertex 1.59456 2.07454 2.47115 + vertex 1.59849 2.07333 2.47085 + vertex 1.5984 2.07739 2.46957 + endloop + endfacet + facet normal 0.163529 0.301787 0.939246 + outer loop + vertex 1.59849 2.07333 2.47085 + vertex 1.60051 2.07073 2.47134 + vertex 1.60266 2.07396 2.46993 + endloop + endfacet + facet normal 0.155998 0.306673 0.938944 + outer loop + vertex 1.60444 2.06968 2.47103 + vertex 1.60266 2.07396 2.46993 + vertex 1.60051 2.07073 2.47134 + endloop + endfacet + facet normal 0.154871 0.301966 0.940655 + outer loop + vertex 1.60051 2.07073 2.47134 + vertex 1.60063 2.06673 2.4726 + vertex 1.60444 2.06968 2.47103 + endloop + endfacet + facet normal 0.147203 0.310967 0.938952 + outer loop + vertex 1.60585 2.06563 2.47215 + vertex 1.60444 2.06968 2.47103 + vertex 1.60063 2.06673 2.4726 + endloop + endfacet + facet normal 0.164225 0.301753 0.939135 + outer loop + vertex 1.60051 2.07073 2.47134 + vertex 1.59626 2.07012 2.47228 + vertex 1.60063 2.06673 2.4726 + endloop + endfacet + facet normal 0.164131 0.30221 0.939005 + outer loop + vertex 1.60051 2.07073 2.47134 + vertex 1.59849 2.07333 2.47085 + vertex 1.59626 2.07012 2.47228 + endloop + endfacet + facet normal 0.152911 0.297012 0.942551 + outer loop + vertex 1.60604 2.0762 2.46865 + vertex 1.60631 2.08006 2.46739 + vertex 1.60288 2.07785 2.46864 + endloop + endfacet + facet normal 0.120536 0.300487 0.946139 + outer loop + vertex 1.60631 2.08006 2.46739 + vertex 1.60604 2.0762 2.46865 + vertex 1.61055 2.07671 2.46791 + endloop + endfacet + facet normal 0.124548 0.304527 0.944326 + outer loop + vertex 1.60918 2.06866 2.47073 + vertex 1.60444 2.06968 2.47103 + vertex 1.60585 2.06563 2.47215 + endloop + endfacet + facet normal 0.100367 0.328567 0.939133 + outer loop + vertex 1.611 2.06458 2.47197 + vertex 1.60918 2.06866 2.47073 + vertex 1.60585 2.06563 2.47215 + endloop + endfacet + facet normal 0.0951178 0.301248 0.94879 + outer loop + vertex 1.60688 2.06165 2.47331 + vertex 1.611 2.06458 2.47197 + vertex 1.60585 2.06563 2.47215 + endloop + endfacet + facet normal 0.0813788 0.318582 0.944396 + outer loop + vertex 1.61089 2.06068 2.47329 + vertex 1.611 2.06458 2.47197 + vertex 1.60688 2.06165 2.47331 + endloop + endfacet + facet normal 0.119449 0.307205 0.944117 + outer loop + vertex 1.60765 2.07278 2.46955 + vertex 1.61055 2.07671 2.46791 + vertex 1.60604 2.0762 2.46865 + endloop + endfacet + facet normal 0.0419741 0.332133 0.942298 + outer loop + vertex 1.61782 2.07282 2.46879 + vertex 1.61594 2.07608 2.46772 + vertex 1.61301 2.07193 2.46931 + endloop + endfacet + facet normal 0.0419357 0.332306 0.942239 + outer loop + vertex 1.61301 2.07193 2.46931 + vertex 1.6171 2.06905 2.47015 + vertex 1.61782 2.07282 2.46879 + endloop + endfacet + facet normal 0.0306242 0.317792 0.947666 + outer loop + vertex 1.61305 2.06795 2.47065 + vertex 1.6171 2.06905 2.47015 + vertex 1.61301 2.07193 2.46931 + endloop + endfacet + facet normal 0.0795266 0.317472 0.944927 + outer loop + vertex 1.60918 2.06866 2.47073 + vertex 1.61305 2.06795 2.47065 + vertex 1.61301 2.07193 2.46931 + endloop + endfacet + facet normal 0.0801452 0.320951 0.943699 + outer loop + vertex 1.61305 2.06795 2.47065 + vertex 1.60918 2.06866 2.47073 + vertex 1.611 2.06458 2.47197 + endloop + endfacet + facet normal 0.044232 0.341043 0.939006 + outer loop + vertex 1.61502 2.06588 2.47131 + vertex 1.61305 2.06795 2.47065 + vertex 1.611 2.06458 2.47197 + endloop + endfacet + facet normal 0.0439921 0.341673 0.938789 + outer loop + vertex 1.61502 2.06588 2.47131 + vertex 1.611 2.06458 2.47197 + vertex 1.61597 2.06213 2.47263 + endloop + endfacet + facet normal 0.00874186 0.334053 0.942514 + outer loop + vertex 1.61502 2.06588 2.47131 + vertex 1.61597 2.06213 2.47263 + vertex 1.618 2.06586 2.47128 + endloop + endfacet + facet normal 0.00875548 0.338215 0.941028 + outer loop + vertex 1.618 2.06586 2.47128 + vertex 1.6171 2.06905 2.47015 + vertex 1.61502 2.06588 2.47131 + endloop + endfacet + facet normal 0.0326006 0.320624 0.946645 + outer loop + vertex 1.611 2.06458 2.47197 + vertex 1.61089 2.06068 2.47329 + vertex 1.61597 2.06213 2.47263 + endloop + endfacet + facet normal 0.0335235 0.317808 0.947562 + outer loop + vertex 1.61269 2.05762 2.47426 + vertex 1.61597 2.06213 2.47263 + vertex 1.61089 2.06068 2.47329 + endloop + endfacet + facet normal 0.0277065 0.327079 0.944591 + outer loop + vertex 1.61305 2.06795 2.47065 + vertex 1.61502 2.06588 2.47131 + vertex 1.6171 2.06905 2.47015 + endloop + endfacet + facet normal 0.158451 0.310806 0.937173 + outer loop + vertex 1.60457 2.08452 2.46628 + vertex 1.60855 2.0832 2.46605 + vertex 1.60837 2.08734 2.4647 + endloop + endfacet + facet normal 0.113719 0.310959 0.943596 + outer loop + vertex 1.60855 2.0832 2.46605 + vertex 1.61278 2.08397 2.46528 + vertex 1.60837 2.08734 2.4647 + endloop + endfacet + facet normal 0.117496 0.294812 0.948304 + outer loop + vertex 1.60855 2.0832 2.46605 + vertex 1.61054 2.08066 2.46659 + vertex 1.61278 2.08397 2.46528 + endloop + endfacet + facet normal 0.084317 0.315973 0.945014 + outer loop + vertex 1.61448 2.07996 2.46647 + vertex 1.61278 2.08397 2.46528 + vertex 1.61054 2.08066 2.46659 + endloop + endfacet + facet normal 0.0842803 0.315754 0.945091 + outer loop + vertex 1.61054 2.08066 2.46659 + vertex 1.61055 2.07671 2.46791 + vertex 1.61448 2.07996 2.46647 + endloop + endfacet + facet normal 0.132109 0.314202 0.940119 + outer loop + vertex 1.61054 2.08066 2.46659 + vertex 1.60631 2.08006 2.46739 + vertex 1.61055 2.07671 2.46791 + endloop + endfacet + facet normal 0.133689 0.306251 0.942517 + outer loop + vertex 1.61054 2.08066 2.46659 + vertex 1.60855 2.0832 2.46605 + vertex 1.60631 2.08006 2.46739 + endloop + endfacet + facet normal 0.152958 0.293051 0.943782 + outer loop + vertex 1.60855 2.0832 2.46605 + vertex 1.60457 2.08452 2.46628 + vertex 1.60631 2.08006 2.46739 + endloop + endfacet + facet normal 0.161813 0.295912 0.94141 + outer loop + vertex 1.60631 2.08006 2.46739 + vertex 1.60457 2.08452 2.46628 + vertex 1.60078 2.08181 2.46779 + endloop + endfacet + facet normal 0.164121 0.301706 0.939169 + outer loop + vertex 1.60055 2.08596 2.46656 + vertex 1.59847 2.08873 2.46603 + vertex 1.59594 2.08572 2.46744 + endloop + endfacet + facet normal 0.163412 0.292681 0.942144 + outer loop + vertex 1.5984 2.07739 2.46957 + vertex 1.60078 2.08181 2.46779 + vertex 1.59628 2.08134 2.46871 + endloop + endfacet + facet normal 0.162059 0.292047 0.942574 + outer loop + vertex 1.5984 2.07739 2.46957 + vertex 1.59628 2.08134 2.46871 + vertex 1.59291 2.07894 2.47003 + endloop + endfacet + facet normal 0.163245 0.290526 0.942839 + outer loop + vertex 1.59291 2.07894 2.47003 + vertex 1.59628 2.08134 2.46871 + vertex 1.59307 2.08279 2.46882 + endloop + endfacet + facet normal 0.161077 0.29946 0.940414 + outer loop + vertex 1.59062 2.07575 2.47144 + vertex 1.58864 2.07839 2.47094 + vertex 1.58632 2.07519 2.47235 + endloop + endfacet + facet normal 0.164123 0.300195 0.939652 + outer loop + vertex 1.59291 2.07894 2.47003 + vertex 1.59456 2.07454 2.47115 + vertex 1.5984 2.07739 2.46957 + endloop + endfacet + facet normal 0.160718 0.301357 0.939869 + outer loop + vertex 1.59062 2.07575 2.47144 + vertex 1.58632 2.07519 2.47235 + vertex 1.5907 2.07168 2.47273 + endloop + endfacet + facet normal 0.158751 0.299026 0.940947 + outer loop + vertex 1.58632 2.07519 2.47235 + vertex 1.58617 2.07114 2.47367 + vertex 1.5907 2.07168 2.47273 + endloop + endfacet + facet normal 0.164031 0.302277 0.939001 + outer loop + vertex 1.59849 2.07333 2.47085 + vertex 1.59456 2.07454 2.47115 + vertex 1.59626 2.07012 2.47228 + endloop + endfacet + facet normal 0.143822 0.292338 0.945438 + outer loop + vertex 1.60288 2.06294 2.47343 + vertex 1.60585 2.06563 2.47215 + vertex 1.60063 2.06673 2.4726 + endloop + endfacet + facet normal 0.150356 0.292591 0.944343 + outer loop + vertex 1.59829 2.05802 2.47572 + vertex 1.60269 2.05886 2.47476 + vertex 1.59823 2.0622 2.47444 + endloop + endfacet + facet normal 0.128462 0.308057 0.942655 + outer loop + vertex 1.60688 2.06165 2.47331 + vertex 1.60585 2.06563 2.47215 + vertex 1.60288 2.06294 2.47343 + endloop + endfacet + facet normal 0.0788501 0.308058 0.948094 + outer loop + vertex 1.60782 2.0578 2.47448 + vertex 1.61089 2.06068 2.47329 + vertex 1.60688 2.06165 2.47331 + endloop + endfacet + facet normal 0.05646 0.329605 0.942429 + outer loop + vertex 1.61269 2.05762 2.47426 + vertex 1.61089 2.06068 2.47329 + vertex 1.60782 2.0578 2.47448 + endloop + endfacet + facet normal 0.0559609 0.306181 0.950327 + outer loop + vertex 1.60782 2.0578 2.47448 + vertex 1.60926 2.05399 2.47562 + vertex 1.61269 2.05762 2.47426 + endloop + endfacet + facet normal 0.0371836 0.32229 0.94591 + outer loop + vertex 1.60926 2.05399 2.47562 + vertex 1.61425 2.05381 2.47549 + vertex 1.61269 2.05762 2.47426 + endloop + endfacet + facet normal 0.036671 0.303789 0.952033 + outer loop + vertex 1.61425 2.05381 2.47549 + vertex 1.60926 2.05399 2.47562 + vertex 1.61065 2.05015 2.4768 + endloop + endfacet + facet normal 0.0314847 0.304925 0.951856 + outer loop + vertex 1.61253 2.04252 2.47916 + vertex 1.61186 2.04639 2.47794 + vertex 1.60858 2.04339 2.47901 + endloop + endfacet + facet normal 0.0315477 0.305196 0.951767 + outer loop + vertex 1.60787 2.03946 2.48029 + vertex 1.61253 2.04252 2.47916 + vertex 1.60858 2.04339 2.47901 + endloop + endfacet + facet normal 0.0717828 0.286926 0.95526 + outer loop + vertex 1.60345 2.03832 2.48097 + vertex 1.60539 2.03592 2.48154 + vertex 1.60787 2.03946 2.48029 + endloop + endfacet + facet normal 0.0377903 0.308997 0.950312 + outer loop + vertex 1.60927 2.03555 2.48151 + vertex 1.60787 2.03946 2.48029 + vertex 1.60539 2.03592 2.48154 + endloop + endfacet + facet normal 0.0379979 0.311191 0.949588 + outer loop + vertex 1.60539 2.03592 2.48154 + vertex 1.60562 2.03194 2.48284 + vertex 1.60927 2.03555 2.48151 + endloop + endfacet + facet normal 0.0955357 0.31292 0.944962 + outer loop + vertex 1.60539 2.03592 2.48154 + vertex 1.60102 2.03491 2.48232 + vertex 1.60562 2.03194 2.48284 + endloop + endfacet + facet normal 0.0793961 0.289452 0.953894 + outer loop + vertex 1.60102 2.03491 2.48232 + vertex 1.60095 2.0307 2.48361 + vertex 1.60562 2.03194 2.48284 + endloop + endfacet + facet normal 0.0791868 0.290123 0.953707 + outer loop + vertex 1.60323 2.02703 2.48453 + vertex 1.60562 2.03194 2.48284 + vertex 1.60095 2.0307 2.48361 + endloop + endfacet + facet normal 0.104627 0.304231 0.946835 + outer loop + vertex 1.60323 2.02703 2.48453 + vertex 1.60095 2.0307 2.48361 + vertex 1.59799 2.02797 2.48481 + endloop + endfacet + facet normal 0.100313 0.277612 0.955442 + outer loop + vertex 1.59799 2.02797 2.48481 + vertex 1.59933 2.02382 2.48588 + vertex 1.60323 2.02703 2.48453 + endloop + endfacet + facet normal 0.0917901 0.287148 0.953478 + outer loop + vertex 1.59933 2.02382 2.48588 + vertex 1.60325 2.02299 2.48575 + vertex 1.60323 2.02703 2.48453 + endloop + endfacet + facet normal 0.0930328 0.293343 0.95147 + outer loop + vertex 1.60325 2.02299 2.48575 + vertex 1.59933 2.02382 2.48588 + vertex 1.60112 2.0196 2.487 + endloop + endfacet + facet normal 0.113298 0.300693 0.946967 + outer loop + vertex 1.60112 2.0196 2.487 + vertex 1.59933 2.02382 2.48588 + vertex 1.59591 2.02082 2.48724 + endloop + endfacet + facet normal 0.108454 0.278766 0.954215 + outer loop + vertex 1.59703 2.01662 2.48834 + vertex 1.60112 2.0196 2.487 + vertex 1.59591 2.02082 2.48724 + endloop + endfacet + facet normal 0.138292 0.285194 0.948441 + outer loop + vertex 1.59703 2.01662 2.48834 + vertex 1.59591 2.02082 2.48724 + vertex 1.59291 2.01814 2.48848 + endloop + endfacet + facet normal 0.135955 0.278652 0.95072 + outer loop + vertex 1.5928 2.01387 2.48975 + vertex 1.59703 2.01662 2.48834 + vertex 1.59291 2.01814 2.48848 + endloop + endfacet + facet normal 0.158858 0.277163 0.9476 + outer loop + vertex 1.58828 2.01747 2.48945 + vertex 1.5928 2.01387 2.48975 + vertex 1.59291 2.01814 2.48848 + endloop + endfacet + facet normal 0.158931 0.276795 0.947695 + outer loop + vertex 1.59291 2.01814 2.48848 + vertex 1.5906 2.02215 2.4877 + vertex 1.58828 2.01747 2.48945 + endloop + endfacet + facet normal 0.163555 0.274458 0.947588 + outer loop + vertex 1.58828 2.01747 2.48945 + vertex 1.5906 2.02215 2.4877 + vertex 1.58611 2.02149 2.48866 + endloop + endfacet + facet normal 0.162065 0.273745 0.94805 + outer loop + vertex 1.58828 2.01747 2.48945 + vertex 1.58611 2.02149 2.48866 + vertex 1.5828 2.01899 2.48995 + endloop + endfacet + facet normal 0.161605 0.271877 0.948666 + outer loop + vertex 1.5828 2.01899 2.48995 + vertex 1.5844 2.01448 2.49097 + vertex 1.58828 2.01747 2.48945 + endloop + endfacet + facet normal 0.162008 0.271389 0.948737 + outer loop + vertex 1.5844 2.01448 2.49097 + vertex 1.58835 2.01324 2.49065 + vertex 1.58828 2.01747 2.48945 + endloop + endfacet + facet normal 0.160385 0.26575 0.950607 + outer loop + vertex 1.58835 2.01324 2.49065 + vertex 1.5844 2.01448 2.49097 + vertex 1.58598 2.00984 2.492 + endloop + endfacet + facet normal 0.160055 0.265978 0.950599 + outer loop + vertex 1.59036 2.01049 2.49108 + vertex 1.58835 2.01324 2.49065 + vertex 1.58598 2.00984 2.492 + endloop + endfacet + facet normal 0.160518 0.263668 0.951164 + outer loop + vertex 1.59036 2.01049 2.49108 + vertex 1.58598 2.00984 2.492 + vertex 1.59039 2.00632 2.49223 + endloop + endfacet + facet normal 0.144229 0.264245 0.95361 + outer loop + vertex 1.59036 2.01049 2.49108 + vertex 1.59039 2.00632 2.49223 + vertex 1.59437 2.0092 2.49083 + endloop + endfacet + facet normal 0.146024 0.270154 0.951679 + outer loop + vertex 1.59437 2.0092 2.49083 + vertex 1.5928 2.01387 2.48975 + vertex 1.59036 2.01049 2.49108 + endloop + endfacet + facet normal 0.118248 0.26226 0.957725 + outer loop + vertex 1.5928 2.01387 2.48975 + vertex 1.59437 2.0092 2.49083 + vertex 1.59849 2.01216 2.48951 + endloop + endfacet + facet normal 0.112257 0.269969 0.956303 + outer loop + vertex 1.59437 2.0092 2.49083 + vertex 1.59836 2.00804 2.49069 + vertex 1.59849 2.01216 2.48951 + endloop + endfacet + facet normal 0.0570813 0.272841 0.960364 + outer loop + vertex 1.59836 2.00804 2.49069 + vertex 1.60283 2.00921 2.49009 + vertex 1.59849 2.01216 2.48951 + endloop + endfacet + facet normal 0.06932 0.289691 0.954607 + outer loop + vertex 1.59849 2.01216 2.48951 + vertex 1.60283 2.00921 2.49009 + vertex 1.60312 2.01322 2.48885 + endloop + endfacet + facet normal 0.0656784 0.303117 0.950687 + outer loop + vertex 1.60312 2.01322 2.48885 + vertex 1.60114 2.01563 2.48822 + vertex 1.59849 2.01216 2.48951 + endloop + endfacet + facet normal 0.0580126 0.269708 0.961193 + outer loop + vertex 1.59836 2.00804 2.49069 + vertex 1.60031 2.00555 2.49127 + vertex 1.60283 2.00921 2.49009 + endloop + endfacet + facet normal 0.0329413 0.285874 0.957701 + outer loop + vertex 1.60436 2.00501 2.49129 + vertex 1.60283 2.00921 2.49009 + vertex 1.60031 2.00555 2.49127 + endloop + endfacet + facet normal 0.0329046 0.285604 0.957783 + outer loop + vertex 1.60031 2.00555 2.49127 + vertex 1.60011 2.0015 2.49249 + vertex 1.60436 2.00501 2.49129 + endloop + endfacet + facet normal 0.0826944 0.282487 0.9557 + outer loop + vertex 1.60031 2.00555 2.49127 + vertex 1.5959 2.00461 2.49193 + vertex 1.60011 2.0015 2.49249 + endloop + endfacet + facet normal 0.0693561 0.26553 0.961605 + outer loop + vertex 1.5959 2.00461 2.49193 + vertex 1.59571 2.0006 2.49305 + vertex 1.60011 2.0015 2.49249 + endloop + endfacet + facet normal 0.0679728 0.271335 0.960082 + outer loop + vertex 1.59704 1.99743 2.49385 + vertex 1.60011 2.0015 2.49249 + vertex 1.59571 2.0006 2.49305 + endloop + endfacet + facet normal 0.098985 0.282921 0.954022 + outer loop + vertex 1.59704 1.99743 2.49385 + vertex 1.59571 2.0006 2.49305 + vertex 1.59328 1.99837 2.49397 + endloop + endfacet + facet normal 0.097641 0.277279 0.955815 + outer loop + vertex 1.59297 1.99448 2.49512 + vertex 1.59704 1.99743 2.49385 + vertex 1.59328 1.99837 2.49397 + endloop + endfacet + facet normal 0.145525 0.272123 0.951195 + outer loop + vertex 1.58846 1.99825 2.49474 + vertex 1.59297 1.99448 2.49512 + vertex 1.59328 1.99837 2.49397 + endloop + endfacet + facet normal 0.145929 0.266147 0.952823 + outer loop + vertex 1.59328 1.99837 2.49397 + vertex 1.592 2.00175 2.49322 + vertex 1.58846 1.99825 2.49474 + endloop + endfacet + facet normal 0.153021 0.259313 0.953594 + outer loop + vertex 1.58846 1.99825 2.49474 + vertex 1.592 2.00175 2.49322 + vertex 1.58809 2.00282 2.49355 + endloop + endfacet + facet normal 0.162208 0.259648 0.951983 + outer loop + vertex 1.5836 2.00221 2.49449 + vertex 1.58846 1.99825 2.49474 + vertex 1.58809 2.00282 2.49355 + endloop + endfacet + facet normal 0.162622 0.257415 0.952518 + outer loop + vertex 1.58809 2.00282 2.49355 + vertex 1.58599 2.00565 2.49315 + vertex 1.5836 2.00221 2.49449 + endloop + endfacet + facet normal 0.161431 0.258237 0.952499 + outer loop + vertex 1.5836 2.00221 2.49449 + vertex 1.58599 2.00565 2.49315 + vertex 1.58194 2.00701 2.49347 + endloop + endfacet + facet normal 0.161102 0.258141 0.95258 + outer loop + vertex 1.5836 2.00221 2.49449 + vertex 1.58194 2.00701 2.49347 + vertex 1.5778 2.00429 2.4949 + endloop + endfacet + facet normal 0.16113 0.258225 0.952553 + outer loop + vertex 1.5778 2.00429 2.4949 + vertex 1.57943 1.99949 2.49593 + vertex 1.5836 2.00221 2.49449 + endloop + endfacet + facet normal 0.161672 0.257456 0.952669 + outer loop + vertex 1.57943 1.99949 2.49593 + vertex 1.58359 1.99794 2.49564 + vertex 1.5836 2.00221 2.49449 + endloop + endfacet + facet normal 0.161901 0.258112 0.952453 + outer loop + vertex 1.58359 1.99794 2.49564 + vertex 1.57943 1.99949 2.49593 + vertex 1.58108 1.99465 2.49696 + endloop + endfacet + facet normal 0.163186 0.25715 0.952494 + outer loop + vertex 1.58549 1.99506 2.49609 + vertex 1.58359 1.99794 2.49564 + vertex 1.58108 1.99465 2.49696 + endloop + endfacet + facet normal 0.162721 0.260421 0.951684 + outer loop + vertex 1.58549 1.99506 2.49609 + vertex 1.58108 1.99465 2.49696 + vertex 1.58577 1.9907 2.49724 + endloop + endfacet + facet normal 0.158038 0.260343 0.952494 + outer loop + vertex 1.58549 1.99506 2.49609 + vertex 1.58577 1.9907 2.49724 + vertex 1.58864 1.99383 2.49591 + endloop + endfacet + facet normal 0.157367 0.258536 0.953097 + outer loop + vertex 1.58864 1.99383 2.49591 + vertex 1.58846 1.99825 2.49474 + vertex 1.58549 1.99506 2.49609 + endloop + endfacet + facet normal 0.149739 0.267677 0.951802 + outer loop + vertex 1.59048 1.99107 2.49639 + vertex 1.58864 1.99383 2.49591 + vertex 1.58577 1.9907 2.49724 + endloop + endfacet + facet normal 0.150001 0.265578 0.952349 + outer loop + vertex 1.59048 1.99107 2.49639 + vertex 1.58577 1.9907 2.49724 + vertex 1.59038 1.98696 2.49756 + endloop + endfacet + facet normal 0.109262 0.267919 0.957226 + outer loop + vertex 1.59048 1.99107 2.49639 + vertex 1.59038 1.98696 2.49756 + vertex 1.59454 1.99004 2.49622 + endloop + endfacet + facet normal 0.110777 0.274227 0.955263 + outer loop + vertex 1.59454 1.99004 2.49622 + vertex 1.59297 1.99448 2.49512 + vertex 1.59048 1.99107 2.49639 + endloop + endfacet + facet normal 0.0823595 0.265537 0.960577 + outer loop + vertex 1.59297 1.99448 2.49512 + vertex 1.59454 1.99004 2.49622 + vertex 1.59817 1.99348 2.49496 + endloop + endfacet + facet normal 0.0608566 0.286615 0.956111 + outer loop + vertex 1.59454 1.99004 2.49622 + vertex 1.59943 1.98945 2.49608 + vertex 1.59817 1.99348 2.49496 + endloop + endfacet + facet normal 0.032503 0.278771 0.959807 + outer loop + vertex 1.59817 1.99348 2.49496 + vertex 1.59943 1.98945 2.49608 + vertex 1.60314 1.99321 2.49487 + endloop + endfacet + facet normal 0.0331307 0.291671 0.955945 + outer loop + vertex 1.60314 1.99321 2.49487 + vertex 1.60181 1.99717 2.49371 + vertex 1.59817 1.99348 2.49496 + endloop + endfacet + facet normal 0.045401 0.280525 0.958772 + outer loop + vertex 1.59817 1.99348 2.49496 + vertex 1.60181 1.99717 2.49371 + vertex 1.59704 1.99743 2.49385 + endloop + endfacet + facet normal 0.0233889 0.28704 0.957633 + outer loop + vertex 1.59943 1.98945 2.49608 + vertex 1.6044 1.98931 2.496 + vertex 1.60314 1.99321 2.49487 + endloop + endfacet + facet normal 0.0231479 0.276704 0.960676 + outer loop + vertex 1.6044 1.98931 2.496 + vertex 1.59943 1.98945 2.49608 + vertex 1.60066 1.9855 2.49719 + endloop + endfacet + facet normal 0.0441564 0.282561 0.958233 + outer loop + vertex 1.60066 1.9855 2.49719 + vertex 1.59943 1.98945 2.49608 + vertex 1.5957 1.98584 2.49732 + endloop + endfacet + facet normal 0.0428704 0.261412 0.964275 + outer loop + vertex 1.59707 1.98174 2.49837 + vertex 1.60066 1.9855 2.49719 + vertex 1.5957 1.98584 2.49732 + endloop + endfacet + facet normal 0.0770053 0.271613 0.959321 + outer loop + vertex 1.59707 1.98174 2.49837 + vertex 1.5957 1.98584 2.49732 + vertex 1.59212 1.9823 2.49861 + endloop + endfacet + facet normal 0.0752264 0.253987 0.964278 + outer loop + vertex 1.59376 1.97754 2.49974 + vertex 1.59707 1.98174 2.49837 + vertex 1.59212 1.9823 2.49861 + endloop + endfacet + facet normal 0.115143 0.266033 0.957063 + outer loop + vertex 1.59376 1.97754 2.49974 + vertex 1.59212 1.9823 2.49861 + vertex 1.5879 1.97928 2.49996 + endloop + endfacet + facet normal 0.108077 0.241341 0.964403 + outer loop + vertex 1.5879 1.97928 2.49996 + vertex 1.58949 1.97441 2.501 + vertex 1.59376 1.97754 2.49974 + endloop + endfacet + facet normal 0.103187 0.2476 0.963352 + outer loop + vertex 1.58949 1.97441 2.501 + vertex 1.59349 1.97322 2.50088 + vertex 1.59376 1.97754 2.49974 + endloop + endfacet + facet normal 0.045047 0.252141 0.966641 + outer loop + vertex 1.59349 1.97322 2.50088 + vertex 1.59789 1.97445 2.50035 + vertex 1.59376 1.97754 2.49974 + endloop + endfacet + facet normal 0.0543975 0.263945 0.963002 + outer loop + vertex 1.59376 1.97754 2.49974 + vertex 1.59789 1.97445 2.50035 + vertex 1.59856 1.97849 2.4992 + endloop + endfacet + facet normal 0.0433517 0.25761 0.965276 + outer loop + vertex 1.59349 1.97322 2.50088 + vertex 1.59537 1.97078 2.50144 + vertex 1.59789 1.97445 2.50035 + endloop + endfacet + facet normal 0.0157288 0.275373 0.961209 + outer loop + vertex 1.59921 1.97048 2.50147 + vertex 1.59789 1.97445 2.50035 + vertex 1.59537 1.97078 2.50144 + endloop + endfacet + facet normal 0.0162232 0.28147 0.959433 + outer loop + vertex 1.59537 1.97078 2.50144 + vertex 1.59529 1.96678 2.50262 + vertex 1.59921 1.97048 2.50147 + endloop + endfacet + facet normal 0.0727241 0.279796 0.957301 + outer loop + vertex 1.59537 1.97078 2.50144 + vertex 1.59101 1.96975 2.50208 + vertex 1.59529 1.96678 2.50262 + endloop + endfacet + facet normal 0.0578049 0.259484 0.964016 + outer loop + vertex 1.59101 1.96975 2.50208 + vertex 1.59082 1.96569 2.50318 + vertex 1.59529 1.96678 2.50262 + endloop + endfacet + facet normal 0.057011 0.262368 0.963282 + outer loop + vertex 1.59218 1.96255 2.50395 + vertex 1.59529 1.96678 2.50262 + vertex 1.59082 1.96569 2.50318 + endloop + endfacet + facet normal 0.0886198 0.274666 0.957447 + outer loop + vertex 1.59218 1.96255 2.50395 + vertex 1.59082 1.96569 2.50318 + vertex 1.58834 1.96343 2.50406 + endloop + endfacet + facet normal 0.0854957 0.260465 0.961691 + outer loop + vertex 1.58801 1.95953 2.50514 + vertex 1.59218 1.96255 2.50395 + vertex 1.58834 1.96343 2.50406 + endloop + endfacet + facet normal 0.134992 0.255058 0.957456 + outer loop + vertex 1.58349 1.96331 2.50477 + vertex 1.58801 1.95953 2.50514 + vertex 1.58834 1.96343 2.50406 + endloop + endfacet + facet normal 0.134839 0.257505 0.956823 + outer loop + vertex 1.58834 1.96343 2.50406 + vertex 1.58706 1.96683 2.50332 + vertex 1.58349 1.96331 2.50477 + endloop + endfacet + facet normal 0.145098 0.247572 0.957943 + outer loop + vertex 1.58349 1.96331 2.50477 + vertex 1.58706 1.96683 2.50332 + vertex 1.58313 1.96794 2.50363 + endloop + endfacet + facet normal 0.155448 0.247951 0.95622 + outer loop + vertex 1.57868 1.96731 2.50452 + vertex 1.58349 1.96331 2.50477 + vertex 1.58313 1.96794 2.50363 + endloop + endfacet + facet normal 0.156008 0.244932 0.956906 + outer loop + vertex 1.58313 1.96794 2.50363 + vertex 1.58098 1.97088 2.50323 + vertex 1.57868 1.96731 2.50452 + endloop + endfacet + facet normal 0.156802 0.244422 0.956907 + outer loop + vertex 1.57868 1.96731 2.50452 + vertex 1.58098 1.97088 2.50323 + vertex 1.57706 1.97206 2.50357 + endloop + endfacet + facet normal 0.157051 0.244496 0.956847 + outer loop + vertex 1.57868 1.96731 2.50452 + vertex 1.57706 1.97206 2.50357 + vertex 1.57301 1.96947 2.5049 + endloop + endfacet + facet normal 0.155873 0.241216 0.957872 + outer loop + vertex 1.57301 1.96947 2.5049 + vertex 1.57455 1.96458 2.50588 + vertex 1.57868 1.96731 2.50452 + endloop + endfacet + facet normal 0.154473 0.2432 0.957597 + outer loop + vertex 1.57455 1.96458 2.50588 + vertex 1.57864 1.96299 2.50562 + vertex 1.57868 1.96731 2.50452 + endloop + endfacet + facet normal 0.153338 0.240126 0.958555 + outer loop + vertex 1.57864 1.96299 2.50562 + vertex 1.57455 1.96458 2.50588 + vertex 1.5761 1.95965 2.50686 + endloop + endfacet + facet normal 0.154807 0.239025 0.958594 + outer loop + vertex 1.58048 1.96006 2.50606 + vertex 1.57864 1.96299 2.50562 + vertex 1.5761 1.95965 2.50686 + endloop + endfacet + facet normal 0.155207 0.236063 0.959263 + outer loop + vertex 1.58048 1.96006 2.50606 + vertex 1.5761 1.95965 2.50686 + vertex 1.5806 1.95553 2.50715 + endloop + endfacet + facet normal 0.147336 0.236138 0.960485 + outer loop + vertex 1.58048 1.96006 2.50606 + vertex 1.5806 1.95553 2.50715 + vertex 1.5836 1.95883 2.50588 + endloop + endfacet + facet normal 0.148923 0.24037 0.959189 + outer loop + vertex 1.5836 1.95883 2.50588 + vertex 1.58349 1.96331 2.50477 + vertex 1.58048 1.96006 2.50606 + endloop + endfacet + facet normal 0.140418 0.242238 0.960002 + outer loop + vertex 1.58542 1.956 2.50633 + vertex 1.5836 1.95883 2.50588 + vertex 1.5806 1.95553 2.50715 + endloop + endfacet + facet normal 0.14097 0.238186 0.960934 + outer loop + vertex 1.58542 1.956 2.50633 + vertex 1.5806 1.95553 2.50715 + vertex 1.58524 1.95164 2.50743 + endloop + endfacet + facet normal 0.0984329 0.241143 0.965485 + outer loop + vertex 1.58542 1.956 2.50633 + vertex 1.58524 1.95164 2.50743 + vertex 1.58956 1.955 2.50615 + endloop + endfacet + facet normal 0.1003 0.249335 0.963209 + outer loop + vertex 1.58956 1.955 2.50615 + vertex 1.58801 1.95953 2.50514 + vertex 1.58542 1.956 2.50633 + endloop + endfacet + facet normal 0.0713177 0.240431 0.968043 + outer loop + vertex 1.58801 1.95953 2.50514 + vertex 1.58956 1.955 2.50615 + vertex 1.59332 1.95856 2.50499 + endloop + endfacet + facet normal 0.0513396 0.260243 0.964177 + outer loop + vertex 1.58956 1.955 2.50615 + vertex 1.59453 1.95449 2.50603 + vertex 1.59332 1.95856 2.50499 + endloop + endfacet + facet normal 0.0495174 0.241569 0.96912 + outer loop + vertex 1.59453 1.95449 2.50603 + vertex 1.58956 1.955 2.50615 + vertex 1.59069 1.95073 2.50716 + endloop + endfacet + facet normal 0.0902547 0.251012 0.963767 + outer loop + vertex 1.59069 1.95073 2.50716 + vertex 1.58956 1.955 2.50615 + vertex 1.58524 1.95164 2.50743 + endloop + endfacet + facet normal 0.0863955 0.226115 0.970262 + outer loop + vertex 1.58711 1.94691 2.50837 + vertex 1.59069 1.95073 2.50716 + vertex 1.58524 1.95164 2.50743 + endloop + endfacet + facet normal 0.117241 0.23716 0.96437 + outer loop + vertex 1.58711 1.94691 2.50837 + vertex 1.58524 1.95164 2.50743 + vertex 1.58229 1.94738 2.50884 + endloop + endfacet + facet normal 0.116637 0.229085 0.966393 + outer loop + vertex 1.5839 1.94263 2.50977 + vertex 1.58711 1.94691 2.50837 + vertex 1.58229 1.94738 2.50884 + endloop + endfacet + facet normal 0.14413 0.237276 0.960691 + outer loop + vertex 1.5839 1.94263 2.50977 + vertex 1.58229 1.94738 2.50884 + vertex 1.57818 1.94451 2.51016 + endloop + endfacet + facet normal 0.139534 0.222437 0.96491 + outer loop + vertex 1.57818 1.94451 2.51016 + vertex 1.57963 1.93961 2.51109 + vertex 1.5839 1.94263 2.50977 + endloop + endfacet + facet normal 0.137273 0.22547 0.964531 + outer loop + vertex 1.57963 1.93961 2.51109 + vertex 1.58356 1.93831 2.51083 + vertex 1.5839 1.94263 2.50977 + endloop + endfacet + facet normal 0.0851636 0.230735 0.969282 + outer loop + vertex 1.58356 1.93831 2.51083 + vertex 1.58804 1.9394 2.51018 + vertex 1.5839 1.94263 2.50977 + endloop + endfacet + facet normal 0.0951894 0.243065 0.965328 + outer loop + vertex 1.5839 1.94263 2.50977 + vertex 1.58804 1.9394 2.51018 + vertex 1.58866 1.94349 2.50909 + endloop + endfacet + facet normal 0.0868755 0.224458 0.970604 + outer loop + vertex 1.58356 1.93831 2.51083 + vertex 1.58539 1.93573 2.51126 + vertex 1.58804 1.9394 2.51018 + endloop + endfacet + facet normal 0.056571 0.245472 0.967752 + outer loop + vertex 1.5894 1.93511 2.51119 + vertex 1.58804 1.9394 2.51018 + vertex 1.58539 1.93573 2.51126 + endloop + endfacet + facet normal 0.0562121 0.243064 0.96838 + outer loop + vertex 1.58539 1.93573 2.51126 + vertex 1.58516 1.93156 2.51232 + vertex 1.5894 1.93511 2.51119 + endloop + endfacet + facet normal 0.053831 0.245735 0.967841 + outer loop + vertex 1.59056 1.93092 2.51218 + vertex 1.5894 1.93511 2.51119 + vertex 1.58516 1.93156 2.51232 + endloop + endfacet + facet normal 0.0513 0.222819 0.973509 + outer loop + vertex 1.58699 1.92696 2.51328 + vertex 1.59056 1.93092 2.51218 + vertex 1.58516 1.93156 2.51232 + endloop + endfacet + facet normal 0.0870783 0.235956 0.967854 + outer loop + vertex 1.58699 1.92696 2.51328 + vertex 1.58516 1.93156 2.51232 + vertex 1.58212 1.9273 2.51363 + endloop + endfacet + facet normal 0.0862469 0.220154 0.971645 + outer loop + vertex 1.58374 1.92253 2.51457 + vertex 1.58699 1.92696 2.51328 + vertex 1.58212 1.9273 2.51363 + endloop + endfacet + facet normal 0.12675 0.232447 0.964315 + outer loop + vertex 1.58374 1.92253 2.51457 + vertex 1.58212 1.9273 2.51363 + vertex 1.57793 1.92434 2.5149 + endloop + endfacet + facet normal 0.118972 0.206285 0.971232 + outer loop + vertex 1.57793 1.92434 2.5149 + vertex 1.57936 1.91938 2.51578 + vertex 1.58374 1.92253 2.51457 + endloop + endfacet + facet normal 0.114981 0.211571 0.970576 + outer loop + vertex 1.57936 1.91938 2.51578 + vertex 1.58343 1.91812 2.51557 + vertex 1.58374 1.92253 2.51457 + endloop + endfacet + facet normal 0.053754 0.216748 0.974747 + outer loop + vertex 1.58343 1.91812 2.51557 + vertex 1.58797 1.9193 2.51506 + vertex 1.58374 1.92253 2.51457 + endloop + endfacet + facet normal 0.0644355 0.230179 0.971013 + outer loop + vertex 1.58374 1.92253 2.51457 + vertex 1.58797 1.9193 2.51506 + vertex 1.58863 1.92347 2.51402 + endloop + endfacet + facet normal 0.0550284 0.212241 0.975667 + outer loop + vertex 1.58343 1.91812 2.51557 + vertex 1.58536 1.9156 2.51601 + vertex 1.58797 1.9193 2.51506 + endloop + endfacet + facet normal 0.019571 0.236176 0.971513 + outer loop + vertex 1.58932 1.91528 2.51601 + vertex 1.58797 1.9193 2.51506 + vertex 1.58536 1.9156 2.51601 + endloop + endfacet + facet normal 0.019095 0.230358 0.972919 + outer loop + vertex 1.58536 1.9156 2.51601 + vertex 1.58521 1.91143 2.517 + vertex 1.58932 1.91528 2.51601 + endloop + endfacet + facet normal 0.0851546 0.227235 0.97011 + outer loop + vertex 1.58536 1.9156 2.51601 + vertex 1.58083 1.91454 2.51665 + vertex 1.58521 1.91143 2.517 + endloop + endfacet + facet normal 0.0702899 0.206926 0.975828 + outer loop + vertex 1.58083 1.91454 2.51665 + vertex 1.58048 1.91014 2.51761 + vertex 1.58521 1.91143 2.517 + endloop + endfacet + facet normal 0.0729887 0.197837 0.977514 + outer loop + vertex 1.58192 1.90679 2.51818 + vertex 1.58521 1.91143 2.517 + vertex 1.58048 1.91014 2.51761 + endloop + endfacet + facet normal 0.108397 0.21198 0.971244 + outer loop + vertex 1.58192 1.90679 2.51818 + vertex 1.58048 1.91014 2.51761 + vertex 1.5775 1.90722 2.51858 + endloop + endfacet + facet normal 0.106704 0.19026 0.975918 + outer loop + vertex 1.5787 1.90371 2.51913 + vertex 1.58192 1.90679 2.51818 + vertex 1.5775 1.90722 2.51858 + endloop + endfacet + facet normal 0.140683 0.200824 0.969473 + outer loop + vertex 1.5787 1.90371 2.51913 + vertex 1.5775 1.90722 2.51858 + vertex 1.57356 1.90372 2.51988 + endloop + endfacet + facet normal 0.140862 0.194123 0.970811 + outer loop + vertex 1.57356 1.90372 2.51988 + vertex 1.57804 1.89938 2.5201 + vertex 1.5787 1.90371 2.51913 + endloop + endfacet + facet normal 0.0858825 0.203498 0.975301 + outer loop + vertex 1.57804 1.89938 2.5201 + vertex 1.58274 1.90255 2.51902 + vertex 1.5787 1.90371 2.51913 + endloop + endfacet + facet normal 0.0822974 0.208545 0.974544 + outer loop + vertex 1.58374 1.89771 2.51997 + vertex 1.58274 1.90255 2.51902 + vertex 1.57804 1.89938 2.5201 + endloop + endfacet + facet normal 0.075215 0.183944 0.980055 + outer loop + vertex 1.57804 1.89938 2.5201 + vertex 1.57932 1.89447 2.52092 + vertex 1.58374 1.89771 2.51997 + endloop + endfacet + facet normal 0.0731662 0.186635 0.979701 + outer loop + vertex 1.57932 1.89447 2.52092 + vertex 1.58317 1.89344 2.52083 + vertex 1.58374 1.89771 2.51997 + endloop + endfacet + facet normal 0.0159874 0.194395 0.980793 + outer loop + vertex 1.58317 1.89344 2.52083 + vertex 1.58742 1.89456 2.52054 + vertex 1.58374 1.89771 2.51997 + endloop + endfacet + facet normal 0.0227404 0.201995 0.979122 + outer loop + vertex 1.58374 1.89771 2.51997 + vertex 1.58742 1.89456 2.52054 + vertex 1.58877 1.89859 2.51967 + endloop + endfacet + facet normal 0.0214682 0.208788 0.977725 + outer loop + vertex 1.58877 1.89859 2.51967 + vertex 1.58765 1.90223 2.51892 + vertex 1.58374 1.89771 2.51997 + endloop + endfacet + facet normal 0.0136781 0.202717 0.979142 + outer loop + vertex 1.58317 1.89344 2.52083 + vertex 1.58502 1.89121 2.52127 + vertex 1.58742 1.89456 2.52054 + endloop + endfacet + facet normal -0.00447714 0.215148 0.976571 + outer loop + vertex 1.58808 1.89121 2.52128 + vertex 1.58742 1.89456 2.52054 + vertex 1.58502 1.89121 2.52127 + endloop + endfacet + facet normal -0.00447486 0.221313 0.975193 + outer loop + vertex 1.58502 1.89121 2.52127 + vertex 1.58581 1.8871 2.5222 + vertex 1.58808 1.89121 2.52128 + endloop + endfacet + facet normal 0.042614 0.229721 0.972323 + outer loop + vertex 1.58502 1.89121 2.52127 + vertex 1.58086 1.88985 2.52177 + vertex 1.58581 1.8871 2.5222 + endloop + endfacet + facet normal 0.0437636 0.226457 0.973037 + outer loop + vertex 1.58502 1.89121 2.52127 + vertex 1.58317 1.89344 2.52083 + vertex 1.58086 1.88985 2.52177 + endloop + endfacet + facet normal 0.0779971 0.205086 0.975631 + outer loop + vertex 1.58317 1.89344 2.52083 + vertex 1.57932 1.89447 2.52092 + vertex 1.58086 1.88985 2.52177 + endloop + endfacet + facet normal 0.113576 0.215932 0.96978 + outer loop + vertex 1.58086 1.88985 2.52177 + vertex 1.57932 1.89447 2.52092 + vertex 1.57512 1.89144 2.52209 + endloop + endfacet + facet normal 0.106304 0.18831 0.97634 + outer loop + vertex 1.57673 1.88648 2.52287 + vertex 1.58086 1.88985 2.52177 + vertex 1.57512 1.89144 2.52209 + endloop + endfacet + facet normal 0.143269 0.199228 0.969424 + outer loop + vertex 1.57673 1.88648 2.52287 + vertex 1.57512 1.89144 2.52209 + vertex 1.57219 1.8873 2.52337 + endloop + endfacet + facet normal 0.141583 0.188414 0.97183 + outer loop + vertex 1.57368 1.88349 2.52389 + vertex 1.57673 1.88648 2.52287 + vertex 1.57219 1.8873 2.52337 + endloop + endfacet + facet normal 0.159509 0.194846 0.967777 + outer loop + vertex 1.57368 1.88349 2.52389 + vertex 1.57219 1.8873 2.52337 + vertex 1.5685 1.88359 2.52473 + endloop + endfacet + facet normal 0.159464 0.19821 0.967101 + outer loop + vertex 1.5685 1.88359 2.52473 + vertex 1.57356 1.87867 2.5249 + vertex 1.57368 1.88349 2.52389 + endloop + endfacet + facet normal 0.124391 0.200091 0.971849 + outer loop + vertex 1.57356 1.87867 2.5249 + vertex 1.5776 1.88226 2.52364 + vertex 1.57368 1.88349 2.52389 + endloop + endfacet + facet normal 0.109352 0.216466 0.970147 + outer loop + vertex 1.57881 1.87882 2.52428 + vertex 1.5776 1.88226 2.52364 + vertex 1.57356 1.87867 2.5249 + endloop + endfacet + facet normal 0.109948 0.205061 0.972554 + outer loop + vertex 1.57356 1.87867 2.5249 + vertex 1.57809 1.87464 2.52524 + vertex 1.57881 1.87882 2.52428 + endloop + endfacet + facet normal 0.0436054 0.217122 0.97517 + outer loop + vertex 1.57809 1.87464 2.52524 + vertex 1.58283 1.87787 2.52431 + vertex 1.57881 1.87882 2.52428 + endloop + endfacet + facet normal 0.0447319 0.221848 0.974055 + outer loop + vertex 1.58283 1.87787 2.52431 + vertex 1.58216 1.88205 2.52339 + vertex 1.57881 1.87882 2.52428 + endloop + endfacet + facet normal 0.0361966 0.227423 0.973123 + outer loop + vertex 1.58333 1.87374 2.52525 + vertex 1.58283 1.87787 2.52431 + vertex 1.57809 1.87464 2.52524 + endloop + endfacet + facet normal 0.031822 0.201908 0.978887 + outer loop + vertex 1.57809 1.87464 2.52524 + vertex 1.5795 1.87018 2.52611 + vertex 1.58333 1.87374 2.52525 + endloop + endfacet + facet normal 0.00558534 0.228776 0.973463 + outer loop + vertex 1.5795 1.87018 2.52611 + vertex 1.58428 1.87004 2.52612 + vertex 1.58333 1.87374 2.52525 + endloop + endfacet + facet normal 0.00500955 0.209586 0.977777 + outer loop + vertex 1.58428 1.87004 2.52612 + vertex 1.5795 1.87018 2.52611 + vertex 1.58073 1.86607 2.52699 + endloop + endfacet + facet normal 0.0557643 0.223724 0.973056 + outer loop + vertex 1.58073 1.86607 2.52699 + vertex 1.5795 1.87018 2.52611 + vertex 1.57515 1.8667 2.52716 + endloop + endfacet + facet normal 0.0519298 0.18758 0.980876 + outer loop + vertex 1.57691 1.8619 2.52799 + vertex 1.58073 1.86607 2.52699 + vertex 1.57515 1.8667 2.52716 + endloop + endfacet + facet normal 0.0945957 0.202171 0.974771 + outer loop + vertex 1.57691 1.8619 2.52799 + vertex 1.57515 1.8667 2.52716 + vertex 1.57216 1.86206 2.52841 + endloop + endfacet + facet normal 0.0942382 0.17906 0.979314 + outer loop + vertex 1.57377 1.85836 2.52893 + vertex 1.57691 1.8619 2.52799 + vertex 1.57216 1.86206 2.52841 + endloop + endfacet + facet normal 0.132697 0.19479 0.971827 + outer loop + vertex 1.57377 1.85836 2.52893 + vertex 1.57216 1.86206 2.52841 + vertex 1.56906 1.85764 2.52972 + endloop + endfacet + facet normal 0.133164 0.192213 0.972276 + outer loop + vertex 1.56906 1.85764 2.52972 + vertex 1.57347 1.85355 2.52993 + vertex 1.57377 1.85836 2.52893 + endloop + endfacet + facet normal 0.0666107 0.197612 0.978015 + outer loop + vertex 1.57347 1.85355 2.52993 + vertex 1.57776 1.85757 2.52882 + vertex 1.57377 1.85836 2.52893 + endloop + endfacet + facet normal 0.0579153 0.206565 0.976717 + outer loop + vertex 1.57867 1.85398 2.52953 + vertex 1.57776 1.85757 2.52882 + vertex 1.57347 1.85355 2.52993 + endloop + endfacet + facet normal 0.0592677 0.192624 0.979481 + outer loop + vertex 1.57347 1.85355 2.52993 + vertex 1.57776 1.84988 2.53039 + vertex 1.57867 1.85398 2.52953 + endloop + endfacet + facet normal 0.0503516 0.182529 0.98191 + outer loop + vertex 1.57329 1.84898 2.53079 + vertex 1.57776 1.84988 2.53039 + vertex 1.57347 1.85355 2.52993 + endloop + endfacet + facet normal 0.112399 0.179282 0.977356 + outer loop + vertex 1.57329 1.84898 2.53079 + vertex 1.57347 1.85355 2.52993 + vertex 1.57021 1.85017 2.53092 + endloop + endfacet + facet normal 0.119355 0.197793 0.97295 + outer loop + vertex 1.57021 1.85017 2.53092 + vertex 1.57034 1.84554 2.53185 + vertex 1.57329 1.84898 2.53079 + endloop + endfacet + facet normal 0.0973044 0.216268 0.971473 + outer loop + vertex 1.57513 1.8463 2.5312 + vertex 1.57329 1.84898 2.53079 + vertex 1.57034 1.84554 2.53185 + endloop + endfacet + facet normal 0.09869 0.208831 0.972959 + outer loop + vertex 1.57513 1.8463 2.5312 + vertex 1.57034 1.84554 2.53185 + vertex 1.57515 1.84193 2.53214 + endloop + endfacet + facet normal 0.022646 0.209515 0.977543 + outer loop + vertex 1.57513 1.8463 2.5312 + vertex 1.57515 1.84193 2.53214 + vertex 1.5792 1.84573 2.53123 + endloop + endfacet + facet normal 0.021981 0.204847 0.978547 + outer loop + vertex 1.5792 1.84573 2.53123 + vertex 1.57776 1.84988 2.53039 + vertex 1.57513 1.8463 2.5312 + endloop + endfacet + facet normal 0.0818238 0.186834 0.978978 + outer loop + vertex 1.57034 1.84554 2.53185 + vertex 1.57048 1.84061 2.53278 + vertex 1.57515 1.84193 2.53214 + endloop + endfacet + facet normal 0.0837553 0.180475 0.980007 + outer loop + vertex 1.57204 1.83706 2.5333 + vertex 1.57515 1.84193 2.53214 + vertex 1.57048 1.84061 2.53278 + endloop + endfacet + facet normal 0.119792 0.195339 0.973392 + outer loop + vertex 1.57204 1.83706 2.5333 + vertex 1.57048 1.84061 2.53278 + vertex 1.56766 1.8375 2.53375 + endloop + endfacet + facet normal 0.118128 0.174069 0.977623 + outer loop + vertex 1.56887 1.83392 2.53424 + vertex 1.57204 1.83706 2.5333 + vertex 1.56766 1.8375 2.53375 + endloop + endfacet + facet normal 0.150036 0.183985 0.971411 + outer loop + vertex 1.56887 1.83392 2.53424 + vertex 1.56766 1.8375 2.53375 + vertex 1.5638 1.83401 2.53501 + endloop + endfacet + facet normal 0.150125 0.174799 0.973092 + outer loop + vertex 1.5638 1.83401 2.53501 + vertex 1.56823 1.82956 2.53512 + vertex 1.56887 1.83392 2.53424 + endloop + endfacet + facet normal 0.0974917 0.183553 0.978163 + outer loop + vertex 1.56823 1.82956 2.53512 + vertex 1.57291 1.83265 2.53407 + vertex 1.56887 1.83392 2.53424 + endloop + endfacet + facet normal 0.0956953 0.186161 0.977848 + outer loop + vertex 1.57389 1.82766 2.53493 + vertex 1.57291 1.83265 2.53407 + vertex 1.56823 1.82956 2.53512 + endloop + endfacet + facet normal 0.0868942 0.159265 0.983404 + outer loop + vertex 1.56823 1.82956 2.53512 + vertex 1.56949 1.82455 2.53582 + vertex 1.57389 1.82766 2.53493 + endloop + endfacet + facet normal 0.0863844 0.159966 0.983335 + outer loop + vertex 1.56949 1.82455 2.53582 + vertex 1.57334 1.82337 2.53568 + vertex 1.57389 1.82766 2.53493 + endloop + endfacet + facet normal 0.0213338 0.168768 0.985425 + outer loop + vertex 1.57334 1.82337 2.53568 + vertex 1.57744 1.82447 2.5354 + vertex 1.57389 1.82766 2.53493 + endloop + endfacet + facet normal 0.0277232 0.175678 0.984057 + outer loop + vertex 1.57389 1.82766 2.53493 + vertex 1.57744 1.82447 2.5354 + vertex 1.57881 1.82855 2.53463 + endloop + endfacet + facet normal 0.0251212 0.189309 0.981596 + outer loop + vertex 1.57881 1.82855 2.53463 + vertex 1.57783 1.83228 2.53394 + vertex 1.57389 1.82766 2.53493 + endloop + endfacet + facet normal 0.0203692 0.172209 0.98485 + outer loop + vertex 1.57334 1.82337 2.53568 + vertex 1.57515 1.82116 2.53602 + vertex 1.57744 1.82447 2.5354 + endloop + endfacet + facet normal -0.00595736 0.189829 0.981799 + outer loop + vertex 1.57806 1.82129 2.53602 + vertex 1.57744 1.82447 2.5354 + vertex 1.57515 1.82116 2.53602 + endloop + endfacet + facet normal -0.00643703 0.200484 0.979676 + outer loop + vertex 1.57515 1.82116 2.53602 + vertex 1.57591 1.81732 2.53681 + vertex 1.57806 1.82129 2.53602 + endloop + endfacet + facet normal 0.05253 0.211351 0.975998 + outer loop + vertex 1.57515 1.82116 2.53602 + vertex 1.57096 1.81988 2.53653 + vertex 1.57591 1.81732 2.53681 + endloop + endfacet + facet normal 0.0368731 0.181839 0.982637 + outer loop + vertex 1.57096 1.81988 2.53653 + vertex 1.57061 1.81541 2.53737 + vertex 1.57591 1.81732 2.53681 + endloop + endfacet + facet normal 0.0395925 0.174672 0.98383 + outer loop + vertex 1.57192 1.81184 2.53795 + vertex 1.57591 1.81732 2.53681 + vertex 1.57061 1.81541 2.53737 + endloop + endfacet + facet normal 0.105104 0.175718 0.978814 + outer loop + vertex 1.57061 1.81541 2.53737 + vertex 1.57096 1.81988 2.53653 + vertex 1.56654 1.81633 2.53764 + endloop + endfacet + facet normal 0.102805 0.164966 0.980927 + outer loop + vertex 1.56726 1.81197 2.5383 + vertex 1.57061 1.81541 2.53737 + vertex 1.56654 1.81633 2.53764 + endloop + endfacet + facet normal 0.140667 0.17033 0.975295 + outer loop + vertex 1.56726 1.81197 2.5383 + vertex 1.56654 1.81633 2.53764 + vertex 1.56285 1.81271 2.5388 + endloop + endfacet + facet normal 0.138922 0.15842 0.97755 + outer loop + vertex 1.56395 1.80886 2.53927 + vertex 1.56726 1.81197 2.5383 + vertex 1.56285 1.81271 2.5388 + endloop + endfacet + facet normal 0.163323 0.164802 0.972711 + outer loop + vertex 1.56395 1.80886 2.53927 + vertex 1.56285 1.81271 2.5388 + vertex 1.55885 1.80905 2.54009 + endloop + endfacet + facet normal 0.163292 0.161734 0.973231 + outer loop + vertex 1.55885 1.80905 2.54009 + vertex 1.56375 1.80391 2.54013 + vertex 1.56395 1.80886 2.53927 + endloop + endfacet + facet normal 0.161144 0.159693 0.973925 + outer loop + vertex 1.55886 1.80422 2.54089 + vertex 1.56375 1.80391 2.54013 + vertex 1.55885 1.80905 2.54009 + endloop + endfacet + facet normal 0.169989 0.15946 0.972459 + outer loop + vertex 1.55886 1.80422 2.54089 + vertex 1.55885 1.80905 2.54009 + vertex 1.55566 1.806 2.54115 + endloop + endfacet + facet normal 0.162993 0.146361 0.975711 + outer loop + vertex 1.55566 1.806 2.54115 + vertex 1.55577 1.80091 2.5419 + vertex 1.55886 1.80422 2.54089 + endloop + endfacet + facet normal 0.16569 0.143824 0.975634 + outer loop + vertex 1.5606 1.80087 2.54108 + vertex 1.55886 1.80422 2.54089 + vertex 1.55577 1.80091 2.5419 + endloop + endfacet + facet normal 0.16579 0.137828 0.976482 + outer loop + vertex 1.5606 1.80087 2.54108 + vertex 1.55577 1.80091 2.5419 + vertex 1.56079 1.7958 2.54177 + endloop + endfacet + facet normal 0.156337 0.13768 0.978061 + outer loop + vertex 1.5606 1.80087 2.54108 + vertex 1.56079 1.7958 2.54177 + vertex 1.56382 1.79903 2.54083 + endloop + endfacet + facet normal 0.159041 0.142585 0.976921 + outer loop + vertex 1.56382 1.79903 2.54083 + vertex 1.56375 1.80391 2.54013 + vertex 1.5606 1.80087 2.54108 + endloop + endfacet + facet normal 0.110414 0.142861 0.983565 + outer loop + vertex 1.56382 1.79903 2.54083 + vertex 1.5686 1.79892 2.54031 + vertex 1.56375 1.80391 2.54013 + endloop + endfacet + facet normal 0.117127 0.14932 0.981827 + outer loop + vertex 1.56375 1.80391 2.54013 + vertex 1.5686 1.79892 2.54031 + vertex 1.56895 1.80378 2.53953 + endloop + endfacet + facet normal 0.11723 0.169515 0.97853 + outer loop + vertex 1.56895 1.80378 2.53953 + vertex 1.56791 1.8077 2.53897 + vertex 1.56375 1.80391 2.54013 + endloop + endfacet + facet normal 0.0640644 0.156482 0.985601 + outer loop + vertex 1.56895 1.80378 2.53953 + vertex 1.57262 1.80729 2.53873 + vertex 1.56791 1.8077 2.53897 + endloop + endfacet + facet normal 0.0657901 0.179015 0.981644 + outer loop + vertex 1.57262 1.80729 2.53873 + vertex 1.57192 1.81184 2.53795 + vertex 1.56791 1.8077 2.53897 + endloop + endfacet + facet normal 0.0782063 0.167289 0.982801 + outer loop + vertex 1.56791 1.8077 2.53897 + vertex 1.57192 1.81184 2.53795 + vertex 1.56726 1.81197 2.5383 + endloop + endfacet + facet normal 0.0785252 0.188138 0.978998 + outer loop + vertex 1.57192 1.81184 2.53795 + vertex 1.57061 1.81541 2.53737 + vertex 1.56726 1.81197 2.5383 + endloop + endfacet + facet normal 0.0525004 0.168304 0.984336 + outer loop + vertex 1.573 1.8027 2.5395 + vertex 1.57262 1.80729 2.53873 + vertex 1.56895 1.80378 2.53953 + endloop + endfacet + facet normal 0.0489529 0.154945 0.98671 + outer loop + vertex 1.5686 1.79892 2.54031 + vertex 1.573 1.8027 2.5395 + vertex 1.56895 1.80378 2.53953 + endloop + endfacet + facet normal 0.0422526 0.162554 0.985795 + outer loop + vertex 1.57367 1.79888 2.5401 + vertex 1.573 1.8027 2.5395 + vertex 1.5686 1.79892 2.54031 + endloop + endfacet + facet normal 0.0422331 0.132537 0.990278 + outer loop + vertex 1.5686 1.79892 2.54031 + vertex 1.57254 1.79503 2.54066 + vertex 1.57367 1.79888 2.5401 + endloop + endfacet + facet normal 0.0354554 0.125764 0.991426 + outer loop + vertex 1.56868 1.79437 2.54088 + vertex 1.57254 1.79503 2.54066 + vertex 1.5686 1.79892 2.54031 + endloop + endfacet + facet normal 0.103812 0.126318 0.986543 + outer loop + vertex 1.56868 1.79437 2.54088 + vertex 1.5686 1.79892 2.54031 + vertex 1.56561 1.7958 2.54102 + endloop + endfacet + facet normal 0.111905 0.144076 0.983219 + outer loop + vertex 1.56561 1.7958 2.54102 + vertex 1.56589 1.79108 2.54168 + vertex 1.56868 1.79437 2.54088 + endloop + endfacet + facet normal 0.0846082 0.166973 0.982325 + outer loop + vertex 1.57055 1.79192 2.54114 + vertex 1.56868 1.79437 2.54088 + vertex 1.56589 1.79108 2.54168 + endloop + endfacet + facet normal 0.0826068 0.177077 0.980724 + outer loop + vertex 1.57055 1.79192 2.54114 + vertex 1.56589 1.79108 2.54168 + vertex 1.57141 1.7879 2.54179 + endloop + endfacet + facet normal 0.010564 0.162581 0.986639 + outer loop + vertex 1.57055 1.79192 2.54114 + vertex 1.57141 1.7879 2.54179 + vertex 1.57357 1.79191 2.54111 + endloop + endfacet + facet normal 0.0105372 0.145069 0.989365 + outer loop + vertex 1.57357 1.79191 2.54111 + vertex 1.57254 1.79503 2.54066 + vertex 1.57055 1.79192 2.54114 + endloop + endfacet + facet normal 0.055805 0.1309 0.989824 + outer loop + vertex 1.56589 1.79108 2.54168 + vertex 1.56588 1.78579 2.54238 + vertex 1.57141 1.7879 2.54179 + endloop + endfacet + facet normal 0.0569612 0.127948 0.990144 + outer loop + vertex 1.56709 1.78185 2.54282 + vertex 1.57141 1.7879 2.54179 + vertex 1.56588 1.78579 2.54238 + endloop + endfacet + facet normal 0.0908675 0.137901 0.986269 + outer loop + vertex 1.56709 1.78185 2.54282 + vertex 1.56588 1.78579 2.54238 + vertex 1.56217 1.78181 2.54328 + endloop + endfacet + facet normal 0.0912498 0.119442 0.988639 + outer loop + vertex 1.56262 1.77721 2.54379 + vertex 1.56709 1.78185 2.54282 + vertex 1.56217 1.78181 2.54328 + endloop + endfacet + facet normal 0.125557 0.122339 0.984514 + outer loop + vertex 1.56262 1.77721 2.54379 + vertex 1.56217 1.78181 2.54328 + vertex 1.55794 1.77784 2.54431 + endloop + endfacet + facet normal 0.12421 0.111171 0.986009 + outer loop + vertex 1.55907 1.77378 2.54463 + vertex 1.56262 1.77721 2.54379 + vertex 1.55794 1.77784 2.54431 + endloop + endfacet + facet normal 0.107496 0.128443 0.985874 + outer loop + vertex 1.5629 1.77268 2.54435 + vertex 1.56262 1.77721 2.54379 + vertex 1.55907 1.77378 2.54463 + endloop + endfacet + facet normal 0.109021 0.133988 0.984968 + outer loop + vertex 1.55873 1.76904 2.54531 + vertex 1.5629 1.77268 2.54435 + vertex 1.55907 1.77378 2.54463 + endloop + endfacet + facet normal 0.102895 0.14092 0.984659 + outer loop + vertex 1.56362 1.769 2.5448 + vertex 1.5629 1.77268 2.54435 + vertex 1.55873 1.76904 2.54531 + endloop + endfacet + facet normal 0.102885 0.142146 0.984484 + outer loop + vertex 1.55873 1.76904 2.54531 + vertex 1.56293 1.76502 2.54545 + vertex 1.56362 1.769 2.5448 + endloop + endfacet + facet normal 0.0733298 0.126739 0.989222 + outer loop + vertex 1.5629 1.77268 2.54435 + vertex 1.56744 1.77694 2.54347 + vertex 1.56262 1.77721 2.54379 + endloop + endfacet + facet normal 0.0606213 0.140092 0.988281 + outer loop + vertex 1.56753 1.77226 2.54413 + vertex 1.56744 1.77694 2.54347 + vertex 1.5629 1.77268 2.54435 + endloop + endfacet + facet normal 0.0600404 0.133022 0.989293 + outer loop + vertex 1.56362 1.769 2.5448 + vertex 1.56753 1.77226 2.54413 + vertex 1.5629 1.77268 2.54435 + endloop + endfacet + facet normal 0.0476058 0.147637 0.987895 + outer loop + vertex 1.56759 1.76796 2.54477 + vertex 1.56753 1.77226 2.54413 + vertex 1.56362 1.769 2.5448 + endloop + endfacet + facet normal 0.0487568 0.152024 0.987173 + outer loop + vertex 1.56293 1.76502 2.54545 + vertex 1.56759 1.76796 2.54477 + vertex 1.56362 1.769 2.5448 + endloop + endfacet + facet normal 0.0473685 0.154167 0.986909 + outer loop + vertex 1.56819 1.76388 2.54538 + vertex 1.56759 1.76796 2.54477 + vertex 1.56293 1.76502 2.54545 + endloop + endfacet + facet normal 0.0267051 0.151306 0.988126 + outer loop + vertex 1.56819 1.76388 2.54538 + vertex 1.57254 1.7676 2.54469 + vertex 1.56759 1.76796 2.54477 + endloop + endfacet + facet normal 0.0264572 0.147678 0.988682 + outer loop + vertex 1.57254 1.7676 2.54469 + vertex 1.57235 1.77211 2.54402 + vertex 1.56759 1.76796 2.54477 + endloop + endfacet + facet normal 0.0287241 0.149003 0.98842 + outer loop + vertex 1.57338 1.7634 2.5453 + vertex 1.57254 1.7676 2.54469 + vertex 1.56819 1.76388 2.54538 + endloop + endfacet + facet normal 0.0289778 0.15183 0.987982 + outer loop + vertex 1.56819 1.76388 2.54538 + vertex 1.56949 1.75995 2.54594 + vertex 1.57338 1.7634 2.5453 + endloop + endfacet + facet normal 0.0277718 0.153157 0.987812 + outer loop + vertex 1.56949 1.75995 2.54594 + vertex 1.57456 1.75943 2.54588 + vertex 1.57338 1.7634 2.5453 + endloop + endfacet + facet normal 0.0275472 0.150911 0.988163 + outer loop + vertex 1.57456 1.75943 2.54588 + vertex 1.56949 1.75995 2.54594 + vertex 1.57091 1.75595 2.54651 + endloop + endfacet + facet normal 0.0281654 0.151124 0.988113 + outer loop + vertex 1.57091 1.75595 2.54651 + vertex 1.56949 1.75995 2.54594 + vertex 1.56576 1.75632 2.54661 + endloop + endfacet + facet normal 0.0275458 0.142022 0.98948 + outer loop + vertex 1.56685 1.75181 2.54722 + vertex 1.57091 1.75595 2.54651 + vertex 1.56576 1.75632 2.54661 + endloop + endfacet + facet normal 0.05658 0.148789 0.987249 + outer loop + vertex 1.56685 1.75181 2.54722 + vertex 1.56576 1.75632 2.54661 + vertex 1.56174 1.75194 2.5475 + endloop + endfacet + facet normal 0.0563832 0.136832 0.988988 + outer loop + vertex 1.56236 1.74711 2.54813 + vertex 1.56685 1.75181 2.54722 + vertex 1.56174 1.75194 2.5475 + endloop + endfacet + facet normal 0.0953556 0.141328 0.98536 + outer loop + vertex 1.56236 1.74711 2.54813 + vertex 1.56174 1.75194 2.5475 + vertex 1.55759 1.7474 2.54855 + endloop + endfacet + facet normal 0.094754 0.128982 0.98711 + outer loop + vertex 1.55795 1.74277 2.54912 + vertex 1.56236 1.74711 2.54813 + vertex 1.55759 1.7474 2.54855 + endloop + endfacet + facet normal 0.129907 0.131189 0.982809 + outer loop + vertex 1.55795 1.74277 2.54912 + vertex 1.55759 1.7474 2.54855 + vertex 1.55414 1.74388 2.54947 + endloop + endfacet + facet normal 0.129359 0.129211 0.983143 + outer loop + vertex 1.55376 1.73888 2.55018 + vertex 1.55795 1.74277 2.54912 + vertex 1.55414 1.74388 2.54947 + endloop + endfacet + facet normal 0.158456 0.126422 0.979239 + outer loop + vertex 1.54969 1.74359 2.55023 + vertex 1.55376 1.73888 2.55018 + vertex 1.55414 1.74388 2.54947 + endloop + endfacet + facet normal 0.158408 0.126995 0.979173 + outer loop + vertex 1.55414 1.74388 2.54947 + vertex 1.55299 1.74792 2.54914 + vertex 1.54969 1.74359 2.55023 + endloop + endfacet + facet normal 0.160555 0.125326 0.979038 + outer loop + vertex 1.54969 1.74359 2.55023 + vertex 1.55299 1.74792 2.54914 + vertex 1.54791 1.74938 2.54978 + endloop + endfacet + facet normal 0.169564 0.127959 0.977177 + outer loop + vertex 1.54969 1.74359 2.55023 + vertex 1.54791 1.74938 2.54978 + vertex 1.54484 1.7452 2.55086 + endloop + endfacet + facet normal 0.168367 0.124081 0.977884 + outer loop + vertex 1.5463 1.74112 2.55113 + vertex 1.54969 1.74359 2.55023 + vertex 1.54484 1.7452 2.55086 + endloop + endfacet + facet normal 0.1742 0.126081 0.976605 + outer loop + vertex 1.54484 1.7452 2.55086 + vertex 1.54189 1.7408 2.55196 + vertex 1.5463 1.74112 2.55113 + endloop + endfacet + facet normal 0.174607 0.121727 0.977085 + outer loop + vertex 1.5463 1.74112 2.55113 + vertex 1.54189 1.7408 2.55196 + vertex 1.54599 1.73604 2.55182 + endloop + endfacet + facet normal 0.167665 0.122314 0.978227 + outer loop + vertex 1.5463 1.74112 2.55113 + vertex 1.54599 1.73604 2.55182 + vertex 1.54915 1.73923 2.55088 + endloop + endfacet + facet normal 0.167722 0.122256 0.978224 + outer loop + vertex 1.55057 1.73598 2.55104 + vertex 1.54915 1.73923 2.55088 + vertex 1.54599 1.73604 2.55182 + endloop + endfacet + facet normal 0.167706 0.124084 0.977997 + outer loop + vertex 1.55057 1.73598 2.55104 + vertex 1.54599 1.73604 2.55182 + vertex 1.55065 1.73092 2.55167 + endloop + endfacet + facet normal 0.157715 0.124141 0.97965 + outer loop + vertex 1.55057 1.73598 2.55104 + vertex 1.55065 1.73092 2.55167 + vertex 1.55361 1.73412 2.55079 + endloop + endfacet + facet normal 0.155044 0.119644 0.980636 + outer loop + vertex 1.55361 1.73412 2.55079 + vertex 1.55376 1.73888 2.55018 + vertex 1.55057 1.73598 2.55104 + endloop + endfacet + facet normal 0.16433 0.120983 0.978958 + outer loop + vertex 1.54599 1.73604 2.55182 + vertex 1.54569 1.73076 2.55252 + vertex 1.55065 1.73092 2.55167 + endloop + endfacet + facet normal 0.164363 0.120334 0.979032 + outer loop + vertex 1.5468 1.72673 2.55283 + vertex 1.55065 1.73092 2.55167 + vertex 1.54569 1.73076 2.55252 + endloop + endfacet + facet normal 0.166946 0.121001 0.978513 + outer loop + vertex 1.5468 1.72673 2.55283 + vertex 1.54569 1.73076 2.55252 + vertex 1.54247 1.72747 2.55347 + endloop + endfacet + facet normal 0.166525 0.1182 0.978927 + outer loop + vertex 1.54314 1.72305 2.5539 + vertex 1.5468 1.72673 2.55283 + vertex 1.54247 1.72747 2.55347 + endloop + endfacet + facet normal 0.177805 0.119702 0.976758 + outer loop + vertex 1.54314 1.72305 2.5539 + vertex 1.54247 1.72747 2.55347 + vertex 1.53933 1.72425 2.55444 + endloop + endfacet + facet normal 0.178182 0.121004 0.976529 + outer loop + vertex 1.53906 1.7192 2.55512 + vertex 1.54314 1.72305 2.5539 + vertex 1.53933 1.72425 2.55444 + endloop + endfacet + facet normal 0.20547 0.11888 0.971416 + outer loop + vertex 1.53469 1.72386 2.55547 + vertex 1.53906 1.7192 2.55512 + vertex 1.53933 1.72425 2.55444 + endloop + endfacet + facet normal 0.205373 0.119797 0.971324 + outer loop + vertex 1.53933 1.72425 2.55444 + vertex 1.53798 1.72827 2.55423 + vertex 1.53469 1.72386 2.55547 + endloop + endfacet + facet normal 0.208817 0.117117 0.970917 + outer loop + vertex 1.53469 1.72386 2.55547 + vertex 1.53798 1.72827 2.55423 + vertex 1.53266 1.72958 2.55522 + endloop + endfacet + facet normal 0.212926 0.118528 0.969853 + outer loop + vertex 1.53469 1.72386 2.55547 + vertex 1.53266 1.72958 2.55522 + vertex 1.52959 1.72521 2.55643 + endloop + endfacet + facet normal 0.211385 0.111921 0.970974 + outer loop + vertex 1.53119 1.72122 2.55654 + vertex 1.53469 1.72386 2.55547 + vertex 1.52959 1.72521 2.55643 + endloop + endfacet + facet normal 0.122947 0.0771595 0.989409 + outer loop + vertex 1.52959 1.72521 2.55643 + vertex 1.52687 1.72081 2.55711 + vertex 1.53119 1.72122 2.55654 + endloop + endfacet + facet normal 0.119903 0.106303 0.987078 + outer loop + vertex 1.53119 1.72122 2.55654 + vertex 1.52687 1.72081 2.55711 + vertex 1.53092 1.7161 2.55712 + endloop + endfacet + facet normal 0.201224 0.100671 0.974358 + outer loop + vertex 1.53119 1.72122 2.55654 + vertex 1.53092 1.7161 2.55712 + vertex 1.53424 1.7194 2.5561 + endloop + endfacet + facet normal 0.194918 0.107205 0.974943 + outer loop + vertex 1.53573 1.71615 2.55616 + vertex 1.53424 1.7194 2.5561 + vertex 1.53092 1.7161 2.55712 + endloop + endfacet + facet normal 0.194658 0.115195 0.974083 + outer loop + vertex 1.53573 1.71615 2.55616 + vertex 1.53092 1.7161 2.55712 + vertex 1.53561 1.71116 2.55677 + endloop + endfacet + facet normal 0.199179 0.114975 0.973195 + outer loop + vertex 1.53573 1.71615 2.55616 + vertex 1.53561 1.71116 2.55677 + vertex 1.53881 1.71436 2.55574 + endloop + endfacet + facet normal 0.198779 0.114251 0.973362 + outer loop + vertex 1.53881 1.71436 2.55574 + vertex 1.53906 1.7192 2.55512 + vertex 1.53573 1.71615 2.55616 + endloop + endfacet + facet normal 0.180235 0.115655 0.9768 + outer loop + vertex 1.53881 1.71436 2.55574 + vertex 1.5436 1.71408 2.55489 + vertex 1.53906 1.7192 2.55512 + endloop + endfacet + facet normal 0.178697 0.114271 0.977246 + outer loop + vertex 1.53906 1.7192 2.55512 + vertex 1.5436 1.71408 2.55489 + vertex 1.54415 1.71911 2.5542 + endloop + endfacet + facet normal 0.165928 0.115951 0.979297 + outer loop + vertex 1.5436 1.71408 2.55489 + vertex 1.54801 1.71784 2.55369 + vertex 1.54415 1.71911 2.5542 + endloop + endfacet + facet normal 0.166035 0.116302 0.979238 + outer loop + vertex 1.54801 1.71784 2.55369 + vertex 1.54749 1.72225 2.55326 + vertex 1.54415 1.71911 2.5542 + endloop + endfacet + facet normal 0.165157 0.117246 0.979274 + outer loop + vertex 1.54415 1.71911 2.5542 + vertex 1.54749 1.72225 2.55326 + vertex 1.54314 1.72305 2.5539 + endloop + endfacet + facet normal 0.159802 0.115666 0.980349 + outer loop + vertex 1.54801 1.71784 2.55369 + vertex 1.55181 1.72158 2.55263 + vertex 1.54749 1.72225 2.55326 + endloop + endfacet + facet normal 0.160279 0.11921 0.979847 + outer loop + vertex 1.55181 1.72158 2.55263 + vertex 1.55065 1.72558 2.55233 + vertex 1.54749 1.72225 2.55326 + endloop + endfacet + facet normal 0.16089 0.118622 0.979818 + outer loop + vertex 1.54749 1.72225 2.55326 + vertex 1.55065 1.72558 2.55233 + vertex 1.5468 1.72673 2.55283 + endloop + endfacet + facet normal 0.147836 0.115787 0.982211 + outer loop + vertex 1.55181 1.72158 2.55263 + vertex 1.55559 1.72597 2.55155 + vertex 1.55065 1.72558 2.55233 + endloop + endfacet + facet normal 0.147163 0.122829 0.981456 + outer loop + vertex 1.55065 1.73092 2.55167 + vertex 1.55065 1.72558 2.55233 + vertex 1.55559 1.72597 2.55155 + endloop + endfacet + facet normal 0.142724 0.120234 0.982433 + outer loop + vertex 1.55564 1.72072 2.55218 + vertex 1.55559 1.72597 2.55155 + vertex 1.55181 1.72158 2.55263 + endloop + endfacet + facet normal 0.141711 0.115338 0.983166 + outer loop + vertex 1.5524 1.71713 2.55307 + vertex 1.55564 1.72072 2.55218 + vertex 1.55181 1.72158 2.55263 + endloop + endfacet + facet normal 0.13097 0.12513 0.983458 + outer loop + vertex 1.5569 1.71686 2.5525 + vertex 1.55564 1.72072 2.55218 + vertex 1.5524 1.71713 2.55307 + endloop + endfacet + facet normal 0.130478 0.114086 0.984865 + outer loop + vertex 1.55265 1.71264 2.55356 + vertex 1.5569 1.71686 2.5525 + vertex 1.5524 1.71713 2.55307 + endloop + endfacet + facet normal 0.155164 0.115029 0.981169 + outer loop + vertex 1.55265 1.71264 2.55356 + vertex 1.5524 1.71713 2.55307 + vertex 1.54877 1.71395 2.55402 + endloop + endfacet + facet normal 0.154516 0.113 0.981507 + outer loop + vertex 1.54766 1.70924 2.55473 + vertex 1.55265 1.71264 2.55356 + vertex 1.54877 1.71395 2.55402 + endloop + endfacet + facet normal 0.167477 0.109672 0.979757 + outer loop + vertex 1.5436 1.71408 2.55489 + vertex 1.54766 1.70924 2.55473 + vertex 1.54877 1.71395 2.55402 + endloop + endfacet + facet normal 0.171151 0.112786 0.978768 + outer loop + vertex 1.54312 1.70915 2.55554 + vertex 1.54766 1.70924 2.55473 + vertex 1.5436 1.71408 2.55489 + endloop + endfacet + facet normal 0.18073 0.111652 0.977175 + outer loop + vertex 1.54312 1.70915 2.55554 + vertex 1.5436 1.71408 2.55489 + vertex 1.54022 1.71109 2.55585 + endloop + endfacet + facet normal 0.179381 0.10956 0.97766 + outer loop + vertex 1.54022 1.71109 2.55585 + vertex 1.53981 1.70653 2.55644 + vertex 1.54312 1.70915 2.55554 + endloop + endfacet + facet normal 0.178458 0.11074 0.977696 + outer loop + vertex 1.54452 1.70503 2.55575 + vertex 1.54312 1.70915 2.55554 + vertex 1.53981 1.70653 2.55644 + endloop + endfacet + facet normal 0.195505 0.107747 0.974766 + outer loop + vertex 1.54022 1.71109 2.55585 + vertex 1.53561 1.71116 2.55677 + vertex 1.53981 1.70653 2.55644 + endloop + endfacet + facet normal 0.188244 0.101003 0.976915 + outer loop + vertex 1.53561 1.71116 2.55677 + vertex 1.53558 1.70595 2.55731 + vertex 1.53981 1.70653 2.55644 + endloop + endfacet + facet normal 0.189268 0.0942609 0.977391 + outer loop + vertex 1.53683 1.70187 2.55747 + vertex 1.53981 1.70653 2.55644 + vertex 1.53558 1.70595 2.55731 + endloop + endfacet + facet normal 0.195939 0.0962459 0.975881 + outer loop + vertex 1.53683 1.70187 2.55747 + vertex 1.53558 1.70595 2.55731 + vertex 1.53245 1.70254 2.55828 + endloop + endfacet + facet normal 0.195008 0.0891691 0.97674 + outer loop + vertex 1.53271 1.69799 2.55864 + vertex 1.53683 1.70187 2.55747 + vertex 1.53245 1.70254 2.55828 + endloop + endfacet + facet normal 0.203234 0.0895136 0.97503 + outer loop + vertex 1.53271 1.69799 2.55864 + vertex 1.53245 1.70254 2.55828 + vertex 1.52877 1.69928 2.55935 + endloop + endfacet + facet normal 0.205798 0.0980946 0.973666 + outer loop + vertex 1.52755 1.69445 2.56009 + vertex 1.53271 1.69799 2.55864 + vertex 1.52877 1.69928 2.55935 + endloop + endfacet + facet normal 0.171851 0.107531 0.979236 + outer loop + vertex 1.52357 1.69873 2.56032 + vertex 1.52755 1.69445 2.56009 + vertex 1.52877 1.69928 2.55935 + endloop + endfacet + facet normal 0.173667 0.092391 0.980461 + outer loop + vertex 1.52877 1.69928 2.55935 + vertex 1.52799 1.7031 2.55912 + vertex 1.52357 1.69873 2.56032 + endloop + endfacet + facet normal 0.11736 0.149652 0.981749 + outer loop + vertex 1.52357 1.69873 2.56032 + vertex 1.52799 1.7031 2.55912 + vertex 1.5242 1.70381 2.55947 + endloop + endfacet + facet normal -0.153219 0.181369 0.971406 + outer loop + vertex 1.52025 1.70245 2.5591 + vertex 1.52357 1.69873 2.56032 + vertex 1.5242 1.70381 2.55947 + endloop + endfacet + facet normal -0.145702 0.158028 0.976626 + outer loop + vertex 1.5242 1.70381 2.55947 + vertex 1.52311 1.70753 2.5587 + vertex 1.52025 1.70245 2.5591 + endloop + endfacet + facet normal 0.006517 0.203267 0.979102 + outer loop + vertex 1.5242 1.70381 2.55947 + vertex 1.52741 1.70741 2.5587 + vertex 1.52311 1.70753 2.5587 + endloop + endfacet + facet normal 0.00436991 0.128579 0.99169 + outer loop + vertex 1.52741 1.70741 2.5587 + vertex 1.52669 1.7118 2.55813 + vertex 1.52311 1.70753 2.5587 + endloop + endfacet + facet normal -0.122793 0.231868 0.964966 + outer loop + vertex 1.52311 1.70753 2.5587 + vertex 1.52669 1.7118 2.55813 + vertex 1.52211 1.71228 2.55744 + endloop + endfacet + facet normal -0.139876 0.0984466 0.985263 + outer loop + vertex 1.52669 1.7118 2.55813 + vertex 1.52587 1.71585 2.55761 + vertex 1.52211 1.71228 2.55744 + endloop + endfacet + facet normal -0.189812 0.151773 0.970019 + outer loop + vertex 1.52211 1.71228 2.55744 + vertex 1.52587 1.71585 2.55761 + vertex 1.5228 1.71768 2.55672 + endloop + endfacet + facet normal -0.197795 0.138567 0.9704 + outer loop + vertex 1.52587 1.71585 2.55761 + vertex 1.52687 1.72081 2.55711 + vertex 1.5228 1.71768 2.55672 + endloop + endfacet + facet normal -0.147344 0.071012 0.986533 + outer loop + vertex 1.5228 1.71768 2.55672 + vertex 1.52687 1.72081 2.55711 + vertex 1.52289 1.72255 2.55639 + endloop + endfacet + facet normal -0.178039 -0.000255004 0.984023 + outer loop + vertex 1.52687 1.72081 2.55711 + vertex 1.52524 1.72627 2.55681 + vertex 1.52289 1.72255 2.55639 + endloop + endfacet + facet normal -0.232791 0.0357787 0.971868 + outer loop + vertex 1.52289 1.72255 2.55639 + vertex 1.52524 1.72627 2.55681 + vertex 1.5223 1.72629 2.55611 + endloop + endfacet + facet normal -0.232407 0.0579727 0.970889 + outer loop + vertex 1.52304 1.72953 2.55609 + vertex 1.5223 1.72629 2.55611 + vertex 1.52524 1.72627 2.55681 + endloop + endfacet + facet normal -0.175834 0.0981664 0.979513 + outer loop + vertex 1.5255 1.73024 2.55646 + vertex 1.52304 1.72953 2.55609 + vertex 1.52524 1.72627 2.55681 + endloop + endfacet + facet normal 0.0999246 0.080865 0.991704 + outer loop + vertex 1.5255 1.73024 2.55646 + vertex 1.52524 1.72627 2.55681 + vertex 1.52804 1.72904 2.55631 + endloop + endfacet + facet normal 0.145424 0.178685 0.9731 + outer loop + vertex 1.52804 1.72904 2.55631 + vertex 1.52862 1.73368 2.55537 + vertex 1.5255 1.73024 2.55646 + endloop + endfacet + facet normal 0.0138981 0.292657 0.956117 + outer loop + vertex 1.5244 1.73268 2.55573 + vertex 1.5255 1.73024 2.55646 + vertex 1.52862 1.73368 2.55537 + endloop + endfacet + facet normal 0.0153403 0.287175 0.957755 + outer loop + vertex 1.5244 1.73268 2.55573 + vertex 1.52862 1.73368 2.55537 + vertex 1.52501 1.73723 2.55436 + endloop + endfacet + facet normal 0.207117 0.168955 0.963617 + outer loop + vertex 1.52804 1.72904 2.55631 + vertex 1.53266 1.72958 2.55522 + vertex 1.52862 1.73368 2.55537 + endloop + endfacet + facet normal 0.175083 0.136972 0.974979 + outer loop + vertex 1.52862 1.73368 2.55537 + vertex 1.53266 1.72958 2.55522 + vertex 1.5337 1.7343 2.55437 + endloop + endfacet + facet normal 0.177596 0.119331 0.976842 + outer loop + vertex 1.5337 1.7343 2.55437 + vertex 1.53297 1.73808 2.55404 + vertex 1.52862 1.73368 2.55537 + endloop + endfacet + facet normal 0.196883 0.122666 0.972723 + outer loop + vertex 1.5337 1.7343 2.55437 + vertex 1.53738 1.73741 2.55323 + vertex 1.53297 1.73808 2.55404 + endloop + endfacet + facet normal 0.195984 0.115569 0.973773 + outer loop + vertex 1.53738 1.73741 2.55323 + vertex 1.53682 1.74201 2.5528 + vertex 1.53297 1.73808 2.55404 + endloop + endfacet + facet normal 0.187906 0.123658 0.974372 + outer loop + vertex 1.53297 1.73808 2.55404 + vertex 1.53682 1.74201 2.5528 + vertex 1.53245 1.74237 2.5536 + endloop + endfacet + facet normal 0.13459 0.118117 0.983836 + outer loop + vertex 1.53297 1.73808 2.55404 + vertex 1.53245 1.74237 2.5536 + vertex 1.52925 1.73869 2.55447 + endloop + endfacet + facet normal 0.14009 0.156628 0.977672 + outer loop + vertex 1.52862 1.73368 2.55537 + vertex 1.53297 1.73808 2.55404 + vertex 1.52925 1.73869 2.55447 + endloop + endfacet + facet normal -0.0900189 0.185721 0.97847 + outer loop + vertex 1.52501 1.73723 2.55436 + vertex 1.52862 1.73368 2.55537 + vertex 1.52925 1.73869 2.55447 + endloop + endfacet + facet normal -0.0676337 0.119563 0.99052 + outer loop + vertex 1.52925 1.73869 2.55447 + vertex 1.52824 1.74235 2.55396 + vertex 1.52501 1.73723 2.55436 + endloop + endfacet + facet normal -0.21915 0.211993 0.952382 + outer loop + vertex 1.52501 1.73723 2.55436 + vertex 1.52824 1.74235 2.55396 + vertex 1.52426 1.74266 2.55298 + endloop + endfacet + facet normal -0.233514 0.0782616 0.969199 + outer loop + vertex 1.52824 1.74235 2.55396 + vertex 1.52762 1.74689 2.55345 + vertex 1.52426 1.74266 2.55298 + endloop + endfacet + facet normal -0.262819 0.102666 0.959368 + outer loop + vertex 1.52426 1.74266 2.55298 + vertex 1.52762 1.74689 2.55345 + vertex 1.5241 1.74776 2.55239 + endloop + endfacet + facet normal -0.275535 0.0516681 0.959901 + outer loop + vertex 1.52762 1.74689 2.55345 + vertex 1.52715 1.75157 2.55306 + vertex 1.5241 1.74776 2.55239 + endloop + endfacet + facet normal -0.283475 0.0584872 0.957194 + outer loop + vertex 1.5241 1.74776 2.55239 + vertex 1.52715 1.75157 2.55306 + vertex 1.52393 1.75263 2.55204 + endloop + endfacet + facet normal -0.296251 0.0172896 0.954954 + outer loop + vertex 1.52715 1.75157 2.55306 + vertex 1.52621 1.75572 2.55269 + vertex 1.52393 1.75263 2.55204 + endloop + endfacet + facet normal -0.349088 0.0605817 0.93513 + outer loop + vertex 1.52393 1.75263 2.55204 + vertex 1.52621 1.75572 2.55269 + vertex 1.52364 1.75744 2.55162 + endloop + endfacet + facet normal -0.309034 0.125109 0.942786 + outer loop + vertex 1.52621 1.75572 2.55269 + vertex 1.52622 1.76087 2.55201 + vertex 1.52364 1.75744 2.55162 + endloop + endfacet + facet normal -0.283952 0.105063 0.953065 + outer loop + vertex 1.52364 1.75744 2.55162 + vertex 1.52622 1.76087 2.55201 + vertex 1.52311 1.76141 2.55103 + endloop + endfacet + facet normal 0.0841936 0.130469 0.987871 + outer loop + vertex 1.52622 1.76087 2.55201 + vertex 1.52621 1.75572 2.55269 + vertex 1.53064 1.75595 2.55229 + endloop + endfacet + facet normal 0.0887087 0.134476 0.986938 + outer loop + vertex 1.53033 1.76104 2.55162 + vertex 1.52622 1.76087 2.55201 + vertex 1.53064 1.75595 2.55229 + endloop + endfacet + facet normal 0.199883 0.139036 0.969905 + outer loop + vertex 1.53033 1.76104 2.55162 + vertex 1.53064 1.75595 2.55229 + vertex 1.53366 1.75938 2.55117 + endloop + endfacet + facet normal 0.210837 0.162666 0.963892 + outer loop + vertex 1.53366 1.75938 2.55117 + vertex 1.53363 1.76421 2.55036 + vertex 1.53033 1.76104 2.55162 + endloop + endfacet + facet normal 0.194556 0.179775 0.964276 + outer loop + vertex 1.52856 1.76414 2.5514 + vertex 1.53033 1.76104 2.55162 + vertex 1.53363 1.76421 2.55036 + endloop + endfacet + facet normal 0.191645 0.233361 0.953318 + outer loop + vertex 1.52856 1.76414 2.5514 + vertex 1.53363 1.76421 2.55036 + vertex 1.52875 1.76862 2.55026 + endloop + endfacet + facet normal 0.121126 0.155898 0.980319 + outer loop + vertex 1.52875 1.76862 2.55026 + vertex 1.53363 1.76421 2.55036 + vertex 1.53391 1.76923 2.54953 + endloop + endfacet + facet normal 0.124926 0.128116 0.98386 + outer loop + vertex 1.53391 1.76923 2.54953 + vertex 1.53284 1.77299 2.54918 + vertex 1.52875 1.76862 2.55026 + endloop + endfacet + facet normal 0.0341775 0.211431 0.976795 + outer loop + vertex 1.52875 1.76862 2.55026 + vertex 1.53284 1.77299 2.54918 + vertex 1.52896 1.77348 2.54921 + endloop + endfacet + facet normal 0.0257247 0.143012 0.989387 + outer loop + vertex 1.53284 1.77299 2.54918 + vertex 1.53231 1.77719 2.54858 + vertex 1.52896 1.77348 2.54921 + endloop + endfacet + facet normal -0.153967 0.296865 0.942425 + outer loop + vertex 1.52896 1.77348 2.54921 + vertex 1.53231 1.77719 2.54858 + vertex 1.52766 1.77708 2.54786 + endloop + endfacet + facet normal -0.155417 0.116404 0.980967 + outer loop + vertex 1.53231 1.77719 2.54858 + vertex 1.53217 1.78171 2.54802 + vertex 1.52766 1.77708 2.54786 + endloop + endfacet + facet normal -0.200337 0.1607 0.966458 + outer loop + vertex 1.52766 1.77708 2.54786 + vertex 1.53217 1.78171 2.54802 + vertex 1.52838 1.78261 2.54709 + endloop + endfacet + facet normal -0.22717 0.054312 0.972339 + outer loop + vertex 1.53217 1.78171 2.54802 + vertex 1.53197 1.78664 2.5477 + vertex 1.52838 1.78261 2.54709 + endloop + endfacet + facet normal -0.208967 0.0373471 0.977209 + outer loop + vertex 1.52838 1.78261 2.54709 + vertex 1.53197 1.78664 2.5477 + vertex 1.5286 1.78753 2.54695 + endloop + endfacet + facet normal -0.224116 -0.022051 0.974313 + outer loop + vertex 1.53197 1.78664 2.5477 + vertex 1.53093 1.79069 2.54755 + vertex 1.5286 1.78753 2.54695 + endloop + endfacet + facet normal -0.298123 0.0367525 0.95382 + outer loop + vertex 1.5286 1.78753 2.54695 + vertex 1.53093 1.79069 2.54755 + vertex 1.52843 1.79215 2.54672 + endloop + endfacet + facet normal -0.262586 0.100739 0.959635 + outer loop + vertex 1.53093 1.79069 2.54755 + vertex 1.53107 1.79566 2.54707 + vertex 1.52843 1.79215 2.54672 + endloop + endfacet + facet normal -0.250679 0.0913784 0.963748 + outer loop + vertex 1.52843 1.79215 2.54672 + vertex 1.53107 1.79566 2.54707 + vertex 1.52797 1.796 2.54623 + endloop + endfacet + facet normal 0.103909 0.0692341 0.992174 + outer loop + vertex 1.53217 1.78171 2.54802 + vertex 1.53681 1.78559 2.54727 + vertex 1.53197 1.78664 2.5477 + endloop + endfacet + facet normal 0.102373 0.0618399 0.992822 + outer loop + vertex 1.53681 1.78559 2.54727 + vertex 1.5348 1.79143 2.54711 + vertex 1.53197 1.78664 2.5477 + endloop + endfacet + facet normal 0.101921 0.0621104 0.992852 + outer loop + vertex 1.53197 1.78664 2.5477 + vertex 1.5348 1.79143 2.54711 + vertex 1.53093 1.79069 2.54755 + endloop + endfacet + facet normal 0.0956285 0.0937663 0.990991 + outer loop + vertex 1.53107 1.79566 2.54707 + vertex 1.53093 1.79069 2.54755 + vertex 1.5348 1.79143 2.54711 + endloop + endfacet + facet normal 0.119619 0.114877 0.986151 + outer loop + vertex 1.53507 1.79601 2.54654 + vertex 1.53107 1.79566 2.54707 + vertex 1.5348 1.79143 2.54711 + endloop + endfacet + facet normal 0.20982 0.107822 0.971777 + outer loop + vertex 1.53507 1.79601 2.54654 + vertex 1.5348 1.79143 2.54711 + vertex 1.53813 1.79432 2.54607 + endloop + endfacet + facet normal 0.227223 0.141816 0.963461 + outer loop + vertex 1.53813 1.79432 2.54607 + vertex 1.53852 1.79915 2.54527 + vertex 1.53507 1.79601 2.54654 + endloop + endfacet + facet normal 0.216471 0.153851 0.96409 + outer loop + vertex 1.53363 1.79899 2.54639 + vertex 1.53507 1.79601 2.54654 + vertex 1.53852 1.79915 2.54527 + endloop + endfacet + facet normal 0.213204 0.198971 0.956533 + outer loop + vertex 1.53363 1.79899 2.54639 + vertex 1.53852 1.79915 2.54527 + vertex 1.5339 1.80363 2.54537 + endloop + endfacet + facet normal 0.137574 0.206209 0.968789 + outer loop + vertex 1.53363 1.79899 2.54639 + vertex 1.5339 1.80363 2.54537 + vertex 1.53098 1.80016 2.54652 + endloop + endfacet + facet normal 0.101529 0.122806 0.987224 + outer loop + vertex 1.53098 1.80016 2.54652 + vertex 1.53107 1.79566 2.54707 + vertex 1.53363 1.79899 2.54639 + endloop + endfacet + facet normal -0.198699 0.115013 0.973289 + outer loop + vertex 1.53098 1.80016 2.54652 + vertex 1.52858 1.79945 2.54611 + vertex 1.53107 1.79566 2.54707 + endloop + endfacet + facet normal -0.252395 0.0775534 0.964511 + outer loop + vertex 1.52858 1.79945 2.54611 + vertex 1.52797 1.796 2.54623 + vertex 1.53107 1.79566 2.54707 + endloop + endfacet + facet normal -0.221493 0.203901 0.953606 + outer loop + vertex 1.53098 1.80016 2.54652 + vertex 1.52976 1.8028 2.54567 + vertex 1.52858 1.79945 2.54611 + endloop + endfacet + facet normal 0.00852385 0.309037 0.951012 + outer loop + vertex 1.52976 1.8028 2.54567 + vertex 1.53098 1.80016 2.54652 + vertex 1.5339 1.80363 2.54537 + endloop + endfacet + facet normal 0.0101672 0.301693 0.953351 + outer loop + vertex 1.52976 1.8028 2.54567 + vertex 1.5339 1.80363 2.54537 + vertex 1.5302 1.80748 2.54419 + endloop + endfacet + facet normal -0.121412 0.181982 0.975777 + outer loop + vertex 1.5302 1.80748 2.54419 + vertex 1.5339 1.80363 2.54537 + vertex 1.53405 1.80869 2.54444 + endloop + endfacet + facet normal -0.106292 0.131965 0.985539 + outer loop + vertex 1.53405 1.80869 2.54444 + vertex 1.53275 1.81244 2.5438 + vertex 1.5302 1.80748 2.54419 + endloop + endfacet + facet normal -0.282356 0.218434 0.93411 + outer loop + vertex 1.5302 1.80748 2.54419 + vertex 1.53275 1.81244 2.5438 + vertex 1.52931 1.81297 2.54263 + endloop + endfacet + facet normal -0.302053 0.117738 0.945992 + outer loop + vertex 1.53275 1.81244 2.5438 + vertex 1.53199 1.81693 2.543 + vertex 1.52931 1.81297 2.54263 + endloop + endfacet + facet normal -0.327945 0.136325 0.934809 + outer loop + vertex 1.52931 1.81297 2.54263 + vertex 1.53199 1.81693 2.543 + vertex 1.52898 1.81762 2.54184 + endloop + endfacet + facet normal -0.334828 0.108434 0.936019 + outer loop + vertex 1.53199 1.81693 2.543 + vertex 1.53122 1.82048 2.54231 + vertex 1.52898 1.81762 2.54184 + endloop + endfacet + facet normal -0.00595095 0.189246 0.981912 + outer loop + vertex 1.53199 1.81693 2.543 + vertex 1.5356 1.82084 2.54227 + vertex 1.53122 1.82048 2.54231 + endloop + endfacet + facet normal -0.0113625 0.253947 0.967152 + outer loop + vertex 1.53192 1.82415 2.54135 + vertex 1.53122 1.82048 2.54231 + vertex 1.5356 1.82084 2.54227 + endloop + endfacet + facet normal -0.0827481 0.178401 0.980472 + outer loop + vertex 1.5356 1.82541 2.54143 + vertex 1.53192 1.82415 2.54135 + vertex 1.5356 1.82084 2.54227 + endloop + endfacet + facet normal 0.112199 0.177708 0.977666 + outer loop + vertex 1.5356 1.82541 2.54143 + vertex 1.5356 1.82084 2.54227 + vertex 1.53873 1.82428 2.54128 + endloop + endfacet + facet normal 0.126127 0.217549 0.967866 + outer loop + vertex 1.53873 1.82428 2.54128 + vertex 1.53894 1.82877 2.54024 + vertex 1.5356 1.82541 2.54143 + endloop + endfacet + facet normal 0.00281056 0.331384 0.943492 + outer loop + vertex 1.53411 1.82778 2.54061 + vertex 1.5356 1.82541 2.54143 + vertex 1.53894 1.82877 2.54024 + endloop + endfacet + facet normal 0.00936611 0.303076 0.95292 + outer loop + vertex 1.53411 1.82778 2.54061 + vertex 1.53894 1.82877 2.54024 + vertex 1.53491 1.83222 2.53919 + endloop + endfacet + facet normal -0.0941489 0.189767 0.977305 + outer loop + vertex 1.53491 1.83222 2.53919 + vertex 1.53894 1.82877 2.54024 + vertex 1.53914 1.83358 2.53933 + endloop + endfacet + facet normal -0.0743662 0.127116 0.989096 + outer loop + vertex 1.53914 1.83358 2.53933 + vertex 1.53783 1.83705 2.53879 + vertex 1.53491 1.83222 2.53919 + endloop + endfacet + facet normal -0.220037 0.212252 0.95212 + outer loop + vertex 1.53491 1.83222 2.53919 + vertex 1.53783 1.83705 2.53879 + vertex 1.53418 1.83757 2.53783 + endloop + endfacet + facet normal -0.239455 0.100842 0.965656 + outer loop + vertex 1.53783 1.83705 2.53879 + vertex 1.537 1.84146 2.53812 + vertex 1.53418 1.83757 2.53783 + endloop + endfacet + facet normal -0.256498 0.113609 0.959845 + outer loop + vertex 1.53418 1.83757 2.53783 + vertex 1.537 1.84146 2.53812 + vertex 1.53378 1.84254 2.53713 + endloop + endfacet + facet normal -0.276319 0.054234 0.959535 + outer loop + vertex 1.537 1.84146 2.53812 + vertex 1.53593 1.84551 2.53758 + vertex 1.53378 1.84254 2.53713 + endloop + endfacet + facet normal -0.327873 0.0946717 0.939966 + outer loop + vertex 1.53378 1.84254 2.53713 + vertex 1.53593 1.84551 2.53758 + vertex 1.53338 1.84728 2.53651 + endloop + endfacet + facet normal -0.294633 0.145117 0.944528 + outer loop + vertex 1.53593 1.84551 2.53758 + vertex 1.53596 1.85057 2.53681 + vertex 1.53338 1.84728 2.53651 + endloop + endfacet + facet normal -0.249254 0.107832 0.962416 + outer loop + vertex 1.53338 1.84728 2.53651 + vertex 1.53596 1.85057 2.53681 + vertex 1.53284 1.85113 2.53594 + endloop + endfacet + facet normal -0.250024 0.1039 0.962649 + outer loop + vertex 1.53343 1.85439 2.53574 + vertex 1.53284 1.85113 2.53594 + vertex 1.53596 1.85057 2.53681 + endloop + endfacet + facet normal 0.083362 0.148434 0.985403 + outer loop + vertex 1.53596 1.85057 2.53681 + vertex 1.53593 1.84551 2.53758 + vertex 1.54039 1.84563 2.53718 + endloop + endfacet + facet normal 0.101935 0.164754 0.981053 + outer loop + vertex 1.54013 1.85068 2.53636 + vertex 1.53596 1.85057 2.53681 + vertex 1.54039 1.84563 2.53718 + endloop + endfacet + facet normal 0.200268 0.167244 0.965361 + outer loop + vertex 1.54013 1.85068 2.53636 + vertex 1.54039 1.84563 2.53718 + vertex 1.54347 1.84901 2.53596 + endloop + endfacet + facet normal 0.211338 0.190954 0.958578 + outer loop + vertex 1.54347 1.84901 2.53596 + vertex 1.54344 1.85386 2.535 + vertex 1.54013 1.85068 2.53636 + endloop + endfacet + facet normal 0.203964 0.198644 0.958613 + outer loop + vertex 1.53843 1.85386 2.53607 + vertex 1.54013 1.85068 2.53636 + vertex 1.54344 1.85386 2.535 + endloop + endfacet + facet normal 0.20146 0.249447 0.947201 + outer loop + vertex 1.53843 1.85386 2.53607 + vertex 1.54344 1.85386 2.535 + vertex 1.53857 1.85834 2.53486 + endloop + endfacet + facet normal 0.124439 0.254961 0.958911 + outer loop + vertex 1.53843 1.85386 2.53607 + vertex 1.53857 1.85834 2.53486 + vertex 1.53576 1.85512 2.53608 + endloop + endfacet + facet normal 0.0810678 0.163062 0.98328 + outer loop + vertex 1.53576 1.85512 2.53608 + vertex 1.53596 1.85057 2.53681 + vertex 1.53843 1.85386 2.53607 + endloop + endfacet + facet normal -0.185886 0.148905 0.971223 + outer loop + vertex 1.53576 1.85512 2.53608 + vertex 1.53343 1.85439 2.53574 + vertex 1.53596 1.85057 2.53681 + endloop + endfacet + facet normal 0.147259 0.191277 0.970427 + outer loop + vertex 1.53857 1.85834 2.53486 + vertex 1.54344 1.85386 2.535 + vertex 1.54334 1.85872 2.53406 + endloop + endfacet + facet normal 0.148933 0.17578 0.973098 + outer loop + vertex 1.54334 1.85872 2.53406 + vertex 1.54198 1.86233 2.53361 + vertex 1.53857 1.85834 2.53486 + endloop + endfacet + facet normal 0.0645679 0.246098 0.967092 + outer loop + vertex 1.53857 1.85834 2.53486 + vertex 1.54198 1.86233 2.53361 + vertex 1.53845 1.86297 2.53369 + endloop + endfacet + facet normal 0.0546627 0.190151 0.980232 + outer loop + vertex 1.54198 1.86233 2.53361 + vertex 1.54068 1.86581 2.53301 + vertex 1.53845 1.86297 2.53369 + endloop + endfacet + facet normal -0.150649 0.339285 0.928542 + outer loop + vertex 1.53845 1.86297 2.53369 + vertex 1.54068 1.86581 2.53301 + vertex 1.53706 1.86627 2.53226 + endloop + endfacet + facet normal -0.174498 0.206817 0.962693 + outer loop + vertex 1.54068 1.86581 2.53301 + vertex 1.54093 1.87045 2.53206 + vertex 1.53706 1.86627 2.53226 + endloop + endfacet + facet normal -0.222707 0.250355 0.942191 + outer loop + vertex 1.53706 1.86627 2.53226 + vertex 1.54093 1.87045 2.53206 + vertex 1.53715 1.87058 2.53113 + endloop + endfacet + facet normal -0.233749 0.101281 0.967008 + outer loop + vertex 1.53836 1.87425 2.53104 + vertex 1.53715 1.87058 2.53113 + vertex 1.54093 1.87045 2.53206 + endloop + endfacet + facet normal -0.174328 0.143397 0.974191 + outer loop + vertex 1.54102 1.87496 2.53141 + vertex 1.53836 1.87425 2.53104 + vertex 1.54093 1.87045 2.53206 + endloop + endfacet + facet normal 0.100622 0.139706 0.985067 + outer loop + vertex 1.54102 1.87496 2.53141 + vertex 1.54093 1.87045 2.53206 + vertex 1.54378 1.87382 2.53129 + endloop + endfacet + facet normal 0.136678 0.229219 0.963731 + outer loop + vertex 1.54378 1.87382 2.53129 + vertex 1.54388 1.8784 2.53019 + vertex 1.54102 1.87496 2.53141 + endloop + endfacet + facet normal 0.0342342 0.309586 0.950255 + outer loop + vertex 1.53974 1.87758 2.5306 + vertex 1.54102 1.87496 2.53141 + vertex 1.54388 1.8784 2.53019 + endloop + endfacet + facet normal 0.0331464 0.314275 0.948753 + outer loop + vertex 1.53974 1.87758 2.5306 + vertex 1.54388 1.8784 2.53019 + vertex 1.54003 1.88219 2.52907 + endloop + endfacet + facet normal -0.0981501 0.188891 0.977081 + outer loop + vertex 1.54003 1.88219 2.52907 + vertex 1.54388 1.8784 2.53019 + vertex 1.54361 1.88323 2.52922 + endloop + endfacet + facet normal -0.0889935 0.156646 0.983637 + outer loop + vertex 1.54361 1.88323 2.52922 + vertex 1.54226 1.88683 2.52853 + vertex 1.54003 1.88219 2.52907 + endloop + endfacet + facet normal -0.242247 0.225619 0.943617 + outer loop + vertex 1.54003 1.88219 2.52907 + vertex 1.54226 1.88683 2.52853 + vertex 1.53894 1.88755 2.52751 + endloop + endfacet + facet normal -0.268697 0.120647 0.955639 + outer loop + vertex 1.54226 1.88683 2.52853 + vertex 1.54112 1.89048 2.52775 + vertex 1.53894 1.88755 2.52751 + endloop + endfacet + facet normal -0.316519 0.157835 0.935363 + outer loop + vertex 1.53894 1.88755 2.52751 + vertex 1.54112 1.89048 2.52775 + vertex 1.53865 1.89189 2.52667 + endloop + endfacet + facet normal -0.255841 0.260815 0.930871 + outer loop + vertex 1.54112 1.89048 2.52775 + vertex 1.5415 1.89434 2.52677 + vertex 1.53865 1.89189 2.52667 + endloop + endfacet + facet normal 0.0366407 0.241419 0.969729 + outer loop + vertex 1.5415 1.89434 2.52677 + vertex 1.54112 1.89048 2.52775 + vertex 1.54553 1.89094 2.52747 + endloop + endfacet + facet normal 0.0390293 0.221167 0.974455 + outer loop + vertex 1.54226 1.88683 2.52853 + vertex 1.54553 1.89094 2.52747 + vertex 1.54112 1.89048 2.52775 + endloop + endfacet + facet normal 0.0703075 0.197163 0.977846 + outer loop + vertex 1.54566 1.88617 2.52842 + vertex 1.54553 1.89094 2.52747 + vertex 1.54226 1.88683 2.52853 + endloop + endfacet + facet normal 0.185178 0.197426 0.962669 + outer loop + vertex 1.54553 1.89094 2.52747 + vertex 1.54566 1.88617 2.52842 + vertex 1.55015 1.88691 2.5274 + endloop + endfacet + facet normal 0.168885 0.178594 0.96932 + outer loop + vertex 1.55041 1.89156 2.5265 + vertex 1.54553 1.89094 2.52747 + vertex 1.55015 1.88691 2.5274 + endloop + endfacet + facet normal 0.199599 0.175825 0.963974 + outer loop + vertex 1.55041 1.89156 2.5265 + vertex 1.55015 1.88691 2.5274 + vertex 1.55459 1.88995 2.52593 + endloop + endfacet + facet normal 0.203391 0.186641 0.961144 + outer loop + vertex 1.55459 1.88995 2.52593 + vertex 1.55327 1.89499 2.52523 + vertex 1.55041 1.89156 2.5265 + endloop + endfacet + facet normal 0.200566 0.189041 0.961268 + outer loop + vertex 1.54859 1.89449 2.52631 + vertex 1.55041 1.89156 2.5265 + vertex 1.55327 1.89499 2.52523 + endloop + endfacet + facet normal 0.190703 0.253547 0.948339 + outer loop + vertex 1.54859 1.89449 2.52631 + vertex 1.55327 1.89499 2.52523 + vertex 1.54864 1.89881 2.52514 + endloop + endfacet + facet normal 0.146963 0.255971 0.955448 + outer loop + vertex 1.54859 1.89449 2.52631 + vertex 1.54864 1.89881 2.52514 + vertex 1.54541 1.89545 2.52654 + endloop + endfacet + facet normal 0.1321 0.20338 0.970147 + outer loop + vertex 1.54541 1.89545 2.52654 + vertex 1.54553 1.89094 2.52747 + vertex 1.54859 1.89449 2.52631 + endloop + endfacet + facet normal 0.00163173 0.201939 0.979397 + outer loop + vertex 1.54541 1.89545 2.52654 + vertex 1.5415 1.89434 2.52677 + vertex 1.54553 1.89094 2.52747 + endloop + endfacet + facet normal -0.0306211 0.308771 0.950643 + outer loop + vertex 1.54541 1.89545 2.52654 + vertex 1.54355 1.89774 2.52573 + vertex 1.5415 1.89434 2.52677 + endloop + endfacet + facet normal 0.0342475 0.355613 0.934006 + outer loop + vertex 1.54355 1.89774 2.52573 + vertex 1.54541 1.89545 2.52654 + vertex 1.54864 1.89881 2.52514 + endloop + endfacet + facet normal 0.0147771 0.430975 0.902243 + outer loop + vertex 1.54355 1.89774 2.52573 + vertex 1.54864 1.89881 2.52514 + vertex 1.5436 1.90188 2.52376 + endloop + endfacet + facet normal -0.129027 0.223749 0.966069 + outer loop + vertex 1.5436 1.90188 2.52376 + vertex 1.54864 1.89881 2.52514 + vertex 1.54873 1.90339 2.52409 + endloop + endfacet + facet normal -0.0988186 0.116099 0.98831 + outer loop + vertex 1.54873 1.90339 2.52409 + vertex 1.54717 1.90685 2.52353 + vertex 1.5436 1.90188 2.52376 + endloop + endfacet + facet normal -0.211108 0.195361 0.957741 + outer loop + vertex 1.5436 1.90188 2.52376 + vertex 1.54717 1.90685 2.52353 + vertex 1.54338 1.90734 2.52259 + endloop + endfacet + facet normal -0.233356 0.0497683 0.971117 + outer loop + vertex 1.54717 1.90685 2.52353 + vertex 1.54585 1.91055 2.52302 + vertex 1.54338 1.90734 2.52259 + endloop + endfacet + facet normal -0.294545 0.0997572 0.950417 + outer loop + vertex 1.54338 1.90734 2.52259 + vertex 1.54585 1.91055 2.52302 + vertex 1.54316 1.91199 2.52204 + endloop + endfacet + facet normal -0.261587 0.162163 0.951459 + outer loop + vertex 1.54585 1.91055 2.52302 + vertex 1.54606 1.91553 2.52223 + vertex 1.54316 1.91199 2.52204 + endloop + endfacet + facet normal -0.233655 0.138684 0.962378 + outer loop + vertex 1.54316 1.91199 2.52204 + vertex 1.54606 1.91553 2.52223 + vertex 1.54278 1.91584 2.52139 + endloop + endfacet + facet normal -0.2311 0.158788 0.959885 + outer loop + vertex 1.54357 1.91925 2.52102 + vertex 1.54278 1.91584 2.52139 + vertex 1.54606 1.91553 2.52223 + endloop + endfacet + facet normal 0.0717231 0.153601 0.985526 + outer loop + vertex 1.54606 1.91553 2.52223 + vertex 1.54585 1.91055 2.52302 + vertex 1.55016 1.91152 2.52256 + endloop + endfacet + facet normal 0.0993904 0.181291 0.978394 + outer loop + vertex 1.55032 1.91618 2.52168 + vertex 1.54606 1.91553 2.52223 + vertex 1.55016 1.91152 2.52256 + endloop + endfacet + facet normal 0.199716 0.175176 0.964068 + outer loop + vertex 1.55032 1.91618 2.52168 + vertex 1.55016 1.91152 2.52256 + vertex 1.55443 1.91478 2.52108 + endloop + endfacet + facet normal 0.211204 0.213182 0.953911 + outer loop + vertex 1.55443 1.91478 2.52108 + vertex 1.55297 1.91971 2.5203 + vertex 1.55032 1.91618 2.52168 + endloop + endfacet + facet normal 0.201963 0.220288 0.954298 + outer loop + vertex 1.54858 1.91903 2.52139 + vertex 1.55032 1.91618 2.52168 + vertex 1.55297 1.91971 2.5203 + endloop + endfacet + facet normal 0.187971 0.287054 0.939291 + outer loop + vertex 1.54858 1.91903 2.52139 + vertex 1.55297 1.91971 2.5203 + vertex 1.54867 1.9234 2.52004 + endloop + endfacet + facet normal 0.108618 0.292203 0.950168 + outer loop + vertex 1.54858 1.91903 2.52139 + vertex 1.54867 1.9234 2.52004 + vertex 1.546 1.91999 2.52139 + endloop + endfacet + facet normal 0.0690794 0.186209 0.980079 + outer loop + vertex 1.546 1.91999 2.52139 + vertex 1.54606 1.91553 2.52223 + vertex 1.54858 1.91903 2.52139 + endloop + endfacet + facet normal -0.202468 0.178913 0.962807 + outer loop + vertex 1.546 1.91999 2.52139 + vertex 1.54357 1.91925 2.52102 + vertex 1.54606 1.91553 2.52223 + endloop + endfacet + facet normal -0.232831 0.296372 0.926258 + outer loop + vertex 1.546 1.91999 2.52139 + vertex 1.5448 1.92248 2.52029 + vertex 1.54357 1.91925 2.52102 + endloop + endfacet + facet normal -0.0312893 0.390369 0.920127 + outer loop + vertex 1.5448 1.92248 2.52029 + vertex 1.546 1.91999 2.52139 + vertex 1.54867 1.9234 2.52004 + endloop + endfacet + facet normal 0.140958 0.234059 0.96195 + outer loop + vertex 1.54867 1.9234 2.52004 + vertex 1.55297 1.91971 2.5203 + vertex 1.55328 1.92384 2.51925 + endloop + endfacet + facet normal 0.143452 0.215301 0.965954 + outer loop + vertex 1.55328 1.92384 2.51925 + vertex 1.55197 1.92718 2.5187 + vertex 1.54867 1.9234 2.52004 + endloop + endfacet + facet normal 0.0646755 0.281087 0.957501 + outer loop + vertex 1.54867 1.9234 2.52004 + vertex 1.55197 1.92718 2.5187 + vertex 1.54847 1.92791 2.51872 + endloop + endfacet + facet normal 0.0535593 0.227969 0.972194 + outer loop + vertex 1.55197 1.92718 2.5187 + vertex 1.55062 1.9306 2.51798 + vertex 1.54847 1.92791 2.51872 + endloop + endfacet + facet normal -0.093822 0.336127 0.937132 + outer loop + vertex 1.54847 1.92791 2.51872 + vertex 1.55062 1.9306 2.51798 + vertex 1.54697 1.93151 2.51728 + endloop + endfacet + facet normal -0.125966 0.228273 0.965414 + outer loop + vertex 1.55062 1.9306 2.51798 + vertex 1.55079 1.93525 2.5169 + vertex 1.54697 1.93151 2.51728 + endloop + endfacet + facet normal -0.164752 0.266251 0.949719 + outer loop + vertex 1.54697 1.93151 2.51728 + vertex 1.55079 1.93525 2.5169 + vertex 1.54693 1.93571 2.5161 + endloop + endfacet + facet normal -0.183864 0.143981 0.97235 + outer loop + vertex 1.54813 1.93911 2.51582 + vertex 1.54693 1.93571 2.5161 + vertex 1.55079 1.93525 2.5169 + endloop + endfacet + facet normal 0.130799 0.219028 0.966912 + outer loop + vertex 1.55079 1.93525 2.5169 + vertex 1.55062 1.9306 2.51798 + vertex 1.55545 1.93088 2.51726 + endloop + endfacet + facet normal 0.110359 0.197864 0.973997 + outer loop + vertex 1.55529 1.93557 2.51632 + vertex 1.55079 1.93525 2.5169 + vertex 1.55545 1.93088 2.51726 + endloop + endfacet + facet normal 0.191973 0.198103 0.961198 + outer loop + vertex 1.55529 1.93557 2.51632 + vertex 1.55545 1.93088 2.51726 + vertex 1.55855 1.93419 2.51596 + endloop + endfacet + facet normal 0.196788 0.210429 0.957598 + outer loop + vertex 1.55855 1.93419 2.51596 + vertex 1.55844 1.93878 2.51497 + vertex 1.55529 1.93557 2.51632 + endloop + endfacet + facet normal 0.204367 0.203001 0.957614 + outer loop + vertex 1.55359 1.93855 2.51605 + vertex 1.55529 1.93557 2.51632 + vertex 1.55844 1.93878 2.51497 + endloop + endfacet + facet normal 0.200514 0.242967 0.949085 + outer loop + vertex 1.55359 1.93855 2.51605 + vertex 1.55844 1.93878 2.51497 + vertex 1.55353 1.94313 2.5149 + endloop + endfacet + facet normal 0.137869 0.244771 0.959729 + outer loop + vertex 1.55359 1.93855 2.51605 + vertex 1.55353 1.94313 2.5149 + vertex 1.55083 1.93972 2.51615 + endloop + endfacet + facet normal 0.103777 0.162908 0.981168 + outer loop + vertex 1.55083 1.93972 2.51615 + vertex 1.55079 1.93525 2.5169 + vertex 1.55359 1.93855 2.51605 + endloop + endfacet + facet normal -0.156016 0.163716 0.974092 + outer loop + vertex 1.55083 1.93972 2.51615 + vertex 1.54813 1.93911 2.51582 + vertex 1.55079 1.93525 2.5169 + endloop + endfacet + facet normal -0.165671 0.212264 0.963067 + outer loop + vertex 1.55083 1.93972 2.51615 + vertex 1.54945 1.94235 2.51534 + vertex 1.54813 1.93911 2.51582 + endloop + endfacet + facet normal 0.0418315 0.316477 0.947677 + outer loop + vertex 1.54945 1.94235 2.51534 + vertex 1.55083 1.93972 2.51615 + vertex 1.55353 1.94313 2.5149 + endloop + endfacet + facet normal 0.0383178 0.33198 0.942508 + outer loop + vertex 1.54945 1.94235 2.51534 + vertex 1.55353 1.94313 2.5149 + vertex 1.54946 1.94675 2.51379 + endloop + endfacet + facet normal -0.0733231 0.216214 0.973589 + outer loop + vertex 1.54946 1.94675 2.51379 + vertex 1.55353 1.94313 2.5149 + vertex 1.55299 1.94796 2.51378 + endloop + endfacet + facet normal -0.0650211 0.192052 0.979228 + outer loop + vertex 1.55299 1.94796 2.51378 + vertex 1.55115 1.95065 2.51313 + vertex 1.54946 1.94675 2.51379 + endloop + endfacet + facet normal -0.27406 0.272518 0.922293 + outer loop + vertex 1.54946 1.94675 2.51379 + vertex 1.55115 1.95065 2.51313 + vertex 1.54843 1.95162 2.51204 + endloop + endfacet + facet normal -0.264687 0.294344 0.918315 + outer loop + vertex 1.55115 1.95065 2.51313 + vertex 1.55136 1.95468 2.5119 + vertex 1.54843 1.95162 2.51204 + endloop + endfacet + facet normal -0.257286 0.287469 0.922587 + outer loop + vertex 1.54843 1.95162 2.51204 + vertex 1.55136 1.95468 2.5119 + vertex 1.54838 1.95527 2.51089 + endloop + endfacet + facet normal 0.0691259 0.288032 0.955123 + outer loop + vertex 1.55136 1.95468 2.5119 + vertex 1.55115 1.95065 2.51313 + vertex 1.5552 1.95171 2.51252 + endloop + endfacet + facet normal 0.0364939 0.248558 0.967929 + outer loop + vertex 1.5552 1.95592 2.51144 + vertex 1.55136 1.95468 2.5119 + vertex 1.5552 1.95171 2.51252 + endloop + endfacet + facet normal 0.160801 0.245418 0.955988 + outer loop + vertex 1.5552 1.95592 2.51144 + vertex 1.5552 1.95171 2.51252 + vertex 1.5593 1.95476 2.51105 + endloop + endfacet + facet normal 0.163047 0.25425 0.953296 + outer loop + vertex 1.5593 1.95476 2.51105 + vertex 1.55781 1.95934 2.51008 + vertex 1.5552 1.95592 2.51144 + endloop + endfacet + facet normal 0.0955838 0.303761 0.947942 + outer loop + vertex 1.5534 1.95825 2.51087 + vertex 1.5552 1.95592 2.51144 + vertex 1.55781 1.95934 2.51008 + endloop + endfacet + facet normal 0.0828511 0.3459 0.934606 + outer loop + vertex 1.5534 1.95825 2.51087 + vertex 1.55781 1.95934 2.51008 + vertex 1.5538 1.96208 2.50942 + endloop + endfacet + facet normal 0.0219593 0.263698 0.964355 + outer loop + vertex 1.5538 1.96208 2.50942 + vertex 1.55781 1.95934 2.51008 + vertex 1.55816 1.96334 2.50898 + endloop + endfacet + facet normal 0.0285292 0.242926 0.969625 + outer loop + vertex 1.55816 1.96334 2.50898 + vertex 1.55678 1.96654 2.50822 + vertex 1.5538 1.96208 2.50942 + endloop + endfacet + facet normal -0.1705 0.361886 0.916498 + outer loop + vertex 1.5538 1.96208 2.50942 + vertex 1.55678 1.96654 2.50822 + vertex 1.55214 1.96627 2.50746 + endloop + endfacet + facet normal -0.168412 0.177061 0.969684 + outer loop + vertex 1.55678 1.96654 2.50822 + vertex 1.55563 1.9712 2.50717 + vertex 1.55214 1.96627 2.50746 + endloop + endfacet + facet normal -0.263871 0.242473 0.933584 + outer loop + vertex 1.55214 1.96627 2.50746 + vertex 1.55563 1.9712 2.50717 + vertex 1.55209 1.97063 2.50631 + endloop + endfacet + facet normal -0.25006 0.113337 0.961574 + outer loop + vertex 1.55325 1.97446 2.50616 + vertex 1.55209 1.97063 2.50631 + vertex 1.55563 1.9712 2.50717 + endloop + endfacet + facet normal 0.0891932 0.240162 0.966627 + outer loop + vertex 1.55678 1.96654 2.50822 + vertex 1.56098 1.96974 2.50703 + vertex 1.55563 1.9712 2.50717 + endloop + endfacet + facet normal 0.0999227 0.270787 0.957439 + outer loop + vertex 1.55816 1.96334 2.50898 + vertex 1.5607 1.96569 2.50805 + vertex 1.55678 1.96654 2.50822 + endloop + endfacet + facet normal 0.0927742 0.235751 0.967375 + outer loop + vertex 1.5607 1.96569 2.50805 + vertex 1.56098 1.96974 2.50703 + vertex 1.55678 1.96654 2.50822 + endloop + endfacet + facet normal 0.172566 0.228075 0.958229 + outer loop + vertex 1.56098 1.96974 2.50703 + vertex 1.5607 1.96569 2.50805 + vertex 1.5656 1.96586 2.50712 + endloop + endfacet + facet normal 0.177015 0.233337 0.956148 + outer loop + vertex 1.56543 1.97035 2.50606 + vertex 1.56098 1.96974 2.50703 + vertex 1.5656 1.96586 2.50712 + endloop + endfacet + facet normal 0.184903 0.233293 0.954665 + outer loop + vertex 1.56543 1.97035 2.50606 + vertex 1.5656 1.96586 2.50712 + vertex 1.5686 1.9691 2.50575 + endloop + endfacet + facet normal 0.185866 0.235943 0.953826 + outer loop + vertex 1.5686 1.9691 2.50575 + vertex 1.56843 1.97355 2.50468 + vertex 1.56543 1.97035 2.50606 + endloop + endfacet + facet normal 0.193696 0.228673 0.954039 + outer loop + vertex 1.56354 1.97319 2.50576 + vertex 1.56543 1.97035 2.50606 + vertex 1.56843 1.97355 2.50468 + endloop + endfacet + facet normal 0.191333 0.247753 0.949742 + outer loop + vertex 1.56354 1.97319 2.50576 + vertex 1.56843 1.97355 2.50468 + vertex 1.56359 1.9774 2.50466 + endloop + endfacet + facet normal 0.183634 0.248221 0.951139 + outer loop + vertex 1.55949 1.97446 2.50621 + vertex 1.56354 1.97319 2.50576 + vertex 1.56359 1.9774 2.50466 + endloop + endfacet + facet normal 0.176279 0.222127 0.95895 + outer loop + vertex 1.56354 1.97319 2.50576 + vertex 1.55949 1.97446 2.50621 + vertex 1.56098 1.96974 2.50703 + endloop + endfacet + facet normal 0.192275 0.248935 0.949243 + outer loop + vertex 1.56359 1.9774 2.50466 + vertex 1.56843 1.97355 2.50468 + vertex 1.56809 1.97812 2.50355 + endloop + endfacet + facet normal 0.190518 0.257094 0.94742 + outer loop + vertex 1.56809 1.97812 2.50355 + vertex 1.56602 1.9809 2.50322 + vertex 1.56359 1.9774 2.50466 + endloop + endfacet + facet normal 0.186115 0.260163 0.947458 + outer loop + vertex 1.56359 1.9774 2.50466 + vertex 1.56602 1.9809 2.50322 + vertex 1.56197 1.98213 2.50368 + endloop + endfacet + facet normal 0.163492 0.253624 0.953386 + outer loop + vertex 1.56359 1.9774 2.50466 + vertex 1.56197 1.98213 2.50368 + vertex 1.55803 1.97909 2.50516 + endloop + endfacet + facet normal 0.150299 0.269628 0.951163 + outer loop + vertex 1.55803 1.97909 2.50516 + vertex 1.56197 1.98213 2.50368 + vertex 1.558 1.98333 2.50396 + endloop + endfacet + facet normal -0.0413275 0.27097 0.9617 + outer loop + vertex 1.55389 1.98258 2.504 + vertex 1.55803 1.97909 2.50516 + vertex 1.558 1.98333 2.50396 + endloop + endfacet + facet normal -0.0230183 0.172594 0.984724 + outer loop + vertex 1.558 1.98333 2.50396 + vertex 1.5562 1.98609 2.50344 + vertex 1.55389 1.98258 2.504 + endloop + endfacet + facet normal 0.00102142 0.157244 0.987559 + outer loop + vertex 1.55389 1.98258 2.504 + vertex 1.5562 1.98609 2.50344 + vertex 1.55337 1.98727 2.50325 + endloop + endfacet + facet normal 0.0352444 0.2366 0.970968 + outer loop + vertex 1.5562 1.98609 2.50344 + vertex 1.55581 1.99065 2.50234 + vertex 1.55337 1.98727 2.50325 + endloop + endfacet + facet normal 0.060552 0.219136 0.973814 + outer loop + vertex 1.55337 1.98727 2.50325 + vertex 1.55581 1.99065 2.50234 + vertex 1.55144 1.9904 2.50267 + endloop + endfacet + facet normal 0.0644625 0.164469 0.984274 + outer loop + vertex 1.55113 1.99486 2.50194 + vertex 1.55144 1.9904 2.50267 + vertex 1.55581 1.99065 2.50234 + endloop + endfacet + facet normal 0.139341 0.24536 0.959366 + outer loop + vertex 1.55541 1.99515 2.50124 + vertex 1.55113 1.99486 2.50194 + vertex 1.55581 1.99065 2.50234 + endloop + endfacet + facet normal 0.171801 0.246857 0.953701 + outer loop + vertex 1.55541 1.99515 2.50124 + vertex 1.55581 1.99065 2.50234 + vertex 1.55864 1.99391 2.50098 + endloop + endfacet + facet normal 0.178605 0.26594 0.947299 + outer loop + vertex 1.55864 1.99391 2.50098 + vertex 1.55846 1.99838 2.49976 + vertex 1.55541 1.99515 2.50124 + endloop + endfacet + facet normal 0.184511 0.260533 0.94767 + outer loop + vertex 1.55344 1.99809 2.50082 + vertex 1.55541 1.99515 2.50124 + vertex 1.55846 1.99838 2.49976 + endloop + endfacet + facet normal 0.183652 0.268144 0.945712 + outer loop + vertex 1.55344 1.99809 2.50082 + vertex 1.55846 1.99838 2.49976 + vertex 1.55351 2.00235 2.4996 + endloop + endfacet + facet normal 0.186995 0.267921 0.94512 + outer loop + vertex 1.54936 1.99974 2.50116 + vertex 1.55344 1.99809 2.50082 + vertex 1.55351 2.00235 2.4996 + endloop + endfacet + facet normal 0.185747 0.269745 0.944847 + outer loop + vertex 1.5477 2.00425 2.5002 + vertex 1.54936 1.99974 2.50116 + vertex 1.55351 2.00235 2.4996 + endloop + endfacet + facet normal 0.187746 0.2766 0.942467 + outer loop + vertex 1.55351 2.00235 2.4996 + vertex 1.55195 2.0071 2.49851 + vertex 1.5477 2.00425 2.5002 + endloop + endfacet + facet normal 0.176463 0.291977 0.940005 + outer loop + vertex 1.5477 2.00425 2.5002 + vertex 1.55195 2.0071 2.49851 + vertex 1.54786 2.0083 2.49891 + endloop + endfacet + facet normal 0.124389 0.296256 0.946974 + outer loop + vertex 1.54323 2.00717 2.49987 + vertex 1.5477 2.00425 2.5002 + vertex 1.54786 2.0083 2.49891 + endloop + endfacet + facet normal 0.131592 0.272082 0.953234 + outer loop + vertex 1.54786 2.0083 2.49891 + vertex 1.54596 2.01089 2.49843 + vertex 1.54323 2.00717 2.49987 + endloop + endfacet + facet normal 0.121327 0.279325 0.9525 + outer loop + vertex 1.54323 2.00717 2.49987 + vertex 1.54596 2.01089 2.49843 + vertex 1.54173 2.01174 2.49873 + endloop + endfacet + facet normal -0.0192117 0.237906 0.971098 + outer loop + vertex 1.54323 2.00717 2.49987 + vertex 1.54173 2.01174 2.49873 + vertex 1.53632 2.00725 2.49972 + endloop + endfacet + facet normal -0.0182714 0.293034 0.955928 + outer loop + vertex 1.53632 2.00725 2.49972 + vertex 1.54035 2.00369 2.50089 + vertex 1.54323 2.00717 2.49987 + endloop + endfacet + facet normal -0.0379729 0.307789 0.950697 + outer loop + vertex 1.54035 2.00369 2.50089 + vertex 1.5436 2.00346 2.50109 + vertex 1.54323 2.00717 2.49987 + endloop + endfacet + facet normal -0.0469801 0.203231 0.978003 + outer loop + vertex 1.5436 2.00346 2.50109 + vertex 1.54035 2.00369 2.50089 + vertex 1.54279 2.00057 2.50165 + endloop + endfacet + facet normal 0.0199263 0.185474 0.982447 + outer loop + vertex 1.54558 2.00119 2.50148 + vertex 1.5436 2.00346 2.50109 + vertex 1.54279 2.00057 2.50165 + endloop + endfacet + facet normal 0.0334231 0.127453 0.991281 + outer loop + vertex 1.54558 2.00119 2.50148 + vertex 1.54279 2.00057 2.50165 + vertex 1.54628 1.99762 2.50191 + endloop + endfacet + facet normal 0.138665 0.146479 0.979447 + outer loop + vertex 1.54558 2.00119 2.50148 + vertex 1.54628 1.99762 2.50191 + vertex 1.54936 1.99974 2.50116 + endloop + endfacet + facet normal 0.104776 0.194258 0.975339 + outer loop + vertex 1.55113 1.99486 2.50194 + vertex 1.54936 1.99974 2.50116 + vertex 1.54628 1.99762 2.50191 + endloop + endfacet + facet normal -0.00219883 0.00640972 0.999977 + outer loop + vertex 1.54756 1.99267 2.50195 + vertex 1.55113 1.99486 2.50194 + vertex 1.54628 1.99762 2.50191 + endloop + endfacet + facet normal -0.195338 -0.04368 0.979763 + outer loop + vertex 1.54756 1.99267 2.50195 + vertex 1.54628 1.99762 2.50191 + vertex 1.54328 1.99675 2.50128 + endloop + endfacet + facet normal -0.17341 -0.118173 0.977734 + outer loop + vertex 1.54279 2.00057 2.50165 + vertex 1.54328 1.99675 2.50128 + vertex 1.54628 1.99762 2.50191 + endloop + endfacet + facet normal -0.279799 -0.129116 0.951337 + outer loop + vertex 1.54328 1.99675 2.50128 + vertex 1.54279 2.00057 2.50165 + vertex 1.54024 2.00037 2.50087 + endloop + endfacet + facet normal 0.148916 0.291603 0.944876 + outer loop + vertex 1.5436 2.00346 2.50109 + vertex 1.54558 2.00119 2.50148 + vertex 1.5477 2.00425 2.5002 + endloop + endfacet + facet normal -0.291626 0.0065785 0.95651 + outer loop + vertex 1.54279 2.00057 2.50165 + vertex 1.54035 2.00369 2.50089 + vertex 1.54024 2.00037 2.50087 + endloop + endfacet + facet normal 0.105156 0.0924151 0.990152 + outer loop + vertex 1.53632 2.00725 2.49972 + vertex 1.54173 2.01174 2.49873 + vertex 1.53771 2.01271 2.49906 + endloop + endfacet + facet normal 0.175947 0.0734663 0.981654 + outer loop + vertex 1.53319 2.01167 2.49995 + vertex 1.53632 2.00725 2.49972 + vertex 1.53771 2.01271 2.49906 + endloop + endfacet + facet normal 0.139123 0.219469 0.965649 + outer loop + vertex 1.53771 2.01271 2.49906 + vertex 1.53615 2.01567 2.49861 + vertex 1.53319 2.01167 2.49995 + endloop + endfacet + facet normal 0.0927263 0.252987 0.963016 + outer loop + vertex 1.53319 2.01167 2.49995 + vertex 1.53615 2.01567 2.49861 + vertex 1.53201 2.01653 2.49879 + endloop + endfacet + facet normal 0.100737 0.294243 0.950407 + outer loop + vertex 1.53615 2.01567 2.49861 + vertex 1.53637 2.02007 2.49723 + vertex 1.53201 2.01653 2.49879 + endloop + endfacet + facet normal 0.12645 0.265047 0.955908 + outer loop + vertex 1.53201 2.01653 2.49879 + vertex 1.53637 2.02007 2.49723 + vertex 1.53072 2.02161 2.49755 + endloop + endfacet + facet normal 0.124286 0.264597 0.956317 + outer loop + vertex 1.53201 2.01653 2.49879 + vertex 1.53072 2.02161 2.49755 + vertex 1.528 2.01761 2.49901 + endloop + endfacet + facet normal 0.0813959 0.0981316 0.991839 + outer loop + vertex 1.52669 2.01208 2.49966 + vertex 1.53201 2.01653 2.49879 + vertex 1.528 2.01761 2.49901 + endloop + endfacet + facet normal 0.197892 0.0689003 0.977799 + outer loop + vertex 1.52356 2.01702 2.49995 + vertex 1.52669 2.01208 2.49966 + vertex 1.528 2.01761 2.49901 + endloop + endfacet + facet normal 0.167918 0.255188 0.952199 + outer loop + vertex 1.528 2.01761 2.49901 + vertex 1.52624 2.02069 2.49849 + vertex 1.52356 2.01702 2.49995 + endloop + endfacet + facet normal 0.13512 0.278694 0.950827 + outer loop + vertex 1.52356 2.01702 2.49995 + vertex 1.52624 2.02069 2.49849 + vertex 1.52215 2.02191 2.49872 + endloop + endfacet + facet normal 0.169448 0.28657 0.942955 + outer loop + vertex 1.52356 2.01702 2.49995 + vertex 1.52215 2.02191 2.49872 + vertex 1.51816 2.01898 2.50032 + endloop + endfacet + facet normal 0.167401 0.280511 0.94514 + outer loop + vertex 1.51816 2.01898 2.50032 + vertex 1.51991 2.01503 2.50119 + vertex 1.52356 2.01702 2.49995 + endloop + endfacet + facet normal 0.195903 0.232994 0.952542 + outer loop + vertex 1.51991 2.01503 2.50119 + vertex 1.52299 2.01355 2.50092 + vertex 1.52356 2.01702 2.49995 + endloop + endfacet + facet normal 0.105859 0.0381916 0.993647 + outer loop + vertex 1.52299 2.01355 2.50092 + vertex 1.51991 2.01503 2.50119 + vertex 1.52092 2.01275 2.50117 + endloop + endfacet + facet normal 0.162321 -0.110484 0.980533 + outer loop + vertex 1.52303 2.01212 2.50075 + vertex 1.52299 2.01355 2.50092 + vertex 1.52092 2.01275 2.50117 + endloop + endfacet + facet normal 0.281608 -0.103582 0.953922 + outer loop + vertex 1.52299 2.01355 2.50092 + vertex 1.52303 2.01212 2.50075 + vertex 1.52669 2.01208 2.49966 + endloop + endfacet + facet normal 0.0259856 0.00283146 0.999658 + outer loop + vertex 1.52092 2.01275 2.50117 + vertex 1.51991 2.01503 2.50119 + vertex 1.51712 2.0134 2.50126 + endloop + endfacet + facet normal 0.057029 -0.0504098 0.997099 + outer loop + vertex 1.51633 2.01608 2.50144 + vertex 1.51712 2.0134 2.50126 + vertex 1.51991 2.01503 2.50119 + endloop + endfacet + facet normal 0.0690622 -0.0468424 0.996512 + outer loop + vertex 1.51633 2.01608 2.50144 + vertex 1.51293 2.016 2.50168 + vertex 1.51712 2.0134 2.50126 + endloop + endfacet + facet normal -0.0300836 -0.203398 0.978634 + outer loop + vertex 1.51293 2.016 2.50168 + vertex 1.5128 2.01358 2.50117 + vertex 1.51712 2.0134 2.50126 + endloop + endfacet + facet normal -0.057407 -0.20172 0.97776 + outer loop + vertex 1.5128 2.01358 2.50117 + vertex 1.51293 2.016 2.50168 + vertex 1.5079 2.0167 2.50152 + endloop + endfacet + facet normal -0.0136019 0.115378 0.993229 + outer loop + vertex 1.51293 2.016 2.50168 + vertex 1.51021 2.01952 2.50123 + vertex 1.5079 2.0167 2.50152 + endloop + endfacet + facet normal 0.0723657 0.0453996 0.996344 + outer loop + vertex 1.50618 2.02067 2.50147 + vertex 1.5079 2.0167 2.50152 + vertex 1.51021 2.01952 2.50123 + endloop + endfacet + facet normal 0.138598 0.287886 0.947582 + outer loop + vertex 1.51021 2.01952 2.50123 + vertex 1.50794 2.02401 2.5002 + vertex 1.50618 2.02067 2.50147 + endloop + endfacet + facet normal 0.159749 0.276699 0.947585 + outer loop + vertex 1.50369 2.02335 2.50111 + vertex 1.50618 2.02067 2.50147 + vertex 1.50794 2.02401 2.5002 + endloop + endfacet + facet normal 0.150405 0.320086 0.935373 + outer loop + vertex 1.50369 2.02335 2.50111 + vertex 1.50794 2.02401 2.5002 + vertex 1.50347 2.02744 2.49974 + endloop + endfacet + facet normal 0.141349 0.32008 0.936787 + outer loop + vertex 1.49963 2.02455 2.50131 + vertex 1.50369 2.02335 2.50111 + vertex 1.50347 2.02744 2.49974 + endloop + endfacet + facet normal 0.138852 0.323046 0.936142 + outer loop + vertex 1.49784 2.02904 2.50002 + vertex 1.49963 2.02455 2.50131 + vertex 1.50347 2.02744 2.49974 + endloop + endfacet + facet normal 0.136258 0.313271 0.939838 + outer loop + vertex 1.50347 2.02744 2.49974 + vertex 1.50199 2.03203 2.49843 + vertex 1.49784 2.02904 2.50002 + endloop + endfacet + facet normal 0.127814 0.323734 0.937475 + outer loop + vertex 1.49784 2.02904 2.50002 + vertex 1.50199 2.03203 2.49843 + vertex 1.49798 2.03311 2.4986 + endloop + endfacet + facet normal 0.123625 0.324034 0.937933 + outer loop + vertex 1.49352 2.03213 2.49953 + vertex 1.49784 2.02904 2.50002 + vertex 1.49798 2.03311 2.4986 + endloop + endfacet + facet normal 0.128293 0.30755 0.942844 + outer loop + vertex 1.49798 2.03311 2.4986 + vertex 1.49605 2.03559 2.49805 + vertex 1.49352 2.03213 2.49953 + endloop + endfacet + facet normal 0.121779 0.312052 0.942228 + outer loop + vertex 1.49352 2.03213 2.49953 + vertex 1.49605 2.03559 2.49805 + vertex 1.49202 2.03645 2.49829 + endloop + endfacet + facet normal 0.116105 0.282472 0.952223 + outer loop + vertex 1.49605 2.03559 2.49805 + vertex 1.49616 2.03952 2.49688 + vertex 1.49202 2.03645 2.49829 + endloop + endfacet + facet normal 0.11413 0.282587 0.952428 + outer loop + vertex 1.49616 2.03952 2.49688 + vertex 1.49605 2.03559 2.49805 + vertex 1.50052 2.0365 2.49725 + endloop + endfacet + facet normal 0.109234 0.275839 0.954977 + outer loop + vertex 1.50055 2.04051 2.49609 + vertex 1.49616 2.03952 2.49688 + vertex 1.50052 2.0365 2.49725 + endloop + endfacet + facet normal 0.114771 0.275628 0.954388 + outer loop + vertex 1.50055 2.04051 2.49609 + vertex 1.50052 2.0365 2.49725 + vertex 1.50459 2.03945 2.49591 + endloop + endfacet + facet normal 0.116549 0.282802 0.952071 + outer loop + vertex 1.50459 2.03945 2.49591 + vertex 1.50296 2.04389 2.49479 + vertex 1.50055 2.04051 2.49609 + endloop + endfacet + facet normal 0.114209 0.284395 0.95188 + outer loop + vertex 1.4985 2.04297 2.4956 + vertex 1.50055 2.04051 2.49609 + vertex 1.50296 2.04389 2.49479 + endloop + endfacet + facet normal 0.112369 0.291595 0.949919 + outer loop + vertex 1.4985 2.04297 2.4956 + vertex 1.50296 2.04389 2.49479 + vertex 1.49841 2.047 2.49437 + endloop + endfacet + facet normal 0.114402 0.294415 0.948806 + outer loop + vertex 1.49841 2.047 2.49437 + vertex 1.50296 2.04389 2.49479 + vertex 1.50302 2.04805 2.49349 + endloop + endfacet + facet normal 0.113167 0.298826 0.947574 + outer loop + vertex 1.50302 2.04805 2.49349 + vertex 1.50072 2.05172 2.49261 + vertex 1.49841 2.047 2.49437 + endloop + endfacet + facet normal 0.114854 0.298018 0.947625 + outer loop + vertex 1.49841 2.047 2.49437 + vertex 1.50072 2.05172 2.49261 + vertex 1.49611 2.05068 2.49349 + endloop + endfacet + facet normal 0.114588 0.29897 0.947358 + outer loop + vertex 1.4962 2.05486 2.49216 + vertex 1.49611 2.05068 2.49349 + vertex 1.50072 2.05172 2.49261 + endloop + endfacet + facet normal 0.11515 0.299736 0.947048 + outer loop + vertex 1.50066 2.05577 2.49133 + vertex 1.4962 2.05486 2.49216 + vertex 1.50072 2.05172 2.49261 + endloop + endfacet + facet normal 0.118156 0.299671 0.946698 + outer loop + vertex 1.50066 2.05577 2.49133 + vertex 1.50072 2.05172 2.49261 + vertex 1.50467 2.0549 2.49111 + endloop + endfacet + facet normal 0.118065 0.299213 0.946854 + outer loop + vertex 1.50467 2.0549 2.49111 + vertex 1.503 2.05918 2.48996 + vertex 1.50066 2.05577 2.49133 + endloop + endfacet + facet normal 0.117067 0.299864 0.946772 + outer loop + vertex 1.49864 2.05827 2.49079 + vertex 1.50066 2.05577 2.49133 + vertex 1.503 2.05918 2.48996 + endloop + endfacet + facet normal 0.117336 0.298841 0.947062 + outer loop + vertex 1.49864 2.05827 2.49079 + vertex 1.503 2.05918 2.48996 + vertex 1.49865 2.06227 2.48953 + endloop + endfacet + facet normal 0.115069 0.298928 0.947313 + outer loop + vertex 1.49458 2.05933 2.49095 + vertex 1.49864 2.05827 2.49079 + vertex 1.49865 2.06227 2.48953 + endloop + endfacet + facet normal 0.114835 0.299221 0.947249 + outer loop + vertex 1.49293 2.0638 2.48974 + vertex 1.49458 2.05933 2.49095 + vertex 1.49865 2.06227 2.48953 + endloop + endfacet + facet normal 0.114808 0.299116 0.947285 + outer loop + vertex 1.49865 2.06227 2.48953 + vertex 1.49712 2.06667 2.48832 + vertex 1.49293 2.0638 2.48974 + endloop + endfacet + facet normal 0.114171 0.299954 0.947097 + outer loop + vertex 1.49293 2.0638 2.48974 + vertex 1.49712 2.06667 2.48832 + vertex 1.49298 2.06798 2.48841 + endloop + endfacet + facet normal 0.113679 0.299976 0.947149 + outer loop + vertex 1.48834 2.06694 2.48929 + vertex 1.49293 2.0638 2.48974 + vertex 1.49298 2.06798 2.48841 + endloop + endfacet + facet normal 0.113123 0.301972 0.946581 + outer loop + vertex 1.49298 2.06798 2.48841 + vertex 1.49066 2.07163 2.48752 + vertex 1.48834 2.06694 2.48929 + endloop + endfacet + facet normal 0.114188 0.301461 0.946616 + outer loop + vertex 1.48834 2.06694 2.48929 + vertex 1.49066 2.07163 2.48752 + vertex 1.48606 2.07055 2.48842 + endloop + endfacet + facet normal 0.114235 0.301487 0.946602 + outer loop + vertex 1.48834 2.06694 2.48929 + vertex 1.48606 2.07055 2.48842 + vertex 1.48306 2.06781 2.48966 + endloop + endfacet + facet normal 0.114078 0.300377 0.946974 + outer loop + vertex 1.48306 2.06781 2.48966 + vertex 1.48441 2.06379 2.49077 + vertex 1.48834 2.06694 2.48929 + endloop + endfacet + facet normal 0.114306 0.300119 0.947028 + outer loop + vertex 1.48441 2.06379 2.49077 + vertex 1.48845 2.06291 2.49056 + vertex 1.48834 2.06694 2.48929 + endloop + endfacet + facet normal 0.114279 0.299984 0.947074 + outer loop + vertex 1.48845 2.06291 2.49056 + vertex 1.48441 2.06379 2.49077 + vertex 1.48614 2.05951 2.49191 + endloop + endfacet + facet normal 0.114584 0.299788 0.9471 + outer loop + vertex 1.49052 2.06041 2.4911 + vertex 1.48845 2.06291 2.49056 + vertex 1.48614 2.05951 2.49191 + endloop + endfacet + facet normal 0.113983 0.299339 0.947314 + outer loop + vertex 1.48845 2.06291 2.49056 + vertex 1.49052 2.06041 2.4911 + vertex 1.49293 2.0638 2.48974 + endloop + endfacet + facet normal 0.115632 0.300449 0.946763 + outer loop + vertex 1.48614 2.05951 2.49191 + vertex 1.48441 2.06379 2.49077 + vertex 1.48098 2.06073 2.49216 + endloop + endfacet + facet normal 0.115654 0.30055 0.946728 + outer loop + vertex 1.48212 2.05665 2.49331 + vertex 1.48614 2.05951 2.49191 + vertex 1.48098 2.06073 2.49216 + endloop + endfacet + facet normal 0.117001 0.300852 0.946467 + outer loop + vertex 1.48212 2.05665 2.49331 + vertex 1.48098 2.06073 2.49216 + vertex 1.47799 2.05797 2.4934 + endloop + endfacet + facet normal 0.116995 0.300834 0.946473 + outer loop + vertex 1.47792 2.05379 2.49474 + vertex 1.48212 2.05665 2.49331 + vertex 1.47799 2.05797 2.4934 + endloop + endfacet + facet normal 0.116769 0.300846 0.946497 + outer loop + vertex 1.47335 2.05696 2.4943 + vertex 1.47792 2.05379 2.49474 + vertex 1.47799 2.05797 2.4934 + endloop + endfacet + facet normal 0.116626 0.301374 0.946347 + outer loop + vertex 1.47799 2.05797 2.4934 + vertex 1.47568 2.06164 2.49252 + vertex 1.47335 2.05696 2.4943 + endloop + endfacet + facet normal 0.115345 0.301996 0.946305 + outer loop + vertex 1.47335 2.05696 2.4943 + vertex 1.47568 2.06164 2.49252 + vertex 1.47106 2.06065 2.4934 + endloop + endfacet + facet normal 0.113622 0.301049 0.946815 + outer loop + vertex 1.47335 2.05696 2.4943 + vertex 1.47106 2.06065 2.4934 + vertex 1.46806 2.05788 2.49464 + endloop + endfacet + facet normal 0.113998 0.303518 0.945982 + outer loop + vertex 1.46806 2.05788 2.49464 + vertex 1.4694 2.05382 2.49578 + vertex 1.47335 2.05696 2.4943 + endloop + endfacet + facet normal 0.115219 0.302124 0.94628 + outer loop + vertex 1.4694 2.05382 2.49578 + vertex 1.47343 2.05292 2.49558 + vertex 1.47335 2.05696 2.4943 + endloop + endfacet + facet normal 0.114575 0.299015 0.947345 + outer loop + vertex 1.47343 2.05292 2.49558 + vertex 1.4694 2.05382 2.49578 + vertex 1.47112 2.04953 2.49693 + endloop + endfacet + facet normal 0.117226 0.297299 0.947561 + outer loop + vertex 1.47549 2.05039 2.49612 + vertex 1.47343 2.05292 2.49558 + vertex 1.47112 2.04953 2.49693 + endloop + endfacet + facet normal 0.118831 0.290887 0.949349 + outer loop + vertex 1.47549 2.05039 2.49612 + vertex 1.47112 2.04953 2.49693 + vertex 1.47553 2.04637 2.49734 + endloop + endfacet + facet normal 0.119903 0.29086 0.949223 + outer loop + vertex 1.47549 2.05039 2.49612 + vertex 1.47553 2.04637 2.49734 + vertex 1.47957 2.04929 2.49594 + endloop + endfacet + facet normal 0.12133 0.296467 0.947305 + outer loop + vertex 1.47957 2.04929 2.49594 + vertex 1.47792 2.05379 2.49474 + vertex 1.47549 2.05039 2.49612 + endloop + endfacet + facet normal 0.117547 0.295305 0.948144 + outer loop + vertex 1.47792 2.05379 2.49474 + vertex 1.47957 2.04929 2.49594 + vertex 1.48363 2.05224 2.49451 + endloop + endfacet + facet normal 0.11912 0.293334 0.94856 + outer loop + vertex 1.47957 2.04929 2.49594 + vertex 1.48363 2.0482 2.49576 + vertex 1.48363 2.05224 2.49451 + endloop + endfacet + facet normal 0.115672 0.293454 0.948949 + outer loop + vertex 1.48363 2.0482 2.49576 + vertex 1.488 2.04909 2.49496 + vertex 1.48363 2.05224 2.49451 + endloop + endfacet + facet normal 0.116789 0.294922 0.948357 + outer loop + vertex 1.48363 2.05224 2.49451 + vertex 1.488 2.04909 2.49496 + vertex 1.48807 2.05306 2.49371 + endloop + endfacet + facet normal 0.114393 0.295046 0.948611 + outer loop + vertex 1.488 2.04909 2.49496 + vertex 1.49203 2.05198 2.49357 + vertex 1.48807 2.05306 2.49371 + endloop + endfacet + facet normal 0.11524 0.298308 0.947487 + outer loop + vertex 1.49203 2.05198 2.49357 + vertex 1.49053 2.05639 2.49236 + vertex 1.48807 2.05306 2.49371 + endloop + endfacet + facet normal 0.115668 0.29801 0.947529 + outer loop + vertex 1.48807 2.05306 2.49371 + vertex 1.49053 2.05639 2.49236 + vertex 1.4861 2.05558 2.49316 + endloop + endfacet + facet normal 0.116007 0.298249 0.947412 + outer loop + vertex 1.48807 2.05306 2.49371 + vertex 1.4861 2.05558 2.49316 + vertex 1.48363 2.05224 2.49451 + endloop + endfacet + facet normal 0.116074 0.298202 0.947419 + outer loop + vertex 1.48363 2.05224 2.49451 + vertex 1.4861 2.05558 2.49316 + vertex 1.48212 2.05665 2.49331 + endloop + endfacet + facet normal 0.11436 0.298059 0.947672 + outer loop + vertex 1.49203 2.05198 2.49357 + vertex 1.4962 2.05486 2.49216 + vertex 1.49053 2.05639 2.49236 + endloop + endfacet + facet normal 0.114537 0.298745 0.947435 + outer loop + vertex 1.4962 2.05486 2.49216 + vertex 1.49458 2.05933 2.49095 + vertex 1.49053 2.05639 2.49236 + endloop + endfacet + facet normal 0.114347 0.298982 0.947383 + outer loop + vertex 1.49052 2.06041 2.4911 + vertex 1.49053 2.05639 2.49236 + vertex 1.49458 2.05933 2.49095 + endloop + endfacet + facet normal 0.114795 0.298968 0.947333 + outer loop + vertex 1.49052 2.06041 2.4911 + vertex 1.48614 2.05951 2.49191 + vertex 1.49053 2.05639 2.49236 + endloop + endfacet + facet normal 0.115289 0.299624 0.947066 + outer loop + vertex 1.48614 2.05951 2.49191 + vertex 1.4861 2.05558 2.49316 + vertex 1.49053 2.05639 2.49236 + endloop + endfacet + facet normal 0.113765 0.29584 0.948439 + outer loop + vertex 1.49313 2.04787 2.49472 + vertex 1.49203 2.05198 2.49357 + vertex 1.488 2.04909 2.49496 + endloop + endfacet + facet normal 0.111942 0.287639 0.951175 + outer loop + vertex 1.488 2.04909 2.49496 + vertex 1.48966 2.04477 2.49607 + vertex 1.49313 2.04787 2.49472 + endloop + endfacet + facet normal 0.110576 0.289047 0.950907 + outer loop + vertex 1.48966 2.04477 2.49607 + vertex 1.49447 2.0438 2.4958 + vertex 1.49313 2.04787 2.49472 + endloop + endfacet + facet normal 0.109416 0.282748 0.952933 + outer loop + vertex 1.49447 2.0438 2.4958 + vertex 1.48966 2.04477 2.49607 + vertex 1.49088 2.0406 2.49716 + endloop + endfacet + facet normal 0.113618 0.28377 0.952137 + outer loop + vertex 1.49088 2.0406 2.49716 + vertex 1.48966 2.04477 2.49607 + vertex 1.48561 2.04173 2.49746 + endloop + endfacet + facet normal 0.115029 0.291019 0.949777 + outer loop + vertex 1.48718 2.03744 2.49858 + vertex 1.49088 2.0406 2.49716 + vertex 1.48561 2.04173 2.49746 + endloop + endfacet + facet normal 0.118107 0.291972 0.949107 + outer loop + vertex 1.48718 2.03744 2.49858 + vertex 1.48561 2.04173 2.49746 + vertex 1.48318 2.03833 2.49881 + endloop + endfacet + facet normal 0.123403 0.318134 0.93998 + outer loop + vertex 1.48304 2.03441 2.50015 + vertex 1.48718 2.03744 2.49858 + vertex 1.48318 2.03833 2.49881 + endloop + endfacet + facet normal 0.127352 0.317841 0.939552 + outer loop + vertex 1.47875 2.0375 2.49969 + vertex 1.48304 2.03441 2.50015 + vertex 1.48318 2.03833 2.49881 + endloop + endfacet + facet normal 0.131415 0.301299 0.944431 + outer loop + vertex 1.48318 2.03833 2.49881 + vertex 1.48122 2.0408 2.49829 + vertex 1.47875 2.0375 2.49969 + endloop + endfacet + facet normal 0.129079 0.302958 0.944222 + outer loop + vertex 1.47875 2.0375 2.49969 + vertex 1.48122 2.0408 2.49829 + vertex 1.47717 2.04192 2.49849 + endloop + endfacet + facet normal 0.123429 0.301293 0.945509 + outer loop + vertex 1.47875 2.0375 2.49969 + vertex 1.47717 2.04192 2.49849 + vertex 1.47312 2.03911 2.49991 + endloop + endfacet + facet normal 0.128943 0.321561 0.938069 + outer loop + vertex 1.47312 2.03911 2.49991 + vertex 1.47477 2.03457 2.50124 + vertex 1.47875 2.0375 2.49969 + endloop + endfacet + facet normal 0.126858 0.324085 0.937484 + outer loop + vertex 1.47477 2.03457 2.50124 + vertex 1.47872 2.03347 2.50108 + vertex 1.47875 2.0375 2.49969 + endloop + endfacet + facet normal 0.121101 0.302421 0.94545 + outer loop + vertex 1.47872 2.03347 2.50108 + vertex 1.47477 2.03457 2.50124 + vertex 1.4765 2.0299 2.50251 + endloop + endfacet + facet normal 0.111724 0.307993 0.944806 + outer loop + vertex 1.48072 2.03088 2.50169 + vertex 1.47872 2.03347 2.50108 + vertex 1.4765 2.0299 2.50251 + endloop + endfacet + facet normal 0.128689 0.247551 0.96029 + outer loop + vertex 1.48072 2.03088 2.50169 + vertex 1.4765 2.0299 2.50251 + vertex 1.48108 2.0266 2.50275 + endloop + endfacet + facet normal 0.111333 0.246708 0.962673 + outer loop + vertex 1.48072 2.03088 2.50169 + vertex 1.48108 2.0266 2.50275 + vertex 1.48466 2.02997 2.50147 + endloop + endfacet + facet normal 0.127939 0.32504 0.937006 + outer loop + vertex 1.48466 2.02997 2.50147 + vertex 1.48304 2.03441 2.50015 + vertex 1.48072 2.03088 2.50169 + endloop + endfacet + facet normal 0.127348 0.324865 0.937147 + outer loop + vertex 1.48304 2.03441 2.50015 + vertex 1.48466 2.02997 2.50147 + vertex 1.48826 2.03325 2.49984 + endloop + endfacet + facet normal 0.122109 0.330063 0.936028 + outer loop + vertex 1.48466 2.02997 2.50147 + vertex 1.48941 2.02898 2.5012 + vertex 1.48826 2.03325 2.49984 + endloop + endfacet + facet normal 0.126644 0.330982 0.9351 + outer loop + vertex 1.48826 2.03325 2.49984 + vertex 1.48941 2.02898 2.5012 + vertex 1.49352 2.03213 2.49953 + endloop + endfacet + facet normal 0.12309 0.312423 0.941934 + outer loop + vertex 1.49352 2.03213 2.49953 + vertex 1.49202 2.03645 2.49829 + vertex 1.48826 2.03325 2.49984 + endloop + endfacet + facet normal 0.120975 0.31468 0.941457 + outer loop + vertex 1.48826 2.03325 2.49984 + vertex 1.49202 2.03645 2.49829 + vertex 1.48718 2.03744 2.49858 + endloop + endfacet + facet normal 0.123276 0.334878 0.934162 + outer loop + vertex 1.48941 2.02898 2.5012 + vertex 1.49338 2.0281 2.50099 + vertex 1.49352 2.03213 2.49953 + endloop + endfacet + facet normal 0.13146 0.334267 0.933265 + outer loop + vertex 1.49338 2.0281 2.50099 + vertex 1.49784 2.02904 2.50002 + vertex 1.49352 2.03213 2.49953 + endloop + endfacet + facet normal 0.133211 0.327976 0.935247 + outer loop + vertex 1.49338 2.0281 2.50099 + vertex 1.49548 2.0256 2.50157 + vertex 1.49784 2.02904 2.50002 + endloop + endfacet + facet normal 0.10196 0.304499 0.94704 + outer loop + vertex 1.49548 2.0256 2.50157 + vertex 1.49338 2.0281 2.50099 + vertex 1.49118 2.02458 2.50236 + endloop + endfacet + facet normal 0.128066 0.211147 0.969028 + outer loop + vertex 1.49548 2.0256 2.50157 + vertex 1.49118 2.02458 2.50236 + vertex 1.49596 2.02164 2.50237 + endloop + endfacet + facet normal 0.113636 0.209832 0.971111 + outer loop + vertex 1.49548 2.0256 2.50157 + vertex 1.49596 2.02164 2.50237 + vertex 1.49963 2.02455 2.50131 + endloop + endfacet + facet normal 0.115907 0.207085 0.971433 + outer loop + vertex 1.5021 2.0202 2.50194 + vertex 1.49963 2.02455 2.50131 + vertex 1.49596 2.02164 2.50237 + endloop + endfacet + facet normal 0.0347297 -0.146112 0.988658 + outer loop + vertex 1.49867 2.01804 2.50174 + vertex 1.5021 2.0202 2.50194 + vertex 1.49596 2.02164 2.50237 + endloop + endfacet + facet normal 0.068797 -0.120757 0.990295 + outer loop + vertex 1.49867 2.01804 2.50174 + vertex 1.49596 2.02164 2.50237 + vertex 1.49366 2.0183 2.50212 + endloop + endfacet + facet normal 0.149142 -0.174788 0.973245 + outer loop + vertex 1.49366 2.0183 2.50212 + vertex 1.49596 2.02164 2.50237 + vertex 1.49138 2.02073 2.50291 + endloop + endfacet + facet normal 0.0298919 -0.281759 0.959019 + outer loop + vertex 1.49366 2.0183 2.50212 + vertex 1.49138 2.02073 2.50291 + vertex 1.48903 2.01845 2.50231 + endloop + endfacet + facet normal -0.0265065 -0.227558 0.973404 + outer loop + vertex 1.48903 2.01845 2.50231 + vertex 1.49138 2.02073 2.50291 + vertex 1.48747 2.0217 2.50303 + endloop + endfacet + facet normal 0.0657222 0.144258 0.987355 + outer loop + vertex 1.49138 2.02073 2.50291 + vertex 1.49118 2.02458 2.50236 + vertex 1.48747 2.0217 2.50303 + endloop + endfacet + facet normal 0.0750816 0.132444 0.988343 + outer loop + vertex 1.48747 2.0217 2.50303 + vertex 1.49118 2.02458 2.50236 + vertex 1.48608 2.0257 2.5026 + endloop + endfacet + facet normal 0.0561807 0.126133 0.990421 + outer loop + vertex 1.48747 2.0217 2.50303 + vertex 1.48608 2.0257 2.5026 + vertex 1.4836 2.02282 2.5031 + endloop + endfacet + facet normal 0.0531169 0.128747 0.990254 + outer loop + vertex 1.4836 2.02282 2.5031 + vertex 1.48608 2.0257 2.5026 + vertex 1.48108 2.0266 2.50275 + endloop + endfacet + facet normal -0.123909 0.0109147 0.992234 + outer loop + vertex 1.4836 2.02282 2.5031 + vertex 1.48108 2.0266 2.50275 + vertex 1.4797 2.02192 2.50263 + endloop + endfacet + facet normal 0.132007 -0.0640772 0.989176 + outer loop + vertex 1.4797 2.02192 2.50263 + vertex 1.48108 2.0266 2.50275 + vertex 1.47687 2.02551 2.50324 + endloop + endfacet + facet normal -0.00479317 -0.171477 0.985177 + outer loop + vertex 1.4797 2.02192 2.50263 + vertex 1.47687 2.02551 2.50324 + vertex 1.47432 2.02284 2.50276 + endloop + endfacet + facet normal 0.0170751 -0.191694 0.981306 + outer loop + vertex 1.47432 2.02284 2.50276 + vertex 1.47687 2.02551 2.50324 + vertex 1.47263 2.0268 2.50356 + endloop + endfacet + facet normal 0.163866 -0.128744 0.978045 + outer loop + vertex 1.47432 2.02284 2.50276 + vertex 1.47263 2.0268 2.50356 + vertex 1.46811 2.02373 2.50392 + endloop + endfacet + facet normal 0.10451 -0.0396982 0.993731 + outer loop + vertex 1.46811 2.02373 2.50392 + vertex 1.47263 2.0268 2.50356 + vertex 1.46849 2.02788 2.50404 + endloop + endfacet + facet normal 0.170334 0.228374 0.958557 + outer loop + vertex 1.47263 2.0268 2.50356 + vertex 1.47086 2.03152 2.50276 + vertex 1.46849 2.02788 2.50404 + endloop + endfacet + facet normal 0.145122 0.244805 0.95865 + outer loop + vertex 1.46849 2.02788 2.50404 + vertex 1.47086 2.03152 2.50276 + vertex 1.46638 2.03064 2.50366 + endloop + endfacet + facet normal 0.150082 0.248381 0.956965 + outer loop + vertex 1.46849 2.02788 2.50404 + vertex 1.46638 2.03064 2.50366 + vertex 1.46392 2.02717 2.50495 + endloop + endfacet + facet normal 0.20062 -0.0481253 0.978486 + outer loop + vertex 1.46392 2.02717 2.50495 + vertex 1.46811 2.02373 2.50392 + vertex 1.46849 2.02788 2.50404 + endloop + endfacet + facet normal 0.355192 0.156954 0.921523 + outer loop + vertex 1.46367 2.02372 2.50563 + vertex 1.46811 2.02373 2.50392 + vertex 1.46392 2.02717 2.50495 + endloop + endfacet + facet normal 0.198099 0.177065 0.964056 + outer loop + vertex 1.46007 2.02486 2.50616 + vertex 1.46367 2.02372 2.50563 + vertex 1.46392 2.02717 2.50495 + endloop + endfacet + facet normal 0.134859 0.276015 0.951645 + outer loop + vertex 1.45809 2.02875 2.50531 + vertex 1.46007 2.02486 2.50616 + vertex 1.46392 2.02717 2.50495 + endloop + endfacet + facet normal 0.140652 0.29922 0.943761 + outer loop + vertex 1.46392 2.02717 2.50495 + vertex 1.46213 2.03179 2.50375 + vertex 1.45809 2.02875 2.50531 + endloop + endfacet + facet normal 0.10152 0.34572 0.93283 + outer loop + vertex 1.45809 2.02875 2.50531 + vertex 1.46213 2.03179 2.50375 + vertex 1.45789 2.03287 2.50381 + endloop + endfacet + facet normal 0.105472 0.345747 0.932381 + outer loop + vertex 1.45348 2.03186 2.50468 + vertex 1.45809 2.02875 2.50531 + vertex 1.45789 2.03287 2.50381 + endloop + endfacet + facet normal 0.106011 0.343924 0.932994 + outer loop + vertex 1.45789 2.03287 2.50381 + vertex 1.45585 2.03545 2.50309 + vertex 1.45348 2.03186 2.50468 + endloop + endfacet + facet normal 0.113385 0.33941 0.93378 + outer loop + vertex 1.45348 2.03186 2.50468 + vertex 1.45585 2.03545 2.50309 + vertex 1.45177 2.03631 2.50327 + endloop + endfacet + facet normal 0.110645 0.338563 0.934416 + outer loop + vertex 1.45348 2.03186 2.50468 + vertex 1.45177 2.03631 2.50327 + vertex 1.44821 2.03304 2.50488 + endloop + endfacet + facet normal 0.103698 0.305698 0.946465 + outer loop + vertex 1.44821 2.03304 2.50488 + vertex 1.45011 2.02894 2.50599 + vertex 1.45348 2.03186 2.50468 + endloop + endfacet + facet normal 0.0963817 0.302757 0.948182 + outer loop + vertex 1.44533 2.03002 2.50613 + vertex 1.45011 2.02894 2.50599 + vertex 1.44821 2.03304 2.50488 + endloop + endfacet + facet normal 0.116639 0.284785 0.951469 + outer loop + vertex 1.44293 2.03416 2.50519 + vertex 1.44533 2.03002 2.50613 + vertex 1.44821 2.03304 2.50488 + endloop + endfacet + facet normal 0.126548 0.336847 0.933017 + outer loop + vertex 1.44821 2.03304 2.50488 + vertex 1.44691 2.03729 2.50352 + vertex 1.44293 2.03416 2.50519 + endloop + endfacet + facet normal 0.116377 0.348234 0.930156 + outer loop + vertex 1.44293 2.03416 2.50519 + vertex 1.44691 2.03729 2.50352 + vertex 1.4429 2.03808 2.50372 + endloop + endfacet + facet normal 0.123657 0.34797 0.929315 + outer loop + vertex 1.43855 2.03698 2.50472 + vertex 1.44293 2.03416 2.50519 + vertex 1.4429 2.03808 2.50372 + endloop + endfacet + facet normal 0.12678 0.33842 0.932416 + outer loop + vertex 1.4429 2.03808 2.50372 + vertex 1.44102 2.04048 2.50311 + vertex 1.43855 2.03698 2.50472 + endloop + endfacet + facet normal 0.120369 0.342631 0.931727 + outer loop + vertex 1.43855 2.03698 2.50472 + vertex 1.44102 2.04048 2.50311 + vertex 1.43701 2.04131 2.50332 + endloop + endfacet + facet normal 0.114061 0.340852 0.933172 + outer loop + vertex 1.43855 2.03698 2.50472 + vertex 1.43701 2.04131 2.50332 + vertex 1.43325 2.03806 2.50497 + endloop + endfacet + facet normal 0.114614 0.34386 0.932 + outer loop + vertex 1.43325 2.03806 2.50497 + vertex 1.43471 2.03395 2.50631 + vertex 1.43855 2.03698 2.50472 + endloop + endfacet + facet normal 0.107921 0.351296 0.930024 + outer loop + vertex 1.43471 2.03395 2.50631 + vertex 1.43873 2.03316 2.50614 + vertex 1.43855 2.03698 2.50472 + endloop + endfacet + facet normal 0.0826591 0.214093 0.97331 + outer loop + vertex 1.43873 2.03316 2.50614 + vertex 1.43471 2.03395 2.50631 + vertex 1.43712 2.03019 2.50693 + endloop + endfacet + facet normal 0.0706079 0.220503 0.972827 + outer loop + vertex 1.44114 2.03095 2.50647 + vertex 1.43873 2.03316 2.50614 + vertex 1.43712 2.03019 2.50693 + endloop + endfacet + facet normal 0.116781 -0.0116226 0.99309 + outer loop + vertex 1.44114 2.03095 2.50647 + vertex 1.43712 2.03019 2.50693 + vertex 1.44233 2.02772 2.50629 + endloop + endfacet + facet normal 0.0728463 -0.0280609 0.996948 + outer loop + vertex 1.44114 2.03095 2.50647 + vertex 1.44233 2.02772 2.50629 + vertex 1.44533 2.03002 2.50613 + endloop + endfacet + facet normal 0.0268047 0.0321503 0.999124 + outer loop + vertex 1.44845 2.02605 2.50618 + vertex 1.44533 2.03002 2.50613 + vertex 1.44233 2.02772 2.50629 + endloop + endfacet + facet normal 0.0235161 -0.204865 0.978508 + outer loop + vertex 1.43712 2.03019 2.50693 + vertex 1.43793 2.0274 2.50633 + vertex 1.44233 2.02772 2.50629 + endloop + endfacet + facet normal 0.043937 -0.199062 0.979001 + outer loop + vertex 1.43793 2.0274 2.50633 + vertex 1.43712 2.03019 2.50693 + vertex 1.43369 2.02802 2.50664 + endloop + endfacet + facet normal 0.0196206 -0.161565 0.986667 + outer loop + vertex 1.43369 2.02802 2.50664 + vertex 1.43712 2.03019 2.50693 + vertex 1.43163 2.03107 2.50718 + endloop + endfacet + facet normal 0.0014856 -0.173555 0.984823 + outer loop + vertex 1.43369 2.02802 2.50664 + vertex 1.43163 2.03107 2.50718 + vertex 1.42873 2.02854 2.50674 + endloop + endfacet + facet normal 0.00290419 -0.175132 0.984541 + outer loop + vertex 1.42873 2.02854 2.50674 + vertex 1.43163 2.03107 2.50718 + vertex 1.42619 2.03199 2.50736 + endloop + endfacet + facet normal -0.0138613 -0.18708 0.982247 + outer loop + vertex 1.42873 2.02854 2.50674 + vertex 1.42619 2.03199 2.50736 + vertex 1.42384 2.02908 2.50678 + endloop + endfacet + facet normal 0.0675632 0.2091 0.975557 + outer loop + vertex 1.43163 2.03107 2.50718 + vertex 1.42975 2.03487 2.5065 + vertex 1.42619 2.03199 2.50736 + endloop + endfacet + facet normal 0.0787911 0.195793 0.977475 + outer loop + vertex 1.42568 2.03565 2.50667 + vertex 1.42619 2.03199 2.50736 + vertex 1.42975 2.03487 2.5065 + endloop + endfacet + facet normal 0.103157 0.331474 0.937808 + outer loop + vertex 1.42975 2.03487 2.5065 + vertex 1.4279 2.03914 2.50519 + vertex 1.42568 2.03565 2.50667 + endloop + endfacet + facet normal 0.108326 0.328398 0.938307 + outer loop + vertex 1.42359 2.03805 2.50607 + vertex 1.42568 2.03565 2.50667 + vertex 1.4279 2.03914 2.50519 + endloop + endfacet + facet normal 0.103983 0.342019 0.933922 + outer loop + vertex 1.42359 2.03805 2.50607 + vertex 1.4279 2.03914 2.50519 + vertex 1.4236 2.04205 2.5046 + endloop + endfacet + facet normal 0.0973166 0.342276 0.934546 + outer loop + vertex 1.41969 2.03891 2.50616 + vertex 1.42359 2.03805 2.50607 + vertex 1.4236 2.04205 2.5046 + endloop + endfacet + facet normal 0.104564 0.334296 0.93665 + outer loop + vertex 1.41831 2.04313 2.50481 + vertex 1.41969 2.03891 2.50616 + vertex 1.4236 2.04205 2.5046 + endloop + endfacet + facet normal 0.103774 0.330129 0.938214 + outer loop + vertex 1.4236 2.04205 2.5046 + vertex 1.42207 2.04631 2.50327 + vertex 1.41831 2.04313 2.50481 + endloop + endfacet + facet normal 0.0990098 0.335154 0.936946 + outer loop + vertex 1.41831 2.04313 2.50481 + vertex 1.42207 2.04631 2.50327 + vertex 1.41723 2.04724 2.50345 + endloop + endfacet + facet normal 0.106387 0.336647 0.935602 + outer loop + vertex 1.41831 2.04313 2.50481 + vertex 1.41723 2.04724 2.50345 + vertex 1.41297 2.04425 2.50501 + endloop + endfacet + facet normal 0.106344 0.336428 0.935685 + outer loop + vertex 1.41297 2.04425 2.50501 + vertex 1.41486 2.03994 2.50635 + vertex 1.41831 2.04313 2.50481 + endloop + endfacet + facet normal 0.121552 0.341889 0.931846 + outer loop + vertex 1.41486 2.03994 2.50635 + vertex 1.41297 2.04425 2.50501 + vertex 1.41076 2.04077 2.50658 + endloop + endfacet + facet normal 0.102076 0.235848 0.966414 + outer loop + vertex 1.41076 2.04077 2.50658 + vertex 1.41127 2.03677 2.5075 + vertex 1.41486 2.03994 2.50635 + endloop + endfacet + facet normal 0.0995368 0.238578 0.966009 + outer loop + vertex 1.41681 2.03569 2.5072 + vertex 1.41486 2.03994 2.50635 + vertex 1.41127 2.03677 2.5075 + endloop + endfacet + facet normal 0.0343491 -0.104969 0.993882 + outer loop + vertex 1.41413 2.03273 2.50698 + vertex 1.41681 2.03569 2.5072 + vertex 1.41127 2.03677 2.5075 + endloop + endfacet + facet normal 0.0704189 -0.0794941 0.994345 + outer loop + vertex 1.41413 2.03273 2.50698 + vertex 1.41127 2.03677 2.5075 + vertex 1.40905 2.03314 2.50737 + endloop + endfacet + facet normal 0.164702 -0.136556 0.976845 + outer loop + vertex 1.40905 2.03314 2.50737 + vertex 1.41127 2.03677 2.5075 + vertex 1.40678 2.03571 2.50811 + endloop + endfacet + facet normal 0.0570642 -0.229902 0.971539 + outer loop + vertex 1.40905 2.03314 2.50737 + vertex 1.40678 2.03571 2.50811 + vertex 1.40421 2.03314 2.50765 + endloop + endfacet + facet normal 0.00884431 -0.183548 0.982971 + outer loop + vertex 1.40421 2.03314 2.50765 + vertex 1.40678 2.03571 2.50811 + vertex 1.40261 2.0364 2.50828 + endloop + endfacet + facet normal -0.0068817 -0.190975 0.981571 + outer loop + vertex 1.40421 2.03314 2.50765 + vertex 1.40261 2.0364 2.50828 + vertex 1.39931 2.03342 2.50767 + endloop + endfacet + facet normal -0.0195451 -0.177437 0.983938 + outer loop + vertex 1.39931 2.03342 2.50767 + vertex 1.40261 2.0364 2.50828 + vertex 1.39772 2.03708 2.5083 + endloop + endfacet + facet normal -0.0462102 -0.188516 0.980982 + outer loop + vertex 1.39931 2.03342 2.50767 + vertex 1.39772 2.03708 2.5083 + vertex 1.39418 2.03404 2.50755 + endloop + endfacet + facet normal -0.0174541 -0.220587 0.975211 + outer loop + vertex 1.39418 2.03404 2.50755 + vertex 1.39772 2.03708 2.5083 + vertex 1.39367 2.03778 2.50839 + endloop + endfacet + facet normal -0.0445663 -0.223938 0.973584 + outer loop + vertex 1.39418 2.03404 2.50755 + vertex 1.39367 2.03778 2.50839 + vertex 1.3895 2.03675 2.50796 + endloop + endfacet + facet normal -0.0952953 -0.0274454 0.995071 + outer loop + vertex 1.39367 2.03778 2.50839 + vertex 1.39149 2.04036 2.50825 + vertex 1.3895 2.03675 2.50796 + endloop + endfacet + facet normal -0.00121036 -0.0795001 0.996834 + outer loop + vertex 1.3895 2.03675 2.50796 + vertex 1.39149 2.04036 2.50825 + vertex 1.38747 2.04131 2.50832 + endloop + endfacet + facet normal 0.101465 -0.0335427 0.994273 + outer loop + vertex 1.3895 2.03675 2.50796 + vertex 1.38747 2.04131 2.50832 + vertex 1.38316 2.03802 2.50865 + endloop + endfacet + facet normal 0.0672819 0.0116034 0.997667 + outer loop + vertex 1.38316 2.03802 2.50865 + vertex 1.38747 2.04131 2.50832 + vertex 1.38329 2.04247 2.50859 + endloop + endfacet + facet normal 0.173391 0.00815719 0.984819 + outer loop + vertex 1.37841 2.04121 2.50946 + vertex 1.38316 2.03802 2.50865 + vertex 1.38329 2.04247 2.50859 + endloop + endfacet + facet normal 0.0977862 0.280041 0.954995 + outer loop + vertex 1.38329 2.04247 2.50859 + vertex 1.38133 2.04606 2.50774 + vertex 1.37841 2.04121 2.50946 + endloop + endfacet + facet normal 0.0501409 0.307138 0.950343 + outer loop + vertex 1.37841 2.04121 2.50946 + vertex 1.38133 2.04606 2.50774 + vertex 1.37586 2.0466 2.50785 + endloop + endfacet + facet normal 0.0536734 0.345602 0.936845 + outer loop + vertex 1.38133 2.04606 2.50774 + vertex 1.37977 2.05026 2.50628 + vertex 1.37586 2.0466 2.50785 + endloop + endfacet + facet normal 0.0398552 0.358591 0.932644 + outer loop + vertex 1.37568 2.05083 2.50623 + vertex 1.37586 2.0466 2.50785 + vertex 1.37977 2.05026 2.50628 + endloop + endfacet + facet normal 0.0373856 0.341349 0.939193 + outer loop + vertex 1.37977 2.05026 2.50628 + vertex 1.37802 2.05433 2.50487 + vertex 1.37568 2.05083 2.50623 + endloop + endfacet + facet normal 0.0343891 0.343146 0.938652 + outer loop + vertex 1.37358 2.05311 2.50548 + vertex 1.37568 2.05083 2.50623 + vertex 1.37802 2.05433 2.50487 + endloop + endfacet + facet normal 0.0414135 0.321237 0.946093 + outer loop + vertex 1.37358 2.05311 2.50548 + vertex 1.37802 2.05433 2.50487 + vertex 1.37352 2.05705 2.50414 + endloop + endfacet + facet normal 0.0502652 0.321244 0.945662 + outer loop + vertex 1.36948 2.05361 2.50552 + vertex 1.37358 2.05311 2.50548 + vertex 1.37352 2.05705 2.50414 + endloop + endfacet + facet normal 0.0541478 0.317158 0.946826 + outer loop + vertex 1.36803 2.0575 2.50431 + vertex 1.36948 2.05361 2.50552 + vertex 1.37352 2.05705 2.50414 + endloop + endfacet + facet normal 0.0538733 0.313324 0.948117 + outer loop + vertex 1.37352 2.05705 2.50414 + vertex 1.37094 2.06161 2.50278 + vertex 1.36803 2.0575 2.50431 + endloop + endfacet + facet normal 0.0630961 0.307329 0.949509 + outer loop + vertex 1.36803 2.0575 2.50431 + vertex 1.37094 2.06161 2.50278 + vertex 1.36623 2.06062 2.50341 + endloop + endfacet + facet normal 0.0735665 0.312627 0.947023 + outer loop + vertex 1.36803 2.0575 2.50431 + vertex 1.36623 2.06062 2.50341 + vertex 1.36327 2.05781 2.50457 + endloop + endfacet + facet normal 0.0735029 0.311287 0.947469 + outer loop + vertex 1.36327 2.05781 2.50457 + vertex 1.36458 2.05405 2.50571 + vertex 1.36803 2.0575 2.50431 + endloop + endfacet + facet normal 0.0815673 0.313677 0.94602 + outer loop + vertex 1.35976 2.05446 2.50598 + vertex 1.36458 2.05405 2.50571 + vertex 1.36327 2.05781 2.50457 + endloop + endfacet + facet normal 0.0800814 0.291535 0.953202 + outer loop + vertex 1.36458 2.05405 2.50571 + vertex 1.35976 2.05446 2.50598 + vertex 1.36101 2.05038 2.50713 + endloop + endfacet + facet normal 0.0521941 0.316381 0.947195 + outer loop + vertex 1.3659 2.05 2.50698 + vertex 1.36458 2.05405 2.50571 + vertex 1.36101 2.05038 2.50713 + endloop + endfacet + facet normal 0.0497265 0.280047 0.958698 + outer loop + vertex 1.36226 2.04618 2.50829 + vertex 1.3659 2.05 2.50698 + vertex 1.36101 2.05038 2.50713 + endloop + endfacet + facet normal -0.00749932 0.264592 0.964331 + outer loop + vertex 1.36226 2.04618 2.50829 + vertex 1.36101 2.05038 2.50713 + vertex 1.35761 2.04645 2.50818 + endloop + endfacet + facet normal -0.0146304 0.155112 0.987789 + outer loop + vertex 1.35928 2.0429 2.50876 + vertex 1.36226 2.04618 2.50829 + vertex 1.35761 2.04645 2.50818 + endloop + endfacet + facet normal -0.178263 0.0774207 0.980932 + outer loop + vertex 1.35928 2.0429 2.50876 + vertex 1.35761 2.04645 2.50818 + vertex 1.35478 2.04199 2.50802 + endloop + endfacet + facet normal -0.10607 0.23532 0.966113 + outer loop + vertex 1.36338 2.04159 2.50953 + vertex 1.36226 2.04618 2.50829 + vertex 1.35928 2.0429 2.50876 + endloop + endfacet + facet normal -0.00759687 0.259342 0.965756 + outer loop + vertex 1.36338 2.04159 2.50953 + vertex 1.36706 2.0457 2.50846 + vertex 1.36226 2.04618 2.50829 + endloop + endfacet + facet normal -0.0559382 0.299171 0.952558 + outer loop + vertex 1.36886 2.04143 2.5099 + vertex 1.36706 2.0457 2.50846 + vertex 1.36338 2.04159 2.50953 + endloop + endfacet + facet normal -0.0546104 0.324977 0.944144 + outer loop + vertex 1.36338 2.04159 2.50953 + vertex 1.36562 2.03861 2.51069 + vertex 1.36886 2.04143 2.5099 + endloop + endfacet + facet normal 0.0211802 0.244765 0.969351 + outer loop + vertex 1.36562 2.03861 2.51069 + vertex 1.36863 2.03821 2.51072 + vertex 1.36886 2.04143 2.5099 + endloop + endfacet + facet normal 0.162961 0.231912 0.958989 + outer loop + vertex 1.36863 2.03821 2.51072 + vertex 1.37302 2.03854 2.50989 + vertex 1.36886 2.04143 2.5099 + endloop + endfacet + facet normal 0.085497 0.120024 0.989083 + outer loop + vertex 1.36886 2.04143 2.5099 + vertex 1.37302 2.03854 2.50989 + vertex 1.37347 2.0426 2.50936 + endloop + endfacet + facet normal 0.0319943 0.311579 0.949681 + outer loop + vertex 1.37347 2.0426 2.50936 + vertex 1.37126 2.04523 2.50857 + vertex 1.36886 2.04143 2.5099 + endloop + endfacet + facet normal 0.0514206 0.326219 0.943895 + outer loop + vertex 1.37347 2.0426 2.50936 + vertex 1.37586 2.0466 2.50785 + vertex 1.37126 2.04523 2.50857 + endloop + endfacet + facet normal 0.0397697 0.359265 0.932388 + outer loop + vertex 1.37124 2.04941 2.50696 + vertex 1.37126 2.04523 2.50857 + vertex 1.37586 2.0466 2.50785 + endloop + endfacet + facet normal 0.0138252 0.35941 0.933077 + outer loop + vertex 1.37126 2.04523 2.50857 + vertex 1.37124 2.04941 2.50696 + vertex 1.36706 2.0457 2.50846 + endloop + endfacet + facet normal 0.0402816 0.33324 0.941981 + outer loop + vertex 1.36706 2.0457 2.50846 + vertex 1.37124 2.04941 2.50696 + vertex 1.3659 2.05 2.50698 + endloop + endfacet + facet normal 0.0409794 0.339647 0.93966 + outer loop + vertex 1.37124 2.04941 2.50696 + vertex 1.36948 2.05361 2.50552 + vertex 1.3659 2.05 2.50698 + endloop + endfacet + facet normal 0.070684 0.31562 0.946249 + outer loop + vertex 1.37841 2.04121 2.50946 + vertex 1.37586 2.0466 2.50785 + vertex 1.37347 2.0426 2.50936 + endloop + endfacet + facet normal 0.0166089 0.12808 0.991625 + outer loop + vertex 1.37302 2.03854 2.50989 + vertex 1.37841 2.04121 2.50946 + vertex 1.37347 2.0426 2.50936 + endloop + endfacet + facet normal -0.0716562 0.300029 0.951235 + outer loop + vertex 1.37737 2.03792 2.51042 + vertex 1.37841 2.04121 2.50946 + vertex 1.37302 2.03854 2.50989 + endloop + endfacet + facet normal 0.0489689 0.265409 0.962892 + outer loop + vertex 1.37737 2.03792 2.51042 + vertex 1.37956 2.0379 2.51031 + vertex 1.37841 2.04121 2.50946 + endloop + endfacet + facet normal 0.197919 -0.44698 0.872374 + outer loop + vertex 1.36863 2.03821 2.51072 + vertex 1.36907 2.0367 2.50984 + vertex 1.37302 2.03854 2.50989 + endloop + endfacet + facet normal 0.236461 -0.43389 0.869382 + outer loop + vertex 1.36907 2.0367 2.50984 + vertex 1.36863 2.03821 2.51072 + vertex 1.36665 2.03691 2.51061 + endloop + endfacet + facet normal -0.0192537 -0.0574697 0.998162 + outer loop + vertex 1.36863 2.03821 2.51072 + vertex 1.36562 2.03861 2.51069 + vertex 1.36665 2.03691 2.51061 + endloop + endfacet + facet normal -0.150548 -0.136498 0.979134 + outer loop + vertex 1.36665 2.03691 2.51061 + vertex 1.36562 2.03861 2.51069 + vertex 1.36439 2.03685 2.51025 + endloop + endfacet + facet normal 0.00956281 0.324407 0.945869 + outer loop + vertex 1.36886 2.04143 2.5099 + vertex 1.37126 2.04523 2.50857 + vertex 1.36706 2.0457 2.50846 + endloop + endfacet + facet normal 0.0706088 0.200482 0.97715 + outer loop + vertex 1.35761 2.04645 2.50818 + vertex 1.36101 2.05038 2.50713 + vertex 1.35616 2.05081 2.50739 + endloop + endfacet + facet normal -0.000558565 0.323664 0.946172 + outer loop + vertex 1.36706 2.0457 2.50846 + vertex 1.3659 2.05 2.50698 + vertex 1.36226 2.04618 2.50829 + endloop + endfacet + facet normal 0.0635967 0.319547 0.945434 + outer loop + vertex 1.36948 2.05361 2.50552 + vertex 1.36458 2.05405 2.50571 + vertex 1.3659 2.05 2.50698 + endloop + endfacet + facet normal 0.0823122 0.304219 0.949039 + outer loop + vertex 1.36327 2.05781 2.50457 + vertex 1.36623 2.06062 2.50341 + vertex 1.36226 2.06158 2.50345 + endloop + endfacet + facet normal 0.0905399 0.306019 0.94771 + outer loop + vertex 1.36327 2.05781 2.50457 + vertex 1.36226 2.06158 2.50345 + vertex 1.35855 2.05843 2.50482 + endloop + endfacet + facet normal 0.0904479 0.305213 0.947979 + outer loop + vertex 1.35855 2.05843 2.50482 + vertex 1.35976 2.05446 2.50598 + vertex 1.36327 2.05781 2.50457 + endloop + endfacet + facet normal 0.097943 0.307105 0.946622 + outer loop + vertex 1.35499 2.05507 2.50628 + vertex 1.35976 2.05446 2.50598 + vertex 1.35855 2.05843 2.50482 + endloop + endfacet + facet normal 0.103275 0.301928 0.94772 + outer loop + vertex 1.3534 2.05932 2.5051 + vertex 1.35499 2.05507 2.50628 + vertex 1.35855 2.05843 2.50482 + endloop + endfacet + facet normal 0.103212 0.301523 0.947856 + outer loop + vertex 1.35855 2.05843 2.50482 + vertex 1.35752 2.06243 2.50366 + vertex 1.3534 2.05932 2.5051 + endloop + endfacet + facet normal 0.108439 0.295246 0.949248 + outer loop + vertex 1.3534 2.05932 2.5051 + vertex 1.35752 2.06243 2.50366 + vertex 1.35353 2.06322 2.50387 + endloop + endfacet + facet normal 0.123298 0.294286 0.947731 + outer loop + vertex 1.34907 2.0624 2.50471 + vertex 1.3534 2.05932 2.5051 + vertex 1.35353 2.06322 2.50387 + endloop + endfacet + facet normal 0.126016 0.282677 0.950902 + outer loop + vertex 1.35353 2.06322 2.50387 + vertex 1.35156 2.06571 2.50339 + vertex 1.34907 2.0624 2.50471 + endloop + endfacet + facet normal 0.134848 0.276311 0.951561 + outer loop + vertex 1.34907 2.0624 2.50471 + vertex 1.35156 2.06571 2.50339 + vertex 1.34748 2.06693 2.50362 + endloop + endfacet + facet normal 0.136951 0.276932 0.95108 + outer loop + vertex 1.34907 2.0624 2.50471 + vertex 1.34748 2.06693 2.50362 + vertex 1.34334 2.06429 2.50498 + endloop + endfacet + facet normal 0.136906 0.276789 0.951128 + outer loop + vertex 1.34334 2.06429 2.50498 + vertex 1.34501 2.0596 2.50611 + vertex 1.34907 2.0624 2.50471 + endloop + endfacet + facet normal 0.129006 0.287237 0.949133 + outer loop + vertex 1.34501 2.0596 2.50611 + vertex 1.34906 2.05837 2.50593 + vertex 1.34907 2.0624 2.50471 + endloop + endfacet + facet normal 0.133767 0.303692 0.943333 + outer loop + vertex 1.34906 2.05837 2.50593 + vertex 1.34501 2.0596 2.50611 + vertex 1.34674 2.05505 2.50733 + endloop + endfacet + facet normal 0.126436 0.308574 0.94276 + outer loop + vertex 1.35104 2.05584 2.50649 + vertex 1.34906 2.05837 2.50593 + vertex 1.34674 2.05505 2.50733 + endloop + endfacet + facet normal 0.131118 0.289145 0.948263 + outer loop + vertex 1.35104 2.05584 2.50649 + vertex 1.34674 2.05505 2.50733 + vertex 1.35099 2.05174 2.50775 + endloop + endfacet + facet normal 0.10705 0.290232 0.95095 + outer loop + vertex 1.35104 2.05584 2.50649 + vertex 1.35099 2.05174 2.50775 + vertex 1.35499 2.05507 2.50628 + endloop + endfacet + facet normal 0.109489 0.303874 0.9464 + outer loop + vertex 1.35499 2.05507 2.50628 + vertex 1.3534 2.05932 2.5051 + vertex 1.35104 2.05584 2.50649 + endloop + endfacet + facet normal 0.144396 0.305338 0.941232 + outer loop + vertex 1.34674 2.05505 2.50733 + vertex 1.3467 2.05094 2.50866 + vertex 1.35099 2.05174 2.50775 + endloop + endfacet + facet normal 0.147348 0.305181 0.940826 + outer loop + vertex 1.3467 2.05094 2.50866 + vertex 1.34674 2.05505 2.50733 + vertex 1.34336 2.05245 2.5087 + endloop + endfacet + facet normal 0.136543 0.31786 0.938254 + outer loop + vertex 1.34336 2.05245 2.5087 + vertex 1.34674 2.05505 2.50733 + vertex 1.34097 2.05671 2.5076 + endloop + endfacet + facet normal 0.146016 0.322407 0.935272 + outer loop + vertex 1.34336 2.05245 2.5087 + vertex 1.34097 2.05671 2.5076 + vertex 1.33866 2.05194 2.50961 + endloop + endfacet + facet normal 0.15258 0.282773 0.946974 + outer loop + vertex 1.33866 2.05194 2.50961 + vertex 1.34377 2.04785 2.51001 + vertex 1.34336 2.05245 2.5087 + endloop + endfacet + facet normal 0.137062 0.282132 0.949534 + outer loop + vertex 1.34377 2.04785 2.51001 + vertex 1.3467 2.05094 2.50866 + vertex 1.34336 2.05245 2.5087 + endloop + endfacet + facet normal 0.203996 0.220487 0.953819 + outer loop + vertex 1.34853 2.04803 2.50895 + vertex 1.3467 2.05094 2.50866 + vertex 1.34377 2.04785 2.51001 + endloop + endfacet + facet normal 0.169079 0.199708 0.965158 + outer loop + vertex 1.34853 2.04803 2.50895 + vertex 1.35099 2.05174 2.50775 + vertex 1.3467 2.05094 2.50866 + endloop + endfacet + facet normal 0.173991 0.196383 0.964967 + outer loop + vertex 1.35271 2.04692 2.50842 + vertex 1.35099 2.05174 2.50775 + vertex 1.34853 2.04803 2.50895 + endloop + endfacet + facet normal 0.0986459 0.171597 0.980216 + outer loop + vertex 1.35271 2.04692 2.50842 + vertex 1.35616 2.05081 2.50739 + vertex 1.35099 2.05174 2.50775 + endloop + endfacet + facet normal 0.0666326 0.199253 0.97768 + outer loop + vertex 1.35761 2.04645 2.50818 + vertex 1.35616 2.05081 2.50739 + vertex 1.35271 2.04692 2.50842 + endloop + endfacet + facet normal 0.206672 0.347207 0.914732 + outer loop + vertex 1.33912 2.04777 2.51108 + vertex 1.34377 2.04785 2.51001 + vertex 1.33866 2.05194 2.50961 + endloop + endfacet + facet normal 0.127011 0.343834 0.930401 + outer loop + vertex 1.33486 2.0492 2.51114 + vertex 1.33912 2.04777 2.51108 + vertex 1.33866 2.05194 2.50961 + endloop + endfacet + facet normal 0.13595 0.332944 0.933095 + outer loop + vertex 1.33275 2.05366 2.50985 + vertex 1.33486 2.0492 2.51114 + vertex 1.33866 2.05194 2.50961 + endloop + endfacet + facet normal 0.136747 0.335831 0.931943 + outer loop + vertex 1.33866 2.05194 2.50961 + vertex 1.3362 2.05618 2.50844 + vertex 1.33275 2.05366 2.50985 + endloop + endfacet + facet normal 0.144127 0.326872 0.934014 + outer loop + vertex 1.33275 2.05366 2.50985 + vertex 1.3362 2.05618 2.50844 + vertex 1.33288 2.05767 2.50843 + endloop + endfacet + facet normal 0.155112 0.326012 0.932554 + outer loop + vertex 1.32849 2.05714 2.50935 + vertex 1.33275 2.05366 2.50985 + vertex 1.33288 2.05767 2.50843 + endloop + endfacet + facet normal 0.160729 0.295747 0.941648 + outer loop + vertex 1.33288 2.05767 2.50843 + vertex 1.3312 2.06039 2.50786 + vertex 1.32849 2.05714 2.50935 + endloop + endfacet + facet normal 0.161997 0.294738 0.941746 + outer loop + vertex 1.32849 2.05714 2.50935 + vertex 1.3312 2.06039 2.50786 + vertex 1.32724 2.06168 2.50814 + endloop + endfacet + facet normal 0.16175 0.294686 0.941805 + outer loop + vertex 1.32849 2.05714 2.50935 + vertex 1.32724 2.06168 2.50814 + vertex 1.32298 2.05892 2.50974 + endloop + endfacet + facet normal 0.164058 0.302445 0.938942 + outer loop + vertex 1.32298 2.05892 2.50974 + vertex 1.32465 2.05427 2.51094 + vertex 1.32849 2.05714 2.50935 + endloop + endfacet + facet normal 0.153811 0.314886 0.936584 + outer loop + vertex 1.32465 2.05427 2.51094 + vertex 1.32849 2.05305 2.51072 + vertex 1.32849 2.05714 2.50935 + endloop + endfacet + facet normal 0.137042 0.258466 0.95625 + outer loop + vertex 1.32849 2.05305 2.51072 + vertex 1.32465 2.05427 2.51094 + vertex 1.32682 2.04977 2.51185 + endloop + endfacet + facet normal 0.0930331 0.280456 0.955348 + outer loop + vertex 1.33067 2.05043 2.51128 + vertex 1.32849 2.05305 2.51072 + vertex 1.32682 2.04977 2.51185 + endloop + endfacet + facet normal 0.144867 0.319577 0.936421 + outer loop + vertex 1.32849 2.05305 2.51072 + vertex 1.33067 2.05043 2.51128 + vertex 1.33275 2.05366 2.50985 + endloop + endfacet + facet normal 0.167006 0.303297 0.938147 + outer loop + vertex 1.32465 2.05427 2.51094 + vertex 1.32298 2.05892 2.50974 + vertex 1.32072 2.05548 2.51125 + endloop + endfacet + facet normal 0.141436 0.212609 0.966847 + outer loop + vertex 1.32072 2.05548 2.51125 + vertex 1.32131 2.05121 2.5121 + vertex 1.32465 2.05427 2.51094 + endloop + endfacet + facet normal 0.109193 0.246381 0.963002 + outer loop + vertex 1.32682 2.04977 2.51185 + vertex 1.32465 2.05427 2.51094 + vertex 1.32131 2.05121 2.5121 + endloop + endfacet + facet normal 0.0361519 -0.0388993 0.998589 + outer loop + vertex 1.32443 2.04649 2.51181 + vertex 1.32682 2.04977 2.51185 + vertex 1.32131 2.05121 2.5121 + endloop + endfacet + facet normal 0.00394644 -0.0602265 0.998177 + outer loop + vertex 1.32443 2.04649 2.51181 + vertex 1.32131 2.05121 2.5121 + vertex 1.31928 2.04744 2.51188 + endloop + endfacet + facet normal 0.166684 -0.146232 0.975106 + outer loop + vertex 1.31928 2.04744 2.51188 + vertex 1.32131 2.05121 2.5121 + vertex 1.31697 2.05055 2.51275 + endloop + endfacet + facet normal 0.0929935 -0.200948 0.975178 + outer loop + vertex 1.31928 2.04744 2.51188 + vertex 1.31697 2.05055 2.51275 + vertex 1.31437 2.04798 2.51246 + endloop + endfacet + facet normal 0.0676357 -0.176117 0.982043 + outer loop + vertex 1.31437 2.04798 2.51246 + vertex 1.31697 2.05055 2.51275 + vertex 1.31278 2.05172 2.51324 + endloop + endfacet + facet normal 0.194261 -0.120749 0.97349 + outer loop + vertex 1.31437 2.04798 2.51246 + vertex 1.31278 2.05172 2.51324 + vertex 1.30833 2.04853 2.51374 + endloop + endfacet + facet normal 0.131653 -0.0307376 0.990819 + outer loop + vertex 1.30833 2.04853 2.51374 + vertex 1.31278 2.05172 2.51324 + vertex 1.30867 2.05272 2.51382 + endloop + endfacet + facet normal 0.228486 -0.0381337 0.9728 + outer loop + vertex 1.30418 2.05204 2.51485 + vertex 1.30833 2.04853 2.51374 + vertex 1.30867 2.05272 2.51382 + endloop + endfacet + facet normal 0.180992 0.244233 0.952676 + outer loop + vertex 1.30867 2.05272 2.51382 + vertex 1.30657 2.05548 2.51351 + vertex 1.30418 2.05204 2.51485 + endloop + endfacet + facet normal 0.136283 0.274942 0.951753 + outer loop + vertex 1.30418 2.05204 2.51485 + vertex 1.30657 2.05548 2.51351 + vertex 1.30246 2.05671 2.51375 + endloop + endfacet + facet normal 0.178696 0.287995 0.940812 + outer loop + vertex 1.30418 2.05204 2.51485 + vertex 1.30246 2.05671 2.51375 + vertex 1.2985 2.05385 2.51537 + endloop + endfacet + facet normal 0.168888 0.253799 0.952398 + outer loop + vertex 1.2985 2.05385 2.51537 + vertex 1.30037 2.04984 2.51611 + vertex 1.30418 2.05204 2.51485 + endloop + endfacet + facet normal 0.223346 0.164372 0.96078 + outer loop + vertex 1.30037 2.04984 2.51611 + vertex 1.30391 2.04855 2.51551 + vertex 1.30418 2.05204 2.51485 + endloop + endfacet + facet normal 0.141048 -0.0756799 0.987106 + outer loop + vertex 1.30391 2.04855 2.51551 + vertex 1.30037 2.04984 2.51611 + vertex 1.30148 2.04739 2.51577 + endloop + endfacet + facet normal 0.284187 -0.398682 0.871946 + outer loop + vertex 1.30423 2.04669 2.51455 + vertex 1.30391 2.04855 2.51551 + vertex 1.30148 2.04739 2.51577 + endloop + endfacet + facet normal 0.341998 -0.381912 0.858592 + outer loop + vertex 1.30391 2.04855 2.51551 + vertex 1.30423 2.04669 2.51455 + vertex 1.30833 2.04853 2.51374 + endloop + endfacet + facet normal 0.046271 -0.119339 0.991775 + outer loop + vertex 1.30148 2.04739 2.51577 + vertex 1.30037 2.04984 2.51611 + vertex 1.29729 2.04815 2.51605 + endloop + endfacet + facet normal 0.0503033 -0.126677 0.990668 + outer loop + vertex 1.29661 2.05096 2.51645 + vertex 1.29729 2.04815 2.51605 + vertex 1.30037 2.04984 2.51611 + endloop + endfacet + facet normal 0.0524368 -0.126153 0.990624 + outer loop + vertex 1.29661 2.05096 2.51645 + vertex 1.29312 2.05097 2.51663 + vertex 1.29729 2.04815 2.51605 + endloop + endfacet + facet normal 0.0536279 0.156655 0.986196 + outer loop + vertex 1.29661 2.05096 2.51645 + vertex 1.29434 2.05335 2.51619 + vertex 1.29312 2.05097 2.51663 + endloop + endfacet + facet normal 0.0720622 0.147211 0.986477 + outer loop + vertex 1.29434 2.05335 2.51619 + vertex 1.29051 2.05466 2.51627 + vertex 1.29312 2.05097 2.51663 + endloop + endfacet + facet normal -0.00698255 0.0923168 0.995705 + outer loop + vertex 1.29312 2.05097 2.51663 + vertex 1.29051 2.05466 2.51627 + vertex 1.28799 2.05173 2.51653 + endloop + endfacet + facet normal 0.0761269 0.0209877 0.996877 + outer loop + vertex 1.28647 2.05603 2.51655 + vertex 1.28799 2.05173 2.51653 + vertex 1.29051 2.05466 2.51627 + endloop + endfacet + facet normal 0.156548 0.26793 0.950635 + outer loop + vertex 1.29051 2.05466 2.51627 + vertex 1.28837 2.05936 2.5153 + vertex 1.28647 2.05603 2.51655 + endloop + endfacet + facet normal 0.187228 0.250193 0.949921 + outer loop + vertex 1.2842 2.05892 2.51624 + vertex 1.28647 2.05603 2.51655 + vertex 1.28837 2.05936 2.5153 + endloop + endfacet + facet normal 0.179155 0.298998 0.937285 + outer loop + vertex 1.2842 2.05892 2.51624 + vertex 1.28837 2.05936 2.5153 + vertex 1.28368 2.06328 2.51495 + endloop + endfacet + facet normal 0.184367 0.299286 0.936182 + outer loop + vertex 1.2842 2.05892 2.51624 + vertex 1.28368 2.06328 2.51495 + vertex 1.28108 2.06015 2.51646 + endloop + endfacet + facet normal 0.141989 0.185041 0.972419 + outer loop + vertex 1.28108 2.06015 2.51646 + vertex 1.28207 2.05576 2.51715 + vertex 1.2842 2.05892 2.51624 + endloop + endfacet + facet normal 0.167175 0.189952 0.967456 + outer loop + vertex 1.28108 2.06015 2.51646 + vertex 1.2769 2.05963 2.51729 + vertex 1.28207 2.05576 2.51715 + endloop + endfacet + facet normal 0.146969 0.162753 0.97566 + outer loop + vertex 1.2769 2.05963 2.51729 + vertex 1.27729 2.05553 2.51791 + vertex 1.28207 2.05576 2.51715 + endloop + endfacet + facet normal 0.162481 -0.201709 0.965875 + outer loop + vertex 1.2794 2.05265 2.51695 + vertex 1.28207 2.05576 2.51715 + vertex 1.27729 2.05553 2.51791 + endloop + endfacet + facet normal 0.104429 -0.243815 0.964183 + outer loop + vertex 1.2794 2.05265 2.51695 + vertex 1.27729 2.05553 2.51791 + vertex 1.27456 2.05318 2.51761 + endloop + endfacet + facet normal 0.0466575 -0.179108 0.982723 + outer loop + vertex 1.27456 2.05318 2.51761 + vertex 1.27729 2.05553 2.51791 + vertex 1.27295 2.05689 2.51837 + endloop + endfacet + facet normal 0.174829 -0.122439 0.976956 + outer loop + vertex 1.27456 2.05318 2.51761 + vertex 1.27295 2.05689 2.51837 + vertex 1.26844 2.05394 2.5188 + endloop + endfacet + facet normal 0.115289 -0.0290031 0.992908 + outer loop + vertex 1.26844 2.05394 2.5188 + vertex 1.27295 2.05689 2.51837 + vertex 1.26871 2.05816 2.51889 + endloop + endfacet + facet normal 0.21831 -0.0351044 0.975248 + outer loop + vertex 1.26395 2.05793 2.51995 + vertex 1.26844 2.05394 2.5188 + vertex 1.26871 2.05816 2.51889 + endloop + endfacet + facet normal 0.19854 0.251635 0.947239 + outer loop + vertex 1.26871 2.05816 2.51889 + vertex 1.26667 2.06107 2.51855 + vertex 1.26395 2.05793 2.51995 + endloop + endfacet + facet normal 0.152646 0.290225 0.944706 + outer loop + vertex 1.26395 2.05793 2.51995 + vertex 1.26667 2.06107 2.51855 + vertex 1.26342 2.06232 2.51869 + endloop + endfacet + facet normal 0.181096 0.292084 0.939091 + outer loop + vertex 1.25905 2.06192 2.51965 + vertex 1.26395 2.05793 2.51995 + vertex 1.26342 2.06232 2.51869 + endloop + endfacet + facet normal 0.169817 0.232729 0.957601 + outer loop + vertex 1.26871 2.05816 2.51889 + vertex 1.27104 2.06166 2.51763 + vertex 1.26667 2.06107 2.51855 + endloop + endfacet + facet normal 0.398635 0.190258 0.897158 + outer loop + vertex 1.26414 2.0542 2.52066 + vertex 1.26844 2.05394 2.5188 + vertex 1.26395 2.05793 2.51995 + endloop + endfacet + facet normal 0.317487 0.192233 0.928574 + outer loop + vertex 1.26414 2.0542 2.52066 + vertex 1.26395 2.05793 2.51995 + vertex 1.26136 2.05541 2.52136 + endloop + endfacet + facet normal 0.208973 -0.0842439 0.974286 + outer loop + vertex 1.26136 2.05541 2.52136 + vertex 1.26137 2.05306 2.52116 + vertex 1.26414 2.0542 2.52066 + endloop + endfacet + facet normal 0.312561 -0.381138 0.87008 + outer loop + vertex 1.26442 2.05216 2.51966 + vertex 1.26414 2.0542 2.52066 + vertex 1.26137 2.05306 2.52116 + endloop + endfacet + facet normal 0.137992 -0.0855819 0.986729 + outer loop + vertex 1.26136 2.05541 2.52136 + vertex 1.25744 2.0552 2.52189 + vertex 1.26137 2.05306 2.52116 + endloop + endfacet + facet normal 0.120059 0.209151 0.970485 + outer loop + vertex 1.26136 2.05541 2.52136 + vertex 1.25938 2.05782 2.52109 + vertex 1.25744 2.0552 2.52189 + endloop + endfacet + facet normal 0.223602 0.289791 0.930604 + outer loop + vertex 1.25938 2.05782 2.52109 + vertex 1.26136 2.05541 2.52136 + vertex 1.26395 2.05793 2.51995 + endloop + endfacet + facet normal 0.218803 0.336643 0.915859 + outer loop + vertex 1.25938 2.05782 2.52109 + vertex 1.26395 2.05793 2.51995 + vertex 1.25905 2.06192 2.51965 + endloop + endfacet + facet normal 0.163416 0.336342 0.927453 + outer loop + vertex 1.25518 2.05937 2.52126 + vertex 1.25938 2.05782 2.52109 + vertex 1.25905 2.06192 2.51965 + endloop + endfacet + facet normal 0.171862 0.325082 0.929938 + outer loop + vertex 1.25321 2.06418 2.51994 + vertex 1.25518 2.05937 2.52126 + vertex 1.25905 2.06192 2.51965 + endloop + endfacet + facet normal 0.167488 0.313138 0.934822 + outer loop + vertex 1.25905 2.06192 2.51965 + vertex 1.25734 2.06685 2.51831 + vertex 1.25321 2.06418 2.51994 + endloop + endfacet + facet normal 0.174487 0.303471 0.936728 + outer loop + vertex 1.25321 2.06418 2.51994 + vertex 1.25734 2.06685 2.51831 + vertex 1.25329 2.06841 2.51856 + endloop + endfacet + facet normal 0.17185 0.30366 0.937154 + outer loop + vertex 1.24857 2.06812 2.51952 + vertex 1.25321 2.06418 2.51994 + vertex 1.25329 2.06841 2.51856 + endloop + endfacet + facet normal 0.176079 0.267708 0.947274 + outer loop + vertex 1.25329 2.06841 2.51856 + vertex 1.25162 2.07118 2.51809 + vertex 1.24857 2.06812 2.51952 + endloop + endfacet + facet normal 0.167318 0.262911 0.950201 + outer loop + vertex 1.25329 2.06841 2.51856 + vertex 1.25594 2.0716 2.51721 + vertex 1.25162 2.07118 2.51809 + endloop + endfacet + facet normal 0.169781 0.246107 0.954257 + outer loop + vertex 1.25185 2.0751 2.51704 + vertex 1.25162 2.07118 2.51809 + vertex 1.25594 2.0716 2.51721 + endloop + endfacet + facet normal 0.169976 0.24633 0.954164 + outer loop + vertex 1.25607 2.07565 2.51614 + vertex 1.25185 2.0751 2.51704 + vertex 1.25594 2.0716 2.51721 + endloop + endfacet + facet normal 0.173587 0.24606 0.953584 + outer loop + vertex 1.25607 2.07565 2.51614 + vertex 1.25594 2.0716 2.51721 + vertex 1.25994 2.0743 2.51579 + endloop + endfacet + facet normal 0.176039 0.253751 0.951115 + outer loop + vertex 1.25994 2.0743 2.51579 + vertex 1.25835 2.07883 2.51487 + vertex 1.25607 2.07565 2.51614 + endloop + endfacet + facet normal 0.175653 0.254027 0.951113 + outer loop + vertex 1.25417 2.07831 2.51578 + vertex 1.25607 2.07565 2.51614 + vertex 1.25835 2.07883 2.51487 + endloop + endfacet + facet normal 0.173294 0.267402 0.947874 + outer loop + vertex 1.25417 2.07831 2.51578 + vertex 1.25835 2.07883 2.51487 + vertex 1.25418 2.08233 2.51465 + endloop + endfacet + facet normal 0.171334 0.267503 0.948202 + outer loop + vertex 1.25023 2.07964 2.51612 + vertex 1.25417 2.07831 2.51578 + vertex 1.25418 2.08233 2.51465 + endloop + endfacet + facet normal 0.170264 0.268953 0.947984 + outer loop + vertex 1.24858 2.08435 2.51508 + vertex 1.25023 2.07964 2.51612 + vertex 1.25418 2.08233 2.51465 + endloop + endfacet + facet normal 0.173753 0.279371 0.944331 + outer loop + vertex 1.25418 2.08233 2.51465 + vertex 1.25263 2.08697 2.51356 + vertex 1.24858 2.08435 2.51508 + endloop + endfacet + facet normal 0.173315 0.279988 0.944229 + outer loop + vertex 1.24858 2.08435 2.51508 + vertex 1.25263 2.08697 2.51356 + vertex 1.24856 2.08849 2.51385 + endloop + endfacet + facet normal 0.175547 0.279888 0.943846 + outer loop + vertex 1.2439 2.08821 2.51481 + vertex 1.24858 2.08435 2.51508 + vertex 1.24856 2.08849 2.51385 + endloop + endfacet + facet normal 0.175268 0.28227 0.943189 + outer loop + vertex 1.24856 2.08849 2.51385 + vertex 1.24665 2.09129 2.51337 + vertex 1.2439 2.08821 2.51481 + endloop + endfacet + facet normal 0.177203 0.280606 0.943324 + outer loop + vertex 1.2439 2.08821 2.51481 + vertex 1.24665 2.09129 2.51337 + vertex 1.24353 2.0925 2.5136 + endloop + endfacet + facet normal 0.178415 0.280643 0.943084 + outer loop + vertex 1.23922 2.0921 2.51453 + vertex 1.2439 2.08821 2.51481 + vertex 1.24353 2.0925 2.5136 + endloop + endfacet + facet normal 0.178746 0.278443 0.943673 + outer loop + vertex 1.24353 2.0925 2.5136 + vertex 1.24164 2.09531 2.51313 + vertex 1.23922 2.0921 2.51453 + endloop + endfacet + facet normal 0.181839 0.27615 0.943756 + outer loop + vertex 1.23922 2.0921 2.51453 + vertex 1.24164 2.09531 2.51313 + vertex 1.23757 2.09689 2.51345 + endloop + endfacet + facet normal 0.178558 0.275224 0.944653 + outer loop + vertex 1.23922 2.0921 2.51453 + vertex 1.23757 2.09689 2.51345 + vertex 1.2335 2.0943 2.51497 + endloop + endfacet + facet normal 0.178077 0.273881 0.945134 + outer loop + vertex 1.2335 2.0943 2.51497 + vertex 1.23519 2.08949 2.51605 + vertex 1.23922 2.0921 2.51453 + endloop + endfacet + facet normal 0.175905 0.276957 0.944644 + outer loop + vertex 1.23519 2.08949 2.51605 + vertex 1.23926 2.08795 2.51574 + vertex 1.23922 2.0921 2.51453 + endloop + endfacet + facet normal 0.174276 0.272319 0.946293 + outer loop + vertex 1.23926 2.08795 2.51574 + vertex 1.23519 2.08949 2.51605 + vertex 1.23693 2.08477 2.51709 + endloop + endfacet + facet normal 0.172735 0.273434 0.946254 + outer loop + vertex 1.24115 2.08513 2.51621 + vertex 1.23926 2.08795 2.51574 + vertex 1.23693 2.08477 2.51709 + endloop + endfacet + facet normal 0.173686 0.266569 0.948037 + outer loop + vertex 1.24115 2.08513 2.51621 + vertex 1.23693 2.08477 2.51709 + vertex 1.24145 2.08082 2.51737 + endloop + endfacet + facet normal 0.170261 0.266502 0.948677 + outer loop + vertex 1.24115 2.08513 2.51621 + vertex 1.24145 2.08082 2.51737 + vertex 1.24426 2.0839 2.516 + endloop + endfacet + facet normal 0.173952 0.276436 0.945158 + outer loop + vertex 1.24426 2.0839 2.516 + vertex 1.2439 2.08821 2.51481 + vertex 1.24115 2.08513 2.51621 + endloop + endfacet + facet normal 0.169556 0.267123 0.948628 + outer loop + vertex 1.24618 2.08107 2.51645 + vertex 1.24426 2.0839 2.516 + vertex 1.24145 2.08082 2.51737 + endloop + endfacet + facet normal 0.17073 0.255648 0.951575 + outer loop + vertex 1.24618 2.08107 2.51645 + vertex 1.24145 2.08082 2.51737 + vertex 1.24626 2.07678 2.51759 + endloop + endfacet + facet normal 0.168779 0.255701 0.951909 + outer loop + vertex 1.24618 2.08107 2.51645 + vertex 1.24626 2.07678 2.51759 + vertex 1.25023 2.07964 2.51612 + endloop + endfacet + facet normal 0.170724 0.253161 0.952241 + outer loop + vertex 1.25185 2.0751 2.51704 + vertex 1.25023 2.07964 2.51612 + vertex 1.24626 2.07678 2.51759 + endloop + endfacet + facet normal 0.173657 0.269667 0.947166 + outer loop + vertex 1.24426 2.0839 2.516 + vertex 1.24618 2.08107 2.51645 + vertex 1.24858 2.08435 2.51508 + endloop + endfacet + facet normal 0.172328 0.265063 0.948707 + outer loop + vertex 1.23693 2.08477 2.51709 + vertex 1.23679 2.08079 2.51822 + vertex 1.24145 2.08082 2.51737 + endloop + endfacet + facet normal 0.172856 0.255299 0.951285 + outer loop + vertex 1.23836 2.07796 2.5187 + vertex 1.24145 2.08082 2.51737 + vertex 1.23679 2.08079 2.51822 + endloop + endfacet + facet normal 0.170918 0.254325 0.951896 + outer loop + vertex 1.23836 2.07796 2.5187 + vertex 1.23679 2.08079 2.51822 + vertex 1.23372 2.07796 2.51953 + endloop + endfacet + facet normal 0.174309 0.264905 0.948389 + outer loop + vertex 1.23679 2.08079 2.51822 + vertex 1.23693 2.08477 2.51709 + vertex 1.23351 2.08247 2.51836 + endloop + endfacet + facet normal 0.169693 0.255602 0.951773 + outer loop + vertex 1.23372 2.07796 2.51953 + vertex 1.23679 2.08079 2.51822 + vertex 1.23351 2.08247 2.51836 + endloop + endfacet + facet normal 0.175486 0.255594 0.950724 + outer loop + vertex 1.22891 2.08209 2.51931 + vertex 1.23372 2.07796 2.51953 + vertex 1.23351 2.08247 2.51836 + endloop + endfacet + facet normal 0.173958 0.26695 0.94788 + outer loop + vertex 1.23351 2.08247 2.51836 + vertex 1.23122 2.08672 2.51758 + vertex 1.22891 2.08209 2.51931 + endloop + endfacet + facet normal 0.177498 0.265133 0.947734 + outer loop + vertex 1.22891 2.08209 2.51931 + vertex 1.23122 2.08672 2.51758 + vertex 1.22662 2.08634 2.51855 + endloop + endfacet + facet normal 0.179762 0.266221 0.947002 + outer loop + vertex 1.22891 2.08209 2.51931 + vertex 1.22662 2.08634 2.51855 + vertex 1.22325 2.08404 2.51983 + endloop + endfacet + facet normal 0.177193 0.258035 0.949748 + outer loop + vertex 1.22325 2.08404 2.51983 + vertex 1.22497 2.07932 2.5208 + vertex 1.22891 2.08209 2.51931 + endloop + endfacet + facet normal 0.179626 0.254791 0.950166 + outer loop + vertex 1.22497 2.07932 2.5208 + vertex 1.22904 2.07776 2.52044 + vertex 1.22891 2.08209 2.51931 + endloop + endfacet + facet normal 0.183278 0.259922 0.948077 + outer loop + vertex 1.22497 2.07932 2.5208 + vertex 1.22325 2.08404 2.51983 + vertex 1.22094 2.08086 2.52115 + endloop + endfacet + facet normal 0.179994 0.250598 0.951211 + outer loop + vertex 1.22094 2.08086 2.52115 + vertex 1.22095 2.07669 2.52225 + vertex 1.22497 2.07932 2.5208 + endloop + endfacet + facet normal 0.182142 0.247536 0.951604 + outer loop + vertex 1.22659 2.07451 2.52174 + vertex 1.22497 2.07932 2.5208 + vertex 1.22095 2.07669 2.52225 + endloop + endfacet + facet normal 0.182563 0.248718 0.951215 + outer loop + vertex 1.22248 2.07187 2.52322 + vertex 1.22659 2.07451 2.52174 + vertex 1.22095 2.07669 2.52225 + endloop + endfacet + facet normal 0.181894 0.24854 0.95139 + outer loop + vertex 1.22248 2.07187 2.52322 + vertex 1.22095 2.07669 2.52225 + vertex 1.21846 2.07343 2.52358 + endloop + endfacet + facet normal 0.185218 0.25781 0.948276 + outer loop + vertex 1.21833 2.06924 2.52474 + vertex 1.22248 2.07187 2.52322 + vertex 1.21846 2.07343 2.52358 + endloop + endfacet + facet normal 0.180345 0.258196 0.949111 + outer loop + vertex 1.21381 2.07313 2.52454 + vertex 1.21833 2.06924 2.52474 + vertex 1.21846 2.07343 2.52358 + endloop + endfacet + facet normal 0.181595 0.247278 0.951776 + outer loop + vertex 1.21846 2.07343 2.52358 + vertex 1.21665 2.07625 2.52319 + vertex 1.21381 2.07313 2.52454 + endloop + endfacet + facet normal 0.181432 0.247423 0.951769 + outer loop + vertex 1.21381 2.07313 2.52454 + vertex 1.21665 2.07625 2.52319 + vertex 1.21356 2.07745 2.52347 + endloop + endfacet + facet normal 0.179033 0.247398 0.95223 + outer loop + vertex 1.20923 2.07703 2.52439 + vertex 1.21381 2.07313 2.52454 + vertex 1.21356 2.07745 2.52347 + endloop + endfacet + facet normal 0.17834 0.252118 0.951121 + outer loop + vertex 1.21356 2.07745 2.52347 + vertex 1.21171 2.08028 2.52307 + vertex 1.20923 2.07703 2.52439 + endloop + endfacet + facet normal 0.177231 0.252959 0.951105 + outer loop + vertex 1.20923 2.07703 2.52439 + vertex 1.21171 2.08028 2.52307 + vertex 1.20765 2.08186 2.5234 + endloop + endfacet + facet normal 0.181541 0.254138 0.949977 + outer loop + vertex 1.20923 2.07703 2.52439 + vertex 1.20765 2.08186 2.5234 + vertex 1.20355 2.07926 2.52488 + endloop + endfacet + facet normal 0.179237 0.247805 0.952085 + outer loop + vertex 1.20355 2.07926 2.52488 + vertex 1.20513 2.07442 2.52584 + vertex 1.20923 2.07703 2.52439 + endloop + endfacet + facet normal 0.180161 0.246451 0.952263 + outer loop + vertex 1.20513 2.07442 2.52584 + vertex 1.20917 2.07284 2.52549 + vertex 1.20923 2.07703 2.52439 + endloop + endfacet + facet normal 0.181103 0.24906 0.951405 + outer loop + vertex 1.20917 2.07284 2.52549 + vertex 1.20513 2.07442 2.52584 + vertex 1.20668 2.06957 2.52681 + endloop + endfacet + facet normal 0.177469 0.251815 0.951364 + outer loop + vertex 1.21099 2.07001 2.5259 + vertex 1.20917 2.07284 2.52549 + vertex 1.20668 2.06957 2.52681 + endloop + endfacet + facet normal 0.175395 0.265261 0.948089 + outer loop + vertex 1.21099 2.07001 2.5259 + vertex 1.20668 2.06957 2.52681 + vertex 1.21123 2.06563 2.52708 + endloop + endfacet + facet normal 0.178739 0.265273 0.947461 + outer loop + vertex 1.21099 2.07001 2.5259 + vertex 1.21123 2.06563 2.52708 + vertex 1.21403 2.06882 2.52566 + endloop + endfacet + facet normal 0.174802 0.254513 0.95114 + outer loop + vertex 1.21403 2.06882 2.52566 + vertex 1.21381 2.07313 2.52454 + vertex 1.21099 2.07001 2.5259 + endloop + endfacet + facet normal 0.172948 0.270226 0.947136 + outer loop + vertex 1.21582 2.06596 2.52614 + vertex 1.21403 2.06882 2.52566 + vertex 1.21123 2.06563 2.52708 + endloop + endfacet + facet normal 0.173489 0.265882 0.948266 + outer loop + vertex 1.21582 2.06596 2.52614 + vertex 1.21123 2.06563 2.52708 + vertex 1.21581 2.06162 2.52736 + endloop + endfacet + facet normal 0.16301 0.266374 0.949986 + outer loop + vertex 1.21582 2.06596 2.52614 + vertex 1.21581 2.06162 2.52736 + vertex 1.21984 2.06435 2.52591 + endloop + endfacet + facet normal 0.166984 0.276869 0.946287 + outer loop + vertex 1.21984 2.06435 2.52591 + vertex 1.21833 2.06924 2.52474 + vertex 1.21582 2.06596 2.52614 + endloop + endfacet + facet normal 0.180041 0.280111 0.942933 + outer loop + vertex 1.21833 2.06924 2.52474 + vertex 1.21984 2.06435 2.52591 + vertex 1.22398 2.06699 2.52433 + endloop + endfacet + facet normal 0.166438 0.299404 0.939498 + outer loop + vertex 1.21984 2.06435 2.52591 + vertex 1.22395 2.0627 2.52571 + vertex 1.22398 2.06699 2.52433 + endloop + endfacet + facet normal 0.17086 0.299149 0.938785 + outer loop + vertex 1.22395 2.0627 2.52571 + vertex 1.2288 2.06284 2.52478 + vertex 1.22398 2.06699 2.52433 + endloop + endfacet + facet normal 0.180133 0.309375 0.933723 + outer loop + vertex 1.22398 2.06699 2.52433 + vertex 1.2288 2.06284 2.52478 + vertex 1.22834 2.0674 2.52335 + endloop + endfacet + facet normal 0.18505 0.278261 0.942511 + outer loop + vertex 1.22834 2.0674 2.52335 + vertex 1.2265 2.0703 2.52286 + vertex 1.22398 2.06699 2.52433 + endloop + endfacet + facet normal 0.19068 0.274029 0.942629 + outer loop + vertex 1.22398 2.06699 2.52433 + vertex 1.2265 2.0703 2.52286 + vertex 1.22248 2.07187 2.52322 + endloop + endfacet + facet normal 0.173321 0.27153 0.946695 + outer loop + vertex 1.22834 2.0674 2.52335 + vertex 1.23117 2.07058 2.52192 + vertex 1.2265 2.0703 2.52286 + endloop + endfacet + facet normal 0.175692 0.250074 0.952153 + outer loop + vertex 1.22659 2.07451 2.52174 + vertex 1.2265 2.0703 2.52286 + vertex 1.23117 2.07058 2.52192 + endloop + endfacet + facet normal 0.16684 0.277099 0.946246 + outer loop + vertex 1.2315 2.06612 2.52317 + vertex 1.23117 2.07058 2.52192 + vertex 1.22834 2.0674 2.52335 + endloop + endfacet + facet normal 0.167965 0.277123 0.94604 + outer loop + vertex 1.23117 2.07058 2.52192 + vertex 1.2315 2.06612 2.52317 + vertex 1.23584 2.06658 2.52227 + endloop + endfacet + facet normal 0.169686 0.279057 0.945163 + outer loop + vertex 1.2358 2.07086 2.52101 + vertex 1.23117 2.07058 2.52192 + vertex 1.23584 2.06658 2.52227 + endloop + endfacet + facet normal 0.17039 0.27903 0.945045 + outer loop + vertex 1.2358 2.07086 2.52101 + vertex 1.23584 2.06658 2.52227 + vertex 1.23983 2.0693 2.52074 + endloop + endfacet + facet normal 0.162389 0.25694 0.952687 + outer loop + vertex 1.23983 2.0693 2.52074 + vertex 1.23817 2.07403 2.51975 + vertex 1.2358 2.07086 2.52101 + endloop + endfacet + facet normal 0.168405 0.252489 0.952832 + outer loop + vertex 1.23396 2.07369 2.52059 + vertex 1.2358 2.07086 2.52101 + vertex 1.23817 2.07403 2.51975 + endloop + endfacet + facet normal 0.169322 0.245311 0.954543 + outer loop + vertex 1.23396 2.07369 2.52059 + vertex 1.23817 2.07403 2.51975 + vertex 1.23372 2.07796 2.51953 + endloop + endfacet + facet normal 0.175149 0.245383 0.953473 + outer loop + vertex 1.23396 2.07369 2.52059 + vertex 1.23372 2.07796 2.51953 + vertex 1.23091 2.07492 2.52083 + endloop + endfacet + facet normal 0.177148 0.250695 0.95172 + outer loop + vertex 1.23091 2.07492 2.52083 + vertex 1.23117 2.07058 2.52192 + vertex 1.23396 2.07369 2.52059 + endloop + endfacet + facet normal 0.175769 0.244824 0.953502 + outer loop + vertex 1.22904 2.07776 2.52044 + vertex 1.23091 2.07492 2.52083 + vertex 1.23372 2.07796 2.51953 + endloop + endfacet + facet normal 0.171235 0.247427 0.953655 + outer loop + vertex 1.23372 2.07796 2.51953 + vertex 1.23817 2.07403 2.51975 + vertex 1.23836 2.07796 2.5187 + endloop + endfacet + facet normal 0.170821 0.247465 0.95372 + outer loop + vertex 1.23817 2.07403 2.51975 + vertex 1.24163 2.07632 2.51854 + vertex 1.23836 2.07796 2.5187 + endloop + endfacet + facet normal 0.174041 0.254069 0.951398 + outer loop + vertex 1.24163 2.07632 2.51854 + vertex 1.24145 2.08082 2.51737 + vertex 1.23836 2.07796 2.5187 + endloop + endfacet + facet normal 0.172124 0.259834 0.950189 + outer loop + vertex 1.23817 2.07403 2.51975 + vertex 1.23983 2.0693 2.52074 + vertex 1.24383 2.07213 2.51925 + endloop + endfacet + facet normal 0.169079 0.249923 0.953389 + outer loop + vertex 1.24383 2.07213 2.51925 + vertex 1.24163 2.07632 2.51854 + vertex 1.23817 2.07403 2.51975 + endloop + endfacet + facet normal 0.169962 0.250341 0.953122 + outer loop + vertex 1.24383 2.07213 2.51925 + vertex 1.24626 2.07678 2.51759 + vertex 1.24163 2.07632 2.51854 + endloop + endfacet + facet normal 0.169399 0.2541 0.952227 + outer loop + vertex 1.24145 2.08082 2.51737 + vertex 1.24163 2.07632 2.51854 + vertex 1.24626 2.07678 2.51759 + endloop + endfacet + facet normal 0.167302 0.266191 0.94929 + outer loop + vertex 1.23983 2.0693 2.52074 + vertex 1.24387 2.06778 2.52046 + vertex 1.24383 2.07213 2.51925 + endloop + endfacet + facet normal 0.170372 0.266076 0.948776 + outer loop + vertex 1.24387 2.06778 2.52046 + vertex 1.24857 2.06812 2.51952 + vertex 1.24383 2.07213 2.51925 + endloop + endfacet + facet normal 0.169088 0.264602 0.949418 + outer loop + vertex 1.24383 2.07213 2.51925 + vertex 1.24857 2.06812 2.51952 + vertex 1.24844 2.07264 2.51828 + endloop + endfacet + facet normal 0.179539 0.264383 0.947559 + outer loop + vertex 1.24857 2.06812 2.51952 + vertex 1.25162 2.07118 2.51809 + vertex 1.24844 2.07264 2.51828 + endloop + endfacet + facet normal 0.166731 0.294455 0.941008 + outer loop + vertex 1.24387 2.06778 2.52046 + vertex 1.24576 2.06488 2.52103 + vertex 1.24857 2.06812 2.51952 + endloop + endfacet + facet normal 0.160998 0.299188 0.940514 + outer loop + vertex 1.24885 2.06369 2.52088 + vertex 1.24857 2.06812 2.51952 + vertex 1.24576 2.06488 2.52103 + endloop + endfacet + facet normal 0.160219 0.297062 0.94132 + outer loop + vertex 1.24576 2.06488 2.52103 + vertex 1.24627 2.06035 2.52237 + vertex 1.24885 2.06369 2.52088 + endloop + endfacet + facet normal 0.148222 0.305933 0.940444 + outer loop + vertex 1.25092 2.06084 2.52148 + vertex 1.24885 2.06369 2.52088 + vertex 1.24627 2.06035 2.52237 + endloop + endfacet + facet normal 0.160366 0.227063 0.960586 + outer loop + vertex 1.25092 2.06084 2.52148 + vertex 1.24627 2.06035 2.52237 + vertex 1.25157 2.05671 2.52235 + endloop + endfacet + facet normal 0.126798 0.223026 0.966531 + outer loop + vertex 1.25092 2.06084 2.52148 + vertex 1.25157 2.05671 2.52235 + vertex 1.25518 2.05937 2.52126 + endloop + endfacet + facet normal 0.131577 0.216848 0.967297 + outer loop + vertex 1.25744 2.0552 2.52189 + vertex 1.25518 2.05937 2.52126 + vertex 1.25157 2.05671 2.52235 + endloop + endfacet + facet normal 0.122634 0.172046 0.977426 + outer loop + vertex 1.24627 2.06035 2.52237 + vertex 1.24714 2.05589 2.52305 + vertex 1.25157 2.05671 2.52235 + endloop + endfacet + facet normal 0.183662 -0.164339 0.969155 + outer loop + vertex 1.2495 2.05323 2.52215 + vertex 1.25157 2.05671 2.52235 + vertex 1.24714 2.05589 2.52305 + endloop + endfacet + facet normal 0.112169 -0.22728 0.967348 + outer loop + vertex 1.2495 2.05323 2.52215 + vertex 1.24714 2.05589 2.52305 + vertex 1.2447 2.05334 2.52273 + endloop + endfacet + facet normal 0.0855385 -0.202892 0.975458 + outer loop + vertex 1.2447 2.05334 2.52273 + vertex 1.24714 2.05589 2.52305 + vertex 1.24306 2.05676 2.52359 + endloop + endfacet + facet normal 0.168667 -0.162201 0.972236 + outer loop + vertex 1.2447 2.05334 2.52273 + vertex 1.24306 2.05676 2.52359 + vertex 1.23876 2.05407 2.52389 + endloop + endfacet + facet normal 0.11215 -0.0697863 0.991238 + outer loop + vertex 1.23876 2.05407 2.52389 + vertex 1.24306 2.05676 2.52359 + vertex 1.23915 2.05803 2.52412 + endloop + endfacet + facet normal 0.178239 -0.0757181 0.98107 + outer loop + vertex 1.2342 2.05839 2.52505 + vertex 1.23876 2.05407 2.52389 + vertex 1.23915 2.05803 2.52412 + endloop + endfacet + facet normal 0.19556 0.239757 0.950933 + outer loop + vertex 1.23915 2.05803 2.52412 + vertex 1.23765 2.06169 2.52351 + vertex 1.2342 2.05839 2.52505 + endloop + endfacet + facet normal 0.159429 0.276032 0.947834 + outer loop + vertex 1.2342 2.05839 2.52505 + vertex 1.23765 2.06169 2.52351 + vertex 1.23357 2.06308 2.52379 + endloop + endfacet + facet normal 0.182086 0.277861 0.943206 + outer loop + vertex 1.2288 2.06284 2.52478 + vertex 1.2342 2.05839 2.52505 + vertex 1.23357 2.06308 2.52379 + endloop + endfacet + facet normal 0.178473 0.309961 0.933848 + outer loop + vertex 1.23357 2.06308 2.52379 + vertex 1.2315 2.06612 2.52317 + vertex 1.2288 2.06284 2.52478 + endloop + endfacet + facet normal 0.166846 0.299364 0.939438 + outer loop + vertex 1.23765 2.06169 2.52351 + vertex 1.23584 2.06658 2.52227 + vertex 1.23357 2.06308 2.52379 + endloop + endfacet + facet normal 0.165788 0.299047 0.939726 + outer loop + vertex 1.23765 2.06169 2.52351 + vertex 1.24152 2.06438 2.52197 + vertex 1.23584 2.06658 2.52227 + endloop + endfacet + facet normal 0.171441 0.291677 0.941027 + outer loop + vertex 1.24156 2.06014 2.52327 + vertex 1.24152 2.06438 2.52197 + vertex 1.23765 2.06169 2.52351 + endloop + endfacet + facet normal 0.166558 0.291879 0.941841 + outer loop + vertex 1.24152 2.06438 2.52197 + vertex 1.24156 2.06014 2.52327 + vertex 1.24627 2.06035 2.52237 + endloop + endfacet + facet normal 0.17724 0.169782 0.969412 + outer loop + vertex 1.24306 2.05676 2.52359 + vertex 1.24627 2.06035 2.52237 + vertex 1.24156 2.06014 2.52327 + endloop + endfacet + facet normal 0.187397 0.174057 0.96674 + outer loop + vertex 1.24306 2.05676 2.52359 + vertex 1.24156 2.06014 2.52327 + vertex 1.23915 2.05803 2.52412 + endloop + endfacet + facet normal 0.145043 0.221299 0.964359 + outer loop + vertex 1.23915 2.05803 2.52412 + vertex 1.24156 2.06014 2.52327 + vertex 1.23765 2.06169 2.52351 + endloop + endfacet + facet normal 0.393581 0.172664 0.902929 + outer loop + vertex 1.23437 2.0545 2.52571 + vertex 1.23876 2.05407 2.52389 + vertex 1.2342 2.05839 2.52505 + endloop + endfacet + facet normal 0.292744 0.17469 0.940098 + outer loop + vertex 1.23437 2.0545 2.52571 + vertex 1.2342 2.05839 2.52505 + vertex 1.23138 2.05586 2.5264 + endloop + endfacet + facet normal 0.175576 -0.102919 0.979071 + outer loop + vertex 1.23138 2.05586 2.5264 + vertex 1.23146 2.05337 2.52612 + vertex 1.23437 2.0545 2.52571 + endloop + endfacet + facet normal 0.270104 -0.379341 0.884954 + outer loop + vertex 1.23478 2.05236 2.52467 + vertex 1.23437 2.0545 2.52571 + vertex 1.23146 2.05337 2.52612 + endloop + endfacet + facet normal 0.113907 -0.105963 0.987824 + outer loop + vertex 1.23138 2.05586 2.5264 + vertex 1.22687 2.05578 2.52691 + vertex 1.23146 2.05337 2.52612 + endloop + endfacet + facet normal 0.0712999 -0.184598 0.980225 + outer loop + vertex 1.22687 2.05578 2.52691 + vertex 1.22838 2.05242 2.52616 + vertex 1.23146 2.05337 2.52612 + endloop + endfacet + facet normal 0.143308 -0.151774 0.977971 + outer loop + vertex 1.22838 2.05242 2.52616 + vertex 1.22687 2.05578 2.52691 + vertex 1.22434 2.05271 2.5268 + endloop + endfacet + facet normal 0.142903 -0.151445 0.978081 + outer loop + vertex 1.22434 2.05271 2.5268 + vertex 1.22687 2.05578 2.52691 + vertex 1.22198 2.0554 2.52756 + endloop + endfacet + facet normal 0.132703 -0.160397 0.978091 + outer loop + vertex 1.22434 2.05271 2.5268 + vertex 1.22198 2.0554 2.52756 + vertex 1.21961 2.05296 2.52748 + endloop + endfacet + facet normal 0.0690839 -0.0987017 0.992716 + outer loop + vertex 1.21961 2.05296 2.52748 + vertex 1.22198 2.0554 2.52756 + vertex 1.21765 2.05672 2.52799 + endloop + endfacet + facet normal 0.178645 -0.0401781 0.983093 + outer loop + vertex 1.21961 2.05296 2.52748 + vertex 1.21765 2.05672 2.52799 + vertex 1.21385 2.05332 2.52854 + endloop + endfacet + facet normal 0.130454 0.0150426 0.99134 + outer loop + vertex 1.21385 2.05332 2.52854 + vertex 1.21765 2.05672 2.52799 + vertex 1.21345 2.05808 2.52852 + endloop + endfacet + facet normal 0.217622 0.0223395 0.975777 + outer loop + vertex 1.20875 2.05783 2.52958 + vertex 1.21385 2.05332 2.52854 + vertex 1.21345 2.05808 2.52852 + endloop + endfacet + facet normal 0.203615 0.206454 0.957036 + outer loop + vertex 1.21345 2.05808 2.52852 + vertex 1.2115 2.06112 2.52828 + vertex 1.20875 2.05783 2.52958 + endloop + endfacet + facet normal 0.165219 0.238542 0.956974 + outer loop + vertex 1.20875 2.05783 2.52958 + vertex 1.2115 2.06112 2.52828 + vertex 1.20844 2.0624 2.52849 + endloop + endfacet + facet normal 0.182155 0.238922 0.953801 + outer loop + vertex 1.20415 2.06199 2.52941 + vertex 1.20875 2.05783 2.52958 + vertex 1.20844 2.0624 2.52849 + endloop + endfacet + facet normal 0.177252 0.272266 0.945755 + outer loop + vertex 1.20844 2.0624 2.52849 + vertex 1.20662 2.06533 2.52799 + vertex 1.20415 2.06199 2.52941 + endloop + endfacet + facet normal 0.176172 0.273057 0.945729 + outer loop + vertex 1.20415 2.06199 2.52941 + vertex 1.20662 2.06533 2.52799 + vertex 1.20259 2.06692 2.52828 + endloop + endfacet + facet normal 0.169611 0.271367 0.947413 + outer loop + vertex 1.20415 2.06199 2.52941 + vertex 1.20259 2.06692 2.52828 + vertex 1.19848 2.06427 2.52978 + endloop + endfacet + facet normal 0.174839 0.285169 0.942396 + outer loop + vertex 1.19848 2.06427 2.52978 + vertex 1.20008 2.05939 2.53096 + vertex 1.20415 2.06199 2.52941 + endloop + endfacet + facet normal 0.171996 0.289199 0.941691 + outer loop + vertex 1.20008 2.05939 2.53096 + vertex 1.20408 2.05774 2.53073 + vertex 1.20415 2.06199 2.52941 + endloop + endfacet + facet normal 0.161013 0.261126 0.951781 + outer loop + vertex 1.20408 2.05774 2.53073 + vertex 1.20008 2.05939 2.53096 + vertex 1.20161 2.05461 2.53201 + endloop + endfacet + facet normal 0.194821 0.234653 0.952356 + outer loop + vertex 1.20581 2.05491 2.53108 + vertex 1.20408 2.05774 2.53073 + vertex 1.20161 2.05461 2.53201 + endloop + endfacet + facet normal 0.208065 0.108187 0.972113 + outer loop + vertex 1.20581 2.05491 2.53108 + vertex 1.20161 2.05461 2.53201 + vertex 1.20566 2.05125 2.53152 + endloop + endfacet + facet normal 0.294238 0.102074 0.950266 + outer loop + vertex 1.20581 2.05491 2.53108 + vertex 1.20566 2.05125 2.53152 + vertex 1.20887 2.0533 2.5303 + endloop + endfacet + facet normal 0.319619 0.15779 0.934316 + outer loop + vertex 1.20887 2.0533 2.5303 + vertex 1.20875 2.05783 2.52958 + vertex 1.20581 2.05491 2.53108 + endloop + endfacet + facet normal 0.409154 -0.103638 0.906561 + outer loop + vertex 1.21019 2.04965 2.52929 + vertex 1.20887 2.0533 2.5303 + vertex 1.20566 2.05125 2.53152 + endloop + endfacet + facet normal 0.330273 -0.139727 0.933486 + outer loop + vertex 1.20887 2.0533 2.5303 + vertex 1.21019 2.04965 2.52929 + vertex 1.21385 2.05332 2.52854 + endloop + endfacet + facet normal 0.246281 0.156531 0.956475 + outer loop + vertex 1.20161 2.05461 2.53201 + vertex 1.20164 2.05054 2.53267 + vertex 1.20566 2.05125 2.53152 + endloop + endfacet + facet normal 0.282871 -0.0489889 0.957906 + outer loop + vertex 1.2038 2.04803 2.5319 + vertex 1.20566 2.05125 2.53152 + vertex 1.20164 2.05054 2.53267 + endloop + endfacet + facet normal 0.202789 -0.122022 0.97159 + outer loop + vertex 1.2038 2.04803 2.5319 + vertex 1.20164 2.05054 2.53267 + vertex 1.19891 2.04712 2.53281 + endloop + endfacet + facet normal 0.121116 -0.0559926 0.991058 + outer loop + vertex 1.19891 2.04712 2.53281 + vertex 1.20164 2.05054 2.53267 + vertex 1.19758 2.05184 2.53324 + endloop + endfacet + facet normal 0.24675 -0.0184196 0.968904 + outer loop + vertex 1.19891 2.04712 2.53281 + vertex 1.19758 2.05184 2.53324 + vertex 1.19311 2.04876 2.53432 + endloop + endfacet + facet normal 0.156697 0.115979 0.980813 + outer loop + vertex 1.19311 2.04876 2.53432 + vertex 1.19758 2.05184 2.53324 + vertex 1.19354 2.05332 2.53371 + endloop + endfacet + facet normal 0.185236 0.112715 0.976208 + outer loop + vertex 1.18884 2.05303 2.53463 + vertex 1.19311 2.04876 2.53432 + vertex 1.19354 2.05332 2.53371 + endloop + endfacet + facet normal 0.17253 0.246275 0.95372 + outer loop + vertex 1.19354 2.05332 2.53371 + vertex 1.19173 2.05624 2.53328 + vertex 1.18884 2.05303 2.53463 + endloop + endfacet + facet normal 0.153052 0.263265 0.952506 + outer loop + vertex 1.18884 2.05303 2.53463 + vertex 1.19173 2.05624 2.53328 + vertex 1.18862 2.05744 2.53345 + endloop + endfacet + facet normal 0.169138 0.263336 0.949761 + outer loop + vertex 1.1843 2.05697 2.53435 + vertex 1.18884 2.05303 2.53463 + vertex 1.18862 2.05744 2.53345 + endloop + endfacet + facet normal 0.168932 0.264609 0.949444 + outer loop + vertex 1.18862 2.05744 2.53345 + vertex 1.18677 2.06029 2.53298 + vertex 1.1843 2.05697 2.53435 + endloop + endfacet + facet normal 0.181007 0.255728 0.949652 + outer loop + vertex 1.1843 2.05697 2.53435 + vertex 1.18677 2.06029 2.53298 + vertex 1.18271 2.06185 2.53334 + endloop + endfacet + facet normal 0.170752 0.252951 0.952292 + outer loop + vertex 1.1843 2.05697 2.53435 + vertex 1.18271 2.06185 2.53334 + vertex 1.17856 2.0592 2.53479 + endloop + endfacet + facet normal 0.171468 0.254919 0.951638 + outer loop + vertex 1.17856 2.0592 2.53479 + vertex 1.1802 2.05429 2.53581 + vertex 1.1843 2.05697 2.53435 + endloop + endfacet + facet normal 0.158217 0.273641 0.94873 + outer loop + vertex 1.1802 2.05429 2.53581 + vertex 1.18424 2.05278 2.53557 + vertex 1.1843 2.05697 2.53435 + endloop + endfacet + facet normal 0.15691 0.269926 0.95001 + outer loop + vertex 1.18424 2.05278 2.53557 + vertex 1.1802 2.05429 2.53581 + vertex 1.18171 2.04963 2.53688 + endloop + endfacet + facet normal 0.163874 0.264482 0.950366 + outer loop + vertex 1.1859 2.05006 2.53604 + vertex 1.18424 2.05278 2.53557 + vertex 1.18171 2.04963 2.53688 + endloop + endfacet + facet normal 0.177398 0.271933 0.945824 + outer loop + vertex 1.18424 2.05278 2.53557 + vertex 1.1859 2.05006 2.53604 + vertex 1.18884 2.05303 2.53463 + endloop + endfacet + facet normal 0.232413 0.218211 0.947823 + outer loop + vertex 1.18873 2.04861 2.53568 + vertex 1.18884 2.05303 2.53463 + vertex 1.1859 2.05006 2.53604 + endloop + endfacet + facet normal 0.212617 0.176434 0.961075 + outer loop + vertex 1.1859 2.05006 2.53604 + vertex 1.18538 2.04621 2.53686 + vertex 1.18873 2.04861 2.53568 + endloop + endfacet + facet normal 0.324067 0.0139375 0.945932 + outer loop + vertex 1.18961 2.04476 2.53543 + vertex 1.18873 2.04861 2.53568 + vertex 1.18538 2.04621 2.53686 + endloop + endfacet + facet normal 0.320762 0.00309187 0.947155 + outer loop + vertex 1.18538 2.04621 2.53686 + vertex 1.18632 2.04177 2.53656 + vertex 1.18961 2.04476 2.53543 + endloop + endfacet + facet normal 0.353135 0.0107289 0.935511 + outer loop + vertex 1.18632 2.04177 2.53656 + vertex 1.18538 2.04621 2.53686 + vertex 1.18252 2.04243 2.53798 + endloop + endfacet + facet normal 0.29644 0.00704921 0.955025 + outer loop + vertex 1.18873 2.04861 2.53568 + vertex 1.18961 2.04476 2.53543 + vertex 1.19311 2.04876 2.53432 + endloop + endfacet + facet normal 0.175869 0.182671 0.967317 + outer loop + vertex 1.1859 2.05006 2.53604 + vertex 1.18171 2.04963 2.53688 + vertex 1.18538 2.04621 2.53686 + endloop + endfacet + facet normal 0.226113 0.236859 0.944865 + outer loop + vertex 1.18171 2.04963 2.53688 + vertex 1.18149 2.04574 2.53791 + vertex 1.18538 2.04621 2.53686 + endloop + endfacet + facet normal 0.247732 0.0990162 0.963755 + outer loop + vertex 1.18252 2.04243 2.53798 + vertex 1.18538 2.04621 2.53686 + vertex 1.18149 2.04574 2.53791 + endloop + endfacet + facet normal 0.250934 0.0999877 0.962826 + outer loop + vertex 1.18252 2.04243 2.53798 + vertex 1.18149 2.04574 2.53791 + vertex 1.17905 2.0435 2.53878 + endloop + endfacet + facet normal 0.234916 0.0421225 0.971103 + outer loop + vertex 1.17826 2.03909 2.53916 + vertex 1.18252 2.04243 2.53798 + vertex 1.17905 2.0435 2.53878 + endloop + endfacet + facet normal 0.184367 0.0521068 0.981475 + outer loop + vertex 1.17419 2.04329 2.5397 + vertex 1.17826 2.03909 2.53916 + vertex 1.17905 2.0435 2.53878 + endloop + endfacet + facet normal 0.173853 0.208928 0.962354 + outer loop + vertex 1.17905 2.0435 2.53878 + vertex 1.17786 2.04689 2.53826 + vertex 1.17419 2.04329 2.5397 + endloop + endfacet + facet normal 0.144646 0.237932 0.960451 + outer loop + vertex 1.17419 2.04329 2.5397 + vertex 1.17786 2.04689 2.53826 + vertex 1.17392 2.04788 2.5386 + endloop + endfacet + facet normal 0.167447 0.238359 0.956633 + outer loop + vertex 1.16948 2.0472 2.53955 + vertex 1.17419 2.04329 2.5397 + vertex 1.17392 2.04788 2.5386 + endloop + endfacet + facet normal 0.163766 0.256732 0.952507 + outer loop + vertex 1.17392 2.04788 2.5386 + vertex 1.17172 2.05078 2.5382 + vertex 1.16948 2.0472 2.53955 + endloop + endfacet + facet normal 0.177642 0.247974 0.95234 + outer loop + vertex 1.16948 2.0472 2.53955 + vertex 1.17172 2.05078 2.5382 + vertex 1.16781 2.05197 2.53862 + endloop + endfacet + facet normal 0.176469 0.247624 0.952649 + outer loop + vertex 1.16948 2.0472 2.53955 + vertex 1.16781 2.05197 2.53862 + vertex 1.16386 2.04939 2.54002 + endloop + endfacet + facet normal 0.173839 0.240378 0.954986 + outer loop + vertex 1.16386 2.04939 2.54002 + vertex 1.16533 2.04448 2.54099 + vertex 1.16948 2.0472 2.53955 + endloop + endfacet + facet normal 0.164114 0.254209 0.953123 + outer loop + vertex 1.16533 2.04448 2.54099 + vertex 1.16936 2.04295 2.5407 + vertex 1.16948 2.0472 2.53955 + endloop + endfacet + facet normal 0.160479 0.244062 0.956389 + outer loop + vertex 1.16936 2.04295 2.5407 + vertex 1.16533 2.04448 2.54099 + vertex 1.1667 2.03974 2.54197 + endloop + endfacet + facet normal 0.167766 0.238097 0.956642 + outer loop + vertex 1.17098 2.04018 2.54111 + vertex 1.16936 2.04295 2.5407 + vertex 1.1667 2.03974 2.54197 + endloop + endfacet + facet normal 0.176725 0.17446 0.968675 + outer loop + vertex 1.17098 2.04018 2.54111 + vertex 1.1667 2.03974 2.54197 + vertex 1.17046 2.03626 2.54191 + endloop + endfacet + facet normal 0.225803 0.1661 0.959908 + outer loop + vertex 1.17098 2.04018 2.54111 + vertex 1.17046 2.03626 2.54191 + vertex 1.17388 2.03877 2.54067 + endloop + endfacet + facet normal 0.235859 0.188706 0.953289 + outer loop + vertex 1.17388 2.03877 2.54067 + vertex 1.17419 2.04329 2.5397 + vertex 1.17098 2.04018 2.54111 + endloop + endfacet + facet normal 0.324123 0.0252563 0.945678 + outer loop + vertex 1.17484 2.03486 2.54045 + vertex 1.17388 2.03877 2.54067 + vertex 1.17046 2.03626 2.54191 + endloop + endfacet + facet normal 0.324582 0.0253789 0.945517 + outer loop + vertex 1.17388 2.03877 2.54067 + vertex 1.17484 2.03486 2.54045 + vertex 1.17826 2.03909 2.53916 + endloop + endfacet + facet normal 0.219009 0.220319 0.950523 + outer loop + vertex 1.1667 2.03974 2.54197 + vertex 1.16647 2.03577 2.54294 + vertex 1.17046 2.03626 2.54191 + endloop + endfacet + facet normal 0.231372 0.143263 0.962259 + outer loop + vertex 1.16782 2.03242 2.54312 + vertex 1.17046 2.03626 2.54191 + vertex 1.16647 2.03577 2.54294 + endloop + endfacet + facet normal 0.222931 0.140005 0.964728 + outer loop + vertex 1.16782 2.03242 2.54312 + vertex 1.16647 2.03577 2.54294 + vertex 1.16418 2.03345 2.54381 + endloop + endfacet + facet normal 0.216944 0.115944 0.969274 + outer loop + vertex 1.16409 2.02866 2.5444 + vertex 1.16782 2.03242 2.54312 + vertex 1.16418 2.03345 2.54381 + endloop + endfacet + facet normal 0.162254 0.200393 0.966186 + outer loop + vertex 1.16418 2.03345 2.54381 + vertex 1.16647 2.03577 2.54294 + vertex 1.16283 2.037 2.5433 + endloop + endfacet + facet normal 0.325626 0.0722987 0.94273 + outer loop + vertex 1.17175 2.03181 2.54181 + vertex 1.17046 2.03626 2.54191 + vertex 1.16782 2.03242 2.54312 + endloop + endfacet + facet normal 0.317383 0.00705197 0.948271 + outer loop + vertex 1.17175 2.03181 2.54181 + vertex 1.16782 2.03242 2.54312 + vertex 1.16923 2.02824 2.54267 + endloop + endfacet + facet normal 0.318637 0.0075215 0.947847 + outer loop + vertex 1.16923 2.02824 2.54267 + vertex 1.16782 2.03242 2.54312 + vertex 1.16409 2.02866 2.5444 + endloop + endfacet + facet normal 0.337761 0.075932 0.938164 + outer loop + vertex 1.17046 2.03626 2.54191 + vertex 1.17175 2.03181 2.54181 + vertex 1.17484 2.03486 2.54045 + endloop + endfacet + facet normal 0.169978 0.225287 0.95935 + outer loop + vertex 1.16647 2.03577 2.54294 + vertex 1.1667 2.03974 2.54197 + vertex 1.16283 2.037 2.5433 + endloop + endfacet + facet normal 0.161355 0.236807 0.958064 + outer loop + vertex 1.16283 2.037 2.5433 + vertex 1.1667 2.03974 2.54197 + vertex 1.16121 2.04171 2.54241 + endloop + endfacet + facet normal 0.159823 0.236349 0.958434 + outer loop + vertex 1.16283 2.037 2.5433 + vertex 1.16121 2.04171 2.54241 + vertex 1.15895 2.03806 2.54368 + endloop + endfacet + facet normal 0.156777 0.223939 0.961911 + outer loop + vertex 1.15936 2.03333 2.54472 + vertex 1.16283 2.037 2.5433 + vertex 1.15895 2.03806 2.54368 + endloop + endfacet + facet normal 0.171669 0.224644 0.9592 + outer loop + vertex 1.15454 2.03735 2.54464 + vertex 1.15936 2.03333 2.54472 + vertex 1.15895 2.03806 2.54368 + endloop + endfacet + facet normal 0.170047 0.232547 0.957604 + outer loop + vertex 1.15895 2.03806 2.54368 + vertex 1.15682 2.04098 2.54335 + vertex 1.15454 2.03735 2.54464 + endloop + endfacet + facet normal 0.180244 0.226019 0.957302 + outer loop + vertex 1.15454 2.03735 2.54464 + vertex 1.15682 2.04098 2.54335 + vertex 1.15298 2.04211 2.54381 + endloop + endfacet + facet normal 0.180265 0.226025 0.957297 + outer loop + vertex 1.15454 2.03735 2.54464 + vertex 1.15298 2.04211 2.54381 + vertex 1.14897 2.03949 2.54518 + endloop + endfacet + facet normal 0.186799 0.216502 0.958245 + outer loop + vertex 1.14897 2.03949 2.54518 + vertex 1.15298 2.04211 2.54381 + vertex 1.14928 2.04356 2.5442 + endloop + endfacet + facet normal 0.187969 0.216363 0.958047 + outer loop + vertex 1.14455 2.04379 2.54508 + vertex 1.14897 2.03949 2.54518 + vertex 1.14928 2.04356 2.5442 + endloop + endfacet + facet normal 0.187955 0.214454 0.958479 + outer loop + vertex 1.14928 2.04356 2.5442 + vertex 1.14807 2.04703 2.54366 + vertex 1.14455 2.04379 2.54508 + endloop + endfacet + facet normal 0.186884 0.215596 0.958432 + outer loop + vertex 1.14455 2.04379 2.54508 + vertex 1.14807 2.04703 2.54366 + vertex 1.14441 2.04834 2.54408 + endloop + endfacet + facet normal 0.182553 0.215638 0.959257 + outer loop + vertex 1.13955 2.04859 2.54495 + vertex 1.14455 2.04379 2.54508 + vertex 1.14441 2.04834 2.54408 + endloop + endfacet + facet normal 0.182594 0.219526 0.958367 + outer loop + vertex 1.14441 2.04834 2.54408 + vertex 1.14298 2.05196 2.54353 + vertex 1.13955 2.04859 2.54495 + endloop + endfacet + facet normal 0.180927 0.221196 0.958299 + outer loop + vertex 1.13955 2.04859 2.54495 + vertex 1.14298 2.05196 2.54353 + vertex 1.13923 2.05331 2.54392 + endloop + endfacet + facet normal 0.181252 0.222187 0.958009 + outer loop + vertex 1.14298 2.05196 2.54353 + vertex 1.14151 2.0556 2.54296 + vertex 1.13923 2.05331 2.54392 + endloop + endfacet + facet normal 0.181163 0.222274 0.958005 + outer loop + vertex 1.13923 2.05331 2.54392 + vertex 1.14151 2.0556 2.54296 + vertex 1.13776 2.05693 2.54336 + endloop + endfacet + facet normal 0.18592 0.223991 0.956693 + outer loop + vertex 1.13923 2.05331 2.54392 + vertex 1.13776 2.05693 2.54336 + vertex 1.13435 2.05355 2.54481 + endloop + endfacet + facet normal 0.181329 0.222788 0.957855 + outer loop + vertex 1.14151 2.0556 2.54296 + vertex 1.14122 2.0603 2.54192 + vertex 1.13776 2.05693 2.54336 + endloop + endfacet + facet normal 0.18338 0.220723 0.957942 + outer loop + vertex 1.13776 2.05693 2.54336 + vertex 1.14122 2.0603 2.54192 + vertex 1.13643 2.06047 2.5428 + endloop + endfacet + facet normal 0.183993 0.222837 0.957335 + outer loop + vertex 1.14122 2.0603 2.54192 + vertex 1.14151 2.0556 2.54296 + vertex 1.14633 2.05543 2.54207 + endloop + endfacet + facet normal 0.18444 0.223299 0.957141 + outer loop + vertex 1.14602 2.0603 2.541 + vertex 1.14122 2.0603 2.54192 + vertex 1.14633 2.05543 2.54207 + endloop + endfacet + facet normal 0.188391 0.223379 0.956353 + outer loop + vertex 1.14602 2.0603 2.541 + vertex 1.14633 2.05543 2.54207 + vertex 1.14939 2.05862 2.54073 + endloop + endfacet + facet normal 0.191268 0.229454 0.954341 + outer loop + vertex 1.14939 2.05862 2.54073 + vertex 1.14902 2.06334 2.53966 + vertex 1.14602 2.0603 2.541 + endloop + endfacet + facet normal 0.191305 0.229418 0.954343 + outer loop + vertex 1.14422 2.06348 2.54059 + vertex 1.14602 2.0603 2.541 + vertex 1.14902 2.06334 2.53966 + endloop + endfacet + facet normal 0.191232 0.233742 0.953307 + outer loop + vertex 1.14422 2.06348 2.54059 + vertex 1.14902 2.06334 2.53966 + vertex 1.144 2.06801 2.53953 + endloop + endfacet + facet normal 0.187776 0.233735 0.953996 + outer loop + vertex 1.14422 2.06348 2.54059 + vertex 1.144 2.06801 2.53953 + vertex 1.14103 2.06499 2.54085 + endloop + endfacet + facet normal 0.184258 0.225831 0.956582 + outer loop + vertex 1.14103 2.06499 2.54085 + vertex 1.14122 2.0603 2.54192 + vertex 1.14422 2.06348 2.54059 + endloop + endfacet + facet normal 0.189098 0.225814 0.955641 + outer loop + vertex 1.14103 2.06499 2.54085 + vertex 1.13672 2.06466 2.54178 + vertex 1.14122 2.0603 2.54192 + endloop + endfacet + facet normal 0.18829 0.232398 0.954221 + outer loop + vertex 1.14103 2.06499 2.54085 + vertex 1.13927 2.06796 2.54048 + vertex 1.13672 2.06466 2.54178 + endloop + endfacet + facet normal 0.191001 0.233496 0.953414 + outer loop + vertex 1.144 2.06801 2.53953 + vertex 1.14902 2.06334 2.53966 + vertex 1.14866 2.06794 2.53861 + endloop + endfacet + facet normal 0.190854 0.237812 0.952376 + outer loop + vertex 1.14866 2.06794 2.53861 + vertex 1.14688 2.07103 2.5382 + vertex 1.144 2.06801 2.53953 + endloop + endfacet + facet normal 0.195311 0.240174 0.950879 + outer loop + vertex 1.14866 2.06794 2.53861 + vertex 1.15151 2.07096 2.53726 + vertex 1.14688 2.07103 2.5382 + endloop + endfacet + facet normal 0.195238 0.242296 0.950355 + outer loop + vertex 1.14649 2.07562 2.53711 + vertex 1.14688 2.07103 2.5382 + vertex 1.15151 2.07096 2.53726 + endloop + endfacet + facet normal 0.194648 0.241668 0.950636 + outer loop + vertex 1.15123 2.07542 2.53619 + vertex 1.14649 2.07562 2.53711 + vertex 1.15151 2.07096 2.53726 + endloop + endfacet + facet normal 0.195599 0.241681 0.950438 + outer loop + vertex 1.15123 2.07542 2.53619 + vertex 1.15151 2.07096 2.53726 + vertex 1.1544 2.07394 2.53591 + endloop + endfacet + facet normal 0.196042 0.242689 0.950089 + outer loop + vertex 1.1544 2.07394 2.53591 + vertex 1.15409 2.07842 2.53483 + vertex 1.15123 2.07542 2.53619 + endloop + endfacet + facet normal 0.195918 0.242687 0.950115 + outer loop + vertex 1.1544 2.07394 2.53591 + vertex 1.15869 2.07429 2.53494 + vertex 1.15409 2.07842 2.53483 + endloop + endfacet + facet normal 0.196493 0.243319 0.949835 + outer loop + vertex 1.15409 2.07842 2.53483 + vertex 1.15869 2.07429 2.53494 + vertex 1.15878 2.07851 2.53384 + endloop + endfacet + facet normal 0.192961 0.243564 0.950496 + outer loop + vertex 1.15869 2.07429 2.53494 + vertex 1.16275 2.07697 2.53343 + vertex 1.15878 2.07851 2.53384 + endloop + endfacet + facet normal 0.192879 0.243334 0.950572 + outer loop + vertex 1.16275 2.07697 2.53343 + vertex 1.16124 2.08184 2.53249 + vertex 1.15878 2.07851 2.53384 + endloop + endfacet + facet normal 0.190875 0.242816 0.951108 + outer loop + vertex 1.16275 2.07697 2.53343 + vertex 1.16681 2.07965 2.53193 + vertex 1.16124 2.08184 2.53249 + endloop + endfacet + facet normal 0.188772 0.245809 0.950759 + outer loop + vertex 1.16675 2.0754 2.53304 + vertex 1.16681 2.07965 2.53193 + vertex 1.16275 2.07697 2.53343 + endloop + endfacet + facet normal 0.187768 0.243026 0.951673 + outer loop + vertex 1.16428 2.07208 2.53437 + vertex 1.16675 2.0754 2.53304 + vertex 1.16275 2.07697 2.53343 + endloop + endfacet + facet normal 0.185736 0.244543 0.951683 + outer loop + vertex 1.16861 2.07245 2.53343 + vertex 1.16675 2.0754 2.53304 + vertex 1.16428 2.07208 2.53437 + endloop + endfacet + facet normal 0.186477 0.238999 0.952946 + outer loop + vertex 1.16428 2.07208 2.53437 + vertex 1.16891 2.0679 2.53451 + vertex 1.16861 2.07245 2.53343 + endloop + endfacet + facet normal 0.181878 0.238913 0.953856 + outer loop + vertex 1.16891 2.0679 2.53451 + vertex 1.1718 2.07099 2.53319 + vertex 1.16861 2.07245 2.53343 + endloop + endfacet + facet normal 0.184176 0.244237 0.952065 + outer loop + vertex 1.1718 2.07099 2.53319 + vertex 1.17148 2.07549 2.5321 + vertex 1.16861 2.07245 2.53343 + endloop + endfacet + facet normal 0.183479 0.244221 0.952204 + outer loop + vertex 1.17148 2.07549 2.5321 + vertex 1.1718 2.07099 2.53319 + vertex 1.17646 2.071 2.53229 + endloop + endfacet + facet normal 0.183796 0.237738 0.953782 + outer loop + vertex 1.17357 2.06794 2.53361 + vertex 1.17646 2.071 2.53229 + vertex 1.1718 2.07099 2.53319 + endloop + endfacet + facet normal 0.185795 0.235882 0.953855 + outer loop + vertex 1.17677 2.06646 2.53335 + vertex 1.17646 2.071 2.53229 + vertex 1.17357 2.06794 2.53361 + endloop + endfacet + facet normal 0.18362 0.230875 0.9555 + outer loop + vertex 1.17384 2.06341 2.53465 + vertex 1.17677 2.06646 2.53335 + vertex 1.17357 2.06794 2.53361 + endloop + endfacet + facet normal 0.183744 0.230877 0.955476 + outer loop + vertex 1.16891 2.0679 2.53451 + vertex 1.17384 2.06341 2.53465 + vertex 1.17357 2.06794 2.53361 + endloop + endfacet + facet normal 0.186159 0.233491 0.954373 + outer loop + vertex 1.16916 2.06335 2.53558 + vertex 1.17384 2.06341 2.53465 + vertex 1.16891 2.0679 2.53451 + endloop + endfacet + facet normal 0.188956 0.233514 0.953817 + outer loop + vertex 1.16916 2.06335 2.53558 + vertex 1.16891 2.0679 2.53451 + vertex 1.16601 2.0648 2.53585 + endloop + endfacet + facet normal 0.188402 0.23223 0.95424 + outer loop + vertex 1.16601 2.0648 2.53585 + vertex 1.16622 2.06017 2.53693 + vertex 1.16916 2.06335 2.53558 + endloop + endfacet + facet normal 0.189849 0.230903 0.954275 + outer loop + vertex 1.1709 2.06027 2.53598 + vertex 1.16916 2.06335 2.53558 + vertex 1.16622 2.06017 2.53693 + endloop + endfacet + facet normal 0.189552 0.235254 0.953271 + outer loop + vertex 1.1709 2.06027 2.53598 + vertex 1.16622 2.06017 2.53693 + vertex 1.17119 2.0556 2.53707 + endloop + endfacet + facet normal 0.188587 0.235242 0.953465 + outer loop + vertex 1.1709 2.06027 2.53598 + vertex 1.17119 2.0556 2.53707 + vertex 1.17412 2.05884 2.5357 + endloop + endfacet + facet normal 0.186126 0.229371 0.955377 + outer loop + vertex 1.17412 2.05884 2.5357 + vertex 1.17384 2.06341 2.53465 + vertex 1.1709 2.06027 2.53598 + endloop + endfacet + facet normal 0.177119 0.229224 0.957123 + outer loop + vertex 1.17412 2.05884 2.5357 + vertex 1.17856 2.0592 2.53479 + vertex 1.17384 2.06341 2.53465 + endloop + endfacet + facet normal 0.183562 0.236358 0.95417 + outer loop + vertex 1.17384 2.06341 2.53465 + vertex 1.17856 2.0592 2.53479 + vertex 1.17863 2.06348 2.53371 + endloop + endfacet + facet normal 0.175605 0.241142 0.95447 + outer loop + vertex 1.17412 2.05884 2.5357 + vertex 1.17605 2.05585 2.53609 + vertex 1.17856 2.0592 2.53479 + endloop + endfacet + facet normal 0.179407 0.243432 0.953181 + outer loop + vertex 1.17605 2.05585 2.53609 + vertex 1.17412 2.05884 2.5357 + vertex 1.17119 2.0556 2.53707 + endloop + endfacet + facet normal 0.177843 0.25897 0.949372 + outer loop + vertex 1.17605 2.05585 2.53609 + vertex 1.17119 2.0556 2.53707 + vertex 1.17613 2.05151 2.53726 + endloop + endfacet + facet normal 0.163635 0.259375 0.951813 + outer loop + vertex 1.17605 2.05585 2.53609 + vertex 1.17613 2.05151 2.53726 + vertex 1.1802 2.05429 2.53581 + endloop + endfacet + facet normal 0.16327 0.241667 0.956525 + outer loop + vertex 1.17119 2.0556 2.53707 + vertex 1.17172 2.05078 2.5382 + vertex 1.17613 2.05151 2.53726 + endloop + endfacet + facet normal 0.185355 0.23076 0.955193 + outer loop + vertex 1.16622 2.06017 2.53693 + vertex 1.16644 2.0556 2.53799 + vertex 1.17119 2.0556 2.53707 + endloop + endfacet + facet normal 0.185197 0.234274 0.954368 + outer loop + vertex 1.16781 2.05197 2.53862 + vertex 1.17119 2.0556 2.53707 + vertex 1.16644 2.0556 2.53799 + endloop + endfacet + facet normal 0.186773 0.234794 0.953933 + outer loop + vertex 1.16781 2.05197 2.53862 + vertex 1.16644 2.0556 2.53799 + vertex 1.16409 2.05348 2.53898 + endloop + endfacet + facet normal 0.191473 0.229722 0.954236 + outer loop + vertex 1.16409 2.05348 2.53898 + vertex 1.16644 2.0556 2.53799 + vertex 1.16283 2.05689 2.53841 + endloop + endfacet + facet normal 0.19136 0.229686 0.954267 + outer loop + vertex 1.16409 2.05348 2.53898 + vertex 1.16283 2.05689 2.53841 + vertex 1.15936 2.0537 2.53987 + endloop + endfacet + facet normal 0.191364 0.232982 0.953467 + outer loop + vertex 1.15936 2.0537 2.53987 + vertex 1.16386 2.04939 2.54002 + vertex 1.16409 2.05348 2.53898 + endloop + endfacet + facet normal 0.182885 0.224254 0.957216 + outer loop + vertex 1.1595 2.04908 2.54093 + vertex 1.16386 2.04939 2.54002 + vertex 1.15936 2.0537 2.53987 + endloop + endfacet + facet normal 0.190391 0.22414 0.955779 + outer loop + vertex 1.1595 2.04908 2.54093 + vertex 1.15936 2.0537 2.53987 + vertex 1.15632 2.05054 2.54122 + endloop + endfacet + facet normal 0.189634 0.222378 0.95634 + outer loop + vertex 1.15632 2.05054 2.54122 + vertex 1.15645 2.04581 2.54229 + vertex 1.1595 2.04908 2.54093 + endloop + endfacet + facet normal 0.181968 0.229458 0.956157 + outer loop + vertex 1.16129 2.04607 2.54131 + vertex 1.1595 2.04908 2.54093 + vertex 1.15645 2.04581 2.54229 + endloop + endfacet + facet normal 0.181205 0.237109 0.954434 + outer loop + vertex 1.16129 2.04607 2.54131 + vertex 1.15645 2.04581 2.54229 + vertex 1.16121 2.04171 2.54241 + endloop + endfacet + facet normal 0.169129 0.237855 0.956462 + outer loop + vertex 1.16129 2.04607 2.54131 + vertex 1.16121 2.04171 2.54241 + vertex 1.16533 2.04448 2.54099 + endloop + endfacet + facet normal 0.169619 0.223799 0.959762 + outer loop + vertex 1.15645 2.04581 2.54229 + vertex 1.15682 2.04098 2.54335 + vertex 1.16121 2.04171 2.54241 + endloop + endfacet + facet normal 0.191088 0.222353 0.956057 + outer loop + vertex 1.15632 2.05054 2.54122 + vertex 1.15147 2.05051 2.5422 + vertex 1.15645 2.04581 2.54229 + endloop + endfacet + facet normal 0.186839 0.217889 0.957922 + outer loop + vertex 1.15147 2.05051 2.5422 + vertex 1.15169 2.04575 2.54323 + vertex 1.15645 2.04581 2.54229 + endloop + endfacet + facet normal 0.186856 0.217596 0.957986 + outer loop + vertex 1.15298 2.04211 2.54381 + vertex 1.15645 2.04581 2.54229 + vertex 1.15169 2.04575 2.54323 + endloop + endfacet + facet normal 0.19067 0.217902 0.957164 + outer loop + vertex 1.15169 2.04575 2.54323 + vertex 1.15147 2.05051 2.5422 + vertex 1.14807 2.04703 2.54366 + endloop + endfacet + facet normal 0.190325 0.218237 0.957157 + outer loop + vertex 1.14807 2.04703 2.54366 + vertex 1.15147 2.05051 2.5422 + vertex 1.1467 2.05062 2.54312 + endloop + endfacet + facet normal 0.190245 0.222282 0.956241 + outer loop + vertex 1.14633 2.05543 2.54207 + vertex 1.1467 2.05062 2.54312 + vertex 1.15147 2.05051 2.5422 + endloop + endfacet + facet normal 0.189058 0.221057 0.956761 + outer loop + vertex 1.15124 2.05536 2.54112 + vertex 1.14633 2.05543 2.54207 + vertex 1.15147 2.05051 2.5422 + endloop + endfacet + facet normal 0.19126 0.221064 0.956321 + outer loop + vertex 1.15124 2.05536 2.54112 + vertex 1.15147 2.05051 2.5422 + vertex 1.15458 2.05371 2.54083 + endloop + endfacet + facet normal 0.193584 0.22604 0.954689 + outer loop + vertex 1.15458 2.05371 2.54083 + vertex 1.15431 2.0585 2.53975 + vertex 1.15124 2.05536 2.54112 + endloop + endfacet + facet normal 0.194134 0.225509 0.954703 + outer loop + vertex 1.14939 2.05862 2.54073 + vertex 1.15124 2.05536 2.54112 + vertex 1.15431 2.0585 2.53975 + endloop + endfacet + facet normal 0.192501 0.226029 0.954911 + outer loop + vertex 1.15458 2.05371 2.54083 + vertex 1.15936 2.0537 2.53987 + vertex 1.15431 2.0585 2.53975 + endloop + endfacet + facet normal 0.194296 0.227899 0.954102 + outer loop + vertex 1.15431 2.0585 2.53975 + vertex 1.15936 2.0537 2.53987 + vertex 1.15918 2.05823 2.53883 + endloop + endfacet + facet normal 0.194335 0.23165 0.953191 + outer loop + vertex 1.15918 2.05823 2.53883 + vertex 1.15779 2.06189 2.53822 + vertex 1.15431 2.0585 2.53975 + endloop + endfacet + facet normal 0.195216 0.230761 0.953226 + outer loop + vertex 1.15431 2.0585 2.53975 + vertex 1.15779 2.06189 2.53822 + vertex 1.15383 2.06333 2.53868 + endloop + endfacet + facet normal 0.195168 0.230758 0.953237 + outer loop + vertex 1.14902 2.06334 2.53966 + vertex 1.15431 2.0585 2.53975 + vertex 1.15383 2.06333 2.53868 + endloop + endfacet + facet normal 0.195062 0.233093 0.95269 + outer loop + vertex 1.15383 2.06333 2.53868 + vertex 1.15184 2.06642 2.53833 + vertex 1.14902 2.06334 2.53966 + endloop + endfacet + facet normal 0.197374 0.234487 0.951872 + outer loop + vertex 1.15383 2.06333 2.53868 + vertex 1.15617 2.06673 2.53736 + vertex 1.15184 2.06642 2.53833 + endloop + endfacet + facet normal 0.196843 0.238765 0.950917 + outer loop + vertex 1.15151 2.07096 2.53726 + vertex 1.15184 2.06642 2.53833 + vertex 1.15617 2.06673 2.53736 + endloop + endfacet + facet normal 0.196682 0.23859 0.950995 + outer loop + vertex 1.15622 2.071 2.53628 + vertex 1.15151 2.07096 2.53726 + vertex 1.15617 2.06673 2.53736 + endloop + endfacet + facet normal 0.194565 0.238719 0.951398 + outer loop + vertex 1.15622 2.071 2.53628 + vertex 1.15617 2.06673 2.53736 + vertex 1.1602 2.0694 2.53587 + endloop + endfacet + facet normal 0.195457 0.241132 0.950606 + outer loop + vertex 1.1602 2.0694 2.53587 + vertex 1.15869 2.07429 2.53494 + vertex 1.15622 2.071 2.53628 + endloop + endfacet + facet normal 0.19092 0.239964 0.951823 + outer loop + vertex 1.15869 2.07429 2.53494 + vertex 1.1602 2.0694 2.53587 + vertex 1.16428 2.07208 2.53437 + endloop + endfacet + facet normal 0.191268 0.239465 0.951879 + outer loop + vertex 1.1602 2.0694 2.53587 + vertex 1.16419 2.06779 2.53547 + vertex 1.16428 2.07208 2.53437 + endloop + endfacet + facet normal 0.190169 0.236498 0.95284 + outer loop + vertex 1.16419 2.06779 2.53547 + vertex 1.1602 2.0694 2.53587 + vertex 1.16172 2.06446 2.53679 + endloop + endfacet + facet normal 0.190268 0.236423 0.952839 + outer loop + vertex 1.16601 2.0648 2.53585 + vertex 1.16419 2.06779 2.53547 + vertex 1.16172 2.06446 2.53679 + endloop + endfacet + facet normal 0.195213 0.237793 0.951497 + outer loop + vertex 1.16172 2.06446 2.53679 + vertex 1.1602 2.0694 2.53587 + vertex 1.15617 2.06673 2.53736 + endloop + endfacet + facet normal 0.193877 0.234242 0.95265 + outer loop + vertex 1.15779 2.06189 2.53822 + vertex 1.16172 2.06446 2.53679 + vertex 1.15617 2.06673 2.53736 + endloop + endfacet + facet normal 0.19438 0.233515 0.952726 + outer loop + vertex 1.16155 2.06032 2.53784 + vertex 1.16172 2.06446 2.53679 + vertex 1.15779 2.06189 2.53822 + endloop + endfacet + facet normal 0.192223 0.233702 0.953118 + outer loop + vertex 1.16172 2.06446 2.53679 + vertex 1.16155 2.06032 2.53784 + vertex 1.16622 2.06017 2.53693 + endloop + endfacet + facet normal 0.192278 0.230309 0.953933 + outer loop + vertex 1.16283 2.05689 2.53841 + vertex 1.16622 2.06017 2.53693 + vertex 1.16155 2.06032 2.53784 + endloop + endfacet + facet normal 0.194023 0.230879 0.953441 + outer loop + vertex 1.16283 2.05689 2.53841 + vertex 1.16155 2.06032 2.53784 + vertex 1.15918 2.05823 2.53883 + endloop + endfacet + facet normal 0.196606 0.235024 0.951898 + outer loop + vertex 1.15779 2.06189 2.53822 + vertex 1.15617 2.06673 2.53736 + vertex 1.15383 2.06333 2.53868 + endloop + endfacet + facet normal 0.193557 0.231392 0.953412 + outer loop + vertex 1.15918 2.05823 2.53883 + vertex 1.16155 2.06032 2.53784 + vertex 1.15779 2.06189 2.53822 + endloop + endfacet + facet normal 0.185097 0.222122 0.957288 + outer loop + vertex 1.1467 2.05062 2.54312 + vertex 1.14633 2.05543 2.54207 + vertex 1.14298 2.05196 2.54353 + endloop + endfacet + facet normal 0.191148 0.221171 0.956319 + outer loop + vertex 1.15632 2.05054 2.54122 + vertex 1.15458 2.05371 2.54083 + vertex 1.15147 2.05051 2.5422 + endloop + endfacet + facet normal 0.19268 0.221954 0.95583 + outer loop + vertex 1.15458 2.05371 2.54083 + vertex 1.15632 2.05054 2.54122 + vertex 1.15936 2.0537 2.53987 + endloop + endfacet + facet normal 0.182261 0.229621 0.956062 + outer loop + vertex 1.1595 2.04908 2.54093 + vertex 1.16129 2.04607 2.54131 + vertex 1.16386 2.04939 2.54002 + endloop + endfacet + facet normal 0.193039 0.227906 0.954356 + outer loop + vertex 1.15936 2.0537 2.53987 + vertex 1.16283 2.05689 2.53841 + vertex 1.15918 2.05823 2.53883 + endloop + endfacet + facet normal 0.191813 0.23078 0.953912 + outer loop + vertex 1.16644 2.0556 2.53799 + vertex 1.16622 2.06017 2.53693 + vertex 1.16283 2.05689 2.53841 + endloop + endfacet + facet normal 0.190799 0.232227 0.953764 + outer loop + vertex 1.16601 2.0648 2.53585 + vertex 1.16172 2.06446 2.53679 + vertex 1.16622 2.06017 2.53693 + endloop + endfacet + facet normal 0.187499 0.234858 0.953775 + outer loop + vertex 1.16419 2.06779 2.53547 + vertex 1.16601 2.0648 2.53585 + vertex 1.16891 2.0679 2.53451 + endloop + endfacet + facet normal 0.186417 0.229102 0.955385 + outer loop + vertex 1.16916 2.06335 2.53558 + vertex 1.1709 2.06027 2.53598 + vertex 1.17384 2.06341 2.53465 + endloop + endfacet + facet normal 0.183912 0.2306 0.95551 + outer loop + vertex 1.17863 2.06348 2.53371 + vertex 1.17677 2.06646 2.53335 + vertex 1.17384 2.06341 2.53465 + endloop + endfacet + facet normal 0.185518 0.23154 0.954972 + outer loop + vertex 1.17863 2.06348 2.53371 + vertex 1.18115 2.06678 2.53242 + vertex 1.17677 2.06646 2.53335 + endloop + endfacet + facet normal 0.181377 0.234709 0.954994 + outer loop + vertex 1.18271 2.06185 2.53334 + vertex 1.18115 2.06678 2.53242 + vertex 1.17863 2.06348 2.53371 + endloop + endfacet + facet normal 0.184682 0.235595 0.954142 + outer loop + vertex 1.18271 2.06185 2.53334 + vertex 1.18681 2.06456 2.53188 + vertex 1.18115 2.06678 2.53242 + endloop + endfacet + facet normal 0.185306 0.237316 0.953594 + outer loop + vertex 1.18681 2.06456 2.53188 + vertex 1.18527 2.06942 2.53096 + vertex 1.18115 2.06678 2.53242 + endloop + endfacet + facet normal 0.187022 0.234801 0.953882 + outer loop + vertex 1.18123 2.07105 2.53136 + vertex 1.18115 2.06678 2.53242 + vertex 1.18527 2.06942 2.53096 + endloop + endfacet + facet normal 0.18965 0.241862 0.951596 + outer loop + vertex 1.18527 2.06942 2.53096 + vertex 1.18371 2.07431 2.53003 + vertex 1.18123 2.07105 2.53136 + endloop + endfacet + facet normal 0.187348 0.243616 0.951605 + outer loop + vertex 1.17935 2.07402 2.53097 + vertex 1.18123 2.07105 2.53136 + vertex 1.18371 2.07431 2.53003 + endloop + endfacet + facet normal 0.186548 0.25037 0.950008 + outer loop + vertex 1.17935 2.07402 2.53097 + vertex 1.18371 2.07431 2.53003 + vertex 1.179 2.0785 2.52985 + endloop + endfacet + facet normal 0.184807 0.250325 0.95036 + outer loop + vertex 1.17935 2.07402 2.53097 + vertex 1.179 2.0785 2.52985 + vertex 1.17614 2.0755 2.5312 + endloop + endfacet + facet normal 0.181794 0.24341 0.952734 + outer loop + vertex 1.17614 2.0755 2.5312 + vertex 1.17646 2.071 2.53229 + vertex 1.17935 2.07402 2.53097 + endloop + endfacet + facet normal 0.182755 0.243433 0.952544 + outer loop + vertex 1.17614 2.0755 2.5312 + vertex 1.17148 2.07549 2.5321 + vertex 1.17646 2.071 2.53229 + endloop + endfacet + facet normal 0.182457 0.249488 0.951034 + outer loop + vertex 1.17614 2.0755 2.5312 + vertex 1.17434 2.07853 2.53075 + vertex 1.17148 2.07549 2.5321 + endloop + endfacet + facet normal 0.183276 0.248736 0.951073 + outer loop + vertex 1.17114 2.08 2.53098 + vertex 1.17148 2.07549 2.5321 + vertex 1.17434 2.07853 2.53075 + endloop + endfacet + facet normal 0.184114 0.250668 0.950404 + outer loop + vertex 1.17434 2.07853 2.53075 + vertex 1.17402 2.08299 2.52964 + vertex 1.17114 2.08 2.53098 + endloop + endfacet + facet normal 0.186545 0.248388 0.950528 + outer loop + vertex 1.16927 2.08294 2.53058 + vertex 1.17114 2.08 2.53098 + vertex 1.17402 2.08299 2.52964 + endloop + endfacet + facet normal 0.186765 0.244657 0.951452 + outer loop + vertex 1.16927 2.08294 2.53058 + vertex 1.17402 2.08299 2.52964 + vertex 1.16933 2.08718 2.52948 + endloop + endfacet + facet normal 0.190649 0.244419 0.950743 + outer loop + vertex 1.16528 2.08454 2.53097 + vertex 1.16927 2.08294 2.53058 + vertex 1.16933 2.08718 2.52948 + endloop + endfacet + facet normal 0.191064 0.245547 0.950369 + outer loop + vertex 1.16927 2.08294 2.53058 + vertex 1.16528 2.08454 2.53097 + vertex 1.16681 2.07965 2.53193 + endloop + endfacet + facet normal 0.190753 0.249038 0.949523 + outer loop + vertex 1.16933 2.08718 2.52948 + vertex 1.17402 2.08299 2.52964 + vertex 1.17365 2.08752 2.52852 + endloop + endfacet + facet normal 0.191494 0.243333 0.950852 + outer loop + vertex 1.17365 2.08752 2.52852 + vertex 1.17168 2.09058 2.52814 + vertex 1.16933 2.08718 2.52948 + endloop + endfacet + facet normal 0.195598 0.240458 0.950748 + outer loop + vertex 1.16933 2.08718 2.52948 + vertex 1.17168 2.09058 2.52814 + vertex 1.16778 2.09194 2.52859 + endloop + endfacet + facet normal 0.195392 0.240401 0.950805 + outer loop + vertex 1.16933 2.08718 2.52948 + vertex 1.16778 2.09194 2.52859 + vertex 1.16383 2.0894 2.53005 + endloop + endfacet + facet normal 0.199222 0.234795 0.951411 + outer loop + vertex 1.16383 2.0894 2.53005 + vertex 1.16778 2.09194 2.52859 + vertex 1.16409 2.09348 2.52899 + endloop + endfacet + facet normal 0.199223 0.234797 0.95141 + outer loop + vertex 1.16778 2.09194 2.52859 + vertex 1.16655 2.09549 2.52798 + vertex 1.16409 2.09348 2.52899 + endloop + endfacet + facet normal 0.2018 0.231739 0.951616 + outer loop + vertex 1.16409 2.09348 2.52899 + vertex 1.16655 2.09549 2.52798 + vertex 1.16286 2.09702 2.52839 + endloop + endfacet + facet normal 0.20293 0.232075 0.951294 + outer loop + vertex 1.16409 2.09348 2.52899 + vertex 1.16286 2.09702 2.52839 + vertex 1.15936 2.09365 2.52996 + endloop + endfacet + facet normal 0.203959 0.231019 0.951331 + outer loop + vertex 1.15936 2.09365 2.52996 + vertex 1.16286 2.09702 2.52839 + vertex 1.15899 2.09835 2.52889 + endloop + endfacet + facet normal 0.203566 0.231008 0.951418 + outer loop + vertex 1.15424 2.09834 2.52991 + vertex 1.15936 2.09365 2.52996 + vertex 1.15899 2.09835 2.52889 + endloop + endfacet + facet normal 0.203323 0.235758 0.950304 + outer loop + vertex 1.15899 2.09835 2.52889 + vertex 1.15703 2.10139 2.52856 + vertex 1.15424 2.09834 2.52991 + endloop + endfacet + facet normal 0.202948 0.2361 0.9503 + outer loop + vertex 1.15424 2.09834 2.52991 + vertex 1.15703 2.10139 2.52856 + vertex 1.15383 2.10293 2.52886 + endloop + endfacet + facet normal 0.206604 0.244212 0.947457 + outer loop + vertex 1.15703 2.10139 2.52856 + vertex 1.15663 2.10597 2.52746 + vertex 1.15383 2.10293 2.52886 + endloop + endfacet + facet normal 0.206787 0.244045 0.94746 + outer loop + vertex 1.15383 2.10293 2.52886 + vertex 1.15663 2.10597 2.52746 + vertex 1.152 2.10609 2.52844 + endloop + endfacet + facet normal 0.211342 0.24647 0.945826 + outer loop + vertex 1.15383 2.10293 2.52886 + vertex 1.152 2.10609 2.52844 + vertex 1.14921 2.10321 2.52982 + endloop + endfacet + facet normal 0.206751 0.24531 0.947142 + outer loop + vertex 1.15159 2.11074 2.52733 + vertex 1.152 2.10609 2.52844 + vertex 1.15663 2.10597 2.52746 + endloop + endfacet + facet normal 0.2138 0.252652 0.94364 + outer loop + vertex 1.15628 2.11046 2.52634 + vertex 1.15159 2.11074 2.52733 + vertex 1.15663 2.10597 2.52746 + endloop + endfacet + facet normal 0.201596 0.252389 0.946392 + outer loop + vertex 1.15628 2.11046 2.52634 + vertex 1.15663 2.10597 2.52746 + vertex 1.15947 2.10896 2.52606 + endloop + endfacet + facet normal 0.203111 0.255853 0.945138 + outer loop + vertex 1.15947 2.10896 2.52606 + vertex 1.15912 2.11343 2.52493 + vertex 1.15628 2.11046 2.52634 + endloop + endfacet + facet normal 0.204283 0.254753 0.945182 + outer loop + vertex 1.15448 2.11356 2.52589 + vertex 1.15628 2.11046 2.52634 + vertex 1.15912 2.11343 2.52493 + endloop + endfacet + facet normal 0.201372 0.255815 0.94552 + outer loop + vertex 1.15947 2.10896 2.52606 + vertex 1.16376 2.10932 2.52505 + vertex 1.15912 2.11343 2.52493 + endloop + endfacet + facet normal 0.200966 0.255364 0.945728 + outer loop + vertex 1.15912 2.11343 2.52493 + vertex 1.16376 2.10932 2.52505 + vertex 1.1638 2.1135 2.52392 + endloop + endfacet + facet normal 0.200846 0.257102 0.945283 + outer loop + vertex 1.1638 2.1135 2.52392 + vertex 1.16194 2.11639 2.52352 + vertex 1.15912 2.11343 2.52493 + endloop + endfacet + facet normal 0.201563 0.256432 0.945312 + outer loop + vertex 1.15912 2.11343 2.52493 + vertex 1.16194 2.11639 2.52352 + vertex 1.15879 2.11786 2.5238 + endloop + endfacet + facet normal 0.212694 0.25663 0.942816 + outer loop + vertex 1.15421 2.1181 2.52476 + vertex 1.15912 2.11343 2.52493 + vertex 1.15879 2.11786 2.5238 + endloop + endfacet + facet normal 0.212715 0.251971 0.944067 + outer loop + vertex 1.15879 2.11786 2.5238 + vertex 1.15699 2.12099 2.52336 + vertex 1.15421 2.1181 2.52476 + endloop + endfacet + facet normal 0.205303 0.248091 0.946732 + outer loop + vertex 1.15879 2.11786 2.5238 + vertex 1.16158 2.12089 2.5224 + vertex 1.15699 2.12099 2.52336 + endloop + endfacet + facet normal 0.205854 0.229889 0.951197 + outer loop + vertex 1.15664 2.12576 2.52229 + vertex 1.15699 2.12099 2.52336 + vertex 1.16158 2.12089 2.5224 + endloop + endfacet + facet normal 0.226361 0.250541 0.94127 + outer loop + vertex 1.16125 2.12539 2.52128 + vertex 1.15664 2.12576 2.52229 + vertex 1.16158 2.12089 2.5224 + endloop + endfacet + facet normal 0.208436 0.250279 0.945471 + outer loop + vertex 1.16125 2.12539 2.52128 + vertex 1.16158 2.12089 2.5224 + vertex 1.1644 2.12385 2.52099 + endloop + endfacet + facet normal 0.206964 0.24705 0.946643 + outer loop + vertex 1.1644 2.12385 2.52099 + vertex 1.1641 2.12837 2.51988 + vertex 1.16125 2.12539 2.52128 + endloop + endfacet + facet normal 0.204023 0.247014 0.94729 + outer loop + vertex 1.1644 2.12385 2.52099 + vertex 1.16867 2.1242 2.51998 + vertex 1.1641 2.12837 2.51988 + endloop + endfacet + facet normal 0.209627 0.253078 0.944462 + outer loop + vertex 1.1641 2.12837 2.51988 + vertex 1.16867 2.1242 2.51998 + vertex 1.16873 2.12838 2.51885 + endloop + endfacet + facet normal 0.20979 0.250236 0.945183 + outer loop + vertex 1.16873 2.12838 2.51885 + vertex 1.16693 2.13131 2.51847 + vertex 1.1641 2.12837 2.51988 + endloop + endfacet + facet normal 0.20638 0.248298 0.946444 + outer loop + vertex 1.16873 2.12838 2.51885 + vertex 1.17117 2.13166 2.51746 + vertex 1.16693 2.13131 2.51847 + endloop + endfacet + facet normal 0.208052 0.235963 0.949229 + outer loop + vertex 1.16663 2.13591 2.51739 + vertex 1.16693 2.13131 2.51847 + vertex 1.17117 2.13166 2.51746 + endloop + endfacet + facet normal 0.215795 0.244167 0.945418 + outer loop + vertex 1.17127 2.1359 2.51634 + vertex 1.16663 2.13591 2.51739 + vertex 1.17117 2.13166 2.51746 + endloop + endfacet + facet normal 0.20765 0.2448 0.947077 + outer loop + vertex 1.17127 2.1359 2.51634 + vertex 1.17117 2.13166 2.51746 + vertex 1.17519 2.13432 2.51589 + endloop + endfacet + facet normal 0.204875 0.237203 0.949611 + outer loop + vertex 1.17519 2.13432 2.51589 + vertex 1.17373 2.13923 2.51497 + vertex 1.17127 2.1359 2.51634 + endloop + endfacet + facet normal 0.208379 0.234573 0.949502 + outer loop + vertex 1.16945 2.13891 2.51599 + vertex 1.17127 2.1359 2.51634 + vertex 1.17373 2.13923 2.51497 + endloop + endfacet + facet normal 0.208284 0.235324 0.949337 + outer loop + vertex 1.16945 2.13891 2.51599 + vertex 1.17373 2.13923 2.51497 + vertex 1.16904 2.1435 2.51494 + endloop + endfacet + facet normal 0.224848 0.235896 0.945408 + outer loop + vertex 1.16945 2.13891 2.51599 + vertex 1.16904 2.1435 2.51494 + vertex 1.16629 2.14052 2.51634 + endloop + endfacet + facet normal 0.223159 0.232291 0.9467 + outer loop + vertex 1.16629 2.14052 2.51634 + vertex 1.16663 2.13591 2.51739 + vertex 1.16945 2.13891 2.51599 + endloop + endfacet + facet normal 0.24241 0.232639 0.941868 + outer loop + vertex 1.16629 2.14052 2.51634 + vertex 1.16173 2.14082 2.51744 + vertex 1.16663 2.13591 2.51739 + endloop + endfacet + facet normal 0.225511 0.215671 0.950069 + outer loop + vertex 1.16173 2.14082 2.51744 + vertex 1.16212 2.1361 2.51842 + vertex 1.16663 2.13591 2.51739 + endloop + endfacet + facet normal 0.206237 0.233084 0.950336 + outer loop + vertex 1.16904 2.1435 2.51494 + vertex 1.17373 2.13923 2.51497 + vertex 1.17382 2.14347 2.51392 + endloop + endfacet + facet normal 0.205303 0.253385 0.945329 + outer loop + vertex 1.17382 2.14347 2.51392 + vertex 1.17197 2.1463 2.51356 + vertex 1.16904 2.1435 2.51494 + endloop + endfacet + facet normal 0.207956 0.232962 0.949991 + outer loop + vertex 1.17373 2.13923 2.51497 + vertex 1.17777 2.14187 2.51344 + vertex 1.17382 2.14347 2.51392 + endloop + endfacet + facet normal 0.214703 0.251461 0.943753 + outer loop + vertex 1.17777 2.14187 2.51344 + vertex 1.17619 2.14657 2.51255 + vertex 1.17382 2.14347 2.51392 + endloop + endfacet + facet normal 0.203854 0.248408 0.946962 + outer loop + vertex 1.17777 2.14187 2.51344 + vertex 1.18166 2.14448 2.51192 + vertex 1.17619 2.14657 2.51255 + endloop + endfacet + facet normal 0.210979 0.238403 0.947973 + outer loop + vertex 1.1817 2.1403 2.51296 + vertex 1.18166 2.14448 2.51192 + vertex 1.17777 2.14187 2.51344 + endloop + endfacet + facet normal 0.209764 0.235019 0.949086 + outer loop + vertex 1.17925 2.13701 2.51432 + vertex 1.1817 2.1403 2.51296 + vertex 1.17777 2.14187 2.51344 + endloop + endfacet + facet normal 0.209184 0.235459 0.949105 + outer loop + vertex 1.1835 2.13738 2.51329 + vertex 1.1817 2.1403 2.51296 + vertex 1.17925 2.13701 2.51432 + endloop + endfacet + facet normal 0.207658 0.246218 0.946708 + outer loop + vertex 1.17925 2.13701 2.51432 + vertex 1.1838 2.13286 2.5144 + vertex 1.1835 2.13738 2.51329 + endloop + endfacet + facet normal 0.209604 0.246237 0.946273 + outer loop + vertex 1.1838 2.13286 2.5144 + vertex 1.18664 2.13588 2.51299 + vertex 1.1835 2.13738 2.51329 + endloop + endfacet + facet normal 0.206447 0.239153 0.948781 + outer loop + vertex 1.18664 2.13588 2.51299 + vertex 1.1863 2.14037 2.51193 + vertex 1.1835 2.13738 2.51329 + endloop + endfacet + facet normal 0.207467 0.239176 0.948553 + outer loop + vertex 1.1863 2.14037 2.51193 + vertex 1.18664 2.13588 2.51299 + vertex 1.19134 2.13558 2.51203 + endloop + endfacet + facet normal 0.213375 0.245341 0.945663 + outer loop + vertex 1.19089 2.14024 2.51093 + vertex 1.1863 2.14037 2.51193 + vertex 1.19134 2.13558 2.51203 + endloop + endfacet + facet normal 0.215747 0.245436 0.9451 + outer loop + vertex 1.19089 2.14024 2.51093 + vertex 1.19134 2.13558 2.51203 + vertex 1.1942 2.13843 2.51064 + endloop + endfacet + facet normal 0.215373 0.244706 0.945375 + outer loop + vertex 1.1942 2.13843 2.51064 + vertex 1.19376 2.14307 2.50954 + vertex 1.19089 2.14024 2.51093 + endloop + endfacet + facet normal 0.215507 0.244572 0.945379 + outer loop + vertex 1.189 2.1434 2.51054 + vertex 1.19089 2.14024 2.51093 + vertex 1.19376 2.14307 2.50954 + endloop + endfacet + facet normal 0.210957 0.244525 0.946417 + outer loop + vertex 1.1942 2.13843 2.51064 + vertex 1.19899 2.13803 2.50968 + vertex 1.19376 2.14307 2.50954 + endloop + endfacet + facet normal 0.210681 0.244242 0.946551 + outer loop + vertex 1.19376 2.14307 2.50954 + vertex 1.19899 2.13803 2.50968 + vertex 1.1986 2.14264 2.50857 + endloop + endfacet + facet normal 0.214286 0.244343 0.945716 + outer loop + vertex 1.19899 2.13803 2.50968 + vertex 1.20191 2.14087 2.50828 + vertex 1.1986 2.14264 2.50857 + endloop + endfacet + facet normal 0.216475 0.248725 0.944073 + outer loop + vertex 1.20191 2.14087 2.50828 + vertex 1.20146 2.14545 2.50718 + vertex 1.1986 2.14264 2.50857 + endloop + endfacet + facet normal 0.208332 0.248387 0.945993 + outer loop + vertex 1.20146 2.14545 2.50718 + vertex 1.20191 2.14087 2.50828 + vertex 1.2065 2.14079 2.50729 + endloop + endfacet + facet normal 0.208444 0.248507 0.945936 + outer loop + vertex 1.20603 2.14536 2.50619 + vertex 1.20146 2.14545 2.50718 + vertex 1.2065 2.14079 2.50729 + endloop + endfacet + facet normal 0.209361 0.24855 0.945722 + outer loop + vertex 1.20603 2.14536 2.50619 + vertex 1.2065 2.14079 2.50729 + vertex 1.2092 2.14383 2.50589 + endloop + endfacet + facet normal 0.222594 0.278043 0.934422 + outer loop + vertex 1.2092 2.14383 2.50589 + vertex 1.20855 2.14835 2.5047 + vertex 1.20603 2.14536 2.50619 + endloop + endfacet + facet normal 0.205405 0.276703 0.938746 + outer loop + vertex 1.2092 2.14383 2.50589 + vertex 1.21337 2.14401 2.50493 + vertex 1.20855 2.14835 2.5047 + endloop + endfacet + facet normal 0.207975 0.251607 0.94522 + outer loop + vertex 1.2092 2.14383 2.50589 + vertex 1.21112 2.14082 2.50627 + vertex 1.21337 2.14401 2.50493 + endloop + endfacet + facet normal 0.206732 0.250871 0.945688 + outer loop + vertex 1.21112 2.14082 2.50627 + vertex 1.2092 2.14383 2.50589 + vertex 1.2065 2.14079 2.50729 + endloop + endfacet + facet normal 0.212076 0.246574 0.945635 + outer loop + vertex 1.20372 2.13774 2.50869 + vertex 1.20191 2.14087 2.50828 + vertex 1.19899 2.13803 2.50968 + endloop + endfacet + facet normal 0.212123 0.258414 0.942457 + outer loop + vertex 1.19899 2.13803 2.50968 + vertex 1.20401 2.1333 2.50984 + vertex 1.20372 2.13774 2.50869 + endloop + endfacet + facet normal 0.208923 0.258387 0.943179 + outer loop + vertex 1.20401 2.1333 2.50984 + vertex 1.20686 2.13625 2.5084 + vertex 1.20372 2.13774 2.50869 + endloop + endfacet + facet normal 0.204471 0.248284 0.946862 + outer loop + vertex 1.20686 2.13625 2.5084 + vertex 1.2065 2.14079 2.50729 + vertex 1.20372 2.13774 2.50869 + endloop + endfacet + facet normal 0.200878 0.248195 0.947654 + outer loop + vertex 1.2065 2.14079 2.50729 + vertex 1.20686 2.13625 2.5084 + vertex 1.21112 2.1366 2.50741 + endloop + endfacet + facet normal 0.206517 0.254322 0.944813 + outer loop + vertex 1.21112 2.14082 2.50627 + vertex 1.2065 2.14079 2.50729 + vertex 1.21112 2.1366 2.50741 + endloop + endfacet + facet normal 0.202958 0.254518 0.945531 + outer loop + vertex 1.21112 2.14082 2.50627 + vertex 1.21112 2.1366 2.50741 + vertex 1.21507 2.1392 2.50586 + endloop + endfacet + facet normal 0.196623 0.263498 0.944409 + outer loop + vertex 1.21667 2.1344 2.50687 + vertex 1.21507 2.1392 2.50586 + vertex 1.21112 2.1366 2.50741 + endloop + endfacet + facet normal 0.19775 0.266615 0.943298 + outer loop + vertex 1.21267 2.13182 2.50844 + vertex 1.21667 2.1344 2.50687 + vertex 1.21112 2.1366 2.50741 + endloop + endfacet + facet normal 0.193267 0.265435 0.944559 + outer loop + vertex 1.21267 2.13182 2.50844 + vertex 1.21112 2.1366 2.50741 + vertex 1.20868 2.13336 2.50882 + endloop + endfacet + facet normal 0.195757 0.272472 0.942039 + outer loop + vertex 1.20864 2.12923 2.51002 + vertex 1.21267 2.13182 2.50844 + vertex 1.20868 2.13336 2.50882 + endloop + endfacet + facet normal 0.202823 0.271995 0.940681 + outer loop + vertex 1.20401 2.1333 2.50984 + vertex 1.20864 2.12923 2.51002 + vertex 1.20868 2.13336 2.50882 + endloop + endfacet + facet normal 0.19794 0.266567 0.943272 + outer loop + vertex 1.20435 2.12887 2.51102 + vertex 1.20864 2.12923 2.51002 + vertex 1.20401 2.1333 2.50984 + endloop + endfacet + facet normal 0.201031 0.266621 0.942603 + outer loop + vertex 1.20435 2.12887 2.51102 + vertex 1.20401 2.1333 2.50984 + vertex 1.2012 2.13031 2.51129 + endloop + endfacet + facet normal 0.202464 0.269967 0.941343 + outer loop + vertex 1.2012 2.13031 2.51129 + vertex 1.20153 2.12592 2.51248 + vertex 1.20435 2.12887 2.51102 + endloop + endfacet + facet normal 0.198466 0.273678 0.941123 + outer loop + vertex 1.20622 2.126 2.51146 + vertex 1.20435 2.12887 2.51102 + vertex 1.20153 2.12592 2.51248 + endloop + endfacet + facet normal 0.198423 0.274238 0.940969 + outer loop + vertex 1.20622 2.126 2.51146 + vertex 1.20153 2.12592 2.51248 + vertex 1.20633 2.12174 2.51268 + endloop + endfacet + facet normal 0.193579 0.274386 0.941934 + outer loop + vertex 1.20622 2.126 2.51146 + vertex 1.20633 2.12174 2.51268 + vertex 1.21025 2.12448 2.51108 + endloop + endfacet + facet normal 0.193858 0.275196 0.94164 + outer loop + vertex 1.21025 2.12448 2.51108 + vertex 1.20864 2.12923 2.51002 + vertex 1.20622 2.126 2.51146 + endloop + endfacet + facet normal 0.19294 0.274942 0.941903 + outer loop + vertex 1.20864 2.12923 2.51002 + vertex 1.21025 2.12448 2.51108 + vertex 1.21425 2.12707 2.5095 + endloop + endfacet + facet normal 0.191638 0.276781 0.94163 + outer loop + vertex 1.21025 2.12448 2.51108 + vertex 1.21426 2.12295 2.51071 + vertex 1.21425 2.12707 2.5095 + endloop + endfacet + facet normal 0.191179 0.276805 0.941716 + outer loop + vertex 1.21426 2.12295 2.51071 + vertex 1.21887 2.12312 2.50973 + vertex 1.21425 2.12707 2.5095 + endloop + endfacet + facet normal 0.191802 0.277511 0.941382 + outer loop + vertex 1.21425 2.12707 2.5095 + vertex 1.21887 2.12312 2.50973 + vertex 1.21856 2.12742 2.50852 + endloop + endfacet + facet normal 0.191788 0.27761 0.941356 + outer loop + vertex 1.21856 2.12742 2.50852 + vertex 1.21668 2.13026 2.50807 + vertex 1.21425 2.12707 2.5095 + endloop + endfacet + facet normal 0.193783 0.276109 0.941388 + outer loop + vertex 1.21425 2.12707 2.5095 + vertex 1.21668 2.13026 2.50807 + vertex 1.21267 2.13182 2.50844 + endloop + endfacet + facet normal 0.192898 0.278278 0.940931 + outer loop + vertex 1.21856 2.12742 2.50852 + vertex 1.22135 2.13036 2.50708 + vertex 1.21668 2.13026 2.50807 + endloop + endfacet + facet normal 0.193273 0.27354 0.942243 + outer loop + vertex 1.21667 2.1344 2.50687 + vertex 1.21668 2.13026 2.50807 + vertex 1.22135 2.13036 2.50708 + endloop + endfacet + facet normal 0.196045 0.276671 0.940755 + outer loop + vertex 1.22093 2.13476 2.50587 + vertex 1.21667 2.1344 2.50687 + vertex 1.22135 2.13036 2.50708 + endloop + endfacet + facet normal 0.196356 0.276682 0.940687 + outer loop + vertex 1.22093 2.13476 2.50587 + vertex 1.22135 2.13036 2.50708 + vertex 1.2241 2.13333 2.50563 + endloop + endfacet + facet normal 0.193694 0.270347 0.943078 + outer loop + vertex 1.2241 2.13333 2.50563 + vertex 1.22367 2.13782 2.50443 + vertex 1.22093 2.13476 2.50587 + endloop + endfacet + facet normal 0.195072 0.277835 0.940614 + outer loop + vertex 1.22593 2.13036 2.50613 + vertex 1.2241 2.13333 2.50563 + vertex 1.22135 2.13036 2.50708 + endloop + endfacet + facet normal 0.194882 0.281081 0.939688 + outer loop + vertex 1.22593 2.13036 2.50613 + vertex 1.22135 2.13036 2.50708 + vertex 1.22635 2.12597 2.50736 + endloop + endfacet + facet normal 0.194243 0.281059 0.939827 + outer loop + vertex 1.22593 2.13036 2.50613 + vertex 1.22635 2.12597 2.50736 + vertex 1.22911 2.12888 2.50592 + endloop + endfacet + facet normal 0.193839 0.28014 0.940185 + outer loop + vertex 1.22911 2.12888 2.50592 + vertex 1.22874 2.13322 2.5047 + vertex 1.22593 2.13036 2.50613 + endloop + endfacet + facet normal 0.192596 0.282565 0.939715 + outer loop + vertex 1.23107 2.12595 2.5064 + vertex 1.22911 2.12888 2.50592 + vertex 1.22635 2.12597 2.50736 + endloop + endfacet + facet normal 0.192647 0.281624 0.939987 + outer loop + vertex 1.23107 2.12595 2.5064 + vertex 1.22635 2.12597 2.50736 + vertex 1.23128 2.12169 2.50763 + endloop + endfacet + facet normal 0.189753 0.28165 0.940568 + outer loop + vertex 1.23107 2.12595 2.5064 + vertex 1.23128 2.12169 2.50763 + vertex 1.23515 2.12434 2.50605 + endloop + endfacet + facet normal 0.190783 0.2845 0.939501 + outer loop + vertex 1.23515 2.12434 2.50605 + vertex 1.23333 2.12903 2.505 + vertex 1.23107 2.12595 2.5064 + endloop + endfacet + facet normal 0.190559 0.284429 0.939568 + outer loop + vertex 1.23333 2.12903 2.505 + vertex 1.23515 2.12434 2.50605 + vertex 1.23898 2.12704 2.50446 + endloop + endfacet + facet normal 0.188688 0.286874 0.939202 + outer loop + vertex 1.23515 2.12434 2.50605 + vertex 1.23919 2.12283 2.5057 + vertex 1.23898 2.12704 2.50446 + endloop + endfacet + facet normal 0.18596 0.286899 0.939738 + outer loop + vertex 1.23919 2.12283 2.5057 + vertex 1.24379 2.12309 2.50471 + vertex 1.23898 2.12704 2.50446 + endloop + endfacet + facet normal 0.188858 0.290326 0.938106 + outer loop + vertex 1.23898 2.12704 2.50446 + vertex 1.24379 2.12309 2.50471 + vertex 1.24346 2.12749 2.50342 + endloop + endfacet + facet normal 0.189095 0.288876 0.938506 + outer loop + vertex 1.24346 2.12749 2.50342 + vertex 1.2412 2.13159 2.50261 + vertex 1.23898 2.12704 2.50446 + endloop + endfacet + facet normal 0.188859 0.288762 0.938589 + outer loop + vertex 1.24346 2.12749 2.50342 + vertex 1.2467 2.12987 2.50203 + vertex 1.2412 2.13159 2.50261 + endloop + endfacet + facet normal 0.18591 0.292442 0.938038 + outer loop + vertex 1.24665 2.12602 2.50324 + vertex 1.2467 2.12987 2.50203 + vertex 1.24346 2.12749 2.50342 + endloop + endfacet + facet normal 0.181932 0.292715 0.938732 + outer loop + vertex 1.2467 2.12987 2.50203 + vertex 1.24665 2.12602 2.50324 + vertex 1.2509 2.12641 2.5023 + endloop + endfacet + facet normal 0.18363 0.2947 0.93778 + outer loop + vertex 1.25087 2.13038 2.50106 + vertex 1.2467 2.12987 2.50203 + vertex 1.2509 2.12641 2.5023 + endloop + endfacet + facet normal 0.178248 0.294957 0.938737 + outer loop + vertex 1.25087 2.13038 2.50106 + vertex 1.2509 2.12641 2.5023 + vertex 1.2548 2.12901 2.50074 + endloop + endfacet + facet normal 0.176987 0.29098 0.940216 + outer loop + vertex 1.2548 2.12901 2.50074 + vertex 1.25316 2.13352 2.49965 + vertex 1.25087 2.13038 2.50106 + endloop + endfacet + facet normal 0.180136 0.288724 0.940313 + outer loop + vertex 1.2489 2.13306 2.50061 + vertex 1.25087 2.13038 2.50106 + vertex 1.25316 2.13352 2.49965 + endloop + endfacet + facet normal 0.181273 0.282011 0.94213 + outer loop + vertex 1.2489 2.13306 2.50061 + vertex 1.25316 2.13352 2.49965 + vertex 1.24883 2.13722 2.49938 + endloop + endfacet + facet normal 0.186246 0.281828 0.941215 + outer loop + vertex 1.24501 2.13438 2.50099 + vertex 1.2489 2.13306 2.50061 + vertex 1.24883 2.13722 2.49938 + endloop + endfacet + facet normal 0.18833 0.288648 0.93873 + outer loop + vertex 1.2489 2.13306 2.50061 + vertex 1.24501 2.13438 2.50099 + vertex 1.2467 2.12987 2.50203 + endloop + endfacet + facet normal 0.18307 0.284046 0.941171 + outer loop + vertex 1.24883 2.13722 2.49938 + vertex 1.25316 2.13352 2.49965 + vertex 1.25338 2.13758 2.49839 + endloop + endfacet + facet normal 0.183457 0.28127 0.941929 + outer loop + vertex 1.25338 2.13758 2.49839 + vertex 1.25119 2.14171 2.49758 + vertex 1.24883 2.13722 2.49938 + endloop + endfacet + facet normal 0.184675 0.281836 0.941522 + outer loop + vertex 1.25338 2.13758 2.49839 + vertex 1.25688 2.13969 2.49707 + vertex 1.25119 2.14171 2.49758 + endloop + endfacet + facet normal 0.18179 0.286154 0.940781 + outer loop + vertex 1.25674 2.13565 2.49832 + vertex 1.25688 2.13969 2.49707 + vertex 1.25338 2.13758 2.49839 + endloop + endfacet + facet normal 0.18042 0.286271 0.941009 + outer loop + vertex 1.25688 2.13969 2.49707 + vertex 1.25674 2.13565 2.49832 + vertex 1.26156 2.13567 2.49739 + endloop + endfacet + facet normal 0.18623 0.29279 0.937866 + outer loop + vertex 1.26104 2.13994 2.49616 + vertex 1.25688 2.13969 2.49707 + vertex 1.26156 2.13567 2.49739 + endloop + endfacet + facet normal 0.187414 0.292858 0.937609 + outer loop + vertex 1.26104 2.13994 2.49616 + vertex 1.26156 2.13567 2.49739 + vertex 1.26409 2.13871 2.49594 + endloop + endfacet + facet normal 0.195728 0.314995 0.928692 + outer loop + vertex 1.26409 2.13871 2.49594 + vertex 1.26346 2.1428 2.49468 + vertex 1.26104 2.13994 2.49616 + endloop + endfacet + facet normal 0.184785 0.294978 0.937466 + outer loop + vertex 1.26605 2.13598 2.49641 + vertex 1.26409 2.13871 2.49594 + vertex 1.26156 2.13567 2.49739 + endloop + endfacet + facet normal 0.184826 0.29467 0.937555 + outer loop + vertex 1.26605 2.13598 2.49641 + vertex 1.26156 2.13567 2.49739 + vertex 1.26624 2.13196 2.49764 + endloop + endfacet + facet normal 0.186715 0.294647 0.937188 + outer loop + vertex 1.26605 2.13598 2.49641 + vertex 1.26624 2.13196 2.49764 + vertex 1.27002 2.13458 2.49606 + endloop + endfacet + facet normal 0.184527 0.297523 0.936712 + outer loop + vertex 1.27173 2.13006 2.49716 + vertex 1.27002 2.13458 2.49606 + vertex 1.26624 2.13196 2.49764 + endloop + endfacet + facet normal 0.183984 0.295787 0.937369 + outer loop + vertex 1.26822 2.12796 2.49851 + vertex 1.27173 2.13006 2.49716 + vertex 1.26624 2.13196 2.49764 + endloop + endfacet + facet normal 0.181252 0.294629 0.938265 + outer loop + vertex 1.26822 2.12796 2.49851 + vertex 1.26624 2.13196 2.49764 + vertex 1.26341 2.12792 2.49945 + endloop + endfacet + facet normal 0.181305 0.293843 0.938502 + outer loop + vertex 1.26341 2.12792 2.49945 + vertex 1.2681 2.12394 2.49979 + vertex 1.26822 2.12796 2.49851 + endloop + endfacet + facet normal 0.181525 0.293824 0.938465 + outer loop + vertex 1.2681 2.12394 2.49979 + vertex 1.27159 2.12606 2.49845 + vertex 1.26822 2.12796 2.49851 + endloop + endfacet + facet normal 0.182194 0.292833 0.938645 + outer loop + vertex 1.27381 2.12198 2.49929 + vertex 1.27159 2.12606 2.49845 + vertex 1.2681 2.12394 2.49979 + endloop + endfacet + facet normal 0.180226 0.286492 0.940979 + outer loop + vertex 1.2681 2.12394 2.49979 + vertex 1.2699 2.11928 2.50087 + vertex 1.27381 2.12198 2.49929 + endloop + endfacet + facet normal 0.180689 0.285879 0.941076 + outer loop + vertex 1.2699 2.11928 2.50087 + vertex 1.274 2.11776 2.50054 + vertex 1.27381 2.12198 2.49929 + endloop + endfacet + facet normal 0.178454 0.285906 0.941495 + outer loop + vertex 1.274 2.11776 2.50054 + vertex 1.27865 2.11797 2.4996 + vertex 1.27381 2.12198 2.49929 + endloop + endfacet + facet normal 0.180173 0.287905 0.940557 + outer loop + vertex 1.27381 2.12198 2.49929 + vertex 1.27865 2.11797 2.4996 + vertex 1.27836 2.12238 2.4983 + endloop + endfacet + facet normal 0.179165 0.294722 0.938637 + outer loop + vertex 1.27836 2.12238 2.4983 + vertex 1.27612 2.12641 2.49746 + vertex 1.27381 2.12198 2.49929 + endloop + endfacet + facet normal 0.178756 0.294524 0.938777 + outer loop + vertex 1.27836 2.12238 2.4983 + vertex 1.28169 2.12462 2.49696 + vertex 1.27612 2.12641 2.49746 + endloop + endfacet + facet normal 0.179916 0.298565 0.937278 + outer loop + vertex 1.28169 2.12462 2.49696 + vertex 1.2799 2.12914 2.49587 + vertex 1.27612 2.12641 2.49746 + endloop + endfacet + facet normal 0.179735 0.298793 0.93724 + outer loop + vertex 1.27597 2.13049 2.49619 + vertex 1.27612 2.12641 2.49746 + vertex 1.2799 2.12914 2.49587 + endloop + endfacet + facet normal 0.183375 0.29872 0.936557 + outer loop + vertex 1.27597 2.13049 2.49619 + vertex 1.27173 2.13006 2.49716 + vertex 1.27612 2.12641 2.49746 + endloop + endfacet + facet normal 0.181899 0.297018 0.937386 + outer loop + vertex 1.27173 2.13006 2.49716 + vertex 1.27159 2.12606 2.49845 + vertex 1.27612 2.12641 2.49746 + endloop + endfacet + facet normal 0.183255 0.299444 0.93635 + outer loop + vertex 1.27597 2.13049 2.49619 + vertex 1.27397 2.1332 2.49572 + vertex 1.27173 2.13006 2.49716 + endloop + endfacet + facet normal 0.179474 0.293558 0.938943 + outer loop + vertex 1.28164 2.12075 2.49818 + vertex 1.28169 2.12462 2.49696 + vertex 1.27836 2.12238 2.4983 + endloop + endfacet + facet normal 0.178025 0.293656 0.939188 + outer loop + vertex 1.28169 2.12462 2.49696 + vertex 1.28164 2.12075 2.49818 + vertex 1.28626 2.12072 2.49732 + endloop + endfacet + facet normal 0.177967 0.293591 0.939219 + outer loop + vertex 1.28585 2.12498 2.49607 + vertex 1.28169 2.12462 2.49696 + vertex 1.28626 2.12072 2.49732 + endloop + endfacet + facet normal 0.174978 0.29348 0.939815 + outer loop + vertex 1.28585 2.12498 2.49607 + vertex 1.28626 2.12072 2.49732 + vertex 1.28896 2.12371 2.49588 + endloop + endfacet + facet normal 0.176454 0.297317 0.938332 + outer loop + vertex 1.28896 2.12371 2.49588 + vertex 1.28848 2.12801 2.49461 + vertex 1.28585 2.12498 2.49607 + endloop + endfacet + facet normal 0.175102 0.297248 0.938607 + outer loop + vertex 1.28896 2.12371 2.49588 + vertex 1.2932 2.12404 2.49499 + vertex 1.28848 2.12801 2.49461 + endloop + endfacet + facet normal 0.174914 0.297034 0.93871 + outer loop + vertex 1.28848 2.12801 2.49461 + vertex 1.2932 2.12404 2.49499 + vertex 1.29334 2.12802 2.4937 + endloop + endfacet + facet normal 0.173262 0.297176 0.938971 + outer loop + vertex 1.2932 2.12404 2.49499 + vertex 1.29671 2.12616 2.49367 + vertex 1.29334 2.12802 2.4937 + endloop + endfacet + facet normal 0.174495 0.299424 0.938028 + outer loop + vertex 1.29671 2.12616 2.49367 + vertex 1.29686 2.13011 2.49238 + vertex 1.29334 2.12802 2.4937 + endloop + endfacet + facet normal 0.174504 0.299411 0.938031 + outer loop + vertex 1.29334 2.12802 2.4937 + vertex 1.29686 2.13011 2.49238 + vertex 1.29129 2.13202 2.49281 + endloop + endfacet + facet normal 0.172358 0.299616 0.938362 + outer loop + vertex 1.29686 2.13011 2.49238 + vertex 1.29671 2.12616 2.49367 + vertex 1.30122 2.12659 2.4927 + endloop + endfacet + facet normal 0.173287 0.300719 0.937838 + outer loop + vertex 1.30112 2.13058 2.49144 + vertex 1.29686 2.13011 2.49238 + vertex 1.30122 2.12659 2.4927 + endloop + endfacet + facet normal 0.169794 0.300822 0.938444 + outer loop + vertex 1.30112 2.13058 2.49144 + vertex 1.30122 2.12659 2.4927 + vertex 1.30503 2.12941 2.49111 + endloop + endfacet + facet normal 0.170778 0.299608 0.938653 + outer loop + vertex 1.30671 2.12503 2.4922 + vertex 1.30503 2.12941 2.49111 + vertex 1.30122 2.12659 2.4927 + endloop + endfacet + facet normal 0.169784 0.29566 0.940084 + outer loop + vertex 1.30327 2.12274 2.49354 + vertex 1.30671 2.12503 2.4922 + vertex 1.30122 2.12659 2.4927 + endloop + endfacet + facet normal 0.171157 0.296293 0.939636 + outer loop + vertex 1.30327 2.12274 2.49354 + vertex 1.30122 2.12659 2.4927 + vertex 1.29879 2.12225 2.49451 + endloop + endfacet + facet normal 0.172113 0.290617 0.941233 + outer loop + vertex 1.29879 2.12225 2.49451 + vertex 1.30314 2.11872 2.49481 + vertex 1.30327 2.12274 2.49354 + endloop + endfacet + facet normal 0.170105 0.290782 0.941547 + outer loop + vertex 1.30314 2.11872 2.49481 + vertex 1.30657 2.12102 2.49348 + vertex 1.30327 2.12274 2.49354 + endloop + endfacet + facet normal 0.171822 0.290272 0.941392 + outer loop + vertex 1.29891 2.11818 2.49575 + vertex 1.30314 2.11872 2.49481 + vertex 1.29879 2.12225 2.49451 + endloop + endfacet + facet normal 0.174131 0.290219 0.940984 + outer loop + vertex 1.29497 2.11946 2.49608 + vertex 1.29891 2.11818 2.49575 + vertex 1.29879 2.12225 2.49451 + endloop + endfacet + facet normal 0.173021 0.291611 0.940758 + outer loop + vertex 1.2932 2.12404 2.49499 + vertex 1.29497 2.11946 2.49608 + vertex 1.29879 2.12225 2.49451 + endloop + endfacet + facet normal 0.176017 0.29257 0.939905 + outer loop + vertex 1.29497 2.11946 2.49608 + vertex 1.2932 2.12404 2.49499 + vertex 1.29093 2.12089 2.49639 + endloop + endfacet + facet normal 0.174308 0.28728 0.941853 + outer loop + vertex 1.29093 2.12089 2.49639 + vertex 1.29112 2.11667 2.49764 + vertex 1.29497 2.11946 2.49608 + endloop + endfacet + facet normal 0.174634 0.286867 0.941918 + outer loop + vertex 1.29671 2.11497 2.49712 + vertex 1.29497 2.11946 2.49608 + vertex 1.29112 2.11667 2.49764 + endloop + endfacet + facet normal 0.176267 0.287262 0.941494 + outer loop + vertex 1.29093 2.12089 2.49639 + vertex 1.28626 2.12072 2.49732 + vertex 1.29112 2.11667 2.49764 + endloop + endfacet + facet normal 0.175819 0.286744 0.941735 + outer loop + vertex 1.28626 2.12072 2.49732 + vertex 1.28655 2.11628 2.49862 + vertex 1.29112 2.11667 2.49764 + endloop + endfacet + facet normal 0.179215 0.286775 0.941086 + outer loop + vertex 1.28655 2.11628 2.49862 + vertex 1.28626 2.12072 2.49732 + vertex 1.28326 2.11796 2.49873 + endloop + endfacet + facet normal 0.172984 0.286334 0.942385 + outer loop + vertex 1.29891 2.11818 2.49575 + vertex 1.29497 2.11946 2.49608 + vertex 1.29671 2.11497 2.49712 + endloop + endfacet + facet normal 0.17235 0.286763 0.942371 + outer loop + vertex 1.30091 2.11552 2.49619 + vertex 1.29891 2.11818 2.49575 + vertex 1.29671 2.11497 2.49712 + endloop + endfacet + facet normal 0.172304 0.287002 0.942306 + outer loop + vertex 1.30091 2.11552 2.49619 + vertex 1.29671 2.11497 2.49712 + vertex 1.30095 2.1115 2.49741 + endloop + endfacet + facet normal 0.170906 0.287059 0.942543 + outer loop + vertex 1.30091 2.11552 2.49619 + vertex 1.30095 2.1115 2.49741 + vertex 1.30486 2.11418 2.49588 + endloop + endfacet + facet normal 0.171125 0.287761 0.94229 + outer loop + vertex 1.30486 2.11418 2.49588 + vertex 1.30314 2.11872 2.49481 + vertex 1.30091 2.11552 2.49619 + endloop + endfacet + facet normal 0.16824 0.290607 0.941936 + outer loop + vertex 1.30657 2.10948 2.49702 + vertex 1.30486 2.11418 2.49588 + vertex 1.30095 2.1115 2.49741 + endloop + endfacet + facet normal 0.168191 0.29046 0.94199 + outer loop + vertex 1.30253 2.1069 2.49854 + vertex 1.30657 2.10948 2.49702 + vertex 1.30095 2.1115 2.49741 + endloop + endfacet + facet normal 0.166483 0.289986 0.942439 + outer loop + vertex 1.30253 2.1069 2.49854 + vertex 1.30095 2.1115 2.49741 + vertex 1.29847 2.10836 2.49881 + endloop + endfacet + facet normal 0.167108 0.291842 0.941755 + outer loop + vertex 1.29847 2.1043 2.50007 + vertex 1.30253 2.1069 2.49854 + vertex 1.29847 2.10836 2.49881 + endloop + endfacet + facet normal 0.169815 0.291706 0.941313 + outer loop + vertex 1.29376 2.10811 2.49974 + vertex 1.29847 2.1043 2.50007 + vertex 1.29847 2.10836 2.49881 + endloop + endfacet + facet normal 0.170235 0.287926 0.9424 + outer loop + vertex 1.29847 2.10836 2.49881 + vertex 1.29666 2.11107 2.49831 + vertex 1.29376 2.10811 2.49974 + endloop + endfacet + facet normal 0.173441 0.284946 0.942722 + outer loop + vertex 1.29376 2.10811 2.49974 + vertex 1.29666 2.11107 2.49831 + vertex 1.29343 2.11255 2.49846 + endloop + endfacet + facet normal 0.173957 0.284956 0.942624 + outer loop + vertex 1.28887 2.1121 2.49944 + vertex 1.29376 2.10811 2.49974 + vertex 1.29343 2.11255 2.49846 + endloop + endfacet + facet normal 0.174149 0.28373 0.942958 + outer loop + vertex 1.29343 2.11255 2.49846 + vertex 1.29112 2.11667 2.49764 + vertex 1.28887 2.1121 2.49944 + endloop + endfacet + facet normal 0.17642 0.282581 0.942881 + outer loop + vertex 1.28887 2.1121 2.49944 + vertex 1.29112 2.11667 2.49764 + vertex 1.28655 2.11628 2.49862 + endloop + endfacet + facet normal 0.176062 0.282406 0.943 + outer loop + vertex 1.28887 2.1121 2.49944 + vertex 1.28655 2.11628 2.49862 + vertex 1.28317 2.11405 2.49991 + endloop + endfacet + facet normal 0.174972 0.278927 0.944238 + outer loop + vertex 1.28317 2.11405 2.49991 + vertex 1.28496 2.10938 2.50096 + vertex 1.28887 2.1121 2.49944 + endloop + endfacet + facet normal 0.173027 0.281495 0.943834 + outer loop + vertex 1.28496 2.10938 2.50096 + vertex 1.28906 2.10785 2.50067 + vertex 1.28887 2.1121 2.49944 + endloop + endfacet + facet normal 0.173222 0.282051 0.943632 + outer loop + vertex 1.28906 2.10785 2.50067 + vertex 1.28496 2.10938 2.50096 + vertex 1.28678 2.10471 2.50202 + endloop + endfacet + facet normal 0.170168 0.28423 0.943534 + outer loop + vertex 1.29101 2.10503 2.50116 + vertex 1.28906 2.10785 2.50067 + vertex 1.28678 2.10471 2.50202 + endloop + endfacet + facet normal 0.169567 0.288754 0.942267 + outer loop + vertex 1.29101 2.10503 2.50116 + vertex 1.28678 2.10471 2.50202 + vertex 1.29137 2.10081 2.50239 + endloop + endfacet + facet normal 0.167845 0.288703 0.942591 + outer loop + vertex 1.29101 2.10503 2.50116 + vertex 1.29137 2.10081 2.50239 + vertex 1.29414 2.10383 2.50098 + endloop + endfacet + facet normal 0.167378 0.287414 0.943068 + outer loop + vertex 1.29414 2.10383 2.50098 + vertex 1.29376 2.10811 2.49974 + vertex 1.29101 2.10503 2.50116 + endloop + endfacet + facet normal 0.164893 0.291283 0.942319 + outer loop + vertex 1.29608 2.10107 2.50149 + vertex 1.29414 2.10383 2.50098 + vertex 1.29137 2.10081 2.50239 + endloop + endfacet + facet normal 0.164807 0.292064 0.942092 + outer loop + vertex 1.29608 2.10107 2.50149 + vertex 1.29137 2.10081 2.50239 + vertex 1.2962 2.09688 2.50277 + endloop + endfacet + facet normal 0.162201 0.29212 0.942527 + outer loop + vertex 1.29608 2.10107 2.50149 + vertex 1.2962 2.09688 2.50277 + vertex 1.30016 2.09967 2.50122 + endloop + endfacet + facet normal 0.162683 0.293635 0.941973 + outer loop + vertex 1.30016 2.09967 2.50122 + vertex 1.29847 2.1043 2.50007 + vertex 1.29608 2.10107 2.50149 + endloop + endfacet + facet normal 0.162837 0.289738 0.943152 + outer loop + vertex 1.29137 2.10081 2.50239 + vertex 1.29162 2.0964 2.5037 + vertex 1.2962 2.09688 2.50277 + endloop + endfacet + facet normal 0.162945 0.289068 0.943339 + outer loop + vertex 1.29383 2.09238 2.50456 + vertex 1.2962 2.09688 2.50277 + vertex 1.29162 2.0964 2.5037 + endloop + endfacet + facet normal 0.164631 0.289878 0.942798 + outer loop + vertex 1.29383 2.09238 2.50456 + vertex 1.29162 2.0964 2.5037 + vertex 1.28823 2.09413 2.50499 + endloop + endfacet + facet normal 0.164142 0.288164 0.943408 + outer loop + vertex 1.28823 2.09413 2.50499 + vertex 1.29 2.08955 2.50608 + vertex 1.29383 2.09238 2.50456 + endloop + endfacet + facet normal 0.165524 0.286445 0.94369 + outer loop + vertex 1.29 2.08955 2.50608 + vertex 1.29396 2.08824 2.50579 + vertex 1.29383 2.09238 2.50456 + endloop + endfacet + facet normal 0.164491 0.286463 0.943865 + outer loop + vertex 1.29396 2.08824 2.50579 + vertex 1.29821 2.08878 2.50488 + vertex 1.29383 2.09238 2.50456 + endloop + endfacet + facet normal 0.162737 0.284414 0.944788 + outer loop + vertex 1.29383 2.09238 2.50456 + vertex 1.29821 2.08878 2.50488 + vertex 1.29837 2.09286 2.50363 + endloop + endfacet + facet normal 0.161185 0.284544 0.945015 + outer loop + vertex 1.29821 2.08878 2.50488 + vertex 1.30168 2.09111 2.50359 + vertex 1.29837 2.09286 2.50363 + endloop + endfacet + facet normal 0.162239 0.286558 0.944226 + outer loop + vertex 1.30168 2.09111 2.50359 + vertex 1.30185 2.09517 2.50233 + vertex 1.29837 2.09286 2.50363 + endloop + endfacet + facet normal 0.160478 0.28896 0.943795 + outer loop + vertex 1.29837 2.09286 2.50363 + vertex 1.30185 2.09517 2.50233 + vertex 1.2962 2.09688 2.50277 + endloop + endfacet + facet normal 0.16157 0.292934 0.942383 + outer loop + vertex 1.30185 2.09517 2.50233 + vertex 1.30016 2.09967 2.50122 + vertex 1.2962 2.09688 2.50277 + endloop + endfacet + facet normal 0.159987 0.292443 0.942805 + outer loop + vertex 1.30413 2.09836 2.50095 + vertex 1.30016 2.09967 2.50122 + vertex 1.30185 2.09517 2.50233 + endloop + endfacet + facet normal 0.158846 0.293237 0.942751 + outer loop + vertex 1.30612 2.09572 2.50144 + vertex 1.30413 2.09836 2.50095 + vertex 1.30185 2.09517 2.50233 + endloop + endfacet + facet normal 0.159931 0.287408 0.944361 + outer loop + vertex 1.30612 2.09572 2.50144 + vertex 1.30185 2.09517 2.50233 + vertex 1.30622 2.09161 2.50267 + endloop + endfacet + facet normal 0.157731 0.287463 0.944715 + outer loop + vertex 1.30612 2.09572 2.50144 + vertex 1.30622 2.09161 2.50267 + vertex 1.31004 2.09452 2.50115 + endloop + endfacet + facet normal 0.159819 0.294922 0.942061 + outer loop + vertex 1.31004 2.09452 2.50115 + vertex 1.30834 2.09892 2.50006 + vertex 1.30612 2.09572 2.50144 + endloop + endfacet + facet normal 0.158227 0.294412 0.942489 + outer loop + vertex 1.30834 2.09892 2.50006 + vertex 1.31004 2.09452 2.50115 + vertex 1.31385 2.09748 2.49958 + endloop + endfacet + facet normal 0.159553 0.300171 0.940447 + outer loop + vertex 1.31385 2.09748 2.49958 + vertex 1.31161 2.10136 2.49873 + vertex 1.30834 2.09892 2.50006 + endloop + endfacet + facet normal 0.159892 0.299756 0.940521 + outer loop + vertex 1.30834 2.09892 2.50006 + vertex 1.31161 2.10136 2.49873 + vertex 1.30841 2.10273 2.49884 + endloop + endfacet + facet normal 0.162429 0.299588 0.94014 + outer loop + vertex 1.30411 2.10232 2.49971 + vertex 1.30834 2.09892 2.50006 + vertex 1.30841 2.10273 2.49884 + endloop + endfacet + facet normal 0.162562 0.298718 0.940394 + outer loop + vertex 1.30841 2.10273 2.49884 + vertex 1.30659 2.10542 2.49829 + vertex 1.30411 2.10232 2.49971 + endloop + endfacet + facet normal 0.165582 0.296391 0.940603 + outer loop + vertex 1.30411 2.10232 2.49971 + vertex 1.30659 2.10542 2.49829 + vertex 1.30253 2.1069 2.49854 + endloop + endfacet + facet normal 0.162586 0.298733 0.940385 + outer loop + vertex 1.30841 2.10273 2.49884 + vertex 1.31128 2.10571 2.49739 + vertex 1.30659 2.10542 2.49829 + endloop + endfacet + facet normal 0.163031 0.294962 0.941498 + outer loop + vertex 1.30657 2.10948 2.49702 + vertex 1.30659 2.10542 2.49829 + vertex 1.31128 2.10571 2.49739 + endloop + endfacet + facet normal 0.166162 0.298698 0.939771 + outer loop + vertex 1.3109 2.10993 2.49612 + vertex 1.30657 2.10948 2.49702 + vertex 1.31128 2.10571 2.49739 + endloop + endfacet + facet normal 0.164142 0.298627 0.940148 + outer loop + vertex 1.3109 2.10993 2.49612 + vertex 1.31128 2.10571 2.49739 + vertex 1.31403 2.10879 2.49593 + endloop + endfacet + facet normal 0.162733 0.294498 0.941695 + outer loop + vertex 1.31403 2.10879 2.49593 + vertex 1.31365 2.11305 2.49467 + vertex 1.3109 2.10993 2.49612 + endloop + endfacet + facet normal 0.165705 0.291999 0.941954 + outer loop + vertex 1.30894 2.11273 2.49559 + vertex 1.3109 2.10993 2.49612 + vertex 1.31365 2.11305 2.49467 + endloop + endfacet + facet normal 0.166087 0.288924 0.942835 + outer loop + vertex 1.30894 2.11273 2.49559 + vertex 1.31365 2.11305 2.49467 + vertex 1.30877 2.11697 2.49432 + endloop + endfacet + facet normal 0.168993 0.288885 0.94233 + outer loop + vertex 1.30486 2.11418 2.49588 + vertex 1.30894 2.11273 2.49559 + vertex 1.30877 2.11697 2.49432 + endloop + endfacet + facet normal 0.169705 0.291045 0.941538 + outer loop + vertex 1.30894 2.11273 2.49559 + vertex 1.30486 2.11418 2.49588 + vertex 1.30657 2.10948 2.49702 + endloop + endfacet + facet normal 0.16792 0.291115 0.941836 + outer loop + vertex 1.30877 2.11697 2.49432 + vertex 1.31365 2.11305 2.49467 + vertex 1.31333 2.11747 2.49336 + endloop + endfacet + facet normal 0.168056 0.290308 0.942061 + outer loop + vertex 1.31333 2.11747 2.49336 + vertex 1.3111 2.12149 2.49252 + vertex 1.30877 2.11697 2.49432 + endloop + endfacet + facet normal 0.169813 0.289392 0.942028 + outer loop + vertex 1.30877 2.11697 2.49432 + vertex 1.3111 2.12149 2.49252 + vertex 1.30657 2.12102 2.49348 + endloop + endfacet + facet normal 0.170789 0.289856 0.941708 + outer loop + vertex 1.30877 2.11697 2.49432 + vertex 1.30657 2.12102 2.49348 + vertex 1.30314 2.11872 2.49481 + endloop + endfacet + facet normal 0.170115 0.287444 0.942569 + outer loop + vertex 1.30314 2.11872 2.49481 + vertex 1.30486 2.11418 2.49588 + vertex 1.30877 2.11697 2.49432 + endloop + endfacet + facet normal 0.166719 0.289658 0.942498 + outer loop + vertex 1.31333 2.11747 2.49336 + vertex 1.31662 2.11989 2.49203 + vertex 1.3111 2.12149 2.49252 + endloop + endfacet + facet normal 0.167355 0.292115 0.941627 + outer loop + vertex 1.31662 2.11989 2.49203 + vertex 1.31491 2.12434 2.49095 + vertex 1.3111 2.12149 2.49252 + endloop + endfacet + facet normal 0.166605 0.293033 0.941475 + outer loop + vertex 1.31096 2.1256 2.49126 + vertex 1.3111 2.12149 2.49252 + vertex 1.31491 2.12434 2.49095 + endloop + endfacet + facet normal 0.167845 0.297329 0.939906 + outer loop + vertex 1.31491 2.12434 2.49095 + vertex 1.31323 2.12878 2.48985 + vertex 1.31096 2.1256 2.49126 + endloop + endfacet + facet normal 0.164662 0.296342 0.94078 + outer loop + vertex 1.31323 2.12878 2.48985 + vertex 1.31491 2.12434 2.49095 + vertex 1.31878 2.12715 2.48939 + endloop + endfacet + facet normal 0.166278 0.294313 0.941133 + outer loop + vertex 1.31491 2.12434 2.49095 + vertex 1.31885 2.12309 2.49065 + vertex 1.31878 2.12715 2.48939 + endloop + endfacet + facet normal 0.164776 0.294363 0.941381 + outer loop + vertex 1.31885 2.12309 2.49065 + vertex 1.32311 2.12365 2.48973 + vertex 1.31878 2.12715 2.48939 + endloop + endfacet + facet normal 0.164562 0.29411 0.941498 + outer loop + vertex 1.31878 2.12715 2.48939 + vertex 1.32311 2.12365 2.48973 + vertex 1.32329 2.12762 2.48846 + endloop + endfacet + facet normal 0.162873 0.304412 0.938513 + outer loop + vertex 1.32329 2.12762 2.48846 + vertex 1.32115 2.13146 2.48758 + vertex 1.31878 2.12715 2.48939 + endloop + endfacet + facet normal 0.1638 0.304862 0.938205 + outer loop + vertex 1.32329 2.12762 2.48846 + vertex 1.32664 2.12984 2.48715 + vertex 1.32115 2.13146 2.48758 + endloop + endfacet + facet normal 0.170095 0.328697 0.928992 + outer loop + vertex 1.32664 2.12984 2.48715 + vertex 1.32466 2.13406 2.48602 + vertex 1.32115 2.13146 2.48758 + endloop + endfacet + facet normal 0.163697 0.29419 0.941624 + outer loop + vertex 1.32311 2.12365 2.48973 + vertex 1.32657 2.12594 2.48841 + vertex 1.32329 2.12762 2.48846 + endloop + endfacet + facet normal 0.166954 0.300595 0.939026 + outer loop + vertex 1.32657 2.12594 2.48841 + vertex 1.32664 2.12984 2.48715 + vertex 1.32329 2.12762 2.48846 + endloop + endfacet + facet normal 0.16418 0.293531 0.941745 + outer loop + vertex 1.32862 2.12206 2.48927 + vertex 1.32657 2.12594 2.48841 + vertex 1.32311 2.12365 2.48973 + endloop + endfacet + facet normal 0.164803 0.293817 0.941548 + outer loop + vertex 1.32862 2.12206 2.48927 + vertex 1.33104 2.12644 2.48747 + vertex 1.32657 2.12594 2.48841 + endloop + endfacet + facet normal 0.163596 0.300818 0.939545 + outer loop + vertex 1.32664 2.12984 2.48715 + vertex 1.32657 2.12594 2.48841 + vertex 1.33104 2.12644 2.48747 + endloop + endfacet + facet normal 0.165295 0.291635 0.942139 + outer loop + vertex 1.31885 2.12309 2.49065 + vertex 1.32083 2.12044 2.49112 + vertex 1.32311 2.12365 2.48973 + endloop + endfacet + facet normal 0.164363 0.292281 0.942102 + outer loop + vertex 1.32474 2.1192 2.49083 + vertex 1.32311 2.12365 2.48973 + vertex 1.32083 2.12044 2.49112 + endloop + endfacet + facet normal 0.164303 0.292075 0.942177 + outer loop + vertex 1.32083 2.12044 2.49112 + vertex 1.32083 2.11647 2.49235 + vertex 1.32474 2.1192 2.49083 + endloop + endfacet + facet normal 0.161826 0.295305 0.941598 + outer loop + vertex 1.32635 2.11466 2.49197 + vertex 1.32474 2.1192 2.49083 + vertex 1.32083 2.11647 2.49235 + endloop + endfacet + facet normal 0.1618 0.295218 0.94163 + outer loop + vertex 1.32226 2.112 2.49351 + vertex 1.32635 2.11466 2.49197 + vertex 1.32083 2.11647 2.49235 + endloop + endfacet + facet normal 0.160514 0.29489 0.941953 + outer loop + vertex 1.32226 2.112 2.49351 + vertex 1.32083 2.11647 2.49235 + vertex 1.31833 2.11333 2.49376 + endloop + endfacet + facet normal 0.161332 0.297474 0.941 + outer loop + vertex 1.31825 2.1094 2.49502 + vertex 1.32226 2.112 2.49351 + vertex 1.31833 2.11333 2.49376 + endloop + endfacet + facet normal 0.163898 0.297294 0.940614 + outer loop + vertex 1.31365 2.11305 2.49467 + vertex 1.31825 2.1094 2.49502 + vertex 1.31833 2.11333 2.49376 + endloop + endfacet + facet normal 0.164332 0.293608 0.941695 + outer loop + vertex 1.31833 2.11333 2.49376 + vertex 1.31656 2.116 2.49324 + vertex 1.31365 2.11305 2.49467 + endloop + endfacet + facet normal 0.158993 0.300717 0.940367 + outer loop + vertex 1.32337 2.10786 2.49465 + vertex 1.32226 2.112 2.49351 + vertex 1.31825 2.1094 2.49502 + endloop + endfacet + facet normal 0.159207 0.301497 0.940081 + outer loop + vertex 1.31825 2.1094 2.49502 + vertex 1.31997 2.10498 2.49615 + vertex 1.32337 2.10786 2.49465 + endloop + endfacet + facet normal 0.157478 0.303376 0.939768 + outer loop + vertex 1.31997 2.10498 2.49615 + vertex 1.32475 2.10373 2.49575 + vertex 1.32337 2.10786 2.49465 + endloop + endfacet + facet normal 0.156965 0.30324 0.939898 + outer loop + vertex 1.32337 2.10786 2.49465 + vertex 1.32475 2.10373 2.49575 + vertex 1.32865 2.10663 2.49416 + endloop + endfacet + facet normal 0.156968 0.303251 0.939894 + outer loop + vertex 1.32865 2.10663 2.49416 + vertex 1.32631 2.11047 2.49331 + vertex 1.32337 2.10786 2.49465 + endloop + endfacet + facet normal 0.156587 0.303048 0.940023 + outer loop + vertex 1.32865 2.10663 2.49416 + vertex 1.33088 2.11121 2.49231 + vertex 1.32631 2.11047 2.49331 + endloop + endfacet + facet normal 0.157392 0.299421 0.94105 + outer loop + vertex 1.32635 2.11466 2.49197 + vertex 1.32631 2.11047 2.49331 + vertex 1.33088 2.11121 2.49231 + endloop + endfacet + facet normal 0.159365 0.301905 0.939923 + outer loop + vertex 1.3307 2.11532 2.49102 + vertex 1.32635 2.11466 2.49197 + vertex 1.33088 2.11121 2.49231 + endloop + endfacet + facet normal 0.156822 0.301925 0.940345 + outer loop + vertex 1.3307 2.11532 2.49102 + vertex 1.33088 2.11121 2.49231 + vertex 1.33468 2.11415 2.49074 + endloop + endfacet + facet normal 0.156142 0.299393 0.941267 + outer loop + vertex 1.33468 2.11415 2.49074 + vertex 1.33296 2.11858 2.48961 + vertex 1.3307 2.11532 2.49102 + endloop + endfacet + facet normal 0.15943 0.297179 0.941417 + outer loop + vertex 1.32867 2.11797 2.49053 + vertex 1.3307 2.11532 2.49102 + vertex 1.33296 2.11858 2.48961 + endloop + endfacet + facet normal 0.160141 0.293668 0.942398 + outer loop + vertex 1.32867 2.11797 2.49053 + vertex 1.33296 2.11858 2.48961 + vertex 1.32862 2.12206 2.48927 + endloop + endfacet + facet normal 0.162632 0.29358 0.941999 + outer loop + vertex 1.32474 2.1192 2.49083 + vertex 1.32867 2.11797 2.49053 + vertex 1.32862 2.12206 2.48927 + endloop + endfacet + facet normal 0.16187 0.295733 0.941456 + outer loop + vertex 1.32862 2.12206 2.48927 + vertex 1.33296 2.11858 2.48961 + vertex 1.33313 2.12258 2.48832 + endloop + endfacet + facet normal 0.161927 0.295407 0.941549 + outer loop + vertex 1.33313 2.12258 2.48832 + vertex 1.33104 2.12644 2.48747 + vertex 1.32862 2.12206 2.48927 + endloop + endfacet + facet normal 0.16097 0.294954 0.941855 + outer loop + vertex 1.33313 2.12258 2.48832 + vertex 1.33657 2.12487 2.48702 + vertex 1.33104 2.12644 2.48747 + endloop + endfacet + facet normal 0.160019 0.296242 0.941613 + outer loop + vertex 1.33643 2.1209 2.48829 + vertex 1.33657 2.12487 2.48702 + vertex 1.33313 2.12258 2.48832 + endloop + endfacet + facet normal 0.159852 0.295913 0.941745 + outer loop + vertex 1.33296 2.11858 2.48961 + vertex 1.33643 2.1209 2.48829 + vertex 1.33313 2.12258 2.48832 + endloop + endfacet + facet normal 0.157221 0.299466 0.941064 + outer loop + vertex 1.33851 2.11701 2.48918 + vertex 1.33643 2.1209 2.48829 + vertex 1.33296 2.11858 2.48961 + endloop + endfacet + facet normal 0.157202 0.299457 0.94107 + outer loop + vertex 1.33851 2.11701 2.48918 + vertex 1.34095 2.12139 2.48738 + vertex 1.33643 2.1209 2.48829 + endloop + endfacet + facet normal 0.15669 0.299739 0.941066 + outer loop + vertex 1.34303 2.11751 2.48827 + vertex 1.34095 2.12139 2.48738 + vertex 1.33851 2.11701 2.48918 + endloop + endfacet + facet normal 0.155771 0.30511 0.939491 + outer loop + vertex 1.33851 2.11701 2.48918 + vertex 1.34291 2.11353 2.48958 + vertex 1.34303 2.11751 2.48827 + endloop + endfacet + facet normal 0.155827 0.305106 0.939483 + outer loop + vertex 1.34291 2.11353 2.48958 + vertex 1.34633 2.11583 2.48827 + vertex 1.34303 2.11751 2.48827 + endloop + endfacet + facet normal 0.155113 0.303697 0.940057 + outer loop + vertex 1.34633 2.11583 2.48827 + vertex 1.34645 2.11979 2.48697 + vertex 1.34303 2.11751 2.48827 + endloop + endfacet + facet normal 0.155698 0.303652 0.939975 + outer loop + vertex 1.34645 2.11979 2.48697 + vertex 1.34633 2.11583 2.48827 + vertex 1.35082 2.11634 2.48736 + endloop + endfacet + facet normal 0.156477 0.30459 0.939542 + outer loop + vertex 1.35066 2.12036 2.48608 + vertex 1.34645 2.11979 2.48697 + vertex 1.35082 2.11634 2.48736 + endloop + endfacet + facet normal 0.153384 0.304621 0.940042 + outer loop + vertex 1.35066 2.12036 2.48608 + vertex 1.35082 2.11634 2.48736 + vertex 1.35461 2.11918 2.48582 + endloop + endfacet + facet normal 0.150075 0.308633 0.939267 + outer loop + vertex 1.3564 2.11478 2.48698 + vertex 1.35461 2.11918 2.48582 + vertex 1.35082 2.11634 2.48736 + endloop + endfacet + facet normal 0.149856 0.30778 0.939582 + outer loop + vertex 1.35298 2.1125 2.48827 + vertex 1.3564 2.11478 2.48698 + vertex 1.35082 2.11634 2.48736 + endloop + endfacet + facet normal 0.153127 0.309368 0.938533 + outer loop + vertex 1.35298 2.1125 2.48827 + vertex 1.35082 2.11634 2.48736 + vertex 1.34847 2.11197 2.48918 + endloop + endfacet + facet normal 0.152401 0.31346 0.937292 + outer loop + vertex 1.34847 2.11197 2.48918 + vertex 1.35292 2.10853 2.48961 + vertex 1.35298 2.1125 2.48827 + endloop + endfacet + facet normal 0.146376 0.313834 0.938127 + outer loop + vertex 1.35292 2.10853 2.48961 + vertex 1.35634 2.11083 2.48831 + vertex 1.35298 2.1125 2.48827 + endloop + endfacet + facet normal 0.142177 0.319378 0.936901 + outer loop + vertex 1.35851 2.10702 2.48928 + vertex 1.35634 2.11083 2.48831 + vertex 1.35292 2.10853 2.48961 + endloop + endfacet + facet normal 0.140099 0.311038 0.940015 + outer loop + vertex 1.35292 2.10853 2.48961 + vertex 1.35468 2.10414 2.4908 + vertex 1.35851 2.10702 2.48928 + endloop + endfacet + facet normal 0.137732 0.313874 0.939422 + outer loop + vertex 1.35468 2.10414 2.4908 + vertex 1.35863 2.10301 2.4906 + vertex 1.35851 2.10702 2.48928 + endloop + endfacet + facet normal 0.124301 0.314044 0.941236 + outer loop + vertex 1.35863 2.10301 2.4906 + vertex 1.36286 2.10377 2.48979 + vertex 1.35851 2.10702 2.48928 + endloop + endfacet + facet normal 0.127302 0.317806 0.939571 + outer loop + vertex 1.35851 2.10702 2.48928 + vertex 1.36286 2.10377 2.48979 + vertex 1.36305 2.10759 2.48847 + endloop + endfacet + facet normal 0.127016 0.319372 0.939079 + outer loop + vertex 1.36305 2.10759 2.48847 + vertex 1.36091 2.11135 2.48748 + vertex 1.35851 2.10702 2.48928 + endloop + endfacet + facet normal 0.119469 0.315661 0.941321 + outer loop + vertex 1.36305 2.10759 2.48847 + vertex 1.36657 2.10992 2.48724 + vertex 1.36091 2.11135 2.48748 + endloop + endfacet + facet normal 0.121004 0.322144 0.938926 + outer loop + vertex 1.36657 2.10992 2.48724 + vertex 1.36479 2.11422 2.486 + vertex 1.36091 2.11135 2.48748 + endloop + endfacet + facet normal 0.123927 0.318612 0.939749 + outer loop + vertex 1.36071 2.11534 2.48615 + vertex 1.36091 2.11135 2.48748 + vertex 1.36479 2.11422 2.486 + endloop + endfacet + facet normal 0.122324 0.312461 0.942022 + outer loop + vertex 1.36479 2.11422 2.486 + vertex 1.36301 2.11859 2.48478 + vertex 1.36071 2.11534 2.48615 + endloop + endfacet + facet normal 0.11912 0.31137 0.942793 + outer loop + vertex 1.36301 2.11859 2.48478 + vertex 1.36479 2.11422 2.486 + vertex 1.36873 2.11727 2.48449 + endloop + endfacet + facet normal 0.11934 0.312409 0.942422 + outer loop + vertex 1.36873 2.11727 2.48449 + vertex 1.36657 2.12099 2.48353 + vertex 1.36301 2.11859 2.48478 + endloop + endfacet + facet normal 0.114717 0.31648 0.941637 + outer loop + vertex 1.36479 2.11422 2.486 + vertex 1.36887 2.11319 2.48585 + vertex 1.36873 2.11727 2.48449 + endloop + endfacet + facet normal 0.138583 0.318647 0.937688 + outer loop + vertex 1.36071 2.11534 2.48615 + vertex 1.3564 2.11478 2.48698 + vertex 1.36091 2.11135 2.48748 + endloop + endfacet + facet normal 0.134542 0.313654 0.939957 + outer loop + vertex 1.3564 2.11478 2.48698 + vertex 1.35634 2.11083 2.48831 + vertex 1.36091 2.11135 2.48748 + endloop + endfacet + facet normal 0.13965 0.313066 0.939408 + outer loop + vertex 1.36071 2.11534 2.48615 + vertex 1.35862 2.11797 2.48559 + vertex 1.3564 2.11478 2.48698 + endloop + endfacet + facet normal 0.115635 0.320307 0.94023 + outer loop + vertex 1.36887 2.11319 2.48585 + vertex 1.36479 2.11422 2.486 + vertex 1.36657 2.10992 2.48724 + endloop + endfacet + facet normal 0.111936 0.322754 0.939841 + outer loop + vertex 1.37094 2.11071 2.48645 + vertex 1.36887 2.11319 2.48585 + vertex 1.36657 2.10992 2.48724 + endloop + endfacet + facet normal 0.111822 0.323233 0.93969 + outer loop + vertex 1.37094 2.11071 2.48645 + vertex 1.36657 2.10992 2.48724 + vertex 1.37098 2.1067 2.48782 + endloop + endfacet + facet normal 0.109479 0.323297 0.939943 + outer loop + vertex 1.37094 2.11071 2.48645 + vertex 1.37098 2.1067 2.48782 + vertex 1.37494 2.10991 2.48626 + endloop + endfacet + facet normal 0.106683 0.326387 0.939197 + outer loop + vertex 1.37644 2.10594 2.48747 + vertex 1.37494 2.10991 2.48626 + vertex 1.37098 2.1067 2.48782 + endloop + endfacet + facet normal 0.106203 0.322303 0.94066 + outer loop + vertex 1.37357 2.10188 2.48918 + vertex 1.37644 2.10594 2.48747 + vertex 1.37098 2.1067 2.48782 + endloop + endfacet + facet normal 0.106392 0.32239 0.940609 + outer loop + vertex 1.37357 2.10188 2.48918 + vertex 1.37098 2.1067 2.48782 + vertex 1.368 2.10275 2.48952 + endloop + endfacet + facet normal 0.105435 0.315327 0.943108 + outer loop + vertex 1.368 2.10275 2.48952 + vertex 1.36956 2.09864 2.49072 + vertex 1.37357 2.10188 2.48918 + endloop + endfacet + facet normal 0.103018 0.318014 0.942473 + outer loop + vertex 1.36956 2.09864 2.49072 + vertex 1.37365 2.09778 2.49056 + vertex 1.37357 2.10188 2.48918 + endloop + endfacet + facet normal 0.0927825 0.318141 0.943492 + outer loop + vertex 1.37365 2.09778 2.49056 + vertex 1.37805 2.09883 2.48977 + vertex 1.37357 2.10188 2.48918 + endloop + endfacet + facet normal 0.0993391 0.327043 0.939774 + outer loop + vertex 1.37357 2.10188 2.48918 + vertex 1.37805 2.09883 2.48977 + vertex 1.37827 2.10271 2.4884 + endloop + endfacet + facet normal 0.0845003 0.328269 0.940797 + outer loop + vertex 1.37805 2.09883 2.48977 + vertex 1.38213 2.10164 2.48842 + vertex 1.37827 2.10271 2.4884 + endloop + endfacet + facet normal 0.0861679 0.334219 0.938548 + outer loop + vertex 1.38213 2.10164 2.48842 + vertex 1.38118 2.10538 2.48718 + vertex 1.37827 2.10271 2.4884 + endloop + endfacet + facet normal 0.0956466 0.324947 0.940883 + outer loop + vertex 1.37827 2.10271 2.4884 + vertex 1.38118 2.10538 2.48718 + vertex 1.37644 2.10594 2.48747 + endloop + endfacet + facet normal 0.0964154 0.333026 0.937975 + outer loop + vertex 1.38118 2.10538 2.48718 + vertex 1.3797 2.10917 2.48599 + vertex 1.37644 2.10594 2.48747 + endloop + endfacet + facet normal 0.0734786 0.331667 0.940531 + outer loop + vertex 1.38213 2.10164 2.48842 + vertex 1.38615 2.10447 2.48711 + vertex 1.38118 2.10538 2.48718 + endloop + endfacet + facet normal 0.075277 0.341755 0.936769 + outer loop + vertex 1.38615 2.10447 2.48711 + vertex 1.38445 2.10849 2.48578 + vertex 1.38118 2.10538 2.48718 + endloop + endfacet + facet normal 0.0771212 0.33767 0.9381 + outer loop + vertex 1.38309 2.09793 2.48968 + vertex 1.38213 2.10164 2.48842 + vertex 1.37805 2.09883 2.48977 + endloop + endfacet + facet normal 0.0746429 0.323154 0.943398 + outer loop + vertex 1.37805 2.09883 2.48977 + vertex 1.37975 2.09471 2.49105 + vertex 1.38309 2.09793 2.48968 + endloop + endfacet + facet normal 0.0789935 0.324676 0.942521 + outer loop + vertex 1.37975 2.09471 2.49105 + vertex 1.37805 2.09883 2.48977 + vertex 1.37572 2.09538 2.49116 + endloop + endfacet + facet normal 0.0775508 0.315482 0.945757 + outer loop + vertex 1.37572 2.09538 2.49116 + vertex 1.37571 2.09147 2.49246 + vertex 1.37975 2.09471 2.49105 + endloop + endfacet + facet normal 0.0935169 0.315012 0.944469 + outer loop + vertex 1.37572 2.09538 2.49116 + vertex 1.37134 2.09435 2.49193 + vertex 1.37571 2.09147 2.49246 + endloop + endfacet + facet normal 0.0864637 0.305009 0.948416 + outer loop + vertex 1.37134 2.09435 2.49193 + vertex 1.3713 2.0904 2.49321 + vertex 1.37571 2.09147 2.49246 + endloop + endfacet + facet normal 0.0864955 0.304899 0.948449 + outer loop + vertex 1.3733 2.08797 2.49381 + vertex 1.37571 2.09147 2.49246 + vertex 1.3713 2.0904 2.49321 + endloop + endfacet + facet normal 0.0932264 0.309883 0.946193 + outer loop + vertex 1.3733 2.08797 2.49381 + vertex 1.3713 2.0904 2.49321 + vertex 1.3688 2.08708 2.49454 + endloop + endfacet + facet normal 0.0922913 0.313639 0.945046 + outer loop + vertex 1.3688 2.08708 2.49454 + vertex 1.37322 2.08409 2.4951 + vertex 1.3733 2.08797 2.49381 + endloop + endfacet + facet normal 0.0703944 0.314581 0.946617 + outer loop + vertex 1.37322 2.08409 2.4951 + vertex 1.37737 2.08732 2.49372 + vertex 1.3733 2.08797 2.49381 + endloop + endfacet + facet normal 0.0704874 0.315184 0.946409 + outer loop + vertex 1.37737 2.08732 2.49372 + vertex 1.37571 2.09147 2.49246 + vertex 1.3733 2.08797 2.49381 + endloop + endfacet + facet normal 0.0656017 0.313517 0.947314 + outer loop + vertex 1.37737 2.08732 2.49372 + vertex 1.38101 2.09077 2.49233 + vertex 1.37571 2.09147 2.49246 + endloop + endfacet + facet normal 0.0672699 0.326945 0.942646 + outer loop + vertex 1.38101 2.09077 2.49233 + vertex 1.37975 2.09471 2.49105 + vertex 1.37571 2.09147 2.49246 + endloop + endfacet + facet normal 0.0520116 0.326429 0.94379 + outer loop + vertex 1.38229 2.08688 2.4936 + vertex 1.38101 2.09077 2.49233 + vertex 1.37737 2.08732 2.49372 + endloop + endfacet + facet normal 0.0515277 0.320386 0.945885 + outer loop + vertex 1.3785 2.08337 2.495 + vertex 1.38229 2.08688 2.4936 + vertex 1.37737 2.08732 2.49372 + endloop + endfacet + facet normal 0.043431 0.32821 0.943606 + outer loop + vertex 1.38347 2.0831 2.49486 + vertex 1.38229 2.08688 2.4936 + vertex 1.3785 2.08337 2.495 + endloop + endfacet + facet normal 0.0432393 0.323921 0.945096 + outer loop + vertex 1.3785 2.08337 2.495 + vertex 1.37976 2.07952 2.49626 + vertex 1.38347 2.0831 2.49486 + endloop + endfacet + facet normal 0.0406034 0.32637 0.94437 + outer loop + vertex 1.37976 2.07952 2.49626 + vertex 1.38465 2.07936 2.4961 + vertex 1.38347 2.0831 2.49486 + endloop + endfacet + facet normal 0.044405 0.327394 0.943844 + outer loop + vertex 1.38347 2.0831 2.49486 + vertex 1.38465 2.07936 2.4961 + vertex 1.38837 2.08293 2.49469 + endloop + endfacet + facet normal 0.0443865 0.326566 0.944132 + outer loop + vertex 1.38837 2.08293 2.49469 + vertex 1.38722 2.08666 2.49345 + vertex 1.38347 2.0831 2.49486 + endloop + endfacet + facet normal 0.0512331 0.321013 0.945688 + outer loop + vertex 1.38465 2.07936 2.4961 + vertex 1.38957 2.07915 2.49591 + vertex 1.38837 2.08293 2.49469 + endloop + endfacet + facet normal 0.0513273 0.324443 0.944512 + outer loop + vertex 1.38957 2.07915 2.49591 + vertex 1.38465 2.07936 2.4961 + vertex 1.38586 2.07558 2.49734 + endloop + endfacet + facet normal 0.0435879 0.322313 0.945629 + outer loop + vertex 1.38586 2.07558 2.49734 + vertex 1.38465 2.07936 2.4961 + vertex 1.38096 2.07576 2.4975 + endloop + endfacet + facet normal 0.0436226 0.323626 0.945179 + outer loop + vertex 1.38214 2.07198 2.49874 + vertex 1.38586 2.07558 2.49734 + vertex 1.38096 2.07576 2.4975 + endloop + endfacet + facet normal 0.0437766 0.323667 0.945158 + outer loop + vertex 1.38214 2.07198 2.49874 + vertex 1.38096 2.07576 2.4975 + vertex 1.37734 2.07235 2.49883 + endloop + endfacet + facet normal 0.0436381 0.321725 0.945827 + outer loop + vertex 1.37842 2.06847 2.5001 + vertex 1.38214 2.07198 2.49874 + vertex 1.37734 2.07235 2.49883 + endloop + endfacet + facet normal 0.0515198 0.323573 0.9448 + outer loop + vertex 1.37842 2.06847 2.5001 + vertex 1.37734 2.07235 2.49883 + vertex 1.37322 2.06917 2.50015 + endloop + endfacet + facet normal 0.0549621 0.319594 0.945959 + outer loop + vertex 1.37322 2.06917 2.50015 + vertex 1.37734 2.07235 2.49883 + vertex 1.3733 2.07316 2.4988 + endloop + endfacet + facet normal 0.0754273 0.31879 0.944819 + outer loop + vertex 1.36877 2.07201 2.49955 + vertex 1.37322 2.06917 2.50015 + vertex 1.3733 2.07316 2.4988 + endloop + endfacet + facet normal 0.0748737 0.320598 0.944251 + outer loop + vertex 1.3733 2.07316 2.4988 + vertex 1.37098 2.07666 2.49779 + vertex 1.36877 2.07201 2.49955 + endloop + endfacet + facet normal 0.0904372 0.313561 0.945252 + outer loop + vertex 1.36877 2.07201 2.49955 + vertex 1.37098 2.07666 2.49779 + vertex 1.36641 2.07564 2.49857 + endloop + endfacet + facet normal 0.0952376 0.316311 0.943863 + outer loop + vertex 1.36877 2.07201 2.49955 + vertex 1.36641 2.07564 2.49857 + vertex 1.3635 2.07291 2.49978 + endloop + endfacet + facet normal 0.103864 0.307917 0.945727 + outer loop + vertex 1.3635 2.07291 2.49978 + vertex 1.36641 2.07564 2.49857 + vertex 1.36229 2.07699 2.49858 + endloop + endfacet + facet normal 0.111575 0.309762 0.944245 + outer loop + vertex 1.3635 2.07291 2.49978 + vertex 1.36229 2.07699 2.49858 + vertex 1.35833 2.07415 2.49998 + endloop + endfacet + facet normal 0.108318 0.29541 0.94921 + outer loop + vertex 1.35833 2.07415 2.49998 + vertex 1.36004 2.06982 2.50113 + vertex 1.3635 2.07291 2.49978 + endloop + endfacet + facet normal 0.100659 0.303265 0.947575 + outer loop + vertex 1.36004 2.06982 2.50113 + vertex 1.36488 2.06883 2.50094 + vertex 1.3635 2.07291 2.49978 + endloop + endfacet + facet normal 0.0928684 0.301058 0.949073 + outer loop + vertex 1.3635 2.07291 2.49978 + vertex 1.36488 2.06883 2.50094 + vertex 1.36877 2.07201 2.49955 + endloop + endfacet + facet normal 0.0862405 0.308398 0.94734 + outer loop + vertex 1.36488 2.06883 2.50094 + vertex 1.36889 2.06801 2.50084 + vertex 1.36877 2.07201 2.49955 + endloop + endfacet + facet normal 0.0847285 0.300627 0.949971 + outer loop + vertex 1.36889 2.06801 2.50084 + vertex 1.36488 2.06883 2.50094 + vertex 1.36652 2.06455 2.50214 + endloop + endfacet + facet normal 0.0710677 0.309355 0.948287 + outer loop + vertex 1.37091 2.06563 2.50146 + vertex 1.36889 2.06801 2.50084 + vertex 1.36652 2.06455 2.50214 + endloop + endfacet + facet normal 0.0705267 0.311203 0.947723 + outer loop + vertex 1.37091 2.06563 2.50146 + vertex 1.36652 2.06455 2.50214 + vertex 1.37094 2.06161 2.50278 + endloop + endfacet + facet normal 0.0541479 0.311414 0.94873 + outer loop + vertex 1.37091 2.06563 2.50146 + vertex 1.37094 2.06161 2.50278 + vertex 1.37491 2.06503 2.50143 + endloop + endfacet + facet normal 0.0547733 0.315656 0.947292 + outer loop + vertex 1.37491 2.06503 2.50143 + vertex 1.37322 2.06917 2.50015 + vertex 1.37091 2.06563 2.50146 + endloop + endfacet + facet normal 0.0684791 0.307383 0.949119 + outer loop + vertex 1.36889 2.06801 2.50084 + vertex 1.37091 2.06563 2.50146 + vertex 1.37322 2.06917 2.50015 + endloop + endfacet + facet normal 0.0502853 0.314058 0.948071 + outer loop + vertex 1.37322 2.06917 2.50015 + vertex 1.37491 2.06503 2.50143 + vertex 1.37842 2.06847 2.5001 + endloop + endfacet + facet normal 0.0489506 0.316865 0.947207 + outer loop + vertex 1.37638 2.06115 2.50265 + vertex 1.37491 2.06503 2.50143 + vertex 1.37094 2.06161 2.50278 + endloop + endfacet + facet normal 0.0434302 0.31505 0.948081 + outer loop + vertex 1.37977 2.0646 2.50135 + vertex 1.37491 2.06503 2.50143 + vertex 1.37638 2.06115 2.50265 + endloop + endfacet + facet normal 0.0419999 0.316316 0.947724 + outer loop + vertex 1.38117 2.06093 2.50251 + vertex 1.37977 2.0646 2.50135 + vertex 1.37638 2.06115 2.50265 + endloop + endfacet + facet normal 0.0419459 0.314789 0.948234 + outer loop + vertex 1.37823 2.0581 2.50359 + vertex 1.38117 2.06093 2.50251 + vertex 1.37638 2.06115 2.50265 + endloop + endfacet + facet normal 0.0419428 0.314787 0.948235 + outer loop + vertex 1.37823 2.0581 2.50359 + vertex 1.37638 2.06115 2.50265 + vertex 1.37352 2.05705 2.50414 + endloop + endfacet + facet normal 0.044428 0.312463 0.94889 + outer loop + vertex 1.38225 2.05731 2.50366 + vertex 1.38117 2.06093 2.50251 + vertex 1.37823 2.0581 2.50359 + endloop + endfacet + facet normal 0.0458743 0.319657 0.946422 + outer loop + vertex 1.37802 2.05433 2.50487 + vertex 1.38225 2.05731 2.50366 + vertex 1.37823 2.0581 2.50359 + endloop + endfacet + facet normal 0.0465478 0.318805 0.946677 + outer loop + vertex 1.3833 2.05356 2.50487 + vertex 1.38225 2.05731 2.50366 + vertex 1.37802 2.05433 2.50487 + endloop + endfacet + facet normal 0.0505419 0.346189 0.936802 + outer loop + vertex 1.37802 2.05433 2.50487 + vertex 1.37977 2.05026 2.50628 + vertex 1.3833 2.05356 2.50487 + endloop + endfacet + facet normal 0.0593683 0.337847 0.939327 + outer loop + vertex 1.37977 2.05026 2.50628 + vertex 1.38468 2.04967 2.50618 + vertex 1.3833 2.05356 2.50487 + endloop + endfacet + facet normal 0.0604683 0.347709 0.935651 + outer loop + vertex 1.38468 2.04967 2.50618 + vertex 1.37977 2.05026 2.50628 + vertex 1.38133 2.04606 2.50774 + endloop + endfacet + facet normal 0.0542102 0.314977 0.94755 + outer loop + vertex 1.38225 2.05731 2.50366 + vertex 1.386 2.06045 2.5024 + vertex 1.38117 2.06093 2.50251 + endloop + endfacet + facet normal 0.0538812 0.311355 0.948765 + outer loop + vertex 1.386 2.06045 2.5024 + vertex 1.38469 2.06429 2.50121 + vertex 1.38117 2.06093 2.50251 + endloop + endfacet + facet normal 0.0632523 0.314095 0.947282 + outer loop + vertex 1.38968 2.06381 2.50104 + vertex 1.38469 2.06429 2.50121 + vertex 1.386 2.06045 2.5024 + endloop + endfacet + facet normal 0.063173 0.31315 0.9476 + outer loop + vertex 1.38469 2.06429 2.50121 + vertex 1.38968 2.06381 2.50104 + vertex 1.38845 2.06778 2.49981 + endloop + endfacet + facet normal 0.0558828 0.320224 0.945692 + outer loop + vertex 1.38338 2.06813 2.49999 + vertex 1.38469 2.06429 2.50121 + vertex 1.38845 2.06778 2.49981 + endloop + endfacet + facet normal 0.055663 0.3165 0.946958 + outer loop + vertex 1.38845 2.06778 2.49981 + vertex 1.38712 2.07172 2.49857 + vertex 1.38338 2.06813 2.49999 + endloop + endfacet + facet normal 0.0492783 0.322499 0.945286 + outer loop + vertex 1.38338 2.06813 2.49999 + vertex 1.38712 2.07172 2.49857 + vertex 1.38214 2.07198 2.49874 + endloop + endfacet + facet normal 0.0469176 0.317607 0.947061 + outer loop + vertex 1.37977 2.0646 2.50135 + vertex 1.38469 2.06429 2.50121 + vertex 1.38338 2.06813 2.49999 + endloop + endfacet + facet normal 0.0442146 0.3201 0.946351 + outer loop + vertex 1.37842 2.06847 2.5001 + vertex 1.37977 2.0646 2.50135 + vertex 1.38338 2.06813 2.49999 + endloop + endfacet + facet normal 0.0469365 0.317948 0.946946 + outer loop + vertex 1.38469 2.06429 2.50121 + vertex 1.37977 2.0646 2.50135 + vertex 1.38117 2.06093 2.50251 + endloop + endfacet + facet normal 0.0438332 0.319985 0.946408 + outer loop + vertex 1.37491 2.06503 2.50143 + vertex 1.37977 2.0646 2.50135 + vertex 1.37842 2.06847 2.5001 + endloop + endfacet + facet normal 0.0887549 0.301952 0.949183 + outer loop + vertex 1.36652 2.06455 2.50214 + vertex 1.36488 2.06883 2.50094 + vertex 1.36125 2.06564 2.50229 + endloop + endfacet + facet normal 0.087145 0.293797 0.951887 + outer loop + vertex 1.36226 2.06158 2.50345 + vertex 1.36652 2.06455 2.50214 + vertex 1.36125 2.06564 2.50229 + endloop + endfacet + facet normal 0.095351 0.295471 0.950582 + outer loop + vertex 1.36226 2.06158 2.50345 + vertex 1.36125 2.06564 2.50229 + vertex 1.35752 2.06243 2.50366 + endloop + endfacet + facet normal 0.10424 0.285991 0.952546 + outer loop + vertex 1.35752 2.06243 2.50366 + vertex 1.36125 2.06564 2.50229 + vertex 1.35597 2.06671 2.50255 + endloop + endfacet + facet normal 0.0984575 0.291835 0.951388 + outer loop + vertex 1.36488 2.06883 2.50094 + vertex 1.36004 2.06982 2.50113 + vertex 1.36125 2.06564 2.50229 + endloop + endfacet + facet normal 0.105649 0.293549 0.950088 + outer loop + vertex 1.36125 2.06564 2.50229 + vertex 1.36004 2.06982 2.50113 + vertex 1.35597 2.06671 2.50255 + endloop + endfacet + facet normal 0.111621 0.286421 0.95158 + outer loop + vertex 1.35602 2.07072 2.50133 + vertex 1.35597 2.06671 2.50255 + vertex 1.36004 2.06982 2.50113 + endloop + endfacet + facet normal 0.125083 0.285786 0.950095 + outer loop + vertex 1.35602 2.07072 2.50133 + vertex 1.35158 2.06982 2.50219 + vertex 1.35597 2.06671 2.50255 + endloop + endfacet + facet normal 0.119736 0.27856 0.952926 + outer loop + vertex 1.35158 2.06982 2.50219 + vertex 1.35156 2.06571 2.50339 + vertex 1.35597 2.06671 2.50255 + endloop + endfacet + facet normal 0.123466 0.29211 0.948382 + outer loop + vertex 1.35602 2.07072 2.50133 + vertex 1.35399 2.07324 2.50082 + vertex 1.35158 2.06982 2.50219 + endloop + endfacet + facet normal 0.122732 0.29157 0.948643 + outer loop + vertex 1.35399 2.07324 2.50082 + vertex 1.35602 2.07072 2.50133 + vertex 1.35833 2.07415 2.49998 + endloop + endfacet + facet normal 0.121035 0.297985 0.946866 + outer loop + vertex 1.35399 2.07324 2.50082 + vertex 1.35833 2.07415 2.49998 + vertex 1.35393 2.07728 2.49956 + endloop + endfacet + facet normal 0.126061 0.304673 0.944078 + outer loop + vertex 1.35393 2.07728 2.49956 + vertex 1.35833 2.07415 2.49998 + vertex 1.35832 2.07809 2.49871 + endloop + endfacet + facet normal 0.125705 0.306156 0.943646 + outer loop + vertex 1.35832 2.07809 2.49871 + vertex 1.35631 2.0806 2.49816 + vertex 1.35393 2.07728 2.49956 + endloop + endfacet + facet normal 0.132399 0.3016 0.944197 + outer loop + vertex 1.35393 2.07728 2.49956 + vertex 1.35631 2.0806 2.49816 + vertex 1.35237 2.08169 2.49837 + endloop + endfacet + facet normal 0.134993 0.302355 0.943588 + outer loop + vertex 1.35393 2.07728 2.49956 + vertex 1.35237 2.08169 2.49837 + vertex 1.34826 2.0789 2.49985 + endloop + endfacet + facet normal 0.133285 0.295945 0.94586 + outer loop + vertex 1.34826 2.0789 2.49985 + vertex 1.34993 2.07435 2.50104 + vertex 1.35393 2.07728 2.49956 + endloop + endfacet + facet normal 0.131859 0.29771 0.945506 + outer loop + vertex 1.34993 2.07435 2.50104 + vertex 1.35399 2.07324 2.50082 + vertex 1.35393 2.07728 2.49956 + endloop + endfacet + facet normal 0.12941 0.288095 0.948817 + outer loop + vertex 1.35399 2.07324 2.50082 + vertex 1.34993 2.07435 2.50104 + vertex 1.35158 2.06982 2.50219 + endloop + endfacet + facet normal 0.138559 0.290878 0.946674 + outer loop + vertex 1.35158 2.06982 2.50219 + vertex 1.34993 2.07435 2.50104 + vertex 1.3459 2.07152 2.5025 + endloop + endfacet + facet normal 0.135021 0.278269 0.950966 + outer loop + vertex 1.34748 2.06693 2.50362 + vertex 1.35158 2.06982 2.50219 + vertex 1.3459 2.07152 2.5025 + endloop + endfacet + facet normal 0.144849 0.281111 0.948681 + outer loop + vertex 1.34748 2.06693 2.50362 + vertex 1.3459 2.07152 2.5025 + vertex 1.34335 2.06834 2.50383 + endloop + endfacet + facet normal 0.145215 0.28083 0.948708 + outer loop + vertex 1.34335 2.06834 2.50383 + vertex 1.3459 2.07152 2.5025 + vertex 1.3415 2.07106 2.50331 + endloop + endfacet + facet normal 0.142232 0.278984 0.949704 + outer loop + vertex 1.34335 2.06834 2.50383 + vertex 1.3415 2.07106 2.50331 + vertex 1.33856 2.06809 2.50462 + endloop + endfacet + facet normal 0.143049 0.27045 0.952047 + outer loop + vertex 1.33856 2.06809 2.50462 + vertex 1.34334 2.06429 2.50498 + vertex 1.34335 2.06834 2.50383 + endloop + endfacet + facet normal 0.139435 0.266088 0.953811 + outer loop + vertex 1.33892 2.06387 2.50574 + vertex 1.34334 2.06429 2.50498 + vertex 1.33856 2.06809 2.50462 + endloop + endfacet + facet normal 0.143736 0.266268 0.953122 + outer loop + vertex 1.33892 2.06387 2.50574 + vertex 1.33856 2.06809 2.50462 + vertex 1.33576 2.06502 2.5059 + endloop + endfacet + facet normal 0.143531 0.26568 0.953317 + outer loop + vertex 1.33576 2.06502 2.5059 + vertex 1.33603 2.06072 2.50706 + vertex 1.33892 2.06387 2.50574 + endloop + endfacet + facet normal 0.13932 0.269372 0.952905 + outer loop + vertex 1.34087 2.06105 2.50626 + vertex 1.33892 2.06387 2.50574 + vertex 1.33603 2.06072 2.50706 + endloop + endfacet + facet normal 0.136227 0.29627 0.945339 + outer loop + vertex 1.34087 2.06105 2.50626 + vertex 1.33603 2.06072 2.50706 + vertex 1.34097 2.05671 2.5076 + endloop + endfacet + facet normal 0.138198 0.296231 0.945065 + outer loop + vertex 1.34087 2.06105 2.50626 + vertex 1.34097 2.05671 2.5076 + vertex 1.34501 2.0596 2.50611 + endloop + endfacet + facet normal 0.133749 0.293387 0.946591 + outer loop + vertex 1.33603 2.06072 2.50706 + vertex 1.3362 2.05618 2.50844 + vertex 1.34097 2.05671 2.5076 + endloop + endfacet + facet normal 0.1405 0.26562 0.953785 + outer loop + vertex 1.33576 2.06502 2.5059 + vertex 1.33145 2.06438 2.50671 + vertex 1.33603 2.06072 2.50706 + endloop + endfacet + facet normal 0.140949 0.26616 0.953568 + outer loop + vertex 1.33145 2.06438 2.50671 + vertex 1.3312 2.06039 2.50786 + vertex 1.33603 2.06072 2.50706 + endloop + endfacet + facet normal 0.15298 0.264954 0.952049 + outer loop + vertex 1.3312 2.06039 2.50786 + vertex 1.33145 2.06438 2.50671 + vertex 1.32724 2.06168 2.50814 + endloop + endfacet + facet normal 0.14674 0.273873 0.950506 + outer loop + vertex 1.32724 2.06168 2.50814 + vertex 1.33145 2.06438 2.50671 + vertex 1.3263 2.06584 2.50709 + endloop + endfacet + facet normal 0.151607 0.274722 0.949496 + outer loop + vertex 1.32724 2.06168 2.50814 + vertex 1.3263 2.06584 2.50709 + vertex 1.32321 2.06314 2.50836 + endloop + endfacet + facet normal 0.148171 0.278411 0.948964 + outer loop + vertex 1.32321 2.06314 2.50836 + vertex 1.3263 2.06584 2.50709 + vertex 1.32109 2.06689 2.50759 + endloop + endfacet + facet normal 0.15775 0.283218 0.945993 + outer loop + vertex 1.32321 2.06314 2.50836 + vertex 1.32109 2.06689 2.50759 + vertex 1.31857 2.06235 2.50937 + endloop + endfacet + facet normal 0.154275 0.298316 0.941916 + outer loop + vertex 1.31857 2.06235 2.50937 + vertex 1.32298 2.05892 2.50974 + vertex 1.32321 2.06314 2.50836 + endloop + endfacet + facet normal 0.163308 0.309388 0.936808 + outer loop + vertex 1.31863 2.05818 2.51074 + vertex 1.32298 2.05892 2.50974 + vertex 1.31857 2.06235 2.50937 + endloop + endfacet + facet normal 0.15078 0.309847 0.938755 + outer loop + vertex 1.31473 2.05935 2.51098 + vertex 1.31863 2.05818 2.51074 + vertex 1.31857 2.06235 2.50937 + endloop + endfacet + facet normal 0.151783 0.308681 0.938977 + outer loop + vertex 1.31308 2.06384 2.50977 + vertex 1.31473 2.05935 2.51098 + vertex 1.31857 2.06235 2.50937 + endloop + endfacet + facet normal 0.147528 0.291349 0.945173 + outer loop + vertex 1.31857 2.06235 2.50937 + vertex 1.31657 2.06616 2.50851 + vertex 1.31308 2.06384 2.50977 + endloop + endfacet + facet normal 0.152503 0.284553 0.946453 + outer loop + vertex 1.31308 2.06384 2.50977 + vertex 1.31657 2.06616 2.50851 + vertex 1.3133 2.06783 2.50854 + endloop + endfacet + facet normal 0.152208 0.284581 0.946491 + outer loop + vertex 1.30878 2.06737 2.5094 + vertex 1.31308 2.06384 2.50977 + vertex 1.3133 2.06783 2.50854 + endloop + endfacet + facet normal 0.148183 0.279887 0.948528 + outer loop + vertex 1.30882 2.06325 2.51061 + vertex 1.31308 2.06384 2.50977 + vertex 1.30878 2.06737 2.5094 + endloop + endfacet + facet normal 0.149086 0.279857 0.948395 + outer loop + vertex 1.30492 2.06447 2.51086 + vertex 1.30882 2.06325 2.51061 + vertex 1.30878 2.06737 2.5094 + endloop + endfacet + facet normal 0.156934 0.270182 0.949933 + outer loop + vertex 1.30334 2.06894 2.50985 + vertex 1.30492 2.06447 2.51086 + vertex 1.30878 2.06737 2.5094 + endloop + endfacet + facet normal 0.157568 0.272608 0.949135 + outer loop + vertex 1.30878 2.06737 2.5094 + vertex 1.30663 2.07133 2.50862 + vertex 1.30334 2.06894 2.50985 + endloop + endfacet + facet normal 0.16 0.26952 0.94961 + outer loop + vertex 1.30334 2.06894 2.50985 + vertex 1.30663 2.07133 2.50862 + vertex 1.30342 2.07278 2.50875 + endloop + endfacet + facet normal 0.16152 0.269421 0.949381 + outer loop + vertex 1.29913 2.07235 2.5096 + vertex 1.30334 2.06894 2.50985 + vertex 1.30342 2.07278 2.50875 + endloop + endfacet + facet normal 0.160337 0.277214 0.947336 + outer loop + vertex 1.30342 2.07278 2.50875 + vertex 1.30159 2.07548 2.50827 + vertex 1.29913 2.07235 2.5096 + endloop + endfacet + facet normal 0.1624 0.275635 0.947445 + outer loop + vertex 1.29913 2.07235 2.5096 + vertex 1.30159 2.07548 2.50827 + vertex 1.29754 2.07693 2.50854 + endloop + endfacet + facet normal 0.162931 0.275789 0.947309 + outer loop + vertex 1.29913 2.07235 2.5096 + vertex 1.29754 2.07693 2.50854 + vertex 1.29349 2.07431 2.51 + endloop + endfacet + facet normal 0.159349 0.264714 0.95107 + outer loop + vertex 1.29349 2.07431 2.51 + vertex 1.29512 2.06964 2.51103 + vertex 1.29913 2.07235 2.5096 + endloop + endfacet + facet normal 0.159549 0.264441 0.951113 + outer loop + vertex 1.29512 2.06964 2.51103 + vertex 1.29911 2.06834 2.51072 + vertex 1.29913 2.07235 2.5096 + endloop + endfacet + facet normal 0.159059 0.262812 0.951646 + outer loop + vertex 1.29911 2.06834 2.51072 + vertex 1.29512 2.06964 2.51103 + vertex 1.29659 2.06498 2.51207 + endloop + endfacet + facet normal 0.158427 0.263278 0.951623 + outer loop + vertex 1.30102 2.06568 2.51114 + vertex 1.29911 2.06834 2.51072 + vertex 1.29659 2.06498 2.51207 + endloop + endfacet + facet normal 0.154475 0.281955 0.94691 + outer loop + vertex 1.30102 2.06568 2.51114 + vertex 1.29659 2.06498 2.51207 + vertex 1.30088 2.06149 2.51241 + endloop + endfacet + facet normal 0.154106 0.281983 0.946962 + outer loop + vertex 1.30102 2.06568 2.51114 + vertex 1.30088 2.06149 2.51241 + vertex 1.30492 2.06447 2.51086 + endloop + endfacet + facet normal 0.142362 0.29654 0.94435 + outer loop + vertex 1.30649 2.05979 2.5121 + vertex 1.30492 2.06447 2.51086 + vertex 1.30088 2.06149 2.51241 + endloop + endfacet + facet normal 0.14661 0.311535 0.938857 + outer loop + vertex 1.30246 2.05671 2.51375 + vertex 1.30649 2.05979 2.5121 + vertex 1.30088 2.06149 2.51241 + endloop + endfacet + facet normal 0.144326 0.310936 0.939409 + outer loop + vertex 1.30246 2.05671 2.51375 + vertex 1.30088 2.06149 2.51241 + vertex 1.29835 2.05796 2.51396 + endloop + endfacet + facet normal 0.147954 0.308443 0.939666 + outer loop + vertex 1.29835 2.05796 2.51396 + vertex 1.30088 2.06149 2.51241 + vertex 1.29639 2.06074 2.51336 + endloop + endfacet + facet normal 0.162593 0.317598 0.934181 + outer loop + vertex 1.29835 2.05796 2.51396 + vertex 1.29639 2.06074 2.51336 + vertex 1.29397 2.05733 2.51494 + endloop + endfacet + facet normal 0.160922 0.325439 0.931769 + outer loop + vertex 1.29397 2.05733 2.51494 + vertex 1.2985 2.05385 2.51537 + vertex 1.29835 2.05796 2.51396 + endloop + endfacet + facet normal 0.147289 0.308686 0.939691 + outer loop + vertex 1.29434 2.05335 2.51619 + vertex 1.2985 2.05385 2.51537 + vertex 1.29397 2.05733 2.51494 + endloop + endfacet + facet normal 0.175276 0.308891 0.934807 + outer loop + vertex 1.29397 2.05733 2.51494 + vertex 1.29639 2.06074 2.51336 + vertex 1.29239 2.0621 2.51366 + endloop + endfacet + facet normal 0.172127 0.308079 0.93566 + outer loop + vertex 1.29397 2.05733 2.51494 + vertex 1.29239 2.0621 2.51366 + vertex 1.28837 2.05936 2.5153 + endloop + endfacet + facet normal 0.176077 0.302847 0.936633 + outer loop + vertex 1.28837 2.05936 2.5153 + vertex 1.29239 2.0621 2.51366 + vertex 1.28836 2.06357 2.51394 + endloop + endfacet + facet normal 0.168722 0.28114 0.944719 + outer loop + vertex 1.29239 2.0621 2.51366 + vertex 1.29095 2.06689 2.51249 + vertex 1.28836 2.06357 2.51394 + endloop + endfacet + facet normal 0.164861 0.284074 0.944523 + outer loop + vertex 1.28836 2.06357 2.51394 + vertex 1.29095 2.06689 2.51249 + vertex 1.28656 2.06639 2.51341 + endloop + endfacet + facet normal 0.183227 0.294565 0.937901 + outer loop + vertex 1.28836 2.06357 2.51394 + vertex 1.28656 2.06639 2.51341 + vertex 1.28368 2.06328 2.51495 + endloop + endfacet + facet normal 0.175252 0.301582 0.937195 + outer loop + vertex 1.28368 2.06328 2.51495 + vertex 1.28656 2.06639 2.51341 + vertex 1.28343 2.06759 2.51361 + endloop + endfacet + facet normal 0.168962 0.301571 0.938353 + outer loop + vertex 1.27903 2.06716 2.51454 + vertex 1.28368 2.06328 2.51495 + vertex 1.28343 2.06759 2.51361 + endloop + endfacet + facet normal 0.171733 0.284021 0.943313 + outer loop + vertex 1.28343 2.06759 2.51361 + vertex 1.28158 2.07039 2.5131 + vertex 1.27903 2.06716 2.51454 + endloop + endfacet + facet normal 0.168815 0.286255 0.943165 + outer loop + vertex 1.27903 2.06716 2.51454 + vertex 1.28158 2.07039 2.5131 + vertex 1.27747 2.07189 2.51338 + endloop + endfacet + facet normal 0.158123 0.283396 0.945877 + outer loop + vertex 1.27903 2.06716 2.51454 + vertex 1.27747 2.07189 2.51338 + vertex 1.2733 2.06929 2.51486 + endloop + endfacet + facet normal 0.165085 0.303183 0.938524 + outer loop + vertex 1.2733 2.06929 2.51486 + vertex 1.27498 2.06449 2.51612 + vertex 1.27903 2.06716 2.51454 + endloop + endfacet + facet normal 0.158149 0.312587 0.936631 + outer loop + vertex 1.27498 2.06449 2.51612 + vertex 1.27906 2.06298 2.51593 + vertex 1.27903 2.06716 2.51454 + endloop + endfacet + facet normal 0.149251 0.287309 0.946138 + outer loop + vertex 1.27906 2.06298 2.51593 + vertex 1.27498 2.06449 2.51612 + vertex 1.2769 2.05963 2.51729 + endloop + endfacet + facet normal 0.155497 0.289387 0.944498 + outer loop + vertex 1.2769 2.05963 2.51729 + vertex 1.27498 2.06449 2.51612 + vertex 1.27104 2.06166 2.51763 + endloop + endfacet + facet normal 0.126306 0.200469 0.971524 + outer loop + vertex 1.27295 2.05689 2.51837 + vertex 1.2769 2.05963 2.51729 + vertex 1.27104 2.06166 2.51763 + endloop + endfacet + facet normal 0.146987 0.300195 0.942485 + outer loop + vertex 1.27085 2.066 2.51628 + vertex 1.27104 2.06166 2.51763 + vertex 1.27498 2.06449 2.51612 + endloop + endfacet + facet normal 0.153955 0.300157 0.941384 + outer loop + vertex 1.27085 2.066 2.51628 + vertex 1.26617 2.06561 2.51717 + vertex 1.27104 2.06166 2.51763 + endloop + endfacet + facet normal 0.156504 0.303143 0.940006 + outer loop + vertex 1.26617 2.06561 2.51717 + vertex 1.26667 2.06107 2.51855 + vertex 1.27104 2.06166 2.51763 + endloop + endfacet + facet normal 0.157442 0.303193 0.939833 + outer loop + vertex 1.26667 2.06107 2.51855 + vertex 1.26617 2.06561 2.51717 + vertex 1.26342 2.06232 2.51869 + endloop + endfacet + facet normal 0.156266 0.30413 0.939727 + outer loop + vertex 1.26342 2.06232 2.51869 + vertex 1.26617 2.06561 2.51717 + vertex 1.26143 2.06527 2.51807 + endloop + endfacet + facet normal 0.177262 0.316591 0.931852 + outer loop + vertex 1.26342 2.06232 2.51869 + vertex 1.26143 2.06527 2.51807 + vertex 1.25905 2.06192 2.51965 + endloop + endfacet + facet normal 0.159141 0.281341 0.94632 + outer loop + vertex 1.26148 2.06954 2.51679 + vertex 1.26143 2.06527 2.51807 + vertex 1.26617 2.06561 2.51717 + endloop + endfacet + facet normal 0.164088 0.286989 0.943776 + outer loop + vertex 1.26581 2.07003 2.51589 + vertex 1.26148 2.06954 2.51679 + vertex 1.26617 2.06561 2.51717 + endloop + endfacet + facet normal 0.165175 0.28702 0.943577 + outer loop + vertex 1.26581 2.07003 2.51589 + vertex 1.26617 2.06561 2.51717 + vertex 1.26892 2.06884 2.5157 + endloop + endfacet + facet normal 0.157509 0.265743 0.95109 + outer loop + vertex 1.26892 2.06884 2.5157 + vertex 1.26865 2.07316 2.51454 + vertex 1.26581 2.07003 2.51589 + endloop + endfacet + facet normal 0.156056 0.265717 0.951336 + outer loop + vertex 1.26892 2.06884 2.5157 + vertex 1.2733 2.06929 2.51486 + vertex 1.26865 2.07316 2.51454 + endloop + endfacet + facet normal 0.163463 0.274322 0.947643 + outer loop + vertex 1.26865 2.07316 2.51454 + vertex 1.2733 2.06929 2.51486 + vertex 1.2734 2.0734 2.51365 + endloop + endfacet + facet normal 0.16482 0.260621 0.951268 + outer loop + vertex 1.2734 2.0734 2.51365 + vertex 1.27164 2.07613 2.51321 + vertex 1.26865 2.07316 2.51454 + endloop + endfacet + facet normal 0.167262 0.258259 0.951486 + outer loop + vertex 1.26865 2.07316 2.51454 + vertex 1.27164 2.07613 2.51321 + vertex 1.26843 2.07762 2.51337 + endloop + endfacet + facet normal 0.17038 0.258268 0.95093 + outer loop + vertex 1.26388 2.07712 2.51432 + vertex 1.26865 2.07316 2.51454 + vertex 1.26843 2.07762 2.51337 + endloop + endfacet + facet normal 0.169216 0.265396 0.949174 + outer loop + vertex 1.26843 2.07762 2.51337 + vertex 1.26619 2.08175 2.51261 + vertex 1.26388 2.07712 2.51432 + endloop + endfacet + facet normal 0.174251 0.262816 0.948981 + outer loop + vertex 1.26388 2.07712 2.51432 + vertex 1.26619 2.08175 2.51261 + vertex 1.26165 2.08123 2.51359 + endloop + endfacet + facet normal 0.176191 0.263752 0.948363 + outer loop + vertex 1.26388 2.07712 2.51432 + vertex 1.26165 2.08123 2.51359 + vertex 1.25835 2.07883 2.51487 + endloop + endfacet + facet normal 0.172884 0.267983 0.947785 + outer loop + vertex 1.25835 2.07883 2.51487 + vertex 1.26165 2.08123 2.51359 + vertex 1.25846 2.08272 2.51375 + endloop + endfacet + facet normal 0.176713 0.276542 0.944615 + outer loop + vertex 1.26165 2.08123 2.51359 + vertex 1.26137 2.08569 2.51234 + vertex 1.25846 2.08272 2.51375 + endloop + endfacet + facet normal 0.17362 0.279436 0.944337 + outer loop + vertex 1.25846 2.08272 2.51375 + vertex 1.26137 2.08569 2.51234 + vertex 1.25668 2.08546 2.51327 + endloop + endfacet + facet normal 0.172168 0.278583 0.944854 + outer loop + vertex 1.25846 2.08272 2.51375 + vertex 1.25668 2.08546 2.51327 + vertex 1.25418 2.08233 2.51465 + endloop + endfacet + facet normal 0.173182 0.28359 0.943178 + outer loop + vertex 1.25668 2.08955 2.51204 + vertex 1.25668 2.08546 2.51327 + vertex 1.26137 2.08569 2.51234 + endloop + endfacet + facet normal 0.172592 0.282898 0.943494 + outer loop + vertex 1.26101 2.08997 2.51112 + vertex 1.25668 2.08955 2.51204 + vertex 1.26137 2.08569 2.51234 + endloop + endfacet + facet normal 0.169694 0.282812 0.944045 + outer loop + vertex 1.26101 2.08997 2.51112 + vertex 1.26137 2.08569 2.51234 + vertex 1.26414 2.0888 2.51091 + endloop + endfacet + facet normal 0.170173 0.284182 0.943548 + outer loop + vertex 1.26414 2.0888 2.51091 + vertex 1.26376 2.09308 2.50969 + vertex 1.26101 2.08997 2.51112 + endloop + endfacet + facet normal 0.171162 0.283338 0.943622 + outer loop + vertex 1.25907 2.09278 2.51063 + vertex 1.26101 2.08997 2.51112 + vertex 1.26376 2.09308 2.50969 + endloop + endfacet + facet normal 0.171374 0.281557 0.944117 + outer loop + vertex 1.25907 2.09278 2.51063 + vertex 1.26376 2.09308 2.50969 + vertex 1.25888 2.09706 2.50939 + endloop + endfacet + facet normal 0.172792 0.281544 0.943862 + outer loop + vertex 1.25495 2.09431 2.51093 + vertex 1.25907 2.09278 2.51063 + vertex 1.25888 2.09706 2.50939 + endloop + endfacet + facet normal 0.174565 0.279217 0.944227 + outer loop + vertex 1.25319 2.099 2.50987 + vertex 1.25495 2.09431 2.51093 + vertex 1.25888 2.09706 2.50939 + endloop + endfacet + facet normal 0.174106 0.277738 0.944748 + outer loop + vertex 1.25888 2.09706 2.50939 + vertex 1.25658 2.10127 2.50857 + vertex 1.25319 2.099 2.50987 + endloop + endfacet + facet normal 0.175692 0.278505 0.944228 + outer loop + vertex 1.25888 2.09706 2.50939 + vertex 1.26116 2.10168 2.5076 + vertex 1.25658 2.10127 2.50857 + endloop + endfacet + facet normal 0.176745 0.271253 0.946141 + outer loop + vertex 1.25637 2.10577 2.50732 + vertex 1.25658 2.10127 2.50857 + vertex 1.26116 2.10168 2.5076 + endloop + endfacet + facet normal 0.179424 0.274291 0.94476 + outer loop + vertex 1.26105 2.10596 2.50638 + vertex 1.25637 2.10577 2.50732 + vertex 1.26116 2.10168 2.5076 + endloop + endfacet + facet normal 0.178975 0.274303 0.944842 + outer loop + vertex 1.26105 2.10596 2.50638 + vertex 1.26116 2.10168 2.5076 + vertex 1.26508 2.10449 2.50604 + endloop + endfacet + facet normal 0.177726 0.270586 0.946149 + outer loop + vertex 1.26508 2.10449 2.50604 + vertex 1.26348 2.10924 2.50498 + vertex 1.26105 2.10596 2.50638 + endloop + endfacet + facet normal 0.180291 0.268708 0.946198 + outer loop + vertex 1.25916 2.10882 2.50592 + vertex 1.26105 2.10596 2.50638 + vertex 1.26348 2.10924 2.50498 + endloop + endfacet + facet normal 0.180527 0.267164 0.946591 + outer loop + vertex 1.25916 2.10882 2.50592 + vertex 1.26348 2.10924 2.50498 + vertex 1.25885 2.11315 2.50476 + endloop + endfacet + facet normal 0.18203 0.267194 0.946294 + outer loop + vertex 1.25916 2.10882 2.50592 + vertex 1.25885 2.11315 2.50476 + vertex 1.25609 2.11009 2.50616 + endloop + endfacet + facet normal 0.181882 0.266808 0.946432 + outer loop + vertex 1.25609 2.11009 2.50616 + vertex 1.25637 2.10577 2.50732 + vertex 1.25916 2.10882 2.50592 + endloop + endfacet + facet normal 0.179903 0.266783 0.946817 + outer loop + vertex 1.25609 2.11009 2.50616 + vertex 1.25188 2.10976 2.50705 + vertex 1.25637 2.10577 2.50732 + endloop + endfacet + facet normal 0.178081 0.264795 0.947719 + outer loop + vertex 1.25188 2.10976 2.50705 + vertex 1.25174 2.10579 2.50819 + vertex 1.25637 2.10577 2.50732 + endloop + endfacet + facet normal 0.179665 0.264663 0.947457 + outer loop + vertex 1.25174 2.10579 2.50819 + vertex 1.25188 2.10976 2.50705 + vertex 1.24847 2.10747 2.50834 + endloop + endfacet + facet normal 0.180638 0.266615 0.946724 + outer loop + vertex 1.24868 2.10295 2.50957 + vertex 1.25174 2.10579 2.50819 + vertex 1.24847 2.10747 2.50834 + endloop + endfacet + facet normal 0.181607 0.266611 0.94654 + outer loop + vertex 1.24388 2.10709 2.50933 + vertex 1.24868 2.10295 2.50957 + vertex 1.24847 2.10747 2.50834 + endloop + endfacet + facet normal 0.181806 0.26518 0.946903 + outer loop + vertex 1.24847 2.10747 2.50834 + vertex 1.2462 2.11172 2.50758 + vertex 1.24388 2.10709 2.50933 + endloop + endfacet + facet normal 0.18042 0.265266 0.947144 + outer loop + vertex 1.24401 2.10275 2.51052 + vertex 1.24868 2.10295 2.50957 + vertex 1.24388 2.10709 2.50933 + endloop + endfacet + facet normal 0.18413 0.265184 0.946453 + outer loop + vertex 1.23994 2.10432 2.51087 + vertex 1.24401 2.10275 2.51052 + vertex 1.24388 2.10709 2.50933 + endloop + endfacet + facet normal 0.185074 0.263932 0.946619 + outer loop + vertex 1.23824 2.10906 2.50988 + vertex 1.23994 2.10432 2.51087 + vertex 1.24388 2.10709 2.50933 + endloop + endfacet + facet normal 0.186149 0.264256 0.946318 + outer loop + vertex 1.23994 2.10432 2.51087 + vertex 1.23824 2.10906 2.50988 + vertex 1.23592 2.10589 2.51122 + endloop + endfacet + facet normal 0.186581 0.265462 0.945895 + outer loop + vertex 1.23592 2.10589 2.51122 + vertex 1.23594 2.1017 2.51239 + vertex 1.23994 2.10432 2.51087 + endloop + endfacet + facet normal 0.184055 0.26902 0.945385 + outer loop + vertex 1.24161 2.09949 2.51192 + vertex 1.23994 2.10432 2.51087 + vertex 1.23594 2.1017 2.51239 + endloop + endfacet + facet normal 0.184509 0.270279 0.944937 + outer loop + vertex 1.23757 2.09689 2.51345 + vertex 1.24161 2.09949 2.51192 + vertex 1.23594 2.1017 2.51239 + endloop + endfacet + facet normal 0.181174 0.269353 0.945846 + outer loop + vertex 1.23757 2.09689 2.51345 + vertex 1.23594 2.1017 2.51239 + vertex 1.23351 2.09847 2.51378 + endloop + endfacet + facet normal 0.183785 0.267409 0.945894 + outer loop + vertex 1.23351 2.09847 2.51378 + vertex 1.23594 2.1017 2.51239 + vertex 1.23165 2.10129 2.51334 + endloop + endfacet + facet normal 0.181744 0.266184 0.946634 + outer loop + vertex 1.23351 2.09847 2.51378 + vertex 1.23165 2.10129 2.51334 + vertex 1.22887 2.09819 2.51475 + endloop + endfacet + facet normal 0.181223 0.270766 0.945433 + outer loop + vertex 1.22887 2.09819 2.51475 + vertex 1.2335 2.0943 2.51497 + vertex 1.23351 2.09847 2.51378 + endloop + endfacet + facet normal 0.178586 0.267712 0.946804 + outer loop + vertex 1.22917 2.0939 2.5159 + vertex 1.2335 2.0943 2.51497 + vertex 1.22887 2.09819 2.51475 + endloop + endfacet + facet normal 0.17771 0.267697 0.946973 + outer loop + vertex 1.22917 2.0939 2.5159 + vertex 1.22887 2.09819 2.51475 + vertex 1.2261 2.09512 2.51613 + endloop + endfacet + facet normal 0.178822 0.270691 0.945912 + outer loop + vertex 1.2261 2.09512 2.51613 + vertex 1.22639 2.09084 2.5173 + vertex 1.22917 2.0939 2.5159 + endloop + endfacet + facet normal 0.177648 0.271723 0.945837 + outer loop + vertex 1.23108 2.09105 2.51636 + vertex 1.22917 2.0939 2.5159 + vertex 1.22639 2.09084 2.5173 + endloop + endfacet + facet normal 0.177645 0.271753 0.945829 + outer loop + vertex 1.23108 2.09105 2.51636 + vertex 1.22639 2.09084 2.5173 + vertex 1.23122 2.08672 2.51758 + endloop + endfacet + facet normal 0.175555 0.271789 0.946209 + outer loop + vertex 1.23108 2.09105 2.51636 + vertex 1.23122 2.08672 2.51758 + vertex 1.23519 2.08949 2.51605 + endloop + endfacet + facet normal 0.181284 0.270726 0.945433 + outer loop + vertex 1.2261 2.09512 2.51613 + vertex 1.22194 2.09475 2.51704 + vertex 1.22639 2.09084 2.5173 + endloop + endfacet + facet normal 0.179169 0.268389 0.946502 + outer loop + vertex 1.22194 2.09475 2.51704 + vertex 1.22179 2.09082 2.51818 + vertex 1.22639 2.09084 2.5173 + endloop + endfacet + facet normal 0.179052 0.270398 0.945952 + outer loop + vertex 1.22336 2.08801 2.51869 + vertex 1.22639 2.09084 2.5173 + vertex 1.22179 2.09082 2.51818 + endloop + endfacet + facet normal 0.180689 0.271215 0.945407 + outer loop + vertex 1.22336 2.08801 2.51869 + vertex 1.22179 2.09082 2.51818 + vertex 1.21877 2.08798 2.51957 + endloop + endfacet + facet normal 0.180846 0.268622 0.946117 + outer loop + vertex 1.21877 2.08798 2.51957 + vertex 1.22325 2.08404 2.51983 + vertex 1.22336 2.08801 2.51869 + endloop + endfacet + facet normal 0.180483 0.268221 0.9463 + outer loop + vertex 1.21907 2.08369 2.52073 + vertex 1.22325 2.08404 2.51983 + vertex 1.21877 2.08798 2.51957 + endloop + endfacet + facet normal 0.181003 0.26823 0.946198 + outer loop + vertex 1.21907 2.08369 2.52073 + vertex 1.21877 2.08798 2.51957 + vertex 1.21601 2.08491 2.52097 + endloop + endfacet + facet normal 0.178379 0.261174 0.948667 + outer loop + vertex 1.21601 2.08491 2.52097 + vertex 1.21634 2.08058 2.5221 + vertex 1.21907 2.08369 2.52073 + endloop + endfacet + facet normal 0.179617 0.260113 0.948725 + outer loop + vertex 1.22094 2.08086 2.52115 + vertex 1.21907 2.08369 2.52073 + vertex 1.21634 2.08058 2.5221 + endloop + endfacet + facet normal 0.180445 0.261227 0.948262 + outer loop + vertex 1.21601 2.08491 2.52097 + vertex 1.21172 2.08448 2.52191 + vertex 1.21634 2.08058 2.5221 + endloop + endfacet + facet normal 0.180349 0.261116 0.94831 + outer loop + vertex 1.21172 2.08448 2.52191 + vertex 1.21171 2.08028 2.52307 + vertex 1.21634 2.08058 2.5221 + endloop + endfacet + facet normal 0.179595 0.266715 0.946894 + outer loop + vertex 1.21601 2.08491 2.52097 + vertex 1.21412 2.08774 2.52053 + vertex 1.21172 2.08448 2.52191 + endloop + endfacet + facet normal 0.180836 0.265809 0.946913 + outer loop + vertex 1.21412 2.08774 2.52053 + vertex 1.21007 2.08929 2.52087 + vertex 1.21172 2.08448 2.52191 + endloop + endfacet + facet normal 0.181124 0.265891 0.946835 + outer loop + vertex 1.21172 2.08448 2.52191 + vertex 1.21007 2.08929 2.52087 + vertex 1.20604 2.0867 2.52237 + endloop + endfacet + facet normal 0.179663 0.261868 0.948233 + outer loop + vertex 1.20765 2.08186 2.5234 + vertex 1.21172 2.08448 2.52191 + vertex 1.20604 2.0867 2.52237 + endloop + endfacet + facet normal 0.18153 0.262385 0.947735 + outer loop + vertex 1.20765 2.08186 2.5234 + vertex 1.20604 2.0867 2.52237 + vertex 1.2036 2.08345 2.52374 + endloop + endfacet + facet normal 0.181575 0.262351 0.947735 + outer loop + vertex 1.2036 2.08345 2.52374 + vertex 1.20604 2.0867 2.52237 + vertex 1.20172 2.08633 2.5233 + endloop + endfacet + facet normal 0.181188 0.262119 0.947874 + outer loop + vertex 1.2036 2.08345 2.52374 + vertex 1.20172 2.08633 2.5233 + vertex 1.19894 2.0832 2.5247 + endloop + endfacet + facet normal 0.181746 0.256897 0.949196 + outer loop + vertex 1.19894 2.0832 2.5247 + vertex 1.20355 2.07926 2.52488 + vertex 1.2036 2.08345 2.52374 + endloop + endfacet + facet normal 0.181712 0.261665 0.947899 + outer loop + vertex 1.19894 2.0832 2.5247 + vertex 1.20172 2.08633 2.5233 + vertex 1.19861 2.08759 2.52355 + endloop + endfacet + facet normal 0.184717 0.261737 0.947298 + outer loop + vertex 1.19434 2.0871 2.52451 + vertex 1.19894 2.0832 2.5247 + vertex 1.19861 2.08759 2.52355 + endloop + endfacet + facet normal 0.185138 0.259232 0.947904 + outer loop + vertex 1.19861 2.08759 2.52355 + vertex 1.19666 2.0905 2.52313 + vertex 1.19434 2.0871 2.52451 + endloop + endfacet + facet normal 0.187671 0.257497 0.947879 + outer loop + vertex 1.19434 2.0871 2.52451 + vertex 1.19666 2.0905 2.52313 + vertex 1.19276 2.09179 2.52355 + endloop + endfacet + facet normal 0.187718 0.25751 0.947866 + outer loop + vertex 1.19434 2.0871 2.52451 + vertex 1.19276 2.09179 2.52355 + vertex 1.18877 2.08928 2.52503 + endloop + endfacet + facet normal 0.187342 0.256466 0.948224 + outer loop + vertex 1.18877 2.08928 2.52503 + vertex 1.19031 2.08442 2.52604 + vertex 1.19434 2.0871 2.52451 + endloop + endfacet + facet normal 0.18493 0.259849 0.947776 + outer loop + vertex 1.19031 2.08442 2.52604 + vertex 1.19432 2.08289 2.52567 + vertex 1.19434 2.0871 2.52451 + endloop + endfacet + facet normal 0.183864 0.256822 0.948808 + outer loop + vertex 1.19432 2.08289 2.52567 + vertex 1.19031 2.08442 2.52604 + vertex 1.19186 2.07959 2.52704 + endloop + endfacet + facet normal 0.183113 0.257379 0.948802 + outer loop + vertex 1.19615 2.08007 2.52609 + vertex 1.19432 2.08289 2.52567 + vertex 1.19186 2.07959 2.52704 + endloop + endfacet + facet normal 0.184373 0.249667 0.950617 + outer loop + vertex 1.19615 2.08007 2.52609 + vertex 1.19186 2.07959 2.52704 + vertex 1.19643 2.07571 2.52718 + endloop + endfacet + facet normal 0.181384 0.249619 0.951205 + outer loop + vertex 1.19615 2.08007 2.52609 + vertex 1.19643 2.07571 2.52718 + vertex 1.19922 2.07886 2.52582 + endloop + endfacet + facet normal 0.184077 0.257035 0.948709 + outer loop + vertex 1.19922 2.07886 2.52582 + vertex 1.19894 2.0832 2.5247 + vertex 1.19615 2.08007 2.52609 + endloop + endfacet + facet normal 0.181839 0.257004 0.949149 + outer loop + vertex 1.19922 2.07886 2.52582 + vertex 1.20355 2.07926 2.52488 + vertex 1.19894 2.0832 2.5247 + endloop + endfacet + facet normal 0.182977 0.249076 0.951042 + outer loop + vertex 1.19922 2.07886 2.52582 + vertex 1.20107 2.07601 2.52621 + vertex 1.20355 2.07926 2.52488 + endloop + endfacet + facet normal 0.182403 0.248732 0.951242 + outer loop + vertex 1.20107 2.07601 2.52621 + vertex 1.19922 2.07886 2.52582 + vertex 1.19643 2.07571 2.52718 + endloop + endfacet + facet normal 0.183037 0.243157 0.952561 + outer loop + vertex 1.20107 2.07601 2.52621 + vertex 1.19643 2.07571 2.52718 + vertex 1.20102 2.07179 2.5273 + endloop + endfacet + facet normal 0.181174 0.243263 0.95289 + outer loop + vertex 1.20107 2.07601 2.52621 + vertex 1.20102 2.07179 2.5273 + vertex 1.20513 2.07442 2.52584 + endloop + endfacet + facet normal 0.181538 0.241425 0.953288 + outer loop + vertex 1.19643 2.07571 2.52718 + vertex 1.1967 2.07136 2.52823 + vertex 1.20102 2.07179 2.5273 + endloop + endfacet + facet normal 0.181273 0.243215 0.952883 + outer loop + vertex 1.19854 2.06851 2.5286 + vertex 1.20102 2.07179 2.5273 + vertex 1.1967 2.07136 2.52823 + endloop + endfacet + facet normal 0.182794 0.244126 0.95236 + outer loop + vertex 1.19854 2.06851 2.5286 + vertex 1.1967 2.07136 2.52823 + vertex 1.19389 2.06821 2.52957 + endloop + endfacet + facet normal 0.180959 0.259996 0.948502 + outer loop + vertex 1.19389 2.06821 2.52957 + vertex 1.19848 2.06427 2.52978 + vertex 1.19854 2.06851 2.5286 + endloop + endfacet + facet normal 0.170137 0.247633 0.953798 + outer loop + vertex 1.19416 2.06385 2.53066 + vertex 1.19848 2.06427 2.52978 + vertex 1.19389 2.06821 2.52957 + endloop + endfacet + facet normal 0.177174 0.247744 0.952487 + outer loop + vertex 1.19416 2.06385 2.53066 + vertex 1.19389 2.06821 2.52957 + vertex 1.19108 2.06505 2.53092 + endloop + endfacet + facet normal 0.181977 0.261016 0.948027 + outer loop + vertex 1.19108 2.06505 2.53092 + vertex 1.1914 2.06065 2.53207 + vertex 1.19416 2.06385 2.53066 + endloop + endfacet + facet normal 0.167354 0.273302 0.947259 + outer loop + vertex 1.19603 2.06098 2.53115 + vertex 1.19416 2.06385 2.53066 + vertex 1.1914 2.06065 2.53207 + endloop + endfacet + facet normal 0.166492 0.280195 0.945395 + outer loop + vertex 1.19603 2.06098 2.53115 + vertex 1.1914 2.06065 2.53207 + vertex 1.19603 2.05672 2.53242 + endloop + endfacet + facet normal 0.156324 0.280657 0.946992 + outer loop + vertex 1.19603 2.06098 2.53115 + vertex 1.19603 2.05672 2.53242 + vertex 1.20008 2.05939 2.53096 + endloop + endfacet + facet normal 0.160115 0.272967 0.948605 + outer loop + vertex 1.1914 2.06065 2.53207 + vertex 1.19173 2.05624 2.53328 + vertex 1.19603 2.05672 2.53242 + endloop + endfacet + facet normal 0.182575 0.261028 0.947909 + outer loop + vertex 1.19108 2.06505 2.53092 + vertex 1.18681 2.06456 2.53188 + vertex 1.1914 2.06065 2.53207 + endloop + endfacet + facet normal 0.185887 0.241139 0.952522 + outer loop + vertex 1.19108 2.06505 2.53092 + vertex 1.18927 2.06788 2.53056 + vertex 1.18681 2.06456 2.53188 + endloop + endfacet + facet normal 0.185202 0.24073 0.952759 + outer loop + vertex 1.18927 2.06788 2.53056 + vertex 1.19108 2.06505 2.53092 + vertex 1.19389 2.06821 2.52957 + endloop + endfacet + facet normal 0.185529 0.238 0.953381 + outer loop + vertex 1.18927 2.06788 2.53056 + vertex 1.19389 2.06821 2.52957 + vertex 1.18934 2.07209 2.52949 + endloop + endfacet + facet normal 0.189271 0.237762 0.952704 + outer loop + vertex 1.18527 2.06942 2.53096 + vertex 1.18927 2.06788 2.53056 + vertex 1.18934 2.07209 2.52949 + endloop + endfacet + facet normal 0.187295 0.240048 0.952522 + outer loop + vertex 1.18934 2.07209 2.52949 + vertex 1.19389 2.06821 2.52957 + vertex 1.19363 2.07256 2.52853 + endloop + endfacet + facet normal 0.18688 0.24267 0.951939 + outer loop + vertex 1.19363 2.07256 2.52853 + vertex 1.19181 2.07538 2.52817 + vertex 1.18934 2.07209 2.52949 + endloop + endfacet + facet normal 0.184401 0.244536 0.951945 + outer loop + vertex 1.18934 2.07209 2.52949 + vertex 1.19181 2.07538 2.52817 + vertex 1.1878 2.07692 2.52855 + endloop + endfacet + facet normal 0.188565 0.245653 0.950841 + outer loop + vertex 1.18934 2.07209 2.52949 + vertex 1.1878 2.07692 2.52855 + vertex 1.18371 2.07431 2.53003 + endloop + endfacet + facet normal 0.185783 0.249734 0.950325 + outer loop + vertex 1.18371 2.07431 2.53003 + vertex 1.1878 2.07692 2.52855 + vertex 1.18375 2.07853 2.52892 + endloop + endfacet + facet normal 0.187449 0.254259 0.948797 + outer loop + vertex 1.1878 2.07692 2.52855 + vertex 1.18622 2.08179 2.52755 + vertex 1.18375 2.07853 2.52892 + endloop + endfacet + facet normal 0.186953 0.254633 0.948794 + outer loop + vertex 1.18375 2.07853 2.52892 + vertex 1.18622 2.08179 2.52755 + vertex 1.18187 2.08147 2.5285 + endloop + endfacet + facet normal 0.185722 0.253907 0.94923 + outer loop + vertex 1.18375 2.07853 2.52892 + vertex 1.18187 2.08147 2.5285 + vertex 1.179 2.0785 2.52985 + endloop + endfacet + facet normal 0.186389 0.253281 0.949267 + outer loop + vertex 1.179 2.0785 2.52985 + vertex 1.18187 2.08147 2.5285 + vertex 1.17868 2.08295 2.52873 + endloop + endfacet + facet normal 0.186913 0.253293 0.949161 + outer loop + vertex 1.17402 2.08299 2.52964 + vertex 1.179 2.0785 2.52985 + vertex 1.17868 2.08295 2.52873 + endloop + endfacet + facet normal 0.187002 0.251124 0.949719 + outer loop + vertex 1.17868 2.08295 2.52873 + vertex 1.17687 2.08601 2.52828 + vertex 1.17402 2.08299 2.52964 + endloop + endfacet + facet normal 0.188557 0.251965 0.949189 + outer loop + vertex 1.17868 2.08295 2.52873 + vertex 1.18152 2.08598 2.52736 + vertex 1.17687 2.08601 2.52828 + endloop + endfacet + facet normal 0.188814 0.246173 0.950657 + outer loop + vertex 1.17644 2.09061 2.52717 + vertex 1.17687 2.08601 2.52828 + vertex 1.18152 2.08598 2.52736 + endloop + endfacet + facet normal 0.18804 0.246141 0.950818 + outer loop + vertex 1.17687 2.08601 2.52828 + vertex 1.17644 2.09061 2.52717 + vertex 1.17365 2.08752 2.52852 + endloop + endfacet + facet normal 0.186599 0.25376 0.949098 + outer loop + vertex 1.18187 2.08147 2.5285 + vertex 1.18152 2.08598 2.52736 + vertex 1.17868 2.08295 2.52873 + endloop + endfacet + facet normal 0.187062 0.253772 0.949003 + outer loop + vertex 1.18152 2.08598 2.52736 + vertex 1.18187 2.08147 2.5285 + vertex 1.18622 2.08179 2.52755 + endloop + endfacet + facet normal 0.18968 0.256649 0.947709 + outer loop + vertex 1.18627 2.08603 2.5264 + vertex 1.18152 2.08598 2.52736 + vertex 1.18622 2.08179 2.52755 + endloop + endfacet + facet normal 0.186835 0.256824 0.948227 + outer loop + vertex 1.18627 2.08603 2.5264 + vertex 1.18622 2.08179 2.52755 + vertex 1.19031 2.08442 2.52604 + endloop + endfacet + facet normal 0.189861 0.253741 0.948456 + outer loop + vertex 1.18627 2.08603 2.5264 + vertex 1.18442 2.089 2.52597 + vertex 1.18152 2.08598 2.52736 + endloop + endfacet + facet normal 0.192752 0.251031 0.948594 + outer loop + vertex 1.1812 2.0905 2.52623 + vertex 1.18152 2.08598 2.52736 + vertex 1.18442 2.089 2.52597 + endloop + endfacet + facet normal 0.191144 0.247367 0.949881 + outer loop + vertex 1.18442 2.089 2.52597 + vertex 1.18418 2.09358 2.52483 + vertex 1.1812 2.0905 2.52623 + endloop + endfacet + facet normal 0.194139 0.244533 0.950007 + outer loop + vertex 1.17937 2.09363 2.5258 + vertex 1.1812 2.0905 2.52623 + vertex 1.18418 2.09358 2.52483 + endloop + endfacet + facet normal 0.19433 0.239851 0.951161 + outer loop + vertex 1.17937 2.09363 2.5258 + vertex 1.18418 2.09358 2.52483 + vertex 1.17898 2.09828 2.5247 + endloop + endfacet + facet normal 0.195 0.239874 0.951018 + outer loop + vertex 1.17937 2.09363 2.5258 + vertex 1.17898 2.09828 2.5247 + vertex 1.17603 2.09528 2.52607 + endloop + endfacet + facet normal 0.195944 0.241889 0.950313 + outer loop + vertex 1.17603 2.09528 2.52607 + vertex 1.17644 2.09061 2.52717 + vertex 1.17937 2.09363 2.5258 + endloop + endfacet + facet normal 0.196023 0.241892 0.950297 + outer loop + vertex 1.17603 2.09528 2.52607 + vertex 1.17129 2.0953 2.52704 + vertex 1.17644 2.09061 2.52717 + endloop + endfacet + facet normal 0.191655 0.237144 0.952382 + outer loop + vertex 1.17129 2.0953 2.52704 + vertex 1.17168 2.09058 2.52814 + vertex 1.17644 2.09061 2.52717 + endloop + endfacet + facet normal 0.196192 0.238222 0.951188 + outer loop + vertex 1.17603 2.09528 2.52607 + vertex 1.17422 2.09842 2.52565 + vertex 1.17129 2.0953 2.52704 + endloop + endfacet + facet normal 0.197938 0.236601 0.951231 + outer loop + vertex 1.17105 2.09993 2.52594 + vertex 1.17129 2.0953 2.52704 + vertex 1.17422 2.09842 2.52565 + endloop + endfacet + facet normal 0.199356 0.239781 0.950138 + outer loop + vertex 1.17422 2.09842 2.52565 + vertex 1.17393 2.10294 2.52457 + vertex 1.17105 2.09993 2.52594 + endloop + endfacet + facet normal 0.196499 0.239745 0.950742 + outer loop + vertex 1.17422 2.09842 2.52565 + vertex 1.17898 2.09828 2.5247 + vertex 1.17393 2.10294 2.52457 + endloop + endfacet + facet normal 0.197419 0.240729 0.950303 + outer loop + vertex 1.17393 2.10294 2.52457 + vertex 1.17898 2.09828 2.5247 + vertex 1.17857 2.10289 2.52362 + endloop + endfacet + facet normal 0.197207 0.246191 0.948947 + outer loop + vertex 1.17857 2.10289 2.52362 + vertex 1.17677 2.10596 2.5232 + vertex 1.17393 2.10294 2.52457 + endloop + endfacet + facet normal 0.196789 0.246576 0.948933 + outer loop + vertex 1.17393 2.10294 2.52457 + vertex 1.17677 2.10596 2.5232 + vertex 1.17359 2.10745 2.52347 + endloop + endfacet + facet normal 0.199698 0.246641 0.948309 + outer loop + vertex 1.16931 2.10712 2.52446 + vertex 1.17393 2.10294 2.52457 + vertex 1.17359 2.10745 2.52347 + endloop + endfacet + facet normal 0.198821 0.253326 0.946729 + outer loop + vertex 1.17359 2.10745 2.52347 + vertex 1.17173 2.11037 2.52308 + vertex 1.16931 2.10712 2.52446 + endloop + endfacet + facet normal 0.198987 0.253201 0.946728 + outer loop + vertex 1.16931 2.10712 2.52446 + vertex 1.17173 2.11037 2.52308 + vertex 1.16776 2.11194 2.52349 + endloop + endfacet + facet normal 0.201468 0.253857 0.946027 + outer loop + vertex 1.16931 2.10712 2.52446 + vertex 1.16776 2.11194 2.52349 + vertex 1.16376 2.10932 2.52505 + endloop + endfacet + facet normal 0.199596 0.248655 0.947804 + outer loop + vertex 1.16376 2.10932 2.52505 + vertex 1.16529 2.10447 2.526 + vertex 1.16931 2.10712 2.52446 + endloop + endfacet + facet normal 0.20133 0.246185 0.948082 + outer loop + vertex 1.16529 2.10447 2.526 + vertex 1.16924 2.1029 2.52557 + vertex 1.16931 2.10712 2.52446 + endloop + endfacet + facet normal 0.198908 0.239511 0.9503 + outer loop + vertex 1.16924 2.1029 2.52557 + vertex 1.16529 2.10447 2.526 + vertex 1.16679 2.09959 2.52692 + endloop + endfacet + facet normal 0.199432 0.239118 0.950289 + outer loop + vertex 1.17105 2.09993 2.52594 + vertex 1.16924 2.1029 2.52557 + vertex 1.16679 2.09959 2.52692 + endloop + endfacet + facet normal 0.199824 0.239339 0.950151 + outer loop + vertex 1.16924 2.1029 2.52557 + vertex 1.17105 2.09993 2.52594 + vertex 1.17393 2.10294 2.52457 + endloop + endfacet + facet normal 0.20371 0.240731 0.948974 + outer loop + vertex 1.16679 2.09959 2.52692 + vertex 1.16529 2.10447 2.526 + vertex 1.1613 2.10178 2.52754 + endloop + endfacet + facet normal 0.201648 0.235021 0.950843 + outer loop + vertex 1.16286 2.09702 2.52839 + vertex 1.16679 2.09959 2.52692 + vertex 1.1613 2.10178 2.52754 + endloop + endfacet + facet normal 0.201744 0.243483 0.948692 + outer loop + vertex 1.16133 2.10605 2.52644 + vertex 1.1613 2.10178 2.52754 + vertex 1.16529 2.10447 2.526 + endloop + endfacet + facet normal 0.203012 0.24341 0.94844 + outer loop + vertex 1.16133 2.10605 2.52644 + vertex 1.15663 2.10597 2.52746 + vertex 1.1613 2.10178 2.52754 + endloop + endfacet + facet normal 0.204018 0.249815 0.946556 + outer loop + vertex 1.16529 2.10447 2.526 + vertex 1.16376 2.10932 2.52505 + vertex 1.16133 2.10605 2.52644 + endloop + endfacet + facet normal 0.200648 0.257819 0.945129 + outer loop + vertex 1.17173 2.11037 2.52308 + vertex 1.17176 2.11456 2.52193 + vertex 1.16776 2.11194 2.52349 + endloop + endfacet + facet normal 0.201333 0.256843 0.945249 + outer loop + vertex 1.16776 2.11194 2.52349 + vertex 1.17176 2.11456 2.52193 + vertex 1.16621 2.11675 2.52252 + endloop + endfacet + facet normal 0.200852 0.256715 0.945387 + outer loop + vertex 1.16776 2.11194 2.52349 + vertex 1.16621 2.11675 2.52252 + vertex 1.1638 2.1135 2.52392 + endloop + endfacet + facet normal 0.201539 0.25742 0.945049 + outer loop + vertex 1.17176 2.11456 2.52193 + vertex 1.1702 2.11939 2.52095 + vertex 1.16621 2.11675 2.52252 + endloop + endfacet + facet normal 0.202509 0.256048 0.945214 + outer loop + vertex 1.16624 2.12094 2.52138 + vertex 1.16621 2.11675 2.52252 + vertex 1.1702 2.11939 2.52095 + endloop + endfacet + facet normal 0.202028 0.254692 0.945683 + outer loop + vertex 1.1702 2.11939 2.52095 + vertex 1.16867 2.1242 2.51998 + vertex 1.16624 2.12094 2.52138 + endloop + endfacet + facet normal 0.202986 0.254942 0.94541 + outer loop + vertex 1.16867 2.1242 2.51998 + vertex 1.1702 2.11939 2.52095 + vertex 1.17421 2.12203 2.51938 + endloop + endfacet + facet normal 0.203032 0.25507 0.945366 + outer loop + vertex 1.17421 2.12203 2.51938 + vertex 1.17267 2.12683 2.51841 + vertex 1.16867 2.1242 2.51998 + endloop + endfacet + facet normal 0.203121 0.255094 0.945341 + outer loop + vertex 1.17421 2.12203 2.51938 + vertex 1.17662 2.12529 2.51798 + vertex 1.17267 2.12683 2.51841 + endloop + endfacet + facet normal 0.202837 0.254286 0.945619 + outer loop + vertex 1.17662 2.12529 2.51798 + vertex 1.17666 2.12949 2.51684 + vertex 1.17267 2.12683 2.51841 + endloop + endfacet + facet normal 0.205043 0.251172 0.945976 + outer loop + vertex 1.17267 2.12683 2.51841 + vertex 1.17666 2.12949 2.51684 + vertex 1.17117 2.13166 2.51746 + endloop + endfacet + facet normal 0.201696 0.254358 0.945844 + outer loop + vertex 1.17666 2.12949 2.51684 + vertex 1.17662 2.12529 2.51798 + vertex 1.18131 2.12536 2.51696 + endloop + endfacet + facet normal 0.203791 0.256687 0.944765 + outer loop + vertex 1.18092 2.12987 2.51582 + vertex 1.17666 2.12949 2.51684 + vertex 1.18131 2.12536 2.51696 + endloop + endfacet + facet normal 0.202835 0.256658 0.944979 + outer loop + vertex 1.18092 2.12987 2.51582 + vertex 1.18131 2.12536 2.51696 + vertex 1.18411 2.12838 2.51554 + endloop + endfacet + facet normal 0.201826 0.25434 0.945821 + outer loop + vertex 1.18411 2.12838 2.51554 + vertex 1.1838 2.13286 2.5144 + vertex 1.18092 2.12987 2.51582 + endloop + endfacet + facet normal 0.204254 0.252045 0.945914 + outer loop + vertex 1.17911 2.13277 2.51544 + vertex 1.18092 2.12987 2.51582 + vertex 1.1838 2.13286 2.5144 + endloop + endfacet + facet normal 0.203254 0.254361 0.945509 + outer loop + vertex 1.18411 2.12838 2.51554 + vertex 1.18887 2.12811 2.51459 + vertex 1.1838 2.13286 2.5144 + endloop + endfacet + facet normal 0.206288 0.257543 0.94399 + outer loop + vertex 1.1838 2.13286 2.5144 + vertex 1.18887 2.12811 2.51459 + vertex 1.18845 2.13274 2.51342 + endloop + endfacet + facet normal 0.206556 0.257552 0.943929 + outer loop + vertex 1.18887 2.12811 2.51459 + vertex 1.19177 2.13095 2.51318 + vertex 1.18845 2.13274 2.51342 + endloop + endfacet + facet normal 0.204216 0.252972 0.945675 + outer loop + vertex 1.19177 2.13095 2.51318 + vertex 1.19134 2.13558 2.51203 + vertex 1.18845 2.13274 2.51342 + endloop + endfacet + facet normal 0.206041 0.253036 0.945262 + outer loop + vertex 1.19134 2.13558 2.51203 + vertex 1.19177 2.13095 2.51318 + vertex 1.19652 2.13058 2.51224 + endloop + endfacet + facet normal 0.212351 0.259429 0.942127 + outer loop + vertex 1.1961 2.13517 2.51107 + vertex 1.19134 2.13558 2.51203 + vertex 1.19652 2.13058 2.51224 + endloop + endfacet + facet normal 0.211194 0.259393 0.942397 + outer loop + vertex 1.1961 2.13517 2.51107 + vertex 1.19652 2.13058 2.51224 + vertex 1.19939 2.1334 2.51082 + endloop + endfacet + facet normal 0.207501 0.252148 0.94518 + outer loop + vertex 1.19939 2.1334 2.51082 + vertex 1.19899 2.13803 2.50968 + vertex 1.1961 2.13517 2.51107 + endloop + endfacet + facet normal 0.207395 0.263173 0.942193 + outer loop + vertex 1.2012 2.13031 2.51129 + vertex 1.19939 2.1334 2.51082 + vertex 1.19652 2.13058 2.51224 + endloop + endfacet + facet normal 0.206212 0.260289 0.943253 + outer loop + vertex 1.19364 2.12774 2.51365 + vertex 1.19652 2.13058 2.51224 + vertex 1.19177 2.13095 2.51318 + endloop + endfacet + facet normal 0.203358 0.2631 0.943093 + outer loop + vertex 1.19691 2.12603 2.51343 + vertex 1.19652 2.13058 2.51224 + vertex 1.19364 2.12774 2.51365 + endloop + endfacet + facet normal 0.203447 0.263279 0.943024 + outer loop + vertex 1.19397 2.12328 2.51483 + vertex 1.19691 2.12603 2.51343 + vertex 1.19364 2.12774 2.51365 + endloop + endfacet + facet normal 0.204726 0.263299 0.942741 + outer loop + vertex 1.18887 2.12811 2.51459 + vertex 1.19397 2.12328 2.51483 + vertex 1.19364 2.12774 2.51365 + endloop + endfacet + facet normal 0.201291 0.259753 0.944463 + outer loop + vertex 1.18931 2.12352 2.51576 + vertex 1.19397 2.12328 2.51483 + vertex 1.18887 2.12811 2.51459 + endloop + endfacet + facet normal 0.201948 0.259778 0.944316 + outer loop + vertex 1.18931 2.12352 2.51576 + vertex 1.18887 2.12811 2.51459 + vertex 1.18598 2.12525 2.51599 + endloop + endfacet + facet normal 0.201968 0.259819 0.9443 + outer loop + vertex 1.18598 2.12525 2.51599 + vertex 1.18644 2.12066 2.51716 + vertex 1.18931 2.12352 2.51576 + endloop + endfacet + facet normal 0.200535 0.261216 0.94422 + outer loop + vertex 1.19117 2.12039 2.51623 + vertex 1.18931 2.12352 2.51576 + vertex 1.18644 2.12066 2.51716 + endloop + endfacet + facet normal 0.200539 0.263729 0.943521 + outer loop + vertex 1.19117 2.12039 2.51623 + vertex 1.18644 2.12066 2.51716 + vertex 1.19153 2.11596 2.51739 + endloop + endfacet + facet normal 0.198936 0.263692 0.94387 + outer loop + vertex 1.19117 2.12039 2.51623 + vertex 1.19153 2.11596 2.51739 + vertex 1.19434 2.11886 2.51599 + endloop + endfacet + facet normal 0.198981 0.263792 0.943833 + outer loop + vertex 1.19434 2.11886 2.51599 + vertex 1.19397 2.12328 2.51483 + vertex 1.19117 2.12039 2.51623 + endloop + endfacet + facet normal 0.196582 0.263729 0.944353 + outer loop + vertex 1.19434 2.11886 2.51599 + vertex 1.1985 2.11911 2.51505 + vertex 1.19397 2.12328 2.51483 + endloop + endfacet + facet normal 0.200518 0.267896 0.94235 + outer loop + vertex 1.19397 2.12328 2.51483 + vertex 1.1985 2.11911 2.51505 + vertex 1.1986 2.12305 2.51391 + endloop + endfacet + facet normal 0.19618 0.268246 0.943164 + outer loop + vertex 1.1985 2.11911 2.51505 + vertex 1.20183 2.12135 2.51372 + vertex 1.1986 2.12305 2.51391 + endloop + endfacet + facet normal 0.197 0.269866 0.94253 + outer loop + vertex 1.20183 2.12135 2.51372 + vertex 1.20153 2.12592 2.51248 + vertex 1.1986 2.12305 2.51391 + endloop + endfacet + facet normal 0.200594 0.266319 0.942781 + outer loop + vertex 1.1986 2.12305 2.51391 + vertex 1.20153 2.12592 2.51248 + vertex 1.19691 2.12603 2.51343 + endloop + endfacet + facet normal 0.194459 0.270617 0.942843 + outer loop + vertex 1.20407 2.11716 2.51446 + vertex 1.20183 2.12135 2.51372 + vertex 1.1985 2.11911 2.51505 + endloop + endfacet + facet normal 0.193187 0.266567 0.944257 + outer loop + vertex 1.1985 2.11911 2.51505 + vertex 1.2002 2.11446 2.51602 + vertex 1.20407 2.11716 2.51446 + endloop + endfacet + facet normal 0.192225 0.267848 0.944091 + outer loop + vertex 1.2002 2.11446 2.51602 + vertex 1.20421 2.11292 2.51564 + vertex 1.20407 2.11716 2.51446 + endloop + endfacet + facet normal 0.192028 0.267852 0.944129 + outer loop + vertex 1.20421 2.11292 2.51564 + vertex 1.20893 2.11293 2.51468 + vertex 1.20407 2.11716 2.51446 + endloop + endfacet + facet normal 0.191901 0.267709 0.944196 + outer loop + vertex 1.20407 2.11716 2.51446 + vertex 1.20893 2.11293 2.51468 + vertex 1.20859 2.11751 2.51344 + endloop + endfacet + facet normal 0.191291 0.2722 0.943035 + outer loop + vertex 1.20859 2.11751 2.51344 + vertex 1.20633 2.12174 2.51268 + vertex 1.20407 2.11716 2.51446 + endloop + endfacet + facet normal 0.191649 0.272369 0.942913 + outer loop + vertex 1.20859 2.11751 2.51344 + vertex 1.21195 2.11979 2.5121 + vertex 1.20633 2.12174 2.51268 + endloop + endfacet + facet normal 0.19181 0.272151 0.942944 + outer loop + vertex 1.21187 2.1158 2.51327 + vertex 1.21195 2.11979 2.5121 + vertex 1.20859 2.11751 2.51344 + endloop + endfacet + facet normal 0.191717 0.272158 0.942961 + outer loop + vertex 1.21195 2.11979 2.5121 + vertex 1.21187 2.1158 2.51327 + vertex 1.21646 2.11581 2.51234 + endloop + endfacet + facet normal 0.191347 0.271752 0.943153 + outer loop + vertex 1.21613 2.12012 2.51116 + vertex 1.21195 2.11979 2.5121 + vertex 1.21646 2.11581 2.51234 + endloop + endfacet + facet normal 0.189761 0.271722 0.943482 + outer loop + vertex 1.21613 2.12012 2.51116 + vertex 1.21646 2.11581 2.51234 + vertex 1.21919 2.11883 2.51092 + endloop + endfacet + facet normal 0.191274 0.275572 0.942058 + outer loop + vertex 1.21919 2.11883 2.51092 + vertex 1.21887 2.12312 2.50973 + vertex 1.21613 2.12012 2.51116 + endloop + endfacet + facet normal 0.190887 0.275565 0.942139 + outer loop + vertex 1.21919 2.11883 2.51092 + vertex 1.22337 2.11913 2.50998 + vertex 1.21887 2.12312 2.50973 + endloop + endfacet + facet normal 0.191574 0.27632 0.941779 + outer loop + vertex 1.21887 2.12312 2.50973 + vertex 1.22337 2.11913 2.50998 + vertex 1.22343 2.12313 2.50879 + endloop + endfacet + facet normal 0.191485 0.277778 0.941368 + outer loop + vertex 1.22343 2.12313 2.50879 + vertex 1.22172 2.12603 2.50829 + vertex 1.21887 2.12312 2.50973 + endloop + endfacet + facet normal 0.192861 0.278505 0.940872 + outer loop + vertex 1.22343 2.12313 2.50879 + vertex 1.22635 2.12597 2.50736 + vertex 1.22172 2.12603 2.50829 + endloop + endfacet + facet normal 0.192057 0.279297 0.940801 + outer loop + vertex 1.22672 2.1214 2.50864 + vertex 1.22635 2.12597 2.50736 + vertex 1.22343 2.12313 2.50879 + endloop + endfacet + facet normal 0.190582 0.276388 0.94196 + outer loop + vertex 1.22337 2.11913 2.50998 + vertex 1.22672 2.1214 2.50864 + vertex 1.22343 2.12313 2.50879 + endloop + endfacet + facet normal 0.19094 0.275901 0.94203 + outer loop + vertex 1.22903 2.11713 2.50942 + vertex 1.22672 2.1214 2.50864 + vertex 1.22337 2.11913 2.50998 + endloop + endfacet + facet normal 0.189437 0.271183 0.943702 + outer loop + vertex 1.22337 2.11913 2.50998 + vertex 1.22511 2.11439 2.511 + vertex 1.22903 2.11713 2.50942 + endloop + endfacet + facet normal 0.189634 0.270921 0.943738 + outer loop + vertex 1.22511 2.11439 2.511 + vertex 1.22916 2.11282 2.51063 + vertex 1.22903 2.11713 2.50942 + endloop + endfacet + facet normal 0.18843 0.270948 0.943971 + outer loop + vertex 1.22916 2.11282 2.51063 + vertex 1.2338 2.11301 2.50965 + vertex 1.22903 2.11713 2.50942 + endloop + endfacet + facet normal 0.188674 0.271223 0.943843 + outer loop + vertex 1.22903 2.11713 2.50942 + vertex 1.2338 2.11301 2.50965 + vertex 1.23358 2.11748 2.50841 + endloop + endfacet + facet normal 0.187834 0.277513 0.942181 + outer loop + vertex 1.23358 2.11748 2.50841 + vertex 1.23128 2.12169 2.50763 + vertex 1.22903 2.11713 2.50942 + endloop + endfacet + facet normal 0.187295 0.277254 0.942365 + outer loop + vertex 1.23358 2.11748 2.50841 + vertex 1.23693 2.11971 2.50709 + vertex 1.23128 2.12169 2.50763 + endloop + endfacet + facet normal 0.188031 0.276239 0.942516 + outer loop + vertex 1.23681 2.11581 2.50825 + vertex 1.23693 2.11971 2.50709 + vertex 1.23358 2.11748 2.50841 + endloop + endfacet + facet normal 0.185983 0.276406 0.942873 + outer loop + vertex 1.23693 2.11971 2.50709 + vertex 1.23681 2.11581 2.50825 + vertex 1.2414 2.11582 2.50735 + endloop + endfacet + facet normal 0.186359 0.276824 0.942676 + outer loop + vertex 1.24108 2.12005 2.50617 + vertex 1.23693 2.11971 2.50709 + vertex 1.2414 2.11582 2.50735 + endloop + endfacet + facet normal 0.182268 0.276751 0.943497 + outer loop + vertex 1.24108 2.12005 2.50617 + vertex 1.2414 2.11582 2.50735 + vertex 1.24415 2.11885 2.50593 + endloop + endfacet + facet normal 0.185161 0.284699 0.940565 + outer loop + vertex 1.24415 2.11885 2.50593 + vertex 1.24379 2.12309 2.50471 + vertex 1.24108 2.12005 2.50617 + endloop + endfacet + facet normal 0.182153 0.284623 0.941175 + outer loop + vertex 1.24415 2.11885 2.50593 + vertex 1.24845 2.11925 2.50497 + vertex 1.24379 2.12309 2.50471 + endloop + endfacet + facet normal 0.183566 0.286284 0.940396 + outer loop + vertex 1.24379 2.12309 2.50471 + vertex 1.24845 2.11925 2.50497 + vertex 1.24844 2.12332 2.50374 + endloop + endfacet + facet normal 0.18293 0.292149 0.938715 + outer loop + vertex 1.24844 2.12332 2.50374 + vertex 1.24665 2.12602 2.50324 + vertex 1.24379 2.12309 2.50471 + endloop + endfacet + facet normal 0.179246 0.286506 0.941162 + outer loop + vertex 1.24845 2.11925 2.50497 + vertex 1.25249 2.12181 2.50342 + vertex 1.24844 2.12332 2.50374 + endloop + endfacet + facet normal 0.181244 0.292312 0.938991 + outer loop + vertex 1.25249 2.12181 2.50342 + vertex 1.2509 2.12641 2.5023 + vertex 1.24844 2.12332 2.50374 + endloop + endfacet + facet normal 0.177772 0.291346 0.939954 + outer loop + vertex 1.25249 2.12181 2.50342 + vertex 1.2565 2.12438 2.50187 + vertex 1.2509 2.12641 2.5023 + endloop + endfacet + facet normal 0.17915 0.289409 0.940291 + outer loop + vertex 1.25657 2.12028 2.50312 + vertex 1.2565 2.12438 2.50187 + vertex 1.25249 2.12181 2.50342 + endloop + endfacet + facet normal 0.176529 0.28185 0.943079 + outer loop + vertex 1.25417 2.11707 2.50453 + vertex 1.25657 2.12028 2.50312 + vertex 1.25249 2.12181 2.50342 + endloop + endfacet + facet normal 0.17849 0.280408 0.94314 + outer loop + vertex 1.25849 2.11747 2.50359 + vertex 1.25657 2.12028 2.50312 + vertex 1.25417 2.11707 2.50453 + endloop + endfacet + facet normal 0.179772 0.271781 0.945419 + outer loop + vertex 1.25417 2.11707 2.50453 + vertex 1.25885 2.11315 2.50476 + vertex 1.25849 2.11747 2.50359 + endloop + endfacet + facet normal 0.179559 0.271775 0.945461 + outer loop + vertex 1.25885 2.11315 2.50476 + vertex 1.26162 2.11624 2.50335 + vertex 1.25849 2.11747 2.50359 + endloop + endfacet + facet normal 0.182466 0.279741 0.942577 + outer loop + vertex 1.26162 2.11624 2.50335 + vertex 1.26121 2.12055 2.50215 + vertex 1.25849 2.11747 2.50359 + endloop + endfacet + facet normal 0.180782 0.279676 0.94292 + outer loop + vertex 1.26121 2.12055 2.50215 + vertex 1.26162 2.11624 2.50335 + vertex 1.26592 2.11666 2.5024 + endloop + endfacet + facet normal 0.179948 0.278693 0.943371 + outer loop + vertex 1.26583 2.12081 2.50119 + vertex 1.26121 2.12055 2.50215 + vertex 1.26592 2.11666 2.5024 + endloop + endfacet + facet normal 0.179927 0.278694 0.943375 + outer loop + vertex 1.26583 2.12081 2.50119 + vertex 1.26592 2.11666 2.5024 + vertex 1.2699 2.11928 2.50087 + endloop + endfacet + facet normal 0.180725 0.277586 0.943549 + outer loop + vertex 1.27162 2.11452 2.50194 + vertex 1.2699 2.11928 2.50087 + vertex 1.26592 2.11666 2.5024 + endloop + endfacet + facet normal 0.178375 0.270818 0.94596 + outer loop + vertex 1.26756 2.11188 2.50346 + vertex 1.27162 2.11452 2.50194 + vertex 1.26592 2.11666 2.5024 + endloop + endfacet + facet normal 0.181584 0.271723 0.945089 + outer loop + vertex 1.26756 2.11188 2.50346 + vertex 1.26592 2.11666 2.5024 + vertex 1.26351 2.11341 2.5038 + endloop + endfacet + facet normal 0.180273 0.267961 0.946414 + outer loop + vertex 1.26348 2.10924 2.50498 + vertex 1.26756 2.11188 2.50346 + vertex 1.26351 2.11341 2.5038 + endloop + endfacet + facet normal 0.178769 0.270098 0.946091 + outer loop + vertex 1.26904 2.1072 2.50451 + vertex 1.26756 2.11188 2.50346 + vertex 1.26348 2.10924 2.50498 + endloop + endfacet + facet normal 0.178492 0.270026 0.946164 + outer loop + vertex 1.26904 2.1072 2.50451 + vertex 1.27158 2.11038 2.50313 + vertex 1.26756 2.11188 2.50346 + endloop + endfacet + facet normal 0.17595 0.272016 0.94607 + outer loop + vertex 1.27333 2.10765 2.50359 + vertex 1.27158 2.11038 2.50313 + vertex 1.26904 2.1072 2.50451 + endloop + endfacet + facet normal 0.175129 0.277142 0.944734 + outer loop + vertex 1.26904 2.1072 2.50451 + vertex 1.2732 2.10373 2.50476 + vertex 1.27333 2.10765 2.50359 + endloop + endfacet + facet normal 0.172344 0.277367 0.94518 + outer loop + vertex 1.2732 2.10373 2.50476 + vertex 1.27652 2.10619 2.50344 + vertex 1.27333 2.10765 2.50359 + endloop + endfacet + facet normal 0.170969 0.274248 0.946339 + outer loop + vertex 1.27652 2.10619 2.50344 + vertex 1.27625 2.11065 2.50219 + vertex 1.27333 2.10765 2.50359 + endloop + endfacet + facet normal 0.171125 0.274249 0.946311 + outer loop + vertex 1.27625 2.11065 2.50219 + vertex 1.27652 2.10619 2.50344 + vertex 1.28107 2.10665 2.50248 + endloop + endfacet + facet normal 0.17396 0.277561 0.944827 + outer loop + vertex 1.28089 2.11092 2.50126 + vertex 1.27625 2.11065 2.50219 + vertex 1.28107 2.10665 2.50248 + endloop + endfacet + facet normal 0.173557 0.277564 0.9449 + outer loop + vertex 1.28089 2.11092 2.50126 + vertex 1.28107 2.10665 2.50248 + vertex 1.28496 2.10938 2.50096 + endloop + endfacet + facet normal 0.174184 0.27557 0.945368 + outer loop + vertex 1.28089 2.11092 2.50126 + vertex 1.27898 2.11374 2.50079 + vertex 1.27625 2.11065 2.50219 + endloop + endfacet + facet normal 0.176078 0.273947 0.945489 + outer loop + vertex 1.27592 2.11496 2.50101 + vertex 1.27625 2.11065 2.50219 + vertex 1.27898 2.11374 2.50079 + endloop + endfacet + facet normal 0.178188 0.279637 0.943426 + outer loop + vertex 1.27898 2.11374 2.50079 + vertex 1.27865 2.11797 2.4996 + vertex 1.27592 2.11496 2.50101 + endloop + endfacet + facet normal 0.175948 0.279582 0.943862 + outer loop + vertex 1.27898 2.11374 2.50079 + vertex 1.28317 2.11405 2.49991 + vertex 1.27865 2.11797 2.4996 + endloop + endfacet + facet normal 0.177692 0.281522 0.942959 + outer loop + vertex 1.27865 2.11797 2.4996 + vertex 1.28317 2.11405 2.49991 + vertex 1.28326 2.11796 2.49873 + endloop + endfacet + facet normal 0.177396 0.287213 0.941297 + outer loop + vertex 1.28326 2.11796 2.49873 + vertex 1.28164 2.12075 2.49818 + vertex 1.27865 2.11797 2.4996 + endloop + endfacet + facet normal 0.177221 0.273975 0.945268 + outer loop + vertex 1.27592 2.11496 2.50101 + vertex 1.27162 2.11452 2.50194 + vertex 1.27625 2.11065 2.50219 + endloop + endfacet + facet normal 0.174399 0.27069 0.946738 + outer loop + vertex 1.27162 2.11452 2.50194 + vertex 1.27158 2.11038 2.50313 + vertex 1.27625 2.11065 2.50219 + endloop + endfacet + facet normal 0.176704 0.277227 0.944416 + outer loop + vertex 1.27592 2.11496 2.50101 + vertex 1.274 2.11776 2.50054 + vertex 1.27162 2.11452 2.50194 + endloop + endfacet + facet normal 0.176305 0.276873 0.944594 + outer loop + vertex 1.27898 2.11374 2.50079 + vertex 1.28089 2.11092 2.50126 + vertex 1.28317 2.11405 2.49991 + endloop + endfacet + facet normal 0.170066 0.280915 0.944545 + outer loop + vertex 1.27879 2.10205 2.50426 + vertex 1.28107 2.10665 2.50248 + vertex 1.27652 2.10619 2.50344 + endloop + endfacet + facet normal 0.170001 0.280947 0.944547 + outer loop + vertex 1.28338 2.10247 2.50331 + vertex 1.28107 2.10665 2.50248 + vertex 1.27879 2.10205 2.50426 + endloop + endfacet + facet normal 0.169169 0.286571 0.943005 + outer loop + vertex 1.27879 2.10205 2.50426 + vertex 1.28366 2.09802 2.50461 + vertex 1.28338 2.10247 2.50331 + endloop + endfacet + facet normal 0.169199 0.286572 0.943 + outer loop + vertex 1.28366 2.09802 2.50461 + vertex 1.2867 2.1008 2.50322 + vertex 1.28338 2.10247 2.50331 + endloop + endfacet + facet normal 0.168299 0.284747 0.943713 + outer loop + vertex 1.2867 2.1008 2.50322 + vertex 1.28678 2.10471 2.50202 + vertex 1.28338 2.10247 2.50331 + endloop + endfacet + facet normal 0.167085 0.288742 0.942714 + outer loop + vertex 1.28833 2.09801 2.50378 + vertex 1.2867 2.1008 2.50322 + vertex 1.28366 2.09802 2.50461 + endloop + endfacet + facet normal 0.16703 0.28983 0.94239 + outer loop + vertex 1.28366 2.09802 2.50461 + vertex 1.28823 2.09413 2.50499 + vertex 1.28833 2.09801 2.50378 + endloop + endfacet + facet normal 0.166343 0.289057 0.942749 + outer loop + vertex 1.28401 2.09377 2.50585 + vertex 1.28823 2.09413 2.50499 + vertex 1.28366 2.09802 2.50461 + endloop + endfacet + facet normal 0.167514 0.289091 0.942532 + outer loop + vertex 1.28401 2.09377 2.50585 + vertex 1.28366 2.09802 2.50461 + vertex 1.28088 2.09499 2.50603 + endloop + endfacet + facet normal 0.167727 0.289668 0.942317 + outer loop + vertex 1.28088 2.09499 2.50603 + vertex 1.28127 2.09069 2.50728 + vertex 1.28401 2.09377 2.50585 + endloop + endfacet + facet normal 0.16763 0.28975 0.942308 + outer loop + vertex 1.28595 2.09096 2.50637 + vertex 1.28401 2.09377 2.50585 + vertex 1.28127 2.09069 2.50728 + endloop + endfacet + facet normal 0.167918 0.287232 0.943028 + outer loop + vertex 1.28595 2.09096 2.50637 + vertex 1.28127 2.09069 2.50728 + vertex 1.28613 2.08674 2.50762 + endloop + endfacet + facet normal 0.165902 0.287253 0.943378 + outer loop + vertex 1.28595 2.09096 2.50637 + vertex 1.28613 2.08674 2.50762 + vertex 1.29 2.08955 2.50608 + endloop + endfacet + facet normal 0.167216 0.285596 0.943649 + outer loop + vertex 1.29173 2.08503 2.50715 + vertex 1.29 2.08955 2.50608 + vertex 1.28613 2.08674 2.50762 + endloop + endfacet + facet normal 0.166611 0.283396 0.944419 + outer loop + vertex 1.28842 2.08261 2.50846 + vertex 1.29173 2.08503 2.50715 + vertex 1.28613 2.08674 2.50762 + endloop + endfacet + facet normal 0.165164 0.282686 0.944886 + outer loop + vertex 1.28842 2.08261 2.50846 + vertex 1.28613 2.08674 2.50762 + vertex 1.28387 2.0821 2.50941 + endloop + endfacet + facet normal 0.165972 0.277878 0.94617 + outer loop + vertex 1.28387 2.0821 2.50941 + vertex 1.28875 2.07814 2.50971 + vertex 1.28842 2.08261 2.50846 + endloop + endfacet + facet normal 0.164912 0.277854 0.946362 + outer loop + vertex 1.28875 2.07814 2.50971 + vertex 1.29166 2.08112 2.50833 + vertex 1.28842 2.08261 2.50846 + endloop + endfacet + facet normal 0.16376 0.278924 0.946247 + outer loop + vertex 1.29347 2.07839 2.50882 + vertex 1.29166 2.08112 2.50833 + vertex 1.28875 2.07814 2.50971 + endloop + endfacet + facet normal 0.164219 0.274529 0.947452 + outer loop + vertex 1.28875 2.07814 2.50971 + vertex 1.29349 2.07431 2.51 + vertex 1.29347 2.07839 2.50882 + endloop + endfacet + facet normal 0.160467 0.270029 0.949386 + outer loop + vertex 1.28914 2.07383 2.51087 + vertex 1.29349 2.07431 2.51 + vertex 1.28875 2.07814 2.50971 + endloop + endfacet + facet normal 0.160842 0.270045 0.949319 + outer loop + vertex 1.28914 2.07383 2.51087 + vertex 1.28875 2.07814 2.50971 + vertex 1.28597 2.07501 2.51107 + endloop + endfacet + facet normal 0.158588 0.263624 0.9515 + outer loop + vertex 1.28597 2.07501 2.51107 + vertex 1.28632 2.0707 2.51221 + vertex 1.28914 2.07383 2.51087 + endloop + endfacet + facet normal 0.159254 0.263044 0.951549 + outer loop + vertex 1.29106 2.07105 2.51132 + vertex 1.28914 2.07383 2.51087 + vertex 1.28632 2.0707 2.51221 + endloop + endfacet + facet normal 0.159116 0.264181 0.951257 + outer loop + vertex 1.29106 2.07105 2.51132 + vertex 1.28632 2.0707 2.51221 + vertex 1.29095 2.06689 2.51249 + endloop + endfacet + facet normal 0.160188 0.264109 0.951097 + outer loop + vertex 1.29106 2.07105 2.51132 + vertex 1.29095 2.06689 2.51249 + vertex 1.29512 2.06964 2.51103 + endloop + endfacet + facet normal 0.159495 0.263655 0.95134 + outer loop + vertex 1.28597 2.07501 2.51107 + vertex 1.28161 2.07453 2.51194 + vertex 1.28632 2.0707 2.51221 + endloop + endfacet + facet normal 0.161663 0.266238 0.950254 + outer loop + vertex 1.28161 2.07453 2.51194 + vertex 1.28158 2.07039 2.5131 + vertex 1.28632 2.0707 2.51221 + endloop + endfacet + facet normal 0.159158 0.265767 0.950808 + outer loop + vertex 1.28597 2.07501 2.51107 + vertex 1.28402 2.07782 2.51061 + vertex 1.28161 2.07453 2.51194 + endloop + endfacet + facet normal 0.161013 0.264436 0.950867 + outer loop + vertex 1.28402 2.07782 2.51061 + vertex 1.27996 2.07925 2.5109 + vertex 1.28161 2.07453 2.51194 + endloop + endfacet + facet normal 0.163442 0.265154 0.950253 + outer loop + vertex 1.28161 2.07453 2.51194 + vertex 1.27996 2.07925 2.5109 + vertex 1.27598 2.07655 2.51234 + endloop + endfacet + facet normal 0.163192 0.264405 0.950504 + outer loop + vertex 1.27747 2.07189 2.51338 + vertex 1.28161 2.07453 2.51194 + vertex 1.27598 2.07655 2.51234 + endloop + endfacet + facet normal 0.160765 0.263759 0.951097 + outer loop + vertex 1.27747 2.07189 2.51338 + vertex 1.27598 2.07655 2.51234 + vertex 1.2734 2.0734 2.51365 + endloop + endfacet + facet normal 0.164253 0.264051 0.95042 + outer loop + vertex 1.27602 2.0806 2.51121 + vertex 1.27598 2.07655 2.51234 + vertex 1.27996 2.07925 2.5109 + endloop + endfacet + facet normal 0.167048 0.272954 0.947413 + outer loop + vertex 1.27996 2.07925 2.5109 + vertex 1.27828 2.08381 2.50989 + vertex 1.27602 2.0806 2.51121 + endloop + endfacet + facet normal 0.167346 0.272747 0.94742 + outer loop + vertex 1.27406 2.08328 2.51079 + vertex 1.27602 2.0806 2.51121 + vertex 1.27828 2.08381 2.50989 + endloop + endfacet + facet normal 0.166098 0.279644 0.945627 + outer loop + vertex 1.27406 2.08328 2.51079 + vertex 1.27828 2.08381 2.50989 + vertex 1.27406 2.0873 2.50959 + endloop + endfacet + facet normal 0.167049 0.279599 0.945473 + outer loop + vertex 1.27012 2.08461 2.51109 + vertex 1.27406 2.08328 2.51079 + vertex 1.27406 2.0873 2.50959 + endloop + endfacet + facet normal 0.166201 0.280736 0.945285 + outer loop + vertex 1.26845 2.08928 2.50999 + vertex 1.27012 2.08461 2.51109 + vertex 1.27406 2.0873 2.50959 + endloop + endfacet + facet normal 0.167933 0.286021 0.943393 + outer loop + vertex 1.27406 2.0873 2.50959 + vertex 1.27251 2.0919 2.50848 + vertex 1.26845 2.08928 2.50999 + endloop + endfacet + facet normal 0.168112 0.285769 0.943437 + outer loop + vertex 1.26845 2.08928 2.50999 + vertex 1.27251 2.0919 2.50848 + vertex 1.26846 2.09334 2.50876 + endloop + endfacet + facet normal 0.16981 0.285681 0.94316 + outer loop + vertex 1.26376 2.09308 2.50969 + vertex 1.26845 2.08928 2.50999 + vertex 1.26846 2.09334 2.50876 + endloop + endfacet + facet normal 0.169706 0.286606 0.942898 + outer loop + vertex 1.26846 2.09334 2.50876 + vertex 1.26666 2.09604 2.50827 + vertex 1.26376 2.09308 2.50969 + endloop + endfacet + facet normal 0.17235 0.284153 0.943161 + outer loop + vertex 1.26376 2.09308 2.50969 + vertex 1.26666 2.09604 2.50827 + vertex 1.26343 2.09752 2.50841 + endloop + endfacet + facet normal 0.172338 0.284126 0.943171 + outer loop + vertex 1.26666 2.09604 2.50827 + vertex 1.26673 2.09995 2.50708 + vertex 1.26343 2.09752 2.50841 + endloop + endfacet + facet normal 0.17576 0.279838 0.943822 + outer loop + vertex 1.26343 2.09752 2.50841 + vertex 1.26673 2.09995 2.50708 + vertex 1.26116 2.10168 2.5076 + endloop + endfacet + facet normal 0.170564 0.284246 0.943458 + outer loop + vertex 1.26673 2.09995 2.50708 + vertex 1.26666 2.09604 2.50827 + vertex 1.27095 2.09649 2.50735 + endloop + endfacet + facet normal 0.172884 0.286973 0.942209 + outer loop + vertex 1.27093 2.10051 2.50614 + vertex 1.26673 2.09995 2.50708 + vertex 1.27095 2.09649 2.50735 + endloop + endfacet + facet normal 0.170202 0.287099 0.942659 + outer loop + vertex 1.27093 2.10051 2.50614 + vertex 1.27095 2.09649 2.50735 + vertex 1.27487 2.09921 2.50582 + endloop + endfacet + facet normal 0.169014 0.28313 0.944072 + outer loop + vertex 1.27487 2.09921 2.50582 + vertex 1.2732 2.10373 2.50476 + vertex 1.27093 2.10051 2.50614 + endloop + endfacet + facet normal 0.171917 0.281119 0.944149 + outer loop + vertex 1.26899 2.10316 2.5057 + vertex 1.27093 2.10051 2.50614 + vertex 1.2732 2.10373 2.50476 + endloop + endfacet + facet normal 0.170428 0.283564 0.943687 + outer loop + vertex 1.2732 2.10373 2.50476 + vertex 1.27487 2.09921 2.50582 + vertex 1.27879 2.10205 2.50426 + endloop + endfacet + facet normal 0.168831 0.28559 0.943363 + outer loop + vertex 1.27487 2.09921 2.50582 + vertex 1.27894 2.0978 2.50552 + vertex 1.27879 2.10205 2.50426 + endloop + endfacet + facet normal 0.169795 0.288595 0.942275 + outer loop + vertex 1.27894 2.0978 2.50552 + vertex 1.27487 2.09921 2.50582 + vertex 1.27656 2.09453 2.50695 + endloop + endfacet + facet normal 0.168927 0.289211 0.942242 + outer loop + vertex 1.28088 2.09499 2.50603 + vertex 1.27894 2.0978 2.50552 + vertex 1.27656 2.09453 2.50695 + endloop + endfacet + facet normal 0.1692 0.288419 0.942436 + outer loop + vertex 1.27656 2.09453 2.50695 + vertex 1.27487 2.09921 2.50582 + vertex 1.27095 2.09649 2.50735 + endloop + endfacet + facet normal 0.169047 0.287947 0.942608 + outer loop + vertex 1.27251 2.0919 2.50848 + vertex 1.27656 2.09453 2.50695 + vertex 1.27095 2.09649 2.50735 + endloop + endfacet + facet normal 0.168147 0.289204 0.942384 + outer loop + vertex 1.27656 2.09045 2.5082 + vertex 1.27656 2.09453 2.50695 + vertex 1.27251 2.0919 2.50848 + endloop + endfacet + facet normal 0.168409 0.289191 0.942341 + outer loop + vertex 1.27656 2.09453 2.50695 + vertex 1.27656 2.09045 2.5082 + vertex 1.28127 2.09069 2.50728 + endloop + endfacet + facet normal 0.168624 0.28718 0.942917 + outer loop + vertex 1.27836 2.08772 2.50871 + vertex 1.28127 2.09069 2.50728 + vertex 1.27656 2.09045 2.5082 + endloop + endfacet + facet normal 0.166669 0.28602 0.943618 + outer loop + vertex 1.27836 2.08772 2.50871 + vertex 1.27656 2.09045 2.5082 + vertex 1.27406 2.0873 2.50959 + endloop + endfacet + facet normal 0.169063 0.286774 0.942963 + outer loop + vertex 1.28159 2.08623 2.50858 + vertex 1.28127 2.09069 2.50728 + vertex 1.27836 2.08772 2.50871 + endloop + endfacet + facet normal 0.166587 0.28123 0.94507 + outer loop + vertex 1.27828 2.08381 2.50989 + vertex 1.28159 2.08623 2.50858 + vertex 1.27836 2.08772 2.50871 + endloop + endfacet + facet normal 0.167219 0.280436 0.945195 + outer loop + vertex 1.28387 2.0821 2.50941 + vertex 1.28159 2.08623 2.50858 + vertex 1.27828 2.08381 2.50989 + endloop + endfacet + facet normal 0.173771 0.282358 0.943439 + outer loop + vertex 1.27093 2.10051 2.50614 + vertex 1.26899 2.10316 2.5057 + vertex 1.26673 2.09995 2.50708 + endloop + endfacet + facet normal 0.177845 0.279525 0.943524 + outer loop + vertex 1.26899 2.10316 2.5057 + vertex 1.26508 2.10449 2.50604 + vertex 1.26673 2.09995 2.50708 + endloop + endfacet + facet normal 0.176329 0.274632 0.945243 + outer loop + vertex 1.26508 2.10449 2.50604 + vertex 1.26899 2.10316 2.5057 + vertex 1.26904 2.1072 2.50451 + endloop + endfacet + facet normal 0.170138 0.286866 0.942741 + outer loop + vertex 1.26846 2.09334 2.50876 + vertex 1.27095 2.09649 2.50735 + vertex 1.26666 2.09604 2.50827 + endloop + endfacet + facet normal 0.168809 0.287881 0.942671 + outer loop + vertex 1.27251 2.0919 2.50848 + vertex 1.27095 2.09649 2.50735 + vertex 1.26846 2.09334 2.50876 + endloop + endfacet + facet normal 0.167 0.285765 0.943636 + outer loop + vertex 1.27406 2.0873 2.50959 + vertex 1.27656 2.09045 2.5082 + vertex 1.27251 2.0919 2.50848 + endloop + endfacet + facet normal 0.169002 0.281558 0.944544 + outer loop + vertex 1.27012 2.08461 2.51109 + vertex 1.26845 2.08928 2.50999 + vertex 1.26606 2.08602 2.51139 + endloop + endfacet + facet normal 0.167052 0.275509 0.946672 + outer loop + vertex 1.26606 2.08602 2.51139 + vertex 1.26619 2.08175 2.51261 + vertex 1.27012 2.08461 2.51109 + endloop + endfacet + facet normal 0.169246 0.272713 0.947092 + outer loop + vertex 1.27178 2.08006 2.5121 + vertex 1.27012 2.08461 2.51109 + vertex 1.26619 2.08175 2.51261 + endloop + endfacet + facet normal 0.171047 0.275431 0.945981 + outer loop + vertex 1.26606 2.08602 2.51139 + vertex 1.26137 2.08569 2.51234 + vertex 1.26619 2.08175 2.51261 + endloop + endfacet + facet normal 0.16893 0.281609 0.944542 + outer loop + vertex 1.26414 2.0888 2.51091 + vertex 1.26606 2.08602 2.51139 + vertex 1.26845 2.08928 2.50999 + endloop + endfacet + facet normal 0.164456 0.271238 0.948358 + outer loop + vertex 1.27406 2.08328 2.51079 + vertex 1.27012 2.08461 2.51109 + vertex 1.27178 2.08006 2.5121 + endloop + endfacet + facet normal 0.167413 0.281173 0.944941 + outer loop + vertex 1.27406 2.0873 2.50959 + vertex 1.27828 2.08381 2.50989 + vertex 1.27836 2.08772 2.50871 + endloop + endfacet + facet normal 0.164769 0.27102 0.948367 + outer loop + vertex 1.27602 2.0806 2.51121 + vertex 1.27406 2.08328 2.51079 + vertex 1.27178 2.08006 2.5121 + endloop + endfacet + facet normal 0.164979 0.272313 0.94796 + outer loop + vertex 1.27828 2.08381 2.50989 + vertex 1.27996 2.07925 2.5109 + vertex 1.28387 2.0821 2.50941 + endloop + endfacet + facet normal 0.166035 0.263956 0.950137 + outer loop + vertex 1.27602 2.0806 2.51121 + vertex 1.27178 2.08006 2.5121 + vertex 1.27598 2.07655 2.51234 + endloop + endfacet + facet normal 0.164512 0.262187 0.950891 + outer loop + vertex 1.27178 2.08006 2.5121 + vertex 1.27164 2.07613 2.51321 + vertex 1.27598 2.07655 2.51234 + endloop + endfacet + facet normal 0.164004 0.273555 0.947771 + outer loop + vertex 1.27996 2.07925 2.5109 + vertex 1.28402 2.07782 2.51061 + vertex 1.28387 2.0821 2.50941 + endloop + endfacet + facet normal 0.162993 0.268204 0.949473 + outer loop + vertex 1.28402 2.07782 2.51061 + vertex 1.28597 2.07501 2.51107 + vertex 1.28875 2.07814 2.50971 + endloop + endfacet + facet normal 0.161387 0.264396 0.950815 + outer loop + vertex 1.28914 2.07383 2.51087 + vertex 1.29106 2.07105 2.51132 + vertex 1.29349 2.07431 2.51 + endloop + endfacet + facet normal 0.167205 0.280995 0.945031 + outer loop + vertex 1.29347 2.07839 2.50882 + vertex 1.29595 2.08154 2.50745 + vertex 1.29166 2.08112 2.50833 + endloop + endfacet + facet normal 0.166931 0.282783 0.944546 + outer loop + vertex 1.29173 2.08503 2.50715 + vertex 1.29166 2.08112 2.50833 + vertex 1.29595 2.08154 2.50745 + endloop + endfacet + facet normal 0.166904 0.282751 0.944561 + outer loop + vertex 1.29594 2.08556 2.50624 + vertex 1.29173 2.08503 2.50715 + vertex 1.29595 2.08154 2.50745 + endloop + endfacet + facet normal 0.166593 0.282766 0.944611 + outer loop + vertex 1.29594 2.08556 2.50624 + vertex 1.29595 2.08154 2.50745 + vertex 1.29987 2.08423 2.50595 + endloop + endfacet + facet normal 0.166335 0.281937 0.944904 + outer loop + vertex 1.29987 2.08423 2.50595 + vertex 1.29821 2.08878 2.50488 + vertex 1.29594 2.08556 2.50624 + endloop + endfacet + facet normal 0.162737 0.280845 0.945856 + outer loop + vertex 1.29821 2.08878 2.50488 + vertex 1.29987 2.08423 2.50595 + vertex 1.30382 2.08705 2.50443 + endloop + endfacet + facet normal 0.164338 0.278785 0.946188 + outer loop + vertex 1.29987 2.08423 2.50595 + vertex 1.30391 2.08281 2.50567 + vertex 1.30382 2.08705 2.50443 + endloop + endfacet + facet normal 0.15917 0.278916 0.947033 + outer loop + vertex 1.30391 2.08281 2.50567 + vertex 1.30866 2.08312 2.50478 + vertex 1.30382 2.08705 2.50443 + endloop + endfacet + facet normal 0.159021 0.278739 0.94711 + outer loop + vertex 1.30382 2.08705 2.50443 + vertex 1.30866 2.08312 2.50478 + vertex 1.30838 2.08759 2.50351 + endloop + endfacet + facet normal 0.158496 0.281791 0.946294 + outer loop + vertex 1.30838 2.08759 2.50351 + vertex 1.30622 2.09161 2.50267 + vertex 1.30382 2.08705 2.50443 + endloop + endfacet + facet normal 0.160415 0.280773 0.946274 + outer loop + vertex 1.30382 2.08705 2.50443 + vertex 1.30622 2.09161 2.50267 + vertex 1.30168 2.09111 2.50359 + endloop + endfacet + facet normal 0.155877 0.28055 0.947098 + outer loop + vertex 1.30838 2.08759 2.50351 + vertex 1.31174 2.09006 2.50222 + vertex 1.30622 2.09161 2.50267 + endloop + endfacet + facet normal 0.156152 0.280205 0.947155 + outer loop + vertex 1.31163 2.08613 2.50341 + vertex 1.31174 2.09006 2.50222 + vertex 1.30838 2.08759 2.50351 + endloop + endfacet + facet normal 0.153187 0.280421 0.947575 + outer loop + vertex 1.31174 2.09006 2.50222 + vertex 1.31163 2.08613 2.50341 + vertex 1.316 2.08662 2.50255 + endloop + endfacet + facet normal 0.155144 0.28275 0.946564 + outer loop + vertex 1.31603 2.0907 2.50133 + vertex 1.31174 2.09006 2.50222 + vertex 1.316 2.08662 2.50255 + endloop + endfacet + facet normal 0.154845 0.282765 0.946608 + outer loop + vertex 1.31603 2.0907 2.50133 + vertex 1.316 2.08662 2.50255 + vertex 1.32001 2.08946 2.50105 + endloop + endfacet + facet normal 0.157016 0.290332 0.943956 + outer loop + vertex 1.32001 2.08946 2.50105 + vertex 1.3184 2.09403 2.49991 + vertex 1.31603 2.0907 2.50133 + endloop + endfacet + facet normal 0.157505 0.289995 0.943978 + outer loop + vertex 1.31401 2.09335 2.50085 + vertex 1.31603 2.0907 2.50133 + vertex 1.3184 2.09403 2.49991 + endloop + endfacet + facet normal 0.156399 0.295158 0.942561 + outer loop + vertex 1.31401 2.09335 2.50085 + vertex 1.3184 2.09403 2.49991 + vertex 1.31385 2.09748 2.49958 + endloop + endfacet + facet normal 0.158091 0.297299 0.941605 + outer loop + vertex 1.31385 2.09748 2.49958 + vertex 1.3184 2.09403 2.49991 + vertex 1.31843 2.09823 2.49858 + endloop + endfacet + facet normal 0.157134 0.301574 0.940405 + outer loop + vertex 1.31843 2.09823 2.49858 + vertex 1.31607 2.10207 2.49774 + vertex 1.31385 2.09748 2.49958 + endloop + endfacet + facet normal 0.157824 0.301945 0.940171 + outer loop + vertex 1.31843 2.09823 2.49858 + vertex 1.32135 2.10085 2.49725 + vertex 1.31607 2.10207 2.49774 + endloop + endfacet + facet normal 0.158193 0.303804 0.93951 + outer loop + vertex 1.32135 2.10085 2.49725 + vertex 1.31997 2.10498 2.49615 + vertex 1.31607 2.10207 2.49774 + endloop + endfacet + facet normal 0.158888 0.302958 0.939665 + outer loop + vertex 1.31594 2.10613 2.49645 + vertex 1.31607 2.10207 2.49774 + vertex 1.31997 2.10498 2.49615 + endloop + endfacet + facet normal 0.161353 0.302908 0.939261 + outer loop + vertex 1.31594 2.10613 2.49645 + vertex 1.31128 2.10571 2.49739 + vertex 1.31607 2.10207 2.49774 + endloop + endfacet + facet normal 0.159664 0.300775 0.940235 + outer loop + vertex 1.31128 2.10571 2.49739 + vertex 1.31161 2.10136 2.49873 + vertex 1.31607 2.10207 2.49774 + endloop + endfacet + facet normal 0.156022 0.290045 0.944209 + outer loop + vertex 1.3184 2.09403 2.49991 + vertex 1.32001 2.08946 2.50105 + vertex 1.32397 2.09224 2.49954 + endloop + endfacet + facet normal 0.157753 0.295871 0.942112 + outer loop + vertex 1.32397 2.09224 2.49954 + vertex 1.3225 2.09671 2.49838 + vertex 1.3184 2.09403 2.49991 + endloop + endfacet + facet normal 0.156661 0.297378 0.941819 + outer loop + vertex 1.3184 2.09403 2.49991 + vertex 1.3225 2.09671 2.49838 + vertex 1.31843 2.09823 2.49858 + endloop + endfacet + facet normal 0.158155 0.301603 0.940225 + outer loop + vertex 1.3225 2.09671 2.49838 + vertex 1.32135 2.10085 2.49725 + vertex 1.31843 2.09823 2.49858 + endloop + endfacet + facet normal 0.156212 0.295463 0.942497 + outer loop + vertex 1.32397 2.09224 2.49954 + vertex 1.32646 2.09539 2.49814 + vertex 1.3225 2.09671 2.49838 + endloop + endfacet + facet normal 0.157775 0.300484 0.940647 + outer loop + vertex 1.32646 2.09539 2.49814 + vertex 1.3265 2.09931 2.49688 + vertex 1.3225 2.09671 2.49838 + endloop + endfacet + facet normal 0.157123 0.301383 0.940468 + outer loop + vertex 1.3225 2.09671 2.49838 + vertex 1.3265 2.09931 2.49688 + vertex 1.32135 2.10085 2.49725 + endloop + endfacet + facet normal 0.157689 0.303462 0.939705 + outer loop + vertex 1.3265 2.09931 2.49688 + vertex 1.32475 2.10373 2.49575 + vertex 1.32135 2.10085 2.49725 + endloop + endfacet + facet normal 0.156262 0.302997 0.940093 + outer loop + vertex 1.32878 2.10257 2.49545 + vertex 1.32475 2.10373 2.49575 + vertex 1.3265 2.09931 2.49688 + endloop + endfacet + facet normal 0.156356 0.302933 0.940098 + outer loop + vertex 1.33072 2.09991 2.49599 + vertex 1.32878 2.10257 2.49545 + vertex 1.3265 2.09931 2.49688 + endloop + endfacet + facet normal 0.156847 0.3005 0.940797 + outer loop + vertex 1.33072 2.09991 2.49599 + vertex 1.3265 2.09931 2.49688 + vertex 1.33114 2.09568 2.49727 + endloop + endfacet + facet normal 0.153993 0.300372 0.941309 + outer loop + vertex 1.33072 2.09991 2.49599 + vertex 1.33114 2.09568 2.49727 + vertex 1.33389 2.09877 2.49583 + endloop + endfacet + facet normal 0.154662 0.302324 0.940574 + outer loop + vertex 1.33389 2.09877 2.49583 + vertex 1.33349 2.10297 2.49454 + vertex 1.33072 2.09991 2.49599 + endloop + endfacet + facet normal 0.150909 0.302175 0.941232 + outer loop + vertex 1.33389 2.09877 2.49583 + vertex 1.3383 2.09921 2.49498 + vertex 1.33349 2.10297 2.49454 + endloop + endfacet + facet normal 0.151893 0.303367 0.94069 + outer loop + vertex 1.33349 2.10297 2.49454 + vertex 1.3383 2.09921 2.49498 + vertex 1.33827 2.10325 2.49368 + endloop + endfacet + facet normal 0.151678 0.305259 0.940112 + outer loop + vertex 1.33827 2.10325 2.49368 + vertex 1.33641 2.10594 2.49311 + vertex 1.33349 2.10297 2.49454 + endloop + endfacet + facet normal 0.152674 0.304347 0.940247 + outer loop + vertex 1.33349 2.10297 2.49454 + vertex 1.33641 2.10594 2.49311 + vertex 1.33315 2.10733 2.49319 + endloop + endfacet + facet normal 0.155159 0.304409 0.93982 + outer loop + vertex 1.32865 2.10663 2.49416 + vertex 1.33349 2.10297 2.49454 + vertex 1.33315 2.10733 2.49319 + endloop + endfacet + facet normal 0.15473 0.303866 0.940066 + outer loop + vertex 1.32878 2.10257 2.49545 + vertex 1.33349 2.10297 2.49454 + vertex 1.32865 2.10663 2.49416 + endloop + endfacet + facet normal 0.152979 0.305081 0.939959 + outer loop + vertex 1.33641 2.10594 2.49311 + vertex 1.33645 2.10976 2.49186 + vertex 1.33315 2.10733 2.49319 + endloop + endfacet + facet normal 0.151179 0.305183 0.940217 + outer loop + vertex 1.33645 2.10976 2.49186 + vertex 1.33641 2.10594 2.49311 + vertex 1.34075 2.10639 2.49227 + endloop + endfacet + facet normal 0.152623 0.306931 0.939415 + outer loop + vertex 1.34068 2.11034 2.49099 + vertex 1.33645 2.10976 2.49186 + vertex 1.34075 2.10639 2.49227 + endloop + endfacet + facet normal 0.151604 0.306963 0.939569 + outer loop + vertex 1.34068 2.11034 2.49099 + vertex 1.34075 2.10639 2.49227 + vertex 1.34466 2.10912 2.49075 + endloop + endfacet + facet normal 0.151741 0.307443 0.93939 + outer loop + vertex 1.34466 2.10912 2.49075 + vertex 1.34291 2.11353 2.48958 + vertex 1.34068 2.11034 2.49099 + endloop + endfacet + facet normal 0.153461 0.306288 0.939488 + outer loop + vertex 1.33864 2.11296 2.49047 + vertex 1.34068 2.11034 2.49099 + vertex 1.34291 2.11353 2.48958 + endloop + endfacet + facet normal 0.153787 0.308108 0.938839 + outer loop + vertex 1.34291 2.11353 2.48958 + vertex 1.34466 2.10912 2.49075 + vertex 1.34847 2.11197 2.48918 + endloop + endfacet + facet normal 0.151954 0.310322 0.938408 + outer loop + vertex 1.34466 2.10912 2.49075 + vertex 1.34865 2.10791 2.4905 + vertex 1.34847 2.11197 2.48918 + endloop + endfacet + facet normal 0.151558 0.308908 0.938939 + outer loop + vertex 1.34865 2.10791 2.4905 + vertex 1.34466 2.10912 2.49075 + vertex 1.34637 2.10461 2.49195 + endloop + endfacet + facet normal 0.149622 0.310196 0.938825 + outer loop + vertex 1.35071 2.10529 2.49103 + vertex 1.34865 2.10791 2.4905 + vertex 1.34637 2.10461 2.49195 + endloop + endfacet + facet normal 0.149527 0.310624 0.938698 + outer loop + vertex 1.35071 2.10529 2.49103 + vertex 1.34637 2.10461 2.49195 + vertex 1.35078 2.1013 2.49234 + endloop + endfacet + facet normal 0.145308 0.310756 0.939317 + outer loop + vertex 1.35071 2.10529 2.49103 + vertex 1.35078 2.1013 2.49234 + vertex 1.35468 2.10414 2.4908 + endloop + endfacet + facet normal 0.142795 0.313857 0.938671 + outer loop + vertex 1.35632 2.09971 2.49203 + vertex 1.35468 2.10414 2.4908 + vertex 1.35078 2.1013 2.49234 + endloop + endfacet + facet normal 0.140812 0.306431 0.94142 + outer loop + vertex 1.35226 2.09692 2.49355 + vertex 1.35632 2.09971 2.49203 + vertex 1.35078 2.1013 2.49234 + endloop + endfacet + facet normal 0.145049 0.307582 0.940401 + outer loop + vertex 1.35226 2.09692 2.49355 + vertex 1.35078 2.1013 2.49234 + vertex 1.34842 2.09801 2.49379 + endloop + endfacet + facet normal 0.143791 0.302753 0.94216 + outer loop + vertex 1.34834 2.09412 2.49505 + vertex 1.35226 2.09692 2.49355 + vertex 1.34842 2.09801 2.49379 + endloop + endfacet + facet normal 0.146295 0.302591 0.941826 + outer loop + vertex 1.34404 2.09732 2.49469 + vertex 1.34834 2.09412 2.49505 + vertex 1.34842 2.09801 2.49379 + endloop + endfacet + facet normal 0.145794 0.3049 0.941159 + outer loop + vertex 1.34842 2.09801 2.49379 + vertex 1.34645 2.10057 2.49326 + vertex 1.34404 2.09732 2.49469 + endloop + endfacet + facet normal 0.147369 0.303788 0.941273 + outer loop + vertex 1.34404 2.09732 2.49469 + vertex 1.34645 2.10057 2.49326 + vertex 1.34239 2.10185 2.49348 + endloop + endfacet + facet normal 0.148573 0.304147 0.940968 + outer loop + vertex 1.34404 2.09732 2.49469 + vertex 1.34239 2.10185 2.49348 + vertex 1.3383 2.09921 2.49498 + endloop + endfacet + facet normal 0.147137 0.29952 0.942676 + outer loop + vertex 1.3383 2.09921 2.49498 + vertex 1.34005 2.09456 2.49619 + vertex 1.34404 2.09732 2.49469 + endloop + endfacet + facet normal 0.146639 0.300171 0.942547 + outer loop + vertex 1.34005 2.09456 2.49619 + vertex 1.34408 2.09332 2.49596 + vertex 1.34404 2.09732 2.49469 + endloop + endfacet + facet normal 0.145323 0.295588 0.944197 + outer loop + vertex 1.34408 2.09332 2.49596 + vertex 1.34005 2.09456 2.49619 + vertex 1.34175 2.0901 2.49732 + endloop + endfacet + facet normal 0.144169 0.296393 0.944122 + outer loop + vertex 1.34606 2.09079 2.49645 + vertex 1.34408 2.09332 2.49596 + vertex 1.34175 2.0901 2.49732 + endloop + endfacet + facet normal 0.144495 0.294893 0.944542 + outer loop + vertex 1.34606 2.09079 2.49645 + vertex 1.34175 2.0901 2.49732 + vertex 1.34607 2.08682 2.49768 + endloop + endfacet + facet normal 0.142573 0.29497 0.94481 + outer loop + vertex 1.34606 2.09079 2.49645 + vertex 1.34607 2.08682 2.49768 + vertex 1.34994 2.08986 2.49615 + endloop + endfacet + facet normal 0.143312 0.298413 0.943616 + outer loop + vertex 1.34994 2.08986 2.49615 + vertex 1.34834 2.09412 2.49505 + vertex 1.34606 2.09079 2.49645 + endloop + endfacet + facet normal 0.1414 0.297816 0.944093 + outer loop + vertex 1.34834 2.09412 2.49505 + vertex 1.34994 2.08986 2.49615 + vertex 1.35332 2.09288 2.49469 + endloop + endfacet + facet normal 0.13985 0.299415 0.943818 + outer loop + vertex 1.34994 2.08986 2.49615 + vertex 1.35462 2.08883 2.49579 + vertex 1.35332 2.09288 2.49469 + endloop + endfacet + facet normal 0.13391 0.297866 0.945169 + outer loop + vertex 1.35332 2.09288 2.49469 + vertex 1.35462 2.08883 2.49579 + vertex 1.35851 2.09192 2.49426 + endloop + endfacet + facet normal 0.135112 0.3056 0.942525 + outer loop + vertex 1.35851 2.09192 2.49426 + vertex 1.35624 2.0956 2.49339 + vertex 1.35332 2.09288 2.49469 + endloop + endfacet + facet normal 0.137733 0.303003 0.942984 + outer loop + vertex 1.35332 2.09288 2.49469 + vertex 1.35624 2.0956 2.49339 + vertex 1.35226 2.09692 2.49355 + endloop + endfacet + facet normal 0.130176 0.302924 0.944082 + outer loop + vertex 1.35851 2.09192 2.49426 + vertex 1.3608 2.09654 2.49246 + vertex 1.35624 2.0956 2.49339 + endloop + endfacet + facet normal 0.128589 0.3089 0.942362 + outer loop + vertex 1.35632 2.09971 2.49203 + vertex 1.35624 2.0956 2.49339 + vertex 1.3608 2.09654 2.49246 + endloop + endfacet + facet normal 0.13129 0.312515 0.940796 + outer loop + vertex 1.36067 2.10051 2.49116 + vertex 1.35632 2.09971 2.49203 + vertex 1.3608 2.09654 2.49246 + endloop + endfacet + facet normal 0.117449 0.312644 0.942581 + outer loop + vertex 1.36067 2.10051 2.49116 + vertex 1.3608 2.09654 2.49246 + vertex 1.36467 2.09961 2.49096 + endloop + endfacet + facet normal 0.118309 0.316805 0.941083 + outer loop + vertex 1.36467 2.09961 2.49096 + vertex 1.36286 2.10377 2.48979 + vertex 1.36067 2.10051 2.49116 + endloop + endfacet + facet normal 0.112346 0.314614 0.942548 + outer loop + vertex 1.36286 2.10377 2.48979 + vertex 1.36467 2.09961 2.49096 + vertex 1.368 2.10275 2.48952 + endloop + endfacet + facet normal 0.113564 0.321444 0.940094 + outer loop + vertex 1.368 2.10275 2.48952 + vertex 1.36631 2.1061 2.48857 + vertex 1.36286 2.10377 2.48979 + endloop + endfacet + facet normal 0.117541 0.31254 0.942604 + outer loop + vertex 1.36612 2.09557 2.49212 + vertex 1.36467 2.09961 2.49096 + vertex 1.3608 2.09654 2.49246 + endloop + endfacet + facet normal 0.115954 0.302656 0.94602 + outer loop + vertex 1.36313 2.09285 2.49336 + vertex 1.36612 2.09557 2.49212 + vertex 1.3608 2.09654 2.49246 + endloop + endfacet + facet normal 0.113803 0.304824 0.945585 + outer loop + vertex 1.36728 2.09147 2.4933 + vertex 1.36612 2.09557 2.49212 + vertex 1.36313 2.09285 2.49336 + endloop + endfacet + facet normal 0.104603 0.302722 0.947321 + outer loop + vertex 1.36728 2.09147 2.4933 + vertex 1.37134 2.09435 2.49193 + vertex 1.36612 2.09557 2.49212 + endloop + endfacet + facet normal 0.106697 0.312164 0.944018 + outer loop + vertex 1.37134 2.09435 2.49193 + vertex 1.36956 2.09864 2.49072 + vertex 1.36612 2.09557 2.49212 + endloop + endfacet + facet normal 0.108849 0.309971 0.944494 + outer loop + vertex 1.36956 2.09864 2.49072 + vertex 1.36467 2.09961 2.49096 + vertex 1.36612 2.09557 2.49212 + endloop + endfacet + facet normal 0.130212 0.316916 0.939473 + outer loop + vertex 1.36067 2.10051 2.49116 + vertex 1.35863 2.10301 2.4906 + vertex 1.35632 2.09971 2.49203 + endloop + endfacet + facet normal 0.122847 0.306494 0.943912 + outer loop + vertex 1.36313 2.09285 2.49336 + vertex 1.3608 2.09654 2.49246 + vertex 1.35851 2.09192 2.49426 + endloop + endfacet + facet normal 0.133022 0.298885 0.944972 + outer loop + vertex 1.35462 2.08883 2.49579 + vertex 1.35858 2.0879 2.49552 + vertex 1.35851 2.09192 2.49426 + endloop + endfacet + facet normal 0.12225 0.299122 0.946351 + outer loop + vertex 1.35858 2.0879 2.49552 + vertex 1.36306 2.0887 2.49469 + vertex 1.35851 2.09192 2.49426 + endloop + endfacet + facet normal 0.124108 0.301608 0.94532 + outer loop + vertex 1.35851 2.09192 2.49426 + vertex 1.36306 2.0887 2.49469 + vertex 1.36313 2.09285 2.49336 + endloop + endfacet + facet normal 0.11294 0.302186 0.946535 + outer loop + vertex 1.36306 2.0887 2.49469 + vertex 1.36728 2.09147 2.4933 + vertex 1.36313 2.09285 2.49336 + endloop + endfacet + facet normal 0.110675 0.305265 0.945814 + outer loop + vertex 1.3688 2.08708 2.49454 + vertex 1.36728 2.09147 2.4933 + vertex 1.36306 2.0887 2.49469 + endloop + endfacet + facet normal 0.109428 0.300691 0.947423 + outer loop + vertex 1.36306 2.0887 2.49469 + vertex 1.36471 2.08421 2.49592 + vertex 1.3688 2.08708 2.49454 + endloop + endfacet + facet normal 0.105867 0.305259 0.946366 + outer loop + vertex 1.36471 2.08421 2.49592 + vertex 1.36879 2.08308 2.49583 + vertex 1.3688 2.08708 2.49454 + endloop + endfacet + facet normal 0.107354 0.310794 0.944395 + outer loop + vertex 1.36879 2.08308 2.49583 + vertex 1.36471 2.08421 2.49592 + vertex 1.36639 2.07975 2.4972 + endloop + endfacet + facet normal 0.0964506 0.318137 0.943126 + outer loop + vertex 1.37086 2.0806 2.49646 + vertex 1.36879 2.08308 2.49583 + vertex 1.36639 2.07975 2.4972 + endloop + endfacet + facet normal 0.0955038 0.322021 0.941903 + outer loop + vertex 1.37086 2.0806 2.49646 + vertex 1.36639 2.07975 2.4972 + vertex 1.37098 2.07666 2.49779 + endloop + endfacet + facet normal 0.0716451 0.322011 0.944021 + outer loop + vertex 1.37086 2.0806 2.49646 + vertex 1.37098 2.07666 2.49779 + vertex 1.37491 2.07993 2.49638 + endloop + endfacet + facet normal 0.0711661 0.31899 0.945083 + outer loop + vertex 1.37491 2.07993 2.49638 + vertex 1.37322 2.08409 2.4951 + vertex 1.37086 2.0806 2.49646 + endloop + endfacet + facet normal 0.0619768 0.315782 0.946805 + outer loop + vertex 1.37322 2.08409 2.4951 + vertex 1.37491 2.07993 2.49638 + vertex 1.3785 2.08337 2.495 + endloop + endfacet + facet normal 0.067145 0.326836 0.942693 + outer loop + vertex 1.37619 2.07612 2.49761 + vertex 1.37491 2.07993 2.49638 + vertex 1.37098 2.07666 2.49779 + endloop + endfacet + facet normal 0.05074 0.322174 0.94532 + outer loop + vertex 1.37976 2.07952 2.49626 + vertex 1.37491 2.07993 2.49638 + vertex 1.37619 2.07612 2.49761 + endloop + endfacet + facet normal 0.0460558 0.326588 0.944044 + outer loop + vertex 1.38096 2.07576 2.4975 + vertex 1.37976 2.07952 2.49626 + vertex 1.37619 2.07612 2.49761 + endloop + endfacet + facet normal 0.0855074 0.309957 0.946898 + outer loop + vertex 1.36879 2.08308 2.49583 + vertex 1.37086 2.0806 2.49646 + vertex 1.37322 2.08409 2.4951 + endloop + endfacet + facet normal 0.112522 0.312417 0.943257 + outer loop + vertex 1.36639 2.07975 2.4972 + vertex 1.36471 2.08421 2.49592 + vertex 1.36069 2.08137 2.49735 + endloop + endfacet + facet normal 0.111122 0.307319 0.945096 + outer loop + vertex 1.36229 2.07699 2.49858 + vertex 1.36639 2.07975 2.4972 + vertex 1.36069 2.08137 2.49735 + endloop + endfacet + facet normal 0.116372 0.308908 0.943945 + outer loop + vertex 1.36229 2.07699 2.49858 + vertex 1.36069 2.08137 2.49735 + vertex 1.35832 2.07809 2.49871 + endloop + endfacet + facet normal 0.117099 0.306617 0.944603 + outer loop + vertex 1.36063 2.08536 2.49606 + vertex 1.36069 2.08137 2.49735 + vertex 1.36471 2.08421 2.49592 + endloop + endfacet + facet normal 0.127037 0.306377 0.943395 + outer loop + vertex 1.36063 2.08536 2.49606 + vertex 1.35631 2.08452 2.49691 + vertex 1.36069 2.08137 2.49735 + endloop + endfacet + facet normal 0.123654 0.301943 0.945273 + outer loop + vertex 1.35631 2.08452 2.49691 + vertex 1.35631 2.0806 2.49816 + vertex 1.36069 2.08137 2.49735 + endloop + endfacet + facet normal 0.128034 0.302411 0.94454 + outer loop + vertex 1.36063 2.08536 2.49606 + vertex 1.35858 2.0879 2.49552 + vertex 1.35631 2.08452 2.49691 + endloop + endfacet + facet normal 0.116045 0.302729 0.945986 + outer loop + vertex 1.36471 2.08421 2.49592 + vertex 1.36306 2.0887 2.49469 + vertex 1.36063 2.08536 2.49606 + endloop + endfacet + facet normal 0.122436 0.298318 0.946581 + outer loop + vertex 1.35858 2.0879 2.49552 + vertex 1.36063 2.08536 2.49606 + vertex 1.36306 2.0887 2.49469 + endloop + endfacet + facet normal 0.13308 0.299156 0.944879 + outer loop + vertex 1.35858 2.0879 2.49552 + vertex 1.35462 2.08883 2.49579 + vertex 1.35631 2.08452 2.49691 + endloop + endfacet + facet normal 0.135458 0.299938 0.944293 + outer loop + vertex 1.35631 2.08452 2.49691 + vertex 1.35462 2.08883 2.49579 + vertex 1.35125 2.08579 2.49723 + endloop + endfacet + facet normal 0.135066 0.298221 0.944892 + outer loop + vertex 1.35237 2.08169 2.49837 + vertex 1.35631 2.08452 2.49691 + vertex 1.35125 2.08579 2.49723 + endloop + endfacet + facet normal 0.137336 0.29871 0.94441 + outer loop + vertex 1.35237 2.08169 2.49837 + vertex 1.35125 2.08579 2.49723 + vertex 1.34831 2.08308 2.49852 + endloop + endfacet + facet normal 0.140926 0.29511 0.945013 + outer loop + vertex 1.34831 2.08308 2.49852 + vertex 1.35125 2.08579 2.49723 + vertex 1.34607 2.08682 2.49768 + endloop + endfacet + facet normal 0.141707 0.295521 0.944768 + outer loop + vertex 1.34831 2.08308 2.49852 + vertex 1.34607 2.08682 2.49768 + vertex 1.34368 2.08229 2.49946 + endloop + endfacet + facet normal 0.140934 0.298908 0.943818 + outer loop + vertex 1.34368 2.08229 2.49946 + vertex 1.34826 2.0789 2.49985 + vertex 1.34831 2.08308 2.49852 + endloop + endfacet + facet normal 0.139748 0.297381 0.944476 + outer loop + vertex 1.34381 2.07818 2.50074 + vertex 1.34826 2.0789 2.49985 + vertex 1.34368 2.08229 2.49946 + endloop + endfacet + facet normal 0.142042 0.297348 0.944144 + outer loop + vertex 1.33978 2.07934 2.50098 + vertex 1.34381 2.07818 2.50074 + vertex 1.34368 2.08229 2.49946 + endloop + endfacet + facet normal 0.143696 0.295352 0.94452 + outer loop + vertex 1.33807 2.08376 2.49985 + vertex 1.33978 2.07934 2.50098 + vertex 1.34368 2.08229 2.49946 + endloop + endfacet + facet normal 0.143762 0.295628 0.944424 + outer loop + vertex 1.34368 2.08229 2.49946 + vertex 1.34156 2.0861 2.49859 + vertex 1.33807 2.08376 2.49985 + endloop + endfacet + facet normal 0.146012 0.292587 0.945026 + outer loop + vertex 1.33807 2.08376 2.49985 + vertex 1.34156 2.0861 2.49859 + vertex 1.33824 2.08776 2.49859 + endloop + endfacet + facet normal 0.149965 0.292255 0.944509 + outer loop + vertex 1.33368 2.08728 2.49946 + vertex 1.33807 2.08376 2.49985 + vertex 1.33824 2.08776 2.49859 + endloop + endfacet + facet normal 0.149917 0.292561 0.944422 + outer loop + vertex 1.33824 2.08776 2.49859 + vertex 1.33605 2.09178 2.49769 + vertex 1.33368 2.08728 2.49946 + endloop + endfacet + facet normal 0.153555 0.290649 0.944428 + outer loop + vertex 1.33368 2.08728 2.49946 + vertex 1.33605 2.09178 2.49769 + vertex 1.33148 2.09129 2.49859 + endloop + endfacet + facet normal 0.155556 0.291614 0.943803 + outer loop + vertex 1.33368 2.08728 2.49946 + vertex 1.33148 2.09129 2.49859 + vertex 1.32819 2.08886 2.49988 + endloop + endfacet + facet normal 0.154448 0.287351 0.945291 + outer loop + vertex 1.32819 2.08886 2.49988 + vertex 1.32985 2.08439 2.50097 + vertex 1.33368 2.08728 2.49946 + endloop + endfacet + facet normal 0.152674 0.289512 0.94492 + outer loop + vertex 1.32985 2.08439 2.50097 + vertex 1.33377 2.08317 2.50071 + vertex 1.33368 2.08728 2.49946 + endloop + endfacet + facet normal 0.153149 0.291146 0.944341 + outer loop + vertex 1.33377 2.08317 2.50071 + vertex 1.32985 2.08439 2.50097 + vertex 1.33142 2.07984 2.50212 + endloop + endfacet + facet normal 0.148867 0.29407 0.944119 + outer loop + vertex 1.33578 2.08051 2.50122 + vertex 1.33377 2.08317 2.50071 + vertex 1.33142 2.07984 2.50212 + endloop + endfacet + facet normal 0.147129 0.292876 0.944763 + outer loop + vertex 1.33377 2.08317 2.50071 + vertex 1.33578 2.08051 2.50122 + vertex 1.33807 2.08376 2.49985 + endloop + endfacet + facet normal 0.150841 0.290494 0.944913 + outer loop + vertex 1.33142 2.07984 2.50212 + vertex 1.32985 2.08439 2.50097 + vertex 1.32592 2.08152 2.50248 + endloop + endfacet + facet normal 0.150347 0.288752 0.945525 + outer loop + vertex 1.32735 2.07706 2.50361 + vertex 1.33142 2.07984 2.50212 + vertex 1.32592 2.08152 2.50248 + endloop + endfacet + facet normal 0.147958 0.288133 0.946091 + outer loop + vertex 1.32735 2.07706 2.50361 + vertex 1.32592 2.08152 2.50248 + vertex 1.32351 2.07816 2.50388 + endloop + endfacet + facet normal 0.147498 0.286379 0.946695 + outer loop + vertex 1.32341 2.07422 2.50508 + vertex 1.32735 2.07706 2.50361 + vertex 1.32351 2.07816 2.50388 + endloop + endfacet + facet normal 0.149156 0.286266 0.946469 + outer loop + vertex 1.31914 2.07741 2.50479 + vertex 1.32341 2.07422 2.50508 + vertex 1.32351 2.07816 2.50388 + endloop + endfacet + facet normal 0.149487 0.284797 0.94686 + outer loop + vertex 1.32351 2.07816 2.50388 + vertex 1.32158 2.08075 2.5034 + vertex 1.31914 2.07741 2.50479 + endloop + endfacet + facet normal 0.151484 0.28338 0.946968 + outer loop + vertex 1.31914 2.07741 2.50479 + vertex 1.32158 2.08075 2.5034 + vertex 1.31756 2.08199 2.50367 + endloop + endfacet + facet normal 0.15029 0.283038 0.947261 + outer loop + vertex 1.31914 2.07741 2.50479 + vertex 1.31756 2.08199 2.50367 + vertex 1.31343 2.07927 2.50514 + endloop + endfacet + facet normal 0.149852 0.281595 0.94776 + outer loop + vertex 1.31343 2.07927 2.50514 + vertex 1.31515 2.0746 2.50626 + vertex 1.31914 2.07741 2.50479 + endloop + endfacet + facet normal 0.148826 0.282927 0.947525 + outer loop + vertex 1.31515 2.0746 2.50626 + vertex 1.31916 2.07337 2.50599 + vertex 1.31914 2.07741 2.50479 + endloop + endfacet + facet normal 0.147563 0.278452 0.949047 + outer loop + vertex 1.31916 2.07337 2.50599 + vertex 1.31515 2.0746 2.50626 + vertex 1.31682 2.07015 2.5073 + endloop + endfacet + facet normal 0.146167 0.279436 0.948973 + outer loop + vertex 1.32112 2.07086 2.50643 + vertex 1.31916 2.07337 2.50599 + vertex 1.31682 2.07015 2.5073 + endloop + endfacet + facet normal 0.146774 0.276633 0.949701 + outer loop + vertex 1.32112 2.07086 2.50643 + vertex 1.31682 2.07015 2.5073 + vertex 1.32109 2.06689 2.50759 + endloop + endfacet + facet normal 0.14456 0.276741 0.950009 + outer loop + vertex 1.32112 2.07086 2.50643 + vertex 1.32109 2.06689 2.50759 + vertex 1.32503 2.06993 2.50611 + endloop + endfacet + facet normal 0.145547 0.281442 0.948476 + outer loop + vertex 1.32503 2.06993 2.50611 + vertex 1.32341 2.07422 2.50508 + vertex 1.32112 2.07086 2.50643 + endloop + endfacet + facet normal 0.147323 0.280264 0.94855 + outer loop + vertex 1.31916 2.07337 2.50599 + vertex 1.32112 2.07086 2.50643 + vertex 1.32341 2.07422 2.50508 + endloop + endfacet + facet normal 0.143204 0.280697 0.949053 + outer loop + vertex 1.32341 2.07422 2.50508 + vertex 1.32503 2.06993 2.50611 + vertex 1.32842 2.07294 2.5047 + endloop + endfacet + facet normal 0.143418 0.280471 0.949088 + outer loop + vertex 1.32503 2.06993 2.50611 + vertex 1.32978 2.06882 2.50572 + vertex 1.32842 2.07294 2.5047 + endloop + endfacet + facet normal 0.141606 0.279977 0.949505 + outer loop + vertex 1.32842 2.07294 2.5047 + vertex 1.32978 2.06882 2.50572 + vertex 1.3337 2.07178 2.50426 + endloop + endfacet + facet normal 0.14363 0.290475 0.946042 + outer loop + vertex 1.3337 2.07178 2.50426 + vertex 1.33135 2.07564 2.50343 + vertex 1.32842 2.07294 2.5047 + endloop + endfacet + facet normal 0.14485 0.289245 0.946232 + outer loop + vertex 1.32842 2.07294 2.5047 + vertex 1.33135 2.07564 2.50343 + vertex 1.32735 2.07706 2.50361 + endloop + endfacet + facet normal 0.145646 0.291566 0.945398 + outer loop + vertex 1.3337 2.07178 2.50426 + vertex 1.33594 2.07639 2.5025 + vertex 1.33135 2.07564 2.50343 + endloop + endfacet + facet normal 0.145108 0.294029 0.944717 + outer loop + vertex 1.33142 2.07984 2.50212 + vertex 1.33135 2.07564 2.50343 + vertex 1.33594 2.07639 2.5025 + endloop + endfacet + facet normal 0.148085 0.297752 0.943088 + outer loop + vertex 1.33578 2.08051 2.50122 + vertex 1.33142 2.07984 2.50212 + vertex 1.33594 2.07639 2.5025 + endloop + endfacet + facet normal 0.144225 0.297785 0.943675 + outer loop + vertex 1.33578 2.08051 2.50122 + vertex 1.33594 2.07639 2.5025 + vertex 1.33978 2.07934 2.50098 + endloop + endfacet + facet normal 0.143721 0.298383 0.943563 + outer loop + vertex 1.34155 2.07492 2.5021 + vertex 1.33978 2.07934 2.50098 + vertex 1.33594 2.07639 2.5025 + endloop + endfacet + facet normal 0.142903 0.294922 0.944775 + outer loop + vertex 1.33821 2.07247 2.50337 + vertex 1.34155 2.07492 2.5021 + vertex 1.33594 2.07639 2.5025 + endloop + endfacet + facet normal 0.144654 0.292751 0.945184 + outer loop + vertex 1.3415 2.07106 2.50331 + vertex 1.34155 2.07492 2.5021 + vertex 1.33821 2.07247 2.50337 + endloop + endfacet + facet normal 0.140877 0.293884 0.945403 + outer loop + vertex 1.33821 2.07247 2.50337 + vertex 1.33594 2.07639 2.5025 + vertex 1.3337 2.07178 2.50426 + endloop + endfacet + facet normal 0.143471 0.281398 0.948805 + outer loop + vertex 1.3337 2.07178 2.50426 + vertex 1.33856 2.06809 2.50462 + vertex 1.33821 2.07247 2.50337 + endloop + endfacet + facet normal 0.142065 0.279613 0.949544 + outer loop + vertex 1.33384 2.0677 2.50544 + vertex 1.33856 2.06809 2.50462 + vertex 1.3337 2.07178 2.50426 + endloop + endfacet + facet normal 0.141903 0.279614 0.949568 + outer loop + vertex 1.32978 2.06882 2.50572 + vertex 1.33384 2.0677 2.50544 + vertex 1.3337 2.07178 2.50426 + endloop + endfacet + facet normal 0.138393 0.265858 0.954027 + outer loop + vertex 1.33384 2.0677 2.50544 + vertex 1.32978 2.06882 2.50572 + vertex 1.33145 2.06438 2.50671 + endloop + endfacet + facet normal 0.141666 0.271978 0.951819 + outer loop + vertex 1.32978 2.06882 2.50572 + vertex 1.32503 2.06993 2.50611 + vertex 1.3263 2.06584 2.50709 + endloop + endfacet + facet normal 0.147718 0.277826 0.949206 + outer loop + vertex 1.31682 2.07015 2.5073 + vertex 1.31657 2.06616 2.50851 + vertex 1.32109 2.06689 2.50759 + endloop + endfacet + facet normal 0.152497 0.280014 0.947806 + outer loop + vertex 1.31682 2.07015 2.5073 + vertex 1.31515 2.0746 2.50626 + vertex 1.31116 2.07182 2.50772 + endloop + endfacet + facet normal 0.151101 0.27485 0.94954 + outer loop + vertex 1.3133 2.06783 2.50854 + vertex 1.31682 2.07015 2.5073 + vertex 1.31116 2.07182 2.50772 + endloop + endfacet + facet normal 0.153526 0.276003 0.948816 + outer loop + vertex 1.3133 2.06783 2.50854 + vertex 1.31116 2.07182 2.50772 + vertex 1.30878 2.06737 2.5094 + endloop + endfacet + facet normal 0.151975 0.280701 0.947687 + outer loop + vertex 1.31101 2.076 2.50651 + vertex 1.31116 2.07182 2.50772 + vertex 1.31515 2.0746 2.50626 + endloop + endfacet + facet normal 0.158876 0.280617 0.946579 + outer loop + vertex 1.31101 2.076 2.50651 + vertex 1.30628 2.07572 2.50738 + vertex 1.31116 2.07182 2.50772 + endloop + endfacet + facet normal 0.157787 0.279303 0.94715 + outer loop + vertex 1.30628 2.07572 2.50738 + vertex 1.30663 2.07133 2.50862 + vertex 1.31116 2.07182 2.50772 + endloop + endfacet + facet normal 0.15837 0.285168 0.945303 + outer loop + vertex 1.31101 2.076 2.50651 + vertex 1.30903 2.0788 2.50599 + vertex 1.30628 2.07572 2.50738 + endloop + endfacet + facet normal 0.159365 0.284321 0.945391 + outer loop + vertex 1.30585 2.08 2.50617 + vertex 1.30628 2.07572 2.50738 + vertex 1.30903 2.0788 2.50599 + endloop + endfacet + facet normal 0.1579 0.280249 0.946852 + outer loop + vertex 1.30903 2.0788 2.50599 + vertex 1.30866 2.08312 2.50478 + vertex 1.30585 2.08 2.50617 + endloop + endfacet + facet normal 0.153546 0.280087 0.947615 + outer loop + vertex 1.30903 2.0788 2.50599 + vertex 1.31343 2.07927 2.50514 + vertex 1.30866 2.08312 2.50478 + endloop + endfacet + facet normal 0.15424 0.280916 0.947257 + outer loop + vertex 1.30866 2.08312 2.50478 + vertex 1.31343 2.07927 2.50514 + vertex 1.31345 2.08338 2.50392 + endloop + endfacet + facet normal 0.154362 0.279746 0.947584 + outer loop + vertex 1.31345 2.08338 2.50392 + vertex 1.31163 2.08613 2.50341 + vertex 1.30866 2.08312 2.50478 + endloop + endfacet + facet normal 0.153395 0.279166 0.947911 + outer loop + vertex 1.31345 2.08338 2.50392 + vertex 1.316 2.08662 2.50255 + vertex 1.31163 2.08613 2.50341 + endloop + endfacet + facet normal 0.151585 0.280543 0.947796 + outer loop + vertex 1.31756 2.08199 2.50367 + vertex 1.316 2.08662 2.50255 + vertex 1.31345 2.08338 2.50392 + endloop + endfacet + facet normal 0.152964 0.280924 0.947462 + outer loop + vertex 1.31756 2.08199 2.50367 + vertex 1.3216 2.08487 2.50217 + vertex 1.316 2.08662 2.50255 + endloop + endfacet + facet normal 0.164489 0.284561 0.944441 + outer loop + vertex 1.30585 2.08 2.50617 + vertex 1.30155 2.07954 2.50706 + vertex 1.30628 2.07572 2.50738 + endloop + endfacet + facet normal 0.163798 0.283738 0.944808 + outer loop + vertex 1.30155 2.07954 2.50706 + vertex 1.30159 2.07548 2.50827 + vertex 1.30628 2.07572 2.50738 + endloop + endfacet + facet normal 0.164788 0.282732 0.944938 + outer loop + vertex 1.30585 2.08 2.50617 + vertex 1.30391 2.08281 2.50567 + vertex 1.30155 2.07954 2.50706 + endloop + endfacet + facet normal 0.153259 0.281883 0.947129 + outer loop + vertex 1.30903 2.0788 2.50599 + vertex 1.31101 2.076 2.50651 + vertex 1.31343 2.07927 2.50514 + endloop + endfacet + facet normal 0.15252 0.282412 0.947091 + outer loop + vertex 1.31515 2.0746 2.50626 + vertex 1.31343 2.07927 2.50514 + vertex 1.31101 2.076 2.50651 + endloop + endfacet + facet normal 0.15174 0.281035 0.947626 + outer loop + vertex 1.31343 2.07927 2.50514 + vertex 1.31756 2.08199 2.50367 + vertex 1.31345 2.08338 2.50392 + endloop + endfacet + facet normal 0.15137 0.282981 0.947106 + outer loop + vertex 1.32158 2.08075 2.5034 + vertex 1.3216 2.08487 2.50217 + vertex 1.31756 2.08199 2.50367 + endloop + endfacet + facet normal 0.151836 0.282959 0.947038 + outer loop + vertex 1.3216 2.08487 2.50217 + vertex 1.32158 2.08075 2.5034 + vertex 1.32592 2.08152 2.50248 + endloop + endfacet + facet normal 0.154095 0.285766 0.945829 + outer loop + vertex 1.32594 2.08559 2.50124 + vertex 1.3216 2.08487 2.50217 + vertex 1.32592 2.08152 2.50248 + endloop + endfacet + facet normal 0.154365 0.284555 0.94615 + outer loop + vertex 1.32594 2.08559 2.50124 + vertex 1.32397 2.08823 2.50077 + vertex 1.3216 2.08487 2.50217 + endloop + endfacet + facet normal 0.154756 0.284287 0.946167 + outer loop + vertex 1.32397 2.08823 2.50077 + vertex 1.32001 2.08946 2.50105 + vertex 1.3216 2.08487 2.50217 + endloop + endfacet + facet normal 0.156992 0.286344 0.945177 + outer loop + vertex 1.32397 2.08823 2.50077 + vertex 1.32594 2.08559 2.50124 + vertex 1.32819 2.08886 2.49988 + endloop + endfacet + facet normal 0.156302 0.28969 0.944272 + outer loop + vertex 1.32397 2.08823 2.50077 + vertex 1.32819 2.08886 2.49988 + vertex 1.32397 2.09224 2.49954 + endloop + endfacet + facet normal 0.157288 0.290864 0.943747 + outer loop + vertex 1.32397 2.09224 2.49954 + vertex 1.32819 2.08886 2.49988 + vertex 1.32825 2.09274 2.49867 + endloop + endfacet + facet normal 0.146624 0.283013 0.947842 + outer loop + vertex 1.31916 2.07337 2.50599 + vertex 1.32341 2.07422 2.50508 + vertex 1.31914 2.07741 2.50479 + endloop + endfacet + facet normal 0.145178 0.289312 0.946162 + outer loop + vertex 1.32842 2.07294 2.5047 + vertex 1.32735 2.07706 2.50361 + vertex 1.32341 2.07422 2.50508 + endloop + endfacet + facet normal 0.151143 0.285921 0.946259 + outer loop + vertex 1.32351 2.07816 2.50388 + vertex 1.32592 2.08152 2.50248 + vertex 1.32158 2.08075 2.5034 + endloop + endfacet + facet normal 0.146446 0.293949 0.944536 + outer loop + vertex 1.33135 2.07564 2.50343 + vertex 1.33142 2.07984 2.50212 + vertex 1.32735 2.07706 2.50361 + endloop + endfacet + facet normal 0.154648 0.285738 0.945747 + outer loop + vertex 1.32594 2.08559 2.50124 + vertex 1.32592 2.08152 2.50248 + vertex 1.32985 2.08439 2.50097 + endloop + endfacet + facet normal 0.155165 0.287572 0.945106 + outer loop + vertex 1.32985 2.08439 2.50097 + vertex 1.32819 2.08886 2.49988 + vertex 1.32594 2.08559 2.50124 + endloop + endfacet + facet normal 0.156102 0.290937 0.943921 + outer loop + vertex 1.32819 2.08886 2.49988 + vertex 1.33148 2.09129 2.49859 + vertex 1.32825 2.09274 2.49867 + endloop + endfacet + facet normal 0.157997 0.295238 0.942269 + outer loop + vertex 1.33148 2.09129 2.49859 + vertex 1.33114 2.09568 2.49727 + vertex 1.32825 2.09274 2.49867 + endloop + endfacet + facet normal 0.157432 0.295761 0.9422 + outer loop + vertex 1.32825 2.09274 2.49867 + vertex 1.33114 2.09568 2.49727 + vertex 1.32646 2.09539 2.49814 + endloop + endfacet + facet normal 0.152825 0.29511 0.943162 + outer loop + vertex 1.33114 2.09568 2.49727 + vertex 1.33148 2.09129 2.49859 + vertex 1.33605 2.09178 2.49769 + endloop + endfacet + facet normal 0.15389 0.296389 0.942588 + outer loop + vertex 1.33589 2.09598 2.4964 + vertex 1.33114 2.09568 2.49727 + vertex 1.33605 2.09178 2.49769 + endloop + endfacet + facet normal 0.148834 0.296442 0.943382 + outer loop + vertex 1.33589 2.09598 2.4964 + vertex 1.33605 2.09178 2.49769 + vertex 1.34005 2.09456 2.49619 + endloop + endfacet + facet normal 0.150126 0.300446 0.94191 + outer loop + vertex 1.34005 2.09456 2.49619 + vertex 1.3383 2.09921 2.49498 + vertex 1.33589 2.09598 2.4964 + endloop + endfacet + facet normal 0.148673 0.296652 0.943342 + outer loop + vertex 1.34175 2.0901 2.49732 + vertex 1.34005 2.09456 2.49619 + vertex 1.33605 2.09178 2.49769 + endloop + endfacet + facet normal 0.147214 0.291273 0.945245 + outer loop + vertex 1.33824 2.08776 2.49859 + vertex 1.34175 2.0901 2.49732 + vertex 1.33605 2.09178 2.49769 + endloop + endfacet + facet normal 0.147757 0.289635 0.945664 + outer loop + vertex 1.33377 2.08317 2.50071 + vertex 1.33807 2.08376 2.49985 + vertex 1.33368 2.08728 2.49946 + endloop + endfacet + facet normal 0.146107 0.292777 0.944952 + outer loop + vertex 1.34156 2.0861 2.49859 + vertex 1.34175 2.0901 2.49732 + vertex 1.33824 2.08776 2.49859 + endloop + endfacet + facet normal 0.143552 0.295306 0.944557 + outer loop + vertex 1.33978 2.07934 2.50098 + vertex 1.33807 2.08376 2.49985 + vertex 1.33578 2.08051 2.50122 + endloop + endfacet + facet normal 0.14218 0.297866 0.94396 + outer loop + vertex 1.34381 2.07818 2.50074 + vertex 1.33978 2.07934 2.50098 + vertex 1.34155 2.07492 2.5021 + endloop + endfacet + facet normal 0.141651 0.29822 0.943928 + outer loop + vertex 1.34588 2.07555 2.50126 + vertex 1.34381 2.07818 2.50074 + vertex 1.34155 2.07492 2.5021 + endloop + endfacet + facet normal 0.142846 0.292211 0.945626 + outer loop + vertex 1.34588 2.07555 2.50126 + vertex 1.34155 2.07492 2.5021 + vertex 1.3459 2.07152 2.5025 + endloop + endfacet + facet normal 0.139845 0.296934 0.944602 + outer loop + vertex 1.34381 2.07818 2.50074 + vertex 1.34588 2.07555 2.50126 + vertex 1.34826 2.0789 2.49985 + endloop + endfacet + facet normal 0.14259 0.295059 0.944779 + outer loop + vertex 1.34368 2.08229 2.49946 + vertex 1.34607 2.08682 2.49768 + vertex 1.34156 2.0861 2.49859 + endloop + endfacet + facet normal 0.139209 0.296085 0.944963 + outer loop + vertex 1.35462 2.08883 2.49579 + vertex 1.34994 2.08986 2.49615 + vertex 1.35125 2.08579 2.49723 + endloop + endfacet + facet normal 0.141177 0.296597 0.94451 + outer loop + vertex 1.35125 2.08579 2.49723 + vertex 1.34994 2.08986 2.49615 + vertex 1.34607 2.08682 2.49768 + endloop + endfacet + facet normal 0.143025 0.293044 0.945341 + outer loop + vertex 1.34175 2.0901 2.49732 + vertex 1.34156 2.0861 2.49859 + vertex 1.34607 2.08682 2.49768 + endloop + endfacet + facet normal 0.14523 0.297146 0.943723 + outer loop + vertex 1.34408 2.09332 2.49596 + vertex 1.34606 2.09079 2.49645 + vertex 1.34834 2.09412 2.49505 + endloop + endfacet + facet normal 0.148436 0.307422 0.939925 + outer loop + vertex 1.34645 2.10057 2.49326 + vertex 1.34637 2.10461 2.49195 + vertex 1.34239 2.10185 2.49348 + endloop + endfacet + facet normal 0.149599 0.305915 0.940232 + outer loop + vertex 1.34239 2.10185 2.49348 + vertex 1.34637 2.10461 2.49195 + vertex 1.34075 2.10639 2.49227 + endloop + endfacet + facet normal 0.149863 0.305992 0.940165 + outer loop + vertex 1.34239 2.10185 2.49348 + vertex 1.34075 2.10639 2.49227 + vertex 1.33827 2.10325 2.49368 + endloop + endfacet + facet normal 0.144461 0.300248 0.942858 + outer loop + vertex 1.34408 2.09332 2.49596 + vertex 1.34834 2.09412 2.49505 + vertex 1.34404 2.09732 2.49469 + endloop + endfacet + facet normal 0.14279 0.304018 0.941905 + outer loop + vertex 1.35332 2.09288 2.49469 + vertex 1.35226 2.09692 2.49355 + vertex 1.34834 2.09412 2.49505 + endloop + endfacet + facet normal 0.147368 0.305988 0.94056 + outer loop + vertex 1.34842 2.09801 2.49379 + vertex 1.35078 2.1013 2.49234 + vertex 1.34645 2.10057 2.49326 + endloop + endfacet + facet normal 0.139404 0.308267 0.94103 + outer loop + vertex 1.35624 2.0956 2.49339 + vertex 1.35632 2.09971 2.49203 + vertex 1.35226 2.09692 2.49355 + endloop + endfacet + facet normal 0.147029 0.307464 0.940132 + outer loop + vertex 1.34637 2.10461 2.49195 + vertex 1.34645 2.10057 2.49326 + vertex 1.35078 2.1013 2.49234 + endloop + endfacet + facet normal 0.149842 0.310352 0.938738 + outer loop + vertex 1.34865 2.10791 2.4905 + vertex 1.35071 2.10529 2.49103 + vertex 1.35292 2.10853 2.48961 + endloop + endfacet + facet normal 0.150376 0.308541 0.939249 + outer loop + vertex 1.34637 2.10461 2.49195 + vertex 1.34466 2.10912 2.49075 + vertex 1.34075 2.10639 2.49227 + endloop + endfacet + facet normal 0.152837 0.30585 0.939732 + outer loop + vertex 1.34068 2.11034 2.49099 + vertex 1.33864 2.11296 2.49047 + vertex 1.33645 2.10976 2.49186 + endloop + endfacet + facet normal 0.154956 0.304443 0.939842 + outer loop + vertex 1.33864 2.11296 2.49047 + vertex 1.33468 2.11415 2.49074 + vertex 1.33645 2.10976 2.49186 + endloop + endfacet + facet normal 0.154741 0.304371 0.939901 + outer loop + vertex 1.33645 2.10976 2.49186 + vertex 1.33468 2.11415 2.49074 + vertex 1.33088 2.11121 2.49231 + endloop + endfacet + facet normal 0.15448 0.303241 0.940309 + outer loop + vertex 1.33315 2.10733 2.49319 + vertex 1.33645 2.10976 2.49186 + vertex 1.33088 2.11121 2.49231 + endloop + endfacet + facet normal 0.154579 0.303075 0.940346 + outer loop + vertex 1.33468 2.11415 2.49074 + vertex 1.33864 2.11296 2.49047 + vertex 1.33851 2.11701 2.48918 + endloop + endfacet + facet normal 0.151213 0.304973 0.94028 + outer loop + vertex 1.33827 2.10325 2.49368 + vertex 1.34075 2.10639 2.49227 + vertex 1.33641 2.10594 2.49311 + endloop + endfacet + facet normal 0.149053 0.30348 0.941107 + outer loop + vertex 1.3383 2.09921 2.49498 + vertex 1.34239 2.10185 2.49348 + vertex 1.33827 2.10325 2.49368 + endloop + endfacet + facet normal 0.151317 0.299594 0.941991 + outer loop + vertex 1.33389 2.09877 2.49583 + vertex 1.33589 2.09598 2.4964 + vertex 1.3383 2.09921 2.49498 + endloop + endfacet + facet normal 0.153357 0.300907 0.941242 + outer loop + vertex 1.33589 2.09598 2.4964 + vertex 1.33389 2.09877 2.49583 + vertex 1.33114 2.09568 2.49727 + endloop + endfacet + facet normal 0.154993 0.302041 0.94061 + outer loop + vertex 1.32878 2.10257 2.49545 + vertex 1.33072 2.09991 2.49599 + vertex 1.33349 2.10297 2.49454 + endloop + endfacet + facet normal 0.156877 0.300536 0.94078 + outer loop + vertex 1.3265 2.09931 2.49688 + vertex 1.32646 2.09539 2.49814 + vertex 1.33114 2.09568 2.49727 + endloop + endfacet + facet normal 0.156535 0.295218 0.94252 + outer loop + vertex 1.32825 2.09274 2.49867 + vertex 1.32646 2.09539 2.49814 + vertex 1.32397 2.09224 2.49954 + endloop + endfacet + facet normal 0.156296 0.289691 0.944273 + outer loop + vertex 1.32001 2.08946 2.50105 + vertex 1.32397 2.08823 2.50077 + vertex 1.32397 2.09224 2.49954 + endloop + endfacet + facet normal 0.153867 0.284032 0.946388 + outer loop + vertex 1.3216 2.08487 2.50217 + vertex 1.32001 2.08946 2.50105 + vertex 1.316 2.08662 2.50255 + endloop + endfacet + facet normal 0.154142 0.287663 0.945246 + outer loop + vertex 1.31603 2.0907 2.50133 + vertex 1.31401 2.09335 2.50085 + vertex 1.31174 2.09006 2.50222 + endloop + endfacet + facet normal 0.155488 0.278693 0.94771 + outer loop + vertex 1.30866 2.08312 2.50478 + vertex 1.31163 2.08613 2.50341 + vertex 1.30838 2.08759 2.50351 + endloop + endfacet + facet normal 0.159139 0.279182 0.94696 + outer loop + vertex 1.30391 2.08281 2.50567 + vertex 1.30585 2.08 2.50617 + vertex 1.30866 2.08312 2.50478 + endloop + endfacet + facet normal 0.16547 0.28225 0.944963 + outer loop + vertex 1.30391 2.08281 2.50567 + vertex 1.29987 2.08423 2.50595 + vertex 1.30155 2.07954 2.50706 + endloop + endfacet + facet normal 0.166706 0.282615 0.944636 + outer loop + vertex 1.30155 2.07954 2.50706 + vertex 1.29987 2.08423 2.50595 + vertex 1.29595 2.08154 2.50745 + endloop + endfacet + facet normal 0.16644 0.281811 0.944923 + outer loop + vertex 1.29754 2.07693 2.50854 + vertex 1.30155 2.07954 2.50706 + vertex 1.29595 2.08154 2.50745 + endloop + endfacet + facet normal 0.166717 0.283775 0.944287 + outer loop + vertex 1.29594 2.08556 2.50624 + vertex 1.29396 2.08824 2.50579 + vertex 1.29173 2.08503 2.50715 + endloop + endfacet + facet normal 0.16622 0.281749 0.944981 + outer loop + vertex 1.29754 2.07693 2.50854 + vertex 1.29595 2.08154 2.50745 + vertex 1.29347 2.07839 2.50882 + endloop + endfacet + facet normal 0.162362 0.273576 0.948048 + outer loop + vertex 1.28402 2.07782 2.51061 + vertex 1.28875 2.07814 2.50971 + vertex 1.28387 2.0821 2.50941 + endloop + endfacet + facet normal 0.168463 0.281043 0.944794 + outer loop + vertex 1.28387 2.0821 2.50941 + vertex 1.28613 2.08674 2.50762 + vertex 1.28159 2.08623 2.50858 + endloop + endfacet + facet normal 0.167107 0.282772 0.944519 + outer loop + vertex 1.29166 2.08112 2.50833 + vertex 1.29173 2.08503 2.50715 + vertex 1.28842 2.08261 2.50846 + endloop + endfacet + facet normal 0.167506 0.286745 0.943249 + outer loop + vertex 1.28127 2.09069 2.50728 + vertex 1.28159 2.08623 2.50858 + vertex 1.28613 2.08674 2.50762 + endloop + endfacet + facet normal 0.168846 0.289706 0.942105 + outer loop + vertex 1.28088 2.09499 2.50603 + vertex 1.27656 2.09453 2.50695 + vertex 1.28127 2.09069 2.50728 + endloop + endfacet + facet normal 0.168023 0.288645 0.942577 + outer loop + vertex 1.27894 2.0978 2.50552 + vertex 1.28088 2.09499 2.50603 + vertex 1.28366 2.09802 2.50461 + endloop + endfacet + facet normal 0.166358 0.288955 0.942778 + outer loop + vertex 1.28401 2.09377 2.50585 + vertex 1.28595 2.09096 2.50637 + vertex 1.28823 2.09413 2.50499 + endloop + endfacet + facet normal 0.165962 0.288162 0.94309 + outer loop + vertex 1.28833 2.09801 2.50378 + vertex 1.29137 2.10081 2.50239 + vertex 1.2867 2.1008 2.50322 + endloop + endfacet + facet normal 0.168331 0.285598 0.94345 + outer loop + vertex 1.27894 2.0978 2.50552 + vertex 1.28366 2.09802 2.50461 + vertex 1.27879 2.10205 2.50426 + endloop + endfacet + facet normal 0.170775 0.281325 0.944295 + outer loop + vertex 1.28338 2.10247 2.50331 + vertex 1.28678 2.10471 2.50202 + vertex 1.28107 2.10665 2.50248 + endloop + endfacet + facet normal 0.169662 0.28072 0.944675 + outer loop + vertex 1.27879 2.10205 2.50426 + vertex 1.27652 2.10619 2.50344 + vertex 1.2732 2.10373 2.50476 + endloop + endfacet + facet normal 0.173134 0.274831 0.945776 + outer loop + vertex 1.26899 2.10316 2.5057 + vertex 1.2732 2.10373 2.50476 + vertex 1.26904 2.1072 2.50451 + endloop + endfacet + facet normal 0.174354 0.271093 0.946631 + outer loop + vertex 1.27333 2.10765 2.50359 + vertex 1.27625 2.11065 2.50219 + vertex 1.27158 2.11038 2.50313 + endloop + endfacet + facet normal 0.178637 0.270448 0.946016 + outer loop + vertex 1.27158 2.11038 2.50313 + vertex 1.27162 2.11452 2.50194 + vertex 1.26756 2.11188 2.50346 + endloop + endfacet + facet normal 0.179071 0.286372 0.941236 + outer loop + vertex 1.26583 2.12081 2.50119 + vertex 1.26388 2.12362 2.50071 + vertex 1.26121 2.12055 2.50215 + endloop + endfacet + facet normal 0.177396 0.287773 0.941125 + outer loop + vertex 1.26076 2.12484 2.50092 + vertex 1.26121 2.12055 2.50215 + vertex 1.26388 2.12362 2.50071 + endloop + endfacet + facet normal 0.179495 0.29352 0.93895 + outer loop + vertex 1.26388 2.12362 2.50071 + vertex 1.26341 2.12792 2.49945 + vertex 1.26076 2.12484 2.50092 + endloop + endfacet + facet normal 0.181845 0.288114 0.940172 + outer loop + vertex 1.26388 2.12362 2.50071 + vertex 1.26583 2.12081 2.50119 + vertex 1.2681 2.12394 2.49979 + endloop + endfacet + facet normal 0.182073 0.271364 0.945098 + outer loop + vertex 1.26351 2.11341 2.5038 + vertex 1.26592 2.11666 2.5024 + vertex 1.26162 2.11624 2.50335 + endloop + endfacet + facet normal 0.180873 0.270631 0.945539 + outer loop + vertex 1.26351 2.11341 2.5038 + vertex 1.26162 2.11624 2.50335 + vertex 1.25885 2.11315 2.50476 + endloop + endfacet + facet normal 0.180855 0.27304 0.94485 + outer loop + vertex 1.25422 2.11293 2.50571 + vertex 1.25885 2.11315 2.50476 + vertex 1.25417 2.11707 2.50453 + endloop + endfacet + facet normal 0.180989 0.273034 0.944826 + outer loop + vertex 1.25015 2.11448 2.50604 + vertex 1.25422 2.11293 2.50571 + vertex 1.25417 2.11707 2.50453 + endloop + endfacet + facet normal 0.178917 0.275977 0.944365 + outer loop + vertex 1.24845 2.11925 2.50497 + vertex 1.25015 2.11448 2.50604 + vertex 1.25417 2.11707 2.50453 + endloop + endfacet + facet normal 0.183383 0.277288 0.943124 + outer loop + vertex 1.25015 2.11448 2.50604 + vertex 1.24845 2.11925 2.50497 + vertex 1.24606 2.11603 2.50638 + endloop + endfacet + facet normal 0.180481 0.268993 0.946081 + outer loop + vertex 1.24606 2.11603 2.50638 + vertex 1.2462 2.11172 2.50758 + vertex 1.25015 2.11448 2.50604 + endloop + endfacet + facet normal 0.181136 0.268123 0.946203 + outer loop + vertex 1.25188 2.10976 2.50705 + vertex 1.25015 2.11448 2.50604 + vertex 1.2462 2.11172 2.50758 + endloop + endfacet + facet normal 0.183055 0.268943 0.945601 + outer loop + vertex 1.24606 2.11603 2.50638 + vertex 1.2414 2.11582 2.50735 + vertex 1.2462 2.11172 2.50758 + endloop + endfacet + facet normal 0.182805 0.268657 0.94573 + outer loop + vertex 1.2414 2.11582 2.50735 + vertex 1.24162 2.11134 2.50858 + vertex 1.2462 2.11172 2.50758 + endloop + endfacet + facet normal 0.187256 0.268639 0.944864 + outer loop + vertex 1.24162 2.11134 2.50858 + vertex 1.2414 2.11582 2.50735 + vertex 1.23837 2.11301 2.50875 + endloop + endfacet + facet normal 0.179026 0.267475 0.946788 + outer loop + vertex 1.25422 2.11293 2.50571 + vertex 1.25015 2.11448 2.50604 + vertex 1.25188 2.10976 2.50705 + endloop + endfacet + facet normal 0.180341 0.281555 0.942446 + outer loop + vertex 1.25849 2.11747 2.50359 + vertex 1.26121 2.12055 2.50215 + vertex 1.25657 2.12028 2.50312 + endloop + endfacet + facet normal 0.179432 0.289399 0.940241 + outer loop + vertex 1.2565 2.12438 2.50187 + vertex 1.25657 2.12028 2.50312 + vertex 1.26121 2.12055 2.50215 + endloop + endfacet + facet normal 0.17809 0.287805 0.940985 + outer loop + vertex 1.26076 2.12484 2.50092 + vertex 1.2565 2.12438 2.50187 + vertex 1.26121 2.12055 2.50215 + endloop + endfacet + facet normal 0.181492 0.283288 0.941705 + outer loop + vertex 1.25417 2.11707 2.50453 + vertex 1.25249 2.12181 2.50342 + vertex 1.24845 2.11925 2.50497 + endloop + endfacet + facet normal 0.183254 0.277382 0.943121 + outer loop + vertex 1.24415 2.11885 2.50593 + vertex 1.24606 2.11603 2.50638 + vertex 1.24845 2.11925 2.50497 + endloop + endfacet + facet normal 0.182253 0.276763 0.943497 + outer loop + vertex 1.24606 2.11603 2.50638 + vertex 1.24415 2.11885 2.50593 + vertex 1.2414 2.11582 2.50735 + endloop + endfacet + facet normal 0.185457 0.28314 0.940977 + outer loop + vertex 1.24108 2.12005 2.50617 + vertex 1.23919 2.12283 2.5057 + vertex 1.23693 2.11971 2.50709 + endloop + endfacet + facet normal 0.186368 0.269554 0.944779 + outer loop + vertex 1.23837 2.11301 2.50875 + vertex 1.2414 2.11582 2.50735 + vertex 1.23681 2.11581 2.50825 + endloop + endfacet + facet normal 0.186921 0.269829 0.944591 + outer loop + vertex 1.23837 2.11301 2.50875 + vertex 1.23681 2.11581 2.50825 + vertex 1.2338 2.11301 2.50965 + endloop + endfacet + facet normal 0.187167 0.265137 0.94587 + outer loop + vertex 1.2338 2.11301 2.50965 + vertex 1.23824 2.10906 2.50988 + vertex 1.23837 2.11301 2.50875 + endloop + endfacet + facet normal 0.185586 0.26527 0.946145 + outer loop + vertex 1.23824 2.10906 2.50988 + vertex 1.24162 2.11134 2.50858 + vertex 1.23837 2.11301 2.50875 + endloop + endfacet + facet normal 0.185523 0.265357 0.946133 + outer loop + vertex 1.24388 2.10709 2.50933 + vertex 1.24162 2.11134 2.50858 + vertex 1.23824 2.10906 2.50988 + endloop + endfacet + facet normal 0.183405 0.264351 0.946827 + outer loop + vertex 1.24388 2.10709 2.50933 + vertex 1.2462 2.11172 2.50758 + vertex 1.24162 2.11134 2.50858 + endloop + endfacet + facet normal 0.187395 0.265386 0.945756 + outer loop + vertex 1.23408 2.10873 2.5108 + vertex 1.23824 2.10906 2.50988 + vertex 1.2338 2.11301 2.50965 + endloop + endfacet + facet normal 0.189289 0.265408 0.945372 + outer loop + vertex 1.23408 2.10873 2.5108 + vertex 1.2338 2.11301 2.50965 + vertex 1.23104 2.10997 2.51106 + endloop + endfacet + facet normal 0.188079 0.262208 0.946506 + outer loop + vertex 1.23104 2.10997 2.51106 + vertex 1.23135 2.10562 2.5122 + vertex 1.23408 2.10873 2.5108 + endloop + endfacet + facet normal 0.187295 0.262884 0.946474 + outer loop + vertex 1.23592 2.10589 2.51122 + vertex 1.23408 2.10873 2.5108 + vertex 1.23135 2.10562 2.5122 + endloop + endfacet + facet normal 0.187748 0.262202 0.946573 + outer loop + vertex 1.23104 2.10997 2.51106 + vertex 1.22676 2.10954 2.51202 + vertex 1.23135 2.10562 2.5122 + endloop + endfacet + facet normal 0.186131 0.260344 0.947405 + outer loop + vertex 1.22676 2.10954 2.51202 + vertex 1.22674 2.10532 2.51319 + vertex 1.23135 2.10562 2.5122 + endloop + endfacet + facet normal 0.186084 0.260729 0.947308 + outer loop + vertex 1.22858 2.1025 2.5136 + vertex 1.23135 2.10562 2.5122 + vertex 1.22674 2.10532 2.51319 + endloop + endfacet + facet normal 0.184908 0.260025 0.947732 + outer loop + vertex 1.22858 2.1025 2.5136 + vertex 1.22674 2.10532 2.51319 + vertex 1.22429 2.10206 2.51456 + endloop + endfacet + facet normal 0.184309 0.263847 0.946792 + outer loop + vertex 1.22429 2.10206 2.51456 + vertex 1.22887 2.09819 2.51475 + vertex 1.22858 2.1025 2.5136 + endloop + endfacet + facet normal 0.181237 0.260288 0.948369 + outer loop + vertex 1.22427 2.09791 2.5157 + vertex 1.22887 2.09819 2.51475 + vertex 1.22429 2.10206 2.51456 + endloop + endfacet + facet normal 0.183974 0.260141 0.947882 + outer loop + vertex 1.22027 2.09943 2.51606 + vertex 1.22427 2.09791 2.5157 + vertex 1.22429 2.10206 2.51456 + endloop + endfacet + facet normal 0.186515 0.256537 0.948367 + outer loop + vertex 1.21864 2.10429 2.51507 + vertex 1.22027 2.09943 2.51606 + vertex 1.22429 2.10206 2.51456 + endloop + endfacet + facet normal 0.18718 0.258371 0.947738 + outer loop + vertex 1.22429 2.10206 2.51456 + vertex 1.22271 2.10688 2.51356 + vertex 1.21864 2.10429 2.51507 + endloop + endfacet + facet normal 0.18874 0.256102 0.948045 + outer loop + vertex 1.21864 2.10429 2.51507 + vertex 1.22271 2.10688 2.51356 + vertex 1.21865 2.10851 2.51393 + endloop + endfacet + facet normal 0.190772 0.255994 0.947667 + outer loop + vertex 1.21392 2.10846 2.51489 + vertex 1.21864 2.10429 2.51507 + vertex 1.21865 2.10851 2.51393 + endloop + endfacet + facet normal 0.18942 0.254493 0.948342 + outer loop + vertex 1.21429 2.10399 2.51602 + vertex 1.21864 2.10429 2.51507 + vertex 1.21392 2.10846 2.51489 + endloop + endfacet + facet normal 0.19275 0.254595 0.947644 + outer loop + vertex 1.21429 2.10399 2.51602 + vertex 1.21392 2.10846 2.51489 + vertex 1.2111 2.10546 2.51627 + endloop + endfacet + facet normal 0.192035 0.252952 0.948229 + outer loop + vertex 1.2111 2.10546 2.51627 + vertex 1.21145 2.10098 2.5174 + vertex 1.21429 2.10399 2.51602 + endloop + endfacet + facet normal 0.190137 0.254706 0.948142 + outer loop + vertex 1.21621 2.10102 2.51643 + vertex 1.21429 2.10399 2.51602 + vertex 1.21145 2.10098 2.5174 + endloop + endfacet + facet normal 0.18987 0.259012 0.947028 + outer loop + vertex 1.21621 2.10102 2.51643 + vertex 1.21145 2.10098 2.5174 + vertex 1.21632 2.09668 2.51759 + endloop + endfacet + facet normal 0.187369 0.259079 0.947508 + outer loop + vertex 1.21621 2.10102 2.51643 + vertex 1.21632 2.09668 2.51759 + vertex 1.22027 2.09943 2.51606 + endloop + endfacet + facet normal 0.184248 0.263267 0.946965 + outer loop + vertex 1.22194 2.09475 2.51704 + vertex 1.22027 2.09943 2.51606 + vertex 1.21632 2.09668 2.51759 + endloop + endfacet + facet normal 0.184506 0.2641 0.946683 + outer loop + vertex 1.21856 2.09246 2.51834 + vertex 1.22194 2.09475 2.51704 + vertex 1.21632 2.09668 2.51759 + endloop + endfacet + facet normal 0.184283 0.263995 0.946756 + outer loop + vertex 1.21856 2.09246 2.51834 + vertex 1.21632 2.09668 2.51759 + vertex 1.21401 2.09205 2.51934 + endloop + endfacet + facet normal 0.183466 0.269644 0.945321 + outer loop + vertex 1.21401 2.09205 2.51934 + vertex 1.21877 2.08798 2.51957 + vertex 1.21856 2.09246 2.51834 + endloop + endfacet + facet normal 0.181493 0.267398 0.94634 + outer loop + vertex 1.21412 2.08774 2.52053 + vertex 1.21877 2.08798 2.51957 + vertex 1.21401 2.09205 2.51934 + endloop + endfacet + facet normal 0.185766 0.263226 0.94668 + outer loop + vertex 1.21401 2.09205 2.51934 + vertex 1.21632 2.09668 2.51759 + vertex 1.21175 2.09632 2.51859 + endloop + endfacet + facet normal 0.184362 0.262562 0.947139 + outer loop + vertex 1.21401 2.09205 2.51934 + vertex 1.21175 2.09632 2.51859 + vertex 1.20834 2.09406 2.51988 + endloop + endfacet + facet normal 0.184564 0.263193 0.946924 + outer loop + vertex 1.20834 2.09406 2.51988 + vertex 1.21007 2.08929 2.52087 + vertex 1.21401 2.09205 2.51934 + endloop + endfacet + facet normal 0.181558 0.262277 0.947759 + outer loop + vertex 1.21007 2.08929 2.52087 + vertex 1.20834 2.09406 2.51988 + vertex 1.20601 2.09089 2.52121 + endloop + endfacet + facet normal 0.184957 0.259786 0.947788 + outer loop + vertex 1.20409 2.09383 2.52077 + vertex 1.20601 2.09089 2.52121 + vertex 1.20834 2.09406 2.51988 + endloop + endfacet + facet normal 0.185673 0.253032 0.949474 + outer loop + vertex 1.20409 2.09383 2.52077 + vertex 1.20834 2.09406 2.51988 + vertex 1.20376 2.09828 2.51965 + endloop + endfacet + facet normal 0.186292 0.253047 0.949349 + outer loop + vertex 1.20409 2.09383 2.52077 + vertex 1.20376 2.09828 2.51965 + vertex 1.20091 2.09529 2.52101 + endloop + endfacet + facet normal 0.187936 0.256851 0.948002 + outer loop + vertex 1.20091 2.09529 2.52101 + vertex 1.20131 2.09078 2.52215 + vertex 1.20409 2.09383 2.52077 + endloop + endfacet + facet normal 0.188957 0.256887 0.947789 + outer loop + vertex 1.20091 2.09529 2.52101 + vertex 1.19623 2.09518 2.52197 + vertex 1.20131 2.09078 2.52215 + endloop + endfacet + facet normal 0.185039 0.252453 0.949752 + outer loop + vertex 1.19623 2.09518 2.52197 + vertex 1.19666 2.0905 2.52313 + vertex 1.20131 2.09078 2.52215 + endloop + endfacet + facet normal 0.18987 0.257475 0.947447 + outer loop + vertex 1.20376 2.09828 2.51965 + vertex 1.20834 2.09406 2.51988 + vertex 1.20844 2.09809 2.51877 + endloop + endfacet + facet normal 0.189925 0.252286 0.948831 + outer loop + vertex 1.20844 2.09809 2.51877 + vertex 1.20674 2.10111 2.5183 + vertex 1.20376 2.09828 2.51965 + endloop + endfacet + facet normal 0.1921 0.250063 0.948981 + outer loop + vertex 1.20376 2.09828 2.51965 + vertex 1.20674 2.10111 2.5183 + vertex 1.20351 2.10274 2.51853 + endloop + endfacet + facet normal 0.192062 0.250063 0.948989 + outer loop + vertex 1.19883 2.10284 2.51945 + vertex 1.20376 2.09828 2.51965 + vertex 1.20351 2.10274 2.51853 + endloop + endfacet + facet normal 0.192037 0.250913 0.94877 + outer loop + vertex 1.20351 2.10274 2.51853 + vertex 1.20182 2.10575 2.51808 + vertex 1.19883 2.10284 2.51945 + endloop + endfacet + facet normal 0.191664 0.251285 0.948747 + outer loop + vertex 1.19883 2.10284 2.51945 + vertex 1.20182 2.10575 2.51808 + vertex 1.19856 2.1075 2.51827 + endloop + endfacet + facet normal 0.194627 0.251305 0.948138 + outer loop + vertex 1.19404 2.10709 2.51931 + vertex 1.19883 2.10284 2.51945 + vertex 1.19856 2.1075 2.51827 + endloop + endfacet + facet normal 0.193585 0.25851 0.946413 + outer loop + vertex 1.19856 2.1075 2.51827 + vertex 1.19634 2.11173 2.51757 + vertex 1.19404 2.10709 2.51931 + endloop + endfacet + facet normal 0.196308 0.257095 0.946238 + outer loop + vertex 1.19404 2.10709 2.51931 + vertex 1.19634 2.11173 2.51757 + vertex 1.19183 2.11134 2.51861 + endloop + endfacet + facet normal 0.197542 0.257667 0.945825 + outer loop + vertex 1.19404 2.10709 2.51931 + vertex 1.19183 2.11134 2.51861 + vertex 1.18845 2.10908 2.51993 + endloop + endfacet + facet normal 0.195574 0.251505 0.94789 + outer loop + vertex 1.18845 2.10908 2.51993 + vertex 1.19012 2.1043 2.52086 + vertex 1.19404 2.10709 2.51931 + endloop + endfacet + facet normal 0.196696 0.250018 0.948051 + outer loop + vertex 1.19012 2.1043 2.52086 + vertex 1.19411 2.10273 2.52044 + vertex 1.19404 2.10709 2.51931 + endloop + endfacet + facet normal 0.194794 0.244706 0.949828 + outer loop + vertex 1.19411 2.10273 2.52044 + vertex 1.19012 2.1043 2.52086 + vertex 1.19169 2.09942 2.52179 + endloop + endfacet + facet normal 0.193598 0.245589 0.949845 + outer loop + vertex 1.19597 2.09977 2.52083 + vertex 1.19411 2.10273 2.52044 + vertex 1.19169 2.09942 2.52179 + endloop + endfacet + facet normal 0.193317 0.247698 0.949355 + outer loop + vertex 1.19597 2.09977 2.52083 + vertex 1.19169 2.09942 2.52179 + vertex 1.19623 2.09518 2.52197 + endloop + endfacet + facet normal 0.192459 0.247692 0.94953 + outer loop + vertex 1.19597 2.09977 2.52083 + vertex 1.19623 2.09518 2.52197 + vertex 1.19912 2.09832 2.52057 + endloop + endfacet + facet normal 0.192266 0.247241 0.949687 + outer loop + vertex 1.19912 2.09832 2.52057 + vertex 1.19883 2.10284 2.51945 + vertex 1.19597 2.09977 2.52083 + endloop + endfacet + facet normal 0.189441 0.25042 0.949422 + outer loop + vertex 1.20091 2.09529 2.52101 + vertex 1.19912 2.09832 2.52057 + vertex 1.19623 2.09518 2.52197 + endloop + endfacet + facet normal 0.189234 0.250308 0.949493 + outer loop + vertex 1.19912 2.09832 2.52057 + vertex 1.20091 2.09529 2.52101 + vertex 1.20376 2.09828 2.51965 + endloop + endfacet + facet normal 0.189282 0.24345 0.951265 + outer loop + vertex 1.19169 2.09942 2.52179 + vertex 1.19149 2.09532 2.52288 + vertex 1.19623 2.09518 2.52197 + endloop + endfacet + facet normal 0.193975 0.243006 0.950432 + outer loop + vertex 1.19149 2.09532 2.52288 + vertex 1.19169 2.09942 2.52179 + vertex 1.18774 2.09688 2.52325 + endloop + endfacet + facet normal 0.194488 0.244342 0.949985 + outer loop + vertex 1.18901 2.09333 2.5239 + vertex 1.19149 2.09532 2.52288 + vertex 1.18774 2.09688 2.52325 + endloop + endfacet + facet normal 0.195264 0.244578 0.949765 + outer loop + vertex 1.18901 2.09333 2.5239 + vertex 1.18774 2.09688 2.52325 + vertex 1.18418 2.09358 2.52483 + endloop + endfacet + facet normal 0.195271 0.252184 0.947772 + outer loop + vertex 1.18418 2.09358 2.52483 + vertex 1.18877 2.08928 2.52503 + vertex 1.18901 2.09333 2.5239 + endloop + endfacet + facet normal 0.197212 0.242536 0.949886 + outer loop + vertex 1.18418 2.09358 2.52483 + vertex 1.18774 2.09688 2.52325 + vertex 1.18379 2.09828 2.52371 + endloop + endfacet + facet normal 0.196985 0.241818 0.950116 + outer loop + vertex 1.18774 2.09688 2.52325 + vertex 1.18613 2.10166 2.52236 + vertex 1.18379 2.09828 2.52371 + endloop + endfacet + facet normal 0.197627 0.241368 0.950097 + outer loop + vertex 1.18379 2.09828 2.52371 + vertex 1.18613 2.10166 2.52236 + vertex 1.1818 2.10134 2.52334 + endloop + endfacet + facet normal 0.196852 0.240899 0.950377 + outer loop + vertex 1.18379 2.09828 2.52371 + vertex 1.1818 2.10134 2.52334 + vertex 1.17898 2.09828 2.5247 + endloop + endfacet + facet normal 0.197071 0.24577 0.949084 + outer loop + vertex 1.18141 2.1059 2.52224 + vertex 1.1818 2.10134 2.52334 + vertex 1.18613 2.10166 2.52236 + endloop + endfacet + facet normal 0.196694 0.245356 0.949269 + outer loop + vertex 1.18612 2.10591 2.52127 + vertex 1.18141 2.1059 2.52224 + vertex 1.18613 2.10166 2.52236 + endloop + endfacet + facet normal 0.19646 0.245367 0.949315 + outer loop + vertex 1.18612 2.10591 2.52127 + vertex 1.18613 2.10166 2.52236 + vertex 1.19012 2.1043 2.52086 + endloop + endfacet + facet normal 0.196333 0.252177 0.947555 + outer loop + vertex 1.18612 2.10591 2.52127 + vertex 1.18424 2.10887 2.52087 + vertex 1.18141 2.1059 2.52224 + endloop + endfacet + facet normal 0.194902 0.253511 0.947494 + outer loop + vertex 1.18106 2.11039 2.52112 + vertex 1.18141 2.1059 2.52224 + vertex 1.18424 2.10887 2.52087 + endloop + endfacet + facet normal 0.197512 0.259332 0.945376 + outer loop + vertex 1.18424 2.10887 2.52087 + vertex 1.18389 2.11331 2.51972 + vertex 1.18106 2.11039 2.52112 + endloop + endfacet + facet normal 0.197514 0.259331 0.945376 + outer loop + vertex 1.17924 2.11343 2.52066 + vertex 1.18106 2.11039 2.52112 + vertex 1.18389 2.11331 2.51972 + endloop + endfacet + facet normal 0.197503 0.259725 0.94527 + outer loop + vertex 1.17924 2.11343 2.52066 + vertex 1.18389 2.11331 2.51972 + vertex 1.17889 2.11789 2.51951 + endloop + endfacet + facet normal 0.198162 0.259741 0.945128 + outer loop + vertex 1.17924 2.11343 2.52066 + vertex 1.17889 2.11789 2.51951 + vertex 1.17605 2.11491 2.52092 + endloop + endfacet + facet normal 0.197824 0.258958 0.945413 + outer loop + vertex 1.17605 2.11491 2.52092 + vertex 1.17643 2.11043 2.52207 + vertex 1.17924 2.11343 2.52066 + endloop + endfacet + facet normal 0.20078 0.259038 0.944768 + outer loop + vertex 1.17605 2.11491 2.52092 + vertex 1.17176 2.11456 2.52193 + vertex 1.17643 2.11043 2.52207 + endloop + endfacet + facet normal 0.200788 0.258978 0.944783 + outer loop + vertex 1.17605 2.11491 2.52092 + vertex 1.17418 2.11783 2.52052 + vertex 1.17176 2.11456 2.52193 + endloop + endfacet + facet normal 0.199684 0.258326 0.945195 + outer loop + vertex 1.17418 2.11783 2.52052 + vertex 1.17605 2.11491 2.52092 + vertex 1.17889 2.11789 2.51951 + endloop + endfacet + facet normal 0.199815 0.256429 0.945684 + outer loop + vertex 1.17418 2.11783 2.52052 + vertex 1.17889 2.11789 2.51951 + vertex 1.17421 2.12203 2.51938 + endloop + endfacet + facet normal 0.201479 0.258281 0.944826 + outer loop + vertex 1.17421 2.12203 2.51938 + vertex 1.17889 2.11789 2.51951 + vertex 1.1785 2.12239 2.51836 + endloop + endfacet + facet normal 0.20056 0.258253 0.94503 + outer loop + vertex 1.17889 2.11789 2.51951 + vertex 1.18171 2.12088 2.51809 + vertex 1.1785 2.12239 2.51836 + endloop + endfacet + facet normal 0.200142 0.257297 0.945379 + outer loop + vertex 1.18171 2.12088 2.51809 + vertex 1.18131 2.12536 2.51696 + vertex 1.1785 2.12239 2.51836 + endloop + endfacet + facet normal 0.199296 0.257268 0.945566 + outer loop + vertex 1.18131 2.12536 2.51696 + vertex 1.18171 2.12088 2.51809 + vertex 1.18644 2.12066 2.51716 + endloop + endfacet + facet normal 0.199282 0.259649 0.944918 + outer loop + vertex 1.18356 2.11779 2.51855 + vertex 1.18644 2.12066 2.51716 + vertex 1.18171 2.12088 2.51809 + endloop + endfacet + facet normal 0.197895 0.261 0.944837 + outer loop + vertex 1.18685 2.11611 2.51833 + vertex 1.18644 2.12066 2.51716 + vertex 1.18356 2.11779 2.51855 + endloop + endfacet + facet normal 0.198084 0.26139 0.944689 + outer loop + vertex 1.18389 2.11331 2.51972 + vertex 1.18685 2.11611 2.51833 + vertex 1.18356 2.11779 2.51855 + endloop + endfacet + facet normal 0.197506 0.261979 0.944647 + outer loop + vertex 1.18857 2.11309 2.5188 + vertex 1.18685 2.11611 2.51833 + vertex 1.18389 2.11331 2.51972 + endloop + endfacet + facet normal 0.197525 0.259361 0.945365 + outer loop + vertex 1.18389 2.11331 2.51972 + vertex 1.18845 2.10908 2.51993 + vertex 1.18857 2.11309 2.5188 + endloop + endfacet + facet normal 0.197935 0.2622 0.944496 + outer loop + vertex 1.18857 2.11309 2.5188 + vertex 1.19153 2.11596 2.51739 + vertex 1.18685 2.11611 2.51833 + endloop + endfacet + facet normal 0.197751 0.262384 0.944484 + outer loop + vertex 1.19183 2.11134 2.51861 + vertex 1.19153 2.11596 2.51739 + vertex 1.18857 2.11309 2.5188 + endloop + endfacet + facet normal 0.199136 0.259569 0.94497 + outer loop + vertex 1.18356 2.11779 2.51855 + vertex 1.18171 2.12088 2.51809 + vertex 1.17889 2.11789 2.51951 + endloop + endfacet + facet normal 0.199075 0.261407 0.944476 + outer loop + vertex 1.17889 2.11789 2.51951 + vertex 1.18389 2.11331 2.51972 + vertex 1.18356 2.11779 2.51855 + endloop + endfacet + facet normal 0.197454 0.259298 0.945398 + outer loop + vertex 1.18106 2.11039 2.52112 + vertex 1.17924 2.11343 2.52066 + vertex 1.17643 2.11043 2.52207 + endloop + endfacet + facet normal 0.197497 0.259332 0.945379 + outer loop + vertex 1.18424 2.10887 2.52087 + vertex 1.18845 2.10908 2.51993 + vertex 1.18389 2.11331 2.51972 + endloop + endfacet + facet normal 0.197716 0.253583 0.946892 + outer loop + vertex 1.18106 2.11039 2.52112 + vertex 1.17643 2.11043 2.52207 + vertex 1.18141 2.1059 2.52224 + endloop + endfacet + facet normal 0.198043 0.253937 0.946729 + outer loop + vertex 1.17643 2.11043 2.52207 + vertex 1.17677 2.10596 2.5232 + vertex 1.18141 2.1059 2.52224 + endloop + endfacet + facet normal 0.19814 0.253238 0.946895 + outer loop + vertex 1.18424 2.10887 2.52087 + vertex 1.18612 2.10591 2.52127 + vertex 1.18845 2.10908 2.51993 + endloop + endfacet + facet normal 0.199349 0.245844 0.948589 + outer loop + vertex 1.1818 2.10134 2.52334 + vertex 1.18141 2.1059 2.52224 + vertex 1.17857 2.10289 2.52362 + endloop + endfacet + facet normal 0.18994 0.249786 0.949489 + outer loop + vertex 1.19276 2.09179 2.52355 + vertex 1.19149 2.09532 2.52288 + vertex 1.18901 2.09333 2.5239 + endloop + endfacet + facet normal 0.189163 0.249549 0.949707 + outer loop + vertex 1.19276 2.09179 2.52355 + vertex 1.19623 2.09518 2.52197 + vertex 1.19149 2.09532 2.52288 + endloop + endfacet + facet normal 0.195146 0.241294 0.950629 + outer loop + vertex 1.18774 2.09688 2.52325 + vertex 1.19169 2.09942 2.52179 + vertex 1.18613 2.10166 2.52236 + endloop + endfacet + facet normal 0.193887 0.245756 0.949743 + outer loop + vertex 1.19411 2.10273 2.52044 + vertex 1.19597 2.09977 2.52083 + vertex 1.19883 2.10284 2.51945 + endloop + endfacet + facet normal 0.196586 0.245188 0.949335 + outer loop + vertex 1.19169 2.09942 2.52179 + vertex 1.19012 2.1043 2.52086 + vertex 1.18613 2.10166 2.52236 + endloop + endfacet + facet normal 0.199093 0.252533 0.946884 + outer loop + vertex 1.19012 2.1043 2.52086 + vertex 1.18845 2.10908 2.51993 + vertex 1.18612 2.10591 2.52127 + endloop + endfacet + facet normal 0.196251 0.259465 0.945602 + outer loop + vertex 1.18845 2.10908 2.51993 + vertex 1.19183 2.11134 2.51861 + vertex 1.18857 2.11309 2.5188 + endloop + endfacet + facet normal 0.19556 0.262361 0.944946 + outer loop + vertex 1.19153 2.11596 2.51739 + vertex 1.19183 2.11134 2.51861 + vertex 1.19634 2.11173 2.51757 + endloop + endfacet + facet normal 0.19702 0.26399 0.944189 + outer loop + vertex 1.19622 2.11598 2.51641 + vertex 1.19153 2.11596 2.51739 + vertex 1.19634 2.11173 2.51757 + endloop + endfacet + facet normal 0.193236 0.264095 0.944941 + outer loop + vertex 1.19622 2.11598 2.51641 + vertex 1.19634 2.11173 2.51757 + vertex 1.2002 2.11446 2.51602 + endloop + endfacet + facet normal 0.193886 0.263236 0.945048 + outer loop + vertex 1.20192 2.10976 2.51697 + vertex 1.2002 2.11446 2.51602 + vertex 1.19634 2.11173 2.51757 + endloop + endfacet + facet normal 0.192187 0.257853 0.946877 + outer loop + vertex 1.19856 2.1075 2.51827 + vertex 1.20192 2.10976 2.51697 + vertex 1.19634 2.11173 2.51757 + endloop + endfacet + facet normal 0.193563 0.250124 0.948668 + outer loop + vertex 1.19411 2.10273 2.52044 + vertex 1.19883 2.10284 2.51945 + vertex 1.19404 2.10709 2.51931 + endloop + endfacet + facet normal 0.193852 0.255543 0.947164 + outer loop + vertex 1.20182 2.10575 2.51808 + vertex 1.20192 2.10976 2.51697 + vertex 1.19856 2.1075 2.51827 + endloop + endfacet + facet normal 0.192478 0.255648 0.947416 + outer loop + vertex 1.20192 2.10976 2.51697 + vertex 1.20182 2.10575 2.51808 + vertex 1.20648 2.10556 2.51718 + endloop + endfacet + facet normal 0.19185 0.254982 0.947722 + outer loop + vertex 1.20613 2.10999 2.51606 + vertex 1.20192 2.10976 2.51697 + vertex 1.20648 2.10556 2.51718 + endloop + endfacet + facet normal 0.191058 0.25496 0.947888 + outer loop + vertex 1.20613 2.10999 2.51606 + vertex 1.20648 2.10556 2.51718 + vertex 1.2093 2.10849 2.51582 + endloop + endfacet + facet normal 0.193696 0.26089 0.945737 + outer loop + vertex 1.2093 2.10849 2.51582 + vertex 1.20893 2.11293 2.51468 + vertex 1.20613 2.10999 2.51606 + endloop + endfacet + facet normal 0.192352 0.260851 0.946022 + outer loop + vertex 1.2093 2.10849 2.51582 + vertex 1.21392 2.10846 2.51489 + vertex 1.20893 2.11293 2.51468 + endloop + endfacet + facet normal 0.191332 0.259736 0.946535 + outer loop + vertex 1.20893 2.11293 2.51468 + vertex 1.21392 2.10846 2.51489 + vertex 1.21358 2.11286 2.51375 + endloop + endfacet + facet normal 0.191071 0.266174 0.944798 + outer loop + vertex 1.21358 2.11286 2.51375 + vertex 1.21187 2.1158 2.51327 + vertex 1.20893 2.11293 2.51468 + endloop + endfacet + facet normal 0.190247 0.259711 0.946761 + outer loop + vertex 1.21392 2.10846 2.51489 + vertex 1.21676 2.11143 2.51351 + vertex 1.21358 2.11286 2.51375 + endloop + endfacet + facet normal 0.192863 0.265894 0.944513 + outer loop + vertex 1.21676 2.11143 2.51351 + vertex 1.21646 2.11581 2.51234 + vertex 1.21358 2.11286 2.51375 + endloop + endfacet + facet normal 0.190575 0.265863 0.944986 + outer loop + vertex 1.21646 2.11581 2.51234 + vertex 1.21676 2.11143 2.51351 + vertex 1.2211 2.11175 2.51254 + endloop + endfacet + facet normal 0.190803 0.266118 0.944868 + outer loop + vertex 1.22107 2.11596 2.51136 + vertex 1.21646 2.11581 2.51234 + vertex 1.2211 2.11175 2.51254 + endloop + endfacet + facet normal 0.189427 0.266181 0.945127 + outer loop + vertex 1.22107 2.11596 2.51136 + vertex 1.2211 2.11175 2.51254 + vertex 1.22511 2.11439 2.511 + endloop + endfacet + facet normal 0.189973 0.265412 0.945234 + outer loop + vertex 1.22676 2.10954 2.51202 + vertex 1.22511 2.11439 2.511 + vertex 1.2211 2.11175 2.51254 + endloop + endfacet + facet normal 0.188015 0.259961 0.947138 + outer loop + vertex 1.22271 2.10688 2.51356 + vertex 1.22676 2.10954 2.51202 + vertex 1.2211 2.11175 2.51254 + endloop + endfacet + facet normal 0.191351 0.259901 0.946486 + outer loop + vertex 1.21865 2.10851 2.51393 + vertex 1.2211 2.11175 2.51254 + vertex 1.21676 2.11143 2.51351 + endloop + endfacet + facet normal 0.190553 0.259427 0.946777 + outer loop + vertex 1.21865 2.10851 2.51393 + vertex 1.21676 2.11143 2.51351 + vertex 1.21392 2.10846 2.51489 + endloop + endfacet + facet normal 0.191808 0.254259 0.947925 + outer loop + vertex 1.2111 2.10546 2.51627 + vertex 1.2093 2.10849 2.51582 + vertex 1.20648 2.10556 2.51718 + endloop + endfacet + facet normal 0.191153 0.261416 0.946109 + outer loop + vertex 1.20613 2.10999 2.51606 + vertex 1.20421 2.11292 2.51564 + vertex 1.20192 2.10976 2.51697 + endloop + endfacet + facet normal 0.192523 0.251162 0.948606 + outer loop + vertex 1.20351 2.10274 2.51853 + vertex 1.20648 2.10556 2.51718 + vertex 1.20182 2.10575 2.51808 + endloop + endfacet + facet normal 0.189361 0.2472 0.950281 + outer loop + vertex 1.19912 2.09832 2.52057 + vertex 1.20376 2.09828 2.51965 + vertex 1.19883 2.10284 2.51945 + endloop + endfacet + facet normal 0.192593 0.251091 0.94861 + outer loop + vertex 1.20674 2.10111 2.5183 + vertex 1.20648 2.10556 2.51718 + vertex 1.20351 2.10274 2.51853 + endloop + endfacet + facet normal 0.190083 0.251073 0.949121 + outer loop + vertex 1.20648 2.10556 2.51718 + vertex 1.20674 2.10111 2.5183 + vertex 1.21145 2.10098 2.5174 + endloop + endfacet + facet normal 0.190054 0.252352 0.948788 + outer loop + vertex 1.20844 2.09809 2.51877 + vertex 1.21145 2.10098 2.5174 + vertex 1.20674 2.10111 2.5183 + endloop + endfacet + facet normal 0.186834 0.255591 0.94856 + outer loop + vertex 1.21175 2.09632 2.51859 + vertex 1.21145 2.10098 2.5174 + vertex 1.20844 2.09809 2.51877 + endloop + endfacet + facet normal 0.184772 0.259676 0.947854 + outer loop + vertex 1.20601 2.09089 2.52121 + vertex 1.20409 2.09383 2.52077 + vertex 1.20131 2.09078 2.52215 + endloop + endfacet + facet normal 0.184432 0.264147 0.946684 + outer loop + vertex 1.20601 2.09089 2.52121 + vertex 1.20131 2.09078 2.52215 + vertex 1.20604 2.0867 2.52237 + endloop + endfacet + facet normal 0.187888 0.257625 0.947801 + outer loop + vertex 1.20834 2.09406 2.51988 + vertex 1.21175 2.09632 2.51859 + vertex 1.20844 2.09809 2.51877 + endloop + endfacet + facet normal 0.186794 0.25559 0.948568 + outer loop + vertex 1.21145 2.10098 2.5174 + vertex 1.21175 2.09632 2.51859 + vertex 1.21632 2.09668 2.51759 + endloop + endfacet + facet normal 0.19185 0.252947 0.948268 + outer loop + vertex 1.2111 2.10546 2.51627 + vertex 1.20648 2.10556 2.51718 + vertex 1.21145 2.10098 2.5174 + endloop + endfacet + facet normal 0.192629 0.254706 0.947639 + outer loop + vertex 1.2093 2.10849 2.51582 + vertex 1.2111 2.10546 2.51627 + vertex 1.21392 2.10846 2.51489 + endloop + endfacet + facet normal 0.189445 0.254292 0.948391 + outer loop + vertex 1.21429 2.10399 2.51602 + vertex 1.21621 2.10102 2.51643 + vertex 1.21864 2.10429 2.51507 + endloop + endfacet + facet normal 0.190401 0.260615 0.946481 + outer loop + vertex 1.22271 2.10688 2.51356 + vertex 1.2211 2.11175 2.51254 + vertex 1.21865 2.10851 2.51393 + endloop + endfacet + facet normal 0.186445 0.256517 0.948387 + outer loop + vertex 1.22027 2.09943 2.51606 + vertex 1.21864 2.10429 2.51507 + vertex 1.21621 2.10102 2.51643 + endloop + endfacet + facet normal 0.185161 0.263539 0.946712 + outer loop + vertex 1.22427 2.09791 2.5157 + vertex 1.22027 2.09943 2.51606 + vertex 1.22194 2.09475 2.51704 + endloop + endfacet + facet normal 0.187134 0.258359 0.947751 + outer loop + vertex 1.22429 2.10206 2.51456 + vertex 1.22674 2.10532 2.51319 + vertex 1.22271 2.10688 2.51356 + endloop + endfacet + facet normal 0.187809 0.260253 0.947099 + outer loop + vertex 1.22674 2.10532 2.51319 + vertex 1.22676 2.10954 2.51202 + vertex 1.22271 2.10688 2.51356 + endloop + endfacet + facet normal 0.187348 0.264763 0.945939 + outer loop + vertex 1.23104 2.10997 2.51106 + vertex 1.22916 2.11282 2.51063 + vertex 1.22676 2.10954 2.51202 + endloop + endfacet + facet normal 0.187701 0.263125 0.946326 + outer loop + vertex 1.23408 2.10873 2.5108 + vertex 1.23592 2.10589 2.51122 + vertex 1.23824 2.10906 2.50988 + endloop + endfacet + facet normal 0.185552 0.27124 0.944457 + outer loop + vertex 1.2338 2.11301 2.50965 + vertex 1.23681 2.11581 2.50825 + vertex 1.23358 2.11748 2.50841 + endloop + endfacet + facet normal 0.188937 0.265719 0.945355 + outer loop + vertex 1.22916 2.11282 2.51063 + vertex 1.23104 2.10997 2.51106 + vertex 1.2338 2.11301 2.50965 + endloop + endfacet + facet normal 0.187438 0.264697 0.94594 + outer loop + vertex 1.22916 2.11282 2.51063 + vertex 1.22511 2.11439 2.511 + vertex 1.22676 2.10954 2.51202 + endloop + endfacet + facet normal 0.191436 0.27179 0.943124 + outer loop + vertex 1.22511 2.11439 2.511 + vertex 1.22337 2.11913 2.50998 + vertex 1.22107 2.11596 2.51136 + endloop + endfacet + facet normal 0.190955 0.275908 0.942025 + outer loop + vertex 1.22903 2.11713 2.50942 + vertex 1.23128 2.12169 2.50763 + vertex 1.22672 2.1214 2.50864 + endloop + endfacet + facet normal 0.191379 0.271831 0.943123 + outer loop + vertex 1.21919 2.11883 2.51092 + vertex 1.22107 2.11596 2.51136 + vertex 1.22337 2.11913 2.50998 + endloop + endfacet + facet normal 0.190342 0.271211 0.943512 + outer loop + vertex 1.22107 2.11596 2.51136 + vertex 1.21919 2.11883 2.51092 + vertex 1.21646 2.11581 2.51234 + endloop + endfacet + facet normal 0.190861 0.275291 0.942224 + outer loop + vertex 1.21613 2.12012 2.51116 + vertex 1.21426 2.12295 2.51071 + vertex 1.21195 2.11979 2.5121 + endloop + endfacet + facet normal 0.192034 0.26668 0.94446 + outer loop + vertex 1.21358 2.11286 2.51375 + vertex 1.21646 2.11581 2.51234 + vertex 1.21187 2.1158 2.51327 + endloop + endfacet + facet normal 0.189558 0.267668 0.944681 + outer loop + vertex 1.20893 2.11293 2.51468 + vertex 1.21187 2.1158 2.51327 + vertex 1.20859 2.11751 2.51344 + endloop + endfacet + facet normal 0.192351 0.262138 0.945666 + outer loop + vertex 1.20421 2.11292 2.51564 + vertex 1.20613 2.10999 2.51606 + vertex 1.20893 2.11293 2.51468 + endloop + endfacet + facet normal 0.190206 0.262102 0.94611 + outer loop + vertex 1.20421 2.11292 2.51564 + vertex 1.2002 2.11446 2.51602 + vertex 1.20192 2.10976 2.51697 + endloop + endfacet + facet normal 0.194201 0.266876 0.943961 + outer loop + vertex 1.2002 2.11446 2.51602 + vertex 1.1985 2.11911 2.51505 + vertex 1.19622 2.11598 2.51641 + endloop + endfacet + facet normal 0.194403 0.27059 0.942862 + outer loop + vertex 1.20407 2.11716 2.51446 + vertex 1.20633 2.12174 2.51268 + vertex 1.20183 2.12135 2.51372 + endloop + endfacet + facet normal 0.1964 0.265276 0.943957 + outer loop + vertex 1.19434 2.11886 2.51599 + vertex 1.19622 2.11598 2.51641 + vertex 1.1985 2.11911 2.51505 + endloop + endfacet + facet normal 0.196923 0.265588 0.943761 + outer loop + vertex 1.19622 2.11598 2.51641 + vertex 1.19434 2.11886 2.51599 + vertex 1.19153 2.11596 2.51739 + endloop + endfacet + facet normal 0.19796 0.261002 0.944823 + outer loop + vertex 1.18644 2.12066 2.51716 + vertex 1.18685 2.11611 2.51833 + vertex 1.19153 2.11596 2.51739 + endloop + endfacet + facet normal 0.201671 0.259807 0.944367 + outer loop + vertex 1.18598 2.12525 2.51599 + vertex 1.18131 2.12536 2.51696 + vertex 1.18644 2.12066 2.51716 + endloop + endfacet + facet normal 0.201283 0.261621 0.943949 + outer loop + vertex 1.18931 2.12352 2.51576 + vertex 1.19117 2.12039 2.51623 + vertex 1.19397 2.12328 2.51483 + endloop + endfacet + facet normal 0.20053 0.266286 0.942804 + outer loop + vertex 1.1986 2.12305 2.51391 + vertex 1.19691 2.12603 2.51343 + vertex 1.19397 2.12328 2.51483 + endloop + endfacet + facet normal 0.200702 0.263024 0.943683 + outer loop + vertex 1.19652 2.13058 2.51224 + vertex 1.19691 2.12603 2.51343 + vertex 1.20153 2.12592 2.51248 + endloop + endfacet + facet normal 0.204641 0.259455 0.943825 + outer loop + vertex 1.19364 2.12774 2.51365 + vertex 1.19177 2.13095 2.51318 + vertex 1.18887 2.12811 2.51459 + endloop + endfacet + facet normal 0.20326 0.25849 0.944388 + outer loop + vertex 1.18411 2.12838 2.51554 + vertex 1.18598 2.12525 2.51599 + vertex 1.18887 2.12811 2.51459 + endloop + endfacet + facet normal 0.201738 0.257661 0.944941 + outer loop + vertex 1.18598 2.12525 2.51599 + vertex 1.18411 2.12838 2.51554 + vertex 1.18131 2.12536 2.51696 + endloop + endfacet + facet normal 0.204455 0.252161 0.94584 + outer loop + vertex 1.18092 2.12987 2.51582 + vertex 1.17911 2.13277 2.51544 + vertex 1.17666 2.12949 2.51684 + endloop + endfacet + facet normal 0.207206 0.250094 0.94579 + outer loop + vertex 1.17911 2.13277 2.51544 + vertex 1.17519 2.13432 2.51589 + vertex 1.17666 2.12949 2.51684 + endloop + endfacet + facet normal 0.204754 0.243229 0.948112 + outer loop + vertex 1.17519 2.13432 2.51589 + vertex 1.17911 2.13277 2.51544 + vertex 1.17925 2.13701 2.51432 + endloop + endfacet + facet normal 0.201583 0.25596 0.945436 + outer loop + vertex 1.1785 2.12239 2.51836 + vertex 1.18131 2.12536 2.51696 + vertex 1.17662 2.12529 2.51798 + endloop + endfacet + facet normal 0.20179 0.256084 0.945358 + outer loop + vertex 1.1785 2.12239 2.51836 + vertex 1.17662 2.12529 2.51798 + vertex 1.17421 2.12203 2.51938 + endloop + endfacet + facet normal 0.202035 0.256293 0.945249 + outer loop + vertex 1.1702 2.11939 2.52095 + vertex 1.17418 2.11783 2.52052 + vertex 1.17421 2.12203 2.51938 + endloop + endfacet + facet normal 0.203895 0.255961 0.94494 + outer loop + vertex 1.16624 2.12094 2.52138 + vertex 1.16158 2.12089 2.5224 + vertex 1.16621 2.11675 2.52252 + endloop + endfacet + facet normal 0.20113 0.252918 0.94635 + outer loop + vertex 1.16158 2.12089 2.5224 + vertex 1.16194 2.11639 2.52352 + vertex 1.16621 2.11675 2.52252 + endloop + endfacet + facet normal 0.202529 0.257683 0.944765 + outer loop + vertex 1.17418 2.11783 2.52052 + vertex 1.1702 2.11939 2.52095 + vertex 1.17176 2.11456 2.52193 + endloop + endfacet + facet normal 0.199731 0.257875 0.945308 + outer loop + vertex 1.17176 2.11456 2.52193 + vertex 1.17173 2.11037 2.52308 + vertex 1.17643 2.11043 2.52207 + endloop + endfacet + facet normal 0.19999 0.254011 0.946299 + outer loop + vertex 1.17359 2.10745 2.52347 + vertex 1.17643 2.11043 2.52207 + vertex 1.17173 2.11037 2.52308 + endloop + endfacet + facet normal 0.199399 0.246313 0.948457 + outer loop + vertex 1.16924 2.1029 2.52557 + vertex 1.17393 2.10294 2.52457 + vertex 1.16931 2.10712 2.52446 + endloop + endfacet + facet normal 0.200023 0.25398 0.946301 + outer loop + vertex 1.17677 2.10596 2.5232 + vertex 1.17643 2.11043 2.52207 + vertex 1.17359 2.10745 2.52347 + endloop + endfacet + facet normal 0.198324 0.246793 0.948557 + outer loop + vertex 1.17857 2.10289 2.52362 + vertex 1.18141 2.1059 2.52224 + vertex 1.17677 2.10596 2.5232 + endloop + endfacet + facet normal 0.197053 0.240716 0.950382 + outer loop + vertex 1.17898 2.09828 2.5247 + vertex 1.1818 2.10134 2.52334 + vertex 1.17857 2.10289 2.52362 + endloop + endfacet + facet normal 0.199759 0.236604 0.95085 + outer loop + vertex 1.17105 2.09993 2.52594 + vertex 1.16679 2.09959 2.52692 + vertex 1.17129 2.0953 2.52704 + endloop + endfacet + facet normal 0.197484 0.23425 0.951907 + outer loop + vertex 1.16679 2.09959 2.52692 + vertex 1.16655 2.09549 2.52798 + vertex 1.17129 2.0953 2.52704 + endloop + endfacet + facet normal 0.196526 0.238401 0.951074 + outer loop + vertex 1.17422 2.09842 2.52565 + vertex 1.17603 2.09528 2.52607 + vertex 1.17898 2.09828 2.5247 + endloop + endfacet + facet normal 0.196772 0.242522 0.949981 + outer loop + vertex 1.17898 2.09828 2.5247 + vertex 1.18418 2.09358 2.52483 + vertex 1.18379 2.09828 2.52371 + endloop + endfacet + facet normal 0.193519 0.244198 0.95022 + outer loop + vertex 1.1812 2.0905 2.52623 + vertex 1.17937 2.09363 2.5258 + vertex 1.17644 2.09061 2.52717 + endloop + endfacet + facet normal 0.190666 0.247366 0.949977 + outer loop + vertex 1.18442 2.089 2.52597 + vertex 1.18877 2.08928 2.52503 + vertex 1.18418 2.09358 2.52483 + endloop + endfacet + facet normal 0.193335 0.251042 0.948472 + outer loop + vertex 1.1812 2.0905 2.52623 + vertex 1.17644 2.09061 2.52717 + vertex 1.18152 2.08598 2.52736 + endloop + endfacet + facet normal 0.189916 0.253772 0.948436 + outer loop + vertex 1.18442 2.089 2.52597 + vertex 1.18627 2.08603 2.5264 + vertex 1.18877 2.08928 2.52503 + endloop + endfacet + facet normal 0.184974 0.253593 0.949461 + outer loop + vertex 1.1878 2.07692 2.52855 + vertex 1.19186 2.07959 2.52704 + vertex 1.18622 2.08179 2.52755 + endloop + endfacet + facet normal 0.186721 0.25112 0.949776 + outer loop + vertex 1.19181 2.07538 2.52817 + vertex 1.19186 2.07959 2.52704 + vertex 1.1878 2.07692 2.52855 + endloop + endfacet + facet normal 0.186738 0.242585 0.951988 + outer loop + vertex 1.19363 2.07256 2.52853 + vertex 1.19643 2.07571 2.52718 + vertex 1.19181 2.07538 2.52817 + endloop + endfacet + facet normal 0.166413 0.272744 0.947585 + outer loop + vertex 1.19416 2.06385 2.53066 + vertex 1.19603 2.06098 2.53115 + vertex 1.19848 2.06427 2.52978 + endloop + endfacet + facet normal 0.187428 0.24005 0.952495 + outer loop + vertex 1.19389 2.06821 2.52957 + vertex 1.1967 2.07136 2.52823 + vertex 1.19363 2.07256 2.52853 + endloop + endfacet + facet normal 0.173381 0.249172 0.952813 + outer loop + vertex 1.20259 2.06692 2.52828 + vertex 1.20102 2.07179 2.5273 + vertex 1.19854 2.06851 2.5286 + endloop + endfacet + facet normal 0.178686 0.250601 0.951457 + outer loop + vertex 1.20259 2.06692 2.52828 + vertex 1.20668 2.06957 2.52681 + vertex 1.20102 2.07179 2.5273 + endloop + endfacet + facet normal 0.187955 0.241518 0.95202 + outer loop + vertex 1.1967 2.07136 2.52823 + vertex 1.19643 2.07571 2.52718 + vertex 1.19363 2.07256 2.52853 + endloop + endfacet + facet normal 0.185681 0.251182 0.949963 + outer loop + vertex 1.19186 2.07959 2.52704 + vertex 1.19181 2.07538 2.52817 + vertex 1.19643 2.07571 2.52718 + endloop + endfacet + facet normal 0.183452 0.257581 0.948682 + outer loop + vertex 1.19432 2.08289 2.52567 + vertex 1.19615 2.08007 2.52609 + vertex 1.19894 2.0832 2.5247 + endloop + endfacet + facet normal 0.186373 0.25749 0.948137 + outer loop + vertex 1.19186 2.07959 2.52704 + vertex 1.19031 2.08442 2.52604 + vertex 1.18622 2.08179 2.52755 + endloop + endfacet + facet normal 0.186636 0.256282 0.948413 + outer loop + vertex 1.19031 2.08442 2.52604 + vertex 1.18877 2.08928 2.52503 + vertex 1.18627 2.08603 2.5264 + endloop + endfacet + facet normal 0.191023 0.252637 0.948517 + outer loop + vertex 1.18877 2.08928 2.52503 + vertex 1.19276 2.09179 2.52355 + vertex 1.18901 2.09333 2.5239 + endloop + endfacet + facet normal 0.186197 0.252499 0.949513 + outer loop + vertex 1.19666 2.0905 2.52313 + vertex 1.19623 2.09518 2.52197 + vertex 1.19276 2.09179 2.52355 + endloop + endfacet + facet normal 0.184339 0.258739 0.948195 + outer loop + vertex 1.19861 2.08759 2.52355 + vertex 1.20131 2.09078 2.52215 + vertex 1.19666 2.0905 2.52313 + endloop + endfacet + facet normal 0.183168 0.259948 0.948091 + outer loop + vertex 1.19432 2.08289 2.52567 + vertex 1.19894 2.0832 2.5247 + vertex 1.19434 2.0871 2.52451 + endloop + endfacet + facet normal 0.181498 0.261096 0.948097 + outer loop + vertex 1.20172 2.08633 2.5233 + vertex 1.20131 2.09078 2.52215 + vertex 1.19861 2.08759 2.52355 + endloop + endfacet + facet normal 0.181749 0.261107 0.948046 + outer loop + vertex 1.20131 2.09078 2.52215 + vertex 1.20172 2.08633 2.5233 + vertex 1.20604 2.0867 2.52237 + endloop + endfacet + facet normal 0.182274 0.264241 0.947076 + outer loop + vertex 1.20601 2.09089 2.52121 + vertex 1.20604 2.0867 2.52237 + vertex 1.21007 2.08929 2.52087 + endloop + endfacet + facet normal 0.181397 0.2674 0.946357 + outer loop + vertex 1.21007 2.08929 2.52087 + vertex 1.21412 2.08774 2.52053 + vertex 1.21401 2.09205 2.51934 + endloop + endfacet + facet normal 0.181446 0.267843 0.946223 + outer loop + vertex 1.21412 2.08774 2.52053 + vertex 1.21601 2.08491 2.52097 + vertex 1.21877 2.08798 2.51957 + endloop + endfacet + facet normal 0.182231 0.269651 0.945558 + outer loop + vertex 1.21877 2.08798 2.51957 + vertex 1.22179 2.09082 2.51818 + vertex 1.21856 2.09246 2.51834 + endloop + endfacet + facet normal 0.178747 0.270709 0.945921 + outer loop + vertex 1.22662 2.08634 2.51855 + vertex 1.22639 2.09084 2.5173 + vertex 1.22336 2.08801 2.51869 + endloop + endfacet + facet normal 0.181514 0.268185 0.946113 + outer loop + vertex 1.22179 2.09082 2.51818 + vertex 1.22194 2.09475 2.51704 + vertex 1.21856 2.09246 2.51834 + endloop + endfacet + facet normal 0.181988 0.265868 0.946675 + outer loop + vertex 1.2261 2.09512 2.51613 + vertex 1.22427 2.09791 2.5157 + vertex 1.22194 2.09475 2.51704 + endloop + endfacet + facet normal 0.180688 0.265088 0.947143 + outer loop + vertex 1.22427 2.09791 2.5157 + vertex 1.2261 2.09512 2.51613 + vertex 1.22887 2.09819 2.51475 + endloop + endfacet + facet normal 0.177971 0.27192 0.94572 + outer loop + vertex 1.22917 2.0939 2.5159 + vertex 1.23108 2.09105 2.51636 + vertex 1.2335 2.0943 2.51497 + endloop + endfacet + facet normal 0.184419 0.263848 0.94677 + outer loop + vertex 1.22887 2.09819 2.51475 + vertex 1.23165 2.10129 2.51334 + vertex 1.22858 2.1025 2.5136 + endloop + endfacet + facet normal 0.183956 0.262572 0.947215 + outer loop + vertex 1.23165 2.10129 2.51334 + vertex 1.23135 2.10562 2.5122 + vertex 1.22858 2.1025 2.5136 + endloop + endfacet + facet normal 0.184513 0.262582 0.947104 + outer loop + vertex 1.23135 2.10562 2.5122 + vertex 1.23165 2.10129 2.51334 + vertex 1.23594 2.1017 2.51239 + endloop + endfacet + facet normal 0.187008 0.265442 0.945816 + outer loop + vertex 1.23592 2.10589 2.51122 + vertex 1.23135 2.10562 2.5122 + vertex 1.23594 2.1017 2.51239 + endloop + endfacet + facet normal 0.185664 0.26948 0.944939 + outer loop + vertex 1.24401 2.10275 2.51052 + vertex 1.23994 2.10432 2.51087 + vertex 1.24161 2.09949 2.51192 + endloop + endfacet + facet normal 0.18306 0.271377 0.944904 + outer loop + vertex 1.24591 2.09989 2.51097 + vertex 1.24401 2.10275 2.51052 + vertex 1.24161 2.09949 2.51192 + endloop + endfacet + facet normal 0.182114 0.277647 0.943264 + outer loop + vertex 1.24591 2.09989 2.51097 + vertex 1.24161 2.09949 2.51192 + vertex 1.24627 2.09558 2.51217 + endloop + endfacet + facet normal 0.1797 0.277578 0.943747 + outer loop + vertex 1.24591 2.09989 2.51097 + vertex 1.24627 2.09558 2.51217 + vertex 1.24899 2.09865 2.51075 + endloop + endfacet + facet normal 0.177504 0.271713 0.945867 + outer loop + vertex 1.24899 2.09865 2.51075 + vertex 1.24868 2.10295 2.50957 + vertex 1.24591 2.09989 2.51097 + endloop + endfacet + facet normal 0.176073 0.271688 0.946142 + outer loop + vertex 1.24899 2.09865 2.51075 + vertex 1.25319 2.099 2.50987 + vertex 1.24868 2.10295 2.50957 + endloop + endfacet + facet normal 0.178284 0.274121 0.945025 + outer loop + vertex 1.24868 2.10295 2.50957 + vertex 1.25319 2.099 2.50987 + vertex 1.25331 2.10295 2.5087 + endloop + endfacet + facet normal 0.175272 0.27753 0.944594 + outer loop + vertex 1.24899 2.09865 2.51075 + vertex 1.25088 2.09584 2.51122 + vertex 1.25319 2.099 2.50987 + endloop + endfacet + facet normal 0.177887 0.279128 0.943633 + outer loop + vertex 1.25088 2.09584 2.51122 + vertex 1.24899 2.09865 2.51075 + vertex 1.24627 2.09558 2.51217 + endloop + endfacet + facet normal 0.177505 0.282476 0.942708 + outer loop + vertex 1.25088 2.09584 2.51122 + vertex 1.24627 2.09558 2.51217 + vertex 1.25096 2.09171 2.51244 + endloop + endfacet + facet normal 0.174725 0.282569 0.9432 + outer loop + vertex 1.25088 2.09584 2.51122 + vertex 1.25096 2.09171 2.51244 + vertex 1.25495 2.09431 2.51093 + endloop + endfacet + facet normal 0.17402 0.283554 0.943035 + outer loop + vertex 1.25668 2.08955 2.51204 + vertex 1.25495 2.09431 2.51093 + vertex 1.25096 2.09171 2.51244 + endloop + endfacet + facet normal 0.173843 0.283049 0.943219 + outer loop + vertex 1.25263 2.08697 2.51356 + vertex 1.25668 2.08955 2.51204 + vertex 1.25096 2.09171 2.51244 + endloop + endfacet + facet normal 0.175821 0.280501 0.943613 + outer loop + vertex 1.24627 2.09558 2.51217 + vertex 1.24665 2.09129 2.51337 + vertex 1.25096 2.09171 2.51244 + endloop + endfacet + facet normal 0.179713 0.274863 0.944539 + outer loop + vertex 1.24161 2.09949 2.51192 + vertex 1.24164 2.09531 2.51313 + vertex 1.24627 2.09558 2.51217 + endloop + endfacet + facet normal 0.180006 0.26952 0.946022 + outer loop + vertex 1.24401 2.10275 2.51052 + vertex 1.24591 2.09989 2.51097 + vertex 1.24868 2.10295 2.50957 + endloop + endfacet + facet normal 0.179936 0.264289 0.947509 + outer loop + vertex 1.24847 2.10747 2.50834 + vertex 1.25188 2.10976 2.50705 + vertex 1.2462 2.11172 2.50758 + endloop + endfacet + facet normal 0.179895 0.266839 0.946802 + outer loop + vertex 1.25609 2.11009 2.50616 + vertex 1.25422 2.11293 2.50571 + vertex 1.25188 2.10976 2.50705 + endloop + endfacet + facet normal 0.181401 0.267745 0.946259 + outer loop + vertex 1.25422 2.11293 2.50571 + vertex 1.25609 2.11009 2.50616 + vertex 1.25885 2.11315 2.50476 + endloop + endfacet + facet normal 0.181172 0.267909 0.946257 + outer loop + vertex 1.25885 2.11315 2.50476 + vertex 1.26348 2.10924 2.50498 + vertex 1.26351 2.11341 2.5038 + endloop + endfacet + facet normal 0.179057 0.270954 0.945792 + outer loop + vertex 1.26348 2.10924 2.50498 + vertex 1.26508 2.10449 2.50604 + vertex 1.26904 2.1072 2.50451 + endloop + endfacet + facet normal 0.175476 0.278811 0.944178 + outer loop + vertex 1.26673 2.09995 2.50708 + vertex 1.26508 2.10449 2.50604 + vertex 1.26116 2.10168 2.5076 + endloop + endfacet + facet normal 0.179967 0.268513 0.946315 + outer loop + vertex 1.26105 2.10596 2.50638 + vertex 1.25916 2.10882 2.50592 + vertex 1.25637 2.10577 2.50732 + endloop + endfacet + facet normal 0.175153 0.271258 0.946436 + outer loop + vertex 1.25658 2.10127 2.50857 + vertex 1.25637 2.10577 2.50732 + vertex 1.25331 2.10295 2.5087 + endloop + endfacet + facet normal 0.176648 0.274251 0.945295 + outer loop + vertex 1.25319 2.099 2.50987 + vertex 1.25658 2.10127 2.50857 + vertex 1.25331 2.10295 2.5087 + endloop + endfacet + facet normal 0.17438 0.27917 0.944275 + outer loop + vertex 1.26343 2.09752 2.50841 + vertex 1.26116 2.10168 2.5076 + vertex 1.25888 2.09706 2.50939 + endloop + endfacet + facet normal 0.173426 0.278859 0.944543 + outer loop + vertex 1.25495 2.09431 2.51093 + vertex 1.25319 2.099 2.50987 + vertex 1.25088 2.09584 2.51122 + endloop + endfacet + facet normal 0.173426 0.283376 0.943197 + outer loop + vertex 1.25907 2.09278 2.51063 + vertex 1.25495 2.09431 2.51093 + vertex 1.25668 2.08955 2.51204 + endloop + endfacet + facet normal 0.173587 0.284177 0.942927 + outer loop + vertex 1.25888 2.09706 2.50939 + vertex 1.26376 2.09308 2.50969 + vertex 1.26343 2.09752 2.50841 + endloop + endfacet + facet normal 0.168506 0.284126 0.943863 + outer loop + vertex 1.26414 2.0888 2.51091 + vertex 1.26845 2.08928 2.50999 + vertex 1.26376 2.09308 2.50969 + endloop + endfacet + facet normal 0.170181 0.282395 0.944082 + outer loop + vertex 1.26606 2.08602 2.51139 + vertex 1.26414 2.0888 2.51091 + vertex 1.26137 2.08569 2.51234 + endloop + endfacet + facet normal 0.172403 0.284117 0.943162 + outer loop + vertex 1.26101 2.08997 2.51112 + vertex 1.25907 2.09278 2.51063 + vertex 1.25668 2.08955 2.51204 + endloop + endfacet + facet normal 0.173474 0.283575 0.943129 + outer loop + vertex 1.25668 2.08546 2.51327 + vertex 1.25668 2.08955 2.51204 + vertex 1.25263 2.08697 2.51356 + endloop + endfacet + facet normal 0.171936 0.276487 0.945512 + outer loop + vertex 1.26137 2.08569 2.51234 + vertex 1.26165 2.08123 2.51359 + vertex 1.26619 2.08175 2.51261 + endloop + endfacet + facet normal 0.166951 0.264299 0.949881 + outer loop + vertex 1.26843 2.07762 2.51337 + vertex 1.27178 2.08006 2.5121 + vertex 1.26619 2.08175 2.51261 + endloop + endfacet + facet normal 0.166118 0.253243 0.953034 + outer loop + vertex 1.26394 2.07286 2.51544 + vertex 1.26865 2.07316 2.51454 + vertex 1.26388 2.07712 2.51432 + endloop + endfacet + facet normal 0.173074 0.253033 0.951851 + outer loop + vertex 1.25994 2.0743 2.51579 + vertex 1.26394 2.07286 2.51544 + vertex 1.26388 2.07712 2.51432 + endloop + endfacet + facet normal 0.174191 0.256397 0.950746 + outer loop + vertex 1.26394 2.07286 2.51544 + vertex 1.25994 2.0743 2.51579 + vertex 1.26148 2.06954 2.51679 + endloop + endfacet + facet normal 0.1685 0.260567 0.950638 + outer loop + vertex 1.26581 2.07003 2.51589 + vertex 1.26394 2.07286 2.51544 + vertex 1.26148 2.06954 2.51679 + endloop + endfacet + facet normal 0.1655 0.258744 0.951662 + outer loop + vertex 1.26394 2.07286 2.51544 + vertex 1.26581 2.07003 2.51589 + vertex 1.26865 2.07316 2.51454 + endloop + endfacet + facet normal 0.168861 0.261844 0.950223 + outer loop + vertex 1.27164 2.07613 2.51321 + vertex 1.27178 2.08006 2.5121 + vertex 1.26843 2.07762 2.51337 + endloop + endfacet + facet normal 0.164747 0.260578 0.951293 + outer loop + vertex 1.2734 2.0734 2.51365 + vertex 1.27598 2.07655 2.51234 + vertex 1.27164 2.07613 2.51321 + endloop + endfacet + facet normal 0.151681 0.293866 0.943735 + outer loop + vertex 1.26892 2.06884 2.5157 + vertex 1.27085 2.066 2.51628 + vertex 1.2733 2.06929 2.51486 + endloop + endfacet + facet normal 0.165367 0.280981 0.945359 + outer loop + vertex 1.26143 2.06527 2.51807 + vertex 1.26148 2.06954 2.51679 + vertex 1.25734 2.06685 2.51831 + endloop + endfacet + facet normal 0.172909 0.270359 0.947105 + outer loop + vertex 1.25734 2.06685 2.51831 + vertex 1.26148 2.06954 2.51679 + vertex 1.25594 2.0716 2.51721 + endloop + endfacet + facet normal 0.154591 0.295631 0.942711 + outer loop + vertex 1.27085 2.066 2.51628 + vertex 1.26892 2.06884 2.5157 + vertex 1.26617 2.06561 2.51717 + endloop + endfacet + facet normal 0.146153 0.297823 0.943367 + outer loop + vertex 1.27498 2.06449 2.51612 + vertex 1.2733 2.06929 2.51486 + vertex 1.27085 2.066 2.51628 + endloop + endfacet + facet normal 0.164393 0.274258 0.947501 + outer loop + vertex 1.2733 2.06929 2.51486 + vertex 1.27747 2.07189 2.51338 + vertex 1.2734 2.0734 2.51365 + endloop + endfacet + facet normal 0.161932 0.266224 0.950212 + outer loop + vertex 1.28158 2.07039 2.5131 + vertex 1.28161 2.07453 2.51194 + vertex 1.27747 2.07189 2.51338 + endloop + endfacet + facet normal 0.160387 0.277231 0.947322 + outer loop + vertex 1.28343 2.06759 2.51361 + vertex 1.28632 2.0707 2.51221 + vertex 1.28158 2.07039 2.5131 + endloop + endfacet + facet normal 0.177791 0.311631 0.933422 + outer loop + vertex 1.27906 2.06298 2.51593 + vertex 1.28368 2.06328 2.51495 + vertex 1.27903 2.06716 2.51454 + endloop + endfacet + facet normal 0.165004 0.273122 0.947723 + outer loop + vertex 1.28656 2.06639 2.51341 + vertex 1.28632 2.0707 2.51221 + vertex 1.28343 2.06759 2.51361 + endloop + endfacet + facet normal 0.166707 0.273133 0.947421 + outer loop + vertex 1.28632 2.0707 2.51221 + vertex 1.28656 2.06639 2.51341 + vertex 1.29095 2.06689 2.51249 + endloop + endfacet + facet normal 0.166197 0.280532 0.945347 + outer loop + vertex 1.29239 2.0621 2.51366 + vertex 1.29659 2.06498 2.51207 + vertex 1.29095 2.06689 2.51249 + endloop + endfacet + facet normal 0.166347 0.280331 0.94538 + outer loop + vertex 1.29639 2.06074 2.51336 + vertex 1.29659 2.06498 2.51207 + vertex 1.29239 2.0621 2.51366 + endloop + endfacet + facet normal 0.154051 0.281455 0.947128 + outer loop + vertex 1.29659 2.06498 2.51207 + vertex 1.29639 2.06074 2.51336 + vertex 1.30088 2.06149 2.51241 + endloop + endfacet + facet normal 0.157761 0.262836 0.951855 + outer loop + vertex 1.29911 2.06834 2.51072 + vertex 1.30102 2.06568 2.51114 + vertex 1.30334 2.06894 2.50985 + endloop + endfacet + facet normal 0.160791 0.263267 0.951229 + outer loop + vertex 1.29659 2.06498 2.51207 + vertex 1.29512 2.06964 2.51103 + vertex 1.29095 2.06689 2.51249 + endloop + endfacet + facet normal 0.160492 0.26505 0.950784 + outer loop + vertex 1.29512 2.06964 2.51103 + vertex 1.29349 2.07431 2.51 + vertex 1.29106 2.07105 2.51132 + endloop + endfacet + facet normal 0.16381 0.274546 0.947518 + outer loop + vertex 1.29349 2.07431 2.51 + vertex 1.29754 2.07693 2.50854 + vertex 1.29347 2.07839 2.50882 + endloop + endfacet + facet normal 0.165098 0.283688 0.944597 + outer loop + vertex 1.30159 2.07548 2.50827 + vertex 1.30155 2.07954 2.50706 + vertex 1.29754 2.07693 2.50854 + endloop + endfacet + facet normal 0.164228 0.279613 0.945963 + outer loop + vertex 1.30342 2.07278 2.50875 + vertex 1.30628 2.07572 2.50738 + vertex 1.30159 2.07548 2.50827 + endloop + endfacet + facet normal 0.157434 0.264541 0.951437 + outer loop + vertex 1.29911 2.06834 2.51072 + vertex 1.30334 2.06894 2.50985 + vertex 1.29913 2.07235 2.5096 + endloop + endfacet + facet normal 0.164361 0.27949 0.945976 + outer loop + vertex 1.30663 2.07133 2.50862 + vertex 1.30628 2.07572 2.50738 + vertex 1.30342 2.07278 2.50875 + endloop + endfacet + facet normal 0.158764 0.273184 0.94877 + outer loop + vertex 1.30878 2.06737 2.5094 + vertex 1.31116 2.07182 2.50772 + vertex 1.30663 2.07133 2.50862 + endloop + endfacet + facet normal 0.150143 0.268156 0.951604 + outer loop + vertex 1.30492 2.06447 2.51086 + vertex 1.30334 2.06894 2.50985 + vertex 1.30102 2.06568 2.51114 + endloop + endfacet + facet normal 0.154909 0.299935 0.941298 + outer loop + vertex 1.30882 2.06325 2.51061 + vertex 1.30492 2.06447 2.51086 + vertex 1.30649 2.05979 2.5121 + endloop + endfacet + facet normal 0.147077 0.305052 0.94091 + outer loop + vertex 1.3108 2.06055 2.51117 + vertex 1.30882 2.06325 2.51061 + vertex 1.30649 2.05979 2.5121 + endloop + endfacet + facet normal 0.146726 0.306527 0.940485 + outer loop + vertex 1.3108 2.06055 2.51117 + vertex 1.30649 2.05979 2.5121 + vertex 1.31096 2.05634 2.51252 + endloop + endfacet + facet normal 0.140588 0.306591 0.941402 + outer loop + vertex 1.3108 2.06055 2.51117 + vertex 1.31096 2.05634 2.51252 + vertex 1.31473 2.05935 2.51098 + endloop + endfacet + facet normal 0.151806 0.293773 0.943744 + outer loop + vertex 1.31657 2.0547 2.51213 + vertex 1.31473 2.05935 2.51098 + vertex 1.31096 2.05634 2.51252 + endloop + endfacet + facet normal 0.126828 0.201775 0.971186 + outer loop + vertex 1.31278 2.05172 2.51324 + vertex 1.31657 2.0547 2.51213 + vertex 1.31096 2.05634 2.51252 + endloop + endfacet + facet normal 0.150754 0.311466 0.938223 + outer loop + vertex 1.30649 2.05979 2.5121 + vertex 1.30657 2.05548 2.51351 + vertex 1.31096 2.05634 2.51252 + endloop + endfacet + facet normal 0.143732 0.30285 0.942138 + outer loop + vertex 1.30882 2.06325 2.51061 + vertex 1.3108 2.06055 2.51117 + vertex 1.31308 2.06384 2.50977 + endloop + endfacet + facet normal 0.149045 0.277695 0.949037 + outer loop + vertex 1.31657 2.06616 2.50851 + vertex 1.31682 2.07015 2.5073 + vertex 1.3133 2.06783 2.50854 + endloop + endfacet + facet normal 0.140189 0.305203 0.941912 + outer loop + vertex 1.31473 2.05935 2.51098 + vertex 1.31308 2.06384 2.50977 + vertex 1.3108 2.06055 2.51117 + endloop + endfacet + facet normal 0.145773 0.291778 0.945312 + outer loop + vertex 1.31863 2.05818 2.51074 + vertex 1.31473 2.05935 2.51098 + vertex 1.31657 2.0547 2.51213 + endloop + endfacet + facet normal 0.145553 0.291907 0.945307 + outer loop + vertex 1.32072 2.05548 2.51125 + vertex 1.31863 2.05818 2.51074 + vertex 1.31657 2.0547 2.51213 + endloop + endfacet + facet normal 0.145063 0.290223 0.9459 + outer loop + vertex 1.31857 2.06235 2.50937 + vertex 1.32109 2.06689 2.50759 + vertex 1.31657 2.06616 2.50851 + endloop + endfacet + facet normal 0.14732 0.27343 0.950543 + outer loop + vertex 1.3263 2.06584 2.50709 + vertex 1.32503 2.06993 2.50611 + vertex 1.32109 2.06689 2.50759 + endloop + endfacet + facet normal 0.14524 0.26807 0.952388 + outer loop + vertex 1.33145 2.06438 2.50671 + vertex 1.32978 2.06882 2.50572 + vertex 1.3263 2.06584 2.50709 + endloop + endfacet + facet normal 0.140781 0.264183 0.954143 + outer loop + vertex 1.33576 2.06502 2.5059 + vertex 1.33384 2.0677 2.50544 + vertex 1.33145 2.06438 2.50671 + endloop + endfacet + facet normal 0.143818 0.266197 0.953129 + outer loop + vertex 1.33384 2.0677 2.50544 + vertex 1.33576 2.06502 2.5059 + vertex 1.33856 2.06809 2.50462 + endloop + endfacet + facet normal 0.139003 0.269173 0.953008 + outer loop + vertex 1.33892 2.06387 2.50574 + vertex 1.34087 2.06105 2.50626 + vertex 1.34334 2.06429 2.50498 + endloop + endfacet + facet normal 0.139782 0.281271 0.949393 + outer loop + vertex 1.33856 2.06809 2.50462 + vertex 1.3415 2.07106 2.50331 + vertex 1.33821 2.07247 2.50337 + endloop + endfacet + facet normal 0.14335 0.292823 0.94536 + outer loop + vertex 1.34155 2.07492 2.5021 + vertex 1.3415 2.07106 2.50331 + vertex 1.3459 2.07152 2.5025 + endloop + endfacet + facet normal 0.137374 0.292415 0.946373 + outer loop + vertex 1.34588 2.07555 2.50126 + vertex 1.3459 2.07152 2.5025 + vertex 1.34993 2.07435 2.50104 + endloop + endfacet + facet normal 0.13882 0.297634 0.944533 + outer loop + vertex 1.34993 2.07435 2.50104 + vertex 1.34826 2.0789 2.49985 + vertex 1.34588 2.07555 2.50126 + endloop + endfacet + facet normal 0.13746 0.299091 0.944272 + outer loop + vertex 1.34826 2.0789 2.49985 + vertex 1.35237 2.08169 2.49837 + vertex 1.34831 2.08308 2.49852 + endloop + endfacet + facet normal 0.132395 0.301586 0.944202 + outer loop + vertex 1.35631 2.0806 2.49816 + vertex 1.35631 2.08452 2.49691 + vertex 1.35237 2.08169 2.49837 + endloop + endfacet + facet normal 0.123115 0.304292 0.944589 + outer loop + vertex 1.35832 2.07809 2.49871 + vertex 1.36069 2.08137 2.49735 + vertex 1.35631 2.0806 2.49816 + endloop + endfacet + facet normal 0.113865 0.297271 0.947979 + outer loop + vertex 1.36004 2.06982 2.50113 + vertex 1.35833 2.07415 2.49998 + vertex 1.35602 2.07072 2.50133 + endloop + endfacet + facet normal 0.115344 0.305032 0.945331 + outer loop + vertex 1.35833 2.07415 2.49998 + vertex 1.36229 2.07699 2.49858 + vertex 1.35832 2.07809 2.49871 + endloop + endfacet + facet normal 0.105918 0.314207 0.943428 + outer loop + vertex 1.36641 2.07564 2.49857 + vertex 1.36639 2.07975 2.4972 + vertex 1.36229 2.07699 2.49858 + endloop + endfacet + facet normal 0.0901391 0.314643 0.944921 + outer loop + vertex 1.36639 2.07975 2.4972 + vertex 1.36641 2.07564 2.49857 + vertex 1.37098 2.07666 2.49779 + endloop + endfacet + facet normal 0.0661173 0.315471 0.946629 + outer loop + vertex 1.3733 2.07316 2.4988 + vertex 1.37619 2.07612 2.49761 + vertex 1.37098 2.07666 2.49779 + endloop + endfacet + facet normal 0.0681829 0.308326 0.948834 + outer loop + vertex 1.36889 2.06801 2.50084 + vertex 1.37322 2.06917 2.50015 + vertex 1.36877 2.07201 2.49955 + endloop + endfacet + facet normal 0.0559538 0.324456 0.944244 + outer loop + vertex 1.37734 2.07235 2.49883 + vertex 1.37619 2.07612 2.49761 + vertex 1.3733 2.07316 2.4988 + endloop + endfacet + facet normal 0.0442759 0.321117 0.946004 + outer loop + vertex 1.38338 2.06813 2.49999 + vertex 1.38214 2.07198 2.49874 + vertex 1.37842 2.06847 2.5001 + endloop + endfacet + facet normal 0.0457341 0.321804 0.945701 + outer loop + vertex 1.37734 2.07235 2.49883 + vertex 1.38096 2.07576 2.4975 + vertex 1.37619 2.07612 2.49761 + endloop + endfacet + facet normal 0.0491143 0.318517 0.946644 + outer loop + vertex 1.38712 2.07172 2.49857 + vertex 1.38586 2.07558 2.49734 + vertex 1.38214 2.07198 2.49874 + endloop + endfacet + facet normal 0.0405744 0.32509 0.944812 + outer loop + vertex 1.38465 2.07936 2.4961 + vertex 1.37976 2.07952 2.49626 + vertex 1.38096 2.07576 2.4975 + endloop + endfacet + facet normal 0.0510417 0.326093 0.943959 + outer loop + vertex 1.37491 2.07993 2.49638 + vertex 1.37976 2.07952 2.49626 + vertex 1.3785 2.08337 2.495 + endloop + endfacet + facet normal 0.0428147 0.328047 0.943691 + outer loop + vertex 1.38347 2.0831 2.49486 + vertex 1.38722 2.08666 2.49345 + vertex 1.38229 2.08688 2.4936 + endloop + endfacet + facet normal 0.0429098 0.330908 0.942687 + outer loop + vertex 1.38722 2.08666 2.49345 + vertex 1.38599 2.09043 2.49219 + vertex 1.38229 2.08688 2.4936 + endloop + endfacet + facet normal 0.0497507 0.332808 0.941681 + outer loop + vertex 1.38722 2.08666 2.49345 + vertex 1.39095 2.09012 2.49203 + vertex 1.38599 2.09043 2.49219 + endloop + endfacet + facet normal 0.0497686 0.333154 0.941558 + outer loop + vertex 1.39095 2.09012 2.49203 + vertex 1.38949 2.09396 2.49075 + vertex 1.38599 2.09043 2.49219 + endloop + endfacet + facet normal 0.048713 0.334089 0.941282 + outer loop + vertex 1.38949 2.09396 2.49075 + vertex 1.38459 2.09422 2.49091 + vertex 1.38599 2.09043 2.49219 + endloop + endfacet + facet normal 0.0492179 0.334248 0.941199 + outer loop + vertex 1.38599 2.09043 2.49219 + vertex 1.38459 2.09422 2.49091 + vertex 1.38101 2.09077 2.49233 + endloop + endfacet + facet normal 0.0489616 0.340155 0.939094 + outer loop + vertex 1.38459 2.09422 2.49091 + vertex 1.38949 2.09396 2.49075 + vertex 1.38779 2.09769 2.48949 + endloop + endfacet + facet normal 0.0555667 0.33471 0.940682 + outer loop + vertex 1.38309 2.09793 2.48968 + vertex 1.38459 2.09422 2.49091 + vertex 1.38779 2.09769 2.48949 + endloop + endfacet + facet normal 0.0559334 0.344642 0.937066 + outer loop + vertex 1.38779 2.09769 2.48949 + vertex 1.38596 2.10068 2.4885 + vertex 1.38309 2.09793 2.48968 + endloop + endfacet + facet normal 0.0514901 0.342293 0.938182 + outer loop + vertex 1.38779 2.09769 2.48949 + vertex 1.39056 2.10176 2.48785 + vertex 1.38596 2.10068 2.4885 + endloop + endfacet + facet normal 0.0519558 0.340652 0.938753 + outer loop + vertex 1.38615 2.10447 2.48711 + vertex 1.38596 2.10068 2.4885 + vertex 1.39056 2.10176 2.48785 + endloop + endfacet + facet normal 0.0519563 0.342008 0.93826 + outer loop + vertex 1.39283 2.09753 2.48927 + vertex 1.39056 2.10176 2.48785 + vertex 1.38779 2.09769 2.48949 + endloop + endfacet + facet normal 0.0604018 0.336368 0.939791 + outer loop + vertex 1.37975 2.09471 2.49105 + vertex 1.38459 2.09422 2.49091 + vertex 1.38309 2.09793 2.48968 + endloop + endfacet + facet normal 0.0593644 0.324829 0.943908 + outer loop + vertex 1.38459 2.09422 2.49091 + vertex 1.37975 2.09471 2.49105 + vertex 1.38101 2.09077 2.49233 + endloop + endfacet + facet normal 0.0519458 0.341318 0.938511 + outer loop + vertex 1.38779 2.09769 2.48949 + vertex 1.38949 2.09396 2.49075 + vertex 1.39283 2.09753 2.48927 + endloop + endfacet + facet normal 0.0580175 0.336259 0.939981 + outer loop + vertex 1.38949 2.09396 2.49075 + vertex 1.39443 2.09354 2.4906 + vertex 1.39283 2.09753 2.48927 + endloop + endfacet + facet normal 0.0579838 0.33581 0.940143 + outer loop + vertex 1.39443 2.09354 2.4906 + vertex 1.38949 2.09396 2.49075 + vertex 1.39095 2.09012 2.49203 + endloop + endfacet + facet normal 0.055063 0.327692 0.943179 + outer loop + vertex 1.39205 2.08629 2.4933 + vertex 1.39095 2.09012 2.49203 + vertex 1.38722 2.08666 2.49345 + endloop + endfacet + facet normal 0.0551721 0.329361 0.942591 + outer loop + vertex 1.38837 2.08293 2.49469 + vertex 1.39205 2.08629 2.4933 + vertex 1.38722 2.08666 2.49345 + endloop + endfacet + facet normal 0.0647744 0.319938 0.945221 + outer loop + vertex 1.3932 2.08253 2.49449 + vertex 1.39205 2.08629 2.4933 + vertex 1.38837 2.08293 2.49469 + endloop + endfacet + facet normal 0.0651043 0.324753 0.943555 + outer loop + vertex 1.38837 2.08293 2.49469 + vertex 1.38957 2.07915 2.49591 + vertex 1.3932 2.08253 2.49449 + endloop + endfacet + facet normal 0.0749044 0.315275 0.94604 + outer loop + vertex 1.38957 2.07915 2.49591 + vertex 1.39449 2.07867 2.49568 + vertex 1.3932 2.08253 2.49449 + endloop + endfacet + facet normal 0.091862 0.320016 0.942948 + outer loop + vertex 1.3932 2.08253 2.49449 + vertex 1.39449 2.07867 2.49568 + vertex 1.39846 2.08195 2.49418 + endloop + endfacet + facet normal 0.0911946 0.312593 0.945499 + outer loop + vertex 1.39846 2.08195 2.49418 + vertex 1.39616 2.08545 2.49324 + vertex 1.3932 2.08253 2.49449 + endloop + endfacet + facet normal 0.0997072 0.317514 0.942997 + outer loop + vertex 1.39846 2.08195 2.49418 + vertex 1.40075 2.08656 2.49239 + vertex 1.39616 2.08545 2.49324 + endloop + endfacet + facet normal 0.0985068 0.321545 0.941757 + outer loop + vertex 1.39623 2.08943 2.49188 + vertex 1.39616 2.08545 2.49324 + vertex 1.40075 2.08656 2.49239 + endloop + endfacet + facet normal 0.0941363 0.315137 0.944366 + outer loop + vertex 1.40057 2.0905 2.49109 + vertex 1.39623 2.08943 2.49188 + vertex 1.40075 2.08656 2.49239 + endloop + endfacet + facet normal 0.106103 0.315232 0.943065 + outer loop + vertex 1.40057 2.0905 2.49109 + vertex 1.40075 2.08656 2.49239 + vertex 1.40458 2.08965 2.49092 + endloop + endfacet + facet normal 0.106499 0.317235 0.942348 + outer loop + vertex 1.40458 2.08965 2.49092 + vertex 1.40274 2.09378 2.48974 + vertex 1.40057 2.0905 2.49109 + endloop + endfacet + facet normal 0.104383 0.316435 0.942854 + outer loop + vertex 1.40274 2.09378 2.48974 + vertex 1.40458 2.08965 2.49092 + vertex 1.40788 2.09281 2.4895 + endloop + endfacet + facet normal 0.104323 0.316086 0.942977 + outer loop + vertex 1.40788 2.09281 2.4895 + vertex 1.4062 2.09615 2.48856 + vertex 1.40274 2.09378 2.48974 + endloop + endfacet + facet normal 0.103705 0.31582 0.943135 + outer loop + vertex 1.40788 2.09281 2.4895 + vertex 1.41088 2.09679 2.48783 + vertex 1.4062 2.09615 2.48856 + endloop + endfacet + facet normal 0.102845 0.320423 0.941675 + outer loop + vertex 1.40653 2.09989 2.48725 + vertex 1.4062 2.09615 2.48856 + vertex 1.41088 2.09679 2.48783 + endloop + endfacet + facet normal 0.102357 0.319787 0.941944 + outer loop + vertex 1.41086 2.10082 2.48646 + vertex 1.40653 2.09989 2.48725 + vertex 1.41088 2.09679 2.48783 + endloop + endfacet + facet normal 0.0997701 0.319859 0.942197 + outer loop + vertex 1.41086 2.10082 2.48646 + vertex 1.41088 2.09679 2.48783 + vertex 1.41487 2.10004 2.4863 + endloop + endfacet + facet normal 0.0991224 0.320573 0.942023 + outer loop + vertex 1.41636 2.09605 2.48751 + vertex 1.41487 2.10004 2.4863 + vertex 1.41088 2.09679 2.48783 + endloop + endfacet + facet normal 0.0986504 0.316461 0.943462 + outer loop + vertex 1.41345 2.09195 2.48919 + vertex 1.41636 2.09605 2.48751 + vertex 1.41088 2.09679 2.48783 + endloop + endfacet + facet normal 0.0958476 0.31831 0.943129 + outer loop + vertex 1.41817 2.0928 2.48842 + vertex 1.41636 2.09605 2.48751 + vertex 1.41345 2.09195 2.48919 + endloop + endfacet + facet normal 0.0957721 0.318635 0.943027 + outer loop + vertex 1.41345 2.09195 2.48919 + vertex 1.41793 2.08887 2.48977 + vertex 1.41817 2.0928 2.48842 + endloop + endfacet + facet normal 0.0942013 0.31877 0.943139 + outer loop + vertex 1.41793 2.08887 2.48977 + vertex 1.42208 2.09168 2.48841 + vertex 1.41817 2.0928 2.48842 + endloop + endfacet + facet normal 0.0942885 0.319074 0.943028 + outer loop + vertex 1.42208 2.09168 2.48841 + vertex 1.42113 2.09551 2.48721 + vertex 1.41817 2.0928 2.48842 + endloop + endfacet + facet normal 0.0944464 0.319105 0.943001 + outer loop + vertex 1.42208 2.09168 2.48841 + vertex 1.42619 2.09453 2.48703 + vertex 1.42113 2.09551 2.48721 + endloop + endfacet + facet normal 0.0936905 0.320072 0.942749 + outer loop + vertex 1.42609 2.09054 2.4884 + vertex 1.42619 2.09453 2.48703 + vertex 1.42208 2.09168 2.48841 + endloop + endfacet + facet normal 0.0935947 0.319734 0.942874 + outer loop + vertex 1.42312 2.08777 2.48963 + vertex 1.42609 2.09054 2.4884 + vertex 1.42208 2.09168 2.48841 + endloop + endfacet + facet normal 0.0934506 0.319874 0.94284 + outer loop + vertex 1.42845 2.087 2.48936 + vertex 1.42609 2.09054 2.4884 + vertex 1.42312 2.08777 2.48963 + endloop + endfacet + facet normal 0.0933741 0.31927 0.943052 + outer loop + vertex 1.42312 2.08777 2.48963 + vertex 1.42453 2.08381 2.49083 + vertex 1.42845 2.087 2.48936 + endloop + endfacet + facet normal 0.0934154 0.319225 0.943064 + outer loop + vertex 1.42453 2.08381 2.49083 + vertex 1.4286 2.08303 2.49069 + vertex 1.42845 2.087 2.48936 + endloop + endfacet + facet normal 0.0934521 0.319225 0.94306 + outer loop + vertex 1.4286 2.08303 2.49069 + vertex 1.433 2.08406 2.48991 + vertex 1.42845 2.087 2.48936 + endloop + endfacet + facet normal 0.0935959 0.319432 0.942975 + outer loop + vertex 1.42845 2.087 2.48936 + vertex 1.433 2.08406 2.48991 + vertex 1.43308 2.08809 2.48853 + endloop + endfacet + facet normal 0.0933946 0.320126 0.94276 + outer loop + vertex 1.43308 2.08809 2.48853 + vertex 1.43072 2.09164 2.48756 + vertex 1.42845 2.087 2.48936 + endloop + endfacet + facet normal 0.0941558 0.320571 0.942533 + outer loop + vertex 1.43308 2.08809 2.48853 + vertex 1.43608 2.09083 2.4873 + vertex 1.43072 2.09164 2.48756 + endloop + endfacet + facet normal 0.0941939 0.320858 0.942432 + outer loop + vertex 1.43608 2.09083 2.4873 + vertex 1.43464 2.09481 2.48609 + vertex 1.43072 2.09164 2.48756 + endloop + endfacet + facet normal 0.0942226 0.320826 0.94244 + outer loop + vertex 1.43056 2.0956 2.48623 + vertex 1.43072 2.09164 2.48756 + vertex 1.43464 2.09481 2.48609 + endloop + endfacet + facet normal 0.0947538 0.323734 0.941392 + outer loop + vertex 1.43464 2.09481 2.48609 + vertex 1.43289 2.09899 2.48483 + vertex 1.43056 2.0956 2.48623 + endloop + endfacet + facet normal 0.0955788 0.323207 0.941489 + outer loop + vertex 1.42847 2.09798 2.48563 + vertex 1.43056 2.0956 2.48623 + vertex 1.43289 2.09899 2.48483 + endloop + endfacet + facet normal 0.0946127 0.326581 0.940422 + outer loop + vertex 1.42847 2.09798 2.48563 + vertex 1.43289 2.09899 2.48483 + vertex 1.42841 2.10198 2.48424 + endloop + endfacet + facet normal 0.0955672 0.326566 0.940331 + outer loop + vertex 1.42445 2.09867 2.4858 + vertex 1.42847 2.09798 2.48563 + vertex 1.42841 2.10198 2.48424 + endloop + endfacet + facet normal 0.0966272 0.325435 0.940614 + outer loop + vertex 1.42295 2.1026 2.48459 + vertex 1.42445 2.09867 2.4858 + vertex 1.42841 2.10198 2.48424 + endloop + endfacet + facet normal 0.0971887 0.331655 0.938381 + outer loop + vertex 1.42841 2.10198 2.48424 + vertex 1.42583 2.10666 2.48286 + vertex 1.42295 2.1026 2.48459 + endloop + endfacet + facet normal 0.0965876 0.331372 0.938543 + outer loop + vertex 1.42841 2.10198 2.48424 + vertex 1.43129 2.10604 2.48251 + vertex 1.42583 2.10666 2.48286 + endloop + endfacet + facet normal 0.0949511 0.332444 0.938331 + outer loop + vertex 1.43312 2.10286 2.48346 + vertex 1.43129 2.10604 2.48251 + vertex 1.42841 2.10198 2.48424 + endloop + endfacet + facet normal 0.0951741 0.332554 0.93827 + outer loop + vertex 1.43312 2.10286 2.48346 + vertex 1.43609 2.10551 2.48222 + vertex 1.43129 2.10604 2.48251 + endloop + endfacet + facet normal 0.0952036 0.332887 0.938148 + outer loop + vertex 1.43609 2.10551 2.48222 + vertex 1.43462 2.10927 2.48103 + vertex 1.43129 2.10604 2.48251 + endloop + endfacet + facet normal 0.0953202 0.332779 0.938175 + outer loop + vertex 1.43462 2.10927 2.48103 + vertex 1.42982 2.10994 2.48128 + vertex 1.43129 2.10604 2.48251 + endloop + endfacet + facet normal 0.0949643 0.329805 0.93926 + outer loop + vertex 1.42982 2.10994 2.48128 + vertex 1.43462 2.10927 2.48103 + vertex 1.43321 2.11305 2.47984 + endloop + endfacet + facet normal 0.0924349 0.329023 0.939787 + outer loop + vertex 1.43321 2.11305 2.47984 + vertex 1.43462 2.10927 2.48103 + vertex 1.43797 2.11254 2.47955 + endloop + endfacet + facet normal 0.0927364 0.332093 0.938677 + outer loop + vertex 1.43946 2.10862 2.48078 + vertex 1.43462 2.10927 2.48103 + vertex 1.43609 2.10551 2.48222 + endloop + endfacet + facet normal 0.0959869 0.331737 0.938476 + outer loop + vertex 1.43706 2.10172 2.48346 + vertex 1.43609 2.10551 2.48222 + vertex 1.43312 2.10286 2.48346 + endloop + endfacet + facet normal 0.0950401 0.328469 0.939721 + outer loop + vertex 1.43289 2.09899 2.48483 + vertex 1.43706 2.10172 2.48346 + vertex 1.43312 2.10286 2.48346 + endloop + endfacet + facet normal 0.0958519 0.33171 0.938499 + outer loop + vertex 1.43706 2.10172 2.48346 + vertex 1.44119 2.10449 2.48205 + vertex 1.43609 2.10551 2.48222 + endloop + endfacet + facet normal 0.0978989 0.329031 0.939231 + outer loop + vertex 1.4411 2.10054 2.48345 + vertex 1.44119 2.10449 2.48205 + vertex 1.43706 2.10172 2.48346 + endloop + endfacet + facet normal 0.096109 0.32527 0.940724 + outer loop + vertex 1.41967 2.09933 2.48605 + vertex 1.42445 2.09867 2.4858 + vertex 1.42295 2.1026 2.48459 + endloop + endfacet + facet normal 0.0967447 0.324692 0.940859 + outer loop + vertex 1.4182 2.10315 2.48489 + vertex 1.41967 2.09933 2.48605 + vertex 1.42295 2.1026 2.48459 + endloop + endfacet + facet normal 0.0971909 0.324834 0.940764 + outer loop + vertex 1.41487 2.10004 2.4863 + vertex 1.41967 2.09933 2.48605 + vertex 1.4182 2.10315 2.48489 + endloop + endfacet + facet normal 0.0955598 0.320668 0.942359 + outer loop + vertex 1.42445 2.09867 2.4858 + vertex 1.41967 2.09933 2.48605 + vertex 1.42113 2.09551 2.48721 + endloop + endfacet + facet normal 0.094853 0.321341 0.942201 + outer loop + vertex 1.42619 2.09453 2.48703 + vertex 1.42445 2.09867 2.4858 + vertex 1.42113 2.09551 2.48721 + endloop + endfacet + facet normal 0.0955577 0.320668 0.942359 + outer loop + vertex 1.42113 2.09551 2.48721 + vertex 1.41967 2.09933 2.48605 + vertex 1.41636 2.09605 2.48751 + endloop + endfacet + facet normal 0.0947375 0.3213 0.942227 + outer loop + vertex 1.42847 2.09798 2.48563 + vertex 1.42445 2.09867 2.4858 + vertex 1.42619 2.09453 2.48703 + endloop + endfacet + facet normal 0.0959257 0.328394 0.939657 + outer loop + vertex 1.42841 2.10198 2.48424 + vertex 1.43289 2.09899 2.48483 + vertex 1.43312 2.10286 2.48346 + endloop + endfacet + facet normal 0.0938507 0.321847 0.942129 + outer loop + vertex 1.43056 2.0956 2.48623 + vertex 1.42847 2.09798 2.48563 + vertex 1.42619 2.09453 2.48703 + endloop + endfacet + facet normal 0.0954334 0.323973 0.941241 + outer loop + vertex 1.43289 2.09899 2.48483 + vertex 1.43464 2.09481 2.48609 + vertex 1.43811 2.09784 2.4847 + endloop + endfacet + facet normal 0.0961159 0.323271 0.941412 + outer loop + vertex 1.43464 2.09481 2.48609 + vertex 1.43955 2.09388 2.48591 + vertex 1.43811 2.09784 2.4847 + endloop + endfacet + facet normal 0.0941601 0.320826 0.942446 + outer loop + vertex 1.43056 2.0956 2.48623 + vertex 1.42619 2.09453 2.48703 + vertex 1.43072 2.09164 2.48756 + endloop + endfacet + facet normal 0.0957763 0.321332 0.942111 + outer loop + vertex 1.43955 2.09388 2.48591 + vertex 1.43464 2.09481 2.48609 + vertex 1.43608 2.09083 2.4873 + endloop + endfacet + facet normal 0.0947879 0.319948 0.942682 + outer loop + vertex 1.43716 2.08687 2.48854 + vertex 1.43608 2.09083 2.4873 + vertex 1.43308 2.08809 2.48853 + endloop + endfacet + facet normal 0.0967485 0.320377 0.942337 + outer loop + vertex 1.43716 2.08687 2.48854 + vertex 1.44133 2.08968 2.48716 + vertex 1.43608 2.09083 2.4873 + endloop + endfacet + facet normal 0.0967415 0.320344 0.942349 + outer loop + vertex 1.44133 2.08968 2.48716 + vertex 1.43955 2.09388 2.48591 + vertex 1.43608 2.09083 2.4873 + endloop + endfacet + facet normal 0.0972749 0.319683 0.942518 + outer loop + vertex 1.44124 2.08565 2.48853 + vertex 1.44133 2.08968 2.48716 + vertex 1.43716 2.08687 2.48854 + endloop + endfacet + facet normal 0.0971084 0.319129 0.942723 + outer loop + vertex 1.43824 2.0829 2.48977 + vertex 1.44124 2.08565 2.48853 + vertex 1.43716 2.08687 2.48854 + endloop + endfacet + facet normal 0.099009 0.317244 0.943161 + outer loop + vertex 1.44358 2.08206 2.48949 + vertex 1.44124 2.08565 2.48853 + vertex 1.43824 2.0829 2.48977 + endloop + endfacet + facet normal 0.099136 0.31816 0.942839 + outer loop + vertex 1.43824 2.0829 2.48977 + vertex 1.43964 2.0789 2.49097 + vertex 1.44358 2.08206 2.48949 + endloop + endfacet + facet normal 0.099567 0.317679 0.942956 + outer loop + vertex 1.43964 2.0789 2.49097 + vertex 1.44371 2.07808 2.49082 + vertex 1.44358 2.08206 2.48949 + endloop + endfacet + facet normal 0.103217 0.317663 0.942569 + outer loop + vertex 1.44371 2.07808 2.49082 + vertex 1.44807 2.07913 2.48999 + vertex 1.44358 2.08206 2.48949 + endloop + endfacet + facet normal 0.103727 0.315958 0.943086 + outer loop + vertex 1.44371 2.07808 2.49082 + vertex 1.44577 2.0757 2.49139 + vertex 1.44807 2.07913 2.48999 + endloop + endfacet + facet normal 0.104474 0.315489 0.943161 + outer loop + vertex 1.44976 2.07499 2.49119 + vertex 1.44807 2.07913 2.48999 + vertex 1.44577 2.0757 2.49139 + endloop + endfacet + facet normal 0.10407 0.312947 0.944052 + outer loop + vertex 1.44577 2.0757 2.49139 + vertex 1.44586 2.07174 2.49269 + vertex 1.44976 2.07499 2.49119 + endloop + endfacet + facet normal 0.104705 0.312256 0.94421 + outer loop + vertex 1.4511 2.0711 2.49232 + vertex 1.44976 2.07499 2.49119 + vertex 1.44586 2.07174 2.49269 + endloop + endfacet + facet normal 0.10447 0.309848 0.945029 + outer loop + vertex 1.44816 2.06822 2.49359 + vertex 1.4511 2.0711 2.49232 + vertex 1.44586 2.07174 2.49269 + endloop + endfacet + facet normal 0.104166 0.309672 0.945121 + outer loop + vertex 1.44816 2.06822 2.49359 + vertex 1.44586 2.07174 2.49269 + vertex 1.44353 2.06707 2.49448 + endloop + endfacet + facet normal 0.105398 0.305609 0.946306 + outer loop + vertex 1.44353 2.06707 2.49448 + vertex 1.44806 2.06414 2.49492 + vertex 1.44816 2.06822 2.49359 + endloop + endfacet + facet normal 0.10638 0.307039 0.945733 + outer loop + vertex 1.44363 2.06308 2.49577 + vertex 1.44806 2.06414 2.49492 + vertex 1.44353 2.06707 2.49448 + endloop + endfacet + facet normal 0.102975 0.307072 0.946099 + outer loop + vertex 1.43957 2.06391 2.49594 + vertex 1.44363 2.06308 2.49577 + vertex 1.44353 2.06707 2.49448 + endloop + endfacet + facet normal 0.100583 0.309772 0.945476 + outer loop + vertex 1.43819 2.0679 2.49478 + vertex 1.43957 2.06391 2.49594 + vertex 1.44353 2.06707 2.49448 + endloop + endfacet + facet normal 0.100424 0.308608 0.945873 + outer loop + vertex 1.44353 2.06707 2.49448 + vertex 1.44123 2.07064 2.49356 + vertex 1.43819 2.0679 2.49478 + endloop + endfacet + facet normal 0.0970852 0.311974 0.945117 + outer loop + vertex 1.43819 2.0679 2.49478 + vertex 1.44123 2.07064 2.49356 + vertex 1.43717 2.07187 2.49357 + endloop + endfacet + facet normal 0.0934579 0.311223 0.94573 + outer loop + vertex 1.43819 2.0679 2.49478 + vertex 1.43717 2.07187 2.49357 + vertex 1.43298 2.06907 2.49491 + endloop + endfacet + facet normal 0.0936174 0.311968 0.945469 + outer loop + vertex 1.43298 2.06907 2.49491 + vertex 1.43471 2.06486 2.49613 + vertex 1.43819 2.0679 2.49478 + endloop + endfacet + facet normal 0.0918188 0.311339 0.945853 + outer loop + vertex 1.43471 2.06486 2.49613 + vertex 1.43298 2.06907 2.49491 + vertex 1.43065 2.06565 2.49626 + endloop + endfacet + facet normal 0.0917286 0.310845 0.946024 + outer loop + vertex 1.43065 2.06565 2.49626 + vertex 1.43077 2.06166 2.49756 + vertex 1.43471 2.06486 2.49613 + endloop + endfacet + facet normal 0.0939295 0.308402 0.946607 + outer loop + vertex 1.4361 2.06086 2.49729 + vertex 1.43471 2.06486 2.49613 + vertex 1.43077 2.06166 2.49756 + endloop + endfacet + facet normal 0.0940372 0.309215 0.946331 + outer loop + vertex 1.43311 2.0581 2.49849 + vertex 1.4361 2.06086 2.49729 + vertex 1.43077 2.06166 2.49756 + endloop + endfacet + facet normal 0.0908687 0.307372 0.947241 + outer loop + vertex 1.43311 2.0581 2.49849 + vertex 1.43077 2.06166 2.49756 + vertex 1.4285 2.05694 2.49931 + endloop + endfacet + facet normal 0.0931335 0.299909 0.949411 + outer loop + vertex 1.4285 2.05694 2.49931 + vertex 1.43301 2.05404 2.49978 + vertex 1.43311 2.0581 2.49849 + endloop + endfacet + facet normal 0.0975155 0.299692 0.949039 + outer loop + vertex 1.43301 2.05404 2.49978 + vertex 1.43716 2.05686 2.49846 + vertex 1.43311 2.0581 2.49849 + endloop + endfacet + facet normal 0.0989366 0.304362 0.947404 + outer loop + vertex 1.43716 2.05686 2.49846 + vertex 1.4361 2.06086 2.49729 + vertex 1.43311 2.0581 2.49849 + endloop + endfacet + facet normal 0.101591 0.304927 0.946942 + outer loop + vertex 1.43716 2.05686 2.49846 + vertex 1.4413 2.05965 2.49712 + vertex 1.4361 2.06086 2.49729 + endloop + endfacet + facet normal 0.104515 0.301034 0.947869 + outer loop + vertex 1.44119 2.05559 2.49842 + vertex 1.4413 2.05965 2.49712 + vertex 1.43716 2.05686 2.49846 + endloop + endfacet + facet normal 0.102971 0.296086 0.949595 + outer loop + vertex 1.43821 2.05284 2.4996 + vertex 1.44119 2.05559 2.49842 + vertex 1.43716 2.05686 2.49846 + endloop + endfacet + facet normal 0.105052 0.294008 0.950012 + outer loop + vertex 1.4435 2.05196 2.49929 + vertex 1.44119 2.05559 2.49842 + vertex 1.43821 2.05284 2.4996 + endloop + endfacet + facet normal 0.104155 0.287922 0.951973 + outer loop + vertex 1.43821 2.05284 2.4996 + vertex 1.43957 2.04876 2.50069 + vertex 1.4435 2.05196 2.49929 + endloop + endfacet + facet normal 0.103593 0.288556 0.951842 + outer loop + vertex 1.43957 2.04876 2.50069 + vertex 1.44362 2.04794 2.5005 + vertex 1.4435 2.05196 2.49929 + endloop + endfacet + facet normal 0.102251 0.288561 0.951986 + outer loop + vertex 1.44362 2.04794 2.5005 + vertex 1.44797 2.04896 2.49972 + vertex 1.4435 2.05196 2.49929 + endloop + endfacet + facet normal 0.106042 0.293923 0.949929 + outer loop + vertex 1.4435 2.05196 2.49929 + vertex 1.44797 2.04896 2.49972 + vertex 1.44808 2.05301 2.49846 + endloop + endfacet + facet normal 0.104984 0.297694 0.948871 + outer loop + vertex 1.44808 2.05301 2.49846 + vertex 1.44579 2.05663 2.49757 + vertex 1.4435 2.05196 2.49929 + endloop + endfacet + facet normal 0.107675 0.299203 0.948095 + outer loop + vertex 1.44808 2.05301 2.49846 + vertex 1.45107 2.05577 2.49724 + vertex 1.44579 2.05663 2.49757 + endloop + endfacet + facet normal 0.107961 0.301222 0.947423 + outer loop + vertex 1.45107 2.05577 2.49724 + vertex 1.44975 2.05984 2.4961 + vertex 1.44579 2.05663 2.49757 + endloop + endfacet + facet normal 0.108699 0.300393 0.947601 + outer loop + vertex 1.4457 2.06066 2.49631 + vertex 1.44579 2.05663 2.49757 + vertex 1.44975 2.05984 2.4961 + endloop + endfacet + facet normal 0.109059 0.302356 0.946935 + outer loop + vertex 1.44975 2.05984 2.4961 + vertex 1.44806 2.06414 2.49492 + vertex 1.4457 2.06066 2.49631 + endloop + endfacet + facet normal 0.107322 0.301775 0.947319 + outer loop + vertex 1.44806 2.06414 2.49492 + vertex 1.44975 2.05984 2.4961 + vertex 1.4534 2.06304 2.49467 + endloop + endfacet + facet normal 0.107599 0.303239 0.94682 + outer loop + vertex 1.4534 2.06304 2.49467 + vertex 1.45228 2.06717 2.49347 + vertex 1.44806 2.06414 2.49492 + endloop + endfacet + facet normal 0.105728 0.30559 0.946275 + outer loop + vertex 1.44806 2.06414 2.49492 + vertex 1.45228 2.06717 2.49347 + vertex 1.44816 2.06822 2.49359 + endloop + endfacet + facet normal 0.105627 0.302809 0.94718 + outer loop + vertex 1.4534 2.06304 2.49467 + vertex 1.45709 2.06624 2.49323 + vertex 1.45228 2.06717 2.49347 + endloop + endfacet + facet normal 0.106117 0.305577 0.946236 + outer loop + vertex 1.45709 2.06624 2.49323 + vertex 1.45592 2.07031 2.49205 + vertex 1.45228 2.06717 2.49347 + endloop + endfacet + facet normal 0.104215 0.30758 0.945798 + outer loop + vertex 1.45228 2.06717 2.49347 + vertex 1.45592 2.07031 2.49205 + vertex 1.4511 2.0711 2.49232 + endloop + endfacet + facet normal 0.104761 0.311352 0.944503 + outer loop + vertex 1.45592 2.07031 2.49205 + vertex 1.45453 2.07429 2.49089 + vertex 1.4511 2.0711 2.49232 + endloop + endfacet + facet normal 0.102848 0.310799 0.944895 + outer loop + vertex 1.45936 2.07358 2.4906 + vertex 1.45453 2.07429 2.49089 + vertex 1.45592 2.07031 2.49205 + endloop + endfacet + facet normal 0.104901 0.308825 0.945316 + outer loop + vertex 1.46113 2.06935 2.49179 + vertex 1.45936 2.07358 2.4906 + vertex 1.45592 2.07031 2.49205 + endloop + endfacet + facet normal 0.103175 0.308215 0.945705 + outer loop + vertex 1.46339 2.07281 2.49041 + vertex 1.45936 2.07358 2.4906 + vertex 1.46113 2.06935 2.49179 + endloop + endfacet + facet normal 0.106028 0.306448 0.945964 + outer loop + vertex 1.46545 2.07033 2.49098 + vertex 1.46339 2.07281 2.49041 + vertex 1.46113 2.06935 2.49179 + endloop + endfacet + facet normal 0.108866 0.308574 0.94495 + outer loop + vertex 1.46339 2.07281 2.49041 + vertex 1.46545 2.07033 2.49098 + vertex 1.46774 2.07361 2.48965 + endloop + endfacet + facet normal 0.107706 0.313483 0.943466 + outer loop + vertex 1.46339 2.07281 2.49041 + vertex 1.46774 2.07361 2.48965 + vertex 1.46332 2.07684 2.48908 + endloop + endfacet + facet normal 0.105732 0.310967 0.944521 + outer loop + vertex 1.46332 2.07684 2.48908 + vertex 1.46774 2.07361 2.48965 + vertex 1.46798 2.07745 2.48836 + endloop + endfacet + facet normal 0.10489 0.315613 0.943073 + outer loop + vertex 1.46798 2.07745 2.48836 + vertex 1.46629 2.08081 2.48742 + vertex 1.46332 2.07684 2.48908 + endloop + endfacet + facet normal 0.103145 0.316826 0.942859 + outer loop + vertex 1.46332 2.07684 2.48908 + vertex 1.46629 2.08081 2.48742 + vertex 1.46075 2.08165 2.48774 + endloop + endfacet + facet normal 0.103389 0.316938 0.942794 + outer loop + vertex 1.46332 2.07684 2.48908 + vertex 1.46075 2.08165 2.48774 + vertex 1.45786 2.07758 2.48943 + endloop + endfacet + facet normal 0.103126 0.314621 0.943599 + outer loop + vertex 1.45786 2.07758 2.48943 + vertex 1.45936 2.07358 2.4906 + vertex 1.46332 2.07684 2.48908 + endloop + endfacet + facet normal 0.103064 0.317154 0.942757 + outer loop + vertex 1.45786 2.07758 2.48943 + vertex 1.46075 2.08165 2.48774 + vertex 1.45606 2.08082 2.48854 + endloop + endfacet + facet normal 0.103506 0.317366 0.942637 + outer loop + vertex 1.45786 2.07758 2.48943 + vertex 1.45606 2.08082 2.48854 + vertex 1.45311 2.07812 2.48977 + endloop + endfacet + facet normal 0.10327 0.314751 0.94354 + outer loop + vertex 1.45311 2.07812 2.48977 + vertex 1.45453 2.07429 2.49089 + vertex 1.45786 2.07758 2.48943 + endloop + endfacet + facet normal 0.104417 0.315107 0.943295 + outer loop + vertex 1.44976 2.07499 2.49119 + vertex 1.45453 2.07429 2.49089 + vertex 1.45311 2.07812 2.48977 + endloop + endfacet + facet normal 0.103868 0.317006 0.942719 + outer loop + vertex 1.45311 2.07812 2.48977 + vertex 1.45606 2.08082 2.48854 + vertex 1.45218 2.08196 2.48858 + endloop + endfacet + facet normal 0.104464 0.317118 0.942615 + outer loop + vertex 1.45311 2.07812 2.48977 + vertex 1.45218 2.08196 2.48858 + vertex 1.44807 2.07913 2.48999 + endloop + endfacet + facet normal 0.104395 0.317206 0.942593 + outer loop + vertex 1.44807 2.07913 2.48999 + vertex 1.45218 2.08196 2.48858 + vertex 1.4482 2.08313 2.48863 + endloop + endfacet + facet normal 0.104708 0.318283 0.942195 + outer loop + vertex 1.45218 2.08196 2.48858 + vertex 1.45118 2.08588 2.48737 + vertex 1.4482 2.08313 2.48863 + endloop + endfacet + facet normal 0.104082 0.3189 0.942056 + outer loop + vertex 1.4482 2.08313 2.48863 + vertex 1.45118 2.08588 2.48737 + vertex 1.44588 2.0867 2.48768 + endloop + endfacet + facet normal 0.102722 0.318123 0.942468 + outer loop + vertex 1.4482 2.08313 2.48863 + vertex 1.44588 2.0867 2.48768 + vertex 1.44358 2.08206 2.48949 + endloop + endfacet + facet normal 0.102961 0.317296 0.942721 + outer loop + vertex 1.44358 2.08206 2.48949 + vertex 1.44807 2.07913 2.48999 + vertex 1.4482 2.08313 2.48863 + endloop + endfacet + facet normal 0.10418 0.319618 0.941802 + outer loop + vertex 1.45118 2.08588 2.48737 + vertex 1.44978 2.08985 2.48618 + vertex 1.44588 2.0867 2.48768 + endloop + endfacet + facet normal 0.104532 0.319226 0.941896 + outer loop + vertex 1.44574 2.09068 2.48634 + vertex 1.44588 2.0867 2.48768 + vertex 1.44978 2.08985 2.48618 + endloop + endfacet + facet normal 0.105113 0.322302 0.940783 + outer loop + vertex 1.44978 2.08985 2.48618 + vertex 1.44801 2.09406 2.48493 + vertex 1.44574 2.09068 2.48634 + endloop + endfacet + facet normal 0.10428 0.322825 0.940696 + outer loop + vertex 1.44363 2.09307 2.48576 + vertex 1.44574 2.09068 2.48634 + vertex 1.44801 2.09406 2.48493 + endloop + endfacet + facet normal 0.103908 0.324136 0.940287 + outer loop + vertex 1.44363 2.09307 2.48576 + vertex 1.44801 2.09406 2.48493 + vertex 1.44346 2.09702 2.48442 + endloop + endfacet + facet normal 0.0997153 0.324114 0.940748 + outer loop + vertex 1.43955 2.09388 2.48591 + vertex 1.44363 2.09307 2.48576 + vertex 1.44346 2.09702 2.48442 + endloop + endfacet + facet normal 0.0995489 0.3243 0.940702 + outer loop + vertex 1.43811 2.09784 2.4847 + vertex 1.43955 2.09388 2.48591 + vertex 1.44346 2.09702 2.48442 + endloop + endfacet + facet normal 0.0996593 0.325117 0.940408 + outer loop + vertex 1.44346 2.09702 2.48442 + vertex 1.4411 2.10054 2.48345 + vertex 1.43811 2.09784 2.4847 + endloop + endfacet + facet normal 0.101918 0.326437 0.939708 + outer loop + vertex 1.44346 2.09702 2.48442 + vertex 1.44571 2.10159 2.48258 + vertex 1.4411 2.10054 2.48345 + endloop + endfacet + facet normal 0.103958 0.325476 0.939818 + outer loop + vertex 1.44806 2.09805 2.48355 + vertex 1.44571 2.10159 2.48258 + vertex 1.44346 2.09702 2.48442 + endloop + endfacet + facet normal 0.105551 0.326398 0.939321 + outer loop + vertex 1.44806 2.09805 2.48355 + vertex 1.45102 2.10074 2.48228 + vertex 1.44571 2.10159 2.48258 + endloop + endfacet + facet normal 0.106567 0.325393 0.939555 + outer loop + vertex 1.4521 2.09681 2.48352 + vertex 1.45102 2.10074 2.48228 + vertex 1.44806 2.09805 2.48355 + endloop + endfacet + facet normal 0.106288 0.324475 0.939903 + outer loop + vertex 1.44801 2.09406 2.48493 + vertex 1.4521 2.09681 2.48352 + vertex 1.44806 2.09805 2.48355 + endloop + endfacet + facet normal 0.10608 0.324749 0.939833 + outer loop + vertex 1.45319 2.09288 2.48475 + vertex 1.4521 2.09681 2.48352 + vertex 1.44801 2.09406 2.48493 + endloop + endfacet + facet normal 0.105412 0.324602 0.939958 + outer loop + vertex 1.45319 2.09288 2.48475 + vertex 1.45612 2.09558 2.48349 + vertex 1.4521 2.09681 2.48352 + endloop + endfacet + facet normal 0.105826 0.325967 0.939439 + outer loop + vertex 1.45612 2.09558 2.48349 + vertex 1.45618 2.09956 2.48211 + vertex 1.4521 2.09681 2.48352 + endloop + endfacet + facet normal 0.103227 0.326092 0.939685 + outer loop + vertex 1.45618 2.09956 2.48211 + vertex 1.45612 2.09558 2.48349 + vertex 1.46069 2.09662 2.48263 + endloop + endfacet + facet normal 0.103733 0.326816 0.939378 + outer loop + vertex 1.46054 2.10055 2.48128 + vertex 1.45618 2.09956 2.48211 + vertex 1.46069 2.09662 2.48263 + endloop + endfacet + facet normal 0.100555 0.326813 0.939724 + outer loop + vertex 1.46054 2.10055 2.48128 + vertex 1.46069 2.09662 2.48263 + vertex 1.46461 2.09975 2.48112 + endloop + endfacet + facet normal 0.0998598 0.322974 0.941125 + outer loop + vertex 1.46461 2.09975 2.48112 + vertex 1.46291 2.10394 2.47986 + vertex 1.46054 2.10055 2.48128 + endloop + endfacet + facet normal 0.100901 0.322299 0.941245 + outer loop + vertex 1.45848 2.10292 2.48069 + vertex 1.46054 2.10055 2.48128 + vertex 1.46291 2.10394 2.47986 + endloop + endfacet + facet normal 0.102087 0.318179 0.942518 + outer loop + vertex 1.45848 2.10292 2.48069 + vertex 1.46291 2.10394 2.47986 + vertex 1.45843 2.1069 2.47935 + endloop + endfacet + facet normal 0.101251 0.316999 0.943006 + outer loop + vertex 1.45843 2.1069 2.47935 + vertex 1.46291 2.10394 2.47986 + vertex 1.46308 2.10797 2.47849 + endloop + endfacet + facet normal 0.0985424 0.317191 0.943228 + outer loop + vertex 1.46291 2.10394 2.47986 + vertex 1.46713 2.10675 2.47848 + vertex 1.46308 2.10797 2.47849 + endloop + endfacet + facet normal 0.0984407 0.316852 0.943353 + outer loop + vertex 1.46713 2.10675 2.47848 + vertex 1.46605 2.11067 2.47728 + vertex 1.46308 2.10797 2.47849 + endloop + endfacet + facet normal 0.0999049 0.315393 0.943688 + outer loop + vertex 1.46308 2.10797 2.47849 + vertex 1.46605 2.11067 2.47728 + vertex 1.46073 2.11155 2.47754 + endloop + endfacet + facet normal 0.096784 0.316486 0.943647 + outer loop + vertex 1.46713 2.10675 2.47848 + vertex 1.47122 2.1095 2.47714 + vertex 1.46605 2.11067 2.47728 + endloop + endfacet + facet normal 0.100749 0.334929 0.936842 + outer loop + vertex 1.47122 2.1095 2.47714 + vertex 1.4693 2.1135 2.47591 + vertex 1.46605 2.11067 2.47728 + endloop + endfacet + facet normal 0.0978132 0.315127 0.943996 + outer loop + vertex 1.47118 2.10556 2.47846 + vertex 1.47122 2.1095 2.47714 + vertex 1.46713 2.10675 2.47848 + endloop + endfacet + facet normal 0.0983845 0.31708 0.943282 + outer loop + vertex 1.46814 2.10281 2.4797 + vertex 1.47118 2.10556 2.47846 + vertex 1.46713 2.10675 2.47848 + endloop + endfacet + facet normal 0.100152 0.315305 0.943691 + outer loop + vertex 1.47347 2.10201 2.4794 + vertex 1.47118 2.10556 2.47846 + vertex 1.46814 2.10281 2.4797 + endloop + endfacet + facet normal 0.101109 0.322706 0.941083 + outer loop + vertex 1.46814 2.10281 2.4797 + vertex 1.46949 2.09884 2.48091 + vertex 1.47347 2.10201 2.4794 + endloop + endfacet + facet normal 0.103267 0.320287 0.941675 + outer loop + vertex 1.46949 2.09884 2.48091 + vertex 1.47355 2.09804 2.48074 + vertex 1.47347 2.10201 2.4794 + endloop + endfacet + facet normal 0.10879 0.320204 0.941082 + outer loop + vertex 1.47355 2.09804 2.48074 + vertex 1.47795 2.09906 2.47989 + vertex 1.47347 2.10201 2.4794 + endloop + endfacet + facet normal 0.105664 0.315769 0.942934 + outer loop + vertex 1.47347 2.10201 2.4794 + vertex 1.47795 2.09906 2.47989 + vertex 1.47809 2.1031 2.47852 + endloop + endfacet + facet normal 0.106523 0.31284 0.943814 + outer loop + vertex 1.47809 2.1031 2.47852 + vertex 1.47576 2.10664 2.47761 + vertex 1.47347 2.10201 2.4794 + endloop + endfacet + facet normal 0.108614 0.314052 0.943173 + outer loop + vertex 1.47809 2.1031 2.47852 + vertex 1.48105 2.10584 2.47727 + vertex 1.47576 2.10664 2.47761 + endloop + endfacet + facet normal 0.109314 0.31942 0.941287 + outer loop + vertex 1.48105 2.10584 2.47727 + vertex 1.47951 2.10979 2.4761 + vertex 1.47576 2.10664 2.47761 + endloop + endfacet + facet normal 0.110811 0.31781 0.941657 + outer loop + vertex 1.47547 2.11053 2.47633 + vertex 1.47576 2.10664 2.47761 + vertex 1.47951 2.10979 2.4761 + endloop + endfacet + facet normal 0.102576 0.317523 0.942686 + outer loop + vertex 1.47547 2.11053 2.47633 + vertex 1.47122 2.1095 2.47714 + vertex 1.47576 2.10664 2.47761 + endloop + endfacet + facet normal 0.0987287 0.330312 0.938694 + outer loop + vertex 1.47547 2.11053 2.47633 + vertex 1.47324 2.1127 2.4758 + vertex 1.47122 2.1095 2.47714 + endloop + endfacet + facet normal 0.110854 0.311841 0.943645 + outer loop + vertex 1.4821 2.10186 2.47846 + vertex 1.48105 2.10584 2.47727 + vertex 1.47809 2.1031 2.47852 + endloop + endfacet + facet normal 0.114015 0.312498 0.943051 + outer loop + vertex 1.4821 2.10186 2.47846 + vertex 1.48622 2.10458 2.47705 + vertex 1.48105 2.10584 2.47727 + endloop + endfacet + facet normal 0.115169 0.317576 0.941213 + outer loop + vertex 1.48622 2.10458 2.47705 + vertex 1.48444 2.10881 2.47585 + vertex 1.48105 2.10584 2.47727 + endloop + endfacet + facet normal 0.114623 0.311679 0.943248 + outer loop + vertex 1.48611 2.10055 2.4784 + vertex 1.48622 2.10458 2.47705 + vertex 1.4821 2.10186 2.47846 + endloop + endfacet + facet normal 0.115866 0.315536 0.941813 + outer loop + vertex 1.48312 2.09785 2.47967 + vertex 1.48611 2.10055 2.4784 + vertex 1.4821 2.10186 2.47846 + endloop + endfacet + facet normal 0.112317 0.314837 0.942477 + outer loop + vertex 1.48312 2.09785 2.47967 + vertex 1.4821 2.10186 2.47846 + vertex 1.47795 2.09906 2.47989 + endloop + endfacet + facet normal 0.113641 0.3209 0.940271 + outer loop + vertex 1.47795 2.09906 2.47989 + vertex 1.47966 2.09482 2.48112 + vertex 1.48312 2.09785 2.47967 + endloop + endfacet + facet normal 0.114636 0.319876 0.940499 + outer loop + vertex 1.47966 2.09482 2.48112 + vertex 1.48449 2.09383 2.48087 + vertex 1.48312 2.09785 2.47967 + endloop + endfacet + facet normal 0.116052 0.320268 0.940192 + outer loop + vertex 1.48312 2.09785 2.47967 + vertex 1.48449 2.09383 2.48087 + vertex 1.48837 2.09689 2.47935 + endloop + endfacet + facet normal 0.115908 0.320431 0.940154 + outer loop + vertex 1.48449 2.09383 2.48087 + vertex 1.48847 2.09295 2.48068 + vertex 1.48837 2.09689 2.47935 + endloop + endfacet + facet normal 0.116239 0.320427 0.940114 + outer loop + vertex 1.48847 2.09295 2.48068 + vertex 1.49269 2.09386 2.47985 + vertex 1.48837 2.09689 2.47935 + endloop + endfacet + facet normal 0.116856 0.321249 0.939757 + outer loop + vertex 1.48837 2.09689 2.47935 + vertex 1.49269 2.09386 2.47985 + vertex 1.49287 2.0977 2.47852 + endloop + endfacet + facet normal 0.118221 0.315477 0.94154 + outer loop + vertex 1.49287 2.0977 2.47852 + vertex 1.49074 2.10139 2.47755 + vertex 1.48837 2.09689 2.47935 + endloop + endfacet + facet normal 0.116219 0.316494 0.941448 + outer loop + vertex 1.48837 2.09689 2.47935 + vertex 1.49074 2.10139 2.47755 + vertex 1.48611 2.10055 2.4784 + endloop + endfacet + facet normal 0.119101 0.315917 0.941282 + outer loop + vertex 1.49287 2.0977 2.47852 + vertex 1.49635 2.10007 2.47728 + vertex 1.49074 2.10139 2.47755 + endloop + endfacet + facet normal 0.118646 0.313833 0.942036 + outer loop + vertex 1.49635 2.10007 2.47728 + vertex 1.49461 2.10439 2.47606 + vertex 1.49074 2.10139 2.47755 + endloop + endfacet + facet normal 0.120877 0.311233 0.942615 + outer loop + vertex 1.49057 2.10544 2.47623 + vertex 1.49074 2.10139 2.47755 + vertex 1.49461 2.10439 2.47606 + endloop + endfacet + facet normal 0.117209 0.311233 0.943078 + outer loop + vertex 1.49057 2.10544 2.47623 + vertex 1.48622 2.10458 2.47705 + vertex 1.49074 2.10139 2.47755 + endloop + endfacet + facet normal 0.116451 0.314224 0.94218 + outer loop + vertex 1.49057 2.10544 2.47623 + vertex 1.48849 2.1079 2.47567 + vertex 1.48622 2.10458 2.47705 + endloop + endfacet + facet normal 0.115795 0.322038 0.939619 + outer loop + vertex 1.48847 2.09295 2.48068 + vertex 1.49054 2.09056 2.48125 + vertex 1.49269 2.09386 2.47985 + endloop + endfacet + facet normal 0.115646 0.321922 0.939677 + outer loop + vertex 1.49054 2.09056 2.48125 + vertex 1.48847 2.09295 2.48068 + vertex 1.48622 2.0896 2.48211 + endloop + endfacet + facet normal 0.115983 0.320725 0.940044 + outer loop + vertex 1.49054 2.09056 2.48125 + vertex 1.48622 2.0896 2.48211 + vertex 1.4907 2.08663 2.48257 + endloop + endfacet + facet normal 0.114384 0.320725 0.94024 + outer loop + vertex 1.49054 2.09056 2.48125 + vertex 1.4907 2.08663 2.48257 + vertex 1.49454 2.08976 2.48103 + endloop + endfacet + facet normal 0.114528 0.320567 0.940277 + outer loop + vertex 1.49598 2.08579 2.48221 + vertex 1.49454 2.08976 2.48103 + vertex 1.4907 2.08663 2.48257 + endloop + endfacet + facet normal 0.114062 0.317073 0.941517 + outer loop + vertex 1.49302 2.08307 2.48349 + vertex 1.49598 2.08579 2.48221 + vertex 1.4907 2.08663 2.48257 + endloop + endfacet + facet normal 0.114424 0.317279 0.941404 + outer loop + vertex 1.49302 2.08307 2.48349 + vertex 1.4907 2.08663 2.48257 + vertex 1.48843 2.08202 2.4844 + endloop + endfacet + facet normal 0.115595 0.313233 0.942615 + outer loop + vertex 1.48843 2.08202 2.4844 + vertex 1.49289 2.07906 2.48484 + vertex 1.49302 2.08307 2.48349 + endloop + endfacet + facet normal 0.11415 0.313327 0.94276 + outer loop + vertex 1.49289 2.07906 2.48484 + vertex 1.49703 2.08184 2.48341 + vertex 1.49302 2.08307 2.48349 + endloop + endfacet + facet normal 0.114994 0.31615 0.941714 + outer loop + vertex 1.49703 2.08184 2.48341 + vertex 1.49598 2.08579 2.48221 + vertex 1.49302 2.08307 2.48349 + endloop + endfacet + facet normal 0.114457 0.316039 0.941817 + outer loop + vertex 1.49703 2.08184 2.48341 + vertex 1.50114 2.08458 2.48199 + vertex 1.49598 2.08579 2.48221 + endloop + endfacet + facet normal 0.1162 0.313707 0.942383 + outer loop + vertex 1.50104 2.08056 2.48334 + vertex 1.50114 2.08458 2.48199 + vertex 1.49703 2.08184 2.48341 + endloop + endfacet + facet normal 0.115545 0.311616 0.943157 + outer loop + vertex 1.49804 2.07787 2.4846 + vertex 1.50104 2.08056 2.48334 + vertex 1.49703 2.08184 2.48341 + endloop + endfacet + facet normal 0.117828 0.309299 0.943637 + outer loop + vertex 1.5033 2.0769 2.48426 + vertex 1.50104 2.08056 2.48334 + vertex 1.49804 2.07787 2.4846 + endloop + endfacet + facet normal 0.117674 0.308349 0.943967 + outer loop + vertex 1.49804 2.07787 2.4846 + vertex 1.49941 2.07384 2.48574 + vertex 1.5033 2.0769 2.48426 + endloop + endfacet + facet normal 0.117938 0.308045 0.944033 + outer loop + vertex 1.49941 2.07384 2.48574 + vertex 1.50341 2.07293 2.48554 + vertex 1.5033 2.0769 2.48426 + endloop + endfacet + facet normal 0.122867 0.307985 0.943424 + outer loop + vertex 1.50341 2.07293 2.48554 + vertex 1.50773 2.0737 2.48473 + vertex 1.5033 2.0769 2.48426 + endloop + endfacet + facet normal 0.122165 0.307074 0.943812 + outer loop + vertex 1.5033 2.0769 2.48426 + vertex 1.50773 2.0737 2.48473 + vertex 1.50783 2.07767 2.48342 + endloop + endfacet + facet normal 0.121667 0.309294 0.943151 + outer loop + vertex 1.50783 2.07767 2.48342 + vertex 1.50565 2.08141 2.48248 + vertex 1.5033 2.0769 2.48426 + endloop + endfacet + facet normal 0.124603 0.310784 0.942278 + outer loop + vertex 1.50783 2.07767 2.48342 + vertex 1.51129 2.08003 2.48218 + vertex 1.50565 2.08141 2.48248 + endloop + endfacet + facet normal 0.124227 0.30912 0.942875 + outer loop + vertex 1.51129 2.08003 2.48218 + vertex 1.50949 2.08438 2.481 + vertex 1.50565 2.08141 2.48248 + endloop + endfacet + facet normal 0.122144 0.311547 0.942348 + outer loop + vertex 1.50547 2.08543 2.48117 + vertex 1.50565 2.08141 2.48248 + vertex 1.50949 2.08438 2.481 + endloop + endfacet + facet normal 0.123077 0.315338 0.940964 + outer loop + vertex 1.50949 2.08438 2.481 + vertex 1.50771 2.08867 2.47979 + vertex 1.50547 2.08543 2.48117 + endloop + endfacet + facet normal 0.122791 0.315239 0.941035 + outer loop + vertex 1.50771 2.08867 2.47979 + vertex 1.50949 2.08438 2.481 + vertex 1.51334 2.08731 2.47951 + endloop + endfacet + facet normal 0.122902 0.315738 0.940853 + outer loop + vertex 1.51334 2.08731 2.47951 + vertex 1.51116 2.09102 2.47855 + vertex 1.50771 2.08867 2.47979 + endloop + endfacet + facet normal 0.122862 0.315718 0.940865 + outer loop + vertex 1.51334 2.08731 2.47951 + vertex 1.51567 2.09178 2.47771 + vertex 1.51116 2.09102 2.47855 + endloop + endfacet + facet normal 0.125104 0.314584 0.940949 + outer loop + vertex 1.518 2.0881 2.47863 + vertex 1.51567 2.09178 2.47771 + vertex 1.51334 2.08731 2.47951 + endloop + endfacet + facet normal 0.126208 0.309671 0.942431 + outer loop + vertex 1.51334 2.08731 2.47951 + vertex 1.518 2.08396 2.47999 + vertex 1.518 2.0881 2.47863 + endloop + endfacet + facet normal 0.12744 0.309622 0.942281 + outer loop + vertex 1.518 2.08396 2.47999 + vertex 1.52214 2.08671 2.47853 + vertex 1.518 2.0881 2.47863 + endloop + endfacet + facet normal 0.127842 0.310857 0.94182 + outer loop + vertex 1.52214 2.08671 2.47853 + vertex 1.52096 2.09079 2.47734 + vertex 1.518 2.0881 2.47863 + endloop + endfacet + facet normal 0.128599 0.31103 0.941659 + outer loop + vertex 1.52214 2.08671 2.47853 + vertex 1.52613 2.08955 2.47704 + vertex 1.52096 2.09079 2.47734 + endloop + endfacet + facet normal 0.128488 0.310526 0.941841 + outer loop + vertex 1.52613 2.08955 2.47704 + vertex 1.52439 2.09385 2.47586 + vertex 1.52096 2.09079 2.47734 + endloop + endfacet + facet normal 0.129387 0.310828 0.941618 + outer loop + vertex 1.52842 2.09293 2.47562 + vertex 1.52439 2.09385 2.47586 + vertex 1.52613 2.08955 2.47704 + endloop + endfacet + facet normal 0.131648 0.309366 0.941786 + outer loop + vertex 1.53044 2.09042 2.47615 + vertex 1.52842 2.09293 2.47562 + vertex 1.52613 2.08955 2.47704 + endloop + endfacet + facet normal 0.131663 0.309309 0.941803 + outer loop + vertex 1.53044 2.09042 2.47615 + vertex 1.52613 2.08955 2.47704 + vertex 1.53049 2.08646 2.47745 + endloop + endfacet + facet normal 0.13352 0.309251 0.94156 + outer loop + vertex 1.53044 2.09042 2.47615 + vertex 1.53049 2.08646 2.47745 + vertex 1.53444 2.08935 2.47594 + endloop + endfacet + facet normal 0.133375 0.308667 0.941773 + outer loop + vertex 1.53444 2.08935 2.47594 + vertex 1.53277 2.09367 2.47476 + vertex 1.53044 2.09042 2.47615 + endloop + endfacet + facet normal 0.133262 0.30863 0.941801 + outer loop + vertex 1.53277 2.09367 2.47476 + vertex 1.53444 2.08935 2.47594 + vertex 1.53837 2.09225 2.47443 + endloop + endfacet + facet normal 0.134107 0.307598 0.942018 + outer loop + vertex 1.53444 2.08935 2.47594 + vertex 1.53847 2.08822 2.47574 + vertex 1.53837 2.09225 2.47443 + endloop + endfacet + facet normal 0.13411 0.307598 0.942018 + outer loop + vertex 1.53847 2.08822 2.47574 + vertex 1.54283 2.08885 2.47491 + vertex 1.53837 2.09225 2.47443 + endloop + endfacet + facet normal 0.133946 0.308416 0.941774 + outer loop + vertex 1.53847 2.08822 2.47574 + vertex 1.54055 2.08561 2.47629 + vertex 1.54283 2.08885 2.47491 + endloop + endfacet + facet normal 0.134351 0.308708 0.941621 + outer loop + vertex 1.54055 2.08561 2.47629 + vertex 1.53847 2.08822 2.47574 + vertex 1.53612 2.08489 2.47716 + endloop + endfacet + facet normal 0.134588 0.307643 0.941935 + outer loop + vertex 1.54055 2.08561 2.47629 + vertex 1.53612 2.08489 2.47716 + vertex 1.5407 2.08154 2.4776 + endloop + endfacet + facet normal 0.133882 0.307649 0.942034 + outer loop + vertex 1.54055 2.08561 2.47629 + vertex 1.5407 2.08154 2.4776 + vertex 1.54459 2.08446 2.47609 + endloop + endfacet + facet normal 0.134196 0.307272 0.942112 + outer loop + vertex 1.54633 2.0801 2.47727 + vertex 1.54459 2.08446 2.47609 + vertex 1.5407 2.08154 2.4776 + endloop + endfacet + facet normal 0.133579 0.30463 0.943057 + outer loop + vertex 1.54284 2.07775 2.47852 + vertex 1.54633 2.0801 2.47727 + vertex 1.5407 2.08154 2.4776 + endloop + endfacet + facet normal 0.132385 0.304041 0.943416 + outer loop + vertex 1.54284 2.07775 2.47852 + vertex 1.5407 2.08154 2.4776 + vertex 1.53831 2.077 2.4794 + endloop + endfacet + facet normal 0.133262 0.300074 0.944562 + outer loop + vertex 1.53831 2.077 2.4794 + vertex 1.54268 2.07377 2.47981 + vertex 1.54284 2.07775 2.47852 + endloop + endfacet + facet normal 0.132888 0.300103 0.944605 + outer loop + vertex 1.54268 2.07377 2.47981 + vertex 1.54619 2.07615 2.47856 + vertex 1.54284 2.07775 2.47852 + endloop + endfacet + facet normal 0.133966 0.298672 0.944906 + outer loop + vertex 1.54832 2.07228 2.47948 + vertex 1.54619 2.07615 2.47856 + vertex 1.54268 2.07377 2.47981 + endloop + endfacet + facet normal 0.134058 0.299051 0.944774 + outer loop + vertex 1.54268 2.07377 2.47981 + vertex 1.5444 2.06937 2.48096 + vertex 1.54832 2.07228 2.47948 + endloop + endfacet + facet normal 0.134132 0.298961 0.944792 + outer loop + vertex 1.5444 2.06937 2.48096 + vertex 1.54847 2.06819 2.48075 + vertex 1.54832 2.07228 2.47948 + endloop + endfacet + facet normal 0.139302 0.298915 0.944058 + outer loop + vertex 1.54847 2.06819 2.48075 + vertex 1.55281 2.0688 2.47992 + vertex 1.54832 2.07228 2.47948 + endloop + endfacet + facet normal 0.138119 0.297466 0.944689 + outer loop + vertex 1.54832 2.07228 2.47948 + vertex 1.55281 2.0688 2.47992 + vertex 1.55292 2.07281 2.47864 + endloop + endfacet + facet normal 0.137763 0.299568 0.944076 + outer loop + vertex 1.55292 2.07281 2.47864 + vertex 1.55077 2.07669 2.47772 + vertex 1.54832 2.07228 2.47948 + endloop + endfacet + facet normal 0.142228 0.301722 0.942727 + outer loop + vertex 1.55292 2.07281 2.47864 + vertex 1.55638 2.07515 2.47737 + vertex 1.55077 2.07669 2.47772 + endloop + endfacet + facet normal 0.144695 0.298435 0.943398 + outer loop + vertex 1.55628 2.07112 2.47866 + vertex 1.55638 2.07515 2.47737 + vertex 1.55292 2.07281 2.47864 + endloop + endfacet + facet normal 0.150046 0.298071 0.942677 + outer loop + vertex 1.55638 2.07515 2.47737 + vertex 1.55628 2.07112 2.47866 + vertex 1.56082 2.07166 2.47777 + endloop + endfacet + facet normal 0.148813 0.296573 0.943345 + outer loop + vertex 1.56068 2.07578 2.47649 + vertex 1.55638 2.07515 2.47737 + vertex 1.56082 2.07166 2.47777 + endloop + endfacet + facet normal 0.154515 0.296485 0.942455 + outer loop + vertex 1.56068 2.07578 2.47649 + vertex 1.56082 2.07166 2.47777 + vertex 1.56468 2.07455 2.47622 + endloop + endfacet + facet normal 0.155195 0.298885 0.941585 + outer loop + vertex 1.56468 2.07455 2.47622 + vertex 1.56299 2.07912 2.47505 + vertex 1.56068 2.07578 2.47649 + endloop + endfacet + facet normal 0.151636 0.301271 0.941405 + outer loop + vertex 1.5586 2.07843 2.47598 + vertex 1.56068 2.07578 2.47649 + vertex 1.56299 2.07912 2.47505 + endloop + endfacet + facet normal 0.150956 0.304378 0.940514 + outer loop + vertex 1.5586 2.07843 2.47598 + vertex 1.56299 2.07912 2.47505 + vertex 1.55842 2.08251 2.47469 + endloop + endfacet + facet normal 0.148627 0.301384 0.941848 + outer loop + vertex 1.55842 2.08251 2.47469 + vertex 1.56299 2.07912 2.47505 + vertex 1.563 2.0833 2.47371 + endloop + endfacet + facet normal 0.148307 0.302757 0.941458 + outer loop + vertex 1.563 2.0833 2.47371 + vertex 1.56074 2.08702 2.47287 + vertex 1.55842 2.08251 2.47469 + endloop + endfacet + facet normal 0.153074 0.301166 0.941205 + outer loop + vertex 1.56299 2.07912 2.47505 + vertex 1.56709 2.08181 2.47353 + vertex 1.563 2.0833 2.47371 + endloop + endfacet + facet normal 0.152823 0.300442 0.941477 + outer loop + vertex 1.56709 2.08181 2.47353 + vertex 1.56593 2.08593 2.4724 + vertex 1.563 2.0833 2.47371 + endloop + endfacet + facet normal 0.149797 0.303552 0.940966 + outer loop + vertex 1.563 2.0833 2.47371 + vertex 1.56593 2.08593 2.4724 + vertex 1.56074 2.08702 2.47287 + endloop + endfacet + facet normal 0.149349 0.301008 0.941854 + outer loop + vertex 1.56593 2.08593 2.4724 + vertex 1.56456 2.08999 2.47132 + vertex 1.56074 2.08702 2.47287 + endloop + endfacet + facet normal 0.153509 0.302142 0.940822 + outer loop + vertex 1.56936 2.08886 2.4709 + vertex 1.56456 2.08999 2.47132 + vertex 1.56593 2.08593 2.4724 + endloop + endfacet + facet normal 0.154846 0.308697 0.938472 + outer loop + vertex 1.56456 2.08999 2.47132 + vertex 1.56936 2.08886 2.4709 + vertex 1.56787 2.09302 2.46978 + endloop + endfacet + facet normal 0.155327 0.300982 0.940895 + outer loop + vertex 1.56709 2.08181 2.47353 + vertex 1.57111 2.08443 2.47203 + vertex 1.56593 2.08593 2.4724 + endloop + endfacet + facet normal 0.155162 0.300363 0.94112 + outer loop + vertex 1.57111 2.08443 2.47203 + vertex 1.56936 2.08886 2.4709 + vertex 1.56593 2.08593 2.4724 + endloop + endfacet + facet normal 0.156723 0.299054 0.941278 + outer loop + vertex 1.57108 2.08048 2.47328 + vertex 1.57111 2.08443 2.47203 + vertex 1.56709 2.08181 2.47353 + endloop + endfacet + facet normal 0.156535 0.298452 0.9415 + outer loop + vertex 1.5686 2.07731 2.4747 + vertex 1.57108 2.08048 2.47328 + vertex 1.56709 2.08181 2.47353 + endloop + endfacet + facet normal 0.158279 0.297143 0.941623 + outer loop + vertex 1.57289 2.0778 2.47382 + vertex 1.57108 2.08048 2.47328 + vertex 1.5686 2.07731 2.4747 + endloop + endfacet + facet normal 0.158505 0.295828 0.941999 + outer loop + vertex 1.5686 2.07731 2.4747 + vertex 1.57284 2.0739 2.47506 + vertex 1.57289 2.0778 2.47382 + endloop + endfacet + facet normal 0.160453 0.29571 0.941706 + outer loop + vertex 1.57284 2.0739 2.47506 + vertex 1.57612 2.07636 2.47373 + vertex 1.57289 2.0778 2.47382 + endloop + endfacet + facet normal 0.16099 0.296941 0.941227 + outer loop + vertex 1.57612 2.07636 2.47373 + vertex 1.57578 2.08078 2.47239 + vertex 1.57289 2.0778 2.47382 + endloop + endfacet + facet normal 0.160554 0.295587 0.941728 + outer loop + vertex 1.57833 2.07234 2.47461 + vertex 1.57612 2.07636 2.47373 + vertex 1.57284 2.0739 2.47506 + endloop + endfacet + facet normal 0.160284 0.294528 0.942105 + outer loop + vertex 1.57284 2.0739 2.47506 + vertex 1.57454 2.0695 2.47614 + vertex 1.57833 2.07234 2.47461 + endloop + endfacet + facet normal 0.160415 0.294369 0.942133 + outer loop + vertex 1.57454 2.0695 2.47614 + vertex 1.57846 2.06826 2.47586 + vertex 1.57833 2.07234 2.47461 + endloop + endfacet + facet normal 0.160735 0.295471 0.941733 + outer loop + vertex 1.57846 2.06826 2.47586 + vertex 1.57454 2.0695 2.47614 + vertex 1.57628 2.06526 2.47718 + endloop + endfacet + facet normal 0.160212 0.29584 0.941706 + outer loop + vertex 1.58051 2.06568 2.47633 + vertex 1.57846 2.06826 2.47586 + vertex 1.57628 2.06526 2.47718 + endloop + endfacet + facet normal 0.159888 0.297925 0.941104 + outer loop + vertex 1.58051 2.06568 2.47633 + vertex 1.57628 2.06526 2.47718 + vertex 1.58079 2.06183 2.4775 + endloop + endfacet + facet normal 0.161983 0.300572 0.939903 + outer loop + vertex 1.57628 2.06526 2.47718 + vertex 1.57628 2.06158 2.47836 + vertex 1.58079 2.06183 2.4775 + endloop + endfacet + facet normal 0.161238 0.300609 0.940019 + outer loop + vertex 1.57628 2.06158 2.47836 + vertex 1.57628 2.06526 2.47718 + vertex 1.57284 2.06325 2.47841 + endloop + endfacet + facet normal 0.1726 0.32439 0.930043 + outer loop + vertex 1.57291 2.05942 2.47974 + vertex 1.57628 2.06158 2.47836 + vertex 1.57284 2.06325 2.47841 + endloop + endfacet + facet normal 0.156463 0.325015 0.932676 + outer loop + vertex 1.56824 2.06276 2.47935 + vertex 1.57291 2.05942 2.47974 + vertex 1.57284 2.06325 2.47841 + endloop + endfacet + facet normal 0.160853 0.298942 0.940617 + outer loop + vertex 1.57284 2.06325 2.47841 + vertex 1.57071 2.06682 2.47764 + vertex 1.56824 2.06276 2.47935 + endloop + endfacet + facet normal 0.158996 0.300053 0.940579 + outer loop + vertex 1.56824 2.06276 2.47935 + vertex 1.57071 2.06682 2.47764 + vertex 1.56618 2.0663 2.47857 + endloop + endfacet + facet normal 0.155752 0.298395 0.941649 + outer loop + vertex 1.56824 2.06276 2.47935 + vertex 1.56618 2.0663 2.47857 + vertex 1.56268 2.06407 2.47986 + endloop + endfacet + facet normal 0.157561 0.307322 0.938471 + outer loop + vertex 1.56268 2.06407 2.47986 + vertex 1.56432 2.05992 2.48094 + vertex 1.56824 2.06276 2.47935 + endloop + endfacet + facet normal 0.144435 0.323622 0.935098 + outer loop + vertex 1.56432 2.05992 2.48094 + vertex 1.5685 2.05885 2.48067 + vertex 1.56824 2.06276 2.47935 + endloop + endfacet + facet normal 0.165601 0.416124 0.894101 + outer loop + vertex 1.5685 2.05885 2.48067 + vertex 1.56432 2.05992 2.48094 + vertex 1.5667 2.05554 2.48254 + endloop + endfacet + facet normal 0.0818757 0.456848 0.885769 + outer loop + vertex 1.57131 2.0563 2.48172 + vertex 1.5685 2.05885 2.48067 + vertex 1.5667 2.05554 2.48254 + endloop + endfacet + facet normal -0.0905348 0.931602 0.352026 + outer loop + vertex 1.57131 2.0563 2.48172 + vertex 1.5667 2.05554 2.48254 + vertex 1.575 2.055 2.4861 + endloop + endfacet + facet normal 0.213865 0.970967 0.107169 + outer loop + vertex 1.57131 2.0563 2.48172 + vertex 1.575 2.055 2.4861 + vertex 1.57556 2.05536 2.48173 + endloop + endfacet + facet normal 0.10769 0.494478 0.862493 + outer loop + vertex 1.57556 2.05536 2.48173 + vertex 1.57291 2.05942 2.47974 + vertex 1.57131 2.0563 2.48172 + endloop + endfacet + facet normal 0.226323 0.544972 0.807331 + outer loop + vertex 1.57291 2.05942 2.47974 + vertex 1.57556 2.05536 2.48173 + vertex 1.57872 2.05766 2.47929 + endloop + endfacet + facet normal 0.307962 0.459863 0.832878 + outer loop + vertex 1.57556 2.05536 2.48173 + vertex 1.57931 2.05394 2.48113 + vertex 1.57872 2.05766 2.47929 + endloop + endfacet + facet normal 0.299403 0.910661 -0.2847 + outer loop + vertex 1.57931 2.05394 2.48113 + vertex 1.57556 2.05536 2.48173 + vertex 1.58 2.055 2.48525 + endloop + endfacet + facet normal 0.809474 0.521389 -0.270009 + outer loop + vertex 1.58129 2.05111 2.48162 + vertex 1.57931 2.05394 2.48113 + vertex 1.58 2.055 2.48525 + endloop + endfacet + facet normal 0.971038 0.148012 0.187555 + outer loop + vertex 1.58129 2.05111 2.48162 + vertex 1.58 2.055 2.48525 + vertex 1.58168 2.0468 2.483 + endloop + endfacet + facet normal 0.38294 0.312561 0.869289 + outer loop + vertex 1.58129 2.05111 2.48162 + vertex 1.58168 2.0468 2.483 + vertex 1.58426 2.04937 2.48094 + endloop + endfacet + facet normal 0.380881 0.308075 0.871791 + outer loop + vertex 1.58426 2.04937 2.48094 + vertex 1.58373 2.05368 2.47965 + vertex 1.58129 2.05111 2.48162 + endloop + endfacet + facet normal 0.336195 0.36008 0.870238 + outer loop + vertex 1.58615 2.04638 2.48145 + vertex 1.58426 2.04937 2.48094 + vertex 1.58168 2.0468 2.483 + endloop + endfacet + facet normal 0.338542 0.262774 0.903515 + outer loop + vertex 1.58615 2.04638 2.48145 + vertex 1.58168 2.0468 2.483 + vertex 1.58615 2.0419 2.48275 + endloop + endfacet + facet normal 0.179832 0.274438 0.94464 + outer loop + vertex 1.58615 2.04638 2.48145 + vertex 1.58615 2.0419 2.48275 + vertex 1.58997 2.04477 2.48119 + endloop + endfacet + facet normal 0.217357 0.149289 0.964608 + outer loop + vertex 1.58168 2.0468 2.483 + vertex 1.58154 2.04151 2.48385 + vertex 1.58615 2.0419 2.48275 + endloop + endfacet + facet normal 0.204629 0.249771 0.946436 + outer loop + vertex 1.58373 2.03704 2.48455 + vertex 1.58615 2.0419 2.48275 + vertex 1.58154 2.04151 2.48385 + endloop + endfacet + facet normal 0.257013 0.272385 0.927228 + outer loop + vertex 1.58373 2.03704 2.48455 + vertex 1.58154 2.04151 2.48385 + vertex 1.57805 2.03915 2.48551 + endloop + endfacet + facet normal 0.229456 0.185258 0.955526 + outer loop + vertex 1.57805 2.03915 2.48551 + vertex 1.57963 2.03402 2.48612 + vertex 1.58373 2.03704 2.48455 + endloop + endfacet + facet normal 0.166124 0.267757 0.949057 + outer loop + vertex 1.57963 2.03402 2.48612 + vertex 1.58374 2.03273 2.48577 + vertex 1.58373 2.03704 2.48455 + endloop + endfacet + facet normal 0.161132 0.267973 0.949856 + outer loop + vertex 1.58374 2.03273 2.48577 + vertex 1.58841 2.03321 2.48484 + vertex 1.58373 2.03704 2.48455 + endloop + endfacet + facet normal 0.167937 0.276037 0.946362 + outer loop + vertex 1.58373 2.03704 2.48455 + vertex 1.58841 2.03321 2.48484 + vertex 1.58826 2.03765 2.48357 + endloop + endfacet + facet normal 0.161966 0.276115 0.947379 + outer loop + vertex 1.58841 2.03321 2.48484 + vertex 1.59133 2.03622 2.48346 + vertex 1.58826 2.03765 2.48357 + endloop + endfacet + facet normal 0.1624 0.27707 0.947026 + outer loop + vertex 1.59133 2.03622 2.48346 + vertex 1.59149 2.04014 2.48229 + vertex 1.58826 2.03765 2.48357 + endloop + endfacet + facet normal 0.169764 0.268157 0.9483 + outer loop + vertex 1.58826 2.03765 2.48357 + vertex 1.59149 2.04014 2.48229 + vertex 1.58615 2.0419 2.48275 + endloop + endfacet + facet normal 0.173856 0.281805 0.943589 + outer loop + vertex 1.59149 2.04014 2.48229 + vertex 1.58997 2.04477 2.48119 + vertex 1.58615 2.0419 2.48275 + endloop + endfacet + facet normal 0.162521 0.278768 0.946507 + outer loop + vertex 1.59368 2.04336 2.48097 + vertex 1.58997 2.04477 2.48119 + vertex 1.59149 2.04014 2.48229 + endloop + endfacet + facet normal 0.163525 0.281567 0.945505 + outer loop + vertex 1.58997 2.04477 2.48119 + vertex 1.59368 2.04336 2.48097 + vertex 1.59367 2.04744 2.47975 + endloop + endfacet + facet normal 0.160731 0.277211 0.94727 + outer loop + vertex 1.59149 2.04014 2.48229 + vertex 1.59133 2.03622 2.48346 + vertex 1.59551 2.03667 2.48262 + endloop + endfacet + facet normal 0.162651 0.279345 0.946314 + outer loop + vertex 1.59557 2.04066 2.48143 + vertex 1.59149 2.04014 2.48229 + vertex 1.59551 2.03667 2.48262 + endloop + endfacet + facet normal 0.152366 0.279937 0.94785 + outer loop + vertex 1.59557 2.04066 2.48143 + vertex 1.59551 2.03667 2.48262 + vertex 1.59949 2.03941 2.48117 + endloop + endfacet + facet normal 0.152575 0.280641 0.947608 + outer loop + vertex 1.59949 2.03941 2.48117 + vertex 1.59795 2.04398 2.48007 + vertex 1.59557 2.04066 2.48143 + endloop + endfacet + facet normal 0.158971 0.276151 0.947876 + outer loop + vertex 1.59368 2.04336 2.48097 + vertex 1.59557 2.04066 2.48143 + vertex 1.59795 2.04398 2.48007 + endloop + endfacet + facet normal 0.16279 0.278588 0.946514 + outer loop + vertex 1.59557 2.04066 2.48143 + vertex 1.59368 2.04336 2.48097 + vertex 1.59149 2.04014 2.48229 + endloop + endfacet + facet normal 0.160996 0.275563 0.947705 + outer loop + vertex 1.59301 2.03353 2.48396 + vertex 1.59551 2.03667 2.48262 + vertex 1.59133 2.03622 2.48346 + endloop + endfacet + facet normal 0.156153 0.279316 0.947417 + outer loop + vertex 1.5969 2.03215 2.48373 + vertex 1.59551 2.03667 2.48262 + vertex 1.59301 2.03353 2.48396 + endloop + endfacet + facet normal 0.15563 0.277745 0.947965 + outer loop + vertex 1.59288 2.02957 2.48514 + vertex 1.5969 2.03215 2.48373 + vertex 1.59301 2.03353 2.48396 + endloop + endfacet + facet normal 0.15073 0.284674 0.9467 + outer loop + vertex 1.59799 2.02797 2.48481 + vertex 1.5969 2.03215 2.48373 + vertex 1.59288 2.02957 2.48514 + endloop + endfacet + facet normal 0.139808 0.275224 0.95116 + outer loop + vertex 1.5969 2.03215 2.48373 + vertex 1.60102 2.03491 2.48232 + vertex 1.59551 2.03667 2.48262 + endloop + endfacet + facet normal 0.144387 0.290474 0.945927 + outer loop + vertex 1.60102 2.03491 2.48232 + vertex 1.59949 2.03941 2.48117 + vertex 1.59551 2.03667 2.48262 + endloop + endfacet + facet normal 0.16197 0.276111 0.94738 + outer loop + vertex 1.59301 2.03353 2.48396 + vertex 1.59133 2.03622 2.48346 + vertex 1.58841 2.03321 2.48484 + endloop + endfacet + facet normal 0.161828 0.277283 0.947062 + outer loop + vertex 1.58841 2.03321 2.48484 + vertex 1.59288 2.02957 2.48514 + vertex 1.59301 2.03353 2.48396 + endloop + endfacet + facet normal 0.162087 0.27759 0.946927 + outer loop + vertex 1.58867 2.02903 2.48602 + vertex 1.59288 2.02957 2.48514 + vertex 1.58841 2.03321 2.48484 + endloop + endfacet + facet normal 0.159529 0.278336 0.947143 + outer loop + vertex 1.58374 2.03273 2.48577 + vertex 1.58559 2.03009 2.48623 + vertex 1.58841 2.03321 2.48484 + endloop + endfacet + facet normal 0.160411 0.277571 0.947218 + outer loop + vertex 1.58867 2.02903 2.48602 + vertex 1.58841 2.03321 2.48484 + vertex 1.58559 2.03009 2.48623 + endloop + endfacet + facet normal 0.160425 0.277614 0.947203 + outer loop + vertex 1.58559 2.03009 2.48623 + vertex 1.58587 2.0259 2.48741 + vertex 1.58867 2.02903 2.48602 + endloop + endfacet + facet normal 0.158754 0.277585 0.947493 + outer loop + vertex 1.58559 2.03009 2.48623 + vertex 1.58123 2.0295 2.48714 + vertex 1.58587 2.0259 2.48741 + endloop + endfacet + facet normal 0.159919 0.279036 0.946871 + outer loop + vertex 1.58123 2.0295 2.48714 + vertex 1.58116 2.02558 2.4883 + vertex 1.58587 2.0259 2.48741 + endloop + endfacet + facet normal 0.159903 0.279166 0.946836 + outer loop + vertex 1.58293 2.02291 2.48879 + vertex 1.58587 2.0259 2.48741 + vertex 1.58116 2.02558 2.4883 + endloop + endfacet + facet normal 0.158329 0.278223 0.947377 + outer loop + vertex 1.58293 2.02291 2.48879 + vertex 1.58116 2.02558 2.4883 + vertex 1.57862 2.02245 2.48965 + endloop + endfacet + facet normal 0.158819 0.275116 0.948203 + outer loop + vertex 1.57862 2.02245 2.48965 + vertex 1.5828 2.01899 2.48995 + vertex 1.58293 2.02291 2.48879 + endloop + endfacet + facet normal 0.158827 0.275125 0.948198 + outer loop + vertex 1.57859 2.0184 2.49083 + vertex 1.5828 2.01899 2.48995 + vertex 1.57862 2.02245 2.48965 + endloop + endfacet + facet normal 0.159612 0.275084 0.948079 + outer loop + vertex 1.57464 2.01976 2.4911 + vertex 1.57859 2.0184 2.49083 + vertex 1.57862 2.02245 2.48965 + endloop + endfacet + facet normal 0.159602 0.275096 0.948077 + outer loop + vertex 1.57298 2.02445 2.49002 + vertex 1.57464 2.01976 2.4911 + vertex 1.57862 2.02245 2.48965 + endloop + endfacet + facet normal 0.160853 0.278877 0.94676 + outer loop + vertex 1.57862 2.02245 2.48965 + vertex 1.57709 2.02695 2.48858 + vertex 1.57298 2.02445 2.49002 + endloop + endfacet + facet normal 0.160599 0.279255 0.946691 + outer loop + vertex 1.57298 2.02445 2.49002 + vertex 1.57709 2.02695 2.48858 + vertex 1.57298 2.02833 2.48887 + endloop + endfacet + facet normal 0.162929 0.279147 0.946325 + outer loop + vertex 1.56821 2.02816 2.48974 + vertex 1.57298 2.02445 2.49002 + vertex 1.57298 2.02833 2.48887 + endloop + endfacet + facet normal 0.163136 0.276777 0.946985 + outer loop + vertex 1.57298 2.02833 2.48887 + vertex 1.57109 2.03087 2.48845 + vertex 1.56821 2.02816 2.48974 + endloop + endfacet + facet normal 0.161974 0.275982 0.947417 + outer loop + vertex 1.57298 2.02833 2.48887 + vertex 1.57551 2.03126 2.48758 + vertex 1.57109 2.03087 2.48845 + endloop + endfacet + facet normal 0.166126 0.246028 0.95492 + outer loop + vertex 1.57116 2.03473 2.48745 + vertex 1.57109 2.03087 2.48845 + vertex 1.57551 2.03126 2.48758 + endloop + endfacet + facet normal 0.168264 0.248672 0.95386 + outer loop + vertex 1.57552 2.03529 2.48653 + vertex 1.57116 2.03473 2.48745 + vertex 1.57551 2.03126 2.48758 + endloop + endfacet + facet normal 0.171639 0.248516 0.9533 + outer loop + vertex 1.57552 2.03529 2.48653 + vertex 1.57551 2.03126 2.48758 + vertex 1.57963 2.03402 2.48612 + endloop + endfacet + facet normal 0.147152 0.162254 0.975715 + outer loop + vertex 1.57963 2.03402 2.48612 + vertex 1.57805 2.03915 2.48551 + vertex 1.57552 2.03529 2.48653 + endloop + endfacet + facet normal 0.150301 0.246916 0.95731 + outer loop + vertex 1.57109 2.03087 2.48845 + vertex 1.57116 2.03473 2.48745 + vertex 1.56776 2.03231 2.48861 + endloop + endfacet + facet normal 0.162834 0.27708 0.946949 + outer loop + vertex 1.56821 2.02816 2.48974 + vertex 1.57109 2.03087 2.48845 + vertex 1.56776 2.03231 2.48861 + endloop + endfacet + facet normal 0.159069 0.276857 0.947654 + outer loop + vertex 1.56323 2.03198 2.48946 + vertex 1.56821 2.02816 2.48974 + vertex 1.56776 2.03231 2.48861 + endloop + endfacet + facet normal 0.161142 0.279479 0.946533 + outer loop + vertex 1.56351 2.02794 2.49061 + vertex 1.56821 2.02816 2.48974 + vertex 1.56323 2.03198 2.48946 + endloop + endfacet + facet normal 0.155571 0.279356 0.947501 + outer loop + vertex 1.55943 2.02933 2.49087 + vertex 1.56351 2.02794 2.49061 + vertex 1.56323 2.03198 2.48946 + endloop + endfacet + facet normal 0.155588 0.279334 0.947505 + outer loop + vertex 1.55766 2.03379 2.48984 + vertex 1.55943 2.02933 2.49087 + vertex 1.56323 2.03198 2.48946 + endloop + endfacet + facet normal 0.154512 0.275752 0.948729 + outer loop + vertex 1.56323 2.03198 2.48946 + vertex 1.56078 2.036 2.48869 + vertex 1.55766 2.03379 2.48984 + endloop + endfacet + facet normal 0.153739 0.276758 0.948562 + outer loop + vertex 1.55766 2.03379 2.48984 + vertex 1.56078 2.036 2.48869 + vertex 1.55759 2.03758 2.48875 + endloop + endfacet + facet normal 0.15284 0.276781 0.9487 + outer loop + vertex 1.55348 2.03727 2.4895 + vertex 1.55766 2.03379 2.48984 + vertex 1.55759 2.03758 2.48875 + endloop + endfacet + facet normal 0.152939 0.275997 0.948913 + outer loop + vertex 1.55759 2.03758 2.48875 + vertex 1.55576 2.04035 2.48824 + vertex 1.55348 2.03727 2.4895 + endloop + endfacet + facet normal 0.151411 0.277099 0.948836 + outer loop + vertex 1.55348 2.03727 2.4895 + vertex 1.55576 2.04035 2.48824 + vertex 1.55191 2.04185 2.48841 + endloop + endfacet + facet normal 0.149328 0.276505 0.94934 + outer loop + vertex 1.55348 2.03727 2.4895 + vertex 1.55191 2.04185 2.48841 + vertex 1.54802 2.03905 2.48984 + endloop + endfacet + facet normal 0.147899 0.27833 0.94903 + outer loop + vertex 1.54802 2.03905 2.48984 + vertex 1.55191 2.04185 2.48841 + vertex 1.54805 2.04314 2.48864 + endloop + endfacet + facet normal 0.14039 0.278694 0.950063 + outer loop + vertex 1.54364 2.04235 2.48952 + vertex 1.54802 2.03905 2.48984 + vertex 1.54805 2.04314 2.48864 + endloop + endfacet + facet normal 0.139584 0.282162 0.949158 + outer loop + vertex 1.54805 2.04314 2.48864 + vertex 1.5461 2.04572 2.48816 + vertex 1.54364 2.04235 2.48952 + endloop + endfacet + facet normal 0.134233 0.285926 0.948803 + outer loop + vertex 1.54364 2.04235 2.48952 + vertex 1.5461 2.04572 2.48816 + vertex 1.54215 2.04679 2.48839 + endloop + endfacet + facet normal 0.135055 0.289217 0.947689 + outer loop + vertex 1.5461 2.04572 2.48816 + vertex 1.54616 2.04967 2.48695 + vertex 1.54215 2.04679 2.48839 + endloop + endfacet + facet normal 0.132138 0.292909 0.946966 + outer loop + vertex 1.54215 2.04679 2.48839 + vertex 1.54616 2.04967 2.48695 + vertex 1.54104 2.05088 2.48728 + endloop + endfacet + facet normal 0.131497 0.292771 0.947098 + outer loop + vertex 1.54215 2.04679 2.48839 + vertex 1.54104 2.05088 2.48728 + vertex 1.53802 2.04813 2.48855 + endloop + endfacet + facet normal 0.130774 0.290455 0.94791 + outer loop + vertex 1.53792 2.04394 2.48985 + vertex 1.54215 2.04679 2.48839 + vertex 1.53802 2.04813 2.48855 + endloop + endfacet + facet normal 0.132811 0.290332 0.947665 + outer loop + vertex 1.53333 2.0473 2.48946 + vertex 1.53792 2.04394 2.48985 + vertex 1.53802 2.04813 2.48855 + endloop + endfacet + facet normal 0.131469 0.296143 0.946052 + outer loop + vertex 1.53802 2.04813 2.48855 + vertex 1.53574 2.05187 2.4877 + vertex 1.53333 2.0473 2.48946 + endloop + endfacet + facet normal 0.133029 0.295335 0.946087 + outer loop + vertex 1.53333 2.0473 2.48946 + vertex 1.53574 2.05187 2.4877 + vertex 1.53119 2.05112 2.48857 + endloop + endfacet + facet normal 0.137209 0.297394 0.944844 + outer loop + vertex 1.53333 2.0473 2.48946 + vertex 1.53119 2.05112 2.48857 + vertex 1.52771 2.04876 2.48982 + endloop + endfacet + facet normal 0.136032 0.292421 0.946565 + outer loop + vertex 1.52771 2.04876 2.48982 + vertex 1.52942 2.04431 2.49095 + vertex 1.53333 2.0473 2.48946 + endloop + endfacet + facet normal 0.137297 0.290908 0.946849 + outer loop + vertex 1.52942 2.04431 2.49095 + vertex 1.53342 2.04316 2.49072 + vertex 1.53333 2.0473 2.48946 + endloop + endfacet + facet normal 0.135886 0.285657 0.948649 + outer loop + vertex 1.53342 2.04316 2.49072 + vertex 1.52942 2.04431 2.49095 + vertex 1.53105 2.03977 2.49208 + endloop + endfacet + facet normal 0.135007 0.286253 0.948595 + outer loop + vertex 1.53546 2.04052 2.49123 + vertex 1.53342 2.04316 2.49072 + vertex 1.53105 2.03977 2.49208 + endloop + endfacet + facet normal 0.136331 0.280315 0.950178 + outer loop + vertex 1.53546 2.04052 2.49123 + vertex 1.53105 2.03977 2.49208 + vertex 1.53544 2.03645 2.49243 + endloop + endfacet + facet normal 0.133946 0.280415 0.950487 + outer loop + vertex 1.53546 2.04052 2.49123 + vertex 1.53544 2.03645 2.49243 + vertex 1.53952 2.03938 2.49099 + endloop + endfacet + facet normal 0.135235 0.285345 0.948836 + outer loop + vertex 1.53952 2.03938 2.49099 + vertex 1.53792 2.04394 2.48985 + vertex 1.53546 2.04052 2.49123 + endloop + endfacet + facet normal 0.135721 0.278158 0.950899 + outer loop + vertex 1.54109 2.03483 2.4921 + vertex 1.53952 2.03938 2.49099 + vertex 1.53544 2.03645 2.49243 + endloop + endfacet + facet normal 0.135152 0.276023 0.951601 + outer loop + vertex 1.53702 2.03194 2.49352 + vertex 1.54109 2.03483 2.4921 + vertex 1.53544 2.03645 2.49243 + endloop + endfacet + facet normal 0.13471 0.275892 0.951702 + outer loop + vertex 1.53702 2.03194 2.49352 + vertex 1.53544 2.03645 2.49243 + vertex 1.53301 2.03311 2.49374 + endloop + endfacet + facet normal 0.134973 0.276851 0.951386 + outer loop + vertex 1.53304 2.02915 2.49489 + vertex 1.53702 2.03194 2.49352 + vertex 1.53301 2.03311 2.49374 + endloop + endfacet + facet normal 0.134734 0.277164 0.951329 + outer loop + vertex 1.53866 2.02748 2.49458 + vertex 1.53702 2.03194 2.49352 + vertex 1.53304 2.02915 2.49489 + endloop + endfacet + facet normal 0.137313 0.277964 0.950727 + outer loop + vertex 1.53866 2.02748 2.49458 + vertex 1.54104 2.03075 2.49328 + vertex 1.53702 2.03194 2.49352 + endloop + endfacet + facet normal 0.140923 0.275414 0.950941 + outer loop + vertex 1.54304 2.02815 2.49374 + vertex 1.54104 2.03075 2.49328 + vertex 1.53866 2.02748 2.49458 + endloop + endfacet + facet normal 0.139937 0.280295 0.949659 + outer loop + vertex 1.53866 2.02748 2.49458 + vertex 1.54309 2.02418 2.4949 + vertex 1.54304 2.02815 2.49374 + endloop + endfacet + facet normal 0.143541 0.280192 0.949151 + outer loop + vertex 1.54309 2.02418 2.4949 + vertex 1.54705 2.02698 2.49348 + vertex 1.54304 2.02815 2.49374 + endloop + endfacet + facet normal 0.141798 0.273725 0.951298 + outer loop + vertex 1.54705 2.02698 2.49348 + vertex 1.54549 2.03152 2.49241 + vertex 1.54304 2.02815 2.49374 + endloop + endfacet + facet normal 0.144928 0.274628 0.950566 + outer loop + vertex 1.54705 2.02698 2.49348 + vertex 1.55109 2.02992 2.49202 + vertex 1.54549 2.03152 2.49241 + endloop + endfacet + facet normal 0.14476 0.273989 0.950776 + outer loop + vertex 1.55109 2.02992 2.49202 + vertex 1.54957 2.03449 2.49093 + vertex 1.54549 2.03152 2.49241 + endloop + endfacet + facet normal 0.145656 0.272854 0.950965 + outer loop + vertex 1.54557 2.03564 2.49121 + vertex 1.54549 2.03152 2.49241 + vertex 1.54957 2.03449 2.49093 + endloop + endfacet + facet normal 0.146569 0.276288 0.949833 + outer loop + vertex 1.54957 2.03449 2.49093 + vertex 1.54802 2.03905 2.48984 + vertex 1.54557 2.03564 2.49121 + endloop + endfacet + facet normal 0.143268 0.278592 0.949663 + outer loop + vertex 1.54358 2.03826 2.49074 + vertex 1.54557 2.03564 2.49121 + vertex 1.54802 2.03905 2.48984 + endloop + endfacet + facet normal 0.138923 0.275566 0.951191 + outer loop + vertex 1.54557 2.03564 2.49121 + vertex 1.54358 2.03826 2.49074 + vertex 1.54109 2.03483 2.4921 + endloop + endfacet + facet normal 0.149515 0.277117 0.949132 + outer loop + vertex 1.54802 2.03905 2.48984 + vertex 1.54957 2.03449 2.49093 + vertex 1.55348 2.03727 2.4895 + endloop + endfacet + facet normal 0.149684 0.276898 0.949169 + outer loop + vertex 1.54957 2.03449 2.49093 + vertex 1.5535 2.03329 2.49066 + vertex 1.55348 2.03727 2.4895 + endloop + endfacet + facet normal 0.139467 0.273215 0.951789 + outer loop + vertex 1.54557 2.03564 2.49121 + vertex 1.54109 2.03483 2.4921 + vertex 1.54549 2.03152 2.49241 + endloop + endfacet + facet normal 0.140297 0.274279 0.951361 + outer loop + vertex 1.54109 2.03483 2.4921 + vertex 1.54104 2.03075 2.49328 + vertex 1.54549 2.03152 2.49241 + endloop + endfacet + facet normal 0.149214 0.275228 0.949729 + outer loop + vertex 1.5535 2.03329 2.49066 + vertex 1.54957 2.03449 2.49093 + vertex 1.55109 2.02992 2.49202 + endloop + endfacet + facet normal 0.148839 0.275489 0.949712 + outer loop + vertex 1.55546 2.03064 2.49112 + vertex 1.5535 2.03329 2.49066 + vertex 1.55109 2.02992 2.49202 + endloop + endfacet + facet normal 0.14859 0.276627 0.94942 + outer loop + vertex 1.55546 2.03064 2.49112 + vertex 1.55109 2.02992 2.49202 + vertex 1.55547 2.02653 2.49232 + endloop + endfacet + facet normal 0.151811 0.276498 0.948948 + outer loop + vertex 1.55546 2.03064 2.49112 + vertex 1.55547 2.02653 2.49232 + vertex 1.55943 2.02933 2.49087 + endloop + endfacet + facet normal 0.151356 0.277089 0.948848 + outer loop + vertex 1.56114 2.02469 2.49195 + vertex 1.55943 2.02933 2.49087 + vertex 1.55547 2.02653 2.49232 + endloop + endfacet + facet normal 0.151123 0.276321 0.949109 + outer loop + vertex 1.55706 2.02193 2.4934 + vertex 1.56114 2.02469 2.49195 + vertex 1.55547 2.02653 2.49232 + endloop + endfacet + facet normal 0.1477 0.275331 0.949936 + outer loop + vertex 1.55706 2.02193 2.4934 + vertex 1.55547 2.02653 2.49232 + vertex 1.55304 2.02317 2.49367 + endloop + endfacet + facet normal 0.147324 0.274018 0.950373 + outer loop + vertex 1.55305 2.01912 2.49484 + vertex 1.55706 2.02193 2.4934 + vertex 1.55304 2.02317 2.49367 + endloop + endfacet + facet normal 0.146999 0.274031 0.95042 + outer loop + vertex 1.54867 2.02248 2.49455 + vertex 1.55305 2.01912 2.49484 + vertex 1.55304 2.02317 2.49367 + endloop + endfacet + facet normal 0.146677 0.275563 0.950027 + outer loop + vertex 1.55304 2.02317 2.49367 + vertex 1.55105 2.0258 2.49321 + vertex 1.54867 2.02248 2.49455 + endloop + endfacet + facet normal 0.145044 0.276699 0.949947 + outer loop + vertex 1.54867 2.02248 2.49455 + vertex 1.55105 2.0258 2.49321 + vertex 1.54705 2.02698 2.49348 + endloop + endfacet + facet normal 0.151072 0.279165 0.948285 + outer loop + vertex 1.54871 2.01846 2.49572 + vertex 1.55305 2.01912 2.49484 + vertex 1.54867 2.02248 2.49455 + endloop + endfacet + facet normal 0.154927 0.279033 0.947702 + outer loop + vertex 1.54474 2.01969 2.49601 + vertex 1.54871 2.01846 2.49572 + vertex 1.54867 2.02248 2.49455 + endloop + endfacet + facet normal 0.148827 0.2869 0.946329 + outer loop + vertex 1.54309 2.02418 2.4949 + vertex 1.54474 2.01969 2.49601 + vertex 1.54867 2.02248 2.49455 + endloop + endfacet + facet normal 0.155872 0.282358 0.946561 + outer loop + vertex 1.54871 2.01846 2.49572 + vertex 1.54474 2.01969 2.49601 + vertex 1.54623 2.01508 2.49714 + endloop + endfacet + facet normal 0.158308 0.280618 0.946674 + outer loop + vertex 1.55068 2.01582 2.49617 + vertex 1.54871 2.01846 2.49572 + vertex 1.54623 2.01508 2.49714 + endloop + endfacet + facet normal 0.15866 0.279039 0.947082 + outer loop + vertex 1.55068 2.01582 2.49617 + vertex 1.54623 2.01508 2.49714 + vertex 1.55054 2.01173 2.4974 + endloop + endfacet + facet normal 0.156964 0.279169 0.947326 + outer loop + vertex 1.55068 2.01582 2.49617 + vertex 1.55054 2.01173 2.4974 + vertex 1.55461 2.01458 2.49589 + endloop + endfacet + facet normal 0.155321 0.273544 0.949236 + outer loop + vertex 1.55461 2.01458 2.49589 + vertex 1.55305 2.01912 2.49484 + vertex 1.55068 2.01582 2.49617 + endloop + endfacet + facet normal 0.149201 0.271787 0.950721 + outer loop + vertex 1.55305 2.01912 2.49484 + vertex 1.55461 2.01458 2.49589 + vertex 1.55858 2.01735 2.49447 + endloop + endfacet + facet normal 0.153111 0.266621 0.951562 + outer loop + vertex 1.55461 2.01458 2.49589 + vertex 1.55853 2.01331 2.49561 + vertex 1.55858 2.01735 2.49447 + endloop + endfacet + facet normal 0.153497 0.2666 0.951506 + outer loop + vertex 1.55853 2.01331 2.49561 + vertex 1.56277 2.01388 2.49477 + vertex 1.55858 2.01735 2.49447 + endloop + endfacet + facet normal 0.152958 0.265972 0.951768 + outer loop + vertex 1.55858 2.01735 2.49447 + vertex 1.56277 2.01388 2.49477 + vertex 1.56288 2.01784 2.49365 + endloop + endfacet + facet normal 0.152298 0.270012 0.950736 + outer loop + vertex 1.56288 2.01784 2.49365 + vertex 1.5611 2.02058 2.49315 + vertex 1.55858 2.01735 2.49447 + endloop + endfacet + facet normal 0.149903 0.271829 0.950599 + outer loop + vertex 1.55858 2.01735 2.49447 + vertex 1.5611 2.02058 2.49315 + vertex 1.55706 2.02193 2.4934 + endloop + endfacet + facet normal 0.158027 0.27339 0.948834 + outer loop + vertex 1.56288 2.01784 2.49365 + vertex 1.56584 2.02089 2.49227 + vertex 1.5611 2.02058 2.49315 + endloop + endfacet + facet normal 0.157749 0.2758 0.948182 + outer loop + vertex 1.56114 2.02469 2.49195 + vertex 1.5611 2.02058 2.49315 + vertex 1.56584 2.02089 2.49227 + endloop + endfacet + facet normal 0.157018 0.274929 0.948556 + outer loop + vertex 1.56549 2.02521 2.49108 + vertex 1.56114 2.02469 2.49195 + vertex 1.56584 2.02089 2.49227 + endloop + endfacet + facet normal 0.160994 0.275056 0.947853 + outer loop + vertex 1.56549 2.02521 2.49108 + vertex 1.56584 2.02089 2.49227 + vertex 1.56864 2.02403 2.49089 + endloop + endfacet + facet normal 0.162405 0.279065 0.946439 + outer loop + vertex 1.56864 2.02403 2.49089 + vertex 1.56821 2.02816 2.48974 + vertex 1.56549 2.02521 2.49108 + endloop + endfacet + facet normal 0.161769 0.274392 0.947914 + outer loop + vertex 1.57057 2.02122 2.49137 + vertex 1.56864 2.02403 2.49089 + vertex 1.56584 2.02089 2.49227 + endloop + endfacet + facet normal 0.162058 0.27202 0.948547 + outer loop + vertex 1.57057 2.02122 2.49137 + vertex 1.56584 2.02089 2.49227 + vertex 1.57068 2.01688 2.4926 + endloop + endfacet + facet normal 0.161329 0.272037 0.948667 + outer loop + vertex 1.57057 2.02122 2.49137 + vertex 1.57068 2.01688 2.4926 + vertex 1.57464 2.01976 2.4911 + endloop + endfacet + facet normal 0.160989 0.272471 0.9486 + outer loop + vertex 1.57628 2.01515 2.49214 + vertex 1.57464 2.01976 2.4911 + vertex 1.57068 2.01688 2.4926 + endloop + endfacet + facet normal 0.159689 0.267861 0.950131 + outer loop + vertex 1.57292 2.01268 2.4934 + vertex 1.57628 2.01515 2.49214 + vertex 1.57068 2.01688 2.4926 + endloop + endfacet + facet normal 0.15965 0.267843 0.950143 + outer loop + vertex 1.57292 2.01268 2.4934 + vertex 1.57068 2.01688 2.4926 + vertex 1.56836 2.01216 2.49432 + endloop + endfacet + facet normal 0.160248 0.2642 0.951062 + outer loop + vertex 1.56836 2.01216 2.49432 + vertex 1.57316 2.00816 2.49462 + vertex 1.57292 2.01268 2.4934 + endloop + endfacet + facet normal 0.157918 0.264182 0.951457 + outer loop + vertex 1.57316 2.00816 2.49462 + vertex 1.57613 2.01118 2.49329 + vertex 1.57292 2.01268 2.4934 + endloop + endfacet + facet normal 0.15816 0.263954 0.95148 + outer loop + vertex 1.57788 2.00843 2.49376 + vertex 1.57613 2.01118 2.49329 + vertex 1.57316 2.00816 2.49462 + endloop + endfacet + facet normal 0.158574 0.260021 0.952493 + outer loop + vertex 1.57316 2.00816 2.49462 + vertex 1.5778 2.00429 2.4949 + vertex 1.57788 2.00843 2.49376 + endloop + endfacet + facet normal 0.157923 0.259262 0.952808 + outer loop + vertex 1.57344 2.00379 2.49576 + vertex 1.5778 2.00429 2.4949 + vertex 1.57316 2.00816 2.49462 + endloop + endfacet + facet normal 0.15817 0.257736 0.953181 + outer loop + vertex 1.57344 2.00379 2.49576 + vertex 1.57531 2.00098 2.49621 + vertex 1.5778 2.00429 2.4949 + endloop + endfacet + facet normal 0.154839 0.255691 0.954278 + outer loop + vertex 1.57531 2.00098 2.49621 + vertex 1.57344 2.00379 2.49576 + vertex 1.5706 2.00057 2.49709 + endloop + endfacet + facet normal 0.154728 0.256522 0.954073 + outer loop + vertex 1.57531 2.00098 2.49621 + vertex 1.5706 2.00057 2.49709 + vertex 1.57535 1.99674 2.49735 + endloop + endfacet + facet normal 0.158155 0.256407 0.953542 + outer loop + vertex 1.57531 2.00098 2.49621 + vertex 1.57535 1.99674 2.49735 + vertex 1.57943 1.99949 2.49593 + endloop + endfacet + facet normal 0.153992 0.255634 0.95443 + outer loop + vertex 1.5706 2.00057 2.49709 + vertex 1.57099 1.99605 2.49823 + vertex 1.57535 1.99674 2.49735 + endloop + endfacet + facet normal 0.153546 0.257798 0.95392 + outer loop + vertex 1.57302 1.99331 2.49865 + vertex 1.57535 1.99674 2.49735 + vertex 1.57099 1.99605 2.49823 + endloop + endfacet + facet normal 0.155228 0.258954 0.953335 + outer loop + vertex 1.57302 1.99331 2.49865 + vertex 1.57099 1.99605 2.49823 + vertex 1.56867 1.99259 2.49955 + endloop + endfacet + facet normal 0.15565 0.256994 0.953796 + outer loop + vertex 1.56867 1.99259 2.49955 + vertex 1.57299 1.98915 2.49977 + vertex 1.57302 1.99331 2.49865 + endloop + endfacet + facet normal 0.153715 0.257085 0.954085 + outer loop + vertex 1.57299 1.98915 2.49977 + vertex 1.577 1.99196 2.49837 + vertex 1.57302 1.99331 2.49865 + endloop + endfacet + facet normal 0.157121 0.258791 0.953069 + outer loop + vertex 1.56859 1.98848 2.50068 + vertex 1.57299 1.98915 2.49977 + vertex 1.56867 1.99259 2.49955 + endloop + endfacet + facet normal 0.169164 0.25804 0.951209 + outer loop + vertex 1.56459 1.98974 2.50105 + vertex 1.56859 1.98848 2.50068 + vertex 1.56867 1.99259 2.49955 + endloop + endfacet + facet normal 0.165533 0.262877 0.950523 + outer loop + vertex 1.5631 1.99443 2.50001 + vertex 1.56459 1.98974 2.50105 + vertex 1.56867 1.99259 2.49955 + endloop + endfacet + facet normal 0.165142 0.261583 0.950948 + outer loop + vertex 1.56867 1.99259 2.49955 + vertex 1.56716 1.99706 2.49858 + vertex 1.5631 1.99443 2.50001 + endloop + endfacet + facet normal 0.162153 0.265834 0.950283 + outer loop + vertex 1.5631 1.99443 2.50001 + vertex 1.56716 1.99706 2.49858 + vertex 1.5634 1.99842 2.49885 + endloop + endfacet + facet normal 0.174404 0.264398 0.948513 + outer loop + vertex 1.55846 1.99838 2.49976 + vertex 1.5631 1.99443 2.50001 + vertex 1.5634 1.99842 2.49885 + endloop + endfacet + facet normal 0.174499 0.262724 0.948961 + outer loop + vertex 1.5634 1.99842 2.49885 + vertex 1.56212 2.00186 2.49813 + vertex 1.55846 1.99838 2.49976 + endloop + endfacet + facet normal 0.168821 0.268425 0.948392 + outer loop + vertex 1.55846 1.99838 2.49976 + vertex 1.56212 2.00186 2.49813 + vertex 1.55813 2.00297 2.49852 + endloop + endfacet + facet normal 0.166725 0.259897 0.951134 + outer loop + vertex 1.56212 2.00186 2.49813 + vertex 1.56051 2.00645 2.49715 + vertex 1.55813 2.00297 2.49852 + endloop + endfacet + facet normal 0.165454 0.260761 0.95112 + outer loop + vertex 1.55813 2.00297 2.49852 + vertex 1.56051 2.00645 2.49715 + vertex 1.55605 2.00579 2.49811 + endloop + endfacet + facet normal 0.183288 0.272955 0.944405 + outer loop + vertex 1.55813 2.00297 2.49852 + vertex 1.55605 2.00579 2.49811 + vertex 1.55351 2.00235 2.4996 + endloop + endfacet + facet normal 0.164622 0.264896 0.950121 + outer loop + vertex 1.55613 2.00997 2.49693 + vertex 1.55605 2.00579 2.49811 + vertex 1.56051 2.00645 2.49715 + endloop + endfacet + facet normal 0.177743 0.264064 0.947986 + outer loop + vertex 1.55605 2.00579 2.49811 + vertex 1.55613 2.00997 2.49693 + vertex 1.55195 2.0071 2.49851 + endloop + endfacet + facet normal 0.167039 0.278452 0.945813 + outer loop + vertex 1.55195 2.0071 2.49851 + vertex 1.55613 2.00997 2.49693 + vertex 1.55054 2.01173 2.4974 + endloop + endfacet + facet normal 0.160405 0.258257 0.952666 + outer loop + vertex 1.5634 1.99842 2.49885 + vertex 1.56592 2.00047 2.49786 + vertex 1.56212 2.00186 2.49813 + endloop + endfacet + facet normal 0.158659 0.253182 0.95432 + outer loop + vertex 1.56592 2.00047 2.49786 + vertex 1.56608 2.00451 2.49677 + vertex 1.56212 2.00186 2.49813 + endloop + endfacet + facet normal 0.153577 0.253583 0.955044 + outer loop + vertex 1.56608 2.00451 2.49677 + vertex 1.56592 2.00047 2.49786 + vertex 1.5706 2.00057 2.49709 + endloop + endfacet + facet normal 0.154647 0.254771 0.954555 + outer loop + vertex 1.57035 2.00498 2.49595 + vertex 1.56608 2.00451 2.49677 + vertex 1.5706 2.00057 2.49709 + endloop + endfacet + facet normal 0.155897 0.254787 0.954348 + outer loop + vertex 1.57035 2.00498 2.49595 + vertex 1.5706 2.00057 2.49709 + vertex 1.57344 2.00379 2.49576 + endloop + endfacet + facet normal 0.157525 0.259254 0.952876 + outer loop + vertex 1.57344 2.00379 2.49576 + vertex 1.57316 2.00816 2.49462 + vertex 1.57035 2.00498 2.49595 + endloop + endfacet + facet normal 0.158392 0.258513 0.952934 + outer loop + vertex 1.56848 2.00784 2.49549 + vertex 1.57035 2.00498 2.49595 + vertex 1.57316 2.00816 2.49462 + endloop + endfacet + facet normal 0.158032 0.261626 0.952144 + outer loop + vertex 1.56848 2.00784 2.49549 + vertex 1.57316 2.00816 2.49462 + vertex 1.56836 2.01216 2.49432 + endloop + endfacet + facet normal 0.154435 0.256125 0.954227 + outer loop + vertex 1.57035 2.00498 2.49595 + vertex 1.56848 2.00784 2.49549 + vertex 1.56608 2.00451 2.49677 + endloop + endfacet + facet normal 0.153364 0.256899 0.954192 + outer loop + vertex 1.56716 1.99706 2.49858 + vertex 1.5706 2.00057 2.49709 + vertex 1.56592 2.00047 2.49786 + endloop + endfacet + facet normal 0.15983 0.258923 0.952583 + outer loop + vertex 1.56716 1.99706 2.49858 + vertex 1.56592 2.00047 2.49786 + vertex 1.5634 1.99842 2.49885 + endloop + endfacet + facet normal 0.170157 0.26153 0.950078 + outer loop + vertex 1.56859 1.98848 2.50068 + vertex 1.56459 1.98974 2.50105 + vertex 1.56608 1.98508 2.50206 + endloop + endfacet + facet normal 0.169337 0.262129 0.95006 + outer loop + vertex 1.57053 1.98579 2.50108 + vertex 1.56859 1.98848 2.50068 + vertex 1.56608 1.98508 2.50206 + endloop + endfacet + facet normal 0.171011 0.254216 0.951908 + outer loop + vertex 1.57053 1.98579 2.50108 + vertex 1.56608 1.98508 2.50206 + vertex 1.57046 1.98161 2.5022 + endloop + endfacet + facet normal 0.156158 0.255067 0.95423 + outer loop + vertex 1.57053 1.98579 2.50108 + vertex 1.57046 1.98161 2.5022 + vertex 1.57451 1.98446 2.50078 + endloop + endfacet + facet normal 0.156357 0.255706 0.954027 + outer loop + vertex 1.57451 1.98446 2.50078 + vertex 1.57299 1.98915 2.49977 + vertex 1.57053 1.98579 2.50108 + endloop + endfacet + facet normal 0.154077 0.255084 0.954564 + outer loop + vertex 1.57299 1.98915 2.49977 + vertex 1.57451 1.98446 2.50078 + vertex 1.57859 1.98717 2.4994 + endloop + endfacet + facet normal 0.154426 0.256139 0.954225 + outer loop + vertex 1.57859 1.98717 2.4994 + vertex 1.577 1.99196 2.49837 + vertex 1.57299 1.98915 2.49977 + endloop + endfacet + facet normal 0.157169 0.256907 0.953571 + outer loop + vertex 1.57859 1.98717 2.4994 + vertex 1.58106 1.99045 2.49811 + vertex 1.577 1.99196 2.49837 + endloop + endfacet + facet normal 0.158074 0.259491 0.952721 + outer loop + vertex 1.58106 1.99045 2.49811 + vertex 1.58108 1.99465 2.49696 + vertex 1.577 1.99196 2.49837 + endloop + endfacet + facet normal 0.158469 0.258936 0.952806 + outer loop + vertex 1.577 1.99196 2.49837 + vertex 1.58108 1.99465 2.49696 + vertex 1.57535 1.99674 2.49735 + endloop + endfacet + facet normal 0.159746 0.254997 0.953655 + outer loop + vertex 1.58293 1.98759 2.49856 + vertex 1.58106 1.99045 2.49811 + vertex 1.57859 1.98717 2.4994 + endloop + endfacet + facet normal 0.159987 0.253298 0.954067 + outer loop + vertex 1.57859 1.98717 2.4994 + vertex 1.58321 1.98322 2.49967 + vertex 1.58293 1.98759 2.49856 + endloop + endfacet + facet normal 0.160075 0.253299 0.954052 + outer loop + vertex 1.58321 1.98322 2.49967 + vertex 1.58605 1.98633 2.49837 + vertex 1.58293 1.98759 2.49856 + endloop + endfacet + facet normal 0.161456 0.256915 0.952852 + outer loop + vertex 1.58605 1.98633 2.49837 + vertex 1.58577 1.9907 2.49724 + vertex 1.58293 1.98759 2.49856 + endloop + endfacet + facet normal 0.15553 0.257305 0.953732 + outer loop + vertex 1.58793 1.9835 2.49882 + vertex 1.58605 1.98633 2.49837 + vertex 1.58321 1.98322 2.49967 + endloop + endfacet + facet normal 0.155808 0.254688 0.954389 + outer loop + vertex 1.58321 1.98322 2.49967 + vertex 1.5879 1.97928 2.49996 + vertex 1.58793 1.9835 2.49882 + endloop + endfacet + facet normal 0.15046 0.248502 0.956875 + outer loop + vertex 1.58348 1.9788 2.50078 + vertex 1.5879 1.97928 2.49996 + vertex 1.58321 1.98322 2.49967 + endloop + endfacet + facet normal 0.162162 0.248707 0.954907 + outer loop + vertex 1.58348 1.9788 2.50078 + vertex 1.58321 1.98322 2.49967 + vertex 1.58035 1.9801 2.50097 + endloop + endfacet + facet normal 0.160584 0.244693 0.95621 + outer loop + vertex 1.58035 1.9801 2.50097 + vertex 1.58056 1.97558 2.50209 + vertex 1.58348 1.9788 2.50078 + endloop + endfacet + facet normal 0.159119 0.245982 0.956125 + outer loop + vertex 1.58537 1.97588 2.50121 + vertex 1.58348 1.9788 2.50078 + vertex 1.58056 1.97558 2.50209 + endloop + endfacet + facet normal 0.158651 0.2504 0.955055 + outer loop + vertex 1.58537 1.97588 2.50121 + vertex 1.58056 1.97558 2.50209 + vertex 1.58539 1.97155 2.50235 + endloop + endfacet + facet normal 0.139766 0.251036 0.957834 + outer loop + vertex 1.58537 1.97588 2.50121 + vertex 1.58539 1.97155 2.50235 + vertex 1.58949 1.97441 2.501 + endloop + endfacet + facet normal 0.154312 0.24533 0.957079 + outer loop + vertex 1.58056 1.97558 2.50209 + vertex 1.58098 1.97088 2.50323 + vertex 1.58539 1.97155 2.50235 + endloop + endfacet + facet normal 0.156499 0.24467 0.956893 + outer loop + vertex 1.58035 1.9801 2.50097 + vertex 1.57603 1.97967 2.50179 + vertex 1.58056 1.97558 2.50209 + endloop + endfacet + facet normal 0.157271 0.245501 0.956554 + outer loop + vertex 1.57603 1.97967 2.50179 + vertex 1.5758 1.97559 2.50287 + vertex 1.58056 1.97558 2.50209 + endloop + endfacet + facet normal 0.157279 0.245272 0.956611 + outer loop + vertex 1.57706 1.97206 2.50357 + vertex 1.58056 1.97558 2.50209 + vertex 1.5758 1.97559 2.50287 + endloop + endfacet + facet normal 0.158346 0.245601 0.956351 + outer loop + vertex 1.57706 1.97206 2.50357 + vertex 1.5758 1.97559 2.50287 + vertex 1.57327 1.97354 2.50382 + endloop + endfacet + facet normal 0.15879 0.245081 0.95641 + outer loop + vertex 1.57327 1.97354 2.50382 + vertex 1.5758 1.97559 2.50287 + vertex 1.57202 1.97703 2.50313 + endloop + endfacet + facet normal 0.17144 0.24899 0.953212 + outer loop + vertex 1.57327 1.97354 2.50382 + vertex 1.57202 1.97703 2.50313 + vertex 1.56843 1.97355 2.50468 + endloop + endfacet + facet normal 0.171731 0.24219 0.95491 + outer loop + vertex 1.56843 1.97355 2.50468 + vertex 1.57301 1.96947 2.5049 + vertex 1.57327 1.97354 2.50382 + endloop + endfacet + facet normal 0.158887 0.245349 0.956326 + outer loop + vertex 1.5758 1.97559 2.50287 + vertex 1.57603 1.97967 2.50179 + vertex 1.57202 1.97703 2.50313 + endloop + endfacet + facet normal 0.157821 0.24686 0.956113 + outer loop + vertex 1.57202 1.97703 2.50313 + vertex 1.57603 1.97967 2.50179 + vertex 1.57046 1.98161 2.5022 + endloop + endfacet + facet normal 0.172696 0.251163 0.952414 + outer loop + vertex 1.57202 1.97703 2.50313 + vertex 1.57046 1.98161 2.5022 + vertex 1.56809 1.97812 2.50355 + endloop + endfacet + facet normal 0.156107 0.247411 0.956252 + outer loop + vertex 1.58035 1.9801 2.50097 + vertex 1.57852 1.98299 2.50052 + vertex 1.57603 1.97967 2.50179 + endloop + endfacet + facet normal 0.153318 0.249474 0.956167 + outer loop + vertex 1.57852 1.98299 2.50052 + vertex 1.57451 1.98446 2.50078 + vertex 1.57603 1.97967 2.50179 + endloop + endfacet + facet normal 0.160644 0.25006 0.954811 + outer loop + vertex 1.57852 1.98299 2.50052 + vertex 1.58035 1.9801 2.50097 + vertex 1.58321 1.98322 2.49967 + endloop + endfacet + facet normal 0.160306 0.253659 0.953918 + outer loop + vertex 1.57852 1.98299 2.50052 + vertex 1.58321 1.98322 2.49967 + vertex 1.57859 1.98717 2.4994 + endloop + endfacet + facet normal 0.15152 0.241426 0.958517 + outer loop + vertex 1.58348 1.9788 2.50078 + vertex 1.58537 1.97588 2.50121 + vertex 1.5879 1.97928 2.49996 + endloop + endfacet + facet normal 0.143607 0.249981 0.957542 + outer loop + vertex 1.58793 1.9835 2.49882 + vertex 1.59038 1.98696 2.49756 + vertex 1.58605 1.98633 2.49837 + endloop + endfacet + facet normal 0.162057 0.256385 0.952893 + outer loop + vertex 1.58293 1.98759 2.49856 + vertex 1.58577 1.9907 2.49724 + vertex 1.58106 1.99045 2.49811 + endloop + endfacet + facet normal 0.154877 0.253968 0.954732 + outer loop + vertex 1.57451 1.98446 2.50078 + vertex 1.57852 1.98299 2.50052 + vertex 1.57859 1.98717 2.4994 + endloop + endfacet + facet normal 0.159187 0.251049 0.954795 + outer loop + vertex 1.57603 1.97967 2.50179 + vertex 1.57451 1.98446 2.50078 + vertex 1.57046 1.98161 2.5022 + endloop + endfacet + facet normal 0.175041 0.259219 0.949824 + outer loop + vertex 1.56608 1.98508 2.50206 + vertex 1.56602 1.9809 2.50322 + vertex 1.57046 1.98161 2.5022 + endloop + endfacet + facet normal 0.177267 0.263413 0.948256 + outer loop + vertex 1.56608 1.98508 2.50206 + vertex 1.56459 1.98974 2.50105 + vertex 1.56042 1.98686 2.50263 + endloop + endfacet + facet normal 0.178513 0.267864 0.946775 + outer loop + vertex 1.56197 1.98213 2.50368 + vertex 1.56608 1.98508 2.50206 + vertex 1.56042 1.98686 2.50263 + endloop + endfacet + facet normal 0.157974 0.254538 0.954073 + outer loop + vertex 1.56859 1.98848 2.50068 + vertex 1.57053 1.98579 2.50108 + vertex 1.57299 1.98915 2.49977 + endloop + endfacet + facet normal 0.155427 0.258822 0.953338 + outer loop + vertex 1.56867 1.99259 2.49955 + vertex 1.57099 1.99605 2.49823 + vertex 1.56716 1.99706 2.49858 + endloop + endfacet + facet normal 0.153871 0.257578 0.953927 + outer loop + vertex 1.577 1.99196 2.49837 + vertex 1.57535 1.99674 2.49735 + vertex 1.57302 1.99331 2.49865 + endloop + endfacet + facet normal 0.154679 0.255664 0.954311 + outer loop + vertex 1.57099 1.99605 2.49823 + vertex 1.5706 2.00057 2.49709 + vertex 1.56716 1.99706 2.49858 + endloop + endfacet + facet normal 0.159442 0.264699 0.951059 + outer loop + vertex 1.57788 2.00843 2.49376 + vertex 1.58045 2.01166 2.49243 + vertex 1.57613 2.01118 2.49329 + endloop + endfacet + facet normal 0.158905 0.268 0.950224 + outer loop + vertex 1.57628 2.01515 2.49214 + vertex 1.57613 2.01118 2.49329 + vertex 1.58045 2.01166 2.49243 + endloop + endfacet + facet normal 0.158838 0.267922 0.950257 + outer loop + vertex 1.58051 2.01572 2.49128 + vertex 1.57628 2.01515 2.49214 + vertex 1.58045 2.01166 2.49243 + endloop + endfacet + facet normal 0.159855 0.267861 0.950104 + outer loop + vertex 1.58051 2.01572 2.49128 + vertex 1.58045 2.01166 2.49243 + vertex 1.5844 2.01448 2.49097 + endloop + endfacet + facet normal 0.158071 0.272065 0.949207 + outer loop + vertex 1.58051 2.01572 2.49128 + vertex 1.57859 2.0184 2.49083 + vertex 1.57628 2.01515 2.49214 + endloop + endfacet + facet normal 0.160989 0.263502 0.951131 + outer loop + vertex 1.58194 2.00701 2.49347 + vertex 1.58045 2.01166 2.49243 + vertex 1.57788 2.00843 2.49376 + endloop + endfacet + facet normal 0.16048 0.263366 0.951254 + outer loop + vertex 1.58194 2.00701 2.49347 + vertex 1.58598 2.00984 2.492 + vertex 1.58045 2.01166 2.49243 + endloop + endfacet + facet normal 0.162439 0.266443 0.950064 + outer loop + vertex 1.56836 2.01216 2.49432 + vertex 1.57068 2.01688 2.4926 + vertex 1.56611 2.01635 2.49353 + endloop + endfacet + facet normal 0.158421 0.264511 0.951281 + outer loop + vertex 1.56836 2.01216 2.49432 + vertex 1.56611 2.01635 2.49353 + vertex 1.56277 2.01388 2.49477 + endloop + endfacet + facet normal 0.15739 0.260839 0.952466 + outer loop + vertex 1.56277 2.01388 2.49477 + vertex 1.56445 2.00928 2.49575 + vertex 1.56836 2.01216 2.49432 + endloop + endfacet + facet normal 0.15611 0.26044 0.952786 + outer loop + vertex 1.56445 2.00928 2.49575 + vertex 1.56277 2.01388 2.49477 + vertex 1.56049 2.01062 2.49603 + endloop + endfacet + facet normal 0.155101 0.257241 0.953819 + outer loop + vertex 1.56049 2.01062 2.49603 + vertex 1.56051 2.00645 2.49715 + vertex 1.56445 2.00928 2.49575 + endloop + endfacet + facet normal 0.158229 0.257129 0.953335 + outer loop + vertex 1.56049 2.01062 2.49603 + vertex 1.55613 2.00997 2.49693 + vertex 1.56051 2.00645 2.49715 + endloop + endfacet + facet normal 0.159625 0.267943 0.950119 + outer loop + vertex 1.57613 2.01118 2.49329 + vertex 1.57628 2.01515 2.49214 + vertex 1.57292 2.01268 2.4934 + endloop + endfacet + facet normal 0.161593 0.271477 0.948782 + outer loop + vertex 1.56584 2.02089 2.49227 + vertex 1.56611 2.01635 2.49353 + vertex 1.57068 2.01688 2.4926 + endloop + endfacet + facet normal 0.16343 0.275433 0.947326 + outer loop + vertex 1.56864 2.02403 2.49089 + vertex 1.57057 2.02122 2.49137 + vertex 1.57298 2.02445 2.49002 + endloop + endfacet + facet normal 0.156611 0.277307 0.947931 + outer loop + vertex 1.56549 2.02521 2.49108 + vertex 1.56351 2.02794 2.49061 + vertex 1.56114 2.02469 2.49195 + endloop + endfacet + facet normal 0.160111 0.271461 0.949038 + outer loop + vertex 1.56611 2.01635 2.49353 + vertex 1.56584 2.02089 2.49227 + vertex 1.56288 2.01784 2.49365 + endloop + endfacet + facet normal 0.157509 0.265658 0.951113 + outer loop + vertex 1.56277 2.01388 2.49477 + vertex 1.56611 2.01635 2.49353 + vertex 1.56288 2.01784 2.49365 + endloop + endfacet + facet normal 0.154408 0.261613 0.952742 + outer loop + vertex 1.55853 2.01331 2.49561 + vertex 1.56049 2.01062 2.49603 + vertex 1.56277 2.01388 2.49477 + endloop + endfacet + facet normal 0.156997 0.263357 0.951838 + outer loop + vertex 1.56049 2.01062 2.49603 + vertex 1.55853 2.01331 2.49561 + vertex 1.55613 2.00997 2.49693 + endloop + endfacet + facet normal 0.152982 0.266192 0.951703 + outer loop + vertex 1.55853 2.01331 2.49561 + vertex 1.55461 2.01458 2.49589 + vertex 1.55613 2.00997 2.49693 + endloop + endfacet + facet normal 0.164431 0.269326 0.948908 + outer loop + vertex 1.55613 2.00997 2.49693 + vertex 1.55461 2.01458 2.49589 + vertex 1.55054 2.01173 2.4974 + endloop + endfacet + facet normal 0.161358 0.282398 0.945629 + outer loop + vertex 1.54623 2.01508 2.49714 + vertex 1.54596 2.01089 2.49843 + vertex 1.55054 2.01173 2.4974 + endloop + endfacet + facet normal 0.158874 0.283148 0.945826 + outer loop + vertex 1.54623 2.01508 2.49714 + vertex 1.54474 2.01969 2.49601 + vertex 1.54066 2.01669 2.49759 + endloop + endfacet + facet normal 0.150561 0.251441 0.956091 + outer loop + vertex 1.54173 2.01174 2.49873 + vertex 1.54623 2.01508 2.49714 + vertex 1.54066 2.01669 2.49759 + endloop + endfacet + facet normal 0.154051 0.289171 0.944801 + outer loop + vertex 1.54079 2.02092 2.49627 + vertex 1.54066 2.01669 2.49759 + vertex 1.54474 2.01969 2.49601 + endloop + endfacet + facet normal 0.153833 0.288418 0.945066 + outer loop + vertex 1.54474 2.01969 2.49601 + vertex 1.54309 2.02418 2.4949 + vertex 1.54079 2.02092 2.49627 + endloop + endfacet + facet normal 0.14565 0.294026 0.944635 + outer loop + vertex 1.53876 2.02354 2.49577 + vertex 1.54079 2.02092 2.49627 + vertex 1.54309 2.02418 2.4949 + endloop + endfacet + facet normal 0.146677 0.289 0.946026 + outer loop + vertex 1.53876 2.02354 2.49577 + vertex 1.54309 2.02418 2.4949 + vertex 1.53866 2.02748 2.49458 + endloop + endfacet + facet normal 0.146848 0.294871 0.944186 + outer loop + vertex 1.54079 2.02092 2.49627 + vertex 1.53876 2.02354 2.49577 + vertex 1.53637 2.02007 2.49723 + endloop + endfacet + facet normal 0.148165 0.289607 0.945608 + outer loop + vertex 1.54079 2.02092 2.49627 + vertex 1.53637 2.02007 2.49723 + vertex 1.54066 2.01669 2.49759 + endloop + endfacet + facet normal 0.1517 0.276093 0.949084 + outer loop + vertex 1.54871 2.01846 2.49572 + vertex 1.55068 2.01582 2.49617 + vertex 1.55305 2.01912 2.49484 + endloop + endfacet + facet normal 0.149152 0.271622 0.950776 + outer loop + vertex 1.55858 2.01735 2.49447 + vertex 1.55706 2.02193 2.4934 + vertex 1.55305 2.01912 2.49484 + endloop + endfacet + facet normal 0.147025 0.275805 0.949903 + outer loop + vertex 1.55304 2.02317 2.49367 + vertex 1.55547 2.02653 2.49232 + vertex 1.55105 2.0258 2.49321 + endloop + endfacet + facet normal 0.151257 0.276139 0.949141 + outer loop + vertex 1.5611 2.02058 2.49315 + vertex 1.56114 2.02469 2.49195 + vertex 1.55706 2.02193 2.4934 + endloop + endfacet + facet normal 0.147218 0.274915 0.950131 + outer loop + vertex 1.55109 2.02992 2.49202 + vertex 1.55105 2.0258 2.49321 + vertex 1.55547 2.02653 2.49232 + endloop + endfacet + facet normal 0.15262 0.278051 0.948364 + outer loop + vertex 1.5535 2.03329 2.49066 + vertex 1.55546 2.03064 2.49112 + vertex 1.55766 2.03379 2.48984 + endloop + endfacet + facet normal 0.144595 0.275051 0.950494 + outer loop + vertex 1.55105 2.0258 2.49321 + vertex 1.55109 2.02992 2.49202 + vertex 1.54705 2.02698 2.49348 + endloop + endfacet + facet normal 0.14601 0.276989 0.949715 + outer loop + vertex 1.54867 2.02248 2.49455 + vertex 1.54705 2.02698 2.49348 + vertex 1.54309 2.02418 2.4949 + endloop + endfacet + facet normal 0.140163 0.274876 0.951208 + outer loop + vertex 1.54304 2.02815 2.49374 + vertex 1.54549 2.03152 2.49241 + vertex 1.54104 2.03075 2.49328 + endloop + endfacet + facet normal 0.135765 0.275149 0.951767 + outer loop + vertex 1.53301 2.03311 2.49374 + vertex 1.53544 2.03645 2.49243 + vertex 1.53103 2.03571 2.49328 + endloop + endfacet + facet normal 0.134541 0.274291 0.952189 + outer loop + vertex 1.53301 2.03311 2.49374 + vertex 1.53103 2.03571 2.49328 + vertex 1.52862 2.03242 2.49456 + endloop + endfacet + facet normal 0.134009 0.276882 0.951514 + outer loop + vertex 1.52862 2.03242 2.49456 + vertex 1.53304 2.02915 2.49489 + vertex 1.53301 2.03311 2.49374 + endloop + endfacet + facet normal 0.133542 0.276277 0.951755 + outer loop + vertex 1.52864 2.02845 2.49571 + vertex 1.53304 2.02915 2.49489 + vertex 1.52862 2.03242 2.49456 + endloop + endfacet + facet normal 0.132336 0.276317 0.951912 + outer loop + vertex 1.52462 2.02958 2.49594 + vertex 1.52864 2.02845 2.49571 + vertex 1.52862 2.03242 2.49456 + endloop + endfacet + facet normal 0.136184 0.271321 0.952806 + outer loop + vertex 1.52306 2.03407 2.49489 + vertex 1.52462 2.02958 2.49594 + vertex 1.52862 2.03242 2.49456 + endloop + endfacet + facet normal 0.13657 0.272712 0.952353 + outer loop + vertex 1.52862 2.03242 2.49456 + vertex 1.52706 2.0369 2.4935 + vertex 1.52306 2.03407 2.49489 + endloop + endfacet + facet normal 0.139148 0.269355 0.952935 + outer loop + vertex 1.52306 2.03407 2.49489 + vertex 1.52706 2.0369 2.4935 + vertex 1.5231 2.03809 2.49375 + endloop + endfacet + facet normal 0.138402 0.269391 0.953034 + outer loop + vertex 1.51871 2.03739 2.49458 + vertex 1.52306 2.03407 2.49489 + vertex 1.5231 2.03809 2.49375 + endloop + endfacet + facet normal 0.137047 0.275846 0.951382 + outer loop + vertex 1.5231 2.03809 2.49375 + vertex 1.52112 2.04072 2.49327 + vertex 1.51871 2.03739 2.49458 + endloop + endfacet + facet normal 0.136209 0.276433 0.951332 + outer loop + vertex 1.51871 2.03739 2.49458 + vertex 1.52112 2.04072 2.49327 + vertex 1.51711 2.04192 2.4935 + endloop + endfacet + facet normal 0.136867 0.276628 0.951181 + outer loop + vertex 1.51871 2.03739 2.49458 + vertex 1.51711 2.04192 2.4935 + vertex 1.51309 2.03904 2.49491 + endloop + endfacet + facet normal 0.134429 0.267797 0.954051 + outer loop + vertex 1.51309 2.03904 2.49491 + vertex 1.51465 2.03451 2.49596 + vertex 1.51871 2.03739 2.49458 + endloop + endfacet + facet normal 0.136073 0.265652 0.954418 + outer loop + vertex 1.51465 2.03451 2.49596 + vertex 1.51865 2.03334 2.49572 + vertex 1.51871 2.03739 2.49458 + endloop + endfacet + facet normal 0.136592 0.267549 0.953814 + outer loop + vertex 1.51865 2.03334 2.49572 + vertex 1.51465 2.03451 2.49596 + vertex 1.51611 2.02995 2.49703 + endloop + endfacet + facet normal 0.137291 0.267043 0.953855 + outer loop + vertex 1.5206 2.03074 2.49617 + vertex 1.51865 2.03334 2.49572 + vertex 1.51611 2.02995 2.49703 + endloop + endfacet + facet normal 0.13351 0.283859 0.949526 + outer loop + vertex 1.5206 2.03074 2.49617 + vertex 1.51611 2.02995 2.49703 + vertex 1.52053 2.02661 2.49741 + endloop + endfacet + facet normal 0.134003 0.283831 0.949464 + outer loop + vertex 1.5206 2.03074 2.49617 + vertex 1.52053 2.02661 2.49741 + vertex 1.52462 2.02958 2.49594 + endloop + endfacet + facet normal 0.129272 0.289783 0.948322 + outer loop + vertex 1.52626 2.02503 2.49711 + vertex 1.52462 2.02958 2.49594 + vertex 1.52053 2.02661 2.49741 + endloop + endfacet + facet normal 0.133965 0.307946 0.941925 + outer loop + vertex 1.52215 2.02191 2.49872 + vertex 1.52626 2.02503 2.49711 + vertex 1.52053 2.02661 2.49741 + endloop + endfacet + facet normal 0.134504 0.308097 0.941799 + outer loop + vertex 1.52215 2.02191 2.49872 + vertex 1.52053 2.02661 2.49741 + vertex 1.51801 2.02309 2.49892 + endloop + endfacet + facet normal 0.130423 0.31087 0.941461 + outer loop + vertex 1.51801 2.02309 2.49892 + vertex 1.52053 2.02661 2.49741 + vertex 1.51596 2.02578 2.49832 + endloop + endfacet + facet normal 0.14478 0.320571 0.936094 + outer loop + vertex 1.51801 2.02309 2.49892 + vertex 1.51596 2.02578 2.49832 + vertex 1.51359 2.02231 2.49987 + endloop + endfacet + facet normal 0.143883 0.324265 0.93496 + outer loop + vertex 1.51359 2.02231 2.49987 + vertex 1.51816 2.01898 2.50032 + vertex 1.51801 2.02309 2.49892 + endloop + endfacet + facet normal 0.139501 0.318596 0.937569 + outer loop + vertex 1.51404 2.01837 2.50114 + vertex 1.51816 2.01898 2.50032 + vertex 1.51359 2.02231 2.49987 + endloop + endfacet + facet normal 0.116143 0.317096 0.941255 + outer loop + vertex 1.51021 2.01952 2.50123 + vertex 1.51404 2.01837 2.50114 + vertex 1.51359 2.02231 2.49987 + endloop + endfacet + facet normal 0.148804 0.273034 0.950426 + outer loop + vertex 1.51404 2.01837 2.50114 + vertex 1.51633 2.01608 2.50144 + vertex 1.51816 2.01898 2.50032 + endloop + endfacet + facet normal 0.136089 0.287115 0.94818 + outer loop + vertex 1.51611 2.02995 2.49703 + vertex 1.51596 2.02578 2.49832 + vertex 1.52053 2.02661 2.49741 + endloop + endfacet + facet normal 0.142199 0.286661 0.94742 + outer loop + vertex 1.51596 2.02578 2.49832 + vertex 1.51611 2.02995 2.49703 + vertex 1.51192 2.02696 2.49857 + endloop + endfacet + facet normal 0.150335 0.316931 0.936458 + outer loop + vertex 1.51359 2.02231 2.49987 + vertex 1.51596 2.02578 2.49832 + vertex 1.51192 2.02696 2.49857 + endloop + endfacet + facet normal 0.149162 0.316596 0.936759 + outer loop + vertex 1.51359 2.02231 2.49987 + vertex 1.51192 2.02696 2.49857 + vertex 1.50794 2.02401 2.5002 + endloop + endfacet + facet normal 0.147867 0.318164 0.936433 + outer loop + vertex 1.50794 2.02401 2.5002 + vertex 1.51192 2.02696 2.49857 + vertex 1.5079 2.02817 2.49879 + endloop + endfacet + facet normal 0.139599 0.288812 0.947154 + outer loop + vertex 1.51192 2.02696 2.49857 + vertex 1.5105 2.0316 2.49736 + vertex 1.5079 2.02817 2.49879 + endloop + endfacet + facet normal 0.132857 0.293708 0.946617 + outer loop + vertex 1.5079 2.02817 2.49879 + vertex 1.5105 2.0316 2.49736 + vertex 1.506 2.03086 2.49822 + endloop + endfacet + facet normal 0.151667 0.30563 0.939993 + outer loop + vertex 1.5079 2.02817 2.49879 + vertex 1.506 2.03086 2.49822 + vertex 1.50347 2.02744 2.49974 + endloop + endfacet + facet normal 0.135798 0.280117 0.950312 + outer loop + vertex 1.50616 2.03495 2.49699 + vertex 1.506 2.03086 2.49822 + vertex 1.5105 2.0316 2.49736 + endloop + endfacet + facet normal 0.125785 0.267693 0.955258 + outer loop + vertex 1.51065 2.0357 2.49619 + vertex 1.50616 2.03495 2.49699 + vertex 1.5105 2.0316 2.49736 + endloop + endfacet + facet normal 0.134208 0.267095 0.954279 + outer loop + vertex 1.51065 2.0357 2.49619 + vertex 1.5105 2.0316 2.49736 + vertex 1.51465 2.03451 2.49596 + endloop + endfacet + facet normal 0.125949 0.266918 0.955454 + outer loop + vertex 1.51065 2.0357 2.49619 + vertex 1.50865 2.03831 2.49573 + vertex 1.50616 2.03495 2.49699 + endloop + endfacet + facet normal 0.11876 0.272047 0.954928 + outer loop + vertex 1.50865 2.03831 2.49573 + vertex 1.50459 2.03945 2.49591 + vertex 1.50616 2.03495 2.49699 + endloop + endfacet + facet normal 0.120974 0.280396 0.952231 + outer loop + vertex 1.50459 2.03945 2.49591 + vertex 1.50865 2.03831 2.49573 + vertex 1.50865 2.04233 2.49454 + endloop + endfacet + facet normal 0.118603 0.283445 0.951626 + outer loop + vertex 1.50296 2.04389 2.49479 + vertex 1.50459 2.03945 2.49591 + vertex 1.50865 2.04233 2.49454 + endloop + endfacet + facet normal 0.120641 0.291276 0.949002 + outer loop + vertex 1.50865 2.04233 2.49454 + vertex 1.50711 2.04674 2.49338 + vertex 1.50296 2.04389 2.49479 + endloop + endfacet + facet normal 0.122882 0.291926 0.948514 + outer loop + vertex 1.50865 2.04233 2.49454 + vertex 1.51108 2.04566 2.49321 + vertex 1.50711 2.04674 2.49338 + endloop + endfacet + facet normal 0.124799 0.299335 0.945951 + outer loop + vertex 1.51108 2.04566 2.49321 + vertex 1.51113 2.0496 2.49195 + vertex 1.50711 2.04674 2.49338 + endloop + endfacet + facet normal 0.124153 0.300155 0.945777 + outer loop + vertex 1.50711 2.04674 2.49338 + vertex 1.51113 2.0496 2.49195 + vertex 1.506 2.05083 2.49223 + endloop + endfacet + facet normal 0.119964 0.29925 0.946603 + outer loop + vertex 1.50711 2.04674 2.49338 + vertex 1.506 2.05083 2.49223 + vertex 1.50302 2.04805 2.49349 + endloop + endfacet + facet normal 0.124094 0.29989 0.945868 + outer loop + vertex 1.51113 2.0496 2.49195 + vertex 1.50945 2.0539 2.49081 + vertex 1.506 2.05083 2.49223 + endloop + endfacet + facet normal 0.122467 0.301565 0.945548 + outer loop + vertex 1.50945 2.0539 2.49081 + vertex 1.50467 2.0549 2.49111 + vertex 1.506 2.05083 2.49223 + endloop + endfacet + facet normal 0.12222 0.300238 0.946002 + outer loop + vertex 1.50467 2.0549 2.49111 + vertex 1.50945 2.0539 2.49081 + vertex 1.50811 2.05797 2.48969 + endloop + endfacet + facet normal 0.127739 0.301718 0.944801 + outer loop + vertex 1.50811 2.05797 2.48969 + vertex 1.50945 2.0539 2.49081 + vertex 1.51334 2.05697 2.4893 + endloop + endfacet + facet normal 0.127276 0.29892 0.945752 + outer loop + vertex 1.51334 2.05697 2.4893 + vertex 1.51108 2.0607 2.48843 + vertex 1.50811 2.05797 2.48969 + endloop + endfacet + facet normal 0.126253 0.299947 0.945564 + outer loop + vertex 1.50811 2.05797 2.48969 + vertex 1.51108 2.0607 2.48843 + vertex 1.50702 2.06205 2.48854 + endloop + endfacet + facet normal 0.12164 0.298969 0.946478 + outer loop + vertex 1.50811 2.05797 2.48969 + vertex 1.50702 2.06205 2.48854 + vertex 1.503 2.05918 2.48996 + endloop + endfacet + facet normal 0.121881 0.298664 0.946544 + outer loop + vertex 1.503 2.05918 2.48996 + vertex 1.50702 2.06205 2.48854 + vertex 1.50309 2.06311 2.48871 + endloop + endfacet + facet normal 0.122125 0.299629 0.946207 + outer loop + vertex 1.50702 2.06205 2.48854 + vertex 1.50551 2.06644 2.48735 + vertex 1.50309 2.06311 2.48871 + endloop + endfacet + facet normal 0.120588 0.300693 0.946067 + outer loop + vertex 1.50309 2.06311 2.48871 + vertex 1.50551 2.06644 2.48735 + vertex 1.50112 2.06561 2.48817 + endloop + endfacet + facet normal 0.117493 0.298495 0.947152 + outer loop + vertex 1.50309 2.06311 2.48871 + vertex 1.50112 2.06561 2.48817 + vertex 1.49865 2.06227 2.48953 + endloop + endfacet + facet normal 0.120469 0.301185 0.945925 + outer loop + vertex 1.50115 2.06955 2.48691 + vertex 1.50112 2.06561 2.48817 + vertex 1.50551 2.06644 2.48735 + endloop + endfacet + facet normal 0.120296 0.300956 0.94602 + outer loop + vertex 1.50547 2.07043 2.48608 + vertex 1.50115 2.06955 2.48691 + vertex 1.50551 2.06644 2.48735 + endloop + endfacet + facet normal 0.124989 0.300832 0.945451 + outer loop + vertex 1.50547 2.07043 2.48608 + vertex 1.50551 2.06644 2.48735 + vertex 1.50947 2.06934 2.4859 + endloop + endfacet + facet normal 0.125817 0.304061 0.944308 + outer loop + vertex 1.50947 2.06934 2.4859 + vertex 1.50773 2.0737 2.48473 + vertex 1.50547 2.07043 2.48608 + endloop + endfacet + facet normal 0.128028 0.3048 0.943772 + outer loop + vertex 1.50773 2.0737 2.48473 + vertex 1.50947 2.06934 2.4859 + vertex 1.51335 2.07223 2.48444 + endloop + endfacet + facet normal 0.127954 0.304494 0.943881 + outer loop + vertex 1.51335 2.07223 2.48444 + vertex 1.5112 2.07608 2.48349 + vertex 1.50773 2.0737 2.48473 + endloop + endfacet + facet normal 0.130021 0.305502 0.943273 + outer loop + vertex 1.51335 2.07223 2.48444 + vertex 1.51579 2.07661 2.48268 + vertex 1.5112 2.07608 2.48349 + endloop + endfacet + facet normal 0.129631 0.307804 0.942578 + outer loop + vertex 1.51129 2.08003 2.48218 + vertex 1.5112 2.07608 2.48349 + vertex 1.51579 2.07661 2.48268 + endloop + endfacet + facet normal 0.128338 0.306206 0.943275 + outer loop + vertex 1.51566 2.08065 2.48139 + vertex 1.51129 2.08003 2.48218 + vertex 1.51579 2.07661 2.48268 + endloop + endfacet + facet normal 0.129776 0.306193 0.943082 + outer loop + vertex 1.51566 2.08065 2.48139 + vertex 1.51579 2.07661 2.48268 + vertex 1.51972 2.07947 2.48121 + endloop + endfacet + facet normal 0.129988 0.306963 0.942803 + outer loop + vertex 1.51972 2.07947 2.48121 + vertex 1.518 2.08396 2.47999 + vertex 1.51566 2.08065 2.48139 + endloop + endfacet + facet normal 0.128374 0.308054 0.942668 + outer loop + vertex 1.51354 2.08327 2.48082 + vertex 1.51566 2.08065 2.48139 + vertex 1.518 2.08396 2.47999 + endloop + endfacet + facet normal 0.128938 0.306631 0.943055 + outer loop + vertex 1.518 2.08396 2.47999 + vertex 1.51972 2.07947 2.48121 + vertex 1.5237 2.08233 2.47974 + endloop + endfacet + facet normal 0.130334 0.304877 0.943431 + outer loop + vertex 1.51972 2.07947 2.48121 + vertex 1.52373 2.07837 2.48102 + vertex 1.5237 2.08233 2.47974 + endloop + endfacet + facet normal 0.131338 0.304843 0.943303 + outer loop + vertex 1.52373 2.07837 2.48102 + vertex 1.52802 2.07924 2.48014 + vertex 1.5237 2.08233 2.47974 + endloop + endfacet + facet normal 0.130841 0.304185 0.943585 + outer loop + vertex 1.5237 2.08233 2.47974 + vertex 1.52802 2.07924 2.48014 + vertex 1.52809 2.08314 2.47887 + endloop + endfacet + facet normal 0.130295 0.306433 0.942933 + outer loop + vertex 1.52809 2.08314 2.47887 + vertex 1.52612 2.08563 2.47833 + vertex 1.5237 2.08233 2.47974 + endloop + endfacet + facet normal 0.129024 0.307317 0.94282 + outer loop + vertex 1.5237 2.08233 2.47974 + vertex 1.52612 2.08563 2.47833 + vertex 1.52214 2.08671 2.47853 + endloop + endfacet + facet normal 0.132336 0.307887 0.942174 + outer loop + vertex 1.52809 2.08314 2.47887 + vertex 1.53049 2.08646 2.47745 + vertex 1.52612 2.08563 2.47833 + endloop + endfacet + facet normal 0.133347 0.307193 0.942259 + outer loop + vertex 1.532 2.08209 2.47866 + vertex 1.53049 2.08646 2.47745 + vertex 1.52809 2.08314 2.47887 + endloop + endfacet + facet normal 0.133733 0.307302 0.942168 + outer loop + vertex 1.532 2.08209 2.47866 + vertex 1.53612 2.08489 2.47716 + vertex 1.53049 2.08646 2.47745 + endloop + endfacet + facet normal 0.13416 0.306739 0.942291 + outer loop + vertex 1.53606 2.08074 2.47852 + vertex 1.53612 2.08489 2.47716 + vertex 1.532 2.08209 2.47866 + endloop + endfacet + facet normal 0.133064 0.303325 0.943551 + outer loop + vertex 1.53309 2.07801 2.47982 + vertex 1.53606 2.08074 2.47852 + vertex 1.532 2.08209 2.47866 + endloop + endfacet + facet normal 0.133163 0.303345 0.94353 + outer loop + vertex 1.53309 2.07801 2.47982 + vertex 1.532 2.08209 2.47866 + vertex 1.52802 2.07924 2.48014 + endloop + endfacet + facet normal 0.132574 0.304086 0.943375 + outer loop + vertex 1.52802 2.07924 2.48014 + vertex 1.532 2.08209 2.47866 + vertex 1.52809 2.08314 2.47887 + endloop + endfacet + facet normal 0.131909 0.302657 0.943927 + outer loop + vertex 1.52373 2.07837 2.48102 + vertex 1.52573 2.07588 2.48153 + vertex 1.52802 2.07924 2.48014 + endloop + endfacet + facet normal 0.133691 0.301492 0.944049 + outer loop + vertex 1.52967 2.07496 2.48127 + vertex 1.52802 2.07924 2.48014 + vertex 1.52573 2.07588 2.48153 + endloop + endfacet + facet normal 0.132685 0.301168 0.944295 + outer loop + vertex 1.52802 2.07924 2.48014 + vertex 1.52967 2.07496 2.48127 + vertex 1.53309 2.07801 2.47982 + endloop + endfacet + facet normal 0.134183 0.299623 0.944575 + outer loop + vertex 1.52967 2.07496 2.48127 + vertex 1.53441 2.07393 2.48092 + vertex 1.53309 2.07801 2.47982 + endloop + endfacet + facet normal 0.133539 0.299454 0.944719 + outer loop + vertex 1.53309 2.07801 2.47982 + vertex 1.53441 2.07393 2.48092 + vertex 1.53831 2.077 2.4794 + endloop + endfacet + facet normal 0.134022 0.302364 0.943723 + outer loop + vertex 1.53831 2.077 2.4794 + vertex 1.53606 2.08074 2.47852 + vertex 1.53309 2.07801 2.47982 + endloop + endfacet + facet normal 0.133905 0.299029 0.944802 + outer loop + vertex 1.53441 2.07393 2.48092 + vertex 1.53836 2.073 2.48066 + vertex 1.53831 2.077 2.4794 + endloop + endfacet + facet normal 0.133531 0.297274 0.945409 + outer loop + vertex 1.53836 2.073 2.48066 + vertex 1.53441 2.07393 2.48092 + vertex 1.53609 2.06962 2.48204 + endloop + endfacet + facet normal 0.132569 0.297893 0.945349 + outer loop + vertex 1.54038 2.07049 2.48117 + vertex 1.53836 2.073 2.48066 + vertex 1.53609 2.06962 2.48204 + endloop + endfacet + facet normal 0.132463 0.298304 0.945235 + outer loop + vertex 1.54038 2.07049 2.48117 + vertex 1.53609 2.06962 2.48204 + vertex 1.54044 2.06648 2.48242 + endloop + endfacet + facet normal 0.132095 0.298314 0.945283 + outer loop + vertex 1.54038 2.07049 2.48117 + vertex 1.54044 2.06648 2.48242 + vertex 1.5444 2.06937 2.48096 + endloop + endfacet + facet normal 0.131757 0.298734 0.945198 + outer loop + vertex 1.54612 2.06486 2.48214 + vertex 1.5444 2.06937 2.48096 + vertex 1.54044 2.06648 2.48242 + endloop + endfacet + facet normal 0.132203 0.300404 0.944606 + outer loop + vertex 1.54199 2.06207 2.48361 + vertex 1.54612 2.06486 2.48214 + vertex 1.54044 2.06648 2.48242 + endloop + endfacet + facet normal 0.129642 0.299661 0.945196 + outer loop + vertex 1.54199 2.06207 2.48361 + vertex 1.54044 2.06648 2.48242 + vertex 1.53802 2.06315 2.48381 + endloop + endfacet + facet normal 0.129786 0.300228 0.944997 + outer loop + vertex 1.53797 2.05922 2.48507 + vertex 1.54199 2.06207 2.48361 + vertex 1.53802 2.06315 2.48381 + endloop + endfacet + facet normal 0.131578 0.300137 0.944778 + outer loop + vertex 1.53362 2.06234 2.48468 + vertex 1.53797 2.05922 2.48507 + vertex 1.53802 2.06315 2.48381 + endloop + endfacet + facet normal 0.131804 0.29919 0.945046 + outer loop + vertex 1.53802 2.06315 2.48381 + vertex 1.53605 2.06566 2.48329 + vertex 1.53362 2.06234 2.48468 + endloop + endfacet + facet normal 0.134161 0.29755 0.945233 + outer loop + vertex 1.53362 2.06234 2.48468 + vertex 1.53605 2.06566 2.48329 + vertex 1.53211 2.06676 2.4835 + endloop + endfacet + facet normal 0.134812 0.297733 0.945083 + outer loop + vertex 1.53362 2.06234 2.48468 + vertex 1.53211 2.06676 2.4835 + vertex 1.52799 2.06398 2.48497 + endloop + endfacet + facet normal 0.134673 0.297221 0.945263 + outer loop + vertex 1.52799 2.06398 2.48497 + vertex 1.52965 2.05947 2.48615 + vertex 1.53362 2.06234 2.48468 + endloop + endfacet + facet normal 0.134002 0.298065 0.945093 + outer loop + vertex 1.52965 2.05947 2.48615 + vertex 1.53364 2.05835 2.48594 + vertex 1.53362 2.06234 2.48468 + endloop + endfacet + facet normal 0.134292 0.299177 0.9447 + outer loop + vertex 1.53364 2.05835 2.48594 + vertex 1.52965 2.05947 2.48615 + vertex 1.53134 2.0551 2.48729 + endloop + endfacet + facet normal 0.131962 0.300757 0.944527 + outer loop + vertex 1.53567 2.05585 2.48645 + vertex 1.53364 2.05835 2.48594 + vertex 1.53134 2.0551 2.48729 + endloop + endfacet + facet normal 0.132344 0.299087 0.945004 + outer loop + vertex 1.53567 2.05585 2.48645 + vertex 1.53134 2.0551 2.48729 + vertex 1.53574 2.05187 2.4877 + endloop + endfacet + facet normal 0.128355 0.299182 0.945524 + outer loop + vertex 1.53567 2.05585 2.48645 + vertex 1.53574 2.05187 2.4877 + vertex 1.53968 2.05494 2.48619 + endloop + endfacet + facet normal 0.128539 0.300077 0.945215 + outer loop + vertex 1.53968 2.05494 2.48619 + vertex 1.53797 2.05922 2.48507 + vertex 1.53567 2.05585 2.48645 + endloop + endfacet + facet normal 0.128957 0.300217 0.945114 + outer loop + vertex 1.53797 2.05922 2.48507 + vertex 1.53968 2.05494 2.48619 + vertex 1.54313 2.05799 2.48475 + endloop + endfacet + facet normal 0.129596 0.299553 0.945237 + outer loop + vertex 1.53968 2.05494 2.48619 + vertex 1.5445 2.05394 2.48585 + vertex 1.54313 2.05799 2.48475 + endloop + endfacet + facet normal 0.133572 0.300653 0.944334 + outer loop + vertex 1.54313 2.05799 2.48475 + vertex 1.5445 2.05394 2.48585 + vertex 1.54834 2.05701 2.48433 + endloop + endfacet + facet normal 0.133422 0.299706 0.944656 + outer loop + vertex 1.54834 2.05701 2.48433 + vertex 1.5461 2.06071 2.48347 + vertex 1.54313 2.05799 2.48475 + endloop + endfacet + facet normal 0.131556 0.301586 0.944319 + outer loop + vertex 1.54313 2.05799 2.48475 + vertex 1.5461 2.06071 2.48347 + vertex 1.54199 2.06207 2.48361 + endloop + endfacet + facet normal 0.137117 0.301679 0.943498 + outer loop + vertex 1.54834 2.05701 2.48433 + vertex 1.5507 2.06153 2.48254 + vertex 1.5461 2.06071 2.48347 + endloop + endfacet + facet normal 0.137255 0.301092 0.943666 + outer loop + vertex 1.54612 2.06486 2.48214 + vertex 1.5461 2.06071 2.48347 + vertex 1.5507 2.06153 2.48254 + endloop + endfacet + facet normal 0.136051 0.299519 0.94434 + outer loop + vertex 1.55057 2.06556 2.48128 + vertex 1.54612 2.06486 2.48214 + vertex 1.5507 2.06153 2.48254 + endloop + endfacet + facet normal 0.142668 0.299429 0.943392 + outer loop + vertex 1.55057 2.06556 2.48128 + vertex 1.5507 2.06153 2.48254 + vertex 1.55456 2.06444 2.48103 + endloop + endfacet + facet normal 0.142293 0.297985 0.943905 + outer loop + vertex 1.55456 2.06444 2.48103 + vertex 1.55281 2.0688 2.47992 + vertex 1.55057 2.06556 2.48128 + endloop + endfacet + facet normal 0.146528 0.299398 0.94281 + outer loop + vertex 1.55281 2.0688 2.47992 + vertex 1.55456 2.06444 2.48103 + vertex 1.55839 2.06729 2.47953 + endloop + endfacet + facet normal 0.145468 0.295105 0.944326 + outer loop + vertex 1.55839 2.06729 2.47953 + vertex 1.55628 2.07112 2.47866 + vertex 1.55281 2.0688 2.47992 + endloop + endfacet + facet normal 0.147466 0.298252 0.943027 + outer loop + vertex 1.55456 2.06444 2.48103 + vertex 1.55844 2.06337 2.48076 + vertex 1.55839 2.06729 2.47953 + endloop + endfacet + facet normal 0.152275 0.2981 0.94231 + outer loop + vertex 1.55844 2.06337 2.48076 + vertex 1.56268 2.06407 2.47986 + vertex 1.55839 2.06729 2.47953 + endloop + endfacet + facet normal 0.152092 0.297867 0.942414 + outer loop + vertex 1.55839 2.06729 2.47953 + vertex 1.56268 2.06407 2.47986 + vertex 1.5629 2.06784 2.47863 + endloop + endfacet + facet normal 0.152402 0.296135 0.942909 + outer loop + vertex 1.5629 2.06784 2.47863 + vertex 1.56082 2.07166 2.47777 + vertex 1.55839 2.06729 2.47953 + endloop + endfacet + facet normal 0.155722 0.297707 0.941871 + outer loop + vertex 1.5629 2.06784 2.47863 + vertex 1.56637 2.07013 2.47733 + vertex 1.56082 2.07166 2.47777 + endloop + endfacet + facet normal 0.155207 0.295641 0.942607 + outer loop + vertex 1.56637 2.07013 2.47733 + vertex 1.56468 2.07455 2.47622 + vertex 1.56082 2.07166 2.47777 + endloop + endfacet + facet normal 0.157066 0.296226 0.942115 + outer loop + vertex 1.56863 2.07331 2.47596 + vertex 1.56468 2.07455 2.47622 + vertex 1.56637 2.07013 2.47733 + endloop + endfacet + facet normal 0.157243 0.296837 0.941893 + outer loop + vertex 1.56468 2.07455 2.47622 + vertex 1.56863 2.07331 2.47596 + vertex 1.5686 2.07731 2.4747 + endloop + endfacet + facet normal 0.155565 0.298997 0.941488 + outer loop + vertex 1.56299 2.07912 2.47505 + vertex 1.56468 2.07455 2.47622 + vertex 1.5686 2.07731 2.4747 + endloop + endfacet + facet normal 0.156244 0.296996 0.942009 + outer loop + vertex 1.56618 2.0663 2.47857 + vertex 1.56637 2.07013 2.47733 + vertex 1.5629 2.06784 2.47863 + endloop + endfacet + facet normal 0.151908 0.299737 0.94185 + outer loop + vertex 1.55844 2.06337 2.48076 + vertex 1.56034 2.06094 2.48123 + vertex 1.56268 2.06407 2.47986 + endloop + endfacet + facet normal 0.149488 0.298027 0.942779 + outer loop + vertex 1.56034 2.06094 2.48123 + vertex 1.55844 2.06337 2.48076 + vertex 1.55613 2.06021 2.48213 + endloop + endfacet + facet normal 0.147863 0.304977 0.940811 + outer loop + vertex 1.56034 2.06094 2.48123 + vertex 1.55613 2.06021 2.48213 + vertex 1.56037 2.05691 2.48253 + endloop + endfacet + facet normal 0.146714 0.30502 0.940977 + outer loop + vertex 1.56034 2.06094 2.48123 + vertex 1.56037 2.05691 2.48253 + vertex 1.56432 2.05992 2.48094 + endloop + endfacet + facet normal 0.143317 0.299448 0.943287 + outer loop + vertex 1.55613 2.06021 2.48213 + vertex 1.55584 2.05628 2.48342 + vertex 1.56037 2.05691 2.48253 + endloop + endfacet + facet normal 0.142879 0.301697 0.942637 + outer loop + vertex 1.55792 2.05224 2.4844 + vertex 1.56037 2.05691 2.48253 + vertex 1.55584 2.05628 2.48342 + endloop + endfacet + facet normal 0.142333 0.301454 0.942797 + outer loop + vertex 1.55792 2.05224 2.4844 + vertex 1.55584 2.05628 2.48342 + vertex 1.55248 2.05383 2.48471 + endloop + endfacet + facet normal 0.138828 0.288505 0.94736 + outer loop + vertex 1.55248 2.05383 2.48471 + vertex 1.55399 2.0493 2.48587 + vertex 1.55792 2.05224 2.4844 + endloop + endfacet + facet normal 0.136191 0.291723 0.946757 + outer loop + vertex 1.55399 2.0493 2.48587 + vertex 1.55795 2.04784 2.48575 + vertex 1.55792 2.05224 2.4844 + endloop + endfacet + facet normal -0.00239988 0.293601 0.955925 + outer loop + vertex 1.55795 2.04784 2.48575 + vertex 1.56356 2.04834 2.48561 + vertex 1.55792 2.05224 2.4844 + endloop + endfacet + facet normal 0.0986475 0.422471 0.900992 + outer loop + vertex 1.55792 2.05224 2.4844 + vertex 1.56356 2.04834 2.48561 + vertex 1.56279 2.05278 2.48361 + endloop + endfacet + facet normal -0.0802193 0.397426 0.914121 + outer loop + vertex 1.56356 2.04834 2.48561 + vertex 1.56728 2.05155 2.48454 + vertex 1.56279 2.05278 2.48361 + endloop + endfacet + facet normal -0.0647184 0.439965 0.89568 + outer loop + vertex 1.56728 2.05155 2.48454 + vertex 1.5667 2.05554 2.48254 + vertex 1.56279 2.05278 2.48361 + endloop + endfacet + facet normal 0.0607187 0.285551 0.956438 + outer loop + vertex 1.56279 2.05278 2.48361 + vertex 1.5667 2.05554 2.48254 + vertex 1.56037 2.05691 2.48253 + endloop + endfacet + facet normal -0.429928 0.691494 0.580515 + outer loop + vertex 1.57 2.05 2.4884 + vertex 1.56728 2.05155 2.48454 + vertex 1.56356 2.04834 2.48561 + endloop + endfacet + facet normal -0.439329 0.258159 0.860433 + outer loop + vertex 1.56356 2.04834 2.48561 + vertex 1.57 2.045 2.4899 + vertex 1.57 2.05 2.4884 + endloop + endfacet + facet normal -0.473192 0.192006 0.859781 + outer loop + vertex 1.56381 2.04385 2.48675 + vertex 1.57 2.045 2.4899 + vertex 1.56356 2.04834 2.48561 + endloop + endfacet + facet normal -0.0324875 0.243964 0.96924 + outer loop + vertex 1.56381 2.04385 2.48675 + vertex 1.56356 2.04834 2.48561 + vertex 1.55998 2.0449 2.48636 + endloop + endfacet + facet normal -0.0300976 0.251973 0.967266 + outer loop + vertex 1.55998 2.0449 2.48636 + vertex 1.56042 2.04046 2.48753 + vertex 1.56381 2.04385 2.48675 + endloop + endfacet + facet normal 0.0264584 0.198222 0.9798 + outer loop + vertex 1.56582 2.04101 2.48727 + vertex 1.56381 2.04385 2.48675 + vertex 1.56042 2.04046 2.48753 + endloop + endfacet + facet normal 0.0330695 0.137835 0.989903 + outer loop + vertex 1.56582 2.04101 2.48727 + vertex 1.56042 2.04046 2.48753 + vertex 1.56544 2.03645 2.48792 + endloop + endfacet + facet normal 0.0325275 0.137882 0.989914 + outer loop + vertex 1.56582 2.04101 2.48727 + vertex 1.56544 2.03645 2.48792 + vertex 1.56998 2.04 2.48727 + endloop + endfacet + facet normal -0.113483 -0.46168 0.879757 + outer loop + vertex 1.56998 2.04 2.48727 + vertex 1.57 2.045 2.4899 + vertex 1.56582 2.04101 2.48727 + endloop + endfacet + facet normal 0.122972 -0.461888 0.878372 + outer loop + vertex 1.57 2.045 2.4899 + vertex 1.56998 2.04 2.48727 + vertex 1.575 2.045 2.4892 + endloop + endfacet + facet normal 0.0188114 -0.375871 0.926481 + outer loop + vertex 1.56998 2.04 2.48727 + vertex 1.57367 2.03861 2.48664 + vertex 1.575 2.045 2.4892 + endloop + endfacet + facet normal 0.197843 0.0767394 0.977225 + outer loop + vertex 1.57367 2.03861 2.48664 + vertex 1.56998 2.04 2.48727 + vertex 1.57116 2.03473 2.48745 + endloop + endfacet + facet normal 0.0978962 0.0549263 0.99368 + outer loop + vertex 1.57116 2.03473 2.48745 + vertex 1.56998 2.04 2.48727 + vertex 1.56544 2.03645 2.48792 + endloop + endfacet + facet normal 0.133946 0.26089 0.956031 + outer loop + vertex 1.56042 2.04046 2.48753 + vertex 1.56078 2.036 2.48869 + vertex 1.56544 2.03645 2.48792 + endloop + endfacet + facet normal 0.127129 0.264366 0.956007 + outer loop + vertex 1.55998 2.0449 2.48636 + vertex 1.55563 2.04446 2.48706 + vertex 1.56042 2.04046 2.48753 + endloop + endfacet + facet normal 0.138664 0.277573 0.950645 + outer loop + vertex 1.55563 2.04446 2.48706 + vertex 1.55576 2.04035 2.48824 + vertex 1.56042 2.04046 2.48753 + endloop + endfacet + facet normal 0.151541 0.277446 0.948714 + outer loop + vertex 1.55576 2.04035 2.48824 + vertex 1.55563 2.04446 2.48706 + vertex 1.55191 2.04185 2.48841 + endloop + endfacet + facet normal 0.148608 0.281281 0.948049 + outer loop + vertex 1.55191 2.04185 2.48841 + vertex 1.55563 2.04446 2.48706 + vertex 1.55032 2.04645 2.4873 + endloop + endfacet + facet normal 0.148852 0.281351 0.94799 + outer loop + vertex 1.55191 2.04185 2.48841 + vertex 1.55032 2.04645 2.4873 + vertex 1.54805 2.04314 2.48864 + endloop + endfacet + facet normal 0.14918 0.282876 0.947484 + outer loop + vertex 1.55563 2.04446 2.48706 + vertex 1.55399 2.0493 2.48587 + vertex 1.55032 2.04645 2.4873 + endloop + endfacet + facet normal 0.147018 0.285441 0.947053 + outer loop + vertex 1.5503 2.05054 2.48607 + vertex 1.55032 2.04645 2.4873 + vertex 1.55399 2.0493 2.48587 + endloop + endfacet + facet normal 0.140126 0.285686 0.948023 + outer loop + vertex 1.5503 2.05054 2.48607 + vertex 1.54616 2.04967 2.48695 + vertex 1.55032 2.04645 2.4873 + endloop + endfacet + facet normal 0.124558 0.282263 0.951217 + outer loop + vertex 1.55998 2.0449 2.48636 + vertex 1.55795 2.04784 2.48575 + vertex 1.55563 2.04446 2.48706 + endloop + endfacet + facet normal -0.428309 -0.140309 0.892673 + outer loop + vertex 1.56381 2.04385 2.48675 + vertex 1.56582 2.04101 2.48727 + vertex 1.57 2.045 2.4899 + endloop + endfacet + facet normal -0.427279 0.693888 0.579614 + outer loop + vertex 1.57 2.05 2.4884 + vertex 1.575 2.055 2.4861 + vertex 1.56728 2.05155 2.48454 + endloop + endfacet + facet normal 0.00591255 0.206044 0.978525 + outer loop + vertex 1.55795 2.04784 2.48575 + vertex 1.55998 2.0449 2.48636 + vertex 1.56356 2.04834 2.48561 + endloop + endfacet + facet normal 0.131219 0.27784 0.951623 + outer loop + vertex 1.55795 2.04784 2.48575 + vertex 1.55399 2.0493 2.48587 + vertex 1.55563 2.04446 2.48706 + endloop + endfacet + facet normal 0.14885 0.291254 0.944995 + outer loop + vertex 1.55399 2.0493 2.48587 + vertex 1.55248 2.05383 2.48471 + vertex 1.5503 2.05054 2.48607 + endloop + endfacet + facet normal 0.145931 0.296977 0.943668 + outer loop + vertex 1.55248 2.05383 2.48471 + vertex 1.55584 2.05628 2.48342 + vertex 1.55272 2.05782 2.48342 + endloop + endfacet + facet normal 0.141 0.297468 0.944263 + outer loop + vertex 1.54834 2.05701 2.48433 + vertex 1.55248 2.05383 2.48471 + vertex 1.55272 2.05782 2.48342 + endloop + endfacet + facet normal 0.142547 0.299376 0.943427 + outer loop + vertex 1.5484 2.05306 2.48557 + vertex 1.55248 2.05383 2.48471 + vertex 1.54834 2.05701 2.48433 + endloop + endfacet + facet normal 0.143744 0.294548 0.944764 + outer loop + vertex 1.5484 2.05306 2.48557 + vertex 1.5503 2.05054 2.48607 + vertex 1.55248 2.05383 2.48471 + endloop + endfacet + facet normal 0.138681 0.291099 0.946588 + outer loop + vertex 1.5503 2.05054 2.48607 + vertex 1.5484 2.05306 2.48557 + vertex 1.54616 2.04967 2.48695 + endloop + endfacet + facet normal 0.133447 0.29445 0.946304 + outer loop + vertex 1.5484 2.05306 2.48557 + vertex 1.5445 2.05394 2.48585 + vertex 1.54616 2.04967 2.48695 + endloop + endfacet + facet normal 0.117219 0.31489 0.941862 + outer loop + vertex 1.56279 2.05278 2.48361 + vertex 1.56037 2.05691 2.48253 + vertex 1.55792 2.05224 2.4844 + endloop + endfacet + facet normal 0.146948 0.299042 0.942858 + outer loop + vertex 1.55584 2.05628 2.48342 + vertex 1.55613 2.06021 2.48213 + vertex 1.55272 2.05782 2.48342 + endloop + endfacet + facet normal 0.144645 0.302001 0.94227 + outer loop + vertex 1.55272 2.05782 2.48342 + vertex 1.55613 2.06021 2.48213 + vertex 1.5507 2.06153 2.48254 + endloop + endfacet + facet normal 0.147721 0.299272 0.942664 + outer loop + vertex 1.55844 2.06337 2.48076 + vertex 1.55456 2.06444 2.48103 + vertex 1.55613 2.06021 2.48213 + endloop + endfacet + facet normal 0.143799 0.298066 0.943652 + outer loop + vertex 1.55613 2.06021 2.48213 + vertex 1.55456 2.06444 2.48103 + vertex 1.5507 2.06153 2.48254 + endloop + endfacet + facet normal 0.136342 0.298156 0.944729 + outer loop + vertex 1.55057 2.06556 2.48128 + vertex 1.54847 2.06819 2.48075 + vertex 1.54612 2.06486 2.48214 + endloop + endfacet + facet normal 0.140392 0.299988 0.943556 + outer loop + vertex 1.55272 2.05782 2.48342 + vertex 1.5507 2.06153 2.48254 + vertex 1.54834 2.05701 2.48433 + endloop + endfacet + facet normal 0.134495 0.299599 0.944538 + outer loop + vertex 1.5445 2.05394 2.48585 + vertex 1.5484 2.05306 2.48557 + vertex 1.54834 2.05701 2.48433 + endloop + endfacet + facet normal 0.129207 0.297421 0.945963 + outer loop + vertex 1.5445 2.05394 2.48585 + vertex 1.53968 2.05494 2.48619 + vertex 1.54104 2.05088 2.48728 + endloop + endfacet + facet normal 0.129736 0.297567 0.945845 + outer loop + vertex 1.54104 2.05088 2.48728 + vertex 1.53968 2.05494 2.48619 + vertex 1.53574 2.05187 2.4877 + endloop + endfacet + facet normal 0.129857 0.299213 0.945309 + outer loop + vertex 1.53364 2.05835 2.48594 + vertex 1.53567 2.05585 2.48645 + vertex 1.53797 2.05922 2.48507 + endloop + endfacet + facet normal 0.136522 0.299899 0.944152 + outer loop + vertex 1.53134 2.0551 2.48729 + vertex 1.52965 2.05947 2.48615 + vertex 1.52574 2.05661 2.48762 + endloop + endfacet + facet normal 0.136245 0.29878 0.944546 + outer loop + vertex 1.52785 2.05274 2.48854 + vertex 1.53134 2.0551 2.48729 + vertex 1.52574 2.05661 2.48762 + endloop + endfacet + facet normal 0.138983 0.300083 0.943734 + outer loop + vertex 1.52785 2.05274 2.48854 + vertex 1.52574 2.05661 2.48762 + vertex 1.52329 2.05222 2.48938 + endloop + endfacet + facet normal 0.139275 0.298354 0.944239 + outer loop + vertex 1.52329 2.05222 2.48938 + vertex 1.52771 2.04876 2.48982 + vertex 1.52785 2.05274 2.48854 + endloop + endfacet + facet normal 0.139807 0.298998 0.943957 + outer loop + vertex 1.52341 2.04814 2.49065 + vertex 1.52771 2.04876 2.48982 + vertex 1.52329 2.05222 2.48938 + endloop + endfacet + facet normal 0.139382 0.299004 0.944018 + outer loop + vertex 1.51942 2.04933 2.49087 + vertex 1.52341 2.04814 2.49065 + vertex 1.52329 2.05222 2.48938 + endloop + endfacet + facet normal 0.138246 0.300389 0.943745 + outer loop + vertex 1.5177 2.05373 2.48972 + vertex 1.51942 2.04933 2.49087 + vertex 1.52329 2.05222 2.48938 + endloop + endfacet + facet normal 0.138136 0.299947 0.943902 + outer loop + vertex 1.52329 2.05222 2.48938 + vertex 1.52117 2.05609 2.48846 + vertex 1.5177 2.05373 2.48972 + endloop + endfacet + facet normal 0.137433 0.300876 0.943709 + outer loop + vertex 1.5177 2.05373 2.48972 + vertex 1.52117 2.05609 2.48846 + vertex 1.51784 2.05771 2.48843 + endloop + endfacet + facet normal 0.133493 0.301166 0.944181 + outer loop + vertex 1.51334 2.05697 2.4893 + vertex 1.5177 2.05373 2.48972 + vertex 1.51784 2.05771 2.48843 + endloop + endfacet + facet normal 0.133797 0.299784 0.944578 + outer loop + vertex 1.51784 2.05771 2.48843 + vertex 1.5157 2.0615 2.48753 + vertex 1.51334 2.05697 2.4893 + endloop + endfacet + facet normal 0.13671 0.301223 0.943703 + outer loop + vertex 1.51784 2.05771 2.48843 + vertex 1.5213 2.06005 2.48718 + vertex 1.5157 2.0615 2.48753 + endloop + endfacet + facet normal 0.136019 0.298303 0.94473 + outer loop + vertex 1.5213 2.06005 2.48718 + vertex 1.51955 2.06444 2.48605 + vertex 1.5157 2.0615 2.48753 + endloop + endfacet + facet normal 0.135557 0.298855 0.944622 + outer loop + vertex 1.51555 2.06558 2.48626 + vertex 1.5157 2.0615 2.48753 + vertex 1.51955 2.06444 2.48605 + endloop + endfacet + facet normal 0.13571 0.299431 0.944417 + outer loop + vertex 1.51955 2.06444 2.48605 + vertex 1.5178 2.06881 2.48491 + vertex 1.51555 2.06558 2.48626 + endloop + endfacet + facet normal 0.133157 0.30113 0.94424 + outer loop + vertex 1.51348 2.06818 2.48572 + vertex 1.51555 2.06558 2.48626 + vertex 1.5178 2.06881 2.48491 + endloop + endfacet + facet normal 0.132717 0.303318 0.943602 + outer loop + vertex 1.51348 2.06818 2.48572 + vertex 1.5178 2.06881 2.48491 + vertex 1.51335 2.07223 2.48444 + endloop + endfacet + facet normal 0.131565 0.301901 0.944217 + outer loop + vertex 1.51335 2.07223 2.48444 + vertex 1.5178 2.06881 2.48491 + vertex 1.51793 2.07277 2.48363 + endloop + endfacet + facet normal 0.133382 0.301773 0.944003 + outer loop + vertex 1.5178 2.06881 2.48491 + vertex 1.52127 2.07116 2.48367 + vertex 1.51793 2.07277 2.48363 + endloop + endfacet + facet normal 0.133598 0.302217 0.943831 + outer loop + vertex 1.52127 2.07116 2.48367 + vertex 1.52142 2.07513 2.48238 + vertex 1.51793 2.07277 2.48363 + endloop + endfacet + facet normal 0.131411 0.305125 0.943202 + outer loop + vertex 1.51793 2.07277 2.48363 + vertex 1.52142 2.07513 2.48238 + vertex 1.51579 2.07661 2.48268 + endloop + endfacet + facet normal 0.13431 0.302162 0.943747 + outer loop + vertex 1.52142 2.07513 2.48238 + vertex 1.52127 2.07116 2.48367 + vertex 1.52579 2.0719 2.48279 + endloop + endfacet + facet normal 0.132645 0.300026 0.944664 + outer loop + vertex 1.52573 2.07588 2.48153 + vertex 1.52142 2.07513 2.48238 + vertex 1.52579 2.0719 2.48279 + endloop + endfacet + facet normal 0.133379 0.300005 0.944567 + outer loop + vertex 1.52573 2.07588 2.48153 + vertex 1.52579 2.0719 2.48279 + vertex 1.52967 2.07496 2.48127 + endloop + endfacet + facet normal 0.134817 0.298339 0.94489 + outer loop + vertex 1.531 2.07088 2.48237 + vertex 1.52967 2.07496 2.48127 + vertex 1.52579 2.0719 2.48279 + endloop + endfacet + facet normal 0.134693 0.297602 0.945141 + outer loop + vertex 1.52804 2.06815 2.48365 + vertex 1.531 2.07088 2.48237 + vertex 1.52579 2.0719 2.48279 + endloop + endfacet + facet normal 0.135981 0.298284 0.944741 + outer loop + vertex 1.52804 2.06815 2.48365 + vertex 1.52579 2.0719 2.48279 + vertex 1.52342 2.06737 2.48456 + endloop + endfacet + facet normal 0.136302 0.296858 0.945144 + outer loop + vertex 1.52342 2.06737 2.48456 + vertex 1.52799 2.06398 2.48497 + vertex 1.52804 2.06815 2.48365 + endloop + endfacet + facet normal 0.136876 0.297595 0.944829 + outer loop + vertex 1.52356 2.06329 2.48583 + vertex 1.52799 2.06398 2.48497 + vertex 1.52342 2.06737 2.48456 + endloop + endfacet + facet normal 0.137084 0.297593 0.9448 + outer loop + vertex 1.51955 2.06444 2.48605 + vertex 1.52356 2.06329 2.48583 + vertex 1.52342 2.06737 2.48456 + endloop + endfacet + facet normal 0.136976 0.297121 0.944964 + outer loop + vertex 1.52356 2.06329 2.48583 + vertex 1.52563 2.06066 2.48635 + vertex 1.52799 2.06398 2.48497 + endloop + endfacet + facet normal 0.138367 0.298113 0.944449 + outer loop + vertex 1.52563 2.06066 2.48635 + vertex 1.52356 2.06329 2.48583 + vertex 1.5213 2.06005 2.48718 + endloop + endfacet + facet normal 0.138069 0.299639 0.944009 + outer loop + vertex 1.52563 2.06066 2.48635 + vertex 1.5213 2.06005 2.48718 + vertex 1.52574 2.05661 2.48762 + endloop + endfacet + facet normal 0.138692 0.300398 0.943677 + outer loop + vertex 1.5213 2.06005 2.48718 + vertex 1.52117 2.05609 2.48846 + vertex 1.52574 2.05661 2.48762 + endloop + endfacet + facet normal 0.13542 0.296873 0.945266 + outer loop + vertex 1.53211 2.06676 2.4835 + vertex 1.531 2.07088 2.48237 + vertex 1.52804 2.06815 2.48365 + endloop + endfacet + facet normal 0.134195 0.296613 0.945522 + outer loop + vertex 1.53211 2.06676 2.4835 + vertex 1.53609 2.06962 2.48204 + vertex 1.531 2.07088 2.48237 + endloop + endfacet + facet normal 0.132017 0.302736 0.943887 + outer loop + vertex 1.52573 2.07588 2.48153 + vertex 1.52373 2.07837 2.48102 + vertex 1.52142 2.07513 2.48238 + endloop + endfacet + facet normal 0.135056 0.29876 0.944723 + outer loop + vertex 1.52342 2.06737 2.48456 + vertex 1.52579 2.0719 2.48279 + vertex 1.52127 2.07116 2.48367 + endloop + endfacet + facet normal 0.135489 0.298974 0.944594 + outer loop + vertex 1.52342 2.06737 2.48456 + vertex 1.52127 2.07116 2.48367 + vertex 1.5178 2.06881 2.48491 + endloop + endfacet + facet normal 0.130668 0.299345 0.945155 + outer loop + vertex 1.51555 2.06558 2.48626 + vertex 1.51348 2.06818 2.48572 + vertex 1.51114 2.06485 2.4871 + endloop + endfacet + facet normal 0.128521 0.300786 0.944992 + outer loop + vertex 1.51348 2.06818 2.48572 + vertex 1.50947 2.06934 2.4859 + vertex 1.51114 2.06485 2.4871 + endloop + endfacet + facet normal 0.135587 0.299389 0.944448 + outer loop + vertex 1.5178 2.06881 2.48491 + vertex 1.51955 2.06444 2.48605 + vertex 1.52342 2.06737 2.48456 + endloop + endfacet + facet normal 0.130767 0.298891 0.945285 + outer loop + vertex 1.51555 2.06558 2.48626 + vertex 1.51114 2.06485 2.4871 + vertex 1.5157 2.0615 2.48753 + endloop + endfacet + facet normal 0.131563 0.299917 0.94485 + outer loop + vertex 1.51114 2.06485 2.4871 + vertex 1.51108 2.0607 2.48843 + vertex 1.5157 2.0615 2.48753 + endloop + endfacet + facet normal 0.137397 0.298763 0.944385 + outer loop + vertex 1.52356 2.06329 2.48583 + vertex 1.51955 2.06444 2.48605 + vertex 1.5213 2.06005 2.48718 + endloop + endfacet + facet normal 0.13406 0.301889 0.94387 + outer loop + vertex 1.51341 2.05298 2.49057 + vertex 1.5177 2.05373 2.48972 + vertex 1.51334 2.05697 2.4893 + endloop + endfacet + facet normal 0.134072 0.301833 0.943886 + outer loop + vertex 1.51341 2.05298 2.49057 + vertex 1.51543 2.05046 2.49109 + vertex 1.5177 2.05373 2.48972 + endloop + endfacet + facet normal 0.130172 0.299005 0.945331 + outer loop + vertex 1.51543 2.05046 2.49109 + vertex 1.51341 2.05298 2.49057 + vertex 1.51113 2.0496 2.49195 + endloop + endfacet + facet normal 0.130662 0.29709 0.945867 + outer loop + vertex 1.51543 2.05046 2.49109 + vertex 1.51113 2.0496 2.49195 + vertex 1.51548 2.04643 2.49234 + endloop + endfacet + facet normal 0.136099 0.296934 0.945149 + outer loop + vertex 1.51543 2.05046 2.49109 + vertex 1.51548 2.04643 2.49234 + vertex 1.51942 2.04933 2.49087 + endloop + endfacet + facet normal 0.137909 0.294699 0.945586 + outer loop + vertex 1.52109 2.0448 2.49204 + vertex 1.51942 2.04933 2.49087 + vertex 1.51548 2.04643 2.49234 + endloop + endfacet + facet normal 0.136903 0.291004 0.946876 + outer loop + vertex 1.51711 2.04192 2.4935 + vertex 1.52109 2.0448 2.49204 + vertex 1.51548 2.04643 2.49234 + endloop + endfacet + facet normal 0.137194 0.291091 0.946807 + outer loop + vertex 1.51711 2.04192 2.4935 + vertex 1.51548 2.04643 2.49234 + vertex 1.51308 2.04309 2.49372 + endloop + endfacet + facet normal 0.133294 0.293776 0.946535 + outer loop + vertex 1.51308 2.04309 2.49372 + vertex 1.51548 2.04643 2.49234 + vertex 1.51108 2.04566 2.49321 + endloop + endfacet + facet normal 0.137251 0.300504 0.943854 + outer loop + vertex 1.52117 2.05609 2.48846 + vertex 1.5213 2.06005 2.48718 + vertex 1.51784 2.05771 2.48843 + endloop + endfacet + facet normal 0.136896 0.299951 0.944081 + outer loop + vertex 1.51942 2.04933 2.49087 + vertex 1.5177 2.05373 2.48972 + vertex 1.51543 2.05046 2.49109 + endloop + endfacet + facet normal 0.138203 0.29479 0.945515 + outer loop + vertex 1.52341 2.04814 2.49065 + vertex 1.51942 2.04933 2.49087 + vertex 1.52109 2.0448 2.49204 + endloop + endfacet + facet normal 0.139688 0.293795 0.945606 + outer loop + vertex 1.52545 2.04549 2.49118 + vertex 1.52341 2.04814 2.49065 + vertex 1.52109 2.0448 2.49204 + endloop + endfacet + facet normal 0.14086 0.288335 0.947112 + outer loop + vertex 1.52545 2.04549 2.49118 + vertex 1.52109 2.0448 2.49204 + vertex 1.52549 2.04144 2.4924 + endloop + endfacet + facet normal 0.139693 0.288372 0.947274 + outer loop + vertex 1.52545 2.04549 2.49118 + vertex 1.52549 2.04144 2.4924 + vertex 1.52942 2.04431 2.49095 + endloop + endfacet + facet normal 0.140455 0.287828 0.947326 + outer loop + vertex 1.52109 2.0448 2.49204 + vertex 1.52112 2.04072 2.49327 + vertex 1.52549 2.04144 2.4924 + endloop + endfacet + facet normal 0.140701 0.294501 0.945237 + outer loop + vertex 1.52341 2.04814 2.49065 + vertex 1.52545 2.04549 2.49118 + vertex 1.52771 2.04876 2.48982 + endloop + endfacet + facet normal 0.138721 0.300226 0.943727 + outer loop + vertex 1.52329 2.05222 2.48938 + vertex 1.52574 2.05661 2.48762 + vertex 1.52117 2.05609 2.48846 + endloop + endfacet + facet normal 0.136351 0.298638 0.944576 + outer loop + vertex 1.53119 2.05112 2.48857 + vertex 1.53134 2.0551 2.48729 + vertex 1.52785 2.05274 2.48854 + endloop + endfacet + facet normal 0.136713 0.299663 0.944199 + outer loop + vertex 1.52563 2.06066 2.48635 + vertex 1.52574 2.05661 2.48762 + vertex 1.52965 2.05947 2.48615 + endloop + endfacet + facet normal 0.136162 0.297676 0.944907 + outer loop + vertex 1.52965 2.05947 2.48615 + vertex 1.52799 2.06398 2.48497 + vertex 1.52563 2.06066 2.48635 + endloop + endfacet + facet normal 0.13543 0.296905 0.945254 + outer loop + vertex 1.52799 2.06398 2.48497 + vertex 1.53211 2.06676 2.4835 + vertex 1.52804 2.06815 2.48365 + endloop + endfacet + facet normal 0.133986 0.296876 0.945469 + outer loop + vertex 1.53605 2.06566 2.48329 + vertex 1.53609 2.06962 2.48204 + vertex 1.53211 2.06676 2.4835 + endloop + endfacet + facet normal 0.130116 0.298203 0.945592 + outer loop + vertex 1.53364 2.05835 2.48594 + vertex 1.53797 2.05922 2.48507 + vertex 1.53362 2.06234 2.48468 + endloop + endfacet + facet normal 0.129139 0.301051 0.944824 + outer loop + vertex 1.54313 2.05799 2.48475 + vertex 1.54199 2.06207 2.48361 + vertex 1.53797 2.05922 2.48507 + endloop + endfacet + facet normal 0.131072 0.298672 0.945312 + outer loop + vertex 1.53802 2.06315 2.48381 + vertex 1.54044 2.06648 2.48242 + vertex 1.53605 2.06566 2.48329 + endloop + endfacet + facet normal 0.131484 0.301362 0.944401 + outer loop + vertex 1.5461 2.06071 2.48347 + vertex 1.54612 2.06486 2.48214 + vertex 1.54199 2.06207 2.48361 + endloop + endfacet + facet normal 0.131474 0.297002 0.945782 + outer loop + vertex 1.53609 2.06962 2.48204 + vertex 1.53605 2.06566 2.48329 + vertex 1.54044 2.06648 2.48242 + endloop + endfacet + facet normal 0.132725 0.298007 0.945291 + outer loop + vertex 1.53836 2.073 2.48066 + vertex 1.54038 2.07049 2.48117 + vertex 1.54268 2.07377 2.47981 + endloop + endfacet + facet normal 0.134409 0.29756 0.945194 + outer loop + vertex 1.53609 2.06962 2.48204 + vertex 1.53441 2.07393 2.48092 + vertex 1.531 2.07088 2.48237 + endloop + endfacet + facet normal 0.13389 0.298094 0.9451 + outer loop + vertex 1.53441 2.07393 2.48092 + vertex 1.52967 2.07496 2.48127 + vertex 1.531 2.07088 2.48237 + endloop + endfacet + facet normal 0.130115 0.304027 0.943736 + outer loop + vertex 1.52373 2.07837 2.48102 + vertex 1.51972 2.07947 2.48121 + vertex 1.52142 2.07513 2.48238 + endloop + endfacet + facet normal 0.131231 0.304393 0.943464 + outer loop + vertex 1.52142 2.07513 2.48238 + vertex 1.51972 2.07947 2.48121 + vertex 1.51579 2.07661 2.48268 + endloop + endfacet + facet normal 0.128024 0.307799 0.942799 + outer loop + vertex 1.51566 2.08065 2.48139 + vertex 1.51354 2.08327 2.48082 + vertex 1.51129 2.08003 2.48218 + endloop + endfacet + facet normal 0.131044 0.304948 0.94331 + outer loop + vertex 1.51793 2.07277 2.48363 + vertex 1.51579 2.07661 2.48268 + vertex 1.51335 2.07223 2.48444 + endloop + endfacet + facet normal 0.129218 0.303355 0.944076 + outer loop + vertex 1.50947 2.06934 2.4859 + vertex 1.51348 2.06818 2.48572 + vertex 1.51335 2.07223 2.48444 + endloop + endfacet + facet normal 0.125729 0.299919 0.945643 + outer loop + vertex 1.51114 2.06485 2.4871 + vertex 1.50947 2.06934 2.4859 + vertex 1.50551 2.06644 2.48735 + endloop + endfacet + facet normal 0.119783 0.30295 0.945449 + outer loop + vertex 1.50547 2.07043 2.48608 + vertex 1.50341 2.07293 2.48554 + vertex 1.50115 2.06955 2.48691 + endloop + endfacet + facet normal 0.12594 0.300709 0.945364 + outer loop + vertex 1.50702 2.06205 2.48854 + vertex 1.51114 2.06485 2.4871 + vertex 1.50551 2.06644 2.48735 + endloop + endfacet + facet normal 0.126332 0.30019 0.945477 + outer loop + vertex 1.51108 2.0607 2.48843 + vertex 1.51114 2.06485 2.4871 + vertex 1.50702 2.06205 2.48854 + endloop + endfacet + facet normal 0.131299 0.301063 0.944522 + outer loop + vertex 1.51334 2.05697 2.4893 + vertex 1.5157 2.0615 2.48753 + vertex 1.51108 2.0607 2.48843 + endloop + endfacet + facet normal 0.127456 0.302044 0.944735 + outer loop + vertex 1.50945 2.0539 2.49081 + vertex 1.51341 2.05298 2.49057 + vertex 1.51334 2.05697 2.4893 + endloop + endfacet + facet normal 0.127218 0.300915 0.945127 + outer loop + vertex 1.51341 2.05298 2.49057 + vertex 1.50945 2.0539 2.49081 + vertex 1.51113 2.0496 2.49195 + endloop + endfacet + facet normal 0.132097 0.298962 0.945078 + outer loop + vertex 1.51113 2.0496 2.49195 + vertex 1.51108 2.04566 2.49321 + vertex 1.51548 2.04643 2.49234 + endloop + endfacet + facet normal 0.126817 0.289183 0.948836 + outer loop + vertex 1.51308 2.04309 2.49372 + vertex 1.51108 2.04566 2.49321 + vertex 1.50865 2.04233 2.49454 + endloop + endfacet + facet normal 0.128793 0.280237 0.951252 + outer loop + vertex 1.50865 2.04233 2.49454 + vertex 1.51309 2.03904 2.49491 + vertex 1.51308 2.04309 2.49372 + endloop + endfacet + facet normal 0.128713 0.280133 0.951293 + outer loop + vertex 1.50865 2.03831 2.49573 + vertex 1.51309 2.03904 2.49491 + vertex 1.50865 2.04233 2.49454 + endloop + endfacet + facet normal 0.130795 0.270338 0.95384 + outer loop + vertex 1.50865 2.03831 2.49573 + vertex 1.51065 2.0357 2.49619 + vertex 1.51309 2.03904 2.49491 + endloop + endfacet + facet normal 0.130431 0.280522 0.950944 + outer loop + vertex 1.506 2.03086 2.49822 + vertex 1.50616 2.03495 2.49699 + vertex 1.50199 2.03203 2.49843 + endloop + endfacet + facet normal 0.122708 0.290579 0.94895 + outer loop + vertex 1.50199 2.03203 2.49843 + vertex 1.50616 2.03495 2.49699 + vertex 1.50052 2.0365 2.49725 + endloop + endfacet + facet normal 0.140368 0.289003 0.946982 + outer loop + vertex 1.51192 2.02696 2.49857 + vertex 1.51611 2.02995 2.49703 + vertex 1.5105 2.0316 2.49736 + endloop + endfacet + facet normal 0.135455 0.265772 0.954472 + outer loop + vertex 1.51865 2.03334 2.49572 + vertex 1.5206 2.03074 2.49617 + vertex 1.52306 2.03407 2.49489 + endloop + endfacet + facet normal 0.134328 0.266938 0.954306 + outer loop + vertex 1.51611 2.02995 2.49703 + vertex 1.51465 2.03451 2.49596 + vertex 1.5105 2.0316 2.49736 + endloop + endfacet + facet normal 0.134401 0.267789 0.954057 + outer loop + vertex 1.51465 2.03451 2.49596 + vertex 1.51309 2.03904 2.49491 + vertex 1.51065 2.0357 2.49619 + endloop + endfacet + facet normal 0.134202 0.280048 0.950559 + outer loop + vertex 1.51309 2.03904 2.49491 + vertex 1.51711 2.04192 2.4935 + vertex 1.51308 2.04309 2.49372 + endloop + endfacet + facet normal 0.139391 0.287865 0.947472 + outer loop + vertex 1.52112 2.04072 2.49327 + vertex 1.52109 2.0448 2.49204 + vertex 1.51711 2.04192 2.4935 + endloop + endfacet + facet normal 0.142265 0.27945 0.949562 + outer loop + vertex 1.5231 2.03809 2.49375 + vertex 1.52549 2.04144 2.4924 + vertex 1.52112 2.04072 2.49327 + endloop + endfacet + facet normal 0.135474 0.265683 0.954494 + outer loop + vertex 1.51865 2.03334 2.49572 + vertex 1.52306 2.03407 2.49489 + vertex 1.51871 2.03739 2.49458 + endloop + endfacet + facet normal 0.142029 0.279613 0.949549 + outer loop + vertex 1.52706 2.0369 2.4935 + vertex 1.52549 2.04144 2.4924 + vertex 1.5231 2.03809 2.49375 + endloop + endfacet + facet normal 0.138303 0.278531 0.950417 + outer loop + vertex 1.52706 2.0369 2.4935 + vertex 1.53105 2.03977 2.49208 + vertex 1.52549 2.04144 2.4924 + endloop + endfacet + facet normal 0.138331 0.278496 0.950423 + outer loop + vertex 1.53103 2.03571 2.49328 + vertex 1.53105 2.03977 2.49208 + vertex 1.52706 2.0369 2.4935 + endloop + endfacet + facet normal 0.130168 0.269545 0.95415 + outer loop + vertex 1.52462 2.02958 2.49594 + vertex 1.52306 2.03407 2.49489 + vertex 1.5206 2.03074 2.49617 + endloop + endfacet + facet normal 0.136446 0.291946 0.946652 + outer loop + vertex 1.52864 2.02845 2.49571 + vertex 1.52462 2.02958 2.49594 + vertex 1.52626 2.02503 2.49711 + endloop + endfacet + facet normal 0.135849 0.292345 0.946615 + outer loop + vertex 1.5307 2.02586 2.49622 + vertex 1.52864 2.02845 2.49571 + vertex 1.52626 2.02503 2.49711 + endloop + endfacet + facet normal 0.134867 0.296377 0.945501 + outer loop + vertex 1.5307 2.02586 2.49622 + vertex 1.52626 2.02503 2.49711 + vertex 1.53072 2.02161 2.49755 + endloop + endfacet + facet normal 0.133874 0.296412 0.945631 + outer loop + vertex 1.5307 2.02586 2.49622 + vertex 1.53072 2.02161 2.49755 + vertex 1.53474 2.02469 2.49601 + endloop + endfacet + facet normal 0.13167 0.288266 0.948454 + outer loop + vertex 1.53474 2.02469 2.49601 + vertex 1.53304 2.02915 2.49489 + vertex 1.5307 2.02586 2.49622 + endloop + endfacet + facet normal 0.130921 0.288777 0.948403 + outer loop + vertex 1.52864 2.02845 2.49571 + vertex 1.5307 2.02586 2.49622 + vertex 1.53304 2.02915 2.49489 + endloop + endfacet + facet normal 0.136711 0.272754 0.952321 + outer loop + vertex 1.52862 2.03242 2.49456 + vertex 1.53103 2.03571 2.49328 + vertex 1.52706 2.0369 2.4935 + endloop + endfacet + facet normal 0.136349 0.274476 0.951878 + outer loop + vertex 1.54104 2.03075 2.49328 + vertex 1.54109 2.03483 2.4921 + vertex 1.53702 2.03194 2.49352 + endloop + endfacet + facet normal 0.135377 0.278058 0.950977 + outer loop + vertex 1.54358 2.03826 2.49074 + vertex 1.53952 2.03938 2.49099 + vertex 1.54109 2.03483 2.4921 + endloop + endfacet + facet normal 0.136345 0.281847 0.949722 + outer loop + vertex 1.53952 2.03938 2.49099 + vertex 1.54358 2.03826 2.49074 + vertex 1.54364 2.04235 2.48952 + endloop + endfacet + facet normal 0.133907 0.284956 0.949141 + outer loop + vertex 1.53792 2.04394 2.48985 + vertex 1.53952 2.03938 2.49099 + vertex 1.54364 2.04235 2.48952 + endloop + endfacet + facet normal 0.134151 0.285903 0.948822 + outer loop + vertex 1.54364 2.04235 2.48952 + vertex 1.54215 2.04679 2.48839 + vertex 1.53792 2.04394 2.48985 + endloop + endfacet + facet normal 0.13501 0.278638 0.950859 + outer loop + vertex 1.53105 2.03977 2.49208 + vertex 1.53103 2.03571 2.49328 + vertex 1.53544 2.03645 2.49243 + endloop + endfacet + facet normal 0.134471 0.285875 0.948785 + outer loop + vertex 1.53342 2.04316 2.49072 + vertex 1.53546 2.04052 2.49123 + vertex 1.53792 2.04394 2.48985 + endloop + endfacet + facet normal 0.140708 0.287103 0.947509 + outer loop + vertex 1.53105 2.03977 2.49208 + vertex 1.52942 2.04431 2.49095 + vertex 1.52549 2.04144 2.4924 + endloop + endfacet + facet normal 0.141289 0.294107 0.945272 + outer loop + vertex 1.52942 2.04431 2.49095 + vertex 1.52771 2.04876 2.48982 + vertex 1.52545 2.04549 2.49118 + endloop + endfacet + facet normal 0.136319 0.298572 0.944602 + outer loop + vertex 1.52771 2.04876 2.48982 + vertex 1.53119 2.05112 2.48857 + vertex 1.52785 2.05274 2.48854 + endloop + endfacet + facet normal 0.13224 0.298954 0.94506 + outer loop + vertex 1.53134 2.0551 2.48729 + vertex 1.53119 2.05112 2.48857 + vertex 1.53574 2.05187 2.4877 + endloop + endfacet + facet normal 0.133313 0.290984 0.947394 + outer loop + vertex 1.53342 2.04316 2.49072 + vertex 1.53792 2.04394 2.48985 + vertex 1.53333 2.0473 2.48946 + endloop + endfacet + facet normal 0.129324 0.294983 0.94671 + outer loop + vertex 1.53802 2.04813 2.48855 + vertex 1.54104 2.05088 2.48728 + vertex 1.53574 2.05187 2.4877 + endloop + endfacet + facet normal 0.132395 0.294106 0.946558 + outer loop + vertex 1.54616 2.04967 2.48695 + vertex 1.5445 2.05394 2.48585 + vertex 1.54104 2.05088 2.48728 + endloop + endfacet + facet normal 0.142654 0.288811 0.946698 + outer loop + vertex 1.54616 2.04967 2.48695 + vertex 1.5461 2.04572 2.48816 + vertex 1.55032 2.04645 2.4873 + endloop + endfacet + facet normal 0.143544 0.284897 0.94775 + outer loop + vertex 1.54805 2.04314 2.48864 + vertex 1.55032 2.04645 2.4873 + vertex 1.5461 2.04572 2.48816 + endloop + endfacet + facet normal 0.142596 0.281511 0.948904 + outer loop + vertex 1.54358 2.03826 2.49074 + vertex 1.54802 2.03905 2.48984 + vertex 1.54364 2.04235 2.48952 + endloop + endfacet + facet normal 0.139324 0.267832 0.953339 + outer loop + vertex 1.55759 2.03758 2.48875 + vertex 1.56042 2.04046 2.48753 + vertex 1.55576 2.04035 2.48824 + endloop + endfacet + facet normal 0.152838 0.276779 0.948701 + outer loop + vertex 1.5535 2.03329 2.49066 + vertex 1.55766 2.03379 2.48984 + vertex 1.55348 2.03727 2.4895 + endloop + endfacet + facet normal 0.146213 0.261389 0.954095 + outer loop + vertex 1.56078 2.036 2.48869 + vertex 1.56042 2.04046 2.48753 + vertex 1.55759 2.03758 2.48875 + endloop + endfacet + facet normal 0.133485 0.264176 0.955193 + outer loop + vertex 1.56323 2.03198 2.48946 + vertex 1.56544 2.03645 2.48792 + vertex 1.56078 2.036 2.48869 + endloop + endfacet + facet normal 0.162327 0.249683 0.954625 + outer loop + vertex 1.56776 2.03231 2.48861 + vertex 1.56544 2.03645 2.48792 + vertex 1.56323 2.03198 2.48946 + endloop + endfacet + facet normal 0.152346 0.278239 0.948353 + outer loop + vertex 1.55943 2.02933 2.49087 + vertex 1.55766 2.03379 2.48984 + vertex 1.55546 2.03064 2.49112 + endloop + endfacet + facet normal 0.15523 0.278289 0.947871 + outer loop + vertex 1.56351 2.02794 2.49061 + vertex 1.55943 2.02933 2.49087 + vertex 1.56114 2.02469 2.49195 + endloop + endfacet + facet normal 0.161067 0.280245 0.946319 + outer loop + vertex 1.56351 2.02794 2.49061 + vertex 1.56549 2.02521 2.49108 + vertex 1.56821 2.02816 2.48974 + endloop + endfacet + facet normal 0.152137 0.244493 0.957642 + outer loop + vertex 1.56776 2.03231 2.48861 + vertex 1.57116 2.03473 2.48745 + vertex 1.56544 2.03645 2.48792 + endloop + endfacet + facet normal 0.162882 0.279089 0.94635 + outer loop + vertex 1.56864 2.02403 2.49089 + vertex 1.57298 2.02445 2.49002 + vertex 1.56821 2.02816 2.48974 + endloop + endfacet + facet normal 0.16007 0.277564 0.947278 + outer loop + vertex 1.57709 2.02695 2.48858 + vertex 1.57551 2.03126 2.48758 + vertex 1.57298 2.02833 2.48887 + endloop + endfacet + facet normal 0.159782 0.277475 0.947353 + outer loop + vertex 1.57709 2.02695 2.48858 + vertex 1.58123 2.0295 2.48714 + vertex 1.57551 2.03126 2.48758 + endloop + endfacet + facet normal 0.157246 0.268487 0.950362 + outer loop + vertex 1.58123 2.0295 2.48714 + vertex 1.57963 2.03402 2.48612 + vertex 1.57551 2.03126 2.48758 + endloop + endfacet + facet normal 0.162662 0.275994 0.947295 + outer loop + vertex 1.57464 2.01976 2.4911 + vertex 1.57298 2.02445 2.49002 + vertex 1.57057 2.02122 2.49137 + endloop + endfacet + facet normal 0.15854 0.271738 0.949223 + outer loop + vertex 1.57859 2.0184 2.49083 + vertex 1.57464 2.01976 2.4911 + vertex 1.57628 2.01515 2.49214 + endloop + endfacet + facet normal 0.159267 0.272852 0.948781 + outer loop + vertex 1.57859 2.0184 2.49083 + vertex 1.58051 2.01572 2.49128 + vertex 1.5828 2.01899 2.48995 + endloop + endfacet + facet normal 0.158379 0.278183 0.947381 + outer loop + vertex 1.57862 2.02245 2.48965 + vertex 1.58116 2.02558 2.4883 + vertex 1.57709 2.02695 2.48858 + endloop + endfacet + facet normal 0.162054 0.277161 0.947059 + outer loop + vertex 1.58611 2.02149 2.48866 + vertex 1.58587 2.0259 2.48741 + vertex 1.58293 2.02291 2.48879 + endloop + endfacet + facet normal 0.15867 0.279114 0.947058 + outer loop + vertex 1.58116 2.02558 2.4883 + vertex 1.58123 2.0295 2.48714 + vertex 1.57709 2.02695 2.48858 + endloop + endfacet + facet normal 0.158711 0.277814 0.947434 + outer loop + vertex 1.58559 2.03009 2.48623 + vertex 1.58374 2.03273 2.48577 + vertex 1.58123 2.0295 2.48714 + endloop + endfacet + facet normal 0.167167 0.271434 0.947828 + outer loop + vertex 1.58374 2.03273 2.48577 + vertex 1.57963 2.03402 2.48612 + vertex 1.58123 2.0295 2.48714 + endloop + endfacet + facet normal 0.38474 0.0781647 0.91971 + outer loop + vertex 1.57805 2.03915 2.48551 + vertex 1.58154 2.04151 2.48385 + vertex 1.57857 2.0441 2.48487 + endloop + endfacet + facet normal 0.771385 0.000366792 0.636368 + outer loop + vertex 1.575 2.045 2.4892 + vertex 1.57805 2.03915 2.48551 + vertex 1.57857 2.0441 2.48487 + endloop + endfacet + facet normal 0.680931 -0.361084 0.637143 + outer loop + vertex 1.57857 2.0441 2.48487 + vertex 1.58 2.05 2.48669 + vertex 1.575 2.045 2.4892 + endloop + endfacet + facet normal 0.690842 -0.360299 0.626835 + outer loop + vertex 1.57857 2.0441 2.48487 + vertex 1.58168 2.0468 2.483 + vertex 1.58 2.05 2.48669 + endloop + endfacet + facet normal 0.27398 -0.407039 0.871352 + outer loop + vertex 1.57367 2.03861 2.48664 + vertex 1.57805 2.03915 2.48551 + vertex 1.575 2.045 2.4892 + endloop + endfacet + facet normal 0.236038 0.101653 0.966412 + outer loop + vertex 1.57367 2.03861 2.48664 + vertex 1.57552 2.03529 2.48653 + vertex 1.57805 2.03915 2.48551 + endloop + endfacet + facet normal 0.195244 0.0784955 0.977608 + outer loop + vertex 1.57552 2.03529 2.48653 + vertex 1.57367 2.03861 2.48664 + vertex 1.57116 2.03473 2.48745 + endloop + endfacet + facet normal 0.16946 0.268024 0.948392 + outer loop + vertex 1.58826 2.03765 2.48357 + vertex 1.58615 2.0419 2.48275 + vertex 1.58373 2.03704 2.48455 + endloop + endfacet + facet normal 0.42398 0.132694 0.895898 + outer loop + vertex 1.58154 2.04151 2.48385 + vertex 1.58168 2.0468 2.483 + vertex 1.57857 2.0441 2.48487 + endloop + endfacet + facet normal 0.934811 0.0982877 0.341273 + outer loop + vertex 1.58 2.055 2.48525 + vertex 1.58 2.05 2.48669 + vertex 1.58168 2.0468 2.483 + endloop + endfacet + facet normal 0.314575 0.372136 0.873246 + outer loop + vertex 1.57931 2.05394 2.48113 + vertex 1.58129 2.05111 2.48162 + vertex 1.58373 2.05368 2.47965 + endloop + endfacet + facet normal 0.0142004 0.996404 0.0835355 + outer loop + vertex 1.58 2.055 2.48525 + vertex 1.57556 2.05536 2.48173 + vertex 1.575 2.055 2.4861 + endloop + endfacet + facet normal -0.343571 0.380503 0.85859 + outer loop + vertex 1.5667 2.05554 2.48254 + vertex 1.56728 2.05155 2.48454 + vertex 1.575 2.055 2.4861 + endloop + endfacet + facet normal 0.119508 0.489315 0.86388 + outer loop + vertex 1.5685 2.05885 2.48067 + vertex 1.57131 2.0563 2.48172 + vertex 1.57291 2.05942 2.47974 + endloop + endfacet + facet normal 0.0812006 0.38019 0.921337 + outer loop + vertex 1.5667 2.05554 2.48254 + vertex 1.56432 2.05992 2.48094 + vertex 1.56037 2.05691 2.48253 + endloop + endfacet + facet normal 0.146407 0.303684 0.941457 + outer loop + vertex 1.56432 2.05992 2.48094 + vertex 1.56268 2.06407 2.47986 + vertex 1.56034 2.06094 2.48123 + endloop + endfacet + facet normal 0.156442 0.297425 0.941841 + outer loop + vertex 1.56268 2.06407 2.47986 + vertex 1.56618 2.0663 2.47857 + vertex 1.5629 2.06784 2.47863 + endloop + endfacet + facet normal 0.159586 0.296679 0.941549 + outer loop + vertex 1.56637 2.07013 2.47733 + vertex 1.56618 2.0663 2.47857 + vertex 1.57071 2.06682 2.47764 + endloop + endfacet + facet normal 0.158825 0.29572 0.941979 + outer loop + vertex 1.57063 2.0707 2.47644 + vertex 1.56637 2.07013 2.47733 + vertex 1.57071 2.06682 2.47764 + endloop + endfacet + facet normal 0.160879 0.29566 0.941649 + outer loop + vertex 1.57063 2.0707 2.47644 + vertex 1.57071 2.06682 2.47764 + vertex 1.57454 2.0695 2.47614 + endloop + endfacet + facet normal 0.158983 0.294901 0.942209 + outer loop + vertex 1.57063 2.0707 2.47644 + vertex 1.56863 2.07331 2.47596 + vertex 1.56637 2.07013 2.47733 + endloop + endfacet + facet normal 0.159576 0.295312 0.94198 + outer loop + vertex 1.56863 2.07331 2.47596 + vertex 1.57063 2.0707 2.47644 + vertex 1.57284 2.0739 2.47506 + endloop + endfacet + facet normal 0.155492 0.323729 0.933285 + outer loop + vertex 1.5685 2.05885 2.48067 + vertex 1.57291 2.05942 2.47974 + vertex 1.56824 2.06276 2.47935 + endloop + endfacet + facet normal 0.169916 0.328059 0.92925 + outer loop + vertex 1.57872 2.05766 2.47929 + vertex 1.57628 2.06158 2.47836 + vertex 1.57291 2.05942 2.47974 + endloop + endfacet + facet normal 0.161958 0.29952 0.940243 + outer loop + vertex 1.57284 2.06325 2.47841 + vertex 1.57628 2.06526 2.47718 + vertex 1.57071 2.06682 2.47764 + endloop + endfacet + facet normal 0.157978 0.294231 0.942587 + outer loop + vertex 1.57846 2.06826 2.47586 + vertex 1.58051 2.06568 2.47633 + vertex 1.58271 2.06881 2.47498 + endloop + endfacet + facet normal 0.160965 0.29555 0.941669 + outer loop + vertex 1.57628 2.06526 2.47718 + vertex 1.57454 2.0695 2.47614 + vertex 1.57071 2.06682 2.47764 + endloop + endfacet + facet normal 0.160593 0.294627 0.942022 + outer loop + vertex 1.57454 2.0695 2.47614 + vertex 1.57284 2.0739 2.47506 + vertex 1.57063 2.0707 2.47644 + endloop + endfacet + facet normal 0.159287 0.296756 0.941575 + outer loop + vertex 1.56863 2.07331 2.47596 + vertex 1.57284 2.0739 2.47506 + vertex 1.5686 2.07731 2.4747 + endloop + endfacet + facet normal 0.159774 0.29805 0.941084 + outer loop + vertex 1.57289 2.0778 2.47382 + vertex 1.57578 2.08078 2.47239 + vertex 1.57108 2.08048 2.47328 + endloop + endfacet + facet normal 0.159673 0.298887 0.940835 + outer loop + vertex 1.57111 2.08443 2.47203 + vertex 1.57108 2.08048 2.47328 + vertex 1.57578 2.08078 2.47239 + endloop + endfacet + facet normal 0.155302 0.298118 0.941811 + outer loop + vertex 1.5686 2.07731 2.4747 + vertex 1.56709 2.08181 2.47353 + vertex 1.56299 2.07912 2.47505 + endloop + endfacet + facet normal 0.148331 0.298915 0.942681 + outer loop + vertex 1.56068 2.07578 2.47649 + vertex 1.5586 2.07843 2.47598 + vertex 1.55638 2.07515 2.47737 + endloop + endfacet + facet normal 0.15017 0.297364 0.942881 + outer loop + vertex 1.55839 2.06729 2.47953 + vertex 1.56082 2.07166 2.47777 + vertex 1.55628 2.07112 2.47866 + endloop + endfacet + facet normal 0.144008 0.297071 0.943934 + outer loop + vertex 1.55281 2.0688 2.47992 + vertex 1.55628 2.07112 2.47866 + vertex 1.55292 2.07281 2.47864 + endloop + endfacet + facet normal 0.139063 0.300133 0.943706 + outer loop + vertex 1.54847 2.06819 2.48075 + vertex 1.55057 2.06556 2.48128 + vertex 1.55281 2.0688 2.47992 + endloop + endfacet + facet normal 0.13429 0.299539 0.944586 + outer loop + vertex 1.54847 2.06819 2.48075 + vertex 1.5444 2.06937 2.48096 + vertex 1.54612 2.06486 2.48214 + endloop + endfacet + facet normal 0.132121 0.298413 0.945248 + outer loop + vertex 1.5444 2.06937 2.48096 + vertex 1.54268 2.07377 2.47981 + vertex 1.54038 2.07049 2.48117 + endloop + endfacet + facet normal 0.136855 0.300062 0.944052 + outer loop + vertex 1.54832 2.07228 2.47948 + vertex 1.55077 2.07669 2.47772 + vertex 1.54619 2.07615 2.47856 + endloop + endfacet + facet normal 0.136303 0.303279 0.943103 + outer loop + vertex 1.54633 2.0801 2.47727 + vertex 1.54619 2.07615 2.47856 + vertex 1.55077 2.07669 2.47772 + endloop + endfacet + facet normal 0.136136 0.303074 0.943193 + outer loop + vertex 1.55063 2.08071 2.47645 + vertex 1.54633 2.0801 2.47727 + vertex 1.55077 2.07669 2.47772 + endloop + endfacet + facet normal 0.139987 0.303028 0.942644 + outer loop + vertex 1.55063 2.08071 2.47645 + vertex 1.55077 2.07669 2.47772 + vertex 1.5546 2.07956 2.47623 + endloop + endfacet + facet normal 0.140919 0.306486 0.941386 + outer loop + vertex 1.5546 2.07956 2.47623 + vertex 1.55286 2.08391 2.47508 + vertex 1.55063 2.08071 2.47645 + endloop + endfacet + facet normal 0.142883 0.307138 0.940877 + outer loop + vertex 1.55286 2.08391 2.47508 + vertex 1.5546 2.07956 2.47623 + vertex 1.55842 2.08251 2.47469 + endloop + endfacet + facet normal 0.142272 0.304449 0.941843 + outer loop + vertex 1.55842 2.08251 2.47469 + vertex 1.55629 2.08628 2.47379 + vertex 1.55286 2.08391 2.47508 + endloop + endfacet + facet normal 0.145201 0.304414 0.941408 + outer loop + vertex 1.5546 2.07956 2.47623 + vertex 1.5586 2.07843 2.47598 + vertex 1.55842 2.08251 2.47469 + endloop + endfacet + facet normal 0.144432 0.301471 0.942473 + outer loop + vertex 1.5586 2.07843 2.47598 + vertex 1.5546 2.07956 2.47623 + vertex 1.55638 2.07515 2.47737 + endloop + endfacet + facet normal 0.141955 0.300642 0.943114 + outer loop + vertex 1.55638 2.07515 2.47737 + vertex 1.5546 2.07956 2.47623 + vertex 1.55077 2.07669 2.47772 + endloop + endfacet + facet normal 0.135465 0.306484 0.942187 + outer loop + vertex 1.55063 2.08071 2.47645 + vertex 1.54858 2.0833 2.4759 + vertex 1.54633 2.0801 2.47727 + endloop + endfacet + facet normal 0.132478 0.299071 0.94499 + outer loop + vertex 1.53836 2.073 2.48066 + vertex 1.54268 2.07377 2.47981 + vertex 1.53831 2.077 2.4794 + endloop + endfacet + facet normal 0.134816 0.302784 0.943476 + outer loop + vertex 1.53831 2.077 2.4794 + vertex 1.5407 2.08154 2.4776 + vertex 1.53606 2.08074 2.47852 + endloop + endfacet + facet normal 0.134489 0.303417 0.943319 + outer loop + vertex 1.54619 2.07615 2.47856 + vertex 1.54633 2.0801 2.47727 + vertex 1.54284 2.07775 2.47852 + endloop + endfacet + facet normal 0.133901 0.306753 0.942323 + outer loop + vertex 1.53612 2.08489 2.47716 + vertex 1.53606 2.08074 2.47852 + vertex 1.5407 2.08154 2.4776 + endloop + endfacet + facet normal 0.134391 0.308681 0.941624 + outer loop + vertex 1.53847 2.08822 2.47574 + vertex 1.53444 2.08935 2.47594 + vertex 1.53612 2.08489 2.47716 + endloop + endfacet + facet normal 0.134066 0.30858 0.941703 + outer loop + vertex 1.53612 2.08489 2.47716 + vertex 1.53444 2.08935 2.47594 + vertex 1.53049 2.08646 2.47745 + endloop + endfacet + facet normal 0.131903 0.309629 0.941664 + outer loop + vertex 1.52613 2.08955 2.47704 + vertex 1.52612 2.08563 2.47833 + vertex 1.53049 2.08646 2.47745 + endloop + endfacet + facet normal 0.131986 0.309612 0.941658 + outer loop + vertex 1.52842 2.09293 2.47562 + vertex 1.53044 2.09042 2.47615 + vertex 1.53277 2.09367 2.47476 + endloop + endfacet + facet normal 0.129636 0.309727 0.941947 + outer loop + vertex 1.52612 2.08563 2.47833 + vertex 1.52613 2.08955 2.47704 + vertex 1.52214 2.08671 2.47853 + endloop + endfacet + facet normal 0.129131 0.307349 0.942795 + outer loop + vertex 1.5237 2.08233 2.47974 + vertex 1.52214 2.08671 2.47853 + vertex 1.518 2.08396 2.47999 + endloop + endfacet + facet normal 0.127643 0.311546 0.941619 + outer loop + vertex 1.51354 2.08327 2.48082 + vertex 1.518 2.08396 2.47999 + vertex 1.51334 2.08731 2.47951 + endloop + endfacet + facet normal 0.124469 0.314233 0.941151 + outer loop + vertex 1.518 2.0881 2.47863 + vertex 1.52096 2.09079 2.47734 + vertex 1.51567 2.09178 2.47771 + endloop + endfacet + facet normal 0.125919 0.311539 0.941854 + outer loop + vertex 1.50949 2.08438 2.481 + vertex 1.51354 2.08327 2.48082 + vertex 1.51334 2.08731 2.47951 + endloop + endfacet + facet normal 0.117395 0.311536 0.942955 + outer loop + vertex 1.50547 2.08543 2.48117 + vertex 1.50114 2.08458 2.48199 + vertex 1.50565 2.08141 2.48248 + endloop + endfacet + facet normal 0.116185 0.316271 0.941527 + outer loop + vertex 1.50547 2.08543 2.48117 + vertex 1.5034 2.08792 2.48059 + vertex 1.50114 2.08458 2.48199 + endloop + endfacet + facet normal 0.125398 0.309528 0.942586 + outer loop + vertex 1.51354 2.08327 2.48082 + vertex 1.50949 2.08438 2.481 + vertex 1.51129 2.08003 2.48218 + endloop + endfacet + facet normal 0.126737 0.307986 0.942912 + outer loop + vertex 1.5112 2.07608 2.48349 + vertex 1.51129 2.08003 2.48218 + vertex 1.50783 2.07767 2.48342 + endloop + endfacet + facet normal 0.126176 0.306821 0.943366 + outer loop + vertex 1.50773 2.0737 2.48473 + vertex 1.5112 2.07608 2.48349 + vertex 1.50783 2.07767 2.48342 + endloop + endfacet + facet normal 0.123415 0.305639 0.944115 + outer loop + vertex 1.50341 2.07293 2.48554 + vertex 1.50547 2.07043 2.48608 + vertex 1.50773 2.0737 2.48473 + endloop + endfacet + facet normal 0.117213 0.30459 0.945244 + outer loop + vertex 1.50341 2.07293 2.48554 + vertex 1.49941 2.07384 2.48574 + vertex 1.50115 2.06955 2.48691 + endloop + endfacet + facet normal 0.116481 0.30434 0.945415 + outer loop + vertex 1.50115 2.06955 2.48691 + vertex 1.49941 2.07384 2.48574 + vertex 1.49597 2.07077 2.48716 + endloop + endfacet + facet normal 0.115985 0.302073 0.946203 + outer loop + vertex 1.49712 2.06667 2.48832 + vertex 1.50115 2.06955 2.48691 + vertex 1.49597 2.07077 2.48716 + endloop + endfacet + facet normal 0.116554 0.301355 0.946362 + outer loop + vertex 1.50112 2.06561 2.48817 + vertex 1.50115 2.06955 2.48691 + vertex 1.49712 2.06667 2.48832 + endloop + endfacet + facet normal 0.115382 0.305464 0.945187 + outer loop + vertex 1.49941 2.07384 2.48574 + vertex 1.49458 2.07482 2.48601 + vertex 1.49597 2.07077 2.48716 + endloop + endfacet + facet normal 0.114405 0.305189 0.945395 + outer loop + vertex 1.49597 2.07077 2.48716 + vertex 1.49458 2.07482 2.48601 + vertex 1.49066 2.07163 2.48752 + endloop + endfacet + facet normal 0.1146 0.304972 0.945441 + outer loop + vertex 1.49057 2.07564 2.48624 + vertex 1.49066 2.07163 2.48752 + vertex 1.49458 2.07482 2.48601 + endloop + endfacet + facet normal 0.115341 0.308982 0.944048 + outer loop + vertex 1.49458 2.07482 2.48601 + vertex 1.49289 2.07906 2.48484 + vertex 1.49057 2.07564 2.48624 + endloop + endfacet + facet normal 0.115571 0.308834 0.944068 + outer loop + vertex 1.48853 2.07804 2.4857 + vertex 1.49057 2.07564 2.48624 + vertex 1.49289 2.07906 2.48484 + endloop + endfacet + facet normal 0.114025 0.307648 0.944643 + outer loop + vertex 1.49057 2.07564 2.48624 + vertex 1.48853 2.07804 2.4857 + vertex 1.48621 2.07462 2.4871 + endloop + endfacet + facet normal 0.114528 0.307325 0.944687 + outer loop + vertex 1.48853 2.07804 2.4857 + vertex 1.48453 2.07886 2.48592 + vertex 1.48621 2.07462 2.4871 + endloop + endfacet + facet normal 0.115396 0.307614 0.944488 + outer loop + vertex 1.48621 2.07462 2.4871 + vertex 1.48453 2.07886 2.48592 + vertex 1.48107 2.07582 2.48733 + endloop + endfacet + facet normal 0.114591 0.303917 0.945782 + outer loop + vertex 1.48206 2.0718 2.4885 + vertex 1.48621 2.07462 2.4871 + vertex 1.48107 2.07582 2.48733 + endloop + endfacet + facet normal 0.11558 0.304108 0.9456 + outer loop + vertex 1.48206 2.0718 2.4885 + vertex 1.48107 2.07582 2.48733 + vertex 1.47806 2.07312 2.48857 + endloop + endfacet + facet normal 0.115009 0.302334 0.946238 + outer loop + vertex 1.47791 2.06905 2.48989 + vertex 1.48206 2.0718 2.4885 + vertex 1.47806 2.07312 2.48857 + endloop + endfacet + facet normal 0.115211 0.30232 0.946218 + outer loop + vertex 1.4734 2.07228 2.48941 + vertex 1.47791 2.06905 2.48989 + vertex 1.47806 2.07312 2.48857 + endloop + endfacet + facet normal 0.11433 0.306098 0.94511 + outer loop + vertex 1.47806 2.07312 2.48857 + vertex 1.47581 2.07679 2.48765 + vertex 1.4734 2.07228 2.48941 + endloop + endfacet + facet normal 0.113465 0.306544 0.94507 + outer loop + vertex 1.4734 2.07228 2.48941 + vertex 1.47581 2.07679 2.48765 + vertex 1.47126 2.076 2.48845 + endloop + endfacet + facet normal 0.112695 0.306156 0.945287 + outer loop + vertex 1.4734 2.07228 2.48941 + vertex 1.47126 2.076 2.48845 + vertex 1.46774 2.07361 2.48965 + endloop + endfacet + facet normal 0.112637 0.305894 0.945379 + outer loop + vertex 1.46774 2.07361 2.48965 + vertex 1.46947 2.06927 2.49085 + vertex 1.4734 2.07228 2.48941 + endloop + endfacet + facet normal 0.114963 0.303143 0.945985 + outer loop + vertex 1.46947 2.06927 2.49085 + vertex 1.47352 2.06819 2.4907 + vertex 1.4734 2.07228 2.48941 + endloop + endfacet + facet normal 0.114514 0.30138 0.946603 + outer loop + vertex 1.47352 2.06819 2.4907 + vertex 1.46947 2.06927 2.49085 + vertex 1.47114 2.06481 2.49206 + endloop + endfacet + facet normal 0.115796 0.300524 0.946719 + outer loop + vertex 1.47559 2.06566 2.49125 + vertex 1.47352 2.06819 2.4907 + vertex 1.47114 2.06481 2.49206 + endloop + endfacet + facet normal 0.115652 0.301112 0.94655 + outer loop + vertex 1.47559 2.06566 2.49125 + vertex 1.47114 2.06481 2.49206 + vertex 1.47568 2.06164 2.49252 + endloop + endfacet + facet normal 0.11648 0.3011 0.946452 + outer loop + vertex 1.47559 2.06566 2.49125 + vertex 1.47568 2.06164 2.49252 + vertex 1.47961 2.06476 2.49104 + endloop + endfacet + facet normal 0.116441 0.300909 0.946517 + outer loop + vertex 1.47961 2.06476 2.49104 + vertex 1.47791 2.06905 2.48989 + vertex 1.47559 2.06566 2.49125 + endloop + endfacet + facet normal 0.115464 0.300584 0.946741 + outer loop + vertex 1.47791 2.06905 2.48989 + vertex 1.47961 2.06476 2.49104 + vertex 1.48306 2.06781 2.48966 + endloop + endfacet + facet normal 0.116494 0.301084 0.946455 + outer loop + vertex 1.48098 2.06073 2.49216 + vertex 1.47961 2.06476 2.49104 + vertex 1.47568 2.06164 2.49252 + endloop + endfacet + facet normal 0.116375 0.300952 0.946512 + outer loop + vertex 1.47352 2.06819 2.4907 + vertex 1.47559 2.06566 2.49125 + vertex 1.47791 2.06905 2.48989 + endloop + endfacet + facet normal 0.112701 0.300812 0.947001 + outer loop + vertex 1.47114 2.06481 2.49206 + vertex 1.46947 2.06927 2.49085 + vertex 1.4655 2.06634 2.49225 + endloop + endfacet + facet normal 0.112823 0.301283 0.946836 + outer loop + vertex 1.46699 2.06197 2.49346 + vertex 1.47114 2.06481 2.49206 + vertex 1.4655 2.06634 2.49225 + endloop + endfacet + facet normal 0.109988 0.300484 0.947424 + outer loop + vertex 1.46699 2.06197 2.49346 + vertex 1.4655 2.06634 2.49225 + vertex 1.46307 2.06298 2.4936 + endloop + endfacet + facet normal 0.109958 0.300363 0.947466 + outer loop + vertex 1.46295 2.05905 2.49486 + vertex 1.46699 2.06197 2.49346 + vertex 1.46307 2.06298 2.4936 + endloop + endfacet + facet normal 0.106765 0.300558 0.947769 + outer loop + vertex 1.45869 2.06197 2.49441 + vertex 1.46295 2.05905 2.49486 + vertex 1.46307 2.06298 2.4936 + endloop + endfacet + facet normal 0.10689 0.300116 0.947895 + outer loop + vertex 1.46307 2.06298 2.4936 + vertex 1.46111 2.06542 2.49305 + vertex 1.45869 2.06197 2.49441 + endloop + endfacet + facet normal 0.105425 0.301086 0.947751 + outer loop + vertex 1.45869 2.06197 2.49441 + vertex 1.46111 2.06542 2.49305 + vertex 1.45709 2.06624 2.49323 + endloop + endfacet + facet normal 0.105844 0.303315 0.946994 + outer loop + vertex 1.46111 2.06542 2.49305 + vertex 1.46113 2.06935 2.49179 + vertex 1.45709 2.06624 2.49323 + endloop + endfacet + facet normal 0.108174 0.30323 0.946758 + outer loop + vertex 1.46113 2.06935 2.49179 + vertex 1.46111 2.06542 2.49305 + vertex 1.4655 2.06634 2.49225 + endloop + endfacet + facet normal 0.10728 0.302004 0.947251 + outer loop + vertex 1.46545 2.07033 2.49098 + vertex 1.46113 2.06935 2.49179 + vertex 1.4655 2.06634 2.49225 + endloop + endfacet + facet normal 0.107067 0.300973 0.947603 + outer loop + vertex 1.4586 2.05803 2.49568 + vertex 1.46295 2.05905 2.49486 + vertex 1.45869 2.06197 2.49441 + endloop + endfacet + facet normal 0.106634 0.300996 0.947645 + outer loop + vertex 1.45461 2.05887 2.49586 + vertex 1.4586 2.05803 2.49568 + vertex 1.45869 2.06197 2.49441 + endloop + endfacet + facet normal 0.10672 0.300894 0.947667 + outer loop + vertex 1.4534 2.06304 2.49467 + vertex 1.45461 2.05887 2.49586 + vertex 1.45869 2.06197 2.49441 + endloop + endfacet + facet normal 0.106997 0.302842 0.947016 + outer loop + vertex 1.4586 2.05803 2.49568 + vertex 1.45461 2.05887 2.49586 + vertex 1.45623 2.05459 2.49704 + endloop + endfacet + facet normal 0.106216 0.303352 0.94694 + outer loop + vertex 1.4606 2.05561 2.49622 + vertex 1.4586 2.05803 2.49568 + vertex 1.45623 2.05459 2.49704 + endloop + endfacet + facet normal 0.106119 0.30369 0.946843 + outer loop + vertex 1.4606 2.05561 2.49622 + vertex 1.45623 2.05459 2.49704 + vertex 1.46069 2.05161 2.4975 + endloop + endfacet + facet normal 0.107308 0.303675 0.946713 + outer loop + vertex 1.4606 2.05561 2.49622 + vertex 1.46069 2.05161 2.4975 + vertex 1.4646 2.05479 2.49603 + endloop + endfacet + facet normal 0.107166 0.302924 0.94697 + outer loop + vertex 1.4646 2.05479 2.49603 + vertex 1.46295 2.05905 2.49486 + vertex 1.4606 2.05561 2.49622 + endloop + endfacet + facet normal 0.110177 0.30391 0.946309 + outer loop + vertex 1.46295 2.05905 2.49486 + vertex 1.4646 2.05479 2.49603 + vertex 1.46806 2.05788 2.49464 + endloop + endfacet + facet normal 0.108651 0.302176 0.94704 + outer loop + vertex 1.46597 2.05076 2.49716 + vertex 1.4646 2.05479 2.49603 + vertex 1.46069 2.05161 2.4975 + endloop + endfacet + facet normal 0.108436 0.300645 0.947552 + outer loop + vertex 1.46303 2.04801 2.49837 + vertex 1.46597 2.05076 2.49716 + vertex 1.46069 2.05161 2.4975 + endloop + endfacet + facet normal 0.104392 0.298306 0.948744 + outer loop + vertex 1.46303 2.04801 2.49837 + vertex 1.46069 2.05161 2.4975 + vertex 1.45842 2.04697 2.4992 + endloop + endfacet + facet normal 0.106531 0.290538 0.950915 + outer loop + vertex 1.45842 2.04697 2.4992 + vertex 1.46299 2.04393 2.49962 + vertex 1.46303 2.04801 2.49837 + endloop + endfacet + facet normal 0.111095 0.290359 0.950447 + outer loop + vertex 1.46299 2.04393 2.49962 + vertex 1.46713 2.04672 2.49829 + vertex 1.46303 2.04801 2.49837 + endloop + endfacet + facet normal 0.111679 0.289577 0.950617 + outer loop + vertex 1.46867 2.04237 2.49943 + vertex 1.46713 2.04672 2.49829 + vertex 1.46299 2.04393 2.49962 + endloop + endfacet + facet normal 0.113323 0.295852 0.948488 + outer loop + vertex 1.46299 2.04393 2.49962 + vertex 1.4646 2.03952 2.50081 + vertex 1.46867 2.04237 2.49943 + endloop + endfacet + facet normal 0.109246 0.301088 0.947318 + outer loop + vertex 1.4646 2.03952 2.50081 + vertex 1.46868 2.0384 2.50069 + vertex 1.46867 2.04237 2.49943 + endloop + endfacet + facet normal 0.11878 0.300768 0.946272 + outer loop + vertex 1.46868 2.0384 2.50069 + vertex 1.47312 2.03911 2.49991 + vertex 1.46867 2.04237 2.49943 + endloop + endfacet + facet normal 0.117416 0.299013 0.946998 + outer loop + vertex 1.46867 2.04237 2.49943 + vertex 1.47312 2.03911 2.49991 + vertex 1.47311 2.04308 2.49866 + endloop + endfacet + facet normal 0.119538 0.288823 0.949891 + outer loop + vertex 1.47311 2.04308 2.49866 + vertex 1.4711 2.04562 2.49814 + vertex 1.46867 2.04237 2.49943 + endloop + endfacet + facet normal 0.121143 0.289981 0.949334 + outer loop + vertex 1.47311 2.04308 2.49866 + vertex 1.47553 2.04637 2.49734 + vertex 1.4711 2.04562 2.49814 + endloop + endfacet + facet normal 0.122713 0.28888 0.949468 + outer loop + vertex 1.47717 2.04192 2.49849 + vertex 1.47553 2.04637 2.49734 + vertex 1.47311 2.04308 2.49866 + endloop + endfacet + facet normal 0.122055 0.288675 0.949615 + outer loop + vertex 1.47717 2.04192 2.49849 + vertex 1.48122 2.04481 2.49708 + vertex 1.47553 2.04637 2.49734 + endloop + endfacet + facet normal 0.114623 0.320355 0.940337 + outer loop + vertex 1.46868 2.0384 2.50069 + vertex 1.47074 2.03576 2.50134 + vertex 1.47312 2.03911 2.49991 + endloop + endfacet + facet normal 0.114858 0.320518 0.940253 + outer loop + vertex 1.47074 2.03576 2.50134 + vertex 1.46868 2.0384 2.50069 + vertex 1.46627 2.03493 2.50217 + endloop + endfacet + facet normal 0.115562 0.317641 0.941143 + outer loop + vertex 1.47074 2.03576 2.50134 + vertex 1.46627 2.03493 2.50217 + vertex 1.47086 2.03152 2.50276 + endloop + endfacet + facet normal 0.117572 0.317618 0.940901 + outer loop + vertex 1.47074 2.03576 2.50134 + vertex 1.47086 2.03152 2.50276 + vertex 1.47477 2.03457 2.50124 + endloop + endfacet + facet normal 0.114426 0.320799 0.94021 + outer loop + vertex 1.46868 2.0384 2.50069 + vertex 1.4646 2.03952 2.50081 + vertex 1.46627 2.03493 2.50217 + endloop + endfacet + facet normal 0.0985183 0.31605 0.943614 + outer loop + vertex 1.46627 2.03493 2.50217 + vertex 1.4646 2.03952 2.50081 + vertex 1.46046 2.03645 2.50227 + endloop + endfacet + facet normal 0.103286 0.334701 0.936647 + outer loop + vertex 1.46213 2.03179 2.50375 + vertex 1.46627 2.03493 2.50217 + vertex 1.46046 2.03645 2.50227 + endloop + endfacet + facet normal 0.108434 0.3287 0.938189 + outer loop + vertex 1.46638 2.03064 2.50366 + vertex 1.46627 2.03493 2.50217 + vertex 1.46213 2.03179 2.50375 + endloop + endfacet + facet normal 0.105576 0.307485 0.945678 + outer loop + vertex 1.46054 2.04056 2.50092 + vertex 1.46046 2.03645 2.50227 + vertex 1.4646 2.03952 2.50081 + endloop + endfacet + facet normal 0.0992168 0.307812 0.94626 + outer loop + vertex 1.46054 2.04056 2.50092 + vertex 1.45605 2.03952 2.50173 + vertex 1.46046 2.03645 2.50227 + endloop + endfacet + facet normal 0.101334 0.31065 0.945108 + outer loop + vertex 1.45605 2.03952 2.50173 + vertex 1.45585 2.03545 2.50309 + vertex 1.46046 2.03645 2.50227 + endloop + endfacet + facet normal 0.104302 0.289855 0.95137 + outer loop + vertex 1.46054 2.04056 2.50092 + vertex 1.45852 2.04301 2.50039 + vertex 1.45605 2.03952 2.50173 + endloop + endfacet + facet normal 0.104802 0.290231 0.951201 + outer loop + vertex 1.45852 2.04301 2.50039 + vertex 1.46054 2.04056 2.50092 + vertex 1.46299 2.04393 2.49962 + endloop + endfacet + facet normal 0.101806 0.292294 0.950894 + outer loop + vertex 1.4646 2.03952 2.50081 + vertex 1.46299 2.04393 2.49962 + vertex 1.46054 2.04056 2.50092 + endloop + endfacet + facet normal 0.116463 0.291007 0.949606 + outer loop + vertex 1.46867 2.04237 2.49943 + vertex 1.4711 2.04562 2.49814 + vertex 1.46713 2.04672 2.49829 + endloop + endfacet + facet normal 0.117042 0.293203 0.948859 + outer loop + vertex 1.4711 2.04562 2.49814 + vertex 1.47112 2.04953 2.49693 + vertex 1.46713 2.04672 2.49829 + endloop + endfacet + facet normal 0.114413 0.296592 0.948126 + outer loop + vertex 1.46713 2.04672 2.49829 + vertex 1.47112 2.04953 2.49693 + vertex 1.46597 2.05076 2.49716 + endloop + endfacet + facet normal 0.105202 0.288642 0.95164 + outer loop + vertex 1.45852 2.04301 2.50039 + vertex 1.46299 2.04393 2.49962 + vertex 1.45842 2.04697 2.4992 + endloop + endfacet + facet normal 0.106994 0.29707 0.948842 + outer loop + vertex 1.45842 2.04697 2.4992 + vertex 1.46069 2.05161 2.4975 + vertex 1.4561 2.05054 2.49835 + endloop + endfacet + facet normal 0.103423 0.294993 0.949886 + outer loop + vertex 1.45842 2.04697 2.4992 + vertex 1.4561 2.05054 2.49835 + vertex 1.45312 2.0478 2.49953 + endloop + endfacet + facet normal 0.102513 0.288326 0.952029 + outer loop + vertex 1.45312 2.0478 2.49953 + vertex 1.45444 2.04381 2.50059 + vertex 1.45842 2.04697 2.4992 + endloop + endfacet + facet normal 0.10222 0.288663 0.951958 + outer loop + vertex 1.45444 2.04381 2.50059 + vertex 1.45852 2.04301 2.50039 + vertex 1.45842 2.04697 2.4992 + endloop + endfacet + facet normal 0.102633 0.290974 0.95121 + outer loop + vertex 1.45852 2.04301 2.50039 + vertex 1.45444 2.04381 2.50059 + vertex 1.45605 2.03952 2.50173 + endloop + endfacet + facet normal 0.102534 0.290943 0.95123 + outer loop + vertex 1.45605 2.03952 2.50173 + vertex 1.45444 2.04381 2.50059 + vertex 1.45071 2.04058 2.50198 + endloop + endfacet + facet normal 0.106327 0.311779 0.944187 + outer loop + vertex 1.45177 2.03631 2.50327 + vertex 1.45605 2.03952 2.50173 + vertex 1.45071 2.04058 2.50198 + endloop + endfacet + facet normal 0.111244 0.312729 0.943305 + outer loop + vertex 1.45177 2.03631 2.50327 + vertex 1.45071 2.04058 2.50198 + vertex 1.44691 2.03729 2.50352 + endloop + endfacet + facet normal 0.107033 0.317143 0.942319 + outer loop + vertex 1.44691 2.03729 2.50352 + vertex 1.45071 2.04058 2.50198 + vertex 1.44545 2.04161 2.50223 + endloop + endfacet + facet normal 0.102564 0.292213 0.950838 + outer loop + vertex 1.45071 2.04058 2.50198 + vertex 1.4496 2.04473 2.50082 + vertex 1.44545 2.04161 2.50223 + endloop + endfacet + facet normal 0.101621 0.293352 0.950588 + outer loop + vertex 1.44562 2.04555 2.501 + vertex 1.44545 2.04161 2.50223 + vertex 1.4496 2.04473 2.50082 + endloop + endfacet + facet normal 0.100529 0.287637 0.952449 + outer loop + vertex 1.4496 2.04473 2.50082 + vertex 1.44797 2.04896 2.49972 + vertex 1.44562 2.04555 2.501 + endloop + endfacet + facet normal 0.100906 0.287762 0.952371 + outer loop + vertex 1.44797 2.04896 2.49972 + vertex 1.4496 2.04473 2.50082 + vertex 1.45312 2.0478 2.49953 + endloop + endfacet + facet normal 0.102648 0.295933 0.949677 + outer loop + vertex 1.45312 2.0478 2.49953 + vertex 1.45209 2.05177 2.4984 + vertex 1.44797 2.04896 2.49972 + endloop + endfacet + facet normal 0.102382 0.293298 0.950523 + outer loop + vertex 1.44562 2.04555 2.501 + vertex 1.44122 2.04447 2.50181 + vertex 1.44545 2.04161 2.50223 + endloop + endfacet + facet normal 0.110083 0.304057 0.946272 + outer loop + vertex 1.44122 2.04447 2.50181 + vertex 1.44102 2.04048 2.50311 + vertex 1.44545 2.04161 2.50223 + endloop + endfacet + facet normal 0.101548 0.291989 0.951015 + outer loop + vertex 1.45444 2.04381 2.50059 + vertex 1.4496 2.04473 2.50082 + vertex 1.45071 2.04058 2.50198 + endloop + endfacet + facet normal 0.10082 0.287852 0.952353 + outer loop + vertex 1.4496 2.04473 2.50082 + vertex 1.45444 2.04381 2.50059 + vertex 1.45312 2.0478 2.49953 + endloop + endfacet + facet normal 0.102511 0.295904 0.949701 + outer loop + vertex 1.45312 2.0478 2.49953 + vertex 1.4561 2.05054 2.49835 + vertex 1.45209 2.05177 2.4984 + endloop + endfacet + facet normal 0.104565 0.302719 0.947326 + outer loop + vertex 1.4561 2.05054 2.49835 + vertex 1.45623 2.05459 2.49704 + vertex 1.45209 2.05177 2.4984 + endloop + endfacet + facet normal 0.106073 0.300733 0.947791 + outer loop + vertex 1.45209 2.05177 2.4984 + vertex 1.45623 2.05459 2.49704 + vertex 1.45107 2.05577 2.49724 + endloop + endfacet + facet normal 0.1129 0.296239 0.948418 + outer loop + vertex 1.46713 2.04672 2.49829 + vertex 1.46597 2.05076 2.49716 + vertex 1.46303 2.04801 2.49837 + endloop + endfacet + facet normal 0.105395 0.302668 0.947251 + outer loop + vertex 1.45623 2.05459 2.49704 + vertex 1.4561 2.05054 2.49835 + vertex 1.46069 2.05161 2.4975 + endloop + endfacet + facet normal 0.106493 0.302681 0.947124 + outer loop + vertex 1.45623 2.05459 2.49704 + vertex 1.45461 2.05887 2.49586 + vertex 1.45107 2.05577 2.49724 + endloop + endfacet + facet normal 0.10635 0.303452 0.946893 + outer loop + vertex 1.4586 2.05803 2.49568 + vertex 1.4606 2.05561 2.49622 + vertex 1.46295 2.05905 2.49486 + endloop + endfacet + facet normal 0.109535 0.300893 0.947347 + outer loop + vertex 1.46806 2.05788 2.49464 + vertex 1.46699 2.06197 2.49346 + vertex 1.46295 2.05905 2.49486 + endloop + endfacet + facet normal 0.108654 0.301396 0.947288 + outer loop + vertex 1.46307 2.06298 2.4936 + vertex 1.4655 2.06634 2.49225 + vertex 1.46111 2.06542 2.49305 + endloop + endfacet + facet normal 0.112898 0.301185 0.946859 + outer loop + vertex 1.47106 2.06065 2.4934 + vertex 1.47114 2.06481 2.49206 + vertex 1.46699 2.06197 2.49346 + endloop + endfacet + facet normal 0.111811 0.301902 0.946759 + outer loop + vertex 1.46545 2.07033 2.49098 + vertex 1.4655 2.06634 2.49225 + vertex 1.46947 2.06927 2.49085 + endloop + endfacet + facet normal 0.112831 0.30596 0.945335 + outer loop + vertex 1.46947 2.06927 2.49085 + vertex 1.46774 2.07361 2.48965 + vertex 1.46545 2.07033 2.49098 + endloop + endfacet + facet normal 0.112241 0.311957 0.943443 + outer loop + vertex 1.47145 2.07985 2.48716 + vertex 1.47126 2.076 2.48845 + vertex 1.47581 2.07679 2.48765 + endloop + endfacet + facet normal 0.110717 0.309927 0.944292 + outer loop + vertex 1.47572 2.08074 2.48637 + vertex 1.47145 2.07985 2.48716 + vertex 1.47581 2.07679 2.48765 + endloop + endfacet + facet normal 0.112956 0.309895 0.944037 + outer loop + vertex 1.47572 2.08074 2.48637 + vertex 1.47581 2.07679 2.48765 + vertex 1.47972 2.07985 2.48618 + endloop + endfacet + facet normal 0.113759 0.313789 0.942654 + outer loop + vertex 1.47972 2.07985 2.48618 + vertex 1.47799 2.0841 2.48498 + vertex 1.47572 2.08074 2.48637 + endloop + endfacet + facet normal 0.111351 0.315326 0.942428 + outer loop + vertex 1.47365 2.08316 2.4858 + vertex 1.47572 2.08074 2.48637 + vertex 1.47799 2.0841 2.48498 + endloop + endfacet + facet normal 0.110588 0.318105 0.941584 + outer loop + vertex 1.47365 2.08316 2.4858 + vertex 1.47799 2.0841 2.48498 + vertex 1.47349 2.08709 2.48449 + endloop + endfacet + facet normal 0.10707 0.318099 0.941992 + outer loop + vertex 1.46962 2.08397 2.48599 + vertex 1.47365 2.08316 2.4858 + vertex 1.47349 2.08709 2.48449 + endloop + endfacet + facet normal 0.10613 0.319145 0.941745 + outer loop + vertex 1.46818 2.08795 2.4848 + vertex 1.46962 2.08397 2.48599 + vertex 1.47349 2.08709 2.48449 + endloop + endfacet + facet normal 0.106159 0.319357 0.941669 + outer loop + vertex 1.47349 2.08709 2.48449 + vertex 1.47115 2.09065 2.48355 + vertex 1.46818 2.08795 2.4848 + endloop + endfacet + facet normal 0.104074 0.321428 0.941197 + outer loop + vertex 1.46818 2.08795 2.4848 + vertex 1.47115 2.09065 2.48355 + vertex 1.4671 2.09188 2.48358 + endloop + endfacet + facet normal 0.102927 0.321179 0.941409 + outer loop + vertex 1.46818 2.08795 2.4848 + vertex 1.4671 2.09188 2.48358 + vertex 1.46298 2.08911 2.48497 + endloop + endfacet + facet normal 0.102711 0.320159 0.941779 + outer loop + vertex 1.46298 2.08911 2.48497 + vertex 1.46474 2.08489 2.48621 + vertex 1.46818 2.08795 2.4848 + endloop + endfacet + facet normal 0.102741 0.32017 0.941773 + outer loop + vertex 1.46474 2.08489 2.48621 + vertex 1.46298 2.08911 2.48497 + vertex 1.46068 2.08572 2.48638 + endloop + endfacet + facet normal 0.102472 0.318746 0.942285 + outer loop + vertex 1.46068 2.08572 2.48638 + vertex 1.46075 2.08165 2.48774 + vertex 1.46474 2.08489 2.48621 + endloop + endfacet + facet normal 0.103084 0.318735 0.942222 + outer loop + vertex 1.46068 2.08572 2.48638 + vertex 1.45631 2.08473 2.48719 + vertex 1.46075 2.08165 2.48774 + endloop + endfacet + facet normal 0.102599 0.320444 0.941695 + outer loop + vertex 1.46068 2.08572 2.48638 + vertex 1.45862 2.08811 2.48579 + vertex 1.45631 2.08473 2.48719 + endloop + endfacet + facet normal 0.103457 0.319896 0.941787 + outer loop + vertex 1.45862 2.08811 2.48579 + vertex 1.45461 2.08892 2.48595 + vertex 1.45631 2.08473 2.48719 + endloop + endfacet + facet normal 0.104681 0.320312 0.94151 + outer loop + vertex 1.45631 2.08473 2.48719 + vertex 1.45461 2.08892 2.48595 + vertex 1.45118 2.08588 2.48737 + endloop + endfacet + facet normal 0.103917 0.322381 0.940889 + outer loop + vertex 1.45461 2.08892 2.48595 + vertex 1.45862 2.08811 2.48579 + vertex 1.45847 2.09205 2.48445 + endloop + endfacet + facet normal 0.104182 0.322089 0.94096 + outer loop + vertex 1.45319 2.09288 2.48475 + vertex 1.45461 2.08892 2.48595 + vertex 1.45847 2.09205 2.48445 + endloop + endfacet + facet normal 0.105565 0.322495 0.940666 + outer loop + vertex 1.44978 2.08985 2.48618 + vertex 1.45461 2.08892 2.48595 + vertex 1.45319 2.09288 2.48475 + endloop + endfacet + facet normal 0.101883 0.322377 0.941113 + outer loop + vertex 1.45862 2.08811 2.48579 + vertex 1.46298 2.08911 2.48497 + vertex 1.45847 2.09205 2.48445 + endloop + endfacet + facet normal 0.102184 0.322808 0.940932 + outer loop + vertex 1.45847 2.09205 2.48445 + vertex 1.46298 2.08911 2.48497 + vertex 1.46305 2.0931 2.4836 + endloop + endfacet + facet normal 0.101312 0.325839 0.939981 + outer loop + vertex 1.46305 2.0931 2.4836 + vertex 1.46069 2.09662 2.48263 + vertex 1.45847 2.09205 2.48445 + endloop + endfacet + facet normal 0.101217 0.325783 0.940011 + outer loop + vertex 1.46305 2.0931 2.4836 + vertex 1.46601 2.0958 2.48234 + vertex 1.46069 2.09662 2.48263 + endloop + endfacet + facet normal 0.102247 0.324766 0.940252 + outer loop + vertex 1.4671 2.09188 2.48358 + vertex 1.46601 2.0958 2.48234 + vertex 1.46305 2.0931 2.4836 + endloop + endfacet + facet normal 0.103205 0.324974 0.940075 + outer loop + vertex 1.4671 2.09188 2.48358 + vertex 1.47123 2.09465 2.48217 + vertex 1.46601 2.0958 2.48234 + endloop + endfacet + facet normal 0.10295 0.323757 0.940523 + outer loop + vertex 1.47123 2.09465 2.48217 + vertex 1.46949 2.09884 2.48091 + vertex 1.46601 2.0958 2.48234 + endloop + endfacet + facet normal 0.100849 0.32592 0.940003 + outer loop + vertex 1.46949 2.09884 2.48091 + vertex 1.46461 2.09975 2.48112 + vertex 1.46601 2.0958 2.48234 + endloop + endfacet + facet normal 0.102467 0.320343 0.941744 + outer loop + vertex 1.45862 2.08811 2.48579 + vertex 1.46068 2.08572 2.48638 + vertex 1.46298 2.08911 2.48497 + endloop + endfacet + facet normal 0.10167 0.322833 0.940979 + outer loop + vertex 1.46298 2.08911 2.48497 + vertex 1.4671 2.09188 2.48358 + vertex 1.46305 2.0931 2.4836 + endloop + endfacet + facet normal 0.10459 0.323146 0.940552 + outer loop + vertex 1.47115 2.09065 2.48355 + vertex 1.47123 2.09465 2.48217 + vertex 1.4671 2.09188 2.48358 + endloop + endfacet + facet normal 0.108331 0.322944 0.940198 + outer loop + vertex 1.47123 2.09465 2.48217 + vertex 1.47115 2.09065 2.48355 + vertex 1.47575 2.09169 2.48266 + endloop + endfacet + facet normal 0.107541 0.321818 0.940674 + outer loop + vertex 1.47563 2.09565 2.48132 + vertex 1.47123 2.09465 2.48217 + vertex 1.47575 2.09169 2.48266 + endloop + endfacet + facet normal 0.111813 0.32179 0.940186 + outer loop + vertex 1.47563 2.09565 2.48132 + vertex 1.47575 2.09169 2.48266 + vertex 1.47966 2.09482 2.48112 + endloop + endfacet + facet normal 0.112488 0.321037 0.940363 + outer loop + vertex 1.48105 2.09082 2.48232 + vertex 1.47966 2.09482 2.48112 + vertex 1.47575 2.09169 2.48266 + endloop + endfacet + facet normal 0.112629 0.322041 0.940002 + outer loop + vertex 1.47808 2.08811 2.48361 + vertex 1.48105 2.09082 2.48232 + vertex 1.47575 2.09169 2.48266 + endloop + endfacet + facet normal 0.10987 0.320473 0.940864 + outer loop + vertex 1.47808 2.08811 2.48361 + vertex 1.47575 2.09169 2.48266 + vertex 1.47349 2.08709 2.48449 + endloop + endfacet + facet normal 0.114183 0.320497 0.940343 + outer loop + vertex 1.48211 2.08685 2.48355 + vertex 1.48105 2.09082 2.48232 + vertex 1.47808 2.08811 2.48361 + endloop + endfacet + facet normal 0.113381 0.31789 0.941324 + outer loop + vertex 1.47799 2.0841 2.48498 + vertex 1.48211 2.08685 2.48355 + vertex 1.47808 2.08811 2.48361 + endloop + endfacet + facet normal 0.114372 0.316576 0.941647 + outer loop + vertex 1.48316 2.08288 2.48476 + vertex 1.48211 2.08685 2.48355 + vertex 1.47799 2.0841 2.48498 + endloop + endfacet + facet normal 0.114957 0.316696 0.941535 + outer loop + vertex 1.48316 2.08288 2.48476 + vertex 1.48613 2.08559 2.48348 + vertex 1.48211 2.08685 2.48355 + endloop + endfacet + facet normal 0.115913 0.319814 0.940363 + outer loop + vertex 1.48613 2.08559 2.48348 + vertex 1.48622 2.0896 2.48211 + vertex 1.48211 2.08685 2.48355 + endloop + endfacet + facet normal 0.115685 0.315973 0.941689 + outer loop + vertex 1.48843 2.08202 2.4844 + vertex 1.48613 2.08559 2.48348 + vertex 1.48316 2.08288 2.48476 + endloop + endfacet + facet normal 0.115157 0.312164 0.943023 + outer loop + vertex 1.48316 2.08288 2.48476 + vertex 1.48453 2.07886 2.48592 + vertex 1.48843 2.08202 2.4844 + endloop + endfacet + facet normal 0.115291 0.312202 0.942994 + outer loop + vertex 1.47972 2.07985 2.48618 + vertex 1.48453 2.07886 2.48592 + vertex 1.48316 2.08288 2.48476 + endloop + endfacet + facet normal 0.115232 0.320713 0.940141 + outer loop + vertex 1.48211 2.08685 2.48355 + vertex 1.48622 2.0896 2.48211 + vertex 1.48105 2.09082 2.48232 + endloop + endfacet + facet normal 0.11537 0.321341 0.939909 + outer loop + vertex 1.48622 2.0896 2.48211 + vertex 1.48449 2.09383 2.48087 + vertex 1.48105 2.09082 2.48232 + endloop + endfacet + facet normal 0.107539 0.321825 0.940672 + outer loop + vertex 1.47563 2.09565 2.48132 + vertex 1.47355 2.09804 2.48074 + vertex 1.47123 2.09465 2.48217 + endloop + endfacet + facet normal 0.108902 0.320934 0.94082 + outer loop + vertex 1.47349 2.08709 2.48449 + vertex 1.47575 2.09169 2.48266 + vertex 1.47115 2.09065 2.48355 + endloop + endfacet + facet normal 0.10426 0.318585 0.942143 + outer loop + vertex 1.46474 2.08489 2.48621 + vertex 1.46962 2.08397 2.48599 + vertex 1.46818 2.08795 2.4848 + endloop + endfacet + facet normal 0.104183 0.318135 0.942304 + outer loop + vertex 1.46962 2.08397 2.48599 + vertex 1.46474 2.08489 2.48621 + vertex 1.46629 2.08081 2.48742 + endloop + endfacet + facet normal 0.106575 0.315846 0.942806 + outer loop + vertex 1.47145 2.07985 2.48716 + vertex 1.46962 2.08397 2.48599 + vertex 1.46629 2.08081 2.48742 + endloop + endfacet + facet normal 0.106654 0.315876 0.942787 + outer loop + vertex 1.47365 2.08316 2.4858 + vertex 1.46962 2.08397 2.48599 + vertex 1.47145 2.07985 2.48716 + endloop + endfacet + facet normal 0.110549 0.31805 0.941607 + outer loop + vertex 1.47349 2.08709 2.48449 + vertex 1.47799 2.0841 2.48498 + vertex 1.47808 2.08811 2.48361 + endloop + endfacet + facet normal 0.113756 0.313788 0.942654 + outer loop + vertex 1.47799 2.0841 2.48498 + vertex 1.47972 2.07985 2.48618 + vertex 1.48316 2.08288 2.48476 + endloop + endfacet + facet normal 0.114284 0.308362 0.944379 + outer loop + vertex 1.48107 2.07582 2.48733 + vertex 1.47972 2.07985 2.48618 + vertex 1.47581 2.07679 2.48765 + endloop + endfacet + facet normal 0.109641 0.314007 0.943069 + outer loop + vertex 1.47572 2.08074 2.48637 + vertex 1.47365 2.08316 2.4858 + vertex 1.47145 2.07985 2.48716 + endloop + endfacet + facet normal 0.109955 0.312143 0.943651 + outer loop + vertex 1.47126 2.076 2.48845 + vertex 1.47145 2.07985 2.48716 + vertex 1.46798 2.07745 2.48836 + endloop + endfacet + facet normal 0.115829 0.303136 0.945882 + outer loop + vertex 1.47352 2.06819 2.4907 + vertex 1.47791 2.06905 2.48989 + vertex 1.4734 2.07228 2.48941 + endloop + endfacet + facet normal 0.115661 0.301451 0.946441 + outer loop + vertex 1.48306 2.06781 2.48966 + vertex 1.48206 2.0718 2.4885 + vertex 1.47791 2.06905 2.48989 + endloop + endfacet + facet normal 0.113872 0.305851 0.945245 + outer loop + vertex 1.47806 2.07312 2.48857 + vertex 1.48107 2.07582 2.48733 + vertex 1.47581 2.07679 2.48765 + endloop + endfacet + facet normal 0.115111 0.303229 0.94594 + outer loop + vertex 1.48606 2.07055 2.48842 + vertex 1.48621 2.07462 2.4871 + vertex 1.48206 2.0718 2.4885 + endloop + endfacet + facet normal 0.114591 0.308447 0.944314 + outer loop + vertex 1.48453 2.07886 2.48592 + vertex 1.47972 2.07985 2.48618 + vertex 1.48107 2.07582 2.48733 + endloop + endfacet + facet normal 0.115381 0.311914 0.943079 + outer loop + vertex 1.48453 2.07886 2.48592 + vertex 1.48853 2.07804 2.4857 + vertex 1.48843 2.08202 2.4844 + endloop + endfacet + facet normal 0.114863 0.308822 0.944159 + outer loop + vertex 1.49289 2.07906 2.48484 + vertex 1.49458 2.07482 2.48601 + vertex 1.49804 2.07787 2.4846 + endloop + endfacet + facet normal 0.11481 0.304969 0.945417 + outer loop + vertex 1.49057 2.07564 2.48624 + vertex 1.48621 2.07462 2.4871 + vertex 1.49066 2.07163 2.48752 + endloop + endfacet + facet normal 0.115817 0.307834 0.944365 + outer loop + vertex 1.49458 2.07482 2.48601 + vertex 1.49941 2.07384 2.48574 + vertex 1.49804 2.07787 2.4846 + endloop + endfacet + facet normal 0.119675 0.310301 0.943075 + outer loop + vertex 1.5033 2.0769 2.48426 + vertex 1.50565 2.08141 2.48248 + vertex 1.50104 2.08056 2.48334 + endloop + endfacet + facet normal 0.118896 0.313543 0.942101 + outer loop + vertex 1.50114 2.08458 2.48199 + vertex 1.50104 2.08056 2.48334 + vertex 1.50565 2.08141 2.48248 + endloop + endfacet + facet normal 0.115457 0.311598 0.943174 + outer loop + vertex 1.49804 2.07787 2.4846 + vertex 1.49703 2.08184 2.48341 + vertex 1.49289 2.07906 2.48484 + endloop + endfacet + facet normal 0.114672 0.311923 0.943162 + outer loop + vertex 1.48853 2.07804 2.4857 + vertex 1.49289 2.07906 2.48484 + vertex 1.48843 2.08202 2.4844 + endloop + endfacet + facet normal 0.11636 0.316353 0.941478 + outer loop + vertex 1.48843 2.08202 2.4844 + vertex 1.4907 2.08663 2.48257 + vertex 1.48613 2.08559 2.48348 + endloop + endfacet + facet normal 0.11536 0.319846 0.94042 + outer loop + vertex 1.48622 2.0896 2.48211 + vertex 1.48613 2.08559 2.48348 + vertex 1.4907 2.08663 2.48257 + endloop + endfacet + facet normal 0.116147 0.321605 0.939723 + outer loop + vertex 1.48847 2.09295 2.48068 + vertex 1.48449 2.09383 2.48087 + vertex 1.48622 2.0896 2.48211 + endloop + endfacet + facet normal 0.114983 0.32174 0.93982 + outer loop + vertex 1.48449 2.09383 2.48087 + vertex 1.47966 2.09482 2.48112 + vertex 1.48105 2.09082 2.48232 + endloop + endfacet + facet normal 0.111513 0.320184 0.940769 + outer loop + vertex 1.47966 2.09482 2.48112 + vertex 1.47795 2.09906 2.47989 + vertex 1.47563 2.09565 2.48132 + endloop + endfacet + facet normal 0.11537 0.316037 0.941706 + outer loop + vertex 1.48837 2.09689 2.47935 + vertex 1.48611 2.10055 2.4784 + vertex 1.48312 2.09785 2.47967 + endloop + endfacet + facet normal 0.117414 0.311506 0.942962 + outer loop + vertex 1.48622 2.10458 2.47705 + vertex 1.48611 2.10055 2.4784 + vertex 1.49074 2.10139 2.47755 + endloop + endfacet + facet normal 0.111926 0.315353 0.942351 + outer loop + vertex 1.47795 2.09906 2.47989 + vertex 1.4821 2.10186 2.47846 + vertex 1.47809 2.1031 2.47852 + endloop + endfacet + facet normal 0.108174 0.322317 0.940431 + outer loop + vertex 1.47355 2.09804 2.48074 + vertex 1.47563 2.09565 2.48132 + vertex 1.47795 2.09906 2.47989 + endloop + endfacet + facet normal 0.103962 0.324108 0.94029 + outer loop + vertex 1.47355 2.09804 2.48074 + vertex 1.46949 2.09884 2.48091 + vertex 1.47123 2.09465 2.48217 + endloop + endfacet + facet normal 0.100256 0.322468 0.941256 + outer loop + vertex 1.46461 2.09975 2.48112 + vertex 1.46949 2.09884 2.48091 + vertex 1.46814 2.10281 2.4797 + endloop + endfacet + facet normal 0.100698 0.315615 0.943529 + outer loop + vertex 1.47347 2.10201 2.4794 + vertex 1.47576 2.10664 2.47761 + vertex 1.47118 2.10556 2.47846 + endloop + endfacet + facet normal 0.100879 0.315 0.943715 + outer loop + vertex 1.47122 2.1095 2.47714 + vertex 1.47118 2.10556 2.47846 + vertex 1.47576 2.10664 2.47761 + endloop + endfacet + facet normal 0.0985939 0.317123 0.943246 + outer loop + vertex 1.46814 2.10281 2.4797 + vertex 1.46713 2.10675 2.47848 + vertex 1.46291 2.10394 2.47986 + endloop + endfacet + facet normal 0.0997907 0.322951 0.94114 + outer loop + vertex 1.46291 2.10394 2.47986 + vertex 1.46461 2.09975 2.48112 + vertex 1.46814 2.10281 2.4797 + endloop + endfacet + facet normal 0.101251 0.326037 0.939919 + outer loop + vertex 1.46601 2.0958 2.48234 + vertex 1.46461 2.09975 2.48112 + vertex 1.46069 2.09662 2.48263 + endloop + endfacet + facet normal 0.104279 0.324914 0.939977 + outer loop + vertex 1.46054 2.10055 2.48128 + vertex 1.45848 2.10292 2.48069 + vertex 1.45618 2.09956 2.48211 + endloop + endfacet + facet normal 0.10597 0.323835 0.94016 + outer loop + vertex 1.45848 2.10292 2.48069 + vertex 1.45447 2.10375 2.48086 + vertex 1.45618 2.09956 2.48211 + endloop + endfacet + facet normal 0.105984 0.32384 0.940157 + outer loop + vertex 1.45618 2.09956 2.48211 + vertex 1.45447 2.10375 2.48086 + vertex 1.45102 2.10074 2.48228 + endloop + endfacet + facet normal 0.103606 0.324771 0.940101 + outer loop + vertex 1.45847 2.09205 2.48445 + vertex 1.46069 2.09662 2.48263 + vertex 1.45612 2.09558 2.48349 + endloop + endfacet + facet normal 0.104631 0.325367 0.939781 + outer loop + vertex 1.45847 2.09205 2.48445 + vertex 1.45612 2.09558 2.48349 + vertex 1.45319 2.09288 2.48475 + endloop + endfacet + facet normal 0.106307 0.325337 0.939604 + outer loop + vertex 1.4521 2.09681 2.48352 + vertex 1.45618 2.09956 2.48211 + vertex 1.45102 2.10074 2.48228 + endloop + endfacet + facet normal 0.0991775 0.321214 0.941799 + outer loop + vertex 1.44363 2.09307 2.48576 + vertex 1.43955 2.09388 2.48591 + vertex 1.44133 2.08968 2.48716 + endloop + endfacet + facet normal 0.104213 0.324574 0.940102 + outer loop + vertex 1.44346 2.09702 2.48442 + vertex 1.44801 2.09406 2.48493 + vertex 1.44806 2.09805 2.48355 + endloop + endfacet + facet normal 0.100875 0.320142 0.941984 + outer loop + vertex 1.44574 2.09068 2.48634 + vertex 1.44363 2.09307 2.48576 + vertex 1.44133 2.08968 2.48716 + endloop + endfacet + facet normal 0.10559 0.32247 0.940672 + outer loop + vertex 1.44801 2.09406 2.48493 + vertex 1.44978 2.08985 2.48618 + vertex 1.45319 2.09288 2.48475 + endloop + endfacet + facet normal 0.101134 0.319229 0.942266 + outer loop + vertex 1.44574 2.09068 2.48634 + vertex 1.44133 2.08968 2.48716 + vertex 1.44588 2.0867 2.48768 + endloop + endfacet + facet normal 0.105102 0.319884 0.941609 + outer loop + vertex 1.45461 2.08892 2.48595 + vertex 1.44978 2.08985 2.48618 + vertex 1.45118 2.08588 2.48737 + endloop + endfacet + facet normal 0.104233 0.318188 0.94228 + outer loop + vertex 1.45218 2.08196 2.48858 + vertex 1.45631 2.08473 2.48719 + vertex 1.45118 2.08588 2.48737 + endloop + endfacet + facet normal 0.104217 0.318209 0.942275 + outer loop + vertex 1.45606 2.08082 2.48854 + vertex 1.45631 2.08473 2.48719 + vertex 1.45218 2.08196 2.48858 + endloop + endfacet + facet normal 0.10279 0.31834 0.942387 + outer loop + vertex 1.45631 2.08473 2.48719 + vertex 1.45606 2.08082 2.48854 + vertex 1.46075 2.08165 2.48774 + endloop + endfacet + facet normal 0.103281 0.317851 0.942499 + outer loop + vertex 1.46629 2.08081 2.48742 + vertex 1.46474 2.08489 2.48621 + vertex 1.46075 2.08165 2.48774 + endloop + endfacet + facet normal 0.106665 0.316383 0.942616 + outer loop + vertex 1.46798 2.07745 2.48836 + vertex 1.47145 2.07985 2.48716 + vertex 1.46629 2.08081 2.48742 + endloop + endfacet + facet normal 0.109275 0.310645 0.944224 + outer loop + vertex 1.46774 2.07361 2.48965 + vertex 1.47126 2.076 2.48845 + vertex 1.46798 2.07745 2.48836 + endloop + endfacet + facet normal 0.104104 0.313547 0.943849 + outer loop + vertex 1.45936 2.07358 2.4906 + vertex 1.46339 2.07281 2.49041 + vertex 1.46332 2.07684 2.48908 + endloop + endfacet + facet normal 0.103339 0.314687 0.943553 + outer loop + vertex 1.45453 2.07429 2.49089 + vertex 1.45936 2.07358 2.4906 + vertex 1.45786 2.07758 2.48943 + endloop + endfacet + facet normal 0.104283 0.305149 0.946577 + outer loop + vertex 1.45709 2.06624 2.49323 + vertex 1.46113 2.06935 2.49179 + vertex 1.45592 2.07031 2.49205 + endloop + endfacet + facet normal 0.106839 0.301533 0.947451 + outer loop + vertex 1.45869 2.06197 2.49441 + vertex 1.45709 2.06624 2.49323 + vertex 1.4534 2.06304 2.49467 + endloop + endfacet + facet normal 0.1079 0.301172 0.947446 + outer loop + vertex 1.44975 2.05984 2.4961 + vertex 1.45461 2.05887 2.49586 + vertex 1.4534 2.06304 2.49467 + endloop + endfacet + facet normal 0.106853 0.300414 0.947805 + outer loop + vertex 1.4457 2.06066 2.49631 + vertex 1.4413 2.05965 2.49712 + vertex 1.44579 2.05663 2.49757 + endloop + endfacet + facet normal 0.106275 0.302466 0.947217 + outer loop + vertex 1.4457 2.06066 2.49631 + vertex 1.44363 2.06308 2.49577 + vertex 1.4413 2.05965 2.49712 + endloop + endfacet + facet normal 0.107907 0.301207 0.947434 + outer loop + vertex 1.45461 2.05887 2.49586 + vertex 1.44975 2.05984 2.4961 + vertex 1.45107 2.05577 2.49724 + endloop + endfacet + facet normal 0.106124 0.300743 0.947782 + outer loop + vertex 1.45209 2.05177 2.4984 + vertex 1.45107 2.05577 2.49724 + vertex 1.44808 2.05301 2.49846 + endloop + endfacet + facet normal 0.104083 0.294032 0.950111 + outer loop + vertex 1.44797 2.04896 2.49972 + vertex 1.45209 2.05177 2.4984 + vertex 1.44808 2.05301 2.49846 + endloop + endfacet + facet normal 0.102963 0.286044 0.952669 + outer loop + vertex 1.44362 2.04794 2.5005 + vertex 1.44562 2.04555 2.501 + vertex 1.44797 2.04896 2.49972 + endloop + endfacet + facet normal 0.104242 0.287023 0.952235 + outer loop + vertex 1.44562 2.04555 2.501 + vertex 1.44362 2.04794 2.5005 + vertex 1.44122 2.04447 2.50181 + endloop + endfacet + facet normal 0.103408 0.287571 0.95216 + outer loop + vertex 1.44362 2.04794 2.5005 + vertex 1.43957 2.04876 2.50069 + vertex 1.44122 2.04447 2.50181 + endloop + endfacet + facet normal 0.104183 0.287826 0.951999 + outer loop + vertex 1.44122 2.04447 2.50181 + vertex 1.43957 2.04876 2.50069 + vertex 1.43592 2.04556 2.50206 + endloop + endfacet + facet normal 0.108345 0.309577 0.944682 + outer loop + vertex 1.43701 2.04131 2.50332 + vertex 1.44122 2.04447 2.50181 + vertex 1.43592 2.04556 2.50206 + endloop + endfacet + facet normal 0.106968 0.309299 0.94493 + outer loop + vertex 1.43701 2.04131 2.50332 + vertex 1.43592 2.04556 2.50206 + vertex 1.43212 2.04232 2.50355 + endloop + endfacet + facet normal 0.104384 0.312045 0.944316 + outer loop + vertex 1.43212 2.04232 2.50355 + vertex 1.43592 2.04556 2.50206 + vertex 1.4306 2.04666 2.50228 + endloop + endfacet + facet normal 0.099761 0.310697 0.945259 + outer loop + vertex 1.43212 2.04232 2.50355 + vertex 1.4306 2.04666 2.50228 + vertex 1.42807 2.04317 2.5037 + endloop + endfacet + facet normal 0.105914 0.342408 0.933563 + outer loop + vertex 1.4279 2.03914 2.50519 + vertex 1.43212 2.04232 2.50355 + vertex 1.42807 2.04317 2.5037 + endloop + endfacet + facet normal 0.107455 0.340611 0.934044 + outer loop + vertex 1.43325 2.03806 2.50497 + vertex 1.43212 2.04232 2.50355 + vertex 1.4279 2.03914 2.50519 + endloop + endfacet + facet normal 0.0943242 0.314377 0.944601 + outer loop + vertex 1.42807 2.04317 2.5037 + vertex 1.4306 2.04666 2.50228 + vertex 1.42613 2.04556 2.50309 + endloop + endfacet + facet normal 0.109727 0.325462 0.939167 + outer loop + vertex 1.42807 2.04317 2.5037 + vertex 1.42613 2.04556 2.50309 + vertex 1.4236 2.04205 2.5046 + endloop + endfacet + facet normal 0.0986999 0.299831 0.948873 + outer loop + vertex 1.42627 2.04946 2.50185 + vertex 1.42613 2.04556 2.50309 + vertex 1.4306 2.04666 2.50228 + endloop + endfacet + facet normal 0.092091 0.290175 0.952532 + outer loop + vertex 1.43068 2.05061 2.50107 + vertex 1.42627 2.04946 2.50185 + vertex 1.4306 2.04666 2.50228 + endloop + endfacet + facet normal 0.0989361 0.289854 0.951944 + outer loop + vertex 1.43068 2.05061 2.50107 + vertex 1.4306 2.04666 2.50228 + vertex 1.43471 2.04977 2.50091 + endloop + endfacet + facet normal 0.0990137 0.290249 0.951815 + outer loop + vertex 1.43471 2.04977 2.50091 + vertex 1.43301 2.05404 2.49978 + vertex 1.43068 2.05061 2.50107 + endloop + endfacet + facet normal 0.0952182 0.292693 0.951454 + outer loop + vertex 1.42863 2.05297 2.50055 + vertex 1.43068 2.05061 2.50107 + vertex 1.43301 2.05404 2.49978 + endloop + endfacet + facet normal 0.0994802 0.290409 0.951718 + outer loop + vertex 1.43301 2.05404 2.49978 + vertex 1.43471 2.04977 2.50091 + vertex 1.43821 2.05284 2.4996 + endloop + endfacet + facet normal 0.0920849 0.290195 0.952527 + outer loop + vertex 1.43068 2.05061 2.50107 + vertex 1.42863 2.05297 2.50055 + vertex 1.42627 2.04946 2.50185 + endloop + endfacet + facet normal 0.0998963 0.288694 0.952196 + outer loop + vertex 1.43592 2.04556 2.50206 + vertex 1.43471 2.04977 2.50091 + vertex 1.4306 2.04666 2.50228 + endloop + endfacet + facet normal 0.102716 0.289368 0.951691 + outer loop + vertex 1.43957 2.04876 2.50069 + vertex 1.43471 2.04977 2.50091 + vertex 1.43592 2.04556 2.50206 + endloop + endfacet + facet normal 0.10234 0.287408 0.952325 + outer loop + vertex 1.43471 2.04977 2.50091 + vertex 1.43957 2.04876 2.50069 + vertex 1.43821 2.05284 2.4996 + endloop + endfacet + facet normal 0.108553 0.295996 0.949001 + outer loop + vertex 1.4435 2.05196 2.49929 + vertex 1.44579 2.05663 2.49757 + vertex 1.44119 2.05559 2.49842 + endloop + endfacet + facet normal 0.107187 0.300883 0.947618 + outer loop + vertex 1.4413 2.05965 2.49712 + vertex 1.44119 2.05559 2.49842 + vertex 1.44579 2.05663 2.49757 + endloop + endfacet + facet normal 0.100619 0.295585 0.950003 + outer loop + vertex 1.43821 2.05284 2.4996 + vertex 1.43716 2.05686 2.49846 + vertex 1.43301 2.05404 2.49978 + endloop + endfacet + facet normal 0.0931087 0.299873 0.949425 + outer loop + vertex 1.42863 2.05297 2.50055 + vertex 1.43301 2.05404 2.49978 + vertex 1.4285 2.05694 2.49931 + endloop + endfacet + facet normal 0.0915005 0.30708 0.947275 + outer loop + vertex 1.4285 2.05694 2.49931 + vertex 1.43077 2.06166 2.49756 + vertex 1.42615 2.06045 2.4984 + endloop + endfacet + facet normal 0.0898424 0.306095 0.947752 + outer loop + vertex 1.4285 2.05694 2.49931 + vertex 1.42615 2.06045 2.4984 + vertex 1.42323 2.05753 2.49962 + endloop + endfacet + facet normal 0.0891779 0.298985 0.950082 + outer loop + vertex 1.42323 2.05753 2.49962 + vertex 1.42457 2.05362 2.50072 + vertex 1.4285 2.05694 2.49931 + endloop + endfacet + facet normal 0.0883634 0.299862 0.949881 + outer loop + vertex 1.42457 2.05362 2.50072 + vertex 1.42863 2.05297 2.50055 + vertex 1.4285 2.05694 2.49931 + endloop + endfacet + facet normal 0.0873884 0.293179 0.952055 + outer loop + vertex 1.42863 2.05297 2.50055 + vertex 1.42457 2.05362 2.50072 + vertex 1.42627 2.04946 2.50185 + endloop + endfacet + facet normal 0.0892541 0.293841 0.951678 + outer loop + vertex 1.42627 2.04946 2.50185 + vertex 1.42457 2.05362 2.50072 + vertex 1.421 2.05035 2.50207 + endloop + endfacet + facet normal 0.091403 0.307745 0.947068 + outer loop + vertex 1.42207 2.04631 2.50327 + vertex 1.42627 2.04946 2.50185 + vertex 1.421 2.05035 2.50207 + endloop + endfacet + facet normal 0.0979456 0.299878 0.948936 + outer loop + vertex 1.42613 2.04556 2.50309 + vertex 1.42627 2.04946 2.50185 + vertex 1.42207 2.04631 2.50327 + endloop + endfacet + facet normal 0.0879476 0.295151 0.951394 + outer loop + vertex 1.42457 2.05362 2.50072 + vertex 1.41971 2.05433 2.50095 + vertex 1.421 2.05035 2.50207 + endloop + endfacet + facet normal 0.089402 0.295551 0.951135 + outer loop + vertex 1.421 2.05035 2.50207 + vertex 1.41971 2.05433 2.50095 + vertex 1.41613 2.05115 2.50228 + endloop + endfacet + facet normal 0.0917261 0.31108 0.945947 + outer loop + vertex 1.41723 2.04724 2.50345 + vertex 1.421 2.05035 2.50207 + vertex 1.41613 2.05115 2.50228 + endloop + endfacet + facet normal 0.0937643 0.311548 0.945593 + outer loop + vertex 1.41723 2.04724 2.50345 + vertex 1.41613 2.05115 2.50228 + vertex 1.41311 2.0483 2.50352 + endloop + endfacet + facet normal 0.097945 0.307505 0.946492 + outer loop + vertex 1.41311 2.0483 2.50352 + vertex 1.41613 2.05115 2.50228 + vertex 1.41088 2.05179 2.50261 + endloop + endfacet + facet normal 0.112724 0.315788 0.94211 + outer loop + vertex 1.41311 2.0483 2.50352 + vertex 1.41088 2.05179 2.50261 + vertex 1.40847 2.04715 2.50445 + endloop + endfacet + facet normal 0.10443 0.342496 0.933697 + outer loop + vertex 1.40847 2.04715 2.50445 + vertex 1.41297 2.04425 2.50501 + vertex 1.41311 2.0483 2.50352 + endloop + endfacet + facet normal 0.112962 0.35468 0.928139 + outer loop + vertex 1.40858 2.04315 2.50597 + vertex 1.41297 2.04425 2.50501 + vertex 1.40847 2.04715 2.50445 + endloop + endfacet + facet normal 0.106813 0.35477 0.928832 + outer loop + vertex 1.40454 2.04389 2.50615 + vertex 1.40858 2.04315 2.50597 + vertex 1.40847 2.04715 2.50445 + endloop + endfacet + facet normal 0.107833 0.353693 0.929125 + outer loop + vertex 1.40318 2.04799 2.50475 + vertex 1.40454 2.04389 2.50615 + vertex 1.40847 2.04715 2.50445 + endloop + endfacet + facet normal 0.10502 0.333199 0.93699 + outer loop + vertex 1.40847 2.04715 2.50445 + vertex 1.40625 2.05071 2.50344 + vertex 1.40318 2.04799 2.50475 + endloop + endfacet + facet normal 0.111557 0.326577 0.938564 + outer loop + vertex 1.40318 2.04799 2.50475 + vertex 1.40625 2.05071 2.50344 + vertex 1.40224 2.05199 2.50347 + endloop + endfacet + facet normal 0.108399 0.326018 0.939128 + outer loop + vertex 1.40318 2.04799 2.50475 + vertex 1.40224 2.05199 2.50347 + vertex 1.39799 2.04926 2.5049 + endloop + endfacet + facet normal 0.112652 0.344207 0.932111 + outer loop + vertex 1.39799 2.04926 2.5049 + vertex 1.39966 2.04486 2.50633 + vertex 1.40318 2.04799 2.50475 + endloop + endfacet + facet normal 0.104097 0.352725 0.929919 + outer loop + vertex 1.39966 2.04486 2.50633 + vertex 1.40454 2.04389 2.50615 + vertex 1.40318 2.04799 2.50475 + endloop + endfacet + facet normal 0.0970008 0.314485 0.944294 + outer loop + vertex 1.40454 2.04389 2.50615 + vertex 1.39966 2.04486 2.50633 + vertex 1.40109 2.04052 2.50763 + endloop + endfacet + facet normal 0.0903783 0.320632 0.942882 + outer loop + vertex 1.40649 2.03959 2.50743 + vertex 1.40454 2.04389 2.50615 + vertex 1.40109 2.04052 2.50763 + endloop + endfacet + facet normal 0.0674851 0.179639 0.981415 + outer loop + vertex 1.40261 2.0364 2.50828 + vertex 1.40649 2.03959 2.50743 + vertex 1.40109 2.04052 2.50763 + endloop + endfacet + facet normal 0.0840588 0.310949 0.946702 + outer loop + vertex 1.40109 2.04052 2.50763 + vertex 1.39966 2.04486 2.50633 + vertex 1.39574 2.04155 2.50776 + endloop + endfacet + facet normal 0.0526586 0.142615 0.988376 + outer loop + vertex 1.39772 2.03708 2.5083 + vertex 1.40109 2.04052 2.50763 + vertex 1.39574 2.04155 2.50776 + endloop + endfacet + facet normal 0.0961913 0.297921 0.949732 + outer loop + vertex 1.39562 2.04579 2.50645 + vertex 1.39574 2.04155 2.50776 + vertex 1.39966 2.04486 2.50633 + endloop + endfacet + facet normal 0.101152 0.297907 0.949221 + outer loop + vertex 1.39562 2.04579 2.50645 + vertex 1.39133 2.04464 2.50727 + vertex 1.39574 2.04155 2.50776 + endloop + endfacet + facet normal 0.0478369 0.225556 0.973055 + outer loop + vertex 1.39133 2.04464 2.50727 + vertex 1.39149 2.04036 2.50825 + vertex 1.39574 2.04155 2.50776 + endloop + endfacet + facet normal 0.0912897 0.328188 0.940191 + outer loop + vertex 1.39562 2.04579 2.50645 + vertex 1.39357 2.04829 2.50577 + vertex 1.39133 2.04464 2.50727 + endloop + endfacet + facet normal 0.101856 0.322107 0.941208 + outer loop + vertex 1.39357 2.04829 2.50577 + vertex 1.38955 2.04901 2.50596 + vertex 1.39133 2.04464 2.50727 + endloop + endfacet + facet normal 0.098259 0.320882 0.942008 + outer loop + vertex 1.39133 2.04464 2.50727 + vertex 1.38955 2.04901 2.50596 + vertex 1.38622 2.04563 2.50746 + endloop + endfacet + facet normal 0.0791444 0.21645 0.973081 + outer loop + vertex 1.38747 2.04131 2.50832 + vertex 1.39133 2.04464 2.50727 + vertex 1.38622 2.04563 2.50746 + endloop + endfacet + facet normal 0.0867756 0.331113 0.939593 + outer loop + vertex 1.38955 2.04901 2.50596 + vertex 1.38468 2.04967 2.50618 + vertex 1.38622 2.04563 2.50746 + endloop + endfacet + facet normal 0.0822103 0.329667 0.940511 + outer loop + vertex 1.38622 2.04563 2.50746 + vertex 1.38468 2.04967 2.50618 + vertex 1.38133 2.04606 2.50774 + endloop + endfacet + facet normal 0.0868079 0.331382 0.939495 + outer loop + vertex 1.38468 2.04967 2.50618 + vertex 1.38955 2.04901 2.50596 + vertex 1.3882 2.05289 2.50472 + endloop + endfacet + facet normal 0.0753242 0.342575 0.936466 + outer loop + vertex 1.3833 2.05356 2.50487 + vertex 1.38468 2.04967 2.50618 + vertex 1.3882 2.05289 2.50472 + endloop + endfacet + facet normal 0.0716814 0.313673 0.946822 + outer loop + vertex 1.3882 2.05289 2.50472 + vertex 1.38704 2.05664 2.50357 + vertex 1.3833 2.05356 2.50487 + endloop + endfacet + facet normal 0.085978 0.317349 0.944403 + outer loop + vertex 1.3882 2.05289 2.50472 + vertex 1.39122 2.05572 2.50349 + vertex 1.38704 2.05664 2.50357 + endloop + endfacet + facet normal 0.0826567 0.301682 0.949819 + outer loop + vertex 1.39122 2.05572 2.50349 + vertex 1.39137 2.0597 2.50222 + vertex 1.38704 2.05664 2.50357 + endloop + endfacet + facet normal 0.0756334 0.310604 0.947526 + outer loop + vertex 1.38704 2.05664 2.50357 + vertex 1.39137 2.0597 2.50222 + vertex 1.386 2.06045 2.5024 + endloop + endfacet + facet normal 0.0612993 0.307346 0.949622 + outer loop + vertex 1.38704 2.05664 2.50357 + vertex 1.386 2.06045 2.5024 + vertex 1.38225 2.05731 2.50366 + endloop + endfacet + facet normal 0.0746245 0.302791 0.950131 + outer loop + vertex 1.39137 2.0597 2.50222 + vertex 1.38968 2.06381 2.50104 + vertex 1.386 2.06045 2.5024 + endloop + endfacet + facet normal 0.0797645 0.304618 0.949129 + outer loop + vertex 1.39381 2.06322 2.50088 + vertex 1.38968 2.06381 2.50104 + vertex 1.39137 2.0597 2.50222 + endloop + endfacet + facet normal 0.0901796 0.297855 0.950342 + outer loop + vertex 1.39588 2.06087 2.50142 + vertex 1.39381 2.06322 2.50088 + vertex 1.39137 2.0597 2.50222 + endloop + endfacet + facet normal 0.0918589 0.29243 0.951865 + outer loop + vertex 1.39588 2.06087 2.50142 + vertex 1.39137 2.0597 2.50222 + vertex 1.39594 2.05687 2.50264 + endloop + endfacet + facet normal 0.10127 0.292287 0.950953 + outer loop + vertex 1.39588 2.06087 2.50142 + vertex 1.39594 2.05687 2.50264 + vertex 1.39998 2.06004 2.50124 + endloop + endfacet + facet normal 0.102773 0.300307 0.94829 + outer loop + vertex 1.39998 2.06004 2.50124 + vertex 1.39825 2.06432 2.50007 + vertex 1.39588 2.06087 2.50142 + endloop + endfacet + facet normal 0.101504 0.299869 0.948565 + outer loop + vertex 1.39825 2.06432 2.50007 + vertex 1.39998 2.06004 2.50124 + vertex 1.40357 2.06317 2.49986 + endloop + endfacet + facet normal 0.103375 0.309122 0.945387 + outer loop + vertex 1.40357 2.06317 2.49986 + vertex 1.4023 2.06737 2.49863 + vertex 1.39825 2.06432 2.50007 + endloop + endfacet + facet normal 0.102706 0.309922 0.945198 + outer loop + vertex 1.39825 2.06432 2.50007 + vertex 1.4023 2.06737 2.49863 + vertex 1.39825 2.06825 2.49878 + endloop + endfacet + facet normal 0.0941903 0.310202 0.945993 + outer loop + vertex 1.39383 2.0671 2.4996 + vertex 1.39825 2.06432 2.50007 + vertex 1.39825 2.06825 2.49878 + endloop + endfacet + facet normal 0.0939117 0.311087 0.94573 + outer loop + vertex 1.39825 2.06825 2.49878 + vertex 1.39622 2.07061 2.49821 + vertex 1.39383 2.0671 2.4996 + endloop + endfacet + facet normal 0.0865402 0.315764 0.944883 + outer loop + vertex 1.39383 2.0671 2.4996 + vertex 1.39622 2.07061 2.49821 + vertex 1.39212 2.07125 2.49837 + endloop + endfacet + facet normal 0.0761433 0.312104 0.946992 + outer loop + vertex 1.39383 2.0671 2.4996 + vertex 1.39212 2.07125 2.49837 + vertex 1.38845 2.06778 2.49981 + endloop + endfacet + facet normal 0.0766562 0.316664 0.945435 + outer loop + vertex 1.38845 2.06778 2.49981 + vertex 1.38968 2.06381 2.50104 + vertex 1.39383 2.0671 2.4996 + endloop + endfacet + facet normal 0.0678944 0.320005 0.94498 + outer loop + vertex 1.38845 2.06778 2.49981 + vertex 1.39212 2.07125 2.49837 + vertex 1.38712 2.07172 2.49857 + endloop + endfacet + facet normal 0.0675004 0.315082 0.946661 + outer loop + vertex 1.39212 2.07125 2.49837 + vertex 1.39089 2.07524 2.49713 + vertex 1.38712 2.07172 2.49857 + endloop + endfacet + facet normal 0.0606468 0.321698 0.944898 + outer loop + vertex 1.38712 2.07172 2.49857 + vertex 1.39089 2.07524 2.49713 + vertex 1.38586 2.07558 2.49734 + endloop + endfacet + facet normal 0.0603496 0.316012 0.946834 + outer loop + vertex 1.39089 2.07524 2.49713 + vertex 1.38957 2.07915 2.49591 + vertex 1.38586 2.07558 2.49734 + endloop + endfacet + facet normal 0.0845025 0.319427 0.943836 + outer loop + vertex 1.39212 2.07125 2.49837 + vertex 1.39622 2.0745 2.4969 + vertex 1.39089 2.07524 2.49713 + endloop + endfacet + facet normal 0.0836252 0.312389 0.946266 + outer loop + vertex 1.39622 2.0745 2.4969 + vertex 1.39449 2.07867 2.49568 + vertex 1.39089 2.07524 2.49713 + endloop + endfacet + facet normal 0.0951018 0.316438 0.943834 + outer loop + vertex 1.39855 2.07799 2.4955 + vertex 1.39449 2.07867 2.49568 + vertex 1.39622 2.0745 2.4969 + endloop + endfacet + facet normal 0.101287 0.31257 0.944479 + outer loop + vertex 1.40059 2.07558 2.49608 + vertex 1.39855 2.07799 2.4955 + vertex 1.39622 2.0745 2.4969 + endloop + endfacet + facet normal 0.100323 0.315749 0.943524 + outer loop + vertex 1.40059 2.07558 2.49608 + vertex 1.39622 2.0745 2.4969 + vertex 1.40059 2.07166 2.49739 + endloop + endfacet + facet normal 0.105239 0.315593 0.943041 + outer loop + vertex 1.40059 2.07558 2.49608 + vertex 1.40059 2.07166 2.49739 + vertex 1.4046 2.07466 2.49594 + endloop + endfacet + facet normal 0.105363 0.31617 0.942834 + outer loop + vertex 1.4046 2.07466 2.49594 + vertex 1.40293 2.07894 2.49469 + vertex 1.40059 2.07558 2.49608 + endloop + endfacet + facet normal 0.103851 0.315676 0.943167 + outer loop + vertex 1.40293 2.07894 2.49469 + vertex 1.4046 2.07466 2.49594 + vertex 1.4081 2.07768 2.49454 + endloop + endfacet + facet normal 0.10424 0.317343 0.942564 + outer loop + vertex 1.4081 2.07768 2.49454 + vertex 1.40708 2.08165 2.49332 + vertex 1.40293 2.07894 2.49469 + endloop + endfacet + facet normal 0.105242 0.315984 0.942909 + outer loop + vertex 1.40293 2.07894 2.49469 + vertex 1.40708 2.08165 2.49332 + vertex 1.40306 2.08296 2.49333 + endloop + endfacet + facet normal 0.105335 0.315978 0.942901 + outer loop + vertex 1.39846 2.08195 2.49418 + vertex 1.40293 2.07894 2.49469 + vertex 1.40306 2.08296 2.49333 + endloop + endfacet + facet normal 0.105608 0.316358 0.942743 + outer loop + vertex 1.39855 2.07799 2.4955 + vertex 1.40293 2.07894 2.49469 + vertex 1.39846 2.08195 2.49418 + endloop + endfacet + facet normal 0.105261 0.316042 0.942888 + outer loop + vertex 1.40708 2.08165 2.49332 + vertex 1.40603 2.08564 2.4921 + vertex 1.40306 2.08296 2.49333 + endloop + endfacet + facet normal 0.106297 0.314999 0.943121 + outer loop + vertex 1.40306 2.08296 2.49333 + vertex 1.40603 2.08564 2.4921 + vertex 1.40075 2.08656 2.49239 + endloop + endfacet + facet normal 0.101149 0.315184 0.943625 + outer loop + vertex 1.40708 2.08165 2.49332 + vertex 1.41122 2.08442 2.49195 + vertex 1.40603 2.08564 2.4921 + endloop + endfacet + facet normal 0.101687 0.317593 0.942759 + outer loop + vertex 1.41122 2.08442 2.49195 + vertex 1.40945 2.08868 2.4907 + vertex 1.40603 2.08564 2.4921 + endloop + endfacet + facet normal 0.104697 0.314534 0.943455 + outer loop + vertex 1.40945 2.08868 2.4907 + vertex 1.40458 2.08965 2.49092 + vertex 1.40603 2.08564 2.4921 + endloop + endfacet + facet normal 0.0989437 0.316632 0.943374 + outer loop + vertex 1.41353 2.08784 2.49056 + vertex 1.40945 2.08868 2.4907 + vertex 1.41122 2.08442 2.49195 + endloop + endfacet + facet normal 0.0950592 0.319077 0.942949 + outer loop + vertex 1.41561 2.08545 2.49116 + vertex 1.41353 2.08784 2.49056 + vertex 1.41122 2.08442 2.49195 + endloop + endfacet + facet normal 0.0953462 0.318085 0.943256 + outer loop + vertex 1.41561 2.08545 2.49116 + vertex 1.41122 2.08442 2.49195 + vertex 1.41573 2.08149 2.49248 + endloop + endfacet + facet normal 0.0925199 0.318091 0.943535 + outer loop + vertex 1.41561 2.08545 2.49116 + vertex 1.41573 2.08149 2.49248 + vertex 1.41966 2.08469 2.49102 + endloop + endfacet + facet normal 0.0926592 0.318888 0.943252 + outer loop + vertex 1.41966 2.08469 2.49102 + vertex 1.41793 2.08887 2.48977 + vertex 1.41561 2.08545 2.49116 + endloop + endfacet + facet normal 0.0933686 0.319136 0.943098 + outer loop + vertex 1.41793 2.08887 2.48977 + vertex 1.41966 2.08469 2.49102 + vertex 1.42312 2.08777 2.48963 + endloop + endfacet + facet normal 0.0931381 0.317408 0.943704 + outer loop + vertex 1.42107 2.08073 2.49221 + vertex 1.41966 2.08469 2.49102 + vertex 1.41573 2.08149 2.49248 + endloop + endfacet + facet normal 0.0928945 0.315474 0.944376 + outer loop + vertex 1.41805 2.07796 2.49343 + vertex 1.42107 2.08073 2.49221 + vertex 1.41573 2.08149 2.49248 + endloop + endfacet + facet normal 0.094272 0.316268 0.943974 + outer loop + vertex 1.41805 2.07796 2.49343 + vertex 1.41573 2.08149 2.49248 + vertex 1.41341 2.07685 2.49427 + endloop + endfacet + facet normal 0.0952343 0.312986 0.944971 + outer loop + vertex 1.41341 2.07685 2.49427 + vertex 1.41791 2.07392 2.49478 + vertex 1.41805 2.07796 2.49343 + endloop + endfacet + facet normal 0.0939129 0.313065 0.945077 + outer loop + vertex 1.41791 2.07392 2.49478 + vertex 1.42211 2.07677 2.49342 + vertex 1.41805 2.07796 2.49343 + endloop + endfacet + facet normal 0.0948569 0.311824 0.945393 + outer loop + vertex 1.42313 2.07279 2.49463 + vertex 1.42211 2.07677 2.49342 + vertex 1.41791 2.07392 2.49478 + endloop + endfacet + facet normal 0.0947442 0.311279 0.945584 + outer loop + vertex 1.41791 2.07392 2.49478 + vertex 1.4196 2.06969 2.49601 + vertex 1.42313 2.07279 2.49463 + endloop + endfacet + facet normal 0.094506 0.311525 0.945527 + outer loop + vertex 1.4196 2.06969 2.49601 + vertex 1.42448 2.06877 2.49582 + vertex 1.42313 2.07279 2.49463 + endloop + endfacet + facet normal 0.0920061 0.310824 0.946004 + outer loop + vertex 1.42313 2.07279 2.49463 + vertex 1.42448 2.06877 2.49582 + vertex 1.42847 2.072 2.49437 + endloop + endfacet + facet normal 0.0921899 0.312224 0.945525 + outer loop + vertex 1.42847 2.072 2.49437 + vertex 1.42617 2.07557 2.49342 + vertex 1.42313 2.07279 2.49463 + endloop + endfacet + facet normal 0.0924455 0.312369 0.945452 + outer loop + vertex 1.42847 2.072 2.49437 + vertex 1.43081 2.07666 2.4926 + vertex 1.42617 2.07557 2.49342 + endloop + endfacet + facet normal 0.092122 0.31349 0.945112 + outer loop + vertex 1.42629 2.07961 2.49207 + vertex 1.42617 2.07557 2.49342 + vertex 1.43081 2.07666 2.4926 + endloop + endfacet + facet normal 0.0930276 0.314785 0.944593 + outer loop + vertex 1.4307 2.08065 2.49129 + vertex 1.42629 2.07961 2.49207 + vertex 1.43081 2.07666 2.4926 + endloop + endfacet + facet normal 0.0934243 0.314783 0.944555 + outer loop + vertex 1.4307 2.08065 2.49129 + vertex 1.43081 2.07666 2.4926 + vertex 1.43476 2.07984 2.49115 + endloop + endfacet + facet normal 0.0939511 0.317604 0.943558 + outer loop + vertex 1.43476 2.07984 2.49115 + vertex 1.433 2.08406 2.48991 + vertex 1.4307 2.08065 2.49129 + endloop + endfacet + facet normal 0.0925207 0.31653 0.94406 + outer loop + vertex 1.4307 2.08065 2.49129 + vertex 1.4286 2.08303 2.49069 + vertex 1.42629 2.07961 2.49207 + endloop + endfacet + facet normal 0.093563 0.313407 0.944998 + outer loop + vertex 1.42617 2.07557 2.49342 + vertex 1.42629 2.07961 2.49207 + vertex 1.42211 2.07677 2.49342 + endloop + endfacet + facet normal 0.0931656 0.313929 0.944864 + outer loop + vertex 1.42211 2.07677 2.49342 + vertex 1.42629 2.07961 2.49207 + vertex 1.42107 2.08073 2.49221 + endloop + endfacet + facet normal 0.0937091 0.316586 0.943924 + outer loop + vertex 1.42629 2.07961 2.49207 + vertex 1.42453 2.08381 2.49083 + vertex 1.42107 2.08073 2.49221 + endloop + endfacet + facet normal 0.0905162 0.313294 0.945333 + outer loop + vertex 1.43311 2.07309 2.49357 + vertex 1.43081 2.07666 2.4926 + vertex 1.42847 2.072 2.49437 + endloop + endfacet + facet normal 0.0907849 0.312359 0.945616 + outer loop + vertex 1.42847 2.072 2.49437 + vertex 1.43298 2.06907 2.49491 + vertex 1.43311 2.07309 2.49357 + endloop + endfacet + facet normal 0.0903469 0.311731 0.945865 + outer loop + vertex 1.42856 2.06802 2.49568 + vertex 1.43298 2.06907 2.49491 + vertex 1.42847 2.072 2.49437 + endloop + endfacet + facet normal 0.0926579 0.314512 0.94472 + outer loop + vertex 1.43311 2.07309 2.49357 + vertex 1.43615 2.07584 2.49235 + vertex 1.43081 2.07666 2.4926 + endloop + endfacet + facet normal 0.0927921 0.315489 0.944382 + outer loop + vertex 1.43615 2.07584 2.49235 + vertex 1.43476 2.07984 2.49115 + vertex 1.43081 2.07666 2.4926 + endloop + endfacet + facet normal 0.0955906 0.316293 0.943833 + outer loop + vertex 1.43964 2.0789 2.49097 + vertex 1.43476 2.07984 2.49115 + vertex 1.43615 2.07584 2.49235 + endloop + endfacet + facet normal 0.0957502 0.317177 0.94352 + outer loop + vertex 1.43476 2.07984 2.49115 + vertex 1.43964 2.0789 2.49097 + vertex 1.43824 2.0829 2.48977 + endloop + endfacet + facet normal 0.0949808 0.317966 0.943332 + outer loop + vertex 1.433 2.08406 2.48991 + vertex 1.43476 2.07984 2.49115 + vertex 1.43824 2.0829 2.48977 + endloop + endfacet + facet normal 0.0951374 0.318704 0.943068 + outer loop + vertex 1.43824 2.0829 2.48977 + vertex 1.43716 2.08687 2.48854 + vertex 1.433 2.08406 2.48991 + endloop + endfacet + facet normal 0.0932092 0.313961 0.944849 + outer loop + vertex 1.43717 2.07187 2.49357 + vertex 1.43615 2.07584 2.49235 + vertex 1.43311 2.07309 2.49357 + endloop + endfacet + facet normal 0.0969805 0.314738 0.944211 + outer loop + vertex 1.43717 2.07187 2.49357 + vertex 1.44137 2.07467 2.49221 + vertex 1.43615 2.07584 2.49235 + endloop + endfacet + facet normal 0.0970015 0.314836 0.944176 + outer loop + vertex 1.44137 2.07467 2.49221 + vertex 1.43964 2.0789 2.49097 + vertex 1.43615 2.07584 2.49235 + endloop + endfacet + facet normal 0.0911962 0.311726 0.945786 + outer loop + vertex 1.42448 2.06877 2.49582 + vertex 1.42856 2.06802 2.49568 + vertex 1.42847 2.072 2.49437 + endloop + endfacet + facet normal 0.0911547 0.311486 0.945869 + outer loop + vertex 1.42856 2.06802 2.49568 + vertex 1.42448 2.06877 2.49582 + vertex 1.42622 2.06453 2.49705 + endloop + endfacet + facet normal 0.0899511 0.312241 0.945735 + outer loop + vertex 1.43065 2.06565 2.49626 + vertex 1.42856 2.06802 2.49568 + vertex 1.42622 2.06453 2.49705 + endloop + endfacet + facet normal 0.0931515 0.31218 0.945445 + outer loop + vertex 1.42622 2.06453 2.49705 + vertex 1.42448 2.06877 2.49582 + vertex 1.42087 2.06557 2.49723 + endloop + endfacet + facet normal 0.0926591 0.309494 0.946376 + outer loop + vertex 1.42202 2.06147 2.49846 + vertex 1.42622 2.06453 2.49705 + vertex 1.42087 2.06557 2.49723 + endloop + endfacet + facet normal 0.0961733 0.3103 0.945761 + outer loop + vertex 1.42202 2.06147 2.49846 + vertex 1.42087 2.06557 2.49723 + vertex 1.41723 2.06237 2.49865 + endloop + endfacet + facet normal 0.0975509 0.308876 0.946086 + outer loop + vertex 1.41723 2.06237 2.49865 + vertex 1.42087 2.06557 2.49723 + vertex 1.41557 2.06659 2.49745 + endloop + endfacet + facet normal 0.101465 0.310178 0.945248 + outer loop + vertex 1.41723 2.06237 2.49865 + vertex 1.41557 2.06659 2.49745 + vertex 1.41323 2.06313 2.49884 + endloop + endfacet + facet normal 0.100121 0.302388 0.947912 + outer loop + vertex 1.41319 2.05923 2.50008 + vertex 1.41723 2.06237 2.49865 + vertex 1.41323 2.06313 2.49884 + endloop + endfacet + facet normal 0.102725 0.302288 0.947665 + outer loop + vertex 1.40887 2.06204 2.49965 + vertex 1.41319 2.05923 2.50008 + vertex 1.41323 2.06313 2.49884 + endloop + endfacet + facet normal 0.100826 0.308532 0.945855 + outer loop + vertex 1.41323 2.06313 2.49884 + vertex 1.41121 2.06548 2.49828 + vertex 1.40887 2.06204 2.49965 + endloop + endfacet + facet normal 0.101823 0.307894 0.945956 + outer loop + vertex 1.40887 2.06204 2.49965 + vertex 1.41121 2.06548 2.49828 + vertex 1.40718 2.06631 2.49845 + endloop + endfacet + facet normal 0.10344 0.308436 0.945604 + outer loop + vertex 1.40887 2.06204 2.49965 + vertex 1.40718 2.06631 2.49845 + vertex 1.40357 2.06317 2.49986 + endloop + endfacet + facet normal 0.101262 0.297571 0.949314 + outer loop + vertex 1.40357 2.06317 2.49986 + vertex 1.40485 2.05899 2.50104 + vertex 1.40887 2.06204 2.49965 + endloop + endfacet + facet normal 0.101171 0.29768 0.94929 + outer loop + vertex 1.40485 2.05899 2.50104 + vertex 1.40885 2.05811 2.50089 + vertex 1.40887 2.06204 2.49965 + endloop + endfacet + facet normal 0.0991101 0.287736 0.952568 + outer loop + vertex 1.40885 2.05811 2.50089 + vertex 1.40485 2.05899 2.50104 + vertex 1.40647 2.05473 2.50216 + endloop + endfacet + facet normal 0.0982897 0.288284 0.952487 + outer loop + vertex 1.41086 2.05574 2.5014 + vertex 1.40885 2.05811 2.50089 + vertex 1.40647 2.05473 2.50216 + endloop + endfacet + facet normal 0.0971505 0.292359 0.951361 + outer loop + vertex 1.41086 2.05574 2.5014 + vertex 1.40647 2.05473 2.50216 + vertex 1.41088 2.05179 2.50261 + endloop + endfacet + facet normal 0.0977078 0.292346 0.951308 + outer loop + vertex 1.41086 2.05574 2.5014 + vertex 1.41088 2.05179 2.50261 + vertex 1.41487 2.05506 2.5012 + endloop + endfacet + facet normal 0.0978627 0.293346 0.950984 + outer loop + vertex 1.41487 2.05506 2.5012 + vertex 1.41319 2.05923 2.50008 + vertex 1.41086 2.05574 2.5014 + endloop + endfacet + facet normal 0.0967295 0.292954 0.951221 + outer loop + vertex 1.41319 2.05923 2.50008 + vertex 1.41487 2.05506 2.5012 + vertex 1.41839 2.05832 2.49983 + endloop + endfacet + facet normal 0.0929079 0.296744 0.950427 + outer loop + vertex 1.41487 2.05506 2.5012 + vertex 1.41971 2.05433 2.50095 + vertex 1.41839 2.05832 2.49983 + endloop + endfacet + facet normal 0.0909694 0.296203 0.950783 + outer loop + vertex 1.41839 2.05832 2.49983 + vertex 1.41971 2.05433 2.50095 + vertex 1.42323 2.05753 2.49962 + endloop + endfacet + facet normal 0.0924255 0.306082 0.947508 + outer loop + vertex 1.42323 2.05753 2.49962 + vertex 1.42202 2.06147 2.49846 + vertex 1.41839 2.05832 2.49983 + endloop + endfacet + facet normal 0.09497 0.30341 0.948116 + outer loop + vertex 1.41839 2.05832 2.49983 + vertex 1.42202 2.06147 2.49846 + vertex 1.41723 2.06237 2.49865 + endloop + endfacet + facet normal 0.100321 0.296862 0.949636 + outer loop + vertex 1.40647 2.05473 2.50216 + vertex 1.40625 2.05071 2.50344 + vertex 1.41088 2.05179 2.50261 + endloop + endfacet + facet normal 0.101688 0.290913 0.95133 + outer loop + vertex 1.40885 2.05811 2.50089 + vertex 1.41086 2.05574 2.5014 + vertex 1.41319 2.05923 2.50008 + endloop + endfacet + facet normal 0.101426 0.288493 0.952095 + outer loop + vertex 1.40647 2.05473 2.50216 + vertex 1.40485 2.05899 2.50104 + vertex 1.4013 2.05598 2.50233 + endloop + endfacet + facet normal 0.103023 0.295384 0.949808 + outer loop + vertex 1.40224 2.05199 2.50347 + vertex 1.40647 2.05473 2.50216 + vertex 1.4013 2.05598 2.50233 + endloop + endfacet + facet normal 0.103926 0.295555 0.949656 + outer loop + vertex 1.40224 2.05199 2.50347 + vertex 1.4013 2.05598 2.50233 + vertex 1.39821 2.0533 2.5035 + endloop + endfacet + facet normal 0.10464 0.294801 0.949812 + outer loop + vertex 1.39821 2.0533 2.5035 + vertex 1.4013 2.05598 2.50233 + vertex 1.39594 2.05687 2.50264 + endloop + endfacet + facet normal 0.112284 0.299128 0.947584 + outer loop + vertex 1.39821 2.0533 2.5035 + vertex 1.39594 2.05687 2.50264 + vertex 1.39352 2.05227 2.50438 + endloop + endfacet + facet normal 0.106109 0.32146 0.940959 + outer loop + vertex 1.39352 2.05227 2.50438 + vertex 1.39799 2.04926 2.5049 + vertex 1.39821 2.0533 2.5035 + endloop + endfacet + facet normal 0.111647 0.329135 0.937659 + outer loop + vertex 1.39357 2.04829 2.50577 + vertex 1.39799 2.04926 2.5049 + vertex 1.39352 2.05227 2.50438 + endloop + endfacet + facet normal 0.0952493 0.307732 0.946693 + outer loop + vertex 1.39352 2.05227 2.50438 + vertex 1.39594 2.05687 2.50264 + vertex 1.39122 2.05572 2.50349 + endloop + endfacet + facet normal 0.101309 0.288619 0.952069 + outer loop + vertex 1.40485 2.05899 2.50104 + vertex 1.39998 2.06004 2.50124 + vertex 1.4013 2.05598 2.50233 + endloop + endfacet + facet normal 0.102911 0.313552 0.943978 + outer loop + vertex 1.41121 2.06548 2.49828 + vertex 1.4112 2.0694 2.49698 + vertex 1.40718 2.06631 2.49845 + endloop + endfacet + facet normal 0.10225 0.314325 0.943793 + outer loop + vertex 1.40718 2.06631 2.49845 + vertex 1.4112 2.0694 2.49698 + vertex 1.40589 2.0705 2.49719 + endloop + endfacet + facet normal 0.104069 0.314779 0.943442 + outer loop + vertex 1.40718 2.06631 2.49845 + vertex 1.40589 2.0705 2.49719 + vertex 1.4023 2.06737 2.49863 + endloop + endfacet + facet normal 0.104055 0.314794 0.943439 + outer loop + vertex 1.4023 2.06737 2.49863 + vertex 1.40589 2.0705 2.49719 + vertex 1.40059 2.07166 2.49739 + endloop + endfacet + facet normal 0.102554 0.315911 0.94323 + outer loop + vertex 1.4112 2.0694 2.49698 + vertex 1.40945 2.07365 2.49575 + vertex 1.40589 2.0705 2.49719 + endloop + endfacet + facet normal 0.102407 0.316062 0.943195 + outer loop + vertex 1.40945 2.07365 2.49575 + vertex 1.4046 2.07466 2.49594 + vertex 1.40589 2.0705 2.49719 + endloop + endfacet + facet normal 0.101057 0.313605 0.944161 + outer loop + vertex 1.4112 2.0694 2.49698 + vertex 1.41121 2.06548 2.49828 + vertex 1.41557 2.06659 2.49745 + endloop + endfacet + facet normal 0.100319 0.312531 0.944595 + outer loop + vertex 1.41556 2.0705 2.49616 + vertex 1.4112 2.0694 2.49698 + vertex 1.41557 2.06659 2.49745 + endloop + endfacet + facet normal 0.0974033 0.312619 0.944872 + outer loop + vertex 1.41556 2.0705 2.49616 + vertex 1.41557 2.06659 2.49745 + vertex 1.4196 2.06969 2.49601 + endloop + endfacet + facet normal 0.0995856 0.297735 0.94944 + outer loop + vertex 1.40885 2.05811 2.50089 + vertex 1.41319 2.05923 2.50008 + vertex 1.40887 2.06204 2.49965 + endloop + endfacet + facet normal 0.0985231 0.304243 0.947486 + outer loop + vertex 1.41839 2.05832 2.49983 + vertex 1.41723 2.06237 2.49865 + vertex 1.41319 2.05923 2.50008 + endloop + endfacet + facet normal 0.102285 0.309656 0.945331 + outer loop + vertex 1.41323 2.06313 2.49884 + vertex 1.41557 2.06659 2.49745 + vertex 1.41121 2.06548 2.49828 + endloop + endfacet + facet normal 0.098075 0.311835 0.945061 + outer loop + vertex 1.42087 2.06557 2.49723 + vertex 1.4196 2.06969 2.49601 + vertex 1.41557 2.06659 2.49745 + endloop + endfacet + facet normal 0.0916593 0.310725 0.94607 + outer loop + vertex 1.42615 2.06045 2.4984 + vertex 1.42622 2.06453 2.49705 + vertex 1.42202 2.06147 2.49846 + endloop + endfacet + facet normal 0.0943973 0.310904 0.945742 + outer loop + vertex 1.42448 2.06877 2.49582 + vertex 1.4196 2.06969 2.49601 + vertex 1.42087 2.06557 2.49723 + endloop + endfacet + facet normal 0.0973153 0.312146 0.945037 + outer loop + vertex 1.4196 2.06969 2.49601 + vertex 1.41791 2.07392 2.49478 + vertex 1.41556 2.0705 2.49616 + endloop + endfacet + facet normal 0.0969837 0.312359 0.945001 + outer loop + vertex 1.41351 2.07287 2.49558 + vertex 1.41556 2.0705 2.49616 + vertex 1.41791 2.07392 2.49478 + endloop + endfacet + facet normal 0.0997176 0.314492 0.944008 + outer loop + vertex 1.41556 2.0705 2.49616 + vertex 1.41351 2.07287 2.49558 + vertex 1.4112 2.0694 2.49698 + endloop + endfacet + facet normal 0.0992704 0.314771 0.943962 + outer loop + vertex 1.41351 2.07287 2.49558 + vertex 1.40945 2.07365 2.49575 + vertex 1.4112 2.0694 2.49698 + endloop + endfacet + facet normal 0.099229 0.314541 0.944043 + outer loop + vertex 1.40945 2.07365 2.49575 + vertex 1.41351 2.07287 2.49558 + vertex 1.41341 2.07685 2.49427 + endloop + endfacet + facet normal 0.0929816 0.311437 0.945707 + outer loop + vertex 1.42313 2.07279 2.49463 + vertex 1.42617 2.07557 2.49342 + vertex 1.42211 2.07677 2.49342 + endloop + endfacet + facet normal 0.0963334 0.314565 0.944335 + outer loop + vertex 1.41351 2.07287 2.49558 + vertex 1.41791 2.07392 2.49478 + vertex 1.41341 2.07685 2.49427 + endloop + endfacet + facet normal 0.0948278 0.316003 0.944007 + outer loop + vertex 1.41341 2.07685 2.49427 + vertex 1.41573 2.08149 2.49248 + vertex 1.41111 2.0804 2.49331 + endloop + endfacet + facet normal 0.0984448 0.318058 0.942946 + outer loop + vertex 1.41341 2.07685 2.49427 + vertex 1.41111 2.0804 2.49331 + vertex 1.4081 2.07768 2.49454 + endloop + endfacet + facet normal 0.0981276 0.315767 0.943749 + outer loop + vertex 1.4081 2.07768 2.49454 + vertex 1.40945 2.07365 2.49575 + vertex 1.41341 2.07685 2.49427 + endloop + endfacet + facet normal 0.0942308 0.314153 0.944684 + outer loop + vertex 1.42211 2.07677 2.49342 + vertex 1.42107 2.08073 2.49221 + vertex 1.41805 2.07796 2.49343 + endloop + endfacet + facet normal 0.0929535 0.317353 0.943741 + outer loop + vertex 1.42453 2.08381 2.49083 + vertex 1.41966 2.08469 2.49102 + vertex 1.42107 2.08073 2.49221 + endloop + endfacet + facet normal 0.0945531 0.316947 0.943718 + outer loop + vertex 1.41122 2.08442 2.49195 + vertex 1.41111 2.0804 2.49331 + vertex 1.41573 2.08149 2.49248 + endloop + endfacet + facet normal 0.0938506 0.318135 0.943389 + outer loop + vertex 1.41353 2.08784 2.49056 + vertex 1.41561 2.08545 2.49116 + vertex 1.41793 2.08887 2.48977 + endloop + endfacet + facet normal 0.0989303 0.316562 0.943399 + outer loop + vertex 1.40945 2.08868 2.4907 + vertex 1.41353 2.08784 2.49056 + vertex 1.41345 2.09195 2.48919 + endloop + endfacet + facet normal 0.100743 0.314564 0.943875 + outer loop + vertex 1.40788 2.09281 2.4895 + vertex 1.40945 2.08868 2.4907 + vertex 1.41345 2.09195 2.48919 + endloop + endfacet + facet normal 0.100056 0.316637 0.943255 + outer loop + vertex 1.41111 2.0804 2.49331 + vertex 1.41122 2.08442 2.49195 + vertex 1.40708 2.08165 2.49332 + endloop + endfacet + facet normal 0.100011 0.316489 0.943309 + outer loop + vertex 1.4081 2.07768 2.49454 + vertex 1.41111 2.0804 2.49331 + vertex 1.40708 2.08165 2.49332 + endloop + endfacet + facet normal 0.10259 0.316998 0.942861 + outer loop + vertex 1.4046 2.07466 2.49594 + vertex 1.40945 2.07365 2.49575 + vertex 1.4081 2.07768 2.49454 + endloop + endfacet + facet normal 0.10442 0.316569 0.942805 + outer loop + vertex 1.40589 2.0705 2.49719 + vertex 1.4046 2.07466 2.49594 + vertex 1.40059 2.07166 2.49739 + endloop + endfacet + facet normal 0.100857 0.316516 0.94321 + outer loop + vertex 1.39622 2.0745 2.4969 + vertex 1.39622 2.07061 2.49821 + vertex 1.40059 2.07166 2.49739 + endloop + endfacet + facet normal 0.105723 0.315935 0.942872 + outer loop + vertex 1.39855 2.07799 2.4955 + vertex 1.40059 2.07558 2.49608 + vertex 1.40293 2.07894 2.49469 + endloop + endfacet + facet normal 0.0867066 0.316941 0.944474 + outer loop + vertex 1.39622 2.07061 2.49821 + vertex 1.39622 2.0745 2.4969 + vertex 1.39212 2.07125 2.49837 + endloop + endfacet + facet normal 0.100872 0.316465 0.943226 + outer loop + vertex 1.39825 2.06825 2.49878 + vertex 1.40059 2.07166 2.49739 + vertex 1.39622 2.07061 2.49821 + endloop + endfacet + facet normal 0.0951105 0.311573 0.94545 + outer loop + vertex 1.39381 2.06322 2.50088 + vertex 1.39825 2.06432 2.50007 + vertex 1.39383 2.0671 2.4996 + endloop + endfacet + facet normal 0.103671 0.314666 0.943524 + outer loop + vertex 1.4023 2.06737 2.49863 + vertex 1.40059 2.07166 2.49739 + vertex 1.39825 2.06825 2.49878 + endloop + endfacet + facet normal 0.102895 0.309003 0.945478 + outer loop + vertex 1.40357 2.06317 2.49986 + vertex 1.40718 2.06631 2.49845 + vertex 1.4023 2.06737 2.49863 + endloop + endfacet + facet normal 0.103221 0.298064 0.948948 + outer loop + vertex 1.39998 2.06004 2.50124 + vertex 1.40485 2.05899 2.50104 + vertex 1.40357 2.06317 2.49986 + endloop + endfacet + facet normal 0.103831 0.289309 0.951588 + outer loop + vertex 1.4013 2.05598 2.50233 + vertex 1.39998 2.06004 2.50124 + vertex 1.39594 2.05687 2.50264 + endloop + endfacet + facet normal 0.0974878 0.303719 0.947761 + outer loop + vertex 1.39381 2.06322 2.50088 + vertex 1.39588 2.06087 2.50142 + vertex 1.39825 2.06432 2.50007 + endloop + endfacet + facet normal 0.0807299 0.312044 0.946632 + outer loop + vertex 1.38968 2.06381 2.50104 + vertex 1.39381 2.06322 2.50088 + vertex 1.39383 2.0671 2.4996 + endloop + endfacet + facet normal 0.0973057 0.300772 0.948719 + outer loop + vertex 1.39137 2.0597 2.50222 + vertex 1.39122 2.05572 2.50349 + vertex 1.39594 2.05687 2.50264 + endloop + endfacet + facet normal 0.0956679 0.30798 0.946571 + outer loop + vertex 1.39352 2.05227 2.50438 + vertex 1.39122 2.05572 2.50349 + vertex 1.3882 2.05289 2.50472 + endloop + endfacet + facet normal 0.0981866 0.334614 0.937226 + outer loop + vertex 1.3882 2.05289 2.50472 + vertex 1.38955 2.04901 2.50596 + vertex 1.39352 2.05227 2.50438 + endloop + endfacet + facet normal 0.10303 0.329348 0.938571 + outer loop + vertex 1.38955 2.04901 2.50596 + vertex 1.39357 2.04829 2.50577 + vertex 1.39352 2.05227 2.50438 + endloop + endfacet + facet normal 0.108408 0.340546 0.933957 + outer loop + vertex 1.39357 2.04829 2.50577 + vertex 1.39562 2.04579 2.50645 + vertex 1.39799 2.04926 2.5049 + endloop + endfacet + facet normal 0.105885 0.342141 0.933664 + outer loop + vertex 1.39966 2.04486 2.50633 + vertex 1.39799 2.04926 2.5049 + vertex 1.39562 2.04579 2.50645 + endloop + endfacet + facet normal 0.112094 0.320953 0.940438 + outer loop + vertex 1.39799 2.04926 2.5049 + vertex 1.40224 2.05199 2.50347 + vertex 1.39821 2.0533 2.5035 + endloop + endfacet + facet normal 0.102061 0.296721 0.949495 + outer loop + vertex 1.40625 2.05071 2.50344 + vertex 1.40647 2.05473 2.50216 + vertex 1.40224 2.05199 2.50347 + endloop + endfacet + facet normal 0.101889 0.325049 0.940192 + outer loop + vertex 1.40858 2.04315 2.50597 + vertex 1.40454 2.04389 2.50615 + vertex 1.40649 2.03959 2.50743 + endloop + endfacet + facet normal 0.0955046 0.328565 0.93964 + outer loop + vertex 1.41076 2.04077 2.50658 + vertex 1.40858 2.04315 2.50597 + vertex 1.40649 2.03959 2.50743 + endloop + endfacet + facet normal 0.0918904 0.326103 0.940858 + outer loop + vertex 1.40847 2.04715 2.50445 + vertex 1.41088 2.05179 2.50261 + vertex 1.40625 2.05071 2.50344 + endloop + endfacet + facet normal 0.0965309 0.293661 0.951023 + outer loop + vertex 1.41613 2.05115 2.50228 + vertex 1.41487 2.05506 2.5012 + vertex 1.41088 2.05179 2.50261 + endloop + endfacet + facet normal 0.0923382 0.29252 0.951791 + outer loop + vertex 1.41971 2.05433 2.50095 + vertex 1.41487 2.05506 2.5012 + vertex 1.41613 2.05115 2.50228 + endloop + endfacet + facet normal 0.0884208 0.298766 0.950221 + outer loop + vertex 1.41971 2.05433 2.50095 + vertex 1.42457 2.05362 2.50072 + vertex 1.42323 2.05753 2.49962 + endloop + endfacet + facet normal 0.0904138 0.305571 0.947867 + outer loop + vertex 1.42323 2.05753 2.49962 + vertex 1.42615 2.06045 2.4984 + vertex 1.42202 2.06147 2.49846 + endloop + endfacet + facet normal 0.090337 0.310783 0.946178 + outer loop + vertex 1.42622 2.06453 2.49705 + vertex 1.42615 2.06045 2.4984 + vertex 1.43077 2.06166 2.49756 + endloop + endfacet + facet normal 0.0968891 0.309263 0.946028 + outer loop + vertex 1.43957 2.06391 2.49594 + vertex 1.43471 2.06486 2.49613 + vertex 1.4361 2.06086 2.49729 + endloop + endfacet + facet normal 0.101494 0.304488 0.947094 + outer loop + vertex 1.4413 2.05965 2.49712 + vertex 1.43957 2.06391 2.49594 + vertex 1.4361 2.06086 2.49729 + endloop + endfacet + facet normal 0.0903786 0.310845 0.946154 + outer loop + vertex 1.43065 2.06565 2.49626 + vertex 1.42622 2.06453 2.49705 + vertex 1.43077 2.06166 2.49756 + endloop + endfacet + facet normal 0.0901527 0.3124 0.945663 + outer loop + vertex 1.42856 2.06802 2.49568 + vertex 1.43065 2.06565 2.49626 + vertex 1.43298 2.06907 2.49491 + endloop + endfacet + facet normal 0.0926906 0.312246 0.945469 + outer loop + vertex 1.43298 2.06907 2.49491 + vertex 1.43717 2.07187 2.49357 + vertex 1.43311 2.07309 2.49357 + endloop + endfacet + facet normal 0.0976515 0.313843 0.94444 + outer loop + vertex 1.44123 2.07064 2.49356 + vertex 1.44137 2.07467 2.49221 + vertex 1.43717 2.07187 2.49357 + endloop + endfacet + facet normal 0.102146 0.313556 0.94406 + outer loop + vertex 1.44137 2.07467 2.49221 + vertex 1.44123 2.07064 2.49356 + vertex 1.44586 2.07174 2.49269 + endloop + endfacet + facet normal 0.0967829 0.30868 0.946229 + outer loop + vertex 1.43471 2.06486 2.49613 + vertex 1.43957 2.06391 2.49594 + vertex 1.43819 2.0679 2.49478 + endloop + endfacet + facet normal 0.102553 0.304853 0.946862 + outer loop + vertex 1.44363 2.06308 2.49577 + vertex 1.43957 2.06391 2.49594 + vertex 1.4413 2.05965 2.49712 + endloop + endfacet + facet normal 0.107459 0.303384 0.94679 + outer loop + vertex 1.44363 2.06308 2.49577 + vertex 1.4457 2.06066 2.49631 + vertex 1.44806 2.06414 2.49492 + endloop + endfacet + facet normal 0.103147 0.310161 0.945072 + outer loop + vertex 1.44353 2.06707 2.49448 + vertex 1.44586 2.07174 2.49269 + vertex 1.44123 2.07064 2.49356 + endloop + endfacet + facet normal 0.106342 0.308104 0.945391 + outer loop + vertex 1.45228 2.06717 2.49347 + vertex 1.4511 2.0711 2.49232 + vertex 1.44816 2.06822 2.49359 + endloop + endfacet + facet normal 0.104035 0.312066 0.944347 + outer loop + vertex 1.45453 2.07429 2.49089 + vertex 1.44976 2.07499 2.49119 + vertex 1.4511 2.0711 2.49232 + endloop + endfacet + facet normal 0.101745 0.312979 0.944294 + outer loop + vertex 1.44577 2.0757 2.49139 + vertex 1.44137 2.07467 2.49221 + vertex 1.44586 2.07174 2.49269 + endloop + endfacet + facet normal 0.104141 0.315375 0.943236 + outer loop + vertex 1.44807 2.07913 2.48999 + vertex 1.44976 2.07499 2.49119 + vertex 1.45311 2.07812 2.48977 + endloop + endfacet + facet normal 0.101407 0.314149 0.943942 + outer loop + vertex 1.44577 2.0757 2.49139 + vertex 1.44371 2.07808 2.49082 + vertex 1.44137 2.07467 2.49221 + endloop + endfacet + facet normal 0.099172 0.315583 0.943701 + outer loop + vertex 1.44371 2.07808 2.49082 + vertex 1.43964 2.0789 2.49097 + vertex 1.44137 2.07467 2.49221 + endloop + endfacet + facet normal 0.10153 0.318689 0.942406 + outer loop + vertex 1.44358 2.08206 2.48949 + vertex 1.44588 2.0867 2.48768 + vertex 1.44124 2.08565 2.48853 + endloop + endfacet + facet normal 0.101306 0.319475 0.942164 + outer loop + vertex 1.44133 2.08968 2.48716 + vertex 1.44124 2.08565 2.48853 + vertex 1.44588 2.0867 2.48768 + endloop + endfacet + facet normal 0.0946199 0.319383 0.94289 + outer loop + vertex 1.433 2.08406 2.48991 + vertex 1.43716 2.08687 2.48854 + vertex 1.43308 2.08809 2.48853 + endloop + endfacet + facet normal 0.0939136 0.317628 0.943553 + outer loop + vertex 1.4286 2.08303 2.49069 + vertex 1.4307 2.08065 2.49129 + vertex 1.433 2.08406 2.48991 + endloop + endfacet + facet normal 0.0928913 0.316297 0.944101 + outer loop + vertex 1.4286 2.08303 2.49069 + vertex 1.42453 2.08381 2.49083 + vertex 1.42629 2.07961 2.49207 + endloop + endfacet + facet normal 0.0932669 0.319238 0.943074 + outer loop + vertex 1.41966 2.08469 2.49102 + vertex 1.42453 2.08381 2.49083 + vertex 1.42312 2.08777 2.48963 + endloop + endfacet + facet normal 0.0936659 0.32 0.942776 + outer loop + vertex 1.42845 2.087 2.48936 + vertex 1.43072 2.09164 2.48756 + vertex 1.42609 2.09054 2.4884 + endloop + endfacet + facet normal 0.0936439 0.320074 0.942753 + outer loop + vertex 1.42619 2.09453 2.48703 + vertex 1.42609 2.09054 2.4884 + vertex 1.43072 2.09164 2.48756 + endloop + endfacet + facet normal 0.0934849 0.31971 0.942892 + outer loop + vertex 1.42312 2.08777 2.48963 + vertex 1.42208 2.09168 2.48841 + vertex 1.41793 2.08887 2.48977 + endloop + endfacet + facet normal 0.0942869 0.316626 0.943853 + outer loop + vertex 1.41353 2.08784 2.49056 + vertex 1.41793 2.08887 2.48977 + vertex 1.41345 2.09195 2.48919 + endloop + endfacet + facet normal 0.0953196 0.318055 0.943268 + outer loop + vertex 1.41817 2.0928 2.48842 + vertex 1.42113 2.09551 2.48721 + vertex 1.41636 2.09605 2.48751 + endloop + endfacet + facet normal 0.0965345 0.319773 0.942564 + outer loop + vertex 1.41967 2.09933 2.48605 + vertex 1.41487 2.10004 2.4863 + vertex 1.41636 2.09605 2.48751 + endloop + endfacet + facet normal 0.10148 0.322999 0.940943 + outer loop + vertex 1.41086 2.10082 2.48646 + vertex 1.40877 2.10322 2.48587 + vertex 1.40653 2.09989 2.48725 + endloop + endfacet + facet normal 0.101155 0.317605 0.942812 + outer loop + vertex 1.41345 2.09195 2.48919 + vertex 1.41088 2.09679 2.48783 + vertex 1.40788 2.09281 2.4895 + endloop + endfacet + facet normal 0.104948 0.315896 0.942972 + outer loop + vertex 1.40458 2.08965 2.49092 + vertex 1.40945 2.08868 2.4907 + vertex 1.40788 2.09281 2.4895 + endloop + endfacet + facet normal 0.106299 0.315013 0.943116 + outer loop + vertex 1.40603 2.08564 2.4921 + vertex 1.40458 2.08965 2.49092 + vertex 1.40075 2.08656 2.49239 + endloop + endfacet + facet normal 0.0934019 0.317552 0.943629 + outer loop + vertex 1.40057 2.0905 2.49109 + vertex 1.39849 2.09288 2.49049 + vertex 1.39623 2.08943 2.49188 + endloop + endfacet + facet normal 0.0790067 0.322433 0.943289 + outer loop + vertex 1.39616 2.08545 2.49324 + vertex 1.39623 2.08943 2.49188 + vertex 1.39205 2.08629 2.4933 + endloop + endfacet + facet normal 0.0713157 0.331545 0.94074 + outer loop + vertex 1.39205 2.08629 2.4933 + vertex 1.39623 2.08943 2.49188 + vertex 1.39095 2.09012 2.49203 + endloop + endfacet + facet normal 0.0704491 0.324418 0.943287 + outer loop + vertex 1.39623 2.08943 2.49188 + vertex 1.39443 2.09354 2.4906 + vertex 1.39095 2.09012 2.49203 + endloop + endfacet + facet normal 0.105699 0.314661 0.943301 + outer loop + vertex 1.40306 2.08296 2.49333 + vertex 1.40075 2.08656 2.49239 + vertex 1.39846 2.08195 2.49418 + endloop + endfacet + facet normal 0.0951082 0.31648 0.943819 + outer loop + vertex 1.39449 2.07867 2.49568 + vertex 1.39855 2.07799 2.4955 + vertex 1.39846 2.08195 2.49418 + endloop + endfacet + facet normal 0.0753145 0.320287 0.944322 + outer loop + vertex 1.39449 2.07867 2.49568 + vertex 1.38957 2.07915 2.49591 + vertex 1.39089 2.07524 2.49713 + endloop + endfacet + facet normal 0.079238 0.323589 0.942874 + outer loop + vertex 1.3932 2.08253 2.49449 + vertex 1.39616 2.08545 2.49324 + vertex 1.39205 2.08629 2.4933 + endloop + endfacet + facet normal 0.048719 0.325502 0.944285 + outer loop + vertex 1.38229 2.08688 2.4936 + vertex 1.38599 2.09043 2.49219 + vertex 1.38101 2.09077 2.49233 + endloop + endfacet + facet normal 0.0629284 0.323145 0.944255 + outer loop + vertex 1.3785 2.08337 2.495 + vertex 1.37737 2.08732 2.49372 + vertex 1.37322 2.08409 2.4951 + endloop + endfacet + facet normal 0.0866368 0.305872 0.948123 + outer loop + vertex 1.36879 2.08308 2.49583 + vertex 1.37322 2.08409 2.4951 + vertex 1.3688 2.08708 2.49454 + endloop + endfacet + facet normal 0.102991 0.303047 0.947394 + outer loop + vertex 1.3688 2.08708 2.49454 + vertex 1.3713 2.0904 2.49321 + vertex 1.36728 2.09147 2.4933 + endloop + endfacet + facet normal 0.103326 0.304345 0.946941 + outer loop + vertex 1.3713 2.0904 2.49321 + vertex 1.37134 2.09435 2.49193 + vertex 1.36728 2.09147 2.4933 + endloop + endfacet + facet normal 0.0933804 0.315485 0.944325 + outer loop + vertex 1.37572 2.09538 2.49116 + vertex 1.37365 2.09778 2.49056 + vertex 1.37134 2.09435 2.49193 + endloop + endfacet + facet normal 0.0659645 0.335346 0.939783 + outer loop + vertex 1.38309 2.09793 2.48968 + vertex 1.38596 2.10068 2.4885 + vertex 1.38213 2.10164 2.48842 + endloop + endfacet + facet normal 0.0670784 0.339672 0.938149 + outer loop + vertex 1.38596 2.10068 2.4885 + vertex 1.38615 2.10447 2.48711 + vertex 1.38213 2.10164 2.48842 + endloop + endfacet + facet normal 0.093526 0.315598 0.944273 + outer loop + vertex 1.37365 2.09778 2.49056 + vertex 1.37572 2.09538 2.49116 + vertex 1.37805 2.09883 2.48977 + endloop + endfacet + facet normal 0.101526 0.310346 0.945187 + outer loop + vertex 1.37365 2.09778 2.49056 + vertex 1.36956 2.09864 2.49072 + vertex 1.37134 2.09435 2.49193 + endloop + endfacet + facet normal 0.110093 0.316788 0.942085 + outer loop + vertex 1.36467 2.09961 2.49096 + vertex 1.36956 2.09864 2.49072 + vertex 1.368 2.10275 2.48952 + endloop + endfacet + facet normal 0.109956 0.319892 0.941052 + outer loop + vertex 1.368 2.10275 2.48952 + vertex 1.37098 2.1067 2.48782 + vertex 1.36631 2.1061 2.48857 + endloop + endfacet + facet normal 0.0993979 0.326788 0.939856 + outer loop + vertex 1.37827 2.10271 2.4884 + vertex 1.37644 2.10594 2.48747 + vertex 1.37357 2.10188 2.48918 + endloop + endfacet + facet normal 0.104465 0.325696 0.939686 + outer loop + vertex 1.3797 2.10917 2.48599 + vertex 1.37494 2.10991 2.48626 + vertex 1.37644 2.10594 2.48747 + endloop + endfacet + facet normal 0.109813 0.320681 0.9408 + outer loop + vertex 1.36657 2.10992 2.48724 + vertex 1.36631 2.1061 2.48857 + vertex 1.37098 2.1067 2.48782 + endloop + endfacet + facet normal 0.11617 0.320066 0.940246 + outer loop + vertex 1.36631 2.1061 2.48857 + vertex 1.36657 2.10992 2.48724 + vertex 1.36305 2.10759 2.48847 + endloop + endfacet + facet normal 0.115577 0.318802 0.940748 + outer loop + vertex 1.36286 2.10377 2.48979 + vertex 1.36631 2.1061 2.48857 + vertex 1.36305 2.10759 2.48847 + endloop + endfacet + facet normal 0.124594 0.312809 0.941609 + outer loop + vertex 1.35863 2.10301 2.4906 + vertex 1.36067 2.10051 2.49116 + vertex 1.36286 2.10377 2.48979 + endloop + endfacet + facet normal 0.137288 0.3122 0.940044 + outer loop + vertex 1.35863 2.10301 2.4906 + vertex 1.35468 2.10414 2.4908 + vertex 1.35632 2.09971 2.49203 + endloop + endfacet + facet normal 0.145897 0.312941 0.9385 + outer loop + vertex 1.35468 2.10414 2.4908 + vertex 1.35292 2.10853 2.48961 + vertex 1.35071 2.10529 2.49103 + endloop + endfacet + facet normal 0.134227 0.315506 0.939382 + outer loop + vertex 1.35851 2.10702 2.48928 + vertex 1.36091 2.11135 2.48748 + vertex 1.35634 2.11083 2.48831 + endloop + endfacet + facet normal 0.149845 0.310338 0.938742 + outer loop + vertex 1.34865 2.10791 2.4905 + vertex 1.35292 2.10853 2.48961 + vertex 1.34847 2.11197 2.48918 + endloop + endfacet + facet normal 0.145957 0.312997 0.938472 + outer loop + vertex 1.35634 2.11083 2.48831 + vertex 1.3564 2.11478 2.48698 + vertex 1.35298 2.1125 2.48827 + endloop + endfacet + facet normal 0.157357 0.300109 0.940836 + outer loop + vertex 1.35066 2.12036 2.48608 + vertex 1.34866 2.12296 2.48559 + vertex 1.34645 2.11979 2.48697 + endloop + endfacet + facet normal 0.154867 0.308441 0.938552 + outer loop + vertex 1.34847 2.11197 2.48918 + vertex 1.35082 2.11634 2.48736 + vertex 1.34633 2.11583 2.48827 + endloop + endfacet + facet normal 0.153734 0.307899 0.938916 + outer loop + vertex 1.34847 2.11197 2.48918 + vertex 1.34633 2.11583 2.48827 + vertex 1.34291 2.11353 2.48958 + endloop + endfacet + facet normal 0.154087 0.303084 0.940424 + outer loop + vertex 1.33864 2.11296 2.49047 + vertex 1.34291 2.11353 2.48958 + vertex 1.33851 2.11701 2.48918 + endloop + endfacet + facet normal 0.157701 0.300209 0.940747 + outer loop + vertex 1.34303 2.11751 2.48827 + vertex 1.34645 2.11979 2.48697 + vertex 1.34095 2.12139 2.48738 + endloop + endfacet + facet normal 0.157297 0.299763 0.940957 + outer loop + vertex 1.33296 2.11858 2.48961 + vertex 1.33468 2.11415 2.49074 + vertex 1.33851 2.11701 2.48918 + endloop + endfacet + facet normal 0.160255 0.297753 0.941096 + outer loop + vertex 1.3307 2.11532 2.49102 + vertex 1.32867 2.11797 2.49053 + vertex 1.32635 2.11466 2.49197 + endloop + endfacet + facet normal 0.15532 0.303669 0.940032 + outer loop + vertex 1.33315 2.10733 2.49319 + vertex 1.33088 2.11121 2.49231 + vertex 1.32865 2.10663 2.49416 + endloop + endfacet + facet normal 0.15648 0.303833 0.939787 + outer loop + vertex 1.32475 2.10373 2.49575 + vertex 1.32878 2.10257 2.49545 + vertex 1.32865 2.10663 2.49416 + endloop + endfacet + facet normal 0.157536 0.303628 0.939677 + outer loop + vertex 1.32475 2.10373 2.49575 + vertex 1.31997 2.10498 2.49615 + vertex 1.32135 2.10085 2.49725 + endloop + endfacet + facet normal 0.158446 0.301254 0.940288 + outer loop + vertex 1.31997 2.10498 2.49615 + vertex 1.31825 2.1094 2.49502 + vertex 1.31594 2.10613 2.49645 + endloop + endfacet + facet normal 0.160439 0.29989 0.940386 + outer loop + vertex 1.31403 2.10879 2.49593 + vertex 1.31594 2.10613 2.49645 + vertex 1.31825 2.1094 2.49502 + endloop + endfacet + facet normal 0.15934 0.300788 0.940286 + outer loop + vertex 1.32337 2.10786 2.49465 + vertex 1.32631 2.11047 2.49331 + vertex 1.32226 2.112 2.49351 + endloop + endfacet + facet normal 0.163125 0.292892 0.942128 + outer loop + vertex 1.31833 2.11333 2.49376 + vertex 1.32083 2.11647 2.49235 + vertex 1.31656 2.116 2.49324 + endloop + endfacet + facet normal 0.163592 0.290109 0.942908 + outer loop + vertex 1.31662 2.11989 2.49203 + vertex 1.31656 2.116 2.49324 + vertex 1.32083 2.11647 2.49235 + endloop + endfacet + facet normal 0.158821 0.299339 0.940836 + outer loop + vertex 1.32631 2.11047 2.49331 + vertex 1.32635 2.11466 2.49197 + vertex 1.32226 2.112 2.49351 + endloop + endfacet + facet normal 0.163241 0.295711 0.941226 + outer loop + vertex 1.32867 2.11797 2.49053 + vertex 1.32474 2.1192 2.49083 + vertex 1.32635 2.11466 2.49197 + endloop + endfacet + facet normal 0.165218 0.292028 0.942031 + outer loop + vertex 1.32083 2.12044 2.49112 + vertex 1.31662 2.11989 2.49203 + vertex 1.32083 2.11647 2.49235 + endloop + endfacet + facet normal 0.163814 0.292116 0.942249 + outer loop + vertex 1.32311 2.12365 2.48973 + vertex 1.32474 2.1192 2.49083 + vertex 1.32862 2.12206 2.48927 + endloop + endfacet + facet normal 0.165294 0.291634 0.94214 + outer loop + vertex 1.32083 2.12044 2.49112 + vertex 1.31885 2.12309 2.49065 + vertex 1.31662 2.11989 2.49203 + endloop + endfacet + facet normal 0.168618 0.292994 0.941128 + outer loop + vertex 1.31096 2.1256 2.49126 + vertex 1.30671 2.12503 2.4922 + vertex 1.3111 2.12149 2.49252 + endloop + endfacet + facet normal 0.169124 0.293597 0.94085 + outer loop + vertex 1.30671 2.12503 2.4922 + vertex 1.30657 2.12102 2.49348 + vertex 1.3111 2.12149 2.49252 + endloop + endfacet + facet normal 0.167604 0.298191 0.939676 + outer loop + vertex 1.31096 2.1256 2.49126 + vertex 1.30895 2.12823 2.49079 + vertex 1.30671 2.12503 2.4922 + endloop + endfacet + facet normal 0.165468 0.291516 0.942146 + outer loop + vertex 1.31885 2.12309 2.49065 + vertex 1.31491 2.12434 2.49095 + vertex 1.31662 2.11989 2.49203 + endloop + endfacet + facet normal 0.166507 0.289923 0.942454 + outer loop + vertex 1.31656 2.116 2.49324 + vertex 1.31662 2.11989 2.49203 + vertex 1.31333 2.11747 2.49336 + endloop + endfacet + facet normal 0.167023 0.291099 0.942 + outer loop + vertex 1.31365 2.11305 2.49467 + vertex 1.31656 2.116 2.49324 + vertex 1.31333 2.11747 2.49336 + endloop + endfacet + facet normal 0.161549 0.294457 0.941912 + outer loop + vertex 1.31403 2.10879 2.49593 + vertex 1.31825 2.1094 2.49502 + vertex 1.31365 2.11305 2.49467 + endloop + endfacet + facet normal 0.161687 0.300698 0.939914 + outer loop + vertex 1.31594 2.10613 2.49645 + vertex 1.31403 2.10879 2.49593 + vertex 1.31128 2.10571 2.49739 + endloop + endfacet + facet normal 0.167111 0.292886 0.941431 + outer loop + vertex 1.3109 2.10993 2.49612 + vertex 1.30894 2.11273 2.49559 + vertex 1.30657 2.10948 2.49702 + endloop + endfacet + facet normal 0.160105 0.296827 0.941414 + outer loop + vertex 1.30413 2.09836 2.50095 + vertex 1.30834 2.09892 2.50006 + vertex 1.30411 2.10232 2.49971 + endloop + endfacet + facet normal 0.160321 0.300788 0.940119 + outer loop + vertex 1.31161 2.10136 2.49873 + vertex 1.31128 2.10571 2.49739 + vertex 1.30841 2.10273 2.49884 + endloop + endfacet + facet normal 0.159774 0.300282 0.940374 + outer loop + vertex 1.31385 2.09748 2.49958 + vertex 1.31607 2.10207 2.49774 + vertex 1.31161 2.10136 2.49873 + endloop + endfacet + facet normal 0.157606 0.295144 0.942364 + outer loop + vertex 1.31004 2.09452 2.50115 + vertex 1.31401 2.09335 2.50085 + vertex 1.31385 2.09748 2.49958 + endloop + endfacet + facet normal 0.155373 0.286837 0.945296 + outer loop + vertex 1.31401 2.09335 2.50085 + vertex 1.31004 2.09452 2.50115 + vertex 1.31174 2.09006 2.50222 + endloop + endfacet + facet normal 0.15765 0.287561 0.944699 + outer loop + vertex 1.31174 2.09006 2.50222 + vertex 1.31004 2.09452 2.50115 + vertex 1.30622 2.09161 2.50267 + endloop + endfacet + facet normal 0.160569 0.294415 0.942092 + outer loop + vertex 1.30413 2.09836 2.50095 + vertex 1.30612 2.09572 2.50144 + vertex 1.30834 2.09892 2.50006 + endloop + endfacet + facet normal 0.161304 0.296775 0.941225 + outer loop + vertex 1.30016 2.09967 2.50122 + vertex 1.30413 2.09836 2.50095 + vertex 1.30411 2.10232 2.49971 + endloop + endfacet + facet normal 0.163464 0.293868 0.941765 + outer loop + vertex 1.29847 2.1043 2.50007 + vertex 1.30016 2.09967 2.50122 + vertex 1.30411 2.10232 2.49971 + endloop + endfacet + facet normal 0.159412 0.286799 0.944634 + outer loop + vertex 1.30185 2.09517 2.50233 + vertex 1.30168 2.09111 2.50359 + vertex 1.30622 2.09161 2.50267 + endloop + endfacet + facet normal 0.163059 0.281995 0.945458 + outer loop + vertex 1.30382 2.08705 2.50443 + vertex 1.30168 2.09111 2.50359 + vertex 1.29821 2.08878 2.50488 + endloop + endfacet + facet normal 0.165177 0.282736 0.944869 + outer loop + vertex 1.29396 2.08824 2.50579 + vertex 1.29594 2.08556 2.50624 + vertex 1.29821 2.08878 2.50488 + endloop + endfacet + facet normal 0.165055 0.284909 0.944237 + outer loop + vertex 1.29396 2.08824 2.50579 + vertex 1.29 2.08955 2.50608 + vertex 1.29173 2.08503 2.50715 + endloop + endfacet + facet normal 0.166435 0.288901 0.942781 + outer loop + vertex 1.29 2.08955 2.50608 + vertex 1.28823 2.09413 2.50499 + vertex 1.28595 2.09096 2.50637 + endloop + endfacet + facet normal 0.16453 0.290015 0.942773 + outer loop + vertex 1.28823 2.09413 2.50499 + vertex 1.29162 2.0964 2.5037 + vertex 1.28833 2.09801 2.50378 + endloop + endfacet + facet normal 0.161895 0.289626 0.943349 + outer loop + vertex 1.29837 2.09286 2.50363 + vertex 1.2962 2.09688 2.50277 + vertex 1.29383 2.09238 2.50456 + endloop + endfacet + facet normal 0.164401 0.289747 0.942878 + outer loop + vertex 1.29162 2.0964 2.5037 + vertex 1.29137 2.10081 2.50239 + vertex 1.28833 2.09801 2.50378 + endloop + endfacet + facet normal 0.165462 0.291644 0.942107 + outer loop + vertex 1.29414 2.10383 2.50098 + vertex 1.29608 2.10107 2.50149 + vertex 1.29847 2.1043 2.50007 + endloop + endfacet + facet normal 0.166139 0.284894 0.944052 + outer loop + vertex 1.28678 2.10471 2.50202 + vertex 1.2867 2.1008 2.50322 + vertex 1.29137 2.10081 2.50239 + endloop + endfacet + facet normal 0.170704 0.284567 0.943335 + outer loop + vertex 1.28906 2.10785 2.50067 + vertex 1.29101 2.10503 2.50116 + vertex 1.29376 2.10811 2.49974 + endloop + endfacet + facet normal 0.17075 0.281247 0.944322 + outer loop + vertex 1.28678 2.10471 2.50202 + vertex 1.28496 2.10938 2.50096 + vertex 1.28107 2.10665 2.50248 + endloop + endfacet + facet normal 0.173915 0.278587 0.944533 + outer loop + vertex 1.28496 2.10938 2.50096 + vertex 1.28317 2.11405 2.49991 + vertex 1.28089 2.11092 2.50126 + endloop + endfacet + facet normal 0.176645 0.281598 0.943132 + outer loop + vertex 1.28317 2.11405 2.49991 + vertex 1.28655 2.11628 2.49862 + vertex 1.28326 2.11796 2.49873 + endloop + endfacet + facet normal 0.173727 0.283522 0.943098 + outer loop + vertex 1.29343 2.11255 2.49846 + vertex 1.29671 2.11497 2.49712 + vertex 1.29112 2.11667 2.49764 + endloop + endfacet + facet normal 0.171043 0.281507 0.944192 + outer loop + vertex 1.28906 2.10785 2.50067 + vertex 1.29376 2.10811 2.49974 + vertex 1.28887 2.1121 2.49944 + endloop + endfacet + facet normal 0.173139 0.284257 0.942985 + outer loop + vertex 1.29666 2.11107 2.49831 + vertex 1.29671 2.11497 2.49712 + vertex 1.29343 2.11255 2.49846 + endloop + endfacet + facet normal 0.166176 0.287372 0.943294 + outer loop + vertex 1.29414 2.10383 2.50098 + vertex 1.29847 2.1043 2.50007 + vertex 1.29376 2.10811 2.49974 + endloop + endfacet + facet normal 0.16416 0.295995 0.940977 + outer loop + vertex 1.30411 2.10232 2.49971 + vertex 1.30253 2.1069 2.49854 + vertex 1.29847 2.1043 2.50007 + endloop + endfacet + facet normal 0.16964 0.28757 0.942617 + outer loop + vertex 1.29847 2.10836 2.49881 + vertex 1.30095 2.1115 2.49741 + vertex 1.29666 2.11107 2.49831 + endloop + endfacet + facet normal 0.165064 0.29487 0.941173 + outer loop + vertex 1.30659 2.10542 2.49829 + vertex 1.30657 2.10948 2.49702 + vertex 1.30253 2.1069 2.49854 + endloop + endfacet + facet normal 0.170132 0.284448 0.943475 + outer loop + vertex 1.29671 2.11497 2.49712 + vertex 1.29666 2.11107 2.49831 + vertex 1.30095 2.1115 2.49741 + endloop + endfacet + facet normal 0.172463 0.286841 0.942326 + outer loop + vertex 1.29891 2.11818 2.49575 + vertex 1.30091 2.11552 2.49619 + vertex 1.30314 2.11872 2.49481 + endloop + endfacet + facet normal 0.171449 0.293402 0.940489 + outer loop + vertex 1.30657 2.12102 2.49348 + vertex 1.30671 2.12503 2.4922 + vertex 1.30327 2.12274 2.49354 + endloop + endfacet + facet normal 0.172214 0.306842 0.93605 + outer loop + vertex 1.30112 2.13058 2.49144 + vertex 1.29907 2.13322 2.49095 + vertex 1.29686 2.13011 2.49238 + endloop + endfacet + facet normal 0.173959 0.305636 0.936122 + outer loop + vertex 1.29907 2.13322 2.49095 + vertex 1.29505 2.13458 2.49126 + vertex 1.29686 2.13011 2.49238 + endloop + endfacet + facet normal 0.173485 0.307732 0.935524 + outer loop + vertex 1.29907 2.13322 2.49095 + vertex 1.30112 2.13058 2.49144 + vertex 1.30331 2.13376 2.48999 + endloop + endfacet + facet normal 0.169872 0.326149 0.92993 + outer loop + vertex 1.29907 2.13322 2.49095 + vertex 1.30331 2.13376 2.48999 + vertex 1.29883 2.13734 2.48955 + endloop + endfacet + facet normal 0.172083 0.328753 0.928606 + outer loop + vertex 1.29883 2.13734 2.48955 + vertex 1.30331 2.13376 2.48999 + vertex 1.30339 2.13759 2.48862 + endloop + endfacet + facet normal 0.17305 0.295227 0.939625 + outer loop + vertex 1.29879 2.12225 2.49451 + vertex 1.30122 2.12659 2.4927 + vertex 1.29671 2.12616 2.49367 + endloop + endfacet + facet normal 0.174216 0.295765 0.93924 + outer loop + vertex 1.29879 2.12225 2.49451 + vertex 1.29671 2.12616 2.49367 + vertex 1.2932 2.12404 2.49499 + endloop + endfacet + facet normal 0.175717 0.292782 0.939895 + outer loop + vertex 1.28896 2.12371 2.49588 + vertex 1.29093 2.12089 2.49639 + vertex 1.2932 2.12404 2.49499 + endloop + endfacet + facet normal 0.175756 0.292806 0.93988 + outer loop + vertex 1.29093 2.12089 2.49639 + vertex 1.28896 2.12371 2.49588 + vertex 1.28626 2.12072 2.49732 + endloop + endfacet + facet normal 0.177337 0.29785 0.937996 + outer loop + vertex 1.28585 2.12498 2.49607 + vertex 1.2839 2.12774 2.49556 + vertex 1.28169 2.12462 2.49696 + endloop + endfacet + facet normal 0.178322 0.287688 0.940977 + outer loop + vertex 1.28326 2.11796 2.49873 + vertex 1.28626 2.12072 2.49732 + vertex 1.28164 2.12075 2.49818 + endloop + endfacet + facet normal 0.176739 0.287879 0.941217 + outer loop + vertex 1.27865 2.11797 2.4996 + vertex 1.28164 2.12075 2.49818 + vertex 1.27836 2.12238 2.4983 + endloop + endfacet + facet normal 0.179182 0.278769 0.943494 + outer loop + vertex 1.274 2.11776 2.50054 + vertex 1.27592 2.11496 2.50101 + vertex 1.27865 2.11797 2.4996 + endloop + endfacet + facet normal 0.177526 0.276633 0.944436 + outer loop + vertex 1.274 2.11776 2.50054 + vertex 1.2699 2.11928 2.50087 + vertex 1.27162 2.11452 2.50194 + endloop + endfacet + facet normal 0.182913 0.287351 0.940198 + outer loop + vertex 1.2699 2.11928 2.50087 + vertex 1.2681 2.12394 2.49979 + vertex 1.26583 2.12081 2.50119 + endloop + endfacet + facet normal 0.182465 0.292962 0.938552 + outer loop + vertex 1.27381 2.12198 2.49929 + vertex 1.27612 2.12641 2.49746 + vertex 1.27159 2.12606 2.49845 + endloop + endfacet + facet normal 0.181088 0.293597 0.93862 + outer loop + vertex 1.26388 2.12362 2.50071 + vertex 1.2681 2.12394 2.49979 + vertex 1.26341 2.12792 2.49945 + endloop + endfacet + facet normal 0.18237 0.293857 0.938291 + outer loop + vertex 1.26341 2.12792 2.49945 + vertex 1.26624 2.13196 2.49764 + vertex 1.26249 2.1318 2.49842 + endloop + endfacet + facet normal 0.178534 0.293201 0.939233 + outer loop + vertex 1.2587 2.13162 2.49919 + vertex 1.26341 2.12792 2.49945 + vertex 1.26249 2.1318 2.49842 + endloop + endfacet + facet normal 0.17874 0.291243 0.939803 + outer loop + vertex 1.26249 2.1318 2.49842 + vertex 1.26156 2.13567 2.49739 + vertex 1.2587 2.13162 2.49919 + endloop + endfacet + facet normal 0.178711 0.293418 0.939132 + outer loop + vertex 1.25882 2.12759 2.50043 + vertex 1.26341 2.12792 2.49945 + vertex 1.2587 2.13162 2.49919 + endloop + endfacet + facet normal 0.176641 0.293473 0.939506 + outer loop + vertex 1.2548 2.12901 2.50074 + vertex 1.25882 2.12759 2.50043 + vertex 1.2587 2.13162 2.49919 + endloop + endfacet + facet normal 0.18324 0.296898 0.937163 + outer loop + vertex 1.27159 2.12606 2.49845 + vertex 1.27173 2.13006 2.49716 + vertex 1.26822 2.12796 2.49851 + endloop + endfacet + facet normal 0.182574 0.291915 0.938857 + outer loop + vertex 1.26156 2.13567 2.49739 + vertex 1.26249 2.1318 2.49842 + vertex 1.26624 2.13196 2.49764 + endloop + endfacet + facet normal 0.192366 0.299895 0.934376 + outer loop + vertex 1.26409 2.13871 2.49594 + vertex 1.26605 2.13598 2.49641 + vertex 1.26805 2.13921 2.49496 + endloop + endfacet + facet normal 0.180172 0.29025 0.939837 + outer loop + vertex 1.2587 2.13162 2.49919 + vertex 1.26156 2.13567 2.49739 + vertex 1.25674 2.13565 2.49832 + endloop + endfacet + facet normal 0.177524 0.289141 0.940682 + outer loop + vertex 1.2587 2.13162 2.49919 + vertex 1.25674 2.13565 2.49832 + vertex 1.25316 2.13352 2.49965 + endloop + endfacet + facet normal 0.180733 0.284288 0.94155 + outer loop + vertex 1.25316 2.13352 2.49965 + vertex 1.25674 2.13565 2.49832 + vertex 1.25338 2.13758 2.49839 + endloop + endfacet + facet normal 0.17821 0.291342 0.939873 + outer loop + vertex 1.25316 2.13352 2.49965 + vertex 1.2548 2.12901 2.50074 + vertex 1.2587 2.13162 2.49919 + endloop + endfacet + facet normal 0.178748 0.294279 0.938855 + outer loop + vertex 1.2565 2.12438 2.50187 + vertex 1.2548 2.12901 2.50074 + vertex 1.2509 2.12641 2.5023 + endloop + endfacet + facet normal 0.184232 0.291459 0.938675 + outer loop + vertex 1.25087 2.13038 2.50106 + vertex 1.2489 2.13306 2.50061 + vertex 1.2467 2.12987 2.50203 + endloop + endfacet + facet normal 0.182096 0.291653 0.939031 + outer loop + vertex 1.24844 2.12332 2.50374 + vertex 1.2509 2.12641 2.5023 + vertex 1.24665 2.12602 2.50324 + endloop + endfacet + facet normal 0.184956 0.290267 0.938902 + outer loop + vertex 1.24379 2.12309 2.50471 + vertex 1.24665 2.12602 2.50324 + vertex 1.24346 2.12749 2.50342 + endloop + endfacet + facet normal 0.186338 0.283684 0.940639 + outer loop + vertex 1.23919 2.12283 2.5057 + vertex 1.24108 2.12005 2.50617 + vertex 1.24379 2.12309 2.50471 + endloop + endfacet + facet normal 0.187023 0.282018 0.941004 + outer loop + vertex 1.23919 2.12283 2.5057 + vertex 1.23515 2.12434 2.50605 + vertex 1.23693 2.11971 2.50709 + endloop + endfacet + facet normal 0.189006 0.282649 0.940418 + outer loop + vertex 1.23693 2.11971 2.50709 + vertex 1.23515 2.12434 2.50605 + vertex 1.23128 2.12169 2.50763 + endloop + endfacet + facet normal 0.190538 0.279262 0.94112 + outer loop + vertex 1.22635 2.12597 2.50736 + vertex 1.22672 2.1214 2.50864 + vertex 1.23128 2.12169 2.50763 + endloop + endfacet + facet normal 0.193063 0.282849 0.939533 + outer loop + vertex 1.22911 2.12888 2.50592 + vertex 1.23107 2.12595 2.5064 + vertex 1.23333 2.12903 2.505 + endloop + endfacet + facet normal 0.192846 0.278833 0.940778 + outer loop + vertex 1.22135 2.13036 2.50708 + vertex 1.22172 2.12603 2.50829 + vertex 1.22635 2.12597 2.50736 + endloop + endfacet + facet normal 0.192308 0.27882 0.940892 + outer loop + vertex 1.22172 2.12603 2.50829 + vertex 1.22135 2.13036 2.50708 + vertex 1.21856 2.12742 2.50852 + endloop + endfacet + facet normal 0.195835 0.278256 0.940331 + outer loop + vertex 1.2241 2.13333 2.50563 + vertex 1.22593 2.13036 2.50613 + vertex 1.22874 2.13322 2.5047 + endloop + endfacet + facet normal 0.19722 0.268519 0.942869 + outer loop + vertex 1.22093 2.13476 2.50587 + vertex 1.21904 2.13763 2.50545 + vertex 1.21667 2.1344 2.50687 + endloop + endfacet + facet normal 0.191768 0.277511 0.941389 + outer loop + vertex 1.21887 2.12312 2.50973 + vertex 1.22172 2.12603 2.50829 + vertex 1.21856 2.12742 2.50852 + endloop + endfacet + facet normal 0.191297 0.275552 0.94206 + outer loop + vertex 1.21426 2.12295 2.51071 + vertex 1.21613 2.12012 2.51116 + vertex 1.21887 2.12312 2.50973 + endloop + endfacet + facet normal 0.19107 0.275139 0.942226 + outer loop + vertex 1.21426 2.12295 2.51071 + vertex 1.21025 2.12448 2.51108 + vertex 1.21195 2.11979 2.5121 + endloop + endfacet + facet normal 0.192652 0.275613 0.941766 + outer loop + vertex 1.21195 2.11979 2.5121 + vertex 1.21025 2.12448 2.51108 + vertex 1.20633 2.12174 2.51268 + endloop + endfacet + facet normal 0.194511 0.269845 0.943053 + outer loop + vertex 1.20153 2.12592 2.51248 + vertex 1.20183 2.12135 2.51372 + vertex 1.20633 2.12174 2.51268 + endloop + endfacet + facet normal 0.207388 0.270042 0.940249 + outer loop + vertex 1.2012 2.13031 2.51129 + vertex 1.19652 2.13058 2.51224 + vertex 1.20153 2.12592 2.51248 + endloop + endfacet + facet normal 0.205728 0.262289 0.942805 + outer loop + vertex 1.19939 2.1334 2.51082 + vertex 1.2012 2.13031 2.51129 + vertex 1.20401 2.1333 2.50984 + endloop + endfacet + facet normal 0.19704 0.272828 0.941669 + outer loop + vertex 1.20435 2.12887 2.51102 + vertex 1.20622 2.126 2.51146 + vertex 1.20864 2.12923 2.51002 + endloop + endfacet + facet normal 0.193302 0.275979 0.941525 + outer loop + vertex 1.21425 2.12707 2.5095 + vertex 1.21267 2.13182 2.50844 + vertex 1.20864 2.12923 2.51002 + endloop + endfacet + facet normal 0.192882 0.273562 0.942317 + outer loop + vertex 1.21668 2.13026 2.50807 + vertex 1.21667 2.1344 2.50687 + vertex 1.21267 2.13182 2.50844 + endloop + endfacet + facet normal 0.199097 0.261062 0.944567 + outer loop + vertex 1.20868 2.13336 2.50882 + vertex 1.21112 2.1366 2.50741 + vertex 1.20686 2.13625 2.5084 + endloop + endfacet + facet normal 0.203433 0.263564 0.942947 + outer loop + vertex 1.20868 2.13336 2.50882 + vertex 1.20686 2.13625 2.5084 + vertex 1.20401 2.1333 2.50984 + endloop + endfacet + facet normal 0.206087 0.252103 0.945501 + outer loop + vertex 1.19939 2.1334 2.51082 + vertex 1.20401 2.1333 2.50984 + vertex 1.19899 2.13803 2.50968 + endloop + endfacet + facet normal 0.208471 0.244666 0.946931 + outer loop + vertex 1.20372 2.13774 2.50869 + vertex 1.2065 2.14079 2.50729 + vertex 1.20191 2.14087 2.50828 + endloop + endfacet + facet normal 0.211086 0.248592 0.945328 + outer loop + vertex 1.1942 2.13843 2.51064 + vertex 1.1961 2.13517 2.51107 + vertex 1.19899 2.13803 2.50968 + endloop + endfacet + facet normal 0.212036 0.249098 0.944982 + outer loop + vertex 1.1961 2.13517 2.51107 + vertex 1.1942 2.13843 2.51064 + vertex 1.19134 2.13558 2.51203 + endloop + endfacet + facet normal 0.213427 0.243418 0.946149 + outer loop + vertex 1.19089 2.14024 2.51093 + vertex 1.189 2.1434 2.51054 + vertex 1.1863 2.14037 2.51193 + endloop + endfacet + facet normal 0.21572 0.241379 0.946151 + outer loop + vertex 1.18581 2.14488 2.51089 + vertex 1.1863 2.14037 2.51193 + vertex 1.189 2.1434 2.51054 + endloop + endfacet + facet normal 0.230016 0.275118 0.933489 + outer loop + vertex 1.189 2.1434 2.51054 + vertex 1.18839 2.14793 2.50935 + vertex 1.18581 2.14488 2.51089 + endloop + endfacet + facet normal 0.212201 0.241192 0.946994 + outer loop + vertex 1.18581 2.14488 2.51089 + vertex 1.18166 2.14448 2.51192 + vertex 1.1863 2.14037 2.51193 + endloop + endfacet + facet normal 0.208357 0.266025 0.941179 + outer loop + vertex 1.18581 2.14488 2.51089 + vertex 1.18378 2.14764 2.51056 + vertex 1.18166 2.14448 2.51192 + endloop + endfacet + facet normal 0.207572 0.249634 0.945831 + outer loop + vertex 1.18845 2.13274 2.51342 + vertex 1.19134 2.13558 2.51203 + vertex 1.18664 2.13588 2.51299 + endloop + endfacet + facet normal 0.206538 0.249089 0.946201 + outer loop + vertex 1.18845 2.13274 2.51342 + vertex 1.18664 2.13588 2.51299 + vertex 1.1838 2.13286 2.5144 + endloop + endfacet + facet normal 0.204897 0.243217 0.948084 + outer loop + vertex 1.17911 2.13277 2.51544 + vertex 1.1838 2.13286 2.5144 + vertex 1.17925 2.13701 2.51432 + endloop + endfacet + facet normal 0.209946 0.235899 0.948828 + outer loop + vertex 1.1835 2.13738 2.51329 + vertex 1.1863 2.14037 2.51193 + vertex 1.1817 2.1403 2.51296 + endloop + endfacet + facet normal 0.209773 0.238453 0.948228 + outer loop + vertex 1.18166 2.14448 2.51192 + vertex 1.1817 2.1403 2.51296 + vertex 1.1863 2.14037 2.51193 + endloop + endfacet + facet normal 0.207016 0.234327 0.949861 + outer loop + vertex 1.17925 2.13701 2.51432 + vertex 1.17777 2.14187 2.51344 + vertex 1.17373 2.13923 2.51497 + endloop + endfacet + facet normal 0.208378 0.238064 0.948633 + outer loop + vertex 1.17373 2.13923 2.51497 + vertex 1.17519 2.13432 2.51589 + vertex 1.17925 2.13701 2.51432 + endloop + endfacet + facet normal 0.20441 0.249398 0.946582 + outer loop + vertex 1.17666 2.12949 2.51684 + vertex 1.17519 2.13432 2.51589 + vertex 1.17117 2.13166 2.51746 + endloop + endfacet + facet normal 0.216077 0.238923 0.946692 + outer loop + vertex 1.17127 2.1359 2.51634 + vertex 1.16945 2.13891 2.51599 + vertex 1.16663 2.13591 2.51739 + endloop + endfacet + facet normal 0.214117 0.236034 0.947862 + outer loop + vertex 1.16693 2.13131 2.51847 + vertex 1.16663 2.13591 2.51739 + vertex 1.16384 2.13287 2.51878 + endloop + endfacet + facet normal 0.203183 0.2507 0.946502 + outer loop + vertex 1.17267 2.12683 2.51841 + vertex 1.17117 2.13166 2.51746 + vertex 1.16873 2.12838 2.51885 + endloop + endfacet + facet normal 0.204164 0.253461 0.945555 + outer loop + vertex 1.16867 2.1242 2.51998 + vertex 1.17267 2.12683 2.51841 + vertex 1.16873 2.12838 2.51885 + endloop + endfacet + facet normal 0.203074 0.253908 0.94567 + outer loop + vertex 1.1644 2.12385 2.52099 + vertex 1.16624 2.12094 2.52138 + vertex 1.16867 2.1242 2.51998 + endloop + endfacet + facet normal 0.203995 0.254444 0.945327 + outer loop + vertex 1.16624 2.12094 2.52138 + vertex 1.1644 2.12385 2.52099 + vertex 1.16158 2.12089 2.5224 + endloop + endfacet + facet normal 0.200017 0.25289 0.946594 + outer loop + vertex 1.16194 2.11639 2.52352 + vertex 1.16158 2.12089 2.5224 + vertex 1.15879 2.11786 2.5238 + endloop + endfacet + facet normal 0.200559 0.256933 0.94539 + outer loop + vertex 1.1638 2.1135 2.52392 + vertex 1.16621 2.11675 2.52252 + vertex 1.16194 2.11639 2.52352 + endloop + endfacet + facet normal 0.200385 0.2554 0.945842 + outer loop + vertex 1.16376 2.10932 2.52505 + vertex 1.16776 2.11194 2.52349 + vertex 1.1638 2.1135 2.52392 + endloop + endfacet + facet normal 0.201996 0.251328 0.946589 + outer loop + vertex 1.15947 2.10896 2.52606 + vertex 1.16133 2.10605 2.52644 + vertex 1.16376 2.10932 2.52505 + endloop + endfacet + facet normal 0.202448 0.251594 0.946422 + outer loop + vertex 1.16133 2.10605 2.52644 + vertex 1.15947 2.10896 2.52606 + vertex 1.15663 2.10597 2.52746 + endloop + endfacet + facet normal 0.218594 0.245685 0.944381 + outer loop + vertex 1.152 2.10609 2.52844 + vertex 1.15159 2.11074 2.52733 + vertex 1.14883 2.10777 2.52874 + endloop + endfacet + facet normal 0.203651 0.244115 0.948122 + outer loop + vertex 1.15663 2.10597 2.52746 + vertex 1.15703 2.10139 2.52856 + vertex 1.1613 2.10178 2.52754 + endloop + endfacet + facet normal 0.204736 0.236613 0.949788 + outer loop + vertex 1.15899 2.09835 2.52889 + vertex 1.1613 2.10178 2.52754 + vertex 1.15703 2.10139 2.52856 + endloop + endfacet + facet normal 0.205494 0.23609 0.949755 + outer loop + vertex 1.16286 2.09702 2.52839 + vertex 1.1613 2.10178 2.52754 + vertex 1.15899 2.09835 2.52889 + endloop + endfacet + facet normal 0.202549 0.233722 0.950972 + outer loop + vertex 1.16655 2.09549 2.52798 + vertex 1.16679 2.09959 2.52692 + vertex 1.16286 2.09702 2.52839 + endloop + endfacet + facet normal 0.197484 0.234281 0.951899 + outer loop + vertex 1.16778 2.09194 2.52859 + vertex 1.17129 2.0953 2.52704 + vertex 1.16655 2.09549 2.52798 + endloop + endfacet + facet normal 0.19459 0.237241 0.951762 + outer loop + vertex 1.17168 2.09058 2.52814 + vertex 1.17129 2.0953 2.52704 + vertex 1.16778 2.09194 2.52859 + endloop + endfacet + facet normal 0.191313 0.243224 0.950916 + outer loop + vertex 1.17365 2.08752 2.52852 + vertex 1.17644 2.09061 2.52717 + vertex 1.17168 2.09058 2.52814 + endloop + endfacet + facet normal 0.189308 0.248995 0.949823 + outer loop + vertex 1.17402 2.08299 2.52964 + vertex 1.17687 2.08601 2.52828 + vertex 1.17365 2.08752 2.52852 + endloop + endfacet + facet normal 0.186955 0.248628 0.950385 + outer loop + vertex 1.17114 2.08 2.53098 + vertex 1.16927 2.08294 2.53058 + vertex 1.16681 2.07965 2.53193 + endloop + endfacet + facet normal 0.184505 0.250677 0.950326 + outer loop + vertex 1.17434 2.07853 2.53075 + vertex 1.179 2.0785 2.52985 + vertex 1.17402 2.08299 2.52964 + endloop + endfacet + facet normal 0.186928 0.248833 0.950337 + outer loop + vertex 1.17114 2.08 2.53098 + vertex 1.16681 2.07965 2.53193 + vertex 1.17148 2.07549 2.5321 + endloop + endfacet + facet normal 0.184508 0.250603 0.950345 + outer loop + vertex 1.17434 2.07853 2.53075 + vertex 1.17614 2.0755 2.5312 + vertex 1.179 2.0785 2.52985 + endloop + endfacet + facet normal 0.185963 0.249724 0.950293 + outer loop + vertex 1.179 2.0785 2.52985 + vertex 1.18371 2.07431 2.53003 + vertex 1.18375 2.07853 2.52892 + endloop + endfacet + facet normal 0.183807 0.24153 0.952826 + outer loop + vertex 1.18123 2.07105 2.53136 + vertex 1.17935 2.07402 2.53097 + vertex 1.17646 2.071 2.53229 + endloop + endfacet + facet normal 0.186925 0.241131 0.952321 + outer loop + vertex 1.18371 2.07431 2.53003 + vertex 1.18527 2.06942 2.53096 + vertex 1.18934 2.07209 2.52949 + endloop + endfacet + facet normal 0.18419 0.234976 0.95439 + outer loop + vertex 1.18123 2.07105 2.53136 + vertex 1.17646 2.071 2.53229 + vertex 1.18115 2.06678 2.53242 + endloop + endfacet + facet normal 0.18951 0.238438 0.952488 + outer loop + vertex 1.18927 2.06788 2.53056 + vertex 1.18527 2.06942 2.53096 + vertex 1.18681 2.06456 2.53188 + endloop + endfacet + facet normal 0.185 0.235866 0.954014 + outer loop + vertex 1.17646 2.071 2.53229 + vertex 1.17677 2.06646 2.53335 + vertex 1.18115 2.06678 2.53242 + endloop + endfacet + facet normal 0.183391 0.237521 0.953914 + outer loop + vertex 1.17357 2.06794 2.53361 + vertex 1.1718 2.07099 2.53319 + vertex 1.16891 2.0679 2.53451 + endloop + endfacet + facet normal 0.187153 0.239738 0.952628 + outer loop + vertex 1.16419 2.06779 2.53547 + vertex 1.16891 2.0679 2.53451 + vertex 1.16428 2.07208 2.53437 + endloop + endfacet + facet normal 0.184578 0.243866 0.952082 + outer loop + vertex 1.16861 2.07245 2.53343 + vertex 1.17148 2.07549 2.5321 + vertex 1.16675 2.0754 2.53304 + endloop + endfacet + facet normal 0.184429 0.246076 0.951542 + outer loop + vertex 1.16681 2.07965 2.53193 + vertex 1.16675 2.0754 2.53304 + vertex 1.17148 2.07549 2.5321 + endloop + endfacet + facet normal 0.192476 0.244253 0.950417 + outer loop + vertex 1.16428 2.07208 2.53437 + vertex 1.16275 2.07697 2.53343 + vertex 1.15869 2.07429 2.53494 + endloop + endfacet + facet normal 0.196201 0.240568 0.950596 + outer loop + vertex 1.1544 2.07394 2.53591 + vertex 1.15622 2.071 2.53628 + vertex 1.15869 2.07429 2.53494 + endloop + endfacet + facet normal 0.196554 0.240772 0.950471 + outer loop + vertex 1.15622 2.071 2.53628 + vertex 1.1544 2.07394 2.53591 + vertex 1.15151 2.07096 2.53726 + endloop + endfacet + facet normal 0.19682 0.238765 0.950922 + outer loop + vertex 1.15184 2.06642 2.53833 + vertex 1.15151 2.07096 2.53726 + vertex 1.14866 2.06794 2.53861 + endloop + endfacet + facet normal 0.194498 0.233606 0.95268 + outer loop + vertex 1.14902 2.06334 2.53966 + vertex 1.15184 2.06642 2.53833 + vertex 1.14866 2.06794 2.53861 + endloop + endfacet + facet normal 0.194042 0.229538 0.953761 + outer loop + vertex 1.14939 2.05862 2.54073 + vertex 1.15431 2.0585 2.53975 + vertex 1.14902 2.06334 2.53966 + endloop + endfacet + facet normal 0.189007 0.222795 0.956367 + outer loop + vertex 1.15124 2.05536 2.54112 + vertex 1.14939 2.05862 2.54073 + vertex 1.14633 2.05543 2.54207 + endloop + endfacet + facet normal 0.184334 0.225761 0.956584 + outer loop + vertex 1.14602 2.0603 2.541 + vertex 1.14422 2.06348 2.54059 + vertex 1.14122 2.0603 2.54192 + endloop + endfacet + facet normal 0.183991 0.223177 0.957256 + outer loop + vertex 1.14298 2.05196 2.54353 + vertex 1.14633 2.05543 2.54207 + vertex 1.14151 2.0556 2.54296 + endloop + endfacet + facet normal 0.184463 0.220184 0.957858 + outer loop + vertex 1.14441 2.04834 2.54408 + vertex 1.1467 2.05062 2.54312 + vertex 1.14298 2.05196 2.54353 + endloop + endfacet + facet normal 0.187422 0.217252 0.957953 + outer loop + vertex 1.14807 2.04703 2.54366 + vertex 1.1467 2.05062 2.54312 + vertex 1.14441 2.04834 2.54408 + endloop + endfacet + facet normal 0.189744 0.215008 0.958003 + outer loop + vertex 1.14928 2.04356 2.5442 + vertex 1.15169 2.04575 2.54323 + vertex 1.14807 2.04703 2.54366 + endloop + endfacet + facet normal 0.185577 0.213934 0.959058 + outer loop + vertex 1.14463 2.03922 2.54608 + vertex 1.14897 2.03949 2.54518 + vertex 1.14455 2.04379 2.54508 + endloop + endfacet + facet normal 0.189417 0.213839 0.958329 + outer loop + vertex 1.14463 2.03922 2.54608 + vertex 1.14455 2.04379 2.54508 + vertex 1.1415 2.04073 2.54636 + endloop + endfacet + facet normal 0.189023 0.212971 0.9586 + outer loop + vertex 1.1415 2.04073 2.54636 + vertex 1.14165 2.03616 2.54735 + vertex 1.14463 2.03922 2.54608 + endloop + endfacet + facet normal 0.187551 0.214394 0.958572 + outer loop + vertex 1.14637 2.03621 2.54642 + vertex 1.14463 2.03922 2.54608 + vertex 1.14165 2.03616 2.54735 + endloop + endfacet + facet normal 0.187369 0.217864 0.957825 + outer loop + vertex 1.14637 2.03621 2.54642 + vertex 1.14165 2.03616 2.54735 + vertex 1.14623 2.03186 2.54743 + endloop + endfacet + facet normal 0.177002 0.218623 0.959622 + outer loop + vertex 1.14637 2.03621 2.54642 + vertex 1.14623 2.03186 2.54743 + vertex 1.15038 2.03457 2.54605 + endloop + endfacet + facet normal 0.181666 0.211834 0.960273 + outer loop + vertex 1.14165 2.03616 2.54735 + vertex 1.14186 2.03151 2.54834 + vertex 1.14623 2.03186 2.54743 + endloop + endfacet + facet normal 0.191657 0.211887 0.958317 + outer loop + vertex 1.14186 2.03151 2.54834 + vertex 1.14165 2.03616 2.54735 + vertex 1.1387 2.03306 2.54863 + endloop + endfacet + facet normal 0.19182 0.212241 0.958206 + outer loop + vertex 1.13898 2.02838 2.54961 + vertex 1.14186 2.03151 2.54834 + vertex 1.1387 2.03306 2.54863 + endloop + endfacet + facet normal 0.192547 0.212252 0.958058 + outer loop + vertex 1.13406 2.03311 2.54955 + vertex 1.13898 2.02838 2.54961 + vertex 1.1387 2.03306 2.54863 + endloop + endfacet + facet normal 0.192551 0.212124 0.958085 + outer loop + vertex 1.1387 2.03306 2.54863 + vertex 1.13701 2.03619 2.54827 + vertex 1.13406 2.03311 2.54955 + endloop + endfacet + facet normal 0.19229 0.211986 0.958169 + outer loop + vertex 1.1342 2.02856 2.55053 + vertex 1.13898 2.02838 2.54961 + vertex 1.13406 2.03311 2.54955 + endloop + endfacet + facet normal 0.189439 0.212022 0.958728 + outer loop + vertex 1.1342 2.02856 2.55053 + vertex 1.13406 2.03311 2.54955 + vertex 1.13104 2.03009 2.55081 + endloop + endfacet + facet normal 0.186854 0.206369 0.960467 + outer loop + vertex 1.13104 2.03009 2.55081 + vertex 1.13118 2.02537 2.5518 + vertex 1.1342 2.02856 2.55053 + endloop + endfacet + facet normal 0.188306 0.204997 0.960477 + outer loop + vertex 1.13594 2.02535 2.55087 + vertex 1.1342 2.02856 2.55053 + vertex 1.13118 2.02537 2.5518 + endloop + endfacet + facet normal 0.188385 0.202787 0.960931 + outer loop + vertex 1.13594 2.02535 2.55087 + vertex 1.13118 2.02537 2.5518 + vertex 1.13619 2.02045 2.55185 + endloop + endfacet + facet normal 0.1885 0.202788 0.960908 + outer loop + vertex 1.13594 2.02535 2.55087 + vertex 1.13619 2.02045 2.55185 + vertex 1.13927 2.02361 2.55058 + endloop + endfacet + facet normal 0.19117 0.208184 0.959226 + outer loop + vertex 1.13927 2.02361 2.55058 + vertex 1.13898 2.02838 2.54961 + vertex 1.13594 2.02535 2.55087 + endloop + endfacet + facet normal 0.180385 0.207961 0.96136 + outer loop + vertex 1.13927 2.02361 2.55058 + vertex 1.14423 2.02345 2.54969 + vertex 1.13898 2.02838 2.54961 + endloop + endfacet + facet normal 0.187823 0.215826 0.958197 + outer loop + vertex 1.13898 2.02838 2.54961 + vertex 1.14423 2.02345 2.54969 + vertex 1.1438 2.02837 2.54867 + endloop + endfacet + facet normal 0.170763 0.21502 0.961565 + outer loop + vertex 1.14423 2.02345 2.54969 + vertex 1.1478 2.02693 2.54828 + vertex 1.1438 2.02837 2.54867 + endloop + endfacet + facet normal 0.172088 0.219034 0.960422 + outer loop + vertex 1.1478 2.02693 2.54828 + vertex 1.14623 2.03186 2.54743 + vertex 1.1438 2.02837 2.54867 + endloop + endfacet + facet normal 0.181608 0.212314 0.960178 + outer loop + vertex 1.1438 2.02837 2.54867 + vertex 1.14623 2.03186 2.54743 + vertex 1.14186 2.03151 2.54834 + endloop + endfacet + facet normal 0.167697 0.21782 0.961474 + outer loop + vertex 1.1478 2.02693 2.54828 + vertex 1.15185 2.02964 2.54695 + vertex 1.14623 2.03186 2.54743 + endloop + endfacet + facet normal 0.171136 0.227127 0.95871 + outer loop + vertex 1.15185 2.02964 2.54695 + vertex 1.15038 2.03457 2.54605 + vertex 1.14623 2.03186 2.54743 + endloop + endfacet + facet normal 0.168846 0.226542 0.959255 + outer loop + vertex 1.15445 2.03302 2.5457 + vertex 1.15038 2.03457 2.54605 + vertex 1.15185 2.02964 2.54695 + endloop + endfacet + facet normal 0.165585 0.229044 0.959229 + outer loop + vertex 1.15629 2.03012 2.54608 + vertex 1.15445 2.03302 2.5457 + vertex 1.15185 2.02964 2.54695 + endloop + endfacet + facet normal 0.176143 0.235279 0.955833 + outer loop + vertex 1.15445 2.03302 2.5457 + vertex 1.15629 2.03012 2.54608 + vertex 1.15936 2.03333 2.54472 + endloop + endfacet + facet normal 0.170416 0.230955 0.957924 + outer loop + vertex 1.15038 2.03457 2.54605 + vertex 1.15445 2.03302 2.5457 + vertex 1.15454 2.03735 2.54464 + endloop + endfacet + facet normal 0.163459 0.223844 0.96082 + outer loop + vertex 1.15163 2.02544 2.54797 + vertex 1.15185 2.02964 2.54695 + vertex 1.1478 2.02693 2.54828 + endloop + endfacet + facet normal 0.161287 0.21791 0.96255 + outer loop + vertex 1.1492 2.02321 2.54888 + vertex 1.15163 2.02544 2.54797 + vertex 1.1478 2.02693 2.54828 + endloop + endfacet + facet normal 0.167354 0.211484 0.962947 + outer loop + vertex 1.15297 2.02202 2.54849 + vertex 1.15163 2.02544 2.54797 + vertex 1.1492 2.02321 2.54888 + endloop + endfacet + facet normal 0.163844 0.199328 0.966139 + outer loop + vertex 1.14942 2.01851 2.54982 + vertex 1.15297 2.02202 2.54849 + vertex 1.1492 2.02321 2.54888 + endloop + endfacet + facet normal 0.165957 0.199356 0.965772 + outer loop + vertex 1.14423 2.02345 2.54969 + vertex 1.14942 2.01851 2.54982 + vertex 1.1492 2.02321 2.54888 + endloop + endfacet + facet normal 0.173424 0.207133 0.962819 + outer loop + vertex 1.14447 2.01859 2.55069 + vertex 1.14942 2.01851 2.54982 + vertex 1.14423 2.02345 2.54969 + endloop + endfacet + facet normal 0.175637 0.207157 0.962412 + outer loop + vertex 1.14447 2.01859 2.55069 + vertex 1.14423 2.02345 2.54969 + vertex 1.1411 2.02031 2.55094 + endloop + endfacet + facet normal 0.173865 0.20353 0.963507 + outer loop + vertex 1.1411 2.02031 2.55094 + vertex 1.14131 2.01539 2.55194 + vertex 1.14447 2.01859 2.55069 + endloop + endfacet + facet normal 0.168987 0.208295 0.963357 + outer loop + vertex 1.14623 2.01533 2.55109 + vertex 1.14447 2.01859 2.55069 + vertex 1.14131 2.01539 2.55194 + endloop + endfacet + facet normal 0.169112 0.203186 0.964425 + outer loop + vertex 1.14623 2.01533 2.55109 + vertex 1.14131 2.01539 2.55194 + vertex 1.14624 2.01053 2.5521 + endloop + endfacet + facet normal 0.184462 0.202647 0.961721 + outer loop + vertex 1.14623 2.01533 2.55109 + vertex 1.14624 2.01053 2.5521 + vertex 1.14948 2.0137 2.55081 + endloop + endfacet + facet normal 0.183436 0.200493 0.962369 + outer loop + vertex 1.14948 2.0137 2.55081 + vertex 1.14942 2.01851 2.54982 + vertex 1.14623 2.01533 2.55109 + endloop + endfacet + facet normal 0.257898 0.197912 0.945685 + outer loop + vertex 1.14948 2.0137 2.55081 + vertex 1.15414 2.01361 2.54955 + vertex 1.14942 2.01851 2.54982 + endloop + endfacet + facet normal 0.193089 0.134157 0.971966 + outer loop + vertex 1.14942 2.01851 2.54982 + vertex 1.15414 2.01361 2.54955 + vertex 1.15438 2.01849 2.54883 + endloop + endfacet + facet normal 0.286928 0.126086 0.949618 + outer loop + vertex 1.15414 2.01361 2.54955 + vertex 1.15835 2.01733 2.54779 + vertex 1.15438 2.01849 2.54883 + endloop + endfacet + facet normal 0.283467 0.111646 0.952461 + outer loop + vertex 1.15835 2.01733 2.54779 + vertex 1.15659 2.02105 2.54788 + vertex 1.15438 2.01849 2.54883 + endloop + endfacet + facet normal 0.210562 0.177606 0.961312 + outer loop + vertex 1.15438 2.01849 2.54883 + vertex 1.15659 2.02105 2.54788 + vertex 1.15297 2.02202 2.54849 + endloop + endfacet + facet normal 0.302859 0.120968 0.945327 + outer loop + vertex 1.16039 2.02179 2.54656 + vertex 1.15659 2.02105 2.54788 + vertex 1.15835 2.01733 2.54779 + endloop + endfacet + facet normal 0.25738 0.212244 0.942713 + outer loop + vertex 1.14948 2.0137 2.55081 + vertex 1.1509 2.01057 2.55112 + vertex 1.15414 2.01361 2.54955 + endloop + endfacet + facet normal 0.308985 0.155139 0.938328 + outer loop + vertex 1.15361 2.00873 2.55053 + vertex 1.15414 2.01361 2.54955 + vertex 1.1509 2.01057 2.55112 + endloop + endfacet + facet normal 0.310515 0.157692 0.937397 + outer loop + vertex 1.1509 2.01057 2.55112 + vertex 1.15034 2.00624 2.55204 + vertex 1.15361 2.00873 2.55053 + endloop + endfacet + facet normal 0.199607 0.177611 0.963645 + outer loop + vertex 1.1509 2.01057 2.55112 + vertex 1.14624 2.01053 2.5521 + vertex 1.15034 2.00624 2.55204 + endloop + endfacet + facet normal 0.232816 0.209584 0.949669 + outer loop + vertex 1.14624 2.01053 2.5521 + vertex 1.14643 2.00578 2.5531 + vertex 1.15034 2.00624 2.55204 + endloop + endfacet + facet normal 0.234109 0.2018 0.951036 + outer loop + vertex 1.14787 2.00223 2.5535 + vertex 1.15034 2.00624 2.55204 + vertex 1.14643 2.00578 2.5531 + endloop + endfacet + facet normal 0.19338 0.186618 0.963212 + outer loop + vertex 1.14787 2.00223 2.5535 + vertex 1.14643 2.00578 2.5531 + vertex 1.14426 2.00332 2.55401 + endloop + endfacet + facet normal 0.193246 0.186115 0.963336 + outer loop + vertex 1.14446 1.99858 2.55489 + vertex 1.14787 2.00223 2.5535 + vertex 1.14426 2.00332 2.55401 + endloop + endfacet + facet normal 0.155763 0.185836 0.970156 + outer loop + vertex 1.13937 2.00349 2.55476 + vertex 1.14446 1.99858 2.55489 + vertex 1.14426 2.00332 2.55401 + endloop + endfacet + facet normal 0.155833 0.209167 0.965384 + outer loop + vertex 1.14426 2.00332 2.55401 + vertex 1.14289 2.0069 2.55345 + vertex 1.13937 2.00349 2.55476 + endloop + endfacet + facet normal 0.158608 0.206366 0.965534 + outer loop + vertex 1.13937 2.00349 2.55476 + vertex 1.14289 2.0069 2.55345 + vertex 1.1392 2.00819 2.55379 + endloop + endfacet + facet normal 0.177044 0.20639 0.962319 + outer loop + vertex 1.13427 2.0085 2.55463 + vertex 1.13937 2.00349 2.55476 + vertex 1.1392 2.00819 2.55379 + endloop + endfacet + facet normal 0.176878 0.20018 0.963661 + outer loop + vertex 1.1392 2.00819 2.55379 + vertex 1.13784 2.01187 2.55327 + vertex 1.13427 2.0085 2.55463 + endloop + endfacet + facet normal 0.184406 0.192262 0.963862 + outer loop + vertex 1.13427 2.0085 2.55463 + vertex 1.13784 2.01187 2.55327 + vertex 1.13411 2.01328 2.5537 + endloop + endfacet + facet normal 0.18524 0.192258 0.963703 + outer loop + vertex 1.1292 2.01354 2.55459 + vertex 1.13427 2.0085 2.55463 + vertex 1.13411 2.01328 2.5537 + endloop + endfacet + facet normal 0.185182 0.188851 0.964387 + outer loop + vertex 1.13411 2.01328 2.5537 + vertex 1.13275 2.01699 2.55324 + vertex 1.1292 2.01354 2.55459 + endloop + endfacet + facet normal 0.187601 0.18966 0.963761 + outer loop + vertex 1.13411 2.01328 2.5537 + vertex 1.13648 2.01559 2.55279 + vertex 1.13275 2.01699 2.55324 + endloop + endfacet + facet normal 0.189728 0.195846 0.962106 + outer loop + vertex 1.13648 2.01559 2.55279 + vertex 1.13619 2.02045 2.55185 + vertex 1.13275 2.01699 2.55324 + endloop + endfacet + facet normal 0.190005 0.195572 0.962107 + outer loop + vertex 1.13275 2.01699 2.55324 + vertex 1.13619 2.02045 2.55185 + vertex 1.13138 2.02067 2.55276 + endloop + endfacet + facet normal 0.185453 0.194033 0.963306 + outer loop + vertex 1.13275 2.01699 2.55324 + vertex 1.13138 2.02067 2.55276 + vertex 1.12903 2.01832 2.55368 + endloop + endfacet + facet normal 0.190058 0.204486 0.960241 + outer loop + vertex 1.13118 2.02537 2.5518 + vertex 1.13138 2.02067 2.55276 + vertex 1.13619 2.02045 2.55185 + endloop + endfacet + facet normal 0.181818 0.204455 0.961842 + outer loop + vertex 1.13138 2.02067 2.55276 + vertex 1.13118 2.02537 2.5518 + vertex 1.12769 2.02193 2.55319 + endloop + endfacet + facet normal 0.180343 0.205934 0.961804 + outer loop + vertex 1.12769 2.02193 2.55319 + vertex 1.13118 2.02537 2.5518 + vertex 1.12641 2.02542 2.55268 + endloop + endfacet + facet normal 0.18033 0.206396 0.961708 + outer loop + vertex 1.12673 2.02965 2.55171 + vertex 1.12641 2.02542 2.55268 + vertex 1.13118 2.02537 2.5518 + endloop + endfacet + facet normal 0.172398 0.207282 0.962971 + outer loop + vertex 1.12641 2.02542 2.55268 + vertex 1.12673 2.02965 2.55171 + vertex 1.12263 2.02666 2.55309 + endloop + endfacet + facet normal 0.177968 0.195596 0.964401 + outer loop + vertex 1.13619 2.02045 2.55185 + vertex 1.13648 2.01559 2.55279 + vertex 1.14131 2.01539 2.55194 + endloop + endfacet + facet normal 0.177943 0.190531 0.965419 + outer loop + vertex 1.13784 2.01187 2.55327 + vertex 1.14131 2.01539 2.55194 + vertex 1.13648 2.01559 2.55279 + endloop + endfacet + facet normal 0.181563 0.188568 0.965131 + outer loop + vertex 1.12928 2.00869 2.55553 + vertex 1.13427 2.0085 2.55463 + vertex 1.1292 2.01354 2.55459 + endloop + endfacet + facet normal 0.178689 0.18862 0.965657 + outer loop + vertex 1.12928 2.00869 2.55553 + vertex 1.1292 2.01354 2.55459 + vertex 1.12597 2.01036 2.55581 + endloop + endfacet + facet normal 0.17663 0.184316 0.966866 + outer loop + vertex 1.12597 2.01036 2.55581 + vertex 1.12609 2.00536 2.55675 + vertex 1.12928 2.00869 2.55553 + endloop + endfacet + facet normal 0.176894 0.184063 0.966866 + outer loop + vertex 1.13102 2.00539 2.55584 + vertex 1.12928 2.00869 2.55553 + vertex 1.12609 2.00536 2.55675 + endloop + endfacet + facet normal 0.176479 0.193895 0.965018 + outer loop + vertex 1.13102 2.00539 2.55584 + vertex 1.12609 2.00536 2.55675 + vertex 1.13118 2.00043 2.55681 + endloop + endfacet + facet normal 0.17679 0.193894 0.964961 + outer loop + vertex 1.13102 2.00539 2.55584 + vertex 1.13118 2.00043 2.55681 + vertex 1.13435 2.00367 2.55557 + endloop + endfacet + facet normal 0.175953 0.192202 0.965453 + outer loop + vertex 1.13435 2.00367 2.55557 + vertex 1.13427 2.0085 2.55463 + vertex 1.13102 2.00539 2.55584 + endloop + endfacet + facet normal 0.169648 0.200856 0.964819 + outer loop + vertex 1.13612 2.00038 2.55595 + vertex 1.13435 2.00367 2.55557 + vertex 1.13118 2.00043 2.55681 + endloop + endfacet + facet normal 0.169459 0.208097 0.963317 + outer loop + vertex 1.13612 2.00038 2.55595 + vertex 1.13118 2.00043 2.55681 + vertex 1.13633 1.99552 2.55696 + endloop + endfacet + facet normal 0.158116 0.208011 0.965262 + outer loop + vertex 1.13612 2.00038 2.55595 + vertex 1.13633 1.99552 2.55696 + vertex 1.13952 1.99868 2.55576 + endloop + endfacet + facet normal 0.156418 0.204516 0.966285 + outer loop + vertex 1.13952 1.99868 2.55576 + vertex 1.13937 2.00349 2.55476 + vertex 1.13612 2.00038 2.55595 + endloop + endfacet + facet normal 0.154842 0.211247 0.96509 + outer loop + vertex 1.14131 1.99544 2.55618 + vertex 1.13952 1.99868 2.55576 + vertex 1.13633 1.99552 2.55696 + endloop + endfacet + facet normal 0.154953 0.204737 0.966474 + outer loop + vertex 1.14131 1.99544 2.55618 + vertex 1.13633 1.99552 2.55696 + vertex 1.14139 1.99067 2.55718 + endloop + endfacet + facet normal 0.191902 0.203925 0.959994 + outer loop + vertex 1.14131 1.99544 2.55618 + vertex 1.14139 1.99067 2.55718 + vertex 1.14456 1.99377 2.55588 + endloop + endfacet + facet normal 0.191525 0.203147 0.960234 + outer loop + vertex 1.14456 1.99377 2.55588 + vertex 1.14446 1.99858 2.55489 + vertex 1.14131 1.99544 2.55618 + endloop + endfacet + facet normal 0.304406 0.199606 0.931394 + outer loop + vertex 1.14456 1.99377 2.55588 + vertex 1.14896 1.99359 2.55448 + vertex 1.14446 1.99858 2.55489 + endloop + endfacet + facet normal 0.237027 0.136407 0.961879 + outer loop + vertex 1.14446 1.99858 2.55489 + vertex 1.14896 1.99359 2.55448 + vertex 1.14924 1.99847 2.55372 + endloop + endfacet + facet normal 0.303758 0.222785 0.926336 + outer loop + vertex 1.14456 1.99377 2.55588 + vertex 1.14603 1.99065 2.55615 + vertex 1.14896 1.99359 2.55448 + endloop + endfacet + facet normal 0.352554 0.170541 0.92012 + outer loop + vertex 1.14865 1.98888 2.55548 + vertex 1.14896 1.99359 2.55448 + vertex 1.14603 1.99065 2.55615 + endloop + endfacet + facet normal 0.343828 0.155356 0.926092 + outer loop + vertex 1.14603 1.99065 2.55615 + vertex 1.14554 1.98641 2.55705 + vertex 1.14865 1.98888 2.55548 + endloop + endfacet + facet normal 0.212607 0.177715 0.960841 + outer loop + vertex 1.14603 1.99065 2.55615 + vertex 1.14139 1.99067 2.55718 + vertex 1.14554 1.98641 2.55705 + endloop + endfacet + facet normal 0.251858 0.21651 0.943234 + outer loop + vertex 1.14139 1.99067 2.55718 + vertex 1.14162 1.98597 2.55819 + vertex 1.14554 1.98641 2.55705 + endloop + endfacet + facet normal 0.254929 0.197691 0.946535 + outer loop + vertex 1.14296 1.9824 2.55858 + vertex 1.14554 1.98641 2.55705 + vertex 1.14162 1.98597 2.55819 + endloop + endfacet + facet normal 0.211229 0.182882 0.960175 + outer loop + vertex 1.14296 1.9824 2.55858 + vertex 1.14162 1.98597 2.55819 + vertex 1.13935 1.98369 2.55913 + endloop + endfacet + facet normal 0.215933 0.197692 0.956185 + outer loop + vertex 1.13901 1.97961 2.56005 + vertex 1.14296 1.9824 2.55858 + vertex 1.13935 1.98369 2.55913 + endloop + endfacet + facet normal 0.156226 0.204864 0.966242 + outer loop + vertex 1.13448 1.98384 2.55988 + vertex 1.13901 1.97961 2.56005 + vertex 1.13935 1.98369 2.55913 + endloop + endfacet + facet normal 0.156183 0.218079 0.963353 + outer loop + vertex 1.13935 1.98369 2.55913 + vertex 1.13803 1.98714 2.55856 + vertex 1.13448 1.98384 2.55988 + endloop + endfacet + facet normal 0.151042 0.223453 0.962941 + outer loop + vertex 1.13448 1.98384 2.55988 + vertex 1.13803 1.98714 2.55856 + vertex 1.13429 1.98841 2.55885 + endloop + endfacet + facet normal 0.160538 0.223487 0.961395 + outer loop + vertex 1.12944 1.98846 2.55965 + vertex 1.13448 1.98384 2.55988 + vertex 1.13429 1.98841 2.55885 + endloop + endfacet + facet normal 0.160671 0.218544 0.962509 + outer loop + vertex 1.13429 1.98841 2.55885 + vertex 1.13289 1.992 2.55827 + vertex 1.12944 1.98846 2.55965 + endloop + endfacet + facet normal 0.165869 0.21358 0.962741 + outer loop + vertex 1.12944 1.98846 2.55965 + vertex 1.13289 1.992 2.55827 + vertex 1.12923 1.99312 2.55865 + endloop + endfacet + facet normal 0.165828 0.21358 0.962749 + outer loop + vertex 1.12476 1.99262 2.55953 + vertex 1.12944 1.98846 2.55965 + vertex 1.12923 1.99312 2.55865 + endloop + endfacet + facet normal 0.167775 0.200565 0.965207 + outer loop + vertex 1.12923 1.99312 2.55865 + vertex 1.12772 1.99665 2.55818 + vertex 1.12476 1.99262 2.55953 + endloop + endfacet + facet normal 0.167507 0.200764 0.965213 + outer loop + vertex 1.12476 1.99262 2.55953 + vertex 1.12772 1.99665 2.55818 + vertex 1.12333 1.99743 2.55878 + endloop + endfacet + facet normal 0.152922 0.196933 0.968417 + outer loop + vertex 1.12476 1.99262 2.55953 + vertex 1.12333 1.99743 2.55878 + vertex 1.119 1.99458 2.56004 + endloop + endfacet + facet normal 0.155629 0.205455 0.966213 + outer loop + vertex 1.119 1.99458 2.56004 + vertex 1.12035 1.98963 2.56088 + vertex 1.12476 1.99262 2.55953 + endloop + endfacet + facet normal 0.152683 0.209604 0.965792 + outer loop + vertex 1.12035 1.98963 2.56088 + vertex 1.12446 1.9882 2.56054 + vertex 1.12476 1.99262 2.55953 + endloop + endfacet + facet normal 0.152404 0.208746 0.966022 + outer loop + vertex 1.12446 1.9882 2.56054 + vertex 1.12035 1.98963 2.56088 + vertex 1.12177 1.9846 2.56174 + endloop + endfacet + facet normal 0.153708 0.207771 0.966026 + outer loop + vertex 1.12627 1.9852 2.5609 + vertex 1.12446 1.9882 2.56054 + vertex 1.12177 1.9846 2.56174 + endloop + endfacet + facet normal 0.153302 0.210178 0.965569 + outer loop + vertex 1.12627 1.9852 2.5609 + vertex 1.12177 1.9846 2.56174 + vertex 1.12634 1.98036 2.56194 + endloop + endfacet + facet normal 0.155412 0.21014 0.96524 + outer loop + vertex 1.12627 1.9852 2.5609 + vertex 1.12634 1.98036 2.56194 + vertex 1.12954 1.98378 2.56068 + endloop + endfacet + facet normal 0.157605 0.215421 0.963719 + outer loop + vertex 1.12954 1.98378 2.56068 + vertex 1.12944 1.98846 2.55965 + vertex 1.12627 1.9852 2.5609 + endloop + endfacet + facet normal 0.150175 0.214946 0.965011 + outer loop + vertex 1.1313 1.98063 2.56111 + vertex 1.12954 1.98378 2.56068 + vertex 1.12634 1.98036 2.56194 + endloop + endfacet + facet normal 0.150292 0.213644 0.965282 + outer loop + vertex 1.1313 1.98063 2.56111 + vertex 1.12634 1.98036 2.56194 + vertex 1.13139 1.97576 2.56217 + endloop + endfacet + facet normal 0.145915 0.213702 0.96594 + outer loop + vertex 1.1313 1.98063 2.56111 + vertex 1.13139 1.97576 2.56217 + vertex 1.1346 1.97919 2.56093 + endloop + endfacet + facet normal 0.148773 0.220531 0.963967 + outer loop + vertex 1.1346 1.97919 2.56093 + vertex 1.13448 1.98384 2.55988 + vertex 1.1313 1.98063 2.56111 + endloop + endfacet + facet normal 0.145947 0.213672 0.965942 + outer loop + vertex 1.13638 1.97619 2.56132 + vertex 1.1346 1.97919 2.56093 + vertex 1.13139 1.97576 2.56217 + endloop + endfacet + facet normal 0.147121 0.203795 0.967896 + outer loop + vertex 1.13638 1.97619 2.56132 + vertex 1.13139 1.97576 2.56217 + vertex 1.136 1.97174 2.56232 + endloop + endfacet + facet normal 0.199247 0.197522 0.959836 + outer loop + vertex 1.13638 1.97619 2.56132 + vertex 1.136 1.97174 2.56232 + vertex 1.14015 1.97477 2.56083 + endloop + endfacet + facet normal 0.201068 0.202862 0.958342 + outer loop + vertex 1.14015 1.97477 2.56083 + vertex 1.13901 1.97961 2.56005 + vertex 1.13638 1.97619 2.56132 + endloop + endfacet + facet normal 0.28266 0.21813 0.934089 + outer loop + vertex 1.13901 1.97961 2.56005 + vertex 1.14015 1.97477 2.56083 + vertex 1.1441 1.97752 2.55899 + endloop + endfacet + facet normal 0.314582 0.171962 0.933524 + outer loop + vertex 1.14015 1.97477 2.56083 + vertex 1.14345 1.97316 2.56002 + vertex 1.1441 1.97752 2.55899 + endloop + endfacet + facet normal 0.316786 0.177381 0.931763 + outer loop + vertex 1.14345 1.97316 2.56002 + vertex 1.14015 1.97477 2.56083 + vertex 1.14071 1.97037 2.56148 + endloop + endfacet + facet normal 0.220213 0.169242 0.960658 + outer loop + vertex 1.14071 1.97037 2.56148 + vertex 1.14015 1.97477 2.56083 + vertex 1.136 1.97174 2.56232 + endloop + endfacet + facet normal 0.228429 0.202729 0.952219 + outer loop + vertex 1.13752 1.96697 2.56297 + vertex 1.14071 1.97037 2.56148 + vertex 1.136 1.97174 2.56232 + endloop + endfacet + facet normal 0.182402 0.189836 0.964724 + outer loop + vertex 1.13752 1.96697 2.56297 + vertex 1.136 1.97174 2.56232 + vertex 1.13319 1.96748 2.56369 + endloop + endfacet + facet normal 0.183586 0.204292 0.961541 + outer loop + vertex 1.13458 1.96399 2.56416 + vertex 1.13752 1.96697 2.56297 + vertex 1.13319 1.96748 2.56369 + endloop + endfacet + facet normal 0.149636 0.191922 0.969936 + outer loop + vertex 1.13458 1.96399 2.56416 + vertex 1.13319 1.96748 2.56369 + vertex 1.12958 1.96367 2.565 + endloop + endfacet + facet normal 0.150236 0.185496 0.971092 + outer loop + vertex 1.12958 1.96367 2.565 + vertex 1.13401 1.95969 2.56507 + vertex 1.13458 1.96399 2.56416 + endloop + endfacet + facet normal 0.235312 0.171314 0.956703 + outer loop + vertex 1.13401 1.95969 2.56507 + vertex 1.13823 1.96262 2.56351 + vertex 1.13458 1.96399 2.56416 + endloop + endfacet + facet normal 0.268073 0.123461 0.955455 + outer loop + vertex 1.139 1.95774 2.56392 + vertex 1.13823 1.96262 2.56351 + vertex 1.13401 1.95969 2.56507 + endloop + endfacet + facet normal 0.296165 0.209241 0.931936 + outer loop + vertex 1.13401 1.95969 2.56507 + vertex 1.13509 1.95485 2.56582 + vertex 1.139 1.95774 2.56392 + endloop + endfacet + facet normal 0.327474 0.165794 0.930201 + outer loop + vertex 1.13509 1.95485 2.56582 + vertex 1.13837 1.95333 2.56493 + vertex 1.139 1.95774 2.56392 + endloop + endfacet + facet normal 0.198626 0.19198 0.961089 + outer loop + vertex 1.13509 1.95485 2.56582 + vertex 1.13401 1.95969 2.56507 + vertex 1.13134 1.9562 2.56632 + endloop + endfacet + facet normal 0.199037 0.193249 0.960749 + outer loop + vertex 1.13134 1.9562 2.56632 + vertex 1.13098 1.95176 2.56729 + vertex 1.13509 1.95485 2.56582 + endloop + endfacet + facet normal 0.220041 0.165556 0.961339 + outer loop + vertex 1.13568 1.95045 2.56644 + vertex 1.13509 1.95485 2.56582 + vertex 1.13098 1.95176 2.56729 + endloop + endfacet + facet normal 0.230335 0.209368 0.950321 + outer loop + vertex 1.13252 1.94702 2.56796 + vertex 1.13568 1.95045 2.56644 + vertex 1.13098 1.95176 2.56729 + endloop + endfacet + facet normal 0.171908 0.192685 0.966085 + outer loop + vertex 1.13252 1.94702 2.56796 + vertex 1.13098 1.95176 2.56729 + vertex 1.12818 1.94749 2.56864 + endloop + endfacet + facet normal 0.173156 0.209491 0.962357 + outer loop + vertex 1.12959 1.944 2.56915 + vertex 1.13252 1.94702 2.56796 + vertex 1.12818 1.94749 2.56864 + endloop + endfacet + facet normal 0.129992 0.193521 0.972446 + outer loop + vertex 1.12959 1.944 2.56915 + vertex 1.12818 1.94749 2.56864 + vertex 1.12455 1.9436 2.5699 + endloop + endfacet + facet normal 0.130765 0.186276 0.973756 + outer loop + vertex 1.12455 1.9436 2.5699 + vertex 1.129 1.93963 2.57006 + vertex 1.12959 1.944 2.56915 + endloop + endfacet + facet normal 0.23143 0.169531 0.957966 + outer loop + vertex 1.129 1.93963 2.57006 + vertex 1.13323 1.94257 2.56852 + vertex 1.12959 1.944 2.56915 + endloop + endfacet + facet normal 0.26942 0.11393 0.95626 + outer loop + vertex 1.13391 1.93709 2.56898 + vertex 1.13323 1.94257 2.56852 + vertex 1.129 1.93963 2.57006 + endloop + endfacet + facet normal 0.316613 0.219317 0.922852 + outer loop + vertex 1.129 1.93963 2.57006 + vertex 1.1299 1.93494 2.57087 + vertex 1.13391 1.93709 2.56898 + endloop + endfacet + facet normal 0.308393 0.233961 0.922039 + outer loop + vertex 1.1299 1.93494 2.57087 + vertex 1.13232 1.93367 2.57038 + vertex 1.13391 1.93709 2.56898 + endloop + endfacet + facet normal 0.177086 0.199588 0.963745 + outer loop + vertex 1.1299 1.93494 2.57087 + vertex 1.129 1.93963 2.57006 + vertex 1.12634 1.93621 2.57126 + endloop + endfacet + facet normal 0.172188 0.184625 0.967608 + outer loop + vertex 1.12634 1.93621 2.57126 + vertex 1.12591 1.93179 2.57218 + vertex 1.1299 1.93494 2.57087 + endloop + endfacet + facet normal 0.109457 0.192238 0.975225 + outer loop + vertex 1.12634 1.93621 2.57126 + vertex 1.1214 1.93555 2.57194 + vertex 1.12591 1.93179 2.57218 + endloop + endfacet + facet normal 0.117455 0.201658 0.972388 + outer loop + vertex 1.1214 1.93555 2.57194 + vertex 1.12136 1.93064 2.57297 + vertex 1.12591 1.93179 2.57218 + endloop + endfacet + facet normal 0.117649 0.200968 0.972507 + outer loop + vertex 1.12306 1.9271 2.57349 + vertex 1.12591 1.93179 2.57218 + vertex 1.12136 1.93064 2.57297 + endloop + endfacet + facet normal 0.106736 0.196076 0.974762 + outer loop + vertex 1.12306 1.9271 2.57349 + vertex 1.12136 1.93064 2.57297 + vertex 1.11836 1.92747 2.57393 + endloop + endfacet + facet normal 0.106698 0.195442 0.974894 + outer loop + vertex 1.1199 1.92265 2.57473 + vertex 1.12306 1.9271 2.57349 + vertex 1.11836 1.92747 2.57393 + endloop + endfacet + facet normal 0.110189 0.19646 0.974301 + outer loop + vertex 1.1199 1.92265 2.57473 + vertex 1.11836 1.92747 2.57393 + vertex 1.11389 1.9246 2.57502 + endloop + endfacet + facet normal 0.109204 0.193318 0.97504 + outer loop + vertex 1.11389 1.9246 2.57502 + vertex 1.11533 1.91965 2.57584 + vertex 1.1199 1.92265 2.57473 + endloop + endfacet + facet normal 0.107529 0.195754 0.97474 + outer loop + vertex 1.11533 1.91965 2.57584 + vertex 1.11959 1.9182 2.57566 + vertex 1.1199 1.92265 2.57473 + endloop + endfacet + facet normal 0.169151 0.189984 0.967106 + outer loop + vertex 1.11959 1.9182 2.57566 + vertex 1.12449 1.91858 2.57473 + vertex 1.1199 1.92265 2.57473 + endloop + endfacet + facet normal 0.141784 0.15913 0.977024 + outer loop + vertex 1.1199 1.92265 2.57473 + vertex 1.12449 1.91858 2.57473 + vertex 1.1248 1.9235 2.57388 + endloop + endfacet + facet normal 0.270483 0.146439 0.951522 + outer loop + vertex 1.12449 1.91858 2.57473 + vertex 1.12877 1.9225 2.57291 + vertex 1.1248 1.9235 2.57388 + endloop + endfacet + facet normal 0.263073 0.110358 0.958443 + outer loop + vertex 1.12877 1.9225 2.57291 + vertex 1.12757 1.9271 2.57271 + vertex 1.1248 1.9235 2.57388 + endloop + endfacet + facet normal 0.168557 0.185957 0.967992 + outer loop + vertex 1.1248 1.9235 2.57388 + vertex 1.12757 1.9271 2.57271 + vertex 1.12306 1.9271 2.57349 + endloop + endfacet + facet normal 0.314733 0.0947445 0.94444 + outer loop + vertex 1.12885 1.91816 2.57332 + vertex 1.12877 1.9225 2.57291 + vertex 1.12449 1.91858 2.57473 + endloop + endfacet + facet normal 0.316778 0.134646 0.938894 + outer loop + vertex 1.12449 1.91858 2.57473 + vertex 1.12783 1.91416 2.57423 + vertex 1.12885 1.91816 2.57332 + endloop + endfacet + facet normal 0.370094 0.178124 0.911758 + outer loop + vertex 1.1243 1.91417 2.57566 + vertex 1.12783 1.91416 2.57423 + vertex 1.12449 1.91858 2.57473 + endloop + endfacet + facet normal 0.193972 0.195978 0.961232 + outer loop + vertex 1.1243 1.91417 2.57566 + vertex 1.12449 1.91858 2.57473 + vertex 1.12141 1.91537 2.576 + endloop + endfacet + facet normal 0.184031 0.169986 0.96811 + outer loop + vertex 1.12141 1.91537 2.576 + vertex 1.12133 1.91083 2.57681 + vertex 1.1243 1.91417 2.57566 + endloop + endfacet + facet normal 0.224361 0.133057 0.96538 + outer loop + vertex 1.12566 1.91145 2.57572 + vertex 1.1243 1.91417 2.57566 + vertex 1.12133 1.91083 2.57681 + endloop + endfacet + facet normal 0.11234 0.173087 0.978479 + outer loop + vertex 1.12141 1.91537 2.576 + vertex 1.11683 1.91465 2.57665 + vertex 1.12133 1.91083 2.57681 + endloop + endfacet + facet normal 0.122494 0.184905 0.975092 + outer loop + vertex 1.11683 1.91465 2.57665 + vertex 1.11638 1.91013 2.57757 + vertex 1.12133 1.91083 2.57681 + endloop + endfacet + facet normal 0.119359 0.203447 0.971783 + outer loop + vertex 1.1177 1.90667 2.57813 + vertex 1.12133 1.91083 2.57681 + vertex 1.11638 1.91013 2.57757 + endloop + endfacet + facet normal 0.0933776 0.194308 0.976486 + outer loop + vertex 1.1177 1.90667 2.57813 + vertex 1.11638 1.91013 2.57757 + vertex 1.11323 1.90694 2.57851 + endloop + endfacet + facet normal 0.0935678 0.198793 0.975565 + outer loop + vertex 1.11474 1.90344 2.57907 + vertex 1.1177 1.90667 2.57813 + vertex 1.11323 1.90694 2.57851 + endloop + endfacet + facet normal 0.0955903 0.199607 0.975202 + outer loop + vertex 1.11474 1.90344 2.57907 + vertex 1.11323 1.90694 2.57851 + vertex 1.10983 1.9027 2.5797 + endloop + endfacet + facet normal 0.0986853 0.1817 0.97839 + outer loop + vertex 1.10983 1.9027 2.5797 + vertex 1.11462 1.89864 2.57998 + vertex 1.11474 1.90344 2.57907 + endloop + endfacet + facet normal 0.114828 0.180986 0.976759 + outer loop + vertex 1.11462 1.89864 2.57998 + vertex 1.11861 1.90263 2.57877 + vertex 1.11474 1.90344 2.57907 + endloop + endfacet + facet normal 0.154595 0.141493 0.977793 + outer loop + vertex 1.11978 1.89892 2.57912 + vertex 1.11861 1.90263 2.57877 + vertex 1.11462 1.89864 2.57998 + endloop + endfacet + facet normal 0.155825 0.124773 0.979873 + outer loop + vertex 1.11462 1.89864 2.57998 + vertex 1.11919 1.89392 2.57985 + vertex 1.11978 1.89892 2.57912 + endloop + endfacet + facet normal 0.311797 0.101501 0.944712 + outer loop + vertex 1.11919 1.89392 2.57985 + vertex 1.12309 1.89725 2.57821 + vertex 1.11978 1.89892 2.57912 + endloop + endfacet + facet normal 0.30525 0.0864684 0.948338 + outer loop + vertex 1.12309 1.89725 2.57821 + vertex 1.12322 1.90227 2.57771 + vertex 1.11978 1.89892 2.57912 + endloop + endfacet + facet normal 0.213857 0.181457 0.959864 + outer loop + vertex 1.11455 1.89404 2.58086 + vertex 1.11919 1.89392 2.57985 + vertex 1.11462 1.89864 2.57998 + endloop + endfacet + facet normal 0.11737 0.185981 0.975518 + outer loop + vertex 1.11455 1.89404 2.58086 + vertex 1.11462 1.89864 2.57998 + vertex 1.11132 1.8954 2.58099 + endloop + endfacet + facet normal 0.114217 0.17828 0.977328 + outer loop + vertex 1.11132 1.8954 2.58099 + vertex 1.11128 1.89069 2.58186 + vertex 1.11455 1.89404 2.58086 + endloop + endfacet + facet normal 0.126729 0.166253 0.977906 + outer loop + vertex 1.11605 1.89104 2.58118 + vertex 1.11455 1.89404 2.58086 + vertex 1.11128 1.89069 2.58186 + endloop + endfacet + facet normal 0.127426 0.15887 0.979042 + outer loop + vertex 1.11605 1.89104 2.58118 + vertex 1.11128 1.89069 2.58186 + vertex 1.11548 1.88658 2.58198 + endloop + endfacet + facet normal 0.249336 0.139479 0.95832 + outer loop + vertex 1.11605 1.89104 2.58118 + vertex 1.11548 1.88658 2.58198 + vertex 1.11883 1.88919 2.58072 + endloop + endfacet + facet normal 0.25945 0.155997 0.953074 + outer loop + vertex 1.11883 1.88919 2.58072 + vertex 1.11919 1.89392 2.57985 + vertex 1.11605 1.89104 2.58118 + endloop + endfacet + facet normal 0.146716 0.178366 0.972965 + outer loop + vertex 1.11128 1.89069 2.58186 + vertex 1.11126 1.88568 2.58278 + vertex 1.11548 1.88658 2.58198 + endloop + endfacet + facet normal 0.144868 0.186034 0.971805 + outer loop + vertex 1.11269 1.88205 2.58326 + vertex 1.11548 1.88658 2.58198 + vertex 1.11126 1.88568 2.58278 + endloop + endfacet + facet normal 0.110033 0.173267 0.978709 + outer loop + vertex 1.11269 1.88205 2.58326 + vertex 1.11126 1.88568 2.58278 + vertex 1.10857 1.88221 2.58369 + endloop + endfacet + facet normal 0.110367 0.190739 0.975417 + outer loop + vertex 1.10993 1.87877 2.58421 + vertex 1.11269 1.88205 2.58326 + vertex 1.10857 1.88221 2.58369 + endloop + endfacet + facet normal 0.0971383 0.185871 0.977761 + outer loop + vertex 1.10993 1.87877 2.58421 + vertex 1.10857 1.88221 2.58369 + vertex 1.1059 1.87818 2.58473 + endloop + endfacet + facet normal 0.0988067 0.175971 0.979424 + outer loop + vertex 1.1059 1.87818 2.58473 + vertex 1.10919 1.87449 2.58506 + vertex 1.10993 1.87877 2.58421 + endloop + endfacet + facet normal 0.151683 0.165864 0.974413 + outer loop + vertex 1.10919 1.87449 2.58506 + vertex 1.11343 1.87761 2.58386 + vertex 1.10993 1.87877 2.58421 + endloop + endfacet + facet normal 0.181087 0.126233 0.975332 + outer loop + vertex 1.11423 1.87259 2.58437 + vertex 1.11343 1.87761 2.58386 + vertex 1.10919 1.87449 2.58506 + endloop + endfacet + facet normal 0.203255 0.190415 0.960432 + outer loop + vertex 1.10919 1.87449 2.58506 + vertex 1.11011 1.86977 2.5858 + vertex 1.11423 1.87259 2.58437 + endloop + endfacet + facet normal 0.215168 0.173324 0.961073 + outer loop + vertex 1.11011 1.86977 2.5858 + vertex 1.11353 1.86829 2.5853 + vertex 1.11423 1.87259 2.58437 + endloop + endfacet + facet normal 0.21457 0.171802 0.96148 + outer loop + vertex 1.11353 1.86829 2.5853 + vertex 1.11011 1.86977 2.5858 + vertex 1.11068 1.86546 2.58644 + endloop + endfacet + facet normal 0.124667 0.162444 0.978811 + outer loop + vertex 1.11068 1.86546 2.58644 + vertex 1.11011 1.86977 2.5858 + vertex 1.10589 1.86654 2.58687 + endloop + endfacet + facet normal 0.128547 0.181211 0.975007 + outer loop + vertex 1.10717 1.86163 2.58762 + vertex 1.11068 1.86546 2.58644 + vertex 1.10589 1.86654 2.58687 + endloop + endfacet + facet normal 0.0922678 0.172615 0.980658 + outer loop + vertex 1.10717 1.86163 2.58762 + vertex 1.10589 1.86654 2.58687 + vertex 1.10256 1.86172 2.58803 + endloop + endfacet + facet normal 0.0923054 0.183657 0.978647 + outer loop + vertex 1.10347 1.85739 2.58876 + vertex 1.10717 1.86163 2.58762 + vertex 1.10256 1.86172 2.58803 + endloop + endfacet + facet normal 0.0829313 0.181891 0.979815 + outer loop + vertex 1.10347 1.85739 2.58876 + vertex 1.10256 1.86172 2.58803 + vertex 1.0987 1.85771 2.5891 + endloop + endfacet + facet normal 0.0828489 0.18032 0.980113 + outer loop + vertex 1.09987 1.85286 2.5899 + vertex 1.10347 1.85739 2.58876 + vertex 1.0987 1.85771 2.5891 + endloop + endfacet + facet normal 0.0914815 0.182218 0.978993 + outer loop + vertex 1.09987 1.85286 2.5899 + vertex 1.0987 1.85771 2.5891 + vertex 1.09401 1.85452 2.59014 + endloop + endfacet + facet normal 0.0886397 0.171897 0.981119 + outer loop + vertex 1.09401 1.85452 2.59014 + vertex 1.09537 1.84991 2.59082 + vertex 1.09987 1.85286 2.5899 + endloop + endfacet + facet normal 0.0863654 0.175242 0.98073 + outer loop + vertex 1.09537 1.84991 2.59082 + vertex 1.09952 1.84852 2.5907 + vertex 1.09987 1.85286 2.5899 + endloop + endfacet + facet normal 0.110506 0.172907 0.978719 + outer loop + vertex 1.09952 1.84852 2.5907 + vertex 1.1045 1.84878 2.5901 + vertex 1.09987 1.85286 2.5899 + endloop + endfacet + facet normal 0.0916169 0.151738 0.984166 + outer loop + vertex 1.09987 1.85286 2.5899 + vertex 1.1045 1.84878 2.5901 + vertex 1.10471 1.85369 2.58932 + endloop + endfacet + facet normal 0.148079 0.148284 0.977796 + outer loop + vertex 1.1045 1.84878 2.5901 + vertex 1.10835 1.85272 2.58891 + vertex 1.10471 1.85369 2.58932 + endloop + endfacet + facet normal 0.148598 0.1504 0.977394 + outer loop + vertex 1.10835 1.85272 2.58891 + vertex 1.10789 1.85716 2.5883 + vertex 1.10471 1.85369 2.58932 + endloop + endfacet + facet normal 0.110781 0.18477 0.976518 + outer loop + vertex 1.10471 1.85369 2.58932 + vertex 1.10789 1.85716 2.5883 + vertex 1.10347 1.85739 2.58876 + endloop + endfacet + facet normal 0.235993 0.156856 0.959012 + outer loop + vertex 1.10835 1.85272 2.58891 + vertex 1.11181 1.85639 2.58746 + vertex 1.10789 1.85716 2.5883 + endloop + endfacet + facet normal 0.230777 0.123698 0.965112 + outer loop + vertex 1.11181 1.85639 2.58746 + vertex 1.11142 1.86104 2.58696 + vertex 1.10789 1.85716 2.5883 + endloop + endfacet + facet normal 0.173668 0.176884 0.968789 + outer loop + vertex 1.10789 1.85716 2.5883 + vertex 1.11142 1.86104 2.58696 + vertex 1.10717 1.86163 2.58762 + endloop + endfacet + facet normal 0.303088 0.0896533 0.948736 + outer loop + vertex 1.11209 1.85176 2.58781 + vertex 1.11181 1.85639 2.58746 + vertex 1.10835 1.85272 2.58891 + endloop + endfacet + facet normal 0.311409 0.130589 0.94126 + outer loop + vertex 1.10923 1.84882 2.58916 + vertex 1.11209 1.85176 2.58781 + vertex 1.10835 1.85272 2.58891 + endloop + endfacet + facet normal 0.388227 0.0463954 0.920395 + outer loop + vertex 1.11237 1.84723 2.58792 + vertex 1.11209 1.85176 2.58781 + vertex 1.10923 1.84882 2.58916 + endloop + endfacet + facet normal 0.399665 0.0741515 0.913657 + outer loop + vertex 1.10896 1.84398 2.58968 + vertex 1.11237 1.84723 2.58792 + vertex 1.10923 1.84882 2.58916 + endloop + endfacet + facet normal 0.191587 0.0925595 0.977101 + outer loop + vertex 1.1045 1.84878 2.5901 + vertex 1.10896 1.84398 2.58968 + vertex 1.10923 1.84882 2.58916 + endloop + endfacet + facet normal 0.260597 0.158883 0.952284 + outer loop + vertex 1.10461 1.84421 2.59083 + vertex 1.10896 1.84398 2.58968 + vertex 1.1045 1.84878 2.5901 + endloop + endfacet + facet normal 0.132232 0.160082 0.978207 + outer loop + vertex 1.10461 1.84421 2.59083 + vertex 1.1045 1.84878 2.5901 + vertex 1.10144 1.84564 2.59102 + endloop + endfacet + facet normal 0.128618 0.151804 0.980007 + outer loop + vertex 1.10144 1.84564 2.59102 + vertex 1.1015 1.84091 2.59175 + vertex 1.10461 1.84421 2.59083 + endloop + endfacet + facet normal 0.143344 0.137943 0.980012 + outer loop + vertex 1.10615 1.84119 2.59103 + vertex 1.10461 1.84421 2.59083 + vertex 1.1015 1.84091 2.59175 + endloop + endfacet + facet normal 0.142971 0.142661 0.979391 + outer loop + vertex 1.10615 1.84119 2.59103 + vertex 1.1015 1.84091 2.59175 + vertex 1.10558 1.83668 2.59177 + endloop + endfacet + facet normal 0.284341 0.120387 0.951135 + outer loop + vertex 1.10615 1.84119 2.59103 + vertex 1.10558 1.83668 2.59177 + vertex 1.10882 1.83932 2.59047 + endloop + endfacet + facet normal 0.303203 0.150489 0.940968 + outer loop + vertex 1.10882 1.83932 2.59047 + vertex 1.10896 1.84398 2.58968 + vertex 1.10615 1.84119 2.59103 + endloop + endfacet + facet normal 0.155967 0.155174 0.975497 + outer loop + vertex 1.1015 1.84091 2.59175 + vertex 1.10134 1.83576 2.59259 + vertex 1.10558 1.83668 2.59177 + endloop + endfacet + facet normal 0.153219 0.166541 0.974057 + outer loop + vertex 1.10248 1.83183 2.59309 + vertex 1.10558 1.83668 2.59177 + vertex 1.10134 1.83576 2.59259 + endloop + endfacet + facet normal 0.100855 0.152492 0.983145 + outer loop + vertex 1.10248 1.83183 2.59309 + vertex 1.10134 1.83576 2.59259 + vertex 1.09816 1.83208 2.59349 + endloop + endfacet + facet normal 0.101624 0.170996 0.980017 + outer loop + vertex 1.09873 1.82775 2.59419 + vertex 1.10248 1.83183 2.59309 + vertex 1.09816 1.83208 2.59349 + endloop + endfacet + facet normal 0.0733415 0.167788 0.983091 + outer loop + vertex 1.09873 1.82775 2.59419 + vertex 1.09816 1.83208 2.59349 + vertex 1.09477 1.82852 2.59435 + endloop + endfacet + facet normal 0.0732899 0.167512 0.983142 + outer loop + vertex 1.09445 1.82375 2.59519 + vertex 1.09873 1.82775 2.59419 + vertex 1.09477 1.82852 2.59435 + endloop + endfacet + facet normal 0.0726553 0.167561 0.983181 + outer loop + vertex 1.08969 1.82765 2.59487 + vertex 1.09445 1.82375 2.59519 + vertex 1.09477 1.82852 2.59435 + endloop + endfacet + facet normal 0.0729411 0.16603 0.983419 + outer loop + vertex 1.09477 1.82852 2.59435 + vertex 1.09356 1.83231 2.5938 + vertex 1.08969 1.82765 2.59487 + endloop + endfacet + facet normal 0.083581 0.157322 0.984004 + outer loop + vertex 1.08969 1.82765 2.59487 + vertex 1.09356 1.83231 2.5938 + vertex 1.08861 1.83272 2.59416 + endloop + endfacet + facet normal 0.0854878 0.157698 0.98378 + outer loop + vertex 1.08969 1.82765 2.59487 + vertex 1.08861 1.83272 2.59416 + vertex 1.08373 1.82935 2.59512 + endloop + endfacet + facet normal 0.0824015 0.146533 0.985768 + outer loop + vertex 1.08373 1.82935 2.59512 + vertex 1.08514 1.82469 2.59569 + vertex 1.08969 1.82765 2.59487 + endloop + endfacet + facet normal 0.0756873 0.156581 0.984761 + outer loop + vertex 1.08514 1.82469 2.59569 + vertex 1.08932 1.82332 2.59559 + vertex 1.08969 1.82765 2.59487 + endloop + endfacet + facet normal 0.072985 0.148259 0.986252 + outer loop + vertex 1.08932 1.82332 2.59559 + vertex 1.08514 1.82469 2.59569 + vertex 1.08687 1.81997 2.59628 + endloop + endfacet + facet normal 0.0629678 0.155493 0.985828 + outer loop + vertex 1.09132 1.82058 2.5959 + vertex 1.08932 1.82332 2.59559 + vertex 1.08687 1.81997 2.59628 + endloop + endfacet + facet normal 0.0642482 0.146906 0.987062 + outer loop + vertex 1.09132 1.82058 2.5959 + vertex 1.08687 1.81997 2.59628 + vertex 1.09164 1.81608 2.59654 + endloop + endfacet + facet normal 0.0549395 0.146349 0.987706 + outer loop + vertex 1.09132 1.82058 2.5959 + vertex 1.09164 1.81608 2.59654 + vertex 1.09457 1.81942 2.59589 + endloop + endfacet + facet normal 0.0600977 0.160834 0.98515 + outer loop + vertex 1.09457 1.81942 2.59589 + vertex 1.09445 1.82375 2.59519 + vertex 1.09132 1.82058 2.5959 + endloop + endfacet + facet normal 0.0958301 0.161342 0.982235 + outer loop + vertex 1.09457 1.81942 2.59589 + vertex 1.09899 1.8199 2.59538 + vertex 1.09445 1.82375 2.59519 + endloop + endfacet + facet normal 0.0816368 0.144817 0.986085 + outer loop + vertex 1.09445 1.82375 2.59519 + vertex 1.09899 1.8199 2.59538 + vertex 1.09964 1.82407 2.59471 + endloop + endfacet + facet normal 0.179675 0.127844 0.975384 + outer loop + vertex 1.09899 1.8199 2.59538 + vertex 1.10338 1.82274 2.5942 + vertex 1.09964 1.82407 2.59471 + endloop + endfacet + facet normal 0.177416 0.120997 0.976669 + outer loop + vertex 1.10338 1.82274 2.5942 + vertex 1.10307 1.82725 2.59369 + vertex 1.09964 1.82407 2.59471 + endloop + endfacet + facet normal 0.130586 0.171398 0.976509 + outer loop + vertex 1.09964 1.82407 2.59471 + vertex 1.10307 1.82725 2.59369 + vertex 1.09873 1.82775 2.59419 + endloop + endfacet + facet normal 0.208927 0.0824068 0.974453 + outer loop + vertex 1.10418 1.81784 2.59444 + vertex 1.10338 1.82274 2.5942 + vertex 1.09899 1.8199 2.59538 + endloop + endfacet + facet normal 0.242711 0.177187 0.95378 + outer loop + vertex 1.09899 1.8199 2.59538 + vertex 1.10033 1.81533 2.59589 + vertex 1.10418 1.81784 2.59444 + endloop + endfacet + facet normal 0.258391 0.153214 0.953813 + outer loop + vertex 1.10033 1.81533 2.59589 + vertex 1.10369 1.81371 2.59523 + vertex 1.10418 1.81784 2.59444 + endloop + endfacet + facet normal 0.252819 0.140226 0.957298 + outer loop + vertex 1.10369 1.81371 2.59523 + vertex 1.10033 1.81533 2.59589 + vertex 1.10104 1.81097 2.59634 + endloop + endfacet + facet normal 0.125573 0.122256 0.984523 + outer loop + vertex 1.10104 1.81097 2.59634 + vertex 1.10033 1.81533 2.59589 + vertex 1.09623 1.8122 2.5968 + endloop + endfacet + facet normal 0.131118 0.145417 0.980644 + outer loop + vertex 1.09745 1.80691 2.59742 + vertex 1.10104 1.81097 2.59634 + vertex 1.09623 1.8122 2.5968 + endloop + endfacet + facet normal 0.0748492 0.133363 0.988237 + outer loop + vertex 1.09745 1.80691 2.59742 + vertex 1.09623 1.8122 2.5968 + vertex 1.09275 1.80697 2.59777 + endloop + endfacet + facet normal 0.0748893 0.147072 0.986287 + outer loop + vertex 1.09317 1.8021 2.59846 + vertex 1.09745 1.80691 2.59742 + vertex 1.09275 1.80697 2.59777 + endloop + endfacet + facet normal 0.0535353 0.145477 0.987912 + outer loop + vertex 1.09317 1.8021 2.59846 + vertex 1.09275 1.80697 2.59777 + vertex 1.08845 1.80222 2.5987 + endloop + endfacet + facet normal 0.0536229 0.150223 0.987197 + outer loop + vertex 1.08868 1.79766 2.59938 + vertex 1.09317 1.8021 2.59846 + vertex 1.08845 1.80222 2.5987 + endloop + endfacet + facet normal 0.0558588 0.150316 0.987059 + outer loop + vertex 1.08868 1.79766 2.59938 + vertex 1.08845 1.80222 2.5987 + vertex 1.08466 1.79841 2.59949 + endloop + endfacet + facet normal 0.0552284 0.146824 0.98762 + outer loop + vertex 1.08427 1.79366 2.60022 + vertex 1.08868 1.79766 2.59938 + vertex 1.08466 1.79841 2.59949 + endloop + endfacet + facet normal 0.048475 0.154113 0.986863 + outer loop + vertex 1.0895 1.79397 2.59992 + vertex 1.08868 1.79766 2.59938 + vertex 1.08427 1.79366 2.60022 + endloop + endfacet + facet normal 0.049503 0.138629 0.989106 + outer loop + vertex 1.08427 1.79366 2.60022 + vertex 1.08894 1.78983 2.60052 + vertex 1.0895 1.79397 2.59992 + endloop + endfacet + facet normal 0.0646448 0.136506 0.988528 + outer loop + vertex 1.08894 1.78983 2.60052 + vertex 1.09362 1.79284 2.5998 + vertex 1.0895 1.79397 2.59992 + endloop + endfacet + facet normal 0.0659061 0.141213 0.987783 + outer loop + vertex 1.09362 1.79284 2.5998 + vertex 1.09334 1.79736 2.59918 + vertex 1.0895 1.79397 2.59992 + endloop + endfacet + facet normal 0.119481 0.143827 0.982364 + outer loop + vertex 1.09362 1.79284 2.5998 + vertex 1.0978 1.79695 2.59869 + vertex 1.09334 1.79736 2.59918 + endloop + endfacet + facet normal 0.118198 0.126848 0.984855 + outer loop + vertex 1.0978 1.79695 2.59869 + vertex 1.09775 1.80187 2.59806 + vertex 1.09334 1.79736 2.59918 + endloop + endfacet + facet normal 0.0925823 0.15169 0.984083 + outer loop + vertex 1.09334 1.79736 2.59918 + vertex 1.09775 1.80187 2.59806 + vertex 1.09317 1.8021 2.59846 + endloop + endfacet + facet normal 0.151865 0.110807 0.98217 + outer loop + vertex 1.0982 1.7923 2.59916 + vertex 1.0978 1.79695 2.59869 + vertex 1.09362 1.79284 2.5998 + endloop + endfacet + facet normal 0.153598 0.128216 0.97978 + outer loop + vertex 1.09487 1.78799 2.60024 + vertex 1.0982 1.7923 2.59916 + vertex 1.09362 1.79284 2.5998 + endloop + endfacet + facet normal 0.221902 0.0735121 0.972294 + outer loop + vertex 1.09926 1.78856 2.5992 + vertex 1.0982 1.7923 2.59916 + vertex 1.09487 1.78799 2.60024 + endloop + endfacet + facet normal 0.222358 0.0702416 0.972432 + outer loop + vertex 1.09487 1.78799 2.60024 + vertex 1.09897 1.78395 2.5996 + vertex 1.09926 1.78856 2.5992 + endloop + endfacet + facet normal 0.281167 0.133249 0.950363 + outer loop + vertex 1.09478 1.78389 2.60084 + vertex 1.09897 1.78395 2.5996 + vertex 1.09487 1.78799 2.60024 + endloop + endfacet + facet normal 0.100136 0.142217 0.984757 + outer loop + vertex 1.09071 1.78529 2.60105 + vertex 1.09478 1.78389 2.60084 + vertex 1.09487 1.78799 2.60024 + endloop + endfacet + facet normal 0.0974434 0.134149 0.986159 + outer loop + vertex 1.09478 1.78389 2.60084 + vertex 1.09071 1.78529 2.60105 + vertex 1.09231 1.78062 2.60153 + endloop + endfacet + facet normal 0.135542 0.105078 0.985184 + outer loop + vertex 1.09642 1.78119 2.6009 + vertex 1.09478 1.78389 2.60084 + vertex 1.09231 1.78062 2.60153 + endloop + endfacet + facet normal 0.136235 0.100466 0.985569 + outer loop + vertex 1.09642 1.78119 2.6009 + vertex 1.09231 1.78062 2.60153 + vertex 1.09593 1.777 2.6014 + endloop + endfacet + facet normal 0.313723 0.0748449 0.94656 + outer loop + vertex 1.09642 1.78119 2.6009 + vertex 1.09593 1.777 2.6014 + vertex 1.09883 1.7796 2.60023 + endloop + endfacet + facet normal 0.342732 0.125361 0.931031 + outer loop + vertex 1.09883 1.7796 2.60023 + vertex 1.09897 1.78395 2.5996 + vertex 1.09642 1.78119 2.6009 + endloop + endfacet + facet normal 0.146592 0.110918 0.982959 + outer loop + vertex 1.09231 1.78062 2.60153 + vertex 1.09183 1.77605 2.60212 + vertex 1.09593 1.777 2.6014 + endloop + endfacet + facet normal 0.146849 0.109867 0.983038 + outer loop + vertex 1.09278 1.77213 2.60242 + vertex 1.09593 1.777 2.6014 + vertex 1.09183 1.77605 2.60212 + endloop + endfacet + facet normal 0.0844634 0.0954122 0.991848 + outer loop + vertex 1.09278 1.77213 2.60242 + vertex 1.09183 1.77605 2.60212 + vertex 1.08825 1.77207 2.60281 + endloop + endfacet + facet normal 0.0842946 0.103513 0.99105 + outer loop + vertex 1.08839 1.76714 2.60331 + vertex 1.09278 1.77213 2.60242 + vertex 1.08825 1.77207 2.60281 + endloop + endfacet + facet normal 0.0637631 0.103087 0.992626 + outer loop + vertex 1.08839 1.76714 2.60331 + vertex 1.08825 1.77207 2.60281 + vertex 1.08341 1.76706 2.60364 + endloop + endfacet + facet normal 0.0639015 0.0971826 0.993213 + outer loop + vertex 1.08339 1.76222 2.60411 + vertex 1.08839 1.76714 2.60331 + vertex 1.08341 1.76706 2.60364 + endloop + endfacet + facet normal 0.0745548 0.0970621 0.992482 + outer loop + vertex 1.08339 1.76222 2.60411 + vertex 1.08341 1.76706 2.60364 + vertex 1.07854 1.76253 2.60445 + endloop + endfacet + facet normal 0.0738822 0.0852553 0.993616 + outer loop + vertex 1.07915 1.75862 2.60474 + vertex 1.08339 1.76222 2.60411 + vertex 1.07854 1.76253 2.60445 + endloop + endfacet + facet normal 0.0946618 0.0883631 0.99158 + outer loop + vertex 1.07915 1.75862 2.60474 + vertex 1.07854 1.76253 2.60445 + vertex 1.07393 1.75873 2.60523 + endloop + endfacet + facet normal 0.0945363 0.077619 0.992491 + outer loop + vertex 1.07393 1.75873 2.60523 + vertex 1.07812 1.75401 2.60519 + vertex 1.07915 1.75862 2.60474 + endloop + endfacet + facet normal 0.0691432 0.0834564 0.99411 + outer loop + vertex 1.07812 1.75401 2.60519 + vertex 1.08321 1.75745 2.60455 + vertex 1.07915 1.75862 2.60474 + endloop + endfacet + facet normal 0.0687287 0.0840648 0.994087 + outer loop + vertex 1.08349 1.75264 2.60494 + vertex 1.08321 1.75745 2.60455 + vertex 1.07812 1.75401 2.60519 + endloop + endfacet + facet normal 0.0734368 0.0843064 0.99373 + outer loop + vertex 1.08349 1.75264 2.60494 + vertex 1.08809 1.75703 2.60423 + vertex 1.08321 1.75745 2.60455 + endloop + endfacet + facet normal 0.0734225 0.084127 0.993746 + outer loop + vertex 1.08809 1.75703 2.60423 + vertex 1.08824 1.76207 2.60379 + vertex 1.08321 1.75745 2.60455 + endloop + endfacet + facet normal 0.0688912 0.0890514 0.993642 + outer loop + vertex 1.08321 1.75745 2.60455 + vertex 1.08824 1.76207 2.60379 + vertex 1.08339 1.76222 2.60411 + endloop + endfacet + facet normal 0.125948 0.0821296 0.988631 + outer loop + vertex 1.08809 1.75703 2.60423 + vertex 1.09289 1.76197 2.60321 + vertex 1.08824 1.76207 2.60379 + endloop + endfacet + facet normal 0.125826 0.0719517 0.98944 + outer loop + vertex 1.09289 1.76197 2.60321 + vertex 1.09303 1.76713 2.60281 + vertex 1.08824 1.76207 2.60379 + endloop + endfacet + facet normal 0.106141 0.0907093 0.990205 + outer loop + vertex 1.08824 1.76207 2.60379 + vertex 1.09303 1.76713 2.60281 + vertex 1.08839 1.76714 2.60331 + endloop + endfacet + facet normal 0.146622 0.0617523 0.987263 + outer loop + vertex 1.09272 1.75688 2.60355 + vertex 1.09289 1.76197 2.60321 + vertex 1.08809 1.75703 2.60423 + endloop + endfacet + facet normal 0.147019 0.0789054 0.985981 + outer loop + vertex 1.08825 1.75224 2.60459 + vertex 1.09272 1.75688 2.60355 + vertex 1.08809 1.75703 2.60423 + endloop + endfacet + facet normal 0.176007 0.0503448 0.983101 + outer loop + vertex 1.0927 1.75195 2.6038 + vertex 1.09272 1.75688 2.60355 + vertex 1.08825 1.75224 2.60459 + endloop + endfacet + facet normal 0.177222 0.0735562 0.981418 + outer loop + vertex 1.08861 1.74776 2.60486 + vertex 1.0927 1.75195 2.6038 + vertex 1.08825 1.75224 2.60459 + endloop + endfacet + facet normal 0.0977664 0.0678628 0.992893 + outer loop + vertex 1.08861 1.74776 2.60486 + vertex 1.08825 1.75224 2.60459 + vertex 1.08471 1.74866 2.60518 + endloop + endfacet + facet normal 0.0979163 0.0685348 0.992832 + outer loop + vertex 1.08454 1.74398 2.60552 + vertex 1.08861 1.74776 2.60486 + vertex 1.08471 1.74866 2.60518 + endloop + endfacet + facet normal 0.058793 0.0701592 0.995802 + outer loop + vertex 1.08015 1.74834 2.60547 + vertex 1.08454 1.74398 2.60552 + vertex 1.08471 1.74866 2.60518 + endloop + endfacet + facet normal 0.0597017 0.0710708 0.995683 + outer loop + vertex 1.07986 1.74416 2.60579 + vertex 1.08454 1.74398 2.60552 + vertex 1.08015 1.74834 2.60547 + endloop + endfacet + facet normal 0.0662595 0.0705926 0.995302 + outer loop + vertex 1.07986 1.74416 2.60579 + vertex 1.08015 1.74834 2.60547 + vertex 1.07694 1.74609 2.60585 + endloop + endfacet + facet normal 0.0734148 0.0814795 0.993967 + outer loop + vertex 1.07694 1.74609 2.60585 + vertex 1.07697 1.74126 2.60624 + vertex 1.07986 1.74416 2.60579 + endloop + endfacet + facet normal 0.0675999 0.0872803 0.993888 + outer loop + vertex 1.08151 1.74112 2.60594 + vertex 1.07986 1.74416 2.60579 + vertex 1.07697 1.74126 2.60624 + endloop + endfacet + facet normal 0.0675362 0.0847328 0.994112 + outer loop + vertex 1.08151 1.74112 2.60594 + vertex 1.07697 1.74126 2.60624 + vertex 1.08178 1.73647 2.60632 + endloop + endfacet + facet normal 0.0596681 0.0843134 0.994651 + outer loop + vertex 1.08151 1.74112 2.60594 + vertex 1.08178 1.73647 2.60632 + vertex 1.08464 1.73956 2.60589 + endloop + endfacet + facet normal 0.0594843 0.083943 0.994694 + outer loop + vertex 1.08464 1.73956 2.60589 + vertex 1.08454 1.74398 2.60552 + vertex 1.08151 1.74112 2.60594 + endloop + endfacet + facet normal 0.117044 0.0847999 0.9895 + outer loop + vertex 1.08464 1.73956 2.60589 + vertex 1.08894 1.73988 2.60535 + vertex 1.08454 1.74398 2.60552 + endloop + endfacet + facet normal 0.106371 0.0732475 0.991625 + outer loop + vertex 1.08454 1.74398 2.60552 + vertex 1.08894 1.73988 2.60535 + vertex 1.08952 1.74407 2.60498 + endloop + endfacet + facet normal 0.24483 0.0519927 0.968171 + outer loop + vertex 1.08894 1.73988 2.60535 + vertex 1.09318 1.74286 2.60412 + vertex 1.08952 1.74407 2.60498 + endloop + endfacet + facet normal 0.241998 0.0425927 0.969341 + outer loop + vertex 1.09318 1.74286 2.60412 + vertex 1.09291 1.74731 2.60399 + vertex 1.08952 1.74407 2.60498 + endloop + endfacet + facet normal 0.205371 0.0827092 0.975183 + outer loop + vertex 1.08952 1.74407 2.60498 + vertex 1.09291 1.74731 2.60399 + vertex 1.08861 1.74776 2.60486 + endloop + endfacet + facet normal 0.255921 0.0353904 0.96605 + outer loop + vertex 1.09396 1.73804 2.60409 + vertex 1.09318 1.74286 2.60412 + vertex 1.08894 1.73988 2.60535 + endloop + endfacet + facet normal 0.287381 0.133276 0.948499 + outer loop + vertex 1.08894 1.73988 2.60535 + vertex 1.09027 1.73528 2.60559 + vertex 1.09396 1.73804 2.60409 + endloop + endfacet + facet normal 0.296347 0.120661 0.947428 + outer loop + vertex 1.09027 1.73528 2.60559 + vertex 1.09352 1.73378 2.60477 + vertex 1.09396 1.73804 2.60409 + endloop + endfacet + facet normal 0.290365 0.105669 0.951064 + outer loop + vertex 1.09352 1.73378 2.60477 + vertex 1.09027 1.73528 2.60559 + vertex 1.09102 1.73106 2.60583 + endloop + endfacet + facet normal 0.138983 0.0806172 0.987008 + outer loop + vertex 1.09102 1.73106 2.60583 + vertex 1.09027 1.73528 2.60559 + vertex 1.08636 1.73234 2.60639 + endloop + endfacet + facet normal 0.144413 0.101578 0.98429 + outer loop + vertex 1.08766 1.72721 2.60672 + vertex 1.09102 1.73106 2.60583 + vertex 1.08636 1.73234 2.60639 + endloop + endfacet + facet normal 0.0758603 0.0847668 0.993509 + outer loop + vertex 1.08766 1.72721 2.60672 + vertex 1.08636 1.73234 2.60639 + vertex 1.08299 1.72723 2.60708 + endloop + endfacet + facet normal 0.0758322 0.0988042 0.992213 + outer loop + vertex 1.08338 1.72228 2.60754 + vertex 1.08766 1.72721 2.60672 + vertex 1.08299 1.72723 2.60708 + endloop + endfacet + facet normal 0.0945137 0.0825674 0.992094 + outer loop + vertex 1.08802 1.72231 2.6071 + vertex 1.08766 1.72721 2.60672 + vertex 1.08338 1.72228 2.60754 + endloop + endfacet + facet normal 0.20024 0.0889622 0.9757 + outer loop + vertex 1.08802 1.72231 2.6071 + vertex 1.09176 1.72662 2.60594 + vertex 1.08766 1.72721 2.60672 + endloop + endfacet + facet normal 0.0584821 0.0962096 0.993642 + outer loop + vertex 1.08299 1.72723 2.60708 + vertex 1.08636 1.73234 2.60639 + vertex 1.0818 1.73124 2.60676 + endloop + endfacet + facet normal 0.0581116 0.0961013 0.993674 + outer loop + vertex 1.08299 1.72723 2.60708 + vertex 1.0818 1.73124 2.60676 + vertex 1.07821 1.72707 2.60737 + endloop + endfacet + facet normal 0.0579541 0.10011 0.993287 + outer loop + vertex 1.07837 1.72211 2.60786 + vertex 1.08299 1.72723 2.60708 + vertex 1.07821 1.72707 2.60737 + endloop + endfacet + facet normal 0.0778533 0.100637 0.991872 + outer loop + vertex 1.07837 1.72211 2.60786 + vertex 1.07821 1.72707 2.60737 + vertex 1.07329 1.72206 2.60827 + endloop + endfacet + facet normal 0.0778211 0.102351 0.9917 + outer loop + vertex 1.07331 1.71719 2.60877 + vertex 1.07837 1.72211 2.60786 + vertex 1.07329 1.72206 2.60827 + endloop + endfacet + facet normal 0.0985694 0.102222 0.989866 + outer loop + vertex 1.07331 1.71719 2.60877 + vertex 1.07329 1.72206 2.60827 + vertex 1.06844 1.71755 2.60922 + endloop + endfacet + facet normal 0.0987461 0.104981 0.98956 + outer loop + vertex 1.06926 1.71357 2.60956 + vertex 1.07331 1.71719 2.60877 + vertex 1.06844 1.71755 2.60922 + endloop + endfacet + facet normal 0.113348 0.107839 0.987686 + outer loop + vertex 1.06926 1.71357 2.60956 + vertex 1.06844 1.71755 2.60922 + vertex 1.06405 1.71371 2.61014 + endloop + endfacet + facet normal 0.113467 0.116491 0.986689 + outer loop + vertex 1.06405 1.71371 2.61014 + vertex 1.06903 1.70873 2.61016 + vertex 1.06926 1.71357 2.60956 + endloop + endfacet + facet normal 0.0971011 0.11749 0.988316 + outer loop + vertex 1.06903 1.70873 2.61016 + vertex 1.07342 1.71252 2.60927 + vertex 1.06926 1.71357 2.60956 + endloop + endfacet + facet normal 0.096067 0.118677 0.988275 + outer loop + vertex 1.07431 1.70858 2.60966 + vertex 1.07342 1.71252 2.60927 + vertex 1.06903 1.70873 2.61016 + endloop + endfacet + facet normal 0.0960972 0.120615 0.988037 + outer loop + vertex 1.06903 1.70873 2.61016 + vertex 1.07416 1.70378 2.61026 + vertex 1.07431 1.70858 2.60966 + endloop + endfacet + facet normal 0.0735116 0.121589 0.989855 + outer loop + vertex 1.07416 1.70378 2.61026 + vertex 1.07851 1.70757 2.60947 + vertex 1.07431 1.70858 2.60966 + endloop + endfacet + facet normal 0.0724309 0.117014 0.990485 + outer loop + vertex 1.07851 1.70757 2.60947 + vertex 1.07831 1.7122 2.60894 + vertex 1.07431 1.70858 2.60966 + endloop + endfacet + facet normal 0.0732923 0.117044 0.990419 + outer loop + vertex 1.07851 1.70757 2.60947 + vertex 1.08317 1.71211 2.60859 + vertex 1.07831 1.7122 2.60894 + endloop + endfacet + facet normal 0.0731497 0.102603 0.992029 + outer loop + vertex 1.08317 1.71211 2.60859 + vertex 1.08331 1.71717 2.60806 + vertex 1.07831 1.7122 2.60894 + endloop + endfacet + facet normal 0.110882 0.101169 0.988671 + outer loop + vertex 1.08317 1.71211 2.60859 + vertex 1.0879 1.71728 2.60753 + vertex 1.08331 1.71717 2.60806 + endloop + endfacet + facet normal 0.111482 0.0827558 0.990315 + outer loop + vertex 1.0879 1.71728 2.60753 + vertex 1.08802 1.72231 2.6071 + vertex 1.08331 1.71717 2.60806 + endloop + endfacet + facet normal 0.228165 0.0783681 0.970463 + outer loop + vertex 1.0879 1.71728 2.60753 + vertex 1.09185 1.72191 2.60623 + vertex 1.08802 1.72231 2.6071 + endloop + endfacet + facet normal 0.133247 0.0805088 0.987807 + outer loop + vertex 1.0877 1.71219 2.60797 + vertex 1.0879 1.71728 2.60753 + vertex 1.08317 1.71211 2.60859 + endloop + endfacet + facet normal 0.132414 0.108932 0.985191 + outer loop + vertex 1.08326 1.70728 2.60911 + vertex 1.0877 1.71219 2.60797 + vertex 1.08317 1.71211 2.60859 + endloop + endfacet + facet normal 0.161111 0.0825238 0.98348 + outer loop + vertex 1.08764 1.70715 2.60841 + vertex 1.0877 1.71219 2.60797 + vertex 1.08326 1.70728 2.60911 + endloop + endfacet + facet normal 0.161519 0.114263 0.980232 + outer loop + vertex 1.08359 1.70271 2.60959 + vertex 1.08764 1.70715 2.60841 + vertex 1.08326 1.70728 2.60911 + endloop + endfacet + facet normal 0.0946477 0.110441 0.989366 + outer loop + vertex 1.08359 1.70271 2.60959 + vertex 1.08326 1.70728 2.60911 + vertex 1.07952 1.70369 2.60987 + endloop + endfacet + facet normal 0.0945863 0.110175 0.989401 + outer loop + vertex 1.07947 1.69892 2.61041 + vertex 1.08359 1.70271 2.60959 + vertex 1.07952 1.70369 2.60987 + endloop + endfacet + facet normal 0.0739102 0.110578 0.991115 + outer loop + vertex 1.07416 1.70378 2.61026 + vertex 1.07947 1.69892 2.61041 + vertex 1.07952 1.70369 2.60987 + endloop + endfacet + facet normal 0.075607 0.112424 0.99078 + outer loop + vertex 1.07444 1.6993 2.61075 + vertex 1.07947 1.69892 2.61041 + vertex 1.07416 1.70378 2.61026 + endloop + endfacet + facet normal 0.0831269 0.112828 0.990131 + outer loop + vertex 1.07444 1.6993 2.61075 + vertex 1.07416 1.70378 2.61026 + vertex 1.07116 1.70112 2.61082 + endloop + endfacet + facet normal 0.0837036 0.113872 0.989963 + outer loop + vertex 1.07116 1.70112 2.61082 + vertex 1.07167 1.69641 2.61131 + vertex 1.07444 1.6993 2.61075 + endloop + endfacet + facet normal 0.0789522 0.118402 0.989822 + outer loop + vertex 1.07645 1.69619 2.61096 + vertex 1.07444 1.6993 2.61075 + vertex 1.07167 1.69641 2.61131 + endloop + endfacet + facet normal 0.0786338 0.109785 0.99084 + outer loop + vertex 1.07645 1.69619 2.61096 + vertex 1.07167 1.69641 2.61131 + vertex 1.07693 1.69145 2.61145 + endloop + endfacet + facet normal 0.0765158 0.109589 0.991028 + outer loop + vertex 1.07645 1.69619 2.61096 + vertex 1.07693 1.69145 2.61145 + vertex 1.07988 1.69441 2.61089 + endloop + endfacet + facet normal 0.0785444 0.113503 0.990428 + outer loop + vertex 1.07988 1.69441 2.61089 + vertex 1.07947 1.69892 2.61041 + vertex 1.07645 1.69619 2.61096 + endloop + endfacet + facet normal 0.138299 0.118074 0.983327 + outer loop + vertex 1.07988 1.69441 2.61089 + vertex 1.08469 1.69404 2.61026 + vertex 1.07947 1.69892 2.61041 + endloop + endfacet + facet normal 0.107356 0.084752 0.990602 + outer loop + vertex 1.07947 1.69892 2.61041 + vertex 1.08469 1.69404 2.61026 + vertex 1.08466 1.69889 2.60985 + endloop + endfacet + facet normal 0.24083 0.0833965 0.966978 + outer loop + vertex 1.08469 1.69404 2.61026 + vertex 1.08825 1.69788 2.60904 + vertex 1.08466 1.69889 2.60985 + endloop + endfacet + facet normal 0.239063 0.0763671 0.967996 + outer loop + vertex 1.08825 1.69788 2.60904 + vertex 1.08784 1.70239 2.60879 + vertex 1.08466 1.69889 2.60985 + endloop + endfacet + facet normal 0.279017 0.0454612 0.959209 + outer loop + vertex 1.08917 1.69395 2.60896 + vertex 1.08825 1.69788 2.60904 + vertex 1.08469 1.69404 2.61026 + endloop + endfacet + facet normal 0.279115 0.0680569 0.957843 + outer loop + vertex 1.08469 1.69404 2.61026 + vertex 1.08903 1.68865 2.60938 + vertex 1.08917 1.69395 2.60896 + endloop + endfacet + facet normal 0.356218 0.13563 0.924507 + outer loop + vertex 1.08505 1.68951 2.61079 + vertex 1.08903 1.68865 2.60938 + vertex 1.08469 1.69404 2.61026 + endloop + endfacet + facet normal 0.157972 0.1263 0.979333 + outer loop + vertex 1.08505 1.68951 2.61079 + vertex 1.08469 1.69404 2.61026 + vertex 1.08188 1.69132 2.61106 + endloop + endfacet + facet normal 0.14697 0.106415 0.9834 + outer loop + vertex 1.08188 1.69132 2.61106 + vertex 1.08203 1.68664 2.61155 + vertex 1.08505 1.68951 2.61079 + endloop + endfacet + facet normal 0.147882 0.105447 0.983368 + outer loop + vertex 1.0864 1.68663 2.61089 + vertex 1.08505 1.68951 2.61079 + vertex 1.08203 1.68664 2.61155 + endloop + endfacet + facet normal 0.148009 0.0950068 0.984412 + outer loop + vertex 1.0864 1.68663 2.61089 + vertex 1.08203 1.68664 2.61155 + vertex 1.08581 1.68259 2.61137 + endloop + endfacet + facet normal 0.263247 0.075338 0.961782 + outer loop + vertex 1.0864 1.68663 2.61089 + vertex 1.08581 1.68259 2.61137 + vertex 1.08809 1.68515 2.61055 + endloop + endfacet + facet normal 0.365487 0.204421 0.908092 + outer loop + vertex 1.08809 1.68515 2.61055 + vertex 1.08903 1.68865 2.60938 + vertex 1.0864 1.68663 2.61089 + endloop + endfacet + facet normal 0.158739 0.105147 0.981706 + outer loop + vertex 1.08203 1.68664 2.61155 + vertex 1.08184 1.68137 2.61214 + vertex 1.08581 1.68259 2.61137 + endloop + endfacet + facet normal 0.159234 0.103589 0.981791 + outer loop + vertex 1.08274 1.67732 2.61242 + vertex 1.08581 1.68259 2.61137 + vertex 1.08184 1.68137 2.61214 + endloop + endfacet + facet normal 0.101302 0.0914212 0.990646 + outer loop + vertex 1.08274 1.67732 2.61242 + vertex 1.08184 1.68137 2.61214 + vertex 1.07824 1.67713 2.6129 + endloop + endfacet + facet normal 0.100379 0.109373 0.988919 + outer loop + vertex 1.07833 1.67219 2.61344 + vertex 1.08274 1.67732 2.61242 + vertex 1.07824 1.67713 2.6129 + endloop + endfacet + facet normal 0.0731612 0.109171 0.991327 + outer loop + vertex 1.07833 1.67219 2.61344 + vertex 1.07824 1.67713 2.6129 + vertex 1.07332 1.67214 2.61381 + endloop + endfacet + facet normal 0.0730578 0.114666 0.990714 + outer loop + vertex 1.07353 1.6673 2.61436 + vertex 1.07833 1.67219 2.61344 + vertex 1.07332 1.67214 2.61381 + endloop + endfacet + facet normal 0.0702811 0.114568 0.990926 + outer loop + vertex 1.07353 1.6673 2.61436 + vertex 1.07332 1.67214 2.61381 + vertex 1.06844 1.66773 2.61467 + endloop + endfacet + facet normal 0.0698769 0.109336 0.991546 + outer loop + vertex 1.06944 1.66264 2.61516 + vertex 1.07353 1.6673 2.61436 + vertex 1.06844 1.66773 2.61467 + endloop + endfacet + facet normal 0.0797443 0.111183 0.990595 + outer loop + vertex 1.06944 1.66264 2.61516 + vertex 1.06844 1.66773 2.61467 + vertex 1.06362 1.66482 2.61539 + endloop + endfacet + facet normal 0.074379 0.0966522 0.992535 + outer loop + vertex 1.06362 1.66482 2.61539 + vertex 1.06513 1.6601 2.61573 + vertex 1.06944 1.66264 2.61516 + endloop + endfacet + facet normal 0.0716994 0.101138 0.992285 + outer loop + vertex 1.06513 1.6601 2.61573 + vertex 1.06907 1.65837 2.61562 + vertex 1.06944 1.66264 2.61516 + endloop + endfacet + facet normal 0.0627085 0.101972 0.992809 + outer loop + vertex 1.06907 1.65837 2.61562 + vertex 1.07415 1.65843 2.6153 + vertex 1.06944 1.66264 2.61516 + endloop + endfacet + facet normal 0.0642137 0.103648 0.992539 + outer loop + vertex 1.06944 1.66264 2.61516 + vertex 1.07415 1.65843 2.6153 + vertex 1.07453 1.66339 2.61475 + endloop + endfacet + facet normal 0.0847604 0.101914 0.991176 + outer loop + vertex 1.07415 1.65843 2.6153 + vertex 1.07853 1.66269 2.61448 + vertex 1.07453 1.66339 2.61475 + endloop + endfacet + facet normal 0.0860776 0.109745 0.990226 + outer loop + vertex 1.07853 1.66269 2.61448 + vertex 1.0784 1.66734 2.61398 + vertex 1.07453 1.66339 2.61475 + endloop + endfacet + facet normal 0.0761907 0.119362 0.989923 + outer loop + vertex 1.07453 1.66339 2.61475 + vertex 1.0784 1.66734 2.61398 + vertex 1.07353 1.6673 2.61436 + endloop + endfacet + facet normal 0.148334 0.110716 0.98272 + outer loop + vertex 1.07853 1.66269 2.61448 + vertex 1.08278 1.66726 2.61333 + vertex 1.0784 1.66734 2.61398 + endloop + endfacet + facet normal 0.148313 0.0902914 0.98481 + outer loop + vertex 1.08278 1.66726 2.61333 + vertex 1.0829 1.67231 2.61285 + vertex 1.0784 1.66734 2.61398 + endloop + endfacet + facet normal 0.124996 0.111611 0.98586 + outer loop + vertex 1.0784 1.66734 2.61398 + vertex 1.0829 1.67231 2.61285 + vertex 1.07833 1.67219 2.61344 + endloop + endfacet + facet normal 0.175886 0.0846619 0.980763 + outer loop + vertex 1.0828 1.66246 2.61374 + vertex 1.08278 1.66726 2.61333 + vertex 1.07853 1.66269 2.61448 + endloop + endfacet + facet normal 0.17672 0.109126 0.978193 + outer loop + vertex 1.07939 1.65877 2.61476 + vertex 1.0828 1.66246 2.61374 + vertex 1.07853 1.66269 2.61448 + endloop + endfacet + facet normal 0.216042 0.0715001 0.973763 + outer loop + vertex 1.08304 1.65784 2.61402 + vertex 1.0828 1.66246 2.61374 + vertex 1.07939 1.65877 2.61476 + endloop + endfacet + facet normal 0.216165 0.0720344 0.973696 + outer loop + vertex 1.07917 1.65381 2.61518 + vertex 1.08304 1.65784 2.61402 + vertex 1.07939 1.65877 2.61476 + endloop + endfacet + facet normal 0.0954109 0.0789147 0.992305 + outer loop + vertex 1.07415 1.65843 2.6153 + vertex 1.07917 1.65381 2.61518 + vertex 1.07939 1.65877 2.61476 + endloop + endfacet + facet normal 0.11647 0.101915 0.987951 + outer loop + vertex 1.07427 1.65391 2.61575 + vertex 1.07917 1.65381 2.61518 + vertex 1.07415 1.65843 2.6153 + endloop + endfacet + facet normal 0.0637511 0.101046 0.992837 + outer loop + vertex 1.07427 1.65391 2.61575 + vertex 1.07415 1.65843 2.6153 + vertex 1.07101 1.65548 2.6158 + endloop + endfacet + facet normal 0.0611467 0.0955909 0.993541 + outer loop + vertex 1.07101 1.65548 2.6158 + vertex 1.07151 1.65104 2.61619 + vertex 1.07427 1.65391 2.61575 + endloop + endfacet + facet normal 0.0638933 0.0929611 0.993618 + outer loop + vertex 1.07621 1.6509 2.61591 + vertex 1.07427 1.65391 2.61575 + vertex 1.07151 1.65104 2.61619 + endloop + endfacet + facet normal 0.063772 0.0881478 0.994064 + outer loop + vertex 1.07621 1.6509 2.61591 + vertex 1.07151 1.65104 2.61619 + vertex 1.07655 1.64636 2.61629 + endloop + endfacet + facet normal 0.123891 0.092147 0.988008 + outer loop + vertex 1.07621 1.6509 2.61591 + vertex 1.07655 1.64636 2.61629 + vertex 1.07942 1.64922 2.61566 + endloop + endfacet + facet normal 0.132884 0.109848 0.985026 + outer loop + vertex 1.07942 1.64922 2.61566 + vertex 1.07917 1.65381 2.61518 + vertex 1.07621 1.6509 2.61591 + endloop + endfacet + facet normal 0.287 0.11468 0.951041 + outer loop + vertex 1.07942 1.64922 2.61566 + vertex 1.08363 1.64904 2.61441 + vertex 1.07917 1.65381 2.61518 + endloop + endfacet + facet normal 0.24034 0.0682802 0.968284 + outer loop + vertex 1.07917 1.65381 2.61518 + vertex 1.08363 1.64904 2.61441 + vertex 1.08389 1.65393 2.614 + endloop + endfacet + facet normal 0.286944 0.16343 0.943903 + outer loop + vertex 1.07942 1.64922 2.61566 + vertex 1.08102 1.64624 2.61569 + vertex 1.08363 1.64904 2.61441 + endloop + endfacet + facet normal 0.321388 0.128836 0.938142 + outer loop + vertex 1.08359 1.64443 2.61506 + vertex 1.08363 1.64904 2.61441 + vertex 1.08102 1.64624 2.61569 + endloop + endfacet + facet normal 0.289066 0.0773454 0.95418 + outer loop + vertex 1.08102 1.64624 2.61569 + vertex 1.08064 1.64206 2.61614 + vertex 1.08359 1.64443 2.61506 + endloop + endfacet + facet normal 0.134141 0.0947798 0.986419 + outer loop + vertex 1.08102 1.64624 2.61569 + vertex 1.07655 1.64636 2.61629 + vertex 1.08064 1.64206 2.61614 + endloop + endfacet + facet normal 0.138383 0.0988608 0.985432 + outer loop + vertex 1.07655 1.64636 2.61629 + vertex 1.07669 1.6414 2.61676 + vertex 1.08064 1.64206 2.61614 + endloop + endfacet + facet normal 0.137419 0.10423 0.985014 + outer loop + vertex 1.07777 1.63741 2.61703 + vertex 1.08064 1.64206 2.61614 + vertex 1.07669 1.6414 2.61676 + endloop + endfacet + facet normal 0.0756005 0.0879772 0.99325 + outer loop + vertex 1.07777 1.63741 2.61703 + vertex 1.07669 1.6414 2.61676 + vertex 1.07337 1.6375 2.61736 + endloop + endfacet + facet normal 0.0757322 0.0981668 0.992284 + outer loop + vertex 1.07351 1.63255 2.61784 + vertex 1.07777 1.63741 2.61703 + vertex 1.07337 1.6375 2.61736 + endloop + endfacet + facet normal 0.0581449 0.097796 0.993506 + outer loop + vertex 1.07351 1.63255 2.61784 + vertex 1.07337 1.6375 2.61736 + vertex 1.06851 1.63239 2.61815 + endloop + endfacet + facet normal 0.0582142 0.0959776 0.99368 + outer loop + vertex 1.06831 1.6272 2.61866 + vertex 1.07351 1.63255 2.61784 + vertex 1.06851 1.63239 2.61815 + endloop + endfacet + facet normal 0.064246 0.0957094 0.993334 + outer loop + vertex 1.06831 1.6272 2.61866 + vertex 1.06851 1.63239 2.61815 + vertex 1.06314 1.62711 2.61901 + endloop + endfacet + facet normal 0.0644255 0.0883805 0.994001 + outer loop + vertex 1.06318 1.62228 2.61943 + vertex 1.06831 1.6272 2.61866 + vertex 1.06314 1.62711 2.61901 + endloop + endfacet + facet normal 0.0756887 0.0884185 0.993204 + outer loop + vertex 1.06318 1.62228 2.61943 + vertex 1.06314 1.62711 2.61901 + vertex 1.05837 1.62269 2.61976 + endloop + endfacet + facet normal 0.0752227 0.0825144 0.993747 + outer loop + vertex 1.05935 1.6188 2.62001 + vertex 1.06318 1.62228 2.61943 + vertex 1.05837 1.62269 2.61976 + endloop + endfacet + facet normal 0.0814628 0.0840479 0.993126 + outer loop + vertex 1.05935 1.6188 2.62001 + vertex 1.05837 1.62269 2.61976 + vertex 1.05422 1.61901 2.62041 + endloop + endfacet + facet normal 0.0814943 0.0849747 0.993045 + outer loop + vertex 1.05422 1.61901 2.62041 + vertex 1.05933 1.61405 2.62042 + vertex 1.05935 1.6188 2.62001 + endloop + endfacet + facet normal 0.0706784 0.0850974 0.993863 + outer loop + vertex 1.05933 1.61405 2.62042 + vertex 1.06347 1.61772 2.61981 + vertex 1.05935 1.6188 2.62001 + endloop + endfacet + facet normal 0.0664842 0.0898136 0.993737 + outer loop + vertex 1.0645 1.61391 2.62009 + vertex 1.06347 1.61772 2.61981 + vertex 1.05933 1.61405 2.62042 + endloop + endfacet + facet normal 0.0664577 0.0885001 0.993857 + outer loop + vertex 1.05933 1.61405 2.62042 + vertex 1.06439 1.60934 2.6205 + vertex 1.0645 1.61391 2.62009 + endloop + endfacet + facet normal 0.0456397 0.0891046 0.994976 + outer loop + vertex 1.06439 1.60934 2.6205 + vertex 1.0686 1.61297 2.61998 + vertex 1.0645 1.61391 2.62009 + endloop + endfacet + facet normal 0.0468284 0.0943021 0.994442 + outer loop + vertex 1.0686 1.61297 2.61998 + vertex 1.06829 1.61739 2.61958 + vertex 1.0645 1.61391 2.62009 + endloop + endfacet + facet normal 0.055051 0.0948322 0.99397 + outer loop + vertex 1.0686 1.61297 2.61998 + vertex 1.0731 1.61726 2.61932 + vertex 1.06829 1.61739 2.61958 + endloop + endfacet + facet normal 0.0550209 0.0934307 0.994104 + outer loop + vertex 1.0731 1.61726 2.61932 + vertex 1.07317 1.62223 2.61885 + vertex 1.06829 1.61739 2.61958 + endloop + endfacet + facet normal 0.056455 0.0919941 0.994158 + outer loop + vertex 1.06829 1.61739 2.61958 + vertex 1.07317 1.62223 2.61885 + vertex 1.06817 1.62215 2.61914 + endloop + endfacet + facet normal 0.0543395 0.09195 0.99428 + outer loop + vertex 1.06829 1.61739 2.61958 + vertex 1.06817 1.62215 2.61914 + vertex 1.06347 1.61772 2.61981 + endloop + endfacet + facet normal 0.0596795 0.086313 0.994479 + outer loop + vertex 1.06347 1.61772 2.61981 + vertex 1.06817 1.62215 2.61914 + vertex 1.06318 1.62228 2.61943 + endloop + endfacet + facet normal 0.0564133 0.0938025 0.993991 + outer loop + vertex 1.07317 1.62223 2.61885 + vertex 1.07337 1.62738 2.61835 + vertex 1.06817 1.62215 2.61914 + endloop + endfacet + facet normal 0.0569868 0.0932359 0.994012 + outer loop + vertex 1.06817 1.62215 2.61914 + vertex 1.07337 1.62738 2.61835 + vertex 1.06831 1.6272 2.61866 + endloop + endfacet + facet normal 0.0949138 0.092035 0.991222 + outer loop + vertex 1.07317 1.62223 2.61885 + vertex 1.07803 1.6274 2.61791 + vertex 1.07337 1.62738 2.61835 + endloop + endfacet + facet normal 0.0949737 0.0871583 0.991657 + outer loop + vertex 1.07803 1.6274 2.61791 + vertex 1.07812 1.63252 2.61745 + vertex 1.07337 1.62738 2.61835 + endloop + endfacet + facet normal 0.0850141 0.0963729 0.991708 + outer loop + vertex 1.07337 1.62738 2.61835 + vertex 1.07812 1.63252 2.61745 + vertex 1.07351 1.63255 2.61784 + endloop + endfacet + facet normal 0.206384 0.0836958 0.974885 + outer loop + vertex 1.07803 1.6274 2.61791 + vertex 1.08206 1.632 2.61666 + vertex 1.07812 1.63252 2.61745 + endloop + endfacet + facet normal 0.205006 0.0711774 0.976169 + outer loop + vertex 1.08206 1.632 2.61666 + vertex 1.08178 1.63694 2.61636 + vertex 1.07812 1.63252 2.61745 + endloop + endfacet + facet normal 0.176641 0.0954901 0.979632 + outer loop + vertex 1.07812 1.63252 2.61745 + vertex 1.08178 1.63694 2.61636 + vertex 1.07777 1.63741 2.61703 + endloop + endfacet + facet normal 0.229217 0.0627379 0.971351 + outer loop + vertex 1.082 1.62696 2.617 + vertex 1.08206 1.632 2.61666 + vertex 1.07803 1.6274 2.61791 + endloop + endfacet + facet normal 0.230358 0.0753337 0.970185 + outer loop + vertex 1.07782 1.62223 2.61836 + vertex 1.082 1.62696 2.617 + vertex 1.07803 1.6274 2.61791 + endloop + endfacet + facet normal 0.249971 0.0569839 0.966575 + outer loop + vertex 1.08186 1.62182 2.61734 + vertex 1.082 1.62696 2.617 + vertex 1.07782 1.62223 2.61836 + endloop + endfacet + facet normal 0.251582 0.0776541 0.964716 + outer loop + vertex 1.0777 1.61714 2.6188 + vertex 1.08186 1.62182 2.61734 + vertex 1.07782 1.62223 2.61836 + endloop + endfacet + facet normal 0.114863 0.0832265 0.989889 + outer loop + vertex 1.0777 1.61714 2.6188 + vertex 1.07782 1.62223 2.61836 + vertex 1.0731 1.61726 2.61932 + endloop + endfacet + facet normal 0.115095 0.0982736 0.988481 + outer loop + vertex 1.07326 1.61262 2.61977 + vertex 1.0777 1.61714 2.6188 + vertex 1.0731 1.61726 2.61932 + endloop + endfacet + facet normal 0.13087 0.0826652 0.987947 + outer loop + vertex 1.07772 1.61221 2.61921 + vertex 1.0777 1.61714 2.6188 + vertex 1.07326 1.61262 2.61977 + endloop + endfacet + facet normal 0.13193 0.0960245 0.986597 + outer loop + vertex 1.07358 1.60815 2.62016 + vertex 1.07772 1.61221 2.61921 + vertex 1.07326 1.61262 2.61977 + endloop + endfacet + facet normal 0.0606465 0.0915142 0.993955 + outer loop + vertex 1.07358 1.60815 2.62016 + vertex 1.07326 1.61262 2.61977 + vertex 1.06953 1.60936 2.62029 + endloop + endfacet + facet normal 0.0579679 0.0824588 0.994907 + outer loop + vertex 1.06898 1.6052 2.62067 + vertex 1.07358 1.60815 2.62016 + vertex 1.06953 1.60936 2.62029 + endloop + endfacet + facet normal 0.0396866 0.0849461 0.995595 + outer loop + vertex 1.06439 1.60934 2.6205 + vertex 1.06898 1.6052 2.62067 + vertex 1.06953 1.60936 2.62029 + endloop + endfacet + facet normal 0.0606334 0.0783346 0.995082 + outer loop + vertex 1.07476 1.60315 2.62048 + vertex 1.07358 1.60815 2.62016 + vertex 1.06898 1.6052 2.62067 + endloop + endfacet + facet normal 0.0664832 0.0950102 0.993254 + outer loop + vertex 1.06898 1.6052 2.62067 + vertex 1.07059 1.60044 2.62102 + vertex 1.07476 1.60315 2.62048 + endloop + endfacet + facet normal 0.0604427 0.10419 0.992719 + outer loop + vertex 1.07059 1.60044 2.62102 + vertex 1.07463 1.59888 2.62094 + vertex 1.07476 1.60315 2.62048 + endloop + endfacet + facet normal 0.199468 0.0980123 0.97499 + outer loop + vertex 1.07463 1.59888 2.62094 + vertex 1.079 1.5989 2.62004 + vertex 1.07476 1.60315 2.62048 + endloop + endfacet + facet normal 0.185127 0.0832576 0.979181 + outer loop + vertex 1.07476 1.60315 2.62048 + vertex 1.079 1.5989 2.62004 + vertex 1.07916 1.6036 2.61961 + endloop + endfacet + facet normal 0.186515 0.0711498 0.979872 + outer loop + vertex 1.07916 1.6036 2.61961 + vertex 1.07811 1.60749 2.61953 + vertex 1.07476 1.60315 2.62048 + endloop + endfacet + facet normal 0.356785 0.115917 0.926967 + outer loop + vertex 1.07916 1.6036 2.61961 + vertex 1.08192 1.60676 2.61815 + vertex 1.07811 1.60749 2.61953 + endloop + endfacet + facet normal 0.348074 0.0532145 0.935955 + outer loop + vertex 1.08192 1.60676 2.61815 + vertex 1.08173 1.61159 2.61795 + vertex 1.07811 1.60749 2.61953 + endloop + endfacet + facet normal 0.311591 0.0893167 0.946009 + outer loop + vertex 1.07811 1.60749 2.61953 + vertex 1.08173 1.61159 2.61795 + vertex 1.07772 1.61221 2.61921 + endloop + endfacet + facet normal 0.307312 0.0538987 0.950081 + outer loop + vertex 1.08173 1.61159 2.61795 + vertex 1.08174 1.61667 2.61766 + vertex 1.07772 1.61221 2.61921 + endloop + endfacet + facet normal 0.415228 0.0559067 0.907998 + outer loop + vertex 1.08221 1.6022 2.6183 + vertex 1.08192 1.60676 2.61815 + vertex 1.07916 1.6036 2.61961 + endloop + endfacet + facet normal 0.419829 0.0686974 0.904999 + outer loop + vertex 1.079 1.5989 2.62004 + vertex 1.08221 1.6022 2.6183 + vertex 1.07916 1.6036 2.61961 + endloop + endfacet + facet normal 0.438526 0.0465768 0.897511 + outer loop + vertex 1.08286 1.59838 2.61818 + vertex 1.08221 1.6022 2.6183 + vertex 1.079 1.5989 2.62004 + endloop + endfacet + facet normal 0.444288 0.126829 0.886861 + outer loop + vertex 1.079 1.5989 2.62004 + vertex 1.08239 1.59444 2.61898 + vertex 1.08286 1.59838 2.61818 + endloop + endfacet + facet normal 0.462844 0.143818 0.874695 + outer loop + vertex 1.07926 1.5947 2.62059 + vertex 1.08239 1.59444 2.61898 + vertex 1.079 1.5989 2.62004 + endloop + endfacet + facet normal 0.217788 0.140648 0.965809 + outer loop + vertex 1.07926 1.5947 2.62059 + vertex 1.079 1.5989 2.62004 + vertex 1.0765 1.59606 2.62102 + endloop + endfacet + facet normal 0.185581 0.0708562 0.980071 + outer loop + vertex 1.0765 1.59606 2.62102 + vertex 1.07668 1.59157 2.62131 + vertex 1.07926 1.5947 2.62059 + endloop + endfacet + facet normal 0.210115 0.0498204 0.976406 + outer loop + vertex 1.08066 1.59193 2.62043 + vertex 1.07926 1.5947 2.62059 + vertex 1.07668 1.59157 2.62131 + endloop + endfacet + facet normal 0.207242 0.0783408 0.975148 + outer loop + vertex 1.08066 1.59193 2.62043 + vertex 1.07668 1.59157 2.62131 + vertex 1.0804 1.58771 2.62083 + endloop + endfacet + facet normal 0.469351 0.0535839 0.881385 + outer loop + vertex 1.08066 1.59193 2.62043 + vertex 1.0804 1.58771 2.62083 + vertex 1.08286 1.59041 2.61935 + endloop + endfacet + facet normal 0.511474 0.138436 0.848074 + outer loop + vertex 1.08286 1.59041 2.61935 + vertex 1.08239 1.59444 2.61898 + vertex 1.08066 1.59193 2.62043 + endloop + endfacet + facet normal 0.0670138 0.0671109 0.995492 + outer loop + vertex 1.0765 1.59606 2.62102 + vertex 1.07227 1.59559 2.62133 + vertex 1.07668 1.59157 2.62131 + endloop + endfacet + facet normal 0.0632418 0.0629646 0.99601 + outer loop + vertex 1.07227 1.59559 2.62133 + vertex 1.07191 1.59105 2.62164 + vertex 1.07668 1.59157 2.62131 + endloop + endfacet + facet normal 0.0615242 0.0780658 0.995048 + outer loop + vertex 1.07297 1.58718 2.62188 + vertex 1.07668 1.59157 2.62131 + vertex 1.07191 1.59105 2.62164 + endloop + endfacet + facet normal 0.033457 0.0704903 0.996951 + outer loop + vertex 1.07297 1.58718 2.62188 + vertex 1.07191 1.59105 2.62164 + vertex 1.06834 1.58747 2.62202 + endloop + endfacet + facet normal 0.0336179 0.0731454 0.996755 + outer loop + vertex 1.06866 1.58266 2.62236 + vertex 1.07297 1.58718 2.62188 + vertex 1.06834 1.58747 2.62202 + endloop + endfacet + facet normal 0.0440452 0.0737995 0.9963 + outer loop + vertex 1.06866 1.58266 2.62236 + vertex 1.06834 1.58747 2.62202 + vertex 1.06364 1.58275 2.62257 + endloop + endfacet + facet normal 0.0440014 0.0709292 0.99651 + outer loop + vertex 1.0636 1.57766 2.62294 + vertex 1.06866 1.58266 2.62236 + vertex 1.06364 1.58275 2.62257 + endloop + endfacet + facet normal 0.0574262 0.0707641 0.995839 + outer loop + vertex 1.0636 1.57766 2.62294 + vertex 1.06364 1.58275 2.62257 + vertex 1.05845 1.57759 2.62324 + endloop + endfacet + facet normal 0.0575346 0.0646695 0.996247 + outer loop + vertex 1.05831 1.57246 2.62358 + vertex 1.0636 1.57766 2.62294 + vertex 1.05845 1.57759 2.62324 + endloop + endfacet + facet normal 0.0612733 0.0645542 0.996031 + outer loop + vertex 1.05831 1.57246 2.62358 + vertex 1.05845 1.57759 2.62324 + vertex 1.05317 1.57229 2.62391 + endloop + endfacet + facet normal 0.061503 0.0584552 0.996394 + outer loop + vertex 1.05307 1.56719 2.62421 + vertex 1.05831 1.57246 2.62358 + vertex 1.05317 1.57229 2.62391 + endloop + endfacet + facet normal 0.0566051 0.0585718 0.996677 + outer loop + vertex 1.05307 1.56719 2.62421 + vertex 1.05317 1.57229 2.62391 + vertex 1.04799 1.56708 2.62451 + endloop + endfacet + facet normal 0.0567371 0.0532321 0.996969 + outer loop + vertex 1.04797 1.56213 2.62477 + vertex 1.05307 1.56719 2.62421 + vertex 1.04799 1.56708 2.62451 + endloop + endfacet + facet normal 0.0508383 0.0532709 0.997285 + outer loop + vertex 1.04797 1.56213 2.62477 + vertex 1.04799 1.56708 2.62451 + vertex 1.04319 1.56244 2.625 + endloop + endfacet + facet normal 0.050439 0.04677 0.997631 + outer loop + vertex 1.04326 1.55784 2.62521 + vertex 1.04797 1.56213 2.62477 + vertex 1.04319 1.56244 2.625 + endloop + endfacet + facet normal 0.047363 0.0467253 0.997784 + outer loop + vertex 1.04326 1.55784 2.62521 + vertex 1.04319 1.56244 2.625 + vertex 1.03951 1.55908 2.62533 + endloop + endfacet + facet normal 0.0452422 0.0402745 0.998164 + outer loop + vertex 1.0386 1.55471 2.62555 + vertex 1.04326 1.55784 2.62521 + vertex 1.03951 1.55908 2.62533 + endloop + endfacet + facet normal 0.0491424 0.0394569 0.998012 + outer loop + vertex 1.03516 1.55889 2.62555 + vertex 1.0386 1.55471 2.62555 + vertex 1.03951 1.55908 2.62533 + endloop + endfacet + facet normal 0.0488549 0.045628 0.997763 + outer loop + vertex 1.03951 1.55908 2.62533 + vertex 1.03856 1.56305 2.6252 + vertex 1.03516 1.55889 2.62555 + endloop + endfacet + facet normal 0.0546051 0.040915 0.997669 + outer loop + vertex 1.03516 1.55889 2.62555 + vertex 1.03856 1.56305 2.6252 + vertex 1.03366 1.56453 2.6254 + endloop + endfacet + facet normal 0.0655034 0.0437836 0.996891 + outer loop + vertex 1.03516 1.55889 2.62555 + vertex 1.03366 1.56453 2.6254 + vertex 1.03064 1.56055 2.62578 + endloop + endfacet + facet normal 0.0620279 0.0342505 0.997487 + outer loop + vertex 1.03186 1.5566 2.62584 + vertex 1.03516 1.55889 2.62555 + vertex 1.03064 1.56055 2.62578 + endloop + endfacet + facet normal 0.0848893 0.0412992 0.995534 + outer loop + vertex 1.03064 1.56055 2.62578 + vertex 1.02768 1.55624 2.62621 + vertex 1.03186 1.5566 2.62584 + endloop + endfacet + facet normal 0.0852718 0.0369494 0.995672 + outer loop + vertex 1.03186 1.5566 2.62584 + vertex 1.02768 1.55624 2.62621 + vertex 1.03123 1.55215 2.62606 + endloop + endfacet + facet normal 0.0642384 0.0399885 0.997133 + outer loop + vertex 1.03186 1.5566 2.62584 + vertex 1.03123 1.55215 2.62606 + vertex 1.03447 1.55465 2.62575 + endloop + endfacet + facet normal 0.0633989 0.0410737 0.997143 + outer loop + vertex 1.03572 1.55091 2.62582 + vertex 1.03447 1.55465 2.62575 + vertex 1.03123 1.55215 2.62606 + endloop + endfacet + facet normal 0.0617195 0.0349345 0.997482 + outer loop + vertex 1.03123 1.55215 2.62606 + vertex 1.03292 1.54655 2.62615 + vertex 1.03572 1.55091 2.62582 + endloop + endfacet + facet normal 0.0566597 0.038198 0.997663 + outer loop + vertex 1.03572 1.55091 2.62582 + vertex 1.03292 1.54655 2.62615 + vertex 1.03715 1.54723 2.62588 + endloop + endfacet + facet normal 0.0442523 0.0333768 0.998463 + outer loop + vertex 1.03715 1.54723 2.62588 + vertex 1.03986 1.54986 2.62567 + vertex 1.03572 1.55091 2.62582 + endloop + endfacet + facet normal 0.0452453 0.0373384 0.998278 + outer loop + vertex 1.03986 1.54986 2.62567 + vertex 1.0386 1.55471 2.62555 + vertex 1.03572 1.55091 2.62582 + endloop + endfacet + facet normal 0.042436 0.0366103 0.998428 + outer loop + vertex 1.03986 1.54986 2.62567 + vertex 1.04355 1.55315 2.6254 + vertex 1.0386 1.55471 2.62555 + endloop + endfacet + facet normal 0.0410495 0.0381646 0.998428 + outer loop + vertex 1.04456 1.54815 2.62555 + vertex 1.04355 1.55315 2.6254 + vertex 1.03986 1.54986 2.62567 + endloop + endfacet + facet normal 0.040043 0.0353922 0.998571 + outer loop + vertex 1.03986 1.54986 2.62567 + vertex 1.04046 1.54558 2.6258 + vertex 1.04456 1.54815 2.62555 + endloop + endfacet + facet normal 0.039225 0.0366945 0.998556 + outer loop + vertex 1.04046 1.54558 2.6258 + vertex 1.04382 1.54391 2.62573 + vertex 1.04456 1.54815 2.62555 + endloop + endfacet + facet normal 0.0437337 0.0359073 0.998398 + outer loop + vertex 1.04382 1.54391 2.62573 + vertex 1.04826 1.54427 2.62552 + vertex 1.04456 1.54815 2.62555 + endloop + endfacet + facet normal 0.0452518 0.0373566 0.998277 + outer loop + vertex 1.04456 1.54815 2.62555 + vertex 1.04826 1.54427 2.62552 + vertex 1.04921 1.54883 2.62531 + endloop + endfacet + facet normal 0.0447675 0.0406255 0.998171 + outer loop + vertex 1.04921 1.54883 2.62531 + vertex 1.04836 1.5526 2.62519 + vertex 1.04456 1.54815 2.62555 + endloop + endfacet + facet normal 0.0527087 0.0423909 0.99771 + outer loop + vertex 1.04921 1.54883 2.62531 + vertex 1.05309 1.55246 2.62495 + vertex 1.04836 1.5526 2.62519 + endloop + endfacet + facet normal 0.0528194 0.0464497 0.997523 + outer loop + vertex 1.05309 1.55246 2.62495 + vertex 1.053 1.55719 2.62474 + vertex 1.04836 1.5526 2.62519 + endloop + endfacet + facet normal 0.0546315 0.0446156 0.997509 + outer loop + vertex 1.04836 1.5526 2.62519 + vertex 1.053 1.55719 2.62474 + vertex 1.04803 1.55728 2.625 + endloop + endfacet + facet normal 0.0469378 0.0440927 0.997924 + outer loop + vertex 1.04836 1.5526 2.62519 + vertex 1.04803 1.55728 2.625 + vertex 1.04355 1.55315 2.6254 + endloop + endfacet + facet normal 0.0486624 0.042222 0.997922 + outer loop + vertex 1.04355 1.55315 2.6254 + vertex 1.04803 1.55728 2.625 + vertex 1.04326 1.55784 2.62521 + endloop + endfacet + facet normal 0.0547093 0.0496034 0.997269 + outer loop + vertex 1.053 1.55719 2.62474 + vertex 1.053 1.56214 2.62449 + vertex 1.04803 1.55728 2.625 + endloop + endfacet + facet normal 0.0562226 0.0480559 0.997261 + outer loop + vertex 1.04803 1.55728 2.625 + vertex 1.053 1.56214 2.62449 + vertex 1.04797 1.56213 2.62477 + endloop + endfacet + facet normal 0.0578405 0.0495957 0.997093 + outer loop + vertex 1.053 1.55719 2.62474 + vertex 1.05812 1.56226 2.62419 + vertex 1.053 1.56214 2.62449 + endloop + endfacet + facet normal 0.0576648 0.0561009 0.996758 + outer loop + vertex 1.05812 1.56226 2.62419 + vertex 1.0582 1.56735 2.6239 + vertex 1.053 1.56214 2.62449 + endloop + endfacet + facet normal 0.0600585 0.0537072 0.996749 + outer loop + vertex 1.053 1.56214 2.62449 + vertex 1.0582 1.56735 2.6239 + vertex 1.05307 1.56719 2.62421 + endloop + endfacet + facet normal 0.0505766 0.0562363 0.997136 + outer loop + vertex 1.05812 1.56226 2.62419 + vertex 1.0634 1.56744 2.62363 + vertex 1.0582 1.56735 2.6239 + endloop + endfacet + facet normal 0.0504124 0.0643861 0.996651 + outer loop + vertex 1.0634 1.56744 2.62363 + vertex 1.0635 1.57254 2.62329 + vertex 1.0582 1.56735 2.6239 + endloop + endfacet + facet normal 0.0544866 0.0602403 0.996696 + outer loop + vertex 1.0582 1.56735 2.6239 + vertex 1.0635 1.57254 2.62329 + vertex 1.05831 1.57246 2.62358 + endloop + endfacet + facet normal 0.0381615 0.0646489 0.997178 + outer loop + vertex 1.0634 1.56744 2.62363 + vertex 1.06869 1.57257 2.62309 + vertex 1.0635 1.57254 2.62329 + endloop + endfacet + facet normal 0.0381109 0.0716177 0.996704 + outer loop + vertex 1.06869 1.57257 2.62309 + vertex 1.06873 1.57765 2.62272 + vertex 1.0635 1.57254 2.62329 + endloop + endfacet + facet normal 0.0414431 0.0682114 0.99681 + outer loop + vertex 1.0635 1.57254 2.62329 + vertex 1.06873 1.57765 2.62272 + vertex 1.0636 1.57766 2.62294 + endloop + endfacet + facet normal 0.0388318 0.0716096 0.996677 + outer loop + vertex 1.06869 1.57257 2.62309 + vertex 1.07367 1.57767 2.62253 + vertex 1.06873 1.57765 2.62272 + endloop + endfacet + facet normal 0.0388454 0.0700096 0.99679 + outer loop + vertex 1.07367 1.57767 2.62253 + vertex 1.07342 1.58252 2.6222 + vertex 1.06873 1.57765 2.62272 + endloop + endfacet + facet normal 0.0352741 0.0734359 0.996676 + outer loop + vertex 1.06873 1.57765 2.62272 + vertex 1.07342 1.58252 2.6222 + vertex 1.06866 1.58266 2.62236 + endloop + endfacet + facet normal 0.0851551 0.0721624 0.993751 + outer loop + vertex 1.07367 1.57767 2.62253 + vertex 1.07772 1.58264 2.62182 + vertex 1.07342 1.58252 2.6222 + endloop + endfacet + facet normal 0.0857167 0.0553176 0.994783 + outer loop + vertex 1.07772 1.58264 2.62182 + vertex 1.07667 1.58652 2.6217 + vertex 1.07342 1.58252 2.6222 + endloop + endfacet + facet normal 0.062612 0.0741415 0.99528 + outer loop + vertex 1.07342 1.58252 2.6222 + vertex 1.07667 1.58652 2.6217 + vertex 1.07297 1.58718 2.62188 + endloop + endfacet + facet normal 0.200614 0.0855754 0.975926 + outer loop + vertex 1.07772 1.58264 2.62182 + vertex 1.0804 1.58771 2.62083 + vertex 1.07667 1.58652 2.6217 + endloop + endfacet + facet normal 0.203993 0.0750905 0.976088 + outer loop + vertex 1.07668 1.59157 2.62131 + vertex 1.07667 1.58652 2.6217 + vertex 1.0804 1.58771 2.62083 + endloop + endfacet + facet normal 0.105947 0.0550616 0.992846 + outer loop + vertex 1.07804 1.57778 2.62206 + vertex 1.07772 1.58264 2.62182 + vertex 1.07367 1.57767 2.62253 + endloop + endfacet + facet normal 0.105511 0.0696389 0.991977 + outer loop + vertex 1.07367 1.57263 2.62288 + vertex 1.07804 1.57778 2.62206 + vertex 1.07367 1.57767 2.62253 + endloop + endfacet + facet normal 0.119331 0.0577751 0.991172 + outer loop + vertex 1.07803 1.57276 2.62235 + vertex 1.07804 1.57778 2.62206 + vertex 1.07367 1.57263 2.62288 + endloop + endfacet + facet normal 0.119096 0.0644411 0.990789 + outer loop + vertex 1.0736 1.56759 2.62322 + vertex 1.07803 1.57276 2.62235 + vertex 1.07367 1.57263 2.62288 + endloop + endfacet + facet normal 0.0429858 0.0659496 0.996897 + outer loop + vertex 1.0736 1.56759 2.62322 + vertex 1.07367 1.57263 2.62288 + vertex 1.06861 1.56749 2.62344 + endloop + endfacet + facet normal 0.043051 0.0631237 0.997077 + outer loop + vertex 1.06856 1.56244 2.62376 + vertex 1.0736 1.56759 2.62322 + vertex 1.06861 1.56749 2.62344 + endloop + endfacet + facet normal 0.0318216 0.0632792 0.997488 + outer loop + vertex 1.06856 1.56244 2.62376 + vertex 1.06861 1.56749 2.62344 + vertex 1.06332 1.56236 2.62394 + endloop + endfacet + facet normal 0.0319485 0.0564282 0.997895 + outer loop + vertex 1.06324 1.55729 2.62423 + vertex 1.06856 1.56244 2.62376 + vertex 1.06332 1.56236 2.62394 + endloop + endfacet + facet normal 0.0433576 0.0562107 0.997477 + outer loop + vertex 1.06324 1.55729 2.62423 + vertex 1.06332 1.56236 2.62394 + vertex 1.05805 1.55723 2.62445 + endloop + endfacet + facet normal 0.0434543 0.0489898 0.997854 + outer loop + vertex 1.05795 1.55226 2.6247 + vertex 1.06324 1.55729 2.62423 + vertex 1.05805 1.55723 2.62445 + endloop + endfacet + facet normal 0.0527943 0.0487902 0.997413 + outer loop + vertex 1.05795 1.55226 2.6247 + vertex 1.05805 1.55723 2.62445 + vertex 1.05309 1.55246 2.62495 + endloop + endfacet + facet normal 0.052525 0.0419181 0.997739 + outer loop + vertex 1.05305 1.54782 2.62515 + vertex 1.05795 1.55226 2.6247 + vertex 1.05309 1.55246 2.62495 + endloop + endfacet + facet normal 0.0506043 0.0440363 0.997747 + outer loop + vertex 1.05792 1.54731 2.62492 + vertex 1.05795 1.55226 2.6247 + vertex 1.05305 1.54782 2.62515 + endloop + endfacet + facet normal 0.0499341 0.0374428 0.99805 + outer loop + vertex 1.05341 1.54308 2.62531 + vertex 1.05792 1.54731 2.62492 + vertex 1.05305 1.54782 2.62515 + endloop + endfacet + facet normal 0.0505339 0.0374873 0.998019 + outer loop + vertex 1.05341 1.54308 2.62531 + vertex 1.05305 1.54782 2.62515 + vertex 1.04826 1.54427 2.62552 + endloop + endfacet + facet normal 0.0500467 0.0353608 0.998121 + outer loop + vertex 1.05021 1.5388 2.62562 + vertex 1.05341 1.54308 2.62531 + vertex 1.04826 1.54427 2.62552 + endloop + endfacet + facet normal 0.0462942 0.0340283 0.998348 + outer loop + vertex 1.05021 1.5388 2.62562 + vertex 1.04826 1.54427 2.62552 + vertex 1.04546 1.54026 2.62579 + endloop + endfacet + facet normal 0.0468318 0.0357856 0.998262 + outer loop + vertex 1.04705 1.5365 2.62585 + vertex 1.05021 1.5388 2.62562 + vertex 1.04546 1.54026 2.62579 + endloop + endfacet + facet normal 0.0387757 0.032391 0.998723 + outer loop + vertex 1.04546 1.54026 2.62579 + vertex 1.04284 1.53618 2.62602 + vertex 1.04705 1.5365 2.62585 + endloop + endfacet + facet normal 0.0390727 0.0284984 0.99883 + outer loop + vertex 1.04705 1.5365 2.62585 + vertex 1.04284 1.53618 2.62602 + vertex 1.04689 1.53172 2.62599 + endloop + endfacet + facet normal 0.0448326 0.0282988 0.998594 + outer loop + vertex 1.04705 1.5365 2.62585 + vertex 1.04689 1.53172 2.62599 + vertex 1.04988 1.53464 2.62578 + endloop + endfacet + facet normal 0.0464199 0.0266724 0.998566 + outer loop + vertex 1.05117 1.53157 2.6258 + vertex 1.04988 1.53464 2.62578 + vertex 1.04689 1.53172 2.62599 + endloop + endfacet + facet normal 0.0463248 0.023782 0.998643 + outer loop + vertex 1.05117 1.53157 2.6258 + vertex 1.04689 1.53172 2.62599 + vertex 1.05067 1.52724 2.62592 + endloop + endfacet + facet normal 0.0516699 0.0231545 0.998396 + outer loop + vertex 1.05117 1.53157 2.6258 + vertex 1.05067 1.52724 2.62592 + vertex 1.05386 1.5296 2.6257 + endloop + endfacet + facet normal 0.0547325 0.0273319 0.998127 + outer loop + vertex 1.05386 1.5296 2.6257 + vertex 1.05427 1.53425 2.62556 + vertex 1.05117 1.53157 2.6258 + endloop + endfacet + facet normal 0.0479023 0.0279437 0.998461 + outer loop + vertex 1.05386 1.5296 2.6257 + vertex 1.05815 1.52954 2.6255 + vertex 1.05427 1.53425 2.62556 + endloop + endfacet + facet normal 0.0456374 0.0260753 0.998618 + outer loop + vertex 1.05427 1.53425 2.62556 + vertex 1.05815 1.52954 2.6255 + vertex 1.05924 1.53407 2.62533 + endloop + endfacet + facet normal 0.0458368 0.031946 0.998438 + outer loop + vertex 1.05924 1.53407 2.62533 + vertex 1.0585 1.53794 2.62524 + vertex 1.05427 1.53425 2.62556 + endloop + endfacet + facet normal 0.0455886 0.0322299 0.99844 + outer loop + vertex 1.05427 1.53425 2.62556 + vertex 1.0585 1.53794 2.62524 + vertex 1.05461 1.53907 2.62538 + endloop + endfacet + facet normal 0.0516073 0.0317963 0.998161 + outer loop + vertex 1.05021 1.5388 2.62562 + vertex 1.05427 1.53425 2.62556 + vertex 1.05461 1.53907 2.62538 + endloop + endfacet + facet normal 0.0532826 0.0332922 0.998024 + outer loop + vertex 1.04988 1.53464 2.62578 + vertex 1.05427 1.53425 2.62556 + vertex 1.05021 1.5388 2.62562 + endloop + endfacet + facet normal 0.0462971 0.0346916 0.998325 + outer loop + vertex 1.0585 1.53794 2.62524 + vertex 1.05816 1.54252 2.6251 + vertex 1.05461 1.53907 2.62538 + endloop + endfacet + facet normal 0.0477369 0.0332058 0.998308 + outer loop + vertex 1.05461 1.53907 2.62538 + vertex 1.05816 1.54252 2.6251 + vertex 1.05341 1.54308 2.62531 + endloop + endfacet + facet normal 0.0355904 0.0339292 0.99879 + outer loop + vertex 1.0585 1.53794 2.62524 + vertex 1.06312 1.54218 2.62493 + vertex 1.05816 1.54252 2.6251 + endloop + endfacet + facet normal 0.0360674 0.0409792 0.998509 + outer loop + vertex 1.06312 1.54218 2.62493 + vertex 1.06308 1.54714 2.62473 + vertex 1.05816 1.54252 2.6251 + endloop + endfacet + facet normal 0.0383311 0.0385758 0.99852 + outer loop + vertex 1.05816 1.54252 2.6251 + vertex 1.06308 1.54714 2.62473 + vertex 1.05792 1.54731 2.62492 + endloop + endfacet + facet normal 0.03857 0.0464158 0.998177 + outer loop + vertex 1.06308 1.54714 2.62473 + vertex 1.06314 1.55221 2.62449 + vertex 1.05792 1.54731 2.62492 + endloop + endfacet + facet normal 0.0317701 0.0465053 0.998413 + outer loop + vertex 1.06308 1.54714 2.62473 + vertex 1.06843 1.55233 2.62432 + vertex 1.06314 1.55221 2.62449 + endloop + endfacet + facet normal 0.0316476 0.0514903 0.998172 + outer loop + vertex 1.06843 1.55233 2.62432 + vertex 1.0685 1.5574 2.62406 + vertex 1.06314 1.55221 2.62449 + endloop + endfacet + facet normal 0.031159 0.0519946 0.998161 + outer loop + vertex 1.06314 1.55221 2.62449 + vertex 1.0685 1.5574 2.62406 + vertex 1.06324 1.55729 2.62423 + endloop + endfacet + facet normal 0.0525993 0.0511614 0.997304 + outer loop + vertex 1.06843 1.55233 2.62432 + vertex 1.07355 1.5576 2.62378 + vertex 1.0685 1.5574 2.62406 + endloop + endfacet + facet normal 0.0525873 0.0514525 0.99729 + outer loop + vertex 1.07355 1.5576 2.62378 + vertex 1.07356 1.56259 2.62352 + vertex 1.0685 1.5574 2.62406 + endloop + endfacet + facet normal 0.0467232 0.0571725 0.99727 + outer loop + vertex 1.0685 1.5574 2.62406 + vertex 1.07356 1.56259 2.62352 + vertex 1.06856 1.56244 2.62376 + endloop + endfacet + facet normal 0.139402 0.0508106 0.988931 + outer loop + vertex 1.07355 1.5576 2.62378 + vertex 1.07798 1.56274 2.62289 + vertex 1.07356 1.56259 2.62352 + endloop + endfacet + facet normal 0.139387 0.0511719 0.988915 + outer loop + vertex 1.07798 1.56274 2.62289 + vertex 1.07797 1.56772 2.62263 + vertex 1.07356 1.56259 2.62352 + endloop + endfacet + facet normal 0.130915 0.0585742 0.989662 + outer loop + vertex 1.07356 1.56259 2.62352 + vertex 1.07797 1.56772 2.62263 + vertex 1.0736 1.56759 2.62322 + endloop + endfacet + facet normal 0.15011 0.0413852 0.987803 + outer loop + vertex 1.07801 1.55778 2.62309 + vertex 1.07798 1.56274 2.62289 + vertex 1.07355 1.5576 2.62378 + endloop + endfacet + facet normal 0.149936 0.0452134 0.987661 + outer loop + vertex 1.07353 1.55258 2.62401 + vertex 1.07801 1.55778 2.62309 + vertex 1.07355 1.5576 2.62378 + endloop + endfacet + facet normal 0.166663 0.0304255 0.985544 + outer loop + vertex 1.07802 1.5528 2.62325 + vertex 1.07801 1.55778 2.62309 + vertex 1.07353 1.55258 2.62401 + endloop + endfacet + facet normal 0.166246 0.0384191 0.985336 + outer loop + vertex 1.0735 1.54753 2.62421 + vertex 1.07802 1.5528 2.62325 + vertex 1.07353 1.55258 2.62401 + endloop + endfacet + facet normal 0.064288 0.03961 0.997145 + outer loop + vertex 1.0735 1.54753 2.62421 + vertex 1.07353 1.55258 2.62401 + vertex 1.06837 1.54724 2.62456 + endloop + endfacet + facet normal 0.0642261 0.0406755 0.997106 + outer loop + vertex 1.06834 1.54219 2.62476 + vertex 1.0735 1.54753 2.62421 + vertex 1.06837 1.54724 2.62456 + endloop + endfacet + facet normal 0.0323194 0.0409284 0.998639 + outer loop + vertex 1.06834 1.54219 2.62476 + vertex 1.06837 1.54724 2.62456 + vertex 1.06312 1.54218 2.62493 + endloop + endfacet + facet normal 0.032343 0.035907 0.998832 + outer loop + vertex 1.06327 1.53743 2.6251 + vertex 1.06834 1.54219 2.62476 + vertex 1.06312 1.54218 2.62493 + endloop + endfacet + facet normal 0.0317623 0.0365252 0.998828 + outer loop + vertex 1.06832 1.53722 2.62495 + vertex 1.06834 1.54219 2.62476 + vertex 1.06327 1.53743 2.6251 + endloop + endfacet + facet normal 0.0315575 0.0313694 0.99901 + outer loop + vertex 1.06326 1.53278 2.62525 + vertex 1.06832 1.53722 2.62495 + vertex 1.06327 1.53743 2.6251 + endloop + endfacet + facet normal 0.031509 0.0313696 0.999011 + outer loop + vertex 1.06326 1.53278 2.62525 + vertex 1.06327 1.53743 2.6251 + vertex 1.05924 1.53407 2.62533 + endloop + endfacet + facet normal 0.0310157 0.0319869 0.999007 + outer loop + vertex 1.0683 1.53229 2.62511 + vertex 1.06832 1.53722 2.62495 + vertex 1.06326 1.53278 2.62525 + endloop + endfacet + facet normal 0.0304703 0.0263353 0.999189 + outer loop + vertex 1.06329 1.5279 2.62537 + vertex 1.0683 1.53229 2.62511 + vertex 1.06326 1.53278 2.62525 + endloop + endfacet + facet normal 0.0330309 0.0263531 0.999107 + outer loop + vertex 1.06329 1.5279 2.62537 + vertex 1.06326 1.53278 2.62525 + vertex 1.05815 1.52954 2.6255 + endloop + endfacet + facet normal 0.0302804 0.0177125 0.999384 + outer loop + vertex 1.05912 1.52414 2.62557 + vertex 1.06329 1.5279 2.62537 + vertex 1.05815 1.52954 2.6255 + endloop + endfacet + facet normal 0.0462825 0.0205879 0.998716 + outer loop + vertex 1.05912 1.52414 2.62557 + vertex 1.05815 1.52954 2.6255 + vertex 1.05497 1.52551 2.62573 + endloop + endfacet + facet normal 0.0440717 0.0138875 0.998932 + outer loop + vertex 1.05574 1.52062 2.62576 + vertex 1.05912 1.52414 2.62557 + vertex 1.05497 1.52551 2.62573 + endloop + endfacet + facet normal 0.0537393 0.0154141 0.998436 + outer loop + vertex 1.05497 1.52551 2.62573 + vertex 1.05185 1.52192 2.62595 + vertex 1.05574 1.52062 2.62576 + endloop + endfacet + facet normal 0.0519222 0.00994959 0.998602 + outer loop + vertex 1.05185 1.52192 2.62595 + vertex 1.05235 1.51695 2.62598 + vertex 1.05574 1.52062 2.62576 + endloop + endfacet + facet normal 0.0528662 0.00907421 0.99856 + outer loop + vertex 1.05574 1.52062 2.62576 + vertex 1.05235 1.51695 2.62598 + vertex 1.0561 1.51572 2.62579 + endloop + endfacet + facet normal 0.041978 0.00828993 0.999084 + outer loop + vertex 1.0561 1.51572 2.62579 + vertex 1.05957 1.51919 2.62562 + vertex 1.05574 1.52062 2.62576 + endloop + endfacet + facet normal 0.0420458 0.0082218 0.999082 + outer loop + vertex 1.05975 1.51428 2.62565 + vertex 1.05957 1.51919 2.62562 + vertex 1.0561 1.51572 2.62579 + endloop + endfacet + facet normal 0.0401194 0.00334684 0.999189 + outer loop + vertex 1.05622 1.51079 2.6258 + vertex 1.05975 1.51428 2.62565 + vertex 1.0561 1.51572 2.62579 + endloop + endfacet + facet normal 0.0518077 0.00364548 0.99865 + outer loop + vertex 1.0561 1.51572 2.62579 + vertex 1.05251 1.512 2.62599 + vertex 1.05622 1.51079 2.6258 + endloop + endfacet + facet normal 0.0504155 -0.00064216 0.998728 + outer loop + vertex 1.05251 1.512 2.62599 + vertex 1.05255 1.50701 2.62598 + vertex 1.05622 1.51079 2.6258 + endloop + endfacet + facet normal 0.0506507 -0.000871428 0.998716 + outer loop + vertex 1.05622 1.51079 2.6258 + vertex 1.05255 1.50701 2.62598 + vertex 1.05625 1.5058 2.6258 + endloop + endfacet + facet normal 0.0382963 -0.000927236 0.999266 + outer loop + vertex 1.05625 1.5058 2.6258 + vertex 1.05982 1.50932 2.62566 + vertex 1.05622 1.51079 2.6258 + endloop + endfacet + facet normal 0.0388365 -0.00147581 0.999244 + outer loop + vertex 1.05981 1.50434 2.62566 + vertex 1.05982 1.50932 2.62566 + vertex 1.05625 1.5058 2.6258 + endloop + endfacet + facet normal 0.0373427 -0.00511502 0.999289 + outer loop + vertex 1.05618 1.50081 2.62577 + vertex 1.05981 1.50434 2.62566 + vertex 1.05625 1.5058 2.6258 + endloop + endfacet + facet normal 0.0496907 -0.00527375 0.998751 + outer loop + vertex 1.05625 1.5058 2.6258 + vertex 1.05253 1.502 2.62596 + vertex 1.05618 1.50081 2.62577 + endloop + endfacet + facet normal 0.0485599 -0.00872931 0.998782 + outer loop + vertex 1.05253 1.502 2.62596 + vertex 1.05243 1.49702 2.62592 + vertex 1.05618 1.50081 2.62577 + endloop + endfacet + facet normal 0.049326 -0.00949124 0.998738 + outer loop + vertex 1.05618 1.50081 2.62577 + vertex 1.05243 1.49702 2.62592 + vertex 1.05596 1.49585 2.62574 + endloop + endfacet + facet normal 0.0365029 -0.00891507 0.999294 + outer loop + vertex 1.05596 1.49585 2.62574 + vertex 1.05971 1.49935 2.62563 + vertex 1.05618 1.50081 2.62577 + endloop + endfacet + facet normal 0.0385582 -0.0111247 0.999194 + outer loop + vertex 1.05935 1.49425 2.62559 + vertex 1.05971 1.49935 2.62563 + vertex 1.05596 1.49585 2.62574 + endloop + endfacet + facet normal 0.0375732 -0.013209 0.999207 + outer loop + vertex 1.0554 1.49101 2.62569 + vertex 1.05935 1.49425 2.62559 + vertex 1.05596 1.49585 2.62574 + endloop + endfacet + facet normal 0.0498665 -0.0146269 0.998649 + outer loop + vertex 1.05596 1.49585 2.62574 + vertex 1.05219 1.49219 2.62587 + vertex 1.0554 1.49101 2.62569 + endloop + endfacet + facet normal 0.0487661 -0.0176212 0.998655 + outer loop + vertex 1.05219 1.49219 2.62587 + vertex 1.05183 1.48781 2.62581 + vertex 1.0554 1.49101 2.62569 + endloop + endfacet + facet normal 0.0511477 -0.0202759 0.998485 + outer loop + vertex 1.0554 1.49101 2.62569 + vertex 1.05183 1.48781 2.62581 + vertex 1.05427 1.48705 2.62567 + endloop + endfacet + facet normal 0.0423954 -0.0177957 0.998942 + outer loop + vertex 1.05427 1.48705 2.62567 + vertex 1.05821 1.48838 2.62553 + vertex 1.0554 1.49101 2.62569 + endloop + endfacet + facet normal 0.0455273 -0.0270816 0.998596 + outer loop + vertex 1.05427 1.48705 2.62567 + vertex 1.05365 1.48292 2.62559 + vertex 1.05821 1.48838 2.62553 + endloop + endfacet + facet normal 0.0446791 -0.0263735 0.998653 + outer loop + vertex 1.05821 1.48838 2.62553 + vertex 1.05365 1.48292 2.62559 + vertex 1.05827 1.48279 2.62538 + endloop + endfacet + facet normal 0.026689 -0.0265803 0.99929 + outer loop + vertex 1.05827 1.48279 2.62538 + vertex 1.06325 1.4877 2.62538 + vertex 1.05821 1.48838 2.62553 + endloop + endfacet + facet normal 0.0273965 -0.0213754 0.999396 + outer loop + vertex 1.06325 1.4877 2.62538 + vertex 1.06344 1.49295 2.62548 + vertex 1.05821 1.48838 2.62553 + endloop + endfacet + facet normal 0.021336 -0.0144301 0.999668 + outer loop + vertex 1.05821 1.48838 2.62553 + vertex 1.06344 1.49295 2.62548 + vertex 1.05935 1.49425 2.62559 + endloop + endfacet + facet normal 0.0218242 -0.0128879 0.999679 + outer loop + vertex 1.06344 1.49295 2.62548 + vertex 1.0637 1.4981 2.62554 + vertex 1.05935 1.49425 2.62559 + endloop + endfacet + facet normal 0.024553 -0.0130224 0.999614 + outer loop + vertex 1.06344 1.49295 2.62548 + vertex 1.0684 1.49747 2.62542 + vertex 1.0637 1.4981 2.62554 + endloop + endfacet + facet normal 0.0252136 -0.00812987 0.999649 + outer loop + vertex 1.0684 1.49747 2.62542 + vertex 1.0684 1.50243 2.62546 + vertex 1.0637 1.4981 2.62554 + endloop + endfacet + facet normal 0.0240604 -0.0068746 0.999687 + outer loop + vertex 1.0637 1.4981 2.62554 + vertex 1.0684 1.50243 2.62546 + vertex 1.06378 1.50309 2.62558 + endloop + endfacet + facet normal 0.0199714 -0.00681137 0.999777 + outer loop + vertex 1.0637 1.4981 2.62554 + vertex 1.06378 1.50309 2.62558 + vertex 1.05971 1.49935 2.62563 + endloop + endfacet + facet normal 0.0185377 -0.00525174 0.999814 + outer loop + vertex 1.05971 1.49935 2.62563 + vertex 1.06378 1.50309 2.62558 + vertex 1.05981 1.50434 2.62566 + endloop + endfacet + facet normal 0.0197343 -0.00144315 0.999804 + outer loop + vertex 1.06378 1.50309 2.62558 + vertex 1.06379 1.50808 2.62558 + vertex 1.05981 1.50434 2.62566 + endloop + endfacet + facet normal 0.0245997 -0.00145696 0.999696 + outer loop + vertex 1.06378 1.50309 2.62558 + vertex 1.06838 1.5074 2.62547 + vertex 1.06379 1.50808 2.62558 + endloop + endfacet + facet normal 0.0252709 0.00308348 0.999676 + outer loop + vertex 1.06838 1.5074 2.62547 + vertex 1.06838 1.5124 2.62545 + vertex 1.06379 1.50808 2.62558 + endloop + endfacet + facet normal 0.0253653 0.0029835 0.999674 + outer loop + vertex 1.06379 1.50808 2.62558 + vertex 1.06838 1.5124 2.62545 + vertex 1.06377 1.51305 2.62557 + endloop + endfacet + facet normal 0.0211301 0.00296522 0.999772 + outer loop + vertex 1.06379 1.50808 2.62558 + vertex 1.06377 1.51305 2.62557 + vertex 1.05982 1.50932 2.62566 + endloop + endfacet + facet normal 0.0209496 0.0031565 0.999776 + outer loop + vertex 1.05982 1.50932 2.62566 + vertex 1.06377 1.51305 2.62557 + vertex 1.05975 1.51428 2.62565 + endloop + endfacet + facet normal 0.0225428 0.00839614 0.999711 + outer loop + vertex 1.06377 1.51305 2.62557 + vertex 1.06372 1.51801 2.62553 + vertex 1.05975 1.51428 2.62565 + endloop + endfacet + facet normal 0.0261663 0.00843165 0.999622 + outer loop + vertex 1.06377 1.51305 2.62557 + vertex 1.06838 1.51741 2.62541 + vertex 1.06372 1.51801 2.62553 + endloop + endfacet + facet normal 0.0270361 0.0151594 0.99952 + outer loop + vertex 1.06838 1.51741 2.62541 + vertex 1.06837 1.52239 2.62534 + vertex 1.06372 1.51801 2.62553 + endloop + endfacet + facet normal 0.0279902 0.0141455 0.999508 + outer loop + vertex 1.06372 1.51801 2.62553 + vertex 1.06837 1.52239 2.62534 + vertex 1.06357 1.52293 2.62546 + endloop + endfacet + facet normal 0.025203 0.0140599 0.999583 + outer loop + vertex 1.06372 1.51801 2.62553 + vertex 1.06357 1.52293 2.62546 + vertex 1.05957 1.51919 2.62562 + endloop + endfacet + facet normal 0.0268154 0.0123372 0.999564 + outer loop + vertex 1.05957 1.51919 2.62562 + vertex 1.06357 1.52293 2.62546 + vertex 1.05912 1.52414 2.62557 + endloop + endfacet + facet normal 0.028658 0.0201079 0.999387 + outer loop + vertex 1.06837 1.52239 2.62534 + vertex 1.06833 1.52734 2.62524 + vertex 1.06357 1.52293 2.62546 + endloop + endfacet + facet normal 0.0292599 0.0194581 0.999382 + outer loop + vertex 1.06357 1.52293 2.62546 + vertex 1.06833 1.52734 2.62524 + vertex 1.06329 1.5279 2.62537 + endloop + endfacet + facet normal 0.0757501 0.0204476 0.996917 + outer loop + vertex 1.06837 1.52239 2.62534 + vertex 1.07336 1.52742 2.62485 + vertex 1.06833 1.52734 2.62524 + endloop + endfacet + facet normal 0.0756864 0.0243323 0.996835 + outer loop + vertex 1.07336 1.52742 2.62485 + vertex 1.07339 1.53241 2.62473 + vertex 1.06833 1.52734 2.62524 + endloop + endfacet + facet normal 0.0730441 0.0269842 0.996964 + outer loop + vertex 1.06833 1.52734 2.62524 + vertex 1.07339 1.53241 2.62473 + vertex 1.0683 1.53229 2.62511 + endloop + endfacet + facet normal 0.0729563 0.0303948 0.996872 + outer loop + vertex 1.07339 1.53241 2.62473 + vertex 1.07342 1.53742 2.62457 + vertex 1.0683 1.53229 2.62511 + endloop + endfacet + facet normal 0.191746 0.0291324 0.981012 + outer loop + vertex 1.07339 1.53241 2.62473 + vertex 1.078 1.53772 2.62367 + vertex 1.07342 1.53742 2.62457 + endloop + endfacet + facet normal 0.192028 0.0249481 0.981072 + outer loop + vertex 1.078 1.53772 2.62367 + vertex 1.07802 1.54276 2.62354 + vertex 1.07342 1.53742 2.62457 + endloop + endfacet + facet normal 0.183276 0.0327813 0.982515 + outer loop + vertex 1.07342 1.53742 2.62457 + vertex 1.07802 1.54276 2.62354 + vertex 1.07346 1.54246 2.6244 + endloop + endfacet + facet normal 0.0714957 0.0340426 0.99686 + outer loop + vertex 1.07342 1.53742 2.62457 + vertex 1.07346 1.54246 2.6244 + vertex 1.06832 1.53722 2.62495 + endloop + endfacet + facet normal 0.183556 0.0286361 0.982592 + outer loop + vertex 1.07802 1.54276 2.62354 + vertex 1.07802 1.54779 2.62339 + vertex 1.07346 1.54246 2.6244 + endloop + endfacet + facet normal 0.176998 0.0344523 0.983608 + outer loop + vertex 1.07346 1.54246 2.6244 + vertex 1.07802 1.54779 2.62339 + vertex 1.0735 1.54753 2.62421 + endloop + endfacet + facet normal 0.1969 0.0244801 0.980118 + outer loop + vertex 1.07798 1.53271 2.6238 + vertex 1.078 1.53772 2.62367 + vertex 1.07339 1.53241 2.62473 + endloop + endfacet + facet normal 0.196986 0.0231786 0.980132 + outer loop + vertex 1.07336 1.52742 2.62485 + vertex 1.07798 1.53271 2.6238 + vertex 1.07339 1.53241 2.62473 + endloop + endfacet + facet normal 0.202681 0.0179926 0.97908 + outer loop + vertex 1.07796 1.5277 2.6239 + vertex 1.07798 1.53271 2.6238 + vertex 1.07336 1.52742 2.62485 + endloop + endfacet + facet normal 0.202635 0.0187228 0.979075 + outer loop + vertex 1.07334 1.52241 2.62495 + vertex 1.07796 1.5277 2.6239 + vertex 1.07336 1.52742 2.62485 + endloop + endfacet + facet normal 0.210389 0.0116304 0.977548 + outer loop + vertex 1.07796 1.5227 2.62396 + vertex 1.07796 1.5277 2.6239 + vertex 1.07334 1.52241 2.62495 + endloop + endfacet + facet normal 0.210499 0.00983763 0.977545 + outer loop + vertex 1.07331 1.5174 2.62501 + vertex 1.07796 1.5227 2.62396 + vertex 1.07334 1.52241 2.62495 + endloop + endfacet + facet normal 0.081103 0.0106263 0.996649 + outer loop + vertex 1.07331 1.5174 2.62501 + vertex 1.07334 1.52241 2.62495 + vertex 1.06838 1.51741 2.62541 + endloop + endfacet + facet normal 0.0810983 0.00840975 0.996671 + outer loop + vertex 1.06838 1.5124 2.62545 + vertex 1.07331 1.5174 2.62501 + vertex 1.06838 1.51741 2.62541 + endloop + endfacet + facet normal 0.0809391 0.0085683 0.996682 + outer loop + vertex 1.07332 1.51236 2.62505 + vertex 1.07331 1.5174 2.62501 + vertex 1.06838 1.5124 2.62545 + endloop + endfacet + facet normal 0.211923 0.00851428 0.977249 + outer loop + vertex 1.07332 1.51236 2.62505 + vertex 1.07796 1.51769 2.624 + vertex 1.07331 1.5174 2.62501 + endloop + endfacet + facet normal 0.214894 0.00579723 0.97662 + outer loop + vertex 1.07798 1.51268 2.62403 + vertex 1.07796 1.51769 2.624 + vertex 1.07332 1.51236 2.62505 + endloop + endfacet + facet normal 0.215086 0.00283793 0.976591 + outer loop + vertex 1.07334 1.50735 2.62506 + vertex 1.07798 1.51268 2.62403 + vertex 1.07332 1.51236 2.62505 + endloop + endfacet + facet normal 0.0816649 0.00238791 0.996657 + outer loop + vertex 1.07334 1.50735 2.62506 + vertex 1.07332 1.51236 2.62505 + vertex 1.06838 1.5074 2.62547 + endloop + endfacet + facet normal 0.081631 -0.00145915 0.996662 + outer loop + vertex 1.0684 1.50243 2.62546 + vertex 1.07334 1.50735 2.62506 + vertex 1.06838 1.5074 2.62547 + endloop + endfacet + facet normal 0.0798096 0.000376916 0.99681 + outer loop + vertex 1.07337 1.50238 2.62506 + vertex 1.07334 1.50735 2.62506 + vertex 1.0684 1.50243 2.62546 + endloop + endfacet + facet normal 0.21605 0.00143295 0.976381 + outer loop + vertex 1.07337 1.50238 2.62506 + vertex 1.07798 1.50766 2.62403 + vertex 1.07334 1.50735 2.62506 + endloop + endfacet + facet normal 0.214818 0.00256056 0.976651 + outer loop + vertex 1.07801 1.50266 2.62404 + vertex 1.07798 1.50766 2.62403 + vertex 1.07337 1.50238 2.62506 + endloop + endfacet + facet normal 0.21533 -0.00633843 0.976521 + outer loop + vertex 1.07341 1.49745 2.62502 + vertex 1.07801 1.50266 2.62404 + vertex 1.07337 1.50238 2.62506 + endloop + endfacet + facet normal 0.0792246 -0.00760165 0.996828 + outer loop + vertex 1.07341 1.49745 2.62502 + vertex 1.07337 1.50238 2.62506 + vertex 1.0684 1.49747 2.62542 + endloop + endfacet + facet normal 0.0791809 -0.0153723 0.996742 + outer loop + vertex 1.06838 1.49248 2.62534 + vertex 1.07341 1.49745 2.62502 + vertex 1.0684 1.49747 2.62542 + endloop + endfacet + facet normal 0.0784991 -0.0146772 0.996806 + outer loop + vertex 1.07346 1.49253 2.62494 + vertex 1.07341 1.49745 2.62502 + vertex 1.06838 1.49248 2.62534 + endloop + endfacet + facet normal 0.0785768 -0.024294 0.996612 + outer loop + vertex 1.0684 1.48749 2.62522 + vertex 1.07346 1.49253 2.62494 + vertex 1.06838 1.49248 2.62534 + endloop + endfacet + facet normal 0.0289517 -0.0245151 0.99928 + outer loop + vertex 1.0684 1.48749 2.62522 + vertex 1.06838 1.49248 2.62534 + vertex 1.06325 1.4877 2.62538 + endloop + endfacet + facet normal 0.0287892 -0.0284835 0.99918 + outer loop + vertex 1.06323 1.48254 2.62523 + vertex 1.0684 1.48749 2.62522 + vertex 1.06325 1.4877 2.62538 + endloop + endfacet + facet normal 0.0306856 -0.0304613 0.999065 + outer loop + vertex 1.06844 1.48253 2.62507 + vertex 1.0684 1.48749 2.62522 + vertex 1.06323 1.48254 2.62523 + endloop + endfacet + facet normal 0.0306762 -0.0329476 0.998986 + outer loop + vertex 1.06324 1.4775 2.62506 + vertex 1.06844 1.48253 2.62507 + vertex 1.06323 1.48254 2.62523 + endloop + endfacet + facet normal 0.0294412 -0.0329508 0.999023 + outer loop + vertex 1.06324 1.4775 2.62506 + vertex 1.06323 1.48254 2.62523 + vertex 1.05818 1.47759 2.62521 + endloop + endfacet + facet normal 0.0294026 -0.0350824 0.998952 + outer loop + vertex 1.05814 1.47253 2.62504 + vertex 1.06324 1.4775 2.62506 + vertex 1.05818 1.47759 2.62521 + endloop + endfacet + facet normal 0.0432384 -0.0352001 0.998444 + outer loop + vertex 1.05814 1.47253 2.62504 + vertex 1.05818 1.47759 2.62521 + vertex 1.05325 1.47265 2.62525 + endloop + endfacet + facet normal 0.0431851 -0.0372109 0.998374 + outer loop + vertex 1.05313 1.46758 2.62507 + vertex 1.05814 1.47253 2.62504 + vertex 1.05325 1.47265 2.62525 + endloop + endfacet + facet normal 0.0517431 -0.0374073 0.99796 + outer loop + vertex 1.05313 1.46758 2.62507 + vertex 1.05325 1.47265 2.62525 + vertex 1.0483 1.46777 2.62533 + endloop + endfacet + facet normal 0.0516473 -0.039639 0.997878 + outer loop + vertex 1.04816 1.46261 2.62513 + vertex 1.05313 1.46758 2.62507 + vertex 1.0483 1.46777 2.62533 + endloop + endfacet + facet normal 0.0519946 -0.0396478 0.99786 + outer loop + vertex 1.04816 1.46261 2.62513 + vertex 1.0483 1.46777 2.62533 + vertex 1.04339 1.46289 2.62539 + endloop + endfacet + facet normal 0.0518731 -0.0416807 0.997783 + outer loop + vertex 1.04323 1.45768 2.62518 + vertex 1.04816 1.46261 2.62513 + vertex 1.04339 1.46289 2.62539 + endloop + endfacet + facet normal 0.0508759 -0.0416519 0.997836 + outer loop + vertex 1.04323 1.45768 2.62518 + vertex 1.04339 1.46289 2.62539 + vertex 1.03869 1.45811 2.62543 + endloop + endfacet + facet normal 0.0507576 -0.0428575 0.997791 + outer loop + vertex 1.03837 1.45287 2.62522 + vertex 1.04323 1.45768 2.62518 + vertex 1.03869 1.45811 2.62543 + endloop + endfacet + facet normal 0.0547515 -0.0430947 0.99757 + outer loop + vertex 1.03837 1.45287 2.62522 + vertex 1.03869 1.45811 2.62543 + vertex 1.0338 1.45353 2.6255 + endloop + endfacet + facet normal 0.0548378 -0.0425047 0.99759 + outer loop + vertex 1.03382 1.44829 2.62528 + vertex 1.03837 1.45287 2.62522 + vertex 1.0338 1.45353 2.6255 + endloop + endfacet + facet normal 0.0671585 -0.0424167 0.99684 + outer loop + vertex 1.0338 1.45353 2.6255 + vertex 1.0301 1.44884 2.62555 + vertex 1.03382 1.44829 2.62528 + endloop + endfacet + facet normal 0.0675378 -0.0398957 0.996919 + outer loop + vertex 1.02961 1.44418 2.6254 + vertex 1.03382 1.44829 2.62528 + vertex 1.0301 1.44884 2.62555 + endloop + endfacet + facet normal 0.0971221 -0.0429669 0.994345 + outer loop + vertex 1.02961 1.44418 2.6254 + vertex 1.0301 1.44884 2.62555 + vertex 1.02639 1.44551 2.62577 + endloop + endfacet + facet normal 0.0977681 -0.0414064 0.994347 + outer loop + vertex 1.02559 1.44086 2.62565 + vertex 1.02961 1.44418 2.6254 + vertex 1.02639 1.44551 2.62577 + endloop + endfacet + facet normal 0.145329 -0.0494082 0.988149 + outer loop + vertex 1.02639 1.44551 2.62577 + vertex 1.02228 1.442 2.6262 + vertex 1.02559 1.44086 2.62565 + endloop + endfacet + facet normal 0.146015 -0.047412 0.988146 + outer loop + vertex 1.02228 1.442 2.6262 + vertex 1.02192 1.43753 2.62604 + vertex 1.02559 1.44086 2.62565 + endloop + endfacet + facet normal 0.156877 -0.0596488 0.985815 + outer loop + vertex 1.02559 1.44086 2.62565 + vertex 1.02192 1.43753 2.62604 + vertex 1.0247 1.43711 2.62557 + endloop + endfacet + facet normal 0.10615 -0.0477068 0.993205 + outer loop + vertex 1.0247 1.43711 2.62557 + vertex 1.02859 1.43859 2.62522 + vertex 1.02559 1.44086 2.62565 + endloop + endfacet + facet normal 0.107736 -0.0519658 0.992821 + outer loop + vertex 1.0247 1.43711 2.62557 + vertex 1.02501 1.43388 2.62537 + vertex 1.02859 1.43859 2.62522 + endloop + endfacet + facet normal 0.108362 -0.0524461 0.992727 + outer loop + vertex 1.02859 1.43859 2.62522 + vertex 1.02501 1.43388 2.62537 + vertex 1.02878 1.43332 2.62492 + endloop + endfacet + facet normal 0.0828675 -0.0535118 0.995123 + outer loop + vertex 1.02878 1.43332 2.62492 + vertex 1.03334 1.43787 2.62479 + vertex 1.02859 1.43859 2.62522 + endloop + endfacet + facet normal 0.0829507 -0.0529732 0.995145 + outer loop + vertex 1.03334 1.43787 2.62479 + vertex 1.03353 1.4431 2.62505 + vertex 1.02859 1.43859 2.62522 + endloop + endfacet + facet normal 0.0752584 -0.0445202 0.99617 + outer loop + vertex 1.02859 1.43859 2.62522 + vertex 1.03353 1.4431 2.62505 + vertex 1.02961 1.44418 2.6254 + endloop + endfacet + facet normal 0.0663328 -0.0524445 0.996418 + outer loop + vertex 1.03334 1.43787 2.62479 + vertex 1.03821 1.44259 2.62471 + vertex 1.03353 1.4431 2.62505 + endloop + endfacet + facet normal 0.066298 -0.0527577 0.996404 + outer loop + vertex 1.03821 1.44259 2.62471 + vertex 1.03827 1.44769 2.62498 + vertex 1.03353 1.4431 2.62505 + endloop + endfacet + facet normal 0.0600671 -0.0463165 0.997119 + outer loop + vertex 1.03353 1.4431 2.62505 + vertex 1.03827 1.44769 2.62498 + vertex 1.03382 1.44829 2.62528 + endloop + endfacet + facet normal 0.0583096 -0.0526932 0.996907 + outer loop + vertex 1.03821 1.44259 2.62471 + vertex 1.04318 1.4475 2.62468 + vertex 1.03827 1.44769 2.62498 + endloop + endfacet + facet normal 0.0583637 -0.0514396 0.996969 + outer loop + vertex 1.04318 1.4475 2.62468 + vertex 1.04316 1.45254 2.62494 + vertex 1.03827 1.44769 2.62498 + endloop + endfacet + facet normal 0.0544082 -0.0474415 0.997391 + outer loop + vertex 1.03827 1.44769 2.62498 + vertex 1.04316 1.45254 2.62494 + vertex 1.03837 1.45287 2.62522 + endloop + endfacet + facet normal 0.0563558 -0.0514533 0.997084 + outer loop + vertex 1.04318 1.4475 2.62468 + vertex 1.0482 1.45253 2.62466 + vertex 1.04316 1.45254 2.62494 + endloop + endfacet + facet normal 0.0563665 -0.0489196 0.997211 + outer loop + vertex 1.0482 1.45253 2.62466 + vertex 1.04815 1.45753 2.62491 + vertex 1.04316 1.45254 2.62494 + endloop + endfacet + facet normal 0.054054 -0.046608 0.99745 + outer loop + vertex 1.04316 1.45254 2.62494 + vertex 1.04815 1.45753 2.62491 + vertex 1.04323 1.45768 2.62518 + endloop + endfacet + facet normal 0.0547529 -0.0489407 0.9973 + outer loop + vertex 1.0482 1.45253 2.62466 + vertex 1.05321 1.45758 2.62463 + vertex 1.04815 1.45753 2.62491 + endloop + endfacet + facet normal 0.0547316 -0.0457239 0.997454 + outer loop + vertex 1.05321 1.45758 2.62463 + vertex 1.05314 1.46255 2.62486 + vertex 1.04815 1.45753 2.62491 + endloop + endfacet + facet normal 0.0529452 -0.0439454 0.99763 + outer loop + vertex 1.04815 1.45753 2.62491 + vertex 1.05314 1.46255 2.62486 + vertex 1.04816 1.46261 2.62513 + endloop + endfacet + facet normal 0.0463876 -0.0458521 0.997871 + outer loop + vertex 1.05321 1.45758 2.62463 + vertex 1.05822 1.46258 2.62463 + vertex 1.05314 1.46255 2.62486 + endloop + endfacet + facet normal 0.0463777 -0.0431008 0.997994 + outer loop + vertex 1.05822 1.46258 2.62463 + vertex 1.05816 1.46754 2.62485 + vertex 1.05314 1.46255 2.62486 + endloop + endfacet + facet normal 0.044319 -0.0410282 0.998175 + outer loop + vertex 1.05314 1.46255 2.62486 + vertex 1.05816 1.46754 2.62485 + vertex 1.05313 1.46758 2.62507 + endloop + endfacet + facet normal 0.0324418 -0.0432913 0.998536 + outer loop + vertex 1.05822 1.46258 2.62463 + vertex 1.06332 1.46756 2.62468 + vertex 1.05816 1.46754 2.62485 + endloop + endfacet + facet normal 0.0324326 -0.0403992 0.998657 + outer loop + vertex 1.06332 1.46756 2.62468 + vertex 1.06328 1.47253 2.62488 + vertex 1.05816 1.46754 2.62485 + endloop + endfacet + facet normal 0.0305607 -0.0384792 0.998792 + outer loop + vertex 1.05816 1.46754 2.62485 + vertex 1.06328 1.47253 2.62488 + vertex 1.05814 1.47253 2.62504 + endloop + endfacet + facet normal 0.0324833 -0.0403987 0.998655 + outer loop + vertex 1.06332 1.46756 2.62468 + vertex 1.0685 1.47261 2.62471 + vertex 1.06328 1.47253 2.62488 + endloop + endfacet + facet normal 0.0324346 -0.0371013 0.998785 + outer loop + vertex 1.0685 1.47261 2.62471 + vertex 1.06847 1.47757 2.6249 + vertex 1.06328 1.47253 2.62488 + endloop + endfacet + facet normal 0.0316232 -0.0362666 0.998842 + outer loop + vertex 1.06328 1.47253 2.62488 + vertex 1.06847 1.47757 2.6249 + vertex 1.06324 1.4775 2.62506 + endloop + endfacet + facet normal 0.0786344 -0.036745 0.996226 + outer loop + vertex 1.0685 1.47261 2.62471 + vertex 1.07353 1.47775 2.62451 + vertex 1.06847 1.47757 2.6249 + endloop + endfacet + facet normal 0.0785619 -0.0344283 0.996315 + outer loop + vertex 1.07353 1.47775 2.62451 + vertex 1.07353 1.4827 2.62468 + vertex 1.06847 1.47757 2.6249 + endloop + endfacet + facet normal 0.0775936 -0.0334681 0.996423 + outer loop + vertex 1.06847 1.47757 2.6249 + vertex 1.07353 1.4827 2.62468 + vertex 1.06844 1.48253 2.62507 + endloop + endfacet + facet normal 0.0773923 -0.0270076 0.996635 + outer loop + vertex 1.07353 1.4827 2.62468 + vertex 1.07349 1.48762 2.62481 + vertex 1.06844 1.48253 2.62507 + endloop + endfacet + facet normal 0.206949 -0.0254849 0.97802 + outer loop + vertex 1.07353 1.4827 2.62468 + vertex 1.07806 1.48781 2.62385 + vertex 1.07349 1.48762 2.62481 + endloop + endfacet + facet normal 0.206732 -0.0192456 0.978208 + outer loop + vertex 1.07806 1.48781 2.62385 + vertex 1.07805 1.49274 2.62395 + vertex 1.07349 1.48762 2.62481 + endloop + endfacet + facet normal 0.212599 -0.0246951 0.976827 + outer loop + vertex 1.07349 1.48762 2.62481 + vertex 1.07805 1.49274 2.62395 + vertex 1.07346 1.49253 2.62494 + endloop + endfacet + facet normal 0.212023 -0.0105001 0.977208 + outer loop + vertex 1.07805 1.49274 2.62395 + vertex 1.07802 1.49769 2.62401 + vertex 1.07346 1.49253 2.62494 + endloop + endfacet + facet normal 0.206851 -0.0253945 0.978043 + outer loop + vertex 1.07805 1.48286 2.62373 + vertex 1.07806 1.48781 2.62385 + vertex 1.07353 1.4827 2.62468 + endloop + endfacet + facet normal 0.207088 -0.0336864 0.977742 + outer loop + vertex 1.07353 1.47775 2.62451 + vertex 1.07805 1.48286 2.62373 + vertex 1.07353 1.4827 2.62468 + endloop + endfacet + facet normal 0.199764 -0.026953 0.979473 + outer loop + vertex 1.07804 1.47789 2.62359 + vertex 1.07805 1.48286 2.62373 + vertex 1.07353 1.47775 2.62451 + endloop + endfacet + facet normal 0.199934 -0.0338453 0.979225 + outer loop + vertex 1.07354 1.47276 2.62433 + vertex 1.07804 1.47789 2.62359 + vertex 1.07353 1.47775 2.62451 + endloop + endfacet + facet normal 0.19805 -0.0321249 0.979665 + outer loop + vertex 1.07801 1.47289 2.62343 + vertex 1.07804 1.47789 2.62359 + vertex 1.07354 1.47276 2.62433 + endloop + endfacet + facet normal 0.198187 -0.0388678 0.979393 + outer loop + vertex 1.07352 1.46776 2.62414 + vertex 1.07801 1.47289 2.62343 + vertex 1.07354 1.47276 2.62433 + endloop + endfacet + facet normal 0.0748925 -0.0392264 0.99642 + outer loop + vertex 1.07352 1.46776 2.62414 + vertex 1.07354 1.47276 2.62433 + vertex 1.06851 1.46763 2.62451 + endloop + endfacet + facet normal 0.075066 -0.0466084 0.996089 + outer loop + vertex 1.06851 1.46263 2.62428 + vertex 1.07352 1.46776 2.62414 + vertex 1.06851 1.46763 2.62451 + endloop + endfacet + facet normal 0.034249 -0.0466622 0.998323 + outer loop + vertex 1.06851 1.46263 2.62428 + vertex 1.06851 1.46763 2.62451 + vertex 1.06335 1.46259 2.62445 + endloop + endfacet + facet normal 0.0342693 -0.0505467 0.998134 + outer loop + vertex 1.06335 1.45761 2.6242 + vertex 1.06851 1.46263 2.62428 + vertex 1.06335 1.46259 2.62445 + endloop + endfacet + facet normal 0.0368847 -0.0505419 0.998041 + outer loop + vertex 1.06335 1.45761 2.6242 + vertex 1.06335 1.46259 2.62445 + vertex 1.05826 1.45762 2.62439 + endloop + endfacet + facet normal 0.0368757 -0.0523561 0.997947 + outer loop + vertex 1.05827 1.45265 2.62413 + vertex 1.06335 1.45761 2.6242 + vertex 1.05826 1.45762 2.62439 + endloop + endfacet + facet normal 0.0503893 -0.0523045 0.997359 + outer loop + vertex 1.05827 1.45265 2.62413 + vertex 1.05826 1.45762 2.62439 + vertex 1.05326 1.45263 2.62438 + endloop + endfacet + facet normal 0.050393 -0.0542023 0.997258 + outer loop + vertex 1.05328 1.44768 2.62411 + vertex 1.05827 1.45265 2.62413 + vertex 1.05326 1.45263 2.62438 + endloop + endfacet + facet normal 0.0572686 -0.0541504 0.996889 + outer loop + vertex 1.05328 1.44768 2.62411 + vertex 1.05326 1.45263 2.62438 + vertex 1.04826 1.44758 2.62439 + endloop + endfacet + facet normal 0.0573128 -0.0569419 0.996731 + outer loop + vertex 1.0483 1.44264 2.62411 + vertex 1.05328 1.44768 2.62411 + vertex 1.04826 1.44758 2.62439 + endloop + endfacet + facet normal 0.0590436 -0.0569208 0.996631 + outer loop + vertex 1.0483 1.44264 2.62411 + vertex 1.04826 1.44758 2.62439 + vertex 1.04323 1.44253 2.6244 + endloop + endfacet + facet normal 0.0590931 -0.0594404 0.996481 + outer loop + vertex 1.04329 1.43758 2.6241 + vertex 1.0483 1.44264 2.62411 + vertex 1.04323 1.44253 2.6244 + endloop + endfacet + facet normal 0.0635168 -0.0593781 0.996213 + outer loop + vertex 1.04329 1.43758 2.6241 + vertex 1.04323 1.44253 2.6244 + vertex 1.03821 1.43755 2.62442 + endloop + endfacet + facet normal 0.0635191 -0.0605564 0.996142 + outer loop + vertex 1.03824 1.43254 2.62412 + vertex 1.04329 1.43758 2.6241 + vertex 1.03821 1.43755 2.62442 + endloop + endfacet + facet normal 0.0739848 -0.060465 0.995425 + outer loop + vertex 1.03824 1.43254 2.62412 + vertex 1.03821 1.43755 2.62442 + vertex 1.03329 1.43272 2.6245 + endloop + endfacet + facet normal 0.0740208 -0.0595845 0.995475 + outer loop + vertex 1.03321 1.42762 2.6242 + vertex 1.03824 1.43254 2.62412 + vertex 1.03329 1.43272 2.6245 + endloop + endfacet + facet normal 0.0766164 -0.0622388 0.995116 + outer loop + vertex 1.03826 1.42756 2.6238 + vertex 1.03824 1.43254 2.62412 + vertex 1.03321 1.42762 2.6242 + endloop + endfacet + facet normal 0.0766429 -0.0605367 0.995219 + outer loop + vertex 1.03318 1.42255 2.62389 + vertex 1.03826 1.42756 2.6238 + vertex 1.03321 1.42762 2.6242 + endloop + endfacet + facet normal 0.0798549 -0.0637973 0.994763 + outer loop + vertex 1.03828 1.42259 2.62348 + vertex 1.03826 1.42756 2.6238 + vertex 1.03318 1.42255 2.62389 + endloop + endfacet + facet normal 0.0798472 -0.0619313 0.994881 + outer loop + vertex 1.03319 1.41753 2.62358 + vertex 1.03828 1.42259 2.62348 + vertex 1.03318 1.42255 2.62389 + endloop + endfacet + facet normal 0.0841912 -0.066311 0.994241 + outer loop + vertex 1.03829 1.41762 2.62315 + vertex 1.03828 1.42259 2.62348 + vertex 1.03319 1.41753 2.62358 + endloop + endfacet + facet normal 0.0841757 -0.0651295 0.99432 + outer loop + vertex 1.0332 1.41254 2.62325 + vertex 1.03829 1.41762 2.62315 + vertex 1.03319 1.41753 2.62358 + endloop + endfacet + facet normal 0.105965 -0.0649537 0.992246 + outer loop + vertex 1.0332 1.41254 2.62325 + vertex 1.03319 1.41753 2.62358 + vertex 1.02824 1.41268 2.62379 + endloop + endfacet + facet normal 0.106056 -0.0623214 0.992405 + outer loop + vertex 1.02823 1.40768 2.62348 + vertex 1.0332 1.41254 2.62325 + vertex 1.02824 1.41268 2.62379 + endloop + endfacet + facet normal 0.138913 -0.0621297 0.988354 + outer loop + vertex 1.02823 1.40768 2.62348 + vertex 1.02824 1.41268 2.62379 + vertex 1.02361 1.40824 2.62416 + endloop + endfacet + facet normal 0.139618 -0.0566472 0.988584 + outer loop + vertex 1.02355 1.40324 2.62388 + vertex 1.02823 1.40768 2.62348 + vertex 1.02361 1.40824 2.62416 + endloop + endfacet + facet normal 0.195267 -0.0567994 0.979104 + outer loop + vertex 1.02355 1.40324 2.62388 + vertex 1.02361 1.40824 2.62416 + vertex 1.01941 1.40434 2.62477 + endloop + endfacet + facet normal 0.197331 -0.0489931 0.979112 + outer loop + vertex 1.01926 1.39932 2.62455 + vertex 1.02355 1.40324 2.62388 + vertex 1.01941 1.40434 2.62477 + endloop + endfacet + facet normal 0.205807 -0.0586554 0.976833 + outer loop + vertex 1.02345 1.39819 2.6236 + vertex 1.02355 1.40324 2.62388 + vertex 1.01926 1.39932 2.62455 + endloop + endfacet + facet normal 0.208538 -0.0485404 0.976809 + outer loop + vertex 1.01896 1.39419 2.62436 + vertex 1.02345 1.39819 2.6236 + vertex 1.01926 1.39932 2.62455 + endloop + endfacet + facet normal 0.216358 -0.0577418 0.974605 + outer loop + vertex 1.02324 1.39298 2.62334 + vertex 1.02345 1.39819 2.6236 + vertex 1.01896 1.39419 2.62436 + endloop + endfacet + facet normal 0.22081 -0.0419222 0.974415 + outer loop + vertex 1.01818 1.38848 2.62429 + vertex 1.02324 1.39298 2.62334 + vertex 1.01896 1.39419 2.62436 + endloop + endfacet + facet normal 0.233539 -0.0570386 0.970673 + outer loop + vertex 1.02318 1.38774 2.62304 + vertex 1.02324 1.39298 2.62334 + vertex 1.01818 1.38848 2.62429 + endloop + endfacet + facet normal 0.234099 -0.0533811 0.970746 + outer loop + vertex 1.01869 1.38319 2.62388 + vertex 1.02318 1.38774 2.62304 + vertex 1.01818 1.38848 2.62429 + endloop + endfacet + facet normal 0.237818 -0.0572632 0.96962 + outer loop + vertex 1.02329 1.38268 2.62272 + vertex 1.02318 1.38774 2.62304 + vertex 1.01869 1.38319 2.62388 + endloop + endfacet + facet normal 0.239099 -0.0464627 0.969883 + outer loop + vertex 1.01879 1.3782 2.62361 + vertex 1.02329 1.38268 2.62272 + vertex 1.01869 1.38319 2.62388 + endloop + endfacet + facet normal 0.248753 -0.0567664 0.966902 + outer loop + vertex 1.02336 1.37772 2.62241 + vertex 1.02329 1.38268 2.62272 + vertex 1.01879 1.3782 2.62361 + endloop + endfacet + facet normal 0.250038 -0.0452914 0.967176 + outer loop + vertex 1.01883 1.37326 2.62337 + vertex 1.02336 1.37772 2.62241 + vertex 1.01879 1.3782 2.62361 + endloop + endfacet + facet normal 0.266047 -0.0626756 0.96192 + outer loop + vertex 1.02326 1.37273 2.62211 + vertex 1.02336 1.37772 2.62241 + vertex 1.01883 1.37326 2.62337 + endloop + endfacet + facet normal 0.26786 -0.0482345 0.96225 + outer loop + vertex 1.01886 1.36831 2.62311 + vertex 1.02326 1.37273 2.62211 + vertex 1.01883 1.37326 2.62337 + endloop + endfacet + facet normal 0.282897 -0.0643869 0.956987 + outer loop + vertex 1.02341 1.36763 2.62172 + vertex 1.02326 1.37273 2.62211 + vertex 1.01886 1.36831 2.62311 + endloop + endfacet + facet normal 0.284912 -0.0512594 0.957182 + outer loop + vertex 1.01872 1.36331 2.62289 + vertex 1.02341 1.36763 2.62172 + vertex 1.01886 1.36831 2.62311 + endloop + endfacet + facet normal 0.309186 -0.080236 0.947611 + outer loop + vertex 1.02237 1.36219 2.6216 + vertex 1.02341 1.36763 2.62172 + vertex 1.01872 1.36331 2.62289 + endloop + endfacet + facet normal 0.316495 -0.0558207 0.94695 + outer loop + vertex 1.0185 1.35839 2.62267 + vertex 1.02237 1.36219 2.6216 + vertex 1.01872 1.36331 2.62289 + endloop + endfacet + facet normal 0.338595 -0.0810024 0.937439 + outer loop + vertex 1.02194 1.35771 2.62137 + vertex 1.02237 1.36219 2.6216 + vertex 1.0185 1.35839 2.62267 + endloop + endfacet + facet normal 0.342871 -0.059307 0.937509 + outer loop + vertex 1.02194 1.35771 2.62137 + vertex 1.0185 1.35839 2.62267 + vertex 1.01871 1.35331 2.62227 + endloop + endfacet + facet normal 0.354161 -0.0685552 0.932668 + outer loop + vertex 1.02226 1.35455 2.62102 + vertex 1.02194 1.35771 2.62137 + vertex 1.01871 1.35331 2.62227 + endloop + endfacet + facet normal 0.353737 -0.0670743 0.932937 + outer loop + vertex 1.02226 1.35455 2.62102 + vertex 1.01871 1.35331 2.62227 + vertex 1.02149 1.35078 2.62104 + endloop + endfacet + facet normal 0.259072 -0.0475233 0.964688 + outer loop + vertex 1.02494 1.35393 2.62027 + vertex 1.02226 1.35455 2.62102 + vertex 1.02149 1.35078 2.62104 + endloop + endfacet + facet normal 0.275065 -0.0664447 0.959127 + outer loop + vertex 1.02474 1.34939 2.62001 + vertex 1.02494 1.35393 2.62027 + vertex 1.02149 1.35078 2.62104 + endloop + endfacet + facet normal 0.280162 -0.0540176 0.958432 + outer loop + vertex 1.02099 1.34596 2.62091 + vertex 1.02474 1.34939 2.62001 + vertex 1.02149 1.35078 2.62104 + endloop + endfacet + facet normal 0.374243 -0.0627911 0.925202 + outer loop + vertex 1.02149 1.35078 2.62104 + vertex 1.01785 1.34778 2.62231 + vertex 1.02099 1.34596 2.62091 + endloop + endfacet + facet normal 0.381071 -0.0495425 0.923218 + outer loop + vertex 1.01785 1.34778 2.62231 + vertex 1.01744 1.34273 2.62221 + vertex 1.02099 1.34596 2.62091 + endloop + endfacet + facet normal 0.392022 -0.0637887 0.917741 + outer loop + vertex 1.02099 1.34596 2.62091 + vertex 1.01744 1.34273 2.62221 + vertex 1.02061 1.34095 2.62073 + endloop + endfacet + facet normal 0.296205 -0.0578441 0.953371 + outer loop + vertex 1.02061 1.34095 2.62073 + vertex 1.02446 1.34442 2.61974 + vertex 1.02099 1.34596 2.62091 + endloop + endfacet + facet normal 0.305556 -0.0692704 0.949651 + outer loop + vertex 1.02408 1.33922 2.61949 + vertex 1.02446 1.34442 2.61974 + vertex 1.02061 1.34095 2.62073 + endloop + endfacet + facet normal 0.310686 -0.0583255 0.948721 + outer loop + vertex 1.02017 1.33602 2.62057 + vertex 1.02408 1.33922 2.61949 + vertex 1.02061 1.34095 2.62073 + endloop + endfacet + facet normal 0.410745 -0.0661158 0.90935 + outer loop + vertex 1.02061 1.34095 2.62073 + vertex 1.01717 1.33779 2.62205 + vertex 1.02017 1.33602 2.62057 + endloop + endfacet + facet normal 0.416013 -0.0557658 0.907647 + outer loop + vertex 1.01717 1.33779 2.62205 + vertex 1.01702 1.33319 2.62184 + vertex 1.02017 1.33602 2.62057 + endloop + endfacet + facet normal 0.430725 -0.0758386 0.899291 + outer loop + vertex 1.02017 1.33602 2.62057 + vertex 1.01702 1.33319 2.62184 + vertex 1.01945 1.33213 2.62058 + endloop + endfacet + facet normal 0.325828 -0.0564657 0.943741 + outer loop + vertex 1.01945 1.33213 2.62058 + vertex 1.02327 1.33344 2.61934 + vertex 1.02017 1.33602 2.62057 + endloop + endfacet + facet normal 0.324979 -0.0535434 0.944204 + outer loop + vertex 1.01945 1.33213 2.62058 + vertex 1.01996 1.32884 2.62022 + vertex 1.02327 1.33344 2.61934 + endloop + endfacet + facet normal 0.326671 -0.0548874 0.943543 + outer loop + vertex 1.02327 1.33344 2.61934 + vertex 1.01996 1.32884 2.62022 + vertex 1.02377 1.3282 2.61887 + endloop + endfacet + facet normal 0.329425 -0.0381117 0.943412 + outer loop + vertex 1.01997 1.32437 2.62004 + vertex 1.02377 1.3282 2.61887 + vertex 1.01996 1.32884 2.62022 + endloop + endfacet + facet normal 0.342656 -0.0529215 0.937969 + outer loop + vertex 1.02386 1.32328 2.61855 + vertex 1.02377 1.3282 2.61887 + vertex 1.01997 1.32437 2.62004 + endloop + endfacet + facet normal 0.346232 -0.0392636 0.937327 + outer loop + vertex 1.01992 1.31957 2.61986 + vertex 1.02386 1.32328 2.61855 + vertex 1.01997 1.32437 2.62004 + endloop + endfacet + facet normal 0.413976 -0.03592 0.909579 + outer loop + vertex 1.01945 1.33213 2.62058 + vertex 1.01741 1.3298 2.62142 + vertex 1.01996 1.32884 2.62022 + endloop + endfacet + facet normal 0.436705 -0.0600959 0.897595 + outer loop + vertex 1.01945 1.33213 2.62058 + vertex 1.01702 1.33319 2.62184 + vertex 1.01741 1.3298 2.62142 + endloop + endfacet + facet normal 0.317441 -0.0675514 0.945869 + outer loop + vertex 1.02327 1.33344 2.61934 + vertex 1.02408 1.33922 2.61949 + vertex 1.02017 1.33602 2.62057 + endloop + endfacet + facet normal 0.398646 -0.0502667 0.915726 + outer loop + vertex 1.01744 1.34273 2.62221 + vertex 1.01717 1.33779 2.62205 + vertex 1.02061 1.34095 2.62073 + endloop + endfacet + facet normal 0.291918 -0.0680149 0.954022 + outer loop + vertex 1.02446 1.34442 2.61974 + vertex 1.02474 1.34939 2.62001 + vertex 1.02099 1.34596 2.62091 + endloop + endfacet + facet normal 0.366259 -0.0514791 0.929088 + outer loop + vertex 1.01871 1.35331 2.62227 + vertex 1.01785 1.34778 2.62231 + vertex 1.02149 1.35078 2.62104 + endloop + endfacet + facet normal 0.168089 -0.0570142 0.984122 + outer loop + vertex 1.02318 1.38774 2.62304 + vertex 1.02819 1.39257 2.62247 + vertex 1.02324 1.39298 2.62334 + endloop + endfacet + facet normal 0.167274 -0.0659934 0.983699 + outer loop + vertex 1.02819 1.39257 2.62247 + vertex 1.0282 1.39763 2.62281 + vertex 1.02324 1.39298 2.62334 + endloop + endfacet + facet normal 0.123608 -0.0662908 0.990114 + outer loop + vertex 1.02819 1.39257 2.62247 + vertex 1.03328 1.39754 2.62217 + vertex 1.0282 1.39763 2.62281 + endloop + endfacet + facet normal 0.123455 -0.0725249 0.989696 + outer loop + vertex 1.03328 1.39754 2.62217 + vertex 1.03324 1.40253 2.62254 + vertex 1.0282 1.39763 2.62281 + endloop + endfacet + facet normal 0.118191 -0.0670624 0.990724 + outer loop + vertex 1.0282 1.39763 2.62281 + vertex 1.03324 1.40253 2.62254 + vertex 1.02823 1.40268 2.62314 + endloop + endfacet + facet normal 0.156792 -0.0668728 0.985365 + outer loop + vertex 1.0282 1.39763 2.62281 + vertex 1.02823 1.40268 2.62314 + vertex 1.02345 1.39819 2.6236 + endloop + endfacet + facet normal 0.118022 -0.0716207 0.990425 + outer loop + vertex 1.03324 1.40253 2.62254 + vertex 1.03321 1.40755 2.6229 + vertex 1.02823 1.40268 2.62314 + endloop + endfacet + facet normal 0.112269 -0.0656732 0.991505 + outer loop + vertex 1.02823 1.40268 2.62314 + vertex 1.03321 1.40755 2.6229 + vertex 1.02823 1.40768 2.62348 + endloop + endfacet + facet normal 0.0948288 -0.0730002 0.992813 + outer loop + vertex 1.03328 1.39754 2.62217 + vertex 1.03836 1.4026 2.62205 + vertex 1.03324 1.40253 2.62254 + endloop + endfacet + facet normal 0.0948373 -0.0745504 0.992697 + outer loop + vertex 1.03836 1.4026 2.62205 + vertex 1.0383 1.40759 2.62243 + vertex 1.03324 1.40253 2.62254 + endloop + endfacet + facet normal 0.0922581 -0.0719622 0.993131 + outer loop + vertex 1.03324 1.40253 2.62254 + vertex 1.0383 1.40759 2.62243 + vertex 1.03321 1.40755 2.6229 + endloop + endfacet + facet normal 0.0922596 -0.0725259 0.99309 + outer loop + vertex 1.0383 1.40759 2.62243 + vertex 1.03829 1.41262 2.6228 + vertex 1.03321 1.40755 2.6229 + endloop + endfacet + facet normal 0.0886097 -0.0688644 0.993683 + outer loop + vertex 1.03321 1.40755 2.6229 + vertex 1.03829 1.41262 2.6228 + vertex 1.0332 1.41254 2.62325 + endloop + endfacet + facet normal 0.0747936 -0.0726836 0.994547 + outer loop + vertex 1.0383 1.40759 2.62243 + vertex 1.04333 1.41269 2.62243 + vertex 1.03829 1.41262 2.6228 + endloop + endfacet + facet normal 0.0747887 -0.0720572 0.994593 + outer loop + vertex 1.04333 1.41269 2.62243 + vertex 1.04334 1.41773 2.62279 + vertex 1.03829 1.41262 2.6228 + endloop + endfacet + facet normal 0.0723852 -0.0696796 0.99494 + outer loop + vertex 1.03829 1.41262 2.6228 + vertex 1.04334 1.41773 2.62279 + vertex 1.03829 1.41762 2.62315 + endloop + endfacet + facet normal 0.072377 -0.0691924 0.994974 + outer loop + vertex 1.04334 1.41773 2.62279 + vertex 1.04336 1.42273 2.62314 + vertex 1.03829 1.41762 2.62315 + endloop + endfacet + facet normal 0.064934 -0.0691971 0.995487 + outer loop + vertex 1.04334 1.41773 2.62279 + vertex 1.04832 1.42278 2.62282 + vertex 1.04336 1.42273 2.62314 + endloop + endfacet + facet normal 0.0649319 -0.0687474 0.995519 + outer loop + vertex 1.04832 1.42278 2.62282 + vertex 1.04835 1.42778 2.62316 + vertex 1.04336 1.42273 2.62314 + endloop + endfacet + facet normal 0.0628301 -0.066671 0.995795 + outer loop + vertex 1.04336 1.42273 2.62314 + vertex 1.04835 1.42778 2.62316 + vertex 1.04336 1.42769 2.62347 + endloop + endfacet + facet normal 0.0695859 -0.0666338 0.995348 + outer loop + vertex 1.04336 1.42273 2.62314 + vertex 1.04336 1.42769 2.62347 + vertex 1.03828 1.42259 2.62348 + endloop + endfacet + facet normal 0.0628238 -0.0661938 0.995827 + outer loop + vertex 1.04835 1.42778 2.62316 + vertex 1.04835 1.43274 2.62349 + vertex 1.04336 1.42769 2.62347 + endloop + endfacet + facet normal 0.0607791 -0.0641735 0.996086 + outer loop + vertex 1.04336 1.42769 2.62347 + vertex 1.04835 1.43274 2.62349 + vertex 1.04333 1.43263 2.62379 + endloop + endfacet + facet normal 0.0668621 -0.0641137 0.9957 + outer loop + vertex 1.04336 1.42769 2.62347 + vertex 1.04333 1.43263 2.62379 + vertex 1.03826 1.42756 2.6238 + endloop + endfacet + facet normal 0.0607609 -0.0631704 0.996151 + outer loop + vertex 1.04835 1.43274 2.62349 + vertex 1.04833 1.4377 2.62381 + vertex 1.04333 1.43263 2.62379 + endloop + endfacet + facet normal 0.0597749 -0.0621959 0.996272 + outer loop + vertex 1.04333 1.43263 2.62379 + vertex 1.04833 1.4377 2.62381 + vertex 1.04329 1.43758 2.6241 + endloop + endfacet + facet normal 0.0594307 -0.0631805 0.996231 + outer loop + vertex 1.04835 1.43274 2.62349 + vertex 1.05329 1.43773 2.62351 + vertex 1.04833 1.4377 2.62381 + endloop + endfacet + facet normal 0.0594245 -0.0614708 0.996338 + outer loop + vertex 1.05329 1.43773 2.62351 + vertex 1.05329 1.44271 2.62382 + vertex 1.04833 1.4377 2.62381 + endloop + endfacet + facet normal 0.0580264 -0.0600897 0.996505 + outer loop + vertex 1.04833 1.4377 2.62381 + vertex 1.05329 1.44271 2.62382 + vertex 1.0483 1.44264 2.62411 + endloop + endfacet + facet normal 0.0547134 -0.0614886 0.996607 + outer loop + vertex 1.05329 1.43773 2.62351 + vertex 1.05825 1.44267 2.62355 + vertex 1.05329 1.44271 2.62382 + endloop + endfacet + facet normal 0.0547273 -0.0601891 0.996686 + outer loop + vertex 1.05825 1.44267 2.62355 + vertex 1.05826 1.44767 2.62385 + vertex 1.05329 1.44271 2.62382 + endloop + endfacet + facet normal 0.0521937 -0.0576483 0.996972 + outer loop + vertex 1.05329 1.44271 2.62382 + vertex 1.05826 1.44767 2.62385 + vertex 1.05328 1.44768 2.62411 + endloop + endfacet + facet normal 0.0422577 -0.0602072 0.997291 + outer loop + vertex 1.05825 1.44267 2.62355 + vertex 1.06333 1.44761 2.62363 + vertex 1.05826 1.44767 2.62385 + endloop + endfacet + facet normal 0.0422723 -0.0591337 0.997355 + outer loop + vertex 1.06333 1.44761 2.62363 + vertex 1.06334 1.45261 2.62392 + vertex 1.05826 1.44767 2.62385 + endloop + endfacet + facet normal 0.039239 -0.0560238 0.997658 + outer loop + vertex 1.05826 1.44767 2.62385 + vertex 1.06334 1.45261 2.62392 + vertex 1.05827 1.45265 2.62413 + endloop + endfacet + facet normal 0.0369425 -0.0591384 0.997566 + outer loop + vertex 1.06333 1.44761 2.62363 + vertex 1.06849 1.45263 2.62373 + vertex 1.06334 1.45261 2.62392 + endloop + endfacet + facet normal 0.0369393 -0.0557391 0.997762 + outer loop + vertex 1.06849 1.45263 2.62373 + vertex 1.06849 1.45763 2.62401 + vertex 1.06334 1.45261 2.62392 + endloop + endfacet + facet normal 0.0360115 -0.0547874 0.997848 + outer loop + vertex 1.06334 1.45261 2.62392 + vertex 1.06849 1.45763 2.62401 + vertex 1.06335 1.45761 2.6242 + endloop + endfacet + facet normal 0.0689217 -0.0556719 0.996067 + outer loop + vertex 1.06849 1.45263 2.62373 + vertex 1.0735 1.45775 2.62367 + vertex 1.06849 1.45763 2.62401 + endloop + endfacet + facet normal 0.0687489 -0.0478152 0.996487 + outer loop + vertex 1.0735 1.45775 2.62367 + vertex 1.0735 1.46276 2.62391 + vertex 1.06849 1.45763 2.62401 + endloop + endfacet + facet normal 0.0733653 -0.0523369 0.995931 + outer loop + vertex 1.06849 1.45763 2.62401 + vertex 1.0735 1.46276 2.62391 + vertex 1.06851 1.46263 2.62428 + endloop + endfacet + facet normal 0.180229 -0.0472588 0.982489 + outer loop + vertex 1.0735 1.45775 2.62367 + vertex 1.07798 1.46289 2.6231 + vertex 1.0735 1.46276 2.62391 + endloop + endfacet + facet normal 0.180006 -0.0367087 0.98298 + outer loop + vertex 1.07798 1.46289 2.6231 + vertex 1.078 1.46789 2.62328 + vertex 1.0735 1.46276 2.62391 + endloop + endfacet + facet normal 0.188676 -0.0445357 0.981029 + outer loop + vertex 1.0735 1.46276 2.62391 + vertex 1.078 1.46789 2.62328 + vertex 1.07352 1.46776 2.62414 + endloop + endfacet + facet normal 0.168307 -0.0365737 0.985056 + outer loop + vertex 1.07798 1.4579 2.62291 + vertex 1.07798 1.46289 2.6231 + vertex 1.0735 1.45775 2.62367 + endloop + endfacet + facet normal 0.168663 -0.0513085 0.984337 + outer loop + vertex 1.07351 1.45277 2.62341 + vertex 1.07798 1.4579 2.62291 + vertex 1.0735 1.45775 2.62367 + endloop + endfacet + facet normal 0.156931 -0.0408558 0.986764 + outer loop + vertex 1.07798 1.45292 2.62271 + vertex 1.07798 1.4579 2.62291 + vertex 1.07351 1.45277 2.62341 + endloop + endfacet + facet normal 0.157356 -0.0578689 0.985845 + outer loop + vertex 1.07351 1.44778 2.62312 + vertex 1.07798 1.45292 2.62271 + vertex 1.07351 1.45277 2.62341 + endloop + endfacet + facet normal 0.063581 -0.0585122 0.99626 + outer loop + vertex 1.07351 1.44778 2.62312 + vertex 1.07351 1.45277 2.62341 + vertex 1.0685 1.44764 2.62343 + endloop + endfacet + facet normal 0.0637607 -0.0658139 0.995793 + outer loop + vertex 1.0685 1.44264 2.6231 + vertex 1.07351 1.44778 2.62312 + vertex 1.0685 1.44764 2.62343 + endloop + endfacet + facet normal 0.0402593 -0.0659204 0.997012 + outer loop + vertex 1.0685 1.44264 2.6231 + vertex 1.0685 1.44764 2.62343 + vertex 1.06333 1.44262 2.62331 + endloop + endfacet + facet normal 0.0402648 -0.0688461 0.996814 + outer loop + vertex 1.06332 1.43761 2.62296 + vertex 1.0685 1.44264 2.6231 + vertex 1.06333 1.44262 2.62331 + endloop + endfacet + facet normal 0.0497468 -0.0688318 0.996387 + outer loop + vertex 1.06332 1.43761 2.62296 + vertex 1.06333 1.44262 2.62331 + vertex 1.05825 1.43768 2.62322 + endloop + endfacet + facet normal 0.0497453 -0.0689268 0.996381 + outer loop + vertex 1.05822 1.43267 2.62288 + vertex 1.06332 1.43761 2.62296 + vertex 1.05825 1.43768 2.62322 + endloop + endfacet + facet normal 0.0614697 -0.0689363 0.995725 + outer loop + vertex 1.05822 1.43267 2.62288 + vertex 1.05825 1.43768 2.62322 + vertex 1.05328 1.43275 2.62319 + endloop + endfacet + facet normal 0.061476 -0.0686233 0.995747 + outer loop + vertex 1.05325 1.42774 2.62284 + vertex 1.05822 1.43267 2.62288 + vertex 1.05328 1.43275 2.62319 + endloop + endfacet + facet normal 0.0641094 -0.0686286 0.99558 + outer loop + vertex 1.05325 1.42774 2.62284 + vertex 1.05328 1.43275 2.62319 + vertex 1.04835 1.42778 2.62316 + endloop + endfacet + facet normal 0.0644635 -0.0716371 0.995345 + outer loop + vertex 1.05819 1.42764 2.62252 + vertex 1.05822 1.43267 2.62288 + vertex 1.05325 1.42774 2.62284 + endloop + endfacet + facet normal 0.0644827 -0.0708976 0.995397 + outer loop + vertex 1.05321 1.42271 2.62249 + vertex 1.05819 1.42764 2.62252 + vertex 1.05325 1.42774 2.62284 + endloop + endfacet + facet normal 0.0662838 -0.0709039 0.995278 + outer loop + vertex 1.05321 1.42271 2.62249 + vertex 1.05325 1.42774 2.62284 + vertex 1.04832 1.42278 2.62282 + endloop + endfacet + facet normal 0.0662826 -0.0709679 0.995274 + outer loop + vertex 1.04828 1.41773 2.62246 + vertex 1.05321 1.42271 2.62249 + vertex 1.04832 1.42278 2.62282 + endloop + endfacet + facet normal 0.0678111 -0.07248 0.995062 + outer loop + vertex 1.05322 1.41768 2.62212 + vertex 1.05321 1.42271 2.62249 + vertex 1.04828 1.41773 2.62246 + endloop + endfacet + facet normal 0.0678026 -0.0729888 0.995025 + outer loop + vertex 1.04831 1.4127 2.62209 + vertex 1.05322 1.41768 2.62212 + vertex 1.04828 1.41773 2.62246 + endloop + endfacet + facet normal 0.0676572 -0.0729902 0.995035 + outer loop + vertex 1.04831 1.4127 2.62209 + vertex 1.04828 1.41773 2.62246 + vertex 1.04333 1.41269 2.62243 + endloop + endfacet + facet normal 0.0676539 -0.0740188 0.994959 + outer loop + vertex 1.04337 1.40766 2.62205 + vertex 1.04831 1.4127 2.62209 + vertex 1.04333 1.41269 2.62243 + endloop + endfacet + facet normal 0.0679539 -0.074313 0.994917 + outer loop + vertex 1.04842 1.40778 2.62172 + vertex 1.04831 1.4127 2.62209 + vertex 1.04337 1.40766 2.62205 + endloop + endfacet + facet normal 0.0679738 -0.0753948 0.994834 + outer loop + vertex 1.04346 1.40277 2.62167 + vertex 1.04842 1.40778 2.62172 + vertex 1.04337 1.40766 2.62205 + endloop + endfacet + facet normal 0.0763677 -0.0751944 0.99424 + outer loop + vertex 1.04346 1.40277 2.62167 + vertex 1.04337 1.40766 2.62205 + vertex 1.03836 1.4026 2.62205 + endloop + endfacet + facet normal 0.0763729 -0.0753751 0.994226 + outer loop + vertex 1.03842 1.39774 2.62168 + vertex 1.04346 1.40277 2.62167 + vertex 1.03836 1.4026 2.62205 + endloop + endfacet + facet normal 0.0766204 -0.0756226 0.994188 + outer loop + vertex 1.0435 1.39809 2.62131 + vertex 1.04346 1.40277 2.62167 + vertex 1.03842 1.39774 2.62168 + endloop + endfacet + facet normal 0.0765974 -0.0752557 0.994218 + outer loop + vertex 1.03841 1.39309 2.62133 + vertex 1.0435 1.39809 2.62131 + vertex 1.03842 1.39774 2.62168 + endloop + endfacet + facet normal 0.0989519 -0.0751524 0.99225 + outer loop + vertex 1.03841 1.39309 2.62133 + vertex 1.03842 1.39774 2.62168 + vertex 1.03332 1.39268 2.62181 + endloop + endfacet + facet normal 0.0988323 -0.0734831 0.992387 + outer loop + vertex 1.03332 1.388 2.62146 + vertex 1.03841 1.39309 2.62133 + vertex 1.03332 1.39268 2.62181 + endloop + endfacet + facet normal 0.135087 -0.0731826 0.988127 + outer loop + vertex 1.03332 1.388 2.62146 + vertex 1.03332 1.39268 2.62181 + vertex 1.02821 1.38761 2.62213 + endloop + endfacet + facet normal 0.134731 -0.0677563 0.988563 + outer loop + vertex 1.02827 1.38277 2.62179 + vertex 1.03332 1.388 2.62146 + vertex 1.02821 1.38761 2.62213 + endloop + endfacet + facet normal 0.184472 -0.0665851 0.98058 + outer loop + vertex 1.02827 1.38277 2.62179 + vertex 1.02821 1.38761 2.62213 + vertex 1.02329 1.38268 2.62272 + endloop + endfacet + facet normal 0.184411 -0.0585044 0.981106 + outer loop + vertex 1.02336 1.37772 2.62241 + vertex 1.02827 1.38277 2.62179 + vertex 1.02329 1.38268 2.62272 + endloop + endfacet + facet normal 0.196936 -0.0710815 0.977836 + outer loop + vertex 1.02841 1.37777 2.6214 + vertex 1.02827 1.38277 2.62179 + vertex 1.02336 1.37772 2.62241 + endloop + endfacet + facet normal 0.196959 -0.0623499 0.978427 + outer loop + vertex 1.02326 1.37273 2.62211 + vertex 1.02841 1.37777 2.6214 + vertex 1.02336 1.37772 2.62241 + endloop + endfacet + facet normal 0.219619 -0.0864528 0.971748 + outer loop + vertex 1.02723 1.37255 2.6212 + vertex 1.02841 1.37777 2.6214 + vertex 1.02326 1.37273 2.62211 + endloop + endfacet + facet normal 0.220777 -0.0674804 0.972987 + outer loop + vertex 1.02723 1.37255 2.6212 + vertex 1.02326 1.37273 2.62211 + vertex 1.02341 1.36763 2.62172 + endloop + endfacet + facet normal 0.232041 -0.0765741 0.969687 + outer loop + vertex 1.02739 1.36934 2.62091 + vertex 1.02723 1.37255 2.6212 + vertex 1.02341 1.36763 2.62172 + endloop + endfacet + facet normal 0.232878 -0.0786993 0.969316 + outer loop + vertex 1.02739 1.36934 2.62091 + vertex 1.02341 1.36763 2.62172 + vertex 1.02636 1.36551 2.62084 + endloop + endfacet + facet normal 0.167621 -0.0614236 0.983936 + outer loop + vertex 1.0301 1.36886 2.62042 + vertex 1.02739 1.36934 2.62091 + vertex 1.02636 1.36551 2.62084 + endloop + endfacet + facet normal 0.178044 -0.0733751 0.981283 + outer loop + vertex 1.02956 1.36421 2.62017 + vertex 1.0301 1.36886 2.62042 + vertex 1.02636 1.36551 2.62084 + endloop + endfacet + facet normal 0.179815 -0.0690055 0.981277 + outer loop + vertex 1.0255 1.36088 2.62068 + vertex 1.02956 1.36421 2.62017 + vertex 1.02636 1.36551 2.62084 + endloop + endfacet + facet normal 0.251723 -0.0817726 0.964339 + outer loop + vertex 1.02636 1.36551 2.62084 + vertex 1.02237 1.36219 2.6216 + vertex 1.0255 1.36088 2.62068 + endloop + endfacet + facet normal 0.254805 -0.0742628 0.964137 + outer loop + vertex 1.02237 1.36219 2.6216 + vertex 1.02194 1.35771 2.62137 + vertex 1.0255 1.36088 2.62068 + endloop + endfacet + facet normal 0.270701 -0.0934994 0.958112 + outer loop + vertex 1.0255 1.36088 2.62068 + vertex 1.02194 1.35771 2.62137 + vertex 1.02456 1.35712 2.62058 + endloop + endfacet + facet normal 0.189419 -0.0736734 0.979128 + outer loop + vertex 1.02456 1.35712 2.62058 + vertex 1.02849 1.35862 2.61993 + vertex 1.0255 1.36088 2.62068 + endloop + endfacet + facet normal 0.188715 -0.0716975 0.979411 + outer loop + vertex 1.02456 1.35712 2.62058 + vertex 1.02494 1.35393 2.62027 + vertex 1.02849 1.35862 2.61993 + endloop + endfacet + facet normal 0.192681 -0.0747746 0.978408 + outer loop + vertex 1.02849 1.35862 2.61993 + vertex 1.02494 1.35393 2.62027 + vertex 1.02876 1.35341 2.61948 + endloop + endfacet + facet normal 0.194241 -0.0639906 0.978864 + outer loop + vertex 1.02474 1.34939 2.62001 + vertex 1.02876 1.35341 2.61948 + vertex 1.02494 1.35393 2.62027 + endloop + endfacet + facet normal 0.205567 -0.0757238 0.975709 + outer loop + vertex 1.02868 1.34838 2.6191 + vertex 1.02876 1.35341 2.61948 + vertex 1.02474 1.34939 2.62001 + endloop + endfacet + facet normal 0.208494 -0.0644432 0.975898 + outer loop + vertex 1.02446 1.34442 2.61974 + vertex 1.02868 1.34838 2.6191 + vertex 1.02474 1.34939 2.62001 + endloop + endfacet + facet normal 0.219682 -0.0768859 0.972537 + outer loop + vertex 1.02851 1.34328 2.61874 + vertex 1.02868 1.34838 2.6191 + vertex 1.02446 1.34442 2.61974 + endloop + endfacet + facet normal 0.22324 -0.0643806 0.972635 + outer loop + vertex 1.02408 1.33922 2.61949 + vertex 1.02851 1.34328 2.61874 + vertex 1.02446 1.34442 2.61974 + endloop + endfacet + facet normal 0.230743 -0.0730172 0.970271 + outer loop + vertex 1.02829 1.33804 2.61839 + vertex 1.02851 1.34328 2.61874 + vertex 1.02408 1.33922 2.61949 + endloop + endfacet + facet normal 0.235316 -0.0567289 0.970262 + outer loop + vertex 1.02327 1.33344 2.61934 + vertex 1.02829 1.33804 2.61839 + vertex 1.02408 1.33922 2.61949 + endloop + endfacet + facet normal 0.247787 -0.071172 0.966197 + outer loop + vertex 1.02826 1.33282 2.61802 + vertex 1.02829 1.33804 2.61839 + vertex 1.02327 1.33344 2.61934 + endloop + endfacet + facet normal 0.248692 -0.0643929 0.96644 + outer loop + vertex 1.02377 1.3282 2.61887 + vertex 1.02826 1.33282 2.61802 + vertex 1.02327 1.33344 2.61934 + endloop + endfacet + facet normal 0.254309 -0.0701968 0.964572 + outer loop + vertex 1.0284 1.32776 2.61761 + vertex 1.02826 1.33282 2.61802 + vertex 1.02377 1.3282 2.61887 + endloop + endfacet + facet normal 0.255785 -0.0562602 0.965095 + outer loop + vertex 1.02386 1.32328 2.61855 + vertex 1.0284 1.32776 2.61761 + vertex 1.02377 1.3282 2.61887 + endloop + endfacet + facet normal 0.272317 -0.0742189 0.959341 + outer loop + vertex 1.02831 1.32275 2.61725 + vertex 1.0284 1.32776 2.61761 + vertex 1.02386 1.32328 2.61855 + endloop + endfacet + facet normal 0.274603 -0.0564333 0.9599 + outer loop + vertex 1.02388 1.31837 2.61826 + vertex 1.02831 1.32275 2.61725 + vertex 1.02386 1.32328 2.61855 + endloop + endfacet + facet normal 0.293483 -0.0771644 0.952845 + outer loop + vertex 1.02843 1.31768 2.6168 + vertex 1.02831 1.32275 2.61725 + vertex 1.02388 1.31837 2.61826 + endloop + endfacet + facet normal 0.296209 -0.0598711 0.953245 + outer loop + vertex 1.02371 1.31342 2.618 + vertex 1.02843 1.31768 2.6168 + vertex 1.02388 1.31837 2.61826 + endloop + endfacet + facet normal 0.32484 -0.0950179 0.940984 + outer loop + vertex 1.02733 1.31231 2.61664 + vertex 1.02843 1.31768 2.6168 + vertex 1.02371 1.31342 2.618 + endloop + endfacet + facet normal 0.332971 -0.0678421 0.940493 + outer loop + vertex 1.02345 1.30854 2.61774 + vertex 1.02733 1.31231 2.61664 + vertex 1.02371 1.31342 2.618 + endloop + endfacet + facet normal 0.356821 -0.0956053 0.929268 + outer loop + vertex 1.02685 1.30791 2.61637 + vertex 1.02733 1.31231 2.61664 + vertex 1.02345 1.30854 2.61774 + endloop + endfacet + facet normal 0.362271 -0.0672481 0.929644 + outer loop + vertex 1.02685 1.30791 2.61637 + vertex 1.02345 1.30854 2.61774 + vertex 1.02364 1.30351 2.61731 + endloop + endfacet + facet normal 0.381103 -0.0828417 0.920813 + outer loop + vertex 1.02713 1.30478 2.61597 + vertex 1.02685 1.30791 2.61637 + vertex 1.02364 1.30351 2.61731 + endloop + endfacet + facet normal 0.378124 -0.0724528 0.922916 + outer loop + vertex 1.02713 1.30478 2.61597 + vertex 1.02364 1.30351 2.61731 + vertex 1.02637 1.30097 2.61599 + endloop + endfacet + facet normal 0.282363 -0.0530794 0.957838 + outer loop + vertex 1.02981 1.30414 2.61515 + vertex 1.02713 1.30478 2.61597 + vertex 1.02637 1.30097 2.61599 + endloop + endfacet + facet normal 0.300114 -0.0741401 0.951018 + outer loop + vertex 1.02962 1.29952 2.61485 + vertex 1.02981 1.30414 2.61515 + vertex 1.02637 1.30097 2.61599 + endloop + endfacet + facet normal 0.306126 -0.0598821 0.950106 + outer loop + vertex 1.02589 1.29606 2.61583 + vertex 1.02962 1.29952 2.61485 + vertex 1.02637 1.30097 2.61599 + endloop + endfacet + facet normal 0.400972 -0.0680208 0.913561 + outer loop + vertex 1.02637 1.30097 2.61599 + vertex 1.02279 1.29793 2.61733 + vertex 1.02589 1.29606 2.61583 + endloop + endfacet + facet normal 0.40932 -0.0520879 0.910903 + outer loop + vertex 1.02279 1.29793 2.61733 + vertex 1.0224 1.2928 2.61722 + vertex 1.02589 1.29606 2.61583 + endloop + endfacet + facet normal 0.419849 -0.0657994 0.905206 + outer loop + vertex 1.02589 1.29606 2.61583 + vertex 1.0224 1.2928 2.61722 + vertex 1.02554 1.29099 2.61563 + endloop + endfacet + facet normal 0.324606 -0.0608155 0.943892 + outer loop + vertex 1.02554 1.29099 2.61563 + vertex 1.02937 1.29446 2.61453 + vertex 1.02589 1.29606 2.61583 + endloop + endfacet + facet normal 0.333476 -0.0718221 0.940019 + outer loop + vertex 1.02904 1.28926 2.61425 + vertex 1.02937 1.29446 2.61453 + vertex 1.02554 1.29099 2.61563 + endloop + endfacet + facet normal 0.338771 -0.0602671 0.938937 + outer loop + vertex 1.02511 1.28606 2.61546 + vertex 1.02904 1.28926 2.61425 + vertex 1.02554 1.29099 2.61563 + endloop + endfacet + facet normal 0.437844 -0.0674281 0.896519 + outer loop + vertex 1.02554 1.29099 2.61563 + vertex 1.02214 1.28783 2.61705 + vertex 1.02511 1.28606 2.61546 + endloop + endfacet + facet normal 0.442581 -0.0580065 0.89485 + outer loop + vertex 1.02214 1.28783 2.61705 + vertex 1.02198 1.28324 2.61683 + vertex 1.02511 1.28606 2.61546 + endloop + endfacet + facet normal 0.45738 -0.0788465 0.885769 + outer loop + vertex 1.02511 1.28606 2.61546 + vertex 1.02198 1.28324 2.61683 + vertex 1.02439 1.28218 2.61549 + endloop + endfacet + facet normal 0.350694 -0.0586147 0.934654 + outer loop + vertex 1.02439 1.28218 2.61549 + vertex 1.02825 1.28354 2.61413 + vertex 1.02511 1.28606 2.61546 + endloop + endfacet + facet normal 0.347952 -0.0492758 0.936216 + outer loop + vertex 1.02439 1.28218 2.61549 + vertex 1.02492 1.27895 2.61513 + vertex 1.02825 1.28354 2.61413 + endloop + endfacet + facet normal 0.351132 -0.0518684 0.934888 + outer loop + vertex 1.02825 1.28354 2.61413 + vertex 1.02492 1.27895 2.61513 + vertex 1.02873 1.27841 2.61366 + endloop + endfacet + facet normal 0.354725 -0.0260887 0.934607 + outer loop + vertex 1.02499 1.27454 2.61497 + vertex 1.02873 1.27841 2.61366 + vertex 1.02492 1.27895 2.61513 + endloop + endfacet + facet normal 0.365609 -0.0381884 0.929985 + outer loop + vertex 1.02889 1.27351 2.6134 + vertex 1.02873 1.27841 2.61366 + vertex 1.02499 1.27454 2.61497 + endloop + endfacet + facet normal 0.435449 -0.0307787 0.899687 + outer loop + vertex 1.02439 1.28218 2.61549 + vertex 1.02236 1.27987 2.6164 + vertex 1.02492 1.27895 2.61513 + endloop + endfacet + facet normal 0.463726 -0.0618882 0.883815 + outer loop + vertex 1.02439 1.28218 2.61549 + vertex 1.02198 1.28324 2.61683 + vertex 1.02236 1.27987 2.6164 + endloop + endfacet + facet normal 0.344131 -0.0677721 0.936473 + outer loop + vertex 1.02825 1.28354 2.61413 + vertex 1.02904 1.28926 2.61425 + vertex 1.02511 1.28606 2.61546 + endloop + endfacet + facet normal 0.426498 -0.0523296 0.902974 + outer loop + vertex 1.0224 1.2928 2.61722 + vertex 1.02214 1.28783 2.61705 + vertex 1.02554 1.29099 2.61563 + endloop + endfacet + facet normal 0.318592 -0.0747985 0.944936 + outer loop + vertex 1.02937 1.29446 2.61453 + vertex 1.02962 1.29952 2.61485 + vertex 1.02589 1.29606 2.61583 + endloop + endfacet + facet normal 0.391932 -0.0552498 0.918334 + outer loop + vertex 1.02364 1.30351 2.61731 + vertex 1.02279 1.29793 2.61733 + vertex 1.02637 1.30097 2.61599 + endloop + endfacet + facet normal 0.205438 -0.0743083 0.975845 + outer loop + vertex 1.02831 1.32275 2.61725 + vertex 1.03355 1.32768 2.61652 + vertex 1.0284 1.32776 2.61761 + endloop + endfacet + facet normal 0.205099 -0.0852667 0.97502 + outer loop + vertex 1.03355 1.32768 2.61652 + vertex 1.03334 1.33276 2.61701 + vertex 1.0284 1.32776 2.61761 + endloop + endfacet + facet normal 0.156631 -0.0880401 0.983725 + outer loop + vertex 1.03853 1.33324 2.61623 + vertex 1.03334 1.33276 2.61701 + vertex 1.03355 1.32768 2.61652 + endloop + endfacet + facet normal 0.174999 -0.104776 0.978978 + outer loop + vertex 1.03785 1.32942 2.61594 + vertex 1.03853 1.33324 2.61623 + vertex 1.03355 1.32768 2.61652 + endloop + endfacet + facet normal 0.173227 -0.100118 0.97978 + outer loop + vertex 1.03785 1.32942 2.61594 + vertex 1.03355 1.32768 2.61652 + vertex 1.03629 1.32565 2.61583 + endloop + endfacet + facet normal 0.132458 -0.0835519 0.987661 + outer loop + vertex 1.04025 1.32862 2.61555 + vertex 1.03785 1.32942 2.61594 + vertex 1.03629 1.32565 2.61583 + endloop + endfacet + facet normal 0.139299 -0.092838 0.985889 + outer loop + vertex 1.03891 1.32356 2.61526 + vertex 1.04025 1.32862 2.61555 + vertex 1.03629 1.32565 2.61583 + endloop + endfacet + facet normal 0.142893 -0.0883098 0.98579 + outer loop + vertex 1.03501 1.32202 2.61569 + vertex 1.03891 1.32356 2.61526 + vertex 1.03629 1.32565 2.61583 + endloop + endfacet + facet normal 0.191156 -0.105017 0.975926 + outer loop + vertex 1.03629 1.32565 2.61583 + vertex 1.03232 1.3225 2.61627 + vertex 1.03501 1.32202 2.61569 + endloop + endfacet + facet normal 0.192926 -0.0959908 0.976507 + outer loop + vertex 1.03501 1.32202 2.61569 + vertex 1.03232 1.3225 2.61627 + vertex 1.03244 1.31935 2.61594 + endloop + endfacet + facet normal 0.183156 -0.0863397 0.979285 + outer loop + vertex 1.03501 1.32202 2.61569 + vertex 1.03244 1.31935 2.61594 + vertex 1.03515 1.3189 2.61539 + endloop + endfacet + facet normal 0.184655 -0.077827 0.979717 + outer loop + vertex 1.03515 1.3189 2.61539 + vertex 1.03244 1.31935 2.61594 + vertex 1.03136 1.31561 2.61584 + endloop + endfacet + facet normal 0.196615 -0.0920625 0.976149 + outer loop + vertex 1.03454 1.31435 2.61508 + vertex 1.03515 1.3189 2.61539 + vertex 1.03136 1.31561 2.61584 + endloop + endfacet + facet normal 0.19911 -0.0857732 0.976216 + outer loop + vertex 1.03044 1.31106 2.61563 + vertex 1.03454 1.31435 2.61508 + vertex 1.03136 1.31561 2.61584 + endloop + endfacet + facet normal 0.271143 -0.0995272 0.95738 + outer loop + vertex 1.03136 1.31561 2.61584 + vertex 1.02733 1.31231 2.61664 + vertex 1.03044 1.31106 2.61563 + endloop + endfacet + facet normal 0.275552 -0.0884851 0.957205 + outer loop + vertex 1.02733 1.31231 2.61664 + vertex 1.02685 1.30791 2.61637 + vertex 1.03044 1.31106 2.61563 + endloop + endfacet + facet normal 0.293869 -0.111227 0.949352 + outer loop + vertex 1.03044 1.31106 2.61563 + vertex 1.02685 1.30791 2.61637 + vertex 1.02945 1.30735 2.6155 + endloop + endfacet + facet normal 0.209811 -0.0896319 0.973625 + outer loop + vertex 1.02945 1.30735 2.6155 + vertex 1.03341 1.3088 2.61478 + vertex 1.03044 1.31106 2.61563 + endloop + endfacet + facet normal 0.207948 -0.0840993 0.974518 + outer loop + vertex 1.02945 1.30735 2.6155 + vertex 1.02981 1.30414 2.61515 + vertex 1.03341 1.3088 2.61478 + endloop + endfacet + facet normal 0.212561 -0.0877624 0.973199 + outer loop + vertex 1.03341 1.3088 2.61478 + vertex 1.02981 1.30414 2.61515 + vertex 1.03367 1.30354 2.61425 + endloop + endfacet + facet normal 0.168181 -0.090811 0.981564 + outer loop + vertex 1.03367 1.30354 2.61425 + vertex 1.03824 1.30806 2.61389 + vertex 1.03341 1.3088 2.61478 + endloop + endfacet + facet normal 0.167339 -0.0959137 0.981223 + outer loop + vertex 1.03824 1.30806 2.61389 + vertex 1.03847 1.31334 2.61436 + vertex 1.03341 1.3088 2.61478 + endloop + endfacet + facet normal 0.158228 -0.0855255 0.983692 + outer loop + vertex 1.03341 1.3088 2.61478 + vertex 1.03847 1.31334 2.61436 + vertex 1.03454 1.31435 2.61508 + endloop + endfacet + facet normal 0.155909 -0.0942791 0.983262 + outer loop + vertex 1.03847 1.31334 2.61436 + vertex 1.03887 1.31849 2.61479 + vertex 1.03454 1.31435 2.61508 + endloop + endfacet + facet normal 0.128717 -0.0925471 0.987353 + outer loop + vertex 1.03847 1.31334 2.61436 + vertex 1.04327 1.31797 2.61417 + vertex 1.03887 1.31849 2.61479 + endloop + endfacet + facet normal 0.127958 -0.0984457 0.986882 + outer loop + vertex 1.04327 1.31797 2.61417 + vertex 1.04344 1.3231 2.61466 + vertex 1.03887 1.31849 2.61479 + endloop + endfacet + facet normal 0.122054 -0.092551 0.988199 + outer loop + vertex 1.03887 1.31849 2.61479 + vertex 1.04344 1.3231 2.61466 + vertex 1.03891 1.32356 2.61526 + endloop + endfacet + facet normal 0.121659 -0.0960874 0.98791 + outer loop + vertex 1.04344 1.3231 2.61466 + vertex 1.04385 1.32818 2.6151 + vertex 1.03891 1.32356 2.61526 + endloop + endfacet + facet normal 0.106125 -0.0949861 0.989806 + outer loop + vertex 1.04344 1.3231 2.61466 + vertex 1.04829 1.32792 2.6146 + vertex 1.04385 1.32818 2.6151 + endloop + endfacet + facet normal 0.105909 -0.0981996 0.989515 + outer loop + vertex 1.04829 1.32792 2.6146 + vertex 1.04861 1.33298 2.61507 + vertex 1.04385 1.32818 2.6151 + endloop + endfacet + facet normal 0.0989482 -0.0912974 0.990896 + outer loop + vertex 1.04385 1.32818 2.6151 + vertex 1.04861 1.33298 2.61507 + vertex 1.04426 1.33302 2.61551 + endloop + endfacet + facet normal 0.098874 -0.0955027 0.990507 + outer loop + vertex 1.04903 1.33793 2.61551 + vertex 1.04426 1.33302 2.61551 + vertex 1.04861 1.33298 2.61507 + endloop + endfacet + facet normal 0.0957942 -0.0952671 0.990832 + outer loop + vertex 1.04861 1.33298 2.61507 + vertex 1.05358 1.33796 2.61507 + vertex 1.04903 1.33793 2.61551 + endloop + endfacet + facet normal 0.0957803 -0.0995908 0.990408 + outer loop + vertex 1.05408 1.34294 2.61552 + vertex 1.04903 1.33793 2.61551 + vertex 1.05358 1.33796 2.61507 + endloop + endfacet + facet normal 0.096037 -0.0996141 0.990381 + outer loop + vertex 1.05358 1.33796 2.61507 + vertex 1.05862 1.34294 2.61508 + vertex 1.05408 1.34294 2.61552 + endloop + endfacet + facet normal 0.0960124 -0.102467 0.990092 + outer loop + vertex 1.05907 1.34777 2.61554 + vertex 1.05408 1.34294 2.61552 + vertex 1.05862 1.34294 2.61508 + endloop + endfacet + facet normal 0.0915209 -0.1021 0.990555 + outer loop + vertex 1.05862 1.34294 2.61508 + vertex 1.06354 1.34786 2.61513 + vertex 1.05907 1.34777 2.61554 + endloop + endfacet + facet normal 0.091488 -0.0988985 0.990883 + outer loop + vertex 1.06341 1.35185 2.61555 + vertex 1.05907 1.34777 2.61554 + vertex 1.06354 1.34786 2.61513 + endloop + endfacet + facet normal 0.0803069 -0.0993754 0.991804 + outer loop + vertex 1.06354 1.34786 2.61513 + vertex 1.06831 1.35329 2.61529 + vertex 1.06341 1.35185 2.61555 + endloop + endfacet + facet normal 0.07659 -0.086444 0.993308 + outer loop + vertex 1.06341 1.35185 2.61555 + vertex 1.06831 1.35329 2.61529 + vertex 1.066 1.35577 2.61569 + endloop + endfacet + facet normal 0.0891204 -0.0946934 0.991509 + outer loop + vertex 1.06256 1.35423 2.61585 + vertex 1.06341 1.35185 2.61555 + vertex 1.066 1.35577 2.61569 + endloop + endfacet + facet normal 0.0884276 -0.0931192 0.99172 + outer loop + vertex 1.066 1.35577 2.61569 + vertex 1.0638 1.35809 2.6161 + vertex 1.06256 1.35423 2.61585 + endloop + endfacet + facet normal 0.0908725 -0.0938865 0.991427 + outer loop + vertex 1.06256 1.35423 2.61585 + vertex 1.0638 1.35809 2.6161 + vertex 1.05866 1.35339 2.61613 + endloop + endfacet + facet normal 0.0908023 -0.0935486 0.991465 + outer loop + vertex 1.06256 1.35423 2.61585 + vertex 1.05866 1.35339 2.61613 + vertex 1.06037 1.35151 2.61579 + endloop + endfacet + facet normal 0.0900891 -0.0941984 0.991469 + outer loop + vertex 1.06037 1.35151 2.61579 + vertex 1.05866 1.35339 2.61613 + vertex 1.05753 1.34971 2.61588 + endloop + endfacet + facet normal 0.0936575 -0.0998701 0.990583 + outer loop + vertex 1.06037 1.35151 2.61579 + vertex 1.05753 1.34971 2.61588 + vertex 1.05907 1.34777 2.61554 + endloop + endfacet + facet normal 0.0934254 -0.100055 0.990586 + outer loop + vertex 1.05907 1.34777 2.61554 + vertex 1.05753 1.34971 2.61588 + vertex 1.05541 1.34683 2.61579 + endloop + endfacet + facet normal 0.0933403 -0.0997113 0.990629 + outer loop + vertex 1.05541 1.34683 2.61579 + vertex 1.05408 1.34294 2.61552 + vertex 1.05907 1.34777 2.61554 + endloop + endfacet + facet normal 0.0912608 -0.0990182 0.990892 + outer loop + vertex 1.05541 1.34683 2.61579 + vertex 1.05243 1.34479 2.61586 + vertex 1.05408 1.34294 2.61552 + endloop + endfacet + facet normal 0.0920135 -0.098349 0.990889 + outer loop + vertex 1.05408 1.34294 2.61552 + vertex 1.05243 1.34479 2.61586 + vertex 1.0503 1.34183 2.61576 + endloop + endfacet + facet normal 0.0920011 -0.0983401 0.990891 + outer loop + vertex 1.05243 1.34479 2.61586 + vertex 1.04849 1.34352 2.6161 + vertex 1.0503 1.34183 2.61576 + endloop + endfacet + facet normal 0.0915759 -0.0969929 0.991063 + outer loop + vertex 1.05243 1.34479 2.61586 + vertex 1.05359 1.34854 2.61612 + vertex 1.04849 1.34352 2.6161 + endloop + endfacet + facet normal 0.0897735 -0.0951657 0.991405 + outer loop + vertex 1.05359 1.34854 2.61612 + vertex 1.04853 1.34813 2.61654 + vertex 1.04849 1.34352 2.6161 + endloop + endfacet + facet normal 0.099817 -0.0951509 0.990446 + outer loop + vertex 1.04849 1.34352 2.6161 + vertex 1.04853 1.34813 2.61654 + vertex 1.04346 1.34305 2.61656 + endloop + endfacet + facet normal 0.0998505 -0.0955494 0.990404 + outer loop + vertex 1.04849 1.34352 2.6161 + vertex 1.04346 1.34305 2.61656 + vertex 1.04345 1.33843 2.61612 + endloop + endfacet + facet normal 0.104679 -0.100327 0.989433 + outer loop + vertex 1.04734 1.33973 2.61584 + vertex 1.04849 1.34352 2.6161 + vertex 1.04345 1.33843 2.61612 + endloop + endfacet + facet normal 0.104925 -0.101083 0.98933 + outer loop + vertex 1.04734 1.33973 2.61584 + vertex 1.04345 1.33843 2.61612 + vertex 1.0453 1.33678 2.61575 + endloop + endfacet + facet normal 0.0937396 -0.0934172 0.991204 + outer loop + vertex 1.04903 1.33793 2.61551 + vertex 1.04734 1.33973 2.61584 + vertex 1.0453 1.33678 2.61575 + endloop + endfacet + facet normal 0.0919713 -0.0950841 0.991212 + outer loop + vertex 1.0503 1.34183 2.61576 + vertex 1.04734 1.33973 2.61584 + vertex 1.04903 1.33793 2.61551 + endloop + endfacet + facet normal 0.107398 -0.0982982 0.989345 + outer loop + vertex 1.0453 1.33678 2.61575 + vertex 1.04345 1.33843 2.61612 + vertex 1.04244 1.33468 2.61585 + endloop + endfacet + facet normal 0.102889 -0.0921205 0.990418 + outer loop + vertex 1.0453 1.33678 2.61575 + vertex 1.04244 1.33468 2.61585 + vertex 1.04426 1.33302 2.61551 + endloop + endfacet + facet normal 0.105874 -0.0888668 0.990401 + outer loop + vertex 1.04426 1.33302 2.61551 + vertex 1.04244 1.33468 2.61585 + vertex 1.04065 1.33182 2.61579 + endloop + endfacet + facet normal 0.105126 -0.0865494 0.990686 + outer loop + vertex 1.04065 1.33182 2.61579 + vertex 1.04025 1.32862 2.61555 + vertex 1.04426 1.33302 2.61551 + endloop + endfacet + facet normal 0.111335 -0.0922122 0.989496 + outer loop + vertex 1.04426 1.33302 2.61551 + vertex 1.04025 1.32862 2.61555 + vertex 1.04385 1.32818 2.6151 + endloop + endfacet + facet normal 0.133314 -0.105925 0.985397 + outer loop + vertex 1.04244 1.33468 2.61585 + vertex 1.03853 1.33324 2.61623 + vertex 1.04065 1.33182 2.61579 + endloop + endfacet + facet normal 0.132961 -0.104926 0.985552 + outer loop + vertex 1.04244 1.33468 2.61585 + vertex 1.04345 1.33843 2.61612 + vertex 1.03853 1.33324 2.61623 + endloop + endfacet + facet normal 0.121954 -0.0944315 0.988033 + outer loop + vertex 1.04345 1.33843 2.61612 + vertex 1.03839 1.33793 2.61669 + vertex 1.03853 1.33324 2.61623 + endloop + endfacet + facet normal 0.0932942 -0.096959 0.990906 + outer loop + vertex 1.0503 1.34183 2.61576 + vertex 1.04849 1.34352 2.6161 + vertex 1.04734 1.33973 2.61584 + endloop + endfacet + facet normal 0.12203 -0.0953276 0.987938 + outer loop + vertex 1.04345 1.33843 2.61612 + vertex 1.04346 1.34305 2.61656 + vertex 1.03839 1.33793 2.61669 + endloop + endfacet + facet normal 0.116645 -0.089968 0.98909 + outer loop + vertex 1.03839 1.33793 2.61669 + vertex 1.04346 1.34305 2.61656 + vertex 1.0383 1.34271 2.61714 + endloop + endfacet + facet normal 0.147342 -0.0889718 0.985076 + outer loop + vertex 1.03839 1.33793 2.61669 + vertex 1.0383 1.34271 2.61714 + vertex 1.03323 1.33771 2.61744 + endloop + endfacet + facet normal 0.147171 -0.0831472 0.98561 + outer loop + vertex 1.03334 1.33276 2.61701 + vertex 1.03839 1.33793 2.61669 + vertex 1.03323 1.33771 2.61744 + endloop + endfacet + facet normal 0.140911 -0.0823681 0.98659 + outer loop + vertex 1.03323 1.33771 2.61744 + vertex 1.0383 1.34271 2.61714 + vertex 1.0332 1.34272 2.61787 + endloop + endfacet + facet normal 0.182925 -0.0815464 0.979739 + outer loop + vertex 1.03323 1.33771 2.61744 + vertex 1.0332 1.34272 2.61787 + vertex 1.02829 1.33804 2.61839 + endloop + endfacet + facet normal 0.140815 -0.0895295 0.985979 + outer loop + vertex 1.0383 1.34271 2.61714 + vertex 1.03821 1.34761 2.6176 + vertex 1.0332 1.34272 2.61787 + endloop + endfacet + facet normal 0.135898 -0.0844303 0.987119 + outer loop + vertex 1.0332 1.34272 2.61787 + vertex 1.03821 1.34761 2.6176 + vertex 1.03323 1.34777 2.6183 + endloop + endfacet + facet normal 0.171919 -0.0841398 0.981511 + outer loop + vertex 1.0332 1.34272 2.61787 + vertex 1.03323 1.34777 2.6183 + vertex 1.02851 1.34328 2.61874 + endloop + endfacet + facet normal 0.13564 -0.0902022 0.986643 + outer loop + vertex 1.03821 1.34761 2.6176 + vertex 1.03817 1.35261 2.61806 + vertex 1.03323 1.34777 2.6183 + endloop + endfacet + facet normal 0.129976 -0.0843477 0.987923 + outer loop + vertex 1.03323 1.34777 2.6183 + vertex 1.03817 1.35261 2.61806 + vertex 1.03326 1.35284 2.61872 + endloop + endfacet + facet normal 0.163016 -0.0841462 0.983029 + outer loop + vertex 1.03323 1.34777 2.6183 + vertex 1.03326 1.35284 2.61872 + vertex 1.02868 1.34838 2.6191 + endloop + endfacet + facet normal 0.129739 -0.0884135 0.987599 + outer loop + vertex 1.03817 1.35261 2.61806 + vertex 1.03816 1.35766 2.61851 + vertex 1.03326 1.35284 2.61872 + endloop + endfacet + facet normal 0.124465 -0.0829946 0.988747 + outer loop + vertex 1.03326 1.35284 2.61872 + vertex 1.03816 1.35766 2.61851 + vertex 1.03329 1.35797 2.61915 + endloop + endfacet + facet normal 0.124238 -0.0860503 0.988514 + outer loop + vertex 1.03816 1.35766 2.61851 + vertex 1.03821 1.36275 2.61895 + vertex 1.03329 1.35797 2.61915 + endloop + endfacet + facet normal 0.117358 -0.0789026 0.98995 + outer loop + vertex 1.03329 1.35797 2.61915 + vertex 1.03821 1.36275 2.61895 + vertex 1.03351 1.36321 2.61954 + endloop + endfacet + facet normal 0.14846 -0.0799287 0.985683 + outer loop + vertex 1.03329 1.35797 2.61915 + vertex 1.03351 1.36321 2.61954 + vertex 1.02849 1.35862 2.61993 + endloop + endfacet + facet normal 0.148786 -0.0776697 0.985814 + outer loop + vertex 1.02876 1.35341 2.61948 + vertex 1.03329 1.35797 2.61915 + vertex 1.02849 1.35862 2.61993 + endloop + endfacet + facet normal 0.138336 -0.0686699 0.988002 + outer loop + vertex 1.02849 1.35862 2.61993 + vertex 1.03351 1.36321 2.61954 + vertex 1.02956 1.36421 2.62017 + endloop + endfacet + facet normal 0.13649 -0.0757964 0.987738 + outer loop + vertex 1.03351 1.36321 2.61954 + vertex 1.03385 1.36841 2.6199 + vertex 1.02956 1.36421 2.62017 + endloop + endfacet + facet normal 0.11697 -0.0825025 0.989703 + outer loop + vertex 1.03821 1.36275 2.61895 + vertex 1.0383 1.36787 2.61937 + vertex 1.03351 1.36321 2.61954 + endloop + endfacet + facet normal 0.10903 -0.0742861 0.991259 + outer loop + vertex 1.03351 1.36321 2.61954 + vertex 1.0383 1.36787 2.61937 + vertex 1.03385 1.36841 2.6199 + endloop + endfacet + facet normal 0.108375 -0.079434 0.990931 + outer loop + vertex 1.0383 1.36787 2.61937 + vertex 1.0384 1.37304 2.61977 + vertex 1.03385 1.36841 2.6199 + endloop + endfacet + facet normal 0.102516 -0.0736512 0.992001 + outer loop + vertex 1.03385 1.36841 2.6199 + vertex 1.0384 1.37304 2.61977 + vertex 1.03379 1.3736 2.62029 + endloop + endfacet + facet normal 0.128496 -0.0731581 0.989008 + outer loop + vertex 1.03379 1.3736 2.62029 + vertex 1.0301 1.36886 2.62042 + vertex 1.03385 1.36841 2.6199 + endloop + endfacet + facet normal 0.12564 -0.0709161 0.989538 + outer loop + vertex 1.0299 1.37206 2.62067 + vertex 1.0301 1.36886 2.62042 + vertex 1.03379 1.3736 2.62029 + endloop + endfacet + facet normal 0.125568 -0.070726 0.989561 + outer loop + vertex 1.0299 1.37206 2.62067 + vertex 1.03379 1.3736 2.62029 + vertex 1.03113 1.37578 2.62078 + endloop + endfacet + facet normal 0.177968 -0.0877431 0.980117 + outer loop + vertex 1.03113 1.37578 2.62078 + vertex 1.02723 1.37255 2.6212 + vertex 1.0299 1.37206 2.62067 + endloop + endfacet + facet normal 0.123114 -0.0737519 0.989648 + outer loop + vertex 1.03379 1.3736 2.62029 + vertex 1.03503 1.37881 2.62052 + vertex 1.03113 1.37578 2.62078 + endloop + endfacet + facet normal 0.117264 -0.0661069 0.990898 + outer loop + vertex 1.03503 1.37881 2.62052 + vertex 1.03262 1.37963 2.62086 + vertex 1.03113 1.37578 2.62078 + endloop + endfacet + facet normal 0.16192 -0.0832359 0.983287 + outer loop + vertex 1.03262 1.37963 2.62086 + vertex 1.02841 1.37777 2.6214 + vertex 1.03113 1.37578 2.62078 + endloop + endfacet + facet normal 0.165239 -0.0910973 0.982037 + outer loop + vertex 1.03262 1.37963 2.62086 + vertex 1.03334 1.38343 2.62109 + vertex 1.02841 1.37777 2.6214 + endloop + endfacet + facet normal 0.10212 -0.0767505 0.991807 + outer loop + vertex 1.0384 1.37304 2.61977 + vertex 1.03871 1.37824 2.62014 + vertex 1.03379 1.3736 2.62029 + endloop + endfacet + facet normal 0.0926895 -0.0666856 0.993459 + outer loop + vertex 1.03379 1.3736 2.62029 + vertex 1.03871 1.37824 2.62014 + vertex 1.03503 1.37881 2.62052 + endloop + endfacet + facet normal 0.091558 -0.0737475 0.993065 + outer loop + vertex 1.03902 1.3832 2.62048 + vertex 1.03503 1.37881 2.62052 + vertex 1.03871 1.37824 2.62014 + endloop + endfacet + facet normal 0.0791199 -0.0730543 0.994185 + outer loop + vertex 1.03871 1.37824 2.62014 + vertex 1.04348 1.383 2.62011 + vertex 1.03902 1.3832 2.62048 + endloop + endfacet + facet normal 0.07877 -0.079715 0.993701 + outer loop + vertex 1.04385 1.38801 2.62048 + vertex 1.03902 1.3832 2.62048 + vertex 1.04348 1.383 2.62011 + endloop + endfacet + facet normal 0.0771437 -0.0796057 0.993837 + outer loop + vertex 1.04348 1.383 2.62011 + vertex 1.04847 1.38791 2.62011 + vertex 1.04385 1.38801 2.62048 + endloop + endfacet + facet normal 0.0769837 -0.0851731 0.993388 + outer loop + vertex 1.04895 1.39291 2.62051 + vertex 1.04385 1.38801 2.62048 + vertex 1.04847 1.38791 2.62011 + endloop + endfacet + facet normal 0.0787791 -0.0853318 0.993233 + outer loop + vertex 1.04847 1.38791 2.62011 + vertex 1.05356 1.39287 2.62014 + vertex 1.04895 1.39291 2.62051 + endloop + endfacet + facet normal 0.0787491 -0.0872468 0.993069 + outer loop + vertex 1.05407 1.39786 2.62054 + vertex 1.04895 1.39291 2.62051 + vertex 1.05356 1.39287 2.62014 + endloop + endfacet + facet normal 0.0742917 -0.0868231 0.99345 + outer loop + vertex 1.05356 1.39287 2.62014 + vertex 1.05865 1.39784 2.62019 + vertex 1.05407 1.39786 2.62054 + endloop + endfacet + facet normal 0.0743272 -0.0834881 0.993733 + outer loop + vertex 1.05904 1.40266 2.62057 + vertex 1.05407 1.39786 2.62054 + vertex 1.05865 1.39784 2.62019 + endloop + endfacet + facet normal 0.0627496 -0.0826004 0.994605 + outer loop + vertex 1.05865 1.39784 2.62019 + vertex 1.06358 1.40279 2.62029 + vertex 1.05904 1.40266 2.62057 + endloop + endfacet + facet normal 0.0625415 -0.0734487 0.995336 + outer loop + vertex 1.06339 1.40676 2.6206 + vertex 1.05904 1.40266 2.62057 + vertex 1.06358 1.40279 2.62029 + endloop + endfacet + facet normal 0.0541548 -0.0739054 0.995794 + outer loop + vertex 1.06358 1.40279 2.62029 + vertex 1.06836 1.40827 2.62044 + vertex 1.06339 1.40676 2.6206 + endloop + endfacet + facet normal 0.0517589 -0.0659745 0.996478 + outer loop + vertex 1.06339 1.40676 2.6206 + vertex 1.06836 1.40827 2.62044 + vertex 1.066 1.41068 2.62072 + endloop + endfacet + facet normal 0.0596963 -0.0712334 0.995672 + outer loop + vertex 1.0625 1.40911 2.62082 + vertex 1.06339 1.40676 2.6206 + vertex 1.066 1.41068 2.62072 + endloop + endfacet + facet normal 0.0619598 -0.0762902 0.995159 + outer loop + vertex 1.066 1.41068 2.62072 + vertex 1.06377 1.41297 2.62103 + vertex 1.0625 1.40911 2.62082 + endloop + endfacet + facet normal 0.071766 -0.0794613 0.994251 + outer loop + vertex 1.0625 1.40911 2.62082 + vertex 1.06377 1.41297 2.62103 + vertex 1.05859 1.40826 2.62103 + endloop + endfacet + facet normal 0.0710912 -0.0762762 0.994549 + outer loop + vertex 1.0625 1.40911 2.62082 + vertex 1.05859 1.40826 2.62103 + vertex 1.0603 1.40639 2.62077 + endloop + endfacet + facet normal 0.0719426 -0.0754948 0.994548 + outer loop + vertex 1.0603 1.40639 2.62077 + vertex 1.05859 1.40826 2.62103 + vertex 1.05747 1.40459 2.62083 + endloop + endfacet + facet normal 0.0735099 -0.0779754 0.994241 + outer loop + vertex 1.0603 1.40639 2.62077 + vertex 1.05747 1.40459 2.62083 + vertex 1.05904 1.40266 2.62057 + endloop + endfacet + facet normal 0.0731649 -0.0782577 0.994245 + outer loop + vertex 1.05904 1.40266 2.62057 + vertex 1.05747 1.40459 2.62083 + vertex 1.05539 1.40174 2.62076 + endloop + endfacet + facet normal 0.0729 -0.0780656 0.994279 + outer loop + vertex 1.05747 1.40459 2.62083 + vertex 1.05356 1.40345 2.62103 + vertex 1.05539 1.40174 2.62076 + endloop + endfacet + facet normal 0.0728127 -0.0781592 0.994278 + outer loop + vertex 1.05539 1.40174 2.62076 + vertex 1.05356 1.40345 2.62103 + vertex 1.05243 1.39972 2.62082 + endloop + endfacet + facet normal 0.0771526 -0.0845579 0.993427 + outer loop + vertex 1.05539 1.40174 2.62076 + vertex 1.05243 1.39972 2.62082 + vertex 1.05407 1.39786 2.62054 + endloop + endfacet + facet normal 0.0772748 -0.0844501 0.993427 + outer loop + vertex 1.05407 1.39786 2.62054 + vertex 1.05243 1.39972 2.62082 + vertex 1.05029 1.3968 2.62074 + endloop + endfacet + facet normal 0.0706016 -0.0796022 0.994323 + outer loop + vertex 1.05243 1.39972 2.62082 + vertex 1.04849 1.3985 2.621 + vertex 1.05029 1.3968 2.62074 + endloop + endfacet + facet normal 0.0707739 -0.0794202 0.994326 + outer loop + vertex 1.05029 1.3968 2.62074 + vertex 1.04849 1.3985 2.621 + vertex 1.04729 1.39476 2.62079 + endloop + endfacet + facet normal 0.0746704 -0.0851763 0.993564 + outer loop + vertex 1.05029 1.3968 2.62074 + vertex 1.04729 1.39476 2.62079 + vertex 1.04895 1.39291 2.62051 + endloop + endfacet + facet normal 0.0748082 -0.085053 0.993564 + outer loop + vertex 1.04895 1.39291 2.62051 + vertex 1.04729 1.39476 2.62079 + vertex 1.04514 1.39186 2.6207 + endloop + endfacet + facet normal 0.0712053 -0.082389 0.994053 + outer loop + vertex 1.04729 1.39476 2.62079 + vertex 1.04337 1.39355 2.62097 + vertex 1.04514 1.39186 2.6207 + endloop + endfacet + facet normal 0.072249 -0.0812996 0.994068 + outer loop + vertex 1.04514 1.39186 2.6207 + vertex 1.04337 1.39355 2.62097 + vertex 1.04215 1.38986 2.62076 + endloop + endfacet + facet normal 0.0724243 -0.0815613 0.994033 + outer loop + vertex 1.04514 1.39186 2.6207 + vertex 1.04215 1.38986 2.62076 + vertex 1.04385 1.38801 2.62048 + endloop + endfacet + facet normal 0.0743474 -0.0797908 0.994035 + outer loop + vertex 1.04385 1.38801 2.62048 + vertex 1.04215 1.38986 2.62076 + vertex 1.04007 1.38699 2.62068 + endloop + endfacet + facet normal 0.0855632 -0.0878852 0.992449 + outer loop + vertex 1.04215 1.38986 2.62076 + vertex 1.03828 1.38859 2.62098 + vertex 1.04007 1.38699 2.62068 + endloop + endfacet + facet normal 0.0889043 -0.0841625 0.992478 + outer loop + vertex 1.04007 1.38699 2.62068 + vertex 1.03828 1.38859 2.62098 + vertex 1.03719 1.38493 2.62077 + endloop + endfacet + facet normal 0.0835274 -0.0765669 0.99356 + outer loop + vertex 1.04007 1.38699 2.62068 + vertex 1.03719 1.38493 2.62077 + vertex 1.03902 1.3832 2.62048 + endloop + endfacet + facet normal 0.0875776 -0.0722672 0.993533 + outer loop + vertex 1.03902 1.3832 2.62048 + vertex 1.03719 1.38493 2.62077 + vertex 1.03539 1.38208 2.62072 + endloop + endfacet + facet normal 0.119745 -0.0924481 0.988491 + outer loop + vertex 1.03719 1.38493 2.62077 + vertex 1.03334 1.38343 2.62109 + vertex 1.03539 1.38208 2.62072 + endloop + endfacet + facet normal 0.125361 -0.0839446 0.988553 + outer loop + vertex 1.03539 1.38208 2.62072 + vertex 1.03334 1.38343 2.62109 + vertex 1.03262 1.37963 2.62086 + endloop + endfacet + facet normal 0.115138 -0.0722406 0.990719 + outer loop + vertex 1.03539 1.38208 2.62072 + vertex 1.03262 1.37963 2.62086 + vertex 1.03503 1.37881 2.62052 + endloop + endfacet + facet normal 0.120041 -0.093231 0.988382 + outer loop + vertex 1.03719 1.38493 2.62077 + vertex 1.03828 1.38859 2.62098 + vertex 1.03334 1.38343 2.62109 + endloop + endfacet + facet normal 0.105298 -0.0790468 0.991294 + outer loop + vertex 1.03828 1.38859 2.62098 + vertex 1.03332 1.388 2.62146 + vertex 1.03334 1.38343 2.62109 + endloop + endfacet + facet normal 0.0847533 -0.0853549 0.992739 + outer loop + vertex 1.04215 1.38986 2.62076 + vertex 1.04337 1.39355 2.62097 + vertex 1.03828 1.38859 2.62098 + endloop + endfacet + facet normal 0.0790697 -0.0795207 0.993692 + outer loop + vertex 1.04337 1.39355 2.62097 + vertex 1.03841 1.39309 2.62133 + vertex 1.03828 1.38859 2.62098 + endloop + endfacet + facet normal 0.0702554 -0.0792572 0.994375 + outer loop + vertex 1.04729 1.39476 2.62079 + vertex 1.04849 1.3985 2.621 + vertex 1.04337 1.39355 2.62097 + endloop + endfacet + facet normal 0.0684242 -0.0773656 0.994652 + outer loop + vertex 1.04849 1.3985 2.621 + vertex 1.0435 1.39809 2.62131 + vertex 1.04337 1.39355 2.62097 + endloop + endfacet + facet normal 0.06834 -0.0762881 0.994741 + outer loop + vertex 1.04849 1.3985 2.621 + vertex 1.04853 1.40307 2.62135 + vertex 1.0435 1.39809 2.62131 + endloop + endfacet + facet normal 0.0689194 -0.0762902 0.994701 + outer loop + vertex 1.05356 1.40345 2.62103 + vertex 1.04853 1.40307 2.62135 + vertex 1.04849 1.3985 2.621 + endloop + endfacet + facet normal 0.0688535 -0.0753572 0.994777 + outer loop + vertex 1.05356 1.40345 2.62103 + vertex 1.05351 1.40801 2.62138 + vertex 1.04853 1.40307 2.62135 + endloop + endfacet + facet normal 0.0686742 -0.0751767 0.994803 + outer loop + vertex 1.04853 1.40307 2.62135 + vertex 1.05351 1.40801 2.62138 + vertex 1.04842 1.40778 2.62172 + endloop + endfacet + facet normal 0.0686422 -0.0743787 0.994865 + outer loop + vertex 1.05351 1.40801 2.62138 + vertex 1.05334 1.41275 2.62175 + vertex 1.04842 1.40778 2.62172 + endloop + endfacet + facet normal 0.0710166 -0.0742816 0.994705 + outer loop + vertex 1.05351 1.40801 2.62138 + vertex 1.0585 1.41289 2.62139 + vertex 1.05334 1.41275 2.62175 + endloop + endfacet + facet normal 0.0710401 -0.0753872 0.994621 + outer loop + vertex 1.0585 1.41289 2.62139 + vertex 1.05829 1.41767 2.62177 + vertex 1.05334 1.41275 2.62175 + endloop + endfacet + facet normal 0.0693717 -0.0737083 0.994864 + outer loop + vertex 1.05334 1.41275 2.62175 + vertex 1.05829 1.41767 2.62177 + vertex 1.05322 1.41768 2.62212 + endloop + endfacet + facet normal 0.0693649 -0.0746898 0.994791 + outer loop + vertex 1.05829 1.41767 2.62177 + vertex 1.05818 1.42261 2.62214 + vertex 1.05322 1.41768 2.62212 + endloop + endfacet + facet normal 0.0594103 -0.0749609 0.995415 + outer loop + vertex 1.05829 1.41767 2.62177 + vertex 1.06335 1.42259 2.62183 + vertex 1.05818 1.42261 2.62214 + endloop + endfacet + facet normal 0.0593945 -0.0768157 0.995275 + outer loop + vertex 1.06335 1.42259 2.62183 + vertex 1.06327 1.42756 2.62222 + vertex 1.05818 1.42261 2.62214 + endloop + endfacet + facet normal 0.0562842 -0.0736239 0.995697 + outer loop + vertex 1.05818 1.42261 2.62214 + vertex 1.06327 1.42756 2.62222 + vertex 1.05819 1.42764 2.62252 + endloop + endfacet + facet normal 0.0562573 -0.0749314 0.995601 + outer loop + vertex 1.06327 1.42756 2.62222 + vertex 1.06329 1.43259 2.6226 + vertex 1.05819 1.42764 2.62252 + endloop + endfacet + facet normal 0.042346 -0.0749182 0.99629 + outer loop + vertex 1.06327 1.42756 2.62222 + vertex 1.06845 1.43259 2.62238 + vertex 1.06329 1.43259 2.6226 + endloop + endfacet + facet normal 0.0423518 -0.07287 0.996442 + outer loop + vertex 1.06845 1.43259 2.62238 + vertex 1.06848 1.43762 2.62275 + vertex 1.06329 1.43259 2.6226 + endloop + endfacet + facet normal 0.0417509 -0.0722531 0.996512 + outer loop + vertex 1.06329 1.43259 2.6226 + vertex 1.06848 1.43762 2.62275 + vertex 1.06332 1.43761 2.62296 + endloop + endfacet + facet normal 0.0533384 -0.0729084 0.995911 + outer loop + vertex 1.06845 1.43259 2.62238 + vertex 1.07346 1.43774 2.62249 + vertex 1.06848 1.43762 2.62275 + endloop + endfacet + facet normal 0.053177 -0.0646113 0.996493 + outer loop + vertex 1.07346 1.43774 2.62249 + vertex 1.0735 1.44277 2.62281 + vertex 1.06848 1.43762 2.62275 + endloop + endfacet + facet normal 0.059108 -0.0703878 0.995767 + outer loop + vertex 1.06848 1.43762 2.62275 + vertex 1.0735 1.44277 2.62281 + vertex 1.0685 1.44264 2.6231 + endloop + endfacet + facet normal 0.133757 -0.0647499 0.988897 + outer loop + vertex 1.07346 1.43774 2.62249 + vertex 1.07793 1.44289 2.62222 + vertex 1.0735 1.44277 2.62281 + endloop + endfacet + facet normal 0.133462 -0.0492435 0.98983 + outer loop + vertex 1.07793 1.44289 2.62222 + vertex 1.07797 1.44792 2.62247 + vertex 1.0735 1.44277 2.62281 + endloop + endfacet + facet normal 0.146378 -0.0606174 0.98737 + outer loop + vertex 1.0735 1.44277 2.62281 + vertex 1.07797 1.44792 2.62247 + vertex 1.07351 1.44778 2.62312 + endloop + endfacet + facet normal 0.118356 -0.0512623 0.991647 + outer loop + vertex 1.07787 1.43787 2.62197 + vertex 1.07793 1.44289 2.62222 + vertex 1.07346 1.43774 2.62249 + endloop + endfacet + facet normal 0.118749 -0.0687275 0.990543 + outer loop + vertex 1.07343 1.43274 2.62215 + vertex 1.07787 1.43787 2.62197 + vertex 1.07346 1.43774 2.62249 + endloop + endfacet + facet normal 0.103848 -0.0557533 0.993029 + outer loop + vertex 1.07786 1.43296 2.6217 + vertex 1.07787 1.43787 2.62197 + vertex 1.07343 1.43274 2.62215 + endloop + endfacet + facet normal 0.104447 -0.0697682 0.99208 + outer loop + vertex 1.07356 1.42786 2.62179 + vertex 1.07786 1.43296 2.6217 + vertex 1.07343 1.43274 2.62215 + endloop + endfacet + facet normal 0.0448822 -0.0716734 0.996418 + outer loop + vertex 1.07356 1.42786 2.62179 + vertex 1.07343 1.43274 2.62215 + vertex 1.06847 1.4276 2.622 + endloop + endfacet + facet normal 0.0452938 -0.0803312 0.995739 + outer loop + vertex 1.06868 1.42273 2.6216 + vertex 1.07356 1.42786 2.62179 + vertex 1.06847 1.4276 2.622 + endloop + endfacet + facet normal 0.0463216 -0.0802839 0.995695 + outer loop + vertex 1.06868 1.42273 2.6216 + vertex 1.06847 1.4276 2.622 + vertex 1.06335 1.42259 2.62183 + endloop + endfacet + facet normal 0.046312 -0.0798537 0.99573 + outer loop + vertex 1.06356 1.41775 2.62144 + vertex 1.06868 1.42273 2.6216 + vertex 1.06335 1.42259 2.62183 + endloop + endfacet + facet normal 0.0524362 -0.0861214 0.994904 + outer loop + vertex 1.06899 1.41789 2.62116 + vertex 1.06868 1.42273 2.6216 + vertex 1.06356 1.41775 2.62144 + endloop + endfacet + facet normal 0.0523374 -0.0814219 0.995305 + outer loop + vertex 1.06377 1.41297 2.62103 + vertex 1.06899 1.41789 2.62116 + vertex 1.06356 1.41775 2.62144 + endloop + endfacet + facet normal 0.0680508 -0.0806689 0.994415 + outer loop + vertex 1.06377 1.41297 2.62103 + vertex 1.06356 1.41775 2.62144 + vertex 1.0585 1.41289 2.62139 + endloop + endfacet + facet normal 0.0639123 -0.0936717 0.99355 + outer loop + vertex 1.06799 1.41401 2.62086 + vertex 1.06899 1.41789 2.62116 + vertex 1.06377 1.41297 2.62103 + endloop + endfacet + facet normal 0.049151 -0.0899558 0.994732 + outer loop + vertex 1.06899 1.41789 2.62116 + vertex 1.06799 1.41401 2.62086 + vertex 1.07141 1.41577 2.62085 + endloop + endfacet + facet normal 0.044669 -0.0950176 0.994473 + outer loop + vertex 1.07325 1.41903 2.62108 + vertex 1.06899 1.41789 2.62116 + vertex 1.07141 1.41577 2.62085 + endloop + endfacet + facet normal 0.0640377 -0.10582 0.992321 + outer loop + vertex 1.07474 1.41752 2.62082 + vertex 1.07325 1.41903 2.62108 + vertex 1.07141 1.41577 2.62085 + endloop + endfacet + facet normal 0.0601672 -0.0984355 0.993323 + outer loop + vertex 1.07353 1.41344 2.62049 + vertex 1.07474 1.41752 2.62082 + vertex 1.07141 1.41577 2.62085 + endloop + endfacet + facet normal 0.0665382 -0.0926332 0.993475 + outer loop + vertex 1.06953 1.4125 2.62067 + vertex 1.07353 1.41344 2.62049 + vertex 1.07141 1.41577 2.62085 + endloop + endfacet + facet normal 0.0618374 -0.0722079 0.995471 + outer loop + vertex 1.06953 1.4125 2.62067 + vertex 1.06836 1.40827 2.62044 + vertex 1.07353 1.41344 2.62049 + endloop + endfacet + facet normal 0.0707787 -0.0811472 0.994186 + outer loop + vertex 1.07353 1.41344 2.62049 + vertex 1.06836 1.40827 2.62044 + vertex 1.07346 1.4082 2.62007 + endloop + endfacet + facet normal 0.153757 -0.0815271 0.98474 + outer loop + vertex 1.07346 1.4082 2.62007 + vertex 1.07813 1.41304 2.61974 + vertex 1.07353 1.41344 2.62049 + endloop + endfacet + facet normal 0.150361 -0.114995 0.98192 + outer loop + vertex 1.07813 1.41304 2.61974 + vertex 1.07829 1.4182 2.62032 + vertex 1.07353 1.41344 2.62049 + endloop + endfacet + facet normal 0.349998 -0.115449 0.929609 + outer loop + vertex 1.07813 1.41304 2.61974 + vertex 1.0821 1.4174 2.61879 + vertex 1.07829 1.4182 2.62032 + endloop + endfacet + facet normal 0.34389 -0.14184 0.928235 + outer loop + vertex 1.08201 1.42208 2.61953 + vertex 1.07829 1.4182 2.62032 + vertex 1.0821 1.4174 2.61879 + endloop + endfacet + facet normal 0.40877 -0.212425 0.887571 + outer loop + vertex 1.07963 1.42229 2.62068 + vertex 1.07829 1.4182 2.62032 + vertex 1.08201 1.42208 2.61953 + endloop + endfacet + facet normal 0.416886 -0.160651 0.894649 + outer loop + vertex 1.08201 1.42208 2.61953 + vertex 1.08141 1.42501 2.62034 + vertex 1.07963 1.42229 2.62068 + endloop + endfacet + facet normal 0.275543 -0.0602995 0.959396 + outer loop + vertex 1.08141 1.42501 2.62034 + vertex 1.07876 1.42474 2.62109 + vertex 1.07963 1.42229 2.62068 + endloop + endfacet + facet normal 0.160567 -0.105011 0.981423 + outer loop + vertex 1.07963 1.42229 2.62068 + vertex 1.07876 1.42474 2.62109 + vertex 1.07662 1.42086 2.62102 + endloop + endfacet + facet normal 0.0861816 -0.0642226 0.994207 + outer loop + vertex 1.07876 1.42474 2.62109 + vertex 1.0741 1.42305 2.62138 + vertex 1.07662 1.42086 2.62102 + endloop + endfacet + facet normal 0.0651787 -0.088288 0.99396 + outer loop + vertex 1.07662 1.42086 2.62102 + vertex 1.0741 1.42305 2.62138 + vertex 1.07325 1.41903 2.62108 + endloop + endfacet + facet normal 0.0864194 -0.0648898 0.994143 + outer loop + vertex 1.07876 1.42474 2.62109 + vertex 1.07806 1.42837 2.62138 + vertex 1.0741 1.42305 2.62138 + endloop + endfacet + facet normal 0.097647 -0.0732733 0.99252 + outer loop + vertex 1.0741 1.42305 2.62138 + vertex 1.07806 1.42837 2.62138 + vertex 1.07356 1.42786 2.62179 + endloop + endfacet + facet normal 0.255151 -0.0302706 0.966427 + outer loop + vertex 1.08152 1.42846 2.62048 + vertex 1.07806 1.42837 2.62138 + vertex 1.07876 1.42474 2.62109 + endloop + endfacet + facet normal 0.178332 -0.144317 0.973329 + outer loop + vertex 1.07963 1.42229 2.62068 + vertex 1.07662 1.42086 2.62102 + vertex 1.07829 1.4182 2.62032 + endloop + endfacet + facet normal 0.166835 -0.151796 0.97423 + outer loop + vertex 1.07474 1.41752 2.62082 + vertex 1.07829 1.4182 2.62032 + vertex 1.07662 1.42086 2.62102 + endloop + endfacet + facet normal 0.316651 -0.0817239 0.945015 + outer loop + vertex 1.08212 1.41227 2.61834 + vertex 1.0821 1.4174 2.61879 + vertex 1.07813 1.41304 2.61974 + endloop + endfacet + facet normal 0.317625 -0.0767955 0.945101 + outer loop + vertex 1.07809 1.4079 2.61934 + vertex 1.08212 1.41227 2.61834 + vertex 1.07813 1.41304 2.61974 + endloop + endfacet + facet normal 0.299114 -0.0580166 0.952452 + outer loop + vertex 1.08214 1.40725 2.61802 + vertex 1.08212 1.41227 2.61834 + vertex 1.07809 1.4079 2.61934 + endloop + endfacet + facet normal 0.297435 -0.0682187 0.952302 + outer loop + vertex 1.07807 1.40284 2.61898 + vertex 1.08214 1.40725 2.61802 + vertex 1.07809 1.4079 2.61934 + endloop + endfacet + facet normal 0.145584 -0.0702718 0.986847 + outer loop + vertex 1.07807 1.40284 2.61898 + vertex 1.07809 1.4079 2.61934 + vertex 1.07343 1.40302 2.61968 + endloop + endfacet + facet normal 0.144953 -0.0834632 0.985912 + outer loop + vertex 1.0734 1.39793 2.61925 + vertex 1.07807 1.40284 2.61898 + vertex 1.07343 1.40302 2.61968 + endloop + endfacet + facet normal 0.073488 -0.0836986 0.993778 + outer loop + vertex 1.0734 1.39793 2.61925 + vertex 1.07343 1.40302 2.61968 + vertex 1.06841 1.39787 2.61961 + endloop + endfacet + facet normal 0.0735273 -0.0918459 0.993055 + outer loop + vertex 1.06838 1.39281 2.61915 + vertex 1.0734 1.39793 2.61925 + vertex 1.06841 1.39787 2.61961 + endloop + endfacet + facet normal 0.0584089 -0.0918522 0.994058 + outer loop + vertex 1.06838 1.39281 2.61915 + vertex 1.06841 1.39787 2.61961 + vertex 1.06328 1.39273 2.61944 + endloop + endfacet + facet normal 0.0584095 -0.0919125 0.994053 + outer loop + vertex 1.06327 1.3877 2.61898 + vertex 1.06838 1.39281 2.61915 + vertex 1.06328 1.39273 2.61944 + endloop + endfacet + facet normal 0.0685871 -0.0918629 0.993407 + outer loop + vertex 1.06327 1.3877 2.61898 + vertex 1.06328 1.39273 2.61944 + vertex 1.05818 1.38769 2.61933 + endloop + endfacet + facet normal 0.0685999 -0.0881226 0.993745 + outer loop + vertex 1.05821 1.38268 2.61888 + vertex 1.06327 1.3877 2.61898 + vertex 1.05818 1.38769 2.61933 + endloop + endfacet + facet normal 0.07977 -0.087984 0.992923 + outer loop + vertex 1.05821 1.38268 2.61888 + vertex 1.05818 1.38769 2.61933 + vertex 1.05315 1.38269 2.61929 + endloop + endfacet + facet normal 0.0797911 -0.0857599 0.993116 + outer loop + vertex 1.0532 1.37769 2.61885 + vertex 1.05821 1.38268 2.61888 + vertex 1.05315 1.38269 2.61929 + endloop + endfacet + facet normal 0.0846079 -0.0856707 0.992725 + outer loop + vertex 1.0532 1.37769 2.61885 + vertex 1.05315 1.38269 2.61929 + vertex 1.04815 1.3777 2.61928 + endloop + endfacet + facet normal 0.0846068 -0.0857943 0.992714 + outer loop + vertex 1.04821 1.37268 2.61884 + vertex 1.0532 1.37769 2.61885 + vertex 1.04815 1.3777 2.61928 + endloop + endfacet + facet normal 0.0886169 -0.0857193 0.992371 + outer loop + vertex 1.04821 1.37268 2.61884 + vertex 1.04815 1.3777 2.61928 + vertex 1.04318 1.37273 2.6193 + endloop + endfacet + facet normal 0.0886265 -0.0851666 0.992417 + outer loop + vertex 1.0432 1.36768 2.61886 + vertex 1.04821 1.37268 2.61884 + vertex 1.04318 1.37273 2.6193 + endloop + endfacet + facet normal 0.098406 -0.0850585 0.991505 + outer loop + vertex 1.0432 1.36768 2.61886 + vertex 1.04318 1.37273 2.6193 + vertex 1.0383 1.36787 2.61937 + endloop + endfacet + facet normal 0.0921793 -0.0887233 0.991782 + outer loop + vertex 1.04825 1.36771 2.6184 + vertex 1.04821 1.37268 2.61884 + vertex 1.0432 1.36768 2.61886 + endloop + endfacet + facet normal 0.0921803 -0.0881606 0.991832 + outer loop + vertex 1.04321 1.36266 2.61842 + vertex 1.04825 1.36771 2.6184 + vertex 1.0432 1.36768 2.61886 + endloop + endfacet + facet normal 0.10415 -0.0880339 0.990658 + outer loop + vertex 1.04321 1.36266 2.61842 + vertex 1.0432 1.36768 2.61886 + vertex 1.03821 1.36275 2.61895 + endloop + endfacet + facet normal 0.104203 -0.0860688 0.990825 + outer loop + vertex 1.03816 1.35766 2.61851 + vertex 1.04321 1.36266 2.61842 + vertex 1.03821 1.36275 2.61895 + endloop + endfacet + facet normal 0.108693 -0.0906164 0.989937 + outer loop + vertex 1.04322 1.35764 2.61795 + vertex 1.04321 1.36266 2.61842 + vertex 1.03816 1.35766 2.61851 + endloop + endfacet + facet normal 0.0951874 -0.0907719 0.991312 + outer loop + vertex 1.04322 1.35764 2.61795 + vertex 1.04827 1.36272 2.61794 + vertex 1.04321 1.36266 2.61842 + endloop + endfacet + facet normal 0.0967308 -0.0923059 0.991021 + outer loop + vertex 1.04831 1.35773 2.61747 + vertex 1.04827 1.36272 2.61794 + vertex 1.04322 1.35764 2.61795 + endloop + endfacet + facet normal 0.0967325 -0.0924768 0.991005 + outer loop + vertex 1.04327 1.35265 2.61748 + vertex 1.04831 1.35773 2.61747 + vertex 1.04322 1.35764 2.61795 + endloop + endfacet + facet normal 0.112191 -0.0921623 0.989403 + outer loop + vertex 1.04327 1.35265 2.61748 + vertex 1.04322 1.35764 2.61795 + vertex 1.03817 1.35261 2.61806 + endloop + endfacet + facet normal 0.0975285 -0.0932658 0.990853 + outer loop + vertex 1.04842 1.35285 2.617 + vertex 1.04831 1.35773 2.61747 + vertex 1.04327 1.35265 2.61748 + endloop + endfacet + facet normal 0.0975253 -0.0931553 0.990864 + outer loop + vertex 1.04337 1.34778 2.61702 + vertex 1.04842 1.35285 2.617 + vertex 1.04327 1.35265 2.61748 + endloop + endfacet + facet normal 0.114149 -0.0926432 0.989135 + outer loop + vertex 1.04337 1.34778 2.61702 + vertex 1.04327 1.35265 2.61748 + vertex 1.03821 1.34761 2.6176 + endloop + endfacet + facet normal 0.0982309 -0.0938574 0.990728 + outer loop + vertex 1.04853 1.34813 2.61654 + vertex 1.04842 1.35285 2.617 + vertex 1.04337 1.34778 2.61702 + endloop + endfacet + facet normal 0.0897798 -0.0941245 0.991504 + outer loop + vertex 1.04853 1.34813 2.61654 + vertex 1.05357 1.35313 2.61656 + vertex 1.04842 1.35285 2.617 + endloop + endfacet + facet normal 0.0897396 -0.0932607 0.991589 + outer loop + vertex 1.05357 1.35313 2.61656 + vertex 1.05341 1.35787 2.61702 + vertex 1.04842 1.35285 2.617 + endloop + endfacet + facet normal 0.0887522 -0.0933021 0.991674 + outer loop + vertex 1.05357 1.35313 2.61656 + vertex 1.05857 1.35803 2.61657 + vertex 1.05341 1.35787 2.61702 + endloop + endfacet + facet normal 0.0887599 -0.0936372 0.991642 + outer loop + vertex 1.05857 1.35803 2.61657 + vertex 1.05836 1.36281 2.61704 + vertex 1.05341 1.35787 2.61702 + endloop + endfacet + facet normal 0.0882204 -0.093097 0.991741 + outer loop + vertex 1.05341 1.35787 2.61702 + vertex 1.05836 1.36281 2.61704 + vertex 1.05329 1.36277 2.61749 + endloop + endfacet + facet normal 0.0899756 -0.0930401 0.991589 + outer loop + vertex 1.05341 1.35787 2.61702 + vertex 1.05329 1.36277 2.61749 + vertex 1.04831 1.35773 2.61747 + endloop + endfacet + facet normal 0.0882205 -0.0935029 0.991703 + outer loop + vertex 1.05836 1.36281 2.61704 + vertex 1.05826 1.36775 2.61751 + vertex 1.05329 1.36277 2.61749 + endloop + endfacet + facet normal 0.0869809 -0.0922664 0.991928 + outer loop + vertex 1.05329 1.36277 2.61749 + vertex 1.05826 1.36775 2.61751 + vertex 1.05327 1.36775 2.61795 + endloop + endfacet + facet normal 0.0893606 -0.0922362 0.991719 + outer loop + vertex 1.05329 1.36277 2.61749 + vertex 1.05327 1.36775 2.61795 + vertex 1.04827 1.36272 2.61794 + endloop + endfacet + facet normal 0.088358 -0.0912414 0.991901 + outer loop + vertex 1.04827 1.36272 2.61794 + vertex 1.05327 1.36775 2.61795 + vertex 1.04825 1.36771 2.6184 + endloop + endfacet + facet normal 0.088357 -0.0904882 0.99197 + outer loop + vertex 1.05327 1.36775 2.61795 + vertex 1.05326 1.37273 2.61841 + vertex 1.04825 1.36771 2.6184 + endloop + endfacet + facet normal 0.0849495 -0.0905195 0.992265 + outer loop + vertex 1.05327 1.36775 2.61795 + vertex 1.05826 1.37274 2.61798 + vertex 1.05326 1.37273 2.61841 + endloop + endfacet + facet normal 0.0849497 -0.090497 0.992267 + outer loop + vertex 1.05826 1.37274 2.61798 + vertex 1.05826 1.37772 2.61843 + vertex 1.05326 1.37273 2.61841 + endloop + endfacet + facet normal 0.0824002 -0.0879428 0.992712 + outer loop + vertex 1.05326 1.37273 2.61841 + vertex 1.05826 1.37772 2.61843 + vertex 1.0532 1.37769 2.61885 + endloop + endfacet + facet normal 0.0771191 -0.0905535 0.992901 + outer loop + vertex 1.05826 1.37274 2.61798 + vertex 1.06331 1.37775 2.61804 + vertex 1.05826 1.37772 2.61843 + endloop + endfacet + facet normal 0.0771176 -0.0928162 0.992692 + outer loop + vertex 1.06331 1.37775 2.61804 + vertex 1.06331 1.38273 2.61851 + vertex 1.05826 1.37772 2.61843 + endloop + endfacet + facet normal 0.0728673 -0.0885443 0.993403 + outer loop + vertex 1.05826 1.37772 2.61843 + vertex 1.06331 1.38273 2.61851 + vertex 1.05821 1.38268 2.61888 + endloop + endfacet + facet normal 0.0652551 -0.0928955 0.993535 + outer loop + vertex 1.06331 1.37775 2.61804 + vertex 1.06841 1.38283 2.61819 + vertex 1.06331 1.38273 2.61851 + endloop + endfacet + facet normal 0.0652989 -0.096014 0.993236 + outer loop + vertex 1.06841 1.38283 2.61819 + vertex 1.06841 1.38782 2.61867 + vertex 1.06331 1.38273 2.61851 + endloop + endfacet + facet normal 0.0618598 -0.0925876 0.993781 + outer loop + vertex 1.06331 1.38273 2.61851 + vertex 1.06841 1.38782 2.61867 + vertex 1.06327 1.3877 2.61898 + endloop + endfacet + facet normal 0.0690999 -0.0959851 0.992981 + outer loop + vertex 1.06841 1.38283 2.61819 + vertex 1.07341 1.38794 2.61833 + vertex 1.06841 1.38782 2.61867 + endloop + endfacet + facet normal 0.069047 -0.0929401 0.993275 + outer loop + vertex 1.07341 1.38794 2.61833 + vertex 1.07341 1.39292 2.6188 + vertex 1.06841 1.38782 2.61867 + endloop + endfacet + facet normal 0.0714546 -0.0952878 0.992882 + outer loop + vertex 1.06841 1.38782 2.61867 + vertex 1.07341 1.39292 2.6188 + vertex 1.06838 1.39281 2.61915 + endloop + endfacet + facet normal 0.123963 -0.0924098 0.987975 + outer loop + vertex 1.07341 1.38794 2.61833 + vertex 1.07806 1.39286 2.61821 + vertex 1.07341 1.39292 2.6188 + endloop + endfacet + facet normal 0.124281 -0.0791773 0.989083 + outer loop + vertex 1.07806 1.39286 2.61821 + vertex 1.07807 1.39785 2.61861 + vertex 1.07341 1.39292 2.6188 + endloop + endfacet + facet normal 0.134644 -0.0890755 0.986882 + outer loop + vertex 1.07341 1.39292 2.6188 + vertex 1.07807 1.39785 2.61861 + vertex 1.0734 1.39793 2.61925 + endloop + endfacet + facet normal 0.260912 -0.0773745 0.962257 + outer loop + vertex 1.07806 1.39286 2.61821 + vertex 1.08213 1.39735 2.61746 + vertex 1.07807 1.39785 2.61861 + endloop + endfacet + facet normal 0.263917 -0.054346 0.963013 + outer loop + vertex 1.08213 1.39735 2.61746 + vertex 1.08214 1.4023 2.61774 + vertex 1.07807 1.39785 2.61861 + endloop + endfacet + facet normal 0.281675 -0.0717817 0.956821 + outer loop + vertex 1.07807 1.39785 2.61861 + vertex 1.08214 1.4023 2.61774 + vertex 1.07807 1.40284 2.61898 + endloop + endfacet + facet normal 0.237339 -0.0547378 0.969883 + outer loop + vertex 1.08211 1.39237 2.61719 + vertex 1.08213 1.39735 2.61746 + vertex 1.07806 1.39286 2.61821 + endloop + endfacet + facet normal 0.234277 -0.0781179 0.969026 + outer loop + vertex 1.07804 1.38785 2.61781 + vertex 1.08211 1.39237 2.61719 + vertex 1.07806 1.39286 2.61821 + endloop + endfacet + facet normal 0.213864 -0.0588446 0.975089 + outer loop + vertex 1.08207 1.38733 2.61689 + vertex 1.08211 1.39237 2.61719 + vertex 1.07804 1.38785 2.61781 + endloop + endfacet + facet normal 0.21028 -0.0847048 0.973965 + outer loop + vertex 1.07798 1.3828 2.61738 + vertex 1.08207 1.38733 2.61689 + vertex 1.07804 1.38785 2.61781 + endloop + endfacet + facet normal 0.0998011 -0.0849727 0.991372 + outer loop + vertex 1.07798 1.3828 2.61738 + vertex 1.07804 1.38785 2.61781 + vertex 1.07338 1.38291 2.61786 + endloop + endfacet + facet normal 0.0994128 -0.0966371 0.990343 + outer loop + vertex 1.07335 1.37787 2.61737 + vertex 1.07798 1.3828 2.61738 + vertex 1.07338 1.38291 2.61786 + endloop + endfacet + facet normal 0.0672348 -0.0967273 0.993037 + outer loop + vertex 1.07335 1.37787 2.61737 + vertex 1.07338 1.38291 2.61786 + vertex 1.06838 1.37781 2.6177 + endloop + endfacet + facet normal 0.0672483 -0.0988507 0.992827 + outer loop + vertex 1.0684 1.37279 2.6172 + vertex 1.07335 1.37787 2.61737 + vertex 1.06838 1.37781 2.6177 + endloop + endfacet + facet normal 0.0736022 -0.098779 0.992384 + outer loop + vertex 1.0684 1.37279 2.6172 + vertex 1.06838 1.37781 2.6177 + vertex 1.06329 1.37274 2.61757 + endloop + endfacet + facet normal 0.0735953 -0.0962914 0.992629 + outer loop + vertex 1.06336 1.36776 2.61708 + vertex 1.0684 1.37279 2.6172 + vertex 1.06329 1.37274 2.61757 + endloop + endfacet + facet normal 0.0845445 -0.0960569 0.991779 + outer loop + vertex 1.06336 1.36776 2.61708 + vertex 1.06329 1.37274 2.61757 + vertex 1.05826 1.36775 2.61751 + endloop + endfacet + facet normal 0.0810996 -0.0925917 0.992396 + outer loop + vertex 1.05826 1.36775 2.61751 + vertex 1.06329 1.37274 2.61757 + vertex 1.05826 1.37274 2.61798 + endloop + endfacet + facet normal 0.0775617 -0.100248 0.991935 + outer loop + vertex 1.06861 1.36784 2.61668 + vertex 1.0684 1.37279 2.6172 + vertex 1.06336 1.36776 2.61708 + endloop + endfacet + facet normal 0.0775367 -0.0973348 0.992227 + outer loop + vertex 1.06358 1.36289 2.61659 + vertex 1.06861 1.36784 2.61668 + vertex 1.06336 1.36776 2.61708 + endloop + endfacet + facet normal 0.0877154 -0.0967938 0.991432 + outer loop + vertex 1.06358 1.36289 2.61659 + vertex 1.06336 1.36776 2.61708 + vertex 1.05836 1.36281 2.61704 + endloop + endfacet + facet normal 0.0823402 -0.102192 0.991351 + outer loop + vertex 1.06892 1.36294 2.61615 + vertex 1.06861 1.36784 2.61668 + vertex 1.06358 1.36289 2.61659 + endloop + endfacet + facet normal 0.0823303 -0.0965319 0.991919 + outer loop + vertex 1.0638 1.35809 2.6161 + vertex 1.06892 1.36294 2.61615 + vertex 1.06358 1.36289 2.61659 + endloop + endfacet + facet normal 0.0900407 -0.0961048 0.99129 + outer loop + vertex 1.0638 1.35809 2.6161 + vertex 1.06358 1.36289 2.61659 + vertex 1.05857 1.35803 2.61657 + endloop + endfacet + facet normal 0.0902505 -0.104879 0.990381 + outer loop + vertex 1.06796 1.35907 2.61583 + vertex 1.06892 1.36294 2.61615 + vertex 1.0638 1.35809 2.6161 + endloop + endfacet + facet normal 0.0733048 -0.100795 0.992203 + outer loop + vertex 1.06892 1.36294 2.61615 + vertex 1.06796 1.35907 2.61583 + vertex 1.07131 1.36075 2.61575 + endloop + endfacet + facet normal 0.0704155 -0.103925 0.992089 + outer loop + vertex 1.07313 1.36398 2.61596 + vertex 1.06892 1.36294 2.61615 + vertex 1.07131 1.36075 2.61575 + endloop + endfacet + facet normal 0.0614741 -0.098952 0.993192 + outer loop + vertex 1.0747 1.36247 2.61571 + vertex 1.07313 1.36398 2.61596 + vertex 1.07131 1.36075 2.61575 + endloop + endfacet + facet normal 0.0565852 -0.0893028 0.994396 + outer loop + vertex 1.07355 1.35843 2.61541 + vertex 1.0747 1.36247 2.61571 + vertex 1.07131 1.36075 2.61575 + endloop + endfacet + facet normal 0.0596301 -0.0863785 0.994476 + outer loop + vertex 1.06948 1.35752 2.61558 + vertex 1.07355 1.35843 2.61541 + vertex 1.07131 1.36075 2.61575 + endloop + endfacet + facet normal 0.0589627 -0.0833481 0.994775 + outer loop + vertex 1.06948 1.35752 2.61558 + vertex 1.06831 1.35329 2.61529 + vertex 1.07355 1.35843 2.61541 + endloop + endfacet + facet normal 0.0641651 -0.0886282 0.993996 + outer loop + vertex 1.07355 1.35843 2.61541 + vertex 1.06831 1.35329 2.61529 + vertex 1.07348 1.35319 2.61495 + endloop + endfacet + facet normal 0.0830319 -0.0887255 0.992589 + outer loop + vertex 1.07348 1.35319 2.61495 + vertex 1.07853 1.35822 2.61498 + vertex 1.07355 1.35843 2.61541 + endloop + endfacet + facet normal 0.082898 -0.0913653 0.992361 + outer loop + vertex 1.07853 1.35822 2.61498 + vertex 1.07868 1.3634 2.61544 + vertex 1.07355 1.35843 2.61541 + endloop + endfacet + facet normal 0.188737 -0.0930121 0.977613 + outer loop + vertex 1.07853 1.35822 2.61498 + vertex 1.08321 1.36299 2.61453 + vertex 1.07868 1.3634 2.61544 + endloop + endfacet + facet normal 0.188587 -0.0944125 0.977508 + outer loop + vertex 1.08337 1.36823 2.615 + vertex 1.07868 1.3634 2.61544 + vertex 1.08321 1.36299 2.61453 + endloop + endfacet + facet normal 0.162033 -0.066155 0.984565 + outer loop + vertex 1.08314 1.35788 2.6142 + vertex 1.08321 1.36299 2.61453 + vertex 1.07853 1.35822 2.61498 + endloop + endfacet + facet normal 0.160375 -0.0861949 0.983286 + outer loop + vertex 1.07846 1.35308 2.61454 + vertex 1.08314 1.35788 2.6142 + vertex 1.07853 1.35822 2.61498 + endloop + endfacet + facet normal 0.146582 -0.0725223 0.986536 + outer loop + vertex 1.0831 1.35287 2.61383 + vertex 1.08314 1.35788 2.6142 + vertex 1.07846 1.35308 2.61454 + endloop + endfacet + facet normal 0.145274 -0.0955166 0.98477 + outer loop + vertex 1.07843 1.34802 2.61405 + vertex 1.0831 1.35287 2.61383 + vertex 1.07846 1.35308 2.61454 + endloop + endfacet + facet normal 0.0760708 -0.095757 0.992494 + outer loop + vertex 1.07843 1.34802 2.61405 + vertex 1.07846 1.35308 2.61454 + vertex 1.07343 1.348 2.61443 + endloop + endfacet + facet normal 0.0760259 -0.1095 0.991075 + outer loop + vertex 1.07339 1.34291 2.61387 + vertex 1.07843 1.34802 2.61405 + vertex 1.07343 1.348 2.61443 + endloop + endfacet + facet normal 0.0684045 -0.109497 0.991631 + outer loop + vertex 1.07339 1.34291 2.61387 + vertex 1.07343 1.348 2.61443 + vertex 1.06829 1.34286 2.61422 + endloop + endfacet + facet normal 0.0684087 -0.11112 0.99145 + outer loop + vertex 1.06825 1.3378 2.61366 + vertex 1.07339 1.34291 2.61387 + vertex 1.06829 1.34286 2.61422 + endloop + endfacet + facet normal 0.086033 -0.111108 0.990077 + outer loop + vertex 1.06825 1.3378 2.61366 + vertex 1.06829 1.34286 2.61422 + vertex 1.06318 1.33781 2.6141 + endloop + endfacet + facet normal 0.0860752 -0.107455 0.990477 + outer loop + vertex 1.06317 1.33276 2.61355 + vertex 1.06825 1.3378 2.61366 + vertex 1.06318 1.33781 2.6141 + endloop + endfacet + facet normal 0.100879 -0.107351 0.98909 + outer loop + vertex 1.06317 1.33276 2.61355 + vertex 1.06318 1.33781 2.6141 + vertex 1.05813 1.33281 2.61407 + endloop + endfacet + facet normal 0.100934 -0.104635 0.989375 + outer loop + vertex 1.05815 1.32776 2.61353 + vertex 1.06317 1.33276 2.61355 + vertex 1.05813 1.33281 2.61407 + endloop + endfacet + facet normal 0.10582 -0.104558 0.988873 + outer loop + vertex 1.05815 1.32776 2.61353 + vertex 1.05813 1.33281 2.61407 + vertex 1.05312 1.3278 2.61408 + endloop + endfacet + facet normal 0.10583 -0.104049 0.988926 + outer loop + vertex 1.05316 1.32274 2.61354 + vertex 1.05815 1.32776 2.61353 + vertex 1.05312 1.3278 2.61408 + endloop + endfacet + facet normal 0.10842 -0.104 0.98865 + outer loop + vertex 1.05316 1.32274 2.61354 + vertex 1.05312 1.3278 2.61408 + vertex 1.04815 1.32283 2.6141 + endloop + endfacet + facet normal 0.108449 -0.102986 0.988753 + outer loop + vertex 1.04816 1.31773 2.61357 + vertex 1.05316 1.32274 2.61354 + vertex 1.04815 1.32283 2.6141 + endloop + endfacet + facet normal 0.117189 -0.102867 0.987768 + outer loop + vertex 1.04816 1.31773 2.61357 + vertex 1.04815 1.32283 2.6141 + vertex 1.04327 1.31797 2.61417 + endloop + endfacet + facet normal 0.117382 -0.099737 0.988066 + outer loop + vertex 1.04318 1.31281 2.61366 + vertex 1.04816 1.31773 2.61357 + vertex 1.04327 1.31797 2.61417 + endloop + endfacet + facet normal 0.121901 -0.104335 0.987043 + outer loop + vertex 1.04822 1.31264 2.61302 + vertex 1.04816 1.31773 2.61357 + vertex 1.04318 1.31281 2.61366 + endloop + endfacet + facet normal 0.122014 -0.101934 0.98728 + outer loop + vertex 1.04317 1.30765 2.61313 + vertex 1.04822 1.31264 2.61302 + vertex 1.04318 1.31281 2.61366 + endloop + endfacet + facet normal 0.142665 -0.101656 0.984537 + outer loop + vertex 1.04317 1.30765 2.61313 + vertex 1.04318 1.31281 2.61366 + vertex 1.03824 1.30806 2.61389 + endloop + endfacet + facet normal 0.143113 -0.0970431 0.984937 + outer loop + vertex 1.03825 1.30287 2.61337 + vertex 1.04317 1.30765 2.61313 + vertex 1.03824 1.30806 2.61389 + endloop + endfacet + facet normal 0.148106 -0.102247 0.983672 + outer loop + vertex 1.04324 1.30263 2.6126 + vertex 1.04317 1.30765 2.61313 + vertex 1.03825 1.30287 2.61337 + endloop + endfacet + facet normal 0.148447 -0.096747 0.984177 + outer loop + vertex 1.03827 1.29781 2.61287 + vertex 1.04324 1.30263 2.6126 + vertex 1.03825 1.30287 2.61337 + endloop + endfacet + facet normal 0.184254 -0.0960384 0.978175 + outer loop + vertex 1.03827 1.29781 2.61287 + vertex 1.03825 1.30287 2.61337 + vertex 1.03362 1.29843 2.61381 + endloop + endfacet + facet normal 0.185963 -0.0843525 0.978929 + outer loop + vertex 1.03351 1.29332 2.61339 + vertex 1.03827 1.29781 2.61287 + vertex 1.03362 1.29843 2.61381 + endloop + endfacet + facet normal 0.195357 -0.0946157 0.976158 + outer loop + vertex 1.03825 1.29291 2.6124 + vertex 1.03827 1.29781 2.61287 + vertex 1.03351 1.29332 2.61339 + endloop + endfacet + facet normal 0.197067 -0.0775282 0.97732 + outer loop + vertex 1.03331 1.28818 2.61302 + vertex 1.03825 1.29291 2.6124 + vertex 1.03351 1.29332 2.61339 + endloop + endfacet + facet normal 0.257353 -0.0788365 0.963096 + outer loop + vertex 1.03331 1.28818 2.61302 + vertex 1.03351 1.29332 2.61339 + vertex 1.02904 1.28926 2.61425 + endloop + endfacet + facet normal 0.262847 -0.0571118 0.963146 + outer loop + vertex 1.02825 1.28354 2.61413 + vertex 1.03331 1.28818 2.61302 + vertex 1.02904 1.28926 2.61425 + endloop + endfacet + facet normal 0.279411 -0.0766384 0.957108 + outer loop + vertex 1.03321 1.28305 2.61264 + vertex 1.03331 1.28818 2.61302 + vertex 1.02825 1.28354 2.61413 + endloop + endfacet + facet normal 0.281199 -0.060495 0.957741 + outer loop + vertex 1.02873 1.27841 2.61366 + vertex 1.03321 1.28305 2.61264 + vertex 1.02825 1.28354 2.61413 + endloop + endfacet + facet normal 0.290499 -0.0702246 0.954295 + outer loop + vertex 1.03313 1.278 2.61229 + vertex 1.03321 1.28305 2.61264 + vertex 1.02873 1.27841 2.61366 + endloop + endfacet + facet normal 0.293349 -0.0418684 0.955088 + outer loop + vertex 1.02889 1.27351 2.6134 + vertex 1.03313 1.278 2.61229 + vertex 1.02873 1.27841 2.61366 + endloop + endfacet + facet normal 0.307575 -0.0566091 0.949838 + outer loop + vertex 1.03335 1.27286 2.61192 + vertex 1.03313 1.278 2.61229 + vertex 1.02889 1.27351 2.6134 + endloop + endfacet + facet normal 0.311516 -0.0293467 0.949788 + outer loop + vertex 1.02904 1.2686 2.6132 + vertex 1.03335 1.27286 2.61192 + vertex 1.02889 1.27351 2.6134 + endloop + endfacet + facet normal 0.258386 -0.0597856 0.96419 + outer loop + vertex 1.03701 1.27779 2.61124 + vertex 1.03313 1.278 2.61229 + vertex 1.03335 1.27286 2.61192 + endloop + endfacet + facet normal 0.271577 -0.0701801 0.959855 + outer loop + vertex 1.03718 1.27454 2.61096 + vertex 1.03701 1.27779 2.61124 + vertex 1.03335 1.27286 2.61192 + endloop + endfacet + facet normal 0.264559 -0.0523455 0.962948 + outer loop + vertex 1.03718 1.27454 2.61096 + vertex 1.03335 1.27286 2.61192 + vertex 1.03637 1.27069 2.61097 + endloop + endfacet + facet normal 0.200242 -0.0387687 0.978979 + outer loop + vertex 1.03995 1.27405 2.61037 + vertex 1.03718 1.27454 2.61096 + vertex 1.03637 1.27069 2.61097 + endloop + endfacet + facet normal 0.21194 -0.0517431 0.975912 + outer loop + vertex 1.03976 1.26949 2.61017 + vertex 1.03995 1.27405 2.61037 + vertex 1.03637 1.27069 2.61097 + endloop + endfacet + facet normal 0.216471 -0.0386482 0.975524 + outer loop + vertex 1.03595 1.26593 2.61087 + vertex 1.03976 1.26949 2.61017 + vertex 1.03637 1.27069 2.61097 + endloop + endfacet + facet normal 0.276832 -0.0437442 0.959922 + outer loop + vertex 1.03637 1.27069 2.61097 + vertex 1.03264 1.26746 2.6119 + vertex 1.03595 1.26593 2.61087 + endloop + endfacet + facet normal 0.28528 -0.0243275 0.958135 + outer loop + vertex 1.03264 1.26746 2.6119 + vertex 1.03224 1.26273 2.6119 + vertex 1.03595 1.26593 2.61087 + endloop + endfacet + facet normal 0.302757 -0.0466006 0.951928 + outer loop + vertex 1.03595 1.26593 2.61087 + vertex 1.03224 1.26273 2.6119 + vertex 1.03562 1.26108 2.61074 + endloop + endfacet + facet normal 0.235034 -0.042607 0.971053 + outer loop + vertex 1.03562 1.26108 2.61074 + vertex 1.03952 1.26456 2.60995 + vertex 1.03595 1.26593 2.61087 + endloop + endfacet + facet normal 0.252622 -0.0635893 0.965473 + outer loop + vertex 1.03918 1.25946 2.6097 + vertex 1.03952 1.26456 2.60995 + vertex 1.03562 1.26108 2.61074 + endloop + endfacet + facet normal 0.192588 -0.0602492 0.979428 + outer loop + vertex 1.03918 1.25946 2.6097 + vertex 1.04357 1.26346 2.60909 + vertex 1.03952 1.26456 2.60995 + endloop + endfacet + facet normal 0.190576 -0.0675969 0.979342 + outer loop + vertex 1.04357 1.26346 2.60909 + vertex 1.04371 1.26855 2.60941 + vertex 1.03952 1.26456 2.60995 + endloop + endfacet + facet normal 0.176611 -0.0524758 0.982881 + outer loop + vertex 1.03952 1.26456 2.60995 + vertex 1.04371 1.26855 2.60941 + vertex 1.03976 1.26949 2.61017 + endloop + endfacet + facet normal 0.17405 -0.0631119 0.982712 + outer loop + vertex 1.04371 1.26855 2.60941 + vertex 1.04378 1.2736 2.60972 + vertex 1.03976 1.26949 2.61017 + endloop + endfacet + facet normal 0.141386 -0.0629596 0.98795 + outer loop + vertex 1.04371 1.26855 2.60941 + vertex 1.04825 1.27301 2.60904 + vertex 1.04378 1.2736 2.60972 + endloop + endfacet + facet normal 0.139597 -0.0758815 0.987297 + outer loop + vertex 1.04825 1.27301 2.60904 + vertex 1.0483 1.2782 2.60944 + vertex 1.04378 1.2736 2.60972 + endloop + endfacet + facet normal 0.133374 -0.0697 0.988612 + outer loop + vertex 1.04378 1.2736 2.60972 + vertex 1.0483 1.2782 2.60944 + vertex 1.04361 1.2788 2.61011 + endloop + endfacet + facet normal 0.123705 -0.0758926 0.989413 + outer loop + vertex 1.04825 1.27301 2.60904 + vertex 1.05312 1.27783 2.6088 + vertex 1.0483 1.2782 2.60944 + endloop + endfacet + facet normal 0.12767 -0.0799429 0.98859 + outer loop + vertex 1.05313 1.27273 2.60839 + vertex 1.05312 1.27783 2.6088 + vertex 1.04825 1.27301 2.60904 + endloop + endfacet + facet normal 0.128116 -0.0732287 0.989052 + outer loop + vertex 1.04821 1.26791 2.60867 + vertex 1.05313 1.27273 2.60839 + vertex 1.04825 1.27301 2.60904 + endloop + endfacet + facet normal 0.134486 -0.0797955 0.987697 + outer loop + vertex 1.05316 1.2677 2.60798 + vertex 1.05313 1.27273 2.60839 + vertex 1.04821 1.26791 2.60867 + endloop + endfacet + facet normal 0.134554 -0.0785383 0.987789 + outer loop + vertex 1.0482 1.26285 2.60827 + vertex 1.05316 1.2677 2.60798 + vertex 1.04821 1.26791 2.60867 + endloop + endfacet + facet normal 0.142421 -0.0866963 0.986002 + outer loop + vertex 1.05326 1.26274 2.60753 + vertex 1.05316 1.2677 2.60798 + vertex 1.0482 1.26285 2.60827 + endloop + endfacet + facet normal 0.142318 -0.0897038 0.985748 + outer loop + vertex 1.04825 1.25783 2.60781 + vertex 1.05326 1.26274 2.60753 + vertex 1.0482 1.26285 2.60827 + endloop + endfacet + facet normal 0.150817 -0.0985053 0.983642 + outer loop + vertex 1.05348 1.25791 2.60701 + vertex 1.05326 1.26274 2.60753 + vertex 1.04825 1.25783 2.60781 + endloop + endfacet + facet normal 0.150814 -0.101907 0.983296 + outer loop + vertex 1.0484 1.25292 2.60728 + vertex 1.05348 1.25791 2.60701 + vertex 1.04825 1.25783 2.60781 + endloop + endfacet + facet normal 0.188144 -0.100084 0.977029 + outer loop + vertex 1.0484 1.25292 2.60728 + vertex 1.04825 1.25783 2.60781 + vertex 1.0433 1.2531 2.60828 + endloop + endfacet + facet normal 0.18846 -0.0939875 0.977573 + outer loop + vertex 1.04339 1.24809 2.60778 + vertex 1.0484 1.25292 2.60728 + vertex 1.0433 1.2531 2.60828 + endloop + endfacet + facet normal 0.206325 -0.113103 0.971925 + outer loop + vertex 1.04858 1.24794 2.60666 + vertex 1.0484 1.25292 2.60728 + vertex 1.04339 1.24809 2.60778 + endloop + endfacet + facet normal 0.164128 -0.11557 0.979646 + outer loop + vertex 1.0537 1.25319 2.60642 + vertex 1.0484 1.25292 2.60728 + vertex 1.04858 1.24794 2.60666 + endloop + endfacet + facet normal 0.187905 -0.139137 0.972282 + outer loop + vertex 1.05294 1.2495 2.60604 + vertex 1.0537 1.25319 2.60642 + vertex 1.04858 1.24794 2.60666 + endloop + endfacet + facet normal 0.184771 -0.129629 0.974195 + outer loop + vertex 1.05294 1.2495 2.60604 + vertex 1.04858 1.24794 2.60666 + vertex 1.0513 1.24592 2.60587 + endloop + endfacet + facet normal 0.147405 -0.112905 0.982611 + outer loop + vertex 1.05523 1.24858 2.60559 + vertex 1.05294 1.2495 2.60604 + vertex 1.0513 1.24592 2.60587 + endloop + endfacet + facet normal 0.148495 -0.114556 0.982256 + outer loop + vertex 1.05389 1.24381 2.60523 + vertex 1.05523 1.24858 2.60559 + vertex 1.0513 1.24592 2.60587 + endloop + endfacet + facet normal 0.152781 -0.109294 0.982198 + outer loop + vertex 1.04993 1.2424 2.60569 + vertex 1.05389 1.24381 2.60523 + vertex 1.0513 1.24592 2.60587 + endloop + endfacet + facet normal 0.203757 -0.128507 0.970551 + outer loop + vertex 1.0513 1.24592 2.60587 + vertex 1.04724 1.2429 2.60632 + vertex 1.04993 1.2424 2.60569 + endloop + endfacet + facet normal 0.207222 -0.111707 0.971895 + outer loop + vertex 1.04993 1.2424 2.60569 + vertex 1.04724 1.2429 2.60632 + vertex 1.04731 1.23975 2.60595 + endloop + endfacet + facet normal 0.191124 -0.0952785 0.976931 + outer loop + vertex 1.04993 1.2424 2.60569 + vertex 1.04731 1.23975 2.60595 + vertex 1.05005 1.23923 2.60536 + endloop + endfacet + facet normal 0.14884 -0.0976425 0.984029 + outer loop + vertex 1.04993 1.2424 2.60569 + vertex 1.05005 1.23923 2.60536 + vertex 1.05389 1.24381 2.60523 + endloop + endfacet + facet normal 0.157367 -0.104846 0.981959 + outer loop + vertex 1.05389 1.24381 2.60523 + vertex 1.05005 1.23923 2.60536 + vertex 1.05382 1.23871 2.6047 + endloop + endfacet + facet normal 0.159832 -0.0885347 0.983166 + outer loop + vertex 1.04947 1.23455 2.60503 + vertex 1.05382 1.23871 2.6047 + vertex 1.05005 1.23923 2.60536 + endloop + endfacet + facet normal 0.17175 -0.101235 0.979925 + outer loop + vertex 1.05344 1.23345 2.60422 + vertex 1.05382 1.23871 2.6047 + vertex 1.04947 1.23455 2.60503 + endloop + endfacet + facet normal 0.176463 -0.0847793 0.980649 + outer loop + vertex 1.04843 1.22885 2.60473 + vertex 1.05344 1.23345 2.60422 + vertex 1.04947 1.23455 2.60503 + endloop + endfacet + facet normal 0.190305 -0.100315 0.976586 + outer loop + vertex 1.05324 1.22812 2.60372 + vertex 1.05344 1.23345 2.60422 + vertex 1.04843 1.22885 2.60473 + endloop + endfacet + facet normal 0.192397 -0.0877063 0.97739 + outer loop + vertex 1.04875 1.22355 2.60419 + vertex 1.05324 1.22812 2.60372 + vertex 1.04843 1.22885 2.60473 + endloop + endfacet + facet normal 0.237086 -0.0840054 0.96785 + outer loop + vertex 1.04843 1.22885 2.60473 + vertex 1.04493 1.22414 2.60518 + vertex 1.04875 1.22355 2.60419 + endloop + endfacet + facet normal 0.240101 -0.0655121 0.968535 + outer loop + vertex 1.04475 1.21951 2.60491 + vertex 1.04875 1.22355 2.60419 + vertex 1.04493 1.22414 2.60518 + endloop + endfacet + facet normal 0.254386 -0.0804897 0.963747 + outer loop + vertex 1.04868 1.21846 2.60378 + vertex 1.04875 1.22355 2.60419 + vertex 1.04475 1.21951 2.60491 + endloop + endfacet + facet normal 0.224486 -0.0742944 0.971641 + outer loop + vertex 1.0445 1.2274 2.60553 + vertex 1.04493 1.22414 2.60518 + vertex 1.04843 1.22885 2.60473 + endloop + endfacet + facet normal 0.226795 -0.0811373 0.970557 + outer loop + vertex 1.0445 1.2274 2.60553 + vertex 1.04843 1.22885 2.60473 + vertex 1.04539 1.23122 2.60564 + endloop + endfacet + facet normal 0.290435 -0.0955122 0.952116 + outer loop + vertex 1.04539 1.23122 2.60564 + vertex 1.04182 1.22804 2.60641 + vertex 1.0445 1.2274 2.60553 + endloop + endfacet + facet normal 0.294815 -0.0775272 0.952404 + outer loop + vertex 1.0445 1.2274 2.60553 + vertex 1.04182 1.22804 2.60641 + vertex 1.04221 1.22482 2.60602 + endloop + endfacet + facet normal 0.273631 -0.0749901 0.958907 + outer loop + vertex 1.0422 1.23258 2.60665 + vertex 1.04182 1.22804 2.60641 + vertex 1.04539 1.23122 2.60564 + endloop + endfacet + facet normal 0.266956 -0.0910641 0.959397 + outer loop + vertex 1.04624 1.23592 2.60585 + vertex 1.0422 1.23258 2.60665 + vertex 1.04539 1.23122 2.60564 + endloop + endfacet + facet normal 0.210502 -0.0815918 0.974183 + outer loop + vertex 1.04539 1.23122 2.60564 + vertex 1.04947 1.23455 2.60503 + vertex 1.04624 1.23592 2.60585 + endloop + endfacet + facet normal 0.205447 -0.0935205 0.97419 + outer loop + vertex 1.04947 1.23455 2.60503 + vertex 1.05005 1.23923 2.60536 + vertex 1.04624 1.23592 2.60585 + endloop + endfacet + facet normal 0.194199 -0.0800571 0.97769 + outer loop + vertex 1.05005 1.23923 2.60536 + vertex 1.04731 1.23975 2.60595 + vertex 1.04624 1.23592 2.60585 + endloop + endfacet + facet normal 0.249526 -0.0951739 0.96368 + outer loop + vertex 1.04731 1.23975 2.60595 + vertex 1.04328 1.23806 2.60683 + vertex 1.04624 1.23592 2.60585 + endloop + endfacet + facet normal 0.254836 -0.10933 0.960784 + outer loop + vertex 1.04731 1.23975 2.60595 + vertex 1.04724 1.2429 2.60632 + vertex 1.04328 1.23806 2.60683 + endloop + endfacet + facet normal 0.234975 -0.0923533 0.967604 + outer loop + vertex 1.04724 1.2429 2.60632 + vertex 1.04322 1.24313 2.60732 + vertex 1.04328 1.23806 2.60683 + endloop + endfacet + facet normal 0.27699 -0.0908183 0.956571 + outer loop + vertex 1.04328 1.23806 2.60683 + vertex 1.04322 1.24313 2.60732 + vertex 1.03867 1.23867 2.60822 + endloop + endfacet + facet normal 0.280925 -0.0633916 0.957634 + outer loop + vertex 1.03847 1.23365 2.60794 + vertex 1.04328 1.23806 2.60683 + vertex 1.03867 1.23867 2.60822 + endloop + endfacet + facet normal 0.302545 -0.0891613 0.948956 + outer loop + vertex 1.0422 1.23258 2.60665 + vertex 1.04328 1.23806 2.60683 + vertex 1.03847 1.23365 2.60794 + endloop + endfacet + facet normal 0.311589 -0.0572171 0.948493 + outer loop + vertex 1.03827 1.22869 2.60771 + vertex 1.0422 1.23258 2.60665 + vertex 1.03847 1.23365 2.60794 + endloop + endfacet + facet normal 0.259081 -0.0712164 0.963226 + outer loop + vertex 1.03867 1.23867 2.60822 + vertex 1.04322 1.24313 2.60732 + vertex 1.03874 1.24362 2.60856 + endloop + endfacet + facet normal 0.319875 -0.070828 0.944809 + outer loop + vertex 1.03867 1.23867 2.60822 + vertex 1.03874 1.24362 2.60856 + vertex 1.0346 1.23962 2.60966 + endloop + endfacet + facet normal 0.325828 -0.0447208 0.944371 + outer loop + vertex 1.03453 1.23469 2.60946 + vertex 1.03867 1.23867 2.60822 + vertex 1.0346 1.23962 2.60966 + endloop + endfacet + facet normal 0.342877 -0.0647013 0.937149 + outer loop + vertex 1.03847 1.23365 2.60794 + vertex 1.03867 1.23867 2.60822 + vertex 1.03453 1.23469 2.60946 + endloop + endfacet + facet normal 0.349693 -0.037469 0.936115 + outer loop + vertex 1.03448 1.22977 2.60928 + vertex 1.03847 1.23365 2.60794 + vertex 1.03453 1.23469 2.60946 + endloop + endfacet + facet normal 0.367446 -0.0584388 0.928207 + outer loop + vertex 1.03827 1.22869 2.60771 + vertex 1.03847 1.23365 2.60794 + vertex 1.03448 1.22977 2.60928 + endloop + endfacet + facet normal 0.375379 -0.0281976 0.926443 + outer loop + vertex 1.03451 1.22484 2.60912 + vertex 1.03827 1.22869 2.60771 + vertex 1.03448 1.22977 2.60928 + endloop + endfacet + facet normal 0.391919 -0.0471539 0.918791 + outer loop + vertex 1.03858 1.22357 2.60731 + vertex 1.03827 1.22869 2.60771 + vertex 1.03451 1.22484 2.60912 + endloop + endfacet + facet normal 0.397847 -0.0256328 0.917094 + outer loop + vertex 1.03441 1.21977 2.60902 + vertex 1.03858 1.22357 2.60731 + vertex 1.03451 1.22484 2.60912 + endloop + endfacet + facet normal 0.418358 -0.0527731 0.906748 + outer loop + vertex 1.03778 1.21799 2.60736 + vertex 1.03858 1.22357 2.60731 + vertex 1.03441 1.21977 2.60902 + endloop + endfacet + facet normal 0.306304 -0.0552831 0.950327 + outer loop + vertex 1.0346 1.23962 2.60966 + vertex 1.03874 1.24362 2.60856 + vertex 1.03475 1.24452 2.6099 + endloop + endfacet + facet normal 0.301991 -0.0744548 0.950399 + outer loop + vertex 1.03874 1.24362 2.60856 + vertex 1.03875 1.24856 2.60895 + vertex 1.03475 1.24452 2.6099 + endloop + endfacet + facet normal 0.288441 -0.0597886 0.955629 + outer loop + vertex 1.03475 1.24452 2.6099 + vertex 1.03875 1.24856 2.60895 + vertex 1.03486 1.2491 2.61015 + endloop + endfacet + facet normal 0.286053 -0.0759427 0.9552 + outer loop + vertex 1.03835 1.25378 2.60948 + vertex 1.03486 1.2491 2.61015 + vertex 1.03875 1.24856 2.60895 + endloop + endfacet + facet normal 0.225628 -0.0822324 0.970737 + outer loop + vertex 1.03875 1.24856 2.60895 + vertex 1.0433 1.2531 2.60828 + vertex 1.03835 1.25378 2.60948 + endloop + endfacet + facet normal 0.224909 -0.0870001 0.970488 + outer loop + vertex 1.0433 1.2531 2.60828 + vertex 1.04336 1.25827 2.60873 + vertex 1.03835 1.25378 2.60948 + endloop + endfacet + facet normal 0.208824 -0.0681914 0.975573 + outer loop + vertex 1.03835 1.25378 2.60948 + vertex 1.04336 1.25827 2.60873 + vertex 1.03918 1.25946 2.6097 + endloop + endfacet + facet normal 0.235046 -0.092134 0.967608 + outer loop + vertex 1.04339 1.24809 2.60778 + vertex 1.0433 1.2531 2.60828 + vertex 1.03875 1.24856 2.60895 + endloop + endfacet + facet normal 0.280394 -0.0714416 0.957223 + outer loop + vertex 1.03441 1.25242 2.61053 + vertex 1.03486 1.2491 2.61015 + vertex 1.03835 1.25378 2.60948 + endloop + endfacet + facet normal 0.278874 -0.0664468 0.958026 + outer loop + vertex 1.03441 1.25242 2.61053 + vertex 1.03835 1.25378 2.60948 + vertex 1.03518 1.25627 2.61058 + endloop + endfacet + facet normal 0.367167 -0.0835866 0.926392 + outer loop + vertex 1.03518 1.25627 2.61058 + vertex 1.03171 1.25326 2.61168 + vertex 1.03441 1.25242 2.61053 + endloop + endfacet + facet normal 0.371527 -0.068853 0.925865 + outer loop + vertex 1.03441 1.25242 2.61053 + vertex 1.03171 1.25326 2.61168 + vertex 1.0321 1.24986 2.61127 + endloop + endfacet + facet normal 0.340331 -0.0480893 0.939075 + outer loop + vertex 1.03188 1.25792 2.61186 + vertex 1.03171 1.25326 2.61168 + vertex 1.03518 1.25627 2.61058 + endloop + endfacet + facet normal 0.333758 -0.0623908 0.940592 + outer loop + vertex 1.03562 1.26108 2.61074 + vertex 1.03188 1.25792 2.61186 + vertex 1.03518 1.25627 2.61058 + endloop + endfacet + facet normal 0.255936 -0.0560149 0.965069 + outer loop + vertex 1.03518 1.25627 2.61058 + vertex 1.03918 1.25946 2.6097 + vertex 1.03562 1.26108 2.61074 + endloop + endfacet + facet normal 0.271264 -0.0767633 0.959439 + outer loop + vertex 1.03835 1.25378 2.60948 + vertex 1.03918 1.25946 2.6097 + vertex 1.03518 1.25627 2.61058 + endloop + endfacet + facet normal 0.360589 -0.0575198 0.930949 + outer loop + vertex 1.03441 1.25242 2.61053 + vertex 1.0321 1.24986 2.61127 + vertex 1.03486 1.2491 2.61015 + endloop + endfacet + facet normal 0.236947 -0.0757108 0.968568 + outer loop + vertex 1.03874 1.24362 2.60856 + vertex 1.04339 1.24809 2.60778 + vertex 1.03875 1.24856 2.60895 + endloop + endfacet + facet normal 0.255944 -0.0966458 0.961848 + outer loop + vertex 1.04322 1.24313 2.60732 + vertex 1.04339 1.24809 2.60778 + vertex 1.03874 1.24362 2.60856 + endloop + endfacet + facet normal 0.207178 -0.0960738 0.973574 + outer loop + vertex 1.04322 1.24313 2.60732 + vertex 1.04858 1.24794 2.60666 + vertex 1.04339 1.24809 2.60778 + endloop + endfacet + facet normal 0.232292 -0.125301 0.964542 + outer loop + vertex 1.04724 1.2429 2.60632 + vertex 1.04858 1.24794 2.60666 + vertex 1.04322 1.24313 2.60732 + endloop + endfacet + facet normal 0.259297 -0.0810882 0.962387 + outer loop + vertex 1.04328 1.23806 2.60683 + vertex 1.0422 1.23258 2.60665 + vertex 1.04624 1.23592 2.60585 + endloop + endfacet + facet normal 0.330726 -0.0787249 0.940438 + outer loop + vertex 1.04182 1.22804 2.60641 + vertex 1.0422 1.23258 2.60665 + vertex 1.03827 1.22869 2.60771 + endloop + endfacet + facet normal 0.335618 -0.0522161 0.94055 + outer loop + vertex 1.04182 1.22804 2.60641 + vertex 1.03827 1.22869 2.60771 + vertex 1.03858 1.22357 2.60731 + endloop + endfacet + facet normal 0.354987 -0.0679217 0.932401 + outer loop + vertex 1.04221 1.22482 2.60602 + vertex 1.04182 1.22804 2.60641 + vertex 1.03858 1.22357 2.60731 + endloop + endfacet + facet normal 0.35296 -0.0607287 0.933666 + outer loop + vertex 1.04221 1.22482 2.60602 + vertex 1.03858 1.22357 2.60731 + vertex 1.04147 1.22099 2.60606 + endloop + endfacet + facet normal 0.286199 -0.0475996 0.956987 + outer loop + vertex 1.04493 1.22414 2.60518 + vertex 1.04221 1.22482 2.60602 + vertex 1.04147 1.22099 2.60606 + endloop + endfacet + facet normal 0.302191 -0.0668867 0.950898 + outer loop + vertex 1.04475 1.21951 2.60491 + vertex 1.04493 1.22414 2.60518 + vertex 1.04147 1.22099 2.60606 + endloop + endfacet + facet normal 0.307649 -0.0540526 0.949963 + outer loop + vertex 1.04096 1.2161 2.60594 + vertex 1.04475 1.21951 2.60491 + vertex 1.04147 1.22099 2.60606 + endloop + endfacet + facet normal 0.376193 -0.0605516 0.924561 + outer loop + vertex 1.04147 1.22099 2.60606 + vertex 1.03778 1.21799 2.60736 + vertex 1.04096 1.2161 2.60594 + endloop + endfacet + facet normal 0.321598 -0.0713052 0.944188 + outer loop + vertex 1.04436 1.21438 2.60465 + vertex 1.04475 1.21951 2.60491 + vertex 1.04096 1.2161 2.60594 + endloop + endfacet + facet normal 0.324118 -0.0659708 0.943714 + outer loop + vertex 1.04044 1.21116 2.60577 + vertex 1.04436 1.21438 2.60465 + vertex 1.04096 1.2161 2.60594 + endloop + endfacet + facet normal 0.39311 -0.0723225 0.916643 + outer loop + vertex 1.04096 1.2161 2.60594 + vertex 1.03739 1.21296 2.60722 + vertex 1.04044 1.21116 2.60577 + endloop + endfacet + facet normal 0.392254 -0.0739703 0.916878 + outer loop + vertex 1.03739 1.21296 2.60722 + vertex 1.03718 1.20834 2.60694 + vertex 1.04044 1.21116 2.60577 + endloop + endfacet + facet normal 0.407387 -0.0949816 0.908303 + outer loop + vertex 1.04044 1.21116 2.60577 + vertex 1.03718 1.20834 2.60694 + vertex 1.03967 1.20727 2.60572 + endloop + endfacet + facet normal 0.379585 -0.0541251 0.923572 + outer loop + vertex 1.03778 1.21799 2.60736 + vertex 1.03739 1.21296 2.60722 + vertex 1.04096 1.2161 2.60594 + endloop + endfacet + facet normal 0.335899 -0.0822272 0.938302 + outer loop + vertex 1.04352 1.20863 2.60445 + vertex 1.04436 1.21438 2.60465 + vertex 1.04044 1.21116 2.60577 + endloop + endfacet + facet normal 0.33656 -0.0813399 0.938142 + outer loop + vertex 1.03967 1.20727 2.60572 + vertex 1.04352 1.20863 2.60445 + vertex 1.04044 1.21116 2.60577 + endloop + endfacet + facet normal 0.257892 -0.0673858 0.963821 + outer loop + vertex 1.04436 1.21438 2.60465 + vertex 1.04868 1.21846 2.60378 + vertex 1.04475 1.21951 2.60491 + endloop + endfacet + facet normal 0.269359 -0.0803966 0.959678 + outer loop + vertex 1.04847 1.21329 2.60341 + vertex 1.04868 1.21846 2.60378 + vertex 1.04436 1.21438 2.60465 + endloop + endfacet + facet normal 0.271194 -0.073479 0.959716 + outer loop + vertex 1.04352 1.20863 2.60445 + vertex 1.04847 1.21329 2.60341 + vertex 1.04436 1.21438 2.60465 + endloop + endfacet + facet normal 0.28514 -0.0895323 0.954295 + outer loop + vertex 1.04839 1.2081 2.60295 + vertex 1.04847 1.21329 2.60341 + vertex 1.04352 1.20863 2.60445 + endloop + endfacet + facet normal 0.365368 -0.0449693 0.929776 + outer loop + vertex 1.03858 1.22357 2.60731 + vertex 1.03778 1.21799 2.60736 + vertex 1.04147 1.22099 2.60606 + endloop + endfacet + facet normal 0.2186 -0.0920145 0.971467 + outer loop + vertex 1.04843 1.22885 2.60473 + vertex 1.04947 1.23455 2.60503 + vertex 1.04539 1.23122 2.60564 + endloop + endfacet + facet normal 0.281897 -0.0651312 0.957232 + outer loop + vertex 1.0445 1.2274 2.60553 + vertex 1.04221 1.22482 2.60602 + vertex 1.04493 1.22414 2.60518 + endloop + endfacet + facet normal 0.201421 -0.0968465 0.974705 + outer loop + vertex 1.05327 1.223 2.6032 + vertex 1.05324 1.22812 2.60372 + vertex 1.04875 1.22355 2.60419 + endloop + endfacet + facet normal 0.203636 -0.0807327 0.975712 + outer loop + vertex 1.04868 1.21846 2.60378 + vertex 1.05327 1.223 2.6032 + vertex 1.04875 1.22355 2.60419 + endloop + endfacet + facet normal 0.215819 -0.0935444 0.971942 + outer loop + vertex 1.05326 1.21804 2.60273 + vertex 1.05327 1.223 2.6032 + vertex 1.04868 1.21846 2.60378 + endloop + endfacet + facet normal 0.12077 -0.107085 0.986888 + outer loop + vertex 1.05389 1.24381 2.60523 + vertex 1.05878 1.24822 2.60511 + vertex 1.05523 1.24858 2.60559 + endloop + endfacet + facet normal 0.119373 -0.119265 0.98566 + outer loop + vertex 1.0587 1.25203 2.60559 + vertex 1.05523 1.24858 2.60559 + vertex 1.05878 1.24822 2.60511 + endloop + endfacet + facet normal 0.110096 -0.119597 0.986699 + outer loop + vertex 1.05878 1.24822 2.60511 + vertex 1.06335 1.25337 2.60523 + vertex 1.0587 1.25203 2.60559 + endloop + endfacet + facet normal 0.111603 -0.125017 0.985858 + outer loop + vertex 1.0587 1.25203 2.60559 + vertex 1.06335 1.25337 2.60523 + vertex 1.06126 1.25593 2.60579 + endloop + endfacet + facet normal 0.115943 -0.127824 0.984997 + outer loop + vertex 1.0577 1.25422 2.60599 + vertex 1.0587 1.25203 2.60559 + vertex 1.06126 1.25593 2.60579 + endloop + endfacet + facet normal 0.112559 -0.120629 0.986296 + outer loop + vertex 1.06126 1.25593 2.60579 + vertex 1.0589 1.25824 2.60634 + vertex 1.0577 1.25422 2.60599 + endloop + endfacet + facet normal 0.138763 -0.128065 0.98201 + outer loop + vertex 1.0577 1.25422 2.60599 + vertex 1.0589 1.25824 2.60634 + vertex 1.0537 1.25319 2.60642 + endloop + endfacet + facet normal 0.142156 -0.142268 0.979567 + outer loop + vertex 1.0577 1.25422 2.60599 + vertex 1.0537 1.25319 2.60642 + vertex 1.05571 1.25157 2.60589 + endloop + endfacet + facet normal 0.150416 -0.132132 0.979753 + outer loop + vertex 1.05571 1.25157 2.60589 + vertex 1.0537 1.25319 2.60642 + vertex 1.05294 1.2495 2.60604 + endloop + endfacet + facet normal 0.128969 -0.117939 0.98461 + outer loop + vertex 1.0589 1.25824 2.60634 + vertex 1.05348 1.25791 2.60701 + vertex 1.0537 1.25319 2.60642 + endloop + endfacet + facet normal 0.128309 -0.103563 0.986312 + outer loop + vertex 1.0589 1.25824 2.60634 + vertex 1.05847 1.26298 2.6069 + vertex 1.05348 1.25791 2.60701 + endloop + endfacet + facet normal 0.111696 -0.105293 0.988148 + outer loop + vertex 1.0589 1.25824 2.60634 + vertex 1.06353 1.26361 2.60639 + vertex 1.05847 1.26298 2.6069 + endloop + endfacet + facet normal 0.11008 -0.0909601 0.989752 + outer loop + vertex 1.06353 1.26361 2.60639 + vertex 1.06335 1.26805 2.60682 + vertex 1.05847 1.26298 2.6069 + endloop + endfacet + facet normal 0.110361 -0.0912319 0.989696 + outer loop + vertex 1.05847 1.26298 2.6069 + vertex 1.06335 1.26805 2.60682 + vertex 1.05828 1.26777 2.60736 + endloop + endfacet + facet normal 0.124451 -0.0905058 0.988089 + outer loop + vertex 1.05847 1.26298 2.6069 + vertex 1.05828 1.26777 2.60736 + vertex 1.05326 1.26274 2.60753 + endloop + endfacet + facet normal 0.109975 -0.0825526 0.9905 + outer loop + vertex 1.06335 1.26805 2.60682 + vertex 1.06328 1.27282 2.60722 + vertex 1.05828 1.26777 2.60736 + endloop + endfacet + facet normal 0.10997 -0.0825477 0.990501 + outer loop + vertex 1.05828 1.26777 2.60736 + vertex 1.06328 1.27282 2.60722 + vertex 1.0582 1.27272 2.60778 + endloop + endfacet + facet normal 0.12133 -0.0822647 0.989197 + outer loop + vertex 1.05828 1.26777 2.60736 + vertex 1.0582 1.27272 2.60778 + vertex 1.05316 1.2677 2.60798 + endloop + endfacet + facet normal 0.109935 -0.0794923 0.990755 + outer loop + vertex 1.06328 1.27282 2.60722 + vertex 1.06325 1.27778 2.60763 + vertex 1.0582 1.27272 2.60778 + endloop + endfacet + facet normal 0.111676 -0.0812376 0.990419 + outer loop + vertex 1.0582 1.27272 2.60778 + vertex 1.06325 1.27778 2.60763 + vertex 1.05817 1.27775 2.6082 + endloop + endfacet + facet normal 0.119131 -0.0811174 0.989559 + outer loop + vertex 1.0582 1.27272 2.60778 + vertex 1.05817 1.27775 2.6082 + vertex 1.05313 1.27273 2.60839 + endloop + endfacet + facet normal 0.111668 -0.0843459 0.99016 + outer loop + vertex 1.06325 1.27778 2.60763 + vertex 1.06321 1.28279 2.60806 + vertex 1.05817 1.27775 2.6082 + endloop + endfacet + facet normal 0.114698 -0.0873886 0.989549 + outer loop + vertex 1.05817 1.27775 2.6082 + vertex 1.06321 1.28279 2.60806 + vertex 1.05814 1.28282 2.60865 + endloop + endfacet + facet normal 0.117876 -0.0873389 0.98918 + outer loop + vertex 1.05817 1.27775 2.6082 + vertex 1.05814 1.28282 2.60865 + vertex 1.05312 1.27783 2.6088 + endloop + endfacet + facet normal 0.114561 -0.0958489 0.988781 + outer loop + vertex 1.06321 1.28279 2.60806 + vertex 1.06315 1.28784 2.60855 + vertex 1.05814 1.28282 2.60865 + endloop + endfacet + facet normal 0.117576 -0.0988749 0.988129 + outer loop + vertex 1.05814 1.28282 2.60865 + vertex 1.06315 1.28784 2.60855 + vertex 1.05816 1.28798 2.60916 + endloop + endfacet + facet normal 0.118078 -0.0988707 0.98807 + outer loop + vertex 1.05814 1.28282 2.60865 + vertex 1.05816 1.28798 2.60916 + vertex 1.05319 1.28302 2.60926 + endloop + endfacet + facet normal 0.118637 -0.0881096 0.989021 + outer loop + vertex 1.05312 1.27783 2.6088 + vertex 1.05814 1.28282 2.60865 + vertex 1.05319 1.28302 2.60926 + endloop + endfacet + facet normal 0.122663 -0.0881195 0.988529 + outer loop + vertex 1.05312 1.27783 2.6088 + vertex 1.05319 1.28302 2.60926 + vertex 1.0483 1.2782 2.60944 + endloop + endfacet + facet normal 0.119237 -0.0846182 0.989253 + outer loop + vertex 1.0483 1.2782 2.60944 + vertex 1.05319 1.28302 2.60926 + vertex 1.04859 1.28345 2.60985 + endloop + endfacet + facet normal 0.131269 -0.085165 0.987682 + outer loop + vertex 1.0483 1.2782 2.60944 + vertex 1.04859 1.28345 2.60985 + vertex 1.04361 1.2788 2.61011 + endloop + endfacet + facet normal 0.123954 -0.0772598 0.989276 + outer loop + vertex 1.04361 1.2788 2.61011 + vertex 1.04859 1.28345 2.60985 + vertex 1.04487 1.28405 2.61036 + endloop + endfacet + facet normal 0.148422 -0.0829448 0.98544 + outer loop + vertex 1.04361 1.2788 2.61011 + vertex 1.04487 1.28405 2.61036 + vertex 1.04092 1.28101 2.6107 + endloop + endfacet + facet normal 0.154533 -0.0754295 0.985104 + outer loop + vertex 1.03965 1.27727 2.61061 + vertex 1.04361 1.2788 2.61011 + vertex 1.04092 1.28101 2.6107 + endloop + endfacet + facet normal 0.212295 -0.0946331 0.972613 + outer loop + vertex 1.04092 1.28101 2.6107 + vertex 1.03701 1.27779 2.61124 + vertex 1.03965 1.27727 2.61061 + endloop + endfacet + facet normal 0.207107 -0.0880608 0.974347 + outer loop + vertex 1.03827 1.28305 2.61145 + vertex 1.03701 1.27779 2.61124 + vertex 1.04092 1.28101 2.6107 + endloop + endfacet + facet normal 0.196695 -0.101896 0.975155 + outer loop + vertex 1.04247 1.28489 2.6108 + vertex 1.03827 1.28305 2.61145 + vertex 1.04092 1.28101 2.6107 + endloop + endfacet + facet normal 0.203387 -0.11833 0.971922 + outer loop + vertex 1.04247 1.28489 2.6108 + vertex 1.04322 1.28872 2.6111 + vertex 1.03827 1.28305 2.61145 + endloop + endfacet + facet normal 0.177468 -0.0951723 0.979514 + outer loop + vertex 1.04322 1.28872 2.6111 + vertex 1.03822 1.28809 2.61195 + vertex 1.03827 1.28305 2.61145 + endloop + endfacet + facet normal 0.228364 -0.0936393 0.969062 + outer loop + vertex 1.03827 1.28305 2.61145 + vertex 1.03822 1.28809 2.61195 + vertex 1.03321 1.28305 2.61264 + endloop + endfacet + facet normal 0.228794 -0.0703847 0.970927 + outer loop + vertex 1.03313 1.278 2.61229 + vertex 1.03827 1.28305 2.61145 + vertex 1.03321 1.28305 2.61264 + endloop + endfacet + facet normal 0.21196 -0.076616 0.97427 + outer loop + vertex 1.03321 1.28305 2.61264 + vertex 1.03822 1.28809 2.61195 + vertex 1.03331 1.28818 2.61302 + endloop + endfacet + facet normal 0.178894 -0.108749 0.97784 + outer loop + vertex 1.04322 1.28872 2.6111 + vertex 1.04324 1.29324 2.6116 + vertex 1.03822 1.28809 2.61195 + endloop + endfacet + facet normal 0.163622 -0.0935573 0.982077 + outer loop + vertex 1.03822 1.28809 2.61195 + vertex 1.04324 1.29324 2.6116 + vertex 1.03825 1.29291 2.6124 + endloop + endfacet + facet normal 0.164145 -0.104373 0.980899 + outer loop + vertex 1.04324 1.29324 2.6116 + vertex 1.04327 1.29782 2.61208 + vertex 1.03825 1.29291 2.6124 + endloop + endfacet + facet normal 0.131772 -0.104672 0.985738 + outer loop + vertex 1.04324 1.29324 2.6116 + vertex 1.04828 1.29833 2.61147 + vertex 1.04327 1.29782 2.61208 + endloop + endfacet + facet normal 0.132031 -0.107701 0.985377 + outer loop + vertex 1.04828 1.29833 2.61147 + vertex 1.04835 1.30285 2.61195 + vertex 1.04327 1.29782 2.61208 + endloop + endfacet + facet normal 0.128783 -0.104396 0.986162 + outer loop + vertex 1.04327 1.29782 2.61208 + vertex 1.04835 1.30285 2.61195 + vertex 1.04324 1.30263 2.6126 + endloop + endfacet + facet normal 0.128844 -0.106522 0.985927 + outer loop + vertex 1.04835 1.30285 2.61195 + vertex 1.04831 1.30763 2.61248 + vertex 1.04324 1.30263 2.6126 + endloop + endfacet + facet normal 0.125251 -0.102863 0.986778 + outer loop + vertex 1.04324 1.30263 2.6126 + vertex 1.04831 1.30763 2.61248 + vertex 1.04317 1.30765 2.61313 + endloop + endfacet + facet normal 0.111839 -0.1069 0.98796 + outer loop + vertex 1.04835 1.30285 2.61195 + vertex 1.0534 1.30789 2.61193 + vertex 1.04831 1.30763 2.61248 + endloop + endfacet + facet normal 0.111804 -0.10599 0.988062 + outer loop + vertex 1.0534 1.30789 2.61193 + vertex 1.05335 1.3127 2.61245 + vertex 1.04831 1.30763 2.61248 + endloop + endfacet + facet normal 0.111402 -0.105589 0.98815 + outer loop + vertex 1.04831 1.30763 2.61248 + vertex 1.05335 1.3127 2.61245 + vertex 1.04822 1.31264 2.61302 + endloop + endfacet + facet normal 0.111402 -0.105418 0.988168 + outer loop + vertex 1.05335 1.3127 2.61245 + vertex 1.05326 1.31769 2.61299 + vertex 1.04822 1.31264 2.61302 + endloop + endfacet + facet normal 0.106209 -0.10558 0.988723 + outer loop + vertex 1.05335 1.3127 2.61245 + vertex 1.05834 1.31775 2.61245 + vertex 1.05326 1.31769 2.61299 + endloop + endfacet + facet normal 0.106208 -0.104717 0.988814 + outer loop + vertex 1.05834 1.31775 2.61245 + vertex 1.05824 1.32273 2.61299 + vertex 1.05326 1.31769 2.61299 + endloop + endfacet + facet normal 0.106736 -0.105239 0.988702 + outer loop + vertex 1.05326 1.31769 2.61299 + vertex 1.05824 1.32273 2.61299 + vertex 1.05316 1.32274 2.61354 + endloop + endfacet + facet normal 0.10674 -0.104956 0.988732 + outer loop + vertex 1.05824 1.32273 2.61299 + vertex 1.05815 1.32776 2.61353 + vertex 1.05316 1.32274 2.61354 + endloop + endfacet + facet normal 0.103194 -0.10506 0.989097 + outer loop + vertex 1.05824 1.32273 2.61299 + vertex 1.06323 1.32774 2.613 + vertex 1.05815 1.32776 2.61353 + endloop + endfacet + facet normal 0.1041 -0.10596 0.988906 + outer loop + vertex 1.06331 1.32277 2.61246 + vertex 1.06323 1.32774 2.613 + vertex 1.05824 1.32273 2.61299 + endloop + endfacet + facet normal 0.0934394 -0.10624 0.989941 + outer loop + vertex 1.06331 1.32277 2.61246 + vertex 1.06831 1.32782 2.61253 + vertex 1.06323 1.32774 2.613 + endloop + endfacet + facet normal 0.0934583 -0.110124 0.989514 + outer loop + vertex 1.06831 1.32782 2.61253 + vertex 1.06827 1.33279 2.61309 + vertex 1.06323 1.32774 2.613 + endloop + endfacet + facet normal 0.0904811 -0.107159 0.990116 + outer loop + vertex 1.06323 1.32774 2.613 + vertex 1.06827 1.33279 2.61309 + vertex 1.06317 1.33276 2.61355 + endloop + endfacet + facet normal 0.0729118 -0.110501 0.991198 + outer loop + vertex 1.06831 1.32782 2.61253 + vertex 1.07337 1.33292 2.61273 + vertex 1.06827 1.33279 2.61309 + endloop + endfacet + facet normal 0.0729715 -0.113951 0.990803 + outer loop + vertex 1.07337 1.33292 2.61273 + vertex 1.07337 1.33791 2.6133 + vertex 1.06827 1.33279 2.61309 + endloop + endfacet + facet normal 0.0711006 -0.112101 0.99115 + outer loop + vertex 1.06827 1.33279 2.61309 + vertex 1.07337 1.33791 2.6133 + vertex 1.06825 1.3378 2.61366 + endloop + endfacet + facet normal 0.0654572 -0.114015 0.99132 + outer loop + vertex 1.07337 1.33292 2.61273 + vertex 1.07835 1.33803 2.61299 + vertex 1.07337 1.33791 2.6133 + endloop + endfacet + facet normal 0.0653553 -0.107938 0.992007 + outer loop + vertex 1.07835 1.33803 2.61299 + vertex 1.07839 1.34302 2.61353 + vertex 1.07337 1.33791 2.6133 + endloop + endfacet + facet normal 0.0714006 -0.113822 0.990932 + outer loop + vertex 1.07337 1.33791 2.6133 + vertex 1.07839 1.34302 2.61353 + vertex 1.07339 1.34291 2.61387 + endloop + endfacet + facet normal 0.113617 -0.107855 0.987653 + outer loop + vertex 1.07835 1.33803 2.61299 + vertex 1.08299 1.34294 2.61299 + vertex 1.07839 1.34302 2.61353 + endloop + endfacet + facet normal 0.114199 -0.0887524 0.989486 + outer loop + vertex 1.08299 1.34294 2.61299 + vertex 1.08306 1.34791 2.61343 + vertex 1.07839 1.34302 2.61353 + endloop + endfacet + facet normal 0.130734 -0.104642 0.98588 + outer loop + vertex 1.07839 1.34302 2.61353 + vertex 1.08306 1.34791 2.61343 + vertex 1.07843 1.34802 2.61405 + endloop + endfacet + facet normal 0.0934316 -0.0887627 0.991661 + outer loop + vertex 1.08296 1.33788 2.61254 + vertex 1.08299 1.34294 2.61299 + vertex 1.07835 1.33803 2.61299 + endloop + endfacet + facet normal 0.0926399 -0.108174 0.989806 + outer loop + vertex 1.07838 1.33298 2.61243 + vertex 1.08296 1.33788 2.61254 + vertex 1.07835 1.33803 2.61299 + endloop + endfacet + facet normal 0.0731148 -0.0899987 0.993254 + outer loop + vertex 1.08316 1.33271 2.61206 + vertex 1.08296 1.33788 2.61254 + vertex 1.07838 1.33298 2.61243 + endloop + endfacet + facet normal 0.0717238 -0.111466 0.991177 + outer loop + vertex 1.07859 1.32793 2.61185 + vertex 1.08316 1.33271 2.61206 + vertex 1.07838 1.33298 2.61243 + endloop + endfacet + facet normal 0.0577027 -0.112129 0.992017 + outer loop + vertex 1.07859 1.32793 2.61185 + vertex 1.07838 1.33298 2.61243 + vertex 1.07343 1.32797 2.61215 + endloop + endfacet + facet normal 0.0576134 -0.117907 0.991352 + outer loop + vertex 1.07351 1.3232 2.61158 + vertex 1.07859 1.32793 2.61185 + vertex 1.07343 1.32797 2.61215 + endloop + endfacet + facet normal 0.083319 -0.11727 0.989599 + outer loop + vertex 1.07351 1.3232 2.61158 + vertex 1.07343 1.32797 2.61215 + vertex 1.06838 1.32296 2.61198 + endloop + endfacet + facet normal 0.0830358 -0.109849 0.990474 + outer loop + vertex 1.0684 1.31831 2.61147 + vertex 1.07351 1.3232 2.61158 + vertex 1.06838 1.32296 2.61198 + endloop + endfacet + facet normal 0.10158 -0.109556 0.988777 + outer loop + vertex 1.0684 1.31831 2.61147 + vertex 1.06838 1.32296 2.61198 + vertex 1.06337 1.31793 2.61194 + endloop + endfacet + facet normal 0.101184 -0.103382 0.989482 + outer loop + vertex 1.06336 1.31331 2.61146 + vertex 1.0684 1.31831 2.61147 + vertex 1.06337 1.31793 2.61194 + endloop + endfacet + facet normal 0.103132 -0.103367 0.989282 + outer loop + vertex 1.06336 1.31331 2.61146 + vertex 1.06337 1.31793 2.61194 + vertex 1.0584 1.31292 2.61194 + endloop + endfacet + facet normal 0.103188 -0.104173 0.989192 + outer loop + vertex 1.05835 1.30832 2.61146 + vertex 1.06336 1.31331 2.61146 + vertex 1.0584 1.31292 2.61194 + endloop + endfacet + facet normal 0.103003 -0.104173 0.989211 + outer loop + vertex 1.05835 1.30832 2.61146 + vertex 1.0584 1.31292 2.61194 + vertex 1.0534 1.30789 2.61193 + endloop + endfacet + facet normal 0.103211 -0.10691 0.988897 + outer loop + vertex 1.05333 1.30335 2.61144 + vertex 1.05835 1.30832 2.61146 + vertex 1.0534 1.30789 2.61193 + endloop + endfacet + facet normal 0.102203 -0.105894 0.989111 + outer loop + vertex 1.05814 1.30389 2.61101 + vertex 1.05835 1.30832 2.61146 + vertex 1.05333 1.30335 2.61144 + endloop + endfacet + facet normal 0.102594 -0.109681 0.988658 + outer loop + vertex 1.05814 1.30389 2.61101 + vertex 1.05333 1.30335 2.61144 + vertex 1.0531 1.29897 2.61098 + endloop + endfacet + facet normal 0.105231 -0.112377 0.988078 + outer loop + vertex 1.05691 1.30024 2.61072 + vertex 1.05814 1.30389 2.61101 + vertex 1.0531 1.29897 2.61098 + endloop + endfacet + facet normal 0.103983 -0.111971 0.988256 + outer loop + vertex 1.05985 1.30223 2.61064 + vertex 1.05814 1.30389 2.61101 + vertex 1.05691 1.30024 2.61072 + endloop + endfacet + facet normal 0.108978 -0.119398 0.986847 + outer loop + vertex 1.05985 1.30223 2.61064 + vertex 1.05691 1.30024 2.61072 + vertex 1.0586 1.29833 2.6103 + endloop + endfacet + facet normal 0.114111 -0.120985 0.986074 + outer loop + vertex 1.05985 1.30223 2.61064 + vertex 1.0586 1.29833 2.6103 + vertex 1.06366 1.30325 2.61032 + endloop + endfacet + facet normal 0.113677 -0.119271 0.986333 + outer loop + vertex 1.06366 1.30325 2.61032 + vertex 1.06196 1.30511 2.61074 + vertex 1.05985 1.30223 2.61064 + endloop + endfacet + facet normal 0.114101 -0.118884 0.98633 + outer loop + vertex 1.06493 1.30715 2.61064 + vertex 1.06196 1.30511 2.61074 + vertex 1.06366 1.30325 2.61032 + endloop + endfacet + facet normal 0.108728 -0.117203 0.987138 + outer loop + vertex 1.06493 1.30715 2.61064 + vertex 1.06366 1.30325 2.61032 + vertex 1.06879 1.30823 2.61035 + endloop + endfacet + facet normal 0.105473 -0.105094 0.988853 + outer loop + vertex 1.06879 1.30823 2.61035 + vertex 1.06706 1.31009 2.61073 + vertex 1.06493 1.30715 2.61064 + endloop + endfacet + facet normal 0.106874 -0.1061 0.988595 + outer loop + vertex 1.06706 1.31009 2.61073 + vertex 1.06318 1.30882 2.61101 + vertex 1.06493 1.30715 2.61064 + endloop + endfacet + facet normal 0.106232 -0.104077 0.98888 + outer loop + vertex 1.06706 1.31009 2.61073 + vertex 1.06828 1.31383 2.61099 + vertex 1.06318 1.30882 2.61101 + endloop + endfacet + facet normal 0.105014 -0.102837 0.989139 + outer loop + vertex 1.06828 1.31383 2.61099 + vertex 1.06336 1.31331 2.61146 + vertex 1.06318 1.30882 2.61101 + endloop + endfacet + facet normal 0.104146 -0.103417 0.989171 + outer loop + vertex 1.07008 1.31218 2.61063 + vertex 1.06828 1.31383 2.61099 + vertex 1.06706 1.31009 2.61073 + endloop + endfacet + facet normal 0.102418 -0.105292 0.989153 + outer loop + vertex 1.07225 1.31511 2.61072 + vertex 1.06828 1.31383 2.61099 + vertex 1.07008 1.31218 2.61063 + endloop + endfacet + facet normal 0.0779064 -0.0872779 0.993133 + outer loop + vertex 1.07396 1.31314 2.61041 + vertex 1.07225 1.31511 2.61072 + vertex 1.07008 1.31218 2.61063 + endloop + endfacet + facet normal 0.0803241 -0.097248 0.992014 + outer loop + vertex 1.07008 1.31218 2.61063 + vertex 1.06879 1.30823 2.61035 + vertex 1.07396 1.31314 2.61041 + endloop + endfacet + facet normal 0.0821625 -0.0991775 0.991672 + outer loop + vertex 1.07396 1.31314 2.61041 + vertex 1.06879 1.30823 2.61035 + vertex 1.07357 1.30814 2.60994 + endloop + endfacet + facet normal 0.0506538 -0.0969294 0.994001 + outer loop + vertex 1.07357 1.30814 2.60994 + vertex 1.07854 1.31285 2.61015 + vertex 1.07396 1.31314 2.61041 + endloop + endfacet + facet normal 0.0508503 -0.0940968 0.994264 + outer loop + vertex 1.07895 1.31745 2.61056 + vertex 1.07396 1.31314 2.61041 + vertex 1.07854 1.31285 2.61015 + endloop + endfacet + facet normal 0.0489615 -0.0939375 0.994373 + outer loop + vertex 1.07854 1.31285 2.61015 + vertex 1.08254 1.31666 2.61031 + vertex 1.07895 1.31745 2.61056 + endloop + endfacet + facet normal 0.0427676 -0.121172 0.99171 + outer loop + vertex 1.08359 1.32057 2.61074 + vertex 1.07895 1.31745 2.61056 + vertex 1.08254 1.31666 2.61031 + endloop + endfacet + facet normal 0.0314578 -0.104502 0.994027 + outer loop + vertex 1.0804 1.32098 2.61089 + vertex 1.07895 1.31745 2.61056 + vertex 1.08359 1.32057 2.61074 + endloop + endfacet + facet normal 0.0268978 -0.138295 0.990026 + outer loop + vertex 1.08359 1.32057 2.61074 + vertex 1.08252 1.32323 2.61114 + vertex 1.0804 1.32098 2.61089 + endloop + endfacet + facet normal 0.0298465 -0.141027 0.989556 + outer loop + vertex 1.08252 1.32323 2.61114 + vertex 1.07866 1.32311 2.61124 + vertex 1.0804 1.32098 2.61089 + endloop + endfacet + facet normal 0.0404128 -0.132568 0.99035 + outer loop + vertex 1.0804 1.32098 2.61089 + vertex 1.07866 1.32311 2.61124 + vertex 1.07746 1.31966 2.61083 + endloop + endfacet + facet normal 0.0825786 -0.146697 0.985729 + outer loop + vertex 1.07746 1.31966 2.61083 + vertex 1.07866 1.32311 2.61124 + vertex 1.07346 1.31872 2.61103 + endloop + endfacet + facet normal 0.0776661 -0.124895 0.989126 + outer loop + vertex 1.07746 1.31966 2.61083 + vertex 1.07346 1.31872 2.61103 + vertex 1.07529 1.31701 2.61067 + endloop + endfacet + facet normal 0.0396105 -0.0940441 0.99478 + outer loop + vertex 1.07895 1.31745 2.61056 + vertex 1.07746 1.31966 2.61083 + vertex 1.07529 1.31701 2.61067 + endloop + endfacet + facet normal 0.0878104 -0.114153 0.989575 + outer loop + vertex 1.07529 1.31701 2.61067 + vertex 1.07346 1.31872 2.61103 + vertex 1.07225 1.31511 2.61072 + endloop + endfacet + facet normal 0.0627134 -0.123371 0.990377 + outer loop + vertex 1.07866 1.32311 2.61124 + vertex 1.07351 1.3232 2.61158 + vertex 1.07346 1.31872 2.61103 + endloop + endfacet + facet normal 0.0286946 -0.098606 0.994713 + outer loop + vertex 1.08252 1.32323 2.61114 + vertex 1.08399 1.32718 2.61149 + vertex 1.07866 1.32311 2.61124 + endloop + endfacet + facet normal 0.047985 -0.123667 0.991163 + outer loop + vertex 1.08399 1.32718 2.61149 + vertex 1.07859 1.32793 2.61185 + vertex 1.07866 1.32311 2.61124 + endloop + endfacet + facet normal 0.0268179 -0.10264 0.994357 + outer loop + vertex 1.0804 1.32098 2.61089 + vertex 1.07746 1.31966 2.61083 + vertex 1.07895 1.31745 2.61056 + endloop + endfacet + facet normal 0.0621096 -0.107646 0.992247 + outer loop + vertex 1.08324 1.313 2.60987 + vertex 1.08254 1.31666 2.61031 + vertex 1.07854 1.31285 2.61015 + endloop + endfacet + facet normal 0.0619026 -0.0997121 0.993089 + outer loop + vertex 1.07847 1.30805 2.60967 + vertex 1.08324 1.313 2.60987 + vertex 1.07854 1.31285 2.61015 + endloop + endfacet + facet normal 0.0595379 -0.0974506 0.993458 + outer loop + vertex 1.08344 1.30807 2.60938 + vertex 1.08324 1.313 2.60987 + vertex 1.07847 1.30805 2.60967 + endloop + endfacet + facet normal 0.0595292 -0.110097 0.992137 + outer loop + vertex 1.07842 1.303 2.60911 + vertex 1.08344 1.30807 2.60938 + vertex 1.07847 1.30805 2.60967 + endloop + endfacet + facet normal 0.0483125 -0.0990958 0.993904 + outer loop + vertex 1.08345 1.30305 2.60887 + vertex 1.08344 1.30807 2.60938 + vertex 1.07842 1.303 2.60911 + endloop + endfacet + facet normal 0.0484187 -0.11743 0.9919 + outer loop + vertex 1.0784 1.29797 2.60852 + vertex 1.08345 1.30305 2.60887 + vertex 1.07842 1.303 2.60911 + endloop + endfacet + facet normal 0.0477638 -0.117431 0.991932 + outer loop + vertex 1.0784 1.29797 2.60852 + vertex 1.07842 1.303 2.60911 + vertex 1.07325 1.2979 2.60876 + endloop + endfacet + facet normal 0.0477703 -0.118256 0.991833 + outer loop + vertex 1.07327 1.29286 2.60816 + vertex 1.0784 1.29797 2.60852 + vertex 1.07325 1.2979 2.60876 + endloop + endfacet + facet normal 0.0792462 -0.117943 0.989853 + outer loop + vertex 1.07327 1.29286 2.60816 + vertex 1.07325 1.2979 2.60876 + vertex 1.06817 1.29285 2.60856 + endloop + endfacet + facet normal 0.0793116 -0.107634 0.991022 + outer loop + vertex 1.06822 1.28782 2.60801 + vertex 1.07327 1.29286 2.60816 + vertex 1.06817 1.29285 2.60856 + endloop + endfacet + facet normal 0.104894 -0.10712 0.988697 + outer loop + vertex 1.06822 1.28782 2.60801 + vertex 1.06817 1.29285 2.60856 + vertex 1.06315 1.28784 2.60855 + endloop + endfacet + facet normal 0.106875 -0.1091 0.988269 + outer loop + vertex 1.06315 1.28784 2.60855 + vertex 1.06817 1.29285 2.60856 + vertex 1.06315 1.29296 2.60912 + endloop + endfacet + facet normal 0.106559 -0.117985 0.987282 + outer loop + vertex 1.06817 1.29285 2.60856 + vertex 1.0682 1.29797 2.60917 + vertex 1.06315 1.29296 2.60912 + endloop + endfacet + facet normal 0.107495 -0.118927 0.987067 + outer loop + vertex 1.06315 1.29296 2.60912 + vertex 1.0682 1.29797 2.60917 + vertex 1.06332 1.29815 2.60973 + endloop + endfacet + facet normal 0.117715 -0.119109 0.985878 + outer loop + vertex 1.06315 1.29296 2.60912 + vertex 1.06332 1.29815 2.60973 + vertex 1.0583 1.29319 2.60973 + endloop + endfacet + facet normal 0.118265 -0.110071 0.986863 + outer loop + vertex 1.05816 1.28798 2.60916 + vertex 1.06315 1.29296 2.60912 + vertex 1.0583 1.29319 2.60973 + endloop + endfacet + facet normal 0.116803 -0.110051 0.987039 + outer loop + vertex 1.05816 1.28798 2.60916 + vertex 1.0583 1.29319 2.60973 + vertex 1.05336 1.28826 2.60976 + endloop + endfacet + facet normal 0.114046 -0.107291 0.987665 + outer loop + vertex 1.05336 1.28826 2.60976 + vertex 1.0583 1.29319 2.60973 + vertex 1.05362 1.29341 2.61029 + endloop + endfacet + facet normal 0.112429 -0.107231 0.987857 + outer loop + vertex 1.05362 1.29341 2.61029 + vertex 1.04887 1.28852 2.6103 + vertex 1.05336 1.28826 2.60976 + endloop + endfacet + facet normal 0.113347 -0.0939698 0.989102 + outer loop + vertex 1.04859 1.28345 2.60985 + vertex 1.05336 1.28826 2.60976 + vertex 1.04887 1.28852 2.6103 + endloop + endfacet + facet normal 0.107084 -0.102044 0.988999 + outer loop + vertex 1.04988 1.29239 2.61059 + vertex 1.04887 1.28852 2.6103 + vertex 1.05362 1.29341 2.61029 + endloop + endfacet + facet normal 0.109232 -0.110207 0.987888 + outer loop + vertex 1.05362 1.29341 2.61029 + vertex 1.0519 1.29531 2.61069 + vertex 1.04988 1.29239 2.61059 + endloop + endfacet + facet normal 0.120734 -0.118069 0.985638 + outer loop + vertex 1.0519 1.29531 2.61069 + vertex 1.04811 1.29394 2.61099 + vertex 1.04988 1.29239 2.61059 + endloop + endfacet + facet normal 0.123843 -0.114555 0.985667 + outer loop + vertex 1.04988 1.29239 2.61059 + vertex 1.04811 1.29394 2.61099 + vertex 1.04704 1.29027 2.6107 + endloop + endfacet + facet normal 0.153398 -0.122739 0.980512 + outer loop + vertex 1.04704 1.29027 2.6107 + vertex 1.04811 1.29394 2.61099 + vertex 1.04322 1.28872 2.6111 + endloop + endfacet + facet normal 0.152433 -0.120246 0.980972 + outer loop + vertex 1.04704 1.29027 2.6107 + vertex 1.04322 1.28872 2.6111 + vertex 1.04526 1.28736 2.61062 + endloop + endfacet + facet normal 0.119999 -0.100459 0.987678 + outer loop + vertex 1.04887 1.28852 2.6103 + vertex 1.04704 1.29027 2.6107 + vertex 1.04526 1.28736 2.61062 + endloop + endfacet + facet normal 0.116986 -0.0906625 0.988987 + outer loop + vertex 1.04526 1.28736 2.61062 + vertex 1.04487 1.28405 2.61036 + vertex 1.04887 1.28852 2.6103 + endloop + endfacet + facet normal 0.14445 -0.0935394 0.985081 + outer loop + vertex 1.04526 1.28736 2.61062 + vertex 1.04247 1.28489 2.6108 + vertex 1.04487 1.28405 2.61036 + endloop + endfacet + facet normal 0.120615 -0.117729 0.985694 + outer loop + vertex 1.0519 1.29531 2.61069 + vertex 1.0531 1.29897 2.61098 + vertex 1.04811 1.29394 2.61099 + endloop + endfacet + facet normal 0.114602 -0.111759 0.987105 + outer loop + vertex 1.0531 1.29897 2.61098 + vertex 1.04828 1.29833 2.61147 + vertex 1.04811 1.29394 2.61099 + endloop + endfacet + facet normal 0.107908 -0.11369 0.987639 + outer loop + vertex 1.05481 1.29735 2.61061 + vertex 1.0531 1.29897 2.61098 + vertex 1.0519 1.29531 2.61069 + endloop + endfacet + facet normal 0.106224 -0.115458 0.987616 + outer loop + vertex 1.05691 1.30024 2.61072 + vertex 1.0531 1.29897 2.61098 + vertex 1.05481 1.29735 2.61061 + endloop + endfacet + facet normal 0.106937 -0.11229 0.987905 + outer loop + vertex 1.05481 1.29735 2.61061 + vertex 1.0519 1.29531 2.61069 + vertex 1.05362 1.29341 2.61029 + endloop + endfacet + facet normal 0.108844 -0.112847 0.987633 + outer loop + vertex 1.05481 1.29735 2.61061 + vertex 1.05362 1.29341 2.61029 + vertex 1.0586 1.29833 2.6103 + endloop + endfacet + facet normal 0.116285 -0.104342 0.98772 + outer loop + vertex 1.04988 1.29239 2.61059 + vertex 1.04704 1.29027 2.6107 + vertex 1.04887 1.28852 2.6103 + endloop + endfacet + facet normal 0.113439 -0.117495 0.986573 + outer loop + vertex 1.0586 1.29833 2.6103 + vertex 1.05362 1.29341 2.61029 + vertex 1.0583 1.29319 2.60973 + endloop + endfacet + facet normal 0.116242 -0.11762 0.986232 + outer loop + vertex 1.0583 1.29319 2.60973 + vertex 1.06332 1.29815 2.60973 + vertex 1.0586 1.29833 2.6103 + endloop + endfacet + facet normal 0.10733 -0.122163 0.98669 + outer loop + vertex 1.0682 1.29797 2.60917 + vertex 1.06841 1.30315 2.60979 + vertex 1.06332 1.29815 2.60973 + endloop + endfacet + facet normal 0.10761 -0.122448 0.986624 + outer loop + vertex 1.06332 1.29815 2.60973 + vertex 1.06841 1.30315 2.60979 + vertex 1.06366 1.30325 2.61032 + endloop + endfacet + facet normal 0.0802725 -0.121358 0.989358 + outer loop + vertex 1.0682 1.29797 2.60917 + vertex 1.07334 1.30302 2.60937 + vertex 1.06841 1.30315 2.60979 + endloop + endfacet + facet normal 0.0805568 -0.113425 0.990275 + outer loop + vertex 1.07334 1.30302 2.60937 + vertex 1.07357 1.30814 2.60994 + vertex 1.06841 1.30315 2.60979 + endloop + endfacet + facet normal 0.0529226 -0.112394 0.992253 + outer loop + vertex 1.07334 1.30302 2.60937 + vertex 1.07847 1.30805 2.60967 + vertex 1.07357 1.30814 2.60994 + endloop + endfacet + facet normal 0.0793552 -0.120431 0.989545 + outer loop + vertex 1.07325 1.2979 2.60876 + vertex 1.07334 1.30302 2.60937 + vertex 1.0682 1.29797 2.60917 + endloop + endfacet + facet normal 0.0772305 -0.105561 0.991409 + outer loop + vertex 1.0733 1.28787 2.60762 + vertex 1.07327 1.29286 2.60816 + vertex 1.06822 1.28782 2.60801 + endloop + endfacet + facet normal 0.077208 -0.0930026 0.992668 + outer loop + vertex 1.06826 1.28282 2.60754 + vertex 1.0733 1.28787 2.60762 + vertex 1.06822 1.28782 2.60801 + endloop + endfacet + facet normal 0.101573 -0.0925707 0.990512 + outer loop + vertex 1.06826 1.28282 2.60754 + vertex 1.06822 1.28782 2.60801 + vertex 1.06321 1.28279 2.60806 + endloop + endfacet + facet normal 0.0765906 -0.092388 0.992773 + outer loop + vertex 1.07333 1.28287 2.60716 + vertex 1.0733 1.28787 2.60762 + vertex 1.06826 1.28282 2.60754 + endloop + endfacet + facet normal 0.0765544 -0.0821332 0.993677 + outer loop + vertex 1.06828 1.27784 2.60713 + vertex 1.07333 1.28287 2.60716 + vertex 1.06826 1.28282 2.60754 + endloop + endfacet + facet normal 0.0989724 -0.0818797 0.991716 + outer loop + vertex 1.06828 1.27784 2.60713 + vertex 1.06826 1.28282 2.60754 + vertex 1.06325 1.27778 2.60763 + endloop + endfacet + facet normal 0.0790676 -0.0846525 0.993268 + outer loop + vertex 1.07335 1.27797 2.60674 + vertex 1.07333 1.28287 2.60716 + vertex 1.06828 1.27784 2.60713 + endloop + endfacet + facet normal 0.0789825 -0.0800553 0.993656 + outer loop + vertex 1.06829 1.27302 2.60674 + vertex 1.07335 1.27797 2.60674 + vertex 1.06828 1.27784 2.60713 + endloop + endfacet + facet normal 0.0991775 -0.0798668 0.991859 + outer loop + vertex 1.06829 1.27302 2.60674 + vertex 1.06828 1.27784 2.60713 + vertex 1.06328 1.27282 2.60722 + endloop + endfacet + facet normal 0.0850948 -0.0862919 0.992629 + outer loop + vertex 1.07331 1.27332 2.60634 + vertex 1.07335 1.27797 2.60674 + vertex 1.06829 1.27302 2.60674 + endloop + endfacet + facet normal 0.0850307 -0.0850829 0.992739 + outer loop + vertex 1.06829 1.26848 2.60635 + vertex 1.07331 1.27332 2.60634 + vertex 1.06829 1.27302 2.60674 + endloop + endfacet + facet normal 0.101433 -0.0849763 0.991207 + outer loop + vertex 1.06829 1.26848 2.60635 + vertex 1.06829 1.27302 2.60674 + vertex 1.06335 1.26805 2.60682 + endloop + endfacet + facet normal 0.0954061 -0.0958465 0.990813 + outer loop + vertex 1.0731 1.26892 2.60593 + vertex 1.07331 1.27332 2.60634 + vertex 1.06829 1.26848 2.60635 + endloop + endfacet + facet normal 0.0952049 -0.0934249 0.991064 + outer loop + vertex 1.0731 1.26892 2.60593 + vertex 1.06829 1.26848 2.60635 + vertex 1.06821 1.26419 2.60595 + endloop + endfacet + facet normal 0.105706 -0.104291 0.988913 + outer loop + vertex 1.07187 1.2653 2.60568 + vertex 1.0731 1.26892 2.60593 + vertex 1.06821 1.26419 2.60595 + endloop + endfacet + facet normal 0.105264 -0.102787 0.989118 + outer loop + vertex 1.07187 1.2653 2.60568 + vertex 1.06821 1.26419 2.60595 + vertex 1.06981 1.26241 2.6056 + endloop + endfacet + facet normal 0.093983 -0.0948152 0.991049 + outer loop + vertex 1.07359 1.26335 2.60533 + vertex 1.07187 1.2653 2.60568 + vertex 1.06981 1.26241 2.6056 + endloop + endfacet + facet normal 0.0977778 -0.11064 0.989039 + outer loop + vertex 1.06981 1.26241 2.6056 + vertex 1.06855 1.25842 2.60528 + vertex 1.07359 1.26335 2.60533 + endloop + endfacet + facet normal 0.0989512 -0.111837 0.988788 + outer loop + vertex 1.07359 1.26335 2.60533 + vertex 1.06855 1.25842 2.60528 + vertex 1.07331 1.25824 2.60478 + endloop + endfacet + facet normal 0.0701199 -0.110549 0.991394 + outer loop + vertex 1.07331 1.25824 2.60478 + vertex 1.07843 1.26321 2.60497 + vertex 1.07359 1.26335 2.60533 + endloop + endfacet + facet normal 0.0705478 -0.0992729 0.992556 + outer loop + vertex 1.07867 1.26804 2.60544 + vertex 1.07359 1.26335 2.60533 + vertex 1.07843 1.26321 2.60497 + endloop + endfacet + facet normal 0.0601114 -0.0880109 0.994304 + outer loop + vertex 1.07481 1.26724 2.6056 + vertex 1.07359 1.26335 2.60533 + vertex 1.07867 1.26804 2.60544 + endloop + endfacet + facet normal 0.059586 -0.085415 0.994562 + outer loop + vertex 1.07867 1.26804 2.60544 + vertex 1.07698 1.27001 2.60571 + vertex 1.07481 1.26724 2.6056 + endloop + endfacet + facet normal 0.0863138 -0.106251 0.990586 + outer loop + vertex 1.07698 1.27001 2.60571 + vertex 1.0731 1.26892 2.60593 + vertex 1.07481 1.26724 2.6056 + endloop + endfacet + facet normal 0.0900016 -0.119842 0.988705 + outer loop + vertex 1.07698 1.27001 2.60571 + vertex 1.07836 1.27357 2.60601 + vertex 1.0731 1.26892 2.60593 + endloop + endfacet + facet normal 0.0759849 -0.116559 0.990273 + outer loop + vertex 1.07828 1.2581 2.60438 + vertex 1.07843 1.26321 2.60497 + vertex 1.07331 1.25824 2.60478 + endloop + endfacet + facet normal 0.0757104 -0.123928 0.989399 + outer loop + vertex 1.07316 1.25303 2.60414 + vertex 1.07828 1.2581 2.60438 + vertex 1.07331 1.25824 2.60478 + endloop + endfacet + facet normal 0.0992592 -0.124357 0.98726 + outer loop + vertex 1.07316 1.25303 2.60414 + vertex 1.07331 1.25824 2.60478 + vertex 1.06824 1.25319 2.60465 + endloop + endfacet + facet normal 0.0991829 -0.126099 0.987047 + outer loop + vertex 1.06812 1.24796 2.604 + vertex 1.07316 1.25303 2.60414 + vertex 1.06824 1.25319 2.60465 + endloop + endfacet + facet normal 0.112946 -0.126212 0.985552 + outer loop + vertex 1.06812 1.24796 2.604 + vertex 1.06824 1.25319 2.60465 + vertex 1.06329 1.24814 2.60457 + endloop + endfacet + facet normal 0.113153 -0.12212 0.986044 + outer loop + vertex 1.06315 1.24296 2.60395 + vertex 1.06812 1.24796 2.604 + vertex 1.06329 1.24814 2.60457 + endloop + endfacet + facet normal 0.122342 -0.122234 0.984932 + outer loop + vertex 1.06315 1.24296 2.60395 + vertex 1.06329 1.24814 2.60457 + vertex 1.05844 1.24329 2.60457 + endloop + endfacet + facet normal 0.123129 -0.112998 0.985936 + outer loop + vertex 1.05824 1.2381 2.604 + vertex 1.06315 1.24296 2.60395 + vertex 1.05844 1.24329 2.60457 + endloop + endfacet + facet normal 0.139398 -0.113381 0.983724 + outer loop + vertex 1.05824 1.2381 2.604 + vertex 1.05844 1.24329 2.60457 + vertex 1.05382 1.23871 2.6047 + endloop + endfacet + facet normal 0.141503 -0.0994813 0.984927 + outer loop + vertex 1.05344 1.23345 2.60422 + vertex 1.05824 1.2381 2.604 + vertex 1.05382 1.23871 2.6047 + endloop + endfacet + facet normal 0.152826 -0.111323 0.981963 + outer loop + vertex 1.05813 1.23289 2.60343 + vertex 1.05824 1.2381 2.604 + vertex 1.05344 1.23345 2.60422 + endloop + endfacet + facet normal 0.154397 -0.0995949 0.982976 + outer loop + vertex 1.05324 1.22812 2.60372 + vertex 1.05813 1.23289 2.60343 + vertex 1.05344 1.23345 2.60422 + endloop + endfacet + facet normal 0.163213 -0.108784 0.980575 + outer loop + vertex 1.05814 1.22781 2.60287 + vertex 1.05813 1.23289 2.60343 + vertex 1.05324 1.22812 2.60372 + endloop + endfacet + facet normal 0.164085 -0.0977507 0.981591 + outer loop + vertex 1.05327 1.223 2.6032 + vertex 1.05814 1.22781 2.60287 + vertex 1.05324 1.22812 2.60372 + endloop + endfacet + facet normal 0.173085 -0.107032 0.979074 + outer loop + vertex 1.05819 1.22296 2.60233 + vertex 1.05814 1.22781 2.60287 + vertex 1.05327 1.223 2.6032 + endloop + endfacet + facet normal 0.173391 -0.0942803 0.98033 + outer loop + vertex 1.05326 1.21804 2.60273 + vertex 1.05819 1.22296 2.60233 + vertex 1.05327 1.223 2.6032 + endloop + endfacet + facet normal 0.186652 -0.107888 0.976484 + outer loop + vertex 1.0582 1.21831 2.60181 + vertex 1.05819 1.22296 2.60233 + vertex 1.05326 1.21804 2.60273 + endloop + endfacet + facet normal 0.140213 -0.107961 0.984218 + outer loop + vertex 1.05819 1.22296 2.60233 + vertex 1.06326 1.22795 2.60215 + vertex 1.05814 1.22781 2.60287 + endloop + endfacet + facet normal 0.140286 -0.114464 0.983472 + outer loop + vertex 1.06326 1.22795 2.60215 + vertex 1.06316 1.23277 2.60273 + vertex 1.05814 1.22781 2.60287 + endloop + endfacet + facet normal 0.116999 -0.115289 0.986418 + outer loop + vertex 1.06326 1.22795 2.60215 + vertex 1.06834 1.23293 2.60213 + vertex 1.06316 1.23277 2.60273 + endloop + endfacet + facet normal 0.117024 -0.116796 0.986237 + outer loop + vertex 1.06834 1.23293 2.60213 + vertex 1.06819 1.23778 2.60272 + vertex 1.06316 1.23277 2.60273 + endloop + endfacet + facet normal 0.117196 -0.116968 0.986197 + outer loop + vertex 1.06316 1.23277 2.60273 + vertex 1.06819 1.23778 2.60272 + vertex 1.06311 1.2378 2.60333 + endloop + endfacet + facet normal 0.134968 -0.116499 0.983977 + outer loop + vertex 1.06316 1.23277 2.60273 + vertex 1.06311 1.2378 2.60333 + vertex 1.05813 1.23289 2.60343 + endloop + endfacet + facet normal 0.117122 -0.120727 0.985752 + outer loop + vertex 1.06819 1.23778 2.60272 + vertex 1.06811 1.24281 2.60335 + vertex 1.06311 1.2378 2.60333 + endloop + endfacet + facet normal 0.115569 -0.119178 0.986124 + outer loop + vertex 1.06311 1.2378 2.60333 + vertex 1.06811 1.24281 2.60335 + vertex 1.06315 1.24296 2.60395 + endloop + endfacet + facet normal 0.103069 -0.121146 0.987269 + outer loop + vertex 1.06819 1.23778 2.60272 + vertex 1.0732 1.2428 2.60282 + vertex 1.06811 1.24281 2.60335 + endloop + endfacet + facet normal 0.102992 -0.125924 0.986679 + outer loop + vertex 1.0732 1.2428 2.60282 + vertex 1.07313 1.24787 2.60347 + vertex 1.06811 1.24281 2.60335 + endloop + endfacet + facet normal 0.101499 -0.124448 0.987021 + outer loop + vertex 1.06811 1.24281 2.60335 + vertex 1.07313 1.24787 2.60347 + vertex 1.06812 1.24796 2.604 + endloop + endfacet + facet normal 0.0853509 -0.126357 0.988306 + outer loop + vertex 1.0732 1.2428 2.60282 + vertex 1.07824 1.24785 2.60303 + vertex 1.07313 1.24787 2.60347 + endloop + endfacet + facet normal 0.0852609 -0.132837 0.987464 + outer loop + vertex 1.07824 1.24785 2.60303 + vertex 1.07822 1.25295 2.60371 + vertex 1.07313 1.24787 2.60347 + endloop + endfacet + facet normal 0.0807797 -0.128399 0.988427 + outer loop + vertex 1.07313 1.24787 2.60347 + vertex 1.07822 1.25295 2.60371 + vertex 1.07316 1.25303 2.60414 + endloop + endfacet + facet normal 0.0807641 -0.128979 0.988353 + outer loop + vertex 1.07822 1.25295 2.60371 + vertex 1.07828 1.2581 2.60438 + vertex 1.07316 1.25303 2.60414 + endloop + endfacet + facet normal 0.0650665 -0.128952 0.989514 + outer loop + vertex 1.07822 1.25295 2.60371 + vertex 1.08336 1.25806 2.60404 + vertex 1.07828 1.2581 2.60438 + endloop + endfacet + facet normal 0.0652114 -0.120806 0.990532 + outer loop + vertex 1.08336 1.25806 2.60404 + vertex 1.08344 1.26314 2.60466 + vertex 1.07828 1.2581 2.60438 + endloop + endfacet + facet normal 0.0606801 -0.116212 0.991369 + outer loop + vertex 1.07828 1.2581 2.60438 + vertex 1.08344 1.26314 2.60466 + vertex 1.07843 1.26321 2.60497 + endloop + endfacet + facet normal 0.0608409 -0.107912 0.992297 + outer loop + vertex 1.08344 1.26314 2.60466 + vertex 1.08353 1.26803 2.60518 + vertex 1.07843 1.26321 2.60497 + endloop + endfacet + facet normal 0.0518575 -0.0984992 0.993785 + outer loop + vertex 1.07843 1.26321 2.60497 + vertex 1.08353 1.26803 2.60518 + vertex 1.07867 1.26804 2.60544 + endloop + endfacet + facet normal 0.0518116 -0.105359 0.993084 + outer loop + vertex 1.08334 1.27194 2.60561 + vertex 1.07867 1.26804 2.60544 + vertex 1.08353 1.26803 2.60518 + endloop + endfacet + facet normal 0.0814765 -0.103733 0.991262 + outer loop + vertex 1.08353 1.26803 2.60518 + vertex 1.08852 1.27333 2.60533 + vertex 1.08334 1.27194 2.60561 + endloop + endfacet + facet normal 0.0941602 -0.152438 0.983817 + outer loop + vertex 1.08334 1.27194 2.60561 + vertex 1.08852 1.27333 2.60533 + vertex 1.08638 1.27585 2.60592 + endloop + endfacet + facet normal 0.0381997 -0.109559 0.993246 + outer loop + vertex 1.08248 1.27431 2.6059 + vertex 1.08334 1.27194 2.60561 + vertex 1.08638 1.27585 2.60592 + endloop + endfacet + facet normal 0.0381809 -0.109511 0.993252 + outer loop + vertex 1.08638 1.27585 2.60592 + vertex 1.08391 1.27828 2.60628 + vertex 1.08248 1.27431 2.6059 + endloop + endfacet + facet normal 0.0472404 -0.112704 0.992505 + outer loop + vertex 1.08248 1.27431 2.6059 + vertex 1.08391 1.27828 2.60628 + vertex 1.07836 1.27357 2.60601 + endloop + endfacet + facet normal 0.048216 -0.11822 0.991816 + outer loop + vertex 1.08248 1.27431 2.6059 + vertex 1.07836 1.27357 2.60601 + vertex 1.08 1.27168 2.60571 + endloop + endfacet + facet normal 0.059584 -0.108431 0.992317 + outer loop + vertex 1.08 1.27168 2.60571 + vertex 1.07836 1.27357 2.60601 + vertex 1.07698 1.27001 2.60571 + endloop + endfacet + facet normal 0.0509127 -0.0927978 0.994382 + outer loop + vertex 1.08 1.27168 2.60571 + vertex 1.07698 1.27001 2.60571 + vertex 1.07867 1.26804 2.60544 + endloop + endfacet + facet normal 0.0363305 -0.0999498 0.994329 + outer loop + vertex 1.08391 1.27828 2.60628 + vertex 1.07851 1.27816 2.60647 + vertex 1.07836 1.27357 2.60601 + endloop + endfacet + facet normal 0.0362601 -0.0959567 0.994725 + outer loop + vertex 1.08391 1.27828 2.60628 + vertex 1.08353 1.2831 2.60676 + vertex 1.07851 1.27816 2.60647 + endloop + endfacet + facet normal 0.0318986 -0.0915608 0.995288 + outer loop + vertex 1.07851 1.27816 2.60647 + vertex 1.08353 1.2831 2.60676 + vertex 1.07844 1.28297 2.60692 + endloop + endfacet + facet normal 0.0320038 -0.0961811 0.994849 + outer loop + vertex 1.08353 1.2831 2.60676 + vertex 1.08339 1.28803 2.60724 + vertex 1.07844 1.28297 2.60692 + endloop + endfacet + facet normal 0.0317047 -0.0958904 0.994887 + outer loop + vertex 1.07844 1.28297 2.60692 + vertex 1.08339 1.28803 2.60724 + vertex 1.0784 1.28796 2.6074 + endloop + endfacet + facet normal 0.058548 -0.0953269 0.993723 + outer loop + vertex 1.08353 1.2831 2.60676 + vertex 1.08804 1.28795 2.60696 + vertex 1.08339 1.28803 2.60724 + endloop + endfacet + facet normal 0.0586334 -0.0913454 0.994092 + outer loop + vertex 1.08804 1.28795 2.60696 + vertex 1.08798 1.29293 2.60742 + vertex 1.08339 1.28803 2.60724 + endloop + endfacet + facet normal 0.0721796 -0.103946 0.99196 + outer loop + vertex 1.08339 1.28803 2.60724 + vertex 1.08798 1.29293 2.60742 + vertex 1.08338 1.29306 2.60777 + endloop + endfacet + facet normal 0.031798 -0.104284 0.994039 + outer loop + vertex 1.08339 1.28803 2.60724 + vertex 1.08338 1.29306 2.60777 + vertex 1.0784 1.28796 2.6074 + endloop + endfacet + facet normal 0.0340379 -0.106448 0.993736 + outer loop + vertex 1.0784 1.28796 2.6074 + vertex 1.08338 1.29306 2.60777 + vertex 1.07839 1.29297 2.60793 + endloop + endfacet + facet normal 0.0340891 -0.110079 0.993338 + outer loop + vertex 1.08338 1.29306 2.60777 + vertex 1.08341 1.29806 2.60833 + vertex 1.07839 1.29297 2.60793 + endloop + endfacet + facet normal 0.0853855 -0.110064 0.99025 + outer loop + vertex 1.08338 1.29306 2.60777 + vertex 1.08802 1.29796 2.60792 + vertex 1.08341 1.29806 2.60833 + endloop + endfacet + facet normal 0.0859352 -0.092342 0.992012 + outer loop + vertex 1.08802 1.29796 2.60792 + vertex 1.08809 1.30294 2.60838 + vertex 1.08341 1.29806 2.60833 + endloop + endfacet + facet normal 0.103692 -0.109335 0.988582 + outer loop + vertex 1.08341 1.29806 2.60833 + vertex 1.08809 1.30294 2.60838 + vertex 1.08345 1.30305 2.60887 + endloop + endfacet + facet normal 0.104804 -0.0756833 0.991609 + outer loop + vertex 1.08809 1.30294 2.60838 + vertex 1.08812 1.30796 2.60875 + vertex 1.08345 1.30305 2.60887 + endloop + endfacet + facet normal 0.128287 -0.0981671 0.986867 + outer loop + vertex 1.08345 1.30305 2.60887 + vertex 1.08812 1.30796 2.60875 + vertex 1.08344 1.30807 2.60938 + endloop + endfacet + facet normal 0.129314 -0.0687777 0.989216 + outer loop + vertex 1.08812 1.30796 2.60875 + vertex 1.08799 1.31313 2.60913 + vertex 1.08344 1.30807 2.60938 + endloop + endfacet + facet normal 0.155542 -0.0926634 0.983474 + outer loop + vertex 1.08344 1.30807 2.60938 + vertex 1.08799 1.31313 2.60913 + vertex 1.08324 1.313 2.60987 + endloop + endfacet + facet normal 0.155748 -0.110924 0.981549 + outer loop + vertex 1.08799 1.31313 2.60913 + vertex 1.08741 1.31888 2.60987 + vertex 1.08324 1.313 2.60987 + endloop + endfacet + facet normal 0.131334 -0.0936079 0.986909 + outer loop + vertex 1.08324 1.313 2.60987 + vertex 1.08741 1.31888 2.60987 + vertex 1.08254 1.31666 2.61031 + endloop + endfacet + facet normal 0.156123 -0.150075 0.97627 + outer loop + vertex 1.08741 1.31888 2.60987 + vertex 1.08359 1.32057 2.61074 + vertex 1.08254 1.31666 2.61031 + endloop + endfacet + facet normal 0.118413 -0.22999 0.965962 + outer loop + vertex 1.08675 1.32237 2.61078 + vertex 1.08359 1.32057 2.61074 + vertex 1.08741 1.31888 2.60987 + endloop + endfacet + facet normal 0.0807085 -0.164081 0.98314 + outer loop + vertex 1.08675 1.32237 2.61078 + vertex 1.08506 1.32376 2.61116 + vertex 1.08359 1.32057 2.61074 + endloop + endfacet + facet normal 0.0247314 -0.139158 0.989961 + outer loop + vertex 1.08359 1.32057 2.61074 + vertex 1.08506 1.32376 2.61116 + vertex 1.08252 1.32323 2.61114 + endloop + endfacet + facet normal 0.0152608 -0.0936781 0.995486 + outer loop + vertex 1.08506 1.32376 2.61116 + vertex 1.08399 1.32718 2.61149 + vertex 1.08252 1.32323 2.61114 + endloop + endfacet + facet normal 0.098326 -0.0672512 0.992879 + outer loop + vertex 1.08506 1.32376 2.61116 + vertex 1.0874 1.32533 2.61103 + vertex 1.08399 1.32718 2.61149 + endloop + endfacet + facet normal 0.113106 -0.0399616 0.992779 + outer loop + vertex 1.0874 1.32533 2.61103 + vertex 1.08804 1.32861 2.61109 + vertex 1.08399 1.32718 2.61149 + endloop + endfacet + facet normal 0.118872 -0.0566939 0.99129 + outer loop + vertex 1.08804 1.32861 2.61109 + vertex 1.08731 1.3323 2.61139 + vertex 1.08399 1.32718 2.61149 + endloop + endfacet + facet normal 0.150829 -0.0775099 0.985516 + outer loop + vertex 1.08399 1.32718 2.61149 + vertex 1.08731 1.3323 2.61139 + vertex 1.08316 1.33271 2.61206 + endloop + endfacet + facet normal 0.153371 -0.053689 0.986709 + outer loop + vertex 1.08731 1.3323 2.61139 + vertex 1.08699 1.33728 2.61171 + vertex 1.08316 1.33271 2.61206 + endloop + endfacet + facet normal 0.189032 -0.0842226 0.978352 + outer loop + vertex 1.08316 1.33271 2.61206 + vertex 1.08699 1.33728 2.61171 + vertex 1.08296 1.33788 2.61254 + endloop + endfacet + facet normal 0.192798 -0.0605732 0.979367 + outer loop + vertex 1.08699 1.33728 2.61171 + vertex 1.08697 1.34238 2.61203 + vertex 1.08296 1.33788 2.61254 + endloop + endfacet + facet normal 0.222202 -0.0877587 0.971043 + outer loop + vertex 1.08296 1.33788 2.61254 + vertex 1.08697 1.34238 2.61203 + vertex 1.08299 1.34294 2.61299 + endloop + endfacet + facet normal 0.226687 -0.0579438 0.972243 + outer loop + vertex 1.08697 1.34238 2.61203 + vertex 1.08705 1.34737 2.61231 + vertex 1.08299 1.34294 2.61299 + endloop + endfacet + facet normal 0.258286 -0.0883666 0.962019 + outer loop + vertex 1.08299 1.34294 2.61299 + vertex 1.08705 1.34737 2.61231 + vertex 1.08306 1.34791 2.61343 + endloop + endfacet + facet normal 0.262027 -0.0628075 0.963015 + outer loop + vertex 1.08705 1.34737 2.61231 + vertex 1.08713 1.35231 2.61261 + vertex 1.08306 1.34791 2.61343 + endloop + endfacet + facet normal 0.280156 -0.0807595 0.956551 + outer loop + vertex 1.08306 1.34791 2.61343 + vertex 1.08713 1.35231 2.61261 + vertex 1.0831 1.35287 2.61383 + endloop + endfacet + facet normal 0.284347 -0.0522953 0.957294 + outer loop + vertex 1.08713 1.35231 2.61261 + vertex 1.08717 1.35723 2.61286 + vertex 1.0831 1.35287 2.61383 + endloop + endfacet + facet normal 0.302891 -0.0711361 0.950367 + outer loop + vertex 1.0831 1.35287 2.61383 + vertex 1.08717 1.35723 2.61286 + vertex 1.08314 1.35788 2.6142 + endloop + endfacet + facet normal 0.30814 -0.0393924 0.950525 + outer loop + vertex 1.08717 1.35723 2.61286 + vertex 1.08719 1.3622 2.61306 + vertex 1.08314 1.35788 2.6142 + endloop + endfacet + facet normal 0.126356 -0.109466 0.985927 + outer loop + vertex 1.08675 1.32237 2.61078 + vertex 1.0874 1.32533 2.61103 + vertex 1.08506 1.32376 2.61116 + endloop + endfacet + facet normal 0.072391 -0.0978231 0.992567 + outer loop + vertex 1.08798 1.29293 2.60742 + vertex 1.08802 1.29796 2.60792 + vertex 1.08338 1.29306 2.60777 + endloop + endfacet + facet normal 0.0461602 -0.0838683 0.995407 + outer loop + vertex 1.08828 1.28332 2.60656 + vertex 1.08804 1.28795 2.60696 + vertex 1.08353 1.2831 2.60676 + endloop + endfacet + facet normal 0.0466153 -0.0951129 0.994374 + outer loop + vertex 1.08391 1.27828 2.60628 + vertex 1.08828 1.28332 2.60656 + vertex 1.08353 1.2831 2.60676 + endloop + endfacet + facet normal 0.0404585 -0.0898074 0.995137 + outer loop + vertex 1.089 1.27972 2.60621 + vertex 1.08828 1.28332 2.60656 + vertex 1.08391 1.27828 2.60628 + endloop + endfacet + facet normal 0.125743 -0.072177 0.989434 + outer loop + vertex 1.09201 1.28328 2.60609 + vertex 1.08828 1.28332 2.60656 + vertex 1.089 1.27972 2.60621 + endloop + endfacet + facet normal 0.131293 -0.0768848 0.988358 + outer loop + vertex 1.09203 1.28025 2.60585 + vertex 1.09201 1.28328 2.60609 + vertex 1.089 1.27972 2.60621 + endloop + endfacet + facet normal 0.137732 -0.116657 0.983576 + outer loop + vertex 1.09203 1.28025 2.60585 + vertex 1.089 1.27972 2.60621 + vertex 1.09011 1.27749 2.60579 + endloop + endfacet + facet normal 0.313148 -0.237259 0.91959 + outer loop + vertex 1.09343 1.27839 2.60489 + vertex 1.09203 1.28025 2.60585 + vertex 1.09011 1.27749 2.60579 + endloop + endfacet + facet normal 0.310172 -0.221269 0.924572 + outer loop + vertex 1.09011 1.27749 2.60579 + vertex 1.08852 1.27333 2.60533 + vertex 1.09343 1.27839 2.60489 + endloop + endfacet + facet normal 0.219098 -0.129079 0.967127 + outer loop + vertex 1.09343 1.27839 2.60489 + vertex 1.08852 1.27333 2.60533 + vertex 1.09317 1.27324 2.60426 + endloop + endfacet + facet normal 0.219891 -0.11187 0.969089 + outer loop + vertex 1.08849 1.26821 2.60474 + vertex 1.09317 1.27324 2.60426 + vertex 1.08852 1.27333 2.60533 + endloop + endfacet + facet normal 0.189262 -0.0824799 0.978456 + outer loop + vertex 1.09308 1.26812 2.60385 + vertex 1.09317 1.27324 2.60426 + vertex 1.08849 1.26821 2.60474 + endloop + endfacet + facet normal 0.188507 -0.102757 0.976681 + outer loop + vertex 1.08841 1.26314 2.60422 + vertex 1.09308 1.26812 2.60385 + vertex 1.08849 1.26821 2.60474 + endloop + endfacet + facet normal 0.0862281 -0.102694 0.990969 + outer loop + vertex 1.08841 1.26314 2.60422 + vertex 1.08849 1.26821 2.60474 + vertex 1.08344 1.26314 2.60466 + endloop + endfacet + facet normal 0.0860403 -0.12092 0.988926 + outer loop + vertex 1.08336 1.25806 2.60404 + vertex 1.08841 1.26314 2.60422 + vertex 1.08344 1.26314 2.60466 + endloop + endfacet + facet normal 0.0803185 -0.115279 0.990081 + outer loop + vertex 1.08838 1.25807 2.60364 + vertex 1.08841 1.26314 2.60422 + vertex 1.08336 1.25806 2.60404 + endloop + endfacet + facet normal 0.0801699 -0.133362 0.987819 + outer loop + vertex 1.08335 1.25296 2.60336 + vertex 1.08838 1.25807 2.60364 + vertex 1.08336 1.25806 2.60404 + endloop + endfacet + facet normal 0.0778586 -0.131108 0.988306 + outer loop + vertex 1.08838 1.25303 2.60297 + vertex 1.08838 1.25807 2.60364 + vertex 1.08335 1.25296 2.60336 + endloop + endfacet + facet normal 0.0778696 -0.13707 0.987496 + outer loop + vertex 1.08338 1.24794 2.60266 + vertex 1.08838 1.25303 2.60297 + vertex 1.08335 1.25296 2.60336 + endloop + endfacet + facet normal 0.0737044 -0.137137 0.987806 + outer loop + vertex 1.08338 1.24794 2.60266 + vertex 1.08335 1.25296 2.60336 + vertex 1.07824 1.24785 2.60303 + endloop + endfacet + facet normal 0.0736521 -0.129178 0.988882 + outer loop + vertex 1.07833 1.24287 2.60237 + vertex 1.08338 1.24794 2.60266 + vertex 1.07824 1.24785 2.60303 + endloop + endfacet + facet normal 0.0767712 -0.132248 0.988239 + outer loop + vertex 1.08345 1.24309 2.602 + vertex 1.08338 1.24794 2.60266 + vertex 1.07833 1.24287 2.60237 + endloop + endfacet + facet normal 0.0764078 -0.121161 0.989688 + outer loop + vertex 1.07852 1.23808 2.60177 + vertex 1.08345 1.24309 2.602 + vertex 1.07833 1.24287 2.60237 + endloop + endfacet + facet normal 0.0877567 -0.120606 0.988814 + outer loop + vertex 1.07852 1.23808 2.60177 + vertex 1.07833 1.24287 2.60237 + vertex 1.07335 1.23788 2.6022 + endloop + endfacet + facet normal 0.0875967 -0.114926 0.989504 + outer loop + vertex 1.07354 1.23317 2.60164 + vertex 1.07852 1.23808 2.60177 + vertex 1.07335 1.23788 2.6022 + endloop + endfacet + facet normal 0.0855334 -0.112846 0.989924 + outer loop + vertex 1.07887 1.23335 2.6012 + vertex 1.07852 1.23808 2.60177 + vertex 1.07354 1.23317 2.60164 + endloop + endfacet + facet normal 0.0855427 -0.113214 0.989881 + outer loop + vertex 1.07887 1.23335 2.6012 + vertex 1.07354 1.23317 2.60164 + vertex 1.07354 1.22862 2.60112 + endloop + endfacet + facet normal 0.083768 -0.111221 0.990259 + outer loop + vertex 1.0775 1.22938 2.60087 + vertex 1.07887 1.23335 2.6012 + vertex 1.07354 1.22862 2.60112 + endloop + endfacet + facet normal 0.0849661 -0.117735 0.989404 + outer loop + vertex 1.0775 1.22938 2.60087 + vertex 1.07354 1.22862 2.60112 + vertex 1.0752 1.22674 2.60075 + endloop + endfacet + facet normal 0.0844019 -0.117248 0.98951 + outer loop + vertex 1.07829 1.22699 2.60052 + vertex 1.0775 1.22938 2.60087 + vertex 1.0752 1.22674 2.60075 + endloop + endfacet + facet normal 0.0847331 -0.121747 0.988938 + outer loop + vertex 1.0752 1.22674 2.60075 + vertex 1.07384 1.22309 2.60042 + vertex 1.07829 1.22699 2.60052 + endloop + endfacet + facet normal 0.0868162 -0.124112 0.988463 + outer loop + vertex 1.07829 1.22699 2.60052 + vertex 1.07384 1.22309 2.60042 + vertex 1.07841 1.22304 2.60001 + endloop + endfacet + facet normal 0.084237 -0.124212 0.988674 + outer loop + vertex 1.07841 1.22304 2.60001 + vertex 1.08332 1.22835 2.60026 + vertex 1.07829 1.22699 2.60052 + endloop + endfacet + facet normal 0.0820914 -0.116035 0.989847 + outer loop + vertex 1.07829 1.22699 2.60052 + vertex 1.08332 1.22835 2.60026 + vertex 1.08117 1.23093 2.60074 + endloop + endfacet + facet normal 0.0854082 -0.125285 0.988438 + outer loop + vertex 1.08332 1.22316 2.5996 + vertex 1.08332 1.22835 2.60026 + vertex 1.07841 1.22304 2.60001 + endloop + endfacet + facet normal 0.0853841 -0.123437 0.988672 + outer loop + vertex 1.07824 1.21809 2.59941 + vertex 1.08332 1.22316 2.5996 + vertex 1.07841 1.22304 2.60001 + endloop + endfacet + facet normal 0.0907884 -0.123554 0.988176 + outer loop + vertex 1.07824 1.21809 2.59941 + vertex 1.07841 1.22304 2.60001 + vertex 1.07344 1.21824 2.59987 + endloop + endfacet + facet normal 0.091387 -0.109444 0.989783 + outer loop + vertex 1.07318 1.21311 2.59933 + vertex 1.07824 1.21809 2.59941 + vertex 1.07344 1.21824 2.59987 + endloop + endfacet + facet normal 0.0938633 -0.111954 0.98927 + outer loop + vertex 1.07815 1.21298 2.59884 + vertex 1.07824 1.21809 2.59941 + vertex 1.07318 1.21311 2.59933 + endloop + endfacet + facet normal 0.0945296 -0.0938875 0.991085 + outer loop + vertex 1.07308 1.20796 2.59885 + vertex 1.07815 1.21298 2.59884 + vertex 1.07318 1.21311 2.59933 + endloop + endfacet + facet normal 0.0940255 -0.0933789 0.991181 + outer loop + vertex 1.07814 1.20792 2.59836 + vertex 1.07815 1.21298 2.59884 + vertex 1.07308 1.20796 2.59885 + endloop + endfacet + facet normal 0.0942298 -0.080627 0.99228 + outer loop + vertex 1.07309 1.20289 2.59843 + vertex 1.07814 1.20792 2.59836 + vertex 1.07308 1.20796 2.59885 + endloop + endfacet + facet normal 0.0914265 -0.0778063 0.992768 + outer loop + vertex 1.07816 1.20292 2.59797 + vertex 1.07814 1.20792 2.59836 + vertex 1.07309 1.20289 2.59843 + endloop + endfacet + facet normal 0.0914249 -0.0800783 0.992587 + outer loop + vertex 1.07313 1.19788 2.59803 + vertex 1.07816 1.20292 2.59797 + vertex 1.07309 1.20289 2.59843 + endloop + endfacet + facet normal 0.0873708 -0.0760267 0.99327 + outer loop + vertex 1.07823 1.19795 2.59758 + vertex 1.07816 1.20292 2.59797 + vertex 1.07313 1.19788 2.59803 + endloop + endfacet + facet normal 0.090141 -0.0934064 0.991539 + outer loop + vertex 1.07814 1.20792 2.59836 + vertex 1.08325 1.21298 2.59838 + vertex 1.07815 1.21298 2.59884 + endloop + endfacet + facet normal 0.090147 -0.0934125 0.991538 + outer loop + vertex 1.08325 1.20798 2.5979 + vertex 1.08325 1.21298 2.59838 + vertex 1.07814 1.20792 2.59836 + endloop + endfacet + facet normal 0.0900939 -0.0778221 0.992888 + outer loop + vertex 1.07816 1.20292 2.59797 + vertex 1.08325 1.20798 2.5979 + vertex 1.07814 1.20792 2.59836 + endloop + endfacet + facet normal 0.0891896 -0.0769098 0.993041 + outer loop + vertex 1.08327 1.20299 2.59752 + vertex 1.08325 1.20798 2.5979 + vertex 1.07816 1.20292 2.59797 + endloop + endfacet + facet normal 0.0891827 -0.0759885 0.993112 + outer loop + vertex 1.07823 1.19795 2.59758 + vertex 1.08327 1.20299 2.59752 + vertex 1.07816 1.20292 2.59797 + endloop + endfacet + facet normal 0.0857356 -0.0725394 0.993674 + outer loop + vertex 1.08336 1.19802 2.59715 + vertex 1.08327 1.20299 2.59752 + vertex 1.07823 1.19795 2.59758 + endloop + endfacet + facet normal 0.0925538 -0.0933888 0.991318 + outer loop + vertex 1.08325 1.20798 2.5979 + vertex 1.08838 1.21309 2.59791 + vertex 1.08325 1.21298 2.59838 + endloop + endfacet + facet normal 0.0928183 -0.115559 0.988954 + outer loop + vertex 1.08838 1.21309 2.59791 + vertex 1.08837 1.21809 2.59849 + vertex 1.08325 1.21298 2.59838 + endloop + endfacet + facet normal 0.09081 -0.113555 0.989373 + outer loop + vertex 1.08325 1.21298 2.59838 + vertex 1.08837 1.21809 2.59849 + vertex 1.08326 1.21804 2.59896 + endloop + endfacet + facet normal 0.0899318 -0.113563 0.989452 + outer loop + vertex 1.08325 1.21298 2.59838 + vertex 1.08326 1.21804 2.59896 + vertex 1.07815 1.21298 2.59884 + endloop + endfacet + facet normal 0.0907883 -0.127434 0.987683 + outer loop + vertex 1.08837 1.21809 2.59849 + vertex 1.08838 1.22316 2.59915 + vertex 1.08326 1.21804 2.59896 + endloop + endfacet + facet normal 0.0893628 -0.12602 0.987995 + outer loop + vertex 1.08326 1.21804 2.59896 + vertex 1.08838 1.22316 2.59915 + vertex 1.08332 1.22316 2.5996 + endloop + endfacet + facet normal 0.0893449 -0.127643 0.987788 + outer loop + vertex 1.08838 1.22316 2.59915 + vertex 1.08846 1.22828 2.5998 + vertex 1.08332 1.22316 2.5996 + endloop + endfacet + facet normal 0.0869615 -0.12527 0.988304 + outer loop + vertex 1.08332 1.22316 2.5996 + vertex 1.08846 1.22828 2.5998 + vertex 1.08332 1.22835 2.60026 + endloop + endfacet + facet normal 0.0870715 -0.120878 0.988841 + outer loop + vertex 1.08877 1.23335 2.60039 + vertex 1.08332 1.22835 2.60026 + vertex 1.08846 1.22828 2.5998 + endloop + endfacet + facet normal 0.119491 -0.122415 0.98526 + outer loop + vertex 1.08846 1.22828 2.5998 + vertex 1.09355 1.23332 2.59981 + vertex 1.08877 1.23335 2.60039 + endloop + endfacet + facet normal 0.11949 -0.122447 0.985256 + outer loop + vertex 1.09387 1.23832 2.60039 + vertex 1.08877 1.23335 2.60039 + vertex 1.09355 1.23332 2.59981 + endloop + endfacet + facet normal 0.230272 -0.127123 0.964787 + outer loop + vertex 1.09355 1.23332 2.59981 + vertex 1.09823 1.23823 2.59934 + vertex 1.09387 1.23832 2.60039 + endloop + endfacet + facet normal 0.230559 -0.121148 0.965487 + outer loop + vertex 1.09845 1.24339 2.59993 + vertex 1.09387 1.23832 2.60039 + vertex 1.09823 1.23823 2.59934 + endloop + endfacet + facet normal 0.306024 -0.192304 0.932399 + outer loop + vertex 1.09506 1.24221 2.6008 + vertex 1.09387 1.23832 2.60039 + vertex 1.09845 1.24339 2.59993 + endloop + endfacet + facet normal 0.309825 -0.206401 0.92812 + outer loop + vertex 1.09845 1.24339 2.59993 + vertex 1.09678 1.24513 2.60088 + vertex 1.09506 1.24221 2.6008 + endloop + endfacet + facet normal 0.152206 -0.114996 0.981636 + outer loop + vertex 1.09678 1.24513 2.60088 + vertex 1.09312 1.2438 2.60129 + vertex 1.09506 1.24221 2.6008 + endloop + endfacet + facet normal 0.139207 -0.130883 0.981576 + outer loop + vertex 1.09506 1.24221 2.6008 + vertex 1.09312 1.2438 2.60129 + vertex 1.0922 1.24012 2.60093 + endloop + endfacet + facet normal 0.0833732 -0.117653 0.989549 + outer loop + vertex 1.0922 1.24012 2.60093 + vertex 1.09312 1.2438 2.60129 + vertex 1.08841 1.23902 2.60112 + endloop + endfacet + facet normal 0.0843924 -0.121235 0.98903 + outer loop + vertex 1.0922 1.24012 2.60093 + vertex 1.08841 1.23902 2.60112 + vertex 1.0901 1.23722 2.60075 + endloop + endfacet + facet normal 0.140851 -0.161341 0.976796 + outer loop + vertex 1.09387 1.23832 2.60039 + vertex 1.0922 1.24012 2.60093 + vertex 1.0901 1.23722 2.60075 + endloop + endfacet + facet normal 0.0843541 -0.121271 0.989029 + outer loop + vertex 1.0901 1.23722 2.60075 + vertex 1.08841 1.23902 2.60112 + vertex 1.08721 1.23538 2.60077 + endloop + endfacet + facet normal 0.0843446 -0.121256 0.989031 + outer loop + vertex 1.0901 1.23722 2.60075 + vertex 1.08721 1.23538 2.60077 + vertex 1.08877 1.23335 2.60039 + endloop + endfacet + facet normal 0.0851393 -0.120644 0.989038 + outer loop + vertex 1.08877 1.23335 2.60039 + vertex 1.08721 1.23538 2.60077 + vertex 1.08487 1.23257 2.60063 + endloop + endfacet + facet normal 0.0758296 -0.113002 0.990697 + outer loop + vertex 1.08721 1.23538 2.60077 + vertex 1.08401 1.23492 2.60097 + vertex 1.08487 1.23257 2.60063 + endloop + endfacet + facet normal 0.0787608 -0.111914 0.990592 + outer loop + vertex 1.08487 1.23257 2.60063 + vertex 1.08401 1.23492 2.60097 + vertex 1.08117 1.23093 2.60074 + endloop + endfacet + facet normal 0.0809677 -0.116969 0.98983 + outer loop + vertex 1.08487 1.23257 2.60063 + vertex 1.08117 1.23093 2.60074 + vertex 1.08332 1.22835 2.60026 + endloop + endfacet + facet normal 0.0790667 -0.11213 0.990543 + outer loop + vertex 1.08401 1.23492 2.60097 + vertex 1.07887 1.23335 2.6012 + vertex 1.08117 1.23093 2.60074 + endloop + endfacet + facet normal 0.0801446 -0.115743 0.990041 + outer loop + vertex 1.08401 1.23492 2.60097 + vertex 1.08362 1.23857 2.60142 + vertex 1.07887 1.23335 2.6012 + endloop + endfacet + facet normal 0.0766216 -0.118806 0.989957 + outer loop + vertex 1.08721 1.23538 2.60077 + vertex 1.08841 1.23902 2.60112 + vertex 1.08401 1.23492 2.60097 + endloop + endfacet + facet normal 0.0743763 -0.116416 0.990412 + outer loop + vertex 1.08841 1.23902 2.60112 + vertex 1.08362 1.23857 2.60142 + vertex 1.08401 1.23492 2.60097 + endloop + endfacet + facet normal 0.0750476 -0.124238 0.98941 + outer loop + vertex 1.08841 1.23902 2.60112 + vertex 1.08841 1.24343 2.60167 + vertex 1.08362 1.23857 2.60142 + endloop + endfacet + facet normal 0.0741905 -0.123401 0.98958 + outer loop + vertex 1.08362 1.23857 2.60142 + vertex 1.08841 1.24343 2.60167 + vertex 1.08345 1.24309 2.602 + endloop + endfacet + facet normal 0.0746477 -0.131078 0.988558 + outer loop + vertex 1.08841 1.24343 2.60167 + vertex 1.08839 1.24811 2.60229 + vertex 1.08345 1.24309 2.602 + endloop + endfacet + facet normal 0.0999049 -0.130649 0.986382 + outer loop + vertex 1.08841 1.24343 2.60167 + vertex 1.09301 1.24824 2.60184 + vertex 1.08839 1.24811 2.60229 + endloop + endfacet + facet normal 0.0997403 -0.12091 0.98764 + outer loop + vertex 1.09301 1.24824 2.60184 + vertex 1.09305 1.25298 2.60242 + vertex 1.08839 1.24811 2.60229 + endloop + endfacet + facet normal 0.114215 -0.134665 0.984287 + outer loop + vertex 1.08839 1.24811 2.60229 + vertex 1.09305 1.25298 2.60242 + vertex 1.08838 1.25303 2.60297 + endloop + endfacet + facet normal 0.114748 -0.111724 0.987092 + outer loop + vertex 1.09305 1.25298 2.60242 + vertex 1.09305 1.25795 2.60298 + vertex 1.08838 1.25303 2.60297 + endloop + endfacet + facet normal 0.237078 -0.109205 0.965333 + outer loop + vertex 1.09305 1.25298 2.60242 + vertex 1.0971 1.25745 2.60193 + vertex 1.09305 1.25795 2.60298 + endloop + endfacet + facet normal 0.244183 -0.0572162 0.96804 + outer loop + vertex 1.0971 1.25745 2.60193 + vertex 1.09708 1.26248 2.60223 + vertex 1.09305 1.25795 2.60298 + endloop + endfacet + facet normal 0.279815 -0.0908777 0.955743 + outer loop + vertex 1.09305 1.25795 2.60298 + vertex 1.09708 1.26248 2.60223 + vertex 1.09305 1.26301 2.60346 + endloop + endfacet + facet normal 0.135879 -0.0937774 0.986277 + outer loop + vertex 1.09305 1.25795 2.60298 + vertex 1.09305 1.26301 2.60346 + vertex 1.08838 1.25807 2.60364 + endloop + endfacet + facet normal 0.205531 -0.0795282 0.975414 + outer loop + vertex 1.09702 1.25259 2.60155 + vertex 1.0971 1.25745 2.60193 + vertex 1.09305 1.25298 2.60242 + endloop + endfacet + facet normal 0.200846 -0.119953 0.972251 + outer loop + vertex 1.09301 1.24824 2.60184 + vertex 1.09702 1.25259 2.60155 + vertex 1.09305 1.25298 2.60242 + endloop + endfacet + facet normal 0.164846 -0.0860613 0.982557 + outer loop + vertex 1.09681 1.24823 2.60121 + vertex 1.09702 1.25259 2.60155 + vertex 1.09301 1.24824 2.60184 + endloop + endfacet + facet normal 0.164227 -0.117956 0.979345 + outer loop + vertex 1.09681 1.24823 2.60121 + vertex 1.09301 1.24824 2.60184 + vertex 1.09312 1.2438 2.60129 + endloop + endfacet + facet normal 0.0897528 -0.121035 0.988582 + outer loop + vertex 1.09312 1.2438 2.60129 + vertex 1.09301 1.24824 2.60184 + vertex 1.08841 1.24343 2.60167 + endloop + endfacet + facet normal 0.0899628 -0.124104 0.988183 + outer loop + vertex 1.09312 1.2438 2.60129 + vertex 1.08841 1.24343 2.60167 + vertex 1.08841 1.23902 2.60112 + endloop + endfacet + facet normal 0.148772 -0.105036 0.983277 + outer loop + vertex 1.09678 1.24513 2.60088 + vertex 1.09681 1.24823 2.60121 + vertex 1.09312 1.2438 2.60129 + endloop + endfacet + facet normal 0.153028 -0.150095 0.976757 + outer loop + vertex 1.09506 1.24221 2.6008 + vertex 1.0922 1.24012 2.60093 + vertex 1.09387 1.23832 2.60039 + endloop + endfacet + facet normal 0.19252 -0.0899505 0.977162 + outer loop + vertex 1.09808 1.23314 2.5989 + vertex 1.09823 1.23823 2.59934 + vertex 1.09355 1.23332 2.59981 + endloop + endfacet + facet normal 0.190974 -0.115797 0.974741 + outer loop + vertex 1.09341 1.22826 2.59924 + vertex 1.09808 1.23314 2.5989 + vertex 1.09355 1.23332 2.59981 + endloop + endfacet + facet normal 0.168619 -0.0939595 0.981193 + outer loop + vertex 1.09806 1.2281 2.59842 + vertex 1.09808 1.23314 2.5989 + vertex 1.09341 1.22826 2.59924 + endloop + endfacet + facet normal 0.167185 -0.122196 0.978324 + outer loop + vertex 1.09339 1.2232 2.59861 + vertex 1.09806 1.2281 2.59842 + vertex 1.09341 1.22826 2.59924 + endloop + endfacet + facet normal 0.107128 -0.123083 0.986597 + outer loop + vertex 1.09339 1.2232 2.59861 + vertex 1.09341 1.22826 2.59924 + vertex 1.08838 1.22316 2.59915 + endloop + endfacet + facet normal 0.150601 -0.10624 0.98287 + outer loop + vertex 1.09809 1.22312 2.59788 + vertex 1.09806 1.2281 2.59842 + vertex 1.09339 1.2232 2.59861 + endloop + endfacet + facet normal 0.149967 -0.124402 0.980833 + outer loop + vertex 1.09341 1.2182 2.59797 + vertex 1.09809 1.22312 2.59788 + vertex 1.09339 1.2232 2.59861 + endloop + endfacet + facet normal 0.105104 -0.12528 0.986538 + outer loop + vertex 1.09341 1.2182 2.59797 + vertex 1.09339 1.2232 2.59861 + vertex 1.08837 1.21809 2.59849 + endloop + endfacet + facet normal 0.136977 -0.111953 0.984228 + outer loop + vertex 1.09807 1.21821 2.59732 + vertex 1.09809 1.22312 2.59788 + vertex 1.09341 1.2182 2.59797 + endloop + endfacet + facet normal 0.136933 -0.114828 0.983902 + outer loop + vertex 1.09339 1.21327 2.5974 + vertex 1.09807 1.21821 2.59732 + vertex 1.09341 1.2182 2.59797 + endloop + endfacet + facet normal 0.104714 -0.115123 0.987817 + outer loop + vertex 1.09339 1.21327 2.5974 + vertex 1.09341 1.2182 2.59797 + vertex 1.08838 1.21309 2.59791 + endloop + endfacet + facet normal 0.129172 -0.107428 0.985786 + outer loop + vertex 1.09799 1.21343 2.59681 + vertex 1.09807 1.21821 2.59732 + vertex 1.09339 1.21327 2.5974 + endloop + endfacet + facet normal 0.198657 -0.10745 0.974161 + outer loop + vertex 1.09799 1.21343 2.59681 + vertex 1.10203 1.21779 2.59647 + vertex 1.09807 1.21821 2.59732 + endloop + endfacet + facet normal 0.201647 -0.0826452 0.975965 + outer loop + vertex 1.10203 1.21779 2.59647 + vertex 1.10218 1.2226 2.59685 + vertex 1.09807 1.21821 2.59732 + endloop + endfacet + facet normal 0.173027 -0.083129 0.981403 + outer loop + vertex 1.10176 1.21344 2.59615 + vertex 1.10203 1.21779 2.59647 + vertex 1.09799 1.21343 2.59681 + endloop + endfacet + facet normal 0.230303 -0.110391 0.966837 + outer loop + vertex 1.09807 1.21821 2.59732 + vertex 1.10218 1.2226 2.59685 + vertex 1.09809 1.22312 2.59788 + endloop + endfacet + facet normal 0.261484 -0.102939 0.959703 + outer loop + vertex 1.09809 1.22312 2.59788 + vertex 1.10218 1.22756 2.59724 + vertex 1.09806 1.2281 2.59842 + endloop + endfacet + facet normal 0.26811 -0.056836 0.96171 + outer loop + vertex 1.10218 1.22756 2.59724 + vertex 1.10211 1.23255 2.59756 + vertex 1.09806 1.2281 2.59842 + endloop + endfacet + facet normal 0.134458 -0.137828 0.981287 + outer loop + vertex 1.0901 1.23722 2.60075 + vertex 1.08877 1.23335 2.60039 + vertex 1.09387 1.23832 2.60039 + endloop + endfacet + facet normal 0.112081 -0.114946 0.987028 + outer loop + vertex 1.09341 1.22826 2.59924 + vertex 1.09355 1.23332 2.59981 + vertex 1.08846 1.22828 2.5998 + endloop + endfacet + facet normal 0.0846847 -0.118294 0.989361 + outer loop + vertex 1.08487 1.23257 2.60063 + vertex 1.08332 1.22835 2.60026 + vertex 1.08877 1.23335 2.60039 + endloop + endfacet + facet normal 0.111848 -0.127719 0.985483 + outer loop + vertex 1.08838 1.22316 2.59915 + vertex 1.09341 1.22826 2.59924 + vertex 1.08846 1.22828 2.5998 + endloop + endfacet + facet normal 0.107107 -0.127236 0.986073 + outer loop + vertex 1.08837 1.21809 2.59849 + vertex 1.09339 1.2232 2.59861 + vertex 1.08838 1.22316 2.59915 + endloop + endfacet + facet normal 0.104998 -0.115402 0.987754 + outer loop + vertex 1.08838 1.21309 2.59791 + vertex 1.09341 1.2182 2.59797 + vertex 1.08837 1.21809 2.59849 + endloop + endfacet + facet normal 0.0946743 -0.0955166 0.990915 + outer loop + vertex 1.08837 1.20812 2.59743 + vertex 1.08838 1.21309 2.59791 + vertex 1.08325 1.20798 2.5979 + endloop + endfacet + facet normal 0.0943265 -0.0768598 0.99257 + outer loop + vertex 1.08327 1.20299 2.59752 + vertex 1.08837 1.20812 2.59743 + vertex 1.08325 1.20798 2.5979 + endloop + endfacet + facet normal 0.0953444 -0.0778763 0.992393 + outer loop + vertex 1.08839 1.20309 2.59703 + vertex 1.08837 1.20812 2.59743 + vertex 1.08327 1.20299 2.59752 + endloop + endfacet + facet normal 0.0952828 -0.0723038 0.992821 + outer loop + vertex 1.08336 1.19802 2.59715 + vertex 1.08839 1.20309 2.59703 + vertex 1.08327 1.20299 2.59752 + endloop + endfacet + facet normal 0.0917068 -0.0687384 0.993411 + outer loop + vertex 1.08837 1.19801 2.59668 + vertex 1.08839 1.20309 2.59703 + vertex 1.08336 1.19802 2.59715 + endloop + endfacet + facet normal 0.0916102 -0.0792513 0.992636 + outer loop + vertex 1.08362 1.1932 2.59674 + vertex 1.08837 1.19801 2.59668 + vertex 1.08336 1.19802 2.59715 + endloop + endfacet + facet normal 0.0842042 -0.0719333 0.993849 + outer loop + vertex 1.08862 1.19309 2.5963 + vertex 1.08837 1.19801 2.59668 + vertex 1.08362 1.1932 2.59674 + endloop + endfacet + facet normal 0.0968017 -0.0712198 0.992752 + outer loop + vertex 1.08862 1.19309 2.5963 + vertex 1.09262 1.19769 2.59624 + vertex 1.08837 1.19801 2.59668 + endloop + endfacet + facet normal 0.088444 -0.0639388 0.994027 + outer loop + vertex 1.09253 1.19421 2.59603 + vertex 1.09262 1.19769 2.59624 + vertex 1.08862 1.19309 2.5963 + endloop + endfacet + facet normal 0.111534 -0.064348 0.991675 + outer loop + vertex 1.09262 1.19769 2.59624 + vertex 1.09253 1.19421 2.59603 + vertex 1.09575 1.19662 2.59582 + endloop + endfacet + facet normal 0.122567 -0.0792498 0.989291 + outer loop + vertex 1.09575 1.19662 2.59582 + vertex 1.09253 1.19421 2.59603 + vertex 1.09429 1.19286 2.5957 + endloop + endfacet + facet normal 0.149972 -0.0896692 0.984616 + outer loop + vertex 1.09429 1.19286 2.5957 + vertex 1.0984 1.1941 2.59519 + vertex 1.09575 1.19662 2.59582 + endloop + endfacet + facet normal 0.159959 -0.0790264 0.983955 + outer loop + vertex 1.0984 1.1941 2.59519 + vertex 1.09977 1.1998 2.59543 + vertex 1.09575 1.19662 2.59582 + endloop + endfacet + facet normal 0.207427 -0.0900079 0.974101 + outer loop + vertex 1.0984 1.1941 2.59519 + vertex 1.10345 1.19869 2.59454 + vertex 1.09977 1.1998 2.59543 + endloop + endfacet + facet normal 0.193066 -0.0735788 0.978423 + outer loop + vertex 1.1032 1.19344 2.59419 + vertex 1.10345 1.19869 2.59454 + vertex 1.0984 1.1941 2.59519 + endloop + endfacet + facet normal 0.188168 -0.106362 0.976361 + outer loop + vertex 1.09842 1.18852 2.59458 + vertex 1.1032 1.19344 2.59419 + vertex 1.0984 1.1941 2.59519 + endloop + endfacet + facet normal 0.139113 -0.107405 0.984435 + outer loop + vertex 1.0984 1.1941 2.59519 + vertex 1.09334 1.18849 2.59529 + vertex 1.09842 1.18852 2.59458 + endloop + endfacet + facet normal 0.138777 -0.137596 0.980718 + outer loop + vertex 1.09346 1.18324 2.59454 + vertex 1.09842 1.18852 2.59458 + vertex 1.09334 1.18849 2.59529 + endloop + endfacet + facet normal 0.111601 -0.138646 0.984034 + outer loop + vertex 1.09346 1.18324 2.59454 + vertex 1.09334 1.18849 2.59529 + vertex 1.08864 1.18297 2.59505 + endloop + endfacet + facet normal 0.112241 -0.154211 0.981642 + outer loop + vertex 1.0884 1.17807 2.59431 + vertex 1.09346 1.18324 2.59454 + vertex 1.08864 1.18297 2.59505 + endloop + endfacet + facet normal 0.0923017 -0.153559 0.983819 + outer loop + vertex 1.0884 1.17807 2.59431 + vertex 1.08864 1.18297 2.59505 + vertex 1.08358 1.17815 2.59477 + endloop + endfacet + facet normal 0.0923042 -0.153478 0.983832 + outer loop + vertex 1.08325 1.17306 2.59401 + vertex 1.0884 1.17807 2.59431 + vertex 1.08358 1.17815 2.59477 + endloop + endfacet + facet normal 0.0796055 -0.152852 0.985038 + outer loop + vertex 1.08325 1.17306 2.59401 + vertex 1.08358 1.17815 2.59477 + vertex 1.07834 1.17324 2.59443 + endloop + endfacet + facet normal 0.0799175 -0.146633 0.985957 + outer loop + vertex 1.07811 1.16802 2.59367 + vertex 1.08325 1.17306 2.59401 + vertex 1.07834 1.17324 2.59443 + endloop + endfacet + facet normal 0.0850167 -0.151753 0.984755 + outer loop + vertex 1.08313 1.16792 2.59323 + vertex 1.08325 1.17306 2.59401 + vertex 1.07811 1.16802 2.59367 + endloop + endfacet + facet normal 0.085181 -0.146578 0.985525 + outer loop + vertex 1.07808 1.16289 2.59291 + vertex 1.08313 1.16792 2.59323 + vertex 1.07811 1.16802 2.59367 + endloop + endfacet + facet normal 0.0897533 -0.151089 0.984437 + outer loop + vertex 1.0832 1.16299 2.59246 + vertex 1.08313 1.16792 2.59323 + vertex 1.07808 1.16289 2.59291 + endloop + endfacet + facet normal 0.0897265 -0.147233 0.985024 + outer loop + vertex 1.07829 1.15811 2.59218 + vertex 1.0832 1.16299 2.59246 + vertex 1.07808 1.16289 2.59291 + endloop + endfacet + facet normal 0.0912959 -0.148791 0.984645 + outer loop + vertex 1.08335 1.15842 2.59176 + vertex 1.0832 1.16299 2.59246 + vertex 1.07829 1.15811 2.59218 + endloop + endfacet + facet normal 0.0912033 -0.146809 0.984951 + outer loop + vertex 1.0787 1.15391 2.59152 + vertex 1.08335 1.15842 2.59176 + vertex 1.07829 1.15811 2.59218 + endloop + endfacet + facet normal 0.0868928 -0.142412 0.985986 + outer loop + vertex 1.08337 1.15411 2.59113 + vertex 1.08335 1.15842 2.59176 + vertex 1.0787 1.15391 2.59152 + endloop + endfacet + facet normal 0.0870249 -0.146709 0.985344 + outer loop + vertex 1.08337 1.15411 2.59113 + vertex 1.0787 1.15391 2.59152 + vertex 1.07911 1.15043 2.59096 + endloop + endfacet + facet normal 0.0810132 -0.139826 0.986856 + outer loop + vertex 1.08215 1.15057 2.59073 + vertex 1.08337 1.15411 2.59113 + vertex 1.07911 1.15043 2.59096 + endloop + endfacet + facet normal 0.103613 -0.147225 0.983661 + outer loop + vertex 1.08497 1.15224 2.59068 + vertex 1.08337 1.15411 2.59113 + vertex 1.08215 1.15057 2.59073 + endloop + endfacet + facet normal 0.116262 -0.168767 0.978775 + outer loop + vertex 1.08497 1.15224 2.59068 + vertex 1.08215 1.15057 2.59073 + vertex 1.0836 1.14843 2.59019 + endloop + endfacet + facet normal 0.137731 -0.175994 0.974708 + outer loop + vertex 1.08497 1.15224 2.59068 + vertex 1.0836 1.14843 2.59019 + vertex 1.08877 1.15322 2.59033 + endloop + endfacet + facet normal 0.134098 -0.160776 0.977839 + outer loop + vertex 1.08877 1.15322 2.59033 + vertex 1.0871 1.15505 2.59086 + vertex 1.08497 1.15224 2.59068 + endloop + endfacet + facet normal 0.136986 -0.15816 0.977865 + outer loop + vertex 1.09011 1.15706 2.59076 + vertex 1.0871 1.15505 2.59086 + vertex 1.08877 1.15322 2.59033 + endloop + endfacet + facet normal 0.135431 -0.157652 0.978164 + outer loop + vertex 1.09011 1.15706 2.59076 + vertex 1.08877 1.15322 2.59033 + vertex 1.094 1.15819 2.5904 + endloop + endfacet + facet normal 0.133536 -0.150656 0.979526 + outer loop + vertex 1.094 1.15819 2.5904 + vertex 1.09231 1.15997 2.59091 + vertex 1.09011 1.15706 2.59076 + endloop + endfacet + facet normal 0.12945 -0.147613 0.980537 + outer loop + vertex 1.09231 1.15997 2.59091 + vertex 1.08832 1.15875 2.59125 + vertex 1.09011 1.15706 2.59076 + endloop + endfacet + facet normal 0.132992 -0.15992 0.97813 + outer loop + vertex 1.09231 1.15997 2.59091 + vertex 1.09353 1.16366 2.59135 + vertex 1.08832 1.15875 2.59125 + endloop + endfacet + facet normal 0.124841 -0.151318 0.98057 + outer loop + vertex 1.09353 1.16366 2.59135 + vertex 1.08836 1.16327 2.59194 + vertex 1.08832 1.15875 2.59125 + endloop + endfacet + facet normal 0.110534 -0.151438 0.982267 + outer loop + vertex 1.08832 1.15875 2.59125 + vertex 1.08836 1.16327 2.59194 + vertex 1.08335 1.15842 2.59176 + endloop + endfacet + facet normal 0.12558 -0.164158 0.978408 + outer loop + vertex 1.09353 1.16366 2.59135 + vertex 1.09352 1.16826 2.59212 + vertex 1.08836 1.16327 2.59194 + endloop + endfacet + facet normal 0.118012 -0.156425 0.980614 + outer loop + vertex 1.08836 1.16327 2.59194 + vertex 1.09352 1.16826 2.59212 + vertex 1.08827 1.168 2.59271 + endloop + endfacet + facet normal 0.107547 -0.156819 0.981754 + outer loop + vertex 1.08836 1.16327 2.59194 + vertex 1.08827 1.168 2.59271 + vertex 1.0832 1.16299 2.59246 + endloop + endfacet + facet normal 0.118211 -0.162896 0.979536 + outer loop + vertex 1.09352 1.16826 2.59212 + vertex 1.09339 1.17309 2.59294 + vertex 1.08827 1.168 2.59271 + endloop + endfacet + facet normal 0.112587 -0.157299 0.981112 + outer loop + vertex 1.08827 1.168 2.59271 + vertex 1.09339 1.17309 2.59294 + vertex 1.08824 1.17299 2.59351 + endloop + endfacet + facet normal 0.101467 -0.157544 0.982285 + outer loop + vertex 1.08827 1.168 2.59271 + vertex 1.08824 1.17299 2.59351 + vertex 1.08313 1.16792 2.59323 + endloop + endfacet + facet normal 0.112588 -0.159457 0.980764 + outer loop + vertex 1.09339 1.17309 2.59294 + vertex 1.09336 1.17812 2.59376 + vertex 1.08824 1.17299 2.59351 + endloop + endfacet + facet normal 0.110121 -0.157023 0.981436 + outer loop + vertex 1.08824 1.17299 2.59351 + vertex 1.09336 1.17812 2.59376 + vertex 1.0884 1.17807 2.59431 + endloop + endfacet + facet normal 0.127711 -0.159083 0.97897 + outer loop + vertex 1.09339 1.17309 2.59294 + vertex 1.09843 1.17821 2.59311 + vertex 1.09336 1.17812 2.59376 + endloop + endfacet + facet normal 0.127732 -0.148049 0.980697 + outer loop + vertex 1.09843 1.17821 2.59311 + vertex 1.09839 1.18329 2.59388 + vertex 1.09336 1.17812 2.59376 + endloop + endfacet + facet normal 0.132014 -0.152188 0.979495 + outer loop + vertex 1.09336 1.17812 2.59376 + vertex 1.09839 1.18329 2.59388 + vertex 1.09346 1.18324 2.59454 + endloop + endfacet + facet normal 0.164668 -0.146992 0.975335 + outer loop + vertex 1.09843 1.17821 2.59311 + vertex 1.10317 1.18318 2.59306 + vertex 1.09839 1.18329 2.59388 + endloop + endfacet + facet normal 0.165877 -0.119981 0.97882 + outer loop + vertex 1.10317 1.18318 2.59306 + vertex 1.10316 1.18826 2.59368 + vertex 1.09839 1.18329 2.59388 + endloop + endfacet + facet normal 0.176942 -0.130721 0.975502 + outer loop + vertex 1.09839 1.18329 2.59388 + vertex 1.10316 1.18826 2.59368 + vertex 1.09842 1.18852 2.59458 + endloop + endfacet + facet normal 0.247259 -0.117756 0.961767 + outer loop + vertex 1.10317 1.18318 2.59306 + vertex 1.10742 1.18765 2.59251 + vertex 1.10316 1.18826 2.59368 + endloop + endfacet + facet normal 0.253436 -0.0789318 0.964127 + outer loop + vertex 1.10742 1.18765 2.59251 + vertex 1.10742 1.19265 2.59292 + vertex 1.10316 1.18826 2.59368 + endloop + endfacet + facet normal 0.270182 -0.096243 0.957987 + outer loop + vertex 1.10316 1.18826 2.59368 + vertex 1.10742 1.19265 2.59292 + vertex 1.1032 1.19344 2.59419 + endloop + endfacet + facet normal 0.222643 -0.0933389 0.970422 + outer loop + vertex 1.10743 1.18273 2.59204 + vertex 1.10742 1.18765 2.59251 + vertex 1.10317 1.18318 2.59306 + endloop + endfacet + facet normal 0.218397 -0.127272 0.967525 + outer loop + vertex 1.10331 1.17826 2.59238 + vertex 1.10743 1.18273 2.59204 + vertex 1.10317 1.18318 2.59306 + endloop + endfacet + facet normal 0.189491 -0.0999251 0.976785 + outer loop + vertex 1.10752 1.17814 2.59155 + vertex 1.10743 1.18273 2.59204 + vertex 1.10331 1.17826 2.59238 + endloop + endfacet + facet normal 0.187765 -0.134301 0.972989 + outer loop + vertex 1.10376 1.17351 2.59164 + vertex 1.10752 1.17814 2.59155 + vertex 1.10331 1.17826 2.59238 + endloop + endfacet + facet normal 0.133101 -0.140675 0.981068 + outer loop + vertex 1.10376 1.17351 2.59164 + vertex 1.10331 1.17826 2.59238 + vertex 1.09861 1.17331 2.59231 + endloop + endfacet + facet normal 0.133514 -0.162821 0.97758 + outer loop + vertex 1.10376 1.17351 2.59164 + vertex 1.09861 1.17331 2.59231 + vertex 1.09875 1.16857 2.5915 + endloop + endfacet + facet normal 0.120795 -0.150014 0.981277 + outer loop + vertex 1.10278 1.16955 2.59115 + vertex 1.10376 1.17351 2.59164 + vertex 1.09875 1.16857 2.5915 + endloop + endfacet + facet normal 0.124959 -0.168335 0.977777 + outer loop + vertex 1.10278 1.16955 2.59115 + vertex 1.09875 1.16857 2.5915 + vertex 1.10054 1.16672 2.59095 + endloop + endfacet + facet normal 0.123935 -0.169318 0.977738 + outer loop + vertex 1.10054 1.16672 2.59095 + vertex 1.09875 1.16857 2.5915 + vertex 1.09759 1.16485 2.591 + endloop + endfacet + facet normal 0.12048 -0.163827 0.979104 + outer loop + vertex 1.10054 1.16672 2.59095 + vertex 1.09759 1.16485 2.591 + vertex 1.09919 1.16304 2.5905 + endloop + endfacet + facet normal 0.124302 -0.160475 0.979182 + outer loop + vertex 1.09919 1.16304 2.5905 + vertex 1.09759 1.16485 2.591 + vertex 1.09539 1.162 2.59081 + endloop + endfacet + facet normal 0.121732 -0.150487 0.981089 + outer loop + vertex 1.09539 1.162 2.59081 + vertex 1.094 1.15819 2.5904 + vertex 1.09919 1.16304 2.5905 + endloop + endfacet + facet normal 0.12932 -0.158544 0.978846 + outer loop + vertex 1.09919 1.16304 2.5905 + vertex 1.094 1.15819 2.5904 + vertex 1.09872 1.1583 2.5898 + endloop + endfacet + facet normal 0.138099 -0.159218 0.977537 + outer loop + vertex 1.09872 1.1583 2.5898 + vertex 1.10377 1.16326 2.58989 + vertex 1.09919 1.16304 2.5905 + endloop + endfacet + facet normal 0.13835 -0.169408 0.975787 + outer loop + vertex 1.10366 1.16722 2.59059 + vertex 1.09919 1.16304 2.5905 + vertex 1.10377 1.16326 2.58989 + endloop + endfacet + facet normal 0.19822 -0.165978 0.966002 + outer loop + vertex 1.10377 1.16326 2.58989 + vertex 1.10847 1.16862 2.58985 + vertex 1.10366 1.16722 2.59059 + endloop + endfacet + facet normal 0.206986 -0.200607 0.957556 + outer loop + vertex 1.10366 1.16722 2.59059 + vertex 1.10847 1.16862 2.58985 + vertex 1.1062 1.17131 2.5909 + endloop + endfacet + facet normal 0.239758 -0.172207 0.955438 + outer loop + vertex 1.10944 1.17326 2.59044 + vertex 1.1062 1.17131 2.5909 + vertex 1.10847 1.16862 2.58985 + endloop + endfacet + facet normal 0.388801 -0.196472 0.900129 + outer loop + vertex 1.10944 1.17326 2.59044 + vertex 1.10847 1.16862 2.58985 + vertex 1.11291 1.1735 2.589 + endloop + endfacet + facet normal 0.297992 -0.105414 0.94873 + outer loop + vertex 1.11291 1.1735 2.589 + vertex 1.10847 1.16862 2.58985 + vertex 1.11331 1.16713 2.58816 + endloop + endfacet + facet normal 0.2861 -0.142681 0.947517 + outer loop + vertex 1.10839 1.16312 2.58904 + vertex 1.11331 1.16713 2.58816 + vertex 1.10847 1.16862 2.58985 + endloop + endfacet + facet normal 0.231643 -0.0708243 0.970219 + outer loop + vertex 1.11193 1.16204 2.58812 + vertex 1.11331 1.16713 2.58816 + vertex 1.10839 1.16312 2.58904 + endloop + endfacet + facet normal 0.212212 -0.133145 0.968111 + outer loop + vertex 1.10817 1.15814 2.58841 + vertex 1.11193 1.16204 2.58812 + vertex 1.10839 1.16312 2.58904 + endloop + endfacet + facet normal 0.150748 -0.131968 0.979724 + outer loop + vertex 1.10817 1.15814 2.58841 + vertex 1.10839 1.16312 2.58904 + vertex 1.10352 1.15832 2.58915 + endloop + endfacet + facet normal 0.149292 -0.156258 0.976368 + outer loop + vertex 1.10338 1.15325 2.58836 + vertex 1.10817 1.15814 2.58841 + vertex 1.10352 1.15832 2.58915 + endloop + endfacet + facet normal 0.128635 -0.156145 0.979322 + outer loop + vertex 1.10338 1.15325 2.58836 + vertex 1.10352 1.15832 2.58915 + vertex 1.09837 1.15324 2.58901 + endloop + endfacet + facet normal 0.128464 -0.165428 0.977819 + outer loop + vertex 1.09829 1.14813 2.58816 + vertex 1.10338 1.15325 2.58836 + vertex 1.09837 1.15324 2.58901 + endloop + endfacet + facet normal 0.132641 -0.165396 0.977267 + outer loop + vertex 1.09829 1.14813 2.58816 + vertex 1.09837 1.15324 2.58901 + vertex 1.09321 1.14812 2.58885 + endloop + endfacet + facet normal 0.132619 -0.166458 0.97709 + outer loop + vertex 1.09325 1.14308 2.58798 + vertex 1.09829 1.14813 2.58816 + vertex 1.09321 1.14812 2.58885 + endloop + endfacet + facet normal 0.136677 -0.166341 0.97655 + outer loop + vertex 1.09325 1.14308 2.58798 + vertex 1.09321 1.14812 2.58885 + vertex 1.08818 1.14308 2.58869 + endloop + endfacet + facet normal 0.136752 -0.163109 0.977085 + outer loop + vertex 1.08827 1.13809 2.58785 + vertex 1.09325 1.14308 2.58798 + vertex 1.08818 1.14308 2.58869 + endloop + endfacet + facet normal 0.128597 -0.163441 0.978136 + outer loop + vertex 1.08827 1.13809 2.58785 + vertex 1.08818 1.14308 2.58869 + vertex 1.08319 1.13806 2.58851 + endloop + endfacet + facet normal 0.128673 -0.15821 0.978986 + outer loop + vertex 1.08327 1.13308 2.58769 + vertex 1.08827 1.13809 2.58785 + vertex 1.08319 1.13806 2.58851 + endloop + endfacet + facet normal 0.117978 -0.158593 0.98027 + outer loop + vertex 1.08327 1.13308 2.58769 + vertex 1.08319 1.13806 2.58851 + vertex 1.07816 1.133 2.5883 + endloop + endfacet + facet normal 0.118008 -0.150792 0.981497 + outer loop + vertex 1.07819 1.12801 2.58753 + vertex 1.08327 1.13308 2.58769 + vertex 1.07816 1.133 2.5883 + endloop + endfacet + facet normal 0.125586 -0.158322 0.979368 + outer loop + vertex 1.08334 1.12841 2.58693 + vertex 1.08327 1.13308 2.58769 + vertex 1.07819 1.12801 2.58753 + endloop + endfacet + facet normal 0.125078 -0.149634 0.980798 + outer loop + vertex 1.07826 1.12339 2.58681 + vertex 1.08334 1.12841 2.58693 + vertex 1.07819 1.12801 2.58753 + endloop + endfacet + facet normal 0.131397 -0.149414 0.980005 + outer loop + vertex 1.07826 1.12339 2.58681 + vertex 1.07819 1.12801 2.58753 + vertex 1.07315 1.123 2.58744 + endloop + endfacet + facet normal 0.130865 -0.139981 0.981468 + outer loop + vertex 1.0734 1.11848 2.58676 + vertex 1.07826 1.12339 2.58681 + vertex 1.07315 1.123 2.58744 + endloop + endfacet + facet normal 0.122028 -0.140026 0.9826 + outer loop + vertex 1.07315 1.123 2.58744 + vertex 1.07819 1.12801 2.58753 + vertex 1.07311 1.12796 2.58815 + endloop + endfacet + facet normal 0.149958 -0.139261 0.978836 + outer loop + vertex 1.07315 1.123 2.58744 + vertex 1.07311 1.12796 2.58815 + vertex 1.06818 1.1231 2.58821 + endloop + endfacet + facet normal 0.15044 -0.127043 0.980422 + outer loop + vertex 1.06832 1.11816 2.58755 + vertex 1.07315 1.123 2.58744 + vertex 1.06818 1.1231 2.58821 + endloop + endfacet + facet normal 0.161011 -0.137664 0.977304 + outer loop + vertex 1.0734 1.11848 2.58676 + vertex 1.07315 1.123 2.58744 + vertex 1.06832 1.11816 2.58755 + endloop + endfacet + facet normal 0.160879 -0.134288 0.977796 + outer loop + vertex 1.06885 1.11324 2.58679 + vertex 1.0734 1.11848 2.58676 + vertex 1.06832 1.11816 2.58755 + endloop + endfacet + facet normal 0.166557 -0.13923 0.976153 + outer loop + vertex 1.07398 1.11487 2.58615 + vertex 1.0734 1.11848 2.58676 + vertex 1.06885 1.11324 2.58679 + endloop + endfacet + facet normal 0.173113 -0.161698 0.971538 + outer loop + vertex 1.07398 1.11487 2.58615 + vertex 1.06885 1.11324 2.58679 + vertex 1.07148 1.11093 2.58594 + endloop + endfacet + facet normal 0.184537 -0.14869 0.971513 + outer loop + vertex 1.07148 1.11093 2.58594 + vertex 1.06885 1.11324 2.58679 + vertex 1.06801 1.1091 2.58632 + endloop + endfacet + facet normal 0.186329 -0.15227 0.970616 + outer loop + vertex 1.06801 1.1091 2.58632 + vertex 1.06977 1.10765 2.58575 + vertex 1.07148 1.11093 2.58594 + endloop + endfacet + facet normal 0.145495 -0.13149 0.980582 + outer loop + vertex 1.06977 1.10765 2.58575 + vertex 1.0737 1.10862 2.5853 + vertex 1.07148 1.11093 2.58594 + endloop + endfacet + facet normal 0.141035 -0.111857 0.983665 + outer loop + vertex 1.0695 1.10424 2.5854 + vertex 1.0737 1.10862 2.5853 + vertex 1.06977 1.10765 2.58575 + endloop + endfacet + facet normal 0.151873 -0.122317 0.980802 + outer loop + vertex 1.07351 1.10351 2.58469 + vertex 1.0737 1.10862 2.5853 + vertex 1.0695 1.10424 2.5854 + endloop + endfacet + facet normal 0.155868 -0.102027 0.982495 + outer loop + vertex 1.06848 1.09894 2.58501 + vertex 1.07351 1.10351 2.58469 + vertex 1.0695 1.10424 2.5854 + endloop + endfacet + facet normal 0.168059 -0.115681 0.978966 + outer loop + vertex 1.07328 1.09832 2.58411 + vertex 1.07351 1.10351 2.58469 + vertex 1.06848 1.09894 2.58501 + endloop + endfacet + facet normal 0.170557 -0.0984429 0.980418 + outer loop + vertex 1.06875 1.09373 2.58444 + vertex 1.07328 1.09832 2.58411 + vertex 1.06848 1.09894 2.58501 + endloop + endfacet + facet normal 0.18413 -0.112141 0.976484 + outer loop + vertex 1.07326 1.09326 2.58354 + vertex 1.07328 1.09832 2.58411 + vertex 1.06875 1.09373 2.58444 + endloop + endfacet + facet normal 0.18667 -0.0908271 0.978215 + outer loop + vertex 1.06869 1.08875 2.58399 + vertex 1.07326 1.09326 2.58354 + vertex 1.06875 1.09373 2.58444 + endloop + endfacet + facet normal 0.204077 -0.109019 0.972866 + outer loop + vertex 1.07325 1.08831 2.58299 + vertex 1.07326 1.09326 2.58354 + vertex 1.06869 1.08875 2.58399 + endloop + endfacet + facet normal 0.206512 -0.0875508 0.974519 + outer loop + vertex 1.0686 1.08382 2.58357 + vertex 1.07325 1.08831 2.58299 + vertex 1.06869 1.08875 2.58399 + endloop + endfacet + facet normal 0.216543 -0.0983425 0.971307 + outer loop + vertex 1.07305 1.08328 2.58252 + vertex 1.07325 1.08831 2.58299 + vertex 1.0686 1.08382 2.58357 + endloop + endfacet + facet normal 0.219177 -0.0787512 0.972502 + outer loop + vertex 1.06853 1.07889 2.58319 + vertex 1.07305 1.08328 2.58252 + vertex 1.0686 1.08382 2.58357 + endloop + endfacet + facet normal 0.223112 -0.0829924 0.971253 + outer loop + vertex 1.07286 1.07831 2.58214 + vertex 1.07305 1.08328 2.58252 + vertex 1.06853 1.07889 2.58319 + endloop + endfacet + facet normal 0.22502 -0.0699366 0.971841 + outer loop + vertex 1.06852 1.07391 2.58283 + vertex 1.07286 1.07831 2.58214 + vertex 1.06853 1.07889 2.58319 + endloop + endfacet + facet normal 0.232628 -0.0778157 0.969448 + outer loop + vertex 1.07325 1.07331 2.58165 + vertex 1.07286 1.07831 2.58214 + vertex 1.06852 1.07391 2.58283 + endloop + endfacet + facet normal 0.23326 -0.073281 0.969649 + outer loop + vertex 1.06836 1.06873 2.58248 + vertex 1.07325 1.07331 2.58165 + vertex 1.06852 1.07391 2.58283 + endloop + endfacet + facet normal 0.256378 -0.0994935 0.961442 + outer loop + vertex 1.07244 1.06802 2.58131 + vertex 1.07325 1.07331 2.58165 + vertex 1.06836 1.06873 2.58248 + endloop + endfacet + facet normal 0.139846 -0.128974 0.981738 + outer loop + vertex 1.06818 1.1231 2.58821 + vertex 1.07311 1.12796 2.58815 + vertex 1.06829 1.12832 2.58889 + endloop + endfacet + facet normal 0.138798 -0.139988 0.980377 + outer loop + vertex 1.07311 1.12796 2.58815 + vertex 1.07322 1.13323 2.58889 + vertex 1.06829 1.12832 2.58889 + endloop + endfacet + facet normal 0.124256 -0.125347 0.984301 + outer loop + vertex 1.06829 1.12832 2.58889 + vertex 1.07322 1.13323 2.58889 + vertex 1.06861 1.13371 2.58953 + endloop + endfacet + facet normal 0.122813 -0.13727 0.982891 + outer loop + vertex 1.07322 1.13323 2.58889 + vertex 1.07329 1.13847 2.58961 + vertex 1.06861 1.13371 2.58953 + endloop + endfacet + facet normal 0.105813 -0.120647 0.98704 + outer loop + vertex 1.06861 1.13371 2.58953 + vertex 1.07329 1.13847 2.58961 + vertex 1.06864 1.13882 2.59015 + endloop + endfacet + facet normal 0.104661 -0.133633 0.985489 + outer loop + vertex 1.07329 1.13847 2.58961 + vertex 1.07293 1.14283 2.59024 + vertex 1.06864 1.13882 2.59015 + endloop + endfacet + facet normal 0.0894374 -0.117406 0.989048 + outer loop + vertex 1.06864 1.13882 2.59015 + vertex 1.07293 1.14283 2.59024 + vertex 1.06954 1.14273 2.59054 + endloop + endfacet + facet normal 0.0899254 -0.149592 0.98465 + outer loop + vertex 1.06954 1.14273 2.59054 + vertex 1.07293 1.14283 2.59024 + vertex 1.07171 1.14584 2.59081 + endloop + endfacet + facet normal 0.128472 -0.175771 0.976012 + outer loop + vertex 1.06801 1.14432 2.59102 + vertex 1.06954 1.14273 2.59054 + vertex 1.07171 1.14584 2.59081 + endloop + endfacet + facet normal 0.127248 -0.172691 0.976722 + outer loop + vertex 1.07171 1.14584 2.59081 + vertex 1.06898 1.14823 2.59159 + vertex 1.06801 1.14432 2.59102 + endloop + endfacet + facet normal 0.115233 -0.186125 0.975745 + outer loop + vertex 1.07467 1.14971 2.5912 + vertex 1.06898 1.14823 2.59159 + vertex 1.07171 1.14584 2.59081 + endloop + endfacet + facet normal 0.106912 -0.152353 0.982527 + outer loop + vertex 1.07467 1.14971 2.5912 + vertex 1.07361 1.15337 2.59188 + vertex 1.06898 1.14823 2.59159 + endloop + endfacet + facet normal 0.111644 -0.156547 0.98134 + outer loop + vertex 1.06898 1.14823 2.59159 + vertex 1.07361 1.15337 2.59188 + vertex 1.06827 1.15302 2.59243 + endloop + endfacet + facet normal 0.111193 -0.147492 0.982793 + outer loop + vertex 1.07361 1.15337 2.59188 + vertex 1.07313 1.15791 2.59262 + vertex 1.06827 1.15302 2.59243 + endloop + endfacet + facet normal 0.108695 -0.145037 0.983438 + outer loop + vertex 1.06827 1.15302 2.59243 + vertex 1.07313 1.15791 2.59262 + vertex 1.06804 1.15796 2.59319 + endloop + endfacet + facet normal 0.108706 -0.144587 0.983503 + outer loop + vertex 1.07313 1.15791 2.59262 + vertex 1.07304 1.16295 2.59337 + vertex 1.06804 1.15796 2.59319 + endloop + endfacet + facet normal 0.104076 -0.139995 0.984667 + outer loop + vertex 1.06804 1.15796 2.59319 + vertex 1.07304 1.16295 2.59337 + vertex 1.06816 1.1632 2.59392 + endloop + endfacet + facet normal 0.103939 -0.142082 0.984383 + outer loop + vertex 1.07304 1.16295 2.59337 + vertex 1.0732 1.16821 2.59411 + vertex 1.06816 1.1632 2.59392 + endloop + endfacet + facet normal 0.096802 -0.134979 0.986109 + outer loop + vertex 1.06816 1.1632 2.59392 + vertex 1.0732 1.16821 2.59411 + vertex 1.06846 1.16846 2.59461 + endloop + endfacet + facet normal 0.134892 -0.136539 0.981408 + outer loop + vertex 1.06816 1.1632 2.59392 + vertex 1.06846 1.16846 2.59461 + vertex 1.06361 1.16358 2.5946 + endloop + endfacet + facet normal 0.135398 -0.131572 0.982016 + outer loop + vertex 1.06322 1.15829 2.59394 + vertex 1.06816 1.1632 2.59392 + vertex 1.06361 1.16358 2.5946 + endloop + endfacet + facet normal 0.143968 -0.140204 0.9796 + outer loop + vertex 1.06804 1.15796 2.59319 + vertex 1.06816 1.1632 2.59392 + vertex 1.06322 1.15829 2.59394 + endloop + endfacet + facet normal 0.144344 -0.135997 0.980138 + outer loop + vertex 1.06318 1.15316 2.59324 + vertex 1.06804 1.15796 2.59319 + vertex 1.06322 1.15829 2.59394 + endloop + endfacet + facet normal 0.193693 -0.135248 0.971695 + outer loop + vertex 1.06318 1.15316 2.59324 + vertex 1.06322 1.15829 2.59394 + vertex 1.05865 1.15366 2.59421 + endloop + endfacet + facet normal 0.195836 -0.118981 0.973392 + outer loop + vertex 1.05858 1.14873 2.59362 + vertex 1.06318 1.15316 2.59324 + vertex 1.05865 1.15366 2.59421 + endloop + endfacet + facet normal 0.25621 -0.118254 0.95936 + outer loop + vertex 1.05858 1.14873 2.59362 + vertex 1.05865 1.15366 2.59421 + vertex 1.05458 1.14961 2.5948 + endloop + endfacet + facet normal 0.261902 -0.0939108 0.960514 + outer loop + vertex 1.05429 1.14476 2.5944 + vertex 1.05858 1.14873 2.59362 + vertex 1.05458 1.14961 2.5948 + endloop + endfacet + facet normal 0.276783 -0.111134 0.954484 + outer loop + vertex 1.05851 1.1438 2.59307 + vertex 1.05858 1.14873 2.59362 + vertex 1.05429 1.14476 2.5944 + endloop + endfacet + facet normal 0.28378 -0.0816283 0.955409 + outer loop + vertex 1.05396 1.13974 2.59407 + vertex 1.05851 1.1438 2.59307 + vertex 1.05429 1.14476 2.5944 + endloop + endfacet + facet normal 0.303699 -0.10604 0.946849 + outer loop + vertex 1.05819 1.13873 2.5926 + vertex 1.05851 1.1438 2.59307 + vertex 1.05396 1.13974 2.59407 + endloop + endfacet + facet normal 0.312331 -0.0706831 0.94734 + outer loop + vertex 1.05322 1.13411 2.59389 + vertex 1.05819 1.13873 2.5926 + vertex 1.05396 1.13974 2.59407 + endloop + endfacet + facet normal 0.344092 -0.108973 0.932591 + outer loop + vertex 1.05818 1.13348 2.59199 + vertex 1.05819 1.13873 2.5926 + vertex 1.05322 1.13411 2.59389 + endloop + endfacet + facet normal 0.282947 -0.111241 0.952663 + outer loop + vertex 1.0622 1.13828 2.59136 + vertex 1.05819 1.13873 2.5926 + vertex 1.05818 1.13348 2.59199 + endloop + endfacet + facet normal 0.307279 -0.132978 0.942283 + outer loop + vertex 1.06221 1.13509 2.5909 + vertex 1.0622 1.13828 2.59136 + vertex 1.05818 1.13348 2.59199 + endloop + endfacet + facet normal 0.306105 -0.129442 0.943157 + outer loop + vertex 1.06221 1.13509 2.5909 + vertex 1.05818 1.13348 2.59199 + vertex 1.06093 1.13125 2.59079 + endloop + endfacet + facet normal 0.224657 -0.10286 0.968994 + outer loop + vertex 1.06482 1.13434 2.59022 + vertex 1.06221 1.13509 2.5909 + vertex 1.06093 1.13125 2.59079 + endloop + endfacet + facet normal 0.238448 -0.121276 0.963553 + outer loop + vertex 1.06362 1.12894 2.58984 + vertex 1.06482 1.13434 2.59022 + vertex 1.06093 1.13125 2.59079 + endloop + endfacet + facet normal 0.247482 -0.11034 0.962589 + outer loop + vertex 1.05971 1.12741 2.59067 + vertex 1.06362 1.12894 2.58984 + vertex 1.06093 1.13125 2.59079 + endloop + endfacet + facet normal 0.336721 -0.13754 0.931505 + outer loop + vertex 1.06093 1.13125 2.59079 + vertex 1.05719 1.12818 2.59169 + vertex 1.05971 1.12741 2.59067 + endloop + endfacet + facet normal 0.342383 -0.119473 0.931934 + outer loop + vertex 1.05971 1.12741 2.59067 + vertex 1.05719 1.12818 2.59169 + vertex 1.0573 1.12478 2.59121 + endloop + endfacet + facet normal 0.327574 -0.104434 0.939036 + outer loop + vertex 1.05971 1.12741 2.59067 + vertex 1.0573 1.12478 2.59121 + vertex 1.05992 1.12414 2.59023 + endloop + endfacet + facet normal 0.248213 -0.112443 0.962157 + outer loop + vertex 1.05971 1.12741 2.59067 + vertex 1.05992 1.12414 2.59023 + vertex 1.06362 1.12894 2.58984 + endloop + endfacet + facet normal 0.3187 -0.112861 0.941112 + outer loop + vertex 1.05818 1.13348 2.59199 + vertex 1.05719 1.12818 2.59169 + vertex 1.06093 1.13125 2.59079 + endloop + endfacet + facet normal 0.276881 -0.154005 0.948483 + outer loop + vertex 1.0622 1.13828 2.59136 + vertex 1.06358 1.14325 2.59176 + vertex 1.05819 1.13873 2.5926 + endloop + endfacet + facet normal 0.23734 -0.103645 0.965882 + outer loop + vertex 1.05819 1.13873 2.5926 + vertex 1.06358 1.14325 2.59176 + vertex 1.05851 1.1438 2.59307 + endloop + endfacet + facet normal 0.232833 -0.137755 0.962711 + outer loop + vertex 1.06358 1.14325 2.59176 + vertex 1.06337 1.14826 2.59253 + vertex 1.05851 1.1438 2.59307 + endloop + endfacet + facet normal 0.210284 -0.112069 0.971196 + outer loop + vertex 1.05851 1.1438 2.59307 + vertex 1.06337 1.14826 2.59253 + vertex 1.05858 1.14873 2.59362 + endloop + endfacet + facet normal 0.24347 -0.104715 0.964239 + outer loop + vertex 1.05458 1.14961 2.5948 + vertex 1.05865 1.15366 2.59421 + vertex 1.05488 1.15409 2.59521 + endloop + endfacet + facet normal 0.318874 -0.107646 0.941664 + outer loop + vertex 1.05458 1.14961 2.5948 + vertex 1.05488 1.15409 2.59521 + vertex 1.05136 1.15094 2.59604 + endloop + endfacet + facet normal 0.328875 -0.0826301 0.940751 + outer loop + vertex 1.0508 1.14617 2.59581 + vertex 1.05458 1.14961 2.5948 + vertex 1.05136 1.15094 2.59604 + endloop + endfacet + facet normal 0.410848 -0.0906671 0.907184 + outer loop + vertex 1.05136 1.15094 2.59604 + vertex 1.04774 1.14799 2.59738 + vertex 1.0508 1.14617 2.59581 + endloop + endfacet + facet normal 0.404404 -0.0810295 0.910984 + outer loop + vertex 1.04871 1.15353 2.59744 + vertex 1.04774 1.14799 2.59738 + vertex 1.05136 1.15094 2.59604 + endloop + endfacet + facet normal 0.383103 -0.106431 0.917554 + outer loop + vertex 1.05226 1.15471 2.5961 + vertex 1.04871 1.15353 2.59744 + vertex 1.05136 1.15094 2.59604 + endloop + endfacet + facet normal 0.386687 -0.121048 0.914232 + outer loop + vertex 1.05226 1.15471 2.5961 + vertex 1.0522 1.15799 2.59656 + vertex 1.04871 1.15353 2.59744 + endloop + endfacet + facet normal 0.354999 -0.0931147 0.930218 + outer loop + vertex 1.0522 1.15799 2.59656 + vertex 1.0487 1.15873 2.59797 + vertex 1.04871 1.15353 2.59744 + endloop + endfacet + facet normal 0.34617 -0.132277 0.9288 + outer loop + vertex 1.0522 1.15799 2.59656 + vertex 1.05343 1.16319 2.59684 + vertex 1.0487 1.15873 2.59797 + endloop + endfacet + facet normal 0.307418 -0.0863858 0.947645 + outer loop + vertex 1.0487 1.15873 2.59797 + vertex 1.05343 1.16319 2.59684 + vertex 1.04885 1.16364 2.59837 + endloop + endfacet + facet normal 0.304547 -0.110252 0.946095 + outer loop + vertex 1.05343 1.16319 2.59684 + vertex 1.05332 1.16824 2.59747 + vertex 1.04885 1.16364 2.59837 + endloop + endfacet + facet normal 0.276819 -0.0810928 0.957494 + outer loop + vertex 1.04885 1.16364 2.59837 + vertex 1.05332 1.16824 2.59747 + vertex 1.04875 1.16847 2.59881 + endloop + endfacet + facet normal 0.237804 -0.1141 0.964588 + outer loop + vertex 1.05822 1.16874 2.59632 + vertex 1.05332 1.16824 2.59747 + vertex 1.05343 1.16319 2.59684 + endloop + endfacet + facet normal 0.272307 -0.145088 0.951209 + outer loop + vertex 1.0575 1.16486 2.59593 + vertex 1.05822 1.16874 2.59632 + vertex 1.05343 1.16319 2.59684 + endloop + endfacet + facet normal 0.269899 -0.1383 0.952905 + outer loop + vertex 1.0575 1.16486 2.59593 + vertex 1.05343 1.16319 2.59684 + vertex 1.05596 1.16099 2.5958 + endloop + endfacet + facet normal 0.213982 -0.116697 0.969842 + outer loop + vertex 1.05991 1.16406 2.5953 + vertex 1.0575 1.16486 2.59593 + vertex 1.05596 1.16099 2.5958 + endloop + endfacet + facet normal 0.224742 -0.1312 0.965545 + outer loop + vertex 1.05858 1.1588 2.5949 + vertex 1.05991 1.16406 2.5953 + vertex 1.05596 1.16099 2.5958 + endloop + endfacet + facet normal 0.233078 -0.120964 0.964905 + outer loop + vertex 1.05468 1.15727 2.59565 + vertex 1.05858 1.1588 2.5949 + vertex 1.05596 1.16099 2.5958 + endloop + endfacet + facet normal 0.304211 -0.144612 0.941564 + outer loop + vertex 1.05596 1.16099 2.5958 + vertex 1.0522 1.15799 2.59656 + vertex 1.05468 1.15727 2.59565 + endloop + endfacet + facet normal 0.309794 -0.126382 0.942367 + outer loop + vertex 1.05468 1.15727 2.59565 + vertex 1.0522 1.15799 2.59656 + vertex 1.05226 1.15471 2.5961 + endloop + endfacet + facet normal 0.296788 -0.113082 0.948224 + outer loop + vertex 1.05468 1.15727 2.59565 + vertex 1.05226 1.15471 2.5961 + vertex 1.05488 1.15409 2.59521 + endloop + endfacet + facet normal 0.232561 -0.119495 0.965213 + outer loop + vertex 1.05468 1.15727 2.59565 + vertex 1.05488 1.15409 2.59521 + vertex 1.05858 1.1588 2.5949 + endloop + endfacet + facet normal 0.171536 -0.1187 0.978001 + outer loop + vertex 1.05858 1.1588 2.5949 + vertex 1.06361 1.16358 2.5946 + vertex 1.05991 1.16406 2.5953 + endloop + endfacet + facet normal 0.170077 -0.128415 0.977028 + outer loop + vertex 1.06397 1.16865 2.5952 + vertex 1.05991 1.16406 2.5953 + vertex 1.06361 1.16358 2.5946 + endloop + endfacet + facet normal 0.162262 -0.121451 0.979245 + outer loop + vertex 1.06029 1.16739 2.59565 + vertex 1.05991 1.16406 2.5953 + vertex 1.06397 1.16865 2.5952 + endloop + endfacet + facet normal 0.185996 -0.13423 0.973339 + outer loop + vertex 1.06322 1.15829 2.59394 + vertex 1.06361 1.16358 2.5946 + vertex 1.05858 1.1588 2.5949 + endloop + endfacet + facet normal 0.210818 -0.125936 0.969379 + outer loop + vertex 1.06029 1.16739 2.59565 + vertex 1.0575 1.16486 2.59593 + vertex 1.05991 1.16406 2.5953 + endloop + endfacet + facet normal 0.285773 -0.119114 0.950866 + outer loop + vertex 1.05343 1.16319 2.59684 + vertex 1.0522 1.15799 2.59656 + vertex 1.05596 1.16099 2.5958 + endloop + endfacet + facet normal 0.220399 -0.136912 0.965753 + outer loop + vertex 1.06029 1.16739 2.59565 + vertex 1.05822 1.16874 2.59632 + vertex 1.0575 1.16486 2.59593 + endloop + endfacet + facet normal 0.238934 -0.130461 0.962232 + outer loop + vertex 1.05822 1.16874 2.59632 + vertex 1.05814 1.17334 2.59696 + vertex 1.05332 1.16824 2.59747 + endloop + endfacet + facet normal 0.214898 -0.106864 0.970772 + outer loop + vertex 1.05332 1.16824 2.59747 + vertex 1.05814 1.17334 2.59696 + vertex 1.0532 1.17314 2.59803 + endloop + endfacet + facet normal 0.27517 -0.103667 0.95579 + outer loop + vertex 1.05332 1.16824 2.59747 + vertex 1.0532 1.17314 2.59803 + vertex 1.04875 1.16847 2.59881 + endloop + endfacet + facet normal 0.261732 -0.0900148 0.960934 + outer loop + vertex 1.04875 1.16847 2.59881 + vertex 1.0532 1.17314 2.59803 + vertex 1.0483 1.17367 2.59942 + endloop + endfacet + facet normal 0.259423 -0.108113 0.959693 + outer loop + vertex 1.0532 1.17314 2.59803 + vertex 1.05332 1.17835 2.59859 + vertex 1.0483 1.17367 2.59942 + endloop + endfacet + facet normal 0.239066 -0.0848754 0.967287 + outer loop + vertex 1.0483 1.17367 2.59942 + vertex 1.05332 1.17835 2.59859 + vertex 1.04927 1.17947 2.59969 + endloop + endfacet + facet normal 0.231787 -0.110418 0.966479 + outer loop + vertex 1.05332 1.17835 2.59859 + vertex 1.05359 1.18365 2.59913 + vertex 1.04927 1.17947 2.59969 + endloop + endfacet + facet normal 0.182177 -0.108997 0.977206 + outer loop + vertex 1.05332 1.17835 2.59859 + vertex 1.05818 1.18307 2.59821 + vertex 1.05359 1.18365 2.59913 + endloop + endfacet + facet normal 0.180523 -0.120533 0.976157 + outer loop + vertex 1.05818 1.18307 2.59821 + vertex 1.05825 1.18825 2.59883 + vertex 1.05359 1.18365 2.59913 + endloop + endfacet + facet normal 0.172059 -0.111808 0.978721 + outer loop + vertex 1.05359 1.18365 2.59913 + vertex 1.05825 1.18825 2.59883 + vertex 1.05343 1.18899 2.59976 + endloop + endfacet + facet normal 0.214056 -0.109598 0.970654 + outer loop + vertex 1.05343 1.18899 2.59976 + vertex 1.04973 1.18431 2.60005 + vertex 1.05359 1.18365 2.59913 + endloop + endfacet + facet normal 0.216901 -0.0943285 0.971626 + outer loop + vertex 1.04927 1.17947 2.59969 + vertex 1.05359 1.18365 2.59913 + vertex 1.04973 1.18431 2.60005 + endloop + endfacet + facet normal 0.208636 -0.105208 0.972318 + outer loop + vertex 1.04945 1.18759 2.60047 + vertex 1.04973 1.18431 2.60005 + vertex 1.05343 1.18899 2.59976 + endloop + endfacet + facet normal 0.269347 -0.0982008 0.958023 + outer loop + vertex 1.04945 1.18759 2.60047 + vertex 1.04706 1.18503 2.60088 + vertex 1.04973 1.18431 2.60005 + endloop + endfacet + facet normal 0.282881 -0.111689 0.95263 + outer loop + vertex 1.04945 1.18759 2.60047 + vertex 1.04681 1.18818 2.60132 + vertex 1.04706 1.18503 2.60088 + endloop + endfacet + facet normal 0.172444 -0.109533 0.97891 + outer loop + vertex 1.05825 1.18825 2.59883 + vertex 1.0585 1.1935 2.59938 + vertex 1.05343 1.18899 2.59976 + endloop + endfacet + facet normal 0.164354 -0.100242 0.981295 + outer loop + vertex 1.05343 1.18899 2.59976 + vertex 1.0585 1.1935 2.59938 + vertex 1.05458 1.19451 2.60014 + endloop + endfacet + facet normal 0.206725 -0.108446 0.97237 + outer loop + vertex 1.05343 1.18899 2.59976 + vertex 1.05458 1.19451 2.60014 + vertex 1.05047 1.19128 2.60065 + endloop + endfacet + facet normal 0.208796 -0.105709 0.972229 + outer loop + vertex 1.04945 1.18759 2.60047 + vertex 1.05343 1.18899 2.59976 + vertex 1.05047 1.19128 2.60065 + endloop + endfacet + facet normal 0.279891 -0.124248 0.951958 + outer loop + vertex 1.05047 1.19128 2.60065 + vertex 1.04681 1.18818 2.60132 + vertex 1.04945 1.18759 2.60047 + endloop + endfacet + facet normal 0.263092 -0.102883 0.959269 + outer loop + vertex 1.04732 1.19255 2.60165 + vertex 1.04681 1.18818 2.60132 + vertex 1.05047 1.19128 2.60065 + endloop + endfacet + facet normal 0.259935 -0.11067 0.959263 + outer loop + vertex 1.05139 1.19579 2.60092 + vertex 1.04732 1.19255 2.60165 + vertex 1.05047 1.19128 2.60065 + endloop + endfacet + facet normal 0.249427 -0.0964653 0.963577 + outer loop + vertex 1.04844 1.1979 2.6019 + vertex 1.04732 1.19255 2.60165 + vertex 1.05139 1.19579 2.60092 + endloop + endfacet + facet normal 0.246533 -0.100656 0.963893 + outer loop + vertex 1.05244 1.19952 2.60104 + vertex 1.04844 1.1979 2.6019 + vertex 1.05139 1.19579 2.60092 + endloop + endfacet + facet normal 0.195941 -0.0867888 0.976768 + outer loop + vertex 1.05514 1.19906 2.60046 + vertex 1.05244 1.19952 2.60104 + vertex 1.05139 1.19579 2.60092 + endloop + endfacet + facet normal 0.201993 -0.0940018 0.974865 + outer loop + vertex 1.05458 1.19451 2.60014 + vertex 1.05514 1.19906 2.60046 + vertex 1.05139 1.19579 2.60092 + endloop + endfacet + facet normal 0.162254 -0.0896506 0.982668 + outer loop + vertex 1.05458 1.19451 2.60014 + vertex 1.05886 1.19865 2.59981 + vertex 1.05514 1.19906 2.60046 + endloop + endfacet + facet normal 0.163181 -0.0820871 0.983175 + outer loop + vertex 1.0588 1.20379 2.60025 + vertex 1.05514 1.19906 2.60046 + vertex 1.05886 1.19865 2.59981 + endloop + endfacet + facet normal 0.13933 -0.0826714 0.986789 + outer loop + vertex 1.05886 1.19865 2.59981 + vertex 1.06338 1.20329 2.59956 + vertex 1.0588 1.20379 2.60025 + endloop + endfacet + facet normal 0.1395 -0.0812406 0.986884 + outer loop + vertex 1.06338 1.20329 2.59956 + vertex 1.06368 1.20852 2.59995 + vertex 1.0588 1.20379 2.60025 + endloop + endfacet + facet normal 0.133705 -0.0751755 0.988166 + outer loop + vertex 1.0588 1.20379 2.60025 + vertex 1.06368 1.20852 2.59995 + vertex 1.05999 1.20903 2.60048 + endloop + endfacet + facet normal 0.167538 -0.082588 0.9824 + outer loop + vertex 1.0588 1.20379 2.60025 + vertex 1.05999 1.20903 2.60048 + vertex 1.05613 1.20595 2.60088 + endloop + endfacet + facet normal 0.167347 -0.0828278 0.982413 + outer loop + vertex 1.05495 1.20221 2.60077 + vertex 1.0588 1.20379 2.60025 + vertex 1.05613 1.20595 2.60088 + endloop + endfacet + facet normal 0.20936 -0.0958722 0.973127 + outer loop + vertex 1.05613 1.20595 2.60088 + vertex 1.05227 1.20273 2.6014 + vertex 1.05495 1.20221 2.60077 + endloop + endfacet + facet normal 0.209208 -0.0966018 0.973088 + outer loop + vertex 1.05495 1.20221 2.60077 + vertex 1.05227 1.20273 2.6014 + vertex 1.05244 1.19952 2.60104 + endloop + endfacet + facet normal 0.210701 -0.0975562 0.97267 + outer loop + vertex 1.05342 1.20803 2.60168 + vertex 1.05227 1.20273 2.6014 + vertex 1.05613 1.20595 2.60088 + endloop + endfacet + facet normal 0.210961 -0.0972077 0.972649 + outer loop + vertex 1.05757 1.20985 2.60096 + vertex 1.05342 1.20803 2.60168 + vertex 1.05613 1.20595 2.60088 + endloop + endfacet + facet normal 0.218314 -0.115416 0.96903 + outer loop + vertex 1.05757 1.20985 2.60096 + vertex 1.05824 1.21372 2.60127 + vertex 1.05342 1.20803 2.60168 + endloop + endfacet + facet normal 0.20232 -0.101489 0.974047 + outer loop + vertex 1.05824 1.21372 2.60127 + vertex 1.05327 1.21315 2.60224 + vertex 1.05342 1.20803 2.60168 + endloop + endfacet + facet normal 0.203318 -0.112631 0.972613 + outer loop + vertex 1.05824 1.21372 2.60127 + vertex 1.0582 1.21831 2.60181 + vertex 1.05327 1.21315 2.60224 + endloop + endfacet + facet normal 0.186243 -0.095878 0.977814 + outer loop + vertex 1.05327 1.21315 2.60224 + vertex 1.0582 1.21831 2.60181 + vertex 1.05326 1.21804 2.60273 + endloop + endfacet + facet normal 0.248617 -0.105237 0.962868 + outer loop + vertex 1.05227 1.20273 2.6014 + vertex 1.05342 1.20803 2.60168 + vertex 1.04832 1.20301 2.60245 + endloop + endfacet + facet normal 0.249258 -0.0981823 0.963447 + outer loop + vertex 1.05227 1.20273 2.6014 + vertex 1.04832 1.20301 2.60245 + vertex 1.04844 1.1979 2.6019 + endloop + endfacet + facet normal 0.166282 -0.0809705 0.982748 + outer loop + vertex 1.05999 1.20903 2.60048 + vertex 1.05757 1.20985 2.60096 + vertex 1.05613 1.20595 2.60088 + endloop + endfacet + facet normal 0.131988 -0.0867701 0.987446 + outer loop + vertex 1.06395 1.21355 2.60035 + vertex 1.05999 1.20903 2.60048 + vertex 1.06368 1.20852 2.59995 + endloop + endfacet + facet normal 0.127554 -0.0828623 0.988364 + outer loop + vertex 1.06029 1.21235 2.60072 + vertex 1.05999 1.20903 2.60048 + vertex 1.06395 1.21355 2.60035 + endloop + endfacet + facet normal 0.130728 -0.0929149 0.987055 + outer loop + vertex 1.06395 1.21355 2.60035 + vertex 1.06206 1.21528 2.60076 + vertex 1.06029 1.21235 2.60072 + endloop + endfacet + facet normal 0.179033 -0.121934 0.976258 + outer loop + vertex 1.06206 1.21528 2.60076 + vertex 1.05824 1.21372 2.60127 + vertex 1.06029 1.21235 2.60072 + endloop + endfacet + facet normal 0.186687 -0.110471 0.976189 + outer loop + vertex 1.06029 1.21235 2.60072 + vertex 1.05824 1.21372 2.60127 + vertex 1.05757 1.20985 2.60096 + endloop + endfacet + facet normal 0.184845 -0.137173 0.973147 + outer loop + vertex 1.06206 1.21528 2.60076 + vertex 1.06316 1.21897 2.60108 + vertex 1.05824 1.21372 2.60127 + endloop + endfacet + facet normal 0.1603 -0.113934 0.980471 + outer loop + vertex 1.06316 1.21897 2.60108 + vertex 1.0582 1.21831 2.60181 + vertex 1.05824 1.21372 2.60127 + endloop + endfacet + facet normal 0.161403 -0.123749 0.979099 + outer loop + vertex 1.06316 1.21897 2.60108 + vertex 1.06328 1.22339 2.60161 + vertex 1.0582 1.21831 2.60181 + endloop + endfacet + facet normal 0.146548 -0.108727 0.98321 + outer loop + vertex 1.0582 1.21831 2.60181 + vertex 1.06328 1.22339 2.60161 + vertex 1.05819 1.22296 2.60233 + endloop + endfacet + facet normal 0.122391 -0.123354 0.984786 + outer loop + vertex 1.06834 1.22394 2.60106 + vertex 1.06328 1.22339 2.60161 + vertex 1.06316 1.21897 2.60108 + endloop + endfacet + facet normal 0.136747 -0.138315 0.980902 + outer loop + vertex 1.06708 1.22034 2.60072 + vertex 1.06834 1.22394 2.60106 + vertex 1.06316 1.21897 2.60108 + endloop + endfacet + facet normal 0.135072 -0.133256 0.981834 + outer loop + vertex 1.06708 1.22034 2.60072 + vertex 1.06316 1.21897 2.60108 + vertex 1.06497 1.21742 2.60062 + endloop + endfacet + facet normal 0.102386 -0.109794 0.988667 + outer loop + vertex 1.0688 1.21843 2.60033 + vertex 1.06708 1.22034 2.60072 + vertex 1.06497 1.21742 2.60062 + endloop + endfacet + facet normal 0.0982993 -0.0937952 0.990727 + outer loop + vertex 1.06497 1.21742 2.60062 + vertex 1.06395 1.21355 2.60035 + vertex 1.0688 1.21843 2.60033 + endloop + endfacet + facet normal 0.109184 -0.104623 0.9885 + outer loop + vertex 1.0688 1.21843 2.60033 + vertex 1.06395 1.21355 2.60035 + vertex 1.06845 1.21336 2.59984 + endloop + endfacet + facet normal 0.0948461 -0.10377 0.990069 + outer loop + vertex 1.06845 1.21336 2.59984 + vertex 1.07344 1.21824 2.59987 + vertex 1.0688 1.21843 2.60033 + endloop + endfacet + facet normal 0.0939975 -0.120072 0.988305 + outer loop + vertex 1.07384 1.22309 2.60042 + vertex 1.0688 1.21843 2.60033 + vertex 1.07344 1.21824 2.59987 + endloop + endfacet + facet normal 0.086211 -0.111679 0.989998 + outer loop + vertex 1.07012 1.22231 2.60066 + vertex 1.0688 1.21843 2.60033 + vertex 1.07384 1.22309 2.60042 + endloop + endfacet + facet normal 0.0881167 -0.121147 0.988716 + outer loop + vertex 1.07384 1.22309 2.60042 + vertex 1.0723 1.22506 2.6008 + vertex 1.07012 1.22231 2.60066 + endloop + endfacet + facet normal 0.101237 -0.131405 0.986146 + outer loop + vertex 1.0723 1.22506 2.6008 + vertex 1.06834 1.22394 2.60106 + vertex 1.07012 1.22231 2.60066 + endloop + endfacet + facet normal 0.099052 -0.12338 0.987404 + outer loop + vertex 1.0723 1.22506 2.6008 + vertex 1.07354 1.22862 2.60112 + vertex 1.06834 1.22394 2.60106 + endloop + endfacet + facet normal 0.0968115 -0.120894 0.987933 + outer loop + vertex 1.07354 1.22862 2.60112 + vertex 1.06844 1.22833 2.60158 + vertex 1.06834 1.22394 2.60106 + endloop + endfacet + facet normal 0.0964553 -0.113112 0.988889 + outer loop + vertex 1.07354 1.22862 2.60112 + vertex 1.07354 1.23317 2.60164 + vertex 1.06844 1.22833 2.60158 + endloop + endfacet + facet normal 0.0988643 -0.115649 0.988358 + outer loop + vertex 1.06844 1.22833 2.60158 + vertex 1.07354 1.23317 2.60164 + vertex 1.06834 1.23293 2.60213 + endloop + endfacet + facet normal 0.0988186 -0.114334 0.988515 + outer loop + vertex 1.07354 1.23317 2.60164 + vertex 1.07335 1.23788 2.6022 + vertex 1.06834 1.23293 2.60213 + endloop + endfacet + facet normal 0.110173 -0.0858456 0.990198 + outer loop + vertex 1.06368 1.20852 2.59995 + vertex 1.06845 1.21336 2.59984 + vertex 1.06395 1.21355 2.60035 + endloop + endfacet + facet normal 0.11676 -0.0923586 0.988856 + outer loop + vertex 1.06821 1.20816 2.59938 + vertex 1.06845 1.21336 2.59984 + vertex 1.06368 1.20852 2.59995 + endloop + endfacet + facet normal 0.101877 -0.0918188 0.99055 + outer loop + vertex 1.06821 1.20816 2.59938 + vertex 1.07318 1.21311 2.59933 + vertex 1.06845 1.21336 2.59984 + endloop + endfacet + facet normal 0.100767 -0.109821 0.98883 + outer loop + vertex 1.07318 1.21311 2.59933 + vertex 1.07344 1.21824 2.59987 + vertex 1.06845 1.21336 2.59984 + endloop + endfacet + facet normal 0.104029 -0.0939826 0.990124 + outer loop + vertex 1.07308 1.20796 2.59885 + vertex 1.07318 1.21311 2.59933 + vertex 1.06821 1.20816 2.59938 + endloop + endfacet + facet normal 0.10462 -0.0819287 0.991132 + outer loop + vertex 1.06811 1.20297 2.59896 + vertex 1.07308 1.20796 2.59885 + vertex 1.06821 1.20816 2.59938 + endloop + endfacet + facet normal 0.119732 -0.0820814 0.989407 + outer loop + vertex 1.06811 1.20297 2.59896 + vertex 1.06821 1.20816 2.59938 + vertex 1.06338 1.20329 2.59956 + endloop + endfacet + facet normal 0.119679 -0.0827702 0.989356 + outer loop + vertex 1.06326 1.19812 2.59914 + vertex 1.06811 1.20297 2.59896 + vertex 1.06338 1.20329 2.59956 + endloop + endfacet + facet normal 0.119607 -0.0826978 0.989371 + outer loop + vertex 1.0681 1.19788 2.59854 + vertex 1.06811 1.20297 2.59896 + vertex 1.06326 1.19812 2.59914 + endloop + endfacet + facet normal 0.103186 -0.0828171 0.991208 + outer loop + vertex 1.0681 1.19788 2.59854 + vertex 1.07309 1.20289 2.59843 + vertex 1.06811 1.20297 2.59896 + endloop + endfacet + facet normal 0.100302 -0.0799304 0.991741 + outer loop + vertex 1.07313 1.19788 2.59803 + vertex 1.07309 1.20289 2.59843 + vertex 1.0681 1.19788 2.59854 + endloop + endfacet + facet normal 0.103245 -0.0805503 0.991389 + outer loop + vertex 1.07309 1.20289 2.59843 + vertex 1.07308 1.20796 2.59885 + vertex 1.06811 1.20297 2.59896 + endloop + endfacet + facet normal 0.0965434 -0.115075 0.988654 + outer loop + vertex 1.07012 1.22231 2.60066 + vertex 1.06708 1.22034 2.60072 + vertex 1.0688 1.21843 2.60033 + endloop + endfacet + facet normal 0.104683 -0.127677 0.986276 + outer loop + vertex 1.07012 1.22231 2.60066 + vertex 1.06834 1.22394 2.60106 + vertex 1.06708 1.22034 2.60072 + endloop + endfacet + facet normal 0.122182 -0.121139 0.985087 + outer loop + vertex 1.06834 1.22394 2.60106 + vertex 1.06844 1.22833 2.60158 + vertex 1.06328 1.22339 2.60161 + endloop + endfacet + facet normal 0.116784 -0.115496 0.986419 + outer loop + vertex 1.06328 1.22339 2.60161 + vertex 1.06844 1.22833 2.60158 + vertex 1.06326 1.22795 2.60215 + endloop + endfacet + facet normal 0.142032 -0.1252 0.981912 + outer loop + vertex 1.06497 1.21742 2.60062 + vertex 1.06316 1.21897 2.60108 + vertex 1.06206 1.21528 2.60076 + endloop + endfacet + facet normal 0.123962 -0.100315 0.987203 + outer loop + vertex 1.06497 1.21742 2.60062 + vertex 1.06206 1.21528 2.60076 + vertex 1.06395 1.21355 2.60035 + endloop + endfacet + facet normal 0.164626 -0.0858132 0.982616 + outer loop + vertex 1.06029 1.21235 2.60072 + vertex 1.05757 1.20985 2.60096 + vertex 1.05999 1.20903 2.60048 + endloop + endfacet + facet normal 0.11785 -0.080199 0.989788 + outer loop + vertex 1.06338 1.20329 2.59956 + vertex 1.06821 1.20816 2.59938 + vertex 1.06368 1.20852 2.59995 + endloop + endfacet + facet normal 0.139663 -0.0829993 0.986714 + outer loop + vertex 1.06326 1.19812 2.59914 + vertex 1.06338 1.20329 2.59956 + vertex 1.05886 1.19865 2.59981 + endloop + endfacet + facet normal 0.138471 -0.0921608 0.986069 + outer loop + vertex 1.0585 1.1935 2.59938 + vertex 1.06326 1.19812 2.59914 + vertex 1.05886 1.19865 2.59981 + endloop + endfacet + facet normal 0.142248 -0.0960998 0.985155 + outer loop + vertex 1.06316 1.19299 2.59865 + vertex 1.06326 1.19812 2.59914 + vertex 1.0585 1.1935 2.59938 + endloop + endfacet + facet normal 0.140704 -0.1085 0.984088 + outer loop + vertex 1.05825 1.18825 2.59883 + vertex 1.06316 1.19299 2.59865 + vertex 1.0585 1.1935 2.59938 + endloop + endfacet + facet normal 0.145982 -0.114025 0.982694 + outer loop + vertex 1.06314 1.18792 2.59807 + vertex 1.06316 1.19299 2.59865 + vertex 1.05825 1.18825 2.59883 + endloop + endfacet + facet normal 0.118492 -0.114339 0.98635 + outer loop + vertex 1.06314 1.18792 2.59807 + vertex 1.06813 1.19286 2.59804 + vertex 1.06316 1.19299 2.59865 + endloop + endfacet + facet normal 0.119176 -0.0962598 0.988196 + outer loop + vertex 1.06813 1.19286 2.59804 + vertex 1.0681 1.19788 2.59854 + vertex 1.06316 1.19299 2.59865 + endloop + endfacet + facet normal 0.100132 -0.0965986 0.990274 + outer loop + vertex 1.06813 1.19286 2.59804 + vertex 1.07313 1.19788 2.59803 + vertex 1.0681 1.19788 2.59854 + endloop + endfacet + facet normal 0.0967021 -0.0931776 0.990942 + outer loop + vertex 1.07326 1.19295 2.59755 + vertex 1.07313 1.19788 2.59803 + vertex 1.06813 1.19286 2.59804 + endloop + endfacet + facet normal 0.0968608 -0.116627 0.988441 + outer loop + vertex 1.06825 1.18798 2.59745 + vertex 1.07326 1.19295 2.59755 + vertex 1.06813 1.19286 2.59804 + endloop + endfacet + facet normal 0.0935628 -0.11332 0.989143 + outer loop + vertex 1.07353 1.1882 2.59698 + vertex 1.07326 1.19295 2.59755 + vertex 1.06825 1.18798 2.59745 + endloop + endfacet + facet normal 0.0942625 -0.135562 0.986274 + outer loop + vertex 1.06842 1.18332 2.5968 + vertex 1.07353 1.1882 2.59698 + vertex 1.06825 1.18798 2.59745 + endloop + endfacet + facet normal 0.123811 -0.134062 0.983208 + outer loop + vertex 1.06842 1.18332 2.5968 + vertex 1.06825 1.18798 2.59745 + vertex 1.06319 1.18303 2.59742 + endloop + endfacet + facet normal 0.124021 -0.139408 0.982438 + outer loop + vertex 1.06321 1.17841 2.59676 + vertex 1.06842 1.18332 2.5968 + vertex 1.06319 1.18303 2.59742 + endloop + endfacet + facet normal 0.139157 -0.155413 0.977999 + outer loop + vertex 1.06835 1.1789 2.5961 + vertex 1.06842 1.18332 2.5968 + vertex 1.06321 1.17841 2.59676 + endloop + endfacet + facet normal 0.138731 -0.149571 0.97897 + outer loop + vertex 1.06835 1.1789 2.5961 + vertex 1.06321 1.17841 2.59676 + vertex 1.06314 1.17402 2.5961 + endloop + endfacet + facet normal 0.166126 -0.178828 0.969754 + outer loop + vertex 1.06706 1.17537 2.59568 + vertex 1.06835 1.1789 2.5961 + vertex 1.06314 1.17402 2.5961 + endloop + endfacet + facet normal 0.160351 -0.160793 0.973875 + outer loop + vertex 1.06706 1.17537 2.59568 + vertex 1.06314 1.17402 2.5961 + vertex 1.06499 1.17252 2.59555 + endloop + endfacet + facet normal 0.114008 -0.127667 0.985243 + outer loop + vertex 1.06874 1.17343 2.59523 + vertex 1.06706 1.17537 2.59568 + vertex 1.06499 1.17252 2.59555 + endloop + endfacet + facet normal 0.111696 -0.117579 0.986762 + outer loop + vertex 1.06499 1.17252 2.59555 + vertex 1.06397 1.16865 2.5952 + vertex 1.06874 1.17343 2.59523 + endloop + endfacet + facet normal 0.124134 -0.129974 0.983716 + outer loop + vertex 1.06874 1.17343 2.59523 + vertex 1.06397 1.16865 2.5952 + vertex 1.06846 1.16846 2.59461 + endloop + endfacet + facet normal 0.0845577 -0.128304 0.988124 + outer loop + vertex 1.06846 1.16846 2.59461 + vertex 1.07342 1.1733 2.59481 + vertex 1.06874 1.17343 2.59523 + endloop + endfacet + facet normal 0.0842336 -0.136422 0.987063 + outer loop + vertex 1.0733 1.17735 2.59538 + vertex 1.06874 1.17343 2.59523 + vertex 1.07342 1.1733 2.59481 + endloop + endfacet + facet normal 0.0755832 -0.126433 0.989091 + outer loop + vertex 1.07001 1.17714 2.59561 + vertex 1.06874 1.17343 2.59523 + vertex 1.0733 1.17735 2.59538 + endloop + endfacet + facet normal 0.0767741 -0.147724 0.986044 + outer loop + vertex 1.0733 1.17735 2.59538 + vertex 1.07246 1.17974 2.59581 + vertex 1.07001 1.17714 2.59561 + endloop + endfacet + facet normal 0.107278 -0.175763 0.97857 + outer loop + vertex 1.07246 1.17974 2.59581 + vertex 1.06835 1.1789 2.5961 + vertex 1.07001 1.17714 2.59561 + endloop + endfacet + facet normal 0.106071 -0.16949 0.979807 + outer loop + vertex 1.07246 1.17974 2.59581 + vertex 1.07397 1.18357 2.5963 + vertex 1.06835 1.1789 2.5961 + endloop + endfacet + facet normal 0.154439 -0.128229 0.979646 + outer loop + vertex 1.06499 1.17252 2.59555 + vertex 1.06209 1.17036 2.59572 + vertex 1.06397 1.16865 2.5952 + endloop + endfacet + facet normal 0.16183 -0.120102 0.979483 + outer loop + vertex 1.06397 1.16865 2.5952 + vertex 1.06209 1.17036 2.59572 + vertex 1.06029 1.16739 2.59565 + endloop + endfacet + facet normal 0.211776 -0.150076 0.965727 + outer loop + vertex 1.06209 1.17036 2.59572 + vertex 1.05822 1.16874 2.59632 + vertex 1.06029 1.16739 2.59565 + endloop + endfacet + facet normal 0.216078 -0.161397 0.962944 + outer loop + vertex 1.06209 1.17036 2.59572 + vertex 1.06314 1.17402 2.5961 + vertex 1.05822 1.16874 2.59632 + endloop + endfacet + facet normal 0.104432 -0.135929 0.985199 + outer loop + vertex 1.07001 1.17714 2.59561 + vertex 1.06706 1.17537 2.59568 + vertex 1.06874 1.17343 2.59523 + endloop + endfacet + facet normal 0.169798 -0.149264 0.974109 + outer loop + vertex 1.06499 1.17252 2.59555 + vertex 1.06314 1.17402 2.5961 + vertex 1.06209 1.17036 2.59572 + endloop + endfacet + facet normal 0.120646 -0.163315 0.979169 + outer loop + vertex 1.07001 1.17714 2.59561 + vertex 1.06835 1.1789 2.5961 + vertex 1.06706 1.17537 2.59568 + endloop + endfacet + facet normal 0.0943627 -0.155541 0.983312 + outer loop + vertex 1.07397 1.18357 2.5963 + vertex 1.06842 1.18332 2.5968 + vertex 1.06835 1.1789 2.5961 + endloop + endfacet + facet normal 0.119852 -0.130017 0.984241 + outer loop + vertex 1.06319 1.18303 2.59742 + vertex 1.06825 1.18798 2.59745 + vertex 1.06314 1.18792 2.59807 + endloop + endfacet + facet normal 0.0937377 -0.135018 0.986399 + outer loop + vertex 1.07397 1.18357 2.5963 + vertex 1.07353 1.1882 2.59698 + vertex 1.06842 1.18332 2.5968 + endloop + endfacet + facet normal 0.119909 -0.115773 0.986011 + outer loop + vertex 1.06825 1.18798 2.59745 + vertex 1.06813 1.19286 2.59804 + vertex 1.06314 1.18792 2.59807 + endloop + endfacet + facet normal 0.118819 -0.0958974 0.988274 + outer loop + vertex 1.06316 1.19299 2.59865 + vertex 1.0681 1.19788 2.59854 + vertex 1.06326 1.19812 2.59914 + endloop + endfacet + facet normal 0.168764 -0.0864637 0.981857 + outer loop + vertex 1.05495 1.20221 2.60077 + vertex 1.05514 1.19906 2.60046 + vertex 1.0588 1.20379 2.60025 + endloop + endfacet + facet normal 0.1964 -0.0842749 0.976895 + outer loop + vertex 1.05495 1.20221 2.60077 + vertex 1.05244 1.19952 2.60104 + vertex 1.05514 1.19906 2.60046 + endloop + endfacet + facet normal 0.244063 -0.0938852 0.965204 + outer loop + vertex 1.05244 1.19952 2.60104 + vertex 1.05227 1.20273 2.6014 + vertex 1.04844 1.1979 2.6019 + endloop + endfacet + facet normal 0.199853 -0.0993194 0.974779 + outer loop + vertex 1.05047 1.19128 2.60065 + vertex 1.05458 1.19451 2.60014 + vertex 1.05139 1.19579 2.60092 + endloop + endfacet + facet normal 0.166102 -0.0937188 0.981645 + outer loop + vertex 1.0585 1.1935 2.59938 + vertex 1.05886 1.19865 2.59981 + vertex 1.05458 1.19451 2.60014 + endloop + endfacet + facet normal 0.145408 -0.120823 0.981967 + outer loop + vertex 1.05818 1.18307 2.59821 + vertex 1.06314 1.18792 2.59807 + vertex 1.05825 1.18825 2.59883 + endloop + endfacet + facet normal 0.153416 -0.129071 0.979696 + outer loop + vertex 1.06319 1.18303 2.59742 + vertex 1.06314 1.18792 2.59807 + vertex 1.05818 1.18307 2.59821 + endloop + endfacet + facet normal 0.153523 -0.125406 0.980155 + outer loop + vertex 1.05813 1.17808 2.59757 + vertex 1.06319 1.18303 2.59742 + vertex 1.05818 1.18307 2.59821 + endloop + endfacet + facet normal 0.166023 -0.138276 0.976379 + outer loop + vertex 1.06321 1.17841 2.59676 + vertex 1.06319 1.18303 2.59742 + vertex 1.05813 1.17808 2.59757 + endloop + endfacet + facet normal 0.165518 -0.126642 0.978042 + outer loop + vertex 1.05814 1.17334 2.59696 + vertex 1.06321 1.17841 2.59676 + vertex 1.05813 1.17808 2.59757 + endloop + endfacet + facet normal 0.187745 -0.149143 0.970829 + outer loop + vertex 1.06314 1.17402 2.5961 + vertex 1.06321 1.17841 2.59676 + vertex 1.05814 1.17334 2.59696 + endloop + endfacet + facet normal 0.197223 -0.124859 0.972375 + outer loop + vertex 1.05813 1.17808 2.59757 + vertex 1.05818 1.18307 2.59821 + vertex 1.05332 1.17835 2.59859 + endloop + endfacet + facet normal 0.198532 -0.108166 0.974107 + outer loop + vertex 1.0532 1.17314 2.59803 + vertex 1.05813 1.17808 2.59757 + vertex 1.05332 1.17835 2.59859 + endloop + endfacet + facet normal 0.215134 -0.125309 0.968512 + outer loop + vertex 1.05814 1.17334 2.59696 + vertex 1.05813 1.17808 2.59757 + vertex 1.0532 1.17314 2.59803 + endloop + endfacet + facet normal 0.185983 -0.132889 0.973525 + outer loop + vertex 1.06314 1.17402 2.5961 + vertex 1.05814 1.17334 2.59696 + vertex 1.05822 1.16874 2.59632 + endloop + endfacet + facet normal 0.340064 -0.0964649 0.935442 + outer loop + vertex 1.05429 1.14476 2.5944 + vertex 1.05458 1.14961 2.5948 + vertex 1.0508 1.14617 2.59581 + endloop + endfacet + facet normal 0.302901 -0.0879189 0.948958 + outer loop + vertex 1.05488 1.15409 2.59521 + vertex 1.05226 1.15471 2.5961 + vertex 1.05136 1.15094 2.59604 + endloop + endfacet + facet normal 0.240545 -0.12596 0.96243 + outer loop + vertex 1.05858 1.1588 2.5949 + vertex 1.05488 1.15409 2.59521 + vertex 1.05865 1.15366 2.59421 + endloop + endfacet + facet normal 0.186778 -0.128295 0.973989 + outer loop + vertex 1.05865 1.15366 2.59421 + vertex 1.06322 1.15829 2.59394 + vertex 1.05858 1.1588 2.5949 + endloop + endfacet + facet normal 0.150545 -0.142297 0.978309 + outer loop + vertex 1.06827 1.15302 2.59243 + vertex 1.06804 1.15796 2.59319 + vertex 1.06318 1.15316 2.59324 + endloop + endfacet + facet normal 0.150886 -0.135528 0.979217 + outer loop + vertex 1.06337 1.14826 2.59253 + vertex 1.06827 1.15302 2.59243 + vertex 1.06318 1.15316 2.59324 + endloop + endfacet + facet normal 0.162863 -0.147918 0.975498 + outer loop + vertex 1.06898 1.14823 2.59159 + vertex 1.06827 1.15302 2.59243 + vertex 1.06337 1.14826 2.59253 + endloop + endfacet + facet normal 0.163012 -0.142743 0.976244 + outer loop + vertex 1.06898 1.14823 2.59159 + vertex 1.06337 1.14826 2.59253 + vertex 1.06358 1.14325 2.59176 + endloop + endfacet + facet normal 0.205887 -0.189811 0.959991 + outer loop + vertex 1.06801 1.14432 2.59102 + vertex 1.06898 1.14823 2.59159 + vertex 1.06358 1.14325 2.59176 + endloop + endfacet + facet normal 0.201943 -0.170421 0.964456 + outer loop + vertex 1.06801 1.14432 2.59102 + vertex 1.06358 1.14325 2.59176 + vertex 1.06617 1.141 2.59082 + endloop + endfacet + facet normal 0.158413 -0.14711 0.976352 + outer loop + vertex 1.06954 1.14273 2.59054 + vertex 1.06801 1.14432 2.59102 + vertex 1.06617 1.141 2.59082 + endloop + endfacet + facet normal 0.150144 -0.130476 0.980017 + outer loop + vertex 1.06864 1.13882 2.59015 + vertex 1.06954 1.14273 2.59054 + vertex 1.06617 1.141 2.59082 + endloop + endfacet + facet normal 0.155346 -0.124573 0.979974 + outer loop + vertex 1.06485 1.13765 2.5906 + vertex 1.06864 1.13882 2.59015 + vertex 1.06617 1.141 2.59082 + endloop + endfacet + facet normal 0.235676 -0.154966 0.959397 + outer loop + vertex 1.06617 1.141 2.59082 + vertex 1.0622 1.13828 2.59136 + vertex 1.06485 1.13765 2.5906 + endloop + endfacet + facet normal 0.24067 -0.135868 0.96105 + outer loop + vertex 1.06485 1.13765 2.5906 + vertex 1.0622 1.13828 2.59136 + vertex 1.06221 1.13509 2.5909 + endloop + endfacet + facet normal 0.221056 -0.114837 0.968476 + outer loop + vertex 1.06485 1.13765 2.5906 + vertex 1.06221 1.13509 2.5909 + vertex 1.06482 1.13434 2.59022 + endloop + endfacet + facet normal 0.226939 -0.141368 0.963594 + outer loop + vertex 1.06358 1.14325 2.59176 + vertex 1.0622 1.13828 2.59136 + vertex 1.06617 1.141 2.59082 + endloop + endfacet + facet normal 0.152772 -0.115639 0.981473 + outer loop + vertex 1.06485 1.13765 2.5906 + vertex 1.06482 1.13434 2.59022 + vertex 1.06864 1.13882 2.59015 + endloop + endfacet + facet normal 0.15793 -0.120051 0.980125 + outer loop + vertex 1.06864 1.13882 2.59015 + vertex 1.06482 1.13434 2.59022 + vertex 1.06861 1.13371 2.58953 + endloop + endfacet + facet normal 0.160598 -0.105264 0.981391 + outer loop + vertex 1.06362 1.12894 2.58984 + vertex 1.06861 1.13371 2.58953 + vertex 1.06482 1.13434 2.59022 + endloop + endfacet + facet normal 0.181644 -0.12771 0.975036 + outer loop + vertex 1.06829 1.12832 2.58889 + vertex 1.06861 1.13371 2.58953 + vertex 1.06362 1.12894 2.58984 + endloop + endfacet + facet normal 0.182885 -0.11956 0.975837 + outer loop + vertex 1.06369 1.12365 2.58918 + vertex 1.06829 1.12832 2.58889 + vertex 1.06362 1.12894 2.58984 + endloop + endfacet + facet normal 0.192153 -0.128873 0.972866 + outer loop + vertex 1.06818 1.1231 2.58821 + vertex 1.06829 1.12832 2.58889 + vertex 1.06369 1.12365 2.58918 + endloop + endfacet + facet normal 0.194601 -0.111814 0.974489 + outer loop + vertex 1.0636 1.11864 2.58862 + vertex 1.06818 1.1231 2.58821 + vertex 1.06369 1.12365 2.58918 + endloop + endfacet + facet normal 0.206331 -0.124239 0.970563 + outer loop + vertex 1.06832 1.11816 2.58755 + vertex 1.06818 1.1231 2.58821 + vertex 1.0636 1.11864 2.58862 + endloop + endfacet + facet normal 0.124355 -0.126094 0.984193 + outer loop + vertex 1.06361 1.16358 2.5946 + vertex 1.06846 1.16846 2.59461 + vertex 1.06397 1.16865 2.5952 + endloop + endfacet + facet normal 0.0964389 -0.140395 0.985388 + outer loop + vertex 1.0732 1.16821 2.59411 + vertex 1.07342 1.1733 2.59481 + vertex 1.06846 1.16846 2.59461 + endloop + endfacet + facet normal 0.111059 -0.139864 0.983923 + outer loop + vertex 1.07311 1.12796 2.58815 + vertex 1.07816 1.133 2.5883 + vertex 1.07322 1.13323 2.58889 + endloop + endfacet + facet normal 0.110377 -0.150755 0.98239 + outer loop + vertex 1.07816 1.133 2.5883 + vertex 1.07819 1.13826 2.5891 + vertex 1.07322 1.13323 2.58889 + endloop + endfacet + facet normal 0.096626 -0.137338 0.9858 + outer loop + vertex 1.07322 1.13323 2.58889 + vertex 1.07819 1.13826 2.5891 + vertex 1.07329 1.13847 2.58961 + endloop + endfacet + facet normal 0.0957329 -0.152614 0.983638 + outer loop + vertex 1.07819 1.13826 2.5891 + vertex 1.07815 1.14372 2.58995 + vertex 1.07329 1.13847 2.58961 + endloop + endfacet + facet normal 0.0777385 -0.136196 0.987627 + outer loop + vertex 1.07329 1.13847 2.58961 + vertex 1.07815 1.14372 2.58995 + vertex 1.07293 1.14283 2.59024 + endloop + endfacet + facet normal 0.0808786 -0.155594 0.984505 + outer loop + vertex 1.07293 1.14283 2.59024 + vertex 1.07815 1.14372 2.58995 + vertex 1.07606 1.14676 2.5906 + endloop + endfacet + facet normal 0.0789265 -0.154072 0.984902 + outer loop + vertex 1.07171 1.14584 2.59081 + vertex 1.07293 1.14283 2.59024 + vertex 1.07606 1.14676 2.5906 + endloop + endfacet + facet normal 0.0801354 -0.160085 0.983845 + outer loop + vertex 1.07606 1.14676 2.5906 + vertex 1.07467 1.14971 2.5912 + vertex 1.07171 1.14584 2.59081 + endloop + endfacet + facet normal 0.121952 -0.150699 0.981029 + outer loop + vertex 1.07819 1.12801 2.58753 + vertex 1.07816 1.133 2.5883 + vertex 1.07311 1.12796 2.58815 + endloop + endfacet + facet normal 0.132422 -0.157011 0.978679 + outer loop + vertex 1.08327 1.12398 2.58623 + vertex 1.08334 1.12841 2.58693 + vertex 1.07826 1.12339 2.58681 + endloop + endfacet + facet normal 0.131409 -0.146665 0.980419 + outer loop + vertex 1.08327 1.12398 2.58623 + vertex 1.07826 1.12339 2.58681 + vertex 1.0783 1.11907 2.58616 + endloop + endfacet + facet normal 0.139375 -0.154701 0.978081 + outer loop + vertex 1.08208 1.12028 2.58581 + vertex 1.08327 1.12398 2.58623 + vertex 1.0783 1.11907 2.58616 + endloop + endfacet + facet normal 0.136972 -0.146713 0.97965 + outer loop + vertex 1.08208 1.12028 2.58581 + vertex 1.0783 1.11907 2.58616 + vertex 1.07999 1.11734 2.58567 + endloop + endfacet + facet normal 0.149678 -0.155585 0.976417 + outer loop + vertex 1.08376 1.1184 2.58526 + vertex 1.08208 1.12028 2.58581 + vertex 1.07999 1.11734 2.58567 + endloop + endfacet + facet normal 0.148138 -0.149643 0.97758 + outer loop + vertex 1.07999 1.11734 2.58567 + vertex 1.07872 1.11341 2.58526 + vertex 1.08376 1.1184 2.58526 + endloop + endfacet + facet normal 0.138526 -0.146723 0.97943 + outer loop + vertex 1.07999 1.11734 2.58567 + vertex 1.07717 1.11543 2.58578 + vertex 1.07872 1.11341 2.58526 + endloop + endfacet + facet normal 0.138847 -0.146474 0.979422 + outer loop + vertex 1.07872 1.11341 2.58526 + vertex 1.07717 1.11543 2.58578 + vertex 1.07497 1.1126 2.58567 + endloop + endfacet + facet normal 0.13653 -0.134769 0.981426 + outer loop + vertex 1.07497 1.1126 2.58567 + vertex 1.0737 1.10862 2.5853 + vertex 1.07872 1.11341 2.58526 + endloop + endfacet + facet normal 0.141937 -0.140438 0.979863 + outer loop + vertex 1.07872 1.11341 2.58526 + vertex 1.0737 1.10862 2.5853 + vertex 1.07838 1.10829 2.58457 + endloop + endfacet + facet normal 0.153915 -0.140971 0.977976 + outer loop + vertex 1.07838 1.10829 2.58457 + vertex 1.08338 1.11327 2.5845 + vertex 1.07872 1.11341 2.58526 + endloop + endfacet + facet normal 0.160892 -0.148002 0.975812 + outer loop + vertex 1.08321 1.10813 2.58375 + vertex 1.08338 1.11327 2.5845 + vertex 1.07838 1.10829 2.58457 + endloop + endfacet + facet normal 0.161745 -0.132631 0.977879 + outer loop + vertex 1.07821 1.10315 2.5839 + vertex 1.08321 1.10813 2.58375 + vertex 1.07838 1.10829 2.58457 + endloop + endfacet + facet normal 0.153657 -0.132533 0.979196 + outer loop + vertex 1.07821 1.10315 2.5839 + vertex 1.07838 1.10829 2.58457 + vertex 1.07351 1.10351 2.58469 + endloop + endfacet + facet normal 0.15529 -0.115368 0.981109 + outer loop + vertex 1.07328 1.09832 2.58411 + vertex 1.07821 1.10315 2.5839 + vertex 1.07351 1.10351 2.58469 + endloop + endfacet + facet normal 0.170455 -0.131022 0.976616 + outer loop + vertex 1.07815 1.09816 2.58324 + vertex 1.07821 1.10315 2.5839 + vertex 1.07328 1.09832 2.58411 + endloop + endfacet + facet normal 0.171428 -0.11234 0.978771 + outer loop + vertex 1.07326 1.09326 2.58354 + vertex 1.07815 1.09816 2.58324 + vertex 1.07328 1.09832 2.58411 + endloop + endfacet + facet normal 0.19209 -0.133343 0.972276 + outer loop + vertex 1.07817 1.09332 2.58258 + vertex 1.07815 1.09816 2.58324 + vertex 1.07326 1.09326 2.58354 + endloop + endfacet + facet normal 0.192352 -0.109247 0.975226 + outer loop + vertex 1.07325 1.08831 2.58299 + vertex 1.07817 1.09332 2.58258 + vertex 1.07326 1.09326 2.58354 + endloop + endfacet + facet normal 0.21073 -0.127799 0.969154 + outer loop + vertex 1.07832 1.08825 2.58187 + vertex 1.07817 1.09332 2.58258 + vertex 1.07325 1.08831 2.58299 + endloop + endfacet + facet normal 0.211802 -0.0982536 0.972361 + outer loop + vertex 1.07305 1.08328 2.58252 + vertex 1.07832 1.08825 2.58187 + vertex 1.07325 1.08831 2.58299 + endloop + endfacet + facet normal 0.213994 -0.100677 0.971633 + outer loop + vertex 1.0771 1.0826 2.58156 + vertex 1.07832 1.08825 2.58187 + vertex 1.07305 1.08328 2.58252 + endloop + endfacet + facet normal 0.21724 -0.0828728 0.972594 + outer loop + vertex 1.07286 1.07831 2.58214 + vertex 1.0771 1.0826 2.58156 + vertex 1.07305 1.08328 2.58252 + endloop + endfacet + facet normal 0.216782 -0.0824009 0.972736 + outer loop + vertex 1.07676 1.07806 2.58125 + vertex 1.0771 1.0826 2.58156 + vertex 1.07286 1.07831 2.58214 + endloop + endfacet + facet normal 0.217018 -0.0793809 0.972935 + outer loop + vertex 1.07676 1.07806 2.58125 + vertex 1.07286 1.07831 2.58214 + vertex 1.07325 1.07331 2.58165 + endloop + endfacet + facet normal 0.225518 -0.0858612 0.970448 + outer loop + vertex 1.07723 1.07495 2.58086 + vertex 1.07676 1.07806 2.58125 + vertex 1.07325 1.07331 2.58165 + endloop + endfacet + facet normal 0.232694 -0.104966 0.966869 + outer loop + vertex 1.07723 1.07495 2.58086 + vertex 1.07325 1.07331 2.58165 + vertex 1.07639 1.07123 2.58066 + endloop + endfacet + facet normal 0.237853 -0.0969739 0.966448 + outer loop + vertex 1.07325 1.07331 2.58165 + vertex 1.07244 1.06802 2.58131 + vertex 1.07639 1.07123 2.58066 + endloop + endfacet + facet normal 0.253636 -0.117718 0.96011 + outer loop + vertex 1.07639 1.07123 2.58066 + vertex 1.07244 1.06802 2.58131 + vertex 1.07558 1.06684 2.58034 + endloop + endfacet + facet normal 0.254075 -0.116574 0.960133 + outer loop + vertex 1.07244 1.06802 2.58131 + vertex 1.07238 1.06459 2.58091 + vertex 1.07558 1.06684 2.58034 + endloop + endfacet + facet normal 0.261553 -0.128104 0.95665 + outer loop + vertex 1.07558 1.06684 2.58034 + vertex 1.07238 1.06459 2.58091 + vertex 1.07418 1.06322 2.58024 + endloop + endfacet + facet normal 0.287003 -0.137713 0.947979 + outer loop + vertex 1.07418 1.06322 2.58024 + vertex 1.07825 1.06426 2.57916 + vertex 1.07558 1.06684 2.58034 + endloop + endfacet + facet normal 0.291442 -0.132826 0.947322 + outer loop + vertex 1.07825 1.06426 2.57916 + vertex 1.07958 1.06989 2.57954 + vertex 1.07558 1.06684 2.58034 + endloop + endfacet + facet normal 0.284434 -0.122711 0.95081 + outer loop + vertex 1.07558 1.06684 2.58034 + vertex 1.07958 1.06989 2.57954 + vertex 1.07639 1.07123 2.58066 + endloop + endfacet + facet normal 0.283963 -0.123829 0.950806 + outer loop + vertex 1.07958 1.06989 2.57954 + vertex 1.08001 1.07445 2.58 + vertex 1.07639 1.07123 2.58066 + endloop + endfacet + facet normal 0.275931 -0.11408 0.954384 + outer loop + vertex 1.08001 1.07445 2.58 + vertex 1.07723 1.07495 2.58086 + vertex 1.07639 1.07123 2.58066 + endloop + endfacet + facet normal 0.277006 -0.108659 0.954705 + outer loop + vertex 1.07957 1.07762 2.58049 + vertex 1.07723 1.07495 2.58086 + vertex 1.08001 1.07445 2.58 + endloop + endfacet + facet normal 0.289319 -0.106456 0.951295 + outer loop + vertex 1.07957 1.07762 2.58049 + vertex 1.08001 1.07445 2.58 + vertex 1.08349 1.07919 2.57947 + endloop + endfacet + facet normal 0.284434 -0.0922934 0.954243 + outer loop + vertex 1.07957 1.07762 2.58049 + vertex 1.08349 1.07919 2.57947 + vertex 1.0804 1.08142 2.58061 + endloop + endfacet + facet normal 0.247532 -0.0846514 0.965175 + outer loop + vertex 1.0804 1.08142 2.58061 + vertex 1.07676 1.07806 2.58125 + vertex 1.07957 1.07762 2.58049 + endloop + endfacet + facet normal 0.247088 -0.0841406 0.965333 + outer loop + vertex 1.0771 1.0826 2.58156 + vertex 1.07676 1.07806 2.58125 + vertex 1.0804 1.08142 2.58061 + endloop + endfacet + facet normal 0.241643 -0.0993733 0.965264 + outer loop + vertex 1.08124 1.08615 2.58089 + vertex 1.0771 1.0826 2.58156 + vertex 1.0804 1.08142 2.58061 + endloop + endfacet + facet normal 0.261567 -0.102611 0.959715 + outer loop + vertex 1.0804 1.08142 2.58061 + vertex 1.08442 1.08478 2.57987 + vertex 1.08124 1.08615 2.58089 + endloop + endfacet + facet normal 0.251684 -0.125513 0.959636 + outer loop + vertex 1.08442 1.08478 2.57987 + vertex 1.08504 1.08943 2.58032 + vertex 1.08124 1.08615 2.58089 + endloop + endfacet + facet normal 0.249729 -0.123109 0.960458 + outer loop + vertex 1.08504 1.08943 2.58032 + vertex 1.08254 1.09016 2.58106 + vertex 1.08124 1.08615 2.58089 + endloop + endfacet + facet normal 0.239644 -0.119971 0.96342 + outer loop + vertex 1.08254 1.09016 2.58106 + vertex 1.07832 1.08825 2.58187 + vertex 1.08124 1.08615 2.58089 + endloop + endfacet + facet normal 0.254543 -0.156825 0.954261 + outer loop + vertex 1.08254 1.09016 2.58106 + vertex 1.08319 1.09397 2.58152 + vertex 1.07832 1.08825 2.58187 + endloop + endfacet + facet normal 0.220641 -0.127206 0.967024 + outer loop + vertex 1.08319 1.09397 2.58152 + vertex 1.07817 1.09332 2.58258 + vertex 1.07832 1.08825 2.58187 + endloop + endfacet + facet normal 0.223854 -0.162012 0.961063 + outer loop + vertex 1.08319 1.09397 2.58152 + vertex 1.08316 1.09851 2.58229 + vertex 1.07817 1.09332 2.58258 + endloop + endfacet + facet normal 0.248289 -0.107616 0.96269 + outer loop + vertex 1.07832 1.08825 2.58187 + vertex 1.0771 1.0826 2.58156 + vertex 1.08124 1.08615 2.58089 + endloop + endfacet + facet normal 0.269903 -0.113383 0.956189 + outer loop + vertex 1.08349 1.07919 2.57947 + vertex 1.08442 1.08478 2.57987 + vertex 1.0804 1.08142 2.58061 + endloop + endfacet + facet normal 0.311014 -0.123396 0.942361 + outer loop + vertex 1.08349 1.07919 2.57947 + vertex 1.08001 1.07445 2.58 + vertex 1.08382 1.07402 2.57869 + endloop + endfacet + facet normal 0.284349 -0.126326 0.950362 + outer loop + vertex 1.08382 1.07402 2.57869 + vertex 1.08836 1.07868 2.57795 + vertex 1.08349 1.07919 2.57947 + endloop + endfacet + facet normal 0.282152 -0.142471 0.948732 + outer loop + vertex 1.08836 1.07868 2.57795 + vertex 1.08842 1.08378 2.5787 + vertex 1.08349 1.07919 2.57947 + endloop + endfacet + facet normal 0.25491 -0.111189 0.960551 + outer loop + vertex 1.08349 1.07919 2.57947 + vertex 1.08842 1.08378 2.5787 + vertex 1.08442 1.08478 2.57987 + endloop + endfacet + facet normal 0.312083 -0.155415 0.937257 + outer loop + vertex 1.08843 1.0735 2.57707 + vertex 1.08836 1.07868 2.57795 + vertex 1.08382 1.07402 2.57869 + endloop + endfacet + facet normal 0.31459 -0.138588 0.939056 + outer loop + vertex 1.08337 1.06885 2.57808 + vertex 1.08843 1.0735 2.57707 + vertex 1.08382 1.07402 2.57869 + endloop + endfacet + facet normal 0.322702 -0.138957 0.936245 + outer loop + vertex 1.08337 1.06885 2.57808 + vertex 1.08382 1.07402 2.57869 + vertex 1.07958 1.06989 2.57954 + endloop + endfacet + facet normal 0.322559 -0.139447 0.936221 + outer loop + vertex 1.07825 1.06426 2.57916 + vertex 1.08337 1.06885 2.57808 + vertex 1.07958 1.06989 2.57954 + endloop + endfacet + facet normal 0.32086 -0.137342 0.937116 + outer loop + vertex 1.08319 1.06343 2.57734 + vertex 1.08337 1.06885 2.57808 + vertex 1.07825 1.06426 2.57916 + endloop + endfacet + facet normal 0.323783 -0.122224 0.938204 + outer loop + vertex 1.07815 1.05867 2.57846 + vertex 1.08319 1.06343 2.57734 + vertex 1.07825 1.06426 2.57916 + endloop + endfacet + facet normal 0.28016 -0.123167 0.952019 + outer loop + vertex 1.07825 1.06426 2.57916 + vertex 1.07354 1.05918 2.57989 + vertex 1.07815 1.05867 2.57846 + endloop + endfacet + facet normal 0.283506 -0.0983682 0.953912 + outer loop + vertex 1.07378 1.05413 2.57929 + vertex 1.07815 1.05867 2.57846 + vertex 1.07354 1.05918 2.57989 + endloop + endfacet + facet normal 0.289007 -0.104083 0.951652 + outer loop + vertex 1.07797 1.05349 2.57795 + vertex 1.07815 1.05867 2.57846 + vertex 1.07378 1.05413 2.57929 + endloop + endfacet + facet normal 0.319619 -0.104186 0.941801 + outer loop + vertex 1.07797 1.05349 2.57795 + vertex 1.08213 1.05776 2.57701 + vertex 1.07815 1.05867 2.57846 + endloop + endfacet + facet normal 0.322532 -0.107329 0.940454 + outer loop + vertex 1.08177 1.05319 2.57661 + vertex 1.08213 1.05776 2.57701 + vertex 1.07797 1.05349 2.57795 + endloop + endfacet + facet normal 0.323503 -0.0980875 0.941129 + outer loop + vertex 1.08177 1.05319 2.57661 + vertex 1.07797 1.05349 2.57795 + vertex 1.07825 1.04839 2.57732 + endloop + endfacet + facet normal 0.338496 -0.110086 0.934506 + outer loop + vertex 1.08219 1.05008 2.5761 + vertex 1.08177 1.05319 2.57661 + vertex 1.07825 1.04839 2.57732 + endloop + endfacet + facet normal 0.337979 -0.108622 0.934865 + outer loop + vertex 1.08219 1.05008 2.5761 + vertex 1.07825 1.04839 2.57732 + vertex 1.08131 1.04627 2.57597 + endloop + endfacet + facet normal 0.360627 -0.113541 0.925773 + outer loop + vertex 1.08499 1.04961 2.57495 + vertex 1.08219 1.05008 2.5761 + vertex 1.08131 1.04627 2.57597 + endloop + endfacet + facet normal 0.365361 -0.11957 0.923154 + outer loop + vertex 1.08461 1.04493 2.57449 + vertex 1.08499 1.04961 2.57495 + vertex 1.08131 1.04627 2.57597 + endloop + endfacet + facet normal 0.369782 -0.108275 0.922788 + outer loop + vertex 1.08054 1.04159 2.57573 + vertex 1.08461 1.04493 2.57449 + vertex 1.08131 1.04627 2.57597 + endloop + endfacet + facet normal 0.349173 -0.105334 0.931119 + outer loop + vertex 1.08131 1.04627 2.57597 + vertex 1.07727 1.04285 2.5771 + vertex 1.08054 1.04159 2.57573 + endloop + endfacet + facet normal 0.353315 -0.0941972 0.93075 + outer loop + vertex 1.07727 1.04285 2.5771 + vertex 1.07689 1.03827 2.57678 + vertex 1.08054 1.04159 2.57573 + endloop + endfacet + facet normal 0.358115 -0.100279 0.928277 + outer loop + vertex 1.08054 1.04159 2.57573 + vertex 1.07689 1.03827 2.57678 + vertex 1.07967 1.0378 2.57566 + endloop + endfacet + facet normal 0.378019 -0.104724 0.919855 + outer loop + vertex 1.07967 1.0378 2.57566 + vertex 1.08349 1.03923 2.57425 + vertex 1.08054 1.04159 2.57573 + endloop + endfacet + facet normal 0.37735 -0.102408 0.920391 + outer loop + vertex 1.07967 1.0378 2.57566 + vertex 1.08007 1.03463 2.57514 + vertex 1.08349 1.03923 2.57425 + endloop + endfacet + facet normal 0.369716 -0.10385 0.923323 + outer loop + vertex 1.07967 1.0378 2.57566 + vertex 1.07731 1.03512 2.5763 + vertex 1.08007 1.03463 2.57514 + endloop + endfacet + facet normal 0.359366 -0.0935031 0.9285 + outer loop + vertex 1.07967 1.0378 2.57566 + vertex 1.07689 1.03827 2.57678 + vertex 1.07731 1.03512 2.5763 + endloop + endfacet + facet normal 0.344294 -0.0987247 0.933657 + outer loop + vertex 1.07825 1.04839 2.57732 + vertex 1.07727 1.04285 2.5771 + vertex 1.08131 1.04627 2.57597 + endloop + endfacet + facet normal 0.372609 -0.112311 0.921167 + outer loop + vertex 1.08349 1.03923 2.57425 + vertex 1.08461 1.04493 2.57449 + vertex 1.08054 1.04159 2.57573 + endloop + endfacet + facet normal 0.378364 -0.113333 0.918693 + outer loop + vertex 1.08349 1.03923 2.57425 + vertex 1.08862 1.04365 2.57268 + vertex 1.08461 1.04493 2.57449 + endloop + endfacet + facet normal 0.37282 -0.130641 0.918661 + outer loop + vertex 1.08862 1.04365 2.57268 + vertex 1.08877 1.04905 2.57339 + vertex 1.08461 1.04493 2.57449 + endloop + endfacet + facet normal 0.358457 -0.131008 0.924308 + outer loop + vertex 1.09236 1.04825 2.57188 + vertex 1.08877 1.04905 2.57339 + vertex 1.08862 1.04365 2.57268 + endloop + endfacet + facet normal 0.371846 -0.143108 0.917197 + outer loop + vertex 1.09243 1.04496 2.57134 + vertex 1.09236 1.04825 2.57188 + vertex 1.08862 1.04365 2.57268 + endloop + endfacet + facet normal 0.365954 -0.12032 0.922822 + outer loop + vertex 1.09243 1.04496 2.57134 + vertex 1.08862 1.04365 2.57268 + vertex 1.09149 1.04115 2.57122 + endloop + endfacet + facet normal 0.317843 -0.109016 0.941855 + outer loop + vertex 1.0951 1.04432 2.57037 + vertex 1.09243 1.04496 2.57134 + vertex 1.09149 1.04115 2.57122 + endloop + endfacet + facet normal 0.370024 -0.115093 0.921865 + outer loop + vertex 1.08862 1.04365 2.57268 + vertex 1.08747 1.03787 2.57242 + vertex 1.09149 1.04115 2.57122 + endloop + endfacet + facet normal 0.369434 -0.114245 0.922208 + outer loop + vertex 1.09149 1.04115 2.57122 + vertex 1.08747 1.03787 2.57242 + vertex 1.09086 1.03636 2.57088 + endloop + endfacet + facet normal 0.333377 -0.110514 0.936294 + outer loop + vertex 1.09086 1.03636 2.57088 + vertex 1.09484 1.03987 2.56987 + vertex 1.09149 1.04115 2.57122 + endloop + endfacet + facet normal 0.328682 -0.122861 0.936415 + outer loop + vertex 1.09484 1.03987 2.56987 + vertex 1.0951 1.04432 2.57037 + vertex 1.09149 1.04115 2.57122 + endloop + endfacet + facet normal 0.345126 -0.125617 0.930112 + outer loop + vertex 1.09442 1.03488 2.56936 + vertex 1.09484 1.03987 2.56987 + vertex 1.09086 1.03636 2.57088 + endloop + endfacet + facet normal 0.349511 -0.114762 0.929877 + outer loop + vertex 1.09027 1.03161 2.57051 + vertex 1.09442 1.03488 2.56936 + vertex 1.09086 1.03636 2.57088 + endloop + endfacet + facet normal 0.37607 -0.117246 0.919143 + outer loop + vertex 1.09086 1.03636 2.57088 + vertex 1.08701 1.0329 2.57201 + vertex 1.09027 1.03161 2.57051 + endloop + endfacet + facet normal 0.377323 -0.113963 0.919043 + outer loop + vertex 1.08701 1.0329 2.57201 + vertex 1.08676 1.02848 2.57156 + vertex 1.09027 1.03161 2.57051 + endloop + endfacet + facet normal 0.385082 -0.124167 0.914491 + outer loop + vertex 1.09027 1.03161 2.57051 + vertex 1.08676 1.02848 2.57156 + vertex 1.08943 1.02786 2.57035 + endloop + endfacet + facet normal 0.368588 -0.120807 0.921709 + outer loop + vertex 1.08943 1.02786 2.57035 + vertex 1.09332 1.02922 2.56898 + vertex 1.09027 1.03161 2.57051 + endloop + endfacet + facet normal 0.370939 -0.129681 0.919558 + outer loop + vertex 1.08943 1.02786 2.57035 + vertex 1.08979 1.02466 2.56976 + vertex 1.09332 1.02922 2.56898 + endloop + endfacet + facet normal 0.377018 -0.134946 0.916322 + outer loop + vertex 1.09332 1.02922 2.56898 + vertex 1.08979 1.02466 2.56976 + vertex 1.09335 1.02401 2.5682 + endloop + endfacet + facet normal 0.360855 -0.135984 0.922655 + outer loop + vertex 1.09335 1.02401 2.5682 + vertex 1.09736 1.02793 2.56721 + vertex 1.09332 1.02922 2.56898 + endloop + endfacet + facet normal 0.353193 -0.159004 0.92194 + outer loop + vertex 1.09736 1.02793 2.56721 + vertex 1.09881 1.03351 2.56762 + vertex 1.09332 1.02922 2.56898 + endloop + endfacet + facet normal 0.331091 -0.126585 0.935069 + outer loop + vertex 1.09332 1.02922 2.56898 + vertex 1.09881 1.03351 2.56762 + vertex 1.09442 1.03488 2.56936 + endloop + endfacet + facet normal 0.322673 -0.15239 0.934162 + outer loop + vertex 1.09881 1.03351 2.56762 + vertex 1.0989 1.03894 2.56847 + vertex 1.09442 1.03488 2.56936 + endloop + endfacet + facet normal 0.367184 -0.143373 0.919032 + outer loop + vertex 1.0969 1.02337 2.56668 + vertex 1.09736 1.02793 2.56721 + vertex 1.09335 1.02401 2.5682 + endloop + endfacet + facet normal 0.370167 -0.129051 0.919958 + outer loop + vertex 1.0969 1.02337 2.56668 + vertex 1.09335 1.02401 2.5682 + vertex 1.09337 1.01873 2.56745 + endloop + endfacet + facet normal 0.372559 -0.131077 0.918705 + outer loop + vertex 1.09721 1.02014 2.56609 + vertex 1.0969 1.02337 2.56668 + vertex 1.09337 1.01873 2.56745 + endloop + endfacet + facet normal 0.370071 -0.122161 0.920936 + outer loop + vertex 1.09721 1.02014 2.56609 + vertex 1.09337 1.01873 2.56745 + vertex 1.09628 1.01628 2.56596 + endloop + endfacet + facet normal 0.342957 -0.116004 0.932161 + outer loop + vertex 1.09996 1.01954 2.56501 + vertex 1.09721 1.02014 2.56609 + vertex 1.09628 1.01628 2.56596 + endloop + endfacet + facet normal 0.351961 -0.127594 0.927277 + outer loop + vertex 1.09953 1.01492 2.56454 + vertex 1.09996 1.01954 2.56501 + vertex 1.09628 1.01628 2.56596 + endloop + endfacet + facet normal 0.356039 -0.11762 0.927039 + outer loop + vertex 1.09548 1.01154 2.56566 + vertex 1.09953 1.01492 2.56454 + vertex 1.09628 1.01628 2.56596 + endloop + endfacet + facet normal 0.373409 -0.120113 0.919858 + outer loop + vertex 1.09628 1.01628 2.56596 + vertex 1.09226 1.013 2.56716 + vertex 1.09548 1.01154 2.56566 + endloop + endfacet + facet normal 0.376568 -0.112805 0.919495 + outer loop + vertex 1.09226 1.013 2.56716 + vertex 1.09192 1.00831 2.56672 + vertex 1.09548 1.01154 2.56566 + endloop + endfacet + facet normal 0.382285 -0.1202 0.916193 + outer loop + vertex 1.09548 1.01154 2.56566 + vertex 1.09192 1.00831 2.56672 + vertex 1.09458 1.00768 2.56553 + endloop + endfacet + facet normal 0.370648 -0.117657 0.921291 + outer loop + vertex 1.09458 1.00768 2.56553 + vertex 1.09848 1.00931 2.56417 + vertex 1.09548 1.01154 2.56566 + endloop + endfacet + facet normal 0.371663 -0.120779 0.920477 + outer loop + vertex 1.09458 1.00768 2.56553 + vertex 1.09491 1.00448 2.56498 + vertex 1.09848 1.00931 2.56417 + endloop + endfacet + facet normal 0.386619 -0.118207 0.914633 + outer loop + vertex 1.09458 1.00768 2.56553 + vertex 1.09226 1.00506 2.56617 + vertex 1.09491 1.00448 2.56498 + endloop + endfacet + facet normal 0.387922 -0.112594 0.914789 + outer loop + vertex 1.09491 1.00448 2.56498 + vertex 1.09226 1.00506 2.56617 + vertex 1.0914 1.00129 2.56608 + endloop + endfacet + facet normal 0.394866 -0.121681 0.910645 + outer loop + vertex 1.09445 0.999852 2.56456 + vertex 1.09491 1.00448 2.56498 + vertex 1.0914 1.00129 2.56608 + endloop + endfacet + facet normal 0.397464 -0.115809 0.910281 + outer loop + vertex 1.0906 0.996595 2.56583 + vertex 1.09445 0.999852 2.56456 + vertex 1.0914 1.00129 2.56608 + endloop + endfacet + facet normal 0.427003 -0.120105 0.896238 + outer loop + vertex 1.0914 1.00129 2.56608 + vertex 1.08771 0.998384 2.56744 + vertex 1.0906 0.996595 2.56583 + endloop + endfacet + facet normal 0.431941 -0.111062 0.895037 + outer loop + vertex 1.08771 0.998384 2.56744 + vertex 1.08714 0.993633 2.56713 + vertex 1.0906 0.996595 2.56583 + endloop + endfacet + facet normal 0.441014 -0.124365 0.888842 + outer loop + vertex 1.0906 0.996595 2.56583 + vertex 1.08714 0.993633 2.56713 + vertex 1.08969 0.992746 2.56574 + endloop + endfacet + facet normal 0.403237 -0.11586 0.907731 + outer loop + vertex 1.08969 0.992746 2.56574 + vertex 1.09348 0.99426 2.56425 + vertex 1.0906 0.996595 2.56583 + endloop + endfacet + facet normal 0.401772 -0.110939 0.908995 + outer loop + vertex 1.08969 0.992746 2.56574 + vertex 1.09011 0.989543 2.56516 + vertex 1.09348 0.99426 2.56425 + endloop + endfacet + facet normal 0.40673 -0.115015 0.906279 + outer loop + vertex 1.09348 0.99426 2.56425 + vertex 1.09011 0.989543 2.56516 + vertex 1.09374 0.989063 2.56347 + endloop + endfacet + facet normal 0.408381 -0.104427 0.906818 + outer loop + vertex 1.08998 0.985016 2.5647 + vertex 1.09374 0.989063 2.56347 + vertex 1.09011 0.989543 2.56516 + endloop + endfacet + facet normal 0.419337 -0.116593 0.900313 + outer loop + vertex 1.09381 0.983803 2.56276 + vertex 1.09374 0.989063 2.56347 + vertex 1.08998 0.985016 2.5647 + endloop + endfacet + facet normal 0.422454 -0.106415 0.900116 + outer loop + vertex 1.08947 0.979906 2.56434 + vertex 1.09381 0.983803 2.56276 + vertex 1.08998 0.985016 2.5647 + endloop + endfacet + facet normal 0.432433 -0.120178 0.893621 + outer loop + vertex 1.09266 0.978132 2.56255 + vertex 1.09381 0.983803 2.56276 + vertex 1.08947 0.979906 2.56434 + endloop + endfacet + facet normal 0.435102 -0.114787 0.893034 + outer loop + vertex 1.08837 0.974212 2.56414 + vertex 1.09266 0.978132 2.56255 + vertex 1.08947 0.979906 2.56434 + endloop + endfacet + facet normal 0.438917 -0.115455 0.891079 + outer loop + vertex 1.08837 0.974212 2.56414 + vertex 1.08947 0.979906 2.56434 + vertex 1.08569 0.976707 2.56578 + endloop + endfacet + facet normal 0.434092 -0.121655 0.892617 + outer loop + vertex 1.0849 0.972865 2.56564 + vertex 1.08837 0.974212 2.56414 + vertex 1.08569 0.976707 2.56578 + endloop + endfacet + facet normal 0.382515 -0.112022 0.917133 + outer loop + vertex 1.08569 0.976707 2.56578 + vertex 1.08218 0.973377 2.56684 + vertex 1.0849 0.972865 2.56564 + endloop + endfacet + facet normal 0.377212 -0.137308 0.915892 + outer loop + vertex 1.0849 0.972865 2.56564 + vertex 1.08218 0.973377 2.56684 + vertex 1.08255 0.970201 2.56621 + endloop + endfacet + facet normal 0.395186 -0.15546 0.905351 + outer loop + vertex 1.0849 0.972865 2.56564 + vertex 1.08255 0.970201 2.56621 + vertex 1.085 0.96954 2.56503 + endloop + endfacet + facet normal 0.400687 -0.13459 0.906276 + outer loop + vertex 1.08237 0.977998 2.56744 + vertex 1.08218 0.973377 2.56684 + vertex 1.08569 0.976707 2.56578 + endloop + endfacet + facet normal 0.441665 -0.150179 0.884521 + outer loop + vertex 1.0849 0.972865 2.56564 + vertex 1.085 0.96954 2.56503 + vertex 1.08837 0.974212 2.56414 + endloop + endfacet + facet normal 0.435849 -0.110887 0.893163 + outer loop + vertex 1.08569 0.976707 2.56578 + vertex 1.08947 0.979906 2.56434 + vertex 1.08622 0.981572 2.56613 + endloop + endfacet + facet normal 0.410244 -0.108958 0.905443 + outer loop + vertex 1.08622 0.981572 2.56613 + vertex 1.08237 0.977998 2.56744 + vertex 1.08569 0.976707 2.56578 + endloop + endfacet + facet normal 0.42822 -0.132563 0.893899 + outer loop + vertex 1.0829 0.983202 2.56796 + vertex 1.08237 0.977998 2.56744 + vertex 1.08622 0.981572 2.56613 + endloop + endfacet + facet normal 0.439342 -0.107627 0.891849 + outer loop + vertex 1.08669 0.986443 2.56648 + vertex 1.0829 0.983202 2.56796 + vertex 1.08622 0.981572 2.56613 + endloop + endfacet + facet normal 0.437549 -0.10752 0.892743 + outer loop + vertex 1.08622 0.981572 2.56613 + vertex 1.08998 0.985016 2.5647 + vertex 1.08669 0.986443 2.56648 + endloop + endfacet + facet normal 0.438989 -0.103861 0.892469 + outer loop + vertex 1.08998 0.985016 2.5647 + vertex 1.09011 0.989543 2.56516 + vertex 1.08669 0.986443 2.56648 + endloop + endfacet + facet normal 0.436207 -0.100023 0.89427 + outer loop + vertex 1.09011 0.989543 2.56516 + vertex 1.0874 0.990241 2.56656 + vertex 1.08669 0.986443 2.56648 + endloop + endfacet + facet normal 0.461706 -0.10453 0.880853 + outer loop + vertex 1.0874 0.990241 2.56656 + vertex 1.08356 0.989164 2.56845 + vertex 1.08669 0.986443 2.56648 + endloop + endfacet + facet normal 0.462881 -0.111241 0.879413 + outer loop + vertex 1.0874 0.990241 2.56656 + vertex 1.08714 0.993633 2.56713 + vertex 1.08356 0.989164 2.56845 + endloop + endfacet + facet normal 0.460561 -0.108935 0.880918 + outer loop + vertex 1.08714 0.993633 2.56713 + vertex 1.08406 0.99502 2.56891 + vertex 1.08356 0.989164 2.56845 + endloop + endfacet + facet normal 0.454019 -0.108639 0.884344 + outer loop + vertex 1.08356 0.989164 2.56845 + vertex 1.08406 0.99502 2.56891 + vertex 1.08044 0.991848 2.57038 + endloop + endfacet + facet normal 0.451993 -0.111485 0.885027 + outer loop + vertex 1.07971 0.988026 2.57027 + vertex 1.08356 0.989164 2.56845 + vertex 1.08044 0.991848 2.57038 + endloop + endfacet + facet normal 0.375298 -0.0979298 0.921716 + outer loop + vertex 1.08044 0.991848 2.57038 + vertex 1.0769 0.988532 2.57147 + vertex 1.07971 0.988026 2.57027 + endloop + endfacet + facet normal 0.37131 -0.118272 0.920946 + outer loop + vertex 1.07971 0.988026 2.57027 + vertex 1.0769 0.988532 2.57147 + vertex 1.07729 0.985417 2.57091 + endloop + endfacet + facet normal 0.397515 -0.146331 0.905852 + outer loop + vertex 1.07971 0.988026 2.57027 + vertex 1.07729 0.985417 2.57091 + vertex 1.07976 0.984538 2.56968 + endloop + endfacet + facet normal 0.389684 -0.115953 0.91362 + outer loop + vertex 1.07701 0.992962 2.57198 + vertex 1.0769 0.988532 2.57147 + vertex 1.08044 0.991848 2.57038 + endloop + endfacet + facet normal 0.395285 -0.0982428 0.91329 + outer loop + vertex 1.08081 0.996708 2.57074 + vertex 1.07701 0.992962 2.57198 + vertex 1.08044 0.991848 2.57038 + endloop + endfacet + facet normal 0.405583 -0.110683 0.907332 + outer loop + vertex 1.07727 0.99788 2.57247 + vertex 1.07701 0.992962 2.57198 + vertex 1.08081 0.996708 2.57074 + endloop + endfacet + facet normal 0.411376 -0.0923482 0.906775 + outer loop + vertex 1.08115 1.00172 2.5711 + vertex 1.07727 0.99788 2.57247 + vertex 1.08081 0.996708 2.57074 + endloop + endfacet + facet normal 0.444753 -0.0934064 0.890769 + outer loop + vertex 1.08081 0.996708 2.57074 + vertex 1.08456 1.00019 2.56924 + vertex 1.08115 1.00172 2.5711 + endloop + endfacet + facet normal 0.445945 -0.0904103 0.890483 + outer loop + vertex 1.08456 1.00019 2.56924 + vertex 1.08486 1.00524 2.5696 + vertex 1.08115 1.00172 2.5711 + endloop + endfacet + facet normal 0.44315 -0.0867056 0.892244 + outer loop + vertex 1.08115 1.00172 2.5711 + vertex 1.08486 1.00524 2.5696 + vertex 1.08151 1.00668 2.5714 + endloop + endfacet + facet normal 0.431237 -0.0861973 0.898112 + outer loop + vertex 1.08151 1.00668 2.5714 + vertex 1.07764 1.00308 2.57291 + vertex 1.08115 1.00172 2.5711 + endloop + endfacet + facet normal 0.443022 -0.101993 0.89069 + outer loop + vertex 1.07824 1.00922 2.57332 + vertex 1.07764 1.00308 2.57291 + vertex 1.08151 1.00668 2.5714 + endloop + endfacet + facet normal 0.454834 -0.0837689 0.886628 + outer loop + vertex 1.08219 1.01057 2.57142 + vertex 1.07824 1.00922 2.57332 + vertex 1.08151 1.00668 2.5714 + endloop + endfacet + facet normal 0.441163 -0.0814202 0.893726 + outer loop + vertex 1.08491 1.00982 2.57001 + vertex 1.08219 1.01057 2.57142 + vertex 1.08151 1.00668 2.5714 + endloop + endfacet + facet normal 0.458541 -0.0994756 0.883088 + outer loop + vertex 1.08219 1.01057 2.57142 + vertex 1.08192 1.01395 2.57194 + vertex 1.07824 1.00922 2.57332 + endloop + endfacet + facet normal 0.453893 -0.0950374 0.885973 + outer loop + vertex 1.08192 1.01395 2.57194 + vertex 1.07884 1.01519 2.57365 + vertex 1.07824 1.00922 2.57332 + endloop + endfacet + facet normal 0.433858 -0.0936202 0.896104 + outer loop + vertex 1.07824 1.00922 2.57332 + vertex 1.07884 1.01519 2.57365 + vertex 1.07524 1.01186 2.57504 + endloop + endfacet + facet normal 0.435601 -0.0912474 0.895503 + outer loop + vertex 1.07435 1.00788 2.57507 + vertex 1.07824 1.00922 2.57332 + vertex 1.07524 1.01186 2.57504 + endloop + endfacet + facet normal 0.350335 -0.0718508 0.933865 + outer loop + vertex 1.07524 1.01186 2.57504 + vertex 1.07177 1.00852 2.57609 + vertex 1.07435 1.00788 2.57507 + endloop + endfacet + facet normal 0.346011 -0.0892849 0.933973 + outer loop + vertex 1.07435 1.00788 2.57507 + vertex 1.07177 1.00852 2.57609 + vertex 1.0719 1.00541 2.57575 + endloop + endfacet + facet normal 0.385847 -0.134636 0.912686 + outer loop + vertex 1.07435 1.00788 2.57507 + vertex 1.0719 1.00541 2.57575 + vertex 1.07377 1.00371 2.57471 + endloop + endfacet + facet normal 0.353933 -0.0761285 0.932167 + outer loop + vertex 1.07187 1.01288 2.57641 + vertex 1.07177 1.00852 2.57609 + vertex 1.07524 1.01186 2.57504 + endloop + endfacet + facet normal 0.355341 -0.0712767 0.932015 + outer loop + vertex 1.07559 1.01668 2.57528 + vertex 1.07187 1.01288 2.57641 + vertex 1.07524 1.01186 2.57504 + endloop + endfacet + facet normal 0.357902 -0.0741323 0.930812 + outer loop + vertex 1.07197 1.01769 2.57675 + vertex 1.07187 1.01288 2.57641 + vertex 1.07559 1.01668 2.57528 + endloop + endfacet + facet normal 0.357462 -0.0757672 0.930849 + outer loop + vertex 1.07583 1.0216 2.57559 + vertex 1.07197 1.01769 2.57675 + vertex 1.07559 1.01668 2.57528 + endloop + endfacet + facet normal 0.402367 -0.0768133 0.91225 + outer loop + vertex 1.07559 1.01668 2.57528 + vertex 1.07933 1.02031 2.57394 + vertex 1.07583 1.0216 2.57559 + endloop + endfacet + facet normal 0.396718 -0.0933371 0.913183 + outer loop + vertex 1.07933 1.02031 2.57394 + vertex 1.07966 1.02533 2.57431 + vertex 1.07583 1.0216 2.57559 + endloop + endfacet + facet normal 0.388338 -0.0831526 0.917758 + outer loop + vertex 1.07583 1.0216 2.57559 + vertex 1.07966 1.02533 2.57431 + vertex 1.0761 1.02652 2.57592 + endloop + endfacet + facet normal 0.356464 -0.0822318 0.930683 + outer loop + vertex 1.0761 1.02652 2.57592 + vertex 1.07215 1.02267 2.57709 + vertex 1.07583 1.0216 2.57559 + endloop + endfacet + facet normal 0.355765 -0.0814116 0.931023 + outer loop + vertex 1.07255 1.02778 2.57739 + vertex 1.07215 1.02267 2.57709 + vertex 1.0761 1.02652 2.57592 + endloop + endfacet + facet normal 0.353418 -0.0882997 0.931289 + outer loop + vertex 1.07655 1.03131 2.57621 + vertex 1.07255 1.02778 2.57739 + vertex 1.0761 1.02652 2.57592 + endloop + endfacet + facet normal 0.37794 -0.0899758 0.921448 + outer loop + vertex 1.0761 1.02652 2.57592 + vertex 1.07987 1.03017 2.57473 + vertex 1.07655 1.03131 2.57621 + endloop + endfacet + facet normal 0.374239 -0.101192 0.921794 + outer loop + vertex 1.07987 1.03017 2.57473 + vertex 1.08007 1.03463 2.57514 + vertex 1.07655 1.03131 2.57621 + endloop + endfacet + facet normal 0.371004 -0.097198 0.92353 + outer loop + vertex 1.08007 1.03463 2.57514 + vertex 1.07731 1.03512 2.5763 + vertex 1.07655 1.03131 2.57621 + endloop + endfacet + facet normal 0.346099 -0.0924221 0.933635 + outer loop + vertex 1.07731 1.03512 2.5763 + vertex 1.07338 1.03348 2.57759 + vertex 1.07655 1.03131 2.57621 + endloop + endfacet + facet normal 0.347264 -0.0958135 0.93286 + outer loop + vertex 1.07731 1.03512 2.5763 + vertex 1.07689 1.03827 2.57678 + vertex 1.07338 1.03348 2.57759 + endloop + endfacet + facet normal 0.333118 -0.0844221 0.939098 + outer loop + vertex 1.07689 1.03827 2.57678 + vertex 1.07312 1.03873 2.57816 + vertex 1.07338 1.03348 2.57759 + endloop + endfacet + facet normal 0.331943 -0.0929824 0.938706 + outer loop + vertex 1.07689 1.03827 2.57678 + vertex 1.07727 1.04285 2.5771 + vertex 1.07312 1.03873 2.57816 + endloop + endfacet + facet normal 0.386596 -0.101272 0.916672 + outer loop + vertex 1.07987 1.03017 2.57473 + vertex 1.08353 1.03399 2.57361 + vertex 1.08007 1.03463 2.57514 + endloop + endfacet + facet normal 0.391913 -0.107225 0.913732 + outer loop + vertex 1.08337 1.02915 2.57311 + vertex 1.08353 1.03399 2.57361 + vertex 1.07987 1.03017 2.57473 + endloop + endfacet + facet normal 0.394761 -0.0972184 0.913626 + outer loop + vertex 1.07966 1.02533 2.57431 + vertex 1.08337 1.02915 2.57311 + vertex 1.07987 1.03017 2.57473 + endloop + endfacet + facet normal 0.350797 -0.0848902 0.932596 + outer loop + vertex 1.07338 1.03348 2.57759 + vertex 1.07255 1.02778 2.57739 + vertex 1.07655 1.03131 2.57621 + endloop + endfacet + facet normal 0.383897 -0.0971602 0.91825 + outer loop + vertex 1.07966 1.02533 2.57431 + vertex 1.07987 1.03017 2.57473 + vertex 1.0761 1.02652 2.57592 + endloop + endfacet + facet normal 0.410636 -0.0937992 0.906962 + outer loop + vertex 1.07933 1.02031 2.57394 + vertex 1.08354 1.02411 2.57242 + vertex 1.07966 1.02533 2.57431 + endloop + endfacet + facet normal 0.425023 -0.113273 0.898067 + outer loop + vertex 1.08251 1.01867 2.57222 + vertex 1.08354 1.02411 2.57242 + vertex 1.07933 1.02031 2.57394 + endloop + endfacet + facet normal 0.434936 -0.0916223 0.895788 + outer loop + vertex 1.07884 1.01519 2.57365 + vertex 1.08251 1.01867 2.57222 + vertex 1.07933 1.02031 2.57394 + endloop + endfacet + facet normal 0.413046 -0.0900892 0.906243 + outer loop + vertex 1.07884 1.01519 2.57365 + vertex 1.07933 1.02031 2.57394 + vertex 1.07559 1.01668 2.57528 + endloop + endfacet + facet normal 0.358087 -0.0764733 0.930551 + outer loop + vertex 1.07215 1.02267 2.57709 + vertex 1.07197 1.01769 2.57675 + vertex 1.07583 1.0216 2.57559 + endloop + endfacet + facet normal 0.447087 -0.140626 0.883367 + outer loop + vertex 1.07435 1.00788 2.57507 + vertex 1.07377 1.00371 2.57471 + vertex 1.07824 1.00922 2.57332 + endloop + endfacet + facet normal 0.419466 -0.0744792 0.904711 + outer loop + vertex 1.07524 1.01186 2.57504 + vertex 1.07884 1.01519 2.57365 + vertex 1.07559 1.01668 2.57528 + endloop + endfacet + facet normal 0.40441 -0.0993988 0.90916 + outer loop + vertex 1.07824 1.00922 2.57332 + vertex 1.07377 1.00371 2.57471 + vertex 1.07764 1.00308 2.57291 + endloop + endfacet + facet normal 0.443795 -0.0850026 0.892088 + outer loop + vertex 1.08486 1.00524 2.5696 + vertex 1.08491 1.00982 2.57001 + vertex 1.08151 1.00668 2.5714 + endloop + endfacet + facet normal 0.449031 -0.0992053 0.887992 + outer loop + vertex 1.08406 0.99502 2.56891 + vertex 1.08456 1.00019 2.56924 + vertex 1.08081 0.996708 2.57074 + endloop + endfacet + facet normal 0.42371 -0.10739 0.899409 + outer loop + vertex 1.07764 1.00308 2.57291 + vertex 1.07727 0.99788 2.57247 + vertex 1.08115 1.00172 2.5711 + endloop + endfacet + facet normal 0.457354 -0.140725 0.87808 + outer loop + vertex 1.07971 0.988026 2.57027 + vertex 1.07976 0.984538 2.56968 + vertex 1.08356 0.989164 2.56845 + endloop + endfacet + facet normal 0.448442 -0.100501 0.888143 + outer loop + vertex 1.08044 0.991848 2.57038 + vertex 1.08406 0.99502 2.56891 + vertex 1.08081 0.996708 2.57074 + endloop + endfacet + facet normal 0.458768 -0.113392 0.881291 + outer loop + vertex 1.08714 0.993633 2.56713 + vertex 1.08771 0.998384 2.56744 + vertex 1.08406 0.99502 2.56891 + endloop + endfacet + facet normal 0.448475 -0.0991703 0.888277 + outer loop + vertex 1.08406 0.99502 2.56891 + vertex 1.08771 0.998384 2.56744 + vertex 1.08456 1.00019 2.56924 + endloop + endfacet + facet normal 0.443202 -0.109786 0.889673 + outer loop + vertex 1.08771 0.998384 2.56744 + vertex 1.0887 1.00389 2.56763 + vertex 1.08456 1.00019 2.56924 + endloop + endfacet + facet normal 0.429061 -0.0899854 0.898782 + outer loop + vertex 1.08456 1.00019 2.56924 + vertex 1.0887 1.00389 2.56763 + vertex 1.08486 1.00524 2.5696 + endloop + endfacet + facet normal 0.426114 -0.0990431 0.899232 + outer loop + vertex 1.0887 1.00389 2.56763 + vertex 1.08845 1.00906 2.56832 + vertex 1.08486 1.00524 2.5696 + endloop + endfacet + facet normal 0.414527 -0.0858962 0.905974 + outer loop + vertex 1.08486 1.00524 2.5696 + vertex 1.08845 1.00906 2.56832 + vertex 1.08491 1.00982 2.57001 + endloop + endfacet + facet normal 0.449101 -0.122098 0.885099 + outer loop + vertex 1.08356 0.989164 2.56845 + vertex 1.0829 0.983202 2.56796 + vertex 1.08669 0.986443 2.56648 + endloop + endfacet + facet normal 0.437847 -0.12133 0.890825 + outer loop + vertex 1.08356 0.989164 2.56845 + vertex 1.07976 0.984538 2.56968 + vertex 1.0829 0.983202 2.56796 + endloop + endfacet + facet normal 0.437449 -0.107384 0.892808 + outer loop + vertex 1.08947 0.979906 2.56434 + vertex 1.08998 0.985016 2.5647 + vertex 1.08622 0.981572 2.56613 + endloop + endfacet + facet normal 0.439213 -0.120402 0.890278 + outer loop + vertex 1.09205 0.973094 2.56217 + vertex 1.09266 0.978132 2.56255 + vertex 1.08837 0.974212 2.56414 + endloop + endfacet + facet normal 0.43486 -0.134855 0.890343 + outer loop + vertex 1.08831 0.968974 2.56337 + vertex 1.09205 0.973094 2.56217 + vertex 1.08837 0.974212 2.56414 + endloop + endfacet + facet normal 0.423512 -0.122445 0.897577 + outer loop + vertex 1.09181 0.968638 2.56168 + vertex 1.09205 0.973094 2.56217 + vertex 1.08831 0.968974 2.56337 + endloop + endfacet + facet normal 0.421038 -0.140623 0.896076 + outer loop + vertex 1.09181 0.968638 2.56168 + vertex 1.08831 0.968974 2.56337 + vertex 1.08842 0.963798 2.56251 + endloop + endfacet + facet normal 0.39957 -0.123483 0.908348 + outer loop + vertex 1.09223 0.965529 2.56107 + vertex 1.09181 0.968638 2.56168 + vertex 1.08842 0.963798 2.56251 + endloop + endfacet + facet normal 0.398396 -0.120091 0.909318 + outer loop + vertex 1.09223 0.965529 2.56107 + vertex 1.08842 0.963798 2.56251 + vertex 1.0914 0.961696 2.56093 + endloop + endfacet + facet normal 0.421899 -0.12476 0.898018 + outer loop + vertex 1.09491 0.964944 2.55973 + vertex 1.09223 0.965529 2.56107 + vertex 1.0914 0.961696 2.56093 + endloop + endfacet + facet normal 0.419594 -0.121718 0.899514 + outer loop + vertex 1.09443 0.960152 2.55931 + vertex 1.09491 0.964944 2.55973 + vertex 1.0914 0.961696 2.56093 + endloop + endfacet + facet normal 0.413604 -0.134454 0.900474 + outer loop + vertex 1.09057 0.956955 2.5606 + vertex 1.09443 0.960152 2.55931 + vertex 1.0914 0.961696 2.56093 + endloop + endfacet + facet normal 0.370863 -0.128267 0.919787 + outer loop + vertex 1.0914 0.961696 2.56093 + vertex 1.08743 0.958207 2.56204 + vertex 1.09057 0.956955 2.5606 + endloop + endfacet + facet normal 0.416233 -0.138356 0.89867 + outer loop + vertex 1.09308 0.954302 2.55903 + vertex 1.09443 0.960152 2.55931 + vertex 1.09057 0.956955 2.5606 + endloop + endfacet + facet normal 0.420912 -0.139324 0.896338 + outer loop + vertex 1.09308 0.954302 2.55903 + vertex 1.0976 0.958398 2.55754 + vertex 1.09443 0.960152 2.55931 + endloop + endfacet + facet normal 0.428932 -0.123342 0.894876 + outer loop + vertex 1.0976 0.958398 2.55754 + vertex 1.09868 0.964143 2.55782 + vertex 1.09443 0.960152 2.55931 + endloop + endfacet + facet normal 0.409299 -0.123741 0.90397 + outer loop + vertex 1.09701 0.953225 2.5571 + vertex 1.0976 0.958398 2.55754 + vertex 1.09308 0.954302 2.55903 + endloop + endfacet + facet normal 0.418531 -0.124429 0.899638 + outer loop + vertex 1.0976 0.958398 2.55754 + vertex 1.09701 0.953225 2.5571 + vertex 1.10086 0.956756 2.5558 + endloop + endfacet + facet normal 0.412454 -0.11637 0.903515 + outer loop + vertex 1.10086 0.956756 2.5558 + vertex 1.09701 0.953225 2.5571 + vertex 1.10028 0.951963 2.55545 + endloop + endfacet + facet normal 0.414328 -0.116532 0.902637 + outer loop + vertex 1.10028 0.951963 2.55545 + vertex 1.10415 0.955117 2.55408 + vertex 1.10086 0.956756 2.5558 + endloop + endfacet + facet normal 0.411987 -0.12165 0.903033 + outer loop + vertex 1.10415 0.955117 2.55408 + vertex 1.1047 0.960158 2.55451 + vertex 1.10086 0.956756 2.5558 + endloop + endfacet + facet normal 0.408312 -0.116612 0.905363 + outer loop + vertex 1.10086 0.956756 2.5558 + vertex 1.1047 0.960158 2.55451 + vertex 1.10146 0.961584 2.55615 + endloop + endfacet + facet normal 0.421577 -0.117822 0.899106 + outer loop + vertex 1.10146 0.961584 2.55615 + vertex 1.0976 0.958398 2.55754 + vertex 1.10086 0.956756 2.5558 + endloop + endfacet + facet normal 0.424785 -0.122658 0.896946 + outer loop + vertex 1.09868 0.964143 2.55782 + vertex 1.0976 0.958398 2.55754 + vertex 1.10146 0.961584 2.55615 + endloop + endfacet + facet normal 0.422281 -0.125859 0.897685 + outer loop + vertex 1.1023 0.965413 2.55629 + vertex 1.09868 0.964143 2.55782 + vertex 1.10146 0.961584 2.55615 + endloop + endfacet + facet normal 0.401487 -0.121689 0.907745 + outer loop + vertex 1.10495 0.964696 2.55503 + vertex 1.1023 0.965413 2.55629 + vertex 1.10146 0.961584 2.55615 + endloop + endfacet + facet normal 0.42543 -0.138927 0.894264 + outer loop + vertex 1.1023 0.965413 2.55629 + vertex 1.10209 0.968795 2.55692 + vertex 1.09868 0.964143 2.55782 + endloop + endfacet + facet normal 0.412764 -0.128221 0.901768 + outer loop + vertex 1.10209 0.968795 2.55692 + vertex 1.09822 0.96961 2.55881 + vertex 1.09868 0.964143 2.55782 + endloop + endfacet + facet normal 0.427258 -0.125815 0.895333 + outer loop + vertex 1.09822 0.96961 2.55881 + vertex 1.09491 0.964944 2.55973 + vertex 1.09868 0.964143 2.55782 + endloop + endfacet + facet normal 0.418225 -0.118382 0.900596 + outer loop + vertex 1.09448 0.96817 2.56036 + vertex 1.09491 0.964944 2.55973 + vertex 1.09822 0.96961 2.55881 + endloop + endfacet + facet normal 0.417976 -0.117486 0.900829 + outer loop + vertex 1.09448 0.96817 2.56036 + vertex 1.09822 0.96961 2.55881 + vertex 1.09524 0.971895 2.56048 + endloop + endfacet + facet normal 0.424349 -0.118691 0.897686 + outer loop + vertex 1.09524 0.971895 2.56048 + vertex 1.09181 0.968638 2.56168 + vertex 1.09448 0.96817 2.56036 + endloop + endfacet + facet normal 0.427259 -0.122448 0.895799 + outer loop + vertex 1.09205 0.973094 2.56217 + vertex 1.09181 0.968638 2.56168 + vertex 1.09524 0.971895 2.56048 + endloop + endfacet + facet normal 0.427175 -0.122683 0.895807 + outer loop + vertex 1.09586 0.976591 2.56084 + vertex 1.09205 0.973094 2.56217 + vertex 1.09524 0.971895 2.56048 + endloop + endfacet + facet normal 0.406633 -0.120739 0.905578 + outer loop + vertex 1.09524 0.971895 2.56048 + vertex 1.0992 0.975207 2.55915 + vertex 1.09586 0.976591 2.56084 + endloop + endfacet + facet normal 0.403623 -0.128374 0.905874 + outer loop + vertex 1.0992 0.975207 2.55915 + vertex 1.0997 0.980099 2.55962 + vertex 1.09586 0.976591 2.56084 + endloop + endfacet + facet normal 0.399113 -0.122451 0.908688 + outer loop + vertex 1.09586 0.976591 2.56084 + vertex 1.0997 0.980099 2.55962 + vertex 1.09653 0.981317 2.56118 + endloop + endfacet + facet normal 0.422013 -0.124922 0.897942 + outer loop + vertex 1.09653 0.981317 2.56118 + vertex 1.09266 0.978132 2.56255 + vertex 1.09586 0.976591 2.56084 + endloop + endfacet + facet normal 0.416943 -0.117305 0.901331 + outer loop + vertex 1.09381 0.983803 2.56276 + vertex 1.09266 0.978132 2.56255 + vertex 1.09653 0.981317 2.56118 + endloop + endfacet + facet normal 0.407615 -0.129163 0.903973 + outer loop + vertex 1.09743 0.985106 2.56131 + vertex 1.09381 0.983803 2.56276 + vertex 1.09653 0.981317 2.56118 + endloop + endfacet + facet normal 0.391098 -0.12552 0.911749 + outer loop + vertex 1.10006 0.984552 2.56011 + vertex 1.09743 0.985106 2.56131 + vertex 1.09653 0.981317 2.56118 + endloop + endfacet + facet normal 0.38926 -0.133506 0.911401 + outer loop + vertex 1.09979 0.987739 2.56069 + vertex 1.09743 0.985106 2.56131 + vertex 1.10006 0.984552 2.56011 + endloop + endfacet + facet normal 0.381453 -0.134735 0.914517 + outer loop + vertex 1.09979 0.987739 2.56069 + vertex 1.10006 0.984552 2.56011 + vertex 1.10358 0.989299 2.55934 + endloop + endfacet + facet normal 0.380781 -0.132587 0.91511 + outer loop + vertex 1.09979 0.987739 2.56069 + vertex 1.10358 0.989299 2.55934 + vertex 1.10083 0.991507 2.5608 + endloop + endfacet + facet normal 0.387009 -0.134226 0.912254 + outer loop + vertex 1.10083 0.991507 2.5608 + vertex 1.09724 0.988441 2.56187 + vertex 1.09979 0.987739 2.56069 + endloop + endfacet + facet normal 0.37985 -0.124299 0.916659 + outer loop + vertex 1.09809 0.993688 2.56223 + vertex 1.09724 0.988441 2.56187 + vertex 1.10083 0.991507 2.5608 + endloop + endfacet + facet normal 0.377717 -0.127289 0.91713 + outer loop + vertex 1.10186 0.995282 2.5609 + vertex 1.09809 0.993688 2.56223 + vertex 1.10083 0.991507 2.5608 + endloop + endfacet + facet normal 0.371885 -0.125771 0.919719 + outer loop + vertex 1.1045 0.994615 2.55974 + vertex 1.10186 0.995282 2.5609 + vertex 1.10083 0.991507 2.5608 + endloop + endfacet + facet normal 0.372004 -0.125321 0.919732 + outer loop + vertex 1.10428 0.997966 2.56029 + vertex 1.10186 0.995282 2.5609 + vertex 1.1045 0.994615 2.55974 + endloop + endfacet + facet normal 0.345065 -0.128775 0.929703 + outer loop + vertex 1.10428 0.997966 2.56029 + vertex 1.1045 0.994615 2.55974 + vertex 1.10829 0.999484 2.55901 + endloop + endfacet + facet normal 0.342457 -0.120081 0.931828 + outer loop + vertex 1.10428 0.997966 2.56029 + vertex 1.10829 0.999484 2.55901 + vertex 1.10522 1.00179 2.56044 + endloop + endfacet + facet normal 0.366894 -0.125724 0.921728 + outer loop + vertex 1.10522 1.00179 2.56044 + vertex 1.10158 0.998484 2.56143 + vertex 1.10428 0.997966 2.56029 + endloop + endfacet + facet normal 0.363115 -0.120924 0.923864 + outer loop + vertex 1.10207 1.00309 2.56185 + vertex 1.10158 0.998484 2.56143 + vertex 1.10522 1.00179 2.56044 + endloop + endfacet + facet normal 0.375049 -0.121746 0.918976 + outer loop + vertex 1.10158 0.998484 2.56143 + vertex 1.10207 1.00309 2.56185 + vertex 1.09801 0.998889 2.56295 + endloop + endfacet + facet normal 0.329006 -0.139312 0.933995 + outer loop + vertex 1.10829 0.999484 2.55901 + vertex 1.10933 1.0051 2.55948 + vertex 1.10522 1.00179 2.56044 + endloop + endfacet + facet normal 0.317506 -0.123213 0.940217 + outer loop + vertex 1.10522 1.00179 2.56044 + vertex 1.10933 1.0051 2.55948 + vertex 1.10605 1.00647 2.56077 + endloop + endfacet + facet normal 0.359652 -0.129546 0.92405 + outer loop + vertex 1.10605 1.00647 2.56077 + vertex 1.10207 1.00309 2.56185 + vertex 1.10522 1.00179 2.56044 + endloop + endfacet + facet normal 0.360965 -0.13134 0.923284 + outer loop + vertex 1.1032 1.00869 2.5622 + vertex 1.10207 1.00309 2.56185 + vertex 1.10605 1.00647 2.56077 + endloop + endfacet + facet normal 0.353054 -0.142432 0.924698 + outer loop + vertex 1.10709 1.01026 2.56096 + vertex 1.1032 1.00869 2.5622 + vertex 1.10605 1.00647 2.56077 + endloop + endfacet + facet normal 0.297313 -0.12823 0.94613 + outer loop + vertex 1.10979 1.00965 2.56002 + vertex 1.10709 1.01026 2.56096 + vertex 1.10605 1.00647 2.56077 + endloop + endfacet + facet normal 0.362112 -0.171631 0.916198 + outer loop + vertex 1.10709 1.01026 2.56096 + vertex 1.10709 1.01341 2.56155 + vertex 1.1032 1.00869 2.5622 + endloop + endfacet + facet normal 0.338715 -0.150665 0.928748 + outer loop + vertex 1.10709 1.01341 2.56155 + vertex 1.1034 1.01398 2.56298 + vertex 1.1032 1.00869 2.5622 + endloop + endfacet + facet normal 0.329561 -0.196818 0.923391 + outer loop + vertex 1.10709 1.01341 2.56155 + vertex 1.10854 1.01846 2.5621 + vertex 1.1034 1.01398 2.56298 + endloop + endfacet + facet normal 0.291244 -0.148569 0.945042 + outer loop + vertex 1.1034 1.01398 2.56298 + vertex 1.10854 1.01846 2.5621 + vertex 1.10384 1.01909 2.56365 + endloop + endfacet + facet normal 0.285931 -0.178908 0.941401 + outer loop + vertex 1.10854 1.01846 2.5621 + vertex 1.10847 1.02369 2.56312 + vertex 1.10384 1.01909 2.56365 + endloop + endfacet + facet normal 0.30905 -0.143434 0.940167 + outer loop + vertex 1.10933 1.0051 2.55948 + vertex 1.10979 1.00965 2.56002 + vertex 1.10605 1.00647 2.56077 + endloop + endfacet + facet normal 0.362679 -0.143831 0.920748 + outer loop + vertex 1.10829 0.999484 2.55901 + vertex 1.1045 0.994615 2.55974 + vertex 1.10827 0.994047 2.55817 + endloop + endfacet + facet normal 0.320784 -0.145988 0.935834 + outer loop + vertex 1.10827 0.994047 2.55817 + vertex 1.11336 0.998779 2.55716 + vertex 1.10829 0.999484 2.55901 + endloop + endfacet + facet normal 0.316053 -0.172407 0.932945 + outer loop + vertex 1.11336 0.998779 2.55716 + vertex 1.11349 1.00414 2.55811 + vertex 1.10829 0.999484 2.55901 + endloop + endfacet + facet normal 0.351977 -0.183327 0.91788 + outer loop + vertex 1.11197 0.993461 2.55663 + vertex 1.11336 0.998779 2.55716 + vertex 1.10827 0.994047 2.55817 + endloop + endfacet + facet normal 0.359301 -0.146836 0.921597 + outer loop + vertex 1.11197 0.993461 2.55663 + vertex 1.10827 0.994047 2.55817 + vertex 1.1082 0.988637 2.55734 + endloop + endfacet + facet normal 0.37322 -0.158824 0.914047 + outer loop + vertex 1.11202 0.990144 2.55604 + vertex 1.11197 0.993461 2.55663 + vertex 1.1082 0.988637 2.55734 + endloop + endfacet + facet normal 0.36663 -0.136766 0.92026 + outer loop + vertex 1.11202 0.990144 2.55604 + vertex 1.1082 0.988637 2.55734 + vertex 1.11107 0.986338 2.55585 + endloop + endfacet + facet normal 0.32141 -0.126358 0.938472 + outer loop + vertex 1.11475 0.989544 2.55502 + vertex 1.11202 0.990144 2.55604 + vertex 1.11107 0.986338 2.55585 + endloop + endfacet + facet normal 0.334917 -0.143764 0.931216 + outer loop + vertex 1.11434 0.985005 2.55447 + vertex 1.11475 0.989544 2.55502 + vertex 1.11107 0.986338 2.55585 + endloop + endfacet + facet normal 0.340389 -0.130334 0.931208 + outer loop + vertex 1.11031 0.981708 2.55548 + vertex 1.11434 0.985005 2.55447 + vertex 1.11107 0.986338 2.55585 + endloop + endfacet + facet normal 0.368898 -0.134096 0.919746 + outer loop + vertex 1.11107 0.986338 2.55585 + vertex 1.10716 0.983071 2.55694 + vertex 1.11031 0.981708 2.55548 + endloop + endfacet + facet normal 0.369713 -0.132165 0.919698 + outer loop + vertex 1.10716 0.983071 2.55694 + vertex 1.10669 0.978545 2.55648 + vertex 1.11031 0.981708 2.55548 + endloop + endfacet + facet normal 0.3757 -0.140159 0.916081 + outer loop + vertex 1.11031 0.981708 2.55548 + vertex 1.10669 0.978545 2.55648 + vertex 1.10937 0.977926 2.55529 + endloop + endfacet + facet normal 0.364262 -0.137584 0.921078 + outer loop + vertex 1.10937 0.977926 2.55529 + vertex 1.11337 0.979443 2.55393 + vertex 1.11031 0.981708 2.55548 + endloop + endfacet + facet normal 0.368236 -0.15142 0.917319 + outer loop + vertex 1.10937 0.977926 2.55529 + vertex 1.10958 0.97456 2.55465 + vertex 1.11337 0.979443 2.55393 + endloop + endfacet + facet normal 0.379799 -0.161342 0.91089 + outer loop + vertex 1.11337 0.979443 2.55393 + vertex 1.10958 0.97456 2.55465 + vertex 1.11365 0.97377 2.55281 + endloop + endfacet + facet normal 0.349948 -0.165061 0.922112 + outer loop + vertex 1.11825 0.97916 2.55203 + vertex 1.11337 0.979443 2.55393 + vertex 1.11365 0.97377 2.55281 + endloop + endfacet + facet normal 0.381661 -0.194773 0.903548 + outer loop + vertex 1.11763 0.975122 2.55142 + vertex 1.11825 0.97916 2.55203 + vertex 1.11365 0.97377 2.55281 + endloop + endfacet + facet normal 0.373824 -0.161709 0.913294 + outer loop + vertex 1.11763 0.975122 2.55142 + vertex 1.11365 0.97377 2.55281 + vertex 1.11637 0.971176 2.55124 + endloop + endfacet + facet normal 0.333603 -0.149625 0.930764 + outer loop + vertex 1.12012 0.974288 2.55039 + vertex 1.11763 0.975122 2.55142 + vertex 1.11637 0.971176 2.55124 + endloop + endfacet + facet normal 0.339846 -0.158154 0.927088 + outer loop + vertex 1.11953 0.969782 2.54984 + vertex 1.12012 0.974288 2.55039 + vertex 1.11637 0.971176 2.55124 + endloop + endfacet + facet normal 0.346833 -0.142287 0.927072 + outer loop + vertex 1.11548 0.966471 2.55085 + vertex 1.11953 0.969782 2.54984 + vertex 1.11637 0.971176 2.55124 + endloop + endfacet + facet normal 0.377566 -0.147039 0.914234 + outer loop + vertex 1.11637 0.971176 2.55124 + vertex 1.11234 0.967956 2.55238 + vertex 1.11548 0.966471 2.55085 + endloop + endfacet + facet normal 0.381175 -0.139143 0.913972 + outer loop + vertex 1.11234 0.967956 2.55238 + vertex 1.11192 0.963317 2.55185 + vertex 1.11548 0.966471 2.55085 + endloop + endfacet + facet normal 0.383508 -0.142235 0.912519 + outer loop + vertex 1.11548 0.966471 2.55085 + vertex 1.11192 0.963317 2.55185 + vertex 1.11458 0.962691 2.55064 + endloop + endfacet + facet normal 0.366729 -0.138695 0.919931 + outer loop + vertex 1.11458 0.962691 2.55064 + vertex 1.11851 0.964275 2.54931 + vertex 1.11548 0.966471 2.55085 + endloop + endfacet + facet normal 0.368735 -0.145178 0.918127 + outer loop + vertex 1.11458 0.962691 2.55064 + vertex 1.11493 0.959551 2.55 + vertex 1.11851 0.964275 2.54931 + endloop + endfacet + facet normal 0.384284 -0.158222 0.909556 + outer loop + vertex 1.11851 0.964275 2.54931 + vertex 1.11493 0.959551 2.55 + vertex 1.11856 0.959114 2.54839 + endloop + endfacet + facet normal 0.34969 -0.160971 0.922933 + outer loop + vertex 1.11856 0.959114 2.54839 + vertex 1.12342 0.963747 2.54736 + vertex 1.11851 0.964275 2.54931 + endloop + endfacet + facet normal 0.345432 -0.187797 0.919461 + outer loop + vertex 1.12342 0.963747 2.54736 + vertex 1.12358 0.969012 2.54837 + vertex 1.11851 0.964275 2.54931 + endloop + endfacet + facet normal 0.312213 -0.148483 0.938337 + outer loop + vertex 1.11851 0.964275 2.54931 + vertex 1.12358 0.969012 2.54837 + vertex 1.11953 0.969782 2.54984 + endloop + endfacet + facet normal 0.386351 -0.145578 0.910791 + outer loop + vertex 1.11448 0.954987 2.54946 + vertex 1.11856 0.959114 2.54839 + vertex 1.11493 0.959551 2.55 + endloop + endfacet + facet normal 0.395672 -0.146009 0.906711 + outer loop + vertex 1.11448 0.954987 2.54946 + vertex 1.11493 0.959551 2.55 + vertex 1.11135 0.956425 2.55106 + endloop + endfacet + facet normal 0.397781 -0.141236 0.906545 + outer loop + vertex 1.11049 0.951797 2.55072 + vertex 1.11448 0.954987 2.54946 + vertex 1.11135 0.956425 2.55106 + endloop + endfacet + facet normal 0.405881 -0.14246 0.902755 + outer loop + vertex 1.11135 0.956425 2.55106 + vertex 1.10742 0.953398 2.55235 + vertex 1.11049 0.951797 2.55072 + endloop + endfacet + facet normal 0.407847 -0.138428 0.902496 + outer loop + vertex 1.10742 0.953398 2.55235 + vertex 1.10688 0.948699 2.55187 + vertex 1.11049 0.951797 2.55072 + endloop + endfacet + facet normal 0.412739 -0.145377 0.899173 + outer loop + vertex 1.11049 0.951797 2.55072 + vertex 1.10688 0.948699 2.55187 + vertex 1.10955 0.948014 2.55054 + endloop + endfacet + facet normal 0.399055 -0.142276 0.905821 + outer loop + vertex 1.10955 0.948014 2.55054 + vertex 1.11332 0.949386 2.54909 + vertex 1.11049 0.951797 2.55072 + endloop + endfacet + facet normal 0.4223 -0.139415 0.895671 + outer loop + vertex 1.10688 0.948699 2.55187 + vertex 1.10742 0.953398 2.55235 + vertex 1.10309 0.949498 2.55378 + endloop + endfacet + facet normal 0.421395 -0.143266 0.895489 + outer loop + vertex 1.10688 0.948699 2.55187 + vertex 1.10309 0.949498 2.55378 + vertex 1.10347 0.944004 2.55273 + endloop + endfacet + facet normal 0.41172 -0.125098 0.902683 + outer loop + vertex 1.10309 0.949498 2.55378 + vertex 1.10742 0.953398 2.55235 + vertex 1.10415 0.955117 2.55408 + endloop + endfacet + facet normal 0.407597 -0.133601 0.903336 + outer loop + vertex 1.10742 0.953398 2.55235 + vertex 1.10859 0.958908 2.55264 + vertex 1.10415 0.955117 2.55408 + endloop + endfacet + facet normal 0.399338 -0.132054 0.907244 + outer loop + vertex 1.10859 0.958908 2.55264 + vertex 1.10742 0.953398 2.55235 + vertex 1.11135 0.956425 2.55106 + endloop + endfacet + facet normal 0.393741 -0.139154 0.908628 + outer loop + vertex 1.11226 0.960131 2.55123 + vertex 1.10859 0.958908 2.55264 + vertex 1.11135 0.956425 2.55106 + endloop + endfacet + facet normal 0.392824 -0.135273 0.90961 + outer loop + vertex 1.11226 0.960131 2.55123 + vertex 1.11192 0.963317 2.55185 + vertex 1.10859 0.958908 2.55264 + endloop + endfacet + facet normal 0.38816 -0.131291 0.912192 + outer loop + vertex 1.11192 0.963317 2.55185 + vertex 1.10845 0.964011 2.55343 + vertex 1.10859 0.958908 2.55264 + endloop + endfacet + facet normal 0.395289 -0.130637 0.90922 + outer loop + vertex 1.10859 0.958908 2.55264 + vertex 1.10845 0.964011 2.55343 + vertex 1.1047 0.960158 2.55451 + endloop + endfacet + facet normal 0.398479 -0.120693 0.909202 + outer loop + vertex 1.10415 0.955117 2.55408 + vertex 1.10859 0.958908 2.55264 + vertex 1.1047 0.960158 2.55451 + endloop + endfacet + facet normal 0.390971 -0.125721 0.911776 + outer loop + vertex 1.1047 0.960158 2.55451 + vertex 1.10845 0.964011 2.55343 + vertex 1.10495 0.964696 2.55503 + endloop + endfacet + facet normal 0.387727 -0.140517 0.911001 + outer loop + vertex 1.10845 0.969211 2.55423 + vertex 1.10495 0.964696 2.55503 + vertex 1.10845 0.964011 2.55343 + endloop + endfacet + facet normal 0.387384 -0.140539 0.911144 + outer loop + vertex 1.10845 0.964011 2.55343 + vertex 1.11234 0.967956 2.55238 + vertex 1.10845 0.969211 2.55423 + endloop + endfacet + facet normal 0.383202 -0.153123 0.910884 + outer loop + vertex 1.11234 0.967956 2.55238 + vertex 1.11365 0.97377 2.55281 + vertex 1.10845 0.969211 2.55423 + endloop + endfacet + facet normal 0.398742 -0.142694 0.905894 + outer loop + vertex 1.11332 0.949386 2.54909 + vertex 1.11448 0.954987 2.54946 + vertex 1.11049 0.951797 2.55072 + endloop + endfacet + facet normal 0.396236 -0.142254 0.907061 + outer loop + vertex 1.11332 0.949386 2.54909 + vertex 1.11837 0.953832 2.54758 + vertex 1.11448 0.954987 2.54946 + endloop + endfacet + facet normal 0.392498 -0.1372 0.909462 + outer loop + vertex 1.11724 0.948196 2.54722 + vertex 1.11837 0.953832 2.54758 + vertex 1.11332 0.949386 2.54909 + endloop + endfacet + facet normal 0.390035 -0.138326 0.910351 + outer loop + vertex 1.11493 0.959551 2.55 + vertex 1.11226 0.960131 2.55123 + vertex 1.11135 0.956425 2.55106 + endloop + endfacet + facet normal 0.392876 -0.153079 0.906761 + outer loop + vertex 1.11837 0.953832 2.54758 + vertex 1.11856 0.959114 2.54839 + vertex 1.11448 0.954987 2.54946 + endloop + endfacet + facet normal 0.389315 -0.141319 0.910199 + outer loop + vertex 1.11458 0.962691 2.55064 + vertex 1.11226 0.960131 2.55123 + vertex 1.11493 0.959551 2.55 + endloop + endfacet + facet normal 0.384918 -0.136728 0.912767 + outer loop + vertex 1.11458 0.962691 2.55064 + vertex 1.11192 0.963317 2.55185 + vertex 1.11226 0.960131 2.55123 + endloop + endfacet + facet normal 0.386351 -0.139357 0.911763 + outer loop + vertex 1.11192 0.963317 2.55185 + vertex 1.11234 0.967956 2.55238 + vertex 1.10845 0.964011 2.55343 + endloop + endfacet + facet normal 0.355816 -0.154948 0.921622 + outer loop + vertex 1.11851 0.964275 2.54931 + vertex 1.11953 0.969782 2.54984 + vertex 1.11548 0.966471 2.55085 + endloop + endfacet + facet normal 0.28144 -0.152983 0.947306 + outer loop + vertex 1.11953 0.969782 2.54984 + vertex 1.12386 0.973944 2.54923 + vertex 1.12012 0.974288 2.55039 + endloop + endfacet + facet normal 0.277623 -0.181316 0.943425 + outer loop + vertex 1.12389 0.978615 2.55012 + vertex 1.12012 0.974288 2.55039 + vertex 1.12386 0.973944 2.54923 + endloop + endfacet + facet normal 0.305199 -0.179474 0.935223 + outer loop + vertex 1.12358 0.969012 2.54837 + vertex 1.12386 0.973944 2.54923 + vertex 1.11953 0.969782 2.54984 + endloop + endfacet + facet normal 0.381432 -0.152781 0.911684 + outer loop + vertex 1.11365 0.97377 2.55281 + vertex 1.11234 0.967956 2.55238 + vertex 1.11637 0.971176 2.55124 + endloop + endfacet + facet normal 0.347546 -0.185899 0.91905 + outer loop + vertex 1.11825 0.97916 2.55203 + vertex 1.11839 0.984209 2.553 + vertex 1.11337 0.979443 2.55393 + endloop + endfacet + facet normal 0.382032 -0.151552 0.911638 + outer loop + vertex 1.10845 0.969211 2.55423 + vertex 1.11365 0.97377 2.55281 + vertex 1.10958 0.97456 2.55465 + endloop + endfacet + facet normal 0.384529 -0.151991 0.910514 + outer loop + vertex 1.10845 0.969211 2.55423 + vertex 1.10958 0.97456 2.55465 + vertex 1.10578 0.971653 2.55577 + endloop + endfacet + facet normal 0.386921 -0.149049 0.909987 + outer loop + vertex 1.10466 0.967938 2.55563 + vertex 1.10845 0.969211 2.55423 + vertex 1.10578 0.971653 2.55577 + endloop + endfacet + facet normal 0.40037 -0.152892 0.903509 + outer loop + vertex 1.10578 0.971653 2.55577 + vertex 1.10209 0.968795 2.55692 + vertex 1.10466 0.967938 2.55563 + endloop + endfacet + facet normal 0.404054 -0.142029 0.903642 + outer loop + vertex 1.10466 0.967938 2.55563 + vertex 1.10209 0.968795 2.55692 + vertex 1.1023 0.965413 2.55629 + endloop + endfacet + facet normal 0.39773 -0.135118 0.907499 + outer loop + vertex 1.10466 0.967938 2.55563 + vertex 1.1023 0.965413 2.55629 + vertex 1.10495 0.964696 2.55503 + endloop + endfacet + facet normal 0.393189 -0.141587 0.908491 + outer loop + vertex 1.10314 0.974043 2.55728 + vertex 1.10209 0.968795 2.55692 + vertex 1.10578 0.971653 2.55577 + endloop + endfacet + facet normal 0.386166 -0.150361 0.910092 + outer loop + vertex 1.10692 0.975358 2.5559 + vertex 1.10314 0.974043 2.55728 + vertex 1.10578 0.971653 2.55577 + endloop + endfacet + facet normal 0.383589 -0.140099 0.912815 + outer loop + vertex 1.10692 0.975358 2.5559 + vertex 1.10669 0.978545 2.55648 + vertex 1.10314 0.974043 2.55728 + endloop + endfacet + facet normal 0.377695 -0.134884 0.916053 + outer loop + vertex 1.10669 0.978545 2.55648 + vertex 1.10323 0.979154 2.558 + vertex 1.10314 0.974043 2.55728 + endloop + endfacet + facet normal 0.384115 -0.137362 0.91301 + outer loop + vertex 1.10466 0.967938 2.55563 + vertex 1.10495 0.964696 2.55503 + vertex 1.10845 0.969211 2.55423 + endloop + endfacet + facet normal 0.382882 -0.149413 0.911634 + outer loop + vertex 1.10958 0.97456 2.55465 + vertex 1.10692 0.975358 2.5559 + vertex 1.10578 0.971653 2.55577 + endloop + endfacet + facet normal 0.382874 -0.149439 0.911634 + outer loop + vertex 1.10937 0.977926 2.55529 + vertex 1.10692 0.975358 2.5559 + vertex 1.10958 0.97456 2.55465 + endloop + endfacet + facet normal 0.375418 -0.141274 0.916026 + outer loop + vertex 1.10937 0.977926 2.55529 + vertex 1.10669 0.978545 2.55648 + vertex 1.10692 0.975358 2.5559 + endloop + endfacet + facet normal 0.37814 -0.132695 0.916189 + outer loop + vertex 1.10669 0.978545 2.55648 + vertex 1.10716 0.983071 2.55694 + vertex 1.10323 0.979154 2.558 + endloop + endfacet + facet normal 0.377744 -0.132235 0.916419 + outer loop + vertex 1.10323 0.979154 2.558 + vertex 1.10716 0.983071 2.55694 + vertex 1.10363 0.984104 2.55855 + endloop + endfacet + facet normal 0.384505 -0.132453 0.913571 + outer loop + vertex 1.10323 0.979154 2.558 + vertex 1.10363 0.984104 2.55855 + vertex 1.0997 0.980099 2.55962 + endloop + endfacet + facet normal 0.383338 -0.131128 0.914252 + outer loop + vertex 1.0997 0.980099 2.55962 + vertex 1.10363 0.984104 2.55855 + vertex 1.10006 0.984552 2.56011 + endloop + endfacet + facet normal 0.376869 -0.135133 0.916356 + outer loop + vertex 1.10716 0.983071 2.55694 + vertex 1.1082 0.988637 2.55734 + vertex 1.10363 0.984104 2.55855 + endloop + endfacet + facet normal 0.377648 -0.136039 0.915901 + outer loop + vertex 1.10363 0.984104 2.55855 + vertex 1.1082 0.988637 2.55734 + vertex 1.10358 0.989299 2.55934 + endloop + endfacet + facet normal 0.355103 -0.150979 0.922555 + outer loop + vertex 1.11337 0.979443 2.55393 + vertex 1.11434 0.985005 2.55447 + vertex 1.11031 0.981708 2.55548 + endloop + endfacet + facet normal 0.312484 -0.145136 0.93877 + outer loop + vertex 1.11337 0.979443 2.55393 + vertex 1.11839 0.984209 2.553 + vertex 1.11434 0.985005 2.55447 + endloop + endfacet + facet normal 0.306812 -0.169805 0.9365 + outer loop + vertex 1.11839 0.984209 2.553 + vertex 1.11864 0.989146 2.55381 + vertex 1.11434 0.985005 2.55447 + endloop + endfacet + facet normal 0.281089 -0.141042 0.949261 + outer loop + vertex 1.11434 0.985005 2.55447 + vertex 1.11864 0.989146 2.55381 + vertex 1.11475 0.989544 2.55502 + endloop + endfacet + facet normal 0.277407 -0.167297 0.946074 + outer loop + vertex 1.11857 0.994134 2.55471 + vertex 1.11475 0.989544 2.55502 + vertex 1.11864 0.989146 2.55381 + endloop + endfacet + facet normal 0.316781 -0.145431 0.937283 + outer loop + vertex 1.11454 0.99273 2.55559 + vertex 1.11202 0.990144 2.55604 + vertex 1.11475 0.989544 2.55502 + endloop + endfacet + facet normal 0.259787 -0.152139 0.953606 + outer loop + vertex 1.11454 0.99273 2.55559 + vertex 1.11475 0.989544 2.55502 + vertex 1.11857 0.994134 2.55471 + endloop + endfacet + facet normal 0.26379 -0.165728 0.950236 + outer loop + vertex 1.11454 0.99273 2.55559 + vertex 1.11857 0.994134 2.55471 + vertex 1.11591 0.996392 2.55585 + endloop + endfacet + facet normal 0.324568 -0.186929 0.927207 + outer loop + vertex 1.11591 0.996392 2.55585 + vertex 1.11197 0.993461 2.55663 + vertex 1.11454 0.99273 2.55559 + endloop + endfacet + facet normal 0.332411 -0.162098 0.9291 + outer loop + vertex 1.11454 0.99273 2.55559 + vertex 1.11197 0.993461 2.55663 + vertex 1.11202 0.990144 2.55604 + endloop + endfacet + facet normal 0.368736 -0.133869 0.919844 + outer loop + vertex 1.1082 0.988637 2.55734 + vertex 1.10716 0.983071 2.55694 + vertex 1.11107 0.986338 2.55585 + endloop + endfacet + facet normal 0.37586 -0.146063 0.915093 + outer loop + vertex 1.1082 0.988637 2.55734 + vertex 1.10827 0.994047 2.55817 + vertex 1.10358 0.989299 2.55934 + endloop + endfacet + facet normal 0.3646 -0.13335 0.921566 + outer loop + vertex 1.10358 0.989299 2.55934 + vertex 1.10827 0.994047 2.55817 + vertex 1.1045 0.994615 2.55974 + endloop + endfacet + facet normal 0.367878 -0.121097 0.921955 + outer loop + vertex 1.10428 0.997966 2.56029 + vertex 1.10158 0.998484 2.56143 + vertex 1.10186 0.995282 2.5609 + endloop + endfacet + facet normal 0.375319 -0.119975 0.919098 + outer loop + vertex 1.10186 0.995282 2.5609 + vertex 1.10158 0.998484 2.56143 + vertex 1.09809 0.993688 2.56223 + endloop + endfacet + facet normal 0.375306 -0.119964 0.919105 + outer loop + vertex 1.10158 0.998484 2.56143 + vertex 1.09801 0.998889 2.56295 + vertex 1.09809 0.993688 2.56223 + endloop + endfacet + facet normal 0.385006 -0.119277 0.915174 + outer loop + vertex 1.09809 0.993688 2.56223 + vertex 1.09801 0.998889 2.56295 + vertex 1.09348 0.99426 2.56425 + endloop + endfacet + facet normal 0.38529 -0.117413 0.915295 + outer loop + vertex 1.09374 0.989063 2.56347 + vertex 1.09809 0.993688 2.56223 + vertex 1.09348 0.99426 2.56425 + endloop + endfacet + facet normal 0.383382 -0.117431 0.916094 + outer loop + vertex 1.09348 0.99426 2.56425 + vertex 1.09801 0.998889 2.56295 + vertex 1.09445 0.999852 2.56456 + endloop + endfacet + facet normal 0.381974 -0.122516 0.916016 + outer loop + vertex 1.09801 0.998889 2.56295 + vertex 1.09849 1.00404 2.56343 + vertex 1.09445 0.999852 2.56456 + endloop + endfacet + facet normal 0.380437 -0.120797 0.916884 + outer loop + vertex 1.09445 0.999852 2.56456 + vertex 1.09849 1.00404 2.56343 + vertex 1.09491 1.00448 2.56498 + endloop + endfacet + facet normal 0.379451 -0.127215 0.916424 + outer loop + vertex 1.09848 1.00931 2.56417 + vertex 1.09491 1.00448 2.56498 + vertex 1.09849 1.00404 2.56343 + endloop + endfacet + facet normal 0.367662 -0.127904 0.921122 + outer loop + vertex 1.09849 1.00404 2.56343 + vertex 1.1032 1.00869 2.5622 + vertex 1.09848 1.00931 2.56417 + endloop + endfacet + facet normal 0.363935 -0.150226 0.91923 + outer loop + vertex 1.1032 1.00869 2.5622 + vertex 1.1034 1.01398 2.56298 + vertex 1.09848 1.00931 2.56417 + endloop + endfacet + facet normal 0.342629 -0.124741 0.931153 + outer loop + vertex 1.09848 1.00931 2.56417 + vertex 1.1034 1.01398 2.56298 + vertex 1.09953 1.01492 2.56454 + endloop + endfacet + facet normal 0.335835 -0.150439 0.92983 + outer loop + vertex 1.1034 1.01398 2.56298 + vertex 1.10384 1.01909 2.56365 + vertex 1.09953 1.01492 2.56454 + endloop + endfacet + facet normal 0.393189 -0.126055 0.910776 + outer loop + vertex 1.09724 0.988441 2.56187 + vertex 1.09809 0.993688 2.56223 + vertex 1.09374 0.989063 2.56347 + endloop + endfacet + facet normal 0.394712 -0.118413 0.911143 + outer loop + vertex 1.09724 0.988441 2.56187 + vertex 1.09374 0.989063 2.56347 + vertex 1.09381 0.983803 2.56276 + endloop + endfacet + facet normal 0.378786 -0.135352 0.915533 + outer loop + vertex 1.10358 0.989299 2.55934 + vertex 1.1045 0.994615 2.55974 + vertex 1.10083 0.991507 2.5608 + endloop + endfacet + facet normal 0.382607 -0.135693 0.913893 + outer loop + vertex 1.10358 0.989299 2.55934 + vertex 1.10006 0.984552 2.56011 + vertex 1.10363 0.984104 2.55855 + endloop + endfacet + facet normal 0.387683 -0.131875 0.912311 + outer loop + vertex 1.09979 0.987739 2.56069 + vertex 1.09724 0.988441 2.56187 + vertex 1.09743 0.985106 2.56131 + endloop + endfacet + facet normal 0.407665 -0.129361 0.903922 + outer loop + vertex 1.09743 0.985106 2.56131 + vertex 1.09724 0.988441 2.56187 + vertex 1.09381 0.983803 2.56276 + endloop + endfacet + facet normal 0.395737 -0.131528 0.908896 + outer loop + vertex 1.0997 0.980099 2.55962 + vertex 1.10006 0.984552 2.56011 + vertex 1.09653 0.981317 2.56118 + endloop + endfacet + facet normal 0.385944 -0.127294 0.913698 + outer loop + vertex 1.0992 0.975207 2.55915 + vertex 1.10323 0.979154 2.558 + vertex 1.0997 0.980099 2.55962 + endloop + endfacet + facet normal 0.391807 -0.134315 0.910191 + outer loop + vertex 1.10314 0.974043 2.55728 + vertex 1.10323 0.979154 2.558 + vertex 1.0992 0.975207 2.55915 + endloop + endfacet + facet normal 0.394598 -0.125042 0.910306 + outer loop + vertex 1.09822 0.96961 2.55881 + vertex 1.10314 0.974043 2.55728 + vertex 1.0992 0.975207 2.55915 + endloop + endfacet + facet normal 0.424557 -0.119179 0.897523 + outer loop + vertex 1.09266 0.978132 2.56255 + vertex 1.09205 0.973094 2.56217 + vertex 1.09586 0.976591 2.56084 + endloop + endfacet + facet normal 0.411266 -0.127485 0.902556 + outer loop + vertex 1.09822 0.96961 2.55881 + vertex 1.0992 0.975207 2.55915 + vertex 1.09524 0.971895 2.56048 + endloop + endfacet + facet normal 0.409029 -0.144264 0.901046 + outer loop + vertex 1.10209 0.968795 2.55692 + vertex 1.10314 0.974043 2.55728 + vertex 1.09822 0.96961 2.55881 + endloop + endfacet + facet normal 0.40452 -0.125772 0.905839 + outer loop + vertex 1.1047 0.960158 2.55451 + vertex 1.10495 0.964696 2.55503 + vertex 1.10146 0.961584 2.55615 + endloop + endfacet + facet normal 0.420964 -0.126602 0.898199 + outer loop + vertex 1.10309 0.949498 2.55378 + vertex 1.10415 0.955117 2.55408 + vertex 1.10028 0.951963 2.55545 + endloop + endfacet + facet normal 0.424709 -0.121603 0.897126 + outer loop + vertex 1.0995 0.94819 2.5553 + vertex 1.10309 0.949498 2.55378 + vertex 1.10028 0.951963 2.55545 + endloop + endfacet + facet normal 0.397949 -0.116584 0.90997 + outer loop + vertex 1.10028 0.951963 2.55545 + vertex 1.09682 0.948691 2.55654 + vertex 1.0995 0.94819 2.5553 + endloop + endfacet + facet normal 0.394686 -0.132305 0.909241 + outer loop + vertex 1.0995 0.94819 2.5553 + vertex 1.09682 0.948691 2.55654 + vertex 1.09719 0.945566 2.55593 + endloop + endfacet + facet normal 0.41096 -0.148981 0.899398 + outer loop + vertex 1.0995 0.94819 2.5553 + vertex 1.09719 0.945566 2.55593 + vertex 1.09971 0.944814 2.55465 + endloop + endfacet + facet normal 0.430824 -0.146063 0.890537 + outer loop + vertex 1.0995 0.94819 2.5553 + vertex 1.09971 0.944814 2.55465 + vertex 1.10309 0.949498 2.55378 + endloop + endfacet + facet normal 0.426531 -0.142469 0.893182 + outer loop + vertex 1.10309 0.949498 2.55378 + vertex 1.09971 0.944814 2.55465 + vertex 1.10347 0.944004 2.55273 + endloop + endfacet + facet normal 0.418673 -0.174345 0.891244 + outer loop + vertex 1.0984 0.939311 2.55419 + vertex 1.10347 0.944004 2.55273 + vertex 1.09971 0.944814 2.55465 + endloop + endfacet + facet normal 0.400325 -0.150595 0.903914 + outer loop + vertex 1.10236 0.93829 2.55226 + vertex 1.10347 0.944004 2.55273 + vertex 1.0984 0.939311 2.55419 + endloop + endfacet + facet normal 0.38944 -0.188379 0.901582 + outer loop + vertex 1.09814 0.933866 2.55316 + vertex 1.10236 0.93829 2.55226 + vertex 1.0984 0.939311 2.55419 + endloop + endfacet + facet normal 0.361557 -0.158273 0.918818 + outer loop + vertex 1.10192 0.933656 2.55164 + vertex 1.10236 0.93829 2.55226 + vertex 1.09814 0.933866 2.55316 + endloop + endfacet + facet normal 0.397519 -0.159639 0.903601 + outer loop + vertex 1.10236 0.93829 2.55226 + vertex 1.10192 0.933656 2.55164 + vertex 1.10554 0.936938 2.55062 + endloop + endfacet + facet normal 0.404318 -0.14329 0.903324 + outer loop + vertex 1.10634 0.941631 2.55102 + vertex 1.10236 0.93829 2.55226 + vertex 1.10554 0.936938 2.55062 + endloop + endfacet + facet normal 0.407775 -0.143738 0.901698 + outer loop + vertex 1.10554 0.936938 2.55062 + vertex 1.10948 0.940184 2.54936 + vertex 1.10634 0.941631 2.55102 + endloop + endfacet + facet normal 0.40956 -0.13967 0.901528 + outer loop + vertex 1.10948 0.940184 2.54936 + vertex 1.10987 0.944801 2.5499 + vertex 1.10634 0.941631 2.55102 + endloop + endfacet + facet normal 0.408219 -0.137863 0.902414 + outer loop + vertex 1.10987 0.944801 2.5499 + vertex 1.10722 0.945439 2.5512 + vertex 1.10634 0.941631 2.55102 + endloop + endfacet + facet normal 0.419179 -0.140146 0.897022 + outer loop + vertex 1.10722 0.945439 2.5512 + vertex 1.10347 0.944004 2.55273 + vertex 1.10634 0.941631 2.55102 + endloop + endfacet + facet normal 0.419618 -0.141783 0.896559 + outer loop + vertex 1.10722 0.945439 2.5512 + vertex 1.10688 0.948699 2.55187 + vertex 1.10347 0.944004 2.55273 + endloop + endfacet + facet normal 0.413017 -0.15151 0.898032 + outer loop + vertex 1.10839 0.934541 2.54891 + vertex 1.10948 0.940184 2.54936 + vertex 1.10554 0.936938 2.55062 + endloop + endfacet + facet normal 0.412358 -0.152399 0.898184 + outer loop + vertex 1.10461 0.933132 2.55041 + vertex 1.10839 0.934541 2.54891 + vertex 1.10554 0.936938 2.55062 + endloop + endfacet + facet normal 0.417956 -0.17441 0.891568 + outer loop + vertex 1.10461 0.933132 2.55041 + vertex 1.10475 0.929767 2.54968 + vertex 1.10839 0.934541 2.54891 + endloop + endfacet + facet normal 0.411258 -0.168631 0.895785 + outer loop + vertex 1.10839 0.934541 2.54891 + vertex 1.10475 0.929767 2.54968 + vertex 1.1086 0.92896 2.54776 + endloop + endfacet + facet normal 0.408454 -0.168991 0.896999 + outer loop + vertex 1.11225 0.93371 2.547 + vertex 1.10839 0.934541 2.54891 + vertex 1.1086 0.92896 2.54776 + endloop + endfacet + facet normal 0.405635 -0.16655 0.898733 + outer loop + vertex 1.11244 0.930366 2.54629 + vertex 1.11225 0.93371 2.547 + vertex 1.1086 0.92896 2.54776 + endloop + endfacet + facet normal 0.404362 -0.161521 0.900224 + outer loop + vertex 1.11244 0.930366 2.54629 + vertex 1.1086 0.92896 2.54776 + vertex 1.11147 0.926585 2.54605 + endloop + endfacet + facet normal 0.394924 -0.159391 0.904782 + outer loop + vertex 1.11511 0.929769 2.54502 + vertex 1.11244 0.930366 2.54629 + vertex 1.11147 0.926585 2.54605 + endloop + endfacet + facet normal 0.393073 -0.156869 0.906027 + outer loop + vertex 1.1146 0.925139 2.54444 + vertex 1.11511 0.929769 2.54502 + vertex 1.11147 0.926585 2.54605 + endloop + endfacet + facet normal 0.392845 -0.157376 0.906038 + outer loop + vertex 1.11051 0.92185 2.54564 + vertex 1.1146 0.925139 2.54444 + vertex 1.11147 0.926585 2.54605 + endloop + endfacet + facet normal 0.387741 -0.156552 0.908377 + outer loop + vertex 1.11147 0.926585 2.54605 + vertex 1.10738 0.923272 2.54722 + vertex 1.11051 0.92185 2.54564 + endloop + endfacet + facet normal 0.383262 -0.16655 0.908499 + outer loop + vertex 1.10738 0.923272 2.54722 + vertex 1.10678 0.918616 2.54662 + vertex 1.11051 0.92185 2.54564 + endloop + endfacet + facet normal 0.373645 -0.153532 0.914777 + outer loop + vertex 1.11051 0.92185 2.54564 + vertex 1.10678 0.918616 2.54662 + vertex 1.10925 0.917807 2.54548 + endloop + endfacet + facet normal 0.391819 -0.158875 0.906221 + outer loop + vertex 1.10925 0.917807 2.54548 + vertex 1.11318 0.919238 2.54403 + vertex 1.11051 0.92185 2.54564 + endloop + endfacet + facet normal 0.399841 -0.190672 0.896533 + outer loop + vertex 1.10925 0.917807 2.54548 + vertex 1.1087 0.91365 2.54484 + vertex 1.11318 0.919238 2.54403 + endloop + endfacet + facet normal 0.373894 -0.167642 0.912195 + outer loop + vertex 1.11318 0.919238 2.54403 + vertex 1.1087 0.91365 2.54484 + vertex 1.11342 0.913521 2.54288 + endloop + endfacet + facet normal 0.391616 -0.165472 0.905128 + outer loop + vertex 1.11715 0.918515 2.54218 + vertex 1.11318 0.919238 2.54403 + vertex 1.11342 0.913521 2.54288 + endloop + endfacet + facet normal 0.379812 -0.155699 0.911867 + outer loop + vertex 1.11728 0.915095 2.54154 + vertex 1.11715 0.918515 2.54218 + vertex 1.11342 0.913521 2.54288 + endloop + endfacet + facet normal 0.382296 -0.163907 0.909387 + outer loop + vertex 1.11728 0.915095 2.54154 + vertex 1.11342 0.913521 2.54288 + vertex 1.11642 0.91135 2.54123 + endloop + endfacet + facet normal 0.389685 -0.165308 0.90599 + outer loop + vertex 1.12003 0.914542 2.54026 + vertex 1.11728 0.915095 2.54154 + vertex 1.11642 0.91135 2.54123 + endloop + endfacet + facet normal 0.402181 -0.18209 0.89727 + outer loop + vertex 1.11978 0.91011 2.53947 + vertex 1.12003 0.914542 2.54026 + vertex 1.11642 0.91135 2.54123 + endloop + endfacet + facet normal 0.383944 -0.227886 0.894793 + outer loop + vertex 1.11592 0.907184 2.54038 + vertex 1.11978 0.91011 2.53947 + vertex 1.11642 0.91135 2.54123 + endloop + endfacet + facet normal 0.379297 -0.227733 0.896812 + outer loop + vertex 1.11642 0.91135 2.54123 + vertex 1.11276 0.90836 2.54202 + vertex 1.11592 0.907184 2.54038 + endloop + endfacet + facet normal 0.344061 -0.308608 0.886783 + outer loop + vertex 1.11276 0.90836 2.54202 + vertex 1.11287 0.905172 2.54087 + vertex 1.11592 0.907184 2.54038 + endloop + endfacet + facet normal 0.385871 -0.383412 0.839106 + outer loop + vertex 1.11592 0.907184 2.54038 + vertex 1.11287 0.905172 2.54087 + vertex 1.11507 0.904031 2.53933 + endloop + endfacet + facet normal 0.355713 -0.380144 0.853791 + outer loop + vertex 1.11507 0.904031 2.53933 + vertex 1.11922 0.905298 2.53817 + vertex 1.11592 0.907184 2.54038 + endloop + endfacet + facet normal 0.417949 -0.282438 0.863451 + outer loop + vertex 1.11922 0.905298 2.53817 + vertex 1.11978 0.91011 2.53947 + vertex 1.11592 0.907184 2.54038 + endloop + endfacet + facet normal 0.355055 -0.282731 0.891066 + outer loop + vertex 1.11922 0.905298 2.53817 + vertex 1.12376 0.909075 2.53756 + vertex 1.11978 0.91011 2.53947 + endloop + endfacet + facet normal 0.386753 -0.183906 0.903659 + outer loop + vertex 1.12376 0.909075 2.53756 + vertex 1.12375 0.914105 2.53859 + vertex 1.11978 0.91011 2.53947 + endloop + endfacet + facet normal 0.385434 -0.182402 0.904528 + outer loop + vertex 1.11978 0.91011 2.53947 + vertex 1.12375 0.914105 2.53859 + vertex 1.12003 0.914542 2.54026 + endloop + endfacet + facet normal 0.35878 -0.198513 0.912069 + outer loop + vertex 1.11342 0.913521 2.54288 + vertex 1.11276 0.90836 2.54202 + vertex 1.11642 0.91135 2.54123 + endloop + endfacet + facet normal 0.330339 -0.196714 0.923136 + outer loop + vertex 1.11276 0.90836 2.54202 + vertex 1.11342 0.913521 2.54288 + vertex 1.10896 0.908878 2.54349 + endloop + endfacet + facet normal 0.392618 -0.160947 0.90551 + outer loop + vertex 1.11715 0.918515 2.54218 + vertex 1.11846 0.923951 2.54258 + vertex 1.11318 0.919238 2.54403 + endloop + endfacet + facet normal 0.389515 -0.15683 0.90757 + outer loop + vertex 1.11318 0.919238 2.54403 + vertex 1.11846 0.923951 2.54258 + vertex 1.1146 0.925139 2.54444 + endloop + endfacet + facet normal 0.388626 -0.159569 0.907473 + outer loop + vertex 1.11846 0.923951 2.54258 + vertex 1.11873 0.929287 2.5434 + vertex 1.1146 0.925139 2.54444 + endloop + endfacet + facet normal 0.385934 -0.156469 0.90916 + outer loop + vertex 1.1146 0.925139 2.54444 + vertex 1.11873 0.929287 2.5434 + vertex 1.11511 0.929769 2.54502 + endloop + endfacet + facet normal 0.385414 -0.159398 0.908872 + outer loop + vertex 1.11867 0.934422 2.54433 + vertex 1.11511 0.929769 2.54502 + vertex 1.11873 0.929287 2.5434 + endloop + endfacet + facet normal 0.385139 -0.159422 0.908984 + outer loop + vertex 1.11873 0.929287 2.5434 + vertex 1.12322 0.933842 2.5423 + vertex 1.11867 0.934422 2.54433 + endloop + endfacet + facet normal 0.385604 -0.156722 0.909257 + outer loop + vertex 1.12322 0.933842 2.5423 + vertex 1.12317 0.939002 2.54321 + vertex 1.11867 0.934422 2.54433 + endloop + endfacet + facet normal 0.383184 -0.157198 0.910197 + outer loop + vertex 1.12224 0.928627 2.54181 + vertex 1.12322 0.933842 2.5423 + vertex 1.11873 0.929287 2.5434 + endloop + endfacet + facet normal 0.382632 -0.159664 0.91 + outer loop + vertex 1.12224 0.928627 2.54181 + vertex 1.11873 0.929287 2.5434 + vertex 1.11846 0.923951 2.54258 + endloop + endfacet + facet normal 0.387593 -0.164152 0.907098 + outer loop + vertex 1.12226 0.925279 2.54119 + vertex 1.12224 0.928627 2.54181 + vertex 1.11846 0.923951 2.54258 + endloop + endfacet + facet normal 0.388336 -0.167189 0.906225 + outer loop + vertex 1.12226 0.925279 2.54119 + vertex 1.11846 0.923951 2.54258 + vertex 1.12101 0.921539 2.54104 + endloop + endfacet + facet normal 0.388384 -0.167205 0.906201 + outer loop + vertex 1.12478 0.924537 2.53998 + vertex 1.12226 0.925279 2.54119 + vertex 1.12101 0.921539 2.54104 + endloop + endfacet + facet normal 0.385112 -0.162273 0.908491 + outer loop + vertex 1.12368 0.919284 2.53951 + vertex 1.12478 0.924537 2.53998 + vertex 1.12101 0.921539 2.54104 + endloop + endfacet + facet normal 0.387621 -0.158969 0.908008 + outer loop + vertex 1.11978 0.91777 2.54091 + vertex 1.12368 0.919284 2.53951 + vertex 1.12101 0.921539 2.54104 + endloop + endfacet + facet normal 0.393146 -0.160672 0.905329 + outer loop + vertex 1.12101 0.921539 2.54104 + vertex 1.11715 0.918515 2.54218 + vertex 1.11978 0.91777 2.54091 + endloop + endfacet + facet normal 0.395187 -0.153954 0.905608 + outer loop + vertex 1.11978 0.91777 2.54091 + vertex 1.11715 0.918515 2.54218 + vertex 1.11728 0.915095 2.54154 + endloop + endfacet + facet normal 0.39293 -0.151514 0.907 + outer loop + vertex 1.11978 0.91777 2.54091 + vertex 1.11728 0.915095 2.54154 + vertex 1.12003 0.914542 2.54026 + endloop + endfacet + facet normal 0.38583 -0.152652 0.909853 + outer loop + vertex 1.11978 0.91777 2.54091 + vertex 1.12003 0.914542 2.54026 + vertex 1.12368 0.919284 2.53951 + endloop + endfacet + facet normal 0.387636 -0.162698 0.907341 + outer loop + vertex 1.12368 0.919284 2.53951 + vertex 1.1284 0.924054 2.53835 + vertex 1.12478 0.924537 2.53998 + endloop + endfacet + facet normal 0.385266 -0.159989 0.908831 + outer loop + vertex 1.12825 0.918708 2.53747 + vertex 1.1284 0.924054 2.53835 + vertex 1.12368 0.919284 2.53951 + endloop + endfacet + facet normal 0.385868 -0.156473 0.909188 + outer loop + vertex 1.12375 0.914105 2.53859 + vertex 1.12825 0.918708 2.53747 + vertex 1.12368 0.919284 2.53951 + endloop + endfacet + facet normal 0.389875 -0.156126 0.907536 + outer loop + vertex 1.12368 0.919284 2.53951 + vertex 1.12003 0.914542 2.54026 + vertex 1.12375 0.914105 2.53859 + endloop + endfacet + facet normal 0.38064 -0.150577 0.912381 + outer loop + vertex 1.12727 0.913429 2.53701 + vertex 1.12825 0.918708 2.53747 + vertex 1.12375 0.914105 2.53859 + endloop + endfacet + facet normal 0.372636 -0.185114 0.909327 + outer loop + vertex 1.12727 0.913429 2.53701 + vertex 1.12375 0.914105 2.53859 + vertex 1.12376 0.909075 2.53756 + endloop + endfacet + facet normal 0.351198 -0.166324 0.92141 + outer loop + vertex 1.12736 0.910087 2.53637 + vertex 1.12727 0.913429 2.53701 + vertex 1.12376 0.909075 2.53756 + endloop + endfacet + facet normal 0.360945 -0.218212 0.906699 + outer loop + vertex 1.12736 0.910087 2.53637 + vertex 1.12376 0.909075 2.53756 + vertex 1.12625 0.906635 2.53598 + endloop + endfacet + facet normal 0.378461 -0.222872 0.898385 + outer loop + vertex 1.12987 0.909317 2.53512 + vertex 1.12736 0.910087 2.53637 + vertex 1.12625 0.906635 2.53598 + endloop + endfacet + facet normal 0.38499 -0.233432 0.892912 + outer loop + vertex 1.1289 0.904206 2.5342 + vertex 1.12987 0.909317 2.53512 + vertex 1.12625 0.906635 2.53598 + endloop + endfacet + facet normal 0.325185 -0.301255 0.896382 + outer loop + vertex 1.1248 0.903258 2.53537 + vertex 1.1289 0.904206 2.5342 + vertex 1.12625 0.906635 2.53598 + endloop + endfacet + facet normal 0.350396 -0.309827 0.883872 + outer loop + vertex 1.12625 0.906635 2.53598 + vertex 1.12302 0.905016 2.53669 + vertex 1.1248 0.903258 2.53537 + endloop + endfacet + facet normal 0.392617 -0.181769 0.901561 + outer loop + vertex 1.12977 0.912628 2.53583 + vertex 1.12736 0.910087 2.53637 + vertex 1.12987 0.909317 2.53512 + endloop + endfacet + facet normal 0.394191 -0.181584 0.900911 + outer loop + vertex 1.12977 0.912628 2.53583 + vertex 1.12987 0.909317 2.53512 + vertex 1.13361 0.914218 2.53447 + endloop + endfacet + facet normal 0.384621 -0.150108 0.910788 + outer loop + vertex 1.12977 0.912628 2.53583 + vertex 1.13361 0.914218 2.53447 + vertex 1.13089 0.916437 2.53599 + endloop + endfacet + facet normal 0.381075 -0.149135 0.912437 + outer loop + vertex 1.13089 0.916437 2.53599 + vertex 1.12727 0.913429 2.53701 + vertex 1.12977 0.912628 2.53583 + endloop + endfacet + facet normal 0.382254 -0.150816 0.911667 + outer loop + vertex 1.12825 0.918708 2.53747 + vertex 1.12727 0.913429 2.53701 + vertex 1.13089 0.916437 2.53599 + endloop + endfacet + facet normal 0.378712 -0.158099 0.911911 + outer loop + vertex 1.13361 0.914218 2.53447 + vertex 1.1346 0.919555 2.53499 + vertex 1.13089 0.916437 2.53599 + endloop + endfacet + facet normal 0.367197 -0.142056 0.919231 + outer loop + vertex 1.1346 0.919555 2.53499 + vertex 1.13201 0.920237 2.53613 + vertex 1.13089 0.916437 2.53599 + endloop + endfacet + facet normal 0.385162 -0.147042 0.911059 + outer loop + vertex 1.13201 0.920237 2.53613 + vertex 1.12825 0.918708 2.53747 + vertex 1.13089 0.916437 2.53599 + endloop + endfacet + facet normal 0.389194 -0.160435 0.907077 + outer loop + vertex 1.13201 0.920237 2.53613 + vertex 1.13198 0.923576 2.53673 + vertex 1.12825 0.918708 2.53747 + endloop + endfacet + facet normal 0.372192 -0.161801 0.913944 + outer loop + vertex 1.1345 0.922883 2.53558 + vertex 1.13198 0.923576 2.53673 + vertex 1.13201 0.920237 2.53613 + endloop + endfacet + facet normal 0.367407 -0.177512 0.912963 + outer loop + vertex 1.13576 0.926621 2.5358 + vertex 1.13198 0.923576 2.53673 + vertex 1.1345 0.922883 2.53558 + endloop + endfacet + facet normal 0.323068 -0.163653 0.932119 + outer loop + vertex 1.1345 0.922883 2.53558 + vertex 1.13843 0.924396 2.53448 + vertex 1.13576 0.926621 2.5358 + endloop + endfacet + facet normal 0.309076 -0.18131 0.933595 + outer loop + vertex 1.13843 0.924396 2.53448 + vertex 1.13964 0.929496 2.53507 + vertex 1.13576 0.926621 2.5358 + endloop + endfacet + facet normal 0.303989 -0.173646 0.936716 + outer loop + vertex 1.13964 0.929496 2.53507 + vertex 1.13724 0.930421 2.53602 + vertex 1.13576 0.926621 2.5358 + endloop + endfacet + facet normal 0.356793 -0.192897 0.914051 + outer loop + vertex 1.13724 0.930421 2.53602 + vertex 1.13329 0.928939 2.53726 + vertex 1.13576 0.926621 2.5358 + endloop + endfacet + facet normal 0.366256 -0.228063 0.902133 + outer loop + vertex 1.13724 0.930421 2.53602 + vertex 1.13804 0.934312 2.53668 + vertex 1.13329 0.928939 2.53726 + endloop + endfacet + facet normal 0.321094 -0.157227 0.933905 + outer loop + vertex 1.1345 0.922883 2.53558 + vertex 1.1346 0.919555 2.53499 + vertex 1.13843 0.924396 2.53448 + endloop + endfacet + facet normal 0.368554 -0.179172 0.912176 + outer loop + vertex 1.13329 0.928939 2.53726 + vertex 1.13198 0.923576 2.53673 + vertex 1.13576 0.926621 2.5358 + endloop + endfacet + facet normal 0.364039 -0.153165 0.918703 + outer loop + vertex 1.1345 0.922883 2.53558 + vertex 1.13201 0.920237 2.53613 + vertex 1.1346 0.919555 2.53499 + endloop + endfacet + facet normal 0.347182 -0.153496 0.925151 + outer loop + vertex 1.13361 0.914218 2.53447 + vertex 1.13848 0.9192 2.53347 + vertex 1.1346 0.919555 2.53499 + endloop + endfacet + facet normal 0.34395 -0.176507 0.922249 + outer loop + vertex 1.13843 0.924396 2.53448 + vertex 1.1346 0.919555 2.53499 + vertex 1.13848 0.9192 2.53347 + endloop + endfacet + facet normal 0.374765 -0.183809 0.908717 + outer loop + vertex 1.13836 0.913804 2.53243 + vertex 1.13848 0.9192 2.53347 + vertex 1.13361 0.914218 2.53447 + endloop + endfacet + facet normal 0.37635 -0.172911 0.910199 + outer loop + vertex 1.13353 0.908837 2.53348 + vertex 1.13836 0.913804 2.53243 + vertex 1.13361 0.914218 2.53447 + endloop + endfacet + facet normal 0.37327 -0.169505 0.912106 + outer loop + vertex 1.1371 0.908357 2.53193 + vertex 1.13836 0.913804 2.53243 + vertex 1.13353 0.908837 2.53348 + endloop + endfacet + facet normal 0.37345 -0.168517 0.912216 + outer loop + vertex 1.1371 0.908357 2.53193 + vertex 1.13353 0.908837 2.53348 + vertex 1.13361 0.903642 2.53249 + endloop + endfacet + facet normal 0.343806 -0.144664 0.927831 + outer loop + vertex 1.13714 0.904962 2.53139 + vertex 1.1371 0.908357 2.53193 + vertex 1.13361 0.903642 2.53249 + endloop + endfacet + facet normal 0.343439 -0.143407 0.928162 + outer loop + vertex 1.13714 0.904962 2.53139 + vertex 1.13361 0.903642 2.53249 + vertex 1.13609 0.901346 2.53122 + endloop + endfacet + facet normal 0.369796 -0.150494 0.916844 + outer loop + vertex 1.13967 0.904285 2.53026 + vertex 1.13714 0.904962 2.53139 + vertex 1.13609 0.901346 2.53122 + endloop + endfacet + facet normal 0.393293 -0.184342 0.900743 + outer loop + vertex 1.13866 0.899085 2.52963 + vertex 1.13967 0.904285 2.53026 + vertex 1.13609 0.901346 2.53122 + endloop + endfacet + facet normal 0.361623 -0.223359 0.905174 + outer loop + vertex 1.13475 0.897867 2.53089 + vertex 1.13866 0.899085 2.52963 + vertex 1.13609 0.901346 2.53122 + endloop + endfacet + facet normal 0.326952 -0.211461 0.921079 + outer loop + vertex 1.13609 0.901346 2.53122 + vertex 1.13309 0.899459 2.53185 + vertex 1.13475 0.897867 2.53089 + endloop + endfacet + facet normal 0.359131 -0.179493 0.915864 + outer loop + vertex 1.13866 0.899085 2.52963 + vertex 1.14354 0.904016 2.52869 + vertex 1.13967 0.904285 2.53026 + endloop + endfacet + facet normal 0.36098 -0.164791 0.917898 + outer loop + vertex 1.14349 0.909253 2.52965 + vertex 1.13967 0.904285 2.53026 + vertex 1.14354 0.904016 2.52869 + endloop + endfacet + facet normal 0.334983 -0.143163 0.931284 + outer loop + vertex 1.13956 0.907644 2.53081 + vertex 1.13967 0.904285 2.53026 + vertex 1.14349 0.909253 2.52965 + endloop + endfacet + facet normal 0.336158 -0.146739 0.930304 + outer loop + vertex 1.13956 0.907644 2.53081 + vertex 1.14349 0.909253 2.52965 + vertex 1.14084 0.911481 2.53096 + endloop + endfacet + facet normal 0.370885 -0.15771 0.91519 + outer loop + vertex 1.14084 0.911481 2.53096 + vertex 1.1371 0.908357 2.53193 + vertex 1.13956 0.907644 2.53081 + endloop + endfacet + facet normal 0.360214 -0.180692 0.915203 + outer loop + vertex 1.14348 0.89867 2.52765 + vertex 1.14354 0.904016 2.52869 + vertex 1.13866 0.899085 2.52963 + endloop + endfacet + facet normal 0.372895 -0.139662 0.917302 + outer loop + vertex 1.13956 0.907644 2.53081 + vertex 1.13714 0.904962 2.53139 + vertex 1.13967 0.904285 2.53026 + endloop + endfacet + facet normal 0.310668 -0.181587 0.933012 + outer loop + vertex 1.13361 0.903642 2.53249 + vertex 1.13309 0.899459 2.53185 + vertex 1.13609 0.901346 2.53122 + endloop + endfacet + facet normal 0.20794 -0.173556 0.962621 + outer loop + vertex 1.13309 0.899459 2.53185 + vertex 1.13361 0.903642 2.53249 + vertex 1.12979 0.899567 2.53258 + endloop + endfacet + facet normal 0.195121 -0.321365 0.926635 + outer loop + vertex 1.13309 0.899459 2.53185 + vertex 1.12979 0.899567 2.53258 + vertex 1.13151 0.896304 2.53109 + endloop + endfacet + facet normal 0.213476 -0.328953 0.919901 + outer loop + vertex 1.13475 0.897867 2.53089 + vertex 1.13309 0.899459 2.53185 + vertex 1.13151 0.896304 2.53109 + endloop + endfacet + facet normal 0.236609 -0.380065 0.894185 + outer loop + vertex 1.13475 0.897867 2.53089 + vertex 1.13151 0.896304 2.53109 + vertex 1.13463 0.894725 2.52959 + endloop + endfacet + facet normal 0.387093 -0.365902 0.84633 + outer loop + vertex 1.13475 0.897867 2.53089 + vertex 1.13463 0.894725 2.52959 + vertex 1.13866 0.899085 2.52963 + endloop + endfacet + facet normal 0.27733 -0.26539 0.923394 + outer loop + vertex 1.13866 0.899085 2.52963 + vertex 1.13463 0.894725 2.52959 + vertex 1.13873 0.894179 2.5282 + endloop + endfacet + facet normal 0.301644 -0.262348 0.916616 + outer loop + vertex 1.12979 0.899567 2.53258 + vertex 1.13361 0.903642 2.53249 + vertex 1.1289 0.904206 2.5342 + endloop + endfacet + facet normal 0.375589 -0.142426 0.915777 + outer loop + vertex 1.13956 0.907644 2.53081 + vertex 1.1371 0.908357 2.53193 + vertex 1.13714 0.904962 2.53139 + endloop + endfacet + facet normal 0.317993 -0.173157 0.932147 + outer loop + vertex 1.13361 0.903642 2.53249 + vertex 1.13353 0.908837 2.53348 + vertex 1.1289 0.904206 2.5342 + endloop + endfacet + facet normal 0.371765 -0.231999 0.89887 + outer loop + vertex 1.1289 0.904206 2.5342 + vertex 1.13353 0.908837 2.53348 + vertex 1.12987 0.909317 2.53512 + endloop + endfacet + facet normal 0.383367 -0.172488 0.907347 + outer loop + vertex 1.13361 0.914218 2.53447 + vertex 1.12987 0.909317 2.53512 + vertex 1.13353 0.908837 2.53348 + endloop + endfacet + facet normal 0.328097 -0.253776 0.909917 + outer loop + vertex 1.12376 0.909075 2.53756 + vertex 1.12302 0.905016 2.53669 + vertex 1.12625 0.906635 2.53598 + endloop + endfacet + facet normal 0.33367 -0.254335 0.907732 + outer loop + vertex 1.12302 0.905016 2.53669 + vertex 1.12376 0.909075 2.53756 + vertex 1.11922 0.905298 2.53817 + endloop + endfacet + facet normal 0.376135 -0.163877 0.911958 + outer loop + vertex 1.12977 0.912628 2.53583 + vertex 1.12727 0.913429 2.53701 + vertex 1.12736 0.910087 2.53637 + endloop + endfacet + facet normal 0.387864 -0.168835 0.906121 + outer loop + vertex 1.12477 0.927862 2.5406 + vertex 1.12226 0.925279 2.54119 + vertex 1.12478 0.924537 2.53998 + endloop + endfacet + facet normal 0.384686 -0.169091 0.907427 + outer loop + vertex 1.12477 0.927862 2.5406 + vertex 1.12478 0.924537 2.53998 + vertex 1.12858 0.929394 2.53927 + endloop + endfacet + facet normal 0.382256 -0.160856 0.909948 + outer loop + vertex 1.12477 0.927862 2.5406 + vertex 1.12858 0.929394 2.53927 + vertex 1.12591 0.931611 2.54079 + endloop + endfacet + facet normal 0.384853 -0.161586 0.908723 + outer loop + vertex 1.12591 0.931611 2.54079 + vertex 1.12224 0.928627 2.54181 + vertex 1.12477 0.927862 2.5406 + endloop + endfacet + facet normal 0.381699 -0.156982 0.910858 + outer loop + vertex 1.12322 0.933842 2.5423 + vertex 1.12224 0.928627 2.54181 + vertex 1.12591 0.931611 2.54079 + endloop + endfacet + facet normal 0.382797 -0.155518 0.910649 + outer loop + vertex 1.12698 0.935338 2.54097 + vertex 1.12322 0.933842 2.5423 + vertex 1.12591 0.931611 2.54079 + endloop + endfacet + facet normal 0.367464 -0.151443 0.917625 + outer loop + vertex 1.1296 0.934659 2.53981 + vertex 1.12698 0.935338 2.54097 + vertex 1.12591 0.931611 2.54079 + endloop + endfacet + facet normal 0.366358 -0.155344 0.917415 + outer loop + vertex 1.12941 0.937951 2.54044 + vertex 1.12698 0.935338 2.54097 + vertex 1.1296 0.934659 2.53981 + endloop + endfacet + facet normal 0.324679 -0.16048 0.93211 + outer loop + vertex 1.12941 0.937951 2.54044 + vertex 1.1296 0.934659 2.53981 + vertex 1.13339 0.939467 2.53932 + endloop + endfacet + facet normal 0.324647 -0.160374 0.93214 + outer loop + vertex 1.12941 0.937951 2.54044 + vertex 1.13339 0.939467 2.53932 + vertex 1.13045 0.941697 2.54073 + endloop + endfacet + facet normal 0.366189 -0.170597 0.914769 + outer loop + vertex 1.13045 0.941697 2.54073 + vertex 1.12676 0.938528 2.54161 + vertex 1.12941 0.937951 2.54044 + endloop + endfacet + facet normal 0.345544 -0.178024 0.921361 + outer loop + vertex 1.13339 0.939467 2.53932 + vertex 1.1296 0.934659 2.53981 + vertex 1.13345 0.934279 2.5383 + endloop + endfacet + facet normal 0.347942 -0.16195 0.923422 + outer loop + vertex 1.12858 0.929394 2.53927 + vertex 1.13345 0.934279 2.5383 + vertex 1.1296 0.934659 2.53981 + endloop + endfacet + facet normal 0.371685 -0.188499 0.90902 + outer loop + vertex 1.13329 0.928939 2.53726 + vertex 1.13345 0.934279 2.5383 + vertex 1.12858 0.929394 2.53927 + endloop + endfacet + facet normal 0.374402 -0.170881 0.911385 + outer loop + vertex 1.1284 0.924054 2.53835 + vertex 1.13329 0.928939 2.53726 + vertex 1.12858 0.929394 2.53927 + endloop + endfacet + facet normal 0.3844 -0.182308 0.904986 + outer loop + vertex 1.13198 0.923576 2.53673 + vertex 1.13329 0.928939 2.53726 + vertex 1.1284 0.924054 2.53835 + endloop + endfacet + facet normal 0.388513 -0.159854 0.907471 + outer loop + vertex 1.13198 0.923576 2.53673 + vertex 1.1284 0.924054 2.53835 + vertex 1.12825 0.918708 2.53747 + endloop + endfacet + facet normal 0.369264 -0.158388 0.915728 + outer loop + vertex 1.12941 0.937951 2.54044 + vertex 1.12676 0.938528 2.54161 + vertex 1.12698 0.935338 2.54097 + endloop + endfacet + facet normal 0.383041 -0.15635 0.910403 + outer loop + vertex 1.12698 0.935338 2.54097 + vertex 1.12676 0.938528 2.54161 + vertex 1.12322 0.933842 2.5423 + endloop + endfacet + facet normal 0.383677 -0.156882 0.910044 + outer loop + vertex 1.12676 0.938528 2.54161 + vertex 1.12317 0.939002 2.54321 + vertex 1.12322 0.933842 2.5423 + endloop + endfacet + facet normal 0.382597 -0.162981 0.909426 + outer loop + vertex 1.12676 0.938528 2.54161 + vertex 1.12731 0.943132 2.54221 + vertex 1.12317 0.939002 2.54321 + endloop + endfacet + facet normal 0.378035 -0.157707 0.91226 + outer loop + vertex 1.12317 0.939002 2.54321 + vertex 1.12731 0.943132 2.54221 + vertex 1.12333 0.944342 2.54406 + endloop + endfacet + facet normal 0.390569 -0.157263 0.907041 + outer loop + vertex 1.12333 0.944342 2.54406 + vertex 1.11963 0.939609 2.54484 + vertex 1.12317 0.939002 2.54321 + endloop + endfacet + facet normal 0.389702 -0.161375 0.906692 + outer loop + vertex 1.11867 0.934422 2.54433 + vertex 1.12317 0.939002 2.54321 + vertex 1.11963 0.939609 2.54484 + endloop + endfacet + facet normal 0.392087 -0.161714 0.905603 + outer loop + vertex 1.11867 0.934422 2.54433 + vertex 1.11963 0.939609 2.54484 + vertex 1.11596 0.936636 2.54589 + endloop + endfacet + facet normal 0.389427 -0.165312 0.9061 + outer loop + vertex 1.11486 0.932935 2.5457 + vertex 1.11867 0.934422 2.54433 + vertex 1.11596 0.936636 2.54589 + endloop + endfacet + facet normal 0.40002 -0.168209 0.900938 + outer loop + vertex 1.11596 0.936636 2.54589 + vertex 1.11225 0.93371 2.547 + vertex 1.11486 0.932935 2.5457 + endloop + endfacet + facet normal 0.400303 -0.167324 0.900977 + outer loop + vertex 1.11486 0.932935 2.5457 + vertex 1.11225 0.93371 2.547 + vertex 1.11244 0.930366 2.54629 + endloop + endfacet + facet normal 0.394511 -0.161013 0.904674 + outer loop + vertex 1.11486 0.932935 2.5457 + vertex 1.11244 0.930366 2.54629 + vertex 1.11511 0.929769 2.54502 + endloop + endfacet + facet normal 0.394776 -0.160121 0.904717 + outer loop + vertex 1.11334 0.939003 2.54746 + vertex 1.11225 0.93371 2.547 + vertex 1.11596 0.936636 2.54589 + endloop + endfacet + facet normal 0.393575 -0.161622 0.904973 + outer loop + vertex 1.11708 0.940334 2.54607 + vertex 1.11334 0.939003 2.54746 + vertex 1.11596 0.936636 2.54589 + endloop + endfacet + facet normal 0.389887 -0.147025 0.90905 + outer loop + vertex 1.11708 0.940334 2.54607 + vertex 1.11684 0.943564 2.54669 + vertex 1.11334 0.939003 2.54746 + endloop + endfacet + facet normal 0.388236 -0.145601 0.909985 + outer loop + vertex 1.11684 0.943564 2.54669 + vertex 1.11335 0.94418 2.54828 + vertex 1.11334 0.939003 2.54746 + endloop + endfacet + facet normal 0.401714 -0.144723 0.904257 + outer loop + vertex 1.11334 0.939003 2.54746 + vertex 1.11335 0.94418 2.54828 + vertex 1.10948 0.940184 2.54936 + endloop + endfacet + facet normal 0.400196 -0.14952 0.90415 + outer loop + vertex 1.10839 0.934541 2.54891 + vertex 1.11334 0.939003 2.54746 + vertex 1.10948 0.940184 2.54936 + endloop + endfacet + facet normal 0.396906 -0.139252 0.907235 + outer loop + vertex 1.10948 0.940184 2.54936 + vertex 1.11335 0.94418 2.54828 + vertex 1.10987 0.944801 2.5499 + endloop + endfacet + facet normal 0.390105 -0.136572 0.910586 + outer loop + vertex 1.11684 0.943564 2.54669 + vertex 1.11724 0.948196 2.54722 + vertex 1.11335 0.94418 2.54828 + endloop + endfacet + facet normal 0.39202 -0.138731 0.909436 + outer loop + vertex 1.11335 0.94418 2.54828 + vertex 1.11724 0.948196 2.54722 + vertex 1.11332 0.949386 2.54909 + endloop + endfacet + facet normal 0.397089 -0.138369 0.90729 + outer loop + vertex 1.11332 0.949386 2.54909 + vertex 1.10987 0.944801 2.5499 + vertex 1.11335 0.94418 2.54828 + endloop + endfacet + facet normal 0.398311 -0.139413 0.906594 + outer loop + vertex 1.10955 0.948014 2.55054 + vertex 1.10987 0.944801 2.5499 + vertex 1.11332 0.949386 2.54909 + endloop + endfacet + facet normal 0.408292 -0.137578 0.902424 + outer loop + vertex 1.10955 0.948014 2.55054 + vertex 1.10722 0.945439 2.5512 + vertex 1.10987 0.944801 2.5499 + endloop + endfacet + facet normal 0.413391 -0.142997 0.899255 + outer loop + vertex 1.10955 0.948014 2.55054 + vertex 1.10688 0.948699 2.55187 + vertex 1.10722 0.945439 2.5512 + endloop + endfacet + facet normal 0.386891 -0.147475 0.910256 + outer loop + vertex 1.11949 0.942928 2.54547 + vertex 1.11684 0.943564 2.54669 + vertex 1.11708 0.940334 2.54607 + endloop + endfacet + facet normal 0.393616 -0.154689 0.906166 + outer loop + vertex 1.11949 0.942928 2.54547 + vertex 1.11708 0.940334 2.54607 + vertex 1.11963 0.939609 2.54484 + endloop + endfacet + facet normal 0.3886 -0.140948 0.910562 + outer loop + vertex 1.12043 0.946762 2.54566 + vertex 1.11684 0.943564 2.54669 + vertex 1.11949 0.942928 2.54547 + endloop + endfacet + facet normal 0.384252 -0.13998 0.912555 + outer loop + vertex 1.11949 0.942928 2.54547 + vertex 1.12333 0.944342 2.54406 + vertex 1.12043 0.946762 2.54566 + endloop + endfacet + facet normal 0.385159 -0.136387 0.912716 + outer loop + vertex 1.11724 0.948196 2.54722 + vertex 1.11684 0.943564 2.54669 + vertex 1.12043 0.946762 2.54566 + endloop + endfacet + facet normal 0.391668 -0.161093 0.905895 + outer loop + vertex 1.11963 0.939609 2.54484 + vertex 1.11708 0.940334 2.54607 + vertex 1.11596 0.936636 2.54589 + endloop + endfacet + facet normal 0.388358 -0.155327 0.908324 + outer loop + vertex 1.11949 0.942928 2.54547 + vertex 1.11963 0.939609 2.54484 + vertex 1.12333 0.944342 2.54406 + endloop + endfacet + facet normal 0.372183 -0.17563 0.911391 + outer loop + vertex 1.12731 0.943132 2.54221 + vertex 1.12879 0.948806 2.5427 + vertex 1.12333 0.944342 2.54406 + endloop + endfacet + facet normal 0.349985 -0.144149 0.925598 + outer loop + vertex 1.12333 0.944342 2.54406 + vertex 1.12879 0.948806 2.5427 + vertex 1.12451 0.950034 2.54451 + endloop + endfacet + facet normal 0.377531 -0.148946 0.913939 + outer loop + vertex 1.12333 0.944342 2.54406 + vertex 1.12451 0.950034 2.54451 + vertex 1.12043 0.946762 2.54566 + endloop + endfacet + facet normal 0.365694 -0.131572 0.921388 + outer loop + vertex 1.12043 0.946762 2.54566 + vertex 1.12451 0.950034 2.54451 + vertex 1.12119 0.951456 2.54603 + endloop + endfacet + facet normal 0.386115 -0.134177 0.91264 + outer loop + vertex 1.12119 0.951456 2.54603 + vertex 1.11724 0.948196 2.54722 + vertex 1.12043 0.946762 2.54566 + endloop + endfacet + facet normal 0.387636 -0.136372 0.911669 + outer loop + vertex 1.11837 0.953832 2.54758 + vertex 1.11724 0.948196 2.54722 + vertex 1.12119 0.951456 2.54603 + endloop + endfacet + facet normal 0.38694 -0.1373 0.911826 + outer loop + vertex 1.1221 0.95525 2.54621 + vertex 1.11837 0.953832 2.54758 + vertex 1.12119 0.951456 2.54603 + endloop + endfacet + facet normal 0.348248 -0.12881 0.92851 + outer loop + vertex 1.12485 0.954652 2.5451 + vertex 1.1221 0.95525 2.54621 + vertex 1.12119 0.951456 2.54603 + endloop + endfacet + facet normal 0.393554 -0.161281 0.905044 + outer loop + vertex 1.1221 0.95525 2.54621 + vertex 1.12205 0.958517 2.54682 + vertex 1.11837 0.953832 2.54758 + endloop + endfacet + facet normal 0.384505 -0.153308 0.910303 + outer loop + vertex 1.12205 0.958517 2.54682 + vertex 1.11856 0.959114 2.54839 + vertex 1.11837 0.953832 2.54758 + endloop + endfacet + facet normal 0.376059 -0.192325 0.906416 + outer loop + vertex 1.12205 0.958517 2.54682 + vertex 1.12342 0.963747 2.54736 + vertex 1.11856 0.959114 2.54839 + endloop + endfacet + facet normal 0.36023 -0.144559 0.921595 + outer loop + vertex 1.12451 0.950034 2.54451 + vertex 1.12485 0.954652 2.5451 + vertex 1.12119 0.951456 2.54603 + endloop + endfacet + facet normal 0.312533 -0.143264 0.939041 + outer loop + vertex 1.12451 0.950034 2.54451 + vertex 1.12886 0.954192 2.54369 + vertex 1.12485 0.954652 2.5451 + endloop + endfacet + facet normal 0.340297 -0.175299 0.923833 + outer loop + vertex 1.12879 0.948806 2.5427 + vertex 1.12886 0.954192 2.54369 + vertex 1.12451 0.950034 2.54451 + endloop + endfacet + facet normal 0.359365 -0.161417 0.919131 + outer loop + vertex 1.12731 0.943132 2.54221 + vertex 1.12676 0.938528 2.54161 + vertex 1.13045 0.941697 2.54073 + endloop + endfacet + facet normal 0.35327 -0.174683 0.919068 + outer loop + vertex 1.13148 0.946226 2.54119 + vertex 1.12731 0.943132 2.54221 + vertex 1.13045 0.941697 2.54073 + endloop + endfacet + facet normal 0.302264 -0.165095 0.938819 + outer loop + vertex 1.13045 0.941697 2.54073 + vertex 1.13457 0.944804 2.53995 + vertex 1.13148 0.946226 2.54119 + endloop + endfacet + facet normal 0.378039 -0.166454 0.910703 + outer loop + vertex 1.12858 0.929394 2.53927 + vertex 1.1296 0.934659 2.53981 + vertex 1.12591 0.931611 2.54079 + endloop + endfacet + facet normal 0.393434 -0.161116 0.905125 + outer loop + vertex 1.11846 0.923951 2.54258 + vertex 1.11715 0.918515 2.54218 + vertex 1.12101 0.921539 2.54104 + endloop + endfacet + facet normal 0.383926 -0.164451 0.908602 + outer loop + vertex 1.12477 0.927862 2.5406 + vertex 1.12224 0.928627 2.54181 + vertex 1.12226 0.925279 2.54119 + endloop + endfacet + facet normal 0.388497 -0.162017 0.907094 + outer loop + vertex 1.11486 0.932935 2.5457 + vertex 1.11511 0.929769 2.54502 + vertex 1.11867 0.934422 2.54433 + endloop + endfacet + facet normal 0.367028 -0.234939 0.900052 + outer loop + vertex 1.10896 0.908878 2.54349 + vertex 1.11342 0.913521 2.54288 + vertex 1.1087 0.91365 2.54484 + endloop + endfacet + facet normal 0.391747 -0.190171 0.900205 + outer loop + vertex 1.10925 0.917807 2.54548 + vertex 1.10667 0.915334 2.54608 + vertex 1.1087 0.91365 2.54484 + endloop + endfacet + facet normal 0.370027 -0.164084 0.914416 + outer loop + vertex 1.10925 0.917807 2.54548 + vertex 1.10678 0.918616 2.54662 + vertex 1.10667 0.915334 2.54608 + endloop + endfacet + facet normal 0.347477 -0.163805 0.92327 + outer loop + vertex 1.10678 0.918616 2.54662 + vertex 1.10738 0.923272 2.54722 + vertex 1.10308 0.918902 2.54807 + endloop + endfacet + facet normal 0.392961 -0.157549 0.905958 + outer loop + vertex 1.11318 0.919238 2.54403 + vertex 1.1146 0.925139 2.54444 + vertex 1.11051 0.92185 2.54564 + endloop + endfacet + facet normal 0.397414 -0.170877 0.901589 + outer loop + vertex 1.1086 0.92896 2.54776 + vertex 1.10738 0.923272 2.54722 + vertex 1.11147 0.926585 2.54605 + endloop + endfacet + facet normal 0.383344 -0.168474 0.90811 + outer loop + vertex 1.10738 0.923272 2.54722 + vertex 1.1086 0.92896 2.54776 + vertex 1.10335 0.924301 2.54911 + endloop + endfacet + facet normal 0.375644 -0.194843 0.906051 + outer loop + vertex 1.10308 0.918902 2.54807 + vertex 1.10738 0.923272 2.54722 + vertex 1.10335 0.924301 2.54911 + endloop + endfacet + facet normal 0.410042 -0.16264 0.897448 + outer loop + vertex 1.11225 0.93371 2.547 + vertex 1.11334 0.939003 2.54746 + vertex 1.10839 0.934541 2.54891 + endloop + endfacet + facet normal 0.404237 -0.19631 0.893339 + outer loop + vertex 1.10335 0.924301 2.54911 + vertex 1.1086 0.92896 2.54776 + vertex 1.10475 0.929767 2.54968 + endloop + endfacet + facet normal 0.395569 -0.177406 0.90114 + outer loop + vertex 1.10461 0.933132 2.55041 + vertex 1.10218 0.930507 2.55096 + vertex 1.10475 0.929767 2.54968 + endloop + endfacet + facet normal 0.383798 -0.16495 0.908565 + outer loop + vertex 1.10461 0.933132 2.55041 + vertex 1.10192 0.933656 2.55164 + vertex 1.10218 0.930507 2.55096 + endloop + endfacet + facet normal 0.334386 -0.172907 0.926439 + outer loop + vertex 1.10218 0.930507 2.55096 + vertex 1.10192 0.933656 2.55164 + vertex 1.09824 0.928847 2.55207 + endloop + endfacet + facet normal 0.338185 -0.184315 0.922853 + outer loop + vertex 1.10218 0.930507 2.55096 + vertex 1.09824 0.928847 2.55207 + vertex 1.10094 0.926789 2.55067 + endloop + endfacet + facet normal 0.388509 -0.199327 0.899628 + outer loop + vertex 1.10475 0.929767 2.54968 + vertex 1.10218 0.930507 2.55096 + vertex 1.10094 0.926789 2.55067 + endloop + endfacet + facet normal 0.383801 -0.192113 0.903211 + outer loop + vertex 1.10335 0.924301 2.54911 + vertex 1.10475 0.929767 2.54968 + vertex 1.10094 0.926789 2.55067 + endloop + endfacet + facet normal 0.366824 -0.21044 0.906176 + outer loop + vertex 1.09943 0.92298 2.5504 + vertex 1.10335 0.924301 2.54911 + vertex 1.10094 0.926789 2.55067 + endloop + endfacet + facet normal 0.318215 -0.192809 0.928205 + outer loop + vertex 1.10094 0.926789 2.55067 + vertex 1.09703 0.923848 2.5514 + vertex 1.09943 0.92298 2.5504 + endloop + endfacet + facet normal 0.310632 -0.211948 0.926599 + outer loop + vertex 1.09943 0.92298 2.5504 + vertex 1.09703 0.923848 2.5514 + vertex 1.09668 0.92064 2.55078 + endloop + endfacet + facet normal 0.326533 -0.232377 0.916175 + outer loop + vertex 1.09943 0.92298 2.5504 + vertex 1.09668 0.92064 2.55078 + vertex 1.09862 0.91892 2.54965 + endloop + endfacet + facet normal 0.324755 -0.202586 0.923847 + outer loop + vertex 1.09824 0.928847 2.55207 + vertex 1.09703 0.923848 2.5514 + vertex 1.10094 0.926789 2.55067 + endloop + endfacet + facet normal 0.373054 -0.23808 0.896743 + outer loop + vertex 1.09943 0.92298 2.5504 + vertex 1.09862 0.91892 2.54965 + vertex 1.10335 0.924301 2.54911 + endloop + endfacet + facet normal 0.328236 -0.195962 0.924045 + outer loop + vertex 1.10335 0.924301 2.54911 + vertex 1.09862 0.91892 2.54965 + vertex 1.10308 0.918902 2.54807 + endloop + endfacet + facet normal 0.325497 -0.231568 0.916749 + outer loop + vertex 1.0987 0.913964 2.54838 + vertex 1.10308 0.918902 2.54807 + vertex 1.09862 0.91892 2.54965 + endloop + endfacet + facet normal 0.266209 -0.236956 0.934336 + outer loop + vertex 1.09862 0.91892 2.54965 + vertex 1.09384 0.913763 2.54971 + vertex 1.0987 0.913964 2.54838 + endloop + endfacet + facet normal 0.316199 -0.283684 0.905285 + outer loop + vertex 1.09488 0.917717 2.55059 + vertex 1.09384 0.913763 2.54971 + vertex 1.09862 0.91892 2.54965 + endloop + endfacet + facet normal 0.309095 -0.252553 0.916884 + outer loop + vertex 1.09862 0.91892 2.54965 + vertex 1.09668 0.92064 2.55078 + vertex 1.09488 0.917717 2.55059 + endloop + endfacet + facet normal 0.26601 -0.227288 0.936792 + outer loop + vertex 1.09668 0.92064 2.55078 + vertex 1.09306 0.919486 2.55153 + vertex 1.09488 0.917717 2.55059 + endloop + endfacet + facet normal 0.255115 -0.238557 0.93702 + outer loop + vertex 1.09488 0.917717 2.55059 + vertex 1.09306 0.919486 2.55153 + vertex 1.09206 0.915783 2.55086 + endloop + endfacet + facet normal 0.22611 -0.232332 0.94599 + outer loop + vertex 1.09206 0.915783 2.55086 + vertex 1.09306 0.919486 2.55153 + vertex 1.08884 0.915318 2.55152 + endloop + endfacet + facet normal 0.229797 -0.275474 0.933439 + outer loop + vertex 1.09206 0.915783 2.55086 + vertex 1.08884 0.915318 2.55152 + vertex 1.08985 0.91291 2.55056 + endloop + endfacet + facet normal 0.258635 -0.29617 0.919451 + outer loop + vertex 1.09384 0.913763 2.54971 + vertex 1.09206 0.915783 2.55086 + vertex 1.08985 0.91291 2.55056 + endloop + endfacet + facet normal 0.266978 -0.360746 0.893636 + outer loop + vertex 1.08985 0.91291 2.55056 + vertex 1.08884 0.909001 2.54928 + vertex 1.09384 0.913763 2.54971 + endloop + endfacet + facet normal 0.218279 -0.312423 0.924525 + outer loop + vertex 1.09384 0.913763 2.54971 + vertex 1.08884 0.909001 2.54928 + vertex 1.09426 0.908718 2.5479 + endloop + endfacet + facet normal 0.263731 -0.305196 0.915042 + outer loop + vertex 1.09426 0.908718 2.5479 + vertex 1.0987 0.913964 2.54838 + vertex 1.09384 0.913763 2.54971 + endloop + endfacet + facet normal 0.200943 -0.254903 0.945857 + outer loop + vertex 1.09926 0.909917 2.54717 + vertex 1.0987 0.913964 2.54838 + vertex 1.09426 0.908718 2.5479 + endloop + endfacet + facet normal 0.241868 -0.357041 0.902232 + outer loop + vertex 1.08985 0.91291 2.55056 + vertex 1.08612 0.911276 2.55091 + vertex 1.08884 0.909001 2.54928 + endloop + endfacet + facet normal 0.215566 -0.38503 0.897376 + outer loop + vertex 1.08366 0.907659 2.54995 + vertex 1.08884 0.909001 2.54928 + vertex 1.08612 0.911276 2.55091 + endloop + endfacet + facet normal 0.242308 -0.399661 0.884057 + outer loop + vertex 1.08243 0.909842 2.55127 + vertex 1.08366 0.907659 2.54995 + vertex 1.08612 0.911276 2.55091 + endloop + endfacet + facet normal 0.204993 -0.290928 0.934526 + outer loop + vertex 1.08612 0.911276 2.55091 + vertex 1.08379 0.913853 2.55222 + vertex 1.08243 0.909842 2.55127 + endloop + endfacet + facet normal 0.182308 -0.284818 0.941086 + outer loop + vertex 1.08243 0.909842 2.55127 + vertex 1.08379 0.913853 2.55222 + vertex 1.07912 0.909843 2.55191 + endloop + endfacet + facet normal 0.1761 -0.377417 0.909145 + outer loop + vertex 1.08243 0.909842 2.55127 + vertex 1.07912 0.909843 2.55191 + vertex 1.08021 0.907461 2.55071 + endloop + endfacet + facet normal 0.188601 -0.29188 0.937676 + outer loop + vertex 1.08379 0.913853 2.55222 + vertex 1.07859 0.913746 2.55324 + vertex 1.07912 0.909843 2.55191 + endloop + endfacet + facet normal 0.152727 -0.298309 0.942171 + outer loop + vertex 1.07912 0.909843 2.55191 + vertex 1.07859 0.913746 2.55324 + vertex 1.07399 0.908813 2.55242 + endloop + endfacet + facet normal 0.17151 -0.314379 0.933676 + outer loop + vertex 1.07399 0.908813 2.55242 + vertex 1.07859 0.913746 2.55324 + vertex 1.07342 0.913379 2.55406 + endloop + endfacet + facet normal 0.147952 -0.318309 0.93637 + outer loop + vertex 1.07399 0.908813 2.55242 + vertex 1.07342 0.913379 2.55406 + vertex 1.06888 0.909016 2.5533 + endloop + endfacet + facet normal 0.137658 -0.415964 0.898902 + outer loop + vertex 1.07399 0.908813 2.55242 + vertex 1.06888 0.909016 2.5533 + vertex 1.06966 0.905383 2.5515 + endloop + endfacet + facet normal 0.131366 -0.409112 0.902979 + outer loop + vertex 1.07305 0.90521 2.55092 + vertex 1.07399 0.908813 2.55242 + vertex 1.06966 0.905383 2.5515 + endloop + endfacet + facet normal 0.108527 -0.56824 0.815675 + outer loop + vertex 1.07305 0.90521 2.55092 + vertex 1.06966 0.905383 2.5515 + vertex 1.07111 0.903173 2.54976 + endloop + endfacet + facet normal 0.183233 -0.612496 0.768943 + outer loop + vertex 1.07493 0.903379 2.54902 + vertex 1.07305 0.90521 2.55092 + vertex 1.07111 0.903173 2.54976 + endloop + endfacet + facet normal 0.110781 -0.422142 0.899735 + outer loop + vertex 1.06966 0.905383 2.5515 + vertex 1.06888 0.909016 2.5533 + vertex 1.06519 0.905249 2.55198 + endloop + endfacet + facet normal 0.122601 -0.431615 0.893688 + outer loop + vertex 1.06519 0.905249 2.55198 + vertex 1.06888 0.909016 2.5533 + vertex 1.06392 0.90884 2.55389 + endloop + endfacet + facet normal 0.170612 -0.271202 0.947281 + outer loop + vertex 1.07859 0.913746 2.55324 + vertex 1.07833 0.918637 2.55468 + vertex 1.07342 0.913379 2.55406 + endloop + endfacet + facet normal 0.179687 -0.2792 0.943271 + outer loop + vertex 1.07342 0.913379 2.55406 + vertex 1.07833 0.918637 2.55468 + vertex 1.0731 0.917284 2.55528 + endloop + endfacet + facet normal 0.151135 -0.282749 0.947212 + outer loop + vertex 1.0731 0.917284 2.55528 + vertex 1.06831 0.913391 2.55488 + vertex 1.07342 0.913379 2.55406 + endloop + endfacet + facet normal 0.149211 -0.319513 0.935761 + outer loop + vertex 1.06888 0.909016 2.5533 + vertex 1.07342 0.913379 2.55406 + vertex 1.06831 0.913391 2.55488 + endloop + endfacet + facet normal 0.124104 -0.323614 0.938015 + outer loop + vertex 1.06888 0.909016 2.5533 + vertex 1.06831 0.913391 2.55488 + vertex 1.06392 0.90884 2.55389 + endloop + endfacet + facet normal 0.134586 -0.332705 0.933378 + outer loop + vertex 1.06392 0.90884 2.55389 + vertex 1.06831 0.913391 2.55488 + vertex 1.06319 0.912352 2.55525 + endloop + endfacet + facet normal 0.126513 -0.287248 0.949465 + outer loop + vertex 1.06319 0.912352 2.55525 + vertex 1.06831 0.913391 2.55488 + vertex 1.06622 0.916088 2.55598 + endloop + endfacet + facet normal 0.120816 -0.283017 0.951475 + outer loop + vertex 1.06253 0.91494 2.5561 + vertex 1.06319 0.912352 2.55525 + vertex 1.06622 0.916088 2.55598 + endloop + endfacet + facet normal 0.114826 -0.263025 0.957932 + outer loop + vertex 1.06622 0.916088 2.55598 + vertex 1.06412 0.918903 2.557 + vertex 1.06253 0.91494 2.5561 + endloop + endfacet + facet normal 0.120673 -0.258825 0.958357 + outer loop + vertex 1.0693 0.919949 2.55663 + vertex 1.06412 0.918903 2.557 + vertex 1.06622 0.916088 2.55598 + endloop + endfacet + facet normal 0.13004 -0.265761 0.955228 + outer loop + vertex 1.06991 0.9173 2.55581 + vertex 1.0693 0.919949 2.55663 + vertex 1.06622 0.916088 2.55598 + endloop + endfacet + facet normal 0.144584 -0.262047 0.954163 + outer loop + vertex 1.07253 0.919925 2.55613 + vertex 1.0693 0.919949 2.55663 + vertex 1.06991 0.9173 2.55581 + endloop + endfacet + facet normal 0.15678 -0.273554 0.948993 + outer loop + vertex 1.0731 0.917284 2.55528 + vertex 1.07253 0.919925 2.55613 + vertex 1.06991 0.9173 2.55581 + endloop + endfacet + facet normal 0.169673 -0.270328 0.947699 + outer loop + vertex 1.07253 0.919925 2.55613 + vertex 1.0731 0.917284 2.55528 + vertex 1.07616 0.921281 2.55587 + endloop + endfacet + facet normal 0.169054 -0.268551 0.948315 + outer loop + vertex 1.07616 0.921281 2.55587 + vertex 1.07403 0.923922 2.557 + vertex 1.07253 0.919925 2.55613 + endloop + endfacet + facet normal 0.176461 -0.262695 0.948606 + outer loop + vertex 1.07905 0.925295 2.55645 + vertex 1.07403 0.923922 2.557 + vertex 1.07616 0.921281 2.55587 + endloop + endfacet + facet normal 0.187752 -0.270209 0.944318 + outer loop + vertex 1.07991 0.922856 2.55558 + vertex 1.07905 0.925295 2.55645 + vertex 1.07616 0.921281 2.55587 + endloop + endfacet + facet normal 0.187753 -0.270212 0.944317 + outer loop + vertex 1.07991 0.922856 2.55558 + vertex 1.07616 0.921281 2.55587 + vertex 1.07833 0.918637 2.55468 + endloop + endfacet + facet normal 0.214689 -0.278542 0.936121 + outer loop + vertex 1.07991 0.922856 2.55558 + vertex 1.07833 0.918637 2.55468 + vertex 1.08382 0.923642 2.55491 + endloop + endfacet + facet normal 0.214797 -0.279289 0.935874 + outer loop + vertex 1.08382 0.923642 2.55491 + vertex 1.08225 0.925681 2.55588 + vertex 1.07991 0.922856 2.55558 + endloop + endfacet + facet normal 0.198509 -0.261193 0.944654 + outer loop + vertex 1.08382 0.923642 2.55491 + vertex 1.07833 0.918637 2.55468 + vertex 1.08357 0.918715 2.5536 + endloop + endfacet + facet normal 0.234834 -0.260826 0.936388 + outer loop + vertex 1.08357 0.918715 2.5536 + vertex 1.08863 0.923797 2.55375 + vertex 1.08382 0.923642 2.55491 + endloop + endfacet + facet normal 0.235047 -0.254225 0.938149 + outer loop + vertex 1.08894 0.928661 2.55499 + vertex 1.08382 0.923642 2.55491 + vertex 1.08863 0.923797 2.55375 + endloop + endfacet + facet normal 0.284723 -0.253807 0.9244 + outer loop + vertex 1.08863 0.923797 2.55375 + vertex 1.09358 0.928863 2.55362 + vertex 1.08894 0.928661 2.55499 + endloop + endfacet + facet normal 0.285391 -0.232435 0.929799 + outer loop + vertex 1.09377 0.93387 2.55481 + vertex 1.08894 0.928661 2.55499 + vertex 1.09358 0.928863 2.55362 + endloop + endfacet + facet normal 0.342948 -0.230063 0.910746 + outer loop + vertex 1.09358 0.928863 2.55362 + vertex 1.09814 0.933866 2.55316 + vertex 1.09377 0.93387 2.55481 + endloop + endfacet + facet normal 0.308207 -0.196557 0.930792 + outer loop + vertex 1.09824 0.928847 2.55207 + vertex 1.09814 0.933866 2.55316 + vertex 1.09358 0.928863 2.55362 + endloop + endfacet + facet normal 0.306177 -0.225128 0.924972 + outer loop + vertex 1.09324 0.924001 2.55255 + vertex 1.09824 0.928847 2.55207 + vertex 1.09358 0.928863 2.55362 + endloop + endfacet + facet normal 0.276897 -0.193283 0.941259 + outer loop + vertex 1.09703 0.923848 2.5514 + vertex 1.09824 0.928847 2.55207 + vertex 1.09324 0.924001 2.55255 + endloop + endfacet + facet normal 0.274144 -0.221309 0.935878 + outer loop + vertex 1.09703 0.923848 2.5514 + vertex 1.09324 0.924001 2.55255 + vertex 1.09306 0.919486 2.55153 + endloop + endfacet + facet normal 0.234296 -0.222156 0.946442 + outer loop + vertex 1.09306 0.919486 2.55153 + vertex 1.09324 0.924001 2.55255 + vertex 1.08851 0.919133 2.55257 + endloop + endfacet + facet normal 0.255238 -0.242553 0.93596 + outer loop + vertex 1.08851 0.919133 2.55257 + vertex 1.09324 0.924001 2.55255 + vertex 1.08863 0.923797 2.55375 + endloop + endfacet + facet normal 0.328767 -0.273531 0.903932 + outer loop + vertex 1.09007 0.932561 2.55576 + vertex 1.08894 0.928661 2.55499 + vertex 1.09377 0.93387 2.55481 + endloop + endfacet + facet normal 0.323693 -0.253721 0.911509 + outer loop + vertex 1.09377 0.93387 2.55481 + vertex 1.09187 0.935521 2.55594 + vertex 1.09007 0.932561 2.55576 + endloop + endfacet + facet normal 0.26545 -0.220002 0.938688 + outer loop + vertex 1.09187 0.935521 2.55594 + vertex 1.08813 0.934202 2.55669 + vertex 1.09007 0.932561 2.55576 + endloop + endfacet + facet normal 0.253114 -0.234508 0.938583 + outer loop + vertex 1.09007 0.932561 2.55576 + vertex 1.08813 0.934202 2.55669 + vertex 1.08718 0.930444 2.55601 + endloop + endfacet + facet normal 0.220102 -0.227913 0.948478 + outer loop + vertex 1.08718 0.930444 2.55601 + vertex 1.08813 0.934202 2.55669 + vertex 1.08341 0.92938 2.55663 + endloop + endfacet + facet normal 0.225338 -0.250516 0.941522 + outer loop + vertex 1.08718 0.930444 2.55601 + vertex 1.08341 0.92938 2.55663 + vertex 1.08513 0.927517 2.55572 + endloop + endfacet + facet normal 0.259804 -0.273129 0.92623 + outer loop + vertex 1.08894 0.928661 2.55499 + vertex 1.08718 0.930444 2.55601 + vertex 1.08513 0.927517 2.55572 + endloop + endfacet + facet normal 0.21696 -0.258208 0.941412 + outer loop + vertex 1.08513 0.927517 2.55572 + vertex 1.08341 0.92938 2.55663 + vertex 1.08225 0.925681 2.55588 + endloop + endfacet + facet normal 0.225038 -0.271363 0.935799 + outer loop + vertex 1.08513 0.927517 2.55572 + vertex 1.08225 0.925681 2.55588 + vertex 1.08382 0.923642 2.55491 + endloop + endfacet + facet normal 0.23842 -0.245748 0.939555 + outer loop + vertex 1.08813 0.934202 2.55669 + vertex 1.08347 0.933889 2.55779 + vertex 1.08341 0.92938 2.55663 + endloop + endfacet + facet normal 0.238135 -0.214399 0.947272 + outer loop + vertex 1.08813 0.934202 2.55669 + vertex 1.0883 0.938864 2.5577 + vertex 1.08347 0.933889 2.55779 + endloop + endfacet + facet normal 0.264351 -0.240085 0.934065 + outer loop + vertex 1.08347 0.933889 2.55779 + vertex 1.0883 0.938864 2.5577 + vertex 1.0837 0.938645 2.55895 + endloop + endfacet + facet normal 0.264876 -0.206464 0.94192 + outer loop + vertex 1.0883 0.938864 2.5577 + vertex 1.08862 0.943814 2.5587 + vertex 1.0837 0.938645 2.55895 + endloop + endfacet + facet normal 0.301395 -0.242201 0.922225 + outer loop + vertex 1.0837 0.938645 2.55895 + vertex 1.08862 0.943814 2.5587 + vertex 1.08406 0.943565 2.56013 + endloop + endfacet + facet normal 0.25034 -0.242097 0.9374 + outer loop + vertex 1.08406 0.943565 2.56013 + vertex 1.07898 0.93842 2.56015 + vertex 1.0837 0.938645 2.55895 + endloop + endfacet + facet normal 0.249807 -0.267927 0.93049 + outer loop + vertex 1.07864 0.933572 2.55885 + vertex 1.0837 0.938645 2.55895 + vertex 1.07898 0.93842 2.56015 + endloop + endfacet + facet normal 0.22222 -0.240678 0.944824 + outer loop + vertex 1.08347 0.933889 2.55779 + vertex 1.0837 0.938645 2.55895 + vertex 1.07864 0.933572 2.55885 + endloop + endfacet + facet normal 0.222372 -0.263608 0.938649 + outer loop + vertex 1.07867 0.929024 2.55756 + vertex 1.08347 0.933889 2.55779 + vertex 1.07864 0.933572 2.55885 + endloop + endfacet + facet normal 0.184285 -0.266028 0.946186 + outer loop + vertex 1.07867 0.929024 2.55756 + vertex 1.07864 0.933572 2.55885 + vertex 1.07368 0.928582 2.55841 + endloop + endfacet + facet normal 0.184536 -0.272466 0.944303 + outer loop + vertex 1.07403 0.923922 2.557 + vertex 1.07867 0.929024 2.55756 + vertex 1.07368 0.928582 2.55841 + endloop + endfacet + facet normal 0.150249 -0.27647 0.949205 + outer loop + vertex 1.07403 0.923922 2.557 + vertex 1.07368 0.928582 2.55841 + vertex 1.06889 0.923807 2.55778 + endloop + endfacet + facet normal 0.150437 -0.26738 0.951776 + outer loop + vertex 1.07403 0.923922 2.557 + vertex 1.06889 0.923807 2.55778 + vertex 1.0693 0.919949 2.55663 + endloop + endfacet + facet normal 0.153069 -0.279141 0.947972 + outer loop + vertex 1.06889 0.923807 2.55778 + vertex 1.07368 0.928582 2.55841 + vertex 1.06859 0.928261 2.55914 + endloop + endfacet + facet normal 0.12076 -0.282414 0.951661 + outer loop + vertex 1.06889 0.923807 2.55778 + vertex 1.06859 0.928261 2.55914 + vertex 1.06373 0.923622 2.55838 + endloop + endfacet + facet normal 0.120729 -0.269197 0.955488 + outer loop + vertex 1.06412 0.918903 2.557 + vertex 1.06889 0.923807 2.55778 + vertex 1.06373 0.923622 2.55838 + endloop + endfacet + facet normal 0.117364 -0.279088 0.953066 + outer loop + vertex 1.06373 0.923622 2.55838 + vertex 1.06859 0.928261 2.55914 + vertex 1.06342 0.928359 2.5598 + endloop + endfacet + facet normal 0.11655 -0.293424 0.948851 + outer loop + vertex 1.06835 0.932134 2.56037 + vertex 1.06342 0.928359 2.5598 + vertex 1.06859 0.928261 2.55914 + endloop + endfacet + facet normal 0.159417 -0.289186 0.943906 + outer loop + vertex 1.06859 0.928261 2.55914 + vertex 1.07353 0.933417 2.55988 + vertex 1.06835 0.932134 2.56037 + endloop + endfacet + facet normal 0.16088 -0.295975 0.94155 + outer loop + vertex 1.06835 0.932134 2.56037 + vertex 1.07353 0.933417 2.55988 + vertex 1.0714 0.936019 2.56107 + endloop + endfacet + facet normal 0.176211 -0.283861 0.942535 + outer loop + vertex 1.07513 0.937555 2.56083 + vertex 1.0714 0.936019 2.56107 + vertex 1.07353 0.933417 2.55988 + endloop + endfacet + facet normal 0.230532 -0.300913 0.925368 + outer loop + vertex 1.07513 0.937555 2.56083 + vertex 1.07353 0.933417 2.55988 + vertex 1.07898 0.93842 2.56015 + endloop + endfacet + facet normal 0.227053 -0.279532 0.932903 + outer loop + vertex 1.07898 0.93842 2.56015 + vertex 1.07746 0.940415 2.56112 + vertex 1.07513 0.937555 2.56083 + endloop + endfacet + facet normal 0.190331 -0.251222 0.949032 + outer loop + vertex 1.07746 0.940415 2.56112 + vertex 1.07426 0.940025 2.56166 + vertex 1.07513 0.937555 2.56083 + endloop + endfacet + facet normal 0.188384 -0.226078 0.95572 + outer loop + vertex 1.07746 0.940415 2.56112 + vertex 1.07859 0.944207 2.5618 + vertex 1.07426 0.940025 2.56166 + endloop + endfacet + facet normal 0.199161 -0.267679 0.9427 + outer loop + vertex 1.07898 0.93842 2.56015 + vertex 1.07353 0.933417 2.55988 + vertex 1.07864 0.933572 2.55885 + endloop + endfacet + facet normal 0.166941 -0.260052 0.951054 + outer loop + vertex 1.07513 0.937555 2.56083 + vertex 1.07426 0.940025 2.56166 + vertex 1.0714 0.936019 2.56107 + endloop + endfacet + facet normal 0.14943 -0.248403 0.957061 + outer loop + vertex 1.07426 0.940025 2.56166 + vertex 1.06919 0.93874 2.56212 + vertex 1.0714 0.936019 2.56107 + endloop + endfacet + facet normal 0.135384 -0.259464 0.956216 + outer loop + vertex 1.0714 0.936019 2.56107 + vertex 1.06919 0.93874 2.56212 + vertex 1.06776 0.93476 2.56124 + endloop + endfacet + facet normal 0.148478 -0.244202 0.95829 + outer loop + vertex 1.07426 0.940025 2.56166 + vertex 1.07382 0.943856 2.5627 + vertex 1.06919 0.93874 2.56212 + endloop + endfacet + facet normal 0.159235 -0.253454 0.954152 + outer loop + vertex 1.06919 0.93874 2.56212 + vertex 1.07382 0.943856 2.5627 + vertex 1.06872 0.943481 2.56346 + endloop + endfacet + facet normal 0.158964 -0.245551 0.956261 + outer loop + vertex 1.07382 0.943856 2.5627 + vertex 1.07369 0.94852 2.56392 + vertex 1.06872 0.943481 2.56346 + endloop + endfacet + facet normal 0.175822 -0.261507 0.949053 + outer loop + vertex 1.06872 0.943481 2.56346 + vertex 1.07369 0.94852 2.56392 + vertex 1.06843 0.948434 2.56487 + endloop + endfacet + facet normal 0.176036 -0.254762 0.950846 + outer loop + vertex 1.07399 0.953435 2.56518 + vertex 1.06843 0.948434 2.56487 + vertex 1.07369 0.94852 2.56392 + endloop + endfacet + facet normal 0.216511 -0.298421 0.929552 + outer loop + vertex 1.07014 0.952652 2.56583 + vertex 1.06843 0.948434 2.56487 + vertex 1.07399 0.953435 2.56518 + endloop + endfacet + facet normal 0.213962 -0.280908 0.935581 + outer loop + vertex 1.07399 0.953435 2.56518 + vertex 1.0725 0.955436 2.56613 + vertex 1.07014 0.952652 2.56583 + endloop + endfacet + facet normal 0.166784 -0.242979 0.955586 + outer loop + vertex 1.0725 0.955436 2.56613 + vertex 1.06939 0.955205 2.56661 + vertex 1.07014 0.952652 2.56583 + endloop + endfacet + facet normal 0.136085 -0.252697 0.957927 + outer loop + vertex 1.07014 0.952652 2.56583 + vertex 1.06939 0.955205 2.56661 + vertex 1.06622 0.95128 2.56602 + endloop + endfacet + facet normal 0.16535 -0.204219 0.96486 + outer loop + vertex 1.0725 0.955436 2.56613 + vertex 1.07349 0.959089 2.56673 + vertex 1.06939 0.955205 2.56661 + endloop + endfacet + facet normal 0.175704 -0.215023 0.960673 + outer loop + vertex 1.07349 0.959089 2.56673 + vertex 1.06896 0.958997 2.56754 + vertex 1.06939 0.955205 2.56661 + endloop + endfacet + facet normal 0.176019 -0.19682 0.96451 + outer loop + vertex 1.07349 0.959089 2.56673 + vertex 1.07347 0.963653 2.56766 + vertex 1.06896 0.958997 2.56754 + endloop + endfacet + facet normal 0.193637 -0.213699 0.957516 + outer loop + vertex 1.06896 0.958997 2.56754 + vertex 1.07347 0.963653 2.56766 + vertex 1.06864 0.96358 2.56862 + endloop + endfacet + facet normal 0.194001 -0.200051 0.960387 + outer loop + vertex 1.07347 0.963653 2.56766 + vertex 1.07356 0.968652 2.56869 + vertex 1.06864 0.96358 2.56862 + endloop + endfacet + facet normal 0.218273 -0.223465 0.949958 + outer loop + vertex 1.06864 0.96358 2.56862 + vertex 1.07356 0.968652 2.56869 + vertex 1.06846 0.968685 2.56987 + endloop + endfacet + facet normal 0.218763 -0.214813 0.951839 + outer loop + vertex 1.0737 0.973858 2.56983 + vertex 1.06846 0.968685 2.56987 + vertex 1.07356 0.968652 2.56869 + endloop + endfacet + facet normal 0.26477 -0.261547 0.928165 + outer loop + vertex 1.06996 0.97297 2.57065 + vertex 1.06846 0.968685 2.56987 + vertex 1.0737 0.973858 2.56983 + endloop + endfacet + facet normal 0.263173 -0.251962 0.931265 + outer loop + vertex 1.0737 0.973858 2.56983 + vertex 1.07202 0.975795 2.57083 + vertex 1.06996 0.97297 2.57065 + endloop + endfacet + facet normal 0.200833 -0.208177 0.95725 + outer loop + vertex 1.07202 0.975795 2.57083 + vertex 1.06892 0.975245 2.57136 + vertex 1.06996 0.97297 2.57065 + endloop + endfacet + facet normal 0.176748 -0.219795 0.959401 + outer loop + vertex 1.06996 0.97297 2.57065 + vertex 1.06892 0.975245 2.57136 + vertex 1.06628 0.971278 2.57094 + endloop + endfacet + facet normal 0.196299 -0.175477 0.964715 + outer loop + vertex 1.07202 0.975795 2.57083 + vertex 1.07234 0.978894 2.57133 + vertex 1.06892 0.975245 2.57136 + endloop + endfacet + facet normal 0.201065 -0.179952 0.962907 + outer loop + vertex 1.07234 0.978894 2.57133 + vertex 1.06847 0.978923 2.57214 + vertex 1.06892 0.975245 2.57136 + endloop + endfacet + facet normal 0.202328 -0.149634 0.967819 + outer loop + vertex 1.07234 0.978894 2.57133 + vertex 1.0733 0.983707 2.57187 + vertex 1.06847 0.978923 2.57214 + endloop + endfacet + facet normal 0.229307 -0.177453 0.957042 + outer loop + vertex 1.06847 0.978923 2.57214 + vertex 1.0733 0.983707 2.57187 + vertex 1.06839 0.983631 2.57303 + endloop + endfacet + facet normal 0.229877 -0.153708 0.961005 + outer loop + vertex 1.0733 0.983707 2.57187 + vertex 1.07293 0.98856 2.57274 + vertex 1.06839 0.983631 2.57303 + endloop + endfacet + facet normal 0.248016 -0.170871 0.953568 + outer loop + vertex 1.06839 0.983631 2.57303 + vertex 1.07293 0.98856 2.57274 + vertex 1.06844 0.988668 2.57392 + endloop + endfacet + facet normal 0.249917 -0.140622 0.958002 + outer loop + vertex 1.07293 0.98856 2.57274 + vertex 1.07308 0.993486 2.57342 + vertex 1.06844 0.988668 2.57392 + endloop + endfacet + facet normal 0.275777 -0.166715 0.946654 + outer loop + vertex 1.06844 0.988668 2.57392 + vertex 1.07308 0.993486 2.57342 + vertex 1.06897 0.993766 2.57467 + endloop + endfacet + facet normal 0.278993 -0.136701 0.950513 + outer loop + vertex 1.07308 0.993486 2.57342 + vertex 1.07346 0.998535 2.57404 + vertex 1.06897 0.993766 2.57467 + endloop + endfacet + facet normal 0.311504 -0.169337 0.935035 + outer loop + vertex 1.06897 0.993766 2.57467 + vertex 1.07346 0.998535 2.57404 + vertex 1.06946 0.998621 2.57538 + endloop + endfacet + facet normal 0.313518 -0.140324 0.939157 + outer loop + vertex 1.07377 1.00371 2.57471 + vertex 1.06946 0.998621 2.57538 + vertex 1.07346 0.998535 2.57404 + endloop + endfacet + facet normal 0.18478 -0.23826 0.953461 + outer loop + vertex 1.06996 0.97297 2.57065 + vertex 1.06628 0.971278 2.57094 + vertex 1.06846 0.968685 2.56987 + endloop + endfacet + facet normal 0.214555 -0.215518 0.952638 + outer loop + vertex 1.07527 0.957291 2.56592 + vertex 1.07349 0.959089 2.56673 + vertex 1.0725 0.955436 2.56613 + endloop + endfacet + facet normal 0.227993 -0.202109 0.952455 + outer loop + vertex 1.07708 0.960176 2.5661 + vertex 1.07349 0.959089 2.56673 + vertex 1.07527 0.957291 2.56592 + endloop + endfacet + facet normal 0.296561 -0.243292 0.923504 + outer loop + vertex 1.07895 0.958585 2.56508 + vertex 1.07708 0.960176 2.5661 + vertex 1.07527 0.957291 2.56592 + endloop + endfacet + facet normal 0.305216 -0.275726 0.911493 + outer loop + vertex 1.07527 0.957291 2.56592 + vertex 1.07399 0.953435 2.56518 + vertex 1.07895 0.958585 2.56508 + endloop + endfacet + facet normal 0.251885 -0.223701 0.941547 + outer loop + vertex 1.07895 0.958585 2.56508 + vertex 1.07399 0.953435 2.56518 + vertex 1.07868 0.953624 2.56397 + endloop + endfacet + facet normal 0.317673 -0.222896 0.92163 + outer loop + vertex 1.07868 0.953624 2.56397 + vertex 1.08349 0.958749 2.56356 + vertex 1.07895 0.958585 2.56508 + endloop + endfacet + facet normal 0.275104 -0.181102 0.944203 + outer loop + vertex 1.08313 0.95375 2.5627 + vertex 1.08349 0.958749 2.56356 + vertex 1.07868 0.953624 2.56397 + endloop + endfacet + facet normal 0.273941 -0.219625 0.936334 + outer loop + vertex 1.07854 0.948807 2.56288 + vertex 1.08313 0.95375 2.5627 + vertex 1.07868 0.953624 2.56397 + endloop + endfacet + facet normal 0.21655 -0.221307 0.950857 + outer loop + vertex 1.07854 0.948807 2.56288 + vertex 1.07868 0.953624 2.56397 + vertex 1.07369 0.94852 2.56392 + endloop + endfacet + facet normal 0.216679 -0.241248 0.945965 + outer loop + vertex 1.07382 0.943856 2.5627 + vertex 1.07854 0.948807 2.56288 + vertex 1.07369 0.94852 2.56392 + endloop + endfacet + facet normal 0.19819 -0.223898 0.954249 + outer loop + vertex 1.07859 0.944207 2.5618 + vertex 1.07854 0.948807 2.56288 + vertex 1.07382 0.943856 2.5627 + endloop + endfacet + facet normal 0.249025 -0.220748 0.943004 + outer loop + vertex 1.08318 0.949153 2.56174 + vertex 1.07854 0.948807 2.56288 + vertex 1.07859 0.944207 2.5618 + endloop + endfacet + facet normal 0.229888 -0.202886 0.951834 + outer loop + vertex 1.08234 0.945351 2.56113 + vertex 1.08318 0.949153 2.56174 + vertex 1.07859 0.944207 2.5618 + endloop + endfacet + facet normal 0.235774 -0.226094 0.945142 + outer loop + vertex 1.08234 0.945351 2.56113 + vertex 1.07859 0.944207 2.5618 + vertex 1.08032 0.942335 2.56092 + endloop + endfacet + facet normal 0.27919 -0.253881 0.926065 + outer loop + vertex 1.08406 0.943565 2.56013 + vertex 1.08234 0.945351 2.56113 + vertex 1.08032 0.942335 2.56092 + endloop + endfacet + facet normal 0.293434 -0.2398 0.925415 + outer loop + vertex 1.08517 0.947547 2.56081 + vertex 1.08234 0.945351 2.56113 + vertex 1.08406 0.943565 2.56013 + endloop + endfacet + facet normal 0.349073 -0.25143 0.902735 + outer loop + vertex 1.08517 0.947547 2.56081 + vertex 1.08406 0.943565 2.56013 + vertex 1.08875 0.948884 2.55979 + endloop + endfacet + facet normal 0.34271 -0.227849 0.911392 + outer loop + vertex 1.08875 0.948884 2.55979 + vertex 1.08685 0.950546 2.56092 + vertex 1.08517 0.947547 2.56081 + endloop + endfacet + facet normal 0.28345 -0.195687 0.938809 + outer loop + vertex 1.08685 0.950546 2.56092 + vertex 1.08318 0.949153 2.56174 + vertex 1.08517 0.947547 2.56081 + endloop + endfacet + facet normal 0.27649 -0.173566 0.945213 + outer loop + vertex 1.08685 0.950546 2.56092 + vertex 1.08691 0.953698 2.56148 + vertex 1.08318 0.949153 2.56174 + endloop + endfacet + facet normal 0.298466 -0.192209 0.934866 + outer loop + vertex 1.08691 0.953698 2.56148 + vertex 1.08313 0.95375 2.5627 + vertex 1.08318 0.949153 2.56174 + endloop + endfacet + facet normal 0.301182 -0.150896 0.941552 + outer loop + vertex 1.08691 0.953698 2.56148 + vertex 1.08743 0.958207 2.56204 + vertex 1.08313 0.95375 2.5627 + endloop + endfacet + facet normal 0.225812 -0.23537 0.945309 + outer loop + vertex 1.08032 0.942335 2.56092 + vertex 1.07859 0.944207 2.5618 + vertex 1.07746 0.940415 2.56112 + endloop + endfacet + facet normal 0.245143 -0.265528 0.932416 + outer loop + vertex 1.08032 0.942335 2.56092 + vertex 1.07746 0.940415 2.56112 + vertex 1.07898 0.93842 2.56015 + endloop + endfacet + facet normal 0.271955 -0.210105 0.939093 + outer loop + vertex 1.08517 0.947547 2.56081 + vertex 1.08318 0.949153 2.56174 + vertex 1.08234 0.945351 2.56113 + endloop + endfacet + facet normal 0.248539 -0.195572 0.948673 + outer loop + vertex 1.08318 0.949153 2.56174 + vertex 1.08313 0.95375 2.5627 + vertex 1.07854 0.948807 2.56288 + endloop + endfacet + facet normal 0.330947 -0.181925 0.925947 + outer loop + vertex 1.08313 0.95375 2.5627 + vertex 1.08743 0.958207 2.56204 + vertex 1.08349 0.958749 2.56356 + endloop + endfacet + facet normal 0.25114 -0.254961 0.933768 + outer loop + vertex 1.07369 0.94852 2.56392 + vertex 1.07868 0.953624 2.56397 + vertex 1.07399 0.953435 2.56518 + endloop + endfacet + facet normal 0.315639 -0.220467 0.922912 + outer loop + vertex 1.07982 0.962586 2.56574 + vertex 1.07708 0.960176 2.5661 + vertex 1.07895 0.958585 2.56508 + endloop + endfacet + facet normal 0.369979 -0.228511 0.900499 + outer loop + vertex 1.07982 0.962586 2.56574 + vertex 1.07895 0.958585 2.56508 + vertex 1.08373 0.964164 2.56453 + endloop + endfacet + facet normal 0.36013 -0.195006 0.912294 + outer loop + vertex 1.07982 0.962586 2.56574 + vertex 1.08373 0.964164 2.56453 + vertex 1.08131 0.966446 2.56597 + endloop + endfacet + facet normal 0.29605 -0.17181 0.939593 + outer loop + vertex 1.08131 0.966446 2.56597 + vertex 1.07738 0.963402 2.56666 + vertex 1.07982 0.962586 2.56574 + endloop + endfacet + facet normal 0.301635 -0.179748 0.936326 + outer loop + vertex 1.07851 0.968505 2.56727 + vertex 1.07738 0.963402 2.56666 + vertex 1.08131 0.966446 2.56597 + endloop + endfacet + facet normal 0.31399 -0.16236 0.935441 + outer loop + vertex 1.08255 0.970201 2.56621 + vertex 1.07851 0.968505 2.56727 + vertex 1.08131 0.966446 2.56597 + endloop + endfacet + facet normal 0.38664 -0.184197 0.903649 + outer loop + vertex 1.085 0.96954 2.56503 + vertex 1.08255 0.970201 2.56621 + vertex 1.08131 0.966446 2.56597 + endloop + endfacet + facet normal 0.309588 -0.149638 0.939023 + outer loop + vertex 1.08255 0.970201 2.56621 + vertex 1.08218 0.973377 2.56684 + vertex 1.07851 0.968505 2.56727 + endloop + endfacet + facet normal 0.235819 -0.167786 0.957203 + outer loop + vertex 1.07738 0.963402 2.56666 + vertex 1.07851 0.968505 2.56727 + vertex 1.07347 0.963653 2.56766 + endloop + endfacet + facet normal 0.233018 -0.194182 0.952888 + outer loop + vertex 1.07738 0.963402 2.56666 + vertex 1.07347 0.963653 2.56766 + vertex 1.07349 0.959089 2.56673 + endloop + endfacet + facet normal 0.263916 -0.198037 0.943997 + outer loop + vertex 1.07347 0.963653 2.56766 + vertex 1.07851 0.968505 2.56727 + vertex 1.07356 0.968652 2.56869 + endloop + endfacet + facet normal 0.265524 -0.177972 0.947535 + outer loop + vertex 1.07851 0.968505 2.56727 + vertex 1.07823 0.973634 2.56831 + vertex 1.07356 0.968652 2.56869 + endloop + endfacet + facet normal 0.300557 -0.212118 0.929877 + outer loop + vertex 1.07356 0.968652 2.56869 + vertex 1.07823 0.973634 2.56831 + vertex 1.0737 0.973858 2.56983 + endloop + endfacet + facet normal 0.304344 -0.176843 0.936003 + outer loop + vertex 1.07836 0.979069 2.5693 + vertex 1.0737 0.973858 2.56983 + vertex 1.07823 0.973634 2.56831 + endloop + endfacet + facet normal 0.362642 -0.23243 0.902478 + outer loop + vertex 1.07463 0.977922 2.5705 + vertex 1.0737 0.973858 2.56983 + vertex 1.07836 0.979069 2.5693 + endloop + endfacet + facet normal 0.352858 -0.185087 0.917188 + outer loop + vertex 1.07463 0.977922 2.5705 + vertex 1.07836 0.979069 2.5693 + vertex 1.07608 0.98168 2.57071 + endloop + endfacet + facet normal 0.274869 -0.156689 0.948628 + outer loop + vertex 1.07608 0.98168 2.57071 + vertex 1.07234 0.978894 2.57133 + vertex 1.07463 0.977922 2.5705 + endloop + endfacet + facet normal 0.264657 -0.179752 0.947442 + outer loop + vertex 1.07463 0.977922 2.5705 + vertex 1.07234 0.978894 2.57133 + vertex 1.07202 0.975795 2.57083 + endloop + endfacet + facet normal 0.278828 -0.162477 0.946497 + outer loop + vertex 1.0733 0.983707 2.57187 + vertex 1.07234 0.978894 2.57133 + vertex 1.07608 0.98168 2.57071 + endloop + endfacet + facet normal 0.290247 -0.146362 0.945693 + outer loop + vertex 1.07729 0.985417 2.57091 + vertex 1.0733 0.983707 2.57187 + vertex 1.07608 0.98168 2.57071 + endloop + endfacet + facet normal 0.386899 -0.175446 0.905278 + outer loop + vertex 1.07976 0.984538 2.56968 + vertex 1.07729 0.985417 2.57091 + vertex 1.07608 0.98168 2.57071 + endloop + endfacet + facet normal 0.285715 -0.133985 0.948902 + outer loop + vertex 1.07729 0.985417 2.57091 + vertex 1.0769 0.988532 2.57147 + vertex 1.0733 0.983707 2.57187 + endloop + endfacet + facet normal 0.299984 -0.145138 0.942839 + outer loop + vertex 1.0769 0.988532 2.57147 + vertex 1.07293 0.98856 2.57274 + vertex 1.0733 0.983707 2.57187 + endloop + endfacet + facet normal 0.377401 -0.160786 0.911985 + outer loop + vertex 1.07836 0.979069 2.5693 + vertex 1.07976 0.984538 2.56968 + vertex 1.07608 0.98168 2.57071 + endloop + endfacet + facet normal 0.296585 -0.221745 0.928906 + outer loop + vertex 1.07463 0.977922 2.5705 + vertex 1.07202 0.975795 2.57083 + vertex 1.0737 0.973858 2.56983 + endloop + endfacet + facet normal 0.335128 -0.169993 0.92671 + outer loop + vertex 1.08218 0.973377 2.56684 + vertex 1.07823 0.973634 2.56831 + vertex 1.07851 0.968505 2.56727 + endloop + endfacet + facet normal 0.378811 -0.173183 0.909126 + outer loop + vertex 1.08373 0.964164 2.56453 + vertex 1.085 0.96954 2.56503 + vertex 1.08131 0.966446 2.56597 + endloop + endfacet + facet normal 0.319038 -0.181924 0.930117 + outer loop + vertex 1.08373 0.964164 2.56453 + vertex 1.07895 0.958585 2.56508 + vertex 1.08349 0.958749 2.56356 + endloop + endfacet + facet normal 0.289826 -0.188862 0.93826 + outer loop + vertex 1.07982 0.962586 2.56574 + vertex 1.07738 0.963402 2.56666 + vertex 1.07708 0.960176 2.5661 + endloop + endfacet + facet normal 0.223808 -0.185795 0.95676 + outer loop + vertex 1.07708 0.960176 2.5661 + vertex 1.07738 0.963402 2.56666 + vertex 1.07349 0.959089 2.56673 + endloop + endfacet + facet normal 0.242553 -0.259315 0.934839 + outer loop + vertex 1.07527 0.957291 2.56592 + vertex 1.0725 0.955436 2.56613 + vertex 1.07399 0.953435 2.56518 + endloop + endfacet + facet normal 0.143074 -0.273603 0.951142 + outer loop + vertex 1.07014 0.952652 2.56583 + vertex 1.06622 0.95128 2.56602 + vertex 1.06843 0.948434 2.56487 + endloop + endfacet + facet normal 0.153158 -0.283587 0.946637 + outer loop + vertex 1.07368 0.928582 2.55841 + vertex 1.07353 0.933417 2.55988 + vertex 1.06859 0.928261 2.55914 + endloop + endfacet + facet normal 0.198826 -0.279852 0.939229 + outer loop + vertex 1.07368 0.928582 2.55841 + vertex 1.07864 0.933572 2.55885 + vertex 1.07353 0.933417 2.55988 + endloop + endfacet + facet normal 0.205313 -0.247169 0.946971 + outer loop + vertex 1.08341 0.92938 2.55663 + vertex 1.08347 0.933889 2.55779 + vertex 1.07867 0.929024 2.55756 + endloop + endfacet + facet normal 0.205628 -0.262006 0.942905 + outer loop + vertex 1.08341 0.92938 2.55663 + vertex 1.07867 0.929024 2.55756 + vertex 1.07905 0.925295 2.55645 + endloop + endfacet + facet normal 0.197157 -0.25316 0.947121 + outer loop + vertex 1.08225 0.925681 2.55588 + vertex 1.08341 0.92938 2.55663 + vertex 1.07905 0.925295 2.55645 + endloop + endfacet + facet normal 0.28483 -0.276285 0.917899 + outer loop + vertex 1.08032 0.942335 2.56092 + vertex 1.07898 0.93842 2.56015 + vertex 1.08406 0.943565 2.56013 + endloop + endfacet + facet normal 0.30206 -0.208277 0.930258 + outer loop + vertex 1.08875 0.948884 2.55979 + vertex 1.08406 0.943565 2.56013 + vertex 1.08862 0.943814 2.5587 + endloop + endfacet + facet normal 0.31765 -0.206574 0.925433 + outer loop + vertex 1.0883 0.938864 2.5577 + vertex 1.09329 0.943839 2.5571 + vertex 1.08862 0.943814 2.5587 + endloop + endfacet + facet normal 0.319762 -0.169597 0.932196 + outer loop + vertex 1.09329 0.943839 2.5571 + vertex 1.09305 0.948873 2.5581 + vertex 1.08862 0.943814 2.5587 + endloop + endfacet + facet normal 0.357913 -0.20546 0.91087 + outer loop + vertex 1.08862 0.943814 2.5587 + vertex 1.09305 0.948873 2.5581 + vertex 1.08875 0.948884 2.55979 + endloop + endfacet + facet normal 0.282534 -0.16913 0.94423 + outer loop + vertex 1.09216 0.938756 2.55653 + vertex 1.09329 0.943839 2.5571 + vertex 1.0883 0.938864 2.5577 + endloop + endfacet + facet normal 0.278874 -0.213522 0.936289 + outer loop + vertex 1.09216 0.938756 2.55653 + vertex 1.0883 0.938864 2.5577 + vertex 1.08813 0.934202 2.55669 + endloop + endfacet + facet normal 0.258064 -0.194758 0.946294 + outer loop + vertex 1.09187 0.935521 2.55594 + vertex 1.09216 0.938756 2.55653 + vertex 1.08813 0.934202 2.55669 + endloop + endfacet + facet normal 0.271694 -0.261369 0.926212 + outer loop + vertex 1.09007 0.932561 2.55576 + vertex 1.08718 0.930444 2.55601 + vertex 1.08894 0.928661 2.55499 + endloop + endfacet + facet normal 0.255581 -0.224965 0.94025 + outer loop + vertex 1.09324 0.924001 2.55255 + vertex 1.09358 0.928863 2.55362 + vertex 1.08863 0.923797 2.55375 + endloop + endfacet + facet normal 0.261644 -0.281125 0.923315 + outer loop + vertex 1.08513 0.927517 2.55572 + vertex 1.08382 0.923642 2.55491 + vertex 1.08894 0.928661 2.55499 + endloop + endfacet + facet normal 0.217554 -0.243854 0.945095 + outer loop + vertex 1.08851 0.919133 2.55257 + vertex 1.08863 0.923797 2.55375 + vertex 1.08357 0.918715 2.5536 + endloop + endfacet + facet normal 0.217932 -0.257405 0.941407 + outer loop + vertex 1.08379 0.913853 2.55222 + vertex 1.08851 0.919133 2.55257 + vertex 1.08357 0.918715 2.5536 + endloop + endfacet + facet normal 0.203969 -0.245331 0.947739 + outer loop + vertex 1.08884 0.915318 2.55152 + vertex 1.08851 0.919133 2.55257 + vertex 1.08379 0.913853 2.55222 + endloop + endfacet + facet normal 0.198066 -0.266232 0.94334 + outer loop + vertex 1.08225 0.925681 2.55588 + vertex 1.07905 0.925295 2.55645 + vertex 1.07991 0.922856 2.55558 + endloop + endfacet + facet normal 0.177301 -0.266227 0.947464 + outer loop + vertex 1.07905 0.925295 2.55645 + vertex 1.07867 0.929024 2.55756 + vertex 1.07403 0.923922 2.557 + endloop + endfacet + facet normal 0.144646 -0.260743 0.954511 + outer loop + vertex 1.07253 0.919925 2.55613 + vertex 1.07403 0.923922 2.557 + vertex 1.0693 0.919949 2.55663 + endloop + endfacet + facet normal 0.122904 -0.271175 0.954651 + outer loop + vertex 1.0693 0.919949 2.55663 + vertex 1.06889 0.923807 2.55778 + vertex 1.06412 0.918903 2.557 + endloop + endfacet + facet normal 0.134843 -0.281083 0.950163 + outer loop + vertex 1.06991 0.9173 2.55581 + vertex 1.06622 0.916088 2.55598 + vertex 1.06831 0.913391 2.55488 + endloop + endfacet + facet normal 0.155986 -0.288469 0.944698 + outer loop + vertex 1.06991 0.9173 2.55581 + vertex 1.06831 0.913391 2.55488 + vertex 1.0731 0.917284 2.55528 + endloop + endfacet + facet normal 0.179218 -0.277073 0.943987 + outer loop + vertex 1.0731 0.917284 2.55528 + vertex 1.07833 0.918637 2.55468 + vertex 1.07616 0.921281 2.55587 + endloop + endfacet + facet normal 0.198213 -0.268405 0.942693 + outer loop + vertex 1.07859 0.913746 2.55324 + vertex 1.08357 0.918715 2.5536 + vertex 1.07833 0.918637 2.55468 + endloop + endfacet + facet normal 0.189712 -0.260177 0.94674 + outer loop + vertex 1.08379 0.913853 2.55222 + vertex 1.08357 0.918715 2.5536 + vertex 1.07859 0.913746 2.55324 + endloop + endfacet + facet normal 0.213267 -0.283644 0.934914 + outer loop + vertex 1.08884 0.915318 2.55152 + vertex 1.08379 0.913853 2.55222 + vertex 1.08612 0.911276 2.55091 + endloop + endfacet + facet normal 0.219828 -0.412338 0.884111 + outer loop + vertex 1.08366 0.907659 2.54995 + vertex 1.08243 0.909842 2.55127 + vertex 1.08021 0.907461 2.55071 + endloop + endfacet + facet normal 0.212728 -0.283314 0.935136 + outer loop + vertex 1.08985 0.91291 2.55056 + vertex 1.08884 0.915318 2.55152 + vertex 1.08612 0.911276 2.55091 + endloop + endfacet + facet normal 0.234677 -0.240992 0.941727 + outer loop + vertex 1.09306 0.919486 2.55153 + vertex 1.08851 0.919133 2.55257 + vertex 1.08884 0.915318 2.55152 + endloop + endfacet + facet normal 0.261484 -0.209617 0.942171 + outer loop + vertex 1.09668 0.92064 2.55078 + vertex 1.09703 0.923848 2.5514 + vertex 1.09306 0.919486 2.55153 + endloop + endfacet + facet normal 0.279955 -0.277238 0.919111 + outer loop + vertex 1.09488 0.917717 2.55059 + vertex 1.09206 0.915783 2.55086 + vertex 1.09384 0.913763 2.54971 + endloop + endfacet + facet normal 0.281934 -0.1914 0.940149 + outer loop + vertex 1.10318 0.914143 2.54707 + vertex 1.10308 0.918902 2.54807 + vertex 1.0987 0.913964 2.54838 + endloop + endfacet + facet normal 0.280745 -0.239005 0.929547 + outer loop + vertex 1.10318 0.914143 2.54707 + vertex 1.0987 0.913964 2.54838 + vertex 1.09926 0.909917 2.54717 + endloop + endfacet + facet normal 0.249586 -0.209713 0.945372 + outer loop + vertex 1.10244 0.910354 2.54642 + vertex 1.10318 0.914143 2.54707 + vertex 1.09926 0.909917 2.54717 + endloop + endfacet + facet normal 0.257096 -0.323748 0.910543 + outer loop + vertex 1.10244 0.910354 2.54642 + vertex 1.09926 0.909917 2.54717 + vertex 1.10053 0.907608 2.54599 + endloop + endfacet + facet normal 0.316817 -0.359991 0.877516 + outer loop + vertex 1.1044 0.908679 2.54503 + vertex 1.10244 0.910354 2.54642 + vertex 1.10053 0.907608 2.54599 + endloop + endfacet + facet normal 0.387893 -0.147062 0.909897 + outer loop + vertex 1.10554 0.936938 2.55062 + vertex 1.10192 0.933656 2.55164 + vertex 1.10461 0.933132 2.55041 + endloop + endfacet + facet normal 0.410454 -0.152173 0.899094 + outer loop + vertex 1.10347 0.944004 2.55273 + vertex 1.10236 0.93829 2.55226 + vertex 1.10634 0.941631 2.55102 + endloop + endfacet + facet normal 0.407779 -0.129012 0.903921 + outer loop + vertex 1.09701 0.953225 2.5571 + vertex 1.09682 0.948691 2.55654 + vertex 1.10028 0.951963 2.55545 + endloop + endfacet + facet normal 0.373736 -0.129362 0.91847 + outer loop + vertex 1.09682 0.948691 2.55654 + vertex 1.09701 0.953225 2.5571 + vertex 1.09305 0.948873 2.5581 + endloop + endfacet + facet normal 0.428076 -0.122218 0.895441 + outer loop + vertex 1.09443 0.960152 2.55931 + vertex 1.09868 0.964143 2.55782 + vertex 1.09491 0.964944 2.55973 + endloop + endfacet + facet normal 0.423652 -0.117182 0.898213 + outer loop + vertex 1.09448 0.96817 2.56036 + vertex 1.09223 0.965529 2.56107 + vertex 1.09491 0.964944 2.55973 + endloop + endfacet + facet normal 0.382934 -0.144356 0.912427 + outer loop + vertex 1.08842 0.963798 2.56251 + vertex 1.08743 0.958207 2.56204 + vertex 1.0914 0.961696 2.56093 + endloop + endfacet + facet normal 0.42448 -0.118019 0.897713 + outer loop + vertex 1.09448 0.96817 2.56036 + vertex 1.09181 0.968638 2.56168 + vertex 1.09223 0.965529 2.56107 + endloop + endfacet + facet normal 0.435227 -0.103897 0.894306 + outer loop + vertex 1.08969 0.992746 2.56574 + vertex 1.0874 0.990241 2.56656 + vertex 1.09011 0.989543 2.56516 + endloop + endfacet + facet normal 0.444394 -0.114166 0.888527 + outer loop + vertex 1.08969 0.992746 2.56574 + vertex 1.08714 0.993633 2.56713 + vertex 1.0874 0.990241 2.56656 + endloop + endfacet + facet normal 0.417854 -0.105659 0.902349 + outer loop + vertex 1.0887 1.00389 2.56763 + vertex 1.08771 0.998384 2.56744 + vertex 1.0914 1.00129 2.56608 + endloop + endfacet + facet normal 0.400355 -0.119929 0.908478 + outer loop + vertex 1.09348 0.99426 2.56425 + vertex 1.09445 0.999852 2.56456 + vertex 1.0906 0.996595 2.56583 + endloop + endfacet + facet normal 0.408502 -0.117074 0.905218 + outer loop + vertex 1.09226 1.00506 2.56617 + vertex 1.0887 1.00389 2.56763 + vertex 1.0914 1.00129 2.56608 + endloop + endfacet + facet normal 0.40707 -0.110952 0.906633 + outer loop + vertex 1.09226 1.00506 2.56617 + vertex 1.09192 1.00831 2.56672 + vertex 1.0887 1.00389 2.56763 + endloop + endfacet + facet normal 0.383552 -0.115092 0.91632 + outer loop + vertex 1.09458 1.00768 2.56553 + vertex 1.09192 1.00831 2.56672 + vertex 1.09226 1.00506 2.56617 + endloop + endfacet + facet normal 0.394132 -0.113415 0.912029 + outer loop + vertex 1.09192 1.00831 2.56672 + vertex 1.09226 1.013 2.56716 + vertex 1.08845 1.00906 2.56832 + endloop + endfacet + facet normal 0.396649 -0.102229 0.91226 + outer loop + vertex 1.09192 1.00831 2.56672 + vertex 1.08845 1.00906 2.56832 + vertex 1.0887 1.00389 2.56763 + endloop + endfacet + facet normal 0.38839 -0.1069 0.915273 + outer loop + vertex 1.08845 1.00906 2.56832 + vertex 1.09226 1.013 2.56716 + vertex 1.08828 1.01433 2.569 + endloop + endfacet + facet normal 0.383838 -0.120797 0.915465 + outer loop + vertex 1.09226 1.013 2.56716 + vertex 1.09337 1.01873 2.56745 + vertex 1.08828 1.01433 2.569 + endloop + endfacet + facet normal 0.382 -0.118281 0.916562 + outer loop + vertex 1.08828 1.01433 2.569 + vertex 1.09337 1.01873 2.56745 + vertex 1.08938 1.02001 2.56928 + endloop + endfacet + facet normal 0.378693 -0.128539 0.916553 + outer loop + vertex 1.09337 1.01873 2.56745 + vertex 1.09335 1.02401 2.5682 + vertex 1.08938 1.02001 2.56928 + endloop + endfacet + facet normal 0.363589 -0.128113 0.922708 + outer loop + vertex 1.09848 1.00931 2.56417 + vertex 1.09953 1.01492 2.56454 + vertex 1.09548 1.01154 2.56566 + endloop + endfacet + facet normal 0.314013 -0.125485 0.941089 + outer loop + vertex 1.09953 1.01492 2.56454 + vertex 1.10384 1.01909 2.56365 + vertex 1.09996 1.01954 2.56501 + endloop + endfacet + facet normal 0.311077 -0.145164 0.939233 + outer loop + vertex 1.10354 1.02423 2.56455 + vertex 1.09996 1.01954 2.56501 + vertex 1.10384 1.01909 2.56365 + endloop + endfacet + facet normal 0.340484 -0.126561 0.931693 + outer loop + vertex 1.0996 1.02276 2.56558 + vertex 1.09721 1.02014 2.56609 + vertex 1.09996 1.01954 2.56501 + endloop + endfacet + facet normal 0.297077 -0.133854 0.945425 + outer loop + vertex 1.0996 1.02276 2.56558 + vertex 1.09996 1.01954 2.56501 + vertex 1.10354 1.02423 2.56455 + endloop + endfacet + facet normal 0.297959 -0.13669 0.944741 + outer loop + vertex 1.0996 1.02276 2.56558 + vertex 1.10354 1.02423 2.56455 + vertex 1.10051 1.02646 2.56583 + endloop + endfacet + facet normal 0.345711 -0.147156 0.92673 + outer loop + vertex 1.10051 1.02646 2.56583 + vertex 1.0969 1.02337 2.56668 + vertex 1.0996 1.02276 2.56558 + endloop + endfacet + facet normal 0.372546 -0.11887 0.920369 + outer loop + vertex 1.09337 1.01873 2.56745 + vertex 1.09226 1.013 2.56716 + vertex 1.09628 1.01628 2.56596 + endloop + endfacet + facet normal 0.348769 -0.134967 0.92744 + outer loop + vertex 1.0996 1.02276 2.56558 + vertex 1.0969 1.02337 2.56668 + vertex 1.09721 1.02014 2.56609 + endloop + endfacet + facet normal 0.378422 -0.128228 0.916709 + outer loop + vertex 1.08938 1.02001 2.56928 + vertex 1.09335 1.02401 2.5682 + vertex 1.08979 1.02466 2.56976 + endloop + endfacet + facet normal 0.394587 -0.128939 0.909767 + outer loop + vertex 1.08938 1.02001 2.56928 + vertex 1.08979 1.02466 2.56976 + vertex 1.08625 1.02158 2.57086 + endloop + endfacet + facet normal 0.389443 -0.121896 0.912949 + outer loop + vertex 1.08979 1.02466 2.56976 + vertex 1.08713 1.02532 2.57098 + vertex 1.08625 1.02158 2.57086 + endloop + endfacet + facet normal 0.405767 -0.125457 0.905325 + outer loop + vertex 1.08713 1.02532 2.57098 + vertex 1.08354 1.02411 2.57242 + vertex 1.08625 1.02158 2.57086 + endloop + endfacet + facet normal 0.416631 -0.111836 0.902171 + outer loop + vertex 1.08354 1.02411 2.57242 + vertex 1.08251 1.01867 2.57222 + vertex 1.08625 1.02158 2.57086 + endloop + endfacet + facet normal 0.404393 -0.119751 0.906712 + outer loop + vertex 1.08713 1.02532 2.57098 + vertex 1.08676 1.02848 2.57156 + vertex 1.08354 1.02411 2.57242 + endloop + endfacet + facet normal 0.393964 -0.110938 0.912406 + outer loop + vertex 1.08676 1.02848 2.57156 + vertex 1.08337 1.02915 2.57311 + vertex 1.08354 1.02411 2.57242 + endloop + endfacet + facet normal 0.388256 -0.126491 0.912829 + outer loop + vertex 1.08943 1.02786 2.57035 + vertex 1.08713 1.02532 2.57098 + vertex 1.08979 1.02466 2.56976 + endloop + endfacet + facet normal 0.385279 -0.123367 0.914516 + outer loop + vertex 1.08943 1.02786 2.57035 + vertex 1.08676 1.02848 2.57156 + vertex 1.08713 1.02532 2.57098 + endloop + endfacet + facet normal 0.393273 -0.114176 0.912305 + outer loop + vertex 1.08676 1.02848 2.57156 + vertex 1.08701 1.0329 2.57201 + vertex 1.08337 1.02915 2.57311 + endloop + endfacet + facet normal 0.360936 -0.131601 0.923259 + outer loop + vertex 1.09332 1.02922 2.56898 + vertex 1.09442 1.03488 2.56936 + vertex 1.09027 1.03161 2.57051 + endloop + endfacet + facet normal 0.298836 -0.123424 0.946289 + outer loop + vertex 1.09442 1.03488 2.56936 + vertex 1.0989 1.03894 2.56847 + vertex 1.09484 1.03987 2.56987 + endloop + endfacet + facet normal 0.293459 -0.144967 0.944916 + outer loop + vertex 1.0989 1.03894 2.56847 + vertex 1.09889 1.04389 2.56923 + vertex 1.09484 1.03987 2.56987 + endloop + endfacet + facet normal 0.37097 -0.110633 0.922031 + outer loop + vertex 1.08747 1.03787 2.57242 + vertex 1.08701 1.0329 2.57201 + vertex 1.09086 1.03636 2.57088 + endloop + endfacet + facet normal 0.348802 -0.169451 0.92175 + outer loop + vertex 1.09236 1.04825 2.57188 + vertex 1.09365 1.05344 2.57235 + vertex 1.08877 1.04905 2.57339 + endloop + endfacet + facet normal 0.322575 -0.136805 0.936606 + outer loop + vertex 1.08877 1.04905 2.57339 + vertex 1.09365 1.05344 2.57235 + vertex 1.08859 1.0543 2.57422 + endloop + endfacet + facet normal 0.360729 -0.133405 0.923081 + outer loop + vertex 1.08859 1.0543 2.57422 + vertex 1.08499 1.04961 2.57495 + vertex 1.08877 1.04905 2.57339 + endloop + endfacet + facet normal 0.346025 -0.120995 0.930391 + outer loop + vertex 1.08459 1.05278 2.57551 + vertex 1.08499 1.04961 2.57495 + vertex 1.08859 1.0543 2.57422 + endloop + endfacet + facet normal 0.343729 -0.113395 0.932197 + outer loop + vertex 1.08459 1.05278 2.57551 + vertex 1.08859 1.0543 2.57422 + vertex 1.08544 1.05654 2.57565 + endloop + endfacet + facet normal 0.348254 -0.114353 0.930399 + outer loop + vertex 1.08544 1.05654 2.57565 + vertex 1.08177 1.05319 2.57661 + vertex 1.08459 1.05278 2.57551 + endloop + endfacet + facet normal 0.334424 -0.127529 0.933754 + outer loop + vertex 1.08859 1.0543 2.57422 + vertex 1.08947 1.05985 2.57466 + vertex 1.08544 1.05654 2.57565 + endloop + endfacet + facet normal 0.324239 -0.113521 0.939139 + outer loop + vertex 1.08544 1.05654 2.57565 + vertex 1.08947 1.05985 2.57466 + vertex 1.08618 1.06119 2.57596 + endloop + endfacet + facet normal 0.340707 -0.115728 0.93302 + outer loop + vertex 1.08618 1.06119 2.57596 + vertex 1.08213 1.05776 2.57701 + vertex 1.08544 1.05654 2.57565 + endloop + endfacet + facet normal 0.342913 -0.118684 0.931839 + outer loop + vertex 1.08319 1.06343 2.57734 + vertex 1.08213 1.05776 2.57701 + vertex 1.08618 1.06119 2.57596 + endloop + endfacet + facet normal 0.341295 -0.121024 0.932132 + outer loop + vertex 1.08714 1.06503 2.5761 + vertex 1.08319 1.06343 2.57734 + vertex 1.08618 1.06119 2.57596 + endloop + endfacet + facet normal 0.309498 -0.113467 0.944106 + outer loop + vertex 1.08985 1.06444 2.57515 + vertex 1.08714 1.06503 2.5761 + vertex 1.08618 1.06119 2.57596 + endloop + endfacet + facet normal 0.349204 -0.145663 0.925656 + outer loop + vertex 1.08714 1.06503 2.5761 + vertex 1.08707 1.06829 2.57664 + vertex 1.08319 1.06343 2.57734 + endloop + endfacet + facet normal 0.319297 -0.125754 0.939274 + outer loop + vertex 1.08947 1.05985 2.57466 + vertex 1.08985 1.06444 2.57515 + vertex 1.08618 1.06119 2.57596 + endloop + endfacet + facet normal 0.288174 -0.121484 0.949841 + outer loop + vertex 1.08859 1.0543 2.57422 + vertex 1.09363 1.05884 2.57327 + vertex 1.08947 1.05985 2.57466 + endloop + endfacet + facet normal 0.28238 -0.143603 0.948493 + outer loop + vertex 1.09363 1.05884 2.57327 + vertex 1.09368 1.06392 2.57402 + vertex 1.08947 1.05985 2.57466 + endloop + endfacet + facet normal 0.263732 -0.12304 0.956717 + outer loop + vertex 1.08947 1.05985 2.57466 + vertex 1.09368 1.06392 2.57402 + vertex 1.08985 1.06444 2.57515 + endloop + endfacet + facet normal 0.259998 -0.14599 0.954509 + outer loop + vertex 1.09357 1.06903 2.57484 + vertex 1.08985 1.06444 2.57515 + vertex 1.09368 1.06392 2.57402 + endloop + endfacet + facet normal 0.246848 -0.134991 0.959606 + outer loop + vertex 1.08963 1.06763 2.57565 + vertex 1.08985 1.06444 2.57515 + vertex 1.09357 1.06903 2.57484 + endloop + endfacet + facet normal 0.249926 -0.144965 0.957352 + outer loop + vertex 1.08963 1.06763 2.57565 + vertex 1.09357 1.06903 2.57484 + vertex 1.09094 1.07126 2.57586 + endloop + endfacet + facet normal 0.318629 -0.168395 0.932801 + outer loop + vertex 1.09094 1.07126 2.57586 + vertex 1.08707 1.06829 2.57664 + vertex 1.08963 1.06763 2.57565 + endloop + endfacet + facet normal 0.324567 -0.147596 0.934276 + outer loop + vertex 1.08963 1.06763 2.57565 + vertex 1.08707 1.06829 2.57664 + vertex 1.08714 1.06503 2.5761 + endloop + endfacet + facet normal 0.310969 -0.157257 0.93732 + outer loop + vertex 1.08843 1.0735 2.57707 + vertex 1.08707 1.06829 2.57664 + vertex 1.09094 1.07126 2.57586 + endloop + endfacet + facet normal 0.295562 -0.175513 0.939062 + outer loop + vertex 1.09255 1.07499 2.57605 + vertex 1.08843 1.0735 2.57707 + vertex 1.09094 1.07126 2.57586 + endloop + endfacet + facet normal 0.232019 -0.149206 0.9612 + outer loop + vertex 1.09496 1.07412 2.57533 + vertex 1.09255 1.07499 2.57605 + vertex 1.09094 1.07126 2.57586 + endloop + endfacet + facet normal 0.302787 -0.200566 0.931715 + outer loop + vertex 1.09255 1.07499 2.57605 + vertex 1.09336 1.07878 2.5766 + vertex 1.08843 1.0735 2.57707 + endloop + endfacet + facet normal 0.259897 -0.158663 0.952512 + outer loop + vertex 1.09336 1.07878 2.5766 + vertex 1.08836 1.07868 2.57795 + vertex 1.08843 1.0735 2.57707 + endloop + endfacet + facet normal 0.259501 -0.174955 0.949763 + outer loop + vertex 1.09336 1.07878 2.5766 + vertex 1.09325 1.08348 2.5775 + vertex 1.08836 1.07868 2.57795 + endloop + endfacet + facet normal 0.238425 -0.158815 0.958087 + outer loop + vertex 1.09357 1.06903 2.57484 + vertex 1.09496 1.07412 2.57533 + vertex 1.09094 1.07126 2.57586 + endloop + endfacet + facet normal 0.306013 -0.12832 0.94334 + outer loop + vertex 1.08963 1.06763 2.57565 + vertex 1.08714 1.06503 2.5761 + vertex 1.08985 1.06444 2.57515 + endloop + endfacet + facet normal 0.359703 -0.118388 0.925526 + outer loop + vertex 1.08459 1.05278 2.57551 + vertex 1.08219 1.05008 2.5761 + vertex 1.08499 1.04961 2.57495 + endloop + endfacet + facet normal 0.318279 -0.158019 0.934734 + outer loop + vertex 1.09365 1.05344 2.57235 + vertex 1.09363 1.05884 2.57327 + vertex 1.08859 1.0543 2.57422 + endloop + endfacet + facet normal 0.38112 -0.117104 0.917079 + outer loop + vertex 1.08747 1.03787 2.57242 + vertex 1.08862 1.04365 2.57268 + vertex 1.08349 1.03923 2.57425 + endloop + endfacet + facet normal 0.383823 -0.109003 0.916951 + outer loop + vertex 1.08353 1.03399 2.57361 + vertex 1.08747 1.03787 2.57242 + vertex 1.08349 1.03923 2.57425 + endloop + endfacet + facet normal 0.385913 -0.11148 0.915775 + outer loop + vertex 1.08701 1.0329 2.57201 + vertex 1.08747 1.03787 2.57242 + vertex 1.08353 1.03399 2.57361 + endloop + endfacet + facet normal 0.387212 -0.107279 0.915728 + outer loop + vertex 1.08337 1.02915 2.57311 + vertex 1.08701 1.0329 2.57201 + vertex 1.08353 1.03399 2.57361 + endloop + endfacet + facet normal 0.363184 -0.119476 0.924025 + outer loop + vertex 1.08461 1.04493 2.57449 + vertex 1.08877 1.04905 2.57339 + vertex 1.08499 1.04961 2.57495 + endloop + endfacet + facet normal 0.34931 -0.108016 0.93076 + outer loop + vertex 1.08459 1.05278 2.57551 + vertex 1.08177 1.05319 2.57661 + vertex 1.08219 1.05008 2.5761 + endloop + endfacet + facet normal 0.343403 -0.108313 0.932921 + outer loop + vertex 1.08213 1.05776 2.57701 + vertex 1.08177 1.05319 2.57661 + vertex 1.08544 1.05654 2.57565 + endloop + endfacet + facet normal 0.317144 -0.114439 0.941448 + outer loop + vertex 1.08213 1.05776 2.57701 + vertex 1.08319 1.06343 2.57734 + vertex 1.07815 1.05867 2.57846 + endloop + endfacet + facet normal 0.339371 -0.137086 0.93061 + outer loop + vertex 1.08707 1.06829 2.57664 + vertex 1.08337 1.06885 2.57808 + vertex 1.08319 1.06343 2.57734 + endloop + endfacet + facet normal 0.334561 -0.16263 0.928235 + outer loop + vertex 1.08707 1.06829 2.57664 + vertex 1.08843 1.0735 2.57707 + vertex 1.08337 1.06885 2.57808 + endloop + endfacet + facet normal 0.248007 -0.0818145 0.965297 + outer loop + vertex 1.07957 1.07762 2.58049 + vertex 1.07676 1.07806 2.58125 + vertex 1.07723 1.07495 2.58086 + endloop + endfacet + facet normal 0.310722 -0.125436 0.942188 + outer loop + vertex 1.07958 1.06989 2.57954 + vertex 1.08382 1.07402 2.57869 + vertex 1.08001 1.07445 2.58 + endloop + endfacet + facet normal 0.285045 -0.127997 0.94993 + outer loop + vertex 1.07418 1.06322 2.58024 + vertex 1.07354 1.05918 2.57989 + vertex 1.07825 1.06426 2.57916 + endloop + endfacet + facet normal 0.253971 -0.123896 0.959244 + outer loop + vertex 1.07418 1.06322 2.58024 + vertex 1.07103 1.06136 2.58083 + vertex 1.07354 1.05918 2.57989 + endloop + endfacet + facet normal 0.258479 -0.132289 0.956916 + outer loop + vertex 1.07418 1.06322 2.58024 + vertex 1.07238 1.06459 2.58091 + vertex 1.07103 1.06136 2.58083 + endloop + endfacet + facet normal 0.174528 -0.130977 0.975902 + outer loop + vertex 1.07815 1.09816 2.58324 + vertex 1.08318 1.10319 2.58302 + vertex 1.07821 1.10315 2.5839 + endloop + endfacet + facet normal 0.174289 -0.145326 0.973912 + outer loop + vertex 1.08318 1.10319 2.58302 + vertex 1.08321 1.10813 2.58375 + vertex 1.07821 1.10315 2.5839 + endloop + endfacet + facet normal 0.143547 -0.122155 0.982076 + outer loop + vertex 1.07351 1.10351 2.58469 + vertex 1.07838 1.10829 2.58457 + vertex 1.0737 1.10862 2.5853 + endloop + endfacet + facet normal 0.140764 -0.136045 0.980651 + outer loop + vertex 1.07497 1.1126 2.58567 + vertex 1.07148 1.11093 2.58594 + vertex 1.0737 1.10862 2.5853 + endloop + endfacet + facet normal 0.144364 -0.143831 0.979016 + outer loop + vertex 1.07497 1.1126 2.58567 + vertex 1.07398 1.11487 2.58615 + vertex 1.07148 1.11093 2.58594 + endloop + endfacet + facet normal 0.138725 -0.14638 0.979453 + outer loop + vertex 1.07717 1.11543 2.58578 + vertex 1.07398 1.11487 2.58615 + vertex 1.07497 1.1126 2.58567 + endloop + endfacet + facet normal 0.138669 -0.14602 0.979515 + outer loop + vertex 1.07717 1.11543 2.58578 + vertex 1.0783 1.11907 2.58616 + vertex 1.07398 1.11487 2.58615 + endloop + endfacet + facet normal 0.137272 -0.144587 0.979924 + outer loop + vertex 1.0783 1.11907 2.58616 + vertex 1.0734 1.11848 2.58676 + vertex 1.07398 1.11487 2.58615 + endloop + endfacet + facet normal 0.14718 -0.157821 0.976438 + outer loop + vertex 1.08505 1.12235 2.5857 + vertex 1.08208 1.12028 2.58581 + vertex 1.08376 1.1184 2.58526 + endloop + endfacet + facet normal 0.151364 -0.159093 0.975591 + outer loop + vertex 1.08505 1.12235 2.5857 + vertex 1.08376 1.1184 2.58526 + vertex 1.08887 1.12341 2.58528 + endloop + endfacet + facet normal 0.153355 -0.166898 0.973975 + outer loop + vertex 1.08887 1.12341 2.58528 + vertex 1.08721 1.12528 2.58586 + vertex 1.08505 1.12235 2.5857 + endloop + endfacet + facet normal 0.143671 -0.159909 0.976621 + outer loop + vertex 1.08721 1.12528 2.58586 + vertex 1.08327 1.12398 2.58623 + vertex 1.08505 1.12235 2.5857 + endloop + endfacet + facet normal 0.145154 -0.164684 0.975607 + outer loop + vertex 1.08721 1.12528 2.58586 + vertex 1.08841 1.12895 2.5863 + vertex 1.08327 1.12398 2.58623 + endloop + endfacet + facet normal 0.148904 -0.165824 0.974849 + outer loop + vertex 1.09023 1.12732 2.58575 + vertex 1.08841 1.12895 2.5863 + vertex 1.08721 1.12528 2.58586 + endloop + endfacet + facet normal 0.148259 -0.166535 0.974826 + outer loop + vertex 1.09238 1.13018 2.58591 + vertex 1.08841 1.12895 2.5863 + vertex 1.09023 1.12732 2.58575 + endloop + endfacet + facet normal 0.152463 -0.16963 0.973643 + outer loop + vertex 1.094 1.12832 2.58533 + vertex 1.09238 1.13018 2.58591 + vertex 1.09023 1.12732 2.58575 + endloop + endfacet + facet normal 0.152419 -0.169447 0.973682 + outer loop + vertex 1.09023 1.12732 2.58575 + vertex 1.08887 1.12341 2.58528 + vertex 1.094 1.12832 2.58533 + endloop + endfacet + facet normal 0.155122 -0.172262 0.972761 + outer loop + vertex 1.094 1.12832 2.58533 + vertex 1.08887 1.12341 2.58528 + vertex 1.09348 1.1233 2.58453 + endloop + endfacet + facet normal 0.144316 -0.17143 0.974569 + outer loop + vertex 1.09348 1.1233 2.58453 + vertex 1.09853 1.12823 2.58465 + vertex 1.094 1.12832 2.58533 + endloop + endfacet + facet normal 0.144505 -0.167181 0.975279 + outer loop + vertex 1.09896 1.13302 2.5854 + vertex 1.094 1.12832 2.58533 + vertex 1.09853 1.12823 2.58465 + endloop + endfacet + facet normal 0.130893 -0.166294 0.97735 + outer loop + vertex 1.09853 1.12823 2.58465 + vertex 1.10348 1.13315 2.58482 + vertex 1.09896 1.13302 2.5854 + endloop + endfacet + facet normal 0.130895 -0.166665 0.977287 + outer loop + vertex 1.10336 1.13709 2.58551 + vertex 1.09896 1.13302 2.5854 + vertex 1.10348 1.13315 2.58482 + endloop + endfacet + facet normal 0.132231 -0.166593 0.977119 + outer loop + vertex 1.10348 1.13315 2.58482 + vertex 1.10842 1.13865 2.58509 + vertex 1.10336 1.13709 2.58551 + endloop + endfacet + facet normal 0.138943 -0.189641 0.971973 + outer loop + vertex 1.10336 1.13709 2.58551 + vertex 1.10842 1.13865 2.58509 + vertex 1.10627 1.14118 2.58589 + endloop + endfacet + facet normal 0.119471 -0.176248 0.977069 + outer loop + vertex 1.10252 1.13943 2.58603 + vertex 1.10336 1.13709 2.58551 + vertex 1.10627 1.14118 2.58589 + endloop + endfacet + facet normal 0.122485 -0.182825 0.975486 + outer loop + vertex 1.10627 1.14118 2.58589 + vertex 1.10391 1.14351 2.58662 + vertex 1.10252 1.13943 2.58603 + endloop + endfacet + facet normal 0.138706 -0.187885 0.972348 + outer loop + vertex 1.10252 1.13943 2.58603 + vertex 1.10391 1.14351 2.58662 + vertex 1.09856 1.13856 2.58643 + endloop + endfacet + facet normal 0.137807 -0.18334 0.973342 + outer loop + vertex 1.10252 1.13943 2.58603 + vertex 1.09856 1.13856 2.58643 + vertex 1.10024 1.13667 2.58584 + endloop + endfacet + facet normal 0.146367 -0.175778 0.973488 + outer loop + vertex 1.10024 1.13667 2.58584 + vertex 1.09856 1.13856 2.58643 + vertex 1.09742 1.13491 2.58594 + endloop + endfacet + facet normal 0.139575 -0.164695 0.976419 + outer loop + vertex 1.10024 1.13667 2.58584 + vertex 1.09742 1.13491 2.58594 + vertex 1.09896 1.13302 2.5854 + endloop + endfacet + facet normal 0.142696 -0.162156 0.976393 + outer loop + vertex 1.09896 1.13302 2.5854 + vertex 1.09742 1.13491 2.58594 + vertex 1.09535 1.13214 2.58579 + endloop + endfacet + facet normal 0.150612 -0.167954 0.974221 + outer loop + vertex 1.09742 1.13491 2.58594 + vertex 1.09351 1.13381 2.58636 + vertex 1.09535 1.13214 2.58579 + endloop + endfacet + facet normal 0.151428 -0.167065 0.974248 + outer loop + vertex 1.09535 1.13214 2.58579 + vertex 1.09351 1.13381 2.58636 + vertex 1.09238 1.13018 2.58591 + endloop + endfacet + facet normal 0.153143 -0.177715 0.972093 + outer loop + vertex 1.09742 1.13491 2.58594 + vertex 1.09856 1.13856 2.58643 + vertex 1.09351 1.13381 2.58636 + endloop + endfacet + facet normal 0.143294 -0.167285 0.97544 + outer loop + vertex 1.09856 1.13856 2.58643 + vertex 1.09343 1.13831 2.58714 + vertex 1.09351 1.13381 2.58636 + endloop + endfacet + facet normal 0.145369 -0.167198 0.975148 + outer loop + vertex 1.09351 1.13381 2.58636 + vertex 1.09343 1.13831 2.58714 + vertex 1.08842 1.1334 2.58705 + endloop + endfacet + facet normal 0.145133 -0.16298 0.975896 + outer loop + vertex 1.09351 1.13381 2.58636 + vertex 1.08842 1.1334 2.58705 + vertex 1.08841 1.12895 2.5863 + endloop + endfacet + facet normal 0.138191 -0.163126 0.976879 + outer loop + vertex 1.08841 1.12895 2.5863 + vertex 1.08842 1.1334 2.58705 + vertex 1.08334 1.12841 2.58693 + endloop + endfacet + facet normal 0.140695 -0.162453 0.976634 + outer loop + vertex 1.08842 1.1334 2.58705 + vertex 1.09343 1.13831 2.58714 + vertex 1.08827 1.13809 2.58785 + endloop + endfacet + facet normal 0.143476 -0.175233 0.974016 + outer loop + vertex 1.09856 1.13856 2.58643 + vertex 1.09848 1.14324 2.58728 + vertex 1.09343 1.13831 2.58714 + endloop + endfacet + facet normal 0.13576 -0.167408 0.976496 + outer loop + vertex 1.09343 1.13831 2.58714 + vertex 1.09848 1.14324 2.58728 + vertex 1.09325 1.14308 2.58798 + endloop + endfacet + facet normal 0.127471 -0.175906 0.976119 + outer loop + vertex 1.10391 1.14351 2.58662 + vertex 1.09848 1.14324 2.58728 + vertex 1.09856 1.13856 2.58643 + endloop + endfacet + facet normal 0.127352 -0.171607 0.976899 + outer loop + vertex 1.10391 1.14351 2.58662 + vertex 1.10352 1.14833 2.58752 + vertex 1.09848 1.14324 2.58728 + endloop + endfacet + facet normal 0.125883 -0.170173 0.977341 + outer loop + vertex 1.09848 1.14324 2.58728 + vertex 1.10352 1.14833 2.58752 + vertex 1.09829 1.14813 2.58816 + endloop + endfacet + facet normal 0.128388 -0.1715 0.976783 + outer loop + vertex 1.10391 1.14351 2.58662 + vertex 1.1086 1.14886 2.58695 + vertex 1.10352 1.14833 2.58752 + endloop + endfacet + facet normal 0.126732 -0.152071 0.980211 + outer loop + vertex 1.1086 1.14886 2.58695 + vertex 1.10831 1.15337 2.58768 + vertex 1.10352 1.14833 2.58752 + endloop + endfacet + facet normal 0.137492 -0.162197 0.977132 + outer loop + vertex 1.10352 1.14833 2.58752 + vertex 1.10831 1.15337 2.58768 + vertex 1.10338 1.15325 2.58836 + endloop + endfacet + facet normal 0.18199 -0.147247 0.972213 + outer loop + vertex 1.1086 1.14886 2.58695 + vertex 1.11284 1.15349 2.58685 + vertex 1.10831 1.15337 2.58768 + endloop + endfacet + facet normal 0.181994 -0.123393 0.975527 + outer loop + vertex 1.11284 1.15349 2.58685 + vertex 1.11253 1.15804 2.58749 + vertex 1.10831 1.15337 2.58768 + endloop + endfacet + facet normal 0.201382 -0.141182 0.969285 + outer loop + vertex 1.10831 1.15337 2.58768 + vertex 1.11253 1.15804 2.58749 + vertex 1.10817 1.15814 2.58841 + endloop + endfacet + facet normal 0.160624 -0.127509 0.978745 + outer loop + vertex 1.11322 1.14929 2.58624 + vertex 1.11284 1.15349 2.58685 + vertex 1.1086 1.14886 2.58695 + endloop + endfacet + facet normal 0.162462 -0.154105 0.974606 + outer loop + vertex 1.11322 1.14929 2.58624 + vertex 1.1086 1.14886 2.58695 + vertex 1.10914 1.14528 2.58629 + endloop + endfacet + facet normal 0.147376 -0.138701 0.979307 + outer loop + vertex 1.11235 1.14583 2.58589 + vertex 1.11322 1.14929 2.58624 + vertex 1.10914 1.14528 2.58629 + endloop + endfacet + facet normal 0.153972 -0.183577 0.970872 + outer loop + vertex 1.11235 1.14583 2.58589 + vertex 1.10914 1.14528 2.58629 + vertex 1.11005 1.14298 2.58571 + endloop + endfacet + facet normal 0.222444 -0.237237 0.945641 + outer loop + vertex 1.11376 1.14367 2.58501 + vertex 1.11235 1.14583 2.58589 + vertex 1.11005 1.14298 2.58571 + endloop + endfacet + facet normal 0.220039 -0.219159 0.950554 + outer loop + vertex 1.11005 1.14298 2.58571 + vertex 1.10842 1.13865 2.58509 + vertex 1.11376 1.14367 2.58501 + endloop + endfacet + facet normal 0.182575 -0.179051 0.966751 + outer loop + vertex 1.11376 1.14367 2.58501 + vertex 1.10842 1.13865 2.58509 + vertex 1.11338 1.13858 2.58414 + endloop + endfacet + facet normal 0.295554 -0.182378 0.937756 + outer loop + vertex 1.11338 1.13858 2.58414 + vertex 1.11786 1.14313 2.58361 + vertex 1.11376 1.14367 2.58501 + endloop + endfacet + facet normal 0.302666 -0.140849 0.942632 + outer loop + vertex 1.11829 1.14782 2.58418 + vertex 1.11376 1.14367 2.58501 + vertex 1.11786 1.14313 2.58361 + endloop + endfacet + facet normal 0.387835 -0.244704 0.888653 + outer loop + vertex 1.11503 1.14752 2.58551 + vertex 1.11376 1.14367 2.58501 + vertex 1.11829 1.14782 2.58418 + endloop + endfacet + facet normal 0.388134 -0.19987 0.899669 + outer loop + vertex 1.11829 1.14782 2.58418 + vertex 1.11675 1.15018 2.58536 + vertex 1.11503 1.14752 2.58551 + endloop + endfacet + facet normal 0.26818 -0.119143 0.955973 + outer loop + vertex 1.11675 1.15018 2.58536 + vertex 1.11322 1.14929 2.58624 + vertex 1.11503 1.14752 2.58551 + endloop + endfacet + facet normal 0.244465 -0.129416 0.960983 + outer loop + vertex 1.11784 1.13833 2.58297 + vertex 1.11786 1.14313 2.58361 + vertex 1.11338 1.13858 2.58414 + endloop + endfacet + facet normal 0.242858 -0.147705 0.958751 + outer loop + vertex 1.11334 1.13345 2.58336 + vertex 1.11784 1.13833 2.58297 + vertex 1.11338 1.13858 2.58414 + endloop + endfacet + facet normal 0.162122 -0.14962 0.975362 + outer loop + vertex 1.11334 1.13345 2.58336 + vertex 1.11338 1.13858 2.58414 + vertex 1.1084 1.13341 2.58418 + endloop + endfacet + facet normal 0.161854 -0.163664 0.973148 + outer loop + vertex 1.10839 1.12827 2.58331 + vertex 1.11334 1.13345 2.58336 + vertex 1.1084 1.13341 2.58418 + endloop + endfacet + facet normal 0.132531 -0.164362 0.977456 + outer loop + vertex 1.10839 1.12827 2.58331 + vertex 1.1084 1.13341 2.58418 + vertex 1.10332 1.1282 2.58399 + endloop + endfacet + facet normal 0.132437 -0.17386 0.975824 + outer loop + vertex 1.10329 1.12315 2.58309 + vertex 1.10839 1.12827 2.58331 + vertex 1.10332 1.1282 2.58399 + endloop + endfacet + facet normal 0.134368 -0.173824 0.975567 + outer loop + vertex 1.10329 1.12315 2.58309 + vertex 1.10332 1.1282 2.58399 + vertex 1.09824 1.12316 2.58379 + endloop + endfacet + facet normal 0.134354 -0.174342 0.975476 + outer loop + vertex 1.09822 1.11815 2.5829 + vertex 1.10329 1.12315 2.58309 + vertex 1.09824 1.12316 2.58379 + endloop + endfacet + facet normal 0.149202 -0.174018 0.973374 + outer loop + vertex 1.09822 1.11815 2.5829 + vertex 1.09824 1.12316 2.58379 + vertex 1.0932 1.11817 2.58367 + endloop + endfacet + facet normal 0.149411 -0.167145 0.974546 + outer loop + vertex 1.09322 1.1132 2.58281 + vertex 1.09822 1.11815 2.5829 + vertex 1.0932 1.11817 2.58367 + endloop + endfacet + facet normal 0.16559 -0.166676 0.972008 + outer loop + vertex 1.09322 1.1132 2.58281 + vertex 1.0932 1.11817 2.58367 + vertex 1.08821 1.11316 2.58366 + endloop + endfacet + facet normal 0.165796 -0.156608 0.973646 + outer loop + vertex 1.08821 1.10822 2.58286 + vertex 1.09322 1.1132 2.58281 + vertex 1.08821 1.11316 2.58366 + endloop + endfacet + facet normal 0.175055 -0.156343 0.972066 + outer loop + vertex 1.08821 1.10822 2.58286 + vertex 1.08821 1.11316 2.58366 + vertex 1.08321 1.10813 2.58375 + endloop + endfacet + facet normal 0.175171 -0.145309 0.973756 + outer loop + vertex 1.08318 1.10319 2.58302 + vertex 1.08821 1.10822 2.58286 + vertex 1.08321 1.10813 2.58375 + endloop + endfacet + facet normal 0.190149 -0.160473 0.968551 + outer loop + vertex 1.08822 1.10358 2.58209 + vertex 1.08821 1.10822 2.58286 + vertex 1.08318 1.10319 2.58302 + endloop + endfacet + facet normal 0.189776 -0.152282 0.969946 + outer loop + vertex 1.08316 1.09851 2.58229 + vertex 1.08822 1.10358 2.58209 + vertex 1.08318 1.10319 2.58302 + endloop + endfacet + facet normal 0.21513 -0.177962 0.960234 + outer loop + vertex 1.08809 1.09914 2.5813 + vertex 1.08822 1.10358 2.58209 + vertex 1.08316 1.09851 2.58229 + endloop + endfacet + facet normal 0.21376 -0.16244 0.963286 + outer loop + vertex 1.08809 1.09914 2.5813 + vertex 1.08316 1.09851 2.58229 + vertex 1.08319 1.09397 2.58152 + endloop + endfacet + facet normal 0.1871 -0.178136 0.966054 + outer loop + vertex 1.09319 1.1041 2.58123 + vertex 1.08822 1.10358 2.58209 + vertex 1.08809 1.09914 2.5813 + endloop + endfacet + facet normal 0.209143 -0.200923 0.957021 + outer loop + vertex 1.09193 1.10043 2.58073 + vertex 1.09319 1.1041 2.58123 + vertex 1.08809 1.09914 2.5813 + endloop + endfacet + facet normal 0.209473 -0.202037 0.956714 + outer loop + vertex 1.09193 1.10043 2.58073 + vertex 1.08809 1.09914 2.5813 + vertex 1.08984 1.09756 2.58058 + endloop + endfacet + facet normal 0.175626 -0.178043 0.968223 + outer loop + vertex 1.09362 1.09854 2.58008 + vertex 1.09193 1.10043 2.58073 + vertex 1.08984 1.09756 2.58058 + endloop + endfacet + facet normal 0.171929 -0.162014 0.971695 + outer loop + vertex 1.08984 1.09756 2.58058 + vertex 1.08884 1.09376 2.58013 + vertex 1.09362 1.09854 2.58008 + endloop + endfacet + facet normal 0.186703 -0.176835 0.96637 + outer loop + vertex 1.09362 1.09854 2.58008 + vertex 1.08884 1.09376 2.58013 + vertex 1.0933 1.09346 2.57921 + endloop + endfacet + facet normal 0.160139 -0.175997 0.971278 + outer loop + vertex 1.0933 1.09346 2.57921 + vertex 1.09826 1.09832 2.57927 + vertex 1.09362 1.09854 2.58008 + endloop + endfacet + facet normal 0.159488 -0.184606 0.969786 + outer loop + vertex 1.09874 1.10344 2.58017 + vertex 1.09362 1.09854 2.58008 + vertex 1.09826 1.09832 2.57927 + endloop + endfacet + facet normal 0.146329 -0.183762 0.972018 + outer loop + vertex 1.09826 1.09832 2.57927 + vertex 1.10339 1.1033 2.57944 + vertex 1.09874 1.10344 2.58017 + endloop + endfacet + facet normal 0.146503 -0.180725 0.972561 + outer loop + vertex 1.10394 1.10833 2.5803 + vertex 1.09874 1.10344 2.58017 + vertex 1.10339 1.1033 2.57944 + endloop + endfacet + facet normal 0.138683 -0.180097 0.973823 + outer loop + vertex 1.10339 1.1033 2.57944 + vertex 1.10856 1.10828 2.57963 + vertex 1.10394 1.10833 2.5803 + endloop + endfacet + facet normal 0.138813 -0.176481 0.974467 + outer loop + vertex 1.10902 1.11306 2.58043 + vertex 1.10394 1.10833 2.5803 + vertex 1.10856 1.10828 2.57963 + endloop + endfacet + facet normal 0.140575 -0.176603 0.974192 + outer loop + vertex 1.10856 1.10828 2.57963 + vertex 1.1136 1.11323 2.5798 + vertex 1.10902 1.11306 2.58043 + endloop + endfacet + facet normal 0.140673 -0.185744 0.972476 + outer loop + vertex 1.11353 1.11715 2.58056 + vertex 1.10902 1.11306 2.58043 + vertex 1.1136 1.11323 2.5798 + endloop + endfacet + facet normal 0.174493 -0.184096 0.967296 + outer loop + vertex 1.1136 1.11323 2.5798 + vertex 1.11844 1.11867 2.57996 + vertex 1.11353 1.11715 2.58056 + endloop + endfacet + facet normal 0.183547 -0.216582 0.958855 + outer loop + vertex 1.11353 1.11715 2.58056 + vertex 1.11844 1.11867 2.57996 + vertex 1.1164 1.12121 2.58093 + endloop + endfacet + facet normal 0.14649 -0.191452 0.970509 + outer loop + vertex 1.1127 1.11948 2.58114 + vertex 1.11353 1.11715 2.58056 + vertex 1.1164 1.12121 2.58093 + endloop + endfacet + facet normal 0.142227 -0.182049 0.972949 + outer loop + vertex 1.1164 1.12121 2.58093 + vertex 1.11397 1.12355 2.58172 + vertex 1.1127 1.11948 2.58114 + endloop + endfacet + facet normal 0.129974 -0.178548 0.975309 + outer loop + vertex 1.1127 1.11948 2.58114 + vertex 1.11397 1.12355 2.58172 + vertex 1.10864 1.11859 2.58152 + endloop + endfacet + facet normal 0.132373 -0.190533 0.972715 + outer loop + vertex 1.1127 1.11948 2.58114 + vertex 1.10864 1.11859 2.58152 + vertex 1.11036 1.11671 2.58092 + endloop + endfacet + facet normal 0.135564 -0.187653 0.972835 + outer loop + vertex 1.11036 1.11671 2.58092 + vertex 1.10864 1.11859 2.58152 + vertex 1.10745 1.11493 2.58098 + endloop + endfacet + facet normal 0.130047 -0.17854 0.975301 + outer loop + vertex 1.11036 1.11671 2.58092 + vertex 1.10745 1.11493 2.58098 + vertex 1.10902 1.11306 2.58043 + endloop + endfacet + facet normal 0.134348 -0.174951 0.975368 + outer loop + vertex 1.10902 1.11306 2.58043 + vertex 1.10745 1.11493 2.58098 + vertex 1.10531 1.11215 2.58078 + endloop + endfacet + facet normal 0.140787 -0.17977 0.973582 + outer loop + vertex 1.10745 1.11493 2.58098 + vertex 1.10347 1.11382 2.58135 + vertex 1.10531 1.11215 2.58078 + endloop + endfacet + facet normal 0.144101 -0.176178 0.973754 + outer loop + vertex 1.10531 1.11215 2.58078 + vertex 1.10347 1.11382 2.58135 + vertex 1.10231 1.11019 2.58087 + endloop + endfacet + facet normal 0.14255 -0.17377 0.974415 + outer loop + vertex 1.10531 1.11215 2.58078 + vertex 1.10231 1.11019 2.58087 + vertex 1.10394 1.10833 2.5803 + endloop + endfacet + facet normal 0.143612 -0.172847 0.974423 + outer loop + vertex 1.10394 1.10833 2.5803 + vertex 1.10231 1.11019 2.58087 + vertex 1.10014 1.10733 2.58068 + endloop + endfacet + facet normal 0.14972 -0.17737 0.972689 + outer loop + vertex 1.10231 1.11019 2.58087 + vertex 1.09834 1.10899 2.58126 + vertex 1.10014 1.10733 2.58068 + endloop + endfacet + facet normal 0.150131 -0.17693 0.972706 + outer loop + vertex 1.10014 1.10733 2.58068 + vertex 1.09834 1.10899 2.58126 + vertex 1.09712 1.10533 2.58078 + endloop + endfacet + facet normal 0.153488 -0.182073 0.971232 + outer loop + vertex 1.10014 1.10733 2.58068 + vertex 1.09712 1.10533 2.58078 + vertex 1.09874 1.10344 2.58017 + endloop + endfacet + facet normal 0.154372 -0.181316 0.971233 + outer loop + vertex 1.09874 1.10344 2.58017 + vertex 1.09712 1.10533 2.58078 + vertex 1.09493 1.10244 2.58059 + endloop + endfacet + facet normal 0.170745 -0.193383 0.966152 + outer loop + vertex 1.09712 1.10533 2.58078 + vertex 1.09319 1.1041 2.58123 + vertex 1.09493 1.10244 2.58059 + endloop + endfacet + facet normal 0.167573 -0.182251 0.968867 + outer loop + vertex 1.09712 1.10533 2.58078 + vertex 1.09834 1.10899 2.58126 + vertex 1.09319 1.1041 2.58123 + endloop + endfacet + facet normal 0.160702 -0.17502 0.971361 + outer loop + vertex 1.09834 1.10899 2.58126 + vertex 1.09329 1.10854 2.58201 + vertex 1.09319 1.1041 2.58123 + endloop + endfacet + facet normal 0.160492 -0.17157 0.972011 + outer loop + vertex 1.09834 1.10899 2.58126 + vertex 1.09835 1.11345 2.58204 + vertex 1.09329 1.10854 2.58201 + endloop + endfacet + facet normal 0.154352 -0.165256 0.974098 + outer loop + vertex 1.09329 1.10854 2.58201 + vertex 1.09835 1.11345 2.58204 + vertex 1.09322 1.1132 2.58281 + endloop + endfacet + facet normal 0.144296 -0.171986 0.974474 + outer loop + vertex 1.10347 1.11382 2.58135 + vertex 1.09835 1.11345 2.58204 + vertex 1.09834 1.10899 2.58126 + endloop + endfacet + facet normal 0.144649 -0.179458 0.973073 + outer loop + vertex 1.10347 1.11382 2.58135 + vertex 1.10342 1.11833 2.58219 + vertex 1.09835 1.11345 2.58204 + endloop + endfacet + facet normal 0.138464 -0.173096 0.975123 + outer loop + vertex 1.09835 1.11345 2.58204 + vertex 1.10342 1.11833 2.58219 + vertex 1.09822 1.11815 2.5829 + endloop + endfacet + facet normal 0.133967 -0.179846 0.97453 + outer loop + vertex 1.10864 1.11859 2.58152 + vertex 1.10342 1.11833 2.58219 + vertex 1.10347 1.11382 2.58135 + endloop + endfacet + facet normal 0.134039 -0.182853 0.97396 + outer loop + vertex 1.10864 1.11859 2.58152 + vertex 1.10856 1.12331 2.58242 + vertex 1.10342 1.11833 2.58219 + endloop + endfacet + facet normal 0.130203 -0.178946 0.975205 + outer loop + vertex 1.10342 1.11833 2.58219 + vertex 1.10856 1.12331 2.58242 + vertex 1.10329 1.12315 2.58309 + endloop + endfacet + facet normal 0.149858 -0.177863 0.972578 + outer loop + vertex 1.10231 1.11019 2.58087 + vertex 1.10347 1.11382 2.58135 + vertex 1.09834 1.10899 2.58126 + endloop + endfacet + facet normal 0.143429 -0.189986 0.971253 + outer loop + vertex 1.10745 1.11493 2.58098 + vertex 1.10864 1.11859 2.58152 + vertex 1.10347 1.11382 2.58135 + endloop + endfacet + facet normal 0.134029 -0.182854 0.973961 + outer loop + vertex 1.11397 1.12355 2.58172 + vertex 1.10856 1.12331 2.58242 + vertex 1.10864 1.11859 2.58152 + endloop + endfacet + facet normal 0.13357 -0.161092 0.977859 + outer loop + vertex 1.11397 1.12355 2.58172 + vertex 1.11351 1.12842 2.58258 + vertex 1.10856 1.12331 2.58242 + endloop + endfacet + facet normal 0.143741 -0.170826 0.97476 + outer loop + vertex 1.10856 1.12331 2.58242 + vertex 1.11351 1.12842 2.58258 + vertex 1.10839 1.12827 2.58331 + endloop + endfacet + facet normal 0.169349 -0.156787 0.973005 + outer loop + vertex 1.11397 1.12355 2.58172 + vertex 1.11818 1.12871 2.58182 + vertex 1.11351 1.12842 2.58258 + endloop + endfacet + facet normal 0.16763 -0.112659 0.979392 + outer loop + vertex 1.11818 1.12871 2.58182 + vertex 1.11794 1.13335 2.58239 + vertex 1.11351 1.12842 2.58258 + endloop + endfacet + facet normal 0.200892 -0.142932 0.96913 + outer loop + vertex 1.11351 1.12842 2.58258 + vertex 1.11794 1.13335 2.58239 + vertex 1.11334 1.13345 2.58336 + endloop + endfacet + facet normal 0.142726 -0.135241 0.980479 + outer loop + vertex 1.11889 1.12518 2.58123 + vertex 1.11818 1.12871 2.58182 + vertex 1.11397 1.12355 2.58172 + endloop + endfacet + facet normal 0.226953 -0.116018 0.966971 + outer loop + vertex 1.12178 1.1287 2.58097 + vertex 1.11818 1.12871 2.58182 + vertex 1.11889 1.12518 2.58123 + endloop + endfacet + facet normal 0.22222 -0.112024 0.96854 + outer loop + vertex 1.12178 1.12572 2.58063 + vertex 1.12178 1.1287 2.58097 + vertex 1.11889 1.12518 2.58123 + endloop + endfacet + facet normal 0.230698 -0.169254 0.958192 + outer loop + vertex 1.12178 1.12572 2.58063 + vertex 1.11889 1.12518 2.58123 + vertex 1.11995 1.12296 2.58058 + endloop + endfacet + facet normal 0.188044 -0.19116 0.963378 + outer loop + vertex 1.11995 1.12296 2.58058 + vertex 1.11889 1.12518 2.58123 + vertex 1.1164 1.12121 2.58093 + endloop + endfacet + facet normal 0.153649 -0.170298 0.97334 + outer loop + vertex 1.11889 1.12518 2.58123 + vertex 1.11397 1.12355 2.58172 + vertex 1.1164 1.12121 2.58093 + endloop + endfacet + facet normal 0.137543 -0.194776 0.971156 + outer loop + vertex 1.11353 1.11715 2.58056 + vertex 1.1127 1.11948 2.58114 + vertex 1.11036 1.11671 2.58092 + endloop + endfacet + facet normal 0.195375 -0.206992 0.958636 + outer loop + vertex 1.11995 1.12296 2.58058 + vertex 1.1164 1.12121 2.58093 + vertex 1.11844 1.11867 2.57996 + endloop + endfacet + facet normal 0.344318 -0.251572 0.90452 + outer loop + vertex 1.11995 1.12296 2.58058 + vertex 1.11844 1.11867 2.57996 + vertex 1.12318 1.12365 2.57954 + endloop + endfacet + facet normal 0.343366 -0.243105 0.907193 + outer loop + vertex 1.12318 1.12365 2.57954 + vertex 1.12178 1.12572 2.58063 + vertex 1.11995 1.12296 2.58058 + endloop + endfacet + facet normal 0.258276 -0.165829 0.951732 + outer loop + vertex 1.12318 1.12365 2.57954 + vertex 1.11844 1.11867 2.57996 + vertex 1.123 1.11838 2.57867 + endloop + endfacet + facet normal 0.257228 -0.175731 0.950238 + outer loop + vertex 1.11841 1.11344 2.579 + vertex 1.123 1.11838 2.57867 + vertex 1.11844 1.11867 2.57996 + endloop + endfacet + facet normal 0.213552 -0.133973 0.967702 + outer loop + vertex 1.12301 1.11325 2.57796 + vertex 1.123 1.11838 2.57867 + vertex 1.11841 1.11344 2.579 + endloop + endfacet + facet normal 0.211596 -0.161166 0.963978 + outer loop + vertex 1.11838 1.10836 2.57816 + vertex 1.12301 1.11325 2.57796 + vertex 1.11841 1.11344 2.579 + endloop + endfacet + facet normal 0.153428 -0.162649 0.974682 + outer loop + vertex 1.11838 1.10836 2.57816 + vertex 1.11841 1.11344 2.579 + vertex 1.11341 1.10831 2.57893 + endloop + endfacet + facet normal 0.153162 -0.178733 0.971903 + outer loop + vertex 1.11338 1.10329 2.57801 + vertex 1.11838 1.10836 2.57816 + vertex 1.11341 1.10831 2.57893 + endloop + endfacet + facet normal 0.137619 -0.179069 0.974164 + outer loop + vertex 1.11338 1.10329 2.57801 + vertex 1.11341 1.10831 2.57893 + vertex 1.10827 1.10321 2.57872 + endloop + endfacet + facet normal 0.137521 -0.188161 0.972462 + outer loop + vertex 1.10836 1.09821 2.57774 + vertex 1.11338 1.10329 2.57801 + vertex 1.10827 1.10321 2.57872 + endloop + endfacet + facet normal 0.141665 -0.18798 0.971902 + outer loop + vertex 1.10836 1.09821 2.57774 + vertex 1.10827 1.10321 2.57872 + vertex 1.10316 1.09816 2.57849 + endloop + endfacet + facet normal 0.141643 -0.189225 0.971664 + outer loop + vertex 1.10333 1.09321 2.5775 + vertex 1.10836 1.09821 2.57774 + vertex 1.10316 1.09816 2.57849 + endloop + endfacet + facet normal 0.153988 -0.188467 0.969932 + outer loop + vertex 1.10333 1.09321 2.5775 + vertex 1.10316 1.09816 2.57849 + vertex 1.09812 1.0932 2.57833 + endloop + endfacet + facet normal 0.15418 -0.181761 0.97118 + outer loop + vertex 1.09826 1.08832 2.57739 + vertex 1.10333 1.09321 2.5775 + vertex 1.09812 1.0932 2.57833 + endloop + endfacet + facet normal 0.179971 -0.180216 0.967023 + outer loop + vertex 1.09826 1.08832 2.57739 + vertex 1.09812 1.0932 2.57833 + vertex 1.09319 1.08838 2.57835 + endloop + endfacet + facet normal 0.180628 -0.165569 0.969516 + outer loop + vertex 1.09325 1.08348 2.5775 + vertex 1.09826 1.08832 2.57739 + vertex 1.09319 1.08838 2.57835 + endloop + endfacet + facet normal 0.228254 -0.163285 0.959811 + outer loop + vertex 1.09325 1.08348 2.5775 + vertex 1.09319 1.08838 2.57835 + vertex 1.08842 1.08378 2.5787 + endloop + endfacet + facet normal 0.207038 -0.140689 0.968164 + outer loop + vertex 1.08842 1.08378 2.5787 + vertex 1.09319 1.08838 2.57835 + vertex 1.0887 1.08887 2.57938 + endloop + endfacet + facet normal 0.203127 -0.168698 0.96451 + outer loop + vertex 1.09319 1.08838 2.57835 + vertex 1.0933 1.09346 2.57921 + vertex 1.0887 1.08887 2.57938 + endloop + endfacet + facet normal 0.198267 -0.184021 0.962718 + outer loop + vertex 1.09842 1.08374 2.57648 + vertex 1.09826 1.08832 2.57739 + vertex 1.09325 1.08348 2.5775 + endloop + endfacet + facet normal 0.19821 -0.179038 0.963669 + outer loop + vertex 1.09842 1.08374 2.57648 + vertex 1.09325 1.08348 2.5775 + vertex 1.09336 1.07878 2.5766 + endloop + endfacet + facet normal 0.226946 -0.208713 0.951281 + outer loop + vertex 1.09738 1.08011 2.57593 + vertex 1.09842 1.08374 2.57648 + vertex 1.09336 1.07878 2.5766 + endloop + endfacet + facet normal 0.227553 -0.210865 0.950661 + outer loop + vertex 1.09738 1.08011 2.57593 + vertex 1.09336 1.07878 2.5766 + vertex 1.09544 1.07731 2.57578 + endloop + endfacet + facet normal 0.174804 -0.175469 0.968842 + outer loop + vertex 1.09918 1.07842 2.5753 + vertex 1.09738 1.08011 2.57593 + vertex 1.09544 1.07731 2.57578 + endloop + endfacet + facet normal 0.170996 -0.161349 0.971971 + outer loop + vertex 1.09544 1.07731 2.57578 + vertex 1.09496 1.07412 2.57533 + vertex 1.09918 1.07842 2.5753 + endloop + endfacet + facet normal 0.180045 -0.170247 0.968814 + outer loop + vertex 1.09918 1.07842 2.5753 + vertex 1.09496 1.07412 2.57533 + vertex 1.09865 1.07356 2.57455 + endloop + endfacet + facet normal 0.152745 -0.168038 0.973875 + outer loop + vertex 1.09865 1.07356 2.57455 + vertex 1.10356 1.07827 2.57459 + vertex 1.09918 1.07842 2.5753 + endloop + endfacet + facet normal 0.151833 -0.182589 0.971395 + outer loop + vertex 1.10405 1.08304 2.57541 + vertex 1.09918 1.07842 2.5753 + vertex 1.10356 1.07827 2.57459 + endloop + endfacet + facet normal 0.14234 -0.181877 0.972965 + outer loop + vertex 1.10356 1.07827 2.57459 + vertex 1.10847 1.08309 2.57477 + vertex 1.10405 1.08304 2.57541 + endloop + endfacet + facet normal 0.142279 -0.185964 0.972201 + outer loop + vertex 1.10843 1.08704 2.57554 + vertex 1.10405 1.08304 2.57541 + vertex 1.10847 1.08309 2.57477 + endloop + endfacet + facet normal 0.137322 -0.186152 0.972877 + outer loop + vertex 1.10847 1.08309 2.57477 + vertex 1.1134 1.08845 2.5751 + vertex 1.10843 1.08704 2.57554 + endloop + endfacet + facet normal 0.137466 -0.1867 0.972752 + outer loop + vertex 1.10843 1.08704 2.57554 + vertex 1.1134 1.08845 2.5751 + vertex 1.11127 1.09101 2.5759 + endloop + endfacet + facet normal 0.138887 -0.187682 0.972361 + outer loop + vertex 1.10758 1.08938 2.57611 + vertex 1.10843 1.08704 2.57554 + vertex 1.11127 1.09101 2.5759 + endloop + endfacet + facet normal 0.140751 -0.192059 0.971238 + outer loop + vertex 1.11127 1.09101 2.5759 + vertex 1.10885 1.09338 2.57671 + vertex 1.10758 1.08938 2.57611 + endloop + endfacet + facet normal 0.148555 -0.19429 0.96963 + outer loop + vertex 1.10758 1.08938 2.57611 + vertex 1.10885 1.09338 2.57671 + vertex 1.10355 1.08852 2.57655 + endloop + endfacet + facet normal 0.148114 -0.191956 0.970162 + outer loop + vertex 1.10758 1.08938 2.57611 + vertex 1.10355 1.08852 2.57655 + vertex 1.10535 1.08668 2.57591 + endloop + endfacet + facet normal 0.149466 -0.190647 0.970213 + outer loop + vertex 1.10535 1.08668 2.57591 + vertex 1.10355 1.08852 2.57655 + vertex 1.10248 1.0849 2.57601 + endloop + endfacet + facet normal 0.147187 -0.186908 0.971289 + outer loop + vertex 1.10535 1.08668 2.57591 + vertex 1.10248 1.0849 2.57601 + vertex 1.10405 1.08304 2.57541 + endloop + endfacet + facet normal 0.148424 -0.185865 0.9713 + outer loop + vertex 1.10405 1.08304 2.57541 + vertex 1.10248 1.0849 2.57601 + vertex 1.10038 1.08212 2.5758 + endloop + endfacet + facet normal 0.170869 -0.202235 0.964316 + outer loop + vertex 1.10248 1.0849 2.57601 + vertex 1.09842 1.08374 2.57648 + vertex 1.10038 1.08212 2.5758 + endloop + endfacet + facet normal 0.169217 -0.195837 0.965926 + outer loop + vertex 1.10248 1.0849 2.57601 + vertex 1.10355 1.08852 2.57655 + vertex 1.09842 1.08374 2.57648 + endloop + endfacet + facet normal 0.144198 -0.189585 0.971218 + outer loop + vertex 1.10885 1.09338 2.57671 + vertex 1.10333 1.09321 2.5775 + vertex 1.10355 1.08852 2.57655 + endloop + endfacet + facet normal 0.13801 -0.194804 0.971084 + outer loop + vertex 1.11414 1.09496 2.57628 + vertex 1.10885 1.09338 2.57671 + vertex 1.11127 1.09101 2.5759 + endloop + endfacet + facet normal 0.137185 -0.194226 0.971317 + outer loop + vertex 1.11503 1.09265 2.57569 + vertex 1.11414 1.09496 2.57628 + vertex 1.11127 1.09101 2.5759 + endloop + endfacet + facet normal 0.133441 -0.195712 0.97154 + outer loop + vertex 1.11744 1.09541 2.57592 + vertex 1.11414 1.09496 2.57628 + vertex 1.11503 1.09265 2.57569 + endloop + endfacet + facet normal 0.143759 -0.204474 0.968258 + outer loop + vertex 1.11895 1.09342 2.57527 + vertex 1.11744 1.09541 2.57592 + vertex 1.11503 1.09265 2.57569 + endloop + endfacet + facet normal 0.141451 -0.191167 0.971312 + outer loop + vertex 1.11503 1.09265 2.57569 + vertex 1.1134 1.08845 2.5751 + vertex 1.11895 1.09342 2.57527 + endloop + endfacet + facet normal 0.141493 -0.191214 0.971297 + outer loop + vertex 1.11895 1.09342 2.57527 + vertex 1.1134 1.08845 2.5751 + vertex 1.11849 1.08842 2.57436 + endloop + endfacet + facet normal 0.176922 -0.193291 0.965058 + outer loop + vertex 1.11849 1.08842 2.57436 + vertex 1.12363 1.09344 2.57442 + vertex 1.11895 1.09342 2.57527 + endloop + endfacet + facet normal 0.176932 -0.192985 0.965118 + outer loop + vertex 1.12414 1.09832 2.5753 + vertex 1.11895 1.09342 2.57527 + vertex 1.12363 1.09344 2.57442 + endloop + endfacet + facet normal 0.279749 -0.199104 0.939201 + outer loop + vertex 1.12363 1.09344 2.57442 + vertex 1.12827 1.09829 2.57407 + vertex 1.12414 1.09832 2.5753 + endloop + endfacet + facet normal 0.281244 -0.174219 0.943689 + outer loop + vertex 1.12865 1.10334 2.57488 + vertex 1.12414 1.09832 2.5753 + vertex 1.12827 1.09829 2.57407 + endloop + endfacet + facet normal 0.368183 -0.256572 0.893651 + outer loop + vertex 1.12544 1.10215 2.57587 + vertex 1.12414 1.09832 2.5753 + vertex 1.12865 1.10334 2.57488 + endloop + endfacet + facet normal 0.36172 -0.23138 0.903118 + outer loop + vertex 1.12865 1.10334 2.57488 + vertex 1.1271 1.10506 2.57594 + vertex 1.12544 1.10215 2.57587 + endloop + endfacet + facet normal 0.213141 -0.148043 0.96574 + outer loop + vertex 1.1271 1.10506 2.57594 + vertex 1.12342 1.10376 2.57656 + vertex 1.12544 1.10215 2.57587 + endloop + endfacet + facet normal 0.195018 -0.170712 0.965829 + outer loop + vertex 1.12544 1.10215 2.57587 + vertex 1.12342 1.10376 2.57656 + vertex 1.12258 1.10006 2.57608 + endloop + endfacet + facet normal 0.139534 -0.159515 0.977285 + outer loop + vertex 1.12258 1.10006 2.57608 + vertex 1.12342 1.10376 2.57656 + vertex 1.11866 1.099 2.57646 + endloop + endfacet + facet normal 0.147073 -0.189765 0.970752 + outer loop + vertex 1.12258 1.10006 2.57608 + vertex 1.11866 1.099 2.57646 + vertex 1.12042 1.09721 2.57584 + endloop + endfacet + facet normal 0.208244 -0.234336 0.94959 + outer loop + vertex 1.12414 1.09832 2.5753 + vertex 1.12258 1.10006 2.57608 + vertex 1.12042 1.09721 2.57584 + endloop + endfacet + facet normal 0.141791 -0.194866 0.970527 + outer loop + vertex 1.12042 1.09721 2.57584 + vertex 1.11866 1.099 2.57646 + vertex 1.11744 1.09541 2.57592 + endloop + endfacet + facet normal 0.1581 -0.177991 0.971249 + outer loop + vertex 1.12342 1.10376 2.57656 + vertex 1.11851 1.1035 2.57731 + vertex 1.11866 1.099 2.57646 + endloop + endfacet + facet normal 0.134057 -0.17939 0.974601 + outer loop + vertex 1.11866 1.099 2.57646 + vertex 1.11851 1.1035 2.57731 + vertex 1.11363 1.09863 2.57708 + endloop + endfacet + facet normal 0.134788 -0.194093 0.971679 + outer loop + vertex 1.11866 1.099 2.57646 + vertex 1.11363 1.09863 2.57708 + vertex 1.11414 1.09496 2.57628 + endloop + endfacet + facet normal 0.14139 -0.186622 0.972204 + outer loop + vertex 1.11363 1.09863 2.57708 + vertex 1.11851 1.1035 2.57731 + vertex 1.11338 1.10329 2.57801 + endloop + endfacet + facet normal 0.157241 -0.145419 0.976795 + outer loop + vertex 1.12342 1.10376 2.57656 + vertex 1.12312 1.10834 2.57729 + vertex 1.11851 1.1035 2.57731 + endloop + endfacet + facet normal 0.177702 -0.164921 0.970166 + outer loop + vertex 1.11851 1.1035 2.57731 + vertex 1.12312 1.10834 2.57729 + vertex 1.11838 1.10836 2.57816 + endloop + endfacet + facet normal 0.230504 -0.138397 0.963179 + outer loop + vertex 1.12701 1.10822 2.57634 + vertex 1.12312 1.10834 2.57729 + vertex 1.12342 1.10376 2.57656 + endloop + endfacet + facet normal 0.233765 -0.0793158 0.969053 + outer loop + vertex 1.12701 1.10822 2.57634 + vertex 1.12701 1.11269 2.5767 + vertex 1.12312 1.10834 2.57729 + endloop + endfacet + facet normal 0.202806 -0.115636 0.972367 + outer loop + vertex 1.1271 1.10506 2.57594 + vertex 1.12701 1.10822 2.57634 + vertex 1.12342 1.10376 2.57656 + endloop + endfacet + facet normal 0.227475 -0.216991 0.9493 + outer loop + vertex 1.12544 1.10215 2.57587 + vertex 1.12258 1.10006 2.57608 + vertex 1.12414 1.09832 2.5753 + endloop + endfacet + facet normal 0.226842 -0.146699 0.96282 + outer loop + vertex 1.12805 1.09332 2.57336 + vertex 1.12827 1.09829 2.57407 + vertex 1.12363 1.09344 2.57442 + endloop + endfacet + facet normal 0.224865 -0.177247 0.958133 + outer loop + vertex 1.12342 1.08847 2.57355 + vertex 1.12805 1.09332 2.57336 + vertex 1.12363 1.09344 2.57442 + endloop + endfacet + facet normal 0.19311 -0.146493 0.97018 + outer loop + vertex 1.12814 1.08841 2.5726 + vertex 1.12805 1.09332 2.57336 + vertex 1.12342 1.08847 2.57355 + endloop + endfacet + facet normal 0.191707 -0.179255 0.964944 + outer loop + vertex 1.12354 1.08355 2.57261 + vertex 1.12814 1.08841 2.5726 + vertex 1.12342 1.08847 2.57355 + endloop + endfacet + facet normal 0.151177 -0.181482 0.971705 + outer loop + vertex 1.12354 1.08355 2.57261 + vertex 1.12342 1.08847 2.57355 + vertex 1.11838 1.08338 2.57338 + endloop + endfacet + facet normal 0.151217 -0.197366 0.968597 + outer loop + vertex 1.11843 1.07852 2.57238 + vertex 1.12354 1.08355 2.57261 + vertex 1.11838 1.08338 2.57338 + endloop + endfacet + facet normal 0.146717 -0.197543 0.969253 + outer loop + vertex 1.11843 1.07852 2.57238 + vertex 1.11838 1.08338 2.57338 + vertex 1.1132 1.07825 2.57312 + endloop + endfacet + facet normal 0.146691 -0.196393 0.96949 + outer loop + vertex 1.11321 1.0735 2.57216 + vertex 1.11843 1.07852 2.57238 + vertex 1.1132 1.07825 2.57312 + endloop + endfacet + facet normal 0.154757 -0.196142 0.968286 + outer loop + vertex 1.11321 1.0735 2.57216 + vertex 1.1132 1.07825 2.57312 + vertex 1.10806 1.0732 2.57292 + endloop + endfacet + facet normal 0.154527 -0.188202 0.969898 + outer loop + vertex 1.1081 1.06857 2.57201 + vertex 1.11321 1.0735 2.57216 + vertex 1.10806 1.0732 2.57292 + endloop + endfacet + facet normal 0.16659 -0.187729 0.96799 + outer loop + vertex 1.1081 1.06857 2.57201 + vertex 1.10806 1.0732 2.57292 + vertex 1.10306 1.06828 2.57283 + endloop + endfacet + facet normal 0.166467 -0.182891 0.968937 + outer loop + vertex 1.10329 1.06378 2.57194 + vertex 1.1081 1.06857 2.57201 + vertex 1.10306 1.06828 2.57283 + endloop + endfacet + facet normal 0.193744 -0.180592 0.964287 + outer loop + vertex 1.10329 1.06378 2.57194 + vertex 1.10306 1.06828 2.57283 + vertex 1.0983 1.06349 2.57288 + endloop + endfacet + facet normal 0.193733 -0.18008 0.964385 + outer loop + vertex 1.09875 1.05856 2.57187 + vertex 1.10329 1.06378 2.57194 + vertex 1.0983 1.06349 2.57288 + endloop + endfacet + facet normal 0.206779 -0.191374 0.959489 + outer loop + vertex 1.10383 1.06023 2.57111 + vertex 1.10329 1.06378 2.57194 + vertex 1.09875 1.05856 2.57187 + endloop + endfacet + facet normal 0.213585 -0.214964 0.952981 + outer loop + vertex 1.10383 1.06023 2.57111 + vertex 1.09875 1.05856 2.57187 + vertex 1.10127 1.05628 2.57079 + endloop + endfacet + facet normal 0.188882 -0.199638 0.961493 + outer loop + vertex 1.10475 1.05794 2.57046 + vertex 1.10383 1.06023 2.57111 + vertex 1.10127 1.05628 2.57079 + endloop + endfacet + facet normal 0.182951 -0.186428 0.965284 + outer loop + vertex 1.10475 1.05794 2.57046 + vertex 1.10127 1.05628 2.57079 + vertex 1.10335 1.05374 2.56991 + endloop + endfacet + facet normal 0.162809 -0.18031 0.970042 + outer loop + vertex 1.10475 1.05794 2.57046 + vertex 1.10335 1.05374 2.56991 + vertex 1.1085 1.05861 2.56995 + endloop + endfacet + facet normal 0.165111 -0.195588 0.966687 + outer loop + vertex 1.1085 1.05861 2.56995 + vertex 1.10699 1.06074 2.57064 + vertex 1.10475 1.05794 2.57046 + endloop + endfacet + facet normal 0.162483 -0.197472 0.966749 + outer loop + vertex 1.10981 1.06255 2.57053 + vertex 1.10699 1.06074 2.57064 + vertex 1.1085 1.05861 2.56995 + endloop + endfacet + facet normal 0.159868 -0.196686 0.967345 + outer loop + vertex 1.10981 1.06255 2.57053 + vertex 1.1085 1.05861 2.56995 + vertex 1.11363 1.06349 2.57009 + endloop + endfacet + facet normal 0.158946 -0.192485 0.968342 + outer loop + vertex 1.11363 1.06349 2.57009 + vertex 1.11193 1.0654 2.57075 + vertex 1.10981 1.06255 2.57053 + endloop + endfacet + facet normal 0.162753 -0.195218 0.967162 + outer loop + vertex 1.11193 1.0654 2.57075 + vertex 1.10814 1.0643 2.57117 + vertex 1.10981 1.06255 2.57053 + endloop + endfacet + facet normal 0.161815 -0.191639 0.968034 + outer loop + vertex 1.11193 1.0654 2.57075 + vertex 1.11314 1.06905 2.57128 + vertex 1.10814 1.0643 2.57117 + endloop + endfacet + facet normal 0.160312 -0.190071 0.968593 + outer loop + vertex 1.11314 1.06905 2.57128 + vertex 1.1081 1.06857 2.57201 + vertex 1.10814 1.0643 2.57117 + endloop + endfacet + facet normal 0.159192 -0.190855 0.968624 + outer loop + vertex 1.11495 1.06739 2.57065 + vertex 1.11314 1.06905 2.57128 + vertex 1.11193 1.0654 2.57075 + endloop + endfacet + facet normal 0.159773 -0.191749 0.968352 + outer loop + vertex 1.11495 1.06739 2.57065 + vertex 1.11193 1.0654 2.57075 + vertex 1.11363 1.06349 2.57009 + endloop + endfacet + facet normal 0.148723 -0.188367 0.970773 + outer loop + vertex 1.11495 1.06739 2.57065 + vertex 1.11363 1.06349 2.57009 + vertex 1.11889 1.06842 2.57025 + endloop + endfacet + facet normal 0.151847 -0.191663 0.969643 + outer loop + vertex 1.11889 1.06842 2.57025 + vertex 1.11363 1.06349 2.57009 + vertex 1.11845 1.0634 2.56932 + endloop + endfacet + facet normal 0.146002 -0.191327 0.970607 + outer loop + vertex 1.11845 1.0634 2.56932 + vertex 1.12367 1.06842 2.56953 + vertex 1.11889 1.06842 2.57025 + endloop + endfacet + facet normal 0.145952 -0.193086 0.970266 + outer loop + vertex 1.12409 1.0732 2.57041 + vertex 1.11889 1.06842 2.57025 + vertex 1.12367 1.06842 2.56953 + endloop + endfacet + facet normal 0.172623 -0.194547 0.965584 + outer loop + vertex 1.12367 1.06842 2.56953 + vertex 1.12863 1.07337 2.56964 + vertex 1.12409 1.0732 2.57041 + endloop + endfacet + facet normal 0.172653 -0.208218 0.962723 + outer loop + vertex 1.12853 1.07732 2.57051 + vertex 1.12409 1.0732 2.57041 + vertex 1.12863 1.07337 2.56964 + endloop + endfacet + facet normal 0.258765 -0.202003 0.944582 + outer loop + vertex 1.12863 1.07337 2.56964 + vertex 1.13309 1.07877 2.56957 + vertex 1.12853 1.07732 2.57051 + endloop + endfacet + facet normal 0.268514 -0.239987 0.932902 + outer loop + vertex 1.12853 1.07732 2.57051 + vertex 1.13309 1.07877 2.56957 + vertex 1.13104 1.08137 2.57083 + endloop + endfacet + facet normal 0.211617 -0.206553 0.955277 + outer loop + vertex 1.12769 1.07968 2.57121 + vertex 1.12853 1.07732 2.57051 + vertex 1.13104 1.08137 2.57083 + endloop + endfacet + facet normal 0.19765 -0.176939 0.964172 + outer loop + vertex 1.13104 1.08137 2.57083 + vertex 1.12862 1.08362 2.57174 + vertex 1.12769 1.07968 2.57121 + endloop + endfacet + facet normal 0.143265 -0.165715 0.975712 + outer loop + vertex 1.12769 1.07968 2.57121 + vertex 1.12862 1.08362 2.57174 + vertex 1.12366 1.07878 2.57165 + endloop + endfacet + facet normal 0.149072 -0.195041 0.9694 + outer loop + vertex 1.12769 1.07968 2.57121 + vertex 1.12366 1.07878 2.57165 + vertex 1.12546 1.07689 2.57099 + endloop + endfacet + facet normal 0.141499 -0.202142 0.96908 + outer loop + vertex 1.12546 1.07689 2.57099 + vertex 1.12366 1.07878 2.57165 + vertex 1.12249 1.07508 2.57104 + endloop + endfacet + facet normal 0.142084 -0.203114 0.968791 + outer loop + vertex 1.12546 1.07689 2.57099 + vertex 1.12249 1.07508 2.57104 + vertex 1.12409 1.0732 2.57041 + endloop + endfacet + facet normal 0.143702 -0.201754 0.968837 + outer loop + vertex 1.12409 1.0732 2.57041 + vertex 1.12249 1.07508 2.57104 + vertex 1.12027 1.07226 2.57079 + endloop + endfacet + facet normal 0.147781 -0.204856 0.967572 + outer loop + vertex 1.12249 1.07508 2.57104 + vertex 1.1184 1.07394 2.57143 + vertex 1.12027 1.07226 2.57079 + endloop + endfacet + facet normal 0.147521 -0.203836 0.967827 + outer loop + vertex 1.12249 1.07508 2.57104 + vertex 1.12366 1.07878 2.57165 + vertex 1.1184 1.07394 2.57143 + endloop + endfacet + facet normal 0.14689 -0.203161 0.968065 + outer loop + vertex 1.12366 1.07878 2.57165 + vertex 1.11843 1.07852 2.57238 + vertex 1.1184 1.07394 2.57143 + endloop + endfacet + facet normal 0.168665 -0.191602 0.966872 + outer loop + vertex 1.12862 1.08362 2.57174 + vertex 1.12354 1.08355 2.57261 + vertex 1.12366 1.07878 2.57165 + endloop + endfacet + facet normal 0.216439 -0.156532 0.963666 + outer loop + vertex 1.13253 1.08482 2.57106 + vertex 1.12862 1.08362 2.57174 + vertex 1.13104 1.08137 2.57083 + endloop + endfacet + facet normal 0.20547 -0.116059 0.971757 + outer loop + vertex 1.13253 1.08482 2.57106 + vertex 1.13222 1.08816 2.57152 + vertex 1.12862 1.08362 2.57174 + endloop + endfacet + facet normal 0.24461 -0.147758 0.958297 + outer loop + vertex 1.12862 1.08362 2.57174 + vertex 1.13222 1.08816 2.57152 + vertex 1.12814 1.08841 2.5726 + endloop + endfacet + facet normal 0.179974 -0.218917 0.959002 + outer loop + vertex 1.12853 1.07732 2.57051 + vertex 1.12769 1.07968 2.57121 + vertex 1.12546 1.07689 2.57099 + endloop + endfacet + facet normal 0.226134 -0.174948 0.958257 + outer loop + vertex 1.13314 1.07343 2.56859 + vertex 1.13309 1.07877 2.56957 + vertex 1.12863 1.07337 2.56964 + endloop + endfacet + facet normal 0.22589 -0.18379 0.956658 + outer loop + vertex 1.12848 1.06848 2.56873 + vertex 1.13314 1.07343 2.56859 + vertex 1.12863 1.07337 2.56964 + endloop + endfacet + facet normal 0.195968 -0.155338 0.968229 + outer loop + vertex 1.13309 1.06845 2.5678 + vertex 1.13314 1.07343 2.56859 + vertex 1.12848 1.06848 2.56873 + endloop + endfacet + facet normal 0.194856 -0.182147 0.963771 + outer loop + vertex 1.12848 1.06357 2.5678 + vertex 1.13309 1.06845 2.5678 + vertex 1.12848 1.06848 2.56873 + endloop + endfacet + facet normal 0.152521 -0.183532 0.971109 + outer loop + vertex 1.12848 1.06357 2.5678 + vertex 1.12848 1.06848 2.56873 + vertex 1.12343 1.06341 2.56857 + endloop + endfacet + facet normal 0.152536 -0.200489 0.967748 + outer loop + vertex 1.12345 1.0585 2.56755 + vertex 1.12848 1.06357 2.5678 + vertex 1.12343 1.06341 2.56857 + endloop + endfacet + facet normal 0.148577 -0.200626 0.968336 + outer loop + vertex 1.12345 1.0585 2.56755 + vertex 1.12343 1.06341 2.56857 + vertex 1.11824 1.05833 2.56831 + endloop + endfacet + facet normal 0.148589 -0.204399 0.967545 + outer loop + vertex 1.11824 1.05351 2.56729 + vertex 1.12345 1.0585 2.56755 + vertex 1.11824 1.05833 2.56831 + endloop + endfacet + facet normal 0.158749 -0.204073 0.965998 + outer loop + vertex 1.11824 1.05351 2.56729 + vertex 1.11824 1.05833 2.56831 + vertex 1.11308 1.0533 2.5681 + endloop + endfacet + facet normal 0.158695 -0.19807 0.967256 + outer loop + vertex 1.11313 1.04859 2.56712 + vertex 1.11824 1.05351 2.56729 + vertex 1.11308 1.0533 2.5681 + endloop + endfacet + facet normal 0.175136 -0.197367 0.964559 + outer loop + vertex 1.11313 1.04859 2.56712 + vertex 1.11308 1.0533 2.5681 + vertex 1.1081 1.04835 2.56799 + endloop + endfacet + facet normal 0.175055 -0.190009 0.96605 + outer loop + vertex 1.1083 1.04377 2.56705 + vertex 1.11313 1.04859 2.56712 + vertex 1.1081 1.04835 2.56799 + endloop + endfacet + facet normal 0.20742 -0.187383 0.960138 + outer loop + vertex 1.1083 1.04377 2.56705 + vertex 1.1081 1.04835 2.56799 + vertex 1.10341 1.04352 2.56806 + endloop + endfacet + facet normal 0.207352 -0.181322 0.961315 + outer loop + vertex 1.10382 1.03856 2.56704 + vertex 1.1083 1.04377 2.56705 + vertex 1.10341 1.04352 2.56806 + endloop + endfacet + facet normal 0.225285 -0.196752 0.95422 + outer loop + vertex 1.10881 1.04017 2.56619 + vertex 1.1083 1.04377 2.56705 + vertex 1.10382 1.03856 2.56704 + endloop + endfacet + facet normal 0.231528 -0.219485 0.947745 + outer loop + vertex 1.10881 1.04017 2.56619 + vertex 1.10382 1.03856 2.56704 + vertex 1.10632 1.03628 2.5659 + endloop + endfacet + facet normal 0.205419 -0.203523 0.957278 + outer loop + vertex 1.10975 1.0379 2.56551 + vertex 1.10881 1.04017 2.56619 + vertex 1.10632 1.03628 2.5659 + endloop + endfacet + facet normal 0.199872 -0.190888 0.961048 + outer loop + vertex 1.10975 1.0379 2.56551 + vertex 1.10632 1.03628 2.5659 + vertex 1.10853 1.03391 2.56497 + endloop + endfacet + facet normal 0.172152 -0.18331 0.967864 + outer loop + vertex 1.10975 1.0379 2.56551 + vertex 1.10853 1.03391 2.56497 + vertex 1.11354 1.03861 2.56497 + endloop + endfacet + facet normal 0.174489 -0.198344 0.964476 + outer loop + vertex 1.11354 1.03861 2.56497 + vertex 1.11197 1.04068 2.56568 + vertex 1.10975 1.0379 2.56551 + endloop + endfacet + facet normal 0.169483 -0.202177 0.964572 + outer loop + vertex 1.11485 1.04251 2.56555 + vertex 1.11197 1.04068 2.56568 + vertex 1.11354 1.03861 2.56497 + endloop + endfacet + facet normal 0.163887 -0.20049 0.965891 + outer loop + vertex 1.11485 1.04251 2.56555 + vertex 1.11354 1.03861 2.56497 + vertex 1.1187 1.04346 2.5651 + endloop + endfacet + facet normal 0.163984 -0.200933 0.965782 + outer loop + vertex 1.1187 1.04346 2.5651 + vertex 1.11701 1.04538 2.56578 + vertex 1.11485 1.04251 2.56555 + endloop + endfacet + facet normal 0.170364 -0.20557 0.9637 + outer loop + vertex 1.11701 1.04538 2.56578 + vertex 1.11316 1.04427 2.56623 + vertex 1.11485 1.04251 2.56555 + endloop + endfacet + facet normal 0.170161 -0.204784 0.963903 + outer loop + vertex 1.11701 1.04538 2.56578 + vertex 1.11821 1.04902 2.56635 + vertex 1.11316 1.04427 2.56623 + endloop + endfacet + facet normal 0.165225 -0.199591 0.965849 + outer loop + vertex 1.11821 1.04902 2.56635 + vertex 1.11313 1.04859 2.56712 + vertex 1.11316 1.04427 2.56623 + endloop + endfacet + facet normal 0.164573 -0.20315 0.965218 + outer loop + vertex 1.12004 1.04735 2.56568 + vertex 1.11821 1.04902 2.56635 + vertex 1.11701 1.04538 2.56578 + endloop + endfacet + facet normal 0.161838 -0.20608 0.965059 + outer loop + vertex 1.12221 1.05017 2.56592 + vertex 1.11821 1.04902 2.56635 + vertex 1.12004 1.04735 2.56568 + endloop + endfacet + facet normal 0.153791 -0.200103 0.96763 + outer loop + vertex 1.12382 1.04824 2.56526 + vertex 1.12221 1.05017 2.56592 + vertex 1.12004 1.04735 2.56568 + endloop + endfacet + facet normal 0.153411 -0.198275 0.968066 + outer loop + vertex 1.12004 1.04735 2.56568 + vertex 1.1187 1.04346 2.5651 + vertex 1.12382 1.04824 2.56526 + endloop + endfacet + facet normal 0.158443 -0.203611 0.966146 + outer loop + vertex 1.12382 1.04824 2.56526 + vertex 1.1187 1.04346 2.5651 + vertex 1.12346 1.04337 2.5643 + endloop + endfacet + facet normal 0.153819 -0.203424 0.966932 + outer loop + vertex 1.12346 1.04337 2.5643 + vertex 1.12853 1.04834 2.56454 + vertex 1.12382 1.04824 2.56526 + endloop + endfacet + facet normal 0.153725 -0.211204 0.965278 + outer loop + vertex 1.12837 1.05233 2.56544 + vertex 1.12382 1.04824 2.56526 + vertex 1.12853 1.04834 2.56454 + endloop + endfacet + facet normal 0.174213 -0.209675 0.962126 + outer loop + vertex 1.12853 1.04834 2.56454 + vertex 1.13342 1.05383 2.56485 + vertex 1.12837 1.05233 2.56544 + endloop + endfacet + facet normal 0.181659 -0.238008 0.954124 + outer loop + vertex 1.12837 1.05233 2.56544 + vertex 1.13342 1.05383 2.56485 + vertex 1.13127 1.05641 2.5659 + endloop + endfacet + facet normal 0.149886 -0.216605 0.964685 + outer loop + vertex 1.12751 1.05471 2.5661 + vertex 1.12837 1.05233 2.56544 + vertex 1.13127 1.05641 2.5659 + endloop + endfacet + facet normal 0.14767 -0.211541 0.966149 + outer loop + vertex 1.13127 1.05641 2.5659 + vertex 1.12884 1.05876 2.56679 + vertex 1.12751 1.05471 2.5661 + endloop + endfacet + facet normal 0.147786 -0.211575 0.966124 + outer loop + vertex 1.12751 1.05471 2.5661 + vertex 1.12884 1.05876 2.56679 + vertex 1.12344 1.05382 2.56653 + endloop + endfacet + facet normal 0.149186 -0.218889 0.964277 + outer loop + vertex 1.12751 1.05471 2.5661 + vertex 1.12344 1.05382 2.56653 + vertex 1.12516 1.05195 2.56584 + endloop + endfacet + facet normal 0.154974 -0.213672 0.964535 + outer loop + vertex 1.12516 1.05195 2.56584 + vertex 1.12344 1.05382 2.56653 + vertex 1.12221 1.05017 2.56592 + endloop + endfacet + facet normal 0.146762 -0.210475 0.96652 + outer loop + vertex 1.12884 1.05876 2.56679 + vertex 1.12345 1.0585 2.56755 + vertex 1.12344 1.05382 2.56653 + endloop + endfacet + facet normal 0.156372 -0.202713 0.966672 + outer loop + vertex 1.13384 1.0604 2.56632 + vertex 1.12884 1.05876 2.56679 + vertex 1.13127 1.05641 2.5659 + endloop + endfacet + facet normal 0.185377 -0.220458 0.957619 + outer loop + vertex 1.13491 1.05817 2.5656 + vertex 1.13384 1.0604 2.56632 + vertex 1.13127 1.05641 2.5659 + endloop + endfacet + facet normal 0.21909 -0.203179 0.954315 + outer loop + vertex 1.13685 1.06096 2.56575 + vertex 1.13384 1.0604 2.56632 + vertex 1.13491 1.05817 2.5656 + endloop + endfacet + facet normal 0.308231 -0.262527 0.91437 + outer loop + vertex 1.13836 1.05888 2.56464 + vertex 1.13685 1.06096 2.56575 + vertex 1.13491 1.05817 2.5656 + endloop + endfacet + facet normal 0.308481 -0.264696 0.91366 + outer loop + vertex 1.13491 1.05817 2.5656 + vertex 1.13342 1.05383 2.56485 + vertex 1.13836 1.05888 2.56464 + endloop + endfacet + facet normal 0.239521 -0.195697 0.950964 + outer loop + vertex 1.13836 1.05888 2.56464 + vertex 1.13342 1.05383 2.56485 + vertex 1.13819 1.05357 2.56359 + endloop + endfacet + facet normal 0.238565 -0.205029 0.949236 + outer loop + vertex 1.13347 1.04857 2.5637 + vertex 1.13819 1.05357 2.56359 + vertex 1.13342 1.05383 2.56485 + endloop + endfacet + facet normal 0.203233 -0.171414 0.964009 + outer loop + vertex 1.13821 1.04853 2.56269 + vertex 1.13819 1.05357 2.56359 + vertex 1.13347 1.04857 2.5637 + endloop + endfacet + facet normal 0.202097 -0.196476 0.959455 + outer loop + vertex 1.13351 1.04358 2.56267 + vertex 1.13821 1.04853 2.56269 + vertex 1.13347 1.04857 2.5637 + endloop + endfacet + facet normal 0.16422 -0.198161 0.966315 + outer loop + vertex 1.13351 1.04358 2.56267 + vertex 1.13347 1.04857 2.5637 + vertex 1.12843 1.04341 2.5635 + endloop + endfacet + facet normal 0.164212 -0.207556 0.964342 + outer loop + vertex 1.12837 1.03852 2.56245 + vertex 1.13351 1.04358 2.56267 + vertex 1.12843 1.04341 2.5635 + endloop + endfacet + facet normal 0.158114 -0.207695 0.965331 + outer loop + vertex 1.12837 1.03852 2.56245 + vertex 1.12843 1.04341 2.5635 + vertex 1.12324 1.03835 2.56326 + endloop + endfacet + facet normal 0.158113 -0.208004 0.965264 + outer loop + vertex 1.12321 1.03358 2.56224 + vertex 1.12837 1.03852 2.56245 + vertex 1.12324 1.03835 2.56326 + endloop + endfacet + facet normal 0.16541 -0.207802 0.964084 + outer loop + vertex 1.12321 1.03358 2.56224 + vertex 1.12324 1.03835 2.56326 + vertex 1.11816 1.0334 2.56306 + endloop + endfacet + facet normal 0.165403 -0.203924 0.964913 + outer loop + vertex 1.11833 1.0288 2.56206 + vertex 1.12321 1.03358 2.56224 + vertex 1.11816 1.0334 2.56306 + endloop + endfacet + facet normal 0.183806 -0.202564 0.961864 + outer loop + vertex 1.11833 1.0288 2.56206 + vertex 1.11816 1.0334 2.56306 + vertex 1.11329 1.0285 2.56296 + endloop + endfacet + facet normal 0.183737 -0.199085 0.962604 + outer loop + vertex 1.11372 1.02357 2.56186 + vertex 1.11833 1.0288 2.56206 + vertex 1.11329 1.0285 2.56296 + endloop + endfacet + facet normal 0.224938 -0.193773 0.954911 + outer loop + vertex 1.11372 1.02357 2.56186 + vertex 1.11329 1.0285 2.56296 + vertex 1.10847 1.02369 2.56312 + endloop + endfacet + facet normal 0.225679 -0.182718 0.956913 + outer loop + vertex 1.11372 1.02357 2.56186 + vertex 1.10847 1.02369 2.56312 + vertex 1.10854 1.01846 2.5621 + endloop + endfacet + facet normal 0.266967 -0.225449 0.936964 + outer loop + vertex 1.11271 1.01948 2.56116 + vertex 1.11372 1.02357 2.56186 + vertex 1.10854 1.01846 2.5621 + endloop + endfacet + facet normal 0.265249 -0.215967 0.939681 + outer loop + vertex 1.11271 1.01948 2.56116 + vertex 1.10854 1.01846 2.5621 + vertex 1.11092 1.01606 2.56088 + endloop + endfacet + facet normal 0.229546 -0.198317 0.952879 + outer loop + vertex 1.1143 1.01797 2.56046 + vertex 1.11271 1.01948 2.56116 + vertex 1.11092 1.01606 2.56088 + endloop + endfacet + facet normal 0.22539 -0.190382 0.955486 + outer loop + vertex 1.11349 1.01402 2.55987 + vertex 1.1143 1.01797 2.56046 + vertex 1.11092 1.01606 2.56088 + endloop + endfacet + facet normal 0.234906 -0.178365 0.955513 + outer loop + vertex 1.10962 1.01274 2.56058 + vertex 1.11349 1.01402 2.55987 + vertex 1.11092 1.01606 2.56088 + endloop + endfacet + facet normal 0.301812 -0.202405 0.931634 + outer loop + vertex 1.11092 1.01606 2.56088 + vertex 1.10709 1.01341 2.56155 + vertex 1.10962 1.01274 2.56058 + endloop + endfacet + facet normal 0.179021 -0.182537 0.966764 + outer loop + vertex 1.11349 1.01402 2.55987 + vertex 1.11835 1.01883 2.55988 + vertex 1.1143 1.01797 2.56046 + endloop + endfacet + facet normal 0.182879 -0.203925 0.961754 + outer loop + vertex 1.1143 1.01797 2.56046 + vertex 1.11835 1.01883 2.55988 + vertex 1.11624 1.02132 2.56081 + endloop + endfacet + facet normal 0.176018 -0.20974 0.961783 + outer loop + vertex 1.11976 1.02291 2.56051 + vertex 1.11624 1.02132 2.56081 + vertex 1.11835 1.01883 2.55988 + endloop + endfacet + facet normal 0.16522 -0.206406 0.964416 + outer loop + vertex 1.11976 1.02291 2.56051 + vertex 1.11835 1.01883 2.55988 + vertex 1.12356 1.02356 2.56 + endloop + endfacet + facet normal 0.165902 -0.211326 0.963233 + outer loop + vertex 1.12356 1.02356 2.56 + vertex 1.12201 1.02565 2.56072 + vertex 1.11976 1.02291 2.56051 + endloop + endfacet + facet normal 0.171066 -0.215432 0.961419 + outer loop + vertex 1.12201 1.02565 2.56072 + vertex 1.11884 1.0252 2.56119 + vertex 1.11976 1.02291 2.56051 + endloop + endfacet + facet normal 0.170652 -0.211552 0.962353 + outer loop + vertex 1.12201 1.02565 2.56072 + vertex 1.1232 1.02921 2.56129 + vertex 1.11884 1.0252 2.56119 + endloop + endfacet + facet normal 0.169268 -0.210061 0.962924 + outer loop + vertex 1.1232 1.02921 2.56129 + vertex 1.11833 1.0288 2.56206 + vertex 1.11884 1.0252 2.56119 + endloop + endfacet + facet normal 0.162848 -0.209242 0.964209 + outer loop + vertex 1.12488 1.0274 2.56062 + vertex 1.1232 1.02921 2.56129 + vertex 1.12201 1.02565 2.56072 + endloop + endfacet + facet normal 0.162626 -0.209445 0.964202 + outer loop + vertex 1.12703 1.03021 2.56087 + vertex 1.1232 1.02921 2.56129 + vertex 1.12488 1.0274 2.56062 + endloop + endfacet + facet normal 0.160078 -0.207565 0.965035 + outer loop + vertex 1.12875 1.02835 2.56018 + vertex 1.12703 1.03021 2.56087 + vertex 1.12488 1.0274 2.56062 + endloop + endfacet + facet normal 0.160839 -0.211081 0.964145 + outer loop + vertex 1.12488 1.0274 2.56062 + vertex 1.12356 1.02356 2.56 + vertex 1.12875 1.02835 2.56018 + endloop + endfacet + facet normal 0.163587 -0.214016 0.963035 + outer loop + vertex 1.12875 1.02835 2.56018 + vertex 1.12356 1.02356 2.56 + vertex 1.12836 1.02338 2.55914 + endloop + endfacet + facet normal 0.162354 -0.213967 0.963255 + outer loop + vertex 1.12836 1.02338 2.55914 + vertex 1.13356 1.02839 2.55938 + vertex 1.12875 1.02835 2.56018 + endloop + endfacet + facet normal 0.162449 -0.210543 0.963993 + outer loop + vertex 1.13407 1.0333 2.56037 + vertex 1.12875 1.02835 2.56018 + vertex 1.13356 1.02839 2.55938 + endloop + endfacet + facet normal 0.187368 -0.212135 0.95911 + outer loop + vertex 1.13356 1.02839 2.55938 + vertex 1.13875 1.03348 2.55949 + vertex 1.13407 1.0333 2.56037 + endloop + endfacet + facet normal 0.187387 -0.207309 0.960161 + outer loop + vertex 1.13929 1.03838 2.56044 + vertex 1.13407 1.0333 2.56037 + vertex 1.13875 1.03348 2.55949 + endloop + endfacet + facet normal 0.266221 -0.212076 0.940293 + outer loop + vertex 1.13875 1.03348 2.55949 + vertex 1.14358 1.03846 2.55925 + vertex 1.13929 1.03838 2.56044 + endloop + endfacet + facet normal 0.267222 -0.184599 0.945788 + outer loop + vertex 1.14392 1.0435 2.56014 + vertex 1.13929 1.03838 2.56044 + vertex 1.14358 1.03846 2.55925 + endloop + endfacet + facet normal 0.339882 -0.252638 0.9059 + outer loop + vertex 1.14054 1.04226 2.56106 + vertex 1.13929 1.03838 2.56044 + vertex 1.14392 1.0435 2.56014 + endloop + endfacet + facet normal 0.333197 -0.227838 0.914915 + outer loop + vertex 1.14392 1.0435 2.56014 + vertex 1.14222 1.04521 2.56118 + vertex 1.14054 1.04226 2.56106 + endloop + endfacet + facet normal 0.220701 -0.165913 0.961126 + outer loop + vertex 1.14222 1.04521 2.56118 + vertex 1.13847 1.04386 2.56181 + vertex 1.14054 1.04226 2.56106 + endloop + endfacet + facet normal 0.202219 -0.189755 0.960781 + outer loop + vertex 1.14054 1.04226 2.56106 + vertex 1.13847 1.04386 2.56181 + vertex 1.13763 1.04009 2.56124 + endloop + endfacet + facet normal 0.159241 -0.181601 0.970393 + outer loop + vertex 1.13763 1.04009 2.56124 + vertex 1.13847 1.04386 2.56181 + vertex 1.13354 1.03884 2.56168 + endloop + endfacet + facet normal 0.165735 -0.204728 0.964686 + outer loop + vertex 1.13763 1.04009 2.56124 + vertex 1.13354 1.03884 2.56168 + vertex 1.13547 1.03714 2.56098 + endloop + endfacet + facet normal 0.211255 -0.236426 0.948406 + outer loop + vertex 1.13929 1.03838 2.56044 + vertex 1.13763 1.04009 2.56124 + vertex 1.13547 1.03714 2.56098 + endloop + endfacet + facet normal 0.161099 -0.209878 0.964364 + outer loop + vertex 1.13547 1.03714 2.56098 + vertex 1.13354 1.03884 2.56168 + vertex 1.13234 1.03506 2.56105 + endloop + endfacet + facet normal 0.164641 -0.215287 0.962572 + outer loop + vertex 1.13547 1.03714 2.56098 + vertex 1.13234 1.03506 2.56105 + vertex 1.13407 1.0333 2.56037 + endloop + endfacet + facet normal 0.163553 -0.216334 0.962523 + outer loop + vertex 1.13407 1.0333 2.56037 + vertex 1.13234 1.03506 2.56105 + vertex 1.1301 1.03218 2.56079 + endloop + endfacet + facet normal 0.157743 -0.212 0.964455 + outer loop + vertex 1.13234 1.03506 2.56105 + vertex 1.12827 1.0339 2.56147 + vertex 1.1301 1.03218 2.56079 + endloop + endfacet + facet normal 0.159422 -0.21026 0.96456 + outer loop + vertex 1.1301 1.03218 2.56079 + vertex 1.12827 1.0339 2.56147 + vertex 1.12703 1.03021 2.56087 + endloop + endfacet + facet normal 0.156888 -0.208704 0.965313 + outer loop + vertex 1.13234 1.03506 2.56105 + vertex 1.13354 1.03884 2.56168 + vertex 1.12827 1.0339 2.56147 + endloop + endfacet + facet normal 0.158082 -0.209956 0.964846 + outer loop + vertex 1.13354 1.03884 2.56168 + vertex 1.12837 1.03852 2.56245 + vertex 1.12827 1.0339 2.56147 + endloop + endfacet + facet normal 0.178515 -0.200347 0.963324 + outer loop + vertex 1.13847 1.04386 2.56181 + vertex 1.13351 1.04358 2.56267 + vertex 1.13354 1.03884 2.56168 + endloop + endfacet + facet normal 0.212368 -0.140071 0.967099 + outer loop + vertex 1.14222 1.04521 2.56118 + vertex 1.14215 1.04839 2.56166 + vertex 1.13847 1.04386 2.56181 + endloop + endfacet + facet normal 0.245437 -0.167311 0.954865 + outer loop + vertex 1.14215 1.04839 2.56166 + vertex 1.13821 1.04853 2.56269 + vertex 1.13847 1.04386 2.56181 + endloop + endfacet + facet normal 0.225715 -0.222428 0.948461 + outer loop + vertex 1.14054 1.04226 2.56106 + vertex 1.13763 1.04009 2.56124 + vertex 1.13929 1.03838 2.56044 + endloop + endfacet + facet normal 0.226467 -0.172654 0.958594 + outer loop + vertex 1.14325 1.03347 2.55843 + vertex 1.14358 1.03846 2.55925 + vertex 1.13875 1.03348 2.55949 + endloop + endfacet + facet normal 0.225135 -0.201919 0.953175 + outer loop + vertex 1.1384 1.02851 2.55852 + vertex 1.14325 1.03347 2.55843 + vertex 1.13875 1.03348 2.55949 + endloop + endfacet + facet normal 0.19926 -0.176379 0.963943 + outer loop + vertex 1.14306 1.02862 2.55758 + vertex 1.14325 1.03347 2.55843 + vertex 1.1384 1.02851 2.55852 + endloop + endfacet + facet normal 0.198718 -0.207462 0.957847 + outer loop + vertex 1.13833 1.02373 2.5575 + vertex 1.14306 1.02862 2.55758 + vertex 1.1384 1.02851 2.55852 + endloop + endfacet + facet normal 0.168419 -0.208206 0.963476 + outer loop + vertex 1.13833 1.02373 2.5575 + vertex 1.1384 1.02851 2.55852 + vertex 1.13333 1.02345 2.55831 + endloop + endfacet + facet normal 0.16867 -0.222222 0.960296 + outer loop + vertex 1.13345 1.01883 2.55722 + vertex 1.13833 1.02373 2.5575 + vertex 1.13333 1.02345 2.55831 + endloop + endfacet + facet normal 0.166195 -0.222378 0.960691 + outer loop + vertex 1.13345 1.01883 2.55722 + vertex 1.13333 1.02345 2.55831 + vertex 1.12832 1.01842 2.55802 + endloop + endfacet + facet normal 0.166223 -0.223019 0.960538 + outer loop + vertex 1.12869 1.01356 2.55682 + vertex 1.13345 1.01883 2.55722 + vertex 1.12832 1.01842 2.55802 + endloop + endfacet + facet normal 0.17649 -0.221848 0.958976 + outer loop + vertex 1.12869 1.01356 2.55682 + vertex 1.12832 1.01842 2.55802 + vertex 1.12333 1.0135 2.5578 + endloop + endfacet + facet normal 0.176661 -0.216116 0.960252 + outer loop + vertex 1.12869 1.01356 2.55682 + vertex 1.12333 1.0135 2.5578 + vertex 1.12342 1.0087 2.5567 + endloop + endfacet + facet normal 0.187475 -0.227725 0.955507 + outer loop + vertex 1.12739 1.0095 2.55611 + vertex 1.12869 1.01356 2.55682 + vertex 1.12342 1.0087 2.5567 + endloop + endfacet + facet normal 0.187765 -0.229504 0.955025 + outer loop + vertex 1.12739 1.0095 2.55611 + vertex 1.12342 1.0087 2.5567 + vertex 1.12519 1.00678 2.55589 + endloop + endfacet + facet normal 0.176136 -0.220432 0.959368 + outer loop + vertex 1.12827 1.00715 2.55541 + vertex 1.12739 1.0095 2.55611 + vertex 1.12519 1.00678 2.55589 + endloop + endfacet + facet normal 0.175421 -0.211731 0.961456 + outer loop + vertex 1.12519 1.00678 2.55589 + vertex 1.12408 1.00323 2.55531 + vertex 1.12827 1.00715 2.55541 + endloop + endfacet + facet normal 0.179378 -0.215925 0.959791 + outer loop + vertex 1.12827 1.00715 2.55541 + vertex 1.12408 1.00323 2.55531 + vertex 1.12842 1.00325 2.5545 + endloop + endfacet + facet normal 0.168533 -0.216768 0.961566 + outer loop + vertex 1.12842 1.00325 2.5545 + vertex 1.13325 1.0086 2.55486 + vertex 1.12827 1.00715 2.55541 + endloop + endfacet + facet normal 0.169242 -0.219478 0.960826 + outer loop + vertex 1.12827 1.00715 2.55541 + vertex 1.13325 1.0086 2.55486 + vertex 1.13107 1.01116 2.55583 + endloop + endfacet + facet normal 0.166493 -0.2218 0.960773 + outer loop + vertex 1.13479 1.01284 2.55558 + vertex 1.13107 1.01116 2.55583 + vertex 1.13325 1.0086 2.55486 + endloop + endfacet + facet normal 0.163746 -0.220915 0.961449 + outer loop + vertex 1.13479 1.01284 2.55558 + vertex 1.13325 1.0086 2.55486 + vertex 1.13873 1.01362 2.55508 + endloop + endfacet + facet normal 0.164781 -0.227191 0.959808 + outer loop + vertex 1.13873 1.01362 2.55508 + vertex 1.13715 1.01564 2.55583 + vertex 1.13479 1.01284 2.55558 + endloop + endfacet + facet normal 0.164325 -0.226822 0.959973 + outer loop + vertex 1.13715 1.01564 2.55583 + vertex 1.13391 1.01517 2.55628 + vertex 1.13479 1.01284 2.55558 + endloop + endfacet + facet normal 0.164289 -0.226489 0.960058 + outer loop + vertex 1.13715 1.01564 2.55583 + vertex 1.13836 1.01926 2.55648 + vertex 1.13391 1.01517 2.55628 + endloop + endfacet + facet normal 0.1652 -0.227463 0.959672 + outer loop + vertex 1.13836 1.01926 2.55648 + vertex 1.13345 1.01883 2.55722 + vertex 1.13391 1.01517 2.55628 + endloop + endfacet + facet normal 0.163495 -0.226258 0.960248 + outer loop + vertex 1.1401 1.01746 2.55576 + vertex 1.13836 1.01926 2.55648 + vertex 1.13715 1.01564 2.55583 + endloop + endfacet + facet normal 0.167022 -0.222927 0.96042 + outer loop + vertex 1.14225 1.02034 2.55605 + vertex 1.13836 1.01926 2.55648 + vertex 1.1401 1.01746 2.55576 + endloop + endfacet + facet normal 0.198693 -0.245412 0.948838 + outer loop + vertex 1.14397 1.01856 2.55523 + vertex 1.14225 1.02034 2.55605 + vertex 1.1401 1.01746 2.55576 + endloop + endfacet + facet normal 0.196801 -0.237639 0.951208 + outer loop + vertex 1.1401 1.01746 2.55576 + vertex 1.13873 1.01362 2.55508 + vertex 1.14397 1.01856 2.55523 + endloop + endfacet + facet normal 0.179121 -0.219146 0.959109 + outer loop + vertex 1.14397 1.01856 2.55523 + vertex 1.13873 1.01362 2.55508 + vertex 1.14364 1.01363 2.55417 + endloop + endfacet + facet normal 0.235892 -0.220147 0.946515 + outer loop + vertex 1.14364 1.01363 2.55417 + vertex 1.1485 1.01852 2.5541 + vertex 1.14397 1.01856 2.55523 + endloop + endfacet + facet normal 0.23761 -0.191148 0.952367 + outer loop + vertex 1.14876 1.02363 2.55505 + vertex 1.14397 1.01856 2.55523 + vertex 1.1485 1.01852 2.5541 + endloop + endfacet + facet normal 0.350605 -0.190293 0.916987 + outer loop + vertex 1.1485 1.01852 2.5541 + vertex 1.15271 1.02306 2.55343 + vertex 1.14876 1.02363 2.55505 + endloop + endfacet + facet normal 0.295832 -0.135199 0.945624 + outer loop + vertex 1.15263 1.01794 2.55272 + vertex 1.15271 1.02306 2.55343 + vertex 1.1485 1.01852 2.5541 + endloop + endfacet + facet normal 0.287295 -0.182966 0.940205 + outer loop + vertex 1.14845 1.01357 2.55315 + vertex 1.15263 1.01794 2.55272 + vertex 1.1485 1.01852 2.5541 + endloop + endfacet + facet normal 0.242281 -0.137819 0.960368 + outer loop + vertex 1.15268 1.01324 2.55203 + vertex 1.15263 1.01794 2.55272 + vertex 1.14845 1.01357 2.55315 + endloop + endfacet + facet normal 0.235695 -0.194811 0.952101 + outer loop + vertex 1.14881 1.00872 2.55207 + vertex 1.15268 1.01324 2.55203 + vertex 1.14845 1.01357 2.55315 + endloop + endfacet + facet normal 0.181632 -0.201169 0.96257 + outer loop + vertex 1.14881 1.00872 2.55207 + vertex 1.14845 1.01357 2.55315 + vertex 1.14362 1.0087 2.55304 + endloop + endfacet + facet normal 0.18045 -0.232544 0.955699 + outer loop + vertex 1.14881 1.00872 2.55207 + vertex 1.14362 1.0087 2.55304 + vertex 1.14367 1.00386 2.55185 + endloop + endfacet + facet normal 0.168499 -0.220131 0.960807 + outer loop + vertex 1.14776 1.00472 2.55133 + vertex 1.14881 1.00872 2.55207 + vertex 1.14367 1.00386 2.55185 + endloop + endfacet + facet normal 0.171868 -0.239351 0.955601 + outer loop + vertex 1.14776 1.00472 2.55133 + vertex 1.14367 1.00386 2.55185 + vertex 1.14547 1.00189 2.55104 + endloop + endfacet + facet normal 0.174497 -0.241379 0.954614 + outer loop + vertex 1.14862 1.0023 2.55056 + vertex 1.14776 1.00472 2.55133 + vertex 1.14547 1.00189 2.55104 + endloop + endfacet + facet normal 0.17336 -0.228676 0.957942 + outer loop + vertex 1.14547 1.00189 2.55104 + vertex 1.14411 0.998154 2.55039 + vertex 1.14862 1.0023 2.55056 + endloop + endfacet + facet normal 0.175484 -0.23095 0.95701 + outer loop + vertex 1.14862 1.0023 2.55056 + vertex 1.14411 0.998154 2.55039 + vertex 1.14872 0.998333 2.54959 + endloop + endfacet + facet normal 0.214907 -0.228178 0.949605 + outer loop + vertex 1.14872 0.998333 2.54959 + vertex 1.15331 1.0038 2.54986 + vertex 1.14862 1.0023 2.55056 + endloop + endfacet + facet normal 0.222288 -0.255287 0.940966 + outer loop + vertex 1.14862 1.0023 2.55056 + vertex 1.15331 1.0038 2.54986 + vertex 1.15123 1.00639 2.55106 + endloop + endfacet + facet normal 0.252899 -0.230094 0.939733 + outer loop + vertex 1.15438 1.00821 2.55066 + vertex 1.15123 1.00639 2.55106 + vertex 1.15331 1.0038 2.54986 + endloop + endfacet + facet normal 0.375186 -0.251291 0.892238 + outer loop + vertex 1.15438 1.00821 2.55066 + vertex 1.15331 1.0038 2.54986 + vertex 1.15721 1.0084 2.54952 + endloop + endfacet + facet normal 0.290375 -0.175741 0.940637 + outer loop + vertex 1.15721 1.0084 2.54952 + vertex 1.15331 1.0038 2.54986 + vertex 1.15773 1.00358 2.54846 + endloop + endfacet + facet normal 0.28682 -0.209948 0.934696 + outer loop + vertex 1.15346 0.998638 2.54866 + vertex 1.15773 1.00358 2.54846 + vertex 1.15331 1.0038 2.54986 + endloop + endfacet + facet normal 0.229033 -0.159037 0.960339 + outer loop + vertex 1.158 0.998648 2.54758 + vertex 1.15773 1.00358 2.54846 + vertex 1.15346 0.998638 2.54866 + endloop + endfacet + facet normal 0.227221 -0.203568 0.952329 + outer loop + vertex 1.15344 0.993784 2.54763 + vertex 1.158 0.998648 2.54758 + vertex 1.15346 0.998638 2.54866 + endloop + endfacet + facet normal 0.185449 -0.20525 0.960979 + outer loop + vertex 1.15344 0.993784 2.54763 + vertex 1.15346 0.998638 2.54866 + vertex 1.14851 0.993532 2.54852 + endloop + endfacet + facet normal 0.185636 -0.223872 0.956776 + outer loop + vertex 1.14833 0.988807 2.54745 + vertex 1.15344 0.993784 2.54763 + vertex 1.14851 0.993532 2.54852 + endloop + endfacet + facet normal 0.179746 -0.223904 0.957893 + outer loop + vertex 1.14833 0.988807 2.54745 + vertex 1.14851 0.993532 2.54852 + vertex 1.14335 0.988543 2.54833 + endloop + endfacet + facet normal 0.179795 -0.22826 0.956855 + outer loop + vertex 1.14335 0.983976 2.54724 + vertex 1.14833 0.988807 2.54745 + vertex 1.14335 0.988543 2.54833 + endloop + endfacet + facet normal 0.185228 -0.228017 0.955876 + outer loop + vertex 1.14335 0.983976 2.54724 + vertex 1.14335 0.988543 2.54833 + vertex 1.13831 0.983571 2.54812 + endloop + endfacet + facet normal 0.185204 -0.227366 0.956036 + outer loop + vertex 1.13863 0.97872 2.5469 + vertex 1.14335 0.983976 2.54724 + vertex 1.13831 0.983571 2.54812 + endloop + endfacet + facet normal 0.196135 -0.226182 0.954135 + outer loop + vertex 1.13863 0.97872 2.5469 + vertex 1.13831 0.983571 2.54812 + vertex 1.13335 0.978617 2.54796 + endloop + endfacet + facet normal 0.196125 -0.226567 0.954045 + outer loop + vertex 1.13863 0.97872 2.5469 + vertex 1.13335 0.978617 2.54796 + vertex 1.13339 0.973814 2.54681 + endloop + endfacet + facet normal 0.204743 -0.235693 0.950015 + outer loop + vertex 1.13735 0.974633 2.54616 + vertex 1.13863 0.97872 2.5469 + vertex 1.13339 0.973814 2.54681 + endloop + endfacet + facet normal 0.206259 -0.245205 0.947276 + outer loop + vertex 1.13735 0.974633 2.54616 + vertex 1.13339 0.973814 2.54681 + vertex 1.13516 0.971881 2.54593 + endloop + endfacet + facet normal 0.192543 -0.234718 0.952804 + outer loop + vertex 1.13824 0.972249 2.54539 + vertex 1.13735 0.974633 2.54616 + vertex 1.13516 0.971881 2.54593 + endloop + endfacet + facet normal 0.191857 -0.225546 0.955154 + outer loop + vertex 1.13516 0.971881 2.54593 + vertex 1.13406 0.968316 2.54531 + vertex 1.13824 0.972249 2.54539 + endloop + endfacet + facet normal 0.195057 -0.228919 0.953703 + outer loop + vertex 1.13824 0.972249 2.54539 + vertex 1.13406 0.968316 2.54531 + vertex 1.13843 0.968361 2.54442 + endloop + endfacet + facet normal 0.186501 -0.2297 0.955225 + outer loop + vertex 1.13843 0.968361 2.54442 + vertex 1.14316 0.973684 2.54478 + vertex 1.13824 0.972249 2.54539 + endloop + endfacet + facet normal 0.187073 -0.231937 0.954573 + outer loop + vertex 1.13824 0.972249 2.54539 + vertex 1.14316 0.973684 2.54478 + vertex 1.141 0.976295 2.54584 + endloop + endfacet + facet normal 0.188127 -0.231066 0.954577 + outer loop + vertex 1.14465 0.977966 2.54552 + vertex 1.141 0.976295 2.54584 + vertex 1.14316 0.973684 2.54478 + endloop + endfacet + facet normal 0.181072 -0.228933 0.956453 + outer loop + vertex 1.14465 0.977966 2.54552 + vertex 1.14316 0.973684 2.54478 + vertex 1.14852 0.978659 2.54496 + endloop + endfacet + facet normal 0.180619 -0.225714 0.957303 + outer loop + vertex 1.14852 0.978659 2.54496 + vertex 1.14694 0.980767 2.54575 + vertex 1.14465 0.977966 2.54552 + endloop + endfacet + facet normal 0.187505 -0.231117 0.954687 + outer loop + vertex 1.14694 0.980767 2.54575 + vertex 1.14377 0.980333 2.54627 + vertex 1.14465 0.977966 2.54552 + endloop + endfacet + facet normal 0.188018 -0.23658 0.953247 + outer loop + vertex 1.14694 0.980767 2.54575 + vertex 1.14818 0.984372 2.5464 + vertex 1.14377 0.980333 2.54627 + endloop + endfacet + facet normal 0.184201 -0.232466 0.955002 + outer loop + vertex 1.14818 0.984372 2.5464 + vertex 1.14335 0.983976 2.54724 + vertex 1.14377 0.980333 2.54627 + endloop + endfacet + facet normal 0.181438 -0.234627 0.955003 + outer loop + vertex 1.14982 0.982525 2.54563 + vertex 1.14818 0.984372 2.5464 + vertex 1.14694 0.980767 2.54575 + endloop + endfacet + facet normal 0.178349 -0.237343 0.954914 + outer loop + vertex 1.15203 0.98537 2.54593 + vertex 1.14818 0.984372 2.5464 + vertex 1.14982 0.982525 2.54563 + endloop + endfacet + facet normal 0.171791 -0.232513 0.957301 + outer loop + vertex 1.15379 0.98351 2.54516 + vertex 1.15203 0.98537 2.54593 + vertex 1.14982 0.982525 2.54563 + endloop + endfacet + facet normal 0.170376 -0.22594 0.959126 + outer loop + vertex 1.14982 0.982525 2.54563 + vertex 1.14852 0.978659 2.54496 + vertex 1.15379 0.98351 2.54516 + endloop + endfacet + facet normal 0.175023 -0.230902 0.957106 + outer loop + vertex 1.15379 0.98351 2.54516 + vertex 1.14852 0.978659 2.54496 + vertex 1.15348 0.978578 2.54403 + endloop + endfacet + facet normal 0.179639 -0.230983 0.95623 + outer loop + vertex 1.15348 0.978578 2.54403 + vertex 1.15867 0.983549 2.54426 + vertex 1.15379 0.98351 2.54516 + endloop + endfacet + facet normal 0.179935 -0.222466 0.958192 + outer loop + vertex 1.15902 0.988482 2.54533 + vertex 1.15379 0.98351 2.54516 + vertex 1.15867 0.983549 2.54426 + endloop + endfacet + facet normal 0.228835 -0.223624 0.947432 + outer loop + vertex 1.15867 0.983549 2.54426 + vertex 1.16338 0.988396 2.54426 + vertex 1.15902 0.988482 2.54533 + endloop + endfacet + facet normal 0.232299 -0.171927 0.957329 + outer loop + vertex 1.16363 0.993351 2.54509 + vertex 1.15902 0.988482 2.54533 + vertex 1.16338 0.988396 2.54426 + endloop + endfacet + facet normal 0.328054 -0.172031 0.928863 + outer loop + vertex 1.16338 0.988396 2.54426 + vertex 1.16686 0.99246 2.54378 + vertex 1.16363 0.993351 2.54509 + endloop + endfacet + facet normal 0.2699 -0.118988 0.955508 + outer loop + vertex 1.16764 0.988446 2.54306 + vertex 1.16686 0.99246 2.54378 + vertex 1.16338 0.988396 2.54426 + endloop + endfacet + facet normal 0.267742 -0.188328 0.944906 + outer loop + vertex 1.16353 0.983646 2.54327 + vertex 1.16764 0.988446 2.54306 + vertex 1.16338 0.988396 2.54426 + endloop + endfacet + facet normal 0.207895 -0.136022 0.968647 + outer loop + vertex 1.16818 0.983955 2.54232 + vertex 1.16764 0.988446 2.54306 + vertex 1.16353 0.983646 2.54327 + endloop + endfacet + facet normal 0.209986 -0.210628 0.954747 + outer loop + vertex 1.16396 0.978762 2.5421 + vertex 1.16818 0.983955 2.54232 + vertex 1.16353 0.983646 2.54327 + endloop + endfacet + facet normal 0.182019 -0.214291 0.959661 + outer loop + vertex 1.16396 0.978762 2.5421 + vertex 1.16353 0.983646 2.54327 + vertex 1.15862 0.978643 2.54309 + endloop + endfacet + facet normal 0.181407 -0.243235 0.952853 + outer loop + vertex 1.16396 0.978762 2.5421 + vertex 1.15862 0.978643 2.54309 + vertex 1.15857 0.973799 2.54186 + endloop + endfacet + facet normal 0.18125 -0.243068 0.952925 + outer loop + vertex 1.16261 0.974593 2.54129 + vertex 1.16396 0.978762 2.5421 + vertex 1.15857 0.973799 2.54186 + endloop + endfacet + facet normal 0.183201 -0.255638 0.949256 + outer loop + vertex 1.16261 0.974593 2.54129 + vertex 1.15857 0.973799 2.54186 + vertex 1.16025 0.971803 2.541 + endloop + endfacet + facet normal 0.175194 -0.249198 0.952475 + outer loop + vertex 1.16341 0.972176 2.54051 + vertex 1.16261 0.974593 2.54129 + vertex 1.16025 0.971803 2.541 + endloop + endfacet + facet normal 0.174416 -0.239058 0.955212 + outer loop + vertex 1.16025 0.971803 2.541 + vertex 1.15891 0.968123 2.54032 + vertex 1.16341 0.972176 2.54051 + endloop + endfacet + facet normal 0.180982 -0.246221 0.952166 + outer loop + vertex 1.16341 0.972176 2.54051 + vertex 1.15891 0.968123 2.54032 + vertex 1.16352 0.968299 2.53949 + endloop + endfacet + facet normal 0.174873 -0.246656 0.953195 + outer loop + vertex 1.16352 0.968299 2.53949 + vertex 1.16848 0.973728 2.53999 + vertex 1.16341 0.972176 2.54051 + endloop + endfacet + facet normal 0.176795 -0.253677 0.950995 + outer loop + vertex 1.16341 0.972176 2.54051 + vertex 1.16848 0.973728 2.53999 + vertex 1.16637 0.976299 2.54106 + endloop + endfacet + facet normal 0.181651 -0.249741 0.951122 + outer loop + vertex 1.17006 0.978075 2.54083 + vertex 1.16637 0.976299 2.54106 + vertex 1.16848 0.973728 2.53999 + endloop + endfacet + facet normal 0.242554 -0.268217 0.932324 + outer loop + vertex 1.17006 0.978075 2.54083 + vertex 1.16848 0.973728 2.53999 + vertex 1.17364 0.978891 2.54013 + endloop + endfacet + facet normal 0.238067 -0.241337 0.940787 + outer loop + vertex 1.17364 0.978891 2.54013 + vertex 1.17203 0.980945 2.54106 + vertex 1.17006 0.978075 2.54083 + endloop + endfacet + facet normal 0.194622 -0.212913 0.957492 + outer loop + vertex 1.17203 0.980945 2.54106 + vertex 1.16897 0.980374 2.54156 + vertex 1.17006 0.978075 2.54083 + endloop + endfacet + facet normal 0.18289 -0.136213 0.973652 + outer loop + vertex 1.17203 0.980945 2.54106 + vertex 1.172 0.983991 2.5415 + vertex 1.16897 0.980374 2.54156 + endloop + endfacet + facet normal 0.209389 -0.158516 0.964898 + outer loop + vertex 1.172 0.983991 2.5415 + vertex 1.16818 0.983955 2.54232 + vertex 1.16897 0.980374 2.54156 + endloop + endfacet + facet normal 0.210799 -0.0509382 0.976201 + outer loop + vertex 1.172 0.983991 2.5415 + vertex 1.17178 0.988182 2.54176 + vertex 1.16818 0.983955 2.54232 + endloop + endfacet + facet normal 0.259618 -0.132955 0.956515 + outer loop + vertex 1.17434 0.98304 2.54073 + vertex 1.172 0.983991 2.5415 + vertex 1.17203 0.980945 2.54106 + endloop + endfacet + facet normal 0.304628 -0.186174 0.934099 + outer loop + vertex 1.17434 0.98304 2.54073 + vertex 1.17203 0.980945 2.54106 + vertex 1.17364 0.978891 2.54013 + endloop + endfacet + facet normal 0.376958 -0.194293 0.905623 + outer loop + vertex 1.17434 0.98304 2.54073 + vertex 1.17364 0.978891 2.54013 + vertex 1.17776 0.983945 2.5395 + endloop + endfacet + facet normal 0.250141 -0.0835503 0.964598 + outer loop + vertex 1.17776 0.983945 2.5395 + vertex 1.17364 0.978891 2.54013 + vertex 1.1781 0.978363 2.53892 + endloop + endfacet + facet normal 0.304187 -0.0786105 0.949363 + outer loop + vertex 1.1781 0.978363 2.53892 + vertex 1.18266 0.982437 2.5378 + vertex 1.17776 0.983945 2.5395 + endloop + endfacet + facet normal 0.228975 0.0120008 0.973358 + outer loop + vertex 1.18192 0.977402 2.53804 + vertex 1.18266 0.982437 2.5378 + vertex 1.1781 0.978363 2.53892 + endloop + endfacet + facet normal 0.183284 -0.165418 0.969043 + outer loop + vertex 1.17829 0.973487 2.53806 + vertex 1.18192 0.977402 2.53804 + vertex 1.1781 0.978363 2.53892 + endloop + endfacet + facet normal 0.182829 -0.16545 0.969123 + outer loop + vertex 1.17829 0.973487 2.53806 + vertex 1.1781 0.978363 2.53892 + vertex 1.17348 0.973657 2.53899 + endloop + endfacet + facet normal 0.176992 -0.24407 0.953469 + outer loop + vertex 1.17346 0.968831 2.53776 + vertex 1.17829 0.973487 2.53806 + vertex 1.17348 0.973657 2.53899 + endloop + endfacet + facet normal 0.179627 -0.243963 0.953004 + outer loop + vertex 1.17346 0.968831 2.53776 + vertex 1.17348 0.973657 2.53899 + vertex 1.16845 0.968661 2.53866 + endloop + endfacet + facet normal 0.179467 -0.256302 0.94979 + outer loop + vertex 1.1685 0.964065 2.53741 + vertex 1.17346 0.968831 2.53776 + vertex 1.16845 0.968661 2.53866 + endloop + endfacet + facet normal 0.186933 -0.255871 0.948465 + outer loop + vertex 1.1685 0.964065 2.53741 + vertex 1.16845 0.968661 2.53866 + vertex 1.16346 0.963625 2.53829 + endloop + endfacet + facet normal 0.186555 -0.246415 0.95104 + outer loop + vertex 1.16369 0.958808 2.53699 + vertex 1.1685 0.964065 2.53741 + vertex 1.16346 0.963625 2.53829 + endloop + endfacet + facet normal 0.192655 -0.245831 0.949974 + outer loop + vertex 1.16369 0.958808 2.53699 + vertex 1.16346 0.963625 2.53829 + vertex 1.15845 0.958666 2.53802 + endloop + endfacet + facet normal 0.192841 -0.237268 0.952112 + outer loop + vertex 1.16369 0.958808 2.53699 + vertex 1.15845 0.958666 2.53802 + vertex 1.15842 0.953919 2.53684 + endloop + endfacet + facet normal 0.193077 -0.237258 0.952066 + outer loop + vertex 1.15842 0.953919 2.53684 + vertex 1.15845 0.958666 2.53802 + vertex 1.15336 0.953742 2.53783 + endloop + endfacet + facet normal 0.193107 -0.234824 0.952663 + outer loop + vertex 1.15842 0.953919 2.53684 + vertex 1.15336 0.953742 2.53783 + vertex 1.15332 0.949105 2.53669 + endloop + endfacet + facet normal 0.194 -0.234788 0.952491 + outer loop + vertex 1.15332 0.949105 2.53669 + vertex 1.15336 0.953742 2.53783 + vertex 1.14823 0.948802 2.53765 + endloop + endfacet + facet normal 0.194008 -0.235486 0.952317 + outer loop + vertex 1.15332 0.949105 2.53669 + vertex 1.14823 0.948802 2.53765 + vertex 1.14811 0.94418 2.53654 + endloop + endfacet + facet normal 0.195756 -0.237312 0.951506 + outer loop + vertex 1.15217 0.945379 2.536 + vertex 1.15332 0.949105 2.53669 + vertex 1.14811 0.94418 2.53654 + endloop + endfacet + facet normal 0.197606 -0.244566 0.949284 + outer loop + vertex 1.15217 0.945379 2.536 + vertex 1.14811 0.94418 2.53654 + vertex 1.14997 0.942467 2.53571 + endloop + endfacet + facet normal 0.193531 -0.241652 0.950868 + outer loop + vertex 1.1539 0.943536 2.53518 + vertex 1.15217 0.945379 2.536 + vertex 1.14997 0.942467 2.53571 + endloop + endfacet + facet normal 0.19142 -0.23618 0.952669 + outer loop + vertex 1.15521 0.947382 2.53588 + vertex 1.15332 0.949105 2.53669 + vertex 1.15217 0.945379 2.536 + endloop + endfacet + facet normal 0.194413 -0.240837 0.950895 + outer loop + vertex 1.15521 0.947382 2.53588 + vertex 1.15217 0.945379 2.536 + vertex 1.1539 0.943536 2.53518 + endloop + endfacet + facet normal 0.197004 -0.241591 0.95017 + outer loop + vertex 1.15521 0.947382 2.53588 + vertex 1.1539 0.943536 2.53518 + vertex 1.1589 0.948283 2.53535 + endloop + endfacet + facet normal 0.19624 -0.237806 0.951282 + outer loop + vertex 1.1589 0.948283 2.53535 + vertex 1.15731 0.950213 2.53616 + vertex 1.15521 0.947382 2.53588 + endloop + endfacet + facet normal 0.196936 -0.237232 0.951282 + outer loop + vertex 1.16013 0.95198 2.53601 + vertex 1.15731 0.950213 2.53616 + vertex 1.1589 0.948283 2.53535 + endloop + endfacet + facet normal 0.197474 -0.237384 0.951132 + outer loop + vertex 1.16013 0.95198 2.53601 + vertex 1.1589 0.948283 2.53535 + vertex 1.16321 0.952315 2.53546 + endloop + endfacet + facet normal 0.197398 -0.236151 0.951455 + outer loop + vertex 1.16321 0.952315 2.53546 + vertex 1.16234 0.954728 2.53624 + vertex 1.16013 0.95198 2.53601 + endloop + endfacet + facet normal 0.195343 -0.234565 0.952271 + outer loop + vertex 1.16234 0.954728 2.53624 + vertex 1.15842 0.953919 2.53684 + vertex 1.16013 0.95198 2.53601 + endloop + endfacet + facet normal 0.196397 -0.241048 0.950434 + outer loop + vertex 1.16234 0.954728 2.53624 + vertex 1.16369 0.958808 2.53699 + vertex 1.15842 0.953919 2.53684 + endloop + endfacet + facet normal 0.198034 -0.241505 0.949978 + outer loop + vertex 1.16598 0.956351 2.53589 + vertex 1.16369 0.958808 2.53699 + vertex 1.16234 0.954728 2.53624 + endloop + endfacet + facet normal 0.194936 -0.244355 0.94989 + outer loop + vertex 1.16884 0.960377 2.53634 + vertex 1.16369 0.958808 2.53699 + vertex 1.16598 0.956351 2.53589 + endloop + endfacet + facet normal 0.199767 -0.247577 0.94805 + outer loop + vertex 1.16967 0.957983 2.53554 + vertex 1.16884 0.960377 2.53634 + vertex 1.16598 0.956351 2.53589 + endloop + endfacet + facet normal 0.195848 -0.238014 0.951311 + outer loop + vertex 1.16967 0.957983 2.53554 + vertex 1.16598 0.956351 2.53589 + vertex 1.16818 0.953736 2.53479 + endloop + endfacet + facet normal 0.18922 -0.236005 0.953151 + outer loop + vertex 1.16967 0.957983 2.53554 + vertex 1.16818 0.953736 2.53479 + vertex 1.17357 0.958651 2.53493 + endloop + endfacet + facet normal 0.18995 -0.241687 0.951581 + outer loop + vertex 1.17357 0.958651 2.53493 + vertex 1.17204 0.960771 2.53578 + vertex 1.16967 0.957983 2.53554 + endloop + endfacet + facet normal 0.185968 -0.244575 0.95163 + outer loop + vertex 1.17498 0.962485 2.53564 + vertex 1.17204 0.960771 2.53578 + vertex 1.17357 0.958651 2.53493 + endloop + endfacet + facet normal 0.170967 -0.239783 0.955654 + outer loop + vertex 1.17498 0.962485 2.53564 + vertex 1.17357 0.958651 2.53493 + vertex 1.17879 0.963295 2.53516 + endloop + endfacet + facet normal 0.174013 -0.257087 0.950592 + outer loop + vertex 1.17879 0.963295 2.53516 + vertex 1.17723 0.965252 2.53598 + vertex 1.17498 0.962485 2.53564 + endloop + endfacet + facet normal 0.191839 -0.270654 0.943368 + outer loop + vertex 1.17723 0.965252 2.53598 + vertex 1.17336 0.964376 2.53651 + vertex 1.17498 0.962485 2.53564 + endloop + endfacet + facet normal 0.194391 -0.284746 0.938686 + outer loop + vertex 1.17723 0.965252 2.53598 + vertex 1.17848 0.968932 2.53684 + vertex 1.17336 0.964376 2.53651 + endloop + endfacet + facet normal 0.179975 -0.269079 0.946153 + outer loop + vertex 1.17848 0.968932 2.53684 + vertex 1.17346 0.968831 2.53776 + vertex 1.17336 0.964376 2.53651 + endloop + endfacet + facet normal 0.17506 -0.279395 0.944083 + outer loop + vertex 1.18023 0.966992 2.53594 + vertex 1.17848 0.968932 2.53684 + vertex 1.17723 0.965252 2.53598 + endloop + endfacet + facet normal 0.167121 -0.286243 0.94347 + outer loop + vertex 1.18256 0.969751 2.53636 + vertex 1.17848 0.968932 2.53684 + vertex 1.18023 0.966992 2.53594 + endloop + endfacet + facet normal 0.154389 -0.276278 0.948596 + outer loop + vertex 1.18344 0.967367 2.53552 + vertex 1.18256 0.969751 2.53636 + vertex 1.18023 0.966992 2.53594 + endloop + endfacet + facet normal 0.153039 -0.259162 0.953632 + outer loop + vertex 1.18023 0.966992 2.53594 + vertex 1.17879 0.963295 2.53516 + vertex 1.18344 0.967367 2.53552 + endloop + endfacet + facet normal 0.16136 -0.268309 0.949723 + outer loop + vertex 1.18344 0.967367 2.53552 + vertex 1.17879 0.963295 2.53516 + vertex 1.18355 0.963446 2.5344 + endloop + endfacet + facet normal 0.165737 -0.267996 0.949057 + outer loop + vertex 1.18355 0.963446 2.5344 + vertex 1.18843 0.968773 2.53505 + vertex 1.18344 0.967367 2.53552 + endloop + endfacet + facet normal 0.169534 -0.283184 0.943963 + outer loop + vertex 1.18344 0.967367 2.53552 + vertex 1.18843 0.968773 2.53505 + vertex 1.18621 0.971397 2.53624 + endloop + endfacet + facet normal 0.188299 -0.267763 0.944905 + outer loop + vertex 1.18977 0.972977 2.53597 + vertex 1.18621 0.971397 2.53624 + vertex 1.18843 0.968773 2.53505 + endloop + endfacet + facet normal 0.308752 -0.297128 0.903541 + outer loop + vertex 1.18977 0.972977 2.53597 + vertex 1.18843 0.968773 2.53505 + vertex 1.19326 0.973238 2.53487 + endloop + endfacet + facet normal 0.309466 -0.174033 0.934849 + outer loop + vertex 1.19326 0.973238 2.53487 + vertex 1.19147 0.975615 2.5359 + vertex 1.18977 0.972977 2.53597 + endloop + endfacet + facet normal 0.238106 -0.127429 0.962843 + outer loop + vertex 1.19147 0.975615 2.5359 + vertex 1.18822 0.975235 2.53666 + vertex 1.18977 0.972977 2.53597 + endloop + endfacet + facet normal 0.219005 0.058276 0.973982 + outer loop + vertex 1.19147 0.975615 2.5359 + vertex 1.19067 0.978427 2.53591 + vertex 1.18822 0.975235 2.53666 + endloop + endfacet + facet normal 0.269339 0.0169944 0.962896 + outer loop + vertex 1.19067 0.978427 2.53591 + vertex 1.18628 0.978856 2.53714 + vertex 1.18822 0.975235 2.53666 + endloop + endfacet + facet normal 0.128791 -0.0617287 0.989749 + outer loop + vertex 1.18822 0.975235 2.53666 + vertex 1.18628 0.978856 2.53714 + vertex 1.18337 0.973638 2.53719 + endloop + endfacet + facet normal 0.170092 -0.194994 0.965943 + outer loop + vertex 1.18822 0.975235 2.53666 + vertex 1.18337 0.973638 2.53719 + vertex 1.18621 0.971397 2.53624 + endloop + endfacet + facet normal 0.13858 -0.233503 0.96243 + outer loop + vertex 1.18621 0.971397 2.53624 + vertex 1.18337 0.973638 2.53719 + vertex 1.18256 0.969751 2.53636 + endloop + endfacet + facet normal 0.241182 -0.124717 0.962433 + outer loop + vertex 1.18337 0.973638 2.53719 + vertex 1.18628 0.978856 2.53714 + vertex 1.18192 0.977402 2.53804 + endloop + endfacet + facet normal 0.205356 -0.182977 0.96143 + outer loop + vertex 1.19326 0.973238 2.53487 + vertex 1.18843 0.968773 2.53505 + vertex 1.19318 0.968534 2.53399 + endloop + endfacet + facet normal 0.252076 -0.181676 0.950501 + outer loop + vertex 1.19318 0.968534 2.53399 + vertex 1.19681 0.972144 2.53372 + vertex 1.19326 0.973238 2.53487 + endloop + endfacet + facet normal 0.217205 -0.145475 0.965225 + outer loop + vertex 1.1979 0.968661 2.53295 + vertex 1.19681 0.972144 2.53372 + vertex 1.19318 0.968534 2.53399 + endloop + endfacet + facet normal 0.215389 -0.247903 0.944538 + outer loop + vertex 1.19357 0.96408 2.53273 + vertex 1.1979 0.968661 2.53295 + vertex 1.19318 0.968534 2.53399 + endloop + endfacet + facet normal 0.181554 -0.252548 0.950399 + outer loop + vertex 1.19357 0.96408 2.53273 + vertex 1.19318 0.968534 2.53399 + vertex 1.18855 0.963753 2.5336 + endloop + endfacet + facet normal 0.181863 -0.27126 0.945169 + outer loop + vertex 1.18883 0.958799 2.53213 + vertex 1.19357 0.96408 2.53273 + vertex 1.18855 0.963753 2.5336 + endloop + endfacet + facet normal 0.177903 -0.271672 0.945804 + outer loop + vertex 1.18883 0.958799 2.53213 + vertex 1.18855 0.963753 2.5336 + vertex 1.18349 0.958696 2.5331 + endloop + endfacet + facet normal 0.17837 -0.256327 0.94999 + outer loop + vertex 1.18883 0.958799 2.53213 + vertex 1.18349 0.958696 2.5331 + vertex 1.18338 0.953897 2.53183 + endloop + endfacet + facet normal 0.189458 -0.26832 0.944516 + outer loop + vertex 1.18736 0.954631 2.53124 + vertex 1.18883 0.958799 2.53213 + vertex 1.18338 0.953897 2.53183 + endloop + endfacet + facet normal 0.187546 -0.254587 0.94869 + outer loop + vertex 1.18736 0.954631 2.53124 + vertex 1.18338 0.953897 2.53183 + vertex 1.18502 0.95187 2.53096 + endloop + endfacet + facet normal 0.188428 -0.255298 0.948324 + outer loop + vertex 1.18819 0.952196 2.53042 + vertex 1.18736 0.954631 2.53124 + vertex 1.18502 0.95187 2.53096 + endloop + endfacet + facet normal 0.188001 -0.247609 0.950445 + outer loop + vertex 1.18502 0.95187 2.53096 + vertex 1.18374 0.948215 2.53026 + vertex 1.18819 0.952196 2.53042 + endloop + endfacet + facet normal 0.18878 -0.24784 0.95023 + outer loop + vertex 1.18502 0.95187 2.53096 + vertex 1.18215 0.950174 2.53109 + vertex 1.18374 0.948215 2.53026 + endloop + endfacet + facet normal 0.190186 -0.246705 0.950245 + outer loop + vertex 1.18374 0.948215 2.53026 + vertex 1.18215 0.950174 2.53109 + vertex 1.18005 0.947426 2.53079 + endloop + endfacet + facet normal 0.189875 -0.244893 0.950776 + outer loop + vertex 1.18005 0.947426 2.53079 + vertex 1.1787 0.943604 2.53008 + vertex 1.18374 0.948215 2.53026 + endloop + endfacet + facet normal 0.192113 -0.247296 0.949704 + outer loop + vertex 1.18374 0.948215 2.53026 + vertex 1.1787 0.943604 2.53008 + vertex 1.18347 0.943565 2.5291 + endloop + endfacet + facet normal 0.192199 -0.24583 0.950067 + outer loop + vertex 1.17834 0.938681 2.52888 + vertex 1.18347 0.943565 2.5291 + vertex 1.1787 0.943604 2.53008 + endloop + endfacet + facet normal 0.195005 -0.245891 0.949479 + outer loop + vertex 1.1787 0.943604 2.53008 + vertex 1.1733 0.938654 2.52991 + vertex 1.17834 0.938681 2.52888 + endloop + endfacet + facet normal 0.195052 -0.244855 0.949737 + outer loop + vertex 1.1733 0.933686 2.52863 + vertex 1.17834 0.938681 2.52888 + vertex 1.1733 0.938654 2.52991 + endloop + endfacet + facet normal 0.198444 -0.244686 0.949078 + outer loop + vertex 1.1733 0.933686 2.52863 + vertex 1.1733 0.938654 2.52991 + vertex 1.16849 0.933316 2.52954 + endloop + endfacet + facet normal 0.19845 -0.244928 0.949014 + outer loop + vertex 1.16843 0.928668 2.52835 + vertex 1.1733 0.933686 2.52863 + vertex 1.16849 0.933316 2.52954 + endloop + endfacet + facet normal 0.199366 -0.244893 0.948831 + outer loop + vertex 1.16843 0.928668 2.52835 + vertex 1.16849 0.933316 2.52954 + vertex 1.16365 0.928501 2.52931 + endloop + endfacet + facet normal 0.199346 -0.246101 0.948523 + outer loop + vertex 1.16347 0.923722 2.52811 + vertex 1.16843 0.928668 2.52835 + vertex 1.16365 0.928501 2.52931 + endloop + endfacet + facet normal 0.198682 -0.246111 0.94866 + outer loop + vertex 1.16347 0.923722 2.52811 + vertex 1.16365 0.928501 2.52931 + vertex 1.15858 0.92363 2.52911 + endloop + endfacet + facet normal 0.198687 -0.245964 0.948696 + outer loop + vertex 1.15836 0.918844 2.52792 + vertex 1.16347 0.923722 2.52811 + vertex 1.15858 0.92363 2.52911 + endloop + endfacet + facet normal 0.207032 -0.245915 0.946923 + outer loop + vertex 1.15836 0.918844 2.52792 + vertex 1.15858 0.92363 2.52911 + vertex 1.15348 0.918767 2.52896 + endloop + endfacet + facet normal 0.207401 -0.235938 0.949378 + outer loop + vertex 1.15325 0.913991 2.52782 + vertex 1.15836 0.918844 2.52792 + vertex 1.15348 0.918767 2.52896 + endloop + endfacet + facet normal 0.241694 -0.23565 0.941304 + outer loop + vertex 1.15325 0.913991 2.52782 + vertex 1.15348 0.918767 2.52896 + vertex 1.14855 0.914015 2.52904 + endloop + endfacet + facet normal 0.24363 -0.204046 0.948161 + outer loop + vertex 1.14825 0.90909 2.52805 + vertex 1.15325 0.913991 2.52782 + vertex 1.14855 0.914015 2.52904 + endloop + endfacet + facet normal 0.28162 -0.243741 0.928052 + outer loop + vertex 1.15308 0.90929 2.52664 + vertex 1.15325 0.913991 2.52782 + vertex 1.14825 0.90909 2.52805 + endloop + endfacet + facet normal 0.221581 -0.24547 0.943741 + outer loop + vertex 1.15823 0.914174 2.5267 + vertex 1.15325 0.913991 2.52782 + vertex 1.15308 0.90929 2.52664 + endloop + endfacet + facet normal 0.248364 -0.27359 0.929228 + outer loop + vertex 1.15706 0.910448 2.52592 + vertex 1.15823 0.914174 2.5267 + vertex 1.15308 0.90929 2.52664 + endloop + endfacet + facet normal 0.24861 -0.274676 0.928842 + outer loop + vertex 1.15706 0.910448 2.52592 + vertex 1.15308 0.90929 2.52664 + vertex 1.15492 0.907584 2.52565 + endloop + endfacet + facet normal 0.205919 -0.24462 0.947501 + outer loop + vertex 1.15884 0.90863 2.52506 + vertex 1.15706 0.910448 2.52592 + vertex 1.15492 0.907584 2.52565 + endloop + endfacet + facet normal 0.196323 -0.20202 0.959503 + outer loop + vertex 1.15492 0.907584 2.52565 + vertex 1.15386 0.903821 2.52507 + vertex 1.15884 0.90863 2.52506 + endloop + endfacet + facet normal 0.224688 -0.231412 0.946554 + outer loop + vertex 1.15884 0.90863 2.52506 + vertex 1.15386 0.903821 2.52507 + vertex 1.15848 0.903847 2.52398 + endloop + endfacet + facet normal 0.203022 -0.230955 0.951547 + outer loop + vertex 1.15848 0.903847 2.52398 + vertex 1.16357 0.908699 2.52407 + vertex 1.15884 0.90863 2.52506 + endloop + endfacet + facet normal 0.20207 -0.256206 0.945265 + outer loop + vertex 1.16387 0.913322 2.52526 + vertex 1.15884 0.90863 2.52506 + vertex 1.16357 0.908699 2.52407 + endloop + endfacet + facet normal 0.202814 -0.256212 0.945104 + outer loop + vertex 1.16357 0.908699 2.52407 + vertex 1.16848 0.913488 2.52431 + vertex 1.16387 0.913322 2.52526 + endloop + endfacet + facet normal 0.202762 -0.258951 0.944369 + outer loop + vertex 1.16822 0.917355 2.52543 + vertex 1.16387 0.913322 2.52526 + vertex 1.16848 0.913488 2.52431 + endloop + endfacet + facet normal 0.205891 -0.258574 0.943795 + outer loop + vertex 1.16848 0.913488 2.52431 + vertex 1.17323 0.918799 2.52473 + vertex 1.16822 0.917355 2.52543 + endloop + endfacet + facet normal 0.20459 -0.253226 0.945526 + outer loop + vertex 1.16822 0.917355 2.52543 + vertex 1.17323 0.918799 2.52473 + vertex 1.17098 0.921394 2.52592 + endloop + endfacet + facet normal 0.205368 -0.253722 0.945225 + outer loop + vertex 1.16733 0.91976 2.52627 + vertex 1.16822 0.917355 2.52543 + vertex 1.17098 0.921394 2.52592 + endloop + endfacet + facet normal 0.202673 -0.2472 0.947531 + outer loop + vertex 1.17098 0.921394 2.52592 + vertex 1.16866 0.923851 2.52705 + vertex 1.16733 0.91976 2.52627 + endloop + endfacet + facet normal 0.198097 -0.245961 0.948821 + outer loop + vertex 1.16733 0.91976 2.52627 + vertex 1.16866 0.923851 2.52705 + vertex 1.16339 0.918959 2.52689 + endloop + endfacet + facet normal 0.198707 -0.249849 0.947677 + outer loop + vertex 1.16733 0.91976 2.52627 + vertex 1.16339 0.918959 2.52689 + vertex 1.16511 0.916998 2.52601 + endloop + endfacet + facet normal 0.196084 -0.252127 0.94762 + outer loop + vertex 1.16511 0.916998 2.52601 + vertex 1.16339 0.918959 2.52689 + vertex 1.16224 0.915229 2.52613 + endloop + endfacet + facet normal 0.200768 -0.259943 0.944522 + outer loop + vertex 1.16511 0.916998 2.52601 + vertex 1.16224 0.915229 2.52613 + vertex 1.16387 0.913322 2.52526 + endloop + endfacet + facet normal 0.199019 -0.261419 0.944485 + outer loop + vertex 1.16387 0.913322 2.52526 + vertex 1.16224 0.915229 2.52613 + vertex 1.16012 0.912411 2.5258 + endloop + endfacet + facet normal 0.204218 -0.265083 0.942351 + outer loop + vertex 1.16224 0.915229 2.52613 + vertex 1.15823 0.914174 2.5267 + vertex 1.16012 0.912411 2.5258 + endloop + endfacet + facet normal 0.201704 -0.253541 0.946062 + outer loop + vertex 1.16224 0.915229 2.52613 + vertex 1.16339 0.918959 2.52689 + vertex 1.15823 0.914174 2.5267 + endloop + endfacet + facet normal 0.199553 -0.251265 0.947124 + outer loop + vertex 1.16339 0.918959 2.52689 + vertex 1.15836 0.918844 2.52792 + vertex 1.15823 0.914174 2.5267 + endloop + endfacet + facet normal 0.201219 -0.248553 0.947487 + outer loop + vertex 1.17376 0.925423 2.52638 + vertex 1.16866 0.923851 2.52705 + vertex 1.17098 0.921394 2.52592 + endloop + endfacet + facet normal 0.202888 -0.24963 0.946848 + outer loop + vertex 1.17465 0.923032 2.52556 + vertex 1.17376 0.925423 2.52638 + vertex 1.17098 0.921394 2.52592 + endloop + endfacet + facet normal 0.201041 -0.250387 0.947042 + outer loop + vertex 1.17694 0.925824 2.52581 + vertex 1.17376 0.925423 2.52638 + vertex 1.17465 0.923032 2.52556 + endloop + endfacet + facet normal 0.201507 -0.250751 0.946847 + outer loop + vertex 1.17854 0.923735 2.52492 + vertex 1.17694 0.925824 2.52581 + vertex 1.17465 0.923032 2.52556 + endloop + endfacet + facet normal 0.201754 -0.252618 0.946298 + outer loop + vertex 1.17465 0.923032 2.52556 + vertex 1.17323 0.918799 2.52473 + vertex 1.17854 0.923735 2.52492 + endloop + endfacet + facet normal 0.202844 -0.25377 0.945756 + outer loop + vertex 1.17854 0.923735 2.52492 + vertex 1.17323 0.918799 2.52473 + vertex 1.17843 0.918776 2.52361 + endloop + endfacet + facet normal 0.200609 -0.253838 0.946215 + outer loop + vertex 1.17843 0.918776 2.52361 + vertex 1.18343 0.923725 2.52388 + vertex 1.17854 0.923735 2.52492 + endloop + endfacet + facet normal 0.200651 -0.253083 0.946408 + outer loop + vertex 1.18372 0.928535 2.52511 + vertex 1.17854 0.923735 2.52492 + vertex 1.18343 0.923725 2.52388 + endloop + endfacet + facet normal 0.198188 -0.253071 0.94693 + outer loop + vertex 1.18343 0.923725 2.52388 + vertex 1.18849 0.928587 2.52412 + vertex 1.18372 0.928535 2.52511 + endloop + endfacet + facet normal 0.1982 -0.252789 0.947003 + outer loop + vertex 1.1888 0.93326 2.5253 + vertex 1.18372 0.928535 2.52511 + vertex 1.18849 0.928587 2.52412 + endloop + endfacet + facet normal 0.19333 -0.252729 0.948025 + outer loop + vertex 1.18849 0.928587 2.52412 + vertex 1.19345 0.933422 2.5244 + vertex 1.1888 0.93326 2.5253 + endloop + endfacet + facet normal 0.193317 -0.253505 0.947821 + outer loop + vertex 1.19326 0.937317 2.52548 + vertex 1.1888 0.93326 2.5253 + vertex 1.19345 0.933422 2.5244 + endloop + endfacet + facet normal 0.187251 -0.254086 0.948882 + outer loop + vertex 1.19345 0.933422 2.5244 + vertex 1.19831 0.93873 2.52486 + vertex 1.19326 0.937317 2.52548 + endloop + endfacet + facet normal 0.187085 -0.253399 0.949099 + outer loop + vertex 1.19326 0.937317 2.52548 + vertex 1.19831 0.93873 2.52486 + vertex 1.19613 0.941348 2.52599 + endloop + endfacet + facet normal 0.186766 -0.253186 0.949218 + outer loop + vertex 1.1924 0.939742 2.52629 + vertex 1.19326 0.937317 2.52548 + vertex 1.19613 0.941348 2.52599 + endloop + endfacet + facet normal 0.186501 -0.252527 0.949446 + outer loop + vertex 1.19613 0.941348 2.52599 + vertex 1.19375 0.94382 2.52711 + vertex 1.1924 0.939742 2.52629 + endloop + endfacet + facet normal 0.192668 -0.254229 0.947759 + outer loop + vertex 1.1924 0.939742 2.52629 + vertex 1.19375 0.94382 2.52711 + vertex 1.1884 0.938947 2.52689 + endloop + endfacet + facet normal 0.192578 -0.253644 0.947934 + outer loop + vertex 1.1924 0.939742 2.52629 + vertex 1.1884 0.938947 2.52689 + vertex 1.1901 0.936971 2.52602 + endloop + endfacet + facet normal 0.194914 -0.251657 0.947986 + outer loop + vertex 1.1901 0.936971 2.52602 + vertex 1.1884 0.938947 2.52689 + vertex 1.1872 0.935204 2.52615 + endloop + endfacet + facet normal 0.194819 -0.251495 0.948049 + outer loop + vertex 1.1901 0.936971 2.52602 + vertex 1.1872 0.935204 2.52615 + vertex 1.1888 0.93326 2.5253 + endloop + endfacet + facet normal 0.197008 -0.252215 0.947405 + outer loop + vertex 1.1872 0.935204 2.52615 + vertex 1.1884 0.938947 2.52689 + vertex 1.18322 0.934166 2.5267 + endloop + endfacet + facet normal 0.196668 -0.250658 0.947888 + outer loop + vertex 1.1872 0.935204 2.52615 + vertex 1.18322 0.934166 2.5267 + vertex 1.18503 0.932359 2.52584 + endloop + endfacet + facet normal 0.196227 -0.250342 0.948063 + outer loop + vertex 1.1888 0.93326 2.5253 + vertex 1.1872 0.935204 2.52615 + vertex 1.18503 0.932359 2.52584 + endloop + endfacet + facet normal 0.196317 -0.250802 0.947923 + outer loop + vertex 1.18503 0.932359 2.52584 + vertex 1.18372 0.928535 2.52511 + vertex 1.1888 0.93326 2.5253 + endloop + endfacet + facet normal 0.198765 -0.251512 0.947224 + outer loop + vertex 1.18503 0.932359 2.52584 + vertex 1.182 0.930425 2.52597 + vertex 1.18372 0.928535 2.52511 + endloop + endfacet + facet normal 0.197642 -0.249705 0.947937 + outer loop + vertex 1.18503 0.932359 2.52584 + vertex 1.18322 0.934166 2.5267 + vertex 1.182 0.930425 2.52597 + endloop + endfacet + facet normal 0.197973 -0.249795 0.947845 + outer loop + vertex 1.182 0.930425 2.52597 + vertex 1.18322 0.934166 2.5267 + vertex 1.17817 0.929461 2.52651 + endloop + endfacet + facet normal 0.198089 -0.250354 0.947673 + outer loop + vertex 1.182 0.930425 2.52597 + vertex 1.17817 0.929461 2.52651 + vertex 1.17984 0.927583 2.52567 + endloop + endfacet + facet normal 0.199181 -0.25114 0.947236 + outer loop + vertex 1.18372 0.928535 2.52511 + vertex 1.182 0.930425 2.52597 + vertex 1.17984 0.927583 2.52567 + endloop + endfacet + facet normal 0.198815 -0.249715 0.947689 + outer loop + vertex 1.17984 0.927583 2.52567 + vertex 1.17817 0.929461 2.52651 + vertex 1.17694 0.925824 2.52581 + endloop + endfacet + facet normal 0.195949 -0.247657 0.948826 + outer loop + vertex 1.18322 0.934166 2.5267 + vertex 1.17824 0.933937 2.52767 + vertex 1.17817 0.929461 2.52651 + endloop + endfacet + facet normal 0.198558 -0.247568 0.948306 + outer loop + vertex 1.17817 0.929461 2.52651 + vertex 1.17824 0.933937 2.52767 + vertex 1.17336 0.929115 2.52743 + endloop + endfacet + facet normal 0.198561 -0.247678 0.948277 + outer loop + vertex 1.17817 0.929461 2.52651 + vertex 1.17336 0.929115 2.52743 + vertex 1.17376 0.925423 2.52638 + endloop + endfacet + facet normal 0.196758 -0.245788 0.949144 + outer loop + vertex 1.17336 0.929115 2.52743 + vertex 1.17824 0.933937 2.52767 + vertex 1.1733 0.933686 2.52863 + endloop + endfacet + facet normal 0.195945 -0.248637 0.94857 + outer loop + vertex 1.18322 0.934166 2.5267 + vertex 1.18334 0.938813 2.52789 + vertex 1.17824 0.933937 2.52767 + endloop + endfacet + facet normal 0.193973 -0.24662 0.949501 + outer loop + vertex 1.17824 0.933937 2.52767 + vertex 1.18334 0.938813 2.52789 + vertex 1.17834 0.938681 2.52888 + endloop + endfacet + facet normal 0.193698 -0.248696 0.949016 + outer loop + vertex 1.1884 0.938947 2.52689 + vertex 1.18334 0.938813 2.52789 + vertex 1.18322 0.934166 2.5267 + endloop + endfacet + facet normal 0.19367 -0.249866 0.948715 + outer loop + vertex 1.1884 0.938947 2.52689 + vertex 1.18844 0.943691 2.52814 + vertex 1.18334 0.938813 2.52789 + endloop + endfacet + facet normal 0.191536 -0.247683 0.949719 + outer loop + vertex 1.18334 0.938813 2.52789 + vertex 1.18844 0.943691 2.52814 + vertex 1.18347 0.943565 2.5291 + endloop + endfacet + facet normal 0.191513 -0.248641 0.949474 + outer loop + vertex 1.18844 0.943691 2.52814 + vertex 1.18841 0.948344 2.52936 + vertex 1.18347 0.943565 2.5291 + endloop + endfacet + facet normal 0.187763 -0.248853 0.950167 + outer loop + vertex 1.18844 0.943691 2.52814 + vertex 1.19341 0.948658 2.52845 + vertex 1.18841 0.948344 2.52936 + endloop + endfacet + facet normal 0.187816 -0.252524 0.949187 + outer loop + vertex 1.19341 0.948658 2.52845 + vertex 1.19329 0.953603 2.52979 + vertex 1.18841 0.948344 2.52936 + endloop + endfacet + facet normal 0.185439 -0.250401 0.950217 + outer loop + vertex 1.18841 0.948344 2.52936 + vertex 1.19329 0.953603 2.52979 + vertex 1.18819 0.952196 2.53042 + endloop + endfacet + facet normal 0.190106 -0.249922 0.94942 + outer loop + vertex 1.18819 0.952196 2.53042 + vertex 1.18374 0.948215 2.53026 + vertex 1.18841 0.948344 2.52936 + endloop + endfacet + facet normal 0.190164 -0.247282 0.9501 + outer loop + vertex 1.18347 0.943565 2.5291 + vertex 1.18841 0.948344 2.52936 + vertex 1.18374 0.948215 2.53026 + endloop + endfacet + facet normal 0.187169 -0.257686 0.947927 + outer loop + vertex 1.18819 0.952196 2.53042 + vertex 1.19329 0.953603 2.52979 + vertex 1.19115 0.95624 2.53093 + endloop + endfacet + facet normal 0.184452 -0.259866 0.947865 + outer loop + vertex 1.19494 0.957812 2.53063 + vertex 1.19115 0.95624 2.53093 + vertex 1.19329 0.953603 2.52979 + endloop + endfacet + facet normal 0.171958 -0.255672 0.951348 + outer loop + vertex 1.19494 0.957812 2.53063 + vertex 1.19329 0.953603 2.52979 + vertex 1.19871 0.958348 2.53009 + endloop + endfacet + facet normal 0.173263 -0.268704 0.947511 + outer loop + vertex 1.19871 0.958348 2.53009 + vertex 1.19733 0.960563 2.53097 + vertex 1.19494 0.957812 2.53063 + endloop + endfacet + facet normal 0.185369 -0.278615 0.942344 + outer loop + vertex 1.19733 0.960563 2.53097 + vertex 1.19411 0.960295 2.53152 + vertex 1.19494 0.957812 2.53063 + endloop + endfacet + facet normal 0.185353 -0.278089 0.942502 + outer loop + vertex 1.19733 0.960563 2.53097 + vertex 1.19849 0.96424 2.53183 + vertex 1.19411 0.960295 2.53152 + endloop + endfacet + facet normal 0.182558 -0.275091 0.943927 + outer loop + vertex 1.19849 0.96424 2.53183 + vertex 1.19357 0.96408 2.53273 + vertex 1.19411 0.960295 2.53152 + endloop + endfacet + facet normal 0.164463 -0.272777 0.947916 + outer loop + vertex 1.20016 0.962099 2.53092 + vertex 1.19849 0.96424 2.53183 + vertex 1.19733 0.960563 2.53097 + endloop + endfacet + facet normal 0.161772 -0.274816 0.94779 + outer loop + vertex 1.20243 0.964869 2.53134 + vertex 1.19849 0.96424 2.53183 + vertex 1.20016 0.962099 2.53092 + endloop + endfacet + facet normal 0.157828 -0.271814 0.94932 + outer loop + vertex 1.20334 0.962386 2.53047 + vertex 1.20243 0.964869 2.53134 + vertex 1.20016 0.962099 2.53092 + endloop + endfacet + facet normal 0.157812 -0.271478 0.949418 + outer loop + vertex 1.20016 0.962099 2.53092 + vertex 1.19871 0.958348 2.53009 + vertex 1.20334 0.962386 2.53047 + endloop + endfacet + facet normal 0.166508 -0.281026 0.945145 + outer loop + vertex 1.20334 0.962386 2.53047 + vertex 1.19871 0.958348 2.53009 + vertex 1.20348 0.958446 2.52928 + endloop + endfacet + facet normal 0.168251 -0.28088 0.94488 + outer loop + vertex 1.20348 0.958446 2.52928 + vertex 1.20846 0.96388 2.53001 + vertex 1.20334 0.962386 2.53047 + endloop + endfacet + facet normal 0.16798 -0.279839 0.945237 + outer loop + vertex 1.20334 0.962386 2.53047 + vertex 1.20846 0.96388 2.53001 + vertex 1.20613 0.966487 2.53119 + endloop + endfacet + facet normal 0.168854 -0.279088 0.945303 + outer loop + vertex 1.20979 0.968113 2.53102 + vertex 1.20613 0.966487 2.53119 + vertex 1.20846 0.96388 2.53001 + endloop + endfacet + facet normal 0.271265 -0.303565 0.91338 + outer loop + vertex 1.20979 0.968113 2.53102 + vertex 1.20846 0.96388 2.53001 + vertex 1.21326 0.968515 2.53012 + endloop + endfacet + facet normal 0.267534 -0.212494 0.939825 + outer loop + vertex 1.21326 0.968515 2.53012 + vertex 1.21138 0.970586 2.53112 + vertex 1.20979 0.968113 2.53102 + endloop + endfacet + facet normal 0.157581 -0.143045 0.977091 + outer loop + vertex 1.21138 0.970586 2.53112 + vertex 1.20824 0.970194 2.53157 + vertex 1.20979 0.968113 2.53102 + endloop + endfacet + facet normal 0.124462 0.130009 0.98367 + outer loop + vertex 1.21138 0.970586 2.53112 + vertex 1.21068 0.972879 2.53091 + vertex 1.20824 0.970194 2.53157 + endloop + endfacet + facet normal 0.130752 0.124282 0.983594 + outer loop + vertex 1.21068 0.972879 2.53091 + vertex 1.20664 0.973086 2.53142 + vertex 1.20824 0.970194 2.53157 + endloop + endfacet + facet normal 0.0608293 0.0862309 0.994416 + outer loop + vertex 1.20824 0.970194 2.53157 + vertex 1.20664 0.973086 2.53142 + vertex 1.20321 0.968843 2.532 + endloop + endfacet + facet normal 0.129138 -0.173819 0.976274 + outer loop + vertex 1.20824 0.970194 2.53157 + vertex 1.20321 0.968843 2.532 + vertex 1.20613 0.966487 2.53119 + endloop + endfacet + facet normal 0.119224 -0.18577 0.975333 + outer loop + vertex 1.20613 0.966487 2.53119 + vertex 1.20321 0.968843 2.532 + vertex 1.20243 0.964869 2.53134 + endloop + endfacet + facet normal 0.153699 0.0102786 0.988064 + outer loop + vertex 1.20321 0.968843 2.532 + vertex 1.20664 0.973086 2.53142 + vertex 1.20152 0.97352 2.53221 + endloop + endfacet + facet normal 0.175189 0.0182103 0.984366 + outer loop + vertex 1.20321 0.968843 2.532 + vertex 1.20152 0.97352 2.53221 + vertex 1.1979 0.968661 2.53295 + endloop + endfacet + facet normal 0.178832 -0.219174 0.959157 + outer loop + vertex 1.20321 0.968843 2.532 + vertex 1.1979 0.968661 2.53295 + vertex 1.19849 0.96424 2.53183 + endloop + endfacet + facet normal 0.202047 -0.232879 0.951285 + outer loop + vertex 1.21326 0.968515 2.53012 + vertex 1.20846 0.96388 2.53001 + vertex 1.21348 0.963774 2.52891 + endloop + endfacet + facet normal 0.252311 -0.227751 0.940462 + outer loop + vertex 1.21348 0.963774 2.52891 + vertex 1.21778 0.967931 2.52877 + vertex 1.21326 0.968515 2.53012 + endloop + endfacet + facet normal 0.1996 -0.172337 0.964603 + outer loop + vertex 1.21823 0.963649 2.52791 + vertex 1.21778 0.967931 2.52877 + vertex 1.21348 0.963774 2.52891 + endloop + endfacet + facet normal 0.192767 -0.267268 0.944144 + outer loop + vertex 1.21362 0.959164 2.52758 + vertex 1.21823 0.963649 2.52791 + vertex 1.21348 0.963774 2.52891 + endloop + endfacet + facet normal 0.181957 -0.268148 0.946038 + outer loop + vertex 1.21362 0.959164 2.52758 + vertex 1.21348 0.963774 2.52891 + vertex 1.20856 0.958817 2.52846 + endloop + endfacet + facet normal 0.182096 -0.275815 0.943805 + outer loop + vertex 1.2087 0.953884 2.52699 + vertex 1.21362 0.959164 2.52758 + vertex 1.20856 0.958817 2.52846 + endloop + endfacet + facet normal 0.177585 -0.276169 0.94456 + outer loop + vertex 1.2087 0.953884 2.52699 + vertex 1.20856 0.958817 2.52846 + vertex 1.20344 0.953766 2.52794 + endloop + endfacet + facet normal 0.178037 -0.259984 0.949058 + outer loop + vertex 1.2087 0.953884 2.52699 + vertex 1.20344 0.953766 2.52794 + vertex 1.20337 0.949169 2.52669 + endloop + endfacet + facet normal 0.182623 -0.265021 0.946791 + outer loop + vertex 1.20716 0.949742 2.52612 + vertex 1.2087 0.953884 2.52699 + vertex 1.20337 0.949169 2.52669 + endloop + endfacet + facet normal 0.181609 -0.255532 0.94959 + outer loop + vertex 1.20716 0.949742 2.52612 + vertex 1.20337 0.949169 2.52669 + vertex 1.20486 0.947056 2.52584 + endloop + endfacet + facet normal 0.185774 -0.258923 0.947864 + outer loop + vertex 1.20799 0.947295 2.52529 + vertex 1.20716 0.949742 2.52612 + vertex 1.20486 0.947056 2.52584 + endloop + endfacet + facet normal 0.185748 -0.257978 0.948127 + outer loop + vertex 1.20486 0.947056 2.52584 + vertex 1.20356 0.943416 2.52511 + vertex 1.20799 0.947295 2.52529 + endloop + endfacet + facet normal 0.183626 -0.257339 0.948714 + outer loop + vertex 1.20486 0.947056 2.52584 + vertex 1.20214 0.945588 2.52597 + vertex 1.20356 0.943416 2.52511 + endloop + endfacet + facet normal 0.184375 -0.256846 0.948702 + outer loop + vertex 1.20356 0.943416 2.52511 + vertex 1.20214 0.945588 2.52597 + vertex 1.19985 0.942912 2.52569 + endloop + endfacet + facet normal 0.184323 -0.256271 0.948868 + outer loop + vertex 1.19985 0.942912 2.52569 + vertex 1.19831 0.93873 2.52486 + vertex 1.20356 0.943416 2.52511 + endloop + endfacet + facet normal 0.180903 -0.254025 0.950129 + outer loop + vertex 1.20214 0.945588 2.52597 + vertex 1.19897 0.945309 2.5265 + vertex 1.19985 0.942912 2.52569 + endloop + endfacet + facet normal 0.18269 -0.253311 0.949978 + outer loop + vertex 1.19985 0.942912 2.52569 + vertex 1.19897 0.945309 2.5265 + vertex 1.19613 0.941348 2.52599 + endloop + endfacet + facet normal 0.180925 -0.254557 0.949983 + outer loop + vertex 1.20214 0.945588 2.52597 + vertex 1.20337 0.949169 2.52669 + vertex 1.19897 0.945309 2.5265 + endloop + endfacet + facet normal 0.184844 -0.259266 0.947952 + outer loop + vertex 1.20716 0.949742 2.52612 + vertex 1.20799 0.947295 2.52529 + vertex 1.21093 0.95132 2.52582 + endloop + endfacet + facet normal 0.185934 -0.260008 0.947536 + outer loop + vertex 1.20799 0.947295 2.52529 + vertex 1.21315 0.948681 2.52466 + vertex 1.21093 0.95132 2.52582 + endloop + endfacet + facet normal 0.18379 -0.261783 0.947465 + outer loop + vertex 1.21472 0.952909 2.52553 + vertex 1.21093 0.95132 2.52582 + vertex 1.21315 0.948681 2.52466 + endloop + endfacet + facet normal 0.170064 -0.257456 0.951207 + outer loop + vertex 1.21472 0.952909 2.52553 + vertex 1.21315 0.948681 2.52466 + vertex 1.21853 0.953424 2.52498 + endloop + endfacet + facet normal 0.170821 -0.265558 0.948841 + outer loop + vertex 1.21853 0.953424 2.52498 + vertex 1.21713 0.95566 2.52586 + vertex 1.21472 0.952909 2.52553 + endloop + endfacet + facet normal 0.182391 -0.275118 0.943951 + outer loop + vertex 1.21713 0.95566 2.52586 + vertex 1.21393 0.955382 2.5264 + vertex 1.21472 0.952909 2.52553 + endloop + endfacet + facet normal 0.182701 -0.28375 0.941332 + outer loop + vertex 1.21713 0.95566 2.52586 + vertex 1.21844 0.959288 2.5267 + vertex 1.21393 0.955382 2.5264 + endloop + endfacet + facet normal 0.179438 -0.280121 0.943045 + outer loop + vertex 1.21844 0.959288 2.5267 + vertex 1.21362 0.959164 2.52758 + vertex 1.21393 0.955382 2.5264 + endloop + endfacet + facet normal 0.165895 -0.27877 0.945921 + outer loop + vertex 1.21995 0.957159 2.52581 + vertex 1.21844 0.959288 2.5267 + vertex 1.21713 0.95566 2.52586 + endloop + endfacet + facet normal 0.162302 -0.281272 0.945804 + outer loop + vertex 1.22226 0.959861 2.52622 + vertex 1.21844 0.959288 2.5267 + vertex 1.21995 0.957159 2.52581 + endloop + endfacet + facet normal 0.15342 -0.274192 0.949358 + outer loop + vertex 1.22312 0.957386 2.52536 + vertex 1.22226 0.959861 2.52622 + vertex 1.21995 0.957159 2.52581 + endloop + endfacet + facet normal 0.153243 -0.268377 0.951047 + outer loop + vertex 1.21995 0.957159 2.52581 + vertex 1.21853 0.953424 2.52498 + vertex 1.22312 0.957386 2.52536 + endloop + endfacet + facet normal 0.163046 -0.279259 0.946272 + outer loop + vertex 1.22312 0.957386 2.52536 + vertex 1.21853 0.953424 2.52498 + vertex 1.22339 0.953475 2.52416 + endloop + endfacet + facet normal 0.165279 -0.279008 0.945959 + outer loop + vertex 1.22339 0.953475 2.52416 + vertex 1.22831 0.95883 2.52488 + vertex 1.22312 0.957386 2.52536 + endloop + endfacet + facet normal 0.165451 -0.279704 0.945723 + outer loop + vertex 1.22312 0.957386 2.52536 + vertex 1.22831 0.95883 2.52488 + vertex 1.22598 0.961443 2.52606 + endloop + endfacet + facet normal 0.177977 -0.26891 0.946579 + outer loop + vertex 1.22974 0.963114 2.52583 + vertex 1.22598 0.961443 2.52606 + vertex 1.22831 0.95883 2.52488 + endloop + endfacet + facet normal 0.253175 -0.288812 0.923304 + outer loop + vertex 1.22974 0.963114 2.52583 + vertex 1.22831 0.95883 2.52488 + vertex 1.23354 0.963693 2.52497 + endloop + endfacet + facet normal 0.244278 -0.18909 0.95109 + outer loop + vertex 1.23354 0.963693 2.52497 + vertex 1.23173 0.965877 2.52587 + vertex 1.22974 0.963114 2.52583 + endloop + endfacet + facet normal 0.19645 -0.15484 0.968211 + outer loop + vertex 1.23173 0.965877 2.52587 + vertex 1.22827 0.965347 2.52648 + vertex 1.22974 0.963114 2.52583 + endloop + endfacet + facet normal 0.174017 0.0107664 0.984684 + outer loop + vertex 1.23173 0.965877 2.52587 + vertex 1.23115 0.968539 2.52594 + vertex 1.22827 0.965347 2.52648 + endloop + endfacet + facet normal 0.198545 -0.0121428 0.980017 + outer loop + vertex 1.23115 0.968539 2.52594 + vertex 1.22636 0.968675 2.52691 + vertex 1.22827 0.965347 2.52648 + endloop + endfacet + facet normal 0.121256 -0.0580443 0.990923 + outer loop + vertex 1.22827 0.965347 2.52648 + vertex 1.22636 0.968675 2.52691 + vertex 1.22324 0.963755 2.52701 + endloop + endfacet + facet normal 0.163845 -0.200783 0.965837 + outer loop + vertex 1.22827 0.965347 2.52648 + vertex 1.22324 0.963755 2.52701 + vertex 1.22598 0.961443 2.52606 + endloop + endfacet + facet normal 0.137931 -0.2304 0.963271 + outer loop + vertex 1.22598 0.961443 2.52606 + vertex 1.22324 0.963755 2.52701 + vertex 1.22226 0.959861 2.52622 + endloop + endfacet + facet normal 0.230731 -0.127767 0.964593 + outer loop + vertex 1.22324 0.963755 2.52701 + vertex 1.22636 0.968675 2.52691 + vertex 1.22174 0.967243 2.52783 + endloop + endfacet + facet normal 0.178366 -0.152111 0.972136 + outer loop + vertex 1.22324 0.963755 2.52701 + vertex 1.22174 0.967243 2.52783 + vertex 1.21823 0.963649 2.52791 + endloop + endfacet + facet normal 0.176669 -0.254986 0.950668 + outer loop + vertex 1.22324 0.963755 2.52701 + vertex 1.21823 0.963649 2.52791 + vertex 1.21844 0.959288 2.5267 + endloop + endfacet + facet normal 0.313559 0.042322 0.948625 + outer loop + vertex 1.23477 0.968023 2.52477 + vertex 1.23115 0.968539 2.52594 + vertex 1.23173 0.965877 2.52587 + endloop + endfacet + facet normal 0.380114 -0.0650355 0.92265 + outer loop + vertex 1.23477 0.968023 2.52477 + vertex 1.23173 0.965877 2.52587 + vertex 1.23354 0.963693 2.52497 + endloop + endfacet + facet normal 0.255967 -0.0278773 0.966283 + outer loop + vertex 1.23477 0.968023 2.52477 + vertex 1.23354 0.963693 2.52497 + vertex 1.23757 0.966924 2.52399 + endloop + endfacet + facet normal 0.184956 -0.216132 0.958686 + outer loop + vertex 1.23354 0.963693 2.52497 + vertex 1.22831 0.95883 2.52488 + vertex 1.23352 0.958798 2.52387 + endloop + endfacet + facet normal 0.212884 -0.215012 0.953127 + outer loop + vertex 1.23352 0.958798 2.52387 + vertex 1.23805 0.963425 2.5239 + vertex 1.23354 0.963693 2.52497 + endloop + endfacet + facet normal 0.230711 0.00565642 0.973006 + outer loop + vertex 1.23757 0.966924 2.52399 + vertex 1.23354 0.963693 2.52497 + vertex 1.23805 0.963425 2.5239 + endloop + endfacet + facet normal 0.247021 0.00797614 0.968977 + outer loop + vertex 1.23805 0.963425 2.5239 + vertex 1.24146 0.967402 2.523 + vertex 1.23757 0.966924 2.52399 + endloop + endfacet + facet normal 0.180317 -0.183226 0.966392 + outer loop + vertex 1.23857 0.95907 2.52298 + vertex 1.23805 0.963425 2.5239 + vertex 1.23352 0.958798 2.52387 + endloop + endfacet + facet normal 0.181348 -0.275048 0.944172 + outer loop + vertex 1.23383 0.953789 2.52235 + vertex 1.23857 0.95907 2.52298 + vertex 1.23352 0.958798 2.52387 + endloop + endfacet + facet normal 0.176805 -0.275553 0.944887 + outer loop + vertex 1.23383 0.953789 2.52235 + vertex 1.23352 0.958798 2.52387 + vertex 1.22852 0.953785 2.52334 + endloop + endfacet + facet normal 0.176097 -0.288809 0.941052 + outer loop + vertex 1.23383 0.953789 2.52235 + vertex 1.22852 0.953785 2.52334 + vertex 1.22856 0.949081 2.52189 + endloop + endfacet + facet normal 0.183224 -0.296431 0.937314 + outer loop + vertex 1.23237 0.949611 2.52131 + vertex 1.23383 0.953789 2.52235 + vertex 1.22856 0.949081 2.52189 + endloop + endfacet + facet normal 0.182296 -0.286046 0.940716 + outer loop + vertex 1.23237 0.949611 2.52131 + vertex 1.22856 0.949081 2.52189 + vertex 1.23006 0.946935 2.52095 + endloop + endfacet + facet normal 0.187162 -0.282665 0.940782 + outer loop + vertex 1.23006 0.946935 2.52095 + vertex 1.22856 0.949081 2.52189 + vertex 1.22732 0.945466 2.52105 + endloop + endfacet + facet normal 0.179176 -0.267291 0.946811 + outer loop + vertex 1.23006 0.946935 2.52095 + vertex 1.22732 0.945466 2.52105 + vertex 1.22868 0.943299 2.52018 + endloop + endfacet + facet normal 0.181261 -0.265972 0.946786 + outer loop + vertex 1.22868 0.943299 2.52018 + vertex 1.22732 0.945466 2.52105 + vertex 1.22496 0.942778 2.52075 + endloop + endfacet + facet normal 0.180817 -0.261297 0.948171 + outer loop + vertex 1.22496 0.942778 2.52075 + vertex 1.22333 0.938619 2.51991 + vertex 1.22868 0.943299 2.52018 + endloop + endfacet + facet normal 0.181785 -0.262376 0.947688 + outer loop + vertex 1.22868 0.943299 2.52018 + vertex 1.22333 0.938619 2.51991 + vertex 1.2284 0.938639 2.51895 + endloop + endfacet + facet normal 0.180032 -0.262363 0.948026 + outer loop + vertex 1.2284 0.938639 2.51895 + vertex 1.23331 0.943328 2.51931 + vertex 1.22868 0.943299 2.52018 + endloop + endfacet + facet normal 0.179777 -0.268088 0.946472 + outer loop + vertex 1.23313 0.947135 2.52042 + vertex 1.22868 0.943299 2.52018 + vertex 1.23331 0.943328 2.51931 + endloop + endfacet + facet normal 0.177191 -0.268334 0.94689 + outer loop + vertex 1.23331 0.943328 2.51931 + vertex 1.23806 0.948384 2.51986 + vertex 1.23313 0.947135 2.52042 + endloop + endfacet + facet normal 0.181281 -0.287369 0.940508 + outer loop + vertex 1.23313 0.947135 2.52042 + vertex 1.23806 0.948384 2.51986 + vertex 1.23606 0.951097 2.52107 + endloop + endfacet + facet normal 0.180042 -0.288265 0.940472 + outer loop + vertex 1.23969 0.952462 2.52079 + vertex 1.23606 0.951097 2.52107 + vertex 1.23806 0.948384 2.51986 + endloop + endfacet + facet normal 0.181517 -0.288754 0.940039 + outer loop + vertex 1.23969 0.952462 2.52079 + vertex 1.23806 0.948384 2.51986 + vertex 1.24286 0.952474 2.52018 + endloop + endfacet + facet normal 0.18083 -0.301347 0.936211 + outer loop + vertex 1.24286 0.952474 2.52018 + vertex 1.2423 0.955189 2.52117 + vertex 1.23969 0.952462 2.52079 + endloop + endfacet + facet normal 0.181436 -0.301888 0.935919 + outer loop + vertex 1.2423 0.955189 2.52117 + vertex 1.23908 0.955153 2.52178 + vertex 1.23969 0.952462 2.52079 + endloop + endfacet + facet normal 0.182582 -0.276667 0.943461 + outer loop + vertex 1.2423 0.955189 2.52117 + vertex 1.24376 0.959252 2.52208 + vertex 1.23908 0.955153 2.52178 + endloop + endfacet + facet normal 0.174107 -0.267302 0.947753 + outer loop + vertex 1.24376 0.959252 2.52208 + vertex 1.23857 0.95907 2.52298 + vertex 1.23908 0.955153 2.52178 + endloop + endfacet + facet normal 0.174533 -0.166936 0.970397 + outer loop + vertex 1.24376 0.959252 2.52208 + vertex 1.24282 0.963665 2.523 + vertex 1.23857 0.95907 2.52298 + endloop + endfacet + facet normal 0.190496 -0.181645 0.964736 + outer loop + vertex 1.23857 0.95907 2.52298 + vertex 1.24282 0.963665 2.523 + vertex 1.23805 0.963425 2.5239 + endloop + endfacet + facet normal 0.181017 0.0674884 0.981162 + outer loop + vertex 1.24282 0.963665 2.523 + vertex 1.24146 0.967402 2.523 + vertex 1.23805 0.963425 2.5239 + endloop + endfacet + facet normal 0.176667 0.0659179 0.982061 + outer loop + vertex 1.24282 0.963665 2.523 + vertex 1.24615 0.967594 2.52214 + vertex 1.24146 0.967402 2.523 + endloop + endfacet + facet normal 0.145032 0.0933938 0.985009 + outer loop + vertex 1.24789 0.964042 2.52222 + vertex 1.24615 0.967594 2.52214 + vertex 1.24282 0.963665 2.523 + endloop + endfacet + facet normal 0.144234 0.0930052 0.985163 + outer loop + vertex 1.24789 0.964042 2.52222 + vertex 1.25117 0.967753 2.52139 + vertex 1.24615 0.967594 2.52214 + endloop + endfacet + facet normal 0.122203 0.112675 0.986089 + outer loop + vertex 1.25309 0.96416 2.52156 + vertex 1.25117 0.967753 2.52139 + vertex 1.24789 0.964042 2.52222 + endloop + endfacet + facet normal 0.127464 -0.152789 0.980004 + outer loop + vertex 1.25309 0.96416 2.52156 + vertex 1.24789 0.964042 2.52222 + vertex 1.24898 0.960578 2.52154 + endloop + endfacet + facet normal 0.151797 -0.180682 0.971757 + outer loop + vertex 1.25234 0.960798 2.52106 + vertex 1.25309 0.96416 2.52156 + vertex 1.24898 0.960578 2.52154 + endloop + endfacet + facet normal 0.154662 -0.274818 0.948975 + outer loop + vertex 1.25234 0.960798 2.52106 + vertex 1.24898 0.960578 2.52154 + vertex 1.2499 0.958081 2.52067 + endloop + endfacet + facet normal 0.16795 -0.285959 0.943409 + outer loop + vertex 1.25376 0.958513 2.52011 + vertex 1.25234 0.960798 2.52106 + vertex 1.2499 0.958081 2.52067 + endloop + endfacet + facet normal 0.168919 -0.300795 0.93861 + outer loop + vertex 1.2499 0.958081 2.52067 + vertex 1.24815 0.953781 2.5196 + vertex 1.25376 0.958513 2.52011 + endloop + endfacet + facet normal 0.173038 -0.305439 0.936357 + outer loop + vertex 1.25376 0.958513 2.52011 + vertex 1.24815 0.953781 2.5196 + vertex 1.25343 0.953668 2.51859 + endloop + endfacet + facet normal 0.165683 -0.305353 0.937715 + outer loop + vertex 1.25343 0.953668 2.51859 + vertex 1.2585 0.958503 2.51927 + vertex 1.25376 0.958513 2.52011 + endloop + endfacet + facet normal 0.165953 -0.300659 0.939182 + outer loop + vertex 1.25826 0.962374 2.52055 + vertex 1.25376 0.958513 2.52011 + vertex 1.2585 0.958503 2.51927 + endloop + endfacet + facet normal 0.175678 -0.29959 0.937754 + outer loop + vertex 1.2585 0.958503 2.51927 + vertex 1.26307 0.963922 2.52015 + vertex 1.25826 0.962374 2.52055 + endloop + endfacet + facet normal 0.161779 -0.288826 0.943614 + outer loop + vertex 1.26352 0.95885 2.51852 + vertex 1.26307 0.963922 2.52015 + vertex 1.2585 0.958503 2.51927 + endloop + endfacet + facet normal 0.162179 -0.308001 0.937461 + outer loop + vertex 1.25855 0.953921 2.51776 + vertex 1.26352 0.95885 2.51852 + vertex 1.2585 0.958503 2.51927 + endloop + endfacet + facet normal 0.166405 -0.311941 0.935416 + outer loop + vertex 1.26369 0.954067 2.51689 + vertex 1.26352 0.95885 2.51852 + vertex 1.25855 0.953921 2.51776 + endloop + endfacet + facet normal 0.16688 -0.292982 0.941442 + outer loop + vertex 1.26369 0.954067 2.51689 + vertex 1.25855 0.953921 2.51776 + vertex 1.25884 0.950093 2.51651 + endloop + endfacet + facet normal 0.168087 -0.294391 0.940787 + outer loop + vertex 1.26207 0.950133 2.51595 + vertex 1.26369 0.954067 2.51689 + vertex 1.25884 0.950093 2.51651 + endloop + endfacet + facet normal 0.168879 -0.274113 0.946753 + outer loop + vertex 1.26207 0.950133 2.51595 + vertex 1.25884 0.950093 2.51651 + vertex 1.2595 0.947539 2.51566 + endloop + endfacet + facet normal 0.167075 -0.272421 0.947561 + outer loop + vertex 1.26273 0.947535 2.51508 + vertex 1.26207 0.950133 2.51595 + vertex 1.2595 0.947539 2.51566 + endloop + endfacet + facet normal 0.167378 -0.266324 0.94924 + outer loop + vertex 1.2595 0.947539 2.51566 + vertex 1.25803 0.943542 2.51479 + vertex 1.26273 0.947535 2.51508 + endloop + endfacet + facet normal 0.171409 -0.270927 0.947216 + outer loop + vertex 1.26273 0.947535 2.51508 + vertex 1.25803 0.943542 2.51479 + vertex 1.26322 0.943587 2.51387 + endloop + endfacet + facet normal 0.169678 -0.271214 0.947445 + outer loop + vertex 1.26322 0.943587 2.51387 + vertex 1.26798 0.948812 2.51451 + vertex 1.26273 0.947535 2.51508 + endloop + endfacet + facet normal 0.170857 -0.276888 0.94559 + outer loop + vertex 1.26273 0.947535 2.51508 + vertex 1.26798 0.948812 2.51451 + vertex 1.26573 0.951449 2.51569 + endloop + endfacet + facet normal 0.171791 -0.276118 0.945646 + outer loop + vertex 1.26947 0.952915 2.51544 + vertex 1.26573 0.951449 2.51569 + vertex 1.26798 0.948812 2.51451 + endloop + endfacet + facet normal 0.173975 -0.276777 0.945054 + outer loop + vertex 1.26947 0.952915 2.51544 + vertex 1.26798 0.948812 2.51451 + vertex 1.27325 0.953438 2.51489 + endloop + endfacet + facet normal 0.175629 -0.294701 0.939311 + outer loop + vertex 1.27325 0.953438 2.51489 + vertex 1.27188 0.955603 2.51583 + vertex 1.26947 0.952915 2.51544 + endloop + endfacet + facet normal 0.176244 -0.294315 0.939317 + outer loop + vertex 1.27469 0.957118 2.51578 + vertex 1.27188 0.955603 2.51583 + vertex 1.27325 0.953438 2.51489 + endloop + endfacet + facet normal 0.179969 -0.295512 0.938234 + outer loop + vertex 1.27469 0.957118 2.51578 + vertex 1.27325 0.953438 2.51489 + vertex 1.27782 0.957348 2.51525 + endloop + endfacet + facet normal 0.180367 -0.31772 0.930871 + outer loop + vertex 1.27782 0.957348 2.51525 + vertex 1.27718 0.959855 2.51623 + vertex 1.27469 0.957118 2.51578 + endloop + endfacet + facet normal 0.191362 -0.326816 0.925512 + outer loop + vertex 1.27718 0.959855 2.51623 + vertex 1.2734 0.95926 2.5168 + vertex 1.27469 0.957118 2.51578 + endloop + endfacet + facet normal 0.189959 -0.313072 0.930538 + outer loop + vertex 1.27718 0.959855 2.51623 + vertex 1.27879 0.963918 2.51727 + vertex 1.2734 0.95926 2.5168 + endloop + endfacet + facet normal 0.181648 -0.303919 0.93522 + outer loop + vertex 1.27879 0.963918 2.51727 + vertex 1.27349 0.963877 2.51828 + vertex 1.2734 0.95926 2.5168 + endloop + endfacet + facet normal 0.183437 -0.303851 0.934893 + outer loop + vertex 1.2734 0.95926 2.5168 + vertex 1.27349 0.963877 2.51828 + vertex 1.26859 0.95916 2.51771 + endloop + endfacet + facet normal 0.182744 -0.320705 0.929383 + outer loop + vertex 1.2734 0.95926 2.5168 + vertex 1.26859 0.95916 2.51771 + vertex 1.26876 0.955357 2.51637 + endloop + endfacet + facet normal 0.184963 -0.323194 0.928081 + outer loop + vertex 1.27188 0.955603 2.51583 + vertex 1.2734 0.95926 2.5168 + vertex 1.26876 0.955357 2.51637 + endloop + endfacet + facet normal 0.177734 -0.321214 0.930179 + outer loop + vertex 1.26876 0.955357 2.51637 + vertex 1.26859 0.95916 2.51771 + vertex 1.26369 0.954067 2.51689 + endloop + endfacet + facet normal 0.168867 -0.289591 0.942136 + outer loop + vertex 1.26859 0.95916 2.51771 + vertex 1.27349 0.963877 2.51828 + vertex 1.26832 0.963994 2.51925 + endloop + endfacet + facet normal 0.16695 -0.289786 0.942418 + outer loop + vertex 1.26859 0.95916 2.51771 + vertex 1.26832 0.963994 2.51925 + vertex 1.26352 0.95885 2.51852 + endloop + endfacet + facet normal 0.186377 -0.186693 0.964577 + outer loop + vertex 1.27879 0.963918 2.51727 + vertex 1.27786 0.968344 2.5183 + vertex 1.27349 0.963877 2.51828 + endloop + endfacet + facet normal 0.159645 -0.193116 0.968101 + outer loop + vertex 1.27879 0.963918 2.51727 + vertex 1.28314 0.968716 2.51751 + vertex 1.27786 0.968344 2.5183 + endloop + endfacet + facet normal 0.135897 0.162973 0.977227 + outer loop + vertex 1.28314 0.968716 2.51751 + vertex 1.28098 0.972096 2.51724 + vertex 1.27786 0.968344 2.5183 + endloop + endfacet + facet normal 0.135663 0.163168 0.977227 + outer loop + vertex 1.27786 0.968344 2.5183 + vertex 1.28098 0.972096 2.51724 + vertex 1.27574 0.971932 2.518 + endloop + endfacet + facet normal 0.187422 0.192574 0.963218 + outer loop + vertex 1.27786 0.968344 2.5183 + vertex 1.27574 0.971932 2.518 + vertex 1.27268 0.968449 2.51929 + endloop + endfacet + facet normal 0.180521 -0.180972 0.966779 + outer loop + vertex 1.27349 0.963877 2.51828 + vertex 1.27786 0.968344 2.5183 + vertex 1.27268 0.968449 2.51929 + endloop + endfacet + facet normal 0.175999 -0.181922 0.967434 + outer loop + vertex 1.27349 0.963877 2.51828 + vertex 1.27268 0.968449 2.51929 + vertex 1.26832 0.963994 2.51925 + endloop + endfacet + facet normal 0.153255 -0.15977 0.975185 + outer loop + vertex 1.26832 0.963994 2.51925 + vertex 1.27268 0.968449 2.51929 + vertex 1.26719 0.969726 2.52036 + endloop + endfacet + facet normal 0.168667 -0.156341 0.973195 + outer loop + vertex 1.26719 0.969726 2.52036 + vertex 1.26307 0.963922 2.52015 + vertex 1.26832 0.963994 2.51925 + endloop + endfacet + facet normal 0.2333 -0.201442 0.951311 + outer loop + vertex 1.26333 0.967793 2.5209 + vertex 1.26307 0.963922 2.52015 + vertex 1.26719 0.969726 2.52036 + endloop + endfacet + facet normal 0.158514 -0.199363 0.96702 + outer loop + vertex 1.26333 0.967793 2.5209 + vertex 1.26034 0.965997 2.52102 + vertex 1.26307 0.963922 2.52015 + endloop + endfacet + facet normal 0.149463 -0.210847 0.966025 + outer loop + vertex 1.25826 0.962374 2.52055 + vertex 1.26307 0.963922 2.52015 + vertex 1.26034 0.965997 2.52102 + endloop + endfacet + facet normal 0.143685 -0.207738 0.967574 + outer loop + vertex 1.2571 0.96466 2.52121 + vertex 1.25826 0.962374 2.52055 + vertex 1.26034 0.965997 2.52102 + endloop + endfacet + facet normal 0.0351751 0.0591515 0.997629 + outer loop + vertex 1.26034 0.965997 2.52102 + vertex 1.25675 0.967758 2.52104 + vertex 1.2571 0.96466 2.52121 + endloop + endfacet + facet normal 0.0788027 0.0639883 0.994834 + outer loop + vertex 1.2571 0.96466 2.52121 + vertex 1.25675 0.967758 2.52104 + vertex 1.25309 0.96416 2.52156 + endloop + endfacet + facet normal 0.106597 -0.169614 0.979729 + outer loop + vertex 1.2571 0.96466 2.52121 + vertex 1.25309 0.96416 2.52156 + vertex 1.25517 0.962219 2.521 + endloop + endfacet + facet normal 0.0216375 0.0315306 0.999269 + outer loop + vertex 1.26085 0.968657 2.52093 + vertex 1.25675 0.967758 2.52104 + vertex 1.26034 0.965997 2.52102 + endloop + endfacet + facet normal 0.151237 -0.203812 0.967258 + outer loop + vertex 1.25826 0.962374 2.52055 + vertex 1.2571 0.96466 2.52121 + vertex 1.25517 0.962219 2.521 + endloop + endfacet + facet normal 0.0213093 0.0315933 0.999274 + outer loop + vertex 1.26333 0.967793 2.5209 + vertex 1.26085 0.968657 2.52093 + vertex 1.26034 0.965997 2.52102 + endloop + endfacet + facet normal 0.209483 0.0824652 0.974329 + outer loop + vertex 1.27126 0.972024 2.51929 + vertex 1.26719 0.969726 2.52036 + vertex 1.27268 0.968449 2.51929 + endloop + endfacet + facet normal 0.277982 0.109634 0.954309 + outer loop + vertex 1.27268 0.968449 2.51929 + vertex 1.27574 0.971932 2.518 + vertex 1.27126 0.972024 2.51929 + endloop + endfacet + facet normal 0.0967864 0.1387 0.985594 + outer loop + vertex 1.28314 0.968716 2.51751 + vertex 1.28624 0.972361 2.51669 + vertex 1.28098 0.972096 2.51724 + endloop + endfacet + facet normal 0.120786 0.118249 0.98561 + outer loop + vertex 1.28852 0.96896 2.51682 + vertex 1.28624 0.972361 2.51669 + vertex 1.28314 0.968716 2.51751 + endloop + endfacet + facet normal 0.132981 -0.184303 0.973832 + outer loop + vertex 1.28852 0.96896 2.51682 + vertex 1.28314 0.968716 2.51751 + vertex 1.28413 0.96534 2.51673 + endloop + endfacet + facet normal 0.161445 -0.218553 0.962377 + outer loop + vertex 1.28748 0.965407 2.51619 + vertex 1.28852 0.96896 2.51682 + vertex 1.28413 0.96534 2.51673 + endloop + endfacet + facet normal 0.159159 -0.310438 0.937175 + outer loop + vertex 1.28748 0.965407 2.51619 + vertex 1.28413 0.96534 2.51673 + vertex 1.28475 0.962779 2.51578 + endloop + endfacet + facet normal 0.159873 -0.311127 0.936825 + outer loop + vertex 1.28804 0.962687 2.51519 + vertex 1.28748 0.965407 2.51619 + vertex 1.28475 0.962779 2.51578 + endloop + endfacet + facet normal 0.160262 -0.306536 0.938271 + outer loop + vertex 1.28475 0.962779 2.51578 + vertex 1.28296 0.958589 2.51472 + vertex 1.28804 0.962687 2.51519 + endloop + endfacet + facet normal 0.158028 -0.303909 0.939503 + outer loop + vertex 1.28804 0.962687 2.51519 + vertex 1.28296 0.958589 2.51472 + vertex 1.28827 0.958532 2.51381 + endloop + endfacet + facet normal 0.151598 -0.304551 0.940354 + outer loop + vertex 1.28827 0.958532 2.51381 + vertex 1.29339 0.96388 2.51471 + vertex 1.28804 0.962687 2.51519 + endloop + endfacet + facet normal 0.15295 -0.311639 0.93781 + outer loop + vertex 1.28804 0.962687 2.51519 + vertex 1.29339 0.96388 2.51471 + vertex 1.29123 0.966623 2.51598 + endloop + endfacet + facet normal 0.154564 -0.31043 0.937946 + outer loop + vertex 1.29496 0.96805 2.51583 + vertex 1.29123 0.966623 2.51598 + vertex 1.29339 0.96388 2.51471 + endloop + endfacet + facet normal 0.227227 -0.331794 0.915577 + outer loop + vertex 1.29496 0.96805 2.51583 + vertex 1.29339 0.96388 2.51471 + vertex 1.29831 0.968709 2.51524 + endloop + endfacet + facet normal 0.214362 -0.237965 0.947323 + outer loop + vertex 1.29831 0.968709 2.51524 + vertex 1.2966 0.970526 2.51608 + vertex 1.29496 0.96805 2.51583 + endloop + endfacet + facet normal 0.133301 -0.186894 0.973294 + outer loop + vertex 1.2966 0.970526 2.51608 + vertex 1.2935 0.97013 2.51643 + vertex 1.29496 0.96805 2.51583 + endloop + endfacet + facet normal 0.0982011 0.103089 0.989813 + outer loop + vertex 1.2966 0.970526 2.51608 + vertex 1.29541 0.972837 2.51596 + vertex 1.2935 0.97013 2.51643 + endloop + endfacet + facet normal 0.069158 0.123615 0.989917 + outer loop + vertex 1.29541 0.972837 2.51596 + vertex 1.29125 0.972706 2.51627 + vertex 1.2935 0.97013 2.51643 + endloop + endfacet + facet normal 0.0515109 0.108385 0.992774 + outer loop + vertex 1.2935 0.97013 2.51643 + vertex 1.29125 0.972706 2.51627 + vertex 1.28852 0.96896 2.51682 + endloop + endfacet + facet normal 0.123866 -0.206585 0.970556 + outer loop + vertex 1.2935 0.97013 2.51643 + vertex 1.28852 0.96896 2.51682 + vertex 1.29123 0.966623 2.51598 + endloop + endfacet + facet normal 0.124379 0.116347 0.98539 + outer loop + vertex 1.29818 0.972234 2.51568 + vertex 1.29541 0.972837 2.51596 + vertex 1.2966 0.970526 2.51608 + endloop + endfacet + facet normal 0.349521 -0.103561 0.931187 + outer loop + vertex 1.29818 0.972234 2.51568 + vertex 1.2966 0.970526 2.51608 + vertex 1.29831 0.968709 2.51524 + endloop + endfacet + facet normal 0.287327 -0.108505 0.951667 + outer loop + vertex 1.29818 0.972234 2.51568 + vertex 1.29831 0.968709 2.51524 + vertex 1.30106 0.973434 2.51495 + endloop + endfacet + facet normal 0.15031 -0.0264019 0.988286 + outer loop + vertex 1.30106 0.973434 2.51495 + vertex 1.29831 0.968709 2.51524 + vertex 1.30311 0.968832 2.51451 + endloop + endfacet + facet normal -0.00823844 -0.0974449 0.995207 + outer loop + vertex 1.30311 0.968832 2.51451 + vertex 1.30724 0.974339 2.51509 + vertex 1.30106 0.973434 2.51495 + endloop + endfacet + facet normal 0.125207 -0.195242 0.97273 + outer loop + vertex 1.3084 0.968921 2.51385 + vertex 1.30724 0.974339 2.51509 + vertex 1.30311 0.968832 2.51451 + endloop + endfacet + facet normal 0.124088 -0.276847 0.952868 + outer loop + vertex 1.30365 0.963977 2.51303 + vertex 1.3084 0.968921 2.51385 + vertex 1.30311 0.968832 2.51451 + endloop + endfacet + facet normal 0.153156 -0.272655 0.949843 + outer loop + vertex 1.30365 0.963977 2.51303 + vertex 1.30311 0.968832 2.51451 + vertex 1.29857 0.963772 2.51379 + endloop + endfacet + facet normal 0.152965 -0.307693 0.93911 + outer loop + vertex 1.29884 0.958861 2.51214 + vertex 1.30365 0.963977 2.51303 + vertex 1.29857 0.963772 2.51379 + endloop + endfacet + facet normal 0.159876 -0.307008 0.938182 + outer loop + vertex 1.29884 0.958861 2.51214 + vertex 1.29857 0.963772 2.51379 + vertex 1.29362 0.958861 2.51303 + endloop + endfacet + facet normal 0.159917 -0.307047 0.938162 + outer loop + vertex 1.29362 0.958861 2.51303 + vertex 1.29857 0.963772 2.51379 + vertex 1.29339 0.96388 2.51471 + endloop + endfacet + facet normal 0.171315 -0.323487 0.930595 + outer loop + vertex 1.3039 0.960013 2.51161 + vertex 1.30365 0.963977 2.51303 + vertex 1.29884 0.958861 2.51214 + endloop + endfacet + facet normal 0.167102 -0.301179 0.938812 + outer loop + vertex 1.3039 0.960013 2.51161 + vertex 1.29884 0.958861 2.51214 + vertex 1.30085 0.956143 2.51091 + endloop + endfacet + facet normal 0.179927 -0.310328 0.933447 + outer loop + vertex 1.30441 0.957405 2.51064 + vertex 1.3039 0.960013 2.51161 + vertex 1.30085 0.956143 2.51091 + endloop + endfacet + facet normal 0.1696 -0.278638 0.945302 + outer loop + vertex 1.30441 0.957405 2.51064 + vertex 1.30085 0.956143 2.51091 + vertex 1.30288 0.953448 2.50975 + endloop + endfacet + facet normal 0.165157 -0.277186 0.946515 + outer loop + vertex 1.30441 0.957405 2.51064 + vertex 1.30288 0.953448 2.50975 + vertex 1.30764 0.957426 2.51009 + endloop + endfacet + facet normal 0.162179 -0.273745 0.948031 + outer loop + vertex 1.30764 0.957426 2.51009 + vertex 1.30288 0.953448 2.50975 + vertex 1.30812 0.953505 2.50887 + endloop + endfacet + facet normal 0.156528 -0.274643 0.94872 + outer loop + vertex 1.30812 0.953505 2.50887 + vertex 1.313 0.958732 2.50958 + vertex 1.30764 0.957426 2.51009 + endloop + endfacet + facet normal 0.161635 -0.298753 0.940543 + outer loop + vertex 1.30764 0.957426 2.51009 + vertex 1.313 0.958732 2.50958 + vertex 1.3108 0.961398 2.51081 + endloop + endfacet + facet normal 0.163013 -0.299748 0.939988 + outer loop + vertex 1.30705 0.960028 2.51102 + vertex 1.30764 0.957426 2.51009 + vertex 1.3108 0.961398 2.51081 + endloop + endfacet + facet normal 0.175792 -0.33707 0.924922 + outer loop + vertex 1.3108 0.961398 2.51081 + vertex 1.3088 0.964047 2.51215 + vertex 1.30705 0.960028 2.51102 + endloop + endfacet + facet normal 0.175116 -0.336835 0.925136 + outer loop + vertex 1.30705 0.960028 2.51102 + vertex 1.3088 0.964047 2.51215 + vertex 1.3039 0.960013 2.51161 + endloop + endfacet + facet normal 0.176617 -0.311116 0.933816 + outer loop + vertex 1.30705 0.960028 2.51102 + vertex 1.3039 0.960013 2.51161 + vertex 1.30441 0.957405 2.51064 + endloop + endfacet + facet normal 0.175795 -0.337068 0.924922 + outer loop + vertex 1.314 0.965346 2.51164 + vertex 1.3088 0.964047 2.51215 + vertex 1.3108 0.961398 2.51081 + endloop + endfacet + facet normal 0.179734 -0.339884 0.923133 + outer loop + vertex 1.31465 0.962885 2.5106 + vertex 1.314 0.965346 2.51164 + vertex 1.3108 0.961398 2.51081 + endloop + endfacet + facet normal 0.17711 -0.340672 0.92335 + outer loop + vertex 1.31721 0.965566 2.5111 + vertex 1.314 0.965346 2.51164 + vertex 1.31465 0.962885 2.5106 + endloop + endfacet + facet normal 0.155318 -0.321887 0.933951 + outer loop + vertex 1.31846 0.963303 2.51011 + vertex 1.31721 0.965566 2.5111 + vertex 1.31465 0.962885 2.5106 + endloop + endfacet + facet normal 0.153426 -0.293314 0.943624 + outer loop + vertex 1.31465 0.962885 2.5106 + vertex 1.313 0.958732 2.50958 + vertex 1.31846 0.963303 2.51011 + endloop + endfacet + facet normal 0.151123 -0.290698 0.944805 + outer loop + vertex 1.31846 0.963303 2.51011 + vertex 1.313 0.958732 2.50958 + vertex 1.31832 0.958629 2.5087 + endloop + endfacet + facet normal 0.151497 -0.290691 0.944747 + outer loop + vertex 1.31832 0.958629 2.5087 + vertex 1.32309 0.963129 2.50932 + vertex 1.31846 0.963303 2.51011 + endloop + endfacet + facet normal 0.14883 -0.32003 0.935644 + outer loop + vertex 1.32305 0.966938 2.51063 + vertex 1.31846 0.963303 2.51011 + vertex 1.32309 0.963129 2.50932 + endloop + endfacet + facet normal 0.154419 -0.319705 0.934849 + outer loop + vertex 1.32309 0.963129 2.50932 + vertex 1.3274 0.967507 2.5101 + vertex 1.32305 0.966938 2.51063 + endloop + endfacet + facet normal 0.154666 -0.32252 0.933841 + outer loop + vertex 1.32305 0.966938 2.51063 + vertex 1.3274 0.967507 2.5101 + vertex 1.3263 0.97076 2.51141 + endloop + endfacet + facet normal 0.158608 -0.325522 0.932137 + outer loop + vertex 1.32253 0.969535 2.51162 + vertex 1.32305 0.966938 2.51063 + vertex 1.3263 0.97076 2.51141 + endloop + endfacet + facet normal 0.122672 -0.208161 0.970371 + outer loop + vertex 1.3263 0.97076 2.51141 + vertex 1.32354 0.973369 2.51232 + vertex 1.32253 0.969535 2.51162 + endloop + endfacet + facet normal 0.143041 -0.21286 0.966556 + outer loop + vertex 1.32253 0.969535 2.51162 + vertex 1.32354 0.973369 2.51232 + vertex 1.31862 0.969105 2.51211 + endloop + endfacet + facet normal 0.151337 -0.325225 0.933448 + outer loop + vertex 1.32253 0.969535 2.51162 + vertex 1.31862 0.969105 2.51211 + vertex 1.32007 0.966963 2.51112 + endloop + endfacet + facet normal 0.151226 -0.325297 0.933441 + outer loop + vertex 1.32007 0.966963 2.51112 + vertex 1.31862 0.969105 2.51211 + vertex 1.31721 0.965566 2.5111 + endloop + endfacet + facet normal 0.117083 -0.213877 0.969819 + outer loop + vertex 1.32924 0.974829 2.51195 + vertex 1.32354 0.973369 2.51232 + vertex 1.3263 0.97076 2.51141 + endloop + endfacet + facet normal 0.131432 -0.22371 0.965753 + outer loop + vertex 1.33086 0.971782 2.51102 + vertex 1.32924 0.974829 2.51195 + vertex 1.3263 0.97076 2.51141 + endloop + endfacet + facet normal 0.0959396 -0.242453 0.965408 + outer loop + vertex 1.33399 0.975559 2.51166 + vertex 1.32924 0.974829 2.51195 + vertex 1.33086 0.971782 2.51102 + endloop + endfacet + facet normal 0.136928 -0.274162 0.951885 + outer loop + vertex 1.33463 0.972902 2.51081 + vertex 1.33399 0.975559 2.51166 + vertex 1.33086 0.971782 2.51102 + endloop + endfacet + facet normal 0.154035 -0.336244 0.929093 + outer loop + vertex 1.33463 0.972902 2.51081 + vertex 1.33086 0.971782 2.51102 + vertex 1.33286 0.968718 2.50958 + endloop + endfacet + facet normal 0.155311 -0.336676 0.928724 + outer loop + vertex 1.33463 0.972902 2.51081 + vertex 1.33286 0.968718 2.50958 + vertex 1.33784 0.972721 2.5102 + endloop + endfacet + facet normal 0.156107 -0.330029 0.930973 + outer loop + vertex 1.33784 0.972721 2.5102 + vertex 1.33727 0.975415 2.51125 + vertex 1.33463 0.972902 2.51081 + endloop + endfacet + facet normal 0.139555 -0.333998 0.932186 + outer loop + vertex 1.33727 0.975415 2.51125 + vertex 1.33784 0.972721 2.5102 + vertex 1.34096 0.97653 2.5111 + endloop + endfacet + facet normal 0.09252 -0.171969 0.980748 + outer loop + vertex 1.34096 0.97653 2.5111 + vertex 1.33825 0.978758 2.51175 + vertex 1.33727 0.975415 2.51125 + endloop + endfacet + facet normal 0.114178 -0.177792 0.977422 + outer loop + vertex 1.33727 0.975415 2.51125 + vertex 1.33825 0.978758 2.51175 + vertex 1.33399 0.975559 2.51166 + endloop + endfacet + facet normal -0.0229338 0.00406082 0.999729 + outer loop + vertex 1.33825 0.978758 2.51175 + vertex 1.33234 0.97892 2.51161 + vertex 1.33399 0.975559 2.51166 + endloop + endfacet + facet normal -0.0168377 0.207824 0.978021 + outer loop + vertex 1.33234 0.97892 2.51161 + vertex 1.33825 0.978758 2.51175 + vertex 1.33634 0.98163 2.5111 + endloop + endfacet + facet normal -0.0433272 0.19081 0.98067 + outer loop + vertex 1.33825 0.978758 2.51175 + vertex 1.34128 0.982055 2.51124 + vertex 1.33634 0.98163 2.5111 + endloop + endfacet + facet normal -0.0150565 0.165654 0.986069 + outer loop + vertex 1.34351 0.979852 2.51164 + vertex 1.34128 0.982055 2.51124 + vertex 1.33825 0.978758 2.51175 + endloop + endfacet + facet normal 0.0070811 0.187394 0.982259 + outer loop + vertex 1.34663 0.982503 2.51112 + vertex 1.34128 0.982055 2.51124 + vertex 1.34351 0.979852 2.51164 + endloop + endfacet + facet normal 0.0563594 0.130872 0.989796 + outer loop + vertex 1.34703 0.979997 2.51142 + vertex 1.34663 0.982503 2.51112 + vertex 1.34351 0.979852 2.51164 + endloop + endfacet + facet normal 0.0695799 -0.212922 0.974589 + outer loop + vertex 1.34703 0.979997 2.51142 + vertex 1.34351 0.979852 2.51164 + vertex 1.34479 0.977759 2.5111 + endloop + endfacet + facet normal 0.139595 -0.279408 0.949971 + outer loop + vertex 1.34804 0.97765 2.51058 + vertex 1.34703 0.979997 2.51142 + vertex 1.34479 0.977759 2.5111 + endloop + endfacet + facet normal 0.133527 -0.3517 0.926541 + outer loop + vertex 1.34479 0.977759 2.5111 + vertex 1.34314 0.973774 2.50982 + vertex 1.34804 0.97765 2.51058 + endloop + endfacet + facet normal 0.133298 -0.351436 0.926674 + outer loop + vertex 1.34804 0.97765 2.51058 + vertex 1.34314 0.973774 2.50982 + vertex 1.34844 0.973683 2.50902 + endloop + endfacet + facet normal 0.198761 -0.341686 0.918556 + outer loop + vertex 1.34844 0.973683 2.50902 + vertex 1.35306 0.978786 2.50992 + vertex 1.34804 0.97765 2.51058 + endloop + endfacet + facet normal 0.184425 -0.261499 0.947421 + outer loop + vertex 1.34804 0.97765 2.51058 + vertex 1.35306 0.978786 2.50992 + vertex 1.35025 0.981041 2.51109 + endloop + endfacet + facet normal 0.296791 -0.121404 0.947194 + outer loop + vertex 1.35324 0.98253 2.51034 + vertex 1.35025 0.981041 2.51109 + vertex 1.35306 0.978786 2.50992 + endloop + endfacet + facet normal 0.325631 -0.12171 0.937631 + outer loop + vertex 1.35324 0.98253 2.51034 + vertex 1.35306 0.978786 2.50992 + vertex 1.35716 0.983251 2.50908 + endloop + endfacet + facet normal 0.167473 0.032322 0.985347 + outer loop + vertex 1.35716 0.983251 2.50908 + vertex 1.35306 0.978786 2.50992 + vertex 1.35846 0.978704 2.50901 + endloop + endfacet + facet normal 0.0389028 -0.00468906 0.999232 + outer loop + vertex 1.35846 0.978704 2.50901 + vertex 1.36266 0.98306 2.50886 + vertex 1.35716 0.983251 2.50908 + endloop + endfacet + facet normal 0.0944931 -0.0584563 0.993808 + outer loop + vertex 1.36369 0.978918 2.50852 + vertex 1.36266 0.98306 2.50886 + vertex 1.35846 0.978704 2.50901 + endloop + endfacet + facet normal 0.0998681 -0.275423 0.956122 + outer loop + vertex 1.35902 0.973843 2.50755 + vertex 1.36369 0.978918 2.50852 + vertex 1.35846 0.978704 2.50901 + endloop + endfacet + facet normal 0.137449 -0.27014 0.95296 + outer loop + vertex 1.35902 0.973843 2.50755 + vertex 1.35846 0.978704 2.50901 + vertex 1.35373 0.973962 2.50834 + endloop + endfacet + facet normal 0.132644 -0.339139 0.931338 + outer loop + vertex 1.35902 0.973843 2.50755 + vertex 1.35373 0.973962 2.50834 + vertex 1.35408 0.969935 2.50683 + endloop + endfacet + facet normal 0.14174 -0.349679 0.926085 + outer loop + vertex 1.35728 0.969745 2.50627 + vertex 1.35902 0.973843 2.50755 + vertex 1.35408 0.969935 2.50683 + endloop + endfacet + facet normal 0.143473 -0.335319 0.931116 + outer loop + vertex 1.35728 0.969745 2.50627 + vertex 1.35408 0.969935 2.50683 + vertex 1.3546 0.967223 2.50577 + endloop + endfacet + facet normal 0.134448 -0.326591 0.935554 + outer loop + vertex 1.35765 0.966976 2.50525 + vertex 1.35728 0.969745 2.50627 + vertex 1.3546 0.967223 2.50577 + endloop + endfacet + facet normal 0.138369 -0.297488 0.944646 + outer loop + vertex 1.3546 0.967223 2.50577 + vertex 1.35292 0.963301 2.50478 + vertex 1.35765 0.966976 2.50525 + endloop + endfacet + facet normal 0.137677 -0.296643 0.945012 + outer loop + vertex 1.35765 0.966976 2.50525 + vertex 1.35292 0.963301 2.50478 + vertex 1.35786 0.963208 2.50403 + endloop + endfacet + facet normal 0.131394 -0.297226 0.945723 + outer loop + vertex 1.35786 0.963208 2.50403 + vertex 1.36209 0.967466 2.50478 + vertex 1.35765 0.966976 2.50525 + endloop + endfacet + facet normal 0.133982 -0.332079 0.933688 + outer loop + vertex 1.35765 0.966976 2.50525 + vertex 1.36209 0.967466 2.50478 + vertex 1.36101 0.970762 2.50611 + endloop + endfacet + facet normal 0.133351 -0.332291 0.933702 + outer loop + vertex 1.36101 0.970762 2.50611 + vertex 1.36209 0.967466 2.50478 + vertex 1.36556 0.971624 2.50577 + endloop + endfacet + facet normal 0.137487 -0.358159 0.923482 + outer loop + vertex 1.36556 0.971624 2.50577 + vertex 1.36453 0.974968 2.50722 + vertex 1.36101 0.970762 2.50611 + endloop + endfacet + facet normal 0.127027 -0.350576 0.92788 + outer loop + vertex 1.36453 0.974968 2.50722 + vertex 1.35902 0.973843 2.50755 + vertex 1.36101 0.970762 2.50611 + endloop + endfacet + facet normal 0.133659 -0.359378 0.923571 + outer loop + vertex 1.36901 0.975449 2.50676 + vertex 1.36453 0.974968 2.50722 + vertex 1.36556 0.971624 2.50577 + endloop + endfacet + facet normal 0.144931 -0.368219 0.918374 + outer loop + vertex 1.36933 0.972626 2.50557 + vertex 1.36901 0.975449 2.50676 + vertex 1.36556 0.971624 2.50577 + endloop + endfacet + facet normal 0.138713 -0.369168 0.918952 + outer loop + vertex 1.37213 0.975165 2.50617 + vertex 1.36901 0.975449 2.50676 + vertex 1.36933 0.972626 2.50557 + endloop + endfacet + facet normal 0.132065 -0.331343 0.934222 + outer loop + vertex 1.36209 0.967466 2.50478 + vertex 1.36764 0.968589 2.5044 + vertex 1.36556 0.971624 2.50577 + endloop + endfacet + facet normal 0.135405 -0.329177 0.93451 + outer loop + vertex 1.36933 0.972626 2.50557 + vertex 1.36556 0.971624 2.50577 + vertex 1.36764 0.968589 2.5044 + endloop + endfacet + facet normal 0.127908 -0.326607 0.936465 + outer loop + vertex 1.36933 0.972626 2.50557 + vertex 1.36764 0.968589 2.5044 + vertex 1.37264 0.972414 2.50505 + endloop + endfacet + facet normal 0.124475 -0.355239 0.926451 + outer loop + vertex 1.37264 0.972414 2.50505 + vertex 1.37213 0.975165 2.50617 + vertex 1.36933 0.972626 2.50557 + endloop + endfacet + facet normal 0.123395 -0.355462 0.92651 + outer loop + vertex 1.37213 0.975165 2.50617 + vertex 1.37264 0.972414 2.50505 + vertex 1.37594 0.976258 2.50608 + endloop + endfacet + facet normal 0.119602 -0.341789 0.932135 + outer loop + vertex 1.37594 0.976258 2.50608 + vertex 1.37379 0.979094 2.5074 + vertex 1.37213 0.975165 2.50617 + endloop + endfacet + facet normal 0.141878 -0.349345 0.92619 + outer loop + vertex 1.37213 0.975165 2.50617 + vertex 1.37379 0.979094 2.5074 + vertex 1.36901 0.975449 2.50676 + endloop + endfacet + facet normal 0.117034 -0.319277 0.940407 + outer loop + vertex 1.37379 0.979094 2.5074 + vertex 1.36872 0.97926 2.50809 + vertex 1.36901 0.975449 2.50676 + endloop + endfacet + facet normal 0.130795 -0.317768 0.939104 + outer loop + vertex 1.36901 0.975449 2.50676 + vertex 1.36872 0.97926 2.50809 + vertex 1.36453 0.974968 2.50722 + endloop + endfacet + facet normal 0.102055 -0.292072 0.950936 + outer loop + vertex 1.36453 0.974968 2.50722 + vertex 1.36872 0.97926 2.50809 + vertex 1.36369 0.978918 2.50852 + endloop + endfacet + facet normal 0.0935177 -0.118891 0.988494 + outer loop + vertex 1.36872 0.97926 2.50809 + vertex 1.36769 0.983255 2.50867 + vertex 1.36369 0.978918 2.50852 + endloop + endfacet + facet normal 0.0763607 -0.123465 0.989407 + outer loop + vertex 1.36872 0.97926 2.50809 + vertex 1.3727 0.983406 2.5083 + vertex 1.36769 0.983255 2.50867 + endloop + endfacet + facet normal 0.0636522 0.244994 0.967433 + outer loop + vertex 1.3727 0.983406 2.5083 + vertex 1.37059 0.986855 2.50756 + vertex 1.36769 0.983255 2.50867 + endloop + endfacet + facet normal 0.0244445 0.222503 0.974626 + outer loop + vertex 1.3727 0.983406 2.5083 + vertex 1.37565 0.987053 2.50739 + vertex 1.37059 0.986855 2.50756 + endloop + endfacet + facet normal 0.0742606 0.183538 0.980204 + outer loop + vertex 1.37793 0.983587 2.50787 + vertex 1.37565 0.987053 2.50739 + vertex 1.3727 0.983406 2.5083 + endloop + endfacet + facet normal 0.0868453 -0.18191 0.979473 + outer loop + vertex 1.37379 0.979094 2.5074 + vertex 1.37793 0.983587 2.50787 + vertex 1.3727 0.983406 2.5083 + endloop + endfacet + facet normal 0.0985628 -0.192377 0.976359 + outer loop + vertex 1.37909 0.980019 2.50705 + vertex 1.37793 0.983587 2.50787 + vertex 1.37379 0.979094 2.5074 + endloop + endfacet + facet normal 0.0969551 -0.192912 0.976414 + outer loop + vertex 1.38348 0.98354 2.50731 + vertex 1.37793 0.983587 2.50787 + vertex 1.37909 0.980019 2.50705 + endloop + endfacet + facet normal 0.100684 0.128259 0.986617 + outer loop + vertex 1.38348 0.98354 2.50731 + vertex 1.38092 0.987236 2.50709 + vertex 1.37793 0.983587 2.50787 + endloop + endfacet + facet normal 0.03256 0.081535 0.996138 + outer loop + vertex 1.38348 0.98354 2.50731 + vertex 1.38644 0.98781 2.50686 + vertex 1.38092 0.987236 2.50709 + endloop + endfacet + facet normal 0.0281927 0.0845445 0.996021 + outer loop + vertex 1.38924 0.984717 2.50704 + vertex 1.38644 0.98781 2.50686 + vertex 1.38348 0.98354 2.50731 + endloop + endfacet + facet normal 0.0916182 -0.231565 0.968496 + outer loop + vertex 1.38924 0.984717 2.50704 + vertex 1.38348 0.98354 2.50731 + vertex 1.38627 0.980729 2.50637 + endloop + endfacet + facet normal 0.0953967 -0.234202 0.967496 + outer loop + vertex 1.39098 0.981542 2.5061 + vertex 1.38924 0.984717 2.50704 + vertex 1.38627 0.980729 2.50637 + endloop + endfacet + facet normal 0.111617 -0.339133 0.934093 + outer loop + vertex 1.38627 0.980729 2.50637 + vertex 1.3875 0.977418 2.50502 + vertex 1.39098 0.981542 2.5061 + endloop + endfacet + facet normal 0.113689 -0.340669 0.933284 + outer loop + vertex 1.3875 0.977418 2.50502 + vertex 1.39306 0.978451 2.50472 + vertex 1.39098 0.981542 2.5061 + endloop + endfacet + facet normal 0.106601 -0.345076 0.932501 + outer loop + vertex 1.39484 0.982479 2.50601 + vertex 1.39098 0.981542 2.5061 + vertex 1.39306 0.978451 2.50472 + endloop + endfacet + facet normal 0.118928 -0.34952 0.92935 + outer loop + vertex 1.39484 0.982479 2.50601 + vertex 1.39306 0.978451 2.50472 + vertex 1.39791 0.982099 2.50547 + endloop + endfacet + facet normal 0.123591 -0.323977 0.937957 + outer loop + vertex 1.39791 0.982099 2.50547 + vertex 1.39747 0.984895 2.5065 + vertex 1.39484 0.982479 2.50601 + endloop + endfacet + facet normal 0.0704981 -0.270703 0.960078 + outer loop + vertex 1.39747 0.984895 2.5065 + vertex 1.39413 0.98524 2.50684 + vertex 1.39484 0.982479 2.50601 + endloop + endfacet + facet normal 0.0849223 -0.155021 0.984254 + outer loop + vertex 1.39747 0.984895 2.5065 + vertex 1.39832 0.988439 2.50698 + vertex 1.39413 0.98524 2.50684 + endloop + endfacet + facet normal -0.0162799 -0.0230613 0.999601 + outer loop + vertex 1.39832 0.988439 2.50698 + vertex 1.39242 0.988861 2.5069 + vertex 1.39413 0.98524 2.50684 + endloop + endfacet + facet normal 0.0412713 0.00401844 0.99914 + outer loop + vertex 1.39413 0.98524 2.50684 + vertex 1.39242 0.988861 2.5069 + vertex 1.38924 0.984717 2.50704 + endloop + endfacet + facet normal 0.0818151 -0.154325 0.984627 + outer loop + vertex 1.40116 0.985819 2.50634 + vertex 1.39832 0.988439 2.50698 + vertex 1.39747 0.984895 2.5065 + endloop + endfacet + facet normal 0.0605027 -0.176877 0.982372 + outer loop + vertex 1.40385 0.989473 2.50683 + vertex 1.39832 0.988439 2.50698 + vertex 1.40116 0.985819 2.50634 + endloop + endfacet + facet normal 0.0821769 -0.192251 0.977899 + outer loop + vertex 1.40587 0.986708 2.50611 + vertex 1.40385 0.989473 2.50683 + vertex 1.40116 0.985819 2.50634 + endloop + endfacet + facet normal 0.105806 -0.326851 0.939135 + outer loop + vertex 1.40116 0.985819 2.50634 + vertex 1.40243 0.982559 2.50506 + vertex 1.40587 0.986708 2.50611 + endloop + endfacet + facet normal 0.106703 -0.32751 0.938803 + outer loop + vertex 1.40243 0.982559 2.50506 + vertex 1.40805 0.983659 2.5048 + vertex 1.40587 0.986708 2.50611 + endloop + endfacet + facet normal 0.0975558 -0.333574 0.937663 + outer loop + vertex 1.40982 0.987683 2.50605 + vertex 1.40587 0.986708 2.50611 + vertex 1.40805 0.983659 2.5048 + endloop + endfacet + facet normal 0.100557 -0.334674 0.936953 + outer loop + vertex 1.40982 0.987683 2.50605 + vertex 1.40805 0.983659 2.5048 + vertex 1.41298 0.987199 2.50554 + endloop + endfacet + facet normal 0.113747 -0.269148 0.956358 + outer loop + vertex 1.41298 0.987199 2.50554 + vertex 1.41224 0.989798 2.50636 + vertex 1.40982 0.987683 2.50605 + endloop + endfacet + facet normal 0.0631999 -0.214076 0.97477 + outer loop + vertex 1.41224 0.989798 2.50636 + vertex 1.4087 0.990037 2.50664 + vertex 1.40982 0.987683 2.50605 + endloop + endfacet + facet normal 0.0842236 0.0754419 0.993587 + outer loop + vertex 1.41224 0.989798 2.50636 + vertex 1.412 0.992497 2.50617 + vertex 1.4087 0.990037 2.50664 + endloop + endfacet + facet normal 0.0294542 0.147956 0.988555 + outer loop + vertex 1.412 0.992497 2.50617 + vertex 1.40627 0.992484 2.50635 + vertex 1.4087 0.990037 2.50664 + endloop + endfacet + facet normal 0.0220062 0.140717 0.989805 + outer loop + vertex 1.4087 0.990037 2.50664 + vertex 1.40627 0.992484 2.50635 + vertex 1.40385 0.989473 2.50683 + endloop + endfacet + facet normal 0.0101605 0.150047 0.988627 + outer loop + vertex 1.40385 0.989473 2.50683 + vertex 1.40627 0.992484 2.50635 + vertex 1.40103 0.991986 2.50647 + endloop + endfacet + facet normal 0.0668717 0.0740297 0.995011 + outer loop + vertex 1.41574 0.990378 2.50608 + vertex 1.412 0.992497 2.50617 + vertex 1.41224 0.989798 2.50636 + endloop + endfacet + facet normal 0.0647797 0.0703227 0.995419 + outer loop + vertex 1.41708 0.993137 2.5058 + vertex 1.412 0.992497 2.50617 + vertex 1.41574 0.990378 2.50608 + endloop + endfacet + facet normal 0.0609516 0.0721971 0.995526 + outer loop + vertex 1.4199 0.991065 2.50577 + vertex 1.41708 0.993137 2.5058 + vertex 1.41574 0.990378 2.50608 + endloop + endfacet + facet normal 0.111932 -0.251428 0.961382 + outer loop + vertex 1.41574 0.990378 2.50608 + vertex 1.41738 0.987432 2.50512 + vertex 1.4199 0.991065 2.50577 + endloop + endfacet + facet normal 0.105579 -0.24734 0.963159 + outer loop + vertex 1.41738 0.987432 2.50512 + vertex 1.42269 0.988756 2.50488 + vertex 1.4199 0.991065 2.50577 + endloop + endfacet + facet normal 0.163578 -0.179968 0.969976 + outer loop + vertex 1.42291 0.992556 2.50554 + vertex 1.4199 0.991065 2.50577 + vertex 1.42269 0.988756 2.50488 + endloop + endfacet + facet normal 0.12257 -0.178649 0.976248 + outer loop + vertex 1.42291 0.992556 2.50554 + vertex 1.42269 0.988756 2.50488 + vertex 1.42685 0.994081 2.50533 + endloop + endfacet + facet normal 0.0897749 -0.153638 0.984041 + outer loop + vertex 1.42685 0.994081 2.50533 + vertex 1.42269 0.988756 2.50488 + vertex 1.42814 0.988836 2.50439 + endloop + endfacet + facet normal -0.000849891 -0.176008 0.984388 + outer loop + vertex 1.42814 0.988836 2.50439 + vertex 1.43266 0.993725 2.50527 + vertex 1.42685 0.994081 2.50533 + endloop + endfacet + facet normal -0.0107408 -0.330672 0.943685 + outer loop + vertex 1.42685 0.994081 2.50533 + vertex 1.43266 0.993725 2.50527 + vertex 1.43087 0.996391 2.50618 + endloop + endfacet + facet normal 0.292391 -0.127842 0.947715 + outer loop + vertex 1.43309 0.997111 2.50559 + vertex 1.43087 0.996391 2.50618 + vertex 1.43266 0.993725 2.50527 + endloop + endfacet + facet normal 0.387828 -0.136464 0.911574 + outer loop + vertex 1.43309 0.997111 2.50559 + vertex 1.43266 0.993725 2.50527 + vertex 1.4359 0.996939 2.50437 + endloop + endfacet + facet normal 0.199128 0.0717459 0.977344 + outer loop + vertex 1.4359 0.996939 2.50437 + vertex 1.43266 0.993725 2.50527 + vertex 1.43767 0.993193 2.50429 + endloop + endfacet + facet normal 0.230406 0.0867185 0.969223 + outer loop + vertex 1.43767 0.993193 2.50429 + vertex 1.44054 0.997041 2.50326 + vertex 1.4359 0.996939 2.50437 + endloop + endfacet + facet normal 0.137299 0.1585 0.977766 + outer loop + vertex 1.44276 0.993265 2.50356 + vertex 1.44054 0.997041 2.50326 + vertex 1.43767 0.993193 2.50429 + endloop + endfacet + facet normal 0.141081 -0.209388 0.967602 + outer loop + vertex 1.43857 0.988814 2.50321 + vertex 1.44276 0.993265 2.50356 + vertex 1.43767 0.993193 2.50429 + endloop + endfacet + facet normal 0.124631 -0.213131 0.969042 + outer loop + vertex 1.43857 0.988814 2.50321 + vertex 1.43767 0.993193 2.50429 + vertex 1.43341 0.988744 2.50386 + endloop + endfacet + facet normal 0.122078 -0.329731 0.936149 + outer loop + vertex 1.4337 0.983964 2.50214 + vertex 1.43857 0.988814 2.50321 + vertex 1.43341 0.988744 2.50386 + endloop + endfacet + facet normal 0.112031 -0.330669 0.937074 + outer loop + vertex 1.4337 0.983964 2.50214 + vertex 1.43341 0.988744 2.50386 + vertex 1.42861 0.984135 2.5028 + endloop + endfacet + facet normal 0.111603 -0.336085 0.935196 + outer loop + vertex 1.4337 0.983964 2.50214 + vertex 1.42861 0.984135 2.5028 + vertex 1.42873 0.980275 2.5014 + endloop + endfacet + facet normal 0.109963 -0.336196 0.93535 + outer loop + vertex 1.42873 0.980275 2.5014 + vertex 1.42861 0.984135 2.5028 + vertex 1.42414 0.979797 2.50177 + endloop + endfacet + facet normal 0.108042 -0.310852 0.944298 + outer loop + vertex 1.42873 0.980275 2.5014 + vertex 1.42414 0.979797 2.50177 + vertex 1.42531 0.976558 2.50057 + endloop + endfacet + facet normal 0.117331 -0.318589 0.940603 + outer loop + vertex 1.42913 0.977568 2.50044 + vertex 1.42873 0.980275 2.5014 + vertex 1.42531 0.976558 2.50057 + endloop + endfacet + facet normal 0.111166 -0.294052 0.949303 + outer loop + vertex 1.42913 0.977568 2.50044 + vertex 1.42531 0.976558 2.50057 + vertex 1.42759 0.973644 2.4994 + endloop + endfacet + facet normal 0.112143 -0.29438 0.949086 + outer loop + vertex 1.42913 0.977568 2.50044 + vertex 1.42759 0.973644 2.4994 + vertex 1.43245 0.9774 2.49999 + endloop + endfacet + facet normal 0.110657 -0.310572 0.944087 + outer loop + vertex 1.43245 0.9774 2.49999 + vertex 1.43189 0.980048 2.50093 + vertex 1.42913 0.977568 2.50044 + endloop + endfacet + facet normal 0.110936 -0.310508 0.944075 + outer loop + vertex 1.43189 0.980048 2.50093 + vertex 1.43245 0.9774 2.49999 + vertex 1.43566 0.981171 2.50085 + endloop + endfacet + facet normal 0.12029 -0.342806 0.931673 + outer loop + vertex 1.43566 0.981171 2.50085 + vertex 1.4337 0.983964 2.50214 + vertex 1.43189 0.980048 2.50093 + endloop + endfacet + facet normal 0.115601 -0.341016 0.932923 + outer loop + vertex 1.43189 0.980048 2.50093 + vertex 1.4337 0.983964 2.50214 + vertex 1.42873 0.980275 2.5014 + endloop + endfacet + facet normal 0.120514 -0.342661 0.931697 + outer loop + vertex 1.43894 0.984954 2.50182 + vertex 1.4337 0.983964 2.50214 + vertex 1.43566 0.981171 2.50085 + endloop + endfacet + facet normal 0.127099 -0.347669 0.928963 + outer loop + vertex 1.4394 0.982276 2.50076 + vertex 1.43894 0.984954 2.50182 + vertex 1.43566 0.981171 2.50085 + endloop + endfacet + facet normal 0.116797 -0.311549 0.943025 + outer loop + vertex 1.4394 0.982276 2.50076 + vertex 1.43566 0.981171 2.50085 + vertex 1.4377 0.978366 2.49968 + endloop + endfacet + facet normal 0.116718 -0.31152 0.943044 + outer loop + vertex 1.4394 0.982276 2.50076 + vertex 1.4377 0.978366 2.49968 + vertex 1.44252 0.98199 2.50028 + endloop + endfacet + facet normal 0.113026 -0.3374 0.934552 + outer loop + vertex 1.44252 0.98199 2.50028 + vertex 1.44218 0.984767 2.50132 + vertex 1.4394 0.982276 2.50076 + endloop + endfacet + facet normal 0.111993 -0.337551 0.934621 + outer loop + vertex 1.44218 0.984767 2.50132 + vertex 1.44252 0.98199 2.50028 + vertex 1.44599 0.985744 2.50122 + endloop + endfacet + facet normal 0.109796 -0.328637 0.938053 + outer loop + vertex 1.44599 0.985744 2.50122 + vertex 1.44386 0.988761 2.50252 + vertex 1.44218 0.984767 2.50132 + endloop + endfacet + facet normal 0.125496 -0.334079 0.934153 + outer loop + vertex 1.44218 0.984767 2.50132 + vertex 1.44386 0.988761 2.50252 + vertex 1.43894 0.984954 2.50182 + endloop + endfacet + facet normal 0.118447 -0.325678 0.938032 + outer loop + vertex 1.44386 0.988761 2.50252 + vertex 1.43857 0.988814 2.50321 + vertex 1.43894 0.984954 2.50182 + endloop + endfacet + facet normal 0.10822 -0.329668 0.937874 + outer loop + vertex 1.44948 0.989906 2.50228 + vertex 1.44386 0.988761 2.50252 + vertex 1.44599 0.985744 2.50122 + endloop + endfacet + facet normal 0.118304 -0.337154 0.933987 + outer loop + vertex 1.4506 0.986552 2.50092 + vertex 1.44948 0.989906 2.50228 + vertex 1.44599 0.985744 2.50122 + endloop + endfacet + facet normal 0.118364 -0.337551 0.933836 + outer loop + vertex 1.44599 0.985744 2.50122 + vertex 1.44704 0.982403 2.49988 + vertex 1.4506 0.986552 2.50092 + endloop + endfacet + facet normal 0.122378 -0.340589 0.932214 + outer loop + vertex 1.44704 0.982403 2.49988 + vertex 1.45255 0.983422 2.49952 + vertex 1.4506 0.986552 2.50092 + endloop + endfacet + facet normal 0.126912 -0.337928 0.932576 + outer loop + vertex 1.45437 0.987476 2.50075 + vertex 1.4506 0.986552 2.50092 + vertex 1.45255 0.983422 2.49952 + endloop + endfacet + facet normal 0.131797 -0.33972 0.931246 + outer loop + vertex 1.45437 0.987476 2.50075 + vertex 1.45255 0.983422 2.49952 + vertex 1.45742 0.987088 2.50017 + endloop + endfacet + facet normal 0.126916 -0.364948 0.922337 + outer loop + vertex 1.45742 0.987088 2.50017 + vertex 1.45717 0.989973 2.50135 + vertex 1.45437 0.987476 2.50075 + endloop + endfacet + facet normal 0.122416 -0.360465 0.924705 + outer loop + vertex 1.45717 0.989973 2.50135 + vertex 1.45408 0.990355 2.50191 + vertex 1.45437 0.987476 2.50075 + endloop + endfacet + facet normal 0.128501 -0.327687 0.936007 + outer loop + vertex 1.45717 0.989973 2.50135 + vertex 1.4588 0.993963 2.50252 + vertex 1.45408 0.990355 2.50191 + endloop + endfacet + facet normal 0.0697999 -0.255568 0.964268 + outer loop + vertex 1.4588 0.993963 2.50252 + vertex 1.45354 0.994187 2.50296 + vertex 1.45408 0.990355 2.50191 + endloop + endfacet + facet normal 0.101898 -0.250619 0.962708 + outer loop + vertex 1.45408 0.990355 2.50191 + vertex 1.45354 0.994187 2.50296 + vertex 1.44948 0.989906 2.50228 + endloop + endfacet + facet normal 0.0544989 -0.207953 0.976619 + outer loop + vertex 1.44948 0.989906 2.50228 + vertex 1.45354 0.994187 2.50296 + vertex 1.44816 0.993753 2.50317 + endloop + endfacet + facet normal 0.0311588 0.090329 0.995424 + outer loop + vertex 1.45354 0.994187 2.50296 + vertex 1.45178 0.998449 2.50263 + vertex 1.44816 0.993753 2.50317 + endloop + endfacet + facet normal -0.00320849 0.116583 0.993176 + outer loop + vertex 1.44816 0.993753 2.50317 + vertex 1.45178 0.998449 2.50263 + vertex 1.44584 0.997412 2.50273 + endloop + endfacet + facet normal 0.0576375 0.154428 0.986321 + outer loop + vertex 1.44816 0.993753 2.50317 + vertex 1.44584 0.997412 2.50273 + vertex 1.44276 0.993265 2.50356 + endloop + endfacet + facet normal 0.0891103 -0.203077 0.9751 + outer loop + vertex 1.44386 0.988761 2.50252 + vertex 1.44816 0.993753 2.50317 + vertex 1.44276 0.993265 2.50356 + endloop + endfacet + facet normal -0.082336 0.0436465 0.995648 + outer loop + vertex 1.45354 0.994187 2.50296 + vertex 1.45756 0.998249 2.50312 + vertex 1.45178 0.998449 2.50263 + endloop + endfacet + facet normal 0.0779643 -0.114735 0.990332 + outer loop + vertex 1.4588 0.993963 2.50252 + vertex 1.45756 0.998249 2.50312 + vertex 1.45354 0.994187 2.50296 + endloop + endfacet + facet normal 0.0280688 -0.129389 0.991197 + outer loop + vertex 1.4588 0.993963 2.50252 + vertex 1.46276 0.998506 2.503 + vertex 1.45756 0.998249 2.50312 + endloop + endfacet + facet normal 0.0104178 0.2204 0.975354 + outer loop + vertex 1.46276 0.998506 2.503 + vertex 1.46057 1.00168 2.50231 + vertex 1.45756 0.998249 2.50312 + endloop + endfacet + facet normal 0.0157479 0.22389 0.974487 + outer loop + vertex 1.46276 0.998506 2.503 + vertex 1.46552 1.00196 2.50216 + vertex 1.46057 1.00168 2.50231 + endloop + endfacet + facet normal 0.0659677 0.185277 0.98047 + outer loop + vertex 1.46785 0.998877 2.50259 + vertex 1.46552 1.00196 2.50216 + vertex 1.46276 0.998506 2.503 + endloop + endfacet + facet normal 0.0923187 -0.176521 0.979958 + outer loop + vertex 1.46432 0.995026 2.50223 + vertex 1.46785 0.998877 2.50259 + vertex 1.46276 0.998506 2.503 + endloop + endfacet + facet normal 0.123826 -0.20454 0.970995 + outer loop + vertex 1.46887 0.995536 2.50175 + vertex 1.46785 0.998877 2.50259 + vertex 1.46432 0.995026 2.50223 + endloop + endfacet + facet normal 0.117229 -0.206653 0.971366 + outer loop + vertex 1.47307 0.998857 2.50195 + vertex 1.46785 0.998877 2.50259 + vertex 1.46887 0.995536 2.50175 + endloop + endfacet + facet normal 0.152442 -0.250278 0.956098 + outer loop + vertex 1.47205 0.995316 2.50119 + vertex 1.47307 0.998857 2.50195 + vertex 1.46887 0.995536 2.50175 + endloop + endfacet + facet normal 0.113076 -0.240605 0.964014 + outer loop + vertex 1.47572 0.996402 2.50103 + vertex 1.47307 0.998857 2.50195 + vertex 1.47205 0.995316 2.50119 + endloop + endfacet + facet normal 0.143537 -0.349092 0.92603 + outer loop + vertex 1.47205 0.995316 2.50119 + vertex 1.47259 0.992587 2.50008 + vertex 1.47572 0.996402 2.50103 + endloop + endfacet + facet normal 0.129402 -0.338972 0.931855 + outer loop + vertex 1.47259 0.992587 2.50008 + vertex 1.47782 0.993544 2.4997 + vertex 1.47572 0.996402 2.50103 + endloop + endfacet + facet normal 0.126531 -0.340932 0.931534 + outer loop + vertex 1.47948 0.997555 2.50094 + vertex 1.47572 0.996402 2.50103 + vertex 1.47782 0.993544 2.4997 + endloop + endfacet + facet normal 0.126252 -0.340839 0.931606 + outer loop + vertex 1.47948 0.997555 2.50094 + vertex 1.47782 0.993544 2.4997 + vertex 1.48267 0.99727 2.50041 + endloop + endfacet + facet normal 0.133303 -0.291451 0.947252 + outer loop + vertex 1.48267 0.99727 2.50041 + vertex 1.482 1 2.50134 + vertex 1.47948 0.997555 2.50094 + endloop + endfacet + facet normal 0.0815287 -0.241376 0.967001 + outer loop + vertex 1.482 1 2.50134 + vertex 1.47839 0.999974 2.50164 + vertex 1.47948 0.997555 2.50094 + endloop + endfacet + facet normal 0.0823723 -0.0167976 0.99646 + outer loop + vertex 1.482 1 2.50134 + vertex 1.4824 1.0035 2.50137 + vertex 1.47839 0.999974 2.50164 + endloop + endfacet + facet normal 0.00907547 0.0665103 0.997744 + outer loop + vertex 1.4824 1.0035 2.50137 + vertex 1.47607 1.00266 2.50148 + vertex 1.47839 0.999974 2.50164 + endloop + endfacet + facet normal 0.0397382 0.0928803 0.994884 + outer loop + vertex 1.47839 0.999974 2.50164 + vertex 1.47607 1.00266 2.50148 + vertex 1.47307 0.998857 2.50195 + endloop + endfacet + facet normal 0.056026 0.0800799 0.995213 + outer loop + vertex 1.47307 0.998857 2.50195 + vertex 1.47607 1.00266 2.50148 + vertex 1.47067 1.0022 2.50182 + endloop + endfacet + facet normal 0.0406127 -0.012085 0.999102 + outer loop + vertex 1.48585 1.00093 2.50119 + vertex 1.4824 1.0035 2.50137 + vertex 1.482 1 2.50134 + endloop + endfacet + facet normal -0.0314306 -0.108484 0.993601 + outer loop + vertex 1.48867 1.00438 2.50166 + vertex 1.4824 1.0035 2.50137 + vertex 1.48585 1.00093 2.50119 + endloop + endfacet + facet normal -0.0789376 0.240398 0.967459 + outer loop + vertex 1.4824 1.0035 2.50137 + vertex 1.48867 1.00438 2.50166 + vertex 1.48633 1.00657 2.50092 + endloop + endfacet + facet normal 0.107912 -0.298059 0.948428 + outer loop + vertex 1.482 1 2.50134 + vertex 1.48267 0.99727 2.50041 + vertex 1.48585 1.00093 2.50119 + endloop + endfacet + facet normal 0.113578 -0.302534 0.946347 + outer loop + vertex 1.48267 0.99727 2.50041 + vertex 1.4873 0.997707 2.49999 + vertex 1.48585 1.00093 2.50119 + endloop + endfacet + facet normal 0.116036 -0.341737 0.932605 + outer loop + vertex 1.48294 0.993303 2.49892 + vertex 1.4873 0.997707 2.49999 + vertex 1.48267 0.99727 2.50041 + endloop + endfacet + facet normal 0.11621 -0.34189 0.932527 + outer loop + vertex 1.48819 0.993696 2.49841 + vertex 1.4873 0.997707 2.49999 + vertex 1.48294 0.993303 2.49892 + endloop + endfacet + facet normal 0.115154 -0.315678 0.941853 + outer loop + vertex 1.48356 0.988673 2.49729 + vertex 1.48819 0.993696 2.49841 + vertex 1.48294 0.993303 2.49892 + endloop + endfacet + facet normal 0.117827 -0.315254 0.941664 + outer loop + vertex 1.48356 0.988673 2.49729 + vertex 1.48294 0.993303 2.49892 + vertex 1.47822 0.988818 2.49801 + endloop + endfacet + facet normal 0.119358 -0.29311 0.948599 + outer loop + vertex 1.48356 0.988673 2.49729 + vertex 1.47822 0.988818 2.49801 + vertex 1.47876 0.984924 2.49674 + endloop + endfacet + facet normal 0.11819 -0.293302 0.948686 + outer loop + vertex 1.47876 0.984924 2.49674 + vertex 1.47822 0.988818 2.49801 + vertex 1.47344 0.983924 2.49709 + endloop + endfacet + facet normal 0.115909 -0.279603 0.953093 + outer loop + vertex 1.47876 0.984924 2.49674 + vertex 1.47344 0.983924 2.49709 + vertex 1.47571 0.981144 2.496 + endloop + endfacet + facet normal 0.114946 -0.278888 0.953419 + outer loop + vertex 1.47944 0.982239 2.49587 + vertex 1.47876 0.984924 2.49674 + vertex 1.47571 0.981144 2.496 + endloop + endfacet + facet normal 0.116292 -0.283663 0.951846 + outer loop + vertex 1.47944 0.982239 2.49587 + vertex 1.47571 0.981144 2.496 + vertex 1.47782 0.978307 2.4949 + endloop + endfacet + facet normal 0.115691 -0.283449 0.951983 + outer loop + vertex 1.47944 0.982239 2.49587 + vertex 1.47782 0.978307 2.4949 + vertex 1.48254 0.981937 2.4954 + endloop + endfacet + facet normal 0.116263 -0.279332 0.95313 + outer loop + vertex 1.48254 0.981937 2.4954 + vertex 1.48206 0.984704 2.49627 + vertex 1.47944 0.982239 2.49587 + endloop + endfacet + facet normal 0.113684 -0.279828 0.953296 + outer loop + vertex 1.48206 0.984704 2.49627 + vertex 1.48254 0.981937 2.4954 + vertex 1.48579 0.985642 2.4961 + endloop + endfacet + facet normal 0.115559 -0.287759 0.950705 + outer loop + vertex 1.48579 0.985642 2.4961 + vertex 1.48356 0.988673 2.49729 + vertex 1.48206 0.984704 2.49627 + endloop + endfacet + facet normal 0.114699 -0.287482 0.950893 + outer loop + vertex 1.48206 0.984704 2.49627 + vertex 1.48356 0.988673 2.49729 + vertex 1.47876 0.984924 2.49674 + endloop + endfacet + facet normal 0.112092 -0.290185 0.950383 + outer loop + vertex 1.48914 0.989732 2.49696 + vertex 1.48356 0.988673 2.49729 + vertex 1.48579 0.985642 2.4961 + endloop + endfacet + facet normal 0.111457 -0.289712 0.950602 + outer loop + vertex 1.4904 0.986433 2.4958 + vertex 1.48914 0.989732 2.49696 + vertex 1.48579 0.985642 2.4961 + endloop + endfacet + facet normal 0.110376 -0.282565 0.952877 + outer loop + vertex 1.48579 0.985642 2.4961 + vertex 1.48702 0.982365 2.49499 + vertex 1.4904 0.986433 2.4958 + endloop + endfacet + facet normal 0.112105 -0.283881 0.952284 + outer loop + vertex 1.48702 0.982365 2.49499 + vertex 1.49261 0.983435 2.49465 + vertex 1.4904 0.986433 2.4958 + endloop + endfacet + facet normal 0.108192 -0.28662 0.951916 + outer loop + vertex 1.49422 0.987387 2.49566 + vertex 1.4904 0.986433 2.4958 + vertex 1.49261 0.983435 2.49465 + endloop + endfacet + facet normal 0.108165 -0.286611 0.951922 + outer loop + vertex 1.49422 0.987387 2.49566 + vertex 1.49261 0.983435 2.49465 + vertex 1.49753 0.98718 2.49522 + endloop + endfacet + facet normal 0.107304 -0.295076 0.949429 + outer loop + vertex 1.49753 0.98718 2.49522 + vertex 1.49693 0.989852 2.49612 + vertex 1.49422 0.987387 2.49566 + endloop + endfacet + facet normal 0.107811 -0.295593 0.949211 + outer loop + vertex 1.49693 0.989852 2.49612 + vertex 1.49374 0.990155 2.49657 + vertex 1.49422 0.987387 2.49566 + endloop + endfacet + facet normal 0.104473 -0.319571 0.941785 + outer loop + vertex 1.49693 0.989852 2.49612 + vertex 1.49861 0.993811 2.49727 + vertex 1.49374 0.990155 2.49657 + endloop + endfacet + facet normal 0.106027 -0.321485 0.94096 + outer loop + vertex 1.49861 0.993811 2.49727 + vertex 1.49345 0.994075 2.49794 + vertex 1.49374 0.990155 2.49657 + endloop + endfacet + facet normal 0.108002 -0.321285 0.940804 + outer loop + vertex 1.49374 0.990155 2.49657 + vertex 1.49345 0.994075 2.49794 + vertex 1.48914 0.989732 2.49696 + endloop + endfacet + facet normal 0.106057 -0.319538 0.941619 + outer loop + vertex 1.48914 0.989732 2.49696 + vertex 1.49345 0.994075 2.49794 + vertex 1.48819 0.993696 2.49841 + endloop + endfacet + facet normal 0.107346 -0.351653 0.929955 + outer loop + vertex 1.49345 0.994075 2.49794 + vertex 1.49303 0.998791 2.49978 + vertex 1.48819 0.993696 2.49841 + endloop + endfacet + facet normal 0.11042 -0.35129 0.929733 + outer loop + vertex 1.49345 0.994075 2.49794 + vertex 1.49831 0.998593 2.49907 + vertex 1.49303 0.998791 2.49978 + endloop + endfacet + facet normal 0.103775 -0.34493 0.932874 + outer loop + vertex 1.49861 0.993811 2.49727 + vertex 1.49831 0.998593 2.49907 + vertex 1.49345 0.994075 2.49794 + endloop + endfacet + facet normal 0.110994 -0.290115 0.950533 + outer loop + vertex 1.49753 0.98718 2.49522 + vertex 1.49261 0.983435 2.49465 + vertex 1.498 0.983339 2.49399 + endloop + endfacet + facet normal 0.110136 -0.290241 0.950595 + outer loop + vertex 1.498 0.983339 2.49399 + vertex 1.50275 0.988146 2.49491 + vertex 1.49753 0.98718 2.49522 + endloop + endfacet + facet normal 0.111703 -0.299727 0.947463 + outer loop + vertex 1.49753 0.98718 2.49522 + vertex 1.50275 0.988146 2.49491 + vertex 1.50067 0.990935 2.49603 + endloop + endfacet + facet normal 0.106 -0.295385 0.94948 + outer loop + vertex 1.49693 0.989852 2.49612 + vertex 1.49753 0.98718 2.49522 + vertex 1.50067 0.990935 2.49603 + endloop + endfacet + facet normal 0.113728 -0.322863 0.939588 + outer loop + vertex 1.50067 0.990935 2.49603 + vertex 1.49861 0.993811 2.49727 + vertex 1.49693 0.989852 2.49612 + endloop + endfacet + facet normal 0.111524 -0.324338 0.939344 + outer loop + vertex 1.50386 0.994743 2.49697 + vertex 1.49861 0.993811 2.49727 + vertex 1.50067 0.990935 2.49603 + endloop + endfacet + facet normal 0.121557 -0.331786 0.93549 + outer loop + vertex 1.5044 0.992018 2.49593 + vertex 1.50386 0.994743 2.49697 + vertex 1.50067 0.990935 2.49603 + endloop + endfacet + facet normal 0.119672 -0.332196 0.935588 + outer loop + vertex 1.50712 0.99452 2.49647 + vertex 1.50386 0.994743 2.49697 + vertex 1.5044 0.992018 2.49593 + endloop + endfacet + facet normal 0.109977 -0.32263 0.940114 + outer loop + vertex 1.50752 0.991758 2.49548 + vertex 1.50712 0.99452 2.49647 + vertex 1.5044 0.992018 2.49593 + endloop + endfacet + facet normal 0.112969 -0.299431 0.947407 + outer loop + vertex 1.5044 0.992018 2.49593 + vertex 1.50275 0.988146 2.49491 + vertex 1.50752 0.991758 2.49548 + endloop + endfacet + facet normal 0.111856 -0.322317 0.94 + outer loop + vertex 1.50712 0.99452 2.49647 + vertex 1.50752 0.991758 2.49548 + vertex 1.51092 0.995518 2.49637 + endloop + endfacet + facet normal 0.115781 -0.337909 0.93403 + outer loop + vertex 1.51092 0.995518 2.49637 + vertex 1.50881 0.998621 2.49775 + vertex 1.50712 0.99452 2.49647 + endloop + endfacet + facet normal 0.117973 -0.336519 0.934258 + outer loop + vertex 1.51438 0.99969 2.49743 + vertex 1.50881 0.998621 2.49775 + vertex 1.51092 0.995518 2.49637 + endloop + endfacet + facet normal 0.126051 -0.342398 0.931061 + outer loop + vertex 1.51555 0.996334 2.49604 + vertex 1.51438 0.99969 2.49743 + vertex 1.51092 0.995518 2.49637 + endloop + endfacet + facet normal 0.122879 -0.321222 0.938998 + outer loop + vertex 1.51092 0.995518 2.49637 + vertex 1.51204 0.992223 2.49509 + vertex 1.51555 0.996334 2.49604 + endloop + endfacet + facet normal 0.120521 -0.319424 0.939916 + outer loop + vertex 1.51204 0.992223 2.49509 + vertex 1.51759 0.993284 2.49474 + vertex 1.51555 0.996334 2.49604 + endloop + endfacet + facet normal 0.115812 -0.291653 0.949487 + outer loop + vertex 1.5129 0.988333 2.49379 + vertex 1.51759 0.993284 2.49474 + vertex 1.51204 0.992223 2.49509 + endloop + endfacet + facet normal 0.10822 -0.279921 0.953904 + outer loop + vertex 1.51438 0.99969 2.49743 + vertex 1.51337 1.00371 2.49873 + vertex 1.50881 0.998621 2.49775 + endloop + endfacet + facet normal 0.0952963 -0.269205 0.958357 + outer loop + vertex 1.50881 0.998621 2.49775 + vertex 1.51337 1.00371 2.49873 + vertex 1.50815 1.00351 2.49919 + endloop + endfacet + facet normal 0.123501 -0.264807 0.95636 + outer loop + vertex 1.50881 0.998621 2.49775 + vertex 1.50815 1.00351 2.49919 + vertex 1.50351 0.998787 2.49848 + endloop + endfacet + facet normal 0.118072 -0.338023 0.933702 + outer loop + vertex 1.50881 0.998621 2.49775 + vertex 1.50351 0.998787 2.49848 + vertex 1.50386 0.994743 2.49697 + endloop + endfacet + facet normal 0.149356 -0.288563 0.94574 + outer loop + vertex 1.50351 0.998787 2.49848 + vertex 1.50815 1.00351 2.49919 + vertex 1.50286 1.00362 2.50005 + endloop + endfacet + facet normal 0.119425 -0.293485 0.948475 + outer loop + vertex 1.50351 0.998787 2.49848 + vertex 1.50286 1.00362 2.50005 + vertex 1.49831 0.998593 2.49907 + endloop + endfacet + facet normal 0.119352 -0.34345 0.931556 + outer loop + vertex 1.49861 0.993811 2.49727 + vertex 1.50351 0.998787 2.49848 + vertex 1.49831 0.998593 2.49907 + endloop + endfacet + facet normal 0.185403 -0.347575 0.91914 + outer loop + vertex 1.49831 0.998593 2.49907 + vertex 1.50286 1.00362 2.50005 + vertex 1.49793 1.00254 2.50064 + endloop + endfacet + facet normal 0.109833 -0.35806 0.927216 + outer loop + vertex 1.49793 1.00254 2.50064 + vertex 1.49303 0.998791 2.49978 + vertex 1.49831 0.998593 2.49907 + endloop + endfacet + facet normal 0.113497 -0.362355 0.925104 + outer loop + vertex 1.49471 1.00278 2.50113 + vertex 1.49303 0.998791 2.49978 + vertex 1.49793 1.00254 2.50064 + endloop + endfacet + facet normal 0.122491 -0.290268 0.949074 + outer loop + vertex 1.49793 1.00254 2.50064 + vertex 1.49696 1.00495 2.5015 + vertex 1.49471 1.00278 2.50113 + endloop + endfacet + facet normal 0.0414714 -0.210848 0.976639 + outer loop + vertex 1.49696 1.00495 2.5015 + vertex 1.4935 1.00498 2.50166 + vertex 1.49471 1.00278 2.50113 + endloop + endfacet + facet normal 0.0438623 -0.209566 0.97681 + outer loop + vertex 1.49471 1.00278 2.50113 + vertex 1.4935 1.00498 2.50166 + vertex 1.49074 1.00177 2.50109 + endloop + endfacet + facet normal 0.0459101 0.152197 0.987283 + outer loop + vertex 1.49696 1.00495 2.5015 + vertex 1.49646 1.00743 2.50114 + vertex 1.4935 1.00498 2.50166 + endloop + endfacet + facet normal -0.00488235 0.211592 0.977346 + outer loop + vertex 1.49646 1.00743 2.50114 + vertex 1.49122 1.00713 2.50118 + vertex 1.4935 1.00498 2.50166 + endloop + endfacet + facet normal 0.061523 0.155143 0.985974 + outer loop + vertex 1.50007 1.00588 2.50116 + vertex 1.49646 1.00743 2.50114 + vertex 1.49696 1.00495 2.5015 + endloop + endfacet + facet normal 0.0815496 0.201535 0.97608 + outer loop + vertex 1.50039 1.0083 2.50064 + vertex 1.49646 1.00743 2.50114 + vertex 1.50007 1.00588 2.50116 + endloop + endfacet + facet normal 0.150133 0.191235 0.969994 + outer loop + vertex 1.50299 1.00733 2.50042 + vertex 1.50039 1.0083 2.50064 + vertex 1.50007 1.00588 2.50116 + endloop + endfacet + facet normal 0.292783 -0.104629 0.950437 + outer loop + vertex 1.50299 1.00733 2.50042 + vertex 1.50007 1.00588 2.50116 + vertex 1.50286 1.00362 2.50005 + endloop + endfacet + facet normal 0.312972 -0.10469 0.943975 + outer loop + vertex 1.50299 1.00733 2.50042 + vertex 1.50286 1.00362 2.50005 + vertex 1.50688 1.00808 2.49922 + endloop + endfacet + facet normal 0.182961 -0.264984 0.946736 + outer loop + vertex 1.49696 1.00495 2.5015 + vertex 1.49793 1.00254 2.50064 + vertex 1.50007 1.00588 2.50116 + endloop + endfacet + facet normal 0.0803877 -0.351031 0.932907 + outer loop + vertex 1.49471 1.00278 2.50113 + vertex 1.49074 1.00177 2.50109 + vertex 1.49303 0.998791 2.49978 + endloop + endfacet + facet normal 0.169625 -0.257139 0.951371 + outer loop + vertex 1.49793 1.00254 2.50064 + vertex 1.50286 1.00362 2.50005 + vertex 1.50007 1.00588 2.50116 + endloop + endfacet + facet normal 0.162219 0.0389593 0.985985 + outer loop + vertex 1.50688 1.00808 2.49922 + vertex 1.50286 1.00362 2.50005 + vertex 1.50815 1.00351 2.49919 + endloop + endfacet + facet normal 0.0245736 0.000704427 0.999698 + outer loop + vertex 1.50815 1.00351 2.49919 + vertex 1.51227 1.00793 2.49908 + vertex 1.50688 1.00808 2.49922 + endloop + endfacet + facet normal 0.090638 -0.0610746 0.994009 + outer loop + vertex 1.51337 1.00371 2.49873 + vertex 1.51227 1.00793 2.49908 + vertex 1.50815 1.00351 2.49919 + endloop + endfacet + facet normal 0.0350703 -0.0757178 0.996512 + outer loop + vertex 1.51337 1.00371 2.49873 + vertex 1.51743 1.00822 2.49893 + vertex 1.51227 1.00793 2.49908 + endloop + endfacet + facet normal 0.0131958 0.288805 0.957297 + outer loop + vertex 1.51743 1.00822 2.49893 + vertex 1.51548 1.01167 2.49791 + vertex 1.51227 1.00793 2.49908 + endloop + endfacet + facet normal -0.0794194 0.239593 0.96762 + outer loop + vertex 1.51743 1.00822 2.49893 + vertex 1.52133 1.01272 2.49813 + vertex 1.51548 1.01167 2.49791 + endloop + endfacet + facet normal 0.0188587 0.157732 0.987302 + outer loop + vertex 1.52267 1.00835 2.49881 + vertex 1.52133 1.01272 2.49813 + vertex 1.51743 1.00822 2.49893 + endloop + endfacet + facet normal 0.0259396 -0.144298 0.989194 + outer loop + vertex 1.51848 1.00398 2.49828 + vertex 1.52267 1.00835 2.49881 + vertex 1.51743 1.00822 2.49893 + endloop + endfacet + facet normal 0.113995 -0.226126 0.967405 + outer loop + vertex 1.52368 1.0037 2.4976 + vertex 1.52267 1.00835 2.49881 + vertex 1.51848 1.00398 2.49828 + endloop + endfacet + facet normal 0.106439 -0.31077 0.944507 + outer loop + vertex 1.52368 1.0037 2.4976 + vertex 1.51848 1.00398 2.49828 + vertex 1.51895 1.00008 2.49694 + endloop + endfacet + facet normal 0.13363 -0.343615 0.929554 + outer loop + vertex 1.52211 0.999679 2.49634 + vertex 1.52368 1.0037 2.4976 + vertex 1.51895 1.00008 2.49694 + endloop + endfacet + facet normal 0.132664 -0.348622 0.927827 + outer loop + vertex 1.52211 0.999679 2.49634 + vertex 1.51895 1.00008 2.49694 + vertex 1.51935 0.997248 2.49582 + endloop + endfacet + facet normal 0.117371 -0.332947 0.935612 + outer loop + vertex 1.52247 0.996883 2.4953 + vertex 1.52211 0.999679 2.49634 + vertex 1.51935 0.997248 2.49582 + endloop + endfacet + facet normal 0.121109 -0.31108 0.942636 + outer loop + vertex 1.51935 0.997248 2.49582 + vertex 1.51759 0.993284 2.49474 + vertex 1.52247 0.996883 2.4953 + endloop + endfacet + facet normal 0.111896 -0.299341 0.947562 + outer loop + vertex 1.52247 0.996883 2.4953 + vertex 1.51759 0.993284 2.49474 + vertex 1.52272 0.993137 2.49409 + endloop + endfacet + facet normal 0.104121 -0.300068 0.948218 + outer loop + vertex 1.52272 0.993137 2.49409 + vertex 1.52705 0.997291 2.49493 + vertex 1.52247 0.996883 2.4953 + endloop + endfacet + facet normal 0.105781 -0.327066 0.939063 + outer loop + vertex 1.52247 0.996883 2.4953 + vertex 1.52705 0.997291 2.49493 + vertex 1.52591 1.00057 2.4962 + endloop + endfacet + facet normal 0.109822 -0.325663 0.939086 + outer loop + vertex 1.52591 1.00057 2.4962 + vertex 1.52705 0.997291 2.49493 + vertex 1.53057 1.00131 2.49591 + endloop + endfacet + facet normal 0.111603 -0.338864 0.934193 + outer loop + vertex 1.53057 1.00131 2.49591 + vertex 1.52928 1.00467 2.49728 + vertex 1.52591 1.00057 2.4962 + endloop + endfacet + facet normal 0.112049 -0.339186 0.934023 + outer loop + vertex 1.52928 1.00467 2.49728 + vertex 1.52368 1.0037 2.4976 + vertex 1.52591 1.00057 2.4962 + endloop + endfacet + facet normal 0.104918 -0.292939 0.950357 + outer loop + vertex 1.52928 1.00467 2.49728 + vertex 1.52796 1.00872 2.49868 + vertex 1.52368 1.0037 2.4976 + endloop + endfacet + facet normal 0.0997054 -0.294647 0.95039 + outer loop + vertex 1.52928 1.00467 2.49728 + vertex 1.53324 1.00911 2.49824 + vertex 1.52796 1.00872 2.49868 + endloop + endfacet + facet normal 0.0959053 -0.220474 0.970666 + outer loop + vertex 1.53324 1.00911 2.49824 + vertex 1.53181 1.01436 2.49958 + vertex 1.52796 1.00872 2.49868 + endloop + endfacet + facet normal -0.0201283 -0.144251 0.989336 + outer loop + vertex 1.52796 1.00872 2.49868 + vertex 1.53181 1.01436 2.49958 + vertex 1.52642 1.01221 2.49915 + endloop + endfacet + facet normal 0.0327703 -0.121201 0.992087 + outer loop + vertex 1.52796 1.00872 2.49868 + vertex 1.52642 1.01221 2.49915 + vertex 1.52267 1.00835 2.49881 + endloop + endfacet + facet normal 0.0838835 -0.223841 0.971009 + outer loop + vertex 1.53324 1.00911 2.49824 + vertex 1.53751 1.01387 2.49897 + vertex 1.53181 1.01436 2.49958 + endloop + endfacet + facet normal 0.100696 -0.0568703 0.993291 + outer loop + vertex 1.5361 1.01931 2.49943 + vertex 1.53181 1.01436 2.49958 + vertex 1.53751 1.01387 2.49897 + endloop + endfacet + facet normal 0.428823 -0.346008 0.834499 + outer loop + vertex 1.53306 1.01778 2.50035 + vertex 1.53181 1.01436 2.49958 + vertex 1.5361 1.01931 2.49943 + endloop + endfacet + facet normal 0.0424392 -0.235791 0.970877 + outer loop + vertex 1.53306 1.01778 2.50035 + vertex 1.53141 1.01718 2.50028 + vertex 1.53181 1.01436 2.49958 + endloop + endfacet + facet normal 0.0417677 -0.233989 0.971342 + outer loop + vertex 1.53306 1.01778 2.50035 + vertex 1.53228 1.01826 2.5005 + vertex 1.53141 1.01718 2.50028 + endloop + endfacet + facet normal 0.128155 -0.2614 0.956685 + outer loop + vertex 1.5385 1.00862 2.49741 + vertex 1.53751 1.01387 2.49897 + vertex 1.53324 1.00911 2.49824 + endloop + endfacet + facet normal 0.121574 -0.309103 0.943226 + outer loop + vertex 1.5385 1.00862 2.49741 + vertex 1.53324 1.00911 2.49824 + vertex 1.53389 1.00499 2.49681 + endloop + endfacet + facet normal 0.120319 -0.30762 0.943871 + outer loop + vertex 1.53702 1.00454 2.49626 + vertex 1.5385 1.00862 2.49741 + vertex 1.53389 1.00499 2.49681 + endloop + endfacet + facet normal 0.116414 -0.327371 0.937697 + outer loop + vertex 1.53702 1.00454 2.49626 + vertex 1.53389 1.00499 2.49681 + vertex 1.53437 1.00216 2.49576 + endloop + endfacet + facet normal 0.102829 -0.313539 0.943991 + outer loop + vertex 1.53743 1.00178 2.4953 + vertex 1.53702 1.00454 2.49626 + vertex 1.53437 1.00216 2.49576 + endloop + endfacet + facet normal 0.103213 -0.311305 0.944688 + outer loop + vertex 1.53437 1.00216 2.49576 + vertex 1.53264 0.998261 2.49467 + vertex 1.53743 1.00178 2.4953 + endloop + endfacet + facet normal 0.0943488 -0.300055 0.949245 + outer loop + vertex 1.53743 1.00178 2.4953 + vertex 1.53264 0.998261 2.49467 + vertex 1.5378 0.997997 2.49407 + endloop + endfacet + facet normal 0.0945726 -0.297471 0.950035 + outer loop + vertex 1.5332 0.993676 2.49317 + vertex 1.5378 0.997997 2.49407 + vertex 1.53264 0.998261 2.49467 + endloop + endfacet + facet normal 0.0944621 -0.297486 0.950041 + outer loop + vertex 1.5332 0.993676 2.49317 + vertex 1.53264 0.998261 2.49467 + vertex 1.52788 0.993426 2.49362 + endloop + endfacet + facet normal 0.0943979 -0.294368 0.951019 + outer loop + vertex 1.52846 0.988933 2.49218 + vertex 1.5332 0.993676 2.49317 + vertex 1.52788 0.993426 2.49362 + endloop + endfacet + facet normal 0.105945 -0.29267 0.950326 + outer loop + vertex 1.52846 0.988933 2.49218 + vertex 1.52788 0.993426 2.49362 + vertex 1.52328 0.989068 2.4928 + endloop + endfacet + facet normal 0.105921 -0.29306 0.950209 + outer loop + vertex 1.52846 0.988933 2.49218 + vertex 1.52328 0.989068 2.4928 + vertex 1.52366 0.985321 2.4916 + endloop + endfacet + facet normal 0.112982 -0.301878 0.946628 + outer loop + vertex 1.52685 0.985047 2.49113 + vertex 1.52846 0.988933 2.49218 + vertex 1.52366 0.985321 2.4916 + endloop + endfacet + facet normal 0.113329 -0.299215 0.947432 + outer loop + vertex 1.52685 0.985047 2.49113 + vertex 1.52366 0.985321 2.4916 + vertex 1.52415 0.982552 2.49066 + endloop + endfacet + facet normal 0.11034 -0.296217 0.948726 + outer loop + vertex 1.52746 0.982318 2.49021 + vertex 1.52685 0.985047 2.49113 + vertex 1.52415 0.982552 2.49066 + endloop + endfacet + facet normal 0.110294 -0.29663 0.948602 + outer loop + vertex 1.52415 0.982552 2.49066 + vertex 1.5226 0.978546 2.48959 + vertex 1.52746 0.982318 2.49021 + endloop + endfacet + facet normal 0.110152 -0.296459 0.948672 + outer loop + vertex 1.52746 0.982318 2.49021 + vertex 1.5226 0.978546 2.48959 + vertex 1.52794 0.978423 2.48893 + endloop + endfacet + facet normal 0.0998289 -0.297954 0.949346 + outer loop + vertex 1.52794 0.978423 2.48893 + vertex 1.53271 0.983203 2.48993 + vertex 1.52746 0.982318 2.49021 + endloop + endfacet + facet normal 0.0994072 -0.29517 0.95026 + outer loop + vertex 1.52746 0.982318 2.49021 + vertex 1.53271 0.983203 2.48993 + vertex 1.53063 0.986087 2.49105 + endloop + endfacet + facet normal 0.094691 -0.298372 0.949741 + outer loop + vertex 1.5344 0.987093 2.49099 + vertex 1.53063 0.986087 2.49105 + vertex 1.53271 0.983203 2.48993 + endloop + endfacet + facet normal 0.0895108 -0.296423 0.950853 + outer loop + vertex 1.5344 0.987093 2.49099 + vertex 1.53271 0.983203 2.48993 + vertex 1.53752 0.986728 2.49058 + endloop + endfacet + facet normal 0.088948 -0.300033 0.949773 + outer loop + vertex 1.53752 0.986728 2.49058 + vertex 1.53709 0.989514 2.4915 + vertex 1.5344 0.987093 2.49099 + endloop + endfacet + facet normal 0.0900823 -0.301193 0.949299 + outer loop + vertex 1.53709 0.989514 2.4915 + vertex 1.53376 0.989815 2.49191 + vertex 1.5344 0.987093 2.49099 + endloop + endfacet + facet normal 0.0906975 -0.29638 0.950754 + outer loop + vertex 1.53709 0.989514 2.4915 + vertex 1.53858 0.993479 2.49259 + vertex 1.53376 0.989815 2.49191 + endloop + endfacet + facet normal 0.0918388 -0.297779 0.950207 + outer loop + vertex 1.53858 0.993479 2.49259 + vertex 1.5332 0.993676 2.49317 + vertex 1.53376 0.989815 2.49191 + endloop + endfacet + facet normal 0.0936945 -0.301757 0.94877 + outer loop + vertex 1.53752 0.986728 2.49058 + vertex 1.53271 0.983203 2.48993 + vertex 1.53776 0.982975 2.48936 + endloop + endfacet + facet normal 0.0937425 -0.301157 0.948956 + outer loop + vertex 1.53319 0.978678 2.48845 + vertex 1.53776 0.982975 2.48936 + vertex 1.53271 0.983203 2.48993 + endloop + endfacet + facet normal 0.0978271 -0.305144 0.947268 + outer loop + vertex 1.53829 0.978906 2.488 + vertex 1.53776 0.982975 2.48936 + vertex 1.53319 0.978678 2.48845 + endloop + endfacet + facet normal 0.0978657 -0.307573 0.946478 + outer loop + vertex 1.53409 0.974784 2.48709 + vertex 1.53829 0.978906 2.488 + vertex 1.53319 0.978678 2.48845 + endloop + endfacet + facet normal 0.106056 -0.305585 0.94624 + outer loop + vertex 1.53409 0.974784 2.48709 + vertex 1.53319 0.978678 2.48845 + vertex 1.52855 0.973778 2.48739 + endloop + endfacet + facet normal 0.1068 -0.310147 0.944671 + outer loop + vertex 1.53409 0.974784 2.48709 + vertex 1.52855 0.973778 2.48739 + vertex 1.53072 0.970707 2.48613 + endloop + endfacet + facet normal 0.107337 -0.310546 0.944479 + outer loop + vertex 1.53536 0.971496 2.48587 + vertex 1.53409 0.974784 2.48709 + vertex 1.53072 0.970707 2.48613 + endloop + endfacet + facet normal 0.107824 -0.313786 0.943352 + outer loop + vertex 1.53072 0.970707 2.48613 + vertex 1.53199 0.96743 2.4849 + vertex 1.53536 0.971496 2.48587 + endloop + endfacet + facet normal 0.104911 -0.311625 0.944396 + outer loop + vertex 1.53199 0.96743 2.4849 + vertex 1.53756 0.96846 2.48462 + vertex 1.53536 0.971496 2.48587 + endloop + endfacet + facet normal 0.100014 -0.314939 0.943828 + outer loop + vertex 1.53914 0.972374 2.48576 + vertex 1.53536 0.971496 2.48587 + vertex 1.53756 0.96846 2.48462 + endloop + endfacet + facet normal 0.0949916 -0.313218 0.944919 + outer loop + vertex 1.53914 0.972374 2.48576 + vertex 1.53756 0.96846 2.48462 + vertex 1.54231 0.971957 2.4853 + endloop + endfacet + facet normal 0.0948595 -0.313963 0.944684 + outer loop + vertex 1.54231 0.971957 2.4853 + vertex 1.54183 0.97475 2.48628 + vertex 1.53914 0.972374 2.48576 + endloop + endfacet + facet normal 0.0946976 -0.313796 0.944756 + outer loop + vertex 1.54183 0.97475 2.48628 + vertex 1.53867 0.975161 2.48673 + vertex 1.53914 0.972374 2.48576 + endloop + endfacet + facet normal 0.0960315 -0.306151 0.947127 + outer loop + vertex 1.54183 0.97475 2.48628 + vertex 1.54344 0.978688 2.48739 + vertex 1.53867 0.975161 2.48673 + endloop + endfacet + facet normal 0.0987276 -0.309543 0.945746 + outer loop + vertex 1.54344 0.978688 2.48739 + vertex 1.53829 0.978906 2.488 + vertex 1.53867 0.975161 2.48673 + endloop + endfacet + facet normal 0.0991137 -0.304711 0.947274 + outer loop + vertex 1.54344 0.978688 2.48739 + vertex 1.54285 0.983227 2.48891 + vertex 1.53829 0.978906 2.488 + endloop + endfacet + facet normal 0.0978963 -0.316869 0.943404 + outer loop + vertex 1.54231 0.971957 2.4853 + vertex 1.53756 0.96846 2.48462 + vertex 1.54276 0.968184 2.48399 + endloop + endfacet + facet normal 0.0977469 -0.318477 0.942878 + outer loop + vertex 1.53826 0.964038 2.48305 + vertex 1.54276 0.968184 2.48399 + vertex 1.53756 0.96846 2.48462 + endloop + endfacet + facet normal 0.105622 -0.31708 0.942499 + outer loop + vertex 1.53826 0.964038 2.48305 + vertex 1.53756 0.96846 2.48462 + vertex 1.53304 0.963645 2.48351 + endloop + endfacet + facet normal 0.105715 -0.319124 0.941799 + outer loop + vertex 1.53409 0.95986 2.48211 + vertex 1.53826 0.964038 2.48305 + vertex 1.53304 0.963645 2.48351 + endloop + endfacet + facet normal 0.111711 -0.31742 0.941682 + outer loop + vertex 1.53409 0.95986 2.48211 + vertex 1.53304 0.963645 2.48351 + vertex 1.52853 0.958801 2.48241 + endloop + endfacet + facet normal 0.111576 -0.316631 0.941964 + outer loop + vertex 1.53409 0.95986 2.48211 + vertex 1.52853 0.958801 2.48241 + vertex 1.5307 0.955775 2.48113 + endloop + endfacet + facet normal 0.111149 -0.316314 0.942121 + outer loop + vertex 1.53535 0.956581 2.48086 + vertex 1.53409 0.95986 2.48211 + vertex 1.5307 0.955775 2.48113 + endloop + endfacet + facet normal 0.110682 -0.313254 0.943197 + outer loop + vertex 1.5307 0.955775 2.48113 + vertex 1.53194 0.952484 2.4799 + vertex 1.53535 0.956581 2.48086 + endloop + endfacet + facet normal 0.10977 -0.313595 0.943191 + outer loop + vertex 1.52737 0.952057 2.48029 + vertex 1.53194 0.952484 2.4799 + vertex 1.5307 0.955775 2.48113 + endloop + endfacet + facet normal 0.110431 -0.314129 0.942936 + outer loop + vertex 1.52693 0.95486 2.48127 + vertex 1.52737 0.952057 2.48029 + vertex 1.5307 0.955775 2.48113 + endloop + endfacet + facet normal 0.109732 -0.313005 0.943391 + outer loop + vertex 1.52774 0.948268 2.47899 + vertex 1.53194 0.952484 2.4799 + vertex 1.52737 0.952057 2.48029 + endloop + endfacet + facet normal 0.110045 -0.312966 0.943367 + outer loop + vertex 1.52737 0.952057 2.48029 + vertex 1.52261 0.948514 2.47966 + vertex 1.52774 0.948268 2.47899 + endloop + endfacet + facet normal 0.10987 -0.314895 0.942746 + outer loop + vertex 1.52323 0.944075 2.47811 + vertex 1.52774 0.948268 2.47899 + vertex 1.52261 0.948514 2.47966 + endloop + endfacet + facet normal 0.114253 -0.314182 0.942463 + outer loop + vertex 1.52323 0.944075 2.47811 + vertex 1.52261 0.948514 2.47966 + vertex 1.51808 0.943668 2.4786 + endloop + endfacet + facet normal 0.114581 -0.321234 0.940043 + outer loop + vertex 1.51911 0.939888 2.47718 + vertex 1.52323 0.944075 2.47811 + vertex 1.51808 0.943668 2.4786 + endloop + endfacet + facet normal 0.120822 -0.319462 0.939865 + outer loop + vertex 1.51911 0.939888 2.47718 + vertex 1.51808 0.943668 2.4786 + vertex 1.51355 0.938766 2.47751 + endloop + endfacet + facet normal 0.12097 -0.319585 0.939804 + outer loop + vertex 1.51355 0.938766 2.47751 + vertex 1.51808 0.943668 2.4786 + vertex 1.5129 0.943202 2.47911 + endloop + endfacet + facet normal 0.124791 -0.318922 0.93953 + outer loop + vertex 1.51355 0.938766 2.47751 + vertex 1.5129 0.943202 2.47911 + vertex 1.50821 0.93882 2.47824 + endloop + endfacet + facet normal 0.124473 -0.324622 0.937618 + outer loop + vertex 1.51355 0.938766 2.47751 + vertex 1.50821 0.93882 2.47824 + vertex 1.5087 0.935013 2.47686 + endloop + endfacet + facet normal 0.127962 -0.328797 0.935691 + outer loop + vertex 1.51203 0.934832 2.47634 + vertex 1.51355 0.938766 2.47751 + vertex 1.5087 0.935013 2.47686 + endloop + endfacet + facet normal 0.127385 -0.334166 0.933866 + outer loop + vertex 1.51203 0.934832 2.47634 + vertex 1.5087 0.935013 2.47686 + vertex 1.50938 0.932346 2.47581 + endloop + endfacet + facet normal 0.133888 -0.340427 0.93069 + outer loop + vertex 1.51261 0.932091 2.47525 + vertex 1.51203 0.934832 2.47634 + vertex 1.50938 0.932346 2.47581 + endloop + endfacet + facet normal 0.133426 -0.343752 0.929533 + outer loop + vertex 1.50938 0.932346 2.47581 + vertex 1.50786 0.928462 2.47459 + vertex 1.51261 0.932091 2.47525 + endloop + endfacet + facet normal 0.137808 -0.34902 0.926927 + outer loop + vertex 1.51261 0.932091 2.47525 + vertex 1.50786 0.928462 2.47459 + vertex 1.51312 0.928359 2.47377 + endloop + endfacet + facet normal 0.13184 -0.350023 0.927417 + outer loop + vertex 1.51312 0.928359 2.47377 + vertex 1.51728 0.932537 2.47476 + vertex 1.51261 0.932091 2.47525 + endloop + endfacet + facet normal 0.131375 -0.341604 0.930617 + outer loop + vertex 1.51261 0.932091 2.47525 + vertex 1.51728 0.932537 2.47476 + vertex 1.51585 0.935819 2.47617 + endloop + endfacet + facet normal 0.123796 -0.344846 0.93046 + outer loop + vertex 1.51585 0.935819 2.47617 + vertex 1.51728 0.932537 2.47476 + vertex 1.52049 0.936638 2.47585 + endloop + endfacet + facet normal 0.121736 -0.331183 0.93568 + outer loop + vertex 1.52049 0.936638 2.47585 + vertex 1.51911 0.939888 2.47718 + vertex 1.51585 0.935819 2.47617 + endloop + endfacet + facet normal 0.123099 -0.332148 0.93516 + outer loop + vertex 1.51911 0.939888 2.47718 + vertex 1.51355 0.938766 2.47751 + vertex 1.51585 0.935819 2.47617 + endloop + endfacet + facet normal 0.115062 -0.333946 0.935543 + outer loop + vertex 1.52366 0.940305 2.47677 + vertex 1.51911 0.939888 2.47718 + vertex 1.52049 0.936638 2.47585 + endloop + endfacet + facet normal 0.113303 -0.332598 0.936238 + outer loop + vertex 1.52423 0.937532 2.47572 + vertex 1.52366 0.940305 2.47677 + vertex 1.52049 0.936638 2.47585 + endloop + endfacet + facet normal 0.116466 -0.346693 0.93072 + outer loop + vertex 1.52423 0.937532 2.47572 + vertex 1.52049 0.936638 2.47585 + vertex 1.52294 0.933657 2.47443 + endloop + endfacet + facet normal 0.112151 -0.345563 0.93167 + outer loop + vertex 1.52423 0.937532 2.47572 + vertex 1.52294 0.933657 2.47443 + vertex 1.52748 0.937151 2.47518 + endloop + endfacet + facet normal 0.113544 -0.337537 0.934439 + outer loop + vertex 1.52748 0.937151 2.47518 + vertex 1.52683 0.939907 2.47626 + vertex 1.52423 0.937532 2.47572 + endloop + endfacet + facet normal 0.114316 -0.34812 0.930454 + outer loop + vertex 1.52748 0.937151 2.47518 + vertex 1.52294 0.933657 2.47443 + vertex 1.52824 0.933549 2.47374 + endloop + endfacet + facet normal 0.12124 -0.343109 0.931438 + outer loop + vertex 1.51728 0.932537 2.47476 + vertex 1.52294 0.933657 2.47443 + vertex 1.52049 0.936638 2.47585 + endloop + endfacet + facet normal 0.109403 -0.333463 0.936394 + outer loop + vertex 1.52683 0.939907 2.47626 + vertex 1.52366 0.940305 2.47677 + vertex 1.52423 0.937532 2.47572 + endloop + endfacet + facet normal 0.111225 -0.323266 0.939749 + outer loop + vertex 1.52683 0.939907 2.47626 + vertex 1.52839 0.943825 2.47742 + vertex 1.52366 0.940305 2.47677 + endloop + endfacet + facet normal 0.135476 -0.353232 0.925675 + outer loop + vertex 1.51853 0.928454 2.47302 + vertex 1.51728 0.932537 2.47476 + vertex 1.51312 0.928359 2.47377 + endloop + endfacet + facet normal 0.135129 -0.362924 0.921969 + outer loop + vertex 1.51853 0.928454 2.47302 + vertex 1.51312 0.928359 2.47377 + vertex 1.51375 0.924719 2.47225 + endloop + endfacet + facet normal 0.144987 -0.3743 0.915903 + outer loop + vertex 1.5171 0.924561 2.47165 + vertex 1.51853 0.928454 2.47302 + vertex 1.51375 0.924719 2.47225 + endloop + endfacet + facet normal 0.142802 -0.392734 0.908497 + outer loop + vertex 1.5171 0.924561 2.47165 + vertex 1.51375 0.924719 2.47225 + vertex 1.51445 0.922153 2.47103 + endloop + endfacet + facet normal 0.158252 -0.40739 0.899439 + outer loop + vertex 1.51772 0.92194 2.47036 + vertex 1.5171 0.924561 2.47165 + vertex 1.51445 0.922153 2.47103 + endloop + endfacet + facet normal 0.150973 -0.453237 0.878512 + outer loop + vertex 1.51445 0.922153 2.47103 + vertex 1.51317 0.918694 2.46947 + vertex 1.51772 0.92194 2.47036 + endloop + endfacet + facet normal 0.167474 -0.472716 0.865154 + outer loop + vertex 1.51772 0.92194 2.47036 + vertex 1.51317 0.918694 2.46947 + vertex 1.51849 0.918372 2.46826 + endloop + endfacet + facet normal 0.168153 -0.457253 0.873295 + outer loop + vertex 1.51445 0.922153 2.47103 + vertex 1.51074 0.921097 2.47119 + vertex 1.51317 0.918694 2.46947 + endloop + endfacet + facet normal 0.150673 -0.390449 0.908211 + outer loop + vertex 1.51445 0.922153 2.47103 + vertex 1.51375 0.924719 2.47225 + vertex 1.51074 0.921097 2.47119 + endloop + endfacet + facet normal 0.145798 -0.360757 0.921193 + outer loop + vertex 1.51375 0.924719 2.47225 + vertex 1.51312 0.928359 2.47377 + vertex 1.50847 0.923776 2.47271 + endloop + endfacet + facet normal 0.149886 -0.389901 0.908576 + outer loop + vertex 1.51375 0.924719 2.47225 + vertex 1.50847 0.923776 2.47271 + vertex 1.51074 0.921097 2.47119 + endloop + endfacet + facet normal 0.13748 -0.353275 0.925363 + outer loop + vertex 1.50847 0.923776 2.47271 + vertex 1.51312 0.928359 2.47377 + vertex 1.50786 0.928462 2.47459 + endloop + endfacet + facet normal 0.141518 -0.352609 0.925008 + outer loop + vertex 1.50847 0.923776 2.47271 + vertex 1.50786 0.928462 2.47459 + vertex 1.5032 0.923884 2.47356 + endloop + endfacet + facet normal 0.140155 -0.369333 0.918667 + outer loop + vertex 1.50847 0.923776 2.47271 + vertex 1.5032 0.923884 2.47356 + vertex 1.50376 0.920235 2.47201 + endloop + endfacet + facet normal 0.130087 -0.371207 0.919392 + outer loop + vertex 1.50376 0.920235 2.47201 + vertex 1.5032 0.923884 2.47356 + vertex 1.49907 0.919778 2.47249 + endloop + endfacet + facet normal 0.134108 -0.34588 0.928645 + outer loop + vertex 1.5032 0.923884 2.47356 + vertex 1.50786 0.928462 2.47459 + vertex 1.50254 0.927519 2.47501 + endloop + endfacet + facet normal 0.13038 -0.346648 0.92889 + outer loop + vertex 1.50254 0.927519 2.47501 + vertex 1.49776 0.923798 2.47429 + vertex 1.5032 0.923884 2.47356 + endloop + endfacet + facet normal 0.133326 -0.340561 0.930721 + outer loop + vertex 1.50254 0.927519 2.47501 + vertex 1.50786 0.928462 2.47459 + vertex 1.50561 0.931248 2.47593 + endloop + endfacet + facet normal 0.127457 -0.336314 0.933085 + outer loop + vertex 1.50184 0.930156 2.47606 + vertex 1.50254 0.927519 2.47501 + vertex 1.50561 0.931248 2.47593 + endloop + endfacet + facet normal 0.125822 -0.330395 0.935419 + outer loop + vertex 1.50561 0.931248 2.47593 + vertex 1.50342 0.934036 2.47721 + vertex 1.50184 0.930156 2.47606 + endloop + endfacet + facet normal 0.12345 -0.329601 0.936015 + outer loop + vertex 1.50184 0.930156 2.47606 + vertex 1.50342 0.934036 2.47721 + vertex 1.49862 0.930421 2.47657 + endloop + endfacet + facet normal 0.123159 -0.331727 0.935302 + outer loop + vertex 1.50184 0.930156 2.47606 + vertex 1.49862 0.930421 2.47657 + vertex 1.49917 0.92769 2.47553 + endloop + endfacet + facet normal 0.124347 -0.33147 0.935236 + outer loop + vertex 1.5087 0.935013 2.47686 + vertex 1.50342 0.934036 2.47721 + vertex 1.50561 0.931248 2.47593 + endloop + endfacet + facet normal 0.12776 -0.336228 0.933075 + outer loop + vertex 1.50254 0.927519 2.47501 + vertex 1.50184 0.930156 2.47606 + vertex 1.49917 0.92769 2.47553 + endloop + endfacet + facet normal 0.130328 -0.342788 0.930328 + outer loop + vertex 1.50938 0.932346 2.47581 + vertex 1.50561 0.931248 2.47593 + vertex 1.50786 0.928462 2.47459 + endloop + endfacet + facet normal 0.130789 -0.341156 0.930864 + outer loop + vertex 1.51203 0.934832 2.47634 + vertex 1.51261 0.932091 2.47525 + vertex 1.51585 0.935819 2.47617 + endloop + endfacet + facet normal 0.127888 -0.33403 0.933846 + outer loop + vertex 1.50938 0.932346 2.47581 + vertex 1.5087 0.935013 2.47686 + vertex 1.50561 0.931248 2.47593 + endloop + endfacet + facet normal 0.127803 -0.328747 0.935731 + outer loop + vertex 1.51585 0.935819 2.47617 + vertex 1.51355 0.938766 2.47751 + vertex 1.51203 0.934832 2.47634 + endloop + endfacet + facet normal 0.12328 -0.324809 0.937711 + outer loop + vertex 1.5087 0.935013 2.47686 + vertex 1.50821 0.93882 2.47824 + vertex 1.50342 0.934036 2.47721 + endloop + endfacet + facet normal 0.123163 -0.324703 0.937763 + outer loop + vertex 1.50342 0.934036 2.47721 + vertex 1.50821 0.93882 2.47824 + vertex 1.50294 0.938544 2.47884 + endloop + endfacet + facet normal 0.12143 -0.324941 0.937906 + outer loop + vertex 1.50342 0.934036 2.47721 + vertex 1.50294 0.938544 2.47884 + vertex 1.49823 0.934186 2.47794 + endloop + endfacet + facet normal 0.121279 -0.326933 0.937233 + outer loop + vertex 1.50342 0.934036 2.47721 + vertex 1.49823 0.934186 2.47794 + vertex 1.49862 0.930421 2.47657 + endloop + endfacet + facet normal 0.120967 -0.326975 0.937259 + outer loop + vertex 1.49862 0.930421 2.47657 + vertex 1.49823 0.934186 2.47794 + vertex 1.49403 0.929943 2.477 + endloop + endfacet + facet normal 0.118781 -0.32502 0.938218 + outer loop + vertex 1.49403 0.929943 2.477 + vertex 1.49823 0.934186 2.47794 + vertex 1.49302 0.933719 2.47844 + endloop + endfacet + facet normal 0.120554 -0.324527 0.938163 + outer loop + vertex 1.49403 0.929943 2.477 + vertex 1.49302 0.933719 2.47844 + vertex 1.48851 0.928874 2.47734 + endloop + endfacet + facet normal 0.12083 -0.326144 0.937566 + outer loop + vertex 1.49403 0.929943 2.477 + vertex 1.48851 0.928874 2.47734 + vertex 1.4907 0.925888 2.47602 + endloop + endfacet + facet normal 0.123641 -0.328193 0.936484 + outer loop + vertex 1.49534 0.926706 2.47569 + vertex 1.49403 0.929943 2.477 + vertex 1.4907 0.925888 2.47602 + endloop + endfacet + facet normal 0.12539 -0.339892 0.932068 + outer loop + vertex 1.4907 0.925888 2.47602 + vertex 1.49207 0.922649 2.47465 + vertex 1.49534 0.926706 2.47569 + endloop + endfacet + facet normal 0.128644 -0.338532 0.932119 + outer loop + vertex 1.48749 0.922285 2.47515 + vertex 1.49207 0.922649 2.47465 + vertex 1.4907 0.925888 2.47602 + endloop + endfacet + facet normal 0.125484 -0.336039 0.933452 + outer loop + vertex 1.48694 0.92498 2.4762 + vertex 1.48749 0.922285 2.47515 + vertex 1.4907 0.925888 2.47602 + endloop + endfacet + facet normal 0.122946 -0.324696 0.937794 + outer loop + vertex 1.4907 0.925888 2.47602 + vertex 1.48851 0.928874 2.47734 + vertex 1.48694 0.92498 2.4762 + endloop + endfacet + facet normal 0.1184 -0.322724 0.939058 + outer loop + vertex 1.48851 0.928874 2.47734 + vertex 1.49302 0.933719 2.47844 + vertex 1.48787 0.933288 2.47894 + endloop + endfacet + facet normal 0.120222 -0.322413 0.938934 + outer loop + vertex 1.48851 0.928874 2.47734 + vertex 1.48787 0.933288 2.47894 + vertex 1.48337 0.929071 2.47807 + endloop + endfacet + facet normal 0.120218 -0.322454 0.93892 + outer loop + vertex 1.48851 0.928874 2.47734 + vertex 1.48337 0.929071 2.47807 + vertex 1.48379 0.925325 2.47673 + endloop + endfacet + facet normal 0.120133 -0.322466 0.938927 + outer loop + vertex 1.48379 0.925325 2.47673 + vertex 1.48337 0.929071 2.47807 + vertex 1.4792 0.924858 2.47715 + endloop + endfacet + facet normal 0.118767 -0.321242 0.93952 + outer loop + vertex 1.4792 0.924858 2.47715 + vertex 1.48337 0.929071 2.47807 + vertex 1.47817 0.928633 2.47857 + endloop + endfacet + facet normal 0.11829 -0.321377 0.939534 + outer loop + vertex 1.4792 0.924858 2.47715 + vertex 1.47817 0.928633 2.47857 + vertex 1.47361 0.923777 2.47749 + endloop + endfacet + facet normal 0.11514 -0.318707 0.940834 + outer loop + vertex 1.47361 0.923777 2.47749 + vertex 1.47817 0.928633 2.47857 + vertex 1.47296 0.928209 2.47907 + endloop + endfacet + facet normal 0.113912 -0.318915 0.940913 + outer loop + vertex 1.47361 0.923777 2.47749 + vertex 1.47296 0.928209 2.47907 + vertex 1.4684 0.924003 2.47819 + endloop + endfacet + facet normal 0.113335 -0.325432 0.938749 + outer loop + vertex 1.47361 0.923777 2.47749 + vertex 1.4684 0.924003 2.47819 + vertex 1.46882 0.920245 2.47684 + endloop + endfacet + facet normal 0.116843 -0.329822 0.936785 + outer loop + vertex 1.47203 0.919866 2.47631 + vertex 1.47361 0.923777 2.47749 + vertex 1.46882 0.920245 2.47684 + endloop + endfacet + facet normal 0.112538 -0.354293 0.928338 + outer loop + vertex 1.47203 0.919866 2.47631 + vertex 1.46882 0.920245 2.47684 + vertex 1.46939 0.917535 2.47574 + endloop + endfacet + facet normal 0.129177 -0.371012 0.9196 + outer loop + vertex 1.47264 0.917167 2.47513 + vertex 1.47203 0.919866 2.47631 + vertex 1.46939 0.917535 2.47574 + endloop + endfacet + facet normal 0.13028 -0.370741 0.919553 + outer loop + vertex 1.47203 0.919866 2.47631 + vertex 1.47264 0.917167 2.47513 + vertex 1.47586 0.920808 2.47614 + endloop + endfacet + facet normal 0.126683 -0.368005 0.921153 + outer loop + vertex 1.47264 0.917167 2.47513 + vertex 1.47739 0.917721 2.4747 + vertex 1.47586 0.920808 2.47614 + endloop + endfacet + facet normal 0.131554 -0.43236 0.892053 + outer loop + vertex 1.47345 0.91338 2.47318 + vertex 1.47739 0.917721 2.4747 + vertex 1.47264 0.917167 2.47513 + endloop + endfacet + facet normal 0.13243 -0.432156 0.892022 + outer loop + vertex 1.47264 0.917167 2.47513 + vertex 1.46804 0.913927 2.47425 + vertex 1.47345 0.91338 2.47318 + endloop + endfacet + facet normal 0.120403 -0.417451 0.900687 + outer loop + vertex 1.46939 0.917535 2.47574 + vertex 1.46804 0.913927 2.47425 + vertex 1.47264 0.917167 2.47513 + endloop + endfacet + facet normal 0.121877 -0.417844 0.900307 + outer loop + vertex 1.46939 0.917535 2.47574 + vertex 1.46558 0.916683 2.47586 + vertex 1.46804 0.913927 2.47425 + endloop + endfacet + facet normal 0.122154 -0.417632 0.900368 + outer loop + vertex 1.46252 0.912957 2.47454 + vertex 1.46804 0.913927 2.47425 + vertex 1.46558 0.916683 2.47586 + endloop + endfacet + facet normal 0.120797 -0.416728 0.900969 + outer loop + vertex 1.46083 0.915864 2.47612 + vertex 1.46252 0.912957 2.47454 + vertex 1.46558 0.916683 2.47586 + endloop + endfacet + facet normal 0.111881 -0.356505 0.927571 + outer loop + vertex 1.46558 0.916683 2.47586 + vertex 1.46418 0.919834 2.47724 + vertex 1.46083 0.915864 2.47612 + endloop + endfacet + facet normal 0.11242 -0.356898 0.927354 + outer loop + vertex 1.46418 0.919834 2.47724 + vertex 1.45854 0.918787 2.47752 + vertex 1.46083 0.915864 2.47612 + endloop + endfacet + facet normal 0.111979 -0.357212 0.927287 + outer loop + vertex 1.46083 0.915864 2.47612 + vertex 1.45854 0.918787 2.47752 + vertex 1.45689 0.9149 2.47622 + endloop + endfacet + facet normal 0.126268 -0.418545 0.899376 + outer loop + vertex 1.45689 0.9149 2.47622 + vertex 1.45769 0.912319 2.47491 + vertex 1.46083 0.915864 2.47612 + endloop + endfacet + facet normal 0.123742 -0.419319 0.899366 + outer loop + vertex 1.45769 0.912319 2.47491 + vertex 1.45689 0.9149 2.47622 + vertex 1.45423 0.912528 2.47548 + endloop + endfacet + facet normal 0.11514 -0.48014 0.869602 + outer loop + vertex 1.45423 0.912528 2.47548 + vertex 1.45318 0.908754 2.47354 + vertex 1.45769 0.912319 2.47491 + endloop + endfacet + facet normal 0.128984 -0.493916 0.85989 + outer loop + vertex 1.45769 0.912319 2.47491 + vertex 1.45318 0.908754 2.47354 + vertex 1.45912 0.909359 2.47299 + endloop + endfacet + facet normal 0.129706 -0.49361 0.859957 + outer loop + vertex 1.45912 0.909359 2.47299 + vertex 1.46252 0.912957 2.47454 + vertex 1.45769 0.912319 2.47491 + endloop + endfacet + facet normal 0.130675 -0.494293 0.859418 + outer loop + vertex 1.4642 0.909948 2.47256 + vertex 1.46252 0.912957 2.47454 + vertex 1.45912 0.909359 2.47299 + endloop + endfacet + facet normal 0.119959 -0.480921 0.868518 + outer loop + vertex 1.45423 0.912528 2.47548 + vertex 1.45038 0.911767 2.47559 + vertex 1.45318 0.908754 2.47354 + endloop + endfacet + facet normal 0.104798 -0.397976 0.911391 + outer loop + vertex 1.45423 0.912528 2.47548 + vertex 1.45367 0.915297 2.47675 + vertex 1.45038 0.911767 2.47559 + endloop + endfacet + facet normal 0.101925 -0.398581 0.911452 + outer loop + vertex 1.45689 0.9149 2.47622 + vertex 1.45367 0.915297 2.47675 + vertex 1.45423 0.912528 2.47548 + endloop + endfacet + facet normal 0.109832 -0.356483 0.927824 + outer loop + vertex 1.45689 0.9149 2.47622 + vertex 1.45854 0.918787 2.47752 + vertex 1.45367 0.915297 2.47675 + endloop + endfacet + facet normal 0.110927 -0.356911 0.927529 + outer loop + vertex 1.46882 0.920245 2.47684 + vertex 1.46418 0.919834 2.47724 + vertex 1.46558 0.916683 2.47586 + endloop + endfacet + facet normal 0.122517 -0.415827 0.901153 + outer loop + vertex 1.45769 0.912319 2.47491 + vertex 1.46252 0.912957 2.47454 + vertex 1.46083 0.915864 2.47612 + endloop + endfacet + facet normal 0.133209 -0.49308 0.859725 + outer loop + vertex 1.4642 0.909948 2.47256 + vertex 1.46804 0.913927 2.47425 + vertex 1.46252 0.912957 2.47454 + endloop + endfacet + facet normal 0.108697 -0.355142 0.928471 + outer loop + vertex 1.46939 0.917535 2.47574 + vertex 1.46882 0.920245 2.47684 + vertex 1.46558 0.916683 2.47586 + endloop + endfacet + facet normal 0.122837 -0.42597 0.89636 + outer loop + vertex 1.4792 0.914549 2.47295 + vertex 1.47739 0.917721 2.4747 + vertex 1.47345 0.91338 2.47318 + endloop + endfacet + facet normal 0.132383 -0.421056 0.897322 + outer loop + vertex 1.4792 0.914549 2.47295 + vertex 1.48299 0.918933 2.47444 + vertex 1.47739 0.917721 2.4747 + endloop + endfacet + facet normal 0.121338 -0.364416 0.923298 + outer loop + vertex 1.47739 0.917721 2.4747 + vertex 1.48299 0.918933 2.47444 + vertex 1.48055 0.92168 2.47585 + endloop + endfacet + facet normal 0.126631 -0.36803 0.921151 + outer loop + vertex 1.47586 0.920808 2.47614 + vertex 1.47739 0.917721 2.4747 + vertex 1.48055 0.92168 2.47585 + endloop + endfacet + facet normal 0.120962 -0.332698 0.935244 + outer loop + vertex 1.48055 0.92168 2.47585 + vertex 1.4792 0.924858 2.47715 + vertex 1.47586 0.920808 2.47614 + endloop + endfacet + facet normal 0.120123 -0.332087 0.935569 + outer loop + vertex 1.4792 0.924858 2.47715 + vertex 1.47361 0.923777 2.47749 + vertex 1.47586 0.920808 2.47614 + endloop + endfacet + facet normal 0.120836 -0.33275 0.935241 + outer loop + vertex 1.48379 0.925325 2.47673 + vertex 1.4792 0.924858 2.47715 + vertex 1.48055 0.92168 2.47585 + endloop + endfacet + facet normal 0.121265 -0.331283 0.935706 + outer loop + vertex 1.47586 0.920808 2.47614 + vertex 1.47361 0.923777 2.47749 + vertex 1.47203 0.919866 2.47631 + endloop + endfacet + facet normal 0.109173 -0.326006 0.939043 + outer loop + vertex 1.46882 0.920245 2.47684 + vertex 1.4684 0.924003 2.47819 + vertex 1.46418 0.919834 2.47724 + endloop + endfacet + facet normal 0.111018 -0.327691 0.93824 + outer loop + vertex 1.46418 0.919834 2.47724 + vertex 1.4684 0.924003 2.47819 + vertex 1.46318 0.923601 2.47867 + endloop + endfacet + facet normal 0.10772 -0.328592 0.938309 + outer loop + vertex 1.46418 0.919834 2.47724 + vertex 1.46318 0.923601 2.47867 + vertex 1.45854 0.918787 2.47752 + endloop + endfacet + facet normal 0.11217 -0.332437 0.936431 + outer loop + vertex 1.45854 0.918787 2.47752 + vertex 1.46318 0.923601 2.47867 + vertex 1.45801 0.923187 2.47914 + endloop + endfacet + facet normal 0.110406 -0.332692 0.93655 + outer loop + vertex 1.45854 0.918787 2.47752 + vertex 1.45801 0.923187 2.47914 + vertex 1.4534 0.919062 2.47822 + endloop + endfacet + facet normal 0.108185 -0.354405 0.928813 + outer loop + vertex 1.45854 0.918787 2.47752 + vertex 1.4534 0.919062 2.47822 + vertex 1.45367 0.915297 2.47675 + endloop + endfacet + facet normal 0.106621 -0.354565 0.928933 + outer loop + vertex 1.45367 0.915297 2.47675 + vertex 1.4534 0.919062 2.47822 + vertex 1.44917 0.915088 2.47719 + endloop + endfacet + facet normal 0.106912 -0.399628 0.910422 + outer loop + vertex 1.45367 0.915297 2.47675 + vertex 1.44917 0.915088 2.47719 + vertex 1.45038 0.911767 2.47559 + endloop + endfacet + facet normal 0.115312 -0.396692 0.91068 + outer loop + vertex 1.45038 0.911767 2.47559 + vertex 1.44917 0.915088 2.47719 + vertex 1.44559 0.911269 2.47598 + endloop + endfacet + facet normal 0.119492 -0.4616 0.879003 + outer loop + vertex 1.44559 0.911269 2.47598 + vertex 1.44732 0.908194 2.47413 + vertex 1.45038 0.911767 2.47559 + endloop + endfacet + facet normal 0.13352 -0.470772 0.872093 + outer loop + vertex 1.44732 0.908194 2.47413 + vertex 1.45318 0.908754 2.47354 + vertex 1.45038 0.911767 2.47559 + endloop + endfacet + facet normal 0.108939 -0.356745 0.927828 + outer loop + vertex 1.44917 0.915088 2.47719 + vertex 1.4534 0.919062 2.47822 + vertex 1.44833 0.918847 2.47873 + endloop + endfacet + facet normal 0.107109 -0.357172 0.927877 + outer loop + vertex 1.44917 0.915088 2.47719 + vertex 1.44833 0.918847 2.47873 + vertex 1.44413 0.91465 2.4776 + endloop + endfacet + facet normal 0.106254 -0.356422 0.928264 + outer loop + vertex 1.44413 0.91465 2.4776 + vertex 1.44833 0.918847 2.47873 + vertex 1.44287 0.918741 2.47932 + endloop + endfacet + facet normal 0.10379 -0.357178 0.928252 + outer loop + vertex 1.44413 0.91465 2.4776 + vertex 1.44287 0.918741 2.47932 + vertex 1.43837 0.913604 2.47784 + endloop + endfacet + facet normal 0.102992 -0.356572 0.928574 + outer loop + vertex 1.43837 0.913604 2.47784 + vertex 1.44287 0.918741 2.47932 + vertex 1.43709 0.917669 2.47955 + endloop + endfacet + facet normal 0.102165 -0.35683 0.928566 + outer loop + vertex 1.43837 0.913604 2.47784 + vertex 1.43709 0.917669 2.47955 + vertex 1.43316 0.913696 2.47845 + endloop + endfacet + facet normal 0.100875 -0.355711 0.929136 + outer loop + vertex 1.43316 0.913696 2.47845 + vertex 1.43709 0.917669 2.47955 + vertex 1.43217 0.917269 2.47993 + endloop + endfacet + facet normal 0.102055 -0.355383 0.929133 + outer loop + vertex 1.43316 0.913696 2.47845 + vertex 1.43217 0.917269 2.47993 + vertex 1.42832 0.913518 2.47892 + endloop + endfacet + facet normal 0.10202 -0.380838 0.918996 + outer loop + vertex 1.42931 0.909973 2.47734 + vertex 1.43316 0.913696 2.47845 + vertex 1.42832 0.913518 2.47892 + endloop + endfacet + facet normal 0.107025 -0.379439 0.919006 + outer loop + vertex 1.42931 0.909973 2.47734 + vertex 1.42832 0.913518 2.47892 + vertex 1.42431 0.90956 2.47775 + endloop + endfacet + facet normal 0.10228 -0.355586 0.92903 + outer loop + vertex 1.42832 0.913518 2.47892 + vertex 1.43217 0.917269 2.47993 + vertex 1.42777 0.917032 2.48032 + endloop + endfacet + facet normal 0.102933 -0.355473 0.929001 + outer loop + vertex 1.42777 0.917032 2.48032 + vertex 1.42312 0.913599 2.47952 + vertex 1.42832 0.913518 2.47892 + endloop + endfacet + facet normal 0.100984 -0.353093 0.930122 + outer loop + vertex 1.42461 0.91743 2.48082 + vertex 1.42312 0.913599 2.47952 + vertex 1.42777 0.917032 2.48032 + endloop + endfacet + facet normal 0.102958 -0.342179 0.933977 + outer loop + vertex 1.42777 0.917032 2.48032 + vertex 1.42723 0.919791 2.48139 + vertex 1.42461 0.91743 2.48082 + endloop + endfacet + facet normal 0.0992807 -0.338517 0.935708 + outer loop + vertex 1.42723 0.919791 2.48139 + vertex 1.424 0.92019 2.48188 + vertex 1.42461 0.91743 2.48082 + endloop + endfacet + facet normal 0.0977386 -0.338871 0.935742 + outer loop + vertex 1.42461 0.91743 2.48082 + vertex 1.424 0.92019 2.48188 + vertex 1.42076 0.916558 2.4809 + endloop + endfacet + facet normal 0.0989593 -0.339833 0.935265 + outer loop + vertex 1.424 0.92019 2.48188 + vertex 1.41932 0.919774 2.48222 + vertex 1.42076 0.916558 2.4809 + endloop + endfacet + facet normal 0.098734 -0.339929 0.935254 + outer loop + vertex 1.42076 0.916558 2.4809 + vertex 1.41932 0.919774 2.48222 + vertex 1.41599 0.915813 2.48114 + endloop + endfacet + facet normal 0.100215 -0.350711 0.931106 + outer loop + vertex 1.41599 0.915813 2.48114 + vertex 1.41739 0.912565 2.47976 + vertex 1.42076 0.916558 2.4809 + endloop + endfacet + facet normal 0.102117 -0.352104 0.930373 + outer loop + vertex 1.41739 0.912565 2.47976 + vertex 1.42312 0.913599 2.47952 + vertex 1.42076 0.916558 2.4809 + endloop + endfacet + facet normal 0.105055 -0.370063 0.923048 + outer loop + vertex 1.41855 0.908559 2.47802 + vertex 1.42312 0.913599 2.47952 + vertex 1.41739 0.912565 2.47976 + endloop + endfacet + facet normal 0.109042 -0.368911 0.923046 + outer loop + vertex 1.41855 0.908559 2.47802 + vertex 1.41739 0.912565 2.47976 + vertex 1.41324 0.90866 2.47869 + endloop + endfacet + facet normal 0.103431 -0.363687 0.925761 + outer loop + vertex 1.41324 0.90866 2.47869 + vertex 1.41739 0.912565 2.47976 + vertex 1.41266 0.912222 2.48016 + endloop + endfacet + facet normal 0.107248 -0.363003 0.925595 + outer loop + vertex 1.41266 0.912222 2.48016 + vertex 1.40791 0.90874 2.47934 + vertex 1.41324 0.90866 2.47869 + endloop + endfacet + facet normal 0.10198 -0.356539 0.928698 + outer loop + vertex 1.4094 0.912593 2.48066 + vertex 1.40791 0.90874 2.47934 + vertex 1.41266 0.912222 2.48016 + endloop + endfacet + facet normal 0.103432 -0.34795 0.93179 + outer loop + vertex 1.41266 0.912222 2.48016 + vertex 1.41211 0.914958 2.48124 + vertex 1.4094 0.912593 2.48066 + endloop + endfacet + facet normal 0.100776 -0.345226 0.933093 + outer loop + vertex 1.41211 0.914958 2.48124 + vertex 1.4089 0.915345 2.48173 + vertex 1.4094 0.912593 2.48066 + endloop + endfacet + facet normal 0.104438 -0.344506 0.932957 + outer loop + vertex 1.4094 0.912593 2.48066 + vertex 1.4089 0.915345 2.48173 + vertex 1.40555 0.911688 2.48075 + endloop + endfacet + facet normal 0.104321 -0.344411 0.933005 + outer loop + vertex 1.4089 0.915345 2.48173 + vertex 1.40426 0.914927 2.48209 + vertex 1.40555 0.911688 2.48075 + endloop + endfacet + facet normal 0.10957 -0.34238 0.933151 + outer loop + vertex 1.40555 0.911688 2.48075 + vertex 1.40426 0.914927 2.48209 + vertex 1.40084 0.910894 2.48102 + endloop + endfacet + facet normal 0.111543 -0.35585 0.927862 + outer loop + vertex 1.40084 0.910894 2.48102 + vertex 1.4022 0.907657 2.47961 + vertex 1.40555 0.911688 2.48075 + endloop + endfacet + facet normal 0.111197 -0.355601 0.928 + outer loop + vertex 1.4022 0.907657 2.47961 + vertex 1.40791 0.90874 2.47934 + vertex 1.40555 0.911688 2.48075 + endloop + endfacet + facet normal 0.116233 -0.38528 0.91545 + outer loop + vertex 1.40339 0.90368 2.47779 + vertex 1.40791 0.90874 2.47934 + vertex 1.4022 0.907657 2.47961 + endloop + endfacet + facet normal 0.125853 -0.382379 0.915395 + outer loop + vertex 1.40339 0.90368 2.47779 + vertex 1.4022 0.907657 2.47961 + vertex 1.39817 0.903791 2.47855 + endloop + endfacet + facet normal 0.122922 -0.417266 0.900433 + outer loop + vertex 1.40339 0.90368 2.47779 + vertex 1.39817 0.903791 2.47855 + vertex 1.39882 0.900357 2.47687 + endloop + endfacet + facet normal 0.123945 -0.417052 0.900391 + outer loop + vertex 1.39882 0.900357 2.47687 + vertex 1.39817 0.903791 2.47855 + vertex 1.39435 0.900136 2.47738 + endloop + endfacet + facet normal 0.118916 -0.412655 0.903092 + outer loop + vertex 1.39435 0.900136 2.47738 + vertex 1.39817 0.903791 2.47855 + vertex 1.3931 0.903962 2.47929 + endloop + endfacet + facet normal 0.132631 -0.408233 0.903191 + outer loop + vertex 1.39435 0.900136 2.47738 + vertex 1.3931 0.903962 2.47929 + vertex 1.38929 0.899514 2.47784 + endloop + endfacet + facet normal 0.134119 -0.409282 0.902497 + outer loop + vertex 1.38929 0.899514 2.47784 + vertex 1.3931 0.903962 2.47929 + vertex 1.38756 0.902796 2.47959 + endloop + endfacet + facet normal 0.143424 -0.404726 0.90312 + outer loop + vertex 1.38929 0.899514 2.47784 + vertex 1.38756 0.902796 2.47959 + vertex 1.38356 0.898339 2.47823 + endloop + endfacet + facet normal 0.155701 -0.47685 0.865085 + outer loop + vertex 1.38929 0.899514 2.47784 + vertex 1.38356 0.898339 2.47823 + vertex 1.38625 0.895678 2.47628 + endloop + endfacet + facet normal 0.159273 -0.478943 0.863276 + outer loop + vertex 1.39124 0.896476 2.4758 + vertex 1.38929 0.899514 2.47784 + vertex 1.38625 0.895678 2.47628 + endloop + endfacet + facet normal 0.169983 -0.59031 0.789075 + outer loop + vertex 1.38625 0.895678 2.47628 + vertex 1.38829 0.892806 2.47369 + vertex 1.39124 0.896476 2.4758 + endloop + endfacet + facet normal 0.173945 -0.461865 0.869726 + outer loop + vertex 1.38625 0.895678 2.47628 + vertex 1.38356 0.898339 2.47823 + vertex 1.3823 0.894767 2.47658 + endloop + endfacet + facet normal 0.193468 -0.570302 0.798327 + outer loop + vertex 1.3823 0.894767 2.47658 + vertex 1.38325 0.8926 2.4748 + vertex 1.38625 0.895678 2.47628 + endloop + endfacet + facet normal 0.199361 -0.574048 0.794181 + outer loop + vertex 1.38325 0.8926 2.4748 + vertex 1.38829 0.892806 2.47369 + vertex 1.38625 0.895678 2.47628 + endloop + endfacet + facet normal 0.139505 -0.401797 0.90504 + outer loop + vertex 1.38356 0.898339 2.47823 + vertex 1.38756 0.902796 2.47959 + vertex 1.38282 0.902232 2.48007 + endloop + endfacet + facet normal 0.153533 -0.3987 0.904138 + outer loop + vertex 1.38282 0.902232 2.48007 + vertex 1.37807 0.898671 2.47931 + vertex 1.38356 0.898339 2.47823 + endloop + endfacet + facet normal 0.14726 -0.441128 0.88528 + outer loop + vertex 1.38356 0.898339 2.47823 + vertex 1.37807 0.898671 2.47931 + vertex 1.37887 0.894931 2.47731 + endloop + endfacet + facet normal 0.163016 -0.459536 0.873071 + outer loop + vertex 1.3823 0.894767 2.47658 + vertex 1.38356 0.898339 2.47823 + vertex 1.37887 0.894931 2.47731 + endloop + endfacet + facet normal 0.151317 -0.530638 0.833982 + outer loop + vertex 1.3823 0.894767 2.47658 + vertex 1.37887 0.894931 2.47731 + vertex 1.37989 0.892687 2.4757 + endloop + endfacet + facet normal 0.15449 -0.439383 0.884915 + outer loop + vertex 1.37887 0.894931 2.47731 + vertex 1.37807 0.898671 2.47931 + vertex 1.37355 0.893925 2.47774 + endloop + endfacet + facet normal 0.169821 -0.4511 0.876168 + outer loop + vertex 1.37355 0.893925 2.47774 + vertex 1.37807 0.898671 2.47931 + vertex 1.37268 0.897597 2.4798 + endloop + endfacet + facet normal 0.178474 -0.448761 0.875649 + outer loop + vertex 1.37268 0.897597 2.4798 + vertex 1.36805 0.894153 2.47898 + vertex 1.37355 0.893925 2.47774 + endloop + endfacet + facet normal 0.165339 -0.433545 0.885834 + outer loop + vertex 1.36929 0.897734 2.4805 + vertex 1.36805 0.894153 2.47898 + vertex 1.37268 0.897597 2.4798 + endloop + endfacet + facet normal 0.171475 -0.434884 0.884009 + outer loop + vertex 1.36929 0.897734 2.4805 + vertex 1.36554 0.896749 2.48074 + vertex 1.36805 0.894153 2.47898 + endloop + endfacet + facet normal 0.175285 -0.43174 0.884803 + outer loop + vertex 1.36264 0.893009 2.47949 + vertex 1.36805 0.894153 2.47898 + vertex 1.36554 0.896749 2.48074 + endloop + endfacet + facet normal 0.188631 -0.517325 0.834742 + outer loop + vertex 1.36453 0.890272 2.47737 + vertex 1.36805 0.894153 2.47898 + vertex 1.36264 0.893009 2.47949 + endloop + endfacet + facet normal 0.188915 -0.517159 0.83478 + outer loop + vertex 1.36453 0.890272 2.47737 + vertex 1.36264 0.893009 2.47949 + vertex 1.3596 0.889506 2.47801 + endloop + endfacet + facet normal 0.182893 -0.513598 0.838312 + outer loop + vertex 1.36917 0.890712 2.47662 + vertex 1.36805 0.894153 2.47898 + vertex 1.36453 0.890272 2.47737 + endloop + endfacet + facet normal 0.167178 -0.51876 0.838415 + outer loop + vertex 1.37355 0.893925 2.47774 + vertex 1.36805 0.894153 2.47898 + vertex 1.36917 0.890712 2.47662 + endloop + endfacet + facet normal 0.156741 -0.371206 0.915226 + outer loop + vertex 1.36929 0.897734 2.4805 + vertex 1.36876 0.900418 2.48168 + vertex 1.36554 0.896749 2.48074 + endloop + endfacet + facet normal 0.153789 -0.371885 0.915451 + outer loop + vertex 1.37193 0.900191 2.48105 + vertex 1.36876 0.900418 2.48168 + vertex 1.36929 0.897734 2.4805 + endloop + endfacet + facet normal 0.171215 -0.388391 0.905449 + outer loop + vertex 1.37268 0.897597 2.4798 + vertex 1.37193 0.900191 2.48105 + vertex 1.36929 0.897734 2.4805 + endloop + endfacet + facet normal 0.156842 -0.350713 0.923256 + outer loop + vertex 1.37193 0.900191 2.48105 + vertex 1.37358 0.904103 2.48226 + vertex 1.36876 0.900418 2.48168 + endloop + endfacet + facet normal 0.159786 -0.385928 0.908586 + outer loop + vertex 1.37268 0.897597 2.4798 + vertex 1.37807 0.898671 2.47931 + vertex 1.37573 0.90136 2.48086 + endloop + endfacet + facet normal 0.165872 -0.390061 0.905726 + outer loop + vertex 1.37193 0.900191 2.48105 + vertex 1.37268 0.897597 2.4798 + vertex 1.37573 0.90136 2.48086 + endloop + endfacet + facet normal 0.154452 -0.349922 0.923958 + outer loop + vertex 1.37573 0.90136 2.48086 + vertex 1.37358 0.904103 2.48226 + vertex 1.37193 0.900191 2.48105 + endloop + endfacet + facet normal 0.14723 -0.355169 0.923135 + outer loop + vertex 1.37885 0.905149 2.48182 + vertex 1.37358 0.904103 2.48226 + vertex 1.37573 0.90136 2.48086 + endloop + endfacet + facet normal 0.146117 -0.354377 0.923616 + outer loop + vertex 1.37953 0.902507 2.4807 + vertex 1.37885 0.905149 2.48182 + vertex 1.37573 0.90136 2.48086 + endloop + endfacet + facet normal 0.15591 -0.388943 0.907973 + outer loop + vertex 1.37953 0.902507 2.4807 + vertex 1.37573 0.90136 2.48086 + vertex 1.37807 0.898671 2.47931 + endloop + endfacet + facet normal 0.142118 -0.385118 0.911859 + outer loop + vertex 1.37953 0.902507 2.4807 + vertex 1.37807 0.898671 2.47931 + vertex 1.38282 0.902232 2.48007 + endloop + endfacet + facet normal 0.126103 -0.366316 0.921906 + outer loop + vertex 1.38756 0.902796 2.47959 + vertex 1.3931 0.903962 2.47929 + vertex 1.39068 0.906782 2.48075 + endloop + endfacet + facet normal 0.122634 -0.368987 0.921309 + outer loop + vertex 1.39441 0.907662 2.4806 + vertex 1.39068 0.906782 2.48075 + vertex 1.3931 0.903962 2.47929 + endloop + endfacet + facet normal 0.116202 -0.367256 0.922833 + outer loop + vertex 1.39441 0.907662 2.4806 + vertex 1.3931 0.903962 2.47929 + vertex 1.39758 0.907298 2.48006 + endloop + endfacet + facet normal 0.118968 -0.351701 0.928522 + outer loop + vertex 1.39758 0.907298 2.48006 + vertex 1.39702 0.910002 2.48115 + vertex 1.39441 0.907662 2.4806 + endloop + endfacet + facet normal 0.114479 -0.347217 0.930771 + outer loop + vertex 1.39702 0.910002 2.48115 + vertex 1.39388 0.910388 2.48168 + vertex 1.39441 0.907662 2.4806 + endloop + endfacet + facet normal 0.115743 -0.340249 0.933185 + outer loop + vertex 1.39702 0.910002 2.48115 + vertex 1.39865 0.913886 2.48237 + vertex 1.39388 0.910388 2.48168 + endloop + endfacet + facet normal 0.112336 -0.335983 0.935145 + outer loop + vertex 1.39865 0.913886 2.48237 + vertex 1.39348 0.914115 2.48307 + vertex 1.39388 0.910388 2.48168 + endloop + endfacet + facet normal 0.118384 -0.335173 0.93469 + outer loop + vertex 1.39388 0.910388 2.48168 + vertex 1.39348 0.914115 2.48307 + vertex 1.38932 0.909977 2.48211 + endloop + endfacet + facet normal 0.117969 -0.334798 0.934876 + outer loop + vertex 1.38932 0.909977 2.48211 + vertex 1.39348 0.914115 2.48307 + vertex 1.38831 0.913706 2.48358 + endloop + endfacet + facet normal 0.125133 -0.33278 0.934665 + outer loop + vertex 1.38932 0.909977 2.48211 + vertex 1.38831 0.913706 2.48358 + vertex 1.38374 0.908876 2.48247 + endloop + endfacet + facet normal 0.127597 -0.347061 0.929122 + outer loop + vertex 1.38932 0.909977 2.48211 + vertex 1.38374 0.908876 2.48247 + vertex 1.38603 0.905963 2.48107 + endloop + endfacet + facet normal 0.124932 -0.345161 0.930191 + outer loop + vertex 1.39068 0.906782 2.48075 + vertex 1.38932 0.909977 2.48211 + vertex 1.38603 0.905963 2.48107 + endloop + endfacet + facet normal 0.128286 -0.367767 0.921027 + outer loop + vertex 1.38603 0.905963 2.48107 + vertex 1.38756 0.902796 2.47959 + vertex 1.39068 0.906782 2.48075 + endloop + endfacet + facet normal 0.136653 -0.363888 0.921364 + outer loop + vertex 1.38282 0.902232 2.48007 + vertex 1.38756 0.902796 2.47959 + vertex 1.38603 0.905963 2.48107 + endloop + endfacet + facet normal 0.137238 -0.364322 0.921105 + outer loop + vertex 1.38219 0.904984 2.48125 + vertex 1.38282 0.902232 2.48007 + vertex 1.38603 0.905963 2.48107 + endloop + endfacet + facet normal 0.132373 -0.34359 0.929744 + outer loop + vertex 1.38603 0.905963 2.48107 + vertex 1.38374 0.908876 2.48247 + vertex 1.38219 0.904984 2.48125 + endloop + endfacet + facet normal 0.125239 -0.33287 0.934619 + outer loop + vertex 1.38374 0.908876 2.48247 + vertex 1.38831 0.913706 2.48358 + vertex 1.38314 0.913245 2.48411 + endloop + endfacet + facet normal 0.13499 -0.331242 0.933839 + outer loop + vertex 1.38374 0.908876 2.48247 + vertex 1.38314 0.913245 2.48411 + vertex 1.37842 0.90891 2.48325 + endloop + endfacet + facet normal 0.134549 -0.33886 0.931166 + outer loop + vertex 1.38374 0.908876 2.48247 + vertex 1.37842 0.90891 2.48325 + vertex 1.37885 0.905149 2.48182 + endloop + endfacet + facet normal 0.140606 -0.34618 0.927572 + outer loop + vertex 1.38219 0.904984 2.48125 + vertex 1.38374 0.908876 2.48247 + vertex 1.37885 0.905149 2.48182 + endloop + endfacet + facet normal 0.13949 -0.356219 0.923932 + outer loop + vertex 1.38219 0.904984 2.48125 + vertex 1.37885 0.905149 2.48182 + vertex 1.37953 0.902507 2.4807 + endloop + endfacet + facet normal 0.14571 -0.362174 0.920651 + outer loop + vertex 1.38282 0.902232 2.48007 + vertex 1.38219 0.904984 2.48125 + vertex 1.37953 0.902507 2.4807 + endloop + endfacet + facet normal 0.144288 -0.337402 0.930237 + outer loop + vertex 1.37885 0.905149 2.48182 + vertex 1.37842 0.90891 2.48325 + vertex 1.37358 0.904103 2.48226 + endloop + endfacet + facet normal 0.140362 -0.33384 0.932121 + outer loop + vertex 1.37358 0.904103 2.48226 + vertex 1.37842 0.90891 2.48325 + vertex 1.37322 0.908591 2.48392 + endloop + endfacet + facet normal 0.148562 -0.332836 0.931209 + outer loop + vertex 1.37358 0.904103 2.48226 + vertex 1.37322 0.908591 2.48392 + vertex 1.36847 0.904196 2.48311 + endloop + endfacet + facet normal 0.148014 -0.340017 0.928698 + outer loop + vertex 1.37358 0.904103 2.48226 + vertex 1.36847 0.904196 2.48311 + vertex 1.36876 0.900418 2.48168 + endloop + endfacet + facet normal 0.152796 -0.339443 0.928134 + outer loop + vertex 1.36876 0.900418 2.48168 + vertex 1.36847 0.904196 2.48311 + vertex 1.36423 0.899905 2.48223 + endloop + endfacet + facet normal 0.149104 -0.336155 0.929929 + outer loop + vertex 1.36423 0.899905 2.48223 + vertex 1.36847 0.904196 2.48311 + vertex 1.36333 0.903743 2.48377 + endloop + endfacet + facet normal 0.154307 -0.334799 0.929569 + outer loop + vertex 1.36423 0.899905 2.48223 + vertex 1.36333 0.903743 2.48377 + vertex 1.35866 0.898766 2.48275 + endloop + endfacet + facet normal 0.159135 -0.363722 0.917814 + outer loop + vertex 1.36423 0.899905 2.48223 + vertex 1.35866 0.898766 2.48275 + vertex 1.36096 0.895838 2.48119 + endloop + endfacet + facet normal 0.162878 -0.366298 0.916131 + outer loop + vertex 1.36554 0.896749 2.48074 + vertex 1.36423 0.899905 2.48223 + vertex 1.36096 0.895838 2.48119 + endloop + endfacet + facet normal 0.172609 -0.430106 0.886124 + outer loop + vertex 1.36096 0.895838 2.48119 + vertex 1.36264 0.893009 2.47949 + vertex 1.36554 0.896749 2.48074 + endloop + endfacet + facet normal 0.178263 -0.426979 0.886516 + outer loop + vertex 1.35801 0.892239 2.48005 + vertex 1.36264 0.893009 2.47949 + vertex 1.36096 0.895838 2.48119 + endloop + endfacet + facet normal 0.149984 -0.331148 0.931582 + outer loop + vertex 1.35866 0.898766 2.48275 + vertex 1.36333 0.903743 2.48377 + vertex 1.35801 0.903611 2.48458 + endloop + endfacet + facet normal 0.157851 -0.329787 0.930765 + outer loop + vertex 1.35866 0.898766 2.48275 + vertex 1.35801 0.903611 2.48458 + vertex 1.35328 0.898738 2.48365 + endloop + endfacet + facet normal 0.1568 -0.349015 0.923906 + outer loop + vertex 1.35866 0.898766 2.48275 + vertex 1.35328 0.898738 2.48365 + vertex 1.35381 0.894898 2.48211 + endloop + endfacet + facet normal 0.163281 -0.34785 0.923222 + outer loop + vertex 1.35381 0.894898 2.48211 + vertex 1.35328 0.898738 2.48365 + vertex 1.34852 0.893927 2.48268 + endloop + endfacet + facet normal 0.160913 -0.34575 0.924426 + outer loop + vertex 1.34852 0.893927 2.48268 + vertex 1.35328 0.898738 2.48365 + vertex 1.34798 0.898682 2.48455 + endloop + endfacet + facet normal 0.174205 -0.343606 0.922815 + outer loop + vertex 1.34852 0.893927 2.48268 + vertex 1.34798 0.898682 2.48455 + vertex 1.34336 0.893973 2.48367 + endloop + endfacet + facet normal 0.172908 -0.342458 0.923485 + outer loop + vertex 1.34336 0.893973 2.48367 + vertex 1.34798 0.898682 2.48455 + vertex 1.3428 0.897575 2.48511 + endloop + endfacet + facet normal 0.174905 -0.342057 0.923258 + outer loop + vertex 1.3428 0.897575 2.48511 + vertex 1.33817 0.893741 2.48457 + vertex 1.34336 0.893973 2.48367 + endloop + endfacet + facet normal 0.171839 -0.33862 0.925099 + outer loop + vertex 1.33954 0.897581 2.48572 + vertex 1.33817 0.893741 2.48457 + vertex 1.3428 0.897575 2.48511 + endloop + endfacet + facet normal 0.17322 -0.31751 0.932299 + outer loop + vertex 1.3428 0.897575 2.48511 + vertex 1.3421 0.900159 2.48612 + vertex 1.33954 0.897581 2.48572 + endloop + endfacet + facet normal 0.168411 -0.31311 0.934666 + outer loop + vertex 1.3421 0.900159 2.48612 + vertex 1.33885 0.90019 2.48672 + vertex 1.33954 0.897581 2.48572 + endloop + endfacet + facet normal 0.17065 -0.312445 0.934482 + outer loop + vertex 1.33954 0.897581 2.48572 + vertex 1.33885 0.90019 2.48672 + vertex 1.33589 0.896331 2.48597 + endloop + endfacet + facet normal 0.166327 -0.309467 0.936251 + outer loop + vertex 1.33885 0.90019 2.48672 + vertex 1.33367 0.899047 2.48726 + vertex 1.33589 0.896331 2.48597 + endloop + endfacet + facet normal 0.169831 -0.30674 0.936519 + outer loop + vertex 1.33589 0.896331 2.48597 + vertex 1.33367 0.899047 2.48726 + vertex 1.3322 0.895091 2.48623 + endloop + endfacet + facet normal 0.180458 -0.34123 0.922495 + outer loop + vertex 1.3322 0.895091 2.48623 + vertex 1.33296 0.8925 2.48512 + vertex 1.33589 0.896331 2.48597 + endloop + endfacet + facet normal 0.179576 -0.340643 0.922884 + outer loop + vertex 1.33296 0.8925 2.48512 + vertex 1.33817 0.893741 2.48457 + vertex 1.33589 0.896331 2.48597 + endloop + endfacet + facet normal 0.179847 -0.341429 0.922541 + outer loop + vertex 1.33296 0.8925 2.48512 + vertex 1.3322 0.895091 2.48623 + vertex 1.32965 0.892563 2.48579 + endloop + endfacet + facet normal 0.16121 -0.324254 0.932132 + outer loop + vertex 1.3322 0.895091 2.48623 + vertex 1.3289 0.895157 2.48683 + vertex 1.32965 0.892563 2.48579 + endloop + endfacet + facet normal 0.162741 -0.304613 0.93847 + outer loop + vertex 1.3322 0.895091 2.48623 + vertex 1.33367 0.899047 2.48726 + vertex 1.3289 0.895157 2.48683 + endloop + endfacet + facet normal 0.161075 -0.302669 0.939386 + outer loop + vertex 1.33367 0.899047 2.48726 + vertex 1.32841 0.899011 2.48815 + vertex 1.3289 0.895157 2.48683 + endloop + endfacet + facet normal 0.157824 -0.303208 0.939764 + outer loop + vertex 1.3289 0.895157 2.48683 + vertex 1.32841 0.899011 2.48815 + vertex 1.32362 0.894016 2.48734 + endloop + endfacet + facet normal 0.163739 -0.308441 0.937045 + outer loop + vertex 1.32362 0.894016 2.48734 + vertex 1.32841 0.899011 2.48815 + vertex 1.32321 0.898612 2.48893 + endloop + endfacet + facet normal 0.16629 -0.308096 0.936709 + outer loop + vertex 1.32362 0.894016 2.48734 + vertex 1.32321 0.898612 2.48893 + vertex 1.31834 0.893951 2.48826 + endloop + endfacet + facet normal 0.165301 -0.329802 0.929466 + outer loop + vertex 1.32362 0.894016 2.48734 + vertex 1.31834 0.893951 2.48826 + vertex 1.31872 0.890091 2.48682 + endloop + endfacet + facet normal 0.170395 -0.329055 0.92881 + outer loop + vertex 1.31872 0.890091 2.48682 + vertex 1.31834 0.893951 2.48826 + vertex 1.31348 0.889017 2.4874 + endloop + endfacet + facet normal 0.178817 -0.382235 0.906598 + outer loop + vertex 1.31872 0.890091 2.48682 + vertex 1.31348 0.889017 2.4874 + vertex 1.31576 0.886311 2.48581 + endloop + endfacet + facet normal 0.167428 -0.374721 0.911895 + outer loop + vertex 1.31957 0.887499 2.4856 + vertex 1.31872 0.890091 2.48682 + vertex 1.31576 0.886311 2.48581 + endloop + endfacet + facet normal 0.194222 -0.469565 0.86127 + outer loop + vertex 1.31957 0.887499 2.4856 + vertex 1.31576 0.886311 2.48581 + vertex 1.31864 0.883754 2.48377 + endloop + endfacet + facet normal 0.177008 -0.467618 0.866026 + outer loop + vertex 1.31957 0.887499 2.4856 + vertex 1.31864 0.883754 2.48377 + vertex 1.3231 0.887641 2.48496 + endloop + endfacet + facet normal 0.180523 -0.392795 0.901734 + outer loop + vertex 1.3231 0.887641 2.48496 + vertex 1.32211 0.890075 2.48621 + vertex 1.31957 0.887499 2.4856 + endloop + endfacet + facet normal 0.184914 -0.474963 0.860359 + outer loop + vertex 1.3231 0.887641 2.48496 + vertex 1.31864 0.883754 2.48377 + vertex 1.3244 0.884677 2.48304 + endloop + endfacet + facet normal 0.19235 -0.471771 0.860485 + outer loop + vertex 1.3244 0.884677 2.48304 + vertex 1.32835 0.888873 2.48446 + vertex 1.3231 0.887641 2.48496 + endloop + endfacet + facet normal 0.177085 -0.38895 0.904079 + outer loop + vertex 1.3231 0.887641 2.48496 + vertex 1.32835 0.888873 2.48446 + vertex 1.32592 0.891354 2.486 + endloop + endfacet + facet normal 0.182142 -0.392124 0.9017 + outer loop + vertex 1.32211 0.890075 2.48621 + vertex 1.3231 0.887641 2.48496 + vertex 1.32592 0.891354 2.486 + endloop + endfacet + facet normal 0.162438 -0.328773 0.930335 + outer loop + vertex 1.32592 0.891354 2.486 + vertex 1.32362 0.894016 2.48734 + vertex 1.32211 0.890075 2.48621 + endloop + endfacet + facet normal 0.162427 -0.328782 0.930333 + outer loop + vertex 1.3289 0.895157 2.48683 + vertex 1.32362 0.894016 2.48734 + vertex 1.32592 0.891354 2.486 + endloop + endfacet + facet normal 0.157554 -0.325406 0.932356 + outer loop + vertex 1.32965 0.892563 2.48579 + vertex 1.3289 0.895157 2.48683 + vertex 1.32592 0.891354 2.486 + endloop + endfacet + facet normal 0.176679 -0.389303 0.904007 + outer loop + vertex 1.32965 0.892563 2.48579 + vertex 1.32592 0.891354 2.486 + vertex 1.32835 0.888873 2.48446 + endloop + endfacet + facet normal 0.17528 -0.388962 0.904426 + outer loop + vertex 1.32965 0.892563 2.48579 + vertex 1.32835 0.888873 2.48446 + vertex 1.33296 0.8925 2.48512 + endloop + endfacet + facet normal 0.192598 -0.408726 0.892104 + outer loop + vertex 1.33296 0.8925 2.48512 + vertex 1.32835 0.888873 2.48446 + vertex 1.33373 0.88863 2.48319 + endloop + endfacet + facet normal 0.192532 -0.408742 0.892111 + outer loop + vertex 1.33373 0.88863 2.48319 + vertex 1.33817 0.893741 2.48457 + vertex 1.33296 0.8925 2.48512 + endloop + endfacet + facet normal 0.170929 -0.39304 0.903495 + outer loop + vertex 1.33928 0.889865 2.48267 + vertex 1.33817 0.893741 2.48457 + vertex 1.33373 0.88863 2.48319 + endloop + endfacet + facet normal 0.173706 -0.392167 0.903344 + outer loop + vertex 1.33928 0.889865 2.48267 + vertex 1.34336 0.893973 2.48367 + vertex 1.33817 0.893741 2.48457 + endloop + endfacet + facet normal 0.161746 -0.376673 0.912116 + outer loop + vertex 1.32211 0.890075 2.48621 + vertex 1.31872 0.890091 2.48682 + vertex 1.31957 0.887499 2.4856 + endloop + endfacet + facet normal 0.165107 -0.329575 0.929581 + outer loop + vertex 1.32211 0.890075 2.48621 + vertex 1.32362 0.894016 2.48734 + vertex 1.31872 0.890091 2.48682 + endloop + endfacet + facet normal 0.186622 -0.376208 0.907546 + outer loop + vertex 1.31576 0.886311 2.48581 + vertex 1.31348 0.889017 2.4874 + vertex 1.31194 0.885194 2.48614 + endloop + endfacet + facet normal 0.210298 -0.471916 0.856195 + outer loop + vertex 1.31194 0.885194 2.48614 + vertex 1.31308 0.882961 2.48462 + vertex 1.31576 0.886311 2.48581 + endloop + endfacet + facet normal 0.199043 -0.465168 0.862555 + outer loop + vertex 1.31308 0.882961 2.48462 + vertex 1.31864 0.883754 2.48377 + vertex 1.31576 0.886311 2.48581 + endloop + endfacet + facet normal 0.209121 -0.472493 0.856165 + outer loop + vertex 1.31308 0.882961 2.48462 + vertex 1.31194 0.885194 2.48614 + vertex 1.30959 0.882971 2.48548 + endloop + endfacet + facet normal 0.174754 -0.442998 0.879326 + outer loop + vertex 1.31194 0.885194 2.48614 + vertex 1.30877 0.88542 2.48688 + vertex 1.30959 0.882971 2.48548 + endloop + endfacet + facet normal 0.186177 -0.376078 0.907691 + outer loop + vertex 1.31194 0.885194 2.48614 + vertex 1.31348 0.889017 2.4874 + vertex 1.30877 0.88542 2.48688 + endloop + endfacet + facet normal 0.179275 -0.367753 0.912479 + outer loop + vertex 1.31348 0.889017 2.4874 + vertex 1.30845 0.889164 2.48845 + vertex 1.30877 0.88542 2.48688 + endloop + endfacet + facet normal 0.176896 -0.368097 0.912805 + outer loop + vertex 1.30877 0.88542 2.48688 + vertex 1.30845 0.889164 2.48845 + vertex 1.3043 0.884925 2.48755 + endloop + endfacet + facet normal 0.182008 -0.372506 0.910007 + outer loop + vertex 1.3043 0.884925 2.48755 + vertex 1.30845 0.889164 2.48845 + vertex 1.3032 0.888991 2.48943 + endloop + endfacet + facet normal 0.181356 -0.372705 0.910056 + outer loop + vertex 1.3043 0.884925 2.48755 + vertex 1.3032 0.888991 2.48943 + vertex 1.29877 0.883645 2.48812 + endloop + endfacet + facet normal 0.198927 -0.385082 0.901188 + outer loop + vertex 1.29877 0.883645 2.48812 + vertex 1.3032 0.888991 2.48943 + vertex 1.29786 0.8876 2.49001 + endloop + endfacet + facet normal 0.200267 -0.384707 0.901051 + outer loop + vertex 1.29786 0.8876 2.49001 + vertex 1.29338 0.883884 2.48942 + vertex 1.29877 0.883645 2.48812 + endloop + endfacet + facet normal 0.182923 -0.332767 0.925097 + outer loop + vertex 1.31348 0.889017 2.4874 + vertex 1.31324 0.893553 2.48908 + vertex 1.30845 0.889164 2.48845 + endloop + endfacet + facet normal 0.17543 -0.333577 0.926256 + outer loop + vertex 1.31348 0.889017 2.4874 + vertex 1.31834 0.893951 2.48826 + vertex 1.31324 0.893553 2.48908 + endloop + endfacet + facet normal 0.170861 -0.312537 0.934413 + outer loop + vertex 1.31834 0.893951 2.48826 + vertex 1.32321 0.898612 2.48893 + vertex 1.31806 0.898529 2.48984 + endloop + endfacet + facet normal 0.174968 -0.312077 0.933806 + outer loop + vertex 1.31834 0.893951 2.48826 + vertex 1.31806 0.898529 2.48984 + vertex 1.31324 0.893553 2.48908 + endloop + endfacet + facet normal 0.178928 -0.315612 0.931866 + outer loop + vertex 1.31324 0.893553 2.48908 + vertex 1.31806 0.898529 2.48984 + vertex 1.31297 0.897269 2.49039 + endloop + endfacet + facet normal 0.181221 -0.315319 0.931522 + outer loop + vertex 1.31297 0.897269 2.49039 + vertex 1.30841 0.893498 2.49 + vertex 1.31324 0.893553 2.48908 + endloop + endfacet + facet normal 0.18043 -0.330242 0.926491 + outer loop + vertex 1.30845 0.889164 2.48845 + vertex 1.31324 0.893553 2.48908 + vertex 1.30841 0.893498 2.49 + endloop + endfacet + facet normal 0.183583 -0.330025 0.925949 + outer loop + vertex 1.30841 0.893498 2.49 + vertex 1.3032 0.888991 2.48943 + vertex 1.30845 0.889164 2.48845 + endloop + endfacet + facet normal 0.18309 -0.32949 0.926237 + outer loop + vertex 1.30455 0.892969 2.49058 + vertex 1.3032 0.888991 2.48943 + vertex 1.30841 0.893498 2.49 + endloop + endfacet + facet normal 0.181677 -0.312481 0.932389 + outer loop + vertex 1.30841 0.893498 2.49 + vertex 1.30693 0.895609 2.491 + vertex 1.30455 0.892969 2.49058 + endloop + endfacet + facet normal 0.176912 -0.308536 0.934616 + outer loop + vertex 1.30693 0.895609 2.491 + vertex 1.3037 0.895398 2.49154 + vertex 1.30455 0.892969 2.49058 + endloop + endfacet + facet normal 0.178872 -0.3078 0.934486 + outer loop + vertex 1.30455 0.892969 2.49058 + vertex 1.3037 0.895398 2.49154 + vertex 1.30075 0.89151 2.49083 + endloop + endfacet + facet normal 0.178249 -0.307373 0.934746 + outer loop + vertex 1.3037 0.895398 2.49154 + vertex 1.29855 0.894159 2.49212 + vertex 1.30075 0.89151 2.49083 + endloop + endfacet + facet normal 0.181124 -0.305089 0.934941 + outer loop + vertex 1.30075 0.89151 2.49083 + vertex 1.29855 0.894159 2.49212 + vertex 1.29702 0.890189 2.49112 + endloop + endfacet + facet normal 0.189768 -0.331839 0.924051 + outer loop + vertex 1.29702 0.890189 2.49112 + vertex 1.29786 0.8876 2.49001 + vertex 1.30075 0.89151 2.49083 + endloop + endfacet + facet normal 0.187256 -0.330212 0.925146 + outer loop + vertex 1.29786 0.8876 2.49001 + vertex 1.3032 0.888991 2.48943 + vertex 1.30075 0.89151 2.49083 + endloop + endfacet + facet normal 0.192244 -0.330955 0.923857 + outer loop + vertex 1.29786 0.8876 2.49001 + vertex 1.29702 0.890189 2.49112 + vertex 1.29452 0.887628 2.49072 + endloop + endfacet + facet normal 0.188736 -0.372041 0.908826 + outer loop + vertex 1.29452 0.887628 2.49072 + vertex 1.29338 0.883884 2.48942 + vertex 1.29786 0.8876 2.49001 + endloop + endfacet + facet normal 0.193847 -0.373075 0.907325 + outer loop + vertex 1.29452 0.887628 2.49072 + vertex 1.29089 0.886392 2.49099 + vertex 1.29338 0.883884 2.48942 + endloop + endfacet + facet normal 0.18957 -0.376902 0.906647 + outer loop + vertex 1.28823 0.882629 2.48998 + vertex 1.29338 0.883884 2.48942 + vertex 1.29089 0.886392 2.49099 + endloop + endfacet + facet normal 0.203323 -0.384911 0.90028 + outer loop + vertex 1.28719 0.885092 2.49127 + vertex 1.28823 0.882629 2.48998 + vertex 1.29089 0.886392 2.49099 + endloop + endfacet + facet normal 0.183448 -0.32229 0.928696 + outer loop + vertex 1.29089 0.886392 2.49099 + vertex 1.28862 0.889051 2.49236 + vertex 1.28719 0.885092 2.49127 + endloop + endfacet + facet normal 0.18265 -0.322067 0.92893 + outer loop + vertex 1.28719 0.885092 2.49127 + vertex 1.28862 0.889051 2.49236 + vertex 1.28385 0.885077 2.49192 + endloop + endfacet + facet normal 0.179445 -0.370513 0.911329 + outer loop + vertex 1.28719 0.885092 2.49127 + vertex 1.28385 0.885077 2.49192 + vertex 1.28475 0.882472 2.49068 + endloop + endfacet + facet normal 0.180571 -0.319708 0.930151 + outer loop + vertex 1.28862 0.889051 2.49236 + vertex 1.28343 0.888941 2.49333 + vertex 1.28385 0.885077 2.49192 + endloop + endfacet + facet normal 0.179919 -0.319813 0.930241 + outer loop + vertex 1.28385 0.885077 2.49192 + vertex 1.28343 0.888941 2.49333 + vertex 1.2786 0.883894 2.49253 + endloop + endfacet + facet normal 0.181229 -0.303157 0.935549 + outer loop + vertex 1.28862 0.889051 2.49236 + vertex 1.28823 0.893653 2.49393 + vertex 1.28343 0.888941 2.49333 + endloop + endfacet + facet normal 0.181147 -0.303078 0.93559 + outer loop + vertex 1.28343 0.888941 2.49333 + vertex 1.28823 0.893653 2.49393 + vertex 1.28313 0.893516 2.49487 + endloop + endfacet + facet normal 0.182177 -0.302956 0.93543 + outer loop + vertex 1.28343 0.888941 2.49333 + vertex 1.28313 0.893516 2.49487 + vertex 1.27835 0.88848 2.49417 + endloop + endfacet + facet normal 0.182842 -0.322375 0.928786 + outer loop + vertex 1.2786 0.883894 2.49253 + vertex 1.28343 0.888941 2.49333 + vertex 1.27835 0.88848 2.49417 + endloop + endfacet + facet normal 0.186386 -0.321979 0.928219 + outer loop + vertex 1.2786 0.883894 2.49253 + vertex 1.27835 0.88848 2.49417 + vertex 1.27339 0.88388 2.49357 + endloop + endfacet + facet normal 0.18581 -0.321399 0.928535 + outer loop + vertex 1.27339 0.88388 2.49357 + vertex 1.27835 0.88848 2.49417 + vertex 1.27355 0.888392 2.4951 + endloop + endfacet + facet normal 0.193807 -0.321156 0.926983 + outer loop + vertex 1.27355 0.888392 2.4951 + vertex 1.26813 0.883782 2.49463 + vertex 1.27339 0.88388 2.49357 + endloop + endfacet + facet normal 0.19294 -0.320188 0.927499 + outer loop + vertex 1.26974 0.887839 2.4957 + vertex 1.26813 0.883782 2.49463 + vertex 1.27355 0.888392 2.4951 + endloop + endfacet + facet normal 0.191183 -0.300558 0.934406 + outer loop + vertex 1.27355 0.888392 2.4951 + vertex 1.27216 0.890546 2.49607 + vertex 1.26974 0.887839 2.4957 + endloop + endfacet + facet normal 0.19024 -0.299775 0.93485 + outer loop + vertex 1.27216 0.890546 2.49607 + vertex 1.26894 0.890316 2.49666 + vertex 1.26974 0.887839 2.4957 + endloop + endfacet + facet normal 0.1934 -0.29865 0.934561 + outer loop + vertex 1.26974 0.887839 2.4957 + vertex 1.26894 0.890316 2.49666 + vertex 1.26594 0.886345 2.49601 + endloop + endfacet + facet normal 0.192888 -0.298297 0.93478 + outer loop + vertex 1.26894 0.890316 2.49666 + vertex 1.2638 0.889018 2.4973 + vertex 1.26594 0.886345 2.49601 + endloop + endfacet + facet normal 0.198092 -0.294234 0.934979 + outer loop + vertex 1.26594 0.886345 2.49601 + vertex 1.2638 0.889018 2.4973 + vertex 1.26224 0.884985 2.49636 + endloop + endfacet + facet normal 0.208441 -0.325683 0.922216 + outer loop + vertex 1.26224 0.884985 2.49636 + vertex 1.2629 0.882467 2.49533 + vertex 1.26594 0.886345 2.49601 + endloop + endfacet + facet normal 0.203349 -0.322115 0.924603 + outer loop + vertex 1.2629 0.882467 2.49533 + vertex 1.26813 0.883782 2.49463 + vertex 1.26594 0.886345 2.49601 + endloop + endfacet + facet normal 0.210644 -0.325001 0.921956 + outer loop + vertex 1.2629 0.882467 2.49533 + vertex 1.26224 0.884985 2.49636 + vertex 1.25967 0.882394 2.49604 + endloop + endfacet + facet normal 0.207266 -0.381605 0.900788 + outer loop + vertex 1.25967 0.882394 2.49604 + vertex 1.25848 0.878744 2.49477 + vertex 1.2629 0.882467 2.49533 + endloop + endfacet + facet normal 0.220805 -0.384479 0.896337 + outer loop + vertex 1.25967 0.882394 2.49604 + vertex 1.25601 0.881057 2.49637 + vertex 1.25848 0.878744 2.49477 + endloop + endfacet + facet normal 0.214971 -0.390026 0.895359 + outer loop + vertex 1.25343 0.877245 2.49533 + vertex 1.25848 0.878744 2.49477 + vertex 1.25601 0.881057 2.49637 + endloop + endfacet + facet normal 0.234724 -0.400757 0.885606 + outer loop + vertex 1.25222 0.879531 2.49668 + vertex 1.25343 0.877245 2.49533 + vertex 1.25601 0.881057 2.49637 + endloop + endfacet + facet normal 0.239473 -0.495051 0.835211 + outer loop + vertex 1.25502 0.87441 2.49319 + vertex 1.25848 0.878744 2.49477 + vertex 1.25343 0.877245 2.49533 + endloop + endfacet + facet normal 0.197439 -0.312419 0.9292 + outer loop + vertex 1.25967 0.882394 2.49604 + vertex 1.259 0.884974 2.49705 + vertex 1.25601 0.881057 2.49637 + endloop + endfacet + facet normal 0.199701 -0.313967 0.928194 + outer loop + vertex 1.259 0.884974 2.49705 + vertex 1.25371 0.883665 2.49774 + vertex 1.25601 0.881057 2.49637 + endloop + endfacet + facet normal 0.202361 -0.311716 0.928377 + outer loop + vertex 1.25601 0.881057 2.49637 + vertex 1.25371 0.883665 2.49774 + vertex 1.25222 0.879531 2.49668 + endloop + endfacet + facet normal 0.19422 -0.286532 0.938178 + outer loop + vertex 1.259 0.884974 2.49705 + vertex 1.25859 0.888896 2.49833 + vertex 1.25371 0.883665 2.49774 + endloop + endfacet + facet normal 0.190538 -0.283287 0.939917 + outer loop + vertex 1.25371 0.883665 2.49774 + vertex 1.25859 0.888896 2.49833 + vertex 1.25348 0.888458 2.49924 + endloop + endfacet + facet normal 0.193949 -0.282937 0.939325 + outer loop + vertex 1.25371 0.883665 2.49774 + vertex 1.25348 0.888458 2.49924 + vertex 1.24849 0.883758 2.49885 + endloop + endfacet + facet normal 0.191982 -0.307208 0.932076 + outer loop + vertex 1.25371 0.883665 2.49774 + vertex 1.24849 0.883758 2.49885 + vertex 1.24837 0.879023 2.49731 + endloop + endfacet + facet normal 0.196071 -0.307051 0.931277 + outer loop + vertex 1.24837 0.879023 2.49731 + vertex 1.24849 0.883758 2.49885 + vertex 1.24361 0.879165 2.49836 + endloop + endfacet + facet normal 0.188715 -0.299654 0.935197 + outer loop + vertex 1.24361 0.879165 2.49836 + vertex 1.24849 0.883758 2.49885 + vertex 1.24334 0.883793 2.4999 + endloop + endfacet + facet normal 0.189771 -0.299533 0.935022 + outer loop + vertex 1.24361 0.879165 2.49836 + vertex 1.24334 0.883793 2.4999 + vertex 1.23864 0.878616 2.4992 + endloop + endfacet + facet normal 0.193172 -0.370675 0.908452 + outer loop + vertex 1.2395 0.874833 2.49747 + vertex 1.24361 0.879165 2.49836 + vertex 1.23864 0.878616 2.4992 + endloop + endfacet + facet normal 0.182835 -0.373482 0.909441 + outer loop + vertex 1.2395 0.874833 2.49747 + vertex 1.23864 0.878616 2.4992 + vertex 1.23413 0.873748 2.4981 + endloop + endfacet + facet normal 0.20605 -0.392123 0.89654 + outer loop + vertex 1.23413 0.873748 2.4981 + vertex 1.23864 0.878616 2.4992 + vertex 1.2337 0.878219 2.50016 + endloop + endfacet + facet normal 0.225444 -0.388795 0.893316 + outer loop + vertex 1.2337 0.878219 2.50016 + vertex 1.22887 0.873956 2.49952 + vertex 1.23413 0.873748 2.4981 + endloop + endfacet + facet normal 0.237339 -0.401014 0.884793 + outer loop + vertex 1.22978 0.877349 2.50081 + vertex 1.22887 0.873956 2.49952 + vertex 1.2337 0.878219 2.50016 + endloop + endfacet + facet normal 0.253701 -0.403292 0.879199 + outer loop + vertex 1.22978 0.877349 2.50081 + vertex 1.22685 0.875693 2.5009 + vertex 1.22887 0.873956 2.49952 + endloop + endfacet + facet normal 0.238248 -0.418838 0.876249 + outer loop + vertex 1.22887 0.873956 2.49952 + vertex 1.22685 0.875693 2.5009 + vertex 1.22477 0.873248 2.5003 + endloop + endfacet + facet normal 0.205506 -0.315767 0.926314 + outer loop + vertex 1.22978 0.877349 2.50081 + vertex 1.22805 0.879276 2.50185 + vertex 1.22685 0.875693 2.5009 + endloop + endfacet + facet normal 0.209739 -0.316834 0.925 + outer loop + vertex 1.22685 0.875693 2.5009 + vertex 1.22805 0.879276 2.50185 + vertex 1.22369 0.875497 2.50155 + endloop + endfacet + facet normal 0.203315 -0.309716 0.928837 + outer loop + vertex 1.22805 0.879276 2.50185 + vertex 1.22337 0.8792 2.50285 + vertex 1.22369 0.875497 2.50155 + endloop + endfacet + facet normal 0.195356 -0.310865 0.930161 + outer loop + vertex 1.22369 0.875497 2.50155 + vertex 1.22337 0.8792 2.50285 + vertex 1.21932 0.874832 2.50225 + endloop + endfacet + facet normal 0.199591 -0.314495 0.928039 + outer loop + vertex 1.21932 0.874832 2.50225 + vertex 1.22337 0.8792 2.50285 + vertex 1.21852 0.878847 2.50378 + endloop + endfacet + facet normal 0.183421 -0.318458 0.930022 + outer loop + vertex 1.21932 0.874832 2.50225 + vertex 1.21852 0.878847 2.50378 + vertex 1.21399 0.873769 2.50293 + endloop + endfacet + facet normal 0.201945 -0.333453 0.920884 + outer loop + vertex 1.21399 0.873769 2.50293 + vertex 1.21852 0.878847 2.50378 + vertex 1.21353 0.878735 2.50483 + endloop + endfacet + facet normal 0.203476 -0.333213 0.920634 + outer loop + vertex 1.21353 0.878735 2.50483 + vertex 1.20856 0.874109 2.50425 + vertex 1.21399 0.873769 2.50293 + endloop + endfacet + facet normal 0.229156 -0.358817 0.904841 + outer loop + vertex 1.20953 0.877995 2.50555 + vertex 1.20856 0.874109 2.50425 + vertex 1.21353 0.878735 2.50483 + endloop + endfacet + facet normal 0.237372 -0.359998 0.90225 + outer loop + vertex 1.20953 0.877995 2.50555 + vertex 1.20586 0.876398 2.50588 + vertex 1.20856 0.874109 2.50425 + endloop + endfacet + facet normal 0.207799 -0.285068 0.935711 + outer loop + vertex 1.20953 0.877995 2.50555 + vertex 1.20857 0.880405 2.5065 + vertex 1.20586 0.876398 2.50588 + endloop + endfacet + facet normal 0.218077 -0.291356 0.931426 + outer loop + vertex 1.20857 0.880405 2.5065 + vertex 1.20354 0.878954 2.50722 + vertex 1.20586 0.876398 2.50588 + endloop + endfacet + facet normal 0.21411 -0.294857 0.931245 + outer loop + vertex 1.20586 0.876398 2.50588 + vertex 1.20354 0.878954 2.50722 + vertex 1.20223 0.874956 2.50626 + endloop + endfacet + facet normal 0.252128 -0.404121 0.879271 + outer loop + vertex 1.20223 0.874956 2.50626 + vertex 1.20344 0.872778 2.50491 + vertex 1.20586 0.876398 2.50588 + endloop + endfacet + facet normal 0.235693 -0.413407 0.879514 + outer loop + vertex 1.20344 0.872778 2.50491 + vertex 1.20223 0.874956 2.50626 + vertex 1.20002 0.872563 2.50572 + endloop + endfacet + facet normal 0.197318 -0.383123 0.902376 + outer loop + vertex 1.20223 0.874956 2.50626 + vertex 1.19894 0.874923 2.50696 + vertex 1.20002 0.872563 2.50572 + endloop + endfacet + facet normal 0.203317 -0.292106 0.934525 + outer loop + vertex 1.20223 0.874956 2.50626 + vertex 1.20354 0.878954 2.50722 + vertex 1.19894 0.874923 2.50696 + endloop + endfacet + facet normal 0.204074 -0.292942 0.934098 + outer loop + vertex 1.20354 0.878954 2.50722 + vertex 1.1985 0.878807 2.50828 + vertex 1.19894 0.874923 2.50696 + endloop + endfacet + facet normal 0.172653 -0.298145 0.938776 + outer loop + vertex 1.19894 0.874923 2.50696 + vertex 1.1985 0.878807 2.50828 + vertex 1.19391 0.873877 2.50755 + endloop + endfacet + facet normal 0.200923 -0.3224 0.925034 + outer loop + vertex 1.19391 0.873877 2.50755 + vertex 1.1985 0.878807 2.50828 + vertex 1.19366 0.87852 2.50923 + endloop + endfacet + facet normal 0.186118 -0.32412 0.927527 + outer loop + vertex 1.19391 0.873877 2.50755 + vertex 1.19366 0.87852 2.50923 + vertex 1.18893 0.874021 2.50861 + endloop + endfacet + facet normal 0.201046 -0.261108 0.944141 + outer loop + vertex 1.1985 0.878807 2.50828 + vertex 1.19847 0.883362 2.50954 + vertex 1.19366 0.87852 2.50923 + endloop + endfacet + facet normal 0.209519 -0.269257 0.940001 + outer loop + vertex 1.19366 0.87852 2.50923 + vertex 1.19847 0.883362 2.50954 + vertex 1.19392 0.883119 2.51049 + endloop + endfacet + facet normal 0.214696 -0.269241 0.938837 + outer loop + vertex 1.19392 0.883119 2.51049 + vertex 1.18892 0.878358 2.51027 + vertex 1.19366 0.87852 2.50923 + endloop + endfacet + facet normal 0.211735 -0.349005 0.912888 + outer loop + vertex 1.18893 0.874021 2.50861 + vertex 1.19366 0.87852 2.50923 + vertex 1.18892 0.878358 2.51027 + endloop + endfacet + facet normal 0.202081 -0.34976 0.914785 + outer loop + vertex 1.18892 0.878358 2.51027 + vertex 1.18399 0.873837 2.50963 + vertex 1.18893 0.874021 2.50861 + endloop + endfacet + facet normal 0.207492 -0.260711 0.942856 + outer loop + vertex 1.1985 0.878807 2.50828 + vertex 1.20332 0.883766 2.50859 + vertex 1.19847 0.883362 2.50954 + endloop + endfacet + facet normal 0.207189 -0.250134 0.945783 + outer loop + vertex 1.20332 0.883766 2.50859 + vertex 1.2033 0.888723 2.5099 + vertex 1.19847 0.883362 2.50954 + endloop + endfacet + facet normal 0.202284 -0.245853 0.947965 + outer loop + vertex 1.19847 0.883362 2.50954 + vertex 1.2033 0.888723 2.5099 + vertex 1.19834 0.887244 2.51058 + endloop + endfacet + facet normal 0.209591 -0.245228 0.946538 + outer loop + vertex 1.19834 0.887244 2.51058 + vertex 1.19392 0.883119 2.51049 + vertex 1.19847 0.883362 2.50954 + endloop + endfacet + facet normal 0.207932 -0.243471 0.947357 + outer loop + vertex 1.19524 0.88688 2.51116 + vertex 1.19392 0.883119 2.51049 + vertex 1.19834 0.887244 2.51058 + endloop + endfacet + facet normal 0.203628 -0.251134 0.946291 + outer loop + vertex 1.19834 0.887244 2.51058 + vertex 1.2033 0.888723 2.5099 + vertex 1.20118 0.891338 2.51105 + endloop + endfacet + facet normal 0.199474 -0.254496 0.946278 + outer loop + vertex 1.20487 0.892933 2.5107 + vertex 1.20118 0.891338 2.51105 + vertex 1.2033 0.888723 2.5099 + endloop + endfacet + facet normal 0.196208 -0.253464 0.947237 + outer loop + vertex 1.20487 0.892933 2.5107 + vertex 1.2033 0.888723 2.5099 + vertex 1.20858 0.893485 2.51008 + endloop + endfacet + facet normal 0.197456 -0.266044 0.943521 + outer loop + vertex 1.20858 0.893485 2.51008 + vertex 1.20716 0.895647 2.51099 + vertex 1.20487 0.892933 2.5107 + endloop + endfacet + facet normal 0.20062 -0.268564 0.942139 + outer loop + vertex 1.20716 0.895647 2.51099 + vertex 1.204 0.895359 2.51158 + vertex 1.20487 0.892933 2.5107 + endloop + endfacet + facet normal 0.200876 -0.27571 0.940018 + outer loop + vertex 1.20716 0.895647 2.51099 + vertex 1.20837 0.899251 2.51179 + vertex 1.204 0.895359 2.51158 + endloop + endfacet + facet normal 0.198307 -0.272893 0.941384 + outer loop + vertex 1.20837 0.899251 2.51179 + vertex 1.20356 0.899103 2.51276 + vertex 1.204 0.895359 2.51158 + endloop + endfacet + facet normal 0.206301 -0.27154 0.940056 + outer loop + vertex 1.204 0.895359 2.51158 + vertex 1.20356 0.899103 2.51276 + vertex 1.19883 0.893876 2.51229 + endloop + endfacet + facet normal 0.205352 -0.267601 0.941393 + outer loop + vertex 1.204 0.895359 2.51158 + vertex 1.19883 0.893876 2.51229 + vertex 1.20118 0.891338 2.51105 + endloop + endfacet + facet normal 0.208662 -0.264594 0.941515 + outer loop + vertex 1.20118 0.891338 2.51105 + vertex 1.19883 0.893876 2.51229 + vertex 1.19751 0.889701 2.51141 + endloop + endfacet + facet normal 0.219355 -0.267319 0.938309 + outer loop + vertex 1.19751 0.889701 2.51141 + vertex 1.19883 0.893876 2.51229 + vertex 1.19352 0.888922 2.51212 + endloop + endfacet + facet normal 0.217766 -0.255967 0.941838 + outer loop + vertex 1.19751 0.889701 2.51141 + vertex 1.19352 0.888922 2.51212 + vertex 1.19524 0.88688 2.51116 + endloop + endfacet + facet normal 0.210836 -0.258335 0.942768 + outer loop + vertex 1.19883 0.893876 2.51229 + vertex 1.19348 0.893864 2.51348 + vertex 1.19352 0.888922 2.51212 + endloop + endfacet + facet normal 0.218384 -0.257842 0.941183 + outer loop + vertex 1.19352 0.888922 2.51212 + vertex 1.19348 0.893864 2.51348 + vertex 1.18839 0.888837 2.51328 + endloop + endfacet + facet normal 0.218851 -0.246747 0.944045 + outer loop + vertex 1.19352 0.888922 2.51212 + vertex 1.18839 0.888837 2.51328 + vertex 1.18835 0.884002 2.51203 + endloop + endfacet + facet normal 0.223566 -0.251655 0.941641 + outer loop + vertex 1.19235 0.885069 2.51136 + vertex 1.19352 0.888922 2.51212 + vertex 1.18835 0.884002 2.51203 + endloop + endfacet + facet normal 0.222785 -0.248015 0.942791 + outer loop + vertex 1.19235 0.885069 2.51136 + vertex 1.18835 0.884002 2.51203 + vertex 1.1902 0.882151 2.51111 + endloop + endfacet + facet normal 0.220938 -0.246718 0.943566 + outer loop + vertex 1.19392 0.883119 2.51049 + vertex 1.19235 0.885069 2.51136 + vertex 1.1902 0.882151 2.51111 + endloop + endfacet + facet normal 0.228437 -0.283353 0.931412 + outer loop + vertex 1.1902 0.882151 2.51111 + vertex 1.18892 0.878358 2.51027 + vertex 1.19392 0.883119 2.51049 + endloop + endfacet + facet normal 0.24508 -0.287732 0.925822 + outer loop + vertex 1.1902 0.882151 2.51111 + vertex 1.18714 0.880126 2.51129 + vertex 1.18892 0.878358 2.51027 + endloop + endfacet + facet normal 0.233181 -0.299354 0.92521 + outer loop + vertex 1.18892 0.878358 2.51027 + vertex 1.18714 0.880126 2.51129 + vertex 1.18499 0.87725 2.5109 + endloop + endfacet + facet normal 0.254835 -0.402217 0.879364 + outer loop + vertex 1.18499 0.87725 2.5109 + vertex 1.18399 0.873837 2.50963 + vertex 1.18892 0.878358 2.51027 + endloop + endfacet + facet normal 0.256219 -0.402434 0.878862 + outer loop + vertex 1.18499 0.87725 2.5109 + vertex 1.18207 0.875498 2.51095 + vertex 1.18399 0.873837 2.50963 + endloop + endfacet + facet normal 0.21659 -0.441689 0.870632 + outer loop + vertex 1.18399 0.873837 2.50963 + vertex 1.18207 0.875498 2.51095 + vertex 1.17994 0.873054 2.51024 + endloop + endfacet + facet normal 0.173182 -0.410864 0.895097 + outer loop + vertex 1.18207 0.875498 2.51095 + vertex 1.17893 0.875387 2.5115 + vertex 1.17994 0.873054 2.51024 + endloop + endfacet + facet normal 0.176886 -0.294231 0.939223 + outer loop + vertex 1.18207 0.875498 2.51095 + vertex 1.18327 0.87918 2.51187 + vertex 1.17893 0.875387 2.5115 + endloop + endfacet + facet normal 0.194463 -0.313377 0.929505 + outer loop + vertex 1.18327 0.87918 2.51187 + vertex 1.17861 0.879191 2.51285 + vertex 1.17893 0.875387 2.5115 + endloop + endfacet + facet normal 0.161787 -0.317758 0.934267 + outer loop + vertex 1.17893 0.875387 2.5115 + vertex 1.17861 0.879191 2.51285 + vertex 1.17463 0.875065 2.51214 + endloop + endfacet + facet normal 0.196555 -0.3483 0.916544 + outer loop + vertex 1.17463 0.875065 2.51214 + vertex 1.17861 0.879191 2.51285 + vertex 1.17389 0.879045 2.51381 + endloop + endfacet + facet normal 0.179394 -0.352317 0.918526 + outer loop + vertex 1.17463 0.875065 2.51214 + vertex 1.17389 0.879045 2.51381 + vertex 1.16986 0.874816 2.51297 + endloop + endfacet + facet normal 0.22215 -0.388288 0.894361 + outer loop + vertex 1.16986 0.874816 2.51297 + vertex 1.17389 0.879045 2.51381 + vertex 1.16895 0.878799 2.51493 + endloop + endfacet + facet normal 0.225483 -0.284573 0.93176 + outer loop + vertex 1.17381 0.883573 2.51521 + vertex 1.16895 0.878799 2.51493 + vertex 1.17389 0.879045 2.51381 + endloop + endfacet + facet normal 0.214707 -0.285453 0.934033 + outer loop + vertex 1.17389 0.879045 2.51381 + vertex 1.17857 0.883696 2.51415 + vertex 1.17381 0.883573 2.51521 + endloop + endfacet + facet normal 0.216084 -0.246431 0.944764 + outer loop + vertex 1.17882 0.888352 2.51531 + vertex 1.17381 0.883573 2.51521 + vertex 1.17857 0.883696 2.51415 + endloop + endfacet + facet normal 0.211043 -0.246442 0.9459 + outer loop + vertex 1.17857 0.883696 2.51415 + vertex 1.18341 0.888516 2.51433 + vertex 1.17882 0.888352 2.51531 + endloop + endfacet + facet normal 0.211093 -0.243803 0.946573 + outer loop + vertex 1.18319 0.892432 2.51539 + vertex 1.17882 0.888352 2.51531 + vertex 1.18341 0.888516 2.51433 + endloop + endfacet + facet normal 0.207404 -0.244207 0.947284 + outer loop + vertex 1.18341 0.888516 2.51433 + vertex 1.1882 0.893891 2.51467 + vertex 1.18319 0.892432 2.51539 + endloop + endfacet + facet normal 0.20921 -0.251568 0.944958 + outer loop + vertex 1.18319 0.892432 2.51539 + vertex 1.1882 0.893891 2.51467 + vertex 1.18595 0.896489 2.51586 + endloop + endfacet + facet normal 0.205926 -0.249482 0.946231 + outer loop + vertex 1.18233 0.894866 2.51622 + vertex 1.18319 0.892432 2.51539 + vertex 1.18595 0.896489 2.51586 + endloop + endfacet + facet normal 0.209436 -0.257987 0.943175 + outer loop + vertex 1.18595 0.896489 2.51586 + vertex 1.18366 0.898958 2.51704 + vertex 1.18233 0.894866 2.51622 + endloop + endfacet + facet normal 0.212783 -0.258874 0.942182 + outer loop + vertex 1.18233 0.894866 2.51622 + vertex 1.18366 0.898958 2.51704 + vertex 1.17842 0.894071 2.51688 + endloop + endfacet + facet normal 0.211583 -0.25097 0.944588 + outer loop + vertex 1.18233 0.894866 2.51622 + vertex 1.17842 0.894071 2.51688 + vertex 1.1801 0.892092 2.51598 + endloop + endfacet + facet normal 0.214963 -0.248097 0.944584 + outer loop + vertex 1.1801 0.892092 2.51598 + vertex 1.17842 0.894071 2.51688 + vertex 1.17723 0.89031 2.51616 + endloop + endfacet + facet normal 0.210908 -0.241295 0.947256 + outer loop + vertex 1.1801 0.892092 2.51598 + vertex 1.17723 0.89031 2.51616 + vertex 1.17882 0.888352 2.51531 + endloop + endfacet + facet normal 0.213784 -0.238942 0.947208 + outer loop + vertex 1.17882 0.888352 2.51531 + vertex 1.17723 0.89031 2.51616 + vertex 1.17508 0.887423 2.51592 + endloop + endfacet + facet normal 0.221419 -0.244388 0.94406 + outer loop + vertex 1.17723 0.89031 2.51616 + vertex 1.17323 0.88919 2.51681 + vertex 1.17508 0.887423 2.51592 + endloop + endfacet + facet normal 0.225575 -0.240106 0.944174 + outer loop + vertex 1.17508 0.887423 2.51592 + vertex 1.17323 0.88919 2.51681 + vertex 1.17198 0.885367 2.51614 + endloop + endfacet + facet normal 0.231779 -0.249892 0.940124 + outer loop + vertex 1.17508 0.887423 2.51592 + vertex 1.17198 0.885367 2.51614 + vertex 1.17381 0.883573 2.51521 + endloop + endfacet + facet normal 0.232438 -0.249224 0.940138 + outer loop + vertex 1.17381 0.883573 2.51521 + vertex 1.17198 0.885367 2.51614 + vertex 1.16981 0.882412 2.51589 + endloop + endfacet + facet normal 0.233675 -0.250086 0.939603 + outer loop + vertex 1.17198 0.885367 2.51614 + vertex 1.16798 0.884148 2.51681 + vertex 1.16981 0.882412 2.51589 + endloop + endfacet + facet normal 0.231663 -0.252183 0.93954 + outer loop + vertex 1.16981 0.882412 2.51589 + vertex 1.16798 0.884148 2.51681 + vertex 1.16682 0.880375 2.51608 + endloop + endfacet + facet normal 0.267385 -0.307127 0.913334 + outer loop + vertex 1.16981 0.882412 2.51589 + vertex 1.16682 0.880375 2.51608 + vertex 1.16895 0.878799 2.51493 + endloop + endfacet + facet normal 0.254572 -0.323108 0.911479 + outer loop + vertex 1.16895 0.878799 2.51493 + vertex 1.16682 0.880375 2.51608 + vertex 1.16499 0.877655 2.51563 + endloop + endfacet + facet normal 0.27953 -0.447169 0.849648 + outer loop + vertex 1.16499 0.877655 2.51563 + vertex 1.16477 0.874545 2.51407 + vertex 1.16895 0.878799 2.51493 + endloop + endfacet + facet normal 0.212922 -0.39093 0.895454 + outer loop + vertex 1.16895 0.878799 2.51493 + vertex 1.16477 0.874545 2.51407 + vertex 1.16986 0.874816 2.51297 + endloop + endfacet + facet normal 0.271644 -0.447729 0.851909 + outer loop + vertex 1.16499 0.877655 2.51563 + vertex 1.16237 0.875993 2.51559 + vertex 1.16477 0.874545 2.51407 + endloop + endfacet + facet normal 0.220147 -0.510973 0.830928 + outer loop + vertex 1.16477 0.874545 2.51407 + vertex 1.16237 0.875993 2.51559 + vertex 1.1607 0.873682 2.51461 + endloop + endfacet + facet normal 0.200789 -0.337147 0.919791 + outer loop + vertex 1.16499 0.877655 2.51563 + vertex 1.16313 0.879385 2.51667 + vertex 1.16237 0.875993 2.51559 + endloop + endfacet + facet normal 0.170871 -0.332814 0.927382 + outer loop + vertex 1.16237 0.875993 2.51559 + vertex 1.16313 0.879385 2.51667 + vertex 1.15926 0.875734 2.51607 + endloop + endfacet + facet normal 0.229529 -0.308266 0.923195 + outer loop + vertex 1.16682 0.880375 2.51608 + vertex 1.16313 0.879385 2.51667 + vertex 1.16499 0.877655 2.51563 + endloop + endfacet + facet normal 0.216801 -0.248499 0.944058 + outer loop + vertex 1.16682 0.880375 2.51608 + vertex 1.16798 0.884148 2.51681 + vertex 1.16313 0.879385 2.51667 + endloop + endfacet + facet normal 0.232419 -0.264147 0.93606 + outer loop + vertex 1.16798 0.884148 2.51681 + vertex 1.16317 0.883861 2.51792 + vertex 1.16313 0.879385 2.51667 + endloop + endfacet + facet normal 0.219238 -0.264852 0.939036 + outer loop + vertex 1.16313 0.879385 2.51667 + vertex 1.16317 0.883861 2.51792 + vertex 1.15855 0.879257 2.5177 + endloop + endfacet + facet normal 0.21399 -0.374466 0.90221 + outer loop + vertex 1.16313 0.879385 2.51667 + vertex 1.15855 0.879257 2.5177 + vertex 1.15926 0.875734 2.51607 + endloop + endfacet + facet normal 0.244491 -0.289561 0.925407 + outer loop + vertex 1.15855 0.879257 2.5177 + vertex 1.16317 0.883861 2.51792 + vertex 1.15851 0.883733 2.51911 + endloop + endfacet + facet normal 0.246825 -0.233389 0.940535 + outer loop + vertex 1.16317 0.883861 2.51792 + vertex 1.1634 0.888652 2.51905 + vertex 1.15851 0.883733 2.51911 + endloop + endfacet + facet normal 0.249734 -0.236302 0.939039 + outer loop + vertex 1.15851 0.883733 2.51911 + vertex 1.1634 0.888652 2.51905 + vertex 1.15878 0.88852 2.52025 + endloop + endfacet + facet normal 0.250268 -0.219524 0.942961 + outer loop + vertex 1.16375 0.893593 2.52011 + vertex 1.15878 0.88852 2.52025 + vertex 1.1634 0.888652 2.51905 + endloop + endfacet + facet normal 0.218649 -0.21902 0.950906 + outer loop + vertex 1.1634 0.888652 2.51905 + vertex 1.16854 0.893729 2.51904 + vertex 1.16375 0.893593 2.52011 + endloop + endfacet + facet normal 0.218177 -0.238337 0.946358 + outer loop + vertex 1.16895 0.898593 2.52017 + vertex 1.16375 0.893593 2.52011 + vertex 1.16854 0.893729 2.51904 + endloop + endfacet + facet normal 0.207087 -0.237999 0.948932 + outer loop + vertex 1.16854 0.893729 2.51904 + vertex 1.17365 0.898663 2.51916 + vertex 1.16895 0.898593 2.52017 + endloop + endfacet + facet normal 0.206434 -0.254686 0.944733 + outer loop + vertex 1.17395 0.903276 2.52034 + vertex 1.16895 0.898593 2.52017 + vertex 1.17365 0.898663 2.51916 + endloop + endfacet + facet normal 0.204079 -0.254666 0.94525 + outer loop + vertex 1.17365 0.898663 2.51916 + vertex 1.17851 0.90343 2.5194 + vertex 1.17395 0.903276 2.52034 + endloop + endfacet + facet normal 0.203951 -0.260573 0.943666 + outer loop + vertex 1.17829 0.907238 2.5205 + vertex 1.17395 0.903276 2.52034 + vertex 1.17851 0.90343 2.5194 + endloop + endfacet + facet normal 0.202314 -0.260757 0.943968 + outer loop + vertex 1.17851 0.90343 2.5194 + vertex 1.18329 0.9087 2.51983 + vertex 1.17829 0.907238 2.5205 + endloop + endfacet + facet normal 0.202198 -0.260291 0.944121 + outer loop + vertex 1.17829 0.907238 2.5205 + vertex 1.18329 0.9087 2.51983 + vertex 1.1811 0.911254 2.521 + endloop + endfacet + facet normal 0.202166 -0.26027 0.944134 + outer loop + vertex 1.17742 0.909645 2.52134 + vertex 1.17829 0.907238 2.5205 + vertex 1.1811 0.911254 2.521 + endloop + endfacet + facet normal 0.201318 -0.258169 0.944891 + outer loop + vertex 1.1811 0.911254 2.521 + vertex 1.17875 0.913791 2.52219 + vertex 1.17742 0.909645 2.52134 + endloop + endfacet + facet normal 0.202207 -0.258402 0.944638 + outer loop + vertex 1.17742 0.909645 2.52134 + vertex 1.17875 0.913791 2.52219 + vertex 1.17349 0.908924 2.52199 + endloop + endfacet + facet normal 0.202361 -0.25956 0.944287 + outer loop + vertex 1.17742 0.909645 2.52134 + vertex 1.17349 0.908924 2.52199 + vertex 1.17519 0.906914 2.52107 + endloop + endfacet + facet normal 0.202428 -0.259504 0.944288 + outer loop + vertex 1.17519 0.906914 2.52107 + vertex 1.17349 0.908924 2.52199 + vertex 1.17235 0.905208 2.52121 + endloop + endfacet + facet normal 0.202278 -0.259245 0.944392 + outer loop + vertex 1.17519 0.906914 2.52107 + vertex 1.17235 0.905208 2.52121 + vertex 1.17395 0.903276 2.52034 + endloop + endfacet + facet normal 0.202853 -0.258772 0.944398 + outer loop + vertex 1.17395 0.903276 2.52034 + vertex 1.17235 0.905208 2.52121 + vertex 1.17026 0.90242 2.5209 + endloop + endfacet + facet normal 0.206817 -0.261566 0.942767 + outer loop + vertex 1.17235 0.905208 2.52121 + vertex 1.16838 0.90419 2.5218 + vertex 1.17026 0.90242 2.5209 + endloop + endfacet + facet normal 0.20896 -0.259361 0.942904 + outer loop + vertex 1.17026 0.90242 2.5209 + vertex 1.16838 0.90419 2.5218 + vertex 1.16721 0.900466 2.52103 + endloop + endfacet + facet normal 0.202833 -0.249544 0.946883 + outer loop + vertex 1.17026 0.90242 2.5209 + vertex 1.16721 0.900466 2.52103 + vertex 1.16895 0.898593 2.52017 + endloop + endfacet + facet normal 0.207034 -0.245696 0.94698 + outer loop + vertex 1.16895 0.898593 2.52017 + vertex 1.16721 0.900466 2.52103 + vertex 1.16503 0.897542 2.52075 + endloop + endfacet + facet normal 0.226886 -0.259726 0.938651 + outer loop + vertex 1.16721 0.900466 2.52103 + vertex 1.16316 0.899287 2.52169 + vertex 1.16503 0.897542 2.52075 + endloop + endfacet + facet normal 0.236234 -0.249899 0.939012 + outer loop + vertex 1.16503 0.897542 2.52075 + vertex 1.16316 0.899287 2.52169 + vertex 1.16194 0.895456 2.52098 + endloop + endfacet + facet normal 0.22119 -0.226558 0.94855 + outer loop + vertex 1.16503 0.897542 2.52075 + vertex 1.16194 0.895456 2.52098 + vertex 1.16375 0.893593 2.52011 + endloop + endfacet + facet normal 0.232991 -0.215023 0.948409 + outer loop + vertex 1.16375 0.893593 2.52011 + vertex 1.16194 0.895456 2.52098 + vertex 1.15981 0.892433 2.52081 + endloop + endfacet + facet normal 0.271667 -0.241293 0.931652 + outer loop + vertex 1.16194 0.895456 2.52098 + vertex 1.15801 0.894196 2.52179 + vertex 1.15981 0.892433 2.52081 + endloop + endfacet + facet normal 0.286723 -0.225617 0.931067 + outer loop + vertex 1.15981 0.892433 2.52081 + vertex 1.15801 0.894196 2.52179 + vertex 1.15691 0.890279 2.52118 + endloop + endfacet + facet normal 0.274848 -0.208342 0.938644 + outer loop + vertex 1.15981 0.892433 2.52081 + vertex 1.15691 0.890279 2.52118 + vertex 1.15878 0.88852 2.52025 + endloop + endfacet + facet normal 0.284809 -0.197438 0.938031 + outer loop + vertex 1.15878 0.88852 2.52025 + vertex 1.15691 0.890279 2.52118 + vertex 1.15517 0.887321 2.52109 + endloop + endfacet + facet normal 0.295231 -0.237804 0.925358 + outer loop + vertex 1.15517 0.887321 2.52109 + vertex 1.15479 0.884095 2.52038 + vertex 1.15878 0.88852 2.52025 + endloop + endfacet + facet normal 0.327007 -0.239042 0.91429 + outer loop + vertex 1.15517 0.887321 2.52109 + vertex 1.15274 0.885189 2.5214 + vertex 1.15479 0.884095 2.52038 + endloop + endfacet + facet normal 0.304084 -0.210736 0.929044 + outer loop + vertex 1.15517 0.887321 2.52109 + vertex 1.15341 0.889067 2.52206 + vertex 1.15274 0.885189 2.5214 + endloop + endfacet + facet normal 0.30542 -0.209325 0.928925 + outer loop + vertex 1.15691 0.890279 2.52118 + vertex 1.15341 0.889067 2.52206 + vertex 1.15517 0.887321 2.52109 + endloop + endfacet + facet normal 0.311155 -0.231042 0.921847 + outer loop + vertex 1.15691 0.890279 2.52118 + vertex 1.15801 0.894196 2.52179 + vertex 1.15341 0.889067 2.52206 + endloop + endfacet + facet normal 0.289921 -0.21137 0.933418 + outer loop + vertex 1.15801 0.894196 2.52179 + vertex 1.1533 0.893911 2.52319 + vertex 1.15341 0.889067 2.52206 + endloop + endfacet + facet normal 0.289787 -0.226987 0.929785 + outer loop + vertex 1.15801 0.894196 2.52179 + vertex 1.15821 0.899005 2.52291 + vertex 1.1533 0.893911 2.52319 + endloop + endfacet + facet normal 0.261818 -0.199212 0.944333 + outer loop + vertex 1.1533 0.893911 2.52319 + vertex 1.15821 0.899005 2.52291 + vertex 1.15356 0.898947 2.52419 + endloop + endfacet + facet normal 0.260757 -0.222498 0.939415 + outer loop + vertex 1.15821 0.899005 2.52291 + vertex 1.15848 0.903847 2.52398 + vertex 1.15356 0.898947 2.52419 + endloop + endfacet + facet normal 0.220308 -0.222484 0.949718 + outer loop + vertex 1.15821 0.899005 2.52291 + vertex 1.16335 0.903972 2.52288 + vertex 1.15848 0.903847 2.52398 + endloop + endfacet + facet normal 0.244881 -0.247975 0.937306 + outer loop + vertex 1.16316 0.899287 2.52169 + vertex 1.16335 0.903972 2.52288 + vertex 1.15821 0.899005 2.52291 + endloop + endfacet + facet normal 0.213193 -0.248604 0.944852 + outer loop + vertex 1.16838 0.90419 2.5218 + vertex 1.16335 0.903972 2.52288 + vertex 1.16316 0.899287 2.52169 + endloop + endfacet + facet normal 0.213081 -0.256858 0.942667 + outer loop + vertex 1.16838 0.90419 2.5218 + vertex 1.16847 0.90884 2.52305 + vertex 1.16335 0.903972 2.52288 + endloop + endfacet + facet normal 0.203473 -0.25722 0.944689 + outer loop + vertex 1.17349 0.908924 2.52199 + vertex 1.16847 0.90884 2.52305 + vertex 1.16838 0.90419 2.5218 + endloop + endfacet + facet normal 0.203436 -0.258161 0.94444 + outer loop + vertex 1.17349 0.908924 2.52199 + vertex 1.17346 0.913758 2.52332 + vertex 1.16847 0.90884 2.52305 + endloop + endfacet + facet normal 0.203274 -0.258001 0.944518 + outer loop + vertex 1.16847 0.90884 2.52305 + vertex 1.17346 0.913758 2.52332 + vertex 1.16848 0.913488 2.52431 + endloop + endfacet + facet normal 0.24498 -0.228064 0.942322 + outer loop + vertex 1.16316 0.899287 2.52169 + vertex 1.15821 0.899005 2.52291 + vertex 1.15801 0.894196 2.52179 + endloop + endfacet + facet normal 0.276376 -0.260147 0.92517 + outer loop + vertex 1.16194 0.895456 2.52098 + vertex 1.16316 0.899287 2.52169 + vertex 1.15801 0.894196 2.52179 + endloop + endfacet + facet normal 0.227921 -0.264105 0.937177 + outer loop + vertex 1.16721 0.900466 2.52103 + vertex 1.16838 0.90419 2.5218 + vertex 1.16316 0.899287 2.52169 + endloop + endfacet + facet normal 0.206601 -0.260532 0.943101 + outer loop + vertex 1.17235 0.905208 2.52121 + vertex 1.17349 0.908924 2.52199 + vertex 1.16838 0.90419 2.5218 + endloop + endfacet + facet normal 0.202057 -0.258243 0.944714 + outer loop + vertex 1.17875 0.913791 2.52219 + vertex 1.17346 0.913758 2.52332 + vertex 1.17349 0.908924 2.52199 + endloop + endfacet + facet normal 0.202172 -0.255892 0.945328 + outer loop + vertex 1.17875 0.913791 2.52219 + vertex 1.17843 0.918776 2.52361 + vertex 1.17346 0.913758 2.52332 + endloop + endfacet + facet normal 0.200823 -0.256051 0.945573 + outer loop + vertex 1.17875 0.913791 2.52219 + vertex 1.18349 0.919082 2.52262 + vertex 1.17843 0.918776 2.52361 + endloop + endfacet + facet normal 0.200014 -0.255356 0.945932 + outer loop + vertex 1.18394 0.915309 2.52151 + vertex 1.18349 0.919082 2.52262 + vertex 1.17875 0.913791 2.52219 + endloop + endfacet + facet normal 0.198862 -0.255548 0.946123 + outer loop + vertex 1.18834 0.919349 2.52167 + vertex 1.18349 0.919082 2.52262 + vertex 1.18394 0.915309 2.52151 + endloop + endfacet + facet normal 0.199348 -0.256068 0.94588 + outer loop + vertex 1.18717 0.915707 2.52094 + vertex 1.18834 0.919349 2.52167 + vertex 1.18394 0.915309 2.52151 + endloop + endfacet + facet normal 0.199498 -0.258152 0.945282 + outer loop + vertex 1.18717 0.915707 2.52094 + vertex 1.18394 0.915309 2.52151 + vertex 1.18483 0.912897 2.52066 + endloop + endfacet + facet normal 0.200322 -0.258803 0.944929 + outer loop + vertex 1.18868 0.913622 2.52004 + vertex 1.18717 0.915707 2.52094 + vertex 1.18483 0.912897 2.52066 + endloop + endfacet + facet normal 0.200628 -0.260996 0.944261 + outer loop + vertex 1.18483 0.912897 2.52066 + vertex 1.18329 0.9087 2.51983 + vertex 1.18868 0.913622 2.52004 + endloop + endfacet + facet normal 0.201865 -0.262322 0.94363 + outer loop + vertex 1.18868 0.913622 2.52004 + vertex 1.18329 0.9087 2.51983 + vertex 1.18835 0.908772 2.51876 + endloop + endfacet + facet normal 0.199305 -0.262295 0.944182 + outer loop + vertex 1.18835 0.908772 2.51876 + vertex 1.19344 0.913628 2.51904 + vertex 1.18868 0.913622 2.52004 + endloop + endfacet + facet normal 0.19944 -0.259804 0.944841 + outer loop + vertex 1.19372 0.918267 2.52026 + vertex 1.18868 0.913622 2.52004 + vertex 1.19344 0.913628 2.51904 + endloop + endfacet + facet normal 0.196479 -0.259792 0.945465 + outer loop + vertex 1.19344 0.913628 2.51904 + vertex 1.1984 0.918434 2.51933 + vertex 1.19372 0.918267 2.52026 + endloop + endfacet + facet normal 0.196524 -0.257255 0.946149 + outer loop + vertex 1.19814 0.922298 2.52043 + vertex 1.19372 0.918267 2.52026 + vertex 1.1984 0.918434 2.51933 + endloop + endfacet + facet normal 0.193371 -0.257625 0.946698 + outer loop + vertex 1.1984 0.918434 2.51933 + vertex 1.20326 0.923766 2.51979 + vertex 1.19814 0.922298 2.52043 + endloop + endfacet + facet normal 0.192853 -0.25552 0.947374 + outer loop + vertex 1.19814 0.922298 2.52043 + vertex 1.20326 0.923766 2.51979 + vertex 1.201 0.926357 2.52095 + endloop + endfacet + facet normal 0.192935 -0.255574 0.947343 + outer loop + vertex 1.19726 0.924719 2.52127 + vertex 1.19814 0.922298 2.52043 + vertex 1.201 0.926357 2.52095 + endloop + endfacet + facet normal 0.193522 -0.257013 0.946833 + outer loop + vertex 1.201 0.926357 2.52095 + vertex 1.19868 0.928852 2.5221 + vertex 1.19726 0.924719 2.52127 + endloop + endfacet + facet normal 0.195983 -0.257715 0.946136 + outer loop + vertex 1.19726 0.924719 2.52127 + vertex 1.19868 0.928852 2.5221 + vertex 1.19332 0.923961 2.52188 + endloop + endfacet + facet normal 0.195653 -0.255452 0.946818 + outer loop + vertex 1.19726 0.924719 2.52127 + vertex 1.19332 0.923961 2.52188 + vertex 1.19497 0.921948 2.52099 + endloop + endfacet + facet normal 0.196495 -0.254766 0.946828 + outer loop + vertex 1.19497 0.921948 2.52099 + vertex 1.19332 0.923961 2.52188 + vertex 1.19213 0.920227 2.52112 + endloop + endfacet + facet normal 0.197331 -0.256191 0.94627 + outer loop + vertex 1.19497 0.921948 2.52099 + vertex 1.19213 0.920227 2.52112 + vertex 1.19372 0.918267 2.52026 + endloop + endfacet + facet normal 0.19783 -0.255787 0.946275 + outer loop + vertex 1.19372 0.918267 2.52026 + vertex 1.19213 0.920227 2.52112 + vertex 1.19003 0.917448 2.52081 + endloop + endfacet + facet normal 0.197811 -0.255773 0.946283 + outer loop + vertex 1.19213 0.920227 2.52112 + vertex 1.18834 0.919349 2.52167 + vertex 1.19003 0.917448 2.52081 + endloop + endfacet + facet normal 0.197681 -0.25508 0.946497 + outer loop + vertex 1.19213 0.920227 2.52112 + vertex 1.19332 0.923961 2.52188 + vertex 1.18834 0.919349 2.52167 + endloop + endfacet + facet normal 0.196898 -0.254251 0.946883 + outer loop + vertex 1.19332 0.923961 2.52188 + vertex 1.18837 0.923868 2.52288 + vertex 1.18834 0.919349 2.52167 + endloop + endfacet + facet normal 0.196873 -0.25499 0.946689 + outer loop + vertex 1.19332 0.923961 2.52188 + vertex 1.19342 0.928724 2.52314 + vertex 1.18837 0.923868 2.52288 + endloop + endfacet + facet normal 0.195747 -0.253848 0.94723 + outer loop + vertex 1.18837 0.923868 2.52288 + vertex 1.19342 0.928724 2.52314 + vertex 1.18849 0.928587 2.52412 + endloop + endfacet + facet normal 0.193542 -0.255099 0.947347 + outer loop + vertex 1.19868 0.928852 2.5221 + vertex 1.19342 0.928724 2.52314 + vertex 1.19332 0.923961 2.52188 + endloop + endfacet + facet normal 0.193472 -0.257597 0.946685 + outer loop + vertex 1.19868 0.928852 2.5221 + vertex 1.19842 0.93375 2.52348 + vertex 1.19342 0.928724 2.52314 + endloop + endfacet + facet normal 0.191109 -0.25532 0.947781 + outer loop + vertex 1.19342 0.928724 2.52314 + vertex 1.19842 0.93375 2.52348 + vertex 1.19345 0.933422 2.5244 + endloop + endfacet + facet normal 0.190335 -0.257914 0.947234 + outer loop + vertex 1.19868 0.928852 2.5221 + vertex 1.20349 0.934127 2.52257 + vertex 1.19842 0.93375 2.52348 + endloop + endfacet + facet normal 0.190395 -0.260388 0.946545 + outer loop + vertex 1.20349 0.934127 2.52257 + vertex 1.20338 0.938714 2.52385 + vertex 1.19842 0.93375 2.52348 + endloop + endfacet + facet normal 0.187668 -0.257757 0.947809 + outer loop + vertex 1.19842 0.93375 2.52348 + vertex 1.20338 0.938714 2.52385 + vertex 1.19831 0.93873 2.52486 + endloop + endfacet + facet normal 0.187555 -0.259808 0.947271 + outer loop + vertex 1.20356 0.943416 2.52511 + vertex 1.19831 0.93873 2.52486 + vertex 1.20338 0.938714 2.52385 + endloop + endfacet + facet normal 0.187623 -0.259807 0.947258 + outer loop + vertex 1.20338 0.938714 2.52385 + vertex 1.20828 0.943446 2.52418 + vertex 1.20356 0.943416 2.52511 + endloop + endfacet + facet normal 0.187611 -0.260061 0.947191 + outer loop + vertex 1.20799 0.947295 2.52529 + vertex 1.20356 0.943416 2.52511 + vertex 1.20828 0.943446 2.52418 + endloop + endfacet + facet normal 0.188908 -0.260497 0.946813 + outer loop + vertex 1.20349 0.934127 2.52257 + vertex 1.20836 0.938858 2.5229 + vertex 1.20338 0.938714 2.52385 + endloop + endfacet + facet normal 0.188894 -0.261082 0.946655 + outer loop + vertex 1.20836 0.938858 2.5229 + vertex 1.20828 0.943446 2.52418 + vertex 1.20338 0.938714 2.52385 + endloop + endfacet + facet normal 0.187187 -0.261197 0.946962 + outer loop + vertex 1.20836 0.938858 2.5229 + vertex 1.21338 0.943698 2.52324 + vertex 1.20828 0.943446 2.52418 + endloop + endfacet + facet normal 0.187187 -0.261324 0.946927 + outer loop + vertex 1.21338 0.943698 2.52324 + vertex 1.21315 0.948681 2.52466 + vertex 1.20828 0.943446 2.52418 + endloop + endfacet + facet normal 0.179339 -0.26206 0.948242 + outer loop + vertex 1.21338 0.943698 2.52324 + vertex 1.21843 0.948637 2.52365 + vertex 1.21315 0.948681 2.52466 + endloop + endfacet + facet normal 0.183157 -0.265817 0.946464 + outer loop + vertex 1.21878 0.943733 2.5222 + vertex 1.21843 0.948637 2.52365 + vertex 1.21338 0.943698 2.52324 + endloop + endfacet + facet normal 0.183339 -0.261801 0.947548 + outer loop + vertex 1.21878 0.943733 2.5222 + vertex 1.21338 0.943698 2.52324 + vertex 1.21338 0.93891 2.52192 + endloop + endfacet + facet normal 0.185634 -0.264305 0.946405 + outer loop + vertex 1.21738 0.93961 2.52133 + vertex 1.21878 0.943733 2.5222 + vertex 1.21338 0.93891 2.52192 + endloop + endfacet + facet normal 0.185324 -0.261929 0.947126 + outer loop + vertex 1.21738 0.93961 2.52133 + vertex 1.21338 0.93891 2.52192 + vertex 1.21503 0.936865 2.52103 + endloop + endfacet + facet normal 0.183211 -0.26022 0.948008 + outer loop + vertex 1.21821 0.937189 2.5205 + vertex 1.21738 0.93961 2.52133 + vertex 1.21503 0.936865 2.52103 + endloop + endfacet + facet normal 0.183165 -0.259378 0.948248 + outer loop + vertex 1.21503 0.936865 2.52103 + vertex 1.21372 0.933222 2.52029 + vertex 1.21821 0.937189 2.5205 + endloop + endfacet + facet normal 0.184386 -0.260729 0.94764 + outer loop + vertex 1.21821 0.937189 2.5205 + vertex 1.21372 0.933222 2.52029 + vertex 1.2184 0.93336 2.51941 + endloop + endfacet + facet normal 0.182293 -0.26093 0.94799 + outer loop + vertex 1.2184 0.93336 2.51941 + vertex 1.22333 0.938619 2.51991 + vertex 1.21821 0.937189 2.5205 + endloop + endfacet + facet normal 0.182266 -0.260815 0.948027 + outer loop + vertex 1.21821 0.937189 2.5205 + vertex 1.22333 0.938619 2.51991 + vertex 1.22117 0.94121 2.52104 + endloop + endfacet + facet normal 0.184027 -0.262481 0.947226 + outer loop + vertex 1.2234 0.933705 2.51854 + vertex 1.22333 0.938619 2.51991 + vertex 1.2184 0.93336 2.51941 + endloop + endfacet + facet normal 0.184033 -0.262801 0.947136 + outer loop + vertex 1.21844 0.92876 2.51813 + vertex 1.2234 0.933705 2.51854 + vertex 1.2184 0.93336 2.51941 + endloop + endfacet + facet normal 0.186975 -0.262628 0.946608 + outer loop + vertex 1.21844 0.92876 2.51813 + vertex 1.2184 0.93336 2.51941 + vertex 1.21349 0.928621 2.51907 + endloop + endfacet + facet normal 0.186991 -0.261959 0.94679 + outer loop + vertex 1.21358 0.924027 2.51778 + vertex 1.21844 0.92876 2.51813 + vertex 1.21349 0.928621 2.51907 + endloop + endfacet + facet normal 0.190208 -0.261734 0.946212 + outer loop + vertex 1.21358 0.924027 2.51778 + vertex 1.21349 0.928621 2.51907 + vertex 1.2085 0.923756 2.51873 + endloop + endfacet + facet normal 0.190209 -0.262594 0.945973 + outer loop + vertex 1.20882 0.918791 2.51728 + vertex 1.21358 0.924027 2.51778 + vertex 1.2085 0.923756 2.51873 + endloop + endfacet + facet normal 0.194077 -0.262154 0.945309 + outer loop + vertex 1.20882 0.918791 2.51728 + vertex 1.2085 0.923756 2.51873 + vertex 1.20345 0.91874 2.51837 + endloop + endfacet + facet normal 0.194004 -0.263771 0.944874 + outer loop + vertex 1.20882 0.918791 2.51728 + vertex 1.20345 0.91874 2.51837 + vertex 1.20343 0.913899 2.51702 + endloop + endfacet + facet normal 0.196542 -0.2665 0.943583 + outer loop + vertex 1.20744 0.91464 2.5164 + vertex 1.20882 0.918791 2.51728 + vertex 1.20343 0.913899 2.51702 + endloop + endfacet + facet normal 0.196748 -0.268016 0.943111 + outer loop + vertex 1.20744 0.91464 2.5164 + vertex 1.20343 0.913899 2.51702 + vertex 1.20511 0.911877 2.5161 + endloop + endfacet + facet normal 0.196876 -0.268116 0.943055 + outer loop + vertex 1.20827 0.912209 2.51553 + vertex 1.20744 0.91464 2.5164 + vertex 1.20511 0.911877 2.5161 + endloop + endfacet + facet normal 0.196917 -0.268913 0.94282 + outer loop + vertex 1.20511 0.911877 2.5161 + vertex 1.20378 0.908212 2.51533 + vertex 1.20827 0.912209 2.51553 + endloop + endfacet + facet normal 0.197272 -0.269302 0.942635 + outer loop + vertex 1.20827 0.912209 2.51553 + vertex 1.20378 0.908212 2.51533 + vertex 1.20843 0.908384 2.51441 + endloop + endfacet + facet normal 0.194721 -0.269541 0.943097 + outer loop + vertex 1.20843 0.908384 2.51441 + vertex 1.21332 0.913642 2.5149 + vertex 1.20827 0.912209 2.51553 + endloop + endfacet + facet normal 0.194287 -0.267745 0.943698 + outer loop + vertex 1.20827 0.912209 2.51553 + vertex 1.21332 0.913642 2.5149 + vertex 1.21119 0.916245 2.51608 + endloop + endfacet + facet normal 0.193559 -0.268334 0.94368 + outer loop + vertex 1.21492 0.917817 2.51576 + vertex 1.21119 0.916245 2.51608 + vertex 1.21332 0.913642 2.5149 + endloop + endfacet + facet normal 0.191814 -0.26777 0.944196 + outer loop + vertex 1.21492 0.917817 2.51576 + vertex 1.21332 0.913642 2.5149 + vertex 1.21863 0.918351 2.51516 + endloop + endfacet + facet normal 0.191805 -0.267673 0.944226 + outer loop + vertex 1.21863 0.918351 2.51516 + vertex 1.21724 0.920524 2.51606 + vertex 1.21492 0.917817 2.51576 + endloop + endfacet + facet normal 0.191812 -0.26768 0.944222 + outer loop + vertex 1.21724 0.920524 2.51606 + vertex 1.21405 0.920253 2.51663 + vertex 1.21492 0.917817 2.51576 + endloop + endfacet + facet normal 0.191797 -0.267224 0.944354 + outer loop + vertex 1.21724 0.920524 2.51606 + vertex 1.21845 0.92415 2.51684 + vertex 1.21405 0.920253 2.51663 + endloop + endfacet + facet normal 0.18984 -0.265068 0.945357 + outer loop + vertex 1.21845 0.92415 2.51684 + vertex 1.21358 0.924027 2.51778 + vertex 1.21405 0.920253 2.51663 + endloop + endfacet + facet normal 0.191018 -0.267011 0.944573 + outer loop + vertex 1.21997 0.922018 2.51593 + vertex 1.21845 0.92415 2.51684 + vertex 1.21724 0.920524 2.51606 + endloop + endfacet + facet normal 0.191479 -0.267884 0.944232 + outer loop + vertex 1.21997 0.922018 2.51593 + vertex 1.21724 0.920524 2.51606 + vertex 1.21863 0.918351 2.51516 + endloop + endfacet + facet normal 0.190303 -0.267524 0.944572 + outer loop + vertex 1.21997 0.922018 2.51593 + vertex 1.21863 0.918351 2.51516 + vertex 1.22309 0.922273 2.51537 + endloop + endfacet + facet normal 0.190758 -0.268029 0.944337 + outer loop + vertex 1.22309 0.922273 2.51537 + vertex 1.21863 0.918351 2.51516 + vertex 1.2233 0.91843 2.51424 + endloop + endfacet + facet normal 0.188998 -0.268216 0.944638 + outer loop + vertex 1.2233 0.91843 2.51424 + vertex 1.22819 0.923705 2.51476 + vertex 1.22309 0.922273 2.51537 + endloop + endfacet + facet normal 0.189005 -0.268248 0.944627 + outer loop + vertex 1.22309 0.922273 2.51537 + vertex 1.22819 0.923705 2.51476 + vertex 1.226 0.926314 2.51594 + endloop + endfacet + facet normal 0.189314 -0.268453 0.944507 + outer loop + vertex 1.22226 0.924727 2.51623 + vertex 1.22309 0.922273 2.51537 + vertex 1.226 0.926314 2.51594 + endloop + endfacet + facet normal 0.189102 -0.267919 0.944701 + outer loop + vertex 1.226 0.926314 2.51594 + vertex 1.22367 0.928851 2.51712 + vertex 1.22226 0.924727 2.51623 + endloop + endfacet + facet normal 0.189981 -0.268168 0.944454 + outer loop + vertex 1.22226 0.924727 2.51623 + vertex 1.22367 0.928851 2.51712 + vertex 1.21845 0.92415 2.51684 + endloop + endfacet + facet normal 0.189941 -0.267777 0.944573 + outer loop + vertex 1.22226 0.924727 2.51623 + vertex 1.21845 0.92415 2.51684 + vertex 1.21997 0.922018 2.51593 + endloop + endfacet + facet normal 0.187 -0.264947 0.945957 + outer loop + vertex 1.22367 0.928851 2.51712 + vertex 1.21844 0.92876 2.51813 + vertex 1.21845 0.92415 2.51684 + endloop + endfacet + facet normal 0.187077 -0.26972 0.944592 + outer loop + vertex 1.2289 0.930344 2.51651 + vertex 1.22367 0.928851 2.51712 + vertex 1.226 0.926314 2.51594 + endloop + endfacet + facet normal 0.188422 -0.270614 0.944069 + outer loop + vertex 1.22977 0.927912 2.51564 + vertex 1.2289 0.930344 2.51651 + vertex 1.226 0.926314 2.51594 + endloop + endfacet + facet normal 0.185968 -0.271566 0.944282 + outer loop + vertex 1.23211 0.930637 2.51596 + vertex 1.2289 0.930344 2.51651 + vertex 1.22977 0.927912 2.51564 + endloop + endfacet + facet normal 0.184899 -0.270702 0.94474 + outer loop + vertex 1.23353 0.928444 2.51506 + vertex 1.23211 0.930637 2.51596 + vertex 1.22977 0.927912 2.51564 + endloop + endfacet + facet normal 0.184662 -0.268188 0.945503 + outer loop + vertex 1.22977 0.927912 2.51564 + vertex 1.22819 0.923705 2.51476 + vertex 1.23353 0.928444 2.51506 + endloop + endfacet + facet normal 0.186395 -0.270084 0.944622 + outer loop + vertex 1.23353 0.928444 2.51506 + vertex 1.22819 0.923705 2.51476 + vertex 1.23331 0.923736 2.51375 + endloop + endfacet + facet normal 0.183154 -0.270108 0.945249 + outer loop + vertex 1.23331 0.923736 2.51375 + vertex 1.2383 0.928493 2.51415 + vertex 1.23353 0.928444 2.51506 + endloop + endfacet + facet normal 0.183003 -0.273628 0.944266 + outer loop + vertex 1.23803 0.932352 2.51532 + vertex 1.23353 0.928444 2.51506 + vertex 1.2383 0.928493 2.51415 + endloop + endfacet + facet normal 0.180152 -0.273961 0.944717 + outer loop + vertex 1.2383 0.928493 2.51415 + vertex 1.24323 0.933744 2.51473 + vertex 1.23803 0.932352 2.51532 + endloop + endfacet + facet normal 0.180112 -0.273789 0.944775 + outer loop + vertex 1.23803 0.932352 2.51532 + vertex 1.24323 0.933744 2.51473 + vertex 1.24097 0.936358 2.51592 + endloop + endfacet + facet normal 0.179611 -0.27345 0.944968 + outer loop + vertex 1.23719 0.934808 2.51619 + vertex 1.23803 0.932352 2.51532 + vertex 1.24097 0.936358 2.51592 + endloop + endfacet + facet normal 0.177424 -0.267753 0.947011 + outer loop + vertex 1.24097 0.936358 2.51592 + vertex 1.23862 0.938882 2.51707 + vertex 1.23719 0.934808 2.51619 + endloop + endfacet + facet normal 0.180738 -0.268722 0.946109 + outer loop + vertex 1.23719 0.934808 2.51619 + vertex 1.23862 0.938882 2.51707 + vertex 1.23336 0.934242 2.51676 + endloop + endfacet + facet normal 0.181172 -0.272971 0.944809 + outer loop + vertex 1.23719 0.934808 2.51619 + vertex 1.23336 0.934242 2.51676 + vertex 1.23487 0.932125 2.51586 + endloop + endfacet + facet normal 0.182798 -0.271821 0.944827 + outer loop + vertex 1.23487 0.932125 2.51586 + vertex 1.23336 0.934242 2.51676 + vertex 1.23211 0.930637 2.51596 + endloop + endfacet + facet normal 0.179003 -0.266815 0.946978 + outer loop + vertex 1.23862 0.938882 2.51707 + vertex 1.23338 0.938793 2.51804 + vertex 1.23336 0.934242 2.51676 + endloop + endfacet + facet normal 0.183095 -0.266627 0.946249 + outer loop + vertex 1.23336 0.934242 2.51676 + vertex 1.23338 0.938793 2.51804 + vertex 1.22848 0.93408 2.51766 + endloop + endfacet + facet normal 0.183043 -0.269438 0.945462 + outer loop + vertex 1.23336 0.934242 2.51676 + vertex 1.22848 0.93408 2.51766 + vertex 1.2289 0.930344 2.51651 + endloop + endfacet + facet normal 0.181016 -0.264547 0.947232 + outer loop + vertex 1.22848 0.93408 2.51766 + vertex 1.23338 0.938793 2.51804 + vertex 1.2284 0.938639 2.51895 + endloop + endfacet + facet normal 0.183568 -0.264378 0.946788 + outer loop + vertex 1.22848 0.93408 2.51766 + vertex 1.2284 0.938639 2.51895 + vertex 1.2234 0.933705 2.51854 + endloop + endfacet + facet normal 0.183608 -0.265995 0.946327 + outer loop + vertex 1.22367 0.928851 2.51712 + vertex 1.22848 0.93408 2.51766 + vertex 1.2234 0.933705 2.51854 + endloop + endfacet + facet normal 0.179116 -0.263436 0.947902 + outer loop + vertex 1.23862 0.938882 2.51707 + vertex 1.23827 0.943643 2.51846 + vertex 1.23338 0.938793 2.51804 + endloop + endfacet + facet normal 0.179178 -0.263496 0.947874 + outer loop + vertex 1.23338 0.938793 2.51804 + vertex 1.23827 0.943643 2.51846 + vertex 1.23331 0.943328 2.51931 + endloop + endfacet + facet normal 0.17715 -0.263667 0.948208 + outer loop + vertex 1.23862 0.938882 2.51707 + vertex 1.24337 0.944039 2.51762 + vertex 1.23827 0.943643 2.51846 + endloop + endfacet + facet normal 0.177295 -0.268458 0.946835 + outer loop + vertex 1.24337 0.944039 2.51762 + vertex 1.24311 0.948497 2.51893 + vertex 1.23827 0.943643 2.51846 + endloop + endfacet + facet normal 0.179131 -0.270205 0.945992 + outer loop + vertex 1.23827 0.943643 2.51846 + vertex 1.24311 0.948497 2.51893 + vertex 1.23806 0.948384 2.51986 + endloop + endfacet + facet normal 0.175707 -0.268624 0.947084 + outer loop + vertex 1.24337 0.944039 2.51762 + vertex 1.24826 0.948795 2.51806 + vertex 1.24311 0.948497 2.51893 + endloop + endfacet + facet normal 0.175854 -0.287573 0.941476 + outer loop + vertex 1.24826 0.948795 2.51806 + vertex 1.24815 0.953781 2.5196 + vertex 1.24311 0.948497 2.51893 + endloop + endfacet + facet normal 0.174126 -0.286025 0.942269 + outer loop + vertex 1.24311 0.948497 2.51893 + vertex 1.24815 0.953781 2.5196 + vertex 1.24286 0.952474 2.52018 + endloop + endfacet + facet normal 0.176988 -0.29974 0.93746 + outer loop + vertex 1.24286 0.952474 2.52018 + vertex 1.24815 0.953781 2.5196 + vertex 1.24601 0.956575 2.5209 + endloop + endfacet + facet normal 0.174038 -0.266977 0.947858 + outer loop + vertex 1.24831 0.944212 2.51676 + vertex 1.24826 0.948795 2.51806 + vertex 1.24337 0.944039 2.51762 + endloop + endfacet + facet normal 0.174105 -0.261872 0.949268 + outer loop + vertex 1.24831 0.944212 2.51676 + vertex 1.24337 0.944039 2.51762 + vertex 1.24387 0.940345 2.51651 + endloop + endfacet + facet normal 0.174424 -0.262228 0.949111 + outer loop + vertex 1.24711 0.940638 2.51599 + vertex 1.24831 0.944212 2.51676 + vertex 1.24387 0.940345 2.51651 + endloop + endfacet + facet normal 0.174675 -0.26784 0.947497 + outer loop + vertex 1.24711 0.940638 2.51599 + vertex 1.24387 0.940345 2.51651 + vertex 1.24478 0.937931 2.51566 + endloop + endfacet + facet normal 0.178713 -0.271115 0.945811 + outer loop + vertex 1.24857 0.938462 2.51509 + vertex 1.24711 0.940638 2.51599 + vertex 1.24478 0.937931 2.51566 + endloop + endfacet + facet normal 0.179136 -0.275617 0.944429 + outer loop + vertex 1.24478 0.937931 2.51566 + vertex 1.24323 0.933744 2.51473 + vertex 1.24857 0.938462 2.51509 + endloop + endfacet + facet normal 0.180666 -0.27729 0.943647 + outer loop + vertex 1.24857 0.938462 2.51509 + vertex 1.24323 0.933744 2.51473 + vertex 1.24849 0.933734 2.51372 + endloop + endfacet + facet normal 0.178237 -0.277374 0.944084 + outer loop + vertex 1.24849 0.933734 2.51372 + vertex 1.25337 0.93851 2.5142 + vertex 1.24857 0.938462 2.51509 + endloop + endfacet + facet normal 0.178433 -0.272759 0.945391 + outer loop + vertex 1.25301 0.94232 2.51537 + vertex 1.24857 0.938462 2.51509 + vertex 1.25337 0.93851 2.5142 + endloop + endfacet + facet normal 0.174882 -0.273254 0.945911 + outer loop + vertex 1.25337 0.93851 2.5142 + vertex 1.25803 0.943542 2.51479 + vertex 1.25301 0.94232 2.51537 + endloop + endfacet + facet normal 0.173181 -0.265022 0.948563 + outer loop + vertex 1.25301 0.94232 2.51537 + vertex 1.25803 0.943542 2.51479 + vertex 1.25586 0.946211 2.51594 + endloop + endfacet + facet normal 0.173225 -0.265052 0.948546 + outer loop + vertex 1.25215 0.944762 2.51621 + vertex 1.25301 0.94232 2.51537 + vertex 1.25586 0.946211 2.51594 + endloop + endfacet + facet normal 0.174286 -0.267963 0.947534 + outer loop + vertex 1.25586 0.946211 2.51594 + vertex 1.25359 0.948786 2.51708 + vertex 1.25215 0.944762 2.51621 + endloop + endfacet + facet normal 0.174594 -0.268055 0.947451 + outer loop + vertex 1.25215 0.944762 2.51621 + vertex 1.25359 0.948786 2.51708 + vertex 1.24831 0.944212 2.51676 + endloop + endfacet + facet normal 0.173999 -0.26215 0.949211 + outer loop + vertex 1.25215 0.944762 2.51621 + vertex 1.24831 0.944212 2.51676 + vertex 1.24987 0.942119 2.5159 + endloop + endfacet + facet normal 0.170117 -0.271523 0.947278 + outer loop + vertex 1.25884 0.950093 2.51651 + vertex 1.25359 0.948786 2.51708 + vertex 1.25586 0.946211 2.51594 + endloop + endfacet + facet normal 0.176187 -0.263932 0.948313 + outer loop + vertex 1.25301 0.94232 2.51537 + vertex 1.25215 0.944762 2.51621 + vertex 1.24987 0.942119 2.5159 + endloop + endfacet + facet normal 0.176094 -0.274315 0.945379 + outer loop + vertex 1.25842 0.93878 2.51334 + vertex 1.25803 0.943542 2.51479 + vertex 1.25337 0.93851 2.5142 + endloop + endfacet + facet normal 0.176111 -0.279267 0.943925 + outer loop + vertex 1.2536 0.934046 2.51284 + vertex 1.25842 0.93878 2.51334 + vertex 1.25337 0.93851 2.5142 + endloop + endfacet + facet normal 0.178352 -0.281437 0.942859 + outer loop + vertex 1.25851 0.934151 2.51194 + vertex 1.25842 0.93878 2.51334 + vertex 1.2536 0.934046 2.51284 + endloop + endfacet + facet normal 0.178347 -0.281595 0.942813 + outer loop + vertex 1.25851 0.934151 2.51194 + vertex 1.2536 0.934046 2.51284 + vertex 1.25402 0.930281 2.51163 + endloop + endfacet + facet normal 0.180705 -0.284232 0.941572 + outer loop + vertex 1.25723 0.930531 2.51109 + vertex 1.25851 0.934151 2.51194 + vertex 1.25402 0.930281 2.51163 + endloop + endfacet + facet normal 0.180599 -0.280252 0.942785 + outer loop + vertex 1.25723 0.930531 2.51109 + vertex 1.25402 0.930281 2.51163 + vertex 1.25485 0.927839 2.51075 + endloop + endfacet + facet normal 0.179128 -0.279035 0.943426 + outer loop + vertex 1.25861 0.928342 2.51018 + vertex 1.25723 0.930531 2.51109 + vertex 1.25485 0.927839 2.51075 + endloop + endfacet + facet normal 0.178768 -0.274907 0.944705 + outer loop + vertex 1.25485 0.927839 2.51075 + vertex 1.25326 0.923677 2.50984 + vertex 1.25861 0.928342 2.51018 + endloop + endfacet + facet normal 0.182189 -0.278702 0.942938 + outer loop + vertex 1.25861 0.928342 2.51018 + vertex 1.25326 0.923677 2.50984 + vertex 1.25846 0.923656 2.50883 + endloop + endfacet + facet normal 0.177763 -0.278791 0.943756 + outer loop + vertex 1.25846 0.923656 2.50883 + vertex 1.26334 0.928387 2.50931 + vertex 1.25861 0.928342 2.51018 + endloop + endfacet + facet normal 0.177623 -0.281969 0.942838 + outer loop + vertex 1.26311 0.93217 2.51048 + vertex 1.25861 0.928342 2.51018 + vertex 1.26334 0.928387 2.50931 + endloop + endfacet + facet normal 0.17372 -0.282393 0.943438 + outer loop + vertex 1.26334 0.928387 2.50931 + vertex 1.26809 0.933405 2.50993 + vertex 1.26311 0.93217 2.51048 + endloop + endfacet + facet normal 0.174152 -0.284445 0.942742 + outer loop + vertex 1.26311 0.93217 2.51048 + vertex 1.26809 0.933405 2.50993 + vertex 1.26605 0.936095 2.51112 + endloop + endfacet + facet normal 0.17432 -0.28456 0.942676 + outer loop + vertex 1.26234 0.93465 2.51137 + vertex 1.26311 0.93217 2.51048 + vertex 1.26605 0.936095 2.51112 + endloop + endfacet + facet normal 0.174172 -0.284153 0.942826 + outer loop + vertex 1.26605 0.936095 2.51112 + vertex 1.26375 0.938764 2.51235 + vertex 1.26234 0.93465 2.51137 + endloop + endfacet + facet normal 0.17696 -0.284932 0.942072 + outer loop + vertex 1.26234 0.93465 2.51137 + vertex 1.26375 0.938764 2.51235 + vertex 1.25851 0.934151 2.51194 + endloop + endfacet + facet normal 0.176946 -0.284756 0.942127 + outer loop + vertex 1.26234 0.93465 2.51137 + vertex 1.25851 0.934151 2.51194 + vertex 1.26 0.931988 2.51101 + endloop + endfacet + facet normal 0.17305 -0.285086 0.942751 + outer loop + vertex 1.26903 0.94006 2.51177 + vertex 1.26375 0.938764 2.51235 + vertex 1.26605 0.936095 2.51112 + endloop + endfacet + facet normal 0.17294 -0.28501 0.942794 + outer loop + vertex 1.2697 0.937419 2.51085 + vertex 1.26903 0.94006 2.51177 + vertex 1.26605 0.936095 2.51112 + endloop + endfacet + facet normal 0.171032 -0.285562 0.942975 + outer loop + vertex 1.27228 0.940059 2.51118 + vertex 1.26903 0.94006 2.51177 + vertex 1.2697 0.937419 2.51085 + endloop + endfacet + facet normal 0.170859 -0.285403 0.943055 + outer loop + vertex 1.2729 0.937417 2.51027 + vertex 1.27228 0.940059 2.51118 + vertex 1.2697 0.937419 2.51085 + endloop + endfacet + facet normal 0.170904 -0.284561 0.943301 + outer loop + vertex 1.2697 0.937419 2.51085 + vertex 1.26809 0.933405 2.50993 + vertex 1.2729 0.937417 2.51027 + endloop + endfacet + facet normal 0.172193 -0.286047 0.942617 + outer loop + vertex 1.2729 0.937417 2.51027 + vertex 1.26809 0.933405 2.50993 + vertex 1.27316 0.933523 2.50904 + endloop + endfacet + facet normal 0.168906 -0.28642 0.943098 + outer loop + vertex 1.27316 0.933523 2.50904 + vertex 1.27814 0.938704 2.50973 + vertex 1.2729 0.937417 2.51027 + endloop + endfacet + facet normal 0.168725 -0.285559 0.943392 + outer loop + vertex 1.2729 0.937417 2.51027 + vertex 1.27814 0.938704 2.50973 + vertex 1.27596 0.941378 2.51092 + endloop + endfacet + facet normal 0.16695 -0.28696 0.943282 + outer loop + vertex 1.27976 0.942828 2.51069 + vertex 1.27596 0.941378 2.51092 + vertex 1.27814 0.938704 2.50973 + endloop + endfacet + facet normal 0.166782 -0.286905 0.943329 + outer loop + vertex 1.27976 0.942828 2.51069 + vertex 1.27814 0.938704 2.50973 + vertex 1.28358 0.943316 2.51017 + endloop + endfacet + facet normal 0.166378 -0.282103 0.944847 + outer loop + vertex 1.28358 0.943316 2.51017 + vertex 1.28214 0.945483 2.51107 + vertex 1.27976 0.942828 2.51069 + endloop + endfacet + facet normal 0.162831 -0.279128 0.946347 + outer loop + vertex 1.28214 0.945483 2.51107 + vertex 1.27889 0.945282 2.51157 + vertex 1.27976 0.942828 2.51069 + endloop + endfacet + facet normal 0.162682 -0.270227 0.948953 + outer loop + vertex 1.28214 0.945483 2.51107 + vertex 1.28337 0.949067 2.51188 + vertex 1.27889 0.945282 2.51157 + endloop + endfacet + facet normal 0.16193 -0.269369 0.949326 + outer loop + vertex 1.28337 0.949067 2.51188 + vertex 1.27838 0.949025 2.51272 + vertex 1.27889 0.945282 2.51157 + endloop + endfacet + facet normal 0.164138 -0.268983 0.949056 + outer loop + vertex 1.27889 0.945282 2.51157 + vertex 1.27838 0.949025 2.51272 + vertex 1.27374 0.944055 2.51211 + endloop + endfacet + facet normal 0.166471 -0.280417 0.945333 + outer loop + vertex 1.27889 0.945282 2.51157 + vertex 1.27374 0.944055 2.51211 + vertex 1.27596 0.941378 2.51092 + endloop + endfacet + facet normal 0.16715 -0.279874 0.945374 + outer loop + vertex 1.27596 0.941378 2.51092 + vertex 1.27374 0.944055 2.51211 + vertex 1.27228 0.940059 2.51118 + endloop + endfacet + facet normal 0.167504 -0.271947 0.947622 + outer loop + vertex 1.27374 0.944055 2.51211 + vertex 1.27838 0.949025 2.51272 + vertex 1.27326 0.948778 2.51355 + endloop + endfacet + facet normal 0.169784 -0.27162 0.94731 + outer loop + vertex 1.27374 0.944055 2.51211 + vertex 1.27326 0.948778 2.51355 + vertex 1.26848 0.943996 2.51303 + endloop + endfacet + facet normal 0.169494 -0.279104 0.945184 + outer loop + vertex 1.27374 0.944055 2.51211 + vertex 1.26848 0.943996 2.51303 + vertex 1.26903 0.94006 2.51177 + endloop + endfacet + facet normal 0.170613 -0.272407 0.946935 + outer loop + vertex 1.26848 0.943996 2.51303 + vertex 1.27326 0.948778 2.51355 + vertex 1.26798 0.948812 2.51451 + endloop + endfacet + facet normal 0.1675 -0.269087 0.948439 + outer loop + vertex 1.27838 0.949025 2.51272 + vertex 1.27807 0.953473 2.51403 + vertex 1.27326 0.948778 2.51355 + endloop + endfacet + facet normal 0.1715 -0.272997 0.946605 + outer loop + vertex 1.27326 0.948778 2.51355 + vertex 1.27807 0.953473 2.51403 + vertex 1.27325 0.953438 2.51489 + endloop + endfacet + facet normal 0.163958 -0.269481 0.948945 + outer loop + vertex 1.27838 0.949025 2.51272 + vertex 1.28322 0.953695 2.51321 + vertex 1.27807 0.953473 2.51403 + endloop + endfacet + facet normal 0.163908 -0.283236 0.94494 + outer loop + vertex 1.28322 0.953695 2.51321 + vertex 1.28296 0.958589 2.51472 + vertex 1.27807 0.953473 2.51403 + endloop + endfacet + facet normal 0.166859 -0.285878 0.943627 + outer loop + vertex 1.27807 0.953473 2.51403 + vertex 1.28296 0.958589 2.51472 + vertex 1.27782 0.957348 2.51525 + endloop + endfacet + facet normal 0.161999 -0.267542 0.94983 + outer loop + vertex 1.28337 0.949067 2.51188 + vertex 1.28322 0.953695 2.51321 + vertex 1.27838 0.949025 2.51272 + endloop + endfacet + facet normal 0.15942 -0.267733 0.950213 + outer loop + vertex 1.28868 0.953628 2.51227 + vertex 1.28322 0.953695 2.51321 + vertex 1.28337 0.949067 2.51188 + endloop + endfacet + facet normal 0.160413 -0.268847 0.949731 + outer loop + vertex 1.28728 0.949557 2.51135 + vertex 1.28868 0.953628 2.51227 + vertex 1.28337 0.949067 2.51188 + endloop + endfacet + facet normal 0.160421 -0.268942 0.949703 + outer loop + vertex 1.28728 0.949557 2.51135 + vertex 1.28337 0.949067 2.51188 + vertex 1.28495 0.946925 2.511 + endloop + endfacet + facet normal 0.165445 -0.273112 0.947649 + outer loop + vertex 1.28811 0.94712 2.51051 + vertex 1.28728 0.949557 2.51135 + vertex 1.28495 0.946925 2.511 + endloop + endfacet + facet normal 0.165579 -0.281983 0.945024 + outer loop + vertex 1.28495 0.946925 2.511 + vertex 1.28358 0.943316 2.51017 + vertex 1.28811 0.94712 2.51051 + endloop + endfacet + facet normal 0.168196 -0.284981 0.943661 + outer loop + vertex 1.28811 0.94712 2.51051 + vertex 1.28358 0.943316 2.51017 + vertex 1.28836 0.943381 2.50933 + endloop + endfacet + facet normal 0.168241 -0.284976 0.943654 + outer loop + vertex 1.28836 0.943381 2.50933 + vertex 1.29313 0.948363 2.50999 + vertex 1.28811 0.94712 2.51051 + endloop + endfacet + facet normal 0.166063 -0.27477 0.947061 + outer loop + vertex 1.28811 0.94712 2.51051 + vertex 1.29313 0.948363 2.50999 + vertex 1.29104 0.950996 2.51112 + endloop + endfacet + facet normal 0.164661 -0.275851 0.946992 + outer loop + vertex 1.29472 0.952312 2.51086 + vertex 1.29104 0.950996 2.51112 + vertex 1.29313 0.948363 2.50999 + endloop + endfacet + facet normal 0.165979 -0.276302 0.94663 + outer loop + vertex 1.29472 0.952312 2.51086 + vertex 1.29313 0.948363 2.50999 + vertex 1.29786 0.9523 2.51031 + endloop + endfacet + facet normal 0.165933 -0.277163 0.946386 + outer loop + vertex 1.29786 0.9523 2.51031 + vertex 1.29728 0.954894 2.51117 + vertex 1.29472 0.952312 2.51086 + endloop + endfacet + facet normal 0.164755 -0.276058 0.946915 + outer loop + vertex 1.29728 0.954894 2.51117 + vertex 1.29404 0.954896 2.51173 + vertex 1.29472 0.952312 2.51086 + endloop + endfacet + facet normal 0.163772 -0.295107 0.941324 + outer loop + vertex 1.29728 0.954894 2.51117 + vertex 1.29884 0.958861 2.51214 + vertex 1.29404 0.954896 2.51173 + endloop + endfacet + facet normal 0.160691 -0.291548 0.942962 + outer loop + vertex 1.29884 0.958861 2.51214 + vertex 1.29362 0.958861 2.51303 + vertex 1.29404 0.954896 2.51173 + endloop + endfacet + facet normal 0.163366 -0.291154 0.942625 + outer loop + vertex 1.29404 0.954896 2.51173 + vertex 1.29362 0.958861 2.51303 + vertex 1.28868 0.953628 2.51227 + endloop + endfacet + facet normal 0.159558 -0.272397 0.948863 + outer loop + vertex 1.29404 0.954896 2.51173 + vertex 1.28868 0.953628 2.51227 + vertex 1.29104 0.950996 2.51112 + endloop + endfacet + facet normal 0.154562 -0.283397 0.946466 + outer loop + vertex 1.28868 0.953628 2.51227 + vertex 1.29362 0.958861 2.51303 + vertex 1.28827 0.958532 2.51381 + endloop + endfacet + facet normal 0.165289 -0.277329 0.94645 + outer loop + vertex 1.29728 0.954894 2.51117 + vertex 1.29786 0.9523 2.51031 + vertex 1.30085 0.956143 2.51091 + endloop + endfacet + facet normal 0.167333 -0.277873 0.945932 + outer loop + vertex 1.29786 0.9523 2.51031 + vertex 1.29313 0.948363 2.50999 + vertex 1.29815 0.948468 2.50913 + endloop + endfacet + facet normal 0.168038 -0.277788 0.945831 + outer loop + vertex 1.29815 0.948468 2.50913 + vertex 1.30288 0.953448 2.50975 + vertex 1.29786 0.9523 2.51031 + endloop + endfacet + facet normal 0.165471 -0.275493 0.946955 + outer loop + vertex 1.30326 0.948741 2.50832 + vertex 1.30288 0.953448 2.50975 + vertex 1.29815 0.948468 2.50913 + endloop + endfacet + facet normal 0.165534 -0.285725 0.943907 + outer loop + vertex 1.29842 0.944099 2.50776 + vertex 1.30326 0.948741 2.50832 + vertex 1.29815 0.948468 2.50913 + endloop + endfacet + facet normal 0.167361 -0.285532 0.943643 + outer loop + vertex 1.29842 0.944099 2.50776 + vertex 1.29815 0.948468 2.50913 + vertex 1.29336 0.94374 2.50855 + endloop + endfacet + facet normal 0.167528 -0.292947 0.941338 + outer loop + vertex 1.29367 0.939131 2.50706 + vertex 1.29842 0.944099 2.50776 + vertex 1.29336 0.94374 2.50855 + endloop + endfacet + facet normal 0.169965 -0.29267 0.940987 + outer loop + vertex 1.29367 0.939131 2.50706 + vertex 1.29336 0.94374 2.50855 + vertex 1.28853 0.938979 2.50794 + endloop + endfacet + facet normal 0.169937 -0.293908 0.940606 + outer loop + vertex 1.29367 0.939131 2.50706 + vertex 1.28853 0.938979 2.50794 + vertex 1.28889 0.935148 2.50668 + endloop + endfacet + facet normal 0.17131 -0.295486 0.939862 + outer loop + vertex 1.29213 0.935169 2.5061 + vertex 1.29367 0.939131 2.50706 + vertex 1.28889 0.935148 2.50668 + endloop + endfacet + facet normal 0.171421 -0.293188 0.940562 + outer loop + vertex 1.29213 0.935169 2.5061 + vertex 1.28889 0.935148 2.50668 + vertex 1.28955 0.932536 2.50574 + endloop + endfacet + facet normal 0.169419 -0.291354 0.941493 + outer loop + vertex 1.29279 0.932524 2.50516 + vertex 1.29213 0.935169 2.5061 + vertex 1.28955 0.932536 2.50574 + endloop + endfacet + facet normal 0.169512 -0.289733 0.941977 + outer loop + vertex 1.28955 0.932536 2.50574 + vertex 1.28802 0.928517 2.50478 + vertex 1.29279 0.932524 2.50516 + endloop + endfacet + facet normal 0.169969 -0.290255 0.941734 + outer loop + vertex 1.29279 0.932524 2.50516 + vertex 1.28802 0.928517 2.50478 + vertex 1.29322 0.928575 2.50386 + endloop + endfacet + facet normal 0.165934 -0.290867 0.942264 + outer loop + vertex 1.29322 0.928575 2.50386 + vertex 1.29808 0.933796 2.50462 + vertex 1.29279 0.932524 2.50516 + endloop + endfacet + facet normal 0.165846 -0.290436 0.942413 + outer loop + vertex 1.29279 0.932524 2.50516 + vertex 1.29808 0.933796 2.50462 + vertex 1.29581 0.936482 2.50585 + endloop + endfacet + facet normal 0.165558 -0.290669 0.942392 + outer loop + vertex 1.29961 0.937917 2.50562 + vertex 1.29581 0.936482 2.50585 + vertex 1.29808 0.933796 2.50462 + endloop + endfacet + facet normal 0.161061 -0.289286 0.943596 + outer loop + vertex 1.29961 0.937917 2.50562 + vertex 1.29808 0.933796 2.50462 + vertex 1.30346 0.938366 2.5051 + endloop + endfacet + facet normal 0.161183 -0.290948 0.943064 + outer loop + vertex 1.30346 0.938366 2.5051 + vertex 1.30202 0.940568 2.50603 + vertex 1.29961 0.937917 2.50562 + endloop + endfacet + facet normal 0.165498 -0.294583 0.941186 + outer loop + vertex 1.30202 0.940568 2.50603 + vertex 1.29879 0.940383 2.50654 + vertex 1.29961 0.937917 2.50562 + endloop + endfacet + facet normal 0.165496 -0.294389 0.941247 + outer loop + vertex 1.30202 0.940568 2.50603 + vertex 1.30335 0.944162 2.50692 + vertex 1.29879 0.940383 2.50654 + endloop + endfacet + facet normal 0.164827 -0.293618 0.941605 + outer loop + vertex 1.30335 0.944162 2.50692 + vertex 1.29842 0.944099 2.50776 + vertex 1.29879 0.940383 2.50654 + endloop + endfacet + facet normal 0.1605 -0.292879 0.942582 + outer loop + vertex 1.30487 0.941988 2.50598 + vertex 1.30335 0.944162 2.50692 + vertex 1.30202 0.940568 2.50603 + endloop + endfacet + facet normal 0.159959 -0.293248 0.94256 + outer loop + vertex 1.30726 0.944619 2.5064 + vertex 1.30335 0.944162 2.50692 + vertex 1.30487 0.941988 2.50598 + endloop + endfacet + facet normal 0.157565 -0.291234 0.943587 + outer loop + vertex 1.30805 0.942132 2.5055 + vertex 1.30726 0.944619 2.5064 + vertex 1.30487 0.941988 2.50598 + endloop + endfacet + facet normal 0.157565 -0.29098 0.943665 + outer loop + vertex 1.30487 0.941988 2.50598 + vertex 1.30346 0.938366 2.5051 + vertex 1.30805 0.942132 2.5055 + endloop + endfacet + facet normal 0.158939 -0.292578 0.94294 + outer loop + vertex 1.30805 0.942132 2.5055 + vertex 1.30346 0.938366 2.5051 + vertex 1.30828 0.938371 2.50429 + endloop + endfacet + facet normal 0.156321 -0.292848 0.943294 + outer loop + vertex 1.30828 0.938371 2.50429 + vertex 1.31312 0.943311 2.50502 + vertex 1.30805 0.942132 2.5055 + endloop + endfacet + facet normal 0.155998 -0.291237 0.943846 + outer loop + vertex 1.30805 0.942132 2.5055 + vertex 1.31312 0.943311 2.50502 + vertex 1.31106 0.946017 2.5062 + endloop + endfacet + facet normal 0.154622 -0.292245 0.943761 + outer loop + vertex 1.3148 0.947289 2.50598 + vertex 1.31106 0.946017 2.5062 + vertex 1.31312 0.943311 2.50502 + endloop + endfacet + facet normal 0.155875 -0.29269 0.943417 + outer loop + vertex 1.3148 0.947289 2.50598 + vertex 1.31312 0.943311 2.50502 + vertex 1.31797 0.947232 2.50544 + endloop + endfacet + facet normal 0.156265 -0.286997 0.9451 + outer loop + vertex 1.31797 0.947232 2.50544 + vertex 1.3174 0.949892 2.50634 + vertex 1.3148 0.947289 2.50598 + endloop + endfacet + facet normal 0.151078 -0.282136 0.947404 + outer loop + vertex 1.3174 0.949892 2.50634 + vertex 1.31408 0.949947 2.50689 + vertex 1.3148 0.947289 2.50598 + endloop + endfacet + facet normal 0.151639 -0.273237 0.94992 + outer loop + vertex 1.3174 0.949892 2.50634 + vertex 1.31882 0.953886 2.50726 + vertex 1.31408 0.949947 2.50689 + endloop + endfacet + facet normal 0.150501 -0.271921 0.950478 + outer loop + vertex 1.31882 0.953886 2.50726 + vertex 1.31348 0.953899 2.50811 + vertex 1.31408 0.949947 2.50689 + endloop + endfacet + facet normal 0.151608 -0.271715 0.950361 + outer loop + vertex 1.31408 0.949947 2.50689 + vertex 1.31348 0.953899 2.50811 + vertex 1.30868 0.948706 2.50739 + endloop + endfacet + facet normal 0.154046 -0.28394 0.946387 + outer loop + vertex 1.31408 0.949947 2.50689 + vertex 1.30868 0.948706 2.50739 + vertex 1.31106 0.946017 2.5062 + endloop + endfacet + facet normal 0.153887 -0.284075 0.946372 + outer loop + vertex 1.31106 0.946017 2.5062 + vertex 1.30868 0.948706 2.50739 + vertex 1.30726 0.944619 2.5064 + endloop + endfacet + facet normal 0.155106 -0.274745 0.948924 + outer loop + vertex 1.30868 0.948706 2.50739 + vertex 1.31348 0.953899 2.50811 + vertex 1.30812 0.953505 2.50887 + endloop + endfacet + facet normal 0.160097 -0.273972 0.948319 + outer loop + vertex 1.30868 0.948706 2.50739 + vertex 1.30812 0.953505 2.50887 + vertex 1.30326 0.948741 2.50832 + endloop + endfacet + facet normal 0.159447 -0.285715 0.944957 + outer loop + vertex 1.30868 0.948706 2.50739 + vertex 1.30326 0.948741 2.50832 + vertex 1.30335 0.944162 2.50692 + endloop + endfacet + facet normal 0.152286 -0.27343 0.94976 + outer loop + vertex 1.32103 0.951117 2.50611 + vertex 1.31882 0.953886 2.50726 + vertex 1.3174 0.949892 2.50634 + endloop + endfacet + facet normal 0.150996 -0.274426 0.949679 + outer loop + vertex 1.324 0.954989 2.50676 + vertex 1.31882 0.953886 2.50726 + vertex 1.32103 0.951117 2.50611 + endloop + endfacet + facet normal 0.151081 -0.274486 0.949648 + outer loop + vertex 1.32469 0.952347 2.50588 + vertex 1.324 0.954989 2.50676 + vertex 1.32103 0.951117 2.50611 + endloop + endfacet + facet normal 0.155097 -0.287245 0.945217 + outer loop + vertex 1.32469 0.952347 2.50588 + vertex 1.32103 0.951117 2.50611 + vertex 1.32304 0.948365 2.50494 + endloop + endfacet + facet normal 0.154639 -0.287085 0.945341 + outer loop + vertex 1.32469 0.952347 2.50588 + vertex 1.32304 0.948365 2.50494 + vertex 1.32787 0.952292 2.50535 + endloop + endfacet + facet normal 0.155197 -0.278628 0.947777 + outer loop + vertex 1.32787 0.952292 2.50535 + vertex 1.32727 0.954943 2.50622 + vertex 1.32469 0.952347 2.50588 + endloop + endfacet + facet normal 0.154038 -0.278928 0.947877 + outer loop + vertex 1.32727 0.954943 2.50622 + vertex 1.32787 0.952292 2.50535 + vertex 1.33092 0.956171 2.50599 + endloop + endfacet + facet normal 0.151906 -0.272152 0.950188 + outer loop + vertex 1.33092 0.956171 2.50599 + vertex 1.32868 0.958891 2.50713 + vertex 1.32727 0.954943 2.50622 + endloop + endfacet + facet normal 0.151006 -0.271881 0.950409 + outer loop + vertex 1.32727 0.954943 2.50622 + vertex 1.32868 0.958891 2.50713 + vertex 1.324 0.954989 2.50676 + endloop + endfacet + facet normal 0.150585 -0.273201 0.950098 + outer loop + vertex 1.33389 0.96003 2.50663 + vertex 1.32868 0.958891 2.50713 + vertex 1.33092 0.956171 2.50599 + endloop + endfacet + facet normal 0.147373 -0.270922 0.951253 + outer loop + vertex 1.3346 0.957392 2.50577 + vertex 1.33389 0.96003 2.50663 + vertex 1.33092 0.956171 2.50599 + endloop + endfacet + facet normal 0.1496 -0.278085 0.948835 + outer loop + vertex 1.3346 0.957392 2.50577 + vertex 1.33092 0.956171 2.50599 + vertex 1.33298 0.95341 2.50486 + endloop + endfacet + facet normal 0.144039 -0.276142 0.950262 + outer loop + vertex 1.3346 0.957392 2.50577 + vertex 1.33298 0.95341 2.50486 + vertex 1.33782 0.957304 2.50526 + endloop + endfacet + facet normal 0.144364 -0.271587 0.951525 + outer loop + vertex 1.33782 0.957304 2.50526 + vertex 1.33719 0.959959 2.50611 + vertex 1.3346 0.957392 2.50577 + endloop + endfacet + facet normal 0.139631 -0.272832 0.951875 + outer loop + vertex 1.33719 0.959959 2.50611 + vertex 1.33782 0.957304 2.50526 + vertex 1.34087 0.961143 2.50591 + endloop + endfacet + facet normal 0.142019 -0.280704 0.949229 + outer loop + vertex 1.34087 0.961143 2.50591 + vertex 1.33863 0.963917 2.50706 + vertex 1.33719 0.959959 2.50611 + endloop + endfacet + facet normal 0.143913 -0.281287 0.948771 + outer loop + vertex 1.33719 0.959959 2.50611 + vertex 1.33863 0.963917 2.50706 + vertex 1.33389 0.96003 2.50663 + endloop + endfacet + facet normal 0.146873 -0.284739 0.947287 + outer loop + vertex 1.33863 0.963917 2.50706 + vertex 1.33331 0.963918 2.50789 + vertex 1.33389 0.96003 2.50663 + endloop + endfacet + facet normal 0.145842 -0.306397 0.940665 + outer loop + vertex 1.33863 0.963917 2.50706 + vertex 1.33814 0.968652 2.50868 + vertex 1.33331 0.963918 2.50789 + endloop + endfacet + facet normal 0.155894 -0.315853 0.935913 + outer loop + vertex 1.33331 0.963918 2.50789 + vertex 1.33814 0.968652 2.50868 + vertex 1.33286 0.968718 2.50958 + endloop + endfacet + facet normal 0.1565 -0.315771 0.93584 + outer loop + vertex 1.33331 0.963918 2.50789 + vertex 1.33286 0.968718 2.50958 + vertex 1.32807 0.963484 2.50862 + endloop + endfacet + facet normal 0.15539 -0.286133 0.945506 + outer loop + vertex 1.32868 0.958891 2.50713 + vertex 1.33331 0.963918 2.50789 + vertex 1.32807 0.963484 2.50862 + endloop + endfacet + facet normal 0.150779 -0.286908 0.946018 + outer loop + vertex 1.32868 0.958891 2.50713 + vertex 1.32807 0.963484 2.50862 + vertex 1.32345 0.958819 2.50794 + endloop + endfacet + facet normal 0.151238 -0.272148 0.950296 + outer loop + vertex 1.32868 0.958891 2.50713 + vertex 1.32345 0.958819 2.50794 + vertex 1.324 0.954989 2.50676 + endloop + endfacet + facet normal 0.153133 -0.28909 0.944975 + outer loop + vertex 1.32345 0.958819 2.50794 + vertex 1.32807 0.963484 2.50862 + vertex 1.32309 0.963129 2.50932 + endloop + endfacet + facet normal 0.153892 -0.31923 0.935098 + outer loop + vertex 1.32807 0.963484 2.50862 + vertex 1.3274 0.967507 2.5101 + vertex 1.32309 0.963129 2.50932 + endloop + endfacet + facet normal 0.159331 -0.318126 0.934564 + outer loop + vertex 1.32807 0.963484 2.50862 + vertex 1.33286 0.968718 2.50958 + vertex 1.3274 0.967507 2.5101 + endloop + endfacet + facet normal 0.136677 -0.307688 0.94162 + outer loop + vertex 1.33863 0.963917 2.50706 + vertex 1.34346 0.968953 2.50801 + vertex 1.33814 0.968652 2.50868 + endloop + endfacet + facet normal 0.137087 -0.340337 0.930257 + outer loop + vertex 1.34346 0.968953 2.50801 + vertex 1.34314 0.973774 2.50982 + vertex 1.33814 0.968652 2.50868 + endloop + endfacet + facet normal 0.134454 -0.338034 0.93148 + outer loop + vertex 1.33814 0.968652 2.50868 + vertex 1.34314 0.973774 2.50982 + vertex 1.33784 0.972721 2.5102 + endloop + endfacet + facet normal 0.141287 -0.31173 0.939608 + outer loop + vertex 1.34391 0.964988 2.50663 + vertex 1.34346 0.968953 2.50801 + vertex 1.33863 0.963917 2.50706 + endloop + endfacet + facet normal 0.132737 -0.312982 0.940438 + outer loop + vertex 1.34881 0.968891 2.50723 + vertex 1.34346 0.968953 2.50801 + vertex 1.34391 0.964988 2.50663 + endloop + endfacet + facet normal 0.135443 -0.316157 0.938989 + outer loop + vertex 1.34723 0.964894 2.50612 + vertex 1.34881 0.968891 2.50723 + vertex 1.34391 0.964988 2.50663 + endloop + endfacet + facet normal 0.137505 -0.289081 0.947378 + outer loop + vertex 1.34723 0.964894 2.50612 + vertex 1.34391 0.964988 2.50663 + vertex 1.34458 0.962331 2.50572 + endloop + endfacet + facet normal 0.137433 -0.289011 0.94741 + outer loop + vertex 1.34782 0.962253 2.50522 + vertex 1.34723 0.964894 2.50612 + vertex 1.34458 0.962331 2.50572 + endloop + endfacet + facet normal 0.138193 -0.277831 0.950638 + outer loop + vertex 1.34458 0.962331 2.50572 + vertex 1.34296 0.958388 2.5048 + vertex 1.34782 0.962253 2.50522 + endloop + endfacet + facet normal 0.142467 -0.282978 0.948487 + outer loop + vertex 1.34782 0.962253 2.50522 + vertex 1.34296 0.958388 2.5048 + vertex 1.3481 0.95843 2.50404 + endloop + endfacet + facet normal 0.140339 -0.283206 0.948735 + outer loop + vertex 1.3481 0.95843 2.50404 + vertex 1.35292 0.963301 2.50478 + vertex 1.34782 0.962253 2.50522 + endloop + endfacet + facet normal 0.142693 -0.296495 0.944314 + outer loop + vertex 1.34782 0.962253 2.50522 + vertex 1.35292 0.963301 2.50478 + vertex 1.35093 0.966082 2.50596 + endloop + endfacet + facet normal 0.142596 -0.285293 0.947773 + outer loop + vertex 1.35319 0.958726 2.50337 + vertex 1.35292 0.963301 2.50478 + vertex 1.3481 0.95843 2.50404 + endloop + endfacet + facet normal 0.1426 -0.285503 0.94771 + outer loop + vertex 1.34836 0.954087 2.50269 + vertex 1.35319 0.958726 2.50337 + vertex 1.3481 0.95843 2.50404 + endloop + endfacet + facet normal 0.144936 -0.285272 0.947424 + outer loop + vertex 1.34836 0.954087 2.50269 + vertex 1.3481 0.95843 2.50404 + vertex 1.34322 0.95375 2.50338 + endloop + endfacet + facet normal 0.144434 -0.287293 0.946891 + outer loop + vertex 1.35353 0.954181 2.50193 + vertex 1.35319 0.958726 2.50337 + vertex 1.34836 0.954087 2.50269 + endloop + endfacet + facet normal 0.137938 -0.288023 0.947637 + outer loop + vertex 1.35353 0.954181 2.50193 + vertex 1.35829 0.959031 2.50272 + vertex 1.35319 0.958726 2.50337 + endloop + endfacet + facet normal 0.13788 -0.285211 0.948495 + outer loop + vertex 1.35829 0.959031 2.50272 + vertex 1.35786 0.963208 2.50403 + vertex 1.35319 0.958726 2.50337 + endloop + endfacet + facet normal 0.130745 -0.28617 0.949217 + outer loop + vertex 1.35829 0.959031 2.50272 + vertex 1.36293 0.963571 2.50344 + vertex 1.35786 0.963208 2.50403 + endloop + endfacet + facet normal 0.130643 -0.286072 0.94926 + outer loop + vertex 1.36352 0.95909 2.50201 + vertex 1.36293 0.963571 2.50344 + vertex 1.35829 0.959031 2.50272 + endloop + endfacet + facet normal 0.130513 -0.290573 0.94791 + outer loop + vertex 1.36352 0.95909 2.50201 + vertex 1.35829 0.959031 2.50272 + vertex 1.35871 0.955292 2.50151 + endloop + endfacet + facet normal 0.13441 -0.295249 0.945919 + outer loop + vertex 1.36198 0.955202 2.50102 + vertex 1.36352 0.95909 2.50201 + vertex 1.35871 0.955292 2.50151 + endloop + endfacet + facet normal 0.134223 -0.297797 0.945146 + outer loop + vertex 1.36198 0.955202 2.50102 + vertex 1.35871 0.955292 2.50151 + vertex 1.35934 0.952656 2.50059 + endloop + endfacet + facet normal 0.133299 -0.296909 0.945556 + outer loop + vertex 1.36264 0.952516 2.50008 + vertex 1.36198 0.955202 2.50102 + vertex 1.35934 0.952656 2.50059 + endloop + endfacet + facet normal 0.133408 -0.295673 0.945928 + outer loop + vertex 1.35934 0.952656 2.50059 + vertex 1.35781 0.948661 2.49956 + vertex 1.36264 0.952516 2.50008 + endloop + endfacet + facet normal 0.13633 -0.299128 0.944424 + outer loop + vertex 1.36264 0.952516 2.50008 + vertex 1.35781 0.948661 2.49956 + vertex 1.36313 0.948597 2.49877 + endloop + endfacet + facet normal 0.129423 -0.300202 0.945055 + outer loop + vertex 1.36313 0.948597 2.49877 + vertex 1.36792 0.953523 2.49968 + vertex 1.36264 0.952516 2.50008 + endloop + endfacet + facet normal 0.1292 -0.298849 0.945514 + outer loop + vertex 1.36264 0.952516 2.50008 + vertex 1.36792 0.953523 2.49968 + vertex 1.36572 0.956338 2.50087 + endloop + endfacet + facet normal 0.124857 -0.302045 0.945082 + outer loop + vertex 1.3695 0.957476 2.50073 + vertex 1.36572 0.956338 2.50087 + vertex 1.36792 0.953523 2.49968 + endloop + endfacet + facet normal 0.124849 -0.302042 0.945084 + outer loop + vertex 1.3695 0.957476 2.50073 + vertex 1.36792 0.953523 2.49968 + vertex 1.3728 0.957328 2.50025 + endloop + endfacet + facet normal 0.125049 -0.299807 0.945769 + outer loop + vertex 1.3728 0.957328 2.50025 + vertex 1.37216 0.960007 2.50118 + vertex 1.3695 0.957476 2.50073 + endloop + endfacet + facet normal 0.120154 -0.295031 0.947903 + outer loop + vertex 1.37216 0.960007 2.50118 + vertex 1.36881 0.960137 2.50165 + vertex 1.3695 0.957476 2.50073 + endloop + endfacet + facet normal 0.120477 -0.291022 0.9491 + outer loop + vertex 1.37216 0.960007 2.50118 + vertex 1.37366 0.963921 2.50219 + vertex 1.36881 0.960137 2.50165 + endloop + endfacet + facet normal 0.117456 -0.287362 0.950593 + outer loop + vertex 1.37366 0.963921 2.50219 + vertex 1.36825 0.963969 2.50288 + vertex 1.36881 0.960137 2.50165 + endloop + endfacet + facet normal 0.122108 -0.286572 0.950245 + outer loop + vertex 1.36881 0.960137 2.50165 + vertex 1.36825 0.963969 2.50288 + vertex 1.36352 0.95909 2.50201 + endloop + endfacet + facet normal 0.123599 -0.295065 0.947449 + outer loop + vertex 1.36881 0.960137 2.50165 + vertex 1.36352 0.95909 2.50201 + vertex 1.36572 0.956338 2.50087 + endloop + endfacet + facet normal 0.117191 -0.293043 0.94889 + outer loop + vertex 1.37366 0.963921 2.50219 + vertex 1.37306 0.968503 2.50368 + vertex 1.36825 0.963969 2.50288 + endloop + endfacet + facet normal 0.120302 -0.296106 0.947549 + outer loop + vertex 1.36825 0.963969 2.50288 + vertex 1.37306 0.968503 2.50368 + vertex 1.36764 0.968589 2.5044 + endloop + endfacet + facet normal 0.123265 -0.29564 0.947313 + outer loop + vertex 1.36825 0.963969 2.50288 + vertex 1.36764 0.968589 2.5044 + vertex 1.36293 0.963571 2.50344 + endloop + endfacet + facet normal 0.114188 -0.293508 0.949112 + outer loop + vertex 1.37366 0.963921 2.50219 + vertex 1.37843 0.968756 2.50312 + vertex 1.37306 0.968503 2.50368 + endloop + endfacet + facet normal 0.114493 -0.317561 0.9413 + outer loop + vertex 1.37843 0.968756 2.50312 + vertex 1.37798 0.973362 2.50472 + vertex 1.37306 0.968503 2.50368 + endloop + endfacet + facet normal 0.113606 -0.316745 0.941683 + outer loop + vertex 1.37306 0.968503 2.50368 + vertex 1.37798 0.973362 2.50472 + vertex 1.37264 0.972414 2.50505 + endloop + endfacet + facet normal 0.117306 -0.317208 0.941073 + outer loop + vertex 1.37843 0.968756 2.50312 + vertex 1.38316 0.973134 2.504 + vertex 1.37798 0.973362 2.50472 + endloop + endfacet + facet normal 0.115208 -0.340175 0.933278 + outer loop + vertex 1.38292 0.977001 2.50544 + vertex 1.37798 0.973362 2.50472 + vertex 1.38316 0.973134 2.504 + endloop + endfacet + facet normal 0.116179 -0.340083 0.933191 + outer loop + vertex 1.38316 0.973134 2.504 + vertex 1.3875 0.977418 2.50502 + vertex 1.38292 0.977001 2.50544 + endloop + endfacet + facet normal 0.112302 -0.336568 0.934939 + outer loop + vertex 1.3884 0.973539 2.50352 + vertex 1.3875 0.977418 2.50502 + vertex 1.38316 0.973134 2.504 + endloop + endfacet + facet normal 0.111207 -0.312166 0.943496 + outer loop + vertex 1.38383 0.96864 2.50244 + vertex 1.3884 0.973539 2.50352 + vertex 1.38316 0.973134 2.504 + endloop + endfacet + facet normal 0.109815 -0.31099 0.944048 + outer loop + vertex 1.38946 0.969714 2.50213 + vertex 1.3884 0.973539 2.50352 + vertex 1.38383 0.96864 2.50244 + endloop + endfacet + facet normal 0.108038 -0.300673 0.947588 + outer loop + vertex 1.38946 0.969714 2.50213 + vertex 1.38383 0.96864 2.50244 + vertex 1.38611 0.965655 2.50123 + endloop + endfacet + facet normal 0.103916 -0.297595 0.94902 + outer loop + vertex 1.3908 0.966444 2.50096 + vertex 1.38946 0.969714 2.50213 + vertex 1.38611 0.965655 2.50123 + endloop + endfacet + facet normal 0.104496 -0.301467 0.947733 + outer loop + vertex 1.38611 0.965655 2.50123 + vertex 1.38732 0.962377 2.50005 + vertex 1.3908 0.966444 2.50096 + endloop + endfacet + facet normal 0.101175 -0.298895 0.948908 + outer loop + vertex 1.38732 0.962377 2.50005 + vertex 1.3929 0.963391 2.49978 + vertex 1.3908 0.966444 2.50096 + endloop + endfacet + facet normal 0.0971929 -0.301483 0.948505 + outer loop + vertex 1.39463 0.96732 2.50085 + vertex 1.3908 0.966444 2.50096 + vertex 1.3929 0.963391 2.49978 + endloop + endfacet + facet normal 0.093389 -0.300039 0.949345 + outer loop + vertex 1.39463 0.96732 2.50085 + vertex 1.3929 0.963391 2.49978 + vertex 1.39772 0.966876 2.5004 + endloop + endfacet + facet normal 0.0943749 -0.294741 0.950906 + outer loop + vertex 1.39772 0.966876 2.5004 + vertex 1.39729 0.969682 2.50132 + vertex 1.39463 0.96732 2.50085 + endloop + endfacet + facet normal 0.0944819 -0.294852 0.95086 + outer loop + vertex 1.39729 0.969682 2.50132 + vertex 1.3941 0.970108 2.50177 + vertex 1.39463 0.96732 2.50085 + endloop + endfacet + facet normal 0.0945932 -0.294215 0.951046 + outer loop + vertex 1.39729 0.969682 2.50132 + vertex 1.39877 0.97362 2.50239 + vertex 1.3941 0.970108 2.50177 + endloop + endfacet + facet normal 0.103135 -0.304832 0.946805 + outer loop + vertex 1.39877 0.97362 2.50239 + vertex 1.3936 0.973911 2.50304 + vertex 1.3941 0.970108 2.50177 + endloop + endfacet + facet normal 0.101204 -0.305123 0.94692 + outer loop + vertex 1.3941 0.970108 2.50177 + vertex 1.3936 0.973911 2.50304 + vertex 1.38946 0.969714 2.50213 + endloop + endfacet + facet normal 0.101911 -0.317459 0.94278 + outer loop + vertex 1.39877 0.97362 2.50239 + vertex 1.39813 0.978189 2.504 + vertex 1.3936 0.973911 2.50304 + endloop + endfacet + facet normal 0.117046 -0.33196 0.936004 + outer loop + vertex 1.3936 0.973911 2.50304 + vertex 1.39813 0.978189 2.504 + vertex 1.39306 0.978451 2.50472 + endloop + endfacet + facet normal 0.109097 -0.333116 0.936553 + outer loop + vertex 1.3936 0.973911 2.50304 + vertex 1.39306 0.978451 2.50472 + vertex 1.3884 0.973539 2.50352 + endloop + endfacet + facet normal 0.109742 -0.316193 0.942326 + outer loop + vertex 1.39877 0.97362 2.50239 + vertex 1.40329 0.978587 2.50353 + vertex 1.39813 0.978189 2.504 + endloop + endfacet + facet normal 0.110649 -0.336305 0.93523 + outer loop + vertex 1.40329 0.978587 2.50353 + vertex 1.40243 0.982559 2.50506 + vertex 1.39813 0.978189 2.504 + endloop + endfacet + facet normal 0.120697 -0.345107 0.93077 + outer loop + vertex 1.39813 0.978189 2.504 + vertex 1.40243 0.982559 2.50506 + vertex 1.39791 0.982099 2.50547 + endloop + endfacet + facet normal 0.100796 -0.308848 0.945755 + outer loop + vertex 1.40434 0.974596 2.50211 + vertex 1.40329 0.978587 2.50353 + vertex 1.39877 0.97362 2.50239 + endloop + endfacet + facet normal 0.0981592 -0.292267 0.951286 + outer loop + vertex 1.40434 0.974596 2.50211 + vertex 1.39877 0.97362 2.50239 + vertex 1.401 0.970481 2.50119 + endloop + endfacet + facet normal 0.0939428 -0.289155 0.952662 + outer loop + vertex 1.40567 0.971071 2.50091 + vertex 1.40434 0.974596 2.50211 + vertex 1.401 0.970481 2.50119 + endloop + endfacet + facet normal 0.0944626 -0.294007 0.951124 + outer loop + vertex 1.401 0.970481 2.50119 + vertex 1.4021 0.967097 2.50004 + vertex 1.40567 0.971071 2.50091 + endloop + endfacet + facet normal 0.0939203 -0.293562 0.951315 + outer loop + vertex 1.4021 0.967097 2.50004 + vertex 1.40701 0.967607 2.49971 + vertex 1.40567 0.971071 2.50091 + endloop + endfacet + facet normal 0.0930406 -0.293897 0.951298 + outer loop + vertex 1.40567 0.971071 2.50091 + vertex 1.40701 0.967607 2.49971 + vertex 1.41039 0.971684 2.50064 + endloop + endfacet + facet normal 0.0922197 -0.286538 0.95362 + outer loop + vertex 1.41039 0.971684 2.50064 + vertex 1.40926 0.975071 2.50177 + vertex 1.40567 0.971071 2.50091 + endloop + endfacet + facet normal 0.0918409 -0.286665 0.953619 + outer loop + vertex 1.41371 0.97529 2.5014 + vertex 1.40926 0.975071 2.50177 + vertex 1.41039 0.971684 2.50064 + endloop + endfacet + facet normal 0.0922797 -0.287036 0.953465 + outer loop + vertex 1.41417 0.972515 2.50052 + vertex 1.41371 0.97529 2.5014 + vertex 1.41039 0.971684 2.50064 + endloop + endfacet + facet normal 0.0941509 -0.295953 0.950551 + outer loop + vertex 1.41417 0.972515 2.50052 + vertex 1.41039 0.971684 2.50064 + vertex 1.41265 0.968621 2.49946 + endloop + endfacet + facet normal 0.0976302 -0.297123 0.949835 + outer loop + vertex 1.41417 0.972515 2.50052 + vertex 1.41265 0.968621 2.49946 + vertex 1.41735 0.972116 2.50007 + endloop + endfacet + facet normal 0.0986053 -0.291285 0.951541 + outer loop + vertex 1.41735 0.972116 2.50007 + vertex 1.41684 0.974865 2.50097 + vertex 1.41417 0.972515 2.50052 + endloop + endfacet + facet normal 0.0997572 -0.291055 0.951491 + outer loop + vertex 1.41684 0.974865 2.50097 + vertex 1.41735 0.972116 2.50007 + vertex 1.42064 0.975742 2.50084 + endloop + endfacet + facet normal 0.101912 -0.300891 0.948198 + outer loop + vertex 1.42064 0.975742 2.50084 + vertex 1.41856 0.978794 2.50203 + vertex 1.41684 0.974865 2.50097 + endloop + endfacet + facet normal 0.0923772 -0.297297 0.950306 + outer loop + vertex 1.41684 0.974865 2.50097 + vertex 1.41856 0.978794 2.50203 + vertex 1.41371 0.97529 2.5014 + endloop + endfacet + facet normal 0.0933694 -0.29858 0.949806 + outer loop + vertex 1.41856 0.978794 2.50203 + vertex 1.41346 0.979096 2.50262 + vertex 1.41371 0.97529 2.5014 + endloop + endfacet + facet normal 0.0913664 -0.319398 0.943206 + outer loop + vertex 1.41856 0.978794 2.50203 + vertex 1.41815 0.983489 2.50366 + vertex 1.41346 0.979096 2.50262 + endloop + endfacet + facet normal 0.0975998 -0.325421 0.940519 + outer loop + vertex 1.41346 0.979096 2.50262 + vertex 1.41815 0.983489 2.50366 + vertex 1.41312 0.983326 2.50412 + endloop + endfacet + facet normal 0.0960213 -0.325585 0.940624 + outer loop + vertex 1.41346 0.979096 2.50262 + vertex 1.41312 0.983326 2.50412 + vertex 1.40849 0.979017 2.5031 + endloop + endfacet + facet normal 0.0963914 -0.302778 0.948174 + outer loop + vertex 1.40926 0.975071 2.50177 + vertex 1.41346 0.979096 2.50262 + vertex 1.40849 0.979017 2.5031 + endloop + endfacet + facet normal 0.0959894 -0.30286 0.948189 + outer loop + vertex 1.40926 0.975071 2.50177 + vertex 1.40849 0.979017 2.5031 + vertex 1.40434 0.974596 2.50211 + endloop + endfacet + facet normal 0.103706 -0.333032 0.937195 + outer loop + vertex 1.40849 0.979017 2.5031 + vertex 1.41312 0.983326 2.50412 + vertex 1.40805 0.983659 2.5048 + endloop + endfacet + facet normal 0.103808 -0.33302 0.937188 + outer loop + vertex 1.40849 0.979017 2.5031 + vertex 1.40805 0.983659 2.5048 + vertex 1.40329 0.978587 2.50353 + endloop + endfacet + facet normal 0.0976002 -0.32878 0.93935 + outer loop + vertex 1.41815 0.983489 2.50366 + vertex 1.41738 0.987432 2.50512 + vertex 1.41312 0.983326 2.50412 + endloop + endfacet + facet normal 0.107204 -0.337701 0.935128 + outer loop + vertex 1.41312 0.983326 2.50412 + vertex 1.41738 0.987432 2.50512 + vertex 1.41298 0.987199 2.50554 + endloop + endfacet + facet normal 0.0958549 -0.318914 0.942924 + outer loop + vertex 1.41856 0.978794 2.50203 + vertex 1.42341 0.983865 2.50325 + vertex 1.41815 0.983489 2.50366 + endloop + endfacet + facet normal 0.0950523 -0.301348 0.948765 + outer loop + vertex 1.42341 0.983865 2.50325 + vertex 1.42269 0.988756 2.50488 + vertex 1.41815 0.983489 2.50366 + endloop + endfacet + facet normal 0.10158 -0.323847 0.94064 + outer loop + vertex 1.42414 0.979797 2.50177 + vertex 1.42341 0.983865 2.50325 + vertex 1.41856 0.978794 2.50203 + endloop + endfacet + facet normal 0.0982201 -0.30327 0.947829 + outer loop + vertex 1.42414 0.979797 2.50177 + vertex 1.41856 0.978794 2.50203 + vertex 1.42064 0.975742 2.50084 + endloop + endfacet + facet normal 0.103751 -0.294374 0.950042 + outer loop + vertex 1.41735 0.972116 2.50007 + vertex 1.42196 0.97253 2.4997 + vertex 1.42064 0.975742 2.50084 + endloop + endfacet + facet normal 0.105302 -0.293746 0.950066 + outer loop + vertex 1.42064 0.975742 2.50084 + vertex 1.42196 0.97253 2.4997 + vertex 1.42531 0.976558 2.50057 + endloop + endfacet + facet normal 0.108402 -0.296087 0.94899 + outer loop + vertex 1.42196 0.97253 2.4997 + vertex 1.42759 0.973644 2.4994 + vertex 1.42531 0.976558 2.50057 + endloop + endfacet + facet normal 0.108381 -0.295969 0.949029 + outer loop + vertex 1.42311 0.968744 2.49838 + vertex 1.42759 0.973644 2.4994 + vertex 1.42196 0.97253 2.4997 + endloop + endfacet + facet normal 0.102906 -0.297657 0.949111 + outer loop + vertex 1.42311 0.968744 2.49838 + vertex 1.42196 0.97253 2.4997 + vertex 1.41787 0.968359 2.49883 + endloop + endfacet + facet normal 0.103359 -0.307563 0.945897 + outer loop + vertex 1.41864 0.963891 2.4973 + vertex 1.42311 0.968744 2.49838 + vertex 1.41787 0.968359 2.49883 + endloop + endfacet + facet normal 0.0997585 -0.308241 0.946063 + outer loop + vertex 1.41864 0.963891 2.4973 + vertex 1.41787 0.968359 2.49883 + vertex 1.41341 0.96417 2.49794 + endloop + endfacet + facet normal 0.0991463 -0.314853 0.943948 + outer loop + vertex 1.41864 0.963891 2.4973 + vertex 1.41341 0.96417 2.49794 + vertex 1.41387 0.960353 2.49662 + endloop + endfacet + facet normal 0.0986822 -0.314274 0.944189 + outer loop + vertex 1.41707 0.959935 2.49614 + vertex 1.41864 0.963891 2.4973 + vertex 1.41387 0.960353 2.49662 + endloop + endfacet + facet normal 0.097826 -0.319082 0.942665 + outer loop + vertex 1.41707 0.959935 2.49614 + vertex 1.41387 0.960353 2.49662 + vertex 1.41438 0.95752 2.4956 + endloop + endfacet + facet normal 0.0996006 -0.320877 0.941869 + outer loop + vertex 1.4176 0.957119 2.49513 + vertex 1.41707 0.959935 2.49614 + vertex 1.41438 0.95752 2.4956 + endloop + endfacet + facet normal 0.0992564 -0.322867 0.941225 + outer loop + vertex 1.41438 0.95752 2.4956 + vertex 1.41289 0.953547 2.4944 + vertex 1.4176 0.957119 2.49513 + endloop + endfacet + facet normal 0.099874 -0.323614 0.940903 + outer loop + vertex 1.4176 0.957119 2.49513 + vertex 1.41289 0.953547 2.4944 + vertex 1.41821 0.953383 2.49378 + endloop + endfacet + facet normal 0.101164 -0.32338 0.940846 + outer loop + vertex 1.41821 0.953383 2.49378 + vertex 1.42221 0.957541 2.49478 + vertex 1.4176 0.957119 2.49513 + endloop + endfacet + facet normal 0.100994 -0.320748 0.941765 + outer loop + vertex 1.4176 0.957119 2.49513 + vertex 1.42221 0.957541 2.49478 + vertex 1.42088 0.960815 2.49603 + endloop + endfacet + facet normal 0.101658 -0.320484 0.941783 + outer loop + vertex 1.42088 0.960815 2.49603 + vertex 1.42221 0.957541 2.49478 + vertex 1.42554 0.961575 2.49579 + endloop + endfacet + facet normal 0.100592 -0.313098 0.944379 + outer loop + vertex 1.42554 0.961575 2.49579 + vertex 1.42423 0.964894 2.49703 + vertex 1.42088 0.960815 2.49603 + endloop + endfacet + facet normal 0.101092 -0.313466 0.944203 + outer loop + vertex 1.42423 0.964894 2.49703 + vertex 1.41864 0.963891 2.4973 + vertex 1.42088 0.960815 2.49603 + endloop + endfacet + facet normal 0.102106 -0.312513 0.94441 + outer loop + vertex 1.42886 0.965286 2.49666 + vertex 1.42423 0.964894 2.49703 + vertex 1.42554 0.961575 2.49579 + endloop + endfacet + facet normal 0.10074 -0.311409 0.944921 + outer loop + vertex 1.42934 0.962458 2.49568 + vertex 1.42886 0.965286 2.49666 + vertex 1.42554 0.961575 2.49579 + endloop + endfacet + facet normal 0.102808 -0.320745 0.94157 + outer loop + vertex 1.42934 0.962458 2.49568 + vertex 1.42554 0.961575 2.49579 + vertex 1.42775 0.958553 2.49452 + endloop + endfacet + facet normal 0.104467 -0.321311 0.941194 + outer loop + vertex 1.42934 0.962458 2.49568 + vertex 1.42775 0.958553 2.49452 + vertex 1.43251 0.96207 2.49519 + endloop + endfacet + facet normal 0.105631 -0.31453 0.943352 + outer loop + vertex 1.43251 0.96207 2.49519 + vertex 1.43204 0.96488 2.49618 + vertex 1.42934 0.962458 2.49568 + endloop + endfacet + facet normal 0.107003 -0.31428 0.943281 + outer loop + vertex 1.43204 0.96488 2.49618 + vertex 1.43251 0.96207 2.49519 + vertex 1.43585 0.965786 2.49605 + endloop + endfacet + facet normal 0.103497 -0.29878 0.948693 + outer loop + vertex 1.43585 0.965786 2.49605 + vertex 1.43364 0.968889 2.49727 + vertex 1.43204 0.96488 2.49618 + endloop + endfacet + facet normal 0.104378 -0.29908 0.948502 + outer loop + vertex 1.43204 0.96488 2.49618 + vertex 1.43364 0.968889 2.49727 + vertex 1.42886 0.965286 2.49666 + endloop + endfacet + facet normal 0.104736 -0.299524 0.948323 + outer loop + vertex 1.43364 0.968889 2.49727 + vertex 1.42839 0.969154 2.49793 + vertex 1.42886 0.965286 2.49666 + endloop + endfacet + facet normal 0.105701 -0.288604 0.951596 + outer loop + vertex 1.43364 0.968889 2.49727 + vertex 1.43298 0.973548 2.49875 + vertex 1.42839 0.969154 2.49793 + endloop + endfacet + facet normal 0.108717 -0.291524 0.950365 + outer loop + vertex 1.42839 0.969154 2.49793 + vertex 1.43298 0.973548 2.49875 + vertex 1.42759 0.973644 2.4994 + endloop + endfacet + facet normal 0.107368 -0.288333 0.951492 + outer loop + vertex 1.43364 0.968889 2.49727 + vertex 1.43826 0.973818 2.49824 + vertex 1.43298 0.973548 2.49875 + endloop + endfacet + facet normal 0.10734 -0.287022 0.951891 + outer loop + vertex 1.43826 0.973818 2.49824 + vertex 1.4377 0.978366 2.49968 + vertex 1.43298 0.973548 2.49875 + endloop + endfacet + facet normal 0.110626 -0.289998 0.950612 + outer loop + vertex 1.43298 0.973548 2.49875 + vertex 1.4377 0.978366 2.49968 + vertex 1.43245 0.9774 2.49999 + endloop + endfacet + facet normal 0.110977 -0.286494 0.951633 + outer loop + vertex 1.43826 0.973818 2.49824 + vertex 1.44277 0.978192 2.49903 + vertex 1.4377 0.978366 2.49968 + endloop + endfacet + facet normal 0.104954 -0.280712 0.954036 + outer loop + vertex 1.4434 0.974067 2.49775 + vertex 1.44277 0.978192 2.49903 + vertex 1.43826 0.973818 2.49824 + endloop + endfacet + facet normal 0.104998 -0.282929 0.953377 + outer loop + vertex 1.43924 0.969882 2.49697 + vertex 1.4434 0.974067 2.49775 + vertex 1.43826 0.973818 2.49824 + endloop + endfacet + facet normal 0.101155 -0.279381 0.954837 + outer loop + vertex 1.44384 0.970286 2.4966 + vertex 1.4434 0.974067 2.49775 + vertex 1.43924 0.969882 2.49697 + endloop + endfacet + facet normal 0.102228 -0.296429 0.949568 + outer loop + vertex 1.44384 0.970286 2.4966 + vertex 1.43924 0.969882 2.49697 + vertex 1.44053 0.966575 2.49579 + endloop + endfacet + facet normal 0.0996714 -0.294342 0.950488 + outer loop + vertex 1.44434 0.967491 2.49568 + vertex 1.44384 0.970286 2.4966 + vertex 1.44053 0.966575 2.49579 + endloop + endfacet + facet normal 0.103923 -0.312866 0.944095 + outer loop + vertex 1.44434 0.967491 2.49568 + vertex 1.44053 0.966575 2.49579 + vertex 1.44272 0.963548 2.49455 + endloop + endfacet + facet normal 0.109196 -0.314685 0.942894 + outer loop + vertex 1.44434 0.967491 2.49568 + vertex 1.44272 0.963548 2.49455 + vertex 1.44748 0.967117 2.49519 + endloop + endfacet + facet normal 0.111301 -0.302058 0.94677 + outer loop + vertex 1.44748 0.967117 2.49519 + vertex 1.44701 0.969917 2.49614 + vertex 1.44434 0.967491 2.49568 + endloop + endfacet + facet normal 0.115534 -0.301262 0.946516 + outer loop + vertex 1.44701 0.969917 2.49614 + vertex 1.44748 0.967117 2.49519 + vertex 1.45076 0.970842 2.49597 + endloop + endfacet + facet normal 0.11076 -0.280709 0.953381 + outer loop + vertex 1.45076 0.970842 2.49597 + vertex 1.44856 0.973879 2.49712 + vertex 1.44701 0.969917 2.49614 + endloop + endfacet + facet normal 0.105416 -0.278896 0.954518 + outer loop + vertex 1.44701 0.969917 2.49614 + vertex 1.44856 0.973879 2.49712 + vertex 1.44384 0.970286 2.4966 + endloop + endfacet + facet normal 0.110805 -0.280678 0.953384 + outer loop + vertex 1.45408 0.974942 2.4968 + vertex 1.44856 0.973879 2.49712 + vertex 1.45076 0.970842 2.49597 + endloop + endfacet + facet normal 0.113942 -0.28301 0.952325 + outer loop + vertex 1.45536 0.97169 2.49568 + vertex 1.45408 0.974942 2.4968 + vertex 1.45076 0.970842 2.49597 + endloop + endfacet + facet normal 0.116684 -0.299811 0.946836 + outer loop + vertex 1.45076 0.970842 2.49597 + vertex 1.45203 0.967561 2.49478 + vertex 1.45536 0.97169 2.49568 + endloop + endfacet + facet normal 0.117454 -0.300372 0.946563 + outer loop + vertex 1.45203 0.967561 2.49478 + vertex 1.45759 0.968701 2.49445 + vertex 1.45536 0.97169 2.49568 + endloop + endfacet + facet normal 0.119002 -0.308759 0.943667 + outer loop + vertex 1.45307 0.963721 2.49339 + vertex 1.45759 0.968701 2.49445 + vertex 1.45203 0.967561 2.49478 + endloop + endfacet + facet normal 0.112891 -0.310487 0.94385 + outer loop + vertex 1.45307 0.963721 2.49339 + vertex 1.45203 0.967561 2.49478 + vertex 1.44789 0.963313 2.49388 + endloop + endfacet + facet normal 0.113041 -0.31366 0.942783 + outer loop + vertex 1.44859 0.958839 2.49231 + vertex 1.45307 0.963721 2.49339 + vertex 1.44789 0.963313 2.49388 + endloop + endfacet + facet normal 0.106261 -0.314848 0.943175 + outer loop + vertex 1.44859 0.958839 2.49231 + vertex 1.44789 0.963313 2.49388 + vertex 1.44341 0.959102 2.49298 + endloop + endfacet + facet normal 0.106173 -0.315798 0.942867 + outer loop + vertex 1.44859 0.958839 2.49231 + vertex 1.44341 0.959102 2.49298 + vertex 1.44386 0.955312 2.49166 + endloop + endfacet + facet normal 0.10359 -0.312583 0.944225 + outer loop + vertex 1.44703 0.954901 2.49117 + vertex 1.44859 0.958839 2.49231 + vertex 1.44386 0.955312 2.49166 + endloop + endfacet + facet normal 0.102821 -0.316913 0.942865 + outer loop + vertex 1.44703 0.954901 2.49117 + vertex 1.44386 0.955312 2.49166 + vertex 1.44437 0.952502 2.49066 + endloop + endfacet + facet normal 0.105942 -0.320065 0.941454 + outer loop + vertex 1.44755 0.952103 2.49016 + vertex 1.44703 0.954901 2.49117 + vertex 1.44437 0.952502 2.49066 + endloop + endfacet + facet normal 0.105317 -0.323625 0.940306 + outer loop + vertex 1.44437 0.952502 2.49066 + vertex 1.44284 0.948527 2.48946 + vertex 1.44755 0.952103 2.49016 + endloop + endfacet + facet normal 0.106274 -0.324785 0.939798 + outer loop + vertex 1.44755 0.952103 2.49016 + vertex 1.44284 0.948527 2.48946 + vertex 1.44816 0.948395 2.48881 + endloop + endfacet + facet normal 0.109391 -0.32421 0.939639 + outer loop + vertex 1.44816 0.948395 2.48881 + vertex 1.45211 0.952529 2.48978 + vertex 1.44755 0.952103 2.49016 + endloop + endfacet + facet normal 0.109075 -0.319257 0.94137 + outer loop + vertex 1.44755 0.952103 2.49016 + vertex 1.45211 0.952529 2.48978 + vertex 1.45078 0.955774 2.49103 + endloop + endfacet + facet normal 0.111543 -0.31826 0.941418 + outer loop + vertex 1.45078 0.955774 2.49103 + vertex 1.45211 0.952529 2.48978 + vertex 1.45541 0.95656 2.49075 + endloop + endfacet + facet normal 0.110755 -0.312944 0.943292 + outer loop + vertex 1.45541 0.95656 2.49075 + vertex 1.45412 0.959857 2.492 + vertex 1.45078 0.955774 2.49103 + endloop + endfacet + facet normal 0.110283 -0.312598 0.943462 + outer loop + vertex 1.45412 0.959857 2.492 + vertex 1.44859 0.958839 2.49231 + vertex 1.45078 0.955774 2.49103 + endloop + endfacet + facet normal 0.113126 -0.312027 0.943314 + outer loop + vertex 1.45874 0.960307 2.49159 + vertex 1.45412 0.959857 2.492 + vertex 1.45541 0.95656 2.49075 + endloop + endfacet + facet normal 0.11181 -0.310971 0.94382 + outer loop + vertex 1.45924 0.957526 2.49061 + vertex 1.45874 0.960307 2.49159 + vertex 1.45541 0.95656 2.49075 + endloop + endfacet + facet normal 0.11324 -0.316954 0.941657 + outer loop + vertex 1.45924 0.957526 2.49061 + vertex 1.45541 0.95656 2.49075 + vertex 1.45767 0.953612 2.48949 + endloop + endfacet + facet normal 0.112996 -0.316872 0.941713 + outer loop + vertex 1.45924 0.957526 2.49061 + vertex 1.45767 0.953612 2.48949 + vertex 1.46258 0.957319 2.49014 + endloop + endfacet + facet normal 0.113559 -0.311612 0.943399 + outer loop + vertex 1.46258 0.957319 2.49014 + vertex 1.46196 0.960016 2.49111 + vertex 1.45924 0.957526 2.49061 + endloop + endfacet + facet normal 0.113321 -0.31167 0.943409 + outer loop + vertex 1.46196 0.960016 2.49111 + vertex 1.46258 0.957319 2.49014 + vertex 1.46574 0.9611 2.49101 + endloop + endfacet + facet normal 0.111441 -0.304902 0.945841 + outer loop + vertex 1.46574 0.9611 2.49101 + vertex 1.46354 0.963964 2.4922 + vertex 1.46196 0.960016 2.49111 + endloop + endfacet + facet normal 0.113446 -0.305578 0.945385 + outer loop + vertex 1.46196 0.960016 2.49111 + vertex 1.46354 0.963964 2.4922 + vertex 1.45874 0.960307 2.49159 + endloop + endfacet + facet normal 0.114792 -0.307231 0.944686 + outer loop + vertex 1.46354 0.963964 2.4922 + vertex 1.45831 0.964161 2.4929 + vertex 1.45874 0.960307 2.49159 + endloop + endfacet + facet normal 0.115258 -0.301375 0.946514 + outer loop + vertex 1.46354 0.963964 2.4922 + vertex 1.46295 0.968601 2.49374 + vertex 1.45831 0.964161 2.4929 + endloop + endfacet + facet normal 0.118856 -0.304843 0.944957 + outer loop + vertex 1.45831 0.964161 2.4929 + vertex 1.46295 0.968601 2.49374 + vertex 1.45759 0.968701 2.49445 + endloop + endfacet + facet normal 0.116599 -0.301172 0.946414 + outer loop + vertex 1.46354 0.963964 2.4922 + vertex 1.46829 0.968833 2.49316 + vertex 1.46295 0.968601 2.49374 + endloop + endfacet + facet normal 0.111717 -0.296798 0.948383 + outer loop + vertex 1.46884 0.964895 2.49186 + vertex 1.46829 0.968833 2.49316 + vertex 1.46354 0.963964 2.4922 + endloop + endfacet + facet normal 0.11523 -0.296226 0.948141 + outer loop + vertex 1.47368 0.968692 2.49246 + vertex 1.46829 0.968833 2.49316 + vertex 1.46884 0.964895 2.49186 + endloop + endfacet + facet normal 0.112575 -0.293049 0.949447 + outer loop + vertex 1.47215 0.964655 2.4914 + vertex 1.47368 0.968692 2.49246 + vertex 1.46884 0.964895 2.49186 + endloop + endfacet + facet normal 0.111693 -0.300735 0.947145 + outer loop + vertex 1.47215 0.964655 2.4914 + vertex 1.46884 0.964895 2.49186 + vertex 1.4695 0.96217 2.49092 + endloop + endfacet + facet normal 0.115564 -0.304541 0.945463 + outer loop + vertex 1.47264 0.961875 2.49044 + vertex 1.47215 0.964655 2.4914 + vertex 1.4695 0.96217 2.49092 + endloop + endfacet + facet normal 0.114571 -0.311575 0.943289 + outer loop + vertex 1.4695 0.96217 2.49092 + vertex 1.46786 0.958263 2.48983 + vertex 1.47264 0.961875 2.49044 + endloop + endfacet + facet normal 0.114363 -0.311318 0.943399 + outer loop + vertex 1.47264 0.961875 2.49044 + vertex 1.46786 0.958263 2.48983 + vertex 1.47301 0.958083 2.48915 + endloop + endfacet + facet normal 0.12058 -0.310534 0.942884 + outer loop + vertex 1.47301 0.958083 2.48915 + vertex 1.47715 0.962363 2.49003 + vertex 1.47264 0.961875 2.49044 + endloop + endfacet + facet normal 0.120038 -0.303498 0.945241 + outer loop + vertex 1.47264 0.961875 2.49044 + vertex 1.47715 0.962363 2.49003 + vertex 1.47589 0.965636 2.49124 + endloop + endfacet + facet normal 0.124616 -0.301728 0.945215 + outer loop + vertex 1.47589 0.965636 2.49124 + vertex 1.47715 0.962363 2.49003 + vertex 1.48045 0.966499 2.49091 + endloop + endfacet + facet normal 0.123753 -0.296503 0.94698 + outer loop + vertex 1.48045 0.966499 2.49091 + vertex 1.47921 0.969789 2.4921 + vertex 1.47589 0.965636 2.49124 + endloop + endfacet + facet normal 0.11976 -0.293604 0.948395 + outer loop + vertex 1.47921 0.969789 2.4921 + vertex 1.47368 0.968692 2.49246 + vertex 1.47589 0.965636 2.49124 + endloop + endfacet + facet normal 0.125417 -0.295868 0.94696 + outer loop + vertex 1.48373 0.970286 2.49166 + vertex 1.47921 0.969789 2.4921 + vertex 1.48045 0.966499 2.49091 + endloop + endfacet + facet normal 0.125485 -0.296737 0.946679 + outer loop + vertex 1.48373 0.970286 2.49166 + vertex 1.48338 0.974052 2.49289 + vertex 1.47921 0.969789 2.4921 + endloop + endfacet + facet normal 0.121483 -0.293128 0.948324 + outer loop + vertex 1.47921 0.969789 2.4921 + vertex 1.48338 0.974052 2.49289 + vertex 1.47832 0.973729 2.49344 + endloop + endfacet + facet normal 0.119751 -0.293552 0.948413 + outer loop + vertex 1.47921 0.969789 2.4921 + vertex 1.47832 0.973729 2.49344 + vertex 1.47368 0.968692 2.49246 + endloop + endfacet + facet normal 0.118401 -0.292411 0.948935 + outer loop + vertex 1.47368 0.968692 2.49246 + vertex 1.47832 0.973729 2.49344 + vertex 1.47307 0.973405 2.49399 + endloop + endfacet + facet normal 0.11545 -0.292867 0.949158 + outer loop + vertex 1.47368 0.968692 2.49246 + vertex 1.47307 0.973405 2.49399 + vertex 1.46829 0.968833 2.49316 + endloop + endfacet + facet normal 0.117362 -0.294718 0.94835 + outer loop + vertex 1.46829 0.968833 2.49316 + vertex 1.47307 0.973405 2.49399 + vertex 1.46772 0.973503 2.49468 + endloop + endfacet + facet normal 0.116543 -0.29484 0.948413 + outer loop + vertex 1.46829 0.968833 2.49316 + vertex 1.46772 0.973503 2.49468 + vertex 1.46295 0.968601 2.49374 + endloop + endfacet + facet normal 0.120339 -0.298233 0.946877 + outer loop + vertex 1.46295 0.968601 2.49374 + vertex 1.46772 0.973503 2.49468 + vertex 1.46242 0.97251 2.49504 + endloop + endfacet + facet normal 0.119239 -0.298412 0.94696 + outer loop + vertex 1.46242 0.97251 2.49504 + vertex 1.45759 0.968701 2.49445 + vertex 1.46295 0.968601 2.49374 + endloop + endfacet + facet normal 0.118743 -0.288565 0.950069 + outer loop + vertex 1.46242 0.97251 2.49504 + vertex 1.46772 0.973503 2.49468 + vertex 1.46549 0.976316 2.49582 + endloop + endfacet + facet normal 0.120866 -0.290128 0.949325 + outer loop + vertex 1.46177 0.975207 2.49595 + vertex 1.46242 0.97251 2.49504 + vertex 1.46549 0.976316 2.49582 + endloop + endfacet + facet normal 0.11749 -0.278317 0.953276 + outer loop + vertex 1.46549 0.976316 2.49582 + vertex 1.46331 0.979081 2.49689 + vertex 1.46177 0.975207 2.49595 + endloop + endfacet + facet normal 0.115354 -0.27992 0.953068 + outer loop + vertex 1.46857 0.980114 2.49656 + vertex 1.46331 0.979081 2.49689 + vertex 1.46549 0.976316 2.49582 + endloop + endfacet + facet normal 0.115167 -0.279781 0.953131 + outer loop + vertex 1.46927 0.977466 2.4957 + vertex 1.46857 0.980114 2.49656 + vertex 1.46549 0.976316 2.49582 + endloop + endfacet + facet normal 0.114236 -0.280038 0.953168 + outer loop + vertex 1.47193 0.980006 2.49612 + vertex 1.46857 0.980114 2.49656 + vertex 1.46927 0.977466 2.4957 + endloop + endfacet + facet normal 0.117119 -0.282866 0.951982 + outer loop + vertex 1.4726 0.977329 2.49525 + vertex 1.47193 0.980006 2.49612 + vertex 1.46927 0.977466 2.4957 + endloop + endfacet + facet normal 0.116647 -0.288745 0.950274 + outer loop + vertex 1.46927 0.977466 2.4957 + vertex 1.46772 0.973503 2.49468 + vertex 1.4726 0.977329 2.49525 + endloop + endfacet + facet normal 0.117636 -0.289937 0.949789 + outer loop + vertex 1.4726 0.977329 2.49525 + vertex 1.46772 0.973503 2.49468 + vertex 1.47307 0.973405 2.49399 + endloop + endfacet + facet normal 0.118151 -0.289862 0.949747 + outer loop + vertex 1.47307 0.973405 2.49399 + vertex 1.47782 0.978307 2.4949 + vertex 1.4726 0.977329 2.49525 + endloop + endfacet + facet normal 0.118332 -0.290024 0.949676 + outer loop + vertex 1.47832 0.973729 2.49344 + vertex 1.47782 0.978307 2.4949 + vertex 1.47307 0.973405 2.49399 + endloop + endfacet + facet normal 0.118001 -0.290069 0.949703 + outer loop + vertex 1.47832 0.973729 2.49344 + vertex 1.48283 0.978161 2.49423 + vertex 1.47782 0.978307 2.4949 + endloop + endfacet + facet normal 0.11679 -0.282953 0.951997 + outer loop + vertex 1.47193 0.980006 2.49612 + vertex 1.4726 0.977329 2.49525 + vertex 1.47571 0.981144 2.496 + endloop + endfacet + facet normal 0.114297 -0.279154 0.95342 + outer loop + vertex 1.47193 0.980006 2.49612 + vertex 1.47344 0.983924 2.49709 + vertex 1.46857 0.980114 2.49656 + endloop + endfacet + facet normal 0.117004 -0.282435 0.952124 + outer loop + vertex 1.47344 0.983924 2.49709 + vertex 1.46805 0.98396 2.49776 + vertex 1.46857 0.980114 2.49656 + endloop + endfacet + facet normal 0.116341 -0.297448 0.947623 + outer loop + vertex 1.47344 0.983924 2.49709 + vertex 1.47291 0.988576 2.49862 + vertex 1.46805 0.98396 2.49776 + endloop + endfacet + facet normal 0.128007 -0.308796 0.942475 + outer loop + vertex 1.46805 0.98396 2.49776 + vertex 1.47291 0.988576 2.49862 + vertex 1.46756 0.988678 2.49937 + endloop + endfacet + facet normal 0.117354 -0.3102 0.9434 + outer loop + vertex 1.46805 0.98396 2.49776 + vertex 1.46756 0.988678 2.49937 + vertex 1.46273 0.98357 2.4983 + endloop + endfacet + facet normal 0.116219 -0.282971 0.952061 + outer loop + vertex 1.46331 0.979081 2.49689 + vertex 1.46805 0.98396 2.49776 + vertex 1.46273 0.98357 2.4983 + endloop + endfacet + facet normal 0.113087 -0.283449 0.952296 + outer loop + vertex 1.46331 0.979081 2.49689 + vertex 1.46273 0.98357 2.4983 + vertex 1.4582 0.979142 2.49752 + endloop + endfacet + facet normal 0.11531 -0.285564 0.951397 + outer loop + vertex 1.4582 0.979142 2.49752 + vertex 1.46273 0.98357 2.4983 + vertex 1.45762 0.983235 2.49882 + endloop + endfacet + facet normal 0.112883 -0.285965 0.951568 + outer loop + vertex 1.4582 0.979142 2.49752 + vertex 1.45762 0.983235 2.49882 + vertex 1.45311 0.978815 2.49802 + endloop + endfacet + facet normal 0.112474 -0.274187 0.955077 + outer loop + vertex 1.45408 0.974942 2.4968 + vertex 1.4582 0.979142 2.49752 + vertex 1.45311 0.978815 2.49802 + endloop + endfacet + facet normal 0.112525 -0.274233 0.955057 + outer loop + vertex 1.45862 0.975441 2.4964 + vertex 1.4582 0.979142 2.49752 + vertex 1.45408 0.974942 2.4968 + endloop + endfacet + facet normal 0.113527 -0.274097 0.954978 + outer loop + vertex 1.46331 0.979081 2.49689 + vertex 1.4582 0.979142 2.49752 + vertex 1.45862 0.975441 2.4964 + endloop + endfacet + facet normal 0.121701 -0.294305 0.947931 + outer loop + vertex 1.45311 0.978815 2.49802 + vertex 1.45762 0.983235 2.49882 + vertex 1.45255 0.983422 2.49952 + endloop + endfacet + facet normal 0.111911 -0.295747 0.948689 + outer loop + vertex 1.45311 0.978815 2.49802 + vertex 1.45255 0.983422 2.49952 + vertex 1.44787 0.978451 2.49853 + endloop + endfacet + facet normal 0.116365 -0.317778 0.940998 + outer loop + vertex 1.46273 0.98357 2.4983 + vertex 1.46195 0.987534 2.49973 + vertex 1.45762 0.983235 2.49882 + endloop + endfacet + facet normal 0.123156 -0.323983 0.938012 + outer loop + vertex 1.45762 0.983235 2.49882 + vertex 1.46195 0.987534 2.49973 + vertex 1.45742 0.987088 2.50017 + endloop + endfacet + facet normal 0.1255 -0.361955 0.923709 + outer loop + vertex 1.45742 0.987088 2.50017 + vertex 1.46195 0.987534 2.49973 + vertex 1.46094 0.990919 2.5012 + endloop + endfacet + facet normal 0.134978 -0.359031 0.923514 + outer loop + vertex 1.46094 0.990919 2.5012 + vertex 1.46195 0.987534 2.49973 + vertex 1.46556 0.991781 2.50086 + endloop + endfacet + facet normal 0.132431 -0.342793 0.93003 + outer loop + vertex 1.46556 0.991781 2.50086 + vertex 1.46432 0.995026 2.50223 + vertex 1.46094 0.990919 2.5012 + endloop + endfacet + facet normal 0.113177 -0.328832 0.937582 + outer loop + vertex 1.46432 0.995026 2.50223 + vertex 1.4588 0.993963 2.50252 + vertex 1.46094 0.990919 2.5012 + endloop + endfacet + facet normal 0.131447 -0.356434 0.925028 + outer loop + vertex 1.46195 0.987534 2.49973 + vertex 1.46756 0.988678 2.49937 + vertex 1.46556 0.991781 2.50086 + endloop + endfacet + facet normal 0.124203 -0.316078 0.940568 + outer loop + vertex 1.46273 0.98357 2.4983 + vertex 1.46756 0.988678 2.49937 + vertex 1.46195 0.987534 2.49973 + endloop + endfacet + facet normal 0.126542 -0.330898 0.935144 + outer loop + vertex 1.47259 0.992587 2.50008 + vertex 1.46756 0.988678 2.49937 + vertex 1.47291 0.988576 2.49862 + endloop + endfacet + facet normal 0.14273 -0.350041 0.925797 + outer loop + vertex 1.46937 0.992815 2.50066 + vertex 1.46756 0.988678 2.49937 + vertex 1.47259 0.992587 2.50008 + endloop + endfacet + facet normal 0.142253 -0.349875 0.925933 + outer loop + vertex 1.46937 0.992815 2.50066 + vertex 1.46556 0.991781 2.50086 + vertex 1.46756 0.988678 2.49937 + endloop + endfacet + facet normal 0.115831 -0.282622 0.952212 + outer loop + vertex 1.46857 0.980114 2.49656 + vertex 1.46805 0.98396 2.49776 + vertex 1.46331 0.979081 2.49689 + endloop + endfacet + facet normal 0.117932 -0.289173 0.949985 + outer loop + vertex 1.46927 0.977466 2.4957 + vertex 1.46549 0.976316 2.49582 + vertex 1.46772 0.973503 2.49468 + endloop + endfacet + facet normal 0.12149 -0.293365 0.948249 + outer loop + vertex 1.48338 0.974052 2.49289 + vertex 1.48283 0.978161 2.49423 + vertex 1.47832 0.973729 2.49344 + endloop + endfacet + facet normal 0.118679 -0.29381 0.948468 + outer loop + vertex 1.48338 0.974052 2.49289 + vertex 1.48791 0.978473 2.49369 + vertex 1.48283 0.978161 2.49423 + endloop + endfacet + facet normal 0.118567 -0.289876 0.949691 + outer loop + vertex 1.48791 0.978473 2.49369 + vertex 1.48702 0.982365 2.49499 + vertex 1.48283 0.978161 2.49423 + endloop + endfacet + facet normal 0.115341 -0.286895 0.950993 + outer loop + vertex 1.48283 0.978161 2.49423 + vertex 1.48702 0.982365 2.49499 + vertex 1.48254 0.981937 2.4954 + endloop + endfacet + facet normal 0.123504 -0.298381 0.946422 + outer loop + vertex 1.48847 0.973964 2.49219 + vertex 1.48791 0.978473 2.49369 + vertex 1.48338 0.974052 2.49289 + endloop + endfacet + facet normal 0.116668 -0.29942 0.946962 + outer loop + vertex 1.48847 0.973964 2.49219 + vertex 1.49322 0.97882 2.49314 + vertex 1.48791 0.978473 2.49369 + endloop + endfacet + facet normal 0.116486 -0.293874 0.94872 + outer loop + vertex 1.49322 0.97882 2.49314 + vertex 1.49261 0.983435 2.49465 + vertex 1.48791 0.978473 2.49369 + endloop + endfacet + facet normal 0.119837 -0.302262 0.945662 + outer loop + vertex 1.49374 0.974951 2.49184 + vertex 1.49322 0.97882 2.49314 + vertex 1.48847 0.973964 2.49219 + endloop + endfacet + facet normal 0.120037 -0.303479 0.945247 + outer loop + vertex 1.49374 0.974951 2.49184 + vertex 1.48847 0.973964 2.49219 + vertex 1.49061 0.971152 2.49102 + endloop + endfacet + facet normal 0.118802 -0.302559 0.945698 + outer loop + vertex 1.49435 0.972242 2.4909 + vertex 1.49374 0.974951 2.49184 + vertex 1.49061 0.971152 2.49102 + endloop + endfacet + facet normal 0.116504 -0.294339 0.948573 + outer loop + vertex 1.49435 0.972242 2.4909 + vertex 1.49061 0.971152 2.49102 + vertex 1.49271 0.968296 2.48988 + endloop + endfacet + facet normal 0.107972 -0.291283 0.950524 + outer loop + vertex 1.49435 0.972242 2.4909 + vertex 1.49271 0.968296 2.48988 + vertex 1.49751 0.971931 2.49044 + endloop + endfacet + facet normal 0.10697 -0.2984 0.948427 + outer loop + vertex 1.49751 0.971931 2.49044 + vertex 1.49706 0.974725 2.49137 + vertex 1.49435 0.972242 2.4909 + endloop + endfacet + facet normal 0.110023 -0.293834 0.949503 + outer loop + vertex 1.49751 0.971931 2.49044 + vertex 1.49271 0.968296 2.48988 + vertex 1.49781 0.968132 2.48923 + endloop + endfacet + facet normal 0.110088 -0.292901 0.949784 + outer loop + vertex 1.49323 0.963724 2.48841 + vertex 1.49781 0.968132 2.48923 + vertex 1.49271 0.968296 2.48988 + endloop + endfacet + facet normal 0.1154 -0.292166 0.94938 + outer loop + vertex 1.49323 0.963724 2.48841 + vertex 1.49271 0.968296 2.48988 + vertex 1.48797 0.963436 2.48896 + endloop + endfacet + facet normal 0.115539 -0.298485 0.947395 + outer loop + vertex 1.48858 0.95877 2.48741 + vertex 1.49323 0.963724 2.48841 + vertex 1.48797 0.963436 2.48896 + endloop + endfacet + facet normal 0.11778 -0.29814 0.947228 + outer loop + vertex 1.48858 0.95877 2.48741 + vertex 1.48797 0.963436 2.48896 + vertex 1.48339 0.959018 2.48813 + endloop + endfacet + facet normal 0.117052 -0.306156 0.944758 + outer loop + vertex 1.48858 0.95877 2.48741 + vertex 1.48339 0.959018 2.48813 + vertex 1.48384 0.955171 2.48683 + endloop + endfacet + facet normal 0.116148 -0.305041 0.94523 + outer loop + vertex 1.48697 0.95477 2.48632 + vertex 1.48858 0.95877 2.48741 + vertex 1.48384 0.955171 2.48683 + endloop + endfacet + facet normal 0.115106 -0.310912 0.943443 + outer loop + vertex 1.48697 0.95477 2.48632 + vertex 1.48384 0.955171 2.48683 + vertex 1.48431 0.952354 2.48585 + endloop + endfacet + facet normal 0.11524 -0.311048 0.943382 + outer loop + vertex 1.48744 0.951961 2.48533 + vertex 1.48697 0.95477 2.48632 + vertex 1.48431 0.952354 2.48585 + endloop + endfacet + facet normal 0.114505 -0.315214 0.942087 + outer loop + vertex 1.48431 0.952354 2.48585 + vertex 1.48272 0.94842 2.48472 + vertex 1.48744 0.951961 2.48533 + endloop + endfacet + facet normal 0.115036 -0.315873 0.941802 + outer loop + vertex 1.48744 0.951961 2.48533 + vertex 1.48272 0.94842 2.48472 + vertex 1.48788 0.948191 2.48402 + endloop + endfacet + facet normal 0.114411 -0.315962 0.941848 + outer loop + vertex 1.48788 0.948191 2.48402 + vertex 1.49202 0.952388 2.48492 + vertex 1.48744 0.951961 2.48533 + endloop + endfacet + facet normal 0.114091 -0.310844 0.943589 + outer loop + vertex 1.48744 0.951961 2.48533 + vertex 1.49202 0.952388 2.48492 + vertex 1.49074 0.955667 2.48616 + endloop + endfacet + facet normal 0.113047 -0.311248 0.943581 + outer loop + vertex 1.49074 0.955667 2.48616 + vertex 1.49202 0.952388 2.48492 + vertex 1.49541 0.956473 2.48586 + endloop + endfacet + facet normal 0.111779 -0.30286 0.946457 + outer loop + vertex 1.49541 0.956473 2.48586 + vertex 1.49414 0.959777 2.48707 + vertex 1.49074 0.955667 2.48616 + endloop + endfacet + facet normal 0.113074 -0.303828 0.945993 + outer loop + vertex 1.49414 0.959777 2.48707 + vertex 1.48858 0.95877 2.48741 + vertex 1.49074 0.955667 2.48616 + endloop + endfacet + facet normal 0.111952 -0.302794 0.946458 + outer loop + vertex 1.49877 0.960231 2.48667 + vertex 1.49414 0.959777 2.48707 + vertex 1.49541 0.956473 2.48586 + endloop + endfacet + facet normal 0.113718 -0.304227 0.945787 + outer loop + vertex 1.49927 0.957465 2.48572 + vertex 1.49877 0.960231 2.48667 + vertex 1.49541 0.956473 2.48586 + endloop + endfacet + facet normal 0.116235 -0.314559 0.942095 + outer loop + vertex 1.49927 0.957465 2.48572 + vertex 1.49541 0.956473 2.48586 + vertex 1.49766 0.953518 2.4846 + endloop + endfacet + facet normal 0.123243 -0.316943 0.940403 + outer loop + vertex 1.49927 0.957465 2.48572 + vertex 1.49766 0.953518 2.4846 + vertex 1.50259 0.957288 2.48522 + endloop + endfacet + facet normal 0.123865 -0.310802 0.942369 + outer loop + vertex 1.50259 0.957288 2.48522 + vertex 1.50198 0.959972 2.48619 + vertex 1.49927 0.957465 2.48572 + endloop + endfacet + facet normal 0.125524 -0.310397 0.942283 + outer loop + vertex 1.50198 0.959972 2.48619 + vertex 1.50259 0.957288 2.48522 + vertex 1.50574 0.96109 2.48606 + endloop + endfacet + facet normal 0.123087 -0.301851 0.945376 + outer loop + vertex 1.50574 0.96109 2.48606 + vertex 1.50356 0.963897 2.48724 + vertex 1.50198 0.959972 2.48619 + endloop + endfacet + facet normal 0.117154 -0.299834 0.946771 + outer loop + vertex 1.50198 0.959972 2.48619 + vertex 1.50356 0.963897 2.48724 + vertex 1.49877 0.960231 2.48667 + endloop + endfacet + facet normal 0.113913 -0.29585 0.948418 + outer loop + vertex 1.50356 0.963897 2.48724 + vertex 1.49838 0.964011 2.48789 + vertex 1.49877 0.960231 2.48667 + endloop + endfacet + facet normal 0.113738 -0.298723 0.947538 + outer loop + vertex 1.50356 0.963897 2.48724 + vertex 1.50297 0.968419 2.48873 + vertex 1.49838 0.964011 2.48789 + endloop + endfacet + facet normal 0.11341 -0.298774 0.947561 + outer loop + vertex 1.50356 0.963897 2.48724 + vertex 1.50828 0.968731 2.48819 + vertex 1.50297 0.968419 2.48873 + endloop + endfacet + facet normal 0.113558 -0.304431 0.945741 + outer loop + vertex 1.50828 0.968731 2.48819 + vertex 1.50769 0.973355 2.48975 + vertex 1.50297 0.968419 2.48873 + endloop + endfacet + facet normal 0.107399 -0.299044 0.948176 + outer loop + vertex 1.50297 0.968419 2.48873 + vertex 1.50769 0.973355 2.48975 + vertex 1.50209 0.972345 2.49007 + endloop + endfacet + facet normal 0.108699 -0.298735 0.948125 + outer loop + vertex 1.50297 0.968419 2.48873 + vertex 1.50209 0.972345 2.49007 + vertex 1.49781 0.968132 2.48923 + endloop + endfacet + facet normal 0.104122 -0.294446 0.949979 + outer loop + vertex 1.49781 0.968132 2.48923 + vertex 1.50209 0.972345 2.49007 + vertex 1.49751 0.971931 2.49044 + endloop + endfacet + facet normal 0.104511 -0.300508 0.948036 + outer loop + vertex 1.49751 0.971931 2.49044 + vertex 1.50209 0.972345 2.49007 + vertex 1.50088 0.975667 2.49126 + endloop + endfacet + facet normal 0.10285 -0.299143 0.948649 + outer loop + vertex 1.49706 0.974725 2.49137 + vertex 1.49751 0.971931 2.49044 + vertex 1.50088 0.975667 2.49126 + endloop + endfacet + facet normal 0.103609 -0.302364 0.947545 + outer loop + vertex 1.50088 0.975667 2.49126 + vertex 1.49864 0.978712 2.49247 + vertex 1.49706 0.974725 2.49137 + endloop + endfacet + facet normal 0.105159 -0.301294 0.947715 + outer loop + vertex 1.50428 0.979758 2.49218 + vertex 1.49864 0.978712 2.49247 + vertex 1.50088 0.975667 2.49126 + endloop + endfacet + facet normal 0.103242 -0.299853 0.948382 + outer loop + vertex 1.50556 0.976442 2.49099 + vertex 1.50428 0.979758 2.49218 + vertex 1.50088 0.975667 2.49126 + endloop + endfacet + facet normal 0.103398 -0.300912 0.94803 + outer loop + vertex 1.50088 0.975667 2.49126 + vertex 1.50209 0.972345 2.49007 + vertex 1.50556 0.976442 2.49099 + endloop + endfacet + facet normal 0.105258 -0.299084 0.948404 + outer loop + vertex 1.50887 0.980157 2.4918 + vertex 1.50428 0.979758 2.49218 + vertex 1.50556 0.976442 2.49099 + endloop + endfacet + facet normal 0.105921 -0.299622 0.94816 + outer loop + vertex 1.50936 0.977341 2.49085 + vertex 1.50887 0.980157 2.4918 + vertex 1.50556 0.976442 2.49099 + endloop + endfacet + facet normal 0.10721 -0.305381 0.946176 + outer loop + vertex 1.50936 0.977341 2.49085 + vertex 1.50556 0.976442 2.49099 + vertex 1.50769 0.973355 2.48975 + endloop + endfacet + facet normal 0.114987 -0.30813 0.944369 + outer loop + vertex 1.50936 0.977341 2.49085 + vertex 1.50769 0.973355 2.48975 + vertex 1.51248 0.976961 2.49035 + endloop + endfacet + facet normal 0.115584 -0.304644 0.945427 + outer loop + vertex 1.51248 0.976961 2.49035 + vertex 1.51202 0.979776 2.49131 + vertex 1.50936 0.977341 2.49085 + endloop + endfacet + facet normal 0.119832 -0.303851 0.945153 + outer loop + vertex 1.51202 0.979776 2.49131 + vertex 1.51248 0.976961 2.49035 + vertex 1.51574 0.980706 2.49114 + endloop + endfacet + facet normal 0.117073 -0.292049 0.949211 + outer loop + vertex 1.51574 0.980706 2.49114 + vertex 1.51357 0.983766 2.49235 + vertex 1.51202 0.979776 2.49131 + endloop + endfacet + facet normal 0.111309 -0.290142 0.950488 + outer loop + vertex 1.51202 0.979776 2.49131 + vertex 1.51357 0.983766 2.49235 + vertex 1.50887 0.980157 2.4918 + endloop + endfacet + facet normal 0.110274 -0.288872 0.950996 + outer loop + vertex 1.51357 0.983766 2.49235 + vertex 1.50843 0.983941 2.493 + vertex 1.50887 0.980157 2.4918 + endloop + endfacet + facet normal 0.110568 -0.28474 0.952207 + outer loop + vertex 1.51357 0.983766 2.49235 + vertex 1.5129 0.988333 2.49379 + vertex 1.50843 0.983941 2.493 + endloop + endfacet + facet normal 0.110179 -0.284372 0.952362 + outer loop + vertex 1.50843 0.983941 2.493 + vertex 1.5129 0.988333 2.49379 + vertex 1.50781 0.988026 2.49429 + endloop + endfacet + facet normal 0.106265 -0.285041 0.952607 + outer loop + vertex 1.50843 0.983941 2.493 + vertex 1.50781 0.988026 2.49429 + vertex 1.50331 0.98366 2.49348 + endloop + endfacet + facet normal 0.106425 -0.29124 0.950712 + outer loop + vertex 1.50428 0.979758 2.49218 + vertex 1.50843 0.983941 2.493 + vertex 1.50331 0.98366 2.49348 + endloop + endfacet + facet normal 0.109518 -0.288157 0.9513 + outer loop + vertex 1.50331 0.98366 2.49348 + vertex 1.50781 0.988026 2.49429 + vertex 1.50275 0.988146 2.49491 + endloop + endfacet + facet normal 0.109126 -0.294666 0.949349 + outer loop + vertex 1.50752 0.991758 2.49548 + vertex 1.50275 0.988146 2.49491 + vertex 1.50781 0.988026 2.49429 + endloop + endfacet + facet normal 0.111994 -0.294367 0.949108 + outer loop + vertex 1.50781 0.988026 2.49429 + vertex 1.51204 0.992223 2.49509 + vertex 1.50752 0.991758 2.49548 + endloop + endfacet + facet normal 0.110436 -0.292916 0.949739 + outer loop + vertex 1.5129 0.988333 2.49379 + vertex 1.51204 0.992223 2.49509 + vertex 1.50781 0.988026 2.49429 + endloop + endfacet + facet normal 0.112342 -0.284442 0.952088 + outer loop + vertex 1.51357 0.983766 2.49235 + vertex 1.51814 0.988736 2.49329 + vertex 1.5129 0.988333 2.49379 + endloop + endfacet + facet normal 0.11255 -0.288806 0.950749 + outer loop + vertex 1.51814 0.988736 2.49329 + vertex 1.51759 0.993284 2.49474 + vertex 1.5129 0.988333 2.49379 + endloop + endfacet + facet normal 0.11444 -0.286226 0.951304 + outer loop + vertex 1.51907 0.984839 2.49201 + vertex 1.51814 0.988736 2.49329 + vertex 1.51357 0.983766 2.49235 + endloop + endfacet + facet normal 0.110661 -0.28718 0.951463 + outer loop + vertex 1.51907 0.984839 2.49201 + vertex 1.52328 0.989068 2.4928 + vertex 1.51814 0.988736 2.49329 + endloop + endfacet + facet normal 0.110651 -0.286916 0.951544 + outer loop + vertex 1.52328 0.989068 2.4928 + vertex 1.52272 0.993137 2.49409 + vertex 1.51814 0.988736 2.49329 + endloop + endfacet + facet normal 0.115628 -0.293026 0.949087 + outer loop + vertex 1.51907 0.984839 2.49201 + vertex 1.51357 0.983766 2.49235 + vertex 1.51574 0.980706 2.49114 + endloop + endfacet + facet normal 0.119112 -0.29558 0.947863 + outer loop + vertex 1.52034 0.98155 2.49082 + vertex 1.51907 0.984839 2.49201 + vertex 1.51574 0.980706 2.49114 + endloop + endfacet + facet normal 0.120197 -0.302343 0.945591 + outer loop + vertex 1.51574 0.980706 2.49114 + vertex 1.51702 0.977412 2.48992 + vertex 1.52034 0.98155 2.49082 + endloop + endfacet + facet normal 0.11707 -0.300078 0.946704 + outer loop + vertex 1.51702 0.977412 2.48992 + vertex 1.5226 0.978546 2.48959 + vertex 1.52034 0.98155 2.49082 + endloop + endfacet + facet normal 0.117825 -0.304196 0.945295 + outer loop + vertex 1.51811 0.973574 2.48855 + vertex 1.5226 0.978546 2.48959 + vertex 1.51702 0.977412 2.48992 + endloop + endfacet + facet normal 0.116202 -0.304675 0.945341 + outer loop + vertex 1.51811 0.973574 2.48855 + vertex 1.51702 0.977412 2.48992 + vertex 1.51289 0.973124 2.48905 + endloop + endfacet + facet normal 0.116263 -0.305789 0.944974 + outer loop + vertex 1.51365 0.968631 2.4875 + vertex 1.51811 0.973574 2.48855 + vertex 1.51289 0.973124 2.48905 + endloop + endfacet + facet normal 0.116505 -0.305743 0.944959 + outer loop + vertex 1.51365 0.968631 2.4875 + vertex 1.51289 0.973124 2.48905 + vertex 1.50828 0.968731 2.48819 + endloop + endfacet + facet normal 0.116567 -0.304702 0.945288 + outer loop + vertex 1.51365 0.968631 2.4875 + vertex 1.50828 0.968731 2.48819 + vertex 1.50884 0.964884 2.48689 + endloop + endfacet + facet normal 0.119791 -0.308572 0.943628 + outer loop + vertex 1.51214 0.964672 2.4864 + vertex 1.51365 0.968631 2.4875 + vertex 1.50884 0.964884 2.48689 + endloop + endfacet + facet normal 0.119801 -0.308485 0.943655 + outer loop + vertex 1.51214 0.964672 2.4864 + vertex 1.50884 0.964884 2.48689 + vertex 1.50948 0.962192 2.48593 + endloop + endfacet + facet normal 0.120782 -0.309456 0.943212 + outer loop + vertex 1.51262 0.961902 2.48543 + vertex 1.51214 0.964672 2.4864 + vertex 1.50948 0.962192 2.48593 + endloop + endfacet + facet normal 0.120708 -0.309982 0.943049 + outer loop + vertex 1.50948 0.962192 2.48593 + vertex 1.50784 0.958276 2.48485 + vertex 1.51262 0.961902 2.48543 + endloop + endfacet + facet normal 0.124043 -0.314094 0.941254 + outer loop + vertex 1.51262 0.961902 2.48543 + vertex 1.50784 0.958276 2.48485 + vertex 1.51297 0.958119 2.48412 + endloop + endfacet + facet normal 0.118025 -0.314836 0.94178 + outer loop + vertex 1.51297 0.958119 2.48412 + vertex 1.51717 0.96236 2.48501 + vertex 1.51262 0.961902 2.48543 + endloop + endfacet + facet normal 0.117783 -0.311362 0.942964 + outer loop + vertex 1.51262 0.961902 2.48543 + vertex 1.51717 0.96236 2.48501 + vertex 1.51592 0.96563 2.48625 + endloop + endfacet + facet normal 0.120454 -0.317023 0.940737 + outer loop + vertex 1.51818 0.958584 2.48361 + vertex 1.51717 0.96236 2.48501 + vertex 1.51297 0.958119 2.48412 + endloop + endfacet + facet normal 0.120566 -0.319032 0.940044 + outer loop + vertex 1.51364 0.953697 2.48253 + vertex 1.51818 0.958584 2.48361 + vertex 1.51297 0.958119 2.48412 + endloop + endfacet + facet normal 0.12595 -0.318081 0.93966 + outer loop + vertex 1.51364 0.953697 2.48253 + vertex 1.51297 0.958119 2.48412 + vertex 1.5083 0.953752 2.48327 + endloop + endfacet + facet normal 0.126002 -0.317141 0.939971 + outer loop + vertex 1.51364 0.953697 2.48253 + vertex 1.5083 0.953752 2.48327 + vertex 1.50878 0.94994 2.48192 + endloop + endfacet + facet normal 0.127914 -0.319444 0.938932 + outer loop + vertex 1.51208 0.949758 2.48141 + vertex 1.51364 0.953697 2.48253 + vertex 1.50878 0.94994 2.48192 + endloop + endfacet + facet normal 0.128305 -0.315718 0.940138 + outer loop + vertex 1.51208 0.949758 2.48141 + vertex 1.50878 0.94994 2.48192 + vertex 1.5094 0.94726 2.48093 + endloop + endfacet + facet normal 0.126932 -0.314366 0.940778 + outer loop + vertex 1.51256 0.946997 2.48042 + vertex 1.51208 0.949758 2.48141 + vertex 1.5094 0.94726 2.48093 + endloop + endfacet + facet normal 0.126714 -0.315978 0.940267 + outer loop + vertex 1.5094 0.94726 2.48093 + vertex 1.50776 0.943342 2.47984 + vertex 1.51256 0.946997 2.48042 + endloop + endfacet + facet normal 0.12505 -0.313936 0.941173 + outer loop + vertex 1.51256 0.946997 2.48042 + vertex 1.50776 0.943342 2.47984 + vertex 1.5129 0.943202 2.47911 + endloop + endfacet + facet normal 0.121866 -0.31432 0.941462 + outer loop + vertex 1.5129 0.943202 2.47911 + vertex 1.51711 0.947474 2.47999 + vertex 1.51256 0.946997 2.48042 + endloop + endfacet + facet normal 0.121813 -0.31358 0.941716 + outer loop + vertex 1.51256 0.946997 2.48042 + vertex 1.51711 0.947474 2.47999 + vertex 1.51587 0.950746 2.48124 + endloop + endfacet + facet normal 0.117945 -0.31504 0.941721 + outer loop + vertex 1.51587 0.950746 2.48124 + vertex 1.51711 0.947474 2.47999 + vertex 1.52048 0.951555 2.48093 + endloop + endfacet + facet normal 0.11838 -0.317906 0.940703 + outer loop + vertex 1.52048 0.951555 2.48093 + vertex 1.51922 0.95482 2.48219 + vertex 1.51587 0.950746 2.48124 + endloop + endfacet + facet normal 0.121623 -0.320287 0.939481 + outer loop + vertex 1.51922 0.95482 2.48219 + vertex 1.51364 0.953697 2.48253 + vertex 1.51587 0.950746 2.48124 + endloop + endfacet + facet normal 0.116081 -0.31879 0.94069 + outer loop + vertex 1.52379 0.955248 2.48177 + vertex 1.51922 0.95482 2.48219 + vertex 1.52048 0.951555 2.48093 + endloop + endfacet + facet normal 0.116145 -0.319828 0.94033 + outer loop + vertex 1.52379 0.955248 2.48177 + vertex 1.52337 0.959016 2.48311 + vertex 1.51922 0.95482 2.48219 + endloop + endfacet + facet normal 0.114254 -0.320091 0.940472 + outer loop + vertex 1.52853 0.958801 2.48241 + vertex 1.52337 0.959016 2.48311 + vertex 1.52379 0.955248 2.48177 + endloop + endfacet + facet normal 0.111968 -0.317263 0.941704 + outer loop + vertex 1.52693 0.95486 2.48127 + vertex 1.52853 0.958801 2.48241 + vertex 1.52379 0.955248 2.48177 + endloop + endfacet + facet normal 0.112041 -0.316843 0.941837 + outer loop + vertex 1.52693 0.95486 2.48127 + vertex 1.52379 0.955248 2.48177 + vertex 1.52425 0.952448 2.48078 + endloop + endfacet + facet normal 0.109532 -0.314288 0.942988 + outer loop + vertex 1.52737 0.952057 2.48029 + vertex 1.52693 0.95486 2.48127 + vertex 1.52425 0.952448 2.48078 + endloop + endfacet + facet normal 0.113365 -0.316602 0.94176 + outer loop + vertex 1.52425 0.952448 2.48078 + vertex 1.52379 0.955248 2.48177 + vertex 1.52048 0.951555 2.48093 + endloop + endfacet + facet normal 0.112717 -0.313691 0.942811 + outer loop + vertex 1.52425 0.952448 2.48078 + vertex 1.52048 0.951555 2.48093 + vertex 1.52261 0.948514 2.47966 + endloop + endfacet + facet normal 0.114435 -0.317988 0.941163 + outer loop + vertex 1.52853 0.958801 2.48241 + vertex 1.52784 0.963219 2.48398 + vertex 1.52337 0.959016 2.48311 + endloop + endfacet + facet normal 0.115824 -0.319336 0.940537 + outer loop + vertex 1.52337 0.959016 2.48311 + vertex 1.52784 0.963219 2.48398 + vertex 1.5227 0.963418 2.48468 + endloop + endfacet + facet normal 0.117383 -0.319062 0.940436 + outer loop + vertex 1.52337 0.959016 2.48311 + vertex 1.5227 0.963418 2.48468 + vertex 1.51818 0.958584 2.48361 + endloop + endfacet + facet normal 0.117481 -0.321023 0.939757 + outer loop + vertex 1.51922 0.95482 2.48219 + vertex 1.52337 0.959016 2.48311 + vertex 1.51818 0.958584 2.48361 + endloop + endfacet + facet normal 0.116329 -0.318172 0.940869 + outer loop + vertex 1.51818 0.958584 2.48361 + vertex 1.5227 0.963418 2.48468 + vertex 1.51717 0.96236 2.48501 + endloop + endfacet + facet normal 0.115662 -0.314257 0.942266 + outer loop + vertex 1.51717 0.96236 2.48501 + vertex 1.5227 0.963418 2.48468 + vertex 1.52054 0.966428 2.48595 + endloop + endfacet + facet normal 0.113808 -0.312883 0.942948 + outer loop + vertex 1.51592 0.96563 2.48625 + vertex 1.51717 0.96236 2.48501 + vertex 1.52054 0.966428 2.48595 + endloop + endfacet + facet normal 0.112923 -0.307021 0.94498 + outer loop + vertex 1.52054 0.966428 2.48595 + vertex 1.51923 0.969727 2.48718 + vertex 1.51592 0.96563 2.48625 + endloop + endfacet + facet normal 0.111893 -0.307426 0.944971 + outer loop + vertex 1.52382 0.970155 2.48678 + vertex 1.51923 0.969727 2.48718 + vertex 1.52054 0.966428 2.48595 + endloop + endfacet + facet normal 0.111566 -0.302344 0.946647 + outer loop + vertex 1.52382 0.970155 2.48678 + vertex 1.52335 0.974018 2.48807 + vertex 1.51923 0.969727 2.48718 + endloop + endfacet + facet normal 0.113249 -0.30382 0.945975 + outer loop + vertex 1.51923 0.969727 2.48718 + vertex 1.52335 0.974018 2.48807 + vertex 1.51811 0.973574 2.48855 + endloop + endfacet + facet normal 0.116078 -0.316286 0.941535 + outer loop + vertex 1.52743 0.96698 2.4853 + vertex 1.5227 0.963418 2.48468 + vertex 1.52784 0.963219 2.48398 + endloop + endfacet + facet normal 0.113944 -0.316577 0.941698 + outer loop + vertex 1.52784 0.963219 2.48398 + vertex 1.53199 0.96743 2.4849 + vertex 1.52743 0.96698 2.4853 + endloop + endfacet + facet normal 0.112597 -0.315371 0.942265 + outer loop + vertex 1.53304 0.963645 2.48351 + vertex 1.53199 0.96743 2.4849 + vertex 1.52784 0.963219 2.48398 + endloop + endfacet + facet normal 0.115906 -0.316073 0.941628 + outer loop + vertex 1.5243 0.967337 2.4858 + vertex 1.5227 0.963418 2.48468 + vertex 1.52743 0.96698 2.4853 + endloop + endfacet + facet normal 0.116644 -0.311586 0.943031 + outer loop + vertex 1.52743 0.96698 2.4853 + vertex 1.52697 0.969776 2.48628 + vertex 1.5243 0.967337 2.4858 + endloop + endfacet + facet normal 0.112659 -0.307586 0.944827 + outer loop + vertex 1.52697 0.969776 2.48628 + vertex 1.52382 0.970155 2.48678 + vertex 1.5243 0.967337 2.4858 + endloop + endfacet + facet normal 0.112203 -0.307674 0.944853 + outer loop + vertex 1.5243 0.967337 2.4858 + vertex 1.52382 0.970155 2.48678 + vertex 1.52054 0.966428 2.48595 + endloop + endfacet + facet normal 0.112898 -0.306166 0.94526 + outer loop + vertex 1.52697 0.969776 2.48628 + vertex 1.52855 0.973778 2.48739 + vertex 1.52382 0.970155 2.48678 + endloop + endfacet + facet normal 0.10996 -0.302577 0.946761 + outer loop + vertex 1.52855 0.973778 2.48739 + vertex 1.52335 0.974018 2.48807 + vertex 1.52382 0.970155 2.48678 + endloop + endfacet + facet normal 0.11009 -0.301065 0.947228 + outer loop + vertex 1.52855 0.973778 2.48739 + vertex 1.52794 0.978423 2.48893 + vertex 1.52335 0.974018 2.48807 + endloop + endfacet + facet normal 0.113958 -0.315407 0.942089 + outer loop + vertex 1.5243 0.967337 2.4858 + vertex 1.52054 0.966428 2.48595 + vertex 1.5227 0.963418 2.48468 + endloop + endfacet + facet normal 0.114526 -0.3125 0.942989 + outer loop + vertex 1.51711 0.947474 2.47999 + vertex 1.52261 0.948514 2.47966 + vertex 1.52048 0.951555 2.48093 + endloop + endfacet + facet normal 0.127871 -0.316382 0.939974 + outer loop + vertex 1.5094 0.94726 2.48093 + vertex 1.50565 0.946142 2.48107 + vertex 1.50776 0.943342 2.47984 + endloop + endfacet + facet normal 0.125005 -0.318408 0.939675 + outer loop + vertex 1.5025 0.942352 2.4802 + vertex 1.50776 0.943342 2.47984 + vertex 1.50565 0.946142 2.48107 + endloop + endfacet + facet normal 0.125271 -0.318606 0.939573 + outer loop + vertex 1.50189 0.945031 2.48119 + vertex 1.5025 0.942352 2.4802 + vertex 1.50565 0.946142 2.48107 + endloop + endfacet + facet normal 0.124513 -0.315929 0.940577 + outer loop + vertex 1.50565 0.946142 2.48107 + vertex 1.50351 0.948946 2.48229 + vertex 1.50189 0.945031 2.48119 + endloop + endfacet + facet normal 0.120319 -0.314487 0.941606 + outer loop + vertex 1.50189 0.945031 2.48119 + vertex 1.50351 0.948946 2.48229 + vertex 1.4987 0.945301 2.48169 + endloop + endfacet + facet normal 0.119861 -0.317892 0.94052 + outer loop + vertex 1.50189 0.945031 2.48119 + vertex 1.4987 0.945301 2.48169 + vertex 1.49919 0.942543 2.48069 + endloop + endfacet + facet normal 0.116845 -0.318488 0.940698 + outer loop + vertex 1.49919 0.942543 2.48069 + vertex 1.4987 0.945301 2.48169 + vertex 1.49538 0.941567 2.48084 + endloop + endfacet + facet normal 0.11761 -0.321644 0.939528 + outer loop + vertex 1.49919 0.942543 2.48069 + vertex 1.49538 0.941567 2.48084 + vertex 1.49759 0.938609 2.47955 + endloop + endfacet + facet normal 0.121152 -0.322832 0.93867 + outer loop + vertex 1.49919 0.942543 2.48069 + vertex 1.49759 0.938609 2.47955 + vertex 1.5025 0.942352 2.4802 + endloop + endfacet + facet normal 0.120411 -0.321931 0.939075 + outer loop + vertex 1.5025 0.942352 2.4802 + vertex 1.49759 0.938609 2.47955 + vertex 1.50294 0.938544 2.47884 + endloop + endfacet + facet normal 0.117205 -0.321926 0.939482 + outer loop + vertex 1.49203 0.937495 2.47986 + vertex 1.49759 0.938609 2.47955 + vertex 1.49538 0.941567 2.48084 + endloop + endfacet + facet normal 0.116769 -0.321606 0.939646 + outer loop + vertex 1.49079 0.940758 2.48113 + vertex 1.49203 0.937495 2.47986 + vertex 1.49538 0.941567 2.48084 + endloop + endfacet + facet normal 0.116519 -0.319975 0.940234 + outer loop + vertex 1.49538 0.941567 2.48084 + vertex 1.49412 0.944829 2.4821 + vertex 1.49079 0.940758 2.48113 + endloop + endfacet + facet normal 0.116929 -0.320275 0.940081 + outer loop + vertex 1.49412 0.944829 2.4821 + vertex 1.4886 0.943775 2.48243 + vertex 1.49079 0.940758 2.48113 + endloop + endfacet + facet normal 0.116828 -0.320343 0.94007 + outer loop + vertex 1.49079 0.940758 2.48113 + vertex 1.4886 0.943775 2.48243 + vertex 1.48706 0.939855 2.48129 + endloop + endfacet + facet normal 0.117019 -0.321183 0.93976 + outer loop + vertex 1.48706 0.939855 2.48129 + vertex 1.4875 0.937063 2.48028 + vertex 1.49079 0.940758 2.48113 + endloop + endfacet + facet normal 0.117618 -0.321074 0.939722 + outer loop + vertex 1.4875 0.937063 2.48028 + vertex 1.48706 0.939855 2.48129 + vertex 1.48439 0.937438 2.48079 + endloop + endfacet + facet normal 0.11766 -0.320829 0.9398 + outer loop + vertex 1.48439 0.937438 2.48079 + vertex 1.48274 0.933497 2.47965 + vertex 1.4875 0.937063 2.48028 + endloop + endfacet + facet normal 0.118293 -0.321614 0.939453 + outer loop + vertex 1.4875 0.937063 2.48028 + vertex 1.48274 0.933497 2.47965 + vertex 1.48787 0.933288 2.47894 + endloop + endfacet + facet normal 0.11732 -0.321736 0.939533 + outer loop + vertex 1.48787 0.933288 2.47894 + vertex 1.49203 0.937495 2.47986 + vertex 1.4875 0.937063 2.48028 + endloop + endfacet + facet normal 0.115634 -0.320124 0.940292 + outer loop + vertex 1.48439 0.937438 2.48079 + vertex 1.48059 0.936513 2.48095 + vertex 1.48274 0.933497 2.47965 + endloop + endfacet + facet normal 0.115909 -0.31994 0.940321 + outer loop + vertex 1.47717 0.932426 2.47998 + vertex 1.48274 0.933497 2.47965 + vertex 1.48059 0.936513 2.48095 + endloop + endfacet + facet normal 0.112536 -0.317421 0.941583 + outer loop + vertex 1.47593 0.9357 2.48123 + vertex 1.47717 0.932426 2.47998 + vertex 1.48059 0.936513 2.48095 + endloop + endfacet + facet normal 0.112852 -0.319491 0.940845 + outer loop + vertex 1.48059 0.936513 2.48095 + vertex 1.47929 0.939783 2.48221 + vertex 1.47593 0.9357 2.48123 + endloop + endfacet + facet normal 0.111848 -0.318752 0.941216 + outer loop + vertex 1.47929 0.939783 2.48221 + vertex 1.47373 0.938728 2.48252 + vertex 1.47593 0.9357 2.48123 + endloop + endfacet + facet normal 0.111071 -0.319279 0.941129 + outer loop + vertex 1.47593 0.9357 2.48123 + vertex 1.47373 0.938728 2.48252 + vertex 1.47215 0.934787 2.48137 + endloop + endfacet + facet normal 0.110298 -0.315894 0.942361 + outer loop + vertex 1.47215 0.934787 2.48137 + vertex 1.47259 0.93199 2.48038 + vertex 1.47593 0.9357 2.48123 + endloop + endfacet + facet normal 0.110257 -0.315902 0.942364 + outer loop + vertex 1.47259 0.93199 2.48038 + vertex 1.47215 0.934787 2.48137 + vertex 1.46946 0.932375 2.48087 + endloop + endfacet + facet normal 0.110591 -0.313965 0.942972 + outer loop + vertex 1.46946 0.932375 2.48087 + vertex 1.4678 0.92844 2.47976 + vertex 1.47259 0.93199 2.48038 + endloop + endfacet + facet normal 0.111704 -0.315363 0.942374 + outer loop + vertex 1.47259 0.93199 2.48038 + vertex 1.4678 0.92844 2.47976 + vertex 1.47296 0.928209 2.47907 + endloop + endfacet + facet normal 0.112153 -0.315308 0.942339 + outer loop + vertex 1.47296 0.928209 2.47907 + vertex 1.47717 0.932426 2.47998 + vertex 1.47259 0.93199 2.48038 + endloop + endfacet + facet normal 0.112616 -0.314684 0.942492 + outer loop + vertex 1.46946 0.932375 2.48087 + vertex 1.46569 0.931479 2.48102 + vertex 1.4678 0.92844 2.47976 + endloop + endfacet + facet normal 0.112365 -0.314848 0.942467 + outer loop + vertex 1.46227 0.927395 2.48007 + vertex 1.4678 0.92844 2.47976 + vertex 1.46569 0.931479 2.48102 + endloop + endfacet + facet normal 0.114971 -0.316802 0.941498 + outer loop + vertex 1.46105 0.930675 2.48132 + vertex 1.46227 0.927395 2.48007 + vertex 1.46569 0.931479 2.48102 + endloop + endfacet + facet normal 0.114937 -0.316574 0.941579 + outer loop + vertex 1.46569 0.931479 2.48102 + vertex 1.4644 0.934779 2.48229 + vertex 1.46105 0.930675 2.48132 + endloop + endfacet + facet normal 0.114573 -0.316309 0.941712 + outer loop + vertex 1.4644 0.934779 2.48229 + vertex 1.4587 0.933711 2.48263 + vertex 1.46105 0.930675 2.48132 + endloop + endfacet + facet normal 0.11675 -0.314736 0.941972 + outer loop + vertex 1.46105 0.930675 2.48132 + vertex 1.4587 0.933711 2.48263 + vertex 1.45724 0.929687 2.48146 + endloop + endfacet + facet normal 0.117652 -0.318408 0.940624 + outer loop + vertex 1.45724 0.929687 2.48146 + vertex 1.45772 0.926928 2.48047 + vertex 1.46105 0.930675 2.48132 + endloop + endfacet + facet normal 0.114936 -0.314194 0.942375 + outer loop + vertex 1.45724 0.929687 2.48146 + vertex 1.4587 0.933711 2.48263 + vertex 1.45385 0.929872 2.48194 + endloop + endfacet + facet normal 0.114814 -0.315415 0.941982 + outer loop + vertex 1.45724 0.929687 2.48146 + vertex 1.45385 0.929872 2.48194 + vertex 1.45456 0.927194 2.48095 + endloop + endfacet + facet normal 0.117824 -0.318374 0.940614 + outer loop + vertex 1.45772 0.926928 2.48047 + vertex 1.45724 0.929687 2.48146 + vertex 1.45456 0.927194 2.48095 + endloop + endfacet + facet normal 0.1167 -0.326755 0.937877 + outer loop + vertex 1.45456 0.927194 2.48095 + vertex 1.45294 0.923375 2.47983 + vertex 1.45772 0.926928 2.48047 + endloop + endfacet + facet normal 0.11616 -0.326565 0.93801 + outer loop + vertex 1.45456 0.927194 2.48095 + vertex 1.45076 0.926104 2.48104 + vertex 1.45294 0.923375 2.47983 + endloop + endfacet + facet normal 0.113182 -0.315864 0.94203 + outer loop + vertex 1.45456 0.927194 2.48095 + vertex 1.45385 0.929872 2.48194 + vertex 1.45076 0.926104 2.48104 + endloop + endfacet + facet normal 0.114841 -0.317917 0.941138 + outer loop + vertex 1.4644 0.934779 2.48229 + vertex 1.4633 0.938643 2.48373 + vertex 1.4587 0.933711 2.48263 + endloop + endfacet + facet normal 0.111216 -0.314858 0.9426 + outer loop + vertex 1.4587 0.933711 2.48263 + vertex 1.4633 0.938643 2.48373 + vertex 1.45774 0.938624 2.48438 + endloop + endfacet + facet normal 0.11153 -0.314791 0.942585 + outer loop + vertex 1.4587 0.933711 2.48263 + vertex 1.45774 0.938624 2.48438 + vertex 1.45311 0.933661 2.48327 + endloop + endfacet + facet normal 0.107069 -0.311025 0.944351 + outer loop + vertex 1.45311 0.933661 2.48327 + vertex 1.45774 0.938624 2.48438 + vertex 1.45197 0.937604 2.4847 + endloop + endfacet + facet normal 0.105743 -0.311415 0.944372 + outer loop + vertex 1.45311 0.933661 2.48327 + vertex 1.45197 0.937604 2.4847 + vertex 1.44783 0.933264 2.48373 + endloop + endfacet + facet normal 0.105562 -0.307486 0.945679 + outer loop + vertex 1.44851 0.928889 2.48223 + vertex 1.45311 0.933661 2.48327 + vertex 1.44783 0.933264 2.48373 + endloop + endfacet + facet normal 0.10222 -0.308069 0.945856 + outer loop + vertex 1.44851 0.928889 2.48223 + vertex 1.44783 0.933264 2.48373 + vertex 1.44341 0.929108 2.48285 + endloop + endfacet + facet normal 0.101014 -0.306897 0.946367 + outer loop + vertex 1.44341 0.929108 2.48285 + vertex 1.44783 0.933264 2.48373 + vertex 1.4429 0.933155 2.48422 + endloop + endfacet + facet normal 0.0994498 -0.307125 0.946459 + outer loop + vertex 1.44341 0.929108 2.48285 + vertex 1.4429 0.933155 2.48422 + vertex 1.43848 0.928998 2.48334 + endloop + endfacet + facet normal 0.0993916 -0.313111 0.944501 + outer loop + vertex 1.43928 0.925126 2.48197 + vertex 1.44341 0.929108 2.48285 + vertex 1.43848 0.928998 2.48334 + endloop + endfacet + facet normal 0.0978002 -0.313459 0.944552 + outer loop + vertex 1.43928 0.925126 2.48197 + vertex 1.43848 0.928998 2.48334 + vertex 1.43435 0.924681 2.48233 + endloop + endfacet + facet normal 0.0986387 -0.32644 0.940057 + outer loop + vertex 1.43928 0.925126 2.48197 + vertex 1.43435 0.924681 2.48233 + vertex 1.43568 0.921147 2.48096 + endloop + endfacet + facet normal 0.0969384 -0.325066 0.94071 + outer loop + vertex 1.44044 0.921723 2.48067 + vertex 1.43928 0.925126 2.48197 + vertex 1.43568 0.921147 2.48096 + endloop + endfacet + facet normal 0.0985034 -0.340892 0.934928 + outer loop + vertex 1.43568 0.921147 2.48096 + vertex 1.43709 0.917669 2.47955 + vertex 1.44044 0.921723 2.48067 + endloop + endfacet + facet normal 0.0974868 -0.324883 0.940717 + outer loop + vertex 1.44376 0.925359 2.48159 + vertex 1.43928 0.925126 2.48197 + vertex 1.44044 0.921723 2.48067 + endloop + endfacet + facet normal 0.0963516 -0.323957 0.941153 + outer loop + vertex 1.44429 0.922596 2.48058 + vertex 1.44376 0.925359 2.48159 + vertex 1.44044 0.921723 2.48067 + endloop + endfacet + facet normal 0.10039 -0.342537 0.934125 + outer loop + vertex 1.44429 0.922596 2.48058 + vertex 1.44044 0.921723 2.48067 + vertex 1.44287 0.918741 2.47932 + endloop + endfacet + facet normal 0.107591 -0.344673 0.932537 + outer loop + vertex 1.44429 0.922596 2.48058 + vertex 1.44287 0.918741 2.47932 + vertex 1.44767 0.922408 2.48012 + endloop + endfacet + facet normal 0.108938 -0.331607 0.937107 + outer loop + vertex 1.44767 0.922408 2.48012 + vertex 1.44696 0.925022 2.48113 + vertex 1.44429 0.922596 2.48058 + endloop + endfacet + facet normal 0.114509 -0.330049 0.936993 + outer loop + vertex 1.44696 0.925022 2.48113 + vertex 1.44767 0.922408 2.48012 + vertex 1.45076 0.926104 2.48104 + endloop + endfacet + facet normal 0.109884 -0.313334 0.943264 + outer loop + vertex 1.45076 0.926104 2.48104 + vertex 1.44851 0.928889 2.48223 + vertex 1.44696 0.925022 2.48113 + endloop + endfacet + facet normal 0.102289 -0.310783 0.944961 + outer loop + vertex 1.44696 0.925022 2.48113 + vertex 1.44851 0.928889 2.48223 + vertex 1.44376 0.925359 2.48159 + endloop + endfacet + facet normal 0.102025 -0.310452 0.945098 + outer loop + vertex 1.44851 0.928889 2.48223 + vertex 1.44341 0.929108 2.48285 + vertex 1.44376 0.925359 2.48159 + endloop + endfacet + facet normal 0.109808 -0.31339 0.943254 + outer loop + vertex 1.45385 0.929872 2.48194 + vertex 1.44851 0.928889 2.48223 + vertex 1.45076 0.926104 2.48104 + endloop + endfacet + facet normal 0.112972 -0.328912 0.937579 + outer loop + vertex 1.44767 0.922408 2.48012 + vertex 1.45294 0.923375 2.47983 + vertex 1.45076 0.926104 2.48104 + endloop + endfacet + facet normal 0.11505 -0.341675 0.932749 + outer loop + vertex 1.44833 0.918847 2.47873 + vertex 1.45294 0.923375 2.47983 + vertex 1.44767 0.922408 2.48012 + endloop + endfacet + facet normal 0.10043 -0.323117 0.941015 + outer loop + vertex 1.44696 0.925022 2.48113 + vertex 1.44376 0.925359 2.48159 + vertex 1.44429 0.922596 2.48058 + endloop + endfacet + facet normal 0.0993989 -0.326161 0.940074 + outer loop + vertex 1.43568 0.921147 2.48096 + vertex 1.43435 0.924681 2.48233 + vertex 1.43098 0.920597 2.48127 + endloop + endfacet + facet normal 0.100763 -0.340831 0.934709 + outer loop + vertex 1.43098 0.920597 2.48127 + vertex 1.43217 0.917269 2.47993 + vertex 1.43568 0.921147 2.48096 + endloop + endfacet + facet normal 0.102159 -0.328179 0.939075 + outer loop + vertex 1.43435 0.924681 2.48233 + vertex 1.42869 0.923756 2.48262 + vertex 1.43098 0.920597 2.48127 + endloop + endfacet + facet normal 0.101273 -0.328774 0.938963 + outer loop + vertex 1.43098 0.920597 2.48127 + vertex 1.42869 0.923756 2.48262 + vertex 1.42723 0.919791 2.48139 + endloop + endfacet + facet normal 0.100676 -0.31795 0.942747 + outer loop + vertex 1.43435 0.924681 2.48233 + vertex 1.43327 0.928631 2.48378 + vertex 1.42869 0.923756 2.48262 + endloop + endfacet + facet normal 0.105698 -0.3222 0.940752 + outer loop + vertex 1.42869 0.923756 2.48262 + vertex 1.43327 0.928631 2.48378 + vertex 1.42779 0.928646 2.4844 + endloop + endfacet + facet normal 0.102228 -0.322893 0.940898 + outer loop + vertex 1.42869 0.923756 2.48262 + vertex 1.42779 0.928646 2.4844 + vertex 1.42332 0.923891 2.48325 + endloop + endfacet + facet normal 0.101789 -0.329649 0.9386 + outer loop + vertex 1.42869 0.923756 2.48262 + vertex 1.42332 0.923891 2.48325 + vertex 1.424 0.92019 2.48188 + endloop + endfacet + facet normal 0.104567 -0.324863 0.939963 + outer loop + vertex 1.42332 0.923891 2.48325 + vertex 1.42779 0.928646 2.4844 + vertex 1.42209 0.927642 2.48469 + endloop + endfacet + facet normal 0.0995895 -0.326491 0.939939 + outer loop + vertex 1.42332 0.923891 2.48325 + vertex 1.42209 0.927642 2.48469 + vertex 1.41812 0.923404 2.48364 + endloop + endfacet + facet normal 0.0999385 -0.331687 0.938081 + outer loop + vertex 1.41932 0.919774 2.48222 + vertex 1.42332 0.923891 2.48325 + vertex 1.41812 0.923404 2.48364 + endloop + endfacet + facet normal 0.0974643 -0.332493 0.938056 + outer loop + vertex 1.41932 0.919774 2.48222 + vertex 1.41812 0.923404 2.48364 + vertex 1.41371 0.918797 2.48246 + endloop + endfacet + facet normal 0.0983162 -0.333219 0.937709 + outer loop + vertex 1.41371 0.918797 2.48246 + vertex 1.41812 0.923404 2.48364 + vertex 1.41307 0.923149 2.48407 + endloop + endfacet + facet normal 0.099936 -0.332952 0.937633 + outer loop + vertex 1.41371 0.918797 2.48246 + vertex 1.41307 0.923149 2.48407 + vertex 1.40853 0.919072 2.48311 + endloop + endfacet + facet normal 0.0995157 -0.337308 0.93612 + outer loop + vertex 1.41371 0.918797 2.48246 + vertex 1.40853 0.919072 2.48311 + vertex 1.4089 0.915345 2.48173 + endloop + endfacet + facet normal 0.0986061 -0.331616 0.938247 + outer loop + vertex 1.40853 0.919072 2.48311 + vertex 1.41307 0.923149 2.48407 + vertex 1.40796 0.923458 2.48472 + endloop + endfacet + facet normal 0.102234 -0.331072 0.938051 + outer loop + vertex 1.40853 0.919072 2.48311 + vertex 1.40796 0.923458 2.48472 + vertex 1.40329 0.918679 2.48354 + endloop + endfacet + facet normal 0.102433 -0.33546 0.936469 + outer loop + vertex 1.40426 0.914927 2.48209 + vertex 1.40853 0.919072 2.48311 + vertex 1.40329 0.918679 2.48354 + endloop + endfacet + facet normal 0.1079 -0.334007 0.936374 + outer loop + vertex 1.40426 0.914927 2.48209 + vertex 1.40329 0.918679 2.48354 + vertex 1.39865 0.913886 2.48237 + endloop + endfacet + facet normal 0.10598 -0.332347 0.937184 + outer loop + vertex 1.39865 0.913886 2.48237 + vertex 1.40329 0.918679 2.48354 + vertex 1.39805 0.918267 2.48399 + endloop + endfacet + facet normal 0.105816 -0.32893 0.938407 + outer loop + vertex 1.40329 0.918679 2.48354 + vertex 1.40232 0.922434 2.48497 + vertex 1.39805 0.918267 2.48399 + endloop + endfacet + facet normal 0.104229 -0.327462 0.939098 + outer loop + vertex 1.39805 0.918267 2.48399 + vertex 1.40232 0.922434 2.48497 + vertex 1.39768 0.922004 2.48533 + endloop + endfacet + facet normal 0.110717 -0.326669 0.938632 + outer loop + vertex 1.39768 0.922004 2.48533 + vertex 1.39288 0.918491 2.48468 + vertex 1.39805 0.918267 2.48399 + endloop + endfacet + facet normal 0.11051 -0.329013 0.937837 + outer loop + vertex 1.39348 0.914115 2.48307 + vertex 1.39805 0.918267 2.48399 + vertex 1.39288 0.918491 2.48468 + endloop + endfacet + facet normal 0.108292 -0.323603 0.939975 + outer loop + vertex 1.39452 0.922383 2.48583 + vertex 1.39288 0.918491 2.48468 + vertex 1.39768 0.922004 2.48533 + endloop + endfacet + facet normal 0.107868 -0.326081 0.939167 + outer loop + vertex 1.39768 0.922004 2.48533 + vertex 1.39723 0.924783 2.48635 + vertex 1.39452 0.922383 2.48583 + endloop + endfacet + facet normal 0.110077 -0.328341 0.938123 + outer loop + vertex 1.39723 0.924783 2.48635 + vertex 1.39405 0.925175 2.48686 + vertex 1.39452 0.922383 2.48583 + endloop + endfacet + facet normal 0.11452 -0.327503 0.937884 + outer loop + vertex 1.39452 0.922383 2.48583 + vertex 1.39405 0.925175 2.48686 + vertex 1.39074 0.921498 2.48598 + endloop + endfacet + facet normal 0.115271 -0.328106 0.937582 + outer loop + vertex 1.39405 0.925175 2.48686 + vertex 1.38945 0.924784 2.48729 + vertex 1.39074 0.921498 2.48598 + endloop + endfacet + facet normal 0.119502 -0.326462 0.937626 + outer loop + vertex 1.39074 0.921498 2.48598 + vertex 1.38945 0.924784 2.48729 + vertex 1.38613 0.920716 2.4863 + endloop + endfacet + facet normal 0.119386 -0.325657 0.93792 + outer loop + vertex 1.38613 0.920716 2.4863 + vertex 1.38736 0.917455 2.48501 + vertex 1.39074 0.921498 2.48598 + endloop + endfacet + facet normal 0.11689 -0.323801 0.938877 + outer loop + vertex 1.38736 0.917455 2.48501 + vertex 1.39288 0.918491 2.48468 + vertex 1.39074 0.921498 2.48598 + endloop + endfacet + facet normal 0.117546 -0.327758 0.937421 + outer loop + vertex 1.38831 0.913706 2.48358 + vertex 1.39288 0.918491 2.48468 + vertex 1.38736 0.917455 2.48501 + endloop + endfacet + facet normal 0.124246 -0.323821 0.937925 + outer loop + vertex 1.38285 0.916994 2.48545 + vertex 1.38736 0.917455 2.48501 + vertex 1.38613 0.920716 2.4863 + endloop + endfacet + facet normal 0.124573 -0.324079 0.937792 + outer loop + vertex 1.38237 0.919756 2.48646 + vertex 1.38285 0.916994 2.48545 + vertex 1.38613 0.920716 2.4863 + endloop + endfacet + facet normal 0.125017 -0.325943 0.937087 + outer loop + vertex 1.38613 0.920716 2.4863 + vertex 1.38382 0.923746 2.48766 + vertex 1.38237 0.919756 2.48646 + endloop + endfacet + facet normal 0.131664 -0.327885 0.935498 + outer loop + vertex 1.38237 0.919756 2.48646 + vertex 1.38382 0.923746 2.48766 + vertex 1.37905 0.919946 2.487 + endloop + endfacet + facet normal 0.131973 -0.32509 0.936429 + outer loop + vertex 1.38237 0.919756 2.48646 + vertex 1.37905 0.919946 2.487 + vertex 1.37973 0.917275 2.48597 + endloop + endfacet + facet normal 0.136007 -0.323994 0.936232 + outer loop + vertex 1.37973 0.917275 2.48597 + vertex 1.37905 0.919946 2.487 + vertex 1.37599 0.916165 2.48613 + endloop + endfacet + facet normal 0.135852 -0.323444 0.936444 + outer loop + vertex 1.37973 0.917275 2.48597 + vertex 1.37599 0.916165 2.48613 + vertex 1.37806 0.913386 2.48487 + endloop + endfacet + facet normal 0.130097 -0.321407 0.937962 + outer loop + vertex 1.37973 0.917275 2.48597 + vertex 1.37806 0.913386 2.48487 + vertex 1.38285 0.916994 2.48545 + endloop + endfacet + facet normal 0.132531 -0.324418 0.936583 + outer loop + vertex 1.38285 0.916994 2.48545 + vertex 1.37806 0.913386 2.48487 + vertex 1.38314 0.913245 2.48411 + endloop + endfacet + facet normal 0.137828 -0.322061 0.936632 + outer loop + vertex 1.37286 0.912372 2.48529 + vertex 1.37806 0.913386 2.48487 + vertex 1.37599 0.916165 2.48613 + endloop + endfacet + facet normal 0.139175 -0.323053 0.936091 + outer loop + vertex 1.37224 0.915007 2.48629 + vertex 1.37286 0.912372 2.48529 + vertex 1.37599 0.916165 2.48613 + endloop + endfacet + facet normal 0.139005 -0.322472 0.936317 + outer loop + vertex 1.37599 0.916165 2.48613 + vertex 1.37376 0.918893 2.4874 + vertex 1.37224 0.915007 2.48629 + endloop + endfacet + facet normal 0.141533 -0.323271 0.935663 + outer loop + vertex 1.37224 0.915007 2.48629 + vertex 1.37376 0.918893 2.4874 + vertex 1.36892 0.915098 2.48682 + endloop + endfacet + facet normal 0.141591 -0.322547 0.935904 + outer loop + vertex 1.37224 0.915007 2.48629 + vertex 1.36892 0.915098 2.48682 + vertex 1.36957 0.912466 2.48582 + endloop + endfacet + facet normal 0.143473 -0.322041 0.935791 + outer loop + vertex 1.36957 0.912466 2.48582 + vertex 1.36892 0.915098 2.48682 + vertex 1.36582 0.911284 2.48599 + endloop + endfacet + facet normal 0.143852 -0.323313 0.935294 + outer loop + vertex 1.36957 0.912466 2.48582 + vertex 1.36582 0.911284 2.48599 + vertex 1.36799 0.908582 2.48472 + endloop + endfacet + facet normal 0.14149 -0.322533 0.935924 + outer loop + vertex 1.36957 0.912466 2.48582 + vertex 1.36799 0.908582 2.48472 + vertex 1.37286 0.912372 2.48529 + endloop + endfacet + facet normal 0.143707 -0.325191 0.934665 + outer loop + vertex 1.37286 0.912372 2.48529 + vertex 1.36799 0.908582 2.48472 + vertex 1.37322 0.908591 2.48392 + endloop + endfacet + facet normal 0.14565 -0.321957 0.935484 + outer loop + vertex 1.36278 0.907478 2.48515 + vertex 1.36799 0.908582 2.48472 + vertex 1.36582 0.911284 2.48599 + endloop + endfacet + facet normal 0.145153 -0.321603 0.935683 + outer loop + vertex 1.36209 0.910101 2.48616 + vertex 1.36278 0.907478 2.48515 + vertex 1.36582 0.911284 2.48599 + endloop + endfacet + facet normal 0.144824 -0.320503 0.936111 + outer loop + vertex 1.36582 0.911284 2.48599 + vertex 1.36366 0.91402 2.48726 + vertex 1.36209 0.910101 2.48616 + endloop + endfacet + facet normal 0.147239 -0.321286 0.935466 + outer loop + vertex 1.36209 0.910101 2.48616 + vertex 1.36366 0.91402 2.48726 + vertex 1.35881 0.910192 2.48671 + endloop + endfacet + facet normal 0.147268 -0.320931 0.935583 + outer loop + vertex 1.36209 0.910101 2.48616 + vertex 1.35881 0.910192 2.48671 + vertex 1.35948 0.907556 2.4857 + endloop + endfacet + facet normal 0.1496 -0.32028 0.935436 + outer loop + vertex 1.35948 0.907556 2.4857 + vertex 1.35881 0.910192 2.48671 + vertex 1.35578 0.906377 2.48589 + endloop + endfacet + facet normal 0.150035 -0.321738 0.934866 + outer loop + vertex 1.35948 0.907556 2.4857 + vertex 1.35578 0.906377 2.48589 + vertex 1.35801 0.903611 2.48458 + endloop + endfacet + facet normal 0.147333 -0.320928 0.935574 + outer loop + vertex 1.35948 0.907556 2.4857 + vertex 1.35801 0.903611 2.48458 + vertex 1.36278 0.907478 2.48515 + endloop + endfacet + facet normal 0.153012 -0.319479 0.935158 + outer loop + vertex 1.35276 0.902555 2.48507 + vertex 1.35801 0.903611 2.48458 + vertex 1.35578 0.906377 2.48589 + endloop + endfacet + facet normal 0.152443 -0.319079 0.935388 + outer loop + vertex 1.35207 0.905193 2.48609 + vertex 1.35276 0.902555 2.48507 + vertex 1.35578 0.906377 2.48589 + endloop + endfacet + facet normal 0.152441 -0.319071 0.93539 + outer loop + vertex 1.35578 0.906377 2.48589 + vertex 1.3536 0.9091 2.48717 + vertex 1.35207 0.905193 2.48609 + endloop + endfacet + facet normal 0.157749 -0.320739 0.933939 + outer loop + vertex 1.35207 0.905193 2.48609 + vertex 1.3536 0.9091 2.48717 + vertex 1.34879 0.905246 2.48666 + endloop + endfacet + facet normal 0.157911 -0.31854 0.934664 + outer loop + vertex 1.35207 0.905193 2.48609 + vertex 1.34879 0.905246 2.48666 + vertex 1.34947 0.902627 2.48565 + endloop + endfacet + facet normal 0.163192 -0.317027 0.934271 + outer loop + vertex 1.34947 0.902627 2.48565 + vertex 1.34879 0.905246 2.48666 + vertex 1.34578 0.901399 2.48588 + endloop + endfacet + facet normal 0.164643 -0.321737 0.932404 + outer loop + vertex 1.34947 0.902627 2.48565 + vertex 1.34578 0.901399 2.48588 + vertex 1.34798 0.898682 2.48455 + endloop + endfacet + facet normal 0.156928 -0.31941 0.934533 + outer loop + vertex 1.34947 0.902627 2.48565 + vertex 1.34798 0.898682 2.48455 + vertex 1.35276 0.902555 2.48507 + endloop + endfacet + facet normal 0.162064 -0.316238 0.934735 + outer loop + vertex 1.34879 0.905246 2.48666 + vertex 1.34361 0.904097 2.48717 + vertex 1.34578 0.901399 2.48588 + endloop + endfacet + facet normal 0.167112 -0.312374 0.935145 + outer loop + vertex 1.34578 0.901399 2.48588 + vertex 1.34361 0.904097 2.48717 + vertex 1.3421 0.900159 2.48612 + endloop + endfacet + facet normal 0.162041 -0.316112 0.934781 + outer loop + vertex 1.34879 0.905246 2.48666 + vertex 1.34834 0.909051 2.48802 + vertex 1.34361 0.904097 2.48717 + endloop + endfacet + facet normal 0.15774 -0.312346 0.936781 + outer loop + vertex 1.34361 0.904097 2.48717 + vertex 1.34834 0.909051 2.48802 + vertex 1.34313 0.908647 2.48877 + endloop + endfacet + facet normal 0.162712 -0.311613 0.936174 + outer loop + vertex 1.34361 0.904097 2.48717 + vertex 1.34313 0.908647 2.48877 + vertex 1.33838 0.904031 2.48806 + endloop + endfacet + facet normal 0.16293 -0.306432 0.937845 + outer loop + vertex 1.34361 0.904097 2.48717 + vertex 1.33838 0.904031 2.48806 + vertex 1.33885 0.90019 2.48672 + endloop + endfacet + facet normal 0.165687 -0.305976 0.937511 + outer loop + vertex 1.33885 0.90019 2.48672 + vertex 1.33838 0.904031 2.48806 + vertex 1.33367 0.899047 2.48726 + endloop + endfacet + facet normal 0.160458 -0.301422 0.939893 + outer loop + vertex 1.33367 0.899047 2.48726 + vertex 1.33838 0.904031 2.48806 + vertex 1.33317 0.90364 2.48882 + endloop + endfacet + facet normal 0.160597 -0.306596 0.938194 + outer loop + vertex 1.33838 0.904031 2.48806 + vertex 1.3379 0.908612 2.48963 + vertex 1.33317 0.90364 2.48882 + endloop + endfacet + facet normal 0.155575 -0.302187 0.940468 + outer loop + vertex 1.33317 0.90364 2.48882 + vertex 1.3379 0.908612 2.48963 + vertex 1.33273 0.907511 2.49014 + endloop + endfacet + facet normal 0.160526 -0.301422 0.939881 + outer loop + vertex 1.33273 0.907511 2.49014 + vertex 1.32797 0.903621 2.4897 + vertex 1.33317 0.90364 2.48882 + endloop + endfacet + facet normal 0.160559 -0.300764 0.940086 + outer loop + vertex 1.32841 0.899011 2.48815 + vertex 1.33317 0.90364 2.48882 + vertex 1.32797 0.903621 2.4897 + endloop + endfacet + facet normal 0.158551 -0.299124 0.94095 + outer loop + vertex 1.3295 0.907594 2.49071 + vertex 1.32797 0.903621 2.4897 + vertex 1.33273 0.907511 2.49014 + endloop + endfacet + facet normal 0.158158 -0.304021 0.939445 + outer loop + vertex 1.33273 0.907511 2.49014 + vertex 1.33208 0.910167 2.4911 + vertex 1.3295 0.907594 2.49071 + endloop + endfacet + facet normal 0.162185 -0.307767 0.937537 + outer loop + vertex 1.33208 0.910167 2.4911 + vertex 1.32885 0.910235 2.49169 + vertex 1.3295 0.907594 2.49071 + endloop + endfacet + facet normal 0.167229 -0.306373 0.937107 + outer loop + vertex 1.3295 0.907594 2.49071 + vertex 1.32885 0.910235 2.49169 + vertex 1.32587 0.906377 2.49096 + endloop + endfacet + facet normal 0.167775 -0.306753 0.936885 + outer loop + vertex 1.32885 0.910235 2.49169 + vertex 1.32373 0.909088 2.49223 + vertex 1.32587 0.906377 2.49096 + endloop + endfacet + facet normal 0.170618 -0.304596 0.937076 + outer loop + vertex 1.32587 0.906377 2.49096 + vertex 1.32373 0.909088 2.49223 + vertex 1.32226 0.905141 2.49121 + endloop + endfacet + facet normal 0.170142 -0.303085 0.937652 + outer loop + vertex 1.32226 0.905141 2.49121 + vertex 1.32287 0.902491 2.49025 + vertex 1.32587 0.906377 2.49096 + endloop + endfacet + facet normal 0.166669 -0.300655 0.939057 + outer loop + vertex 1.32287 0.902491 2.49025 + vertex 1.32797 0.903621 2.4897 + vertex 1.32587 0.906377 2.49096 + endloop + endfacet + facet normal 0.167211 -0.303603 0.938012 + outer loop + vertex 1.32321 0.898612 2.48893 + vertex 1.32797 0.903621 2.4897 + vertex 1.32287 0.902491 2.49025 + endloop + endfacet + facet normal 0.172916 -0.302351 0.937381 + outer loop + vertex 1.32287 0.902491 2.49025 + vertex 1.32226 0.905141 2.49121 + vertex 1.31968 0.902521 2.49084 + endloop + endfacet + facet normal 0.17275 -0.304796 0.93662 + outer loop + vertex 1.31968 0.902521 2.49084 + vertex 1.31806 0.898529 2.48984 + vertex 1.32287 0.902491 2.49025 + endloop + endfacet + facet normal 0.176682 -0.306098 0.935461 + outer loop + vertex 1.31968 0.902521 2.49084 + vertex 1.31598 0.901184 2.4911 + vertex 1.31806 0.898529 2.48984 + endloop + endfacet + facet normal 0.175753 -0.303316 0.936542 + outer loop + vertex 1.31968 0.902521 2.49084 + vertex 1.31901 0.905135 2.49182 + vertex 1.31598 0.901184 2.4911 + endloop + endfacet + facet normal 0.174447 -0.302411 0.937078 + outer loop + vertex 1.31901 0.905135 2.49182 + vertex 1.31368 0.903799 2.49238 + vertex 1.31598 0.901184 2.4911 + endloop + endfacet + facet normal 0.17603 -0.301084 0.93721 + outer loop + vertex 1.31598 0.901184 2.4911 + vertex 1.31368 0.903799 2.49238 + vertex 1.31218 0.899716 2.49135 + endloop + endfacet + facet normal 0.178064 -0.306711 0.934998 + outer loop + vertex 1.31218 0.899716 2.49135 + vertex 1.31297 0.897269 2.49039 + vertex 1.31598 0.901184 2.4911 + endloop + endfacet + facet normal 0.178475 -0.306567 0.934967 + outer loop + vertex 1.31297 0.897269 2.49039 + vertex 1.31218 0.899716 2.49135 + vertex 1.30977 0.897061 2.49093 + endloop + endfacet + facet normal 0.178524 -0.312224 0.933084 + outer loop + vertex 1.30977 0.897061 2.49093 + vertex 1.30841 0.893498 2.49 + vertex 1.31297 0.897269 2.49039 + endloop + endfacet + facet normal 0.174949 -0.303628 0.936591 + outer loop + vertex 1.31218 0.899716 2.49135 + vertex 1.30829 0.899204 2.49191 + vertex 1.30977 0.897061 2.49093 + endloop + endfacet + facet normal 0.175947 -0.30295 0.936624 + outer loop + vertex 1.30977 0.897061 2.49093 + vertex 1.30829 0.899204 2.49191 + vertex 1.30693 0.895609 2.491 + endloop + endfacet + facet normal 0.174706 -0.300691 0.937584 + outer loop + vertex 1.31218 0.899716 2.49135 + vertex 1.31368 0.903799 2.49238 + vertex 1.30829 0.899204 2.49191 + endloop + endfacet + facet normal 0.17259 -0.298325 0.93873 + outer loop + vertex 1.31368 0.903799 2.49238 + vertex 1.30833 0.903775 2.49335 + vertex 1.30829 0.899204 2.49191 + endloop + endfacet + facet normal 0.174305 -0.29825 0.938437 + outer loop + vertex 1.30829 0.899204 2.49191 + vertex 1.30833 0.903775 2.49335 + vertex 1.30337 0.899123 2.49279 + endloop + endfacet + facet normal 0.174227 -0.3002 0.93783 + outer loop + vertex 1.30829 0.899204 2.49191 + vertex 1.30337 0.899123 2.49279 + vertex 1.3037 0.895398 2.49154 + endloop + endfacet + facet normal 0.172565 -0.296502 0.939312 + outer loop + vertex 1.30337 0.899123 2.49279 + vertex 1.30833 0.903775 2.49335 + vertex 1.30325 0.903491 2.4942 + endloop + endfacet + facet normal 0.175343 -0.296278 0.938868 + outer loop + vertex 1.30337 0.899123 2.49279 + vertex 1.30325 0.903491 2.4942 + vertex 1.29831 0.898837 2.49365 + endloop + endfacet + facet normal 0.17535 -0.298595 0.938133 + outer loop + vertex 1.29855 0.894159 2.49212 + vertex 1.30337 0.899123 2.49279 + vertex 1.29831 0.898837 2.49365 + endloop + endfacet + facet normal 0.178202 -0.298298 0.93769 + outer loop + vertex 1.29855 0.894159 2.49212 + vertex 1.29831 0.898837 2.49365 + vertex 1.29337 0.8941 2.49308 + endloop + endfacet + facet normal 0.178032 -0.301931 0.936559 + outer loop + vertex 1.29855 0.894159 2.49212 + vertex 1.29337 0.8941 2.49308 + vertex 1.29377 0.890223 2.49176 + endloop + endfacet + facet normal 0.178273 -0.301895 0.936524 + outer loop + vertex 1.29377 0.890223 2.49176 + vertex 1.29337 0.8941 2.49308 + vertex 1.28862 0.889051 2.49236 + endloop + endfacet + facet normal 0.178317 -0.298411 0.937632 + outer loop + vertex 1.29337 0.8941 2.49308 + vertex 1.29831 0.898837 2.49365 + vertex 1.29308 0.898829 2.49464 + endloop + endfacet + facet normal 0.179752 -0.298247 0.93741 + outer loop + vertex 1.29337 0.8941 2.49308 + vertex 1.29308 0.898829 2.49464 + vertex 1.28823 0.893653 2.49393 + endloop + endfacet + facet normal 0.178482 -0.295481 0.938528 + outer loop + vertex 1.29842 0.903435 2.49508 + vertex 1.29308 0.898829 2.49464 + vertex 1.29831 0.898837 2.49365 + endloop + endfacet + facet normal 0.179089 -0.296155 0.9382 + outer loop + vertex 1.29461 0.902924 2.49564 + vertex 1.29308 0.898829 2.49464 + vertex 1.29842 0.903435 2.49508 + endloop + endfacet + facet normal 0.178822 -0.293019 0.939235 + outer loop + vertex 1.29842 0.903435 2.49508 + vertex 1.29698 0.905601 2.49603 + vertex 1.29461 0.902924 2.49564 + endloop + endfacet + facet normal 0.17998 -0.29397 0.938717 + outer loop + vertex 1.29698 0.905601 2.49603 + vertex 1.29379 0.905377 2.49657 + vertex 1.29461 0.902924 2.49564 + endloop + endfacet + facet normal 0.180208 -0.293886 0.938699 + outer loop + vertex 1.29461 0.902924 2.49564 + vertex 1.29379 0.905377 2.49657 + vertex 1.29086 0.901451 2.4959 + endloop + endfacet + facet normal 0.179493 -0.293402 0.938987 + outer loop + vertex 1.29379 0.905377 2.49657 + vertex 1.2887 0.904114 2.49715 + vertex 1.29086 0.901451 2.4959 + endloop + endfacet + facet normal 0.18006 -0.292957 0.939018 + outer loop + vertex 1.29086 0.901451 2.4959 + vertex 1.2887 0.904114 2.49715 + vertex 1.28722 0.900114 2.49618 + endloop + endfacet + facet normal 0.18174 -0.297926 0.937129 + outer loop + vertex 1.28722 0.900114 2.49618 + vertex 1.28787 0.897504 2.49523 + vertex 1.29086 0.901451 2.4959 + endloop + endfacet + facet normal 0.180756 -0.29725 0.937534 + outer loop + vertex 1.28787 0.897504 2.49523 + vertex 1.29308 0.898829 2.49464 + vertex 1.29086 0.901451 2.4959 + endloop + endfacet + facet normal 0.181249 -0.29955 0.936706 + outer loop + vertex 1.28823 0.893653 2.49393 + vertex 1.29308 0.898829 2.49464 + vertex 1.28787 0.897504 2.49523 + endloop + endfacet + facet normal 0.181258 -0.298065 0.937178 + outer loop + vertex 1.28787 0.897504 2.49523 + vertex 1.28722 0.900114 2.49618 + vertex 1.28468 0.897486 2.49584 + endloop + endfacet + facet normal 0.181183 -0.299464 0.936747 + outer loop + vertex 1.28468 0.897486 2.49584 + vertex 1.28313 0.893516 2.49487 + vertex 1.28787 0.897504 2.49523 + endloop + endfacet + facet normal 0.180654 -0.299296 0.936902 + outer loop + vertex 1.28468 0.897486 2.49584 + vertex 1.28103 0.896165 2.49612 + vertex 1.28313 0.893516 2.49487 + endloop + endfacet + facet normal 0.181787 -0.298428 0.93696 + outer loop + vertex 1.27811 0.892243 2.49544 + vertex 1.28313 0.893516 2.49487 + vertex 1.28103 0.896165 2.49612 + endloop + endfacet + facet normal 0.181696 -0.298367 0.936997 + outer loop + vertex 1.27731 0.894711 2.49638 + vertex 1.27811 0.892243 2.49544 + vertex 1.28103 0.896165 2.49612 + endloop + endfacet + facet normal 0.181021 -0.29651 0.937717 + outer loop + vertex 1.28103 0.896165 2.49612 + vertex 1.27872 0.898813 2.4974 + vertex 1.27731 0.894711 2.49638 + endloop + endfacet + facet normal 0.184925 -0.297572 0.936618 + outer loop + vertex 1.27731 0.894711 2.49638 + vertex 1.27872 0.898813 2.4974 + vertex 1.27345 0.894201 2.49698 + endloop + endfacet + facet normal 0.185013 -0.298671 0.936251 + outer loop + vertex 1.27731 0.894711 2.49638 + vertex 1.27345 0.894201 2.49698 + vertex 1.27497 0.892034 2.49599 + endloop + endfacet + facet normal 0.183742 -0.297643 0.936828 + outer loop + vertex 1.27811 0.892243 2.49544 + vertex 1.27731 0.894711 2.49638 + vertex 1.27497 0.892034 2.49599 + endloop + endfacet + facet normal 0.183766 -0.299882 0.936109 + outer loop + vertex 1.27497 0.892034 2.49599 + vertex 1.27355 0.888392 2.4951 + vertex 1.27811 0.892243 2.49544 + endloop + endfacet + facet normal 0.187132 -0.297208 0.936295 + outer loop + vertex 1.27497 0.892034 2.49599 + vertex 1.27345 0.894201 2.49698 + vertex 1.27216 0.890546 2.49607 + endloop + endfacet + facet normal 0.182781 -0.295234 0.937778 + outer loop + vertex 1.27872 0.898813 2.4974 + vertex 1.27339 0.898874 2.49846 + vertex 1.27345 0.894201 2.49698 + endloop + endfacet + facet normal 0.186759 -0.294955 0.937082 + outer loop + vertex 1.27345 0.894201 2.49698 + vertex 1.27339 0.898874 2.49846 + vertex 1.2685 0.894153 2.49795 + endloop + endfacet + facet normal 0.186794 -0.294259 0.937294 + outer loop + vertex 1.27345 0.894201 2.49698 + vertex 1.2685 0.894153 2.49795 + vertex 1.26894 0.890316 2.49666 + endloop + endfacet + facet normal 0.184783 -0.293019 0.938081 + outer loop + vertex 1.2685 0.894153 2.49795 + vertex 1.27339 0.898874 2.49846 + vertex 1.26808 0.898929 2.49952 + endloop + endfacet + facet normal 0.187338 -0.292665 0.937684 + outer loop + vertex 1.2685 0.894153 2.49795 + vertex 1.26808 0.898929 2.49952 + vertex 1.26334 0.893689 2.49884 + endloop + endfacet + facet normal 0.187224 -0.289427 0.938711 + outer loop + vertex 1.2638 0.889018 2.4973 + vertex 1.2685 0.894153 2.49795 + vertex 1.26334 0.893689 2.49884 + endloop + endfacet + facet normal 0.191787 -0.288743 0.938 + outer loop + vertex 1.2638 0.889018 2.4973 + vertex 1.26334 0.893689 2.49884 + vertex 1.25859 0.888896 2.49833 + endloop + endfacet + facet normal 0.187728 -0.284936 0.939984 + outer loop + vertex 1.25859 0.888896 2.49833 + vertex 1.26334 0.893689 2.49884 + vertex 1.25817 0.893554 2.49983 + endloop + endfacet + facet normal 0.187546 -0.290757 0.938236 + outer loop + vertex 1.26286 0.897595 2.50014 + vertex 1.25817 0.893554 2.49983 + vertex 1.26334 0.893689 2.49884 + endloop + endfacet + facet normal 0.186613 -0.289716 0.938744 + outer loop + vertex 1.25963 0.897562 2.50077 + vertex 1.25817 0.893554 2.49983 + vertex 1.26286 0.897595 2.50014 + endloop + endfacet + facet normal 0.1865 -0.292045 0.938045 + outer loop + vertex 1.26286 0.897595 2.50014 + vertex 1.26215 0.900209 2.5011 + vertex 1.25963 0.897562 2.50077 + endloop + endfacet + facet normal 0.186776 -0.292292 0.937913 + outer loop + vertex 1.26215 0.900209 2.5011 + vertex 1.25894 0.900154 2.50172 + vertex 1.25963 0.897562 2.50077 + endloop + endfacet + facet normal 0.187463 -0.292082 0.937841 + outer loop + vertex 1.25963 0.897562 2.50077 + vertex 1.25894 0.900154 2.50172 + vertex 1.256 0.896206 2.50108 + endloop + endfacet + facet normal 0.188034 -0.292468 0.937606 + outer loop + vertex 1.25894 0.900154 2.50172 + vertex 1.25374 0.898813 2.50234 + vertex 1.256 0.896206 2.50108 + endloop + endfacet + facet normal 0.187708 -0.292741 0.937586 + outer loop + vertex 1.256 0.896206 2.50108 + vertex 1.25374 0.898813 2.50234 + vertex 1.25229 0.894734 2.50136 + endloop + endfacet + facet normal 0.186069 -0.288276 0.939295 + outer loop + vertex 1.25229 0.894734 2.50136 + vertex 1.25313 0.892279 2.50044 + vertex 1.256 0.896206 2.50108 + endloop + endfacet + facet normal 0.187384 -0.289151 0.938764 + outer loop + vertex 1.25313 0.892279 2.50044 + vertex 1.25817 0.893554 2.49983 + vertex 1.256 0.896206 2.50108 + endloop + endfacet + facet normal 0.185473 -0.280102 0.941883 + outer loop + vertex 1.25348 0.888458 2.49924 + vertex 1.25817 0.893554 2.49983 + vertex 1.25313 0.892279 2.50044 + endloop + endfacet + facet normal 0.187585 -0.279809 0.941551 + outer loop + vertex 1.25313 0.892279 2.50044 + vertex 1.24866 0.888439 2.50019 + vertex 1.25348 0.888458 2.49924 + endloop + endfacet + facet normal 0.185977 -0.277991 0.942408 + outer loop + vertex 1.24999 0.892075 2.501 + vertex 1.24866 0.888439 2.50019 + vertex 1.25313 0.892279 2.50044 + endloop + endfacet + facet normal 0.184718 -0.277612 0.942768 + outer loop + vertex 1.24999 0.892075 2.501 + vertex 1.24722 0.89061 2.50111 + vertex 1.24866 0.888439 2.50019 + endloop + endfacet + facet normal 0.187637 -0.275669 0.942761 + outer loop + vertex 1.24866 0.888439 2.50019 + vertex 1.24722 0.89061 2.50111 + vertex 1.24487 0.887922 2.50079 + endloop + endfacet + facet normal 0.187443 -0.273441 0.943449 + outer loop + vertex 1.24487 0.887922 2.50079 + vertex 1.24334 0.883793 2.4999 + vertex 1.24866 0.888439 2.50019 + endloop + endfacet + facet normal 0.194957 -0.275763 0.941247 + outer loop + vertex 1.24487 0.887922 2.50079 + vertex 1.24108 0.886336 2.50111 + vertex 1.24334 0.883793 2.4999 + endloop + endfacet + facet normal 0.194502 -0.276157 0.941226 + outer loop + vertex 1.23815 0.882267 2.50052 + vertex 1.24334 0.883793 2.4999 + vertex 1.24108 0.886336 2.50111 + endloop + endfacet + facet normal 0.20132 -0.280665 0.938455 + outer loop + vertex 1.23726 0.88468 2.50144 + vertex 1.23815 0.882267 2.50052 + vertex 1.24108 0.886336 2.50111 + endloop + endfacet + facet normal 0.200141 -0.277721 0.939582 + outer loop + vertex 1.24108 0.886336 2.50111 + vertex 1.23875 0.888843 2.50235 + vertex 1.23726 0.88468 2.50144 + endloop + endfacet + facet normal 0.205678 -0.279333 0.937907 + outer loop + vertex 1.23726 0.88468 2.50144 + vertex 1.23875 0.888843 2.50235 + vertex 1.23322 0.883912 2.50209 + endloop + endfacet + facet normal 0.205672 -0.279291 0.937921 + outer loop + vertex 1.23726 0.88468 2.50144 + vertex 1.23322 0.883912 2.50209 + vertex 1.23488 0.881855 2.50112 + endloop + endfacet + facet normal 0.207059 -0.278187 0.937944 + outer loop + vertex 1.23488 0.881855 2.50112 + vertex 1.23322 0.883912 2.50209 + vertex 1.23191 0.880095 2.50125 + endloop + endfacet + facet normal 0.229655 -0.317638 0.919981 + outer loop + vertex 1.23488 0.881855 2.50112 + vertex 1.23191 0.880095 2.50125 + vertex 1.2337 0.878219 2.50016 + endloop + endfacet + facet normal 0.207521 -0.312332 0.92703 + outer loop + vertex 1.23488 0.881855 2.50112 + vertex 1.2337 0.878219 2.50016 + vertex 1.23815 0.882267 2.50052 + endloop + endfacet + facet normal 0.225536 -0.321398 0.919694 + outer loop + vertex 1.2337 0.878219 2.50016 + vertex 1.23191 0.880095 2.50125 + vertex 1.22978 0.877349 2.50081 + endloop + endfacet + facet normal 0.210887 -0.311141 0.92667 + outer loop + vertex 1.23191 0.880095 2.50125 + vertex 1.22805 0.879276 2.50185 + vertex 1.22978 0.877349 2.50081 + endloop + endfacet + facet normal 0.205632 -0.277791 0.938375 + outer loop + vertex 1.23191 0.880095 2.50125 + vertex 1.23322 0.883912 2.50209 + vertex 1.22805 0.879276 2.50185 + endloop + endfacet + facet normal 0.203904 -0.275912 0.939306 + outer loop + vertex 1.23322 0.883912 2.50209 + vertex 1.22825 0.883842 2.50315 + vertex 1.22805 0.879276 2.50185 + endloop + endfacet + facet normal 0.204954 -0.275893 0.939083 + outer loop + vertex 1.22805 0.879276 2.50185 + vertex 1.22825 0.883842 2.50315 + vertex 1.22337 0.8792 2.50285 + endloop + endfacet + facet normal 0.200638 -0.271498 0.941294 + outer loop + vertex 1.22337 0.8792 2.50285 + vertex 1.22825 0.883842 2.50315 + vertex 1.2234 0.88367 2.50414 + endloop + endfacet + facet normal 0.200768 -0.265414 0.942999 + outer loop + vertex 1.22825 0.883842 2.50315 + vertex 1.22842 0.888441 2.50441 + vertex 1.2234 0.88367 2.50414 + endloop + endfacet + facet normal 0.194285 -0.258783 0.946195 + outer loop + vertex 1.2234 0.88367 2.50414 + vertex 1.22842 0.888441 2.50441 + vertex 1.22375 0.888279 2.50533 + endloop + endfacet + facet normal 0.19897 -0.258883 0.945193 + outer loop + vertex 1.22375 0.888279 2.50533 + vertex 1.21862 0.883584 2.50512 + vertex 1.2234 0.88367 2.50414 + endloop + endfacet + facet normal 0.198507 -0.271045 0.941875 + outer loop + vertex 1.21852 0.878847 2.50378 + vertex 1.2234 0.88367 2.50414 + vertex 1.21862 0.883584 2.50512 + endloop + endfacet + facet normal 0.204695 -0.270816 0.940616 + outer loop + vertex 1.21862 0.883584 2.50512 + vertex 1.21353 0.878735 2.50483 + vertex 1.21852 0.878847 2.50378 + endloop + endfacet + facet normal 0.209603 -0.275816 0.938079 + outer loop + vertex 1.2147 0.882622 2.50571 + vertex 1.21353 0.878735 2.50483 + vertex 1.21862 0.883584 2.50512 + endloop + endfacet + facet normal 0.205263 -0.253672 0.945261 + outer loop + vertex 1.21862 0.883584 2.50512 + vertex 1.2169 0.885514 2.50601 + vertex 1.2147 0.882622 2.50571 + endloop + endfacet + facet normal 0.212769 -0.259071 0.942131 + outer loop + vertex 1.2169 0.885514 2.50601 + vertex 1.21305 0.884535 2.50661 + vertex 1.2147 0.882622 2.50571 + endloop + endfacet + facet normal 0.214553 -0.26784 0.93927 + outer loop + vertex 1.2169 0.885514 2.50601 + vertex 1.21822 0.889274 2.50678 + vertex 1.21305 0.884535 2.50661 + endloop + endfacet + facet normal 0.208741 -0.261614 0.94233 + outer loop + vertex 1.21822 0.889274 2.50678 + vertex 1.21326 0.889048 2.50782 + vertex 1.21305 0.884535 2.50661 + endloop + endfacet + facet normal 0.213013 -0.261558 0.941389 + outer loop + vertex 1.21305 0.884535 2.50661 + vertex 1.21326 0.889048 2.50782 + vertex 1.20827 0.884199 2.5076 + endloop + endfacet + facet normal 0.212953 -0.256834 0.942702 + outer loop + vertex 1.21305 0.884535 2.50661 + vertex 1.20827 0.884199 2.5076 + vertex 1.20857 0.880405 2.5065 + endloop + endfacet + facet normal 0.207711 -0.256228 0.944035 + outer loop + vertex 1.20827 0.884199 2.5076 + vertex 1.21326 0.889048 2.50782 + vertex 1.20832 0.888792 2.50883 + endloop + endfacet + facet normal 0.210677 -0.256093 0.943415 + outer loop + vertex 1.20827 0.884199 2.5076 + vertex 1.20832 0.888792 2.50883 + vertex 1.20332 0.883766 2.50859 + endloop + endfacet + facet normal 0.210735 -0.257932 0.942901 + outer loop + vertex 1.20354 0.878954 2.50722 + vertex 1.20827 0.884199 2.5076 + vertex 1.20332 0.883766 2.50859 + endloop + endfacet + facet normal 0.20764 -0.269499 0.940349 + outer loop + vertex 1.21326 0.889048 2.50782 + vertex 1.21332 0.893602 2.50911 + vertex 1.20832 0.888792 2.50883 + endloop + endfacet + facet normal 0.200382 -0.262161 0.943991 + outer loop + vertex 1.20832 0.888792 2.50883 + vertex 1.21332 0.893602 2.50911 + vertex 1.20858 0.893485 2.51008 + endloop + endfacet + facet normal 0.199975 -0.274644 0.940521 + outer loop + vertex 1.21305 0.897419 2.51028 + vertex 1.20858 0.893485 2.51008 + vertex 1.21332 0.893602 2.50911 + endloop + endfacet + facet normal 0.196607 -0.275066 0.941108 + outer loop + vertex 1.21332 0.893602 2.50911 + vertex 1.21823 0.898867 2.50962 + vertex 1.21305 0.897419 2.51028 + endloop + endfacet + facet normal 0.197368 -0.278296 0.939998 + outer loop + vertex 1.21305 0.897419 2.51028 + vertex 1.21823 0.898867 2.50962 + vertex 1.21594 0.901442 2.51087 + endloop + endfacet + facet normal 0.194963 -0.280384 0.93988 + outer loop + vertex 1.21971 0.903055 2.51056 + vertex 1.21594 0.901442 2.51087 + vertex 1.21823 0.898867 2.50962 + endloop + endfacet + facet normal 0.196165 -0.280729 0.939527 + outer loop + vertex 1.21971 0.903055 2.51056 + vertex 1.21823 0.898867 2.50962 + vertex 1.22351 0.903592 2.50993 + endloop + endfacet + facet normal 0.196016 -0.279049 0.940058 + outer loop + vertex 1.22351 0.903592 2.50993 + vertex 1.222 0.905768 2.51089 + vertex 1.21971 0.903055 2.51056 + endloop + endfacet + facet normal 0.192202 -0.276037 0.941733 + outer loop + vertex 1.222 0.905768 2.51089 + vertex 1.2188 0.905449 2.51145 + vertex 1.21971 0.903055 2.51056 + endloop + endfacet + facet normal 0.19203 -0.272389 0.94283 + outer loop + vertex 1.222 0.905768 2.51089 + vertex 1.22322 0.909335 2.51168 + vertex 1.2188 0.905449 2.51145 + endloop + endfacet + facet normal 0.189786 -0.269905 0.943998 + outer loop + vertex 1.22322 0.909335 2.51168 + vertex 1.2184 0.909136 2.51259 + vertex 1.2188 0.905449 2.51145 + endloop + endfacet + facet normal 0.190616 -0.269774 0.943868 + outer loop + vertex 1.2188 0.905449 2.51145 + vertex 1.2184 0.909136 2.51259 + vertex 1.2136 0.903934 2.51207 + endloop + endfacet + facet normal 0.1919 -0.274889 0.942131 + outer loop + vertex 1.2188 0.905449 2.51145 + vertex 1.2136 0.903934 2.51207 + vertex 1.21594 0.901442 2.51087 + endloop + endfacet + facet normal 0.193219 -0.273691 0.94221 + outer loop + vertex 1.21594 0.901442 2.51087 + vertex 1.2136 0.903934 2.51207 + vertex 1.21217 0.899843 2.51117 + endloop + endfacet + facet normal 0.194215 -0.276216 0.941268 + outer loop + vertex 1.21217 0.899843 2.51117 + vertex 1.21305 0.897419 2.51028 + vertex 1.21594 0.901442 2.51087 + endloop + endfacet + facet normal 0.195356 -0.275765 0.941164 + outer loop + vertex 1.21305 0.897419 2.51028 + vertex 1.21217 0.899843 2.51117 + vertex 1.20989 0.897144 2.51086 + endloop + endfacet + facet normal 0.195009 -0.275489 0.941317 + outer loop + vertex 1.21217 0.899843 2.51117 + vertex 1.20837 0.899251 2.51179 + vertex 1.20989 0.897144 2.51086 + endloop + endfacet + facet normal 0.19487 -0.274163 0.941733 + outer loop + vertex 1.21217 0.899843 2.51117 + vertex 1.2136 0.903934 2.51207 + vertex 1.20837 0.899251 2.51179 + endloop + endfacet + facet normal 0.193565 -0.272748 0.942412 + outer loop + vertex 1.2136 0.903934 2.51207 + vertex 1.20841 0.903816 2.5131 + vertex 1.20837 0.899251 2.51179 + endloop + endfacet + facet normal 0.193654 -0.270069 0.943165 + outer loop + vertex 1.2136 0.903934 2.51207 + vertex 1.21337 0.90874 2.51349 + vertex 1.20841 0.903816 2.5131 + endloop + endfacet + facet normal 0.194086 -0.270487 0.942957 + outer loop + vertex 1.20841 0.903816 2.5131 + vertex 1.21337 0.90874 2.51349 + vertex 1.20843 0.908384 2.51441 + endloop + endfacet + facet normal 0.197232 -0.270324 0.942351 + outer loop + vertex 1.20841 0.903816 2.5131 + vertex 1.20843 0.908384 2.51441 + vertex 1.20352 0.903645 2.51408 + endloop + endfacet + facet normal 0.197209 -0.271419 0.942041 + outer loop + vertex 1.20356 0.899103 2.51276 + vertex 1.20841 0.903816 2.5131 + vertex 1.20352 0.903645 2.51408 + endloop + endfacet + facet normal 0.20251 -0.271076 0.941014 + outer loop + vertex 1.20356 0.899103 2.51276 + vertex 1.20352 0.903645 2.51408 + vertex 1.19855 0.898806 2.51375 + endloop + endfacet + facet normal 0.200359 -0.268936 0.942088 + outer loop + vertex 1.19855 0.898806 2.51375 + vertex 1.20352 0.903645 2.51408 + vertex 1.1987 0.903577 2.51508 + endloop + endfacet + facet normal 0.204316 -0.268834 0.941267 + outer loop + vertex 1.1987 0.903577 2.51508 + vertex 1.19354 0.898832 2.51485 + vertex 1.19855 0.898806 2.51375 + endloop + endfacet + facet normal 0.204761 -0.261839 0.94314 + outer loop + vertex 1.19348 0.893864 2.51348 + vertex 1.19855 0.898806 2.51375 + vertex 1.19354 0.898832 2.51485 + endloop + endfacet + facet normal 0.210494 -0.261571 0.941952 + outer loop + vertex 1.19354 0.898832 2.51485 + vertex 1.1882 0.893891 2.51467 + vertex 1.19348 0.893864 2.51348 + endloop + endfacet + facet normal 0.203263 -0.253904 0.94563 + outer loop + vertex 1.1896 0.898128 2.5155 + vertex 1.1882 0.893891 2.51467 + vertex 1.19354 0.898832 2.51485 + endloop + endfacet + facet normal 0.204283 -0.261835 0.943245 + outer loop + vertex 1.19354 0.898832 2.51485 + vertex 1.19188 0.900911 2.51578 + vertex 1.1896 0.898128 2.5155 + endloop + endfacet + facet normal 0.205577 -0.262836 0.942685 + outer loop + vertex 1.19188 0.900911 2.51578 + vertex 1.18871 0.900512 2.51636 + vertex 1.1896 0.898128 2.5155 + endloop + endfacet + facet normal 0.208621 -0.261578 0.942366 + outer loop + vertex 1.1896 0.898128 2.5155 + vertex 1.18871 0.900512 2.51636 + vertex 1.18595 0.896489 2.51586 + endloop + endfacet + facet normal 0.206014 -0.268945 0.940865 + outer loop + vertex 1.19188 0.900911 2.51578 + vertex 1.19311 0.904519 2.51654 + vertex 1.18871 0.900512 2.51636 + endloop + endfacet + facet normal 0.203257 -0.265978 0.942307 + outer loop + vertex 1.19311 0.904519 2.51654 + vertex 1.18835 0.904199 2.51748 + vertex 1.18871 0.900512 2.51636 + endloop + endfacet + facet normal 0.208056 -0.265263 0.941461 + outer loop + vertex 1.18871 0.900512 2.51636 + vertex 1.18835 0.904199 2.51748 + vertex 1.18366 0.898958 2.51704 + endloop + endfacet + facet normal 0.203838 -0.261645 0.943394 + outer loop + vertex 1.18366 0.898958 2.51704 + vertex 1.18835 0.904199 2.51748 + vertex 1.1834 0.903782 2.51844 + endloop + endfacet + facet normal 0.207578 -0.261242 0.94269 + outer loop + vertex 1.18366 0.898958 2.51704 + vertex 1.1834 0.903782 2.51844 + vertex 1.17851 0.898811 2.51814 + endloop + endfacet + facet normal 0.204192 -0.258007 0.944319 + outer loop + vertex 1.17851 0.898811 2.51814 + vertex 1.1834 0.903782 2.51844 + vertex 1.17851 0.90343 2.5194 + endloop + endfacet + facet normal 0.203926 -0.264633 0.942541 + outer loop + vertex 1.18835 0.904199 2.51748 + vertex 1.18835 0.908772 2.51876 + vertex 1.1834 0.903782 2.51844 + endloop + endfacet + facet normal 0.200856 -0.264806 0.943152 + outer loop + vertex 1.18835 0.904199 2.51748 + vertex 1.19327 0.908969 2.51777 + vertex 1.18835 0.908772 2.51876 + endloop + endfacet + facet normal 0.203271 -0.267218 0.941953 + outer loop + vertex 1.19311 0.904519 2.51654 + vertex 1.19327 0.908969 2.51777 + vertex 1.18835 0.904199 2.51748 + endloop + endfacet + facet normal 0.199808 -0.267299 0.942671 + outer loop + vertex 1.19821 0.909161 2.51678 + vertex 1.19327 0.908969 2.51777 + vertex 1.19311 0.904519 2.51654 + endloop + endfacet + facet normal 0.201615 -0.269234 0.941735 + outer loop + vertex 1.19695 0.905456 2.51599 + vertex 1.19821 0.909161 2.51678 + vertex 1.19311 0.904519 2.51654 + endloop + endfacet + facet normal 0.201634 -0.269329 0.941704 + outer loop + vertex 1.19695 0.905456 2.51599 + vertex 1.19311 0.904519 2.51654 + vertex 1.19478 0.902652 2.51565 + endloop + endfacet + facet normal 0.200859 -0.268768 0.942029 + outer loop + vertex 1.1987 0.903577 2.51508 + vertex 1.19695 0.905456 2.51599 + vertex 1.19478 0.902652 2.51565 + endloop + endfacet + facet normal 0.200284 -0.269291 0.942003 + outer loop + vertex 1.2 0.907345 2.51588 + vertex 1.19695 0.905456 2.51599 + vertex 1.1987 0.903577 2.51508 + endloop + endfacet + facet normal 0.198964 -0.268917 0.942389 + outer loop + vertex 1.2 0.907345 2.51588 + vertex 1.1987 0.903577 2.51508 + vertex 1.20378 0.908212 2.51533 + endloop + endfacet + facet normal 0.199015 -0.269192 0.9423 + outer loop + vertex 1.20378 0.908212 2.51533 + vertex 1.20219 0.910146 2.51622 + vertex 1.2 0.907345 2.51588 + endloop + endfacet + facet normal 0.199315 -0.269411 0.942174 + outer loop + vertex 1.20219 0.910146 2.51622 + vertex 1.19821 0.909161 2.51678 + vertex 1.2 0.907345 2.51588 + endloop + endfacet + facet normal 0.198987 -0.267782 0.942707 + outer loop + vertex 1.20219 0.910146 2.51622 + vertex 1.20343 0.913899 2.51702 + vertex 1.19821 0.909161 2.51678 + endloop + endfacet + facet normal 0.197125 -0.265779 0.943665 + outer loop + vertex 1.20343 0.913899 2.51702 + vertex 1.19836 0.913795 2.51805 + vertex 1.19821 0.909161 2.51678 + endloop + endfacet + facet normal 0.199975 -0.268779 0.942214 + outer loop + vertex 1.2 0.907345 2.51588 + vertex 1.19821 0.909161 2.51678 + vertex 1.19695 0.905456 2.51599 + endloop + endfacet + facet normal 0.199835 -0.26572 0.943111 + outer loop + vertex 1.19821 0.909161 2.51678 + vertex 1.19836 0.913795 2.51805 + vertex 1.19327 0.908969 2.51777 + endloop + endfacet + facet normal 0.198104 -0.263942 0.943975 + outer loop + vertex 1.19327 0.908969 2.51777 + vertex 1.19836 0.913795 2.51805 + vertex 1.19344 0.913628 2.51904 + endloop + endfacet + facet normal 0.20303 -0.268108 0.941752 + outer loop + vertex 1.19478 0.902652 2.51565 + vertex 1.19311 0.904519 2.51654 + vertex 1.19188 0.900911 2.51578 + endloop + endfacet + facet normal 0.200932 -0.264499 0.943221 + outer loop + vertex 1.19478 0.902652 2.51565 + vertex 1.19188 0.900911 2.51578 + vertex 1.19354 0.898832 2.51485 + endloop + endfacet + facet normal 0.200006 -0.264254 0.943487 + outer loop + vertex 1.19478 0.902652 2.51565 + vertex 1.19354 0.898832 2.51485 + vertex 1.1987 0.903577 2.51508 + endloop + endfacet + facet normal 0.200298 -0.270342 0.941699 + outer loop + vertex 1.20378 0.908212 2.51533 + vertex 1.1987 0.903577 2.51508 + vertex 1.20352 0.903645 2.51408 + endloop + endfacet + facet normal 0.191229 -0.270312 0.94359 + outer loop + vertex 1.2136 0.903934 2.51207 + vertex 1.2184 0.909136 2.51259 + vertex 1.21337 0.90874 2.51349 + endloop + endfacet + facet normal 0.19117 -0.268071 0.944242 + outer loop + vertex 1.2184 0.909136 2.51259 + vertex 1.21836 0.913673 2.51388 + vertex 1.21337 0.90874 2.51349 + endloop + endfacet + facet normal 0.192197 -0.26907 0.943749 + outer loop + vertex 1.21337 0.90874 2.51349 + vertex 1.21836 0.913673 2.51388 + vertex 1.21332 0.913642 2.5149 + endloop + endfacet + facet normal 0.189858 -0.268151 0.944484 + outer loop + vertex 1.2184 0.909136 2.51259 + vertex 1.2233 0.913858 2.51294 + vertex 1.21836 0.913673 2.51388 + endloop + endfacet + facet normal 0.18987 -0.26735 0.944708 + outer loop + vertex 1.2233 0.913858 2.51294 + vertex 1.2233 0.91843 2.51424 + vertex 1.21836 0.913673 2.51388 + endloop + endfacet + facet normal 0.188535 -0.26742 0.944956 + outer loop + vertex 1.2233 0.913858 2.51294 + vertex 1.22829 0.918785 2.51334 + vertex 1.2233 0.91843 2.51424 + endloop + endfacet + facet normal 0.188477 -0.267364 0.944983 + outer loop + vertex 1.22847 0.913982 2.51195 + vertex 1.22829 0.918785 2.51334 + vertex 1.2233 0.913858 2.51294 + endloop + endfacet + facet normal 0.188454 -0.268148 0.944765 + outer loop + vertex 1.22847 0.913982 2.51195 + vertex 1.2233 0.913858 2.51294 + vertex 1.22322 0.909335 2.51168 + endloop + endfacet + facet normal 0.190441 -0.270334 0.943743 + outer loop + vertex 1.22699 0.90992 2.51108 + vertex 1.22847 0.913982 2.51195 + vertex 1.22322 0.909335 2.51168 + endloop + endfacet + facet normal 0.190727 -0.273031 0.942909 + outer loop + vertex 1.22699 0.90992 2.51108 + vertex 1.22322 0.909335 2.51168 + vertex 1.22472 0.907254 2.51077 + endloop + endfacet + facet normal 0.193722 -0.275424 0.941602 + outer loop + vertex 1.2279 0.907487 2.51018 + vertex 1.22699 0.90992 2.51108 + vertex 1.22472 0.907254 2.51077 + endloop + endfacet + facet normal 0.193787 -0.27897 0.940544 + outer loop + vertex 1.22472 0.907254 2.51077 + vertex 1.22351 0.903592 2.50993 + vertex 1.2279 0.907487 2.51018 + endloop + endfacet + facet normal 0.195828 -0.281198 0.939457 + outer loop + vertex 1.2279 0.907487 2.51018 + vertex 1.22351 0.903592 2.50993 + vertex 1.22841 0.90363 2.50892 + endloop + endfacet + facet normal 0.193085 -0.281696 0.939875 + outer loop + vertex 1.22841 0.90363 2.50892 + vertex 1.23312 0.908906 2.50953 + vertex 1.2279 0.907487 2.51018 + endloop + endfacet + facet normal 0.191776 -0.27598 0.941837 + outer loop + vertex 1.2279 0.907487 2.51018 + vertex 1.23312 0.908906 2.50953 + vertex 1.23075 0.91148 2.51077 + endloop + endfacet + facet normal 0.190342 -0.277263 0.941751 + outer loop + vertex 1.23456 0.913096 2.51048 + vertex 1.23075 0.91148 2.51077 + vertex 1.23312 0.908906 2.50953 + endloop + endfacet + facet normal 0.189537 -0.277039 0.941979 + outer loop + vertex 1.23456 0.913096 2.51048 + vertex 1.23312 0.908906 2.50953 + vertex 1.23854 0.91375 2.50987 + endloop + endfacet + facet normal 0.189129 -0.273523 0.943088 + outer loop + vertex 1.23854 0.91375 2.50987 + vertex 1.23694 0.915868 2.51081 + vertex 1.23456 0.913096 2.51048 + endloop + endfacet + facet normal 0.186987 -0.271796 0.944014 + outer loop + vertex 1.23694 0.915868 2.51081 + vertex 1.23367 0.915493 2.51134 + vertex 1.23456 0.913096 2.51048 + endloop + endfacet + facet normal 0.186829 -0.269369 0.944741 + outer loop + vertex 1.23694 0.915868 2.51081 + vertex 1.2382 0.919461 2.51158 + vertex 1.23367 0.915493 2.51134 + endloop + endfacet + facet normal 0.185779 -0.268205 0.945279 + outer loop + vertex 1.2382 0.919461 2.51158 + vertex 1.23334 0.919191 2.51246 + vertex 1.23367 0.915493 2.51134 + endloop + endfacet + facet normal 0.187266 -0.268001 0.945043 + outer loop + vertex 1.23367 0.915493 2.51134 + vertex 1.23334 0.919191 2.51246 + vertex 1.22847 0.913982 2.51195 + endloop + endfacet + facet normal 0.188137 -0.271465 0.943881 + outer loop + vertex 1.23367 0.915493 2.51134 + vertex 1.22847 0.913982 2.51195 + vertex 1.23075 0.91148 2.51077 + endloop + endfacet + facet normal 0.185784 -0.269279 0.944973 + outer loop + vertex 1.2382 0.919461 2.51158 + vertex 1.2383 0.923919 2.51283 + vertex 1.23334 0.919191 2.51246 + endloop + endfacet + facet normal 0.184828 -0.268315 0.945434 + outer loop + vertex 1.23334 0.919191 2.51246 + vertex 1.2383 0.923919 2.51283 + vertex 1.23331 0.923736 2.51375 + endloop + endfacet + facet normal 0.186745 -0.268203 0.945089 + outer loop + vertex 1.23334 0.919191 2.51246 + vertex 1.23331 0.923736 2.51375 + vertex 1.22829 0.918785 2.51334 + endloop + endfacet + facet normal 0.184793 -0.269309 0.945158 + outer loop + vertex 1.24328 0.923993 2.51188 + vertex 1.2383 0.923919 2.51283 + vertex 1.2382 0.919461 2.51158 + endloop + endfacet + facet normal 0.186872 -0.271573 0.944101 + outer loop + vertex 1.242 0.920277 2.51106 + vertex 1.24328 0.923993 2.51188 + vertex 1.2382 0.919461 2.51158 + endloop + endfacet + facet normal 0.186524 -0.269538 0.944753 + outer loop + vertex 1.242 0.920277 2.51106 + vertex 1.2382 0.919461 2.51158 + vertex 1.23985 0.917549 2.51071 + endloop + endfacet + facet normal 0.187799 -0.270472 0.944233 + outer loop + vertex 1.24361 0.918301 2.51018 + vertex 1.242 0.920277 2.51106 + vertex 1.23985 0.917549 2.51071 + endloop + endfacet + facet normal 0.188235 -0.273289 0.943335 + outer loop + vertex 1.23985 0.917549 2.51071 + vertex 1.23854 0.91375 2.50987 + vertex 1.24361 0.918301 2.51018 + endloop + endfacet + facet normal 0.188677 -0.273766 0.943108 + outer loop + vertex 1.24361 0.918301 2.51018 + vertex 1.23854 0.91375 2.50987 + vertex 1.24351 0.913664 2.50885 + endloop + endfacet + facet normal 0.186825 -0.273826 0.943459 + outer loop + vertex 1.24351 0.913664 2.50885 + vertex 1.24839 0.918449 2.50927 + vertex 1.24361 0.918301 2.51018 + endloop + endfacet + facet normal 0.186851 -0.272673 0.943788 + outer loop + vertex 1.2481 0.922262 2.51043 + vertex 1.24361 0.918301 2.51018 + vertex 1.24839 0.918449 2.50927 + endloop + endfacet + facet normal 0.183459 -0.273097 0.944331 + outer loop + vertex 1.24839 0.918449 2.50927 + vertex 1.25326 0.923677 2.50984 + vertex 1.2481 0.922262 2.51043 + endloop + endfacet + facet normal 0.183646 -0.27389 0.944065 + outer loop + vertex 1.2481 0.922262 2.51043 + vertex 1.25326 0.923677 2.50984 + vertex 1.25106 0.926285 2.51102 + endloop + endfacet + facet normal 0.182962 -0.273425 0.944332 + outer loop + vertex 1.24726 0.924692 2.5113 + vertex 1.2481 0.922262 2.51043 + vertex 1.25106 0.926285 2.51102 + endloop + endfacet + facet normal 0.184323 -0.276896 0.943056 + outer loop + vertex 1.25106 0.926285 2.51102 + vertex 1.24875 0.92883 2.51222 + vertex 1.24726 0.924692 2.5113 + endloop + endfacet + facet normal 0.186079 -0.277416 0.942558 + outer loop + vertex 1.24726 0.924692 2.5113 + vertex 1.24875 0.92883 2.51222 + vertex 1.24328 0.923993 2.51188 + endloop + endfacet + facet normal 0.185495 -0.272906 0.943988 + outer loop + vertex 1.24726 0.924692 2.5113 + vertex 1.24328 0.923993 2.51188 + vertex 1.24489 0.921946 2.51097 + endloop + endfacet + facet normal 0.18291 -0.273954 0.944189 + outer loop + vertex 1.24875 0.92883 2.51222 + vertex 1.24339 0.928778 2.51324 + vertex 1.24328 0.923993 2.51188 + endloop + endfacet + facet normal 0.182719 -0.278259 0.942967 + outer loop + vertex 1.24875 0.92883 2.51222 + vertex 1.24849 0.933734 2.51372 + vertex 1.24339 0.928778 2.51324 + endloop + endfacet + facet normal 0.179796 -0.278556 0.94344 + outer loop + vertex 1.24875 0.92883 2.51222 + vertex 1.2536 0.934046 2.51284 + vertex 1.24849 0.933734 2.51372 + endloop + endfacet + facet normal 0.182031 -0.27891 0.942907 + outer loop + vertex 1.25402 0.930281 2.51163 + vertex 1.24875 0.92883 2.51222 + vertex 1.25106 0.926285 2.51102 + endloop + endfacet + facet normal 0.185128 -0.272609 0.944146 + outer loop + vertex 1.2481 0.922262 2.51043 + vertex 1.24726 0.924692 2.5113 + vertex 1.24489 0.921946 2.51097 + endloop + endfacet + facet normal 0.186044 -0.27538 0.943162 + outer loop + vertex 1.25345 0.918768 2.50837 + vertex 1.25326 0.923677 2.50984 + vertex 1.24839 0.918449 2.50927 + endloop + endfacet + facet normal 0.186032 -0.274291 0.943481 + outer loop + vertex 1.24857 0.913962 2.50793 + vertex 1.25345 0.918768 2.50837 + vertex 1.24839 0.918449 2.50927 + endloop + endfacet + facet normal 0.18715 -0.275377 0.942943 + outer loop + vertex 1.25349 0.914102 2.507 + vertex 1.25345 0.918768 2.50837 + vertex 1.24857 0.913962 2.50793 + endloop + endfacet + facet normal 0.187175 -0.274423 0.943217 + outer loop + vertex 1.25349 0.914102 2.507 + vertex 1.24857 0.913962 2.50793 + vertex 1.24902 0.910165 2.50674 + endloop + endfacet + facet normal 0.187648 -0.274943 0.942971 + outer loop + vertex 1.25226 0.910451 2.50618 + vertex 1.25349 0.914102 2.507 + vertex 1.24902 0.910165 2.50674 + endloop + endfacet + facet normal 0.187732 -0.277264 0.942274 + outer loop + vertex 1.25226 0.910451 2.50618 + vertex 1.24902 0.910165 2.50674 + vertex 1.2499 0.907724 2.50585 + endloop + endfacet + facet normal 0.190087 -0.279175 0.941238 + outer loop + vertex 1.25367 0.908292 2.50525 + vertex 1.25226 0.910451 2.50618 + vertex 1.2499 0.907724 2.50585 + endloop + endfacet + facet normal 0.190685 -0.28514 0.939326 + outer loop + vertex 1.2499 0.907724 2.50585 + vertex 1.24833 0.903593 2.50491 + vertex 1.25367 0.908292 2.50525 + endloop + endfacet + facet normal 0.189611 -0.28396 0.939901 + outer loop + vertex 1.25367 0.908292 2.50525 + vertex 1.24833 0.903593 2.50491 + vertex 1.25351 0.903641 2.50388 + endloop + endfacet + facet normal 0.188509 -0.283985 0.940115 + outer loop + vertex 1.25351 0.903641 2.50388 + vertex 1.25837 0.908396 2.50434 + vertex 1.25367 0.908292 2.50525 + endloop + endfacet + facet normal 0.1887 -0.278444 0.941733 + outer loop + vertex 1.25811 0.91218 2.50551 + vertex 1.25367 0.908292 2.50525 + vertex 1.25837 0.908396 2.50434 + endloop + endfacet + facet normal 0.185165 -0.278862 0.942311 + outer loop + vertex 1.25837 0.908396 2.50434 + vertex 1.26307 0.913457 2.50492 + vertex 1.25811 0.91218 2.50551 + endloop + endfacet + facet normal 0.184575 -0.27615 0.943225 + outer loop + vertex 1.25811 0.91218 2.50551 + vertex 1.26307 0.913457 2.50492 + vertex 1.261 0.91614 2.50611 + endloop + endfacet + facet normal 0.185562 -0.276811 0.942838 + outer loop + vertex 1.25731 0.914655 2.5064 + vertex 1.25811 0.91218 2.50551 + vertex 1.261 0.91614 2.50611 + endloop + endfacet + facet normal 0.186031 -0.278065 0.942376 + outer loop + vertex 1.261 0.91614 2.50611 + vertex 1.25874 0.918776 2.50733 + vertex 1.25731 0.914655 2.5064 + endloop + endfacet + facet normal 0.188486 -0.278758 0.941683 + outer loop + vertex 1.25731 0.914655 2.5064 + vertex 1.25874 0.918776 2.50733 + vertex 1.25349 0.914102 2.507 + endloop + endfacet + facet normal 0.18823 -0.276073 0.942525 + outer loop + vertex 1.25731 0.914655 2.5064 + vertex 1.25349 0.914102 2.507 + vertex 1.25502 0.911958 2.50606 + endloop + endfacet + facet normal 0.183236 -0.280397 0.942232 + outer loop + vertex 1.26396 0.920112 2.50671 + vertex 1.25874 0.918776 2.50733 + vertex 1.261 0.91614 2.50611 + endloop + endfacet + facet normal 0.183175 -0.280355 0.942257 + outer loop + vertex 1.26463 0.917494 2.5058 + vertex 1.26396 0.920112 2.50671 + vertex 1.261 0.91614 2.50611 + endloop + endfacet + facet normal 0.17933 -0.281477 0.942662 + outer loop + vertex 1.26719 0.920146 2.50611 + vertex 1.26396 0.920112 2.50671 + vertex 1.26463 0.917494 2.5058 + endloop + endfacet + facet normal 0.178067 -0.280322 0.943245 + outer loop + vertex 1.26783 0.917502 2.5052 + vertex 1.26719 0.920146 2.50611 + vertex 1.26463 0.917494 2.5058 + endloop + endfacet + facet normal 0.17826 -0.27654 0.944325 + outer loop + vertex 1.26463 0.917494 2.5058 + vertex 1.26307 0.913457 2.50492 + vertex 1.26783 0.917502 2.5052 + endloop + endfacet + facet normal 0.182 -0.280802 0.942351 + outer loop + vertex 1.26783 0.917502 2.5052 + vertex 1.26307 0.913457 2.50492 + vertex 1.26811 0.913595 2.50398 + endloop + endfacet + facet normal 0.177747 -0.28132 0.943009 + outer loop + vertex 1.26811 0.913595 2.50398 + vertex 1.27306 0.918806 2.50461 + vertex 1.26783 0.917502 2.5052 + endloop + endfacet + facet normal 0.181826 -0.284965 0.941135 + outer loop + vertex 1.27321 0.913926 2.5031 + vertex 1.27306 0.918806 2.50461 + vertex 1.26811 0.913595 2.50398 + endloop + endfacet + facet normal 0.181798 -0.282696 0.941824 + outer loop + vertex 1.26831 0.909187 2.50262 + vertex 1.27321 0.913926 2.5031 + vertex 1.26811 0.913595 2.50398 + endloop + endfacet + facet normal 0.184247 -0.282461 0.941418 + outer loop + vertex 1.26831 0.909187 2.50262 + vertex 1.26811 0.913595 2.50398 + vertex 1.26331 0.908781 2.50348 + endloop + endfacet + facet normal 0.184301 -0.284342 0.940842 + outer loop + vertex 1.26364 0.904173 2.50202 + vertex 1.26831 0.909187 2.50262 + vertex 1.26331 0.908781 2.50348 + endloop + endfacet + facet normal 0.186669 -0.284055 0.940461 + outer loop + vertex 1.26364 0.904173 2.50202 + vertex 1.26331 0.908781 2.50348 + vertex 1.25855 0.903979 2.50297 + endloop + endfacet + facet normal 0.186581 -0.288871 0.939011 + outer loop + vertex 1.26364 0.904173 2.50202 + vertex 1.25855 0.903979 2.50297 + vertex 1.25894 0.900154 2.50172 + endloop + endfacet + facet normal 0.186443 -0.283842 0.94057 + outer loop + vertex 1.25855 0.903979 2.50297 + vertex 1.26331 0.908781 2.50348 + vertex 1.25837 0.908396 2.50434 + endloop + endfacet + facet normal 0.183784 -0.284653 0.940848 + outer loop + vertex 1.27313 0.909338 2.50173 + vertex 1.27321 0.913926 2.5031 + vertex 1.26831 0.909187 2.50262 + endloop + endfacet + facet normal 0.183792 -0.28435 0.940939 + outer loop + vertex 1.27313 0.909338 2.50173 + vertex 1.26831 0.909187 2.50262 + vertex 1.26867 0.905493 2.50144 + endloop + endfacet + facet normal 0.184182 -0.284787 0.94073 + outer loop + vertex 1.27183 0.905739 2.50089 + vertex 1.27313 0.909338 2.50173 + vertex 1.26867 0.905493 2.50144 + endloop + endfacet + facet normal 0.1841 -0.284763 0.940753 + outer loop + vertex 1.2746 0.907214 2.50079 + vertex 1.27313 0.909338 2.50173 + vertex 1.27183 0.905739 2.50089 + endloop + endfacet + facet normal 0.185624 -0.287702 0.939559 + outer loop + vertex 1.2746 0.907214 2.50079 + vertex 1.27183 0.905739 2.50089 + vertex 1.27334 0.903565 2.49993 + endloop + endfacet + facet normal 0.183065 -0.286989 0.940279 + outer loop + vertex 1.2746 0.907214 2.50079 + vertex 1.27334 0.903565 2.49993 + vertex 1.27782 0.907445 2.50024 + endloop + endfacet + facet normal 0.183018 -0.284473 0.941052 + outer loop + vertex 1.27782 0.907445 2.50024 + vertex 1.27695 0.909895 2.50115 + vertex 1.2746 0.907214 2.50079 + endloop + endfacet + facet normal 0.182038 -0.284848 0.941129 + outer loop + vertex 1.27695 0.909895 2.50115 + vertex 1.27782 0.907445 2.50024 + vertex 1.28077 0.911439 2.50088 + endloop + endfacet + facet normal 0.182524 -0.286136 0.940644 + outer loop + vertex 1.28077 0.911439 2.50088 + vertex 1.2785 0.913982 2.50209 + vertex 1.27695 0.909895 2.50115 + endloop + endfacet + facet normal 0.183851 -0.286549 0.94026 + outer loop + vertex 1.27695 0.909895 2.50115 + vertex 1.2785 0.913982 2.50209 + vertex 1.27313 0.909338 2.50173 + endloop + endfacet + facet normal 0.181116 -0.28735 0.940546 + outer loop + vertex 1.28377 0.915411 2.50151 + vertex 1.2785 0.913982 2.50209 + vertex 1.28077 0.911439 2.50088 + endloop + endfacet + facet normal 0.180163 -0.286693 0.940929 + outer loop + vertex 1.2846 0.91298 2.50061 + vertex 1.28377 0.915411 2.50151 + vertex 1.28077 0.911439 2.50088 + endloop + endfacet + facet normal 0.179205 -0.284147 0.941884 + outer loop + vertex 1.2846 0.91298 2.50061 + vertex 1.28077 0.911439 2.50088 + vertex 1.28308 0.908836 2.49965 + endloop + endfacet + facet normal 0.174245 -0.282644 0.943266 + outer loop + vertex 1.2846 0.91298 2.50061 + vertex 1.28308 0.908836 2.49965 + vertex 1.28843 0.913466 2.50005 + endloop + endfacet + facet normal 0.176928 -0.285627 0.941867 + outer loop + vertex 1.28843 0.913466 2.50005 + vertex 1.28308 0.908836 2.49965 + vertex 1.28836 0.908828 2.49866 + endloop + endfacet + facet normal 0.171945 -0.285803 0.942736 + outer loop + vertex 1.28836 0.908828 2.49866 + vertex 1.29326 0.913487 2.49918 + vertex 1.28843 0.913466 2.50005 + endloop + endfacet + facet normal 0.176302 -0.290149 0.940602 + outer loop + vertex 1.29342 0.909111 2.4978 + vertex 1.29326 0.913487 2.49918 + vertex 1.28836 0.908828 2.49866 + endloop + endfacet + facet normal 0.176298 -0.289068 0.940935 + outer loop + vertex 1.2887 0.904114 2.49715 + vertex 1.29342 0.909111 2.4978 + vertex 1.28836 0.908828 2.49866 + endloop + endfacet + facet normal 0.178632 -0.288786 0.940581 + outer loop + vertex 1.2887 0.904114 2.49715 + vertex 1.28836 0.908828 2.49866 + vertex 1.28349 0.904035 2.49811 + endloop + endfacet + facet normal 0.178519 -0.291573 0.939742 + outer loop + vertex 1.2887 0.904114 2.49715 + vertex 1.28349 0.904035 2.49811 + vertex 1.28398 0.900109 2.4968 + endloop + endfacet + facet normal 0.179402 -0.291422 0.939621 + outer loop + vertex 1.28398 0.900109 2.4968 + vertex 1.28349 0.904035 2.49811 + vertex 1.27872 0.898813 2.4974 + endloop + endfacet + facet normal 0.180225 -0.292124 0.939246 + outer loop + vertex 1.27872 0.898813 2.4974 + vertex 1.28349 0.904035 2.49811 + vertex 1.27828 0.9036 2.49898 + endloop + endfacet + facet normal 0.180053 -0.286645 0.940965 + outer loop + vertex 1.28349 0.904035 2.49811 + vertex 1.28308 0.908836 2.49965 + vertex 1.27828 0.9036 2.49898 + endloop + endfacet + facet normal 0.180876 -0.28735 0.940592 + outer loop + vertex 1.27828 0.9036 2.49898 + vertex 1.28308 0.908836 2.49965 + vertex 1.27782 0.907445 2.50024 + endloop + endfacet + facet normal 0.176846 -0.28707 0.941444 + outer loop + vertex 1.28349 0.904035 2.49811 + vertex 1.28836 0.908828 2.49866 + vertex 1.28308 0.908836 2.49965 + endloop + endfacet + facet normal 0.172577 -0.290475 0.941191 + outer loop + vertex 1.29342 0.909111 2.4978 + vertex 1.29834 0.913769 2.49833 + vertex 1.29326 0.913487 2.49918 + endloop + endfacet + facet normal 0.172592 -0.294432 0.939958 + outer loop + vertex 1.29834 0.913769 2.49833 + vertex 1.29809 0.918458 2.49985 + vertex 1.29326 0.913487 2.49918 + endloop + endfacet + facet normal 0.167452 -0.28976 0.942337 + outer loop + vertex 1.29326 0.913487 2.49918 + vertex 1.29809 0.918458 2.49985 + vertex 1.29298 0.917257 2.50039 + endloop + endfacet + facet normal 0.171774 -0.289247 0.941716 + outer loop + vertex 1.29298 0.917257 2.50039 + vertex 1.28843 0.913466 2.50005 + vertex 1.29326 0.913487 2.49918 + endloop + endfacet + facet normal 0.168232 -0.285163 0.9436 + outer loop + vertex 1.28981 0.917097 2.5009 + vertex 1.28843 0.913466 2.50005 + vertex 1.29298 0.917257 2.50039 + endloop + endfacet + facet normal 0.168236 -0.290892 0.941849 + outer loop + vertex 1.29298 0.917257 2.50039 + vertex 1.29219 0.91973 2.50129 + vertex 1.28981 0.917097 2.5009 + endloop + endfacet + facet normal 0.172009 -0.294047 0.940186 + outer loop + vertex 1.29219 0.91973 2.50129 + vertex 1.28833 0.919241 2.50184 + vertex 1.28981 0.917097 2.5009 + endloop + endfacet + facet normal 0.174517 -0.292343 0.940255 + outer loop + vertex 1.28981 0.917097 2.5009 + vertex 1.28833 0.919241 2.50184 + vertex 1.287 0.915659 2.50098 + endloop + endfacet + facet normal 0.178328 -0.293497 0.93918 + outer loop + vertex 1.287 0.915659 2.50098 + vertex 1.28833 0.919241 2.50184 + vertex 1.28377 0.915411 2.50151 + endloop + endfacet + facet normal 0.178178 -0.28743 0.941082 + outer loop + vertex 1.287 0.915659 2.50098 + vertex 1.28377 0.915411 2.50151 + vertex 1.2846 0.91298 2.50061 + endloop + endfacet + facet normal 0.174375 -0.284256 0.942757 + outer loop + vertex 1.28843 0.913466 2.50005 + vertex 1.287 0.915659 2.50098 + vertex 1.2846 0.91298 2.50061 + endloop + endfacet + facet normal 0.172131 -0.295571 0.939686 + outer loop + vertex 1.29219 0.91973 2.50129 + vertex 1.29366 0.9238 2.5023 + vertex 1.28833 0.919241 2.50184 + endloop + endfacet + facet normal 0.167161 -0.29411 0.94104 + outer loop + vertex 1.29597 0.921149 2.50106 + vertex 1.29366 0.9238 2.5023 + vertex 1.29219 0.91973 2.50129 + endloop + endfacet + facet normal 0.165953 -0.295115 0.940939 + outer loop + vertex 1.29898 0.925081 2.50177 + vertex 1.29366 0.9238 2.5023 + vertex 1.29597 0.921149 2.50106 + endloop + endfacet + facet normal 0.16552 -0.294814 0.94111 + outer loop + vertex 1.29968 0.922451 2.50082 + vertex 1.29898 0.925081 2.50177 + vertex 1.29597 0.921149 2.50106 + endloop + endfacet + facet normal 0.165507 -0.294772 0.941125 + outer loop + vertex 1.29968 0.922451 2.50082 + vertex 1.29597 0.921149 2.50106 + vertex 1.29809 0.918458 2.49985 + endloop + endfacet + facet normal 0.166551 -0.295118 0.940833 + outer loop + vertex 1.29968 0.922451 2.50082 + vertex 1.29809 0.918458 2.49985 + vertex 1.3029 0.922419 2.50024 + endloop + endfacet + facet normal 0.166433 -0.296936 0.940282 + outer loop + vertex 1.3029 0.922419 2.50024 + vertex 1.30226 0.925065 2.50119 + vertex 1.29968 0.922451 2.50082 + endloop + endfacet + facet normal 0.166258 -0.296984 0.940297 + outer loop + vertex 1.30226 0.925065 2.50119 + vertex 1.3029 0.922419 2.50024 + vertex 1.30588 0.926317 2.50094 + endloop + endfacet + facet normal 0.165454 -0.294473 0.941228 + outer loop + vertex 1.30588 0.926317 2.50094 + vertex 1.30373 0.92904 2.50217 + vertex 1.30226 0.925065 2.50119 + endloop + endfacet + facet normal 0.164522 -0.294189 0.94148 + outer loop + vertex 1.30226 0.925065 2.50119 + vertex 1.30373 0.92904 2.50217 + vertex 1.29898 0.925081 2.50177 + endloop + endfacet + facet normal 0.164314 -0.295341 0.941156 + outer loop + vertex 1.30884 0.930193 2.50164 + vertex 1.30373 0.92904 2.50217 + vertex 1.30588 0.926317 2.50094 + endloop + endfacet + facet normal 0.166253 -0.296681 0.940394 + outer loop + vertex 1.3095 0.927573 2.5007 + vertex 1.30884 0.930193 2.50164 + vertex 1.30588 0.926317 2.50094 + endloop + endfacet + facet normal 0.166861 -0.298569 0.939688 + outer loop + vertex 1.3095 0.927573 2.5007 + vertex 1.30588 0.926317 2.50094 + vertex 1.30802 0.923587 2.49969 + endloop + endfacet + facet normal 0.166738 -0.298532 0.939722 + outer loop + vertex 1.3095 0.927573 2.5007 + vertex 1.30802 0.923587 2.49969 + vertex 1.31272 0.927538 2.50012 + endloop + endfacet + facet normal 0.166776 -0.297955 0.939898 + outer loop + vertex 1.31272 0.927538 2.50012 + vertex 1.31204 0.930176 2.50107 + vertex 1.3095 0.927573 2.5007 + endloop + endfacet + facet normal 0.165477 -0.298328 0.940009 + outer loop + vertex 1.31204 0.930176 2.50107 + vertex 1.31272 0.927538 2.50012 + vertex 1.31568 0.93143 2.50083 + endloop + endfacet + facet normal 0.165379 -0.298021 0.940124 + outer loop + vertex 1.31568 0.93143 2.50083 + vertex 1.31357 0.934108 2.50205 + vertex 1.31204 0.930176 2.50107 + endloop + endfacet + facet normal 0.165513 -0.298064 0.940087 + outer loop + vertex 1.31204 0.930176 2.50107 + vertex 1.31357 0.934108 2.50205 + vertex 1.30884 0.930193 2.50164 + endloop + endfacet + facet normal 0.162646 -0.294755 0.941629 + outer loop + vertex 1.31357 0.934108 2.50205 + vertex 1.30846 0.934003 2.5029 + vertex 1.30884 0.930193 2.50164 + endloop + endfacet + facet normal 0.162582 -0.296814 0.940993 + outer loop + vertex 1.31357 0.934108 2.50205 + vertex 1.31329 0.93869 2.50354 + vertex 1.30846 0.934003 2.5029 + endloop + endfacet + facet normal 0.159143 -0.293497 0.94262 + outer loop + vertex 1.30846 0.934003 2.5029 + vertex 1.31329 0.93869 2.50354 + vertex 1.30828 0.938371 2.50429 + endloop + endfacet + facet normal 0.161449 -0.293294 0.942291 + outer loop + vertex 1.30846 0.934003 2.5029 + vertex 1.30828 0.938371 2.50429 + vertex 1.30338 0.933745 2.50369 + endloop + endfacet + facet normal 0.161446 -0.292132 0.942653 + outer loop + vertex 1.30373 0.92904 2.50217 + vertex 1.30846 0.934003 2.5029 + vertex 1.30338 0.933745 2.50369 + endloop + endfacet + facet normal 0.163352 -0.291904 0.942395 + outer loop + vertex 1.30373 0.92904 2.50217 + vertex 1.30338 0.933745 2.50369 + vertex 1.29848 0.928992 2.50307 + endloop + endfacet + facet normal 0.163313 -0.292805 0.942122 + outer loop + vertex 1.30373 0.92904 2.50217 + vertex 1.29848 0.928992 2.50307 + vertex 1.29898 0.925081 2.50177 + endloop + endfacet + facet normal 0.160029 -0.297088 0.941344 + outer loop + vertex 1.31357 0.934108 2.50205 + vertex 1.31835 0.939047 2.5028 + vertex 1.31329 0.93869 2.50354 + endloop + endfacet + facet normal 0.160047 -0.297827 0.941108 + outer loop + vertex 1.31835 0.939047 2.5028 + vertex 1.31816 0.943389 2.5042 + vertex 1.31329 0.93869 2.50354 + endloop + endfacet + facet normal 0.157726 -0.295575 0.942209 + outer loop + vertex 1.31329 0.93869 2.50354 + vertex 1.31816 0.943389 2.5042 + vertex 1.31312 0.943311 2.50502 + endloop + endfacet + facet normal 0.157809 -0.298029 0.941422 + outer loop + vertex 1.31835 0.939047 2.5028 + vertex 1.32322 0.943731 2.50346 + vertex 1.31816 0.943389 2.5042 + endloop + endfacet + facet normal 0.157745 -0.295012 0.942382 + outer loop + vertex 1.32322 0.943731 2.50346 + vertex 1.32304 0.948365 2.50494 + vertex 1.31816 0.943389 2.5042 + endloop + endfacet + facet normal 0.155648 -0.295188 0.942676 + outer loop + vertex 1.32322 0.943731 2.50346 + vertex 1.32811 0.948433 2.50413 + vertex 1.32304 0.948365 2.50494 + endloop + endfacet + facet normal 0.154446 -0.294018 0.943239 + outer loop + vertex 1.32833 0.944072 2.50273 + vertex 1.32811 0.948433 2.50413 + vertex 1.32322 0.943731 2.50346 + endloop + endfacet + facet normal 0.154553 -0.299109 0.941619 + outer loop + vertex 1.3235 0.939166 2.50197 + vertex 1.32833 0.944072 2.50273 + vertex 1.32322 0.943731 2.50346 + endloop + endfacet + facet normal 0.152942 -0.297636 0.942349 + outer loop + vertex 1.32866 0.940303 2.50149 + vertex 1.32833 0.944072 2.50273 + vertex 1.3235 0.939166 2.50197 + endloop + endfacet + facet normal 0.153724 -0.301804 0.940895 + outer loop + vertex 1.32866 0.940303 2.50149 + vertex 1.3235 0.939166 2.50197 + vertex 1.32561 0.93648 2.50076 + endloop + endfacet + facet normal 0.151768 -0.300388 0.941665 + outer loop + vertex 1.32931 0.93769 2.50055 + vertex 1.32866 0.940303 2.50149 + vertex 1.32561 0.93648 2.50076 + endloop + endfacet + facet normal 0.152273 -0.302035 0.941057 + outer loop + vertex 1.32931 0.93769 2.50055 + vertex 1.32561 0.93648 2.50076 + vertex 1.32779 0.933724 2.49952 + endloop + endfacet + facet normal 0.150621 -0.301517 0.941489 + outer loop + vertex 1.32931 0.93769 2.50055 + vertex 1.32779 0.933724 2.49952 + vertex 1.33259 0.937602 2.5 + endloop + endfacet + facet normal 0.150613 -0.301612 0.94146 + outer loop + vertex 1.33259 0.937602 2.5 + vertex 1.33193 0.940247 2.50095 + vertex 1.32931 0.93769 2.50055 + endloop + endfacet + facet normal 0.14903 -0.302049 0.941571 + outer loop + vertex 1.33193 0.940247 2.50095 + vertex 1.33259 0.937602 2.5 + vertex 1.33563 0.941439 2.50075 + endloop + endfacet + facet normal 0.147633 -0.297415 0.943265 + outer loop + vertex 1.33563 0.941439 2.50075 + vertex 1.33351 0.94415 2.50193 + vertex 1.33193 0.940247 2.50095 + endloop + endfacet + facet normal 0.150051 -0.298233 0.942625 + outer loop + vertex 1.33193 0.940247 2.50095 + vertex 1.33351 0.94415 2.50193 + vertex 1.32866 0.940303 2.50149 + endloop + endfacet + facet normal 0.147169 -0.297763 0.943228 + outer loop + vertex 1.33869 0.945265 2.50148 + vertex 1.33351 0.94415 2.50193 + vertex 1.33563 0.941439 2.50075 + endloop + endfacet + facet normal 0.146927 -0.297587 0.943321 + outer loop + vertex 1.33933 0.942642 2.50055 + vertex 1.33869 0.945265 2.50148 + vertex 1.33563 0.941439 2.50075 + endloop + endfacet + facet normal 0.149025 -0.304452 0.940798 + outer loop + vertex 1.33933 0.942642 2.50055 + vertex 1.33563 0.941439 2.50075 + vertex 1.33781 0.938691 2.49951 + endloop + endfacet + facet normal 0.15081 -0.305018 0.94033 + outer loop + vertex 1.33933 0.942642 2.50055 + vertex 1.33781 0.938691 2.49951 + vertex 1.3426 0.942571 2.5 + endloop + endfacet + facet normal 0.151086 -0.301275 0.941492 + outer loop + vertex 1.3426 0.942571 2.5 + vertex 1.34195 0.945213 2.50095 + vertex 1.33933 0.942642 2.50055 + endloop + endfacet + facet normal 0.151753 -0.301092 0.941443 + outer loop + vertex 1.34195 0.945213 2.50095 + vertex 1.3426 0.942571 2.5 + vertex 1.34564 0.946438 2.50075 + endloop + endfacet + facet normal 0.149491 -0.293827 0.944096 + outer loop + vertex 1.34564 0.946438 2.50075 + vertex 1.34353 0.949147 2.50193 + vertex 1.34195 0.945213 2.50095 + endloop + endfacet + facet normal 0.147412 -0.293126 0.944641 + outer loop + vertex 1.34195 0.945213 2.50095 + vertex 1.34353 0.949147 2.50193 + vertex 1.33869 0.945265 2.50148 + endloop + endfacet + facet normal 0.146237 -0.291732 0.945255 + outer loop + vertex 1.34353 0.949147 2.50193 + vertex 1.33834 0.949062 2.5027 + vertex 1.33869 0.945265 2.50148 + endloop + endfacet + facet normal 0.146327 -0.288627 0.946194 + outer loop + vertex 1.34353 0.949147 2.50193 + vertex 1.34322 0.95375 2.50338 + vertex 1.33834 0.949062 2.5027 + endloop + endfacet + facet normal 0.145463 -0.287785 0.946584 + outer loop + vertex 1.33834 0.949062 2.5027 + vertex 1.34322 0.95375 2.50338 + vertex 1.33809 0.953441 2.50407 + endloop + endfacet + facet normal 0.14732 -0.287606 0.946351 + outer loop + vertex 1.33834 0.949062 2.5027 + vertex 1.33809 0.953441 2.50407 + vertex 1.3332 0.948747 2.50341 + endloop + endfacet + facet normal 0.147421 -0.293004 0.944677 + outer loop + vertex 1.33351 0.94415 2.50193 + vertex 1.33834 0.949062 2.5027 + vertex 1.3332 0.948747 2.50341 + endloop + endfacet + facet normal 0.150055 -0.292725 0.944349 + outer loop + vertex 1.33351 0.94415 2.50193 + vertex 1.3332 0.948747 2.50341 + vertex 1.32833 0.944072 2.50273 + endloop + endfacet + facet normal 0.147115 -0.287407 0.946443 + outer loop + vertex 1.3332 0.948747 2.50341 + vertex 1.33809 0.953441 2.50407 + vertex 1.33298 0.95341 2.50486 + endloop + endfacet + facet normal 0.151516 -0.287015 0.945867 + outer loop + vertex 1.3332 0.948747 2.50341 + vertex 1.33298 0.95341 2.50486 + vertex 1.32811 0.948433 2.50413 + endloop + endfacet + facet normal 0.153468 -0.288799 0.945009 + outer loop + vertex 1.32811 0.948433 2.50413 + vertex 1.33298 0.95341 2.50486 + vertex 1.32787 0.952292 2.50535 + endloop + endfacet + facet normal 0.145022 -0.288765 0.946352 + outer loop + vertex 1.34353 0.949147 2.50193 + vertex 1.34836 0.954087 2.50269 + vertex 1.34322 0.95375 2.50338 + endloop + endfacet + facet normal 0.14706 -0.290622 0.945469 + outer loop + vertex 1.3487 0.950302 2.50148 + vertex 1.34836 0.954087 2.50269 + vertex 1.34353 0.949147 2.50193 + endloop + endfacet + facet normal 0.144337 -0.290969 0.945782 + outer loop + vertex 1.35353 0.954181 2.50193 + vertex 1.34836 0.954087 2.50269 + vertex 1.3487 0.950302 2.50148 + endloop + endfacet + facet normal 0.14791 -0.295009 0.943977 + outer loop + vertex 1.3487 0.950302 2.50148 + vertex 1.34353 0.949147 2.50193 + vertex 1.34564 0.946438 2.50075 + endloop + endfacet + facet normal 0.149507 -0.296158 0.943365 + outer loop + vertex 1.34933 0.947674 2.50055 + vertex 1.3487 0.950302 2.50148 + vertex 1.34564 0.946438 2.50075 + endloop + endfacet + facet normal 0.151032 -0.30099 0.941591 + outer loop + vertex 1.34933 0.947674 2.50055 + vertex 1.34564 0.946438 2.50075 + vertex 1.3478 0.943684 2.49952 + endloop + endfacet + facet normal 0.148412 -0.300164 0.942271 + outer loop + vertex 1.34933 0.947674 2.50055 + vertex 1.3478 0.943684 2.49952 + vertex 1.35259 0.947593 2.50001 + endloop + endfacet + facet normal 0.148632 -0.297253 0.943159 + outer loop + vertex 1.35259 0.947593 2.50001 + vertex 1.35195 0.950264 2.50096 + vertex 1.34933 0.947674 2.50055 + endloop + endfacet + facet normal 0.148299 -0.300033 0.942331 + outer loop + vertex 1.35259 0.947593 2.50001 + vertex 1.3478 0.943684 2.49952 + vertex 1.35307 0.943677 2.49869 + endloop + endfacet + facet normal 0.143785 -0.300749 0.942802 + outer loop + vertex 1.35307 0.943677 2.49869 + vertex 1.35781 0.948661 2.49956 + vertex 1.35259 0.947593 2.50001 + endloop + endfacet + facet normal 0.14297 -0.296087 0.9444 + outer loop + vertex 1.35259 0.947593 2.50001 + vertex 1.35781 0.948661 2.49956 + vertex 1.35564 0.951468 2.50077 + endloop + endfacet + facet normal 0.145698 -0.298035 0.94337 + outer loop + vertex 1.35195 0.950264 2.50096 + vertex 1.35259 0.947593 2.50001 + vertex 1.35564 0.951468 2.50077 + endloop + endfacet + facet normal 0.144491 -0.294106 0.944788 + outer loop + vertex 1.35564 0.951468 2.50077 + vertex 1.35353 0.954181 2.50193 + vertex 1.35195 0.950264 2.50096 + endloop + endfacet + facet normal 0.140762 -0.296871 0.944486 + outer loop + vertex 1.35871 0.955292 2.50151 + vertex 1.35353 0.954181 2.50193 + vertex 1.35564 0.951468 2.50077 + endloop + endfacet + facet normal 0.141834 -0.299042 0.94364 + outer loop + vertex 1.35835 0.944003 2.498 + vertex 1.35781 0.948661 2.49956 + vertex 1.35307 0.943677 2.49869 + endloop + endfacet + facet normal 0.141906 -0.302722 0.942455 + outer loop + vertex 1.35361 0.939048 2.49712 + vertex 1.35835 0.944003 2.498 + vertex 1.35307 0.943677 2.49869 + endloop + endfacet + facet normal 0.14553 -0.302173 0.942079 + outer loop + vertex 1.35361 0.939048 2.49712 + vertex 1.35307 0.943677 2.49869 + vertex 1.34832 0.939063 2.49794 + endloop + endfacet + facet normal 0.145306 -0.306495 0.940716 + outer loop + vertex 1.35361 0.939048 2.49712 + vertex 1.34832 0.939063 2.49794 + vertex 1.3488 0.935197 2.49661 + endloop + endfacet + facet normal 0.144627 -0.305694 0.941082 + outer loop + vertex 1.35208 0.935097 2.49607 + vertex 1.35361 0.939048 2.49712 + vertex 1.3488 0.935197 2.49661 + endloop + endfacet + facet normal 0.144534 -0.306832 0.940725 + outer loop + vertex 1.35208 0.935097 2.49607 + vertex 1.3488 0.935197 2.49661 + vertex 1.34944 0.932543 2.49565 + endloop + endfacet + facet normal 0.143658 -0.305997 0.941131 + outer loop + vertex 1.35271 0.932443 2.49511 + vertex 1.35208 0.935097 2.49607 + vertex 1.34944 0.932543 2.49565 + endloop + endfacet + facet normal 0.14366 -0.305981 0.941136 + outer loop + vertex 1.34944 0.932543 2.49565 + vertex 1.34787 0.928598 2.4946 + vertex 1.35271 0.932443 2.49511 + endloop + endfacet + facet normal 0.145914 -0.308658 0.939914 + outer loop + vertex 1.35271 0.932443 2.49511 + vertex 1.34787 0.928598 2.4946 + vertex 1.35315 0.9286 2.49379 + endloop + endfacet + facet normal 0.142095 -0.309225 0.940313 + outer loop + vertex 1.35315 0.9286 2.49379 + vertex 1.35796 0.933522 2.49468 + vertex 1.35271 0.932443 2.49511 + endloop + endfacet + facet normal 0.141585 -0.306336 0.941335 + outer loop + vertex 1.35271 0.932443 2.49511 + vertex 1.35796 0.933522 2.49468 + vertex 1.3558 0.936273 2.4959 + endloop + endfacet + facet normal 0.139541 -0.307856 0.941145 + outer loop + vertex 1.35954 0.937454 2.49573 + vertex 1.3558 0.936273 2.4959 + vertex 1.35796 0.933522 2.49468 + endloop + endfacet + facet normal 0.138469 -0.307498 0.94142 + outer loop + vertex 1.35954 0.937454 2.49573 + vertex 1.35796 0.933522 2.49468 + vertex 1.36283 0.937363 2.49522 + endloop + endfacet + facet normal 0.138658 -0.305029 0.942195 + outer loop + vertex 1.36283 0.937363 2.49522 + vertex 1.36218 0.940016 2.49617 + vertex 1.35954 0.937454 2.49573 + endloop + endfacet + facet normal 0.137249 -0.303683 0.942836 + outer loop + vertex 1.36218 0.940016 2.49617 + vertex 1.35887 0.940113 2.49668 + vertex 1.35954 0.937454 2.49573 + endloop + endfacet + facet normal 0.137369 -0.302128 0.943318 + outer loop + vertex 1.36218 0.940016 2.49617 + vertex 1.36369 0.943969 2.49722 + vertex 1.35887 0.940113 2.49668 + endloop + endfacet + facet normal 0.136748 -0.301394 0.943643 + outer loop + vertex 1.36369 0.943969 2.49722 + vertex 1.35835 0.944003 2.498 + vertex 1.35887 0.940113 2.49668 + endloop + endfacet + facet normal 0.136801 -0.30037 0.943961 + outer loop + vertex 1.36369 0.943969 2.49722 + vertex 1.36313 0.948597 2.49877 + vertex 1.35835 0.944003 2.498 + endloop + endfacet + facet normal 0.132734 -0.300997 0.944342 + outer loop + vertex 1.36369 0.943969 2.49722 + vertex 1.36844 0.948894 2.49812 + vertex 1.36313 0.948597 2.49877 + endloop + endfacet + facet normal 0.13495 -0.30296 0.9434 + outer loop + vertex 1.36896 0.945015 2.4968 + vertex 1.36844 0.948894 2.49812 + vertex 1.36369 0.943969 2.49722 + endloop + endfacet + facet normal 0.13494 -0.302901 0.94342 + outer loop + vertex 1.36896 0.945015 2.4968 + vertex 1.36369 0.943969 2.49722 + vertex 1.36591 0.941194 2.49601 + endloop + endfacet + facet normal 0.135811 -0.303529 0.943094 + outer loop + vertex 1.36961 0.94233 2.49584 + vertex 1.36896 0.945015 2.4968 + vertex 1.36591 0.941194 2.49601 + endloop + endfacet + facet normal 0.136673 -0.306488 0.942012 + outer loop + vertex 1.36961 0.94233 2.49584 + vertex 1.36591 0.941194 2.49601 + vertex 1.36802 0.938403 2.49479 + endloop + endfacet + facet normal 0.13477 -0.305849 0.942493 + outer loop + vertex 1.36961 0.94233 2.49584 + vertex 1.36802 0.938403 2.49479 + vertex 1.37272 0.942077 2.49531 + endloop + endfacet + facet normal 0.134937 -0.304593 0.942876 + outer loop + vertex 1.37272 0.942077 2.49531 + vertex 1.37223 0.944837 2.49628 + vertex 1.36961 0.94233 2.49584 + endloop + endfacet + facet normal 0.13181 -0.305235 0.943111 + outer loop + vertex 1.37223 0.944837 2.49628 + vertex 1.37272 0.942077 2.49531 + vertex 1.37597 0.945844 2.49608 + endloop + endfacet + facet normal 0.131995 -0.305976 0.942845 + outer loop + vertex 1.37597 0.945844 2.49608 + vertex 1.37378 0.948829 2.49735 + vertex 1.37223 0.944837 2.49628 + endloop + endfacet + facet normal 0.13398 -0.306617 0.942356 + outer loop + vertex 1.37223 0.944837 2.49628 + vertex 1.37378 0.948829 2.49735 + vertex 1.36896 0.945015 2.4968 + endloop + endfacet + facet normal 0.128442 -0.308443 0.942532 + outer loop + vertex 1.37931 0.949955 2.49697 + vertex 1.37378 0.948829 2.49735 + vertex 1.37597 0.945844 2.49608 + endloop + endfacet + facet normal 0.128146 -0.308226 0.942643 + outer loop + vertex 1.38053 0.946699 2.49574 + vertex 1.37931 0.949955 2.49697 + vertex 1.37597 0.945844 2.49608 + endloop + endfacet + facet normal 0.127911 -0.306764 0.943151 + outer loop + vertex 1.37597 0.945844 2.49608 + vertex 1.37723 0.94258 2.49485 + vertex 1.38053 0.946699 2.49574 + endloop + endfacet + facet normal 0.125452 -0.304986 0.944058 + outer loop + vertex 1.37723 0.94258 2.49485 + vertex 1.38273 0.943674 2.49447 + vertex 1.38053 0.946699 2.49574 + endloop + endfacet + facet normal 0.122581 -0.306958 0.943796 + outer loop + vertex 1.38427 0.947646 2.49556 + vertex 1.38053 0.946699 2.49574 + vertex 1.38273 0.943674 2.49447 + endloop + endfacet + facet normal 0.115243 -0.30457 0.945492 + outer loop + vertex 1.38427 0.947646 2.49556 + vertex 1.38273 0.943674 2.49447 + vertex 1.38745 0.947272 2.49505 + endloop + endfacet + facet normal 0.114443 -0.309375 0.944028 + outer loop + vertex 1.38745 0.947272 2.49505 + vertex 1.38695 0.950083 2.49603 + vertex 1.38427 0.947646 2.49556 + endloop + endfacet + facet normal 0.117027 -0.311988 0.942851 + outer loop + vertex 1.38695 0.950083 2.49603 + vertex 1.38382 0.950425 2.49654 + vertex 1.38427 0.947646 2.49556 + endloop + endfacet + facet normal 0.116175 -0.317326 0.941173 + outer loop + vertex 1.38695 0.950083 2.49603 + vertex 1.38864 0.954017 2.49715 + vertex 1.38382 0.950425 2.49654 + endloop + endfacet + facet normal 0.113143 -0.313543 0.942809 + outer loop + vertex 1.38864 0.954017 2.49715 + vertex 1.38352 0.954145 2.49781 + vertex 1.38382 0.950425 2.49654 + endloop + endfacet + facet normal 0.122972 -0.312436 0.941946 + outer loop + vertex 1.38382 0.950425 2.49654 + vertex 1.38352 0.954145 2.49781 + vertex 1.37931 0.949955 2.49697 + endloop + endfacet + facet normal 0.12115 -0.310765 0.942734 + outer loop + vertex 1.37931 0.949955 2.49697 + vertex 1.38352 0.954145 2.49781 + vertex 1.37845 0.95381 2.49835 + endloop + endfacet + facet normal 0.121129 -0.31008 0.942962 + outer loop + vertex 1.38352 0.954145 2.49781 + vertex 1.38303 0.958191 2.4992 + vertex 1.37845 0.95381 2.49835 + endloop + endfacet + facet normal 0.119926 -0.308925 0.943495 + outer loop + vertex 1.37845 0.95381 2.49835 + vertex 1.38303 0.958191 2.4992 + vertex 1.378 0.958311 2.49988 + endloop + endfacet + facet normal 0.126516 -0.30807 0.942914 + outer loop + vertex 1.37845 0.95381 2.49835 + vertex 1.378 0.958311 2.49988 + vertex 1.37322 0.953451 2.49893 + endloop + endfacet + facet normal 0.126489 -0.30723 0.943192 + outer loop + vertex 1.37378 0.948829 2.49735 + vertex 1.37845 0.95381 2.49835 + vertex 1.37322 0.953451 2.49893 + endloop + endfacet + facet normal 0.131222 -0.306515 0.942777 + outer loop + vertex 1.37378 0.948829 2.49735 + vertex 1.37322 0.953451 2.49893 + vertex 1.36844 0.948894 2.49812 + endloop + endfacet + facet normal 0.128439 -0.303818 0.944033 + outer loop + vertex 1.36844 0.948894 2.49812 + vertex 1.37322 0.953451 2.49893 + vertex 1.36792 0.953523 2.49968 + endloop + endfacet + facet normal 0.12496 -0.30667 0.943578 + outer loop + vertex 1.37322 0.953451 2.49893 + vertex 1.378 0.958311 2.49988 + vertex 1.3728 0.957328 2.50025 + endloop + endfacet + facet normal 0.124028 -0.301016 0.945519 + outer loop + vertex 1.3728 0.957328 2.50025 + vertex 1.378 0.958311 2.49988 + vertex 1.37592 0.961133 2.50105 + endloop + endfacet + facet normal 0.120855 -0.303235 0.945221 + outer loop + vertex 1.37965 0.962224 2.50093 + vertex 1.37592 0.961133 2.50105 + vertex 1.378 0.958311 2.49988 + endloop + endfacet + facet normal 0.117356 -0.301983 0.946062 + outer loop + vertex 1.37965 0.962224 2.50093 + vertex 1.378 0.958311 2.49988 + vertex 1.38278 0.961936 2.50044 + endloop + endfacet + facet normal 0.117803 -0.298751 0.947032 + outer loop + vertex 1.38278 0.961936 2.50044 + vertex 1.38232 0.964699 2.50137 + vertex 1.37965 0.962224 2.50093 + endloop + endfacet + facet normal 0.115328 -0.296284 0.948112 + outer loop + vertex 1.38232 0.964699 2.50137 + vertex 1.37899 0.964912 2.50185 + vertex 1.37965 0.962224 2.50093 + endloop + endfacet + facet normal 0.115021 -0.29916 0.947245 + outer loop + vertex 1.38232 0.964699 2.50137 + vertex 1.38383 0.96864 2.50244 + vertex 1.37899 0.964912 2.50185 + endloop + endfacet + facet normal 0.112995 -0.296692 0.948265 + outer loop + vertex 1.38383 0.96864 2.50244 + vertex 1.37843 0.968756 2.50312 + vertex 1.37899 0.964912 2.50185 + endloop + endfacet + facet normal 0.112077 -0.299834 0.947385 + outer loop + vertex 1.38232 0.964699 2.50137 + vertex 1.38278 0.961936 2.50044 + vertex 1.38611 0.965655 2.50123 + endloop + endfacet + facet normal 0.118664 -0.295415 0.947971 + outer loop + vertex 1.37965 0.962224 2.50093 + vertex 1.37899 0.964912 2.50185 + vertex 1.37592 0.961133 2.50105 + endloop + endfacet + facet normal 0.116603 -0.293891 0.9487 + outer loop + vertex 1.37899 0.964912 2.50185 + vertex 1.37366 0.963921 2.50219 + vertex 1.37592 0.961133 2.50105 + endloop + endfacet + facet normal 0.120157 -0.305449 0.944597 + outer loop + vertex 1.38278 0.961936 2.50044 + vertex 1.378 0.958311 2.49988 + vertex 1.38303 0.958191 2.4992 + endloop + endfacet + facet normal 0.111598 -0.306278 0.945378 + outer loop + vertex 1.38303 0.958191 2.4992 + vertex 1.38732 0.962377 2.50005 + vertex 1.38278 0.961936 2.50044 + endloop + endfacet + facet normal 0.111803 -0.30647 0.945292 + outer loop + vertex 1.38812 0.958511 2.4987 + vertex 1.38732 0.962377 2.50005 + vertex 1.38303 0.958191 2.4992 + endloop + endfacet + facet normal 0.111953 -0.311419 0.943655 + outer loop + vertex 1.38352 0.954145 2.49781 + vertex 1.38812 0.958511 2.4987 + vertex 1.38303 0.958191 2.4992 + endloop + endfacet + facet normal 0.113204 -0.312627 0.943106 + outer loop + vertex 1.38864 0.954017 2.49715 + vertex 1.38812 0.958511 2.4987 + vertex 1.38352 0.954145 2.49781 + endloop + endfacet + facet normal 0.104161 -0.313877 0.943733 + outer loop + vertex 1.38864 0.954017 2.49715 + vertex 1.39338 0.95889 2.49825 + vertex 1.38812 0.958511 2.4987 + endloop + endfacet + facet normal 0.103974 -0.309555 0.94518 + outer loop + vertex 1.39338 0.95889 2.49825 + vertex 1.3929 0.963391 2.49978 + vertex 1.38812 0.958511 2.4987 + endloop + endfacet + facet normal 0.0963895 -0.310525 0.945666 + outer loop + vertex 1.39338 0.95889 2.49825 + vertex 1.39796 0.963143 2.49918 + vertex 1.3929 0.963391 2.49978 + endloop + endfacet + facet normal 0.0992453 -0.313337 0.944442 + outer loop + vertex 1.39847 0.959147 2.4978 + vertex 1.39796 0.963143 2.49918 + vertex 1.39338 0.95889 2.49825 + endloop + endfacet + facet normal 0.0993081 -0.316339 0.943434 + outer loop + vertex 1.39421 0.955055 2.49688 + vertex 1.39847 0.959147 2.4978 + vertex 1.39338 0.95889 2.49825 + endloop + endfacet + facet normal 0.100933 -0.317874 0.942745 + outer loop + vertex 1.39878 0.955453 2.49652 + vertex 1.39847 0.959147 2.4978 + vertex 1.39421 0.955055 2.49688 + endloop + endfacet + facet normal 0.100929 -0.317817 0.942765 + outer loop + vertex 1.39878 0.955453 2.49652 + vertex 1.39421 0.955055 2.49688 + vertex 1.39546 0.951763 2.49563 + endloop + endfacet + facet normal 0.101825 -0.318541 0.942424 + outer loop + vertex 1.39927 0.952651 2.49552 + vertex 1.39878 0.955453 2.49652 + vertex 1.39546 0.951763 2.49563 + endloop + endfacet + facet normal 0.101164 -0.315576 0.943492 + outer loop + vertex 1.39927 0.952651 2.49552 + vertex 1.39546 0.951763 2.49563 + vertex 1.3978 0.948625 2.49433 + endloop + endfacet + facet normal 0.0997891 -0.31516 0.943778 + outer loop + vertex 1.39927 0.952651 2.49552 + vertex 1.3978 0.948625 2.49433 + vertex 1.40253 0.952241 2.49504 + endloop + endfacet + facet normal 0.0990903 -0.319204 0.942491 + outer loop + vertex 1.40253 0.952241 2.49504 + vertex 1.40196 0.955059 2.49605 + vertex 1.39927 0.952651 2.49552 + endloop + endfacet + facet normal 0.0976691 -0.319508 0.942537 + outer loop + vertex 1.40196 0.955059 2.49605 + vertex 1.40253 0.952241 2.49504 + vertex 1.40581 0.955923 2.49595 + endloop + endfacet + facet normal 0.0976205 -0.319281 0.942619 + outer loop + vertex 1.40581 0.955923 2.49595 + vertex 1.4036 0.958958 2.4972 + vertex 1.40196 0.955059 2.49605 + endloop + endfacet + facet normal 0.0988569 -0.31972 0.942341 + outer loop + vertex 1.40196 0.955059 2.49605 + vertex 1.4036 0.958958 2.4972 + vertex 1.39878 0.955453 2.49652 + endloop + endfacet + facet normal 0.0972761 -0.319514 0.942575 + outer loop + vertex 1.40922 0.959974 2.49697 + vertex 1.4036 0.958958 2.4972 + vertex 1.40581 0.955923 2.49595 + endloop + endfacet + facet normal 0.0973412 -0.319563 0.942552 + outer loop + vertex 1.41055 0.956655 2.49571 + vertex 1.40922 0.959974 2.49697 + vertex 1.40581 0.955923 2.49595 + endloop + endfacet + facet normal 0.097536 -0.320989 0.942047 + outer loop + vertex 1.40581 0.955923 2.49595 + vertex 1.40724 0.952622 2.49468 + vertex 1.41055 0.956655 2.49571 + endloop + endfacet + facet normal 0.0988288 -0.321934 0.94159 + outer loop + vertex 1.40724 0.952622 2.49468 + vertex 1.41289 0.953547 2.4944 + vertex 1.41055 0.956655 2.49571 + endloop + endfacet + facet normal 0.0987086 -0.321111 0.941884 + outer loop + vertex 1.4085 0.948858 2.49326 + vertex 1.41289 0.953547 2.4944 + vertex 1.40724 0.952622 2.49468 + endloop + endfacet + facet normal 0.100991 -0.320351 0.9419 + outer loop + vertex 1.4085 0.948858 2.49326 + vertex 1.40724 0.952622 2.49468 + vertex 1.40324 0.948469 2.49369 + endloop + endfacet + facet normal 0.100859 -0.317466 0.942891 + outer loop + vertex 1.4045 0.944705 2.49229 + vertex 1.4085 0.948858 2.49326 + vertex 1.40324 0.948469 2.49369 + endloop + endfacet + facet normal 0.104663 -0.316192 0.942904 + outer loop + vertex 1.4045 0.944705 2.49229 + vertex 1.40324 0.948469 2.49369 + vertex 1.3988 0.94369 2.49258 + endloop + endfacet + facet normal 0.104372 -0.31437 0.943545 + outer loop + vertex 1.4045 0.944705 2.49229 + vertex 1.3988 0.94369 2.49258 + vertex 1.40117 0.940631 2.4913 + endloop + endfacet + facet normal 0.105067 -0.314878 0.943299 + outer loop + vertex 1.40587 0.941424 2.49104 + vertex 1.4045 0.944705 2.49229 + vertex 1.40117 0.940631 2.4913 + endloop + endfacet + facet normal 0.104966 -0.314204 0.943535 + outer loop + vertex 1.40117 0.940631 2.4913 + vertex 1.40242 0.937344 2.49007 + vertex 1.40587 0.941424 2.49104 + endloop + endfacet + facet normal 0.104067 -0.313522 0.943861 + outer loop + vertex 1.40242 0.937344 2.49007 + vertex 1.40802 0.938372 2.48979 + vertex 1.40587 0.941424 2.49104 + endloop + endfacet + facet normal 0.104641 -0.316973 0.942644 + outer loop + vertex 1.40342 0.933548 2.48868 + vertex 1.40802 0.938372 2.48979 + vertex 1.40242 0.937344 2.49007 + endloop + endfacet + facet normal 0.10617 -0.316561 0.942612 + outer loop + vertex 1.40342 0.933548 2.48868 + vertex 1.40242 0.937344 2.49007 + vertex 1.39817 0.933133 2.48913 + endloop + endfacet + facet normal 0.106486 -0.322971 0.940399 + outer loop + vertex 1.39883 0.928713 2.48754 + vertex 1.40342 0.933548 2.48868 + vertex 1.39817 0.933133 2.48913 + endloop + endfacet + facet normal 0.109856 -0.322395 0.940209 + outer loop + vertex 1.39883 0.928713 2.48754 + vertex 1.39817 0.933133 2.48913 + vertex 1.39362 0.928955 2.48823 + endloop + endfacet + facet normal 0.109381 -0.32761 0.93846 + outer loop + vertex 1.39883 0.928713 2.48754 + vertex 1.39362 0.928955 2.48823 + vertex 1.39405 0.925175 2.48686 + endloop + endfacet + facet normal 0.109748 -0.322289 0.940258 + outer loop + vertex 1.39362 0.928955 2.48823 + vertex 1.39817 0.933133 2.48913 + vertex 1.39303 0.933333 2.4898 + endloop + endfacet + facet normal 0.114873 -0.321471 0.939926 + outer loop + vertex 1.39362 0.928955 2.48823 + vertex 1.39303 0.933333 2.4898 + vertex 1.38841 0.928635 2.48876 + endloop + endfacet + facet normal 0.115007 -0.326623 0.938132 + outer loop + vertex 1.38945 0.924784 2.48729 + vertex 1.39362 0.928955 2.48823 + vertex 1.38841 0.928635 2.48876 + endloop + endfacet + facet normal 0.121336 -0.324833 0.937956 + outer loop + vertex 1.38945 0.924784 2.48729 + vertex 1.38841 0.928635 2.48876 + vertex 1.38382 0.923746 2.48766 + endloop + endfacet + facet normal 0.120239 -0.323908 0.938417 + outer loop + vertex 1.38382 0.923746 2.48766 + vertex 1.38841 0.928635 2.48876 + vertex 1.38292 0.928618 2.48946 + endloop + endfacet + facet normal 0.128895 -0.322107 0.937888 + outer loop + vertex 1.38382 0.923746 2.48766 + vertex 1.38292 0.928618 2.48946 + vertex 1.37834 0.923698 2.48839 + endloop + endfacet + facet normal 0.127228 -0.320708 0.938594 + outer loop + vertex 1.37834 0.923698 2.48839 + vertex 1.38292 0.928618 2.48946 + vertex 1.37729 0.927559 2.48986 + endloop + endfacet + facet normal 0.133753 -0.318825 0.938329 + outer loop + vertex 1.37834 0.923698 2.48839 + vertex 1.37729 0.927559 2.48986 + vertex 1.37312 0.923297 2.489 + endloop + endfacet + facet normal 0.133826 -0.320839 0.937632 + outer loop + vertex 1.37376 0.918893 2.4874 + vertex 1.37834 0.923698 2.48839 + vertex 1.37312 0.923297 2.489 + endloop + endfacet + facet normal 0.139105 -0.319909 0.937181 + outer loop + vertex 1.37376 0.918893 2.4874 + vertex 1.37312 0.923297 2.489 + vertex 1.36846 0.918902 2.48819 + endloop + endfacet + facet normal 0.137142 -0.318 0.938119 + outer loop + vertex 1.36846 0.918902 2.48819 + vertex 1.37312 0.923297 2.489 + vertex 1.36801 0.923439 2.4898 + endloop + endfacet + facet normal 0.141146 -0.31746 0.937708 + outer loop + vertex 1.36846 0.918902 2.48819 + vertex 1.36801 0.923439 2.4898 + vertex 1.36321 0.918565 2.48887 + endloop + endfacet + facet normal 0.141164 -0.318347 0.937405 + outer loop + vertex 1.36366 0.91402 2.48726 + vertex 1.36846 0.918902 2.48819 + vertex 1.36321 0.918565 2.48887 + endloop + endfacet + facet normal 0.145455 -0.317764 0.936947 + outer loop + vertex 1.36366 0.91402 2.48726 + vertex 1.36321 0.918565 2.48887 + vertex 1.35838 0.914009 2.48808 + endloop + endfacet + facet normal 0.143516 -0.315869 0.937886 + outer loop + vertex 1.35838 0.914009 2.48808 + vertex 1.36321 0.918565 2.48887 + vertex 1.35794 0.918556 2.48967 + endloop + endfacet + facet normal 0.148847 -0.315152 0.937296 + outer loop + vertex 1.35838 0.914009 2.48808 + vertex 1.35794 0.918556 2.48967 + vertex 1.35314 0.91363 2.48878 + endloop + endfacet + facet normal 0.148911 -0.317598 0.93646 + outer loop + vertex 1.3536 0.9091 2.48717 + vertex 1.35838 0.914009 2.48808 + vertex 1.35314 0.91363 2.48878 + endloop + endfacet + facet normal 0.15481 -0.316758 0.935788 + outer loop + vertex 1.3536 0.9091 2.48717 + vertex 1.35314 0.91363 2.48878 + vertex 1.34834 0.909051 2.48802 + endloop + endfacet + facet normal 0.153286 -0.315287 0.936535 + outer loop + vertex 1.34834 0.909051 2.48802 + vertex 1.35314 0.91363 2.48878 + vertex 1.3479 0.913599 2.48963 + endloop + endfacet + facet normal 0.153335 -0.314236 0.93688 + outer loop + vertex 1.35273 0.917461 2.49013 + vertex 1.3479 0.913599 2.48963 + vertex 1.35314 0.91363 2.48878 + endloop + endfacet + facet normal 0.15213 -0.312818 0.937551 + outer loop + vertex 1.34947 0.917543 2.49069 + vertex 1.3479 0.913599 2.48963 + vertex 1.35273 0.917461 2.49013 + endloop + endfacet + facet normal 0.152109 -0.313089 0.937464 + outer loop + vertex 1.35273 0.917461 2.49013 + vertex 1.35209 0.920107 2.49112 + vertex 1.34947 0.917543 2.49069 + endloop + endfacet + facet normal 0.152774 -0.313717 0.937146 + outer loop + vertex 1.35209 0.920107 2.49112 + vertex 1.34882 0.920187 2.49168 + vertex 1.34947 0.917543 2.49069 + endloop + endfacet + facet normal 0.154515 -0.31324 0.937019 + outer loop + vertex 1.34947 0.917543 2.49069 + vertex 1.34882 0.920187 2.49168 + vertex 1.34577 0.916341 2.4909 + endloop + endfacet + facet normal 0.152472 -0.311788 0.937838 + outer loop + vertex 1.34882 0.920187 2.49168 + vertex 1.3436 0.919082 2.49216 + vertex 1.34577 0.916341 2.4909 + endloop + endfacet + facet normal 0.153957 -0.310671 0.937966 + outer loop + vertex 1.34577 0.916341 2.4909 + vertex 1.3436 0.919082 2.49216 + vertex 1.34207 0.915136 2.4911 + endloop + endfacet + facet normal 0.15443 -0.312223 0.937373 + outer loop + vertex 1.34207 0.915136 2.4911 + vertex 1.34271 0.912488 2.49012 + vertex 1.34577 0.916341 2.4909 + endloop + endfacet + facet normal 0.155505 -0.312989 0.93694 + outer loop + vertex 1.34271 0.912488 2.49012 + vertex 1.3479 0.913599 2.48963 + vertex 1.34577 0.916341 2.4909 + endloop + endfacet + facet normal 0.155427 -0.312555 0.937098 + outer loop + vertex 1.34313 0.908647 2.48877 + vertex 1.3479 0.913599 2.48963 + vertex 1.34271 0.912488 2.49012 + endloop + endfacet + facet normal 0.157631 -0.312224 0.93684 + outer loop + vertex 1.34271 0.912488 2.49012 + vertex 1.3379 0.908612 2.48963 + vertex 1.34313 0.908647 2.48877 + endloop + endfacet + facet normal 0.154912 -0.309038 0.938349 + outer loop + vertex 1.33945 0.912565 2.49068 + vertex 1.3379 0.908612 2.48963 + vertex 1.34271 0.912488 2.49012 + endloop + endfacet + facet normal 0.153463 -0.308572 0.93874 + outer loop + vertex 1.33945 0.912565 2.49068 + vertex 1.33576 0.911365 2.49089 + vertex 1.3379 0.908612 2.48963 + endloop + endfacet + facet normal 0.153975 -0.310261 0.938099 + outer loop + vertex 1.33945 0.912565 2.49068 + vertex 1.3388 0.915213 2.49166 + vertex 1.33576 0.911365 2.49089 + endloop + endfacet + facet normal 0.154156 -0.310389 0.938027 + outer loop + vertex 1.3388 0.915213 2.49166 + vertex 1.3336 0.914106 2.49215 + vertex 1.33576 0.911365 2.49089 + endloop + endfacet + facet normal 0.155655 -0.309266 0.93815 + outer loop + vertex 1.33576 0.911365 2.49089 + vertex 1.3336 0.914106 2.49215 + vertex 1.33208 0.910167 2.4911 + endloop + endfacet + facet normal 0.153821 -0.308521 0.938698 + outer loop + vertex 1.3388 0.915213 2.49166 + vertex 1.33833 0.919057 2.493 + vertex 1.3336 0.914106 2.49215 + endloop + endfacet + facet normal 0.154151 -0.30881 0.938549 + outer loop + vertex 1.3336 0.914106 2.49215 + vertex 1.33833 0.919057 2.493 + vertex 1.3331 0.918675 2.49374 + endloop + endfacet + facet normal 0.159972 -0.307941 0.93786 + outer loop + vertex 1.3336 0.914106 2.49215 + vertex 1.3331 0.918675 2.49374 + vertex 1.32838 0.914064 2.49303 + endloop + endfacet + facet normal 0.159927 -0.308922 0.937545 + outer loop + vertex 1.3336 0.914106 2.49215 + vertex 1.32838 0.914064 2.49303 + vertex 1.32885 0.910235 2.49169 + endloop + endfacet + facet normal 0.159008 -0.307024 0.938324 + outer loop + vertex 1.32838 0.914064 2.49303 + vertex 1.3331 0.918675 2.49374 + vertex 1.3279 0.918634 2.49461 + endloop + endfacet + facet normal 0.165342 -0.306077 0.937539 + outer loop + vertex 1.32838 0.914064 2.49303 + vertex 1.3279 0.918634 2.49461 + vertex 1.32321 0.913644 2.4938 + endloop + endfacet + facet normal 0.16532 -0.305352 0.937779 + outer loop + vertex 1.32373 0.909088 2.49223 + vertex 1.32838 0.914064 2.49303 + vertex 1.32321 0.913644 2.4938 + endloop + endfacet + facet normal 0.171251 -0.304411 0.93702 + outer loop + vertex 1.32373 0.909088 2.49223 + vertex 1.32321 0.913644 2.4938 + vertex 1.3185 0.908971 2.49315 + endloop + endfacet + facet normal 0.168343 -0.301679 0.93843 + outer loop + vertex 1.3185 0.908971 2.49315 + vertex 1.32321 0.913644 2.4938 + vertex 1.31802 0.913572 2.49471 + endloop + endfacet + facet normal 0.171159 -0.301261 0.938054 + outer loop + vertex 1.3185 0.908971 2.49315 + vertex 1.31802 0.913572 2.49471 + vertex 1.31327 0.908522 2.49395 + endloop + endfacet + facet normal 0.167824 -0.298353 0.939585 + outer loop + vertex 1.31327 0.908522 2.49395 + vertex 1.31802 0.913572 2.49471 + vertex 1.31291 0.912431 2.49526 + endloop + endfacet + facet normal 0.16973 -0.298089 0.939327 + outer loop + vertex 1.31291 0.912431 2.49526 + vertex 1.30809 0.908477 2.49488 + vertex 1.31327 0.908522 2.49395 + endloop + endfacet + facet normal 0.169821 -0.296117 0.939934 + outer loop + vertex 1.30833 0.903775 2.49335 + vertex 1.31327 0.908522 2.49395 + vertex 1.30809 0.908477 2.49488 + endloop + endfacet + facet normal 0.167517 -0.295508 0.940539 + outer loop + vertex 1.3097 0.912484 2.49585 + vertex 1.30809 0.908477 2.49488 + vertex 1.31291 0.912431 2.49526 + endloop + endfacet + facet normal 0.16729 -0.298656 0.939584 + outer loop + vertex 1.31291 0.912431 2.49526 + vertex 1.31229 0.915092 2.49622 + vertex 1.3097 0.912484 2.49585 + endloop + endfacet + facet normal 0.16811 -0.299416 0.939196 + outer loop + vertex 1.31229 0.915092 2.49622 + vertex 1.30902 0.915111 2.49681 + vertex 1.3097 0.912484 2.49585 + endloop + endfacet + facet normal 0.169588 -0.298987 0.939067 + outer loop + vertex 1.3097 0.912484 2.49585 + vertex 1.30902 0.915111 2.49681 + vertex 1.30598 0.911176 2.4961 + endloop + endfacet + facet normal 0.170426 -0.299574 0.938728 + outer loop + vertex 1.30902 0.915111 2.49681 + vertex 1.30368 0.913799 2.49736 + vertex 1.30598 0.911176 2.4961 + endloop + endfacet + facet normal 0.172108 -0.298167 0.938869 + outer loop + vertex 1.30598 0.911176 2.4961 + vertex 1.30368 0.913799 2.49736 + vertex 1.30218 0.909732 2.49634 + endloop + endfacet + facet normal 0.170864 -0.294673 0.940198 + outer loop + vertex 1.30218 0.909732 2.49634 + vertex 1.30298 0.907261 2.49542 + vertex 1.30598 0.911176 2.4961 + endloop + endfacet + facet normal 0.170486 -0.29441 0.94035 + outer loop + vertex 1.30298 0.907261 2.49542 + vertex 1.30809 0.908477 2.49488 + vertex 1.30598 0.911176 2.4961 + endloop + endfacet + facet normal 0.173547 -0.29373 0.940002 + outer loop + vertex 1.30298 0.907261 2.49542 + vertex 1.30218 0.909732 2.49634 + vertex 1.29979 0.907069 2.49595 + endloop + endfacet + facet normal 0.173532 -0.291932 0.940565 + outer loop + vertex 1.29979 0.907069 2.49595 + vertex 1.29842 0.903435 2.49508 + vertex 1.30298 0.907261 2.49542 + endloop + endfacet + facet normal 0.174762 -0.293337 0.9399 + outer loop + vertex 1.30298 0.907261 2.49542 + vertex 1.29842 0.903435 2.49508 + vertex 1.30325 0.903491 2.4942 + endloop + endfacet + facet normal 0.170375 -0.293857 0.940543 + outer loop + vertex 1.30325 0.903491 2.4942 + vertex 1.30809 0.908477 2.49488 + vertex 1.30298 0.907261 2.49542 + endloop + endfacet + facet normal 0.176416 -0.296113 0.93872 + outer loop + vertex 1.30218 0.909732 2.49634 + vertex 1.29831 0.90921 2.49691 + vertex 1.29979 0.907069 2.49595 + endloop + endfacet + facet normal 0.178814 -0.294478 0.93878 + outer loop + vertex 1.29979 0.907069 2.49595 + vertex 1.29831 0.90921 2.49691 + vertex 1.29698 0.905601 2.49603 + endloop + endfacet + facet normal 0.176711 -0.299544 0.937575 + outer loop + vertex 1.30218 0.909732 2.49634 + vertex 1.30368 0.913799 2.49736 + vertex 1.29831 0.90921 2.49691 + endloop + endfacet + facet normal 0.170503 -0.299943 0.938596 + outer loop + vertex 1.30902 0.915111 2.49681 + vertex 1.30852 0.918965 2.49813 + vertex 1.30368 0.913799 2.49736 + endloop + endfacet + facet normal 0.168938 -0.298585 0.939312 + outer loop + vertex 1.30368 0.913799 2.49736 + vertex 1.30852 0.918965 2.49813 + vertex 1.30328 0.918517 2.49893 + endloop + endfacet + facet normal 0.17278 -0.298077 0.938774 + outer loop + vertex 1.30368 0.913799 2.49736 + vertex 1.30328 0.918517 2.49893 + vertex 1.29834 0.913769 2.49833 + endloop + endfacet + facet normal 0.172919 -0.295306 0.939624 + outer loop + vertex 1.30368 0.913799 2.49736 + vertex 1.29834 0.913769 2.49833 + vertex 1.29831 0.90921 2.49691 + endloop + endfacet + facet normal 0.168971 -0.2995 0.939015 + outer loop + vertex 1.30852 0.918965 2.49813 + vertex 1.30802 0.923587 2.49969 + vertex 1.30328 0.918517 2.49893 + endloop + endfacet + facet normal 0.167762 -0.298452 0.939565 + outer loop + vertex 1.30328 0.918517 2.49893 + vertex 1.30802 0.923587 2.49969 + vertex 1.3029 0.922419 2.50024 + endloop + endfacet + facet normal 0.166974 -0.299802 0.939275 + outer loop + vertex 1.30852 0.918965 2.49813 + vertex 1.31322 0.92366 2.49879 + vertex 1.30802 0.923587 2.49969 + endloop + endfacet + facet normal 0.167254 -0.300064 0.939142 + outer loop + vertex 1.31376 0.919058 2.49723 + vertex 1.31322 0.92366 2.49879 + vertex 1.30852 0.918965 2.49813 + endloop + endfacet + facet normal 0.164508 -0.300507 0.939485 + outer loop + vertex 1.31376 0.919058 2.49723 + vertex 1.3184 0.924069 2.49802 + vertex 1.31322 0.92366 2.49879 + endloop + endfacet + facet normal 0.164467 -0.299147 0.939926 + outer loop + vertex 1.3184 0.924069 2.49802 + vertex 1.31785 0.928693 2.49958 + vertex 1.31322 0.92366 2.49879 + endloop + endfacet + facet normal 0.164594 -0.299255 0.93987 + outer loop + vertex 1.31322 0.92366 2.49879 + vertex 1.31785 0.928693 2.49958 + vertex 1.31272 0.927538 2.50012 + endloop + endfacet + facet normal 0.160425 -0.299795 0.940418 + outer loop + vertex 1.3184 0.924069 2.49802 + vertex 1.32309 0.928726 2.4987 + vertex 1.31785 0.928693 2.49958 + endloop + endfacet + facet normal 0.160437 -0.299515 0.940505 + outer loop + vertex 1.32259 0.93262 2.50003 + vertex 1.31785 0.928693 2.49958 + vertex 1.32309 0.928726 2.4987 + endloop + endfacet + facet normal 0.155037 -0.300423 0.941121 + outer loop + vertex 1.32309 0.928726 2.4987 + vertex 1.32779 0.933724 2.49952 + vertex 1.32259 0.93262 2.50003 + endloop + endfacet + facet normal 0.158265 -0.303224 0.939685 + outer loop + vertex 1.32832 0.92911 2.49794 + vertex 1.32779 0.933724 2.49952 + vertex 1.32309 0.928726 2.4987 + endloop + endfacet + facet normal 0.158252 -0.302744 0.939842 + outer loop + vertex 1.32362 0.924113 2.49713 + vertex 1.32832 0.92911 2.49794 + vertex 1.32309 0.928726 2.4987 + endloop + endfacet + facet normal 0.161381 -0.305455 0.938432 + outer loop + vertex 1.3288 0.925251 2.49661 + vertex 1.32832 0.92911 2.49794 + vertex 1.32362 0.924113 2.49713 + endloop + endfacet + facet normal 0.161477 -0.305977 0.938245 + outer loop + vertex 1.3288 0.925251 2.49661 + vertex 1.32362 0.924113 2.49713 + vertex 1.32577 0.921373 2.49586 + endloop + endfacet + facet normal 0.162085 -0.306405 0.938 + outer loop + vertex 1.32944 0.922603 2.49563 + vertex 1.3288 0.925251 2.49661 + vertex 1.32577 0.921373 2.49586 + endloop + endfacet + facet normal 0.161796 -0.305478 0.938353 + outer loop + vertex 1.32944 0.922603 2.49563 + vertex 1.32577 0.921373 2.49586 + vertex 1.3279 0.918634 2.49461 + endloop + endfacet + facet normal 0.157775 -0.304203 0.939451 + outer loop + vertex 1.32944 0.922603 2.49563 + vertex 1.3279 0.918634 2.49461 + vertex 1.33267 0.922534 2.49507 + endloop + endfacet + facet normal 0.157672 -0.305569 0.939025 + outer loop + vertex 1.33267 0.922534 2.49507 + vertex 1.33204 0.925191 2.49604 + vertex 1.32944 0.922603 2.49563 + endloop + endfacet + facet normal 0.155201 -0.306225 0.939222 + outer loop + vertex 1.33204 0.925191 2.49604 + vertex 1.33267 0.922534 2.49507 + vertex 1.33572 0.926402 2.49582 + endloop + endfacet + facet normal 0.155673 -0.30776 0.938642 + outer loop + vertex 1.33572 0.926402 2.49582 + vertex 1.33358 0.929143 2.49708 + vertex 1.33204 0.925191 2.49604 + endloop + endfacet + facet normal 0.159232 -0.308888 0.937674 + outer loop + vertex 1.33204 0.925191 2.49604 + vertex 1.33358 0.929143 2.49708 + vertex 1.3288 0.925251 2.49661 + endloop + endfacet + facet normal 0.154694 -0.30849 0.938565 + outer loop + vertex 1.33877 0.930254 2.49659 + vertex 1.33358 0.929143 2.49708 + vertex 1.33572 0.926402 2.49582 + endloop + endfacet + facet normal 0.153492 -0.307633 0.939043 + outer loop + vertex 1.33941 0.927607 2.49562 + vertex 1.33877 0.930254 2.49659 + vertex 1.33572 0.926402 2.49582 + endloop + endfacet + facet normal 0.15295 -0.305859 0.939711 + outer loop + vertex 1.33941 0.927607 2.49562 + vertex 1.33572 0.926402 2.49582 + vertex 1.33785 0.923643 2.49458 + endloop + endfacet + facet normal 0.149558 -0.304761 0.940613 + outer loop + vertex 1.33941 0.927607 2.49562 + vertex 1.33785 0.923643 2.49458 + vertex 1.34266 0.927517 2.49507 + endloop + endfacet + facet normal 0.149464 -0.305942 0.940245 + outer loop + vertex 1.34266 0.927517 2.49507 + vertex 1.34203 0.930175 2.49603 + vertex 1.33941 0.927607 2.49562 + endloop + endfacet + facet normal 0.147943 -0.306341 0.940355 + outer loop + vertex 1.34203 0.930175 2.49603 + vertex 1.34266 0.927517 2.49507 + vertex 1.34573 0.931361 2.49584 + endloop + endfacet + facet normal 0.148462 -0.308066 0.93971 + outer loop + vertex 1.34573 0.931361 2.49584 + vertex 1.34358 0.934115 2.49708 + vertex 1.34203 0.930175 2.49603 + endloop + endfacet + facet normal 0.151666 -0.309099 0.938859 + outer loop + vertex 1.34203 0.930175 2.49603 + vertex 1.34358 0.934115 2.49708 + vertex 1.33877 0.930254 2.49659 + endloop + endfacet + facet normal 0.151731 -0.309175 0.938823 + outer loop + vertex 1.34358 0.934115 2.49708 + vertex 1.33832 0.9341 2.49793 + vertex 1.33877 0.930254 2.49659 + endloop + endfacet + facet normal 0.151803 -0.307704 0.939295 + outer loop + vertex 1.34358 0.934115 2.49708 + vertex 1.34307 0.938703 2.49867 + vertex 1.33832 0.9341 2.49793 + endloop + endfacet + facet normal 0.151812 -0.307712 0.93929 + outer loop + vertex 1.33832 0.9341 2.49793 + vertex 1.34307 0.938703 2.49867 + vertex 1.33781 0.938691 2.49951 + endloop + endfacet + facet normal 0.153395 -0.307475 0.939111 + outer loop + vertex 1.33832 0.9341 2.49793 + vertex 1.33781 0.938691 2.49951 + vertex 1.33307 0.93373 2.49866 + endloop + endfacet + facet normal 0.153397 -0.307529 0.939093 + outer loop + vertex 1.33358 0.929143 2.49708 + vertex 1.33832 0.9341 2.49793 + vertex 1.33307 0.93373 2.49866 + endloop + endfacet + facet normal 0.156869 -0.307004 0.938691 + outer loop + vertex 1.33358 0.929143 2.49708 + vertex 1.33307 0.93373 2.49866 + vertex 1.32832 0.92911 2.49794 + endloop + endfacet + facet normal 0.151048 -0.305413 0.940163 + outer loop + vertex 1.33307 0.93373 2.49866 + vertex 1.33781 0.938691 2.49951 + vertex 1.33259 0.937602 2.5 + endloop + endfacet + facet normal 0.150189 -0.307944 0.939475 + outer loop + vertex 1.34358 0.934115 2.49708 + vertex 1.34832 0.939063 2.49794 + vertex 1.34307 0.938703 2.49867 + endloop + endfacet + facet normal 0.150104 -0.304289 0.940679 + outer loop + vertex 1.34832 0.939063 2.49794 + vertex 1.3478 0.943684 2.49952 + vertex 1.34307 0.938703 2.49867 + endloop + endfacet + facet normal 0.152298 -0.306204 0.939704 + outer loop + vertex 1.34307 0.938703 2.49867 + vertex 1.3478 0.943684 2.49952 + vertex 1.3426 0.942571 2.5 + endloop + endfacet + facet normal 0.148407 -0.308107 0.939705 + outer loop + vertex 1.3488 0.935197 2.49661 + vertex 1.34358 0.934115 2.49708 + vertex 1.34573 0.931361 2.49584 + endloop + endfacet + facet normal 0.147377 -0.305933 0.940577 + outer loop + vertex 1.34266 0.927517 2.49507 + vertex 1.34787 0.928598 2.4946 + vertex 1.34573 0.931361 2.49584 + endloop + endfacet + facet normal 0.147476 -0.306493 0.940379 + outer loop + vertex 1.3431 0.923655 2.49374 + vertex 1.34787 0.928598 2.4946 + vertex 1.34266 0.927517 2.49507 + endloop + endfacet + facet normal 0.149436 -0.308233 0.939501 + outer loop + vertex 1.34835 0.924024 2.49303 + vertex 1.34787 0.928598 2.4946 + vertex 1.3431 0.923655 2.49374 + endloop + endfacet + facet normal 0.149442 -0.308468 0.939422 + outer loop + vertex 1.3436 0.919082 2.49216 + vertex 1.34835 0.924024 2.49303 + vertex 1.3431 0.923655 2.49374 + endloop + endfacet + facet normal 0.151722 -0.308129 0.939168 + outer loop + vertex 1.3436 0.919082 2.49216 + vertex 1.3431 0.923655 2.49374 + vertex 1.33833 0.919057 2.493 + endloop + endfacet + facet normal 0.15058 -0.307032 0.939711 + outer loop + vertex 1.33833 0.919057 2.493 + vertex 1.3431 0.923655 2.49374 + vertex 1.33785 0.923643 2.49458 + endloop + endfacet + facet normal 0.150629 -0.306018 0.940034 + outer loop + vertex 1.34266 0.927517 2.49507 + vertex 1.33785 0.923643 2.49458 + vertex 1.3431 0.923655 2.49374 + endloop + endfacet + facet normal 0.151744 -0.308099 0.939174 + outer loop + vertex 1.34203 0.930175 2.49603 + vertex 1.33877 0.930254 2.49659 + vertex 1.33941 0.927607 2.49562 + endloop + endfacet + facet normal 0.154732 -0.308701 0.938489 + outer loop + vertex 1.33877 0.930254 2.49659 + vertex 1.33832 0.9341 2.49793 + vertex 1.33358 0.929143 2.49708 + endloop + endfacet + facet normal 0.153804 -0.305231 0.939776 + outer loop + vertex 1.33267 0.922534 2.49507 + vertex 1.33785 0.923643 2.49458 + vertex 1.33572 0.926402 2.49582 + endloop + endfacet + facet normal 0.154028 -0.306471 0.939335 + outer loop + vertex 1.3331 0.918675 2.49374 + vertex 1.33785 0.923643 2.49458 + vertex 1.33267 0.922534 2.49507 + endloop + endfacet + facet normal 0.163598 -0.304135 0.938476 + outer loop + vertex 1.32276 0.91749 2.49513 + vertex 1.3279 0.918634 2.49461 + vertex 1.32577 0.921373 2.49586 + endloop + endfacet + facet normal 0.163942 -0.304375 0.938338 + outer loop + vertex 1.32212 0.920139 2.4961 + vertex 1.32276 0.91749 2.49513 + vertex 1.32577 0.921373 2.49586 + endloop + endfacet + facet normal 0.166095 -0.303785 0.938151 + outer loop + vertex 1.32276 0.91749 2.49513 + vertex 1.32212 0.920139 2.4961 + vertex 1.31955 0.917544 2.49572 + endloop + endfacet + facet normal 0.166254 -0.301625 0.938819 + outer loop + vertex 1.31955 0.917544 2.49572 + vertex 1.31802 0.913572 2.49471 + vertex 1.32276 0.91749 2.49513 + endloop + endfacet + facet normal 0.166695 -0.301763 0.938697 + outer loop + vertex 1.31955 0.917544 2.49572 + vertex 1.31592 0.916319 2.49597 + vertex 1.31802 0.913572 2.49471 + endloop + endfacet + facet normal 0.166938 -0.302545 0.938402 + outer loop + vertex 1.31955 0.917544 2.49572 + vertex 1.3189 0.920197 2.49669 + vertex 1.31592 0.916319 2.49597 + endloop + endfacet + facet normal 0.16563 -0.301638 0.938926 + outer loop + vertex 1.3189 0.920197 2.49669 + vertex 1.31376 0.919058 2.49723 + vertex 1.31592 0.916319 2.49597 + endloop + endfacet + facet normal 0.166553 -0.300939 0.938987 + outer loop + vertex 1.31592 0.916319 2.49597 + vertex 1.31376 0.919058 2.49723 + vertex 1.31229 0.915092 2.49622 + endloop + endfacet + facet normal 0.165255 -0.303011 0.938549 + outer loop + vertex 1.32212 0.920139 2.4961 + vertex 1.3189 0.920197 2.49669 + vertex 1.31955 0.917544 2.49572 + endloop + endfacet + facet normal 0.165139 -0.304563 0.938067 + outer loop + vertex 1.32212 0.920139 2.4961 + vertex 1.32362 0.924113 2.49713 + vertex 1.3189 0.920197 2.49669 + endloop + endfacet + facet normal 0.162816 -0.301901 0.939333 + outer loop + vertex 1.32362 0.924113 2.49713 + vertex 1.3184 0.924069 2.49802 + vertex 1.3189 0.920197 2.49669 + endloop + endfacet + facet normal 0.159361 -0.307146 0.938225 + outer loop + vertex 1.33204 0.925191 2.49604 + vertex 1.3288 0.925251 2.49661 + vertex 1.32944 0.922603 2.49563 + endloop + endfacet + facet normal 0.163879 -0.304175 0.938414 + outer loop + vertex 1.32577 0.921373 2.49586 + vertex 1.32362 0.924113 2.49713 + vertex 1.32212 0.920139 2.4961 + endloop + endfacet + facet normal 0.156907 -0.306184 0.938952 + outer loop + vertex 1.33358 0.929143 2.49708 + vertex 1.32832 0.92911 2.49794 + vertex 1.3288 0.925251 2.49661 + endloop + endfacet + facet normal 0.153651 -0.303936 0.94022 + outer loop + vertex 1.32832 0.92911 2.49794 + vertex 1.33307 0.93373 2.49866 + vertex 1.32779 0.933724 2.49952 + endloop + endfacet + facet normal 0.158163 -0.29691 0.941716 + outer loop + vertex 1.31932 0.932685 2.5006 + vertex 1.31785 0.928693 2.49958 + vertex 1.32259 0.93262 2.50003 + endloop + endfacet + facet normal 0.158019 -0.298884 0.941116 + outer loop + vertex 1.32259 0.93262 2.50003 + vertex 1.32191 0.935268 2.50098 + vertex 1.31932 0.932685 2.5006 + endloop + endfacet + facet normal 0.160177 -0.300897 0.940109 + outer loop + vertex 1.32191 0.935268 2.50098 + vertex 1.31868 0.935289 2.50154 + vertex 1.31932 0.932685 2.5006 + endloop + endfacet + facet normal 0.163581 -0.299954 0.939824 + outer loop + vertex 1.31932 0.932685 2.5006 + vertex 1.31868 0.935289 2.50154 + vertex 1.31568 0.93143 2.50083 + endloop + endfacet + facet normal 0.160078 -0.302535 0.9396 + outer loop + vertex 1.32191 0.935268 2.50098 + vertex 1.3235 0.939166 2.50197 + vertex 1.31868 0.935289 2.50154 + endloop + endfacet + facet normal 0.158446 -0.300607 0.940495 + outer loop + vertex 1.3235 0.939166 2.50197 + vertex 1.31835 0.939047 2.5028 + vertex 1.31868 0.935289 2.50154 + endloop + endfacet + facet normal 0.154704 -0.299817 0.941369 + outer loop + vertex 1.32191 0.935268 2.50098 + vertex 1.32259 0.93262 2.50003 + vertex 1.32561 0.93648 2.50076 + endloop + endfacet + facet normal 0.163082 -0.298391 0.940408 + outer loop + vertex 1.31932 0.932685 2.5006 + vertex 1.31568 0.93143 2.50083 + vertex 1.31785 0.928693 2.49958 + endloop + endfacet + facet normal 0.16281 -0.30203 0.939293 + outer loop + vertex 1.32362 0.924113 2.49713 + vertex 1.32309 0.928726 2.4987 + vertex 1.3184 0.924069 2.49802 + endloop + endfacet + facet normal 0.165592 -0.301433 0.938998 + outer loop + vertex 1.3189 0.920197 2.49669 + vertex 1.3184 0.924069 2.49802 + vertex 1.31376 0.919058 2.49723 + endloop + endfacet + facet normal 0.167238 -0.30051 0.939002 + outer loop + vertex 1.31376 0.919058 2.49723 + vertex 1.30852 0.918965 2.49813 + vertex 1.30902 0.915111 2.49681 + endloop + endfacet + facet normal 0.16799 -0.301371 0.938592 + outer loop + vertex 1.31229 0.915092 2.49622 + vertex 1.31376 0.919058 2.49723 + vertex 1.30902 0.915111 2.49681 + endloop + endfacet + facet normal 0.165951 -0.299011 0.939709 + outer loop + vertex 1.31229 0.915092 2.49622 + vertex 1.31291 0.912431 2.49526 + vertex 1.31592 0.916319 2.49597 + endloop + endfacet + facet normal 0.168567 -0.295858 0.940241 + outer loop + vertex 1.3097 0.912484 2.49585 + vertex 1.30598 0.911176 2.4961 + vertex 1.30809 0.908477 2.49488 + endloop + endfacet + facet normal 0.168243 -0.300618 0.938788 + outer loop + vertex 1.31291 0.912431 2.49526 + vertex 1.31802 0.913572 2.49471 + vertex 1.31592 0.916319 2.49597 + endloop + endfacet + facet normal 0.168251 -0.30392 0.937723 + outer loop + vertex 1.32276 0.91749 2.49513 + vertex 1.31802 0.913572 2.49471 + vertex 1.32321 0.913644 2.4938 + endloop + endfacet + facet normal 0.163694 -0.304651 0.938292 + outer loop + vertex 1.32321 0.913644 2.4938 + vertex 1.3279 0.918634 2.49461 + vertex 1.32276 0.91749 2.49513 + endloop + endfacet + facet normal 0.159068 -0.305701 0.938746 + outer loop + vertex 1.33267 0.922534 2.49507 + vertex 1.3279 0.918634 2.49461 + vertex 1.3331 0.918675 2.49374 + endloop + endfacet + facet normal 0.15409 -0.306526 0.939307 + outer loop + vertex 1.33833 0.919057 2.493 + vertex 1.33785 0.923643 2.49458 + vertex 1.3331 0.918675 2.49374 + endloop + endfacet + facet normal 0.151687 -0.308864 0.938932 + outer loop + vertex 1.3436 0.919082 2.49216 + vertex 1.33833 0.919057 2.493 + vertex 1.3388 0.915213 2.49166 + endloop + endfacet + facet normal 0.152948 -0.310543 0.938174 + outer loop + vertex 1.34207 0.915136 2.4911 + vertex 1.3388 0.915213 2.49166 + vertex 1.33945 0.912565 2.49068 + endloop + endfacet + facet normal 0.154666 -0.312159 0.937355 + outer loop + vertex 1.34271 0.912488 2.49012 + vertex 1.34207 0.915136 2.4911 + vertex 1.33945 0.912565 2.49068 + endloop + endfacet + facet normal 0.152962 -0.310357 0.938233 + outer loop + vertex 1.34207 0.915136 2.4911 + vertex 1.3436 0.919082 2.49216 + vertex 1.3388 0.915213 2.49166 + endloop + endfacet + facet normal 0.152335 -0.311018 0.938116 + outer loop + vertex 1.34882 0.920187 2.49168 + vertex 1.34835 0.924024 2.49303 + vertex 1.3436 0.919082 2.49216 + endloop + endfacet + facet normal 0.149288 -0.311507 0.938444 + outer loop + vertex 1.35364 0.924041 2.49219 + vertex 1.34835 0.924024 2.49303 + vertex 1.34882 0.920187 2.49168 + endloop + endfacet + facet normal 0.149265 -0.311986 0.938288 + outer loop + vertex 1.35364 0.924041 2.49219 + vertex 1.35315 0.9286 2.49379 + vertex 1.34835 0.924024 2.49303 + endloop + endfacet + facet normal 0.144647 -0.312657 0.938788 + outer loop + vertex 1.35364 0.924041 2.49219 + vertex 1.35843 0.928968 2.49309 + vertex 1.35315 0.9286 2.49379 + endloop + endfacet + facet normal 0.146995 -0.314746 0.937725 + outer loop + vertex 1.35888 0.925136 2.49174 + vertex 1.35843 0.928968 2.49309 + vertex 1.35364 0.924041 2.49219 + endloop + endfacet + facet normal 0.147268 -0.316285 0.937164 + outer loop + vertex 1.35888 0.925136 2.49174 + vertex 1.35364 0.924041 2.49219 + vertex 1.3558 0.921298 2.49093 + endloop + endfacet + facet normal 0.146442 -0.315692 0.937493 + outer loop + vertex 1.35953 0.922492 2.49075 + vertex 1.35888 0.925136 2.49174 + vertex 1.3558 0.921298 2.49093 + endloop + endfacet + facet normal 0.146087 -0.314513 0.937945 + outer loop + vertex 1.35953 0.922492 2.49075 + vertex 1.3558 0.921298 2.49093 + vertex 1.35794 0.918556 2.48967 + endloop + endfacet + facet normal 0.141815 -0.313095 0.939074 + outer loop + vertex 1.35953 0.922492 2.49075 + vertex 1.35794 0.918556 2.48967 + vertex 1.36282 0.922403 2.49022 + endloop + endfacet + facet normal 0.141681 -0.314799 0.938524 + outer loop + vertex 1.36282 0.922403 2.49022 + vertex 1.36219 0.925055 2.4912 + vertex 1.35953 0.922492 2.49075 + endloop + endfacet + facet normal 0.139423 -0.315384 0.938666 + outer loop + vertex 1.36219 0.925055 2.4912 + vertex 1.36282 0.922403 2.49022 + vertex 1.36592 0.926235 2.49105 + endloop + endfacet + facet normal 0.139585 -0.315924 0.938461 + outer loop + vertex 1.36592 0.926235 2.49105 + vertex 1.36375 0.928984 2.49229 + vertex 1.36219 0.925055 2.4912 + endloop + endfacet + facet normal 0.143407 -0.317162 0.937466 + outer loop + vertex 1.36219 0.925055 2.4912 + vertex 1.36375 0.928984 2.49229 + vertex 1.35888 0.925136 2.49174 + endloop + endfacet + facet normal 0.138772 -0.316529 0.938377 + outer loop + vertex 1.369 0.930045 2.49188 + vertex 1.36375 0.928984 2.49229 + vertex 1.36592 0.926235 2.49105 + endloop + endfacet + facet normal 0.137545 -0.315643 0.938856 + outer loop + vertex 1.36962 0.92737 2.49089 + vertex 1.369 0.930045 2.49188 + vertex 1.36592 0.926235 2.49105 + endloop + endfacet + facet normal 0.137711 -0.316213 0.93864 + outer loop + vertex 1.36962 0.92737 2.49089 + vertex 1.36592 0.926235 2.49105 + vertex 1.36801 0.923439 2.4898 + endloop + endfacet + facet normal 0.135681 -0.315527 0.939166 + outer loop + vertex 1.36962 0.92737 2.49089 + vertex 1.36801 0.923439 2.4898 + vertex 1.37274 0.927097 2.49034 + endloop + endfacet + facet normal 0.135702 -0.31538 0.939213 + outer loop + vertex 1.37274 0.927097 2.49034 + vertex 1.37226 0.929864 2.49134 + vertex 1.36962 0.92737 2.49089 + endloop + endfacet + facet normal 0.133059 -0.315915 0.939411 + outer loop + vertex 1.37226 0.929864 2.49134 + vertex 1.37274 0.927097 2.49034 + vertex 1.376 0.930843 2.49114 + endloop + endfacet + facet normal 0.132608 -0.314049 0.9401 + outer loop + vertex 1.376 0.930843 2.49114 + vertex 1.37379 0.93382 2.49245 + vertex 1.37226 0.929864 2.49134 + endloop + endfacet + facet normal 0.136379 -0.315245 0.93916 + outer loop + vertex 1.37226 0.929864 2.49134 + vertex 1.37379 0.93382 2.49245 + vertex 1.369 0.930045 2.49188 + endloop + endfacet + facet normal 0.135534 -0.314243 0.939618 + outer loop + vertex 1.37379 0.93382 2.49245 + vertex 1.3685 0.933864 2.49322 + vertex 1.369 0.930045 2.49188 + endloop + endfacet + facet normal 0.13573 -0.310731 0.940757 + outer loop + vertex 1.37379 0.93382 2.49245 + vertex 1.37311 0.938278 2.49402 + vertex 1.3685 0.933864 2.49322 + endloop + endfacet + facet normal 0.13567 -0.310673 0.940785 + outer loop + vertex 1.3685 0.933864 2.49322 + vertex 1.37311 0.938278 2.49402 + vertex 1.36802 0.938403 2.49479 + endloop + endfacet + facet normal 0.138597 -0.310261 0.940494 + outer loop + vertex 1.3685 0.933864 2.49322 + vertex 1.36802 0.938403 2.49479 + vertex 1.36326 0.93353 2.49389 + endloop + endfacet + facet normal 0.138679 -0.314134 0.939195 + outer loop + vertex 1.36375 0.928984 2.49229 + vertex 1.3685 0.933864 2.49322 + vertex 1.36326 0.93353 2.49389 + endloop + endfacet + facet normal 0.142106 -0.313641 0.938848 + outer loop + vertex 1.36375 0.928984 2.49229 + vertex 1.36326 0.93353 2.49389 + vertex 1.35843 0.928968 2.49309 + endloop + endfacet + facet normal 0.140488 -0.312062 0.939617 + outer loop + vertex 1.35843 0.928968 2.49309 + vertex 1.36326 0.93353 2.49389 + vertex 1.35796 0.933522 2.49468 + endloop + endfacet + facet normal 0.138645 -0.310303 0.940473 + outer loop + vertex 1.36326 0.93353 2.49389 + vertex 1.36802 0.938403 2.49479 + vertex 1.36283 0.937363 2.49522 + endloop + endfacet + facet normal 0.131715 -0.31146 0.941087 + outer loop + vertex 1.37379 0.93382 2.49245 + vertex 1.37827 0.938764 2.49346 + vertex 1.37311 0.938278 2.49402 + endloop + endfacet + facet normal 0.131476 -0.307295 0.942488 + outer loop + vertex 1.37827 0.938764 2.49346 + vertex 1.37723 0.94258 2.49485 + vertex 1.37311 0.938278 2.49402 + endloop + endfacet + facet normal 0.132009 -0.307761 0.942261 + outer loop + vertex 1.37311 0.938278 2.49402 + vertex 1.37723 0.94258 2.49485 + vertex 1.37272 0.942077 2.49531 + endloop + endfacet + facet normal 0.130144 -0.310168 0.941732 + outer loop + vertex 1.37931 0.934947 2.49206 + vertex 1.37827 0.938764 2.49346 + vertex 1.37379 0.93382 2.49245 + endloop + endfacet + facet normal 0.124762 -0.311719 0.941948 + outer loop + vertex 1.37931 0.934947 2.49206 + vertex 1.38345 0.939198 2.49291 + vertex 1.37827 0.938764 2.49346 + endloop + endfacet + facet normal 0.124559 -0.307542 0.943347 + outer loop + vertex 1.38345 0.939198 2.49291 + vertex 1.38273 0.943674 2.49447 + vertex 1.37827 0.938764 2.49346 + endloop + endfacet + facet normal 0.11732 -0.308879 0.943838 + outer loop + vertex 1.38345 0.939198 2.49291 + vertex 1.38794 0.943434 2.49374 + vertex 1.38273 0.943674 2.49447 + endloop + endfacet + facet normal 0.11699 -0.308558 0.943984 + outer loop + vertex 1.38863 0.938978 2.4922 + vertex 1.38794 0.943434 2.49374 + vertex 1.38345 0.939198 2.49291 + endloop + endfacet + facet normal 0.116725 -0.311635 0.943005 + outer loop + vertex 1.38863 0.938978 2.4922 + vertex 1.38345 0.939198 2.49291 + vertex 1.38388 0.935397 2.4916 + endloop + endfacet + facet normal 0.117987 -0.313197 0.94233 + outer loop + vertex 1.38708 0.935086 2.4911 + vertex 1.38863 0.938978 2.4922 + vertex 1.38388 0.935397 2.4916 + endloop + endfacet + facet normal 0.117766 -0.314699 0.941857 + outer loop + vertex 1.38708 0.935086 2.4911 + vertex 1.38388 0.935397 2.4916 + vertex 1.3844 0.932615 2.49061 + endloop + endfacet + facet normal 0.117151 -0.314088 0.942138 + outer loop + vertex 1.38775 0.932394 2.49012 + vertex 1.38708 0.935086 2.4911 + vertex 1.3844 0.932615 2.49061 + endloop + endfacet + facet normal 0.116988 -0.315524 0.941678 + outer loop + vertex 1.3844 0.932615 2.49061 + vertex 1.38292 0.928618 2.48946 + vertex 1.38775 0.932394 2.49012 + endloop + endfacet + facet normal 0.12328 -0.317443 0.94023 + outer loop + vertex 1.3844 0.932615 2.49061 + vertex 1.3806 0.931661 2.49079 + vertex 1.38292 0.928618 2.48946 + endloop + endfacet + facet normal 0.113728 -0.314984 0.942259 + outer loop + vertex 1.38708 0.935086 2.4911 + vertex 1.38775 0.932394 2.49012 + vertex 1.39085 0.936141 2.491 + endloop + endfacet + facet normal 0.113154 -0.314558 0.94247 + outer loop + vertex 1.38775 0.932394 2.49012 + vertex 1.39303 0.933333 2.4898 + vertex 1.39085 0.936141 2.491 + endloop + endfacet + facet normal 0.11104 -0.316082 0.942211 + outer loop + vertex 1.39464 0.937193 2.49091 + vertex 1.39085 0.936141 2.491 + vertex 1.39303 0.933333 2.4898 + endloop + endfacet + facet normal 0.108461 -0.315178 0.942814 + outer loop + vertex 1.39464 0.937193 2.49091 + vertex 1.39303 0.933333 2.4898 + vertex 1.39782 0.936893 2.49044 + endloop + endfacet + facet normal 0.108797 -0.312795 0.943569 + outer loop + vertex 1.39782 0.936893 2.49044 + vertex 1.39733 0.939672 2.49142 + vertex 1.39464 0.937193 2.49091 + endloop + endfacet + facet normal 0.108085 -0.312086 0.943886 + outer loop + vertex 1.39733 0.939672 2.49142 + vertex 1.39396 0.939905 2.49188 + vertex 1.39464 0.937193 2.49091 + endloop + endfacet + facet normal 0.107967 -0.31313 0.943553 + outer loop + vertex 1.39733 0.939672 2.49142 + vertex 1.3988 0.94369 2.49258 + vertex 1.39396 0.939905 2.49188 + endloop + endfacet + facet normal 0.106373 -0.311243 0.944358 + outer loop + vertex 1.3988 0.94369 2.49258 + vertex 1.39323 0.943731 2.49322 + vertex 1.39396 0.939905 2.49188 + endloop + endfacet + facet normal 0.110831 -0.31032 0.944149 + outer loop + vertex 1.39396 0.939905 2.49188 + vertex 1.39323 0.943731 2.49322 + vertex 1.38863 0.938978 2.4922 + endloop + endfacet + facet normal 0.111184 -0.312625 0.943347 + outer loop + vertex 1.39396 0.939905 2.49188 + vertex 1.38863 0.938978 2.4922 + vertex 1.39085 0.936141 2.491 + endloop + endfacet + facet normal 0.106285 -0.313218 0.943715 + outer loop + vertex 1.3988 0.94369 2.49258 + vertex 1.3978 0.948625 2.49433 + vertex 1.39323 0.943731 2.49322 + endloop + endfacet + facet normal 0.10415 -0.311414 0.94455 + outer loop + vertex 1.39323 0.943731 2.49322 + vertex 1.3978 0.948625 2.49433 + vertex 1.39211 0.947662 2.49464 + endloop + endfacet + facet normal 0.110196 -0.309642 0.944446 + outer loop + vertex 1.39323 0.943731 2.49322 + vertex 1.39211 0.947662 2.49464 + vertex 1.38794 0.943434 2.49374 + endloop + endfacet + facet normal 0.109012 -0.308579 0.944931 + outer loop + vertex 1.38794 0.943434 2.49374 + vertex 1.39211 0.947662 2.49464 + vertex 1.38745 0.947272 2.49505 + endloop + endfacet + facet normal 0.109155 -0.311197 0.944056 + outer loop + vertex 1.38745 0.947272 2.49505 + vertex 1.39211 0.947662 2.49464 + vertex 1.39077 0.950994 2.4959 + endloop + endfacet + facet normal 0.10422 -0.313144 0.94397 + outer loop + vertex 1.39077 0.950994 2.4959 + vertex 1.39211 0.947662 2.49464 + vertex 1.39546 0.951763 2.49563 + endloop + endfacet + facet normal 0.106752 -0.313188 0.943672 + outer loop + vertex 1.39733 0.939672 2.49142 + vertex 1.39782 0.936893 2.49044 + vertex 1.40117 0.940631 2.4913 + endloop + endfacet + facet normal 0.109841 -0.31163 0.943833 + outer loop + vertex 1.39464 0.937193 2.49091 + vertex 1.39396 0.939905 2.49188 + vertex 1.39085 0.936141 2.491 + endloop + endfacet + facet normal 0.122412 -0.313734 0.941587 + outer loop + vertex 1.3844 0.932615 2.49061 + vertex 1.38388 0.935397 2.4916 + vertex 1.3806 0.931661 2.49079 + endloop + endfacet + facet normal 0.123847 -0.31487 0.94102 + outer loop + vertex 1.38388 0.935397 2.4916 + vertex 1.37931 0.934947 2.49206 + vertex 1.3806 0.931661 2.49079 + endloop + endfacet + facet normal 0.128248 -0.313137 0.941009 + outer loop + vertex 1.3806 0.931661 2.49079 + vertex 1.37931 0.934947 2.49206 + vertex 1.376 0.930843 2.49114 + endloop + endfacet + facet normal 0.128837 -0.317059 0.939614 + outer loop + vertex 1.376 0.930843 2.49114 + vertex 1.37729 0.927559 2.48986 + vertex 1.3806 0.931661 2.49079 + endloop + endfacet + facet normal 0.112779 -0.31146 0.943543 + outer loop + vertex 1.39085 0.936141 2.491 + vertex 1.38863 0.938978 2.4922 + vertex 1.38708 0.935086 2.4911 + endloop + endfacet + facet normal 0.110199 -0.309764 0.944406 + outer loop + vertex 1.38863 0.938978 2.4922 + vertex 1.39323 0.943731 2.49322 + vertex 1.38794 0.943434 2.49374 + endloop + endfacet + facet normal 0.123574 -0.310665 0.942453 + outer loop + vertex 1.38388 0.935397 2.4916 + vertex 1.38345 0.939198 2.49291 + vertex 1.37931 0.934947 2.49206 + endloop + endfacet + facet normal 0.131034 -0.315152 0.939952 + outer loop + vertex 1.37931 0.934947 2.49206 + vertex 1.37379 0.93382 2.49245 + vertex 1.376 0.930843 2.49114 + endloop + endfacet + facet normal 0.132616 -0.315568 0.93959 + outer loop + vertex 1.37274 0.927097 2.49034 + vertex 1.37729 0.927559 2.48986 + vertex 1.376 0.930843 2.49114 + endloop + endfacet + facet normal 0.136302 -0.315961 0.93893 + outer loop + vertex 1.37226 0.929864 2.49134 + vertex 1.369 0.930045 2.49188 + vertex 1.36962 0.92737 2.49089 + endloop + endfacet + facet normal 0.138299 -0.313795 0.939365 + outer loop + vertex 1.369 0.930045 2.49188 + vertex 1.3685 0.933864 2.49322 + vertex 1.36375 0.928984 2.49229 + endloop + endfacet + facet normal 0.139157 -0.315191 0.93877 + outer loop + vertex 1.36282 0.922403 2.49022 + vertex 1.36801 0.923439 2.4898 + vertex 1.36592 0.926235 2.49105 + endloop + endfacet + facet normal 0.148239 -0.312923 0.938139 + outer loop + vertex 1.35273 0.917461 2.49013 + vertex 1.35794 0.918556 2.48967 + vertex 1.3558 0.921298 2.49093 + endloop + endfacet + facet normal 0.149453 -0.313795 0.937655 + outer loop + vertex 1.35209 0.920107 2.49112 + vertex 1.35273 0.917461 2.49013 + vertex 1.3558 0.921298 2.49093 + endloop + endfacet + facet normal 0.143458 -0.316494 0.937684 + outer loop + vertex 1.36219 0.925055 2.4912 + vertex 1.35888 0.925136 2.49174 + vertex 1.35953 0.922492 2.49075 + endloop + endfacet + facet normal 0.149664 -0.314496 0.937386 + outer loop + vertex 1.3558 0.921298 2.49093 + vertex 1.35364 0.924041 2.49219 + vertex 1.35209 0.920107 2.49112 + endloop + endfacet + facet normal 0.142019 -0.315518 0.938232 + outer loop + vertex 1.36375 0.928984 2.49229 + vertex 1.35843 0.928968 2.49309 + vertex 1.35888 0.925136 2.49174 + endloop + endfacet + facet normal 0.152637 -0.315443 0.936588 + outer loop + vertex 1.35209 0.920107 2.49112 + vertex 1.35364 0.924041 2.49219 + vertex 1.34882 0.920187 2.49168 + endloop + endfacet + facet normal 0.154634 -0.313632 0.936869 + outer loop + vertex 1.34947 0.917543 2.49069 + vertex 1.34577 0.916341 2.4909 + vertex 1.3479 0.913599 2.48963 + endloop + endfacet + facet normal 0.149834 -0.318417 0.936034 + outer loop + vertex 1.35881 0.910192 2.48671 + vertex 1.35838 0.914009 2.48808 + vertex 1.3536 0.9091 2.48717 + endloop + endfacet + facet normal 0.148596 -0.314929 0.937411 + outer loop + vertex 1.35314 0.91363 2.48878 + vertex 1.35794 0.918556 2.48967 + vertex 1.35273 0.917461 2.49013 + endloop + endfacet + facet normal 0.143551 -0.315159 0.938119 + outer loop + vertex 1.36282 0.922403 2.49022 + vertex 1.35794 0.918556 2.48967 + vertex 1.36321 0.918565 2.48887 + endloop + endfacet + facet normal 0.142762 -0.319779 0.936675 + outer loop + vertex 1.36892 0.915098 2.48682 + vertex 1.36846 0.918902 2.48819 + vertex 1.36366 0.91402 2.48726 + endloop + endfacet + facet normal 0.139254 -0.31576 0.938565 + outer loop + vertex 1.36321 0.918565 2.48887 + vertex 1.36801 0.923439 2.4898 + vertex 1.36282 0.922403 2.49022 + endloop + endfacet + facet normal 0.137193 -0.317357 0.93833 + outer loop + vertex 1.37274 0.927097 2.49034 + vertex 1.36801 0.923439 2.4898 + vertex 1.37312 0.923297 2.489 + endloop + endfacet + facet normal 0.136286 -0.32296 0.936549 + outer loop + vertex 1.37905 0.919946 2.487 + vertex 1.37834 0.923698 2.48839 + vertex 1.37376 0.918893 2.4874 + endloop + endfacet + facet normal 0.132769 -0.317952 0.938765 + outer loop + vertex 1.37312 0.923297 2.489 + vertex 1.37729 0.927559 2.48986 + vertex 1.37274 0.927097 2.49034 + endloop + endfacet + facet normal 0.126342 -0.315256 0.940559 + outer loop + vertex 1.37729 0.927559 2.48986 + vertex 1.38292 0.928618 2.48946 + vertex 1.3806 0.931661 2.49079 + endloop + endfacet + facet normal 0.12041 -0.319586 0.939875 + outer loop + vertex 1.38775 0.932394 2.49012 + vertex 1.38292 0.928618 2.48946 + vertex 1.38841 0.928635 2.48876 + endloop + endfacet + facet normal 0.114133 -0.320813 0.940241 + outer loop + vertex 1.38841 0.928635 2.48876 + vertex 1.39303 0.933333 2.4898 + vertex 1.38775 0.932394 2.49012 + endloop + endfacet + facet normal 0.110157 -0.317298 0.941906 + outer loop + vertex 1.39782 0.936893 2.49044 + vertex 1.39303 0.933333 2.4898 + vertex 1.39817 0.933133 2.48913 + endloop + endfacet + facet normal 0.103496 -0.320423 0.941604 + outer loop + vertex 1.40449 0.929755 2.48727 + vertex 1.40342 0.933548 2.48868 + vertex 1.39883 0.928713 2.48754 + endloop + endfacet + facet normal 0.104539 -0.326661 0.939342 + outer loop + vertex 1.40449 0.929755 2.48727 + vertex 1.39883 0.928713 2.48754 + vertex 1.40106 0.925691 2.48624 + endloop + endfacet + facet normal 0.101156 -0.324126 0.94059 + outer loop + vertex 1.40581 0.926482 2.486 + vertex 1.40449 0.929755 2.48727 + vertex 1.40106 0.925691 2.48624 + endloop + endfacet + facet normal 0.10162 -0.327242 0.939461 + outer loop + vertex 1.40106 0.925691 2.48624 + vertex 1.40232 0.922434 2.48497 + vertex 1.40581 0.926482 2.486 + endloop + endfacet + facet normal 0.100567 -0.326437 0.939854 + outer loop + vertex 1.40232 0.922434 2.48497 + vertex 1.40796 0.923458 2.48472 + vertex 1.40581 0.926482 2.486 + endloop + endfacet + facet normal 0.0992413 -0.327312 0.93969 + outer loop + vertex 1.40967 0.927365 2.4859 + vertex 1.40581 0.926482 2.486 + vertex 1.40796 0.923458 2.48472 + endloop + endfacet + facet normal 0.0978905 -0.326815 0.940005 + outer loop + vertex 1.40967 0.927365 2.4859 + vertex 1.40796 0.923458 2.48472 + vertex 1.41278 0.926915 2.48542 + endloop + endfacet + facet normal 0.0982747 -0.322895 0.941319 + outer loop + vertex 1.40967 0.927365 2.4859 + vertex 1.40918 0.930159 2.48691 + vertex 1.40581 0.926482 2.486 + endloop + endfacet + facet normal 0.0979802 -0.322951 0.94133 + outer loop + vertex 1.41237 0.929735 2.48643 + vertex 1.40918 0.930159 2.48691 + vertex 1.40967 0.927365 2.4859 + endloop + endfacet + facet normal 0.0988617 -0.318077 0.942896 + outer loop + vertex 1.41237 0.929735 2.48643 + vertex 1.41387 0.933629 2.48759 + vertex 1.40918 0.930159 2.48691 + endloop + endfacet + facet normal 0.0991514 -0.31844 0.942743 + outer loop + vertex 1.41387 0.933629 2.48759 + vertex 1.40868 0.933932 2.48824 + vertex 1.40918 0.930159 2.48691 + endloop + endfacet + facet normal 0.099855 -0.318334 0.942705 + outer loop + vertex 1.40918 0.930159 2.48691 + vertex 1.40868 0.933932 2.48824 + vertex 1.40449 0.929755 2.48727 + endloop + endfacet + facet normal 0.0995857 -0.314045 0.944171 + outer loop + vertex 1.41387 0.933629 2.48759 + vertex 1.41313 0.938056 2.48914 + vertex 1.40868 0.933932 2.48824 + endloop + endfacet + facet normal 0.100699 -0.315139 0.943688 + outer loop + vertex 1.40868 0.933932 2.48824 + vertex 1.41313 0.938056 2.48914 + vertex 1.40802 0.938372 2.48979 + endloop + endfacet + facet normal 0.102219 -0.314884 0.94361 + outer loop + vertex 1.40868 0.933932 2.48824 + vertex 1.40802 0.938372 2.48979 + vertex 1.40342 0.933548 2.48868 + endloop + endfacet + facet normal 0.100929 -0.312909 0.944405 + outer loop + vertex 1.41278 0.941863 2.49044 + vertex 1.40802 0.938372 2.48979 + vertex 1.41313 0.938056 2.48914 + endloop + endfacet + facet normal 0.0989717 -0.313132 0.944538 + outer loop + vertex 1.41313 0.938056 2.48914 + vertex 1.41717 0.942091 2.49005 + vertex 1.41278 0.941863 2.49044 + endloop + endfacet + facet normal 0.0990333 -0.315852 0.943626 + outer loop + vertex 1.41278 0.941863 2.49044 + vertex 1.41717 0.942091 2.49005 + vertex 1.41608 0.945513 2.49131 + endloop + endfacet + facet normal 0.0988773 -0.315725 0.943685 + outer loop + vertex 1.41237 0.944707 2.49143 + vertex 1.41278 0.941863 2.49044 + vertex 1.41608 0.945513 2.49131 + endloop + endfacet + facet normal 0.0998687 -0.320557 0.94195 + outer loop + vertex 1.41608 0.945513 2.49131 + vertex 1.41383 0.948674 2.49263 + vertex 1.41237 0.944707 2.49143 + endloop + endfacet + facet normal 0.101376 -0.321018 0.941632 + outer loop + vertex 1.41237 0.944707 2.49143 + vertex 1.41383 0.948674 2.49263 + vertex 1.40918 0.945118 2.49192 + endloop + endfacet + facet normal 0.102039 -0.317283 0.942825 + outer loop + vertex 1.41237 0.944707 2.49143 + vertex 1.40918 0.945118 2.49192 + vertex 1.40969 0.942312 2.49092 + endloop + endfacet + facet normal 0.104334 -0.316826 0.942728 + outer loop + vertex 1.40969 0.942312 2.49092 + vertex 1.40918 0.945118 2.49192 + vertex 1.40587 0.941424 2.49104 + endloop + endfacet + facet normal 0.103663 -0.313788 0.943817 + outer loop + vertex 1.40969 0.942312 2.49092 + vertex 1.40587 0.941424 2.49104 + vertex 1.40802 0.938372 2.48979 + endloop + endfacet + facet normal 0.100549 -0.320021 0.94206 + outer loop + vertex 1.41383 0.948674 2.49263 + vertex 1.4085 0.948858 2.49326 + vertex 1.40918 0.945118 2.49192 + endloop + endfacet + facet normal 0.0998609 -0.320562 0.941949 + outer loop + vertex 1.41943 0.949597 2.49235 + vertex 1.41383 0.948674 2.49263 + vertex 1.41608 0.945513 2.49131 + endloop + endfacet + facet normal 0.0992844 -0.320141 0.942153 + outer loop + vertex 1.42075 0.946099 2.49102 + vertex 1.41943 0.949597 2.49235 + vertex 1.41608 0.945513 2.49131 + endloop + endfacet + facet normal 0.100573 -0.319665 0.942178 + outer loop + vertex 1.42434 0.95011 2.492 + vertex 1.41943 0.949597 2.49235 + vertex 1.42075 0.946099 2.49102 + endloop + endfacet + facet normal 0.0998872 -0.319114 0.942438 + outer loop + vertex 1.42543 0.946708 2.49073 + vertex 1.42434 0.95011 2.492 + vertex 1.42075 0.946099 2.49102 + endloop + endfacet + facet normal 0.0995111 -0.31564 0.943647 + outer loop + vertex 1.42075 0.946099 2.49102 + vertex 1.42205 0.942618 2.48972 + vertex 1.42543 0.946708 2.49073 + endloop + endfacet + facet normal 0.10039 -0.316289 0.943336 + outer loop + vertex 1.42205 0.942618 2.48972 + vertex 1.42764 0.943626 2.48946 + vertex 1.42543 0.946708 2.49073 + endloop + endfacet + facet normal 0.100175 -0.316432 0.943311 + outer loop + vertex 1.42921 0.947541 2.49061 + vertex 1.42543 0.946708 2.49073 + vertex 1.42764 0.943626 2.48946 + endloop + endfacet + facet normal 0.101009 -0.316714 0.943127 + outer loop + vertex 1.42921 0.947541 2.49061 + vertex 1.42764 0.943626 2.48946 + vertex 1.43241 0.94714 2.49013 + endloop + endfacet + facet normal 0.100827 -0.317767 0.942793 + outer loop + vertex 1.43241 0.94714 2.49013 + vertex 1.43193 0.949941 2.49113 + vertex 1.42921 0.947541 2.49061 + endloop + endfacet + facet normal 0.101149 -0.318099 0.942646 + outer loop + vertex 1.43193 0.949941 2.49113 + vertex 1.42879 0.950365 2.49161 + vertex 1.42921 0.947541 2.49061 + endloop + endfacet + facet normal 0.100978 -0.319026 0.942351 + outer loop + vertex 1.43193 0.949941 2.49113 + vertex 1.43358 0.953875 2.49228 + vertex 1.42879 0.950365 2.49161 + endloop + endfacet + facet normal 0.102323 -0.320724 0.941629 + outer loop + vertex 1.43358 0.953875 2.49228 + vertex 1.42843 0.954157 2.49294 + vertex 1.42879 0.950365 2.49161 + endloop + endfacet + facet normal 0.101216 -0.320856 0.941704 + outer loop + vertex 1.42879 0.950365 2.49161 + vertex 1.42843 0.954157 2.49294 + vertex 1.42434 0.95011 2.492 + endloop + endfacet + facet normal 0.102291 -0.321837 0.941253 + outer loop + vertex 1.42434 0.95011 2.492 + vertex 1.42843 0.954157 2.49294 + vertex 1.42337 0.953871 2.49339 + endloop + endfacet + facet normal 0.102309 -0.322557 0.941005 + outer loop + vertex 1.42843 0.954157 2.49294 + vertex 1.42775 0.958553 2.49452 + vertex 1.42337 0.953871 2.49339 + endloop + endfacet + facet normal 0.102704 -0.322889 0.940848 + outer loop + vertex 1.42337 0.953871 2.49339 + vertex 1.42775 0.958553 2.49452 + vertex 1.42221 0.957541 2.49478 + endloop + endfacet + facet normal 0.103938 -0.322276 0.940922 + outer loop + vertex 1.42843 0.954157 2.49294 + vertex 1.43291 0.9583 2.49386 + vertex 1.42775 0.958553 2.49452 + endloop + endfacet + facet normal 0.102326 -0.320692 0.94164 + outer loop + vertex 1.43358 0.953875 2.49228 + vertex 1.43291 0.9583 2.49386 + vertex 1.42843 0.954157 2.49294 + endloop + endfacet + facet normal 0.103833 -0.320436 0.941562 + outer loop + vertex 1.43358 0.953875 2.49228 + vertex 1.43816 0.958702 2.49342 + vertex 1.43291 0.9583 2.49386 + endloop + endfacet + facet normal 0.103765 -0.319021 0.94205 + outer loop + vertex 1.43816 0.958702 2.49342 + vertex 1.43712 0.962495 2.49482 + vertex 1.43291 0.9583 2.49386 + endloop + endfacet + facet normal 0.105532 -0.320623 0.94131 + outer loop + vertex 1.43291 0.9583 2.49386 + vertex 1.43712 0.962495 2.49482 + vertex 1.43251 0.96207 2.49519 + endloop + endfacet + facet normal 0.10524 -0.318609 0.942026 + outer loop + vertex 1.43816 0.958702 2.49342 + vertex 1.44272 0.963548 2.49455 + vertex 1.43712 0.962495 2.49482 + endloop + endfacet + facet normal 0.103894 -0.317467 0.942561 + outer loop + vertex 1.44341 0.959102 2.49298 + vertex 1.44272 0.963548 2.49455 + vertex 1.43816 0.958702 2.49342 + endloop + endfacet + facet normal 0.103927 -0.318153 0.942326 + outer loop + vertex 1.43921 0.954907 2.49202 + vertex 1.44341 0.959102 2.49298 + vertex 1.43816 0.958702 2.49342 + endloop + endfacet + facet normal 0.101848 -0.318742 0.942354 + outer loop + vertex 1.43921 0.954907 2.49202 + vertex 1.43816 0.958702 2.49342 + vertex 1.43358 0.953875 2.49228 + endloop + endfacet + facet normal 0.101794 -0.318415 0.94247 + outer loop + vertex 1.43921 0.954907 2.49202 + vertex 1.43358 0.953875 2.49228 + vertex 1.43579 0.950839 2.49102 + endloop + endfacet + facet normal 0.101414 -0.31813 0.942607 + outer loop + vertex 1.44054 0.951617 2.49077 + vertex 1.43921 0.954907 2.49202 + vertex 1.43579 0.950839 2.49102 + endloop + endfacet + facet normal 0.101645 -0.319717 0.942045 + outer loop + vertex 1.43579 0.950839 2.49102 + vertex 1.43712 0.947545 2.48976 + vertex 1.44054 0.951617 2.49077 + endloop + endfacet + facet normal 0.104125 -0.321573 0.941142 + outer loop + vertex 1.43712 0.947545 2.48976 + vertex 1.44284 0.948527 2.48946 + vertex 1.44054 0.951617 2.49077 + endloop + endfacet + facet normal 0.104377 -0.323224 0.940548 + outer loop + vertex 1.43821 0.943698 2.48831 + vertex 1.44284 0.948527 2.48946 + vertex 1.43712 0.947545 2.48976 + endloop + endfacet + facet normal 0.106499 -0.322611 0.940521 + outer loop + vertex 1.43821 0.943698 2.48831 + vertex 1.43712 0.947545 2.48976 + vertex 1.43288 0.943366 2.4888 + endloop + endfacet + facet normal 0.106435 -0.320504 0.941248 + outer loop + vertex 1.43356 0.938988 2.48724 + vertex 1.43821 0.943698 2.48831 + vertex 1.43288 0.943366 2.4888 + endloop + endfacet + facet normal 0.10744 -0.320327 0.941194 + outer loop + vertex 1.43356 0.938988 2.48724 + vertex 1.43288 0.943366 2.4888 + vertex 1.42838 0.939211 2.4879 + endloop + endfacet + facet normal 0.107782 -0.316316 0.942511 + outer loop + vertex 1.43356 0.938988 2.48724 + vertex 1.42838 0.939211 2.4879 + vertex 1.42878 0.935426 2.48659 + endloop + endfacet + facet normal 0.105329 -0.316641 0.942679 + outer loop + vertex 1.42878 0.935426 2.48659 + vertex 1.42838 0.939211 2.4879 + vertex 1.4243 0.935128 2.48699 + endloop + endfacet + facet normal 0.105347 -0.31712 0.942516 + outer loop + vertex 1.42878 0.935426 2.48659 + vertex 1.4243 0.935128 2.48699 + vertex 1.42546 0.93173 2.48571 + endloop + endfacet + facet normal 0.10668 -0.318198 0.942003 + outer loop + vertex 1.42928 0.932628 2.48558 + vertex 1.42878 0.935426 2.48659 + vertex 1.42546 0.93173 2.48571 + endloop + endfacet + facet normal 0.107125 -0.320195 0.941275 + outer loop + vertex 1.42928 0.932628 2.48558 + vertex 1.42546 0.93173 2.48571 + vertex 1.42779 0.928646 2.4844 + endloop + endfacet + facet normal 0.109809 -0.321027 0.940682 + outer loop + vertex 1.42928 0.932628 2.48558 + vertex 1.42779 0.928646 2.4844 + vertex 1.43265 0.932418 2.48512 + endloop + endfacet + facet normal 0.110145 -0.317894 0.941707 + outer loop + vertex 1.43265 0.932418 2.48512 + vertex 1.43199 0.935108 2.48611 + vertex 1.42928 0.932628 2.48558 + endloop + endfacet + facet normal 0.111782 -0.317473 0.941656 + outer loop + vertex 1.43199 0.935108 2.48611 + vertex 1.43265 0.932418 2.48512 + vertex 1.43579 0.936202 2.48602 + endloop + endfacet + facet normal 0.112371 -0.319582 0.940872 + outer loop + vertex 1.43579 0.936202 2.48602 + vertex 1.43356 0.938988 2.48724 + vertex 1.43199 0.935108 2.48611 + endloop + endfacet + facet normal 0.109671 -0.318666 0.941501 + outer loop + vertex 1.43199 0.935108 2.48611 + vertex 1.43356 0.938988 2.48724 + vertex 1.42878 0.935426 2.48659 + endloop + endfacet + facet normal 0.110827 -0.320727 0.940666 + outer loop + vertex 1.43893 0.939965 2.48694 + vertex 1.43356 0.938988 2.48724 + vertex 1.43579 0.936202 2.48602 + endloop + endfacet + facet normal 0.112506 -0.321975 0.94004 + outer loop + vertex 1.4396 0.937288 2.48594 + vertex 1.43893 0.939965 2.48694 + vertex 1.43579 0.936202 2.48602 + endloop + endfacet + facet normal 0.110194 -0.313638 0.943127 + outer loop + vertex 1.4396 0.937288 2.48594 + vertex 1.43579 0.936202 2.48602 + vertex 1.43792 0.93339 2.48484 + endloop + endfacet + facet normal 0.105009 -0.311752 0.944343 + outer loop + vertex 1.4396 0.937288 2.48594 + vertex 1.43792 0.93339 2.48484 + vertex 1.4427 0.936929 2.48548 + endloop + endfacet + facet normal 0.104163 -0.316955 0.942703 + outer loop + vertex 1.4427 0.936929 2.48548 + vertex 1.4423 0.93974 2.48647 + vertex 1.4396 0.937288 2.48594 + endloop + endfacet + facet normal 0.10211 -0.317291 0.942815 + outer loop + vertex 1.4423 0.93974 2.48647 + vertex 1.4427 0.936929 2.48548 + vertex 1.44605 0.940584 2.48634 + endloop + endfacet + facet normal 0.103967 -0.326007 0.939633 + outer loop + vertex 1.44605 0.940584 2.48634 + vertex 1.44376 0.94368 2.48767 + vertex 1.4423 0.93974 2.48647 + endloop + endfacet + facet normal 0.109293 -0.327621 0.938467 + outer loop + vertex 1.4423 0.93974 2.48647 + vertex 1.44376 0.94368 2.48767 + vertex 1.43893 0.939965 2.48694 + endloop + endfacet + facet normal 0.107782 -0.325818 0.939269 + outer loop + vertex 1.44376 0.94368 2.48767 + vertex 1.43821 0.943698 2.48831 + vertex 1.43893 0.939965 2.48694 + endloop + endfacet + facet normal 0.105738 -0.324791 0.939857 + outer loop + vertex 1.44938 0.944642 2.48737 + vertex 1.44376 0.94368 2.48767 + vertex 1.44605 0.940584 2.48634 + endloop + endfacet + facet normal 0.103468 -0.323132 0.94068 + outer loop + vertex 1.4507 0.941148 2.48603 + vertex 1.44938 0.944642 2.48737 + vertex 1.44605 0.940584 2.48634 + endloop + endfacet + facet normal 0.10277 -0.315969 0.943187 + outer loop + vertex 1.44605 0.940584 2.48634 + vertex 1.44706 0.937144 2.48508 + vertex 1.4507 0.941148 2.48603 + endloop + endfacet + facet normal 0.103121 -0.316256 0.943053 + outer loop + vertex 1.44706 0.937144 2.48508 + vertex 1.45197 0.937604 2.4847 + vertex 1.4507 0.941148 2.48603 + endloop + endfacet + facet normal 0.105554 -0.315389 0.943074 + outer loop + vertex 1.4507 0.941148 2.48603 + vertex 1.45197 0.937604 2.4847 + vertex 1.45539 0.941743 2.4857 + endloop + endfacet + facet normal 0.106162 -0.321333 0.940997 + outer loop + vertex 1.45539 0.941743 2.4857 + vertex 1.45426 0.945144 2.48699 + vertex 1.4507 0.941148 2.48603 + endloop + endfacet + facet normal 0.108922 -0.320413 0.940995 + outer loop + vertex 1.4587 0.945427 2.48657 + vertex 1.45426 0.945144 2.48699 + vertex 1.45539 0.941743 2.4857 + endloop + endfacet + facet normal 0.108958 -0.320442 0.940981 + outer loop + vertex 1.45921 0.942634 2.48556 + vertex 1.4587 0.945427 2.48657 + vertex 1.45539 0.941743 2.4857 + endloop + endfacet + facet normal 0.108225 -0.31711 0.942193 + outer loop + vertex 1.45921 0.942634 2.48556 + vertex 1.45539 0.941743 2.4857 + vertex 1.45774 0.938624 2.48438 + endloop + endfacet + facet normal 0.110072 -0.317671 0.94179 + outer loop + vertex 1.45921 0.942634 2.48556 + vertex 1.45774 0.938624 2.48438 + vertex 1.46259 0.942408 2.48509 + endloop + endfacet + facet normal 0.109829 -0.319842 0.941084 + outer loop + vertex 1.46259 0.942408 2.48509 + vertex 1.46189 0.945093 2.48608 + vertex 1.45921 0.942634 2.48556 + endloop + endfacet + facet normal 0.109716 -0.319872 0.941087 + outer loop + vertex 1.46189 0.945093 2.48608 + vertex 1.46259 0.942408 2.48509 + vertex 1.46568 0.946154 2.486 + endloop + endfacet + facet normal 0.109862 -0.320412 0.940886 + outer loop + vertex 1.46568 0.946154 2.486 + vertex 1.46351 0.948978 2.48722 + vertex 1.46189 0.945093 2.48608 + endloop + endfacet + facet normal 0.11014 -0.320509 0.940821 + outer loop + vertex 1.46189 0.945093 2.48608 + vertex 1.46351 0.948978 2.48722 + vertex 1.4587 0.945427 2.48657 + endloop + endfacet + facet normal 0.110896 -0.321456 0.940408 + outer loop + vertex 1.46351 0.948978 2.48722 + vertex 1.45835 0.949216 2.48791 + vertex 1.4587 0.945427 2.48657 + endloop + endfacet + facet normal 0.111098 -0.319213 0.941148 + outer loop + vertex 1.46351 0.948978 2.48722 + vertex 1.46303 0.9535 2.48881 + vertex 1.45835 0.949216 2.48791 + endloop + endfacet + facet normal 0.1124 -0.320508 0.940553 + outer loop + vertex 1.45835 0.949216 2.48791 + vertex 1.46303 0.9535 2.48881 + vertex 1.45767 0.953612 2.48949 + endloop + endfacet + facet normal 0.110492 -0.320843 0.940665 + outer loop + vertex 1.45835 0.949216 2.48791 + vertex 1.45767 0.953612 2.48949 + vertex 1.45329 0.948891 2.48839 + endloop + endfacet + facet normal 0.110564 -0.323142 0.93987 + outer loop + vertex 1.45426 0.945144 2.48699 + vertex 1.45835 0.949216 2.48791 + vertex 1.45329 0.948891 2.48839 + endloop + endfacet + facet normal 0.107016 -0.324094 0.939952 + outer loop + vertex 1.45426 0.945144 2.48699 + vertex 1.45329 0.948891 2.48839 + vertex 1.44938 0.944642 2.48737 + endloop + endfacet + facet normal 0.108648 -0.325436 0.939301 + outer loop + vertex 1.44938 0.944642 2.48737 + vertex 1.45329 0.948891 2.48839 + vertex 1.44816 0.948395 2.48881 + endloop + endfacet + facet normal 0.112191 -0.322262 0.939979 + outer loop + vertex 1.45329 0.948891 2.48839 + vertex 1.45767 0.953612 2.48949 + vertex 1.45211 0.952529 2.48978 + endloop + endfacet + facet normal 0.111939 -0.319102 0.941087 + outer loop + vertex 1.46351 0.948978 2.48722 + vertex 1.46833 0.953728 2.48825 + vertex 1.46303 0.9535 2.48881 + endloop + endfacet + facet normal 0.111912 -0.315579 0.942277 + outer loop + vertex 1.46833 0.953728 2.48825 + vertex 1.46786 0.958263 2.48983 + vertex 1.46303 0.9535 2.48881 + endloop + endfacet + facet normal 0.11283 -0.316427 0.941883 + outer loop + vertex 1.46303 0.9535 2.48881 + vertex 1.46786 0.958263 2.48983 + vertex 1.46258 0.957319 2.49014 + endloop + endfacet + facet normal 0.110416 -0.317698 0.941741 + outer loop + vertex 1.46883 0.949901 2.48691 + vertex 1.46833 0.953728 2.48825 + vertex 1.46351 0.948978 2.48722 + endloop + endfacet + facet normal 0.113107 -0.317287 0.94156 + outer loop + vertex 1.4737 0.953628 2.48758 + vertex 1.46833 0.953728 2.48825 + vertex 1.46883 0.949901 2.48691 + endloop + endfacet + facet normal 0.111232 -0.31501 0.942548 + outer loop + vertex 1.47216 0.949679 2.48644 + vertex 1.4737 0.953628 2.48758 + vertex 1.46883 0.949901 2.48691 + endloop + endfacet + facet normal 0.110819 -0.318694 0.941357 + outer loop + vertex 1.47216 0.949679 2.48644 + vertex 1.46883 0.949901 2.48691 + vertex 1.46947 0.947216 2.48592 + endloop + endfacet + facet normal 0.109663 -0.318984 0.941394 + outer loop + vertex 1.46947 0.947216 2.48592 + vertex 1.46883 0.949901 2.48691 + vertex 1.46568 0.946154 2.486 + endloop + endfacet + facet normal 0.11016 -0.32081 0.940715 + outer loop + vertex 1.46947 0.947216 2.48592 + vertex 1.46568 0.946154 2.486 + vertex 1.4679 0.94336 2.48479 + endloop + endfacet + facet normal 0.111854 -0.321385 0.940319 + outer loop + vertex 1.46947 0.947216 2.48592 + vertex 1.4679 0.94336 2.48479 + vertex 1.47264 0.946922 2.48544 + endloop + endfacet + facet normal 0.11206 -0.319932 0.94079 + outer loop + vertex 1.47264 0.946922 2.48544 + vertex 1.47216 0.949679 2.48644 + vertex 1.46947 0.947216 2.48592 + endloop + endfacet + facet normal 0.114544 -0.319447 0.940656 + outer loop + vertex 1.47216 0.949679 2.48644 + vertex 1.47264 0.946922 2.48544 + vertex 1.47595 0.950644 2.4863 + endloop + endfacet + facet normal 0.113749 -0.318812 0.940968 + outer loop + vertex 1.47264 0.946922 2.48544 + vertex 1.4772 0.947373 2.48504 + vertex 1.47595 0.950644 2.4863 + endloop + endfacet + facet normal 0.116281 -0.317853 0.940983 + outer loop + vertex 1.47595 0.950644 2.4863 + vertex 1.4772 0.947373 2.48504 + vertex 1.48056 0.951453 2.48601 + endloop + endfacet + facet normal 0.115591 -0.313335 0.942582 + outer loop + vertex 1.48056 0.951453 2.48601 + vertex 1.47928 0.954741 2.48726 + vertex 1.47595 0.950644 2.4863 + endloop + endfacet + facet normal 0.116364 -0.313897 0.942299 + outer loop + vertex 1.47928 0.954741 2.48726 + vertex 1.4737 0.953628 2.48758 + vertex 1.47595 0.950644 2.4863 + endloop + endfacet + facet normal 0.115813 -0.310828 0.943384 + outer loop + vertex 1.47928 0.954741 2.48726 + vertex 1.4782 0.958558 2.48865 + vertex 1.4737 0.953628 2.48758 + endloop + endfacet + facet normal 0.119053 -0.313501 0.942095 + outer loop + vertex 1.4737 0.953628 2.48758 + vertex 1.4782 0.958558 2.48865 + vertex 1.47301 0.958083 2.48915 + endloop + endfacet + facet normal 0.120551 -0.30944 0.943247 + outer loop + vertex 1.47928 0.954741 2.48726 + vertex 1.48339 0.959018 2.48813 + vertex 1.4782 0.958558 2.48865 + endloop + endfacet + facet normal 0.120172 -0.302653 0.945494 + outer loop + vertex 1.48339 0.959018 2.48813 + vertex 1.48267 0.963523 2.48967 + vertex 1.4782 0.958558 2.48865 + endloop + endfacet + facet normal 0.125493 -0.307014 0.943395 + outer loop + vertex 1.4782 0.958558 2.48865 + vertex 1.48267 0.963523 2.48967 + vertex 1.47715 0.962363 2.49003 + endloop + endfacet + facet normal 0.117254 -0.312689 0.942591 + outer loop + vertex 1.48384 0.955171 2.48683 + vertex 1.47928 0.954741 2.48726 + vertex 1.48056 0.951453 2.48601 + endloop + endfacet + facet normal 0.114718 -0.316702 0.941562 + outer loop + vertex 1.4772 0.947373 2.48504 + vertex 1.48272 0.94842 2.48472 + vertex 1.48056 0.951453 2.48601 + endloop + endfacet + facet normal 0.115163 -0.319342 0.940616 + outer loop + vertex 1.47822 0.943577 2.48363 + vertex 1.48272 0.94842 2.48472 + vertex 1.4772 0.947373 2.48504 + endloop + endfacet + facet normal 0.112918 -0.31997 0.940675 + outer loop + vertex 1.47822 0.943577 2.48363 + vertex 1.4772 0.947373 2.48504 + vertex 1.47304 0.94316 2.48411 + endloop + endfacet + facet normal 0.112953 -0.320705 0.94042 + outer loop + vertex 1.47373 0.938728 2.48252 + vertex 1.47822 0.943577 2.48363 + vertex 1.47304 0.94316 2.48411 + endloop + endfacet + facet normal 0.111787 -0.320912 0.940489 + outer loop + vertex 1.47373 0.938728 2.48252 + vertex 1.47304 0.94316 2.48411 + vertex 1.46855 0.938972 2.48322 + endloop + endfacet + facet normal 0.111865 -0.320061 0.94077 + outer loop + vertex 1.47373 0.938728 2.48252 + vertex 1.46855 0.938972 2.48322 + vertex 1.469 0.93518 2.48187 + endloop + endfacet + facet normal 0.113478 -0.31983 0.940655 + outer loop + vertex 1.469 0.93518 2.48187 + vertex 1.46855 0.938972 2.48322 + vertex 1.4644 0.934779 2.48229 + endloop + endfacet + facet normal 0.111674 -0.320802 0.94054 + outer loop + vertex 1.46855 0.938972 2.48322 + vertex 1.47304 0.94316 2.48411 + vertex 1.4679 0.94336 2.48479 + endloop + endfacet + facet normal 0.11226 -0.320702 0.940504 + outer loop + vertex 1.46855 0.938972 2.48322 + vertex 1.4679 0.94336 2.48479 + vertex 1.4633 0.938643 2.48373 + endloop + endfacet + facet normal 0.110337 -0.319011 0.941307 + outer loop + vertex 1.4633 0.938643 2.48373 + vertex 1.4679 0.94336 2.48479 + vertex 1.46259 0.942408 2.48509 + endloop + endfacet + facet normal 0.114053 -0.318412 0.941066 + outer loop + vertex 1.48343 0.943994 2.48314 + vertex 1.48272 0.94842 2.48472 + vertex 1.47822 0.943577 2.48363 + endloop + endfacet + facet normal 0.114098 -0.319359 0.94074 + outer loop + vertex 1.47929 0.939783 2.48221 + vertex 1.48343 0.943994 2.48314 + vertex 1.47822 0.943577 2.48363 + endloop + endfacet + facet normal 0.113888 -0.320836 0.940263 + outer loop + vertex 1.47304 0.94316 2.48411 + vertex 1.4772 0.947373 2.48504 + vertex 1.47264 0.946922 2.48544 + endloop + endfacet + facet normal 0.111647 -0.321129 0.940431 + outer loop + vertex 1.47264 0.946922 2.48544 + vertex 1.4679 0.94336 2.48479 + vertex 1.47304 0.94316 2.48411 + endloop + endfacet + facet normal 0.113663 -0.3158 0.941993 + outer loop + vertex 1.47595 0.950644 2.4863 + vertex 1.4737 0.953628 2.48758 + vertex 1.47216 0.949679 2.48644 + endloop + endfacet + facet normal 0.113272 -0.314535 0.942463 + outer loop + vertex 1.4737 0.953628 2.48758 + vertex 1.47301 0.958083 2.48915 + vertex 1.46833 0.953728 2.48825 + endloop + endfacet + facet normal 0.110735 -0.319787 0.940996 + outer loop + vertex 1.46883 0.949901 2.48691 + vertex 1.46351 0.948978 2.48722 + vertex 1.46568 0.946154 2.486 + endloop + endfacet + facet normal 0.110575 -0.320506 0.940771 + outer loop + vertex 1.46259 0.942408 2.48509 + vertex 1.4679 0.94336 2.48479 + vertex 1.46568 0.946154 2.486 + endloop + endfacet + facet normal 0.110188 -0.320198 0.940921 + outer loop + vertex 1.46189 0.945093 2.48608 + vertex 1.4587 0.945427 2.48657 + vertex 1.45921 0.942634 2.48556 + endloop + endfacet + facet normal 0.108962 -0.321687 0.940555 + outer loop + vertex 1.4587 0.945427 2.48657 + vertex 1.45835 0.949216 2.48791 + vertex 1.45426 0.945144 2.48699 + endloop + endfacet + facet normal 0.106849 -0.321881 0.940731 + outer loop + vertex 1.45426 0.945144 2.48699 + vertex 1.44938 0.944642 2.48737 + vertex 1.4507 0.941148 2.48603 + endloop + endfacet + facet normal 0.105968 -0.32631 0.939304 + outer loop + vertex 1.44938 0.944642 2.48737 + vertex 1.44816 0.948395 2.48881 + vertex 1.44376 0.94368 2.48767 + endloop + endfacet + facet normal 0.101106 -0.316464 0.943201 + outer loop + vertex 1.4427 0.936929 2.48548 + vertex 1.44706 0.937144 2.48508 + vertex 1.44605 0.940584 2.48634 + endloop + endfacet + facet normal 0.100964 -0.309013 0.945683 + outer loop + vertex 1.4429 0.933155 2.48422 + vertex 1.44706 0.937144 2.48508 + vertex 1.4427 0.936929 2.48548 + endloop + endfacet + facet normal 0.102718 -0.308873 0.94554 + outer loop + vertex 1.4427 0.936929 2.48548 + vertex 1.43792 0.93339 2.48484 + vertex 1.4429 0.933155 2.48422 + endloop + endfacet + facet normal 0.109854 -0.322665 0.940117 + outer loop + vertex 1.4423 0.93974 2.48647 + vertex 1.43893 0.939965 2.48694 + vertex 1.4396 0.937288 2.48594 + endloop + endfacet + facet normal 0.108366 -0.314931 0.942908 + outer loop + vertex 1.43265 0.932418 2.48512 + vertex 1.43792 0.93339 2.48484 + vertex 1.43579 0.936202 2.48602 + endloop + endfacet + facet normal 0.108532 -0.315939 0.942551 + outer loop + vertex 1.43327 0.928631 2.48378 + vertex 1.43792 0.93339 2.48484 + vertex 1.43265 0.932418 2.48512 + endloop + endfacet + facet normal 0.105933 -0.316418 0.942686 + outer loop + vertex 1.43265 0.932418 2.48512 + vertex 1.42779 0.928646 2.4844 + vertex 1.43327 0.928631 2.48378 + endloop + endfacet + facet normal 0.102131 -0.310267 0.945147 + outer loop + vertex 1.43848 0.928998 2.48334 + vertex 1.43792 0.93339 2.48484 + vertex 1.43327 0.928631 2.48378 + endloop + endfacet + facet normal 0.109831 -0.317581 0.941849 + outer loop + vertex 1.43199 0.935108 2.48611 + vertex 1.42878 0.935426 2.48659 + vertex 1.42928 0.932628 2.48558 + endloop + endfacet + facet normal 0.10279 -0.317986 0.942507 + outer loop + vertex 1.42546 0.93173 2.48571 + vertex 1.4243 0.935128 2.48699 + vertex 1.42075 0.931112 2.48602 + endloop + endfacet + facet normal 0.103176 -0.321554 0.941253 + outer loop + vertex 1.42075 0.931112 2.48602 + vertex 1.42209 0.927642 2.48469 + vertex 1.42546 0.93173 2.48571 + endloop + endfacet + facet normal 0.100263 -0.322657 0.94119 + outer loop + vertex 1.41718 0.927135 2.48504 + vertex 1.42209 0.927642 2.48469 + vertex 1.42075 0.931112 2.48602 + endloop + endfacet + facet normal 0.0999085 -0.322372 0.941326 + outer loop + vertex 1.41609 0.930529 2.48631 + vertex 1.41718 0.927135 2.48504 + vertex 1.42075 0.931112 2.48602 + endloop + endfacet + facet normal 0.0993742 -0.317192 0.94314 + outer loop + vertex 1.42075 0.931112 2.48602 + vertex 1.4194 0.934594 2.48733 + vertex 1.41609 0.930529 2.48631 + endloop + endfacet + facet normal 0.0991067 -0.316998 0.943234 + outer loop + vertex 1.4194 0.934594 2.48733 + vertex 1.41387 0.933629 2.48759 + vertex 1.41609 0.930529 2.48631 + endloop + endfacet + facet normal 0.0986045 -0.313824 0.944347 + outer loop + vertex 1.4194 0.934594 2.48733 + vertex 1.41815 0.93832 2.4887 + vertex 1.41387 0.933629 2.48759 + endloop + endfacet + facet normal 0.0993464 -0.313577 0.944352 + outer loop + vertex 1.4194 0.934594 2.48733 + vertex 1.42329 0.938898 2.48835 + vertex 1.41815 0.93832 2.4887 + endloop + endfacet + facet normal 0.099373 -0.313875 0.94425 + outer loop + vertex 1.42329 0.938898 2.48835 + vertex 1.42205 0.942618 2.48972 + vertex 1.41815 0.93832 2.4887 + endloop + endfacet + facet normal 0.0985987 -0.313241 0.944542 + outer loop + vertex 1.41815 0.93832 2.4887 + vertex 1.42205 0.942618 2.48972 + vertex 1.41717 0.942091 2.49005 + endloop + endfacet + facet normal 0.100864 -0.314812 0.94378 + outer loop + vertex 1.4243 0.935128 2.48699 + vertex 1.42329 0.938898 2.48835 + vertex 1.4194 0.934594 2.48733 + endloop + endfacet + facet normal 0.098375 -0.32286 0.94132 + outer loop + vertex 1.41278 0.926915 2.48542 + vertex 1.41718 0.927135 2.48504 + vertex 1.41609 0.930529 2.48631 + endloop + endfacet + facet normal 0.0984808 -0.328236 0.939448 + outer loop + vertex 1.41307 0.923149 2.48407 + vertex 1.41718 0.927135 2.48504 + vertex 1.41278 0.926915 2.48542 + endloop + endfacet + facet normal 0.101013 -0.316572 0.943175 + outer loop + vertex 1.4243 0.935128 2.48699 + vertex 1.4194 0.934594 2.48733 + vertex 1.42075 0.931112 2.48602 + endloop + endfacet + facet normal 0.102738 -0.314297 0.943749 + outer loop + vertex 1.4243 0.935128 2.48699 + vertex 1.42838 0.939211 2.4879 + vertex 1.42329 0.938898 2.48835 + endloop + endfacet + facet normal 0.103041 -0.315983 0.943153 + outer loop + vertex 1.42838 0.939211 2.4879 + vertex 1.43288 0.943366 2.4888 + vertex 1.42764 0.943626 2.48946 + endloop + endfacet + facet normal 0.102793 -0.316029 0.943165 + outer loop + vertex 1.42838 0.939211 2.4879 + vertex 1.42764 0.943626 2.48946 + vertex 1.42329 0.938898 2.48835 + endloop + endfacet + facet normal 0.111524 -0.325037 0.939102 + outer loop + vertex 1.43893 0.939965 2.48694 + vertex 1.43821 0.943698 2.48831 + vertex 1.43356 0.938988 2.48724 + endloop + endfacet + facet normal 0.102529 -0.318967 0.942204 + outer loop + vertex 1.43288 0.943366 2.4888 + vertex 1.43712 0.947545 2.48976 + vertex 1.43241 0.94714 2.49013 + endloop + endfacet + facet normal 0.107768 -0.326144 0.939157 + outer loop + vertex 1.44376 0.94368 2.48767 + vertex 1.44284 0.948527 2.48946 + vertex 1.43821 0.943698 2.48831 + endloop + endfacet + facet normal 0.102552 -0.319359 0.942068 + outer loop + vertex 1.43241 0.94714 2.49013 + vertex 1.43712 0.947545 2.48976 + vertex 1.43579 0.950839 2.49102 + endloop + endfacet + facet normal 0.102067 -0.317873 0.942623 + outer loop + vertex 1.44386 0.955312 2.49166 + vertex 1.43921 0.954907 2.49202 + vertex 1.44054 0.951617 2.49077 + endloop + endfacet + facet normal 0.100921 -0.319006 0.942364 + outer loop + vertex 1.43579 0.950839 2.49102 + vertex 1.43358 0.953875 2.49228 + vertex 1.43193 0.949941 2.49113 + endloop + endfacet + facet normal 0.100652 -0.3178 0.9428 + outer loop + vertex 1.43193 0.949941 2.49113 + vertex 1.43241 0.94714 2.49013 + vertex 1.43579 0.950839 2.49102 + endloop + endfacet + facet normal 0.102774 -0.318932 0.942189 + outer loop + vertex 1.43241 0.94714 2.49013 + vertex 1.42764 0.943626 2.48946 + vertex 1.43288 0.943366 2.4888 + endloop + endfacet + facet normal 0.100544 -0.318201 0.942677 + outer loop + vertex 1.42921 0.947541 2.49061 + vertex 1.42879 0.950365 2.49161 + vertex 1.42543 0.946708 2.49073 + endloop + endfacet + facet normal 0.0999609 -0.313681 0.944252 + outer loop + vertex 1.42329 0.938898 2.48835 + vertex 1.42764 0.943626 2.48946 + vertex 1.42205 0.942618 2.48972 + endloop + endfacet + facet normal 0.0988226 -0.315894 0.943634 + outer loop + vertex 1.41717 0.942091 2.49005 + vertex 1.42205 0.942618 2.48972 + vertex 1.42075 0.946099 2.49102 + endloop + endfacet + facet normal 0.101157 -0.318705 0.942441 + outer loop + vertex 1.42879 0.950365 2.49161 + vertex 1.42434 0.95011 2.492 + vertex 1.42543 0.946708 2.49073 + endloop + endfacet + facet normal 0.100778 -0.322236 0.94128 + outer loop + vertex 1.42434 0.95011 2.492 + vertex 1.42337 0.953871 2.49339 + vertex 1.41943 0.949597 2.49235 + endloop + endfacet + facet normal 0.101101 -0.322504 0.941154 + outer loop + vertex 1.41943 0.949597 2.49235 + vertex 1.42337 0.953871 2.49339 + vertex 1.41821 0.953383 2.49378 + endloop + endfacet + facet normal 0.100189 -0.322795 0.941151 + outer loop + vertex 1.41943 0.949597 2.49235 + vertex 1.41821 0.953383 2.49378 + vertex 1.41383 0.948674 2.49263 + endloop + endfacet + facet normal 0.100282 -0.315494 0.943614 + outer loop + vertex 1.41278 0.941863 2.49044 + vertex 1.41237 0.944707 2.49143 + vertex 1.40969 0.942312 2.49092 + endloop + endfacet + facet normal 0.0988446 -0.315912 0.943626 + outer loop + vertex 1.41608 0.945513 2.49131 + vertex 1.41717 0.942091 2.49005 + vertex 1.42075 0.946099 2.49102 + endloop + endfacet + facet normal 0.0989795 -0.313139 0.944535 + outer loop + vertex 1.41815 0.93832 2.4887 + vertex 1.41717 0.942091 2.49005 + vertex 1.41313 0.938056 2.48914 + endloop + endfacet + facet normal 0.100812 -0.312761 0.944467 + outer loop + vertex 1.40969 0.942312 2.49092 + vertex 1.40802 0.938372 2.48979 + vertex 1.41278 0.941863 2.49044 + endloop + endfacet + facet normal 0.0990031 -0.314152 0.944196 + outer loop + vertex 1.41387 0.933629 2.48759 + vertex 1.41815 0.93832 2.4887 + vertex 1.41313 0.938056 2.48914 + endloop + endfacet + facet normal 0.0979344 -0.317778 0.943094 + outer loop + vertex 1.41609 0.930529 2.48631 + vertex 1.41387 0.933629 2.48759 + vertex 1.41237 0.929735 2.48643 + endloop + endfacet + facet normal 0.100222 -0.324492 0.940564 + outer loop + vertex 1.40918 0.930159 2.48691 + vertex 1.40449 0.929755 2.48727 + vertex 1.40581 0.926482 2.486 + endloop + endfacet + facet normal 0.104617 -0.326608 0.939352 + outer loop + vertex 1.40106 0.925691 2.48624 + vertex 1.39883 0.928713 2.48754 + vertex 1.39723 0.924783 2.48635 + endloop + endfacet + facet normal 0.102476 -0.320715 0.941616 + outer loop + vertex 1.40449 0.929755 2.48727 + vertex 1.40868 0.933932 2.48824 + vertex 1.40342 0.933548 2.48868 + endloop + endfacet + facet normal 0.10734 -0.317634 0.942118 + outer loop + vertex 1.39817 0.933133 2.48913 + vertex 1.40242 0.937344 2.49007 + vertex 1.39782 0.936893 2.49044 + endloop + endfacet + facet normal 0.107044 -0.313424 0.943561 + outer loop + vertex 1.39782 0.936893 2.49044 + vertex 1.40242 0.937344 2.49007 + vertex 1.40117 0.940631 2.4913 + endloop + endfacet + facet normal 0.102973 -0.315731 0.943245 + outer loop + vertex 1.40918 0.945118 2.49192 + vertex 1.4045 0.944705 2.49229 + vertex 1.40587 0.941424 2.49104 + endloop + endfacet + facet normal 0.106643 -0.31273 0.943837 + outer loop + vertex 1.40117 0.940631 2.4913 + vertex 1.3988 0.94369 2.49258 + vertex 1.39733 0.939672 2.49142 + endloop + endfacet + facet normal 0.102173 -0.314103 0.943875 + outer loop + vertex 1.3988 0.94369 2.49258 + vertex 1.40324 0.948469 2.49369 + vertex 1.3978 0.948625 2.49433 + endloop + endfacet + facet normal 0.103203 -0.3195 0.941949 + outer loop + vertex 1.40918 0.945118 2.49192 + vertex 1.4085 0.948858 2.49326 + vertex 1.4045 0.944705 2.49229 + endloop + endfacet + facet normal 0.0987292 -0.318388 0.942805 + outer loop + vertex 1.40324 0.948469 2.49369 + vertex 1.40724 0.952622 2.49468 + vertex 1.40253 0.952241 2.49504 + endloop + endfacet + facet normal 0.100365 -0.322505 0.941232 + outer loop + vertex 1.41383 0.948674 2.49263 + vertex 1.41289 0.953547 2.4944 + vertex 1.4085 0.948858 2.49326 + endloop + endfacet + facet normal 0.0976482 -0.319444 0.942561 + outer loop + vertex 1.41387 0.960353 2.49662 + vertex 1.40922 0.959974 2.49697 + vertex 1.41055 0.956655 2.49571 + endloop + endfacet + facet normal 0.0966138 -0.31552 0.943988 + outer loop + vertex 1.40922 0.959974 2.49697 + vertex 1.40815 0.963784 2.49835 + vertex 1.4036 0.958958 2.4972 + endloop + endfacet + facet normal 0.0968572 -0.315728 0.943893 + outer loop + vertex 1.4036 0.958958 2.4972 + vertex 1.40815 0.963784 2.49835 + vertex 1.40292 0.963307 2.49873 + endloop + endfacet + facet normal 0.0978839 -0.315551 0.943847 + outer loop + vertex 1.4036 0.958958 2.4972 + vertex 1.40292 0.963307 2.49873 + vertex 1.39847 0.959147 2.4978 + endloop + endfacet + facet normal 0.0963112 -0.307534 0.94665 + outer loop + vertex 1.40815 0.963784 2.49835 + vertex 1.40701 0.967607 2.49971 + vertex 1.40292 0.963307 2.49873 + endloop + endfacet + facet normal 0.0969755 -0.307335 0.946647 + outer loop + vertex 1.40815 0.963784 2.49835 + vertex 1.41265 0.968621 2.49946 + vertex 1.40701 0.967607 2.49971 + endloop + endfacet + facet normal 0.0972112 -0.307533 0.946559 + outer loop + vertex 1.41341 0.96417 2.49794 + vertex 1.41265 0.968621 2.49946 + vertex 1.40815 0.963784 2.49835 + endloop + endfacet + facet normal 0.0975741 -0.315248 0.94398 + outer loop + vertex 1.40922 0.959974 2.49697 + vertex 1.41341 0.96417 2.49794 + vertex 1.40815 0.963784 2.49835 + endloop + endfacet + facet normal 0.0988403 -0.320446 0.942096 + outer loop + vertex 1.40253 0.952241 2.49504 + vertex 1.40724 0.952622 2.49468 + vertex 1.40581 0.955923 2.49595 + endloop + endfacet + facet normal 0.101928 -0.317739 0.942684 + outer loop + vertex 1.40253 0.952241 2.49504 + vertex 1.3978 0.948625 2.49433 + vertex 1.40324 0.948469 2.49369 + endloop + endfacet + facet normal 0.104433 -0.3133 0.943895 + outer loop + vertex 1.39211 0.947662 2.49464 + vertex 1.3978 0.948625 2.49433 + vertex 1.39546 0.951763 2.49563 + endloop + endfacet + facet normal 0.0989669 -0.319079 0.942547 + outer loop + vertex 1.40196 0.955059 2.49605 + vertex 1.39878 0.955453 2.49652 + vertex 1.39927 0.952651 2.49552 + endloop + endfacet + facet normal 0.104692 -0.316412 0.942827 + outer loop + vertex 1.39546 0.951763 2.49563 + vertex 1.39421 0.955055 2.49688 + vertex 1.39077 0.950994 2.4959 + endloop + endfacet + facet normal 0.105765 -0.317226 0.942434 + outer loop + vertex 1.39421 0.955055 2.49688 + vertex 1.38864 0.954017 2.49715 + vertex 1.39077 0.950994 2.4959 + endloop + endfacet + facet normal 0.0976829 -0.318229 0.942968 + outer loop + vertex 1.4036 0.958958 2.4972 + vertex 1.39847 0.959147 2.4978 + vertex 1.39878 0.955453 2.49652 + endloop + endfacet + facet normal 0.0960814 -0.313795 0.944617 + outer loop + vertex 1.39847 0.959147 2.4978 + vertex 1.40292 0.963307 2.49873 + vertex 1.39796 0.963143 2.49918 + endloop + endfacet + facet normal 0.0960545 -0.30613 0.947131 + outer loop + vertex 1.40292 0.963307 2.49873 + vertex 1.4021 0.967097 2.50004 + vertex 1.39796 0.963143 2.49918 + endloop + endfacet + facet normal 0.0946421 -0.304778 0.94771 + outer loop + vertex 1.39796 0.963143 2.49918 + vertex 1.4021 0.967097 2.50004 + vertex 1.39772 0.966876 2.5004 + endloop + endfacet + facet normal 0.105382 -0.314954 0.943238 + outer loop + vertex 1.39421 0.955055 2.49688 + vertex 1.39338 0.95889 2.49825 + vertex 1.38864 0.954017 2.49715 + endloop + endfacet + facet normal 0.109336 -0.314867 0.942817 + outer loop + vertex 1.39077 0.950994 2.4959 + vertex 1.38864 0.954017 2.49715 + vertex 1.38695 0.950083 2.49603 + endloop + endfacet + facet normal 0.108364 -0.310559 0.944357 + outer loop + vertex 1.38695 0.950083 2.49603 + vertex 1.38745 0.947272 2.49505 + vertex 1.39077 0.950994 2.4959 + endloop + endfacet + facet normal 0.117463 -0.307293 0.944338 + outer loop + vertex 1.38745 0.947272 2.49505 + vertex 1.38273 0.943674 2.49447 + vertex 1.38794 0.943434 2.49374 + endloop + endfacet + facet normal 0.123486 -0.310788 0.942423 + outer loop + vertex 1.38427 0.947646 2.49556 + vertex 1.38382 0.950425 2.49654 + vertex 1.38053 0.946699 2.49574 + endloop + endfacet + facet normal 0.126125 -0.308835 0.942716 + outer loop + vertex 1.37827 0.938764 2.49346 + vertex 1.38273 0.943674 2.49447 + vertex 1.37723 0.94258 2.49485 + endloop + endfacet + facet normal 0.122816 -0.310253 0.942687 + outer loop + vertex 1.38382 0.950425 2.49654 + vertex 1.37931 0.949955 2.49697 + vertex 1.38053 0.946699 2.49574 + endloop + endfacet + facet normal 0.128538 -0.30898 0.942343 + outer loop + vertex 1.37931 0.949955 2.49697 + vertex 1.37845 0.95381 2.49835 + vertex 1.37378 0.948829 2.49735 + endloop + endfacet + facet normal 0.131814 -0.305239 0.943109 + outer loop + vertex 1.37272 0.942077 2.49531 + vertex 1.37723 0.94258 2.49485 + vertex 1.37597 0.945844 2.49608 + endloop + endfacet + facet normal 0.13592 -0.307233 0.941878 + outer loop + vertex 1.37272 0.942077 2.49531 + vertex 1.36802 0.938403 2.49479 + vertex 1.37311 0.938278 2.49402 + endloop + endfacet + facet normal 0.137845 -0.305646 0.942114 + outer loop + vertex 1.36283 0.937363 2.49522 + vertex 1.36802 0.938403 2.49479 + vertex 1.36591 0.941194 2.49601 + endloop + endfacet + facet normal 0.134258 -0.303936 0.943185 + outer loop + vertex 1.37223 0.944837 2.49628 + vertex 1.36896 0.945015 2.4968 + vertex 1.36961 0.94233 2.49584 + endloop + endfacet + facet normal 0.131393 -0.303543 0.943715 + outer loop + vertex 1.37378 0.948829 2.49735 + vertex 1.36844 0.948894 2.49812 + vertex 1.36896 0.945015 2.4968 + endloop + endfacet + facet normal 0.136378 -0.301814 0.943562 + outer loop + vertex 1.36591 0.941194 2.49601 + vertex 1.36369 0.943969 2.49722 + vertex 1.36218 0.940016 2.49617 + endloop + endfacet + facet normal 0.137441 -0.305352 0.942269 + outer loop + vertex 1.36218 0.940016 2.49617 + vertex 1.36283 0.937363 2.49522 + vertex 1.36591 0.941194 2.49601 + endloop + endfacet + facet normal 0.140583 -0.310021 0.940278 + outer loop + vertex 1.36283 0.937363 2.49522 + vertex 1.35796 0.933522 2.49468 + vertex 1.36326 0.93353 2.49389 + endloop + endfacet + facet normal 0.138214 -0.303419 0.94278 + outer loop + vertex 1.35954 0.937454 2.49573 + vertex 1.35887 0.940113 2.49668 + vertex 1.3558 0.936273 2.4959 + endloop + endfacet + facet normal 0.140559 -0.30511 0.941887 + outer loop + vertex 1.35887 0.940113 2.49668 + vertex 1.35361 0.939048 2.49712 + vertex 1.3558 0.936273 2.4959 + endloop + endfacet + facet normal 0.144616 -0.311486 0.939182 + outer loop + vertex 1.35843 0.928968 2.49309 + vertex 1.35796 0.933522 2.49468 + vertex 1.35315 0.9286 2.49379 + endloop + endfacet + facet normal 0.14591 -0.308735 0.93989 + outer loop + vertex 1.34835 0.924024 2.49303 + vertex 1.35315 0.9286 2.49379 + vertex 1.34787 0.928598 2.4946 + endloop + endfacet + facet normal 0.146183 -0.306812 0.940477 + outer loop + vertex 1.34944 0.932543 2.49565 + vertex 1.34573 0.931361 2.49584 + vertex 1.34787 0.928598 2.4946 + endloop + endfacet + facet normal 0.141794 -0.306488 0.941254 + outer loop + vertex 1.35208 0.935097 2.49607 + vertex 1.35271 0.932443 2.49511 + vertex 1.3558 0.936273 2.4959 + endloop + endfacet + facet normal 0.146066 -0.306422 0.940622 + outer loop + vertex 1.34944 0.932543 2.49565 + vertex 1.3488 0.935197 2.49661 + vertex 1.34573 0.931361 2.49584 + endloop + endfacet + facet normal 0.141232 -0.304606 0.941949 + outer loop + vertex 1.3558 0.936273 2.4959 + vertex 1.35361 0.939048 2.49712 + vertex 1.35208 0.935097 2.49607 + endloop + endfacet + facet normal 0.148048 -0.306059 0.940431 + outer loop + vertex 1.3488 0.935197 2.49661 + vertex 1.34832 0.939063 2.49794 + vertex 1.34358 0.934115 2.49708 + endloop + endfacet + facet normal 0.139825 -0.30089 0.943353 + outer loop + vertex 1.35887 0.940113 2.49668 + vertex 1.35835 0.944003 2.498 + vertex 1.35361 0.939048 2.49712 + endloop + endfacet + facet normal 0.148068 -0.304595 0.940903 + outer loop + vertex 1.34832 0.939063 2.49794 + vertex 1.35307 0.943677 2.49869 + vertex 1.3478 0.943684 2.49952 + endloop + endfacet + facet normal 0.147914 -0.296579 0.943484 + outer loop + vertex 1.35195 0.950264 2.50096 + vertex 1.3487 0.950302 2.50148 + vertex 1.34933 0.947674 2.50055 + endloop + endfacet + facet normal 0.147992 -0.295297 0.943874 + outer loop + vertex 1.35195 0.950264 2.50096 + vertex 1.35353 0.954181 2.50193 + vertex 1.3487 0.950302 2.50148 + endloop + endfacet + facet normal 0.151313 -0.300779 0.941613 + outer loop + vertex 1.3426 0.942571 2.5 + vertex 1.3478 0.943684 2.49952 + vertex 1.34564 0.946438 2.50075 + endloop + endfacet + facet normal 0.151883 -0.306271 0.93975 + outer loop + vertex 1.3426 0.942571 2.5 + vertex 1.33781 0.938691 2.49951 + vertex 1.34307 0.938703 2.49867 + endloop + endfacet + facet normal 0.147127 -0.297533 0.943307 + outer loop + vertex 1.34195 0.945213 2.50095 + vertex 1.33869 0.945265 2.50148 + vertex 1.33933 0.942642 2.50055 + endloop + endfacet + facet normal 0.146056 -0.291755 0.945276 + outer loop + vertex 1.33869 0.945265 2.50148 + vertex 1.33834 0.949062 2.5027 + vertex 1.33351 0.94415 2.50193 + endloop + endfacet + facet normal 0.150662 -0.303218 0.940936 + outer loop + vertex 1.33259 0.937602 2.5 + vertex 1.33781 0.938691 2.49951 + vertex 1.33563 0.941439 2.50075 + endloop + endfacet + facet normal 0.153597 -0.305001 0.939884 + outer loop + vertex 1.33259 0.937602 2.5 + vertex 1.32779 0.933724 2.49952 + vertex 1.33307 0.93373 2.49866 + endloop + endfacet + facet normal 0.154962 -0.3 0.941269 + outer loop + vertex 1.32259 0.93262 2.50003 + vertex 1.32779 0.933724 2.49952 + vertex 1.32561 0.93648 2.50076 + endloop + endfacet + facet normal 0.149871 -0.300905 0.941804 + outer loop + vertex 1.33193 0.940247 2.50095 + vertex 1.32866 0.940303 2.50149 + vertex 1.32931 0.93769 2.50055 + endloop + endfacet + facet normal 0.155015 -0.300833 0.940994 + outer loop + vertex 1.32561 0.93648 2.50076 + vertex 1.3235 0.939166 2.50197 + vertex 1.32191 0.935268 2.50098 + endloop + endfacet + facet normal 0.149883 -0.298031 0.942716 + outer loop + vertex 1.33351 0.94415 2.50193 + vertex 1.32833 0.944072 2.50273 + vertex 1.32866 0.940303 2.50149 + endloop + endfacet + facet normal 0.151646 -0.294278 0.943612 + outer loop + vertex 1.32833 0.944072 2.50273 + vertex 1.3332 0.948747 2.50341 + vertex 1.32811 0.948433 2.50413 + endloop + endfacet + facet normal 0.158498 -0.298697 0.941094 + outer loop + vertex 1.3235 0.939166 2.50197 + vertex 1.32322 0.943731 2.50346 + vertex 1.31835 0.939047 2.5028 + endloop + endfacet + facet normal 0.163248 -0.299981 0.939873 + outer loop + vertex 1.31868 0.935289 2.50154 + vertex 1.31835 0.939047 2.5028 + vertex 1.31357 0.934108 2.50205 + endloop + endfacet + facet normal 0.163189 -0.299677 0.93998 + outer loop + vertex 1.31868 0.935289 2.50154 + vertex 1.31357 0.934108 2.50205 + vertex 1.31568 0.93143 2.50083 + endloop + endfacet + facet normal 0.164261 -0.297491 0.940488 + outer loop + vertex 1.31272 0.927538 2.50012 + vertex 1.31785 0.928693 2.49958 + vertex 1.31568 0.93143 2.50083 + endloop + endfacet + facet normal 0.167012 -0.298843 0.939574 + outer loop + vertex 1.31272 0.927538 2.50012 + vertex 1.30802 0.923587 2.49969 + vertex 1.31322 0.92366 2.49879 + endloop + endfacet + facet normal 0.165585 -0.296871 0.940452 + outer loop + vertex 1.31204 0.930176 2.50107 + vertex 1.30884 0.930193 2.50164 + vertex 1.3095 0.927573 2.5007 + endloop + endfacet + facet normal 0.164162 -0.294541 0.941433 + outer loop + vertex 1.30884 0.930193 2.50164 + vertex 1.30846 0.934003 2.5029 + vertex 1.30373 0.92904 2.50217 + endloop + endfacet + facet normal 0.167668 -0.297961 0.939738 + outer loop + vertex 1.3029 0.922419 2.50024 + vertex 1.30802 0.923587 2.49969 + vertex 1.30588 0.926317 2.50094 + endloop + endfacet + facet normal 0.16924 -0.298242 0.939367 + outer loop + vertex 1.3029 0.922419 2.50024 + vertex 1.29809 0.918458 2.49985 + vertex 1.30328 0.918517 2.49893 + endloop + endfacet + facet normal 0.164467 -0.295126 0.941197 + outer loop + vertex 1.30226 0.925065 2.50119 + vertex 1.29898 0.925081 2.50177 + vertex 1.29968 0.922451 2.50082 + endloop + endfacet + facet normal 0.165405 -0.292454 0.941866 + outer loop + vertex 1.29898 0.925081 2.50177 + vertex 1.29848 0.928992 2.50307 + vertex 1.29366 0.9238 2.5023 + endloop + endfacet + facet normal 0.165631 -0.292649 0.941766 + outer loop + vertex 1.29366 0.9238 2.5023 + vertex 1.29848 0.928992 2.50307 + vertex 1.29322 0.928575 2.50386 + endloop + endfacet + facet normal 0.170161 -0.292029 0.94115 + outer loop + vertex 1.29366 0.9238 2.5023 + vertex 1.29322 0.928575 2.50386 + vertex 1.28833 0.923801 2.50327 + endloop + endfacet + facet normal 0.170092 -0.293296 0.940769 + outer loop + vertex 1.29366 0.9238 2.5023 + vertex 1.28833 0.923801 2.50327 + vertex 1.28833 0.919241 2.50184 + endloop + endfacet + facet normal 0.176423 -0.292965 0.939706 + outer loop + vertex 1.28833 0.919241 2.50184 + vertex 1.28833 0.923801 2.50327 + vertex 1.28342 0.919121 2.50273 + endloop + endfacet + facet normal 0.176471 -0.291374 0.940191 + outer loop + vertex 1.28833 0.919241 2.50184 + vertex 1.28342 0.919121 2.50273 + vertex 1.28377 0.915411 2.50151 + endloop + endfacet + facet normal 0.174916 -0.29147 0.940452 + outer loop + vertex 1.28342 0.919121 2.50273 + vertex 1.28833 0.923801 2.50327 + vertex 1.28327 0.923509 2.50412 + endloop + endfacet + facet normal 0.179257 -0.291099 0.939749 + outer loop + vertex 1.28342 0.919121 2.50273 + vertex 1.28327 0.923509 2.50412 + vertex 1.27832 0.918792 2.5036 + endloop + endfacet + facet normal 0.179224 -0.288222 0.940642 + outer loop + vertex 1.2785 0.913982 2.50209 + vertex 1.28342 0.919121 2.50273 + vertex 1.27832 0.918792 2.5036 + endloop + endfacet + facet normal 0.182053 -0.287969 0.940176 + outer loop + vertex 1.2785 0.913982 2.50209 + vertex 1.27832 0.918792 2.5036 + vertex 1.27321 0.913926 2.5031 + endloop + endfacet + facet normal 0.176987 -0.288838 0.940876 + outer loop + vertex 1.27832 0.918792 2.5036 + vertex 1.28327 0.923509 2.50412 + vertex 1.27846 0.923452 2.505 + endloop + endfacet + facet normal 0.179045 -0.288789 0.940502 + outer loop + vertex 1.27846 0.923452 2.505 + vertex 1.27306 0.918806 2.50461 + vertex 1.27832 0.918792 2.5036 + endloop + endfacet + facet normal 0.176074 -0.285469 0.942075 + outer loop + vertex 1.27464 0.922952 2.50557 + vertex 1.27306 0.918806 2.50461 + vertex 1.27846 0.923452 2.505 + endloop + endfacet + facet normal 0.176254 -0.287609 0.94139 + outer loop + vertex 1.27846 0.923452 2.505 + vertex 1.27701 0.925633 2.50594 + vertex 1.27464 0.922952 2.50557 + endloop + endfacet + facet normal 0.174508 -0.28617 0.942154 + outer loop + vertex 1.27701 0.925633 2.50594 + vertex 1.2738 0.925407 2.50647 + vertex 1.27464 0.922952 2.50557 + endloop + endfacet + facet normal 0.175635 -0.285753 0.942071 + outer loop + vertex 1.27464 0.922952 2.50557 + vertex 1.2738 0.925407 2.50647 + vertex 1.27086 0.921481 2.50582 + endloop + endfacet + facet normal 0.174491 -0.28497 0.942521 + outer loop + vertex 1.2738 0.925407 2.50647 + vertex 1.26869 0.924119 2.50702 + vertex 1.27086 0.921481 2.50582 + endloop + endfacet + facet normal 0.176089 -0.283697 0.942607 + outer loop + vertex 1.27086 0.921481 2.50582 + vertex 1.26869 0.924119 2.50702 + vertex 1.26719 0.920146 2.50611 + endloop + endfacet + facet normal 0.17452 -0.285103 0.942475 + outer loop + vertex 1.2738 0.925407 2.50647 + vertex 1.27339 0.929118 2.50767 + vertex 1.26869 0.924119 2.50702 + endloop + endfacet + facet normal 0.173458 -0.284168 0.942953 + outer loop + vertex 1.26869 0.924119 2.50702 + vertex 1.27339 0.929118 2.50767 + vertex 1.26833 0.928738 2.50848 + endloop + endfacet + facet normal 0.177459 -0.283664 0.94236 + outer loop + vertex 1.26869 0.924119 2.50702 + vertex 1.26833 0.928738 2.50848 + vertex 1.26355 0.923958 2.50794 + endloop + endfacet + facet normal 0.17748 -0.282717 0.942641 + outer loop + vertex 1.26869 0.924119 2.50702 + vertex 1.26355 0.923958 2.50794 + vertex 1.26396 0.920112 2.50671 + endloop + endfacet + facet normal 0.175629 -0.281931 0.943223 + outer loop + vertex 1.26355 0.923958 2.50794 + vertex 1.26833 0.928738 2.50848 + vertex 1.26334 0.928387 2.50931 + endloop + endfacet + facet normal 0.173496 -0.285672 0.942492 + outer loop + vertex 1.27339 0.929118 2.50767 + vertex 1.27316 0.933523 2.50904 + vertex 1.26833 0.928738 2.50848 + endloop + endfacet + facet normal 0.170996 -0.285922 0.942873 + outer loop + vertex 1.27339 0.929118 2.50767 + vertex 1.2783 0.933832 2.5082 + vertex 1.27316 0.933523 2.50904 + endloop + endfacet + facet normal 0.17272 -0.287624 0.94204 + outer loop + vertex 1.27829 0.929234 2.5068 + vertex 1.2783 0.933832 2.5082 + vertex 1.27339 0.929118 2.50767 + endloop + endfacet + facet normal 0.171639 -0.287677 0.942222 + outer loop + vertex 1.28363 0.933835 2.50724 + vertex 1.2783 0.933832 2.5082 + vertex 1.27829 0.929234 2.5068 + endloop + endfacet + facet normal 0.17417 -0.290488 0.940894 + outer loop + vertex 1.28215 0.929756 2.50625 + vertex 1.28363 0.933835 2.50724 + vertex 1.27829 0.929234 2.5068 + endloop + endfacet + facet normal 0.173968 -0.288212 0.941631 + outer loop + vertex 1.28215 0.929756 2.50625 + vertex 1.27829 0.929234 2.5068 + vertex 1.27981 0.927096 2.50587 + endloop + endfacet + facet normal 0.1753 -0.289299 0.94105 + outer loop + vertex 1.28297 0.927289 2.50534 + vertex 1.28215 0.929756 2.50625 + vertex 1.27981 0.927096 2.50587 + endloop + endfacet + facet normal 0.175289 -0.288159 0.941402 + outer loop + vertex 1.27981 0.927096 2.50587 + vertex 1.27846 0.923452 2.505 + vertex 1.28297 0.927289 2.50534 + endloop + endfacet + facet normal 0.173909 -0.289802 0.941154 + outer loop + vertex 1.28215 0.929756 2.50625 + vertex 1.28297 0.927289 2.50534 + vertex 1.28589 0.931209 2.50601 + endloop + endfacet + facet normal 0.17386 -0.289769 0.941173 + outer loop + vertex 1.28297 0.927289 2.50534 + vertex 1.28802 0.928517 2.50478 + vertex 1.28589 0.931209 2.50601 + endloop + endfacet + facet normal 0.173988 -0.290392 0.940957 + outer loop + vertex 1.28327 0.923509 2.50412 + vertex 1.28802 0.928517 2.50478 + vertex 1.28297 0.927289 2.50534 + endloop + endfacet + facet normal 0.175015 -0.287482 0.94166 + outer loop + vertex 1.27981 0.927096 2.50587 + vertex 1.27829 0.929234 2.5068 + vertex 1.27701 0.925633 2.50594 + endloop + endfacet + facet normal 0.174157 -0.290484 0.940898 + outer loop + vertex 1.28589 0.931209 2.50601 + vertex 1.28363 0.933835 2.50724 + vertex 1.28215 0.929756 2.50625 + endloop + endfacet + facet normal 0.172332 -0.291996 0.940766 + outer loop + vertex 1.28889 0.935148 2.50668 + vertex 1.28363 0.933835 2.50724 + vertex 1.28589 0.931209 2.50601 + endloop + endfacet + facet normal 0.171464 -0.290944 0.94125 + outer loop + vertex 1.28363 0.933835 2.50724 + vertex 1.28341 0.938672 2.50877 + vertex 1.2783 0.933832 2.5082 + endloop + endfacet + facet normal 0.169918 -0.29109 0.941485 + outer loop + vertex 1.28363 0.933835 2.50724 + vertex 1.28853 0.938979 2.50794 + vertex 1.28341 0.938672 2.50877 + endloop + endfacet + facet normal 0.169919 -0.291253 0.941434 + outer loop + vertex 1.28853 0.938979 2.50794 + vertex 1.28836 0.943381 2.50933 + vertex 1.28341 0.938672 2.50877 + endloop + endfacet + facet normal 0.172785 -0.285372 0.942713 + outer loop + vertex 1.27829 0.929234 2.5068 + vertex 1.27339 0.929118 2.50767 + vertex 1.2738 0.925407 2.50647 + endloop + endfacet + facet normal 0.174531 -0.287342 0.941793 + outer loop + vertex 1.27701 0.925633 2.50594 + vertex 1.27829 0.929234 2.5068 + vertex 1.2738 0.925407 2.50647 + endloop + endfacet + facet normal 0.175376 -0.288186 0.941378 + outer loop + vertex 1.27981 0.927096 2.50587 + vertex 1.27701 0.925633 2.50594 + vertex 1.27846 0.923452 2.505 + endloop + endfacet + facet normal 0.175461 -0.285275 0.942248 + outer loop + vertex 1.27464 0.922952 2.50557 + vertex 1.27086 0.921481 2.50582 + vertex 1.27306 0.918806 2.50461 + endloop + endfacet + facet normal 0.178132 -0.283148 0.942389 + outer loop + vertex 1.26783 0.917502 2.5052 + vertex 1.27306 0.918806 2.50461 + vertex 1.27086 0.921481 2.50582 + endloop + endfacet + facet normal 0.176936 -0.290018 0.940523 + outer loop + vertex 1.28297 0.927289 2.50534 + vertex 1.27846 0.923452 2.505 + vertex 1.28327 0.923509 2.50412 + endloop + endfacet + facet normal 0.174915 -0.291214 0.940531 + outer loop + vertex 1.28833 0.923801 2.50327 + vertex 1.28802 0.928517 2.50478 + vertex 1.28327 0.923509 2.50412 + endloop + endfacet + facet normal 0.166267 -0.291576 0.941986 + outer loop + vertex 1.29219 0.91973 2.50129 + vertex 1.29298 0.917257 2.50039 + vertex 1.29597 0.921149 2.50106 + endloop + endfacet + facet normal 0.171427 -0.286169 0.942719 + outer loop + vertex 1.28981 0.917097 2.5009 + vertex 1.287 0.915659 2.50098 + vertex 1.28843 0.913466 2.50005 + endloop + endfacet + facet normal 0.168063 -0.292831 0.941278 + outer loop + vertex 1.29298 0.917257 2.50039 + vertex 1.29809 0.918458 2.49985 + vertex 1.29597 0.921149 2.50106 + endloop + endfacet + facet normal 0.169389 -0.294758 0.940439 + outer loop + vertex 1.29834 0.913769 2.49833 + vertex 1.30328 0.918517 2.49893 + vertex 1.29809 0.918458 2.49985 + endloop + endfacet + facet normal 0.177214 -0.295102 0.938888 + outer loop + vertex 1.29831 0.90921 2.49691 + vertex 1.29834 0.913769 2.49833 + vertex 1.29342 0.909111 2.4978 + endloop + endfacet + facet normal 0.177331 -0.291815 0.939892 + outer loop + vertex 1.29831 0.90921 2.49691 + vertex 1.29342 0.909111 2.4978 + vertex 1.29379 0.905377 2.49657 + endloop + endfacet + facet normal 0.181873 -0.290605 0.939399 + outer loop + vertex 1.28377 0.915411 2.50151 + vertex 1.28342 0.919121 2.50273 + vertex 1.2785 0.913982 2.50209 + endloop + endfacet + facet normal 0.179999 -0.283468 0.941937 + outer loop + vertex 1.27782 0.907445 2.50024 + vertex 1.28308 0.908836 2.49965 + vertex 1.28077 0.911439 2.50088 + endloop + endfacet + facet normal 0.183062 -0.286986 0.94028 + outer loop + vertex 1.27782 0.907445 2.50024 + vertex 1.27334 0.903565 2.49993 + vertex 1.27828 0.9036 2.49898 + endloop + endfacet + facet normal 0.182834 -0.29154 0.938923 + outer loop + vertex 1.27339 0.898874 2.49846 + vertex 1.27828 0.9036 2.49898 + vertex 1.27334 0.903565 2.49993 + endloop + endfacet + facet normal 0.184907 -0.288195 0.939549 + outer loop + vertex 1.27334 0.903565 2.49993 + vertex 1.27183 0.905739 2.50089 + vertex 1.26951 0.903059 2.50052 + endloop + endfacet + facet normal 0.185195 -0.291732 0.9384 + outer loop + vertex 1.26951 0.903059 2.50052 + vertex 1.26808 0.898929 2.49952 + vertex 1.27334 0.903565 2.49993 + endloop + endfacet + facet normal 0.18535 -0.291775 0.938356 + outer loop + vertex 1.26951 0.903059 2.50052 + vertex 1.26579 0.901568 2.5008 + vertex 1.26808 0.898929 2.49952 + endloop + endfacet + facet normal 0.185595 -0.291569 0.938372 + outer loop + vertex 1.26286 0.897595 2.50014 + vertex 1.26808 0.898929 2.49952 + vertex 1.26579 0.901568 2.5008 + endloop + endfacet + facet normal 0.183704 -0.285035 0.940748 + outer loop + vertex 1.27695 0.909895 2.50115 + vertex 1.27313 0.909338 2.50173 + vertex 1.2746 0.907214 2.50079 + endloop + endfacet + facet normal 0.184236 -0.284285 0.940871 + outer loop + vertex 1.26867 0.905493 2.50144 + vertex 1.26831 0.909187 2.50262 + vertex 1.26364 0.904173 2.50202 + endloop + endfacet + facet normal 0.182202 -0.284712 0.941138 + outer loop + vertex 1.2785 0.913982 2.50209 + vertex 1.27321 0.913926 2.5031 + vertex 1.27313 0.909338 2.50173 + endloop + endfacet + facet normal 0.179257 -0.28518 0.941562 + outer loop + vertex 1.27321 0.913926 2.5031 + vertex 1.27832 0.918792 2.5036 + vertex 1.27306 0.918806 2.50461 + endloop + endfacet + facet normal 0.182012 -0.280346 0.942485 + outer loop + vertex 1.26331 0.908781 2.50348 + vertex 1.26811 0.913595 2.50398 + vertex 1.26307 0.913457 2.50492 + endloop + endfacet + facet normal 0.175217 -0.281105 0.943546 + outer loop + vertex 1.26719 0.920146 2.50611 + vertex 1.26783 0.917502 2.5052 + vertex 1.27086 0.921481 2.50582 + endloop + endfacet + facet normal 0.179188 -0.284664 0.941731 + outer loop + vertex 1.26719 0.920146 2.50611 + vertex 1.26869 0.924119 2.50702 + vertex 1.26396 0.920112 2.50671 + endloop + endfacet + facet normal 0.183534 -0.281781 0.941761 + outer loop + vertex 1.26396 0.920112 2.50671 + vertex 1.26355 0.923958 2.50794 + vertex 1.25874 0.918776 2.50733 + endloop + endfacet + facet normal 0.180465 -0.279096 0.943153 + outer loop + vertex 1.25874 0.918776 2.50733 + vertex 1.26355 0.923958 2.50794 + vertex 1.25846 0.923656 2.50883 + endloop + endfacet + facet normal 0.185299 -0.278581 0.942368 + outer loop + vertex 1.25874 0.918776 2.50733 + vertex 1.25846 0.923656 2.50883 + vertex 1.25345 0.918768 2.50837 + endloop + endfacet + facet normal 0.188041 -0.275923 0.942606 + outer loop + vertex 1.25811 0.91218 2.50551 + vertex 1.25731 0.914655 2.5064 + vertex 1.25502 0.911958 2.50606 + endloop + endfacet + facet normal 0.182319 -0.277859 0.943162 + outer loop + vertex 1.26463 0.917494 2.5058 + vertex 1.261 0.91614 2.50611 + vertex 1.26307 0.913457 2.50492 + endloop + endfacet + facet normal 0.186345 -0.279896 0.941771 + outer loop + vertex 1.26331 0.908781 2.50348 + vertex 1.26307 0.913457 2.50492 + vertex 1.25837 0.908396 2.50434 + endloop + endfacet + facet normal 0.188075 -0.277752 0.942062 + outer loop + vertex 1.25502 0.911958 2.50606 + vertex 1.25367 0.908292 2.50525 + vertex 1.25811 0.91218 2.50551 + endloop + endfacet + facet normal 0.188192 -0.283677 0.940272 + outer loop + vertex 1.25855 0.903979 2.50297 + vertex 1.25837 0.908396 2.50434 + vertex 1.25351 0.903641 2.50388 + endloop + endfacet + facet normal 0.188263 -0.289669 0.938429 + outer loop + vertex 1.25374 0.898813 2.50234 + vertex 1.25855 0.903979 2.50297 + vertex 1.25351 0.903641 2.50388 + endloop + endfacet + facet normal 0.189553 -0.289538 0.93821 + outer loop + vertex 1.25374 0.898813 2.50234 + vertex 1.25351 0.903641 2.50388 + vertex 1.24849 0.898784 2.50339 + endloop + endfacet + facet normal 0.189369 -0.292934 0.937192 + outer loop + vertex 1.25374 0.898813 2.50234 + vertex 1.24849 0.898784 2.50339 + vertex 1.24848 0.894203 2.50197 + endloop + endfacet + facet normal 0.192487 -0.292764 0.93661 + outer loop + vertex 1.24848 0.894203 2.50197 + vertex 1.24849 0.898784 2.50339 + vertex 1.2436 0.894051 2.50292 + endloop + endfacet + facet normal 0.19258 -0.289476 0.937612 + outer loop + vertex 1.24848 0.894203 2.50197 + vertex 1.2436 0.894051 2.50292 + vertex 1.24401 0.890339 2.50169 + endloop + endfacet + facet normal 0.193662 -0.290684 0.937015 + outer loop + vertex 1.24722 0.89061 2.50111 + vertex 1.24848 0.894203 2.50197 + vertex 1.24401 0.890339 2.50169 + endloop + endfacet + facet normal 0.199536 -0.288351 0.936503 + outer loop + vertex 1.24401 0.890339 2.50169 + vertex 1.2436 0.894051 2.50292 + vertex 1.23875 0.888843 2.50235 + endloop + endfacet + facet normal 0.193236 -0.282804 0.939511 + outer loop + vertex 1.23875 0.888843 2.50235 + vertex 1.2436 0.894051 2.50292 + vertex 1.23855 0.893692 2.50385 + endloop + endfacet + facet normal 0.199034 -0.282244 0.938469 + outer loop + vertex 1.23875 0.888843 2.50235 + vertex 1.23855 0.893692 2.50385 + vertex 1.23342 0.888752 2.50345 + endloop + endfacet + facet normal 0.192743 -0.275977 0.941641 + outer loop + vertex 1.23342 0.888752 2.50345 + vertex 1.23855 0.893692 2.50385 + vertex 1.23339 0.893674 2.5049 + endloop + endfacet + facet normal 0.197331 -0.27569 0.940774 + outer loop + vertex 1.23342 0.888752 2.50345 + vertex 1.23339 0.893674 2.5049 + vertex 1.22842 0.888441 2.50441 + endloop + endfacet + facet normal 0.188864 -0.26801 0.944723 + outer loop + vertex 1.22842 0.888441 2.50441 + vertex 1.23339 0.893674 2.5049 + vertex 1.2283 0.892271 2.50552 + endloop + endfacet + facet normal 0.191225 -0.278079 0.941332 + outer loop + vertex 1.2283 0.892271 2.50552 + vertex 1.23339 0.893674 2.5049 + vertex 1.23123 0.896273 2.50611 + endloop + endfacet + facet normal 0.188546 -0.280254 0.941227 + outer loop + vertex 1.23497 0.897797 2.50581 + vertex 1.23123 0.896273 2.50611 + vertex 1.23339 0.893674 2.5049 + endloop + endfacet + facet normal 0.18686 -0.279718 0.941723 + outer loop + vertex 1.23497 0.897797 2.50581 + vertex 1.23339 0.893674 2.5049 + vertex 1.2387 0.898307 2.50522 + endloop + endfacet + facet normal 0.187283 -0.284585 0.940179 + outer loop + vertex 1.2387 0.898307 2.50522 + vertex 1.23728 0.900455 2.50616 + vertex 1.23497 0.897797 2.50581 + endloop + endfacet + facet normal 0.188276 -0.285389 0.939737 + outer loop + vertex 1.23728 0.900455 2.50616 + vertex 1.23409 0.900239 2.50673 + vertex 1.23497 0.897797 2.50581 + endloop + endfacet + facet normal 0.188268 -0.284839 0.939905 + outer loop + vertex 1.23728 0.900455 2.50616 + vertex 1.23849 0.904088 2.50702 + vertex 1.23409 0.900239 2.50673 + endloop + endfacet + facet normal 0.188456 -0.285046 0.939805 + outer loop + vertex 1.23849 0.904088 2.50702 + vertex 1.23356 0.90407 2.508 + vertex 1.23409 0.900239 2.50673 + endloop + endfacet + facet normal 0.191778 -0.284424 0.939321 + outer loop + vertex 1.23409 0.900239 2.50673 + vertex 1.23356 0.90407 2.508 + vertex 1.22886 0.898829 2.50737 + endloop + endfacet + facet normal 0.19211 -0.285887 0.938809 + outer loop + vertex 1.23409 0.900239 2.50673 + vertex 1.22886 0.898829 2.50737 + vertex 1.23123 0.896273 2.50611 + endloop + endfacet + facet normal 0.192774 -0.285292 0.938854 + outer loop + vertex 1.23123 0.896273 2.50611 + vertex 1.22886 0.898829 2.50737 + vertex 1.22749 0.894707 2.5064 + endloop + endfacet + facet normal 0.199059 -0.286962 0.937032 + outer loop + vertex 1.22749 0.894707 2.5064 + vertex 1.22886 0.898829 2.50737 + vertex 1.22348 0.894005 2.50704 + endloop + endfacet + facet normal 0.198446 -0.281962 0.938678 + outer loop + vertex 1.22749 0.894707 2.5064 + vertex 1.22348 0.894005 2.50704 + vertex 1.22514 0.891962 2.50607 + endloop + endfacet + facet normal 0.200897 -0.28 0.938744 + outer loop + vertex 1.22514 0.891962 2.50607 + vertex 1.22348 0.894005 2.50704 + vertex 1.2222 0.89025 2.50619 + endloop + endfacet + facet normal 0.191975 -0.264236 0.945159 + outer loop + vertex 1.22514 0.891962 2.50607 + vertex 1.2222 0.89025 2.50619 + vertex 1.22375 0.888279 2.50533 + endloop + endfacet + facet normal 0.1951 -0.261789 0.9452 + outer loop + vertex 1.22375 0.888279 2.50533 + vertex 1.2222 0.89025 2.50619 + vertex 1.21997 0.887431 2.50587 + endloop + endfacet + facet normal 0.20564 -0.269595 0.940761 + outer loop + vertex 1.2222 0.89025 2.50619 + vertex 1.21822 0.889274 2.50678 + vertex 1.21997 0.887431 2.50587 + endloop + endfacet + facet normal 0.208055 -0.281953 0.936598 + outer loop + vertex 1.2222 0.89025 2.50619 + vertex 1.22348 0.894005 2.50704 + vertex 1.21822 0.889274 2.50678 + endloop + endfacet + facet normal 0.202504 -0.275947 0.939599 + outer loop + vertex 1.22348 0.894005 2.50704 + vertex 1.21838 0.893952 2.50812 + vertex 1.21822 0.889274 2.50678 + endloop + endfacet + facet normal 0.202095 -0.284035 0.937274 + outer loop + vertex 1.22348 0.894005 2.50704 + vertex 1.22352 0.898833 2.50849 + vertex 1.21838 0.893952 2.50812 + endloop + endfacet + facet normal 0.198882 -0.280781 0.93894 + outer loop + vertex 1.21838 0.893952 2.50812 + vertex 1.22352 0.898833 2.50849 + vertex 1.21823 0.898867 2.50962 + endloop + endfacet + facet normal 0.196608 -0.284316 0.938355 + outer loop + vertex 1.22886 0.898829 2.50737 + vertex 1.22352 0.898833 2.50849 + vertex 1.22348 0.894005 2.50704 + endloop + endfacet + facet normal 0.196596 -0.28452 0.938296 + outer loop + vertex 1.22886 0.898829 2.50737 + vertex 1.22841 0.90363 2.50892 + vertex 1.22352 0.898833 2.50849 + endloop + endfacet + facet normal 0.192593 -0.285109 0.938946 + outer loop + vertex 1.22886 0.898829 2.50737 + vertex 1.23356 0.90407 2.508 + vertex 1.22841 0.90363 2.50892 + endloop + endfacet + facet normal 0.188692 -0.280689 0.941068 + outer loop + vertex 1.23849 0.904088 2.50702 + vertex 1.23845 0.908845 2.50844 + vertex 1.23356 0.90407 2.508 + endloop + endfacet + facet normal 0.189607 -0.281586 0.940616 + outer loop + vertex 1.23356 0.90407 2.508 + vertex 1.23845 0.908845 2.50844 + vertex 1.23312 0.908906 2.50953 + endloop + endfacet + facet normal 0.186784 -0.280808 0.941413 + outer loop + vertex 1.24376 0.908744 2.50736 + vertex 1.23845 0.908845 2.50844 + vertex 1.23849 0.904088 2.50702 + endloop + endfacet + facet normal 0.184903 -0.278753 0.942395 + outer loop + vertex 1.24231 0.90458 2.50641 + vertex 1.24376 0.908744 2.50736 + vertex 1.23849 0.904088 2.50702 + endloop + endfacet + facet normal 0.185286 -0.283603 0.940871 + outer loop + vertex 1.24231 0.90458 2.50641 + vertex 1.23849 0.904088 2.50702 + vertex 1.24001 0.901903 2.50606 + endloop + endfacet + facet normal 0.186583 -0.284644 0.9403 + outer loop + vertex 1.24316 0.902153 2.50551 + vertex 1.24231 0.90458 2.50641 + vertex 1.24001 0.901903 2.50606 + endloop + endfacet + facet normal 0.186615 -0.285892 0.939915 + outer loop + vertex 1.24001 0.901903 2.50606 + vertex 1.2387 0.898307 2.50522 + vertex 1.24316 0.902153 2.50551 + endloop + endfacet + facet normal 0.188948 -0.288504 0.93865 + outer loop + vertex 1.24316 0.902153 2.50551 + vertex 1.2387 0.898307 2.50522 + vertex 1.24346 0.898431 2.50431 + endloop + endfacet + facet normal 0.189052 -0.28849 0.938634 + outer loop + vertex 1.24346 0.898431 2.50431 + vertex 1.24833 0.903593 2.50491 + vertex 1.24316 0.902153 2.50551 + endloop + endfacet + facet normal 0.188164 -0.284761 0.93995 + outer loop + vertex 1.24316 0.902153 2.50551 + vertex 1.24833 0.903593 2.50491 + vertex 1.24609 0.906141 2.50613 + endloop + endfacet + facet normal 0.189941 -0.28928 0.938211 + outer loop + vertex 1.24849 0.898784 2.50339 + vertex 1.24833 0.903593 2.50491 + vertex 1.24346 0.898431 2.50431 + endloop + endfacet + facet normal 0.189036 -0.285727 0.939482 + outer loop + vertex 1.23855 0.893692 2.50385 + vertex 1.24346 0.898431 2.50431 + vertex 1.2387 0.898307 2.50522 + endloop + endfacet + facet normal 0.187483 -0.284302 0.940225 + outer loop + vertex 1.24231 0.90458 2.50641 + vertex 1.24316 0.902153 2.50551 + vertex 1.24609 0.906141 2.50613 + endloop + endfacet + facet normal 0.185399 -0.278893 0.942256 + outer loop + vertex 1.24609 0.906141 2.50613 + vertex 1.24376 0.908744 2.50736 + vertex 1.24231 0.90458 2.50641 + endloop + endfacet + facet normal 0.186275 -0.278132 0.942308 + outer loop + vertex 1.24902 0.910165 2.50674 + vertex 1.24376 0.908744 2.50736 + vertex 1.24609 0.906141 2.50613 + endloop + endfacet + facet normal 0.187135 -0.276207 0.942704 + outer loop + vertex 1.24376 0.908744 2.50736 + vertex 1.24351 0.913664 2.50885 + vertex 1.23845 0.908845 2.50844 + endloop + endfacet + facet normal 0.187203 -0.2762 0.942692 + outer loop + vertex 1.24376 0.908744 2.50736 + vertex 1.24857 0.913962 2.50793 + vertex 1.24351 0.913664 2.50885 + endloop + endfacet + facet normal 0.184832 -0.283915 0.940866 + outer loop + vertex 1.24001 0.901903 2.50606 + vertex 1.23849 0.904088 2.50702 + vertex 1.23728 0.900455 2.50616 + endloop + endfacet + facet normal 0.185712 -0.285624 0.940176 + outer loop + vertex 1.24001 0.901903 2.50606 + vertex 1.23728 0.900455 2.50616 + vertex 1.2387 0.898307 2.50522 + endloop + endfacet + facet normal 0.190203 -0.284635 0.939577 + outer loop + vertex 1.23497 0.897797 2.50581 + vertex 1.23409 0.900239 2.50673 + vertex 1.23123 0.896273 2.50611 + endloop + endfacet + facet normal 0.192209 -0.285647 0.938862 + outer loop + vertex 1.2387 0.898307 2.50522 + vertex 1.23339 0.893674 2.5049 + vertex 1.23855 0.893692 2.50385 + endloop + endfacet + facet normal 0.193339 -0.289975 0.937302 + outer loop + vertex 1.2436 0.894051 2.50292 + vertex 1.24346 0.898431 2.50431 + vertex 1.23855 0.893692 2.50385 + endloop + endfacet + facet normal 0.189955 -0.290278 0.9379 + outer loop + vertex 1.2436 0.894051 2.50292 + vertex 1.24849 0.898784 2.50339 + vertex 1.24346 0.898431 2.50431 + endloop + endfacet + facet normal 0.189345 -0.289333 0.938315 + outer loop + vertex 1.24849 0.898784 2.50339 + vertex 1.25351 0.903641 2.50388 + vertex 1.24833 0.903593 2.50491 + endloop + endfacet + facet normal 0.188518 -0.28446 0.93997 + outer loop + vertex 1.2499 0.907724 2.50585 + vertex 1.24609 0.906141 2.50613 + vertex 1.24833 0.903593 2.50491 + endloop + endfacet + facet normal 0.190934 -0.278618 0.941231 + outer loop + vertex 1.25502 0.911958 2.50606 + vertex 1.25226 0.910451 2.50618 + vertex 1.25367 0.908292 2.50525 + endloop + endfacet + facet normal 0.185994 -0.277944 0.942419 + outer loop + vertex 1.2499 0.907724 2.50585 + vertex 1.24902 0.910165 2.50674 + vertex 1.24609 0.906141 2.50613 + endloop + endfacet + facet normal 0.189216 -0.275374 0.942532 + outer loop + vertex 1.25502 0.911958 2.50606 + vertex 1.25349 0.914102 2.507 + vertex 1.25226 0.910451 2.50618 + endloop + endfacet + facet normal 0.185486 -0.274702 0.943469 + outer loop + vertex 1.24902 0.910165 2.50674 + vertex 1.24857 0.913962 2.50793 + vertex 1.24376 0.908744 2.50736 + endloop + endfacet + facet normal 0.185467 -0.275481 0.943246 + outer loop + vertex 1.25874 0.918776 2.50733 + vertex 1.25345 0.918768 2.50837 + vertex 1.25349 0.914102 2.507 + endloop + endfacet + facet normal 0.185034 -0.270675 0.944721 + outer loop + vertex 1.24489 0.921946 2.51097 + vertex 1.24361 0.918301 2.51018 + vertex 1.2481 0.922262 2.51043 + endloop + endfacet + facet normal 0.187192 -0.274184 0.943283 + outer loop + vertex 1.24857 0.913962 2.50793 + vertex 1.24839 0.918449 2.50927 + vertex 1.24351 0.913664 2.50885 + endloop + endfacet + facet normal 0.188401 -0.277483 0.942077 + outer loop + vertex 1.23845 0.908845 2.50844 + vertex 1.24351 0.913664 2.50885 + vertex 1.23854 0.91375 2.50987 + endloop + endfacet + facet normal 0.186879 -0.271211 0.944204 + outer loop + vertex 1.24489 0.921946 2.51097 + vertex 1.242 0.920277 2.51106 + vertex 1.24361 0.918301 2.51018 + endloop + endfacet + facet normal 0.187123 -0.271644 0.944031 + outer loop + vertex 1.24489 0.921946 2.51097 + vertex 1.24328 0.923993 2.51188 + vertex 1.242 0.920277 2.51106 + endloop + endfacet + facet normal 0.184616 -0.273902 0.943872 + outer loop + vertex 1.24328 0.923993 2.51188 + vertex 1.24339 0.928778 2.51324 + vertex 1.2383 0.923919 2.51283 + endloop + endfacet + facet normal 0.182584 -0.271855 0.944859 + outer loop + vertex 1.2383 0.923919 2.51283 + vertex 1.24339 0.928778 2.51324 + vertex 1.2383 0.928493 2.51415 + endloop + endfacet + facet normal 0.18675 -0.269346 0.944763 + outer loop + vertex 1.23985 0.917549 2.51071 + vertex 1.2382 0.919461 2.51158 + vertex 1.23694 0.915868 2.51081 + endloop + endfacet + facet normal 0.18911 -0.273538 0.943088 + outer loop + vertex 1.23985 0.917549 2.51071 + vertex 1.23694 0.915868 2.51081 + vertex 1.23854 0.91375 2.50987 + endloop + endfacet + facet normal 0.189895 -0.277426 0.941793 + outer loop + vertex 1.23854 0.91375 2.50987 + vertex 1.23312 0.908906 2.50953 + vertex 1.23845 0.908845 2.50844 + endloop + endfacet + facet normal 0.188018 -0.271385 0.943928 + outer loop + vertex 1.23456 0.913096 2.51048 + vertex 1.23367 0.915493 2.51134 + vertex 1.23075 0.91148 2.51077 + endloop + endfacet + facet normal 0.192474 -0.281182 0.940154 + outer loop + vertex 1.23356 0.90407 2.508 + vertex 1.23312 0.908906 2.50953 + vertex 1.22841 0.90363 2.50892 + endloop + endfacet + facet normal 0.195701 -0.283647 0.938747 + outer loop + vertex 1.22352 0.898833 2.50849 + vertex 1.22841 0.90363 2.50892 + vertex 1.22351 0.903592 2.50993 + endloop + endfacet + facet normal 0.191996 -0.276124 0.94175 + outer loop + vertex 1.22699 0.90992 2.51108 + vertex 1.2279 0.907487 2.51018 + vertex 1.23075 0.91148 2.51077 + endloop + endfacet + facet normal 0.189677 -0.270103 0.943963 + outer loop + vertex 1.23075 0.91148 2.51077 + vertex 1.22847 0.913982 2.51195 + vertex 1.22699 0.90992 2.51108 + endloop + endfacet + facet normal 0.186724 -0.267519 0.945287 + outer loop + vertex 1.22847 0.913982 2.51195 + vertex 1.23334 0.919191 2.51246 + vertex 1.22829 0.918785 2.51334 + endloop + endfacet + facet normal 0.189807 -0.2681 0.944508 + outer loop + vertex 1.22322 0.909335 2.51168 + vertex 1.2233 0.913858 2.51294 + vertex 1.2184 0.909136 2.51259 + endloop + endfacet + facet normal 0.191732 -0.272306 0.942915 + outer loop + vertex 1.22472 0.907254 2.51077 + vertex 1.22322 0.909335 2.51168 + vertex 1.222 0.905768 2.51089 + endloop + endfacet + facet normal 0.195482 -0.27942 0.940059 + outer loop + vertex 1.22472 0.907254 2.51077 + vertex 1.222 0.905768 2.51089 + vertex 1.22351 0.903592 2.50993 + endloop + endfacet + facet normal 0.198699 -0.283471 0.93817 + outer loop + vertex 1.22351 0.903592 2.50993 + vertex 1.21823 0.898867 2.50962 + vertex 1.22352 0.898833 2.50849 + endloop + endfacet + facet normal 0.193091 -0.27567 0.941659 + outer loop + vertex 1.21971 0.903055 2.51056 + vertex 1.2188 0.905449 2.51145 + vertex 1.21594 0.901442 2.51087 + endloop + endfacet + facet normal 0.202682 -0.280451 0.938226 + outer loop + vertex 1.21838 0.893952 2.50812 + vertex 1.21823 0.898867 2.50962 + vertex 1.21332 0.893602 2.50911 + endloop + endfacet + facet normal 0.195143 -0.269283 0.943083 + outer loop + vertex 1.20989 0.897144 2.51086 + vertex 1.20858 0.893485 2.51008 + vertex 1.21305 0.897419 2.51028 + endloop + endfacet + facet normal 0.202558 -0.269722 0.941393 + outer loop + vertex 1.21326 0.889048 2.50782 + vertex 1.21838 0.893952 2.50812 + vertex 1.21332 0.893602 2.50911 + endloop + endfacet + facet normal 0.20855 -0.275789 0.938322 + outer loop + vertex 1.21822 0.889274 2.50678 + vertex 1.21838 0.893952 2.50812 + vertex 1.21326 0.889048 2.50782 + endloop + endfacet + facet normal 0.209183 -0.266295 0.940919 + outer loop + vertex 1.21997 0.887431 2.50587 + vertex 1.21822 0.889274 2.50678 + vertex 1.2169 0.885514 2.50601 + endloop + endfacet + facet normal 0.202839 -0.255808 0.945208 + outer loop + vertex 1.21997 0.887431 2.50587 + vertex 1.2169 0.885514 2.50601 + vertex 1.21862 0.883584 2.50512 + endloop + endfacet + facet normal 0.226912 -0.279824 0.93285 + outer loop + vertex 1.2147 0.882622 2.50571 + vertex 1.21177 0.88081 2.50588 + vertex 1.21353 0.878735 2.50483 + endloop + endfacet + facet normal 0.22055 -0.285164 0.932759 + outer loop + vertex 1.21353 0.878735 2.50483 + vertex 1.21177 0.88081 2.50588 + vertex 1.20953 0.877995 2.50555 + endloop + endfacet + facet normal 0.215746 -0.281596 0.934964 + outer loop + vertex 1.21177 0.88081 2.50588 + vertex 1.20857 0.880405 2.5065 + vertex 1.20953 0.877995 2.50555 + endloop + endfacet + facet normal 0.214151 -0.258118 0.94208 + outer loop + vertex 1.21177 0.88081 2.50588 + vertex 1.21305 0.884535 2.50661 + vertex 1.20857 0.880405 2.5065 + endloop + endfacet + facet normal 0.213949 -0.258061 0.942141 + outer loop + vertex 1.2147 0.882622 2.50571 + vertex 1.21305 0.884535 2.50661 + vertex 1.21177 0.88081 2.50588 + endloop + endfacet + facet normal 0.193528 -0.253052 0.947898 + outer loop + vertex 1.21997 0.887431 2.50587 + vertex 1.21862 0.883584 2.50512 + vertex 1.22375 0.888279 2.50533 + endloop + endfacet + facet normal 0.194118 -0.267574 0.943781 + outer loop + vertex 1.2283 0.892271 2.50552 + vertex 1.22375 0.888279 2.50533 + vertex 1.22842 0.888441 2.50441 + endloop + endfacet + facet normal 0.197262 -0.265485 0.943719 + outer loop + vertex 1.22825 0.883842 2.50315 + vertex 1.23342 0.888752 2.50345 + vertex 1.22842 0.888441 2.50441 + endloop + endfacet + facet normal 0.204064 -0.272446 0.940282 + outer loop + vertex 1.23322 0.883912 2.50209 + vertex 1.23342 0.888752 2.50345 + vertex 1.22825 0.883842 2.50315 + endloop + endfacet + facet normal 0.199442 -0.272527 0.94125 + outer loop + vertex 1.23875 0.888843 2.50235 + vertex 1.23342 0.888752 2.50345 + vertex 1.23322 0.883912 2.50209 + endloop + endfacet + facet normal 0.197549 -0.280065 0.939435 + outer loop + vertex 1.24401 0.890339 2.50169 + vertex 1.23875 0.888843 2.50235 + vertex 1.24108 0.886336 2.50111 + endloop + endfacet + facet normal 0.20534 -0.279029 0.938072 + outer loop + vertex 1.23815 0.882267 2.50052 + vertex 1.23726 0.88468 2.50144 + vertex 1.23488 0.881855 2.50112 + endloop + endfacet + facet normal 0.196295 -0.279223 0.939948 + outer loop + vertex 1.24487 0.887922 2.50079 + vertex 1.24401 0.890339 2.50169 + vertex 1.24108 0.886336 2.50111 + endloop + endfacet + facet normal 0.19337 -0.28037 0.940213 + outer loop + vertex 1.24722 0.89061 2.50111 + vertex 1.24401 0.890339 2.50169 + vertex 1.24487 0.887922 2.50079 + endloop + endfacet + facet normal 0.191054 -0.289953 0.937777 + outer loop + vertex 1.24999 0.892075 2.501 + vertex 1.24848 0.894203 2.50197 + vertex 1.24722 0.89061 2.50111 + endloop + endfacet + facet normal 0.189517 -0.291034 0.937754 + outer loop + vertex 1.25229 0.894734 2.50136 + vertex 1.24848 0.894203 2.50197 + vertex 1.24999 0.892075 2.501 + endloop + endfacet + facet normal 0.186088 -0.288269 0.939294 + outer loop + vertex 1.25313 0.892279 2.50044 + vertex 1.25229 0.894734 2.50136 + vertex 1.24999 0.892075 2.501 + endloop + endfacet + facet normal 0.189714 -0.293313 0.937004 + outer loop + vertex 1.25229 0.894734 2.50136 + vertex 1.25374 0.898813 2.50234 + vertex 1.24848 0.894203 2.50197 + endloop + endfacet + facet normal 0.187238 -0.288772 0.93891 + outer loop + vertex 1.25894 0.900154 2.50172 + vertex 1.25855 0.903979 2.50297 + vertex 1.25374 0.898813 2.50234 + endloop + endfacet + facet normal 0.186903 -0.289235 0.938835 + outer loop + vertex 1.26215 0.900209 2.5011 + vertex 1.26364 0.904173 2.50202 + vertex 1.25894 0.900154 2.50172 + endloop + endfacet + facet normal 0.18521 -0.288717 0.93933 + outer loop + vertex 1.26579 0.901568 2.5008 + vertex 1.26364 0.904173 2.50202 + vertex 1.26215 0.900209 2.5011 + endloop + endfacet + facet normal 0.186365 -0.292086 0.938059 + outer loop + vertex 1.26215 0.900209 2.5011 + vertex 1.26286 0.897595 2.50014 + vertex 1.26579 0.901568 2.5008 + endloop + endfacet + facet normal 0.186658 -0.289729 0.938731 + outer loop + vertex 1.25963 0.897562 2.50077 + vertex 1.256 0.896206 2.50108 + vertex 1.25817 0.893554 2.49983 + endloop + endfacet + facet normal 0.185497 -0.291109 0.938534 + outer loop + vertex 1.26334 0.893689 2.49884 + vertex 1.26808 0.898929 2.49952 + vertex 1.26286 0.897595 2.50014 + endloop + endfacet + facet normal 0.184895 -0.291406 0.938561 + outer loop + vertex 1.27334 0.903565 2.49993 + vertex 1.26808 0.898929 2.49952 + vertex 1.27339 0.898874 2.49846 + endloop + endfacet + facet normal 0.183029 -0.291731 0.938825 + outer loop + vertex 1.27872 0.898813 2.4974 + vertex 1.27828 0.9036 2.49898 + vertex 1.27339 0.898874 2.49846 + endloop + endfacet + facet normal 0.180533 -0.29692 0.937681 + outer loop + vertex 1.28398 0.900109 2.4968 + vertex 1.27872 0.898813 2.4974 + vertex 1.28103 0.896165 2.49612 + endloop + endfacet + facet normal 0.179667 -0.296335 0.938033 + outer loop + vertex 1.28468 0.897486 2.49584 + vertex 1.28398 0.900109 2.4968 + vertex 1.28103 0.896165 2.49612 + endloop + endfacet + facet normal 0.179426 -0.296408 0.938056 + outer loop + vertex 1.28722 0.900114 2.49618 + vertex 1.28398 0.900109 2.4968 + vertex 1.28468 0.897486 2.49584 + endloop + endfacet + facet normal 0.179628 -0.292827 0.939141 + outer loop + vertex 1.28722 0.900114 2.49618 + vertex 1.2887 0.904114 2.49715 + vertex 1.28398 0.900109 2.4968 + endloop + endfacet + facet normal 0.179109 -0.291558 0.939635 + outer loop + vertex 1.29379 0.905377 2.49657 + vertex 1.29342 0.909111 2.4978 + vertex 1.2887 0.904114 2.49715 + endloop + endfacet + facet normal 0.179994 -0.294831 0.938444 + outer loop + vertex 1.29698 0.905601 2.49603 + vertex 1.29831 0.90921 2.49691 + vertex 1.29379 0.905377 2.49657 + endloop + endfacet + facet normal 0.178259 -0.293391 0.939226 + outer loop + vertex 1.29979 0.907069 2.49595 + vertex 1.29698 0.905601 2.49603 + vertex 1.29842 0.903435 2.49508 + endloop + endfacet + facet normal 0.181282 -0.296821 0.937568 + outer loop + vertex 1.29461 0.902924 2.49564 + vertex 1.29086 0.901451 2.4959 + vertex 1.29308 0.898829 2.49464 + endloop + endfacet + facet normal 0.174663 -0.295596 0.93921 + outer loop + vertex 1.29831 0.898837 2.49365 + vertex 1.30325 0.903491 2.4942 + vertex 1.29842 0.903435 2.49508 + endloop + endfacet + facet normal 0.172563 -0.295842 0.939521 + outer loop + vertex 1.30833 0.903775 2.49335 + vertex 1.30809 0.908477 2.49488 + vertex 1.30325 0.903491 2.4942 + endloop + endfacet + facet normal 0.172565 -0.298804 0.938583 + outer loop + vertex 1.31368 0.903799 2.49238 + vertex 1.31327 0.908522 2.49395 + vertex 1.30833 0.903775 2.49335 + endloop + endfacet + facet normal 0.171079 -0.299001 0.938792 + outer loop + vertex 1.31368 0.903799 2.49238 + vertex 1.3185 0.908971 2.49315 + vertex 1.31327 0.908522 2.49395 + endloop + endfacet + facet normal 0.174316 -0.301796 0.937301 + outer loop + vertex 1.31901 0.905135 2.49182 + vertex 1.3185 0.908971 2.49315 + vertex 1.31368 0.903799 2.49238 + endloop + endfacet + facet normal 0.17132 -0.302324 0.937683 + outer loop + vertex 1.32373 0.909088 2.49223 + vertex 1.3185 0.908971 2.49315 + vertex 1.31901 0.905135 2.49182 + endloop + endfacet + facet normal 0.174398 -0.303711 0.936667 + outer loop + vertex 1.32226 0.905141 2.49121 + vertex 1.31901 0.905135 2.49182 + vertex 1.31968 0.902521 2.49084 + endloop + endfacet + facet normal 0.174286 -0.305697 0.936042 + outer loop + vertex 1.32226 0.905141 2.49121 + vertex 1.32373 0.909088 2.49223 + vertex 1.31901 0.905135 2.49182 + endloop + endfacet + facet normal 0.167933 -0.307603 0.936578 + outer loop + vertex 1.32885 0.910235 2.49169 + vertex 1.32838 0.914064 2.49303 + vertex 1.32373 0.909088 2.49223 + endloop + endfacet + facet normal 0.161915 -0.311227 0.936441 + outer loop + vertex 1.33208 0.910167 2.4911 + vertex 1.3336 0.914106 2.49215 + vertex 1.32885 0.910235 2.49169 + endloop + endfacet + facet normal 0.154375 -0.30505 0.939741 + outer loop + vertex 1.33208 0.910167 2.4911 + vertex 1.33273 0.907511 2.49014 + vertex 1.33576 0.911365 2.49089 + endloop + endfacet + facet normal 0.165681 -0.301379 0.939 + outer loop + vertex 1.3295 0.907594 2.49071 + vertex 1.32587 0.906377 2.49096 + vertex 1.32797 0.903621 2.4897 + endloop + endfacet + facet normal 0.156334 -0.306439 0.938965 + outer loop + vertex 1.33273 0.907511 2.49014 + vertex 1.3379 0.908612 2.48963 + vertex 1.33576 0.911365 2.49089 + endloop + endfacet + facet normal 0.157876 -0.306992 0.938526 + outer loop + vertex 1.33838 0.904031 2.48806 + vertex 1.34313 0.908647 2.48877 + vertex 1.3379 0.908612 2.48963 + endloop + endfacet + facet normal 0.157808 -0.314656 0.935996 + outer loop + vertex 1.34834 0.909051 2.48802 + vertex 1.3479 0.913599 2.48963 + vertex 1.34313 0.908647 2.48877 + endloop + endfacet + facet normal 0.154787 -0.317271 0.935618 + outer loop + vertex 1.3536 0.9091 2.48717 + vertex 1.34834 0.909051 2.48802 + vertex 1.34879 0.905246 2.48666 + endloop + endfacet + facet normal 0.15706 -0.317747 0.935077 + outer loop + vertex 1.35276 0.902555 2.48507 + vertex 1.35207 0.905193 2.48609 + vertex 1.34947 0.902627 2.48565 + endloop + endfacet + facet normal 0.150243 -0.320735 0.935177 + outer loop + vertex 1.35881 0.910192 2.48671 + vertex 1.3536 0.9091 2.48717 + vertex 1.35578 0.906377 2.48589 + endloop + endfacet + facet normal 0.145389 -0.319095 0.936504 + outer loop + vertex 1.36366 0.91402 2.48726 + vertex 1.35838 0.914009 2.48808 + vertex 1.35881 0.910192 2.48671 + endloop + endfacet + facet normal 0.147328 -0.320987 0.935554 + outer loop + vertex 1.36278 0.907478 2.48515 + vertex 1.36209 0.910101 2.48616 + vertex 1.35948 0.907556 2.4857 + endloop + endfacet + facet normal 0.146189 -0.324937 0.934369 + outer loop + vertex 1.36333 0.903743 2.48377 + vertex 1.36799 0.908582 2.48472 + vertex 1.36278 0.907478 2.48515 + endloop + endfacet + facet normal 0.143111 -0.321778 0.935937 + outer loop + vertex 1.36892 0.915098 2.48682 + vertex 1.36366 0.91402 2.48726 + vertex 1.36582 0.911284 2.48599 + endloop + endfacet + facet normal 0.139082 -0.320355 0.937032 + outer loop + vertex 1.37376 0.918893 2.4874 + vertex 1.36846 0.918902 2.48819 + vertex 1.36892 0.915098 2.48682 + endloop + endfacet + facet normal 0.141496 -0.322455 0.935949 + outer loop + vertex 1.37286 0.912372 2.48529 + vertex 1.37224 0.915007 2.48629 + vertex 1.36957 0.912466 2.48582 + endloop + endfacet + facet normal 0.13846 -0.325884 0.935216 + outer loop + vertex 1.37322 0.908591 2.48392 + vertex 1.37806 0.913386 2.48487 + vertex 1.37286 0.912372 2.48529 + endloop + endfacet + facet normal 0.136526 -0.324367 0.936027 + outer loop + vertex 1.37905 0.919946 2.487 + vertex 1.37376 0.918893 2.4874 + vertex 1.37599 0.916165 2.48613 + endloop + endfacet + facet normal 0.128804 -0.324564 0.937053 + outer loop + vertex 1.38382 0.923746 2.48766 + vertex 1.37834 0.923698 2.48839 + vertex 1.37905 0.919946 2.487 + endloop + endfacet + facet normal 0.129861 -0.323037 0.937434 + outer loop + vertex 1.38285 0.916994 2.48545 + vertex 1.38237 0.919756 2.48646 + vertex 1.37973 0.917275 2.48597 + endloop + endfacet + facet normal 0.124349 -0.325338 0.937386 + outer loop + vertex 1.38314 0.913245 2.48411 + vertex 1.38736 0.917455 2.48501 + vertex 1.38285 0.916994 2.48545 + endloop + endfacet + facet normal 0.121871 -0.328175 0.936722 + outer loop + vertex 1.38945 0.924784 2.48729 + vertex 1.38382 0.923746 2.48766 + vertex 1.38613 0.920716 2.4863 + endloop + endfacet + facet normal 0.115203 -0.326799 0.938046 + outer loop + vertex 1.39405 0.925175 2.48686 + vertex 1.39362 0.928955 2.48823 + vertex 1.38945 0.924784 2.48729 + endloop + endfacet + facet normal 0.110057 -0.328452 0.938087 + outer loop + vertex 1.39723 0.924783 2.48635 + vertex 1.39883 0.928713 2.48754 + vertex 1.39405 0.925175 2.48686 + endloop + endfacet + facet normal 0.104632 -0.326675 0.939327 + outer loop + vertex 1.39723 0.924783 2.48635 + vertex 1.39768 0.922004 2.48533 + vertex 1.40106 0.925691 2.48624 + endloop + endfacet + facet normal 0.114114 -0.325646 0.93858 + outer loop + vertex 1.39452 0.922383 2.48583 + vertex 1.39074 0.921498 2.48598 + vertex 1.39288 0.918491 2.48468 + endloop + endfacet + facet normal 0.104153 -0.326282 0.939517 + outer loop + vertex 1.39768 0.922004 2.48533 + vertex 1.40232 0.922434 2.48497 + vertex 1.40106 0.925691 2.48624 + endloop + endfacet + facet normal 0.101182 -0.330153 0.938489 + outer loop + vertex 1.40329 0.918679 2.48354 + vertex 1.40796 0.923458 2.48472 + vertex 1.40232 0.922434 2.48497 + endloop + endfacet + facet normal 0.0989607 -0.328187 0.939415 + outer loop + vertex 1.41278 0.926915 2.48542 + vertex 1.40796 0.923458 2.48472 + vertex 1.41307 0.923149 2.48407 + endloop + endfacet + facet normal 0.098213 -0.327988 0.939563 + outer loop + vertex 1.41812 0.923404 2.48364 + vertex 1.41718 0.927135 2.48504 + vertex 1.41307 0.923149 2.48407 + endloop + endfacet + facet normal 0.10063 -0.327362 0.939525 + outer loop + vertex 1.41812 0.923404 2.48364 + vertex 1.42209 0.927642 2.48469 + vertex 1.41718 0.927135 2.48504 + endloop + endfacet + facet normal 0.104158 -0.322274 0.940899 + outer loop + vertex 1.42209 0.927642 2.48469 + vertex 1.42779 0.928646 2.4844 + vertex 1.42546 0.93173 2.48571 + endloop + endfacet + facet normal 0.102433 -0.317461 0.942722 + outer loop + vertex 1.43435 0.924681 2.48233 + vertex 1.43848 0.928998 2.48334 + vertex 1.43327 0.928631 2.48378 + endloop + endfacet + facet normal 0.0971642 -0.311007 0.945428 + outer loop + vertex 1.44376 0.925359 2.48159 + vertex 1.44341 0.929108 2.48285 + vertex 1.43928 0.925126 2.48197 + endloop + endfacet + facet normal 0.102603 -0.310197 0.945119 + outer loop + vertex 1.43848 0.928998 2.48334 + vertex 1.4429 0.933155 2.48422 + vertex 1.43792 0.93339 2.48484 + endloop + endfacet + facet normal 0.100993 -0.309041 0.945671 + outer loop + vertex 1.44783 0.933264 2.48373 + vertex 1.44706 0.937144 2.48508 + vertex 1.4429 0.933155 2.48422 + endloop + endfacet + facet normal 0.109388 -0.310837 0.944148 + outer loop + vertex 1.45385 0.929872 2.48194 + vertex 1.45311 0.933661 2.48327 + vertex 1.44851 0.928889 2.48223 + endloop + endfacet + facet normal 0.111658 -0.310354 0.944041 + outer loop + vertex 1.4587 0.933711 2.48263 + vertex 1.45311 0.933661 2.48327 + vertex 1.45385 0.929872 2.48194 + endloop + endfacet + facet normal 0.102614 -0.3087 0.945608 + outer loop + vertex 1.44783 0.933264 2.48373 + vertex 1.45197 0.937604 2.4847 + vertex 1.44706 0.937144 2.48508 + endloop + endfacet + facet normal 0.108049 -0.317233 0.942172 + outer loop + vertex 1.45197 0.937604 2.4847 + vertex 1.45774 0.938624 2.48438 + vertex 1.45539 0.941743 2.4857 + endloop + endfacet + facet normal 0.111074 -0.318858 0.941272 + outer loop + vertex 1.46259 0.942408 2.48509 + vertex 1.45774 0.938624 2.48438 + vertex 1.4633 0.938643 2.48373 + endloop + endfacet + facet normal 0.112202 -0.318685 0.941197 + outer loop + vertex 1.4644 0.934779 2.48229 + vertex 1.46855 0.938972 2.48322 + vertex 1.4633 0.938643 2.48373 + endloop + endfacet + facet normal 0.113331 -0.317196 0.941564 + outer loop + vertex 1.469 0.93518 2.48187 + vertex 1.4644 0.934779 2.48229 + vertex 1.46569 0.931479 2.48102 + endloop + endfacet + facet normal 0.115427 -0.316633 0.941499 + outer loop + vertex 1.45772 0.926928 2.48047 + vertex 1.46227 0.927395 2.48007 + vertex 1.46105 0.930675 2.48132 + endloop + endfacet + facet normal 0.115912 -0.32337 0.939147 + outer loop + vertex 1.45801 0.923187 2.47914 + vertex 1.46227 0.927395 2.48007 + vertex 1.45772 0.926928 2.48047 + endloop + endfacet + facet normal 0.114137 -0.323558 0.939299 + outer loop + vertex 1.45772 0.926928 2.48047 + vertex 1.45294 0.923375 2.47983 + vertex 1.45801 0.923187 2.47914 + endloop + endfacet + facet normal 0.113063 -0.318982 0.940993 + outer loop + vertex 1.46318 0.923601 2.47867 + vertex 1.4678 0.92844 2.47976 + vertex 1.46227 0.927395 2.48007 + endloop + endfacet + facet normal 0.113142 -0.317045 0.941638 + outer loop + vertex 1.46946 0.932375 2.48087 + vertex 1.469 0.93518 2.48187 + vertex 1.46569 0.931479 2.48102 + endloop + endfacet + facet normal 0.111649 -0.317321 0.941723 + outer loop + vertex 1.47215 0.934787 2.48137 + vertex 1.469 0.93518 2.48187 + vertex 1.46946 0.932375 2.48087 + endloop + endfacet + facet normal 0.111292 -0.319353 0.941078 + outer loop + vertex 1.47215 0.934787 2.48137 + vertex 1.47373 0.938728 2.48252 + vertex 1.469 0.93518 2.48187 + endloop + endfacet + facet normal 0.112052 -0.319953 0.940784 + outer loop + vertex 1.47929 0.939783 2.48221 + vertex 1.47822 0.943577 2.48363 + vertex 1.47373 0.938728 2.48252 + endloop + endfacet + facet normal 0.114232 -0.318951 0.940862 + outer loop + vertex 1.48391 0.940225 2.4818 + vertex 1.47929 0.939783 2.48221 + vertex 1.48059 0.936513 2.48095 + endloop + endfacet + facet normal 0.114269 -0.319511 0.940667 + outer loop + vertex 1.48391 0.940225 2.4818 + vertex 1.48343 0.943994 2.48314 + vertex 1.47929 0.939783 2.48221 + endloop + endfacet + facet normal 0.115667 -0.3193 0.940568 + outer loop + vertex 1.4886 0.943775 2.48243 + vertex 1.48343 0.943994 2.48314 + vertex 1.48391 0.940225 2.4818 + endloop + endfacet + facet normal 0.112297 -0.317512 0.941581 + outer loop + vertex 1.47259 0.93199 2.48038 + vertex 1.47717 0.932426 2.47998 + vertex 1.47593 0.9357 2.48123 + endloop + endfacet + facet normal 0.115554 -0.317867 0.941067 + outer loop + vertex 1.47817 0.928633 2.47857 + vertex 1.48274 0.933497 2.47965 + vertex 1.47717 0.932426 2.47998 + endloop + endfacet + facet normal 0.11562 -0.320064 0.940314 + outer loop + vertex 1.48439 0.937438 2.48079 + vertex 1.48391 0.940225 2.4818 + vertex 1.48059 0.936513 2.48095 + endloop + endfacet + facet normal 0.116456 -0.319901 0.940267 + outer loop + vertex 1.48706 0.939855 2.48129 + vertex 1.48391 0.940225 2.4818 + vertex 1.48439 0.937438 2.48079 + endloop + endfacet + facet normal 0.116404 -0.320205 0.94017 + outer loop + vertex 1.48706 0.939855 2.48129 + vertex 1.4886 0.943775 2.48243 + vertex 1.48391 0.940225 2.4818 + endloop + endfacet + facet normal 0.116813 -0.319586 0.940329 + outer loop + vertex 1.49412 0.944829 2.4821 + vertex 1.49308 0.948615 2.48352 + vertex 1.4886 0.943775 2.48243 + endloop + endfacet + facet normal 0.118914 -0.318986 0.94027 + outer loop + vertex 1.49412 0.944829 2.4821 + vertex 1.49832 0.949088 2.48302 + vertex 1.49308 0.948615 2.48352 + endloop + endfacet + facet normal 0.118874 -0.31828 0.940514 + outer loop + vertex 1.49832 0.949088 2.48302 + vertex 1.49766 0.953518 2.4846 + vertex 1.49308 0.948615 2.48352 + endloop + endfacet + facet normal 0.117409 -0.317045 0.941115 + outer loop + vertex 1.49308 0.948615 2.48352 + vertex 1.49766 0.953518 2.4846 + vertex 1.49202 0.952388 2.48492 + endloop + endfacet + facet normal 0.116057 -0.317437 0.941151 + outer loop + vertex 1.49308 0.948615 2.48352 + vertex 1.49202 0.952388 2.48492 + vertex 1.48788 0.948191 2.48402 + endloop + endfacet + facet normal 0.116133 -0.319021 0.940606 + outer loop + vertex 1.4886 0.943775 2.48243 + vertex 1.49308 0.948615 2.48352 + vertex 1.48788 0.948191 2.48402 + endloop + endfacet + facet normal 0.115684 -0.319104 0.940633 + outer loop + vertex 1.4886 0.943775 2.48243 + vertex 1.48788 0.948191 2.48402 + vertex 1.48343 0.943994 2.48314 + endloop + endfacet + facet normal 0.114822 -0.318272 0.94102 + outer loop + vertex 1.48343 0.943994 2.48314 + vertex 1.48788 0.948191 2.48402 + vertex 1.48272 0.94842 2.48472 + endloop + endfacet + facet normal 0.123131 -0.317537 0.940217 + outer loop + vertex 1.49832 0.949088 2.48302 + vertex 1.50302 0.95347 2.48388 + vertex 1.49766 0.953518 2.4846 + endloop + endfacet + facet normal 0.12275 -0.317163 0.940393 + outer loop + vertex 1.50351 0.948946 2.48229 + vertex 1.50302 0.95347 2.48388 + vertex 1.49832 0.949088 2.48302 + endloop + endfacet + facet normal 0.12617 -0.316694 0.940099 + outer loop + vertex 1.50351 0.948946 2.48229 + vertex 1.5083 0.953752 2.48327 + vertex 1.50302 0.95347 2.48388 + endloop + endfacet + facet normal 0.126157 -0.315764 0.940413 + outer loop + vertex 1.5083 0.953752 2.48327 + vertex 1.50784 0.958276 2.48485 + vertex 1.50302 0.95347 2.48388 + endloop + endfacet + facet normal 0.12678 -0.316332 0.940139 + outer loop + vertex 1.50302 0.95347 2.48388 + vertex 1.50784 0.958276 2.48485 + vertex 1.50259 0.957288 2.48522 + endloop + endfacet + facet normal 0.117901 -0.31808 0.940704 + outer loop + vertex 1.4987 0.945301 2.48169 + vertex 1.49832 0.949088 2.48302 + vertex 1.49412 0.944829 2.4821 + endloop + endfacet + facet normal 0.117299 -0.321405 0.939649 + outer loop + vertex 1.4875 0.937063 2.48028 + vertex 1.49203 0.937495 2.47986 + vertex 1.49079 0.940758 2.48113 + endloop + endfacet + facet normal 0.117394 -0.322977 0.939098 + outer loop + vertex 1.49302 0.933719 2.47844 + vertex 1.49759 0.938609 2.47955 + vertex 1.49203 0.937495 2.47986 + endloop + endfacet + facet normal 0.117996 -0.319408 0.940242 + outer loop + vertex 1.4987 0.945301 2.48169 + vertex 1.49412 0.944829 2.4821 + vertex 1.49538 0.941567 2.48084 + endloop + endfacet + facet normal 0.122729 -0.317449 0.9403 + outer loop + vertex 1.50351 0.948946 2.48229 + vertex 1.49832 0.949088 2.48302 + vertex 1.4987 0.945301 2.48169 + endloop + endfacet + facet normal 0.126187 -0.314729 0.940756 + outer loop + vertex 1.50878 0.94994 2.48192 + vertex 1.50351 0.948946 2.48229 + vertex 1.50565 0.946142 2.48107 + endloop + endfacet + facet normal 0.121504 -0.319524 0.939756 + outer loop + vertex 1.5025 0.942352 2.4802 + vertex 1.50189 0.945031 2.48119 + vertex 1.49919 0.942543 2.48069 + endloop + endfacet + facet normal 0.125461 -0.321198 0.938665 + outer loop + vertex 1.50294 0.938544 2.47884 + vertex 1.50776 0.943342 2.47984 + vertex 1.5025 0.942352 2.4802 + endloop + endfacet + facet normal 0.123614 -0.315016 0.941002 + outer loop + vertex 1.51208 0.949758 2.48141 + vertex 1.51256 0.946997 2.48042 + vertex 1.51587 0.950746 2.48124 + endloop + endfacet + facet normal 0.127724 -0.315865 0.940168 + outer loop + vertex 1.5094 0.94726 2.48093 + vertex 1.50878 0.94994 2.48192 + vertex 1.50565 0.946142 2.48107 + endloop + endfacet + facet normal 0.124418 -0.318308 0.939787 + outer loop + vertex 1.51587 0.950746 2.48124 + vertex 1.51364 0.953697 2.48253 + vertex 1.51208 0.949758 2.48141 + endloop + endfacet + facet normal 0.126566 -0.317053 0.939925 + outer loop + vertex 1.50878 0.94994 2.48192 + vertex 1.5083 0.953752 2.48327 + vertex 1.50351 0.948946 2.48229 + endloop + endfacet + facet normal 0.121546 -0.319853 0.939639 + outer loop + vertex 1.51922 0.95482 2.48219 + vertex 1.51818 0.958584 2.48361 + vertex 1.51364 0.953697 2.48253 + endloop + endfacet + facet normal 0.123892 -0.316064 0.940614 + outer loop + vertex 1.5083 0.953752 2.48327 + vertex 1.51297 0.958119 2.48412 + vertex 1.50784 0.958276 2.48485 + endloop + endfacet + facet normal 0.124767 -0.311406 0.942051 + outer loop + vertex 1.50948 0.962192 2.48593 + vertex 1.50574 0.96109 2.48606 + vertex 1.50784 0.958276 2.48485 + endloop + endfacet + facet normal 0.116453 -0.310299 0.943479 + outer loop + vertex 1.51214 0.964672 2.4864 + vertex 1.51262 0.961902 2.48543 + vertex 1.51592 0.96563 2.48625 + endloop + endfacet + facet normal 0.123667 -0.307505 0.943476 + outer loop + vertex 1.50948 0.962192 2.48593 + vertex 1.50884 0.964884 2.48689 + vertex 1.50574 0.96109 2.48606 + endloop + endfacet + facet normal 0.115731 -0.307282 0.944555 + outer loop + vertex 1.51592 0.96563 2.48625 + vertex 1.51365 0.968631 2.4875 + vertex 1.51214 0.964672 2.4864 + endloop + endfacet + facet normal 0.114492 -0.308161 0.944419 + outer loop + vertex 1.51923 0.969727 2.48718 + vertex 1.51365 0.968631 2.4875 + vertex 1.51592 0.96563 2.48625 + endloop + endfacet + facet normal 0.1137 -0.303686 0.945964 + outer loop + vertex 1.51923 0.969727 2.48718 + vertex 1.51811 0.973574 2.48855 + vertex 1.51365 0.968631 2.4875 + endloop + endfacet + facet normal 0.113055 -0.300279 0.947128 + outer loop + vertex 1.52335 0.974018 2.48807 + vertex 1.5226 0.978546 2.48959 + vertex 1.51811 0.973574 2.48855 + endloop + endfacet + facet normal 0.116095 -0.296745 0.947874 + outer loop + vertex 1.52366 0.985321 2.4916 + vertex 1.51907 0.984839 2.49201 + vertex 1.52034 0.98155 2.49082 + endloop + endfacet + facet normal 0.118674 -0.302936 0.945593 + outer loop + vertex 1.51248 0.976961 2.49035 + vertex 1.51702 0.977412 2.48992 + vertex 1.51574 0.980706 2.49114 + endloop + endfacet + facet normal 0.118958 -0.3071 0.944213 + outer loop + vertex 1.51289 0.973124 2.48905 + vertex 1.51702 0.977412 2.48992 + vertex 1.51248 0.976961 2.49035 + endloop + endfacet + facet normal 0.114627 -0.307683 0.944559 + outer loop + vertex 1.51248 0.976961 2.49035 + vertex 1.50769 0.973355 2.48975 + vertex 1.51289 0.973124 2.48905 + endloop + endfacet + facet normal 0.109862 -0.29887 0.947949 + outer loop + vertex 1.51202 0.979776 2.49131 + vertex 1.50887 0.980157 2.4918 + vertex 1.50936 0.977341 2.49085 + endloop + endfacet + facet normal 0.104687 -0.289648 0.951391 + outer loop + vertex 1.50887 0.980157 2.4918 + vertex 1.50843 0.983941 2.493 + vertex 1.50428 0.979758 2.49218 + endloop + endfacet + facet normal 0.10359 -0.291976 0.950799 + outer loop + vertex 1.50428 0.979758 2.49218 + vertex 1.50331 0.98366 2.49348 + vertex 1.49864 0.978712 2.49247 + endloop + endfacet + facet normal 0.10832 -0.296065 0.949006 + outer loop + vertex 1.49864 0.978712 2.49247 + vertex 1.50331 0.98366 2.49348 + vertex 1.498 0.983339 2.49399 + endloop + endfacet + facet normal 0.111537 -0.295551 0.948794 + outer loop + vertex 1.49864 0.978712 2.49247 + vertex 1.498 0.983339 2.49399 + vertex 1.49322 0.97882 2.49314 + endloop + endfacet + facet normal 0.108306 -0.304665 0.946282 + outer loop + vertex 1.50209 0.972345 2.49007 + vertex 1.50769 0.973355 2.48975 + vertex 1.50556 0.976442 2.49099 + endloop + endfacet + facet normal 0.114928 -0.304222 0.945643 + outer loop + vertex 1.50828 0.968731 2.48819 + vertex 1.51289 0.973124 2.48905 + vertex 1.50769 0.973355 2.48975 + endloop + endfacet + facet normal 0.119484 -0.304213 0.945081 + outer loop + vertex 1.50884 0.964884 2.48689 + vertex 1.50828 0.968731 2.48819 + vertex 1.50356 0.963897 2.48724 + endloop + endfacet + facet normal 0.119523 -0.30445 0.945 + outer loop + vertex 1.50884 0.964884 2.48689 + vertex 1.50356 0.963897 2.48724 + vertex 1.50574 0.96109 2.48606 + endloop + endfacet + facet normal 0.125853 -0.310642 0.942159 + outer loop + vertex 1.50259 0.957288 2.48522 + vertex 1.50784 0.958276 2.48485 + vertex 1.50574 0.96109 2.48606 + endloop + endfacet + facet normal 0.123168 -0.316852 0.940444 + outer loop + vertex 1.50259 0.957288 2.48522 + vertex 1.49766 0.953518 2.4846 + vertex 1.50302 0.95347 2.48388 + endloop + endfacet + facet normal 0.116677 -0.303631 0.945619 + outer loop + vertex 1.50198 0.959972 2.48619 + vertex 1.49877 0.960231 2.48667 + vertex 1.49927 0.957465 2.48572 + endloop + endfacet + facet normal 0.111488 -0.296159 0.94861 + outer loop + vertex 1.49877 0.960231 2.48667 + vertex 1.49838 0.964011 2.48789 + vertex 1.49414 0.959777 2.48707 + endloop + endfacet + facet normal 0.110683 -0.295416 0.948935 + outer loop + vertex 1.49414 0.959777 2.48707 + vertex 1.49838 0.964011 2.48789 + vertex 1.49323 0.963724 2.48841 + endloop + endfacet + facet normal 0.116879 -0.314101 0.942168 + outer loop + vertex 1.49202 0.952388 2.48492 + vertex 1.49766 0.953518 2.4846 + vertex 1.49541 0.956473 2.48586 + endloop + endfacet + facet normal 0.116124 -0.31576 0.941706 + outer loop + vertex 1.48431 0.952354 2.48585 + vertex 1.48056 0.951453 2.48601 + vertex 1.48272 0.94842 2.48472 + endloop + endfacet + facet normal 0.114513 -0.311184 0.943425 + outer loop + vertex 1.48697 0.95477 2.48632 + vertex 1.48744 0.951961 2.48533 + vertex 1.49074 0.955667 2.48616 + endloop + endfacet + facet normal 0.115038 -0.310925 0.943447 + outer loop + vertex 1.48431 0.952354 2.48585 + vertex 1.48384 0.955171 2.48683 + vertex 1.48056 0.951453 2.48601 + endloop + endfacet + facet normal 0.112899 -0.303943 0.945977 + outer loop + vertex 1.49074 0.955667 2.48616 + vertex 1.48858 0.95877 2.48741 + vertex 1.48697 0.95477 2.48632 + endloop + endfacet + facet normal 0.116846 -0.306185 0.944774 + outer loop + vertex 1.48384 0.955171 2.48683 + vertex 1.48339 0.959018 2.48813 + vertex 1.47928 0.954741 2.48726 + endloop + endfacet + facet normal 0.12212 -0.302294 0.94536 + outer loop + vertex 1.48339 0.959018 2.48813 + vertex 1.48797 0.963436 2.48896 + vertex 1.48267 0.963523 2.48967 + endloop + endfacet + facet normal 0.111686 -0.29517 0.948895 + outer loop + vertex 1.49414 0.959777 2.48707 + vertex 1.49323 0.963724 2.48841 + vertex 1.48858 0.95877 2.48741 + endloop + endfacet + facet normal 0.118505 -0.294953 0.948135 + outer loop + vertex 1.48797 0.963436 2.48896 + vertex 1.49271 0.968296 2.48988 + vertex 1.48749 0.967331 2.49023 + endloop + endfacet + facet normal 0.122579 -0.294337 0.947808 + outer loop + vertex 1.48749 0.967331 2.49023 + vertex 1.48267 0.963523 2.48967 + vertex 1.48797 0.963436 2.48896 + endloop + endfacet + facet normal 0.110634 -0.293426 0.949559 + outer loop + vertex 1.49838 0.964011 2.48789 + vertex 1.49781 0.968132 2.48923 + vertex 1.49323 0.963724 2.48841 + endloop + endfacet + facet normal 0.108575 -0.293757 0.949694 + outer loop + vertex 1.49838 0.964011 2.48789 + vertex 1.50297 0.968419 2.48873 + vertex 1.49781 0.968132 2.48923 + endloop + endfacet + facet normal 0.118212 -0.293148 0.948731 + outer loop + vertex 1.48749 0.967331 2.49023 + vertex 1.49271 0.968296 2.48988 + vertex 1.49061 0.971152 2.49102 + endloop + endfacet + facet normal 0.12275 -0.296518 0.947106 + outer loop + vertex 1.48688 0.970043 2.49116 + vertex 1.48749 0.967331 2.49023 + vertex 1.49061 0.971152 2.49102 + endloop + endfacet + facet normal 0.112604 -0.304064 0.945973 + outer loop + vertex 1.49706 0.974725 2.49137 + vertex 1.49374 0.974951 2.49184 + vertex 1.49435 0.972242 2.4909 + endloop + endfacet + facet normal 0.112461 -0.305347 0.945577 + outer loop + vertex 1.49706 0.974725 2.49137 + vertex 1.49864 0.978712 2.49247 + vertex 1.49374 0.974951 2.49184 + endloop + endfacet + facet normal 0.123935 -0.300683 0.945637 + outer loop + vertex 1.49061 0.971152 2.49102 + vertex 1.48847 0.973964 2.49219 + vertex 1.48688 0.970043 2.49116 + endloop + endfacet + facet normal 0.111066 -0.303645 0.946289 + outer loop + vertex 1.49864 0.978712 2.49247 + vertex 1.49322 0.97882 2.49314 + vertex 1.49374 0.974951 2.49184 + endloop + endfacet + facet normal 0.123587 -0.296971 0.946855 + outer loop + vertex 1.48847 0.973964 2.49219 + vertex 1.48338 0.974052 2.49289 + vertex 1.48373 0.970286 2.49166 + endloop + endfacet + facet normal 0.124483 -0.301632 0.945263 + outer loop + vertex 1.47715 0.962363 2.49003 + vertex 1.48267 0.963523 2.48967 + vertex 1.48045 0.966499 2.49091 + endloop + endfacet + facet normal 0.118783 -0.308949 0.943632 + outer loop + vertex 1.4782 0.958558 2.48865 + vertex 1.47715 0.962363 2.49003 + vertex 1.47301 0.958083 2.48915 + endloop + endfacet + facet normal 0.114052 -0.315301 0.942113 + outer loop + vertex 1.46833 0.953728 2.48825 + vertex 1.47301 0.958083 2.48915 + vertex 1.46786 0.958263 2.48983 + endloop + endfacet + facet normal 0.111891 -0.310628 0.943923 + outer loop + vertex 1.4695 0.96217 2.49092 + vertex 1.46574 0.9611 2.49101 + vertex 1.46786 0.958263 2.48983 + endloop + endfacet + facet normal 0.12021 -0.303633 0.945175 + outer loop + vertex 1.47215 0.964655 2.4914 + vertex 1.47264 0.961875 2.49044 + vertex 1.47589 0.965636 2.49124 + endloop + endfacet + facet normal 0.109328 -0.301335 0.94723 + outer loop + vertex 1.4695 0.96217 2.49092 + vertex 1.46884 0.964895 2.49186 + vertex 1.46574 0.9611 2.49101 + endloop + endfacet + facet normal 0.118025 -0.294797 0.948243 + outer loop + vertex 1.47589 0.965636 2.49124 + vertex 1.47368 0.968692 2.49246 + vertex 1.47215 0.964655 2.4914 + endloop + endfacet + facet normal 0.112815 -0.303911 0.945997 + outer loop + vertex 1.46884 0.964895 2.49186 + vertex 1.46354 0.963964 2.4922 + vertex 1.46574 0.9611 2.49101 + endloop + endfacet + facet normal 0.111914 -0.310612 0.943925 + outer loop + vertex 1.46258 0.957319 2.49014 + vertex 1.46786 0.958263 2.48983 + vertex 1.46574 0.9611 2.49101 + endloop + endfacet + facet normal 0.112654 -0.316452 0.941896 + outer loop + vertex 1.46258 0.957319 2.49014 + vertex 1.45767 0.953612 2.48949 + vertex 1.46303 0.9535 2.48881 + endloop + endfacet + facet normal 0.112735 -0.310786 0.943771 + outer loop + vertex 1.46196 0.960016 2.49111 + vertex 1.45874 0.960307 2.49159 + vertex 1.45924 0.957526 2.49061 + endloop + endfacet + facet normal 0.112818 -0.307502 0.944836 + outer loop + vertex 1.45874 0.960307 2.49159 + vertex 1.45831 0.964161 2.4929 + vertex 1.45412 0.959857 2.492 + endloop + endfacet + facet normal 0.115295 -0.309699 0.943819 + outer loop + vertex 1.45412 0.959857 2.492 + vertex 1.45831 0.964161 2.4929 + vertex 1.45307 0.963721 2.49339 + endloop + endfacet + facet normal 0.11148 -0.318214 0.941441 + outer loop + vertex 1.45211 0.952529 2.48978 + vertex 1.45767 0.953612 2.48949 + vertex 1.45541 0.95656 2.49075 + endloop + endfacet + facet normal 0.108514 -0.323456 0.94 + outer loop + vertex 1.45329 0.948891 2.48839 + vertex 1.45211 0.952529 2.48978 + vertex 1.44816 0.948395 2.48881 + endloop + endfacet + facet normal 0.106163 -0.326472 0.939226 + outer loop + vertex 1.44376 0.94368 2.48767 + vertex 1.44816 0.948395 2.48881 + vertex 1.44284 0.948527 2.48946 + endloop + endfacet + facet normal 0.10247 -0.322718 0.940932 + outer loop + vertex 1.44437 0.952502 2.49066 + vertex 1.44054 0.951617 2.49077 + vertex 1.44284 0.948527 2.48946 + endloop + endfacet + facet normal 0.109247 -0.319393 0.941304 + outer loop + vertex 1.44703 0.954901 2.49117 + vertex 1.44755 0.952103 2.49016 + vertex 1.45078 0.955774 2.49103 + endloop + endfacet + facet normal 0.10126 -0.317222 0.94293 + outer loop + vertex 1.44437 0.952502 2.49066 + vertex 1.44386 0.955312 2.49166 + vertex 1.44054 0.951617 2.49077 + endloop + endfacet + facet normal 0.108082 -0.314075 0.943226 + outer loop + vertex 1.45078 0.955774 2.49103 + vertex 1.44859 0.958839 2.49231 + vertex 1.44703 0.954901 2.49117 + endloop + endfacet + facet normal 0.101977 -0.316387 0.943133 + outer loop + vertex 1.44386 0.955312 2.49166 + vertex 1.44341 0.959102 2.49298 + vertex 1.43921 0.954907 2.49202 + endloop + endfacet + facet normal 0.10819 -0.316721 0.942328 + outer loop + vertex 1.44341 0.959102 2.49298 + vertex 1.44789 0.963313 2.49388 + vertex 1.44272 0.963548 2.49455 + endloop + endfacet + facet normal 0.110048 -0.311171 0.943961 + outer loop + vertex 1.45412 0.959857 2.492 + vertex 1.45307 0.963721 2.49339 + vertex 1.44859 0.958839 2.49231 + endloop + endfacet + facet normal 0.115516 -0.312813 0.942764 + outer loop + vertex 1.44789 0.963313 2.49388 + vertex 1.45203 0.967561 2.49478 + vertex 1.44748 0.967117 2.49519 + endloop + endfacet + facet normal 0.115075 -0.305525 0.945205 + outer loop + vertex 1.45831 0.964161 2.4929 + vertex 1.45759 0.968701 2.49445 + vertex 1.45307 0.963721 2.49339 + endloop + endfacet + facet normal 0.113284 -0.283268 0.952327 + outer loop + vertex 1.45862 0.975441 2.4964 + vertex 1.45408 0.974942 2.4968 + vertex 1.45536 0.97169 2.49568 + endloop + endfacet + facet normal 0.109798 -0.274892 0.955185 + outer loop + vertex 1.45408 0.974942 2.4968 + vertex 1.45311 0.978815 2.49802 + vertex 1.44856 0.973879 2.49712 + endloop + endfacet + facet normal 0.11112 -0.276023 0.954706 + outer loop + vertex 1.44856 0.973879 2.49712 + vertex 1.45311 0.978815 2.49802 + vertex 1.44787 0.978451 2.49853 + endloop + endfacet + facet normal 0.105468 -0.276988 0.955068 + outer loop + vertex 1.44856 0.973879 2.49712 + vertex 1.44787 0.978451 2.49853 + vertex 1.4434 0.974067 2.49775 + endloop + endfacet + facet normal 0.114687 -0.300584 0.946835 + outer loop + vertex 1.44748 0.967117 2.49519 + vertex 1.45203 0.967561 2.49478 + vertex 1.45076 0.970842 2.49597 + endloop + endfacet + facet normal 0.108449 -0.313759 0.943289 + outer loop + vertex 1.44748 0.967117 2.49519 + vertex 1.44272 0.963548 2.49455 + vertex 1.44789 0.963313 2.49388 + endloop + endfacet + facet normal 0.104224 -0.312662 0.944129 + outer loop + vertex 1.43712 0.962495 2.49482 + vertex 1.44272 0.963548 2.49455 + vertex 1.44053 0.966575 2.49579 + endloop + endfacet + facet normal 0.104499 -0.312868 0.944031 + outer loop + vertex 1.43585 0.965786 2.49605 + vertex 1.43712 0.962495 2.49482 + vertex 1.44053 0.966575 2.49579 + endloop + endfacet + facet normal 0.103088 -0.293684 0.950328 + outer loop + vertex 1.44701 0.969917 2.49614 + vertex 1.44384 0.970286 2.4966 + vertex 1.44434 0.967491 2.49568 + endloop + endfacet + facet normal 0.102038 -0.296502 0.949566 + outer loop + vertex 1.44053 0.966575 2.49579 + vertex 1.43924 0.969882 2.49697 + vertex 1.43585 0.965786 2.49605 + endloop + endfacet + facet normal 0.10534 -0.278801 0.954554 + outer loop + vertex 1.44856 0.973879 2.49712 + vertex 1.4434 0.974067 2.49775 + vertex 1.44384 0.970286 2.4966 + endloop + endfacet + facet normal 0.108707 -0.280072 0.953804 + outer loop + vertex 1.4434 0.974067 2.49775 + vertex 1.44787 0.978451 2.49853 + vertex 1.44277 0.978192 2.49903 + endloop + endfacet + facet normal 0.10912 -0.300448 0.947536 + outer loop + vertex 1.44787 0.978451 2.49853 + vertex 1.44704 0.982403 2.49988 + vertex 1.44277 0.978192 2.49903 + endloop + endfacet + facet normal 0.111585 -0.302741 0.946518 + outer loop + vertex 1.44277 0.978192 2.49903 + vertex 1.44704 0.982403 2.49988 + vertex 1.44252 0.98199 2.50028 + endloop + endfacet + facet normal 0.102004 -0.283703 0.953472 + outer loop + vertex 1.43924 0.969882 2.49697 + vertex 1.43826 0.973818 2.49824 + vertex 1.43364 0.968889 2.49727 + endloop + endfacet + facet normal 0.10433 -0.298222 0.948778 + outer loop + vertex 1.43924 0.969882 2.49697 + vertex 1.43364 0.968889 2.49727 + vertex 1.43585 0.965786 2.49605 + endloop + endfacet + facet normal 0.105018 -0.31267 0.944038 + outer loop + vertex 1.43251 0.96207 2.49519 + vertex 1.43712 0.962495 2.49482 + vertex 1.43585 0.965786 2.49605 + endloop + endfacet + facet normal 0.104071 -0.320815 0.941407 + outer loop + vertex 1.43251 0.96207 2.49519 + vertex 1.42775 0.958553 2.49452 + vertex 1.43291 0.9583 2.49386 + endloop + endfacet + facet normal 0.102293 -0.31112 0.944849 + outer loop + vertex 1.43204 0.96488 2.49618 + vertex 1.42886 0.965286 2.49666 + vertex 1.42934 0.962458 2.49568 + endloop + endfacet + facet normal 0.101379 -0.300005 0.948535 + outer loop + vertex 1.42886 0.965286 2.49666 + vertex 1.42839 0.969154 2.49793 + vertex 1.42423 0.964894 2.49703 + endloop + endfacet + facet normal 0.104669 -0.302941 0.947244 + outer loop + vertex 1.42423 0.964894 2.49703 + vertex 1.42839 0.969154 2.49793 + vertex 1.42311 0.968744 2.49838 + endloop + endfacet + facet normal 0.102395 -0.321025 0.941519 + outer loop + vertex 1.42221 0.957541 2.49478 + vertex 1.42775 0.958553 2.49452 + vertex 1.42554 0.961575 2.49579 + endloop + endfacet + facet normal 0.101161 -0.323377 0.940847 + outer loop + vertex 1.42337 0.953871 2.49339 + vertex 1.42221 0.957541 2.49478 + vertex 1.41821 0.953383 2.49378 + endloop + endfacet + facet normal 0.0999456 -0.322592 0.941247 + outer loop + vertex 1.41383 0.948674 2.49263 + vertex 1.41821 0.953383 2.49378 + vertex 1.41289 0.953547 2.4944 + endloop + endfacet + facet normal 0.0980348 -0.322488 0.941483 + outer loop + vertex 1.41438 0.95752 2.4956 + vertex 1.41055 0.956655 2.49571 + vertex 1.41289 0.953547 2.4944 + endloop + endfacet + facet normal 0.100842 -0.320627 0.941822 + outer loop + vertex 1.41707 0.959935 2.49614 + vertex 1.4176 0.957119 2.49513 + vertex 1.42088 0.960815 2.49603 + endloop + endfacet + facet normal 0.0973208 -0.31918 0.942684 + outer loop + vertex 1.41438 0.95752 2.4956 + vertex 1.41387 0.960353 2.49662 + vertex 1.41055 0.956655 2.49571 + endloop + endfacet + facet normal 0.0994978 -0.314547 0.944013 + outer loop + vertex 1.42088 0.960815 2.49603 + vertex 1.41864 0.963891 2.4973 + vertex 1.41707 0.959935 2.49614 + endloop + endfacet + facet normal 0.0974061 -0.315096 0.944048 + outer loop + vertex 1.41387 0.960353 2.49662 + vertex 1.41341 0.96417 2.49794 + vertex 1.40922 0.959974 2.49697 + endloop + endfacet + facet normal 0.098738 -0.307247 0.946493 + outer loop + vertex 1.41341 0.96417 2.49794 + vertex 1.41787 0.968359 2.49883 + vertex 1.41265 0.968621 2.49946 + endloop + endfacet + facet normal 0.0996208 -0.304436 0.947309 + outer loop + vertex 1.42423 0.964894 2.49703 + vertex 1.42311 0.968744 2.49838 + vertex 1.41864 0.963891 2.4973 + endloop + endfacet + facet normal 0.10414 -0.29242 0.950603 + outer loop + vertex 1.42839 0.969154 2.49793 + vertex 1.42759 0.973644 2.4994 + vertex 1.42311 0.968744 2.49838 + endloop + endfacet + facet normal 0.104026 -0.298665 0.948672 + outer loop + vertex 1.41787 0.968359 2.49883 + vertex 1.42196 0.97253 2.4997 + vertex 1.41735 0.972116 2.50007 + endloop + endfacet + facet normal 0.0994268 -0.299386 0.948938 + outer loop + vertex 1.41735 0.972116 2.50007 + vertex 1.41265 0.968621 2.49946 + vertex 1.41787 0.968359 2.49883 + endloop + endfacet + facet normal 0.0942458 -0.286681 0.953379 + outer loop + vertex 1.41684 0.974865 2.50097 + vertex 1.41371 0.97529 2.5014 + vertex 1.41417 0.972515 2.50052 + endloop + endfacet + facet normal 0.0921293 -0.298689 0.949893 + outer loop + vertex 1.41371 0.97529 2.5014 + vertex 1.41346 0.979096 2.50262 + vertex 1.40926 0.975071 2.50177 + endloop + endfacet + facet normal 0.0949954 -0.295369 0.950649 + outer loop + vertex 1.40701 0.967607 2.49971 + vertex 1.41265 0.968621 2.49946 + vertex 1.41039 0.971684 2.50064 + endloop + endfacet + facet normal 0.0949714 -0.306373 0.947162 + outer loop + vertex 1.40292 0.963307 2.49873 + vertex 1.40701 0.967607 2.49971 + vertex 1.4021 0.967097 2.50004 + endloop + endfacet + facet normal 0.0943838 -0.294033 0.951124 + outer loop + vertex 1.39772 0.966876 2.5004 + vertex 1.4021 0.967097 2.50004 + vertex 1.401 0.970481 2.50119 + endloop + endfacet + facet normal 0.0949466 -0.288779 0.952676 + outer loop + vertex 1.40926 0.975071 2.50177 + vertex 1.40434 0.974596 2.50211 + vertex 1.40567 0.971071 2.50091 + endloop + endfacet + facet normal 0.102466 -0.308398 0.945723 + outer loop + vertex 1.40434 0.974596 2.50211 + vertex 1.40849 0.979017 2.5031 + vertex 1.40329 0.978587 2.50353 + endloop + endfacet + facet normal 0.0950359 -0.294359 0.950958 + outer loop + vertex 1.401 0.970481 2.50119 + vertex 1.39877 0.97362 2.50239 + vertex 1.39729 0.969682 2.50132 + endloop + endfacet + facet normal 0.0950891 -0.294619 0.950872 + outer loop + vertex 1.39729 0.969682 2.50132 + vertex 1.39772 0.966876 2.5004 + vertex 1.401 0.970481 2.50119 + endloop + endfacet + facet normal 0.0969033 -0.304577 0.947546 + outer loop + vertex 1.39772 0.966876 2.5004 + vertex 1.3929 0.963391 2.49978 + vertex 1.39796 0.963143 2.49918 + endloop + endfacet + facet normal 0.0956913 -0.294607 0.950815 + outer loop + vertex 1.39463 0.96732 2.50085 + vertex 1.3941 0.970108 2.50177 + vertex 1.3908 0.966444 2.50096 + endloop + endfacet + facet normal 0.102757 -0.30847 0.945667 + outer loop + vertex 1.38812 0.958511 2.4987 + vertex 1.3929 0.963391 2.49978 + vertex 1.38732 0.962377 2.50005 + endloop + endfacet + facet normal 0.111101 -0.299037 0.947752 + outer loop + vertex 1.38278 0.961936 2.50044 + vertex 1.38732 0.962377 2.50005 + vertex 1.38611 0.965655 2.50123 + endloop + endfacet + facet normal 0.100831 -0.298835 0.948963 + outer loop + vertex 1.3941 0.970108 2.50177 + vertex 1.38946 0.969714 2.50213 + vertex 1.3908 0.966444 2.50096 + endloop + endfacet + facet normal 0.111656 -0.298068 0.947992 + outer loop + vertex 1.38611 0.965655 2.50123 + vertex 1.38383 0.96864 2.50244 + vertex 1.38232 0.964699 2.50137 + endloop + endfacet + facet normal 0.108231 -0.311441 0.944082 + outer loop + vertex 1.38946 0.969714 2.50213 + vertex 1.3936 0.973911 2.50304 + vertex 1.3884 0.973539 2.50352 + endloop + endfacet + facet normal 0.124361 -0.351543 0.927875 + outer loop + vertex 1.37977 0.977335 2.50599 + vertex 1.37798 0.973362 2.50472 + vertex 1.38292 0.977001 2.50544 + endloop + endfacet + facet normal 0.125133 -0.346935 0.929504 + outer loop + vertex 1.38292 0.977001 2.50544 + vertex 1.38248 0.979795 2.50654 + vertex 1.37977 0.977335 2.50599 + endloop + endfacet + facet normal 0.116682 -0.338561 0.933682 + outer loop + vertex 1.38248 0.979795 2.50654 + vertex 1.37909 0.980019 2.50705 + vertex 1.37977 0.977335 2.50599 + endloop + endfacet + facet normal 0.118307 -0.338131 0.933633 + outer loop + vertex 1.37977 0.977335 2.50599 + vertex 1.37909 0.980019 2.50705 + vertex 1.37594 0.976258 2.50608 + endloop + endfacet + facet normal 0.128364 -0.23122 0.964396 + outer loop + vertex 1.38248 0.979795 2.50654 + vertex 1.38348 0.98354 2.50731 + vertex 1.37909 0.980019 2.50705 + endloop + endfacet + facet normal 0.127373 -0.346522 0.929354 + outer loop + vertex 1.38248 0.979795 2.50654 + vertex 1.38292 0.977001 2.50544 + vertex 1.38627 0.980729 2.50637 + endloop + endfacet + facet normal 0.121682 -0.350567 0.928599 + outer loop + vertex 1.37977 0.977335 2.50599 + vertex 1.37594 0.976258 2.50608 + vertex 1.37798 0.973362 2.50472 + endloop + endfacet + facet normal 0.112061 -0.31202 0.943444 + outer loop + vertex 1.38383 0.96864 2.50244 + vertex 1.38316 0.973134 2.504 + vertex 1.37843 0.968756 2.50312 + endloop + endfacet + facet normal 0.116953 -0.296021 0.947994 + outer loop + vertex 1.37899 0.964912 2.50185 + vertex 1.37843 0.968756 2.50312 + vertex 1.37366 0.963921 2.50219 + endloop + endfacet + facet normal 0.120397 -0.290997 0.949118 + outer loop + vertex 1.37592 0.961133 2.50105 + vertex 1.37366 0.963921 2.50219 + vertex 1.37216 0.960007 2.50118 + endloop + endfacet + facet normal 0.123079 -0.300313 0.945867 + outer loop + vertex 1.37216 0.960007 2.50118 + vertex 1.3728 0.957328 2.50025 + vertex 1.37592 0.961133 2.50105 + endloop + endfacet + facet normal 0.128301 -0.306208 0.943279 + outer loop + vertex 1.3728 0.957328 2.50025 + vertex 1.36792 0.953523 2.49968 + vertex 1.37322 0.953451 2.49893 + endloop + endfacet + facet normal 0.122634 -0.294353 0.947796 + outer loop + vertex 1.3695 0.957476 2.50073 + vertex 1.36881 0.960137 2.50165 + vertex 1.36572 0.956338 2.50087 + endloop + endfacet + facet normal 0.13277 -0.303195 0.943634 + outer loop + vertex 1.36844 0.948894 2.49812 + vertex 1.36792 0.953523 2.49968 + vertex 1.36313 0.948597 2.49877 + endloop + endfacet + facet normal 0.136287 -0.299875 0.944193 + outer loop + vertex 1.35835 0.944003 2.498 + vertex 1.36313 0.948597 2.49877 + vertex 1.35781 0.948661 2.49956 + endloop + endfacet + facet normal 0.140465 -0.297932 0.944196 + outer loop + vertex 1.35934 0.952656 2.50059 + vertex 1.35564 0.951468 2.50077 + vertex 1.35781 0.948661 2.49956 + endloop + endfacet + facet normal 0.128342 -0.29822 0.94583 + outer loop + vertex 1.36198 0.955202 2.50102 + vertex 1.36264 0.952516 2.50008 + vertex 1.36572 0.956338 2.50087 + endloop + endfacet + facet normal 0.139966 -0.296291 0.944786 + outer loop + vertex 1.35934 0.952656 2.50059 + vertex 1.35871 0.955292 2.50151 + vertex 1.35564 0.951468 2.50077 + endloop + endfacet + facet normal 0.12674 -0.292682 0.947773 + outer loop + vertex 1.36572 0.956338 2.50087 + vertex 1.36352 0.95909 2.50201 + vertex 1.36198 0.955202 2.50102 + endloop + endfacet + facet normal 0.12292 -0.287301 0.94992 + outer loop + vertex 1.36352 0.95909 2.50201 + vertex 1.36825 0.963969 2.50288 + vertex 1.36293 0.963571 2.50344 + endloop + endfacet + facet normal 0.139345 -0.289306 0.94704 + outer loop + vertex 1.35871 0.955292 2.50151 + vertex 1.35829 0.959031 2.50272 + vertex 1.35353 0.954181 2.50193 + endloop + endfacet + facet normal 0.142471 -0.282858 0.948522 + outer loop + vertex 1.34322 0.95375 2.50338 + vertex 1.3481 0.95843 2.50404 + vertex 1.34296 0.958388 2.5048 + endloop + endfacet + facet normal 0.145364 -0.282586 0.948164 + outer loop + vertex 1.34322 0.95375 2.50338 + vertex 1.34296 0.958388 2.5048 + vertex 1.33809 0.953441 2.50407 + endloop + endfacet + facet normal 0.143205 -0.280597 0.949083 + outer loop + vertex 1.33809 0.953441 2.50407 + vertex 1.34296 0.958388 2.5048 + vertex 1.33782 0.957304 2.50526 + endloop + endfacet + facet normal 0.137918 -0.277733 0.950707 + outer loop + vertex 1.34458 0.962331 2.50572 + vertex 1.34087 0.961143 2.50591 + vertex 1.34296 0.958388 2.5048 + endloop + endfacet + facet normal 0.133803 -0.289917 0.947652 + outer loop + vertex 1.34723 0.964894 2.50612 + vertex 1.34782 0.962253 2.50522 + vertex 1.35093 0.966082 2.50596 + endloop + endfacet + facet normal 0.141049 -0.288106 0.947154 + outer loop + vertex 1.34458 0.962331 2.50572 + vertex 1.34391 0.964988 2.50663 + vertex 1.34087 0.961143 2.50591 + endloop + endfacet + facet normal 0.142495 -0.318451 0.937168 + outer loop + vertex 1.35093 0.966082 2.50596 + vertex 1.34881 0.968891 2.50723 + vertex 1.34723 0.964894 2.50612 + endloop + endfacet + facet normal 0.135947 -0.32311 0.936546 + outer loop + vertex 1.35408 0.969935 2.50683 + vertex 1.34881 0.968891 2.50723 + vertex 1.35093 0.966082 2.50596 + endloop + endfacet + facet normal 0.131219 -0.337954 0.93197 + outer loop + vertex 1.34881 0.968891 2.50723 + vertex 1.34844 0.973683 2.50902 + vertex 1.34346 0.968953 2.50801 + endloop + endfacet + facet normal 0.137213 -0.337261 0.931358 + outer loop + vertex 1.34881 0.968891 2.50723 + vertex 1.35373 0.973962 2.50834 + vertex 1.34844 0.973683 2.50902 + endloop + endfacet + facet normal 0.136593 -0.284883 0.94878 + outer loop + vertex 1.34391 0.964988 2.50663 + vertex 1.33863 0.963917 2.50706 + vertex 1.34087 0.961143 2.50591 + endloop + endfacet + facet normal 0.14212 -0.274654 0.950982 + outer loop + vertex 1.33782 0.957304 2.50526 + vertex 1.34296 0.958388 2.5048 + vertex 1.34087 0.961143 2.50591 + endloop + endfacet + facet normal 0.147399 -0.280149 0.948573 + outer loop + vertex 1.33782 0.957304 2.50526 + vertex 1.33298 0.95341 2.50486 + vertex 1.33809 0.953441 2.50407 + endloop + endfacet + facet normal 0.144543 -0.271756 0.951449 + outer loop + vertex 1.33719 0.959959 2.50611 + vertex 1.33389 0.96003 2.50663 + vertex 1.3346 0.957392 2.50577 + endloop + endfacet + facet normal 0.152558 -0.283704 0.946698 + outer loop + vertex 1.33389 0.96003 2.50663 + vertex 1.33331 0.963918 2.50789 + vertex 1.32868 0.958891 2.50713 + endloop + endfacet + facet normal 0.151233 -0.276902 0.948922 + outer loop + vertex 1.32787 0.952292 2.50535 + vertex 1.33298 0.95341 2.50486 + vertex 1.33092 0.956171 2.50599 + endloop + endfacet + facet normal 0.155884 -0.288552 0.944689 + outer loop + vertex 1.32787 0.952292 2.50535 + vertex 1.32304 0.948365 2.50494 + vertex 1.32811 0.948433 2.50413 + endloop + endfacet + facet normal 0.150847 -0.274553 0.949666 + outer loop + vertex 1.32727 0.954943 2.50622 + vertex 1.324 0.954989 2.50676 + vertex 1.32469 0.952347 2.50588 + endloop + endfacet + facet normal 0.150601 -0.272261 0.950365 + outer loop + vertex 1.324 0.954989 2.50676 + vertex 1.32345 0.958819 2.50794 + vertex 1.31882 0.953886 2.50726 + endloop + endfacet + facet normal 0.150357 -0.272045 0.950465 + outer loop + vertex 1.31882 0.953886 2.50726 + vertex 1.32345 0.958819 2.50794 + vertex 1.31832 0.958629 2.5087 + endloop + endfacet + facet normal 0.150496 -0.272026 0.950449 + outer loop + vertex 1.31882 0.953886 2.50726 + vertex 1.31832 0.958629 2.5087 + vertex 1.31348 0.953899 2.50811 + endloop + endfacet + facet normal 0.15654 -0.286928 0.945075 + outer loop + vertex 1.3174 0.949892 2.50634 + vertex 1.31797 0.947232 2.50544 + vertex 1.32103 0.951117 2.50611 + endloop + endfacet + facet normal 0.156046 -0.286573 0.945265 + outer loop + vertex 1.31797 0.947232 2.50544 + vertex 1.32304 0.948365 2.50494 + vertex 1.32103 0.951117 2.50611 + endloop + endfacet + facet normal 0.157638 -0.294914 0.942431 + outer loop + vertex 1.31816 0.943389 2.5042 + vertex 1.32304 0.948365 2.50494 + vertex 1.31797 0.947232 2.50544 + endloop + endfacet + facet normal 0.15775 -0.294904 0.942415 + outer loop + vertex 1.31797 0.947232 2.50544 + vertex 1.31312 0.943311 2.50502 + vertex 1.31816 0.943389 2.5042 + endloop + endfacet + facet normal 0.151359 -0.282054 0.947384 + outer loop + vertex 1.3148 0.947289 2.50598 + vertex 1.31408 0.949947 2.50689 + vertex 1.31106 0.946017 2.5062 + endloop + endfacet + facet normal 0.159176 -0.295456 0.942002 + outer loop + vertex 1.31329 0.93869 2.50354 + vertex 1.31312 0.943311 2.50502 + vertex 1.30828 0.938371 2.50429 + endloop + endfacet + facet normal 0.159023 -0.290875 0.943453 + outer loop + vertex 1.30338 0.933745 2.50369 + vertex 1.30828 0.938371 2.50429 + vertex 1.30346 0.938366 2.5051 + endloop + endfacet + facet normal 0.156505 -0.291595 0.943652 + outer loop + vertex 1.30726 0.944619 2.5064 + vertex 1.30805 0.942132 2.5055 + vertex 1.31106 0.946017 2.5062 + endloop + endfacet + facet normal 0.159395 -0.285657 0.944983 + outer loop + vertex 1.30726 0.944619 2.5064 + vertex 1.30868 0.948706 2.50739 + vertex 1.30335 0.944162 2.50692 + endloop + endfacet + facet normal 0.159941 -0.291746 0.943029 + outer loop + vertex 1.30487 0.941988 2.50598 + vertex 1.30202 0.940568 2.50603 + vertex 1.30346 0.938366 2.5051 + endloop + endfacet + facet normal 0.162384 -0.290774 0.942912 + outer loop + vertex 1.30346 0.938366 2.5051 + vertex 1.29808 0.933796 2.50462 + vertex 1.30338 0.933745 2.50369 + endloop + endfacet + facet normal 0.162372 -0.290957 0.942857 + outer loop + vertex 1.29848 0.928992 2.50307 + vertex 1.30338 0.933745 2.50369 + vertex 1.29808 0.933796 2.50462 + endloop + endfacet + facet normal 0.166787 -0.294125 0.941102 + outer loop + vertex 1.29961 0.937917 2.50562 + vertex 1.29879 0.940383 2.50654 + vertex 1.29581 0.936482 2.50585 + endloop + endfacet + facet normal 0.168197 -0.295104 0.940544 + outer loop + vertex 1.29879 0.940383 2.50654 + vertex 1.29367 0.939131 2.50706 + vertex 1.29581 0.936482 2.50585 + endloop + endfacet + facet normal 0.165564 -0.290547 0.942428 + outer loop + vertex 1.29848 0.928992 2.50307 + vertex 1.29808 0.933796 2.50462 + vertex 1.29322 0.928575 2.50386 + endloop + endfacet + facet normal 0.169905 -0.291782 0.941273 + outer loop + vertex 1.28833 0.923801 2.50327 + vertex 1.29322 0.928575 2.50386 + vertex 1.28802 0.928517 2.50478 + endloop + endfacet + facet normal 0.172629 -0.290713 0.941109 + outer loop + vertex 1.28955 0.932536 2.50574 + vertex 1.28589 0.931209 2.50601 + vertex 1.28802 0.928517 2.50478 + endloop + endfacet + facet normal 0.167816 -0.291808 0.94164 + outer loop + vertex 1.29213 0.935169 2.5061 + vertex 1.29279 0.932524 2.50516 + vertex 1.29581 0.936482 2.50585 + endloop + endfacet + facet normal 0.173282 -0.292654 0.940387 + outer loop + vertex 1.28955 0.932536 2.50574 + vertex 1.28889 0.935148 2.50668 + vertex 1.28589 0.931209 2.50601 + endloop + endfacet + facet normal 0.16876 -0.294665 0.940581 + outer loop + vertex 1.29581 0.936482 2.50585 + vertex 1.29367 0.939131 2.50706 + vertex 1.29213 0.935169 2.5061 + endloop + endfacet + facet normal 0.172658 -0.293528 0.940229 + outer loop + vertex 1.28889 0.935148 2.50668 + vertex 1.28853 0.938979 2.50794 + vertex 1.28363 0.933835 2.50724 + endloop + endfacet + facet normal 0.1686 -0.291367 0.941636 + outer loop + vertex 1.28853 0.938979 2.50794 + vertex 1.29336 0.94374 2.50855 + vertex 1.28836 0.943381 2.50933 + endloop + endfacet + facet normal 0.167797 -0.293187 0.941215 + outer loop + vertex 1.29879 0.940383 2.50654 + vertex 1.29842 0.944099 2.50776 + vertex 1.29367 0.939131 2.50706 + endloop + endfacet + facet normal 0.165146 -0.285342 0.94409 + outer loop + vertex 1.30335 0.944162 2.50692 + vertex 1.30326 0.948741 2.50832 + vertex 1.29842 0.944099 2.50776 + endloop + endfacet + facet normal 0.162099 -0.275909 0.947417 + outer loop + vertex 1.30326 0.948741 2.50832 + vertex 1.30812 0.953505 2.50887 + vertex 1.30288 0.953448 2.50975 + endloop + endfacet + facet normal 0.167117 -0.285299 0.943757 + outer loop + vertex 1.29336 0.94374 2.50855 + vertex 1.29815 0.948468 2.50913 + vertex 1.29313 0.948363 2.50999 + endloop + endfacet + facet normal 0.164732 -0.276065 0.946917 + outer loop + vertex 1.29472 0.952312 2.51086 + vertex 1.29404 0.954896 2.51173 + vertex 1.29104 0.950996 2.51112 + endloop + endfacet + facet normal 0.168456 -0.285168 0.943558 + outer loop + vertex 1.29336 0.94374 2.50855 + vertex 1.29313 0.948363 2.50999 + vertex 1.28836 0.943381 2.50933 + endloop + endfacet + facet normal 0.168028 -0.289371 0.942354 + outer loop + vertex 1.28341 0.938672 2.50877 + vertex 1.28836 0.943381 2.50933 + vertex 1.28358 0.943316 2.51017 + endloop + endfacet + facet normal 0.168953 -0.289358 0.942193 + outer loop + vertex 1.28358 0.943316 2.51017 + vertex 1.27814 0.938704 2.50973 + vertex 1.28341 0.938672 2.50877 + endloop + endfacet + facet normal 0.169005 -0.288491 0.942449 + outer loop + vertex 1.2783 0.933832 2.5082 + vertex 1.28341 0.938672 2.50877 + vertex 1.27814 0.938704 2.50973 + endloop + endfacet + facet normal 0.16429 -0.273535 0.947727 + outer loop + vertex 1.28728 0.949557 2.51135 + vertex 1.28811 0.94712 2.51051 + vertex 1.29104 0.950996 2.51112 + endloop + endfacet + facet normal 0.162853 -0.269546 0.949117 + outer loop + vertex 1.29104 0.950996 2.51112 + vertex 1.28868 0.953628 2.51227 + vertex 1.28728 0.949557 2.51135 + endloop + endfacet + facet normal 0.158506 -0.282909 0.945959 + outer loop + vertex 1.28868 0.953628 2.51227 + vertex 1.28827 0.958532 2.51381 + vertex 1.28322 0.953695 2.51321 + endloop + endfacet + facet normal 0.159789 -0.2694 0.949679 + outer loop + vertex 1.28495 0.946925 2.511 + vertex 1.28337 0.949067 2.51188 + vertex 1.28214 0.945483 2.51107 + endloop + endfacet + facet normal 0.166241 -0.282193 0.944844 + outer loop + vertex 1.28495 0.946925 2.511 + vertex 1.28214 0.945483 2.51107 + vertex 1.28358 0.943316 2.51017 + endloop + endfacet + facet normal 0.163979 -0.278698 0.946276 + outer loop + vertex 1.27976 0.942828 2.51069 + vertex 1.27889 0.945282 2.51157 + vertex 1.27596 0.941378 2.51092 + endloop + endfacet + facet normal 0.17102 -0.288326 0.942136 + outer loop + vertex 1.2783 0.933832 2.5082 + vertex 1.27814 0.938704 2.50973 + vertex 1.27316 0.933523 2.50904 + endloop + endfacet + facet normal 0.172239 -0.284473 0.943085 + outer loop + vertex 1.26833 0.928738 2.50848 + vertex 1.27316 0.933523 2.50904 + vertex 1.26809 0.933405 2.50993 + endloop + endfacet + facet normal 0.169148 -0.285858 0.943225 + outer loop + vertex 1.27228 0.940059 2.51118 + vertex 1.2729 0.937417 2.51027 + vertex 1.27596 0.941378 2.51092 + endloop + endfacet + facet normal 0.171267 -0.281119 0.944267 + outer loop + vertex 1.27228 0.940059 2.51118 + vertex 1.27374 0.944055 2.51211 + vertex 1.26903 0.94006 2.51177 + endloop + endfacet + facet normal 0.171718 -0.278704 0.944901 + outer loop + vertex 1.26903 0.94006 2.51177 + vertex 1.26848 0.943996 2.51303 + vertex 1.26375 0.938764 2.51235 + endloop + endfacet + facet normal 0.171187 -0.278254 0.94513 + outer loop + vertex 1.26375 0.938764 2.51235 + vertex 1.26848 0.943996 2.51303 + vertex 1.26322 0.943587 2.51387 + endloop + endfacet + facet normal 0.174249 -0.277788 0.944707 + outer loop + vertex 1.26375 0.938764 2.51235 + vertex 1.26322 0.943587 2.51387 + vertex 1.25842 0.93878 2.51334 + endloop + endfacet + facet normal 0.176004 -0.283986 0.942536 + outer loop + vertex 1.26311 0.93217 2.51048 + vertex 1.26234 0.93465 2.51137 + vertex 1.26 0.931988 2.51101 + endloop + endfacet + facet normal 0.173029 -0.285277 0.942697 + outer loop + vertex 1.2697 0.937419 2.51085 + vertex 1.26605 0.936095 2.51112 + vertex 1.26809 0.933405 2.50993 + endloop + endfacet + facet normal 0.175674 -0.284133 0.942554 + outer loop + vertex 1.26833 0.928738 2.50848 + vertex 1.26809 0.933405 2.50993 + vertex 1.26334 0.928387 2.50931 + endloop + endfacet + facet normal 0.175973 -0.2801 0.943704 + outer loop + vertex 1.26 0.931988 2.51101 + vertex 1.25861 0.928342 2.51018 + vertex 1.26311 0.93217 2.51048 + endloop + endfacet + facet normal 0.180482 -0.281464 0.942446 + outer loop + vertex 1.26355 0.923958 2.50794 + vertex 1.26334 0.928387 2.50931 + vertex 1.25846 0.923656 2.50883 + endloop + endfacet + facet normal 0.182365 -0.275708 0.943784 + outer loop + vertex 1.25345 0.918768 2.50837 + vertex 1.25846 0.923656 2.50883 + vertex 1.25326 0.923677 2.50984 + endloop + endfacet + facet normal 0.18139 -0.275746 0.943961 + outer loop + vertex 1.25485 0.927839 2.51075 + vertex 1.25106 0.926285 2.51102 + vertex 1.25326 0.923677 2.50984 + endloop + endfacet + facet normal 0.176955 -0.280412 0.943428 + outer loop + vertex 1.26 0.931988 2.51101 + vertex 1.25723 0.930531 2.51109 + vertex 1.25861 0.928342 2.51018 + endloop + endfacet + facet normal 0.182804 -0.279435 0.942602 + outer loop + vertex 1.25485 0.927839 2.51075 + vertex 1.25402 0.930281 2.51163 + vertex 1.25106 0.926285 2.51102 + endloop + endfacet + facet normal 0.178603 -0.283625 0.942156 + outer loop + vertex 1.26 0.931988 2.51101 + vertex 1.25851 0.934151 2.51194 + vertex 1.25723 0.930531 2.51109 + endloop + endfacet + facet normal 0.182512 -0.280939 0.942212 + outer loop + vertex 1.25402 0.930281 2.51163 + vertex 1.2536 0.934046 2.51284 + vertex 1.24875 0.92883 2.51222 + endloop + endfacet + facet normal 0.174027 -0.281735 0.943578 + outer loop + vertex 1.26375 0.938764 2.51235 + vertex 1.25842 0.93878 2.51334 + vertex 1.25851 0.934151 2.51194 + endloop + endfacet + facet normal 0.176291 -0.270376 0.946477 + outer loop + vertex 1.24987 0.942119 2.5159 + vertex 1.24857 0.938462 2.51509 + vertex 1.25301 0.94232 2.51537 + endloop + endfacet + facet normal 0.1798 -0.278895 0.94334 + outer loop + vertex 1.2536 0.934046 2.51284 + vertex 1.25337 0.93851 2.5142 + vertex 1.24849 0.933734 2.51372 + endloop + endfacet + facet normal 0.180722 -0.276296 0.943928 + outer loop + vertex 1.24339 0.928778 2.51324 + vertex 1.24849 0.933734 2.51372 + vertex 1.24323 0.933744 2.51473 + endloop + endfacet + facet normal 0.178742 -0.271096 0.945811 + outer loop + vertex 1.24987 0.942119 2.5159 + vertex 1.24711 0.940638 2.51599 + vertex 1.24857 0.938462 2.51509 + endloop + endfacet + facet normal 0.17525 -0.267609 0.947456 + outer loop + vertex 1.24478 0.937931 2.51566 + vertex 1.24387 0.940345 2.51651 + vertex 1.24097 0.936358 2.51592 + endloop + endfacet + facet normal 0.17404 -0.262121 0.949212 + outer loop + vertex 1.24987 0.942119 2.5159 + vertex 1.24831 0.944212 2.51676 + vertex 1.24711 0.940638 2.51599 + endloop + endfacet + facet normal 0.173651 -0.267 0.947922 + outer loop + vertex 1.25359 0.948786 2.51708 + vertex 1.24826 0.948795 2.51806 + vertex 1.24831 0.944212 2.51676 + endloop + endfacet + facet normal 0.172641 -0.285863 0.942591 + outer loop + vertex 1.25359 0.948786 2.51708 + vertex 1.25343 0.953668 2.51859 + vertex 1.24826 0.948795 2.51806 + endloop + endfacet + facet normal 0.168058 -0.286239 0.943305 + outer loop + vertex 1.25359 0.948786 2.51708 + vertex 1.25855 0.953921 2.51776 + vertex 1.25343 0.953668 2.51859 + endloop + endfacet + facet normal 0.174935 -0.261726 0.949156 + outer loop + vertex 1.24387 0.940345 2.51651 + vertex 1.24337 0.944039 2.51762 + vertex 1.23862 0.938882 2.51707 + endloop + endfacet + facet normal 0.176587 -0.268507 0.946954 + outer loop + vertex 1.24387 0.940345 2.51651 + vertex 1.23862 0.938882 2.51707 + vertex 1.24097 0.936358 2.51592 + endloop + endfacet + facet normal 0.181085 -0.2729 0.944846 + outer loop + vertex 1.23803 0.932352 2.51532 + vertex 1.23719 0.934808 2.51619 + vertex 1.23487 0.932125 2.51586 + endloop + endfacet + facet normal 0.178258 -0.275347 0.944673 + outer loop + vertex 1.24478 0.937931 2.51566 + vertex 1.24097 0.936358 2.51592 + vertex 1.24323 0.933744 2.51473 + endloop + endfacet + facet normal 0.182602 -0.27614 0.943612 + outer loop + vertex 1.24339 0.928778 2.51324 + vertex 1.24323 0.933744 2.51473 + vertex 1.2383 0.928493 2.51415 + endloop + endfacet + facet normal 0.181054 -0.271448 0.94527 + outer loop + vertex 1.23487 0.932125 2.51586 + vertex 1.23353 0.928444 2.51506 + vertex 1.23803 0.932352 2.51532 + endloop + endfacet + facet normal 0.184774 -0.271742 0.944465 + outer loop + vertex 1.2383 0.923919 2.51283 + vertex 1.2383 0.928493 2.51415 + vertex 1.23331 0.923736 2.51375 + endloop + endfacet + facet normal 0.186496 -0.26796 0.945207 + outer loop + vertex 1.22829 0.918785 2.51334 + vertex 1.23331 0.923736 2.51375 + vertex 1.22819 0.923705 2.51476 + endloop + endfacet + facet normal 0.182895 -0.272006 0.944755 + outer loop + vertex 1.23487 0.932125 2.51586 + vertex 1.23211 0.930637 2.51596 + vertex 1.23353 0.928444 2.51506 + endloop + endfacet + facet normal 0.186016 -0.272743 0.943933 + outer loop + vertex 1.23211 0.930637 2.51596 + vertex 1.23336 0.934242 2.51676 + vertex 1.2289 0.930344 2.51651 + endloop + endfacet + facet normal 0.186858 -0.268835 0.944887 + outer loop + vertex 1.2289 0.930344 2.51651 + vertex 1.22848 0.93408 2.51766 + vertex 1.22367 0.928851 2.51712 + endloop + endfacet + facet normal 0.19032 -0.268079 0.944411 + outer loop + vertex 1.22309 0.922273 2.51537 + vertex 1.22226 0.924727 2.51623 + vertex 1.21997 0.922018 2.51593 + endloop + endfacet + facet normal 0.18786 -0.269193 0.944587 + outer loop + vertex 1.22977 0.927912 2.51564 + vertex 1.226 0.926314 2.51594 + vertex 1.22819 0.923705 2.51476 + endloop + endfacet + facet normal 0.188543 -0.267814 0.944842 + outer loop + vertex 1.22829 0.918785 2.51334 + vertex 1.22819 0.923705 2.51476 + vertex 1.2233 0.91843 2.51424 + endloop + endfacet + facet normal 0.190751 -0.268233 0.94428 + outer loop + vertex 1.21836 0.913673 2.51388 + vertex 1.2233 0.91843 2.51424 + vertex 1.21863 0.918351 2.51516 + endloop + endfacet + facet normal 0.192238 -0.268236 0.943978 + outer loop + vertex 1.21863 0.918351 2.51516 + vertex 1.21332 0.913642 2.5149 + vertex 1.21836 0.913673 2.51388 + endloop + endfacet + facet normal 0.193107 -0.267172 0.944102 + outer loop + vertex 1.21492 0.917817 2.51576 + vertex 1.21405 0.920253 2.51663 + vertex 1.21119 0.916245 2.51608 + endloop + endfacet + facet normal 0.193145 -0.267198 0.944087 + outer loop + vertex 1.21405 0.920253 2.51663 + vertex 1.20882 0.918791 2.51728 + vertex 1.21119 0.916245 2.51608 + endloop + endfacet + facet normal 0.194057 -0.268952 0.943402 + outer loop + vertex 1.21337 0.90874 2.51349 + vertex 1.21332 0.913642 2.5149 + vertex 1.20843 0.908384 2.51441 + endloop + endfacet + facet normal 0.197252 -0.270343 0.942341 + outer loop + vertex 1.20352 0.903645 2.51408 + vertex 1.20843 0.908384 2.51441 + vertex 1.20378 0.908212 2.51533 + endloop + endfacet + facet normal 0.198698 -0.26945 0.942293 + outer loop + vertex 1.20511 0.911877 2.5161 + vertex 1.20219 0.910146 2.51622 + vertex 1.20378 0.908212 2.51533 + endloop + endfacet + facet normal 0.195576 -0.268607 0.943186 + outer loop + vertex 1.20744 0.91464 2.5164 + vertex 1.20827 0.912209 2.51553 + vertex 1.21119 0.916245 2.51608 + endloop + endfacet + facet normal 0.197513 -0.267386 0.94313 + outer loop + vertex 1.20511 0.911877 2.5161 + vertex 1.20343 0.913899 2.51702 + vertex 1.20219 0.910146 2.51622 + endloop + endfacet + facet normal 0.19452 -0.265951 0.944157 + outer loop + vertex 1.21119 0.916245 2.51608 + vertex 1.20882 0.918791 2.51728 + vertex 1.20744 0.91464 2.5164 + endloop + endfacet + facet normal 0.197201 -0.263617 0.944255 + outer loop + vertex 1.20343 0.913899 2.51702 + vertex 1.20345 0.91874 2.51837 + vertex 1.19836 0.913795 2.51805 + endloop + endfacet + facet normal 0.19519 -0.26161 0.945231 + outer loop + vertex 1.19836 0.913795 2.51805 + vertex 1.20345 0.91874 2.51837 + vertex 1.1984 0.918434 2.51933 + endloop + endfacet + facet normal 0.191384 -0.259536 0.94658 + outer loop + vertex 1.20345 0.91874 2.51837 + vertex 1.2085 0.923756 2.51873 + vertex 1.20326 0.923766 2.51979 + endloop + endfacet + facet normal 0.191413 -0.259017 0.946716 + outer loop + vertex 1.20866 0.928663 2.52004 + vertex 1.20326 0.923766 2.51979 + vertex 1.2085 0.923756 2.51873 + endloop + endfacet + facet normal 0.188638 -0.256024 0.948086 + outer loop + vertex 1.20477 0.927998 2.52063 + vertex 1.20326 0.923766 2.51979 + vertex 1.20866 0.928663 2.52004 + endloop + endfacet + facet normal 0.188792 -0.257244 0.947725 + outer loop + vertex 1.20866 0.928663 2.52004 + vertex 1.20712 0.930776 2.52092 + vertex 1.20477 0.927998 2.52063 + endloop + endfacet + facet normal 0.190422 -0.258555 0.947042 + outer loop + vertex 1.20712 0.930776 2.52092 + vertex 1.20389 0.9304 2.52146 + vertex 1.20477 0.927998 2.52063 + endloop + endfacet + facet normal 0.1918 -0.258005 0.946914 + outer loop + vertex 1.20477 0.927998 2.52063 + vertex 1.20389 0.9304 2.52146 + vertex 1.201 0.926357 2.52095 + endloop + endfacet + facet normal 0.190594 -0.261085 0.946313 + outer loop + vertex 1.20712 0.930776 2.52092 + vertex 1.20835 0.934377 2.52166 + vertex 1.20389 0.9304 2.52146 + endloop + endfacet + facet normal 0.189876 -0.260298 0.946674 + outer loop + vertex 1.20835 0.934377 2.52166 + vertex 1.20349 0.934127 2.52257 + vertex 1.20389 0.9304 2.52146 + endloop + endfacet + facet normal 0.188888 -0.260603 0.946788 + outer loop + vertex 1.21001 0.93246 2.5208 + vertex 1.20835 0.934377 2.52166 + vertex 1.20712 0.930776 2.52092 + endloop + endfacet + facet normal 0.188051 -0.261314 0.946758 + outer loop + vertex 1.21214 0.93519 2.52113 + vertex 1.20835 0.934377 2.52166 + vertex 1.21001 0.93246 2.5208 + endloop + endfacet + facet normal 0.18541 -0.259379 0.947811 + outer loop + vertex 1.21372 0.933222 2.52029 + vertex 1.21214 0.93519 2.52113 + vertex 1.21001 0.93246 2.5208 + endloop + endfacet + facet normal 0.185097 -0.25746 0.948395 + outer loop + vertex 1.21001 0.93246 2.5208 + vertex 1.20866 0.928663 2.52004 + vertex 1.21372 0.933222 2.52029 + endloop + endfacet + facet normal 0.187485 -0.260043 0.947221 + outer loop + vertex 1.21372 0.933222 2.52029 + vertex 1.20866 0.928663 2.52004 + vertex 1.21349 0.928621 2.51907 + endloop + endfacet + facet normal 0.188213 -0.26226 0.946465 + outer loop + vertex 1.21214 0.93519 2.52113 + vertex 1.21338 0.93891 2.52192 + vertex 1.20835 0.934377 2.52166 + endloop + endfacet + facet normal 0.187578 -0.261573 0.946781 + outer loop + vertex 1.21338 0.93891 2.52192 + vertex 1.20836 0.938858 2.5229 + vertex 1.20835 0.934377 2.52166 + endloop + endfacet + facet normal 0.18751 -0.258179 0.947726 + outer loop + vertex 1.21001 0.93246 2.5208 + vertex 1.20712 0.930776 2.52092 + vertex 1.20866 0.928663 2.52004 + endloop + endfacet + facet normal 0.192528 -0.264606 0.944943 + outer loop + vertex 1.21405 0.920253 2.51663 + vertex 1.21358 0.924027 2.51778 + vertex 1.20882 0.918791 2.51728 + endloop + endfacet + facet normal 0.187543 -0.25909 0.94747 + outer loop + vertex 1.2085 0.923756 2.51873 + vertex 1.21349 0.928621 2.51907 + vertex 1.20866 0.928663 2.52004 + endloop + endfacet + facet normal 0.189848 -0.264791 0.945433 + outer loop + vertex 1.21845 0.92415 2.51684 + vertex 1.21844 0.92876 2.51813 + vertex 1.21358 0.924027 2.51778 + endloop + endfacet + facet normal 0.186975 -0.265642 0.945766 + outer loop + vertex 1.22367 0.928851 2.51712 + vertex 1.2234 0.933705 2.51854 + vertex 1.21844 0.92876 2.51813 + endloop + endfacet + facet normal 0.184401 -0.260051 0.947824 + outer loop + vertex 1.21349 0.928621 2.51907 + vertex 1.2184 0.93336 2.51941 + vertex 1.21372 0.933222 2.52029 + endloop + endfacet + facet normal 0.184789 -0.259871 0.947798 + outer loop + vertex 1.21503 0.936865 2.52103 + vertex 1.21214 0.93519 2.52113 + vertex 1.21372 0.933222 2.52029 + endloop + endfacet + facet normal 0.182039 -0.26066 0.948113 + outer loop + vertex 1.21738 0.93961 2.52133 + vertex 1.21821 0.937189 2.5205 + vertex 1.22117 0.94121 2.52104 + endloop + endfacet + facet normal 0.185757 -0.261583 0.947137 + outer loop + vertex 1.21503 0.936865 2.52103 + vertex 1.21338 0.93891 2.52192 + vertex 1.21214 0.93519 2.52113 + endloop + endfacet + facet normal 0.183206 -0.263617 0.94707 + outer loop + vertex 1.22117 0.94121 2.52104 + vertex 1.21878 0.943733 2.5222 + vertex 1.21738 0.93961 2.52133 + endloop + endfacet + facet normal 0.18137 -0.2653 0.946954 + outer loop + vertex 1.22409 0.945192 2.5216 + vertex 1.21878 0.943733 2.5222 + vertex 1.22117 0.94121 2.52104 + endloop + endfacet + facet normal 0.183438 -0.266705 0.94616 + outer loop + vertex 1.22496 0.942778 2.52075 + vertex 1.22409 0.945192 2.5216 + vertex 1.22117 0.94121 2.52104 + endloop + endfacet + facet normal 0.183593 -0.274681 0.943845 + outer loop + vertex 1.22409 0.945192 2.5216 + vertex 1.2236 0.948944 2.52278 + vertex 1.21878 0.943733 2.5222 + endloop + endfacet + facet normal 0.17781 -0.275692 0.944657 + outer loop + vertex 1.22856 0.949081 2.52189 + vertex 1.2236 0.948944 2.52278 + vertex 1.22409 0.945192 2.5216 + endloop + endfacet + facet normal 0.174621 -0.266826 0.947793 + outer loop + vertex 1.21878 0.943733 2.5222 + vertex 1.2236 0.948944 2.52278 + vertex 1.21843 0.948637 2.52365 + endloop + endfacet + facet normal 0.174748 -0.278751 0.944331 + outer loop + vertex 1.2236 0.948944 2.52278 + vertex 1.22339 0.953475 2.52416 + vertex 1.21843 0.948637 2.52365 + endloop + endfacet + facet normal 0.167788 -0.279401 0.945401 + outer loop + vertex 1.2236 0.948944 2.52278 + vertex 1.22852 0.953785 2.52334 + vertex 1.22339 0.953475 2.52416 + endloop + endfacet + facet normal 0.187577 -0.261587 0.946777 + outer loop + vertex 1.21338 0.93891 2.52192 + vertex 1.21338 0.943698 2.52324 + vertex 1.20836 0.938858 2.5229 + endloop + endfacet + facet normal 0.189876 -0.261463 0.946353 + outer loop + vertex 1.20835 0.934377 2.52166 + vertex 1.20836 0.938858 2.5229 + vertex 1.20349 0.934127 2.52257 + endloop + endfacet + facet normal 0.192587 -0.259879 0.946242 + outer loop + vertex 1.20389 0.9304 2.52146 + vertex 1.20349 0.934127 2.52257 + vertex 1.19868 0.928852 2.5221 + endloop + endfacet + facet normal 0.192167 -0.258249 0.946773 + outer loop + vertex 1.20389 0.9304 2.52146 + vertex 1.19868 0.928852 2.5221 + vertex 1.201 0.926357 2.52095 + endloop + endfacet + facet normal 0.194845 -0.254818 0.947155 + outer loop + vertex 1.19814 0.922298 2.52043 + vertex 1.19726 0.924719 2.52127 + vertex 1.19497 0.921948 2.52099 + endloop + endfacet + facet normal 0.191323 -0.256831 0.94733 + outer loop + vertex 1.20477 0.927998 2.52063 + vertex 1.201 0.926357 2.52095 + vertex 1.20326 0.923766 2.51979 + endloop + endfacet + facet normal 0.19517 -0.259196 0.9459 + outer loop + vertex 1.20345 0.91874 2.51837 + vertex 1.20326 0.923766 2.51979 + vertex 1.1984 0.918434 2.51933 + endloop + endfacet + facet normal 0.194886 -0.255496 0.946964 + outer loop + vertex 1.19497 0.921948 2.52099 + vertex 1.19372 0.918267 2.52026 + vertex 1.19814 0.922298 2.52043 + endloop + endfacet + facet normal 0.198156 -0.261472 0.944652 + outer loop + vertex 1.19836 0.913795 2.51805 + vertex 1.1984 0.918434 2.51933 + vertex 1.19344 0.913628 2.51904 + endloop + endfacet + facet normal 0.198331 -0.258626 0.945398 + outer loop + vertex 1.19003 0.917448 2.52081 + vertex 1.18868 0.913622 2.52004 + vertex 1.19372 0.918267 2.52026 + endloop + endfacet + facet normal 0.20087 -0.263892 0.943405 + outer loop + vertex 1.19327 0.908969 2.51777 + vertex 1.19344 0.913628 2.51904 + vertex 1.18835 0.908772 2.51876 + endloop + endfacet + facet normal 0.201851 -0.262641 0.943544 + outer loop + vertex 1.1834 0.903782 2.51844 + vertex 1.18835 0.908772 2.51876 + vertex 1.18329 0.9087 2.51983 + endloop + endfacet + facet normal 0.199922 -0.259096 0.944934 + outer loop + vertex 1.19003 0.917448 2.52081 + vertex 1.18717 0.915707 2.52094 + vertex 1.18868 0.913622 2.52004 + endloop + endfacet + facet normal 0.19988 -0.257997 0.945244 + outer loop + vertex 1.18483 0.912897 2.52066 + vertex 1.18394 0.915309 2.52151 + vertex 1.1811 0.911254 2.521 + endloop + endfacet + facet normal 0.197912 -0.255685 0.946285 + outer loop + vertex 1.19003 0.917448 2.52081 + vertex 1.18834 0.919349 2.52167 + vertex 1.18717 0.915707 2.52094 + endloop + endfacet + facet normal 0.198859 -0.254158 0.946498 + outer loop + vertex 1.18834 0.919349 2.52167 + vertex 1.18837 0.923868 2.52288 + vertex 1.18349 0.919082 2.52262 + endloop + endfacet + facet normal 0.198862 -0.254161 0.946497 + outer loop + vertex 1.18349 0.919082 2.52262 + vertex 1.18837 0.923868 2.52288 + vertex 1.18343 0.923725 2.52388 + endloop + endfacet + facet normal 0.200828 -0.258614 0.944874 + outer loop + vertex 1.18394 0.915309 2.52151 + vertex 1.17875 0.913791 2.52219 + vertex 1.1811 0.911254 2.521 + endloop + endfacet + facet normal 0.2029 -0.259978 0.944057 + outer loop + vertex 1.17829 0.907238 2.5205 + vertex 1.17742 0.909645 2.52134 + vertex 1.17519 0.906914 2.52107 + endloop + endfacet + facet normal 0.20117 -0.261162 0.9441 + outer loop + vertex 1.18483 0.912897 2.52066 + vertex 1.1811 0.911254 2.521 + vertex 1.18329 0.9087 2.51983 + endloop + endfacet + facet normal 0.204268 -0.262455 0.943076 + outer loop + vertex 1.1834 0.903782 2.51844 + vertex 1.18329 0.9087 2.51983 + vertex 1.17851 0.90343 2.5194 + endloop + endfacet + facet normal 0.202871 -0.259412 0.944219 + outer loop + vertex 1.17519 0.906914 2.52107 + vertex 1.17395 0.903276 2.52034 + vertex 1.17829 0.907238 2.5205 + endloop + endfacet + facet normal 0.207269 -0.257842 0.943693 + outer loop + vertex 1.17851 0.898811 2.51814 + vertex 1.17851 0.90343 2.5194 + vertex 1.17365 0.898663 2.51916 + endloop + endfacet + facet normal 0.207545 -0.246689 0.946609 + outer loop + vertex 1.17343 0.893907 2.51797 + vertex 1.17851 0.898811 2.51814 + vertex 1.17365 0.898663 2.51916 + endloop + endfacet + facet normal 0.2141 -0.253364 0.943381 + outer loop + vertex 1.17842 0.894071 2.51688 + vertex 1.17851 0.898811 2.51814 + vertex 1.17343 0.893907 2.51797 + endloop + endfacet + facet normal 0.214379 -0.241285 0.946479 + outer loop + vertex 1.17842 0.894071 2.51688 + vertex 1.17343 0.893907 2.51797 + vertex 1.17323 0.88919 2.51681 + endloop + endfacet + facet normal 0.225024 -0.241142 0.944042 + outer loop + vertex 1.17323 0.88919 2.51681 + vertex 1.17343 0.893907 2.51797 + vertex 1.16824 0.888877 2.51792 + endloop + endfacet + facet normal 0.224983 -0.234871 0.945631 + outer loop + vertex 1.17323 0.88919 2.51681 + vertex 1.16824 0.888877 2.51792 + vertex 1.16798 0.884148 2.51681 + endloop + endfacet + facet normal 0.21577 -0.231628 0.948574 + outer loop + vertex 1.16824 0.888877 2.51792 + vertex 1.17343 0.893907 2.51797 + vertex 1.16854 0.893729 2.51904 + endloop + endfacet + facet normal 0.20105 -0.249033 0.947397 + outer loop + vertex 1.17026 0.90242 2.5209 + vertex 1.16895 0.898593 2.52017 + vertex 1.17395 0.903276 2.52034 + endloop + endfacet + facet normal 0.215502 -0.24662 0.944848 + outer loop + vertex 1.17343 0.893907 2.51797 + vertex 1.17365 0.898663 2.51916 + vertex 1.16854 0.893729 2.51904 + endloop + endfacet + facet normal 0.201513 -0.221084 0.954209 + outer loop + vertex 1.16503 0.897542 2.52075 + vertex 1.16375 0.893593 2.52011 + vertex 1.16895 0.898593 2.52017 + endloop + endfacet + facet normal 0.231209 -0.231747 0.9449 + outer loop + vertex 1.16824 0.888877 2.51792 + vertex 1.16854 0.893729 2.51904 + vertex 1.1634 0.888652 2.51905 + endloop + endfacet + facet normal 0.2289 -0.198351 0.953028 + outer loop + vertex 1.15981 0.892433 2.52081 + vertex 1.15878 0.88852 2.52025 + vertex 1.16375 0.893593 2.52011 + endloop + endfacet + facet normal 0.23119 -0.233572 0.944455 + outer loop + vertex 1.16317 0.883861 2.51792 + vertex 1.16824 0.888877 2.51792 + vertex 1.1634 0.888652 2.51905 + endloop + endfacet + facet normal 0.232465 -0.234859 0.943823 + outer loop + vertex 1.16798 0.884148 2.51681 + vertex 1.16824 0.888877 2.51792 + vertex 1.16317 0.883861 2.51792 + endloop + endfacet + facet normal 0.231585 -0.241747 0.942299 + outer loop + vertex 1.17198 0.885367 2.51614 + vertex 1.17323 0.88919 2.51681 + vertex 1.16798 0.884148 2.51681 + endloop + endfacet + facet normal 0.222723 -0.250103 0.942254 + outer loop + vertex 1.17723 0.89031 2.51616 + vertex 1.17842 0.894071 2.51688 + vertex 1.17323 0.88919 2.51681 + endloop + endfacet + facet normal 0.207791 -0.253608 0.944725 + outer loop + vertex 1.18366 0.898958 2.51704 + vertex 1.17851 0.898811 2.51814 + vertex 1.17842 0.894071 2.51688 + endloop + endfacet + facet normal 0.206782 -0.260409 0.943095 + outer loop + vertex 1.18871 0.900512 2.51636 + vertex 1.18366 0.898958 2.51704 + vertex 1.18595 0.896489 2.51586 + endloop + endfacet + facet normal 0.208382 -0.248517 0.945947 + outer loop + vertex 1.18319 0.892432 2.51539 + vertex 1.18233 0.894866 2.51622 + vertex 1.1801 0.892092 2.51598 + endloop + endfacet + facet normal 0.205725 -0.254575 0.944917 + outer loop + vertex 1.1896 0.898128 2.5155 + vertex 1.18595 0.896489 2.51586 + vertex 1.1882 0.893891 2.51467 + endloop + endfacet + facet normal 0.21455 -0.250374 0.944077 + outer loop + vertex 1.18839 0.888837 2.51328 + vertex 1.1882 0.893891 2.51467 + vertex 1.18341 0.888516 2.51433 + endloop + endfacet + facet normal 0.214513 -0.246159 0.945193 + outer loop + vertex 1.18338 0.883835 2.51312 + vertex 1.18839 0.888837 2.51328 + vertex 1.18341 0.888516 2.51433 + endloop + endfacet + facet normal 0.207911 -0.240426 0.948139 + outer loop + vertex 1.1801 0.892092 2.51598 + vertex 1.17882 0.888352 2.51531 + vertex 1.18319 0.892432 2.51539 + endloop + endfacet + facet normal 0.210927 -0.246327 0.945956 + outer loop + vertex 1.18338 0.883835 2.51312 + vertex 1.18341 0.888516 2.51433 + vertex 1.17857 0.883696 2.51415 + endloop + endfacet + facet normal 0.210253 -0.269773 0.939689 + outer loop + vertex 1.17861 0.879191 2.51285 + vertex 1.18338 0.883835 2.51312 + vertex 1.17857 0.883696 2.51415 + endloop + endfacet + facet normal 0.215063 -0.245372 0.945273 + outer loop + vertex 1.17508 0.887423 2.51592 + vertex 1.17381 0.883573 2.51521 + vertex 1.17882 0.888352 2.51531 + endloop + endfacet + facet normal 0.244946 -0.303751 0.920726 + outer loop + vertex 1.16981 0.882412 2.51589 + vertex 1.16895 0.878799 2.51493 + vertex 1.17381 0.883573 2.51521 + endloop + endfacet + facet normal 0.199284 -0.270509 0.941866 + outer loop + vertex 1.17861 0.879191 2.51285 + vertex 1.17857 0.883696 2.51415 + vertex 1.17389 0.879045 2.51381 + endloop + endfacet + facet normal 0.198002 -0.25756 0.945758 + outer loop + vertex 1.18327 0.87918 2.51187 + vertex 1.18338 0.883835 2.51312 + vertex 1.17861 0.879191 2.51285 + endloop + endfacet + facet normal 0.215044 -0.257012 0.942179 + outer loop + vertex 1.18835 0.884002 2.51203 + vertex 1.18338 0.883835 2.51312 + vertex 1.18327 0.87918 2.51187 + endloop + endfacet + facet normal 0.203846 -0.245371 0.947755 + outer loop + vertex 1.18714 0.880126 2.51129 + vertex 1.18835 0.884002 2.51203 + vertex 1.18327 0.87918 2.51187 + endloop + endfacet + facet normal 0.194919 -0.298818 0.934192 + outer loop + vertex 1.18499 0.87725 2.5109 + vertex 1.18327 0.87918 2.51187 + vertex 1.18207 0.875498 2.51095 + endloop + endfacet + facet normal 0.211479 -0.284475 0.935067 + outer loop + vertex 1.18714 0.880126 2.51129 + vertex 1.18327 0.87918 2.51187 + vertex 1.18499 0.87725 2.5109 + endloop + endfacet + facet normal 0.220406 -0.247151 0.943577 + outer loop + vertex 1.19524 0.88688 2.51116 + vertex 1.19235 0.885069 2.51136 + vertex 1.19392 0.883119 2.51049 + endloop + endfacet + facet normal 0.220976 -0.249793 0.942747 + outer loop + vertex 1.1902 0.882151 2.51111 + vertex 1.18835 0.884002 2.51203 + vertex 1.18714 0.880126 2.51129 + endloop + endfacet + facet normal 0.223027 -0.251523 0.941804 + outer loop + vertex 1.19524 0.88688 2.51116 + vertex 1.19352 0.888922 2.51212 + vertex 1.19235 0.885069 2.51136 + endloop + endfacet + facet normal 0.215284 -0.24692 0.944819 + outer loop + vertex 1.18835 0.884002 2.51203 + vertex 1.18839 0.888837 2.51328 + vertex 1.18338 0.883835 2.51312 + endloop + endfacet + facet normal 0.211179 -0.250685 0.944754 + outer loop + vertex 1.18839 0.888837 2.51328 + vertex 1.19348 0.893864 2.51348 + vertex 1.1882 0.893891 2.51467 + endloop + endfacet + facet normal 0.210318 -0.267377 0.940359 + outer loop + vertex 1.19883 0.893876 2.51229 + vertex 1.19855 0.898806 2.51375 + vertex 1.19348 0.893864 2.51348 + endloop + endfacet + facet normal 0.202504 -0.268267 0.94182 + outer loop + vertex 1.19883 0.893876 2.51229 + vertex 1.20356 0.899103 2.51276 + vertex 1.19855 0.898806 2.51375 + endloop + endfacet + facet normal 0.198317 -0.27252 0.94149 + outer loop + vertex 1.20837 0.899251 2.51179 + vertex 1.20841 0.903816 2.5131 + vertex 1.20356 0.899103 2.51276 + endloop + endfacet + facet normal 0.196407 -0.274488 0.941319 + outer loop + vertex 1.20989 0.897144 2.51086 + vertex 1.20837 0.899251 2.51179 + vertex 1.20716 0.895647 2.51099 + endloop + endfacet + facet normal 0.193376 -0.268761 0.943596 + outer loop + vertex 1.20989 0.897144 2.51086 + vertex 1.20716 0.895647 2.51099 + vertex 1.20858 0.893485 2.51008 + endloop + endfacet + facet normal 0.20419 -0.262153 0.943177 + outer loop + vertex 1.20858 0.893485 2.51008 + vertex 1.2033 0.888723 2.5099 + vertex 1.20832 0.888792 2.50883 + endloop + endfacet + facet normal 0.204474 -0.267033 0.941745 + outer loop + vertex 1.20487 0.892933 2.5107 + vertex 1.204 0.895359 2.51158 + vertex 1.20118 0.891338 2.51105 + endloop + endfacet + facet normal 0.204689 -0.250277 0.946289 + outer loop + vertex 1.20332 0.883766 2.50859 + vertex 1.20832 0.888792 2.50883 + vertex 1.2033 0.888723 2.5099 + endloop + endfacet + facet normal 0.20514 -0.258492 0.943981 + outer loop + vertex 1.20354 0.878954 2.50722 + vertex 1.20332 0.883766 2.50859 + vertex 1.1985 0.878807 2.50828 + endloop + endfacet + facet normal 0.20993 -0.257232 0.943271 + outer loop + vertex 1.20857 0.880405 2.5065 + vertex 1.20827 0.884199 2.5076 + vertex 1.20354 0.878954 2.50722 + endloop + endfacet + facet normal 0.199052 -0.271577 0.941607 + outer loop + vertex 1.22337 0.8792 2.50285 + vertex 1.2234 0.88367 2.50414 + vertex 1.21852 0.878847 2.50378 + endloop + endfacet + facet normal 0.205614 -0.310334 0.928125 + outer loop + vertex 1.23815 0.882267 2.50052 + vertex 1.2337 0.878219 2.50016 + vertex 1.23864 0.878616 2.4992 + endloop + endfacet + facet normal 0.203176 -0.3108 0.928506 + outer loop + vertex 1.23864 0.878616 2.4992 + vertex 1.24334 0.883793 2.4999 + vertex 1.23815 0.882267 2.50052 + endloop + endfacet + facet normal 0.190256 -0.276574 0.941971 + outer loop + vertex 1.24866 0.888439 2.50019 + vertex 1.24334 0.883793 2.4999 + vertex 1.24849 0.883758 2.49885 + endloop + endfacet + facet normal 0.187753 -0.276622 0.942459 + outer loop + vertex 1.24849 0.883758 2.49885 + vertex 1.25348 0.888458 2.49924 + vertex 1.24866 0.888439 2.50019 + endloop + endfacet + facet normal 0.190577 -0.284532 0.939533 + outer loop + vertex 1.25859 0.888896 2.49833 + vertex 1.25817 0.893554 2.49983 + vertex 1.25348 0.888458 2.49924 + endloop + endfacet + facet normal 0.191853 -0.286897 0.938553 + outer loop + vertex 1.2638 0.889018 2.4973 + vertex 1.25859 0.888896 2.49833 + vertex 1.259 0.884974 2.49705 + endloop + endfacet + facet normal 0.197133 -0.312513 0.929233 + outer loop + vertex 1.26224 0.884985 2.49636 + vertex 1.259 0.884974 2.49705 + vertex 1.25967 0.882394 2.49604 + endloop + endfacet + facet normal 0.198271 -0.29429 0.934924 + outer loop + vertex 1.26224 0.884985 2.49636 + vertex 1.2638 0.889018 2.4973 + vertex 1.259 0.884974 2.49705 + endloop + endfacet + facet normal 0.191877 -0.293414 0.936532 + outer loop + vertex 1.26894 0.890316 2.49666 + vertex 1.2685 0.894153 2.49795 + vertex 1.2638 0.889018 2.4973 + endloop + endfacet + facet normal 0.190218 -0.298076 0.935397 + outer loop + vertex 1.27216 0.890546 2.49607 + vertex 1.27345 0.894201 2.49698 + vertex 1.26894 0.890316 2.49666 + endloop + endfacet + facet normal 0.189441 -0.301678 0.9344 + outer loop + vertex 1.27497 0.892034 2.49599 + vertex 1.27216 0.890546 2.49607 + vertex 1.27355 0.888392 2.4951 + endloop + endfacet + facet normal 0.202181 -0.323073 0.924525 + outer loop + vertex 1.26974 0.887839 2.4957 + vertex 1.26594 0.886345 2.49601 + vertex 1.26813 0.883782 2.49463 + endloop + endfacet + facet normal 0.18663 -0.303129 0.934496 + outer loop + vertex 1.27811 0.892243 2.49544 + vertex 1.27355 0.888392 2.4951 + vertex 1.27835 0.88848 2.49417 + endloop + endfacet + facet normal 0.18288 -0.303575 0.935092 + outer loop + vertex 1.27835 0.88848 2.49417 + vertex 1.28313 0.893516 2.49487 + vertex 1.27811 0.892243 2.49544 + endloop + endfacet + facet normal 0.181258 -0.299549 0.936705 + outer loop + vertex 1.28787 0.897504 2.49523 + vertex 1.28313 0.893516 2.49487 + vertex 1.28823 0.893653 2.49393 + endloop + endfacet + facet normal 0.17992 -0.303334 0.935744 + outer loop + vertex 1.28862 0.889051 2.49236 + vertex 1.29337 0.8941 2.49308 + vertex 1.28823 0.893653 2.49393 + endloop + endfacet + facet normal 0.182216 -0.323287 0.928592 + outer loop + vertex 1.29377 0.890223 2.49176 + vertex 1.28862 0.889051 2.49236 + vertex 1.29089 0.886392 2.49099 + endloop + endfacet + facet normal 0.199387 -0.386639 0.900419 + outer loop + vertex 1.28823 0.882629 2.48998 + vertex 1.28719 0.885092 2.49127 + vertex 1.28475 0.882472 2.49068 + endloop + endfacet + facet normal 0.195409 -0.465602 0.863151 + outer loop + vertex 1.28475 0.882472 2.49068 + vertex 1.28393 0.878651 2.48881 + vertex 1.28823 0.882629 2.48998 + endloop + endfacet + facet normal 0.19282 -0.463335 0.864952 + outer loop + vertex 1.28823 0.882629 2.48998 + vertex 1.28393 0.878651 2.48881 + vertex 1.28963 0.879609 2.48805 + endloop + endfacet + facet normal 0.204834 -0.457866 0.865102 + outer loop + vertex 1.28963 0.879609 2.48805 + vertex 1.29338 0.883884 2.48942 + vertex 1.28823 0.882629 2.48998 + endloop + endfacet + facet normal 0.209616 -0.466723 0.859203 + outer loop + vertex 1.28475 0.882472 2.49068 + vertex 1.281 0.881221 2.49092 + vertex 1.28393 0.878651 2.48881 + endloop + endfacet + facet normal 0.211211 -0.465244 0.859615 + outer loop + vertex 1.27839 0.877772 2.48969 + vertex 1.28393 0.878651 2.48881 + vertex 1.281 0.881221 2.49092 + endloop + endfacet + facet normal 0.222981 -0.47181 0.853039 + outer loop + vertex 1.27716 0.880001 2.49125 + vertex 1.27839 0.877772 2.48969 + vertex 1.281 0.881221 2.49092 + endloop + endfacet + facet normal 0.195672 -0.370972 0.907795 + outer loop + vertex 1.281 0.881221 2.49092 + vertex 1.2786 0.883894 2.49253 + vertex 1.27716 0.880001 2.49125 + endloop + endfacet + facet normal 0.18984 -0.375767 0.907061 + outer loop + vertex 1.28385 0.885077 2.49192 + vertex 1.2786 0.883894 2.49253 + vertex 1.281 0.881221 2.49092 + endloop + endfacet + facet normal 0.180651 -0.370068 0.911271 + outer loop + vertex 1.28475 0.882472 2.49068 + vertex 1.28385 0.885077 2.49192 + vertex 1.281 0.881221 2.49092 + endloop + endfacet + facet normal 0.177547 -0.320177 0.930572 + outer loop + vertex 1.29452 0.887628 2.49072 + vertex 1.29377 0.890223 2.49176 + vertex 1.29089 0.886392 2.49099 + endloop + endfacet + facet normal 0.179531 -0.319537 0.930411 + outer loop + vertex 1.29702 0.890189 2.49112 + vertex 1.29377 0.890223 2.49176 + vertex 1.29452 0.887628 2.49072 + endloop + endfacet + facet normal 0.180606 -0.304928 0.935094 + outer loop + vertex 1.29702 0.890189 2.49112 + vertex 1.29855 0.894159 2.49212 + vertex 1.29377 0.890223 2.49176 + endloop + endfacet + facet normal 0.176744 -0.299858 0.937468 + outer loop + vertex 1.3037 0.895398 2.49154 + vertex 1.30337 0.899123 2.49279 + vertex 1.29855 0.894159 2.49212 + endloop + endfacet + facet normal 0.176857 -0.303227 0.936363 + outer loop + vertex 1.30693 0.895609 2.491 + vertex 1.30829 0.899204 2.49191 + vertex 1.3037 0.895398 2.49154 + endloop + endfacet + facet normal 0.180968 -0.312968 0.932364 + outer loop + vertex 1.30977 0.897061 2.49093 + vertex 1.30693 0.895609 2.491 + vertex 1.30841 0.893498 2.49 + endloop + endfacet + facet normal 0.186962 -0.330478 0.92511 + outer loop + vertex 1.30455 0.892969 2.49058 + vertex 1.30075 0.89151 2.49083 + vertex 1.3032 0.888991 2.48943 + endloop + endfacet + facet normal 0.176919 -0.305919 0.935475 + outer loop + vertex 1.31297 0.897269 2.49039 + vertex 1.31806 0.898529 2.48984 + vertex 1.31598 0.901184 2.4911 + endloop + endfacet + facet normal 0.171249 -0.303062 0.937458 + outer loop + vertex 1.32287 0.902491 2.49025 + vertex 1.31806 0.898529 2.48984 + vertex 1.32321 0.898612 2.48893 + endloop + endfacet + facet normal 0.163516 -0.300353 0.939708 + outer loop + vertex 1.32841 0.899011 2.48815 + vertex 1.32797 0.903621 2.4897 + vertex 1.32321 0.898612 2.48893 + endloop + endfacet + facet normal 0.161137 -0.301319 0.939809 + outer loop + vertex 1.33367 0.899047 2.48726 + vertex 1.33317 0.90364 2.48882 + vertex 1.32841 0.899011 2.48815 + endloop + endfacet + facet normal 0.168434 -0.312781 0.934772 + outer loop + vertex 1.3421 0.900159 2.48612 + vertex 1.34361 0.904097 2.48717 + vertex 1.33885 0.90019 2.48672 + endloop + endfacet + facet normal 0.169095 -0.31875 0.932634 + outer loop + vertex 1.3421 0.900159 2.48612 + vertex 1.3428 0.897575 2.48511 + vertex 1.34578 0.901399 2.48588 + endloop + endfacet + facet normal 0.179509 -0.340697 0.922877 + outer loop + vertex 1.33954 0.897581 2.48572 + vertex 1.33589 0.896331 2.48597 + vertex 1.33817 0.893741 2.48457 + endloop + endfacet + facet normal 0.1688 -0.318545 0.932757 + outer loop + vertex 1.3428 0.897575 2.48511 + vertex 1.34798 0.898682 2.48455 + vertex 1.34578 0.901399 2.48588 + endloop + endfacet + facet normal 0.161928 -0.325208 0.931675 + outer loop + vertex 1.35276 0.902555 2.48507 + vertex 1.34798 0.898682 2.48455 + vertex 1.35328 0.898738 2.48365 + endloop + endfacet + facet normal 0.154189 -0.326563 0.932514 + outer loop + vertex 1.35328 0.898738 2.48365 + vertex 1.35801 0.903611 2.48458 + vertex 1.35276 0.902555 2.48507 + endloop + endfacet + facet normal 0.150178 -0.324203 0.933991 + outer loop + vertex 1.36278 0.907478 2.48515 + vertex 1.35801 0.903611 2.48458 + vertex 1.36333 0.903743 2.48377 + endloop + endfacet + facet normal 0.14873 -0.327153 0.933194 + outer loop + vertex 1.36847 0.904196 2.48311 + vertex 1.36799 0.908582 2.48472 + vertex 1.36333 0.903743 2.48377 + endloop + endfacet + facet normal 0.14357 -0.327917 0.933734 + outer loop + vertex 1.36847 0.904196 2.48311 + vertex 1.37322 0.908591 2.48392 + vertex 1.36799 0.908582 2.48472 + endloop + endfacet + facet normal 0.140264 -0.327538 0.934369 + outer loop + vertex 1.37842 0.90891 2.48325 + vertex 1.37806 0.913386 2.48487 + vertex 1.37322 0.908591 2.48392 + endloop + endfacet + facet normal 0.132211 -0.328488 0.935209 + outer loop + vertex 1.37842 0.90891 2.48325 + vertex 1.38314 0.913245 2.48411 + vertex 1.37806 0.913386 2.48487 + endloop + endfacet + facet normal 0.124869 -0.325811 0.937152 + outer loop + vertex 1.38831 0.913706 2.48358 + vertex 1.38736 0.917455 2.48501 + vertex 1.38314 0.913245 2.48411 + endloop + endfacet + facet normal 0.117665 -0.32786 0.93737 + outer loop + vertex 1.39348 0.914115 2.48307 + vertex 1.39288 0.918491 2.48468 + vertex 1.38831 0.913706 2.48358 + endloop + endfacet + facet normal 0.112767 -0.331259 0.936777 + outer loop + vertex 1.39865 0.913886 2.48237 + vertex 1.39805 0.918267 2.48399 + vertex 1.39348 0.914115 2.48307 + endloop + endfacet + facet normal 0.113312 -0.339417 0.933786 + outer loop + vertex 1.40084 0.910894 2.48102 + vertex 1.39865 0.913886 2.48237 + vertex 1.39702 0.910002 2.48115 + endloop + endfacet + facet normal 0.116144 -0.352331 0.928641 + outer loop + vertex 1.39702 0.910002 2.48115 + vertex 1.39758 0.907298 2.48006 + vertex 1.40084 0.910894 2.48102 + endloop + endfacet + facet normal 0.122521 -0.374846 0.918955 + outer loop + vertex 1.39758 0.907298 2.48006 + vertex 1.3931 0.903962 2.47929 + vertex 1.39817 0.903791 2.47855 + endloop + endfacet + facet normal 0.117694 -0.346534 0.930625 + outer loop + vertex 1.39441 0.907662 2.4806 + vertex 1.39388 0.910388 2.48168 + vertex 1.39068 0.906782 2.48075 + endloop + endfacet + facet normal 0.119068 -0.347604 0.930051 + outer loop + vertex 1.39388 0.910388 2.48168 + vertex 1.38932 0.909977 2.48211 + vertex 1.39068 0.906782 2.48075 + endloop + endfacet + facet normal 0.118386 -0.37564 0.919173 + outer loop + vertex 1.39817 0.903791 2.47855 + vertex 1.4022 0.907657 2.47961 + vertex 1.39758 0.907298 2.48006 + endloop + endfacet + facet normal 0.117721 -0.386406 0.914785 + outer loop + vertex 1.40915 0.904775 2.47751 + vertex 1.40791 0.90874 2.47934 + vertex 1.40339 0.90368 2.47779 + endloop + endfacet + facet normal 0.117521 -0.353421 0.928053 + outer loop + vertex 1.39758 0.907298 2.48006 + vertex 1.4022 0.907657 2.47961 + vertex 1.40084 0.910894 2.48102 + endloop + endfacet + facet normal 0.109258 -0.342147 0.933273 + outer loop + vertex 1.40426 0.914927 2.48209 + vertex 1.39865 0.913886 2.48237 + vertex 1.40084 0.910894 2.48102 + endloop + endfacet + facet normal 0.103856 -0.336771 0.935841 + outer loop + vertex 1.4089 0.915345 2.48173 + vertex 1.40853 0.919072 2.48311 + vertex 1.40426 0.914927 2.48209 + endloop + endfacet + facet normal 0.101673 -0.340055 0.934893 + outer loop + vertex 1.41211 0.914958 2.48124 + vertex 1.41371 0.918797 2.48246 + vertex 1.4089 0.915345 2.48173 + endloop + endfacet + facet normal 0.0994395 -0.339289 0.935411 + outer loop + vertex 1.41599 0.915813 2.48114 + vertex 1.41371 0.918797 2.48246 + vertex 1.41211 0.914958 2.48124 + endloop + endfacet + facet normal 0.101354 -0.348391 0.931854 + outer loop + vertex 1.41211 0.914958 2.48124 + vertex 1.41266 0.912222 2.48016 + vertex 1.41599 0.915813 2.48114 + endloop + endfacet + facet normal 0.107528 -0.358252 0.927412 + outer loop + vertex 1.4094 0.912593 2.48066 + vertex 1.40555 0.911688 2.48075 + vertex 1.40791 0.90874 2.47934 + endloop + endfacet + facet normal 0.102864 -0.349619 0.931228 + outer loop + vertex 1.41266 0.912222 2.48016 + vertex 1.41739 0.912565 2.47976 + vertex 1.41599 0.915813 2.48114 + endloop + endfacet + facet normal 0.0986308 -0.339853 0.935292 + outer loop + vertex 1.41932 0.919774 2.48222 + vertex 1.41371 0.918797 2.48246 + vertex 1.41599 0.915813 2.48114 + endloop + endfacet + facet normal 0.0983699 -0.330322 0.938728 + outer loop + vertex 1.424 0.92019 2.48188 + vertex 1.42332 0.923891 2.48325 + vertex 1.41932 0.919774 2.48222 + endloop + endfacet + facet normal 0.100993 -0.32869 0.939023 + outer loop + vertex 1.42723 0.919791 2.48139 + vertex 1.42869 0.923756 2.48262 + vertex 1.424 0.92019 2.48188 + endloop + endfacet + facet normal 0.103947 -0.341972 0.933943 + outer loop + vertex 1.42723 0.919791 2.48139 + vertex 1.42777 0.917032 2.48032 + vertex 1.43098 0.920597 2.48127 + endloop + endfacet + facet normal 0.100819 -0.353041 0.93016 + outer loop + vertex 1.42461 0.91743 2.48082 + vertex 1.42076 0.916558 2.4809 + vertex 1.42312 0.913599 2.47952 + endloop + endfacet + facet normal 0.101976 -0.340406 0.934732 + outer loop + vertex 1.42777 0.917032 2.48032 + vertex 1.43217 0.917269 2.47993 + vertex 1.43098 0.920597 2.48127 + endloop + endfacet + facet normal 0.100071 -0.340279 0.934984 + outer loop + vertex 1.43217 0.917269 2.47993 + vertex 1.43709 0.917669 2.47955 + vertex 1.43568 0.921147 2.48096 + endloop + endfacet + facet normal 0.100583 -0.342394 0.934157 + outer loop + vertex 1.43709 0.917669 2.47955 + vertex 1.44287 0.918741 2.47932 + vertex 1.44044 0.921723 2.48067 + endloop + endfacet + facet normal 0.106521 -0.343401 0.933129 + outer loop + vertex 1.44767 0.922408 2.48012 + vertex 1.44287 0.918741 2.47932 + vertex 1.44833 0.918847 2.47873 + endloop + endfacet + facet normal 0.10884 -0.336036 0.935539 + outer loop + vertex 1.4534 0.919062 2.47822 + vertex 1.45294 0.923375 2.47983 + vertex 1.44833 0.918847 2.47873 + endloop + endfacet + facet normal 0.113148 -0.33546 0.935235 + outer loop + vertex 1.4534 0.919062 2.47822 + vertex 1.45801 0.923187 2.47914 + vertex 1.45294 0.923375 2.47983 + endloop + endfacet + facet normal 0.111546 -0.319366 0.941044 + outer loop + vertex 1.46318 0.923601 2.47867 + vertex 1.46227 0.927395 2.48007 + vertex 1.45801 0.923187 2.47914 + endloop + endfacet + facet normal 0.110525 -0.316792 0.942033 + outer loop + vertex 1.4684 0.924003 2.47819 + vertex 1.4678 0.92844 2.47976 + vertex 1.46318 0.923601 2.47867 + endloop + endfacet + facet normal 0.111593 -0.316623 0.941964 + outer loop + vertex 1.4684 0.924003 2.47819 + vertex 1.47296 0.928209 2.47907 + vertex 1.4678 0.92844 2.47976 + endloop + endfacet + facet normal 0.115105 -0.31799 0.941081 + outer loop + vertex 1.47817 0.928633 2.47857 + vertex 1.47717 0.932426 2.47998 + vertex 1.47296 0.928209 2.47907 + endloop + endfacet + facet normal 0.118733 -0.320565 0.939756 + outer loop + vertex 1.48337 0.929071 2.47807 + vertex 1.48274 0.933497 2.47965 + vertex 1.47817 0.928633 2.47857 + endloop + endfacet + facet normal 0.118379 -0.320624 0.93978 + outer loop + vertex 1.48337 0.929071 2.47807 + vertex 1.48787 0.933288 2.47894 + vertex 1.48274 0.933497 2.47965 + endloop + endfacet + facet normal 0.118399 -0.3227 0.939067 + outer loop + vertex 1.49302 0.933719 2.47844 + vertex 1.49203 0.937495 2.47986 + vertex 1.48787 0.933288 2.47894 + endloop + endfacet + facet normal 0.11873 -0.3241 0.938543 + outer loop + vertex 1.49823 0.934186 2.47794 + vertex 1.49759 0.938609 2.47955 + vertex 1.49302 0.933719 2.47844 + endloop + endfacet + facet normal 0.120303 -0.323832 0.938435 + outer loop + vertex 1.49823 0.934186 2.47794 + vertex 1.50294 0.938544 2.47884 + vertex 1.49759 0.938609 2.47955 + endloop + endfacet + facet normal 0.123087 -0.319033 0.939717 + outer loop + vertex 1.50821 0.93882 2.47824 + vertex 1.50776 0.943342 2.47984 + vertex 1.50294 0.938544 2.47884 + endloop + endfacet + facet normal 0.12469 -0.318823 0.939577 + outer loop + vertex 1.50821 0.93882 2.47824 + vertex 1.5129 0.943202 2.47911 + vertex 1.50776 0.943342 2.47984 + endloop + endfacet + facet normal 0.120611 -0.313193 0.941999 + outer loop + vertex 1.51808 0.943668 2.4786 + vertex 1.51711 0.947474 2.47999 + vertex 1.5129 0.943202 2.47911 + endloop + endfacet + facet normal 0.114291 -0.320976 0.940166 + outer loop + vertex 1.52366 0.940305 2.47677 + vertex 1.52323 0.944075 2.47811 + vertex 1.51911 0.939888 2.47718 + endloop + endfacet + facet normal 0.109877 -0.321589 0.940483 + outer loop + vertex 1.52839 0.943825 2.47742 + vertex 1.52323 0.944075 2.47811 + vertex 1.52366 0.940305 2.47677 + endloop + endfacet + facet normal 0.1149 -0.314729 0.942201 + outer loop + vertex 1.51808 0.943668 2.4786 + vertex 1.52261 0.948514 2.47966 + vertex 1.51711 0.947474 2.47999 + endloop + endfacet + facet normal 0.110442 -0.315456 0.942492 + outer loop + vertex 1.52839 0.943825 2.47742 + vertex 1.52774 0.948268 2.47899 + vertex 1.52323 0.944075 2.47811 + endloop + endfacet + facet normal 0.109226 -0.315661 0.942564 + outer loop + vertex 1.52839 0.943825 2.47742 + vertex 1.53295 0.948669 2.47852 + vertex 1.52774 0.948268 2.47899 + endloop + endfacet + facet normal 0.109307 -0.31573 0.942532 + outer loop + vertex 1.53401 0.944856 2.47712 + vertex 1.53295 0.948669 2.47852 + vertex 1.52839 0.943825 2.47742 + endloop + endfacet + facet normal 0.110558 -0.323357 0.939796 + outer loop + vertex 1.53401 0.944856 2.47712 + vertex 1.52839 0.943825 2.47742 + vertex 1.53067 0.940788 2.47611 + endloop + endfacet + facet normal 0.110843 -0.323565 0.939691 + outer loop + vertex 1.5354 0.941568 2.47582 + vertex 1.53401 0.944856 2.47712 + vertex 1.53067 0.940788 2.47611 + endloop + endfacet + facet normal 0.112557 -0.335611 0.935252 + outer loop + vertex 1.53067 0.940788 2.47611 + vertex 1.53218 0.937495 2.47475 + vertex 1.5354 0.941568 2.47582 + endloop + endfacet + facet normal 0.109552 -0.333526 0.936354 + outer loop + vertex 1.53218 0.937495 2.47475 + vertex 1.53785 0.938556 2.47446 + vertex 1.5354 0.941568 2.47582 + endloop + endfacet + facet normal 0.111896 -0.331776 0.936698 + outer loop + vertex 1.53921 0.942478 2.47569 + vertex 1.5354 0.941568 2.47582 + vertex 1.53785 0.938556 2.47446 + endloop + endfacet + facet normal 0.106949 -0.330392 0.937765 + outer loop + vertex 1.53921 0.942478 2.47569 + vertex 1.53785 0.938556 2.47446 + vertex 1.5424 0.94211 2.47519 + endloop + endfacet + facet normal 0.108097 -0.323477 0.940041 + outer loop + vertex 1.5424 0.94211 2.47519 + vertex 1.54184 0.944883 2.47621 + vertex 1.53921 0.942478 2.47569 + endloop + endfacet + facet normal 0.108629 -0.324006 0.939798 + outer loop + vertex 1.54184 0.944883 2.47621 + vertex 1.53866 0.945273 2.47671 + vertex 1.53921 0.942478 2.47569 + endloop + endfacet + facet normal 0.108781 -0.323128 0.940083 + outer loop + vertex 1.54184 0.944883 2.47621 + vertex 1.54343 0.948793 2.47737 + vertex 1.53866 0.945273 2.47671 + endloop + endfacet + facet normal 0.104956 -0.318332 0.942151 + outer loop + vertex 1.54343 0.948793 2.47737 + vertex 1.5382 0.949062 2.47804 + vertex 1.53866 0.945273 2.47671 + endloop + endfacet + facet normal 0.109857 -0.317629 0.94183 + outer loop + vertex 1.53866 0.945273 2.47671 + vertex 1.5382 0.949062 2.47804 + vertex 1.53401 0.944856 2.47712 + endloop + endfacet + facet normal 0.105054 -0.317293 0.942491 + outer loop + vertex 1.54343 0.948793 2.47737 + vertex 1.54275 0.953239 2.47894 + vertex 1.5382 0.949062 2.47804 + endloop + endfacet + facet normal 0.101453 -0.313716 0.944081 + outer loop + vertex 1.5382 0.949062 2.47804 + vertex 1.54275 0.953239 2.47894 + vertex 1.53753 0.953524 2.4796 + endloop + endfacet + facet normal 0.107974 -0.31261 0.943725 + outer loop + vertex 1.5382 0.949062 2.47804 + vertex 1.53753 0.953524 2.4796 + vertex 1.53295 0.948669 2.47852 + endloop + endfacet + facet normal 0.101415 -0.314117 0.943952 + outer loop + vertex 1.54235 0.957043 2.48025 + vertex 1.53753 0.953524 2.4796 + vertex 1.54275 0.953239 2.47894 + endloop + endfacet + facet normal 0.0973392 -0.308932 0.94609 + outer loop + vertex 1.53917 0.95748 2.48072 + vertex 1.53753 0.953524 2.4796 + vertex 1.54235 0.957043 2.48025 + endloop + endfacet + facet normal 0.0960974 -0.315709 0.943977 + outer loop + vertex 1.54235 0.957043 2.48025 + vertex 1.54189 0.959859 2.48124 + vertex 1.53917 0.95748 2.48072 + endloop + endfacet + facet normal 0.0999994 -0.319787 0.942198 + outer loop + vertex 1.54189 0.959859 2.48124 + vertex 1.5387 0.960275 2.48172 + vertex 1.53917 0.95748 2.48072 + endloop + endfacet + facet normal 0.107723 -0.318371 0.941826 + outer loop + vertex 1.53917 0.95748 2.48072 + vertex 1.5387 0.960275 2.48172 + vertex 1.53535 0.956581 2.48086 + endloop + endfacet + facet normal 0.107094 -0.317859 0.94207 + outer loop + vertex 1.5387 0.960275 2.48172 + vertex 1.53409 0.95986 2.48211 + vertex 1.53535 0.956581 2.48086 + endloop + endfacet + facet normal 0.099302 -0.323682 0.940941 + outer loop + vertex 1.54189 0.959859 2.48124 + vertex 1.5435 0.963751 2.48241 + vertex 1.5387 0.960275 2.48172 + endloop + endfacet + facet normal 0.0978375 -0.321818 0.941733 + outer loop + vertex 1.5435 0.963751 2.48241 + vertex 1.53826 0.964038 2.48305 + vertex 1.5387 0.960275 2.48172 + endloop + endfacet + facet normal 0.106319 -0.312082 0.944088 + outer loop + vertex 1.53917 0.95748 2.48072 + vertex 1.53535 0.956581 2.48086 + vertex 1.53753 0.953524 2.4796 + endloop + endfacet + facet normal 0.0983452 -0.318438 0.942828 + outer loop + vertex 1.54343 0.948793 2.47737 + vertex 1.54801 0.953585 2.47851 + vertex 1.54275 0.953239 2.47894 + endloop + endfacet + facet normal 0.0984184 -0.320385 0.942161 + outer loop + vertex 1.54801 0.953585 2.47851 + vertex 1.54699 0.957386 2.47991 + vertex 1.54275 0.953239 2.47894 + endloop + endfacet + facet normal 0.0928274 -0.315198 0.944475 + outer loop + vertex 1.54275 0.953239 2.47894 + vertex 1.54699 0.957386 2.47991 + vertex 1.54235 0.957043 2.48025 + endloop + endfacet + facet normal 0.0930325 -0.319418 0.943036 + outer loop + vertex 1.54235 0.957043 2.48025 + vertex 1.54699 0.957386 2.47991 + vertex 1.54572 0.960682 2.48115 + endloop + endfacet + facet normal 0.0899014 -0.316804 0.944221 + outer loop + vertex 1.54189 0.959859 2.48124 + vertex 1.54235 0.957043 2.48025 + vertex 1.54572 0.960682 2.48115 + endloop + endfacet + facet normal 0.0907036 -0.320698 0.942829 + outer loop + vertex 1.54572 0.960682 2.48115 + vertex 1.5435 0.963751 2.48241 + vertex 1.54189 0.959859 2.48124 + endloop + endfacet + facet normal 0.0945479 -0.318109 0.943328 + outer loop + vertex 1.54913 0.964711 2.48217 + vertex 1.5435 0.963751 2.48241 + vertex 1.54572 0.960682 2.48115 + endloop + endfacet + facet normal 0.0922321 -0.316358 0.944146 + outer loop + vertex 1.55045 0.961406 2.48093 + vertex 1.54913 0.964711 2.48217 + vertex 1.54572 0.960682 2.48115 + endloop + endfacet + facet normal 0.0926707 -0.319554 0.943026 + outer loop + vertex 1.54572 0.960682 2.48115 + vertex 1.54699 0.957386 2.47991 + vertex 1.55045 0.961406 2.48093 + endloop + endfacet + facet normal 0.103633 -0.311935 0.944435 + outer loop + vertex 1.55378 0.965134 2.4818 + vertex 1.54913 0.964711 2.48217 + vertex 1.55045 0.961406 2.48093 + endloop + endfacet + facet normal 0.0938495 -0.313616 0.944901 + outer loop + vertex 1.54913 0.964711 2.48217 + vertex 1.54802 0.968556 2.48356 + vertex 1.5435 0.963751 2.48241 + endloop + endfacet + facet normal 0.0996794 -0.318563 0.942646 + outer loop + vertex 1.5435 0.963751 2.48241 + vertex 1.54802 0.968556 2.48356 + vertex 1.54276 0.968184 2.48399 + endloop + endfacet + facet normal 0.0995549 -0.315662 0.943635 + outer loop + vertex 1.54802 0.968556 2.48356 + vertex 1.54691 0.972361 2.48495 + vertex 1.54276 0.968184 2.48399 + endloop + endfacet + facet normal 0.100492 -0.316505 0.943253 + outer loop + vertex 1.54276 0.968184 2.48399 + vertex 1.54691 0.972361 2.48495 + vertex 1.54231 0.971957 2.4853 + endloop + endfacet + facet normal 0.1003 -0.3134 0.94431 + outer loop + vertex 1.54231 0.971957 2.4853 + vertex 1.54691 0.972361 2.48495 + vertex 1.54561 0.97563 2.48617 + endloop + endfacet + facet normal 0.0998472 -0.313032 0.944479 + outer loop + vertex 1.54183 0.97475 2.48628 + vertex 1.54231 0.971957 2.4853 + vertex 1.54561 0.97563 2.48617 + endloop + endfacet + facet normal 0.0985082 -0.307016 0.946593 + outer loop + vertex 1.54561 0.97563 2.48617 + vertex 1.54344 0.978688 2.48739 + vertex 1.54183 0.97475 2.48628 + endloop + endfacet + facet normal 0.108904 -0.30008 0.947677 + outer loop + vertex 1.54898 0.979735 2.48708 + vertex 1.54344 0.978688 2.48739 + vertex 1.54561 0.97563 2.48617 + endloop + endfacet + facet normal 0.108605 -0.298326 0.948265 + outer loop + vertex 1.54898 0.979735 2.48708 + vertex 1.54811 0.98364 2.48841 + vertex 1.54344 0.978688 2.48739 + endloop + endfacet + facet normal 0.110297 -0.308777 0.944718 + outer loop + vertex 1.54913 0.964711 2.48217 + vertex 1.55329 0.968997 2.48309 + vertex 1.54802 0.968556 2.48356 + endloop + endfacet + facet normal 0.110137 -0.305808 0.945701 + outer loop + vertex 1.55329 0.968997 2.48309 + vertex 1.55251 0.973515 2.48464 + vertex 1.54802 0.968556 2.48356 + endloop + endfacet + facet normal 0.136253 -0.300703 0.943935 + outer loop + vertex 1.55329 0.968997 2.48309 + vertex 1.55782 0.973503 2.48387 + vertex 1.55251 0.973515 2.48464 + endloop + endfacet + facet normal 0.136426 -0.297035 0.94507 + outer loop + vertex 1.55727 0.977406 2.48517 + vertex 1.55251 0.973515 2.48464 + vertex 1.55782 0.973503 2.48387 + endloop + endfacet + facet normal 0.156218 -0.293559 0.94309 + outer loop + vertex 1.55782 0.973503 2.48387 + vertex 1.56243 0.97854 2.48467 + vertex 1.55727 0.977406 2.48517 + endloop + endfacet + facet normal 0.155414 -0.289251 0.944553 + outer loop + vertex 1.55727 0.977406 2.48517 + vertex 1.56243 0.97854 2.48467 + vertex 1.56025 0.981302 2.48588 + endloop + endfacet + facet normal 0.159881 -0.29236 0.942849 + outer loop + vertex 1.55662 0.98009 2.48611 + vertex 1.55727 0.977406 2.48517 + vertex 1.56025 0.981302 2.48588 + endloop + endfacet + facet normal 0.157545 -0.284855 0.945535 + outer loop + vertex 1.56025 0.981302 2.48588 + vertex 1.55818 0.984023 2.48704 + vertex 1.55662 0.98009 2.48611 + endloop + endfacet + facet normal 0.143745 -0.280226 0.949111 + outer loop + vertex 1.55662 0.98009 2.48611 + vertex 1.55818 0.984023 2.48704 + vertex 1.55351 0.98027 2.48664 + endloop + endfacet + facet normal 0.142789 -0.289249 0.946544 + outer loop + vertex 1.55662 0.98009 2.48611 + vertex 1.55351 0.98027 2.48664 + vertex 1.55402 0.977525 2.48572 + endloop + endfacet + facet normal 0.125498 -0.292917 0.947866 + outer loop + vertex 1.55402 0.977525 2.48572 + vertex 1.55351 0.98027 2.48664 + vertex 1.55025 0.976468 2.4859 + endloop + endfacet + facet normal 0.128453 -0.304117 0.943935 + outer loop + vertex 1.55402 0.977525 2.48572 + vertex 1.55025 0.976468 2.4859 + vertex 1.55251 0.973515 2.48464 + endloop + endfacet + facet normal 0.116513 -0.31273 0.942669 + outer loop + vertex 1.54691 0.972361 2.48495 + vertex 1.55251 0.973515 2.48464 + vertex 1.55025 0.976468 2.4859 + endloop + endfacet + facet normal 0.127309 -0.294339 0.947184 + outer loop + vertex 1.55351 0.98027 2.48664 + vertex 1.54898 0.979735 2.48708 + vertex 1.55025 0.976468 2.4859 + endloop + endfacet + facet normal 0.11015 -0.301006 0.94724 + outer loop + vertex 1.55025 0.976468 2.4859 + vertex 1.54898 0.979735 2.48708 + vertex 1.54561 0.97563 2.48617 + endloop + endfacet + facet normal 0.111439 -0.309032 0.9445 + outer loop + vertex 1.54561 0.97563 2.48617 + vertex 1.54691 0.972361 2.48495 + vertex 1.55025 0.976468 2.4859 + endloop + endfacet + facet normal 0.126816 -0.288657 0.948997 + outer loop + vertex 1.55351 0.98027 2.48664 + vertex 1.55319 0.98403 2.48783 + vertex 1.54898 0.979735 2.48708 + endloop + endfacet + facet normal 0.131401 -0.292824 0.947095 + outer loop + vertex 1.54898 0.979735 2.48708 + vertex 1.55319 0.98403 2.48783 + vertex 1.54811 0.98364 2.48841 + endloop + endfacet + facet normal 0.131403 -0.292874 0.947079 + outer loop + vertex 1.55319 0.98403 2.48783 + vertex 1.55279 0.988244 2.48918 + vertex 1.54811 0.98364 2.48841 + endloop + endfacet + facet normal 0.136516 -0.297701 0.944848 + outer loop + vertex 1.54811 0.98364 2.48841 + vertex 1.55279 0.988244 2.48918 + vertex 1.54759 0.988202 2.48992 + endloop + endfacet + facet normal 0.113417 -0.30098 0.946862 + outer loop + vertex 1.54811 0.98364 2.48841 + vertex 1.54759 0.988202 2.48992 + vertex 1.54285 0.983227 2.48891 + endloop + endfacet + facet normal 0.114181 -0.301646 0.946558 + outer loop + vertex 1.54285 0.983227 2.48891 + vertex 1.54759 0.988202 2.48992 + vertex 1.54204 0.987107 2.49024 + endloop + endfacet + facet normal 0.115129 -0.306981 0.944726 + outer loop + vertex 1.54204 0.987107 2.49024 + vertex 1.54759 0.988202 2.48992 + vertex 1.54549 0.991195 2.49115 + endloop + endfacet + facet normal 0.124224 -0.300917 0.945525 + outer loop + vertex 1.54929 0.992192 2.49097 + vertex 1.54549 0.991195 2.49115 + vertex 1.54759 0.988202 2.48992 + endloop + endfacet + facet normal 0.146011 -0.308705 0.939884 + outer loop + vertex 1.54929 0.992192 2.49097 + vertex 1.54759 0.988202 2.48992 + vertex 1.55249 0.992056 2.49043 + endloop + endfacet + facet normal 0.147284 -0.295191 0.944018 + outer loop + vertex 1.55249 0.992056 2.49043 + vertex 1.55193 0.994746 2.49136 + vertex 1.54929 0.992192 2.49097 + endloop + endfacet + facet normal 0.138192 -0.286403 0.948091 + outer loop + vertex 1.55193 0.994746 2.49136 + vertex 1.54877 0.994999 2.49189 + vertex 1.54929 0.992192 2.49097 + endloop + endfacet + facet normal 0.139376 -0.277106 0.950677 + outer loop + vertex 1.55193 0.994746 2.49136 + vertex 1.55343 0.998785 2.49231 + vertex 1.54877 0.994999 2.49189 + endloop + endfacet + facet normal 0.141231 -0.279292 0.949763 + outer loop + vertex 1.55343 0.998785 2.49231 + vertex 1.54827 0.998936 2.49312 + vertex 1.54877 0.994999 2.49189 + endloop + endfacet + facet normal 0.119022 -0.282703 0.951794 + outer loop + vertex 1.54877 0.994999 2.49189 + vertex 1.54827 0.998936 2.49312 + vertex 1.54417 0.994529 2.49233 + endloop + endfacet + facet normal 0.119427 -0.288247 0.95008 + outer loop + vertex 1.54877 0.994999 2.49189 + vertex 1.54417 0.994529 2.49233 + vertex 1.54549 0.991195 2.49115 + endloop + endfacet + facet normal 0.104036 -0.294312 0.95003 + outer loop + vertex 1.54549 0.991195 2.49115 + vertex 1.54417 0.994529 2.49233 + vertex 1.54086 0.99041 2.49141 + endloop + endfacet + facet normal 0.141166 -0.28017 0.949514 + outer loop + vertex 1.55343 0.998785 2.49231 + vertex 1.55297 1.00357 2.49379 + vertex 1.54827 0.998936 2.49312 + endloop + endfacet + facet normal 0.141078 -0.280086 0.949552 + outer loop + vertex 1.54827 0.998936 2.49312 + vertex 1.55297 1.00357 2.49379 + vertex 1.54759 1.00363 2.49461 + endloop + endfacet + facet normal 0.120489 -0.283639 0.951331 + outer loop + vertex 1.54827 0.998936 2.49312 + vertex 1.54759 1.00363 2.49461 + vertex 1.54303 0.998446 2.49364 + endloop + endfacet + facet normal 0.120511 -0.283988 0.951224 + outer loop + vertex 1.54417 0.994529 2.49233 + vertex 1.54827 0.998936 2.49312 + vertex 1.54303 0.998446 2.49364 + endloop + endfacet + facet normal 0.125323 -0.287556 0.949529 + outer loop + vertex 1.54303 0.998446 2.49364 + vertex 1.54759 1.00363 2.49461 + vertex 1.54194 1.00227 2.49495 + endloop + endfacet + facet normal 0.126571 -0.293203 0.947635 + outer loop + vertex 1.54194 1.00227 2.49495 + vertex 1.54759 1.00363 2.49461 + vertex 1.54526 1.00645 2.49579 + endloop + endfacet + facet normal 0.128902 -0.294888 0.946797 + outer loop + vertex 1.54069 1.00547 2.49611 + vertex 1.54194 1.00227 2.49495 + vertex 1.54526 1.00645 2.49579 + endloop + endfacet + facet normal 0.128197 -0.291192 0.948036 + outer loop + vertex 1.54526 1.00645 2.49579 + vertex 1.54399 1.00962 2.49694 + vertex 1.54069 1.00547 2.49611 + endloop + endfacet + facet normal 0.145652 -0.284053 0.947681 + outer loop + vertex 1.54848 1.01029 2.49645 + vertex 1.54399 1.00962 2.49694 + vertex 1.54526 1.00645 2.49579 + endloop + endfacet + facet normal 0.137081 -0.277425 0.950917 + outer loop + vertex 1.54913 1.00777 2.49562 + vertex 1.54848 1.01029 2.49645 + vertex 1.54526 1.00645 2.49579 + endloop + endfacet + facet normal 0.147615 -0.27447 0.950198 + outer loop + vertex 1.55157 1.0104 2.496 + vertex 1.54848 1.01029 2.49645 + vertex 1.54913 1.00777 2.49562 + endloop + endfacet + facet normal 0.148673 -0.275389 0.949767 + outer loop + vertex 1.55297 1.00821 2.49515 + vertex 1.55157 1.0104 2.496 + vertex 1.54913 1.00777 2.49562 + endloop + endfacet + facet normal 0.149549 -0.286696 0.946277 + outer loop + vertex 1.54913 1.00777 2.49562 + vertex 1.54759 1.00363 2.49461 + vertex 1.55297 1.00821 2.49515 + endloop + endfacet + facet normal 0.152172 -0.273178 0.949851 + outer loop + vertex 1.55439 1.01183 2.49596 + vertex 1.55157 1.0104 2.496 + vertex 1.55297 1.00821 2.49515 + endloop + endfacet + facet normal 0.151059 -0.272806 0.950136 + outer loop + vertex 1.55439 1.01183 2.49596 + vertex 1.55297 1.00821 2.49515 + vertex 1.55756 1.01202 2.49551 + endloop + endfacet + facet normal 0.150945 -0.267046 0.951789 + outer loop + vertex 1.55756 1.01202 2.49551 + vertex 1.55679 1.01446 2.49632 + vertex 1.55439 1.01183 2.49596 + endloop + endfacet + facet normal 0.150709 -0.266844 0.951883 + outer loop + vertex 1.55679 1.01446 2.49632 + vertex 1.55294 1.01397 2.49679 + vertex 1.55439 1.01183 2.49596 + endloop + endfacet + facet normal 0.150339 -0.262873 0.953045 + outer loop + vertex 1.55679 1.01446 2.49632 + vertex 1.55827 1.01853 2.49721 + vertex 1.55294 1.01397 2.49679 + endloop + endfacet + facet normal 0.157027 -0.27038 0.949862 + outer loop + vertex 1.55827 1.01853 2.49721 + vertex 1.5529 1.01859 2.49811 + vertex 1.55294 1.01397 2.49679 + endloop + endfacet + facet normal 0.156234 -0.270422 0.949981 + outer loop + vertex 1.55294 1.01397 2.49679 + vertex 1.5529 1.01859 2.49811 + vertex 1.54813 1.01396 2.49758 + endloop + endfacet + facet normal 0.155943 -0.276801 0.948189 + outer loop + vertex 1.55294 1.01397 2.49679 + vertex 1.54813 1.01396 2.49758 + vertex 1.54848 1.01029 2.49645 + endloop + endfacet + facet normal 0.166981 -0.280931 0.94509 + outer loop + vertex 1.54813 1.01396 2.49758 + vertex 1.5529 1.01859 2.49811 + vertex 1.54763 1.01839 2.49898 + endloop + endfacet + facet normal 0.150478 -0.283449 0.947108 + outer loop + vertex 1.54813 1.01396 2.49758 + vertex 1.54763 1.01839 2.49898 + vertex 1.54298 1.01371 2.49832 + endloop + endfacet + facet normal 0.150476 -0.28314 0.9472 + outer loop + vertex 1.54399 1.00962 2.49694 + vertex 1.54813 1.01396 2.49758 + vertex 1.54298 1.01371 2.49832 + endloop + endfacet + facet normal 0.134875 -0.268894 0.95368 + outer loop + vertex 1.54298 1.01371 2.49832 + vertex 1.54763 1.01839 2.49898 + vertex 1.54222 1.01875 2.49985 + endloop + endfacet + facet normal 0.105584 -0.274029 0.955908 + outer loop + vertex 1.54298 1.01371 2.49832 + vertex 1.54222 1.01875 2.49985 + vertex 1.53751 1.01387 2.49897 + endloop + endfacet + facet normal -0.0782576 -0.103073 0.99159 + outer loop + vertex 1.53751 1.01387 2.49897 + vertex 1.54222 1.01875 2.49985 + vertex 1.5361 1.01931 2.49943 + endloop + endfacet + facet normal -0.0974898 -0.360861 0.92751 + outer loop + vertex 1.5361 1.01931 2.49943 + vertex 1.54222 1.01875 2.49985 + vertex 1.54059 1.02182 2.50087 + endloop + endfacet + facet normal 0.0363109 -0.298639 0.953675 + outer loop + vertex 1.54389 1.0225 2.50096 + vertex 1.54059 1.02182 2.50087 + vertex 1.54222 1.01875 2.49985 + endloop + endfacet + facet normal 0.161599 -0.345833 0.924276 + outer loop + vertex 1.54389 1.0225 2.50096 + vertex 1.54222 1.01875 2.49985 + vertex 1.54712 1.02238 2.50035 + endloop + endfacet + facet normal 0.166911 -0.291576 0.941873 + outer loop + vertex 1.54712 1.02238 2.50035 + vertex 1.54646 1.02494 2.50126 + vertex 1.54389 1.0225 2.50096 + endloop + endfacet + facet normal 0.0762514 -0.200703 0.97668 + outer loop + vertex 1.54646 1.02494 2.50126 + vertex 1.54352 1.02488 2.50148 + vertex 1.54389 1.0225 2.50096 + endloop + endfacet + facet normal 0.0758653 -0.15708 0.984668 + outer loop + vertex 1.54646 1.02494 2.50126 + vertex 1.54796 1.02866 2.50174 + vertex 1.54352 1.02488 2.50148 + endloop + endfacet + facet normal -0.14087 0.0975716 0.985208 + outer loop + vertex 1.54796 1.02866 2.50174 + vertex 1.54309 1.02761 2.50115 + vertex 1.54352 1.02488 2.50148 + endloop + endfacet + facet normal -0.114148 -0.0306733 0.99299 + outer loop + vertex 1.54309 1.02761 2.50115 + vertex 1.54796 1.02866 2.50174 + vertex 1.54757 1.03269 2.50182 + endloop + endfacet + facet normal 0.15645 -0.187769 0.969673 + outer loop + vertex 1.55021 1.02633 2.50093 + vertex 1.54796 1.02866 2.50174 + vertex 1.54646 1.02494 2.50126 + endloop + endfacet + facet normal 0.118395 -0.223758 0.967427 + outer loop + vertex 1.55318 1.03031 2.50148 + vertex 1.54796 1.02866 2.50174 + vertex 1.55021 1.02633 2.50093 + endloop + endfacet + facet normal 0.18537 -0.270752 0.944633 + outer loop + vertex 1.55411 1.02791 2.50061 + vertex 1.55318 1.03031 2.50148 + vertex 1.55021 1.02633 2.50093 + endloop + endfacet + facet normal 0.188627 -0.279457 0.941448 + outer loop + vertex 1.55411 1.02791 2.50061 + vertex 1.55021 1.02633 2.50093 + vertex 1.55255 1.02362 2.49965 + endloop + endfacet + facet normal 0.180693 -0.27708 0.943704 + outer loop + vertex 1.55411 1.02791 2.50061 + vertex 1.55255 1.02362 2.49965 + vertex 1.55798 1.02835 2.5 + endloop + endfacet + facet normal 0.180583 -0.275403 0.944216 + outer loop + vertex 1.55798 1.02835 2.5 + vertex 1.55651 1.03063 2.50095 + vertex 1.55411 1.02791 2.50061 + endloop + endfacet + facet normal 0.178459 -0.276772 0.944219 + outer loop + vertex 1.55933 1.03207 2.50084 + vertex 1.55651 1.03063 2.50095 + vertex 1.55798 1.02835 2.5 + endloop + endfacet + facet normal 0.169256 -0.273999 0.946719 + outer loop + vertex 1.55933 1.03207 2.50084 + vertex 1.55798 1.02835 2.5 + vertex 1.56251 1.0322 2.50031 + endloop + endfacet + facet normal 0.169241 -0.276719 0.94593 + outer loop + vertex 1.56251 1.0322 2.50031 + vertex 1.56167 1.0347 2.50119 + vertex 1.55933 1.03207 2.50084 + endloop + endfacet + facet normal 0.175267 -0.281726 0.943352 + outer loop + vertex 1.56167 1.0347 2.50119 + vertex 1.55774 1.03417 2.50176 + vertex 1.55933 1.03207 2.50084 + endloop + endfacet + facet normal 0.174552 -0.273889 0.945789 + outer loop + vertex 1.56167 1.0347 2.50119 + vertex 1.56309 1.03875 2.5021 + vertex 1.55774 1.03417 2.50176 + endloop + endfacet + facet normal 0.162935 -0.260762 0.951554 + outer loop + vertex 1.56309 1.03875 2.5021 + vertex 1.55765 1.03859 2.50299 + vertex 1.55774 1.03417 2.50176 + endloop + endfacet + facet normal 0.134405 -0.262476 0.955532 + outer loop + vertex 1.55774 1.03417 2.50176 + vertex 1.55765 1.03859 2.50299 + vertex 1.55269 1.03377 2.50236 + endloop + endfacet + facet normal 0.0491374 -0.178301 0.982748 + outer loop + vertex 1.55269 1.03377 2.50236 + vertex 1.55765 1.03859 2.50299 + vertex 1.55265 1.03801 2.50313 + endloop + endfacet + facet normal 0.0568402 -0.24899 0.966837 + outer loop + vertex 1.55765 1.03859 2.50299 + vertex 1.55745 1.0431 2.50416 + vertex 1.55265 1.03801 2.50313 + endloop + endfacet + facet normal -0.0977822 -0.108086 0.989321 + outer loop + vertex 1.55265 1.03801 2.50313 + vertex 1.55745 1.0431 2.50416 + vertex 1.55266 1.04281 2.50366 + endloop + endfacet + facet normal -0.0807941 -0.311293 0.946873 + outer loop + vertex 1.55725 1.04704 2.50544 + vertex 1.55266 1.04281 2.50366 + vertex 1.55745 1.0431 2.50416 + endloop + endfacet + facet normal 0.176943 -0.29609 0.938627 + outer loop + vertex 1.55745 1.0431 2.50416 + vertex 1.56241 1.04856 2.50495 + vertex 1.55725 1.04704 2.50544 + endloop + endfacet + facet normal 0.177501 -0.298237 0.937842 + outer loop + vertex 1.55725 1.04704 2.50544 + vertex 1.56241 1.04856 2.50495 + vertex 1.56028 1.05116 2.50618 + endloop + endfacet + facet normal 0.192431 -0.308085 0.931694 + outer loop + vertex 1.55684 1.04969 2.5064 + vertex 1.55725 1.04704 2.50544 + vertex 1.56028 1.05116 2.50618 + endloop + endfacet + facet normal 0.153 -0.211262 0.96538 + outer loop + vertex 1.56028 1.05116 2.50618 + vertex 1.55834 1.05374 2.50705 + vertex 1.55684 1.04969 2.5064 + endloop + endfacet + facet normal -0.119154 -0.113755 0.986338 + outer loop + vertex 1.55684 1.04969 2.5064 + vertex 1.55834 1.05374 2.50705 + vertex 1.55441 1.04993 2.50613 + endloop + endfacet + facet normal -0.124686 -0.181958 0.975369 + outer loop + vertex 1.55684 1.04969 2.5064 + vertex 1.55441 1.04993 2.50613 + vertex 1.55457 1.04707 2.50562 + endloop + endfacet + facet normal -0.453318 -0.181246 0.872727 + outer loop + vertex 1.55457 1.04707 2.50562 + vertex 1.55441 1.04993 2.50613 + vertex 1.55243 1.04657 2.50441 + endloop + endfacet + facet normal -0.447691 -0.201591 0.871168 + outer loop + vertex 1.55457 1.04707 2.50562 + vertex 1.55243 1.04657 2.50441 + vertex 1.55266 1.04281 2.50366 + endloop + endfacet + facet normal 0.158258 -0.2073 0.965392 + outer loop + vertex 1.56321 1.05517 2.50656 + vertex 1.55834 1.05374 2.50705 + vertex 1.56028 1.05116 2.50618 + endloop + endfacet + facet normal 0.216378 -0.247874 0.944319 + outer loop + vertex 1.56403 1.05283 2.50575 + vertex 1.56321 1.05517 2.50656 + vertex 1.56028 1.05116 2.50618 + endloop + endfacet + facet normal 0.219274 -0.246737 0.943949 + outer loop + vertex 1.56642 1.05555 2.50591 + vertex 1.56321 1.05517 2.50656 + vertex 1.56403 1.05283 2.50575 + endloop + endfacet + facet normal 0.204686 -0.234343 0.950362 + outer loop + vertex 1.56784 1.05337 2.50507 + vertex 1.56642 1.05555 2.50591 + vertex 1.56403 1.05283 2.50575 + endloop + endfacet + facet normal 0.206833 -0.25731 0.943934 + outer loop + vertex 1.56403 1.05283 2.50575 + vertex 1.56241 1.04856 2.50495 + vertex 1.56784 1.05337 2.50507 + endloop + endfacet + facet normal 0.191596 -0.240306 0.951601 + outer loop + vertex 1.56784 1.05337 2.50507 + vertex 1.56241 1.04856 2.50495 + vertex 1.5677 1.04856 2.50388 + endloop + endfacet + facet normal 0.174531 -0.24057 0.954811 + outer loop + vertex 1.5677 1.04856 2.50388 + vertex 1.57265 1.05335 2.50418 + vertex 1.56784 1.05337 2.50507 + endloop + endfacet + facet normal 0.174647 -0.238198 0.955385 + outer loop + vertex 1.57236 1.05728 2.50522 + vertex 1.56784 1.05337 2.50507 + vertex 1.57265 1.05335 2.50418 + endloop + endfacet + facet normal 0.160132 -0.239829 0.957518 + outer loop + vertex 1.57265 1.05335 2.50418 + vertex 1.57753 1.05866 2.5047 + vertex 1.57236 1.05728 2.50522 + endloop + endfacet + facet normal 0.161472 -0.245441 0.955869 + outer loop + vertex 1.57236 1.05728 2.50522 + vertex 1.57753 1.05866 2.5047 + vertex 1.57528 1.06128 2.50575 + endloop + endfacet + facet normal 0.162098 -0.244913 0.955898 + outer loop + vertex 1.57908 1.06291 2.50552 + vertex 1.57528 1.06128 2.50575 + vertex 1.57753 1.05866 2.5047 + endloop + endfacet + facet normal 0.15684 -0.243247 0.9572 + outer loop + vertex 1.57908 1.06291 2.50552 + vertex 1.57753 1.05866 2.5047 + vertex 1.5829 1.06341 2.50502 + endloop + endfacet + facet normal 0.156348 -0.238063 0.958583 + outer loop + vertex 1.5829 1.06341 2.50502 + vertex 1.58146 1.06566 2.50582 + vertex 1.57908 1.06291 2.50552 + endloop + endfacet + facet normal 0.15329 -0.240021 0.958589 + outer loop + vertex 1.58429 1.06712 2.50573 + vertex 1.58146 1.06566 2.50582 + vertex 1.5829 1.06341 2.50502 + endloop + endfacet + facet normal 0.120828 -0.229256 0.965838 + outer loop + vertex 1.58429 1.06712 2.50573 + vertex 1.5829 1.06341 2.50502 + vertex 1.58741 1.06702 2.50532 + endloop + endfacet + facet normal 0.11958 -0.248727 0.961164 + outer loop + vertex 1.58741 1.06702 2.50532 + vertex 1.58671 1.06965 2.50608 + vertex 1.58429 1.06712 2.50573 + endloop + endfacet + facet normal 0.140948 -0.268053 0.953038 + outer loop + vertex 1.58671 1.06965 2.50608 + vertex 1.58275 1.0692 2.50655 + vertex 1.58429 1.06712 2.50573 + endloop + endfacet + facet normal 0.142805 -0.292054 0.94568 + outer loop + vertex 1.58671 1.06965 2.50608 + vertex 1.58821 1.07359 2.50707 + vertex 1.58275 1.0692 2.50655 + endloop + endfacet + facet normal 0.111031 -0.25429 0.960733 + outer loop + vertex 1.58821 1.07359 2.50707 + vertex 1.58273 1.07372 2.50774 + vertex 1.58275 1.0692 2.50655 + endloop + endfacet + facet normal 0.154769 -0.252628 0.955105 + outer loop + vertex 1.58275 1.0692 2.50655 + vertex 1.58273 1.07372 2.50774 + vertex 1.57775 1.06898 2.50729 + endloop + endfacet + facet normal 0.15472 -0.244673 0.957182 + outer loop + vertex 1.58275 1.0692 2.50655 + vertex 1.57775 1.06898 2.50729 + vertex 1.57819 1.0653 2.50628 + endloop + endfacet + facet normal 0.167731 -0.242661 0.955501 + outer loop + vertex 1.57819 1.0653 2.50628 + vertex 1.57775 1.06898 2.50729 + vertex 1.57292 1.06373 2.50681 + endloop + endfacet + facet normal 0.169749 -0.244444 0.95469 + outer loop + vertex 1.57292 1.06373 2.50681 + vertex 1.57775 1.06898 2.50729 + vertex 1.57266 1.06851 2.50808 + endloop + endfacet + facet normal 0.185156 -0.242963 0.952201 + outer loop + vertex 1.57292 1.06373 2.50681 + vertex 1.57266 1.06851 2.50808 + vertex 1.56762 1.06353 2.50779 + endloop + endfacet + facet normal 0.185078 -0.250658 0.950219 + outer loop + vertex 1.57292 1.06373 2.50681 + vertex 1.56762 1.06353 2.50779 + vertex 1.56766 1.05906 2.5066 + endloop + endfacet + facet normal 0.19815 -0.249891 0.947782 + outer loop + vertex 1.56766 1.05906 2.5066 + vertex 1.56762 1.06353 2.50779 + vertex 1.56276 1.05876 2.50755 + endloop + endfacet + facet normal 0.198024 -0.237681 0.950944 + outer loop + vertex 1.56766 1.05906 2.5066 + vertex 1.56276 1.05876 2.50755 + vertex 1.56321 1.05517 2.50656 + endloop + endfacet + facet normal 0.178582 -0.230389 0.956572 + outer loop + vertex 1.56276 1.05876 2.50755 + vertex 1.56762 1.06353 2.50779 + vertex 1.56251 1.0633 2.50869 + endloop + endfacet + facet normal 0.119506 -0.235643 0.964464 + outer loop + vertex 1.56276 1.05876 2.50755 + vertex 1.56251 1.0633 2.50869 + vertex 1.55781 1.05846 2.50809 + endloop + endfacet + facet normal 0.118278 -0.201012 0.972422 + outer loop + vertex 1.55834 1.05374 2.50705 + vertex 1.56276 1.05876 2.50755 + vertex 1.55781 1.05846 2.50809 + endloop + endfacet + facet normal -0.0786577 -0.223009 0.971638 + outer loop + vertex 1.55834 1.05374 2.50705 + vertex 1.55781 1.05846 2.50809 + vertex 1.55403 1.05402 2.50676 + endloop + endfacet + facet normal -0.0752829 -0.158544 0.984478 + outer loop + vertex 1.55834 1.05374 2.50705 + vertex 1.55403 1.05402 2.50676 + vertex 1.55441 1.04993 2.50613 + endloop + endfacet + facet normal -0.0922796 -0.211798 0.972947 + outer loop + vertex 1.55403 1.05402 2.50676 + vertex 1.55781 1.05846 2.50809 + vertex 1.55288 1.05905 2.50775 + endloop + endfacet + facet normal -0.0961706 -0.249745 0.963524 + outer loop + vertex 1.55781 1.05846 2.50809 + vertex 1.55745 1.06325 2.50929 + vertex 1.55288 1.05905 2.50775 + endloop + endfacet + facet normal -0.0217927 -0.324171 0.945748 + outer loop + vertex 1.55288 1.05905 2.50775 + vertex 1.55745 1.06325 2.50929 + vertex 1.55288 1.06442 2.50959 + endloop + endfacet + facet normal -0.0164032 -0.304775 0.952283 + outer loop + vertex 1.55714 1.06715 2.51054 + vertex 1.55288 1.06442 2.50959 + vertex 1.55745 1.06325 2.50929 + endloop + endfacet + facet normal 0.168613 -0.286944 0.942991 + outer loop + vertex 1.55745 1.06325 2.50929 + vertex 1.56241 1.06832 2.50995 + vertex 1.55714 1.06715 2.51054 + endloop + endfacet + facet normal 0.164176 -0.262919 0.950747 + outer loop + vertex 1.55714 1.06715 2.51054 + vertex 1.56241 1.06832 2.50995 + vertex 1.56019 1.07093 2.51106 + endloop + endfacet + facet normal 0.185357 -0.27887 0.942271 + outer loop + vertex 1.55642 1.0697 2.51143 + vertex 1.55714 1.06715 2.51054 + vertex 1.56019 1.07093 2.51106 + endloop + endfacet + facet normal 0.171799 -0.232783 0.957234 + outer loop + vertex 1.56019 1.07093 2.51106 + vertex 1.55807 1.07371 2.51211 + vertex 1.55642 1.0697 2.51143 + endloop + endfacet + facet normal 0.0738623 -0.195941 0.97783 + outer loop + vertex 1.55642 1.0697 2.51143 + vertex 1.55807 1.07371 2.51211 + vertex 1.55324 1.07039 2.51181 + endloop + endfacet + facet normal 0.0641161 -0.236448 0.969527 + outer loop + vertex 1.55642 1.0697 2.51143 + vertex 1.55324 1.07039 2.51181 + vertex 1.55407 1.06749 2.51105 + endloop + endfacet + facet normal -0.0923166 -0.277572 0.956259 + outer loop + vertex 1.55407 1.06749 2.51105 + vertex 1.55324 1.07039 2.51181 + vertex 1.55157 1.06725 2.51074 + endloop + endfacet + facet normal -0.0744903 -0.404587 0.911461 + outer loop + vertex 1.55407 1.06749 2.51105 + vertex 1.55157 1.06725 2.51074 + vertex 1.55288 1.06442 2.50959 + endloop + endfacet + facet normal 0.115717 -0.255258 0.959923 + outer loop + vertex 1.55807 1.07371 2.51211 + vertex 1.55417 1.07448 2.51279 + vertex 1.55324 1.07039 2.51181 + endloop + endfacet + facet normal 0.120674 -0.234287 0.964649 + outer loop + vertex 1.55807 1.07371 2.51211 + vertex 1.55778 1.07836 2.51328 + vertex 1.55417 1.07448 2.51279 + endloop + endfacet + facet normal 0.106808 -0.221965 0.969187 + outer loop + vertex 1.55417 1.07448 2.51279 + vertex 1.55778 1.07836 2.51328 + vertex 1.55328 1.07824 2.51375 + endloop + endfacet + facet normal 0.106848 -0.238352 0.965283 + outer loop + vertex 1.55778 1.07836 2.51328 + vertex 1.55763 1.08303 2.51445 + vertex 1.55328 1.07824 2.51375 + endloop + endfacet + facet normal 0.159817 -0.283524 0.945554 + outer loop + vertex 1.55328 1.07824 2.51375 + vertex 1.55763 1.08303 2.51445 + vertex 1.55305 1.08305 2.51523 + endloop + endfacet + facet normal -0.12405 -0.297588 0.946601 + outer loop + vertex 1.55305 1.08305 2.51523 + vertex 1.54907 1.07883 2.51338 + vertex 1.55328 1.07824 2.51375 + endloop + endfacet + facet normal 0.162219 -0.234909 0.958386 + outer loop + vertex 1.55797 1.08785 2.51557 + vertex 1.55305 1.08305 2.51523 + vertex 1.55763 1.08303 2.51445 + endloop + endfacet + facet normal 0.191971 -0.235665 0.952685 + outer loop + vertex 1.55763 1.08303 2.51445 + vertex 1.56261 1.08801 2.51468 + vertex 1.55797 1.08785 2.51557 + endloop + endfacet + facet normal 0.192124 -0.220019 0.956389 + outer loop + vertex 1.56263 1.09199 2.51559 + vertex 1.55797 1.08785 2.51557 + vertex 1.56261 1.08801 2.51468 + endloop + endfacet + facet normal 0.173225 -0.220725 0.95983 + outer loop + vertex 1.56261 1.08801 2.51468 + vertex 1.56771 1.09344 2.51501 + vertex 1.56263 1.09199 2.51559 + endloop + endfacet + facet normal 0.173869 -0.223266 0.959126 + outer loop + vertex 1.56263 1.09199 2.51559 + vertex 1.56771 1.09344 2.51501 + vertex 1.56565 1.09602 2.51598 + endloop + endfacet + facet normal 0.174572 -0.22377 0.95888 + outer loop + vertex 1.56186 1.09441 2.51629 + vertex 1.56263 1.09199 2.51559 + vertex 1.56565 1.09602 2.51598 + endloop + endfacet + facet normal 0.176193 -0.227836 0.957626 + outer loop + vertex 1.56565 1.09602 2.51598 + vertex 1.56319 1.09844 2.51701 + vertex 1.56186 1.09441 2.51629 + endloop + endfacet + facet normal 0.191702 -0.232222 0.953585 + outer loop + vertex 1.56186 1.09441 2.51629 + vertex 1.56319 1.09844 2.51701 + vertex 1.55774 1.09359 2.51692 + endloop + endfacet + facet normal 0.189791 -0.220163 0.956822 + outer loop + vertex 1.56186 1.09441 2.51629 + vertex 1.55774 1.09359 2.51692 + vertex 1.55943 1.09164 2.51614 + endloop + endfacet + facet normal 0.200913 -0.210466 0.956733 + outer loop + vertex 1.55943 1.09164 2.51614 + vertex 1.55774 1.09359 2.51692 + vertex 1.55644 1.08984 2.51637 + endloop + endfacet + facet normal 0.2077 -0.222243 0.952612 + outer loop + vertex 1.55943 1.09164 2.51614 + vertex 1.55644 1.08984 2.51637 + vertex 1.55797 1.08785 2.51557 + endloop + endfacet + facet normal 0.207527 -0.222377 0.952618 + outer loop + vertex 1.55797 1.08785 2.51557 + vertex 1.55644 1.08984 2.51637 + vertex 1.55423 1.08693 2.51617 + endloop + endfacet + facet normal 0.147581 -0.17813 0.972877 + outer loop + vertex 1.55644 1.08984 2.51637 + vertex 1.55276 1.08886 2.51675 + vertex 1.55423 1.08693 2.51617 + endloop + endfacet + facet normal 0.132665 -0.189475 0.972882 + outer loop + vertex 1.55423 1.08693 2.51617 + vertex 1.55276 1.08886 2.51675 + vertex 1.55151 1.0851 2.51619 + endloop + endfacet + facet normal 0.198987 -0.288288 0.93664 + outer loop + vertex 1.55423 1.08693 2.51617 + vertex 1.55151 1.0851 2.51619 + vertex 1.55305 1.08305 2.51523 + endloop + endfacet + facet normal 0.113706 -0.349014 0.930194 + outer loop + vertex 1.55305 1.08305 2.51523 + vertex 1.55151 1.0851 2.51619 + vertex 1.54969 1.08247 2.51542 + endloop + endfacet + facet normal 0.135803 -0.501927 0.854182 + outer loop + vertex 1.54969 1.08247 2.51542 + vertex 1.54907 1.07883 2.51338 + vertex 1.55305 1.08305 2.51523 + endloop + endfacet + facet normal -0.247506 -0.441156 0.862625 + outer loop + vertex 1.54969 1.08247 2.51542 + vertex 1.54758 1.08186 2.5145 + vertex 1.54907 1.07883 2.51338 + endloop + endfacet + facet normal -0.309579 -0.289677 0.905676 + outer loop + vertex 1.54969 1.08247 2.51542 + vertex 1.54909 1.08497 2.51602 + vertex 1.54758 1.08186 2.5145 + endloop + endfacet + facet normal -0.0549237 -0.243465 0.968353 + outer loop + vertex 1.55151 1.0851 2.51619 + vertex 1.54909 1.08497 2.51602 + vertex 1.54969 1.08247 2.51542 + endloop + endfacet + facet normal -0.0627039 -0.127162 0.989898 + outer loop + vertex 1.55151 1.0851 2.51619 + vertex 1.55276 1.08886 2.51675 + vertex 1.54909 1.08497 2.51602 + endloop + endfacet + facet normal -0.0374767 -0.150595 0.987885 + outer loop + vertex 1.55276 1.08886 2.51675 + vertex 1.54865 1.08878 2.51658 + vertex 1.54909 1.08497 2.51602 + endloop + endfacet + facet normal -0.0366329 -0.183524 0.982332 + outer loop + vertex 1.55276 1.08886 2.51675 + vertex 1.5527 1.0935 2.51761 + vertex 1.54865 1.08878 2.51658 + endloop + endfacet + facet normal -0.01627 -0.200395 0.97958 + outer loop + vertex 1.54865 1.08878 2.51658 + vertex 1.5527 1.0935 2.51761 + vertex 1.5478 1.09381 2.5176 + endloop + endfacet + facet normal -0.0179659 -0.227511 0.97361 + outer loop + vertex 1.5527 1.0935 2.51761 + vertex 1.55259 1.09841 2.51876 + vertex 1.5478 1.09381 2.5176 + endloop + endfacet + facet normal 0.0471648 -0.290911 0.955587 + outer loop + vertex 1.5478 1.09381 2.5176 + vertex 1.55259 1.09841 2.51876 + vertex 1.54869 1.09882 2.51908 + endloop + endfacet + facet normal 0.0526117 -0.248531 0.967194 + outer loop + vertex 1.55259 1.09841 2.51876 + vertex 1.5524 1.10339 2.52005 + vertex 1.54869 1.09882 2.51908 + endloop + endfacet + facet normal 0.0312553 -0.23227 0.972149 + outer loop + vertex 1.54869 1.09882 2.51908 + vertex 1.5524 1.10339 2.52005 + vertex 1.54731 1.10198 2.51988 + endloop + endfacet + facet normal 0.0613517 -0.336807 0.939573 + outer loop + vertex 1.54731 1.10198 2.51988 + vertex 1.5524 1.10339 2.52005 + vertex 1.55004 1.10605 2.52116 + endloop + endfacet + facet normal -0.0273659 -0.283192 0.958673 + outer loop + vertex 1.54598 1.10538 2.52084 + vertex 1.54731 1.10198 2.51988 + vertex 1.55004 1.10605 2.52116 + endloop + endfacet + facet normal -0.0263579 -0.288572 0.957095 + outer loop + vertex 1.55004 1.10605 2.52116 + vertex 1.54887 1.10922 2.52208 + vertex 1.54598 1.10538 2.52084 + endloop + endfacet + facet normal 0.135516 -0.230549 0.963578 + outer loop + vertex 1.55318 1.11001 2.52166 + vertex 1.54887 1.10922 2.52208 + vertex 1.55004 1.10605 2.52116 + endloop + endfacet + facet normal 0.156982 -0.24666 0.956303 + outer loop + vertex 1.55392 1.10757 2.52091 + vertex 1.55318 1.11001 2.52166 + vertex 1.55004 1.10605 2.52116 + endloop + endfacet + facet normal 0.206914 -0.229863 0.950973 + outer loop + vertex 1.55646 1.11041 2.52104 + vertex 1.55318 1.11001 2.52166 + vertex 1.55392 1.10757 2.52091 + endloop + endfacet + facet normal 0.200939 -0.224633 0.953501 + outer loop + vertex 1.55795 1.10831 2.52024 + vertex 1.55646 1.11041 2.52104 + vertex 1.55392 1.10757 2.52091 + endloop + endfacet + facet normal 0.206976 -0.269547 0.940481 + outer loop + vertex 1.55392 1.10757 2.52091 + vertex 1.5524 1.10339 2.52005 + vertex 1.55795 1.10831 2.52024 + endloop + endfacet + facet normal 0.162824 -0.220522 0.961695 + outer loop + vertex 1.55795 1.10831 2.52024 + vertex 1.5524 1.10339 2.52005 + vertex 1.55757 1.10328 2.51915 + endloop + endfacet + facet normal 0.181659 -0.221167 0.958168 + outer loop + vertex 1.55757 1.10328 2.51915 + vertex 1.56277 1.10823 2.51931 + vertex 1.55795 1.10831 2.52024 + endloop + endfacet + facet normal 0.182111 -0.213303 0.959863 + outer loop + vertex 1.56317 1.11302 2.52029 + vertex 1.55795 1.10831 2.52024 + vertex 1.56277 1.10823 2.51931 + endloop + endfacet + facet normal 0.170675 -0.21279 0.962076 + outer loop + vertex 1.56277 1.10823 2.51931 + vertex 1.56774 1.11318 2.51952 + vertex 1.56317 1.11302 2.52029 + endloop + endfacet + facet normal 0.170667 -0.214794 0.961632 + outer loop + vertex 1.56762 1.11713 2.52042 + vertex 1.56317 1.11302 2.52029 + vertex 1.56774 1.11318 2.51952 + endloop + endfacet + facet normal 0.163924 -0.215241 0.962705 + outer loop + vertex 1.56774 1.11318 2.51952 + vertex 1.57261 1.11864 2.51991 + vertex 1.56762 1.11713 2.52042 + endloop + endfacet + facet normal 0.161815 -0.207579 0.964742 + outer loop + vertex 1.56762 1.11713 2.52042 + vertex 1.57261 1.11864 2.51991 + vertex 1.57046 1.12126 2.52083 + endloop + endfacet + facet normal 0.168949 -0.212265 0.962497 + outer loop + vertex 1.56676 1.1195 2.5211 + vertex 1.56762 1.11713 2.52042 + vertex 1.57046 1.12126 2.52083 + endloop + endfacet + facet normal 0.166001 -0.205749 0.964423 + outer loop + vertex 1.57046 1.12126 2.52083 + vertex 1.56802 1.1236 2.52175 + vertex 1.56676 1.1195 2.5211 + endloop + endfacet + facet normal 0.175433 -0.208315 0.9622 + outer loop + vertex 1.56676 1.1195 2.5211 + vertex 1.56802 1.1236 2.52175 + vertex 1.56273 1.11862 2.52164 + endloop + endfacet + facet normal 0.177401 -0.219017 0.959458 + outer loop + vertex 1.56676 1.1195 2.5211 + vertex 1.56273 1.11862 2.52164 + vertex 1.5645 1.11671 2.52088 + endloop + endfacet + facet normal 0.178342 -0.218152 0.959481 + outer loop + vertex 1.5645 1.11671 2.52088 + vertex 1.56273 1.11862 2.52164 + vertex 1.56163 1.11496 2.52101 + endloop + endfacet + facet normal 0.176691 -0.215376 0.960413 + outer loop + vertex 1.5645 1.11671 2.52088 + vertex 1.56163 1.11496 2.52101 + vertex 1.56317 1.11302 2.52029 + endloop + endfacet + facet normal 0.180727 -0.212147 0.960381 + outer loop + vertex 1.56317 1.11302 2.52029 + vertex 1.56163 1.11496 2.52101 + vertex 1.55947 1.11219 2.52081 + endloop + endfacet + facet normal 0.202991 -0.228908 0.952048 + outer loop + vertex 1.56163 1.11496 2.52101 + vertex 1.55769 1.11398 2.52161 + vertex 1.55947 1.11219 2.52081 + endloop + endfacet + facet normal 0.208145 -0.223853 0.952137 + outer loop + vertex 1.55947 1.11219 2.52081 + vertex 1.55769 1.11398 2.52161 + vertex 1.55646 1.11041 2.52104 + endloop + endfacet + facet normal 0.202019 -0.224188 0.953377 + outer loop + vertex 1.56163 1.11496 2.52101 + vertex 1.56273 1.11862 2.52164 + vertex 1.55769 1.11398 2.52161 + endloop + endfacet + facet normal 0.192525 -0.213921 0.957691 + outer loop + vertex 1.56273 1.11862 2.52164 + vertex 1.55751 1.11833 2.52262 + vertex 1.55769 1.11398 2.52161 + endloop + endfacet + facet normal 0.197428 -0.21351 0.956784 + outer loop + vertex 1.55769 1.11398 2.52161 + vertex 1.55751 1.11833 2.52262 + vertex 1.55278 1.11358 2.52254 + endloop + endfacet + facet normal 0.19741 -0.213046 0.956891 + outer loop + vertex 1.55769 1.11398 2.52161 + vertex 1.55278 1.11358 2.52254 + vertex 1.55318 1.11001 2.52166 + endloop + endfacet + facet normal 0.183373 -0.199593 0.962568 + outer loop + vertex 1.55278 1.11358 2.52254 + vertex 1.55751 1.11833 2.52262 + vertex 1.55242 1.11798 2.52352 + endloop + endfacet + facet normal 0.10944 -0.207623 0.972068 + outer loop + vertex 1.55278 1.11358 2.52254 + vertex 1.55242 1.11798 2.52352 + vertex 1.54809 1.11316 2.52298 + endloop + endfacet + facet normal 0.108955 -0.200593 0.973597 + outer loop + vertex 1.54887 1.10922 2.52208 + vertex 1.55278 1.11358 2.52254 + vertex 1.54809 1.11316 2.52298 + endloop + endfacet + facet normal 0.102323 -0.201451 0.974139 + outer loop + vertex 1.54809 1.11316 2.52298 + vertex 1.55242 1.11798 2.52352 + vertex 1.54774 1.11793 2.524 + endloop + endfacet + facet normal -0.164342 -0.218426 0.961916 + outer loop + vertex 1.54809 1.11316 2.52298 + vertex 1.54774 1.11793 2.524 + vertex 1.54406 1.1135 2.52237 + endloop + endfacet + facet normal -0.0814924 -0.284732 0.955137 + outer loop + vertex 1.54406 1.1135 2.52237 + vertex 1.54774 1.11793 2.524 + vertex 1.54358 1.11869 2.52387 + endloop + endfacet + facet normal -0.0722345 -0.232057 0.970016 + outer loop + vertex 1.54788 1.12305 2.52524 + vertex 1.54358 1.11869 2.52387 + vertex 1.54774 1.11793 2.524 + endloop + endfacet + facet normal 0.145833 -0.235668 0.96083 + outer loop + vertex 1.54774 1.11793 2.524 + vertex 1.55252 1.12296 2.52451 + vertex 1.54788 1.12305 2.52524 + endloop + endfacet + facet normal 0.147914 -0.1962 0.969344 + outer loop + vertex 1.55306 1.12809 2.52547 + vertex 1.54788 1.12305 2.52524 + vertex 1.55252 1.12296 2.52451 + endloop + endfacet + facet normal 0.183606 -0.198677 0.962713 + outer loop + vertex 1.55252 1.12296 2.52451 + vertex 1.55774 1.12812 2.52458 + vertex 1.55306 1.12809 2.52547 + endloop + endfacet + facet normal 0.18374 -0.194317 0.963577 + outer loop + vertex 1.55831 1.13298 2.52545 + vertex 1.55306 1.12809 2.52547 + vertex 1.55774 1.12812 2.52458 + endloop + endfacet + facet normal 0.174862 -0.193596 0.965372 + outer loop + vertex 1.55774 1.12812 2.52458 + vertex 1.56281 1.13314 2.52467 + vertex 1.55831 1.13298 2.52545 + endloop + endfacet + facet normal 0.174847 -0.204284 0.96317 + outer loop + vertex 1.56278 1.13709 2.52551 + vertex 1.55831 1.13298 2.52545 + vertex 1.56281 1.13314 2.52467 + endloop + endfacet + facet normal 0.164957 -0.204688 0.964827 + outer loop + vertex 1.56281 1.13314 2.52467 + vertex 1.5677 1.13858 2.52498 + vertex 1.56278 1.13709 2.52551 + endloop + endfacet + facet normal 0.165458 -0.206503 0.964355 + outer loop + vertex 1.56278 1.13709 2.52551 + vertex 1.5677 1.13858 2.52498 + vertex 1.5656 1.14114 2.5259 + endloop + endfacet + facet normal 0.168801 -0.208719 0.963298 + outer loop + vertex 1.56192 1.13942 2.52617 + vertex 1.56278 1.13709 2.52551 + vertex 1.5656 1.14114 2.5259 + endloop + endfacet + facet normal 0.166624 -0.203835 0.964722 + outer loop + vertex 1.5656 1.14114 2.5259 + vertex 1.56309 1.14344 2.52681 + vertex 1.56192 1.13942 2.52617 + endloop + endfacet + facet normal 0.174158 -0.205752 0.962982 + outer loop + vertex 1.56192 1.13942 2.52617 + vertex 1.56309 1.14344 2.52681 + vertex 1.55782 1.13855 2.52672 + endloop + endfacet + facet normal 0.175446 -0.212985 0.961174 + outer loop + vertex 1.56192 1.13942 2.52617 + vertex 1.55782 1.13855 2.52672 + vertex 1.55968 1.13668 2.52597 + endloop + endfacet + facet normal 0.179675 -0.208822 0.961307 + outer loop + vertex 1.55968 1.13668 2.52597 + vertex 1.55782 1.13855 2.52672 + vertex 1.55675 1.13491 2.52613 + endloop + endfacet + facet normal 0.174127 -0.199348 0.964334 + outer loop + vertex 1.55968 1.13668 2.52597 + vertex 1.55675 1.13491 2.52613 + vertex 1.55831 1.13298 2.52545 + endloop + endfacet + facet normal 0.170513 -0.201844 0.964461 + outer loop + vertex 1.56309 1.14344 2.52681 + vertex 1.55757 1.14321 2.52774 + vertex 1.55782 1.13855 2.52672 + endloop + endfacet + facet normal 0.178573 -0.201138 0.963149 + outer loop + vertex 1.55782 1.13855 2.52672 + vertex 1.55757 1.14321 2.52774 + vertex 1.55252 1.13838 2.52767 + endloop + endfacet + facet normal 0.178569 -0.20225 0.962917 + outer loop + vertex 1.55782 1.13855 2.52672 + vertex 1.55252 1.13838 2.52767 + vertex 1.55263 1.13383 2.52669 + endloop + endfacet + facet normal 0.186047 -0.210432 0.959742 + outer loop + vertex 1.55675 1.13491 2.52613 + vertex 1.55782 1.13855 2.52672 + vertex 1.55263 1.13383 2.52669 + endloop + endfacet + facet normal 0.182753 -0.195995 0.963425 + outer loop + vertex 1.55675 1.13491 2.52613 + vertex 1.55263 1.13383 2.52669 + vertex 1.55454 1.13207 2.52597 + endloop + endfacet + facet normal 0.180418 -0.194222 0.964224 + outer loop + vertex 1.55831 1.13298 2.52545 + vertex 1.55675 1.13491 2.52613 + vertex 1.55454 1.13207 2.52597 + endloop + endfacet + facet normal 0.186485 -0.191978 0.963518 + outer loop + vertex 1.55454 1.13207 2.52597 + vertex 1.55263 1.13383 2.52669 + vertex 1.5514 1.13006 2.52618 + endloop + endfacet + facet normal 0.186597 -0.192158 0.963461 + outer loop + vertex 1.55454 1.13207 2.52597 + vertex 1.5514 1.13006 2.52618 + vertex 1.55306 1.12809 2.52547 + endloop + endfacet + facet normal 0.177596 -0.200122 0.963541 + outer loop + vertex 1.55252 1.13838 2.52767 + vertex 1.55757 1.14321 2.52774 + vertex 1.5524 1.14311 2.52867 + endloop + endfacet + facet normal 0.166681 -0.200787 0.965351 + outer loop + vertex 1.55252 1.13838 2.52767 + vertex 1.5524 1.14311 2.52867 + vertex 1.54762 1.13832 2.5285 + endloop + endfacet + facet normal 0.166286 -0.216902 0.961926 + outer loop + vertex 1.54769 1.13373 2.52746 + vertex 1.55252 1.13838 2.52767 + vertex 1.54762 1.13832 2.5285 + endloop + endfacet + facet normal 0.0837144 -0.220409 0.971808 + outer loop + vertex 1.54769 1.13373 2.52746 + vertex 1.54762 1.13832 2.5285 + vertex 1.544 1.13429 2.5279 + endloop + endfacet + facet normal 0.0755759 -0.265759 0.961073 + outer loop + vertex 1.54304 1.12925 2.52658 + vertex 1.54769 1.13373 2.52746 + vertex 1.544 1.13429 2.5279 + endloop + endfacet + facet normal -0.00272649 -0.188673 0.982036 + outer loop + vertex 1.54756 1.12907 2.52656 + vertex 1.54769 1.13373 2.52746 + vertex 1.54304 1.12925 2.52658 + endloop + endfacet + facet normal -0.000997143 -0.145393 0.989374 + outer loop + vertex 1.54756 1.12907 2.52656 + vertex 1.54304 1.12925 2.52658 + vertex 1.54377 1.12502 2.52596 + endloop + endfacet + facet normal -0.0209268 -0.127078 0.991672 + outer loop + vertex 1.54634 1.1252 2.52604 + vertex 1.54756 1.12907 2.52656 + vertex 1.54377 1.12502 2.52596 + endloop + endfacet + facet normal -0.0160428 -0.195142 0.980644 + outer loop + vertex 1.54634 1.1252 2.52604 + vertex 1.54377 1.12502 2.52596 + vertex 1.54442 1.12245 2.52546 + endloop + endfacet + facet normal 0.110188 -0.277508 0.954384 + outer loop + vertex 1.54788 1.12305 2.52524 + vertex 1.54634 1.1252 2.52604 + vertex 1.54442 1.12245 2.52546 + endloop + endfacet + facet normal 0.167875 -0.236997 0.956896 + outer loop + vertex 1.54915 1.12707 2.52601 + vertex 1.54634 1.1252 2.52604 + vertex 1.54788 1.12305 2.52524 + endloop + endfacet + facet normal -0.197375 -0.235175 0.951701 + outer loop + vertex 1.54442 1.12245 2.52546 + vertex 1.54377 1.12502 2.52596 + vertex 1.54226 1.12164 2.52481 + endloop + endfacet + facet normal -0.143064 -0.357833 0.922761 + outer loop + vertex 1.54442 1.12245 2.52546 + vertex 1.54226 1.12164 2.52481 + vertex 1.54358 1.11869 2.52387 + endloop + endfacet + facet normal 0.124253 -0.171161 0.977377 + outer loop + vertex 1.54915 1.12707 2.52601 + vertex 1.54756 1.12907 2.52656 + vertex 1.54634 1.1252 2.52604 + endloop + endfacet + facet normal 0.138328 -0.160083 0.977363 + outer loop + vertex 1.5514 1.13006 2.52618 + vertex 1.54756 1.12907 2.52656 + vertex 1.54915 1.12707 2.52601 + endloop + endfacet + facet normal 0.184426 -0.193994 0.963511 + outer loop + vertex 1.55306 1.12809 2.52547 + vertex 1.5514 1.13006 2.52618 + vertex 1.54915 1.12707 2.52601 + endloop + endfacet + facet normal 0.142833 -0.179063 0.973414 + outer loop + vertex 1.5514 1.13006 2.52618 + vertex 1.55263 1.13383 2.52669 + vertex 1.54756 1.12907 2.52656 + endloop + endfacet + facet normal 0.153566 -0.1904 0.969621 + outer loop + vertex 1.55263 1.13383 2.52669 + vertex 1.54769 1.13373 2.52746 + vertex 1.54756 1.12907 2.52656 + endloop + endfacet + facet normal 0.0868111 -0.223057 0.970932 + outer loop + vertex 1.544 1.13429 2.5279 + vertex 1.54762 1.13832 2.5285 + vertex 1.54327 1.13821 2.52887 + endloop + endfacet + facet normal 0.0867745 -0.218243 0.972029 + outer loop + vertex 1.54762 1.13832 2.5285 + vertex 1.54758 1.14303 2.52957 + vertex 1.54327 1.13821 2.52887 + endloop + endfacet + facet normal 0.173759 -0.291315 0.940714 + outer loop + vertex 1.54327 1.13821 2.52887 + vertex 1.54758 1.14303 2.52957 + vertex 1.54307 1.14297 2.53038 + endloop + endfacet + facet normal 0.176202 -0.217408 0.960045 + outer loop + vertex 1.54797 1.14796 2.53061 + vertex 1.54307 1.14297 2.53038 + vertex 1.54758 1.14303 2.52957 + endloop + endfacet + facet normal 0.206863 -0.218506 0.953658 + outer loop + vertex 1.54758 1.14303 2.52957 + vertex 1.55264 1.14807 2.52962 + vertex 1.54797 1.14796 2.53061 + endloop + endfacet + facet normal 0.207468 -0.188625 0.959884 + outer loop + vertex 1.55329 1.15309 2.53047 + vertex 1.54797 1.14796 2.53061 + vertex 1.55264 1.14807 2.52962 + endloop + endfacet + facet normal 0.185312 -0.186551 0.96481 + outer loop + vertex 1.55264 1.14807 2.52962 + vertex 1.55781 1.15315 2.52961 + vertex 1.55329 1.15309 2.53047 + endloop + endfacet + facet normal 0.185458 -0.179746 0.966073 + outer loop + vertex 1.55842 1.15818 2.53043 + vertex 1.55329 1.15309 2.53047 + vertex 1.55781 1.15315 2.52961 + endloop + endfacet + facet normal 0.170307 -0.178401 0.969107 + outer loop + vertex 1.55781 1.15315 2.52961 + vertex 1.56285 1.15827 2.52967 + vertex 1.55842 1.15818 2.53043 + endloop + endfacet + facet normal 0.170424 -0.165903 0.971304 + outer loop + vertex 1.56335 1.16333 2.53044 + vertex 1.55842 1.15818 2.53043 + vertex 1.56285 1.15827 2.52967 + endloop + endfacet + facet normal 0.14891 -0.164375 0.975093 + outer loop + vertex 1.56285 1.15827 2.52967 + vertex 1.56782 1.16336 2.52976 + vertex 1.56335 1.16333 2.53044 + endloop + endfacet + facet normal 0.149195 -0.148707 0.977562 + outer loop + vertex 1.56819 1.16825 2.53045 + vertex 1.56335 1.16333 2.53044 + vertex 1.56782 1.16336 2.52976 + endloop + endfacet + facet normal 0.151026 -0.166432 0.974419 + outer loop + vertex 1.56748 1.15824 2.52894 + vertex 1.56782 1.16336 2.52976 + vertex 1.56285 1.15827 2.52967 + endloop + endfacet + facet normal 0.150741 -0.175011 0.972959 + outer loop + vertex 1.56248 1.15314 2.5288 + vertex 1.56748 1.15824 2.52894 + vertex 1.56285 1.15827 2.52967 + endloop + endfacet + facet normal 0.153396 -0.177587 0.972076 + outer loop + vertex 1.5674 1.15322 2.52804 + vertex 1.56748 1.15824 2.52894 + vertex 1.56248 1.15314 2.5288 + endloop + endfacet + facet normal 0.153319 -0.183553 0.97098 + outer loop + vertex 1.56253 1.1482 2.52786 + vertex 1.5674 1.15322 2.52804 + vertex 1.56248 1.15314 2.5288 + endloop + endfacet + facet normal 0.168261 -0.18295 0.968616 + outer loop + vertex 1.56253 1.1482 2.52786 + vertex 1.56248 1.15314 2.5288 + vertex 1.55746 1.14808 2.52872 + endloop + endfacet + facet normal 0.168197 -0.190064 0.967257 + outer loop + vertex 1.55757 1.14321 2.52774 + vertex 1.56253 1.1482 2.52786 + vertex 1.55746 1.14808 2.52872 + endloop + endfacet + facet normal 0.167375 -0.182076 0.968934 + outer loop + vertex 1.55746 1.14808 2.52872 + vertex 1.56248 1.15314 2.5288 + vertex 1.55781 1.15315 2.52961 + endloop + endfacet + facet normal 0.157877 -0.187917 0.969413 + outer loop + vertex 1.56772 1.14866 2.5271 + vertex 1.5674 1.15322 2.52804 + vertex 1.56253 1.1482 2.52786 + endloop + endfacet + facet normal 0.15824 -0.194099 0.968135 + outer loop + vertex 1.56309 1.14344 2.52681 + vertex 1.56772 1.14866 2.5271 + vertex 1.56253 1.1482 2.52786 + endloop + endfacet + facet normal 0.163193 -0.198395 0.966441 + outer loop + vertex 1.56836 1.14514 2.52627 + vertex 1.56772 1.14866 2.5271 + vertex 1.56309 1.14344 2.52681 + endloop + endfacet + facet normal 0.144386 -0.202304 0.96862 + outer loop + vertex 1.57277 1.14896 2.52641 + vertex 1.56772 1.14866 2.5271 + vertex 1.56836 1.14514 2.52627 + endloop + endfacet + facet normal 0.162717 -0.223185 0.961099 + outer loop + vertex 1.57158 1.14558 2.52583 + vertex 1.57277 1.14896 2.52641 + vertex 1.56836 1.14514 2.52627 + endloop + endfacet + facet normal 0.160918 -0.205832 0.965266 + outer loop + vertex 1.57158 1.14558 2.52583 + vertex 1.56836 1.14514 2.52627 + vertex 1.56929 1.14286 2.52563 + endloop + endfacet + facet normal 0.14527 -0.19303 0.970379 + outer loop + vertex 1.57298 1.14334 2.52518 + vertex 1.57158 1.14558 2.52583 + vertex 1.56929 1.14286 2.52563 + endloop + endfacet + facet normal 0.146051 -0.200463 0.968754 + outer loop + vertex 1.56929 1.14286 2.52563 + vertex 1.5677 1.13858 2.52498 + vertex 1.57298 1.14334 2.52518 + endloop + endfacet + facet normal 0.148071 -0.202669 0.967988 + outer loop + vertex 1.57298 1.14334 2.52518 + vertex 1.5677 1.13858 2.52498 + vertex 1.57262 1.13843 2.5242 + endloop + endfacet + facet normal 0.102713 -0.200631 0.974268 + outer loop + vertex 1.57262 1.13843 2.5242 + vertex 1.5775 1.14293 2.52461 + vertex 1.57298 1.14334 2.52518 + endloop + endfacet + facet normal 0.103021 -0.197965 0.97478 + outer loop + vertex 1.57744 1.14684 2.52541 + vertex 1.57298 1.14334 2.52518 + vertex 1.5775 1.14293 2.52461 + endloop + endfacet + facet normal 0.048702 -0.19961 0.978664 + outer loop + vertex 1.5775 1.14293 2.52461 + vertex 1.58183 1.14691 2.52521 + vertex 1.57744 1.14684 2.52541 + endloop + endfacet + facet normal 0.04878 -0.210226 0.976435 + outer loop + vertex 1.57744 1.14684 2.52541 + vertex 1.58183 1.14691 2.52521 + vertex 1.58073 1.1503 2.526 + endloop + endfacet + facet normal 0.0555722 -0.21638 0.974726 + outer loop + vertex 1.57674 1.1494 2.52602 + vertex 1.57744 1.14684 2.52541 + vertex 1.58073 1.1503 2.526 + endloop + endfacet + facet normal 0.0572861 -0.224033 0.972897 + outer loop + vertex 1.58073 1.1503 2.526 + vertex 1.57817 1.15323 2.52682 + vertex 1.57674 1.1494 2.52602 + endloop + endfacet + facet normal 0.122017 -0.245917 0.96158 + outer loop + vertex 1.57674 1.1494 2.52602 + vertex 1.57817 1.15323 2.52682 + vertex 1.57277 1.14896 2.52641 + endloop + endfacet + facet normal 0.121195 -0.236289 0.964095 + outer loop + vertex 1.57674 1.1494 2.52602 + vertex 1.57277 1.14896 2.52641 + vertex 1.57435 1.147 2.52573 + endloop + endfacet + facet normal 0.0925326 -0.209744 0.973368 + outer loop + vertex 1.57817 1.15323 2.52682 + vertex 1.57256 1.15335 2.52738 + vertex 1.57277 1.14896 2.52641 + endloop + endfacet + facet normal 0.093074 -0.196589 0.976058 + outer loop + vertex 1.57817 1.15323 2.52682 + vertex 1.57757 1.15815 2.52787 + vertex 1.57256 1.15335 2.52738 + endloop + endfacet + facet normal 0.0840243 -0.187414 0.978681 + outer loop + vertex 1.57256 1.15335 2.52738 + vertex 1.57757 1.15815 2.52787 + vertex 1.57237 1.15819 2.52832 + endloop + endfacet + facet normal 0.129277 -0.184774 0.974241 + outer loop + vertex 1.57256 1.15335 2.52738 + vertex 1.57237 1.15819 2.52832 + vertex 1.5674 1.15322 2.52804 + endloop + endfacet + facet normal 0.0842389 -0.178501 0.980327 + outer loop + vertex 1.57757 1.15815 2.52787 + vertex 1.57741 1.16311 2.52878 + vertex 1.57237 1.15819 2.52832 + endloop + endfacet + facet normal 0.0772365 -0.171503 0.982151 + outer loop + vertex 1.57237 1.15819 2.52832 + vertex 1.57741 1.16311 2.52878 + vertex 1.57249 1.16323 2.52919 + endloop + endfacet + facet normal 0.122491 -0.171748 0.977496 + outer loop + vertex 1.57237 1.15819 2.52832 + vertex 1.57249 1.16323 2.52919 + vertex 1.56748 1.15824 2.52894 + endloop + endfacet + facet normal 0.0774397 -0.166402 0.983012 + outer loop + vertex 1.57741 1.16311 2.52878 + vertex 1.57736 1.16794 2.52961 + vertex 1.57249 1.16323 2.52919 + endloop + endfacet + facet normal 0.0670271 -0.155846 0.985505 + outer loop + vertex 1.57249 1.16323 2.52919 + vertex 1.57736 1.16794 2.52961 + vertex 1.57264 1.16804 2.52994 + endloop + endfacet + facet normal 0.115878 -0.15662 0.980838 + outer loop + vertex 1.57249 1.16323 2.52919 + vertex 1.57264 1.16804 2.52994 + vertex 1.56782 1.16336 2.52976 + endloop + endfacet + facet normal 0.0670507 -0.155111 0.985619 + outer loop + vertex 1.57736 1.16794 2.52961 + vertex 1.57694 1.17215 2.5303 + vertex 1.57264 1.16804 2.52994 + endloop + endfacet + facet normal 0.0553577 -0.1431 0.988159 + outer loop + vertex 1.57264 1.16804 2.52994 + vertex 1.57694 1.17215 2.5303 + vertex 1.57258 1.172 2.53052 + endloop + endfacet + facet normal 0.105991 -0.141769 0.984209 + outer loop + vertex 1.57258 1.172 2.53052 + vertex 1.56819 1.16825 2.53045 + vertex 1.57264 1.16804 2.52994 + endloop + endfacet + facet normal 0.105703 -0.146258 0.983583 + outer loop + vertex 1.56782 1.16336 2.52976 + vertex 1.57264 1.16804 2.52994 + vertex 1.56819 1.16825 2.53045 + endloop + endfacet + facet normal 0.0906268 -0.123866 0.988152 + outer loop + vertex 1.56944 1.17198 2.5308 + vertex 1.56819 1.16825 2.53045 + vertex 1.57258 1.172 2.53052 + endloop + endfacet + facet normal 0.0905156 -0.147754 0.984873 + outer loop + vertex 1.57258 1.172 2.53052 + vertex 1.57182 1.17451 2.53097 + vertex 1.56944 1.17198 2.5308 + endloop + endfacet + facet normal 0.120134 -0.175091 0.977195 + outer loop + vertex 1.57182 1.17451 2.53097 + vertex 1.56773 1.17375 2.53133 + vertex 1.56944 1.17198 2.5308 + endloop + endfacet + facet normal 0.141409 -0.154716 0.977786 + outer loop + vertex 1.56944 1.17198 2.5308 + vertex 1.56773 1.17375 2.53133 + vertex 1.56657 1.17021 2.53094 + endloop + endfacet + facet normal 0.123482 -0.195429 0.972913 + outer loop + vertex 1.57182 1.17451 2.53097 + vertex 1.57324 1.17832 2.53155 + vertex 1.56773 1.17375 2.53133 + endloop + endfacet + facet normal 0.0906218 -0.156202 0.983559 + outer loop + vertex 1.57324 1.17832 2.53155 + vertex 1.5676 1.17829 2.53207 + vertex 1.56773 1.17375 2.53133 + endloop + endfacet + facet normal 0.0626607 -0.174278 0.982701 + outer loop + vertex 1.57582 1.17553 2.53089 + vertex 1.57324 1.17832 2.53155 + vertex 1.57182 1.17451 2.53097 + endloop + endfacet + facet normal 0.0485352 -0.187 0.98116 + outer loop + vertex 1.5792 1.17935 2.53145 + vertex 1.57324 1.17832 2.53155 + vertex 1.57582 1.17553 2.53089 + endloop + endfacet + facet normal 0.0453227 -0.168191 0.984712 + outer loop + vertex 1.5792 1.17935 2.53145 + vertex 1.57801 1.18334 2.53219 + vertex 1.57324 1.17832 2.53155 + endloop + endfacet + facet normal 0.0584621 -0.157594 0.985772 + outer loop + vertex 1.57182 1.17451 2.53097 + vertex 1.57258 1.172 2.53052 + vertex 1.57582 1.17553 2.53089 + endloop + endfacet + facet normal 0.130509 -0.136674 0.981981 + outer loop + vertex 1.56944 1.17198 2.5308 + vertex 1.56657 1.17021 2.53094 + vertex 1.56819 1.16825 2.53045 + endloop + endfacet + facet normal 0.0556814 -0.155095 0.986329 + outer loop + vertex 1.57258 1.172 2.53052 + vertex 1.57694 1.17215 2.5303 + vertex 1.57582 1.17553 2.53089 + endloop + endfacet + facet normal 0.0510238 -0.202176 0.978019 + outer loop + vertex 1.57817 1.15323 2.52682 + vertex 1.58297 1.15829 2.52761 + vertex 1.57757 1.15815 2.52787 + endloop + endfacet + facet normal 0.0506516 -0.180014 0.982359 + outer loop + vertex 1.58297 1.15829 2.52761 + vertex 1.58253 1.16306 2.52851 + vertex 1.57757 1.15815 2.52787 + endloop + endfacet + facet normal 0.0505677 -0.179932 0.982379 + outer loop + vertex 1.57757 1.15815 2.52787 + vertex 1.58253 1.16306 2.52851 + vertex 1.57741 1.16311 2.52878 + endloop + endfacet + facet normal 0.0507098 -0.17216 0.983763 + outer loop + vertex 1.58253 1.16306 2.52851 + vertex 1.5824 1.168 2.52938 + vertex 1.57741 1.16311 2.52878 + endloop + endfacet + facet normal 0.0455791 -0.167077 0.98489 + outer loop + vertex 1.57741 1.16311 2.52878 + vertex 1.5824 1.168 2.52938 + vertex 1.57736 1.16794 2.52961 + endloop + endfacet + facet normal 0.0456023 -0.171101 0.984198 + outer loop + vertex 1.5824 1.168 2.52938 + vertex 1.5818 1.17235 2.53017 + vertex 1.57736 1.16794 2.52961 + endloop + endfacet + facet normal 0.0329114 -0.158668 0.986783 + outer loop + vertex 1.57736 1.16794 2.52961 + vertex 1.5818 1.17235 2.53017 + vertex 1.57694 1.17215 2.5303 + endloop + endfacet + facet normal 0.0333421 -0.170385 0.984813 + outer loop + vertex 1.57694 1.17215 2.5303 + vertex 1.5818 1.17235 2.53017 + vertex 1.58063 1.17593 2.53083 + endloop + endfacet + facet normal 0.027137 -0.164489 0.986006 + outer loop + vertex 1.57582 1.17553 2.53089 + vertex 1.57694 1.17215 2.5303 + vertex 1.58063 1.17593 2.53083 + endloop + endfacet + facet normal 0.0275049 -0.169038 0.985226 + outer loop + vertex 1.58063 1.17593 2.53083 + vertex 1.5792 1.17935 2.53145 + vertex 1.57582 1.17553 2.53089 + endloop + endfacet + facet normal 0.0266518 -0.169388 0.985189 + outer loop + vertex 1.58407 1.17958 2.53136 + vertex 1.5792 1.17935 2.53145 + vertex 1.58063 1.17593 2.53083 + endloop + endfacet + facet normal 0.0259972 -0.154144 0.987706 + outer loop + vertex 1.58407 1.17958 2.53136 + vertex 1.58329 1.18355 2.532 + vertex 1.5792 1.17935 2.53145 + endloop + endfacet + facet normal 0.0418838 -0.169214 0.984689 + outer loop + vertex 1.5792 1.17935 2.53145 + vertex 1.58329 1.18355 2.532 + vertex 1.57801 1.18334 2.53219 + endloop + endfacet + facet normal 0.0412371 -0.193233 0.980286 + outer loop + vertex 1.58416 1.15421 2.52676 + vertex 1.58297 1.15829 2.52761 + vertex 1.57817 1.15323 2.52682 + endloop + endfacet + facet normal 0.0474882 -0.232194 0.97151 + outer loop + vertex 1.58416 1.15421 2.52676 + vertex 1.57817 1.15323 2.52682 + vertex 1.58073 1.1503 2.526 + endloop + endfacet + facet normal 0.0901674 -0.206769 0.974226 + outer loop + vertex 1.57744 1.14684 2.52541 + vertex 1.57674 1.1494 2.52602 + vertex 1.57435 1.147 2.52573 + endloop + endfacet + facet normal 0.0558997 -0.207147 0.976711 + outer loop + vertex 1.58232 1.1428 2.52431 + vertex 1.58183 1.14691 2.52521 + vertex 1.5775 1.14293 2.52461 + endloop + endfacet + facet normal 0.0559161 -0.206743 0.976796 + outer loop + vertex 1.5775 1.13828 2.52363 + vertex 1.58232 1.1428 2.52431 + vertex 1.5775 1.14293 2.52461 + endloop + endfacet + facet normal 0.0624278 -0.213413 0.974966 + outer loop + vertex 1.58263 1.13812 2.52327 + vertex 1.58232 1.1428 2.52431 + vertex 1.5775 1.13828 2.52363 + endloop + endfacet + facet normal 0.0622705 -0.216719 0.974246 + outer loop + vertex 1.57765 1.1335 2.52256 + vertex 1.58263 1.13812 2.52327 + vertex 1.5775 1.13828 2.52363 + endloop + endfacet + facet normal 0.113637 -0.214246 0.970147 + outer loop + vertex 1.57765 1.1335 2.52256 + vertex 1.5775 1.13828 2.52363 + vertex 1.57254 1.13349 2.52315 + endloop + endfacet + facet normal 0.113664 -0.213038 0.97041 + outer loop + vertex 1.57274 1.12888 2.52212 + vertex 1.57765 1.1335 2.52256 + vertex 1.57254 1.13349 2.52315 + endloop + endfacet + facet normal 0.1538 -0.210177 0.96549 + outer loop + vertex 1.57274 1.12888 2.52212 + vertex 1.57254 1.13349 2.52315 + vertex 1.5676 1.12844 2.52284 + endloop + endfacet + facet normal 0.15346 -0.204045 0.966859 + outer loop + vertex 1.56802 1.1236 2.52175 + vertex 1.57274 1.12888 2.52212 + vertex 1.5676 1.12844 2.52284 + endloop + endfacet + facet normal 0.17361 -0.201644 0.96395 + outer loop + vertex 1.56802 1.1236 2.52175 + vertex 1.5676 1.12844 2.52284 + vertex 1.56259 1.12332 2.52267 + endloop + endfacet + facet normal 0.171106 -0.199218 0.964902 + outer loop + vertex 1.56259 1.12332 2.52267 + vertex 1.5676 1.12844 2.52284 + vertex 1.56256 1.12824 2.52369 + endloop + endfacet + facet normal 0.18637 -0.198568 0.962204 + outer loop + vertex 1.56259 1.12332 2.52267 + vertex 1.56256 1.12824 2.52369 + vertex 1.55743 1.12309 2.52362 + endloop + endfacet + facet normal 0.186373 -0.199077 0.962098 + outer loop + vertex 1.55751 1.11833 2.52262 + vertex 1.56259 1.12332 2.52267 + vertex 1.55743 1.12309 2.52362 + endloop + endfacet + facet normal 0.182082 -0.194312 0.963893 + outer loop + vertex 1.55743 1.12309 2.52362 + vertex 1.56256 1.12824 2.52369 + vertex 1.55774 1.12812 2.52458 + endloop + endfacet + facet normal 0.171125 -0.203638 0.963975 + outer loop + vertex 1.5676 1.12844 2.52284 + vertex 1.56759 1.1334 2.52389 + vertex 1.56256 1.12824 2.52369 + endloop + endfacet + facet normal 0.167915 -0.200557 0.965185 + outer loop + vertex 1.56256 1.12824 2.52369 + vertex 1.56759 1.1334 2.52389 + vertex 1.56281 1.13314 2.52467 + endloop + endfacet + facet normal 0.163913 -0.213125 0.963177 + outer loop + vertex 1.57328 1.1253 2.52123 + vertex 1.57274 1.12888 2.52212 + vertex 1.56802 1.1236 2.52175 + endloop + endfacet + facet normal 0.132925 -0.218616 0.966715 + outer loop + vertex 1.57774 1.12904 2.52147 + vertex 1.57274 1.12888 2.52212 + vertex 1.57328 1.1253 2.52123 + endloop + endfacet + facet normal 0.156652 -0.246291 0.956452 + outer loop + vertex 1.57651 1.12569 2.5208 + vertex 1.57774 1.12904 2.52147 + vertex 1.57328 1.1253 2.52123 + endloop + endfacet + facet normal 0.153708 -0.211917 0.965124 + outer loop + vertex 1.57651 1.12569 2.5208 + vertex 1.57328 1.1253 2.52123 + vertex 1.57419 1.12297 2.52058 + endloop + endfacet + facet normal 0.130774 -0.192917 0.972461 + outer loop + vertex 1.5779 1.12331 2.52014 + vertex 1.57651 1.12569 2.5208 + vertex 1.57419 1.12297 2.52058 + endloop + endfacet + facet normal 0.13109 -0.197749 0.971448 + outer loop + vertex 1.57419 1.12297 2.52058 + vertex 1.57261 1.11864 2.51991 + vertex 1.5779 1.12331 2.52014 + endloop + endfacet + facet normal 0.139876 -0.207547 0.968173 + outer loop + vertex 1.5779 1.12331 2.52014 + vertex 1.57261 1.11864 2.51991 + vertex 1.57758 1.1184 2.51914 + endloop + endfacet + facet normal 0.085489 -0.205407 0.974936 + outer loop + vertex 1.57758 1.1184 2.51914 + vertex 1.58234 1.12254 2.51959 + vertex 1.5779 1.12331 2.52014 + endloop + endfacet + facet normal 0.0844536 -0.210672 0.973902 + outer loop + vertex 1.5824 1.1265 2.52045 + vertex 1.5779 1.12331 2.52014 + vertex 1.58234 1.12254 2.51959 + endloop + endfacet + facet normal 0.0668251 -0.186416 0.980196 + outer loop + vertex 1.57929 1.12697 2.52075 + vertex 1.5779 1.12331 2.52014 + vertex 1.5824 1.1265 2.52045 + endloop + endfacet + facet normal 0.0606599 -0.222737 0.972989 + outer loop + vertex 1.5824 1.1265 2.52045 + vertex 1.58167 1.12922 2.52111 + vertex 1.57929 1.12697 2.52075 + endloop + endfacet + facet normal 0.0979712 -0.260249 0.960558 + outer loop + vertex 1.58167 1.12922 2.52111 + vertex 1.57774 1.12904 2.52147 + vertex 1.57929 1.12697 2.52075 + endloop + endfacet + facet normal 0.0982004 -0.27223 0.957208 + outer loop + vertex 1.58167 1.12922 2.52111 + vertex 1.58321 1.13305 2.52205 + vertex 1.57774 1.12904 2.52147 + endloop + endfacet + facet normal 0.0700658 -0.235601 0.969321 + outer loop + vertex 1.58321 1.13305 2.52205 + vertex 1.57765 1.1335 2.52256 + vertex 1.57774 1.12904 2.52147 + endloop + endfacet + facet normal 0.0967122 -0.217882 0.971171 + outer loop + vertex 1.58236 1.11813 2.5186 + vertex 1.58234 1.12254 2.51959 + vertex 1.57758 1.1184 2.51914 + endloop + endfacet + facet normal 0.0966466 -0.218691 0.970996 + outer loop + vertex 1.57765 1.11352 2.51803 + vertex 1.58236 1.11813 2.5186 + vertex 1.57758 1.1184 2.51914 + endloop + endfacet + facet normal 0.141519 -0.216941 0.965872 + outer loop + vertex 1.57765 1.11352 2.51803 + vertex 1.57758 1.1184 2.51914 + vertex 1.57261 1.11346 2.51876 + endloop + endfacet + facet normal 0.141503 -0.217734 0.965696 + outer loop + vertex 1.57273 1.10856 2.51764 + vertex 1.57765 1.11352 2.51803 + vertex 1.57261 1.11346 2.51876 + endloop + endfacet + facet normal 0.163689 -0.216468 0.96247 + outer loop + vertex 1.57273 1.10856 2.51764 + vertex 1.57261 1.11346 2.51876 + vertex 1.56768 1.10835 2.51845 + endloop + endfacet + facet normal 0.163686 -0.215974 0.962581 + outer loop + vertex 1.56791 1.10368 2.51736 + vertex 1.57273 1.10856 2.51764 + vertex 1.56768 1.10835 2.51845 + endloop + endfacet + facet normal 0.172605 -0.215199 0.961195 + outer loop + vertex 1.56791 1.10368 2.51736 + vertex 1.56768 1.10835 2.51845 + vertex 1.56273 1.10332 2.51821 + endloop + endfacet + facet normal 0.172771 -0.220233 0.960025 + outer loop + vertex 1.56319 1.09844 2.51701 + vertex 1.56791 1.10368 2.51736 + vertex 1.56273 1.10332 2.51821 + endloop + endfacet + facet normal 0.175867 -0.219826 0.959556 + outer loop + vertex 1.56319 1.09844 2.51701 + vertex 1.56273 1.10332 2.51821 + vertex 1.55766 1.09835 2.518 + endloop + endfacet + facet normal 0.176007 -0.219967 0.959498 + outer loop + vertex 1.55766 1.09835 2.518 + vertex 1.56273 1.10332 2.51821 + vertex 1.55757 1.10328 2.51915 + endloop + endfacet + facet normal 0.141548 -0.221831 0.964757 + outer loop + vertex 1.55766 1.09835 2.518 + vertex 1.55757 1.10328 2.51915 + vertex 1.55259 1.09841 2.51876 + endloop + endfacet + facet normal 0.169949 -0.217759 0.961092 + outer loop + vertex 1.5685 1.09998 2.51642 + vertex 1.56791 1.10368 2.51736 + vertex 1.56319 1.09844 2.51701 + endloop + endfacet + facet normal 0.172989 -0.215569 0.961044 + outer loop + vertex 1.56273 1.10332 2.51821 + vertex 1.56768 1.10835 2.51845 + vertex 1.56277 1.10823 2.51931 + endloop + endfacet + facet normal 0.165046 -0.217287 0.962053 + outer loop + vertex 1.57286 1.10396 2.51657 + vertex 1.57273 1.10856 2.51764 + vertex 1.56791 1.10368 2.51736 + endloop + endfacet + facet normal 0.165072 -0.218701 0.961728 + outer loop + vertex 1.57286 1.10396 2.51657 + vertex 1.56791 1.10368 2.51736 + vertex 1.5685 1.09998 2.51642 + endloop + endfacet + facet normal 0.164585 -0.218175 0.961931 + outer loop + vertex 1.5717 1.10036 2.51596 + vertex 1.57286 1.10396 2.51657 + vertex 1.5685 1.09998 2.51642 + endloop + endfacet + facet normal 0.165203 -0.225629 0.960104 + outer loop + vertex 1.5717 1.10036 2.51596 + vertex 1.5685 1.09998 2.51642 + vertex 1.5694 1.09764 2.51571 + endloop + endfacet + facet normal 0.16942 -0.229044 0.958559 + outer loop + vertex 1.57306 1.09827 2.51521 + vertex 1.5717 1.10036 2.51596 + vertex 1.5694 1.09764 2.51571 + endloop + endfacet + facet normal 0.169508 -0.229691 0.958389 + outer loop + vertex 1.5694 1.09764 2.51571 + vertex 1.56771 1.09344 2.51501 + vertex 1.57306 1.09827 2.51521 + endloop + endfacet + facet normal 0.169186 -0.229339 0.95853 + outer loop + vertex 1.57306 1.09827 2.51521 + vertex 1.56771 1.09344 2.51501 + vertex 1.57275 1.09344 2.51412 + endloop + endfacet + facet normal 0.169304 -0.226401 0.959207 + outer loop + vertex 1.56759 1.08834 2.51382 + vertex 1.57275 1.09344 2.51412 + vertex 1.56771 1.09344 2.51501 + endloop + endfacet + facet normal 0.16951 -0.226605 0.959123 + outer loop + vertex 1.57278 1.0885 2.51294 + vertex 1.57275 1.09344 2.51412 + vertex 1.56759 1.08834 2.51382 + endloop + endfacet + facet normal 0.16951 -0.226602 0.959123 + outer loop + vertex 1.56761 1.08351 2.51268 + vertex 1.57278 1.0885 2.51294 + vertex 1.56759 1.08834 2.51382 + endloop + endfacet + facet normal 0.17951 -0.226141 0.957411 + outer loop + vertex 1.56761 1.08351 2.51268 + vertex 1.56759 1.08834 2.51382 + vertex 1.56249 1.08324 2.51357 + endloop + endfacet + facet normal 0.179539 -0.228723 0.956792 + outer loop + vertex 1.56269 1.07868 2.51245 + vertex 1.56761 1.08351 2.51268 + vertex 1.56249 1.08324 2.51357 + endloop + endfacet + facet normal 0.177201 -0.228925 0.95718 + outer loop + vertex 1.56269 1.07868 2.51245 + vertex 1.56249 1.08324 2.51357 + vertex 1.55778 1.07836 2.51328 + endloop + endfacet + facet normal 0.181127 -0.230307 0.956113 + outer loop + vertex 1.56776 1.07903 2.51157 + vertex 1.56761 1.08351 2.51268 + vertex 1.56269 1.07868 2.51245 + endloop + endfacet + facet normal 0.1812 -0.233109 0.955419 + outer loop + vertex 1.56776 1.07903 2.51157 + vertex 1.56269 1.07868 2.51245 + vertex 1.56322 1.07497 2.51144 + endloop + endfacet + facet normal 0.186588 -0.239057 0.952909 + outer loop + vertex 1.5666 1.07542 2.51089 + vertex 1.56776 1.07903 2.51157 + vertex 1.56322 1.07497 2.51144 + endloop + endfacet + facet normal 0.186085 -0.233374 0.954416 + outer loop + vertex 1.5666 1.07542 2.51089 + vertex 1.56322 1.07497 2.51144 + vertex 1.56413 1.07256 2.51067 + endloop + endfacet + facet normal 0.177914 -0.226564 0.957609 + outer loop + vertex 1.5681 1.07332 2.51012 + vertex 1.5666 1.07542 2.51089 + vertex 1.56413 1.07256 2.51067 + endloop + endfacet + facet normal 0.179302 -0.235546 0.95518 + outer loop + vertex 1.56413 1.07256 2.51067 + vertex 1.56241 1.06832 2.50995 + vertex 1.5681 1.07332 2.51012 + endloop + endfacet + facet normal 0.177092 -0.233072 0.956199 + outer loop + vertex 1.5681 1.07332 2.51012 + vertex 1.56241 1.06832 2.50995 + vertex 1.56763 1.06832 2.50898 + endloop + endfacet + facet normal 0.174105 -0.232927 0.956782 + outer loop + vertex 1.56763 1.06832 2.50898 + vertex 1.57284 1.07333 2.50926 + vertex 1.5681 1.07332 2.51012 + endloop + endfacet + facet normal 0.173871 -0.238545 0.95544 + outer loop + vertex 1.57327 1.07803 2.51035 + vertex 1.5681 1.07332 2.51012 + vertex 1.57284 1.07333 2.50926 + endloop + endfacet + facet normal 0.164831 -0.238118 0.957147 + outer loop + vertex 1.57284 1.07333 2.50926 + vertex 1.57785 1.07818 2.5096 + vertex 1.57327 1.07803 2.51035 + endloop + endfacet + facet normal 0.164849 -0.235973 0.957675 + outer loop + vertex 1.57778 1.08203 2.51056 + vertex 1.57327 1.07803 2.51035 + vertex 1.57785 1.07818 2.5096 + endloop + endfacet + facet normal 0.145999 -0.237009 0.960475 + outer loop + vertex 1.57785 1.07818 2.5096 + vertex 1.58271 1.0832 2.5101 + vertex 1.57778 1.08203 2.51056 + endloop + endfacet + facet normal 0.142751 -0.221625 0.964627 + outer loop + vertex 1.57778 1.08203 2.51056 + vertex 1.58271 1.0832 2.5101 + vertex 1.58073 1.08599 2.51103 + endloop + endfacet + facet normal 0.157701 -0.2322 0.959799 + outer loop + vertex 1.57693 1.08445 2.51129 + vertex 1.57778 1.08203 2.51056 + vertex 1.58073 1.08599 2.51103 + endloop + endfacet + facet normal 0.157055 -0.230523 0.960309 + outer loop + vertex 1.58073 1.08599 2.51103 + vertex 1.57829 1.08857 2.51205 + vertex 1.57693 1.08445 2.51129 + endloop + endfacet + facet normal 0.163807 -0.232449 0.958715 + outer loop + vertex 1.57693 1.08445 2.51129 + vertex 1.57829 1.08857 2.51205 + vertex 1.57284 1.08367 2.5118 + endloop + endfacet + facet normal 0.163285 -0.229122 0.959605 + outer loop + vertex 1.57693 1.08445 2.51129 + vertex 1.57284 1.08367 2.5118 + vertex 1.5746 1.08169 2.51102 + endloop + endfacet + facet normal 0.162582 -0.229737 0.959577 + outer loop + vertex 1.5746 1.08169 2.51102 + vertex 1.57284 1.08367 2.5118 + vertex 1.57169 1.07996 2.5111 + endloop + endfacet + facet normal 0.166359 -0.2362 0.957358 + outer loop + vertex 1.5746 1.08169 2.51102 + vertex 1.57169 1.07996 2.5111 + vertex 1.57327 1.07803 2.51035 + endloop + endfacet + facet normal 0.166818 -0.235828 0.95737 + outer loop + vertex 1.57327 1.07803 2.51035 + vertex 1.57169 1.07996 2.5111 + vertex 1.56956 1.07719 2.51079 + endloop + endfacet + facet normal 0.170353 -0.238409 0.956107 + outer loop + vertex 1.57169 1.07996 2.5111 + vertex 1.56776 1.07903 2.51157 + vertex 1.56956 1.07719 2.51079 + endloop + endfacet + facet normal 0.168933 -0.23143 0.958072 + outer loop + vertex 1.57169 1.07996 2.5111 + vertex 1.57284 1.08367 2.5118 + vertex 1.56776 1.07903 2.51157 + endloop + endfacet + facet normal 0.158257 -0.226397 0.961093 + outer loop + vertex 1.57829 1.08857 2.51205 + vertex 1.57278 1.0885 2.51294 + vertex 1.57284 1.08367 2.5118 + endloop + endfacet + facet normal 0.158209 -0.228318 0.960646 + outer loop + vertex 1.57829 1.08857 2.51205 + vertex 1.57783 1.09354 2.51331 + vertex 1.57278 1.0885 2.51294 + endloop + endfacet + facet normal 0.129066 -0.231875 0.964145 + outer loop + vertex 1.57829 1.08857 2.51205 + vertex 1.58307 1.09371 2.51265 + vertex 1.57783 1.09354 2.51331 + endloop + endfacet + facet normal 0.129063 -0.229706 0.964665 + outer loop + vertex 1.58307 1.09371 2.51265 + vertex 1.58262 1.09838 2.51382 + vertex 1.57783 1.09354 2.51331 + endloop + endfacet + facet normal 0.126675 -0.227432 0.96552 + outer loop + vertex 1.57783 1.09354 2.51331 + vertex 1.58262 1.09838 2.51382 + vertex 1.5777 1.09832 2.51445 + endloop + endfacet + facet normal 0.15702 -0.225627 0.961477 + outer loop + vertex 1.57783 1.09354 2.51331 + vertex 1.5777 1.09832 2.51445 + vertex 1.57275 1.09344 2.51412 + endloop + endfacet + facet normal 0.156994 -0.227135 0.961126 + outer loop + vertex 1.57278 1.0885 2.51294 + vertex 1.57783 1.09354 2.51331 + vertex 1.57275 1.09344 2.51412 + endloop + endfacet + facet normal 0.160576 -0.229134 0.960059 + outer loop + vertex 1.57275 1.09344 2.51412 + vertex 1.5777 1.09832 2.51445 + vertex 1.57306 1.09827 2.51521 + endloop + endfacet + facet normal 0.160778 -0.221223 0.961879 + outer loop + vertex 1.57749 1.10225 2.51539 + vertex 1.57306 1.09827 2.51521 + vertex 1.5777 1.09832 2.51445 + endloop + endfacet + facet normal 0.128179 -0.224019 0.966119 + outer loop + vertex 1.5777 1.09832 2.51445 + vertex 1.58243 1.10328 2.51498 + vertex 1.57749 1.10225 2.51539 + endloop + endfacet + facet normal 0.125593 -0.210235 0.96955 + outer loop + vertex 1.57749 1.10225 2.51539 + vertex 1.58243 1.10328 2.51498 + vertex 1.58039 1.10617 2.51587 + endloop + endfacet + facet normal 0.145554 -0.224292 0.963591 + outer loop + vertex 1.57666 1.10467 2.51608 + vertex 1.57749 1.10225 2.51539 + vertex 1.58039 1.10617 2.51587 + endloop + endfacet + facet normal 0.148792 -0.232696 0.9611 + outer loop + vertex 1.58039 1.10617 2.51587 + vertex 1.57806 1.10868 2.51683 + vertex 1.57666 1.10467 2.51608 + endloop + endfacet + facet normal 0.168996 -0.238798 0.956251 + outer loop + vertex 1.57666 1.10467 2.51608 + vertex 1.57806 1.10868 2.51683 + vertex 1.57286 1.10396 2.51657 + endloop + endfacet + facet normal 0.166289 -0.221183 0.960951 + outer loop + vertex 1.57666 1.10467 2.51608 + vertex 1.57286 1.10396 2.51657 + vertex 1.5744 1.10195 2.51584 + endloop + endfacet + facet normal 0.1687 -0.219331 0.960955 + outer loop + vertex 1.5744 1.10195 2.51584 + vertex 1.57286 1.10396 2.51657 + vertex 1.5717 1.10036 2.51596 + endloop + endfacet + facet normal 0.172944 -0.226721 0.958482 + outer loop + vertex 1.5744 1.10195 2.51584 + vertex 1.5717 1.10036 2.51596 + vertex 1.57306 1.09827 2.51521 + endloop + endfacet + facet normal 0.122767 -0.256065 0.958832 + outer loop + vertex 1.58341 1.10989 2.51647 + vertex 1.57806 1.10868 2.51683 + vertex 1.58039 1.10617 2.51587 + endloop + endfacet + facet normal 0.116229 -0.2511 0.960958 + outer loop + vertex 1.58409 1.1073 2.51571 + vertex 1.58341 1.10989 2.51647 + vertex 1.58039 1.10617 2.51587 + endloop + endfacet + facet normal 0.0674972 -0.264176 0.96211 + outer loop + vertex 1.58675 1.10951 2.51613 + vertex 1.58341 1.10989 2.51647 + vertex 1.58409 1.1073 2.51571 + endloop + endfacet + facet normal 0.0395415 -0.232394 0.971818 + outer loop + vertex 1.58722 1.10657 2.51541 + vertex 1.58675 1.10951 2.51613 + vertex 1.58409 1.1073 2.51571 + endloop + endfacet + facet normal 0.0478659 -0.199596 0.978709 + outer loop + vertex 1.58409 1.1073 2.51571 + vertex 1.58243 1.10328 2.51498 + vertex 1.58722 1.10657 2.51541 + endloop + endfacet + facet normal 0.0692225 -0.229649 0.970809 + outer loop + vertex 1.58722 1.10657 2.51541 + vertex 1.58243 1.10328 2.51498 + vertex 1.58721 1.1025 2.51445 + endloop + endfacet + facet normal 0.0698805 -0.226124 0.971589 + outer loop + vertex 1.58262 1.09838 2.51382 + vertex 1.58721 1.1025 2.51445 + vertex 1.58243 1.10328 2.51498 + endloop + endfacet + facet normal 0.0787247 -0.235531 0.968673 + outer loop + vertex 1.58756 1.09809 2.51335 + vertex 1.58721 1.1025 2.51445 + vertex 1.58262 1.09838 2.51382 + endloop + endfacet + facet normal 0.0787269 -0.235504 0.968679 + outer loop + vertex 1.58307 1.09371 2.51265 + vertex 1.58756 1.09809 2.51335 + vertex 1.58262 1.09838 2.51382 + endloop + endfacet + facet normal 0.0827843 -0.239462 0.96737 + outer loop + vertex 1.58848 1.09343 2.51212 + vertex 1.58756 1.09809 2.51335 + vertex 1.58307 1.09371 2.51265 + endloop + endfacet + facet normal 0.0817357 -0.253194 0.963956 + outer loop + vertex 1.58848 1.09343 2.51212 + vertex 1.58307 1.09371 2.51265 + vertex 1.58373 1.08984 2.51158 + endloop + endfacet + facet normal 0.0994985 -0.275516 0.956133 + outer loop + vertex 1.58708 1.08959 2.51116 + vertex 1.58848 1.09343 2.51212 + vertex 1.58373 1.08984 2.51158 + endloop + endfacet + facet normal 0.101793 -0.254099 0.961807 + outer loop + vertex 1.58708 1.08959 2.51116 + vertex 1.58373 1.08984 2.51158 + vertex 1.58445 1.08722 2.51081 + endloop + endfacet + facet normal 0.0781125 -0.229086 0.970267 + outer loop + vertex 1.58749 1.08675 2.51045 + vertex 1.58708 1.08959 2.51116 + vertex 1.58445 1.08722 2.51081 + endloop + endfacet + facet normal 0.0819926 -0.207266 0.974843 + outer loop + vertex 1.58445 1.08722 2.51081 + vertex 1.58271 1.0832 2.5101 + vertex 1.58749 1.08675 2.51045 + endloop + endfacet + facet normal 0.035404 -0.235577 0.971211 + outer loop + vertex 1.58708 1.08959 2.51116 + vertex 1.58749 1.08675 2.51045 + vertex 1.59085 1.0902 2.51117 + endloop + endfacet + facet normal 0.0375071 -0.237508 0.970661 + outer loop + vertex 1.58749 1.08675 2.51045 + vertex 1.59182 1.08669 2.51027 + vertex 1.59085 1.0902 2.51117 + endloop + endfacet + facet normal 0.0377339 -0.227983 0.972934 + outer loop + vertex 1.5875 1.08281 2.50953 + vertex 1.59182 1.08669 2.51027 + vertex 1.58749 1.08675 2.51045 + endloop + endfacet + facet normal 0.0971016 -0.227011 0.969039 + outer loop + vertex 1.58749 1.08675 2.51045 + vertex 1.58271 1.0832 2.5101 + vertex 1.5875 1.08281 2.50953 + endloop + endfacet + facet normal 0.0962332 -0.235058 0.967206 + outer loop + vertex 1.58268 1.0784 2.50894 + vertex 1.5875 1.08281 2.50953 + vertex 1.58271 1.0832 2.5101 + endloop + endfacet + facet normal 0.101402 -0.24045 0.96535 + outer loop + vertex 1.5877 1.07837 2.5084 + vertex 1.5875 1.08281 2.50953 + vertex 1.58268 1.0784 2.50894 + endloop + endfacet + facet normal 0.101259 -0.244845 0.96426 + outer loop + vertex 1.58273 1.07372 2.50774 + vertex 1.5877 1.07837 2.5084 + vertex 1.58268 1.0784 2.50894 + endloop + endfacet + facet normal 0.145282 -0.243038 0.959075 + outer loop + vertex 1.58273 1.07372 2.50774 + vertex 1.58268 1.0784 2.50894 + vertex 1.57769 1.07353 2.50846 + endloop + endfacet + facet normal 0.142924 -0.240712 0.960016 + outer loop + vertex 1.57769 1.07353 2.50846 + vertex 1.58268 1.0784 2.50894 + vertex 1.57785 1.07818 2.5096 + endloop + endfacet + facet normal 0.0499967 -0.243601 0.968586 + outer loop + vertex 1.5877 1.07837 2.5084 + vertex 1.59236 1.08274 2.50926 + vertex 1.5875 1.08281 2.50953 + endloop + endfacet + facet normal 0.0578447 -0.251495 0.966128 + outer loop + vertex 1.59296 1.07849 2.50812 + vertex 1.59236 1.08274 2.50926 + vertex 1.5877 1.07837 2.5084 + endloop + endfacet + facet normal 0.0579282 -0.261289 0.963521 + outer loop + vertex 1.58821 1.07359 2.50707 + vertex 1.59296 1.07849 2.50812 + vertex 1.5877 1.07837 2.5084 + endloop + endfacet + facet normal 0.0582792 -0.261607 0.963413 + outer loop + vertex 1.59414 1.07454 2.50697 + vertex 1.59296 1.07849 2.50812 + vertex 1.58821 1.07359 2.50707 + endloop + endfacet + facet normal 0.0627999 -0.290674 0.954759 + outer loop + vertex 1.59414 1.07454 2.50697 + vertex 1.58821 1.07359 2.50707 + vertex 1.5907 1.07062 2.50601 + endloop + endfacet + facet normal 0.0500731 -0.24102 0.969227 + outer loop + vertex 1.59236 1.08274 2.50926 + vertex 1.59182 1.08669 2.51027 + vertex 1.5875 1.08281 2.50953 + endloop + endfacet + facet normal 0.138819 -0.243414 0.959937 + outer loop + vertex 1.58445 1.08722 2.51081 + vertex 1.58373 1.08984 2.51158 + vertex 1.58073 1.08599 2.51103 + endloop + endfacet + facet normal 0.0386838 -0.255728 0.965974 + outer loop + vertex 1.59085 1.0902 2.51117 + vertex 1.58848 1.09343 2.51212 + vertex 1.58708 1.08959 2.51116 + endloop + endfacet + facet normal 0.0331328 -0.259556 0.965159 + outer loop + vertex 1.59421 1.09412 2.51211 + vertex 1.58848 1.09343 2.51212 + vertex 1.59085 1.0902 2.51117 + endloop + endfacet + facet normal 0.0655635 -0.277772 0.958407 + outer loop + vertex 1.58675 1.10951 2.51613 + vertex 1.58832 1.11327 2.51712 + vertex 1.58341 1.10989 2.51647 + endloop + endfacet + facet normal 0.051623 -0.258727 0.96457 + outer loop + vertex 1.58832 1.11327 2.51712 + vertex 1.58284 1.11367 2.51752 + vertex 1.58341 1.10989 2.51647 + endloop + endfacet + facet normal 0.0537139 -0.235626 0.970358 + outer loop + vertex 1.58832 1.11327 2.51712 + vertex 1.58743 1.11819 2.51836 + vertex 1.58284 1.11367 2.51752 + endloop + endfacet + facet normal 0.0492298 -0.231314 0.971633 + outer loop + vertex 1.58284 1.11367 2.51752 + vertex 1.58743 1.11819 2.51836 + vertex 1.58236 1.11813 2.5186 + endloop + endfacet + facet normal 0.0492073 -0.221757 0.97386 + outer loop + vertex 1.58743 1.11819 2.51836 + vertex 1.58628 1.12184 2.51925 + vertex 1.58236 1.11813 2.5186 + endloop + endfacet + facet normal 0.120948 -0.247296 0.961362 + outer loop + vertex 1.58341 1.10989 2.51647 + vertex 1.58284 1.11367 2.51752 + vertex 1.57806 1.10868 2.51683 + endloop + endfacet + facet normal 0.102954 -0.230896 0.967516 + outer loop + vertex 1.57806 1.10868 2.51683 + vertex 1.58284 1.11367 2.51752 + vertex 1.57765 1.11352 2.51803 + endloop + endfacet + facet normal 0.162527 -0.218171 0.962282 + outer loop + vertex 1.57749 1.10225 2.51539 + vertex 1.57666 1.10467 2.51608 + vertex 1.5744 1.10195 2.51584 + endloop + endfacet + facet normal 0.107837 -0.222565 0.968935 + outer loop + vertex 1.58409 1.1073 2.51571 + vertex 1.58039 1.10617 2.51587 + vertex 1.58243 1.10328 2.51498 + endloop + endfacet + facet normal 0.162859 -0.223494 0.961003 + outer loop + vertex 1.5744 1.10195 2.51584 + vertex 1.57306 1.09827 2.51521 + vertex 1.57749 1.10225 2.51539 + endloop + endfacet + facet normal 0.126759 -0.222717 0.966607 + outer loop + vertex 1.58262 1.09838 2.51382 + vertex 1.58243 1.10328 2.51498 + vertex 1.5777 1.09832 2.51445 + endloop + endfacet + facet normal 0.140534 -0.242049 0.960033 + outer loop + vertex 1.58373 1.08984 2.51158 + vertex 1.58307 1.09371 2.51265 + vertex 1.57829 1.08857 2.51205 + endloop + endfacet + facet normal 0.141179 -0.245141 0.959153 + outer loop + vertex 1.58373 1.08984 2.51158 + vertex 1.57829 1.08857 2.51205 + vertex 1.58073 1.08599 2.51103 + endloop + endfacet + facet normal 0.16412 -0.229799 0.9593 + outer loop + vertex 1.57778 1.08203 2.51056 + vertex 1.57693 1.08445 2.51129 + vertex 1.5746 1.08169 2.51102 + endloop + endfacet + facet normal 0.133939 -0.227814 0.964449 + outer loop + vertex 1.58445 1.08722 2.51081 + vertex 1.58073 1.08599 2.51103 + vertex 1.58271 1.0832 2.5101 + endloop + endfacet + facet normal 0.142845 -0.234074 0.961668 + outer loop + vertex 1.58268 1.0784 2.50894 + vertex 1.58271 1.0832 2.5101 + vertex 1.57785 1.07818 2.5096 + endloop + endfacet + facet normal 0.164528 -0.235619 0.957817 + outer loop + vertex 1.5746 1.08169 2.51102 + vertex 1.57327 1.07803 2.51035 + vertex 1.57778 1.08203 2.51056 + endloop + endfacet + facet normal 0.167312 -0.240607 0.956094 + outer loop + vertex 1.57769 1.07353 2.50846 + vertex 1.57785 1.07818 2.5096 + vertex 1.57284 1.07333 2.50926 + endloop + endfacet + facet normal 0.167311 -0.239524 0.956366 + outer loop + vertex 1.57266 1.06851 2.50808 + vertex 1.57769 1.07353 2.50846 + vertex 1.57284 1.07333 2.50926 + endloop + endfacet + facet normal 0.165632 -0.229662 0.959073 + outer loop + vertex 1.56956 1.07719 2.51079 + vertex 1.5681 1.07332 2.51012 + vertex 1.57327 1.07803 2.51035 + endloop + endfacet + facet normal 0.180504 -0.239435 0.953986 + outer loop + vertex 1.57266 1.06851 2.50808 + vertex 1.57284 1.07333 2.50926 + vertex 1.56763 1.06832 2.50898 + endloop + endfacet + facet normal 0.176931 -0.236811 0.955309 + outer loop + vertex 1.56251 1.0633 2.50869 + vertex 1.56763 1.06832 2.50898 + vertex 1.56241 1.06832 2.50995 + endloop + endfacet + facet normal 0.17107 -0.231472 0.957683 + outer loop + vertex 1.56956 1.07719 2.51079 + vertex 1.5666 1.07542 2.51089 + vertex 1.5681 1.07332 2.51012 + endloop + endfacet + facet normal 0.188774 -0.232274 0.954156 + outer loop + vertex 1.56413 1.07256 2.51067 + vertex 1.56322 1.07497 2.51144 + vertex 1.56019 1.07093 2.51106 + endloop + endfacet + facet normal 0.173425 -0.235474 0.956282 + outer loop + vertex 1.56956 1.07719 2.51079 + vertex 1.56776 1.07903 2.51157 + vertex 1.5666 1.07542 2.51089 + endloop + endfacet + facet normal 0.181752 -0.233009 0.955339 + outer loop + vertex 1.56322 1.07497 2.51144 + vertex 1.56269 1.07868 2.51245 + vertex 1.55807 1.07371 2.51211 + endloop + endfacet + facet normal 0.168725 -0.231207 0.958162 + outer loop + vertex 1.57284 1.08367 2.5118 + vertex 1.56761 1.08351 2.51268 + vertex 1.56776 1.07903 2.51157 + endloop + endfacet + facet normal 0.179232 -0.225869 0.957528 + outer loop + vertex 1.56249 1.08324 2.51357 + vertex 1.56759 1.08834 2.51382 + vertex 1.56261 1.08801 2.51468 + endloop + endfacet + facet normal 0.168777 -0.225859 0.959428 + outer loop + vertex 1.57284 1.08367 2.5118 + vertex 1.57278 1.0885 2.51294 + vertex 1.56761 1.08351 2.51268 + endloop + endfacet + facet normal 0.166945 -0.228769 0.959059 + outer loop + vertex 1.5694 1.09764 2.51571 + vertex 1.56565 1.09602 2.51598 + vertex 1.56771 1.09344 2.51501 + endloop + endfacet + facet normal 0.165594 -0.22547 0.960074 + outer loop + vertex 1.5694 1.09764 2.51571 + vertex 1.5685 1.09998 2.51642 + vertex 1.56565 1.09602 2.51598 + endloop + endfacet + facet normal 0.149908 -0.218226 0.964316 + outer loop + vertex 1.57806 1.10868 2.51683 + vertex 1.57273 1.10856 2.51764 + vertex 1.57286 1.10396 2.51657 + endloop + endfacet + facet normal 0.162495 -0.215343 0.962924 + outer loop + vertex 1.56768 1.10835 2.51845 + vertex 1.57261 1.11346 2.51876 + vertex 1.56774 1.11318 2.51952 + endloop + endfacet + facet normal 0.149813 -0.225729 0.962602 + outer loop + vertex 1.57806 1.10868 2.51683 + vertex 1.57765 1.11352 2.51803 + vertex 1.57273 1.10856 2.51764 + endloop + endfacet + facet normal 0.102922 -0.224853 0.968942 + outer loop + vertex 1.58284 1.11367 2.51752 + vertex 1.58236 1.11813 2.5186 + vertex 1.57765 1.11352 2.51803 + endloop + endfacet + facet normal 0.0462959 -0.218817 0.974667 + outer loop + vertex 1.58236 1.11813 2.5186 + vertex 1.58628 1.12184 2.51925 + vertex 1.58234 1.12254 2.51959 + endloop + endfacet + facet normal 0.0429939 -0.235399 0.970947 + outer loop + vertex 1.58628 1.12184 2.51925 + vertex 1.58712 1.12601 2.52022 + vertex 1.58234 1.12254 2.51959 + endloop + endfacet + facet normal 0.139292 -0.21476 0.966683 + outer loop + vertex 1.57261 1.11346 2.51876 + vertex 1.57758 1.1184 2.51914 + vertex 1.57261 1.11864 2.51991 + endloop + endfacet + facet normal 0.16155 -0.207796 0.96474 + outer loop + vertex 1.57419 1.12297 2.52058 + vertex 1.57046 1.12126 2.52083 + vertex 1.57261 1.11864 2.51991 + endloop + endfacet + facet normal 0.161884 -0.208552 0.964521 + outer loop + vertex 1.57419 1.12297 2.52058 + vertex 1.57328 1.1253 2.52123 + vertex 1.57046 1.12126 2.52083 + endloop + endfacet + facet normal 0.113703 -0.202961 0.972563 + outer loop + vertex 1.57929 1.12697 2.52075 + vertex 1.57651 1.12569 2.5208 + vertex 1.5779 1.12331 2.52014 + endloop + endfacet + facet normal 0.129392 -0.237502 0.962731 + outer loop + vertex 1.57929 1.12697 2.52075 + vertex 1.57774 1.12904 2.52147 + vertex 1.57651 1.12569 2.5208 + endloop + endfacet + facet normal 0.147824 -0.204469 0.967647 + outer loop + vertex 1.5676 1.12844 2.52284 + vertex 1.57254 1.13349 2.52315 + vertex 1.56759 1.1334 2.52389 + endloop + endfacet + facet normal 0.147778 -0.207686 0.966968 + outer loop + vertex 1.57254 1.13349 2.52315 + vertex 1.57262 1.13843 2.5242 + vertex 1.56759 1.1334 2.52389 + endloop + endfacet + facet normal 0.132955 -0.232855 0.96338 + outer loop + vertex 1.57774 1.12904 2.52147 + vertex 1.57765 1.1335 2.52256 + vertex 1.57274 1.12888 2.52212 + endloop + endfacet + facet normal 0.107527 -0.208128 0.972173 + outer loop + vertex 1.57254 1.13349 2.52315 + vertex 1.5775 1.13828 2.52363 + vertex 1.57262 1.13843 2.5242 + endloop + endfacet + facet normal 0.0710673 -0.225798 0.971578 + outer loop + vertex 1.58321 1.13305 2.52205 + vertex 1.58263 1.13812 2.52327 + vertex 1.57765 1.1335 2.52256 + endloop + endfacet + facet normal 0.0918189 -0.18392 0.978643 + outer loop + vertex 1.57435 1.147 2.52573 + vertex 1.57298 1.14334 2.52518 + vertex 1.57744 1.14684 2.52541 + endloop + endfacet + facet normal 0.10765 -0.205834 0.972648 + outer loop + vertex 1.5775 1.13828 2.52363 + vertex 1.5775 1.14293 2.52461 + vertex 1.57262 1.13843 2.5242 + endloop + endfacet + facet normal 0.147758 -0.207667 0.966976 + outer loop + vertex 1.56759 1.1334 2.52389 + vertex 1.57262 1.13843 2.5242 + vertex 1.5677 1.13858 2.52498 + endloop + endfacet + facet normal 0.135569 -0.199142 0.970548 + outer loop + vertex 1.57435 1.147 2.52573 + vertex 1.57158 1.14558 2.52583 + vertex 1.57298 1.14334 2.52518 + endloop + endfacet + facet normal 0.164022 -0.204502 0.965026 + outer loop + vertex 1.56929 1.14286 2.52563 + vertex 1.56836 1.14514 2.52627 + vertex 1.5656 1.14114 2.5259 + endloop + endfacet + facet normal 0.144824 -0.217613 0.965231 + outer loop + vertex 1.57435 1.147 2.52573 + vertex 1.57277 1.14896 2.52641 + vertex 1.57158 1.14558 2.52583 + endloop + endfacet + facet normal 0.144501 -0.2061 0.967803 + outer loop + vertex 1.57277 1.14896 2.52641 + vertex 1.57256 1.15335 2.52738 + vertex 1.56772 1.14866 2.5271 + endloop + endfacet + facet normal 0.129281 -0.190691 0.9731 + outer loop + vertex 1.56772 1.14866 2.5271 + vertex 1.57256 1.15335 2.52738 + vertex 1.5674 1.15322 2.52804 + endloop + endfacet + facet normal 0.122287 -0.177898 0.976421 + outer loop + vertex 1.5674 1.15322 2.52804 + vertex 1.57237 1.15819 2.52832 + vertex 1.56748 1.15824 2.52894 + endloop + endfacet + facet normal 0.115505 -0.164833 0.979535 + outer loop + vertex 1.56748 1.15824 2.52894 + vertex 1.57249 1.16323 2.52919 + vertex 1.56782 1.16336 2.52976 + endloop + endfacet + facet normal 0.177138 -0.172314 0.968984 + outer loop + vertex 1.55969 1.16211 2.5309 + vertex 1.55842 1.15818 2.53043 + vertex 1.56335 1.16333 2.53044 + endloop + endfacet + facet normal 0.170809 -0.15167 0.973561 + outer loop + vertex 1.56335 1.16333 2.53044 + vertex 1.56167 1.16514 2.53102 + vertex 1.55969 1.16211 2.5309 + endloop + endfacet + facet normal 0.184482 -0.160474 0.969647 + outer loop + vertex 1.56167 1.16514 2.53102 + vertex 1.55778 1.16374 2.53153 + vertex 1.55969 1.16211 2.5309 + endloop + endfacet + facet normal 0.182102 -0.163249 0.969633 + outer loop + vertex 1.55969 1.16211 2.5309 + vertex 1.55778 1.16374 2.53153 + vertex 1.5568 1.15995 2.53107 + endloop + endfacet + facet normal 0.200029 -0.167353 0.965392 + outer loop + vertex 1.5568 1.15995 2.53107 + vertex 1.55778 1.16374 2.53153 + vertex 1.5528 1.15861 2.53167 + endloop + endfacet + facet normal 0.207476 -0.192352 0.959143 + outer loop + vertex 1.5568 1.15995 2.53107 + vertex 1.5528 1.15861 2.53167 + vertex 1.55473 1.15699 2.53093 + endloop + endfacet + facet normal 0.188721 -0.17954 0.965479 + outer loop + vertex 1.55842 1.15818 2.53043 + vertex 1.5568 1.15995 2.53107 + vertex 1.55473 1.15699 2.53093 + endloop + endfacet + facet normal 0.208965 -0.190582 0.959173 + outer loop + vertex 1.55473 1.15699 2.53093 + vertex 1.5528 1.15861 2.53167 + vertex 1.55171 1.15488 2.53117 + endloop + endfacet + facet normal 0.209172 -0.190891 0.959066 + outer loop + vertex 1.55473 1.15699 2.53093 + vertex 1.55171 1.15488 2.53117 + vertex 1.55329 1.15309 2.53047 + endloop + endfacet + facet normal 0.21281 -0.187605 0.958914 + outer loop + vertex 1.55329 1.15309 2.53047 + vertex 1.55171 1.15488 2.53117 + vertex 1.54944 1.15191 2.53109 + endloop + endfacet + facet normal 0.222079 -0.194573 0.955417 + outer loop + vertex 1.55171 1.15488 2.53117 + vertex 1.54765 1.1535 2.53183 + vertex 1.54944 1.15191 2.53109 + endloop + endfacet + facet normal 0.221877 -0.193888 0.955604 + outer loop + vertex 1.55171 1.15488 2.53117 + vertex 1.5528 1.15861 2.53167 + vertex 1.54765 1.1535 2.53183 + endloop + endfacet + facet normal 0.196061 -0.167529 0.966175 + outer loop + vertex 1.5528 1.15861 2.53167 + vertex 1.5476 1.15805 2.53263 + vertex 1.54765 1.1535 2.53183 + endloop + endfacet + facet normal 0.133437 -0.170105 0.97635 + outer loop + vertex 1.54765 1.1535 2.53183 + vertex 1.5476 1.15805 2.53263 + vertex 1.54289 1.15309 2.53241 + endloop + endfacet + facet normal 0.131151 -0.136086 0.981978 + outer loop + vertex 1.54765 1.1535 2.53183 + vertex 1.54289 1.15309 2.53241 + vertex 1.5428 1.14858 2.5318 + endloop + endfacet + facet normal 0.157294 -0.161805 0.974206 + outer loop + vertex 1.54634 1.14974 2.53142 + vertex 1.54765 1.1535 2.53183 + vertex 1.5428 1.14858 2.5318 + endloop + endfacet + facet normal 0.152136 -0.144946 0.977673 + outer loop + vertex 1.54634 1.14974 2.53142 + vertex 1.5428 1.14858 2.5318 + vertex 1.54414 1.14673 2.53131 + endloop + endfacet + facet normal 0.241448 -0.209412 0.947549 + outer loop + vertex 1.54797 1.14796 2.53061 + vertex 1.54634 1.14974 2.53142 + vertex 1.54414 1.14673 2.53131 + endloop + endfacet + facet normal 0.265425 -0.303012 0.915278 + outer loop + vertex 1.54414 1.14673 2.53131 + vertex 1.54307 1.14297 2.53038 + vertex 1.54797 1.14796 2.53061 + endloop + endfacet + facet normal 0.231152 -0.296113 0.926761 + outer loop + vertex 1.54414 1.14673 2.53131 + vertex 1.54153 1.14485 2.53136 + vertex 1.54307 1.14297 2.53038 + endloop + endfacet + facet normal 0.128722 -0.375465 0.917855 + outer loop + vertex 1.54307 1.14297 2.53038 + vertex 1.54153 1.14485 2.53136 + vertex 1.53985 1.14232 2.53056 + endloop + endfacet + facet normal -0.166545 -0.194771 0.966606 + outer loop + vertex 1.54153 1.14485 2.53136 + vertex 1.53931 1.14484 2.53098 + vertex 1.53985 1.14232 2.53056 + endloop + endfacet + facet normal -0.502298 -0.244711 0.829345 + outer loop + vertex 1.53985 1.14232 2.53056 + vertex 1.53931 1.14484 2.53098 + vertex 1.53799 1.14195 2.52932 + endloop + endfacet + facet normal -0.169843 -0.0565486 0.983847 + outer loop + vertex 1.54153 1.14485 2.53136 + vertex 1.5428 1.14858 2.5318 + vertex 1.53931 1.14484 2.53098 + endloop + endfacet + facet normal -0.137287 -0.0875854 0.986651 + outer loop + vertex 1.5428 1.14858 2.5318 + vertex 1.53913 1.14876 2.5313 + vertex 1.53931 1.14484 2.53098 + endloop + endfacet + facet normal 0.24446 -0.206583 0.947398 + outer loop + vertex 1.54944 1.15191 2.53109 + vertex 1.54634 1.14974 2.53142 + vertex 1.54797 1.14796 2.53061 + endloop + endfacet + facet normal 0.133012 -0.159037 0.978271 + outer loop + vertex 1.54414 1.14673 2.53131 + vertex 1.5428 1.14858 2.5318 + vertex 1.54153 1.14485 2.53136 + endloop + endfacet + facet normal 0.230362 -0.185236 0.955312 + outer loop + vertex 1.54944 1.15191 2.53109 + vertex 1.54765 1.1535 2.53183 + vertex 1.54634 1.14974 2.53142 + endloop + endfacet + facet normal -0.138743 -0.130457 0.981698 + outer loop + vertex 1.5428 1.14858 2.5318 + vertex 1.54289 1.15309 2.53241 + vertex 1.53913 1.14876 2.5313 + endloop + endfacet + facet normal -0.11161 -0.154061 0.981738 + outer loop + vertex 1.53913 1.14876 2.5313 + vertex 1.54289 1.15309 2.53241 + vertex 1.53877 1.1534 2.53199 + endloop + endfacet + facet normal -0.111673 -0.155141 0.98156 + outer loop + vertex 1.54289 1.15309 2.53241 + vertex 1.54262 1.15785 2.53313 + vertex 1.53877 1.1534 2.53199 + endloop + endfacet + facet normal -0.097775 -0.167062 0.981086 + outer loop + vertex 1.53877 1.1534 2.53199 + vertex 1.54262 1.15785 2.53313 + vertex 1.53831 1.15826 2.53277 + endloop + endfacet + facet normal -0.0957732 -0.142249 0.985187 + outer loop + vertex 1.54262 1.15785 2.53313 + vertex 1.54233 1.16294 2.53384 + vertex 1.53831 1.15826 2.53277 + endloop + endfacet + facet normal -0.0935006 -0.144185 0.985123 + outer loop + vertex 1.53831 1.15826 2.53277 + vertex 1.54233 1.16294 2.53384 + vertex 1.53755 1.16354 2.53347 + endloop + endfacet + facet normal 0.0895794 -0.131956 0.9872 + outer loop + vertex 1.54262 1.15785 2.53313 + vertex 1.54736 1.16287 2.53337 + vertex 1.54233 1.16294 2.53384 + endloop + endfacet + facet normal 0.105013 -0.146349 0.983643 + outer loop + vertex 1.5476 1.15805 2.53263 + vertex 1.54736 1.16287 2.53337 + vertex 1.54262 1.15785 2.53313 + endloop + endfacet + facet normal 0.174533 -0.141574 0.97442 + outer loop + vertex 1.5476 1.15805 2.53263 + vertex 1.55262 1.16319 2.53248 + vertex 1.54736 1.16287 2.53337 + endloop + endfacet + facet normal 0.104938 -0.14344 0.98408 + outer loop + vertex 1.54289 1.15309 2.53241 + vertex 1.5476 1.15805 2.53263 + vertex 1.54262 1.15785 2.53313 + endloop + endfacet + facet normal 0.195696 -0.162458 0.967114 + outer loop + vertex 1.5528 1.15861 2.53167 + vertex 1.55262 1.16319 2.53248 + vertex 1.5476 1.15805 2.53263 + endloop + endfacet + facet normal 0.19508 -0.162503 0.967231 + outer loop + vertex 1.55778 1.16374 2.53153 + vertex 1.55262 1.16319 2.53248 + vertex 1.5528 1.15861 2.53167 + endloop + endfacet + facet normal 0.179422 -0.145142 0.973006 + outer loop + vertex 1.56167 1.16514 2.53102 + vertex 1.56269 1.16889 2.53139 + vertex 1.55778 1.16374 2.53153 + endloop + endfacet + facet normal 0.165464 -0.14167 0.975987 + outer loop + vertex 1.56454 1.1673 2.53085 + vertex 1.56269 1.16889 2.53139 + vertex 1.56167 1.16514 2.53102 + endloop + endfacet + facet normal 0.162581 -0.145035 0.975978 + outer loop + vertex 1.56657 1.17021 2.53094 + vertex 1.56269 1.16889 2.53139 + vertex 1.56454 1.1673 2.53085 + endloop + endfacet + facet normal 0.139506 -0.129154 0.981762 + outer loop + vertex 1.56819 1.16825 2.53045 + vertex 1.56657 1.17021 2.53094 + vertex 1.56454 1.1673 2.53085 + endloop + endfacet + facet normal 0.142702 -0.142312 0.979481 + outer loop + vertex 1.56454 1.1673 2.53085 + vertex 1.56335 1.16333 2.53044 + vertex 1.56819 1.16825 2.53045 + endloop + endfacet + facet normal 0.168188 -0.16282 0.972215 + outer loop + vertex 1.56657 1.17021 2.53094 + vertex 1.56773 1.17375 2.53133 + vertex 1.56269 1.16889 2.53139 + endloop + endfacet + facet normal 0.14462 -0.138321 0.979772 + outer loop + vertex 1.56773 1.17375 2.53133 + vertex 1.56257 1.17338 2.53204 + vertex 1.56269 1.16889 2.53139 + endloop + endfacet + facet normal 0.176205 -0.136803 0.974801 + outer loop + vertex 1.56269 1.16889 2.53139 + vertex 1.56257 1.17338 2.53204 + vertex 1.55761 1.16833 2.53223 + endloop + endfacet + facet normal 0.176682 -0.142506 0.973897 + outer loop + vertex 1.56269 1.16889 2.53139 + vertex 1.55761 1.16833 2.53223 + vertex 1.55778 1.16374 2.53153 + endloop + endfacet + facet normal 0.193512 -0.141433 0.97085 + outer loop + vertex 1.55778 1.16374 2.53153 + vertex 1.55761 1.16833 2.53223 + vertex 1.55262 1.16319 2.53248 + endloop + endfacet + facet normal 0.18613 -0.134134 0.973326 + outer loop + vertex 1.55262 1.16319 2.53248 + vertex 1.55761 1.16833 2.53223 + vertex 1.55242 1.168 2.53318 + endloop + endfacet + facet normal 0.174294 -0.134923 0.975406 + outer loop + vertex 1.55262 1.16319 2.53248 + vertex 1.55242 1.168 2.53318 + vertex 1.54736 1.16287 2.53337 + endloop + endfacet + facet normal 0.166486 -0.127139 0.977813 + outer loop + vertex 1.54736 1.16287 2.53337 + vertex 1.55242 1.168 2.53318 + vertex 1.54729 1.16798 2.53405 + endloop + endfacet + facet normal 0.0896411 -0.129613 0.987504 + outer loop + vertex 1.54736 1.16287 2.53337 + vertex 1.54729 1.16798 2.53405 + vertex 1.54233 1.16294 2.53384 + endloop + endfacet + facet normal 0.110123 -0.149569 0.9826 + outer loop + vertex 1.54233 1.16294 2.53384 + vertex 1.54729 1.16798 2.53405 + vertex 1.54246 1.16825 2.53463 + endloop + endfacet + facet normal -0.0935866 -0.144952 0.985003 + outer loop + vertex 1.54233 1.16294 2.53384 + vertex 1.54246 1.16825 2.53463 + vertex 1.53755 1.16354 2.53347 + endloop + endfacet + facet normal 0.111798 -0.126908 0.985594 + outer loop + vertex 1.54729 1.16798 2.53405 + vertex 1.5475 1.17321 2.5347 + vertex 1.54246 1.16825 2.53463 + endloop + endfacet + facet normal 0.166842 -0.182625 0.968923 + outer loop + vertex 1.54246 1.16825 2.53463 + vertex 1.5475 1.17321 2.5347 + vertex 1.54286 1.17336 2.53553 + endloop + endfacet + facet normal 0.169961 -0.131676 0.976614 + outer loop + vertex 1.54787 1.17837 2.53533 + vertex 1.54286 1.17336 2.53553 + vertex 1.5475 1.17321 2.5347 + endloop + endfacet + facet normal 0.177211 -0.132044 0.975275 + outer loop + vertex 1.5475 1.17321 2.5347 + vertex 1.55258 1.17831 2.53447 + vertex 1.54787 1.17837 2.53533 + endloop + endfacet + facet normal 0.177127 -0.134364 0.974973 + outer loop + vertex 1.55291 1.18354 2.53513 + vertex 1.54787 1.17837 2.53533 + vertex 1.55258 1.17831 2.53447 + endloop + endfacet + facet normal 0.163558 -0.133819 0.977415 + outer loop + vertex 1.55258 1.17831 2.53447 + vertex 1.5576 1.18343 2.53433 + vertex 1.55291 1.18354 2.53513 + endloop + endfacet + facet normal 0.162533 -0.155351 0.974397 + outer loop + vertex 1.55793 1.18863 2.5351 + vertex 1.55291 1.18354 2.53513 + vertex 1.5576 1.18343 2.53433 + endloop + endfacet + facet normal 0.144997 -0.154657 0.97727 + outer loop + vertex 1.5576 1.18343 2.53433 + vertex 1.56267 1.18849 2.53438 + vertex 1.55793 1.18863 2.5351 + endloop + endfacet + facet normal 0.144142 -0.170829 0.9747 + outer loop + vertex 1.56309 1.19357 2.5352 + vertex 1.55793 1.18863 2.5351 + vertex 1.56267 1.18849 2.53438 + endloop + endfacet + facet normal 0.134808 -0.161135 0.977682 + outer loop + vertex 1.55918 1.19256 2.53558 + vertex 1.55793 1.18863 2.5351 + vertex 1.56309 1.19357 2.5352 + endloop + endfacet + facet normal 0.135891 -0.165677 0.976773 + outer loop + vertex 1.56309 1.19357 2.5352 + vertex 1.56135 1.19545 2.53576 + vertex 1.55918 1.19256 2.53558 + endloop + endfacet + facet normal 0.156 -0.18046 0.971132 + outer loop + vertex 1.56135 1.19545 2.53576 + vertex 1.55737 1.19414 2.53616 + vertex 1.55918 1.19256 2.53558 + endloop + endfacet + facet normal 0.158898 -0.177193 0.971264 + outer loop + vertex 1.55918 1.19256 2.53558 + vertex 1.55737 1.19414 2.53616 + vertex 1.55617 1.19049 2.53569 + endloop + endfacet + facet normal 0.187863 -0.185875 0.964447 + outer loop + vertex 1.55617 1.19049 2.53569 + vertex 1.55737 1.19414 2.53616 + vertex 1.55227 1.18912 2.53619 + endloop + endfacet + facet normal 0.187141 -0.183604 0.965022 + outer loop + vertex 1.55617 1.19049 2.53569 + vertex 1.55227 1.18912 2.53619 + vertex 1.55409 1.18755 2.53553 + endloop + endfacet + facet normal 0.15567 -0.161875 0.974455 + outer loop + vertex 1.55793 1.18863 2.5351 + vertex 1.55617 1.19049 2.53569 + vertex 1.55409 1.18755 2.53553 + endloop + endfacet + facet normal 0.192009 -0.177999 0.965116 + outer loop + vertex 1.55409 1.18755 2.53553 + vertex 1.55227 1.18912 2.53619 + vertex 1.55116 1.18542 2.53573 + endloop + endfacet + facet normal 0.172079 -0.149786 0.973629 + outer loop + vertex 1.55409 1.18755 2.53553 + vertex 1.55116 1.18542 2.53573 + vertex 1.55291 1.18354 2.53513 + endloop + endfacet + facet normal 0.177666 -0.14454 0.973418 + outer loop + vertex 1.55291 1.18354 2.53513 + vertex 1.55116 1.18542 2.53573 + vertex 1.54911 1.1824 2.53565 + endloop + endfacet + facet normal 0.221566 -0.173974 0.959501 + outer loop + vertex 1.55116 1.18542 2.53573 + vertex 1.54726 1.18396 2.53636 + vertex 1.54911 1.1824 2.53565 + endloop + endfacet + facet normal 0.225676 -0.169077 0.959418 + outer loop + vertex 1.54911 1.1824 2.53565 + vertex 1.54726 1.18396 2.53636 + vertex 1.54616 1.1802 2.53596 + endloop + endfacet + facet normal 0.205188 -0.14029 0.968616 + outer loop + vertex 1.54911 1.1824 2.53565 + vertex 1.54616 1.1802 2.53596 + vertex 1.54787 1.17837 2.53533 + endloop + endfacet + facet normal 0.204065 -0.141366 0.968697 + outer loop + vertex 1.54787 1.17837 2.53533 + vertex 1.54616 1.1802 2.53596 + vertex 1.54408 1.1772 2.53596 + endloop + endfacet + facet normal 0.225713 -0.156424 0.961553 + outer loop + vertex 1.54616 1.1802 2.53596 + vertex 1.54244 1.17889 2.53662 + vertex 1.54408 1.1772 2.53596 + endloop + endfacet + facet normal 0.216881 -0.165204 0.962117 + outer loop + vertex 1.54408 1.1772 2.53596 + vertex 1.54244 1.17889 2.53662 + vertex 1.54128 1.17526 2.53625 + endloop + endfacet + facet normal 0.226334 -0.179498 0.957368 + outer loop + vertex 1.54408 1.1772 2.53596 + vertex 1.54128 1.17526 2.53625 + vertex 1.54286 1.17336 2.53553 + endloop + endfacet + facet normal 0.229999 -0.170212 0.95819 + outer loop + vertex 1.54616 1.1802 2.53596 + vertex 1.54726 1.18396 2.53636 + vertex 1.54244 1.17889 2.53662 + endloop + endfacet + facet normal 0.221709 -0.162166 0.961534 + outer loop + vertex 1.54726 1.18396 2.53636 + vertex 1.5424 1.18316 2.53735 + vertex 1.54244 1.17889 2.53662 + endloop + endfacet + facet normal 0.223176 -0.17413 0.959099 + outer loop + vertex 1.54726 1.18396 2.53636 + vertex 1.54728 1.18836 2.53715 + vertex 1.5424 1.18316 2.53735 + endloop + endfacet + facet normal 0.198125 -0.150219 0.968597 + outer loop + vertex 1.5424 1.18316 2.53735 + vertex 1.54728 1.18836 2.53715 + vertex 1.54227 1.18772 2.53808 + endloop + endfacet + facet normal 0.113315 -0.154664 0.981447 + outer loop + vertex 1.5424 1.18316 2.53735 + vertex 1.54227 1.18772 2.53808 + vertex 1.53783 1.18273 2.53781 + endloop + endfacet + facet normal 0.112117 -0.139597 0.983841 + outer loop + vertex 1.53819 1.17841 2.53715 + vertex 1.5424 1.18316 2.53735 + vertex 1.53783 1.18273 2.53781 + endloop + endfacet + facet normal -0.171123 -0.16177 0.971878 + outer loop + vertex 1.53819 1.17841 2.53715 + vertex 1.53783 1.18273 2.53781 + vertex 1.53443 1.1785 2.5365 + endloop + endfacet + facet normal -0.193009 -0.143811 0.970601 + outer loop + vertex 1.53443 1.1785 2.5365 + vertex 1.53783 1.18273 2.53781 + vertex 1.53393 1.18326 2.53711 + endloop + endfacet + facet normal -0.192542 -0.139459 0.971328 + outer loop + vertex 1.53783 1.18273 2.53781 + vertex 1.5376 1.18758 2.53846 + vertex 1.53393 1.18326 2.53711 + endloop + endfacet + facet normal -0.189353 -0.142238 0.971552 + outer loop + vertex 1.53393 1.18326 2.53711 + vertex 1.5376 1.18758 2.53846 + vertex 1.53363 1.18834 2.5378 + endloop + endfacet + facet normal -0.190045 -0.146553 0.970775 + outer loop + vertex 1.5376 1.18758 2.53846 + vertex 1.5376 1.19278 2.53924 + vertex 1.53363 1.18834 2.5378 + endloop + endfacet + facet normal -0.107081 -0.220334 0.969529 + outer loop + vertex 1.53363 1.18834 2.5378 + vertex 1.5376 1.19278 2.53924 + vertex 1.5335 1.19364 2.53899 + endloop + endfacet + facet normal -0.101368 -0.191375 0.976268 + outer loop + vertex 1.53788 1.198 2.5403 + vertex 1.5335 1.19364 2.53899 + vertex 1.5376 1.19278 2.53924 + endloop + endfacet + facet normal 0.14179 -0.20286 0.968888 + outer loop + vertex 1.5376 1.19278 2.53924 + vertex 1.54249 1.1979 2.5396 + vertex 1.53788 1.198 2.5403 + endloop + endfacet + facet normal 0.143535 -0.167424 0.97538 + outer loop + vertex 1.54292 1.20313 2.54043 + vertex 1.53788 1.198 2.5403 + vertex 1.54249 1.1979 2.5396 + endloop + endfacet + facet normal 0.191074 -0.16999 0.966744 + outer loop + vertex 1.54249 1.1979 2.5396 + vertex 1.54764 1.20314 2.5395 + vertex 1.54292 1.20313 2.54043 + endloop + endfacet + facet normal 0.191355 -0.160503 0.968309 + outer loop + vertex 1.54806 1.20832 2.54028 + vertex 1.54292 1.20313 2.54043 + vertex 1.54764 1.20314 2.5395 + endloop + endfacet + facet normal 0.181885 -0.160017 0.970212 + outer loop + vertex 1.54764 1.20314 2.5395 + vertex 1.5527 1.20829 2.5394 + vertex 1.54806 1.20832 2.54028 + endloop + endfacet + facet normal 0.181775 -0.162934 0.969748 + outer loop + vertex 1.55305 1.21345 2.54021 + vertex 1.54806 1.20832 2.54028 + vertex 1.5527 1.20829 2.5394 + endloop + endfacet + facet normal 0.158967 -0.162042 0.973895 + outer loop + vertex 1.5527 1.20829 2.5394 + vertex 1.55768 1.21339 2.53944 + vertex 1.55305 1.21345 2.54021 + endloop + endfacet + facet normal 0.159024 -0.16054 0.974135 + outer loop + vertex 1.55802 1.21854 2.54023 + vertex 1.55305 1.21345 2.54021 + vertex 1.55768 1.21339 2.53944 + endloop + endfacet + facet normal 0.125407 -0.159144 0.979258 + outer loop + vertex 1.55768 1.21339 2.53944 + vertex 1.56269 1.21838 2.53961 + vertex 1.55802 1.21854 2.54023 + endloop + endfacet + facet normal 0.125796 -0.151964 0.980348 + outer loop + vertex 1.56301 1.22327 2.54033 + vertex 1.55802 1.21854 2.54023 + vertex 1.56269 1.21838 2.53961 + endloop + endfacet + facet normal 0.0783427 -0.149669 0.985627 + outer loop + vertex 1.56269 1.21838 2.53961 + vertex 1.56757 1.22291 2.53991 + vertex 1.56301 1.22327 2.54033 + endloop + endfacet + facet normal 0.0785081 -0.14786 0.985887 + outer loop + vertex 1.56752 1.22684 2.5405 + vertex 1.56301 1.22327 2.54033 + vertex 1.56757 1.22291 2.53991 + endloop + endfacet + facet normal 0.0345192 -0.148829 0.98826 + outer loop + vertex 1.56757 1.22291 2.53991 + vertex 1.57193 1.22693 2.54036 + vertex 1.56752 1.22684 2.5405 + endloop + endfacet + facet normal 0.0347166 -0.161491 0.986263 + outer loop + vertex 1.56752 1.22684 2.5405 + vertex 1.57193 1.22693 2.54036 + vertex 1.57083 1.23032 2.54096 + endloop + endfacet + facet normal 0.0413449 -0.167637 0.984981 + outer loop + vertex 1.56679 1.22936 2.54096 + vertex 1.56752 1.22684 2.5405 + vertex 1.57083 1.23032 2.54096 + endloop + endfacet + facet normal 0.0447483 -0.182042 0.982272 + outer loop + vertex 1.57083 1.23032 2.54096 + vertex 1.56825 1.23316 2.5416 + vertex 1.56679 1.22936 2.54096 + endloop + endfacet + facet normal 0.104421 -0.203487 0.973493 + outer loop + vertex 1.56679 1.22936 2.54096 + vertex 1.56825 1.23316 2.5416 + vertex 1.56264 1.22872 2.54127 + endloop + endfacet + facet normal 0.103349 -0.195809 0.975181 + outer loop + vertex 1.56679 1.22936 2.54096 + vertex 1.56264 1.22872 2.54127 + vertex 1.56433 1.22692 2.54073 + endloop + endfacet + facet normal 0.123496 -0.177164 0.976402 + outer loop + vertex 1.56433 1.22692 2.54073 + vertex 1.56264 1.22872 2.54127 + vertex 1.56138 1.22528 2.54081 + endloop + endfacet + facet normal 0.107727 -0.148396 0.983043 + outer loop + vertex 1.56433 1.22692 2.54073 + vertex 1.56138 1.22528 2.54081 + vertex 1.56301 1.22327 2.54033 + endloop + endfacet + facet normal 0.117281 -0.140653 0.983088 + outer loop + vertex 1.56301 1.22327 2.54033 + vertex 1.56138 1.22528 2.54081 + vertex 1.55924 1.22247 2.54066 + endloop + endfacet + facet normal 0.151104 -0.1659 0.974497 + outer loop + vertex 1.56138 1.22528 2.54081 + vertex 1.55744 1.22403 2.54121 + vertex 1.55924 1.22247 2.54066 + endloop + endfacet + facet normal 0.155843 -0.160475 0.974659 + outer loop + vertex 1.55924 1.22247 2.54066 + vertex 1.55744 1.22403 2.54121 + vertex 1.55628 1.22041 2.54079 + endloop + endfacet + facet normal 0.150904 -0.153277 0.976593 + outer loop + vertex 1.55924 1.22247 2.54066 + vertex 1.55628 1.22041 2.54079 + vertex 1.55802 1.21854 2.54023 + endloop + endfacet + facet normal 0.153237 -0.151103 0.976569 + outer loop + vertex 1.55802 1.21854 2.54023 + vertex 1.55628 1.22041 2.54079 + vertex 1.55423 1.21743 2.54066 + endloop + endfacet + facet normal 0.173643 -0.164902 0.970904 + outer loop + vertex 1.55628 1.22041 2.54079 + vertex 1.55241 1.219 2.54125 + vertex 1.55423 1.21743 2.54066 + endloop + endfacet + facet normal 0.175047 -0.163286 0.970925 + outer loop + vertex 1.55423 1.21743 2.54066 + vertex 1.55241 1.219 2.54125 + vertex 1.55133 1.21528 2.54082 + endloop + endfacet + facet normal 0.173738 -0.161475 0.971463 + outer loop + vertex 1.55423 1.21743 2.54066 + vertex 1.55133 1.21528 2.54082 + vertex 1.55305 1.21345 2.54021 + endloop + endfacet + facet normal 0.176007 -0.159325 0.97141 + outer loop + vertex 1.55305 1.21345 2.54021 + vertex 1.55133 1.21528 2.54082 + vertex 1.5493 1.2123 2.5407 + endloop + endfacet + facet normal 0.19219 -0.170125 0.966499 + outer loop + vertex 1.55133 1.21528 2.54082 + vertex 1.54743 1.21391 2.54135 + vertex 1.5493 1.2123 2.5407 + endloop + endfacet + facet normal 0.194908 -0.166948 0.966509 + outer loop + vertex 1.5493 1.2123 2.5407 + vertex 1.54743 1.21391 2.54135 + vertex 1.54637 1.21018 2.54092 + endloop + endfacet + facet normal 0.190748 -0.161001 0.968346 + outer loop + vertex 1.5493 1.2123 2.5407 + vertex 1.54637 1.21018 2.54092 + vertex 1.54806 1.20832 2.54028 + endloop + endfacet + facet normal 0.194172 -0.157819 0.968189 + outer loop + vertex 1.54806 1.20832 2.54028 + vertex 1.54637 1.21018 2.54092 + vertex 1.54425 1.20718 2.54086 + endloop + endfacet + facet normal 0.192543 -0.156682 0.968699 + outer loop + vertex 1.54637 1.21018 2.54092 + vertex 1.54243 1.20884 2.54149 + vertex 1.54425 1.20718 2.54086 + endloop + endfacet + facet normal 0.193365 -0.155773 0.968682 + outer loop + vertex 1.54425 1.20718 2.54086 + vertex 1.54243 1.20884 2.54149 + vertex 1.54127 1.20504 2.54111 + endloop + endfacet + facet normal 0.200989 -0.166775 0.965292 + outer loop + vertex 1.54425 1.20718 2.54086 + vertex 1.54127 1.20504 2.54111 + vertex 1.54292 1.20313 2.54043 + endloop + endfacet + facet normal 0.194029 -0.172914 0.965636 + outer loop + vertex 1.54292 1.20313 2.54043 + vertex 1.54127 1.20504 2.54111 + vertex 1.53913 1.20199 2.54099 + endloop + endfacet + facet normal 0.13209 -0.130057 0.982668 + outer loop + vertex 1.54127 1.20504 2.54111 + vertex 1.53767 1.20387 2.54144 + vertex 1.53913 1.20199 2.54099 + endloop + endfacet + facet normal 0.111898 -0.145866 0.982956 + outer loop + vertex 1.53913 1.20199 2.54099 + vertex 1.53767 1.20387 2.54144 + vertex 1.53646 1.20007 2.54101 + endloop + endfacet + facet normal 0.164514 -0.219247 0.961699 + outer loop + vertex 1.53913 1.20199 2.54099 + vertex 1.53646 1.20007 2.54101 + vertex 1.53788 1.198 2.5403 + endloop + endfacet + facet normal 0.0954874 -0.26571 0.959312 + outer loop + vertex 1.53788 1.198 2.5403 + vertex 1.53646 1.20007 2.54101 + vertex 1.53455 1.19736 2.54045 + endloop + endfacet + facet normal -0.0425205 -0.173882 0.983848 + outer loop + vertex 1.53646 1.20007 2.54101 + vertex 1.53405 1.19982 2.54086 + vertex 1.53455 1.19736 2.54045 + endloop + endfacet + facet normal -0.223975 -0.205671 0.952646 + outer loop + vertex 1.53455 1.19736 2.54045 + vertex 1.53405 1.19982 2.54086 + vertex 1.5324 1.19656 2.53977 + endloop + endfacet + facet normal -0.176377 -0.31689 0.931918 + outer loop + vertex 1.53455 1.19736 2.54045 + vertex 1.5324 1.19656 2.53977 + vertex 1.5335 1.19364 2.53899 + endloop + endfacet + facet normal -0.0513083 -0.0950509 0.994149 + outer loop + vertex 1.53646 1.20007 2.54101 + vertex 1.53767 1.20387 2.54144 + vertex 1.53405 1.19982 2.54086 + endloop + endfacet + facet normal -0.0226832 -0.120397 0.992467 + outer loop + vertex 1.53767 1.20387 2.54144 + vertex 1.53362 1.2036 2.54131 + vertex 1.53405 1.19982 2.54086 + endloop + endfacet + facet normal -0.0205227 -0.151079 0.988309 + outer loop + vertex 1.53767 1.20387 2.54144 + vertex 1.53761 1.20845 2.54214 + vertex 1.53362 1.2036 2.54131 + endloop + endfacet + facet normal 0.00625111 -0.172511 0.984988 + outer loop + vertex 1.53362 1.2036 2.54131 + vertex 1.53761 1.20845 2.54214 + vertex 1.53285 1.20877 2.54222 + endloop + endfacet + facet normal 0.00548172 -0.183391 0.983025 + outer loop + vertex 1.53761 1.20845 2.54214 + vertex 1.53757 1.21322 2.54303 + vertex 1.53285 1.20877 2.54222 + endloop + endfacet + facet normal 0.0714944 -0.250241 0.96554 + outer loop + vertex 1.53285 1.20877 2.54222 + vertex 1.53757 1.21322 2.54303 + vertex 1.53393 1.21392 2.54348 + endloop + endfacet + facet normal 0.0871037 -0.178616 0.980056 + outer loop + vertex 1.53757 1.21322 2.54303 + vertex 1.53758 1.21798 2.54389 + vertex 1.53393 1.21392 2.54348 + endloop + endfacet + facet normal 0.082581 -0.174658 0.98116 + outer loop + vertex 1.53393 1.21392 2.54348 + vertex 1.53758 1.21798 2.54389 + vertex 1.53325 1.21797 2.54426 + endloop + endfacet + facet normal 0.0826948 -0.164671 0.982876 + outer loop + vertex 1.53758 1.21798 2.54389 + vertex 1.53758 1.2229 2.54472 + vertex 1.53325 1.21797 2.54426 + endloop + endfacet + facet normal 0.171983 -0.240441 0.955306 + outer loop + vertex 1.53325 1.21797 2.54426 + vertex 1.53758 1.2229 2.54472 + vertex 1.53308 1.22284 2.54551 + endloop + endfacet + facet normal 0.173816 -0.161625 0.971424 + outer loop + vertex 1.53787 1.22809 2.54553 + vertex 1.53308 1.22284 2.54551 + vertex 1.53758 1.2229 2.54472 + endloop + endfacet + facet normal 0.209393 -0.162522 0.964231 + outer loop + vertex 1.53758 1.2229 2.54472 + vertex 1.54256 1.2281 2.54451 + vertex 1.53787 1.22809 2.54553 + endloop + endfacet + facet normal 0.210147 -0.137439 0.967961 + outer loop + vertex 1.54292 1.2334 2.54519 + vertex 1.53787 1.22809 2.54553 + vertex 1.54256 1.2281 2.54451 + endloop + endfacet + facet normal 0.183578 -0.136375 0.973499 + outer loop + vertex 1.54256 1.2281 2.54451 + vertex 1.54762 1.23322 2.54427 + vertex 1.54292 1.2334 2.54519 + endloop + endfacet + facet normal 0.183012 -0.145174 0.972333 + outer loop + vertex 1.54792 1.23868 2.54503 + vertex 1.54292 1.2334 2.54519 + vertex 1.54762 1.23322 2.54427 + endloop + endfacet + facet normal 0.163563 -0.144615 0.975876 + outer loop + vertex 1.54762 1.23322 2.54427 + vertex 1.55261 1.23818 2.54417 + vertex 1.54792 1.23868 2.54503 + endloop + endfacet + facet normal 0.163052 -0.148535 0.975373 + outer loop + vertex 1.55261 1.23818 2.54417 + vertex 1.55315 1.24337 2.54487 + vertex 1.54792 1.23868 2.54503 + endloop + endfacet + facet normal 0.163021 -0.1485 0.975383 + outer loop + vertex 1.54792 1.23868 2.54503 + vertex 1.55315 1.24337 2.54487 + vertex 1.54956 1.24381 2.54554 + endloop + endfacet + facet normal 0.163592 -0.144626 0.975869 + outer loop + vertex 1.55359 1.24818 2.54551 + vertex 1.54956 1.24381 2.54554 + vertex 1.55315 1.24337 2.54487 + endloop + endfacet + facet normal 0.139176 -0.142921 0.9799 + outer loop + vertex 1.55315 1.24337 2.54487 + vertex 1.55793 1.24821 2.5449 + vertex 1.55359 1.24818 2.54551 + endloop + endfacet + facet normal 0.139314 -0.131845 0.981432 + outer loop + vertex 1.55823 1.25303 2.5455 + vertex 1.55359 1.24818 2.54551 + vertex 1.55793 1.24821 2.5449 + endloop + endfacet + facet normal 0.139388 -0.131916 0.981412 + outer loop + vertex 1.5546 1.25196 2.54588 + vertex 1.55359 1.24818 2.54551 + vertex 1.55823 1.25303 2.5455 + endloop + endfacet + facet normal 0.136722 -0.122319 0.983028 + outer loop + vertex 1.55823 1.25303 2.5455 + vertex 1.5566 1.25492 2.54597 + vertex 1.5546 1.25196 2.54588 + endloop + endfacet + facet normal 0.167627 -0.14289 0.97544 + outer loop + vertex 1.5566 1.25492 2.54597 + vertex 1.55272 1.2536 2.54644 + vertex 1.5546 1.25196 2.54588 + endloop + endfacet + facet normal 0.169087 -0.141217 0.975432 + outer loop + vertex 1.5546 1.25196 2.54588 + vertex 1.55272 1.2536 2.54644 + vertex 1.55176 1.24981 2.54606 + endloop + endfacet + facet normal 0.190022 -0.146059 0.970855 + outer loop + vertex 1.55176 1.24981 2.54606 + vertex 1.55272 1.2536 2.54644 + vertex 1.54784 1.24842 2.54662 + endloop + endfacet + facet normal 0.193055 -0.155452 0.968795 + outer loop + vertex 1.55176 1.24981 2.54606 + vertex 1.54784 1.24842 2.54662 + vertex 1.54999 1.24695 2.54595 + endloop + endfacet + facet normal 0.166873 -0.139546 0.976054 + outer loop + vertex 1.55359 1.24818 2.54551 + vertex 1.55176 1.24981 2.54606 + vertex 1.54999 1.24695 2.54595 + endloop + endfacet + facet normal 0.193214 -0.155223 0.9688 + outer loop + vertex 1.54999 1.24695 2.54595 + vertex 1.54784 1.24842 2.54662 + vertex 1.54719 1.24464 2.54614 + endloop + endfacet + facet normal 0.214449 -0.158266 0.963828 + outer loop + vertex 1.54719 1.24464 2.54614 + vertex 1.54784 1.24842 2.54662 + vertex 1.54282 1.24301 2.54685 + endloop + endfacet + facet normal 0.218258 -0.169699 0.961023 + outer loop + vertex 1.54719 1.24464 2.54614 + vertex 1.54282 1.24301 2.54685 + vertex 1.54554 1.24102 2.54587 + endloop + endfacet + facet normal 0.219724 -0.167704 0.961039 + outer loop + vertex 1.54282 1.24301 2.54685 + vertex 1.54143 1.23815 2.54631 + vertex 1.54554 1.24102 2.54587 + endloop + endfacet + facet normal 0.228135 -0.180422 0.956766 + outer loop + vertex 1.54554 1.24102 2.54587 + vertex 1.54143 1.23815 2.54631 + vertex 1.54389 1.23743 2.54559 + endloop + endfacet + facet normal 0.184574 -0.161363 0.969481 + outer loop + vertex 1.54389 1.23743 2.54559 + vertex 1.54792 1.23868 2.54503 + vertex 1.54554 1.24102 2.54587 + endloop + endfacet + facet normal 0.229268 -0.176964 0.957142 + outer loop + vertex 1.54389 1.23743 2.54559 + vertex 1.54143 1.23815 2.54631 + vertex 1.54106 1.23515 2.54585 + endloop + endfacet + facet normal 0.206262 -0.147171 0.967366 + outer loop + vertex 1.54389 1.23743 2.54559 + vertex 1.54106 1.23515 2.54585 + vertex 1.54292 1.2334 2.54519 + endloop + endfacet + facet normal 0.213773 -0.139009 0.966942 + outer loop + vertex 1.54292 1.2334 2.54519 + vertex 1.54106 1.23515 2.54585 + vertex 1.53913 1.23222 2.54585 + endloop + endfacet + facet normal 0.245227 -0.159624 0.956234 + outer loop + vertex 1.54106 1.23515 2.54585 + vertex 1.5373 1.23365 2.54656 + vertex 1.53913 1.23222 2.54585 + endloop + endfacet + facet normal 0.251231 -0.151796 0.95595 + outer loop + vertex 1.53913 1.23222 2.54585 + vertex 1.5373 1.23365 2.54656 + vertex 1.53621 1.22994 2.54626 + endloop + endfacet + facet normal 0.251503 -0.152169 0.955819 + outer loop + vertex 1.53913 1.23222 2.54585 + vertex 1.53621 1.22994 2.54626 + vertex 1.53787 1.22809 2.54553 + endloop + endfacet + facet normal 0.245611 -0.157721 0.956452 + outer loop + vertex 1.53787 1.22809 2.54553 + vertex 1.53621 1.22994 2.54626 + vertex 1.53414 1.22678 2.54627 + endloop + endfacet + facet normal 0.168962 -0.107455 0.979748 + outer loop + vertex 1.53621 1.22994 2.54626 + vertex 1.5328 1.22859 2.5467 + vertex 1.53414 1.22678 2.54627 + endloop + endfacet + facet normal 0.146762 -0.124277 0.981334 + outer loop + vertex 1.53414 1.22678 2.54627 + vertex 1.5328 1.22859 2.5467 + vertex 1.53159 1.22474 2.54639 + endloop + endfacet + facet normal 0.241743 -0.245802 0.938691 + outer loop + vertex 1.53414 1.22678 2.54627 + vertex 1.53159 1.22474 2.54639 + vertex 1.53308 1.22284 2.54551 + endloop + endfacet + facet normal -0.179519 -0.0220306 0.983508 + outer loop + vertex 1.53159 1.22474 2.54639 + vertex 1.5328 1.22859 2.5467 + vertex 1.52939 1.22468 2.54599 + endloop + endfacet + facet normal -0.174024 -0.152168 0.972914 + outer loop + vertex 1.53159 1.22474 2.54639 + vertex 1.52939 1.22468 2.54599 + vertex 1.5299 1.22212 2.54568 + endloop + endfacet + facet normal 0.125634 -0.334955 0.933821 + outer loop + vertex 1.53308 1.22284 2.54551 + vertex 1.53159 1.22474 2.54639 + vertex 1.5299 1.22212 2.54568 + endloop + endfacet + facet normal -0.496243 -0.199805 0.844879 + outer loop + vertex 1.5299 1.22212 2.54568 + vertex 1.52939 1.22468 2.54599 + vertex 1.52795 1.22171 2.54444 + endloop + endfacet + facet normal -0.133478 -0.063069 0.989043 + outer loop + vertex 1.5328 1.22859 2.5467 + vertex 1.52925 1.2286 2.54622 + vertex 1.52939 1.22468 2.54599 + endloop + endfacet + facet normal -0.133144 -0.101479 0.985888 + outer loop + vertex 1.5328 1.22859 2.5467 + vertex 1.53292 1.23308 2.54718 + vertex 1.52925 1.2286 2.54622 + endloop + endfacet + facet normal -0.125886 -0.10749 0.986204 + outer loop + vertex 1.52925 1.2286 2.54622 + vertex 1.53292 1.23308 2.54718 + vertex 1.52901 1.23324 2.5467 + endloop + endfacet + facet normal -0.126452 -0.129571 0.983474 + outer loop + vertex 1.53292 1.23308 2.54718 + vertex 1.53276 1.23774 2.54777 + vertex 1.52901 1.23324 2.5467 + endloop + endfacet + facet normal -0.143934 -0.114871 0.982898 + outer loop + vertex 1.52901 1.23324 2.5467 + vertex 1.53276 1.23774 2.54777 + vertex 1.52863 1.23814 2.54721 + endloop + endfacet + facet normal -0.14431 -0.119701 0.982266 + outer loop + vertex 1.53276 1.23774 2.54777 + vertex 1.53252 1.2427 2.54834 + vertex 1.52863 1.23814 2.54721 + endloop + endfacet + facet normal -0.14624 -0.118034 0.982182 + outer loop + vertex 1.52863 1.23814 2.54721 + vertex 1.53252 1.2427 2.54834 + vertex 1.52827 1.24316 2.54776 + endloop + endfacet + facet normal -0.145966 -0.115011 0.982582 + outer loop + vertex 1.53252 1.2427 2.54834 + vertex 1.53234 1.24786 2.54892 + vertex 1.52827 1.24316 2.54776 + endloop + endfacet + facet normal -0.131307 -0.127808 0.983068 + outer loop + vertex 1.52827 1.24316 2.54776 + vertex 1.53234 1.24786 2.54892 + vertex 1.52763 1.24843 2.54836 + endloop + endfacet + facet normal -0.131885 -0.133363 0.982253 + outer loop + vertex 1.53234 1.24786 2.54892 + vertex 1.53257 1.25311 2.54966 + vertex 1.52763 1.24843 2.54836 + endloop + endfacet + facet normal 0.01554 -0.282426 0.959163 + outer loop + vertex 1.52763 1.24843 2.54836 + vertex 1.53257 1.25311 2.54966 + vertex 1.52865 1.25391 2.54996 + endloop + endfacet + facet normal 0.0384237 -0.17862 0.983168 + outer loop + vertex 1.53303 1.25815 2.55056 + vertex 1.52865 1.25391 2.54996 + vertex 1.53257 1.25311 2.54966 + endloop + endfacet + facet normal 0.160013 -0.187214 0.969199 + outer loop + vertex 1.53257 1.25311 2.54966 + vertex 1.53762 1.25806 2.54978 + vertex 1.53303 1.25815 2.55056 + endloop + endfacet + facet normal 0.162857 -0.125188 0.978676 + outer loop + vertex 1.53796 1.26317 2.55038 + vertex 1.53303 1.25815 2.55056 + vertex 1.53762 1.25806 2.54978 + endloop + endfacet + facet normal 0.178062 -0.125883 0.975934 + outer loop + vertex 1.53762 1.25806 2.54978 + vertex 1.54267 1.26313 2.54952 + vertex 1.53796 1.26317 2.55038 + endloop + endfacet + facet normal 0.178316 -0.117135 0.976976 + outer loop + vertex 1.54295 1.26857 2.55012 + vertex 1.53796 1.26317 2.55038 + vertex 1.54267 1.26313 2.54952 + endloop + endfacet + facet normal 0.173436 -0.116987 0.977872 + outer loop + vertex 1.54267 1.26313 2.54952 + vertex 1.54762 1.26809 2.54923 + vertex 1.54295 1.26857 2.55012 + endloop + endfacet + facet normal 0.172441 -0.125188 0.977032 + outer loop + vertex 1.54762 1.26809 2.54923 + vertex 1.54811 1.27331 2.54981 + vertex 1.54295 1.26857 2.55012 + endloop + endfacet + facet normal 0.170768 -0.123333 0.977562 + outer loop + vertex 1.54295 1.26857 2.55012 + vertex 1.54811 1.27331 2.54981 + vertex 1.54458 1.27385 2.5505 + endloop + endfacet + facet normal 0.187053 -0.128094 0.973963 + outer loop + vertex 1.54295 1.26857 2.55012 + vertex 1.54458 1.27385 2.5505 + vertex 1.54055 1.27095 2.55089 + endloop + endfacet + facet normal 0.184658 -0.130546 0.974094 + outer loop + vertex 1.53889 1.26719 2.5507 + vertex 1.54295 1.26857 2.55012 + vertex 1.54055 1.27095 2.55089 + endloop + endfacet + facet normal 0.221116 -0.14613 0.964237 + outer loop + vertex 1.54055 1.27095 2.55089 + vertex 1.53641 1.26795 2.55138 + vertex 1.53889 1.26719 2.5507 + endloop + endfacet + facet normal 0.221591 -0.144678 0.964347 + outer loop + vertex 1.53889 1.26719 2.5507 + vertex 1.53641 1.26795 2.55138 + vertex 1.53606 1.26482 2.551 + endloop + endfacet + facet normal 0.205937 -0.125193 0.970524 + outer loop + vertex 1.53889 1.26719 2.5507 + vertex 1.53606 1.26482 2.551 + vertex 1.53796 1.26317 2.55038 + endloop + endfacet + facet normal 0.203029 -0.128601 0.970691 + outer loop + vertex 1.53796 1.26317 2.55038 + vertex 1.53606 1.26482 2.551 + vertex 1.5342 1.26193 2.551 + endloop + endfacet + facet normal 0.217069 -0.137666 0.9664 + outer loop + vertex 1.53606 1.26482 2.551 + vertex 1.53242 1.26356 2.55163 + vertex 1.5342 1.26193 2.551 + endloop + endfacet + facet normal 0.203814 -0.152418 0.967072 + outer loop + vertex 1.5342 1.26193 2.551 + vertex 1.53242 1.26356 2.55163 + vertex 1.53143 1.26 2.55128 + endloop + endfacet + facet normal 0.223183 -0.181528 0.957725 + outer loop + vertex 1.5342 1.26193 2.551 + vertex 1.53143 1.26 2.55128 + vertex 1.53303 1.25815 2.55056 + endloop + endfacet + facet normal 0.166953 -0.230368 0.958675 + outer loop + vertex 1.53303 1.25815 2.55056 + vertex 1.53143 1.26 2.55128 + vertex 1.5294 1.25733 2.55099 + endloop + endfacet + facet normal 0.114949 -0.192641 0.974513 + outer loop + vertex 1.53143 1.26 2.55128 + vertex 1.52861 1.25963 2.55154 + vertex 1.5294 1.25733 2.55099 + endloop + endfacet + facet normal -0.0572173 -0.250157 0.966513 + outer loop + vertex 1.5294 1.25733 2.55099 + vertex 1.52861 1.25963 2.55154 + vertex 1.52638 1.25595 2.55046 + endloop + endfacet + facet normal -0.0418967 -0.280691 0.958883 + outer loop + vertex 1.5294 1.25733 2.55099 + vertex 1.52638 1.25595 2.55046 + vertex 1.52865 1.25391 2.54996 + endloop + endfacet + facet normal 0.107354 -0.127408 0.986023 + outer loop + vertex 1.53143 1.26 2.55128 + vertex 1.53242 1.26356 2.55163 + vertex 1.52861 1.25963 2.55154 + endloop + endfacet + facet normal 0.139621 -0.158494 0.977438 + outer loop + vertex 1.53242 1.26356 2.55163 + vertex 1.52824 1.26325 2.55218 + vertex 1.52861 1.25963 2.55154 + endloop + endfacet + facet normal 0.139414 -0.154493 0.978108 + outer loop + vertex 1.53242 1.26356 2.55163 + vertex 1.53241 1.26789 2.55232 + vertex 1.52824 1.26325 2.55218 + endloop + endfacet + facet normal 0.127327 -0.143703 0.981396 + outer loop + vertex 1.52824 1.26325 2.55218 + vertex 1.53241 1.26789 2.55232 + vertex 1.52794 1.26765 2.55287 + endloop + endfacet + facet normal 0.127182 -0.139515 0.982018 + outer loop + vertex 1.53241 1.26789 2.55232 + vertex 1.53246 1.27262 2.55299 + vertex 1.52794 1.26765 2.55287 + endloop + endfacet + facet normal 0.11063 -0.124558 0.986026 + outer loop + vertex 1.52794 1.26765 2.55287 + vertex 1.53246 1.27262 2.55299 + vertex 1.52775 1.27246 2.55349 + endloop + endfacet + facet normal -0.185223 -0.134766 0.973412 + outer loop + vertex 1.52794 1.26765 2.55287 + vertex 1.52775 1.27246 2.55349 + vertex 1.52416 1.26815 2.55221 + endloop + endfacet + facet normal -0.230351 -0.0956102 0.968399 + outer loop + vertex 1.52416 1.26815 2.55221 + vertex 1.52775 1.27246 2.55349 + vertex 1.52397 1.27314 2.55266 + endloop + endfacet + facet normal -0.231078 -0.100412 0.96774 + outer loop + vertex 1.52775 1.27246 2.55349 + vertex 1.52768 1.2775 2.554 + vertex 1.52397 1.27314 2.55266 + endloop + endfacet + facet normal -0.251174 -0.0823071 0.964436 + outer loop + vertex 1.52397 1.27314 2.55266 + vertex 1.52768 1.2775 2.554 + vertex 1.52393 1.2783 2.55309 + endloop + endfacet + facet normal -0.255378 -0.106087 0.961003 + outer loop + vertex 1.52768 1.2775 2.554 + vertex 1.52772 1.28271 2.55459 + vertex 1.52393 1.2783 2.55309 + endloop + endfacet + facet normal -0.185702 -0.168223 0.968099 + outer loop + vertex 1.52393 1.2783 2.55309 + vertex 1.52772 1.28271 2.55459 + vertex 1.52381 1.2836 2.55399 + endloop + endfacet + facet normal -0.187467 -0.177337 0.96613 + outer loop + vertex 1.52776 1.28785 2.55554 + vertex 1.52381 1.2836 2.55399 + vertex 1.52772 1.28271 2.55459 + endloop + endfacet + facet normal 0.171322 -0.180854 0.968473 + outer loop + vertex 1.52772 1.28271 2.55459 + vertex 1.53238 1.28789 2.55473 + vertex 1.52776 1.28785 2.55554 + endloop + endfacet + facet normal 0.172433 -0.117661 0.977969 + outer loop + vertex 1.53252 1.29343 2.55537 + vertex 1.52776 1.28785 2.55554 + vertex 1.53238 1.28789 2.55473 + endloop + endfacet + facet normal 0.211661 -0.117765 0.970222 + outer loop + vertex 1.53238 1.28789 2.55473 + vertex 1.53745 1.29311 2.55425 + vertex 1.53252 1.29343 2.55537 + endloop + endfacet + facet normal 0.212696 -0.105689 0.971386 + outer loop + vertex 1.53745 1.29311 2.55425 + vertex 1.53788 1.2984 2.55474 + vertex 1.53252 1.29343 2.55537 + endloop + endfacet + facet normal 0.206458 -0.0986981 0.973465 + outer loop + vertex 1.53252 1.29343 2.55537 + vertex 1.53788 1.2984 2.55474 + vertex 1.53419 1.29893 2.55557 + endloop + endfacet + facet normal 0.228331 -0.105127 0.967891 + outer loop + vertex 1.53252 1.29343 2.55537 + vertex 1.53419 1.29893 2.55557 + vertex 1.5302 1.29579 2.55617 + endloop + endfacet + facet normal 0.232684 -0.100646 0.967331 + outer loop + vertex 1.5285 1.29184 2.55617 + vertex 1.53252 1.29343 2.55537 + vertex 1.5302 1.29579 2.55617 + endloop + endfacet + facet normal 0.133441 -0.0581908 0.989347 + outer loop + vertex 1.5302 1.29579 2.55617 + vertex 1.52665 1.29283 2.55648 + vertex 1.5285 1.29184 2.55617 + endloop + endfacet + facet normal 0.122229 -0.0790418 0.98935 + outer loop + vertex 1.5285 1.29184 2.55617 + vertex 1.52665 1.29283 2.55648 + vertex 1.52613 1.2896 2.55628 + endloop + endfacet + facet normal 0.22926 -0.194024 0.953832 + outer loop + vertex 1.5285 1.29184 2.55617 + vertex 1.52613 1.2896 2.55628 + vertex 1.52776 1.28785 2.55554 + endloop + endfacet + facet normal 0.116367 -0.296576 0.947893 + outer loop + vertex 1.52776 1.28785 2.55554 + vertex 1.52613 1.2896 2.55628 + vertex 1.52465 1.28706 2.55567 + endloop + endfacet + facet normal -0.187807 -0.12529 0.974182 + outer loop + vertex 1.52613 1.2896 2.55628 + vertex 1.52404 1.2895 2.55587 + vertex 1.52465 1.28706 2.55567 + endloop + endfacet + facet normal -0.468286 -0.18674 0.863618 + outer loop + vertex 1.52465 1.28706 2.55567 + vertex 1.52404 1.2895 2.55587 + vertex 1.5227 1.28659 2.55451 + endloop + endfacet + facet normal -0.43033 -0.307438 0.848704 + outer loop + vertex 1.52465 1.28706 2.55567 + vertex 1.5227 1.28659 2.55451 + vertex 1.52381 1.2836 2.55399 + endloop + endfacet + facet normal -0.193384 -0.0281403 0.98072 + outer loop + vertex 1.52613 1.2896 2.55628 + vertex 1.52665 1.29283 2.55648 + vertex 1.52404 1.2895 2.55587 + endloop + endfacet + facet normal -0.182551 -0.0369539 0.982502 + outer loop + vertex 1.52665 1.29283 2.55648 + vertex 1.52399 1.29348 2.55601 + vertex 1.52404 1.2895 2.55587 + endloop + endfacet + facet normal -0.17179 0.00903248 0.985092 + outer loop + vertex 1.52665 1.29283 2.55648 + vertex 1.528 1.29791 2.55667 + vertex 1.52399 1.29348 2.55601 + endloop + endfacet + facet normal -0.0451554 -0.106762 0.993259 + outer loop + vertex 1.52399 1.29348 2.55601 + vertex 1.528 1.29791 2.55667 + vertex 1.52397 1.29822 2.55652 + endloop + endfacet + facet normal -0.0450972 -0.105978 0.993345 + outer loop + vertex 1.528 1.29791 2.55667 + vertex 1.52776 1.30292 2.55719 + vertex 1.52397 1.29822 2.55652 + endloop + endfacet + facet normal -0.0453184 -0.105801 0.993354 + outer loop + vertex 1.52397 1.29822 2.55652 + vertex 1.52776 1.30292 2.55719 + vertex 1.52337 1.30307 2.55701 + endloop + endfacet + facet normal -0.0455768 -0.114956 0.992324 + outer loop + vertex 1.52776 1.30292 2.55719 + vertex 1.52739 1.30795 2.55776 + vertex 1.52337 1.30307 2.55701 + endloop + endfacet + facet normal -0.0579376 -0.104862 0.992798 + outer loop + vertex 1.52337 1.30307 2.55701 + vertex 1.52739 1.30795 2.55776 + vertex 1.52246 1.30859 2.55753 + endloop + endfacet + facet normal 0.122641 -0.101942 0.987202 + outer loop + vertex 1.52776 1.30292 2.55719 + vertex 1.53234 1.308 2.55715 + vertex 1.52739 1.30795 2.55776 + endloop + endfacet + facet normal 0.122618 -0.112907 0.986011 + outer loop + vertex 1.53234 1.308 2.55715 + vertex 1.53239 1.31292 2.5577 + vertex 1.52739 1.30795 2.55776 + endloop + endfacet + facet normal 0.123581 -0.113878 0.985779 + outer loop + vertex 1.52739 1.30795 2.55776 + vertex 1.53239 1.31292 2.5577 + vertex 1.52733 1.31308 2.55836 + endloop + endfacet + facet normal -0.0594094 -0.116755 0.991382 + outer loop + vertex 1.52739 1.30795 2.55776 + vertex 1.52733 1.31308 2.55836 + vertex 1.52246 1.30859 2.55753 + endloop + endfacet + facet normal 0.00352322 -0.183457 0.983021 + outer loop + vertex 1.52246 1.30859 2.55753 + vertex 1.52733 1.31308 2.55836 + vertex 1.52357 1.31383 2.55851 + endloop + endfacet + facet normal 0.0185076 -0.111432 0.9936 + outer loop + vertex 1.52733 1.31308 2.55836 + vertex 1.52738 1.31792 2.5589 + vertex 1.52357 1.31383 2.55851 + endloop + endfacet + facet normal -0.00654509 -0.0883193 0.996071 + outer loop + vertex 1.52357 1.31383 2.55851 + vertex 1.52738 1.31792 2.5589 + vertex 1.52303 1.31779 2.55886 + endloop + endfacet + facet normal -0.0061487 -0.10132 0.994835 + outer loop + vertex 1.52738 1.31792 2.5589 + vertex 1.52735 1.3227 2.55938 + vertex 1.52303 1.31779 2.55886 + endloop + endfacet + facet normal 0.036186 -0.138116 0.989755 + outer loop + vertex 1.52303 1.31779 2.55886 + vertex 1.52735 1.3227 2.55938 + vertex 1.52301 1.32266 2.55954 + endloop + endfacet + facet normal 0.0360874 -0.111507 0.993108 + outer loop + vertex 1.52735 1.3227 2.55938 + vertex 1.52753 1.32775 2.55995 + vertex 1.52301 1.32266 2.55954 + endloop + endfacet + facet normal 0.163763 -0.222414 0.9611 + outer loop + vertex 1.52301 1.32266 2.55954 + vertex 1.52753 1.32775 2.55995 + vertex 1.52319 1.32756 2.56064 + endloop + endfacet + facet normal 0.162092 -0.117997 0.979695 + outer loop + vertex 1.52769 1.333 2.56055 + vertex 1.52319 1.32756 2.56064 + vertex 1.52753 1.32775 2.55995 + endloop + endfacet + facet normal 0.204072 -0.118353 0.971775 + outer loop + vertex 1.52753 1.32775 2.55995 + vertex 1.53249 1.33306 2.55955 + vertex 1.52769 1.333 2.56055 + endloop + endfacet + facet normal 0.204398 -0.0788431 0.975708 + outer loop + vertex 1.53251 1.33872 2.56 + vertex 1.52769 1.333 2.56055 + vertex 1.53249 1.33306 2.55955 + endloop + endfacet + facet normal 0.184285 -0.0791092 0.979684 + outer loop + vertex 1.53249 1.33306 2.55955 + vertex 1.53752 1.33806 2.55901 + vertex 1.53251 1.33872 2.56 + endloop + endfacet + facet normal 0.183921 -0.0816726 0.979542 + outer loop + vertex 1.53752 1.33806 2.55901 + vertex 1.53781 1.34336 2.55939 + vertex 1.53251 1.33872 2.56 + endloop + endfacet + facet normal 0.182842 -0.0803999 0.979849 + outer loop + vertex 1.53251 1.33872 2.56 + vertex 1.53781 1.34336 2.55939 + vertex 1.53391 1.3445 2.56022 + endloop + endfacet + facet normal 0.212558 -0.0873473 0.973237 + outer loop + vertex 1.53251 1.33872 2.56 + vertex 1.53391 1.3445 2.56022 + vertex 1.52968 1.34117 2.56084 + endloop + endfacet + facet normal 0.214259 -0.0853158 0.973044 + outer loop + vertex 1.52837 1.33723 2.56079 + vertex 1.53251 1.33872 2.56 + vertex 1.52968 1.34117 2.56084 + endloop + endfacet + facet normal 0.247971 -0.0964479 0.963954 + outer loop + vertex 1.52968 1.34117 2.56084 + vertex 1.52593 1.33774 2.56146 + vertex 1.52837 1.33723 2.56079 + endloop + endfacet + facet normal 0.2502 -0.0862019 0.964349 + outer loop + vertex 1.52837 1.33723 2.56079 + vertex 1.52593 1.33774 2.56146 + vertex 1.52578 1.33464 2.56123 + endloop + endfacet + facet normal 0.258045 -0.0945097 0.961499 + outer loop + vertex 1.52837 1.33723 2.56079 + vertex 1.52578 1.33464 2.56123 + vertex 1.52769 1.333 2.56055 + endloop + endfacet + facet normal 0.249805 -0.104592 0.962631 + outer loop + vertex 1.52769 1.333 2.56055 + vertex 1.52578 1.33464 2.56123 + vertex 1.52415 1.3315 2.56131 + endloop + endfacet + facet normal 0.178464 -0.0670679 0.981658 + outer loop + vertex 1.52578 1.33464 2.56123 + vertex 1.52268 1.33316 2.56169 + vertex 1.52415 1.3315 2.56131 + endloop + endfacet + facet normal 0.152271 -0.090718 0.984167 + outer loop + vertex 1.52415 1.3315 2.56131 + vertex 1.52268 1.33316 2.56169 + vertex 1.52179 1.32934 2.56147 + endloop + endfacet + facet normal 0.271768 -0.224416 0.935831 + outer loop + vertex 1.52415 1.3315 2.56131 + vertex 1.52179 1.32934 2.56147 + vertex 1.52319 1.32756 2.56064 + endloop + endfacet + facet normal 0.147925 -0.32132 0.935346 + outer loop + vertex 1.52319 1.32756 2.56064 + vertex 1.52179 1.32934 2.56147 + vertex 1.52021 1.32666 2.5608 + endloop + endfacet + facet normal -0.184428 -0.133458 0.973743 + outer loop + vertex 1.52179 1.32934 2.56147 + vertex 1.51974 1.32921 2.56106 + vertex 1.52021 1.32666 2.5608 + endloop + endfacet + facet normal -0.19363 -0.0102868 0.981021 + outer loop + vertex 1.52179 1.32934 2.56147 + vertex 1.52268 1.33316 2.56169 + vertex 1.51974 1.32921 2.56106 + endloop + endfacet + facet normal -0.163869 -0.0332011 0.985923 + outer loop + vertex 1.52268 1.33316 2.56169 + vertex 1.51961 1.33328 2.56118 + vertex 1.51974 1.32921 2.56106 + endloop + endfacet + facet normal -0.164973 -0.067916 0.983957 + outer loop + vertex 1.52268 1.33316 2.56169 + vertex 1.52267 1.3376 2.56199 + vertex 1.51961 1.33328 2.56118 + endloop + endfacet + facet normal -0.148316 -0.0800797 0.985692 + outer loop + vertex 1.51961 1.33328 2.56118 + vertex 1.52267 1.3376 2.56199 + vertex 1.51948 1.33806 2.56155 + endloop + endfacet + facet normal -0.146483 -0.066304 0.986989 + outer loop + vertex 1.52267 1.3376 2.56199 + vertex 1.52288 1.34244 2.56235 + vertex 1.51948 1.33806 2.56155 + endloop + endfacet + facet normal -0.141292 -0.0704245 0.98746 + outer loop + vertex 1.51948 1.33806 2.56155 + vertex 1.52288 1.34244 2.56235 + vertex 1.51938 1.34304 2.56189 + endloop + endfacet + facet normal -0.143002 -0.0812106 0.986385 + outer loop + vertex 1.52288 1.34244 2.56235 + vertex 1.52297 1.3475 2.56278 + vertex 1.51938 1.34304 2.56189 + endloop + endfacet + facet normal -0.156204 -0.0703312 0.985218 + outer loop + vertex 1.51938 1.34304 2.56189 + vertex 1.52297 1.3475 2.56278 + vertex 1.51923 1.34804 2.56222 + endloop + endfacet + facet normal -0.158478 -0.0878344 0.983448 + outer loop + vertex 1.52297 1.3475 2.56278 + vertex 1.52287 1.35249 2.56321 + vertex 1.51923 1.34804 2.56222 + endloop + endfacet + facet normal -0.195433 -0.0566901 0.979077 + outer loop + vertex 1.51923 1.34804 2.56222 + vertex 1.52287 1.35249 2.56321 + vertex 1.51911 1.35303 2.56249 + endloop + endfacet + facet normal -0.198103 -0.0779239 0.977079 + outer loop + vertex 1.52287 1.35249 2.56321 + vertex 1.5228 1.35743 2.56359 + vertex 1.51911 1.35303 2.56249 + endloop + endfacet + facet normal -0.232684 -0.0475282 0.97139 + outer loop + vertex 1.51911 1.35303 2.56249 + vertex 1.5228 1.35743 2.56359 + vertex 1.51901 1.35801 2.56271 + endloop + endfacet + facet normal -0.234898 -0.0642181 0.969896 + outer loop + vertex 1.5228 1.35743 2.56359 + vertex 1.52275 1.36237 2.5639 + vertex 1.51901 1.35801 2.56271 + endloop + endfacet + facet normal -0.258187 -0.0429901 0.965138 + outer loop + vertex 1.51901 1.35801 2.56271 + vertex 1.52275 1.36237 2.5639 + vertex 1.51894 1.36301 2.56291 + endloop + endfacet + facet normal -0.261289 -0.0646633 0.963092 + outer loop + vertex 1.52275 1.36237 2.5639 + vertex 1.52269 1.36737 2.56422 + vertex 1.51894 1.36301 2.56291 + endloop + endfacet + facet normal -0.262342 -0.0636902 0.962871 + outer loop + vertex 1.51894 1.36301 2.56291 + vertex 1.52269 1.36737 2.56422 + vertex 1.51889 1.36811 2.56323 + endloop + endfacet + facet normal -0.265323 -0.0818804 0.960676 + outer loop + vertex 1.52269 1.36737 2.56422 + vertex 1.52266 1.37256 2.56465 + vertex 1.51889 1.36811 2.56323 + endloop + endfacet + facet normal -0.178587 -0.15886 0.971015 + outer loop + vertex 1.51889 1.36811 2.56323 + vertex 1.52266 1.37256 2.56465 + vertex 1.51869 1.37343 2.56407 + endloop + endfacet + facet normal -0.174767 -0.138939 0.974758 + outer loop + vertex 1.52261 1.37804 2.56543 + vertex 1.51869 1.37343 2.56407 + vertex 1.52266 1.37256 2.56465 + endloop + endfacet + facet normal 0.163079 -0.136454 0.977131 + outer loop + vertex 1.52266 1.37256 2.56465 + vertex 1.52739 1.37766 2.56458 + vertex 1.52261 1.37804 2.56543 + endloop + endfacet + facet normal 0.169644 -0.0679208 0.983162 + outer loop + vertex 1.52739 1.37766 2.56458 + vertex 1.52759 1.38302 2.56491 + vertex 1.52261 1.37804 2.56543 + endloop + endfacet + facet normal 0.226531 -0.126515 0.965752 + outer loop + vertex 1.52261 1.37804 2.56543 + vertex 1.52759 1.38302 2.56491 + vertex 1.52376 1.38352 2.56588 + endloop + endfacet + facet normal 0.208208 -0.123065 0.970311 + outer loop + vertex 1.52261 1.37804 2.56543 + vertex 1.52376 1.38352 2.56588 + vertex 1.52052 1.38057 2.5662 + endloop + endfacet + facet normal 0.1304 -0.188453 0.973387 + outer loop + vertex 1.51924 1.37703 2.56569 + vertex 1.52261 1.37804 2.56543 + vertex 1.52052 1.38057 2.5662 + endloop + endfacet + facet normal -0.150345 -0.0889728 0.984622 + outer loop + vertex 1.52052 1.38057 2.5662 + vertex 1.51829 1.37888 2.56571 + vertex 1.51924 1.37703 2.56569 + endloop + endfacet + facet normal -0.4452 -0.238106 0.863193 + outer loop + vertex 1.51924 1.37703 2.56569 + vertex 1.51829 1.37888 2.56571 + vertex 1.51747 1.37629 2.56457 + endloop + endfacet + facet normal -0.405185 -0.322378 0.85551 + outer loop + vertex 1.51924 1.37703 2.56569 + vertex 1.51747 1.37629 2.56457 + vertex 1.51869 1.37343 2.56407 + endloop + endfacet + facet normal -0.198748 -0.0239204 0.979759 + outer loop + vertex 1.5189 1.38308 2.56593 + vertex 1.51829 1.37888 2.56571 + vertex 1.52052 1.38057 2.5662 + endloop + endfacet + facet normal -0.163995 -0.000852665 0.986461 + outer loop + vertex 1.52151 1.38425 2.56637 + vertex 1.5189 1.38308 2.56593 + vertex 1.52052 1.38057 2.5662 + endloop + endfacet + facet normal -0.153493 -0.0246436 0.987842 + outer loop + vertex 1.52151 1.38425 2.56637 + vertex 1.52146 1.38747 2.56644 + vertex 1.5189 1.38308 2.56593 + endloop + endfacet + facet normal -0.171589 -0.0137951 0.985072 + outer loop + vertex 1.52146 1.38747 2.56644 + vertex 1.51884 1.38812 2.56599 + vertex 1.5189 1.38308 2.56593 + endloop + endfacet + facet normal -0.169109 -0.00345679 0.985591 + outer loop + vertex 1.52146 1.38747 2.56644 + vertex 1.52193 1.39201 2.56654 + vertex 1.51884 1.38812 2.56599 + endloop + endfacet + facet normal 0.147445 -0.0364348 0.988399 + outer loop + vertex 1.52193 1.39201 2.56654 + vertex 1.52146 1.38747 2.56644 + vertex 1.52474 1.39082 2.56608 + endloop + endfacet + facet normal 0.137072 -0.026084 0.990218 + outer loop + vertex 1.52474 1.39082 2.56608 + vertex 1.52146 1.38747 2.56644 + vertex 1.52369 1.38696 2.56612 + endloop + endfacet + facet normal 0.235071 -0.0528712 0.970539 + outer loop + vertex 1.52369 1.38696 2.56612 + vertex 1.52757 1.38854 2.56527 + vertex 1.52474 1.39082 2.56608 + endloop + endfacet + facet normal 0.229611 -0.0599611 0.971434 + outer loop + vertex 1.52757 1.38854 2.56527 + vertex 1.52874 1.39422 2.56534 + vertex 1.52474 1.39082 2.56608 + endloop + endfacet + facet normal 0.233998 -0.0654323 0.970033 + outer loop + vertex 1.52474 1.39082 2.56608 + vertex 1.52874 1.39422 2.56534 + vertex 1.52561 1.39549 2.56618 + endloop + endfacet + facet normal 0.142303 -0.0486988 0.988624 + outer loop + vertex 1.52561 1.39549 2.56618 + vertex 1.52193 1.39201 2.56654 + vertex 1.52474 1.39082 2.56608 + endloop + endfacet + facet normal 0.146787 -0.0535333 0.987718 + outer loop + vertex 1.52281 1.39751 2.56671 + vertex 1.52193 1.39201 2.56654 + vertex 1.52561 1.39549 2.56618 + endloop + endfacet + facet normal 0.143865 -0.0576435 0.987917 + outer loop + vertex 1.52656 1.39931 2.56627 + vertex 1.52281 1.39751 2.56671 + vertex 1.52561 1.39549 2.56618 + endloop + endfacet + facet normal 0.235637 -0.0799303 0.968549 + outer loop + vertex 1.52926 1.39886 2.56557 + vertex 1.52656 1.39931 2.56627 + vertex 1.52561 1.39549 2.56618 + endloop + endfacet + facet normal 0.235347 -0.0815635 0.968483 + outer loop + vertex 1.52896 1.40206 2.56591 + vertex 1.52656 1.39931 2.56627 + vertex 1.52926 1.39886 2.56557 + endloop + endfacet + facet normal 0.231829 -0.0819747 0.969296 + outer loop + vertex 1.52896 1.40206 2.56591 + vertex 1.52926 1.39886 2.56557 + vertex 1.53285 1.40357 2.56511 + endloop + endfacet + facet normal 0.228594 -0.0728399 0.970793 + outer loop + vertex 1.52896 1.40206 2.56591 + vertex 1.53285 1.40357 2.56511 + vertex 1.52988 1.40584 2.56598 + endloop + endfacet + facet normal 0.222344 -0.07136 0.972353 + outer loop + vertex 1.52988 1.40584 2.56598 + vertex 1.52619 1.4024 2.56657 + vertex 1.52896 1.40206 2.56591 + endloop + endfacet + facet normal 0.211638 -0.0593255 0.975546 + outer loop + vertex 1.52649 1.40696 2.56678 + vertex 1.52619 1.4024 2.56657 + vertex 1.52988 1.40584 2.56598 + endloop + endfacet + facet normal 0.211286 -0.0603938 0.975557 + outer loop + vertex 1.53068 1.41057 2.5661 + vertex 1.52649 1.40696 2.56678 + vertex 1.52988 1.40584 2.56598 + endloop + endfacet + facet normal 0.223295 -0.0623581 0.972754 + outer loop + vertex 1.52988 1.40584 2.56598 + vertex 1.53389 1.40918 2.56527 + vertex 1.53068 1.41057 2.5661 + endloop + endfacet + facet normal 0.224162 -0.0603079 0.972684 + outer loop + vertex 1.53389 1.40918 2.56527 + vertex 1.53436 1.41391 2.56546 + vertex 1.53068 1.41057 2.5661 + endloop + endfacet + facet normal 0.219699 -0.0551408 0.974008 + outer loop + vertex 1.53436 1.41391 2.56546 + vertex 1.53164 1.41451 2.56611 + vertex 1.53068 1.41057 2.5661 + endloop + endfacet + facet normal 0.210952 -0.0529974 0.976059 + outer loop + vertex 1.53164 1.41451 2.56611 + vertex 1.52746 1.41263 2.56691 + vertex 1.53068 1.41057 2.5661 + endloop + endfacet + facet normal 0.213523 -0.059127 0.975147 + outer loop + vertex 1.53164 1.41451 2.56611 + vertex 1.53123 1.41771 2.56639 + vertex 1.52746 1.41263 2.56691 + endloop + endfacet + facet normal 0.212956 -0.0586906 0.975298 + outer loop + vertex 1.53123 1.41771 2.56639 + vertex 1.52711 1.41775 2.56729 + vertex 1.52746 1.41263 2.56691 + endloop + endfacet + facet normal 0.151194 -0.06366 0.986452 + outer loop + vertex 1.52746 1.41263 2.56691 + vertex 1.52711 1.41775 2.56729 + vertex 1.52245 1.41289 2.56769 + endloop + endfacet + facet normal 0.150445 -0.0758982 0.985701 + outer loop + vertex 1.5223 1.40768 2.56731 + vertex 1.52746 1.41263 2.56691 + vertex 1.52245 1.41289 2.56769 + endloop + endfacet + facet normal -0.0712822 -0.0699407 0.995001 + outer loop + vertex 1.5223 1.40768 2.56731 + vertex 1.52245 1.41289 2.56769 + vertex 1.51759 1.40861 2.56704 + endloop + endfacet + facet normal -0.0747061 -0.0876275 0.993348 + outer loop + vertex 1.5183 1.40324 2.56662 + vertex 1.5223 1.40768 2.56731 + vertex 1.51759 1.40861 2.56704 + endloop + endfacet + facet normal -0.108562 -0.056932 0.992458 + outer loop + vertex 1.52236 1.40254 2.56703 + vertex 1.5223 1.40768 2.56731 + vertex 1.5183 1.40324 2.56662 + endloop + endfacet + facet normal -0.110382 -0.0680372 0.991558 + outer loop + vertex 1.51877 1.39823 2.56633 + vertex 1.52236 1.40254 2.56703 + vertex 1.5183 1.40324 2.56662 + endloop + endfacet + facet normal -0.105077 -0.0724935 0.991818 + outer loop + vertex 1.52281 1.39751 2.56671 + vertex 1.52236 1.40254 2.56703 + vertex 1.51877 1.39823 2.56633 + endloop + endfacet + facet normal -0.0993938 -0.0396448 0.994258 + outer loop + vertex 1.51893 1.39315 2.56614 + vertex 1.52281 1.39751 2.56671 + vertex 1.51877 1.39823 2.56633 + endloop + endfacet + facet normal 0.115784 -0.0528246 0.991869 + outer loop + vertex 1.52619 1.4024 2.56657 + vertex 1.52236 1.40254 2.56703 + vertex 1.52281 1.39751 2.56671 + endloop + endfacet + facet normal 0.116311 -0.0541541 0.991735 + outer loop + vertex 1.52236 1.40254 2.56703 + vertex 1.52649 1.40696 2.56678 + vertex 1.5223 1.40768 2.56731 + endloop + endfacet + facet normal 0.0179299 -0.169874 0.985303 + outer loop + vertex 1.51759 1.40861 2.56704 + vertex 1.52245 1.41289 2.56769 + vertex 1.51876 1.41362 2.56789 + endloop + endfacet + facet normal 0.0370876 -0.0758315 0.996431 + outer loop + vertex 1.52245 1.41289 2.56769 + vertex 1.5225 1.41776 2.56806 + vertex 1.51876 1.41362 2.56789 + endloop + endfacet + facet normal 0.0160833 -0.0568997 0.99825 + outer loop + vertex 1.51876 1.41362 2.56789 + vertex 1.5225 1.41776 2.56806 + vertex 1.51808 1.41753 2.56812 + endloop + endfacet + facet normal 0.0160136 -0.0555339 0.998328 + outer loop + vertex 1.5225 1.41776 2.56806 + vertex 1.52241 1.42255 2.56833 + vertex 1.51808 1.41753 2.56812 + endloop + endfacet + facet normal 0.0224912 -0.061097 0.997878 + outer loop + vertex 1.51808 1.41753 2.56812 + vertex 1.52241 1.42255 2.56833 + vertex 1.51786 1.42238 2.56842 + endloop + endfacet + facet normal 0.0221706 -0.0520869 0.998396 + outer loop + vertex 1.52241 1.42255 2.56833 + vertex 1.5224 1.42751 2.56859 + vertex 1.51786 1.42238 2.56842 + endloop + endfacet + facet normal 0.0426051 -0.0701356 0.996627 + outer loop + vertex 1.51786 1.42238 2.56842 + vertex 1.5224 1.42751 2.56859 + vertex 1.5178 1.42742 2.56878 + endloop + endfacet + facet normal 0.0423742 -0.0564467 0.997506 + outer loop + vertex 1.5224 1.42751 2.56859 + vertex 1.5224 1.43254 2.56887 + vertex 1.5178 1.42742 2.56878 + endloop + endfacet + facet normal 0.0854619 -0.0950536 0.991797 + outer loop + vertex 1.5178 1.42742 2.56878 + vertex 1.5224 1.43254 2.56887 + vertex 1.51769 1.43264 2.56929 + endloop + endfacet + facet normal 0.0864287 -0.0605759 0.994415 + outer loop + vertex 1.5224 1.43254 2.56887 + vertex 1.52236 1.43772 2.56919 + vertex 1.51769 1.43264 2.56929 + endloop + endfacet + facet normal 0.177845 -0.145162 0.973293 + outer loop + vertex 1.51769 1.43264 2.56929 + vertex 1.52236 1.43772 2.56919 + vertex 1.51728 1.43813 2.57018 + endloop + endfacet + facet normal 0.187131 -0.049911 0.981066 + outer loop + vertex 1.52236 1.43772 2.56919 + vertex 1.52246 1.44302 2.56944 + vertex 1.51728 1.43813 2.57018 + endloop + endfacet + facet normal 0.233212 -0.10089 0.967178 + outer loop + vertex 1.51728 1.43813 2.57018 + vertex 1.52246 1.44302 2.56944 + vertex 1.51819 1.44391 2.57057 + endloop + endfacet + facet normal 0.249852 -0.103198 0.962769 + outer loop + vertex 1.51728 1.43813 2.57018 + vertex 1.51819 1.44391 2.57057 + vertex 1.51471 1.44071 2.57113 + endloop + endfacet + facet normal 0.16115 -0.193604 0.967754 + outer loop + vertex 1.51388 1.4372 2.57056 + vertex 1.51728 1.43813 2.57018 + vertex 1.51471 1.44071 2.57113 + endloop + endfacet + facet normal -0.117732 -0.130986 0.984369 + outer loop + vertex 1.51471 1.44071 2.57113 + vertex 1.51286 1.43892 2.57067 + vertex 1.51388 1.4372 2.57056 + endloop + endfacet + facet normal -0.493769 -0.342992 0.799092 + outer loop + vertex 1.51388 1.4372 2.57056 + vertex 1.51286 1.43892 2.57067 + vertex 1.51257 1.43649 2.56944 + endloop + endfacet + facet normal -0.232935 -0.00970021 0.972444 + outer loop + vertex 1.51304 1.44247 2.57074 + vertex 1.51286 1.43892 2.57067 + vertex 1.51471 1.44071 2.57113 + endloop + endfacet + facet normal -0.222794 0.000469113 0.974865 + outer loop + vertex 1.51522 1.44542 2.57124 + vertex 1.51304 1.44247 2.57074 + vertex 1.51471 1.44071 2.57113 + endloop + endfacet + facet normal -0.208053 -0.0109523 0.978056 + outer loop + vertex 1.51331 1.44725 2.57086 + vertex 1.51304 1.44247 2.57074 + vertex 1.51522 1.44542 2.57124 + endloop + endfacet + facet normal -0.184822 0.0141513 0.98267 + outer loop + vertex 1.51559 1.45041 2.57124 + vertex 1.51331 1.44725 2.57086 + vertex 1.51522 1.44542 2.57124 + endloop + endfacet + facet normal 0.201273 -0.0149214 0.979422 + outer loop + vertex 1.51522 1.44542 2.57124 + vertex 1.51857 1.44908 2.57061 + vertex 1.51559 1.45041 2.57124 + endloop + endfacet + facet normal 0.201962 -0.0133233 0.979303 + outer loop + vertex 1.51857 1.44908 2.57061 + vertex 1.5188 1.45407 2.57063 + vertex 1.51559 1.45041 2.57124 + endloop + endfacet + facet normal 0.207033 -0.0179633 0.978169 + outer loop + vertex 1.51559 1.45041 2.57124 + vertex 1.5188 1.45407 2.57063 + vertex 1.51595 1.45531 2.57125 + endloop + endfacet + facet normal -0.175786 0.0103943 0.984374 + outer loop + vertex 1.51595 1.45531 2.57125 + vertex 1.51364 1.45236 2.57087 + vertex 1.51559 1.45041 2.57124 + endloop + endfacet + facet normal -0.149112 -0.0111045 0.988758 + outer loop + vertex 1.51415 1.45795 2.57101 + vertex 1.51364 1.45236 2.57087 + vertex 1.51595 1.45531 2.57125 + endloop + endfacet + facet normal -0.139485 -0.00438615 0.990214 + outer loop + vertex 1.51642 1.45915 2.57134 + vertex 1.51415 1.45795 2.57101 + vertex 1.51595 1.45531 2.57125 + endloop + endfacet + facet normal 0.226048 -0.0485295 0.972907 + outer loop + vertex 1.51885 1.45865 2.57075 + vertex 1.51642 1.45915 2.57134 + vertex 1.51595 1.45531 2.57125 + endloop + endfacet + facet normal 0.226827 -0.0447873 0.972905 + outer loop + vertex 1.51834 1.46185 2.57101 + vertex 1.51642 1.45915 2.57134 + vertex 1.51885 1.45865 2.57075 + endloop + endfacet + facet normal 0.254739 -0.0397915 0.966191 + outer loop + vertex 1.51834 1.46185 2.57101 + vertex 1.51885 1.45865 2.57075 + vertex 1.52232 1.4635 2.57003 + endloop + endfacet + facet normal 0.253748 -0.0371801 0.966556 + outer loop + vertex 1.51834 1.46185 2.57101 + vertex 1.52232 1.4635 2.57003 + vertex 1.51909 1.46568 2.57096 + endloop + endfacet + facet normal 0.18518 -0.0234395 0.982425 + outer loop + vertex 1.51909 1.46568 2.57096 + vertex 1.51615 1.46233 2.57144 + vertex 1.51834 1.46185 2.57101 + endloop + endfacet + facet normal 0.194689 -0.0320872 0.98034 + outer loop + vertex 1.5163 1.46674 2.57155 + vertex 1.51615 1.46233 2.57144 + vertex 1.51909 1.46568 2.57096 + endloop + endfacet + facet normal 0.194043 -0.0338342 0.980409 + outer loop + vertex 1.5195 1.47049 2.57105 + vertex 1.5163 1.46674 2.57155 + vertex 1.51909 1.46568 2.57096 + endloop + endfacet + facet normal 0.254837 -0.0387352 0.966208 + outer loop + vertex 1.51909 1.46568 2.57096 + vertex 1.52315 1.46921 2.57003 + vertex 1.5195 1.47049 2.57105 + endloop + endfacet + facet normal 0.256935 -0.0325031 0.965882 + outer loop + vertex 1.52315 1.46921 2.57003 + vertex 1.52345 1.47434 2.57013 + vertex 1.5195 1.47049 2.57105 + endloop + endfacet + facet normal 0.25583 -0.0312877 0.966215 + outer loop + vertex 1.5195 1.47049 2.57105 + vertex 1.52345 1.47434 2.57013 + vertex 1.51971 1.47546 2.57115 + endloop + endfacet + facet normal 0.191159 -0.0289481 0.981132 + outer loop + vertex 1.51971 1.47546 2.57115 + vertex 1.51647 1.47156 2.57167 + vertex 1.5195 1.47049 2.57105 + endloop + endfacet + facet normal 0.188535 -0.0266966 0.981704 + outer loop + vertex 1.51658 1.47653 2.57178 + vertex 1.51647 1.47156 2.57167 + vertex 1.51971 1.47546 2.57115 + endloop + endfacet + facet normal -0.171434 -0.0187925 0.985016 + outer loop + vertex 1.51647 1.47156 2.57167 + vertex 1.51658 1.47653 2.57178 + vertex 1.51402 1.47282 2.57127 + endloop + endfacet + facet normal -0.170883 -0.0176788 0.985133 + outer loop + vertex 1.51396 1.46789 2.57117 + vertex 1.51647 1.47156 2.57167 + vertex 1.51402 1.47282 2.57127 + endloop + endfacet + facet normal -0.170324 -0.0180734 0.985222 + outer loop + vertex 1.5163 1.46674 2.57155 + vertex 1.51647 1.47156 2.57167 + vertex 1.51396 1.46789 2.57117 + endloop + endfacet + facet normal -0.174185 -0.0262008 0.984364 + outer loop + vertex 1.51395 1.46306 2.57104 + vertex 1.5163 1.46674 2.57155 + vertex 1.51396 1.46789 2.57117 + endloop + endfacet + facet normal -0.174488 -0.0166124 0.984519 + outer loop + vertex 1.51402 1.47282 2.57127 + vertex 1.51658 1.47653 2.57178 + vertex 1.51406 1.4778 2.57136 + endloop + endfacet + facet normal -0.171559 -0.0105893 0.985117 + outer loop + vertex 1.51658 1.47653 2.57178 + vertex 1.51666 1.48154 2.57185 + vertex 1.51406 1.4778 2.57136 + endloop + endfacet + facet normal -0.175709 -0.00760472 0.984413 + outer loop + vertex 1.51406 1.4778 2.57136 + vertex 1.51666 1.48154 2.57185 + vertex 1.51409 1.4828 2.5714 + endloop + endfacet + facet normal -0.174866 -0.00582855 0.984575 + outer loop + vertex 1.51666 1.48154 2.57185 + vertex 1.51672 1.48655 2.57189 + vertex 1.51409 1.4828 2.5714 + endloop + endfacet + facet normal -0.18102 -0.00136864 0.983479 + outer loop + vertex 1.51409 1.4828 2.5714 + vertex 1.51672 1.48655 2.57189 + vertex 1.51411 1.48781 2.57141 + endloop + endfacet + facet normal -0.183686 -0.00704728 0.98296 + outer loop + vertex 1.51672 1.48655 2.57189 + vertex 1.51674 1.49154 2.57193 + vertex 1.51411 1.48781 2.57141 + endloop + endfacet + facet normal -0.184445 -0.00649304 0.982821 + outer loop + vertex 1.51411 1.48781 2.57141 + vertex 1.51674 1.49154 2.57193 + vertex 1.51412 1.4928 2.57145 + endloop + endfacet + facet normal -0.182099 -0.00141794 0.983279 + outer loop + vertex 1.51674 1.49154 2.57193 + vertex 1.51679 1.49654 2.57195 + vertex 1.51412 1.4928 2.57145 + endloop + endfacet + facet normal -0.181173 -0.00210281 0.983449 + outer loop + vertex 1.51412 1.4928 2.57145 + vertex 1.51679 1.49654 2.57195 + vertex 1.51415 1.49779 2.57146 + endloop + endfacet + facet normal -0.182566 -0.00513188 0.98318 + outer loop + vertex 1.51679 1.49654 2.57195 + vertex 1.51685 1.50153 2.57198 + vertex 1.51415 1.49779 2.57146 + endloop + endfacet + facet normal -0.18589 -0.00264628 0.982567 + outer loop + vertex 1.51415 1.49779 2.57146 + vertex 1.51685 1.50153 2.57198 + vertex 1.51418 1.50279 2.57148 + endloop + endfacet + facet normal -0.185261 -0.0012704 0.982689 + outer loop + vertex 1.51685 1.50153 2.57198 + vertex 1.51691 1.50652 2.572 + vertex 1.51418 1.50279 2.57148 + endloop + endfacet + facet normal -0.18399 -0.00223041 0.982926 + outer loop + vertex 1.51418 1.50279 2.57148 + vertex 1.51691 1.50652 2.572 + vertex 1.51421 1.50779 2.5715 + endloop + endfacet + facet normal -0.183565 -0.00129122 0.983007 + outer loop + vertex 1.51691 1.50652 2.572 + vertex 1.51694 1.51152 2.57201 + vertex 1.51421 1.50779 2.5715 + endloop + endfacet + facet normal -0.184349 -0.000697905 0.982861 + outer loop + vertex 1.51421 1.50779 2.5715 + vertex 1.51694 1.51152 2.57201 + vertex 1.51422 1.51278 2.5715 + endloop + endfacet + facet normal -0.186415 -0.00531243 0.982457 + outer loop + vertex 1.51694 1.51152 2.57201 + vertex 1.51692 1.5165 2.57204 + vertex 1.51422 1.51278 2.5715 + endloop + endfacet + facet normal -0.193679 0.000149239 0.981065 + outer loop + vertex 1.51422 1.51278 2.5715 + vertex 1.51692 1.5165 2.57204 + vertex 1.51419 1.51777 2.5715 + endloop + endfacet + facet normal -0.191611 0.0047502 0.981459 + outer loop + vertex 1.51692 1.5165 2.57204 + vertex 1.51686 1.5215 2.572 + vertex 1.51419 1.51777 2.5715 + endloop + endfacet + facet normal -0.187752 0.00188483 0.982215 + outer loop + vertex 1.51419 1.51777 2.5715 + vertex 1.51686 1.5215 2.572 + vertex 1.51414 1.52276 2.57148 + endloop + endfacet + facet normal -0.18685 0.00388995 0.982381 + outer loop + vertex 1.51686 1.5215 2.572 + vertex 1.51675 1.52649 2.57196 + vertex 1.51414 1.52276 2.57148 + endloop + endfacet + facet normal -0.187394 0.00428499 0.982276 + outer loop + vertex 1.51414 1.52276 2.57148 + vertex 1.51675 1.52649 2.57196 + vertex 1.51407 1.52776 2.57144 + endloop + endfacet + facet normal -0.187885 0.00320915 0.982186 + outer loop + vertex 1.51675 1.52649 2.57196 + vertex 1.51662 1.53148 2.57192 + vertex 1.51407 1.52776 2.57144 + endloop + endfacet + facet normal -0.190852 0.00531628 0.981604 + outer loop + vertex 1.51407 1.52776 2.57144 + vertex 1.51662 1.53148 2.57192 + vertex 1.514 1.53276 2.5714 + endloop + endfacet + facet normal -0.190305 0.00648085 0.981704 + outer loop + vertex 1.51662 1.53148 2.57192 + vertex 1.5165 1.53648 2.57186 + vertex 1.514 1.53276 2.5714 + endloop + endfacet + facet normal -0.192095 0.0077281 0.981346 + outer loop + vertex 1.514 1.53276 2.5714 + vertex 1.5165 1.53648 2.57186 + vertex 1.51395 1.53776 2.57135 + endloop + endfacet + facet normal -0.191309 0.00935201 0.981485 + outer loop + vertex 1.5165 1.53648 2.57186 + vertex 1.5164 1.54147 2.5718 + vertex 1.51395 1.53776 2.57135 + endloop + endfacet + facet normal -0.187084 0.00645942 0.982323 + outer loop + vertex 1.51395 1.53776 2.57135 + vertex 1.5164 1.54147 2.5718 + vertex 1.51391 1.54273 2.57131 + endloop + endfacet + facet normal -0.188517 0.00353614 0.982064 + outer loop + vertex 1.5164 1.54147 2.5718 + vertex 1.51626 1.5464 2.57175 + vertex 1.51391 1.54273 2.57131 + endloop + endfacet + facet normal -0.18178 -0.000929764 0.983339 + outer loop + vertex 1.51391 1.54273 2.57131 + vertex 1.51626 1.5464 2.57175 + vertex 1.51381 1.54764 2.5713 + endloop + endfacet + facet normal -0.183644 -0.00475759 0.982981 + outer loop + vertex 1.51626 1.5464 2.57175 + vertex 1.51596 1.55131 2.57172 + vertex 1.51381 1.54764 2.5713 + endloop + endfacet + facet normal -0.209515 0.0109944 0.977744 + outer loop + vertex 1.51381 1.54764 2.5713 + vertex 1.51596 1.55131 2.57172 + vertex 1.5136 1.55247 2.5712 + endloop + endfacet + facet normal -0.215584 -0.00191165 0.976483 + outer loop + vertex 1.51596 1.55131 2.57172 + vertex 1.5154 1.55657 2.57161 + vertex 1.5136 1.55247 2.5712 + endloop + endfacet + facet normal -0.285277 0.0306687 0.957954 + outer loop + vertex 1.5136 1.55247 2.5712 + vertex 1.5154 1.55657 2.57161 + vertex 1.51322 1.55662 2.57096 + endloop + endfacet + facet normal -0.285815 0.0118693 0.958211 + outer loop + vertex 1.51375 1.56137 2.57105 + vertex 1.51322 1.55662 2.57096 + vertex 1.5154 1.55657 2.57161 + endloop + endfacet + facet normal -0.14916 0.0621632 0.986857 + outer loop + vertex 1.51614 1.56103 2.57144 + vertex 1.51375 1.56137 2.57105 + vertex 1.5154 1.55657 2.57161 + endloop + endfacet + facet normal 0.173016 0.00881337 0.98488 + outer loop + vertex 1.51614 1.56103 2.57144 + vertex 1.5154 1.55657 2.57161 + vertex 1.51815 1.55906 2.5711 + endloop + endfacet + facet normal 0.214884 0.053093 0.975195 + outer loop + vertex 1.51815 1.55906 2.5711 + vertex 1.51943 1.5636 2.57057 + vertex 1.51614 1.56103 2.57144 + endloop + endfacet + facet normal 0.212551 0.0561877 0.975533 + outer loop + vertex 1.51614 1.56103 2.57144 + vertex 1.51943 1.5636 2.57057 + vertex 1.51569 1.56527 2.57129 + endloop + endfacet + facet normal 0.198751 0.0233381 0.979772 + outer loop + vertex 1.51943 1.5636 2.57057 + vertex 1.51871 1.56896 2.57059 + vertex 1.51569 1.56527 2.57129 + endloop + endfacet + facet normal 0.191708 0.0293346 0.981014 + outer loop + vertex 1.51569 1.56527 2.57129 + vertex 1.51871 1.56896 2.57059 + vertex 1.51509 1.57029 2.57126 + endloop + endfacet + facet normal -0.176772 -0.0144195 0.984146 + outer loop + vertex 1.51509 1.57029 2.57126 + vertex 1.51324 1.56715 2.57088 + vertex 1.51569 1.56527 2.57129 + endloop + endfacet + facet normal -0.153739 0.016399 0.987975 + outer loop + vertex 1.51324 1.56715 2.57088 + vertex 1.51375 1.56137 2.57105 + vertex 1.51569 1.56527 2.57129 + endloop + endfacet + facet normal -0.19357 -0.00416631 0.981078 + outer loop + vertex 1.51279 1.57203 2.57081 + vertex 1.51324 1.56715 2.57088 + vertex 1.51509 1.57029 2.57126 + endloop + endfacet + facet normal -0.186641 0.0054009 0.982413 + outer loop + vertex 1.51452 1.57485 2.57112 + vertex 1.51279 1.57203 2.57081 + vertex 1.51509 1.57029 2.57126 + endloop + endfacet + facet normal 0.158095 0.0491192 0.986201 + outer loop + vertex 1.51509 1.57029 2.57126 + vertex 1.51812 1.57401 2.57059 + vertex 1.51452 1.57485 2.57112 + endloop + endfacet + facet normal 0.164041 0.0765013 0.983483 + outer loop + vertex 1.51812 1.57401 2.57059 + vertex 1.51749 1.5792 2.57029 + vertex 1.51452 1.57485 2.57112 + endloop + endfacet + facet normal 0.0307785 0.167934 0.985318 + outer loop + vertex 1.51382 1.57814 2.57058 + vertex 1.51452 1.57485 2.57112 + vertex 1.51749 1.5792 2.57029 + endloop + endfacet + facet normal 0.00447164 0.254038 0.967184 + outer loop + vertex 1.51382 1.57814 2.57058 + vertex 1.51749 1.5792 2.57029 + vertex 1.51484 1.58258 2.56941 + endloop + endfacet + facet normal -0.123281 0.157057 0.979865 + outer loop + vertex 1.51484 1.58258 2.56941 + vertex 1.51749 1.5792 2.57029 + vertex 1.51882 1.58402 2.56968 + endloop + endfacet + facet normal -0.102196 0.096559 0.990067 + outer loop + vertex 1.51882 1.58402 2.56968 + vertex 1.51817 1.5878 2.56925 + vertex 1.51484 1.58258 2.56941 + endloop + endfacet + facet normal 0.0738292 0.12658 0.989205 + outer loop + vertex 1.51882 1.58402 2.56968 + vertex 1.52266 1.58789 2.5689 + vertex 1.51817 1.5878 2.56925 + endloop + endfacet + facet normal 0.0758542 0.0535279 0.995681 + outer loop + vertex 1.52266 1.58789 2.5689 + vertex 1.52239 1.59259 2.56867 + vertex 1.51817 1.5878 2.56925 + endloop + endfacet + facet normal 0.0191685 0.103271 0.994469 + outer loop + vertex 1.51817 1.5878 2.56925 + vertex 1.52239 1.59259 2.56867 + vertex 1.51791 1.59258 2.56876 + endloop + endfacet + facet normal 0.0193192 0.053295 0.998392 + outer loop + vertex 1.52239 1.59259 2.56867 + vertex 1.52215 1.59738 2.56842 + vertex 1.51791 1.59258 2.56876 + endloop + endfacet + facet normal -0.0050795 0.0747703 0.997188 + outer loop + vertex 1.51791 1.59258 2.56876 + vertex 1.52215 1.59738 2.56842 + vertex 1.5179 1.59759 2.56838 + endloop + endfacet + facet normal -0.00537216 0.0689429 0.997606 + outer loop + vertex 1.52215 1.59738 2.56842 + vertex 1.52221 1.60231 2.56808 + vertex 1.5179 1.59759 2.56838 + endloop + endfacet + facet normal -0.00702031 0.0704401 0.997491 + outer loop + vertex 1.5179 1.59759 2.56838 + vertex 1.52221 1.60231 2.56808 + vertex 1.51799 1.60266 2.56802 + endloop + endfacet + facet normal -0.00703296 0.0702897 0.997502 + outer loop + vertex 1.52221 1.60231 2.56808 + vertex 1.52217 1.6075 2.56771 + vertex 1.51799 1.60266 2.56802 + endloop + endfacet + facet normal -0.00450704 0.0681147 0.997667 + outer loop + vertex 1.51799 1.60266 2.56802 + vertex 1.52217 1.6075 2.56771 + vertex 1.5179 1.60765 2.56768 + endloop + endfacet + facet normal -0.00509376 0.0516731 0.998651 + outer loop + vertex 1.52217 1.6075 2.56771 + vertex 1.52157 1.61245 2.56745 + vertex 1.5179 1.60765 2.56768 + endloop + endfacet + facet normal -0.0294332 0.0702003 0.997099 + outer loop + vertex 1.5179 1.60765 2.56768 + vertex 1.52157 1.61245 2.56745 + vertex 1.51756 1.6122 2.56735 + endloop + endfacet + facet normal -0.0282371 0.0504806 0.998326 + outer loop + vertex 1.52157 1.61245 2.56745 + vertex 1.52062 1.61624 2.56723 + vertex 1.51756 1.6122 2.56735 + endloop + endfacet + facet normal -0.155833 0.146541 0.976853 + outer loop + vertex 1.51756 1.6122 2.56735 + vertex 1.52062 1.61624 2.56723 + vertex 1.51716 1.61662 2.56663 + endloop + endfacet + facet normal -0.158524 0.125991 0.979284 + outer loop + vertex 1.52062 1.61624 2.56723 + vertex 1.52186 1.62104 2.56682 + vertex 1.51716 1.61662 2.56663 + endloop + endfacet + facet normal -0.132907 0.0984479 0.986227 + outer loop + vertex 1.51716 1.61662 2.56663 + vertex 1.52186 1.62104 2.56682 + vertex 1.518 1.62242 2.56616 + endloop + endfacet + facet normal -0.167611 0.00111943 0.985853 + outer loop + vertex 1.52186 1.62104 2.56682 + vertex 1.52119 1.62648 2.5667 + vertex 1.518 1.62242 2.56616 + endloop + endfacet + facet normal -0.170098 0.00312705 0.985422 + outer loop + vertex 1.518 1.62242 2.56616 + vertex 1.52119 1.62648 2.5667 + vertex 1.51803 1.62771 2.56615 + endloop + endfacet + facet normal -0.180611 -0.0249099 0.983239 + outer loop + vertex 1.52119 1.62648 2.5667 + vertex 1.52029 1.63177 2.56667 + vertex 1.51803 1.62771 2.56615 + endloop + endfacet + facet normal -0.24044 0.0100868 0.970611 + outer loop + vertex 1.51803 1.62771 2.56615 + vertex 1.52029 1.63177 2.56667 + vertex 1.51756 1.63183 2.56599 + endloop + endfacet + facet normal -0.240704 -0.00156831 0.970597 + outer loop + vertex 1.51811 1.63604 2.56613 + vertex 1.51756 1.63183 2.56599 + vertex 1.52029 1.63177 2.56667 + endloop + endfacet + facet normal -0.133574 0.0552526 0.989497 + outer loop + vertex 1.52088 1.63602 2.56651 + vertex 1.51811 1.63604 2.56613 + vertex 1.52029 1.63177 2.56667 + endloop + endfacet + facet normal 0.133986 0.0178209 0.990823 + outer loop + vertex 1.52088 1.63602 2.56651 + vertex 1.52029 1.63177 2.56667 + vertex 1.52322 1.63422 2.56622 + endloop + endfacet + facet normal 0.189805 0.0924782 0.977457 + outer loop + vertex 1.52322 1.63422 2.56622 + vertex 1.52421 1.63862 2.56562 + vertex 1.52088 1.63602 2.56651 + endloop + endfacet + facet normal 0.167074 0.121792 0.978393 + outer loop + vertex 1.52088 1.63602 2.56651 + vertex 1.52421 1.63862 2.56562 + vertex 1.52006 1.63951 2.56621 + endloop + endfacet + facet normal 0.164081 0.106306 0.980702 + outer loop + vertex 1.52421 1.63862 2.56562 + vertex 1.52284 1.64393 2.56527 + vertex 1.52006 1.63951 2.56621 + endloop + endfacet + facet normal 0.0351314 0.187786 0.981581 + outer loop + vertex 1.51896 1.6427 2.56564 + vertex 1.52006 1.63951 2.56621 + vertex 1.52284 1.64393 2.56527 + endloop + endfacet + facet normal 0.0149777 0.247671 0.968729 + outer loop + vertex 1.51896 1.6427 2.56564 + vertex 1.52284 1.64393 2.56527 + vertex 1.51973 1.64728 2.56446 + endloop + endfacet + facet normal -0.0886203 0.155331 0.983879 + outer loop + vertex 1.51973 1.64728 2.56446 + vertex 1.52284 1.64393 2.56527 + vertex 1.52391 1.6488 2.5646 + endloop + endfacet + facet normal -0.0660023 0.0919584 0.993573 + outer loop + vertex 1.52391 1.6488 2.5646 + vertex 1.52317 1.65253 2.5642 + vertex 1.51973 1.64728 2.56446 + endloop + endfacet + facet normal -0.219969 0.191126 0.956601 + outer loop + vertex 1.51973 1.64728 2.56446 + vertex 1.52317 1.65253 2.5642 + vertex 1.51919 1.65263 2.56327 + endloop + endfacet + facet normal -0.226173 0.0805789 0.970748 + outer loop + vertex 1.52317 1.65253 2.5642 + vertex 1.52294 1.65725 2.56376 + vertex 1.51919 1.65263 2.56327 + endloop + endfacet + facet normal -0.245384 0.0968355 0.964577 + outer loop + vertex 1.51919 1.65263 2.56327 + vertex 1.52294 1.65725 2.56376 + vertex 1.51919 1.65775 2.56275 + endloop + endfacet + facet normal -0.250903 0.0590639 0.966209 + outer loop + vertex 1.52294 1.65725 2.56376 + vertex 1.52286 1.66216 2.56344 + vertex 1.51919 1.65775 2.56275 + endloop + endfacet + facet normal -0.239631 0.0491341 0.96962 + outer loop + vertex 1.51919 1.65775 2.56275 + vertex 1.52286 1.66216 2.56344 + vertex 1.51926 1.66274 2.56252 + endloop + endfacet + facet normal -0.241684 0.0363222 0.969675 + outer loop + vertex 1.52286 1.66216 2.56344 + vertex 1.52266 1.66697 2.56321 + vertex 1.51926 1.66274 2.56252 + endloop + endfacet + facet normal -0.261 0.0527557 0.963896 + outer loop + vertex 1.51926 1.66274 2.56252 + vertex 1.52266 1.66697 2.56321 + vertex 1.51935 1.66774 2.56227 + endloop + endfacet + facet normal -0.259087 0.0610636 0.963922 + outer loop + vertex 1.52266 1.66697 2.56321 + vertex 1.52255 1.67177 2.56287 + vertex 1.51935 1.66774 2.56227 + endloop + endfacet + facet normal -0.246518 0.050508 0.967821 + outer loop + vertex 1.51935 1.66774 2.56227 + vertex 1.52255 1.67177 2.56287 + vertex 1.51935 1.67272 2.56201 + endloop + endfacet + facet normal -0.247233 0.0480501 0.967764 + outer loop + vertex 1.52255 1.67177 2.56287 + vertex 1.5222 1.67664 2.56254 + vertex 1.51935 1.67272 2.56201 + endloop + endfacet + facet normal -0.22791 0.0333041 0.973113 + outer loop + vertex 1.51935 1.67272 2.56201 + vertex 1.5222 1.67664 2.56254 + vertex 1.51918 1.67756 2.5618 + endloop + endfacet + facet normal -0.240044 -0.00882265 0.970722 + outer loop + vertex 1.5222 1.67664 2.56254 + vertex 1.5213 1.6807 2.56236 + vertex 1.51918 1.67756 2.5618 + endloop + endfacet + facet normal -0.307839 0.0404369 0.950579 + outer loop + vertex 1.51918 1.67756 2.5618 + vertex 1.5213 1.6807 2.56236 + vertex 1.51904 1.68244 2.56155 + endloop + endfacet + facet normal -0.262731 0.103079 0.959347 + outer loop + vertex 1.5213 1.6807 2.56236 + vertex 1.5218 1.68562 2.56196 + vertex 1.51904 1.68244 2.56155 + endloop + endfacet + facet normal -0.183328 0.0312062 0.982556 + outer loop + vertex 1.51904 1.68244 2.56155 + vertex 1.5218 1.68562 2.56196 + vertex 1.51863 1.68741 2.56132 + endloop + endfacet + facet normal -0.210134 -0.0180582 0.977506 + outer loop + vertex 1.5218 1.68562 2.56196 + vertex 1.52026 1.69123 2.56174 + vertex 1.51863 1.68741 2.56132 + endloop + endfacet + facet normal -0.290159 0.0183117 0.956803 + outer loop + vertex 1.51863 1.68741 2.56132 + vertex 1.52026 1.69123 2.56174 + vertex 1.5179 1.6914 2.56102 + endloop + endfacet + facet normal -0.287973 0.0473253 0.956468 + outer loop + vertex 1.51834 1.69477 2.56098 + vertex 1.5179 1.6914 2.56102 + vertex 1.52026 1.69123 2.56174 + endloop + endfacet + facet normal -0.208469 0.0941383 0.973488 + outer loop + vertex 1.52045 1.69534 2.56138 + vertex 1.51834 1.69477 2.56098 + vertex 1.52026 1.69123 2.56174 + endloop + endfacet + facet normal 0.112682 0.0806834 0.99035 + outer loop + vertex 1.52045 1.69534 2.56138 + vertex 1.52026 1.69123 2.56174 + vertex 1.52285 1.69394 2.56122 + endloop + endfacet + facet normal 0.157974 0.160162 0.974368 + outer loop + vertex 1.52285 1.69394 2.56122 + vertex 1.52357 1.69873 2.56032 + vertex 1.52045 1.69534 2.56138 + endloop + endfacet + facet normal 0.0127507 0.288496 0.957396 + outer loop + vertex 1.51954 1.69795 2.56061 + vertex 1.52045 1.69534 2.56138 + vertex 1.52357 1.69873 2.56032 + endloop + endfacet + facet normal 0.132963 0.0611387 0.989233 + outer loop + vertex 1.52425 1.69 2.56128 + vertex 1.52285 1.69394 2.56122 + vertex 1.52026 1.69123 2.56174 + endloop + endfacet + facet normal 0.223691 0.0930447 0.970209 + outer loop + vertex 1.52285 1.69394 2.56122 + vertex 1.52425 1.69 2.56128 + vertex 1.52755 1.69445 2.56009 + endloop + endfacet + facet normal 0.229964 0.088128 0.969201 + outer loop + vertex 1.52916 1.68869 2.56023 + vertex 1.52755 1.69445 2.56009 + vertex 1.52425 1.69 2.56128 + endloop + endfacet + facet normal 0.229627 0.0866924 0.96941 + outer loop + vertex 1.52549 1.68603 2.56134 + vertex 1.52916 1.68869 2.56023 + vertex 1.52425 1.69 2.56128 + endloop + endfacet + facet normal 0.160137 0.065204 0.984939 + outer loop + vertex 1.52425 1.69 2.56128 + vertex 1.5218 1.68562 2.56196 + vertex 1.52549 1.68603 2.56134 + endloop + endfacet + facet normal 0.156288 0.0970955 0.982928 + outer loop + vertex 1.52549 1.68603 2.56134 + vertex 1.5218 1.68562 2.56196 + vertex 1.5249 1.68141 2.56189 + endloop + endfacet + facet normal 0.230406 0.0859197 0.969294 + outer loop + vertex 1.52549 1.68603 2.56134 + vertex 1.5249 1.68141 2.56189 + vertex 1.52823 1.68418 2.56085 + endloop + endfacet + facet normal 0.222878 0.0953173 0.970175 + outer loop + vertex 1.52948 1.6802 2.56095 + vertex 1.52823 1.68418 2.56085 + vertex 1.5249 1.68141 2.56189 + endloop + endfacet + facet normal 0.223321 0.0972287 0.969884 + outer loop + vertex 1.5249 1.68141 2.56189 + vertex 1.52649 1.67573 2.56209 + vertex 1.52948 1.6802 2.56095 + endloop + endfacet + facet normal 0.223767 0.0969116 0.969813 + outer loop + vertex 1.52948 1.6802 2.56095 + vertex 1.52649 1.67573 2.56209 + vertex 1.5307 1.67629 2.56106 + endloop + endfacet + facet normal 0.212608 0.0935256 0.972652 + outer loop + vertex 1.5307 1.67629 2.56106 + vertex 1.53436 1.67877 2.56002 + vertex 1.52948 1.6802 2.56095 + endloop + endfacet + facet normal 0.212579 0.0934186 0.972668 + outer loop + vertex 1.53436 1.67877 2.56002 + vertex 1.53287 1.68447 2.5598 + vertex 1.52948 1.6802 2.56095 + endloop + endfacet + facet normal 0.182248 0.0857474 0.979507 + outer loop + vertex 1.53436 1.67877 2.56002 + vertex 1.53804 1.68314 2.55896 + vertex 1.53287 1.68447 2.5598 + endloop + endfacet + facet normal 0.182626 0.0873489 0.979295 + outer loop + vertex 1.53804 1.68314 2.55896 + vertex 1.53776 1.68791 2.55858 + vertex 1.53287 1.68447 2.5598 + endloop + endfacet + facet normal 0.178312 0.0935531 0.979516 + outer loop + vertex 1.53287 1.68447 2.5598 + vertex 1.53776 1.68791 2.55858 + vertex 1.534 1.68917 2.55915 + endloop + endfacet + facet normal 0.209285 0.0853749 0.974121 + outer loop + vertex 1.52916 1.68869 2.56023 + vertex 1.53287 1.68447 2.5598 + vertex 1.534 1.68917 2.55915 + endloop + endfacet + facet normal 0.209272 0.0854945 0.974113 + outer loop + vertex 1.534 1.68917 2.55915 + vertex 1.53302 1.69317 2.55901 + vertex 1.52916 1.68869 2.56023 + endloop + endfacet + facet normal 0.183881 0.0794423 0.979733 + outer loop + vertex 1.534 1.68917 2.55915 + vertex 1.53756 1.69244 2.55822 + vertex 1.53302 1.69317 2.55901 + endloop + endfacet + facet normal 0.185375 0.0899936 0.978538 + outer loop + vertex 1.53756 1.69244 2.55822 + vertex 1.53728 1.69701 2.55785 + vertex 1.53302 1.69317 2.55901 + endloop + endfacet + facet normal 0.188444 0.0865056 0.978267 + outer loop + vertex 1.53302 1.69317 2.55901 + vertex 1.53728 1.69701 2.55785 + vertex 1.53271 1.69799 2.55864 + endloop + endfacet + facet normal 0.169628 0.0892607 0.981458 + outer loop + vertex 1.53756 1.69244 2.55822 + vertex 1.54088 1.69581 2.55733 + vertex 1.53728 1.69701 2.55785 + endloop + endfacet + facet normal 0.168066 0.0908324 0.981582 + outer loop + vertex 1.54184 1.69183 2.55754 + vertex 1.54088 1.69581 2.55733 + vertex 1.53756 1.69244 2.55822 + endloop + endfacet + facet normal 0.167647 0.0874418 0.981961 + outer loop + vertex 1.53776 1.68791 2.55858 + vertex 1.54184 1.69183 2.55754 + vertex 1.53756 1.69244 2.55822 + endloop + endfacet + facet normal 0.166846 0.0882921 0.982022 + outer loop + vertex 1.54219 1.68701 2.55791 + vertex 1.54184 1.69183 2.55754 + vertex 1.53776 1.68791 2.55858 + endloop + endfacet + facet normal 0.172693 0.0886315 0.98098 + outer loop + vertex 1.54219 1.68701 2.55791 + vertex 1.54663 1.6908 2.55679 + vertex 1.54184 1.69183 2.55754 + endloop + endfacet + facet normal 0.173198 0.091203 0.980655 + outer loop + vertex 1.54663 1.6908 2.55679 + vertex 1.54508 1.69651 2.55653 + vertex 1.54184 1.69183 2.55754 + endloop + endfacet + facet normal 0.174723 0.0916034 0.980347 + outer loop + vertex 1.54508 1.69651 2.55653 + vertex 1.54663 1.6908 2.55679 + vertex 1.54957 1.69514 2.55586 + endloop + endfacet + facet normal 0.176007 0.0961265 0.979684 + outer loop + vertex 1.54957 1.69514 2.55586 + vertex 1.54836 1.69909 2.55569 + vertex 1.54508 1.69651 2.55653 + endloop + endfacet + facet normal 0.174475 0.0980995 0.979763 + outer loop + vertex 1.54577 1.70105 2.55595 + vertex 1.54508 1.69651 2.55653 + vertex 1.54836 1.69909 2.55569 + endloop + endfacet + facet normal 0.175862 0.100002 0.979322 + outer loop + vertex 1.54836 1.69909 2.55569 + vertex 1.54918 1.70345 2.5551 + vertex 1.54577 1.70105 2.55595 + endloop + endfacet + facet normal 0.172562 0.104713 0.979417 + outer loop + vertex 1.54577 1.70105 2.55595 + vertex 1.54918 1.70345 2.5551 + vertex 1.54452 1.70503 2.55575 + endloop + endfacet + facet normal 0.172128 0.104581 0.979507 + outer loop + vertex 1.54452 1.70503 2.55575 + vertex 1.54164 1.70068 2.55672 + vertex 1.54577 1.70105 2.55595 + endloop + endfacet + facet normal 0.175869 0.102009 0.979114 + outer loop + vertex 1.53981 1.70653 2.55644 + vertex 1.54164 1.70068 2.55672 + vertex 1.54452 1.70503 2.55575 + endloop + endfacet + facet normal 0.173257 0.106911 0.979057 + outer loop + vertex 1.54918 1.70345 2.5551 + vertex 1.54766 1.70924 2.55473 + vertex 1.54452 1.70503 2.55575 + endloop + endfacet + facet normal 0.155901 0.102583 0.982431 + outer loop + vertex 1.54918 1.70345 2.5551 + vertex 1.55288 1.70782 2.55405 + vertex 1.54766 1.70924 2.55473 + endloop + endfacet + facet normal 0.153197 0.104913 0.982611 + outer loop + vertex 1.55372 1.70378 2.55435 + vertex 1.55288 1.70782 2.55405 + vertex 1.54918 1.70345 2.5551 + endloop + endfacet + facet normal 0.153707 0.099135 0.983131 + outer loop + vertex 1.54918 1.70345 2.5551 + vertex 1.55264 1.69915 2.55499 + vertex 1.55372 1.70378 2.55435 + endloop + endfacet + facet normal 0.11006 0.109976 0.987822 + outer loop + vertex 1.55264 1.69915 2.55499 + vertex 1.55755 1.70261 2.55406 + vertex 1.55372 1.70378 2.55435 + endloop + endfacet + facet normal 0.109549 0.108247 0.98807 + outer loop + vertex 1.55755 1.70261 2.55406 + vertex 1.55766 1.70737 2.55352 + vertex 1.55372 1.70378 2.55435 + endloop + endfacet + facet normal 0.114345 0.10392 0.987991 + outer loop + vertex 1.55769 1.69781 2.55455 + vertex 1.55755 1.70261 2.55406 + vertex 1.55264 1.69915 2.55499 + endloop + endfacet + facet normal 0.109641 0.0854169 0.990294 + outer loop + vertex 1.55413 1.69359 2.5553 + vertex 1.55769 1.69781 2.55455 + vertex 1.55264 1.69915 2.55499 + endloop + endfacet + facet normal 0.152627 0.0965335 0.983558 + outer loop + vertex 1.55413 1.69359 2.5553 + vertex 1.55264 1.69915 2.55499 + vertex 1.54957 1.69514 2.55586 + endloop + endfacet + facet normal 0.14806 0.0823725 0.985542 + outer loop + vertex 1.55079 1.69124 2.556 + vertex 1.55413 1.69359 2.5553 + vertex 1.54957 1.69514 2.55586 + endloop + endfacet + facet normal 0.149479 0.0803463 0.985495 + outer loop + vertex 1.55342 1.68935 2.55576 + vertex 1.55413 1.69359 2.5553 + vertex 1.55079 1.69124 2.556 + endloop + endfacet + facet normal 0.158627 0.0934547 0.982906 + outer loop + vertex 1.55079 1.69124 2.556 + vertex 1.55012 1.68669 2.55654 + vertex 1.55342 1.68935 2.55576 + endloop + endfacet + facet normal 0.155916 0.0968435 0.983011 + outer loop + vertex 1.55472 1.68553 2.55593 + vertex 1.55342 1.68935 2.55576 + vertex 1.55012 1.68669 2.55654 + endloop + endfacet + facet normal 0.153771 0.0877357 0.984204 + outer loop + vertex 1.55012 1.68669 2.55654 + vertex 1.55185 1.68097 2.55678 + vertex 1.55472 1.68553 2.55593 + endloop + endfacet + facet normal 0.145828 0.0928541 0.984943 + outer loop + vertex 1.55472 1.68553 2.55593 + vertex 1.55185 1.68097 2.55678 + vertex 1.55631 1.68173 2.55605 + endloop + endfacet + facet normal 0.0950959 0.0717886 0.992876 + outer loop + vertex 1.55631 1.68173 2.55605 + vertex 1.55904 1.68454 2.55559 + vertex 1.55472 1.68553 2.55593 + endloop + endfacet + facet normal 0.0976588 0.0833062 0.991727 + outer loop + vertex 1.55904 1.68454 2.55559 + vertex 1.55765 1.68948 2.55531 + vertex 1.55472 1.68553 2.55593 + endloop + endfacet + facet normal 0.0461643 0.0690163 0.996547 + outer loop + vertex 1.55904 1.68454 2.55559 + vertex 1.56276 1.68794 2.55518 + vertex 1.55765 1.68948 2.55531 + endloop + endfacet + facet normal 0.0519223 0.088209 0.994748 + outer loop + vertex 1.56276 1.68794 2.55518 + vertex 1.56244 1.69271 2.55477 + vertex 1.55765 1.68948 2.55531 + endloop + endfacet + facet normal 0.0473833 0.0948829 0.99436 + outer loop + vertex 1.55765 1.68948 2.55531 + vertex 1.56244 1.69271 2.55477 + vertex 1.55857 1.69387 2.55484 + endloop + endfacet + facet normal 0.0972449 0.0840681 0.991704 + outer loop + vertex 1.55413 1.69359 2.5553 + vertex 1.55765 1.68948 2.55531 + vertex 1.55857 1.69387 2.55484 + endloop + endfacet + facet normal 0.048298 0.0979429 0.994019 + outer loop + vertex 1.56244 1.69271 2.55477 + vertex 1.56247 1.69737 2.55431 + vertex 1.55857 1.69387 2.55484 + endloop + endfacet + facet normal 0.057079 0.0882276 0.994464 + outer loop + vertex 1.55857 1.69387 2.55484 + vertex 1.56247 1.69737 2.55431 + vertex 1.55769 1.69781 2.55455 + endloop + endfacet + facet normal 0.0587502 0.107117 0.992509 + outer loop + vertex 1.56247 1.69737 2.55431 + vertex 1.56245 1.70219 2.55379 + vertex 1.55769 1.69781 2.55455 + endloop + endfacet + facet normal 0.029413 0.0868126 0.99579 + outer loop + vertex 1.56276 1.68794 2.55518 + vertex 1.56741 1.69222 2.55467 + vertex 1.56244 1.69271 2.55477 + endloop + endfacet + facet normal 0.03043 0.0973746 0.994782 + outer loop + vertex 1.56741 1.69222 2.55467 + vertex 1.56735 1.69718 2.55418 + vertex 1.56244 1.69271 2.55477 + endloop + endfacet + facet normal 0.0297491 0.0981152 0.99473 + outer loop + vertex 1.56244 1.69271 2.55477 + vertex 1.56735 1.69718 2.55418 + vertex 1.56247 1.69737 2.55431 + endloop + endfacet + facet normal 0.0300717 0.10709 0.993794 + outer loop + vertex 1.56735 1.69718 2.55418 + vertex 1.56747 1.70218 2.55364 + vertex 1.56247 1.69737 2.55431 + endloop + endfacet + facet normal 0.0300016 0.107162 0.993789 + outer loop + vertex 1.56247 1.69737 2.55431 + vertex 1.56747 1.70218 2.55364 + vertex 1.56245 1.70219 2.55379 + endloop + endfacet + facet normal 0.0300002 0.115856 0.992813 + outer loop + vertex 1.56747 1.70218 2.55364 + vertex 1.56759 1.70728 2.55304 + vertex 1.56245 1.70219 2.55379 + endloop + endfacet + facet normal 0.0224652 0.094296 0.995291 + outer loop + vertex 1.56781 1.68724 2.55513 + vertex 1.56741 1.69222 2.55467 + vertex 1.56276 1.68794 2.55518 + endloop + endfacet + facet normal 0.0201739 0.0774319 0.996794 + outer loop + vertex 1.56371 1.68287 2.55555 + vertex 1.56781 1.68724 2.55513 + vertex 1.56276 1.68794 2.55518 + endloop + endfacet + facet normal -0.0106668 0.106109 0.994297 + outer loop + vertex 1.56832 1.68291 2.5556 + vertex 1.56781 1.68724 2.55513 + vertex 1.56371 1.68287 2.55555 + endloop + endfacet + facet normal -0.0104714 0.0765487 0.997011 + outer loop + vertex 1.56371 1.68287 2.55555 + vertex 1.56607 1.67962 2.55583 + vertex 1.56832 1.68291 2.5556 + endloop + endfacet + facet normal -0.0194388 0.0700737 0.997352 + outer loop + vertex 1.56321 1.67895 2.55582 + vertex 1.56607 1.67962 2.55583 + vertex 1.56371 1.68287 2.55555 + endloop + endfacet + facet normal 0.0384444 0.0626995 0.997292 + outer loop + vertex 1.55992 1.68012 2.55587 + vertex 1.56321 1.67895 2.55582 + vertex 1.56371 1.68287 2.55555 + endloop + endfacet + facet normal 0.0324245 0.0709633 0.996952 + outer loop + vertex 1.55904 1.68454 2.55559 + vertex 1.55992 1.68012 2.55587 + vertex 1.56371 1.68287 2.55555 + endloop + endfacet + facet normal 0.0497605 0.094496 0.994281 + outer loop + vertex 1.56321 1.67895 2.55582 + vertex 1.55992 1.68012 2.55587 + vertex 1.56133 1.67562 2.55623 + endloop + endfacet + facet normal 0.0257216 0.108008 0.993817 + outer loop + vertex 1.56496 1.67685 2.556 + vertex 1.56321 1.67895 2.55582 + vertex 1.56133 1.67562 2.55623 + endloop + endfacet + facet normal 0.0252052 0.1095 0.993667 + outer loop + vertex 1.56496 1.67685 2.556 + vertex 1.56133 1.67562 2.55623 + vertex 1.56614 1.67301 2.55639 + endloop + endfacet + facet normal -0.0363446 0.0907297 0.995212 + outer loop + vertex 1.56496 1.67685 2.556 + vertex 1.56614 1.67301 2.55639 + vertex 1.5675 1.67716 2.55607 + endloop + endfacet + facet normal -0.0346606 0.0766152 0.996458 + outer loop + vertex 1.5675 1.67716 2.55607 + vertex 1.56607 1.67962 2.55583 + vertex 1.56496 1.67685 2.556 + endloop + endfacet + facet normal 0.0202908 0.100524 0.994728 + outer loop + vertex 1.56133 1.67562 2.55623 + vertex 1.56109 1.67106 2.55669 + vertex 1.56614 1.67301 2.55639 + endloop + endfacet + facet normal 0.0217154 0.0968734 0.99506 + outer loop + vertex 1.56228 1.66725 2.55704 + vertex 1.56614 1.67301 2.55639 + vertex 1.56109 1.67106 2.55669 + endloop + endfacet + facet normal 0.0241937 0.0952226 0.995162 + outer loop + vertex 1.56726 1.66727 2.55692 + vertex 1.56614 1.67301 2.55639 + vertex 1.56228 1.66725 2.55704 + endloop + endfacet + facet normal 0.0241881 0.0960174 0.995086 + outer loop + vertex 1.56267 1.66231 2.55751 + vertex 1.56726 1.66727 2.55692 + vertex 1.56228 1.66725 2.55704 + endloop + endfacet + facet normal 0.0278378 0.0926664 0.995308 + outer loop + vertex 1.56748 1.66235 2.55737 + vertex 1.56726 1.66727 2.55692 + vertex 1.56267 1.66231 2.55751 + endloop + endfacet + facet normal 0.027849 0.0917388 0.995394 + outer loop + vertex 1.56261 1.65726 2.55797 + vertex 1.56748 1.66235 2.55737 + vertex 1.56267 1.66231 2.55751 + endloop + endfacet + facet normal 0.0352796 0.0846739 0.995784 + outer loop + vertex 1.56759 1.65747 2.55778 + vertex 1.56748 1.66235 2.55737 + vertex 1.56261 1.65726 2.55797 + endloop + endfacet + facet normal 0.0352883 0.0844816 0.9958 + outer loop + vertex 1.56248 1.65221 2.55841 + vertex 1.56759 1.65747 2.55778 + vertex 1.56261 1.65726 2.55797 + endloop + endfacet + facet normal 0.0415417 0.0784481 0.996052 + outer loop + vertex 1.56757 1.65239 2.55818 + vertex 1.56759 1.65747 2.55778 + vertex 1.56248 1.65221 2.55841 + endloop + endfacet + facet normal 0.0414734 0.0801715 0.995918 + outer loop + vertex 1.56237 1.64716 2.55882 + vertex 1.56757 1.65239 2.55818 + vertex 1.56248 1.65221 2.55841 + endloop + endfacet + facet normal 0.0451135 0.076563 0.996044 + outer loop + vertex 1.56752 1.64725 2.55858 + vertex 1.56757 1.65239 2.55818 + vertex 1.56237 1.64716 2.55882 + endloop + endfacet + facet normal 0.0450764 0.0784263 0.9959 + outer loop + vertex 1.56236 1.6422 2.55921 + vertex 1.56752 1.64725 2.55858 + vertex 1.56237 1.64716 2.55882 + endloop + endfacet + facet normal 0.0479113 0.0755409 0.995991 + outer loop + vertex 1.56746 1.64219 2.55896 + vertex 1.56752 1.64725 2.55858 + vertex 1.56236 1.6422 2.55921 + endloop + endfacet + facet normal 0.0479089 0.0767288 0.9959 + outer loop + vertex 1.56249 1.63741 2.55957 + vertex 1.56746 1.64219 2.55896 + vertex 1.56236 1.6422 2.55921 + endloop + endfacet + facet normal 0.0501539 0.0743971 0.995967 + outer loop + vertex 1.5674 1.63725 2.55934 + vertex 1.56746 1.64219 2.55896 + vertex 1.56249 1.63741 2.55957 + endloop + endfacet + facet normal 0.0501727 0.0750277 0.995918 + outer loop + vertex 1.56248 1.63276 2.55992 + vertex 1.5674 1.63725 2.55934 + vertex 1.56249 1.63741 2.55957 + endloop + endfacet + facet normal 0.053055 0.0718784 0.996001 + outer loop + vertex 1.56737 1.63237 2.55969 + vertex 1.5674 1.63725 2.55934 + vertex 1.56248 1.63276 2.55992 + endloop + endfacet + facet normal 0.0530095 0.0712934 0.996046 + outer loop + vertex 1.56274 1.628 2.56025 + vertex 1.56737 1.63237 2.55969 + vertex 1.56248 1.63276 2.55992 + endloop + endfacet + facet normal 0.0534019 0.0708784 0.996054 + outer loop + vertex 1.56763 1.62749 2.56002 + vertex 1.56737 1.63237 2.55969 + vertex 1.56274 1.628 2.56025 + endloop + endfacet + facet normal 0.0530607 0.0675041 0.996307 + outer loop + vertex 1.56383 1.62381 2.56048 + vertex 1.56763 1.62749 2.56002 + vertex 1.56274 1.628 2.56025 + endloop + endfacet + facet normal 0.0526304 0.0679476 0.9963 + outer loop + vertex 1.56832 1.62186 2.56037 + vertex 1.56763 1.62749 2.56002 + vertex 1.56383 1.62381 2.56048 + endloop + endfacet + facet normal 0.0440229 0.0480494 0.997874 + outer loop + vertex 1.56267 1.61892 2.56076 + vertex 1.56832 1.62186 2.56037 + vertex 1.56383 1.62381 2.56048 + endloop + endfacet + facet normal 0.00832773 0.116001 0.993214 + outer loop + vertex 1.56619 1.61766 2.56088 + vertex 1.56832 1.62186 2.56037 + vertex 1.56267 1.61892 2.56076 + endloop + endfacet + facet normal -0.0148829 0.0518512 0.998544 + outer loop + vertex 1.56619 1.61766 2.56088 + vertex 1.56267 1.61892 2.56076 + vertex 1.56454 1.61506 2.56099 + endloop + endfacet + facet normal -0.0196105 0.0548402 0.998303 + outer loop + vertex 1.56454 1.61506 2.56099 + vertex 1.5675 1.61496 2.56105 + vertex 1.56619 1.61766 2.56088 + endloop + endfacet + facet normal 0.0370741 0.082191 0.995927 + outer loop + vertex 1.56892 1.61776 2.56077 + vertex 1.56619 1.61766 2.56088 + vertex 1.5675 1.61496 2.56105 + endloop + endfacet + facet normal -0.0197357 0.0511494 0.998496 + outer loop + vertex 1.56565 1.61175 2.56118 + vertex 1.5675 1.61496 2.56105 + vertex 1.56454 1.61506 2.56099 + endloop + endfacet + facet normal -0.0380328 0.0449978 0.998263 + outer loop + vertex 1.56317 1.61251 2.56105 + vertex 1.56565 1.61175 2.56118 + vertex 1.56454 1.61506 2.56099 + endloop + endfacet + facet normal -0.040311 0.0462169 0.998118 + outer loop + vertex 1.56454 1.61506 2.56099 + vertex 1.56226 1.61488 2.56091 + vertex 1.56317 1.61251 2.56105 + endloop + endfacet + facet normal -0.0225432 0.094759 0.995245 + outer loop + vertex 1.56317 1.61251 2.56105 + vertex 1.56154 1.60844 2.5614 + vertex 1.56565 1.61175 2.56118 + endloop + endfacet + facet normal 0.0117965 0.052379 0.998558 + outer loop + vertex 1.56154 1.60844 2.5614 + vertex 1.56651 1.60748 2.5614 + vertex 1.56565 1.61175 2.56118 + endloop + endfacet + facet normal 0.0142833 0.0653193 0.997762 + outer loop + vertex 1.56247 1.60272 2.56176 + vertex 1.56651 1.60748 2.5614 + vertex 1.56154 1.60844 2.5614 + endloop + endfacet + facet normal 0.0313417 0.0508933 0.998212 + outer loop + vertex 1.56714 1.60254 2.56163 + vertex 1.56651 1.60748 2.5614 + vertex 1.56247 1.60272 2.56176 + endloop + endfacet + facet normal 0.0315106 0.0553178 0.997971 + outer loop + vertex 1.56274 1.59761 2.56204 + vertex 1.56714 1.60254 2.56163 + vertex 1.56247 1.60272 2.56176 + endloop + endfacet + facet normal 0.0430527 0.0450027 0.998059 + outer loop + vertex 1.5673 1.59754 2.56185 + vertex 1.56714 1.60254 2.56163 + vertex 1.56274 1.59761 2.56204 + endloop + endfacet + facet normal 0.04308 0.0469266 0.997969 + outer loop + vertex 1.56268 1.59257 2.56228 + vertex 1.5673 1.59754 2.56185 + vertex 1.56274 1.59761 2.56204 + endloop + endfacet + facet normal 0.048863 0.0415447 0.997941 + outer loop + vertex 1.56729 1.59254 2.56205 + vertex 1.5673 1.59754 2.56185 + vertex 1.56268 1.59257 2.56228 + endloop + endfacet + facet normal 0.0488743 0.0436923 0.997849 + outer loop + vertex 1.5626 1.58756 2.5625 + vertex 1.56729 1.59254 2.56205 + vertex 1.56268 1.59257 2.56228 + endloop + endfacet + facet normal 0.0520735 0.0406762 0.997815 + outer loop + vertex 1.56731 1.58753 2.56226 + vertex 1.56729 1.59254 2.56205 + vertex 1.5626 1.58756 2.5625 + endloop + endfacet + facet normal 0.0520815 0.0431856 0.997709 + outer loop + vertex 1.56257 1.58254 2.56272 + vertex 1.56731 1.58753 2.56226 + vertex 1.5626 1.58756 2.5625 + endloop + endfacet + facet normal 0.0549522 0.0404615 0.997669 + outer loop + vertex 1.56736 1.58252 2.56246 + vertex 1.56731 1.58753 2.56226 + vertex 1.56257 1.58254 2.56272 + endloop + endfacet + facet normal 0.0549549 0.0421487 0.997599 + outer loop + vertex 1.56256 1.5775 2.56293 + vertex 1.56736 1.58252 2.56246 + vertex 1.56257 1.58254 2.56272 + endloop + endfacet + facet normal 0.0598381 0.0374691 0.997505 + outer loop + vertex 1.5674 1.57749 2.56264 + vertex 1.56736 1.58252 2.56246 + vertex 1.56256 1.5775 2.56293 + endloop + endfacet + facet normal 0.0598381 0.038225 0.997476 + outer loop + vertex 1.56254 1.57245 2.56313 + vertex 1.5674 1.57749 2.56264 + vertex 1.56256 1.5775 2.56293 + endloop + endfacet + facet normal 0.0668456 0.0314347 0.997268 + outer loop + vertex 1.56746 1.57245 2.5628 + vertex 1.5674 1.57749 2.56264 + vertex 1.56254 1.57245 2.56313 + endloop + endfacet + facet normal 0.0668426 0.0329841 0.997218 + outer loop + vertex 1.56253 1.56741 2.5633 + vertex 1.56746 1.57245 2.5628 + vertex 1.56254 1.57245 2.56313 + endloop + endfacet + facet normal 0.076736 0.0232727 0.99678 + outer loop + vertex 1.5676 1.56736 2.56291 + vertex 1.56746 1.57245 2.5628 + vertex 1.56253 1.56741 2.5633 + endloop + endfacet + facet normal 0.0767881 0.0296333 0.996607 + outer loop + vertex 1.56252 1.56237 2.56345 + vertex 1.5676 1.56736 2.56291 + vertex 1.56253 1.56741 2.5633 + endloop + endfacet + facet normal 0.0769514 0.0294661 0.996599 + outer loop + vertex 1.56748 1.56227 2.56307 + vertex 1.5676 1.56736 2.56291 + vertex 1.56252 1.56237 2.56345 + endloop + endfacet + facet normal 0.0769354 0.0285706 0.996627 + outer loop + vertex 1.56249 1.55738 2.56359 + vertex 1.56748 1.56227 2.56307 + vertex 1.56252 1.56237 2.56345 + endloop + endfacet + facet normal 0.0742305 0.0313407 0.996749 + outer loop + vertex 1.56732 1.55743 2.56323 + vertex 1.56748 1.56227 2.56307 + vertex 1.56249 1.55738 2.56359 + endloop + endfacet + facet normal 0.0743157 0.0243753 0.996937 + outer loop + vertex 1.56249 1.55242 2.56371 + vertex 1.56732 1.55743 2.56323 + vertex 1.56249 1.55738 2.56359 + endloop + endfacet + facet normal 0.0795233 0.0193239 0.996646 + outer loop + vertex 1.56746 1.55263 2.56331 + vertex 1.56732 1.55743 2.56323 + vertex 1.56249 1.55242 2.56371 + endloop + endfacet + facet normal 0.0794926 0.0200264 0.996634 + outer loop + vertex 1.56251 1.54742 2.56381 + vertex 1.56746 1.55263 2.56331 + vertex 1.56249 1.55242 2.56371 + endloop + endfacet + facet normal 0.0822763 0.0173664 0.996458 + outer loop + vertex 1.56753 1.54765 2.56339 + vertex 1.56746 1.55263 2.56331 + vertex 1.56251 1.54742 2.56381 + endloop + endfacet + facet normal 0.0822702 0.0174983 0.996456 + outer loop + vertex 1.5625 1.54239 2.5639 + vertex 1.56753 1.54765 2.56339 + vertex 1.56251 1.54742 2.56381 + endloop + endfacet + facet normal 0.0836936 0.0161271 0.996361 + outer loop + vertex 1.56753 1.54262 2.56348 + vertex 1.56753 1.54765 2.56339 + vertex 1.5625 1.54239 2.5639 + endloop + endfacet + facet normal 0.0837214 0.0155268 0.996368 + outer loop + vertex 1.56247 1.53737 2.56398 + vertex 1.56753 1.54262 2.56348 + vertex 1.5625 1.54239 2.5639 + endloop + endfacet + facet normal 0.0842688 0.0149954 0.99633 + outer loop + vertex 1.56751 1.53761 2.56355 + vertex 1.56753 1.54262 2.56348 + vertex 1.56247 1.53737 2.56398 + endloop + endfacet + facet normal 0.0843666 0.0129623 0.99635 + outer loop + vertex 1.56244 1.53237 2.56405 + vertex 1.56751 1.53761 2.56355 + vertex 1.56247 1.53737 2.56398 + endloop + endfacet + facet normal 0.0847031 0.0126342 0.996326 + outer loop + vertex 1.56751 1.53262 2.56362 + vertex 1.56751 1.53761 2.56355 + vertex 1.56244 1.53237 2.56405 + endloop + endfacet + facet normal 0.0848124 0.0104287 0.996342 + outer loop + vertex 1.56244 1.52739 2.5641 + vertex 1.56751 1.53262 2.56362 + vertex 1.56244 1.53237 2.56405 + endloop + endfacet + facet normal 0.0871003 0.00819484 0.996166 + outer loop + vertex 1.5675 1.52764 2.56366 + vertex 1.56751 1.53262 2.56362 + vertex 1.56244 1.52739 2.5641 + endloop + endfacet + facet normal 0.0871113 0.00796998 0.996167 + outer loop + vertex 1.56243 1.5224 2.56414 + vertex 1.5675 1.52764 2.56366 + vertex 1.56244 1.52739 2.5641 + endloop + endfacet + facet normal 0.0885739 0.00654223 0.996048 + outer loop + vertex 1.56751 1.52265 2.56369 + vertex 1.5675 1.52764 2.56366 + vertex 1.56243 1.5224 2.56414 + endloop + endfacet + facet normal 0.0885937 0.0061376 0.996049 + outer loop + vertex 1.56243 1.51741 2.56417 + vertex 1.56751 1.52265 2.56369 + vertex 1.56243 1.5224 2.56414 + endloop + endfacet + facet normal 0.0900698 0.00469549 0.995924 + outer loop + vertex 1.56751 1.51766 2.56371 + vertex 1.56751 1.52265 2.56369 + vertex 1.56243 1.51741 2.56417 + endloop + endfacet + facet normal 0.0901121 0.0038096 0.995924 + outer loop + vertex 1.56243 1.51242 2.56419 + vertex 1.56751 1.51766 2.56371 + vertex 1.56243 1.51741 2.56417 + endloop + endfacet + facet normal 0.091007 0.00293523 0.995846 + outer loop + vertex 1.56751 1.51266 2.56373 + vertex 1.56751 1.51766 2.56371 + vertex 1.56243 1.51242 2.56419 + endloop + endfacet + facet normal 0.0911167 0.00063361 0.99584 + outer loop + vertex 1.56244 1.50742 2.5642 + vertex 1.56751 1.51266 2.56373 + vertex 1.56243 1.51242 2.56419 + endloop + endfacet + facet normal 0.0912661 0.000487584 0.995826 + outer loop + vertex 1.56752 1.50767 2.56373 + vertex 1.56751 1.51266 2.56373 + vertex 1.56244 1.50742 2.5642 + endloop + endfacet + facet normal 0.0914333 -0.00303127 0.995807 + outer loop + vertex 1.56244 1.50243 2.56418 + vertex 1.56752 1.50767 2.56373 + vertex 1.56244 1.50742 2.5642 + endloop + endfacet + facet normal 0.0916895 -0.00328186 0.995782 + outer loop + vertex 1.56752 1.50267 2.56371 + vertex 1.56752 1.50767 2.56373 + vertex 1.56244 1.50243 2.56418 + endloop + endfacet + facet normal 0.0918606 -0.00695833 0.995748 + outer loop + vertex 1.56244 1.49744 2.56415 + vertex 1.56752 1.50267 2.56371 + vertex 1.56244 1.50243 2.56418 + endloop + endfacet + facet normal 0.0899839 -0.00512121 0.99593 + outer loop + vertex 1.56753 1.49768 2.56369 + vertex 1.56752 1.50267 2.56371 + vertex 1.56244 1.49744 2.56415 + endloop + endfacet + facet normal 0.0901995 -0.00978724 0.995876 + outer loop + vertex 1.56245 1.49245 2.5641 + vertex 1.56753 1.49768 2.56369 + vertex 1.56244 1.49744 2.56415 + endloop + endfacet + facet normal 0.0882097 -0.00783713 0.996071 + outer loop + vertex 1.56754 1.49269 2.56365 + vertex 1.56753 1.49768 2.56369 + vertex 1.56245 1.49245 2.5641 + endloop + endfacet + facet normal 0.0883925 -0.0119178 0.996014 + outer loop + vertex 1.56248 1.48749 2.56403 + vertex 1.56754 1.49269 2.56365 + vertex 1.56245 1.49245 2.5641 + endloop + endfacet + facet normal 0.0853006 -0.0088884 0.996316 + outer loop + vertex 1.56757 1.48772 2.5636 + vertex 1.56754 1.49269 2.56365 + vertex 1.56248 1.48749 2.56403 + endloop + endfacet + facet normal 0.0855363 -0.0142634 0.996233 + outer loop + vertex 1.56252 1.48253 2.56396 + vertex 1.56757 1.48772 2.5636 + vertex 1.56248 1.48749 2.56403 + endloop + endfacet + facet normal 0.0837475 -0.0125099 0.996408 + outer loop + vertex 1.56759 1.48275 2.56354 + vertex 1.56757 1.48772 2.5636 + vertex 1.56252 1.48253 2.56396 + endloop + endfacet + facet normal 0.0839069 -0.0162523 0.996341 + outer loop + vertex 1.56255 1.47756 2.56388 + vertex 1.56759 1.48275 2.56354 + vertex 1.56252 1.48253 2.56396 + endloop + endfacet + facet normal 0.0819544 -0.0143441 0.996533 + outer loop + vertex 1.56761 1.4778 2.56346 + vertex 1.56759 1.48275 2.56354 + vertex 1.56255 1.47756 2.56388 + endloop + endfacet + facet normal 0.0821972 -0.019713 0.996421 + outer loop + vertex 1.56256 1.47259 2.56378 + vertex 1.56761 1.4778 2.56346 + vertex 1.56255 1.47756 2.56388 + endloop + endfacet + facet normal 0.0809469 -0.0184951 0.996547 + outer loop + vertex 1.5676 1.47283 2.56337 + vertex 1.56761 1.4778 2.56346 + vertex 1.56256 1.47259 2.56378 + endloop + endfacet + facet normal 0.0811379 -0.0226275 0.996446 + outer loop + vertex 1.56257 1.4676 2.56366 + vertex 1.5676 1.47283 2.56337 + vertex 1.56256 1.47259 2.56378 + endloop + endfacet + facet normal 0.0778882 -0.0194787 0.996772 + outer loop + vertex 1.5676 1.46785 2.56327 + vertex 1.5676 1.47283 2.56337 + vertex 1.56257 1.4676 2.56366 + endloop + endfacet + facet normal 0.0781306 -0.0245505 0.996641 + outer loop + vertex 1.56257 1.46262 2.56354 + vertex 1.5676 1.46785 2.56327 + vertex 1.56257 1.4676 2.56366 + endloop + endfacet + facet normal 0.076748 -0.0232149 0.99678 + outer loop + vertex 1.56758 1.46286 2.56316 + vertex 1.5676 1.46785 2.56327 + vertex 1.56257 1.46262 2.56354 + endloop + endfacet + facet normal 0.0769543 -0.0278064 0.996647 + outer loop + vertex 1.56257 1.45764 2.5634 + vertex 1.56758 1.46286 2.56316 + vertex 1.56257 1.46262 2.56354 + endloop + endfacet + facet normal 0.075801 -0.0266947 0.996766 + outer loop + vertex 1.56759 1.45786 2.56302 + vertex 1.56758 1.46286 2.56316 + vertex 1.56257 1.45764 2.5634 + endloop + endfacet + facet normal 0.0760182 -0.0319174 0.996595 + outer loop + vertex 1.56261 1.45267 2.56324 + vertex 1.56759 1.45786 2.56302 + vertex 1.56257 1.45764 2.5634 + endloop + endfacet + facet normal 0.0759725 -0.0318733 0.9966 + outer loop + vertex 1.56769 1.45285 2.56286 + vertex 1.56759 1.45786 2.56302 + vertex 1.56261 1.45267 2.56324 + endloop + endfacet + facet normal 0.076068 -0.0349335 0.99649 + outer loop + vertex 1.56265 1.44772 2.56306 + vertex 1.56769 1.45285 2.56286 + vertex 1.56261 1.45267 2.56324 + endloop + endfacet + facet normal 0.0709805 -0.0299181 0.997029 + outer loop + vertex 1.56767 1.44775 2.56271 + vertex 1.56769 1.45285 2.56286 + vertex 1.56265 1.44772 2.56306 + endloop + endfacet + facet normal 0.0710133 -0.037165 0.996783 + outer loop + vertex 1.56268 1.44277 2.56288 + vertex 1.56767 1.44775 2.56271 + vertex 1.56265 1.44772 2.56306 + endloop + endfacet + facet normal 0.0613311 -0.0274226 0.997741 + outer loop + vertex 1.56753 1.4427 2.56258 + vertex 1.56767 1.44775 2.56271 + vertex 1.56268 1.44277 2.56288 + endloop + endfacet + facet normal 0.0611246 -0.0400003 0.997328 + outer loop + vertex 1.56268 1.43785 2.56268 + vertex 1.56753 1.4427 2.56258 + vertex 1.56268 1.44277 2.56288 + endloop + endfacet + facet normal 0.054201 -0.0330671 0.997982 + outer loop + vertex 1.56744 1.43777 2.56242 + vertex 1.56753 1.4427 2.56258 + vertex 1.56268 1.43785 2.56268 + endloop + endfacet + facet normal 0.0540051 -0.0425663 0.997633 + outer loop + vertex 1.56267 1.43294 2.56247 + vertex 1.56744 1.43777 2.56242 + vertex 1.56268 1.43785 2.56268 + endloop + endfacet + facet normal 0.0473839 -0.0360048 0.998228 + outer loop + vertex 1.56736 1.43282 2.56224 + vertex 1.56744 1.43777 2.56242 + vertex 1.56267 1.43294 2.56247 + endloop + endfacet + facet normal 0.0471596 -0.0442146 0.997908 + outer loop + vertex 1.56265 1.42799 2.56225 + vertex 1.56736 1.43282 2.56224 + vertex 1.56267 1.43294 2.56247 + endloop + endfacet + facet normal -0.0398362 0.0397682 0.998415 + outer loop + vertex 1.56267 1.61892 2.56076 + vertex 1.56226 1.61488 2.56091 + vertex 1.56454 1.61506 2.56099 + endloop + endfacet + facet normal 0.0362512 0.101958 0.994128 + outer loop + vertex 1.56619 1.61766 2.56088 + vertex 1.56892 1.61776 2.56077 + vertex 1.56832 1.62186 2.56037 + endloop + endfacet + facet normal 0.0780008 0.0750446 0.994125 + outer loop + vertex 1.56746 1.64219 2.55896 + vertex 1.57238 1.64708 2.55821 + vertex 1.56752 1.64725 2.55858 + endloop + endfacet + facet normal 0.077951 0.0733499 0.994255 + outer loop + vertex 1.57238 1.64708 2.55821 + vertex 1.57244 1.65224 2.55782 + vertex 1.56752 1.64725 2.55858 + endloop + endfacet + facet normal 0.0812547 0.0717731 0.994106 + outer loop + vertex 1.57228 1.64218 2.55857 + vertex 1.57238 1.64708 2.55821 + vertex 1.56746 1.64219 2.55896 + endloop + endfacet + facet normal 0.081244 0.0738469 0.993955 + outer loop + vertex 1.5674 1.63725 2.55934 + vertex 1.57228 1.64218 2.55857 + vertex 1.56746 1.64219 2.55896 + endloop + endfacet + facet normal 0.0751244 0.0761366 0.994263 + outer loop + vertex 1.56752 1.64725 2.55858 + vertex 1.57244 1.65224 2.55782 + vertex 1.56757 1.65239 2.55818 + endloop + endfacet + facet normal 0.0748866 0.0668924 0.994946 + outer loop + vertex 1.57244 1.65224 2.55782 + vertex 1.57222 1.65741 2.55749 + vertex 1.56757 1.65239 2.55818 + endloop + endfacet + facet normal 0.0921093 0.107438 0.989936 + outer loop + vertex 1.56133 1.67562 2.55623 + vertex 1.55992 1.68012 2.55587 + vertex 1.55578 1.677 2.55659 + endloop + endfacet + facet normal 0.0878435 0.0897811 0.99208 + outer loop + vertex 1.55687 1.67175 2.55697 + vertex 1.56133 1.67562 2.55623 + vertex 1.55578 1.677 2.55659 + endloop + endfacet + facet normal 0.130755 0.0982282 0.986537 + outer loop + vertex 1.55687 1.67175 2.55697 + vertex 1.55578 1.677 2.55659 + vertex 1.55197 1.67201 2.5576 + endloop + endfacet + facet normal 0.130302 0.0874805 0.987608 + outer loop + vertex 1.55235 1.66721 2.55797 + vertex 1.55687 1.67175 2.55697 + vertex 1.55197 1.67201 2.5576 + endloop + endfacet + facet normal 0.154403 0.0891353 0.983979 + outer loop + vertex 1.55235 1.66721 2.55797 + vertex 1.55197 1.67201 2.5576 + vertex 1.54759 1.6678 2.55867 + endloop + endfacet + facet normal 0.153369 0.0796672 0.984952 + outer loop + vertex 1.54762 1.6629 2.55906 + vertex 1.55235 1.66721 2.55797 + vertex 1.54759 1.6678 2.55867 + endloop + endfacet + facet normal 0.166242 0.0795852 0.982868 + outer loop + vertex 1.54762 1.6629 2.55906 + vertex 1.54759 1.6678 2.55867 + vertex 1.54268 1.6644 2.55977 + endloop + endfacet + facet normal 0.165643 0.0774839 0.983137 + outer loop + vertex 1.54357 1.659 2.56005 + vertex 1.54762 1.6629 2.55906 + vertex 1.54268 1.6644 2.55977 + endloop + endfacet + facet normal 0.178384 0.0794655 0.980747 + outer loop + vertex 1.54357 1.659 2.56005 + vertex 1.54268 1.6644 2.55977 + vertex 1.53932 1.66031 2.56071 + endloop + endfacet + facet normal 0.177943 0.0779292 0.98095 + outer loop + vertex 1.54029 1.65546 2.56092 + vertex 1.54357 1.659 2.56005 + vertex 1.53932 1.66031 2.56071 + endloop + endfacet + facet normal 0.192788 0.0807581 0.977911 + outer loop + vertex 1.53932 1.66031 2.56071 + vertex 1.53606 1.65657 2.56167 + vertex 1.54029 1.65546 2.56092 + endloop + endfacet + facet normal 0.191034 0.0734769 0.97883 + outer loop + vertex 1.53606 1.65657 2.56167 + vertex 1.53707 1.65108 2.56188 + vertex 1.54029 1.65546 2.56092 + endloop + endfacet + facet normal 0.184623 0.0783854 0.979679 + outer loop + vertex 1.54029 1.65546 2.56092 + vertex 1.53707 1.65108 2.56188 + vertex 1.5412 1.65147 2.56107 + endloop + endfacet + facet normal 0.178519 0.077042 0.980916 + outer loop + vertex 1.5412 1.65147 2.56107 + vertex 1.54454 1.65375 2.56028 + vertex 1.54029 1.65546 2.56092 + endloop + endfacet + facet normal 0.179499 0.0755778 0.980851 + outer loop + vertex 1.54364 1.64947 2.56078 + vertex 1.54454 1.65375 2.56028 + vertex 1.5412 1.65147 2.56107 + endloop + endfacet + facet normal 0.178709 0.074583 0.981071 + outer loop + vertex 1.5412 1.65147 2.56107 + vertex 1.54033 1.64687 2.56158 + vertex 1.54364 1.64947 2.56078 + endloop + endfacet + facet normal 0.178508 0.0748443 0.981088 + outer loop + vertex 1.54473 1.64539 2.56089 + vertex 1.54364 1.64947 2.56078 + vertex 1.54033 1.64687 2.56158 + endloop + endfacet + facet normal 0.178262 0.0740644 0.981192 + outer loop + vertex 1.54033 1.64687 2.56158 + vertex 1.54177 1.64099 2.56176 + vertex 1.54473 1.64539 2.56089 + endloop + endfacet + facet normal 0.17846 0.0739261 0.981166 + outer loop + vertex 1.54473 1.64539 2.56089 + vertex 1.54177 1.64099 2.56176 + vertex 1.54589 1.64136 2.56098 + endloop + endfacet + facet normal 0.167671 0.0708775 0.983292 + outer loop + vertex 1.54589 1.64136 2.56098 + vertex 1.54917 1.64367 2.56026 + vertex 1.54473 1.64539 2.56089 + endloop + endfacet + facet normal 0.169142 0.0748593 0.982745 + outer loop + vertex 1.54917 1.64367 2.56026 + vertex 1.54774 1.6494 2.56007 + vertex 1.54473 1.64539 2.56089 + endloop + endfacet + facet normal 0.140499 0.0678829 0.987751 + outer loop + vertex 1.54917 1.64367 2.56026 + vertex 1.55264 1.64789 2.55948 + vertex 1.54774 1.6494 2.56007 + endloop + endfacet + facet normal 0.14252 0.0747233 0.986967 + outer loop + vertex 1.55264 1.64789 2.55948 + vertex 1.55247 1.65271 2.55914 + vertex 1.54774 1.6494 2.56007 + endloop + endfacet + facet normal 0.138505 0.0804992 0.987085 + outer loop + vertex 1.54774 1.6494 2.56007 + vertex 1.55247 1.65271 2.55914 + vertex 1.54876 1.654 2.55955 + endloop + endfacet + facet normal 0.16674 0.0738163 0.983234 + outer loop + vertex 1.54454 1.65375 2.56028 + vertex 1.54774 1.6494 2.56007 + vertex 1.54876 1.654 2.55955 + endloop + endfacet + facet normal 0.166634 0.0753177 0.983138 + outer loop + vertex 1.54876 1.654 2.55955 + vertex 1.548 1.65798 2.55937 + vertex 1.54454 1.65375 2.56028 + endloop + endfacet + facet normal 0.166775 0.0751991 0.983123 + outer loop + vertex 1.54454 1.65375 2.56028 + vertex 1.548 1.65798 2.55937 + vertex 1.54357 1.659 2.56005 + endloop + endfacet + facet normal 0.142629 0.0709144 0.987233 + outer loop + vertex 1.54876 1.654 2.55955 + vertex 1.55259 1.65745 2.55875 + vertex 1.548 1.65798 2.55937 + endloop + endfacet + facet normal 0.143532 0.0797936 0.986424 + outer loop + vertex 1.55259 1.65745 2.55875 + vertex 1.55249 1.66227 2.55837 + vertex 1.548 1.65798 2.55937 + endloop + endfacet + facet normal 0.148185 0.074852 0.986123 + outer loop + vertex 1.548 1.65798 2.55937 + vertex 1.55249 1.66227 2.55837 + vertex 1.54762 1.6629 2.55906 + endloop + endfacet + facet normal 0.137298 0.0768935 0.987541 + outer loop + vertex 1.55247 1.65271 2.55914 + vertex 1.55259 1.65745 2.55875 + vertex 1.54876 1.654 2.55955 + endloop + endfacet + facet normal 0.100517 0.0781655 0.99186 + outer loop + vertex 1.55247 1.65271 2.55914 + vertex 1.55748 1.65717 2.55828 + vertex 1.55259 1.65745 2.55875 + endloop + endfacet + facet normal 0.100983 0.0876142 0.991023 + outer loop + vertex 1.55748 1.65717 2.55828 + vertex 1.55754 1.66217 2.55783 + vertex 1.55259 1.65745 2.55875 + endloop + endfacet + facet normal 0.10871 0.0794684 0.990892 + outer loop + vertex 1.55259 1.65745 2.55875 + vertex 1.55754 1.66217 2.55783 + vertex 1.55249 1.66227 2.55837 + endloop + endfacet + facet normal 0.108882 0.095413 0.989465 + outer loop + vertex 1.55754 1.66217 2.55783 + vertex 1.5573 1.66698 2.55739 + vertex 1.55249 1.66227 2.55837 + endloop + endfacet + facet normal 0.0649699 0.0935762 0.99349 + outer loop + vertex 1.55754 1.66217 2.55783 + vertex 1.56228 1.66725 2.55704 + vertex 1.5573 1.66698 2.55739 + endloop + endfacet + facet normal 0.0639807 0.109824 0.99189 + outer loop + vertex 1.56228 1.66725 2.55704 + vertex 1.56109 1.67106 2.55669 + vertex 1.5573 1.66698 2.55739 + endloop + endfacet + facet normal 0.0811774 0.0939158 0.992265 + outer loop + vertex 1.5573 1.66698 2.55739 + vertex 1.56109 1.67106 2.55669 + vertex 1.55687 1.67175 2.55697 + endloop + endfacet + facet normal 0.0595422 0.0986183 0.993342 + outer loop + vertex 1.56267 1.66231 2.55751 + vertex 1.56228 1.66725 2.55704 + vertex 1.55754 1.66217 2.55783 + endloop + endfacet + facet normal 0.0598821 0.0884008 0.994283 + outer loop + vertex 1.55748 1.65717 2.55828 + vertex 1.56267 1.66231 2.55751 + vertex 1.55754 1.66217 2.55783 + endloop + endfacet + facet normal 0.0569709 0.0913275 0.99419 + outer loop + vertex 1.56261 1.65726 2.55797 + vertex 1.56267 1.66231 2.55751 + vertex 1.55748 1.65717 2.55828 + endloop + endfacet + facet normal 0.0571745 0.0824767 0.994952 + outer loop + vertex 1.55734 1.65217 2.5587 + vertex 1.56261 1.65726 2.55797 + vertex 1.55748 1.65717 2.55828 + endloop + endfacet + facet normal 0.0558322 0.0838603 0.994912 + outer loop + vertex 1.56248 1.65221 2.55841 + vertex 1.56261 1.65726 2.55797 + vertex 1.55734 1.65217 2.5587 + endloop + endfacet + facet normal 0.0559086 0.0768012 0.995478 + outer loop + vertex 1.5574 1.64735 2.55907 + vertex 1.56248 1.65221 2.55841 + vertex 1.55734 1.65217 2.5587 + endloop + endfacet + facet normal 0.0939266 0.0769826 0.992598 + outer loop + vertex 1.5574 1.64735 2.55907 + vertex 1.55734 1.65217 2.5587 + vertex 1.55264 1.64789 2.55948 + endloop + endfacet + facet normal 0.0926696 0.0652122 0.993559 + outer loop + vertex 1.55353 1.64384 2.55966 + vertex 1.5574 1.64735 2.55907 + vertex 1.55264 1.64789 2.55948 + endloop + endfacet + facet normal 0.0824425 0.0765005 0.993655 + outer loop + vertex 1.55739 1.64261 2.55943 + vertex 1.5574 1.64735 2.55907 + vertex 1.55353 1.64384 2.55966 + endloop + endfacet + facet normal 0.0844155 0.082827 0.992982 + outer loop + vertex 1.55262 1.63927 2.56012 + vertex 1.55739 1.64261 2.55943 + vertex 1.55353 1.64384 2.55966 + endloop + endfacet + facet normal 0.133314 0.072647 0.988408 + outer loop + vertex 1.54917 1.64367 2.56026 + vertex 1.55262 1.63927 2.56012 + vertex 1.55353 1.64384 2.55966 + endloop + endfacet + facet normal 0.137272 0.0757799 0.98763 + outer loop + vertex 1.54845 1.63931 2.56069 + vertex 1.55262 1.63927 2.56012 + vertex 1.54917 1.64367 2.56026 + endloop + endfacet + facet normal 0.137273 0.069887 0.988065 + outer loop + vertex 1.54845 1.63931 2.56069 + vertex 1.54965 1.63529 2.56081 + vertex 1.55262 1.63927 2.56012 + endloop + endfacet + facet normal 0.12883 0.0763162 0.988726 + outer loop + vertex 1.55416 1.63365 2.56035 + vertex 1.55262 1.63927 2.56012 + vertex 1.54965 1.63529 2.56081 + endloop + endfacet + facet normal 0.123302 0.0606137 0.990516 + outer loop + vertex 1.55086 1.63137 2.5609 + vertex 1.55416 1.63365 2.56035 + vertex 1.54965 1.63529 2.56081 + endloop + endfacet + facet normal 0.163807 0.0729195 0.983794 + outer loop + vertex 1.54965 1.63529 2.56081 + vertex 1.54671 1.63096 2.56162 + vertex 1.55086 1.63137 2.5609 + endloop + endfacet + facet normal 0.16401 0.0710345 0.983898 + outer loop + vertex 1.55086 1.63137 2.5609 + vertex 1.54671 1.63096 2.56162 + vertex 1.55017 1.62684 2.56134 + endloop + endfacet + facet normal 0.13282 0.0761732 0.988209 + outer loop + vertex 1.55086 1.63137 2.5609 + vertex 1.55017 1.62684 2.56134 + vertex 1.55345 1.6294 2.5607 + endloop + endfacet + facet normal 0.164644 0.0715778 0.983753 + outer loop + vertex 1.54671 1.63096 2.56162 + vertex 1.54583 1.62602 2.56213 + vertex 1.55017 1.62684 2.56134 + endloop + endfacet + facet normal 0.165686 0.0662615 0.98395 + outer loop + vertex 1.54682 1.62197 2.56223 + vertex 1.55017 1.62684 2.56134 + vertex 1.54583 1.62602 2.56213 + endloop + endfacet + facet normal 0.171263 0.0675926 0.982904 + outer loop + vertex 1.54682 1.62197 2.56223 + vertex 1.54583 1.62602 2.56213 + vertex 1.54223 1.62228 2.56301 + endloop + endfacet + facet normal 0.171007 0.0628952 0.98326 + outer loop + vertex 1.54253 1.61749 2.56327 + vertex 1.54682 1.62197 2.56223 + vertex 1.54223 1.62228 2.56301 + endloop + endfacet + facet normal 0.176985 0.0632044 0.982182 + outer loop + vertex 1.54253 1.61749 2.56327 + vertex 1.54223 1.62228 2.56301 + vertex 1.5378 1.61811 2.56408 + endloop + endfacet + facet normal 0.176478 0.0588006 0.982547 + outer loop + vertex 1.53828 1.61322 2.56429 + vertex 1.54253 1.61749 2.56327 + vertex 1.5378 1.61811 2.56408 + endloop + endfacet + facet normal 0.191162 0.0601371 0.979715 + outer loop + vertex 1.53828 1.61322 2.56429 + vertex 1.5378 1.61811 2.56408 + vertex 1.53378 1.61419 2.5651 + endloop + endfacet + facet normal 0.190127 0.0549092 0.980223 + outer loop + vertex 1.53475 1.60889 2.56521 + vertex 1.53828 1.61322 2.56429 + vertex 1.53378 1.61419 2.5651 + endloop + endfacet + facet normal 0.2129 0.05896 0.975293 + outer loop + vertex 1.53475 1.60889 2.56521 + vertex 1.53378 1.61419 2.5651 + vertex 1.53041 1.61065 2.56605 + endloop + endfacet + facet normal 0.212085 0.0568062 0.975599 + outer loop + vertex 1.53126 1.60662 2.5661 + vertex 1.53475 1.60889 2.56521 + vertex 1.53041 1.61065 2.56605 + endloop + endfacet + facet normal 0.216197 0.0576693 0.974645 + outer loop + vertex 1.53041 1.61065 2.56605 + vertex 1.52704 1.60631 2.56706 + vertex 1.53126 1.60662 2.5661 + endloop + endfacet + facet normal 0.21583 0.0621544 0.974451 + outer loop + vertex 1.53126 1.60662 2.5661 + vertex 1.52704 1.60631 2.56706 + vertex 1.53014 1.60213 2.56664 + endloop + endfacet + facet normal 0.222812 0.0602218 0.973 + outer loop + vertex 1.53126 1.60662 2.5661 + vertex 1.53014 1.60213 2.56664 + vertex 1.53363 1.60458 2.56569 + endloop + endfacet + facet normal 0.225144 0.0567637 0.972671 + outer loop + vertex 1.53431 1.60054 2.56577 + vertex 1.53363 1.60458 2.56569 + vertex 1.53014 1.60213 2.56664 + endloop + endfacet + facet normal 0.222443 0.0490897 0.973709 + outer loop + vertex 1.53014 1.60213 2.56664 + vertex 1.53097 1.59681 2.56672 + vertex 1.53431 1.60054 2.56577 + endloop + endfacet + facet normal 0.220312 0.0510977 0.97409 + outer loop + vertex 1.53431 1.60054 2.56577 + vertex 1.53097 1.59681 2.56672 + vertex 1.53498 1.5956 2.56587 + endloop + endfacet + facet normal 0.196558 0.0480211 0.979316 + outer loop + vertex 1.53498 1.5956 2.56587 + vertex 1.53837 1.59921 2.56502 + vertex 1.53431 1.60054 2.56577 + endloop + endfacet + facet normal 0.197545 0.0512363 0.978954 + outer loop + vertex 1.53837 1.59921 2.56502 + vertex 1.53774 1.60464 2.56486 + vertex 1.53431 1.60054 2.56577 + endloop + endfacet + facet normal 0.177612 0.0490595 0.982877 + outer loop + vertex 1.53837 1.59921 2.56502 + vertex 1.54256 1.60307 2.56407 + vertex 1.53774 1.60464 2.56486 + endloop + endfacet + facet normal 0.177977 0.0502426 0.982751 + outer loop + vertex 1.54256 1.60307 2.56407 + vertex 1.5427 1.60805 2.56379 + vertex 1.53774 1.60464 2.56486 + endloop + endfacet + facet normal 0.174928 0.0547702 0.983057 + outer loop + vertex 1.53774 1.60464 2.56486 + vertex 1.5427 1.60805 2.56379 + vertex 1.53905 1.60926 2.56437 + endloop + endfacet + facet normal 0.188259 0.0507512 0.980807 + outer loop + vertex 1.53475 1.60889 2.56521 + vertex 1.53774 1.60464 2.56486 + vertex 1.53905 1.60926 2.56437 + endloop + endfacet + facet normal 0.196455 0.0566881 0.978873 + outer loop + vertex 1.53363 1.60458 2.56569 + vertex 1.53774 1.60464 2.56486 + vertex 1.53475 1.60889 2.56521 + endloop + endfacet + facet normal 0.174962 0.0548761 0.983045 + outer loop + vertex 1.5427 1.60805 2.56379 + vertex 1.54278 1.61275 2.56351 + vertex 1.53905 1.60926 2.56437 + endloop + endfacet + facet normal 0.175203 0.0546108 0.983017 + outer loop + vertex 1.53905 1.60926 2.56437 + vertex 1.54278 1.61275 2.56351 + vertex 1.53828 1.61322 2.56429 + endloop + endfacet + facet normal 0.168892 0.0550466 0.984096 + outer loop + vertex 1.5427 1.60805 2.56379 + vertex 1.54729 1.61224 2.56276 + vertex 1.54278 1.61275 2.56351 + endloop + endfacet + facet normal 0.169365 0.0597609 0.98374 + outer loop + vertex 1.54729 1.61224 2.56276 + vertex 1.54719 1.61705 2.56249 + vertex 1.54278 1.61275 2.56351 + endloop + endfacet + facet normal 0.169739 0.0593678 0.983699 + outer loop + vertex 1.54278 1.61275 2.56351 + vertex 1.54719 1.61705 2.56249 + vertex 1.54253 1.61749 2.56327 + endloop + endfacet + facet normal 0.161952 0.0596756 0.984993 + outer loop + vertex 1.54729 1.61224 2.56276 + vertex 1.55098 1.61606 2.56193 + vertex 1.54719 1.61705 2.56249 + endloop + endfacet + facet normal 0.161909 0.0594986 0.98501 + outer loop + vertex 1.55098 1.61606 2.56193 + vertex 1.55179 1.62107 2.56149 + vertex 1.54719 1.61705 2.56249 + endloop + endfacet + facet normal 0.158888 0.0630266 0.985283 + outer loop + vertex 1.54719 1.61705 2.56249 + vertex 1.55179 1.62107 2.56149 + vertex 1.54682 1.62197 2.56223 + endloop + endfacet + facet normal 0.135789 0.0640703 0.988664 + outer loop + vertex 1.55179 1.62107 2.56149 + vertex 1.55098 1.61606 2.56193 + vertex 1.55537 1.6169 2.56127 + endloop + endfacet + facet normal 0.127703 0.0570581 0.99017 + outer loop + vertex 1.55598 1.62146 2.56093 + vertex 1.55179 1.62107 2.56149 + vertex 1.55537 1.6169 2.56127 + endloop + endfacet + facet normal 0.0861722 0.0630113 0.994286 + outer loop + vertex 1.55598 1.62146 2.56093 + vertex 1.55537 1.6169 2.56127 + vertex 1.55857 1.61939 2.56083 + endloop + endfacet + facet normal 0.0663574 0.0380757 0.997069 + outer loop + vertex 1.55857 1.61939 2.56083 + vertex 1.55925 1.6237 2.56062 + vertex 1.55598 1.62146 2.56093 + endloop + endfacet + facet normal 0.0642762 0.041121 0.997085 + outer loop + vertex 1.55598 1.62146 2.56093 + vertex 1.55925 1.6237 2.56062 + vertex 1.5547 1.62542 2.56085 + endloop + endfacet + facet normal 0.0725991 0.0632759 0.995352 + outer loop + vertex 1.55925 1.6237 2.56062 + vertex 1.55768 1.62938 2.56038 + vertex 1.5547 1.62542 2.56085 + endloop + endfacet + facet normal 0.077106 0.059877 0.995223 + outer loop + vertex 1.55345 1.6294 2.5607 + vertex 1.5547 1.62542 2.56085 + vertex 1.55768 1.62938 2.56038 + endloop + endfacet + facet normal 0.0770908 0.0699626 0.994566 + outer loop + vertex 1.55345 1.6294 2.5607 + vertex 1.55768 1.62938 2.56038 + vertex 1.55416 1.63365 2.56035 + endloop + endfacet + facet normal 0.072737 0.0663821 0.99514 + outer loop + vertex 1.55416 1.63365 2.56035 + vertex 1.55768 1.62938 2.56038 + vertex 1.5586 1.6339 2.56001 + endloop + endfacet + facet normal 0.072236 0.0746358 0.994591 + outer loop + vertex 1.5586 1.6339 2.56001 + vertex 1.55767 1.63786 2.55978 + vertex 1.55416 1.63365 2.56035 + endloop + endfacet + facet normal 0.0844791 0.0643971 0.994342 + outer loop + vertex 1.55416 1.63365 2.56035 + vertex 1.55767 1.63786 2.55978 + vertex 1.55262 1.63927 2.56012 + endloop + endfacet + facet normal 0.049345 0.0693479 0.996371 + outer loop + vertex 1.5586 1.6339 2.56001 + vertex 1.56249 1.63741 2.55957 + vertex 1.55767 1.63786 2.55978 + endloop + endfacet + facet normal 0.0500115 0.0767773 0.995793 + outer loop + vertex 1.56249 1.63741 2.55957 + vertex 1.56236 1.6422 2.55921 + vertex 1.55767 1.63786 2.55978 + endloop + endfacet + facet normal 0.05107 0.0756361 0.995827 + outer loop + vertex 1.55767 1.63786 2.55978 + vertex 1.56236 1.6422 2.55921 + vertex 1.55739 1.64261 2.55943 + endloop + endfacet + facet normal 0.0512918 0.07839 0.995602 + outer loop + vertex 1.56236 1.6422 2.55921 + vertex 1.56237 1.64716 2.55882 + vertex 1.55739 1.64261 2.55943 + endloop + endfacet + facet normal 0.0441601 0.0750587 0.996201 + outer loop + vertex 1.56248 1.63276 2.55992 + vertex 1.56249 1.63741 2.55957 + vertex 1.5586 1.6339 2.56001 + endloop + endfacet + facet normal 0.0434192 0.0725129 0.996422 + outer loop + vertex 1.55768 1.62938 2.56038 + vertex 1.56248 1.63276 2.55992 + vertex 1.5586 1.6339 2.56001 + endloop + endfacet + facet normal 0.0445883 0.0708596 0.996489 + outer loop + vertex 1.56274 1.628 2.56025 + vertex 1.56248 1.63276 2.55992 + vertex 1.55768 1.62938 2.56038 + endloop + endfacet + facet normal 0.132212 0.0769578 0.988229 + outer loop + vertex 1.5547 1.62542 2.56085 + vertex 1.55345 1.6294 2.5607 + vertex 1.55017 1.62684 2.56134 + endloop + endfacet + facet normal 0.127464 0.0612222 0.989952 + outer loop + vertex 1.55017 1.62684 2.56134 + vertex 1.55179 1.62107 2.56149 + vertex 1.5547 1.62542 2.56085 + endloop + endfacet + facet normal 0.0401223 0.0543683 0.997715 + outer loop + vertex 1.55925 1.6237 2.56062 + vertex 1.56274 1.628 2.56025 + vertex 1.55768 1.62938 2.56038 + endloop + endfacet + facet normal 0.0308771 0.0618517 0.997608 + outer loop + vertex 1.56383 1.62381 2.56048 + vertex 1.56274 1.628 2.56025 + vertex 1.55925 1.6237 2.56062 + endloop + endfacet + facet normal 0.0311629 0.0511116 0.998207 + outer loop + vertex 1.55925 1.6237 2.56062 + vertex 1.56267 1.61892 2.56076 + vertex 1.56383 1.62381 2.56048 + endloop + endfacet + facet normal 0.0227276 0.0450981 0.998724 + outer loop + vertex 1.55857 1.61939 2.56083 + vertex 1.56267 1.61892 2.56076 + vertex 1.55925 1.6237 2.56062 + endloop + endfacet + facet normal 0.0220091 0.0388754 0.999002 + outer loop + vertex 1.55857 1.61939 2.56083 + vertex 1.55962 1.6157 2.56095 + vertex 1.56267 1.61892 2.56076 + endloop + endfacet + facet normal 0.0284059 0.0328236 0.999057 + outer loop + vertex 1.56226 1.61488 2.56091 + vertex 1.56267 1.61892 2.56076 + vertex 1.55962 1.6157 2.56095 + endloop + endfacet + facet normal 0.032683 0.0466979 0.998374 + outer loop + vertex 1.56098 1.61258 2.56106 + vertex 1.56226 1.61488 2.56091 + vertex 1.55962 1.6157 2.56095 + endloop + endfacet + facet normal 0.0793921 0.0668949 0.994596 + outer loop + vertex 1.55962 1.6157 2.56095 + vertex 1.55719 1.61135 2.56144 + vertex 1.56098 1.61258 2.56106 + endloop + endfacet + facet normal 0.07077 0.0930585 0.993142 + outer loop + vertex 1.56098 1.61258 2.56106 + vertex 1.55719 1.61135 2.56144 + vertex 1.56154 1.60844 2.5614 + endloop + endfacet + facet normal 0.00387715 0.0842828 0.996434 + outer loop + vertex 1.56098 1.61258 2.56106 + vertex 1.56154 1.60844 2.5614 + vertex 1.56317 1.61251 2.56105 + endloop + endfacet + facet normal 0.0572502 0.0728582 0.995698 + outer loop + vertex 1.55719 1.61135 2.56144 + vertex 1.55645 1.60625 2.56186 + vertex 1.56154 1.60844 2.5614 + endloop + endfacet + facet normal 0.0618187 0.0622998 0.996141 + outer loop + vertex 1.55741 1.60232 2.56204 + vertex 1.56154 1.60844 2.5614 + vertex 1.55645 1.60625 2.56186 + endloop + endfacet + facet normal 0.0999488 0.0715037 0.99242 + outer loop + vertex 1.55741 1.60232 2.56204 + vertex 1.55645 1.60625 2.56186 + vertex 1.55236 1.60197 2.56258 + endloop + endfacet + facet normal 0.101263 0.0543264 0.993375 + outer loop + vertex 1.55248 1.59712 2.56283 + vertex 1.55741 1.60232 2.56204 + vertex 1.55236 1.60197 2.56258 + endloop + endfacet + facet normal 0.13921 0.0549967 0.988734 + outer loop + vertex 1.55248 1.59712 2.56283 + vertex 1.55236 1.60197 2.56258 + vertex 1.54744 1.59728 2.56353 + endloop + endfacet + facet normal 0.138981 0.0454988 0.989249 + outer loop + vertex 1.54754 1.5925 2.56374 + vertex 1.55248 1.59712 2.56283 + vertex 1.54744 1.59728 2.56353 + endloop + endfacet + facet normal 0.165914 0.0458884 0.985072 + outer loop + vertex 1.54754 1.5925 2.56374 + vertex 1.54744 1.59728 2.56353 + vertex 1.54307 1.59309 2.56446 + endloop + endfacet + facet normal 0.165717 0.0442774 0.985179 + outer loop + vertex 1.54378 1.58915 2.56452 + vertex 1.54754 1.5925 2.56374 + vertex 1.54307 1.59309 2.56446 + endloop + endfacet + facet normal 0.183053 0.0473425 0.981962 + outer loop + vertex 1.54378 1.58915 2.56452 + vertex 1.54307 1.59309 2.56446 + vertex 1.5397 1.58894 2.56529 + endloop + endfacet + facet normal 0.18312 0.0461858 0.982005 + outer loop + vertex 1.5397 1.58894 2.56529 + vertex 1.54259 1.58465 2.56495 + vertex 1.54378 1.58915 2.56452 + endloop + endfacet + facet normal 0.16783 0.0504692 0.984523 + outer loop + vertex 1.54259 1.58465 2.56495 + vertex 1.54743 1.58784 2.56396 + vertex 1.54378 1.58915 2.56452 + endloop + endfacet + facet normal 0.173486 0.0417006 0.983953 + outer loop + vertex 1.54735 1.58298 2.56418 + vertex 1.54743 1.58784 2.56396 + vertex 1.54259 1.58465 2.56495 + endloop + endfacet + facet normal 0.172551 0.0389186 0.984231 + outer loop + vertex 1.5432 1.57926 2.56506 + vertex 1.54735 1.58298 2.56418 + vertex 1.54259 1.58465 2.56495 + endloop + endfacet + facet normal 0.189978 0.0408236 0.980939 + outer loop + vertex 1.5432 1.57926 2.56506 + vertex 1.54259 1.58465 2.56495 + vertex 1.53927 1.58064 2.56576 + endloop + endfacet + facet normal 0.188721 0.0370402 0.981332 + outer loop + vertex 1.53976 1.57566 2.56586 + vertex 1.5432 1.57926 2.56506 + vertex 1.53927 1.58064 2.56576 + endloop + endfacet + facet normal 0.185918 0.0367789 0.981877 + outer loop + vertex 1.53927 1.58064 2.56576 + vertex 1.53595 1.57683 2.56653 + vertex 1.53976 1.57566 2.56586 + endloop + endfacet + facet normal 0.18538 0.0349329 0.982046 + outer loop + vertex 1.53595 1.57683 2.56653 + vertex 1.53628 1.57175 2.56665 + vertex 1.53976 1.57566 2.56586 + endloop + endfacet + facet normal 0.188408 0.0321394 0.981565 + outer loop + vertex 1.53976 1.57566 2.56586 + vertex 1.53628 1.57175 2.56665 + vertex 1.5401 1.57058 2.56596 + endloop + endfacet + facet normal 0.19118 0.0323151 0.981023 + outer loop + vertex 1.5401 1.57058 2.56596 + vertex 1.54353 1.57418 2.56517 + vertex 1.53976 1.57566 2.56586 + endloop + endfacet + facet normal 0.192798 0.0307118 0.980758 + outer loop + vertex 1.54389 1.5691 2.56526 + vertex 1.54353 1.57418 2.56517 + vertex 1.5401 1.57058 2.56596 + endloop + endfacet + facet normal 0.193012 0.031285 0.980698 + outer loop + vertex 1.54057 1.56554 2.56603 + vertex 1.54389 1.5691 2.56526 + vertex 1.5401 1.57058 2.56596 + endloop + endfacet + facet normal 0.190394 0.0310469 0.981217 + outer loop + vertex 1.5401 1.57058 2.56596 + vertex 1.53658 1.5666 2.56677 + vertex 1.54057 1.56554 2.56603 + endloop + endfacet + facet normal 0.191149 0.0340549 0.98097 + outer loop + vertex 1.53658 1.5666 2.56677 + vertex 1.53717 1.56108 2.56684 + vertex 1.54057 1.56554 2.56603 + endloop + endfacet + facet normal 0.191254 0.0339717 0.980952 + outer loop + vertex 1.54057 1.56554 2.56603 + vertex 1.53717 1.56108 2.56684 + vertex 1.5412 1.56148 2.56604 + endloop + endfacet + facet normal 0.192635 0.0341845 0.980675 + outer loop + vertex 1.5412 1.56148 2.56604 + vertex 1.54458 1.56379 2.5653 + vertex 1.54057 1.56554 2.56603 + endloop + endfacet + facet normal 0.192769 0.0339809 0.980656 + outer loop + vertex 1.54346 1.55947 2.56567 + vertex 1.54458 1.56379 2.5653 + vertex 1.5412 1.56148 2.56604 + endloop + endfacet + facet normal 0.194777 0.0363255 0.980175 + outer loop + vertex 1.5412 1.56148 2.56604 + vertex 1.54009 1.55697 2.56643 + vertex 1.54346 1.55947 2.56567 + endloop + endfacet + facet normal 0.19376 0.0377411 0.980323 + outer loop + vertex 1.54414 1.55545 2.56569 + vertex 1.54346 1.55947 2.56567 + vertex 1.54009 1.55697 2.56643 + endloop + endfacet + facet normal 0.192417 0.0339574 0.980726 + outer loop + vertex 1.54009 1.55697 2.56643 + vertex 1.54085 1.55175 2.56646 + vertex 1.54414 1.55545 2.56569 + endloop + endfacet + facet normal 0.194548 0.0319924 0.980371 + outer loop + vertex 1.54414 1.55545 2.56569 + vertex 1.54085 1.55175 2.56646 + vertex 1.54467 1.55059 2.56574 + endloop + endfacet + facet normal 0.174329 0.0298028 0.984236 + outer loop + vertex 1.54467 1.55059 2.56574 + vertex 1.54816 1.55416 2.56502 + vertex 1.54414 1.55545 2.56569 + endloop + endfacet + facet normal 0.175992 0.0281291 0.98399 + outer loop + vertex 1.5485 1.54921 2.5651 + vertex 1.54816 1.55416 2.56502 + vertex 1.54467 1.55059 2.56574 + endloop + endfacet + facet normal 0.174709 0.0244249 0.984317 + outer loop + vertex 1.54494 1.54568 2.56582 + vertex 1.5485 1.54921 2.5651 + vertex 1.54467 1.55059 2.56574 + endloop + endfacet + facet normal 0.19574 0.0255151 0.980324 + outer loop + vertex 1.54467 1.55059 2.56574 + vertex 1.5412 1.5468 2.56653 + vertex 1.54494 1.54568 2.56582 + endloop + endfacet + facet normal 0.194227 0.0201642 0.980749 + outer loop + vertex 1.5412 1.5468 2.56653 + vertex 1.54132 1.54183 2.56661 + vertex 1.54494 1.54568 2.56582 + endloop + endfacet + facet normal 0.196175 0.0182592 0.980399 + outer loop + vertex 1.54494 1.54568 2.56582 + vertex 1.54132 1.54183 2.56661 + vertex 1.54506 1.54074 2.56588 + endloop + endfacet + facet normal 0.176062 0.017836 0.984217 + outer loop + vertex 1.54506 1.54074 2.56588 + vertex 1.54866 1.54427 2.56518 + vertex 1.54494 1.54568 2.56582 + endloop + endfacet + facet normal 0.177688 0.0161318 0.983955 + outer loop + vertex 1.54873 1.5393 2.56525 + vertex 1.54866 1.54427 2.56518 + vertex 1.54506 1.54074 2.56588 + endloop + endfacet + facet normal 0.176432 0.0127873 0.98423 + outer loop + vertex 1.54514 1.53576 2.56594 + vertex 1.54873 1.5393 2.56525 + vertex 1.54506 1.54074 2.56588 + endloop + endfacet + facet normal 0.196543 0.0130618 0.980408 + outer loop + vertex 1.54506 1.54074 2.56588 + vertex 1.54138 1.53685 2.56667 + vertex 1.54514 1.53576 2.56594 + endloop + endfacet + facet normal 0.19599 0.0110673 0.980543 + outer loop + vertex 1.54138 1.53685 2.56667 + vertex 1.54144 1.53185 2.56672 + vertex 1.54514 1.53576 2.56594 + endloop + endfacet + facet normal 0.196708 0.0103588 0.980407 + outer loop + vertex 1.54514 1.53576 2.56594 + vertex 1.54144 1.53185 2.56672 + vertex 1.54522 1.53076 2.56597 + endloop + endfacet + facet normal 0.176046 0.0100513 0.984331 + outer loop + vertex 1.54522 1.53076 2.56597 + vertex 1.5488 1.53431 2.5653 + vertex 1.54514 1.53576 2.56594 + endloop + endfacet + facet normal 0.176982 0.0090781 0.984172 + outer loop + vertex 1.54887 1.52932 2.56533 + vertex 1.5488 1.53431 2.5653 + vertex 1.54522 1.53076 2.56597 + endloop + endfacet + facet normal 0.176663 0.00824265 0.984237 + outer loop + vertex 1.5453 1.52577 2.566 + vertex 1.54887 1.52932 2.56533 + vertex 1.54522 1.53076 2.56597 + endloop + endfacet + facet normal 0.19749 0.00856116 0.980267 + outer loop + vertex 1.54522 1.53076 2.56597 + vertex 1.54151 1.52686 2.56675 + vertex 1.5453 1.52577 2.566 + endloop + endfacet + facet normal 0.197304 0.00788636 0.980311 + outer loop + vertex 1.54151 1.52686 2.56675 + vertex 1.54156 1.52186 2.56678 + vertex 1.5453 1.52577 2.566 + endloop + endfacet + facet normal 0.197814 0.00737864 0.980212 + outer loop + vertex 1.5453 1.52577 2.566 + vertex 1.54156 1.52186 2.56678 + vertex 1.54537 1.52078 2.56602 + endloop + endfacet + facet normal 0.177148 0.00710613 0.984159 + outer loop + vertex 1.54537 1.52078 2.56602 + vertex 1.54893 1.52433 2.56536 + vertex 1.5453 1.52577 2.566 + endloop + endfacet + facet normal 0.17791 0.0063162 0.984026 + outer loop + vertex 1.54898 1.51934 2.56538 + vertex 1.54893 1.52433 2.56536 + vertex 1.54537 1.52078 2.56602 + endloop + endfacet + facet normal 0.177486 0.00521434 0.98411 + outer loop + vertex 1.54541 1.51578 2.56604 + vertex 1.54898 1.51934 2.56538 + vertex 1.54537 1.52078 2.56602 + endloop + endfacet + facet normal 0.198007 0.00537899 0.980186 + outer loop + vertex 1.54537 1.52078 2.56602 + vertex 1.54162 1.51688 2.5668 + vertex 1.54541 1.51578 2.56604 + endloop + endfacet + facet normal 0.197243 0.00261575 0.980351 + outer loop + vertex 1.54162 1.51688 2.5668 + vertex 1.54164 1.51188 2.56681 + vertex 1.54541 1.51578 2.56604 + endloop + endfacet + facet normal 0.197739 0.00211735 0.980252 + outer loop + vertex 1.54541 1.51578 2.56604 + vertex 1.54164 1.51188 2.56681 + vertex 1.54544 1.5108 2.56605 + endloop + endfacet + facet normal 0.176996 0.00200751 0.98421 + outer loop + vertex 1.54544 1.5108 2.56605 + vertex 1.54901 1.51435 2.5654 + vertex 1.54541 1.51578 2.56604 + endloop + endfacet + facet normal 0.177427 0.00156099 0.984133 + outer loop + vertex 1.54902 1.50935 2.5654 + vertex 1.54901 1.51435 2.5654 + vertex 1.54544 1.5108 2.56605 + endloop + endfacet + facet normal 0.175803 -0.00259555 0.984422 + outer loop + vertex 1.54543 1.5058 2.56603 + vertex 1.54902 1.50935 2.5654 + vertex 1.54544 1.5108 2.56605 + endloop + endfacet + facet normal 0.198397 -0.00262323 0.980118 + outer loop + vertex 1.54544 1.5108 2.56605 + vertex 1.54166 1.50689 2.5668 + vertex 1.54543 1.5058 2.56603 + endloop + endfacet + facet normal 0.19753 -0.00572308 0.98028 + outer loop + vertex 1.54166 1.50689 2.5668 + vertex 1.54164 1.5019 2.56678 + vertex 1.54543 1.5058 2.56603 + endloop + endfacet + facet normal 0.198947 -0.00715518 0.979984 + outer loop + vertex 1.54543 1.5058 2.56603 + vertex 1.54164 1.5019 2.56678 + vertex 1.54539 1.50081 2.56601 + endloop + endfacet + facet normal 0.174294 -0.00697349 0.984669 + outer loop + vertex 1.54539 1.50081 2.56601 + vertex 1.549 1.50436 2.56539 + vertex 1.54543 1.5058 2.56603 + endloop + endfacet + facet normal 0.175277 -0.00800273 0.984487 + outer loop + vertex 1.54894 1.49937 2.56536 + vertex 1.549 1.50436 2.56539 + vertex 1.54539 1.50081 2.56601 + endloop + endfacet + facet normal 0.174009 -0.0112098 0.98468 + outer loop + vertex 1.5453 1.49581 2.56597 + vertex 1.54894 1.49937 2.56536 + vertex 1.54539 1.50081 2.56601 + endloop + endfacet + facet normal 0.199893 -0.0116344 0.979749 + outer loop + vertex 1.54539 1.50081 2.56601 + vertex 1.54159 1.4969 2.56674 + vertex 1.5453 1.49581 2.56597 + endloop + endfacet + facet normal 0.199517 -0.0129606 0.979809 + outer loop + vertex 1.54159 1.4969 2.56674 + vertex 1.54151 1.49191 2.56669 + vertex 1.5453 1.49581 2.56597 + endloop + endfacet + facet normal 0.200675 -0.0141327 0.979556 + outer loop + vertex 1.5453 1.49581 2.56597 + vertex 1.54151 1.49191 2.56669 + vertex 1.54519 1.49082 2.56592 + endloop + endfacet + facet normal 0.174713 -0.013606 0.984525 + outer loop + vertex 1.54519 1.49082 2.56592 + vertex 1.54884 1.49438 2.56532 + vertex 1.5453 1.49581 2.56597 + endloop + endfacet + facet normal 0.174488 -0.0133685 0.984569 + outer loop + vertex 1.54875 1.48939 2.56527 + vertex 1.54884 1.49438 2.56532 + vertex 1.54519 1.49082 2.56592 + endloop + endfacet + facet normal 0.174119 -0.0143108 0.984621 + outer loop + vertex 1.54509 1.48582 2.56586 + vertex 1.54875 1.48939 2.56527 + vertex 1.54519 1.49082 2.56592 + endloop + endfacet + facet normal 0.201146 -0.0148209 0.979449 + outer loop + vertex 1.54519 1.49082 2.56592 + vertex 1.54142 1.48692 2.56663 + vertex 1.54509 1.48582 2.56586 + endloop + endfacet + facet normal 0.201112 -0.0149384 0.979454 + outer loop + vertex 1.54142 1.48692 2.56663 + vertex 1.54135 1.48193 2.56657 + vertex 1.54509 1.48582 2.56586 + endloop + endfacet + facet normal 0.201296 -0.0151223 0.979414 + outer loop + vertex 1.54509 1.48582 2.56586 + vertex 1.54135 1.48193 2.56657 + vertex 1.54499 1.48082 2.56581 + endloop + endfacet + facet normal 0.175001 -0.0146611 0.984459 + outer loop + vertex 1.54499 1.48082 2.56581 + vertex 1.54867 1.48439 2.5652 + vertex 1.54509 1.48582 2.56586 + endloop + endfacet + facet normal 0.175667 -0.0153685 0.98433 + outer loop + vertex 1.54856 1.47936 2.56514 + vertex 1.54867 1.48439 2.5652 + vertex 1.54499 1.48082 2.56581 + endloop + endfacet + facet normal 0.175451 -0.0159113 0.98436 + outer loop + vertex 1.54482 1.47581 2.56575 + vertex 1.54856 1.47936 2.56514 + vertex 1.54499 1.48082 2.56581 + endloop + endfacet + facet normal 0.201302 -0.0166985 0.979387 + outer loop + vertex 1.54499 1.48082 2.56581 + vertex 1.54127 1.47695 2.5665 + vertex 1.54482 1.47581 2.56575 + endloop + endfacet + facet normal 0.200574 -0.0190503 0.979493 + outer loop + vertex 1.54127 1.47695 2.5665 + vertex 1.54117 1.47206 2.56643 + vertex 1.54482 1.47581 2.56575 + endloop + endfacet + facet normal 0.201276 -0.0197622 0.979335 + outer loop + vertex 1.54482 1.47581 2.56575 + vertex 1.54117 1.47206 2.56643 + vertex 1.54449 1.47094 2.56572 + endloop + endfacet + facet normal 0.174746 -0.0179725 0.984449 + outer loop + vertex 1.54449 1.47094 2.56572 + vertex 1.54831 1.47421 2.56511 + vertex 1.54482 1.47581 2.56575 + endloop + endfacet + facet normal 0.177413 -0.0211953 0.983908 + outer loop + vertex 1.54755 1.46848 2.56512 + vertex 1.54831 1.47421 2.56511 + vertex 1.54449 1.47094 2.56572 + endloop + endfacet + facet normal 0.178209 -0.020178 0.983786 + outer loop + vertex 1.54384 1.46712 2.56576 + vertex 1.54755 1.46848 2.56512 + vertex 1.54449 1.47094 2.56572 + endloop + endfacet + facet normal 0.201077 -0.0241113 0.979279 + outer loop + vertex 1.54449 1.47094 2.56572 + vertex 1.54115 1.4676 2.56633 + vertex 1.54384 1.46712 2.56576 + endloop + endfacet + facet normal 0.200612 -0.0267607 0.979305 + outer loop + vertex 1.54384 1.46712 2.56576 + vertex 1.54115 1.4676 2.56633 + vertex 1.54167 1.46444 2.56614 + endloop + endfacet + facet normal 0.200598 -0.0267492 0.979308 + outer loop + vertex 1.54384 1.46712 2.56576 + vertex 1.54167 1.46444 2.56614 + vertex 1.5443 1.46385 2.56558 + endloop + endfacet + facet normal 0.19949 -0.0317098 0.979387 + outer loop + vertex 1.5443 1.46385 2.56558 + vertex 1.54167 1.46444 2.56614 + vertex 1.54096 1.46057 2.56615 + endloop + endfacet + facet normal 0.193396 -0.0305915 0.980644 + outer loop + vertex 1.54167 1.46444 2.56614 + vertex 1.53774 1.46262 2.56685 + vertex 1.54096 1.46057 2.56615 + endloop + endfacet + facet normal 0.191871 -0.0330578 0.980863 + outer loop + vertex 1.53774 1.46262 2.56685 + vertex 1.53698 1.45698 2.56681 + vertex 1.54096 1.46057 2.56615 + endloop + endfacet + facet normal 0.192105 -0.0333272 0.980808 + outer loop + vertex 1.54096 1.46057 2.56615 + vertex 1.53698 1.45698 2.56681 + vertex 1.54057 1.45576 2.56607 + endloop + endfacet + facet normal 0.19668 -0.0336766 0.979889 + outer loop + vertex 1.54057 1.45576 2.56607 + vertex 1.54419 1.45929 2.56546 + vertex 1.54096 1.46057 2.56615 + endloop + endfacet + facet normal 0.19804 -0.03017 0.979729 + outer loop + vertex 1.54419 1.45929 2.56546 + vertex 1.5443 1.46385 2.56558 + vertex 1.54096 1.46057 2.56615 + endloop + endfacet + facet normal 0.192062 -0.0334561 0.980812 + outer loop + vertex 1.53698 1.45698 2.56681 + vertex 1.53672 1.45198 2.56669 + vertex 1.54057 1.45576 2.56607 + endloop + endfacet + facet normal 0.19335 -0.0348195 0.980512 + outer loop + vertex 1.54057 1.45576 2.56607 + vertex 1.53672 1.45198 2.56669 + vertex 1.54036 1.45085 2.56593 + endloop + endfacet + facet normal 0.194746 -0.0348734 0.980233 + outer loop + vertex 1.54036 1.45085 2.56593 + vertex 1.544 1.4544 2.56534 + vertex 1.54057 1.45576 2.56607 + endloop + endfacet + facet normal 0.195641 -0.0325698 0.980135 + outer loop + vertex 1.544 1.4544 2.56534 + vertex 1.54419 1.45929 2.56546 + vertex 1.54057 1.45576 2.56607 + endloop + endfacet + facet normal 0.173523 -0.0318442 0.984315 + outer loop + vertex 1.544 1.4544 2.56534 + vertex 1.54791 1.45818 2.56477 + vertex 1.54419 1.45929 2.56546 + endloop + endfacet + facet normal 0.174303 -0.0291799 0.98426 + outer loop + vertex 1.54791 1.45818 2.56477 + vertex 1.54794 1.46319 2.56491 + vertex 1.54419 1.45929 2.56546 + endloop + endfacet + facet normal 0.17325 -0.0315537 0.984372 + outer loop + vertex 1.54781 1.45319 2.56463 + vertex 1.54791 1.45818 2.56477 + vertex 1.544 1.4544 2.56534 + endloop + endfacet + facet normal 0.172461 -0.0340672 0.984427 + outer loop + vertex 1.54383 1.44943 2.56519 + vertex 1.54781 1.45319 2.56463 + vertex 1.544 1.4544 2.56534 + endloop + endfacet + facet normal 0.171644 -0.0331771 0.9846 + outer loop + vertex 1.54772 1.44819 2.56448 + vertex 1.54781 1.45319 2.56463 + vertex 1.54383 1.44943 2.56519 + endloop + endfacet + facet normal 0.171169 -0.0346775 0.984631 + outer loop + vertex 1.54364 1.44443 2.56505 + vertex 1.54772 1.44819 2.56448 + vertex 1.54383 1.44943 2.56519 + endloop + endfacet + facet normal 0.193701 -0.035409 0.980421 + outer loop + vertex 1.54364 1.44443 2.56505 + vertex 1.54383 1.44943 2.56519 + vertex 1.54017 1.44591 2.56579 + endloop + endfacet + facet normal 0.193295 -0.0363812 0.980466 + outer loop + vertex 1.53991 1.44098 2.56566 + vertex 1.54364 1.44443 2.56505 + vertex 1.54017 1.44591 2.56579 + endloop + endfacet + facet normal 0.201077 -0.0367569 0.978886 + outer loop + vertex 1.54017 1.44591 2.56579 + vertex 1.53643 1.44218 2.56642 + vertex 1.53991 1.44098 2.56566 + endloop + endfacet + facet normal 0.201252 -0.0362396 0.978869 + outer loop + vertex 1.53643 1.44218 2.56642 + vertex 1.53621 1.43739 2.56629 + vertex 1.53991 1.44098 2.56566 + endloop + endfacet + facet normal 0.203427 -0.038571 0.97833 + outer loop + vertex 1.53991 1.44098 2.56566 + vertex 1.53621 1.43739 2.56629 + vertex 1.53947 1.43621 2.56556 + endloop + endfacet + facet normal 0.193452 -0.037699 0.980385 + outer loop + vertex 1.53947 1.43621 2.56556 + vertex 1.5433 1.43933 2.56493 + vertex 1.53991 1.44098 2.56566 + endloop + endfacet + facet normal 0.195575 -0.0404173 0.979855 + outer loop + vertex 1.54249 1.43367 2.56486 + vertex 1.5433 1.43933 2.56493 + vertex 1.53947 1.43621 2.56556 + endloop + endfacet + facet normal 0.19549 -0.0405216 0.979868 + outer loop + vertex 1.53873 1.43245 2.56555 + vertex 1.54249 1.43367 2.56486 + vertex 1.53947 1.43621 2.56556 + endloop + endfacet + facet normal 0.197596 -0.0473892 0.979137 + outer loop + vertex 1.53873 1.43245 2.56555 + vertex 1.53912 1.4291 2.56531 + vertex 1.54249 1.43367 2.56486 + endloop + endfacet + facet normal 0.1961 -0.0462505 0.979492 + outer loop + vertex 1.54249 1.43367 2.56486 + vertex 1.53912 1.4291 2.56531 + vertex 1.54281 1.42831 2.56454 + endloop + endfacet + facet normal 0.176226 -0.0476768 0.983194 + outer loop + vertex 1.54281 1.42831 2.56454 + vertex 1.5473 1.43276 2.56395 + vertex 1.54249 1.43367 2.56486 + endloop + endfacet + facet normal 0.177171 -0.0427252 0.983252 + outer loop + vertex 1.5473 1.43276 2.56395 + vertex 1.54739 1.43799 2.56416 + vertex 1.54249 1.43367 2.56486 + endloop + endfacet + facet normal 0.136642 -0.0422858 0.989718 + outer loop + vertex 1.5473 1.43276 2.56395 + vertex 1.55228 1.43751 2.56346 + vertex 1.54739 1.43799 2.56416 + endloop + endfacet + facet normal 0.136869 -0.0400817 0.989778 + outer loop + vertex 1.55228 1.43751 2.56346 + vertex 1.55227 1.44252 2.56367 + vertex 1.54739 1.43799 2.56416 + endloop + endfacet + facet normal 0.132816 -0.0356361 0.9905 + outer loop + vertex 1.54739 1.43799 2.56416 + vertex 1.55227 1.44252 2.56367 + vertex 1.54759 1.44315 2.56432 + endloop + endfacet + facet normal 0.172426 -0.0369872 0.984328 + outer loop + vertex 1.54739 1.43799 2.56416 + vertex 1.54759 1.44315 2.56432 + vertex 1.5433 1.43933 2.56493 + endloop + endfacet + facet normal 0.171186 -0.0355517 0.984597 + outer loop + vertex 1.5433 1.43933 2.56493 + vertex 1.54759 1.44315 2.56432 + vertex 1.54364 1.44443 2.56505 + endloop + endfacet + facet normal 0.132694 -0.0365367 0.990483 + outer loop + vertex 1.55227 1.44252 2.56367 + vertex 1.55228 1.44752 2.56385 + vertex 1.54759 1.44315 2.56432 + endloop + endfacet + facet normal 0.130443 -0.0340769 0.99087 + outer loop + vertex 1.54759 1.44315 2.56432 + vertex 1.55228 1.44752 2.56385 + vertex 1.54772 1.44819 2.56448 + endloop + endfacet + facet normal 0.130519 -0.0335658 0.990877 + outer loop + vertex 1.55228 1.44752 2.56385 + vertex 1.5523 1.4525 2.56402 + vertex 1.54772 1.44819 2.56448 + endloop + endfacet + facet normal 0.089032 -0.0365979 0.995356 + outer loop + vertex 1.55227 1.44252 2.56367 + vertex 1.5574 1.44747 2.56339 + vertex 1.55228 1.44752 2.56385 + endloop + endfacet + facet normal 0.0890512 -0.0350137 0.995411 + outer loop + vertex 1.5574 1.44747 2.56339 + vertex 1.55736 1.45241 2.56357 + vertex 1.55228 1.44752 2.56385 + endloop + endfacet + facet normal 0.0876852 -0.0335889 0.995582 + outer loop + vertex 1.55228 1.44752 2.56385 + vertex 1.55736 1.45241 2.56357 + vertex 1.5523 1.4525 2.56402 + endloop + endfacet + facet normal 0.0877205 -0.0317443 0.995639 + outer loop + vertex 1.55736 1.45241 2.56357 + vertex 1.55734 1.45738 2.56373 + vertex 1.5523 1.4525 2.56402 + endloop + endfacet + facet normal 0.0870655 -0.0310637 0.995718 + outer loop + vertex 1.5523 1.4525 2.56402 + vertex 1.55734 1.45738 2.56373 + vertex 1.55233 1.45749 2.56417 + endloop + endfacet + facet normal 0.129828 -0.0311663 0.991047 + outer loop + vertex 1.5523 1.4525 2.56402 + vertex 1.55233 1.45749 2.56417 + vertex 1.54781 1.45319 2.56463 + endloop + endfacet + facet normal 0.0871273 -0.0285042 0.995789 + outer loop + vertex 1.55734 1.45738 2.56373 + vertex 1.55734 1.46237 2.56387 + vertex 1.55233 1.45749 2.56417 + endloop + endfacet + facet normal 0.0876735 -0.0290692 0.995725 + outer loop + vertex 1.55233 1.45749 2.56417 + vertex 1.55734 1.46237 2.56387 + vertex 1.55236 1.46253 2.56432 + endloop + endfacet + facet normal 0.129846 -0.0291945 0.991104 + outer loop + vertex 1.55233 1.45749 2.56417 + vertex 1.55236 1.46253 2.56432 + vertex 1.54791 1.45818 2.56477 + endloop + endfacet + facet normal 0.129757 -0.0291023 0.991119 + outer loop + vertex 1.54791 1.45818 2.56477 + vertex 1.55236 1.46253 2.56432 + vertex 1.54794 1.46319 2.56491 + endloop + endfacet + facet normal 0.130196 -0.0262016 0.991142 + outer loop + vertex 1.55236 1.46253 2.56432 + vertex 1.55233 1.46764 2.56445 + vertex 1.54794 1.46319 2.56491 + endloop + endfacet + facet normal 0.132731 -0.0287437 0.990735 + outer loop + vertex 1.54794 1.46319 2.56491 + vertex 1.55233 1.46764 2.56445 + vertex 1.54755 1.46848 2.56512 + endloop + endfacet + facet normal 0.175593 -0.0253623 0.984136 + outer loop + vertex 1.54755 1.46848 2.56512 + vertex 1.5443 1.46385 2.56558 + vertex 1.54794 1.46319 2.56491 + endloop + endfacet + facet normal 0.174817 -0.0296884 0.984153 + outer loop + vertex 1.54419 1.45929 2.56546 + vertex 1.54794 1.46319 2.56491 + vertex 1.5443 1.46385 2.56558 + endloop + endfacet + facet normal 0.133909 -0.0219935 0.99075 + outer loop + vertex 1.55233 1.46764 2.56445 + vertex 1.55244 1.4729 2.56456 + vertex 1.54755 1.46848 2.56512 + endloop + endfacet + facet normal 0.0863697 -0.0211451 0.996039 + outer loop + vertex 1.55233 1.46764 2.56445 + vertex 1.55735 1.47245 2.56412 + vertex 1.55244 1.4729 2.56456 + endloop + endfacet + facet normal 0.0865404 -0.0193065 0.996061 + outer loop + vertex 1.55735 1.47245 2.56412 + vertex 1.55738 1.47752 2.56422 + vertex 1.55244 1.4729 2.56456 + endloop + endfacet + facet normal 0.0820924 -0.0145077 0.996519 + outer loop + vertex 1.55244 1.4729 2.56456 + vertex 1.55738 1.47752 2.56422 + vertex 1.55262 1.4781 2.56462 + endloop + endfacet + facet normal 0.081886 -0.0161891 0.99651 + outer loop + vertex 1.55738 1.47752 2.56422 + vertex 1.55739 1.48252 2.5643 + vertex 1.55262 1.4781 2.56462 + endloop + endfacet + facet normal 0.0807278 -0.0149324 0.996624 + outer loop + vertex 1.55262 1.4781 2.56462 + vertex 1.55739 1.48252 2.5643 + vertex 1.55269 1.48315 2.56469 + endloop + endfacet + facet normal 0.124166 -0.0155106 0.99214 + outer loop + vertex 1.55262 1.4781 2.56462 + vertex 1.55269 1.48315 2.56469 + vertex 1.54856 1.47936 2.56514 + endloop + endfacet + facet normal 0.124746 -0.013626 0.992095 + outer loop + vertex 1.54831 1.47421 2.56511 + vertex 1.55262 1.4781 2.56462 + vertex 1.54856 1.47936 2.56514 + endloop + endfacet + facet normal 0.12686 -0.0160054 0.991791 + outer loop + vertex 1.55244 1.4729 2.56456 + vertex 1.55262 1.4781 2.56462 + vertex 1.54831 1.47421 2.56511 + endloop + endfacet + facet normal 0.12312 -0.0143526 0.992288 + outer loop + vertex 1.54856 1.47936 2.56514 + vertex 1.55269 1.48315 2.56469 + vertex 1.54867 1.48439 2.5652 + endloop + endfacet + facet normal 0.123076 -0.0144988 0.992291 + outer loop + vertex 1.55269 1.48315 2.56469 + vertex 1.55272 1.48814 2.56476 + vertex 1.54867 1.48439 2.5652 + endloop + endfacet + facet normal 0.122903 -0.0143093 0.992315 + outer loop + vertex 1.54867 1.48439 2.5652 + vertex 1.55272 1.48814 2.56476 + vertex 1.54875 1.48939 2.56527 + endloop + endfacet + facet normal 0.123111 -0.013644 0.992299 + outer loop + vertex 1.55272 1.48814 2.56476 + vertex 1.55277 1.49312 2.56482 + vertex 1.54875 1.48939 2.56527 + endloop + endfacet + facet normal 0.122068 -0.0125018 0.992443 + outer loop + vertex 1.54875 1.48939 2.56527 + vertex 1.55277 1.49312 2.56482 + vertex 1.54884 1.49438 2.56532 + endloop + endfacet + facet normal 0.12246 -0.0112676 0.992409 + outer loop + vertex 1.55277 1.49312 2.56482 + vertex 1.55282 1.4981 2.56487 + vertex 1.54884 1.49438 2.56532 + endloop + endfacet + facet normal 0.122691 -0.0115179 0.992378 + outer loop + vertex 1.54884 1.49438 2.56532 + vertex 1.55282 1.4981 2.56487 + vertex 1.54894 1.49937 2.56536 + endloop + endfacet + facet normal 0.123848 -0.00792437 0.99227 + outer loop + vertex 1.55282 1.4981 2.56487 + vertex 1.55287 1.5031 2.5649 + vertex 1.54894 1.49937 2.56536 + endloop + endfacet + facet normal 0.0808178 -0.00752175 0.996701 + outer loop + vertex 1.55282 1.4981 2.56487 + vertex 1.5574 1.50245 2.56453 + vertex 1.55287 1.5031 2.5649 + endloop + endfacet + facet normal 0.081464 -0.00300965 0.996672 + outer loop + vertex 1.5574 1.50245 2.56453 + vertex 1.55741 1.50743 2.56454 + vertex 1.55287 1.5031 2.5649 + endloop + endfacet + facet normal 0.0815286 -0.00307759 0.996666 + outer loop + vertex 1.55287 1.5031 2.5649 + vertex 1.55741 1.50743 2.56454 + vertex 1.5529 1.50809 2.56492 + endloop + endfacet + facet normal 0.124701 -0.0033109 0.992189 + outer loop + vertex 1.55287 1.5031 2.5649 + vertex 1.5529 1.50809 2.56492 + vertex 1.549 1.50436 2.56539 + endloop + endfacet + facet normal 0.123984 -0.00254955 0.992281 + outer loop + vertex 1.549 1.50436 2.56539 + vertex 1.5529 1.50809 2.56492 + vertex 1.54902 1.50935 2.5654 + endloop + endfacet + facet normal 0.125379 0.00181874 0.992107 + outer loop + vertex 1.5529 1.50809 2.56492 + vertex 1.5529 1.51308 2.56491 + vertex 1.54902 1.50935 2.5654 + endloop + endfacet + facet normal 0.125681 0.00149996 0.99207 + outer loop + vertex 1.54902 1.50935 2.5654 + vertex 1.5529 1.51308 2.56491 + vertex 1.54901 1.51435 2.5654 + endloop + endfacet + facet normal 0.12661 0.00439663 0.991943 + outer loop + vertex 1.5529 1.51308 2.56491 + vertex 1.55289 1.51808 2.56489 + vertex 1.54901 1.51435 2.5654 + endloop + endfacet + facet normal 0.126617 0.0043892 0.991942 + outer loop + vertex 1.54901 1.51435 2.5654 + vertex 1.55289 1.51808 2.56489 + vertex 1.54898 1.51934 2.56538 + endloop + endfacet + facet normal 0.127267 0.00643784 0.991848 + outer loop + vertex 1.55289 1.51808 2.56489 + vertex 1.55287 1.52306 2.56486 + vertex 1.54898 1.51934 2.56538 + endloop + endfacet + facet normal 0.0822164 0.00435182 0.996605 + outer loop + vertex 1.5529 1.51308 2.56491 + vertex 1.55741 1.51742 2.56452 + vertex 1.55289 1.51808 2.56489 + endloop + endfacet + facet normal 0.0825419 0.00661442 0.996566 + outer loop + vertex 1.55741 1.51742 2.56452 + vertex 1.55741 1.52242 2.56448 + vertex 1.55289 1.51808 2.56489 + endloop + endfacet + facet normal 0.0828855 0.00625431 0.996539 + outer loop + vertex 1.55289 1.51808 2.56489 + vertex 1.55741 1.52242 2.56448 + vertex 1.55287 1.52306 2.56486 + endloop + endfacet + facet normal 0.0831695 0.00826909 0.996501 + outer loop + vertex 1.55741 1.52242 2.56448 + vertex 1.5574 1.5274 2.56444 + vertex 1.55287 1.52306 2.56486 + endloop + endfacet + facet normal 0.0844377 0.00693373 0.996405 + outer loop + vertex 1.55287 1.52306 2.56486 + vertex 1.5574 1.5274 2.56444 + vertex 1.55284 1.52805 2.56482 + endloop + endfacet + facet normal 0.084823 0.00962528 0.99635 + outer loop + vertex 1.5574 1.5274 2.56444 + vertex 1.5574 1.53239 2.56439 + vertex 1.55284 1.52805 2.56482 + endloop + endfacet + facet normal 0.0855608 0.00884328 0.996294 + outer loop + vertex 1.55284 1.52805 2.56482 + vertex 1.5574 1.53239 2.56439 + vertex 1.5528 1.53304 2.56478 + endloop + endfacet + facet normal 0.129062 0.00915755 0.991594 + outer loop + vertex 1.55284 1.52805 2.56482 + vertex 1.5528 1.53304 2.56478 + vertex 1.54887 1.52932 2.56533 + endloop + endfacet + facet normal 0.12838 0.00696762 0.991701 + outer loop + vertex 1.54893 1.52433 2.56536 + vertex 1.55284 1.52805 2.56482 + vertex 1.54887 1.52932 2.56533 + endloop + endfacet + facet normal 0.128217 0.00714173 0.99172 + outer loop + vertex 1.55287 1.52306 2.56486 + vertex 1.55284 1.52805 2.56482 + vertex 1.54893 1.52433 2.56536 + endloop + endfacet + facet normal 0.0860365 0.012239 0.996217 + outer loop + vertex 1.5574 1.53239 2.56439 + vertex 1.55741 1.53739 2.56433 + vertex 1.5528 1.53304 2.56478 + endloop + endfacet + facet normal 0.0871039 0.0111 0.996137 + outer loop + vertex 1.5528 1.53304 2.56478 + vertex 1.55741 1.53739 2.56433 + vertex 1.55277 1.53804 2.56473 + endloop + endfacet + facet normal 0.130568 0.0112591 0.991375 + outer loop + vertex 1.5528 1.53304 2.56478 + vertex 1.55277 1.53804 2.56473 + vertex 1.5488 1.53431 2.5653 + endloop + endfacet + facet normal 0.130124 0.0117405 0.991428 + outer loop + vertex 1.5488 1.53431 2.5653 + vertex 1.55277 1.53804 2.56473 + vertex 1.54873 1.5393 2.56525 + endloop + endfacet + facet normal 0.131126 0.0150267 0.991252 + outer loop + vertex 1.55277 1.53804 2.56473 + vertex 1.55275 1.54305 2.56466 + vertex 1.54873 1.5393 2.56525 + endloop + endfacet + facet normal 0.0880617 0.0149228 0.996003 + outer loop + vertex 1.55277 1.53804 2.56473 + vertex 1.55743 1.54241 2.56425 + vertex 1.55275 1.54305 2.56466 + endloop + endfacet + facet normal 0.0885068 0.0182338 0.995909 + outer loop + vertex 1.55743 1.54241 2.56425 + vertex 1.55744 1.54744 2.56416 + vertex 1.55275 1.54305 2.56466 + endloop + endfacet + facet normal 0.0879524 0.0188298 0.995947 + outer loop + vertex 1.55275 1.54305 2.56466 + vertex 1.55744 1.54744 2.56416 + vertex 1.55271 1.54803 2.56457 + endloop + endfacet + facet normal 0.131723 0.0191677 0.991101 + outer loop + vertex 1.55275 1.54305 2.56466 + vertex 1.55271 1.54803 2.56457 + vertex 1.54866 1.54427 2.56518 + endloop + endfacet + facet normal 0.130737 0.0202498 0.99121 + outer loop + vertex 1.54866 1.54427 2.56518 + vertex 1.55271 1.54803 2.56457 + vertex 1.5485 1.54921 2.5651 + endloop + endfacet + facet normal 0.131591 0.0233808 0.991028 + outer loop + vertex 1.55271 1.54803 2.56457 + vertex 1.55258 1.55298 2.56447 + vertex 1.5485 1.54921 2.5651 + endloop + endfacet + facet normal 0.130071 0.0250462 0.991188 + outer loop + vertex 1.5485 1.54921 2.5651 + vertex 1.55258 1.55298 2.56447 + vertex 1.54816 1.55416 2.56502 + endloop + endfacet + facet normal 0.130731 0.0276035 0.991034 + outer loop + vertex 1.55258 1.55298 2.56447 + vertex 1.55236 1.55796 2.56436 + vertex 1.54816 1.55416 2.56502 + endloop + endfacet + facet normal 0.130233 0.028162 0.991083 + outer loop + vertex 1.54816 1.55416 2.56502 + vertex 1.55236 1.55796 2.56436 + vertex 1.5475 1.5595 2.56495 + endloop + endfacet + facet normal 0.175522 0.0336819 0.983899 + outer loop + vertex 1.54816 1.55416 2.56502 + vertex 1.5475 1.5595 2.56495 + vertex 1.54414 1.55545 2.56569 + endloop + endfacet + facet normal 0.131608 0.0326478 0.990764 + outer loop + vertex 1.55236 1.55796 2.56436 + vertex 1.55239 1.56283 2.56419 + vertex 1.5475 1.5595 2.56495 + endloop + endfacet + facet normal 0.122674 0.0459047 0.991385 + outer loop + vertex 1.5475 1.5595 2.56495 + vertex 1.55239 1.56283 2.56419 + vertex 1.5487 1.56404 2.56459 + endloop + endfacet + facet normal 0.16694 0.0337419 0.98539 + outer loop + vertex 1.54458 1.56379 2.5653 + vertex 1.5475 1.5595 2.56495 + vertex 1.5487 1.56404 2.56459 + endloop + endfacet + facet normal 0.167006 0.032737 0.985412 + outer loop + vertex 1.5487 1.56404 2.56459 + vertex 1.54799 1.56802 2.56458 + vertex 1.54458 1.56379 2.5653 + endloop + endfacet + facet normal 0.170721 0.0296544 0.984873 + outer loop + vertex 1.54458 1.56379 2.5653 + vertex 1.54799 1.56802 2.56458 + vertex 1.54389 1.5691 2.56526 + endloop + endfacet + facet normal 0.171047 0.0309583 0.984776 + outer loop + vertex 1.54799 1.56802 2.56458 + vertex 1.54767 1.57291 2.56448 + vertex 1.54389 1.5691 2.56526 + endloop + endfacet + facet normal 0.131884 0.0285282 0.990855 + outer loop + vertex 1.54799 1.56802 2.56458 + vertex 1.55232 1.57229 2.56388 + vertex 1.54767 1.57291 2.56448 + endloop + endfacet + facet normal 0.132798 0.0357029 0.9905 + outer loop + vertex 1.55232 1.57229 2.56388 + vertex 1.55226 1.57728 2.56371 + vertex 1.54767 1.57291 2.56448 + endloop + endfacet + facet normal 0.136714 0.0315103 0.990109 + outer loop + vertex 1.54767 1.57291 2.56448 + vertex 1.55226 1.57728 2.56371 + vertex 1.54751 1.57794 2.56434 + endloop + endfacet + facet normal 0.173524 0.0325447 0.984292 + outer loop + vertex 1.54767 1.57291 2.56448 + vertex 1.54751 1.57794 2.56434 + vertex 1.54353 1.57418 2.56517 + endloop + endfacet + facet normal 0.173256 0.0328366 0.984329 + outer loop + vertex 1.54353 1.57418 2.56517 + vertex 1.54751 1.57794 2.56434 + vertex 1.5432 1.57926 2.56506 + endloop + endfacet + facet normal 0.137553 0.0378196 0.989772 + outer loop + vertex 1.55226 1.57728 2.56371 + vertex 1.55226 1.58229 2.56352 + vertex 1.54751 1.57794 2.56434 + endloop + endfacet + facet normal 0.139318 0.0358572 0.989598 + outer loop + vertex 1.54751 1.57794 2.56434 + vertex 1.55226 1.58229 2.56352 + vertex 1.54735 1.58298 2.56418 + endloop + endfacet + facet normal 0.139867 0.0400274 0.989361 + outer loop + vertex 1.55226 1.58229 2.56352 + vertex 1.55232 1.58727 2.56331 + vertex 1.54735 1.58298 2.56418 + endloop + endfacet + facet normal 0.0952537 0.0407922 0.994617 + outer loop + vertex 1.55226 1.58229 2.56352 + vertex 1.55752 1.58731 2.56281 + vertex 1.55232 1.58727 2.56331 + endloop + endfacet + facet normal 0.0952153 0.0438291 0.994491 + outer loop + vertex 1.55752 1.58731 2.56281 + vertex 1.55764 1.59232 2.56258 + vertex 1.55232 1.58727 2.56331 + endloop + endfacet + facet normal 0.094614 0.0444662 0.99452 + outer loop + vertex 1.55232 1.58727 2.56331 + vertex 1.55764 1.59232 2.56258 + vertex 1.55243 1.59219 2.56308 + endloop + endfacet + facet normal 0.137802 0.0432486 0.989515 + outer loop + vertex 1.55232 1.58727 2.56331 + vertex 1.55243 1.59219 2.56308 + vertex 1.54743 1.58784 2.56396 + endloop + endfacet + facet normal 0.136111 0.0452233 0.989661 + outer loop + vertex 1.54743 1.58784 2.56396 + vertex 1.55243 1.59219 2.56308 + vertex 1.54754 1.5925 2.56374 + endloop + endfacet + facet normal 0.0944638 0.0495339 0.994295 + outer loop + vertex 1.55764 1.59232 2.56258 + vertex 1.55769 1.59735 2.56232 + vertex 1.55243 1.59219 2.56308 + endloop + endfacet + facet normal 0.0949414 0.0490446 0.994274 + outer loop + vertex 1.55243 1.59219 2.56308 + vertex 1.55769 1.59735 2.56232 + vertex 1.55248 1.59712 2.56283 + endloop + endfacet + facet normal 0.0530293 0.0500759 0.997337 + outer loop + vertex 1.55764 1.59232 2.56258 + vertex 1.56274 1.59761 2.56204 + vertex 1.55769 1.59735 2.56232 + endloop + endfacet + facet normal 0.0526888 0.0563605 0.997019 + outer loop + vertex 1.56274 1.59761 2.56204 + vertex 1.56247 1.60272 2.56176 + vertex 1.55769 1.59735 2.56232 + endloop + endfacet + facet normal 0.0500904 0.0586771 0.99702 + outer loop + vertex 1.55769 1.59735 2.56232 + vertex 1.56247 1.60272 2.56176 + vertex 1.55741 1.60232 2.56204 + endloop + endfacet + facet normal 0.0564784 0.0467495 0.997309 + outer loop + vertex 1.56268 1.59257 2.56228 + vertex 1.56274 1.59761 2.56204 + vertex 1.55764 1.59232 2.56258 + endloop + endfacet + facet normal 0.0565748 0.0449013 0.997388 + outer loop + vertex 1.55752 1.58731 2.56281 + vertex 1.56268 1.59257 2.56228 + vertex 1.55764 1.59232 2.56258 + endloop + endfacet + facet normal 0.0579722 0.0435274 0.997369 + outer loop + vertex 1.5626 1.58756 2.5625 + vertex 1.56268 1.59257 2.56228 + vertex 1.55752 1.58731 2.56281 + endloop + endfacet + facet normal 0.0579961 0.0430573 0.997388 + outer loop + vertex 1.55744 1.5823 2.56303 + vertex 1.5626 1.58756 2.5625 + vertex 1.55752 1.58731 2.56281 + endloop + endfacet + facet normal 0.0579159 0.0431362 0.997389 + outer loop + vertex 1.56257 1.58254 2.56272 + vertex 1.5626 1.58756 2.5625 + vertex 1.55744 1.5823 2.56303 + endloop + endfacet + facet normal 0.0579882 0.0416716 0.997447 + outer loop + vertex 1.55739 1.57727 2.56324 + vertex 1.56257 1.58254 2.56272 + vertex 1.55744 1.5823 2.56303 + endloop + endfacet + facet normal 0.0906092 0.0412959 0.99503 + outer loop + vertex 1.55739 1.57727 2.56324 + vertex 1.55744 1.5823 2.56303 + vertex 1.55226 1.57728 2.56371 + endloop + endfacet + facet normal 0.0575164 0.0421358 0.997455 + outer loop + vertex 1.56256 1.5775 2.56293 + vertex 1.56257 1.58254 2.56272 + vertex 1.55739 1.57727 2.56324 + endloop + endfacet + facet normal 0.0576592 0.0391388 0.997569 + outer loop + vertex 1.55737 1.57226 2.56344 + vertex 1.56256 1.5775 2.56293 + vertex 1.55739 1.57727 2.56324 + endloop + endfacet + facet normal 0.0871624 0.0389373 0.995433 + outer loop + vertex 1.55737 1.57226 2.56344 + vertex 1.55739 1.57727 2.56324 + vertex 1.55232 1.57229 2.56388 + endloop + endfacet + facet normal 0.0871346 0.0314663 0.995699 + outer loop + vertex 1.55244 1.56749 2.56402 + vertex 1.55737 1.57226 2.56344 + vertex 1.55232 1.57229 2.56388 + endloop + endfacet + facet normal 0.0831779 0.0355866 0.995899 + outer loop + vertex 1.55735 1.56731 2.56362 + vertex 1.55737 1.57226 2.56344 + vertex 1.55244 1.56749 2.56402 + endloop + endfacet + facet normal 0.0831676 0.0352934 0.99591 + outer loop + vertex 1.55239 1.56283 2.56419 + vertex 1.55735 1.56731 2.56362 + vertex 1.55244 1.56749 2.56402 + endloop + endfacet + facet normal 0.0855125 0.032682 0.995801 + outer loop + vertex 1.55732 1.56237 2.56378 + vertex 1.55735 1.56731 2.56362 + vertex 1.55239 1.56283 2.56419 + endloop + endfacet + facet normal 0.0614199 0.0328746 0.99757 + outer loop + vertex 1.55732 1.56237 2.56378 + vertex 1.56253 1.56741 2.5633 + vertex 1.55735 1.56731 2.56362 + endloop + endfacet + facet normal 0.0614172 0.0330007 0.997566 + outer loop + vertex 1.56253 1.56741 2.5633 + vertex 1.56254 1.57245 2.56313 + vertex 1.55735 1.56731 2.56362 + endloop + endfacet + facet normal 0.0644895 0.0296934 0.997477 + outer loop + vertex 1.56252 1.56237 2.56345 + vertex 1.56253 1.56741 2.5633 + vertex 1.55732 1.56237 2.56378 + endloop + endfacet + facet normal 0.0644894 0.0296983 0.997476 + outer loop + vertex 1.55736 1.55741 2.56393 + vertex 1.56252 1.56237 2.56345 + vertex 1.55732 1.56237 2.56378 + endloop + endfacet + facet normal 0.0884394 0.0298335 0.995635 + outer loop + vertex 1.55736 1.55741 2.56393 + vertex 1.55732 1.56237 2.56378 + vertex 1.55236 1.55796 2.56436 + endloop + endfacet + facet normal 0.0654814 0.0286627 0.997442 + outer loop + vertex 1.56249 1.55738 2.56359 + vertex 1.56252 1.56237 2.56345 + vertex 1.55736 1.55741 2.56393 + endloop + endfacet + facet normal 0.0654635 0.0251652 0.997538 + outer loop + vertex 1.55741 1.55243 2.56405 + vertex 1.56249 1.55738 2.56359 + vertex 1.55736 1.55741 2.56393 + endloop + endfacet + facet normal 0.0884796 0.0253647 0.995755 + outer loop + vertex 1.55741 1.55243 2.56405 + vertex 1.55736 1.55741 2.56393 + vertex 1.55258 1.55298 2.56447 + endloop + endfacet + facet normal 0.0662251 0.0243813 0.997507 + outer loop + vertex 1.56249 1.55242 2.56371 + vertex 1.56249 1.55738 2.56359 + vertex 1.55741 1.55243 2.56405 + endloop + endfacet + facet normal 0.0662246 0.0220284 0.997562 + outer loop + vertex 1.55744 1.54744 2.56416 + vertex 1.56249 1.55242 2.56371 + vertex 1.55741 1.55243 2.56405 + endloop + endfacet + facet normal 0.0682139 0.0200016 0.99747 + outer loop + vertex 1.56251 1.54742 2.56381 + vertex 1.56249 1.55242 2.56371 + vertex 1.55744 1.54744 2.56416 + endloop + endfacet + facet normal 0.0586706 0.0357768 0.997636 + outer loop + vertex 1.55735 1.56731 2.56362 + vertex 1.56254 1.57245 2.56313 + vertex 1.55737 1.57226 2.56344 + endloop + endfacet + facet normal 0.0585725 0.0382336 0.997551 + outer loop + vertex 1.56254 1.57245 2.56313 + vertex 1.56256 1.5775 2.56293 + vertex 1.55737 1.57226 2.56344 + endloop + endfacet + facet normal 0.0937766 0.0423506 0.994692 + outer loop + vertex 1.55744 1.5823 2.56303 + vertex 1.55752 1.58731 2.56281 + vertex 1.55226 1.58229 2.56352 + endloop + endfacet + facet normal 0.0937974 0.0379878 0.994866 + outer loop + vertex 1.55226 1.57728 2.56371 + vertex 1.55744 1.5823 2.56303 + vertex 1.55226 1.58229 2.56352 + endloop + endfacet + facet normal 0.0906165 0.0353901 0.995257 + outer loop + vertex 1.55232 1.57229 2.56388 + vertex 1.55739 1.57727 2.56324 + vertex 1.55226 1.57728 2.56371 + endloop + endfacet + facet normal 0.128121 0.0324036 0.991229 + outer loop + vertex 1.55244 1.56749 2.56402 + vertex 1.55232 1.57229 2.56388 + vertex 1.54799 1.56802 2.56458 + endloop + endfacet + facet normal 0.127368 0.0257005 0.991522 + outer loop + vertex 1.5487 1.56404 2.56459 + vertex 1.55244 1.56749 2.56402 + vertex 1.54799 1.56802 2.56458 + endloop + endfacet + facet normal 0.11913 0.0347638 0.99227 + outer loop + vertex 1.55239 1.56283 2.56419 + vertex 1.55244 1.56749 2.56402 + vertex 1.5487 1.56404 2.56459 + endloop + endfacet + facet normal 0.0855512 0.033106 0.995784 + outer loop + vertex 1.55236 1.55796 2.56436 + vertex 1.55732 1.56237 2.56378 + vertex 1.55239 1.56283 2.56419 + endloop + endfacet + facet normal 0.0880154 0.0258698 0.995783 + outer loop + vertex 1.55258 1.55298 2.56447 + vertex 1.55736 1.55741 2.56393 + vertex 1.55236 1.55796 2.56436 + endloop + endfacet + facet normal 0.0881392 0.0223368 0.995858 + outer loop + vertex 1.55271 1.54803 2.56457 + vertex 1.55741 1.55243 2.56405 + vertex 1.55258 1.55298 2.56447 + endloop + endfacet + facet normal 0.0883532 0.0221063 0.995844 + outer loop + vertex 1.55744 1.54744 2.56416 + vertex 1.55741 1.55243 2.56405 + vertex 1.55271 1.54803 2.56457 + endloop + endfacet + facet normal 0.0682111 0.0183163 0.997503 + outer loop + vertex 1.55743 1.54241 2.56425 + vertex 1.56251 1.54742 2.56381 + vertex 1.55744 1.54744 2.56416 + endloop + endfacet + facet normal 0.068954 0.0175592 0.997465 + outer loop + vertex 1.5625 1.54239 2.5639 + vertex 1.56251 1.54742 2.56381 + vertex 1.55743 1.54241 2.56425 + endloop + endfacet + facet normal 0.0689497 0.0154085 0.997501 + outer loop + vertex 1.55741 1.53739 2.56433 + vertex 1.5625 1.54239 2.5639 + vertex 1.55743 1.54241 2.56425 + endloop + endfacet + facet normal 0.0687263 0.0156367 0.997513 + outer loop + vertex 1.56247 1.53737 2.56398 + vertex 1.5625 1.54239 2.5639 + vertex 1.55741 1.53739 2.56433 + endloop + endfacet + facet normal 0.0876895 0.0153222 0.99603 + outer loop + vertex 1.55741 1.53739 2.56433 + vertex 1.55743 1.54241 2.56425 + vertex 1.55277 1.53804 2.56473 + endloop + endfacet + facet normal 0.0687167 0.0122954 0.99756 + outer loop + vertex 1.5574 1.53239 2.56439 + vertex 1.56247 1.53737 2.56398 + vertex 1.55741 1.53739 2.56433 + endloop + endfacet + facet normal 0.0679719 0.0130562 0.997602 + outer loop + vertex 1.56244 1.53237 2.56405 + vertex 1.56247 1.53737 2.56398 + vertex 1.5574 1.53239 2.56439 + endloop + endfacet + facet normal 0.0679662 0.00964505 0.997641 + outer loop + vertex 1.5574 1.5274 2.56444 + vertex 1.56244 1.53237 2.56405 + vertex 1.5574 1.53239 2.56439 + endloop + endfacet + facet normal 0.067161 0.0104649 0.997687 + outer loop + vertex 1.56244 1.52739 2.5641 + vertex 1.56244 1.53237 2.56405 + vertex 1.5574 1.5274 2.56444 + endloop + endfacet + facet normal 0.0671603 0.00823976 0.997708 + outer loop + vertex 1.55741 1.52242 2.56448 + vertex 1.56244 1.52739 2.5641 + vertex 1.5574 1.5274 2.56444 + endloop + endfacet + facet normal 0.0673976 0.0079988 0.997694 + outer loop + vertex 1.56243 1.5224 2.56414 + vertex 1.56244 1.52739 2.5641 + vertex 1.55741 1.52242 2.56448 + endloop + endfacet + facet normal 0.0673935 0.00662125 0.997705 + outer loop + vertex 1.55741 1.51742 2.56452 + vertex 1.56243 1.5224 2.56414 + vertex 1.55741 1.52242 2.56448 + endloop + endfacet + facet normal 0.0678706 0.00613765 0.997675 + outer loop + vertex 1.56243 1.51741 2.56417 + vertex 1.56243 1.5224 2.56414 + vertex 1.55741 1.51742 2.56452 + endloop + endfacet + facet normal 0.0678689 0.004833 0.997683 + outer loop + vertex 1.55741 1.51243 2.56454 + vertex 1.56243 1.51741 2.56417 + vertex 1.55741 1.51742 2.56452 + endloop + endfacet + facet normal 0.0688746 0.00381454 0.997618 + outer loop + vertex 1.56243 1.51242 2.56419 + vertex 1.56243 1.51741 2.56417 + vertex 1.55741 1.51243 2.56454 + endloop + endfacet + facet normal 0.0688679 0.000963226 0.997625 + outer loop + vertex 1.55741 1.50743 2.56454 + vertex 1.56243 1.51242 2.56419 + vertex 1.55741 1.51243 2.56454 + endloop + endfacet + facet normal 0.0692071 0.000619452 0.997602 + outer loop + vertex 1.56244 1.50742 2.5642 + vertex 1.56243 1.51242 2.56419 + vertex 1.55741 1.50743 2.56454 + endloop + endfacet + facet normal 0.0817481 0.00484162 0.996641 + outer loop + vertex 1.55741 1.51243 2.56454 + vertex 1.55741 1.51742 2.56452 + vertex 1.5529 1.51308 2.56491 + endloop + endfacet + facet normal 0.0813123 0.00178764 0.996687 + outer loop + vertex 1.5529 1.50809 2.56492 + vertex 1.55741 1.51243 2.56454 + vertex 1.5529 1.51308 2.56491 + endloop + endfacet + facet normal 0.082116 0.000946058 0.996622 + outer loop + vertex 1.55741 1.50743 2.56454 + vertex 1.55741 1.51243 2.56454 + vertex 1.5529 1.50809 2.56492 + endloop + endfacet + facet normal 0.0692006 -0.00299681 0.997598 + outer loop + vertex 1.5574 1.50245 2.56453 + vertex 1.56244 1.50742 2.5642 + vertex 1.55741 1.50743 2.56454 + endloop + endfacet + facet normal 0.069254 -0.00305112 0.997594 + outer loop + vertex 1.56244 1.50243 2.56418 + vertex 1.56244 1.50742 2.5642 + vertex 1.5574 1.50245 2.56453 + endloop + endfacet + facet normal 0.0692389 -0.00748906 0.997572 + outer loop + vertex 1.55738 1.49745 2.56449 + vertex 1.56244 1.50243 2.56418 + vertex 1.5574 1.50245 2.56453 + endloop + endfacet + facet normal 0.0687397 -0.00697914 0.99761 + outer loop + vertex 1.56244 1.49744 2.56415 + vertex 1.56244 1.50243 2.56418 + vertex 1.55738 1.49745 2.56449 + endloop + endfacet + facet normal 0.0687266 -0.0109297 0.997576 + outer loop + vertex 1.55736 1.49247 2.56444 + vertex 1.56244 1.49744 2.56415 + vertex 1.55738 1.49745 2.56449 + endloop + endfacet + facet normal 0.0676847 -0.0098601 0.997658 + outer loop + vertex 1.56245 1.49245 2.5641 + vertex 1.56244 1.49744 2.56415 + vertex 1.55736 1.49247 2.56444 + endloop + endfacet + facet normal 0.0676729 -0.0134066 0.997617 + outer loop + vertex 1.55737 1.4875 2.56437 + vertex 1.56245 1.49245 2.5641 + vertex 1.55736 1.49247 2.56444 + endloop + endfacet + facet normal 0.0801977 -0.0133775 0.996689 + outer loop + vertex 1.55737 1.4875 2.56437 + vertex 1.55736 1.49247 2.56444 + vertex 1.55272 1.48814 2.56476 + endloop + endfacet + facet normal 0.0663719 -0.0120664 0.997722 + outer loop + vertex 1.56248 1.48749 2.56403 + vertex 1.56245 1.49245 2.5641 + vertex 1.55737 1.4875 2.56437 + endloop + endfacet + facet normal 0.066363 -0.0150606 0.997682 + outer loop + vertex 1.55739 1.48252 2.5643 + vertex 1.56248 1.48749 2.56403 + vertex 1.55737 1.4875 2.56437 + endloop + endfacet + facet normal 0.0657438 -0.0144219 0.997732 + outer loop + vertex 1.56252 1.48253 2.56396 + vertex 1.56248 1.48749 2.56403 + vertex 1.55739 1.48252 2.5643 + endloop + endfacet + facet normal 0.0808282 -0.00753283 0.9967 + outer loop + vertex 1.55738 1.49745 2.56449 + vertex 1.5574 1.50245 2.56453 + vertex 1.55282 1.4981 2.56487 + endloop + endfacet + facet normal 0.0803571 -0.0108292 0.996707 + outer loop + vertex 1.55277 1.49312 2.56482 + vertex 1.55738 1.49745 2.56449 + vertex 1.55282 1.4981 2.56487 + endloop + endfacet + facet normal 0.0804725 -0.0109528 0.996697 + outer loop + vertex 1.55736 1.49247 2.56444 + vertex 1.55738 1.49745 2.56449 + vertex 1.55277 1.49312 2.56482 + endloop + endfacet + facet normal 0.0801396 -0.0133148 0.996695 + outer loop + vertex 1.55272 1.48814 2.56476 + vertex 1.55736 1.49247 2.56444 + vertex 1.55277 1.49312 2.56482 + endloop + endfacet + facet normal 0.0800708 -0.0143007 0.996687 + outer loop + vertex 1.55269 1.48315 2.56469 + vertex 1.55737 1.4875 2.56437 + vertex 1.55272 1.48814 2.56476 + endloop + endfacet + facet normal 0.0807185 -0.0150021 0.996624 + outer loop + vertex 1.55739 1.48252 2.5643 + vertex 1.55737 1.4875 2.56437 + vertex 1.55269 1.48315 2.56469 + endloop + endfacet + facet normal 0.0657438 -0.0161884 0.997705 + outer loop + vertex 1.55738 1.47752 2.56422 + vertex 1.56252 1.48253 2.56396 + vertex 1.55739 1.48252 2.5643 + endloop + endfacet + facet normal 0.0659289 -0.0163789 0.99769 + outer loop + vertex 1.56255 1.47756 2.56388 + vertex 1.56252 1.48253 2.56396 + vertex 1.55738 1.47752 2.56422 + endloop + endfacet + facet normal 0.0659498 -0.0192165 0.997638 + outer loop + vertex 1.55735 1.47245 2.56412 + vertex 1.56255 1.47756 2.56388 + vertex 1.55738 1.47752 2.56422 + endloop + endfacet + facet normal 0.0665061 -0.0197846 0.99759 + outer loop + vertex 1.56256 1.47259 2.56378 + vertex 1.56255 1.47756 2.56388 + vertex 1.55735 1.47245 2.56412 + endloop + endfacet + facet normal 0.0665807 -0.0228449 0.997519 + outer loop + vertex 1.55735 1.4674 2.56401 + vertex 1.56256 1.47259 2.56378 + vertex 1.55735 1.47245 2.56412 + endloop + endfacet + facet normal 0.0664008 -0.0226632 0.997536 + outer loop + vertex 1.56257 1.4676 2.56366 + vertex 1.56256 1.47259 2.56378 + vertex 1.55735 1.4674 2.56401 + endloop + endfacet + facet normal 0.0665458 -0.0265452 0.99743 + outer loop + vertex 1.55734 1.46237 2.56387 + vertex 1.56257 1.4676 2.56366 + vertex 1.55735 1.4674 2.56401 + endloop + endfacet + facet normal 0.0645804 -0.024575 0.99761 + outer loop + vertex 1.56257 1.46262 2.56354 + vertex 1.56257 1.4676 2.56366 + vertex 1.55734 1.46237 2.56387 + endloop + endfacet + facet normal 0.0879711 -0.0228287 0.995861 + outer loop + vertex 1.55735 1.4674 2.56401 + vertex 1.55735 1.47245 2.56412 + vertex 1.55233 1.46764 2.56445 + endloop + endfacet + facet normal 0.0877826 -0.0265438 0.995786 + outer loop + vertex 1.55236 1.46253 2.56432 + vertex 1.55735 1.4674 2.56401 + vertex 1.55233 1.46764 2.56445 + endloop + endfacet + facet normal 0.0877572 -0.0265177 0.995789 + outer loop + vertex 1.55734 1.46237 2.56387 + vertex 1.55735 1.4674 2.56401 + vertex 1.55236 1.46253 2.56432 + endloop + endfacet + facet normal 0.0647609 -0.0285519 0.997492 + outer loop + vertex 1.55734 1.45738 2.56373 + vertex 1.56257 1.46262 2.56354 + vertex 1.55734 1.46237 2.56387 + endloop + endfacet + facet normal 0.0640595 -0.0278498 0.997557 + outer loop + vertex 1.56257 1.45764 2.5634 + vertex 1.56257 1.46262 2.56354 + vertex 1.55734 1.45738 2.56373 + endloop + endfacet + facet normal 0.0642486 -0.0318727 0.997425 + outer loop + vertex 1.55736 1.45241 2.56357 + vertex 1.56257 1.45764 2.5634 + vertex 1.55734 1.45738 2.56373 + endloop + endfacet + facet normal 0.0643986 -0.0320228 0.99741 + outer loop + vertex 1.56261 1.45267 2.56324 + vertex 1.56257 1.45764 2.5634 + vertex 1.55736 1.45241 2.56357 + endloop + endfacet + facet normal 0.0645511 -0.0352743 0.997291 + outer loop + vertex 1.5574 1.44747 2.56339 + vertex 1.56261 1.45267 2.56324 + vertex 1.55736 1.45241 2.56357 + endloop + endfacet + facet normal 0.0643513 -0.0350735 0.997311 + outer loop + vertex 1.56265 1.44772 2.56306 + vertex 1.56261 1.45267 2.56324 + vertex 1.5574 1.44747 2.56339 + endloop + endfacet + facet normal 0.0645512 -0.0396263 0.997127 + outer loop + vertex 1.55745 1.44254 2.56319 + vertex 1.56265 1.44772 2.56306 + vertex 1.5574 1.44747 2.56339 + endloop + endfacet + facet normal 0.062173 -0.0372302 0.997371 + outer loop + vertex 1.56268 1.44277 2.56288 + vertex 1.56265 1.44772 2.56306 + vertex 1.55745 1.44254 2.56319 + endloop + endfacet + facet normal 0.062454 -0.0437866 0.997087 + outer loop + vertex 1.55751 1.43761 2.56297 + vertex 1.56268 1.44277 2.56288 + vertex 1.55745 1.44254 2.56319 + endloop + endfacet + facet normal 0.0943913 -0.0432943 0.994593 + outer loop + vertex 1.55751 1.43761 2.56297 + vertex 1.55745 1.44254 2.56319 + vertex 1.55228 1.43751 2.56346 + endloop + endfacet + facet normal 0.0944398 -0.0466237 0.994438 + outer loop + vertex 1.55231 1.43248 2.56323 + vertex 1.55751 1.43761 2.56297 + vertex 1.55228 1.43751 2.56346 + endloop + endfacet + facet normal 0.0936879 -0.0458564 0.994545 + outer loop + vertex 1.55755 1.43269 2.56274 + vertex 1.55751 1.43761 2.56297 + vertex 1.55231 1.43248 2.56323 + endloop + endfacet + facet normal 0.0937763 -0.0484369 0.994414 + outer loop + vertex 1.55234 1.4275 2.56298 + vertex 1.55755 1.43269 2.56274 + vertex 1.55231 1.43248 2.56323 + endloop + endfacet + facet normal 0.139858 -0.0479118 0.989012 + outer loop + vertex 1.55234 1.4275 2.56298 + vertex 1.55231 1.43248 2.56323 + vertex 1.54732 1.42761 2.5637 + endloop + endfacet + facet normal 0.139803 -0.0499084 0.988921 + outer loop + vertex 1.54727 1.42251 2.56345 + vertex 1.55234 1.4275 2.56298 + vertex 1.54732 1.42761 2.5637 + endloop + endfacet + facet normal 0.174896 -0.0499692 0.983318 + outer loop + vertex 1.54727 1.42251 2.56345 + vertex 1.54732 1.42761 2.5637 + vertex 1.54261 1.42305 2.5643 + endloop + endfacet + facet normal 0.1746 -0.0524168 0.983243 + outer loop + vertex 1.54243 1.41778 2.56405 + vertex 1.54727 1.42251 2.56345 + vertex 1.54261 1.42305 2.5643 + endloop + endfacet + facet normal 0.192621 -0.0528767 0.979848 + outer loop + vertex 1.54243 1.41778 2.56405 + vertex 1.54261 1.42305 2.5643 + vertex 1.53782 1.41862 2.565 + endloop + endfacet + facet normal 0.191968 -0.0564041 0.979779 + outer loop + vertex 1.53801 1.41327 2.56466 + vertex 1.54243 1.41778 2.56405 + vertex 1.53782 1.41862 2.565 + endloop + endfacet + facet normal 0.204595 -0.055795 0.977255 + outer loop + vertex 1.53782 1.41862 2.565 + vertex 1.53436 1.41391 2.56546 + vertex 1.53801 1.41327 2.56466 + endloop + endfacet + facet normal 0.206145 -0.056974 0.976861 + outer loop + vertex 1.53405 1.41724 2.56572 + vertex 1.53436 1.41391 2.56546 + vertex 1.53782 1.41862 2.565 + endloop + endfacet + facet normal 0.206074 -0.0567654 0.976888 + outer loop + vertex 1.53405 1.41724 2.56572 + vertex 1.53782 1.41862 2.565 + vertex 1.5349 1.4211 2.56576 + endloop + endfacet + facet normal 0.221753 -0.0601698 0.973245 + outer loop + vertex 1.5349 1.4211 2.56576 + vertex 1.53123 1.41771 2.56639 + vertex 1.53405 1.41724 2.56572 + endloop + endfacet + facet normal 0.21844 -0.0564001 0.974219 + outer loop + vertex 1.53156 1.42235 2.56658 + vertex 1.53123 1.41771 2.56639 + vertex 1.5349 1.4211 2.56576 + endloop + endfacet + facet normal 0.218446 -0.0563835 0.974219 + outer loop + vertex 1.53562 1.4259 2.56588 + vertex 1.53156 1.42235 2.56658 + vertex 1.5349 1.4211 2.56576 + endloop + endfacet + facet normal 0.205171 -0.0544467 0.977211 + outer loop + vertex 1.5349 1.4211 2.56576 + vertex 1.53876 1.42432 2.56513 + vertex 1.53562 1.4259 2.56588 + endloop + endfacet + facet normal 0.206146 -0.0524583 0.977114 + outer loop + vertex 1.53876 1.42432 2.56513 + vertex 1.53912 1.4291 2.56531 + vertex 1.53562 1.4259 2.56588 + endloop + endfacet + facet normal 0.203539 -0.0494938 0.977815 + outer loop + vertex 1.53912 1.4291 2.56531 + vertex 1.53648 1.42983 2.5659 + vertex 1.53562 1.4259 2.56588 + endloop + endfacet + facet normal 0.21387 -0.0517446 0.975491 + outer loop + vertex 1.53648 1.42983 2.5659 + vertex 1.53251 1.42799 2.56667 + vertex 1.53562 1.4259 2.56588 + endloop + endfacet + facet normal 0.214187 -0.0512576 0.975447 + outer loop + vertex 1.53251 1.42799 2.56667 + vertex 1.53156 1.42235 2.56658 + vertex 1.53562 1.4259 2.56588 + endloop + endfacet + facet normal 0.211875 -0.0508782 0.975972 + outer loop + vertex 1.53156 1.42235 2.56658 + vertex 1.53251 1.42799 2.56667 + vertex 1.52729 1.42279 2.56754 + endloop + endfacet + facet normal 0.211477 -0.0545061 0.975862 + outer loop + vertex 1.52711 1.41775 2.56729 + vertex 1.53156 1.42235 2.56658 + vertex 1.52729 1.42279 2.56754 + endloop + endfacet + facet normal 0.164342 -0.0533222 0.984961 + outer loop + vertex 1.52711 1.41775 2.56729 + vertex 1.52729 1.42279 2.56754 + vertex 1.5225 1.41776 2.56806 + endloop + endfacet + facet normal 0.210542 -0.0494806 0.976332 + outer loop + vertex 1.52729 1.42279 2.56754 + vertex 1.53251 1.42799 2.56667 + vertex 1.52743 1.42788 2.56776 + endloop + endfacet + facet normal 0.162734 -0.0485565 0.985474 + outer loop + vertex 1.52729 1.42279 2.56754 + vertex 1.52743 1.42788 2.56776 + vertex 1.52241 1.42255 2.56833 + endloop + endfacet + facet normal 0.210497 -0.0457978 0.976521 + outer loop + vertex 1.53251 1.42799 2.56667 + vertex 1.53217 1.43302 2.56698 + vertex 1.52743 1.42788 2.56776 + endloop + endfacet + facet normal 0.208855 -0.0442202 0.976946 + outer loop + vertex 1.52743 1.42788 2.56776 + vertex 1.53217 1.43302 2.56698 + vertex 1.52745 1.43285 2.56798 + endloop + endfacet + facet normal 0.164938 -0.0444133 0.985304 + outer loop + vertex 1.52743 1.42788 2.56776 + vertex 1.52745 1.43285 2.56798 + vertex 1.5224 1.42751 2.56859 + endloop + endfacet + facet normal 0.208693 -0.0381016 0.977239 + outer loop + vertex 1.53217 1.43302 2.56698 + vertex 1.53224 1.43786 2.56716 + vertex 1.52745 1.43285 2.56798 + endloop + endfacet + facet normal 0.207896 -0.0373064 0.977439 + outer loop + vertex 1.52745 1.43285 2.56798 + vertex 1.53224 1.43786 2.56716 + vertex 1.52749 1.43782 2.56816 + endloop + endfacet + facet normal 0.175557 -0.037261 0.983764 + outer loop + vertex 1.52745 1.43285 2.56798 + vertex 1.52749 1.43782 2.56816 + vertex 1.5224 1.43254 2.56887 + endloop + endfacet + facet normal 0.207893 -0.0306383 0.977672 + outer loop + vertex 1.53224 1.43786 2.56716 + vertex 1.53234 1.44275 2.56729 + vertex 1.52749 1.43782 2.56816 + endloop + endfacet + facet normal 0.206406 -0.0291134 0.978033 + outer loop + vertex 1.52749 1.43782 2.56816 + vertex 1.53234 1.44275 2.56729 + vertex 1.52752 1.44285 2.56831 + endloop + endfacet + facet normal 0.196799 -0.0291081 0.980012 + outer loop + vertex 1.52749 1.43782 2.56816 + vertex 1.52752 1.44285 2.56831 + vertex 1.52236 1.43772 2.56919 + endloop + endfacet + facet normal 0.206488 -0.0259795 0.978104 + outer loop + vertex 1.53234 1.44275 2.56729 + vertex 1.53239 1.44767 2.56741 + vertex 1.52752 1.44285 2.56831 + endloop + endfacet + facet normal 0.201352 -0.0205683 0.979303 + outer loop + vertex 1.52752 1.44285 2.56831 + vertex 1.53239 1.44767 2.56741 + vertex 1.52756 1.44789 2.56841 + endloop + endfacet + facet normal 0.218053 -0.0206247 0.975719 + outer loop + vertex 1.52752 1.44285 2.56831 + vertex 1.52756 1.44789 2.56841 + vertex 1.52246 1.44302 2.56944 + endloop + endfacet + facet normal 0.222992 -0.0260588 0.974472 + outer loop + vertex 1.52246 1.44302 2.56944 + vertex 1.52756 1.44789 2.56841 + vertex 1.52269 1.44824 2.56953 + endloop + endfacet + facet normal 0.223455 -0.0197985 0.974513 + outer loop + vertex 1.52756 1.44789 2.56841 + vertex 1.52761 1.45289 2.56849 + vertex 1.52269 1.44824 2.56953 + endloop + endfacet + facet normal 0.219352 -0.0152274 0.975527 + outer loop + vertex 1.52269 1.44824 2.56953 + vertex 1.52761 1.45289 2.56849 + vertex 1.52283 1.4533 2.56958 + endloop + endfacet + facet normal 0.249865 -0.0159707 0.968149 + outer loop + vertex 1.52269 1.44824 2.56953 + vertex 1.52283 1.4533 2.56958 + vertex 1.51857 1.44908 2.57061 + endloop + endfacet + facet normal 0.247917 -0.025956 0.968433 + outer loop + vertex 1.51819 1.44391 2.57057 + vertex 1.52269 1.44824 2.56953 + vertex 1.51857 1.44908 2.57061 + endloop + endfacet + facet normal 0.218425 -0.0259357 0.975509 + outer loop + vertex 1.52761 1.45289 2.56849 + vertex 1.52763 1.4579 2.56862 + vertex 1.52283 1.4533 2.56958 + endloop + endfacet + facet normal 0.218093 -0.0255704 0.975593 + outer loop + vertex 1.52283 1.4533 2.56958 + vertex 1.52763 1.4579 2.56862 + vertex 1.52281 1.4583 2.56971 + endloop + endfacet + facet normal 0.24765 -0.0252959 0.968519 + outer loop + vertex 1.52283 1.4533 2.56958 + vertex 1.52281 1.4583 2.56971 + vertex 1.5188 1.45407 2.57063 + endloop + endfacet + facet normal 0.250153 -0.0278189 0.967806 + outer loop + vertex 1.5188 1.45407 2.57063 + vertex 1.52281 1.4583 2.56971 + vertex 1.51885 1.45865 2.57075 + endloop + endfacet + facet normal 0.217422 -0.0332873 0.97551 + outer loop + vertex 1.52763 1.4579 2.56862 + vertex 1.52755 1.46298 2.56881 + vertex 1.52281 1.4583 2.56971 + endloop + endfacet + facet normal 0.22251 -0.0387073 0.974162 + outer loop + vertex 1.52281 1.4583 2.56971 + vertex 1.52755 1.46298 2.56881 + vertex 1.52232 1.4635 2.57003 + endloop + endfacet + facet normal 0.223125 -0.0327353 0.97424 + outer loop + vertex 1.52755 1.46298 2.56881 + vertex 1.52762 1.46819 2.56897 + vertex 1.52232 1.4635 2.57003 + endloop + endfacet + facet normal 0.22328 -0.0329202 0.974198 + outer loop + vertex 1.52232 1.4635 2.57003 + vertex 1.52762 1.46819 2.56897 + vertex 1.52315 1.46921 2.57003 + endloop + endfacet + facet normal 0.22433 -0.0282282 0.974104 + outer loop + vertex 1.52762 1.46819 2.56897 + vertex 1.52784 1.47338 2.56908 + vertex 1.52315 1.46921 2.57003 + endloop + endfacet + facet normal 0.195027 -0.0271448 0.980422 + outer loop + vertex 1.52762 1.46819 2.56897 + vertex 1.53259 1.47285 2.56811 + vertex 1.52784 1.47338 2.56908 + endloop + endfacet + facet normal 0.195706 -0.0210837 0.980436 + outer loop + vertex 1.53259 1.47285 2.56811 + vertex 1.53263 1.47787 2.56821 + vertex 1.52784 1.47338 2.56908 + endloop + endfacet + facet normal 0.197485 -0.0230596 0.980035 + outer loop + vertex 1.52784 1.47338 2.56908 + vertex 1.53263 1.47787 2.56821 + vertex 1.52793 1.47842 2.56917 + endloop + endfacet + facet normal 0.228089 -0.0235143 0.973356 + outer loop + vertex 1.52784 1.47338 2.56908 + vertex 1.52793 1.47842 2.56917 + vertex 1.52345 1.47434 2.57013 + endloop + endfacet + facet normal 0.229099 -0.0246858 0.97309 + outer loop + vertex 1.52345 1.47434 2.57013 + vertex 1.52793 1.47842 2.56917 + vertex 1.52358 1.47936 2.57022 + endloop + endfacet + facet normal 0.230347 -0.0187137 0.972929 + outer loop + vertex 1.52793 1.47842 2.56917 + vertex 1.52797 1.48341 2.56926 + vertex 1.52358 1.47936 2.57022 + endloop + endfacet + facet normal 0.198974 -0.0186288 0.979828 + outer loop + vertex 1.52793 1.47842 2.56917 + vertex 1.53265 1.48285 2.5683 + vertex 1.52797 1.48341 2.56926 + endloop + endfacet + facet normal 0.199437 -0.0146702 0.979801 + outer loop + vertex 1.53265 1.48285 2.5683 + vertex 1.53266 1.48783 2.56837 + vertex 1.52797 1.48341 2.56926 + endloop + endfacet + facet normal 0.198496 -0.0136293 0.980007 + outer loop + vertex 1.52797 1.48341 2.56926 + vertex 1.53266 1.48783 2.56837 + vertex 1.52798 1.48839 2.56933 + endloop + endfacet + facet normal 0.231128 -0.0135972 0.972828 + outer loop + vertex 1.52797 1.48341 2.56926 + vertex 1.52798 1.48839 2.56933 + vertex 1.52363 1.48435 2.57031 + endloop + endfacet + facet normal 0.230112 -0.0184458 0.972989 + outer loop + vertex 1.52358 1.47936 2.57022 + vertex 1.52797 1.48341 2.56926 + vertex 1.52363 1.48435 2.57031 + endloop + endfacet + facet normal 0.258222 -0.0185958 0.965907 + outer loop + vertex 1.52358 1.47936 2.57022 + vertex 1.52363 1.48435 2.57031 + vertex 1.51981 1.48047 2.57125 + endloop + endfacet + facet normal 0.256629 -0.0242694 0.966205 + outer loop + vertex 1.51971 1.47546 2.57115 + vertex 1.52358 1.47936 2.57022 + vertex 1.51981 1.48047 2.57125 + endloop + endfacet + facet normal 0.189722 -0.0231368 0.981565 + outer loop + vertex 1.51981 1.48047 2.57125 + vertex 1.51658 1.47653 2.57178 + vertex 1.51971 1.47546 2.57115 + endloop + endfacet + facet normal 0.181751 -0.0163736 0.983208 + outer loop + vertex 1.51666 1.48154 2.57185 + vertex 1.51658 1.47653 2.57178 + vertex 1.51981 1.48047 2.57125 + endloop + endfacet + facet normal 0.182227 -0.0149375 0.983143 + outer loop + vertex 1.51988 1.48547 2.57131 + vertex 1.51666 1.48154 2.57185 + vertex 1.51981 1.48047 2.57125 + endloop + endfacet + facet normal 0.255509 -0.0157456 0.966678 + outer loop + vertex 1.51981 1.48047 2.57125 + vertex 1.52363 1.48435 2.57031 + vertex 1.51988 1.48547 2.57131 + endloop + endfacet + facet normal 0.25645 -0.0124185 0.966478 + outer loop + vertex 1.52363 1.48435 2.57031 + vertex 1.52366 1.48934 2.57036 + vertex 1.51988 1.48547 2.57131 + endloop + endfacet + facet normal 0.254645 -0.0105336 0.966977 + outer loop + vertex 1.51988 1.48547 2.57131 + vertex 1.52366 1.48934 2.57036 + vertex 1.51992 1.49047 2.57136 + endloop + endfacet + facet normal 0.175692 -0.0100677 0.984394 + outer loop + vertex 1.51992 1.49047 2.57136 + vertex 1.51672 1.48655 2.57189 + vertex 1.51988 1.48547 2.57131 + endloop + endfacet + facet normal 0.255281 -0.00829174 0.966831 + outer loop + vertex 1.52366 1.48934 2.57036 + vertex 1.5237 1.49434 2.57039 + vertex 1.51992 1.49047 2.57136 + endloop + endfacet + facet normal 0.254703 -0.00768892 0.966989 + outer loop + vertex 1.51992 1.49047 2.57136 + vertex 1.5237 1.49434 2.57039 + vertex 1.51997 1.49546 2.57139 + endloop + endfacet + facet normal 0.175002 -0.00704119 0.984543 + outer loop + vertex 1.51997 1.49546 2.57139 + vertex 1.51674 1.49154 2.57193 + vertex 1.51992 1.49047 2.57136 + endloop + endfacet + facet normal 0.254766 -0.00746739 0.966974 + outer loop + vertex 1.5237 1.49434 2.57039 + vertex 1.52374 1.49933 2.57042 + vertex 1.51997 1.49546 2.57139 + endloop + endfacet + facet normal 0.255784 -0.00852856 0.966696 + outer loop + vertex 1.51997 1.49546 2.57139 + vertex 1.52374 1.49933 2.57042 + vertex 1.52004 1.50046 2.57141 + endloop + endfacet + facet normal 0.171738 -0.0074749 0.985114 + outer loop + vertex 1.52004 1.50046 2.57141 + vertex 1.51679 1.49654 2.57195 + vertex 1.51997 1.49546 2.57139 + endloop + endfacet + facet normal 0.255979 -0.00784568 0.96665 + outer loop + vertex 1.52374 1.49933 2.57042 + vertex 1.5238 1.50432 2.57045 + vertex 1.52004 1.50046 2.57141 + endloop + endfacet + facet normal 0.256826 -0.00872724 0.966418 + outer loop + vertex 1.52004 1.50046 2.57141 + vertex 1.5238 1.50432 2.57045 + vertex 1.52011 1.50545 2.57144 + endloop + endfacet + facet normal 0.173785 -0.00759566 0.984754 + outer loop + vertex 1.52011 1.50545 2.57144 + vertex 1.51685 1.50153 2.57198 + vertex 1.52004 1.50046 2.57141 + endloop + endfacet + facet normal 0.257333 -0.00696293 0.966298 + outer loop + vertex 1.5238 1.50432 2.57045 + vertex 1.52387 1.50932 2.57046 + vertex 1.52011 1.50545 2.57144 + endloop + endfacet + facet normal 0.257077 -0.00669698 0.966368 + outer loop + vertex 1.52011 1.50545 2.57144 + vertex 1.52387 1.50932 2.57046 + vertex 1.52017 1.51044 2.57146 + endloop + endfacet + facet normal 0.171548 -0.00578529 0.985159 + outer loop + vertex 1.52017 1.51044 2.57146 + vertex 1.51691 1.50652 2.572 + vertex 1.52011 1.50545 2.57144 + endloop + endfacet + facet normal 0.257948 -0.00364266 0.966152 + outer loop + vertex 1.52387 1.50932 2.57046 + vertex 1.52391 1.51431 2.57047 + vertex 1.52017 1.51044 2.57146 + endloop + endfacet + facet normal 0.25635 -0.00198862 0.966582 + outer loop + vertex 1.52017 1.51044 2.57146 + vertex 1.52391 1.51431 2.57047 + vertex 1.52019 1.51543 2.57146 + endloop + endfacet + facet normal 0.169613 -0.00167922 0.985509 + outer loop + vertex 1.52019 1.51543 2.57146 + vertex 1.51694 1.51152 2.57201 + vertex 1.52017 1.51044 2.57146 + endloop + endfacet + facet normal 0.257329 0.0014649 0.966323 + outer loop + vertex 1.52391 1.51431 2.57047 + vertex 1.5239 1.5193 2.57047 + vertex 1.52019 1.51543 2.57146 + endloop + endfacet + facet normal 0.255419 0.00342988 0.966824 + outer loop + vertex 1.52019 1.51543 2.57146 + vertex 1.5239 1.5193 2.57047 + vertex 1.52014 1.52042 2.57146 + endloop + endfacet + facet normal 0.173874 0.00274078 0.984764 + outer loop + vertex 1.52014 1.52042 2.57146 + vertex 1.51692 1.5165 2.57204 + vertex 1.52019 1.51543 2.57146 + endloop + endfacet + facet normal 0.256593 0.00763578 0.966489 + outer loop + vertex 1.5239 1.5193 2.57047 + vertex 1.52385 1.52428 2.57044 + vertex 1.52014 1.52042 2.57146 + endloop + endfacet + facet normal 0.2527 0.0116344 0.967475 + outer loop + vertex 1.52014 1.52042 2.57146 + vertex 1.52385 1.52428 2.57044 + vertex 1.52005 1.52541 2.57142 + endloop + endfacet + facet normal 0.167198 0.0101609 0.985871 + outer loop + vertex 1.52005 1.52541 2.57142 + vertex 1.51686 1.5215 2.572 + vertex 1.52014 1.52042 2.57146 + endloop + endfacet + facet normal 0.252983 0.0126633 0.967388 + outer loop + vertex 1.52385 1.52428 2.57044 + vertex 1.52375 1.52927 2.5704 + vertex 1.52005 1.52541 2.57142 + endloop + endfacet + facet normal 0.249531 0.0161973 0.968231 + outer loop + vertex 1.52005 1.52541 2.57142 + vertex 1.52375 1.52927 2.5704 + vertex 1.51992 1.5304 2.57137 + endloop + endfacet + facet normal 0.166502 0.0141359 0.98594 + outer loop + vertex 1.51992 1.5304 2.57137 + vertex 1.51675 1.52649 2.57196 + vertex 1.52005 1.52541 2.57142 + endloop + endfacet + facet normal 0.249831 0.0172982 0.968135 + outer loop + vertex 1.52375 1.52927 2.5704 + vertex 1.52366 1.53428 2.57034 + vertex 1.51992 1.5304 2.57137 + endloop + endfacet + facet normal 0.247664 0.0195305 0.968649 + outer loop + vertex 1.51992 1.5304 2.57137 + vertex 1.52366 1.53428 2.57034 + vertex 1.51978 1.53541 2.57131 + endloop + endfacet + facet normal 0.169516 0.017636 0.98537 + outer loop + vertex 1.51978 1.53541 2.57131 + vertex 1.51662 1.53148 2.57192 + vertex 1.51992 1.5304 2.57137 + endloop + endfacet + facet normal 0.247782 0.0199721 0.96861 + outer loop + vertex 1.52366 1.53428 2.57034 + vertex 1.52358 1.53931 2.57025 + vertex 1.51978 1.53541 2.57131 + endloop + endfacet + facet normal 0.247961 0.0197863 0.968568 + outer loop + vertex 1.51978 1.53541 2.57131 + vertex 1.52358 1.53931 2.57025 + vertex 1.51966 1.54042 2.57123 + endloop + endfacet + facet normal 0.173227 0.0182072 0.984714 + outer loop + vertex 1.51966 1.54042 2.57123 + vertex 1.5165 1.53648 2.57186 + vertex 1.51978 1.53541 2.57131 + endloop + endfacet + facet normal 0.248674 0.022525 0.968325 + outer loop + vertex 1.52358 1.53931 2.57025 + vertex 1.52352 1.54433 2.57015 + vertex 1.51966 1.54042 2.57123 + endloop + endfacet + facet normal 0.249544 0.0216109 0.968122 + outer loop + vertex 1.51966 1.54042 2.57123 + vertex 1.52352 1.54433 2.57015 + vertex 1.51954 1.54538 2.57115 + endloop + endfacet + facet normal 0.176586 0.0200847 0.98408 + outer loop + vertex 1.51954 1.54538 2.57115 + vertex 1.5164 1.54147 2.5718 + vertex 1.51966 1.54042 2.57123 + endloop + endfacet + facet normal 0.250373 0.0250177 0.967826 + outer loop + vertex 1.52352 1.54433 2.57015 + vertex 1.52338 1.54929 2.57006 + vertex 1.51954 1.54538 2.57115 + endloop + endfacet + facet normal 0.252338 0.0229534 0.967367 + outer loop + vertex 1.51954 1.54538 2.57115 + vertex 1.52338 1.54929 2.57006 + vertex 1.51929 1.55028 2.5711 + endloop + endfacet + facet normal 0.185515 0.0197668 0.982443 + outer loop + vertex 1.51929 1.55028 2.5711 + vertex 1.51626 1.5464 2.57175 + vertex 1.51954 1.54538 2.57115 + endloop + endfacet + facet normal 0.253818 0.029651 0.966797 + outer loop + vertex 1.52338 1.54929 2.57006 + vertex 1.52307 1.55424 2.56999 + vertex 1.51929 1.55028 2.5711 + endloop + endfacet + facet normal 0.252908 0.0305799 0.967007 + outer loop + vertex 1.51929 1.55028 2.5711 + vertex 1.52307 1.55424 2.56999 + vertex 1.51881 1.5551 2.57108 + endloop + endfacet + facet normal 0.189571 0.0243565 0.981565 + outer loop + vertex 1.51881 1.5551 2.57108 + vertex 1.51596 1.55131 2.57172 + vertex 1.51929 1.55028 2.5711 + endloop + endfacet + facet normal 0.254014 0.0366408 0.966506 + outer loop + vertex 1.52307 1.55424 2.56999 + vertex 1.52247 1.55955 2.56994 + vertex 1.51881 1.5551 2.57108 + endloop + endfacet + facet normal 0.254699 0.036037 0.966349 + outer loop + vertex 1.51815 1.55906 2.5711 + vertex 1.51881 1.5551 2.57108 + vertex 1.52247 1.55955 2.56994 + endloop + endfacet + facet normal 0.227003 0.0336736 0.973312 + outer loop + vertex 1.52307 1.55424 2.56999 + vertex 1.52761 1.55826 2.56879 + vertex 1.52247 1.55955 2.56994 + endloop + endfacet + facet normal 0.227701 0.0366868 0.97304 + outer loop + vertex 1.52761 1.55826 2.56879 + vertex 1.52772 1.5632 2.56858 + vertex 1.52247 1.55955 2.56994 + endloop + endfacet + facet normal 0.218876 0.0499049 0.974476 + outer loop + vertex 1.52247 1.55955 2.56994 + vertex 1.52772 1.5632 2.56858 + vertex 1.52395 1.56432 2.56937 + endloop + endfacet + facet normal 0.251458 0.0389247 0.967085 + outer loop + vertex 1.51943 1.5636 2.57057 + vertex 1.52247 1.55955 2.56994 + vertex 1.52395 1.56432 2.56937 + endloop + endfacet + facet normal 0.252909 0.0296383 0.967036 + outer loop + vertex 1.52395 1.56432 2.56937 + vertex 1.52318 1.56826 2.56945 + vertex 1.51943 1.5636 2.57057 + endloop + endfacet + facet normal 0.224639 0.0240144 0.974146 + outer loop + vertex 1.52395 1.56432 2.56937 + vertex 1.52781 1.56794 2.56839 + vertex 1.52318 1.56826 2.56945 + endloop + endfacet + facet normal 0.224886 0.0281607 0.973978 + outer loop + vertex 1.52781 1.56794 2.56839 + vertex 1.52756 1.57271 2.56831 + vertex 1.52318 1.56826 2.56945 + endloop + endfacet + facet normal 0.232483 0.0202825 0.972389 + outer loop + vertex 1.52318 1.56826 2.56945 + vertex 1.52756 1.57271 2.56831 + vertex 1.52274 1.57316 2.56945 + endloop + endfacet + facet normal 0.250681 0.0219211 0.967822 + outer loop + vertex 1.52318 1.56826 2.56945 + vertex 1.52274 1.57316 2.56945 + vertex 1.51871 1.56896 2.57059 + endloop + endfacet + facet normal 0.243723 0.0290242 0.96941 + outer loop + vertex 1.51871 1.56896 2.57059 + vertex 1.52274 1.57316 2.56945 + vertex 1.51812 1.57401 2.57059 + endloop + endfacet + facet normal 0.243558 0.0280277 0.969481 + outer loop + vertex 1.52274 1.57316 2.56945 + vertex 1.52247 1.57819 2.56938 + vertex 1.51812 1.57401 2.57059 + endloop + endfacet + facet normal 0.231738 0.0274232 0.972392 + outer loop + vertex 1.52274 1.57316 2.56945 + vertex 1.52728 1.57753 2.56825 + vertex 1.52247 1.57819 2.56938 + endloop + endfacet + facet normal 0.231525 0.0257031 0.972489 + outer loop + vertex 1.52728 1.57753 2.56825 + vertex 1.52732 1.58239 2.56811 + vertex 1.52247 1.57819 2.56938 + endloop + endfacet + facet normal 0.222881 0.0362003 0.974173 + outer loop + vertex 1.52247 1.57819 2.56938 + vertex 1.52732 1.58239 2.56811 + vertex 1.52258 1.58316 2.56916 + endloop + endfacet + facet normal 0.187823 0.0373067 0.981494 + outer loop + vertex 1.52247 1.57819 2.56938 + vertex 1.52258 1.58316 2.56916 + vertex 1.51749 1.5792 2.57029 + endloop + endfacet + facet normal 0.22208 0.0307496 0.974544 + outer loop + vertex 1.52732 1.58239 2.56811 + vertex 1.52739 1.58742 2.56793 + vertex 1.52258 1.58316 2.56916 + endloop + endfacet + facet normal 0.205051 0.050793 0.977432 + outer loop + vertex 1.52258 1.58316 2.56916 + vertex 1.52739 1.58742 2.56793 + vertex 1.52266 1.58789 2.5689 + endloop + endfacet + facet normal 0.203839 0.0368169 0.978312 + outer loop + vertex 1.52739 1.58742 2.56793 + vertex 1.52709 1.59244 2.56781 + vertex 1.52266 1.58789 2.5689 + endloop + endfacet + facet normal 0.223443 0.0378616 0.973981 + outer loop + vertex 1.52739 1.58742 2.56793 + vertex 1.53157 1.59172 2.56681 + vertex 1.52709 1.59244 2.56781 + endloop + endfacet + facet normal 0.224316 0.0438986 0.973527 + outer loop + vertex 1.53157 1.59172 2.56681 + vertex 1.53097 1.59681 2.56672 + vertex 1.52709 1.59244 2.56781 + endloop + endfacet + facet normal 0.224568 0.043664 0.97348 + outer loop + vertex 1.52709 1.59244 2.56781 + vertex 1.53097 1.59681 2.56672 + vertex 1.52662 1.59731 2.5677 + endloop + endfacet + facet normal 0.181479 0.0396803 0.982594 + outer loop + vertex 1.52709 1.59244 2.56781 + vertex 1.52662 1.59731 2.5677 + vertex 1.52239 1.59259 2.56867 + endloop + endfacet + facet normal 0.219163 0.0422396 0.974774 + outer loop + vertex 1.53231 1.58624 2.56688 + vertex 1.53157 1.59172 2.56681 + vertex 1.52739 1.58742 2.56793 + endloop + endfacet + facet normal 0.207441 0.0407076 0.9774 + outer loop + vertex 1.53157 1.59172 2.56681 + vertex 1.53231 1.58624 2.56688 + vertex 1.53567 1.59066 2.56598 + endloop + endfacet + facet normal 0.209843 0.0507588 0.976417 + outer loop + vertex 1.53498 1.5956 2.56587 + vertex 1.53157 1.59172 2.56681 + vertex 1.53567 1.59066 2.56598 + endloop + endfacet + facet normal 0.193277 0.0485143 0.979944 + outer loop + vertex 1.53567 1.59066 2.56598 + vertex 1.5389 1.59415 2.56517 + vertex 1.53498 1.5956 2.56587 + endloop + endfacet + facet normal 0.19031 0.0513606 0.98038 + outer loop + vertex 1.5397 1.58894 2.56529 + vertex 1.5389 1.59415 2.56517 + vertex 1.53567 1.59066 2.56598 + endloop + endfacet + facet normal 0.18922 0.0486599 0.980728 + outer loop + vertex 1.53639 1.58668 2.56604 + vertex 1.5397 1.58894 2.56529 + vertex 1.53567 1.59066 2.56598 + endloop + endfacet + facet normal 0.188832 0.0492424 0.980774 + outer loop + vertex 1.53864 1.58469 2.56571 + vertex 1.5397 1.58894 2.56529 + vertex 1.53639 1.58668 2.56604 + endloop + endfacet + facet normal 0.184459 0.0441068 0.98185 + outer loop + vertex 1.53639 1.58668 2.56604 + vertex 1.53527 1.58215 2.56645 + vertex 1.53864 1.58469 2.56571 + endloop + endfacet + facet normal 0.185792 0.042283 0.981679 + outer loop + vertex 1.53927 1.58064 2.56576 + vertex 1.53864 1.58469 2.56571 + vertex 1.53527 1.58215 2.56645 + endloop + endfacet + facet normal 0.196948 0.040797 0.979565 + outer loop + vertex 1.53639 1.58668 2.56604 + vertex 1.53231 1.58624 2.56688 + vertex 1.53527 1.58215 2.56645 + endloop + endfacet + facet normal 0.191637 0.0368203 0.980775 + outer loop + vertex 1.53231 1.58624 2.56688 + vertex 1.53105 1.58128 2.56731 + vertex 1.53527 1.58215 2.56645 + endloop + endfacet + facet normal 0.192561 0.0323285 0.980752 + outer loop + vertex 1.53179 1.57728 2.5673 + vertex 1.53527 1.58215 2.56645 + vertex 1.53105 1.58128 2.56731 + endloop + endfacet + facet normal 0.20758 0.0351162 0.977587 + outer loop + vertex 1.53179 1.57728 2.5673 + vertex 1.53105 1.58128 2.56731 + vertex 1.52728 1.57753 2.56825 + endloop + endfacet + facet normal 0.207097 0.0246495 0.97801 + outer loop + vertex 1.52756 1.57271 2.56831 + vertex 1.53179 1.57728 2.5673 + vertex 1.52728 1.57753 2.56825 + endloop + endfacet + facet normal 0.197905 0.0335059 0.979648 + outer loop + vertex 1.53213 1.5724 2.5674 + vertex 1.53179 1.57728 2.5673 + vertex 1.52756 1.57271 2.56831 + endloop + endfacet + facet normal 0.184043 0.0325883 0.982378 + outer loop + vertex 1.53213 1.5724 2.5674 + vertex 1.53595 1.57683 2.56653 + vertex 1.53179 1.57728 2.5673 + endloop + endfacet + facet normal 0.184605 0.0382503 0.982068 + outer loop + vertex 1.53595 1.57683 2.56653 + vertex 1.53527 1.58215 2.56645 + vertex 1.53179 1.57728 2.5673 + endloop + endfacet + facet normal 0.217418 0.0298248 0.975623 + outer loop + vertex 1.53105 1.58128 2.56731 + vertex 1.53231 1.58624 2.56688 + vertex 1.52732 1.58239 2.56811 + endloop + endfacet + facet normal 0.195929 0.0498631 0.979349 + outer loop + vertex 1.53567 1.59066 2.56598 + vertex 1.53231 1.58624 2.56688 + vertex 1.53639 1.58668 2.56604 + endloop + endfacet + facet normal 0.216647 0.0308692 0.975762 + outer loop + vertex 1.52732 1.58239 2.56811 + vertex 1.53231 1.58624 2.56688 + vertex 1.52739 1.58742 2.56793 + endloop + endfacet + facet normal 0.216333 0.0259191 0.975976 + outer loop + vertex 1.52728 1.57753 2.56825 + vertex 1.53105 1.58128 2.56731 + vertex 1.52732 1.58239 2.56811 + endloop + endfacet + facet normal 0.232967 0.0260754 0.972135 + outer loop + vertex 1.52756 1.57271 2.56831 + vertex 1.52728 1.57753 2.56825 + vertex 1.52274 1.57316 2.56945 + endloop + endfacet + facet normal 0.197515 0.0268377 0.979933 + outer loop + vertex 1.52781 1.56794 2.56839 + vertex 1.53213 1.5724 2.5674 + vertex 1.52756 1.57271 2.56831 + endloop + endfacet + facet normal 0.190963 0.033427 0.981028 + outer loop + vertex 1.53227 1.56742 2.56754 + vertex 1.53213 1.5724 2.5674 + vertex 1.52781 1.56794 2.56839 + endloop + endfacet + facet normal 0.191198 0.0356416 0.980904 + outer loop + vertex 1.52772 1.5632 2.56858 + vertex 1.53227 1.56742 2.56754 + vertex 1.52781 1.56794 2.56839 + endloop + endfacet + facet normal 0.192239 0.0344798 0.980742 + outer loop + vertex 1.53239 1.56236 2.56769 + vertex 1.53227 1.56742 2.56754 + vertex 1.52772 1.5632 2.56858 + endloop + endfacet + facet normal 0.182657 0.0343109 0.982578 + outer loop + vertex 1.53239 1.56236 2.56769 + vertex 1.53658 1.5666 2.56677 + vertex 1.53227 1.56742 2.56754 + endloop + endfacet + facet normal 0.182313 0.0323827 0.982707 + outer loop + vertex 1.53658 1.5666 2.56677 + vertex 1.53628 1.57175 2.56665 + vertex 1.53227 1.56742 2.56754 + endloop + endfacet + facet normal 0.181453 0.0332074 0.982839 + outer loop + vertex 1.53227 1.56742 2.56754 + vertex 1.53628 1.57175 2.56665 + vertex 1.53213 1.5724 2.5674 + endloop + endfacet + facet normal 0.214788 0.0350027 0.976033 + outer loop + vertex 1.52772 1.5632 2.56858 + vertex 1.52781 1.56794 2.56839 + vertex 1.52395 1.56432 2.56937 + endloop + endfacet + facet normal 0.192789 0.0377803 0.980513 + outer loop + vertex 1.52761 1.55826 2.56879 + vertex 1.53239 1.56236 2.56769 + vertex 1.52772 1.5632 2.56858 + endloop + endfacet + facet normal 0.19583 0.0341108 0.980044 + outer loop + vertex 1.53236 1.55733 2.56787 + vertex 1.53239 1.56236 2.56769 + vertex 1.52761 1.55826 2.56879 + endloop + endfacet + facet normal 0.195359 0.0315217 0.980225 + outer loop + vertex 1.52779 1.55329 2.56891 + vertex 1.53236 1.55733 2.56787 + vertex 1.52761 1.55826 2.56879 + endloop + endfacet + facet normal 0.194642 0.0323628 0.98034 + outer loop + vertex 1.53239 1.55256 2.56803 + vertex 1.53236 1.55733 2.56787 + vertex 1.52779 1.55329 2.56891 + endloop + endfacet + facet normal 0.194063 0.0284618 0.980576 + outer loop + vertex 1.52793 1.54838 2.56903 + vertex 1.53239 1.55256 2.56803 + vertex 1.52779 1.55329 2.56891 + endloop + endfacet + facet normal 0.226132 0.0292222 0.973658 + outer loop + vertex 1.52793 1.54838 2.56903 + vertex 1.52779 1.55329 2.56891 + vertex 1.52338 1.54929 2.57006 + endloop + endfacet + facet normal 0.193326 0.0292777 0.980698 + outer loop + vertex 1.5326 1.54779 2.56813 + vertex 1.53239 1.55256 2.56803 + vertex 1.52793 1.54838 2.56903 + endloop + endfacet + facet normal 0.192775 0.0245646 0.980936 + outer loop + vertex 1.52799 1.54339 2.56914 + vertex 1.5326 1.54779 2.56813 + vertex 1.52793 1.54838 2.56903 + endloop + endfacet + facet normal 0.224941 0.0248052 0.974057 + outer loop + vertex 1.52799 1.54339 2.56914 + vertex 1.52793 1.54838 2.56903 + vertex 1.52352 1.54433 2.57015 + endloop + endfacet + facet normal 0.193405 0.0238787 0.980828 + outer loop + vertex 1.53268 1.54281 2.56823 + vertex 1.5326 1.54779 2.56813 + vertex 1.52799 1.54339 2.56914 + endloop + endfacet + facet normal 0.193073 0.0210142 0.980959 + outer loop + vertex 1.52801 1.53835 2.56925 + vertex 1.53268 1.54281 2.56823 + vertex 1.52799 1.54339 2.56914 + endloop + endfacet + facet normal 0.225673 0.0209772 0.973977 + outer loop + vertex 1.52801 1.53835 2.56925 + vertex 1.52799 1.54339 2.56914 + vertex 1.52358 1.53931 2.57025 + endloop + endfacet + facet normal 0.195713 0.0181416 0.980493 + outer loop + vertex 1.53267 1.53778 2.56833 + vertex 1.53268 1.54281 2.56823 + vertex 1.52801 1.53835 2.56925 + endloop + endfacet + facet normal 0.195512 0.0164159 0.980564 + outer loop + vertex 1.52803 1.53332 2.56933 + vertex 1.53267 1.53778 2.56833 + vertex 1.52801 1.53835 2.56925 + endloop + endfacet + facet normal 0.228316 0.016424 0.973449 + outer loop + vertex 1.52803 1.53332 2.56933 + vertex 1.52801 1.53835 2.56925 + vertex 1.52366 1.53428 2.57034 + endloop + endfacet + facet normal 0.198357 0.0133369 0.980039 + outer loop + vertex 1.53266 1.53275 2.5684 + vertex 1.53267 1.53778 2.56833 + vertex 1.52803 1.53332 2.56933 + endloop + endfacet + facet normal 0.198277 0.0126308 0.980065 + outer loop + vertex 1.52807 1.52831 2.56938 + vertex 1.53266 1.53275 2.5684 + vertex 1.52803 1.53332 2.56933 + endloop + endfacet + facet normal 0.232172 0.0128144 0.97259 + outer loop + vertex 1.52807 1.52831 2.56938 + vertex 1.52803 1.53332 2.56933 + vertex 1.52375 1.52927 2.5704 + endloop + endfacet + facet normal 0.200438 0.0103041 0.979652 + outer loop + vertex 1.53267 1.52775 2.56845 + vertex 1.53266 1.53275 2.5684 + vertex 1.52807 1.52831 2.56938 + endloop + endfacet + facet normal 0.200286 0.00897567 0.979696 + outer loop + vertex 1.5281 1.52332 2.56942 + vertex 1.53267 1.52775 2.56845 + vertex 1.52807 1.52831 2.56938 + endloop + endfacet + facet normal 0.234896 0.00916514 0.971977 + outer loop + vertex 1.5281 1.52332 2.56942 + vertex 1.52807 1.52831 2.56938 + vertex 1.52385 1.52428 2.57044 + endloop + endfacet + facet normal 0.200961 0.00825082 0.979565 + outer loop + vertex 1.5327 1.52276 2.56849 + vertex 1.53267 1.52775 2.56845 + vertex 1.5281 1.52332 2.56942 + endloop + endfacet + facet normal 0.200656 0.00559958 0.979646 + outer loop + vertex 1.52813 1.51834 2.56945 + vertex 1.5327 1.52276 2.56849 + vertex 1.5281 1.52332 2.56942 + endloop + endfacet + facet normal 0.236117 0.00571395 0.971708 + outer loop + vertex 1.52813 1.51834 2.56945 + vertex 1.5281 1.52332 2.56942 + vertex 1.5239 1.5193 2.57047 + endloop + endfacet + facet normal 0.201093 0.00512915 0.979559 + outer loop + vertex 1.53271 1.51777 2.56851 + vertex 1.5327 1.52276 2.56849 + vertex 1.52813 1.51834 2.56945 + endloop + endfacet + facet normal 0.200587 0.000835879 0.979676 + outer loop + vertex 1.52811 1.51335 2.56945 + vertex 1.53271 1.51777 2.56851 + vertex 1.52813 1.51834 2.56945 + endloop + endfacet + facet normal 0.23586 0.000707635 0.971787 + outer loop + vertex 1.52811 1.51335 2.56945 + vertex 1.52813 1.51834 2.56945 + vertex 1.52391 1.51431 2.57047 + endloop + endfacet + facet normal 0.199373 0.00214816 0.979921 + outer loop + vertex 1.5327 1.51279 2.56852 + vertex 1.53271 1.51777 2.56851 + vertex 1.52811 1.51335 2.56945 + endloop + endfacet + facet normal 0.198861 -0.00222407 0.980025 + outer loop + vertex 1.52808 1.50836 2.56945 + vertex 1.5327 1.51279 2.56852 + vertex 1.52811 1.51335 2.56945 + endloop + endfacet + facet normal 0.233995 -0.00243539 0.972235 + outer loop + vertex 1.52808 1.50836 2.56945 + vertex 1.52811 1.51335 2.56945 + vertex 1.52387 1.50932 2.57046 + endloop + endfacet + facet normal 0.197745 -0.00100962 0.980253 + outer loop + vertex 1.53269 1.50779 2.56852 + vertex 1.5327 1.51279 2.56852 + vertex 1.52808 1.50836 2.56945 + endloop + endfacet + facet normal 0.197294 -0.00483124 0.980332 + outer loop + vertex 1.52803 1.50336 2.56943 + vertex 1.53269 1.50779 2.56852 + vertex 1.52808 1.50836 2.56945 + endloop + endfacet + facet normal 0.231723 -0.00510291 0.972769 + outer loop + vertex 1.52803 1.50336 2.56943 + vertex 1.52808 1.50836 2.56945 + vertex 1.5238 1.50432 2.57045 + endloop + endfacet + facet normal 0.196305 -0.003749 0.980536 + outer loop + vertex 1.53268 1.5028 2.5685 + vertex 1.53269 1.50779 2.56852 + vertex 1.52803 1.50336 2.56943 + endloop + endfacet + facet normal 0.196036 -0.00603043 0.980578 + outer loop + vertex 1.528 1.49837 2.56941 + vertex 1.53268 1.5028 2.5685 + vertex 1.52803 1.50336 2.56943 + endloop + endfacet + facet normal 0.229976 -0.00621222 0.973176 + outer loop + vertex 1.528 1.49837 2.56941 + vertex 1.52803 1.50336 2.56943 + vertex 1.52374 1.49933 2.57042 + endloop + endfacet + facet normal 0.195899 -0.00588017 0.980606 + outer loop + vertex 1.53268 1.4978 2.56847 + vertex 1.53268 1.5028 2.5685 + vertex 1.528 1.49837 2.56941 + endloop + endfacet + facet normal 0.195796 -0.0067617 0.980621 + outer loop + vertex 1.52799 1.49338 2.56938 + vertex 1.53268 1.4978 2.56847 + vertex 1.528 1.49837 2.56941 + endloop + endfacet + facet normal 0.22931 -0.00680584 0.97333 + outer loop + vertex 1.52799 1.49338 2.56938 + vertex 1.528 1.49837 2.56941 + vertex 1.5237 1.49434 2.57039 + endloop + endfacet + facet normal 0.197292 -0.00840984 0.980309 + outer loop + vertex 1.53267 1.49281 2.56843 + vertex 1.53268 1.4978 2.56847 + vertex 1.52799 1.49338 2.56938 + endloop + endfacet + facet normal 0.197126 -0.00982096 0.980329 + outer loop + vertex 1.52798 1.48839 2.56933 + vertex 1.53267 1.49281 2.56843 + vertex 1.52799 1.49338 2.56938 + endloop + endfacet + facet normal 0.230519 -0.00983601 0.973018 + outer loop + vertex 1.52798 1.48839 2.56933 + vertex 1.52799 1.49338 2.56938 + vertex 1.52366 1.48934 2.57036 + endloop + endfacet + facet normal 0.186063 -0.00841053 0.982502 + outer loop + vertex 1.53267 1.49281 2.56843 + vertex 1.53735 1.49747 2.56758 + vertex 1.53268 1.4978 2.56847 + endloop + endfacet + facet normal 0.186129 -0.00747776 0.982497 + outer loop + vertex 1.53735 1.49747 2.56758 + vertex 1.53737 1.50246 2.56762 + vertex 1.53268 1.4978 2.56847 + endloop + endfacet + facet normal 0.192508 -0.00748576 0.981267 + outer loop + vertex 1.53735 1.49747 2.56758 + vertex 1.54164 1.5019 2.56678 + vertex 1.53737 1.50246 2.56762 + endloop + endfacet + facet normal 0.194877 -0.00987071 0.980778 + outer loop + vertex 1.54159 1.4969 2.56674 + vertex 1.54164 1.5019 2.56678 + vertex 1.53735 1.49747 2.56758 + endloop + endfacet + facet normal 0.194746 -0.0108693 0.980794 + outer loop + vertex 1.53732 1.49248 2.56753 + vertex 1.54159 1.4969 2.56674 + vertex 1.53735 1.49747 2.56758 + endloop + endfacet + facet normal 0.188395 -0.0108402 0.982034 + outer loop + vertex 1.53732 1.49248 2.56753 + vertex 1.53735 1.49747 2.56758 + vertex 1.53267 1.49281 2.56843 + endloop + endfacet + facet normal 0.18834 -0.0116008 0.982035 + outer loop + vertex 1.53266 1.48783 2.56837 + vertex 1.53732 1.49248 2.56753 + vertex 1.53267 1.49281 2.56843 + endloop + endfacet + facet normal 0.189919 -0.0132414 0.98171 + outer loop + vertex 1.53727 1.48749 2.56748 + vertex 1.53732 1.49248 2.56753 + vertex 1.53266 1.48783 2.56837 + endloop + endfacet + facet normal 0.196742 -0.01329 0.980365 + outer loop + vertex 1.53727 1.48749 2.56748 + vertex 1.54151 1.49191 2.56669 + vertex 1.53732 1.49248 2.56753 + endloop + endfacet + facet normal 0.197712 -0.0142571 0.980157 + outer loop + vertex 1.54142 1.48692 2.56663 + vertex 1.54151 1.49191 2.56669 + vertex 1.53727 1.48749 2.56748 + endloop + endfacet + facet normal 0.197624 -0.0149065 0.980165 + outer loop + vertex 1.53724 1.48251 2.56741 + vertex 1.54142 1.48692 2.56663 + vertex 1.53727 1.48749 2.56748 + endloop + endfacet + facet normal 0.190003 -0.0148774 0.981671 + outer loop + vertex 1.53724 1.48251 2.56741 + vertex 1.53727 1.48749 2.56748 + vertex 1.53265 1.48285 2.5683 + endloop + endfacet + facet normal 0.189794 -0.0176695 0.981665 + outer loop + vertex 1.53263 1.47787 2.56821 + vertex 1.53724 1.48251 2.56741 + vertex 1.53265 1.48285 2.5683 + endloop + endfacet + facet normal 0.188702 -0.0165456 0.981895 + outer loop + vertex 1.53722 1.47753 2.56733 + vertex 1.53724 1.48251 2.56741 + vertex 1.53263 1.47787 2.56821 + endloop + endfacet + facet normal 0.197381 -0.0165621 0.980187 + outer loop + vertex 1.53722 1.47753 2.56733 + vertex 1.54135 1.48193 2.56657 + vertex 1.53724 1.48251 2.56741 + endloop + endfacet + facet normal 0.197096 -0.0162827 0.980249 + outer loop + vertex 1.54127 1.47695 2.5665 + vertex 1.54135 1.48193 2.56657 + vertex 1.53722 1.47753 2.56733 + endloop + endfacet + facet normal 0.19658 -0.0199124 0.980286 + outer loop + vertex 1.53718 1.47256 2.56723 + vertex 1.54127 1.47695 2.5665 + vertex 1.53722 1.47753 2.56733 + endloop + endfacet + facet normal 0.187224 -0.0198827 0.982116 + outer loop + vertex 1.53718 1.47256 2.56723 + vertex 1.53722 1.47753 2.56733 + vertex 1.53259 1.47285 2.56811 + endloop + endfacet + facet normal 0.186845 -0.0257136 0.982053 + outer loop + vertex 1.53257 1.4678 2.56799 + vertex 1.53718 1.47256 2.56723 + vertex 1.53259 1.47285 2.56811 + endloop + endfacet + facet normal 0.18569 -0.0245545 0.982302 + outer loop + vertex 1.53724 1.46765 2.5671 + vertex 1.53718 1.47256 2.56723 + vertex 1.53257 1.4678 2.56799 + endloop + endfacet + facet normal 0.185458 -0.0309287 0.982165 + outer loop + vertex 1.53265 1.46275 2.56781 + vertex 1.53724 1.46765 2.5671 + vertex 1.53257 1.4678 2.56799 + endloop + endfacet + facet normal 0.19156 -0.0307883 0.980998 + outer loop + vertex 1.53265 1.46275 2.56781 + vertex 1.53257 1.4678 2.56799 + vertex 1.52755 1.46298 2.56881 + endloop + endfacet + facet normal 0.184509 -0.0300085 0.982373 + outer loop + vertex 1.53774 1.46262 2.56685 + vertex 1.53724 1.46765 2.5671 + vertex 1.53265 1.46275 2.56781 + endloop + endfacet + facet normal 0.184427 -0.0326117 0.982305 + outer loop + vertex 1.53262 1.45765 2.56765 + vertex 1.53774 1.46262 2.56685 + vertex 1.53265 1.46275 2.56781 + endloop + endfacet + facet normal 0.190217 -0.032617 0.9812 + outer loop + vertex 1.53262 1.45765 2.56765 + vertex 1.53265 1.46275 2.56781 + vertex 1.52763 1.4579 2.56862 + endloop + endfacet + facet normal 0.193479 -0.0290248 0.980675 + outer loop + vertex 1.54115 1.4676 2.56633 + vertex 1.53724 1.46765 2.5671 + vertex 1.53774 1.46262 2.56685 + endloop + endfacet + facet normal 0.193583 -0.0231473 0.980811 + outer loop + vertex 1.54115 1.4676 2.56633 + vertex 1.54117 1.47206 2.56643 + vertex 1.53724 1.46765 2.5671 + endloop + endfacet + facet normal 0.194933 -0.0243958 0.980513 + outer loop + vertex 1.53724 1.46765 2.5671 + vertex 1.54117 1.47206 2.56643 + vertex 1.53718 1.47256 2.56723 + endloop + endfacet + facet normal 0.184598 -0.00588321 0.982796 + outer loop + vertex 1.53268 1.4978 2.56847 + vertex 1.53737 1.50246 2.56762 + vertex 1.53268 1.5028 2.5685 + endloop + endfacet + facet normal 0.184712 -0.00425223 0.982784 + outer loop + vertex 1.53737 1.50246 2.56762 + vertex 1.53737 1.50746 2.56764 + vertex 1.53268 1.5028 2.5685 + endloop + endfacet + facet normal 0.191287 -0.00424792 0.981525 + outer loop + vertex 1.53737 1.50246 2.56762 + vertex 1.54166 1.50689 2.5668 + vertex 1.53737 1.50746 2.56764 + endloop + endfacet + facet normal 0.191689 -0.00109559 0.981455 + outer loop + vertex 1.54166 1.50689 2.5668 + vertex 1.54164 1.51188 2.56681 + vertex 1.53737 1.50746 2.56764 + endloop + endfacet + facet normal 0.191051 -0.00045539 0.98158 + outer loop + vertex 1.53737 1.50746 2.56764 + vertex 1.54164 1.51188 2.56681 + vertex 1.53735 1.51245 2.56765 + endloop + endfacet + facet normal 0.184433 -0.000474997 0.982845 + outer loop + vertex 1.53737 1.50746 2.56764 + vertex 1.53735 1.51245 2.56765 + vertex 1.53269 1.50779 2.56852 + endloop + endfacet + facet normal 0.184208 -0.00372767 0.98288 + outer loop + vertex 1.53268 1.5028 2.5685 + vertex 1.53737 1.50746 2.56764 + vertex 1.53269 1.50779 2.56852 + endloop + endfacet + facet normal 0.184929 -0.000988339 0.982751 + outer loop + vertex 1.53269 1.50779 2.56852 + vertex 1.53735 1.51245 2.56765 + vertex 1.5327 1.51279 2.56852 + endloop + endfacet + facet normal 0.185197 0.00287992 0.982697 + outer loop + vertex 1.53735 1.51245 2.56765 + vertex 1.53733 1.51744 2.56763 + vertex 1.5327 1.51279 2.56852 + endloop + endfacet + facet normal 0.191123 0.00290358 0.981562 + outer loop + vertex 1.53735 1.51245 2.56765 + vertex 1.54162 1.51688 2.5668 + vertex 1.53733 1.51744 2.56763 + endloop + endfacet + facet normal 0.191498 0.00590121 0.981475 + outer loop + vertex 1.54162 1.51688 2.5668 + vertex 1.54156 1.52186 2.56678 + vertex 1.53733 1.51744 2.56763 + endloop + endfacet + facet normal 0.19153 0.00586923 0.981469 + outer loop + vertex 1.53733 1.51744 2.56763 + vertex 1.54156 1.52186 2.56678 + vertex 1.5373 1.52243 2.56761 + endloop + endfacet + facet normal 0.186148 0.00584234 0.982504 + outer loop + vertex 1.53733 1.51744 2.56763 + vertex 1.5373 1.52243 2.56761 + vertex 1.53271 1.51777 2.56851 + endloop + endfacet + facet normal 0.185895 0.002161 0.982567 + outer loop + vertex 1.5327 1.51279 2.56852 + vertex 1.53733 1.51744 2.56763 + vertex 1.53271 1.51777 2.56851 + endloop + endfacet + facet normal 0.186861 0.00511418 0.982373 + outer loop + vertex 1.53271 1.51777 2.56851 + vertex 1.5373 1.52243 2.56761 + vertex 1.5327 1.52276 2.56849 + endloop + endfacet + facet normal 0.187063 0.00807148 0.982315 + outer loop + vertex 1.5373 1.52243 2.56761 + vertex 1.53727 1.52743 2.56758 + vertex 1.5327 1.52276 2.56849 + endloop + endfacet + facet normal 0.191507 0.00809689 0.981458 + outer loop + vertex 1.5373 1.52243 2.56761 + vertex 1.54151 1.52686 2.56675 + vertex 1.53727 1.52743 2.56758 + endloop + endfacet + facet normal 0.191685 0.00949622 0.981411 + outer loop + vertex 1.54151 1.52686 2.56675 + vertex 1.54144 1.53185 2.56672 + vertex 1.53727 1.52743 2.56758 + endloop + endfacet + facet normal 0.191369 0.00980519 0.981469 + outer loop + vertex 1.53727 1.52743 2.56758 + vertex 1.54144 1.53185 2.56672 + vertex 1.53723 1.53242 2.56753 + endloop + endfacet + facet normal 0.18703 0.00978131 0.982305 + outer loop + vertex 1.53727 1.52743 2.56758 + vertex 1.53723 1.53242 2.56753 + vertex 1.53267 1.52775 2.56845 + endloop + endfacet + facet normal 0.186924 0.00821208 0.98234 + outer loop + vertex 1.5327 1.52276 2.56849 + vertex 1.53727 1.52743 2.56758 + vertex 1.53267 1.52775 2.56845 + endloop + endfacet + facet normal 0.186523 0.010294 0.982397 + outer loop + vertex 1.53267 1.52775 2.56845 + vertex 1.53723 1.53242 2.56753 + vertex 1.53266 1.53275 2.5684 + endloop + endfacet + facet normal 0.186618 0.0116716 0.982363 + outer loop + vertex 1.53723 1.53242 2.56753 + vertex 1.53722 1.53742 2.56748 + vertex 1.53266 1.53275 2.5684 + endloop + endfacet + facet normal 0.190859 0.0116701 0.981548 + outer loop + vertex 1.53723 1.53242 2.56753 + vertex 1.54138 1.53685 2.56667 + vertex 1.53722 1.53742 2.56748 + endloop + endfacet + facet normal 0.191222 0.0144333 0.981441 + outer loop + vertex 1.54138 1.53685 2.56667 + vertex 1.54132 1.54183 2.56661 + vertex 1.53722 1.53742 2.56748 + endloop + endfacet + facet normal 0.18972 0.0158844 0.98171 + outer loop + vertex 1.53722 1.53742 2.56748 + vertex 1.54132 1.54183 2.56661 + vertex 1.53721 1.54243 2.5674 + endloop + endfacet + facet normal 0.185097 0.0158847 0.982592 + outer loop + vertex 1.53722 1.53742 2.56748 + vertex 1.53721 1.54243 2.5674 + vertex 1.53267 1.53778 2.56833 + endloop + endfacet + facet normal 0.184918 0.0133902 0.982663 + outer loop + vertex 1.53266 1.53275 2.5684 + vertex 1.53722 1.53742 2.56748 + vertex 1.53267 1.53778 2.56833 + endloop + endfacet + facet normal 0.182787 0.0182144 0.982984 + outer loop + vertex 1.53267 1.53778 2.56833 + vertex 1.53721 1.54243 2.5674 + vertex 1.53268 1.54281 2.56823 + endloop + endfacet + facet normal 0.183076 0.021986 0.982853 + outer loop + vertex 1.53721 1.54243 2.5674 + vertex 1.5371 1.54741 2.56731 + vertex 1.53268 1.54281 2.56823 + endloop + endfacet + facet normal 0.188192 0.0220774 0.981884 + outer loop + vertex 1.53721 1.54243 2.5674 + vertex 1.5412 1.5468 2.56653 + vertex 1.5371 1.54741 2.56731 + endloop + endfacet + facet normal 0.188952 0.0274933 0.981601 + outer loop + vertex 1.5412 1.5468 2.56653 + vertex 1.54085 1.55175 2.56646 + vertex 1.5371 1.54741 2.56731 + endloop + endfacet + facet normal 0.187612 0.0286952 0.981824 + outer loop + vertex 1.5371 1.54741 2.56731 + vertex 1.54085 1.55175 2.56646 + vertex 1.53675 1.55224 2.56723 + endloop + endfacet + facet normal 0.181649 0.0282751 0.982957 + outer loop + vertex 1.5371 1.54741 2.56731 + vertex 1.53675 1.55224 2.56723 + vertex 1.5326 1.54779 2.56813 + endloop + endfacet + facet normal 0.181305 0.0237453 0.98314 + outer loop + vertex 1.53268 1.54281 2.56823 + vertex 1.5371 1.54741 2.56731 + vertex 1.5326 1.54779 2.56813 + endloop + endfacet + facet normal 0.181117 0.0287875 0.98304 + outer loop + vertex 1.5326 1.54779 2.56813 + vertex 1.53675 1.55224 2.56723 + vertex 1.53239 1.55256 2.56803 + endloop + endfacet + facet normal 0.181353 0.032413 0.982884 + outer loop + vertex 1.53675 1.55224 2.56723 + vertex 1.53598 1.55617 2.56724 + vertex 1.53239 1.55256 2.56803 + endloop + endfacet + facet normal 0.187698 0.0336528 0.98165 + outer loop + vertex 1.53675 1.55224 2.56723 + vertex 1.54009 1.55697 2.56643 + vertex 1.53598 1.55617 2.56724 + endloop + endfacet + facet normal 0.187472 0.0348206 0.981652 + outer loop + vertex 1.53717 1.56108 2.56684 + vertex 1.53598 1.55617 2.56724 + vertex 1.54009 1.55697 2.56643 + endloop + endfacet + facet normal 0.182549 0.0360868 0.982534 + outer loop + vertex 1.53598 1.55617 2.56724 + vertex 1.53717 1.56108 2.56684 + vertex 1.53236 1.55733 2.56787 + endloop + endfacet + facet normal 0.181414 0.0323504 0.982874 + outer loop + vertex 1.53239 1.55256 2.56803 + vertex 1.53598 1.55617 2.56724 + vertex 1.53236 1.55733 2.56787 + endloop + endfacet + facet normal 0.183926 0.0342661 0.982343 + outer loop + vertex 1.53236 1.55733 2.56787 + vertex 1.53717 1.56108 2.56684 + vertex 1.53239 1.56236 2.56769 + endloop + endfacet + facet normal 0.227961 0.0325366 0.973126 + outer loop + vertex 1.52779 1.55329 2.56891 + vertex 1.52761 1.55826 2.56879 + vertex 1.52307 1.55424 2.56999 + endloop + endfacet + facet normal 0.227142 0.0280534 0.973458 + outer loop + vertex 1.52338 1.54929 2.57006 + vertex 1.52779 1.55329 2.56891 + vertex 1.52307 1.55424 2.56999 + endloop + endfacet + facet normal 0.225252 0.0244484 0.973994 + outer loop + vertex 1.52352 1.54433 2.57015 + vertex 1.52793 1.54838 2.56903 + vertex 1.52338 1.54929 2.57006 + endloop + endfacet + facet normal 0.224466 0.0223495 0.974226 + outer loop + vertex 1.52358 1.53931 2.57025 + vertex 1.52799 1.54339 2.56914 + vertex 1.52352 1.54433 2.57015 + endloop + endfacet + facet normal 0.225414 0.0196837 0.974064 + outer loop + vertex 1.52366 1.53428 2.57034 + vertex 1.52801 1.53835 2.56925 + vertex 1.52358 1.53931 2.57025 + endloop + endfacet + facet normal 0.228431 0.0169835 0.973412 + outer loop + vertex 1.52375 1.52927 2.5704 + vertex 1.52803 1.53332 2.56933 + vertex 1.52366 1.53428 2.57034 + endloop + endfacet + facet normal 0.232065 0.0122966 0.972623 + outer loop + vertex 1.52385 1.52428 2.57044 + vertex 1.52807 1.52831 2.56938 + vertex 1.52375 1.52927 2.5704 + endloop + endfacet + facet normal 0.234535 0.0074627 0.972079 + outer loop + vertex 1.5239 1.5193 2.57047 + vertex 1.5281 1.52332 2.56942 + vertex 1.52385 1.52428 2.57044 + endloop + endfacet + facet normal 0.235206 0.00143222 0.971944 + outer loop + vertex 1.52391 1.51431 2.57047 + vertex 1.52813 1.51834 2.56945 + vertex 1.5239 1.5193 2.57047 + endloop + endfacet + facet normal 0.23495 -0.00349809 0.972001 + outer loop + vertex 1.52387 1.50932 2.57046 + vertex 1.52811 1.51335 2.56945 + vertex 1.52391 1.51431 2.57047 + endloop + endfacet + facet normal 0.233086 -0.00663159 0.972433 + outer loop + vertex 1.5238 1.50432 2.57045 + vertex 1.52808 1.50836 2.56945 + vertex 1.52387 1.50932 2.57046 + endloop + endfacet + facet normal 0.231189 -0.00757687 0.972879 + outer loop + vertex 1.52374 1.49933 2.57042 + vertex 1.52803 1.50336 2.56943 + vertex 1.5238 1.50432 2.57045 + endloop + endfacet + facet normal 0.229743 -0.00729469 0.973224 + outer loop + vertex 1.5237 1.49434 2.57039 + vertex 1.528 1.49837 2.56941 + vertex 1.52374 1.49933 2.57042 + endloop + endfacet + facet normal 0.229025 -0.00814274 0.973387 + outer loop + vertex 1.52366 1.48934 2.57036 + vertex 1.52799 1.49338 2.56938 + vertex 1.5237 1.49434 2.57039 + endloop + endfacet + facet normal 0.229994 -0.0123057 0.973114 + outer loop + vertex 1.52363 1.48435 2.57031 + vertex 1.52798 1.48839 2.56933 + vertex 1.52366 1.48934 2.57036 + endloop + endfacet + facet normal 0.198733 -0.0115952 0.979985 + outer loop + vertex 1.53266 1.48783 2.56837 + vertex 1.53267 1.49281 2.56843 + vertex 1.52798 1.48839 2.56933 + endloop + endfacet + facet normal 0.189813 -0.014681 0.98171 + outer loop + vertex 1.53265 1.48285 2.5683 + vertex 1.53727 1.48749 2.56748 + vertex 1.53266 1.48783 2.56837 + endloop + endfacet + facet normal 0.198111 -0.0176727 0.98002 + outer loop + vertex 1.53263 1.47787 2.56821 + vertex 1.53265 1.48285 2.5683 + vertex 1.52793 1.47842 2.56917 + endloop + endfacet + facet normal 0.188364 -0.0210491 0.981874 + outer loop + vertex 1.53259 1.47285 2.56811 + vertex 1.53722 1.47753 2.56733 + vertex 1.53263 1.47787 2.56821 + endloop + endfacet + facet normal 0.193735 -0.025711 0.980717 + outer loop + vertex 1.53257 1.4678 2.56799 + vertex 1.53259 1.47285 2.56811 + vertex 1.52762 1.46819 2.56897 + endloop + endfacet + facet normal 0.193175 -0.0325324 0.980625 + outer loop + vertex 1.52755 1.46298 2.56881 + vertex 1.53257 1.4678 2.56799 + vertex 1.52762 1.46819 2.56897 + endloop + endfacet + facet normal 0.191408 -0.0338934 0.980925 + outer loop + vertex 1.52763 1.4579 2.56862 + vertex 1.53265 1.46275 2.56781 + vertex 1.52755 1.46298 2.56881 + endloop + endfacet + facet normal 0.190567 -0.0259848 0.98133 + outer loop + vertex 1.52761 1.45289 2.56849 + vertex 1.53262 1.45765 2.56765 + vertex 1.52763 1.4579 2.56862 + endloop + endfacet + facet normal 0.194496 -0.0302705 0.980436 + outer loop + vertex 1.53246 1.4526 2.56753 + vertex 1.53262 1.45765 2.56765 + vertex 1.52761 1.45289 2.56849 + endloop + endfacet + facet normal 0.184143 -0.0299976 0.982442 + outer loop + vertex 1.53246 1.4526 2.56753 + vertex 1.53698 1.45698 2.56681 + vertex 1.53262 1.45765 2.56765 + endloop + endfacet + facet normal 0.195159 -0.0196118 0.980576 + outer loop + vertex 1.52756 1.44789 2.56841 + vertex 1.53246 1.4526 2.56753 + vertex 1.52761 1.45289 2.56849 + endloop + endfacet + facet normal 0.201087 -0.0260208 0.979228 + outer loop + vertex 1.53239 1.44767 2.56741 + vertex 1.53246 1.4526 2.56753 + vertex 1.52756 1.44789 2.56841 + endloop + endfacet + facet normal 0.188226 -0.0259031 0.981784 + outer loop + vertex 1.53239 1.44767 2.56741 + vertex 1.53672 1.45198 2.56669 + vertex 1.53246 1.4526 2.56753 + endloop + endfacet + facet normal 0.194759 -0.0327074 0.980306 + outer loop + vertex 1.53659 1.44707 2.56655 + vertex 1.53672 1.45198 2.56669 + vertex 1.53239 1.44767 2.56741 + endloop + endfacet + facet normal 0.195724 -0.0259193 0.980316 + outer loop + vertex 1.53234 1.44275 2.56729 + vertex 1.53659 1.44707 2.56655 + vertex 1.53239 1.44767 2.56741 + endloop + endfacet + facet normal 0.203255 -0.0336188 0.978549 + outer loop + vertex 1.53643 1.44218 2.56642 + vertex 1.53659 1.44707 2.56655 + vertex 1.53234 1.44275 2.56729 + endloop + endfacet + facet normal 0.203679 -0.0305793 0.97856 + outer loop + vertex 1.53224 1.43786 2.56716 + vertex 1.53643 1.44218 2.56642 + vertex 1.53234 1.44275 2.56729 + endloop + endfacet + facet normal 0.209425 -0.0381062 0.977082 + outer loop + vertex 1.53217 1.43302 2.56698 + vertex 1.53621 1.43739 2.56629 + vertex 1.53224 1.43786 2.56716 + endloop + endfacet + facet normal 0.212191 -0.0407729 0.976377 + outer loop + vertex 1.53605 1.43299 2.56614 + vertex 1.53621 1.43739 2.56629 + vertex 1.53217 1.43302 2.56698 + endloop + endfacet + facet normal 0.212108 -0.0456694 0.976179 + outer loop + vertex 1.53605 1.43299 2.56614 + vertex 1.53217 1.43302 2.56698 + vertex 1.53251 1.42799 2.56667 + endloop + endfacet + facet normal 0.206553 -0.0561813 0.976821 + outer loop + vertex 1.53782 1.41862 2.565 + vertex 1.53876 1.42432 2.56513 + vertex 1.5349 1.4211 2.56576 + endloop + endfacet + facet normal 0.188268 -0.0526569 0.980705 + outer loop + vertex 1.5424 1.41266 2.56378 + vertex 1.54243 1.41778 2.56405 + vertex 1.53801 1.41327 2.56466 + endloop + endfacet + facet normal 0.187445 -0.0583499 0.98054 + outer loop + vertex 1.53773 1.40806 2.5644 + vertex 1.5424 1.41266 2.56378 + vertex 1.53801 1.41327 2.56466 + endloop + endfacet + facet normal 0.20465 -0.0590811 0.977051 + outer loop + vertex 1.53773 1.40806 2.5644 + vertex 1.53801 1.41327 2.56466 + vertex 1.53389 1.40918 2.56527 + endloop + endfacet + facet normal 0.202623 -0.0660077 0.97703 + outer loop + vertex 1.53285 1.40357 2.56511 + vertex 1.53773 1.40806 2.5644 + vertex 1.53389 1.40918 2.56527 + endloop + endfacet + facet normal 0.200282 -0.0633613 0.977687 + outer loop + vertex 1.53756 1.40285 2.5641 + vertex 1.53773 1.40806 2.5644 + vertex 1.53285 1.40357 2.56511 + endloop + endfacet + facet normal 0.198446 -0.0748499 0.97725 + outer loop + vertex 1.53302 1.39833 2.56468 + vertex 1.53756 1.40285 2.5641 + vertex 1.53285 1.40357 2.56511 + endloop + endfacet + facet normal 0.18918 -0.0652362 0.979773 + outer loop + vertex 1.53754 1.39775 2.56376 + vertex 1.53756 1.40285 2.5641 + vertex 1.53302 1.39833 2.56468 + endloop + endfacet + facet normal 0.189202 -0.0650702 0.97978 + outer loop + vertex 1.53272 1.39317 2.56439 + vertex 1.53754 1.39775 2.56376 + vertex 1.53302 1.39833 2.56468 + endloop + endfacet + facet normal 0.215083 -0.0662538 0.974346 + outer loop + vertex 1.53272 1.39317 2.56439 + vertex 1.53302 1.39833 2.56468 + vertex 1.52874 1.39422 2.56534 + endloop + endfacet + facet normal 0.221471 -0.0732171 0.972414 + outer loop + vertex 1.52874 1.39422 2.56534 + vertex 1.53302 1.39833 2.56468 + vertex 1.52926 1.39886 2.56557 + endloop + endfacet + facet normal 0.186944 -0.0626139 0.980373 + outer loop + vertex 1.53752 1.39273 2.56345 + vertex 1.53754 1.39775 2.56376 + vertex 1.53272 1.39317 2.56439 + endloop + endfacet + facet normal 0.187511 -0.0569434 0.980611 + outer loop + vertex 1.5325 1.38793 2.56413 + vertex 1.53752 1.39273 2.56345 + vertex 1.53272 1.39317 2.56439 + endloop + endfacet + facet normal 0.217792 -0.0579423 0.974274 + outer loop + vertex 1.5325 1.38793 2.56413 + vertex 1.53272 1.39317 2.56439 + vertex 1.52757 1.38854 2.56527 + endloop + endfacet + facet normal 0.217332 -0.0614476 0.974162 + outer loop + vertex 1.52759 1.38302 2.56491 + vertex 1.5325 1.38793 2.56413 + vertex 1.52757 1.38854 2.56527 + endloop + endfacet + facet normal 0.20976 -0.0535369 0.976286 + outer loop + vertex 1.53246 1.38277 2.56385 + vertex 1.5325 1.38793 2.56413 + vertex 1.52759 1.38302 2.56491 + endloop + endfacet + facet normal 0.190698 -0.0536209 0.980183 + outer loop + vertex 1.53246 1.38277 2.56385 + vertex 1.53754 1.38777 2.56314 + vertex 1.5325 1.38793 2.56413 + endloop + endfacet + facet normal 0.196778 -0.060029 0.978609 + outer loop + vertex 1.53758 1.38286 2.56283 + vertex 1.53754 1.38777 2.56314 + vertex 1.53246 1.38277 2.56385 + endloop + endfacet + facet normal 0.196752 -0.0557548 0.978867 + outer loop + vertex 1.53247 1.37773 2.56357 + vertex 1.53758 1.38286 2.56283 + vertex 1.53246 1.38277 2.56385 + endloop + endfacet + facet normal 0.196054 -0.0557636 0.979006 + outer loop + vertex 1.53247 1.37773 2.56357 + vertex 1.53246 1.38277 2.56385 + vertex 1.52739 1.37766 2.56458 + endloop + endfacet + facet normal 0.196084 -0.0679828 0.978228 + outer loop + vertex 1.52737 1.37248 2.56422 + vertex 1.53247 1.37773 2.56357 + vertex 1.52739 1.37766 2.56458 + endloop + endfacet + facet normal 0.19049 -0.062368 0.979706 + outer loop + vertex 1.5325 1.37278 2.56324 + vertex 1.53247 1.37773 2.56357 + vertex 1.52737 1.37248 2.56422 + endloop + endfacet + facet normal 0.190613 -0.0651802 0.979499 + outer loop + vertex 1.52741 1.36748 2.56388 + vertex 1.5325 1.37278 2.56324 + vertex 1.52737 1.37248 2.56422 + endloop + endfacet + facet normal 0.0732747 -0.0671763 0.995047 + outer loop + vertex 1.52741 1.36748 2.56388 + vertex 1.52737 1.37248 2.56422 + vertex 1.52269 1.36737 2.56422 + endloop + endfacet + facet normal 0.19733 -0.0718533 0.9777 + outer loop + vertex 1.53253 1.36783 2.56287 + vertex 1.5325 1.37278 2.56324 + vertex 1.52741 1.36748 2.56388 + endloop + endfacet + facet normal 0.197291 -0.0710796 0.977765 + outer loop + vertex 1.52742 1.36255 2.56352 + vertex 1.53253 1.36783 2.56287 + vertex 1.52741 1.36748 2.56388 + endloop + endfacet + facet normal 0.0836753 -0.0725708 0.993847 + outer loop + vertex 1.52742 1.36255 2.56352 + vertex 1.52741 1.36748 2.56388 + vertex 1.52275 1.36237 2.5639 + endloop + endfacet + facet normal 0.210029 -0.0838555 0.974092 + outer loop + vertex 1.53235 1.36284 2.56248 + vertex 1.53253 1.36783 2.56287 + vertex 1.52742 1.36255 2.56352 + endloop + endfacet + facet normal 0.210024 -0.0837221 0.974105 + outer loop + vertex 1.5274 1.35766 2.56311 + vertex 1.53235 1.36284 2.56248 + vertex 1.52742 1.36255 2.56352 + endloop + endfacet + facet normal 0.107739 -0.0846115 0.990572 + outer loop + vertex 1.5274 1.35766 2.56311 + vertex 1.52742 1.36255 2.56352 + vertex 1.5228 1.35743 2.56359 + endloop + endfacet + facet normal 0.22279 -0.0964262 0.970086 + outer loop + vertex 1.53209 1.358 2.56206 + vertex 1.53235 1.36284 2.56248 + vertex 1.5274 1.35766 2.56311 + endloop + endfacet + facet normal 0.222751 -0.0956059 0.970176 + outer loop + vertex 1.52747 1.35279 2.56261 + vertex 1.53209 1.358 2.56206 + vertex 1.5274 1.35766 2.56311 + endloop + endfacet + facet normal 0.134494 -0.0984225 0.986014 + outer loop + vertex 1.52747 1.35279 2.56261 + vertex 1.5274 1.35766 2.56311 + vertex 1.52287 1.35249 2.56321 + endloop + endfacet + facet normal 0.234343 -0.106315 0.966323 + outer loop + vertex 1.53234 1.35348 2.56151 + vertex 1.53209 1.358 2.56206 + vertex 1.52747 1.35279 2.56261 + endloop + endfacet + facet normal 0.233959 -0.10285 0.966791 + outer loop + vertex 1.53234 1.35348 2.56151 + vertex 1.52747 1.35279 2.56261 + vertex 1.52775 1.34771 2.562 + endloop + endfacet + facet normal 0.245263 -0.112151 0.962948 + outer loop + vertex 1.53202 1.34977 2.56115 + vertex 1.53234 1.35348 2.56151 + vertex 1.52775 1.34771 2.562 + endloop + endfacet + facet normal 0.240791 -0.101952 0.965207 + outer loop + vertex 1.53202 1.34977 2.56115 + vertex 1.52775 1.34771 2.562 + vertex 1.53073 1.34582 2.56106 + endloop + endfacet + facet normal 0.218214 -0.0947087 0.971294 + outer loop + vertex 1.53461 1.34909 2.56051 + vertex 1.53202 1.34977 2.56115 + vertex 1.53073 1.34582 2.56106 + endloop + endfacet + facet normal 0.217693 -0.0966373 0.971221 + outer loop + vertex 1.53467 1.35224 2.56081 + vertex 1.53202 1.34977 2.56115 + vertex 1.53461 1.34909 2.56051 + endloop + endfacet + facet normal 0.190092 -0.09665 0.976997 + outer loop + vertex 1.53467 1.35224 2.56081 + vertex 1.53461 1.34909 2.56051 + vertex 1.53817 1.35341 2.56024 + endloop + endfacet + facet normal 0.18949 -0.0946939 0.977306 + outer loop + vertex 1.53817 1.35341 2.56024 + vertex 1.53603 1.355 2.56081 + vertex 1.53467 1.35224 2.56081 + endloop + endfacet + facet normal 0.229198 -0.114258 0.966651 + outer loop + vertex 1.53603 1.355 2.56081 + vertex 1.53234 1.35348 2.56151 + vertex 1.53467 1.35224 2.56081 + endloop + endfacet + facet normal 0.224524 -0.101772 0.969139 + outer loop + vertex 1.53603 1.355 2.56081 + vertex 1.53602 1.35804 2.56113 + vertex 1.53234 1.35348 2.56151 + endloop + endfacet + facet normal 0.199586 -0.102416 0.974514 + outer loop + vertex 1.53857 1.3573 2.56053 + vertex 1.53602 1.35804 2.56113 + vertex 1.53603 1.355 2.56081 + endloop + endfacet + facet normal 0.201578 -0.0956874 0.974787 + outer loop + vertex 1.53979 1.36114 2.56065 + vertex 1.53602 1.35804 2.56113 + vertex 1.53857 1.3573 2.56053 + endloop + endfacet + facet normal 0.180005 -0.0889906 0.979632 + outer loop + vertex 1.53857 1.3573 2.56053 + vertex 1.54253 1.35856 2.55992 + vertex 1.53979 1.36114 2.56065 + endloop + endfacet + facet normal 0.184146 -0.0844756 0.979262 + outer loop + vertex 1.54253 1.35856 2.55992 + vertex 1.54382 1.36428 2.56017 + vertex 1.53979 1.36114 2.56065 + endloop + endfacet + facet normal 0.184448 -0.0848773 0.97917 + outer loop + vertex 1.53979 1.36114 2.56065 + vertex 1.54382 1.36428 2.56017 + vertex 1.54076 1.36577 2.56087 + endloop + endfacet + facet normal 0.204785 -0.0889193 0.97476 + outer loop + vertex 1.54076 1.36577 2.56087 + vertex 1.53658 1.36242 2.56144 + vertex 1.53979 1.36114 2.56065 + endloop + endfacet + facet normal 0.203211 -0.0868696 0.975274 + outer loop + vertex 1.53771 1.36786 2.56169 + vertex 1.53658 1.36242 2.56144 + vertex 1.54076 1.36577 2.56087 + endloop + endfacet + facet normal 0.204631 -0.0847639 0.975162 + outer loop + vertex 1.5418 1.36956 2.56098 + vertex 1.53771 1.36786 2.56169 + vertex 1.54076 1.36577 2.56087 + endloop + endfacet + facet normal 0.185097 -0.0795333 0.979497 + outer loop + vertex 1.54439 1.36892 2.56044 + vertex 1.5418 1.36956 2.56098 + vertex 1.54076 1.36577 2.56087 + endloop + endfacet + facet normal 0.185643 -0.0773748 0.979566 + outer loop + vertex 1.5442 1.37215 2.56073 + vertex 1.5418 1.36956 2.56098 + vertex 1.54439 1.36892 2.56044 + endloop + endfacet + facet normal 0.172421 -0.0783468 0.981903 + outer loop + vertex 1.5442 1.37215 2.56073 + vertex 1.54439 1.36892 2.56044 + vertex 1.54792 1.37356 2.56019 + endloop + endfacet + facet normal 0.170569 -0.0731608 0.982626 + outer loop + vertex 1.5442 1.37215 2.56073 + vertex 1.54792 1.37356 2.56019 + vertex 1.54529 1.37588 2.56082 + endloop + endfacet + facet normal 0.188168 -0.0782115 0.979018 + outer loop + vertex 1.54529 1.37588 2.56082 + vertex 1.5416 1.37281 2.56129 + vertex 1.5442 1.37215 2.56073 + endloop + endfacet + facet normal 0.186206 -0.0757658 0.979585 + outer loop + vertex 1.54257 1.37799 2.5615 + vertex 1.5416 1.37281 2.56129 + vertex 1.54529 1.37588 2.56082 + endloop + endfacet + facet normal 0.1855 -0.0766966 0.979646 + outer loop + vertex 1.54645 1.37968 2.5609 + vertex 1.54257 1.37799 2.5615 + vertex 1.54529 1.37588 2.56082 + endloop + endfacet + facet normal 0.166627 -0.0710474 0.983457 + outer loop + vertex 1.54895 1.37889 2.56042 + vertex 1.54645 1.37968 2.5609 + vertex 1.54529 1.37588 2.56082 + endloop + endfacet + facet normal 0.166444 -0.0716192 0.983447 + outer loop + vertex 1.54892 1.38233 2.56068 + vertex 1.54645 1.37968 2.5609 + vertex 1.54895 1.37889 2.56042 + endloop + endfacet + facet normal 0.137267 -0.0722143 0.987898 + outer loop + vertex 1.54892 1.38233 2.56068 + vertex 1.54895 1.37889 2.56042 + vertex 1.55272 1.38364 2.56024 + endloop + endfacet + facet normal 0.135079 -0.0656286 0.988659 + outer loop + vertex 1.54892 1.38233 2.56068 + vertex 1.55272 1.38364 2.56024 + vertex 1.55013 1.3861 2.56076 + endloop + endfacet + facet normal 0.170537 -0.0768706 0.982348 + outer loop + vertex 1.55013 1.3861 2.56076 + vertex 1.54639 1.38298 2.56117 + vertex 1.54892 1.38233 2.56068 + endloop + endfacet + facet normal 0.167394 -0.0729939 0.983184 + outer loop + vertex 1.54747 1.38815 2.56137 + vertex 1.54639 1.38298 2.56117 + vertex 1.55013 1.3861 2.56076 + endloop + endfacet + facet normal 0.16734 -0.0730645 0.983188 + outer loop + vertex 1.55138 1.38991 2.56083 + vertex 1.54747 1.38815 2.56137 + vertex 1.55013 1.3861 2.56076 + endloop + endfacet + facet normal 0.128026 -0.0602825 0.989937 + outer loop + vertex 1.55387 1.38899 2.56045 + vertex 1.55138 1.38991 2.56083 + vertex 1.55013 1.3861 2.56076 + endloop + endfacet + facet normal 0.128064 -0.0601812 0.989938 + outer loop + vertex 1.55394 1.39246 2.56065 + vertex 1.55138 1.38991 2.56083 + vertex 1.55387 1.38899 2.56045 + endloop + endfacet + facet normal 0.0789485 -0.0595322 0.9951 + outer loop + vertex 1.55394 1.39246 2.56065 + vertex 1.55387 1.38899 2.56045 + vertex 1.55768 1.39328 2.56041 + endloop + endfacet + facet normal 0.0768572 -0.0498017 0.995798 + outer loop + vertex 1.55394 1.39246 2.56065 + vertex 1.55768 1.39328 2.56041 + vertex 1.55525 1.39616 2.56074 + endloop + endfacet + facet normal 0.140025 -0.0719282 0.987532 + outer loop + vertex 1.55525 1.39616 2.56074 + vertex 1.5514 1.39319 2.56107 + vertex 1.55394 1.39246 2.56065 + endloop + endfacet + facet normal 0.131922 -0.0612292 0.989367 + outer loop + vertex 1.55251 1.39832 2.56124 + vertex 1.5514 1.39319 2.56107 + vertex 1.55525 1.39616 2.56074 + endloop + endfacet + facet normal 0.135196 -0.0570326 0.989176 + outer loop + vertex 1.55649 1.39993 2.56079 + vertex 1.55251 1.39832 2.56124 + vertex 1.55525 1.39616 2.56074 + endloop + endfacet + facet normal 0.0653611 -0.0340171 0.997282 + outer loop + vertex 1.55894 1.39858 2.56058 + vertex 1.55649 1.39993 2.56079 + vertex 1.55525 1.39616 2.56074 + endloop + endfacet + facet normal 0.067232 -0.0306102 0.997268 + outer loop + vertex 1.55882 1.40217 2.5607 + vertex 1.55649 1.39993 2.56079 + vertex 1.55894 1.39858 2.56058 + endloop + endfacet + facet normal -6.69188e-05 -0.0329813 0.999456 + outer loop + vertex 1.55882 1.40217 2.5607 + vertex 1.55894 1.39858 2.56058 + vertex 1.56204 1.40239 2.56071 + endloop + endfacet + facet normal 0.000127141 -0.0358531 0.999357 + outer loop + vertex 1.55882 1.40217 2.5607 + vertex 1.56204 1.40239 2.56071 + vertex 1.55959 1.40559 2.56082 + endloop + endfacet + facet normal 0.0902765 -0.0559371 0.994345 + outer loop + vertex 1.55959 1.40559 2.56082 + vertex 1.55622 1.40304 2.56098 + vertex 1.55882 1.40217 2.5607 + endloop + endfacet + facet normal 0.0930371 -0.0596143 0.993876 + outer loop + vertex 1.55662 1.40726 2.5612 + vertex 1.55622 1.40304 2.56098 + vertex 1.55959 1.40559 2.56082 + endloop + endfacet + facet normal 0.0923801 -0.0607805 0.993867 + outer loop + vertex 1.56032 1.40963 2.561 + vertex 1.55662 1.40726 2.5612 + vertex 1.55959 1.40559 2.56082 + endloop + endfacet + facet normal 0.0126769 -0.0466682 0.99883 + outer loop + vertex 1.55959 1.40559 2.56082 + vertex 1.5626 1.40739 2.56087 + vertex 1.56032 1.40963 2.561 + endloop + endfacet + facet normal 0.0172273 -0.0420328 0.998968 + outer loop + vertex 1.5626 1.40739 2.56087 + vertex 1.5628 1.41072 2.561 + vertex 1.56032 1.40963 2.561 + endloop + endfacet + facet normal 0.0307854 -0.073039 0.996854 + outer loop + vertex 1.5628 1.41072 2.561 + vertex 1.56176 1.41278 2.56119 + vertex 1.56032 1.40963 2.561 + endloop + endfacet + facet normal 0.0869572 -0.09837 0.991343 + outer loop + vertex 1.56176 1.41278 2.56119 + vertex 1.55793 1.41239 2.56148 + vertex 1.56032 1.40963 2.561 + endloop + endfacet + facet normal 0.0897913 -0.12878 0.9876 + outer loop + vertex 1.56176 1.41278 2.56119 + vertex 1.56343 1.41695 2.56158 + vertex 1.55793 1.41239 2.56148 + endloop + endfacet + facet normal 0.0515273 -0.082833 0.99523 + outer loop + vertex 1.56343 1.41695 2.56158 + vertex 1.55782 1.41773 2.56193 + vertex 1.55793 1.41239 2.56148 + endloop + endfacet + facet normal 0.11886 -0.0810496 0.989598 + outer loop + vertex 1.55793 1.41239 2.56148 + vertex 1.55782 1.41773 2.56193 + vertex 1.55259 1.41276 2.56215 + endloop + endfacet + facet normal 0.120048 -0.0658456 0.990582 + outer loop + vertex 1.55249 1.40788 2.56184 + vertex 1.55793 1.41239 2.56148 + vertex 1.55259 1.41276 2.56215 + endloop + endfacet + facet normal 0.157969 -0.0663407 0.985213 + outer loop + vertex 1.55249 1.40788 2.56184 + vertex 1.55259 1.41276 2.56215 + vertex 1.54745 1.40772 2.56264 + endloop + endfacet + facet normal 0.157785 -0.0575784 0.985793 + outer loop + vertex 1.54751 1.40289 2.56235 + vertex 1.55249 1.40788 2.56184 + vertex 1.54745 1.40772 2.56264 + endloop + endfacet + facet normal 0.169224 -0.0573084 0.98391 + outer loop + vertex 1.54751 1.40289 2.56235 + vertex 1.54745 1.40772 2.56264 + vertex 1.54244 1.40263 2.56321 + endloop + endfacet + facet normal 0.169354 -0.060583 0.983691 + outer loop + vertex 1.54252 1.39771 2.56289 + vertex 1.54751 1.40289 2.56235 + vertex 1.54244 1.40263 2.56321 + endloop + endfacet + facet normal 0.172357 -0.0604967 0.983175 + outer loop + vertex 1.54252 1.39771 2.56289 + vertex 1.54244 1.40263 2.56321 + vertex 1.53754 1.39775 2.56376 + endloop + endfacet + facet normal 0.168933 -0.0601664 0.983789 + outer loop + vertex 1.54757 1.39807 2.56204 + vertex 1.54751 1.40289 2.56235 + vertex 1.54252 1.39771 2.56289 + endloop + endfacet + facet normal 0.169125 -0.0634599 0.983549 + outer loop + vertex 1.54258 1.39284 2.56256 + vertex 1.54757 1.39807 2.56204 + vertex 1.54252 1.39771 2.56289 + endloop + endfacet + facet normal 0.17295 -0.0633749 0.98289 + outer loop + vertex 1.54258 1.39284 2.56256 + vertex 1.54252 1.39771 2.56289 + vertex 1.53752 1.39273 2.56345 + endloop + endfacet + facet normal 0.172919 -0.0603779 0.983084 + outer loop + vertex 1.53754 1.38777 2.56314 + vertex 1.54258 1.39284 2.56256 + vertex 1.53752 1.39273 2.56345 + endloop + endfacet + facet normal 0.179105 -0.06669 0.981567 + outer loop + vertex 1.54259 1.38797 2.56223 + vertex 1.54258 1.39284 2.56256 + vertex 1.53754 1.38777 2.56314 + endloop + endfacet + facet normal 0.171454 -0.0667981 0.982925 + outer loop + vertex 1.54259 1.38797 2.56223 + vertex 1.54744 1.39317 2.56174 + vertex 1.54258 1.39284 2.56256 + endloop + endfacet + facet normal 0.176672 -0.0717969 0.981648 + outer loop + vertex 1.54747 1.38815 2.56137 + vertex 1.54744 1.39317 2.56174 + vertex 1.54259 1.38797 2.56223 + endloop + endfacet + facet normal 0.176632 -0.0700427 0.981782 + outer loop + vertex 1.54246 1.38304 2.5619 + vertex 1.54747 1.38815 2.56137 + vertex 1.54259 1.38797 2.56223 + endloop + endfacet + facet normal 0.188659 -0.0701976 0.97953 + outer loop + vertex 1.54246 1.38304 2.5619 + vertex 1.54259 1.38797 2.56223 + vertex 1.53758 1.38286 2.56283 + endloop + endfacet + facet normal 0.188527 -0.064421 0.979953 + outer loop + vertex 1.53761 1.37796 2.5625 + vertex 1.54246 1.38304 2.5619 + vertex 1.53758 1.38286 2.56283 + endloop + endfacet + facet normal 0.197266 -0.0730363 0.977626 + outer loop + vertex 1.54257 1.37799 2.5615 + vertex 1.54246 1.38304 2.5619 + vertex 1.53761 1.37796 2.5625 + endloop + endfacet + facet normal 0.197277 -0.0716181 0.977728 + outer loop + vertex 1.53753 1.37298 2.56215 + vertex 1.54257 1.37799 2.5615 + vertex 1.53761 1.37796 2.5625 + endloop + endfacet + facet normal 0.214053 -0.0716369 0.974192 + outer loop + vertex 1.53753 1.37298 2.56215 + vertex 1.53761 1.37796 2.5625 + vertex 1.5325 1.37278 2.56324 + endloop + endfacet + facet normal 0.182671 -0.0735632 0.980418 + outer loop + vertex 1.54639 1.38298 2.56117 + vertex 1.54246 1.38304 2.5619 + vertex 1.54257 1.37799 2.5615 + endloop + endfacet + facet normal 0.166751 -0.0719693 0.983369 + outer loop + vertex 1.5514 1.39319 2.56107 + vertex 1.54744 1.39317 2.56174 + vertex 1.54747 1.38815 2.56137 + endloop + endfacet + facet normal 0.171394 -0.0656794 0.983011 + outer loop + vertex 1.54744 1.39317 2.56174 + vertex 1.54757 1.39807 2.56204 + vertex 1.54258 1.39284 2.56256 + endloop + endfacet + facet normal 0.163754 -0.0655617 0.98432 + outer loop + vertex 1.54744 1.39317 2.56174 + vertex 1.55251 1.39832 2.56124 + vertex 1.54757 1.39807 2.56204 + endloop + endfacet + facet normal 0.163515 -0.0593942 0.984751 + outer loop + vertex 1.55251 1.39832 2.56124 + vertex 1.55229 1.40313 2.56156 + vertex 1.54757 1.39807 2.56204 + endloop + endfacet + facet normal 0.164431 -0.0602677 0.984546 + outer loop + vertex 1.54757 1.39807 2.56204 + vertex 1.55229 1.40313 2.56156 + vertex 1.54751 1.40289 2.56235 + endloop + endfacet + facet normal 0.169438 -0.0575249 0.983861 + outer loop + vertex 1.54244 1.40263 2.56321 + vertex 1.54745 1.40772 2.56264 + vertex 1.54238 1.40762 2.56351 + endloop + endfacet + facet normal 0.177508 -0.0573521 0.982447 + outer loop + vertex 1.54244 1.40263 2.56321 + vertex 1.54238 1.40762 2.56351 + vertex 1.53756 1.40285 2.5641 + endloop + endfacet + facet normal 0.169399 -0.05391 0.984072 + outer loop + vertex 1.54745 1.40772 2.56264 + vertex 1.54735 1.41259 2.56292 + vertex 1.54238 1.40762 2.56351 + endloop + endfacet + facet normal 0.170049 -0.0545765 0.983923 + outer loop + vertex 1.54238 1.40762 2.56351 + vertex 1.54735 1.41259 2.56292 + vertex 1.5424 1.41266 2.56378 + endloop + endfacet + facet normal 0.170134 -0.0508394 0.984109 + outer loop + vertex 1.54735 1.41259 2.56292 + vertex 1.54727 1.41751 2.56319 + vertex 1.5424 1.41266 2.56378 + endloop + endfacet + facet normal 0.139971 -0.0515746 0.988811 + outer loop + vertex 1.54735 1.41259 2.56292 + vertex 1.55247 1.41767 2.56246 + vertex 1.54727 1.41751 2.56319 + endloop + endfacet + facet normal 0.139958 -0.0510377 0.988841 + outer loop + vertex 1.55247 1.41767 2.56246 + vertex 1.55237 1.42257 2.56273 + vertex 1.54727 1.41751 2.56319 + endloop + endfacet + facet normal 0.139037 -0.050094 0.989019 + outer loop + vertex 1.54727 1.41751 2.56319 + vertex 1.55237 1.42257 2.56273 + vertex 1.54727 1.42251 2.56345 + endloop + endfacet + facet normal 0.0930286 -0.05227 0.99429 + outer loop + vertex 1.55247 1.41767 2.56246 + vertex 1.55763 1.42284 2.56225 + vertex 1.55237 1.42257 2.56273 + endloop + endfacet + facet normal 0.0929116 -0.049702 0.994433 + outer loop + vertex 1.55763 1.42284 2.56225 + vertex 1.55756 1.42778 2.56251 + vertex 1.55237 1.42257 2.56273 + endloop + endfacet + facet normal 0.0928483 -0.0496384 0.994442 + outer loop + vertex 1.55237 1.42257 2.56273 + vertex 1.55756 1.42778 2.56251 + vertex 1.55234 1.4275 2.56298 + endloop + endfacet + facet normal 0.0522554 -0.0503721 0.997363 + outer loop + vertex 1.55763 1.42284 2.56225 + vertex 1.56265 1.42799 2.56225 + vertex 1.55756 1.42778 2.56251 + endloop + endfacet + facet normal 0.0520137 -0.0442182 0.997667 + outer loop + vertex 1.56265 1.42799 2.56225 + vertex 1.56267 1.43294 2.56247 + vertex 1.55756 1.42778 2.56251 + endloop + endfacet + facet normal 0.0555006 -0.0476632 0.99732 + outer loop + vertex 1.55756 1.42778 2.56251 + vertex 1.56267 1.43294 2.56247 + vertex 1.55755 1.43269 2.56274 + endloop + endfacet + facet normal 0.0552595 -0.0425668 0.997564 + outer loop + vertex 1.56267 1.43294 2.56247 + vertex 1.56268 1.43785 2.56268 + vertex 1.55755 1.43269 2.56274 + endloop + endfacet + facet normal 0.0516515 -0.049783 0.997424 + outer loop + vertex 1.56278 1.42285 2.56199 + vertex 1.56265 1.42799 2.56225 + vertex 1.55763 1.42284 2.56225 + endloop + endfacet + facet normal 0.0516532 -0.0605098 0.99683 + outer loop + vertex 1.55782 1.41773 2.56193 + vertex 1.56278 1.42285 2.56199 + vertex 1.55763 1.42284 2.56225 + endloop + endfacet + facet normal 0.099179 -0.0584568 0.993351 + outer loop + vertex 1.55782 1.41773 2.56193 + vertex 1.55763 1.42284 2.56225 + vertex 1.55247 1.41767 2.56246 + endloop + endfacet + facet normal 0.146776 -0.0585461 0.987436 + outer loop + vertex 1.55259 1.41276 2.56215 + vertex 1.55247 1.41767 2.56246 + vertex 1.54735 1.41259 2.56292 + endloop + endfacet + facet normal 0.164596 -0.0645252 0.984248 + outer loop + vertex 1.55229 1.40313 2.56156 + vertex 1.55249 1.40788 2.56184 + vertex 1.54751 1.40289 2.56235 + endloop + endfacet + facet normal 0.14439 -0.0638927 0.987456 + outer loop + vertex 1.55229 1.40313 2.56156 + vertex 1.55662 1.40726 2.5612 + vertex 1.55249 1.40788 2.56184 + endloop + endfacet + facet normal 0.146678 -0.0545837 0.987677 + outer loop + vertex 1.54745 1.40772 2.56264 + vertex 1.55259 1.41276 2.56215 + vertex 1.54735 1.41259 2.56292 + endloop + endfacet + facet normal 0.140173 -0.0904945 0.985983 + outer loop + vertex 1.55662 1.40726 2.5612 + vertex 1.55793 1.41239 2.56148 + vertex 1.55249 1.40788 2.56184 + endloop + endfacet + facet normal 0.0991854 -0.0601427 0.99325 + outer loop + vertex 1.55259 1.41276 2.56215 + vertex 1.55782 1.41773 2.56193 + vertex 1.55247 1.41767 2.56246 + endloop + endfacet + facet normal 0.054328 -0.0630902 0.996528 + outer loop + vertex 1.56343 1.41695 2.56158 + vertex 1.56278 1.42285 2.56199 + vertex 1.55782 1.41773 2.56193 + endloop + endfacet + facet normal 0.105821 -0.082002 0.990998 + outer loop + vertex 1.55793 1.41239 2.56148 + vertex 1.55662 1.40726 2.5612 + vertex 1.56032 1.40963 2.561 + endloop + endfacet + facet normal 0.144611 -0.0641288 0.987408 + outer loop + vertex 1.55622 1.40304 2.56098 + vertex 1.55662 1.40726 2.5612 + vertex 1.55229 1.40313 2.56156 + endloop + endfacet + facet normal 0.144729 -0.060448 0.987623 + outer loop + vertex 1.55622 1.40304 2.56098 + vertex 1.55229 1.40313 2.56156 + vertex 1.55251 1.39832 2.56124 + endloop + endfacet + facet normal 0.00430523 -0.0326549 0.999457 + outer loop + vertex 1.56204 1.40239 2.56071 + vertex 1.5626 1.40739 2.56087 + vertex 1.55959 1.40559 2.56082 + endloop + endfacet + facet normal 0.00429395 -0.0365252 0.999324 + outer loop + vertex 1.56204 1.40239 2.56071 + vertex 1.55894 1.39858 2.56058 + vertex 1.56274 1.39668 2.56049 + endloop + endfacet + facet normal 0.00564485 -0.0338308 0.999412 + outer loop + vertex 1.55768 1.39328 2.56041 + vertex 1.56274 1.39668 2.56049 + vertex 1.55894 1.39858 2.56058 + endloop + endfacet + facet normal 0.0308179 -0.0712938 0.996979 + outer loop + vertex 1.56138 1.39174 2.56018 + vertex 1.56274 1.39668 2.56049 + vertex 1.55768 1.39328 2.56041 + endloop + endfacet + facet normal 0.0359518 -0.0591064 0.997604 + outer loop + vertex 1.5575 1.388 2.5601 + vertex 1.56138 1.39174 2.56018 + vertex 1.55768 1.39328 2.56041 + endloop + endfacet + facet normal 0.0441328 -0.0675845 0.996737 + outer loop + vertex 1.56213 1.38766 2.55987 + vertex 1.56138 1.39174 2.56018 + vertex 1.5575 1.388 2.5601 + endloop + endfacet + facet normal 0.0443709 -0.064514 0.99693 + outer loop + vertex 1.5574 1.38289 2.55977 + vertex 1.56213 1.38766 2.55987 + vertex 1.5575 1.388 2.5601 + endloop + endfacet + facet normal 0.0891789 -0.0651921 0.99388 + outer loop + vertex 1.5574 1.38289 2.55977 + vertex 1.5575 1.388 2.5601 + vertex 1.55272 1.38364 2.56024 + endloop + endfacet + facet normal 0.088392 -0.069894 0.993631 + outer loop + vertex 1.5527 1.37819 2.55986 + vertex 1.5574 1.38289 2.55977 + vertex 1.55272 1.38364 2.56024 + endloop + endfacet + facet normal 0.0915198 -0.0730282 0.993122 + outer loop + vertex 1.55736 1.37769 2.5594 + vertex 1.5574 1.38289 2.55977 + vertex 1.5527 1.37819 2.55986 + endloop + endfacet + facet normal 0.0914644 -0.0735172 0.993091 + outer loop + vertex 1.55249 1.37291 2.55949 + vertex 1.55736 1.37769 2.5594 + vertex 1.5527 1.37819 2.55986 + endloop + endfacet + facet normal 0.0963125 -0.0784633 0.992254 + outer loop + vertex 1.55732 1.37259 2.559 + vertex 1.55736 1.37769 2.5594 + vertex 1.55249 1.37291 2.55949 + endloop + endfacet + facet normal 0.096266 -0.079105 0.992207 + outer loop + vertex 1.55239 1.36775 2.55909 + vertex 1.55732 1.37259 2.559 + vertex 1.55249 1.37291 2.55949 + endloop + endfacet + facet normal 0.141972 -0.0795679 0.986668 + outer loop + vertex 1.55239 1.36775 2.55909 + vertex 1.55249 1.37291 2.55949 + vertex 1.548 1.36833 2.55977 + endloop + endfacet + facet normal 0.142239 -0.0776765 0.98678 + outer loop + vertex 1.54764 1.36314 2.55941 + vertex 1.55239 1.36775 2.55909 + vertex 1.548 1.36833 2.55977 + endloop + endfacet + facet normal 0.171045 -0.0793693 0.982061 + outer loop + vertex 1.54764 1.36314 2.55941 + vertex 1.548 1.36833 2.55977 + vertex 1.54382 1.36428 2.56017 + endloop + endfacet + facet normal 0.170961 -0.0792806 0.982083 + outer loop + vertex 1.54382 1.36428 2.56017 + vertex 1.548 1.36833 2.55977 + vertex 1.54439 1.36892 2.56044 + endloop + endfacet + facet normal 0.145971 -0.0815887 0.985919 + outer loop + vertex 1.55229 1.36265 2.55868 + vertex 1.55239 1.36775 2.55909 + vertex 1.54764 1.36314 2.55941 + endloop + endfacet + facet normal 0.146044 -0.0809546 0.98596 + outer loop + vertex 1.54735 1.35784 2.55902 + vertex 1.55229 1.36265 2.55868 + vertex 1.54764 1.36314 2.55941 + endloop + endfacet + facet normal 0.17083 -0.0819934 0.981883 + outer loop + vertex 1.54735 1.35784 2.55902 + vertex 1.54764 1.36314 2.55941 + vertex 1.54253 1.35856 2.55992 + endloop + endfacet + facet normal 0.170131 -0.086313 0.981634 + outer loop + vertex 1.54261 1.35304 2.55942 + vertex 1.54735 1.35784 2.55902 + vertex 1.54253 1.35856 2.55992 + endloop + endfacet + facet normal 0.174404 -0.0861904 0.980895 + outer loop + vertex 1.54253 1.35856 2.55992 + vertex 1.53817 1.35341 2.56024 + vertex 1.54261 1.35304 2.55942 + endloop + endfacet + facet normal 0.174006 -0.0903229 0.980593 + outer loop + vertex 1.53821 1.3485 2.55978 + vertex 1.54261 1.35304 2.55942 + vertex 1.53817 1.35341 2.56024 + endloop + endfacet + facet normal 0.182337 -0.0901144 0.979098 + outer loop + vertex 1.53817 1.35341 2.56024 + vertex 1.53461 1.34909 2.56051 + vertex 1.53821 1.3485 2.55978 + endloop + endfacet + facet normal 0.182447 -0.089492 0.979135 + outer loop + vertex 1.53391 1.3445 2.56022 + vertex 1.53821 1.3485 2.55978 + vertex 1.53461 1.34909 2.56051 + endloop + endfacet + facet normal 0.21798 -0.0944181 0.971375 + outer loop + vertex 1.53391 1.3445 2.56022 + vertex 1.53461 1.34909 2.56051 + vertex 1.53073 1.34582 2.56106 + endloop + endfacet + facet normal 0.21794 -0.0945151 0.971375 + outer loop + vertex 1.52968 1.34117 2.56084 + vertex 1.53391 1.3445 2.56022 + vertex 1.53073 1.34582 2.56106 + endloop + endfacet + facet normal 0.242371 -0.0997325 0.965044 + outer loop + vertex 1.53073 1.34582 2.56106 + vertex 1.52653 1.34211 2.56173 + vertex 1.52968 1.34117 2.56084 + endloop + endfacet + facet normal 0.171628 -0.0879735 0.981226 + outer loop + vertex 1.54253 1.34786 2.55897 + vertex 1.54261 1.35304 2.55942 + vertex 1.53821 1.3485 2.55978 + endloop + endfacet + facet normal 0.171787 -0.0869766 0.981287 + outer loop + vertex 1.53781 1.34336 2.55939 + vertex 1.54253 1.34786 2.55897 + vertex 1.53821 1.3485 2.55978 + endloop + endfacet + facet normal 0.17182 -0.0870122 0.981278 + outer loop + vertex 1.54246 1.34279 2.55853 + vertex 1.54253 1.34786 2.55897 + vertex 1.53781 1.34336 2.55939 + endloop + endfacet + facet normal 0.168527 -0.0870187 0.981849 + outer loop + vertex 1.54246 1.34279 2.55853 + vertex 1.54733 1.34761 2.55812 + vertex 1.54253 1.34786 2.55897 + endloop + endfacet + facet normal 0.168496 -0.0874779 0.981813 + outer loop + vertex 1.54733 1.34761 2.55812 + vertex 1.5473 1.35263 2.55857 + vertex 1.54253 1.34786 2.55897 + endloop + endfacet + facet normal 0.150726 -0.0878309 0.984666 + outer loop + vertex 1.54733 1.34761 2.55812 + vertex 1.55229 1.3526 2.55781 + vertex 1.5473 1.35263 2.55857 + endloop + endfacet + facet normal 0.150741 -0.0870428 0.984734 + outer loop + vertex 1.55229 1.3526 2.55781 + vertex 1.55225 1.35758 2.55825 + vertex 1.5473 1.35263 2.55857 + endloop + endfacet + facet normal 0.149234 -0.0855115 0.985097 + outer loop + vertex 1.5473 1.35263 2.55857 + vertex 1.55225 1.35758 2.55825 + vertex 1.54735 1.35784 2.55902 + endloop + endfacet + facet normal 0.109178 -0.0878731 0.990131 + outer loop + vertex 1.55229 1.3526 2.55781 + vertex 1.55737 1.3577 2.5577 + vertex 1.55225 1.35758 2.55825 + endloop + endfacet + facet normal 0.109191 -0.0889308 0.990035 + outer loop + vertex 1.55737 1.3577 2.5577 + vertex 1.55733 1.36262 2.55815 + vertex 1.55225 1.35758 2.55825 + endloop + endfacet + facet normal 0.104828 -0.0845154 0.990893 + outer loop + vertex 1.55225 1.35758 2.55825 + vertex 1.55733 1.36262 2.55815 + vertex 1.55229 1.36265 2.55868 + endloop + endfacet + facet normal 0.1048 -0.0864767 0.990726 + outer loop + vertex 1.55733 1.36262 2.55815 + vertex 1.55732 1.36759 2.55858 + vertex 1.55229 1.36265 2.55868 + endloop + endfacet + facet normal 0.0626242 -0.0869024 0.994247 + outer loop + vertex 1.55733 1.36262 2.55815 + vertex 1.5625 1.36774 2.55827 + vertex 1.55732 1.36759 2.55858 + endloop + endfacet + facet normal 0.0626138 -0.0864729 0.994285 + outer loop + vertex 1.5625 1.36774 2.55827 + vertex 1.56247 1.37267 2.5587 + vertex 1.55732 1.36759 2.55858 + endloop + endfacet + facet normal 0.0588626 -0.0826812 0.994836 + outer loop + vertex 1.55732 1.36759 2.55858 + vertex 1.56247 1.37267 2.5587 + vertex 1.55732 1.37259 2.559 + endloop + endfacet + facet normal 0.0588457 -0.0809488 0.99498 + outer loop + vertex 1.56247 1.37267 2.5587 + vertex 1.56243 1.37762 2.5591 + vertex 1.55732 1.37259 2.559 + endloop + endfacet + facet normal 0.065312 -0.0896048 0.993834 + outer loop + vertex 1.56251 1.36283 2.55782 + vertex 1.5625 1.36774 2.55827 + vertex 1.55733 1.36262 2.55815 + endloop + endfacet + facet normal 0.065312 -0.0896055 0.993834 + outer loop + vertex 1.55737 1.3577 2.5577 + vertex 1.56251 1.36283 2.55782 + vertex 1.55733 1.36262 2.55815 + endloop + endfacet + facet normal 0.067009 -0.0912997 0.993566 + outer loop + vertex 1.56256 1.35794 2.55737 + vertex 1.56251 1.36283 2.55782 + vertex 1.55737 1.3577 2.5577 + endloop + endfacet + facet normal 0.0670376 -0.0920052 0.993499 + outer loop + vertex 1.55748 1.35285 2.55724 + vertex 1.56256 1.35794 2.55737 + vertex 1.55737 1.3577 2.5577 + endloop + endfacet + facet normal 0.065395 -0.0903732 0.993759 + outer loop + vertex 1.56277 1.35304 2.55691 + vertex 1.56256 1.35794 2.55737 + vertex 1.55748 1.35285 2.55724 + endloop + endfacet + facet normal 0.0655859 -0.0966482 0.993155 + outer loop + vertex 1.55771 1.34809 2.55676 + vertex 1.56277 1.35304 2.55691 + vertex 1.55748 1.35285 2.55724 + endloop + endfacet + facet normal 0.115255 -0.0938532 0.988892 + outer loop + vertex 1.55771 1.34809 2.55676 + vertex 1.55748 1.35285 2.55724 + vertex 1.55242 1.34777 2.55735 + endloop + endfacet + facet normal 0.115304 -0.0948478 0.988792 + outer loop + vertex 1.5526 1.34308 2.55688 + vertex 1.55771 1.34809 2.55676 + vertex 1.55242 1.34777 2.55735 + endloop + endfacet + facet normal 0.156131 -0.0927761 0.98337 + outer loop + vertex 1.5526 1.34308 2.55688 + vertex 1.55242 1.34777 2.55735 + vertex 1.54744 1.34274 2.55767 + endloop + endfacet + facet normal 0.155878 -0.0877747 0.983869 + outer loop + vertex 1.54755 1.33795 2.55722 + vertex 1.5526 1.34308 2.55688 + vertex 1.54744 1.34274 2.55767 + endloop + endfacet + facet normal 0.172701 -0.087105 0.981115 + outer loop + vertex 1.54755 1.33795 2.55722 + vertex 1.54744 1.34274 2.55767 + vertex 1.5425 1.3378 2.5581 + endloop + endfacet + facet normal 0.172627 -0.0818317 0.981582 + outer loop + vertex 1.54257 1.33288 2.55767 + vertex 1.54755 1.33795 2.55722 + vertex 1.5425 1.3378 2.5581 + endloop + endfacet + facet normal 0.17933 -0.0816339 0.980396 + outer loop + vertex 1.54257 1.33288 2.55767 + vertex 1.5425 1.3378 2.5581 + vertex 1.5375 1.33287 2.5586 + endloop + endfacet + facet normal 0.179365 -0.0788756 0.980616 + outer loop + vertex 1.53752 1.32783 2.55819 + vertex 1.54257 1.33288 2.55767 + vertex 1.5375 1.33287 2.5586 + endloop + endfacet + facet normal 0.178327 -0.0788968 0.980803 + outer loop + vertex 1.53752 1.32783 2.55819 + vertex 1.5375 1.33287 2.5586 + vertex 1.53238 1.32781 2.55913 + endloop + endfacet + facet normal 0.178255 -0.0859124 0.980227 + outer loop + vertex 1.53234 1.3228 2.55869 + vertex 1.53752 1.32783 2.55819 + vertex 1.53238 1.32781 2.55913 + endloop + endfacet + facet normal 0.138407 -0.0861501 0.986621 + outer loop + vertex 1.53234 1.3228 2.55869 + vertex 1.53238 1.32781 2.55913 + vertex 1.52735 1.3227 2.55938 + endloop + endfacet + facet normal 0.176741 -0.0843121 0.98064 + outer loop + vertex 1.5376 1.32286 2.55775 + vertex 1.53752 1.32783 2.55819 + vertex 1.53234 1.3228 2.55869 + endloop + endfacet + facet normal 0.176714 -0.092406 0.979915 + outer loop + vertex 1.53236 1.31788 2.55823 + vertex 1.5376 1.32286 2.55775 + vertex 1.53234 1.3228 2.55869 + endloop + endfacet + facet normal 0.132421 -0.0932285 0.986799 + outer loop + vertex 1.53236 1.31788 2.55823 + vertex 1.53234 1.3228 2.55869 + vertex 1.52738 1.31792 2.5589 + endloop + endfacet + facet normal 0.177372 -0.0931164 0.979729 + outer loop + vertex 1.53753 1.31787 2.55729 + vertex 1.5376 1.32286 2.55775 + vertex 1.53236 1.31788 2.55823 + endloop + endfacet + facet normal 0.177206 -0.102166 0.978857 + outer loop + vertex 1.53239 1.31292 2.5577 + vertex 1.53753 1.31787 2.55729 + vertex 1.53236 1.31788 2.55823 + endloop + endfacet + facet normal 0.184206 -0.1096 0.976758 + outer loop + vertex 1.53763 1.3129 2.55671 + vertex 1.53753 1.31787 2.55729 + vertex 1.53239 1.31292 2.5577 + endloop + endfacet + facet normal 0.192218 -0.109262 0.975251 + outer loop + vertex 1.54177 1.3177 2.55643 + vertex 1.53753 1.31787 2.55729 + vertex 1.53763 1.3129 2.55671 + endloop + endfacet + facet normal 0.194859 -0.111584 0.974463 + outer loop + vertex 1.54181 1.31453 2.55606 + vertex 1.54177 1.3177 2.55643 + vertex 1.53763 1.3129 2.55671 + endloop + endfacet + facet normal 0.201391 -0.129722 0.970883 + outer loop + vertex 1.54181 1.31453 2.55606 + vertex 1.53763 1.3129 2.55671 + vertex 1.54042 1.31091 2.55587 + endloop + endfacet + facet normal 0.19881 -0.128764 0.971542 + outer loop + vertex 1.54429 1.31383 2.55546 + vertex 1.54181 1.31453 2.55606 + vertex 1.54042 1.31091 2.55587 + endloop + endfacet + facet normal 0.20083 -0.131559 0.970752 + outer loop + vertex 1.54286 1.30857 2.55505 + vertex 1.54429 1.31383 2.55546 + vertex 1.54042 1.31091 2.55587 + endloop + endfacet + facet normal 0.193894 -0.138921 0.971136 + outer loop + vertex 1.5389 1.30727 2.55565 + vertex 1.54286 1.30857 2.55505 + vertex 1.54042 1.31091 2.55587 + endloop + endfacet + facet normal 0.213565 -0.146781 0.965839 + outer loop + vertex 1.54042 1.31091 2.55587 + vertex 1.53642 1.30799 2.55631 + vertex 1.5389 1.30727 2.55565 + endloop + endfacet + facet normal 0.213092 -0.148284 0.965714 + outer loop + vertex 1.5389 1.30727 2.55565 + vertex 1.53642 1.30799 2.55631 + vertex 1.53619 1.30497 2.5559 + endloop + endfacet + facet normal 0.202759 -0.135656 0.969787 + outer loop + vertex 1.5389 1.30727 2.55565 + vertex 1.53619 1.30497 2.5559 + vertex 1.53821 1.30345 2.55526 + endloop + endfacet + facet normal 0.206526 -0.130632 0.969682 + outer loop + vertex 1.53821 1.30345 2.55526 + vertex 1.53619 1.30497 2.5559 + vertex 1.53461 1.30221 2.55586 + endloop + endfacet + facet normal 0.200388 -0.111056 0.973402 + outer loop + vertex 1.53461 1.30221 2.55586 + vertex 1.53419 1.29893 2.55557 + vertex 1.53821 1.30345 2.55526 + endloop + endfacet + facet normal 0.22013 -0.113213 0.968879 + outer loop + vertex 1.53461 1.30221 2.55586 + vertex 1.53186 1.29971 2.55619 + vertex 1.53419 1.29893 2.55557 + endloop + endfacet + facet normal 0.230052 -0.124624 0.965166 + outer loop + vertex 1.53461 1.30221 2.55586 + vertex 1.53246 1.30342 2.55653 + vertex 1.53186 1.29971 2.55619 + endloop + endfacet + facet normal 0.174201 -0.116774 0.977762 + outer loop + vertex 1.53186 1.29971 2.55619 + vertex 1.53246 1.30342 2.55653 + vertex 1.528 1.29791 2.55667 + endloop + endfacet + facet normal 0.153323 -0.0699118 0.9857 + outer loop + vertex 1.53186 1.29971 2.55619 + vertex 1.528 1.29791 2.55667 + vertex 1.5302 1.29579 2.55617 + endloop + endfacet + facet normal 0.221767 -0.139294 0.965099 + outer loop + vertex 1.53619 1.30497 2.5559 + vertex 1.53246 1.30342 2.55653 + vertex 1.53461 1.30221 2.55586 + endloop + endfacet + facet normal 0.225344 -0.148803 0.962849 + outer loop + vertex 1.53619 1.30497 2.5559 + vertex 1.53642 1.30799 2.55631 + vertex 1.53246 1.30342 2.55653 + endloop + endfacet + facet normal 0.198987 -0.125558 0.971926 + outer loop + vertex 1.53642 1.30799 2.55631 + vertex 1.53234 1.308 2.55715 + vertex 1.53246 1.30342 2.55653 + endloop + endfacet + facet normal 0.198892 -0.128935 0.971503 + outer loop + vertex 1.53642 1.30799 2.55631 + vertex 1.53763 1.3129 2.55671 + vertex 1.53234 1.308 2.55715 + endloop + endfacet + facet normal 0.192425 -0.134022 0.972117 + outer loop + vertex 1.5389 1.30727 2.55565 + vertex 1.53821 1.30345 2.55526 + vertex 1.54286 1.30857 2.55505 + endloop + endfacet + facet normal 0.184216 -0.126473 0.974715 + outer loop + vertex 1.54286 1.30857 2.55505 + vertex 1.53821 1.30345 2.55526 + vertex 1.54268 1.30321 2.55438 + endloop + endfacet + facet normal 0.177202 -0.126411 0.976022 + outer loop + vertex 1.54268 1.30321 2.55438 + vertex 1.54751 1.30801 2.55413 + vertex 1.54286 1.30857 2.55505 + endloop + endfacet + facet normal 0.178121 -0.119863 0.976681 + outer loop + vertex 1.54751 1.30801 2.55413 + vertex 1.54791 1.31326 2.5547 + vertex 1.54286 1.30857 2.55505 + endloop + endfacet + facet normal 0.158907 -0.118787 0.980122 + outer loop + vertex 1.54751 1.30801 2.55413 + vertex 1.55239 1.31285 2.55392 + vertex 1.54791 1.31326 2.5547 + endloop + endfacet + facet normal 0.160022 -0.108571 0.981125 + outer loop + vertex 1.55239 1.31285 2.55392 + vertex 1.55262 1.31806 2.55446 + vertex 1.54791 1.31326 2.5547 + endloop + endfacet + facet normal 0.164406 -0.112939 0.979906 + outer loop + vertex 1.54791 1.31326 2.5547 + vertex 1.55262 1.31806 2.55446 + vertex 1.54814 1.31855 2.55527 + endloop + endfacet + facet normal 0.187565 -0.11352 0.97567 + outer loop + vertex 1.54814 1.31855 2.55527 + vertex 1.54429 1.31383 2.55546 + vertex 1.54791 1.31326 2.5547 + endloop + endfacet + facet normal 0.194467 -0.119244 0.973634 + outer loop + vertex 1.54439 1.31708 2.55584 + vertex 1.54429 1.31383 2.55546 + vertex 1.54814 1.31855 2.55527 + endloop + endfacet + facet normal 0.188772 -0.103509 0.97655 + outer loop + vertex 1.54439 1.31708 2.55584 + vertex 1.54814 1.31855 2.55527 + vertex 1.54565 1.32075 2.55599 + endloop + endfacet + facet normal 0.195701 -0.10583 0.974937 + outer loop + vertex 1.54565 1.32075 2.55599 + vertex 1.54177 1.3177 2.55643 + vertex 1.54439 1.31708 2.55584 + endloop + endfacet + facet normal 0.189611 -0.0977676 0.97698 + outer loop + vertex 1.54291 1.32288 2.55673 + vertex 1.54177 1.3177 2.55643 + vertex 1.54565 1.32075 2.55599 + endloop + endfacet + facet normal 0.189404 -0.0980389 0.976993 + outer loop + vertex 1.54705 1.32456 2.5561 + vertex 1.54291 1.32288 2.55673 + vertex 1.54565 1.32075 2.55599 + endloop + endfacet + facet normal 0.182369 -0.095506 0.978581 + outer loop + vertex 1.54941 1.32375 2.55558 + vertex 1.54705 1.32456 2.5561 + vertex 1.54565 1.32075 2.55599 + endloop + endfacet + facet normal 0.18252 -0.0950734 0.978595 + outer loop + vertex 1.54963 1.32701 2.55586 + vertex 1.54705 1.32456 2.5561 + vertex 1.54941 1.32375 2.55558 + endloop + endfacet + facet normal 0.160743 -0.0939452 0.982515 + outer loop + vertex 1.54963 1.32701 2.55586 + vertex 1.54941 1.32375 2.55558 + vertex 1.55316 1.32836 2.55541 + endloop + endfacet + facet normal 0.156784 -0.0830133 0.984138 + outer loop + vertex 1.55316 1.32836 2.55541 + vertex 1.55106 1.32991 2.55587 + vertex 1.54963 1.32701 2.55586 + endloop + endfacet + facet normal 0.178528 -0.0937596 0.979458 + outer loop + vertex 1.55106 1.32991 2.55587 + vertex 1.54749 1.32839 2.55638 + vertex 1.54963 1.32701 2.55586 + endloop + endfacet + facet normal 0.177352 -0.0908408 0.979946 + outer loop + vertex 1.55106 1.32991 2.55587 + vertex 1.55132 1.33313 2.55612 + vertex 1.54749 1.32839 2.55638 + endloop + endfacet + facet normal 0.174499 -0.0884979 0.980672 + outer loop + vertex 1.55132 1.33313 2.55612 + vertex 1.54743 1.33311 2.55681 + vertex 1.54749 1.32839 2.55638 + endloop + endfacet + facet normal 0.183184 -0.0882587 0.979109 + outer loop + vertex 1.54749 1.32839 2.55638 + vertex 1.54743 1.33311 2.55681 + vertex 1.54266 1.32798 2.55724 + endloop + endfacet + facet normal 0.18325 -0.0892399 0.979008 + outer loop + vertex 1.54749 1.32839 2.55638 + vertex 1.54266 1.32798 2.55724 + vertex 1.54291 1.32288 2.55673 + endloop + endfacet + facet normal 0.188101 -0.0889138 0.978117 + outer loop + vertex 1.54291 1.32288 2.55673 + vertex 1.54266 1.32798 2.55724 + vertex 1.5376 1.32286 2.55775 + endloop + endfacet + facet normal 0.17785 -0.0831785 0.980536 + outer loop + vertex 1.54266 1.32798 2.55724 + vertex 1.54743 1.33311 2.55681 + vertex 1.54257 1.33288 2.55767 + endloop + endfacet + facet normal 0.174413 -0.0971749 0.979866 + outer loop + vertex 1.55132 1.33313 2.55612 + vertex 1.55274 1.33825 2.55638 + vertex 1.54743 1.33311 2.55681 + endloop + endfacet + facet normal 0.164854 -0.0870897 0.982466 + outer loop + vertex 1.54743 1.33311 2.55681 + vertex 1.55274 1.33825 2.55638 + vertex 1.54755 1.33795 2.55722 + endloop + endfacet + facet normal 0.155019 -0.0919691 0.983621 + outer loop + vertex 1.55274 1.33825 2.55638 + vertex 1.55132 1.33313 2.55612 + vertex 1.55534 1.33621 2.55578 + endloop + endfacet + facet normal 0.151661 -0.0962771 0.983732 + outer loop + vertex 1.55703 1.33998 2.55589 + vertex 1.55274 1.33825 2.55638 + vertex 1.55534 1.33621 2.55578 + endloop + endfacet + facet normal 0.0984702 -0.0727075 0.99248 + outer loop + vertex 1.55931 1.33873 2.55557 + vertex 1.55703 1.33998 2.55589 + vertex 1.55534 1.33621 2.55578 + endloop + endfacet + facet normal 0.102651 -0.0793672 0.991546 + outer loop + vertex 1.55782 1.33359 2.55531 + vertex 1.55931 1.33873 2.55557 + vertex 1.55534 1.33621 2.55578 + endloop + endfacet + facet normal 0.108372 -0.0739046 0.991359 + outer loop + vertex 1.55373 1.33237 2.55567 + vertex 1.55782 1.33359 2.55531 + vertex 1.55534 1.33621 2.55578 + endloop + endfacet + facet normal 0.110161 -0.0801204 0.990679 + outer loop + vertex 1.55373 1.33237 2.55567 + vertex 1.55316 1.32836 2.55541 + vertex 1.55782 1.33359 2.55531 + endloop + endfacet + facet normal 0.118467 -0.0875624 0.98909 + outer loop + vertex 1.55782 1.33359 2.55531 + vertex 1.55316 1.32836 2.55541 + vertex 1.5577 1.32813 2.55484 + endloop + endfacet + facet normal 0.0579489 -0.0866948 0.994548 + outer loop + vertex 1.5577 1.32813 2.55484 + vertex 1.56253 1.33256 2.55495 + vertex 1.55782 1.33359 2.55531 + endloop + endfacet + facet normal 0.0577916 -0.0873997 0.994496 + outer loop + vertex 1.56253 1.33256 2.55495 + vertex 1.56284 1.33746 2.55536 + vertex 1.55782 1.33359 2.55531 + endloop + endfacet + facet normal 0.0691248 -0.0988227 0.992701 + outer loop + vertex 1.56235 1.32765 2.55447 + vertex 1.56253 1.33256 2.55495 + vertex 1.5577 1.32813 2.55484 + endloop + endfacet + facet normal 0.0695268 -0.0952146 0.993026 + outer loop + vertex 1.55751 1.32293 2.55436 + vertex 1.56235 1.32765 2.55447 + vertex 1.5577 1.32813 2.55484 + endloop + endfacet + facet normal 0.121101 -0.0966795 0.987921 + outer loop + vertex 1.55751 1.32293 2.55436 + vertex 1.5577 1.32813 2.55484 + vertex 1.55301 1.32329 2.55494 + endloop + endfacet + facet normal 0.120837 -0.0995702 0.987666 + outer loop + vertex 1.55262 1.31806 2.55446 + vertex 1.55751 1.32293 2.55436 + vertex 1.55301 1.32329 2.55494 + endloop + endfacet + facet normal 0.120515 -0.0992455 0.987738 + outer loop + vertex 1.55735 1.31778 2.55386 + vertex 1.55751 1.32293 2.55436 + vertex 1.55262 1.31806 2.55446 + endloop + endfacet + facet normal 0.0692092 -0.0981326 0.992764 + outer loop + vertex 1.55735 1.31778 2.55386 + vertex 1.5624 1.32275 2.554 + vertex 1.55751 1.32293 2.55436 + endloop + endfacet + facet normal 0.0691675 -0.0980905 0.992771 + outer loop + vertex 1.56237 1.31773 2.5535 + vertex 1.5624 1.32275 2.554 + vertex 1.55735 1.31778 2.55386 + endloop + endfacet + facet normal 0.0690426 -0.104893 0.992084 + outer loop + vertex 1.55725 1.3127 2.55333 + vertex 1.56237 1.31773 2.5535 + vertex 1.55735 1.31778 2.55386 + endloop + endfacet + facet normal 0.117947 -0.105376 0.987413 + outer loop + vertex 1.55725 1.3127 2.55333 + vertex 1.55735 1.31778 2.55386 + vertex 1.55239 1.31285 2.55392 + endloop + endfacet + facet normal 0.11758 -0.113706 0.986532 + outer loop + vertex 1.55227 1.30774 2.55335 + vertex 1.55725 1.3127 2.55333 + vertex 1.55239 1.31285 2.55392 + endloop + endfacet + facet normal 0.116121 -0.112239 0.986873 + outer loop + vertex 1.55727 1.30774 2.55276 + vertex 1.55725 1.3127 2.55333 + vertex 1.55227 1.30774 2.55335 + endloop + endfacet + facet normal 0.11603 -0.118445 0.986158 + outer loop + vertex 1.55235 1.30279 2.55275 + vertex 1.55727 1.30774 2.55276 + vertex 1.55227 1.30774 2.55335 + endloop + endfacet + facet normal 0.151343 -0.117312 0.981495 + outer loop + vertex 1.55235 1.30279 2.55275 + vertex 1.55227 1.30774 2.55335 + vertex 1.54739 1.30287 2.55352 + endloop + endfacet + facet normal 0.151334 -0.117606 0.981462 + outer loop + vertex 1.54747 1.29789 2.55291 + vertex 1.55235 1.30279 2.55275 + vertex 1.54739 1.30287 2.55352 + endloop + endfacet + facet normal 0.171598 -0.11691 0.978206 + outer loop + vertex 1.54747 1.29789 2.55291 + vertex 1.54739 1.30287 2.55352 + vertex 1.54251 1.29804 2.5538 + endloop + endfacet + facet normal 0.171982 -0.109186 0.97903 + outer loop + vertex 1.54249 1.29297 2.55324 + vertex 1.54747 1.29789 2.55291 + vertex 1.54251 1.29804 2.5538 + endloop + endfacet + facet normal 0.193733 -0.108799 0.975003 + outer loop + vertex 1.54249 1.29297 2.55324 + vertex 1.54251 1.29804 2.5538 + vertex 1.53745 1.29311 2.55425 + endloop + endfacet + facet normal 0.194025 -0.102856 0.97559 + outer loop + vertex 1.53738 1.2879 2.55372 + vertex 1.54249 1.29297 2.55324 + vertex 1.53745 1.29311 2.55425 + endloop + endfacet + facet normal 0.197149 -0.106099 0.974615 + outer loop + vertex 1.54261 1.28797 2.55267 + vertex 1.54249 1.29297 2.55324 + vertex 1.53738 1.2879 2.55372 + endloop + endfacet + facet normal 0.197168 -0.103379 0.974904 + outer loop + vertex 1.53741 1.28284 2.55318 + vertex 1.54261 1.28797 2.55267 + vertex 1.53738 1.2879 2.55372 + endloop + endfacet + facet normal 0.18965 -0.103582 0.976373 + outer loop + vertex 1.53741 1.28284 2.55318 + vertex 1.53738 1.2879 2.55372 + vertex 1.53232 1.28264 2.55414 + endloop + endfacet + facet normal 0.189634 -0.102766 0.976462 + outer loop + vertex 1.53234 1.27755 2.5536 + vertex 1.53741 1.28284 2.55318 + vertex 1.53232 1.28264 2.55414 + endloop + endfacet + facet normal 0.0856456 -0.104852 0.990793 + outer loop + vertex 1.53234 1.27755 2.5536 + vertex 1.53232 1.28264 2.55414 + vertex 1.52768 1.2775 2.554 + endloop + endfacet + facet normal 0.200943 -0.11388 0.972961 + outer loop + vertex 1.53752 1.27792 2.55258 + vertex 1.53741 1.28284 2.55318 + vertex 1.53234 1.27755 2.5536 + endloop + endfacet + facet normal 0.201098 -0.117291 0.972524 + outer loop + vertex 1.53246 1.27262 2.55299 + vertex 1.53752 1.27792 2.55258 + vertex 1.53234 1.27755 2.5536 + endloop + endfacet + facet normal 0.218317 -0.134198 0.966607 + outer loop + vertex 1.53777 1.27296 2.55183 + vertex 1.53752 1.27792 2.55258 + vertex 1.53246 1.27262 2.55299 + endloop + endfacet + facet normal 0.214232 -0.134539 0.967473 + outer loop + vertex 1.54266 1.27839 2.5515 + vertex 1.53752 1.27792 2.55258 + vertex 1.53777 1.27296 2.55183 + endloop + endfacet + facet normal 0.219489 -0.139383 0.965607 + outer loop + vertex 1.54218 1.2747 2.55108 + vertex 1.54266 1.27839 2.5515 + vertex 1.53777 1.27296 2.55183 + endloop + endfacet + facet normal 0.221653 -0.145443 0.964218 + outer loop + vertex 1.54218 1.2747 2.55108 + vertex 1.53777 1.27296 2.55183 + vertex 1.54055 1.27095 2.55089 + endloop + endfacet + facet normal 0.193495 -0.136706 0.97153 + outer loop + vertex 1.54493 1.27704 2.55086 + vertex 1.54266 1.27839 2.5515 + vertex 1.54218 1.2747 2.55108 + endloop + endfacet + facet normal 0.18972 -0.132134 0.972906 + outer loop + vertex 1.54493 1.27704 2.55086 + vertex 1.54218 1.2747 2.55108 + vertex 1.54458 1.27385 2.5505 + endloop + endfacet + facet normal 0.17272 -0.130623 0.976271 + outer loop + vertex 1.54493 1.27704 2.55086 + vertex 1.54458 1.27385 2.5505 + vertex 1.54843 1.27827 2.55041 + endloop + endfacet + facet normal 0.171473 -0.126801 0.976995 + outer loop + vertex 1.54843 1.27827 2.55041 + vertex 1.54643 1.27977 2.55095 + vertex 1.54493 1.27704 2.55086 + endloop + endfacet + facet normal 0.172212 -0.125812 0.976992 + outer loop + vertex 1.54909 1.28209 2.55078 + vertex 1.54643 1.27977 2.55095 + vertex 1.54843 1.27827 2.55041 + endloop + endfacet + facet normal 0.157893 -0.123626 0.979687 + outer loop + vertex 1.54909 1.28209 2.55078 + vertex 1.54843 1.27827 2.55041 + vertex 1.55302 1.28353 2.55033 + endloop + endfacet + facet normal 0.154332 -0.113326 0.981498 + outer loop + vertex 1.54909 1.28209 2.55078 + vertex 1.55302 1.28353 2.55033 + vertex 1.55064 1.28583 2.55097 + endloop + endfacet + facet normal 0.170554 -0.11989 0.978027 + outer loop + vertex 1.55064 1.28583 2.55097 + vertex 1.54665 1.28289 2.55131 + vertex 1.54909 1.28209 2.55078 + endloop + endfacet + facet normal 0.166854 -0.114716 0.979285 + outer loop + vertex 1.54798 1.28799 2.55168 + vertex 1.54665 1.28289 2.55131 + vertex 1.55064 1.28583 2.55097 + endloop + endfacet + facet normal 0.166229 -0.115493 0.9793 + outer loop + vertex 1.55226 1.28957 2.55114 + vertex 1.54798 1.28799 2.55168 + vertex 1.55064 1.28583 2.55097 + endloop + endfacet + facet normal 0.168712 -0.122655 0.978004 + outer loop + vertex 1.55226 1.28957 2.55114 + vertex 1.55294 1.29333 2.55149 + vertex 1.54798 1.28799 2.55168 + endloop + endfacet + facet normal 0.159178 -0.113692 0.980682 + outer loop + vertex 1.55294 1.29333 2.55149 + vertex 1.5477 1.29302 2.55231 + vertex 1.54798 1.28799 2.55168 + endloop + endfacet + facet normal 0.180642 -0.112068 0.977143 + outer loop + vertex 1.54798 1.28799 2.55168 + vertex 1.5477 1.29302 2.55231 + vertex 1.54261 1.28797 2.55267 + endloop + endfacet + facet normal 0.180657 -0.111208 0.977239 + outer loop + vertex 1.54254 1.28305 2.55212 + vertex 1.54798 1.28799 2.55168 + vertex 1.54261 1.28797 2.55267 + endloop + endfacet + facet normal 0.159519 -0.122184 0.979604 + outer loop + vertex 1.55294 1.29333 2.55149 + vertex 1.55264 1.29801 2.55213 + vertex 1.5477 1.29302 2.55231 + endloop + endfacet + facet normal 0.151963 -0.114638 0.981716 + outer loop + vertex 1.5477 1.29302 2.55231 + vertex 1.55264 1.29801 2.55213 + vertex 1.54747 1.29789 2.55291 + endloop + endfacet + facet normal 0.125061 -0.125043 0.984238 + outer loop + vertex 1.55809 1.2982 2.55146 + vertex 1.55264 1.29801 2.55213 + vertex 1.55294 1.29333 2.55149 + endloop + endfacet + facet normal 0.151906 -0.153506 0.976402 + outer loop + vertex 1.55688 1.29436 2.55104 + vertex 1.55809 1.2982 2.55146 + vertex 1.55294 1.29333 2.55149 + endloop + endfacet + facet normal 0.146725 -0.132037 0.980325 + outer loop + vertex 1.55688 1.29436 2.55104 + vertex 1.55294 1.29333 2.55149 + vertex 1.55493 1.29171 2.55098 + endloop + endfacet + facet normal 0.118817 -0.111656 0.986618 + outer loop + vertex 1.55791 1.29206 2.55066 + vertex 1.55688 1.29436 2.55104 + vertex 1.55493 1.29171 2.55098 + endloop + endfacet + facet normal 0.118205 -0.105767 0.98734 + outer loop + vertex 1.55493 1.29171 2.55098 + vertex 1.5545 1.2886 2.55069 + vertex 1.55791 1.29206 2.55066 + endloop + endfacet + facet normal 0.117459 -0.10503 0.987508 + outer loop + vertex 1.55791 1.29206 2.55066 + vertex 1.5545 1.2886 2.55069 + vertex 1.55802 1.28814 2.55023 + endloop + endfacet + facet normal 0.0736916 -0.106682 0.991559 + outer loop + vertex 1.55802 1.28814 2.55023 + vertex 1.56251 1.29273 2.55039 + vertex 1.55791 1.29206 2.55066 + endloop + endfacet + facet normal 0.0735631 -0.105758 0.991667 + outer loop + vertex 1.55791 1.29206 2.55066 + vertex 1.56251 1.29273 2.55039 + vertex 1.56052 1.29572 2.55085 + endloop + endfacet + facet normal 0.0965249 -0.121859 0.987843 + outer loop + vertex 1.55688 1.29436 2.55104 + vertex 1.55791 1.29206 2.55066 + vertex 1.56052 1.29572 2.55085 + endloop + endfacet + facet normal 0.102771 -0.138931 0.984955 + outer loop + vertex 1.56052 1.29572 2.55085 + vertex 1.55809 1.2982 2.55146 + vertex 1.55688 1.29436 2.55104 + endloop + endfacet + facet normal 0.083225 -0.157867 0.983947 + outer loop + vertex 1.56352 1.29926 2.55117 + vertex 1.55809 1.2982 2.55146 + vertex 1.56052 1.29572 2.55085 + endloop + endfacet + facet normal 0.0625508 -0.140659 0.98808 + outer loop + vertex 1.56422 1.2966 2.55074 + vertex 1.56352 1.29926 2.55117 + vertex 1.56052 1.29572 2.55085 + endloop + endfacet + facet normal 0.0312557 -0.148905 0.988357 + outer loop + vertex 1.56679 1.29868 2.55098 + vertex 1.56352 1.29926 2.55117 + vertex 1.56422 1.2966 2.55074 + endloop + endfacet + facet normal 0.0106656 -0.123883 0.99224 + outer loop + vertex 1.56769 1.2957 2.55059 + vertex 1.56679 1.29868 2.55098 + vertex 1.56422 1.2966 2.55074 + endloop + endfacet + facet normal 0.0171659 -0.0994863 0.994891 + outer loop + vertex 1.56422 1.2966 2.55074 + vertex 1.56251 1.29273 2.55039 + vertex 1.56769 1.2957 2.55059 + endloop + endfacet + facet normal 0.0332732 -0.12737 0.991297 + outer loop + vertex 1.56769 1.2957 2.55059 + vertex 1.56251 1.29273 2.55039 + vertex 1.56649 1.29167 2.55012 + endloop + endfacet + facet normal 0.0375352 -0.1119 0.99301 + outer loop + vertex 1.56243 1.28788 2.54984 + vertex 1.56649 1.29167 2.55012 + vertex 1.56251 1.29273 2.55039 + endloop + endfacet + facet normal 0.0420698 -0.116705 0.992275 + outer loop + vertex 1.5673 1.2879 2.54964 + vertex 1.56649 1.29167 2.55012 + vertex 1.56243 1.28788 2.54984 + endloop + endfacet + facet normal 0.0420643 -0.119052 0.991997 + outer loop + vertex 1.56241 1.28297 2.54926 + vertex 1.5673 1.2879 2.54964 + vertex 1.56243 1.28788 2.54984 + endloop + endfacet + facet normal 0.0847014 -0.118928 0.989284 + outer loop + vertex 1.56241 1.28297 2.54926 + vertex 1.56243 1.28788 2.54984 + vertex 1.55766 1.28317 2.54969 + endloop + endfacet + facet normal 0.0844344 -0.123986 0.988685 + outer loop + vertex 1.55742 1.27797 2.54905 + vertex 1.56241 1.28297 2.54926 + vertex 1.55766 1.28317 2.54969 + endloop + endfacet + facet normal 0.130282 -0.12546 0.983507 + outer loop + vertex 1.55742 1.27797 2.54905 + vertex 1.55766 1.28317 2.54969 + vertex 1.5528 1.27819 2.5497 + endloop + endfacet + facet normal 0.130113 -0.128044 0.983197 + outer loop + vertex 1.5525 1.27298 2.54905 + vertex 1.55742 1.27797 2.54905 + vertex 1.5528 1.27819 2.5497 + endloop + endfacet + facet normal 0.133408 -0.131289 0.982327 + outer loop + vertex 1.55728 1.27282 2.54838 + vertex 1.55742 1.27797 2.54905 + vertex 1.5525 1.27298 2.54905 + endloop + endfacet + facet normal 0.13357 -0.128157 0.982718 + outer loop + vertex 1.55236 1.26786 2.54841 + vertex 1.55728 1.27282 2.54838 + vertex 1.5525 1.27298 2.54905 + endloop + endfacet + facet normal 0.163854 -0.1284 0.978093 + outer loop + vertex 1.55236 1.26786 2.54841 + vertex 1.5525 1.27298 2.54905 + vertex 1.54762 1.26809 2.54923 + endloop + endfacet + facet normal 0.164395 -0.120626 0.978991 + outer loop + vertex 1.54747 1.26294 2.54862 + vertex 1.55236 1.26786 2.54841 + vertex 1.54762 1.26809 2.54923 + endloop + endfacet + facet normal 0.170354 -0.126633 0.977212 + outer loop + vertex 1.55245 1.26295 2.54775 + vertex 1.55236 1.26786 2.54841 + vertex 1.54747 1.26294 2.54862 + endloop + endfacet + facet normal 0.170466 -0.121054 0.977899 + outer loop + vertex 1.5475 1.25797 2.548 + vertex 1.55245 1.26295 2.54775 + vertex 1.54747 1.26294 2.54862 + endloop + endfacet + facet normal 0.183145 -0.120687 0.97565 + outer loop + vertex 1.5475 1.25797 2.548 + vertex 1.54747 1.26294 2.54862 + vertex 1.54247 1.25795 2.54894 + endloop + endfacet + facet normal 0.183167 -0.119497 0.975792 + outer loop + vertex 1.54244 1.25291 2.54833 + vertex 1.5475 1.25797 2.548 + vertex 1.54247 1.25795 2.54894 + endloop + endfacet + facet normal 0.161565 -0.119822 0.979561 + outer loop + vertex 1.54244 1.25291 2.54833 + vertex 1.54247 1.25795 2.54894 + vertex 1.53734 1.25289 2.54917 + endloop + endfacet + facet normal 0.161598 -0.117816 0.979799 + outer loop + vertex 1.53731 1.24777 2.54856 + vertex 1.54244 1.25291 2.54833 + vertex 1.53734 1.25289 2.54917 + endloop + endfacet + facet normal 0.0691514 -0.118594 0.990532 + outer loop + vertex 1.53731 1.24777 2.54856 + vertex 1.53734 1.25289 2.54917 + vertex 1.53234 1.24786 2.54892 + endloop + endfacet + facet normal 0.173043 -0.129378 0.97638 + outer loop + vertex 1.54257 1.24797 2.54765 + vertex 1.54244 1.25291 2.54833 + vertex 1.53731 1.24777 2.54856 + endloop + endfacet + facet normal 0.172933 -0.122045 0.977343 + outer loop + vertex 1.53747 1.24278 2.54791 + vertex 1.54257 1.24797 2.54765 + vertex 1.53731 1.24777 2.54856 + endloop + endfacet + facet normal 0.0884676 -0.126037 0.988073 + outer loop + vertex 1.53747 1.24278 2.54791 + vertex 1.53731 1.24777 2.54856 + vertex 1.53252 1.2427 2.54834 + endloop + endfacet + facet normal 0.0883699 -0.109354 0.990067 + outer loop + vertex 1.53276 1.23774 2.54777 + vertex 1.53747 1.24278 2.54791 + vertex 1.53252 1.2427 2.54834 + endloop + endfacet + facet normal 0.121309 -0.139907 0.982705 + outer loop + vertex 1.53741 1.23803 2.54724 + vertex 1.53747 1.24278 2.54791 + vertex 1.53276 1.23774 2.54777 + endloop + endfacet + facet normal 0.198795 -0.138995 0.970134 + outer loop + vertex 1.53741 1.23803 2.54724 + vertex 1.54282 1.24301 2.54685 + vertex 1.53747 1.24278 2.54791 + endloop + endfacet + facet normal 0.198909 -0.148025 0.968774 + outer loop + vertex 1.54282 1.24301 2.54685 + vertex 1.54257 1.24797 2.54765 + vertex 1.53747 1.24278 2.54791 + endloop + endfacet + facet normal 0.190987 -0.128443 0.973153 + outer loop + vertex 1.54257 1.24797 2.54765 + vertex 1.54764 1.25315 2.54734 + vertex 1.54244 1.25291 2.54833 + endloop + endfacet + facet normal 0.202823 -0.140254 0.969119 + outer loop + vertex 1.54784 1.24842 2.54662 + vertex 1.54764 1.25315 2.54734 + vertex 1.54257 1.24797 2.54765 + endloop + endfacet + facet normal 0.166568 -0.124954 0.978081 + outer loop + vertex 1.53734 1.25289 2.54917 + vertex 1.54247 1.25795 2.54894 + vertex 1.53762 1.25806 2.54978 + endloop + endfacet + facet normal 0.190967 -0.127465 0.973285 + outer loop + vertex 1.54764 1.25315 2.54734 + vertex 1.5475 1.25797 2.548 + vertex 1.54244 1.25291 2.54833 + endloop + endfacet + facet normal 0.177795 -0.128157 0.975687 + outer loop + vertex 1.54764 1.25315 2.54734 + vertex 1.55263 1.25823 2.5471 + vertex 1.5475 1.25797 2.548 + endloop + endfacet + facet normal 0.184887 -0.135233 0.973411 + outer loop + vertex 1.55272 1.2536 2.54644 + vertex 1.55263 1.25823 2.5471 + vertex 1.54764 1.25315 2.54734 + endloop + endfacet + facet normal 0.155544 -0.136552 0.978345 + outer loop + vertex 1.55773 1.25862 2.54634 + vertex 1.55263 1.25823 2.5471 + vertex 1.55272 1.2536 2.54644 + endloop + endfacet + facet normal 0.155826 -0.141778 0.977557 + outer loop + vertex 1.55773 1.25862 2.54634 + vertex 1.55761 1.26317 2.54702 + vertex 1.55263 1.25823 2.5471 + endloop + endfacet + facet normal 0.14462 -0.130421 0.980854 + outer loop + vertex 1.55263 1.25823 2.5471 + vertex 1.55761 1.26317 2.54702 + vertex 1.55245 1.26295 2.54775 + endloop + endfacet + facet normal 0.144705 -0.133866 0.980378 + outer loop + vertex 1.55761 1.26317 2.54702 + vertex 1.55735 1.26787 2.5477 + vertex 1.55245 1.26295 2.54775 + endloop + endfacet + facet normal 0.0983767 -0.137184 0.985648 + outer loop + vertex 1.55761 1.26317 2.54702 + vertex 1.56256 1.26803 2.54721 + vertex 1.55735 1.26787 2.5477 + endloop + endfacet + facet normal 0.0984157 -0.139539 0.985314 + outer loop + vertex 1.56256 1.26803 2.54721 + vertex 1.56231 1.27282 2.54791 + vertex 1.55735 1.26787 2.5477 + endloop + endfacet + facet normal 0.0933428 -0.134514 0.986505 + outer loop + vertex 1.55735 1.26787 2.5477 + vertex 1.56231 1.27282 2.54791 + vertex 1.55728 1.27282 2.54838 + endloop + endfacet + facet normal 0.0933318 -0.135501 0.986371 + outer loop + vertex 1.56231 1.27282 2.54791 + vertex 1.56231 1.27785 2.5486 + vertex 1.55728 1.27282 2.54838 + endloop + endfacet + facet normal 0.0537983 -0.135893 0.989262 + outer loop + vertex 1.56231 1.27282 2.54791 + vertex 1.56738 1.27786 2.54833 + vertex 1.56231 1.27785 2.5486 + endloop + endfacet + facet normal 0.0538159 -0.132538 0.989716 + outer loop + vertex 1.56738 1.27786 2.54833 + vertex 1.56742 1.28292 2.549 + vertex 1.56231 1.27785 2.5486 + endloop + endfacet + facet normal 0.0489799 -0.127733 0.990598 + outer loop + vertex 1.56231 1.27785 2.5486 + vertex 1.56742 1.28292 2.549 + vertex 1.56241 1.28297 2.54926 + endloop + endfacet + facet normal 0.0568804 -0.138946 0.988665 + outer loop + vertex 1.56749 1.27291 2.54762 + vertex 1.56738 1.27786 2.54833 + vertex 1.56231 1.27282 2.54791 + endloop + endfacet + facet normal 0.0569117 -0.142161 0.988206 + outer loop + vertex 1.56256 1.26803 2.54721 + vertex 1.56749 1.27291 2.54762 + vertex 1.56231 1.27282 2.54791 + endloop + endfacet + facet normal 0.057727 -0.14297 0.988042 + outer loop + vertex 1.56794 1.26817 2.54691 + vertex 1.56749 1.27291 2.54762 + vertex 1.56256 1.26803 2.54721 + endloop + endfacet + facet normal 0.0578848 -0.151806 0.986714 + outer loop + vertex 1.56307 1.26333 2.54645 + vertex 1.56794 1.26817 2.54691 + vertex 1.56256 1.26803 2.54721 + endloop + endfacet + facet normal 0.0578509 -0.151773 0.986721 + outer loop + vertex 1.56849 1.26426 2.54628 + vertex 1.56794 1.26817 2.54691 + vertex 1.56307 1.26333 2.54645 + endloop + endfacet + facet normal 0.0610074 -0.17093 0.983393 + outer loop + vertex 1.56849 1.26426 2.54628 + vertex 1.56307 1.26333 2.54645 + vertex 1.56545 1.26079 2.54586 + endloop + endfacet + facet normal 0.0764783 -0.156752 0.984672 + outer loop + vertex 1.56545 1.26079 2.54586 + vertex 1.56307 1.26333 2.54645 + vertex 1.56171 1.25955 2.54596 + endloop + endfacet + facet normal 0.0690965 -0.134283 0.988531 + outer loop + vertex 1.56171 1.25955 2.54596 + vertex 1.56256 1.25706 2.54556 + vertex 1.56545 1.26079 2.54586 + endloop + endfacet + facet normal 0.0519756 -0.121233 0.991262 + outer loop + vertex 1.56256 1.25706 2.54556 + vertex 1.56739 1.25772 2.54539 + vertex 1.56545 1.26079 2.54586 + endloop + endfacet + facet normal 0.0334389 -0.132866 0.99057 + outer loop + vertex 1.56917 1.26155 2.54584 + vertex 1.56545 1.26079 2.54586 + vertex 1.56739 1.25772 2.54539 + endloop + endfacet + facet normal 0.0107647 -0.122603 0.992397 + outer loop + vertex 1.56917 1.26155 2.54584 + vertex 1.56739 1.25772 2.54539 + vertex 1.57256 1.26066 2.54569 + endloop + endfacet + facet normal 0.00508326 -0.143599 0.989623 + outer loop + vertex 1.57256 1.26066 2.54569 + vertex 1.57169 1.26361 2.54613 + vertex 1.56917 1.26155 2.54584 + endloop + endfacet + facet normal 0.0152792 -0.155857 0.987662 + outer loop + vertex 1.57169 1.26361 2.54613 + vertex 1.56849 1.26426 2.54628 + vertex 1.56917 1.26155 2.54584 + endloop + endfacet + facet normal 0.0182084 -0.14189 0.989715 + outer loop + vertex 1.57169 1.26361 2.54613 + vertex 1.57365 1.26752 2.54665 + vertex 1.56849 1.26426 2.54628 + endloop + endfacet + facet normal 0.0274071 -0.156145 0.987354 + outer loop + vertex 1.57365 1.26752 2.54665 + vertex 1.56794 1.26817 2.54691 + vertex 1.56849 1.26426 2.54628 + endloop + endfacet + facet normal 0.0304711 -0.13061 0.990965 + outer loop + vertex 1.57365 1.26752 2.54665 + vertex 1.57275 1.2729 2.54739 + vertex 1.56794 1.26817 2.54691 + endloop + endfacet + facet normal 0.0247413 -0.146814 0.988855 + outer loop + vertex 1.57256 1.26066 2.54569 + vertex 1.56739 1.25772 2.54539 + vertex 1.5714 1.25668 2.54513 + endloop + endfacet + facet normal 0.0290648 -0.130703 0.990995 + outer loop + vertex 1.56733 1.25288 2.54475 + vertex 1.5714 1.25668 2.54513 + vertex 1.56739 1.25772 2.54539 + endloop + endfacet + facet normal 0.060669 -0.130931 0.989533 + outer loop + vertex 1.56733 1.25288 2.54475 + vertex 1.56739 1.25772 2.54539 + vertex 1.5627 1.25302 2.54505 + endloop + endfacet + facet normal 0.0605673 -0.133488 0.989198 + outer loop + vertex 1.56252 1.24811 2.5444 + vertex 1.56733 1.25288 2.54475 + vertex 1.5627 1.25302 2.54505 + endloop + endfacet + facet normal 0.104433 -0.13463 0.985377 + outer loop + vertex 1.56252 1.24811 2.5444 + vertex 1.5627 1.25302 2.54505 + vertex 1.55793 1.24821 2.5449 + endloop + endfacet + facet normal 0.10416 -0.141907 0.984385 + outer loop + vertex 1.55757 1.24312 2.5442 + vertex 1.56252 1.24811 2.5444 + vertex 1.55793 1.24821 2.5449 + endloop + endfacet + facet normal 0.107963 -0.145634 0.98343 + outer loop + vertex 1.56235 1.24296 2.54366 + vertex 1.56252 1.24811 2.5444 + vertex 1.55757 1.24312 2.5442 + endloop + endfacet + facet normal 0.107783 -0.149313 0.982898 + outer loop + vertex 1.55737 1.23794 2.54344 + vertex 1.56235 1.24296 2.54366 + vertex 1.55757 1.24312 2.5442 + endloop + endfacet + facet normal 0.112844 -0.154269 0.981564 + outer loop + vertex 1.56236 1.2379 2.54286 + vertex 1.56235 1.24296 2.54366 + vertex 1.55737 1.23794 2.54344 + endloop + endfacet + facet normal 0.112856 -0.153767 0.981641 + outer loop + vertex 1.55739 1.23297 2.54266 + vertex 1.56236 1.2379 2.54286 + vertex 1.55737 1.23794 2.54344 + endloop + endfacet + facet normal 0.148685 -0.152856 0.976999 + outer loop + vertex 1.55739 1.23297 2.54266 + vertex 1.55737 1.23794 2.54344 + vertex 1.55242 1.23297 2.54341 + endloop + endfacet + facet normal 0.148803 -0.147727 0.97777 + outer loop + vertex 1.55241 1.22802 2.54267 + vertex 1.55739 1.23297 2.54266 + vertex 1.55242 1.23297 2.54341 + endloop + endfacet + facet normal 0.174223 -0.147158 0.973648 + outer loop + vertex 1.55241 1.22802 2.54267 + vertex 1.55242 1.23297 2.54341 + vertex 1.54742 1.22797 2.54355 + endloop + endfacet + facet normal 0.174282 -0.143541 0.974178 + outer loop + vertex 1.54737 1.223 2.54283 + vertex 1.55241 1.22802 2.54267 + vertex 1.54742 1.22797 2.54355 + endloop + endfacet + facet normal 0.189683 -0.14328 0.971335 + outer loop + vertex 1.54737 1.223 2.54283 + vertex 1.54742 1.22797 2.54355 + vertex 1.54235 1.2229 2.5438 + endloop + endfacet + facet normal 0.189628 -0.149513 0.970406 + outer loop + vertex 1.54233 1.21798 2.54304 + vertex 1.54737 1.223 2.54283 + vertex 1.54235 1.2229 2.5438 + endloop + endfacet + facet normal 0.174294 -0.149876 0.973221 + outer loop + vertex 1.54233 1.21798 2.54304 + vertex 1.54235 1.2229 2.5438 + vertex 1.53758 1.21798 2.54389 + endloop + endfacet + facet normal 0.191139 -0.151054 0.96987 + outer loop + vertex 1.54741 1.21836 2.5421 + vertex 1.54737 1.223 2.54283 + vertex 1.54233 1.21798 2.54304 + endloop + endfacet + facet normal 0.191635 -0.162603 0.967903 + outer loop + vertex 1.54241 1.21335 2.54225 + vertex 1.54741 1.21836 2.5421 + vertex 1.54233 1.21798 2.54304 + endloop + endfacet + facet normal 0.16071 -0.164049 0.973273 + outer loop + vertex 1.54241 1.21335 2.54225 + vertex 1.54233 1.21798 2.54304 + vertex 1.53757 1.21322 2.54303 + endloop + endfacet + facet normal 0.191033 -0.161996 0.968124 + outer loop + vertex 1.54743 1.21391 2.54135 + vertex 1.54741 1.21836 2.5421 + vertex 1.54241 1.21335 2.54225 + endloop + endfacet + facet normal 0.191072 -0.16249 0.968033 + outer loop + vertex 1.54743 1.21391 2.54135 + vertex 1.54241 1.21335 2.54225 + vertex 1.54243 1.20884 2.54149 + endloop + endfacet + facet normal 0.144463 -0.164031 0.97582 + outer loop + vertex 1.54243 1.20884 2.54149 + vertex 1.54241 1.21335 2.54225 + vertex 1.53761 1.20845 2.54214 + endloop + endfacet + facet normal 0.185893 -0.162182 0.969093 + outer loop + vertex 1.55241 1.219 2.54125 + vertex 1.54741 1.21836 2.5421 + vertex 1.54743 1.21391 2.54135 + endloop + endfacet + facet normal 0.185354 -0.15663 0.970109 + outer loop + vertex 1.55241 1.219 2.54125 + vertex 1.55245 1.22341 2.54195 + vertex 1.54741 1.21836 2.5421 + endloop + endfacet + facet normal 0.180238 -0.151472 0.97189 + outer loop + vertex 1.54741 1.21836 2.5421 + vertex 1.55245 1.22341 2.54195 + vertex 1.54737 1.223 2.54283 + endloop + endfacet + facet normal 0.165185 -0.157011 0.973684 + outer loop + vertex 1.55744 1.22403 2.54121 + vertex 1.55245 1.22341 2.54195 + vertex 1.55241 1.219 2.54125 + endloop + endfacet + facet normal 0.165484 -0.160096 0.973131 + outer loop + vertex 1.55744 1.22403 2.54121 + vertex 1.55749 1.22836 2.54191 + vertex 1.55245 1.22341 2.54195 + endloop + endfacet + facet normal 0.155911 -0.150305 0.976268 + outer loop + vertex 1.55245 1.22341 2.54195 + vertex 1.55749 1.22836 2.54191 + vertex 1.55241 1.22802 2.54267 + endloop + endfacet + facet normal 0.132212 -0.160523 0.978137 + outer loop + vertex 1.56264 1.22872 2.54127 + vertex 1.55749 1.22836 2.54191 + vertex 1.55744 1.22403 2.54121 + endloop + endfacet + facet normal 0.13274 -0.171653 0.976174 + outer loop + vertex 1.56264 1.22872 2.54127 + vertex 1.56259 1.23315 2.54206 + vertex 1.55749 1.22836 2.54191 + endloop + endfacet + facet normal 0.118577 -0.156729 0.980498 + outer loop + vertex 1.55749 1.22836 2.54191 + vertex 1.56259 1.23315 2.54206 + vertex 1.55739 1.23297 2.54266 + endloop + endfacet + facet normal 0.187654 -0.14122 0.97203 + outer loop + vertex 1.54235 1.2229 2.5438 + vertex 1.54742 1.22797 2.54355 + vertex 1.54256 1.2281 2.54451 + endloop + endfacet + facet normal 0.180133 -0.149485 0.972217 + outer loop + vertex 1.55245 1.22341 2.54195 + vertex 1.55241 1.22802 2.54267 + vertex 1.54737 1.223 2.54283 + endloop + endfacet + facet normal 0.167351 -0.140215 0.975876 + outer loop + vertex 1.54742 1.22797 2.54355 + vertex 1.55242 1.23297 2.54341 + vertex 1.54762 1.23322 2.54427 + endloop + endfacet + facet normal 0.156116 -0.155092 0.975487 + outer loop + vertex 1.55749 1.22836 2.54191 + vertex 1.55739 1.23297 2.54266 + vertex 1.55241 1.22802 2.54267 + endloop + endfacet + facet normal 0.143335 -0.147544 0.978614 + outer loop + vertex 1.55242 1.23297 2.54341 + vertex 1.55737 1.23794 2.54344 + vertex 1.55261 1.23818 2.54417 + endloop + endfacet + facet normal 0.143155 -0.150033 0.978262 + outer loop + vertex 1.55737 1.23794 2.54344 + vertex 1.55757 1.24312 2.5442 + vertex 1.55261 1.23818 2.54417 + endloop + endfacet + facet normal 0.118623 -0.159503 0.980045 + outer loop + vertex 1.56259 1.23315 2.54206 + vertex 1.56236 1.2379 2.54286 + vertex 1.55739 1.23297 2.54266 + endloop + endfacet + facet normal 0.0713174 -0.154972 0.985341 + outer loop + vertex 1.56236 1.2379 2.54286 + vertex 1.56736 1.2429 2.54328 + vertex 1.56235 1.24296 2.54366 + endloop + endfacet + facet normal 0.0714252 -0.15047 0.986031 + outer loop + vertex 1.56736 1.2429 2.54328 + vertex 1.56736 1.24799 2.54406 + vertex 1.56235 1.24296 2.54366 + endloop + endfacet + facet normal 0.0461397 -0.150721 0.987499 + outer loop + vertex 1.56736 1.2429 2.54328 + vertex 1.57241 1.24795 2.54382 + vertex 1.56736 1.24799 2.54406 + endloop + endfacet + facet normal 0.0461902 -0.14703 0.988053 + outer loop + vertex 1.57241 1.24795 2.54382 + vertex 1.57222 1.25293 2.54457 + vertex 1.56736 1.24799 2.54406 + endloop + endfacet + facet normal 0.0379855 -0.139098 0.98955 + outer loop + vertex 1.56736 1.24799 2.54406 + vertex 1.57222 1.25293 2.54457 + vertex 1.56733 1.25288 2.54475 + endloop + endfacet + facet normal 0.0495956 -0.154099 0.98681 + outer loop + vertex 1.57254 1.24294 2.54303 + vertex 1.57241 1.24795 2.54382 + vertex 1.56736 1.2429 2.54328 + endloop + endfacet + facet normal 0.0496004 -0.161095 0.985692 + outer loop + vertex 1.56761 1.23798 2.54247 + vertex 1.57254 1.24294 2.54303 + vertex 1.56736 1.2429 2.54328 + endloop + endfacet + facet normal 0.0471298 -0.1587 0.986201 + outer loop + vertex 1.57304 1.23823 2.54225 + vertex 1.57254 1.24294 2.54303 + vertex 1.56761 1.23798 2.54247 + endloop + endfacet + facet normal 0.0476025 -0.170863 0.984144 + outer loop + vertex 1.56825 1.23316 2.5416 + vertex 1.57304 1.23823 2.54225 + vertex 1.56761 1.23798 2.54247 + endloop + endfacet + facet normal 0.0800354 -0.16631 0.98282 + outer loop + vertex 1.56825 1.23316 2.5416 + vertex 1.56761 1.23798 2.54247 + vertex 1.56259 1.23315 2.54206 + endloop + endfacet + facet normal 0.0759779 -0.162179 0.983832 + outer loop + vertex 1.56259 1.23315 2.54206 + vertex 1.56761 1.23798 2.54247 + vertex 1.56236 1.2379 2.54286 + endloop + endfacet + facet normal 0.0368709 -0.160984 0.986268 + outer loop + vertex 1.57422 1.2342 2.54155 + vertex 1.57304 1.23823 2.54225 + vertex 1.56825 1.23316 2.5416 + endloop + endfacet + facet normal 0.0759718 -0.15954 0.984264 + outer loop + vertex 1.56761 1.23798 2.54247 + vertex 1.56736 1.2429 2.54328 + vertex 1.56236 1.2379 2.54286 + endloop + endfacet + facet normal 0.0656333 -0.144794 0.987283 + outer loop + vertex 1.56235 1.24296 2.54366 + vertex 1.56736 1.24799 2.54406 + vertex 1.56252 1.24811 2.5444 + endloop + endfacet + facet normal 0.0996934 -0.129961 0.986494 + outer loop + vertex 1.55793 1.24821 2.5449 + vertex 1.5627 1.25302 2.54505 + vertex 1.55823 1.25303 2.5455 + endloop + endfacet + facet normal 0.0998285 -0.120424 0.98769 + outer loop + vertex 1.56256 1.25706 2.54556 + vertex 1.55823 1.25303 2.5455 + vertex 1.5627 1.25302 2.54505 + endloop + endfacet + facet normal 0.0933427 -0.113489 0.989145 + outer loop + vertex 1.55944 1.25683 2.54583 + vertex 1.55823 1.25303 2.5455 + vertex 1.56256 1.25706 2.54556 + endloop + endfacet + facet normal 0.133039 -0.125525 0.98313 + outer loop + vertex 1.55944 1.25683 2.54583 + vertex 1.5566 1.25492 2.54597 + vertex 1.55823 1.25303 2.5455 + endloop + endfacet + facet normal 0.145477 -0.144309 0.97878 + outer loop + vertex 1.55944 1.25683 2.54583 + vertex 1.55773 1.25862 2.54634 + vertex 1.5566 1.25492 2.54597 + endloop + endfacet + facet normal 0.132128 -0.157085 0.978707 + outer loop + vertex 1.56171 1.25955 2.54596 + vertex 1.55773 1.25862 2.54634 + vertex 1.55944 1.25683 2.54583 + endloop + endfacet + facet normal 0.0658488 -0.13874 0.988137 + outer loop + vertex 1.56736 1.24799 2.54406 + vertex 1.56733 1.25288 2.54475 + vertex 1.56252 1.24811 2.5444 + endloop + endfacet + facet normal 0.0379897 -0.140111 0.989407 + outer loop + vertex 1.57222 1.25293 2.54457 + vertex 1.5714 1.25668 2.54513 + vertex 1.56733 1.25288 2.54475 + endloop + endfacet + facet normal 0.0370401 -0.150446 0.987924 + outer loop + vertex 1.56917 1.26155 2.54584 + vertex 1.56849 1.26426 2.54628 + vertex 1.56545 1.26079 2.54586 + endloop + endfacet + facet normal 0.0521444 -0.122523 0.991095 + outer loop + vertex 1.5627 1.25302 2.54505 + vertex 1.56739 1.25772 2.54539 + vertex 1.56256 1.25706 2.54556 + endloop + endfacet + facet normal 0.0940966 -0.125595 0.987609 + outer loop + vertex 1.56256 1.25706 2.54556 + vertex 1.56171 1.25955 2.54596 + vertex 1.55944 1.25683 2.54583 + endloop + endfacet + facet normal 0.136348 -0.176907 0.974738 + outer loop + vertex 1.56171 1.25955 2.54596 + vertex 1.56307 1.26333 2.54645 + vertex 1.55773 1.25862 2.54634 + endloop + endfacet + facet normal 0.107082 -0.145974 0.983476 + outer loop + vertex 1.56307 1.26333 2.54645 + vertex 1.56256 1.26803 2.54721 + vertex 1.55761 1.26317 2.54702 + endloop + endfacet + facet normal 0.107054 -0.143907 0.983784 + outer loop + vertex 1.56307 1.26333 2.54645 + vertex 1.55761 1.26317 2.54702 + vertex 1.55773 1.25862 2.54634 + endloop + endfacet + facet normal 0.177494 -0.114905 0.977391 + outer loop + vertex 1.54247 1.25795 2.54894 + vertex 1.54747 1.26294 2.54862 + vertex 1.54267 1.26313 2.54952 + endloop + endfacet + facet normal 0.177803 -0.128466 0.975645 + outer loop + vertex 1.55263 1.25823 2.5471 + vertex 1.55245 1.26295 2.54775 + vertex 1.5475 1.25797 2.548 + endloop + endfacet + facet normal 0.138661 -0.127832 0.982055 + outer loop + vertex 1.55245 1.26295 2.54775 + vertex 1.55735 1.26787 2.5477 + vertex 1.55236 1.26786 2.54841 + endloop + endfacet + facet normal 0.138577 -0.133132 0.981363 + outer loop + vertex 1.55735 1.26787 2.5477 + vertex 1.55728 1.27282 2.54838 + vertex 1.55236 1.26786 2.54841 + endloop + endfacet + facet normal 0.0885561 -0.130778 0.987449 + outer loop + vertex 1.55728 1.27282 2.54838 + vertex 1.56231 1.27785 2.5486 + vertex 1.55742 1.27797 2.54905 + endloop + endfacet + facet normal 0.127626 -0.122867 0.984182 + outer loop + vertex 1.5528 1.27819 2.5497 + vertex 1.55766 1.28317 2.54969 + vertex 1.55302 1.28353 2.55033 + endloop + endfacet + facet normal 0.128204 -0.116582 0.984872 + outer loop + vertex 1.55766 1.28317 2.54969 + vertex 1.55802 1.28814 2.55023 + vertex 1.55302 1.28353 2.55033 + endloop + endfacet + facet normal 0.0886509 -0.128155 0.987784 + outer loop + vertex 1.56231 1.27785 2.5486 + vertex 1.56241 1.28297 2.54926 + vertex 1.55742 1.27797 2.54905 + endloop + endfacet + facet normal 0.0793838 -0.113569 0.990354 + outer loop + vertex 1.55766 1.28317 2.54969 + vertex 1.56243 1.28788 2.54984 + vertex 1.55802 1.28814 2.55023 + endloop + endfacet + facet normal 0.0490106 -0.125862 0.990836 + outer loop + vertex 1.56742 1.28292 2.549 + vertex 1.5673 1.2879 2.54964 + vertex 1.56241 1.28297 2.54926 + endloop + endfacet + facet normal 0.0311839 -0.149289 0.988302 + outer loop + vertex 1.56679 1.29868 2.55098 + vertex 1.5688 1.30255 2.5515 + vertex 1.56352 1.29926 2.55117 + endloop + endfacet + facet normal 0.0308388 -0.148745 0.988395 + outer loop + vertex 1.5688 1.30255 2.5515 + vertex 1.56294 1.30313 2.55177 + vertex 1.56352 1.29926 2.55117 + endloop + endfacet + facet normal 0.0336376 -0.122034 0.991956 + outer loop + vertex 1.5688 1.30255 2.5515 + vertex 1.56778 1.30788 2.55219 + vertex 1.56294 1.30313 2.55177 + endloop + endfacet + facet normal 0.0399879 -0.128417 0.990914 + outer loop + vertex 1.56294 1.30313 2.55177 + vertex 1.56778 1.30788 2.55219 + vertex 1.56246 1.30784 2.5524 + endloop + endfacet + facet normal 0.0737658 -0.124727 0.989445 + outer loop + vertex 1.56294 1.30313 2.55177 + vertex 1.56246 1.30784 2.5524 + vertex 1.55753 1.30294 2.55215 + endloop + endfacet + facet normal 0.0740451 -0.135248 0.988041 + outer loop + vertex 1.55809 1.2982 2.55146 + vertex 1.56294 1.30313 2.55177 + vertex 1.55753 1.30294 2.55215 + endloop + endfacet + facet normal 0.07182 -0.122796 0.98983 + outer loop + vertex 1.55753 1.30294 2.55215 + vertex 1.56246 1.30784 2.5524 + vertex 1.55727 1.30774 2.55276 + endloop + endfacet + facet normal 0.071727 -0.115418 0.990724 + outer loop + vertex 1.56246 1.30784 2.5524 + vertex 1.56232 1.31274 2.55298 + vertex 1.55727 1.30774 2.55276 + endloop + endfacet + facet normal 0.0396738 -0.116487 0.9924 + outer loop + vertex 1.56246 1.30784 2.5524 + vertex 1.56748 1.31284 2.55278 + vertex 1.56232 1.31274 2.55298 + endloop + endfacet + facet normal 0.0395022 -0.106398 0.993539 + outer loop + vertex 1.56748 1.31284 2.55278 + vertex 1.56751 1.31782 2.55332 + vertex 1.56232 1.31274 2.55298 + endloop + endfacet + facet normal 0.038162 -0.105045 0.993735 + outer loop + vertex 1.56232 1.31274 2.55298 + vertex 1.56751 1.31782 2.55332 + vertex 1.56237 1.31773 2.5535 + endloop + endfacet + facet normal 0.0380633 -0.098566 0.994402 + outer loop + vertex 1.56751 1.31782 2.55332 + vertex 1.56754 1.32282 2.55381 + vertex 1.56237 1.31773 2.5535 + endloop + endfacet + facet normal 0.0375569 -0.0980559 0.994472 + outer loop + vertex 1.56237 1.31773 2.5535 + vertex 1.56754 1.32282 2.55381 + vertex 1.5624 1.32275 2.554 + endloop + endfacet + facet normal 0.0375826 -0.100625 0.994214 + outer loop + vertex 1.56754 1.32282 2.55381 + vertex 1.5673 1.32775 2.55432 + vertex 1.5624 1.32275 2.554 + endloop + endfacet + facet normal 0.03242 -0.0956022 0.994892 + outer loop + vertex 1.5624 1.32275 2.554 + vertex 1.5673 1.32775 2.55432 + vertex 1.56235 1.32765 2.55447 + endloop + endfacet + facet normal 0.0325573 -0.103611 0.994085 + outer loop + vertex 1.5673 1.32775 2.55432 + vertex 1.56645 1.33161 2.55475 + vertex 1.56235 1.32765 2.55447 + endloop + endfacet + facet normal 0.026516 -0.0974195 0.99489 + outer loop + vertex 1.56235 1.32765 2.55447 + vertex 1.56645 1.33161 2.55475 + vertex 1.56253 1.33256 2.55495 + endloop + endfacet + facet normal 0.0215244 -0.117581 0.99283 + outer loop + vertex 1.56645 1.33161 2.55475 + vertex 1.56753 1.3363 2.55528 + vertex 1.56253 1.33256 2.55495 + endloop + endfacet + facet normal -0.00406633 -0.0837114 0.996482 + outer loop + vertex 1.56253 1.33256 2.55495 + vertex 1.56753 1.3363 2.55528 + vertex 1.56284 1.33746 2.55536 + endloop + endfacet + facet normal -0.00585104 -0.0909295 0.99584 + outer loop + vertex 1.56753 1.3363 2.55528 + vertex 1.56638 1.34073 2.55568 + vertex 1.56284 1.33746 2.55536 + endloop + endfacet + facet normal -0.0210267 -0.0745827 0.996993 + outer loop + vertex 1.56284 1.33746 2.55536 + vertex 1.56638 1.34073 2.55568 + vertex 1.56272 1.34154 2.55566 + endloop + endfacet + facet normal -0.0241192 -0.0885452 0.99578 + outer loop + vertex 1.56272 1.34154 2.55566 + vertex 1.56638 1.34073 2.55568 + vertex 1.56547 1.34444 2.55599 + endloop + endfacet + facet normal -0.000199541 -0.110948 0.993826 + outer loop + vertex 1.56188 1.34413 2.55595 + vertex 1.56272 1.34154 2.55566 + vertex 1.56547 1.34444 2.55599 + endloop + endfacet + facet normal 0.000194135 -0.115328 0.993327 + outer loop + vertex 1.56547 1.34444 2.55599 + vertex 1.56329 1.34787 2.55639 + vertex 1.56188 1.34413 2.55595 + endloop + endfacet + facet normal 0.00345165 -0.113285 0.993557 + outer loop + vertex 1.56915 1.3477 2.55635 + vertex 1.56329 1.34787 2.55639 + vertex 1.56547 1.34444 2.55599 + endloop + endfacet + facet normal 0.00459532 -0.0744384 0.997215 + outer loop + vertex 1.56915 1.3477 2.55635 + vertex 1.56803 1.35299 2.55675 + vertex 1.56329 1.34787 2.55639 + endloop + endfacet + facet normal 0.0305826 -0.0982947 0.994687 + outer loop + vertex 1.56329 1.34787 2.55639 + vertex 1.56803 1.35299 2.55675 + vertex 1.56277 1.35304 2.55691 + endloop + endfacet + facet normal 0.0307916 -0.0811811 0.996224 + outer loop + vertex 1.56803 1.35299 2.55675 + vertex 1.56761 1.35803 2.55717 + vertex 1.56277 1.35304 2.55691 + endloop + endfacet + facet normal 0.041528 -0.0915301 0.994936 + outer loop + vertex 1.56277 1.35304 2.55691 + vertex 1.56761 1.35803 2.55717 + vertex 1.56256 1.35794 2.55737 + endloop + endfacet + facet normal 0.0414266 -0.084734 0.995542 + outer loop + vertex 1.56761 1.35803 2.55717 + vertex 1.56759 1.36298 2.55759 + vertex 1.56256 1.35794 2.55737 + endloop + endfacet + facet normal 0.0483185 -0.0915654 0.994626 + outer loop + vertex 1.56256 1.35794 2.55737 + vertex 1.56759 1.36298 2.55759 + vertex 1.56251 1.36283 2.55782 + endloop + endfacet + facet normal 0.0481574 -0.0854479 0.995178 + outer loop + vertex 1.56759 1.36298 2.55759 + vertex 1.56766 1.36795 2.55801 + vertex 1.56251 1.36283 2.55782 + endloop + endfacet + facet normal 0.052422 -0.0897098 0.994587 + outer loop + vertex 1.56251 1.36283 2.55782 + vertex 1.56766 1.36795 2.55801 + vertex 1.5625 1.36774 2.55827 + endloop + endfacet + facet normal 0.0522452 -0.0847494 0.995032 + outer loop + vertex 1.56766 1.36795 2.55801 + vertex 1.56767 1.3729 2.55844 + vertex 1.5625 1.36774 2.55827 + endloop + endfacet + facet normal 0.054068 -0.0865673 0.994778 + outer loop + vertex 1.5625 1.36774 2.55827 + vertex 1.56767 1.3729 2.55844 + vertex 1.56247 1.37267 2.5587 + endloop + endfacet + facet normal 0.0538312 -0.0808325 0.995273 + outer loop + vertex 1.56767 1.3729 2.55844 + vertex 1.56764 1.37782 2.55884 + vertex 1.56247 1.37267 2.5587 + endloop + endfacet + facet normal 0.0540062 -0.0810073 0.995249 + outer loop + vertex 1.56247 1.37267 2.5587 + vertex 1.56764 1.37782 2.55884 + vertex 1.56243 1.37762 2.5591 + endloop + endfacet + facet normal 0.053769 -0.074395 0.995778 + outer loop + vertex 1.56764 1.37782 2.55884 + vertex 1.56758 1.38275 2.55921 + vertex 1.56243 1.37762 2.5591 + endloop + endfacet + facet normal 0.0892238 -0.0846314 0.99241 + outer loop + vertex 1.56766 1.36795 2.55801 + vertex 1.57269 1.373 2.55799 + vertex 1.56767 1.3729 2.55844 + endloop + endfacet + facet normal 0.0891318 -0.0774111 0.993007 + outer loop + vertex 1.57269 1.373 2.55799 + vertex 1.57265 1.37799 2.55839 + vertex 1.56767 1.3729 2.55844 + endloop + endfacet + facet normal 0.0805535 -0.0759965 0.993849 + outer loop + vertex 1.57254 1.36788 2.55761 + vertex 1.57269 1.373 2.55799 + vertex 1.56766 1.36795 2.55801 + endloop + endfacet + facet normal 0.0803521 -0.0857223 0.993074 + outer loop + vertex 1.56759 1.36298 2.55759 + vertex 1.57254 1.36788 2.55761 + vertex 1.56766 1.36795 2.55801 + endloop + endfacet + facet normal 0.0662394 -0.0714576 0.995242 + outer loop + vertex 1.57226 1.36279 2.55727 + vertex 1.57254 1.36788 2.55761 + vertex 1.56759 1.36298 2.55759 + endloop + endfacet + facet normal 0.0656397 -0.0844963 0.994259 + outer loop + vertex 1.56761 1.35803 2.55717 + vertex 1.57226 1.36279 2.55727 + vertex 1.56759 1.36298 2.55759 + endloop + endfacet + facet normal 0.039973 -0.116784 0.992353 + outer loop + vertex 1.56778 1.30788 2.55219 + vertex 1.56748 1.31284 2.55278 + vertex 1.56246 1.30784 2.5524 + endloop + endfacet + facet normal 0.0800792 -0.141099 0.986751 + outer loop + vertex 1.56352 1.29926 2.55117 + vertex 1.56294 1.30313 2.55177 + vertex 1.55809 1.2982 2.55146 + endloop + endfacet + facet normal 0.056999 -0.116781 0.991521 + outer loop + vertex 1.56422 1.2966 2.55074 + vertex 1.56052 1.29572 2.55085 + vertex 1.56251 1.29273 2.55039 + endloop + endfacet + facet normal 0.0794711 -0.112297 0.990492 + outer loop + vertex 1.56243 1.28788 2.54984 + vertex 1.56251 1.29273 2.55039 + vertex 1.55802 1.28814 2.55023 + endloop + endfacet + facet normal 0.117477 -0.104902 0.987519 + outer loop + vertex 1.55302 1.28353 2.55033 + vertex 1.55802 1.28814 2.55023 + vertex 1.5545 1.2886 2.55069 + endloop + endfacet + facet normal 0.152917 -0.114801 0.981548 + outer loop + vertex 1.55302 1.28353 2.55033 + vertex 1.5545 1.2886 2.55069 + vertex 1.55064 1.28583 2.55097 + endloop + endfacet + facet normal 0.148022 -0.107807 0.983091 + outer loop + vertex 1.5545 1.2886 2.55069 + vertex 1.55226 1.28957 2.55114 + vertex 1.55064 1.28583 2.55097 + endloop + endfacet + facet normal 0.147312 -0.109404 0.983021 + outer loop + vertex 1.55493 1.29171 2.55098 + vertex 1.55226 1.28957 2.55114 + vertex 1.5545 1.2886 2.55069 + endloop + endfacet + facet normal 0.125123 -0.128615 0.98377 + outer loop + vertex 1.55809 1.2982 2.55146 + vertex 1.55753 1.30294 2.55215 + vertex 1.55264 1.29801 2.55213 + endloop + endfacet + facet normal 0.117399 -0.120946 0.985692 + outer loop + vertex 1.55264 1.29801 2.55213 + vertex 1.55753 1.30294 2.55215 + vertex 1.55235 1.30279 2.55275 + endloop + endfacet + facet normal 0.156074 -0.120562 0.98036 + outer loop + vertex 1.55493 1.29171 2.55098 + vertex 1.55294 1.29333 2.55149 + vertex 1.55226 1.28957 2.55114 + endloop + endfacet + facet normal 0.188475 -0.120032 0.974715 + outer loop + vertex 1.54665 1.28289 2.55131 + vertex 1.54798 1.28799 2.55168 + vertex 1.54254 1.28305 2.55212 + endloop + endfacet + facet normal 0.188234 -0.124104 0.974252 + outer loop + vertex 1.54665 1.28289 2.55131 + vertex 1.54254 1.28305 2.55212 + vertex 1.54266 1.27839 2.5515 + endloop + endfacet + facet normal 0.187683 -0.123609 0.974421 + outer loop + vertex 1.54643 1.27977 2.55095 + vertex 1.54665 1.28289 2.55131 + vertex 1.54266 1.27839 2.5515 + endloop + endfacet + facet normal 0.157887 -0.12362 0.979689 + outer loop + vertex 1.55302 1.28353 2.55033 + vertex 1.54843 1.27827 2.55041 + vertex 1.5528 1.27819 2.5497 + endloop + endfacet + facet normal 0.157739 -0.127629 0.979198 + outer loop + vertex 1.54811 1.27331 2.54981 + vertex 1.5528 1.27819 2.5497 + vertex 1.54843 1.27827 2.55041 + endloop + endfacet + facet normal 0.159296 -0.129134 0.978749 + outer loop + vertex 1.5525 1.27298 2.54905 + vertex 1.5528 1.27819 2.5497 + vertex 1.54811 1.27331 2.54981 + endloop + endfacet + facet normal 0.169577 -0.122729 0.977845 + outer loop + vertex 1.54909 1.28209 2.55078 + vertex 1.54665 1.28289 2.55131 + vertex 1.54643 1.27977 2.55095 + endloop + endfacet + facet normal 0.192599 -0.1382 0.971497 + outer loop + vertex 1.54643 1.27977 2.55095 + vertex 1.54266 1.27839 2.5515 + vertex 1.54493 1.27704 2.55086 + endloop + endfacet + facet normal 0.213515 -0.122769 0.969195 + outer loop + vertex 1.54266 1.27839 2.5515 + vertex 1.54254 1.28305 2.55212 + vertex 1.53752 1.27792 2.55258 + endloop + endfacet + facet normal 0.204541 -0.113713 0.972231 + outer loop + vertex 1.53752 1.27792 2.55258 + vertex 1.54254 1.28305 2.55212 + vertex 1.53741 1.28284 2.55318 + endloop + endfacet + facet normal 0.1966 -0.110443 0.974244 + outer loop + vertex 1.53232 1.28264 2.55414 + vertex 1.53738 1.2879 2.55372 + vertex 1.53238 1.28789 2.55473 + endloop + endfacet + facet normal 0.2045 -0.111035 0.972549 + outer loop + vertex 1.54254 1.28305 2.55212 + vertex 1.54261 1.28797 2.55267 + vertex 1.53741 1.28284 2.55318 + endloop + endfacet + facet normal 0.175778 -0.107053 0.978592 + outer loop + vertex 1.54261 1.28797 2.55267 + vertex 1.5477 1.29302 2.55231 + vertex 1.54249 1.29297 2.55324 + endloop + endfacet + facet normal 0.175718 -0.113036 0.97793 + outer loop + vertex 1.5477 1.29302 2.55231 + vertex 1.54747 1.29789 2.55291 + vertex 1.54249 1.29297 2.55324 + endloop + endfacet + facet normal 0.171058 -0.116354 0.978366 + outer loop + vertex 1.54251 1.29804 2.5538 + vertex 1.54739 1.30287 2.55352 + vertex 1.54268 1.30321 2.55438 + endloop + endfacet + facet normal 0.188227 -0.116586 0.975181 + outer loop + vertex 1.54251 1.29804 2.5538 + vertex 1.54268 1.30321 2.55438 + vertex 1.53788 1.2984 2.55474 + endloop + endfacet + facet normal 0.151985 -0.118259 0.981283 + outer loop + vertex 1.55264 1.29801 2.55213 + vertex 1.55235 1.30279 2.55275 + vertex 1.54747 1.29789 2.55291 + endloop + endfacet + facet normal 0.153776 -0.119771 0.98082 + outer loop + vertex 1.54739 1.30287 2.55352 + vertex 1.55227 1.30774 2.55335 + vertex 1.54751 1.30801 2.55413 + endloop + endfacet + facet normal 0.117384 -0.119793 0.985835 + outer loop + vertex 1.55753 1.30294 2.55215 + vertex 1.55727 1.30774 2.55276 + vertex 1.55235 1.30279 2.55275 + endloop + endfacet + facet normal 0.0692815 -0.112967 0.99118 + outer loop + vertex 1.55727 1.30774 2.55276 + vertex 1.56232 1.31274 2.55298 + vertex 1.55725 1.3127 2.55333 + endloop + endfacet + facet normal 0.0692815 -0.105135 0.992042 + outer loop + vertex 1.56232 1.31274 2.55298 + vertex 1.56237 1.31773 2.5535 + vertex 1.55725 1.3127 2.55333 + endloop + endfacet + facet normal 0.0693468 -0.0950305 0.993056 + outer loop + vertex 1.5624 1.32275 2.554 + vertex 1.56235 1.32765 2.55447 + vertex 1.55751 1.32293 2.55436 + endloop + endfacet + facet normal 0.118092 -0.0937467 0.988568 + outer loop + vertex 1.55301 1.32329 2.55494 + vertex 1.5577 1.32813 2.55484 + vertex 1.55316 1.32836 2.55541 + endloop + endfacet + facet normal 0.0372087 -0.060762 0.997459 + outer loop + vertex 1.55782 1.33359 2.55531 + vertex 1.56284 1.33746 2.55536 + vertex 1.55931 1.33873 2.55557 + endloop + endfacet + facet normal 0.0327215 -0.0730565 0.996791 + outer loop + vertex 1.56272 1.34154 2.55566 + vertex 1.55931 1.33873 2.55557 + vertex 1.56284 1.33746 2.55536 + endloop + endfacet + facet normal 0.0344169 -0.0751108 0.996581 + outer loop + vertex 1.5598 1.34189 2.55579 + vertex 1.55931 1.33873 2.55557 + vertex 1.56272 1.34154 2.55566 + endloop + endfacet + facet normal 0.0312407 -0.100802 0.994416 + outer loop + vertex 1.56272 1.34154 2.55566 + vertex 1.56188 1.34413 2.55595 + vertex 1.5598 1.34189 2.55579 + endloop + endfacet + facet normal 0.0914084 -0.156057 0.983509 + outer loop + vertex 1.56188 1.34413 2.55595 + vertex 1.55787 1.34352 2.55623 + vertex 1.5598 1.34189 2.55579 + endloop + endfacet + facet normal 0.119321 -0.123362 0.985162 + outer loop + vertex 1.5598 1.34189 2.55579 + vertex 1.55787 1.34352 2.55623 + vertex 1.55703 1.33998 2.55589 + endloop + endfacet + facet normal 0.0903171 -0.148213 0.984823 + outer loop + vertex 1.56188 1.34413 2.55595 + vertex 1.56329 1.34787 2.55639 + vertex 1.55787 1.34352 2.55623 + endloop + endfacet + facet normal 0.0629107 -0.114286 0.991454 + outer loop + vertex 1.56329 1.34787 2.55639 + vertex 1.55771 1.34809 2.55676 + vertex 1.55787 1.34352 2.55623 + endloop + endfacet + facet normal 0.0923596 -0.0838164 0.992192 + outer loop + vertex 1.5598 1.34189 2.55579 + vertex 1.55703 1.33998 2.55589 + vertex 1.55931 1.33873 2.55557 + endloop + endfacet + facet normal 0.166019 -0.133662 0.977022 + outer loop + vertex 1.55703 1.33998 2.55589 + vertex 1.55787 1.34352 2.55623 + vertex 1.55274 1.33825 2.55638 + endloop + endfacet + facet normal 0.13037 -0.0987439 0.986536 + outer loop + vertex 1.55787 1.34352 2.55623 + vertex 1.5526 1.34308 2.55688 + vertex 1.55274 1.33825 2.55638 + endloop + endfacet + facet normal 0.156338 -0.0937339 0.983246 + outer loop + vertex 1.55534 1.33621 2.55578 + vertex 1.55132 1.33313 2.55612 + vertex 1.55373 1.33237 2.55567 + endloop + endfacet + facet normal 0.157692 -0.0895429 0.98342 + outer loop + vertex 1.55373 1.33237 2.55567 + vertex 1.55132 1.33313 2.55612 + vertex 1.55106 1.32991 2.55587 + endloop + endfacet + facet normal 0.154545 -0.086061 0.98423 + outer loop + vertex 1.55373 1.33237 2.55567 + vertex 1.55106 1.32991 2.55587 + vertex 1.55316 1.32836 2.55541 + endloop + endfacet + facet normal 0.161328 -0.0944258 0.982373 + outer loop + vertex 1.55316 1.32836 2.55541 + vertex 1.54941 1.32375 2.55558 + vertex 1.55301 1.32329 2.55494 + endloop + endfacet + facet normal 0.160932 -0.0972545 0.982162 + outer loop + vertex 1.54814 1.31855 2.55527 + vertex 1.55301 1.32329 2.55494 + vertex 1.54941 1.32375 2.55558 + endloop + endfacet + facet normal 0.179655 -0.0919888 0.979419 + outer loop + vertex 1.54963 1.32701 2.55586 + vertex 1.54749 1.32839 2.55638 + vertex 1.54705 1.32456 2.5561 + endloop + endfacet + facet normal 0.187403 -0.0927611 0.977893 + outer loop + vertex 1.54705 1.32456 2.5561 + vertex 1.54749 1.32839 2.55638 + vertex 1.54291 1.32288 2.55673 + endloop + endfacet + facet normal 0.188653 -0.103647 0.976559 + outer loop + vertex 1.54814 1.31855 2.55527 + vertex 1.54941 1.32375 2.55558 + vertex 1.54565 1.32075 2.55599 + endloop + endfacet + facet normal 0.165743 -0.102278 0.980851 + outer loop + vertex 1.55262 1.31806 2.55446 + vertex 1.55301 1.32329 2.55494 + vertex 1.54814 1.31855 2.55527 + endloop + endfacet + facet normal 0.119941 -0.107385 0.986956 + outer loop + vertex 1.55239 1.31285 2.55392 + vertex 1.55735 1.31778 2.55386 + vertex 1.55262 1.31806 2.55446 + endloop + endfacet + facet normal 0.154208 -0.113991 0.981441 + outer loop + vertex 1.55227 1.30774 2.55335 + vertex 1.55239 1.31285 2.55392 + vertex 1.54751 1.30801 2.55413 + endloop + endfacet + facet normal 0.170744 -0.119821 0.978003 + outer loop + vertex 1.54739 1.30287 2.55352 + vertex 1.54751 1.30801 2.55413 + vertex 1.54268 1.30321 2.55438 + endloop + endfacet + facet normal 0.1852 -0.113489 0.976126 + outer loop + vertex 1.53788 1.2984 2.55474 + vertex 1.54268 1.30321 2.55438 + vertex 1.53821 1.30345 2.55526 + endloop + endfacet + facet normal 0.185105 -0.127561 0.974405 + outer loop + vertex 1.54286 1.30857 2.55505 + vertex 1.54791 1.31326 2.5547 + vertex 1.54429 1.31383 2.55546 + endloop + endfacet + facet normal 0.201656 -0.119305 0.972163 + outer loop + vertex 1.54439 1.31708 2.55584 + vertex 1.54181 1.31453 2.55606 + vertex 1.54429 1.31383 2.55546 + endloop + endfacet + facet normal 0.201525 -0.129532 0.970881 + outer loop + vertex 1.53763 1.3129 2.55671 + vertex 1.53642 1.30799 2.55631 + vertex 1.54042 1.31091 2.55587 + endloop + endfacet + facet normal 0.194257 -0.111606 0.974581 + outer loop + vertex 1.54439 1.31708 2.55584 + vertex 1.54177 1.3177 2.55643 + vertex 1.54181 1.31453 2.55606 + endloop + endfacet + facet normal 0.192863 -0.0984456 0.976275 + outer loop + vertex 1.54177 1.3177 2.55643 + vertex 1.54291 1.32288 2.55673 + vertex 1.53753 1.31787 2.55729 + endloop + endfacet + facet normal 0.188042 -0.0930941 0.977739 + outer loop + vertex 1.53753 1.31787 2.55729 + vertex 1.54291 1.32288 2.55673 + vertex 1.5376 1.32286 2.55775 + endloop + endfacet + facet normal 0.183373 -0.0841028 0.979439 + outer loop + vertex 1.5376 1.32286 2.55775 + vertex 1.54266 1.32798 2.55724 + vertex 1.53752 1.32783 2.55819 + endloop + endfacet + facet normal 0.182284 -0.0830141 0.979735 + outer loop + vertex 1.53238 1.32781 2.55913 + vertex 1.5375 1.33287 2.5586 + vertex 1.53249 1.33306 2.55955 + endloop + endfacet + facet normal 0.18336 -0.0829823 0.979537 + outer loop + vertex 1.54266 1.32798 2.55724 + vertex 1.54257 1.33288 2.55767 + vertex 1.53752 1.32783 2.55819 + endloop + endfacet + facet normal 0.175272 -0.0774078 0.981472 + outer loop + vertex 1.5375 1.33287 2.5586 + vertex 1.5425 1.3378 2.5581 + vertex 1.53752 1.33806 2.55901 + endloop + endfacet + facet normal 0.174861 -0.0836505 0.981033 + outer loop + vertex 1.5425 1.3378 2.5581 + vertex 1.54246 1.34279 2.55853 + vertex 1.53752 1.33806 2.55901 + endloop + endfacet + facet normal 0.177975 -0.0872169 0.980162 + outer loop + vertex 1.54743 1.33311 2.55681 + vertex 1.54755 1.33795 2.55722 + vertex 1.54257 1.33288 2.55767 + endloop + endfacet + facet normal 0.169435 -0.0837677 0.981975 + outer loop + vertex 1.5425 1.3378 2.5581 + vertex 1.54744 1.34274 2.55767 + vertex 1.54246 1.34279 2.55853 + endloop + endfacet + facet normal 0.165274 -0.0971649 0.98145 + outer loop + vertex 1.55274 1.33825 2.55638 + vertex 1.5526 1.34308 2.55688 + vertex 1.54755 1.33795 2.55722 + endloop + endfacet + facet normal 0.151861 -0.0884825 0.984433 + outer loop + vertex 1.54744 1.34274 2.55767 + vertex 1.55242 1.34777 2.55735 + vertex 1.54733 1.34761 2.55812 + endloop + endfacet + facet normal 0.131233 -0.111182 0.985097 + outer loop + vertex 1.55787 1.34352 2.55623 + vertex 1.55771 1.34809 2.55676 + vertex 1.5526 1.34308 2.55688 + endloop + endfacet + facet normal 0.11192 -0.0905125 0.989586 + outer loop + vertex 1.55242 1.34777 2.55735 + vertex 1.55748 1.35285 2.55724 + vertex 1.55229 1.3526 2.55781 + endloop + endfacet + facet normal 0.0638118 -0.0948419 0.993445 + outer loop + vertex 1.56329 1.34787 2.55639 + vertex 1.56277 1.35304 2.55691 + vertex 1.55771 1.34809 2.55676 + endloop + endfacet + facet normal 0.111924 -0.0906226 0.989576 + outer loop + vertex 1.55748 1.35285 2.55724 + vertex 1.55737 1.3577 2.5577 + vertex 1.55229 1.3526 2.55781 + endloop + endfacet + facet normal 0.151871 -0.0889862 0.984387 + outer loop + vertex 1.55242 1.34777 2.55735 + vertex 1.55229 1.3526 2.55781 + vertex 1.54733 1.34761 2.55812 + endloop + endfacet + facet normal 0.169334 -0.087852 0.981635 + outer loop + vertex 1.54744 1.34274 2.55767 + vertex 1.54733 1.34761 2.55812 + vertex 1.54246 1.34279 2.55853 + endloop + endfacet + facet normal 0.168983 -0.0879754 0.981685 + outer loop + vertex 1.54253 1.34786 2.55897 + vertex 1.5473 1.35263 2.55857 + vertex 1.54261 1.35304 2.55942 + endloop + endfacet + facet normal 0.169239 -0.0854096 0.981867 + outer loop + vertex 1.5473 1.35263 2.55857 + vertex 1.54735 1.35784 2.55902 + vertex 1.54261 1.35304 2.55942 + endloop + endfacet + facet normal 0.149308 -0.0843573 0.985186 + outer loop + vertex 1.55225 1.35758 2.55825 + vertex 1.55229 1.36265 2.55868 + vertex 1.54735 1.35784 2.55902 + endloop + endfacet + facet normal 0.0995536 -0.0811118 0.991721 + outer loop + vertex 1.55229 1.36265 2.55868 + vertex 1.55732 1.36759 2.55858 + vertex 1.55239 1.36775 2.55909 + endloop + endfacet + facet normal 0.140692 -0.078294 0.986953 + outer loop + vertex 1.548 1.36833 2.55977 + vertex 1.55249 1.37291 2.55949 + vertex 1.54792 1.37356 2.56019 + endloop + endfacet + facet normal 0.141179 -0.0750736 0.987133 + outer loop + vertex 1.55249 1.37291 2.55949 + vertex 1.5527 1.37819 2.55986 + vertex 1.54792 1.37356 2.56019 + endloop + endfacet + facet normal 0.134466 -0.0680461 0.988579 + outer loop + vertex 1.54792 1.37356 2.56019 + vertex 1.5527 1.37819 2.55986 + vertex 1.54895 1.37889 2.56042 + endloop + endfacet + facet normal 0.0995008 -0.082408 0.991619 + outer loop + vertex 1.55732 1.36759 2.55858 + vertex 1.55732 1.37259 2.559 + vertex 1.55239 1.36775 2.55909 + endloop + endfacet + facet normal 0.0563115 -0.0783771 0.995332 + outer loop + vertex 1.55732 1.37259 2.559 + vertex 1.56243 1.37762 2.5591 + vertex 1.55736 1.37769 2.5594 + endloop + endfacet + facet normal 0.0563599 -0.0759174 0.99552 + outer loop + vertex 1.56243 1.37762 2.5591 + vertex 1.56236 1.38263 2.55949 + vertex 1.55736 1.37769 2.5594 + endloop + endfacet + facet normal 0.053453 -0.0729827 0.9959 + outer loop + vertex 1.55736 1.37769 2.5594 + vertex 1.56236 1.38263 2.55949 + vertex 1.5574 1.38289 2.55977 + endloop + endfacet + facet normal 0.0811975 -0.056418 0.9951 + outer loop + vertex 1.55272 1.38364 2.56024 + vertex 1.5575 1.388 2.5601 + vertex 1.55387 1.38899 2.56045 + endloop + endfacet + facet normal 0.0534262 -0.0734695 0.995865 + outer loop + vertex 1.56236 1.38263 2.55949 + vertex 1.56213 1.38766 2.55987 + vertex 1.5574 1.38289 2.55977 + endloop + endfacet + facet normal 0.0906077 -0.0549548 0.994369 + outer loop + vertex 1.55882 1.40217 2.5607 + vertex 1.55622 1.40304 2.56098 + vertex 1.55649 1.39993 2.56079 + endloop + endfacet + facet normal 0.132826 -0.0509768 0.989828 + outer loop + vertex 1.55649 1.39993 2.56079 + vertex 1.55622 1.40304 2.56098 + vertex 1.55251 1.39832 2.56124 + endloop + endfacet + facet normal 0.166771 -0.068599 0.983606 + outer loop + vertex 1.5514 1.39319 2.56107 + vertex 1.55251 1.39832 2.56124 + vertex 1.54744 1.39317 2.56174 + endloop + endfacet + facet normal 0.076065 -0.0504751 0.995824 + outer loop + vertex 1.55768 1.39328 2.56041 + vertex 1.55894 1.39858 2.56058 + vertex 1.55525 1.39616 2.56074 + endloop + endfacet + facet normal 0.0800681 -0.0605259 0.99495 + outer loop + vertex 1.55768 1.39328 2.56041 + vertex 1.55387 1.38899 2.56045 + vertex 1.5575 1.388 2.5601 + endloop + endfacet + facet normal 0.139928 -0.0722625 0.987521 + outer loop + vertex 1.55394 1.39246 2.56065 + vertex 1.5514 1.39319 2.56107 + vertex 1.55138 1.38991 2.56083 + endloop + endfacet + facet normal 0.16693 -0.0721112 0.983328 + outer loop + vertex 1.55138 1.38991 2.56083 + vertex 1.5514 1.39319 2.56107 + vertex 1.54747 1.38815 2.56137 + endloop + endfacet + facet normal 0.182595 -0.0760483 0.980243 + outer loop + vertex 1.54639 1.38298 2.56117 + vertex 1.54747 1.38815 2.56137 + vertex 1.54246 1.38304 2.5619 + endloop + endfacet + facet normal 0.13342 -0.0674045 0.988765 + outer loop + vertex 1.55272 1.38364 2.56024 + vertex 1.55387 1.38899 2.56045 + vertex 1.55013 1.3861 2.56076 + endloop + endfacet + facet normal 0.134145 -0.0697114 0.988507 + outer loop + vertex 1.55272 1.38364 2.56024 + vertex 1.54895 1.37889 2.56042 + vertex 1.5527 1.37819 2.55986 + endloop + endfacet + facet normal 0.170818 -0.0757985 0.982383 + outer loop + vertex 1.54892 1.38233 2.56068 + vertex 1.54639 1.38298 2.56117 + vertex 1.54645 1.37968 2.5609 + endloop + endfacet + facet normal 0.184942 -0.0753411 0.979857 + outer loop + vertex 1.54645 1.37968 2.5609 + vertex 1.54639 1.38298 2.56117 + vertex 1.54257 1.37799 2.5615 + endloop + endfacet + facet normal 0.204352 -0.0789869 0.975706 + outer loop + vertex 1.5416 1.37281 2.56129 + vertex 1.54257 1.37799 2.5615 + vertex 1.53753 1.37298 2.56215 + endloop + endfacet + facet normal 0.204291 -0.0800811 0.975629 + outer loop + vertex 1.5416 1.37281 2.56129 + vertex 1.53753 1.37298 2.56215 + vertex 1.53771 1.36786 2.56169 + endloop + endfacet + facet normal 0.221587 -0.0791326 0.971924 + outer loop + vertex 1.53771 1.36786 2.56169 + vertex 1.53753 1.37298 2.56215 + vertex 1.53253 1.36783 2.56287 + endloop + endfacet + facet normal 0.169399 -0.0745131 0.982727 + outer loop + vertex 1.54792 1.37356 2.56019 + vertex 1.54895 1.37889 2.56042 + vertex 1.54529 1.37588 2.56082 + endloop + endfacet + facet normal 0.171276 -0.07746 0.982173 + outer loop + vertex 1.54792 1.37356 2.56019 + vertex 1.54439 1.36892 2.56044 + vertex 1.548 1.36833 2.55977 + endloop + endfacet + facet normal 0.187841 -0.079469 0.978979 + outer loop + vertex 1.5442 1.37215 2.56073 + vertex 1.5416 1.37281 2.56129 + vertex 1.5418 1.36956 2.56098 + endloop + endfacet + facet normal 0.202155 -0.0783545 0.976214 + outer loop + vertex 1.5418 1.36956 2.56098 + vertex 1.5416 1.37281 2.56129 + vertex 1.53771 1.36786 2.56169 + endloop + endfacet + facet normal 0.228479 -0.0918279 0.969209 + outer loop + vertex 1.53658 1.36242 2.56144 + vertex 1.53771 1.36786 2.56169 + vertex 1.53235 1.36284 2.56248 + endloop + endfacet + facet normal 0.186323 -0.0809942 0.979144 + outer loop + vertex 1.54382 1.36428 2.56017 + vertex 1.54439 1.36892 2.56044 + vertex 1.54076 1.36577 2.56087 + endloop + endfacet + facet normal 0.170397 -0.0814986 0.981999 + outer loop + vertex 1.54253 1.35856 2.55992 + vertex 1.54764 1.36314 2.55941 + vertex 1.54382 1.36428 2.56017 + endloop + endfacet + facet normal 0.180808 -0.0917142 0.979233 + outer loop + vertex 1.53857 1.3573 2.56053 + vertex 1.53817 1.35341 2.56024 + vertex 1.54253 1.35856 2.55992 + endloop + endfacet + facet normal 0.201902 -0.0960983 0.97468 + outer loop + vertex 1.53658 1.36242 2.56144 + vertex 1.53602 1.35804 2.56113 + vertex 1.53979 1.36114 2.56065 + endloop + endfacet + facet normal 0.230462 -0.0992995 0.968002 + outer loop + vertex 1.53602 1.35804 2.56113 + vertex 1.53658 1.36242 2.56144 + vertex 1.53209 1.358 2.56206 + endloop + endfacet + facet normal 0.191012 -0.0926113 0.977209 + outer loop + vertex 1.53857 1.3573 2.56053 + vertex 1.53603 1.355 2.56081 + vertex 1.53817 1.35341 2.56024 + endloop + endfacet + facet normal 0.242253 -0.0995905 0.965088 + outer loop + vertex 1.52775 1.34771 2.562 + vertex 1.52653 1.34211 2.56173 + vertex 1.53073 1.34582 2.56106 + endloop + endfacet + facet normal 0.159628 -0.0824419 0.983729 + outer loop + vertex 1.52653 1.34211 2.56173 + vertex 1.52775 1.34771 2.562 + vertex 1.52288 1.34244 2.56235 + endloop + endfacet + facet normal 0.230778 -0.111271 0.966623 + outer loop + vertex 1.53467 1.35224 2.56081 + vertex 1.53234 1.35348 2.56151 + vertex 1.53202 1.34977 2.56115 + endloop + endfacet + facet normal 0.164153 -0.108435 0.980457 + outer loop + vertex 1.52775 1.34771 2.562 + vertex 1.52747 1.35279 2.56261 + vertex 1.52297 1.3475 2.56278 + endloop + endfacet + facet normal 0.230354 -0.106643 0.967246 + outer loop + vertex 1.53602 1.35804 2.56113 + vertex 1.53209 1.358 2.56206 + vertex 1.53234 1.35348 2.56151 + endloop + endfacet + facet normal 0.227924 -0.0965987 0.968875 + outer loop + vertex 1.53209 1.358 2.56206 + vertex 1.53658 1.36242 2.56144 + vertex 1.53235 1.36284 2.56248 + endloop + endfacet + facet normal 0.221528 -0.0840555 0.971525 + outer loop + vertex 1.53235 1.36284 2.56248 + vertex 1.53771 1.36786 2.56169 + vertex 1.53253 1.36783 2.56287 + endloop + endfacet + facet normal 0.21405 -0.0714914 0.974203 + outer loop + vertex 1.53253 1.36783 2.56287 + vertex 1.53753 1.37298 2.56215 + vertex 1.5325 1.37278 2.56324 + endloop + endfacet + facet normal 0.204759 -0.0620908 0.976841 + outer loop + vertex 1.5325 1.37278 2.56324 + vertex 1.53761 1.37796 2.5625 + vertex 1.53247 1.37773 2.56357 + endloop + endfacet + facet normal 0.204817 -0.0640977 0.976699 + outer loop + vertex 1.53761 1.37796 2.5625 + vertex 1.53758 1.38286 2.56283 + vertex 1.53247 1.37773 2.56357 + endloop + endfacet + facet normal 0.178931 -0.0603636 0.982008 + outer loop + vertex 1.53758 1.38286 2.56283 + vertex 1.54259 1.38797 2.56223 + vertex 1.53754 1.38777 2.56314 + endloop + endfacet + facet normal 0.190428 -0.0601056 0.979859 + outer loop + vertex 1.53754 1.38777 2.56314 + vertex 1.53752 1.39273 2.56345 + vertex 1.5325 1.38793 2.56413 + endloop + endfacet + facet normal 0.172317 -0.0627226 0.983043 + outer loop + vertex 1.53752 1.39273 2.56345 + vertex 1.54252 1.39771 2.56289 + vertex 1.53754 1.39775 2.56376 + endloop + endfacet + facet normal 0.177072 -0.065356 0.982026 + outer loop + vertex 1.53754 1.39775 2.56376 + vertex 1.54244 1.40263 2.56321 + vertex 1.53756 1.40285 2.5641 + endloop + endfacet + facet normal 0.182882 -0.0629636 0.981117 + outer loop + vertex 1.53756 1.40285 2.5641 + vertex 1.54238 1.40762 2.56351 + vertex 1.53773 1.40806 2.5644 + endloop + endfacet + facet normal 0.183762 -0.0544866 0.98146 + outer loop + vertex 1.54238 1.40762 2.56351 + vertex 1.5424 1.41266 2.56378 + vertex 1.53773 1.40806 2.5644 + endloop + endfacet + facet normal 0.17196 -0.0527234 0.983692 + outer loop + vertex 1.5424 1.41266 2.56378 + vertex 1.54727 1.41751 2.56319 + vertex 1.54243 1.41778 2.56405 + endloop + endfacet + facet normal 0.193728 -0.0541182 0.979562 + outer loop + vertex 1.53782 1.41862 2.565 + vertex 1.54261 1.42305 2.5643 + vertex 1.53876 1.42432 2.56513 + endloop + endfacet + facet normal 0.194618 -0.0514054 0.979531 + outer loop + vertex 1.54261 1.42305 2.5643 + vertex 1.54281 1.42831 2.56454 + vertex 1.53876 1.42432 2.56513 + endloop + endfacet + facet normal 0.172145 -0.0498309 0.98381 + outer loop + vertex 1.54727 1.41751 2.56319 + vertex 1.54727 1.42251 2.56345 + vertex 1.54243 1.41778 2.56405 + endloop + endfacet + facet normal 0.175712 -0.0508381 0.983128 + outer loop + vertex 1.54261 1.42305 2.5643 + vertex 1.54732 1.42761 2.5637 + vertex 1.54281 1.42831 2.56454 + endloop + endfacet + facet normal 0.139033 -0.0491117 0.989069 + outer loop + vertex 1.55237 1.42257 2.56273 + vertex 1.55234 1.4275 2.56298 + vertex 1.54727 1.42251 2.56345 + endloop + endfacet + facet normal 0.140041 -0.0481027 0.988977 + outer loop + vertex 1.54732 1.42761 2.5637 + vertex 1.55231 1.43248 2.56323 + vertex 1.5473 1.43276 2.56395 + endloop + endfacet + facet normal 0.0927415 -0.0473916 0.994562 + outer loop + vertex 1.55756 1.42778 2.56251 + vertex 1.55755 1.43269 2.56274 + vertex 1.55234 1.4275 2.56298 + endloop + endfacet + facet normal 0.0589673 -0.0462553 0.997188 + outer loop + vertex 1.55755 1.43269 2.56274 + vertex 1.56268 1.43785 2.56268 + vertex 1.55751 1.43761 2.56297 + endloop + endfacet + facet normal 0.0586859 -0.0400073 0.997475 + outer loop + vertex 1.56268 1.43785 2.56268 + vertex 1.56268 1.44277 2.56288 + vertex 1.55751 1.43761 2.56297 + endloop + endfacet + facet normal 0.0915752 -0.0392515 0.995024 + outer loop + vertex 1.55745 1.44254 2.56319 + vertex 1.5574 1.44747 2.56339 + vertex 1.55227 1.44252 2.56367 + endloop + endfacet + facet normal 0.0915736 -0.0403755 0.994979 + outer loop + vertex 1.55228 1.43751 2.56346 + vertex 1.55745 1.44254 2.56319 + vertex 1.55227 1.44252 2.56367 + endloop + endfacet + facet normal 0.140167 -0.0460532 0.989056 + outer loop + vertex 1.55231 1.43248 2.56323 + vertex 1.55228 1.43751 2.56346 + vertex 1.5473 1.43276 2.56395 + endloop + endfacet + facet normal 0.176218 -0.0476685 0.983196 + outer loop + vertex 1.54732 1.42761 2.5637 + vertex 1.5473 1.43276 2.56395 + vertex 1.54281 1.42831 2.56454 + endloop + endfacet + facet normal 0.194914 -0.0517177 0.979456 + outer loop + vertex 1.53876 1.42432 2.56513 + vertex 1.54281 1.42831 2.56454 + vertex 1.53912 1.4291 2.56531 + endloop + endfacet + facet normal 0.204357 -0.046518 0.977791 + outer loop + vertex 1.53873 1.43245 2.56555 + vertex 1.53648 1.42983 2.5659 + vertex 1.53912 1.4291 2.56531 + endloop + endfacet + facet normal 0.172382 -0.0371237 0.98433 + outer loop + vertex 1.54249 1.43367 2.56486 + vertex 1.54739 1.43799 2.56416 + vertex 1.5433 1.43933 2.56493 + endloop + endfacet + facet normal 0.20274 -0.0404985 0.978395 + outer loop + vertex 1.53621 1.43739 2.56629 + vertex 1.53605 1.43299 2.56614 + vertex 1.53947 1.43621 2.56556 + endloop + endfacet + facet normal 0.209608 -0.036572 0.977101 + outer loop + vertex 1.53621 1.43739 2.56629 + vertex 1.53643 1.44218 2.56642 + vertex 1.53224 1.43786 2.56716 + endloop + endfacet + facet normal 0.197936 -0.0334794 0.979643 + outer loop + vertex 1.53659 1.44707 2.56655 + vertex 1.53643 1.44218 2.56642 + vertex 1.54017 1.44591 2.56579 + endloop + endfacet + facet normal 0.197147 -0.0359537 0.979714 + outer loop + vertex 1.54036 1.45085 2.56593 + vertex 1.53659 1.44707 2.56655 + vertex 1.54017 1.44591 2.56579 + endloop + endfacet + facet normal 0.193805 -0.0369559 0.980344 + outer loop + vertex 1.5433 1.43933 2.56493 + vertex 1.54364 1.44443 2.56505 + vertex 1.53991 1.44098 2.56566 + endloop + endfacet + facet normal 0.194114 -0.0358561 0.980323 + outer loop + vertex 1.54017 1.44591 2.56579 + vertex 1.54383 1.44943 2.56519 + vertex 1.54036 1.45085 2.56593 + endloop + endfacet + facet normal 0.171388 -0.0349214 0.984585 + outer loop + vertex 1.54759 1.44315 2.56432 + vertex 1.54772 1.44819 2.56448 + vertex 1.54364 1.44443 2.56505 + endloop + endfacet + facet normal 0.129609 -0.032582 0.99103 + outer loop + vertex 1.54772 1.44819 2.56448 + vertex 1.5523 1.4525 2.56402 + vertex 1.54781 1.45319 2.56463 + endloop + endfacet + facet normal 0.129577 -0.0308986 0.991088 + outer loop + vertex 1.54781 1.45319 2.56463 + vertex 1.55233 1.45749 2.56417 + vertex 1.54791 1.45818 2.56477 + endloop + endfacet + facet normal 0.194578 -0.0346942 0.980273 + outer loop + vertex 1.54383 1.44943 2.56519 + vertex 1.544 1.4544 2.56534 + vertex 1.54036 1.45085 2.56593 + endloop + endfacet + facet normal 0.194001 -0.0326911 0.980457 + outer loop + vertex 1.53672 1.45198 2.56669 + vertex 1.53659 1.44707 2.56655 + vertex 1.54036 1.45085 2.56593 + endloop + endfacet + facet normal 0.187158 -0.0332216 0.981768 + outer loop + vertex 1.53672 1.45198 2.56669 + vertex 1.53698 1.45698 2.56681 + vertex 1.53246 1.4526 2.56753 + endloop + endfacet + facet normal 0.183838 -0.0319823 0.982436 + outer loop + vertex 1.53698 1.45698 2.56681 + vertex 1.53774 1.46262 2.56685 + vertex 1.53262 1.45765 2.56765 + endloop + endfacet + facet normal 0.192343 -0.0282231 0.980922 + outer loop + vertex 1.54167 1.46444 2.56614 + vertex 1.54115 1.4676 2.56633 + vertex 1.53774 1.46262 2.56685 + endloop + endfacet + facet normal 0.18153 -0.0296478 0.982938 + outer loop + vertex 1.54384 1.46712 2.56576 + vertex 1.5443 1.46385 2.56558 + vertex 1.54755 1.46848 2.56512 + endloop + endfacet + facet normal 0.127306 -0.0145789 0.991756 + outer loop + vertex 1.54755 1.46848 2.56512 + vertex 1.55244 1.4729 2.56456 + vertex 1.54831 1.47421 2.56511 + endloop + endfacet + facet normal 0.200164 -0.0231607 0.979489 + outer loop + vertex 1.54117 1.47206 2.56643 + vertex 1.54115 1.4676 2.56633 + vertex 1.54449 1.47094 2.56572 + endloop + endfacet + facet normal 0.195602 -0.0189657 0.9805 + outer loop + vertex 1.54117 1.47206 2.56643 + vertex 1.54127 1.47695 2.5665 + vertex 1.53718 1.47256 2.56723 + endloop + endfacet + facet normal 0.1756 -0.0160727 0.98433 + outer loop + vertex 1.54831 1.47421 2.56511 + vertex 1.54856 1.47936 2.56514 + vertex 1.54482 1.47581 2.56575 + endloop + endfacet + facet normal 0.200937 -0.0163337 0.979468 + outer loop + vertex 1.54135 1.48193 2.56657 + vertex 1.54127 1.47695 2.5665 + vertex 1.54499 1.48082 2.56581 + endloop + endfacet + facet normal 0.197614 -0.0148964 0.980167 + outer loop + vertex 1.54135 1.48193 2.56657 + vertex 1.54142 1.48692 2.56663 + vertex 1.53724 1.48251 2.56741 + endloop + endfacet + facet normal 0.17484 -0.0150752 0.984481 + outer loop + vertex 1.54867 1.48439 2.5652 + vertex 1.54875 1.48939 2.56527 + vertex 1.54509 1.48582 2.56586 + endloop + endfacet + facet normal 0.200628 -0.0142991 0.979563 + outer loop + vertex 1.54151 1.49191 2.56669 + vertex 1.54142 1.48692 2.56663 + vertex 1.54519 1.49082 2.56592 + endloop + endfacet + facet normal 0.196791 -0.012922 0.98036 + outer loop + vertex 1.54151 1.49191 2.56669 + vertex 1.54159 1.4969 2.56674 + vertex 1.53732 1.49248 2.56753 + endloop + endfacet + facet normal 0.175174 -0.0124384 0.984459 + outer loop + vertex 1.54884 1.49438 2.56532 + vertex 1.54894 1.49937 2.56536 + vertex 1.5453 1.49581 2.56597 + endloop + endfacet + facet normal 0.123378 -0.00742004 0.992332 + outer loop + vertex 1.54894 1.49937 2.56536 + vertex 1.55287 1.5031 2.5649 + vertex 1.549 1.50436 2.56539 + endloop + endfacet + facet normal 0.198179 -0.00989937 0.980116 + outer loop + vertex 1.54164 1.5019 2.56678 + vertex 1.54159 1.4969 2.56674 + vertex 1.54539 1.50081 2.56601 + endloop + endfacet + facet normal 0.192738 -0.00570808 0.981234 + outer loop + vertex 1.54164 1.5019 2.56678 + vertex 1.54166 1.50689 2.5668 + vertex 1.53737 1.50246 2.56762 + endloop + endfacet + facet normal 0.17595 -0.002748 0.984395 + outer loop + vertex 1.549 1.50436 2.56539 + vertex 1.54902 1.50935 2.5654 + vertex 1.54543 1.5058 2.56603 + endloop + endfacet + facet normal 0.196862 -0.00107518 0.980431 + outer loop + vertex 1.54164 1.51188 2.56681 + vertex 1.54166 1.50689 2.5668 + vertex 1.54544 1.5108 2.56605 + endloop + endfacet + facet normal 0.191439 0.00258744 0.981501 + outer loop + vertex 1.54164 1.51188 2.56681 + vertex 1.54162 1.51688 2.5668 + vertex 1.53735 1.51245 2.56765 + endloop + endfacet + facet normal 0.17802 0.00466083 0.984016 + outer loop + vertex 1.54901 1.51435 2.5654 + vertex 1.54898 1.51934 2.56538 + vertex 1.54541 1.51578 2.56604 + endloop + endfacet + facet normal 0.127813 0.00585872 0.991781 + outer loop + vertex 1.54898 1.51934 2.56538 + vertex 1.55287 1.52306 2.56486 + vertex 1.54893 1.52433 2.56536 + endloop + endfacet + facet normal 0.197427 0.00596012 0.9803 + outer loop + vertex 1.54156 1.52186 2.56678 + vertex 1.54162 1.51688 2.5668 + vertex 1.54537 1.52078 2.56602 + endloop + endfacet + facet normal 0.191779 0.00782897 0.981407 + outer loop + vertex 1.54156 1.52186 2.56678 + vertex 1.54151 1.52686 2.56675 + vertex 1.5373 1.52243 2.56761 + endloop + endfacet + facet normal 0.177322 0.00755973 0.984124 + outer loop + vertex 1.54893 1.52433 2.56536 + vertex 1.54887 1.52932 2.56533 + vertex 1.5453 1.52577 2.566 + endloop + endfacet + facet normal 0.129701 0.00847189 0.991517 + outer loop + vertex 1.54887 1.52932 2.56533 + vertex 1.5528 1.53304 2.56478 + vertex 1.5488 1.53431 2.5653 + endloop + endfacet + facet normal 0.196486 0.00955608 0.98046 + outer loop + vertex 1.54144 1.53185 2.56672 + vertex 1.54151 1.52686 2.56675 + vertex 1.54522 1.53076 2.56597 + endloop + endfacet + facet normal 0.191524 0.0110236 0.981426 + outer loop + vertex 1.54144 1.53185 2.56672 + vertex 1.54138 1.53685 2.56667 + vertex 1.53723 1.53242 2.56753 + endloop + endfacet + facet normal 0.176901 0.012297 0.984152 + outer loop + vertex 1.5488 1.53431 2.5653 + vertex 1.54873 1.5393 2.56525 + vertex 1.54514 1.53576 2.56594 + endloop + endfacet + facet normal 0.130661 0.0155357 0.991305 + outer loop + vertex 1.54873 1.5393 2.56525 + vertex 1.55275 1.54305 2.56466 + vertex 1.54866 1.54427 2.56518 + endloop + endfacet + facet normal 0.195116 0.0144671 0.980673 + outer loop + vertex 1.54132 1.54183 2.56661 + vertex 1.54138 1.53685 2.56667 + vertex 1.54506 1.54074 2.56588 + endloop + endfacet + facet normal 0.190296 0.0200789 0.981521 + outer loop + vertex 1.54132 1.54183 2.56661 + vertex 1.5412 1.5468 2.56653 + vertex 1.53721 1.54243 2.5674 + endloop + endfacet + facet normal 0.177428 0.0215937 0.983897 + outer loop + vertex 1.54866 1.54427 2.56518 + vertex 1.5485 1.54921 2.5651 + vertex 1.54494 1.54568 2.56582 + endloop + endfacet + facet normal 0.193347 0.0277927 0.980737 + outer loop + vertex 1.54085 1.55175 2.56646 + vertex 1.5412 1.5468 2.56653 + vertex 1.54467 1.55059 2.56574 + endloop + endfacet + facet normal 0.188124 0.0333398 0.981579 + outer loop + vertex 1.54085 1.55175 2.56646 + vertex 1.54009 1.55697 2.56643 + vertex 1.53675 1.55224 2.56723 + endloop + endfacet + facet normal 0.174539 0.0345247 0.984045 + outer loop + vertex 1.54346 1.55947 2.56567 + vertex 1.54414 1.55545 2.56569 + vertex 1.5475 1.5595 2.56495 + endloop + endfacet + facet normal 0.174479 0.0389914 0.983889 + outer loop + vertex 1.54346 1.55947 2.56567 + vertex 1.5475 1.5595 2.56495 + vertex 1.54458 1.56379 2.5653 + endloop + endfacet + facet normal 0.190906 0.0373396 0.980898 + outer loop + vertex 1.5412 1.56148 2.56604 + vertex 1.53717 1.56108 2.56684 + vertex 1.54009 1.55697 2.56643 + endloop + endfacet + facet normal 0.183674 0.0332742 0.982424 + outer loop + vertex 1.53717 1.56108 2.56684 + vertex 1.53658 1.5666 2.56677 + vertex 1.53239 1.56236 2.56769 + endloop + endfacet + facet normal 0.191882 0.0323792 0.980884 + outer loop + vertex 1.54458 1.56379 2.5653 + vertex 1.54389 1.5691 2.56526 + vertex 1.54057 1.56554 2.56603 + endloop + endfacet + facet normal 0.172598 0.0293776 0.984554 + outer loop + vertex 1.54389 1.5691 2.56526 + vertex 1.54767 1.57291 2.56448 + vertex 1.54353 1.57418 2.56517 + endloop + endfacet + facet normal 0.188575 0.0327176 0.981514 + outer loop + vertex 1.53628 1.57175 2.56665 + vertex 1.53658 1.5666 2.56677 + vertex 1.5401 1.57058 2.56596 + endloop + endfacet + facet normal 0.181673 0.0347058 0.982746 + outer loop + vertex 1.53628 1.57175 2.56665 + vertex 1.53595 1.57683 2.56653 + vertex 1.53213 1.5724 2.5674 + endloop + endfacet + facet normal 0.184331 0.0382162 0.982121 + outer loop + vertex 1.53527 1.58215 2.56645 + vertex 1.53595 1.57683 2.56653 + vertex 1.53927 1.58064 2.56576 + endloop + endfacet + facet normal 0.191803 0.033992 0.980845 + outer loop + vertex 1.54353 1.57418 2.56517 + vertex 1.5432 1.57926 2.56506 + vertex 1.53976 1.57566 2.56586 + endloop + endfacet + facet normal 0.187899 0.0426049 0.981264 + outer loop + vertex 1.53864 1.58469 2.56571 + vertex 1.53927 1.58064 2.56576 + vertex 1.54259 1.58465 2.56495 + endloop + endfacet + facet normal 0.174407 0.0367875 0.983986 + outer loop + vertex 1.54751 1.57794 2.56434 + vertex 1.54735 1.58298 2.56418 + vertex 1.5432 1.57926 2.56506 + endloop + endfacet + facet normal 0.137726 0.0425499 0.989556 + outer loop + vertex 1.54735 1.58298 2.56418 + vertex 1.55232 1.58727 2.56331 + vertex 1.54743 1.58784 2.56396 + endloop + endfacet + facet normal 0.187903 0.0494896 0.98094 + outer loop + vertex 1.53864 1.58469 2.56571 + vertex 1.54259 1.58465 2.56495 + vertex 1.5397 1.58894 2.56529 + endloop + endfacet + facet normal 0.180086 0.0498324 0.982388 + outer loop + vertex 1.5397 1.58894 2.56529 + vertex 1.54307 1.59309 2.56446 + vertex 1.5389 1.59415 2.56517 + endloop + endfacet + facet normal 0.179657 0.0480295 0.982556 + outer loop + vertex 1.54307 1.59309 2.56446 + vertex 1.54272 1.59797 2.56429 + vertex 1.5389 1.59415 2.56517 + endloop + endfacet + facet normal 0.178697 0.0490193 0.982682 + outer loop + vertex 1.5389 1.59415 2.56517 + vertex 1.54272 1.59797 2.56429 + vertex 1.53837 1.59921 2.56502 + endloop + endfacet + facet normal 0.165711 0.0442846 0.98518 + outer loop + vertex 1.54743 1.58784 2.56396 + vertex 1.54754 1.5925 2.56374 + vertex 1.54378 1.58915 2.56452 + endloop + endfacet + facet normal 0.164823 0.0470567 0.9852 + outer loop + vertex 1.54307 1.59309 2.56446 + vertex 1.54744 1.59728 2.56353 + vertex 1.54272 1.59797 2.56429 + endloop + endfacet + facet normal 0.165113 0.0492217 0.985046 + outer loop + vertex 1.54744 1.59728 2.56353 + vertex 1.54742 1.60229 2.56328 + vertex 1.54272 1.59797 2.56429 + endloop + endfacet + facet normal 0.166348 0.0478462 0.984906 + outer loop + vertex 1.54272 1.59797 2.56429 + vertex 1.54742 1.60229 2.56328 + vertex 1.54256 1.60307 2.56407 + endloop + endfacet + facet normal 0.16689 0.0514964 0.98463 + outer loop + vertex 1.54742 1.60229 2.56328 + vertex 1.54743 1.60737 2.56302 + vertex 1.54256 1.60307 2.56407 + endloop + endfacet + facet normal 0.136291 0.0484211 0.989485 + outer loop + vertex 1.55243 1.59219 2.56308 + vertex 1.55248 1.59712 2.56283 + vertex 1.54754 1.5925 2.56374 + endloop + endfacet + facet normal 0.144548 0.0492974 0.988269 + outer loop + vertex 1.54744 1.59728 2.56353 + vertex 1.55236 1.60197 2.56258 + vertex 1.54742 1.60229 2.56328 + endloop + endfacet + facet normal 0.145017 0.0575929 0.987751 + outer loop + vertex 1.55236 1.60197 2.56258 + vertex 1.55234 1.6069 2.56229 + vertex 1.54742 1.60229 2.56328 + endloop + endfacet + facet normal 0.150477 0.051663 0.987263 + outer loop + vertex 1.54742 1.60229 2.56328 + vertex 1.55234 1.6069 2.56229 + vertex 1.54743 1.60737 2.56302 + endloop + endfacet + facet normal 0.151198 0.0601497 0.986672 + outer loop + vertex 1.55234 1.6069 2.56229 + vertex 1.552 1.61194 2.56204 + vertex 1.54743 1.60737 2.56302 + endloop + endfacet + facet normal 0.155794 0.0554624 0.986231 + outer loop + vertex 1.54743 1.60737 2.56302 + vertex 1.552 1.61194 2.56204 + vertex 1.54729 1.61224 2.56276 + endloop + endfacet + facet normal 0.120464 0.0583014 0.991004 + outer loop + vertex 1.55234 1.6069 2.56229 + vertex 1.55719 1.61135 2.56144 + vertex 1.552 1.61194 2.56204 + endloop + endfacet + facet normal 0.121753 0.0706327 0.990044 + outer loop + vertex 1.55719 1.61135 2.56144 + vertex 1.55537 1.6169 2.56127 + vertex 1.552 1.61194 2.56204 + endloop + endfacet + facet normal 0.094348 0.0609301 0.993673 + outer loop + vertex 1.55769 1.59735 2.56232 + vertex 1.55741 1.60232 2.56204 + vertex 1.55248 1.59712 2.56283 + endloop + endfacet + facet normal 0.114335 0.0576782 0.991766 + outer loop + vertex 1.55236 1.60197 2.56258 + vertex 1.55645 1.60625 2.56186 + vertex 1.55234 1.6069 2.56229 + endloop + endfacet + facet normal 0.0490841 0.0709107 0.996274 + outer loop + vertex 1.56247 1.60272 2.56176 + vertex 1.56154 1.60844 2.5614 + vertex 1.55741 1.60232 2.56204 + endloop + endfacet + facet normal 0.11528 0.0640062 0.991269 + outer loop + vertex 1.55645 1.60625 2.56186 + vertex 1.55719 1.61135 2.56144 + vertex 1.55234 1.6069 2.56229 + endloop + endfacet + facet normal 0.0906856 0.0605243 0.994039 + outer loop + vertex 1.55537 1.6169 2.56127 + vertex 1.55719 1.61135 2.56144 + vertex 1.55962 1.6157 2.56095 + endloop + endfacet + facet normal 0.00322801 0.06298 0.99801 + outer loop + vertex 1.56317 1.61251 2.56105 + vertex 1.56226 1.61488 2.56091 + vertex 1.56098 1.61258 2.56106 + endloop + endfacet + facet normal 0.0900091 0.0580732 0.994246 + outer loop + vertex 1.55962 1.6157 2.56095 + vertex 1.55857 1.61939 2.56083 + vertex 1.55537 1.6169 2.56127 + endloop + endfacet + facet normal 0.127273 0.0613521 0.989968 + outer loop + vertex 1.5547 1.62542 2.56085 + vertex 1.55179 1.62107 2.56149 + vertex 1.55598 1.62146 2.56093 + endloop + endfacet + facet normal 0.136507 0.060427 0.988794 + outer loop + vertex 1.552 1.61194 2.56204 + vertex 1.55537 1.6169 2.56127 + vertex 1.55098 1.61606 2.56193 + endloop + endfacet + facet normal 0.15631 0.0652386 0.985551 + outer loop + vertex 1.552 1.61194 2.56204 + vertex 1.55098 1.61606 2.56193 + vertex 1.54729 1.61224 2.56276 + endloop + endfacet + facet normal 0.16831 0.0557009 0.984159 + outer loop + vertex 1.54743 1.60737 2.56302 + vertex 1.54729 1.61224 2.56276 + vertex 1.5427 1.60805 2.56379 + endloop + endfacet + facet normal 0.167642 0.0506256 0.984547 + outer loop + vertex 1.54256 1.60307 2.56407 + vertex 1.54743 1.60737 2.56302 + vertex 1.5427 1.60805 2.56379 + endloop + endfacet + facet normal 0.178453 0.0481175 0.982771 + outer loop + vertex 1.54272 1.59797 2.56429 + vertex 1.54256 1.60307 2.56407 + vertex 1.53837 1.59921 2.56502 + endloop + endfacet + facet normal 0.193978 0.0505318 0.979704 + outer loop + vertex 1.5389 1.59415 2.56517 + vertex 1.53837 1.59921 2.56502 + vertex 1.53498 1.5956 2.56587 + endloop + endfacet + facet normal 0.218092 0.0431809 0.974972 + outer loop + vertex 1.53097 1.59681 2.56672 + vertex 1.53157 1.59172 2.56681 + vertex 1.53498 1.5956 2.56587 + endloop + endfacet + facet normal 0.225137 0.0495008 0.973069 + outer loop + vertex 1.53097 1.59681 2.56672 + vertex 1.53014 1.60213 2.56664 + vertex 1.52662 1.59731 2.5677 + endloop + endfacet + facet normal 0.219793 0.0536136 0.974072 + outer loop + vertex 1.52662 1.59731 2.5677 + vertex 1.53014 1.60213 2.56664 + vertex 1.52584 1.60133 2.56765 + endloop + endfacet + facet normal 0.159609 0.0420086 0.986286 + outer loop + vertex 1.52662 1.59731 2.5677 + vertex 1.52584 1.60133 2.56765 + vertex 1.52215 1.59738 2.56842 + endloop + endfacet + facet normal 0.196566 0.0520908 0.979106 + outer loop + vertex 1.53363 1.60458 2.56569 + vertex 1.53431 1.60054 2.56577 + vertex 1.53774 1.60464 2.56486 + endloop + endfacet + facet normal 0.217864 0.063718 0.973897 + outer loop + vertex 1.52704 1.60631 2.56706 + vertex 1.52584 1.60133 2.56765 + vertex 1.53014 1.60213 2.56664 + endloop + endfacet + facet normal 0.138498 0.0843765 0.986762 + outer loop + vertex 1.52584 1.60133 2.56765 + vertex 1.52704 1.60631 2.56706 + vertex 1.52221 1.60231 2.56808 + endloop + endfacet + facet normal 0.206961 0.065197 0.976174 + outer loop + vertex 1.52604 1.61189 2.5669 + vertex 1.52704 1.60631 2.56706 + vertex 1.53041 1.61065 2.56605 + endloop + endfacet + facet normal 0.205471 0.0594606 0.976855 + outer loop + vertex 1.52942 1.61557 2.56596 + vertex 1.52604 1.61189 2.5669 + vertex 1.53041 1.61065 2.56605 + endloop + endfacet + facet normal 0.196885 0.0676457 0.97809 + outer loop + vertex 1.52493 1.61716 2.56676 + vertex 1.52604 1.61189 2.5669 + vertex 1.52942 1.61557 2.56596 + endloop + endfacet + facet normal 0.193042 0.0560409 0.979589 + outer loop + vertex 1.52942 1.61557 2.56596 + vertex 1.52855 1.61959 2.5659 + vertex 1.52493 1.61716 2.56676 + endloop + endfacet + facet normal 0.197251 0.0495903 0.979098 + outer loop + vertex 1.52603 1.62154 2.56631 + vertex 1.52493 1.61716 2.56676 + vertex 1.52855 1.61959 2.5659 + endloop + endfacet + facet normal 0.208696 0.0650996 0.975811 + outer loop + vertex 1.52855 1.61959 2.5659 + vertex 1.52972 1.62387 2.56537 + vertex 1.52603 1.62154 2.56631 + endloop + endfacet + facet normal 0.212011 0.0597114 0.975441 + outer loop + vertex 1.52603 1.62154 2.56631 + vertex 1.52972 1.62387 2.56537 + vertex 1.52521 1.62543 2.56625 + endloop + endfacet + facet normal 0.115437 0.0394968 0.992529 + outer loop + vertex 1.52521 1.62543 2.56625 + vertex 1.52186 1.62104 2.56682 + vertex 1.52603 1.62154 2.56631 + endloop + endfacet + facet normal 0.212604 0.061568 0.975197 + outer loop + vertex 1.52972 1.62387 2.56537 + vertex 1.52869 1.62913 2.56526 + vertex 1.52521 1.62543 2.56625 + endloop + endfacet + facet normal 0.220662 0.0536359 0.973874 + outer loop + vertex 1.52521 1.62543 2.56625 + vertex 1.52869 1.62913 2.56526 + vertex 1.52423 1.63025 2.56621 + endloop + endfacet + facet normal 0.118266 0.0330273 0.992433 + outer loop + vertex 1.52423 1.63025 2.56621 + vertex 1.52119 1.62648 2.5667 + vertex 1.52521 1.62543 2.56625 + endloop + endfacet + facet normal 0.223887 0.0678932 0.972248 + outer loop + vertex 1.52869 1.62913 2.56526 + vertex 1.52766 1.63458 2.56512 + vertex 1.52423 1.63025 2.56621 + endloop + endfacet + facet normal 0.237315 0.0566433 0.96978 + outer loop + vertex 1.52322 1.63422 2.56622 + vertex 1.52423 1.63025 2.56621 + vertex 1.52766 1.63458 2.56512 + endloop + endfacet + facet normal 0.220636 0.0672997 0.973032 + outer loop + vertex 1.52869 1.62913 2.56526 + vertex 1.53281 1.63313 2.56405 + vertex 1.52766 1.63458 2.56512 + endloop + endfacet + facet normal 0.222653 0.0752289 0.971991 + outer loop + vertex 1.53281 1.63313 2.56405 + vertex 1.53269 1.63811 2.56369 + vertex 1.52766 1.63458 2.56512 + endloop + endfacet + facet normal 0.217333 0.0830511 0.972558 + outer loop + vertex 1.52766 1.63458 2.56512 + vertex 1.53269 1.63811 2.56369 + vertex 1.52888 1.63935 2.56444 + endloop + endfacet + facet normal 0.232339 0.0787801 0.969439 + outer loop + vertex 1.52421 1.63862 2.56562 + vertex 1.52766 1.63458 2.56512 + vertex 1.52888 1.63935 2.56444 + endloop + endfacet + facet normal 0.232942 0.0751522 0.969582 + outer loop + vertex 1.52888 1.63935 2.56444 + vertex 1.52793 1.64327 2.56436 + vertex 1.52421 1.63862 2.56562 + endloop + endfacet + facet normal 0.217348 0.0714453 0.973476 + outer loop + vertex 1.52888 1.63935 2.56444 + vertex 1.53252 1.64272 2.56338 + vertex 1.52793 1.64327 2.56436 + endloop + endfacet + facet normal 0.21675 0.065467 0.974029 + outer loop + vertex 1.53252 1.64272 2.56338 + vertex 1.5323 1.64733 2.56312 + vertex 1.52793 1.64327 2.56436 + endloop + endfacet + facet normal 0.211568 0.0712709 0.974761 + outer loop + vertex 1.52793 1.64327 2.56436 + vertex 1.5323 1.64733 2.56312 + vertex 1.52767 1.64804 2.56407 + endloop + endfacet + facet normal 0.183988 0.0701308 0.980423 + outer loop + vertex 1.52793 1.64327 2.56436 + vertex 1.52767 1.64804 2.56407 + vertex 1.52284 1.64393 2.56527 + endloop + endfacet + facet normal 0.210845 0.0658391 0.9753 + outer loop + vertex 1.5323 1.64733 2.56312 + vertex 1.53217 1.6523 2.56281 + vertex 1.52767 1.64804 2.56407 + endloop + endfacet + facet normal 0.202561 0.0749179 0.9764 + outer loop + vertex 1.52767 1.64804 2.56407 + vertex 1.53217 1.6523 2.56281 + vertex 1.52759 1.65272 2.56373 + endloop + endfacet + facet normal 0.153414 0.0747411 0.985331 + outer loop + vertex 1.52767 1.64804 2.56407 + vertex 1.52759 1.65272 2.56373 + vertex 1.52391 1.6488 2.5646 + endloop + endfacet + facet normal 0.202051 0.0679989 0.977011 + outer loop + vertex 1.53217 1.6523 2.56281 + vertex 1.53163 1.65718 2.56258 + vertex 1.52759 1.65272 2.56373 + endloop + endfacet + facet normal 0.194886 0.0747305 0.977975 + outer loop + vertex 1.52759 1.65272 2.56373 + vertex 1.53163 1.65718 2.56258 + vertex 1.52723 1.65722 2.56346 + endloop + endfacet + facet normal 0.103922 0.0682088 0.992244 + outer loop + vertex 1.52759 1.65272 2.56373 + vertex 1.52723 1.65722 2.56346 + vertex 1.52317 1.65253 2.5642 + endloop + endfacet + facet normal 0.194933 0.0658849 0.978601 + outer loop + vertex 1.53163 1.65718 2.56258 + vertex 1.53069 1.6611 2.5625 + vertex 1.52723 1.65722 2.56346 + endloop + endfacet + facet normal 0.189559 0.0708691 0.979308 + outer loop + vertex 1.52723 1.65722 2.56346 + vertex 1.53069 1.6611 2.5625 + vertex 1.52709 1.66192 2.56314 + endloop + endfacet + facet normal 0.0702865 0.0685692 0.995167 + outer loop + vertex 1.52723 1.65722 2.56346 + vertex 1.52709 1.66192 2.56314 + vertex 1.52294 1.65725 2.56376 + endloop + endfacet + facet normal 0.192909 0.0870231 0.97735 + outer loop + vertex 1.53069 1.6611 2.5625 + vertex 1.53158 1.66599 2.56189 + vertex 1.52709 1.66192 2.56314 + endloop + endfacet + facet normal 0.206858 0.0711424 0.975781 + outer loop + vertex 1.52709 1.66192 2.56314 + vertex 1.53158 1.66599 2.56189 + vertex 1.52673 1.66681 2.56286 + endloop + endfacet + facet normal 0.0731807 0.0622699 0.995373 + outer loop + vertex 1.52709 1.66192 2.56314 + vertex 1.52673 1.66681 2.56286 + vertex 1.52286 1.66216 2.56344 + endloop + endfacet + facet normal 0.209007 0.0857519 0.974147 + outer loop + vertex 1.53158 1.66599 2.56189 + vertex 1.52996 1.67172 2.56174 + vertex 1.52673 1.66681 2.56286 + endloop + endfacet + facet normal 0.214188 0.0821473 0.973332 + outer loop + vertex 1.52673 1.66681 2.56286 + vertex 1.52996 1.67172 2.56174 + vertex 1.52572 1.67081 2.56275 + endloop + endfacet + facet normal 0.086071 0.0505274 0.995007 + outer loop + vertex 1.52673 1.66681 2.56286 + vertex 1.52572 1.67081 2.56275 + vertex 1.52266 1.66697 2.56321 + endloop + endfacet + facet normal 0.210975 0.0965293 0.972714 + outer loop + vertex 1.52649 1.67573 2.56209 + vertex 1.52572 1.67081 2.56275 + vertex 1.52996 1.67172 2.56174 + endloop + endfacet + facet normal 0.0753777 0.119946 0.989915 + outer loop + vertex 1.52572 1.67081 2.56275 + vertex 1.52649 1.67573 2.56209 + vertex 1.52255 1.67177 2.56287 + endloop + endfacet + facet normal 0.223133 0.089632 0.970658 + outer loop + vertex 1.52996 1.67172 2.56174 + vertex 1.53158 1.66599 2.56189 + vertex 1.53469 1.67033 2.56078 + endloop + endfacet + facet normal 0.226967 0.104314 0.9683 + outer loop + vertex 1.53469 1.67033 2.56078 + vertex 1.53346 1.67436 2.56063 + vertex 1.52996 1.67172 2.56174 + endloop + endfacet + facet normal 0.225724 0.106005 0.968407 + outer loop + vertex 1.5307 1.67629 2.56106 + vertex 1.52996 1.67172 2.56174 + vertex 1.53346 1.67436 2.56063 + endloop + endfacet + facet normal 0.190463 0.0935312 0.977229 + outer loop + vertex 1.53346 1.67436 2.56063 + vertex 1.53469 1.67033 2.56078 + vertex 1.53796 1.67445 2.55975 + endloop + endfacet + facet normal 0.190386 0.095496 0.977054 + outer loop + vertex 1.53346 1.67436 2.56063 + vertex 1.53796 1.67445 2.55975 + vertex 1.53436 1.67877 2.56002 + endloop + endfacet + facet normal 0.179671 0.086385 0.979926 + outer loop + vertex 1.53436 1.67877 2.56002 + vertex 1.53796 1.67445 2.55975 + vertex 1.539 1.67914 2.55914 + endloop + endfacet + facet normal 0.167239 0.0893827 0.981856 + outer loop + vertex 1.53796 1.67445 2.55975 + vertex 1.54271 1.67785 2.55863 + vertex 1.539 1.67914 2.55914 + endloop + endfacet + facet normal 0.165921 0.0853738 0.982436 + outer loop + vertex 1.54271 1.67785 2.55863 + vertex 1.54246 1.68242 2.55827 + vertex 1.539 1.67914 2.55914 + endloop + endfacet + facet normal 0.166217 0.0850556 0.982414 + outer loop + vertex 1.539 1.67914 2.55914 + vertex 1.54246 1.68242 2.55827 + vertex 1.53804 1.68314 2.55896 + endloop + endfacet + facet normal 0.166461 0.0867323 0.982226 + outer loop + vertex 1.54246 1.68242 2.55827 + vertex 1.54219 1.68701 2.55791 + vertex 1.53804 1.68314 2.55896 + endloop + endfacet + facet normal 0.16939 0.0868659 0.981713 + outer loop + vertex 1.54246 1.68242 2.55827 + vertex 1.5458 1.68588 2.55739 + vertex 1.54219 1.68701 2.55791 + endloop + endfacet + facet normal 0.170077 0.0861876 0.981654 + outer loop + vertex 1.54681 1.68186 2.55757 + vertex 1.5458 1.68588 2.55739 + vertex 1.54246 1.68242 2.55827 + endloop + endfacet + facet normal 0.175877 0.0875896 0.980508 + outer loop + vertex 1.54681 1.68186 2.55757 + vertex 1.55012 1.68669 2.55654 + vertex 1.5458 1.68588 2.55739 + endloop + endfacet + facet normal 0.175354 0.0902081 0.980364 + outer loop + vertex 1.54663 1.6908 2.55679 + vertex 1.5458 1.68588 2.55739 + vertex 1.55012 1.68669 2.55654 + endloop + endfacet + facet normal 0.170006 0.0855394 0.981724 + outer loop + vertex 1.54271 1.67785 2.55863 + vertex 1.54681 1.68186 2.55757 + vertex 1.54246 1.68242 2.55827 + endloop + endfacet + facet normal 0.168222 0.0874011 0.981867 + outer loop + vertex 1.54721 1.67698 2.55794 + vertex 1.54681 1.68186 2.55757 + vertex 1.54271 1.67785 2.55863 + endloop + endfacet + facet normal 0.167898 0.0855607 0.982084 + outer loop + vertex 1.54301 1.67304 2.559 + vertex 1.54721 1.67698 2.55794 + vertex 1.54271 1.67785 2.55863 + endloop + endfacet + facet normal 0.166732 0.0868266 0.982172 + outer loop + vertex 1.54745 1.67235 2.5583 + vertex 1.54721 1.67698 2.55794 + vertex 1.54301 1.67304 2.559 + endloop + endfacet + facet normal 0.166288 0.0836122 0.982526 + outer loop + vertex 1.54389 1.66903 2.55919 + vertex 1.54745 1.67235 2.5583 + vertex 1.54301 1.67304 2.559 + endloop + endfacet + facet normal 0.17 0.0843975 0.981823 + outer loop + vertex 1.54389 1.66903 2.55919 + vertex 1.54301 1.67304 2.559 + vertex 1.53939 1.66871 2.55999 + endloop + endfacet + facet normal 0.170423 0.0793362 0.982172 + outer loop + vertex 1.53939 1.66871 2.55999 + vertex 1.54268 1.6644 2.55977 + vertex 1.54389 1.66903 2.55919 + endloop + endfacet + facet normal 0.175984 0.0836513 0.980832 + outer loop + vertex 1.53842 1.66432 2.56054 + vertex 1.54268 1.6644 2.55977 + vertex 1.53939 1.66871 2.55999 + endloop + endfacet + facet normal 0.193621 0.0793693 0.977861 + outer loop + vertex 1.53842 1.66432 2.56054 + vertex 1.53939 1.66871 2.55999 + vertex 1.53585 1.66634 2.56089 + endloop + endfacet + facet normal 0.200626 0.0886383 0.97565 + outer loop + vertex 1.53585 1.66634 2.56089 + vertex 1.53495 1.66188 2.56148 + vertex 1.53842 1.66432 2.56054 + endloop + endfacet + facet normal 0.201742 0.0870165 0.975566 + outer loop + vertex 1.53932 1.66031 2.56071 + vertex 1.53842 1.66432 2.56054 + vertex 1.53495 1.66188 2.56148 + endloop + endfacet + facet normal 0.221957 0.0837496 0.971453 + outer loop + vertex 1.53585 1.66634 2.56089 + vertex 1.53158 1.66599 2.56189 + vertex 1.53495 1.66188 2.56148 + endloop + endfacet + facet normal 0.191507 0.0825854 0.978011 + outer loop + vertex 1.53585 1.66634 2.56089 + vertex 1.53939 1.66871 2.55999 + vertex 1.53469 1.67033 2.56078 + endloop + endfacet + facet normal 0.169628 0.0847172 0.98186 + outer loop + vertex 1.53939 1.66871 2.55999 + vertex 1.54301 1.67304 2.559 + vertex 1.53796 1.67445 2.55975 + endloop + endfacet + facet normal 0.166342 0.0835529 0.982522 + outer loop + vertex 1.54759 1.6678 2.55867 + vertex 1.54745 1.67235 2.5583 + vertex 1.54389 1.66903 2.55919 + endloop + endfacet + facet normal 0.165063 0.0867609 0.98246 + outer loop + vertex 1.54745 1.67235 2.5583 + vertex 1.551 1.67593 2.55739 + vertex 1.54721 1.67698 2.55794 + endloop + endfacet + facet normal 0.165987 0.0903557 0.98198 + outer loop + vertex 1.551 1.67593 2.55739 + vertex 1.55185 1.68097 2.55678 + vertex 1.54721 1.67698 2.55794 + endloop + endfacet + facet normal 0.142578 0.0947329 0.98524 + outer loop + vertex 1.55185 1.68097 2.55678 + vertex 1.551 1.67593 2.55739 + vertex 1.55578 1.677 2.55659 + endloop + endfacet + facet normal 0.160279 0.0915888 0.982813 + outer loop + vertex 1.55197 1.67201 2.5576 + vertex 1.551 1.67593 2.55739 + vertex 1.54745 1.67235 2.5583 + endloop + endfacet + facet normal 0.168471 0.087418 0.981823 + outer loop + vertex 1.54721 1.67698 2.55794 + vertex 1.55185 1.68097 2.55678 + vertex 1.54681 1.68186 2.55757 + endloop + endfacet + facet normal 0.169873 0.0856587 0.981736 + outer loop + vertex 1.54301 1.67304 2.559 + vertex 1.54271 1.67785 2.55863 + vertex 1.53796 1.67445 2.55975 + endloop + endfacet + facet normal 0.194058 0.0905726 0.9768 + outer loop + vertex 1.53939 1.66871 2.55999 + vertex 1.53796 1.67445 2.55975 + vertex 1.53469 1.67033 2.56078 + endloop + endfacet + facet normal 0.221231 0.0910716 0.97096 + outer loop + vertex 1.53469 1.67033 2.56078 + vertex 1.53158 1.66599 2.56189 + vertex 1.53585 1.66634 2.56089 + endloop + endfacet + facet normal 0.219423 0.0815916 0.972212 + outer loop + vertex 1.53158 1.66599 2.56189 + vertex 1.53069 1.6611 2.5625 + vertex 1.53495 1.66188 2.56148 + endloop + endfacet + facet normal 0.221269 0.0720408 0.972548 + outer loop + vertex 1.53163 1.65718 2.56258 + vertex 1.53495 1.66188 2.56148 + vertex 1.53069 1.6611 2.5625 + endloop + endfacet + facet normal 0.21216 0.0788251 0.974051 + outer loop + vertex 1.53606 1.65657 2.56167 + vertex 1.53495 1.66188 2.56148 + vertex 1.53163 1.65718 2.56258 + endloop + endfacet + facet normal 0.210989 0.0689101 0.975057 + outer loop + vertex 1.53217 1.6523 2.56281 + vertex 1.53606 1.65657 2.56167 + vertex 1.53163 1.65718 2.56258 + endloop + endfacet + facet normal 0.201544 0.065721 0.977272 + outer loop + vertex 1.5323 1.64733 2.56312 + vertex 1.53707 1.65108 2.56188 + vertex 1.53217 1.6523 2.56281 + endloop + endfacet + facet normal 0.201698 0.0655181 0.977254 + outer loop + vertex 1.53601 1.64617 2.56243 + vertex 1.53707 1.65108 2.56188 + vertex 1.5323 1.64733 2.56312 + endloop + endfacet + facet normal 0.181412 0.0702626 0.980894 + outer loop + vertex 1.53707 1.65108 2.56188 + vertex 1.53601 1.64617 2.56243 + vertex 1.54033 1.64687 2.56158 + endloop + endfacet + facet normal 0.18122 0.0713843 0.980848 + outer loop + vertex 1.53693 1.64211 2.56255 + vertex 1.54033 1.64687 2.56158 + vertex 1.53601 1.64617 2.56243 + endloop + endfacet + facet normal 0.192944 0.0739597 0.978418 + outer loop + vertex 1.53693 1.64211 2.56255 + vertex 1.53601 1.64617 2.56243 + vertex 1.53252 1.64272 2.56338 + endloop + endfacet + facet normal 0.19293 0.0738441 0.97843 + outer loop + vertex 1.53269 1.63811 2.56369 + vertex 1.53693 1.64211 2.56255 + vertex 1.53252 1.64272 2.56338 + endloop + endfacet + facet normal 0.192054 0.0748021 0.97853 + outer loop + vertex 1.53723 1.63715 2.56287 + vertex 1.53693 1.64211 2.56255 + vertex 1.53269 1.63811 2.56369 + endloop + endfacet + facet normal 0.177796 0.0741222 0.981272 + outer loop + vertex 1.53723 1.63715 2.56287 + vertex 1.54177 1.64099 2.56176 + vertex 1.53693 1.64211 2.56255 + endloop + endfacet + facet normal 0.17792 0.0739718 0.981261 + outer loop + vertex 1.54089 1.63597 2.5623 + vertex 1.54177 1.64099 2.56176 + vertex 1.53723 1.63715 2.56287 + endloop + endfacet + facet normal 0.177427 0.0723399 0.981472 + outer loop + vertex 1.53741 1.63232 2.5632 + vertex 1.54089 1.63597 2.5623 + vertex 1.53723 1.63715 2.56287 + endloop + endfacet + facet normal 0.194077 0.0727484 0.978285 + outer loop + vertex 1.53741 1.63232 2.5632 + vertex 1.53723 1.63715 2.56287 + vertex 1.53281 1.63313 2.56405 + endloop + endfacet + facet normal 0.193207 0.0672293 0.978852 + outer loop + vertex 1.53335 1.62823 2.56428 + vertex 1.53741 1.63232 2.5632 + vertex 1.53281 1.63313 2.56405 + endloop + endfacet + facet normal 0.191854 0.0686181 0.979022 + outer loop + vertex 1.5378 1.6277 2.56344 + vertex 1.53741 1.63232 2.5632 + vertex 1.53335 1.62823 2.56428 + endloop + endfacet + facet normal 0.191266 0.0628733 0.979523 + outer loop + vertex 1.53418 1.62428 2.56437 + vertex 1.5378 1.6277 2.56344 + vertex 1.53335 1.62823 2.56428 + endloop + endfacet + facet normal 0.211738 0.0671112 0.97502 + outer loop + vertex 1.53418 1.62428 2.56437 + vertex 1.53335 1.62823 2.56428 + vertex 1.52972 1.62387 2.56537 + endloop + endfacet + facet normal 0.21216 0.0630103 0.975201 + outer loop + vertex 1.52972 1.62387 2.56537 + vertex 1.5329 1.61964 2.56495 + vertex 1.53418 1.62428 2.56437 + endloop + endfacet + facet normal 0.189534 0.0697965 0.97939 + outer loop + vertex 1.5329 1.61964 2.56495 + vertex 1.53779 1.62302 2.56376 + vertex 1.53418 1.62428 2.56437 + endloop + endfacet + facet normal 0.193806 0.0634677 0.978985 + outer loop + vertex 1.5378 1.61811 2.56408 + vertex 1.53779 1.62302 2.56376 + vertex 1.5329 1.61964 2.56495 + endloop + endfacet + facet normal 0.188319 0.0660953 0.979881 + outer loop + vertex 1.53779 1.62302 2.56376 + vertex 1.5378 1.6277 2.56344 + vertex 1.53418 1.62428 2.56437 + endloop + endfacet + facet normal 0.176824 0.066274 0.982009 + outer loop + vertex 1.53779 1.62302 2.56376 + vertex 1.54216 1.62704 2.5627 + vertex 1.5378 1.6277 2.56344 + endloop + endfacet + facet normal 0.177141 0.068625 0.98179 + outer loop + vertex 1.54216 1.62704 2.5627 + vertex 1.54187 1.63191 2.56242 + vertex 1.5378 1.6277 2.56344 + endloop + endfacet + facet normal 0.174831 0.0685094 0.982212 + outer loop + vertex 1.54216 1.62704 2.5627 + vertex 1.54671 1.63096 2.56162 + vertex 1.54187 1.63191 2.56242 + endloop + endfacet + facet normal 0.175611 0.0728773 0.981758 + outer loop + vertex 1.54671 1.63096 2.56162 + vertex 1.54518 1.63674 2.56147 + vertex 1.54187 1.63191 2.56242 + endloop + endfacet + facet normal 0.177963 0.0712057 0.981457 + outer loop + vertex 1.54187 1.63191 2.56242 + vertex 1.54518 1.63674 2.56147 + vertex 1.54089 1.63597 2.5623 + endloop + endfacet + facet normal 0.176957 0.0661258 0.981995 + outer loop + vertex 1.54223 1.62228 2.56301 + vertex 1.54216 1.62704 2.5627 + vertex 1.53779 1.62302 2.56376 + endloop + endfacet + facet normal 0.178175 0.0675983 0.981674 + outer loop + vertex 1.5378 1.6277 2.56344 + vertex 1.54187 1.63191 2.56242 + vertex 1.53741 1.63232 2.5632 + endloop + endfacet + facet normal 0.178463 0.0713233 0.981358 + outer loop + vertex 1.54187 1.63191 2.56242 + vertex 1.54089 1.63597 2.5623 + vertex 1.53741 1.63232 2.5632 + endloop + endfacet + facet normal 0.177425 0.0740673 0.981343 + outer loop + vertex 1.54177 1.64099 2.56176 + vertex 1.54089 1.63597 2.5623 + vertex 1.54518 1.63674 2.56147 + endloop + endfacet + facet normal 0.201533 0.0649485 0.977326 + outer loop + vertex 1.53252 1.64272 2.56338 + vertex 1.53601 1.64617 2.56243 + vertex 1.5323 1.64733 2.56312 + endloop + endfacet + facet normal 0.214754 0.0743647 0.973833 + outer loop + vertex 1.53269 1.63811 2.56369 + vertex 1.53252 1.64272 2.56338 + vertex 1.52888 1.63935 2.56444 + endloop + endfacet + facet normal 0.192092 0.075002 0.978507 + outer loop + vertex 1.53281 1.63313 2.56405 + vertex 1.53723 1.63715 2.56287 + vertex 1.53269 1.63811 2.56369 + endloop + endfacet + facet normal 0.21836 0.0697421 0.973373 + outer loop + vertex 1.53335 1.62823 2.56428 + vertex 1.53281 1.63313 2.56405 + vertex 1.52869 1.62913 2.56526 + endloop + endfacet + facet normal 0.217107 0.0624255 0.97415 + outer loop + vertex 1.52972 1.62387 2.56537 + vertex 1.53335 1.62823 2.56428 + vertex 1.52869 1.62913 2.56526 + endloop + endfacet + facet normal 0.213144 0.0637766 0.974937 + outer loop + vertex 1.52855 1.61959 2.5659 + vertex 1.5329 1.61964 2.56495 + vertex 1.52972 1.62387 2.56537 + endloop + endfacet + facet normal 0.111367 0.0724905 0.991132 + outer loop + vertex 1.52603 1.62154 2.56631 + vertex 1.52186 1.62104 2.56682 + vertex 1.52493 1.61716 2.56676 + endloop + endfacet + facet normal 0.213228 0.0603278 0.975138 + outer loop + vertex 1.52855 1.61959 2.5659 + vertex 1.52942 1.61557 2.56596 + vertex 1.5329 1.61964 2.56495 + endloop + endfacet + facet normal 0.211602 0.0617847 0.975401 + outer loop + vertex 1.53378 1.61419 2.5651 + vertex 1.5329 1.61964 2.56495 + vertex 1.52942 1.61557 2.56596 + endloop + endfacet + facet normal 0.129694 0.0538431 0.990091 + outer loop + vertex 1.52604 1.61189 2.5669 + vertex 1.52493 1.61716 2.56676 + vertex 1.52157 1.61245 2.56745 + endloop + endfacet + facet normal 0.145843 0.0545762 0.987801 + outer loop + vertex 1.52704 1.60631 2.56706 + vertex 1.52604 1.61189 2.5669 + vertex 1.52217 1.6075 2.56771 + endloop + endfacet + facet normal 0.21554 0.051323 0.975145 + outer loop + vertex 1.53363 1.60458 2.56569 + vertex 1.53475 1.60889 2.56521 + vertex 1.53126 1.60662 2.5661 + endloop + endfacet + facet normal 0.211256 0.0606001 0.97555 + outer loop + vertex 1.53041 1.61065 2.56605 + vertex 1.53378 1.61419 2.5651 + vertex 1.52942 1.61557 2.56596 + endloop + endfacet + facet normal 0.187673 0.056988 0.980577 + outer loop + vertex 1.53905 1.60926 2.56437 + vertex 1.53828 1.61322 2.56429 + vertex 1.53475 1.60889 2.56521 + endloop + endfacet + facet normal 0.192439 0.0587849 0.979547 + outer loop + vertex 1.53378 1.61419 2.5651 + vertex 1.5378 1.61811 2.56408 + vertex 1.5329 1.61964 2.56495 + endloop + endfacet + facet normal 0.175663 0.0596322 0.982643 + outer loop + vertex 1.54278 1.61275 2.56351 + vertex 1.54253 1.61749 2.56327 + vertex 1.53828 1.61322 2.56429 + endloop + endfacet + facet normal 0.176583 0.0636423 0.982226 + outer loop + vertex 1.5378 1.61811 2.56408 + vertex 1.54223 1.62228 2.56301 + vertex 1.53779 1.62302 2.56376 + endloop + endfacet + facet normal 0.170104 0.0637829 0.98336 + outer loop + vertex 1.54719 1.61705 2.56249 + vertex 1.54682 1.62197 2.56223 + vertex 1.54253 1.61749 2.56327 + endloop + endfacet + facet normal 0.172764 0.0661116 0.982742 + outer loop + vertex 1.54223 1.62228 2.56301 + vertex 1.54583 1.62602 2.56213 + vertex 1.54216 1.62704 2.5627 + endloop + endfacet + facet normal 0.160098 0.0702329 0.984599 + outer loop + vertex 1.55179 1.62107 2.56149 + vertex 1.55017 1.62684 2.56134 + vertex 1.54682 1.62197 2.56223 + endloop + endfacet + facet normal 0.173728 0.0698164 0.982316 + outer loop + vertex 1.54583 1.62602 2.56213 + vertex 1.54671 1.63096 2.56162 + vertex 1.54216 1.62704 2.5627 + endloop + endfacet + facet normal 0.167033 0.0706561 0.983416 + outer loop + vertex 1.54518 1.63674 2.56147 + vertex 1.54671 1.63096 2.56162 + vertex 1.54965 1.63529 2.56081 + endloop + endfacet + facet normal 0.122293 0.0620809 0.990551 + outer loop + vertex 1.55345 1.6294 2.5607 + vertex 1.55416 1.63365 2.56035 + vertex 1.55086 1.63137 2.5609 + endloop + endfacet + facet normal 0.169717 0.0794579 0.982284 + outer loop + vertex 1.54965 1.63529 2.56081 + vertex 1.54845 1.63931 2.56069 + vertex 1.54518 1.63674 2.56147 + endloop + endfacet + facet normal 0.0880787 0.0776303 0.993084 + outer loop + vertex 1.55767 1.63786 2.55978 + vertex 1.55739 1.64261 2.55943 + vertex 1.55262 1.63927 2.56012 + endloop + endfacet + facet normal 0.0528483 0.0766925 0.995653 + outer loop + vertex 1.55739 1.64261 2.55943 + vertex 1.56237 1.64716 2.55882 + vertex 1.5574 1.64735 2.55907 + endloop + endfacet + facet normal 0.052952 0.0798832 0.995397 + outer loop + vertex 1.56237 1.64716 2.55882 + vertex 1.56248 1.65221 2.55841 + vertex 1.5574 1.64735 2.55907 + endloop + endfacet + facet normal 0.0978735 0.0811376 0.991886 + outer loop + vertex 1.55734 1.65217 2.5587 + vertex 1.55748 1.65717 2.55828 + vertex 1.55247 1.65271 2.55914 + endloop + endfacet + facet normal 0.0970977 0.0734931 0.992558 + outer loop + vertex 1.55264 1.64789 2.55948 + vertex 1.55734 1.65217 2.5587 + vertex 1.55247 1.65271 2.55914 + endloop + endfacet + facet normal 0.13325 0.0739458 0.98832 + outer loop + vertex 1.55353 1.64384 2.55966 + vertex 1.55264 1.64789 2.55948 + vertex 1.54917 1.64367 2.56026 + endloop + endfacet + facet normal 0.168131 0.0702153 0.983261 + outer loop + vertex 1.54845 1.63931 2.56069 + vertex 1.54917 1.64367 2.56026 + vertex 1.54589 1.64136 2.56098 + endloop + endfacet + facet normal 0.172513 0.0758435 0.982083 + outer loop + vertex 1.54589 1.64136 2.56098 + vertex 1.54518 1.63674 2.56147 + vertex 1.54845 1.63931 2.56069 + endloop + endfacet + facet normal 0.178368 0.0748408 0.981114 + outer loop + vertex 1.54589 1.64136 2.56098 + vertex 1.54177 1.64099 2.56176 + vertex 1.54518 1.63674 2.56147 + endloop + endfacet + facet normal 0.177758 0.0739444 0.981292 + outer loop + vertex 1.54177 1.64099 2.56176 + vertex 1.54033 1.64687 2.56158 + vertex 1.53693 1.64211 2.56255 + endloop + endfacet + facet normal 0.171534 0.0730104 0.982469 + outer loop + vertex 1.54364 1.64947 2.56078 + vertex 1.54473 1.64539 2.56089 + vertex 1.54774 1.6494 2.56007 + endloop + endfacet + facet normal 0.171542 0.0774029 0.982131 + outer loop + vertex 1.54364 1.64947 2.56078 + vertex 1.54774 1.6494 2.56007 + vertex 1.54454 1.65375 2.56028 + endloop + endfacet + facet normal 0.185171 0.0732465 0.979973 + outer loop + vertex 1.5412 1.65147 2.56107 + vertex 1.53707 1.65108 2.56188 + vertex 1.54033 1.64687 2.56158 + endloop + endfacet + facet normal 0.203824 0.0757126 0.976076 + outer loop + vertex 1.53707 1.65108 2.56188 + vertex 1.53606 1.65657 2.56167 + vertex 1.53217 1.6523 2.56281 + endloop + endfacet + facet normal 0.198065 0.0759849 0.977239 + outer loop + vertex 1.53495 1.66188 2.56148 + vertex 1.53606 1.65657 2.56167 + vertex 1.53932 1.66031 2.56071 + endloop + endfacet + facet normal 0.178614 0.0772918 0.980879 + outer loop + vertex 1.54454 1.65375 2.56028 + vertex 1.54357 1.659 2.56005 + vertex 1.54029 1.65546 2.56092 + endloop + endfacet + facet normal 0.176054 0.0814385 0.981006 + outer loop + vertex 1.53842 1.66432 2.56054 + vertex 1.53932 1.66031 2.56071 + vertex 1.54268 1.6644 2.55977 + endloop + endfacet + facet normal 0.166964 0.0760797 0.983023 + outer loop + vertex 1.548 1.65798 2.55937 + vertex 1.54762 1.6629 2.55906 + vertex 1.54357 1.659 2.56005 + endloop + endfacet + facet normal 0.165457 0.0807324 0.982907 + outer loop + vertex 1.54268 1.6644 2.55977 + vertex 1.54759 1.6678 2.55867 + vertex 1.54389 1.66903 2.55919 + endloop + endfacet + facet normal 0.149261 0.0842384 0.985203 + outer loop + vertex 1.55249 1.66227 2.55837 + vertex 1.55235 1.66721 2.55797 + vertex 1.54762 1.6629 2.55906 + endloop + endfacet + facet normal 0.120254 0.0837566 0.989204 + outer loop + vertex 1.55249 1.66227 2.55837 + vertex 1.5573 1.66698 2.55739 + vertex 1.55235 1.66721 2.55797 + endloop + endfacet + facet normal 0.159802 0.0834382 0.983616 + outer loop + vertex 1.54759 1.6678 2.55867 + vertex 1.55197 1.67201 2.5576 + vertex 1.54745 1.67235 2.5583 + endloop + endfacet + facet normal 0.120716 0.0970851 0.987928 + outer loop + vertex 1.5573 1.66698 2.55739 + vertex 1.55687 1.67175 2.55697 + vertex 1.55235 1.66721 2.55797 + endloop + endfacet + facet normal 0.144212 0.0877542 0.985648 + outer loop + vertex 1.55197 1.67201 2.5576 + vertex 1.55578 1.677 2.55659 + vertex 1.551 1.67593 2.55739 + endloop + endfacet + facet normal 0.0816415 0.0969048 0.99194 + outer loop + vertex 1.56109 1.67106 2.55669 + vertex 1.56133 1.67562 2.55623 + vertex 1.55687 1.67175 2.55697 + endloop + endfacet + facet normal 0.0951763 0.103405 0.990075 + outer loop + vertex 1.55631 1.68173 2.55605 + vertex 1.55578 1.677 2.55659 + vertex 1.55992 1.68012 2.55587 + endloop + endfacet + facet normal -0.0195601 0.0705913 0.997314 + outer loop + vertex 1.56321 1.67895 2.55582 + vertex 1.56496 1.67685 2.556 + vertex 1.56607 1.67962 2.55583 + endloop + endfacet + facet normal 0.0357555 0.0803248 0.996127 + outer loop + vertex 1.56371 1.68287 2.55555 + vertex 1.56276 1.68794 2.55518 + vertex 1.55904 1.68454 2.55559 + endloop + endfacet + facet normal 0.0854265 0.0812287 0.993028 + outer loop + vertex 1.55992 1.68012 2.55587 + vertex 1.55904 1.68454 2.55559 + vertex 1.55631 1.68173 2.55605 + endloop + endfacet + facet normal 0.145035 0.0971958 0.984641 + outer loop + vertex 1.55631 1.68173 2.55605 + vertex 1.55185 1.68097 2.55678 + vertex 1.55578 1.677 2.55659 + endloop + endfacet + facet normal 0.169244 0.0922921 0.981243 + outer loop + vertex 1.55185 1.68097 2.55678 + vertex 1.55012 1.68669 2.55654 + vertex 1.54681 1.68186 2.55757 + endloop + endfacet + facet normal 0.103087 0.0792465 0.991511 + outer loop + vertex 1.55342 1.68935 2.55576 + vertex 1.55472 1.68553 2.55593 + vertex 1.55765 1.68948 2.55531 + endloop + endfacet + facet normal 0.175823 0.0906143 0.980242 + outer loop + vertex 1.55079 1.69124 2.556 + vertex 1.54663 1.6908 2.55679 + vertex 1.55012 1.68669 2.55654 + endloop + endfacet + facet normal 0.102718 0.0887535 0.990743 + outer loop + vertex 1.55342 1.68935 2.55576 + vertex 1.55765 1.68948 2.55531 + vertex 1.55413 1.69359 2.5553 + endloop + endfacet + facet normal 0.0963247 0.0967159 0.99064 + outer loop + vertex 1.55857 1.69387 2.55484 + vertex 1.55769 1.69781 2.55455 + vertex 1.55413 1.69359 2.5553 + endloop + endfacet + facet normal 0.0626795 0.102883 0.992717 + outer loop + vertex 1.55769 1.69781 2.55455 + vertex 1.56245 1.70219 2.55379 + vertex 1.55755 1.70261 2.55406 + endloop + endfacet + facet normal 0.063547 0.114007 0.991445 + outer loop + vertex 1.56245 1.70219 2.55379 + vertex 1.56255 1.7072 2.55321 + vertex 1.55755 1.70261 2.55406 + endloop + endfacet + facet normal 0.0676683 0.109572 0.991673 + outer loop + vertex 1.55755 1.70261 2.55406 + vertex 1.56255 1.7072 2.55321 + vertex 1.55766 1.70737 2.55352 + endloop + endfacet + facet normal 0.0678904 0.117887 0.990704 + outer loop + vertex 1.56255 1.7072 2.55321 + vertex 1.56246 1.71214 2.55263 + vertex 1.55766 1.70737 2.55352 + endloop + endfacet + facet normal 0.0750952 0.110686 0.991014 + outer loop + vertex 1.55766 1.70737 2.55352 + vertex 1.56246 1.71214 2.55263 + vertex 1.55745 1.71214 2.55301 + endloop + endfacet + facet normal 0.075001 0.122093 0.989681 + outer loop + vertex 1.56246 1.71214 2.55263 + vertex 1.56187 1.71693 2.55208 + vertex 1.55745 1.71214 2.55301 + endloop + endfacet + facet normal 0.0826989 0.115034 0.989913 + outer loop + vertex 1.55745 1.71214 2.55301 + vertex 1.56187 1.71693 2.55208 + vertex 1.5569 1.71686 2.5525 + endloop + endfacet + facet normal 0.0824089 0.126662 0.988517 + outer loop + vertex 1.56187 1.71693 2.55208 + vertex 1.56032 1.72196 2.55157 + vertex 1.5569 1.71686 2.5525 + endloop + endfacet + facet normal 0.0994205 0.115229 0.988351 + outer loop + vertex 1.5569 1.71686 2.5525 + vertex 1.56032 1.72196 2.55157 + vertex 1.55564 1.72072 2.55218 + endloop + endfacet + facet normal 0.043195 0.11493 0.992434 + outer loop + vertex 1.56187 1.71693 2.55208 + vertex 1.5658 1.72127 2.55141 + vertex 1.56032 1.72196 2.55157 + endloop + endfacet + facet normal 0.0451301 0.130902 0.990368 + outer loop + vertex 1.5658 1.72127 2.55141 + vertex 1.56451 1.72537 2.55092 + vertex 1.56032 1.72196 2.55157 + endloop + endfacet + facet normal 0.0454788 0.130481 0.990407 + outer loop + vertex 1.56038 1.72637 2.55098 + vertex 1.56032 1.72196 2.55157 + vertex 1.56451 1.72537 2.55092 + endloop + endfacet + facet normal 0.0443987 0.125991 0.991037 + outer loop + vertex 1.56451 1.72537 2.55092 + vertex 1.56282 1.72973 2.55045 + vertex 1.56038 1.72637 2.55098 + endloop + endfacet + facet normal 0.0621119 0.113255 0.991623 + outer loop + vertex 1.55844 1.72924 2.55078 + vertex 1.56038 1.72637 2.55098 + vertex 1.56282 1.72973 2.55045 + endloop + endfacet + facet normal 0.0619054 0.114961 0.991439 + outer loop + vertex 1.55844 1.72924 2.55078 + vertex 1.56282 1.72973 2.55045 + vertex 1.55837 1.73387 2.55024 + endloop + endfacet + facet normal 0.111947 0.115227 0.987011 + outer loop + vertex 1.55844 1.72924 2.55078 + vertex 1.55837 1.73387 2.55024 + vertex 1.55531 1.73084 2.55094 + endloop + endfacet + facet normal 0.118649 0.128606 0.984572 + outer loop + vertex 1.55531 1.73084 2.55094 + vertex 1.55559 1.72597 2.55155 + vertex 1.55844 1.72924 2.55078 + endloop + endfacet + facet normal 0.154274 0.129977 0.979441 + outer loop + vertex 1.55531 1.73084 2.55094 + vertex 1.55065 1.73092 2.55167 + vertex 1.55559 1.72597 2.55155 + endloop + endfacet + facet normal 0.15428 0.127362 0.979784 + outer loop + vertex 1.55531 1.73084 2.55094 + vertex 1.55361 1.73412 2.55079 + vertex 1.55065 1.73092 2.55167 + endloop + endfacet + facet normal 0.118135 0.109005 0.986997 + outer loop + vertex 1.55361 1.73412 2.55079 + vertex 1.55531 1.73084 2.55094 + vertex 1.55837 1.73387 2.55024 + endloop + endfacet + facet normal 0.118603 0.121359 0.985498 + outer loop + vertex 1.55361 1.73412 2.55079 + vertex 1.55837 1.73387 2.55024 + vertex 1.55376 1.73888 2.55018 + endloop + endfacet + facet normal 0.125871 0.128024 0.983751 + outer loop + vertex 1.55376 1.73888 2.55018 + vertex 1.55837 1.73387 2.55024 + vertex 1.55875 1.73874 2.54956 + endloop + endfacet + facet normal 0.0697822 0.12336 0.989905 + outer loop + vertex 1.55837 1.73387 2.55024 + vertex 1.56282 1.72973 2.55045 + vertex 1.56352 1.73385 2.54988 + endloop + endfacet + facet normal 0.0697082 0.137396 0.98806 + outer loop + vertex 1.56352 1.73385 2.54988 + vertex 1.56278 1.73765 2.54941 + vertex 1.55837 1.73387 2.55024 + endloop + endfacet + facet normal 0.0736755 0.132833 0.988396 + outer loop + vertex 1.55837 1.73387 2.55024 + vertex 1.56278 1.73765 2.54941 + vertex 1.55875 1.73874 2.54956 + endloop + endfacet + facet normal 0.0746924 0.13668 0.987795 + outer loop + vertex 1.56278 1.73765 2.54941 + vertex 1.56263 1.74231 2.54877 + vertex 1.55875 1.73874 2.54956 + endloop + endfacet + facet normal 0.0852633 0.125339 0.988443 + outer loop + vertex 1.55875 1.73874 2.54956 + vertex 1.56263 1.74231 2.54877 + vertex 1.55795 1.74277 2.54912 + endloop + endfacet + facet normal 0.0424064 0.135876 0.989818 + outer loop + vertex 1.56278 1.73765 2.54941 + vertex 1.5675 1.74212 2.54859 + vertex 1.56263 1.74231 2.54877 + endloop + endfacet + facet normal 0.0425866 0.141209 0.989063 + outer loop + vertex 1.5675 1.74212 2.54859 + vertex 1.56738 1.74706 2.54789 + vertex 1.56263 1.74231 2.54877 + endloop + endfacet + facet normal 0.0481658 0.135727 0.989575 + outer loop + vertex 1.56263 1.74231 2.54877 + vertex 1.56738 1.74706 2.54789 + vertex 1.56236 1.74711 2.54813 + endloop + endfacet + facet normal 0.0395684 0.138821 0.989527 + outer loop + vertex 1.56756 1.73731 2.54926 + vertex 1.5675 1.74212 2.54859 + vertex 1.56278 1.73765 2.54941 + endloop + endfacet + facet normal 0.0390931 0.13173 0.990515 + outer loop + vertex 1.56352 1.73385 2.54988 + vertex 1.56756 1.73731 2.54926 + vertex 1.56278 1.73765 2.54941 + endloop + endfacet + facet normal 0.035356 0.136009 0.990076 + outer loop + vertex 1.56763 1.73284 2.54987 + vertex 1.56756 1.73731 2.54926 + vertex 1.56352 1.73385 2.54988 + endloop + endfacet + facet normal 0.0338009 0.129681 0.99098 + outer loop + vertex 1.56282 1.72973 2.55045 + vertex 1.56763 1.73284 2.54987 + vertex 1.56352 1.73385 2.54988 + endloop + endfacet + facet normal 0.0316838 0.132891 0.990624 + outer loop + vertex 1.56824 1.7287 2.55041 + vertex 1.56763 1.73284 2.54987 + vertex 1.56282 1.72973 2.55045 + endloop + endfacet + facet normal 0.104135 0.141243 0.984483 + outer loop + vertex 1.56038 1.72637 2.55098 + vertex 1.55844 1.72924 2.55078 + vertex 1.55559 1.72597 2.55155 + endloop + endfacet + facet normal 0.0292799 0.120262 0.99231 + outer loop + vertex 1.56282 1.72973 2.55045 + vertex 1.56451 1.72537 2.55092 + vertex 1.56824 1.7287 2.55041 + endloop + endfacet + facet normal 0.0210606 0.129313 0.99138 + outer loop + vertex 1.56451 1.72537 2.55092 + vertex 1.56946 1.72485 2.55089 + vertex 1.56824 1.7287 2.55041 + endloop + endfacet + facet normal 0.105335 0.129056 0.986027 + outer loop + vertex 1.56038 1.72637 2.55098 + vertex 1.55559 1.72597 2.55155 + vertex 1.56032 1.72196 2.55157 + endloop + endfacet + facet normal 0.0204407 0.123349 0.992153 + outer loop + vertex 1.56946 1.72485 2.55089 + vertex 1.56451 1.72537 2.55092 + vertex 1.5658 1.72127 2.55141 + endloop + endfacet + facet normal 0.0341341 0.123036 0.991815 + outer loop + vertex 1.56691 1.71696 2.5519 + vertex 1.5658 1.72127 2.55141 + vertex 1.56187 1.71693 2.55208 + endloop + endfacet + facet normal 0.0341867 0.117404 0.992496 + outer loop + vertex 1.56246 1.71214 2.55263 + vertex 1.56691 1.71696 2.5519 + vertex 1.56187 1.71693 2.55208 + endloop + endfacet + facet normal 0.0316105 0.11975 0.992301 + outer loop + vertex 1.56748 1.71229 2.55245 + vertex 1.56691 1.71696 2.5519 + vertex 1.56246 1.71214 2.55263 + endloop + endfacet + facet normal 0.0316893 0.117492 0.992568 + outer loop + vertex 1.56255 1.7072 2.55321 + vertex 1.56748 1.71229 2.55245 + vertex 1.56246 1.71214 2.55263 + endloop + endfacet + facet normal 0.0309945 0.118156 0.992511 + outer loop + vertex 1.56759 1.70728 2.55304 + vertex 1.56748 1.71229 2.55245 + vertex 1.56255 1.7072 2.55321 + endloop + endfacet + facet normal 0.0310568 0.114801 0.992903 + outer loop + vertex 1.56245 1.70219 2.55379 + vertex 1.56759 1.70728 2.55304 + vertex 1.56255 1.7072 2.55321 + endloop + endfacet + facet normal 0.118776 0.0981241 0.988061 + outer loop + vertex 1.55372 1.70378 2.55435 + vertex 1.55766 1.70737 2.55352 + vertex 1.55288 1.70782 2.55405 + endloop + endfacet + facet normal 0.119913 0.112106 0.986435 + outer loop + vertex 1.55766 1.70737 2.55352 + vertex 1.55745 1.71214 2.55301 + vertex 1.55288 1.70782 2.55405 + endloop + endfacet + facet normal 0.12414 0.107624 0.986411 + outer loop + vertex 1.55288 1.70782 2.55405 + vertex 1.55745 1.71214 2.55301 + vertex 1.55265 1.71264 2.55356 + endloop + endfacet + facet normal 0.15905 0.103478 0.981833 + outer loop + vertex 1.54836 1.69909 2.55569 + vertex 1.55264 1.69915 2.55499 + vertex 1.54918 1.70345 2.5551 + endloop + endfacet + facet normal 0.172767 0.0983948 0.980036 + outer loop + vertex 1.54577 1.70105 2.55595 + vertex 1.54164 1.70068 2.55672 + vertex 1.54508 1.69651 2.55653 + endloop + endfacet + facet normal 0.171369 0.097225 0.980398 + outer loop + vertex 1.54164 1.70068 2.55672 + vertex 1.54088 1.69581 2.55733 + vertex 1.54508 1.69651 2.55653 + endloop + endfacet + facet normal 0.172074 0.0971017 0.980287 + outer loop + vertex 1.54088 1.69581 2.55733 + vertex 1.54164 1.70068 2.55672 + vertex 1.53728 1.69701 2.55785 + endloop + endfacet + facet normal 0.17509 0.0934656 0.980106 + outer loop + vertex 1.53728 1.69701 2.55785 + vertex 1.54164 1.70068 2.55672 + vertex 1.53683 1.70187 2.55747 + endloop + endfacet + facet normal 0.159414 0.0912216 0.982988 + outer loop + vertex 1.54836 1.69909 2.55569 + vertex 1.54957 1.69514 2.55586 + vertex 1.55264 1.69915 2.55499 + endloop + endfacet + facet normal 0.175795 0.0908531 0.980225 + outer loop + vertex 1.54957 1.69514 2.55586 + vertex 1.54663 1.6908 2.55679 + vertex 1.55079 1.69124 2.556 + endloop + endfacet + facet normal 0.170629 0.0910965 0.981115 + outer loop + vertex 1.5458 1.68588 2.55739 + vertex 1.54663 1.6908 2.55679 + vertex 1.54219 1.68701 2.55791 + endloop + endfacet + facet normal 0.172339 0.0918184 0.980749 + outer loop + vertex 1.54184 1.69183 2.55754 + vertex 1.54508 1.69651 2.55653 + vertex 1.54088 1.69581 2.55733 + endloop + endfacet + facet normal 0.213932 0.0895951 0.972731 + outer loop + vertex 1.52823 1.68418 2.56085 + vertex 1.53287 1.68447 2.5598 + vertex 1.52916 1.68869 2.56023 + endloop + endfacet + facet normal 0.176478 0.0877051 0.980389 + outer loop + vertex 1.53776 1.68791 2.55858 + vertex 1.53756 1.69244 2.55822 + vertex 1.534 1.68917 2.55915 + endloop + endfacet + facet normal 0.166541 0.0866446 0.98222 + outer loop + vertex 1.53804 1.68314 2.55896 + vertex 1.54219 1.68701 2.55791 + vertex 1.53776 1.68791 2.55858 + endloop + endfacet + facet normal 0.179509 0.0881269 0.979801 + outer loop + vertex 1.539 1.67914 2.55914 + vertex 1.53804 1.68314 2.55896 + vertex 1.53436 1.67877 2.56002 + endloop + endfacet + facet normal 0.215049 0.0898413 0.972462 + outer loop + vertex 1.53346 1.67436 2.56063 + vertex 1.53436 1.67877 2.56002 + vertex 1.5307 1.67629 2.56106 + endloop + endfacet + facet normal 0.22231 0.106656 0.969125 + outer loop + vertex 1.5307 1.67629 2.56106 + vertex 1.52649 1.67573 2.56209 + vertex 1.52996 1.67172 2.56174 + endloop + endfacet + facet normal 0.118458 0.0685555 0.99059 + outer loop + vertex 1.52649 1.67573 2.56209 + vertex 1.5249 1.68141 2.56189 + vertex 1.5222 1.67664 2.56254 + endloop + endfacet + facet normal 0.213701 0.0924842 0.972511 + outer loop + vertex 1.52823 1.68418 2.56085 + vertex 1.52948 1.6802 2.56095 + vertex 1.53287 1.68447 2.5598 + endloop + endfacet + facet normal 0.230294 0.085743 0.969336 + outer loop + vertex 1.52823 1.68418 2.56085 + vertex 1.52916 1.68869 2.56023 + vertex 1.52549 1.68603 2.56134 + endloop + endfacet + facet normal 0.211873 0.0831587 0.973753 + outer loop + vertex 1.52916 1.68869 2.56023 + vertex 1.53302 1.69317 2.55901 + vertex 1.52755 1.69445 2.56009 + endloop + endfacet + facet normal -0.23299 0.200329 0.951622 + outer loop + vertex 1.52045 1.69534 2.56138 + vertex 1.51954 1.69795 2.56061 + vertex 1.51834 1.69477 2.56098 + endloop + endfacet + facet normal 0.137952 0.0779771 0.987365 + outer loop + vertex 1.52026 1.69123 2.56174 + vertex 1.5218 1.68562 2.56196 + vertex 1.52425 1.69 2.56128 + endloop + endfacet + facet normal 0.115619 0.0670946 0.991025 + outer loop + vertex 1.5218 1.68562 2.56196 + vertex 1.5213 1.6807 2.56236 + vertex 1.5249 1.68141 2.56189 + endloop + endfacet + facet normal 0.114907 0.070602 0.990864 + outer loop + vertex 1.5222 1.67664 2.56254 + vertex 1.5249 1.68141 2.56189 + vertex 1.5213 1.6807 2.56236 + endloop + endfacet + facet normal 0.119905 0.0757105 0.989894 + outer loop + vertex 1.52255 1.67177 2.56287 + vertex 1.52649 1.67573 2.56209 + vertex 1.5222 1.67664 2.56254 + endloop + endfacet + facet normal 0.0607732 0.0707704 0.99564 + outer loop + vertex 1.52266 1.66697 2.56321 + vertex 1.52572 1.67081 2.56275 + vertex 1.52255 1.67177 2.56287 + endloop + endfacet + facet normal 0.0861045 0.0514667 0.994956 + outer loop + vertex 1.52286 1.66216 2.56344 + vertex 1.52673 1.66681 2.56286 + vertex 1.52266 1.66697 2.56321 + endloop + endfacet + facet normal 0.0733656 0.0658284 0.99513 + outer loop + vertex 1.52294 1.65725 2.56376 + vertex 1.52709 1.66192 2.56314 + vertex 1.52286 1.66216 2.56344 + endloop + endfacet + facet normal 0.0702795 0.0973237 0.992768 + outer loop + vertex 1.52317 1.65253 2.5642 + vertex 1.52723 1.65722 2.56346 + vertex 1.52294 1.65725 2.56376 + endloop + endfacet + facet normal 0.100857 0.124365 0.987097 + outer loop + vertex 1.52391 1.6488 2.5646 + vertex 1.52759 1.65272 2.56373 + vertex 1.52317 1.65253 2.5642 + endloop + endfacet + facet normal 0.158233 0.100892 0.982234 + outer loop + vertex 1.52284 1.64393 2.56527 + vertex 1.52767 1.64804 2.56407 + vertex 1.52391 1.6488 2.5646 + endloop + endfacet + facet normal -0.163562 0.11915 0.979311 + outer loop + vertex 1.52006 1.63951 2.56621 + vertex 1.51896 1.6427 2.56564 + vertex 1.51766 1.64005 2.56575 + endloop + endfacet + facet normal -0.174055 0.0746611 0.981901 + outer loop + vertex 1.51766 1.64005 2.56575 + vertex 1.51811 1.63604 2.56613 + vertex 1.52006 1.63951 2.56621 + endloop + endfacet + facet normal 0.18863 0.112281 0.975608 + outer loop + vertex 1.52421 1.63862 2.56562 + vertex 1.52793 1.64327 2.56436 + vertex 1.52284 1.64393 2.56527 + endloop + endfacet + facet normal 0.234998 0.0811573 0.968602 + outer loop + vertex 1.52322 1.63422 2.56622 + vertex 1.52766 1.63458 2.56512 + vertex 1.52421 1.63862 2.56562 + endloop + endfacet + facet normal 0.125464 0.0281913 0.991698 + outer loop + vertex 1.52423 1.63025 2.56621 + vertex 1.52322 1.63422 2.56622 + vertex 1.52029 1.63177 2.56667 + endloop + endfacet + facet normal -0.133632 0.051828 0.989675 + outer loop + vertex 1.52006 1.63951 2.56621 + vertex 1.51811 1.63604 2.56613 + vertex 1.52088 1.63602 2.56651 + endloop + endfacet + facet normal 0.125157 0.0273766 0.991759 + outer loop + vertex 1.52029 1.63177 2.56667 + vertex 1.52119 1.62648 2.5667 + vertex 1.52423 1.63025 2.56621 + endloop + endfacet + facet normal 0.11918 0.0365963 0.992198 + outer loop + vertex 1.52119 1.62648 2.5667 + vertex 1.52186 1.62104 2.56682 + vertex 1.52521 1.62543 2.56625 + endloop + endfacet + facet normal 0.0969233 0.0610389 0.993418 + outer loop + vertex 1.52186 1.62104 2.56682 + vertex 1.52062 1.61624 2.56723 + vertex 1.52493 1.61716 2.56676 + endloop + endfacet + facet normal 0.0926128 0.0806205 0.992433 + outer loop + vertex 1.52157 1.61245 2.56745 + vertex 1.52493 1.61716 2.56676 + vertex 1.52062 1.61624 2.56723 + endloop + endfacet + facet normal 0.131306 0.0676189 0.989033 + outer loop + vertex 1.52217 1.6075 2.56771 + vertex 1.52604 1.61189 2.5669 + vertex 1.52157 1.61245 2.56745 + endloop + endfacet + facet normal 0.149593 0.0708575 0.986205 + outer loop + vertex 1.52221 1.60231 2.56808 + vertex 1.52704 1.60631 2.56706 + vertex 1.52217 1.6075 2.56771 + endloop + endfacet + facet normal 0.133881 0.0664925 0.988764 + outer loop + vertex 1.52215 1.59738 2.56842 + vertex 1.52584 1.60133 2.56765 + vertex 1.52221 1.60231 2.56808 + endloop + endfacet + facet normal 0.159734 0.0597419 0.985351 + outer loop + vertex 1.52239 1.59259 2.56867 + vertex 1.52662 1.59731 2.5677 + vertex 1.52215 1.59738 2.56842 + endloop + endfacet + facet normal 0.181904 0.0589578 0.981547 + outer loop + vertex 1.52266 1.58789 2.5689 + vertex 1.52709 1.59244 2.56781 + vertex 1.52239 1.59259 2.56867 + endloop + endfacet + facet normal 0.148298 0.0523423 0.987557 + outer loop + vertex 1.52258 1.58316 2.56916 + vertex 1.52266 1.58789 2.5689 + vertex 1.51882 1.58402 2.56968 + endloop + endfacet + facet normal 0.154472 0.0810959 0.984663 + outer loop + vertex 1.51749 1.5792 2.57029 + vertex 1.52258 1.58316 2.56916 + vertex 1.51882 1.58402 2.56968 + endloop + endfacet + facet normal -0.210657 0.114265 0.970859 + outer loop + vertex 1.51452 1.57485 2.57112 + vertex 1.51382 1.57814 2.57058 + vertex 1.51259 1.57563 2.57061 + endloop + endfacet + facet normal 0.195712 0.080022 0.977391 + outer loop + vertex 1.51812 1.57401 2.57059 + vertex 1.52247 1.57819 2.56938 + vertex 1.51749 1.5792 2.57029 + endloop + endfacet + facet normal -0.240613 0.0398446 0.969803 + outer loop + vertex 1.51259 1.57563 2.57061 + vertex 1.51279 1.57203 2.57081 + vertex 1.51452 1.57485 2.57112 + endloop + endfacet + facet normal 0.189392 0.0227694 0.981637 + outer loop + vertex 1.51871 1.56896 2.57059 + vertex 1.51812 1.57401 2.57059 + vertex 1.51509 1.57029 2.57126 + endloop + endfacet + facet normal 0.251876 0.0305296 0.967278 + outer loop + vertex 1.51943 1.5636 2.57057 + vertex 1.52318 1.56826 2.56945 + vertex 1.51871 1.56896 2.57059 + endloop + endfacet + facet normal 0.254117 0.0410441 0.966302 + outer loop + vertex 1.51815 1.55906 2.5711 + vertex 1.52247 1.55955 2.56994 + vertex 1.51943 1.5636 2.57057 + endloop + endfacet + facet normal 0.162665 0.0205455 0.986467 + outer loop + vertex 1.51881 1.5551 2.57108 + vertex 1.51815 1.55906 2.5711 + vertex 1.5154 1.55657 2.57161 + endloop + endfacet + facet normal -0.155575 0.0173304 0.987672 + outer loop + vertex 1.51569 1.56527 2.57129 + vertex 1.51375 1.56137 2.57105 + vertex 1.51614 1.56103 2.57144 + endloop + endfacet + facet normal 0.170411 0.0392682 0.98459 + outer loop + vertex 1.5154 1.55657 2.57161 + vertex 1.51596 1.55131 2.57172 + vertex 1.51881 1.5551 2.57108 + endloop + endfacet + facet normal 0.187702 0.0179948 0.982061 + outer loop + vertex 1.51596 1.55131 2.57172 + vertex 1.51626 1.5464 2.57175 + vertex 1.51929 1.55028 2.5711 + endloop + endfacet + facet normal 0.183824 0.0140873 0.982858 + outer loop + vertex 1.51626 1.5464 2.57175 + vertex 1.5164 1.54147 2.5718 + vertex 1.51954 1.54538 2.57115 + endloop + endfacet + facet normal 0.175434 0.0163763 0.984355 + outer loop + vertex 1.5164 1.54147 2.5718 + vertex 1.5165 1.53648 2.57186 + vertex 1.51966 1.54042 2.57123 + endloop + endfacet + facet normal 0.172315 0.015311 0.984923 + outer loop + vertex 1.5165 1.53648 2.57186 + vertex 1.51662 1.53148 2.57192 + vertex 1.51978 1.53541 2.57131 + endloop + endfacet + facet normal 0.168011 0.0128808 0.985701 + outer loop + vertex 1.51662 1.53148 2.57192 + vertex 1.51675 1.52649 2.57196 + vertex 1.51992 1.5304 2.57137 + endloop + endfacet + facet normal 0.165654 0.011456 0.986117 + outer loop + vertex 1.51675 1.52649 2.57196 + vertex 1.51686 1.5215 2.572 + vertex 1.52005 1.52541 2.57142 + endloop + endfacet + facet normal 0.166759 0.00877534 0.985959 + outer loop + vertex 1.51686 1.5215 2.572 + vertex 1.51692 1.5165 2.57204 + vertex 1.52014 1.52042 2.57146 + endloop + endfacet + facet normal 0.171866 -0.00360241 0.985114 + outer loop + vertex 1.51692 1.5165 2.57204 + vertex 1.51694 1.51152 2.57201 + vertex 1.52019 1.51543 2.57146 + endloop + endfacet + facet normal 0.168992 -0.00359562 0.985611 + outer loop + vertex 1.51694 1.51152 2.57201 + vertex 1.51691 1.50652 2.572 + vertex 1.52017 1.51044 2.57146 + endloop + endfacet + facet normal 0.171576 -0.0057003 0.985154 + outer loop + vertex 1.51691 1.50652 2.572 + vertex 1.51685 1.50153 2.57198 + vertex 1.52011 1.50545 2.57144 + endloop + endfacet + facet normal 0.173369 -0.00886499 0.984817 + outer loop + vertex 1.51685 1.50153 2.57198 + vertex 1.51679 1.49654 2.57195 + vertex 1.52004 1.50046 2.57141 + endloop + endfacet + facet normal 0.172561 -0.00497126 0.984986 + outer loop + vertex 1.51679 1.49654 2.57195 + vertex 1.51674 1.49154 2.57193 + vertex 1.51997 1.49546 2.57139 + endloop + endfacet + facet normal 0.174373 -0.00895738 0.984639 + outer loop + vertex 1.51674 1.49154 2.57193 + vertex 1.51672 1.48655 2.57189 + vertex 1.51992 1.49047 2.57136 + endloop + endfacet + facet normal 0.17586 -0.00956001 0.984369 + outer loop + vertex 1.51672 1.48655 2.57189 + vertex 1.51666 1.48154 2.57185 + vertex 1.51988 1.48547 2.57131 + endloop + endfacet + facet normal 0.257564 -0.0252653 0.965931 + outer loop + vertex 1.52345 1.47434 2.57013 + vertex 1.52358 1.47936 2.57022 + vertex 1.51971 1.47546 2.57115 + endloop + endfacet + facet normal 0.226524 -0.0308352 0.973517 + outer loop + vertex 1.52315 1.46921 2.57003 + vertex 1.52784 1.47338 2.56908 + vertex 1.52345 1.47434 2.57013 + endloop + endfacet + facet normal 0.190541 -0.0307432 0.981198 + outer loop + vertex 1.51647 1.47156 2.57167 + vertex 1.5163 1.46674 2.57155 + vertex 1.5195 1.47049 2.57105 + endloop + endfacet + facet normal -0.18493 -0.0190896 0.982566 + outer loop + vertex 1.51615 1.46233 2.57144 + vertex 1.5163 1.46674 2.57155 + vertex 1.51395 1.46306 2.57104 + endloop + endfacet + facet normal -0.182798 -0.0124545 0.983072 + outer loop + vertex 1.51615 1.46233 2.57144 + vertex 1.51395 1.46306 2.57104 + vertex 1.51415 1.45795 2.57101 + endloop + endfacet + facet normal 0.253671 -0.0373014 0.966571 + outer loop + vertex 1.52232 1.4635 2.57003 + vertex 1.52315 1.46921 2.57003 + vertex 1.51909 1.46568 2.57096 + endloop + endfacet + facet normal 0.249446 -0.0357782 0.967728 + outer loop + vertex 1.52232 1.4635 2.57003 + vertex 1.51885 1.45865 2.57075 + vertex 1.52281 1.4583 2.56971 + endloop + endfacet + facet normal 0.186897 -0.0153535 0.982259 + outer loop + vertex 1.51834 1.46185 2.57101 + vertex 1.51615 1.46233 2.57144 + vertex 1.51642 1.45915 2.57134 + endloop + endfacet + facet normal -0.119861 -0.0421488 0.991896 + outer loop + vertex 1.51642 1.45915 2.57134 + vertex 1.51615 1.46233 2.57144 + vertex 1.51415 1.45795 2.57101 + endloop + endfacet + facet normal 0.202959 -0.0276191 0.978798 + outer loop + vertex 1.5188 1.45407 2.57063 + vertex 1.51885 1.45865 2.57075 + vertex 1.51595 1.45531 2.57125 + endloop + endfacet + facet normal 0.249436 -0.0155096 0.968267 + outer loop + vertex 1.51857 1.44908 2.57061 + vertex 1.52283 1.4533 2.56958 + vertex 1.5188 1.45407 2.57063 + endloop + endfacet + facet normal 0.209959 -0.0232164 0.977435 + outer loop + vertex 1.51819 1.44391 2.57057 + vertex 1.51857 1.44908 2.57061 + vertex 1.51522 1.44542 2.57124 + endloop + endfacet + facet normal -0.177458 0.00867244 0.98409 + outer loop + vertex 1.51364 1.45236 2.57087 + vertex 1.51331 1.44725 2.57086 + vertex 1.51559 1.45041 2.57124 + endloop + endfacet + facet normal 0.19912 -0.045305 0.978927 + outer loop + vertex 1.51471 1.44071 2.57113 + vertex 1.51819 1.44391 2.57057 + vertex 1.51522 1.44542 2.57124 + endloop + endfacet + facet normal 0.24893 -0.0270804 0.968143 + outer loop + vertex 1.52246 1.44302 2.56944 + vertex 1.52269 1.44824 2.56953 + vertex 1.51819 1.44391 2.57057 + endloop + endfacet + facet normal 0.216903 -0.0502042 0.974901 + outer loop + vertex 1.52236 1.43772 2.56919 + vertex 1.52752 1.44285 2.56831 + vertex 1.52246 1.44302 2.56944 + endloop + endfacet + facet normal 0.197109 -0.0587466 0.97862 + outer loop + vertex 1.5224 1.43254 2.56887 + vertex 1.52749 1.43782 2.56816 + vertex 1.52236 1.43772 2.56919 + endloop + endfacet + facet normal 0.17649 -0.0556264 0.982729 + outer loop + vertex 1.5224 1.42751 2.56859 + vertex 1.52745 1.43285 2.56798 + vertex 1.5224 1.43254 2.56887 + endloop + endfacet + facet normal 0.165364 -0.0510966 0.984908 + outer loop + vertex 1.52241 1.42255 2.56833 + vertex 1.52743 1.42788 2.56776 + vertex 1.5224 1.42751 2.56859 + endloop + endfacet + facet normal 0.162868 -0.0518876 0.985282 + outer loop + vertex 1.5225 1.41776 2.56806 + vertex 1.52729 1.42279 2.56754 + vertex 1.52241 1.42255 2.56833 + endloop + endfacet + facet normal 0.118413 -0.0420104 0.992075 + outer loop + vertex 1.52649 1.40696 2.56678 + vertex 1.52746 1.41263 2.56691 + vertex 1.5223 1.40768 2.56731 + endloop + endfacet + facet normal 0.164058 -0.0762351 0.9835 + outer loop + vertex 1.52245 1.41289 2.56769 + vertex 1.52711 1.41775 2.56729 + vertex 1.5225 1.41776 2.56806 + endloop + endfacet + facet normal 0.213014 -0.0560577 0.97544 + outer loop + vertex 1.53123 1.41771 2.56639 + vertex 1.53156 1.42235 2.56658 + vertex 1.52711 1.41775 2.56729 + endloop + endfacet + facet normal 0.222156 -0.0578382 0.973294 + outer loop + vertex 1.53405 1.41724 2.56572 + vertex 1.53123 1.41771 2.56639 + vertex 1.53164 1.41451 2.56611 + endloop + endfacet + facet normal 0.219619 -0.0555034 0.974006 + outer loop + vertex 1.53405 1.41724 2.56572 + vertex 1.53164 1.41451 2.56611 + vertex 1.53436 1.41391 2.56546 + endloop + endfacet + facet normal 0.204104 -0.0585082 0.977199 + outer loop + vertex 1.53389 1.40918 2.56527 + vertex 1.53801 1.41327 2.56466 + vertex 1.53436 1.41391 2.56546 + endloop + endfacet + facet normal 0.208478 -0.0569841 0.976366 + outer loop + vertex 1.52746 1.41263 2.56691 + vertex 1.52649 1.40696 2.56678 + vertex 1.53068 1.41057 2.5661 + endloop + endfacet + facet normal 0.11575 -0.0536243 0.99183 + outer loop + vertex 1.52619 1.4024 2.56657 + vertex 1.52649 1.40696 2.56678 + vertex 1.52236 1.40254 2.56703 + endloop + endfacet + facet normal 0.230026 -0.0708958 0.970599 + outer loop + vertex 1.53285 1.40357 2.56511 + vertex 1.53389 1.40918 2.56527 + vertex 1.52988 1.40584 2.56598 + endloop + endfacet + facet normal 0.221397 -0.0737033 0.972395 + outer loop + vertex 1.53285 1.40357 2.56511 + vertex 1.52926 1.39886 2.56557 + vertex 1.53302 1.39833 2.56468 + endloop + endfacet + facet normal 0.222547 -0.0698464 0.972417 + outer loop + vertex 1.52896 1.40206 2.56591 + vertex 1.52619 1.4024 2.56657 + vertex 1.52656 1.39931 2.56627 + endloop + endfacet + facet normal 0.153978 -0.0793782 0.984881 + outer loop + vertex 1.52656 1.39931 2.56627 + vertex 1.52619 1.4024 2.56657 + vertex 1.52281 1.39751 2.56671 + endloop + endfacet + facet normal -0.133082 -0.00921232 0.991062 + outer loop + vertex 1.52193 1.39201 2.56654 + vertex 1.52281 1.39751 2.56671 + vertex 1.51893 1.39315 2.56614 + endloop + endfacet + facet normal -0.139812 -0.0273587 0.9898 + outer loop + vertex 1.51884 1.38812 2.56599 + vertex 1.52193 1.39201 2.56654 + vertex 1.51893 1.39315 2.56614 + endloop + endfacet + facet normal 0.230535 -0.0741166 0.970237 + outer loop + vertex 1.52874 1.39422 2.56534 + vertex 1.52926 1.39886 2.56557 + vertex 1.52561 1.39549 2.56618 + endloop + endfacet + facet normal 0.217401 -0.0574857 0.974388 + outer loop + vertex 1.52757 1.38854 2.56527 + vertex 1.53272 1.39317 2.56439 + vertex 1.52874 1.39422 2.56534 + endloop + endfacet + facet normal 0.239001 -0.0634038 0.968947 + outer loop + vertex 1.52369 1.38696 2.56612 + vertex 1.52376 1.38352 2.56588 + vertex 1.52757 1.38854 2.56527 + endloop + endfacet + facet normal 0.193081 -0.0649691 0.979029 + outer loop + vertex 1.52369 1.38696 2.56612 + vertex 1.52151 1.38425 2.56637 + vertex 1.52376 1.38352 2.56588 + endloop + endfacet + facet normal 0.138454 -0.0199924 0.990167 + outer loop + vertex 1.52369 1.38696 2.56612 + vertex 1.52146 1.38747 2.56644 + vertex 1.52151 1.38425 2.56637 + endloop + endfacet + facet normal 0.18326 -0.0947392 0.978489 + outer loop + vertex 1.52376 1.38352 2.56588 + vertex 1.52151 1.38425 2.56637 + vertex 1.52052 1.38057 2.5662 + endloop + endfacet + facet normal 0.236126 -0.0611152 0.969799 + outer loop + vertex 1.52757 1.38854 2.56527 + vertex 1.52376 1.38352 2.56588 + vertex 1.52759 1.38302 2.56491 + endloop + endfacet + facet normal 0.208809 -0.0689174 0.975525 + outer loop + vertex 1.52739 1.37766 2.56458 + vertex 1.53246 1.38277 2.56385 + vertex 1.52759 1.38302 2.56491 + endloop + endfacet + facet normal 0.0902229 -0.0687187 0.993548 + outer loop + vertex 1.52737 1.37248 2.56422 + vertex 1.52739 1.37766 2.56458 + vertex 1.52266 1.37256 2.56465 + endloop + endfacet + facet normal 0.194648 -0.426252 0.883415 + outer loop + vertex 1.51924 1.37703 2.56569 + vertex 1.51869 1.37343 2.56407 + vertex 1.52261 1.37804 2.56543 + endloop + endfacet + facet normal 0.0899192 -0.0824035 0.992534 + outer loop + vertex 1.52269 1.36737 2.56422 + vertex 1.52737 1.37248 2.56422 + vertex 1.52266 1.37256 2.56465 + endloop + endfacet + facet normal 0.0731934 -0.063004 0.995326 + outer loop + vertex 1.52275 1.36237 2.5639 + vertex 1.52741 1.36748 2.56388 + vertex 1.52269 1.36737 2.56422 + endloop + endfacet + facet normal 0.0833446 -0.0625446 0.994556 + outer loop + vertex 1.5228 1.35743 2.56359 + vertex 1.52742 1.36255 2.56352 + vertex 1.52275 1.36237 2.5639 + endloop + endfacet + facet normal 0.107317 -0.0745038 0.991429 + outer loop + vertex 1.52287 1.35249 2.56321 + vertex 1.5274 1.35766 2.56311 + vertex 1.5228 1.35743 2.56359 + endloop + endfacet + facet normal 0.133645 -0.0823143 0.987605 + outer loop + vertex 1.52297 1.3475 2.56278 + vertex 1.52747 1.35279 2.56261 + vertex 1.52287 1.35249 2.56321 + endloop + endfacet + facet normal 0.163541 -0.0861203 0.98277 + outer loop + vertex 1.52288 1.34244 2.56235 + vertex 1.52775 1.34771 2.562 + vertex 1.52297 1.3475 2.56278 + endloop + endfacet + facet normal 0.159926 -0.0795246 0.983921 + outer loop + vertex 1.52267 1.3376 2.56199 + vertex 1.52653 1.34211 2.56173 + vertex 1.52288 1.34244 2.56235 + endloop + endfacet + facet normal 0.16341 -0.082551 0.983098 + outer loop + vertex 1.52593 1.33774 2.56146 + vertex 1.52653 1.34211 2.56173 + vertex 1.52267 1.3376 2.56199 + endloop + endfacet + facet normal 0.162946 -0.0672638 0.98434 + outer loop + vertex 1.52593 1.33774 2.56146 + vertex 1.52267 1.3376 2.56199 + vertex 1.52268 1.33316 2.56169 + endloop + endfacet + facet normal 0.186165 -0.0840248 0.978919 + outer loop + vertex 1.52578 1.33464 2.56123 + vertex 1.52593 1.33774 2.56146 + vertex 1.52268 1.33316 2.56169 + endloop + endfacet + facet normal 0.244575 -0.0925131 0.965207 + outer loop + vertex 1.52653 1.34211 2.56173 + vertex 1.52593 1.33774 2.56146 + vertex 1.52968 1.34117 2.56084 + endloop + endfacet + facet normal 0.180698 -0.0875536 0.979634 + outer loop + vertex 1.53781 1.34336 2.55939 + vertex 1.53821 1.3485 2.55978 + vertex 1.53391 1.3445 2.56022 + endloop + endfacet + facet normal 0.172591 -0.081219 0.981639 + outer loop + vertex 1.53752 1.33806 2.55901 + vertex 1.54246 1.34279 2.55853 + vertex 1.53781 1.34336 2.55939 + endloop + endfacet + facet normal 0.182581 -0.077344 0.980144 + outer loop + vertex 1.5375 1.33287 2.5586 + vertex 1.53752 1.33806 2.55901 + vertex 1.53249 1.33306 2.55955 + endloop + endfacet + facet normal 0.215228 -0.0882691 0.972567 + outer loop + vertex 1.52837 1.33723 2.56079 + vertex 1.52769 1.333 2.56055 + vertex 1.53251 1.33872 2.56 + endloop + endfacet + facet normal 0.167006 -0.0828991 0.982465 + outer loop + vertex 1.53238 1.32781 2.55913 + vertex 1.53249 1.33306 2.55955 + vertex 1.52753 1.32775 2.55995 + endloop + endfacet + facet normal 0.294975 -0.22867 0.927739 + outer loop + vertex 1.52415 1.3315 2.56131 + vertex 1.52319 1.32756 2.56064 + vertex 1.52769 1.333 2.56055 + endloop + endfacet + facet normal 0.166851 -0.114468 0.979315 + outer loop + vertex 1.52735 1.3227 2.55938 + vertex 1.53238 1.32781 2.55913 + vertex 1.52753 1.32775 2.55995 + endloop + endfacet + facet normal 0.138491 -0.0994592 0.985357 + outer loop + vertex 1.52738 1.31792 2.5589 + vertex 1.53234 1.3228 2.55869 + vertex 1.52735 1.3227 2.55938 + endloop + endfacet + facet normal 0.131999 -0.111795 0.984925 + outer loop + vertex 1.52733 1.31308 2.55836 + vertex 1.53236 1.31788 2.55823 + vertex 1.52738 1.31792 2.5589 + endloop + endfacet + facet normal 0.124037 -0.103407 0.986875 + outer loop + vertex 1.53239 1.31292 2.5577 + vertex 1.53236 1.31788 2.55823 + vertex 1.52733 1.31308 2.55836 + endloop + endfacet + facet normal 0.184132 -0.112536 0.976438 + outer loop + vertex 1.53234 1.308 2.55715 + vertex 1.53763 1.3129 2.55671 + vertex 1.53239 1.31292 2.5577 + endloop + endfacet + facet normal 0.15148 -0.127956 0.980143 + outer loop + vertex 1.53246 1.30342 2.55653 + vertex 1.53234 1.308 2.55715 + vertex 1.52776 1.30292 2.55719 + endloop + endfacet + facet normal 0.148658 -0.0959315 0.984225 + outer loop + vertex 1.53246 1.30342 2.55653 + vertex 1.52776 1.30292 2.55719 + vertex 1.528 1.29791 2.55667 + endloop + endfacet + facet normal 0.147798 -0.0757407 0.986113 + outer loop + vertex 1.528 1.29791 2.55667 + vertex 1.52665 1.29283 2.55648 + vertex 1.5302 1.29579 2.55617 + endloop + endfacet + facet normal 0.224614 -0.100139 0.969289 + outer loop + vertex 1.53419 1.29893 2.55557 + vertex 1.53186 1.29971 2.55619 + vertex 1.5302 1.29579 2.55617 + endloop + endfacet + facet normal 0.203959 -0.114312 0.972282 + outer loop + vertex 1.53821 1.30345 2.55526 + vertex 1.53419 1.29893 2.55557 + vertex 1.53788 1.2984 2.55474 + endloop + endfacet + facet normal 0.18943 -0.104264 0.976343 + outer loop + vertex 1.53745 1.29311 2.55425 + vertex 1.54251 1.29804 2.5538 + vertex 1.53788 1.2984 2.55474 + endloop + endfacet + facet normal 0.196745 -0.102839 0.975046 + outer loop + vertex 1.53738 1.2879 2.55372 + vertex 1.53745 1.29311 2.55425 + vertex 1.53238 1.28789 2.55473 + endloop + endfacet + facet normal 0.266996 -0.199318 0.94286 + outer loop + vertex 1.5285 1.29184 2.55617 + vertex 1.52776 1.28785 2.55554 + vertex 1.53252 1.29343 2.55537 + endloop + endfacet + facet normal 0.0930652 -0.110927 0.989462 + outer loop + vertex 1.53232 1.28264 2.55414 + vertex 1.53238 1.28789 2.55473 + vertex 1.52772 1.28271 2.55459 + endloop + endfacet + facet normal 0.154944 -0.461705 0.873396 + outer loop + vertex 1.52465 1.28706 2.55567 + vertex 1.52381 1.2836 2.55399 + vertex 1.52776 1.28785 2.55554 + endloop + endfacet + facet normal 0.0930497 -0.111492 0.989399 + outer loop + vertex 1.52768 1.2775 2.554 + vertex 1.53232 1.28264 2.55414 + vertex 1.52772 1.28271 2.55459 + endloop + endfacet + facet normal 0.0856349 -0.0987791 0.991418 + outer loop + vertex 1.52775 1.27246 2.55349 + vertex 1.53234 1.27755 2.5536 + vertex 1.52768 1.2775 2.554 + endloop + endfacet + facet normal 0.110555 -0.121153 0.986458 + outer loop + vertex 1.53246 1.27262 2.55299 + vertex 1.53234 1.27755 2.5536 + vertex 1.52775 1.27246 2.55349 + endloop + endfacet + facet normal 0.218438 -0.13812 0.966027 + outer loop + vertex 1.53241 1.26789 2.55232 + vertex 1.53777 1.27296 2.55183 + vertex 1.53246 1.27262 2.55299 + endloop + endfacet + facet normal 0.227137 -0.147647 0.962605 + outer loop + vertex 1.53641 1.26795 2.55138 + vertex 1.53777 1.27296 2.55183 + vertex 1.53241 1.26789 2.55232 + endloop + endfacet + facet normal 0.22705 -0.151814 0.961978 + outer loop + vertex 1.53641 1.26795 2.55138 + vertex 1.53241 1.26789 2.55232 + vertex 1.53242 1.26356 2.55163 + endloop + endfacet + facet normal 0.219169 -0.144479 0.96493 + outer loop + vertex 1.53606 1.26482 2.551 + vertex 1.53641 1.26795 2.55138 + vertex 1.53242 1.26356 2.55163 + endloop + endfacet + facet normal 0.221138 -0.146161 0.964228 + outer loop + vertex 1.53777 1.27296 2.55183 + vertex 1.53641 1.26795 2.55138 + vertex 1.54055 1.27095 2.55089 + endloop + endfacet + facet normal 0.189768 -0.132006 0.972914 + outer loop + vertex 1.54458 1.27385 2.5505 + vertex 1.54218 1.2747 2.55108 + vertex 1.54055 1.27095 2.55089 + endloop + endfacet + facet normal 0.169935 -0.128174 0.977084 + outer loop + vertex 1.54843 1.27827 2.55041 + vertex 1.54458 1.27385 2.5505 + vertex 1.54811 1.27331 2.54981 + endloop + endfacet + facet normal 0.159759 -0.124265 0.979303 + outer loop + vertex 1.54762 1.26809 2.54923 + vertex 1.5525 1.27298 2.54905 + vertex 1.54811 1.27331 2.54981 + endloop + endfacet + facet normal 0.177138 -0.120746 0.976751 + outer loop + vertex 1.54747 1.26294 2.54862 + vertex 1.54762 1.26809 2.54923 + vertex 1.54267 1.26313 2.54952 + endloop + endfacet + facet normal 0.181334 -0.119962 0.976077 + outer loop + vertex 1.53889 1.26719 2.5507 + vertex 1.53796 1.26317 2.55038 + vertex 1.54295 1.26857 2.55012 + endloop + endfacet + facet normal 0.166989 -0.114694 0.979265 + outer loop + vertex 1.54247 1.25795 2.54894 + vertex 1.54267 1.26313 2.54952 + vertex 1.53762 1.25806 2.54978 + endloop + endfacet + facet normal 0.21798 -0.18009 0.959194 + outer loop + vertex 1.5342 1.26193 2.551 + vertex 1.53303 1.25815 2.55056 + vertex 1.53796 1.26317 2.55038 + endloop + endfacet + facet normal 0.0960387 -0.122276 0.987839 + outer loop + vertex 1.53734 1.25289 2.54917 + vertex 1.53762 1.25806 2.54978 + vertex 1.53257 1.25311 2.54966 + endloop + endfacet + facet normal 0.18391 -0.321003 0.92905 + outer loop + vertex 1.5294 1.25733 2.55099 + vertex 1.52865 1.25391 2.54996 + vertex 1.53303 1.25815 2.55056 + endloop + endfacet + facet normal 0.0947647 -0.143778 0.985062 + outer loop + vertex 1.53234 1.24786 2.54892 + vertex 1.53734 1.25289 2.54917 + vertex 1.53257 1.25311 2.54966 + endloop + endfacet + facet normal 0.0694174 -0.108197 0.991703 + outer loop + vertex 1.53252 1.2427 2.54834 + vertex 1.53731 1.24777 2.54856 + vertex 1.53234 1.24786 2.54892 + endloop + endfacet + facet normal 0.120487 -0.121447 0.985258 + outer loop + vertex 1.53292 1.23308 2.54718 + vertex 1.53741 1.23803 2.54724 + vertex 1.53276 1.23774 2.54777 + endloop + endfacet + facet normal 0.157341 -0.154812 0.975334 + outer loop + vertex 1.5373 1.23365 2.54656 + vertex 1.53741 1.23803 2.54724 + vertex 1.53292 1.23308 2.54718 + endloop + endfacet + facet normal 0.226066 -0.154517 0.961779 + outer loop + vertex 1.54143 1.23815 2.54631 + vertex 1.53741 1.23803 2.54724 + vertex 1.5373 1.23365 2.54656 + endloop + endfacet + facet normal 0.152363 -0.108889 0.982308 + outer loop + vertex 1.5373 1.23365 2.54656 + vertex 1.53292 1.23308 2.54718 + vertex 1.5328 1.22859 2.5467 + endloop + endfacet + facet normal 0.177967 -0.131884 0.975159 + outer loop + vertex 1.53621 1.22994 2.54626 + vertex 1.5373 1.23365 2.54656 + vertex 1.5328 1.22859 2.5467 + endloop + endfacet + facet normal 0.251942 -0.178856 0.951071 + outer loop + vertex 1.54106 1.23515 2.54585 + vertex 1.54143 1.23815 2.54631 + vertex 1.5373 1.23365 2.54656 + endloop + endfacet + facet normal 0.22596 -0.169292 0.959313 + outer loop + vertex 1.54143 1.23815 2.54631 + vertex 1.54282 1.24301 2.54685 + vertex 1.53741 1.23803 2.54724 + endloop + endfacet + facet normal 0.203227 -0.147675 0.967931 + outer loop + vertex 1.54784 1.24842 2.54662 + vertex 1.54257 1.24797 2.54765 + vertex 1.54282 1.24301 2.54685 + endloop + endfacet + facet normal 0.185275 -0.141533 0.972441 + outer loop + vertex 1.55272 1.2536 2.54644 + vertex 1.54764 1.25315 2.54734 + vertex 1.54784 1.24842 2.54662 + endloop + endfacet + facet normal 0.1703 -0.151359 0.973698 + outer loop + vertex 1.5566 1.25492 2.54597 + vertex 1.55773 1.25862 2.54634 + vertex 1.55272 1.2536 2.54644 + endloop + endfacet + facet normal 0.167408 -0.138943 0.976048 + outer loop + vertex 1.5546 1.25196 2.54588 + vertex 1.55176 1.24981 2.54606 + vertex 1.55359 1.24818 2.54551 + endloop + endfacet + facet normal 0.140027 -0.14376 0.979656 + outer loop + vertex 1.55757 1.24312 2.5442 + vertex 1.55793 1.24821 2.5449 + vertex 1.55315 1.24337 2.54487 + endloop + endfacet + facet normal 0.170525 -0.151016 0.973712 + outer loop + vertex 1.54999 1.24695 2.54595 + vertex 1.54956 1.24381 2.54554 + vertex 1.55359 1.24818 2.54551 + endloop + endfacet + facet normal 0.139804 -0.146675 0.979256 + outer loop + vertex 1.55261 1.23818 2.54417 + vertex 1.55757 1.24312 2.5442 + vertex 1.55315 1.24337 2.54487 + endloop + endfacet + facet normal 0.16676 -0.147855 0.974849 + outer loop + vertex 1.55242 1.23297 2.54341 + vertex 1.55261 1.23818 2.54417 + vertex 1.54762 1.23322 2.54427 + endloop + endfacet + facet normal 0.178881 -0.141221 0.973683 + outer loop + vertex 1.54389 1.23743 2.54559 + vertex 1.54292 1.2334 2.54519 + vertex 1.54792 1.23868 2.54503 + endloop + endfacet + facet normal 0.187692 -0.140501 0.972127 + outer loop + vertex 1.54742 1.22797 2.54355 + vertex 1.54762 1.23322 2.54427 + vertex 1.54256 1.2281 2.54451 + endloop + endfacet + facet normal 0.214517 -0.14169 0.966388 + outer loop + vertex 1.53913 1.23222 2.54585 + vertex 1.53787 1.22809 2.54553 + vertex 1.54292 1.2334 2.54519 + endloop + endfacet + facet normal 0.187521 -0.141219 0.972056 + outer loop + vertex 1.54235 1.2229 2.5438 + vertex 1.54256 1.2281 2.54451 + vertex 1.53758 1.2229 2.54472 + endloop + endfacet + facet normal 0.273244 -0.252309 0.928266 + outer loop + vertex 1.53414 1.22678 2.54627 + vertex 1.53308 1.22284 2.54551 + vertex 1.53787 1.22809 2.54553 + endloop + endfacet + facet normal 0.186895 -0.162189 0.968899 + outer loop + vertex 1.53758 1.21798 2.54389 + vertex 1.54235 1.2229 2.5438 + vertex 1.53758 1.2229 2.54472 + endloop + endfacet + facet normal 0.173528 -0.176842 0.968821 + outer loop + vertex 1.53757 1.21322 2.54303 + vertex 1.54233 1.21798 2.54304 + vertex 1.53758 1.21798 2.54389 + endloop + endfacet + facet normal 0.1607 -0.179828 0.970483 + outer loop + vertex 1.53761 1.20845 2.54214 + vertex 1.54241 1.21335 2.54225 + vertex 1.53757 1.21322 2.54303 + endloop + endfacet + facet normal 0.143494 -0.147342 0.978621 + outer loop + vertex 1.54243 1.20884 2.54149 + vertex 1.53761 1.20845 2.54214 + vertex 1.53767 1.20387 2.54144 + endloop + endfacet + facet normal 0.134864 -0.139089 0.981053 + outer loop + vertex 1.54127 1.20504 2.54111 + vertex 1.54243 1.20884 2.54149 + vertex 1.53767 1.20387 2.54144 + endloop + endfacet + facet normal 0.195771 -0.16717 0.966296 + outer loop + vertex 1.54637 1.21018 2.54092 + vertex 1.54743 1.21391 2.54135 + vertex 1.54243 1.20884 2.54149 + endloop + endfacet + facet normal 0.191374 -0.167575 0.967106 + outer loop + vertex 1.55133 1.21528 2.54082 + vertex 1.55241 1.219 2.54125 + vertex 1.54743 1.21391 2.54135 + endloop + endfacet + facet normal 0.173951 -0.165821 0.970693 + outer loop + vertex 1.55628 1.22041 2.54079 + vertex 1.55744 1.22403 2.54121 + vertex 1.55241 1.219 2.54125 + endloop + endfacet + facet normal 0.157854 -0.188837 0.969238 + outer loop + vertex 1.56138 1.22528 2.54081 + vertex 1.56264 1.22872 2.54127 + vertex 1.55744 1.22403 2.54121 + endloop + endfacet + facet normal 0.0799572 -0.173244 0.981628 + outer loop + vertex 1.56825 1.23316 2.5416 + vertex 1.56259 1.23315 2.54206 + vertex 1.56264 1.22872 2.54127 + endloop + endfacet + facet normal 0.0410335 -0.185314 0.981822 + outer loop + vertex 1.57422 1.2342 2.54155 + vertex 1.56825 1.23316 2.5416 + vertex 1.57083 1.23032 2.54096 + endloop + endfacet + facet normal 0.0669421 -0.160177 0.984816 + outer loop + vertex 1.56752 1.22684 2.5405 + vertex 1.56679 1.22936 2.54096 + vertex 1.56433 1.22692 2.54073 + endloop + endfacet + facet normal 0.0444992 -0.159403 0.98621 + outer loop + vertex 1.57236 1.22278 2.53967 + vertex 1.57193 1.22693 2.54036 + vertex 1.56757 1.22291 2.53991 + endloop + endfacet + facet normal 0.0445584 -0.157678 0.986485 + outer loop + vertex 1.56749 1.21814 2.53915 + vertex 1.57236 1.22278 2.53967 + vertex 1.56757 1.22291 2.53991 + endloop + endfacet + facet normal 0.0525166 -0.165849 0.984752 + outer loop + vertex 1.57246 1.21799 2.53886 + vertex 1.57236 1.22278 2.53967 + vertex 1.56749 1.21814 2.53915 + endloop + endfacet + facet normal 0.0524485 -0.167528 0.984471 + outer loop + vertex 1.56745 1.21307 2.53829 + vertex 1.57246 1.21799 2.53886 + vertex 1.56749 1.21814 2.53915 + endloop + endfacet + facet normal 0.0911671 -0.16735 0.981673 + outer loop + vertex 1.56745 1.21307 2.53829 + vertex 1.56749 1.21814 2.53915 + vertex 1.56247 1.21322 2.53878 + endloop + endfacet + facet normal 0.0910753 -0.169352 0.981339 + outer loop + vertex 1.56245 1.20811 2.5379 + vertex 1.56745 1.21307 2.53829 + vertex 1.56247 1.21322 2.53878 + endloop + endfacet + facet normal 0.0973267 -0.175518 0.979653 + outer loop + vertex 1.56765 1.2081 2.53738 + vertex 1.56745 1.21307 2.53829 + vertex 1.56245 1.20811 2.5379 + endloop + endfacet + facet normal 0.097343 -0.174652 0.979807 + outer loop + vertex 1.56257 1.20336 2.53704 + vertex 1.56765 1.2081 2.53738 + vertex 1.56245 1.20811 2.5379 + endloop + endfacet + facet normal 0.111564 -0.189583 0.975506 + outer loop + vertex 1.56779 1.2035 2.53647 + vertex 1.56765 1.2081 2.53738 + vertex 1.56257 1.20336 2.53704 + endloop + endfacet + facet normal 0.111486 -0.178434 0.977616 + outer loop + vertex 1.56779 1.2035 2.53647 + vertex 1.56257 1.20336 2.53704 + vertex 1.56256 1.19899 2.53624 + endloop + endfacet + facet normal 0.136813 -0.207364 0.96865 + outer loop + vertex 1.56661 1.2001 2.53591 + vertex 1.56779 1.2035 2.53647 + vertex 1.56256 1.19899 2.53624 + endloop + endfacet + facet normal 0.131356 -0.185836 0.973761 + outer loop + vertex 1.56661 1.2001 2.53591 + vertex 1.56256 1.19899 2.53624 + vertex 1.56443 1.19741 2.53569 + endloop + endfacet + facet normal 0.103555 -0.163968 0.981015 + outer loop + vertex 1.56822 1.19805 2.53539 + vertex 1.56661 1.2001 2.53591 + vertex 1.56443 1.19741 2.53569 + endloop + endfacet + facet normal 0.102922 -0.159872 0.981758 + outer loop + vertex 1.56443 1.19741 2.53569 + vertex 1.56309 1.19357 2.5352 + vertex 1.56822 1.19805 2.53539 + endloop + endfacet + facet normal 0.115079 -0.173628 0.978065 + outer loop + vertex 1.56822 1.19805 2.53539 + vertex 1.56309 1.19357 2.5352 + vertex 1.56777 1.19329 2.5346 + endloop + endfacet + facet normal 0.0684946 -0.17006 0.98305 + outer loop + vertex 1.56777 1.19329 2.5346 + vertex 1.57259 1.19739 2.53498 + vertex 1.56822 1.19805 2.53539 + endloop + endfacet + facet normal 0.0673755 -0.176775 0.981942 + outer loop + vertex 1.57272 1.20127 2.53567 + vertex 1.56822 1.19805 2.53539 + vertex 1.57259 1.19739 2.53498 + endloop + endfacet + facet normal 0.0236702 -0.175699 0.984159 + outer loop + vertex 1.57259 1.19739 2.53498 + vertex 1.57732 1.20086 2.53548 + vertex 1.57272 1.20127 2.53567 + endloop + endfacet + facet normal 0.0225171 -0.187711 0.981966 + outer loop + vertex 1.57272 1.20127 2.53567 + vertex 1.57732 1.20086 2.53548 + vertex 1.57581 1.20447 2.53621 + endloop + endfacet + facet normal 0.0279294 -0.192753 0.98085 + outer loop + vertex 1.57193 1.20388 2.5362 + vertex 1.57272 1.20127 2.53567 + vertex 1.57581 1.20447 2.53621 + endloop + endfacet + facet normal 0.0288749 -0.198985 0.979577 + outer loop + vertex 1.57581 1.20447 2.53621 + vertex 1.57333 1.20775 2.53695 + vertex 1.57193 1.20388 2.5362 + endloop + endfacet + facet normal 0.0826484 -0.217008 0.972665 + outer loop + vertex 1.57193 1.20388 2.5362 + vertex 1.57333 1.20775 2.53695 + vertex 1.56779 1.2035 2.53647 + endloop + endfacet + facet normal 0.0826016 -0.216396 0.972805 + outer loop + vertex 1.57193 1.20388 2.5362 + vertex 1.56779 1.2035 2.53647 + vertex 1.56957 1.20159 2.53589 + endloop + endfacet + facet normal 0.033086 -0.195909 0.980064 + outer loop + vertex 1.57955 1.20823 2.53683 + vertex 1.57333 1.20775 2.53695 + vertex 1.57581 1.20447 2.53621 + endloop + endfacet + facet normal 0.0313297 -0.171838 0.984627 + outer loop + vertex 1.57955 1.20823 2.53683 + vertex 1.57805 1.21297 2.53771 + vertex 1.57333 1.20775 2.53695 + endloop + endfacet + facet normal 0.0461437 -0.184801 0.981692 + outer loop + vertex 1.57333 1.20775 2.53695 + vertex 1.57805 1.21297 2.53771 + vertex 1.57266 1.21295 2.53796 + endloop + endfacet + facet normal 0.0634317 -0.182476 0.981162 + outer loop + vertex 1.57333 1.20775 2.53695 + vertex 1.57266 1.21295 2.53796 + vertex 1.56765 1.2081 2.53738 + endloop + endfacet + facet normal 0.0461974 -0.172499 0.983926 + outer loop + vertex 1.57805 1.21297 2.53771 + vertex 1.57756 1.21796 2.5386 + vertex 1.57266 1.21295 2.53796 + endloop + endfacet + facet normal 0.0480102 -0.174223 0.983535 + outer loop + vertex 1.57266 1.21295 2.53796 + vertex 1.57756 1.21796 2.5386 + vertex 1.57246 1.21799 2.53886 + endloop + endfacet + facet normal 0.0480387 -0.172426 0.98385 + outer loop + vertex 1.57756 1.21796 2.5386 + vertex 1.5774 1.22289 2.53948 + vertex 1.57246 1.21799 2.53886 + endloop + endfacet + facet normal 0.0416436 -0.166141 0.985222 + outer loop + vertex 1.57246 1.21799 2.53886 + vertex 1.5774 1.22289 2.53948 + vertex 1.57236 1.22278 2.53967 + endloop + endfacet + facet normal 0.0417828 -0.175369 0.983616 + outer loop + vertex 1.5774 1.22289 2.53948 + vertex 1.5768 1.22717 2.54027 + vertex 1.57236 1.22278 2.53967 + endloop + endfacet + facet normal 0.0274003 -0.161229 0.986537 + outer loop + vertex 1.57236 1.22278 2.53967 + vertex 1.5768 1.22717 2.54027 + vertex 1.57193 1.22693 2.54036 + endloop + endfacet + facet normal 0.0279914 -0.174241 0.984305 + outer loop + vertex 1.57193 1.22693 2.54036 + vertex 1.5768 1.22717 2.54027 + vertex 1.57564 1.23073 2.54093 + endloop + endfacet + facet normal 0.0196428 -0.166322 0.985876 + outer loop + vertex 1.57083 1.23032 2.54096 + vertex 1.57193 1.22693 2.54036 + vertex 1.57564 1.23073 2.54093 + endloop + endfacet + facet normal 0.0197234 -0.167286 0.985711 + outer loop + vertex 1.57564 1.23073 2.54093 + vertex 1.57422 1.2342 2.54155 + vertex 1.57083 1.23032 2.54096 + endloop + endfacet + facet normal 0.0302997 -0.163046 0.986153 + outer loop + vertex 1.57903 1.23444 2.54144 + vertex 1.57422 1.2342 2.54155 + vertex 1.57564 1.23073 2.54093 + endloop + endfacet + facet normal 0.0333938 -0.165795 0.985595 + outer loop + vertex 1.58016 1.23119 2.54085 + vertex 1.57903 1.23444 2.54144 + vertex 1.57564 1.23073 2.54093 + endloop + endfacet + facet normal 0.0589926 -0.157001 0.985835 + outer loop + vertex 1.5824 1.23437 2.54123 + vertex 1.57903 1.23444 2.54144 + vertex 1.58016 1.23119 2.54085 + endloop + endfacet + facet normal 0.0603226 -0.112209 0.991852 + outer loop + vertex 1.5824 1.23437 2.54123 + vertex 1.58302 1.23829 2.54163 + vertex 1.57903 1.23444 2.54144 + endloop + endfacet + facet normal 0.080653 -0.133102 0.987815 + outer loop + vertex 1.57903 1.23444 2.54144 + vertex 1.58302 1.23829 2.54163 + vertex 1.57825 1.23845 2.54204 + endloop + endfacet + facet normal 0.0812019 -0.121233 0.989297 + outer loop + vertex 1.58302 1.23829 2.54163 + vertex 1.58256 1.24307 2.54225 + vertex 1.57825 1.23845 2.54204 + endloop + endfacet + facet normal 0.0293495 -0.143308 0.989243 + outer loop + vertex 1.57903 1.23444 2.54144 + vertex 1.57825 1.23845 2.54204 + vertex 1.57422 1.2342 2.54155 + endloop + endfacet + facet normal 0.0456682 -0.158417 0.986316 + outer loop + vertex 1.57422 1.2342 2.54155 + vertex 1.57825 1.23845 2.54204 + vertex 1.57304 1.23823 2.54225 + endloop + endfacet + facet normal 0.0451764 -0.14522 0.988367 + outer loop + vertex 1.57825 1.23845 2.54204 + vertex 1.5777 1.24305 2.54274 + vertex 1.57304 1.23823 2.54225 + endloop + endfacet + facet normal 0.0581318 -0.157464 0.985812 + outer loop + vertex 1.57304 1.23823 2.54225 + vertex 1.5777 1.24305 2.54274 + vertex 1.57254 1.24294 2.54303 + endloop + endfacet + facet normal 0.058025 -0.148673 0.987183 + outer loop + vertex 1.5777 1.24305 2.54274 + vertex 1.57754 1.24799 2.5435 + vertex 1.57254 1.24294 2.54303 + endloop + endfacet + facet normal 0.0631387 -0.15364 0.986108 + outer loop + vertex 1.57254 1.24294 2.54303 + vertex 1.57754 1.24799 2.5435 + vertex 1.57241 1.24795 2.54382 + endloop + endfacet + facet normal 0.0631526 -0.147809 0.986998 + outer loop + vertex 1.57754 1.24799 2.5435 + vertex 1.57747 1.25312 2.54427 + vertex 1.57241 1.24795 2.54382 + endloop + endfacet + facet normal 0.0616294 -0.146345 0.987312 + outer loop + vertex 1.57241 1.24795 2.54382 + vertex 1.57747 1.25312 2.54427 + vertex 1.57222 1.25293 2.54457 + endloop + endfacet + facet normal 0.0618989 -0.155766 0.985853 + outer loop + vertex 1.57747 1.25312 2.54427 + vertex 1.57692 1.2587 2.54518 + vertex 1.57222 1.25293 2.54457 + endloop + endfacet + facet normal 0.0413203 -0.139376 0.989377 + outer loop + vertex 1.57222 1.25293 2.54457 + vertex 1.57692 1.2587 2.54518 + vertex 1.5714 1.25668 2.54513 + endloop + endfacet + facet normal 0.0462636 -0.152846 0.987167 + outer loop + vertex 1.57692 1.2587 2.54518 + vertex 1.57256 1.26066 2.54569 + vertex 1.5714 1.25668 2.54513 + endloop + endfacet + facet normal 0.0269691 -0.194126 0.980606 + outer loop + vertex 1.57627 1.26219 2.54589 + vertex 1.57256 1.26066 2.54569 + vertex 1.57692 1.2587 2.54518 + endloop + endfacet + facet normal 0.0102258 -0.154585 0.987927 + outer loop + vertex 1.57627 1.26219 2.54589 + vertex 1.57444 1.26382 2.54617 + vertex 1.57256 1.26066 2.54569 + endloop + endfacet + facet normal -0.00411826 -0.146256 0.989238 + outer loop + vertex 1.57256 1.26066 2.54569 + vertex 1.57444 1.26382 2.54617 + vertex 1.57169 1.26361 2.54613 + endloop + endfacet + facet normal -0.00541281 -0.130313 0.991458 + outer loop + vertex 1.57444 1.26382 2.54617 + vertex 1.57365 1.26752 2.54665 + vertex 1.57169 1.26361 2.54613 + endloop + endfacet + facet normal 0.0269117 -0.123417 0.99199 + outer loop + vertex 1.57444 1.26382 2.54617 + vertex 1.57779 1.26545 2.54628 + vertex 1.57365 1.26752 2.54665 + endloop + endfacet + facet normal 0.0362221 -0.10507 0.993805 + outer loop + vertex 1.57779 1.26545 2.54628 + vertex 1.57844 1.26927 2.54666 + vertex 1.57365 1.26752 2.54665 + endloop + endfacet + facet normal 0.0355307 -0.103174 0.994028 + outer loop + vertex 1.57844 1.26927 2.54666 + vertex 1.57774 1.273 2.54707 + vertex 1.57365 1.26752 2.54665 + endloop + endfacet + facet normal 0.0648316 -0.124762 0.990066 + outer loop + vertex 1.57365 1.26752 2.54665 + vertex 1.57774 1.273 2.54707 + vertex 1.57275 1.2729 2.54739 + endloop + endfacet + facet normal 0.0647403 -0.116722 0.991052 + outer loop + vertex 1.57774 1.273 2.54707 + vertex 1.57752 1.27799 2.54767 + vertex 1.57275 1.2729 2.54739 + endloop + endfacet + facet normal 0.0809523 -0.131764 0.98797 + outer loop + vertex 1.57275 1.2729 2.54739 + vertex 1.57752 1.27799 2.54767 + vertex 1.5725 1.27793 2.54808 + endloop + endfacet + facet normal 0.0809482 -0.124637 0.988895 + outer loop + vertex 1.57752 1.27799 2.54767 + vertex 1.57753 1.28302 2.54831 + vertex 1.5725 1.27793 2.54808 + endloop + endfacet + facet normal 0.0896125 -0.133111 0.987042 + outer loop + vertex 1.5725 1.27793 2.54808 + vertex 1.57753 1.28302 2.54831 + vertex 1.57254 1.28297 2.54875 + endloop + endfacet + facet normal 0.049648 -0.133196 0.989845 + outer loop + vertex 1.5725 1.27793 2.54808 + vertex 1.57254 1.28297 2.54875 + vertex 1.56738 1.27786 2.54833 + endloop + endfacet + facet normal 0.0496941 -0.139162 0.989022 + outer loop + vertex 1.56749 1.27291 2.54762 + vertex 1.5725 1.27793 2.54808 + vertex 1.56738 1.27786 2.54833 + endloop + endfacet + facet normal 0.0442998 -0.133868 0.990009 + outer loop + vertex 1.57275 1.2729 2.54739 + vertex 1.5725 1.27793 2.54808 + vertex 1.56749 1.27291 2.54762 + endloop + endfacet + facet normal 0.0442125 -0.144325 0.988542 + outer loop + vertex 1.56794 1.26817 2.54691 + vertex 1.57275 1.2729 2.54739 + vertex 1.56749 1.27291 2.54762 + endloop + endfacet + facet normal 0.0489743 -0.132527 0.989969 + outer loop + vertex 1.56738 1.27786 2.54833 + vertex 1.57254 1.28297 2.54875 + vertex 1.56742 1.28292 2.549 + endloop + endfacet + facet normal 0.0489664 -0.128933 0.990444 + outer loop + vertex 1.57254 1.28297 2.54875 + vertex 1.57255 1.28808 2.54942 + vertex 1.56742 1.28292 2.549 + endloop + endfacet + facet normal 0.0459333 -0.125956 0.990972 + outer loop + vertex 1.56742 1.28292 2.549 + vertex 1.57255 1.28808 2.54942 + vertex 1.5673 1.2879 2.54964 + endloop + endfacet + facet normal 0.0462247 -0.136011 0.989628 + outer loop + vertex 1.57255 1.28808 2.54942 + vertex 1.57208 1.29363 2.5502 + vertex 1.5673 1.2879 2.54964 + endloop + endfacet + facet normal 0.0267461 -0.120019 0.992411 + outer loop + vertex 1.5673 1.2879 2.54964 + vertex 1.57208 1.29363 2.5502 + vertex 1.56649 1.29167 2.55012 + endloop + endfacet + facet normal 0.0288875 -0.126101 0.991597 + outer loop + vertex 1.57208 1.29363 2.5502 + vertex 1.56769 1.2957 2.55059 + vertex 1.56649 1.29167 2.55012 + endloop + endfacet + facet normal 0.0106715 -0.16386 0.986426 + outer loop + vertex 1.57149 1.29716 2.5508 + vertex 1.56769 1.2957 2.55059 + vertex 1.57208 1.29363 2.5502 + endloop + endfacet + facet normal -0.00156057 -0.132709 0.991154 + outer loop + vertex 1.57149 1.29716 2.5508 + vertex 1.56965 1.29887 2.55102 + vertex 1.56769 1.2957 2.55059 + endloop + endfacet + facet normal -0.00734259 -0.12919 0.991593 + outer loop + vertex 1.56769 1.2957 2.55059 + vertex 1.56965 1.29887 2.55102 + vertex 1.56679 1.29868 2.55098 + endloop + endfacet + facet normal -0.00730837 -0.129706 0.991526 + outer loop + vertex 1.56965 1.29887 2.55102 + vertex 1.5688 1.30255 2.5515 + vertex 1.56679 1.29868 2.55098 + endloop + endfacet + facet normal 0.00600449 -0.126715 0.991921 + outer loop + vertex 1.56965 1.29887 2.55102 + vertex 1.57312 1.30038 2.55119 + vertex 1.5688 1.30255 2.5515 + endloop + endfacet + facet normal 0.0192414 -0.10075 0.994726 + outer loop + vertex 1.57312 1.30038 2.55119 + vertex 1.57386 1.30435 2.55158 + vertex 1.5688 1.30255 2.5515 + endloop + endfacet + facet normal 0.0211067 -0.105958 0.994147 + outer loop + vertex 1.57386 1.30435 2.55158 + vertex 1.57293 1.30809 2.552 + vertex 1.5688 1.30255 2.5515 + endloop + endfacet + facet normal 0.0410473 -0.1206 0.991852 + outer loop + vertex 1.5688 1.30255 2.5515 + vertex 1.57293 1.30809 2.552 + vertex 1.56778 1.30788 2.55219 + endloop + endfacet + facet normal 0.0406412 -0.109583 0.993146 + outer loop + vertex 1.57293 1.30809 2.552 + vertex 1.57253 1.31296 2.55255 + vertex 1.56778 1.30788 2.55219 + endloop + endfacet + facet normal 0.00538029 -0.125309 0.992103 + outer loop + vertex 1.57149 1.29716 2.5508 + vertex 1.57312 1.30038 2.55119 + vertex 1.56965 1.29887 2.55102 + endloop + endfacet + facet normal 0.0961157 -0.128668 0.987019 + outer loop + vertex 1.57254 1.28297 2.54875 + vertex 1.57769 1.28805 2.54891 + vertex 1.57255 1.28808 2.54942 + endloop + endfacet + facet normal 0.0961537 -0.126614 0.987281 + outer loop + vertex 1.57769 1.28805 2.54891 + vertex 1.57778 1.29311 2.54956 + vertex 1.57255 1.28808 2.54942 + endloop + endfacet + facet normal 0.100359 -0.130951 0.986296 + outer loop + vertex 1.57255 1.28808 2.54942 + vertex 1.57778 1.29311 2.54956 + vertex 1.57208 1.29363 2.5502 + endloop + endfacet + facet normal 0.0983068 -0.150413 0.983723 + outer loop + vertex 1.57801 1.29811 2.5503 + vertex 1.57208 1.29363 2.5502 + vertex 1.57778 1.29311 2.54956 + endloop + endfacet + facet normal 0.151588 -0.220397 0.963559 + outer loop + vertex 1.57435 1.29768 2.55077 + vertex 1.57208 1.29363 2.5502 + vertex 1.57801 1.29811 2.5503 + endloop + endfacet + facet normal 0.149983 -0.202141 0.967804 + outer loop + vertex 1.57801 1.29811 2.5503 + vertex 1.57634 1.30004 2.55096 + vertex 1.57435 1.29768 2.55077 + endloop + endfacet + facet normal 0.0591537 -0.127363 0.990091 + outer loop + vertex 1.57634 1.30004 2.55096 + vertex 1.57312 1.30038 2.55119 + vertex 1.57435 1.29768 2.55077 + endloop + endfacet + facet normal 0.0332414 -0.139065 0.989725 + outer loop + vertex 1.57435 1.29768 2.55077 + vertex 1.57312 1.30038 2.55119 + vertex 1.57149 1.29716 2.5508 + endloop + endfacet + facet normal 0.0619296 -0.103057 0.992746 + outer loop + vertex 1.57634 1.30004 2.55096 + vertex 1.57675 1.30324 2.55127 + vertex 1.57312 1.30038 2.55119 + endloop + endfacet + facet normal 0.0668862 -0.109327 0.991753 + outer loop + vertex 1.57675 1.30324 2.55127 + vertex 1.57386 1.30435 2.55158 + vertex 1.57312 1.30038 2.55119 + endloop + endfacet + facet normal 0.078979 -0.0783585 0.993792 + outer loop + vertex 1.57675 1.30324 2.55127 + vertex 1.57762 1.30809 2.55158 + vertex 1.57386 1.30435 2.55158 + endloop + endfacet + facet normal 0.0369086 -0.159496 0.986508 + outer loop + vertex 1.57435 1.29768 2.55077 + vertex 1.57149 1.29716 2.5508 + vertex 1.57208 1.29363 2.5502 + endloop + endfacet + facet normal 0.0896151 -0.12211 0.988463 + outer loop + vertex 1.57753 1.28302 2.54831 + vertex 1.57769 1.28805 2.54891 + vertex 1.57254 1.28297 2.54875 + endloop + endfacet + facet normal 0.0310513 -0.131847 0.990784 + outer loop + vertex 1.57627 1.26219 2.54589 + vertex 1.57779 1.26545 2.54628 + vertex 1.57444 1.26382 2.54617 + endloop + endfacet + facet normal 0.0340377 -0.172292 0.984458 + outer loop + vertex 1.57564 1.23073 2.54093 + vertex 1.5768 1.22717 2.54027 + vertex 1.58016 1.23119 2.54085 + endloop + endfacet + facet normal 0.085933 -0.214018 0.973043 + outer loop + vertex 1.5768 1.22717 2.54027 + vertex 1.5824 1.22832 2.54002 + vertex 1.58016 1.23119 2.54085 + endloop + endfacet + facet normal 0.0773343 -0.170112 0.982386 + outer loop + vertex 1.5774 1.22289 2.53948 + vertex 1.5824 1.22832 2.54002 + vertex 1.5768 1.22717 2.54027 + endloop + endfacet + facet normal 0.0516807 -0.185666 0.981253 + outer loop + vertex 1.57272 1.20127 2.53567 + vertex 1.57193 1.20388 2.5362 + vertex 1.56957 1.20159 2.53589 + endloop + endfacet + facet normal 0.0386056 -0.195448 0.979954 + outer loop + vertex 1.57639 1.19669 2.53469 + vertex 1.57732 1.20086 2.53548 + vertex 1.57259 1.19739 2.53498 + endloop + endfacet + facet normal 0.0417896 -0.179193 0.982926 + outer loop + vertex 1.57234 1.1929 2.53417 + vertex 1.57639 1.19669 2.53469 + vertex 1.57259 1.19739 2.53498 + endloop + endfacet + facet normal 0.0440182 -0.181498 0.982406 + outer loop + vertex 1.57717 1.19295 2.53396 + vertex 1.57639 1.19669 2.53469 + vertex 1.57234 1.1929 2.53417 + endloop + endfacet + facet normal 0.0440032 -0.17605 0.983397 + outer loop + vertex 1.57236 1.18808 2.5333 + vertex 1.57717 1.19295 2.53396 + vertex 1.57234 1.1929 2.53417 + endloop + endfacet + facet normal 0.0807207 -0.175505 0.981164 + outer loop + vertex 1.57236 1.18808 2.5333 + vertex 1.57234 1.1929 2.53417 + vertex 1.56745 1.18825 2.53374 + endloop + endfacet + facet normal 0.0810943 -0.168004 0.982445 + outer loop + vertex 1.56739 1.18315 2.53287 + vertex 1.57236 1.18808 2.5333 + vertex 1.56745 1.18825 2.53374 + endloop + endfacet + facet normal 0.0837625 -0.170635 0.981767 + outer loop + vertex 1.5726 1.18315 2.53243 + vertex 1.57236 1.18808 2.5333 + vertex 1.56739 1.18315 2.53287 + endloop + endfacet + facet normal 0.0485375 -0.17268 0.983781 + outer loop + vertex 1.5726 1.18315 2.53243 + vertex 1.57747 1.18806 2.53305 + vertex 1.57236 1.18808 2.5333 + endloop + endfacet + facet normal 0.0494065 -0.17352 0.98359 + outer loop + vertex 1.57801 1.18334 2.53219 + vertex 1.57747 1.18806 2.53305 + vertex 1.5726 1.18315 2.53243 + endloop + endfacet + facet normal 0.0785033 -0.173229 0.981748 + outer loop + vertex 1.56745 1.18825 2.53374 + vertex 1.57234 1.1929 2.53417 + vertex 1.56777 1.19329 2.5346 + endloop + endfacet + facet normal 0.121172 -0.175097 0.977066 + outer loop + vertex 1.56745 1.18825 2.53374 + vertex 1.56777 1.19329 2.5346 + vertex 1.56267 1.18849 2.53438 + endloop + endfacet + facet normal 0.122058 -0.162888 0.979066 + outer loop + vertex 1.56241 1.18325 2.53354 + vertex 1.56745 1.18825 2.53374 + vertex 1.56267 1.18849 2.53438 + endloop + endfacet + facet normal 0.126924 -0.167737 0.977627 + outer loop + vertex 1.56739 1.18315 2.53287 + vertex 1.56745 1.18825 2.53374 + vertex 1.56241 1.18325 2.53354 + endloop + endfacet + facet normal 0.0484381 -0.180293 0.98242 + outer loop + vertex 1.57747 1.18806 2.53305 + vertex 1.57717 1.19295 2.53396 + vertex 1.57236 1.18808 2.5333 + endloop + endfacet + facet normal 0.0546757 -0.159338 0.985709 + outer loop + vertex 1.56957 1.20159 2.53589 + vertex 1.56822 1.19805 2.53539 + vertex 1.57272 1.20127 2.53567 + endloop + endfacet + facet normal 0.0777474 -0.180714 0.980458 + outer loop + vertex 1.57234 1.1929 2.53417 + vertex 1.57259 1.19739 2.53498 + vertex 1.56777 1.19329 2.5346 + endloop + endfacet + facet normal 0.115444 -0.169089 0.978816 + outer loop + vertex 1.56267 1.18849 2.53438 + vertex 1.56777 1.19329 2.5346 + vertex 1.56309 1.19357 2.5352 + endloop + endfacet + facet normal 0.131902 -0.169341 0.976691 + outer loop + vertex 1.56443 1.19741 2.53569 + vertex 1.56135 1.19545 2.53576 + vertex 1.56309 1.19357 2.5352 + endloop + endfacet + facet normal 0.0920606 -0.172894 0.980629 + outer loop + vertex 1.56957 1.20159 2.53589 + vertex 1.56661 1.2001 2.53591 + vertex 1.56822 1.19805 2.53539 + endloop + endfacet + facet normal 0.137704 -0.17854 0.974249 + outer loop + vertex 1.56443 1.19741 2.53569 + vertex 1.56256 1.19899 2.53624 + vertex 1.56135 1.19545 2.53576 + endloop + endfacet + facet normal 0.104131 -0.197005 0.974857 + outer loop + vertex 1.56957 1.20159 2.53589 + vertex 1.56779 1.2035 2.53647 + vertex 1.56661 1.2001 2.53591 + endloop + endfacet + facet normal 0.0627236 -0.191835 0.979421 + outer loop + vertex 1.57333 1.20775 2.53695 + vertex 1.56765 1.2081 2.53738 + vertex 1.56779 1.2035 2.53647 + endloop + endfacet + facet normal 0.0585523 -0.177583 0.982362 + outer loop + vertex 1.56765 1.2081 2.53738 + vertex 1.57266 1.21295 2.53796 + vertex 1.56745 1.21307 2.53829 + endloop + endfacet + facet normal 0.0859068 -0.162093 0.983029 + outer loop + vertex 1.56247 1.21322 2.53878 + vertex 1.56749 1.21814 2.53915 + vertex 1.56269 1.21838 2.53961 + endloop + endfacet + facet normal 0.0586854 -0.173708 0.983047 + outer loop + vertex 1.57266 1.21295 2.53796 + vertex 1.57246 1.21799 2.53886 + vertex 1.56745 1.21307 2.53829 + endloop + endfacet + facet normal 0.0678268 -0.13452 0.988587 + outer loop + vertex 1.56433 1.22692 2.54073 + vertex 1.56301 1.22327 2.54033 + vertex 1.56752 1.22684 2.5405 + endloop + endfacet + facet normal 0.0861692 -0.157977 0.983676 + outer loop + vertex 1.56749 1.21814 2.53915 + vertex 1.56757 1.22291 2.53991 + vertex 1.56269 1.21838 2.53961 + endloop + endfacet + facet normal 0.117864 -0.143634 0.982587 + outer loop + vertex 1.55924 1.22247 2.54066 + vertex 1.55802 1.21854 2.54023 + vertex 1.56301 1.22327 2.54033 + endloop + endfacet + facet normal 0.129456 -0.163172 0.978068 + outer loop + vertex 1.56247 1.21322 2.53878 + vertex 1.56269 1.21838 2.53961 + vertex 1.55768 1.21339 2.53944 + endloop + endfacet + facet normal 0.129327 -0.165361 0.977717 + outer loop + vertex 1.55748 1.20816 2.53858 + vertex 1.56247 1.21322 2.53878 + vertex 1.55768 1.21339 2.53944 + endloop + endfacet + facet normal 0.132786 -0.168733 0.976677 + outer loop + vertex 1.56245 1.20811 2.5379 + vertex 1.56247 1.21322 2.53878 + vertex 1.55748 1.20816 2.53858 + endloop + endfacet + facet normal 0.132846 -0.166965 0.976972 + outer loop + vertex 1.55746 1.20314 2.53773 + vertex 1.56245 1.20811 2.5379 + vertex 1.55748 1.20816 2.53858 + endloop + endfacet + facet normal 0.166294 -0.166227 0.971964 + outer loop + vertex 1.55746 1.20314 2.53773 + vertex 1.55748 1.20816 2.53858 + vertex 1.55248 1.20309 2.53857 + endloop + endfacet + facet normal 0.166357 -0.162799 0.972534 + outer loop + vertex 1.55242 1.19813 2.53775 + vertex 1.55746 1.20314 2.53773 + vertex 1.55248 1.20309 2.53857 + endloop + endfacet + facet normal 0.189252 -0.162416 0.968403 + outer loop + vertex 1.55242 1.19813 2.53775 + vertex 1.55248 1.20309 2.53857 + vertex 1.54738 1.19794 2.5387 + endloop + endfacet + facet normal 0.189215 -0.15573 0.969508 + outer loop + vertex 1.54729 1.19298 2.53792 + vertex 1.55242 1.19813 2.53775 + vertex 1.54738 1.19794 2.5387 + endloop + endfacet + facet normal 0.180194 -0.155839 0.971208 + outer loop + vertex 1.54729 1.19298 2.53792 + vertex 1.54738 1.19794 2.5387 + vertex 1.54227 1.19267 2.53881 + endloop + endfacet + facet normal 0.179761 -0.14254 0.973328 + outer loop + vertex 1.54227 1.18772 2.53808 + vertex 1.54729 1.19298 2.53792 + vertex 1.54227 1.19267 2.53881 + endloop + endfacet + facet normal 0.0841885 -0.14443 0.985927 + outer loop + vertex 1.54227 1.18772 2.53808 + vertex 1.54227 1.19267 2.53881 + vertex 1.5376 1.18758 2.53846 + endloop + endfacet + facet normal 0.179429 -0.155091 0.971469 + outer loop + vertex 1.54227 1.19267 2.53881 + vertex 1.54738 1.19794 2.5387 + vertex 1.54249 1.1979 2.5396 + endloop + endfacet + facet normal 0.198478 -0.165077 0.966104 + outer loop + vertex 1.55238 1.19351 2.53697 + vertex 1.55242 1.19813 2.53775 + vertex 1.54729 1.19298 2.53792 + endloop + endfacet + facet normal 0.198212 -0.161287 0.966798 + outer loop + vertex 1.54728 1.18836 2.53715 + vertex 1.55238 1.19351 2.53697 + vertex 1.54729 1.19298 2.53792 + endloop + endfacet + facet normal 0.213368 -0.17649 0.960898 + outer loop + vertex 1.55227 1.18912 2.53619 + vertex 1.55238 1.19351 2.53697 + vertex 1.54728 1.18836 2.53715 + endloop + endfacet + facet normal 0.171277 -0.165717 0.971186 + outer loop + vertex 1.55238 1.19351 2.53697 + vertex 1.55749 1.1985 2.53692 + vertex 1.55242 1.19813 2.53775 + endloop + endfacet + facet normal 0.178706 -0.17335 0.968511 + outer loop + vertex 1.55737 1.19414 2.53616 + vertex 1.55749 1.1985 2.53692 + vertex 1.55238 1.19351 2.53697 + endloop + endfacet + facet normal 0.146703 -0.173418 0.973861 + outer loop + vertex 1.56256 1.19899 2.53624 + vertex 1.55749 1.1985 2.53692 + vertex 1.55737 1.19414 2.53616 + endloop + endfacet + facet normal 0.147003 -0.177608 0.97306 + outer loop + vertex 1.56256 1.19899 2.53624 + vertex 1.56257 1.20336 2.53704 + vertex 1.55749 1.1985 2.53692 + endloop + endfacet + facet normal 0.138636 -0.168927 0.97583 + outer loop + vertex 1.55749 1.1985 2.53692 + vertex 1.56257 1.20336 2.53704 + vertex 1.55746 1.20314 2.53773 + endloop + endfacet + facet normal 0.18537 -0.158531 0.969797 + outer loop + vertex 1.54738 1.19794 2.5387 + vertex 1.55248 1.20309 2.53857 + vertex 1.54764 1.20314 2.5395 + endloop + endfacet + facet normal 0.171373 -0.167854 0.970802 + outer loop + vertex 1.55749 1.1985 2.53692 + vertex 1.55746 1.20314 2.53773 + vertex 1.55242 1.19813 2.53775 + endloop + endfacet + facet normal 0.16301 -0.162994 0.973068 + outer loop + vertex 1.55248 1.20309 2.53857 + vertex 1.55748 1.20816 2.53858 + vertex 1.5527 1.20829 2.5394 + endloop + endfacet + facet normal 0.138708 -0.172782 0.975144 + outer loop + vertex 1.56257 1.20336 2.53704 + vertex 1.56245 1.20811 2.5379 + vertex 1.55746 1.20314 2.53773 + endloop + endfacet + facet normal 0.154633 -0.156258 0.975537 + outer loop + vertex 1.55423 1.21743 2.54066 + vertex 1.55305 1.21345 2.54021 + vertex 1.55802 1.21854 2.54023 + endloop + endfacet + facet normal 0.162855 -0.165827 0.972615 + outer loop + vertex 1.55748 1.20816 2.53858 + vertex 1.55768 1.21339 2.53944 + vertex 1.5527 1.20829 2.5394 + endloop + endfacet + facet normal 0.17523 -0.156531 0.972005 + outer loop + vertex 1.5493 1.2123 2.5407 + vertex 1.54806 1.20832 2.54028 + vertex 1.55305 1.21345 2.54021 + endloop + endfacet + facet normal 0.185176 -0.163276 0.969046 + outer loop + vertex 1.55248 1.20309 2.53857 + vertex 1.5527 1.20829 2.5394 + vertex 1.54764 1.20314 2.5395 + endloop + endfacet + facet normal 0.196173 -0.165321 0.966533 + outer loop + vertex 1.54425 1.20718 2.54086 + vertex 1.54292 1.20313 2.54043 + vertex 1.54806 1.20832 2.54028 + endloop + endfacet + facet normal 0.179363 -0.158406 0.970946 + outer loop + vertex 1.54738 1.19794 2.5387 + vertex 1.54764 1.20314 2.5395 + vertex 1.54249 1.1979 2.5396 + endloop + endfacet + facet normal 0.209174 -0.231244 0.950143 + outer loop + vertex 1.53913 1.20199 2.54099 + vertex 1.53788 1.198 2.5403 + vertex 1.54292 1.20313 2.54043 + endloop + endfacet + facet normal 0.0886942 -0.153253 0.984199 + outer loop + vertex 1.54227 1.19267 2.53881 + vertex 1.54249 1.1979 2.5396 + vertex 1.5376 1.19278 2.53924 + endloop + endfacet + facet normal 0.117605 -0.392525 0.912191 + outer loop + vertex 1.53455 1.19736 2.54045 + vertex 1.5335 1.19364 2.53899 + vertex 1.53788 1.198 2.5403 + endloop + endfacet + facet normal 0.0888587 -0.148639 0.984891 + outer loop + vertex 1.5376 1.18758 2.53846 + vertex 1.54227 1.19267 2.53881 + vertex 1.5376 1.19278 2.53924 + endloop + endfacet + facet normal 0.141719 -0.165464 0.97598 + outer loop + vertex 1.54244 1.17889 2.53662 + vertex 1.5424 1.18316 2.53735 + vertex 1.53819 1.17841 2.53715 + endloop + endfacet + facet normal 0.140179 -0.148478 0.97893 + outer loop + vertex 1.54244 1.17889 2.53662 + vertex 1.53819 1.17841 2.53715 + vertex 1.53851 1.17483 2.53656 + endloop + endfacet + facet normal 0.131208 -0.1398 0.981448 + outer loop + vertex 1.54128 1.17526 2.53625 + vertex 1.54244 1.17889 2.53662 + vertex 1.53851 1.17483 2.53656 + endloop + endfacet + facet normal 0.137818 -0.190198 0.972024 + outer loop + vertex 1.54128 1.17526 2.53625 + vertex 1.53851 1.17483 2.53656 + vertex 1.53925 1.17256 2.53602 + endloop + endfacet + facet normal 0.178641 -0.219844 0.959039 + outer loop + vertex 1.54286 1.17336 2.53553 + vertex 1.54128 1.17526 2.53625 + vertex 1.53925 1.17256 2.53602 + endloop + endfacet + facet normal 0.19518 -0.312187 0.929755 + outer loop + vertex 1.53925 1.17256 2.53602 + vertex 1.53853 1.16912 2.53501 + vertex 1.54286 1.17336 2.53553 + endloop + endfacet + facet normal 0.0558646 -0.176444 0.982724 + outer loop + vertex 1.54286 1.17336 2.53553 + vertex 1.53853 1.16912 2.53501 + vertex 1.54246 1.16825 2.53463 + endloop + endfacet + facet normal -0.036666 -0.272677 0.961407 + outer loop + vertex 1.53925 1.17256 2.53602 + vertex 1.5363 1.17119 2.53551 + vertex 1.53853 1.16912 2.53501 + endloop + endfacet + facet normal -0.0481842 -0.249906 0.967071 + outer loop + vertex 1.53925 1.17256 2.53602 + vertex 1.53851 1.17483 2.53656 + vertex 1.5363 1.17119 2.53551 + endloop + endfacet + facet normal 0.0839039 -0.128841 0.988109 + outer loop + vertex 1.53783 1.18273 2.53781 + vertex 1.54227 1.18772 2.53808 + vertex 1.5376 1.18758 2.53846 + endloop + endfacet + facet normal 0.199167 -0.161257 0.966607 + outer loop + vertex 1.54728 1.18836 2.53715 + vertex 1.54729 1.19298 2.53792 + vertex 1.54227 1.18772 2.53808 + endloop + endfacet + facet normal 0.213142 -0.174484 0.961315 + outer loop + vertex 1.55227 1.18912 2.53619 + vertex 1.54728 1.18836 2.53715 + vertex 1.54726 1.18396 2.53636 + endloop + endfacet + facet normal 0.225902 -0.187043 0.956025 + outer loop + vertex 1.55116 1.18542 2.53573 + vertex 1.55227 1.18912 2.53619 + vertex 1.54726 1.18396 2.53636 + endloop + endfacet + facet normal 0.179034 -0.176878 0.967812 + outer loop + vertex 1.55737 1.19414 2.53616 + vertex 1.55238 1.19351 2.53697 + vertex 1.55227 1.18912 2.53619 + endloop + endfacet + facet normal 0.157283 -0.184662 0.970135 + outer loop + vertex 1.56135 1.19545 2.53576 + vertex 1.56256 1.19899 2.53624 + vertex 1.55737 1.19414 2.53616 + endloop + endfacet + facet normal 0.151314 -0.165991 0.974449 + outer loop + vertex 1.55918 1.19256 2.53558 + vertex 1.55617 1.19049 2.53569 + vertex 1.55793 1.18863 2.5351 + endloop + endfacet + facet normal 0.154032 -0.163681 0.974414 + outer loop + vertex 1.56241 1.18325 2.53354 + vertex 1.56267 1.18849 2.53438 + vertex 1.5576 1.18343 2.53433 + endloop + endfacet + facet normal 0.155286 -0.143341 0.977415 + outer loop + vertex 1.55741 1.17817 2.53358 + vertex 1.56241 1.18325 2.53354 + vertex 1.5576 1.18343 2.53433 + endloop + endfacet + facet normal 0.16277 -0.150726 0.975083 + outer loop + vertex 1.56241 1.17815 2.53275 + vertex 1.56241 1.18325 2.53354 + vertex 1.55741 1.17817 2.53358 + endloop + endfacet + facet normal 0.163277 -0.132328 0.977666 + outer loop + vertex 1.55744 1.1731 2.53289 + vertex 1.56241 1.17815 2.53275 + vertex 1.55741 1.17817 2.53358 + endloop + endfacet + facet normal 0.180475 -0.131824 0.974706 + outer loop + vertex 1.55744 1.1731 2.53289 + vertex 1.55741 1.17817 2.53358 + vertex 1.55239 1.17307 2.53383 + endloop + endfacet + facet normal 0.180622 -0.123538 0.975763 + outer loop + vertex 1.55242 1.168 2.53318 + vertex 1.55744 1.1731 2.53289 + vertex 1.55239 1.17307 2.53383 + endloop + endfacet + facet normal 0.174343 -0.125686 0.976631 + outer loop + vertex 1.55239 1.17307 2.53383 + vertex 1.55741 1.17817 2.53358 + vertex 1.55258 1.17831 2.53447 + endloop + endfacet + facet normal 0.169502 -0.138512 0.975748 + outer loop + vertex 1.56257 1.17338 2.53204 + vertex 1.56241 1.17815 2.53275 + vertex 1.55744 1.1731 2.53289 + endloop + endfacet + facet normal 0.132575 -0.140563 0.981156 + outer loop + vertex 1.56257 1.17338 2.53204 + vertex 1.5676 1.17829 2.53207 + vertex 1.56241 1.17815 2.53275 + endloop + endfacet + facet normal 0.127601 -0.15149 0.980188 + outer loop + vertex 1.56241 1.17815 2.53275 + vertex 1.56739 1.18315 2.53287 + vertex 1.56241 1.18325 2.53354 + endloop + endfacet + facet normal 0.132683 -0.156515 0.978723 + outer loop + vertex 1.5676 1.17829 2.53207 + vertex 1.56739 1.18315 2.53287 + vertex 1.56241 1.17815 2.53275 + endloop + endfacet + facet normal 0.151055 -0.143993 0.977982 + outer loop + vertex 1.55409 1.18755 2.53553 + vertex 1.55291 1.18354 2.53513 + vertex 1.55793 1.18863 2.5351 + endloop + endfacet + facet normal 0.173383 -0.143538 0.974338 + outer loop + vertex 1.55741 1.17817 2.53358 + vertex 1.5576 1.18343 2.53433 + vertex 1.55258 1.17831 2.53447 + endloop + endfacet + facet normal 0.174031 -0.131314 0.975946 + outer loop + vertex 1.54911 1.1824 2.53565 + vertex 1.54787 1.17837 2.53533 + vertex 1.55291 1.18354 2.53513 + endloop + endfacet + facet normal 0.170859 -0.125636 0.977253 + outer loop + vertex 1.55239 1.17307 2.53383 + vertex 1.55258 1.17831 2.53447 + vertex 1.5475 1.17321 2.5347 + endloop + endfacet + facet normal 0.21339 -0.175806 0.961019 + outer loop + vertex 1.54408 1.1772 2.53596 + vertex 1.54286 1.17336 2.53553 + vertex 1.54787 1.17837 2.53533 + endloop + endfacet + facet normal 0.170732 -0.128201 0.976942 + outer loop + vertex 1.54729 1.16798 2.53405 + vertex 1.55239 1.17307 2.53383 + vertex 1.5475 1.17321 2.5347 + endloop + endfacet + facet normal 0.166536 -0.123944 0.978215 + outer loop + vertex 1.55242 1.168 2.53318 + vertex 1.55239 1.17307 2.53383 + vertex 1.54729 1.16798 2.53405 + endloop + endfacet + facet normal 0.185935 -0.128869 0.974074 + outer loop + vertex 1.55761 1.16833 2.53223 + vertex 1.55744 1.1731 2.53289 + vertex 1.55242 1.168 2.53318 + endloop + endfacet + facet normal 0.169228 -0.129877 0.976982 + outer loop + vertex 1.55761 1.16833 2.53223 + vertex 1.56257 1.17338 2.53204 + vertex 1.55744 1.1731 2.53289 + endloop + endfacet + facet normal 0.145394 -0.153704 0.977362 + outer loop + vertex 1.56773 1.17375 2.53133 + vertex 1.5676 1.17829 2.53207 + vertex 1.56257 1.17338 2.53204 + endloop + endfacet + facet normal 0.171999 -0.150557 0.973524 + outer loop + vertex 1.56454 1.1673 2.53085 + vertex 1.56167 1.16514 2.53102 + vertex 1.56335 1.16333 2.53044 + endloop + endfacet + facet normal 0.191869 -0.176629 0.965395 + outer loop + vertex 1.55969 1.16211 2.5309 + vertex 1.5568 1.15995 2.53107 + vertex 1.55842 1.15818 2.53043 + endloop + endfacet + facet normal 0.167581 -0.17573 0.97007 + outer loop + vertex 1.56248 1.15314 2.5288 + vertex 1.56285 1.15827 2.52967 + vertex 1.55781 1.15315 2.52961 + endloop + endfacet + facet normal 0.19015 -0.184485 0.964266 + outer loop + vertex 1.55473 1.15699 2.53093 + vertex 1.55329 1.15309 2.53047 + vertex 1.55842 1.15818 2.53043 + endloop + endfacet + facet normal 0.181425 -0.182587 0.966306 + outer loop + vertex 1.55746 1.14808 2.52872 + vertex 1.55781 1.15315 2.52961 + vertex 1.55264 1.14807 2.52962 + endloop + endfacet + facet normal 0.18109 -0.192901 0.964363 + outer loop + vertex 1.5524 1.14311 2.52867 + vertex 1.55746 1.14808 2.52872 + vertex 1.55264 1.14807 2.52962 + endloop + endfacet + facet normal 0.215239 -0.196786 0.956529 + outer loop + vertex 1.54944 1.15191 2.53109 + vertex 1.54797 1.14796 2.53061 + vertex 1.55329 1.15309 2.53047 + endloop + endfacet + facet normal 0.18127 -0.192903 0.964329 + outer loop + vertex 1.5524 1.14311 2.52867 + vertex 1.55264 1.14807 2.52962 + vertex 1.54758 1.14303 2.52957 + endloop + endfacet + facet normal 0.153411 -0.20375 0.966928 + outer loop + vertex 1.55263 1.13383 2.52669 + vertex 1.55252 1.13838 2.52767 + vertex 1.54769 1.13373 2.52746 + endloop + endfacet + facet normal 0.180763 -0.214648 0.959818 + outer loop + vertex 1.54762 1.13832 2.5285 + vertex 1.5524 1.14311 2.52867 + vertex 1.54758 1.14303 2.52957 + endloop + endfacet + facet normal 0.177755 -0.189519 0.965653 + outer loop + vertex 1.55757 1.14321 2.52774 + vertex 1.55746 1.14808 2.52872 + vertex 1.5524 1.14311 2.52867 + endloop + endfacet + facet normal 0.17045 -0.192285 0.966423 + outer loop + vertex 1.56309 1.14344 2.52681 + vertex 1.56253 1.1482 2.52786 + vertex 1.55757 1.14321 2.52774 + endloop + endfacet + facet normal 0.165242 -0.205309 0.964647 + outer loop + vertex 1.56836 1.14514 2.52627 + vertex 1.56309 1.14344 2.52681 + vertex 1.5656 1.14114 2.5259 + endloop + endfacet + facet normal 0.169631 -0.208392 0.963223 + outer loop + vertex 1.56278 1.13709 2.52551 + vertex 1.56192 1.13942 2.52617 + vertex 1.55968 1.13668 2.52597 + endloop + endfacet + facet normal 0.165057 -0.206832 0.964353 + outer loop + vertex 1.56929 1.14286 2.52563 + vertex 1.5656 1.14114 2.5259 + vertex 1.5677 1.13858 2.52498 + endloop + endfacet + facet normal 0.16805 -0.207408 0.963712 + outer loop + vertex 1.56759 1.1334 2.52389 + vertex 1.5677 1.13858 2.52498 + vertex 1.56281 1.13314 2.52467 + endloop + endfacet + facet normal 0.168574 -0.197474 0.965705 + outer loop + vertex 1.55968 1.13668 2.52597 + vertex 1.55831 1.13298 2.52545 + vertex 1.56278 1.13709 2.52551 + endloop + endfacet + facet normal 0.181994 -0.200749 0.962589 + outer loop + vertex 1.56256 1.12824 2.52369 + vertex 1.56281 1.13314 2.52467 + vertex 1.55774 1.12812 2.52458 + endloop + endfacet + facet normal 0.17948 -0.18974 0.96529 + outer loop + vertex 1.55454 1.13207 2.52597 + vertex 1.55306 1.12809 2.52547 + vertex 1.55831 1.13298 2.52545 + endloop + endfacet + facet normal 0.17919 -0.19424 0.964449 + outer loop + vertex 1.55743 1.12309 2.52362 + vertex 1.55774 1.12812 2.52458 + vertex 1.55252 1.12296 2.52451 + endloop + endfacet + facet normal 0.179182 -0.19519 0.964259 + outer loop + vertex 1.55242 1.11798 2.52352 + vertex 1.55743 1.12309 2.52362 + vertex 1.55252 1.12296 2.52451 + endloop + endfacet + facet normal 0.195707 -0.244392 0.949722 + outer loop + vertex 1.54915 1.12707 2.52601 + vertex 1.54788 1.12305 2.52524 + vertex 1.55306 1.12809 2.52547 + endloop + endfacet + facet normal 0.12994 -0.410485 0.902562 + outer loop + vertex 1.54442 1.12245 2.52546 + vertex 1.54358 1.11869 2.52387 + vertex 1.54788 1.12305 2.52524 + endloop + endfacet + facet normal 0.102378 -0.195843 0.975276 + outer loop + vertex 1.55242 1.11798 2.52352 + vertex 1.55252 1.12296 2.52451 + vertex 1.54774 1.11793 2.524 + endloop + endfacet + facet normal 0.183362 -0.199246 0.962642 + outer loop + vertex 1.55751 1.11833 2.52262 + vertex 1.55743 1.12309 2.52362 + vertex 1.55242 1.11798 2.52352 + endloop + endfacet + facet normal 0.192405 -0.205183 0.959625 + outer loop + vertex 1.56273 1.11862 2.52164 + vertex 1.56259 1.12332 2.52267 + vertex 1.55751 1.11833 2.52262 + endloop + endfacet + facet normal 0.173675 -0.206459 0.962918 + outer loop + vertex 1.56802 1.1236 2.52175 + vertex 1.56259 1.12332 2.52267 + vertex 1.56273 1.11862 2.52164 + endloop + endfacet + facet normal 0.162714 -0.209104 0.964261 + outer loop + vertex 1.57328 1.1253 2.52123 + vertex 1.56802 1.1236 2.52175 + vertex 1.57046 1.12126 2.52083 + endloop + endfacet + facet normal 0.168809 -0.212319 0.962509 + outer loop + vertex 1.56762 1.11713 2.52042 + vertex 1.56676 1.1195 2.5211 + vertex 1.5645 1.11671 2.52088 + endloop + endfacet + facet normal 0.162463 -0.213977 0.963234 + outer loop + vertex 1.57261 1.11346 2.51876 + vertex 1.57261 1.11864 2.51991 + vertex 1.56774 1.11318 2.51952 + endloop + endfacet + facet normal 0.168864 -0.212865 0.962379 + outer loop + vertex 1.5645 1.11671 2.52088 + vertex 1.56317 1.11302 2.52029 + vertex 1.56762 1.11713 2.52042 + endloop + endfacet + facet normal 0.172996 -0.215085 0.961151 + outer loop + vertex 1.56768 1.10835 2.51845 + vertex 1.56774 1.11318 2.51952 + vertex 1.56277 1.10823 2.51931 + endloop + endfacet + facet normal 0.180638 -0.211679 0.960501 + outer loop + vertex 1.55947 1.11219 2.52081 + vertex 1.55795 1.10831 2.52024 + vertex 1.56317 1.11302 2.52029 + endloop + endfacet + facet normal 0.176157 -0.21547 0.96049 + outer loop + vertex 1.56273 1.10332 2.51821 + vertex 1.56277 1.10823 2.51931 + vertex 1.55757 1.10328 2.51915 + endloop + endfacet + facet normal 0.20636 -0.220685 0.953265 + outer loop + vertex 1.55947 1.11219 2.52081 + vertex 1.55646 1.11041 2.52104 + vertex 1.55795 1.10831 2.52024 + endloop + endfacet + facet normal 0.206429 -0.223338 0.952632 + outer loop + vertex 1.55646 1.11041 2.52104 + vertex 1.55769 1.11398 2.52161 + vertex 1.55318 1.11001 2.52166 + endloop + endfacet + facet normal 0.13423 -0.222381 0.965675 + outer loop + vertex 1.55318 1.11001 2.52166 + vertex 1.55278 1.11358 2.52254 + vertex 1.54887 1.10922 2.52208 + endloop + endfacet + facet normal 0.160151 -0.255179 0.953538 + outer loop + vertex 1.55392 1.10757 2.52091 + vertex 1.55004 1.10605 2.52116 + vertex 1.5524 1.10339 2.52005 + endloop + endfacet + facet normal 0.16153 -0.241615 0.956834 + outer loop + vertex 1.55259 1.09841 2.51876 + vertex 1.55757 1.10328 2.51915 + vertex 1.5524 1.10339 2.52005 + endloop + endfacet + facet normal 0.14154 -0.222028 0.964712 + outer loop + vertex 1.5527 1.0935 2.51761 + vertex 1.55766 1.09835 2.518 + vertex 1.55259 1.09841 2.51876 + endloop + endfacet + facet normal 0.136231 -0.216745 0.966676 + outer loop + vertex 1.55774 1.09359 2.51692 + vertex 1.55766 1.09835 2.518 + vertex 1.5527 1.0935 2.51761 + endloop + endfacet + facet normal 0.136627 -0.179503 0.974224 + outer loop + vertex 1.55774 1.09359 2.51692 + vertex 1.5527 1.0935 2.51761 + vertex 1.55276 1.08886 2.51675 + endloop + endfacet + facet normal 0.151711 -0.195204 0.968958 + outer loop + vertex 1.55644 1.08984 2.51637 + vertex 1.55774 1.09359 2.51692 + vertex 1.55276 1.08886 2.51675 + endloop + endfacet + facet normal 0.175984 -0.214734 0.960687 + outer loop + vertex 1.56319 1.09844 2.51701 + vertex 1.55766 1.09835 2.518 + vertex 1.55774 1.09359 2.51692 + endloop + endfacet + facet normal 0.173292 -0.230717 0.957465 + outer loop + vertex 1.5685 1.09998 2.51642 + vertex 1.56319 1.09844 2.51701 + vertex 1.56565 1.09602 2.51598 + endloop + endfacet + facet normal 0.188355 -0.218935 0.957387 + outer loop + vertex 1.56263 1.09199 2.51559 + vertex 1.56186 1.09441 2.51629 + vertex 1.55943 1.09164 2.51614 + endloop + endfacet + facet normal 0.179241 -0.22623 0.957441 + outer loop + vertex 1.56759 1.08834 2.51382 + vertex 1.56771 1.09344 2.51501 + vertex 1.56261 1.08801 2.51468 + endloop + endfacet + facet normal 0.188125 -0.215528 0.958205 + outer loop + vertex 1.55943 1.09164 2.51614 + vertex 1.55797 1.08785 2.51557 + vertex 1.56263 1.09199 2.51559 + endloop + endfacet + facet normal 0.181933 -0.225825 0.957029 + outer loop + vertex 1.56249 1.08324 2.51357 + vertex 1.56261 1.08801 2.51468 + vertex 1.55763 1.08303 2.51445 + endloop + endfacet + facet normal 0.221279 -0.293457 0.93001 + outer loop + vertex 1.55423 1.08693 2.51617 + vertex 1.55305 1.08305 2.51523 + vertex 1.55797 1.08785 2.51557 + endloop + endfacet + facet normal 0.181932 -0.233366 0.955218 + outer loop + vertex 1.55778 1.07836 2.51328 + vertex 1.56249 1.08324 2.51357 + vertex 1.55763 1.08303 2.51445 + endloop + endfacet + facet normal 0.1772 -0.2289 0.957186 + outer loop + vertex 1.55807 1.07371 2.51211 + vertex 1.56269 1.07868 2.51245 + vertex 1.55778 1.07836 2.51328 + endloop + endfacet + facet normal 0.18034 -0.226251 0.957229 + outer loop + vertex 1.56322 1.07497 2.51144 + vertex 1.55807 1.07371 2.51211 + vertex 1.56019 1.07093 2.51106 + endloop + endfacet + facet normal 0.125047 -0.297332 0.94655 + outer loop + vertex 1.55714 1.06715 2.51054 + vertex 1.55642 1.0697 2.51143 + vertex 1.55407 1.06749 2.51105 + endloop + endfacet + facet normal 0.191708 -0.23997 0.951663 + outer loop + vertex 1.56413 1.07256 2.51067 + vertex 1.56019 1.07093 2.51106 + vertex 1.56241 1.06832 2.50995 + endloop + endfacet + facet normal 0.117885 -0.239969 0.963596 + outer loop + vertex 1.56251 1.0633 2.50869 + vertex 1.56241 1.06832 2.50995 + vertex 1.55745 1.06325 2.50929 + endloop + endfacet + facet normal 0.0970147 -0.457591 0.883855 + outer loop + vertex 1.55407 1.06749 2.51105 + vertex 1.55288 1.06442 2.50959 + vertex 1.55714 1.06715 2.51054 + endloop + endfacet + facet normal 0.117989 -0.234236 0.964993 + outer loop + vertex 1.55781 1.05846 2.50809 + vertex 1.56251 1.0633 2.50869 + vertex 1.55745 1.06325 2.50929 + endloop + endfacet + facet normal 0.178589 -0.238461 0.95459 + outer loop + vertex 1.56762 1.06353 2.50779 + vertex 1.56763 1.06832 2.50898 + vertex 1.56251 1.0633 2.50869 + endloop + endfacet + facet normal 0.180511 -0.238382 0.954248 + outer loop + vertex 1.56762 1.06353 2.50779 + vertex 1.57266 1.06851 2.50808 + vertex 1.56763 1.06832 2.50898 + endloop + endfacet + facet normal 0.169615 -0.241758 0.955397 + outer loop + vertex 1.57775 1.06898 2.50729 + vertex 1.57769 1.07353 2.50846 + vertex 1.57266 1.06851 2.50808 + endloop + endfacet + facet normal 0.145282 -0.243051 0.959072 + outer loop + vertex 1.57775 1.06898 2.50729 + vertex 1.58273 1.07372 2.50774 + vertex 1.57769 1.07353 2.50846 + endloop + endfacet + facet normal 0.111006 -0.254748 0.960615 + outer loop + vertex 1.58821 1.07359 2.50707 + vertex 1.5877 1.07837 2.5084 + vertex 1.58273 1.07372 2.50774 + endloop + endfacet + facet normal 0.085107 -0.273181 0.95819 + outer loop + vertex 1.5907 1.07062 2.50601 + vertex 1.58821 1.07359 2.50707 + vertex 1.58671 1.06965 2.50608 + endloop + endfacet + facet normal 0.081755 -0.259107 0.962382 + outer loop + vertex 1.58671 1.06965 2.50608 + vertex 1.58741 1.06702 2.50532 + vertex 1.5907 1.07062 2.50601 + endloop + endfacet + facet normal 0.0777709 -0.255701 0.963623 + outer loop + vertex 1.58741 1.06702 2.50532 + vertex 1.59183 1.06716 2.505 + vertex 1.5907 1.07062 2.50601 + endloop + endfacet + facet normal 0.0776061 -0.243549 0.966779 + outer loop + vertex 1.58757 1.06313 2.50432 + vertex 1.59183 1.06716 2.505 + vertex 1.58741 1.06702 2.50532 + endloop + endfacet + facet normal 0.084382 -0.250326 0.964477 + outer loop + vertex 1.59247 1.0631 2.50389 + vertex 1.59183 1.06716 2.505 + vertex 1.58757 1.06313 2.50432 + endloop + endfacet + facet normal 0.0844115 -0.249314 0.964737 + outer loop + vertex 1.58782 1.05866 2.50315 + vertex 1.59247 1.0631 2.50389 + vertex 1.58757 1.06313 2.50432 + endloop + endfacet + facet normal 0.133001 -0.245434 0.960246 + outer loop + vertex 1.58782 1.05866 2.50315 + vertex 1.58757 1.06313 2.50432 + vertex 1.58274 1.05861 2.50384 + endloop + endfacet + facet normal 0.132981 -0.246234 0.960044 + outer loop + vertex 1.58298 1.05391 2.5026 + vertex 1.58782 1.05866 2.50315 + vertex 1.58274 1.05861 2.50384 + endloop + endfacet + facet normal 0.156754 -0.244186 0.956975 + outer loop + vertex 1.58298 1.05391 2.5026 + vertex 1.58274 1.05861 2.50384 + vertex 1.57777 1.0536 2.50337 + endloop + endfacet + facet normal 0.156688 -0.241237 0.957733 + outer loop + vertex 1.57815 1.04861 2.50206 + vertex 1.58298 1.05391 2.5026 + vertex 1.57777 1.0536 2.50337 + endloop + endfacet + facet normal 0.162867 -0.240541 0.956877 + outer loop + vertex 1.57815 1.04861 2.50206 + vertex 1.57777 1.0536 2.50337 + vertex 1.57282 1.04861 2.50296 + endloop + endfacet + facet normal 0.162751 -0.243321 0.956194 + outer loop + vertex 1.57815 1.04861 2.50206 + vertex 1.57282 1.04861 2.50296 + vertex 1.5729 1.04395 2.50176 + endloop + endfacet + facet normal 0.160536 -0.240892 0.957183 + outer loop + vertex 1.57672 1.04448 2.50125 + vertex 1.57815 1.04861 2.50206 + vertex 1.5729 1.04395 2.50176 + endloop + endfacet + facet normal 0.161239 -0.247798 0.9553 + outer loop + vertex 1.57672 1.04448 2.50125 + vertex 1.5729 1.04395 2.50176 + vertex 1.57441 1.0418 2.50095 + endloop + endfacet + facet normal 0.166773 -0.252337 0.953159 + outer loop + vertex 1.57752 1.04203 2.50047 + vertex 1.57672 1.04448 2.50125 + vertex 1.57441 1.0418 2.50095 + endloop + endfacet + facet normal 0.167053 -0.261497 0.950638 + outer loop + vertex 1.57441 1.0418 2.50095 + vertex 1.57302 1.03815 2.50019 + vertex 1.57752 1.04203 2.50047 + endloop + endfacet + facet normal 0.166662 -0.261058 0.950827 + outer loop + vertex 1.57752 1.04203 2.50047 + vertex 1.57302 1.03815 2.50019 + vertex 1.57773 1.0382 2.49938 + endloop + endfacet + facet normal 0.170507 -0.26068 0.950249 + outer loop + vertex 1.57773 1.0382 2.49938 + vertex 1.58254 1.04338 2.49994 + vertex 1.57752 1.04203 2.50047 + endloop + endfacet + facet normal 0.168311 -0.251314 0.953159 + outer loop + vertex 1.57752 1.04203 2.50047 + vertex 1.58254 1.04338 2.49994 + vertex 1.58045 1.04601 2.501 + endloop + endfacet + facet normal 0.168538 -0.251136 0.953166 + outer loop + vertex 1.58413 1.04746 2.50073 + vertex 1.58045 1.04601 2.501 + vertex 1.58254 1.04338 2.49994 + endloop + endfacet + facet normal 0.153004 -0.245843 0.957158 + outer loop + vertex 1.58413 1.04746 2.50073 + vertex 1.58254 1.04338 2.49994 + vertex 1.58733 1.04747 2.50022 + endloop + endfacet + facet normal 0.153097 -0.243175 0.957824 + outer loop + vertex 1.58733 1.04747 2.50022 + vertex 1.58673 1.05014 2.501 + vertex 1.58413 1.04746 2.50073 + endloop + endfacet + facet normal 0.160695 -0.250216 0.954761 + outer loop + vertex 1.58673 1.05014 2.501 + vertex 1.58345 1.05003 2.50152 + vertex 1.58413 1.04746 2.50073 + endloop + endfacet + facet normal 0.160496 -0.270404 0.949275 + outer loop + vertex 1.58673 1.05014 2.501 + vertex 1.58824 1.05403 2.50185 + vertex 1.58345 1.05003 2.50152 + endloop + endfacet + facet normal 0.142618 -0.249677 0.957769 + outer loop + vertex 1.58824 1.05403 2.50185 + vertex 1.58298 1.05391 2.5026 + vertex 1.58345 1.05003 2.50152 + endloop + endfacet + facet normal 0.135513 -0.262043 0.955494 + outer loop + vertex 1.59038 1.05135 2.50081 + vertex 1.58824 1.05403 2.50185 + vertex 1.58673 1.05014 2.501 + endloop + endfacet + facet normal 0.109016 -0.28225 0.953127 + outer loop + vertex 1.59345 1.05499 2.50154 + vertex 1.58824 1.05403 2.50185 + vertex 1.59038 1.05135 2.50081 + endloop + endfacet + facet normal 0.0990666 -0.274521 0.956464 + outer loop + vertex 1.59403 1.05232 2.50071 + vertex 1.59345 1.05499 2.50154 + vertex 1.59038 1.05135 2.50081 + endloop + endfacet + facet normal 0.0927618 -0.25009 0.963769 + outer loop + vertex 1.59403 1.05232 2.50071 + vertex 1.59038 1.05135 2.50081 + vertex 1.59239 1.04835 2.49984 + endloop + endfacet + facet normal 0.0358629 -0.228539 0.972874 + outer loop + vertex 1.59403 1.05232 2.50071 + vertex 1.59239 1.04835 2.49984 + vertex 1.59714 1.05154 2.50041 + endloop + endfacet + facet normal 0.0281554 -0.256642 0.966096 + outer loop + vertex 1.59714 1.05154 2.50041 + vertex 1.59669 1.0545 2.50121 + vertex 1.59403 1.05232 2.50071 + endloop + endfacet + facet normal 0.0596177 -0.262211 0.963167 + outer loop + vertex 1.59714 1.05154 2.50041 + vertex 1.59239 1.04835 2.49984 + vertex 1.59727 1.04754 2.49931 + endloop + endfacet + facet normal 0.0594231 -0.263208 0.962907 + outer loop + vertex 1.59276 1.04357 2.49851 + vertex 1.59727 1.04754 2.49931 + vertex 1.59239 1.04835 2.49984 + endloop + endfacet + facet normal 0.121776 -0.257204 0.958654 + outer loop + vertex 1.59276 1.04357 2.49851 + vertex 1.59239 1.04835 2.49984 + vertex 1.58765 1.04349 2.49913 + endloop + endfacet + facet normal 0.121636 -0.265224 0.956483 + outer loop + vertex 1.58804 1.03896 2.49783 + vertex 1.59276 1.04357 2.49851 + vertex 1.58765 1.04349 2.49913 + endloop + endfacet + facet normal 0.156932 -0.261041 0.952486 + outer loop + vertex 1.58804 1.03896 2.49783 + vertex 1.58765 1.04349 2.49913 + vertex 1.5828 1.03857 2.49859 + endloop + endfacet + facet normal 0.157011 -0.263377 0.95183 + outer loop + vertex 1.58316 1.03368 2.49717 + vertex 1.58804 1.03896 2.49783 + vertex 1.5828 1.03857 2.49859 + endloop + endfacet + facet normal 0.167695 -0.262173 0.950339 + outer loop + vertex 1.58316 1.03368 2.49717 + vertex 1.5828 1.03857 2.49859 + vertex 1.57782 1.03358 2.49809 + endloop + endfacet + facet normal 0.16771 -0.261637 0.950484 + outer loop + vertex 1.58316 1.03368 2.49717 + vertex 1.57782 1.03358 2.49809 + vertex 1.57779 1.02897 2.49682 + endloop + endfacet + facet normal 0.168107 -0.262075 0.950293 + outer loop + vertex 1.58166 1.02953 2.49629 + vertex 1.58316 1.03368 2.49717 + vertex 1.57779 1.02897 2.49682 + endloop + endfacet + facet normal 0.168038 -0.261419 0.950486 + outer loop + vertex 1.58166 1.02953 2.49629 + vertex 1.57779 1.02897 2.49682 + vertex 1.57929 1.02685 2.49598 + endloop + endfacet + facet normal 0.169729 -0.262828 0.949796 + outer loop + vertex 1.58247 1.02709 2.49548 + vertex 1.58166 1.02953 2.49629 + vertex 1.57929 1.02685 2.49598 + endloop + endfacet + facet normal 0.169802 -0.265017 0.949175 + outer loop + vertex 1.57929 1.02685 2.49598 + vertex 1.57794 1.02322 2.4952 + vertex 1.58247 1.02709 2.49548 + endloop + endfacet + facet normal 0.169685 -0.264884 0.949233 + outer loop + vertex 1.58247 1.02709 2.49548 + vertex 1.57794 1.02322 2.4952 + vertex 1.58277 1.02329 2.49436 + endloop + endfacet + facet normal 0.167394 -0.265163 0.949562 + outer loop + vertex 1.58277 1.02329 2.49436 + vertex 1.58757 1.02841 2.49494 + vertex 1.58247 1.02709 2.49548 + endloop + endfacet + facet normal 0.166357 -0.260549 0.95102 + outer loop + vertex 1.58247 1.02709 2.49548 + vertex 1.58757 1.02841 2.49494 + vertex 1.58547 1.03108 2.49604 + endloop + endfacet + facet normal 0.165313 -0.261353 0.950982 + outer loop + vertex 1.58923 1.03251 2.49578 + vertex 1.58547 1.03108 2.49604 + vertex 1.58757 1.02841 2.49494 + endloop + endfacet + facet normal 0.140841 -0.25274 0.957228 + outer loop + vertex 1.58923 1.03251 2.49578 + vertex 1.58757 1.02841 2.49494 + vertex 1.59243 1.03238 2.49528 + endloop + endfacet + facet normal 0.140243 -0.260262 0.955299 + outer loop + vertex 1.59243 1.03238 2.49528 + vertex 1.59187 1.03514 2.49611 + vertex 1.58923 1.03251 2.49578 + endloop + endfacet + facet normal 0.154074 -0.27339 0.949484 + outer loop + vertex 1.59187 1.03514 2.49611 + vertex 1.58855 1.03511 2.49664 + vertex 1.58923 1.03251 2.49578 + endloop + endfacet + facet normal 0.153039 -0.299631 0.941701 + outer loop + vertex 1.59187 1.03514 2.49611 + vertex 1.59333 1.03895 2.49709 + vertex 1.58855 1.03511 2.49664 + endloop + endfacet + facet normal 0.133276 -0.276165 0.951825 + outer loop + vertex 1.59333 1.03895 2.49709 + vertex 1.58804 1.03896 2.49783 + vertex 1.58855 1.03511 2.49664 + endloop + endfacet + facet normal 0.116276 -0.287801 0.950605 + outer loop + vertex 1.59552 1.03613 2.49596 + vertex 1.59333 1.03895 2.49709 + vertex 1.59187 1.03514 2.49611 + endloop + endfacet + facet normal 0.0881246 -0.308318 0.947193 + outer loop + vertex 1.59857 1.03958 2.4968 + vertex 1.59333 1.03895 2.49709 + vertex 1.59552 1.03613 2.49596 + endloop + endfacet + facet normal 0.0756719 -0.298337 0.951456 + outer loop + vertex 1.5992 1.03679 2.49588 + vertex 1.59857 1.03958 2.4968 + vertex 1.59552 1.03613 2.49596 + endloop + endfacet + facet normal 0.0711313 -0.272135 0.959627 + outer loop + vertex 1.5992 1.03679 2.49588 + vertex 1.59552 1.03613 2.49596 + vertex 1.59737 1.03293 2.49492 + endloop + endfacet + facet normal 0.0269244 -0.253042 0.967081 + outer loop + vertex 1.5992 1.03679 2.49588 + vertex 1.59737 1.03293 2.49492 + vertex 1.60247 1.0357 2.4955 + endloop + endfacet + facet normal 0.0166428 -0.281209 0.959502 + outer loop + vertex 1.60247 1.0357 2.4955 + vertex 1.60174 1.03884 2.49644 + vertex 1.5992 1.03679 2.49588 + endloop + endfacet + facet normal 0.0981957 -0.257088 0.961386 + outer loop + vertex 1.59243 1.03238 2.49528 + vertex 1.59737 1.03293 2.49492 + vertex 1.59552 1.03613 2.49596 + endloop + endfacet + facet normal 0.0986874 -0.262526 0.959865 + outer loop + vertex 1.59266 1.02837 2.49416 + vertex 1.59737 1.03293 2.49492 + vertex 1.59243 1.03238 2.49528 + endloop + endfacet + facet normal 0.106336 -0.269951 0.956984 + outer loop + vertex 1.5976 1.02831 2.49359 + vertex 1.59737 1.03293 2.49492 + vertex 1.59266 1.02837 2.49416 + endloop + endfacet + facet normal 0.106164 -0.273767 0.955919 + outer loop + vertex 1.59304 1.02392 2.49284 + vertex 1.5976 1.02831 2.49359 + vertex 1.59266 1.02837 2.49416 + endloop + endfacet + facet normal 0.148446 -0.268833 0.951679 + outer loop + vertex 1.59304 1.02392 2.49284 + vertex 1.59266 1.02837 2.49416 + vertex 1.58787 1.02365 2.49357 + endloop + endfacet + facet normal 0.148469 -0.27063 0.951166 + outer loop + vertex 1.58832 1.01891 2.49215 + vertex 1.59304 1.02392 2.49284 + vertex 1.58787 1.02365 2.49357 + endloop + endfacet + facet normal 0.16778 -0.26804 0.948686 + outer loop + vertex 1.58832 1.01891 2.49215 + vertex 1.58787 1.02365 2.49357 + vertex 1.58308 1.01874 2.49303 + endloop + endfacet + facet normal 0.167827 -0.264708 0.949612 + outer loop + vertex 1.58832 1.01891 2.49215 + vertex 1.58308 1.01874 2.49303 + vertex 1.58366 1.01487 2.49185 + endloop + endfacet + facet normal 0.171736 -0.269065 0.947687 + outer loop + vertex 1.58684 1.01488 2.49128 + vertex 1.58832 1.01891 2.49215 + vertex 1.58366 1.01487 2.49185 + endloop + endfacet + facet normal 0.171892 -0.265644 0.948623 + outer loop + vertex 1.58684 1.01488 2.49128 + vertex 1.58366 1.01487 2.49185 + vertex 1.58435 1.01229 2.491 + endloop + endfacet + facet normal 0.174644 -0.268156 0.947413 + outer loop + vertex 1.58743 1.01224 2.49042 + vertex 1.58684 1.01488 2.49128 + vertex 1.58435 1.01229 2.491 + endloop + endfacet + facet normal 0.174158 -0.275322 0.945445 + outer loop + vertex 1.58435 1.01229 2.491 + vertex 1.58262 1.00836 2.49017 + vertex 1.58743 1.01224 2.49042 + endloop + endfacet + facet normal 0.170405 -0.270809 0.94743 + outer loop + vertex 1.58743 1.01224 2.49042 + vertex 1.58262 1.00836 2.49017 + vertex 1.58771 1.00834 2.48926 + endloop + endfacet + facet normal 0.164953 -0.271437 0.948216 + outer loop + vertex 1.58771 1.00834 2.48926 + vertex 1.59252 1.0134 2.48986 + vertex 1.58743 1.01224 2.49042 + endloop + endfacet + facet normal 0.163082 -0.261721 0.951266 + outer loop + vertex 1.58743 1.01224 2.49042 + vertex 1.59252 1.0134 2.48986 + vertex 1.59047 1.0162 2.49099 + endloop + endfacet + facet normal 0.158405 -0.265087 0.951124 + outer loop + vertex 1.59418 1.01746 2.49072 + vertex 1.59047 1.0162 2.49099 + vertex 1.59252 1.0134 2.48986 + endloop + endfacet + facet normal 0.116247 -0.249954 0.961254 + outer loop + vertex 1.59418 1.01746 2.49072 + vertex 1.59252 1.0134 2.48986 + vertex 1.59734 1.01712 2.49025 + endloop + endfacet + facet normal 0.113385 -0.269666 0.956255 + outer loop + vertex 1.59734 1.01712 2.49025 + vertex 1.59689 1.01995 2.4911 + vertex 1.59418 1.01746 2.49072 + endloop + endfacet + facet normal 0.134003 -0.290615 0.94741 + outer loop + vertex 1.59689 1.01995 2.4911 + vertex 1.59355 1.0201 2.49162 + vertex 1.59418 1.01746 2.49072 + endloop + endfacet + facet normal 0.131549 -0.317083 0.93923 + outer loop + vertex 1.59689 1.01995 2.4911 + vertex 1.5984 1.02379 2.49219 + vertex 1.59355 1.0201 2.49162 + endloop + endfacet + facet normal 0.108921 -0.289145 0.951069 + outer loop + vertex 1.5984 1.02379 2.49219 + vertex 1.59304 1.02392 2.49284 + vertex 1.59355 1.0201 2.49162 + endloop + endfacet + facet normal 0.0713572 -0.297011 0.952204 + outer loop + vertex 1.60077 1.0207 2.49104 + vertex 1.5984 1.02379 2.49219 + vertex 1.59689 1.01995 2.4911 + endloop + endfacet + facet normal 0.0522988 -0.310438 0.949154 + outer loop + vertex 1.60417 1.02458 2.49213 + vertex 1.5984 1.02379 2.49219 + vertex 1.60077 1.0207 2.49104 + endloop + endfacet + facet normal 0.0488752 -0.284723 0.957363 + outer loop + vertex 1.60417 1.02458 2.49213 + vertex 1.60266 1.02843 2.49335 + vertex 1.5984 1.02379 2.49219 + endloop + endfacet + facet normal 0.0525788 -0.287837 0.956235 + outer loop + vertex 1.5984 1.02379 2.49219 + vertex 1.60266 1.02843 2.49335 + vertex 1.5976 1.02831 2.49359 + endloop + endfacet + facet normal 0.0524333 -0.273453 0.960455 + outer loop + vertex 1.60266 1.02843 2.49335 + vertex 1.60131 1.03178 2.49438 + vertex 1.5976 1.02831 2.49359 + endloop + endfacet + facet normal 0.0677422 -0.277614 0.958301 + outer loop + vertex 1.59689 1.01995 2.4911 + vertex 1.59734 1.01712 2.49025 + vertex 1.60077 1.0207 2.49104 + endloop + endfacet + facet normal 0.0687421 -0.278497 0.957974 + outer loop + vertex 1.59734 1.01712 2.49025 + vertex 1.60184 1.01717 2.48994 + vertex 1.60077 1.0207 2.49104 + endloop + endfacet + facet normal 0.0688171 -0.268875 0.960713 + outer loop + vertex 1.59756 1.0132 2.48914 + vertex 1.60184 1.01717 2.48994 + vertex 1.59734 1.01712 2.49025 + endloop + endfacet + facet normal 0.0769916 -0.277091 0.957754 + outer loop + vertex 1.60261 1.01316 2.48872 + vertex 1.60184 1.01717 2.48994 + vertex 1.59756 1.0132 2.48914 + endloop + endfacet + facet normal 0.0768184 -0.282504 0.956185 + outer loop + vertex 1.59804 1.00893 2.48784 + vertex 1.60261 1.01316 2.48872 + vertex 1.59756 1.0132 2.48914 + endloop + endfacet + facet normal 0.131886 -0.275152 0.952311 + outer loop + vertex 1.59804 1.00893 2.48784 + vertex 1.59756 1.0132 2.48914 + vertex 1.59285 1.00869 2.48849 + endloop + endfacet + facet normal 0.131949 -0.281637 0.950405 + outer loop + vertex 1.59329 1.00407 2.48706 + vertex 1.59804 1.00893 2.48784 + vertex 1.59285 1.00869 2.48849 + endloop + endfacet + facet normal 0.163902 -0.2774 0.946671 + outer loop + vertex 1.59329 1.00407 2.48706 + vertex 1.59285 1.00869 2.48849 + vertex 1.58804 1.00387 2.48791 + endloop + endfacet + facet normal 0.163918 -0.275539 0.947211 + outer loop + vertex 1.59329 1.00407 2.48706 + vertex 1.58804 1.00387 2.48791 + vertex 1.58849 1.00002 2.48671 + endloop + endfacet + facet normal 0.171954 -0.28471 0.943065 + outer loop + vertex 1.59176 1.00009 2.48613 + vertex 1.59329 1.00407 2.48706 + vertex 1.58849 1.00002 2.48671 + endloop + endfacet + facet normal 0.172153 -0.277623 0.945139 + outer loop + vertex 1.59176 1.00009 2.48613 + vertex 1.58849 1.00002 2.48671 + vertex 1.58915 0.997402 2.48582 + endloop + endfacet + facet normal 0.172273 -0.277733 0.945086 + outer loop + vertex 1.59236 0.997424 2.48524 + vertex 1.59176 1.00009 2.48613 + vertex 1.58915 0.997402 2.48582 + endloop + endfacet + facet normal 0.172062 -0.282424 0.943733 + outer loop + vertex 1.58915 0.997402 2.48582 + vertex 1.58754 0.993367 2.48491 + vertex 1.59236 0.997424 2.48524 + endloop + endfacet + facet normal 0.169645 -0.279657 0.944993 + outer loop + vertex 1.59236 0.997424 2.48524 + vertex 1.58754 0.993367 2.48491 + vertex 1.59266 0.99351 2.48403 + endloop + endfacet + facet normal 0.153224 -0.281604 0.947218 + outer loop + vertex 1.59266 0.99351 2.48403 + vertex 1.59751 0.998493 2.48473 + vertex 1.59236 0.997424 2.48524 + endloop + endfacet + facet normal 0.15121 -0.270153 0.950869 + outer loop + vertex 1.59236 0.997424 2.48524 + vertex 1.59751 0.998493 2.48473 + vertex 1.59544 1.00138 2.48588 + endloop + endfacet + facet normal 0.140848 -0.277368 0.950384 + outer loop + vertex 1.59914 1.00253 2.48566 + vertex 1.59544 1.00138 2.48588 + vertex 1.59751 0.998493 2.48473 + endloop + endfacet + facet normal 0.0894674 -0.259213 0.961667 + outer loop + vertex 1.59914 1.00253 2.48566 + vertex 1.59751 0.998493 2.48473 + vertex 1.60231 1.00204 2.48524 + endloop + endfacet + facet normal 0.0845945 -0.284637 0.954896 + outer loop + vertex 1.60231 1.00204 2.48524 + vertex 1.60184 1.00491 2.48613 + vertex 1.59914 1.00253 2.48566 + endloop + endfacet + facet normal 0.106747 -0.307899 0.945412 + outer loop + vertex 1.60184 1.00491 2.48613 + vertex 1.59853 1.00519 2.4866 + vertex 1.59914 1.00253 2.48566 + endloop + endfacet + facet normal 0.103854 -0.330252 0.938162 + outer loop + vertex 1.60184 1.00491 2.48613 + vertex 1.60341 1.00868 2.48729 + vertex 1.59853 1.00519 2.4866 + endloop + endfacet + facet normal 0.0832751 -0.303657 0.949135 + outer loop + vertex 1.60341 1.00868 2.48729 + vertex 1.59804 1.00893 2.48784 + vertex 1.59853 1.00519 2.4866 + endloop + endfacet + facet normal 0.0424013 -0.308327 0.950335 + outer loop + vertex 1.60571 1.0055 2.48615 + vertex 1.60341 1.00868 2.48729 + vertex 1.60184 1.00491 2.48613 + endloop + endfacet + facet normal 0.0325396 -0.314825 0.948592 + outer loop + vertex 1.60916 1.00931 2.4873 + vertex 1.60341 1.00868 2.48729 + vertex 1.60571 1.0055 2.48615 + endloop + endfacet + facet normal 0.0303171 -0.294771 0.955087 + outer loop + vertex 1.60916 1.00931 2.4873 + vertex 1.60785 1.01321 2.48854 + vertex 1.60341 1.00868 2.48729 + endloop + endfacet + facet normal 0.034933 -0.298898 0.953645 + outer loop + vertex 1.60341 1.00868 2.48729 + vertex 1.60785 1.01321 2.48854 + vertex 1.60261 1.01316 2.48872 + endloop + endfacet + facet normal 0.0399268 -0.292179 0.95553 + outer loop + vertex 1.60184 1.00491 2.48613 + vertex 1.60231 1.00204 2.48524 + vertex 1.60571 1.0055 2.48615 + endloop + endfacet + facet normal 0.042688 -0.294663 0.954647 + outer loop + vertex 1.60231 1.00204 2.48524 + vertex 1.60685 1.00198 2.48501 + vertex 1.60571 1.0055 2.48615 + endloop + endfacet + facet normal 0.0429216 -0.28662 0.957083 + outer loop + vertex 1.60265 0.998079 2.48403 + vertex 1.60685 1.00198 2.48501 + vertex 1.60231 1.00204 2.48524 + endloop + endfacet + facet normal 0.105872 -0.280314 0.954052 + outer loop + vertex 1.60231 1.00204 2.48524 + vertex 1.59751 0.998493 2.48473 + vertex 1.60265 0.998079 2.48403 + endloop + endfacet + facet normal 0.105207 -0.28591 0.952464 + outer loop + vertex 1.59784 0.993735 2.48326 + vertex 1.60265 0.998079 2.48403 + vertex 1.59751 0.998493 2.48473 + endloop + endfacet + facet normal 0.115432 -0.296428 0.948054 + outer loop + vertex 1.60334 0.993466 2.48251 + vertex 1.60265 0.998079 2.48403 + vertex 1.59784 0.993735 2.48326 + endloop + endfacet + facet normal 0.115145 -0.299587 0.947095 + outer loop + vertex 1.60334 0.993466 2.48251 + vertex 1.59784 0.993735 2.48326 + vertex 1.5979 0.989233 2.48183 + endloop + endfacet + facet normal 0.147785 -0.338671 0.929226 + outer loop + vertex 1.60185 0.989586 2.48133 + vertex 1.60334 0.993466 2.48251 + vertex 1.5979 0.989233 2.48183 + endloop + endfacet + facet normal 0.146794 -0.316122 0.937293 + outer loop + vertex 1.60185 0.989586 2.48133 + vertex 1.5979 0.989233 2.48183 + vertex 1.59939 0.987094 2.48087 + endloop + endfacet + facet normal 0.120628 -0.292371 0.948666 + outer loop + vertex 1.60249 0.986943 2.48044 + vertex 1.60185 0.989586 2.48133 + vertex 1.59939 0.987094 2.48087 + endloop + endfacet + facet normal 0.12273 -0.268751 0.955359 + outer loop + vertex 1.59939 0.987094 2.48087 + vertex 1.59795 0.983435 2.48003 + vertex 1.60249 0.986943 2.48044 + endloop + endfacet + facet normal 0.133049 -0.281512 0.950289 + outer loop + vertex 1.60249 0.986943 2.48044 + vertex 1.59795 0.983435 2.48003 + vertex 1.60266 0.983166 2.47929 + endloop + endfacet + facet normal 0.0759507 -0.285659 0.955317 + outer loop + vertex 1.60266 0.983166 2.47929 + vertex 1.60687 0.987026 2.48011 + vertex 1.60249 0.986943 2.48044 + endloop + endfacet + facet normal 0.0759 -0.299257 0.951149 + outer loop + vertex 1.60249 0.986943 2.48044 + vertex 1.60687 0.987026 2.48011 + vertex 1.60579 0.990465 2.48128 + endloop + endfacet + facet normal 0.0847103 -0.294481 0.951896 + outer loop + vertex 1.6076 0.983101 2.47883 + vertex 1.60687 0.987026 2.48011 + vertex 1.60266 0.983166 2.47929 + endloop + endfacet + facet normal 0.0846546 -0.29582 0.951485 + outer loop + vertex 1.60303 0.978946 2.47795 + vertex 1.6076 0.983101 2.47883 + vertex 1.60266 0.983166 2.47929 + endloop + endfacet + facet normal 0.13916 -0.289641 0.946965 + outer loop + vertex 1.60303 0.978946 2.47795 + vertex 1.60266 0.983166 2.47929 + vertex 1.59787 0.978802 2.47866 + endloop + endfacet + facet normal 0.13911 -0.293066 0.945918 + outer loop + vertex 1.59824 0.974115 2.47715 + vertex 1.60303 0.978946 2.47795 + vertex 1.59787 0.978802 2.47866 + endloop + endfacet + facet normal 0.167895 -0.289609 0.942305 + outer loop + vertex 1.59824 0.974115 2.47715 + vertex 1.59787 0.978802 2.47866 + vertex 1.59298 0.974021 2.47806 + endloop + endfacet + facet normal 0.167954 -0.287888 0.942821 + outer loop + vertex 1.59824 0.974115 2.47715 + vertex 1.59298 0.974021 2.47806 + vertex 1.59346 0.970082 2.47677 + endloop + endfacet + facet normal 0.174137 -0.294916 0.939522 + outer loop + vertex 1.59671 0.970104 2.47618 + vertex 1.59824 0.974115 2.47715 + vertex 1.59346 0.970082 2.47677 + endloop + endfacet + facet normal 0.174402 -0.289483 0.941161 + outer loop + vertex 1.59671 0.970104 2.47618 + vertex 1.59346 0.970082 2.47677 + vertex 1.59413 0.967419 2.47583 + endloop + endfacet + facet normal 0.175583 -0.290548 0.940613 + outer loop + vertex 1.59736 0.967438 2.47523 + vertex 1.59671 0.970104 2.47618 + vertex 1.59413 0.967419 2.47583 + endloop + endfacet + facet normal 0.17525 -0.297186 0.938599 + outer loop + vertex 1.59413 0.967419 2.47583 + vertex 1.59256 0.963403 2.47485 + vertex 1.59736 0.967438 2.47523 + endloop + endfacet + facet normal 0.172951 -0.29457 0.939849 + outer loop + vertex 1.59736 0.967438 2.47523 + vertex 1.59256 0.963403 2.47485 + vertex 1.59777 0.963533 2.47394 + endloop + endfacet + facet normal 0.161427 -0.296264 0.941366 + outer loop + vertex 1.59777 0.963533 2.47394 + vertex 1.60254 0.968565 2.4747 + vertex 1.59736 0.967438 2.47523 + endloop + endfacet + facet normal 0.159236 -0.284275 0.945427 + outer loop + vertex 1.59736 0.967438 2.47523 + vertex 1.60254 0.968565 2.4747 + vertex 1.6004 0.971403 2.47591 + endloop + endfacet + facet normal 0.150509 -0.290622 0.944927 + outer loop + vertex 1.60411 0.972573 2.47568 + vertex 1.6004 0.971403 2.47591 + vertex 1.60254 0.968565 2.4747 + endloop + endfacet + facet normal 0.104423 -0.27518 0.955705 + outer loop + vertex 1.60411 0.972573 2.47568 + vertex 1.60254 0.968565 2.4747 + vertex 1.60728 0.972126 2.47521 + endloop + endfacet + facet normal 0.100209 -0.298222 0.949222 + outer loop + vertex 1.60728 0.972126 2.47521 + vertex 1.60679 0.974959 2.47615 + vertex 1.60411 0.972573 2.47568 + endloop + endfacet + facet normal 0.118839 -0.317515 0.940777 + outer loop + vertex 1.60679 0.974959 2.47615 + vertex 1.60348 0.975217 2.47666 + vertex 1.60411 0.972573 2.47568 + endloop + endfacet + facet normal 0.115485 -0.343468 0.932037 + outer loop + vertex 1.60679 0.974959 2.47615 + vertex 1.60837 0.978702 2.47733 + vertex 1.60348 0.975217 2.47666 + endloop + endfacet + facet normal 0.0592699 -0.323723 0.944294 + outer loop + vertex 1.61067 0.975588 2.47612 + vertex 1.60837 0.978702 2.47733 + vertex 1.60679 0.974959 2.47615 + endloop + endfacet + facet normal 0.0431079 -0.334539 0.941396 + outer loop + vertex 1.61413 0.979365 2.47731 + vertex 1.60837 0.978702 2.47733 + vertex 1.61067 0.975588 2.47612 + endloop + endfacet + facet normal 0.0408829 -0.314898 0.948244 + outer loop + vertex 1.61413 0.979365 2.47731 + vertex 1.61281 0.983155 2.47862 + vertex 1.60837 0.978702 2.47733 + endloop + endfacet + facet normal 0.0416403 -0.315579 0.947985 + outer loop + vertex 1.60837 0.978702 2.47733 + vertex 1.61281 0.983155 2.47862 + vertex 1.6076 0.983101 2.47883 + endloop + endfacet + facet normal 0.041652 -0.311915 0.949197 + outer loop + vertex 1.61281 0.983155 2.47862 + vertex 1.61171 0.987026 2.47994 + vertex 1.6076 0.983101 2.47883 + endloop + endfacet + facet normal 0.0564634 -0.306163 0.950303 + outer loop + vertex 1.60679 0.974959 2.47615 + vertex 1.60728 0.972126 2.47521 + vertex 1.61067 0.975588 2.47612 + endloop + endfacet + facet normal 0.0589272 -0.308345 0.949448 + outer loop + vertex 1.60728 0.972126 2.47521 + vertex 1.61181 0.972126 2.47493 + vertex 1.61067 0.975588 2.47612 + endloop + endfacet + facet normal 0.0590722 -0.301033 0.951782 + outer loop + vertex 1.60766 0.968258 2.47396 + vertex 1.61181 0.972126 2.47493 + vertex 1.60728 0.972126 2.47521 + endloop + endfacet + facet normal 0.0690167 -0.310747 0.947984 + outer loop + vertex 1.61281 0.968338 2.47361 + vertex 1.61181 0.972126 2.47493 + vertex 1.60766 0.968258 2.47396 + endloop + endfacet + facet normal 0.0689506 -0.320182 0.944844 + outer loop + vertex 1.60841 0.963857 2.47241 + vertex 1.61281 0.968338 2.47361 + vertex 1.60766 0.968258 2.47396 + endloop + endfacet + facet normal 0.127777 -0.309302 0.94234 + outer loop + vertex 1.60841 0.963857 2.47241 + vertex 1.60766 0.968258 2.47396 + vertex 1.60304 0.963954 2.47317 + endloop + endfacet + facet normal 0.127275 -0.317153 0.939795 + outer loop + vertex 1.60841 0.963857 2.47241 + vertex 1.60304 0.963954 2.47317 + vertex 1.60357 0.960184 2.47183 + endloop + endfacet + facet normal 0.148312 -0.342918 0.927583 + outer loop + vertex 1.60691 0.960072 2.47126 + vertex 1.60841 0.963857 2.47241 + vertex 1.60357 0.960184 2.47183 + endloop + endfacet + facet normal 0.15049 -0.319279 0.935636 + outer loop + vertex 1.60691 0.960072 2.47126 + vertex 1.60357 0.960184 2.47183 + vertex 1.60426 0.957577 2.47083 + endloop + endfacet + facet normal 0.139227 -0.308263 0.941058 + outer loop + vertex 1.60743 0.957282 2.47026 + vertex 1.60691 0.960072 2.47126 + vertex 1.60426 0.957577 2.47083 + endloop + endfacet + facet normal 0.141684 -0.291388 0.946054 + outer loop + vertex 1.60426 0.957577 2.47083 + vertex 1.60272 0.953541 2.46982 + vertex 1.60743 0.957282 2.47026 + endloop + endfacet + facet normal 0.149827 -0.301144 0.941735 + outer loop + vertex 1.60743 0.957282 2.47026 + vertex 1.60272 0.953541 2.46982 + vertex 1.60783 0.953395 2.46896 + endloop + endfacet + facet normal 0.0998746 -0.307776 0.946203 + outer loop + vertex 1.60783 0.953395 2.46896 + vertex 1.61192 0.957384 2.46982 + vertex 1.60743 0.957282 2.47026 + endloop + endfacet + facet normal 0.0997781 -0.317607 0.942958 + outer loop + vertex 1.60743 0.957282 2.47026 + vertex 1.61192 0.957384 2.46982 + vertex 1.61073 0.960846 2.47112 + endloop + endfacet + facet normal 0.0521652 -0.333373 0.941351 + outer loop + vertex 1.61073 0.960846 2.47112 + vertex 1.61192 0.957384 2.46982 + vertex 1.61552 0.961081 2.47093 + endloop + endfacet + facet normal 0.0520814 -0.331025 0.942184 + outer loop + vertex 1.61552 0.961081 2.47093 + vertex 1.61409 0.964631 2.47226 + vertex 1.61073 0.960846 2.47112 + endloop + endfacet + facet normal 0.0728094 -0.34724 0.934946 + outer loop + vertex 1.61409 0.964631 2.47226 + vertex 1.60841 0.963857 2.47241 + vertex 1.61073 0.960846 2.47112 + endloop + endfacet + facet normal 0.0307308 -0.338906 0.940318 + outer loop + vertex 1.61913 0.964799 2.47216 + vertex 1.61409 0.964631 2.47226 + vertex 1.61552 0.961081 2.47093 + endloop + endfacet + facet normal 0.0517102 -0.332979 0.941515 + outer loop + vertex 1.61192 0.957384 2.46982 + vertex 1.61688 0.957326 2.46953 + vertex 1.61552 0.961081 2.47093 + endloop + endfacet + facet normal 0.0517144 -0.332848 0.941561 + outer loop + vertex 1.61291 0.953484 2.46839 + vertex 1.61688 0.957326 2.46953 + vertex 1.61192 0.957384 2.46982 + endloop + endfacet + facet normal 0.056889 -0.337598 0.93957 + outer loop + vertex 1.61826 0.952998 2.46789 + vertex 1.61688 0.957326 2.46953 + vertex 1.61291 0.953484 2.46839 + endloop + endfacet + facet normal 0.0561098 -0.343881 0.937335 + outer loop + vertex 1.61826 0.952998 2.46789 + vertex 1.61291 0.953484 2.46839 + vertex 1.61369 0.949906 2.46703 + endloop + endfacet + facet normal 0.0699101 -0.362078 0.929523 + outer loop + vertex 1.61694 0.949417 2.4666 + vertex 1.61826 0.952998 2.46789 + vertex 1.61369 0.949906 2.46703 + endloop + endfacet + facet normal 0.0760044 -0.331322 0.940451 + outer loop + vertex 1.61694 0.949417 2.4666 + vertex 1.61369 0.949906 2.46703 + vertex 1.61437 0.94728 2.46605 + endloop + endfacet + facet normal 0.053706 -0.307004 0.950192 + outer loop + vertex 1.61743 0.946547 2.46564 + vertex 1.61694 0.949417 2.4666 + vertex 1.61437 0.94728 2.46605 + endloop + endfacet + facet normal 0.0601391 -0.283895 0.956968 + outer loop + vertex 1.61437 0.94728 2.46605 + vertex 1.61275 0.943386 2.465 + vertex 1.61743 0.946547 2.46564 + endloop + endfacet + facet normal 0.0928777 -0.328878 0.939794 + outer loop + vertex 1.61743 0.946547 2.46564 + vertex 1.61275 0.943386 2.465 + vertex 1.61767 0.942816 2.46431 + endloop + endfacet + facet normal 0.0849594 -0.376436 0.922539 + outer loop + vertex 1.61338 0.938653 2.46301 + vertex 1.61767 0.942816 2.46431 + vertex 1.61275 0.943386 2.465 + endloop + endfacet + facet normal 0.166793 -0.363185 0.916666 + outer loop + vertex 1.61338 0.938653 2.46301 + vertex 1.61275 0.943386 2.465 + vertex 1.60815 0.938818 2.46403 + endloop + endfacet + facet normal 0.146628 -0.345067 0.927054 + outer loop + vertex 1.60815 0.938818 2.46403 + vertex 1.61275 0.943386 2.465 + vertex 1.60766 0.942459 2.46546 + endloop + endfacet + facet normal 0.170711 -0.340815 0.924502 + outer loop + vertex 1.60766 0.942459 2.46546 + vertex 1.60292 0.938519 2.46488 + vertex 1.60815 0.938818 2.46403 + endloop + endfacet + facet normal 0.165415 -0.33491 0.927617 + outer loop + vertex 1.60439 0.942395 2.46602 + vertex 1.60292 0.938519 2.46488 + vertex 1.60766 0.942459 2.46546 + endloop + endfacet + facet normal 0.166829 -0.297051 0.940175 + outer loop + vertex 1.60766 0.942459 2.46546 + vertex 1.60703 0.945079 2.4664 + vertex 1.60439 0.942395 2.46602 + endloop + endfacet + facet normal 0.168853 -0.298909 0.939224 + outer loop + vertex 1.60703 0.945079 2.4664 + vertex 1.6037 0.945004 2.46697 + vertex 1.60439 0.942395 2.46602 + endloop + endfacet + facet normal 0.172449 -0.297844 0.938909 + outer loop + vertex 1.60439 0.942395 2.46602 + vertex 1.6037 0.945004 2.46697 + vertex 1.6006 0.940972 2.46626 + endloop + endfacet + facet normal 0.174351 -0.299172 0.938135 + outer loop + vertex 1.6037 0.945004 2.46697 + vertex 1.59826 0.943632 2.46755 + vertex 1.6006 0.940972 2.46626 + endloop + endfacet + facet normal 0.177599 -0.296445 0.938392 + outer loop + vertex 1.6006 0.940972 2.46626 + vertex 1.59826 0.943632 2.46755 + vertex 1.59668 0.939463 2.46653 + endloop + endfacet + facet normal 0.197798 -0.353056 0.914455 + outer loop + vertex 1.59668 0.939463 2.46653 + vertex 1.59762 0.937094 2.46541 + vertex 1.6006 0.940972 2.46626 + endloop + endfacet + facet normal 0.184445 -0.344175 0.92061 + outer loop + vertex 1.59762 0.937094 2.46541 + vertex 1.60292 0.938519 2.46488 + vertex 1.6006 0.940972 2.46626 + endloop + endfacet + facet normal 0.20574 -0.440737 0.87374 + outer loop + vertex 1.59847 0.933522 2.46341 + vertex 1.60292 0.938519 2.46488 + vertex 1.59762 0.937094 2.46541 + endloop + endfacet + facet normal 0.205178 -0.440899 0.87379 + outer loop + vertex 1.59762 0.937094 2.46541 + vertex 1.59326 0.933681 2.46471 + vertex 1.59847 0.933522 2.46341 + endloop + endfacet + facet normal 0.197719 -0.432559 0.879659 + outer loop + vertex 1.59427 0.936888 2.46606 + vertex 1.59326 0.933681 2.46471 + vertex 1.59762 0.937094 2.46541 + endloop + endfacet + facet normal 0.216476 -0.435887 0.873579 + outer loop + vertex 1.59427 0.936888 2.46606 + vertex 1.59139 0.935531 2.4661 + vertex 1.59326 0.933681 2.46471 + endloop + endfacet + facet normal 0.20473 -0.446044 0.871281 + outer loop + vertex 1.59326 0.933681 2.46471 + vertex 1.59139 0.935531 2.4661 + vertex 1.58924 0.933122 2.46537 + endloop + endfacet + facet normal 0.167363 -0.41906 0.8924 + outer loop + vertex 1.59139 0.935531 2.4661 + vertex 1.58809 0.935319 2.46662 + vertex 1.58924 0.933122 2.46537 + endloop + endfacet + facet normal 0.167448 -0.332424 0.928146 + outer loop + vertex 1.59139 0.935531 2.4661 + vertex 1.59271 0.939031 2.46711 + vertex 1.58809 0.935319 2.46662 + endloop + endfacet + facet normal 0.160615 -0.324456 0.932165 + outer loop + vertex 1.59271 0.939031 2.46711 + vertex 1.58768 0.939054 2.46799 + vertex 1.58809 0.935319 2.46662 + endloop + endfacet + facet normal 0.153329 -0.325556 0.933008 + outer loop + vertex 1.58809 0.935319 2.46662 + vertex 1.58768 0.939054 2.46799 + vertex 1.58291 0.934071 2.46703 + endloop + endfacet + facet normal 0.158166 -0.329755 0.930723 + outer loop + vertex 1.58291 0.934071 2.46703 + vertex 1.58768 0.939054 2.46799 + vertex 1.58249 0.938678 2.46874 + endloop + endfacet + facet normal 0.165597 -0.328745 0.929787 + outer loop + vertex 1.58291 0.934071 2.46703 + vertex 1.58249 0.938678 2.46874 + vertex 1.57787 0.9342 2.46798 + endloop + endfacet + facet normal 0.160148 -0.386014 0.908486 + outer loop + vertex 1.58291 0.934071 2.46703 + vertex 1.57787 0.9342 2.46798 + vertex 1.57827 0.930333 2.46626 + endloop + endfacet + facet normal 0.154626 -0.318349 0.935278 + outer loop + vertex 1.57787 0.9342 2.46798 + vertex 1.58249 0.938678 2.46874 + vertex 1.57733 0.938657 2.46958 + endloop + endfacet + facet normal 0.148098 -0.319394 0.935978 + outer loop + vertex 1.57787 0.9342 2.46798 + vertex 1.57733 0.938657 2.46958 + vertex 1.57298 0.933977 2.46867 + endloop + endfacet + facet normal 0.155157 -0.325335 0.932782 + outer loop + vertex 1.57298 0.933977 2.46867 + vertex 1.57733 0.938657 2.46958 + vertex 1.57221 0.937571 2.47006 + endloop + endfacet + facet normal 0.136404 -0.329854 0.934125 + outer loop + vertex 1.57221 0.937571 2.47006 + vertex 1.56778 0.933937 2.46942 + vertex 1.57298 0.933977 2.46867 + endloop + endfacet + facet normal 0.133925 -0.383079 0.913955 + outer loop + vertex 1.56927 0.929984 2.46755 + vertex 1.57298 0.933977 2.46867 + vertex 1.56778 0.933937 2.46942 + endloop + endfacet + facet normal 0.112983 -0.390771 0.913528 + outer loop + vertex 1.56927 0.929984 2.46755 + vertex 1.56778 0.933937 2.46942 + vertex 1.56419 0.929549 2.46799 + endloop + endfacet + facet normal 0.146225 -0.340888 0.928662 + outer loop + vertex 1.56892 0.93768 2.47061 + vertex 1.56778 0.933937 2.46942 + vertex 1.57221 0.937571 2.47006 + endloop + endfacet + facet normal 0.14902 -0.309797 0.939052 + outer loop + vertex 1.57221 0.937571 2.47006 + vertex 1.57148 0.940172 2.47103 + vertex 1.56892 0.93768 2.47061 + endloop + endfacet + facet normal 0.146103 -0.307027 0.940419 + outer loop + vertex 1.57148 0.940172 2.47103 + vertex 1.56834 0.940372 2.47158 + vertex 1.56892 0.93768 2.47061 + endloop + endfacet + facet normal 0.130163 -0.310835 0.941509 + outer loop + vertex 1.56892 0.93768 2.47061 + vertex 1.56834 0.940372 2.47158 + vertex 1.56519 0.936663 2.47079 + endloop + endfacet + facet normal 0.133712 -0.313557 0.940108 + outer loop + vertex 1.56834 0.940372 2.47158 + vertex 1.56381 0.939841 2.47205 + vertex 1.56519 0.936663 2.47079 + endloop + endfacet + facet normal 0.116744 -0.320827 0.939915 + outer loop + vertex 1.56519 0.936663 2.47079 + vertex 1.56381 0.939841 2.47205 + vertex 1.56055 0.935776 2.47107 + endloop + endfacet + facet normal 0.122382 -0.354265 0.927102 + outer loop + vertex 1.56055 0.935776 2.47107 + vertex 1.56229 0.932774 2.46969 + vertex 1.56519 0.936663 2.47079 + endloop + endfacet + facet normal 0.120603 -0.353127 0.927769 + outer loop + vertex 1.56229 0.932774 2.46969 + vertex 1.56778 0.933937 2.46942 + vertex 1.56519 0.936663 2.47079 + endloop + endfacet + facet normal 0.133019 -0.305108 0.942982 + outer loop + vertex 1.56834 0.940372 2.47158 + vertex 1.5681 0.944119 2.47283 + vertex 1.56381 0.939841 2.47205 + endloop + endfacet + facet normal 0.136049 -0.3079 0.941641 + outer loop + vertex 1.56381 0.939841 2.47205 + vertex 1.5681 0.944119 2.47283 + vertex 1.56302 0.943717 2.47343 + endloop + endfacet + facet normal 0.136078 -0.30864 0.941395 + outer loop + vertex 1.5681 0.944119 2.47283 + vertex 1.56784 0.948306 2.47424 + vertex 1.56302 0.943717 2.47343 + endloop + endfacet + facet normal 0.140207 -0.312637 0.939468 + outer loop + vertex 1.56302 0.943717 2.47343 + vertex 1.56784 0.948306 2.47424 + vertex 1.56269 0.948217 2.47498 + endloop + endfacet + facet normal 0.118598 -0.314978 0.94166 + outer loop + vertex 1.56302 0.943717 2.47343 + vertex 1.56269 0.948217 2.47498 + vertex 1.55779 0.943362 2.47397 + endloop + endfacet + facet normal 0.118651 -0.316582 0.941115 + outer loop + vertex 1.55827 0.93877 2.47237 + vertex 1.56302 0.943717 2.47343 + vertex 1.55779 0.943362 2.47397 + endloop + endfacet + facet normal 0.100503 -0.318948 0.942428 + outer loop + vertex 1.55827 0.93877 2.47237 + vertex 1.55779 0.943362 2.47397 + vertex 1.55314 0.93908 2.47302 + endloop + endfacet + facet normal 0.0991941 -0.331644 0.938175 + outer loop + vertex 1.55827 0.93877 2.47237 + vertex 1.55314 0.93908 2.47302 + vertex 1.55355 0.935246 2.47162 + endloop + endfacet + facet normal 0.0939703 -0.325233 0.940953 + outer loop + vertex 1.55674 0.934814 2.47115 + vertex 1.55827 0.93877 2.47237 + vertex 1.55355 0.935246 2.47162 + endloop + endfacet + facet normal 0.0871848 -0.361582 0.928255 + outer loop + vertex 1.55674 0.934814 2.47115 + vertex 1.55355 0.935246 2.47162 + vertex 1.5542 0.932421 2.47046 + endloop + endfacet + facet normal 0.0997075 -0.373167 0.922391 + outer loop + vertex 1.55756 0.932152 2.46999 + vertex 1.55674 0.934814 2.47115 + vertex 1.5542 0.932421 2.47046 + endloop + endfacet + facet normal 0.113537 -0.368927 0.922498 + outer loop + vertex 1.55674 0.934814 2.47115 + vertex 1.55756 0.932152 2.46999 + vertex 1.56055 0.935776 2.47107 + endloop + endfacet + facet normal 0.105589 -0.363325 0.92566 + outer loop + vertex 1.55756 0.932152 2.46999 + vertex 1.56229 0.932774 2.46969 + vertex 1.56055 0.935776 2.47107 + endloop + endfacet + facet normal 0.103651 -0.328348 0.938852 + outer loop + vertex 1.56055 0.935776 2.47107 + vertex 1.55827 0.93877 2.47237 + vertex 1.55674 0.934814 2.47115 + endloop + endfacet + facet normal 0.11554 -0.319967 0.940357 + outer loop + vertex 1.56381 0.939841 2.47205 + vertex 1.55827 0.93877 2.47237 + vertex 1.56055 0.935776 2.47107 + endloop + endfacet + facet normal 0.114299 -0.312795 0.942918 + outer loop + vertex 1.56381 0.939841 2.47205 + vertex 1.56302 0.943717 2.47343 + vertex 1.55827 0.93877 2.47237 + endloop + endfacet + facet normal 0.0911274 -0.332677 0.938628 + outer loop + vertex 1.55355 0.935246 2.47162 + vertex 1.55314 0.93908 2.47302 + vertex 1.5491 0.935097 2.472 + endloop + endfacet + facet normal 0.0959076 -0.337004 0.936605 + outer loop + vertex 1.5491 0.935097 2.472 + vertex 1.55314 0.93908 2.47302 + vertex 1.54811 0.938868 2.47346 + endloop + endfacet + facet normal 0.095931 -0.336998 0.936605 + outer loop + vertex 1.5491 0.935097 2.472 + vertex 1.54811 0.938868 2.47346 + vertex 1.54427 0.934798 2.47239 + endloop + endfacet + facet normal 0.0989713 -0.339545 0.935368 + outer loop + vertex 1.54427 0.934798 2.47239 + vertex 1.54811 0.938868 2.47346 + vertex 1.5431 0.938513 2.47386 + endloop + endfacet + facet normal 0.100844 -0.338961 0.93538 + outer loop + vertex 1.54427 0.934798 2.47239 + vertex 1.5431 0.938513 2.47386 + vertex 1.53923 0.934398 2.47278 + endloop + endfacet + facet normal 0.102031 -0.363069 0.926159 + outer loop + vertex 1.54427 0.934798 2.47239 + vertex 1.53923 0.934398 2.47278 + vertex 1.54077 0.930921 2.47125 + endloop + endfacet + facet normal 0.102511 -0.363443 0.925959 + outer loop + vertex 1.54564 0.931322 2.47087 + vertex 1.54427 0.934798 2.47239 + vertex 1.54077 0.930921 2.47125 + endloop + endfacet + facet normal 0.104599 -0.405991 0.907871 + outer loop + vertex 1.54077 0.930921 2.47125 + vertex 1.54231 0.927684 2.46963 + vertex 1.54564 0.931322 2.47087 + endloop + endfacet + facet normal 0.0968248 -0.365591 0.925726 + outer loop + vertex 1.5491 0.935097 2.472 + vertex 1.54427 0.934798 2.47239 + vertex 1.54564 0.931322 2.47087 + endloop + endfacet + facet normal 0.0968032 -0.365574 0.925735 + outer loop + vertex 1.55042 0.931709 2.47052 + vertex 1.5491 0.935097 2.472 + vertex 1.54564 0.931322 2.47087 + endloop + endfacet + facet normal 0.0991457 -0.412647 0.905479 + outer loop + vertex 1.54564 0.931322 2.47087 + vertex 1.54731 0.928094 2.46922 + vertex 1.55042 0.931709 2.47052 + endloop + endfacet + facet normal 0.105132 -0.416852 0.902874 + outer loop + vertex 1.54731 0.928094 2.46922 + vertex 1.55309 0.928495 2.46873 + vertex 1.55042 0.931709 2.47052 + endloop + endfacet + facet normal 0.0952634 -0.423845 0.900711 + outer loop + vertex 1.5542 0.932421 2.47046 + vertex 1.55042 0.931709 2.47052 + vertex 1.55309 0.928495 2.46873 + endloop + endfacet + facet normal 0.0927175 -0.423345 0.901211 + outer loop + vertex 1.5542 0.932421 2.47046 + vertex 1.55309 0.928495 2.46873 + vertex 1.55756 0.932152 2.46999 + endloop + endfacet + facet normal 0.0969838 -0.427704 0.898701 + outer loop + vertex 1.55756 0.932152 2.46999 + vertex 1.55309 0.928495 2.46873 + vertex 1.55896 0.928968 2.46832 + endloop + endfacet + facet normal 0.111676 -0.421812 0.899779 + outer loop + vertex 1.55896 0.928968 2.46832 + vertex 1.56229 0.932774 2.46969 + vertex 1.55756 0.932152 2.46999 + endloop + endfacet + facet normal 0.103764 -0.416182 0.903342 + outer loop + vertex 1.56419 0.929549 2.46799 + vertex 1.56229 0.932774 2.46969 + vertex 1.55896 0.928968 2.46832 + endloop + endfacet + facet normal 0.0841512 -0.36228 0.928263 + outer loop + vertex 1.5542 0.932421 2.47046 + vertex 1.55355 0.935246 2.47162 + vertex 1.55042 0.931709 2.47052 + endloop + endfacet + facet normal 0.106678 -0.474837 0.873584 + outer loop + vertex 1.55309 0.928495 2.46873 + vertex 1.54731 0.928094 2.46922 + vertex 1.54864 0.925048 2.4674 + endloop + endfacet + facet normal 0.107953 -0.408536 0.906336 + outer loop + vertex 1.54231 0.927684 2.46963 + vertex 1.54731 0.928094 2.46922 + vertex 1.54564 0.931322 2.47087 + endloop + endfacet + facet normal 0.110501 -0.470455 0.875478 + outer loop + vertex 1.54402 0.924687 2.4678 + vertex 1.54731 0.928094 2.46922 + vertex 1.54231 0.927684 2.46963 + endloop + endfacet + facet normal 0.0911767 -0.367649 0.925484 + outer loop + vertex 1.55355 0.935246 2.47162 + vertex 1.5491 0.935097 2.472 + vertex 1.55042 0.931709 2.47052 + endloop + endfacet + facet normal 0.104135 -0.341699 0.934022 + outer loop + vertex 1.53923 0.934398 2.47278 + vertex 1.5431 0.938513 2.47386 + vertex 1.53785 0.938556 2.47446 + endloop + endfacet + facet normal 0.104751 -0.341496 0.934028 + outer loop + vertex 1.53923 0.934398 2.47278 + vertex 1.53785 0.938556 2.47446 + vertex 1.53353 0.933401 2.47306 + endloop + endfacet + facet normal 0.107992 -0.362274 0.925794 + outer loop + vertex 1.53923 0.934398 2.47278 + vertex 1.53353 0.933401 2.47306 + vertex 1.53599 0.930371 2.47159 + endloop + endfacet + facet normal 0.106455 -0.361212 0.926387 + outer loop + vertex 1.54077 0.930921 2.47125 + vertex 1.53923 0.934398 2.47278 + vertex 1.53599 0.930371 2.47159 + endloop + endfacet + facet normal 0.0983919 -0.325738 0.940326 + outer loop + vertex 1.54811 0.938868 2.47346 + vertex 1.54697 0.942518 2.47484 + vertex 1.5431 0.938513 2.47386 + endloop + endfacet + facet normal 0.101616 -0.328531 0.939011 + outer loop + vertex 1.5431 0.938513 2.47386 + vertex 1.54697 0.942518 2.47484 + vertex 1.5424 0.94211 2.47519 + endloop + endfacet + facet normal 0.101212 -0.322024 0.941306 + outer loop + vertex 1.5424 0.94211 2.47519 + vertex 1.54697 0.942518 2.47484 + vertex 1.54563 0.945753 2.47609 + endloop + endfacet + facet normal 0.0982801 -0.325773 0.940326 + outer loop + vertex 1.54811 0.938868 2.47346 + vertex 1.55251 0.943515 2.47461 + vertex 1.54697 0.942518 2.47484 + endloop + endfacet + facet normal 0.0976588 -0.322003 0.941688 + outer loop + vertex 1.54697 0.942518 2.47484 + vertex 1.55251 0.943515 2.47461 + vertex 1.5503 0.946498 2.47586 + endloop + endfacet + facet normal 0.0989185 -0.322942 0.941235 + outer loop + vertex 1.54563 0.945753 2.47609 + vertex 1.54697 0.942518 2.47484 + vertex 1.5503 0.946498 2.47586 + endloop + endfacet + facet normal 0.0986011 -0.3207 0.942035 + outer loop + vertex 1.5503 0.946498 2.47586 + vertex 1.54903 0.949777 2.47711 + vertex 1.54563 0.945753 2.47609 + endloop + endfacet + facet normal 0.095753 -0.323629 0.941327 + outer loop + vertex 1.55314 0.93908 2.47302 + vertex 1.55251 0.943515 2.47461 + vertex 1.54811 0.938868 2.47346 + endloop + endfacet + facet normal 0.103916 -0.322319 0.94091 + outer loop + vertex 1.55314 0.93908 2.47302 + vertex 1.55779 0.943362 2.47397 + vertex 1.55251 0.943515 2.47461 + endloop + endfacet + facet normal 0.104029 -0.320688 0.941455 + outer loop + vertex 1.55744 0.947183 2.47531 + vertex 1.55251 0.943515 2.47461 + vertex 1.55779 0.943362 2.47397 + endloop + endfacet + facet normal 0.107229 -0.324658 0.939734 + outer loop + vertex 1.55415 0.947411 2.47577 + vertex 1.55251 0.943515 2.47461 + vertex 1.55744 0.947183 2.47531 + endloop + endfacet + facet normal 0.0983448 -0.321532 0.941778 + outer loop + vertex 1.55415 0.947411 2.47577 + vertex 1.5503 0.946498 2.47586 + vertex 1.55251 0.943515 2.47461 + endloop + endfacet + facet normal 0.122398 -0.318467 0.939999 + outer loop + vertex 1.55779 0.943362 2.47397 + vertex 1.56269 0.948217 2.47498 + vertex 1.55744 0.947183 2.47531 + endloop + endfacet + facet normal 0.122711 -0.320264 0.939347 + outer loop + vertex 1.55744 0.947183 2.47531 + vertex 1.56269 0.948217 2.47498 + vertex 1.56063 0.95097 2.47619 + endloop + endfacet + facet normal 0.130683 -0.314668 0.940163 + outer loop + vertex 1.56441 0.952137 2.47605 + vertex 1.56063 0.95097 2.47619 + vertex 1.56269 0.948217 2.47498 + endloop + endfacet + facet normal 0.1473 -0.320729 0.935647 + outer loop + vertex 1.56441 0.952137 2.47605 + vertex 1.56269 0.948217 2.47498 + vertex 1.56764 0.95208 2.47552 + endloop + endfacet + facet normal 0.148191 -0.308168 0.939719 + outer loop + vertex 1.56764 0.95208 2.47552 + vertex 1.56709 0.954729 2.47648 + vertex 1.56441 0.952137 2.47605 + endloop + endfacet + facet normal 0.139935 -0.30028 0.943531 + outer loop + vertex 1.56709 0.954729 2.47648 + vertex 1.56376 0.954819 2.477 + vertex 1.56441 0.952137 2.47605 + endloop + endfacet + facet normal 0.140563 -0.291876 0.946071 + outer loop + vertex 1.56709 0.954729 2.47648 + vertex 1.56857 0.958731 2.47749 + vertex 1.56376 0.954819 2.477 + endloop + endfacet + facet normal 0.14574 -0.297903 0.943405 + outer loop + vertex 1.56857 0.958731 2.47749 + vertex 1.56323 0.95871 2.47831 + vertex 1.56376 0.954819 2.477 + endloop + endfacet + facet normal 0.126261 -0.301146 0.945182 + outer loop + vertex 1.56376 0.954819 2.477 + vertex 1.56323 0.95871 2.47831 + vertex 1.55849 0.953805 2.47738 + endloop + endfacet + facet normal 0.126564 -0.302958 0.944562 + outer loop + vertex 1.56376 0.954819 2.477 + vertex 1.55849 0.953805 2.47738 + vertex 1.56063 0.95097 2.47619 + endloop + endfacet + facet normal 0.116808 -0.309919 0.94356 + outer loop + vertex 1.56063 0.95097 2.47619 + vertex 1.55849 0.953805 2.47738 + vertex 1.55688 0.94987 2.47629 + endloop + endfacet + facet normal 0.118925 -0.317404 0.940804 + outer loop + vertex 1.55688 0.94987 2.47629 + vertex 1.55744 0.947183 2.47531 + vertex 1.56063 0.95097 2.47619 + endloop + endfacet + facet normal 0.135549 -0.309382 0.941228 + outer loop + vertex 1.55849 0.953805 2.47738 + vertex 1.56323 0.95871 2.47831 + vertex 1.55797 0.95837 2.47896 + endloop + endfacet + facet normal 0.135454 -0.305471 0.942518 + outer loop + vertex 1.56323 0.95871 2.47831 + vertex 1.5627 0.963307 2.47988 + vertex 1.55797 0.95837 2.47896 + endloop + endfacet + facet normal 0.148564 -0.316956 0.936732 + outer loop + vertex 1.55797 0.95837 2.47896 + vertex 1.5627 0.963307 2.47988 + vertex 1.55754 0.962184 2.48032 + endloop + endfacet + facet normal 0.120958 -0.321041 0.939309 + outer loop + vertex 1.55754 0.962184 2.48032 + vertex 1.55265 0.958429 2.47966 + vertex 1.55797 0.95837 2.47896 + endloop + endfacet + facet normal 0.12103 -0.319734 0.939746 + outer loop + vertex 1.55329 0.953989 2.47807 + vertex 1.55797 0.95837 2.47896 + vertex 1.55265 0.958429 2.47966 + endloop + endfacet + facet normal 0.103479 -0.322643 0.940847 + outer loop + vertex 1.55329 0.953989 2.47807 + vertex 1.55265 0.958429 2.47966 + vertex 1.54801 0.953585 2.47851 + endloop + endfacet + facet normal 0.10336 -0.320122 0.941721 + outer loop + vertex 1.54903 0.949777 2.47711 + vertex 1.55329 0.953989 2.47807 + vertex 1.54801 0.953585 2.47851 + endloop + endfacet + facet normal 0.113633 -0.312504 0.943095 + outer loop + vertex 1.55849 0.953805 2.47738 + vertex 1.55797 0.95837 2.47896 + vertex 1.55329 0.953989 2.47807 + endloop + endfacet + facet normal 0.147678 -0.312196 0.938469 + outer loop + vertex 1.55754 0.962184 2.48032 + vertex 1.5627 0.963307 2.47988 + vertex 1.56058 0.966044 2.48112 + endloop + endfacet + facet normal 0.150694 -0.314328 0.937277 + outer loop + vertex 1.55695 0.964855 2.48131 + vertex 1.55754 0.962184 2.48032 + vertex 1.56058 0.966044 2.48112 + endloop + endfacet + facet normal 0.14501 -0.295893 0.94415 + outer loop + vertex 1.56058 0.966044 2.48112 + vertex 1.55844 0.968861 2.48233 + vertex 1.55695 0.964855 2.48131 + endloop + endfacet + facet normal 0.121974 -0.288724 0.949611 + outer loop + vertex 1.55695 0.964855 2.48131 + vertex 1.55844 0.968861 2.48233 + vertex 1.55378 0.965134 2.4818 + endloop + endfacet + facet normal 0.119581 -0.306567 0.944308 + outer loop + vertex 1.55695 0.964855 2.48131 + vertex 1.55378 0.965134 2.4818 + vertex 1.55429 0.962344 2.48083 + endloop + endfacet + facet normal 0.101531 -0.310239 0.945221 + outer loop + vertex 1.55429 0.962344 2.48083 + vertex 1.55378 0.965134 2.4818 + vertex 1.55045 0.961406 2.48093 + endloop + endfacet + facet normal 0.130038 -0.298236 0.945593 + outer loop + vertex 1.55844 0.968861 2.48233 + vertex 1.55329 0.968997 2.48309 + vertex 1.55378 0.965134 2.4818 + endloop + endfacet + facet normal 0.150394 -0.291963 0.944531 + outer loop + vertex 1.56356 0.969961 2.48186 + vertex 1.55844 0.968861 2.48233 + vertex 1.56058 0.966044 2.48112 + endloop + endfacet + facet normal 0.156034 -0.295856 0.942403 + outer loop + vertex 1.56423 0.967295 2.48091 + vertex 1.56356 0.969961 2.48186 + vertex 1.56058 0.966044 2.48112 + endloop + endfacet + facet normal 0.160726 -0.294554 0.942022 + outer loop + vertex 1.5668 0.969922 2.48129 + vertex 1.56356 0.969961 2.48186 + vertex 1.56423 0.967295 2.48091 + endloop + endfacet + facet normal 0.161544 -0.295301 0.941648 + outer loop + vertex 1.56746 0.967259 2.48035 + vertex 1.5668 0.969922 2.48129 + vertex 1.56423 0.967295 2.48091 + endloop + endfacet + facet normal 0.160928 -0.304769 0.938732 + outer loop + vertex 1.56423 0.967295 2.48091 + vertex 1.5627 0.963307 2.47988 + vertex 1.56746 0.967259 2.48035 + endloop + endfacet + facet normal 0.153434 -0.296219 0.942715 + outer loop + vertex 1.56746 0.967259 2.48035 + vertex 1.5627 0.963307 2.47988 + vertex 1.56796 0.963366 2.47904 + endloop + endfacet + facet normal 0.158202 -0.295427 0.942176 + outer loop + vertex 1.56796 0.963366 2.47904 + vertex 1.57264 0.968408 2.47984 + vertex 1.56746 0.967259 2.48035 + endloop + endfacet + facet normal 0.157696 -0.292734 0.943101 + outer loop + vertex 1.56746 0.967259 2.48035 + vertex 1.57264 0.968408 2.47984 + vertex 1.57047 0.971172 2.48106 + endloop + endfacet + facet normal 0.157498 -0.292883 0.943087 + outer loop + vertex 1.57414 0.972405 2.48083 + vertex 1.57047 0.971172 2.48106 + vertex 1.57264 0.968408 2.47984 + endloop + endfacet + facet normal 0.155359 -0.292217 0.943649 + outer loop + vertex 1.57414 0.972405 2.48083 + vertex 1.57264 0.968408 2.47984 + vertex 1.57737 0.972325 2.48027 + endloop + endfacet + facet normal 0.155323 -0.292684 0.94351 + outer loop + vertex 1.57737 0.972325 2.48027 + vertex 1.57672 0.974985 2.4812 + vertex 1.57414 0.972405 2.48083 + endloop + endfacet + facet normal 0.155855 -0.29318 0.943268 + outer loop + vertex 1.57672 0.974985 2.4812 + vertex 1.57347 0.975055 2.48176 + vertex 1.57414 0.972405 2.48083 + endloop + endfacet + facet normal 0.156076 -0.290123 0.944176 + outer loop + vertex 1.57672 0.974985 2.4812 + vertex 1.57823 0.978946 2.48217 + vertex 1.57347 0.975055 2.48176 + endloop + endfacet + facet normal 0.156637 -0.290778 0.943882 + outer loop + vertex 1.57823 0.978946 2.48217 + vertex 1.57299 0.978966 2.48305 + vertex 1.57347 0.975055 2.48176 + endloop + endfacet + facet normal 0.158466 -0.290485 0.943667 + outer loop + vertex 1.57347 0.975055 2.48176 + vertex 1.57299 0.978966 2.48305 + vertex 1.56828 0.973917 2.48228 + endloop + endfacet + facet normal 0.159095 -0.293886 0.942507 + outer loop + vertex 1.57347 0.975055 2.48176 + vertex 1.56828 0.973917 2.48228 + vertex 1.57047 0.971172 2.48106 + endloop + endfacet + facet normal 0.160598 -0.292735 0.942611 + outer loop + vertex 1.57047 0.971172 2.48106 + vertex 1.56828 0.973917 2.48228 + vertex 1.5668 0.969922 2.48129 + endloop + endfacet + facet normal 0.157215 -0.289399 0.944209 + outer loop + vertex 1.56828 0.973917 2.48228 + vertex 1.57299 0.978966 2.48305 + vertex 1.56771 0.978587 2.48381 + endloop + endfacet + facet normal 0.158478 -0.289198 0.94406 + outer loop + vertex 1.56828 0.973917 2.48228 + vertex 1.56771 0.978587 2.48381 + vertex 1.56303 0.97387 2.48315 + endloop + endfacet + facet normal 0.158442 -0.290084 0.943794 + outer loop + vertex 1.56828 0.973917 2.48228 + vertex 1.56303 0.97387 2.48315 + vertex 1.56356 0.969961 2.48186 + endloop + endfacet + facet normal 0.156873 -0.287705 0.944784 + outer loop + vertex 1.56303 0.97387 2.48315 + vertex 1.56771 0.978587 2.48381 + vertex 1.56243 0.97854 2.48467 + endloop + endfacet + facet normal 0.156976 -0.285087 0.94556 + outer loop + vertex 1.56718 0.982523 2.48508 + vertex 1.56243 0.97854 2.48467 + vertex 1.56771 0.978587 2.48381 + endloop + endfacet + facet normal 0.154885 -0.285447 0.945796 + outer loop + vertex 1.56771 0.978587 2.48381 + vertex 1.57255 0.983768 2.48458 + vertex 1.56718 0.982523 2.48508 + endloop + endfacet + facet normal 0.154784 -0.284941 0.945965 + outer loop + vertex 1.56718 0.982523 2.48508 + vertex 1.57255 0.983768 2.48458 + vertex 1.57023 0.986453 2.48577 + endloop + endfacet + facet normal 0.153995 -0.28438 0.946263 + outer loop + vertex 1.56648 0.985162 2.48599 + vertex 1.56718 0.982523 2.48508 + vertex 1.57023 0.986453 2.48577 + endloop + endfacet + facet normal 0.15459 -0.286219 0.945611 + outer loop + vertex 1.57023 0.986453 2.48577 + vertex 1.56807 0.989074 2.48691 + vertex 1.56648 0.985162 2.48599 + endloop + endfacet + facet normal 0.158567 -0.287583 0.944538 + outer loop + vertex 1.56648 0.985162 2.48599 + vertex 1.56807 0.989074 2.48691 + vertex 1.56325 0.985167 2.48653 + endloop + endfacet + facet normal 0.158662 -0.28572 0.945087 + outer loop + vertex 1.56648 0.985162 2.48599 + vertex 1.56325 0.985167 2.48653 + vertex 1.56388 0.982557 2.48564 + endloop + endfacet + facet normal 0.16013 -0.285321 0.944961 + outer loop + vertex 1.56388 0.982557 2.48564 + vertex 1.56325 0.985167 2.48653 + vertex 1.56025 0.981302 2.48588 + endloop + endfacet + facet normal 0.158199 -0.287148 0.944732 + outer loop + vertex 1.56807 0.989074 2.48691 + vertex 1.56293 0.988938 2.48773 + vertex 1.56325 0.985167 2.48653 + endloop + endfacet + facet normal 0.15905 -0.28704 0.944622 + outer loop + vertex 1.56325 0.985167 2.48653 + vertex 1.56293 0.988938 2.48773 + vertex 1.55818 0.984023 2.48704 + endloop + endfacet + facet normal 0.158184 -0.286257 0.945005 + outer loop + vertex 1.55818 0.984023 2.48704 + vertex 1.56293 0.988938 2.48773 + vertex 1.55786 0.988587 2.48848 + endloop + endfacet + facet normal 0.148581 -0.287325 0.946239 + outer loop + vertex 1.55818 0.984023 2.48704 + vertex 1.55786 0.988587 2.48848 + vertex 1.55319 0.98403 2.48783 + endloop + endfacet + facet normal 0.158204 -0.287109 0.944743 + outer loop + vertex 1.56293 0.988938 2.48773 + vertex 1.56271 0.993331 2.48911 + vertex 1.55786 0.988587 2.48848 + endloop + endfacet + facet normal 0.159979 -0.288815 0.943924 + outer loop + vertex 1.55786 0.988587 2.48848 + vertex 1.56271 0.993331 2.48911 + vertex 1.5576 0.993207 2.48993 + endloop + endfacet + facet normal 0.151593 -0.289642 0.945054 + outer loop + vertex 1.55786 0.988587 2.48848 + vertex 1.5576 0.993207 2.48993 + vertex 1.55279 0.988244 2.48918 + endloop + endfacet + facet normal 0.157376 -0.294863 0.942491 + outer loop + vertex 1.55279 0.988244 2.48918 + vertex 1.5576 0.993207 2.48993 + vertex 1.55249 0.992056 2.49043 + endloop + endfacet + facet normal 0.156739 -0.291539 0.94363 + outer loop + vertex 1.55249 0.992056 2.49043 + vertex 1.5576 0.993207 2.48993 + vertex 1.55557 0.995952 2.49112 + endloop + endfacet + facet normal 0.161216 -0.288322 0.943865 + outer loop + vertex 1.55925 0.997217 2.49088 + vertex 1.55557 0.995952 2.49112 + vertex 1.5576 0.993207 2.48993 + endloop + endfacet + facet normal 0.161597 -0.288454 0.943759 + outer loop + vertex 1.55925 0.997217 2.49088 + vertex 1.5576 0.993207 2.48993 + vertex 1.56248 0.997224 2.49033 + endloop + endfacet + facet normal 0.16175 -0.285293 0.944693 + outer loop + vertex 1.56248 0.997224 2.49033 + vertex 1.56188 0.999877 2.49123 + vertex 1.55925 0.997217 2.49088 + endloop + endfacet + facet normal 0.16071 -0.284328 0.945161 + outer loop + vertex 1.56188 0.999877 2.49123 + vertex 1.5586 0.999887 2.49179 + vertex 1.55925 0.997217 2.49088 + endloop + endfacet + facet normal 0.160819 -0.282262 0.945762 + outer loop + vertex 1.56188 0.999877 2.49123 + vertex 1.56336 1.00388 2.49217 + vertex 1.5586 0.999887 2.49179 + endloop + endfacet + facet normal 0.160243 -0.282084 0.945913 + outer loop + vertex 1.56558 1.00121 2.491 + vertex 1.56336 1.00388 2.49217 + vertex 1.56188 0.999877 2.49123 + endloop + endfacet + facet normal 0.160634 -0.281771 0.94594 + outer loop + vertex 1.56849 1.00507 2.49166 + vertex 1.56336 1.00388 2.49217 + vertex 1.56558 1.00121 2.491 + endloop + endfacet + facet normal 0.159212 -0.280789 0.946472 + outer loop + vertex 1.56931 1.00265 2.4908 + vertex 1.56849 1.00507 2.49166 + vertex 1.56558 1.00121 2.491 + endloop + endfacet + facet normal 0.160476 -0.284234 0.945229 + outer loop + vertex 1.56931 1.00265 2.4908 + vertex 1.56558 1.00121 2.491 + vertex 1.56768 0.998531 2.48984 + endloop + endfacet + facet normal 0.161417 -0.284545 0.944976 + outer loop + vertex 1.56931 1.00265 2.4908 + vertex 1.56768 0.998531 2.48984 + vertex 1.57288 1.00316 2.49034 + endloop + endfacet + facet normal 0.161131 -0.281749 0.945862 + outer loop + vertex 1.57288 1.00316 2.49034 + vertex 1.57153 1.00517 2.49117 + vertex 1.56931 1.00265 2.4908 + endloop + endfacet + facet normal 0.162588 -0.28078 0.9459 + outer loop + vertex 1.57367 1.00619 2.49111 + vertex 1.57153 1.00517 2.49117 + vertex 1.57288 1.00316 2.49034 + endloop + endfacet + facet normal 0.159845 -0.274916 0.948088 + outer loop + vertex 1.57367 1.00619 2.49111 + vertex 1.57289 1.00857 2.49193 + vertex 1.57153 1.00517 2.49117 + endloop + endfacet + facet normal 0.159831 -0.274911 0.948092 + outer loop + vertex 1.57153 1.00517 2.49117 + vertex 1.57289 1.00857 2.49193 + vertex 1.56849 1.00507 2.49166 + endloop + endfacet + facet normal 0.161872 -0.277394 0.947022 + outer loop + vertex 1.57289 1.00857 2.49193 + vertex 1.56802 1.00884 2.49284 + vertex 1.56849 1.00507 2.49166 + endloop + endfacet + facet normal 0.162392 -0.27254 0.948341 + outer loop + vertex 1.57289 1.00857 2.49193 + vertex 1.57288 1.01353 2.49336 + vertex 1.56802 1.00884 2.49284 + endloop + endfacet + facet normal 0.164766 -0.274879 0.947256 + outer loop + vertex 1.56802 1.00884 2.49284 + vertex 1.57288 1.01353 2.49336 + vertex 1.56772 1.01337 2.49421 + endloop + endfacet + facet normal 0.161218 -0.275267 0.947754 + outer loop + vertex 1.56802 1.00884 2.49284 + vertex 1.56772 1.01337 2.49421 + vertex 1.56291 1.00857 2.49363 + endloop + endfacet + facet normal 0.16125 -0.27898 0.946662 + outer loop + vertex 1.56336 1.00388 2.49217 + vertex 1.56802 1.00884 2.49284 + vertex 1.56291 1.00857 2.49363 + endloop + endfacet + facet normal 0.159272 -0.279252 0.946917 + outer loop + vertex 1.56336 1.00388 2.49217 + vertex 1.56291 1.00857 2.49363 + vertex 1.55813 1.00379 2.49303 + endloop + endfacet + facet normal 0.159237 -0.280451 0.946568 + outer loop + vertex 1.56336 1.00388 2.49217 + vertex 1.55813 1.00379 2.49303 + vertex 1.5586 0.999887 2.49179 + endloop + endfacet + facet normal 0.155575 -0.281029 0.947005 + outer loop + vertex 1.5586 0.999887 2.49179 + vertex 1.55813 1.00379 2.49303 + vertex 1.55343 0.998785 2.49231 + endloop + endfacet + facet normal 0.155652 -0.281455 0.946866 + outer loop + vertex 1.5586 0.999887 2.49179 + vertex 1.55343 0.998785 2.49231 + vertex 1.55557 0.995952 2.49112 + endloop + endfacet + facet normal 0.157482 -0.27756 0.947713 + outer loop + vertex 1.55813 1.00379 2.49303 + vertex 1.56291 1.00857 2.49363 + vertex 1.55782 1.00824 2.49438 + endloop + endfacet + facet normal 0.152832 -0.278066 0.948326 + outer loop + vertex 1.55813 1.00379 2.49303 + vertex 1.55782 1.00824 2.49438 + vertex 1.55297 1.00357 2.49379 + endloop + endfacet + facet normal 0.151716 -0.27697 0.948825 + outer loop + vertex 1.55297 1.00357 2.49379 + vertex 1.55782 1.00824 2.49438 + vertex 1.55297 1.00821 2.49515 + endloop + endfacet + facet normal 0.157441 -0.275544 0.948308 + outer loop + vertex 1.56291 1.00857 2.49363 + vertex 1.56262 1.01326 2.49504 + vertex 1.55782 1.00824 2.49438 + endloop + endfacet + facet normal 0.15502 -0.273367 0.949336 + outer loop + vertex 1.55782 1.00824 2.49438 + vertex 1.56262 1.01326 2.49504 + vertex 1.55756 1.01202 2.49551 + endloop + endfacet + facet normal 0.154207 -0.269602 0.950545 + outer loop + vertex 1.55756 1.01202 2.49551 + vertex 1.56262 1.01326 2.49504 + vertex 1.56057 1.01591 2.49613 + endloop + endfacet + facet normal 0.153051 -0.270474 0.950484 + outer loop + vertex 1.56425 1.01725 2.49592 + vertex 1.56057 1.01591 2.49613 + vertex 1.56262 1.01326 2.49504 + endloop + endfacet + facet normal 0.160668 -0.27314 0.948462 + outer loop + vertex 1.56425 1.01725 2.49592 + vertex 1.56262 1.01326 2.49504 + vertex 1.56743 1.01729 2.49539 + endloop + endfacet + facet normal 0.160862 -0.267792 0.949953 + outer loop + vertex 1.56743 1.01729 2.49539 + vertex 1.56681 1.01988 2.49622 + vertex 1.56425 1.01725 2.49592 + endloop + endfacet + facet normal 0.153416 -0.260903 0.953097 + outer loop + vertex 1.56681 1.01988 2.49622 + vertex 1.56357 1.01984 2.49673 + vertex 1.56425 1.01725 2.49592 + endloop + endfacet + facet normal 0.153522 -0.256959 0.954151 + outer loop + vertex 1.56681 1.01988 2.49622 + vertex 1.56826 1.02384 2.49706 + vertex 1.56357 1.01984 2.49673 + endloop + endfacet + facet normal 0.153877 -0.257361 0.953985 + outer loop + vertex 1.56826 1.02384 2.49706 + vertex 1.56308 1.02371 2.49786 + vertex 1.56357 1.01984 2.49673 + endloop + endfacet + facet normal 0.149106 -0.25812 0.954537 + outer loop + vertex 1.56357 1.01984 2.49673 + vertex 1.56308 1.02371 2.49786 + vertex 1.55827 1.01853 2.49721 + endloop + endfacet + facet normal 0.149895 -0.261732 0.95343 + outer loop + vertex 1.56357 1.01984 2.49673 + vertex 1.55827 1.01853 2.49721 + vertex 1.56057 1.01591 2.49613 + endloop + endfacet + facet normal 0.155452 -0.263702 0.951996 + outer loop + vertex 1.55827 1.01853 2.49721 + vertex 1.56308 1.02371 2.49786 + vertex 1.55792 1.02348 2.49864 + endloop + endfacet + facet normal 0.155446 -0.261106 0.952712 + outer loop + vertex 1.56308 1.02371 2.49786 + vertex 1.5628 1.02828 2.49916 + vertex 1.55792 1.02348 2.49864 + endloop + endfacet + facet normal 0.162778 -0.268227 0.949504 + outer loop + vertex 1.55792 1.02348 2.49864 + vertex 1.5628 1.02828 2.49916 + vertex 1.55798 1.02835 2.5 + endloop + endfacet + facet normal 0.155118 -0.261139 0.952756 + outer loop + vertex 1.56308 1.02371 2.49786 + vertex 1.56785 1.02855 2.49841 + vertex 1.5628 1.02828 2.49916 + endloop + endfacet + facet normal 0.155143 -0.263126 0.952205 + outer loop + vertex 1.56785 1.02855 2.49841 + vertex 1.56766 1.03349 2.4998 + vertex 1.5628 1.02828 2.49916 + endloop + endfacet + facet normal 0.159675 -0.267119 0.950343 + outer loop + vertex 1.5628 1.02828 2.49916 + vertex 1.56766 1.03349 2.4998 + vertex 1.56251 1.0322 2.50031 + endloop + endfacet + facet normal 0.16021 -0.269562 0.949563 + outer loop + vertex 1.56251 1.0322 2.50031 + vertex 1.56766 1.03349 2.4998 + vertex 1.56547 1.03616 2.50093 + endloop + endfacet + facet normal 0.163833 -0.26668 0.949758 + outer loop + vertex 1.56928 1.03766 2.50069 + vertex 1.56547 1.03616 2.50093 + vertex 1.56766 1.03349 2.4998 + endloop + endfacet + facet normal 0.162991 -0.2664 0.949981 + outer loop + vertex 1.56928 1.03766 2.50069 + vertex 1.56766 1.03349 2.4998 + vertex 1.57302 1.03815 2.50019 + endloop + endfacet + facet normal 0.162527 -0.261357 0.951461 + outer loop + vertex 1.57302 1.03815 2.50019 + vertex 1.57165 1.04034 2.50103 + vertex 1.56928 1.03766 2.50069 + endloop + endfacet + facet normal 0.163078 -0.261817 0.95124 + outer loop + vertex 1.57165 1.04034 2.50103 + vertex 1.56842 1.04011 2.50152 + vertex 1.56928 1.03766 2.50069 + endloop + endfacet + facet normal 0.16277 -0.251095 0.954179 + outer loop + vertex 1.57165 1.04034 2.50103 + vertex 1.5729 1.04395 2.50176 + vertex 1.56842 1.04011 2.50152 + endloop + endfacet + facet normal 0.16027 -0.26338 0.951286 + outer loop + vertex 1.57302 1.03815 2.50019 + vertex 1.56766 1.03349 2.4998 + vertex 1.57278 1.03344 2.49893 + endloop + endfacet + facet normal 0.162153 -0.262162 0.951303 + outer loop + vertex 1.56928 1.03766 2.50069 + vertex 1.56842 1.04011 2.50152 + vertex 1.56547 1.03616 2.50093 + endloop + endfacet + facet normal 0.1721 -0.269051 0.947625 + outer loop + vertex 1.56842 1.04011 2.50152 + vertex 1.56309 1.03875 2.5021 + vertex 1.56547 1.03616 2.50093 + endloop + endfacet + facet normal 0.160307 -0.262711 0.951464 + outer loop + vertex 1.56785 1.02855 2.49841 + vertex 1.57278 1.03344 2.49893 + vertex 1.56766 1.03349 2.4998 + endloop + endfacet + facet normal 0.159788 -0.262213 0.951689 + outer loop + vertex 1.57291 1.02886 2.49764 + vertex 1.57278 1.03344 2.49893 + vertex 1.56785 1.02855 2.49841 + endloop + endfacet + facet normal 0.159732 -0.259211 0.952521 + outer loop + vertex 1.56826 1.02384 2.49706 + vertex 1.57291 1.02886 2.49764 + vertex 1.56785 1.02855 2.49841 + endloop + endfacet + facet normal 0.161959 -0.26117 0.951609 + outer loop + vertex 1.57332 1.02514 2.49655 + vertex 1.57291 1.02886 2.49764 + vertex 1.56826 1.02384 2.49706 + endloop + endfacet + facet normal 0.161729 -0.260144 0.951929 + outer loop + vertex 1.57332 1.02514 2.49655 + vertex 1.56826 1.02384 2.49706 + vertex 1.57043 1.02124 2.49598 + endloop + endfacet + facet normal 0.165829 -0.262965 0.950447 + outer loop + vertex 1.57416 1.02272 2.49574 + vertex 1.57332 1.02514 2.49655 + vertex 1.57043 1.02124 2.49598 + endloop + endfacet + facet normal 0.167413 -0.267182 0.948993 + outer loop + vertex 1.57416 1.02272 2.49574 + vertex 1.57043 1.02124 2.49598 + vertex 1.57261 1.01857 2.49484 + endloop + endfacet + facet normal 0.168892 -0.267647 0.948599 + outer loop + vertex 1.57416 1.02272 2.49574 + vertex 1.57261 1.01857 2.49484 + vertex 1.57794 1.02322 2.4952 + endloop + endfacet + facet normal 0.168631 -0.264766 0.949454 + outer loop + vertex 1.57794 1.02322 2.4952 + vertex 1.5765 1.02538 2.49606 + vertex 1.57416 1.02272 2.49574 + endloop + endfacet + facet normal 0.168191 -0.26687 0.948943 + outer loop + vertex 1.57794 1.02322 2.4952 + vertex 1.57261 1.01857 2.49484 + vertex 1.57789 1.01846 2.49387 + endloop + endfacet + facet normal 0.16795 -0.270259 0.948026 + outer loop + vertex 1.57288 1.01353 2.49336 + vertex 1.57789 1.01846 2.49387 + vertex 1.57261 1.01857 2.49484 + endloop + endfacet + facet normal 0.165559 -0.267938 0.949104 + outer loop + vertex 1.57836 1.0133 2.49234 + vertex 1.57789 1.01846 2.49387 + vertex 1.57288 1.01353 2.49336 + endloop + endfacet + facet normal 0.168751 -0.267518 0.948661 + outer loop + vertex 1.57836 1.0133 2.49234 + vertex 1.58308 1.01874 2.49303 + vertex 1.57789 1.01846 2.49387 + endloop + endfacet + facet normal 0.168738 -0.265968 0.949099 + outer loop + vertex 1.58308 1.01874 2.49303 + vertex 1.58277 1.02329 2.49436 + vertex 1.57789 1.01846 2.49387 + endloop + endfacet + facet normal 0.166452 -0.267947 0.948946 + outer loop + vertex 1.56743 1.01729 2.49539 + vertex 1.57261 1.01857 2.49484 + vertex 1.57043 1.02124 2.49598 + endloop + endfacet + facet normal 0.167521 -0.272952 0.94733 + outer loop + vertex 1.56772 1.01337 2.49421 + vertex 1.57261 1.01857 2.49484 + vertex 1.56743 1.01729 2.49539 + endloop + endfacet + facet normal 0.166271 -0.262802 0.950415 + outer loop + vertex 1.5765 1.02538 2.49606 + vertex 1.57332 1.02514 2.49655 + vertex 1.57416 1.02272 2.49574 + endloop + endfacet + facet normal 0.166231 -0.261585 0.950758 + outer loop + vertex 1.5765 1.02538 2.49606 + vertex 1.57779 1.02897 2.49682 + vertex 1.57332 1.02514 2.49655 + endloop + endfacet + facet normal 0.165412 -0.260657 0.951156 + outer loop + vertex 1.57779 1.02897 2.49682 + vertex 1.57291 1.02886 2.49764 + vertex 1.57332 1.02514 2.49655 + endloop + endfacet + facet normal 0.165464 -0.261806 0.950831 + outer loop + vertex 1.57291 1.02886 2.49764 + vertex 1.57782 1.03358 2.49809 + vertex 1.57278 1.03344 2.49893 + endloop + endfacet + facet normal 0.165456 -0.262292 0.950698 + outer loop + vertex 1.57782 1.03358 2.49809 + vertex 1.57773 1.0382 2.49938 + vertex 1.57278 1.03344 2.49893 + endloop + endfacet + facet normal 0.153836 -0.259938 0.953293 + outer loop + vertex 1.56826 1.02384 2.49706 + vertex 1.56785 1.02855 2.49841 + vertex 1.56308 1.02371 2.49786 + endloop + endfacet + facet normal 0.162283 -0.259694 0.951958 + outer loop + vertex 1.57043 1.02124 2.49598 + vertex 1.56826 1.02384 2.49706 + vertex 1.56681 1.01988 2.49622 + endloop + endfacet + facet normal 0.164759 -0.266753 0.949577 + outer loop + vertex 1.56681 1.01988 2.49622 + vertex 1.56743 1.01729 2.49539 + vertex 1.57043 1.02124 2.49598 + endloop + endfacet + facet normal 0.161152 -0.273697 0.948219 + outer loop + vertex 1.56743 1.01729 2.49539 + vertex 1.56262 1.01326 2.49504 + vertex 1.56772 1.01337 2.49421 + endloop + endfacet + facet normal 0.150084 -0.261866 0.953363 + outer loop + vertex 1.56425 1.01725 2.49592 + vertex 1.56357 1.01984 2.49673 + vertex 1.56057 1.01591 2.49613 + endloop + endfacet + facet normal 0.161113 -0.275167 0.9478 + outer loop + vertex 1.56291 1.00857 2.49363 + vertex 1.56772 1.01337 2.49421 + vertex 1.56262 1.01326 2.49504 + endloop + endfacet + facet normal 0.164828 -0.270561 0.948488 + outer loop + vertex 1.57288 1.01353 2.49336 + vertex 1.57261 1.01857 2.49484 + vertex 1.56772 1.01337 2.49421 + endloop + endfacet + facet normal 0.165148 -0.27241 0.947902 + outer loop + vertex 1.57836 1.0133 2.49234 + vertex 1.57288 1.01353 2.49336 + vertex 1.57289 1.00857 2.49193 + endloop + endfacet + facet normal 0.164168 -0.27132 0.948385 + outer loop + vertex 1.57708 1.00774 2.49097 + vertex 1.57836 1.0133 2.49234 + vertex 1.57289 1.00857 2.49193 + endloop + endfacet + facet normal 0.162078 -0.270954 0.948849 + outer loop + vertex 1.58122 1.01128 2.49127 + vertex 1.57836 1.0133 2.49234 + vertex 1.57708 1.00774 2.49097 + endloop + endfacet + facet normal 0.16603 -0.275395 0.946885 + outer loop + vertex 1.57708 1.00774 2.49097 + vertex 1.58262 1.00836 2.49017 + vertex 1.58122 1.01128 2.49127 + endloop + endfacet + facet normal 0.166142 -0.277031 0.946388 + outer loop + vertex 1.57769 1.00328 2.48955 + vertex 1.58262 1.00836 2.49017 + vertex 1.57708 1.00774 2.49097 + endloop + endfacet + facet normal 0.162464 -0.27768 0.946836 + outer loop + vertex 1.57708 1.00774 2.49097 + vertex 1.57288 1.00316 2.49034 + vertex 1.57769 1.00328 2.48955 + endloop + endfacet + facet normal 0.16236 -0.282205 0.945515 + outer loop + vertex 1.5728 0.99851 2.48897 + vertex 1.57769 1.00328 2.48955 + vertex 1.57288 1.00316 2.49034 + endloop + endfacet + facet normal 0.159646 -0.279578 0.946757 + outer loop + vertex 1.57786 0.998618 2.48815 + vertex 1.57769 1.00328 2.48955 + vertex 1.5728 0.99851 2.48897 + endloop + endfacet + facet normal 0.159555 -0.283056 0.945738 + outer loop + vertex 1.5729 0.993998 2.4876 + vertex 1.57786 0.998618 2.48815 + vertex 1.5728 0.99851 2.48897 + endloop + endfacet + facet normal 0.157036 -0.283225 0.94611 + outer loop + vertex 1.5729 0.993998 2.4876 + vertex 1.5728 0.99851 2.48897 + vertex 1.56782 0.993685 2.48835 + endloop + endfacet + facet normal 0.157085 -0.286203 0.945205 + outer loop + vertex 1.56807 0.989074 2.48691 + vertex 1.5729 0.993998 2.4876 + vertex 1.56782 0.993685 2.48835 + endloop + endfacet + facet normal 0.154562 -0.283884 0.946319 + outer loop + vertex 1.57325 0.990314 2.48644 + vertex 1.5729 0.993998 2.4876 + vertex 1.56807 0.989074 2.48691 + endloop + endfacet + facet normal 0.156371 -0.283644 0.946094 + outer loop + vertex 1.57782 0.994064 2.48681 + vertex 1.5729 0.993998 2.4876 + vertex 1.57325 0.990314 2.48644 + endloop + endfacet + facet normal 0.153766 -0.2806 0.947428 + outer loop + vertex 1.5765 0.990509 2.48597 + vertex 1.57782 0.994064 2.48681 + vertex 1.57325 0.990314 2.48644 + endloop + endfacet + facet normal 0.153829 -0.284362 0.946296 + outer loop + vertex 1.5765 0.990509 2.48597 + vertex 1.57325 0.990314 2.48644 + vertex 1.57408 0.987878 2.48557 + endloop + endfacet + facet normal 0.156849 -0.28694 0.945021 + outer loop + vertex 1.57795 0.988322 2.48507 + vertex 1.5765 0.990509 2.48597 + vertex 1.57408 0.987878 2.48557 + endloop + endfacet + facet normal 0.156846 -0.286906 0.945031 + outer loop + vertex 1.57408 0.987878 2.48557 + vertex 1.57255 0.983768 2.48458 + vertex 1.57795 0.988322 2.48507 + endloop + endfacet + facet normal 0.156937 -0.287008 0.944985 + outer loop + vertex 1.57795 0.988322 2.48507 + vertex 1.57255 0.983768 2.48458 + vertex 1.57788 0.983679 2.48367 + endloop + endfacet + facet normal 0.162259 -0.286828 0.944141 + outer loop + vertex 1.57788 0.983679 2.48367 + vertex 1.58276 0.988332 2.48424 + vertex 1.57795 0.988322 2.48507 + endloop + endfacet + facet normal 0.162286 -0.286273 0.944304 + outer loop + vertex 1.58249 0.992104 2.48543 + vertex 1.57795 0.988322 2.48507 + vertex 1.58276 0.988332 2.48424 + endloop + endfacet + facet normal 0.16967 -0.285407 0.943268 + outer loop + vertex 1.58276 0.988332 2.48424 + vertex 1.58754 0.993367 2.48491 + vertex 1.58249 0.992104 2.48543 + endloop + endfacet + facet normal 0.169411 -0.284201 0.943679 + outer loop + vertex 1.58249 0.992104 2.48543 + vertex 1.58754 0.993367 2.48491 + vertex 1.58546 0.996021 2.48608 + endloop + endfacet + facet normal 0.166887 -0.282448 0.944654 + outer loop + vertex 1.58169 0.994558 2.48631 + vertex 1.58249 0.992104 2.48543 + vertex 1.58546 0.996021 2.48608 + endloop + endfacet + facet normal 0.164998 -0.277297 0.94651 + outer loop + vertex 1.58546 0.996021 2.48608 + vertex 1.58317 0.998639 2.48724 + vertex 1.58169 0.994558 2.48631 + endloop + endfacet + facet normal 0.158147 -0.275216 0.948286 + outer loop + vertex 1.58169 0.994558 2.48631 + vertex 1.58317 0.998639 2.48724 + vertex 1.57782 0.994064 2.48681 + endloop + endfacet + facet normal 0.15852 -0.279464 0.94698 + outer loop + vertex 1.58169 0.994558 2.48631 + vertex 1.57782 0.994064 2.48681 + vertex 1.57932 0.991929 2.48593 + endloop + endfacet + facet normal 0.162168 -0.279731 0.946283 + outer loop + vertex 1.58317 0.998639 2.48724 + vertex 1.57786 0.998618 2.48815 + vertex 1.57782 0.994064 2.48681 + endloop + endfacet + facet normal 0.16231 -0.276563 0.94719 + outer loop + vertex 1.58317 0.998639 2.48724 + vertex 1.58284 1.00348 2.48872 + vertex 1.57786 0.998618 2.48815 + endloop + endfacet + facet normal 0.16773 -0.275954 0.946423 + outer loop + vertex 1.58317 0.998639 2.48724 + vertex 1.58804 1.00387 2.48791 + vertex 1.58284 1.00348 2.48872 + endloop + endfacet + facet normal 0.167652 -0.273149 0.94725 + outer loop + vertex 1.58804 1.00387 2.48791 + vertex 1.58771 1.00834 2.48926 + vertex 1.58284 1.00348 2.48872 + endloop + endfacet + facet normal 0.166888 -0.275708 0.946643 + outer loop + vertex 1.58849 1.00002 2.48671 + vertex 1.58317 0.998639 2.48724 + vertex 1.58546 0.996021 2.48608 + endloop + endfacet + facet normal 0.163491 -0.283636 0.944892 + outer loop + vertex 1.58249 0.992104 2.48543 + vertex 1.58169 0.994558 2.48631 + vertex 1.57932 0.991929 2.48593 + endloop + endfacet + facet normal 0.167962 -0.283886 0.944032 + outer loop + vertex 1.5878 0.988694 2.48345 + vertex 1.58754 0.993367 2.48491 + vertex 1.58276 0.988332 2.48424 + endloop + endfacet + facet normal 0.167976 -0.28449 0.943848 + outer loop + vertex 1.58298 0.983914 2.48287 + vertex 1.5878 0.988694 2.48345 + vertex 1.58276 0.988332 2.48424 + endloop + endfacet + facet normal 0.166209 -0.282808 0.944666 + outer loop + vertex 1.58812 0.984055 2.48201 + vertex 1.5878 0.988694 2.48345 + vertex 1.58298 0.983914 2.48287 + endloop + endfacet + facet normal 0.166202 -0.283129 0.944571 + outer loop + vertex 1.58812 0.984055 2.48201 + vertex 1.58298 0.983914 2.48287 + vertex 1.58334 0.980058 2.48165 + endloop + endfacet + facet normal 0.163524 -0.280052 0.945955 + outer loop + vertex 1.58655 0.980046 2.48109 + vertex 1.58812 0.984055 2.48201 + vertex 1.58334 0.980058 2.48165 + endloop + endfacet + facet normal 0.163229 -0.285498 0.944377 + outer loop + vertex 1.58655 0.980046 2.48109 + vertex 1.58334 0.980058 2.48165 + vertex 1.58397 0.977416 2.48074 + endloop + endfacet + facet normal 0.168977 -0.290776 0.941752 + outer loop + vertex 1.58722 0.977428 2.48017 + vertex 1.58655 0.980046 2.48109 + vertex 1.58397 0.977416 2.48074 + endloop + endfacet + facet normal 0.168706 -0.296129 0.940131 + outer loop + vertex 1.58397 0.977416 2.48074 + vertex 1.5825 0.973441 2.47976 + vertex 1.58722 0.977428 2.48017 + endloop + endfacet + facet normal 0.165953 -0.293018 0.941594 + outer loop + vertex 1.58722 0.977428 2.48017 + vertex 1.5825 0.973441 2.47976 + vertex 1.58773 0.973536 2.47886 + endloop + endfacet + facet normal 0.174821 -0.291474 0.940468 + outer loop + vertex 1.58773 0.973536 2.47886 + vertex 1.59254 0.978805 2.4796 + vertex 1.58722 0.977428 2.48017 + endloop + endfacet + facet normal 0.174176 -0.288565 0.941484 + outer loop + vertex 1.58722 0.977428 2.48017 + vertex 1.59254 0.978805 2.4796 + vertex 1.59025 0.981429 2.48083 + endloop + endfacet + facet normal 0.177705 -0.285604 0.941728 + outer loop + vertex 1.59409 0.982969 2.48057 + vertex 1.59025 0.981429 2.48083 + vertex 1.59254 0.978805 2.4796 + endloop + endfacet + facet normal 0.166901 -0.28229 0.944699 + outer loop + vertex 1.59409 0.982969 2.48057 + vertex 1.59254 0.978805 2.4796 + vertex 1.59795 0.983435 2.48003 + endloop + endfacet + facet normal 0.166485 -0.276903 0.946366 + outer loop + vertex 1.59795 0.983435 2.48003 + vertex 1.59653 0.985685 2.48094 + vertex 1.59409 0.982969 2.48057 + endloop + endfacet + facet normal 0.166853 -0.282237 0.944724 + outer loop + vertex 1.59795 0.983435 2.48003 + vertex 1.59254 0.978805 2.4796 + vertex 1.59787 0.978802 2.47866 + endloop + endfacet + facet normal 0.170462 -0.287767 0.942408 + outer loop + vertex 1.59298 0.974021 2.47806 + vertex 1.59254 0.978805 2.4796 + vertex 1.58773 0.973536 2.47886 + endloop + endfacet + facet normal 0.170523 -0.289147 0.941974 + outer loop + vertex 1.58832 0.968861 2.47732 + vertex 1.59298 0.974021 2.47806 + vertex 1.58773 0.973536 2.47886 + endloop + endfacet + facet normal 0.163729 -0.290283 0.94283 + outer loop + vertex 1.58832 0.968861 2.47732 + vertex 1.58773 0.973536 2.47886 + vertex 1.58309 0.9688 2.47821 + endloop + endfacet + facet normal 0.163679 -0.291542 0.94245 + outer loop + vertex 1.58832 0.968861 2.47732 + vertex 1.58309 0.9688 2.47821 + vertex 1.58367 0.964891 2.4769 + endloop + endfacet + facet normal 0.158417 -0.292523 0.943045 + outer loop + vertex 1.58367 0.964891 2.4769 + vertex 1.58309 0.9688 2.47821 + vertex 1.57852 0.963777 2.47742 + endloop + endfacet + facet normal 0.158867 -0.294996 0.942199 + outer loop + vertex 1.58367 0.964891 2.4769 + vertex 1.57852 0.963777 2.47742 + vertex 1.58071 0.961003 2.47618 + endloop + endfacet + facet normal 0.158934 -0.295043 0.942173 + outer loop + vertex 1.58434 0.962223 2.47595 + vertex 1.58367 0.964891 2.4769 + vertex 1.58071 0.961003 2.47618 + endloop + endfacet + facet normal 0.160619 -0.300439 0.94018 + outer loop + vertex 1.58434 0.962223 2.47595 + vertex 1.58071 0.961003 2.47618 + vertex 1.58269 0.958269 2.47497 + endloop + endfacet + facet normal 0.164831 -0.301905 0.93898 + outer loop + vertex 1.58434 0.962223 2.47595 + vertex 1.58269 0.958269 2.47497 + vertex 1.58749 0.962191 2.47539 + endloop + endfacet + facet normal 0.165067 -0.298295 0.940092 + outer loop + vertex 1.58749 0.962191 2.47539 + vertex 1.5869 0.964829 2.47633 + vertex 1.58434 0.962223 2.47595 + endloop + endfacet + facet normal 0.168983 -0.297279 0.939718 + outer loop + vertex 1.5869 0.964829 2.47633 + vertex 1.58749 0.962191 2.47539 + vertex 1.59049 0.966108 2.47609 + endloop + endfacet + facet normal 0.166726 -0.290452 0.942253 + outer loop + vertex 1.59049 0.966108 2.47609 + vertex 1.58832 0.968861 2.47732 + vertex 1.5869 0.964829 2.47633 + endloop + endfacet + facet normal 0.161305 -0.288891 0.943675 + outer loop + vertex 1.5869 0.964829 2.47633 + vertex 1.58832 0.968861 2.47732 + vertex 1.58367 0.964891 2.4769 + endloop + endfacet + facet normal 0.169039 -0.288683 0.942384 + outer loop + vertex 1.59346 0.970082 2.47677 + vertex 1.58832 0.968861 2.47732 + vertex 1.59049 0.966108 2.47609 + endloop + endfacet + facet normal 0.170914 -0.298621 0.938943 + outer loop + vertex 1.58749 0.962191 2.47539 + vertex 1.59256 0.963403 2.47485 + vertex 1.59049 0.966108 2.47609 + endloop + endfacet + facet normal 0.171572 -0.301888 0.937778 + outer loop + vertex 1.58772 0.958385 2.47412 + vertex 1.59256 0.963403 2.47485 + vertex 1.58749 0.962191 2.47539 + endloop + endfacet + facet normal 0.170273 -0.300725 0.938388 + outer loop + vertex 1.59282 0.958745 2.47331 + vertex 1.59256 0.963403 2.47485 + vertex 1.58772 0.958385 2.47412 + endloop + endfacet + facet normal 0.170326 -0.303476 0.937492 + outer loop + vertex 1.58789 0.954085 2.4727 + vertex 1.59282 0.958745 2.47331 + vertex 1.58772 0.958385 2.47412 + endloop + endfacet + facet normal 0.165526 -0.303905 0.938213 + outer loop + vertex 1.58789 0.954085 2.4727 + vertex 1.58772 0.958385 2.47412 + vertex 1.58284 0.953685 2.47346 + endloop + endfacet + facet normal 0.165566 -0.305271 0.937762 + outer loop + vertex 1.5831 0.949155 2.47194 + vertex 1.58789 0.954085 2.4727 + vertex 1.58284 0.953685 2.47346 + endloop + endfacet + facet normal 0.162644 -0.305573 0.938175 + outer loop + vertex 1.5831 0.949155 2.47194 + vertex 1.58284 0.953685 2.47346 + vertex 1.57796 0.949003 2.47278 + endloop + endfacet + facet normal 0.162666 -0.304647 0.938472 + outer loop + vertex 1.5831 0.949155 2.47194 + vertex 1.57796 0.949003 2.47278 + vertex 1.57824 0.94523 2.47151 + endloop + endfacet + facet normal 0.160715 -0.302353 0.93955 + outer loop + vertex 1.58149 0.94522 2.47095 + vertex 1.5831 0.949155 2.47194 + vertex 1.57824 0.94523 2.47151 + endloop + endfacet + facet normal 0.160944 -0.298289 0.940808 + outer loop + vertex 1.58149 0.94522 2.47095 + vertex 1.57824 0.94523 2.47151 + vertex 1.57885 0.942604 2.47057 + endloop + endfacet + facet normal 0.156456 -0.294057 0.942896 + outer loop + vertex 1.58213 0.942577 2.47002 + vertex 1.58149 0.94522 2.47095 + vertex 1.57885 0.942604 2.47057 + endloop + endfacet + facet normal 0.156328 -0.296218 0.94224 + outer loop + vertex 1.57885 0.942604 2.47057 + vertex 1.57733 0.938657 2.46958 + vertex 1.58213 0.942577 2.47002 + endloop + endfacet + facet normal 0.158272 -0.296838 0.94172 + outer loop + vertex 1.57885 0.942604 2.47057 + vertex 1.57516 0.941364 2.4708 + vertex 1.57733 0.938657 2.46958 + endloop + endfacet + facet normal 0.158895 -0.298827 0.940986 + outer loop + vertex 1.57885 0.942604 2.47057 + vertex 1.57824 0.94523 2.47151 + vertex 1.57516 0.941364 2.4708 + endloop + endfacet + facet normal 0.15915 -0.299011 0.940885 + outer loop + vertex 1.57824 0.94523 2.47151 + vertex 1.57311 0.944098 2.47202 + vertex 1.57516 0.941364 2.4708 + endloop + endfacet + facet normal 0.15607 -0.30124 0.940689 + outer loop + vertex 1.57516 0.941364 2.4708 + vertex 1.57311 0.944098 2.47202 + vertex 1.57148 0.940172 2.47103 + endloop + endfacet + facet normal 0.157931 -0.293662 0.942773 + outer loop + vertex 1.58149 0.94522 2.47095 + vertex 1.58213 0.942577 2.47002 + vertex 1.58523 0.946528 2.47073 + endloop + endfacet + facet normal 0.158848 -0.294319 0.942414 + outer loop + vertex 1.58213 0.942577 2.47002 + vertex 1.58747 0.94384 2.46951 + vertex 1.58523 0.946528 2.47073 + endloop + endfacet + facet normal 0.160983 -0.29262 0.942581 + outer loop + vertex 1.58906 0.947971 2.47052 + vertex 1.58523 0.946528 2.47073 + vertex 1.58747 0.94384 2.46951 + endloop + endfacet + facet normal 0.166082 -0.294246 0.941189 + outer loop + vertex 1.58906 0.947971 2.47052 + vertex 1.58747 0.94384 2.46951 + vertex 1.59295 0.948436 2.46998 + endloop + endfacet + facet normal 0.166521 -0.30019 0.939232 + outer loop + vertex 1.59295 0.948436 2.46998 + vertex 1.59146 0.950625 2.47095 + vertex 1.58906 0.947971 2.47052 + endloop + endfacet + facet normal 0.166021 -0.299774 0.939453 + outer loop + vertex 1.59146 0.950625 2.47095 + vertex 1.58823 0.950421 2.47145 + vertex 1.58906 0.947971 2.47052 + endloop + endfacet + facet normal 0.16603 -0.300473 0.939228 + outer loop + vertex 1.59146 0.950625 2.47095 + vertex 1.59278 0.954219 2.47186 + vertex 1.58823 0.950421 2.47145 + endloop + endfacet + facet normal 0.168667 -0.303475 0.937792 + outer loop + vertex 1.59278 0.954219 2.47186 + vertex 1.58789 0.954085 2.4727 + vertex 1.58823 0.950421 2.47145 + endloop + endfacet + facet normal 0.164249 -0.304085 0.938379 + outer loop + vertex 1.58823 0.950421 2.47145 + vertex 1.58789 0.954085 2.4727 + vertex 1.5831 0.949155 2.47194 + endloop + endfacet + facet normal 0.163448 -0.300314 0.939732 + outer loop + vertex 1.58823 0.950421 2.47145 + vertex 1.5831 0.949155 2.47194 + vertex 1.58523 0.946528 2.47073 + endloop + endfacet + facet normal 0.170036 -0.30167 0.938128 + outer loop + vertex 1.59429 0.952077 2.4709 + vertex 1.59278 0.954219 2.47186 + vertex 1.59146 0.950625 2.47095 + endloop + endfacet + facet normal 0.17256 -0.299941 0.938221 + outer loop + vertex 1.59667 0.954759 2.47132 + vertex 1.59278 0.954219 2.47186 + vertex 1.59429 0.952077 2.4709 + endloop + endfacet + facet normal 0.174648 -0.30165 0.937286 + outer loop + vertex 1.59754 0.952291 2.47037 + vertex 1.59667 0.954759 2.47132 + vertex 1.59429 0.952077 2.4709 + endloop + endfacet + facet normal 0.174635 -0.300603 0.937625 + outer loop + vertex 1.59429 0.952077 2.4709 + vertex 1.59295 0.948436 2.46998 + vertex 1.59754 0.952291 2.47037 + endloop + endfacet + facet normal 0.170466 -0.29587 0.939895 + outer loop + vertex 1.59754 0.952291 2.47037 + vertex 1.59295 0.948436 2.46998 + vertex 1.59795 0.948449 2.46908 + endloop + endfacet + facet normal 0.170606 -0.295849 0.939876 + outer loop + vertex 1.59795 0.948449 2.46908 + vertex 1.60272 0.953541 2.46982 + vertex 1.59754 0.952291 2.47037 + endloop + endfacet + facet normal 0.171074 -0.298146 0.939065 + outer loop + vertex 1.59754 0.952291 2.47037 + vertex 1.60272 0.953541 2.46982 + vertex 1.60051 0.956259 2.47108 + endloop + endfacet + facet normal 0.169485 -0.294873 0.940385 + outer loop + vertex 1.60321 0.948894 2.46827 + vertex 1.60272 0.953541 2.46982 + vertex 1.59795 0.948449 2.46908 + endloop + endfacet + facet normal 0.169283 -0.289252 0.942166 + outer loop + vertex 1.59826 0.943632 2.46755 + vertex 1.60321 0.948894 2.46827 + vertex 1.59795 0.948449 2.46908 + endloop + endfacet + facet normal 0.169297 -0.289251 0.942164 + outer loop + vertex 1.59826 0.943632 2.46755 + vertex 1.59795 0.948449 2.46908 + vertex 1.59284 0.943725 2.46855 + endloop + endfacet + facet normal 0.169072 -0.292378 0.941238 + outer loop + vertex 1.59826 0.943632 2.46755 + vertex 1.59284 0.943725 2.46855 + vertex 1.59271 0.939031 2.46711 + endloop + endfacet + facet normal 0.170733 -0.290724 0.941451 + outer loop + vertex 1.59284 0.943725 2.46855 + vertex 1.59795 0.948449 2.46908 + vertex 1.59295 0.948436 2.46998 + endloop + endfacet + facet normal 0.175674 -0.301264 0.937219 + outer loop + vertex 1.59667 0.954759 2.47132 + vertex 1.59754 0.952291 2.47037 + vertex 1.60051 0.956259 2.47108 + endloop + endfacet + facet normal 0.176308 -0.302995 0.936541 + outer loop + vertex 1.60051 0.956259 2.47108 + vertex 1.59818 0.958843 2.47236 + vertex 1.59667 0.954759 2.47132 + endloop + endfacet + facet normal 0.168518 -0.309669 0.935792 + outer loop + vertex 1.60357 0.960184 2.47183 + vertex 1.59818 0.958843 2.47236 + vertex 1.60051 0.956259 2.47108 + endloop + endfacet + facet normal 0.172743 -0.301934 0.937548 + outer loop + vertex 1.59667 0.954759 2.47132 + vertex 1.59818 0.958843 2.47236 + vertex 1.59278 0.954219 2.47186 + endloop + endfacet + facet normal 0.172533 -0.301701 0.937662 + outer loop + vertex 1.59818 0.958843 2.47236 + vertex 1.59282 0.958745 2.47331 + vertex 1.59278 0.954219 2.47186 + endloop + endfacet + facet normal 0.172586 -0.300281 0.938107 + outer loop + vertex 1.59818 0.958843 2.47236 + vertex 1.59777 0.963533 2.47394 + vertex 1.59282 0.958745 2.47331 + endloop + endfacet + facet normal 0.159625 -0.302003 0.939848 + outer loop + vertex 1.59818 0.958843 2.47236 + vertex 1.60304 0.963954 2.47317 + vertex 1.59777 0.963533 2.47394 + endloop + endfacet + facet normal 0.168588 -0.298811 0.939303 + outer loop + vertex 1.59429 0.952077 2.4709 + vertex 1.59146 0.950625 2.47095 + vertex 1.59295 0.948436 2.46998 + endloop + endfacet + facet normal 0.163172 -0.290931 0.942727 + outer loop + vertex 1.59295 0.948436 2.46998 + vertex 1.58747 0.94384 2.46951 + vertex 1.59284 0.943725 2.46855 + endloop + endfacet + facet normal 0.163015 -0.293031 0.942103 + outer loop + vertex 1.58768 0.939054 2.46799 + vertex 1.59284 0.943725 2.46855 + vertex 1.58747 0.94384 2.46951 + endloop + endfacet + facet normal 0.163816 -0.30057 0.939586 + outer loop + vertex 1.58906 0.947971 2.47052 + vertex 1.58823 0.950421 2.47145 + vertex 1.58523 0.946528 2.47073 + endloop + endfacet + facet normal 0.159002 -0.295073 0.942152 + outer loop + vertex 1.58249 0.938678 2.46874 + vertex 1.58747 0.94384 2.46951 + vertex 1.58213 0.942577 2.47002 + endloop + endfacet + facet normal 0.160792 -0.302379 0.939528 + outer loop + vertex 1.58523 0.946528 2.47073 + vertex 1.5831 0.949155 2.47194 + vertex 1.58149 0.94522 2.47095 + endloop + endfacet + facet normal 0.160249 -0.304938 0.938793 + outer loop + vertex 1.57824 0.94523 2.47151 + vertex 1.57796 0.949003 2.47278 + vertex 1.57311 0.944098 2.47202 + endloop + endfacet + facet normal 0.160054 -0.30476 0.938885 + outer loop + vertex 1.57311 0.944098 2.47202 + vertex 1.57796 0.949003 2.47278 + vertex 1.5729 0.948652 2.47353 + endloop + endfacet + facet normal 0.151165 -0.305574 0.940092 + outer loop + vertex 1.57311 0.944098 2.47202 + vertex 1.5729 0.948652 2.47353 + vertex 1.5681 0.944119 2.47283 + endloop + endfacet + facet normal 0.160074 -0.30573 0.938566 + outer loop + vertex 1.57796 0.949003 2.47278 + vertex 1.5778 0.953316 2.47421 + vertex 1.5729 0.948652 2.47353 + endloop + endfacet + facet normal 0.160403 -0.306053 0.938404 + outer loop + vertex 1.5729 0.948652 2.47353 + vertex 1.5778 0.953316 2.47421 + vertex 1.57276 0.953224 2.47505 + endloop + endfacet + facet normal 0.152561 -0.306651 0.939516 + outer loop + vertex 1.5729 0.948652 2.47353 + vertex 1.57276 0.953224 2.47505 + vertex 1.56784 0.948306 2.47424 + endloop + endfacet + facet normal 0.15686 -0.310622 0.937501 + outer loop + vertex 1.56784 0.948306 2.47424 + vertex 1.57276 0.953224 2.47505 + vertex 1.56764 0.95208 2.47552 + endloop + endfacet + facet normal 0.155918 -0.305667 0.939286 + outer loop + vertex 1.56764 0.95208 2.47552 + vertex 1.57276 0.953224 2.47505 + vertex 1.57078 0.95596 2.47626 + endloop + endfacet + facet normal 0.159361 -0.303264 0.939487 + outer loop + vertex 1.57448 0.957188 2.47603 + vertex 1.57078 0.95596 2.47626 + vertex 1.57276 0.953224 2.47505 + endloop + endfacet + facet normal 0.15735 -0.296753 0.941902 + outer loop + vertex 1.57448 0.957188 2.47603 + vertex 1.57381 0.959859 2.47699 + vertex 1.57078 0.95596 2.47626 + endloop + endfacet + facet normal 0.154632 -0.294833 0.942954 + outer loop + vertex 1.57381 0.959859 2.47699 + vertex 1.56857 0.958731 2.47749 + vertex 1.57078 0.95596 2.47626 + endloop + endfacet + facet normal 0.15443 -0.293725 0.943333 + outer loop + vertex 1.57381 0.959859 2.47699 + vertex 1.57323 0.963762 2.4783 + vertex 1.56857 0.958731 2.47749 + endloop + endfacet + facet normal 0.155104 -0.294302 0.943042 + outer loop + vertex 1.56857 0.958731 2.47749 + vertex 1.57323 0.963762 2.4783 + vertex 1.56796 0.963366 2.47904 + endloop + endfacet + facet normal 0.157015 -0.293244 0.943056 + outer loop + vertex 1.57852 0.963777 2.47742 + vertex 1.57323 0.963762 2.4783 + vertex 1.57381 0.959859 2.47699 + endloop + endfacet + facet normal 0.15831 -0.294722 0.942378 + outer loop + vertex 1.57709 0.959785 2.47641 + vertex 1.57852 0.963777 2.47742 + vertex 1.57381 0.959859 2.47699 + endloop + endfacet + facet normal 0.157013 -0.293288 0.943042 + outer loop + vertex 1.57852 0.963777 2.47742 + vertex 1.57788 0.968423 2.47897 + vertex 1.57323 0.963762 2.4783 + endloop + endfacet + facet normal 0.156203 -0.292533 0.943411 + outer loop + vertex 1.57323 0.963762 2.4783 + vertex 1.57788 0.968423 2.47897 + vertex 1.57264 0.968408 2.47984 + endloop + endfacet + facet normal 0.158174 -0.296524 0.941836 + outer loop + vertex 1.57709 0.959785 2.47641 + vertex 1.57381 0.959859 2.47699 + vertex 1.57448 0.957188 2.47603 + endloop + endfacet + facet normal 0.160485 -0.303673 0.939163 + outer loop + vertex 1.57764 0.957128 2.47547 + vertex 1.57276 0.953224 2.47505 + vertex 1.5778 0.953316 2.47421 + endloop + endfacet + facet normal 0.162065 -0.303532 0.938937 + outer loop + vertex 1.5778 0.953316 2.47421 + vertex 1.58269 0.958269 2.47497 + vertex 1.57764 0.957128 2.47547 + endloop + endfacet + facet normal 0.160482 -0.30367 0.939165 + outer loop + vertex 1.57448 0.957188 2.47603 + vertex 1.57276 0.953224 2.47505 + vertex 1.57764 0.957128 2.47547 + endloop + endfacet + facet normal 0.160825 -0.299007 0.940601 + outer loop + vertex 1.57764 0.957128 2.47547 + vertex 1.57709 0.959785 2.47641 + vertex 1.57448 0.957188 2.47603 + endloop + endfacet + facet normal 0.160293 -0.299135 0.940651 + outer loop + vertex 1.57709 0.959785 2.47641 + vertex 1.57764 0.957128 2.47547 + vertex 1.58071 0.961003 2.47618 + endloop + endfacet + facet normal 0.162588 -0.305518 0.938202 + outer loop + vertex 1.57796 0.949003 2.47278 + vertex 1.58284 0.953685 2.47346 + vertex 1.5778 0.953316 2.47421 + endloop + endfacet + facet normal 0.162551 -0.303976 0.93871 + outer loop + vertex 1.58284 0.953685 2.47346 + vertex 1.58269 0.958269 2.47497 + vertex 1.5778 0.953316 2.47421 + endloop + endfacet + facet normal 0.165359 -0.303743 0.938295 + outer loop + vertex 1.58284 0.953685 2.47346 + vertex 1.58772 0.958385 2.47412 + vertex 1.58269 0.958269 2.47497 + endloop + endfacet + facet normal 0.16871 -0.301875 0.938301 + outer loop + vertex 1.59278 0.954219 2.47186 + vertex 1.59282 0.958745 2.47331 + vertex 1.58789 0.954085 2.4727 + endloop + endfacet + facet normal 0.165395 -0.302563 0.93867 + outer loop + vertex 1.58749 0.962191 2.47539 + vertex 1.58269 0.958269 2.47497 + vertex 1.58772 0.958385 2.47412 + endloop + endfacet + facet normal 0.161374 -0.299911 0.940219 + outer loop + vertex 1.57764 0.957128 2.47547 + vertex 1.58269 0.958269 2.47497 + vertex 1.58071 0.961003 2.47618 + endloop + endfacet + facet normal 0.160903 -0.294489 0.942012 + outer loop + vertex 1.5869 0.964829 2.47633 + vertex 1.58367 0.964891 2.4769 + vertex 1.58434 0.962223 2.47595 + endloop + endfacet + facet normal 0.158972 -0.294916 0.942206 + outer loop + vertex 1.58071 0.961003 2.47618 + vertex 1.57852 0.963777 2.47742 + vertex 1.57709 0.959785 2.47641 + endloop + endfacet + facet normal 0.158929 -0.292954 0.942825 + outer loop + vertex 1.57852 0.963777 2.47742 + vertex 1.58309 0.9688 2.47821 + vertex 1.57788 0.968423 2.47897 + endloop + endfacet + facet normal 0.158944 -0.29352 0.942647 + outer loop + vertex 1.58309 0.9688 2.47821 + vertex 1.5825 0.973441 2.47976 + vertex 1.57788 0.968423 2.47897 + endloop + endfacet + facet normal 0.158131 -0.292827 0.942999 + outer loop + vertex 1.57788 0.968423 2.47897 + vertex 1.5825 0.973441 2.47976 + vertex 1.57737 0.972325 2.48027 + endloop + endfacet + facet normal 0.158396 -0.294273 0.942504 + outer loop + vertex 1.57737 0.972325 2.48027 + vertex 1.5825 0.973441 2.47976 + vertex 1.58035 0.976189 2.48098 + endloop + endfacet + facet normal 0.165976 -0.292344 0.9418 + outer loop + vertex 1.58309 0.9688 2.47821 + vertex 1.58773 0.973536 2.47886 + vertex 1.5825 0.973441 2.47976 + endloop + endfacet + facet normal 0.159605 -0.293365 0.942583 + outer loop + vertex 1.58397 0.977416 2.48074 + vertex 1.58035 0.976189 2.48098 + vertex 1.5825 0.973441 2.47976 + endloop + endfacet + facet normal 0.174891 -0.28906 0.9412 + outer loop + vertex 1.58655 0.980046 2.48109 + vertex 1.58722 0.977428 2.48017 + vertex 1.59025 0.981429 2.48083 + endloop + endfacet + facet normal 0.157598 -0.287016 0.944873 + outer loop + vertex 1.58397 0.977416 2.48074 + vertex 1.58334 0.980058 2.48165 + vertex 1.58035 0.976189 2.48098 + endloop + endfacet + facet normal 0.158217 -0.287453 0.944637 + outer loop + vertex 1.58334 0.980058 2.48165 + vertex 1.57823 0.978946 2.48217 + vertex 1.58035 0.976189 2.48098 + endloop + endfacet + facet normal 0.172826 -0.283107 0.943388 + outer loop + vertex 1.59025 0.981429 2.48083 + vertex 1.58812 0.984055 2.48201 + vertex 1.58655 0.980046 2.48109 + endloop + endfacet + facet normal 0.157633 -0.284277 0.945695 + outer loop + vertex 1.58334 0.980058 2.48165 + vertex 1.58298 0.983914 2.48287 + vertex 1.57823 0.978946 2.48217 + endloop + endfacet + facet normal 0.160604 -0.286936 0.944391 + outer loop + vertex 1.57823 0.978946 2.48217 + vertex 1.58298 0.983914 2.48287 + vertex 1.57788 0.983679 2.48367 + endloop + endfacet + facet normal 0.169708 -0.282415 0.944162 + outer loop + vertex 1.58812 0.984055 2.48201 + vertex 1.59291 0.989117 2.48266 + vertex 1.5878 0.988694 2.48345 + endloop + endfacet + facet normal 0.169761 -0.283923 0.9437 + outer loop + vertex 1.59291 0.989117 2.48266 + vertex 1.59266 0.99351 2.48403 + vertex 1.5878 0.988694 2.48345 + endloop + endfacet + facet normal 0.152574 -0.285654 0.94611 + outer loop + vertex 1.59291 0.989117 2.48266 + vertex 1.59784 0.993735 2.48326 + vertex 1.59266 0.99351 2.48403 + endloop + endfacet + facet normal 0.163799 -0.296944 0.940741 + outer loop + vertex 1.5979 0.989233 2.48183 + vertex 1.59784 0.993735 2.48326 + vertex 1.59291 0.989117 2.48266 + endloop + endfacet + facet normal 0.164049 -0.287952 0.943489 + outer loop + vertex 1.5979 0.989233 2.48183 + vertex 1.59291 0.989117 2.48266 + vertex 1.59328 0.985416 2.48147 + endloop + endfacet + facet normal 0.177647 -0.303727 0.936051 + outer loop + vertex 1.59653 0.985685 2.48094 + vertex 1.5979 0.989233 2.48183 + vertex 1.59328 0.985416 2.48147 + endloop + endfacet + facet normal 0.174297 -0.286497 0.942093 + outer loop + vertex 1.59328 0.985416 2.48147 + vertex 1.59291 0.989117 2.48266 + vertex 1.58812 0.984055 2.48201 + endloop + endfacet + facet normal 0.163523 -0.287696 0.943658 + outer loop + vertex 1.57932 0.991929 2.48593 + vertex 1.57795 0.988322 2.48507 + vertex 1.58249 0.992104 2.48543 + endloop + endfacet + facet normal 0.160606 -0.285189 0.944919 + outer loop + vertex 1.58298 0.983914 2.48287 + vertex 1.58276 0.988332 2.48424 + vertex 1.57788 0.983679 2.48367 + endloop + endfacet + facet normal 0.156907 -0.287458 0.944853 + outer loop + vertex 1.57299 0.978966 2.48305 + vertex 1.57788 0.983679 2.48367 + vertex 1.57255 0.983768 2.48458 + endloop + endfacet + facet normal 0.158263 -0.286021 0.945063 + outer loop + vertex 1.57932 0.991929 2.48593 + vertex 1.5765 0.990509 2.48597 + vertex 1.57795 0.988322 2.48507 + endloop + endfacet + facet normal 0.153161 -0.284603 0.946331 + outer loop + vertex 1.57408 0.987878 2.48557 + vertex 1.57325 0.990314 2.48644 + vertex 1.57023 0.986453 2.48577 + endloop + endfacet + facet normal 0.155904 -0.281267 0.946881 + outer loop + vertex 1.57932 0.991929 2.48593 + vertex 1.57782 0.994064 2.48681 + vertex 1.5765 0.990509 2.48597 + endloop + endfacet + facet normal 0.159155 -0.285291 0.945134 + outer loop + vertex 1.56782 0.993685 2.48835 + vertex 1.5728 0.99851 2.48897 + vertex 1.56768 0.998531 2.48984 + endloop + endfacet + facet normal 0.159136 -0.285293 0.945137 + outer loop + vertex 1.56782 0.993685 2.48835 + vertex 1.56768 0.998531 2.48984 + vertex 1.56271 0.993331 2.48911 + endloop + endfacet + facet normal 0.160573 -0.286578 0.944505 + outer loop + vertex 1.56271 0.993331 2.48911 + vertex 1.56768 0.998531 2.48984 + vertex 1.56248 0.997224 2.49033 + endloop + endfacet + facet normal 0.156495 -0.279945 0.947175 + outer loop + vertex 1.57782 0.994064 2.48681 + vertex 1.57786 0.998618 2.48815 + vertex 1.5729 0.993998 2.4876 + endloop + endfacet + facet normal 0.164978 -0.279151 0.945969 + outer loop + vertex 1.57786 0.998618 2.48815 + vertex 1.58284 1.00348 2.48872 + vertex 1.57769 1.00328 2.48955 + endloop + endfacet + facet normal 0.165006 -0.275988 0.946892 + outer loop + vertex 1.58284 1.00348 2.48872 + vertex 1.58262 1.00836 2.49017 + vertex 1.57769 1.00328 2.48955 + endloop + endfacet + facet normal 0.165981 -0.265837 0.949622 + outer loop + vertex 1.58366 1.01487 2.49185 + vertex 1.57836 1.0133 2.49234 + vertex 1.58122 1.01128 2.49127 + endloop + endfacet + facet normal 0.159315 -0.282299 0.946005 + outer loop + vertex 1.57288 1.00316 2.49034 + vertex 1.56768 0.998531 2.48984 + vertex 1.5728 0.99851 2.48897 + endloop + endfacet + facet normal 0.160119 -0.284505 0.945208 + outer loop + vertex 1.56248 0.997224 2.49033 + vertex 1.56768 0.998531 2.48984 + vertex 1.56558 1.00121 2.491 + endloop + endfacet + facet normal 0.159736 -0.280601 0.946439 + outer loop + vertex 1.57153 1.00517 2.49117 + vertex 1.56849 1.00507 2.49166 + vertex 1.56931 1.00265 2.4908 + endloop + endfacet + facet normal 0.159829 -0.277727 0.947271 + outer loop + vertex 1.56849 1.00507 2.49166 + vertex 1.56802 1.00884 2.49284 + vertex 1.56336 1.00388 2.49217 + endloop + endfacet + facet normal 0.161365 -0.285392 0.944729 + outer loop + vertex 1.56188 0.999877 2.49123 + vertex 1.56248 0.997224 2.49033 + vertex 1.56558 1.00121 2.491 + endloop + endfacet + facet normal 0.160001 -0.284523 0.945223 + outer loop + vertex 1.55925 0.997217 2.49088 + vertex 1.5586 0.999887 2.49179 + vertex 1.55557 0.995952 2.49112 + endloop + endfacet + facet normal 0.160032 -0.286633 0.94458 + outer loop + vertex 1.56248 0.997224 2.49033 + vertex 1.5576 0.993207 2.48993 + vertex 1.56271 0.993331 2.48911 + endloop + endfacet + facet normal 0.159178 -0.287018 0.944607 + outer loop + vertex 1.56293 0.988938 2.48773 + vertex 1.56782 0.993685 2.48835 + vertex 1.56271 0.993331 2.48911 + endloop + endfacet + facet normal 0.158221 -0.286091 0.945049 + outer loop + vertex 1.56807 0.989074 2.48691 + vertex 1.56782 0.993685 2.48835 + vertex 1.56293 0.988938 2.48773 + endloop + endfacet + facet normal 0.154985 -0.285907 0.945641 + outer loop + vertex 1.57325 0.990314 2.48644 + vertex 1.56807 0.989074 2.48691 + vertex 1.57023 0.986453 2.48577 + endloop + endfacet + facet normal 0.156466 -0.283662 0.946073 + outer loop + vertex 1.56718 0.982523 2.48508 + vertex 1.56648 0.985162 2.48599 + vertex 1.56388 0.982557 2.48564 + endloop + endfacet + facet normal 0.153618 -0.285901 0.945866 + outer loop + vertex 1.57408 0.987878 2.48557 + vertex 1.57023 0.986453 2.48577 + vertex 1.57255 0.983768 2.48458 + endloop + endfacet + facet normal 0.156419 -0.284452 0.945844 + outer loop + vertex 1.56388 0.982557 2.48564 + vertex 1.56243 0.97854 2.48467 + vertex 1.56718 0.982523 2.48508 + endloop + endfacet + facet normal 0.157162 -0.287424 0.944821 + outer loop + vertex 1.57299 0.978966 2.48305 + vertex 1.57255 0.983768 2.48458 + vertex 1.56771 0.978587 2.48381 + endloop + endfacet + facet normal 0.156819 -0.287373 0.944894 + outer loop + vertex 1.57823 0.978946 2.48217 + vertex 1.57788 0.983679 2.48367 + vertex 1.57299 0.978966 2.48305 + endloop + endfacet + facet normal 0.155059 -0.289801 0.944443 + outer loop + vertex 1.58035 0.976189 2.48098 + vertex 1.57823 0.978946 2.48217 + vertex 1.57672 0.974985 2.4812 + endloop + endfacet + facet normal 0.155901 -0.292526 0.943464 + outer loop + vertex 1.57672 0.974985 2.4812 + vertex 1.57737 0.972325 2.48027 + vertex 1.58035 0.976189 2.48098 + endloop + endfacet + facet normal 0.156174 -0.293156 0.943223 + outer loop + vertex 1.57737 0.972325 2.48027 + vertex 1.57264 0.968408 2.47984 + vertex 1.57788 0.968423 2.47897 + endloop + endfacet + facet normal 0.157451 -0.29273 0.943143 + outer loop + vertex 1.57414 0.972405 2.48083 + vertex 1.57347 0.975055 2.48176 + vertex 1.57047 0.971172 2.48106 + endloop + endfacet + facet normal 0.155055 -0.292722 0.943542 + outer loop + vertex 1.57323 0.963762 2.4783 + vertex 1.57264 0.968408 2.47984 + vertex 1.56796 0.963366 2.47904 + endloop + endfacet + facet normal 0.161423 -0.295335 0.941658 + outer loop + vertex 1.5668 0.969922 2.48129 + vertex 1.56746 0.967259 2.48035 + vertex 1.57047 0.971172 2.48106 + endloop + endfacet + facet normal 0.160838 -0.292808 0.942547 + outer loop + vertex 1.5668 0.969922 2.48129 + vertex 1.56828 0.973917 2.48228 + vertex 1.56356 0.969961 2.48186 + endloop + endfacet + facet normal 0.150307 -0.29149 0.944691 + outer loop + vertex 1.56356 0.969961 2.48186 + vertex 1.56303 0.97387 2.48315 + vertex 1.55844 0.968861 2.48233 + endloop + endfacet + facet normal 0.150625 -0.291759 0.944557 + outer loop + vertex 1.55844 0.968861 2.48233 + vertex 1.56303 0.97387 2.48315 + vertex 1.55782 0.973503 2.48387 + endloop + endfacet + facet normal 0.132241 -0.318848 0.938535 + outer loop + vertex 1.55754 0.962184 2.48032 + vertex 1.55695 0.964855 2.48131 + vertex 1.55429 0.962344 2.48083 + endloop + endfacet + facet normal 0.158676 -0.304067 0.939343 + outer loop + vertex 1.56423 0.967295 2.48091 + vertex 1.56058 0.966044 2.48112 + vertex 1.5627 0.963307 2.47988 + endloop + endfacet + facet normal 0.153182 -0.302792 0.940666 + outer loop + vertex 1.56323 0.95871 2.47831 + vertex 1.56796 0.963366 2.47904 + vertex 1.5627 0.963307 2.47988 + endloop + endfacet + facet normal 0.145828 -0.295856 0.944036 + outer loop + vertex 1.56857 0.958731 2.47749 + vertex 1.56796 0.963366 2.47904 + vertex 1.56323 0.95871 2.47831 + endloop + endfacet + facet normal 0.153356 -0.295808 0.942857 + outer loop + vertex 1.57078 0.95596 2.47626 + vertex 1.56857 0.958731 2.47749 + vertex 1.56709 0.954729 2.47648 + endloop + endfacet + facet normal 0.156581 -0.306151 0.939018 + outer loop + vertex 1.56709 0.954729 2.47648 + vertex 1.56764 0.95208 2.47552 + vertex 1.57078 0.95596 2.47626 + endloop + endfacet + facet normal 0.1274 -0.303572 0.944253 + outer loop + vertex 1.56441 0.952137 2.47605 + vertex 1.56376 0.954819 2.477 + vertex 1.56063 0.95097 2.47619 + endloop + endfacet + facet normal 0.14022 -0.31221 0.939608 + outer loop + vertex 1.56764 0.95208 2.47552 + vertex 1.56269 0.948217 2.47498 + vertex 1.56784 0.948306 2.47424 + endloop + endfacet + facet normal 0.152568 -0.306954 0.939416 + outer loop + vertex 1.5681 0.944119 2.47283 + vertex 1.5729 0.948652 2.47353 + vertex 1.56784 0.948306 2.47424 + endloop + endfacet + facet normal 0.151296 -0.303198 0.94084 + outer loop + vertex 1.57311 0.944098 2.47202 + vertex 1.5681 0.944119 2.47283 + vertex 1.56834 0.940372 2.47158 + endloop + endfacet + facet normal 0.147143 -0.298154 0.943108 + outer loop + vertex 1.57148 0.940172 2.47103 + vertex 1.57311 0.944098 2.47202 + vertex 1.56834 0.940372 2.47158 + endloop + endfacet + facet normal 0.157836 -0.307113 0.938493 + outer loop + vertex 1.57148 0.940172 2.47103 + vertex 1.57221 0.937571 2.47006 + vertex 1.57516 0.941364 2.4708 + endloop + endfacet + facet normal 0.137267 -0.338825 0.930782 + outer loop + vertex 1.56892 0.93768 2.47061 + vertex 1.56519 0.936663 2.47079 + vertex 1.56778 0.933937 2.46942 + endloop + endfacet + facet normal 0.151052 -0.302358 0.94115 + outer loop + vertex 1.57221 0.937571 2.47006 + vertex 1.57733 0.938657 2.46958 + vertex 1.57516 0.941364 2.4708 + endloop + endfacet + facet normal 0.155726 -0.295517 0.94256 + outer loop + vertex 1.58213 0.942577 2.47002 + vertex 1.57733 0.938657 2.46958 + vertex 1.58249 0.938678 2.46874 + endloop + endfacet + facet normal 0.157296 -0.293544 0.942916 + outer loop + vertex 1.58768 0.939054 2.46799 + vertex 1.58747 0.94384 2.46951 + vertex 1.58249 0.938678 2.46874 + endloop + endfacet + facet normal 0.162536 -0.292531 0.942342 + outer loop + vertex 1.59271 0.939031 2.46711 + vertex 1.59284 0.943725 2.46855 + vertex 1.58768 0.939054 2.46799 + endloop + endfacet + facet normal 0.168489 -0.332729 0.927848 + outer loop + vertex 1.59427 0.936888 2.46606 + vertex 1.59271 0.939031 2.46711 + vertex 1.59139 0.935531 2.4661 + endloop + endfacet + facet normal 0.19955 -0.352314 0.91436 + outer loop + vertex 1.59762 0.937094 2.46541 + vertex 1.59668 0.939463 2.46653 + vertex 1.59427 0.936888 2.46606 + endloop + endfacet + facet normal 0.172803 -0.329725 0.928128 + outer loop + vertex 1.59668 0.939463 2.46653 + vertex 1.59271 0.939031 2.46711 + vertex 1.59427 0.936888 2.46606 + endloop + endfacet + facet normal 0.170751 -0.29432 0.94033 + outer loop + vertex 1.59668 0.939463 2.46653 + vertex 1.59826 0.943632 2.46755 + vertex 1.59271 0.939031 2.46711 + endloop + endfacet + facet normal 0.172901 -0.292424 0.940528 + outer loop + vertex 1.6037 0.945004 2.46697 + vertex 1.60321 0.948894 2.46827 + vertex 1.59826 0.943632 2.46755 + endloop + endfacet + facet normal 0.157537 -0.295016 0.942416 + outer loop + vertex 1.6085 0.948978 2.46741 + vertex 1.60321 0.948894 2.46827 + vertex 1.6037 0.945004 2.46697 + endloop + endfacet + facet normal 0.157207 -0.304511 0.939446 + outer loop + vertex 1.6085 0.948978 2.46741 + vertex 1.60783 0.953395 2.46896 + vertex 1.60321 0.948894 2.46827 + endloop + endfacet + facet normal 0.110808 -0.312908 0.943297 + outer loop + vertex 1.6085 0.948978 2.46741 + vertex 1.61291 0.953484 2.46839 + vertex 1.60783 0.953395 2.46896 + endloop + endfacet + facet normal 0.168569 -0.307683 0.936438 + outer loop + vertex 1.60703 0.945079 2.4664 + vertex 1.6085 0.948978 2.46741 + vertex 1.6037 0.945004 2.46697 + endloop + endfacet + facet normal 0.151727 -0.302513 0.940991 + outer loop + vertex 1.61072 0.946305 2.4662 + vertex 1.6085 0.948978 2.46741 + vertex 1.60703 0.945079 2.4664 + endloop + endfacet + facet normal 0.126713 -0.32197 0.938232 + outer loop + vertex 1.61369 0.949906 2.46703 + vertex 1.6085 0.948978 2.46741 + vertex 1.61072 0.946305 2.4662 + endloop + endfacet + facet normal 0.15132 -0.301212 0.941474 + outer loop + vertex 1.60703 0.945079 2.4664 + vertex 1.60766 0.942459 2.46546 + vertex 1.61072 0.946305 2.4662 + endloop + endfacet + facet normal 0.187625 -0.341384 0.921007 + outer loop + vertex 1.60439 0.942395 2.46602 + vertex 1.6006 0.940972 2.46626 + vertex 1.60292 0.938519 2.46488 + endloop + endfacet + facet normal 0.138736 -0.292114 0.946267 + outer loop + vertex 1.60766 0.942459 2.46546 + vertex 1.61275 0.943386 2.465 + vertex 1.61072 0.946305 2.4662 + endloop + endfacet + facet normal 0.117803 -0.405277 0.906572 + outer loop + vertex 1.61886 0.939405 2.46263 + vertex 1.61767 0.942816 2.46431 + vertex 1.61338 0.938653 2.46301 + endloop + endfacet + facet normal 0.0561993 -0.425159 0.903372 + outer loop + vertex 1.61886 0.939405 2.46263 + vertex 1.62185 0.942471 2.46389 + vertex 1.61767 0.942816 2.46431 + endloop + endfacet + facet normal 0.119231 -0.30512 0.944821 + outer loop + vertex 1.61437 0.94728 2.46605 + vertex 1.61072 0.946305 2.4662 + vertex 1.61275 0.943386 2.465 + endloop + endfacet + facet normal 0.122747 -0.319047 0.939757 + outer loop + vertex 1.61437 0.94728 2.46605 + vertex 1.61369 0.949906 2.46703 + vertex 1.61072 0.946305 2.4662 + endloop + endfacet + facet normal 0.12759 -0.327755 0.936108 + outer loop + vertex 1.61369 0.949906 2.46703 + vertex 1.61291 0.953484 2.46839 + vertex 1.6085 0.948978 2.46741 + endloop + endfacet + facet normal 0.110712 -0.317883 0.941644 + outer loop + vertex 1.61291 0.953484 2.46839 + vertex 1.61192 0.957384 2.46982 + vertex 1.60783 0.953395 2.46896 + endloop + endfacet + facet normal 0.150102 -0.297712 0.942782 + outer loop + vertex 1.60321 0.948894 2.46827 + vertex 1.60783 0.953395 2.46896 + vertex 1.60272 0.953541 2.46982 + endloop + endfacet + facet normal 0.168733 -0.29997 0.938907 + outer loop + vertex 1.60426 0.957577 2.47083 + vertex 1.60051 0.956259 2.47108 + vertex 1.60272 0.953541 2.46982 + endloop + endfacet + facet normal 0.0987053 -0.316714 0.943371 + outer loop + vertex 1.60691 0.960072 2.47126 + vertex 1.60743 0.957282 2.47026 + vertex 1.61073 0.960846 2.47112 + endloop + endfacet + facet normal 0.172883 -0.312728 0.933977 + outer loop + vertex 1.60426 0.957577 2.47083 + vertex 1.60357 0.960184 2.47183 + vertex 1.60051 0.956259 2.47108 + endloop + endfacet + facet normal 0.100775 -0.327654 0.939408 + outer loop + vertex 1.61073 0.960846 2.47112 + vertex 1.60841 0.963857 2.47241 + vertex 1.60691 0.960072 2.47126 + endloop + endfacet + facet normal 0.168554 -0.309839 0.935729 + outer loop + vertex 1.60357 0.960184 2.47183 + vertex 1.60304 0.963954 2.47317 + vertex 1.59818 0.958843 2.47236 + endloop + endfacet + facet normal 0.118674 -0.300269 0.946443 + outer loop + vertex 1.60304 0.963954 2.47317 + vertex 1.60766 0.968258 2.47396 + vertex 1.60254 0.968565 2.4747 + endloop + endfacet + facet normal 0.0694422 -0.320615 0.944661 + outer loop + vertex 1.61409 0.964631 2.47226 + vertex 1.61281 0.968338 2.47361 + vertex 1.60841 0.963857 2.47241 + endloop + endfacet + facet normal 0.119322 -0.293988 0.948332 + outer loop + vertex 1.60728 0.972126 2.47521 + vertex 1.60254 0.968565 2.4747 + vertex 1.60766 0.968258 2.47396 + endloop + endfacet + facet normal 0.155586 -0.307966 0.938589 + outer loop + vertex 1.60411 0.972573 2.47568 + vertex 1.60348 0.975217 2.47666 + vertex 1.6004 0.971403 2.47591 + endloop + endfacet + facet normal 0.159374 -0.294457 0.942282 + outer loop + vertex 1.60304 0.963954 2.47317 + vertex 1.60254 0.968565 2.4747 + vertex 1.59777 0.963533 2.47394 + endloop + endfacet + facet normal 0.172774 -0.300463 0.938014 + outer loop + vertex 1.59282 0.958745 2.47331 + vertex 1.59777 0.963533 2.47394 + vertex 1.59256 0.963403 2.47485 + endloop + endfacet + facet normal 0.173573 -0.296651 0.93908 + outer loop + vertex 1.59413 0.967419 2.47583 + vertex 1.59049 0.966108 2.47609 + vertex 1.59256 0.963403 2.47485 + endloop + endfacet + facet normal 0.170309 -0.292026 0.941125 + outer loop + vertex 1.59671 0.970104 2.47618 + vertex 1.59736 0.967438 2.47523 + vertex 1.6004 0.971403 2.47591 + endloop + endfacet + facet normal 0.171456 -0.290323 0.941443 + outer loop + vertex 1.59413 0.967419 2.47583 + vertex 1.59346 0.970082 2.47677 + vertex 1.59049 0.966108 2.47609 + endloop + endfacet + facet normal 0.17092 -0.293905 0.940429 + outer loop + vertex 1.6004 0.971403 2.47591 + vertex 1.59824 0.974115 2.47715 + vertex 1.59671 0.970104 2.47618 + endloop + endfacet + facet normal 0.154017 -0.306823 0.939222 + outer loop + vertex 1.60348 0.975217 2.47666 + vertex 1.59824 0.974115 2.47715 + vertex 1.6004 0.971403 2.47591 + endloop + endfacet + facet normal 0.16885 -0.287741 0.942706 + outer loop + vertex 1.59346 0.970082 2.47677 + vertex 1.59298 0.974021 2.47806 + vertex 1.58832 0.968861 2.47732 + endloop + endfacet + facet normal 0.166536 -0.288299 0.942947 + outer loop + vertex 1.59298 0.974021 2.47806 + vertex 1.59787 0.978802 2.47866 + vertex 1.59254 0.978805 2.4796 + endloop + endfacet + facet normal 0.153998 -0.306715 0.939261 + outer loop + vertex 1.60348 0.975217 2.47666 + vertex 1.60303 0.978946 2.47795 + vertex 1.59824 0.974115 2.47715 + endloop + endfacet + facet normal 0.0940109 -0.315733 0.944179 + outer loop + vertex 1.60837 0.978702 2.47733 + vertex 1.60303 0.978946 2.47795 + vertex 1.60348 0.975217 2.47666 + endloop + endfacet + facet normal 0.0948044 -0.306096 0.947268 + outer loop + vertex 1.60837 0.978702 2.47733 + vertex 1.6076 0.983101 2.47883 + vertex 1.60303 0.978946 2.47795 + endloop + endfacet + facet normal 0.132882 -0.283163 0.949822 + outer loop + vertex 1.59787 0.978802 2.47866 + vertex 1.60266 0.983166 2.47929 + vertex 1.59795 0.983435 2.48003 + endloop + endfacet + facet normal 0.159572 -0.281224 0.946282 + outer loop + vertex 1.59939 0.987094 2.48087 + vertex 1.59653 0.985685 2.48094 + vertex 1.59795 0.983435 2.48003 + endloop + endfacet + facet normal 0.0797327 -0.302529 0.949799 + outer loop + vertex 1.60185 0.989586 2.48133 + vertex 1.60249 0.986943 2.48044 + vertex 1.60579 0.990465 2.48128 + endloop + endfacet + facet normal 0.169155 -0.301055 0.938484 + outer loop + vertex 1.59939 0.987094 2.48087 + vertex 1.5979 0.989233 2.48183 + vertex 1.59653 0.985685 2.48094 + endloop + endfacet + facet normal 0.0832258 -0.318481 0.944269 + outer loop + vertex 1.60579 0.990465 2.48128 + vertex 1.60334 0.993466 2.48251 + vertex 1.60185 0.989586 2.48133 + endloop + endfacet + facet normal 0.0605786 -0.335271 0.940172 + outer loop + vertex 1.60919 0.994297 2.48243 + vertex 1.60334 0.993466 2.48251 + vertex 1.60579 0.990465 2.48128 + endloop + endfacet + facet normal 0.0568481 -0.308111 0.949651 + outer loop + vertex 1.60919 0.994297 2.48243 + vertex 1.60786 0.998095 2.48374 + vertex 1.60334 0.993466 2.48251 + endloop + endfacet + facet normal 0.0548347 -0.30633 0.950345 + outer loop + vertex 1.60334 0.993466 2.48251 + vertex 1.60786 0.998095 2.48374 + vertex 1.60265 0.998079 2.48403 + endloop + endfacet + facet normal 0.0549505 -0.298516 0.952822 + outer loop + vertex 1.60786 0.998095 2.48374 + vertex 1.60685 1.00198 2.48501 + vertex 1.60265 0.998079 2.48403 + endloop + endfacet + facet normal 0.14682 -0.29787 0.943248 + outer loop + vertex 1.59914 1.00253 2.48566 + vertex 1.59853 1.00519 2.4866 + vertex 1.59544 1.00138 2.48588 + endloop + endfacet + facet normal 0.14624 -0.297443 0.943473 + outer loop + vertex 1.59853 1.00519 2.4866 + vertex 1.59329 1.00407 2.48706 + vertex 1.59544 1.00138 2.48588 + endloop + endfacet + facet normal 0.152577 -0.281014 0.947498 + outer loop + vertex 1.59784 0.993735 2.48326 + vertex 1.59751 0.998493 2.48473 + vertex 1.59266 0.99351 2.48403 + endloop + endfacet + facet normal 0.169553 -0.283725 0.943797 + outer loop + vertex 1.5878 0.988694 2.48345 + vertex 1.59266 0.99351 2.48403 + vertex 1.58754 0.993367 2.48491 + endloop + endfacet + facet normal 0.171834 -0.282348 0.943797 + outer loop + vertex 1.58915 0.997402 2.48582 + vertex 1.58546 0.996021 2.48608 + vertex 1.58754 0.993367 2.48491 + endloop + endfacet + facet normal 0.164571 -0.27974 0.945866 + outer loop + vertex 1.59176 1.00009 2.48613 + vertex 1.59236 0.997424 2.48524 + vertex 1.59544 1.00138 2.48588 + endloop + endfacet + facet normal 0.170366 -0.278136 0.945312 + outer loop + vertex 1.58915 0.997402 2.48582 + vertex 1.58849 1.00002 2.48671 + vertex 1.58546 0.996021 2.48608 + endloop + endfacet + facet normal 0.165515 -0.282638 0.944839 + outer loop + vertex 1.59544 1.00138 2.48588 + vertex 1.59329 1.00407 2.48706 + vertex 1.59176 1.00009 2.48613 + endloop + endfacet + facet normal 0.166749 -0.275095 0.946846 + outer loop + vertex 1.58849 1.00002 2.48671 + vertex 1.58804 1.00387 2.48791 + vertex 1.58317 0.998639 2.48724 + endloop + endfacet + facet normal 0.160301 -0.274001 0.948276 + outer loop + vertex 1.58804 1.00387 2.48791 + vertex 1.59285 1.00869 2.48849 + vertex 1.58771 1.00834 2.48926 + endloop + endfacet + facet normal 0.145621 -0.294064 0.944628 + outer loop + vertex 1.59853 1.00519 2.4866 + vertex 1.59804 1.00893 2.48784 + vertex 1.59329 1.00407 2.48706 + endloop + endfacet + facet normal 0.127203 -0.270541 0.954268 + outer loop + vertex 1.59285 1.00869 2.48849 + vertex 1.59756 1.0132 2.48914 + vertex 1.59252 1.0134 2.48986 + endloop + endfacet + facet normal 0.0843383 -0.290033 0.953293 + outer loop + vertex 1.60341 1.00868 2.48729 + vertex 1.60261 1.01316 2.48872 + vertex 1.59804 1.00893 2.48784 + endloop + endfacet + facet normal 0.127691 -0.264248 0.955964 + outer loop + vertex 1.59734 1.01712 2.49025 + vertex 1.59252 1.0134 2.48986 + vertex 1.59756 1.0132 2.48914 + endloop + endfacet + facet normal 0.163942 -0.282668 0.945104 + outer loop + vertex 1.59418 1.01746 2.49072 + vertex 1.59355 1.0201 2.49162 + vertex 1.59047 1.0162 2.49099 + endloop + endfacet + facet normal 0.159803 -0.279669 0.946704 + outer loop + vertex 1.59355 1.0201 2.49162 + vertex 1.58832 1.01891 2.49215 + vertex 1.59047 1.0162 2.49099 + endloop + endfacet + facet normal 0.160135 -0.267094 0.950272 + outer loop + vertex 1.59285 1.00869 2.48849 + vertex 1.59252 1.0134 2.48986 + vertex 1.58771 1.00834 2.48926 + endloop + endfacet + facet normal 0.170155 -0.275531 0.946113 + outer loop + vertex 1.58284 1.00348 2.48872 + vertex 1.58771 1.00834 2.48926 + vertex 1.58262 1.00836 2.49017 + endloop + endfacet + facet normal 0.169642 -0.273612 0.946762 + outer loop + vertex 1.58435 1.01229 2.491 + vertex 1.58122 1.01128 2.49127 + vertex 1.58262 1.00836 2.49017 + endloop + endfacet + facet normal 0.172745 -0.268649 0.947622 + outer loop + vertex 1.58684 1.01488 2.49128 + vertex 1.58743 1.01224 2.49042 + vertex 1.59047 1.0162 2.49099 + endloop + endfacet + facet normal 0.167686 -0.266905 0.949022 + outer loop + vertex 1.58435 1.01229 2.491 + vertex 1.58366 1.01487 2.49185 + vertex 1.58122 1.01128 2.49127 + endloop + endfacet + facet normal 0.173017 -0.269461 0.947341 + outer loop + vertex 1.59047 1.0162 2.49099 + vertex 1.58832 1.01891 2.49215 + vertex 1.58684 1.01488 2.49128 + endloop + endfacet + facet normal 0.165784 -0.265091 0.949865 + outer loop + vertex 1.58366 1.01487 2.49185 + vertex 1.58308 1.01874 2.49303 + vertex 1.57836 1.0133 2.49234 + endloop + endfacet + facet normal 0.165886 -0.266284 0.949513 + outer loop + vertex 1.58308 1.01874 2.49303 + vertex 1.58787 1.02365 2.49357 + vertex 1.58277 1.02329 2.49436 + endloop + endfacet + facet normal 0.160035 -0.280863 0.946311 + outer loop + vertex 1.59355 1.0201 2.49162 + vertex 1.59304 1.02392 2.49284 + vertex 1.58832 1.01891 2.49215 + endloop + endfacet + facet normal 0.145314 -0.265825 0.953006 + outer loop + vertex 1.58787 1.02365 2.49357 + vertex 1.59266 1.02837 2.49416 + vertex 1.58757 1.02841 2.49494 + endloop + endfacet + facet normal 0.109638 -0.277137 0.954555 + outer loop + vertex 1.5984 1.02379 2.49219 + vertex 1.5976 1.02831 2.49359 + vertex 1.59304 1.02392 2.49284 + endloop + endfacet + facet normal 0.0525527 -0.273571 0.960415 + outer loop + vertex 1.5976 1.02831 2.49359 + vertex 1.60131 1.03178 2.49438 + vertex 1.59737 1.03293 2.49492 + endloop + endfacet + facet normal 0.0475562 -0.288745 0.956224 + outer loop + vertex 1.60247 1.0357 2.4955 + vertex 1.59737 1.03293 2.49492 + vertex 1.60131 1.03178 2.49438 + endloop + endfacet + facet normal 0.0388636 -0.306481 0.951083 + outer loop + vertex 1.60174 1.03884 2.49644 + vertex 1.59857 1.03958 2.4968 + vertex 1.5992 1.03679 2.49588 + endloop + endfacet + facet normal 0.0376473 -0.310985 0.949669 + outer loop + vertex 1.60174 1.03884 2.49644 + vertex 1.6036 1.04272 2.49763 + vertex 1.59857 1.03958 2.4968 + endloop + endfacet + facet normal 0.0869632 -0.296947 0.950926 + outer loop + vertex 1.59857 1.03958 2.4968 + vertex 1.59785 1.04329 2.49803 + vertex 1.59333 1.03895 2.49709 + endloop + endfacet + facet normal 0.0744695 -0.284964 0.955641 + outer loop + vertex 1.59333 1.03895 2.49709 + vertex 1.59785 1.04329 2.49803 + vertex 1.59276 1.04357 2.49851 + endloop + endfacet + facet normal 0.110866 -0.26682 0.957348 + outer loop + vertex 1.59187 1.03514 2.49611 + vertex 1.59243 1.03238 2.49528 + vertex 1.59552 1.03613 2.49596 + endloop + endfacet + facet normal 0.145671 -0.258445 0.95498 + outer loop + vertex 1.59243 1.03238 2.49528 + vertex 1.58757 1.02841 2.49494 + vertex 1.59266 1.02837 2.49416 + endloop + endfacet + facet normal 0.168136 -0.2693 0.948266 + outer loop + vertex 1.58923 1.03251 2.49578 + vertex 1.58855 1.03511 2.49664 + vertex 1.58547 1.03108 2.49604 + endloop + endfacet + facet normal 0.164571 -0.266779 0.949603 + outer loop + vertex 1.58855 1.03511 2.49664 + vertex 1.58316 1.03368 2.49717 + vertex 1.58547 1.03108 2.49604 + endloop + endfacet + facet normal 0.16582 -0.263762 0.950228 + outer loop + vertex 1.58787 1.02365 2.49357 + vertex 1.58757 1.02841 2.49494 + vertex 1.58277 1.02329 2.49436 + endloop + endfacet + facet normal 0.16962 -0.266819 0.948703 + outer loop + vertex 1.57789 1.01846 2.49387 + vertex 1.58277 1.02329 2.49436 + vertex 1.57794 1.02322 2.4952 + endloop + endfacet + facet normal 0.16875 -0.264687 0.949455 + outer loop + vertex 1.57929 1.02685 2.49598 + vertex 1.5765 1.02538 2.49606 + vertex 1.57794 1.02322 2.4952 + endloop + endfacet + facet normal 0.169652 -0.262856 0.949803 + outer loop + vertex 1.58166 1.02953 2.49629 + vertex 1.58247 1.02709 2.49548 + vertex 1.58547 1.03108 2.49604 + endloop + endfacet + facet normal 0.167324 -0.261918 0.950475 + outer loop + vertex 1.57929 1.02685 2.49598 + vertex 1.57779 1.02897 2.49682 + vertex 1.5765 1.02538 2.49606 + endloop + endfacet + facet normal 0.169518 -0.262507 0.949923 + outer loop + vertex 1.58547 1.03108 2.49604 + vertex 1.58316 1.03368 2.49717 + vertex 1.58166 1.02953 2.49629 + endloop + endfacet + facet normal 0.165387 -0.261729 0.950865 + outer loop + vertex 1.57779 1.02897 2.49682 + vertex 1.57782 1.03358 2.49809 + vertex 1.57291 1.02886 2.49764 + endloop + endfacet + facet normal 0.167674 -0.262153 0.950348 + outer loop + vertex 1.57782 1.03358 2.49809 + vertex 1.5828 1.03857 2.49859 + vertex 1.57773 1.0382 2.49938 + endloop + endfacet + facet normal 0.165511 -0.270796 0.948302 + outer loop + vertex 1.58855 1.03511 2.49664 + vertex 1.58804 1.03896 2.49783 + vertex 1.58316 1.03368 2.49717 + endloop + endfacet + facet normal 0.155038 -0.259262 0.953282 + outer loop + vertex 1.5828 1.03857 2.49859 + vertex 1.58765 1.04349 2.49913 + vertex 1.58254 1.04338 2.49994 + endloop + endfacet + facet normal 0.133265 -0.276435 0.951748 + outer loop + vertex 1.59333 1.03895 2.49709 + vertex 1.59276 1.04357 2.49851 + vertex 1.58804 1.03896 2.49783 + endloop + endfacet + facet normal 0.116811 -0.252635 0.960485 + outer loop + vertex 1.58765 1.04349 2.49913 + vertex 1.59239 1.04835 2.49984 + vertex 1.58733 1.04747 2.50022 + endloop + endfacet + facet normal 0.0749033 -0.279661 0.957173 + outer loop + vertex 1.59785 1.04329 2.49803 + vertex 1.59727 1.04754 2.49931 + vertex 1.59276 1.04357 2.49851 + endloop + endfacet + facet normal 0.114267 -0.236097 0.964988 + outer loop + vertex 1.58733 1.04747 2.50022 + vertex 1.59239 1.04835 2.49984 + vertex 1.59038 1.05135 2.50081 + endloop + endfacet + facet normal 0.0528959 -0.284813 0.957123 + outer loop + vertex 1.59669 1.0545 2.50121 + vertex 1.59345 1.05499 2.50154 + vertex 1.59403 1.05232 2.50071 + endloop + endfacet + facet normal 0.0510415 -0.295153 0.954086 + outer loop + vertex 1.59669 1.0545 2.50121 + vertex 1.59835 1.05826 2.50229 + vertex 1.59345 1.05499 2.50154 + endloop + endfacet + facet normal 0.0435587 -0.284767 0.957607 + outer loop + vertex 1.59835 1.05826 2.50229 + vertex 1.59299 1.05875 2.50268 + vertex 1.59345 1.05499 2.50154 + endloop + endfacet + facet normal 0.0454567 -0.267794 0.962403 + outer loop + vertex 1.59835 1.05826 2.50229 + vertex 1.59757 1.06301 2.50364 + vertex 1.59299 1.05875 2.50268 + endloop + endfacet + facet normal 0.0414298 -0.263751 0.963701 + outer loop + vertex 1.59299 1.05875 2.50268 + vertex 1.59757 1.06301 2.50364 + vertex 1.59247 1.0631 2.50389 + endloop + endfacet + facet normal 0.0413776 -0.265392 0.963252 + outer loop + vertex 1.59757 1.06301 2.50364 + vertex 1.59669 1.06718 2.50483 + vertex 1.59247 1.0631 2.50389 + endloop + endfacet + facet normal 0.0341808 -0.258436 0.965424 + outer loop + vertex 1.59247 1.0631 2.50389 + vertex 1.59669 1.06718 2.50483 + vertex 1.59183 1.06716 2.505 + endloop + endfacet + facet normal 0.0341356 -0.265824 0.963417 + outer loop + vertex 1.59183 1.06716 2.505 + vertex 1.59669 1.06718 2.50483 + vertex 1.59558 1.07095 2.50591 + endloop + endfacet + facet normal 0.108 -0.276089 0.955045 + outer loop + vertex 1.59345 1.05499 2.50154 + vertex 1.59299 1.05875 2.50268 + vertex 1.58824 1.05403 2.50185 + endloop + endfacet + facet normal 0.0923714 -0.261393 0.960802 + outer loop + vertex 1.58824 1.05403 2.50185 + vertex 1.59299 1.05875 2.50268 + vertex 1.58782 1.05866 2.50315 + endloop + endfacet + facet normal 0.131282 -0.248647 0.959656 + outer loop + vertex 1.58673 1.05014 2.501 + vertex 1.58733 1.04747 2.50022 + vertex 1.59038 1.05135 2.50081 + endloop + endfacet + facet normal 0.155247 -0.248397 0.956137 + outer loop + vertex 1.58733 1.04747 2.50022 + vertex 1.58254 1.04338 2.49994 + vertex 1.58765 1.04349 2.49913 + endloop + endfacet + facet normal 0.167462 -0.248217 0.95412 + outer loop + vertex 1.58413 1.04746 2.50073 + vertex 1.58345 1.05003 2.50152 + vertex 1.58045 1.04601 2.501 + endloop + endfacet + facet normal 0.162358 -0.244645 0.955923 + outer loop + vertex 1.58345 1.05003 2.50152 + vertex 1.57815 1.04861 2.50206 + vertex 1.58045 1.04601 2.501 + endloop + endfacet + facet normal 0.167554 -0.258068 0.951486 + outer loop + vertex 1.5828 1.03857 2.49859 + vertex 1.58254 1.04338 2.49994 + vertex 1.57773 1.0382 2.49938 + endloop + endfacet + facet normal 0.166577 -0.263411 0.950193 + outer loop + vertex 1.57278 1.03344 2.49893 + vertex 1.57773 1.0382 2.49938 + vertex 1.57302 1.03815 2.50019 + endloop + endfacet + facet normal 0.163936 -0.260477 0.95146 + outer loop + vertex 1.57441 1.0418 2.50095 + vertex 1.57165 1.04034 2.50103 + vertex 1.57302 1.03815 2.50019 + endloop + endfacet + facet normal 0.168775 -0.251634 0.952993 + outer loop + vertex 1.57672 1.04448 2.50125 + vertex 1.57752 1.04203 2.50047 + vertex 1.58045 1.04601 2.501 + endloop + endfacet + facet normal 0.158381 -0.249802 0.955256 + outer loop + vertex 1.57441 1.0418 2.50095 + vertex 1.5729 1.04395 2.50176 + vertex 1.57165 1.04034 2.50103 + endloop + endfacet + facet normal 0.165127 -0.24225 0.956059 + outer loop + vertex 1.58045 1.04601 2.501 + vertex 1.57815 1.04861 2.50206 + vertex 1.57672 1.04448 2.50125 + endloop + endfacet + facet normal 0.167352 -0.243056 0.955467 + outer loop + vertex 1.5729 1.04395 2.50176 + vertex 1.57282 1.04861 2.50296 + vertex 1.56793 1.0439 2.50262 + endloop + endfacet + facet normal 0.166919 -0.25581 0.952207 + outer loop + vertex 1.5729 1.04395 2.50176 + vertex 1.56793 1.0439 2.50262 + vertex 1.56842 1.04011 2.50152 + endloop + endfacet + facet normal 0.16909 -0.255442 0.951923 + outer loop + vertex 1.56842 1.04011 2.50152 + vertex 1.56793 1.0439 2.50262 + vertex 1.56309 1.03875 2.5021 + endloop + endfacet + facet normal 0.1735 -0.24924 0.952773 + outer loop + vertex 1.56793 1.0439 2.50262 + vertex 1.57282 1.04861 2.50296 + vertex 1.5677 1.04856 2.50388 + endloop + endfacet + facet normal 0.177157 -0.248902 0.952189 + outer loop + vertex 1.56793 1.0439 2.50262 + vertex 1.5677 1.04856 2.50388 + vertex 1.56266 1.04359 2.50352 + endloop + endfacet + facet normal 0.177339 -0.262837 0.948403 + outer loop + vertex 1.56309 1.03875 2.5021 + vertex 1.56793 1.0439 2.50262 + vertex 1.56266 1.04359 2.50352 + endloop + endfacet + facet normal 0.163016 -0.240684 0.956816 + outer loop + vertex 1.57282 1.04861 2.50296 + vertex 1.57777 1.0536 2.50337 + vertex 1.57265 1.05335 2.50418 + endloop + endfacet + facet normal 0.163029 -0.242381 0.956386 + outer loop + vertex 1.57777 1.0536 2.50337 + vertex 1.57753 1.05866 2.5047 + vertex 1.57265 1.05335 2.50418 + endloop + endfacet + facet normal 0.162819 -0.246593 0.955344 + outer loop + vertex 1.58345 1.05003 2.50152 + vertex 1.58298 1.05391 2.5026 + vertex 1.57815 1.04861 2.50206 + endloop + endfacet + facet normal 0.155523 -0.24301 0.957475 + outer loop + vertex 1.57777 1.0536 2.50337 + vertex 1.58274 1.05861 2.50384 + vertex 1.57753 1.05866 2.5047 + endloop + endfacet + facet normal 0.142532 -0.25553 0.956237 + outer loop + vertex 1.58824 1.05403 2.50185 + vertex 1.58782 1.05866 2.50315 + vertex 1.58298 1.05391 2.5026 + endloop + endfacet + facet normal 0.129606 -0.241955 0.961592 + outer loop + vertex 1.58274 1.05861 2.50384 + vertex 1.58757 1.06313 2.50432 + vertex 1.5829 1.06341 2.50502 + endloop + endfacet + facet normal 0.0923969 -0.257194 0.961933 + outer loop + vertex 1.59299 1.05875 2.50268 + vertex 1.59247 1.0631 2.50389 + vertex 1.58782 1.05866 2.50315 + endloop + endfacet + facet normal 0.12978 -0.240125 0.962028 + outer loop + vertex 1.58741 1.06702 2.50532 + vertex 1.5829 1.06341 2.50502 + vertex 1.58757 1.06313 2.50432 + endloop + endfacet + facet normal 0.160354 -0.254002 0.953818 + outer loop + vertex 1.58429 1.06712 2.50573 + vertex 1.58275 1.0692 2.50655 + vertex 1.58146 1.06566 2.50582 + endloop + endfacet + facet normal 0.163897 -0.255108 0.952921 + outer loop + vertex 1.58146 1.06566 2.50582 + vertex 1.58275 1.0692 2.50655 + vertex 1.57819 1.0653 2.50628 + endloop + endfacet + facet normal 0.155582 -0.241863 0.957756 + outer loop + vertex 1.5829 1.06341 2.50502 + vertex 1.57753 1.05866 2.5047 + vertex 1.58274 1.05861 2.50384 + endloop + endfacet + facet normal 0.169816 -0.232691 0.95761 + outer loop + vertex 1.56921 1.05705 2.50572 + vertex 1.56784 1.05337 2.50507 + vertex 1.57236 1.05728 2.50522 + endloop + endfacet + facet normal 0.170269 -0.246837 0.953981 + outer loop + vertex 1.57236 1.05728 2.50522 + vertex 1.57151 1.0597 2.50599 + vertex 1.56921 1.05705 2.50572 + endloop + endfacet + facet normal 0.193602 -0.266143 0.944291 + outer loop + vertex 1.57151 1.0597 2.50599 + vertex 1.56766 1.05906 2.5066 + vertex 1.56921 1.05705 2.50572 + endloop + endfacet + facet normal 0.203894 -0.258218 0.944325 + outer loop + vertex 1.56921 1.05705 2.50572 + vertex 1.56766 1.05906 2.5066 + vertex 1.56642 1.05555 2.50591 + endloop + endfacet + facet normal 0.192773 -0.259157 0.946402 + outer loop + vertex 1.57151 1.0597 2.50599 + vertex 1.57292 1.06373 2.50681 + vertex 1.56766 1.05906 2.5066 + endloop + endfacet + facet normal 0.167174 -0.251609 0.953281 + outer loop + vertex 1.57528 1.06128 2.50575 + vertex 1.57292 1.06373 2.50681 + vertex 1.57151 1.0597 2.50599 + endloop + endfacet + facet normal 0.165923 -0.248475 0.954322 + outer loop + vertex 1.57151 1.0597 2.50599 + vertex 1.57236 1.05728 2.50522 + vertex 1.57528 1.06128 2.50575 + endloop + endfacet + facet normal 0.173831 -0.239864 0.955117 + outer loop + vertex 1.57282 1.04861 2.50296 + vertex 1.57265 1.05335 2.50418 + vertex 1.5677 1.04856 2.50388 + endloop + endfacet + facet normal 0.190495 -0.261946 0.946095 + outer loop + vertex 1.56266 1.04359 2.50352 + vertex 1.5677 1.04856 2.50388 + vertex 1.56241 1.04856 2.50495 + endloop + endfacet + facet normal 0.195009 -0.240816 0.950778 + outer loop + vertex 1.56921 1.05705 2.50572 + vertex 1.56642 1.05555 2.50591 + vertex 1.56784 1.05337 2.50507 + endloop + endfacet + facet normal 0.220281 -0.263013 0.939308 + outer loop + vertex 1.56642 1.05555 2.50591 + vertex 1.56766 1.05906 2.5066 + vertex 1.56321 1.05517 2.50656 + endloop + endfacet + facet normal 0.167716 -0.242792 0.95547 + outer loop + vertex 1.56321 1.05517 2.50656 + vertex 1.56276 1.05876 2.50755 + vertex 1.55834 1.05374 2.50705 + endloop + endfacet + facet normal 0.060174 -0.332339 0.941238 + outer loop + vertex 1.55725 1.04704 2.50544 + vertex 1.55684 1.04969 2.5064 + vertex 1.55457 1.04707 2.50562 + endloop + endfacet + facet normal 0.222124 -0.2622 0.939102 + outer loop + vertex 1.56403 1.05283 2.50575 + vertex 1.56028 1.05116 2.50618 + vertex 1.56241 1.04856 2.50495 + endloop + endfacet + facet normal 0.142023 -0.266418 0.953337 + outer loop + vertex 1.56266 1.04359 2.50352 + vertex 1.56241 1.04856 2.50495 + vertex 1.55745 1.0431 2.50416 + endloop + endfacet + facet normal 0.0560779 -0.438823 0.896822 + outer loop + vertex 1.55457 1.04707 2.50562 + vertex 1.55266 1.04281 2.50366 + vertex 1.55725 1.04704 2.50544 + endloop + endfacet + facet normal 0.14068 -0.243431 0.959662 + outer loop + vertex 1.55765 1.03859 2.50299 + vertex 1.56266 1.04359 2.50352 + vertex 1.55745 1.0431 2.50416 + endloop + endfacet + facet normal 0.162877 -0.264721 0.95047 + outer loop + vertex 1.56309 1.03875 2.5021 + vertex 1.56266 1.04359 2.50352 + vertex 1.55765 1.03859 2.50299 + endloop + endfacet + facet normal 0.1686 -0.272158 0.947367 + outer loop + vertex 1.56547 1.03616 2.50093 + vertex 1.56309 1.03875 2.5021 + vertex 1.56167 1.0347 2.50119 + endloop + endfacet + facet normal 0.170128 -0.276398 0.945865 + outer loop + vertex 1.56167 1.0347 2.50119 + vertex 1.56251 1.0322 2.50031 + vertex 1.56547 1.03616 2.50093 + endloop + endfacet + facet normal 0.162868 -0.266749 0.949905 + outer loop + vertex 1.56251 1.0322 2.50031 + vertex 1.55798 1.02835 2.5 + vertex 1.5628 1.02828 2.49916 + endloop + endfacet + facet normal 0.179393 -0.278667 0.943484 + outer loop + vertex 1.55933 1.03207 2.50084 + vertex 1.55774 1.03417 2.50176 + vertex 1.55651 1.03063 2.50095 + endloop + endfacet + facet normal 0.178656 -0.278456 0.943687 + outer loop + vertex 1.55651 1.03063 2.50095 + vertex 1.55774 1.03417 2.50176 + vertex 1.55318 1.03031 2.50148 + endloop + endfacet + facet normal 0.172428 -0.2679 0.947891 + outer loop + vertex 1.55798 1.02835 2.5 + vertex 1.55255 1.02362 2.49965 + vertex 1.55792 1.02348 2.49864 + endloop + endfacet + facet normal 0.171696 -0.277437 0.945277 + outer loop + vertex 1.5529 1.01859 2.49811 + vertex 1.55792 1.02348 2.49864 + vertex 1.55255 1.02362 2.49965 + endloop + endfacet + facet normal 0.185704 -0.281908 0.941298 + outer loop + vertex 1.54712 1.02238 2.50035 + vertex 1.55255 1.02362 2.49965 + vertex 1.55021 1.02633 2.50093 + endloop + endfacet + facet normal 0.188462 -0.296903 0.936125 + outer loop + vertex 1.54763 1.01839 2.49898 + vertex 1.55255 1.02362 2.49965 + vertex 1.54712 1.02238 2.50035 + endloop + endfacet + facet normal 0.178419 -0.273611 0.945148 + outer loop + vertex 1.55651 1.03063 2.50095 + vertex 1.55318 1.03031 2.50148 + vertex 1.55411 1.02791 2.50061 + endloop + endfacet + facet normal 0.189755 -0.284818 0.939613 + outer loop + vertex 1.54646 1.02494 2.50126 + vertex 1.54712 1.02238 2.50035 + vertex 1.55021 1.02633 2.50093 + endloop + endfacet + facet normal 0.0175901 -0.210068 0.977528 + outer loop + vertex 1.54389 1.0225 2.50096 + vertex 1.54352 1.02488 2.50148 + vertex 1.54059 1.02182 2.50087 + endloop + endfacet + facet normal 0.130652 -0.306538 0.942849 + outer loop + vertex 1.54712 1.02238 2.50035 + vertex 1.54222 1.01875 2.49985 + vertex 1.54763 1.01839 2.49898 + endloop + endfacet + facet normal 0.167015 -0.277971 0.945959 + outer loop + vertex 1.5529 1.01859 2.49811 + vertex 1.55255 1.02362 2.49965 + vertex 1.54763 1.01839 2.49898 + endloop + endfacet + facet normal 0.15741 -0.263487 0.951734 + outer loop + vertex 1.55827 1.01853 2.49721 + vertex 1.55792 1.02348 2.49864 + vertex 1.5529 1.01859 2.49811 + endloop + endfacet + facet normal 0.149025 -0.262466 0.953364 + outer loop + vertex 1.56057 1.01591 2.49613 + vertex 1.55827 1.01853 2.49721 + vertex 1.55679 1.01446 2.49632 + endloop + endfacet + facet normal 0.150735 -0.267116 0.951803 + outer loop + vertex 1.55679 1.01446 2.49632 + vertex 1.55756 1.01202 2.49551 + vertex 1.56057 1.01591 2.49613 + endloop + endfacet + facet normal 0.151845 -0.273715 0.949749 + outer loop + vertex 1.55756 1.01202 2.49551 + vertex 1.55297 1.00821 2.49515 + vertex 1.55782 1.00824 2.49438 + endloop + endfacet + facet normal 0.149424 -0.267699 0.951845 + outer loop + vertex 1.55439 1.01183 2.49596 + vertex 1.55294 1.01397 2.49679 + vertex 1.55157 1.0104 2.496 + endloop + endfacet + facet normal 0.147659 -0.267118 0.952284 + outer loop + vertex 1.55157 1.0104 2.496 + vertex 1.55294 1.01397 2.49679 + vertex 1.54848 1.01029 2.49645 + endloop + endfacet + facet normal 0.144984 -0.278239 0.949506 + outer loop + vertex 1.54848 1.01029 2.49645 + vertex 1.54813 1.01396 2.49758 + vertex 1.54399 1.00962 2.49694 + endloop + endfacet + facet normal 0.139033 -0.283415 0.948865 + outer loop + vertex 1.54913 1.00777 2.49562 + vertex 1.54526 1.00645 2.49579 + vertex 1.54759 1.00363 2.49461 + endloop + endfacet + facet normal 0.141229 -0.277391 0.95032 + outer loop + vertex 1.55297 1.00821 2.49515 + vertex 1.54759 1.00363 2.49461 + vertex 1.55297 1.00357 2.49379 + endloop + endfacet + facet normal 0.152832 -0.278621 0.948163 + outer loop + vertex 1.55343 0.998785 2.49231 + vertex 1.55813 1.00379 2.49303 + vertex 1.55297 1.00357 2.49379 + endloop + endfacet + facet normal 0.154931 -0.281982 0.946828 + outer loop + vertex 1.55557 0.995952 2.49112 + vertex 1.55343 0.998785 2.49231 + vertex 1.55193 0.994746 2.49136 + endloop + endfacet + facet normal 0.158203 -0.292595 0.943059 + outer loop + vertex 1.55193 0.994746 2.49136 + vertex 1.55249 0.992056 2.49043 + vertex 1.55557 0.995952 2.49112 + endloop + endfacet + facet normal 0.121516 -0.289898 0.949312 + outer loop + vertex 1.54929 0.992192 2.49097 + vertex 1.54877 0.994999 2.49189 + vertex 1.54549 0.991195 2.49115 + endloop + endfacet + facet normal 0.13653 -0.297325 0.944964 + outer loop + vertex 1.55249 0.992056 2.49043 + vertex 1.54759 0.988202 2.48992 + vertex 1.55279 0.988244 2.48918 + endloop + endfacet + facet normal 0.151608 -0.290232 0.944871 + outer loop + vertex 1.55319 0.98403 2.48783 + vertex 1.55786 0.988587 2.48848 + vertex 1.55279 0.988244 2.48918 + endloop + endfacet + facet normal 0.148641 -0.286057 0.946613 + outer loop + vertex 1.55818 0.984023 2.48704 + vertex 1.55319 0.98403 2.48783 + vertex 1.55351 0.98027 2.48664 + endloop + endfacet + facet normal 0.158495 -0.284156 0.945587 + outer loop + vertex 1.56325 0.985167 2.48653 + vertex 1.55818 0.984023 2.48704 + vertex 1.56025 0.981302 2.48588 + endloop + endfacet + facet normal 0.149115 -0.295238 0.943715 + outer loop + vertex 1.55727 0.977406 2.48517 + vertex 1.55662 0.98009 2.48611 + vertex 1.55402 0.977525 2.48572 + endloop + endfacet + facet normal 0.160218 -0.285593 0.944863 + outer loop + vertex 1.56388 0.982557 2.48564 + vertex 1.56025 0.981302 2.48588 + vertex 1.56243 0.97854 2.48467 + endloop + endfacet + facet normal 0.150542 -0.288752 0.945494 + outer loop + vertex 1.56303 0.97387 2.48315 + vertex 1.56243 0.97854 2.48467 + vertex 1.55782 0.973503 2.48387 + endloop + endfacet + facet normal 0.147792 -0.310115 0.939141 + outer loop + vertex 1.55402 0.977525 2.48572 + vertex 1.55251 0.973515 2.48464 + vertex 1.55727 0.977406 2.48517 + endloop + endfacet + facet normal 0.130258 -0.295122 0.946539 + outer loop + vertex 1.55844 0.968861 2.48233 + vertex 1.55782 0.973503 2.48387 + vertex 1.55329 0.968997 2.48309 + endloop + endfacet + facet normal 0.100275 -0.31988 0.942137 + outer loop + vertex 1.54801 0.953585 2.47851 + vertex 1.55265 0.958429 2.47966 + vertex 1.54699 0.957386 2.47991 + endloop + endfacet + facet normal 0.101036 -0.320758 0.941757 + outer loop + vertex 1.54903 0.949777 2.47711 + vertex 1.54801 0.953585 2.47851 + vertex 1.54343 0.948793 2.47737 + endloop + endfacet + facet normal 0.101355 -0.322773 0.941034 + outer loop + vertex 1.54903 0.949777 2.47711 + vertex 1.54343 0.948793 2.47737 + vertex 1.54563 0.945753 2.47609 + endloop + endfacet + facet normal 0.103477 -0.32134 0.941293 + outer loop + vertex 1.54563 0.945753 2.47609 + vertex 1.54343 0.948793 2.47737 + vertex 1.54184 0.944883 2.47621 + endloop + endfacet + facet normal 0.10413 -0.324336 0.940193 + outer loop + vertex 1.54184 0.944883 2.47621 + vertex 1.5424 0.94211 2.47519 + vertex 1.54563 0.945753 2.47609 + endloop + endfacet + facet normal 0.104805 -0.327874 0.93889 + outer loop + vertex 1.5424 0.94211 2.47519 + vertex 1.53785 0.938556 2.47446 + vertex 1.5431 0.938513 2.47386 + endloop + endfacet + facet normal 0.110071 -0.323698 0.939736 + outer loop + vertex 1.53921 0.942478 2.47569 + vertex 1.53866 0.945273 2.47671 + vertex 1.5354 0.941568 2.47582 + endloop + endfacet + facet normal 0.11175 -0.346616 0.931326 + outer loop + vertex 1.53353 0.933401 2.47306 + vertex 1.53785 0.938556 2.47446 + vertex 1.53218 0.937495 2.47475 + endloop + endfacet + facet normal 0.110637 -0.346983 0.931323 + outer loop + vertex 1.53353 0.933401 2.47306 + vertex 1.53218 0.937495 2.47475 + vertex 1.52824 0.933549 2.47374 + endloop + endfacet + facet normal 0.109697 -0.359378 0.926722 + outer loop + vertex 1.53353 0.933401 2.47306 + vertex 1.52824 0.933549 2.47374 + vertex 1.52897 0.929969 2.47227 + endloop + endfacet + facet normal 0.112908 -0.358675 0.926609 + outer loop + vertex 1.52897 0.929969 2.47227 + vertex 1.52824 0.933549 2.47374 + vertex 1.52427 0.929617 2.4727 + endloop + endfacet + facet normal 0.11373 -0.380714 0.917672 + outer loop + vertex 1.52897 0.929969 2.47227 + vertex 1.52427 0.929617 2.4727 + vertex 1.52576 0.926439 2.4712 + endloop + endfacet + facet normal 0.124102 -0.376123 0.918221 + outer loop + vertex 1.52576 0.926439 2.4712 + vertex 1.52427 0.929617 2.4727 + vertex 1.52099 0.925588 2.4715 + endloop + endfacet + facet normal 0.130262 -0.417144 0.899457 + outer loop + vertex 1.52099 0.925588 2.4715 + vertex 1.52248 0.922553 2.46987 + vertex 1.52576 0.926439 2.4712 + endloop + endfacet + facet normal 0.132447 -0.418643 0.898441 + outer loop + vertex 1.52248 0.922553 2.46987 + vertex 1.52812 0.923674 2.46957 + vertex 1.52576 0.926439 2.4712 + endloop + endfacet + facet normal 0.144169 -0.410778 0.900265 + outer loop + vertex 1.51772 0.92194 2.47036 + vertex 1.52248 0.922553 2.46987 + vertex 1.52099 0.925588 2.4715 + endloop + endfacet + facet normal 0.144454 -0.41099 0.900122 + outer loop + vertex 1.5171 0.924561 2.47165 + vertex 1.51772 0.92194 2.47036 + vertex 1.52099 0.925588 2.4715 + endloop + endfacet + facet normal 0.134769 -0.371488 0.918605 + outer loop + vertex 1.52099 0.925588 2.4715 + vertex 1.51853 0.928454 2.47302 + vertex 1.5171 0.924561 2.47165 + endloop + endfacet + facet normal 0.149259 -0.477176 0.86604 + outer loop + vertex 1.51849 0.918372 2.46826 + vertex 1.52248 0.922553 2.46987 + vertex 1.51772 0.92194 2.47036 + endloop + endfacet + facet normal 0.126544 -0.377805 0.917197 + outer loop + vertex 1.52427 0.929617 2.4727 + vertex 1.51853 0.928454 2.47302 + vertex 1.52099 0.925588 2.4715 + endloop + endfacet + facet normal 0.122671 -0.356223 0.926314 + outer loop + vertex 1.52427 0.929617 2.4727 + vertex 1.52294 0.933657 2.47443 + vertex 1.51853 0.928454 2.47302 + endloop + endfacet + facet normal 0.123664 -0.356951 0.925901 + outer loop + vertex 1.51853 0.928454 2.47302 + vertex 1.52294 0.933657 2.47443 + vertex 1.51728 0.932537 2.47476 + endloop + endfacet + facet normal 0.113548 -0.359242 0.926311 + outer loop + vertex 1.52427 0.929617 2.4727 + vertex 1.52824 0.933549 2.47374 + vertex 1.52294 0.933657 2.47443 + endloop + endfacet + facet normal 0.11241 -0.348549 0.930525 + outer loop + vertex 1.52824 0.933549 2.47374 + vertex 1.53218 0.937495 2.47475 + vertex 1.52748 0.937151 2.47518 + endloop + endfacet + facet normal 0.111925 -0.335891 0.935227 + outer loop + vertex 1.52748 0.937151 2.47518 + vertex 1.53218 0.937495 2.47475 + vertex 1.53067 0.940788 2.47611 + endloop + endfacet + facet normal 0.113927 -0.337441 0.934427 + outer loop + vertex 1.52683 0.939907 2.47626 + vertex 1.52748 0.937151 2.47518 + vertex 1.53067 0.940788 2.47611 + endloop + endfacet + facet normal 0.110226 -0.32382 0.939676 + outer loop + vertex 1.53866 0.945273 2.47671 + vertex 1.53401 0.944856 2.47712 + vertex 1.5354 0.941568 2.47582 + endloop + endfacet + facet normal 0.110861 -0.323145 0.939833 + outer loop + vertex 1.53067 0.940788 2.47611 + vertex 1.52839 0.943825 2.47742 + vertex 1.52683 0.939907 2.47626 + endloop + endfacet + facet normal 0.108128 -0.316066 0.942555 + outer loop + vertex 1.53401 0.944856 2.47712 + vertex 1.5382 0.949062 2.47804 + vertex 1.53295 0.948669 2.47852 + endloop + endfacet + facet normal 0.109813 -0.312676 0.943491 + outer loop + vertex 1.52425 0.952448 2.48078 + vertex 1.52261 0.948514 2.47966 + vertex 1.52737 0.952057 2.48029 + endloop + endfacet + facet normal 0.109075 -0.312409 0.943665 + outer loop + vertex 1.53295 0.948669 2.47852 + vertex 1.53194 0.952484 2.4799 + vertex 1.52774 0.948268 2.47899 + endloop + endfacet + facet normal 0.108062 -0.312685 0.94369 + outer loop + vertex 1.53295 0.948669 2.47852 + vertex 1.53753 0.953524 2.4796 + vertex 1.53194 0.952484 2.4799 + endloop + endfacet + facet normal 0.107796 -0.311095 0.944246 + outer loop + vertex 1.53194 0.952484 2.4799 + vertex 1.53753 0.953524 2.4796 + vertex 1.53535 0.956581 2.48086 + endloop + endfacet + facet normal 0.111081 -0.316963 0.94191 + outer loop + vertex 1.5307 0.955775 2.48113 + vertex 1.52853 0.958801 2.48241 + vertex 1.52693 0.95486 2.48127 + endloop + endfacet + facet normal 0.112744 -0.318287 0.941266 + outer loop + vertex 1.52853 0.958801 2.48241 + vertex 1.53304 0.963645 2.48351 + vertex 1.52784 0.963219 2.48398 + endloop + endfacet + facet normal 0.107257 -0.320519 0.94115 + outer loop + vertex 1.5387 0.960275 2.48172 + vertex 1.53826 0.964038 2.48305 + vertex 1.53409 0.95986 2.48211 + endloop + endfacet + facet normal 0.098121 -0.318846 0.942714 + outer loop + vertex 1.5435 0.963751 2.48241 + vertex 1.54276 0.968184 2.48399 + vertex 1.53826 0.964038 2.48305 + endloop + endfacet + facet normal 0.0995605 -0.312893 0.944556 + outer loop + vertex 1.53914 0.972374 2.48576 + vertex 1.53867 0.975161 2.48673 + vertex 1.53536 0.971496 2.48587 + endloop + endfacet + facet normal 0.105859 -0.317281 0.942405 + outer loop + vertex 1.53304 0.963645 2.48351 + vertex 1.53756 0.96846 2.48462 + vertex 1.53199 0.96743 2.4849 + endloop + endfacet + facet normal 0.113601 -0.31157 0.943408 + outer loop + vertex 1.52743 0.96698 2.4853 + vertex 1.53199 0.96743 2.4849 + vertex 1.53072 0.970707 2.48613 + endloop + endfacet + facet normal 0.114196 -0.312045 0.943179 + outer loop + vertex 1.52697 0.969776 2.48628 + vertex 1.52743 0.96698 2.4853 + vertex 1.53072 0.970707 2.48613 + endloop + endfacet + facet normal 0.100058 -0.313298 0.944369 + outer loop + vertex 1.53867 0.975161 2.48673 + vertex 1.53409 0.974784 2.48709 + vertex 1.53536 0.971496 2.48587 + endloop + endfacet + facet normal 0.112816 -0.306139 0.945279 + outer loop + vertex 1.53072 0.970707 2.48613 + vertex 1.52855 0.973778 2.48739 + vertex 1.52697 0.969776 2.48628 + endloop + endfacet + facet normal 0.102204 -0.302264 0.947729 + outer loop + vertex 1.52855 0.973778 2.48739 + vertex 1.53319 0.978678 2.48845 + vertex 1.52794 0.978423 2.48893 + endloop + endfacet + facet normal 0.0998399 -0.309407 0.945674 + outer loop + vertex 1.53867 0.975161 2.48673 + vertex 1.53829 0.978906 2.488 + vertex 1.53409 0.974784 2.48709 + endloop + endfacet + facet normal 0.0951126 -0.299985 0.949191 + outer loop + vertex 1.5344 0.987093 2.49099 + vertex 1.53376 0.989815 2.49191 + vertex 1.53063 0.986087 2.49105 + endloop + endfacet + facet normal 0.0979546 -0.302151 0.948214 + outer loop + vertex 1.53376 0.989815 2.49191 + vertex 1.52846 0.988933 2.49218 + vertex 1.53063 0.986087 2.49105 + endloop + endfacet + facet normal 0.102163 -0.300088 0.948425 + outer loop + vertex 1.53319 0.978678 2.48845 + vertex 1.53271 0.983203 2.48993 + vertex 1.52794 0.978423 2.48893 + endloop + endfacet + facet normal 0.109884 -0.300866 0.947315 + outer loop + vertex 1.52335 0.974018 2.48807 + vertex 1.52794 0.978423 2.48893 + vertex 1.5226 0.978546 2.48959 + endloop + endfacet + facet normal 0.118251 -0.29924 0.946822 + outer loop + vertex 1.52415 0.982552 2.49066 + vertex 1.52034 0.98155 2.49082 + vertex 1.5226 0.978546 2.48959 + endloop + endfacet + facet normal 0.103042 -0.297941 0.949007 + outer loop + vertex 1.52685 0.985047 2.49113 + vertex 1.52746 0.982318 2.49021 + vertex 1.53063 0.986087 2.49105 + endloop + endfacet + facet normal 0.118013 -0.298282 0.947154 + outer loop + vertex 1.52415 0.982552 2.49066 + vertex 1.52366 0.985321 2.4916 + vertex 1.52034 0.98155 2.49082 + endloop + endfacet + facet normal 0.103172 -0.298426 0.94884 + outer loop + vertex 1.53063 0.986087 2.49105 + vertex 1.52846 0.988933 2.49218 + vertex 1.52685 0.985047 2.49113 + endloop + endfacet + facet normal 0.115719 -0.291835 0.949443 + outer loop + vertex 1.52366 0.985321 2.4916 + vertex 1.52328 0.989068 2.4928 + vertex 1.51907 0.984839 2.49201 + endloop + endfacet + facet normal 0.101539 -0.288356 0.952124 + outer loop + vertex 1.52328 0.989068 2.4928 + vertex 1.52788 0.993426 2.49362 + vertex 1.52272 0.993137 2.49409 + endloop + endfacet + facet normal 0.0971715 -0.296916 0.949947 + outer loop + vertex 1.53376 0.989815 2.49191 + vertex 1.5332 0.993676 2.49317 + vertex 1.52846 0.988933 2.49218 + endloop + endfacet + facet normal 0.0962505 -0.299098 0.949356 + outer loop + vertex 1.52788 0.993426 2.49362 + vertex 1.53264 0.998261 2.49467 + vertex 1.52705 0.997291 2.49493 + endloop + endfacet + facet normal 0.0920339 -0.294979 0.951061 + outer loop + vertex 1.53858 0.993479 2.49259 + vertex 1.5378 0.997997 2.49407 + vertex 1.5332 0.993676 2.49317 + endloop + endfacet + facet normal 0.102867 -0.292954 0.950577 + outer loop + vertex 1.53858 0.993479 2.49259 + vertex 1.54303 0.998446 2.49364 + vertex 1.5378 0.997997 2.49407 + endloop + endfacet + facet normal 0.102939 -0.294146 0.950201 + outer loop + vertex 1.54303 0.998446 2.49364 + vertex 1.54194 1.00227 2.49495 + vertex 1.5378 0.997997 2.49407 + endloop + endfacet + facet normal 0.107765 -0.298428 0.948329 + outer loop + vertex 1.5378 0.997997 2.49407 + vertex 1.54194 1.00227 2.49495 + vertex 1.53743 1.00178 2.4953 + endloop + endfacet + facet normal 0.10815 -0.303 0.946834 + outer loop + vertex 1.53743 1.00178 2.4953 + vertex 1.54194 1.00227 2.49495 + vertex 1.54069 1.00547 2.49611 + endloop + endfacet + facet normal 0.0995869 -0.290267 0.95175 + outer loop + vertex 1.54417 0.994529 2.49233 + vertex 1.54303 0.998446 2.49364 + vertex 1.53858 0.993479 2.49259 + endloop + endfacet + facet normal 0.0997447 -0.291182 0.951454 + outer loop + vertex 1.54417 0.994529 2.49233 + vertex 1.53858 0.993479 2.49259 + vertex 1.54086 0.99041 2.49141 + endloop + endfacet + facet normal 0.0917931 -0.296733 0.950538 + outer loop + vertex 1.54086 0.99041 2.49141 + vertex 1.53858 0.993479 2.49259 + vertex 1.53709 0.989514 2.4915 + endloop + endfacet + facet normal 0.0924154 -0.299442 0.949628 + outer loop + vertex 1.53709 0.989514 2.4915 + vertex 1.53752 0.986728 2.49058 + vertex 1.54086 0.99041 2.49141 + endloop + endfacet + facet normal 0.0958049 -0.302237 0.948406 + outer loop + vertex 1.53752 0.986728 2.49058 + vertex 1.54204 0.987107 2.49024 + vertex 1.54086 0.99041 2.49141 + endloop + endfacet + facet normal 0.106539 -0.312556 0.943906 + outer loop + vertex 1.53437 1.00216 2.49576 + vertex 1.53057 1.00131 2.49591 + vertex 1.53264 0.998261 2.49467 + endloop + endfacet + facet normal 0.118093 -0.310948 0.943062 + outer loop + vertex 1.53702 1.00454 2.49626 + vertex 1.53743 1.00178 2.4953 + vertex 1.54069 1.00547 2.49611 + endloop + endfacet + facet normal 0.109909 -0.328589 0.938056 + outer loop + vertex 1.53437 1.00216 2.49576 + vertex 1.53389 1.00499 2.49681 + vertex 1.53057 1.00131 2.49591 + endloop + endfacet + facet normal 0.117062 -0.306641 0.944599 + outer loop + vertex 1.54069 1.00547 2.49611 + vertex 1.5385 1.00862 2.49741 + vertex 1.53702 1.00454 2.49626 + endloop + endfacet + facet normal 0.134028 -0.295408 0.945923 + outer loop + vertex 1.54399 1.00962 2.49694 + vertex 1.5385 1.00862 2.49741 + vertex 1.54069 1.00547 2.49611 + endloop + endfacet + facet normal 0.132869 -0.287878 0.948405 + outer loop + vertex 1.54399 1.00962 2.49694 + vertex 1.54298 1.01371 2.49832 + vertex 1.5385 1.00862 2.49741 + endloop + endfacet + facet normal 0.106075 -0.26602 0.958113 + outer loop + vertex 1.5385 1.00862 2.49741 + vertex 1.54298 1.01371 2.49832 + vertex 1.53751 1.01387 2.49897 + endloop + endfacet + facet normal 0.118282 -0.309704 0.943447 + outer loop + vertex 1.53389 1.00499 2.49681 + vertex 1.53324 1.00911 2.49824 + vertex 1.52928 1.00467 2.49728 + endloop + endfacet + facet normal 0.119136 -0.336002 0.934296 + outer loop + vertex 1.53389 1.00499 2.49681 + vertex 1.52928 1.00467 2.49728 + vertex 1.53057 1.00131 2.49591 + endloop + endfacet + facet normal 0.0991167 -0.317276 0.943139 + outer loop + vertex 1.52705 0.997291 2.49493 + vertex 1.53264 0.998261 2.49467 + vertex 1.53057 1.00131 2.49591 + endloop + endfacet + facet normal 0.101804 -0.297842 0.949171 + outer loop + vertex 1.52788 0.993426 2.49362 + vertex 1.52705 0.997291 2.49493 + vertex 1.52272 0.993137 2.49409 + endloop + endfacet + facet normal 0.112601 -0.288798 0.950745 + outer loop + vertex 1.51814 0.988736 2.49329 + vertex 1.52272 0.993137 2.49409 + vertex 1.51759 0.993284 2.49474 + endloop + endfacet + facet normal 0.129011 -0.314043 0.940603 + outer loop + vertex 1.51935 0.997248 2.49582 + vertex 1.51555 0.996334 2.49604 + vertex 1.51759 0.993284 2.49474 + endloop + endfacet + facet normal 0.113571 -0.333539 0.93587 + outer loop + vertex 1.52211 0.999679 2.49634 + vertex 1.52247 0.996883 2.4953 + vertex 1.52591 1.00057 2.4962 + endloop + endfacet + facet normal 0.136428 -0.347973 0.927525 + outer loop + vertex 1.51935 0.997248 2.49582 + vertex 1.51895 1.00008 2.49694 + vertex 1.51555 0.996334 2.49604 + endloop + endfacet + facet normal 0.128435 -0.34156 0.931043 + outer loop + vertex 1.51895 1.00008 2.49694 + vertex 1.51438 0.99969 2.49743 + vertex 1.51555 0.996334 2.49604 + endloop + endfacet + facet normal 0.114465 -0.337592 0.934307 + outer loop + vertex 1.52591 1.00057 2.4962 + vertex 1.52368 1.0037 2.4976 + vertex 1.52211 0.999679 2.49634 + endloop + endfacet + facet normal 0.126828 -0.307772 0.942969 + outer loop + vertex 1.51895 1.00008 2.49694 + vertex 1.51848 1.00398 2.49828 + vertex 1.51438 0.99969 2.49743 + endloop + endfacet + facet normal 0.0408897 -0.242516 0.969285 + outer loop + vertex 1.52368 1.0037 2.4976 + vertex 1.52796 1.00872 2.49868 + vertex 1.52267 1.00835 2.49881 + endloop + endfacet + facet normal -0.187122 0.0933601 0.97789 + outer loop + vertex 1.52267 1.00835 2.49881 + vertex 1.52642 1.01221 2.49915 + vertex 1.52133 1.01272 2.49813 + endloop + endfacet + facet normal 0.0929658 -0.127404 0.987485 + outer loop + vertex 1.51848 1.00398 2.49828 + vertex 1.51743 1.00822 2.49893 + vertex 1.51337 1.00371 2.49873 + endloop + endfacet + facet normal 0.0981551 -0.282556 0.954216 + outer loop + vertex 1.51438 0.99969 2.49743 + vertex 1.51848 1.00398 2.49828 + vertex 1.51337 1.00371 2.49873 + endloop + endfacet + facet normal 0.114196 -0.324212 0.939066 + outer loop + vertex 1.50752 0.991758 2.49548 + vertex 1.51204 0.992223 2.49509 + vertex 1.51092 0.995518 2.49637 + endloop + endfacet + facet normal 0.118858 -0.338939 0.93327 + outer loop + vertex 1.50712 0.99452 2.49647 + vertex 1.50881 0.998621 2.49775 + vertex 1.50386 0.994743 2.49697 + endloop + endfacet + facet normal 0.113739 -0.338528 0.934057 + outer loop + vertex 1.50386 0.994743 2.49697 + vertex 1.50351 0.998787 2.49848 + vertex 1.49861 0.993811 2.49727 + endloop + endfacet + facet normal 0.112413 -0.299228 0.947537 + outer loop + vertex 1.5044 0.992018 2.49593 + vertex 1.50067 0.990935 2.49603 + vertex 1.50275 0.988146 2.49491 + endloop + endfacet + facet normal 0.108082 -0.288366 0.951401 + outer loop + vertex 1.50331 0.98366 2.49348 + vertex 1.50275 0.988146 2.49491 + vertex 1.498 0.983339 2.49399 + endloop + endfacet + facet normal 0.110739 -0.294768 0.94913 + outer loop + vertex 1.49322 0.97882 2.49314 + vertex 1.498 0.983339 2.49399 + vertex 1.49261 0.983435 2.49465 + endloop + endfacet + facet normal 0.110207 -0.295132 0.949079 + outer loop + vertex 1.49422 0.987387 2.49566 + vertex 1.49374 0.990155 2.49657 + vertex 1.4904 0.986433 2.4958 + endloop + endfacet + facet normal 0.113354 -0.291142 0.949941 + outer loop + vertex 1.48791 0.978473 2.49369 + vertex 1.49261 0.983435 2.49465 + vertex 1.48702 0.982365 2.49499 + endloop + endfacet + facet normal 0.106104 -0.291763 0.950587 + outer loop + vertex 1.49374 0.990155 2.49657 + vertex 1.48914 0.989732 2.49696 + vertex 1.4904 0.986433 2.4958 + endloop + endfacet + facet normal 0.114936 -0.280844 0.952847 + outer loop + vertex 1.48254 0.981937 2.4954 + vertex 1.48702 0.982365 2.49499 + vertex 1.48579 0.985642 2.4961 + endloop + endfacet + facet normal 0.118239 -0.286587 0.95073 + outer loop + vertex 1.48254 0.981937 2.4954 + vertex 1.47782 0.978307 2.4949 + vertex 1.48283 0.978161 2.49423 + endloop + endfacet + facet normal 0.117034 -0.283136 0.951912 + outer loop + vertex 1.4726 0.977329 2.49525 + vertex 1.47782 0.978307 2.4949 + vertex 1.47571 0.981144 2.496 + endloop + endfacet + facet normal 0.115635 -0.278705 0.95339 + outer loop + vertex 1.48206 0.984704 2.49627 + vertex 1.47876 0.984924 2.49674 + vertex 1.47944 0.982239 2.49587 + endloop + endfacet + facet normal 0.115833 -0.279662 0.953085 + outer loop + vertex 1.47571 0.981144 2.496 + vertex 1.47344 0.983924 2.49709 + vertex 1.47193 0.980006 2.49612 + endloop + endfacet + facet normal 0.121925 -0.296662 0.947167 + outer loop + vertex 1.47344 0.983924 2.49709 + vertex 1.47822 0.988818 2.49801 + vertex 1.47291 0.988576 2.49862 + endloop + endfacet + facet normal 0.122149 -0.325407 0.937651 + outer loop + vertex 1.47822 0.988818 2.49801 + vertex 1.47782 0.993544 2.4997 + vertex 1.47291 0.988576 2.49862 + endloop + endfacet + facet normal 0.127707 -0.324753 0.937137 + outer loop + vertex 1.47822 0.988818 2.49801 + vertex 1.48294 0.993303 2.49892 + vertex 1.47782 0.993544 2.4997 + endloop + endfacet + facet normal 0.116619 -0.316897 0.941263 + outer loop + vertex 1.48914 0.989732 2.49696 + vertex 1.48819 0.993696 2.49841 + vertex 1.48356 0.988673 2.49729 + endloop + endfacet + facet normal 0.126124 -0.340686 0.931679 + outer loop + vertex 1.48267 0.99727 2.50041 + vertex 1.47782 0.993544 2.4997 + vertex 1.48294 0.993303 2.49892 + endloop + endfacet + facet normal 0.0950778 -0.235341 0.967251 + outer loop + vertex 1.47948 0.997555 2.50094 + vertex 1.47839 0.999974 2.50164 + vertex 1.47572 0.996402 2.50103 + endloop + endfacet + facet normal 0.128115 -0.330717 0.934993 + outer loop + vertex 1.47291 0.988576 2.49862 + vertex 1.47782 0.993544 2.4997 + vertex 1.47259 0.992587 2.50008 + endloop + endfacet + facet normal 0.142836 -0.349252 0.926078 + outer loop + vertex 1.47259 0.992587 2.50008 + vertex 1.47205 0.995316 2.50119 + vertex 1.46937 0.992815 2.50066 + endloop + endfacet + facet normal 0.108806 -0.244975 0.963405 + outer loop + vertex 1.47839 0.999974 2.50164 + vertex 1.47307 0.998857 2.50195 + vertex 1.47572 0.996402 2.50103 + endloop + endfacet + facet normal 0.120156 0.12557 0.984782 + outer loop + vertex 1.47307 0.998857 2.50195 + vertex 1.47067 1.0022 2.50182 + vertex 1.46785 0.998877 2.50259 + endloop + endfacet + facet normal 0.0569487 0.178707 0.982253 + outer loop + vertex 1.46785 0.998877 2.50259 + vertex 1.47067 1.0022 2.50182 + vertex 1.46552 1.00196 2.50216 + endloop + endfacet + facet normal 0.0865666 -0.179112 0.980013 + outer loop + vertex 1.46432 0.995026 2.50223 + vertex 1.46276 0.998506 2.503 + vertex 1.4588 0.993963 2.50252 + endloop + endfacet + facet normal 0.119521 -0.324675 0.938243 + outer loop + vertex 1.46094 0.990919 2.5012 + vertex 1.4588 0.993963 2.50252 + vertex 1.45717 0.989973 2.50135 + endloop + endfacet + facet normal 0.128945 -0.364698 0.922154 + outer loop + vertex 1.45717 0.989973 2.50135 + vertex 1.45742 0.987088 2.50017 + vertex 1.46094 0.990919 2.5012 + endloop + endfacet + facet normal 0.119259 -0.324319 0.9384 + outer loop + vertex 1.45742 0.987088 2.50017 + vertex 1.45255 0.983422 2.49952 + vertex 1.45762 0.983235 2.49882 + endloop + endfacet + facet normal 0.131718 -0.359199 0.923919 + outer loop + vertex 1.45437 0.987476 2.50075 + vertex 1.45408 0.990355 2.50191 + vertex 1.4506 0.986552 2.50092 + endloop + endfacet + facet normal 0.115641 -0.298964 0.947232 + outer loop + vertex 1.44787 0.978451 2.49853 + vertex 1.45255 0.983422 2.49952 + vertex 1.44704 0.982403 2.49988 + endloop + endfacet + facet normal 0.108373 -0.340467 0.93399 + outer loop + vertex 1.45408 0.990355 2.50191 + vertex 1.44948 0.989906 2.50228 + vertex 1.4506 0.986552 2.50092 + endloop + endfacet + facet normal 0.0831197 -0.19812 0.976647 + outer loop + vertex 1.44948 0.989906 2.50228 + vertex 1.44816 0.993753 2.50317 + vertex 1.44386 0.988761 2.50252 + endloop + endfacet + facet normal 0.113775 -0.339012 0.933877 + outer loop + vertex 1.44252 0.98199 2.50028 + vertex 1.44704 0.982403 2.49988 + vertex 1.44599 0.985744 2.50122 + endloop + endfacet + facet normal 0.109786 -0.302913 0.946673 + outer loop + vertex 1.44252 0.98199 2.50028 + vertex 1.4377 0.978366 2.49968 + vertex 1.44277 0.978192 2.49903 + endloop + endfacet + facet normal 0.1239 -0.3483 0.929159 + outer loop + vertex 1.44218 0.984767 2.50132 + vertex 1.43894 0.984954 2.50182 + vertex 1.4394 0.982276 2.50076 + endloop + endfacet + facet normal 0.114418 -0.313174 0.942778 + outer loop + vertex 1.43245 0.9774 2.49999 + vertex 1.4377 0.978366 2.49968 + vertex 1.43566 0.981171 2.50085 + endloop + endfacet + facet normal 0.108784 -0.290289 0.950736 + outer loop + vertex 1.43245 0.9774 2.49999 + vertex 1.42759 0.973644 2.4994 + vertex 1.43298 0.973548 2.49875 + endloop + endfacet + facet normal 0.118367 -0.318411 0.940534 + outer loop + vertex 1.43189 0.980048 2.50093 + vertex 1.42873 0.980275 2.5014 + vertex 1.42913 0.977568 2.50044 + endloop + endfacet + facet normal 0.107973 -0.310876 0.944298 + outer loop + vertex 1.42531 0.976558 2.50057 + vertex 1.42414 0.979797 2.50177 + vertex 1.42064 0.975742 2.50084 + endloop + endfacet + facet normal 0.0974666 -0.324643 0.940801 + outer loop + vertex 1.42414 0.979797 2.50177 + vertex 1.42861 0.984135 2.5028 + vertex 1.42341 0.983865 2.50325 + endloop + endfacet + facet normal 0.0971194 -0.309547 0.945912 + outer loop + vertex 1.42861 0.984135 2.5028 + vertex 1.42814 0.988836 2.50439 + vertex 1.42341 0.983865 2.50325 + endloop + endfacet + facet normal 0.0905132 -0.310329 0.94631 + outer loop + vertex 1.42861 0.984135 2.5028 + vertex 1.43341 0.988744 2.50386 + vertex 1.42814 0.988836 2.50439 + endloop + endfacet + facet normal 0.117705 -0.325771 0.938093 + outer loop + vertex 1.43894 0.984954 2.50182 + vertex 1.43857 0.988814 2.50321 + vertex 1.4337 0.983964 2.50214 + endloop + endfacet + facet normal 0.124304 -0.194018 0.973091 + outer loop + vertex 1.44386 0.988761 2.50252 + vertex 1.44276 0.993265 2.50356 + vertex 1.43857 0.988814 2.50321 + endloop + endfacet + facet normal 0.0894247 0.131078 0.987331 + outer loop + vertex 1.44276 0.993265 2.50356 + vertex 1.44584 0.997412 2.50273 + vertex 1.44054 0.997041 2.50326 + endloop + endfacet + facet normal 0.161035 -0.246644 0.955633 + outer loop + vertex 1.43341 0.988744 2.50386 + vertex 1.43767 0.993193 2.50429 + vertex 1.43266 0.993725 2.50527 + endloop + endfacet + facet normal 0.181556 0.222978 0.957767 + outer loop + vertex 1.43309 0.997111 2.50559 + vertex 1.43139 0.998095 2.50569 + vertex 1.43087 0.996391 2.50618 + endloop + endfacet + facet normal 0.0929524 -0.258581 0.961507 + outer loop + vertex 1.43341 0.988744 2.50386 + vertex 1.43266 0.993725 2.50527 + vertex 1.42814 0.988836 2.50439 + endloop + endfacet + facet normal 0.0888212 -0.30237 0.949043 + outer loop + vertex 1.42341 0.983865 2.50325 + vertex 1.42814 0.988836 2.50439 + vertex 1.42269 0.988756 2.50488 + endloop + endfacet + facet normal 0.0398778 0.0741972 0.996446 + outer loop + vertex 1.42291 0.992556 2.50554 + vertex 1.42053 0.993516 2.50557 + vertex 1.4199 0.991065 2.50577 + endloop + endfacet + facet normal 0.123381 -0.323282 0.938225 + outer loop + vertex 1.41815 0.983489 2.50366 + vertex 1.42269 0.988756 2.50488 + vertex 1.41738 0.987432 2.50512 + endloop + endfacet + facet normal 0.105302 -0.255046 0.961178 + outer loop + vertex 1.41298 0.987199 2.50554 + vertex 1.41738 0.987432 2.50512 + vertex 1.41574 0.990378 2.50608 + endloop + endfacet + facet normal 0.0588071 0.0692784 0.995863 + outer loop + vertex 1.42053 0.993516 2.50557 + vertex 1.41708 0.993137 2.5058 + vertex 1.4199 0.991065 2.50577 + endloop + endfacet + facet normal 0.120301 -0.267193 0.956104 + outer loop + vertex 1.41224 0.989798 2.50636 + vertex 1.41298 0.987199 2.50554 + vertex 1.41574 0.990378 2.50608 + endloop + endfacet + facet normal 0.103151 -0.337981 0.935483 + outer loop + vertex 1.41298 0.987199 2.50554 + vertex 1.40805 0.983659 2.5048 + vertex 1.41312 0.983326 2.50412 + endloop + endfacet + facet normal 0.0681365 -0.211771 0.974941 + outer loop + vertex 1.40982 0.987683 2.50605 + vertex 1.4087 0.990037 2.50664 + vertex 1.40587 0.986708 2.50611 + endloop + endfacet + facet normal 0.108367 -0.336829 0.935309 + outer loop + vertex 1.40329 0.978587 2.50353 + vertex 1.40805 0.983659 2.5048 + vertex 1.40243 0.982559 2.50506 + endloop + endfacet + facet normal 0.119102 -0.321755 0.939302 + outer loop + vertex 1.39791 0.982099 2.50547 + vertex 1.40243 0.982559 2.50506 + vertex 1.40116 0.985819 2.50634 + endloop + endfacet + facet normal 0.0618594 -0.206662 0.976455 + outer loop + vertex 1.4087 0.990037 2.50664 + vertex 1.40385 0.989473 2.50683 + vertex 1.40587 0.986708 2.50611 + endloop + endfacet + facet normal 0.00144275 0.140444 0.990088 + outer loop + vertex 1.40385 0.989473 2.50683 + vertex 1.40103 0.991986 2.50647 + vertex 1.39832 0.988439 2.50698 + endloop + endfacet + facet normal 0.12226 -0.324222 0.938047 + outer loop + vertex 1.39747 0.984895 2.5065 + vertex 1.39791 0.982099 2.50547 + vertex 1.40116 0.985819 2.50634 + endloop + endfacet + facet normal 0.11566 -0.345562 0.931241 + outer loop + vertex 1.39791 0.982099 2.50547 + vertex 1.39306 0.978451 2.50472 + vertex 1.39813 0.978189 2.504 + endloop + endfacet + facet normal 0.088074 -0.266111 0.95991 + outer loop + vertex 1.39484 0.982479 2.50601 + vertex 1.39413 0.98524 2.50684 + vertex 1.39098 0.981542 2.5061 + endloop + endfacet + facet normal 0.112983 -0.336402 0.934916 + outer loop + vertex 1.3884 0.973539 2.50352 + vertex 1.39306 0.978451 2.50472 + vertex 1.3875 0.977418 2.50502 + endloop + endfacet + facet normal 0.116032 -0.337515 0.934141 + outer loop + vertex 1.38292 0.977001 2.50544 + vertex 1.3875 0.977418 2.50502 + vertex 1.38627 0.980729 2.50637 + endloop + endfacet + facet normal 0.0669811 -0.249419 0.966077 + outer loop + vertex 1.39413 0.98524 2.50684 + vertex 1.38924 0.984717 2.50704 + vertex 1.39098 0.981542 2.5061 + endloop + endfacet + facet normal 0.0991389 -0.224414 0.969438 + outer loop + vertex 1.38627 0.980729 2.50637 + vertex 1.38348 0.98354 2.50731 + vertex 1.38248 0.979795 2.50654 + endloop + endfacet + facet normal -0.0140146 0.0465292 0.998819 + outer loop + vertex 1.38924 0.984717 2.50704 + vertex 1.39242 0.988861 2.5069 + vertex 1.38644 0.98781 2.50686 + endloop + endfacet + facet normal 0.0507588 0.168679 0.984363 + outer loop + vertex 1.37793 0.983587 2.50787 + vertex 1.38092 0.987236 2.50709 + vertex 1.37565 0.987053 2.50739 + endloop + endfacet + facet normal 0.126826 -0.171271 0.977027 + outer loop + vertex 1.37379 0.979094 2.5074 + vertex 1.3727 0.983406 2.5083 + vertex 1.36872 0.97926 2.50809 + endloop + endfacet + facet normal 0.121487 -0.340471 0.932373 + outer loop + vertex 1.37909 0.980019 2.50705 + vertex 1.37379 0.979094 2.5074 + vertex 1.37594 0.976258 2.50608 + endloop + endfacet + facet normal 0.119095 -0.352247 0.928299 + outer loop + vertex 1.37264 0.972414 2.50505 + vertex 1.37798 0.973362 2.50472 + vertex 1.37594 0.976258 2.50608 + endloop + endfacet + facet normal 0.119154 -0.31599 0.94125 + outer loop + vertex 1.37264 0.972414 2.50505 + vertex 1.36764 0.968589 2.5044 + vertex 1.37306 0.968503 2.50368 + endloop + endfacet + facet normal 0.126176 -0.298151 0.946142 + outer loop + vertex 1.36293 0.963571 2.50344 + vertex 1.36764 0.968589 2.5044 + vertex 1.36209 0.967466 2.50478 + endloop + endfacet + facet normal 0.131128 -0.296981 0.945837 + outer loop + vertex 1.36293 0.963571 2.50344 + vertex 1.36209 0.967466 2.50478 + vertex 1.35786 0.963208 2.50403 + endloop + endfacet + facet normal 0.138379 -0.285698 0.948276 + outer loop + vertex 1.35319 0.958726 2.50337 + vertex 1.35786 0.963208 2.50403 + vertex 1.35292 0.963301 2.50478 + endloop + endfacet + facet normal 0.140249 -0.298171 0.944153 + outer loop + vertex 1.3546 0.967223 2.50577 + vertex 1.35093 0.966082 2.50596 + vertex 1.35292 0.963301 2.50478 + endloop + endfacet + facet normal 0.128312 -0.327587 0.936068 + outer loop + vertex 1.35728 0.969745 2.50627 + vertex 1.35765 0.966976 2.50525 + vertex 1.36101 0.970762 2.50611 + endloop + endfacet + facet normal 0.150615 -0.333717 0.930563 + outer loop + vertex 1.3546 0.967223 2.50577 + vertex 1.35408 0.969935 2.50683 + vertex 1.35093 0.966082 2.50596 + endloop + endfacet + facet normal 0.13324 -0.346813 0.928422 + outer loop + vertex 1.36101 0.970762 2.50611 + vertex 1.35902 0.973843 2.50755 + vertex 1.35728 0.969745 2.50627 + endloop + endfacet + facet normal 0.138537 -0.33841 0.930745 + outer loop + vertex 1.35408 0.969935 2.50683 + vertex 1.35373 0.973962 2.50834 + vertex 1.34881 0.968891 2.50723 + endloop + endfacet + facet normal 0.115787 -0.288965 0.950312 + outer loop + vertex 1.36453 0.974968 2.50722 + vertex 1.36369 0.978918 2.50852 + vertex 1.35902 0.973843 2.50755 + endloop + endfacet + facet normal 0.042054 -0.0717608 0.996535 + outer loop + vertex 1.36369 0.978918 2.50852 + vertex 1.36769 0.983255 2.50867 + vertex 1.36266 0.98306 2.50886 + endloop + endfacet + facet normal 0.155758 -0.2873 0.945092 + outer loop + vertex 1.35373 0.973962 2.50834 + vertex 1.35846 0.978704 2.50901 + vertex 1.35306 0.978786 2.50992 + endloop + endfacet + facet normal 0.14543 0.194012 0.97016 + outer loop + vertex 1.35324 0.98253 2.51034 + vertex 1.3506 0.983453 2.51056 + vertex 1.35025 0.981041 2.51109 + endloop + endfacet + facet normal 0.0887279 0.203159 0.975117 + outer loop + vertex 1.3506 0.983453 2.51056 + vertex 1.34663 0.982503 2.51112 + vertex 1.35025 0.981041 2.51109 + endloop + endfacet + facet normal 0.136761 -0.29056 0.947033 + outer loop + vertex 1.35373 0.973962 2.50834 + vertex 1.35306 0.978786 2.50992 + vertex 1.34844 0.973683 2.50902 + endloop + endfacet + facet normal 0.13407 -0.340658 0.930579 + outer loop + vertex 1.34346 0.968953 2.50801 + vertex 1.34844 0.973683 2.50902 + vertex 1.34314 0.973774 2.50982 + endloop + endfacet + facet normal 0.111939 -0.344567 0.932064 + outer loop + vertex 1.34479 0.977759 2.5111 + vertex 1.34096 0.97653 2.5111 + vertex 1.34314 0.973774 2.50982 + endloop + endfacet + facet normal 0.182314 -0.260236 0.948177 + outer loop + vertex 1.34703 0.979997 2.51142 + vertex 1.34804 0.97765 2.51058 + vertex 1.35025 0.981041 2.51109 + endloop + endfacet + facet normal 0.0697167 -0.212841 0.974597 + outer loop + vertex 1.34479 0.977759 2.5111 + vertex 1.34351 0.979852 2.51164 + vertex 1.34096 0.97653 2.5111 + endloop + endfacet + facet normal 0.0598393 0.131385 0.989524 + outer loop + vertex 1.35025 0.981041 2.51109 + vertex 1.34663 0.982503 2.51112 + vertex 1.34703 0.979997 2.51142 + endloop + endfacet + facet normal 0.0623198 -0.20743 0.976263 + outer loop + vertex 1.34351 0.979852 2.51164 + vertex 1.33825 0.978758 2.51175 + vertex 1.34096 0.97653 2.5111 + endloop + endfacet + facet normal 0.132944 -0.329216 0.934849 + outer loop + vertex 1.33784 0.972721 2.5102 + vertex 1.34314 0.973774 2.50982 + vertex 1.34096 0.97653 2.5111 + endloop + endfacet + facet normal 0.154496 -0.335736 0.9292 + outer loop + vertex 1.33784 0.972721 2.5102 + vertex 1.33286 0.968718 2.50958 + vertex 1.33814 0.968652 2.50868 + endloop + endfacet + facet normal 0.161793 -0.33138 0.929522 + outer loop + vertex 1.3274 0.967507 2.5101 + vertex 1.33286 0.968718 2.50958 + vertex 1.33086 0.971782 2.51102 + endloop + endfacet + facet normal 0.106601 -0.28195 0.953488 + outer loop + vertex 1.33727 0.975415 2.51125 + vertex 1.33399 0.975559 2.51166 + vertex 1.33463 0.972902 2.51081 + endloop + endfacet + facet normal 0.0541994 0.0418965 0.997651 + outer loop + vertex 1.33399 0.975559 2.51166 + vertex 1.33234 0.97892 2.51161 + vertex 1.32924 0.974829 2.51195 + endloop + endfacet + facet normal 0.007646 0.0771254 0.996992 + outer loop + vertex 1.32924 0.974829 2.51195 + vertex 1.33234 0.97892 2.51161 + vertex 1.32653 0.97773 2.51175 + endloop + endfacet + facet normal 0.037057 0.104417 0.993843 + outer loop + vertex 1.32924 0.974829 2.51195 + vertex 1.32653 0.97773 2.51175 + vertex 1.32354 0.973369 2.51232 + endloop + endfacet + facet normal 0.0631796 0.0865867 0.994239 + outer loop + vertex 1.32354 0.973369 2.51232 + vertex 1.32653 0.97773 2.51175 + vertex 1.32109 0.977132 2.51214 + endloop + endfacet + facet normal 0.140318 0.136157 0.9807 + outer loop + vertex 1.32354 0.973369 2.51232 + vertex 1.32109 0.977132 2.51214 + vertex 1.31796 0.973341 2.51312 + endloop + endfacet + facet normal 0.140156 -0.209589 0.967693 + outer loop + vertex 1.32354 0.973369 2.51232 + vertex 1.31796 0.973341 2.51312 + vertex 1.31862 0.969105 2.51211 + endloop + endfacet + facet normal 0.17435 -0.203191 0.963491 + outer loop + vertex 1.31862 0.969105 2.51211 + vertex 1.31796 0.973341 2.51312 + vertex 1.31363 0.969054 2.513 + endloop + endfacet + facet normal 0.169663 -0.324963 0.930384 + outer loop + vertex 1.31862 0.969105 2.51211 + vertex 1.31363 0.969054 2.513 + vertex 1.314 0.965346 2.51164 + endloop + endfacet + facet normal 0.179985 -0.208814 0.96125 + outer loop + vertex 1.31363 0.969054 2.513 + vertex 1.31796 0.973341 2.51312 + vertex 1.31272 0.973409 2.51412 + endloop + endfacet + facet normal 0.162495 -0.213037 0.963437 + outer loop + vertex 1.31363 0.969054 2.513 + vertex 1.31272 0.973409 2.51412 + vertex 1.3084 0.968921 2.51385 + endloop + endfacet + facet normal 0.160565 -0.313356 0.935963 + outer loop + vertex 1.3088 0.964047 2.51215 + vertex 1.31363 0.969054 2.513 + vertex 1.3084 0.968921 2.51385 + endloop + endfacet + facet normal 0.186334 0.159591 0.969438 + outer loop + vertex 1.31796 0.973341 2.51312 + vertex 1.31573 0.976982 2.51295 + vertex 1.31272 0.973409 2.51412 + endloop + endfacet + facet normal 0.277932 0.078428 0.957394 + outer loop + vertex 1.31272 0.973409 2.51412 + vertex 1.31573 0.976982 2.51295 + vertex 1.31107 0.977041 2.5143 + endloop + endfacet + facet normal 0.180114 0.0326862 0.983103 + outer loop + vertex 1.31107 0.977041 2.5143 + vertex 1.30724 0.974339 2.51509 + vertex 1.31272 0.973409 2.51412 + endloop + endfacet + facet normal 0.38822 -0.294193 0.873347 + outer loop + vertex 1.30862 0.977446 2.51552 + vertex 1.30724 0.974339 2.51509 + vertex 1.31107 0.977041 2.5143 + endloop + endfacet + facet normal 0.079186 -0.171958 0.981917 + outer loop + vertex 1.30862 0.977446 2.51552 + vertex 1.30695 0.977398 2.51565 + vertex 1.30724 0.974339 2.51509 + endloop + endfacet + facet normal 0.0764133 -0.0370367 0.996388 + outer loop + vertex 1.30862 0.977446 2.51552 + vertex 1.30781 0.978353 2.51562 + vertex 1.30695 0.977398 2.51565 + endloop + endfacet + facet normal 0.143195 0.133753 0.980615 + outer loop + vertex 1.31796 0.973341 2.51312 + vertex 1.32109 0.977132 2.51214 + vertex 1.31573 0.976982 2.51295 + endloop + endfacet + facet normal 0.153155 -0.326797 0.932602 + outer loop + vertex 1.32305 0.966938 2.51063 + vertex 1.32253 0.969535 2.51162 + vertex 1.32007 0.966963 2.51112 + endloop + endfacet + facet normal 0.151182 -0.323755 0.933984 + outer loop + vertex 1.3263 0.97076 2.51141 + vertex 1.3274 0.967507 2.5101 + vertex 1.33086 0.971782 2.51102 + endloop + endfacet + facet normal 0.153255 -0.325258 0.933124 + outer loop + vertex 1.32007 0.966963 2.51112 + vertex 1.31846 0.963303 2.51011 + vertex 1.32305 0.966938 2.51063 + endloop + endfacet + facet normal 0.150243 -0.289445 0.94533 + outer loop + vertex 1.32345 0.958819 2.50794 + vertex 1.32309 0.963129 2.50932 + vertex 1.31832 0.958629 2.5087 + endloop + endfacet + facet normal 0.15226 -0.273738 0.949676 + outer loop + vertex 1.31348 0.953899 2.50811 + vertex 1.31832 0.958629 2.5087 + vertex 1.313 0.958732 2.50958 + endloop + endfacet + facet normal 0.150767 -0.324364 0.93384 + outer loop + vertex 1.32007 0.966963 2.51112 + vertex 1.31721 0.965566 2.5111 + vertex 1.31846 0.963303 2.51011 + endloop + endfacet + facet normal 0.177057 -0.333503 0.925973 + outer loop + vertex 1.31721 0.965566 2.5111 + vertex 1.31862 0.969105 2.51211 + vertex 1.314 0.965346 2.51164 + endloop + endfacet + facet normal 0.173133 -0.324446 0.929924 + outer loop + vertex 1.314 0.965346 2.51164 + vertex 1.31363 0.969054 2.513 + vertex 1.3088 0.964047 2.51215 + endloop + endfacet + facet normal 0.164161 -0.29945 0.939883 + outer loop + vertex 1.30764 0.957426 2.51009 + vertex 1.30705 0.960028 2.51102 + vertex 1.30441 0.957405 2.51064 + endloop + endfacet + facet normal 0.164056 -0.296844 0.940728 + outer loop + vertex 1.31465 0.962885 2.5106 + vertex 1.3108 0.961398 2.51081 + vertex 1.313 0.958732 2.50958 + endloop + endfacet + facet normal 0.155061 -0.273357 0.949332 + outer loop + vertex 1.31348 0.953899 2.50811 + vertex 1.313 0.958732 2.50958 + vertex 1.30812 0.953505 2.50887 + endloop + endfacet + facet normal 0.168375 -0.27954 0.945255 + outer loop + vertex 1.29786 0.9523 2.51031 + vertex 1.30288 0.953448 2.50975 + vertex 1.30085 0.956143 2.51091 + endloop + endfacet + facet normal 0.171896 -0.297737 0.939044 + outer loop + vertex 1.30085 0.956143 2.51091 + vertex 1.29884 0.958861 2.51214 + vertex 1.29728 0.954894 2.51117 + endloop + endfacet + facet normal 0.164092 -0.324301 0.931613 + outer loop + vertex 1.3088 0.964047 2.51215 + vertex 1.30365 0.963977 2.51303 + vertex 1.3039 0.960013 2.51161 + endloop + endfacet + facet normal 0.164592 -0.312838 0.935437 + outer loop + vertex 1.3088 0.964047 2.51215 + vertex 1.3084 0.968921 2.51385 + vertex 1.30365 0.963977 2.51303 + endloop + endfacet + facet normal 0.139929 -0.19179 0.97141 + outer loop + vertex 1.3084 0.968921 2.51385 + vertex 1.31272 0.973409 2.51412 + vertex 1.30724 0.974339 2.51509 + endloop + endfacet + facet normal 0.150926 -0.270783 0.950735 + outer loop + vertex 1.29857 0.963772 2.51379 + vertex 1.30311 0.968832 2.51451 + vertex 1.29831 0.968709 2.51524 + endloop + endfacet + facet normal 0.162642 -0.26969 0.949113 + outer loop + vertex 1.29831 0.968709 2.51524 + vertex 1.29339 0.96388 2.51471 + vertex 1.29857 0.963772 2.51379 + endloop + endfacet + facet normal 0.113906 -0.200459 0.973058 + outer loop + vertex 1.29496 0.96805 2.51583 + vertex 1.2935 0.97013 2.51643 + vertex 1.29123 0.966623 2.51598 + endloop + endfacet + facet normal 0.154941 -0.3075 0.938849 + outer loop + vertex 1.29362 0.958861 2.51303 + vertex 1.29339 0.96388 2.51471 + vertex 1.28827 0.958532 2.51381 + endloop + endfacet + facet normal 0.159293 -0.283685 0.945594 + outer loop + vertex 1.28322 0.953695 2.51321 + vertex 1.28827 0.958532 2.51381 + vertex 1.28296 0.958589 2.51472 + endloop + endfacet + facet normal 0.173141 -0.311075 0.934481 + outer loop + vertex 1.28475 0.962779 2.51578 + vertex 1.28098 0.96139 2.51602 + vertex 1.28296 0.958589 2.51472 + endloop + endfacet + facet normal 0.17215 -0.311754 0.934438 + outer loop + vertex 1.27782 0.957348 2.51525 + vertex 1.28296 0.958589 2.51472 + vertex 1.28098 0.96139 2.51602 + endloop + endfacet + facet normal 0.154108 -0.312485 0.937339 + outer loop + vertex 1.28748 0.965407 2.51619 + vertex 1.28804 0.962687 2.51519 + vertex 1.29123 0.966623 2.51598 + endloop + endfacet + facet normal 0.171745 -0.307016 0.93608 + outer loop + vertex 1.28475 0.962779 2.51578 + vertex 1.28413 0.96534 2.51673 + vertex 1.28098 0.96139 2.51602 + endloop + endfacet + facet normal 0.175993 -0.310081 0.934278 + outer loop + vertex 1.28413 0.96534 2.51673 + vertex 1.27879 0.963918 2.51727 + vertex 1.28098 0.96139 2.51602 + endloop + endfacet + facet normal 0.122179 -0.208469 0.970367 + outer loop + vertex 1.29123 0.966623 2.51598 + vertex 1.28852 0.96896 2.51682 + vertex 1.28748 0.965407 2.51619 + endloop + endfacet + facet normal 0.0775198 0.0894845 0.992967 + outer loop + vertex 1.28852 0.96896 2.51682 + vertex 1.29125 0.972706 2.51627 + vertex 1.28624 0.972361 2.51669 + endloop + endfacet + facet normal 0.145352 -0.180404 0.972793 + outer loop + vertex 1.28413 0.96534 2.51673 + vertex 1.28314 0.968716 2.51751 + vertex 1.27879 0.963918 2.51727 + endloop + endfacet + facet normal 0.177276 -0.309022 0.934387 + outer loop + vertex 1.28098 0.96139 2.51602 + vertex 1.27879 0.963918 2.51727 + vertex 1.27718 0.959855 2.51623 + endloop + endfacet + facet normal 0.180565 -0.317663 0.930853 + outer loop + vertex 1.27718 0.959855 2.51623 + vertex 1.27782 0.957348 2.51525 + vertex 1.28098 0.96139 2.51602 + endloop + endfacet + facet normal 0.17095 -0.285423 0.943032 + outer loop + vertex 1.27782 0.957348 2.51525 + vertex 1.27325 0.953438 2.51489 + vertex 1.27807 0.953473 2.51403 + endloop + endfacet + facet normal 0.192992 -0.325834 0.925519 + outer loop + vertex 1.27469 0.957118 2.51578 + vertex 1.2734 0.95926 2.5168 + vertex 1.27188 0.955603 2.51583 + endloop + endfacet + facet normal 0.170576 -0.273043 0.946758 + outer loop + vertex 1.27325 0.953438 2.51489 + vertex 1.26798 0.948812 2.51451 + vertex 1.27326 0.948778 2.51355 + endloop + endfacet + facet normal 0.171004 -0.27235 0.946881 + outer loop + vertex 1.26848 0.943996 2.51303 + vertex 1.26798 0.948812 2.51451 + vertex 1.26322 0.943587 2.51387 + endloop + endfacet + facet normal 0.171242 -0.274937 0.94609 + outer loop + vertex 1.25842 0.93878 2.51334 + vertex 1.26322 0.943587 2.51387 + vertex 1.25803 0.943542 2.51479 + endloop + endfacet + facet normal 0.170367 -0.267255 0.948446 + outer loop + vertex 1.2595 0.947539 2.51566 + vertex 1.25586 0.946211 2.51594 + vertex 1.25803 0.943542 2.51479 + endloop + endfacet + facet normal 0.165275 -0.27294 0.947728 + outer loop + vertex 1.26207 0.950133 2.51595 + vertex 1.26273 0.947535 2.51508 + vertex 1.26573 0.951449 2.51569 + endloop + endfacet + facet normal 0.172348 -0.273109 0.946418 + outer loop + vertex 1.2595 0.947539 2.51566 + vertex 1.25884 0.950093 2.51651 + vertex 1.25586 0.946211 2.51594 + endloop + endfacet + facet normal 0.17298 -0.29607 0.939372 + outer loop + vertex 1.26573 0.951449 2.51569 + vertex 1.26369 0.954067 2.51689 + vertex 1.26207 0.950133 2.51595 + endloop + endfacet + facet normal 0.174477 -0.292054 0.940352 + outer loop + vertex 1.25884 0.950093 2.51651 + vertex 1.25855 0.953921 2.51776 + vertex 1.25359 0.948786 2.51708 + endloop + endfacet + facet normal 0.167175 -0.311874 0.9353 + outer loop + vertex 1.26369 0.954067 2.51689 + vertex 1.26859 0.95916 2.51771 + vertex 1.26352 0.95885 2.51852 + endloop + endfacet + facet normal 0.165314 -0.288361 0.943143 + outer loop + vertex 1.26352 0.95885 2.51852 + vertex 1.26832 0.963994 2.51925 + vertex 1.26307 0.963922 2.52015 + endloop + endfacet + facet normal 0.152274 -0.285516 0.9462 + outer loop + vertex 1.25517 0.962219 2.521 + vertex 1.25376 0.958513 2.52011 + vertex 1.25826 0.962374 2.52055 + endloop + endfacet + facet normal 0.168011 -0.307634 0.936554 + outer loop + vertex 1.25855 0.953921 2.51776 + vertex 1.2585 0.958503 2.51927 + vertex 1.25343 0.953668 2.51859 + endloop + endfacet + facet normal 0.174445 -0.287676 0.941707 + outer loop + vertex 1.24826 0.948795 2.51806 + vertex 1.25343 0.953668 2.51859 + vertex 1.24815 0.953781 2.5196 + endloop + endfacet + facet normal 0.173502 -0.302328 0.93728 + outer loop + vertex 1.2499 0.958081 2.52067 + vertex 1.24601 0.956575 2.5209 + vertex 1.24815 0.953781 2.5196 + endloop + endfacet + facet normal 0.163103 -0.288953 0.943347 + outer loop + vertex 1.25517 0.962219 2.521 + vertex 1.25234 0.960798 2.52106 + vertex 1.25376 0.958513 2.52011 + endloop + endfacet + facet normal 0.162364 -0.271823 0.948552 + outer loop + vertex 1.2499 0.958081 2.52067 + vertex 1.24898 0.960578 2.52154 + vertex 1.24601 0.956575 2.5209 + endloop + endfacet + facet normal 0.167057 -0.275021 0.946813 + outer loop + vertex 1.24898 0.960578 2.52154 + vertex 1.24376 0.959252 2.52208 + vertex 1.24601 0.956575 2.5209 + endloop + endfacet + facet normal 0.104884 -0.171418 0.979599 + outer loop + vertex 1.25517 0.962219 2.521 + vertex 1.25309 0.96416 2.52156 + vertex 1.25234 0.960798 2.52106 + endloop + endfacet + facet normal 0.138393 -0.149192 0.979076 + outer loop + vertex 1.24898 0.960578 2.52154 + vertex 1.24789 0.964042 2.52222 + vertex 1.24376 0.959252 2.52208 + endloop + endfacet + facet normal 0.0620584 0.0810155 0.994779 + outer loop + vertex 1.25675 0.967758 2.52104 + vertex 1.25117 0.967753 2.52139 + vertex 1.25309 0.96416 2.52156 + endloop + endfacet + facet normal 0.162527 -0.169827 0.971979 + outer loop + vertex 1.24376 0.959252 2.52208 + vertex 1.24789 0.964042 2.52222 + vertex 1.24282 0.963665 2.523 + endloop + endfacet + facet normal 0.169722 -0.272844 0.946969 + outer loop + vertex 1.24601 0.956575 2.5209 + vertex 1.24376 0.959252 2.52208 + vertex 1.2423 0.955189 2.52117 + endloop + endfacet + facet normal 0.179702 -0.301627 0.936338 + outer loop + vertex 1.2423 0.955189 2.52117 + vertex 1.24286 0.952474 2.52018 + vertex 1.24601 0.956575 2.5209 + endloop + endfacet + facet normal 0.178664 -0.285525 0.94157 + outer loop + vertex 1.24286 0.952474 2.52018 + vertex 1.23806 0.948384 2.51986 + vertex 1.24311 0.948497 2.51893 + endloop + endfacet + facet normal 0.184494 -0.301071 0.935585 + outer loop + vertex 1.23969 0.952462 2.52079 + vertex 1.23908 0.955153 2.52178 + vertex 1.23606 0.951097 2.52107 + endloop + endfacet + facet normal 0.179189 -0.29751 0.937752 + outer loop + vertex 1.23908 0.955153 2.52178 + vertex 1.23383 0.953789 2.52235 + vertex 1.23606 0.951097 2.52107 + endloop + endfacet + facet normal 0.179276 -0.270191 0.945969 + outer loop + vertex 1.23827 0.943643 2.51846 + vertex 1.23806 0.948384 2.51986 + vertex 1.23331 0.943328 2.51931 + endloop + endfacet + facet normal 0.181039 -0.26338 0.947553 + outer loop + vertex 1.23338 0.938793 2.51804 + vertex 1.23331 0.943328 2.51931 + vertex 1.2284 0.938639 2.51895 + endloop + endfacet + facet normal 0.181773 -0.262628 0.947621 + outer loop + vertex 1.2234 0.933705 2.51854 + vertex 1.2284 0.938639 2.51895 + vertex 1.22333 0.938619 2.51991 + endloop + endfacet + facet normal 0.181426 -0.261502 0.947999 + outer loop + vertex 1.22496 0.942778 2.52075 + vertex 1.22117 0.94121 2.52104 + vertex 1.22333 0.938619 2.51991 + endloop + endfacet + facet normal 0.182558 -0.267048 0.946234 + outer loop + vertex 1.22732 0.945466 2.52105 + vertex 1.22409 0.945192 2.5216 + vertex 1.22496 0.942778 2.52075 + endloop + endfacet + facet normal 0.183062 -0.281522 0.941931 + outer loop + vertex 1.22732 0.945466 2.52105 + vertex 1.22856 0.949081 2.52189 + vertex 1.22409 0.945192 2.5216 + endloop + endfacet + facet normal 0.181235 -0.295875 0.937876 + outer loop + vertex 1.23606 0.951097 2.52107 + vertex 1.23383 0.953789 2.52235 + vertex 1.23237 0.949611 2.52131 + endloop + endfacet + facet normal 0.17748 -0.288726 0.940818 + outer loop + vertex 1.22856 0.949081 2.52189 + vertex 1.22852 0.953785 2.52334 + vertex 1.2236 0.948944 2.52278 + endloop + endfacet + facet normal 0.17251 -0.267573 0.947969 + outer loop + vertex 1.23908 0.955153 2.52178 + vertex 1.23857 0.95907 2.52298 + vertex 1.23383 0.953789 2.52235 + endloop + endfacet + facet normal 0.181462 -0.279964 0.942704 + outer loop + vertex 1.22852 0.953785 2.52334 + vertex 1.23352 0.958798 2.52387 + vertex 1.22831 0.95883 2.52488 + endloop + endfacet + facet normal 0.144396 -0.189943 0.971119 + outer loop + vertex 1.22974 0.963114 2.52583 + vertex 1.22827 0.965347 2.52648 + vertex 1.22598 0.961443 2.52606 + endloop + endfacet + facet normal 0.16781 -0.281189 0.944866 + outer loop + vertex 1.22852 0.953785 2.52334 + vertex 1.22831 0.95883 2.52488 + vertex 1.22339 0.953475 2.52416 + endloop + endfacet + facet normal 0.163473 -0.267741 0.949522 + outer loop + vertex 1.21843 0.948637 2.52365 + vertex 1.22339 0.953475 2.52416 + vertex 1.21853 0.953424 2.52498 + endloop + endfacet + facet normal 0.155636 -0.273383 0.949231 + outer loop + vertex 1.22226 0.959861 2.52622 + vertex 1.22312 0.957386 2.52536 + vertex 1.22598 0.961443 2.52606 + endloop + endfacet + facet normal 0.157004 -0.234415 0.959374 + outer loop + vertex 1.22226 0.959861 2.52622 + vertex 1.22324 0.963755 2.52701 + vertex 1.21844 0.959288 2.5267 + endloop + endfacet + facet normal 0.161891 -0.271155 0.948824 + outer loop + vertex 1.21995 0.957159 2.52581 + vertex 1.21713 0.95566 2.52586 + vertex 1.21853 0.953424 2.52498 + endloop + endfacet + facet normal 0.179024 -0.267335 0.946827 + outer loop + vertex 1.21853 0.953424 2.52498 + vertex 1.21315 0.948681 2.52466 + vertex 1.21843 0.948637 2.52365 + endloop + endfacet + facet normal 0.188206 -0.273082 0.9434 + outer loop + vertex 1.21472 0.952909 2.52553 + vertex 1.21393 0.955382 2.5264 + vertex 1.21093 0.95132 2.52582 + endloop + endfacet + facet normal 0.183712 -0.270004 0.945171 + outer loop + vertex 1.21393 0.955382 2.5264 + vertex 1.2087 0.953884 2.52699 + vertex 1.21093 0.95132 2.52582 + endloop + endfacet + facet normal 0.185993 -0.260263 0.947455 + outer loop + vertex 1.20828 0.943446 2.52418 + vertex 1.21315 0.948681 2.52466 + vertex 1.20799 0.947295 2.52529 + endloop + endfacet + facet normal 0.182392 -0.254981 0.949588 + outer loop + vertex 1.20486 0.947056 2.52584 + vertex 1.20337 0.949169 2.52669 + vertex 1.20214 0.945588 2.52597 + endloop + endfacet + facet normal 0.187715 -0.266608 0.945348 + outer loop + vertex 1.21093 0.95132 2.52582 + vertex 1.2087 0.953884 2.52699 + vertex 1.20716 0.949742 2.52612 + endloop + endfacet + facet normal 0.178772 -0.259959 0.948927 + outer loop + vertex 1.20337 0.949169 2.52669 + vertex 1.20344 0.953766 2.52794 + vertex 1.1985 0.94901 2.52757 + endloop + endfacet + facet normal 0.17889 -0.252282 0.950974 + outer loop + vertex 1.20337 0.949169 2.52669 + vertex 1.1985 0.94901 2.52757 + vertex 1.19897 0.945309 2.5265 + endloop + endfacet + facet normal 0.183684 -0.251475 0.950274 + outer loop + vertex 1.19897 0.945309 2.5265 + vertex 1.1985 0.94901 2.52757 + vertex 1.19375 0.94382 2.52711 + endloop + endfacet + facet normal 0.182665 -0.250582 0.950706 + outer loop + vertex 1.19375 0.94382 2.52711 + vertex 1.1985 0.94901 2.52757 + vertex 1.19341 0.948658 2.52845 + endloop + endfacet + facet normal 0.18278 -0.255794 0.949295 + outer loop + vertex 1.1985 0.94901 2.52757 + vertex 1.1984 0.953596 2.52882 + vertex 1.19341 0.948658 2.52845 + endloop + endfacet + facet normal 0.175135 -0.256308 0.950597 + outer loop + vertex 1.1985 0.94901 2.52757 + vertex 1.20344 0.953766 2.52794 + vertex 1.1984 0.953596 2.52882 + endloop + endfacet + facet normal 0.17491 -0.271766 0.946335 + outer loop + vertex 1.20344 0.953766 2.52794 + vertex 1.20348 0.958446 2.52928 + vertex 1.1984 0.953596 2.52882 + endloop + endfacet + facet normal 0.173099 -0.271839 0.946647 + outer loop + vertex 1.20344 0.953766 2.52794 + vertex 1.20856 0.958817 2.52846 + vertex 1.20348 0.958446 2.52928 + endloop + endfacet + facet normal 0.173432 -0.285318 0.942611 + outer loop + vertex 1.20856 0.958817 2.52846 + vertex 1.20846 0.96388 2.53001 + vertex 1.20348 0.958446 2.52928 + endloop + endfacet + facet normal 0.186005 -0.27926 0.942027 + outer loop + vertex 1.21393 0.955382 2.5264 + vertex 1.21362 0.959164 2.52758 + vertex 1.2087 0.953884 2.52699 + endloop + endfacet + facet normal 0.180076 -0.25467 0.950114 + outer loop + vertex 1.21844 0.959288 2.5267 + vertex 1.21823 0.963649 2.52791 + vertex 1.21362 0.959164 2.52758 + endloop + endfacet + facet normal 0.198973 -0.172425 0.964717 + outer loop + vertex 1.21823 0.963649 2.52791 + vertex 1.22174 0.967243 2.52783 + vertex 1.21778 0.967931 2.52877 + endloop + endfacet + facet normal 0.198151 -0.283511 0.938274 + outer loop + vertex 1.20856 0.958817 2.52846 + vertex 1.21348 0.963774 2.52891 + vertex 1.20846 0.96388 2.53001 + endloop + endfacet + facet normal 0.121836 -0.16983 0.977913 + outer loop + vertex 1.20979 0.968113 2.53102 + vertex 1.20824 0.970194 2.53157 + vertex 1.20613 0.966487 2.53119 + endloop + endfacet + facet normal 0.166982 -0.263805 0.950013 + outer loop + vertex 1.1984 0.953596 2.52882 + vertex 1.20348 0.958446 2.52928 + vertex 1.19871 0.958348 2.53009 + endloop + endfacet + facet normal 0.1561 -0.27248 0.949414 + outer loop + vertex 1.20243 0.964869 2.53134 + vertex 1.20334 0.962386 2.53047 + vertex 1.20613 0.966487 2.53119 + endloop + endfacet + facet normal 0.151128 -0.191168 0.969853 + outer loop + vertex 1.20243 0.964869 2.53134 + vertex 1.20321 0.968843 2.532 + vertex 1.19849 0.96424 2.53183 + endloop + endfacet + facet normal 0.16503 -0.273831 0.947513 + outer loop + vertex 1.20016 0.962099 2.53092 + vertex 1.19733 0.960563 2.53097 + vertex 1.19871 0.958348 2.53009 + endloop + endfacet + facet normal 0.179445 -0.263998 0.947684 + outer loop + vertex 1.19871 0.958348 2.53009 + vertex 1.19329 0.953603 2.52979 + vertex 1.1984 0.953596 2.52882 + endloop + endfacet + facet normal 0.190902 -0.276583 0.941838 + outer loop + vertex 1.19494 0.957812 2.53063 + vertex 1.19411 0.960295 2.53152 + vertex 1.19115 0.95624 2.53093 + endloop + endfacet + facet normal 0.185273 -0.272803 0.944062 + outer loop + vertex 1.19411 0.960295 2.53152 + vertex 1.18883 0.958799 2.53213 + vertex 1.19115 0.95624 2.53093 + endloop + endfacet + facet normal 0.180004 -0.25308 0.950552 + outer loop + vertex 1.19341 0.948658 2.52845 + vertex 1.1984 0.953596 2.52882 + vertex 1.19329 0.953603 2.52979 + endloop + endfacet + facet normal 0.188805 -0.249865 0.949695 + outer loop + vertex 1.19375 0.94382 2.52711 + vertex 1.19341 0.948658 2.52845 + vertex 1.18844 0.943691 2.52814 + endloop + endfacet + facet normal 0.1888 -0.250066 0.949643 + outer loop + vertex 1.19375 0.94382 2.52711 + vertex 1.18844 0.943691 2.52814 + vertex 1.1884 0.938947 2.52689 + endloop + endfacet + facet normal 0.184428 -0.25447 0.949332 + outer loop + vertex 1.19897 0.945309 2.5265 + vertex 1.19375 0.94382 2.52711 + vertex 1.19613 0.941348 2.52599 + endloop + endfacet + facet normal 0.190282 -0.25183 0.948881 + outer loop + vertex 1.19326 0.937317 2.52548 + vertex 1.1924 0.939742 2.52629 + vertex 1.1901 0.936971 2.52602 + endloop + endfacet + facet normal 0.183787 -0.256103 0.949017 + outer loop + vertex 1.19985 0.942912 2.52569 + vertex 1.19613 0.941348 2.52599 + vertex 1.19831 0.93873 2.52486 + endloop + endfacet + facet normal 0.191143 -0.257504 0.947183 + outer loop + vertex 1.19842 0.93375 2.52348 + vertex 1.19831 0.93873 2.52486 + vertex 1.19345 0.933422 2.5244 + endloop + endfacet + facet normal 0.190175 -0.250113 0.949356 + outer loop + vertex 1.1901 0.936971 2.52602 + vertex 1.1888 0.93326 2.5253 + vertex 1.19326 0.937317 2.52548 + endloop + endfacet + facet normal 0.195716 -0.25511 0.946897 + outer loop + vertex 1.19342 0.928724 2.52314 + vertex 1.19345 0.933422 2.5244 + vertex 1.18849 0.928587 2.52412 + endloop + endfacet + facet normal 0.198872 -0.253766 0.946601 + outer loop + vertex 1.18837 0.923868 2.52288 + vertex 1.18849 0.928587 2.52412 + vertex 1.18343 0.923725 2.52388 + endloop + endfacet + facet normal 0.199281 -0.251633 0.947084 + outer loop + vertex 1.17984 0.927583 2.52567 + vertex 1.17854 0.923735 2.52492 + vertex 1.18372 0.928535 2.52511 + endloop + endfacet + facet normal 0.200808 -0.254035 0.94612 + outer loop + vertex 1.18349 0.919082 2.52262 + vertex 1.18343 0.923725 2.52388 + vertex 1.17843 0.918776 2.52361 + endloop + endfacet + facet normal 0.202687 -0.256387 0.945084 + outer loop + vertex 1.17346 0.913758 2.52332 + vertex 1.17843 0.918776 2.52361 + vertex 1.17323 0.918799 2.52473 + endloop + endfacet + facet normal 0.200073 -0.251855 0.946858 + outer loop + vertex 1.17984 0.927583 2.52567 + vertex 1.17694 0.925824 2.52581 + vertex 1.17854 0.923735 2.52492 + endloop + endfacet + facet normal 0.201038 -0.25034 0.947055 + outer loop + vertex 1.17694 0.925824 2.52581 + vertex 1.17817 0.929461 2.52651 + vertex 1.17376 0.925423 2.52638 + endloop + endfacet + facet normal 0.200889 -0.247317 0.947881 + outer loop + vertex 1.17376 0.925423 2.52638 + vertex 1.17336 0.929115 2.52743 + vertex 1.16866 0.923851 2.52705 + endloop + endfacet + facet normal 0.199203 -0.245862 0.948615 + outer loop + vertex 1.16866 0.923851 2.52705 + vertex 1.17336 0.929115 2.52743 + vertex 1.16843 0.928668 2.52835 + endloop + endfacet + facet normal 0.204321 -0.254148 0.945337 + outer loop + vertex 1.16822 0.917355 2.52543 + vertex 1.16733 0.91976 2.52627 + vertex 1.16511 0.916998 2.52601 + endloop + endfacet + facet normal 0.204428 -0.253366 0.945524 + outer loop + vertex 1.17465 0.923032 2.52556 + vertex 1.17098 0.921394 2.52592 + vertex 1.17323 0.918799 2.52473 + endloop + endfacet + facet normal 0.203275 -0.256328 0.944974 + outer loop + vertex 1.17346 0.913758 2.52332 + vertex 1.17323 0.918799 2.52473 + vertex 1.16848 0.913488 2.52431 + endloop + endfacet + facet normal 0.204746 -0.261052 0.943361 + outer loop + vertex 1.16511 0.916998 2.52601 + vertex 1.16387 0.913322 2.52526 + vertex 1.16822 0.917355 2.52543 + endloop + endfacet + facet normal 0.204537 -0.257937 0.944263 + outer loop + vertex 1.16847 0.90884 2.52305 + vertex 1.16848 0.913488 2.52431 + vertex 1.16357 0.908699 2.52407 + endloop + endfacet + facet normal 0.204785 -0.248283 0.946794 + outer loop + vertex 1.16335 0.903972 2.52288 + vertex 1.16847 0.90884 2.52305 + vertex 1.16357 0.908699 2.52407 + endloop + endfacet + facet normal 0.19691 -0.250781 0.947806 + outer loop + vertex 1.16012 0.912411 2.5258 + vertex 1.15884 0.90863 2.52506 + vertex 1.16387 0.913322 2.52526 + endloop + endfacet + facet normal 0.219568 -0.24815 0.94351 + outer loop + vertex 1.16335 0.903972 2.52288 + vertex 1.16357 0.908699 2.52407 + vertex 1.15848 0.903847 2.52398 + endloop + endfacet + facet normal 0.226622 -0.187466 0.955771 + outer loop + vertex 1.15356 0.898947 2.52419 + vertex 1.15848 0.903847 2.52398 + vertex 1.15386 0.903821 2.52507 + endloop + endfacet + facet normal 0.239843 -0.212438 0.947283 + outer loop + vertex 1.15492 0.907584 2.52565 + vertex 1.15196 0.905544 2.52594 + vertex 1.15386 0.903821 2.52507 + endloop + endfacet + facet normal 0.198918 -0.25135 0.947235 + outer loop + vertex 1.16012 0.912411 2.5258 + vertex 1.15706 0.910448 2.52592 + vertex 1.15884 0.90863 2.52506 + endloop + endfacet + facet normal 0.267263 -0.25482 0.929321 + outer loop + vertex 1.15492 0.907584 2.52565 + vertex 1.15308 0.90929 2.52664 + vertex 1.15196 0.905544 2.52594 + endloop + endfacet + facet normal 0.206214 -0.263026 0.942493 + outer loop + vertex 1.16012 0.912411 2.5258 + vertex 1.15823 0.914174 2.5267 + vertex 1.15706 0.910448 2.52592 + endloop + endfacet + facet normal 0.217673 -0.210581 0.953034 + outer loop + vertex 1.14855 0.914015 2.52904 + vertex 1.15348 0.918767 2.52896 + vertex 1.14883 0.918757 2.53002 + endloop + endfacet + facet normal 0.216267 -0.239123 0.946599 + outer loop + vertex 1.15381 0.923548 2.53009 + vertex 1.14883 0.918757 2.53002 + vertex 1.15348 0.918767 2.52896 + endloop + endfacet + facet normal 0.203052 -0.225494 0.952849 + outer loop + vertex 1.14988 0.922462 2.53067 + vertex 1.14883 0.918757 2.53002 + vertex 1.15381 0.923548 2.53009 + endloop + endfacet + facet normal 0.207325 -0.243883 0.947384 + outer loop + vertex 1.15381 0.923548 2.53009 + vertex 1.15201 0.925345 2.53095 + vertex 1.14988 0.922462 2.53067 + endloop + endfacet + facet normal 0.234175 -0.262643 0.936045 + outer loop + vertex 1.15201 0.925345 2.53095 + vertex 1.14804 0.924213 2.53163 + vertex 1.14988 0.922462 2.53067 + endloop + endfacet + facet normal 0.244006 -0.252457 0.936337 + outer loop + vertex 1.14988 0.922462 2.53067 + vertex 1.14804 0.924213 2.53163 + vertex 1.14692 0.92046 2.53091 + endloop + endfacet + facet normal 0.305343 -0.26641 0.914216 + outer loop + vertex 1.14692 0.92046 2.53091 + vertex 1.14804 0.924213 2.53163 + vertex 1.14313 0.919244 2.53182 + endloop + endfacet + facet normal 0.302585 -0.254592 0.918491 + outer loop + vertex 1.14692 0.92046 2.53091 + vertex 1.14313 0.919244 2.53182 + vertex 1.1451 0.917654 2.53073 + endloop + endfacet + facet normal 0.243432 -0.217803 0.945147 + outer loop + vertex 1.14883 0.918757 2.53002 + vertex 1.14692 0.92046 2.53091 + vertex 1.1451 0.917654 2.53073 + endloop + endfacet + facet normal 0.236888 -0.190847 0.952608 + outer loop + vertex 1.1451 0.917654 2.53073 + vertex 1.14474 0.914423 2.53017 + vertex 1.14883 0.918757 2.53002 + endloop + endfacet + facet normal 0.30195 -0.194624 0.933246 + outer loop + vertex 1.1451 0.917654 2.53073 + vertex 1.14234 0.915339 2.53114 + vertex 1.14474 0.914423 2.53017 + endloop + endfacet + facet normal 0.325751 -0.225652 0.918133 + outer loop + vertex 1.1451 0.917654 2.53073 + vertex 1.14313 0.919244 2.53182 + vertex 1.14234 0.915339 2.53114 + endloop + endfacet + facet normal 0.262489 -0.223122 0.938785 + outer loop + vertex 1.14804 0.924213 2.53163 + vertex 1.14321 0.924124 2.53296 + vertex 1.14313 0.919244 2.53182 + endloop + endfacet + facet normal 0.261835 -0.237413 0.935456 + outer loop + vertex 1.14804 0.924213 2.53163 + vertex 1.14821 0.928953 2.53278 + vertex 1.14321 0.924124 2.53296 + endloop + endfacet + facet normal 0.233269 -0.207279 0.950064 + outer loop + vertex 1.14321 0.924124 2.53296 + vertex 1.14821 0.928953 2.53278 + vertex 1.14348 0.929045 2.53396 + endloop + endfacet + facet normal 0.231802 -0.227584 0.945766 + outer loop + vertex 1.14821 0.928953 2.53278 + vertex 1.1484 0.933778 2.53389 + vertex 1.14348 0.929045 2.53396 + endloop + endfacet + facet normal 0.211458 -0.206305 0.955366 + outer loop + vertex 1.14348 0.929045 2.53396 + vertex 1.1484 0.933778 2.53389 + vertex 1.14371 0.933818 2.53494 + endloop + endfacet + facet normal 0.210086 -0.230472 0.95013 + outer loop + vertex 1.14869 0.938622 2.53501 + vertex 1.14371 0.933818 2.53494 + vertex 1.1484 0.933778 2.53389 + endloop + endfacet + facet normal 0.195621 -0.23034 0.953245 + outer loop + vertex 1.1484 0.933778 2.53389 + vertex 1.15353 0.938666 2.53402 + vertex 1.14869 0.938622 2.53501 + endloop + endfacet + facet normal 0.195236 -0.240133 0.950904 + outer loop + vertex 1.1539 0.943536 2.53518 + vertex 1.14869 0.938622 2.53501 + vertex 1.15353 0.938666 2.53402 + endloop + endfacet + facet normal 0.195617 -0.240142 0.950824 + outer loop + vertex 1.15353 0.938666 2.53402 + vertex 1.15862 0.943566 2.53421 + vertex 1.1539 0.943536 2.53518 + endloop + endfacet + facet normal 0.192522 -0.237301 0.952168 + outer loop + vertex 1.14997 0.942467 2.53571 + vertex 1.14869 0.938622 2.53501 + vertex 1.1539 0.943536 2.53518 + endloop + endfacet + facet normal 0.196586 -0.238451 0.951049 + outer loop + vertex 1.14997 0.942467 2.53571 + vertex 1.14687 0.940433 2.53584 + vertex 1.14869 0.938622 2.53501 + endloop + endfacet + facet normal 0.200277 -0.234815 0.951184 + outer loop + vertex 1.14869 0.938622 2.53501 + vertex 1.14687 0.940433 2.53584 + vertex 1.14474 0.937549 2.53557 + endloop + endfacet + facet normal 0.23032 -0.255903 0.938864 + outer loop + vertex 1.14687 0.940433 2.53584 + vertex 1.14293 0.939269 2.53649 + vertex 1.14474 0.937549 2.53557 + endloop + endfacet + facet normal 0.229107 -0.250876 0.940516 + outer loop + vertex 1.14687 0.940433 2.53584 + vertex 1.14811 0.94418 2.53654 + vertex 1.14293 0.939269 2.53649 + endloop + endfacet + facet normal 0.212067 -0.233013 0.949069 + outer loop + vertex 1.14811 0.94418 2.53654 + vertex 1.14315 0.943925 2.53758 + vertex 1.14293 0.939269 2.53649 + endloop + endfacet + facet normal 0.259697 -0.232435 0.9373 + outer loop + vertex 1.14293 0.939269 2.53649 + vertex 1.14315 0.943925 2.53758 + vertex 1.13816 0.939141 2.53778 + endloop + endfacet + facet normal 0.260164 -0.219271 0.940338 + outer loop + vertex 1.14293 0.939269 2.53649 + vertex 1.13816 0.939141 2.53778 + vertex 1.13804 0.934312 2.53668 + endloop + endfacet + facet normal 0.299901 -0.259409 0.918023 + outer loop + vertex 1.1418 0.935539 2.5358 + vertex 1.14293 0.939269 2.53649 + vertex 1.13804 0.934312 2.53668 + endloop + endfacet + facet normal 0.296974 -0.247381 0.922285 + outer loop + vertex 1.1418 0.935539 2.5358 + vertex 1.13804 0.934312 2.53668 + vertex 1.13997 0.932723 2.53563 + endloop + endfacet + facet normal 0.237278 -0.2103 0.948405 + outer loop + vertex 1.14371 0.933818 2.53494 + vertex 1.1418 0.935539 2.5358 + vertex 1.13997 0.932723 2.53563 + endloop + endfacet + facet normal 0.232318 -0.189845 0.953932 + outer loop + vertex 1.13997 0.932723 2.53563 + vertex 1.13964 0.929496 2.53507 + vertex 1.14371 0.933818 2.53494 + endloop + endfacet + facet normal 0.249478 -0.206241 0.946164 + outer loop + vertex 1.14371 0.933818 2.53494 + vertex 1.13964 0.929496 2.53507 + vertex 1.14348 0.929045 2.53396 + endloop + endfacet + facet normal 0.295998 -0.193132 0.93546 + outer loop + vertex 1.13997 0.932723 2.53563 + vertex 1.13724 0.930421 2.53602 + vertex 1.13964 0.929496 2.53507 + endloop + endfacet + facet normal 0.317966 -0.221513 0.921862 + outer loop + vertex 1.13997 0.932723 2.53563 + vertex 1.13804 0.934312 2.53668 + vertex 1.13724 0.930421 2.53602 + endloop + endfacet + facet normal 0.232287 -0.203321 0.951159 + outer loop + vertex 1.13816 0.939141 2.53778 + vertex 1.14315 0.943925 2.53758 + vertex 1.13848 0.944024 2.53874 + endloop + endfacet + facet normal 0.230931 -0.222006 0.947304 + outer loop + vertex 1.14315 0.943925 2.53758 + vertex 1.1433 0.948683 2.53866 + vertex 1.13848 0.944024 2.53874 + endloop + endfacet + facet normal 0.209093 -0.199216 0.957389 + outer loop + vertex 1.13848 0.944024 2.53874 + vertex 1.1433 0.948683 2.53866 + vertex 1.13881 0.948669 2.53964 + endloop + endfacet + facet normal 0.208 -0.224502 0.952016 + outer loop + vertex 1.1433 0.948683 2.53866 + vertex 1.14327 0.953645 2.53983 + vertex 1.13881 0.948669 2.53964 + endloop + endfacet + facet normal 0.19159 -0.21006 0.958732 + outer loop + vertex 1.13881 0.948669 2.53964 + vertex 1.14327 0.953645 2.53983 + vertex 1.13847 0.952273 2.54049 + endloop + endfacet + facet normal 0.228768 -0.204884 0.951676 + outer loop + vertex 1.13847 0.952273 2.54049 + vertex 1.13522 0.948946 2.54056 + vertex 1.13881 0.948669 2.53964 + endloop + endfacet + facet normal 0.232078 -0.177565 0.956353 + outer loop + vertex 1.13457 0.944804 2.53995 + vertex 1.13881 0.948669 2.53964 + vertex 1.13522 0.948946 2.54056 + endloop + endfacet + facet normal 0.222366 -0.198561 0.95453 + outer loop + vertex 1.13544 0.951872 2.54112 + vertex 1.13522 0.948946 2.54056 + vertex 1.13847 0.952273 2.54049 + endloop + endfacet + facet normal 0.224508 -0.224472 0.948266 + outer loop + vertex 1.13847 0.952273 2.54049 + vertex 1.13737 0.954513 2.54128 + vertex 1.13544 0.951872 2.54112 + endloop + endfacet + facet normal 0.262957 -0.251509 0.931449 + outer loop + vertex 1.13737 0.954513 2.54128 + vertex 1.13356 0.953788 2.54216 + vertex 1.13544 0.951872 2.54112 + endloop + endfacet + facet normal 0.29195 -0.222347 0.93023 + outer loop + vertex 1.13544 0.951872 2.54112 + vertex 1.13356 0.953788 2.54216 + vertex 1.13284 0.949923 2.54147 + endloop + endfacet + facet normal 0.263287 -0.254276 0.930604 + outer loop + vertex 1.13737 0.954513 2.54128 + vertex 1.13864 0.958656 2.54206 + vertex 1.13356 0.953788 2.54216 + endloop + endfacet + facet normal 0.227909 -0.2169 0.949216 + outer loop + vertex 1.13864 0.958656 2.54206 + vertex 1.13352 0.958812 2.54332 + vertex 1.13356 0.953788 2.54216 + endloop + endfacet + facet normal 0.227047 -0.227246 0.947 + outer loop + vertex 1.13864 0.958656 2.54206 + vertex 1.13839 0.963616 2.54331 + vertex 1.13352 0.958812 2.54332 + endloop + endfacet + facet normal 0.208872 -0.208783 0.955396 + outer loop + vertex 1.13352 0.958812 2.54332 + vertex 1.13839 0.963616 2.54331 + vertex 1.13374 0.963735 2.54435 + endloop + endfacet + facet normal 0.251033 -0.208562 0.945243 + outer loop + vertex 1.13352 0.958812 2.54332 + vertex 1.13374 0.963735 2.54435 + vertex 1.12863 0.959239 2.54471 + endloop + endfacet + facet normal 0.254802 -0.180789 0.949943 + outer loop + vertex 1.12886 0.954192 2.54369 + vertex 1.13352 0.958812 2.54332 + vertex 1.12863 0.959239 2.54471 + endloop + endfacet + facet normal 0.285532 -0.21298 0.934404 + outer loop + vertex 1.13356 0.953788 2.54216 + vertex 1.13352 0.958812 2.54332 + vertex 1.12886 0.954192 2.54369 + endloop + endfacet + facet normal 0.207648 -0.225534 0.951849 + outer loop + vertex 1.13839 0.963616 2.54331 + vertex 1.13843 0.968361 2.54442 + vertex 1.13374 0.963735 2.54435 + endloop + endfacet + facet normal 0.18867 -0.226266 0.955619 + outer loop + vertex 1.13839 0.963616 2.54331 + vertex 1.14323 0.968608 2.54353 + vertex 1.13843 0.968361 2.54442 + endloop + endfacet + facet normal 0.194714 -0.232017 0.953024 + outer loop + vertex 1.14338 0.963958 2.54237 + vertex 1.14323 0.968608 2.54353 + vertex 1.13839 0.963616 2.54331 + endloop + endfacet + facet normal 0.184997 -0.232755 0.954778 + outer loop + vertex 1.14338 0.963958 2.54237 + vertex 1.14827 0.968804 2.5426 + vertex 1.14323 0.968608 2.54353 + endloop + endfacet + facet normal 0.184988 -0.234332 0.954394 + outer loop + vertex 1.14827 0.968804 2.5426 + vertex 1.14827 0.97362 2.54379 + vertex 1.14323 0.968608 2.54353 + endloop + endfacet + facet normal 0.182576 -0.231962 0.955437 + outer loop + vertex 1.14323 0.968608 2.54353 + vertex 1.14827 0.97362 2.54379 + vertex 1.14316 0.973684 2.54478 + endloop + endfacet + facet normal 0.180878 -0.234518 0.955136 + outer loop + vertex 1.14827 0.968804 2.5426 + vertex 1.1534 0.973693 2.54283 + vertex 1.14827 0.97362 2.54379 + endloop + endfacet + facet normal 0.180817 -0.23652 0.954654 + outer loop + vertex 1.1534 0.973693 2.54283 + vertex 1.15348 0.978578 2.54403 + vertex 1.14827 0.97362 2.54379 + endloop + endfacet + facet normal 0.178188 -0.23659 0.95513 + outer loop + vertex 1.1534 0.973693 2.54283 + vertex 1.15862 0.978643 2.54309 + vertex 1.15348 0.978578 2.54403 + endloop + endfacet + facet normal 0.186634 -0.240431 0.952555 + outer loop + vertex 1.15335 0.969033 2.54167 + vertex 1.1534 0.973693 2.54283 + vertex 1.14827 0.968804 2.5426 + endloop + endfacet + facet normal 0.186639 -0.235068 0.953892 + outer loop + vertex 1.15335 0.969033 2.54167 + vertex 1.14827 0.968804 2.5426 + vertex 1.1483 0.964331 2.5415 + endloop + endfacet + facet normal 0.189127 -0.2377 0.952748 + outer loop + vertex 1.15218 0.965335 2.54098 + vertex 1.15335 0.969033 2.54167 + vertex 1.1483 0.964331 2.5415 + endloop + endfacet + facet normal 0.18875 -0.235984 0.95325 + outer loop + vertex 1.15218 0.965335 2.54098 + vertex 1.1483 0.964331 2.5415 + vertex 1.15002 0.962495 2.5407 + endloop + endfacet + facet normal 0.194299 -0.239987 0.951133 + outer loop + vertex 1.15385 0.96344 2.54016 + vertex 1.15218 0.965335 2.54098 + vertex 1.15002 0.962495 2.5407 + endloop + endfacet + facet normal 0.194743 -0.24216 0.950491 + outer loop + vertex 1.15002 0.962495 2.5407 + vertex 1.14865 0.958605 2.53999 + vertex 1.15385 0.96344 2.54016 + endloop + endfacet + facet normal 0.192649 -0.239939 0.951481 + outer loop + vertex 1.15385 0.96344 2.54016 + vertex 1.14865 0.958605 2.53999 + vertex 1.15348 0.95857 2.539 + endloop + endfacet + facet normal 0.192223 -0.239927 0.95157 + outer loop + vertex 1.15348 0.95857 2.539 + vertex 1.15856 0.96346 2.53921 + vertex 1.15385 0.96344 2.54016 + endloop + endfacet + facet normal 0.192183 -0.240819 0.951353 + outer loop + vertex 1.15891 0.968123 2.54032 + vertex 1.15385 0.96344 2.54016 + vertex 1.15856 0.96346 2.53921 + endloop + endfacet + facet normal 0.189443 -0.237909 0.952634 + outer loop + vertex 1.15518 0.96725 2.54084 + vertex 1.15385 0.96344 2.54016 + vertex 1.15891 0.968123 2.54032 + endloop + endfacet + facet normal 0.189743 -0.239459 0.952185 + outer loop + vertex 1.15891 0.968123 2.54032 + vertex 1.15733 0.970051 2.54112 + vertex 1.15518 0.96725 2.54084 + endloop + endfacet + facet normal 0.192404 -0.241397 0.951161 + outer loop + vertex 1.15733 0.970051 2.54112 + vertex 1.15335 0.969033 2.54167 + vertex 1.15518 0.96725 2.54084 + endloop + endfacet + facet normal 0.194498 -0.251158 0.948204 + outer loop + vertex 1.15733 0.970051 2.54112 + vertex 1.15857 0.973799 2.54186 + vertex 1.15335 0.969033 2.54167 + endloop + endfacet + facet normal 0.192982 -0.240701 0.951221 + outer loop + vertex 1.15845 0.958666 2.53802 + vertex 1.15856 0.96346 2.53921 + vertex 1.15348 0.95857 2.539 + endloop + endfacet + facet normal 0.193083 -0.237264 0.952063 + outer loop + vertex 1.15336 0.953742 2.53783 + vertex 1.15845 0.958666 2.53802 + vertex 1.15348 0.95857 2.539 + endloop + endfacet + facet normal 0.192511 -0.237277 0.952176 + outer loop + vertex 1.15336 0.953742 2.53783 + vertex 1.15348 0.95857 2.539 + vertex 1.14832 0.953613 2.53881 + endloop + endfacet + facet normal 0.192783 -0.237554 0.952052 + outer loop + vertex 1.14832 0.953613 2.53881 + vertex 1.15348 0.95857 2.539 + vertex 1.14865 0.958605 2.53999 + endloop + endfacet + facet normal 0.191318 -0.23753 0.952353 + outer loop + vertex 1.14865 0.958605 2.53999 + vertex 1.14327 0.953645 2.53983 + vertex 1.14832 0.953613 2.53881 + endloop + endfacet + facet normal 0.187465 -0.233408 0.954137 + outer loop + vertex 1.14474 0.957841 2.54057 + vertex 1.14327 0.953645 2.53983 + vertex 1.14865 0.958605 2.53999 + endloop + endfacet + facet normal 0.188737 -0.241682 0.951824 + outer loop + vertex 1.14865 0.958605 2.53999 + vertex 1.14709 0.960687 2.54083 + vertex 1.14474 0.957841 2.54057 + endloop + endfacet + facet normal 0.187654 -0.240824 0.952255 + outer loop + vertex 1.14709 0.960687 2.54083 + vertex 1.14383 0.960225 2.54136 + vertex 1.14474 0.957841 2.54057 + endloop + endfacet + facet normal 0.191297 -0.239318 0.95191 + outer loop + vertex 1.14474 0.957841 2.54057 + vertex 1.14383 0.960225 2.54136 + vertex 1.14101 0.956154 2.5409 + endloop + endfacet + facet normal 0.202802 -0.246792 0.94761 + outer loop + vertex 1.14383 0.960225 2.54136 + vertex 1.13864 0.958656 2.54206 + vertex 1.14101 0.956154 2.5409 + endloop + endfacet + facet normal 0.199695 -0.234884 0.951289 + outer loop + vertex 1.14383 0.960225 2.54136 + vertex 1.14338 0.963958 2.54237 + vertex 1.13864 0.958656 2.54206 + endloop + endfacet + facet normal 0.187359 -0.236911 0.953294 + outer loop + vertex 1.1483 0.964331 2.5415 + vertex 1.14338 0.963958 2.54237 + vertex 1.14383 0.960225 2.54136 + endloop + endfacet + facet normal 0.187259 -0.236804 0.95334 + outer loop + vertex 1.14709 0.960687 2.54083 + vertex 1.1483 0.964331 2.5415 + vertex 1.14383 0.960225 2.54136 + endloop + endfacet + facet normal 0.188989 -0.233868 0.953724 + outer loop + vertex 1.14474 0.957841 2.54057 + vertex 1.14101 0.956154 2.5409 + vertex 1.14327 0.953645 2.53983 + endloop + endfacet + facet normal 0.190004 -0.24073 0.951813 + outer loop + vertex 1.15002 0.962495 2.5407 + vertex 1.14709 0.960687 2.54083 + vertex 1.14865 0.958605 2.53999 + endloop + endfacet + facet normal 0.194835 -0.239515 0.951142 + outer loop + vertex 1.15518 0.96725 2.54084 + vertex 1.15218 0.965335 2.54098 + vertex 1.15385 0.96344 2.54016 + endloop + endfacet + facet normal 0.187722 -0.236934 0.953217 + outer loop + vertex 1.15002 0.962495 2.5407 + vertex 1.1483 0.964331 2.5415 + vertex 1.14709 0.960687 2.54083 + endloop + endfacet + facet normal 0.194622 -0.239172 0.951272 + outer loop + vertex 1.15518 0.96725 2.54084 + vertex 1.15335 0.969033 2.54167 + vertex 1.15218 0.965335 2.54098 + endloop + endfacet + facet normal 0.184586 -0.240506 0.952935 + outer loop + vertex 1.15857 0.973799 2.54186 + vertex 1.1534 0.973693 2.54283 + vertex 1.15335 0.969033 2.54167 + endloop + endfacet + facet normal 0.187302 -0.235034 0.95377 + outer loop + vertex 1.1483 0.964331 2.5415 + vertex 1.14827 0.968804 2.5426 + vertex 1.14338 0.963958 2.54237 + endloop + endfacet + facet normal 0.194681 -0.230533 0.953391 + outer loop + vertex 1.13864 0.958656 2.54206 + vertex 1.14338 0.963958 2.54237 + vertex 1.13839 0.963616 2.54331 + endloop + endfacet + facet normal 0.209142 -0.240863 0.947758 + outer loop + vertex 1.14101 0.956154 2.5409 + vertex 1.13864 0.958656 2.54206 + vertex 1.13737 0.954513 2.54128 + endloop + endfacet + facet normal 0.206309 -0.234037 0.950086 + outer loop + vertex 1.13737 0.954513 2.54128 + vertex 1.13847 0.952273 2.54049 + vertex 1.14101 0.956154 2.5409 + endloop + endfacet + facet normal 0.276492 -0.199993 0.939976 + outer loop + vertex 1.13544 0.951872 2.54112 + vertex 1.13284 0.949923 2.54147 + vertex 1.13522 0.948946 2.54056 + endloop + endfacet + facet normal 0.195945 -0.227648 0.953825 + outer loop + vertex 1.13847 0.952273 2.54049 + vertex 1.14327 0.953645 2.53983 + vertex 1.14101 0.956154 2.5409 + endloop + endfacet + facet normal 0.191966 -0.225355 0.955178 + outer loop + vertex 1.1433 0.948683 2.53866 + vertex 1.14832 0.953613 2.53881 + vertex 1.14327 0.953645 2.53983 + endloop + endfacet + facet normal 0.199725 -0.233149 0.95171 + outer loop + vertex 1.14823 0.948802 2.53765 + vertex 1.14832 0.953613 2.53881 + vertex 1.1433 0.948683 2.53866 + endloop + endfacet + facet normal 0.199975 -0.222549 0.954192 + outer loop + vertex 1.14315 0.943925 2.53758 + vertex 1.14823 0.948802 2.53765 + vertex 1.1433 0.948683 2.53866 + endloop + endfacet + facet normal 0.199334 -0.242739 0.949391 + outer loop + vertex 1.14997 0.942467 2.53571 + vertex 1.14811 0.94418 2.53654 + vertex 1.14687 0.940433 2.53584 + endloop + endfacet + facet normal 0.202953 -0.237941 0.949839 + outer loop + vertex 1.15335 0.933834 2.53285 + vertex 1.15353 0.938666 2.53402 + vertex 1.1484 0.933778 2.53389 + endloop + endfacet + facet normal 0.196216 -0.238031 0.951231 + outer loop + vertex 1.15335 0.933834 2.53285 + vertex 1.1585 0.938741 2.53302 + vertex 1.15353 0.938666 2.53402 + endloop + endfacet + facet normal 0.196126 -0.240662 0.950587 + outer loop + vertex 1.1585 0.938741 2.53302 + vertex 1.15862 0.943566 2.53421 + vertex 1.15353 0.938666 2.53402 + endloop + endfacet + facet normal 0.197276 -0.240633 0.950357 + outer loop + vertex 1.1585 0.938741 2.53302 + vertex 1.16354 0.943642 2.53321 + vertex 1.15862 0.943566 2.53421 + endloop + endfacet + facet normal 0.197308 -0.239703 0.950585 + outer loop + vertex 1.16354 0.943642 2.53321 + vertex 1.16346 0.948398 2.53443 + vertex 1.15862 0.943566 2.53421 + endloop + endfacet + facet normal 0.197785 -0.24017 0.950368 + outer loop + vertex 1.15862 0.943566 2.53421 + vertex 1.16346 0.948398 2.53443 + vertex 1.1589 0.948283 2.53535 + endloop + endfacet + facet normal 0.197844 -0.237774 0.950958 + outer loop + vertex 1.16321 0.952315 2.53546 + vertex 1.1589 0.948283 2.53535 + vertex 1.16346 0.948398 2.53443 + endloop + endfacet + facet normal 0.196992 -0.237869 0.951111 + outer loop + vertex 1.16346 0.948398 2.53443 + vertex 1.16818 0.953736 2.53479 + vertex 1.16321 0.952315 2.53546 + endloop + endfacet + facet normal 0.197063 -0.23793 0.951081 + outer loop + vertex 1.16839 0.948676 2.53348 + vertex 1.16818 0.953736 2.53479 + vertex 1.16346 0.948398 2.53443 + endloop + endfacet + facet normal 0.192543 -0.238337 0.951905 + outer loop + vertex 1.16839 0.948676 2.53348 + vertex 1.1733 0.953706 2.53374 + vertex 1.16818 0.953736 2.53479 + endloop + endfacet + facet normal 0.194072 -0.239794 0.951228 + outer loop + vertex 1.17347 0.949033 2.53253 + vertex 1.1733 0.953706 2.53374 + vertex 1.16839 0.948676 2.53348 + endloop + endfacet + facet normal 0.194094 -0.240766 0.950978 + outer loop + vertex 1.16879 0.943728 2.53214 + vertex 1.17347 0.949033 2.53253 + vertex 1.16839 0.948676 2.53348 + endloop + endfacet + facet normal 0.1977 -0.240305 0.950352 + outer loop + vertex 1.16879 0.943728 2.53214 + vertex 1.16839 0.948676 2.53348 + vertex 1.16354 0.943642 2.53321 + endloop + endfacet + facet normal 0.197676 -0.241018 0.950176 + outer loop + vertex 1.16879 0.943728 2.53214 + vertex 1.16354 0.943642 2.53321 + vertex 1.16357 0.938818 2.53198 + endloop + endfacet + facet normal 0.199679 -0.24312 0.949221 + outer loop + vertex 1.1675 0.939581 2.53135 + vertex 1.16879 0.943728 2.53214 + vertex 1.16357 0.938818 2.53198 + endloop + endfacet + facet normal 0.199511 -0.241982 0.949547 + outer loop + vertex 1.1675 0.939581 2.53135 + vertex 1.16357 0.938818 2.53198 + vertex 1.16529 0.936823 2.53111 + endloop + endfacet + facet normal 0.200101 -0.242435 0.949308 + outer loop + vertex 1.16835 0.937171 2.53056 + vertex 1.1675 0.939581 2.53135 + vertex 1.16529 0.936823 2.53111 + endloop + endfacet + facet normal 0.200171 -0.243519 0.949015 + outer loop + vertex 1.16529 0.936823 2.53111 + vertex 1.16402 0.933151 2.53044 + vertex 1.16835 0.937171 2.53056 + endloop + endfacet + facet normal 0.200307 -0.243664 0.94895 + outer loop + vertex 1.16835 0.937171 2.53056 + vertex 1.16402 0.933151 2.53044 + vertex 1.16849 0.933316 2.52954 + endloop + endfacet + facet normal 0.201229 -0.243829 0.948712 + outer loop + vertex 1.16529 0.936823 2.53111 + vertex 1.16246 0.935081 2.53127 + vertex 1.16402 0.933151 2.53044 + endloop + endfacet + facet normal 0.200754 -0.244215 0.948713 + outer loop + vertex 1.16402 0.933151 2.53044 + vertex 1.16246 0.935081 2.53127 + vertex 1.16036 0.932263 2.53098 + endloop + endfacet + facet normal 0.201445 -0.247718 0.947658 + outer loop + vertex 1.16036 0.932263 2.53098 + vertex 1.15901 0.928438 2.53027 + vertex 1.16402 0.933151 2.53044 + endloop + endfacet + facet normal 0.199581 -0.24577 0.948559 + outer loop + vertex 1.16402 0.933151 2.53044 + vertex 1.15901 0.928438 2.53027 + vertex 1.16365 0.928501 2.52931 + endloop + endfacet + facet normal 0.200051 -0.247304 0.948061 + outer loop + vertex 1.16036 0.932263 2.53098 + vertex 1.15731 0.930286 2.53111 + vertex 1.15901 0.928438 2.53027 + endloop + endfacet + facet normal 0.199227 -0.248053 0.948039 + outer loop + vertex 1.15901 0.928438 2.53027 + vertex 1.15731 0.930286 2.53111 + vertex 1.15511 0.927374 2.53081 + endloop + endfacet + facet normal 0.198684 -0.245687 0.948769 + outer loop + vertex 1.15511 0.927374 2.53081 + vertex 1.15381 0.923548 2.53009 + vertex 1.15901 0.928438 2.53027 + endloop + endfacet + facet normal 0.199933 -0.246994 0.948167 + outer loop + vertex 1.15901 0.928438 2.53027 + vertex 1.15381 0.923548 2.53009 + vertex 1.15858 0.92363 2.52911 + endloop + endfacet + facet normal 0.203775 -0.251306 0.946214 + outer loop + vertex 1.15731 0.930286 2.53111 + vertex 1.15323 0.929129 2.53168 + vertex 1.15511 0.927374 2.53081 + endloop + endfacet + facet normal 0.205462 -0.249546 0.946315 + outer loop + vertex 1.15511 0.927374 2.53081 + vertex 1.15323 0.929129 2.53168 + vertex 1.15201 0.925345 2.53095 + endloop + endfacet + facet normal 0.202149 -0.244514 0.94834 + outer loop + vertex 1.15731 0.930286 2.53111 + vertex 1.15846 0.934033 2.53183 + vertex 1.15323 0.929129 2.53168 + endloop + endfacet + facet normal 0.198816 -0.241005 0.949941 + outer loop + vertex 1.15846 0.934033 2.53183 + vertex 1.15335 0.933834 2.53285 + vertex 1.15323 0.929129 2.53168 + endloop + endfacet + facet normal 0.21542 -0.240582 0.946422 + outer loop + vertex 1.15323 0.929129 2.53168 + vertex 1.15335 0.933834 2.53285 + vertex 1.14821 0.928953 2.53278 + endloop + endfacet + facet normal 0.19882 -0.240723 0.950012 + outer loop + vertex 1.15846 0.934033 2.53183 + vertex 1.1585 0.938741 2.53302 + vertex 1.15335 0.933834 2.53285 + endloop + endfacet + facet normal 0.197667 -0.24077 0.950241 + outer loop + vertex 1.16357 0.938818 2.53198 + vertex 1.1585 0.938741 2.53302 + vertex 1.15846 0.934033 2.53183 + endloop + endfacet + facet normal 0.197547 -0.243346 0.949609 + outer loop + vertex 1.16036 0.932263 2.53098 + vertex 1.15846 0.934033 2.53183 + vertex 1.15731 0.930286 2.53111 + endloop + endfacet + facet normal 0.198344 -0.242514 0.949656 + outer loop + vertex 1.16246 0.935081 2.53127 + vertex 1.15846 0.934033 2.53183 + vertex 1.16036 0.932263 2.53098 + endloop + endfacet + facet normal 0.198049 -0.241172 0.950059 + outer loop + vertex 1.16246 0.935081 2.53127 + vertex 1.16357 0.938818 2.53198 + vertex 1.15846 0.934033 2.53183 + endloop + endfacet + facet normal 0.198118 -0.243205 0.949526 + outer loop + vertex 1.1675 0.939581 2.53135 + vertex 1.16835 0.937171 2.53056 + vertex 1.17115 0.941224 2.53101 + endloop + endfacet + facet normal 0.19721 -0.242615 0.949866 + outer loop + vertex 1.16835 0.937171 2.53056 + vertex 1.1733 0.938654 2.52991 + vertex 1.17115 0.941224 2.53101 + endloop + endfacet + facet normal 0.195559 -0.24399 0.949856 + outer loop + vertex 1.17486 0.942893 2.53067 + vertex 1.17115 0.941224 2.53101 + vertex 1.1733 0.938654 2.52991 + endloop + endfacet + facet normal 0.195429 -0.243679 0.949962 + outer loop + vertex 1.17486 0.942893 2.53067 + vertex 1.17396 0.945288 2.53147 + vertex 1.17115 0.941224 2.53101 + endloop + endfacet + facet normal 0.196228 -0.244198 0.949664 + outer loop + vertex 1.17396 0.945288 2.53147 + vertex 1.16879 0.943728 2.53214 + vertex 1.17115 0.941224 2.53101 + endloop + endfacet + facet normal 0.192857 -0.244731 0.950217 + outer loop + vertex 1.17719 0.945702 2.53093 + vertex 1.17396 0.945288 2.53147 + vertex 1.17486 0.942893 2.53067 + endloop + endfacet + facet normal 0.192473 -0.244426 0.950374 + outer loop + vertex 1.1787 0.943604 2.53008 + vertex 1.17719 0.945702 2.53093 + vertex 1.17486 0.942893 2.53067 + endloop + endfacet + facet normal 0.192919 -0.245486 0.95001 + outer loop + vertex 1.17719 0.945702 2.53093 + vertex 1.17836 0.949312 2.53162 + vertex 1.17396 0.945288 2.53147 + endloop + endfacet + facet normal 0.190617 -0.243013 0.95111 + outer loop + vertex 1.17836 0.949312 2.53162 + vertex 1.17347 0.949033 2.53253 + vertex 1.17396 0.945288 2.53147 + endloop + endfacet + facet normal 0.190632 -0.244618 0.950695 + outer loop + vertex 1.17836 0.949312 2.53162 + vertex 1.17834 0.95382 2.53278 + vertex 1.17347 0.949033 2.53253 + endloop + endfacet + facet normal 0.18434 -0.244938 0.951853 + outer loop + vertex 1.18338 0.953897 2.53183 + vertex 1.17834 0.95382 2.53278 + vertex 1.17836 0.949312 2.53162 + endloop + endfacet + facet normal 0.190597 -0.251657 0.948863 + outer loop + vertex 1.18215 0.950174 2.53109 + vertex 1.18338 0.953897 2.53183 + vertex 1.17836 0.949312 2.53162 + endloop + endfacet + facet normal 0.191066 -0.244985 0.950513 + outer loop + vertex 1.18005 0.947426 2.53079 + vertex 1.17836 0.949312 2.53162 + vertex 1.17719 0.945702 2.53093 + endloop + endfacet + facet normal 0.199921 -0.24163 0.949551 + outer loop + vertex 1.16529 0.936823 2.53111 + vertex 1.16357 0.938818 2.53198 + vertex 1.16246 0.935081 2.53127 + endloop + endfacet + facet normal 0.197889 -0.242656 0.949715 + outer loop + vertex 1.17115 0.941224 2.53101 + vertex 1.16879 0.943728 2.53214 + vertex 1.1675 0.939581 2.53135 + endloop + endfacet + facet normal 0.197658 -0.241019 0.95018 + outer loop + vertex 1.16357 0.938818 2.53198 + vertex 1.16354 0.943642 2.53321 + vertex 1.1585 0.938741 2.53302 + endloop + endfacet + facet normal 0.195683 -0.242117 0.950309 + outer loop + vertex 1.17396 0.945288 2.53147 + vertex 1.17347 0.949033 2.53253 + vertex 1.16879 0.943728 2.53214 + endloop + endfacet + facet normal 0.186406 -0.240416 0.952603 + outer loop + vertex 1.17347 0.949033 2.53253 + vertex 1.17834 0.95382 2.53278 + vertex 1.1733 0.953706 2.53374 + endloop + endfacet + facet normal 0.186278 -0.245546 0.951319 + outer loop + vertex 1.17834 0.95382 2.53278 + vertex 1.17844 0.958582 2.53399 + vertex 1.1733 0.953706 2.53374 + endloop + endfacet + facet normal 0.180368 -0.239462 0.954005 + outer loop + vertex 1.1733 0.953706 2.53374 + vertex 1.17844 0.958582 2.53399 + vertex 1.17357 0.958651 2.53493 + endloop + endfacet + facet normal 0.173901 -0.245866 0.953577 + outer loop + vertex 1.17834 0.95382 2.53278 + vertex 1.18349 0.958696 2.5331 + vertex 1.17844 0.958582 2.53399 + endloop + endfacet + facet normal 0.173541 -0.261054 0.949597 + outer loop + vertex 1.18349 0.958696 2.5331 + vertex 1.18355 0.963446 2.5344 + vertex 1.17844 0.958582 2.53399 + endloop + endfacet + facet normal 0.197076 -0.239718 0.950629 + outer loop + vertex 1.16354 0.943642 2.53321 + vertex 1.16839 0.948676 2.53348 + vertex 1.16346 0.948398 2.53443 + endloop + endfacet + facet normal 0.195899 -0.215872 0.956568 + outer loop + vertex 1.14474 0.937549 2.53557 + vertex 1.14371 0.933818 2.53494 + vertex 1.14869 0.938622 2.53501 + endloop + endfacet + facet normal 0.226035 -0.222776 0.948303 + outer loop + vertex 1.14474 0.937549 2.53557 + vertex 1.1418 0.935539 2.5358 + vertex 1.14371 0.933818 2.53494 + endloop + endfacet + facet normal 0.240628 -0.245205 0.939134 + outer loop + vertex 1.14474 0.937549 2.53557 + vertex 1.14293 0.939269 2.53649 + vertex 1.1418 0.935539 2.5358 + endloop + endfacet + facet normal 0.203339 -0.227937 0.952207 + outer loop + vertex 1.14821 0.928953 2.53278 + vertex 1.15335 0.933834 2.53285 + vertex 1.1484 0.933778 2.53389 + endloop + endfacet + facet normal 0.21546 -0.238508 0.946938 + outer loop + vertex 1.15323 0.929129 2.53168 + vertex 1.14821 0.928953 2.53278 + vertex 1.14804 0.924213 2.53163 + endloop + endfacet + facet normal 0.232826 -0.256731 0.93802 + outer loop + vertex 1.15201 0.925345 2.53095 + vertex 1.15323 0.929129 2.53168 + vertex 1.14804 0.924213 2.53163 + endloop + endfacet + facet normal 0.203962 -0.247193 0.947257 + outer loop + vertex 1.15511 0.927374 2.53081 + vertex 1.15201 0.925345 2.53095 + vertex 1.15381 0.923548 2.53009 + endloop + endfacet + facet normal 0.230769 -0.231917 0.944966 + outer loop + vertex 1.14988 0.922462 2.53067 + vertex 1.14692 0.92046 2.53091 + vertex 1.14883 0.918757 2.53002 + endloop + endfacet + facet normal 0.221471 -0.250619 0.942412 + outer loop + vertex 1.15823 0.914174 2.5267 + vertex 1.15836 0.918844 2.52792 + vertex 1.15325 0.913991 2.52782 + endloop + endfacet + facet normal 0.200212 -0.238852 0.950192 + outer loop + vertex 1.15348 0.918767 2.52896 + vertex 1.15858 0.92363 2.52911 + vertex 1.15381 0.923548 2.53009 + endloop + endfacet + facet normal 0.19968 -0.246986 0.948222 + outer loop + vertex 1.16339 0.918959 2.52689 + vertex 1.16347 0.923722 2.52811 + vertex 1.15836 0.918844 2.52792 + endloop + endfacet + facet normal 0.199081 -0.247007 0.948343 + outer loop + vertex 1.16866 0.923851 2.52705 + vertex 1.16347 0.923722 2.52811 + vertex 1.16339 0.918959 2.52689 + endloop + endfacet + facet normal 0.199534 -0.24698 0.948255 + outer loop + vertex 1.15858 0.92363 2.52911 + vertex 1.16365 0.928501 2.52931 + vertex 1.15901 0.928438 2.53027 + endloop + endfacet + facet normal 0.199112 -0.245871 0.948632 + outer loop + vertex 1.16866 0.923851 2.52705 + vertex 1.16843 0.928668 2.52835 + vertex 1.16347 0.923722 2.52811 + endloop + endfacet + facet normal 0.200276 -0.245789 0.948408 + outer loop + vertex 1.16365 0.928501 2.52931 + vertex 1.16849 0.933316 2.52954 + vertex 1.16402 0.933151 2.53044 + endloop + endfacet + facet normal 0.199193 -0.24563 0.948677 + outer loop + vertex 1.17336 0.929115 2.52743 + vertex 1.1733 0.933686 2.52863 + vertex 1.16843 0.928668 2.52835 + endloop + endfacet + facet normal 0.197543 -0.243902 0.949467 + outer loop + vertex 1.16849 0.933316 2.52954 + vertex 1.1733 0.938654 2.52991 + vertex 1.16835 0.937171 2.53056 + endloop + endfacet + facet normal 0.196758 -0.246539 0.948949 + outer loop + vertex 1.17824 0.933937 2.52767 + vertex 1.17834 0.938681 2.52888 + vertex 1.1733 0.933686 2.52863 + endloop + endfacet + facet normal 0.192264 -0.242945 0.950796 + outer loop + vertex 1.17486 0.942893 2.53067 + vertex 1.1733 0.938654 2.52991 + vertex 1.1787 0.943604 2.53008 + endloop + endfacet + facet normal 0.193949 -0.24763 0.949243 + outer loop + vertex 1.18334 0.938813 2.52789 + vertex 1.18347 0.943565 2.5291 + vertex 1.17834 0.938681 2.52888 + endloop + endfacet + facet normal 0.191256 -0.245309 0.950392 + outer loop + vertex 1.18005 0.947426 2.53079 + vertex 1.17719 0.945702 2.53093 + vertex 1.1787 0.943604 2.53008 + endloop + endfacet + facet normal 0.189603 -0.246284 0.950471 + outer loop + vertex 1.18215 0.950174 2.53109 + vertex 1.17836 0.949312 2.53162 + vertex 1.18005 0.947426 2.53079 + endloop + endfacet + facet normal 0.185352 -0.256446 0.94862 + outer loop + vertex 1.18736 0.954631 2.53124 + vertex 1.18819 0.952196 2.53042 + vertex 1.19115 0.95624 2.53093 + endloop + endfacet + facet normal 0.191042 -0.251779 0.948741 + outer loop + vertex 1.18502 0.95187 2.53096 + vertex 1.18338 0.953897 2.53183 + vertex 1.18215 0.950174 2.53109 + endloop + endfacet + facet normal 0.190136 -0.268517 0.944323 + outer loop + vertex 1.19115 0.95624 2.53093 + vertex 1.18883 0.958799 2.53213 + vertex 1.18736 0.954631 2.53124 + endloop + endfacet + facet normal 0.183961 -0.25618 0.948963 + outer loop + vertex 1.18338 0.953897 2.53183 + vertex 1.18349 0.958696 2.5331 + vertex 1.17834 0.95382 2.53278 + endloop + endfacet + facet normal 0.167035 -0.261272 0.950703 + outer loop + vertex 1.18349 0.958696 2.5331 + vertex 1.18855 0.963753 2.5336 + vertex 1.18355 0.963446 2.5344 + endloop + endfacet + facet normal 0.185691 -0.27451 0.943485 + outer loop + vertex 1.19411 0.960295 2.53152 + vertex 1.19357 0.96408 2.53273 + vertex 1.18883 0.958799 2.53213 + endloop + endfacet + facet normal 0.183389 -0.218386 0.958476 + outer loop + vertex 1.19849 0.96424 2.53183 + vertex 1.1979 0.968661 2.53295 + vertex 1.19357 0.96408 2.53273 + endloop + endfacet + facet normal 0.330068 -0.104428 0.938163 + outer loop + vertex 1.1979 0.968661 2.53295 + vertex 1.20152 0.97352 2.53221 + vertex 1.19681 0.972144 2.53372 + endloop + endfacet + facet normal 0.197088 -0.26702 0.943322 + outer loop + vertex 1.18855 0.963753 2.5336 + vertex 1.19318 0.968534 2.53399 + vertex 1.18843 0.968773 2.53505 + endloop + endfacet + facet normal 0.154401 -0.187261 0.9701 + outer loop + vertex 1.18977 0.972977 2.53597 + vertex 1.18822 0.975235 2.53666 + vertex 1.18621 0.971397 2.53624 + endloop + endfacet + facet normal 0.167166 -0.269232 0.948457 + outer loop + vertex 1.18855 0.963753 2.5336 + vertex 1.18843 0.968773 2.53505 + vertex 1.18355 0.963446 2.5344 + endloop + endfacet + facet normal 0.161585 -0.248942 0.954944 + outer loop + vertex 1.17844 0.958582 2.53399 + vertex 1.18355 0.963446 2.5344 + vertex 1.17879 0.963295 2.53516 + endloop + endfacet + facet normal 0.156921 -0.275298 0.948466 + outer loop + vertex 1.18256 0.969751 2.53636 + vertex 1.18344 0.967367 2.53552 + vertex 1.18621 0.971397 2.53624 + endloop + endfacet + facet normal 0.158946 -0.236901 0.958443 + outer loop + vertex 1.18256 0.969751 2.53636 + vertex 1.18337 0.973638 2.53719 + vertex 1.17848 0.968932 2.53684 + endloop + endfacet + facet normal 0.170546 -0.248569 0.953482 + outer loop + vertex 1.18337 0.973638 2.53719 + vertex 1.17829 0.973487 2.53806 + vertex 1.17848 0.968932 2.53684 + endloop + endfacet + facet normal 0.165909 -0.263456 0.950297 + outer loop + vertex 1.18023 0.966992 2.53594 + vertex 1.17723 0.965252 2.53598 + vertex 1.17879 0.963295 2.53516 + endloop + endfacet + facet normal 0.179755 -0.249466 0.951554 + outer loop + vertex 1.17879 0.963295 2.53516 + vertex 1.17357 0.958651 2.53493 + vertex 1.17844 0.958582 2.53399 + endloop + endfacet + facet normal 0.197848 -0.265601 0.943564 + outer loop + vertex 1.17498 0.962485 2.53564 + vertex 1.17336 0.964376 2.53651 + vertex 1.17204 0.960771 2.53578 + endloop + endfacet + facet normal 0.199299 -0.266046 0.943133 + outer loop + vertex 1.17204 0.960771 2.53578 + vertex 1.17336 0.964376 2.53651 + vertex 1.16884 0.960377 2.53634 + endloop + endfacet + facet normal 0.191656 -0.257564 0.947063 + outer loop + vertex 1.17336 0.964376 2.53651 + vertex 1.1685 0.964065 2.53741 + vertex 1.16884 0.960377 2.53634 + endloop + endfacet + facet normal 0.192477 -0.239533 0.951618 + outer loop + vertex 1.17357 0.958651 2.53493 + vertex 1.16818 0.953736 2.53479 + vertex 1.1733 0.953706 2.53374 + endloop + endfacet + facet normal 0.196827 -0.237194 0.951314 + outer loop + vertex 1.16321 0.952315 2.53546 + vertex 1.16818 0.953736 2.53479 + vertex 1.16598 0.956351 2.53589 + endloop + endfacet + facet normal 0.198013 -0.248252 0.948241 + outer loop + vertex 1.17204 0.960771 2.53578 + vertex 1.16884 0.960377 2.53634 + vertex 1.16967 0.957983 2.53554 + endloop + endfacet + facet normal 0.196041 -0.236684 0.951603 + outer loop + vertex 1.16234 0.954728 2.53624 + vertex 1.16321 0.952315 2.53546 + vertex 1.16598 0.956351 2.53589 + endloop + endfacet + facet normal 0.195328 -0.234578 0.952271 + outer loop + vertex 1.16013 0.95198 2.53601 + vertex 1.15842 0.953919 2.53684 + vertex 1.15731 0.950213 2.53616 + endloop + endfacet + facet normal 0.19209 -0.233761 0.95313 + outer loop + vertex 1.15731 0.950213 2.53616 + vertex 1.15842 0.953919 2.53684 + vertex 1.15332 0.949105 2.53669 + endloop + endfacet + facet normal 0.195616 -0.240152 0.950821 + outer loop + vertex 1.1589 0.948283 2.53535 + vertex 1.1539 0.943536 2.53518 + vertex 1.15862 0.943566 2.53421 + endloop + endfacet + facet normal 0.192414 -0.235118 0.952731 + outer loop + vertex 1.15731 0.950213 2.53616 + vertex 1.15332 0.949105 2.53669 + vertex 1.15521 0.947382 2.53588 + endloop + endfacet + facet normal 0.212066 -0.235078 0.94856 + outer loop + vertex 1.14811 0.94418 2.53654 + vertex 1.14823 0.948802 2.53765 + vertex 1.14315 0.943925 2.53758 + endloop + endfacet + facet normal 0.192597 -0.233357 0.953127 + outer loop + vertex 1.14823 0.948802 2.53765 + vertex 1.15336 0.953742 2.53783 + vertex 1.14832 0.953613 2.53881 + endloop + endfacet + facet normal 0.187582 -0.240835 0.952266 + outer loop + vertex 1.15845 0.958666 2.53802 + vertex 1.16346 0.963625 2.53829 + vertex 1.15856 0.96346 2.53921 + endloop + endfacet + facet normal 0.187495 -0.246995 0.950705 + outer loop + vertex 1.16346 0.963625 2.53829 + vertex 1.16352 0.968299 2.53949 + vertex 1.15856 0.96346 2.53921 + endloop + endfacet + facet normal 0.198183 -0.256638 0.945971 + outer loop + vertex 1.16884 0.960377 2.53634 + vertex 1.1685 0.964065 2.53741 + vertex 1.16369 0.958808 2.53699 + endloop + endfacet + facet normal 0.178009 -0.247315 0.952443 + outer loop + vertex 1.16346 0.963625 2.53829 + vertex 1.16845 0.968661 2.53866 + vertex 1.16352 0.968299 2.53949 + endloop + endfacet + facet normal 0.191789 -0.268712 0.943934 + outer loop + vertex 1.17336 0.964376 2.53651 + vertex 1.17346 0.968831 2.53776 + vertex 1.1685 0.964065 2.53741 + endloop + endfacet + facet normal 0.184959 -0.249175 0.950632 + outer loop + vertex 1.16845 0.968661 2.53866 + vertex 1.17348 0.973657 2.53899 + vertex 1.16848 0.973728 2.53999 + endloop + endfacet + facet normal 0.180593 -0.247702 0.951856 + outer loop + vertex 1.17848 0.968932 2.53684 + vertex 1.17829 0.973487 2.53806 + vertex 1.17346 0.968831 2.53776 + endloop + endfacet + facet normal 0.171093 -0.154089 0.973131 + outer loop + vertex 1.18337 0.973638 2.53719 + vertex 1.18192 0.977402 2.53804 + vertex 1.17829 0.973487 2.53806 + endloop + endfacet + facet normal 0.197612 0.0168977 0.980135 + outer loop + vertex 1.18266 0.982437 2.5378 + vertex 1.18192 0.977402 2.53804 + vertex 1.18628 0.978856 2.53714 + endloop + endfacet + facet normal 0.230764 -0.212822 0.94945 + outer loop + vertex 1.17348 0.973657 2.53899 + vertex 1.1781 0.978363 2.53892 + vertex 1.17364 0.978891 2.54013 + endloop + endfacet + facet normal 0.187095 -0.213576 0.958843 + outer loop + vertex 1.17364 0.978891 2.54013 + vertex 1.16848 0.973728 2.53999 + vertex 1.17348 0.973657 2.53899 + endloop + endfacet + facet normal 0.170283 -0.225026 0.959358 + outer loop + vertex 1.17006 0.978075 2.54083 + vertex 1.16897 0.980374 2.54156 + vertex 1.16637 0.976299 2.54106 + endloop + endfacet + facet normal 0.177361 -0.229267 0.957068 + outer loop + vertex 1.16897 0.980374 2.54156 + vertex 1.16396 0.978762 2.5421 + vertex 1.16637 0.976299 2.54106 + endloop + endfacet + facet normal 0.178071 -0.249459 0.951872 + outer loop + vertex 1.16845 0.968661 2.53866 + vertex 1.16848 0.973728 2.53999 + vertex 1.16352 0.968299 2.53949 + endloop + endfacet + facet normal 0.181026 -0.240537 0.95361 + outer loop + vertex 1.15856 0.96346 2.53921 + vertex 1.16352 0.968299 2.53949 + vertex 1.15891 0.968123 2.54032 + endloop + endfacet + facet normal 0.185818 -0.242661 0.952149 + outer loop + vertex 1.16025 0.971803 2.541 + vertex 1.15733 0.970051 2.54112 + vertex 1.15891 0.968123 2.54032 + endloop + endfacet + facet normal 0.171881 -0.250391 0.952765 + outer loop + vertex 1.16261 0.974593 2.54129 + vertex 1.16341 0.972176 2.54051 + vertex 1.16637 0.976299 2.54106 + endloop + endfacet + facet normal 0.19006 -0.249931 0.949427 + outer loop + vertex 1.16025 0.971803 2.541 + vertex 1.15857 0.973799 2.54186 + vertex 1.15733 0.970051 2.54112 + endloop + endfacet + facet normal 0.167012 -0.23916 0.956509 + outer loop + vertex 1.16637 0.976299 2.54106 + vertex 1.16396 0.978762 2.5421 + vertex 1.16261 0.974593 2.54129 + endloop + endfacet + facet normal 0.184517 -0.243128 0.952283 + outer loop + vertex 1.15857 0.973799 2.54186 + vertex 1.15862 0.978643 2.54309 + vertex 1.1534 0.973693 2.54283 + endloop + endfacet + facet normal 0.197321 -0.229042 0.953207 + outer loop + vertex 1.15862 0.978643 2.54309 + vertex 1.16353 0.983646 2.54327 + vertex 1.15867 0.983549 2.54426 + endloop + endfacet + facet normal 0.160248 -0.170981 0.972155 + outer loop + vertex 1.16897 0.980374 2.54156 + vertex 1.16818 0.983955 2.54232 + vertex 1.16396 0.978762 2.5421 + endloop + endfacet + facet normal 0.290944 -0.122803 0.948826 + outer loop + vertex 1.16818 0.983955 2.54232 + vertex 1.17178 0.988182 2.54176 + vertex 1.16764 0.988446 2.54306 + endloop + endfacet + facet normal 0.3187 -0.25589 0.912661 + outer loop + vertex 1.16031 0.992411 2.54599 + vertex 1.15902 0.988482 2.54533 + vertex 1.16363 0.993351 2.54509 + endloop + endfacet + facet normal 0.310831 -0.215771 0.925649 + outer loop + vertex 1.16363 0.993351 2.54509 + vertex 1.16199 0.99528 2.54609 + vertex 1.16031 0.992411 2.54599 + endloop + endfacet + facet normal 0.21738 -0.162471 0.96247 + outer loop + vertex 1.16199 0.99528 2.54609 + vertex 1.15828 0.99407 2.54673 + vertex 1.16031 0.992411 2.54599 + endloop + endfacet + facet normal 0.191531 -0.19401 0.962121 + outer loop + vertex 1.16031 0.992411 2.54599 + vertex 1.15828 0.99407 2.54673 + vertex 1.15737 0.990343 2.54615 + endloop + endfacet + facet normal 0.16402 -0.188247 0.968329 + outer loop + vertex 1.15737 0.990343 2.54615 + vertex 1.15828 0.99407 2.54673 + vertex 1.15332 0.98914 2.54661 + endloop + endfacet + facet normal 0.173922 -0.225238 0.958655 + outer loop + vertex 1.15737 0.990343 2.54615 + vertex 1.15332 0.98914 2.54661 + vertex 1.15515 0.987383 2.54586 + endloop + endfacet + facet normal 0.198205 -0.242532 0.949681 + outer loop + vertex 1.15902 0.988482 2.54533 + vertex 1.15737 0.990343 2.54615 + vertex 1.15515 0.987383 2.54586 + endloop + endfacet + facet normal 0.169333 -0.229909 0.958368 + outer loop + vertex 1.15515 0.987383 2.54586 + vertex 1.15332 0.98914 2.54661 + vertex 1.15203 0.98537 2.54593 + endloop + endfacet + facet normal 0.191057 -0.215193 0.9577 + outer loop + vertex 1.15828 0.99407 2.54673 + vertex 1.15344 0.993784 2.54763 + vertex 1.15332 0.98914 2.54661 + endloop + endfacet + facet normal 0.20443 -0.117891 0.971756 + outer loop + vertex 1.16199 0.99528 2.54609 + vertex 1.16185 0.99844 2.5465 + vertex 1.15828 0.99407 2.54673 + endloop + endfacet + facet normal 0.25705 -0.161861 0.952747 + outer loop + vertex 1.16185 0.99844 2.5465 + vertex 1.158 0.998648 2.54758 + vertex 1.15828 0.99407 2.54673 + endloop + endfacet + facet normal 0.214641 -0.22792 0.949727 + outer loop + vertex 1.16031 0.992411 2.54599 + vertex 1.15737 0.990343 2.54615 + vertex 1.15902 0.988482 2.54533 + endloop + endfacet + facet normal 0.198154 -0.193842 0.960812 + outer loop + vertex 1.16353 0.983646 2.54327 + vertex 1.16338 0.988396 2.54426 + vertex 1.15867 0.983549 2.54426 + endloop + endfacet + facet normal 0.197845 -0.241048 0.950133 + outer loop + vertex 1.15515 0.987383 2.54586 + vertex 1.15379 0.98351 2.54516 + vertex 1.15902 0.988482 2.54533 + endloop + endfacet + facet normal 0.178402 -0.229717 0.956767 + outer loop + vertex 1.15862 0.978643 2.54309 + vertex 1.15867 0.983549 2.54426 + vertex 1.15348 0.978578 2.54403 + endloop + endfacet + facet normal 0.175043 -0.230568 0.957183 + outer loop + vertex 1.14827 0.97362 2.54379 + vertex 1.15348 0.978578 2.54403 + vertex 1.14852 0.978659 2.54496 + endloop + endfacet + facet normal 0.171288 -0.232979 0.957278 + outer loop + vertex 1.15515 0.987383 2.54586 + vertex 1.15203 0.98537 2.54593 + vertex 1.15379 0.98351 2.54516 + endloop + endfacet + facet normal 0.177205 -0.232243 0.956379 + outer loop + vertex 1.15203 0.98537 2.54593 + vertex 1.15332 0.98914 2.54661 + vertex 1.14818 0.984372 2.5464 + endloop + endfacet + facet normal 0.177721 -0.23279 0.956151 + outer loop + vertex 1.15332 0.98914 2.54661 + vertex 1.14833 0.988807 2.54745 + vertex 1.14818 0.984372 2.5464 + endloop + endfacet + facet normal 0.177525 -0.228044 0.95733 + outer loop + vertex 1.14982 0.982525 2.54563 + vertex 1.14694 0.980767 2.54575 + vertex 1.14852 0.978659 2.54496 + endloop + endfacet + facet normal 0.182653 -0.230611 0.955749 + outer loop + vertex 1.14852 0.978659 2.54496 + vertex 1.14316 0.973684 2.54478 + vertex 1.14827 0.97362 2.54379 + endloop + endfacet + facet normal 0.188054 -0.230895 0.954633 + outer loop + vertex 1.14465 0.977966 2.54552 + vertex 1.14377 0.980333 2.54627 + vertex 1.141 0.976295 2.54584 + endloop + endfacet + facet normal 0.190216 -0.232295 0.953864 + outer loop + vertex 1.14377 0.980333 2.54627 + vertex 1.13863 0.97872 2.5469 + vertex 1.141 0.976295 2.54584 + endloop + endfacet + facet normal 0.188706 -0.2316 0.954333 + outer loop + vertex 1.14323 0.968608 2.54353 + vertex 1.14316 0.973684 2.54478 + vertex 1.13843 0.968361 2.54442 + endloop + endfacet + facet normal 0.195601 -0.213405 0.957183 + outer loop + vertex 1.13374 0.963735 2.54435 + vertex 1.13843 0.968361 2.54442 + vertex 1.13406 0.968316 2.54531 + endloop + endfacet + facet normal 0.221608 -0.214016 0.951361 + outer loop + vertex 1.13406 0.968316 2.54531 + vertex 1.12998 0.964216 2.54533 + vertex 1.13374 0.963735 2.54435 + endloop + endfacet + facet normal 0.227327 -0.180716 0.956903 + outer loop + vertex 1.12863 0.959239 2.54471 + vertex 1.13374 0.963735 2.54435 + vertex 1.12998 0.964216 2.54533 + endloop + endfacet + facet normal 0.210645 -0.203076 0.956237 + outer loop + vertex 1.13046 0.967379 2.5459 + vertex 1.12998 0.964216 2.54533 + vertex 1.13406 0.968316 2.54531 + endloop + endfacet + facet normal 0.214767 -0.222222 0.951048 + outer loop + vertex 1.13406 0.968316 2.54531 + vertex 1.13234 0.970111 2.54611 + vertex 1.13046 0.967379 2.5459 + endloop + endfacet + facet normal 0.258132 -0.250666 0.933024 + outer loop + vertex 1.13234 0.970111 2.54611 + vertex 1.12841 0.96898 2.5469 + vertex 1.13046 0.967379 2.5459 + endloop + endfacet + facet normal 0.275827 -0.228483 0.933657 + outer loop + vertex 1.13046 0.967379 2.5459 + vertex 1.12841 0.96898 2.5469 + vertex 1.12757 0.965149 2.54621 + endloop + endfacet + facet normal 0.257836 -0.249337 0.933462 + outer loop + vertex 1.13234 0.970111 2.54611 + vertex 1.13339 0.973814 2.54681 + vertex 1.12841 0.96898 2.5469 + endloop + endfacet + facet normal 0.226951 -0.217252 0.949365 + outer loop + vertex 1.13339 0.973814 2.54681 + vertex 1.12841 0.973772 2.54799 + vertex 1.12841 0.96898 2.5469 + endloop + endfacet + facet normal 0.261147 -0.208235 0.942571 + outer loop + vertex 1.13046 0.967379 2.5459 + vertex 1.12757 0.965149 2.54621 + vertex 1.12998 0.964216 2.54533 + endloop + endfacet + facet normal 0.207129 -0.229529 0.951007 + outer loop + vertex 1.13516 0.971881 2.54593 + vertex 1.13234 0.970111 2.54611 + vertex 1.13406 0.968316 2.54531 + endloop + endfacet + facet normal 0.191849 -0.235 0.952874 + outer loop + vertex 1.13735 0.974633 2.54616 + vertex 1.13824 0.972249 2.54539 + vertex 1.141 0.976295 2.54584 + endloop + endfacet + facet normal 0.212927 -0.23915 0.947349 + outer loop + vertex 1.13516 0.971881 2.54593 + vertex 1.13339 0.973814 2.54681 + vertex 1.13234 0.970111 2.54611 + endloop + endfacet + facet normal 0.190555 -0.231969 0.953876 + outer loop + vertex 1.141 0.976295 2.54584 + vertex 1.13863 0.97872 2.5469 + vertex 1.13735 0.974633 2.54616 + endloop + endfacet + facet normal 0.226619 -0.224751 0.947697 + outer loop + vertex 1.13339 0.973814 2.54681 + vertex 1.13335 0.978617 2.54796 + vertex 1.12841 0.973772 2.54799 + endloop + endfacet + facet normal 0.208558 -0.206311 0.956002 + outer loop + vertex 1.12841 0.973772 2.54799 + vertex 1.13335 0.978617 2.54796 + vertex 1.12846 0.978618 2.54903 + endloop + endfacet + facet normal 0.248992 -0.204735 0.946618 + outer loop + vertex 1.12841 0.973772 2.54799 + vertex 1.12846 0.978618 2.54903 + vertex 1.12386 0.973944 2.54923 + endloop + endfacet + facet normal 0.251201 -0.179225 0.951197 + outer loop + vertex 1.12358 0.969012 2.54837 + vertex 1.12841 0.973772 2.54799 + vertex 1.12386 0.973944 2.54923 + endloop + endfacet + facet normal 0.284044 -0.213874 0.934654 + outer loop + vertex 1.12841 0.96898 2.5469 + vertex 1.12841 0.973772 2.54799 + vertex 1.12358 0.969012 2.54837 + endloop + endfacet + facet normal 0.227741 -0.18338 0.956298 + outer loop + vertex 1.12386 0.973944 2.54923 + vertex 1.12846 0.978618 2.54903 + vertex 1.12389 0.978615 2.55012 + endloop + endfacet + facet normal 0.22671 -0.206123 0.951901 + outer loop + vertex 1.12866 0.983497 2.55004 + vertex 1.12389 0.978615 2.55012 + vertex 1.12846 0.978618 2.54903 + endloop + endfacet + facet normal 0.19653 -0.206316 0.958546 + outer loop + vertex 1.12846 0.978618 2.54903 + vertex 1.13339 0.983521 2.54907 + vertex 1.12866 0.983497 2.55004 + endloop + endfacet + facet normal 0.19612 -0.216951 0.956279 + outer loop + vertex 1.13376 0.988476 2.55012 + vertex 1.12866 0.983497 2.55004 + vertex 1.13339 0.983521 2.54907 + endloop + endfacet + facet normal 0.182991 -0.216554 0.958968 + outer loop + vertex 1.13339 0.983521 2.54907 + vertex 1.13848 0.988469 2.54922 + vertex 1.13376 0.988476 2.55012 + endloop + endfacet + facet normal 0.18298 -0.216804 0.958913 + outer loop + vertex 1.13895 0.993395 2.55024 + vertex 1.13376 0.988476 2.55012 + vertex 1.13848 0.988469 2.54922 + endloop + endfacet + facet normal 0.173977 -0.216312 0.960698 + outer loop + vertex 1.13848 0.988469 2.54922 + vertex 1.14366 0.993396 2.54939 + vertex 1.13895 0.993395 2.55024 + endloop + endfacet + facet normal 0.173891 -0.218484 0.960222 + outer loop + vertex 1.14411 0.998154 2.55039 + vertex 1.13895 0.993395 2.55024 + vertex 1.14366 0.993396 2.54939 + endloop + endfacet + facet normal 0.167056 -0.211169 0.963068 + outer loop + vertex 1.1403 0.997239 2.55085 + vertex 1.13895 0.993395 2.55024 + vertex 1.14411 0.998154 2.55039 + endloop + endfacet + facet normal 0.169371 -0.222269 0.960161 + outer loop + vertex 1.14411 0.998154 2.55039 + vertex 1.14248 1.00008 2.55112 + vertex 1.1403 0.997239 2.55085 + endloop + endfacet + facet normal 0.181496 -0.231168 0.955835 + outer loop + vertex 1.14248 1.00008 2.55112 + vertex 1.13841 0.998982 2.55163 + vertex 1.1403 0.997239 2.55085 + endloop + endfacet + facet normal 0.185653 -0.226783 0.956087 + outer loop + vertex 1.1403 0.997239 2.55085 + vertex 1.13841 0.998982 2.55163 + vertex 1.13724 0.995262 2.55098 + endloop + endfacet + facet normal 0.19144 -0.228342 0.954574 + outer loop + vertex 1.13724 0.995262 2.55098 + vertex 1.13841 0.998982 2.55163 + vertex 1.1332 0.994049 2.5515 + endloop + endfacet + facet normal 0.189107 -0.219488 0.957112 + outer loop + vertex 1.13724 0.995262 2.55098 + vertex 1.1332 0.994049 2.5515 + vertex 1.13507 0.992366 2.55074 + endloop + endfacet + facet normal 0.179837 -0.212817 0.9604 + outer loop + vertex 1.13895 0.993395 2.55024 + vertex 1.13724 0.995262 2.55098 + vertex 1.13507 0.992366 2.55074 + endloop + endfacet + facet normal 0.189972 -0.218548 0.957156 + outer loop + vertex 1.13507 0.992366 2.55074 + vertex 1.1332 0.994049 2.5515 + vertex 1.13203 0.990325 2.55088 + endloop + endfacet + facet normal 0.188466 -0.216246 0.957976 + outer loop + vertex 1.13507 0.992366 2.55074 + vertex 1.13203 0.990325 2.55088 + vertex 1.13376 0.988476 2.55012 + endloop + endfacet + facet normal 0.189351 -0.215424 0.957987 + outer loop + vertex 1.13376 0.988476 2.55012 + vertex 1.13203 0.990325 2.55088 + vertex 1.12988 0.987393 2.55064 + endloop + endfacet + facet normal 0.206811 -0.227717 0.951511 + outer loop + vertex 1.13203 0.990325 2.55088 + vertex 1.12805 0.989095 2.55145 + vertex 1.12988 0.987393 2.55064 + endloop + endfacet + facet normal 0.211759 -0.222477 0.951663 + outer loop + vertex 1.12988 0.987393 2.55064 + vertex 1.12805 0.989095 2.55145 + vertex 1.12687 0.985321 2.55083 + endloop + endfacet + facet normal 0.205592 -0.213206 0.955131 + outer loop + vertex 1.12988 0.987393 2.55064 + vertex 1.12687 0.985321 2.55083 + vertex 1.12866 0.983497 2.55004 + endloop + endfacet + facet normal 0.212314 -0.206611 0.95511 + outer loop + vertex 1.12866 0.983497 2.55004 + vertex 1.12687 0.985321 2.55083 + vertex 1.12481 0.982382 2.55065 + endloop + endfacet + facet normal 0.254446 -0.235027 0.938094 + outer loop + vertex 1.12687 0.985321 2.55083 + vertex 1.12302 0.984153 2.55158 + vertex 1.12481 0.982382 2.55065 + endloop + endfacet + facet normal 0.269322 -0.219752 0.937643 + outer loop + vertex 1.12481 0.982382 2.55065 + vertex 1.12302 0.984153 2.55158 + vertex 1.12196 0.980324 2.55099 + endloop + endfacet + facet normal 0.253803 -0.196701 0.947044 + outer loop + vertex 1.12481 0.982382 2.55065 + vertex 1.12196 0.980324 2.55099 + vertex 1.12389 0.978615 2.55012 + endloop + endfacet + facet normal 0.2541 -0.233601 0.938544 + outer loop + vertex 1.12687 0.985321 2.55083 + vertex 1.12805 0.989095 2.55145 + vertex 1.12302 0.984153 2.55158 + endloop + endfacet + facet normal 0.226556 -0.205224 0.952132 + outer loop + vertex 1.12805 0.989095 2.55145 + vertex 1.12319 0.98889 2.55256 + vertex 1.12302 0.984153 2.55158 + endloop + endfacet + facet normal 0.226504 -0.211944 0.950671 + outer loop + vertex 1.12805 0.989095 2.55145 + vertex 1.12816 0.993709 2.55245 + vertex 1.12319 0.98889 2.55256 + endloop + endfacet + facet normal 0.208171 -0.19283 0.958896 + outer loop + vertex 1.12319 0.98889 2.55256 + vertex 1.12816 0.993709 2.55245 + vertex 1.12331 0.993713 2.55351 + endloop + endfacet + facet normal 0.249839 -0.191947 0.949071 + outer loop + vertex 1.12319 0.98889 2.55256 + vertex 1.12331 0.993713 2.55351 + vertex 1.11864 0.989146 2.55381 + endloop + endfacet + facet normal 0.252093 -0.169654 0.952716 + outer loop + vertex 1.11839 0.984209 2.553 + vertex 1.12319 0.98889 2.55256 + vertex 1.11864 0.989146 2.55381 + endloop + endfacet + facet normal 0.229178 -0.17022 0.958386 + outer loop + vertex 1.11864 0.989146 2.55381 + vertex 1.12331 0.993713 2.55351 + vertex 1.11857 0.994134 2.55471 + endloop + endfacet + facet normal 0.225897 -0.195498 0.954333 + outer loop + vertex 1.12331 0.993713 2.55351 + vertex 1.12369 0.99862 2.55442 + vertex 1.11857 0.994134 2.55471 + endloop + endfacet + facet normal 0.206993 -0.173355 0.962862 + outer loop + vertex 1.11857 0.994134 2.55471 + vertex 1.12369 0.99862 2.55442 + vertex 1.12 0.999143 2.55531 + endloop + endfacet + facet normal 0.248693 -0.183851 0.950974 + outer loop + vertex 1.11857 0.994134 2.55471 + vertex 1.12 0.999143 2.55531 + vertex 1.11591 0.996392 2.55585 + endloop + endfacet + facet normal 0.244931 -0.177854 0.953088 + outer loop + vertex 1.12 0.999143 2.55531 + vertex 1.11759 1.00011 2.55611 + vertex 1.11591 0.996392 2.55585 + endloop + endfacet + facet normal 0.295947 -0.19951 0.934136 + outer loop + vertex 1.11759 1.00011 2.55611 + vertex 1.11336 0.998779 2.55716 + vertex 1.11591 0.996392 2.55585 + endloop + endfacet + facet normal 0.301213 -0.221465 0.927482 + outer loop + vertex 1.11759 1.00011 2.55611 + vertex 1.11842 1.00394 2.55675 + vertex 1.11336 0.998779 2.55716 + endloop + endfacet + facet normal 0.236593 -0.197126 0.951402 + outer loop + vertex 1.12049 1.00232 2.55584 + vertex 1.11759 1.00011 2.55611 + vertex 1.12 0.999143 2.55531 + endloop + endfacet + facet normal 0.191803 -0.191996 0.96247 + outer loop + vertex 1.12049 1.00232 2.55584 + vertex 1.12 0.999143 2.55531 + vertex 1.12408 1.00323 2.55531 + endloop + endfacet + facet normal 0.195578 -0.209366 0.958079 + outer loop + vertex 1.12408 1.00323 2.55531 + vertex 1.12237 1.00502 2.55605 + vertex 1.12049 1.00232 2.55584 + endloop + endfacet + facet normal 0.231587 -0.233285 0.944429 + outer loop + vertex 1.12237 1.00502 2.55605 + vertex 1.11842 1.00394 2.55675 + vertex 1.12049 1.00232 2.55584 + endloop + endfacet + facet normal 0.231423 -0.232538 0.944653 + outer loop + vertex 1.12237 1.00502 2.55605 + vertex 1.12342 1.0087 2.5567 + vertex 1.11842 1.00394 2.55675 + endloop + endfacet + facet normal 0.202709 -0.202164 0.958143 + outer loop + vertex 1.12342 1.0087 2.5567 + vertex 1.11838 1.00876 2.55778 + vertex 1.11842 1.00394 2.55675 + endloop + endfacet + facet normal 0.252621 -0.199262 0.946825 + outer loop + vertex 1.11842 1.00394 2.55675 + vertex 1.11838 1.00876 2.55778 + vertex 1.11349 1.00414 2.55811 + endloop + endfacet + facet normal 0.25482 -0.174086 0.951189 + outer loop + vertex 1.11842 1.00394 2.55675 + vertex 1.11349 1.00414 2.55811 + vertex 1.11336 0.998779 2.55716 + endloop + endfacet + facet normal 0.222499 -0.166459 0.960617 + outer loop + vertex 1.11349 1.00414 2.55811 + vertex 1.11838 1.00876 2.55778 + vertex 1.11369 1.00917 2.55893 + endloop + endfacet + facet normal 0.218807 -0.195784 0.955925 + outer loop + vertex 1.11838 1.00876 2.55778 + vertex 1.11831 1.01371 2.55881 + vertex 1.11369 1.00917 2.55893 + endloop + endfacet + facet normal 0.200912 -0.177352 0.963421 + outer loop + vertex 1.11369 1.00917 2.55893 + vertex 1.11831 1.01371 2.55881 + vertex 1.11349 1.01402 2.55987 + endloop + endfacet + facet normal 0.185723 -0.197565 0.962536 + outer loop + vertex 1.11838 1.00876 2.55778 + vertex 1.12333 1.0135 2.5578 + vertex 1.11831 1.01371 2.55881 + endloop + endfacet + facet normal 0.184438 -0.213253 0.95943 + outer loop + vertex 1.12333 1.0135 2.5578 + vertex 1.12326 1.01848 2.55892 + vertex 1.11831 1.01371 2.55881 + endloop + endfacet + facet normal 0.1743 -0.202827 0.963577 + outer loop + vertex 1.11831 1.01371 2.55881 + vertex 1.12326 1.01848 2.55892 + vertex 1.11835 1.01883 2.55988 + endloop + endfacet + facet normal 0.247948 -0.212864 0.945098 + outer loop + vertex 1.12049 1.00232 2.55584 + vertex 1.11842 1.00394 2.55675 + vertex 1.11759 1.00011 2.55611 + endloop + endfacet + facet normal 0.201849 -0.202022 0.958355 + outer loop + vertex 1.12408 1.00323 2.55531 + vertex 1.12 0.999143 2.55531 + vertex 1.12369 0.99862 2.55442 + endloop + endfacet + facet normal 0.19355 -0.194321 0.961654 + outer loop + vertex 1.12331 0.993713 2.55351 + vertex 1.12826 0.998478 2.55347 + vertex 1.12369 0.99862 2.55442 + endloop + endfacet + facet normal 0.192163 -0.213529 0.957851 + outer loop + vertex 1.12826 0.998478 2.55347 + vertex 1.12842 1.00325 2.5545 + vertex 1.12369 0.99862 2.55442 + endloop + endfacet + facet normal 0.175879 -0.213641 0.96095 + outer loop + vertex 1.12826 0.998478 2.55347 + vertex 1.13327 1.00349 2.55367 + vertex 1.12842 1.00325 2.5545 + endloop + endfacet + facet normal 0.18536 -0.222971 0.95704 + outer loop + vertex 1.13326 0.998655 2.55255 + vertex 1.13327 1.00349 2.55367 + vertex 1.12826 0.998478 2.55347 + endloop + endfacet + facet normal 0.185444 -0.209308 0.960105 + outer loop + vertex 1.12816 0.993709 2.55245 + vertex 1.13326 0.998655 2.55255 + vertex 1.12826 0.998478 2.55347 + endloop + endfacet + facet normal 0.195928 -0.220028 0.955615 + outer loop + vertex 1.1332 0.994049 2.5515 + vertex 1.13326 0.998655 2.55255 + vertex 1.12816 0.993709 2.55245 + endloop + endfacet + facet normal 0.17475 -0.223377 0.95894 + outer loop + vertex 1.13326 0.998655 2.55255 + vertex 1.13843 1.00368 2.55277 + vertex 1.13327 1.00349 2.55367 + endloop + endfacet + facet normal 0.17472 -0.23018 0.957335 + outer loop + vertex 1.13843 1.00368 2.55277 + vertex 1.13844 1.0086 2.55395 + vertex 1.13327 1.00349 2.55367 + endloop + endfacet + facet normal 0.168097 -0.223634 0.960068 + outer loop + vertex 1.13327 1.00349 2.55367 + vertex 1.13844 1.0086 2.55395 + vertex 1.13325 1.0086 2.55486 + endloop + endfacet + facet normal 0.173314 -0.230236 0.957577 + outer loop + vertex 1.13843 1.00368 2.55277 + vertex 1.14362 1.0087 2.55304 + vertex 1.13844 1.0086 2.55395 + endloop + endfacet + facet normal 0.17353 -0.22026 0.959882 + outer loop + vertex 1.14362 1.0087 2.55304 + vertex 1.14364 1.01363 2.55417 + vertex 1.13844 1.0086 2.55395 + endloop + endfacet + facet normal 0.184108 -0.232842 0.954929 + outer loop + vertex 1.13841 0.998982 2.55163 + vertex 1.13843 1.00368 2.55277 + vertex 1.13326 0.998655 2.55255 + endloop + endfacet + facet normal 0.175838 -0.233168 0.956407 + outer loop + vertex 1.14367 1.00386 2.55185 + vertex 1.13843 1.00368 2.55277 + vertex 1.13841 0.998982 2.55163 + endloop + endfacet + facet normal 0.207463 -0.208834 0.955692 + outer loop + vertex 1.12816 0.993709 2.55245 + vertex 1.12826 0.998478 2.55347 + vertex 1.12331 0.993713 2.55351 + endloop + endfacet + facet normal 0.195754 -0.212669 0.957315 + outer loop + vertex 1.1332 0.994049 2.5515 + vertex 1.12816 0.993709 2.55245 + vertex 1.12805 0.989095 2.55145 + endloop + endfacet + facet normal 0.205485 -0.222748 0.952974 + outer loop + vertex 1.13203 0.990325 2.55088 + vertex 1.1332 0.994049 2.5515 + vertex 1.12805 0.989095 2.55145 + endloop + endfacet + facet normal 0.183852 -0.220418 0.957922 + outer loop + vertex 1.13841 0.998982 2.55163 + vertex 1.13326 0.998655 2.55255 + vertex 1.1332 0.994049 2.5515 + endloop + endfacet + facet normal 0.183975 -0.241767 0.952734 + outer loop + vertex 1.14248 1.00008 2.55112 + vertex 1.14367 1.00386 2.55185 + vertex 1.13841 0.998982 2.55163 + endloop + endfacet + facet normal 0.177924 -0.214557 0.960369 + outer loop + vertex 1.1403 0.997239 2.55085 + vertex 1.13724 0.995262 2.55098 + vertex 1.13895 0.993395 2.55024 + endloop + endfacet + facet normal 0.179199 -0.221723 0.958502 + outer loop + vertex 1.14335 0.988543 2.54833 + vertex 1.14366 0.993396 2.54939 + vertex 1.13848 0.988469 2.54922 + endloop + endfacet + facet normal 0.180051 -0.21374 0.960155 + outer loop + vertex 1.13507 0.992366 2.55074 + vertex 1.13376 0.988476 2.55012 + vertex 1.13895 0.993395 2.55024 + endloop + endfacet + facet normal 0.188286 -0.221932 0.95671 + outer loop + vertex 1.13831 0.983571 2.54812 + vertex 1.13848 0.988469 2.54922 + vertex 1.13339 0.983521 2.54907 + endloop + endfacet + facet normal 0.187619 -0.208305 0.9599 + outer loop + vertex 1.12988 0.987393 2.55064 + vertex 1.12866 0.983497 2.55004 + vertex 1.13376 0.988476 2.55012 + endloop + endfacet + facet normal 0.2075 -0.18726 0.960144 + outer loop + vertex 1.12481 0.982382 2.55065 + vertex 1.12389 0.978615 2.55012 + vertex 1.12866 0.983497 2.55004 + endloop + endfacet + facet normal 0.208023 -0.21782 0.953562 + outer loop + vertex 1.13335 0.978617 2.54796 + vertex 1.13339 0.983521 2.54907 + vertex 1.12846 0.978618 2.54903 + endloop + endfacet + facet normal 0.188399 -0.218526 0.957472 + outer loop + vertex 1.13335 0.978617 2.54796 + vertex 1.13831 0.983571 2.54812 + vertex 1.13339 0.983521 2.54907 + endloop + endfacet + facet normal 0.190013 -0.231564 0.954082 + outer loop + vertex 1.14377 0.980333 2.54627 + vertex 1.14335 0.983976 2.54724 + vertex 1.13863 0.97872 2.5469 + endloop + endfacet + facet normal 0.179191 -0.222016 0.958436 + outer loop + vertex 1.13831 0.983571 2.54812 + vertex 1.14335 0.988543 2.54833 + vertex 1.13848 0.988469 2.54922 + endloop + endfacet + facet normal 0.184211 -0.232722 0.954938 + outer loop + vertex 1.14818 0.984372 2.5464 + vertex 1.14833 0.988807 2.54745 + vertex 1.14335 0.983976 2.54724 + endloop + endfacet + facet normal 0.177568 -0.221687 0.958814 + outer loop + vertex 1.14335 0.988543 2.54833 + vertex 1.14851 0.993532 2.54852 + vertex 1.14366 0.993396 2.54939 + endloop + endfacet + facet normal 0.177581 -0.220663 0.959048 + outer loop + vertex 1.14851 0.993532 2.54852 + vertex 1.14872 0.998333 2.54959 + vertex 1.14366 0.993396 2.54939 + endloop + endfacet + facet normal 0.177265 -0.215401 0.960302 + outer loop + vertex 1.15332 0.98914 2.54661 + vertex 1.15344 0.993784 2.54763 + vertex 1.14833 0.988807 2.54745 + endloop + endfacet + facet normal 0.201529 -0.220661 0.954303 + outer loop + vertex 1.14851 0.993532 2.54852 + vertex 1.15346 0.998638 2.54866 + vertex 1.14872 0.998333 2.54959 + endloop + endfacet + facet normal 0.190069 -0.168578 0.967189 + outer loop + vertex 1.15828 0.99407 2.54673 + vertex 1.158 0.998648 2.54758 + vertex 1.15344 0.993784 2.54763 + endloop + endfacet + facet normal 0.248886 -0.222519 0.942625 + outer loop + vertex 1.15438 1.00821 2.55066 + vertex 1.15285 1.00983 2.55144 + vertex 1.15123 1.00639 2.55106 + endloop + endfacet + facet normal 0.203665 -0.202907 0.957784 + outer loop + vertex 1.15285 1.00983 2.55144 + vertex 1.14881 1.00872 2.55207 + vertex 1.15123 1.00639 2.55106 + endloop + endfacet + facet normal 0.201464 -0.217164 0.955119 + outer loop + vertex 1.15346 0.998638 2.54866 + vertex 1.15331 1.0038 2.54986 + vertex 1.14872 0.998333 2.54959 + endloop + endfacet + facet normal 0.175507 -0.218571 0.959908 + outer loop + vertex 1.14366 0.993396 2.54939 + vertex 1.14872 0.998333 2.54959 + vertex 1.14411 0.998154 2.55039 + endloop + endfacet + facet normal 0.164931 -0.225971 0.96007 + outer loop + vertex 1.14547 1.00189 2.55104 + vertex 1.14248 1.00008 2.55112 + vertex 1.14411 0.998154 2.55039 + endloop + endfacet + facet normal 0.189215 -0.235675 0.953234 + outer loop + vertex 1.14776 1.00472 2.55133 + vertex 1.14862 1.0023 2.55056 + vertex 1.15123 1.00639 2.55106 + endloop + endfacet + facet normal 0.172552 -0.238737 0.955631 + outer loop + vertex 1.14547 1.00189 2.55104 + vertex 1.14367 1.00386 2.55185 + vertex 1.14248 1.00008 2.55112 + endloop + endfacet + facet normal 0.183657 -0.223459 0.957254 + outer loop + vertex 1.15123 1.00639 2.55106 + vertex 1.14881 1.00872 2.55207 + vertex 1.14776 1.00472 2.55133 + endloop + endfacet + facet normal 0.175841 -0.232788 0.956499 + outer loop + vertex 1.14367 1.00386 2.55185 + vertex 1.14362 1.0087 2.55304 + vertex 1.13843 1.00368 2.55277 + endloop + endfacet + facet normal 0.200039 -0.219249 0.954942 + outer loop + vertex 1.14362 1.0087 2.55304 + vertex 1.14845 1.01357 2.55315 + vertex 1.14364 1.01363 2.55417 + endloop + endfacet + facet normal 0.192929 -0.158038 0.968402 + outer loop + vertex 1.15285 1.00983 2.55144 + vertex 1.15268 1.01324 2.55203 + vertex 1.14881 1.00872 2.55207 + endloop + endfacet + facet normal 0.304893 -0.256037 0.917325 + outer loop + vertex 1.14522 1.02244 2.5559 + vertex 1.14397 1.01856 2.55523 + vertex 1.14876 1.02363 2.55505 + endloop + endfacet + facet normal 0.300766 -0.239506 0.923134 + outer loop + vertex 1.14876 1.02363 2.55505 + vertex 1.14702 1.02541 2.55608 + vertex 1.14522 1.02244 2.5559 + endloop + endfacet + facet normal 0.212391 -0.187891 0.958951 + outer loop + vertex 1.14702 1.02541 2.55608 + vertex 1.1432 1.02406 2.55667 + vertex 1.14522 1.02244 2.5559 + endloop + endfacet + facet normal 0.196224 -0.207745 0.9583 + outer loop + vertex 1.14522 1.02244 2.5559 + vertex 1.1432 1.02406 2.55667 + vertex 1.14225 1.02034 2.55605 + endloop + endfacet + facet normal 0.203535 -0.159607 0.96597 + outer loop + vertex 1.14702 1.02541 2.55608 + vertex 1.14705 1.02859 2.5566 + vertex 1.1432 1.02406 2.55667 + endloop + endfacet + facet normal 0.2318 -0.183873 0.955227 + outer loop + vertex 1.14705 1.02859 2.5566 + vertex 1.14306 1.02862 2.55758 + vertex 1.1432 1.02406 2.55667 + endloop + endfacet + facet normal 0.234016 -0.135418 0.962756 + outer loop + vertex 1.14705 1.02859 2.5566 + vertex 1.14731 1.03304 2.55717 + vertex 1.14306 1.02862 2.55758 + endloop + endfacet + facet normal 0.201887 -0.186128 0.96156 + outer loop + vertex 1.14845 1.01357 2.55315 + vertex 1.1485 1.01852 2.5541 + vertex 1.14364 1.01363 2.55417 + endloop + endfacet + facet normal 0.178866 -0.225679 0.957641 + outer loop + vertex 1.13844 1.0086 2.55395 + vertex 1.14364 1.01363 2.55417 + vertex 1.13873 1.01362 2.55508 + endloop + endfacet + facet normal 0.212904 -0.231889 0.949157 + outer loop + vertex 1.14522 1.02244 2.5559 + vertex 1.14225 1.02034 2.55605 + vertex 1.14397 1.01856 2.55523 + endloop + endfacet + facet normal 0.161395 -0.200242 0.966362 + outer loop + vertex 1.14225 1.02034 2.55605 + vertex 1.1432 1.02406 2.55667 + vertex 1.13836 1.01926 2.55648 + endloop + endfacet + facet normal 0.179036 -0.217743 0.959445 + outer loop + vertex 1.1432 1.02406 2.55667 + vertex 1.13833 1.02373 2.5575 + vertex 1.13836 1.01926 2.55648 + endloop + endfacet + facet normal 0.164292 -0.227571 0.959802 + outer loop + vertex 1.1401 1.01746 2.55576 + vertex 1.13715 1.01564 2.55583 + vertex 1.13873 1.01362 2.55508 + endloop + endfacet + facet normal 0.168024 -0.225508 0.959643 + outer loop + vertex 1.13873 1.01362 2.55508 + vertex 1.13325 1.0086 2.55486 + vertex 1.13844 1.0086 2.55395 + endloop + endfacet + facet normal 0.168016 -0.225338 0.959684 + outer loop + vertex 1.13479 1.01284 2.55558 + vertex 1.13391 1.01517 2.55628 + vertex 1.13107 1.01116 2.55583 + endloop + endfacet + facet normal 0.170464 -0.226978 0.958865 + outer loop + vertex 1.13391 1.01517 2.55628 + vertex 1.12869 1.01356 2.55682 + vertex 1.13107 1.01116 2.55583 + endloop + endfacet + facet normal 0.175962 -0.223285 0.958739 + outer loop + vertex 1.13327 1.00349 2.55367 + vertex 1.13325 1.0086 2.55486 + vertex 1.12842 1.00325 2.5545 + endloop + endfacet + facet normal 0.179868 -0.201062 0.962923 + outer loop + vertex 1.12369 0.99862 2.55442 + vertex 1.12842 1.00325 2.5545 + vertex 1.12408 1.00323 2.55531 + endloop + endfacet + facet normal 0.189146 -0.215458 0.95802 + outer loop + vertex 1.12519 1.00678 2.55589 + vertex 1.12237 1.00502 2.55605 + vertex 1.12408 1.00323 2.55531 + endloop + endfacet + facet normal 0.172735 -0.22179 0.959673 + outer loop + vertex 1.12739 1.0095 2.55611 + vertex 1.12827 1.00715 2.55541 + vertex 1.13107 1.01116 2.55583 + endloop + endfacet + facet normal 0.194121 -0.223706 0.95513 + outer loop + vertex 1.12519 1.00678 2.55589 + vertex 1.12342 1.0087 2.5567 + vertex 1.12237 1.00502 2.55605 + endloop + endfacet + facet normal 0.173638 -0.223902 0.959019 + outer loop + vertex 1.13107 1.01116 2.55583 + vertex 1.12869 1.01356 2.55682 + vertex 1.12739 1.0095 2.55611 + endloop + endfacet + facet normal 0.201995 -0.214577 0.955591 + outer loop + vertex 1.12342 1.0087 2.5567 + vertex 1.12333 1.0135 2.5578 + vertex 1.11838 1.00876 2.55778 + endloop + endfacet + facet normal 0.168683 -0.214079 0.962141 + outer loop + vertex 1.12333 1.0135 2.5578 + vertex 1.12832 1.01842 2.55802 + vertex 1.12326 1.01848 2.55892 + endloop + endfacet + facet normal 0.168405 -0.219658 0.960932 + outer loop + vertex 1.12832 1.01842 2.55802 + vertex 1.12836 1.02338 2.55914 + vertex 1.12326 1.01848 2.55892 + endloop + endfacet + facet normal 0.170369 -0.226639 0.958963 + outer loop + vertex 1.13391 1.01517 2.55628 + vertex 1.13345 1.01883 2.55722 + vertex 1.12869 1.01356 2.55682 + endloop + endfacet + facet normal 0.163545 -0.2198 0.961739 + outer loop + vertex 1.12832 1.01842 2.55802 + vertex 1.13333 1.02345 2.55831 + vertex 1.12836 1.02338 2.55914 + endloop + endfacet + facet normal 0.164736 -0.218394 0.961855 + outer loop + vertex 1.13836 1.01926 2.55648 + vertex 1.13833 1.02373 2.5575 + vertex 1.13345 1.01883 2.55722 + endloop + endfacet + facet normal 0.175689 -0.215365 0.960599 + outer loop + vertex 1.13333 1.02345 2.55831 + vertex 1.1384 1.02851 2.55852 + vertex 1.13356 1.02839 2.55938 + endloop + endfacet + facet normal 0.178066 -0.18758 0.965974 + outer loop + vertex 1.1432 1.02406 2.55667 + vertex 1.14306 1.02862 2.55758 + vertex 1.13833 1.02373 2.5575 + endloop + endfacet + facet normal 0.274659 -0.175987 0.945299 + outer loop + vertex 1.14306 1.02862 2.55758 + vertex 1.14731 1.03304 2.55717 + vertex 1.14325 1.03347 2.55843 + endloop + endfacet + facet normal 0.281447 -0.127991 0.951003 + outer loop + vertex 1.14731 1.03304 2.55717 + vertex 1.14752 1.03796 2.55777 + vertex 1.14325 1.03347 2.55843 + endloop + endfacet + facet normal 0.326944 -0.174491 0.928795 + outer loop + vertex 1.14325 1.03347 2.55843 + vertex 1.14752 1.03796 2.55777 + vertex 1.14358 1.03846 2.55925 + endloop + endfacet + facet normal 0.209372 -0.229769 0.950458 + outer loop + vertex 1.13547 1.03714 2.56098 + vertex 1.13407 1.0333 2.56037 + vertex 1.13929 1.03838 2.56044 + endloop + endfacet + facet normal 0.175875 -0.200504 0.963777 + outer loop + vertex 1.1384 1.02851 2.55852 + vertex 1.13875 1.03348 2.55949 + vertex 1.13356 1.02839 2.55938 + endloop + endfacet + facet normal 0.161926 -0.209989 0.964201 + outer loop + vertex 1.1301 1.03218 2.56079 + vertex 1.12875 1.02835 2.56018 + vertex 1.13407 1.0333 2.56037 + endloop + endfacet + facet normal 0.163643 -0.215279 0.962744 + outer loop + vertex 1.13333 1.02345 2.55831 + vertex 1.13356 1.02839 2.55938 + vertex 1.12836 1.02338 2.55914 + endloop + endfacet + facet normal 0.163537 -0.214683 0.962895 + outer loop + vertex 1.12326 1.01848 2.55892 + vertex 1.12836 1.02338 2.55914 + vertex 1.12356 1.02356 2.56 + endloop + endfacet + facet normal 0.158581 -0.208929 0.964988 + outer loop + vertex 1.1301 1.03218 2.56079 + vertex 1.12703 1.03021 2.56087 + vertex 1.12875 1.02835 2.56018 + endloop + endfacet + facet normal 0.163071 -0.211351 0.963711 + outer loop + vertex 1.12703 1.03021 2.56087 + vertex 1.12827 1.0339 2.56147 + vertex 1.1232 1.02921 2.56129 + endloop + endfacet + facet normal 0.159932 -0.208004 0.964964 + outer loop + vertex 1.12827 1.0339 2.56147 + vertex 1.12321 1.03358 2.56224 + vertex 1.1232 1.02921 2.56129 + endloop + endfacet + facet normal 0.164654 -0.212249 0.963244 + outer loop + vertex 1.12488 1.0274 2.56062 + vertex 1.12201 1.02565 2.56072 + vertex 1.12356 1.02356 2.56 + endloop + endfacet + facet normal 0.172965 -0.214863 0.961206 + outer loop + vertex 1.12356 1.02356 2.56 + vertex 1.11835 1.01883 2.55988 + vertex 1.12326 1.01848 2.55892 + endloop + endfacet + facet normal 0.177315 -0.212775 0.960878 + outer loop + vertex 1.11976 1.02291 2.56051 + vertex 1.11884 1.0252 2.56119 + vertex 1.11624 1.02132 2.56081 + endloop + endfacet + facet normal 0.197208 -0.225429 0.954092 + outer loop + vertex 1.11884 1.0252 2.56119 + vertex 1.11372 1.02357 2.56186 + vertex 1.11624 1.02132 2.56081 + endloop + endfacet + facet normal 0.19835 -0.202039 0.959082 + outer loop + vertex 1.11831 1.01371 2.55881 + vertex 1.11835 1.01883 2.55988 + vertex 1.11349 1.01402 2.55987 + endloop + endfacet + facet normal 0.210056 -0.218774 0.952898 + outer loop + vertex 1.11271 1.01948 2.56116 + vertex 1.1143 1.01797 2.56046 + vertex 1.11624 1.02132 2.56081 + endloop + endfacet + facet normal 0.292719 -0.18772 0.937591 + outer loop + vertex 1.10854 1.01846 2.5621 + vertex 1.10709 1.01341 2.56155 + vertex 1.11092 1.01606 2.56088 + endloop + endfacet + facet normal 0.207671 -0.213877 0.954531 + outer loop + vertex 1.11624 1.02132 2.56081 + vertex 1.11372 1.02357 2.56186 + vertex 1.11271 1.01948 2.56116 + endloop + endfacet + facet normal 0.205319 -0.173884 0.963124 + outer loop + vertex 1.10847 1.02369 2.56312 + vertex 1.11329 1.0285 2.56296 + vertex 1.10847 1.02881 2.56404 + endloop + endfacet + facet normal 0.256368 -0.171687 0.951209 + outer loop + vertex 1.10847 1.02369 2.56312 + vertex 1.10847 1.02881 2.56404 + vertex 1.10354 1.02423 2.56455 + endloop + endfacet + facet normal 0.232993 -0.145397 0.961548 + outer loop + vertex 1.10354 1.02423 2.56455 + vertex 1.10847 1.02881 2.56404 + vertex 1.10443 1.02952 2.56513 + endloop + endfacet + facet normal 0.226701 -0.175768 0.957973 + outer loop + vertex 1.10847 1.02881 2.56404 + vertex 1.10853 1.03391 2.56497 + vertex 1.10443 1.02952 2.56513 + endloop + endfacet + facet normal 0.20345 -0.192295 0.960016 + outer loop + vertex 1.11329 1.0285 2.56296 + vertex 1.11325 1.03351 2.56397 + vertex 1.10847 1.02881 2.56404 + endloop + endfacet + facet normal 0.188311 -0.176807 0.966063 + outer loop + vertex 1.10847 1.02881 2.56404 + vertex 1.11325 1.03351 2.56397 + vertex 1.10853 1.03391 2.56497 + endloop + endfacet + facet normal 0.191747 -0.206037 0.959574 + outer loop + vertex 1.11884 1.0252 2.56119 + vertex 1.11833 1.0288 2.56206 + vertex 1.11372 1.02357 2.56186 + endloop + endfacet + facet normal 0.174719 -0.19359 0.965399 + outer loop + vertex 1.11329 1.0285 2.56296 + vertex 1.11816 1.0334 2.56306 + vertex 1.11325 1.03351 2.56397 + endloop + endfacet + facet normal 0.174097 -0.203991 0.963368 + outer loop + vertex 1.11816 1.0334 2.56306 + vertex 1.11829 1.0384 2.5641 + vertex 1.11325 1.03351 2.56397 + endloop + endfacet + facet normal 0.167728 -0.197484 0.965851 + outer loop + vertex 1.11325 1.03351 2.56397 + vertex 1.11829 1.0384 2.5641 + vertex 1.11354 1.03861 2.56497 + endloop + endfacet + facet normal 0.169151 -0.207692 0.963458 + outer loop + vertex 1.1232 1.02921 2.56129 + vertex 1.12321 1.03358 2.56224 + vertex 1.11833 1.0288 2.56206 + endloop + endfacet + facet normal 0.161742 -0.204095 0.965497 + outer loop + vertex 1.11816 1.0334 2.56306 + vertex 1.12324 1.03835 2.56326 + vertex 1.11829 1.0384 2.5641 + endloop + endfacet + facet normal 0.16162 -0.206849 0.964931 + outer loop + vertex 1.12324 1.03835 2.56326 + vertex 1.12346 1.04337 2.5643 + vertex 1.11829 1.0384 2.5641 + endloop + endfacet + facet normal 0.159988 -0.20993 0.964538 + outer loop + vertex 1.12827 1.0339 2.56147 + vertex 1.12837 1.03852 2.56245 + vertex 1.12321 1.03358 2.56224 + endloop + endfacet + facet normal 0.157235 -0.20681 0.965664 + outer loop + vertex 1.12324 1.03835 2.56326 + vertex 1.12843 1.04341 2.5635 + vertex 1.12346 1.04337 2.5643 + endloop + endfacet + facet normal 0.157833 -0.20118 0.966755 + outer loop + vertex 1.13354 1.03884 2.56168 + vertex 1.13351 1.04358 2.56267 + vertex 1.12837 1.03852 2.56245 + endloop + endfacet + facet normal 0.172983 -0.206611 0.96301 + outer loop + vertex 1.12843 1.04341 2.5635 + vertex 1.13347 1.04857 2.5637 + vertex 1.12853 1.04834 2.56454 + endloop + endfacet + facet normal 0.177948 -0.173595 0.968607 + outer loop + vertex 1.13847 1.04386 2.56181 + vertex 1.13821 1.04853 2.56269 + vertex 1.13351 1.04358 2.56267 + endloop + endfacet + facet normal 0.212731 -0.159652 0.96398 + outer loop + vertex 1.13685 1.06096 2.56575 + vertex 1.13693 1.06394 2.56623 + vertex 1.13384 1.0604 2.56632 + endloop + endfacet + facet normal 0.213282 -0.160138 0.963777 + outer loop + vertex 1.13693 1.06394 2.56623 + vertex 1.13321 1.0639 2.56704 + vertex 1.13384 1.0604 2.56632 + endloop + endfacet + facet normal 0.21406 -0.116354 0.969866 + outer loop + vertex 1.13693 1.06394 2.56623 + vertex 1.13706 1.06802 2.56669 + vertex 1.13321 1.0639 2.56704 + endloop + endfacet + facet normal 0.250647 -0.151707 0.956118 + outer loop + vertex 1.13321 1.0639 2.56704 + vertex 1.13706 1.06802 2.56669 + vertex 1.13309 1.06845 2.5678 + endloop + endfacet + facet normal 0.147622 -0.174092 0.973601 + outer loop + vertex 1.13384 1.0604 2.56632 + vertex 1.13321 1.0639 2.56704 + vertex 1.12884 1.05876 2.56679 + endloop + endfacet + facet normal 0.169339 -0.192191 0.966637 + outer loop + vertex 1.12884 1.05876 2.56679 + vertex 1.13321 1.0639 2.56704 + vertex 1.12848 1.06357 2.5678 + endloop + endfacet + facet normal 0.147505 -0.217508 0.964848 + outer loop + vertex 1.12837 1.05233 2.56544 + vertex 1.12751 1.05471 2.5661 + vertex 1.12516 1.05195 2.56584 + endloop + endfacet + facet normal 0.190157 -0.23098 0.954195 + outer loop + vertex 1.13491 1.05817 2.5656 + vertex 1.13127 1.05641 2.5659 + vertex 1.13342 1.05383 2.56485 + endloop + endfacet + facet normal 0.173002 -0.208621 0.962573 + outer loop + vertex 1.13347 1.04857 2.5637 + vertex 1.13342 1.05383 2.56485 + vertex 1.12853 1.04834 2.56454 + endloop + endfacet + facet normal 0.146205 -0.202976 0.968207 + outer loop + vertex 1.12516 1.05195 2.56584 + vertex 1.12382 1.04824 2.56526 + vertex 1.12837 1.05233 2.56544 + endloop + endfacet + facet normal 0.157234 -0.206849 0.965656 + outer loop + vertex 1.12843 1.04341 2.5635 + vertex 1.12853 1.04834 2.56454 + vertex 1.12346 1.04337 2.5643 + endloop + endfacet + facet normal 0.158444 -0.203598 0.966149 + outer loop + vertex 1.11829 1.0384 2.5641 + vertex 1.12346 1.04337 2.5643 + vertex 1.1187 1.04346 2.5651 + endloop + endfacet + facet normal 0.149173 -0.203941 0.967551 + outer loop + vertex 1.12516 1.05195 2.56584 + vertex 1.12221 1.05017 2.56592 + vertex 1.12382 1.04824 2.56526 + endloop + endfacet + facet normal 0.164535 -0.216526 0.962312 + outer loop + vertex 1.12221 1.05017 2.56592 + vertex 1.12344 1.05382 2.56653 + vertex 1.11821 1.04902 2.56635 + endloop + endfacet + facet normal 0.154157 -0.205369 0.966467 + outer loop + vertex 1.12344 1.05382 2.56653 + vertex 1.11824 1.05351 2.56729 + vertex 1.11821 1.04902 2.56635 + endloop + endfacet + facet normal 0.163451 -0.2014 0.965775 + outer loop + vertex 1.12004 1.04735 2.56568 + vertex 1.11701 1.04538 2.56578 + vertex 1.1187 1.04346 2.5651 + endloop + endfacet + facet normal 0.167208 -0.203986 0.964589 + outer loop + vertex 1.1187 1.04346 2.5651 + vertex 1.11354 1.03861 2.56497 + vertex 1.11829 1.0384 2.5641 + endloop + endfacet + facet normal 0.171136 -0.204836 0.963719 + outer loop + vertex 1.11485 1.04251 2.56555 + vertex 1.11316 1.04427 2.56623 + vertex 1.11197 1.04068 2.56568 + endloop + endfacet + facet normal 0.190026 -0.210367 0.958977 + outer loop + vertex 1.11197 1.04068 2.56568 + vertex 1.11316 1.04427 2.56623 + vertex 1.10881 1.04017 2.56619 + endloop + endfacet + facet normal 0.185795 -0.197837 0.962466 + outer loop + vertex 1.11354 1.03861 2.56497 + vertex 1.10853 1.03391 2.56497 + vertex 1.11325 1.03351 2.56397 + endloop + endfacet + facet normal 0.211743 -0.179677 0.960667 + outer loop + vertex 1.10464 1.03297 2.56565 + vertex 1.10853 1.03391 2.56497 + vertex 1.10632 1.03628 2.5659 + endloop + endfacet + facet normal 0.252205 -0.199222 0.946944 + outer loop + vertex 1.10291 1.0344 2.56641 + vertex 1.10464 1.03297 2.56565 + vertex 1.10632 1.03628 2.5659 + endloop + endfacet + facet normal 0.190032 -0.21042 0.958964 + outer loop + vertex 1.11197 1.04068 2.56568 + vertex 1.10881 1.04017 2.56619 + vertex 1.10975 1.0379 2.56551 + endloop + endfacet + facet normal 0.2514 -0.197609 0.947496 + outer loop + vertex 1.10632 1.03628 2.5659 + vertex 1.10382 1.03856 2.56704 + vertex 1.10291 1.0344 2.56641 + endloop + endfacet + facet normal 0.18422 -0.204219 0.961435 + outer loop + vertex 1.11316 1.04427 2.56623 + vertex 1.1083 1.04377 2.56705 + vertex 1.10881 1.04017 2.56619 + endloop + endfacet + facet normal 0.191348 -0.171682 0.966391 + outer loop + vertex 1.10341 1.04352 2.56806 + vertex 1.1081 1.04835 2.56799 + vertex 1.10329 1.0485 2.56897 + endloop + endfacet + facet normal 0.234513 -0.168956 0.957318 + outer loop + vertex 1.10341 1.04352 2.56806 + vertex 1.10329 1.0485 2.56897 + vertex 1.09889 1.04389 2.56923 + endloop + endfacet + facet normal 0.216809 -0.151686 0.964357 + outer loop + vertex 1.09889 1.04389 2.56923 + vertex 1.10329 1.0485 2.56897 + vertex 1.09862 1.04877 2.57006 + endloop + endfacet + facet normal 0.214627 -0.17513 0.960867 + outer loop + vertex 1.10329 1.0485 2.56897 + vertex 1.10335 1.05374 2.56991 + vertex 1.09862 1.04877 2.57006 + endloop + endfacet + facet normal 0.186989 -0.148545 0.971066 + outer loop + vertex 1.09862 1.04877 2.57006 + vertex 1.10335 1.05374 2.56991 + vertex 1.09937 1.05282 2.57054 + endloop + endfacet + facet normal 0.190242 -0.188504 0.96347 + outer loop + vertex 1.1081 1.04835 2.56799 + vertex 1.10815 1.05339 2.56897 + vertex 1.10329 1.0485 2.56897 + endloop + endfacet + facet normal 0.177678 -0.176011 0.96822 + outer loop + vertex 1.10329 1.0485 2.56897 + vertex 1.10815 1.05339 2.56897 + vertex 1.10335 1.05374 2.56991 + endloop + endfacet + facet normal 0.18387 -0.198788 0.962639 + outer loop + vertex 1.11316 1.04427 2.56623 + vertex 1.11313 1.04859 2.56712 + vertex 1.1083 1.04377 2.56705 + endloop + endfacet + facet normal 0.166892 -0.189123 0.967667 + outer loop + vertex 1.1081 1.04835 2.56799 + vertex 1.11308 1.0533 2.5681 + vertex 1.10815 1.05339 2.56897 + endloop + endfacet + facet normal 0.166367 -0.199044 0.965766 + outer loop + vertex 1.11308 1.0533 2.5681 + vertex 1.11324 1.05837 2.56911 + vertex 1.10815 1.05339 2.56897 + endloop + endfacet + facet normal 0.160845 -0.193456 0.967835 + outer loop + vertex 1.10815 1.05339 2.56897 + vertex 1.11324 1.05837 2.56911 + vertex 1.1085 1.05861 2.56995 + endloop + endfacet + facet normal 0.165514 -0.205056 0.964654 + outer loop + vertex 1.11821 1.04902 2.56635 + vertex 1.11824 1.05351 2.56729 + vertex 1.11313 1.04859 2.56712 + endloop + endfacet + facet normal 0.153783 -0.199068 0.967844 + outer loop + vertex 1.11308 1.0533 2.5681 + vertex 1.11824 1.05833 2.56831 + vertex 1.11324 1.05837 2.56911 + endloop + endfacet + facet normal 0.153778 -0.199206 0.967817 + outer loop + vertex 1.11824 1.05833 2.56831 + vertex 1.11845 1.0634 2.56932 + vertex 1.11324 1.05837 2.56911 + endloop + endfacet + facet normal 0.154293 -0.210244 0.965397 + outer loop + vertex 1.12344 1.05382 2.56653 + vertex 1.12345 1.0585 2.56755 + vertex 1.11824 1.05351 2.56729 + endloop + endfacet + facet normal 0.147093 -0.199137 0.96887 + outer loop + vertex 1.11824 1.05833 2.56831 + vertex 1.12343 1.06341 2.56857 + vertex 1.11845 1.0634 2.56932 + endloop + endfacet + facet normal 0.146489 -0.194586 0.969885 + outer loop + vertex 1.12884 1.05876 2.56679 + vertex 1.12848 1.06357 2.5678 + vertex 1.12345 1.0585 2.56755 + endloop + endfacet + facet normal 0.162019 -0.192884 0.967753 + outer loop + vertex 1.12343 1.06341 2.56857 + vertex 1.12848 1.06848 2.56873 + vertex 1.12367 1.06842 2.56953 + endloop + endfacet + facet normal 0.16793 -0.156726 0.973261 + outer loop + vertex 1.13321 1.0639 2.56704 + vertex 1.13309 1.06845 2.5678 + vertex 1.12848 1.06357 2.5678 + endloop + endfacet + facet normal 0.179647 -0.215696 0.959793 + outer loop + vertex 1.12546 1.07689 2.57099 + vertex 1.12409 1.0732 2.57041 + vertex 1.12853 1.07732 2.57051 + endloop + endfacet + facet normal 0.162188 -0.184164 0.969422 + outer loop + vertex 1.12848 1.06848 2.56873 + vertex 1.12863 1.07337 2.56964 + vertex 1.12367 1.06842 2.56953 + endloop + endfacet + facet normal 0.14047 -0.187186 0.972229 + outer loop + vertex 1.12027 1.07226 2.57079 + vertex 1.11889 1.06842 2.57025 + vertex 1.12409 1.0732 2.57041 + endloop + endfacet + facet normal 0.14444 -0.188492 0.971395 + outer loop + vertex 1.12027 1.07226 2.57079 + vertex 1.11716 1.07028 2.57086 + vertex 1.11889 1.06842 2.57025 + endloop + endfacet + facet normal 0.147979 -0.185233 0.971489 + outer loop + vertex 1.11889 1.06842 2.57025 + vertex 1.11716 1.07028 2.57086 + vertex 1.11495 1.06739 2.57065 + endloop + endfacet + facet normal 0.157699 -0.192457 0.968551 + outer loop + vertex 1.11716 1.07028 2.57086 + vertex 1.11314 1.06905 2.57128 + vertex 1.11495 1.06739 2.57065 + endloop + endfacet + facet normal 0.160645 -0.203004 0.96591 + outer loop + vertex 1.11716 1.07028 2.57086 + vertex 1.1184 1.07394 2.57143 + vertex 1.11314 1.06905 2.57128 + endloop + endfacet + facet normal 0.152692 -0.194544 0.968936 + outer loop + vertex 1.1184 1.07394 2.57143 + vertex 1.11321 1.0735 2.57216 + vertex 1.11314 1.06905 2.57128 + endloop + endfacet + facet normal 0.151925 -0.20036 0.967871 + outer loop + vertex 1.12027 1.07226 2.57079 + vertex 1.1184 1.07394 2.57143 + vertex 1.11716 1.07028 2.57086 + endloop + endfacet + facet normal 0.147275 -0.192633 0.970156 + outer loop + vertex 1.12343 1.06341 2.56857 + vertex 1.12367 1.06842 2.56953 + vertex 1.11845 1.0634 2.56932 + endloop + endfacet + facet normal 0.151584 -0.196969 0.96862 + outer loop + vertex 1.11324 1.05837 2.56911 + vertex 1.11845 1.0634 2.56932 + vertex 1.11363 1.06349 2.57009 + endloop + endfacet + facet normal 0.160517 -0.197361 0.9671 + outer loop + vertex 1.11363 1.06349 2.57009 + vertex 1.1085 1.05861 2.56995 + vertex 1.11324 1.05837 2.56911 + endloop + endfacet + facet normal 0.161696 -0.196215 0.967137 + outer loop + vertex 1.10981 1.06255 2.57053 + vertex 1.10814 1.0643 2.57117 + vertex 1.10699 1.06074 2.57064 + endloop + endfacet + facet normal 0.176408 -0.200477 0.963685 + outer loop + vertex 1.10699 1.06074 2.57064 + vertex 1.10814 1.0643 2.57117 + vertex 1.10383 1.06023 2.57111 + endloop + endfacet + facet normal 0.175745 -0.19395 0.965141 + outer loop + vertex 1.1085 1.05861 2.56995 + vertex 1.10335 1.05374 2.56991 + vertex 1.10815 1.05339 2.56897 + endloop + endfacet + facet normal 0.1929 -0.178121 0.964916 + outer loop + vertex 1.09937 1.05282 2.57054 + vertex 1.10335 1.05374 2.56991 + vertex 1.10127 1.05628 2.57079 + endloop + endfacet + facet normal 0.230763 -0.197977 0.952656 + outer loop + vertex 1.09778 1.05439 2.57125 + vertex 1.09937 1.05282 2.57054 + vertex 1.10127 1.05628 2.57079 + endloop + endfacet + facet normal 0.176951 -0.204754 0.962686 + outer loop + vertex 1.10699 1.06074 2.57064 + vertex 1.10383 1.06023 2.57111 + vertex 1.10475 1.05794 2.57046 + endloop + endfacet + facet normal 0.230129 -0.196707 0.953072 + outer loop + vertex 1.10127 1.05628 2.57079 + vertex 1.09875 1.05856 2.57187 + vertex 1.09778 1.05439 2.57125 + endloop + endfacet + facet normal 0.173732 -0.19766 0.964753 + outer loop + vertex 1.10814 1.0643 2.57117 + vertex 1.10329 1.06378 2.57194 + vertex 1.10383 1.06023 2.57111 + endloop + endfacet + facet normal 0.179949 -0.166827 0.969426 + outer loop + vertex 1.0983 1.06349 2.57288 + vertex 1.10306 1.06828 2.57283 + vertex 1.09823 1.06846 2.57375 + endloop + endfacet + facet normal 0.221432 -0.164841 0.961143 + outer loop + vertex 1.0983 1.06349 2.57288 + vertex 1.09823 1.06846 2.57375 + vertex 1.09368 1.06392 2.57402 + endloop + endfacet + facet normal 0.223936 -0.145222 0.963724 + outer loop + vertex 1.09363 1.05884 2.57327 + vertex 1.0983 1.06349 2.57288 + vertex 1.09368 1.06392 2.57402 + endloop + endfacet + facet normal 0.206228 -0.14923 0.967058 + outer loop + vertex 1.09368 1.06392 2.57402 + vertex 1.09823 1.06846 2.57375 + vertex 1.09357 1.06903 2.57484 + endloop + endfacet + facet normal 0.203481 -0.167182 0.9647 + outer loop + vertex 1.09823 1.06846 2.57375 + vertex 1.09865 1.07356 2.57455 + vertex 1.09357 1.06903 2.57484 + endloop + endfacet + facet normal 0.166233 -0.16529 0.972135 + outer loop + vertex 1.09823 1.06846 2.57375 + vertex 1.10316 1.07322 2.57372 + vertex 1.09865 1.07356 2.57455 + endloop + endfacet + facet normal 0.179137 -0.178666 0.967465 + outer loop + vertex 1.10306 1.06828 2.57283 + vertex 1.10316 1.07322 2.57372 + vertex 1.09823 1.06846 2.57375 + endloop + endfacet + facet normal 0.173122 -0.189536 0.966491 + outer loop + vertex 1.10814 1.0643 2.57117 + vertex 1.1081 1.06857 2.57201 + vertex 1.10329 1.06378 2.57194 + endloop + endfacet + facet normal 0.157858 -0.178912 0.971119 + outer loop + vertex 1.10306 1.06828 2.57283 + vertex 1.10806 1.0732 2.57292 + vertex 1.10316 1.07322 2.57372 + endloop + endfacet + facet normal 0.157534 -0.188476 0.96936 + outer loop + vertex 1.10806 1.0732 2.57292 + vertex 1.1082 1.07817 2.57386 + vertex 1.10316 1.07322 2.57372 + endloop + endfacet + facet normal 0.14875 -0.17961 0.972427 + outer loop + vertex 1.10316 1.07322 2.57372 + vertex 1.1082 1.07817 2.57386 + vertex 1.10356 1.07827 2.57459 + endloop + endfacet + facet normal 0.160597 -0.194415 0.967684 + outer loop + vertex 1.11314 1.06905 2.57128 + vertex 1.11321 1.0735 2.57216 + vertex 1.1081 1.06857 2.57201 + endloop + endfacet + facet normal 0.147131 -0.188496 0.97099 + outer loop + vertex 1.10806 1.0732 2.57292 + vertex 1.1132 1.07825 2.57312 + vertex 1.1082 1.07817 2.57386 + endloop + endfacet + facet normal 0.147071 -0.193716 0.969971 + outer loop + vertex 1.1132 1.07825 2.57312 + vertex 1.1133 1.08328 2.57411 + vertex 1.1082 1.07817 2.57386 + endloop + endfacet + facet normal 0.140946 -0.187711 0.972059 + outer loop + vertex 1.1082 1.07817 2.57386 + vertex 1.1133 1.08328 2.57411 + vertex 1.10847 1.08309 2.57477 + endloop + endfacet + facet normal 0.153149 -0.203006 0.967127 + outer loop + vertex 1.1184 1.07394 2.57143 + vertex 1.11843 1.07852 2.57238 + vertex 1.11321 1.0735 2.57216 + endloop + endfacet + facet normal 0.142901 -0.193757 0.970586 + outer loop + vertex 1.1132 1.07825 2.57312 + vertex 1.11838 1.08338 2.57338 + vertex 1.1133 1.08328 2.57411 + endloop + endfacet + facet normal 0.142925 -0.190793 0.97117 + outer loop + vertex 1.11838 1.08338 2.57338 + vertex 1.11849 1.08842 2.57436 + vertex 1.1133 1.08328 2.57411 + endloop + endfacet + facet normal 0.146677 -0.192819 0.97021 + outer loop + vertex 1.12366 1.07878 2.57165 + vertex 1.12354 1.08355 2.57261 + vertex 1.11843 1.07852 2.57238 + endloop + endfacet + facet normal 0.160531 -0.190657 0.968442 + outer loop + vertex 1.11838 1.08338 2.57338 + vertex 1.12342 1.08847 2.57355 + vertex 1.11849 1.08842 2.57436 + endloop + endfacet + facet normal 0.169187 -0.157967 0.972842 + outer loop + vertex 1.12862 1.08362 2.57174 + vertex 1.12814 1.08841 2.5726 + vertex 1.12354 1.08355 2.57261 + endloop + endfacet + facet normal 0.20537 -0.223067 0.952924 + outer loop + vertex 1.12042 1.09721 2.57584 + vertex 1.11895 1.09342 2.57527 + vertex 1.12414 1.09832 2.5753 + endloop + endfacet + facet normal 0.16083 -0.176921 0.970996 + outer loop + vertex 1.12342 1.08847 2.57355 + vertex 1.12363 1.09344 2.57442 + vertex 1.11849 1.08842 2.57436 + endloop + endfacet + facet normal 0.141554 -0.18943 0.971637 + outer loop + vertex 1.1133 1.08328 2.57411 + vertex 1.11849 1.08842 2.57436 + vertex 1.1134 1.08845 2.5751 + endloop + endfacet + facet normal 0.146365 -0.2025 0.968283 + outer loop + vertex 1.12042 1.09721 2.57584 + vertex 1.11744 1.09541 2.57592 + vertex 1.11895 1.09342 2.57527 + endloop + endfacet + facet normal 0.133048 -0.19218 0.972299 + outer loop + vertex 1.11744 1.09541 2.57592 + vertex 1.11866 1.099 2.57646 + vertex 1.11414 1.09496 2.57628 + endloop + endfacet + facet normal 0.13768 -0.193623 0.971367 + outer loop + vertex 1.11414 1.09496 2.57628 + vertex 1.11363 1.09863 2.57708 + vertex 1.10885 1.09338 2.57671 + endloop + endfacet + facet normal 0.136657 -0.192714 0.971692 + outer loop + vertex 1.10885 1.09338 2.57671 + vertex 1.11363 1.09863 2.57708 + vertex 1.10836 1.09821 2.57774 + endloop + endfacet + facet normal 0.141552 -0.186678 0.97217 + outer loop + vertex 1.10843 1.08704 2.57554 + vertex 1.10758 1.08938 2.57611 + vertex 1.10535 1.08668 2.57591 + endloop + endfacet + facet normal 0.134904 -0.188829 0.9727 + outer loop + vertex 1.11503 1.09265 2.57569 + vertex 1.11127 1.09101 2.5759 + vertex 1.1134 1.08845 2.5751 + endloop + endfacet + facet normal 0.140966 -0.189435 0.971722 + outer loop + vertex 1.1133 1.08328 2.57411 + vertex 1.1134 1.08845 2.5751 + vertex 1.10847 1.08309 2.57477 + endloop + endfacet + facet normal 0.1414 -0.185012 0.97251 + outer loop + vertex 1.10535 1.08668 2.57591 + vertex 1.10405 1.08304 2.57541 + vertex 1.10843 1.08704 2.57554 + endloop + endfacet + facet normal 0.148333 -0.187904 0.970922 + outer loop + vertex 1.1082 1.07817 2.57386 + vertex 1.10847 1.08309 2.57477 + vertex 1.10356 1.07827 2.57459 + endloop + endfacet + facet normal 0.146384 -0.176892 0.973284 + outer loop + vertex 1.10038 1.08212 2.5758 + vertex 1.09918 1.07842 2.5753 + vertex 1.10405 1.08304 2.57541 + endloop + endfacet + facet normal 0.164645 -0.1804 0.969715 + outer loop + vertex 1.10316 1.07322 2.57372 + vertex 1.10356 1.07827 2.57459 + vertex 1.09865 1.07356 2.57455 + endloop + endfacet + facet normal 0.184469 -0.145375 0.972027 + outer loop + vertex 1.09357 1.06903 2.57484 + vertex 1.09865 1.07356 2.57455 + vertex 1.09496 1.07412 2.57533 + endloop + endfacet + facet normal 0.224872 -0.167809 0.95983 + outer loop + vertex 1.09544 1.07731 2.57578 + vertex 1.09255 1.07499 2.57605 + vertex 1.09496 1.07412 2.57533 + endloop + endfacet + facet normal 0.167592 -0.183141 0.968696 + outer loop + vertex 1.10038 1.08212 2.5758 + vertex 1.09738 1.08011 2.57593 + vertex 1.09918 1.07842 2.5753 + endloop + endfacet + facet normal 0.242231 -0.19049 0.951335 + outer loop + vertex 1.09544 1.07731 2.57578 + vertex 1.09336 1.07878 2.5766 + vertex 1.09255 1.07499 2.57605 + endloop + endfacet + facet normal 0.176069 -0.196075 0.964652 + outer loop + vertex 1.10038 1.08212 2.5758 + vertex 1.09842 1.08374 2.57648 + vertex 1.09738 1.08011 2.57593 + endloop + endfacet + facet normal 0.16058 -0.186636 0.969217 + outer loop + vertex 1.10355 1.08852 2.57655 + vertex 1.09826 1.08832 2.57739 + vertex 1.09842 1.08374 2.57648 + endloop + endfacet + facet normal 0.169102 -0.169077 0.970988 + outer loop + vertex 1.09319 1.08838 2.57835 + vertex 1.09812 1.0932 2.57833 + vertex 1.0933 1.09346 2.57921 + endloop + endfacet + facet normal 0.160593 -0.188353 0.968882 + outer loop + vertex 1.10355 1.08852 2.57655 + vertex 1.10333 1.09321 2.5775 + vertex 1.09826 1.08832 2.57739 + endloop + endfacet + facet normal 0.149428 -0.183887 0.971523 + outer loop + vertex 1.09812 1.0932 2.57833 + vertex 1.10316 1.09816 2.57849 + vertex 1.09826 1.09832 2.57927 + endloop + endfacet + facet normal 0.144205 -0.191755 0.970791 + outer loop + vertex 1.10885 1.09338 2.57671 + vertex 1.10836 1.09821 2.57774 + vertex 1.10333 1.09321 2.5775 + endloop + endfacet + facet normal 0.14027 -0.18659 0.972373 + outer loop + vertex 1.10316 1.09816 2.57849 + vertex 1.10827 1.10321 2.57872 + vertex 1.10339 1.1033 2.57944 + endloop + endfacet + facet normal 0.136353 -0.187025 0.972846 + outer loop + vertex 1.11363 1.09863 2.57708 + vertex 1.11338 1.10329 2.57801 + vertex 1.10836 1.09821 2.57774 + endloop + endfacet + facet normal 0.140502 -0.181937 0.973221 + outer loop + vertex 1.10827 1.10321 2.57872 + vertex 1.11341 1.10831 2.57893 + vertex 1.10856 1.10828 2.57963 + endloop + endfacet + facet normal 0.14107 -0.166915 0.975827 + outer loop + vertex 1.11851 1.1035 2.57731 + vertex 1.11838 1.10836 2.57816 + vertex 1.11338 1.10329 2.57801 + endloop + endfacet + facet normal 0.168199 -0.176959 0.96974 + outer loop + vertex 1.11341 1.10831 2.57893 + vertex 1.11841 1.11344 2.579 + vertex 1.1136 1.11323 2.5798 + endloop + endfacet + facet normal 0.178767 -0.129642 0.975313 + outer loop + vertex 1.12312 1.10834 2.57729 + vertex 1.12301 1.11325 2.57796 + vertex 1.11838 1.10836 2.57816 + endloop + endfacet + facet normal 0.168221 -0.17858 0.969439 + outer loop + vertex 1.11841 1.11344 2.579 + vertex 1.11844 1.11867 2.57996 + vertex 1.1136 1.11323 2.5798 + endloop + endfacet + facet normal 0.135915 -0.180543 0.974131 + outer loop + vertex 1.11036 1.11671 2.58092 + vertex 1.10902 1.11306 2.58043 + vertex 1.11353 1.11715 2.58056 + endloop + endfacet + facet normal 0.140615 -0.176644 0.974179 + outer loop + vertex 1.11341 1.10831 2.57893 + vertex 1.1136 1.11323 2.5798 + vertex 1.10856 1.10828 2.57963 + endloop + endfacet + facet normal 0.133386 -0.170705 0.976252 + outer loop + vertex 1.10531 1.11215 2.58078 + vertex 1.10394 1.10833 2.5803 + vertex 1.10902 1.11306 2.58043 + endloop + endfacet + facet normal 0.14048 -0.181936 0.973224 + outer loop + vertex 1.10827 1.10321 2.57872 + vertex 1.10856 1.10828 2.57963 + vertex 1.10339 1.1033 2.57944 + endloop + endfacet + facet normal 0.145172 -0.179325 0.97302 + outer loop + vertex 1.10014 1.10733 2.58068 + vertex 1.09874 1.10344 2.58017 + vertex 1.10394 1.10833 2.5803 + endloop + endfacet + facet normal 0.149252 -0.186742 0.971005 + outer loop + vertex 1.10316 1.09816 2.57849 + vertex 1.10339 1.1033 2.57944 + vertex 1.09826 1.09832 2.57927 + endloop + endfacet + facet normal 0.153738 -0.178627 0.971832 + outer loop + vertex 1.09493 1.10244 2.58059 + vertex 1.09362 1.09854 2.58008 + vertex 1.09874 1.10344 2.58017 + endloop + endfacet + facet normal 0.167862 -0.183846 0.968516 + outer loop + vertex 1.09812 1.0932 2.57833 + vertex 1.09826 1.09832 2.57927 + vertex 1.0933 1.09346 2.57921 + endloop + endfacet + facet normal 0.188916 -0.154258 0.969802 + outer loop + vertex 1.0887 1.08887 2.57938 + vertex 1.0933 1.09346 2.57921 + vertex 1.08884 1.09376 2.58013 + endloop + endfacet + facet normal 0.204422 -0.169678 0.964065 + outer loop + vertex 1.08984 1.09756 2.58058 + vertex 1.08698 1.0955 2.58083 + vertex 1.08884 1.09376 2.58013 + endloop + endfacet + facet normal 0.169519 -0.183478 0.968297 + outer loop + vertex 1.09493 1.10244 2.58059 + vertex 1.09193 1.10043 2.58073 + vertex 1.09362 1.09854 2.58008 + endloop + endfacet + facet normal 0.219284 -0.191171 0.956749 + outer loop + vertex 1.08984 1.09756 2.58058 + vertex 1.08809 1.09914 2.5813 + vertex 1.08698 1.0955 2.58083 + endloop + endfacet + facet normal 0.173873 -0.190124 0.966241 + outer loop + vertex 1.09493 1.10244 2.58059 + vertex 1.09319 1.1041 2.58123 + vertex 1.09193 1.10043 2.58073 + endloop + endfacet + facet normal 0.186865 -0.174835 0.966703 + outer loop + vertex 1.09319 1.1041 2.58123 + vertex 1.09329 1.10854 2.58201 + vertex 1.08822 1.10358 2.58209 + endloop + endfacet + facet normal 0.173413 -0.161012 0.971598 + outer loop + vertex 1.08822 1.10358 2.58209 + vertex 1.09329 1.10854 2.58201 + vertex 1.08821 1.10822 2.58286 + endloop + endfacet + facet normal 0.166768 -0.148056 0.974817 + outer loop + vertex 1.08321 1.10813 2.58375 + vertex 1.08821 1.11316 2.58366 + vertex 1.08338 1.11327 2.5845 + endloop + endfacet + facet normal 0.173531 -0.164401 0.971009 + outer loop + vertex 1.09329 1.10854 2.58201 + vertex 1.09322 1.1132 2.58281 + vertex 1.08821 1.10822 2.58286 + endloop + endfacet + facet normal 0.160304 -0.161405 0.973782 + outer loop + vertex 1.08821 1.11316 2.58366 + vertex 1.0932 1.11817 2.58367 + vertex 1.08841 1.11831 2.58448 + endloop + endfacet + facet normal 0.166109 -0.161481 0.972796 + outer loop + vertex 1.08821 1.11316 2.58366 + vertex 1.08841 1.11831 2.58448 + vertex 1.08338 1.11327 2.5845 + endloop + endfacet + facet normal 0.159685 -0.155056 0.974914 + outer loop + vertex 1.08338 1.11327 2.5845 + vertex 1.08841 1.11831 2.58448 + vertex 1.08376 1.1184 2.58526 + endloop + endfacet + facet normal 0.159753 -0.171192 0.9722 + outer loop + vertex 1.0932 1.11817 2.58367 + vertex 1.09348 1.1233 2.58453 + vertex 1.08841 1.11831 2.58448 + endloop + endfacet + facet normal 0.154501 -0.17226 0.97286 + outer loop + vertex 1.09835 1.11345 2.58204 + vertex 1.09822 1.11815 2.5829 + vertex 1.09322 1.1132 2.58281 + endloop + endfacet + facet normal 0.146024 -0.170836 0.974419 + outer loop + vertex 1.0932 1.11817 2.58367 + vertex 1.09824 1.12316 2.58379 + vertex 1.09348 1.1233 2.58453 + endloop + endfacet + facet normal 0.138517 -0.178516 0.974138 + outer loop + vertex 1.10342 1.11833 2.58219 + vertex 1.10329 1.12315 2.58309 + vertex 1.09822 1.11815 2.5829 + endloop + endfacet + facet normal 0.133162 -0.172625 0.975945 + outer loop + vertex 1.09824 1.12316 2.58379 + vertex 1.10332 1.1282 2.58399 + vertex 1.09853 1.12823 2.58465 + endloop + endfacet + facet normal 0.130148 -0.17161 0.97653 + outer loop + vertex 1.10856 1.12331 2.58242 + vertex 1.10839 1.12827 2.58331 + vertex 1.10329 1.12315 2.58309 + endloop + endfacet + facet normal 0.137038 -0.168709 0.976093 + outer loop + vertex 1.10332 1.1282 2.58399 + vertex 1.1084 1.13341 2.58418 + vertex 1.10348 1.13315 2.58482 + endloop + endfacet + facet normal 0.143589 -0.146253 0.978771 + outer loop + vertex 1.11351 1.12842 2.58258 + vertex 1.11334 1.13345 2.58336 + vertex 1.10839 1.12827 2.58331 + endloop + endfacet + facet normal 0.202438 -0.109343 0.973172 + outer loop + vertex 1.11794 1.13335 2.58239 + vertex 1.11784 1.13833 2.58297 + vertex 1.11334 1.13345 2.58336 + endloop + endfacet + facet normal 0.18302 -0.169852 0.968325 + outer loop + vertex 1.1084 1.13341 2.58418 + vertex 1.11338 1.13858 2.58414 + vertex 1.10842 1.13865 2.58509 + endloop + endfacet + facet normal 0.261904 -0.210008 0.941968 + outer loop + vertex 1.11503 1.14752 2.58551 + vertex 1.11235 1.14583 2.58589 + vertex 1.11376 1.14367 2.58501 + endloop + endfacet + facet normal 0.136955 -0.190597 0.972068 + outer loop + vertex 1.11005 1.14298 2.58571 + vertex 1.10914 1.14528 2.58629 + vertex 1.10627 1.14118 2.58589 + endloop + endfacet + facet normal 0.23173 -0.157966 0.959869 + outer loop + vertex 1.11503 1.14752 2.58551 + vertex 1.11322 1.14929 2.58624 + vertex 1.11235 1.14583 2.58589 + endloop + endfacet + facet normal 0.282831 -0.112762 0.952518 + outer loop + vertex 1.1167 1.15331 2.58569 + vertex 1.11284 1.15349 2.58685 + vertex 1.11322 1.14929 2.58624 + endloop + endfacet + facet normal 0.117262 -0.161937 0.979809 + outer loop + vertex 1.10914 1.14528 2.58629 + vertex 1.1086 1.14886 2.58695 + vertex 1.10391 1.14351 2.58662 + endloop + endfacet + facet normal 0.123668 -0.18165 0.975556 + outer loop + vertex 1.10914 1.14528 2.58629 + vertex 1.10391 1.14351 2.58662 + vertex 1.10627 1.14118 2.58589 + endloop + endfacet + facet normal 0.126029 -0.173827 0.976678 + outer loop + vertex 1.10336 1.13709 2.58551 + vertex 1.10252 1.13943 2.58603 + vertex 1.10024 1.13667 2.58584 + endloop + endfacet + facet normal 0.137197 -0.191116 0.971932 + outer loop + vertex 1.11005 1.14298 2.58571 + vertex 1.10627 1.14118 2.58589 + vertex 1.10842 1.13865 2.58509 + endloop + endfacet + facet normal 0.137104 -0.1709 0.975703 + outer loop + vertex 1.1084 1.13341 2.58418 + vertex 1.10842 1.13865 2.58509 + vertex 1.10348 1.13315 2.58482 + endloop + endfacet + facet normal 0.124418 -0.159706 0.979293 + outer loop + vertex 1.10024 1.13667 2.58584 + vertex 1.09896 1.13302 2.5854 + vertex 1.10336 1.13709 2.58551 + endloop + endfacet + facet normal 0.13328 -0.168671 0.97662 + outer loop + vertex 1.10332 1.1282 2.58399 + vertex 1.10348 1.13315 2.58482 + vertex 1.09853 1.12823 2.58465 + endloop + endfacet + facet normal 0.143603 -0.166234 0.975574 + outer loop + vertex 1.09535 1.13214 2.58579 + vertex 1.094 1.12832 2.58533 + vertex 1.09896 1.13302 2.5854 + endloop + endfacet + facet normal 0.1459 -0.173042 0.974048 + outer loop + vertex 1.09824 1.12316 2.58379 + vertex 1.09853 1.12823 2.58465 + vertex 1.09348 1.1233 2.58453 + endloop + endfacet + facet normal 0.155397 -0.166789 0.97367 + outer loop + vertex 1.08841 1.11831 2.58448 + vertex 1.09348 1.1233 2.58453 + vertex 1.08887 1.12341 2.58528 + endloop + endfacet + facet normal 0.152866 -0.16928 0.973641 + outer loop + vertex 1.09535 1.13214 2.58579 + vertex 1.09238 1.13018 2.58591 + vertex 1.094 1.12832 2.58533 + endloop + endfacet + facet normal 0.14814 -0.166124 0.974914 + outer loop + vertex 1.09238 1.13018 2.58591 + vertex 1.09351 1.13381 2.58636 + vertex 1.08841 1.12895 2.5863 + endloop + endfacet + facet normal 0.151004 -0.168989 0.973982 + outer loop + vertex 1.09023 1.12732 2.58575 + vertex 1.08721 1.12528 2.58586 + vertex 1.08887 1.12341 2.58528 + endloop + endfacet + facet normal 0.159153 -0.167021 0.973023 + outer loop + vertex 1.08887 1.12341 2.58528 + vertex 1.08376 1.1184 2.58526 + vertex 1.08841 1.11831 2.58448 + endloop + endfacet + facet normal 0.137909 -0.145799 0.979655 + outer loop + vertex 1.07999 1.11734 2.58567 + vertex 1.0783 1.11907 2.58616 + vertex 1.07717 1.11543 2.58578 + endloop + endfacet + facet normal 0.146504 -0.156839 0.976698 + outer loop + vertex 1.08505 1.12235 2.5857 + vertex 1.08327 1.12398 2.58623 + vertex 1.08208 1.12028 2.58581 + endloop + endfacet + facet normal 0.137466 -0.146489 0.979614 + outer loop + vertex 1.0783 1.11907 2.58616 + vertex 1.07826 1.12339 2.58681 + vertex 1.0734 1.11848 2.58676 + endloop + endfacet + facet normal 0.137676 -0.15698 0.977958 + outer loop + vertex 1.08841 1.12895 2.5863 + vertex 1.08334 1.12841 2.58693 + vertex 1.08327 1.12398 2.58623 + endloop + endfacet + facet normal 0.13317 -0.15805 0.97841 + outer loop + vertex 1.08334 1.12841 2.58693 + vertex 1.08842 1.1334 2.58705 + vertex 1.08327 1.13308 2.58769 + endloop + endfacet + facet normal 0.109997 -0.15076 0.982432 + outer loop + vertex 1.07816 1.133 2.5883 + vertex 1.08319 1.13806 2.58851 + vertex 1.07819 1.13826 2.5891 + endloop + endfacet + facet normal 0.109462 -0.16005 0.981021 + outer loop + vertex 1.08319 1.13806 2.58851 + vertex 1.08323 1.14327 2.58935 + vertex 1.07819 1.13826 2.5891 + endloop + endfacet + facet normal 0.101849 -0.152482 0.983044 + outer loop + vertex 1.07819 1.13826 2.5891 + vertex 1.08323 1.14327 2.58935 + vertex 1.07815 1.14372 2.58995 + endloop + endfacet + facet normal 0.100397 -0.166065 0.980991 + outer loop + vertex 1.0836 1.14843 2.59019 + vertex 1.07815 1.14372 2.58995 + vertex 1.08323 1.14327 2.58935 + endloop + endfacet + facet normal 0.127284 -0.167425 0.977634 + outer loop + vertex 1.08323 1.14327 2.58935 + vertex 1.08834 1.14821 2.58954 + vertex 1.0836 1.14843 2.59019 + endloop + endfacet + facet normal 0.124695 -0.164782 0.978416 + outer loop + vertex 1.08818 1.14308 2.58869 + vertex 1.08834 1.14821 2.58954 + vertex 1.08323 1.14327 2.58935 + endloop + endfacet + facet normal 0.104534 -0.170786 0.979747 + outer loop + vertex 1.0798 1.14794 2.59051 + vertex 1.07815 1.14372 2.58995 + vertex 1.0836 1.14843 2.59019 + endloop + endfacet + facet normal 0.0747506 -0.15977 0.98432 + outer loop + vertex 1.0798 1.14794 2.59051 + vertex 1.07606 1.14676 2.5906 + vertex 1.07815 1.14372 2.58995 + endloop + endfacet + facet normal 0.133372 -0.162852 0.977595 + outer loop + vertex 1.08842 1.1334 2.58705 + vertex 1.08827 1.13809 2.58785 + vertex 1.08327 1.13308 2.58769 + endloop + endfacet + facet normal 0.124979 -0.159886 0.979192 + outer loop + vertex 1.08319 1.13806 2.58851 + vertex 1.08818 1.14308 2.58869 + vertex 1.08323 1.14327 2.58935 + endloop + endfacet + facet normal 0.140781 -0.167093 0.975838 + outer loop + vertex 1.09343 1.13831 2.58714 + vertex 1.09325 1.14308 2.58798 + vertex 1.08827 1.13809 2.58785 + endloop + endfacet + facet normal 0.135201 -0.16488 0.977003 + outer loop + vertex 1.08818 1.14308 2.58869 + vertex 1.09321 1.14812 2.58885 + vertex 1.08834 1.14821 2.58954 + endloop + endfacet + facet normal 0.135227 -0.16425 0.977106 + outer loop + vertex 1.09321 1.14812 2.58885 + vertex 1.0935 1.15324 2.58967 + vertex 1.08834 1.14821 2.58954 + endloop + endfacet + facet normal 0.136508 -0.165554 0.976707 + outer loop + vertex 1.08834 1.14821 2.58954 + vertex 1.0935 1.15324 2.58967 + vertex 1.08877 1.15322 2.59033 + endloop + endfacet + facet normal 0.135776 -0.169579 0.976119 + outer loop + vertex 1.09848 1.14324 2.58728 + vertex 1.09829 1.14813 2.58816 + vertex 1.09325 1.14308 2.58798 + endloop + endfacet + facet normal 0.131369 -0.164126 0.977653 + outer loop + vertex 1.09321 1.14812 2.58885 + vertex 1.09837 1.15324 2.58901 + vertex 1.0935 1.15324 2.58967 + endloop + endfacet + facet normal 0.131452 -0.160501 0.978243 + outer loop + vertex 1.09837 1.15324 2.58901 + vertex 1.09872 1.1583 2.5898 + vertex 1.0935 1.15324 2.58967 + endloop + endfacet + facet normal 0.125767 -0.162778 0.978614 + outer loop + vertex 1.10352 1.14833 2.58752 + vertex 1.10338 1.15325 2.58836 + vertex 1.09829 1.14813 2.58816 + endloop + endfacet + facet normal 0.13304 -0.160576 0.978016 + outer loop + vertex 1.09837 1.15324 2.58901 + vertex 1.10352 1.15832 2.58915 + vertex 1.09872 1.1583 2.5898 + endloop + endfacet + facet normal 0.137429 -0.144672 0.979889 + outer loop + vertex 1.10831 1.15337 2.58768 + vertex 1.10817 1.15814 2.58841 + vertex 1.10338 1.15325 2.58836 + endloop + endfacet + facet normal 0.173616 -0.155317 0.972489 + outer loop + vertex 1.10352 1.15832 2.58915 + vertex 1.10839 1.16312 2.58904 + vertex 1.10377 1.16326 2.58989 + endloop + endfacet + facet normal 0.202249 -0.123309 0.97154 + outer loop + vertex 1.11253 1.15804 2.58749 + vertex 1.11193 1.16204 2.58812 + vertex 1.10817 1.15814 2.58841 + endloop + endfacet + facet normal 0.174215 -0.144887 0.97399 + outer loop + vertex 1.10839 1.16312 2.58904 + vertex 1.10847 1.16862 2.58985 + vertex 1.10377 1.16326 2.58989 + endloop + endfacet + facet normal 0.133152 -0.154206 0.979026 + outer loop + vertex 1.10352 1.15832 2.58915 + vertex 1.10377 1.16326 2.58989 + vertex 1.09872 1.1583 2.5898 + endloop + endfacet + facet normal 0.129319 -0.158313 0.978884 + outer loop + vertex 1.0935 1.15324 2.58967 + vertex 1.09872 1.1583 2.5898 + vertex 1.094 1.15819 2.5904 + endloop + endfacet + facet normal 0.130804 -0.165378 0.977517 + outer loop + vertex 1.09759 1.16485 2.591 + vertex 1.09353 1.16366 2.59135 + vertex 1.09539 1.162 2.59081 + endloop + endfacet + facet normal 0.13257 -0.171799 0.976171 + outer loop + vertex 1.09759 1.16485 2.591 + vertex 1.09875 1.16857 2.5915 + vertex 1.09353 1.16366 2.59135 + endloop + endfacet + facet normal 0.152397 -0.157197 0.975738 + outer loop + vertex 1.1062 1.17131 2.5909 + vertex 1.10376 1.17351 2.59164 + vertex 1.10278 1.16955 2.59115 + endloop + endfacet + facet normal 0.125289 -0.163229 0.9786 + outer loop + vertex 1.09875 1.16857 2.5915 + vertex 1.09861 1.17331 2.59231 + vertex 1.09352 1.16826 2.59212 + endloop + endfacet + facet normal 0.147831 -0.154583 0.976857 + outer loop + vertex 1.09861 1.17331 2.59231 + vertex 1.10331 1.17826 2.59238 + vertex 1.09843 1.17821 2.59311 + endloop + endfacet + facet normal 0.156392 -0.108681 0.981697 + outer loop + vertex 1.10775 1.17481 2.59115 + vertex 1.10752 1.17814 2.59155 + vertex 1.10376 1.17351 2.59164 + endloop + endfacet + facet normal 0.14807 -0.131101 0.980249 + outer loop + vertex 1.10331 1.17826 2.59238 + vertex 1.10317 1.18318 2.59306 + vertex 1.09843 1.17821 2.59311 + endloop + endfacet + facet normal 0.124512 -0.155967 0.979883 + outer loop + vertex 1.09861 1.17331 2.59231 + vertex 1.09843 1.17821 2.59311 + vertex 1.09339 1.17309 2.59294 + endloop + endfacet + facet normal 0.12466 -0.1626 0.978786 + outer loop + vertex 1.09352 1.16826 2.59212 + vertex 1.09861 1.17331 2.59231 + vertex 1.09339 1.17309 2.59294 + endloop + endfacet + facet normal 0.125326 -0.164163 0.978439 + outer loop + vertex 1.09875 1.16857 2.5915 + vertex 1.09352 1.16826 2.59212 + vertex 1.09353 1.16366 2.59135 + endloop + endfacet + facet normal 0.135136 -0.16058 0.977728 + outer loop + vertex 1.09539 1.162 2.59081 + vertex 1.09353 1.16366 2.59135 + vertex 1.09231 1.15997 2.59091 + endloop + endfacet + facet normal 0.130523 -0.15351 0.979489 + outer loop + vertex 1.09539 1.162 2.59081 + vertex 1.09231 1.15997 2.59091 + vertex 1.094 1.15819 2.5904 + endloop + endfacet + facet normal 0.136624 -0.158904 0.977795 + outer loop + vertex 1.094 1.15819 2.5904 + vertex 1.08877 1.15322 2.59033 + vertex 1.0935 1.15324 2.58967 + endloop + endfacet + facet normal 0.129794 -0.147251 0.980546 + outer loop + vertex 1.09011 1.15706 2.59076 + vertex 1.08832 1.15875 2.59125 + vertex 1.0871 1.15505 2.59086 + endloop + endfacet + facet normal 0.10886 -0.140729 0.984045 + outer loop + vertex 1.0871 1.15505 2.59086 + vertex 1.08832 1.15875 2.59125 + vertex 1.08337 1.15411 2.59113 + endloop + endfacet + facet normal 0.127448 -0.164988 0.978027 + outer loop + vertex 1.08877 1.15322 2.59033 + vertex 1.0836 1.14843 2.59019 + vertex 1.08834 1.14821 2.58954 + endloop + endfacet + facet normal 0.105147 -0.176278 0.978708 + outer loop + vertex 1.0836 1.14843 2.59019 + vertex 1.08215 1.15057 2.59073 + vertex 1.0798 1.14794 2.59051 + endloop + endfacet + facet normal 0.109263 -0.142412 0.983758 + outer loop + vertex 1.0871 1.15505 2.59086 + vertex 1.08337 1.15411 2.59113 + vertex 1.08497 1.15224 2.59068 + endloop + endfacet + facet normal 0.110042 -0.141982 0.983734 + outer loop + vertex 1.08832 1.15875 2.59125 + vertex 1.08335 1.15842 2.59176 + vertex 1.08337 1.15411 2.59113 + endloop + endfacet + facet normal 0.107218 -0.148045 0.983151 + outer loop + vertex 1.08335 1.15842 2.59176 + vertex 1.08836 1.16327 2.59194 + vertex 1.0832 1.16299 2.59246 + endloop + endfacet + facet normal 0.101471 -0.150754 0.98335 + outer loop + vertex 1.0832 1.16299 2.59246 + vertex 1.08827 1.168 2.59271 + vertex 1.08313 1.16792 2.59323 + endloop + endfacet + facet normal 0.0957477 -0.15186 0.983754 + outer loop + vertex 1.08313 1.16792 2.59323 + vertex 1.08824 1.17299 2.59351 + vertex 1.08325 1.17306 2.59401 + endloop + endfacet + facet normal 0.0756643 -0.14871 0.985982 + outer loop + vertex 1.07834 1.17324 2.59443 + vertex 1.08358 1.17815 2.59477 + vertex 1.07857 1.17845 2.5952 + endloop + endfacet + facet normal 0.0750822 -0.156643 0.984797 + outer loop + vertex 1.08414 1.18295 2.59549 + vertex 1.07857 1.17845 2.5952 + vertex 1.08358 1.17815 2.59477 + endloop + endfacet + facet normal 0.0780771 -0.160299 0.983976 + outer loop + vertex 1.0804 1.18253 2.59572 + vertex 1.07857 1.17845 2.5952 + vertex 1.08414 1.18295 2.59549 + endloop + endfacet + facet normal 0.0777575 -0.157154 0.984508 + outer loop + vertex 1.08414 1.18295 2.59549 + vertex 1.08284 1.1851 2.59594 + vertex 1.0804 1.18253 2.59572 + endloop + endfacet + facet normal 0.0626776 -0.14304 0.98773 + outer loop + vertex 1.08284 1.1851 2.59594 + vertex 1.0795 1.18491 2.59612 + vertex 1.0804 1.18253 2.59572 + endloop + endfacet + facet normal 0.0586279 -0.144582 0.987754 + outer loop + vertex 1.0804 1.18253 2.59572 + vertex 1.0795 1.18491 2.59612 + vertex 1.07643 1.18116 2.59576 + endloop + endfacet + facet normal 0.0613234 -0.114387 0.991542 + outer loop + vertex 1.08284 1.1851 2.59594 + vertex 1.08393 1.18862 2.59628 + vertex 1.0795 1.18491 2.59612 + endloop + endfacet + facet normal 0.0689082 -0.123386 0.989963 + outer loop + vertex 1.08393 1.18862 2.59628 + vertex 1.07887 1.18856 2.59662 + vertex 1.0795 1.18491 2.59612 + endloop + endfacet + facet normal 0.0687718 -0.0951977 0.99308 + outer loop + vertex 1.08393 1.18862 2.59628 + vertex 1.08362 1.1932 2.59674 + vertex 1.07887 1.18856 2.59662 + endloop + endfacet + facet normal 0.0788428 -0.105488 0.99129 + outer loop + vertex 1.07887 1.18856 2.59662 + vertex 1.08362 1.1932 2.59674 + vertex 1.07845 1.1931 2.59714 + endloop + endfacet + facet normal 0.0739488 -0.105972 0.991616 + outer loop + vertex 1.07887 1.18856 2.59662 + vertex 1.07845 1.1931 2.59714 + vertex 1.07353 1.1882 2.59698 + endloop + endfacet + facet normal 0.0757666 -0.136926 0.987679 + outer loop + vertex 1.07397 1.18357 2.5963 + vertex 1.07887 1.18856 2.59662 + vertex 1.07353 1.1882 2.59698 + endloop + endfacet + facet normal 0.0628787 -0.12446 0.99023 + outer loop + vertex 1.0795 1.18491 2.59612 + vertex 1.07887 1.18856 2.59662 + vertex 1.07397 1.18357 2.5963 + endloop + endfacet + facet normal 0.0698253 -0.153522 0.985675 + outer loop + vertex 1.0795 1.18491 2.59612 + vertex 1.07397 1.18357 2.5963 + vertex 1.07643 1.18116 2.59576 + endloop + endfacet + facet normal 0.0681593 -0.155189 0.985531 + outer loop + vertex 1.07643 1.18116 2.59576 + vertex 1.07397 1.18357 2.5963 + vertex 1.07246 1.17974 2.59581 + endloop + endfacet + facet normal 0.0667828 -0.151298 0.98623 + outer loop + vertex 1.07246 1.17974 2.59581 + vertex 1.0733 1.17735 2.59538 + vertex 1.07643 1.18116 2.59576 + endloop + endfacet + facet normal 0.0654235 -0.150208 0.986487 + outer loop + vertex 1.0733 1.17735 2.59538 + vertex 1.07857 1.17845 2.5952 + vertex 1.07643 1.18116 2.59576 + endloop + endfacet + facet normal 0.0627846 -0.137266 0.988542 + outer loop + vertex 1.07342 1.1733 2.59481 + vertex 1.07857 1.17845 2.5952 + vertex 1.0733 1.17735 2.59538 + endloop + endfacet + facet normal 0.0744107 -0.14867 0.986083 + outer loop + vertex 1.07834 1.17324 2.59443 + vertex 1.07857 1.17845 2.5952 + vertex 1.07342 1.1733 2.59481 + endloop + endfacet + facet normal 0.0746124 -0.139687 0.987381 + outer loop + vertex 1.0732 1.16821 2.59411 + vertex 1.07834 1.17324 2.59443 + vertex 1.07342 1.1733 2.59481 + endloop + endfacet + facet normal 0.0815517 -0.146682 0.985816 + outer loop + vertex 1.07811 1.16802 2.59367 + vertex 1.07834 1.17324 2.59443 + vertex 1.0732 1.16821 2.59411 + endloop + endfacet + facet normal 0.0818122 -0.141716 0.986521 + outer loop + vertex 1.07304 1.16295 2.59337 + vertex 1.07811 1.16802 2.59367 + vertex 1.0732 1.16821 2.59411 + endloop + endfacet + facet normal 0.0867183 -0.146567 0.985392 + outer loop + vertex 1.07808 1.16289 2.59291 + vertex 1.07811 1.16802 2.59367 + vertex 1.07304 1.16295 2.59337 + endloop + endfacet + facet normal 0.0867515 -0.145312 0.985575 + outer loop + vertex 1.07313 1.15791 2.59262 + vertex 1.07808 1.16289 2.59291 + vertex 1.07304 1.16295 2.59337 + endloop + endfacet + facet normal 0.0887617 -0.147286 0.985103 + outer loop + vertex 1.07829 1.15811 2.59218 + vertex 1.07808 1.16289 2.59291 + vertex 1.07313 1.15791 2.59262 + endloop + endfacet + facet normal 0.088835 -0.150141 0.984665 + outer loop + vertex 1.07361 1.15337 2.59188 + vertex 1.07829 1.15811 2.59218 + vertex 1.07313 1.15791 2.59262 + endloop + endfacet + facet normal 0.0859874 -0.147375 0.985336 + outer loop + vertex 1.0787 1.15391 2.59152 + vertex 1.07829 1.15811 2.59218 + vertex 1.07361 1.15337 2.59188 + endloop + endfacet + facet normal 0.087023 -0.158301 0.983549 + outer loop + vertex 1.07467 1.14971 2.5912 + vertex 1.0787 1.15391 2.59152 + vertex 1.07361 1.15337 2.59188 + endloop + endfacet + facet normal 0.0761785 -0.148097 0.986035 + outer loop + vertex 1.07911 1.15043 2.59096 + vertex 1.0787 1.15391 2.59152 + vertex 1.07467 1.14971 2.5912 + endloop + endfacet + facet normal 0.0820785 -0.114093 0.990074 + outer loop + vertex 1.07353 1.1882 2.59698 + vertex 1.07845 1.1931 2.59714 + vertex 1.07326 1.19295 2.59755 + endloop + endfacet + facet normal 0.0675851 -0.116254 0.990917 + outer loop + vertex 1.0856 1.18653 2.59592 + vertex 1.08393 1.18862 2.59628 + vertex 1.08284 1.1851 2.59594 + endloop + endfacet + facet normal 0.0772205 -0.108618 0.99108 + outer loop + vertex 1.08769 1.18917 2.59604 + vertex 1.08393 1.18862 2.59628 + vertex 1.0856 1.18653 2.59592 + endloop + endfacet + facet normal 0.101875 -0.127949 0.986535 + outer loop + vertex 1.08854 1.18683 2.59565 + vertex 1.08769 1.18917 2.59604 + vertex 1.0856 1.18653 2.59592 + endloop + endfacet + facet normal 0.104621 -0.159275 0.981675 + outer loop + vertex 1.0856 1.18653 2.59592 + vertex 1.08414 1.18295 2.59549 + vertex 1.08854 1.18683 2.59565 + endloop + endfacet + facet normal 0.0975534 -0.151318 0.98366 + outer loop + vertex 1.08854 1.18683 2.59565 + vertex 1.08414 1.18295 2.59549 + vertex 1.08864 1.18297 2.59505 + endloop + endfacet + facet normal 0.110902 -0.124572 0.985993 + outer loop + vertex 1.08769 1.18917 2.59604 + vertex 1.08854 1.18683 2.59565 + vertex 1.09097 1.19079 2.59588 + endloop + endfacet + facet normal 0.0933486 -0.0883323 0.991707 + outer loop + vertex 1.09097 1.19079 2.59588 + vertex 1.08862 1.19309 2.5963 + vertex 1.08769 1.18917 2.59604 + endloop + endfacet + facet normal 0.0948493 -0.0867957 0.991701 + outer loop + vertex 1.09253 1.19421 2.59603 + vertex 1.08862 1.19309 2.5963 + vertex 1.09097 1.19079 2.59588 + endloop + endfacet + facet normal 0.111134 -0.0941137 0.989339 + outer loop + vertex 1.09429 1.19286 2.5957 + vertex 1.09253 1.19421 2.59603 + vertex 1.09097 1.19079 2.59588 + endloop + endfacet + facet normal 0.127012 -0.120019 0.984613 + outer loop + vertex 1.09429 1.19286 2.5957 + vertex 1.09097 1.19079 2.59588 + vertex 1.09334 1.18849 2.59529 + endloop + endfacet + facet normal 0.118279 -0.129015 0.984563 + outer loop + vertex 1.08854 1.18683 2.59565 + vertex 1.09334 1.18849 2.59529 + vertex 1.09097 1.19079 2.59588 + endloop + endfacet + facet normal 0.0737808 -0.0838269 0.993745 + outer loop + vertex 1.08769 1.18917 2.59604 + vertex 1.08862 1.19309 2.5963 + vertex 1.08393 1.18862 2.59628 + endloop + endfacet + facet normal 0.0835651 -0.0941018 0.992049 + outer loop + vertex 1.08862 1.19309 2.5963 + vertex 1.08362 1.1932 2.59674 + vertex 1.08393 1.18862 2.59628 + endloop + endfacet + facet normal 0.0861797 -0.152095 0.984601 + outer loop + vertex 1.0856 1.18653 2.59592 + vertex 1.08284 1.1851 2.59594 + vertex 1.08414 1.18295 2.59549 + endloop + endfacet + facet normal 0.0615962 -0.153187 0.986276 + outer loop + vertex 1.0804 1.18253 2.59572 + vertex 1.07643 1.18116 2.59576 + vertex 1.07857 1.17845 2.5952 + endloop + endfacet + facet normal 0.095607 -0.156814 0.98299 + outer loop + vertex 1.08824 1.17299 2.59351 + vertex 1.0884 1.17807 2.59431 + vertex 1.08325 1.17306 2.59401 + endloop + endfacet + facet normal 0.0974571 -0.158902 0.982473 + outer loop + vertex 1.08358 1.17815 2.59477 + vertex 1.08864 1.18297 2.59505 + vertex 1.08414 1.18295 2.59549 + endloop + endfacet + facet normal 0.110164 -0.152202 0.982191 + outer loop + vertex 1.09336 1.17812 2.59376 + vertex 1.09346 1.18324 2.59454 + vertex 1.0884 1.17807 2.59431 + endloop + endfacet + facet normal 0.1253 -0.150172 0.980688 + outer loop + vertex 1.08864 1.18297 2.59505 + vertex 1.09334 1.18849 2.59529 + vertex 1.08854 1.18683 2.59565 + endloop + endfacet + facet normal 0.132226 -0.131451 0.982465 + outer loop + vertex 1.09839 1.18329 2.59388 + vertex 1.09842 1.18852 2.59458 + vertex 1.09346 1.18324 2.59454 + endloop + endfacet + facet normal 0.160492 -0.126763 0.978863 + outer loop + vertex 1.09429 1.19286 2.5957 + vertex 1.09334 1.18849 2.59529 + vertex 1.0984 1.1941 2.59519 + endloop + endfacet + facet normal 0.179402 -0.0976501 0.978918 + outer loop + vertex 1.10316 1.18826 2.59368 + vertex 1.1032 1.19344 2.59419 + vertex 1.09842 1.18852 2.59458 + endloop + endfacet + facet normal 0.293928 -0.0768065 0.952737 + outer loop + vertex 1.1032 1.19344 2.59419 + vertex 1.10745 1.19768 2.59322 + vertex 1.10345 1.19869 2.59454 + endloop + endfacet + facet normal 0.277473 -0.058887 0.958927 + outer loop + vertex 1.10742 1.19265 2.59292 + vertex 1.10745 1.19768 2.59322 + vertex 1.1032 1.19344 2.59419 + endloop + endfacet + facet normal 0.105051 -0.068681 0.992092 + outer loop + vertex 1.08837 1.19801 2.59668 + vertex 1.09365 1.20315 2.59648 + vertex 1.08839 1.20309 2.59703 + endloop + endfacet + facet normal 0.0976499 -0.0610358 0.993347 + outer loop + vertex 1.09262 1.19769 2.59624 + vertex 1.09365 1.20315 2.59648 + vertex 1.08837 1.19801 2.59668 + endloop + endfacet + facet normal 0.117206 -0.0646193 0.991003 + outer loop + vertex 1.09365 1.20315 2.59648 + vertex 1.09262 1.19769 2.59624 + vertex 1.09666 1.2011 2.59599 + endloop + endfacet + facet normal 0.113117 -0.0597174 0.991785 + outer loop + vertex 1.09666 1.2011 2.59599 + vertex 1.09262 1.19769 2.59624 + vertex 1.09575 1.19662 2.59582 + endloop + endfacet + facet normal 0.15084 -0.0671972 0.986272 + outer loop + vertex 1.09575 1.19662 2.59582 + vertex 1.09977 1.1998 2.59543 + vertex 1.09666 1.2011 2.59599 + endloop + endfacet + facet normal 0.152483 -0.0632685 0.986279 + outer loop + vertex 1.09977 1.1998 2.59543 + vertex 1.10039 1.20435 2.59562 + vertex 1.09666 1.2011 2.59599 + endloop + endfacet + facet normal 0.232893 -0.0735802 0.969715 + outer loop + vertex 1.09977 1.1998 2.59543 + vertex 1.10378 1.20377 2.59476 + vertex 1.10039 1.20435 2.59562 + endloop + endfacet + facet normal 0.21741 -0.0571241 0.974407 + outer loop + vertex 1.10345 1.19869 2.59454 + vertex 1.10378 1.20377 2.59476 + vertex 1.09977 1.1998 2.59543 + endloop + endfacet + facet normal 0.331517 -0.0630551 0.94134 + outer loop + vertex 1.10345 1.19869 2.59454 + vertex 1.10747 1.20271 2.59339 + vertex 1.10378 1.20377 2.59476 + endloop + endfacet + facet normal 0.341673 -0.0253261 0.939478 + outer loop + vertex 1.10747 1.20271 2.59339 + vertex 1.10743 1.20783 2.59354 + vertex 1.10378 1.20377 2.59476 + endloop + endfacet + facet normal 0.304655 -0.0332537 0.951882 + outer loop + vertex 1.10745 1.19768 2.59322 + vertex 1.10747 1.20271 2.59339 + vertex 1.10345 1.19869 2.59454 + endloop + endfacet + facet normal 0.105185 -0.0777591 0.991408 + outer loop + vertex 1.08839 1.20309 2.59703 + vertex 1.09339 1.20834 2.59691 + vertex 1.08837 1.20812 2.59743 + endloop + endfacet + facet normal 0.105869 -0.0970781 0.98963 + outer loop + vertex 1.09339 1.20834 2.59691 + vertex 1.09339 1.21327 2.5974 + vertex 1.08837 1.20812 2.59743 + endloop + endfacet + facet normal 0.128961 -0.0967802 0.986916 + outer loop + vertex 1.09339 1.20834 2.59691 + vertex 1.09799 1.21343 2.59681 + vertex 1.09339 1.21327 2.5974 + endloop + endfacet + facet normal 0.1263 -0.0943646 0.987494 + outer loop + vertex 1.09822 1.20883 2.59634 + vertex 1.09799 1.21343 2.59681 + vertex 1.09339 1.20834 2.59691 + endloop + endfacet + facet normal 0.124711 -0.0765278 0.989237 + outer loop + vertex 1.09822 1.20883 2.59634 + vertex 1.09339 1.20834 2.59691 + vertex 1.09365 1.20315 2.59648 + endloop + endfacet + facet normal 0.125144 -0.0768783 0.989156 + outer loop + vertex 1.09787 1.20501 2.59609 + vertex 1.09822 1.20883 2.59634 + vertex 1.09365 1.20315 2.59648 + endloop + endfacet + facet normal 0.118848 -0.0621971 0.990962 + outer loop + vertex 1.09787 1.20501 2.59609 + vertex 1.09365 1.20315 2.59648 + vertex 1.09666 1.2011 2.59599 + endloop + endfacet + facet normal 0.163114 -0.0757534 0.983695 + outer loop + vertex 1.10039 1.20435 2.59562 + vertex 1.09787 1.20501 2.59609 + vertex 1.09666 1.2011 2.59599 + endloop + endfacet + facet normal 0.162013 -0.0798521 0.983552 + outer loop + vertex 1.10046 1.20752 2.59587 + vertex 1.09787 1.20501 2.59609 + vertex 1.10039 1.20435 2.59562 + endloop + endfacet + facet normal 0.248563 -0.0802734 0.965284 + outer loop + vertex 1.10046 1.20752 2.59587 + vertex 1.10039 1.20435 2.59562 + vertex 1.10372 1.20867 2.59512 + endloop + endfacet + facet normal 0.233827 -0.0683789 0.969871 + outer loop + vertex 1.10372 1.20867 2.59512 + vertex 1.10039 1.20435 2.59562 + vertex 1.10378 1.20377 2.59476 + endloop + endfacet + facet normal 0.162037 -0.0798771 0.983547 + outer loop + vertex 1.10046 1.20752 2.59587 + vertex 1.09822 1.20883 2.59634 + vertex 1.09787 1.20501 2.59609 + endloop + endfacet + facet normal 0.172929 -0.0912708 0.980696 + outer loop + vertex 1.10176 1.21344 2.59615 + vertex 1.09799 1.21343 2.59681 + vertex 1.09822 1.20883 2.59634 + endloop + endfacet + facet normal 0.169475 -0.0885845 0.981545 + outer loop + vertex 1.1018 1.21035 2.59586 + vertex 1.10176 1.21344 2.59615 + vertex 1.09822 1.20883 2.59634 + endloop + endfacet + facet normal 0.16433 -0.0759346 0.983478 + outer loop + vertex 1.1018 1.21035 2.59586 + vertex 1.09822 1.20883 2.59634 + vertex 1.10046 1.20752 2.59587 + endloop + endfacet + facet normal 0.26151 -0.121913 0.957471 + outer loop + vertex 1.10372 1.20867 2.59512 + vertex 1.1018 1.21035 2.59586 + vertex 1.10046 1.20752 2.59587 + endloop + endfacet + facet normal 0.105087 -0.0776659 0.991426 + outer loop + vertex 1.09365 1.20315 2.59648 + vertex 1.09339 1.20834 2.59691 + vertex 1.08839 1.20309 2.59703 + endloop + endfacet + facet normal 0.104202 -0.0954532 0.989965 + outer loop + vertex 1.08837 1.20812 2.59743 + vertex 1.09339 1.21327 2.5974 + vertex 1.08838 1.21309 2.59791 + endloop + endfacet + facet normal 0.0882836 -0.111905 0.989789 + outer loop + vertex 1.07815 1.21298 2.59884 + vertex 1.08326 1.21804 2.59896 + vertex 1.07824 1.21809 2.59941 + endloop + endfacet + facet normal 0.0879825 -0.126019 0.988119 + outer loop + vertex 1.08326 1.21804 2.59896 + vertex 1.08332 1.22316 2.5996 + vertex 1.07824 1.21809 2.59941 + endloop + endfacet + facet normal 0.0869162 -0.119573 0.989014 + outer loop + vertex 1.07344 1.21824 2.59987 + vertex 1.07841 1.22304 2.60001 + vertex 1.07384 1.22309 2.60042 + endloop + endfacet + facet normal 0.0865211 -0.122391 0.988703 + outer loop + vertex 1.0752 1.22674 2.60075 + vertex 1.0723 1.22506 2.6008 + vertex 1.07384 1.22309 2.60042 + endloop + endfacet + facet normal 0.0839777 -0.117393 0.989529 + outer loop + vertex 1.0775 1.22938 2.60087 + vertex 1.07829 1.22699 2.60052 + vertex 1.08117 1.23093 2.60074 + endloop + endfacet + facet normal 0.0842211 -0.118388 0.989389 + outer loop + vertex 1.0752 1.22674 2.60075 + vertex 1.07354 1.22862 2.60112 + vertex 1.0723 1.22506 2.6008 + endloop + endfacet + facet normal 0.0810121 -0.110294 0.990592 + outer loop + vertex 1.08117 1.23093 2.60074 + vertex 1.07887 1.23335 2.6012 + vertex 1.0775 1.22938 2.60087 + endloop + endfacet + facet normal 0.0776593 -0.113503 0.990498 + outer loop + vertex 1.07887 1.23335 2.6012 + vertex 1.08362 1.23857 2.60142 + vertex 1.07852 1.23808 2.60177 + endloop + endfacet + facet normal 0.087765 -0.120615 0.988812 + outer loop + vertex 1.07335 1.23788 2.6022 + vertex 1.07833 1.24287 2.60237 + vertex 1.0732 1.2428 2.60282 + endloop + endfacet + facet normal 0.0785049 -0.123207 0.989271 + outer loop + vertex 1.08362 1.23857 2.60142 + vertex 1.08345 1.24309 2.602 + vertex 1.07852 1.23808 2.60177 + endloop + endfacet + facet normal 0.0758757 -0.13227 0.988305 + outer loop + vertex 1.08345 1.24309 2.602 + vertex 1.08839 1.24811 2.60229 + vertex 1.08338 1.24794 2.60266 + endloop + endfacet + facet normal 0.0759441 -0.135201 0.987903 + outer loop + vertex 1.08839 1.24811 2.60229 + vertex 1.08838 1.25303 2.60297 + vertex 1.08338 1.24794 2.60266 + endloop + endfacet + facet normal 0.134395 -0.130349 0.982317 + outer loop + vertex 1.08838 1.25303 2.60297 + vertex 1.09305 1.25795 2.60298 + vertex 1.08838 1.25807 2.60364 + endloop + endfacet + facet normal 0.157801 -0.114642 0.980794 + outer loop + vertex 1.08838 1.25807 2.60364 + vertex 1.09305 1.26301 2.60346 + vertex 1.08841 1.26314 2.60422 + endloop + endfacet + facet normal 0.159488 -0.0749635 0.98435 + outer loop + vertex 1.09305 1.26301 2.60346 + vertex 1.09308 1.26812 2.60385 + vertex 1.08841 1.26314 2.60422 + endloop + endfacet + facet normal 0.095923 -0.137765 0.985809 + outer loop + vertex 1.09011 1.27749 2.60579 + vertex 1.089 1.27972 2.60621 + vertex 1.08638 1.27585 2.60592 + endloop + endfacet + facet normal 0.126066 -0.0518829 0.990664 + outer loop + vertex 1.09201 1.28328 2.60609 + vertex 1.092 1.28752 2.60631 + vertex 1.08828 1.28332 2.60656 + endloop + endfacet + facet normal 0.154526 -0.0773397 0.984957 + outer loop + vertex 1.08828 1.28332 2.60656 + vertex 1.092 1.28752 2.60631 + vertex 1.08804 1.28795 2.60696 + endloop + endfacet + facet normal 0.15646 -0.0608063 0.985811 + outer loop + vertex 1.092 1.28752 2.60631 + vertex 1.09198 1.2924 2.60661 + vertex 1.08804 1.28795 2.60696 + endloop + endfacet + facet normal 0.18695 -0.0883956 0.978384 + outer loop + vertex 1.08804 1.28795 2.60696 + vertex 1.09198 1.2924 2.60661 + vertex 1.08798 1.29293 2.60742 + endloop + endfacet + facet normal 0.189611 -0.0701027 0.979354 + outer loop + vertex 1.09198 1.2924 2.60661 + vertex 1.09199 1.29741 2.60697 + vertex 1.08798 1.29293 2.60742 + endloop + endfacet + facet normal 0.218506 -0.0967889 0.971024 + outer loop + vertex 1.08798 1.29293 2.60742 + vertex 1.09199 1.29741 2.60697 + vertex 1.08802 1.29796 2.60792 + endloop + endfacet + facet normal 0.222277 -0.0718867 0.97233 + outer loop + vertex 1.09199 1.29741 2.60697 + vertex 1.09205 1.30241 2.60732 + vertex 1.08802 1.29796 2.60792 + endloop + endfacet + facet normal 0.243474 -0.0920187 0.965532 + outer loop + vertex 1.08802 1.29796 2.60792 + vertex 1.09205 1.30241 2.60732 + vertex 1.08809 1.30294 2.60838 + endloop + endfacet + facet normal 0.249865 -0.0479345 0.967093 + outer loop + vertex 1.09205 1.30241 2.60732 + vertex 1.09212 1.30739 2.60755 + vertex 1.08809 1.30294 2.60838 + endloop + endfacet + facet normal 0.277168 -0.0743808 0.957938 + outer loop + vertex 1.08809 1.30294 2.60838 + vertex 1.09212 1.30739 2.60755 + vertex 1.08812 1.30796 2.60875 + endloop + endfacet + facet normal 0.0442681 -0.10337 0.993657 + outer loop + vertex 1.089 1.27972 2.60621 + vertex 1.08391 1.27828 2.60628 + vertex 1.08638 1.27585 2.60592 + endloop + endfacet + facet normal 0.0387181 -0.109371 0.993247 + outer loop + vertex 1.08334 1.27194 2.60561 + vertex 1.08248 1.27431 2.6059 + vertex 1.08 1.27168 2.60571 + endloop + endfacet + facet normal 0.100118 -0.147424 0.983993 + outer loop + vertex 1.09011 1.27749 2.60579 + vertex 1.08638 1.27585 2.60592 + vertex 1.08852 1.27333 2.60533 + endloop + endfacet + facet normal 0.0919268 -0.113512 0.989275 + outer loop + vertex 1.08849 1.26821 2.60474 + vertex 1.08852 1.27333 2.60533 + vertex 1.08353 1.26803 2.60518 + endloop + endfacet + facet normal 0.0370732 -0.0878116 0.995447 + outer loop + vertex 1.08 1.27168 2.60571 + vertex 1.07867 1.26804 2.60544 + vertex 1.08334 1.27194 2.60561 + endloop + endfacet + facet normal 0.0917909 -0.108221 0.98988 + outer loop + vertex 1.08344 1.26314 2.60466 + vertex 1.08849 1.26821 2.60474 + vertex 1.08353 1.26803 2.60518 + endloop + endfacet + facet normal 0.0695795 -0.133443 0.988611 + outer loop + vertex 1.08335 1.25296 2.60336 + vertex 1.08336 1.25806 2.60404 + vertex 1.07822 1.25295 2.60371 + endloop + endfacet + facet normal 0.0695821 -0.133069 0.988661 + outer loop + vertex 1.07824 1.24785 2.60303 + vertex 1.08335 1.25296 2.60336 + vertex 1.07822 1.25295 2.60371 + endloop + endfacet + facet normal 0.0877922 -0.128771 0.987781 + outer loop + vertex 1.07833 1.24287 2.60237 + vertex 1.07824 1.24785 2.60303 + vertex 1.0732 1.2428 2.60282 + endloop + endfacet + facet normal 0.101937 -0.120021 0.987524 + outer loop + vertex 1.07335 1.23788 2.6022 + vertex 1.0732 1.2428 2.60282 + vertex 1.06819 1.23778 2.60272 + endloop + endfacet + facet normal 0.101916 -0.117454 0.987835 + outer loop + vertex 1.06834 1.23293 2.60213 + vertex 1.07335 1.23788 2.6022 + vertex 1.06819 1.23778 2.60272 + endloop + endfacet + facet normal 0.116757 -0.115042 0.986475 + outer loop + vertex 1.06844 1.22833 2.60158 + vertex 1.06834 1.23293 2.60213 + vertex 1.06326 1.22795 2.60215 + endloop + endfacet + facet normal 0.146958 -0.114877 0.982449 + outer loop + vertex 1.06328 1.22339 2.60161 + vertex 1.06326 1.22795 2.60215 + vertex 1.05819 1.22296 2.60233 + endloop + endfacet + facet normal 0.135247 -0.10932 0.984763 + outer loop + vertex 1.05814 1.22781 2.60287 + vertex 1.06316 1.23277 2.60273 + vertex 1.05813 1.23289 2.60343 + endloop + endfacet + facet normal 0.129737 -0.111177 0.985296 + outer loop + vertex 1.05813 1.23289 2.60343 + vertex 1.06311 1.2378 2.60333 + vertex 1.05824 1.2381 2.604 + endloop + endfacet + facet normal 0.131052 -0.1049 0.98581 + outer loop + vertex 1.05382 1.23871 2.6047 + vertex 1.05844 1.24329 2.60457 + vertex 1.05389 1.24381 2.60523 + endloop + endfacet + facet normal 0.129141 -0.119081 0.98445 + outer loop + vertex 1.06311 1.2378 2.60333 + vertex 1.06315 1.24296 2.60395 + vertex 1.05824 1.2381 2.604 + endloop + endfacet + facet normal 0.116237 -0.116137 0.986408 + outer loop + vertex 1.05844 1.24329 2.60457 + vertex 1.06329 1.24814 2.60457 + vertex 1.05878 1.24822 2.60511 + endloop + endfacet + facet normal 0.115349 -0.124297 0.985518 + outer loop + vertex 1.06811 1.24281 2.60335 + vertex 1.06812 1.24796 2.604 + vertex 1.06315 1.24296 2.60395 + endloop + endfacet + facet normal 0.111475 -0.124775 0.985903 + outer loop + vertex 1.06329 1.24814 2.60457 + vertex 1.06824 1.25319 2.60465 + vertex 1.06335 1.25337 2.60523 + endloop + endfacet + facet normal 0.111512 -0.124082 0.985986 + outer loop + vertex 1.06855 1.25842 2.60528 + vertex 1.06335 1.25337 2.60523 + vertex 1.06824 1.25319 2.60465 + endloop + endfacet + facet normal 0.113652 -0.126281 0.985463 + outer loop + vertex 1.06482 1.25766 2.60561 + vertex 1.06335 1.25337 2.60523 + vertex 1.06855 1.25842 2.60528 + endloop + endfacet + facet normal 0.11201 -0.117726 0.986709 + outer loop + vertex 1.06855 1.25842 2.60528 + vertex 1.06705 1.26055 2.6057 + vertex 1.06482 1.25766 2.60561 + endloop + endfacet + facet normal 0.108238 -0.114846 0.987469 + outer loop + vertex 1.06705 1.26055 2.6057 + vertex 1.06397 1.26001 2.60598 + vertex 1.06482 1.25766 2.60561 + endloop + endfacet + facet normal 0.106368 -0.115544 0.987591 + outer loop + vertex 1.06482 1.25766 2.60561 + vertex 1.06397 1.26001 2.60598 + vertex 1.06126 1.25593 2.60579 + endloop + endfacet + facet normal 0.10623 -0.102513 0.989043 + outer loop + vertex 1.06705 1.26055 2.6057 + vertex 1.06821 1.26419 2.60595 + vertex 1.06397 1.26001 2.60598 + endloop + endfacet + facet normal 0.104991 -0.101254 0.989305 + outer loop + vertex 1.06821 1.26419 2.60595 + vertex 1.06353 1.26361 2.60639 + vertex 1.06397 1.26001 2.60598 + endloop + endfacet + facet normal 0.101376 -0.128264 0.986545 + outer loop + vertex 1.07313 1.24787 2.60347 + vertex 1.07316 1.25303 2.60414 + vertex 1.06812 1.24796 2.604 + endloop + endfacet + facet normal 0.0983731 -0.123472 0.98746 + outer loop + vertex 1.06824 1.25319 2.60465 + vertex 1.07331 1.25824 2.60478 + vertex 1.06855 1.25842 2.60528 + endloop + endfacet + facet normal 0.114706 -0.115804 0.986627 + outer loop + vertex 1.06981 1.26241 2.6056 + vertex 1.06705 1.26055 2.6057 + vertex 1.06855 1.25842 2.60528 + endloop + endfacet + facet normal 0.0909444 -0.097496 0.991072 + outer loop + vertex 1.07481 1.26724 2.6056 + vertex 1.07187 1.2653 2.60568 + vertex 1.07359 1.26335 2.60533 + endloop + endfacet + facet normal 0.105737 -0.10236 0.989112 + outer loop + vertex 1.06981 1.26241 2.6056 + vertex 1.06821 1.26419 2.60595 + vertex 1.06705 1.26055 2.6057 + endloop + endfacet + facet normal 0.0925351 -0.0999267 0.990683 + outer loop + vertex 1.07481 1.26724 2.6056 + vertex 1.0731 1.26892 2.60593 + vertex 1.07187 1.2653 2.60568 + endloop + endfacet + facet normal 0.104106 -0.0934963 0.990162 + outer loop + vertex 1.06821 1.26419 2.60595 + vertex 1.06829 1.26848 2.60635 + vertex 1.06353 1.26361 2.60639 + endloop + endfacet + facet normal 0.0677826 -0.0947866 0.993187 + outer loop + vertex 1.07836 1.27357 2.60601 + vertex 1.07331 1.27332 2.60634 + vertex 1.0731 1.26892 2.60593 + endloop + endfacet + facet normal 0.0680391 -0.100848 0.992573 + outer loop + vertex 1.07836 1.27357 2.60601 + vertex 1.07851 1.27816 2.60647 + vertex 1.07331 1.27332 2.60634 + endloop + endfacet + facet normal 0.0543707 -0.0862168 0.994792 + outer loop + vertex 1.07331 1.27332 2.60634 + vertex 1.07851 1.27816 2.60647 + vertex 1.07335 1.27797 2.60674 + endloop + endfacet + facet normal 0.0545316 -0.0911342 0.994344 + outer loop + vertex 1.07851 1.27816 2.60647 + vertex 1.07844 1.28297 2.60692 + vertex 1.07335 1.27797 2.60674 + endloop + endfacet + facet normal 0.0484197 -0.0849438 0.995209 + outer loop + vertex 1.07335 1.27797 2.60674 + vertex 1.07844 1.28297 2.60692 + vertex 1.07333 1.28287 2.60716 + endloop + endfacet + facet normal 0.0485939 -0.0956809 0.994225 + outer loop + vertex 1.07844 1.28297 2.60692 + vertex 1.0784 1.28796 2.6074 + vertex 1.07333 1.28287 2.60716 + endloop + endfacet + facet normal 0.0455972 -0.0927141 0.994648 + outer loop + vertex 1.07333 1.28287 2.60716 + vertex 1.0784 1.28796 2.6074 + vertex 1.0733 1.28787 2.60762 + endloop + endfacet + facet normal 0.0457813 -0.106381 0.993271 + outer loop + vertex 1.0784 1.28796 2.6074 + vertex 1.07839 1.29297 2.60793 + vertex 1.0733 1.28787 2.60762 + endloop + endfacet + facet normal 0.045387 -0.105992 0.993331 + outer loop + vertex 1.0733 1.28787 2.60762 + vertex 1.07839 1.29297 2.60793 + vertex 1.07327 1.29286 2.60816 + endloop + endfacet + facet normal 0.0455523 -0.116054 0.992198 + outer loop + vertex 1.07839 1.29297 2.60793 + vertex 1.0784 1.29797 2.60852 + vertex 1.07327 1.29286 2.60816 + endloop + endfacet + facet normal 0.0794109 -0.118107 0.98982 + outer loop + vertex 1.06817 1.29285 2.60856 + vertex 1.07325 1.2979 2.60876 + vertex 1.0682 1.29797 2.60917 + endloop + endfacet + facet normal 0.0505137 -0.120184 0.991466 + outer loop + vertex 1.07325 1.2979 2.60876 + vertex 1.07842 1.303 2.60911 + vertex 1.07334 1.30302 2.60937 + endloop + endfacet + facet normal 0.0506145 -0.110059 0.992635 + outer loop + vertex 1.07842 1.303 2.60911 + vertex 1.07847 1.30805 2.60967 + vertex 1.07334 1.30302 2.60937 + endloop + endfacet + facet normal 0.0401429 -0.109292 0.993199 + outer loop + vertex 1.08341 1.29806 2.60833 + vertex 1.08345 1.30305 2.60887 + vertex 1.0784 1.29797 2.60852 + endloop + endfacet + facet normal 0.0402452 -0.116075 0.992425 + outer loop + vertex 1.07839 1.29297 2.60793 + vertex 1.08341 1.29806 2.60833 + vertex 1.0784 1.29797 2.60852 + endloop + endfacet + facet normal 0.0378715 -0.0791045 0.996147 + outer loop + vertex 1.07529 1.31701 2.61067 + vertex 1.07396 1.31314 2.61041 + vertex 1.07895 1.31745 2.61056 + endloop + endfacet + facet normal 0.0532355 -0.0996353 0.993599 + outer loop + vertex 1.07847 1.30805 2.60967 + vertex 1.07854 1.31285 2.61015 + vertex 1.07357 1.30814 2.60994 + endloop + endfacet + facet normal 0.081729 -0.114629 0.990041 + outer loop + vertex 1.06841 1.30315 2.60979 + vertex 1.07357 1.30814 2.60994 + vertex 1.06879 1.30823 2.61035 + endloop + endfacet + facet normal 0.0734795 -0.0911345 0.993124 + outer loop + vertex 1.07529 1.31701 2.61067 + vertex 1.07225 1.31511 2.61072 + vertex 1.07396 1.31314 2.61041 + endloop + endfacet + facet normal 0.107109 -0.120384 0.986932 + outer loop + vertex 1.07225 1.31511 2.61072 + vertex 1.07346 1.31872 2.61103 + vertex 1.06828 1.31383 2.61099 + endloop + endfacet + facet normal 0.0949673 -0.107542 0.989654 + outer loop + vertex 1.07346 1.31872 2.61103 + vertex 1.0684 1.31831 2.61147 + vertex 1.06828 1.31383 2.61099 + endloop + endfacet + facet normal 0.105363 -0.105197 0.988854 + outer loop + vertex 1.07008 1.31218 2.61063 + vertex 1.06706 1.31009 2.61073 + vertex 1.06879 1.30823 2.61035 + endloop + endfacet + facet normal 0.107823 -0.116272 0.987347 + outer loop + vertex 1.06879 1.30823 2.61035 + vertex 1.06366 1.30325 2.61032 + vertex 1.06841 1.30315 2.60979 + endloop + endfacet + facet normal 0.10602 -0.106991 0.988591 + outer loop + vertex 1.06493 1.30715 2.61064 + vertex 1.06318 1.30882 2.61101 + vertex 1.06196 1.30511 2.61074 + endloop + endfacet + facet normal 0.101833 -0.105656 0.989175 + outer loop + vertex 1.06196 1.30511 2.61074 + vertex 1.06318 1.30882 2.61101 + vertex 1.05814 1.30389 2.61101 + endloop + endfacet + facet normal 0.115967 -0.122896 0.985621 + outer loop + vertex 1.06366 1.30325 2.61032 + vertex 1.0586 1.29833 2.6103 + vertex 1.06332 1.29815 2.60973 + endloop + endfacet + facet normal 0.110199 -0.118314 0.986842 + outer loop + vertex 1.0586 1.29833 2.6103 + vertex 1.05691 1.30024 2.61072 + vertex 1.05481 1.29735 2.61061 + endloop + endfacet + facet normal 0.103834 -0.112125 0.988254 + outer loop + vertex 1.06196 1.30511 2.61074 + vertex 1.05814 1.30389 2.61101 + vertex 1.05985 1.30223 2.61064 + endloop + endfacet + facet normal 0.114408 -0.110161 0.987307 + outer loop + vertex 1.0531 1.29897 2.61098 + vertex 1.05333 1.30335 2.61144 + vertex 1.04828 1.29833 2.61147 + endloop + endfacet + facet normal 0.10206 -0.105889 0.989127 + outer loop + vertex 1.06318 1.30882 2.61101 + vertex 1.05835 1.30832 2.61146 + vertex 1.05814 1.30389 2.61101 + endloop + endfacet + facet normal 0.101765 -0.102747 0.989488 + outer loop + vertex 1.06318 1.30882 2.61101 + vertex 1.06336 1.31331 2.61146 + vertex 1.05835 1.30832 2.61146 + endloop + endfacet + facet normal 0.104107 -0.104332 0.989079 + outer loop + vertex 1.0584 1.31292 2.61194 + vertex 1.06337 1.31793 2.61194 + vertex 1.05834 1.31775 2.61245 + endloop + endfacet + facet normal 0.104119 -0.104798 0.989028 + outer loop + vertex 1.06337 1.31793 2.61194 + vertex 1.06331 1.32277 2.61246 + vertex 1.05834 1.31775 2.61245 + endloop + endfacet + facet normal 0.105481 -0.107715 0.98857 + outer loop + vertex 1.06828 1.31383 2.61099 + vertex 1.0684 1.31831 2.61147 + vertex 1.06336 1.31331 2.61146 + endloop + endfacet + facet normal 0.0969689 -0.10497 0.989737 + outer loop + vertex 1.06337 1.31793 2.61194 + vertex 1.06838 1.32296 2.61198 + vertex 1.06331 1.32277 2.61246 + endloop + endfacet + facet normal 0.0960933 -0.123421 0.987691 + outer loop + vertex 1.07346 1.31872 2.61103 + vertex 1.07351 1.3232 2.61158 + vertex 1.0684 1.31831 2.61147 + endloop + endfacet + facet normal 0.0763848 -0.110322 0.990956 + outer loop + vertex 1.06838 1.32296 2.61198 + vertex 1.07343 1.32797 2.61215 + vertex 1.06831 1.32782 2.61253 + endloop + endfacet + facet normal 0.0627144 -0.123334 0.990382 + outer loop + vertex 1.07866 1.32311 2.61124 + vertex 1.07859 1.32793 2.61185 + vertex 1.07351 1.3232 2.61158 + endloop + endfacet + facet normal 0.0599437 -0.114322 0.991634 + outer loop + vertex 1.07343 1.32797 2.61215 + vertex 1.07838 1.33298 2.61243 + vertex 1.07337 1.33292 2.61273 + endloop + endfacet + facet normal 0.0524251 -0.0931594 0.99427 + outer loop + vertex 1.08399 1.32718 2.61149 + vertex 1.08316 1.33271 2.61206 + vertex 1.07859 1.32793 2.61185 + endloop + endfacet + facet normal 0.0599102 -0.108656 0.992272 + outer loop + vertex 1.07838 1.33298 2.61243 + vertex 1.07835 1.33803 2.61299 + vertex 1.07337 1.33292 2.61273 + endloop + endfacet + facet normal 0.0764606 -0.113997 0.990534 + outer loop + vertex 1.07343 1.32797 2.61215 + vertex 1.07337 1.33292 2.61273 + vertex 1.06831 1.32782 2.61253 + endloop + endfacet + facet normal 0.097095 -0.109857 0.989194 + outer loop + vertex 1.06838 1.32296 2.61198 + vertex 1.06831 1.32782 2.61253 + vertex 1.06331 1.32277 2.61246 + endloop + endfacet + facet normal 0.104102 -0.104781 0.989032 + outer loop + vertex 1.05834 1.31775 2.61245 + vertex 1.06331 1.32277 2.61246 + vertex 1.05824 1.32273 2.61299 + endloop + endfacet + facet normal 0.104925 -0.104313 0.988994 + outer loop + vertex 1.0584 1.31292 2.61194 + vertex 1.05834 1.31775 2.61245 + vertex 1.05335 1.3127 2.61245 + endloop + endfacet + facet normal 0.104984 -0.106141 0.988793 + outer loop + vertex 1.0534 1.30789 2.61193 + vertex 1.0584 1.31292 2.61194 + vertex 1.05335 1.3127 2.61245 + endloop + endfacet + facet normal 0.11188 -0.106942 0.987951 + outer loop + vertex 1.05333 1.30335 2.61144 + vertex 1.0534 1.30789 2.61193 + vertex 1.04835 1.30285 2.61195 + endloop + endfacet + facet normal 0.111945 -0.10768 0.987863 + outer loop + vertex 1.04828 1.29833 2.61147 + vertex 1.05333 1.30335 2.61144 + vertex 1.04835 1.30285 2.61195 + endloop + endfacet + facet normal 0.139499 -0.112376 0.983825 + outer loop + vertex 1.04811 1.29394 2.61099 + vertex 1.04828 1.29833 2.61147 + vertex 1.04324 1.29324 2.6116 + endloop + endfacet + facet normal 0.139102 -0.109287 0.984229 + outer loop + vertex 1.04811 1.29394 2.61099 + vertex 1.04324 1.29324 2.6116 + vertex 1.04322 1.28872 2.6111 + endloop + endfacet + facet normal 0.159074 -0.11032 0.981084 + outer loop + vertex 1.04526 1.28736 2.61062 + vertex 1.04322 1.28872 2.6111 + vertex 1.04247 1.28489 2.6108 + endloop + endfacet + facet normal 0.255542 -0.0991166 0.961704 + outer loop + vertex 1.03701 1.27779 2.61124 + vertex 1.03827 1.28305 2.61145 + vertex 1.03313 1.278 2.61229 + endloop + endfacet + facet normal 0.148293 -0.0827734 0.985473 + outer loop + vertex 1.04487 1.28405 2.61036 + vertex 1.04247 1.28489 2.6108 + vertex 1.04092 1.28101 2.6107 + endloop + endfacet + facet normal 0.121052 -0.0943143 0.988155 + outer loop + vertex 1.04887 1.28852 2.6103 + vertex 1.04487 1.28405 2.61036 + vertex 1.04859 1.28345 2.60985 + endloop + endfacet + facet normal 0.117806 -0.0984207 0.988147 + outer loop + vertex 1.05319 1.28302 2.60926 + vertex 1.05336 1.28826 2.60976 + vertex 1.04859 1.28345 2.60985 + endloop + endfacet + facet normal 0.117628 -0.0984168 0.988169 + outer loop + vertex 1.05319 1.28302 2.60926 + vertex 1.05816 1.28798 2.60916 + vertex 1.05336 1.28826 2.60976 + endloop + endfacet + facet normal 0.117171 -0.108973 0.987115 + outer loop + vertex 1.06315 1.28784 2.60855 + vertex 1.06315 1.29296 2.60912 + vertex 1.05816 1.28798 2.60916 + endloop + endfacet + facet normal 0.105059 -0.0960516 0.989817 + outer loop + vertex 1.06321 1.28279 2.60806 + vertex 1.06822 1.28782 2.60801 + vertex 1.06315 1.28784 2.60855 + endloop + endfacet + facet normal 0.101608 -0.0845137 0.991228 + outer loop + vertex 1.06325 1.27778 2.60763 + vertex 1.06826 1.28282 2.60754 + vertex 1.06321 1.28279 2.60806 + endloop + endfacet + facet normal 0.0989626 -0.0796518 0.991898 + outer loop + vertex 1.06328 1.27282 2.60722 + vertex 1.06828 1.27784 2.60713 + vertex 1.06325 1.27778 2.60763 + endloop + endfacet + facet normal 0.099269 -0.0828196 0.991608 + outer loop + vertex 1.06335 1.26805 2.60682 + vertex 1.06829 1.27302 2.60674 + vertex 1.06328 1.27282 2.60722 + endloop + endfacet + facet normal 0.101936 -0.0913751 0.990586 + outer loop + vertex 1.06353 1.26361 2.60639 + vertex 1.06829 1.26848 2.60635 + vertex 1.06335 1.26805 2.60682 + endloop + endfacet + facet normal 0.106737 -0.101026 0.989142 + outer loop + vertex 1.06397 1.26001 2.60598 + vertex 1.06353 1.26361 2.60639 + vertex 1.0589 1.25824 2.60634 + endloop + endfacet + facet normal 0.11318 -0.119998 0.986302 + outer loop + vertex 1.06397 1.26001 2.60598 + vertex 1.0589 1.25824 2.60634 + vertex 1.06126 1.25593 2.60579 + endloop + endfacet + facet normal 0.120141 -0.125876 0.984744 + outer loop + vertex 1.0587 1.25203 2.60559 + vertex 1.0577 1.25422 2.60599 + vertex 1.05571 1.25157 2.60589 + endloop + endfacet + facet normal 0.111091 -0.125437 0.985862 + outer loop + vertex 1.06482 1.25766 2.60561 + vertex 1.06126 1.25593 2.60579 + vertex 1.06335 1.25337 2.60523 + endloop + endfacet + facet normal 0.115957 -0.124766 0.985387 + outer loop + vertex 1.06329 1.24814 2.60457 + vertex 1.06335 1.25337 2.60523 + vertex 1.05878 1.24822 2.60511 + endloop + endfacet + facet normal 0.119195 -0.119086 0.985703 + outer loop + vertex 1.05571 1.25157 2.60589 + vertex 1.05523 1.24858 2.60559 + vertex 1.0587 1.25203 2.60559 + endloop + endfacet + facet normal 0.129529 -0.116857 0.984666 + outer loop + vertex 1.05844 1.24329 2.60457 + vertex 1.05878 1.24822 2.60511 + vertex 1.05389 1.24381 2.60523 + endloop + endfacet + facet normal 0.143407 -0.122559 0.982046 + outer loop + vertex 1.05571 1.25157 2.60589 + vertex 1.05294 1.2495 2.60604 + vertex 1.05523 1.24858 2.60559 + endloop + endfacet + facet normal 0.194815 -0.115996 0.973957 + outer loop + vertex 1.04858 1.24794 2.60666 + vertex 1.04724 1.2429 2.60632 + vertex 1.0513 1.24592 2.60587 + endloop + endfacet + facet normal 0.176231 -0.0872844 0.980471 + outer loop + vertex 1.0433 1.2531 2.60828 + vertex 1.04825 1.25783 2.60781 + vertex 1.04336 1.25827 2.60873 + endloop + endfacet + facet normal 0.176066 -0.0888779 0.980358 + outer loop + vertex 1.04825 1.25783 2.60781 + vertex 1.0482 1.26285 2.60827 + vertex 1.04336 1.25827 2.60873 + endloop + endfacet + facet normal 0.163261 -0.0750001 0.983728 + outer loop + vertex 1.04336 1.25827 2.60873 + vertex 1.0482 1.26285 2.60827 + vertex 1.04357 1.26346 2.60909 + endloop + endfacet + facet normal 0.162798 -0.0782846 0.983549 + outer loop + vertex 1.0482 1.26285 2.60827 + vertex 1.04821 1.26791 2.60867 + vertex 1.04357 1.26346 2.60909 + endloop + endfacet + facet normal 0.164131 -0.115682 0.979632 + outer loop + vertex 1.0537 1.25319 2.60642 + vertex 1.05348 1.25791 2.60701 + vertex 1.0484 1.25292 2.60728 + endloop + endfacet + facet normal 0.124778 -0.100074 0.987125 + outer loop + vertex 1.05348 1.25791 2.60701 + vertex 1.05847 1.26298 2.6069 + vertex 1.05326 1.26274 2.60753 + endloop + endfacet + facet normal 0.121351 -0.0873939 0.988755 + outer loop + vertex 1.05326 1.26274 2.60753 + vertex 1.05828 1.26777 2.60736 + vertex 1.05316 1.2677 2.60798 + endloop + endfacet + facet normal 0.119145 -0.0800521 0.989644 + outer loop + vertex 1.05316 1.2677 2.60798 + vertex 1.0582 1.27272 2.60778 + vertex 1.05313 1.27273 2.60839 + endloop + endfacet + facet normal 0.118075 -0.0800468 0.989773 + outer loop + vertex 1.05313 1.27273 2.60839 + vertex 1.05817 1.27775 2.6082 + vertex 1.05312 1.27783 2.6088 + endloop + endfacet + facet normal 0.151228 -0.0731384 0.98579 + outer loop + vertex 1.04821 1.26791 2.60867 + vertex 1.04825 1.27301 2.60904 + vertex 1.04371 1.26855 2.60941 + endloop + endfacet + facet normal 0.152152 -0.0669433 0.986087 + outer loop + vertex 1.04357 1.26346 2.60909 + vertex 1.04821 1.26791 2.60867 + vertex 1.04371 1.26855 2.60941 + endloop + endfacet + facet normal 0.206529 -0.0761636 0.975472 + outer loop + vertex 1.04336 1.25827 2.60873 + vertex 1.04357 1.26346 2.60909 + vertex 1.03918 1.25946 2.6097 + endloop + endfacet + facet normal 0.309947 -0.030744 0.950257 + outer loop + vertex 1.03224 1.26273 2.6119 + vertex 1.03188 1.25792 2.61186 + vertex 1.03562 1.26108 2.61074 + endloop + endfacet + facet normal 0.230577 -0.0545338 0.971525 + outer loop + vertex 1.03952 1.26456 2.60995 + vertex 1.03976 1.26949 2.61017 + vertex 1.03595 1.26593 2.61087 + endloop + endfacet + facet normal 0.161046 -0.0500381 0.985678 + outer loop + vertex 1.03976 1.26949 2.61017 + vertex 1.04378 1.2736 2.60972 + vertex 1.03995 1.27405 2.61037 + endloop + endfacet + facet normal 0.158728 -0.0685845 0.984937 + outer loop + vertex 1.04361 1.2788 2.61011 + vertex 1.03995 1.27405 2.61037 + vertex 1.04378 1.2736 2.60972 + endloop + endfacet + facet normal 0.149256 -0.0611659 0.986905 + outer loop + vertex 1.03965 1.27727 2.61061 + vertex 1.03995 1.27405 2.61037 + vertex 1.04361 1.2788 2.61011 + endloop + endfacet + facet normal 0.197133 -0.056152 0.978767 + outer loop + vertex 1.03965 1.27727 2.61061 + vertex 1.03718 1.27454 2.61096 + vertex 1.03995 1.27405 2.61037 + endloop + endfacet + facet normal 0.273346 -0.0393617 0.96111 + outer loop + vertex 1.03335 1.27286 2.61192 + vertex 1.03264 1.26746 2.6119 + vertex 1.03637 1.27069 2.61097 + endloop + endfacet + facet normal 0.216478 -0.0743194 0.973455 + outer loop + vertex 1.03965 1.27727 2.61061 + vertex 1.03701 1.27779 2.61124 + vertex 1.03718 1.27454 2.61096 + endloop + endfacet + facet normal 0.247951 -0.0677854 0.966398 + outer loop + vertex 1.02904 1.28926 2.61425 + vertex 1.03351 1.29332 2.61339 + vertex 1.02937 1.29446 2.61453 + endloop + endfacet + facet normal 0.243263 -0.0846112 0.966263 + outer loop + vertex 1.03351 1.29332 2.61339 + vertex 1.03362 1.29843 2.61381 + vertex 1.02937 1.29446 2.61453 + endloop + endfacet + facet normal 0.232158 -0.0720288 0.970007 + outer loop + vertex 1.02937 1.29446 2.61453 + vertex 1.03362 1.29843 2.61381 + vertex 1.02962 1.29952 2.61485 + endloop + endfacet + facet normal 0.228302 -0.0859891 0.969786 + outer loop + vertex 1.03362 1.29843 2.61381 + vertex 1.03367 1.30354 2.61425 + vertex 1.02962 1.29952 2.61485 + endloop + endfacet + facet normal 0.211369 -0.0930379 0.972968 + outer loop + vertex 1.03822 1.28809 2.61195 + vertex 1.03825 1.29291 2.6124 + vertex 1.03331 1.28818 2.61302 + endloop + endfacet + facet normal 0.155295 -0.0951752 0.983273 + outer loop + vertex 1.03825 1.29291 2.6124 + vertex 1.04327 1.29782 2.61208 + vertex 1.03827 1.29781 2.61287 + endloop + endfacet + facet normal 0.175298 -0.0864457 0.980713 + outer loop + vertex 1.03362 1.29843 2.61381 + vertex 1.03825 1.30287 2.61337 + vertex 1.03367 1.30354 2.61425 + endloop + endfacet + facet normal 0.155182 -0.103802 0.982417 + outer loop + vertex 1.04327 1.29782 2.61208 + vertex 1.04324 1.30263 2.6126 + vertex 1.03827 1.29781 2.61287 + endloop + endfacet + facet normal 0.125212 -0.105188 0.986538 + outer loop + vertex 1.04831 1.30763 2.61248 + vertex 1.04822 1.31264 2.61302 + vertex 1.04317 1.30765 2.61313 + endloop + endfacet + facet normal 0.110597 -0.104615 0.988344 + outer loop + vertex 1.04822 1.31264 2.61302 + vertex 1.05326 1.31769 2.61299 + vertex 1.04816 1.31773 2.61357 + endloop + endfacet + facet normal 0.110587 -0.105119 0.988292 + outer loop + vertex 1.05326 1.31769 2.61299 + vertex 1.05316 1.32274 2.61354 + vertex 1.04816 1.31773 2.61357 + endloop + endfacet + facet normal 0.105499 -0.101083 0.989268 + outer loop + vertex 1.04815 1.32283 2.6141 + vertex 1.05312 1.3278 2.61408 + vertex 1.04829 1.32792 2.6146 + endloop + endfacet + facet normal 0.105456 -0.102289 0.989149 + outer loop + vertex 1.05312 1.3278 2.61408 + vertex 1.05324 1.33289 2.61459 + vertex 1.04829 1.32792 2.6146 + endloop + endfacet + facet normal 0.103531 -0.102264 0.989355 + outer loop + vertex 1.05312 1.3278 2.61408 + vertex 1.05813 1.33281 2.61407 + vertex 1.05324 1.33289 2.61459 + endloop + endfacet + facet normal 0.103485 -0.103957 0.989183 + outer loop + vertex 1.05813 1.33281 2.61407 + vertex 1.05828 1.33789 2.61459 + vertex 1.05324 1.33289 2.61459 + endloop + endfacet + facet normal 0.0999818 -0.100428 0.989908 + outer loop + vertex 1.05324 1.33289 2.61459 + vertex 1.05828 1.33789 2.61459 + vertex 1.05358 1.33796 2.61507 + endloop + endfacet + facet normal 0.0999049 -0.103529 0.989596 + outer loop + vertex 1.05828 1.33789 2.61459 + vertex 1.05862 1.34294 2.61508 + vertex 1.05358 1.33796 2.61507 + endloop + endfacet + facet normal 0.0934611 -0.103152 0.990265 + outer loop + vertex 1.05828 1.33789 2.61459 + vertex 1.06334 1.3429 2.61463 + vertex 1.05862 1.34294 2.61508 + endloop + endfacet + facet normal 0.0973173 -0.107043 0.98948 + outer loop + vertex 1.06318 1.33781 2.6141 + vertex 1.06334 1.3429 2.61463 + vertex 1.05828 1.33789 2.61459 + endloop + endfacet + facet normal 0.103169 -0.106877 0.988905 + outer loop + vertex 1.06323 1.32774 2.613 + vertex 1.06317 1.33276 2.61355 + vertex 1.05815 1.32776 2.61353 + endloop + endfacet + facet normal 0.0974043 -0.103842 0.989813 + outer loop + vertex 1.05813 1.33281 2.61407 + vertex 1.06318 1.33781 2.6141 + vertex 1.05828 1.33789 2.61459 + endloop + endfacet + facet normal 0.0904638 -0.111864 0.989597 + outer loop + vertex 1.06827 1.33279 2.61309 + vertex 1.06825 1.3378 2.61366 + vertex 1.06317 1.33276 2.61355 + endloop + endfacet + facet normal 0.0816684 -0.106719 0.990929 + outer loop + vertex 1.06318 1.33781 2.6141 + vertex 1.06829 1.34286 2.61422 + vertex 1.06334 1.3429 2.61463 + endloop + endfacet + facet normal 0.0816615 -0.107152 0.990883 + outer loop + vertex 1.06829 1.34286 2.61422 + vertex 1.06839 1.34801 2.61477 + vertex 1.06334 1.3429 2.61463 + endloop + endfacet + facet normal 0.0779717 -0.103528 0.991566 + outer loop + vertex 1.06334 1.3429 2.61463 + vertex 1.06839 1.34801 2.61477 + vertex 1.06354 1.34786 2.61513 + endloop + endfacet + facet normal 0.0711241 -0.113823 0.990952 + outer loop + vertex 1.07337 1.33791 2.6133 + vertex 1.07339 1.34291 2.61387 + vertex 1.06825 1.3378 2.61366 + endloop + endfacet + facet normal 0.0658737 -0.106984 0.992076 + outer loop + vertex 1.06829 1.34286 2.61422 + vertex 1.07343 1.348 2.61443 + vertex 1.06839 1.34801 2.61477 + endloop + endfacet + facet normal 0.0659485 -0.0994789 0.992852 + outer loop + vertex 1.07343 1.348 2.61443 + vertex 1.07348 1.35319 2.61495 + vertex 1.06839 1.34801 2.61477 + endloop + endfacet + facet normal 0.0712732 -0.10484 0.991932 + outer loop + vertex 1.07839 1.34302 2.61353 + vertex 1.07843 1.34802 2.61405 + vertex 1.07339 1.34291 2.61387 + endloop + endfacet + facet normal 0.0798878 -0.0995226 0.991823 + outer loop + vertex 1.07343 1.348 2.61443 + vertex 1.07846 1.35308 2.61454 + vertex 1.07348 1.35319 2.61495 + endloop + endfacet + facet normal 0.131538 -0.0821283 0.987903 + outer loop + vertex 1.08306 1.34791 2.61343 + vertex 1.0831 1.35287 2.61383 + vertex 1.07843 1.34802 2.61405 + endloop + endfacet + facet normal 0.333299 -0.065558 0.940539 + outer loop + vertex 1.08314 1.35788 2.6142 + vertex 1.08719 1.3622 2.61306 + vertex 1.08321 1.36299 2.61453 + endloop + endfacet + facet normal 0.0802744 -0.0859611 0.993059 + outer loop + vertex 1.07846 1.35308 2.61454 + vertex 1.07853 1.35822 2.61498 + vertex 1.07348 1.35319 2.61495 + endloop + endfacet + facet normal 0.0639314 -0.097503 0.99318 + outer loop + vertex 1.06839 1.34801 2.61477 + vertex 1.07348 1.35319 2.61495 + vertex 1.06831 1.35329 2.61529 + endloop + endfacet + facet normal 0.0898421 -0.0985248 0.991071 + outer loop + vertex 1.07355 1.35843 2.61541 + vertex 1.07868 1.3634 2.61544 + vertex 1.0747 1.36247 2.61571 + endloop + endfacet + facet normal 0.0953423 -0.122856 0.987834 + outer loop + vertex 1.0747 1.36247 2.61571 + vertex 1.07868 1.3634 2.61544 + vertex 1.07663 1.36582 2.61594 + endloop + endfacet + facet normal 0.100414 -0.118566 0.987856 + outer loop + vertex 1.08001 1.36749 2.6158 + vertex 1.07663 1.36582 2.61594 + vertex 1.07868 1.3634 2.61544 + endloop + endfacet + facet normal 0.261666 -0.168022 0.950421 + outer loop + vertex 1.08001 1.36749 2.6158 + vertex 1.07868 1.3634 2.61544 + vertex 1.08337 1.36823 2.615 + endloop + endfacet + facet normal 0.265474 -0.191238 0.944961 + outer loop + vertex 1.08337 1.36823 2.615 + vertex 1.08183 1.37024 2.61584 + vertex 1.08001 1.36749 2.6158 + endloop + endfacet + facet normal 0.132978 -0.104655 0.985578 + outer loop + vertex 1.08183 1.37024 2.61584 + vertex 1.07888 1.36968 2.61618 + vertex 1.08001 1.36749 2.6158 + endloop + endfacet + facet normal 0.127335 -0.0729691 0.989172 + outer loop + vertex 1.08183 1.37024 2.61584 + vertex 1.08184 1.37327 2.61607 + vertex 1.07888 1.36968 2.61618 + endloop + endfacet + facet normal 0.129875 -0.0750824 0.988684 + outer loop + vertex 1.08184 1.37327 2.61607 + vertex 1.07816 1.37323 2.61655 + vertex 1.07888 1.36968 2.61618 + endloop + endfacet + facet normal 0.0622246 -0.0893508 0.994055 + outer loop + vertex 1.07888 1.36968 2.61618 + vertex 1.07816 1.37323 2.61655 + vertex 1.07402 1.36803 2.61634 + endloop + endfacet + facet normal 0.0660462 -0.100727 0.992719 + outer loop + vertex 1.07888 1.36968 2.61618 + vertex 1.07402 1.36803 2.61634 + vertex 1.07663 1.36582 2.61594 + endloop + endfacet + facet normal 0.0610145 -0.106625 0.992425 + outer loop + vertex 1.07663 1.36582 2.61594 + vertex 1.07402 1.36803 2.61634 + vertex 1.07313 1.36398 2.61596 + endloop + endfacet + facet normal 0.0744795 -0.0990481 0.992291 + outer loop + vertex 1.07402 1.36803 2.61634 + vertex 1.07816 1.37323 2.61655 + vertex 1.07348 1.37292 2.61687 + endloop + endfacet + facet normal 0.0659917 -0.100043 0.992792 + outer loop + vertex 1.07402 1.36803 2.61634 + vertex 1.07348 1.37292 2.61687 + vertex 1.06861 1.36784 2.61668 + endloop + endfacet + facet normal 0.073685 -0.0853969 0.993619 + outer loop + vertex 1.07816 1.37323 2.61655 + vertex 1.07798 1.37784 2.61696 + vertex 1.07348 1.37292 2.61687 + endloop + endfacet + facet normal 0.0871207 -0.0976594 0.991399 + outer loop + vertex 1.07348 1.37292 2.61687 + vertex 1.07798 1.37784 2.61696 + vertex 1.07335 1.37787 2.61737 + endloop + endfacet + facet normal 0.161347 -0.0809912 0.983569 + outer loop + vertex 1.07816 1.37323 2.61655 + vertex 1.08192 1.37745 2.61628 + vertex 1.07798 1.37784 2.61696 + endloop + endfacet + facet normal 0.163299 -0.062874 0.984571 + outer loop + vertex 1.08192 1.37745 2.61628 + vertex 1.082 1.3823 2.61657 + vertex 1.07798 1.37784 2.61696 + endloop + endfacet + facet normal 0.186305 -0.0841531 0.978881 + outer loop + vertex 1.07798 1.37784 2.61696 + vertex 1.082 1.3823 2.61657 + vertex 1.07798 1.3828 2.61738 + endloop + endfacet + facet normal 0.129834 -0.052548 0.990142 + outer loop + vertex 1.08184 1.37327 2.61607 + vertex 1.08192 1.37745 2.61628 + vertex 1.07816 1.37323 2.61655 + endloop + endfacet + facet normal 0.101665 -0.121136 0.987416 + outer loop + vertex 1.08001 1.36749 2.6158 + vertex 1.07888 1.36968 2.61618 + vertex 1.07663 1.36582 2.61594 + endloop + endfacet + facet normal 0.0585566 -0.101952 0.993064 + outer loop + vertex 1.07313 1.36398 2.61596 + vertex 1.0747 1.36247 2.61571 + vertex 1.07663 1.36582 2.61594 + endloop + endfacet + facet normal 0.0715998 -0.108849 0.991476 + outer loop + vertex 1.07313 1.36398 2.61596 + vertex 1.07402 1.36803 2.61634 + vertex 1.06892 1.36294 2.61615 + endloop + endfacet + facet normal 0.0686548 -0.0914524 0.99344 + outer loop + vertex 1.07131 1.36075 2.61575 + vertex 1.06796 1.35907 2.61583 + vertex 1.06948 1.35752 2.61558 + endloop + endfacet + facet normal 0.0743024 -0.0859175 0.993528 + outer loop + vertex 1.06948 1.35752 2.61558 + vertex 1.06796 1.35907 2.61583 + vertex 1.066 1.35577 2.61569 + endloop + endfacet + facet normal 0.0660846 -0.103363 0.992446 + outer loop + vertex 1.07402 1.36803 2.61634 + vertex 1.06861 1.36784 2.61668 + vertex 1.06892 1.36294 2.61615 + endloop + endfacet + facet normal 0.066764 -0.100779 0.992666 + outer loop + vertex 1.06861 1.36784 2.61668 + vertex 1.07348 1.37292 2.61687 + vertex 1.0684 1.37279 2.6172 + endloop + endfacet + facet normal 0.069387 -0.0945691 0.993097 + outer loop + vertex 1.06329 1.37274 2.61757 + vertex 1.06838 1.37781 2.6177 + vertex 1.06331 1.37775 2.61804 + endloop + endfacet + facet normal 0.0667151 -0.0983345 0.992915 + outer loop + vertex 1.07348 1.37292 2.61687 + vertex 1.07335 1.37787 2.61737 + vertex 1.0684 1.37279 2.6172 + endloop + endfacet + facet normal 0.067548 -0.0970326 0.992986 + outer loop + vertex 1.06838 1.37781 2.6177 + vertex 1.07338 1.38291 2.61786 + vertex 1.06841 1.38283 2.61819 + endloop + endfacet + facet normal 0.0873123 -0.0852723 0.992525 + outer loop + vertex 1.07798 1.37784 2.61696 + vertex 1.07798 1.3828 2.61738 + vertex 1.07335 1.37787 2.61737 + endloop + endfacet + facet normal 0.10974 -0.0943681 0.98947 + outer loop + vertex 1.07338 1.38291 2.61786 + vertex 1.07804 1.38785 2.61781 + vertex 1.07341 1.38794 2.61833 + endloop + endfacet + facet normal 0.188931 -0.0647722 0.979852 + outer loop + vertex 1.082 1.3823 2.61657 + vertex 1.08207 1.38733 2.61689 + vertex 1.07798 1.3828 2.61738 + endloop + endfacet + facet normal 0.110161 -0.0793146 0.990744 + outer loop + vertex 1.07804 1.38785 2.61781 + vertex 1.07806 1.39286 2.61821 + vertex 1.07341 1.38794 2.61833 + endloop + endfacet + facet normal 0.0675233 -0.0944481 0.993237 + outer loop + vertex 1.07338 1.38291 2.61786 + vertex 1.07341 1.38794 2.61833 + vertex 1.06841 1.38283 2.61819 + endloop + endfacet + facet normal 0.0693993 -0.097033 0.992859 + outer loop + vertex 1.06838 1.37781 2.6177 + vertex 1.06841 1.38283 2.61819 + vertex 1.06331 1.37775 2.61804 + endloop + endfacet + facet normal 0.0810828 -0.0945428 0.992213 + outer loop + vertex 1.06329 1.37274 2.61757 + vertex 1.06331 1.37775 2.61804 + vertex 1.05826 1.37274 2.61798 + endloop + endfacet + facet normal 0.0869782 -0.0925489 0.991902 + outer loop + vertex 1.05826 1.36775 2.61751 + vertex 1.05826 1.37274 2.61798 + vertex 1.05327 1.36775 2.61795 + endloop + endfacet + facet normal 0.0845596 -0.0936104 0.992011 + outer loop + vertex 1.05836 1.36281 2.61704 + vertex 1.06336 1.36776 2.61708 + vertex 1.05826 1.36775 2.61751 + endloop + endfacet + facet normal 0.0876982 -0.0936921 0.991731 + outer loop + vertex 1.05857 1.35803 2.61657 + vertex 1.06358 1.36289 2.61659 + vertex 1.05836 1.36281 2.61704 + endloop + endfacet + facet normal 0.0884627 -0.0930062 0.991728 + outer loop + vertex 1.05866 1.35339 2.61613 + vertex 1.05857 1.35803 2.61657 + vertex 1.05357 1.35313 2.61656 + endloop + endfacet + facet normal 0.0885061 -0.0940499 0.991626 + outer loop + vertex 1.05866 1.35339 2.61613 + vertex 1.05357 1.35313 2.61656 + vertex 1.05359 1.34854 2.61612 + endloop + endfacet + facet normal 0.0899838 -0.0935033 0.991544 + outer loop + vertex 1.04842 1.35285 2.617 + vertex 1.05341 1.35787 2.61702 + vertex 1.04831 1.35773 2.61747 + endloop + endfacet + facet normal 0.089361 -0.0924326 0.991701 + outer loop + vertex 1.04831 1.35773 2.61747 + vertex 1.05329 1.36277 2.61749 + vertex 1.04827 1.36272 2.61794 + endloop + endfacet + facet normal 0.0951887 -0.0911668 0.991276 + outer loop + vertex 1.04827 1.36272 2.61794 + vertex 1.04825 1.36771 2.6184 + vertex 1.04321 1.36266 2.61842 + endloop + endfacet + facet normal 0.0866813 -0.0888184 0.992269 + outer loop + vertex 1.04825 1.36771 2.6184 + vertex 1.05326 1.37273 2.61841 + vertex 1.04821 1.37268 2.61884 + endloop + endfacet + facet normal 0.0849864 -0.0820867 0.992995 + outer loop + vertex 1.04318 1.37273 2.6193 + vertex 1.04815 1.3777 2.61928 + vertex 1.04325 1.37786 2.61972 + endloop + endfacet + facet normal 0.0924465 -0.0821247 0.992325 + outer loop + vertex 1.04318 1.37273 2.6193 + vertex 1.04325 1.37786 2.61972 + vertex 1.0384 1.37304 2.61977 + endloop + endfacet + facet normal 0.0926557 -0.0792631 0.992538 + outer loop + vertex 1.0383 1.36787 2.61937 + vertex 1.04318 1.37273 2.6193 + vertex 1.0384 1.37304 2.61977 + endloop + endfacet + facet normal 0.0849307 -0.0834813 0.992883 + outer loop + vertex 1.04815 1.3777 2.61928 + vertex 1.0482 1.38279 2.61971 + vertex 1.04325 1.37786 2.61972 + endloop + endfacet + facet normal 0.0811568 -0.0796918 0.99351 + outer loop + vertex 1.04325 1.37786 2.61972 + vertex 1.0482 1.38279 2.61971 + vertex 1.04348 1.383 2.62011 + endloop + endfacet + facet normal 0.0859221 -0.0798772 0.993095 + outer loop + vertex 1.04325 1.37786 2.61972 + vertex 1.04348 1.383 2.62011 + vertex 1.03871 1.37824 2.62014 + endloop + endfacet + facet normal 0.0866795 -0.087862 0.992354 + outer loop + vertex 1.05326 1.37273 2.61841 + vertex 1.0532 1.37769 2.61885 + vertex 1.04821 1.37268 2.61884 + endloop + endfacet + facet normal 0.0824126 -0.0834753 0.993096 + outer loop + vertex 1.04815 1.3777 2.61928 + vertex 1.05315 1.38269 2.61929 + vertex 1.0482 1.38279 2.61971 + endloop + endfacet + facet normal 0.0823627 -0.08532 0.992944 + outer loop + vertex 1.05315 1.38269 2.61929 + vertex 1.05323 1.38777 2.61972 + vertex 1.0482 1.38279 2.61971 + endloop + endfacet + facet normal 0.080528 -0.0834677 0.993251 + outer loop + vertex 1.0482 1.38279 2.61971 + vertex 1.05323 1.38777 2.61972 + vertex 1.04847 1.38791 2.62011 + endloop + endfacet + facet normal 0.0823996 -0.0883732 0.992673 + outer loop + vertex 1.05826 1.37772 2.61843 + vertex 1.05821 1.38268 2.61888 + vertex 1.0532 1.37769 2.61885 + endloop + endfacet + facet normal 0.0770679 -0.085267 0.993373 + outer loop + vertex 1.05315 1.38269 2.61929 + vertex 1.05818 1.38769 2.61933 + vertex 1.05323 1.38777 2.61972 + endloop + endfacet + facet normal 0.0769905 -0.0884969 0.993097 + outer loop + vertex 1.05818 1.38769 2.61933 + vertex 1.05831 1.39278 2.61977 + vertex 1.05323 1.38777 2.61972 + endloop + endfacet + facet normal 0.0752152 -0.0866972 0.993391 + outer loop + vertex 1.05323 1.38777 2.61972 + vertex 1.05831 1.39278 2.61977 + vertex 1.05356 1.39287 2.62014 + endloop + endfacet + facet normal 0.0728818 -0.0924236 0.993049 + outer loop + vertex 1.06331 1.38273 2.61851 + vertex 1.06327 1.3877 2.61898 + vertex 1.05821 1.38268 2.61888 + endloop + endfacet + facet normal 0.0650028 -0.0882551 0.993975 + outer loop + vertex 1.05818 1.38769 2.61933 + vertex 1.06328 1.39273 2.61944 + vertex 1.05831 1.39278 2.61977 + endloop + endfacet + facet normal 0.0649875 -0.0893096 0.993881 + outer loop + vertex 1.06328 1.39273 2.61944 + vertex 1.06342 1.39783 2.61989 + vertex 1.05831 1.39278 2.61977 + endloop + endfacet + facet normal 0.0626877 -0.0869969 0.994234 + outer loop + vertex 1.05831 1.39278 2.61977 + vertex 1.06342 1.39783 2.61989 + vertex 1.05865 1.39784 2.62019 + endloop + endfacet + facet normal 0.0627197 -0.0825707 0.99461 + outer loop + vertex 1.06342 1.39783 2.61989 + vertex 1.06358 1.40279 2.62029 + vertex 1.05865 1.39784 2.62019 + endloop + endfacet + facet normal 0.0544509 -0.0823312 0.995116 + outer loop + vertex 1.06342 1.39783 2.61989 + vertex 1.06848 1.40302 2.62004 + vertex 1.06358 1.40279 2.62029 + endloop + endfacet + facet normal 0.0556262 -0.083474 0.994956 + outer loop + vertex 1.06841 1.39787 2.61961 + vertex 1.06848 1.40302 2.62004 + vertex 1.06342 1.39783 2.61989 + endloop + endfacet + facet normal 0.0619061 -0.0953953 0.993513 + outer loop + vertex 1.06841 1.38782 2.61867 + vertex 1.06838 1.39281 2.61915 + vertex 1.06327 1.3877 2.61898 + endloop + endfacet + facet normal 0.0556439 -0.089103 0.994467 + outer loop + vertex 1.06328 1.39273 2.61944 + vertex 1.06841 1.39787 2.61961 + vertex 1.06342 1.39783 2.61989 + endloop + endfacet + facet normal 0.0713628 -0.0897316 0.993406 + outer loop + vertex 1.07341 1.39292 2.6188 + vertex 1.0734 1.39793 2.61925 + vertex 1.06838 1.39281 2.61915 + endloop + endfacet + facet normal 0.0734169 -0.0836294 0.993789 + outer loop + vertex 1.06841 1.39787 2.61961 + vertex 1.07343 1.40302 2.61968 + vertex 1.06848 1.40302 2.62004 + endloop + endfacet + facet normal 0.0734714 -0.0758165 0.994411 + outer loop + vertex 1.07343 1.40302 2.61968 + vertex 1.07346 1.4082 2.62007 + vertex 1.06848 1.40302 2.62004 + endloop + endfacet + facet normal 0.135071 -0.0739478 0.988073 + outer loop + vertex 1.07807 1.39785 2.61861 + vertex 1.07807 1.40284 2.61898 + vertex 1.0734 1.39793 2.61925 + endloop + endfacet + facet normal 0.151111 -0.0756236 0.98562 + outer loop + vertex 1.07343 1.40302 2.61968 + vertex 1.07809 1.4079 2.61934 + vertex 1.07346 1.4082 2.62007 + endloop + endfacet + facet normal 0.284054 -0.0548015 0.957241 + outer loop + vertex 1.08214 1.4023 2.61774 + vertex 1.08214 1.40725 2.61802 + vertex 1.07807 1.40284 2.61898 + endloop + endfacet + facet normal 0.150882 -0.0787105 0.985413 + outer loop + vertex 1.07809 1.4079 2.61934 + vertex 1.07813 1.41304 2.61974 + vertex 1.07346 1.4082 2.62007 + endloop + endfacet + facet normal 0.0709377 -0.0733808 0.994778 + outer loop + vertex 1.06848 1.40302 2.62004 + vertex 1.07346 1.4082 2.62007 + vertex 1.06836 1.40827 2.62044 + endloop + endfacet + facet normal 0.16273 -0.127472 0.978402 + outer loop + vertex 1.07353 1.41344 2.62049 + vertex 1.07829 1.4182 2.62032 + vertex 1.07474 1.41752 2.62082 + endloop + endfacet + facet normal 0.0709931 -0.0990111 0.992551 + outer loop + vertex 1.07325 1.41903 2.62108 + vertex 1.07474 1.41752 2.62082 + vertex 1.07662 1.42086 2.62102 + endloop + endfacet + facet normal 0.0416021 -0.0834601 0.995642 + outer loop + vertex 1.07325 1.41903 2.62108 + vertex 1.0741 1.42305 2.62138 + vertex 1.06899 1.41789 2.62116 + endloop + endfacet + facet normal 0.0439105 -0.0797842 0.995845 + outer loop + vertex 1.07141 1.41577 2.62085 + vertex 1.06799 1.41401 2.62086 + vertex 1.06953 1.4125 2.62067 + endloop + endfacet + facet normal 0.0509659 -0.072582 0.996059 + outer loop + vertex 1.06953 1.4125 2.62067 + vertex 1.06799 1.41401 2.62086 + vertex 1.066 1.41068 2.62072 + endloop + endfacet + facet normal 0.0448423 -0.0866434 0.99523 + outer loop + vertex 1.0741 1.42305 2.62138 + vertex 1.06868 1.42273 2.6216 + vertex 1.06899 1.41789 2.62116 + endloop + endfacet + facet normal 0.0444349 -0.0795191 0.995842 + outer loop + vertex 1.0741 1.42305 2.62138 + vertex 1.07356 1.42786 2.62179 + vertex 1.06868 1.42273 2.6216 + endloop + endfacet + facet normal 0.0491241 -0.0757557 0.995916 + outer loop + vertex 1.06847 1.4276 2.622 + vertex 1.07343 1.43274 2.62215 + vertex 1.06845 1.43259 2.62238 + endloop + endfacet + facet normal 0.0965795 -0.0630975 0.993323 + outer loop + vertex 1.07806 1.42837 2.62138 + vertex 1.07786 1.43296 2.6217 + vertex 1.07356 1.42786 2.62179 + endloop + endfacet + facet normal 0.0489392 -0.0686327 0.996441 + outer loop + vertex 1.07343 1.43274 2.62215 + vertex 1.07346 1.43774 2.62249 + vertex 1.06845 1.43259 2.62238 + endloop + endfacet + facet normal 0.0432138 -0.0758071 0.996186 + outer loop + vertex 1.06847 1.4276 2.622 + vertex 1.06845 1.43259 2.62238 + vertex 1.06327 1.42756 2.62222 + endloop + endfacet + facet normal 0.0432217 -0.0771289 0.996084 + outer loop + vertex 1.06335 1.42259 2.62183 + vertex 1.06847 1.4276 2.622 + vertex 1.06327 1.42756 2.62222 + endloop + endfacet + facet normal 0.0633654 -0.0790125 0.994858 + outer loop + vertex 1.06356 1.41775 2.62144 + vertex 1.06335 1.42259 2.62183 + vertex 1.05829 1.41767 2.62177 + endloop + endfacet + facet normal 0.0633295 -0.0757622 0.995113 + outer loop + vertex 1.0585 1.41289 2.62139 + vertex 1.06356 1.41775 2.62144 + vertex 1.05829 1.41767 2.62177 + endloop + endfacet + facet normal 0.0719316 -0.0752184 0.994569 + outer loop + vertex 1.05859 1.40826 2.62103 + vertex 1.0585 1.41289 2.62139 + vertex 1.05351 1.40801 2.62138 + endloop + endfacet + facet normal 0.0719355 -0.0753091 0.994562 + outer loop + vertex 1.05859 1.40826 2.62103 + vertex 1.05351 1.40801 2.62138 + vertex 1.05356 1.40345 2.62103 + endloop + endfacet + facet normal 0.0698951 -0.0772894 0.994556 + outer loop + vertex 1.05243 1.39972 2.62082 + vertex 1.05356 1.40345 2.62103 + vertex 1.04849 1.3985 2.621 + endloop + endfacet + facet normal 0.0721818 -0.0755666 0.994525 + outer loop + vertex 1.05747 1.40459 2.62083 + vertex 1.05859 1.40826 2.62103 + vertex 1.05356 1.40345 2.62103 + endloop + endfacet + facet normal 0.0679921 -0.0753122 0.994839 + outer loop + vertex 1.06377 1.41297 2.62103 + vertex 1.0585 1.41289 2.62139 + vertex 1.05859 1.40826 2.62103 + endloop + endfacet + facet normal 0.0601518 -0.0780482 0.995133 + outer loop + vertex 1.06799 1.41401 2.62086 + vertex 1.06377 1.41297 2.62103 + vertex 1.066 1.41068 2.62072 + endloop + endfacet + facet normal 0.0631945 -0.0699062 0.99555 + outer loop + vertex 1.06339 1.40676 2.6206 + vertex 1.0625 1.40911 2.62082 + vertex 1.0603 1.40639 2.62077 + endloop + endfacet + facet normal 0.0489742 -0.0686985 0.996435 + outer loop + vertex 1.06953 1.4125 2.62067 + vertex 1.066 1.41068 2.62072 + vertex 1.06836 1.40827 2.62044 + endloop + endfacet + facet normal 0.0540853 -0.0738451 0.995802 + outer loop + vertex 1.06848 1.40302 2.62004 + vertex 1.06836 1.40827 2.62044 + vertex 1.06358 1.40279 2.62029 + endloop + endfacet + facet normal 0.0637455 -0.0747252 0.995165 + outer loop + vertex 1.0603 1.40639 2.62077 + vertex 1.05904 1.40266 2.62057 + vertex 1.06339 1.40676 2.6206 + endloop + endfacet + facet normal 0.0745062 -0.0836731 0.993704 + outer loop + vertex 1.05539 1.40174 2.62076 + vertex 1.05407 1.39786 2.62054 + vertex 1.05904 1.40266 2.62057 + endloop + endfacet + facet normal 0.0751872 -0.0877377 0.993302 + outer loop + vertex 1.05831 1.39278 2.61977 + vertex 1.05865 1.39784 2.62019 + vertex 1.05356 1.39287 2.62014 + endloop + endfacet + facet normal 0.0777642 -0.0862278 0.993236 + outer loop + vertex 1.05029 1.3968 2.62074 + vertex 1.04895 1.39291 2.62051 + vertex 1.05407 1.39786 2.62054 + endloop + endfacet + facet normal 0.0804051 -0.0869974 0.992958 + outer loop + vertex 1.05323 1.38777 2.61972 + vertex 1.05356 1.39287 2.62014 + vertex 1.04847 1.38791 2.62011 + endloop + endfacet + facet normal 0.0740056 -0.0820806 0.993874 + outer loop + vertex 1.04514 1.39186 2.6207 + vertex 1.04385 1.38801 2.62048 + vertex 1.04895 1.39291 2.62051 + endloop + endfacet + facet normal 0.0809645 -0.0834879 0.993214 + outer loop + vertex 1.0482 1.38279 2.61971 + vertex 1.04847 1.38791 2.62011 + vertex 1.04348 1.383 2.62011 + endloop + endfacet + facet normal 0.0727131 -0.0736277 0.994631 + outer loop + vertex 1.04007 1.38699 2.62068 + vertex 1.03902 1.3832 2.62048 + vertex 1.04385 1.38801 2.62048 + endloop + endfacet + facet normal 0.0866814 -0.0693134 0.993822 + outer loop + vertex 1.03539 1.38208 2.62072 + vertex 1.03503 1.37881 2.62052 + vertex 1.03902 1.3832 2.62048 + endloop + endfacet + facet normal 0.0862823 -0.0759028 0.993375 + outer loop + vertex 1.0384 1.37304 2.61977 + vertex 1.04325 1.37786 2.61972 + vertex 1.03871 1.37824 2.62014 + endloop + endfacet + facet normal 0.0985382 -0.0823321 0.991722 + outer loop + vertex 1.03821 1.36275 2.61895 + vertex 1.0432 1.36768 2.61886 + vertex 1.0383 1.36787 2.61937 + endloop + endfacet + facet normal 0.108719 -0.0886616 0.990111 + outer loop + vertex 1.03817 1.35261 2.61806 + vertex 1.04322 1.35764 2.61795 + vertex 1.03816 1.35766 2.61851 + endloop + endfacet + facet normal 0.112194 -0.0906713 0.989541 + outer loop + vertex 1.03821 1.34761 2.6176 + vertex 1.04327 1.35265 2.61748 + vertex 1.03817 1.35261 2.61806 + endloop + endfacet + facet normal 0.114098 -0.090299 0.989357 + outer loop + vertex 1.0383 1.34271 2.61714 + vertex 1.04337 1.34778 2.61702 + vertex 1.03821 1.34761 2.6176 + endloop + endfacet + facet normal 0.116811 -0.0930339 0.988787 + outer loop + vertex 1.04346 1.34305 2.61656 + vertex 1.04337 1.34778 2.61702 + vertex 1.0383 1.34271 2.61714 + endloop + endfacet + facet normal 0.0982127 -0.0935484 0.990759 + outer loop + vertex 1.04346 1.34305 2.61656 + vertex 1.04853 1.34813 2.61654 + vertex 1.04337 1.34778 2.61702 + endloop + endfacet + facet normal 0.08969 -0.0940341 0.991521 + outer loop + vertex 1.05359 1.34854 2.61612 + vertex 1.05357 1.35313 2.61656 + vertex 1.04853 1.34813 2.61654 + endloop + endfacet + facet normal 0.0894443 -0.0963509 0.99132 + outer loop + vertex 1.05541 1.34683 2.61579 + vertex 1.05359 1.34854 2.61612 + vertex 1.05243 1.34479 2.61586 + endloop + endfacet + facet normal 0.089001 -0.0968219 0.991314 + outer loop + vertex 1.05753 1.34971 2.61588 + vertex 1.05359 1.34854 2.61612 + vertex 1.05541 1.34683 2.61579 + endloop + endfacet + facet normal 0.0880688 -0.0935923 0.991708 + outer loop + vertex 1.05753 1.34971 2.61588 + vertex 1.05866 1.35339 2.61613 + vertex 1.05359 1.34854 2.61612 + endloop + endfacet + facet normal 0.0900303 -0.0929641 0.991591 + outer loop + vertex 1.0638 1.35809 2.6161 + vertex 1.05857 1.35803 2.61657 + vertex 1.05866 1.35339 2.61613 + endloop + endfacet + facet normal 0.0877287 -0.0937805 0.99172 + outer loop + vertex 1.06796 1.35907 2.61583 + vertex 1.0638 1.35809 2.6161 + vertex 1.066 1.35577 2.61569 + endloop + endfacet + facet normal 0.0912625 -0.0939186 0.991388 + outer loop + vertex 1.06341 1.35185 2.61555 + vertex 1.06256 1.35423 2.61585 + vertex 1.06037 1.35151 2.61579 + endloop + endfacet + facet normal 0.0752094 -0.0877294 0.993301 + outer loop + vertex 1.06948 1.35752 2.61558 + vertex 1.066 1.35577 2.61569 + vertex 1.06831 1.35329 2.61529 + endloop + endfacet + facet normal 0.0778162 -0.0972016 0.992218 + outer loop + vertex 1.06839 1.34801 2.61477 + vertex 1.06831 1.35329 2.61529 + vertex 1.06354 1.34786 2.61513 + endloop + endfacet + facet normal 0.0918142 -0.0992452 0.990818 + outer loop + vertex 1.06037 1.35151 2.61579 + vertex 1.05907 1.34777 2.61554 + vertex 1.06341 1.35185 2.61555 + endloop + endfacet + facet normal 0.0934445 -0.104021 0.990176 + outer loop + vertex 1.06334 1.3429 2.61463 + vertex 1.06354 1.34786 2.61513 + vertex 1.05862 1.34294 2.61508 + endloop + endfacet + facet normal 0.0909979 -0.0947765 0.991331 + outer loop + vertex 1.0503 1.34183 2.61576 + vertex 1.04903 1.33793 2.61551 + vertex 1.05408 1.34294 2.61552 + endloop + endfacet + facet normal 0.101024 -0.100487 0.989796 + outer loop + vertex 1.05324 1.33289 2.61459 + vertex 1.05358 1.33796 2.61507 + vertex 1.04861 1.33298 2.61507 + endloop + endfacet + facet normal 0.0925144 -0.089319 0.991697 + outer loop + vertex 1.0453 1.33678 2.61575 + vertex 1.04426 1.33302 2.61551 + vertex 1.04903 1.33793 2.61551 + endloop + endfacet + facet normal 0.101102 -0.0979408 0.990043 + outer loop + vertex 1.04829 1.32792 2.6146 + vertex 1.05324 1.33289 2.61459 + vertex 1.04861 1.33298 2.61507 + endloop + endfacet + facet normal 0.11228 -0.101186 0.988511 + outer loop + vertex 1.04815 1.32283 2.6141 + vertex 1.04829 1.32792 2.6146 + vertex 1.04344 1.3231 2.61466 + endloop + endfacet + facet normal 0.112491 -0.0981298 0.988795 + outer loop + vertex 1.04327 1.31797 2.61417 + vertex 1.04815 1.32283 2.6141 + vertex 1.04344 1.3231 2.61466 + endloop + endfacet + facet normal 0.135697 -0.0998501 0.985706 + outer loop + vertex 1.04318 1.31281 2.61366 + vertex 1.04327 1.31797 2.61417 + vertex 1.03847 1.31334 2.61436 + endloop + endfacet + facet normal 0.136308 -0.0949698 0.986104 + outer loop + vertex 1.03824 1.30806 2.61389 + vertex 1.04318 1.31281 2.61366 + vertex 1.03847 1.31334 2.61436 + endloop + endfacet + facet normal 0.173696 -0.0964988 0.98006 + outer loop + vertex 1.03825 1.30287 2.61337 + vertex 1.03824 1.30806 2.61389 + vertex 1.03367 1.30354 2.61425 + endloop + endfacet + facet normal 0.215162 -0.0721437 0.97391 + outer loop + vertex 1.02962 1.29952 2.61485 + vertex 1.03367 1.30354 2.61425 + vertex 1.02981 1.30414 2.61515 + endloop + endfacet + facet normal 0.277304 -0.0743712 0.9579 + outer loop + vertex 1.02945 1.30735 2.6155 + vertex 1.02713 1.30478 2.61597 + vertex 1.02981 1.30414 2.61515 + endloop + endfacet + facet normal 0.297744 -0.0942008 0.949987 + outer loop + vertex 1.02945 1.30735 2.6155 + vertex 1.02685 1.30791 2.61637 + vertex 1.02713 1.30478 2.61597 + endloop + endfacet + facet normal 0.257809 -0.0818828 0.96272 + outer loop + vertex 1.02843 1.31768 2.6168 + vertex 1.02733 1.31231 2.61664 + vertex 1.03136 1.31561 2.61584 + endloop + endfacet + facet normal 0.206015 -0.0947581 0.97395 + outer loop + vertex 1.03341 1.3088 2.61478 + vertex 1.03454 1.31435 2.61508 + vertex 1.03044 1.31106 2.61563 + endloop + endfacet + facet normal 0.148336 -0.0862364 0.98517 + outer loop + vertex 1.03454 1.31435 2.61508 + vertex 1.03887 1.31849 2.61479 + vertex 1.03515 1.3189 2.61539 + endloop + endfacet + facet normal 0.147577 -0.0924499 0.98472 + outer loop + vertex 1.03891 1.32356 2.61526 + vertex 1.03515 1.3189 2.61539 + vertex 1.03887 1.31849 2.61479 + endloop + endfacet + facet normal 0.248284 -0.0958714 0.963931 + outer loop + vertex 1.03244 1.31935 2.61594 + vertex 1.02843 1.31768 2.6168 + vertex 1.03136 1.31561 2.61584 + endloop + endfacet + facet normal 0.247062 -0.0926006 0.964565 + outer loop + vertex 1.03244 1.31935 2.61594 + vertex 1.03232 1.3225 2.61627 + vertex 1.02843 1.31768 2.6168 + endloop + endfacet + facet normal 0.232126 -0.080011 0.969389 + outer loop + vertex 1.03232 1.3225 2.61627 + vertex 1.02831 1.32275 2.61725 + vertex 1.02843 1.31768 2.6168 + endloop + endfacet + facet normal 0.143072 -0.0887808 0.985722 + outer loop + vertex 1.03501 1.32202 2.61569 + vertex 1.03515 1.3189 2.61539 + vertex 1.03891 1.32356 2.61526 + endloop + endfacet + facet normal 0.112174 -0.0858692 0.989972 + outer loop + vertex 1.03891 1.32356 2.61526 + vertex 1.04385 1.32818 2.6151 + vertex 1.04025 1.32862 2.61555 + endloop + endfacet + facet normal 0.130457 -0.0894617 0.98741 + outer loop + vertex 1.04065 1.33182 2.61579 + vertex 1.03785 1.32942 2.61594 + vertex 1.04025 1.32862 2.61555 + endloop + endfacet + facet normal 0.180172 -0.0906392 0.97945 + outer loop + vertex 1.03355 1.32768 2.61652 + vertex 1.03232 1.3225 2.61627 + vertex 1.03629 1.32565 2.61583 + endloop + endfacet + facet normal 0.138208 -0.0986471 0.985478 + outer loop + vertex 1.04065 1.33182 2.61579 + vertex 1.03853 1.33324 2.61623 + vertex 1.03785 1.32942 2.61594 + endloop + endfacet + facet normal 0.157 -0.0928956 0.98322 + outer loop + vertex 1.03853 1.33324 2.61623 + vertex 1.03839 1.33793 2.61669 + vertex 1.03334 1.33276 2.61701 + endloop + endfacet + facet normal 0.23037 -0.101962 0.967747 + outer loop + vertex 1.03232 1.3225 2.61627 + vertex 1.03355 1.32768 2.61652 + vertex 1.02831 1.32275 2.61725 + endloop + endfacet + facet normal 0.193113 -0.0730032 0.978457 + outer loop + vertex 1.0284 1.32776 2.61761 + vertex 1.03334 1.33276 2.61701 + vertex 1.02826 1.33282 2.61802 + endloop + endfacet + facet normal 0.192899 -0.0814177 0.977835 + outer loop + vertex 1.03334 1.33276 2.61701 + vertex 1.03323 1.33771 2.61744 + vertex 1.02826 1.33282 2.61802 + endloop + endfacet + facet normal 0.183695 -0.071762 0.98036 + outer loop + vertex 1.02826 1.33282 2.61802 + vertex 1.03323 1.33771 2.61744 + vertex 1.02829 1.33804 2.61839 + endloop + endfacet + facet normal 0.173562 -0.0714431 0.982228 + outer loop + vertex 1.02829 1.33804 2.61839 + vertex 1.0332 1.34272 2.61787 + vertex 1.02851 1.34328 2.61874 + endloop + endfacet + facet normal 0.164213 -0.0758588 0.983504 + outer loop + vertex 1.02851 1.34328 2.61874 + vertex 1.03323 1.34777 2.6183 + vertex 1.02868 1.34838 2.6191 + endloop + endfacet + facet normal 0.154858 -0.0755774 0.985042 + outer loop + vertex 1.02868 1.34838 2.6191 + vertex 1.03326 1.35284 2.61872 + vertex 1.02876 1.35341 2.61948 + endloop + endfacet + facet normal 0.153867 -0.0828043 0.984616 + outer loop + vertex 1.03326 1.35284 2.61872 + vertex 1.03329 1.35797 2.61915 + vertex 1.02876 1.35341 2.61948 + endloop + endfacet + facet normal 0.255682 -0.0621971 0.964758 + outer loop + vertex 1.02456 1.35712 2.62058 + vertex 1.02226 1.35455 2.62102 + vertex 1.02494 1.35393 2.62027 + endloop + endfacet + facet normal 0.273939 -0.0796382 0.958444 + outer loop + vertex 1.02456 1.35712 2.62058 + vertex 1.02194 1.35771 2.62137 + vertex 1.02226 1.35455 2.62102 + endloop + endfacet + facet normal 0.186571 -0.0775255 0.979378 + outer loop + vertex 1.02849 1.35862 2.61993 + vertex 1.02956 1.36421 2.62017 + vertex 1.0255 1.36088 2.62068 + endloop + endfacet + facet normal 0.12914 -0.0681889 0.989279 + outer loop + vertex 1.02956 1.36421 2.62017 + vertex 1.03385 1.36841 2.6199 + vertex 1.0301 1.36886 2.62042 + endloop + endfacet + facet normal 0.166431 -0.0679507 0.983709 + outer loop + vertex 1.0299 1.37206 2.62067 + vertex 1.02739 1.36934 2.62091 + vertex 1.0301 1.36886 2.62042 + endloop + endfacet + facet normal 0.240609 -0.0675238 0.968271 + outer loop + vertex 1.02341 1.36763 2.62172 + vertex 1.02237 1.36219 2.6216 + vertex 1.02636 1.36551 2.62084 + endloop + endfacet + facet normal 0.179412 -0.0802028 0.980499 + outer loop + vertex 1.0299 1.37206 2.62067 + vertex 1.02723 1.37255 2.6212 + vertex 1.02739 1.36934 2.62091 + endloop + endfacet + facet normal 0.167814 -0.0751207 0.982952 + outer loop + vertex 1.02841 1.37777 2.6214 + vertex 1.02723 1.37255 2.6212 + vertex 1.03113 1.37578 2.62078 + endloop + endfacet + facet normal 0.145043 -0.0732685 0.986709 + outer loop + vertex 1.03334 1.38343 2.62109 + vertex 1.02827 1.38277 2.62179 + vertex 1.02841 1.37777 2.6214 + endloop + endfacet + facet normal 0.177427 -0.0593463 0.982343 + outer loop + vertex 1.02329 1.38268 2.62272 + vertex 1.02821 1.38761 2.62213 + vertex 1.02318 1.38774 2.62304 + endloop + endfacet + facet normal 0.145648 -0.0784502 0.986221 + outer loop + vertex 1.03334 1.38343 2.62109 + vertex 1.03332 1.388 2.62146 + vertex 1.02827 1.38277 2.62179 + endloop + endfacet + facet normal 0.129417 -0.0673987 0.989297 + outer loop + vertex 1.02821 1.38761 2.62213 + vertex 1.03332 1.39268 2.62181 + vertex 1.02819 1.39257 2.62247 + endloop + endfacet + facet normal 0.105416 -0.0801088 0.991196 + outer loop + vertex 1.03828 1.38859 2.62098 + vertex 1.03841 1.39309 2.62133 + vertex 1.03332 1.388 2.62146 + endloop + endfacet + facet normal 0.0967142 -0.0728835 0.99264 + outer loop + vertex 1.03332 1.39268 2.62181 + vertex 1.03842 1.39774 2.62168 + vertex 1.03328 1.39754 2.62217 + endloop + endfacet + facet normal 0.0789003 -0.077599 0.993858 + outer loop + vertex 1.04337 1.39355 2.62097 + vertex 1.0435 1.39809 2.62131 + vertex 1.03841 1.39309 2.62133 + endloop + endfacet + facet normal 0.0678086 -0.0757521 0.994818 + outer loop + vertex 1.0435 1.39809 2.62131 + vertex 1.04853 1.40307 2.62135 + vertex 1.04346 1.40277 2.62167 + endloop + endfacet + facet normal 0.0677793 -0.0752025 0.994862 + outer loop + vertex 1.04853 1.40307 2.62135 + vertex 1.04842 1.40778 2.62172 + vertex 1.04346 1.40277 2.62167 + endloop + endfacet + facet normal 0.0685593 -0.0742965 0.994877 + outer loop + vertex 1.04842 1.40778 2.62172 + vertex 1.05334 1.41275 2.62175 + vertex 1.04831 1.4127 2.62209 + endloop + endfacet + facet normal 0.0685565 -0.0737324 0.994919 + outer loop + vertex 1.05334 1.41275 2.62175 + vertex 1.05322 1.41768 2.62212 + vertex 1.04831 1.4127 2.62209 + endloop + endfacet + facet normal 0.0671705 -0.0724851 0.995105 + outer loop + vertex 1.05322 1.41768 2.62212 + vertex 1.05818 1.42261 2.62214 + vertex 1.05321 1.42271 2.62249 + endloop + endfacet + facet normal 0.0671439 -0.0735811 0.995026 + outer loop + vertex 1.05818 1.42261 2.62214 + vertex 1.05819 1.42764 2.62252 + vertex 1.05321 1.42271 2.62249 + endloop + endfacet + facet normal 0.0530208 -0.0715991 0.996023 + outer loop + vertex 1.05819 1.42764 2.62252 + vertex 1.06329 1.43259 2.6226 + vertex 1.05822 1.43267 2.62288 + endloop + endfacet + facet normal 0.0579503 -0.0653924 0.996175 + outer loop + vertex 1.05328 1.43275 2.62319 + vertex 1.05825 1.43768 2.62322 + vertex 1.05329 1.43773 2.62351 + endloop + endfacet + facet normal 0.0530068 -0.0722853 0.995974 + outer loop + vertex 1.06329 1.43259 2.6226 + vertex 1.06332 1.43761 2.62296 + vertex 1.05822 1.43267 2.62288 + endloop + endfacet + facet normal 0.0457996 -0.0647753 0.996848 + outer loop + vertex 1.05825 1.43768 2.62322 + vertex 1.06333 1.44262 2.62331 + vertex 1.05825 1.44267 2.62355 + endloop + endfacet + facet normal 0.0417529 -0.0703743 0.996646 + outer loop + vertex 1.06848 1.43762 2.62275 + vertex 1.0685 1.44264 2.6231 + vertex 1.06332 1.43761 2.62296 + endloop + endfacet + facet normal 0.0382711 -0.0638795 0.997224 + outer loop + vertex 1.06333 1.44262 2.62331 + vertex 1.0685 1.44764 2.62343 + vertex 1.06333 1.44761 2.62363 + endloop + endfacet + facet normal 0.0588998 -0.0610805 0.996393 + outer loop + vertex 1.0735 1.44277 2.62281 + vertex 1.07351 1.44778 2.62312 + vertex 1.0685 1.44264 2.6231 + endloop + endfacet + facet normal 0.0654698 -0.0603572 0.996027 + outer loop + vertex 1.0685 1.44764 2.62343 + vertex 1.07351 1.45277 2.62341 + vertex 1.06849 1.45263 2.62373 + endloop + endfacet + facet normal 0.146094 -0.0478737 0.988112 + outer loop + vertex 1.07797 1.44792 2.62247 + vertex 1.07798 1.45292 2.62271 + vertex 1.07351 1.44778 2.62312 + endloop + endfacet + facet normal 0.0652702 -0.0520991 0.996507 + outer loop + vertex 1.07351 1.45277 2.62341 + vertex 1.0735 1.45775 2.62367 + vertex 1.06849 1.45263 2.62373 + endloop + endfacet + facet normal 0.0382629 -0.0604934 0.997435 + outer loop + vertex 1.0685 1.44764 2.62343 + vertex 1.06849 1.45263 2.62373 + vertex 1.06333 1.44761 2.62363 + endloop + endfacet + facet normal 0.0458124 -0.0638556 0.996907 + outer loop + vertex 1.06333 1.44262 2.62331 + vertex 1.06333 1.44761 2.62363 + vertex 1.05825 1.44267 2.62355 + endloop + endfacet + facet normal 0.0579598 -0.0647492 0.996217 + outer loop + vertex 1.05825 1.43768 2.62322 + vertex 1.05825 1.44267 2.62355 + vertex 1.05329 1.43773 2.62351 + endloop + endfacet + facet normal 0.0616588 -0.0653838 0.995953 + outer loop + vertex 1.05328 1.43275 2.62319 + vertex 1.05329 1.43773 2.62351 + vertex 1.04835 1.43274 2.62349 + endloop + endfacet + facet normal 0.0616565 -0.066198 0.9959 + outer loop + vertex 1.04835 1.42778 2.62316 + vertex 1.05328 1.43275 2.62319 + vertex 1.04835 1.43274 2.62349 + endloop + endfacet + facet normal 0.0641081 -0.0687459 0.995572 + outer loop + vertex 1.04832 1.42278 2.62282 + vertex 1.05325 1.42774 2.62284 + vertex 1.04835 1.42778 2.62316 + endloop + endfacet + facet normal 0.0667309 -0.0709688 0.995244 + outer loop + vertex 1.04828 1.41773 2.62246 + vertex 1.04832 1.42278 2.62282 + vertex 1.04334 1.41773 2.62279 + endloop + endfacet + facet normal 0.0667257 -0.0720755 0.995165 + outer loop + vertex 1.04333 1.41269 2.62243 + vertex 1.04828 1.41773 2.62246 + vertex 1.04334 1.41773 2.62279 + endloop + endfacet + facet normal 0.0760359 -0.0739088 0.994362 + outer loop + vertex 1.04337 1.40766 2.62205 + vertex 1.04333 1.41269 2.62243 + vertex 1.0383 1.40759 2.62243 + endloop + endfacet + facet normal 0.0760437 -0.0748742 0.994289 + outer loop + vertex 1.03836 1.4026 2.62205 + vertex 1.04337 1.40766 2.62205 + vertex 1.0383 1.40759 2.62243 + endloop + endfacet + facet normal 0.0967772 -0.0749649 0.992479 + outer loop + vertex 1.03842 1.39774 2.62168 + vertex 1.03836 1.4026 2.62205 + vertex 1.03328 1.39754 2.62217 + endloop + endfacet + facet normal 0.129478 -0.0723746 0.988938 + outer loop + vertex 1.03332 1.39268 2.62181 + vertex 1.03328 1.39754 2.62217 + vertex 1.02819 1.39257 2.62247 + endloop + endfacet + facet normal 0.177158 -0.066675 0.981921 + outer loop + vertex 1.02821 1.38761 2.62213 + vertex 1.02819 1.39257 2.62247 + vertex 1.02318 1.38774 2.62304 + endloop + endfacet + facet normal 0.158156 -0.0560261 0.985823 + outer loop + vertex 1.02324 1.39298 2.62334 + vertex 1.0282 1.39763 2.62281 + vertex 1.02345 1.39819 2.6236 + endloop + endfacet + facet normal 0.148702 -0.0580787 0.987175 + outer loop + vertex 1.02345 1.39819 2.6236 + vertex 1.02823 1.40268 2.62314 + vertex 1.02355 1.40324 2.62388 + endloop + endfacet + facet normal 0.186309 -0.046816 0.981375 + outer loop + vertex 1.01941 1.40434 2.62477 + vertex 1.02361 1.40824 2.62416 + vertex 1.01955 1.40935 2.62498 + endloop + endfacet + facet normal 0.184538 -0.0533428 0.981377 + outer loop + vertex 1.02361 1.40824 2.62416 + vertex 1.02369 1.41327 2.62442 + vertex 1.01955 1.40935 2.62498 + endloop + endfacet + facet normal 0.176317 -0.0443884 0.983332 + outer loop + vertex 1.01955 1.40935 2.62498 + vertex 1.02369 1.41327 2.62442 + vertex 1.01975 1.41432 2.62517 + endloop + endfacet + facet normal 0.174407 -0.051536 0.983324 + outer loop + vertex 1.02369 1.41327 2.62442 + vertex 1.02374 1.41831 2.62467 + vertex 1.01975 1.41432 2.62517 + endloop + endfacet + facet normal 0.162885 -0.0397375 0.985844 + outer loop + vertex 1.01975 1.41432 2.62517 + vertex 1.02374 1.41831 2.62467 + vertex 1.01991 1.41891 2.62533 + endloop + endfacet + facet normal 0.160936 -0.0520839 0.98559 + outer loop + vertex 1.02345 1.42357 2.625 + vertex 1.01991 1.41891 2.62533 + vertex 1.02374 1.41831 2.62467 + endloop + endfacet + facet normal 0.119626 -0.0547394 0.991309 + outer loop + vertex 1.02374 1.41831 2.62467 + vertex 1.02827 1.42285 2.62438 + vertex 1.02345 1.42357 2.625 + endloop + endfacet + facet normal 0.119114 -0.058058 0.991182 + outer loop + vertex 1.02827 1.42285 2.62438 + vertex 1.02848 1.42811 2.62466 + vertex 1.02345 1.42357 2.625 + endloop + endfacet + facet normal 0.114602 -0.0529941 0.991997 + outer loop + vertex 1.02345 1.42357 2.625 + vertex 1.02848 1.42811 2.62466 + vertex 1.02451 1.4292 2.62518 + endloop + endfacet + facet normal 0.163485 -0.0620258 0.984594 + outer loop + vertex 1.02345 1.42357 2.625 + vertex 1.02451 1.4292 2.62518 + vertex 1.02045 1.42593 2.62565 + endloop + endfacet + facet normal 0.165166 -0.059853 0.984448 + outer loop + vertex 1.01951 1.42216 2.62557 + vertex 1.02345 1.42357 2.625 + vertex 1.02045 1.42593 2.62565 + endloop + endfacet + facet normal 0.255407 -0.0818996 0.963359 + outer loop + vertex 1.02045 1.42593 2.62565 + vertex 1.01687 1.42279 2.62633 + vertex 1.01951 1.42216 2.62557 + endloop + endfacet + facet normal 0.258664 -0.0686504 0.963525 + outer loop + vertex 1.01951 1.42216 2.62557 + vertex 1.01687 1.42279 2.62633 + vertex 1.01721 1.41959 2.62601 + endloop + endfacet + facet normal 0.232947 -0.0441996 0.971485 + outer loop + vertex 1.01951 1.42216 2.62557 + vertex 1.01721 1.41959 2.62601 + vertex 1.01991 1.41891 2.62533 + endloop + endfacet + facet normal 0.239741 -0.0628651 0.968799 + outer loop + vertex 1.01731 1.4273 2.62651 + vertex 1.01687 1.42279 2.62633 + vertex 1.02045 1.42593 2.62565 + endloop + endfacet + facet normal 0.236727 -0.0699404 0.969056 + outer loop + vertex 1.02131 1.43059 2.62577 + vertex 1.01731 1.4273 2.62651 + vertex 1.02045 1.42593 2.62565 + endloop + endfacet + facet normal 0.223539 -0.0529756 0.973254 + outer loop + vertex 1.01833 1.43275 2.62657 + vertex 1.01731 1.4273 2.62651 + vertex 1.02131 1.43059 2.62577 + endloop + endfacet + facet normal 0.217038 -0.06228 0.974174 + outer loop + vertex 1.02228 1.43442 2.6258 + vertex 1.01833 1.43275 2.62657 + vertex 1.02131 1.43059 2.62577 + endloop + endfacet + facet normal 0.148579 -0.0449369 0.987879 + outer loop + vertex 1.02501 1.43388 2.62537 + vertex 1.02228 1.43442 2.6258 + vertex 1.02131 1.43059 2.62577 + endloop + endfacet + facet normal 0.158614 -0.056503 0.985723 + outer loop + vertex 1.02451 1.4292 2.62518 + vertex 1.02501 1.43388 2.62537 + vertex 1.02131 1.43059 2.62577 + endloop + endfacet + facet normal 0.211914 -0.049252 0.976047 + outer loop + vertex 1.02228 1.43442 2.6258 + vertex 1.02192 1.43753 2.62604 + vertex 1.01833 1.43275 2.62657 + endloop + endfacet + facet normal 0.209131 -0.047082 0.976754 + outer loop + vertex 1.02192 1.43753 2.62604 + vertex 1.01805 1.43774 2.62687 + vertex 1.01833 1.43275 2.62657 + endloop + endfacet + facet normal 0.15881 -0.0560502 0.985717 + outer loop + vertex 1.02045 1.42593 2.62565 + vertex 1.02451 1.4292 2.62518 + vertex 1.02131 1.43059 2.62577 + endloop + endfacet + facet normal 0.113553 -0.0567824 0.991908 + outer loop + vertex 1.02848 1.42811 2.62466 + vertex 1.02878 1.43332 2.62492 + vertex 1.02451 1.4292 2.62518 + endloop + endfacet + facet normal 0.0916152 -0.0570969 0.994156 + outer loop + vertex 1.02827 1.42285 2.62438 + vertex 1.03321 1.42762 2.6242 + vertex 1.02848 1.42811 2.62466 + endloop + endfacet + facet normal 0.0913214 -0.0597741 0.994026 + outer loop + vertex 1.03321 1.42762 2.6242 + vertex 1.03329 1.43272 2.6245 + vertex 1.02848 1.42811 2.62466 + endloop + endfacet + facet normal 0.0871357 -0.0553865 0.994656 + outer loop + vertex 1.02848 1.42811 2.62466 + vertex 1.03329 1.43272 2.6245 + vertex 1.02878 1.43332 2.62492 + endloop + endfacet + facet normal 0.0949224 -0.0605485 0.993642 + outer loop + vertex 1.03318 1.42255 2.62389 + vertex 1.03321 1.42762 2.6242 + vertex 1.02827 1.42285 2.62438 + endloop + endfacet + facet normal 0.0951215 -0.0576148 0.993797 + outer loop + vertex 1.02825 1.41771 2.62408 + vertex 1.03318 1.42255 2.62389 + vertex 1.02827 1.42285 2.62438 + endloop + endfacet + facet normal 0.0991965 -0.0617932 0.993147 + outer loop + vertex 1.03319 1.41753 2.62358 + vertex 1.03318 1.42255 2.62389 + vertex 1.02825 1.41771 2.62408 + endloop + endfacet + facet normal 0.122369 -0.0575079 0.990817 + outer loop + vertex 1.02825 1.41771 2.62408 + vertex 1.02827 1.42285 2.62438 + vertex 1.02374 1.41831 2.62467 + endloop + endfacet + facet normal 0.163064 -0.0537295 0.985151 + outer loop + vertex 1.01951 1.42216 2.62557 + vertex 1.01991 1.41891 2.62533 + vertex 1.02345 1.42357 2.625 + endloop + endfacet + facet normal 0.123214 -0.0513984 0.991048 + outer loop + vertex 1.02369 1.41327 2.62442 + vertex 1.02825 1.41771 2.62408 + vertex 1.02374 1.41831 2.62467 + endloop + endfacet + facet normal 0.129603 -0.0580493 0.989865 + outer loop + vertex 1.02824 1.41268 2.62379 + vertex 1.02825 1.41771 2.62408 + vertex 1.02369 1.41327 2.62442 + endloop + endfacet + facet normal 0.147768 -0.0653997 0.986857 + outer loop + vertex 1.02823 1.40268 2.62314 + vertex 1.02823 1.40768 2.62348 + vertex 1.02355 1.40324 2.62388 + endloop + endfacet + facet normal 0.130287 -0.0529818 0.99006 + outer loop + vertex 1.02361 1.40824 2.62416 + vertex 1.02824 1.41268 2.62379 + vertex 1.02369 1.41327 2.62442 + endloop + endfacet + facet normal 0.112169 -0.0686198 0.991317 + outer loop + vertex 1.03321 1.40755 2.6229 + vertex 1.0332 1.41254 2.62325 + vertex 1.02823 1.40768 2.62348 + endloop + endfacet + facet normal 0.0993542 -0.0581643 0.993351 + outer loop + vertex 1.02824 1.41268 2.62379 + vertex 1.03319 1.41753 2.62358 + vertex 1.02825 1.41771 2.62408 + endloop + endfacet + facet normal 0.0886175 -0.0695931 0.993632 + outer loop + vertex 1.03829 1.41262 2.6228 + vertex 1.03829 1.41762 2.62315 + vertex 1.0332 1.41254 2.62325 + endloop + endfacet + facet normal 0.0695809 -0.0664161 0.995363 + outer loop + vertex 1.03829 1.41762 2.62315 + vertex 1.04336 1.42273 2.62314 + vertex 1.03828 1.42259 2.62348 + endloop + endfacet + facet normal 0.0668579 -0.0639165 0.995713 + outer loop + vertex 1.03828 1.42259 2.62348 + vertex 1.04336 1.42769 2.62347 + vertex 1.03826 1.42756 2.6238 + endloop + endfacet + facet normal 0.0650885 -0.0623404 0.99593 + outer loop + vertex 1.03826 1.42756 2.6238 + vertex 1.04333 1.43263 2.62379 + vertex 1.03824 1.43254 2.62412 + endloop + endfacet + facet normal 0.0710179 -0.0574305 0.99582 + outer loop + vertex 1.03329 1.43272 2.6245 + vertex 1.03821 1.43755 2.62442 + vertex 1.03334 1.43787 2.62479 + endloop + endfacet + facet normal 0.0650855 -0.0621283 0.995944 + outer loop + vertex 1.04333 1.43263 2.62379 + vertex 1.04329 1.43758 2.6241 + vertex 1.03824 1.43254 2.62412 + endloop + endfacet + facet normal 0.0614942 -0.0573373 0.996459 + outer loop + vertex 1.03821 1.43755 2.62442 + vertex 1.04323 1.44253 2.6244 + vertex 1.03821 1.44259 2.62471 + endloop + endfacet + facet normal 0.0597319 -0.0600733 0.996405 + outer loop + vertex 1.04833 1.4377 2.62381 + vertex 1.0483 1.44264 2.62411 + vertex 1.04329 1.43758 2.6241 + endloop + endfacet + facet normal 0.0581105 -0.0559929 0.996739 + outer loop + vertex 1.04323 1.44253 2.6244 + vertex 1.04826 1.44758 2.62439 + vertex 1.04318 1.4475 2.62468 + endloop + endfacet + facet normal 0.0580015 -0.0576227 0.996652 + outer loop + vertex 1.05329 1.44271 2.62382 + vertex 1.05328 1.44768 2.62411 + vertex 1.0483 1.44264 2.62411 + endloop + endfacet + facet normal 0.056301 -0.0531922 0.996996 + outer loop + vertex 1.04826 1.44758 2.62439 + vertex 1.05326 1.45263 2.62438 + vertex 1.0482 1.45253 2.62466 + endloop + endfacet + facet normal 0.052202 -0.0560153 0.997064 + outer loop + vertex 1.05826 1.44767 2.62385 + vertex 1.05827 1.45265 2.62413 + vertex 1.05328 1.44768 2.62411 + endloop + endfacet + facet normal 0.0486195 -0.0505313 0.997538 + outer loop + vertex 1.05326 1.45263 2.62438 + vertex 1.05826 1.45762 2.62439 + vertex 1.05321 1.45758 2.62463 + endloop + endfacet + facet normal 0.0392522 -0.0547894 0.997726 + outer loop + vertex 1.06334 1.45261 2.62392 + vertex 1.06335 1.45761 2.6242 + vertex 1.05827 1.45265 2.62413 + endloop + endfacet + facet normal 0.0346093 -0.0482151 0.998237 + outer loop + vertex 1.05826 1.45762 2.62439 + vertex 1.06335 1.46259 2.62445 + vertex 1.05822 1.46258 2.62463 + endloop + endfacet + facet normal 0.0360076 -0.0523293 0.997981 + outer loop + vertex 1.06849 1.45763 2.62401 + vertex 1.06851 1.46263 2.62428 + vertex 1.06335 1.45761 2.6242 + endloop + endfacet + facet normal 0.0331304 -0.045516 0.998414 + outer loop + vertex 1.06335 1.46259 2.62445 + vertex 1.06851 1.46763 2.62451 + vertex 1.06332 1.46756 2.62468 + endloop + endfacet + facet normal 0.0732021 -0.0447812 0.996311 + outer loop + vertex 1.0735 1.46276 2.62391 + vertex 1.07352 1.46776 2.62414 + vertex 1.06851 1.46263 2.62428 + endloop + endfacet + facet normal 0.0764955 -0.0407999 0.996235 + outer loop + vertex 1.06851 1.46763 2.62451 + vertex 1.07354 1.47276 2.62433 + vertex 1.0685 1.47261 2.62471 + endloop + endfacet + facet normal 0.18837 -0.0299708 0.981641 + outer loop + vertex 1.078 1.46789 2.62328 + vertex 1.07801 1.47289 2.62343 + vertex 1.07352 1.46776 2.62414 + endloop + endfacet + facet normal 0.0763203 -0.0344663 0.996487 + outer loop + vertex 1.07354 1.47276 2.62433 + vertex 1.07353 1.47775 2.62451 + vertex 1.0685 1.47261 2.62471 + endloop + endfacet + facet normal 0.0330814 -0.041012 0.998611 + outer loop + vertex 1.06851 1.46763 2.62451 + vertex 1.0685 1.47261 2.62471 + vertex 1.06332 1.46756 2.62468 + endloop + endfacet + facet normal 0.0346068 -0.0455059 0.998364 + outer loop + vertex 1.06335 1.46259 2.62445 + vertex 1.06332 1.46756 2.62468 + vertex 1.05822 1.46258 2.62463 + endloop + endfacet + facet normal 0.0486038 -0.0480747 0.997661 + outer loop + vertex 1.05826 1.45762 2.62439 + vertex 1.05822 1.46258 2.62463 + vertex 1.05321 1.45758 2.62463 + endloop + endfacet + facet normal 0.0562562 -0.0504327 0.997142 + outer loop + vertex 1.05326 1.45263 2.62438 + vertex 1.05321 1.45758 2.62463 + vertex 1.0482 1.45253 2.62466 + endloop + endfacet + facet normal 0.0580729 -0.0531658 0.996896 + outer loop + vertex 1.04826 1.44758 2.62439 + vertex 1.0482 1.45253 2.62466 + vertex 1.04318 1.4475 2.62468 + endloop + endfacet + facet normal 0.0615175 -0.0559464 0.996537 + outer loop + vertex 1.04323 1.44253 2.6244 + vertex 1.04318 1.4475 2.62468 + vertex 1.03821 1.44259 2.62471 + endloop + endfacet + facet normal 0.0710272 -0.0572978 0.995827 + outer loop + vertex 1.03821 1.43755 2.62442 + vertex 1.03821 1.44259 2.62471 + vertex 1.03334 1.43787 2.62479 + endloop + endfacet + facet normal 0.0868457 -0.0575116 0.99456 + outer loop + vertex 1.03329 1.43272 2.6245 + vertex 1.03334 1.43787 2.62479 + vertex 1.02878 1.43332 2.62492 + endloop + endfacet + facet normal 0.108507 -0.0515007 0.992761 + outer loop + vertex 1.02451 1.4292 2.62518 + vertex 1.02878 1.43332 2.62492 + vertex 1.02501 1.43388 2.62537 + endloop + endfacet + facet normal 0.148004 -0.0477966 0.987831 + outer loop + vertex 1.0247 1.43711 2.62557 + vertex 1.02228 1.43442 2.6258 + vertex 1.02501 1.43388 2.62537 + endloop + endfacet + facet normal 0.15739 -0.0563948 0.985925 + outer loop + vertex 1.0247 1.43711 2.62557 + vertex 1.02192 1.43753 2.62604 + vertex 1.02228 1.43442 2.6258 + endloop + endfacet + facet normal 0.208817 -0.0521257 0.976565 + outer loop + vertex 1.02192 1.43753 2.62604 + vertex 1.02228 1.442 2.6262 + vertex 1.01805 1.43774 2.62687 + endloop + endfacet + facet normal 0.19662 -0.0395317 0.979682 + outer loop + vertex 1.01805 1.43774 2.62687 + vertex 1.02228 1.442 2.6262 + vertex 1.01823 1.44268 2.62704 + endloop + endfacet + facet normal 0.194622 -0.0512467 0.979539 + outer loop + vertex 1.02228 1.442 2.6262 + vertex 1.02332 1.44752 2.62628 + vertex 1.01823 1.44268 2.62704 + endloop + endfacet + facet normal 0.178466 -0.0336525 0.98337 + outer loop + vertex 1.01823 1.44268 2.62704 + vertex 1.02332 1.44752 2.62628 + vertex 1.01837 1.44771 2.62718 + endloop + endfacet + facet normal 0.178174 -0.0403143 0.983173 + outer loop + vertex 1.02332 1.44752 2.62628 + vertex 1.02319 1.45264 2.62651 + vertex 1.01837 1.44771 2.62718 + endloop + endfacet + facet normal 0.169138 -0.0312297 0.985097 + outer loop + vertex 1.01837 1.44771 2.62718 + vertex 1.02319 1.45264 2.62651 + vertex 1.01835 1.45267 2.62735 + endloop + endfacet + facet normal 0.169068 -0.0378967 0.984876 + outer loop + vertex 1.02319 1.45264 2.62651 + vertex 1.02331 1.45763 2.62668 + vertex 1.01835 1.45267 2.62735 + endloop + endfacet + facet normal 0.160419 -0.0290084 0.986623 + outer loop + vertex 1.01835 1.45267 2.62735 + vertex 1.02331 1.45763 2.62668 + vertex 1.01831 1.45759 2.6275 + endloop + endfacet + facet normal 0.160429 -0.0328598 0.9865 + outer loop + vertex 1.02331 1.45763 2.62668 + vertex 1.02326 1.46252 2.62686 + vertex 1.01831 1.45759 2.6275 + endloop + endfacet + facet normal 0.110164 -0.033631 0.993344 + outer loop + vertex 1.02331 1.45763 2.62668 + vertex 1.02838 1.46285 2.6263 + vertex 1.02326 1.46252 2.62686 + endloop + endfacet + facet normal 0.110205 -0.0343289 0.993316 + outer loop + vertex 1.02838 1.46285 2.6263 + vertex 1.02835 1.46763 2.62647 + vertex 1.02326 1.46252 2.62686 + endloop + endfacet + facet normal 0.107334 -0.0314377 0.993726 + outer loop + vertex 1.02326 1.46252 2.62686 + vertex 1.02835 1.46763 2.62647 + vertex 1.0232 1.46742 2.62702 + endloop + endfacet + facet normal 0.156312 -0.0305948 0.987234 + outer loop + vertex 1.02326 1.46252 2.62686 + vertex 1.0232 1.46742 2.62702 + vertex 1.01827 1.46253 2.62765 + endloop + endfacet + facet normal 0.152495 -0.0266479 0.987945 + outer loop + vertex 1.01827 1.46253 2.62765 + vertex 1.0232 1.46742 2.62702 + vertex 1.01823 1.46751 2.62779 + endloop + endfacet + facet normal 0.15247 -0.0277299 0.987919 + outer loop + vertex 1.0232 1.46742 2.62702 + vertex 1.02314 1.47237 2.62716 + vertex 1.01823 1.46751 2.62779 + endloop + endfacet + facet normal 0.150984 -0.0261943 0.988189 + outer loop + vertex 1.01823 1.46751 2.62779 + vertex 1.02314 1.47237 2.62716 + vertex 1.01824 1.47253 2.62792 + endloop + endfacet + facet normal 0.151003 -0.0256566 0.9882 + outer loop + vertex 1.02314 1.47237 2.62716 + vertex 1.02312 1.47738 2.6273 + vertex 1.01824 1.47253 2.62792 + endloop + endfacet + facet normal 0.146838 -0.02137 0.98893 + outer loop + vertex 1.01824 1.47253 2.62792 + vertex 1.02312 1.47738 2.6273 + vertex 1.01825 1.47754 2.62803 + endloop + endfacet + facet normal 0.146846 -0.0211383 0.988933 + outer loop + vertex 1.02312 1.47738 2.6273 + vertex 1.02312 1.4824 2.62741 + vertex 1.01825 1.47754 2.62803 + endloop + endfacet + facet normal 0.100859 -0.0212799 0.994673 + outer loop + vertex 1.02312 1.47738 2.6273 + vertex 1.02821 1.48245 2.62689 + vertex 1.02312 1.4824 2.62741 + endloop + endfacet + facet normal 0.100834 -0.0181259 0.994738 + outer loop + vertex 1.02821 1.48245 2.62689 + vertex 1.0282 1.48746 2.62698 + vertex 1.02312 1.4824 2.62741 + endloop + endfacet + facet normal 0.0988459 -0.0161131 0.994972 + outer loop + vertex 1.02312 1.4824 2.62741 + vertex 1.0282 1.48746 2.62698 + vertex 1.02312 1.4874 2.62749 + endloop + endfacet + facet normal 0.143442 -0.016012 0.989529 + outer loop + vertex 1.02312 1.4824 2.62741 + vertex 1.02312 1.4874 2.62749 + vertex 1.01826 1.48255 2.62811 + endloop + endfacet + facet normal 0.0988271 -0.0144683 0.994999 + outer loop + vertex 1.0282 1.48746 2.62698 + vertex 1.02819 1.49246 2.62706 + vertex 1.02312 1.4874 2.62749 + endloop + endfacet + facet normal 0.0969518 -0.0125737 0.99521 + outer loop + vertex 1.02312 1.4874 2.62749 + vertex 1.02819 1.49246 2.62706 + vertex 1.02311 1.49238 2.62755 + endloop + endfacet + facet normal 0.139277 -0.0124466 0.990175 + outer loop + vertex 1.02312 1.4874 2.62749 + vertex 1.02311 1.49238 2.62755 + vertex 1.01826 1.48753 2.62817 + endloop + endfacet + facet normal 0.0969332 -0.0113138 0.995227 + outer loop + vertex 1.02819 1.49246 2.62706 + vertex 1.02817 1.49744 2.62712 + vertex 1.02311 1.49238 2.62755 + endloop + endfacet + facet normal 0.0957752 -0.0101449 0.995351 + outer loop + vertex 1.02311 1.49238 2.62755 + vertex 1.02817 1.49744 2.62712 + vertex 1.02309 1.49735 2.6276 + endloop + endfacet + facet normal 0.136667 -0.00996231 0.990567 + outer loop + vertex 1.02311 1.49238 2.62755 + vertex 1.02309 1.49735 2.6276 + vertex 1.01826 1.4925 2.62822 + endloop + endfacet + facet normal 0.0957556 -0.00896249 0.995365 + outer loop + vertex 1.02817 1.49744 2.62712 + vertex 1.02817 1.50241 2.62716 + vertex 1.02309 1.49735 2.6276 + endloop + endfacet + facet normal 0.0937123 -0.00689828 0.995575 + outer loop + vertex 1.02309 1.49735 2.6276 + vertex 1.02817 1.50241 2.62716 + vertex 1.02307 1.50231 2.62764 + endloop + endfacet + facet normal 0.133159 -0.00666683 0.991072 + outer loop + vertex 1.02309 1.49735 2.6276 + vertex 1.02307 1.50231 2.62764 + vertex 1.01825 1.49746 2.62826 + endloop + endfacet + facet normal 0.131903 -0.00539438 0.991248 + outer loop + vertex 1.01825 1.49746 2.62826 + vertex 1.02307 1.50231 2.62764 + vertex 1.01823 1.50242 2.62828 + endloop + endfacet + facet normal 0.131919 -0.00467535 0.991249 + outer loop + vertex 1.02307 1.50231 2.62764 + vertex 1.02306 1.50728 2.62766 + vertex 1.01823 1.50242 2.62828 + endloop + endfacet + facet normal 0.129526 -0.00225673 0.991573 + outer loop + vertex 1.01823 1.50242 2.62828 + vertex 1.02306 1.50728 2.62766 + vertex 1.0182 1.50736 2.6283 + endloop + endfacet + facet normal 0.129553 -0.000595167 0.991572 + outer loop + vertex 1.02306 1.50728 2.62766 + vertex 1.02307 1.51227 2.62767 + vertex 1.0182 1.50736 2.6283 + endloop + endfacet + facet normal 0.128952 1.15429e-05 0.991651 + outer loop + vertex 1.0182 1.50736 2.6283 + vertex 1.02307 1.51227 2.62767 + vertex 1.01819 1.51231 2.6283 + endloop + endfacet + facet normal 0.128985 0.00366968 0.99164 + outer loop + vertex 1.02307 1.51227 2.62767 + vertex 1.02312 1.51729 2.62764 + vertex 1.01819 1.51231 2.6283 + endloop + endfacet + facet normal 0.129356 0.0032953 0.991593 + outer loop + vertex 1.01819 1.51231 2.6283 + vertex 1.02312 1.51729 2.62764 + vertex 1.0182 1.51729 2.62828 + endloop + endfacet + facet normal 0.129361 0.00808926 0.991565 + outer loop + vertex 1.02312 1.51729 2.62764 + vertex 1.0232 1.52234 2.62759 + vertex 1.0182 1.51729 2.62828 + endloop + endfacet + facet normal 0.13021 0.00723319 0.99146 + outer loop + vertex 1.0182 1.51729 2.62828 + vertex 1.0232 1.52234 2.62759 + vertex 1.01823 1.52232 2.62824 + endloop + endfacet + facet normal 0.130175 0.0133058 0.991402 + outer loop + vertex 1.0232 1.52234 2.62759 + vertex 1.0233 1.52742 2.62751 + vertex 1.01823 1.52232 2.62824 + endloop + endfacet + facet normal 0.132657 0.0107975 0.991103 + outer loop + vertex 1.01823 1.52232 2.62824 + vertex 1.0233 1.52742 2.62751 + vertex 1.0183 1.52739 2.62818 + endloop + endfacet + facet normal 0.132609 0.0173958 0.991016 + outer loop + vertex 1.0233 1.52742 2.62751 + vertex 1.02338 1.53248 2.62741 + vertex 1.0183 1.52739 2.62818 + endloop + endfacet + facet normal 0.135853 0.0140958 0.990629 + outer loop + vertex 1.0183 1.52739 2.62818 + vertex 1.02338 1.53248 2.62741 + vertex 1.01839 1.53249 2.62809 + endloop + endfacet + facet normal 0.135847 0.0215651 0.990495 + outer loop + vertex 1.02338 1.53248 2.62741 + vertex 1.02345 1.53752 2.62729 + vertex 1.01839 1.53249 2.62809 + endloop + endfacet + facet normal 0.102256 0.0221028 0.994513 + outer loop + vertex 1.02338 1.53248 2.62741 + vertex 1.02833 1.53755 2.62679 + vertex 1.02345 1.53752 2.62729 + endloop + endfacet + facet normal 0.102182 0.0294232 0.994331 + outer loop + vertex 1.02833 1.53755 2.62679 + vertex 1.02827 1.54237 2.62665 + vertex 1.02345 1.53752 2.62729 + endloop + endfacet + facet normal 0.105051 0.0265431 0.994113 + outer loop + vertex 1.02345 1.53752 2.62729 + vertex 1.02827 1.54237 2.62665 + vertex 1.02343 1.54254 2.62716 + endloop + endfacet + facet normal 0.139302 0.0265367 0.989894 + outer loop + vertex 1.02345 1.53752 2.62729 + vertex 1.02343 1.54254 2.62716 + vertex 1.01848 1.53759 2.62799 + endloop + endfacet + facet normal 0.143903 0.0218427 0.989351 + outer loop + vertex 1.01848 1.53759 2.62799 + vertex 1.02343 1.54254 2.62716 + vertex 1.01853 1.54266 2.62787 + endloop + endfacet + facet normal 0.144097 0.0320047 0.989046 + outer loop + vertex 1.02343 1.54254 2.62716 + vertex 1.02323 1.54742 2.62703 + vertex 1.01853 1.54266 2.62787 + endloop + endfacet + facet normal 0.148931 0.0271332 0.988475 + outer loop + vertex 1.01853 1.54266 2.62787 + vertex 1.02323 1.54742 2.62703 + vertex 1.01853 1.54768 2.62773 + endloop + endfacet + facet normal 0.149288 0.0342795 0.988199 + outer loop + vertex 1.02323 1.54742 2.62703 + vertex 1.02309 1.55227 2.62688 + vertex 1.01853 1.54768 2.62773 + endloop + endfacet + facet normal 0.154145 0.0293291 0.987613 + outer loop + vertex 1.01853 1.54768 2.62773 + vertex 1.02309 1.55227 2.62688 + vertex 1.01845 1.55269 2.62759 + endloop + endfacet + facet normal 0.116934 0.0335104 0.992574 + outer loop + vertex 1.02323 1.54742 2.62703 + vertex 1.02688 1.55133 2.62647 + vertex 1.02309 1.55227 2.62688 + endloop + endfacet + facet normal 0.116815 0.0330164 0.992605 + outer loop + vertex 1.02688 1.55133 2.62647 + vertex 1.02768 1.55624 2.62621 + vertex 1.02309 1.55227 2.62688 + endloop + endfacet + facet normal 0.114705 0.0354745 0.992766 + outer loop + vertex 1.02309 1.55227 2.62688 + vertex 1.02768 1.55624 2.62621 + vertex 1.02273 1.55719 2.62675 + endloop + endfacet + facet normal 0.116413 0.0447393 0.992193 + outer loop + vertex 1.02768 1.55624 2.62621 + vertex 1.02613 1.562 2.62613 + vertex 1.02273 1.55719 2.62675 + endloop + endfacet + facet normal 0.109106 0.0409147 0.993188 + outer loop + vertex 1.02791 1.54728 2.62652 + vertex 1.02688 1.55133 2.62647 + vertex 1.02323 1.54742 2.62703 + endloop + endfacet + facet normal 0.087077 0.0353431 0.995574 + outer loop + vertex 1.02791 1.54728 2.62652 + vertex 1.03123 1.55215 2.62606 + vertex 1.02688 1.55133 2.62647 + endloop + endfacet + facet normal 0.108839 0.030641 0.993587 + outer loop + vertex 1.02343 1.54254 2.62716 + vertex 1.02791 1.54728 2.62652 + vertex 1.02323 1.54742 2.62703 + endloop + endfacet + facet normal 0.105291 0.0340275 0.993859 + outer loop + vertex 1.02827 1.54237 2.62665 + vertex 1.02791 1.54728 2.62652 + vertex 1.02343 1.54254 2.62716 + endloop + endfacet + facet normal 0.0786254 0.0321229 0.996387 + outer loop + vertex 1.02827 1.54237 2.62665 + vertex 1.03292 1.54655 2.62615 + vertex 1.02791 1.54728 2.62652 + endloop + endfacet + facet normal 0.0800322 0.0305505 0.996324 + outer loop + vertex 1.0321 1.54164 2.62636 + vertex 1.03292 1.54655 2.62615 + vertex 1.02827 1.54237 2.62665 + endloop + endfacet + facet normal 0.079781 0.0292142 0.996384 + outer loop + vertex 1.02833 1.53755 2.62679 + vertex 1.0321 1.54164 2.62636 + vertex 1.02827 1.54237 2.62665 + endloop + endfacet + facet normal 0.0740725 0.0345204 0.996655 + outer loop + vertex 1.03306 1.53775 2.62643 + vertex 1.0321 1.54164 2.62636 + vertex 1.02833 1.53755 2.62679 + endloop + endfacet + facet normal 0.0744456 0.0260101 0.996886 + outer loop + vertex 1.02849 1.53273 2.6269 + vertex 1.03306 1.53775 2.62643 + vertex 1.02833 1.53755 2.62679 + endloop + endfacet + facet normal 0.0699209 0.0301442 0.997097 + outer loop + vertex 1.03352 1.5329 2.62654 + vertex 1.03306 1.53775 2.62643 + vertex 1.02849 1.53273 2.6269 + endloop + endfacet + facet normal 0.0702186 0.0218424 0.997292 + outer loop + vertex 1.0285 1.52769 2.62701 + vertex 1.03352 1.5329 2.62654 + vertex 1.02849 1.53273 2.6269 + endloop + endfacet + facet normal 0.09414 0.0218562 0.995319 + outer loop + vertex 1.0285 1.52769 2.62701 + vertex 1.02849 1.53273 2.6269 + vertex 1.0233 1.52742 2.62751 + endloop + endfacet + facet normal 0.0674741 0.0245002 0.99742 + outer loop + vertex 1.03365 1.52787 2.62666 + vertex 1.03352 1.5329 2.62654 + vertex 1.0285 1.52769 2.62701 + endloop + endfacet + facet normal 0.0677641 0.0165062 0.997565 + outer loop + vertex 1.02842 1.52259 2.6271 + vertex 1.03365 1.52787 2.62666 + vertex 1.0285 1.52769 2.62701 + endloop + endfacet + facet normal 0.0925551 0.0160614 0.995578 + outer loop + vertex 1.02842 1.52259 2.6271 + vertex 1.0285 1.52769 2.62701 + vertex 1.0232 1.52234 2.62759 + endloop + endfacet + facet normal 0.0658389 0.0184237 0.99766 + outer loop + vertex 1.03364 1.52281 2.62675 + vertex 1.03365 1.52787 2.62666 + vertex 1.02842 1.52259 2.6271 + endloop + endfacet + facet normal 0.0661559 0.0107626 0.997751 + outer loop + vertex 1.02832 1.5175 2.62716 + vertex 1.03364 1.52281 2.62675 + vertex 1.02842 1.52259 2.6271 + endloop + endfacet + facet normal 0.0914098 0.0102481 0.995761 + outer loop + vertex 1.02832 1.5175 2.62716 + vertex 1.02842 1.52259 2.6271 + vertex 1.02312 1.51729 2.62764 + endloop + endfacet + facet normal 0.0653113 0.0116137 0.997797 + outer loop + vertex 1.03358 1.51771 2.62681 + vertex 1.03364 1.52281 2.62675 + vertex 1.02832 1.5175 2.62716 + endloop + endfacet + facet normal 0.0655889 0.00479654 0.997835 + outer loop + vertex 1.02824 1.51243 2.62719 + vertex 1.03358 1.51771 2.62681 + vertex 1.02832 1.5175 2.62716 + endloop + endfacet + facet normal 0.0913217 0.00438134 0.995812 + outer loop + vertex 1.02824 1.51243 2.62719 + vertex 1.02832 1.5175 2.62716 + vertex 1.02307 1.51227 2.62767 + endloop + endfacet + facet normal 0.0661992 0.00417609 0.997798 + outer loop + vertex 1.03348 1.51262 2.62684 + vertex 1.03358 1.51771 2.62681 + vertex 1.02824 1.51243 2.62719 + endloop + endfacet + facet normal 0.0663919 -0.00120389 0.997793 + outer loop + vertex 1.02819 1.50741 2.62719 + vertex 1.03348 1.51262 2.62684 + vertex 1.02824 1.51243 2.62719 + endloop + endfacet + facet normal 0.0924191 -0.00147068 0.995719 + outer loop + vertex 1.02819 1.50741 2.62719 + vertex 1.02824 1.51243 2.62719 + vertex 1.02306 1.50728 2.62766 + endloop + endfacet + facet normal 0.0670223 -0.00184708 0.99775 + outer loop + vertex 1.03339 1.50758 2.62684 + vertex 1.03348 1.51262 2.62684 + vertex 1.02819 1.50741 2.62719 + endloop + endfacet + facet normal 0.067151 -0.00589246 0.997725 + outer loop + vertex 1.02817 1.50241 2.62716 + vertex 1.03339 1.50758 2.62684 + vertex 1.02819 1.50741 2.62719 + endloop + endfacet + facet normal 0.067786 -0.00653858 0.997678 + outer loop + vertex 1.03334 1.50257 2.62681 + vertex 1.03339 1.50758 2.62684 + vertex 1.02817 1.50241 2.62716 + endloop + endfacet + facet normal 0.0493281 -0.00635632 0.998762 + outer loop + vertex 1.03334 1.50257 2.62681 + vertex 1.03858 1.50775 2.62658 + vertex 1.03339 1.50758 2.62684 + endloop + endfacet + facet normal 0.0491746 -0.00170767 0.998789 + outer loop + vertex 1.03858 1.50775 2.62658 + vertex 1.03867 1.51278 2.62659 + vertex 1.03339 1.50758 2.62684 + endloop + endfacet + facet normal 0.0411804 -0.00156871 0.99915 + outer loop + vertex 1.03858 1.50775 2.62658 + vertex 1.04368 1.51287 2.62638 + vertex 1.03867 1.51278 2.62659 + endloop + endfacet + facet normal 0.0410889 0.00396651 0.999148 + outer loop + vertex 1.04368 1.51287 2.62638 + vertex 1.04364 1.51788 2.62636 + vertex 1.03867 1.51278 2.62659 + endloop + endfacet + facet normal 0.0405221 0.00452063 0.999168 + outer loop + vertex 1.03867 1.51278 2.62659 + vertex 1.04364 1.51788 2.62636 + vertex 1.03873 1.51784 2.62656 + endloop + endfacet + facet normal 0.0488121 0.00442205 0.998798 + outer loop + vertex 1.03867 1.51278 2.62659 + vertex 1.03873 1.51784 2.62656 + vertex 1.03348 1.51262 2.62684 + endloop + endfacet + facet normal 0.0487241 0.00451069 0.998802 + outer loop + vertex 1.03348 1.51262 2.62684 + vertex 1.03873 1.51784 2.62656 + vertex 1.03358 1.51771 2.62681 + endloop + endfacet + facet normal 0.0485428 0.0115835 0.998754 + outer loop + vertex 1.03873 1.51784 2.62656 + vertex 1.03869 1.52286 2.62651 + vertex 1.03358 1.51771 2.62681 + endloop + endfacet + facet normal 0.0394313 0.0115141 0.999156 + outer loop + vertex 1.03873 1.51784 2.62656 + vertex 1.04338 1.52273 2.62632 + vertex 1.03869 1.52286 2.62651 + endloop + endfacet + facet normal 0.0396109 0.0181145 0.999051 + outer loop + vertex 1.04338 1.52273 2.62632 + vertex 1.04302 1.52745 2.62625 + vertex 1.03869 1.52286 2.62651 + endloop + endfacet + facet normal 0.0389577 0.0187317 0.999065 + outer loop + vertex 1.03869 1.52286 2.62651 + vertex 1.04302 1.52745 2.62625 + vertex 1.03851 1.52774 2.62642 + endloop + endfacet + facet normal 0.048199 0.019068 0.998656 + outer loop + vertex 1.03869 1.52286 2.62651 + vertex 1.03851 1.52774 2.62642 + vertex 1.03364 1.52281 2.62675 + endloop + endfacet + facet normal 0.0393346 0.0246781 0.998921 + outer loop + vertex 1.04302 1.52745 2.62625 + vertex 1.04219 1.53146 2.62619 + vertex 1.03851 1.52774 2.62642 + endloop + endfacet + facet normal 0.0391782 0.0248332 0.998924 + outer loop + vertex 1.03851 1.52774 2.62642 + vertex 1.04219 1.53146 2.62619 + vertex 1.03833 1.53257 2.62631 + endloop + endfacet + facet normal 0.0489666 0.0251839 0.998483 + outer loop + vertex 1.03851 1.52774 2.62642 + vertex 1.03833 1.53257 2.62631 + vertex 1.03365 1.52787 2.62666 + endloop + endfacet + facet normal 0.0402418 0.0285563 0.998782 + outer loop + vertex 1.04219 1.53146 2.62619 + vertex 1.04284 1.53618 2.62602 + vertex 1.03833 1.53257 2.62631 + endloop + endfacet + facet normal 0.0396762 0.0292632 0.998784 + outer loop + vertex 1.03833 1.53257 2.62631 + vertex 1.04284 1.53618 2.62602 + vertex 1.0378 1.53752 2.62619 + endloop + endfacet + facet normal 0.0505197 0.030414 0.99826 + outer loop + vertex 1.03833 1.53257 2.62631 + vertex 1.0378 1.53752 2.62619 + vertex 1.03352 1.5329 2.62654 + endloop + endfacet + facet normal 0.0407212 0.0332187 0.998618 + outer loop + vertex 1.04284 1.53618 2.62602 + vertex 1.04119 1.54124 2.62592 + vertex 1.0378 1.53752 2.62619 + endloop + endfacet + facet normal 0.0419464 0.0320976 0.998604 + outer loop + vertex 1.0378 1.53752 2.62619 + vertex 1.04119 1.54124 2.62592 + vertex 1.03656 1.54274 2.62607 + endloop + endfacet + facet normal 0.0528669 0.0346695 0.998 + outer loop + vertex 1.0378 1.53752 2.62619 + vertex 1.03656 1.54274 2.62607 + vertex 1.03306 1.53775 2.62643 + endloop + endfacet + facet normal 0.0429422 0.0351755 0.998458 + outer loop + vertex 1.04119 1.54124 2.62592 + vertex 1.04046 1.54558 2.6258 + vertex 1.03656 1.54274 2.62607 + endloop + endfacet + facet normal 0.0422587 0.0361138 0.998454 + outer loop + vertex 1.03715 1.54723 2.62588 + vertex 1.03656 1.54274 2.62607 + vertex 1.04046 1.54558 2.6258 + endloop + endfacet + facet normal 0.0395066 0.0247134 0.998914 + outer loop + vertex 1.04302 1.52745 2.62625 + vertex 1.04689 1.53172 2.62599 + vertex 1.04219 1.53146 2.62619 + endloop + endfacet + facet normal 0.0398001 0.0244468 0.998909 + outer loop + vertex 1.04666 1.5266 2.62613 + vertex 1.04689 1.53172 2.62599 + vertex 1.04302 1.52745 2.62625 + endloop + endfacet + facet normal 0.0382997 0.0180152 0.999104 + outer loop + vertex 1.04338 1.52273 2.62632 + vertex 1.04666 1.5266 2.62613 + vertex 1.04302 1.52745 2.62625 + endloop + endfacet + facet normal 0.041105 0.0156303 0.999033 + outer loop + vertex 1.04773 1.52256 2.62615 + vertex 1.04666 1.5266 2.62613 + vertex 1.04338 1.52273 2.62632 + endloop + endfacet + facet normal 0.0409007 0.0105413 0.999108 + outer loop + vertex 1.04364 1.51788 2.62636 + vertex 1.04773 1.52256 2.62615 + vertex 1.04338 1.52273 2.62632 + endloop + endfacet + facet normal 0.0419347 0.00963648 0.999074 + outer loop + vertex 1.04821 1.51766 2.62617 + vertex 1.04773 1.52256 2.62615 + vertex 1.04364 1.51788 2.62636 + endloop + endfacet + facet normal 0.0482697 0.0102595 0.998782 + outer loop + vertex 1.04821 1.51766 2.62617 + vertex 1.05185 1.52192 2.62595 + vertex 1.04773 1.52256 2.62615 + endloop + endfacet + facet normal 0.049228 0.016506 0.998651 + outer loop + vertex 1.05185 1.52192 2.62595 + vertex 1.05067 1.52724 2.62592 + vertex 1.04773 1.52256 2.62615 + endloop + endfacet + facet normal 0.04781 0.0174 0.998705 + outer loop + vertex 1.04773 1.52256 2.62615 + vertex 1.05067 1.52724 2.62592 + vertex 1.04666 1.5266 2.62613 + endloop + endfacet + facet normal 0.0404771 0.0105187 0.999125 + outer loop + vertex 1.04364 1.51788 2.62636 + vertex 1.04338 1.52273 2.62632 + vertex 1.03873 1.51784 2.62656 + endloop + endfacet + facet normal 0.0416722 0.00397075 0.999123 + outer loop + vertex 1.04368 1.51287 2.62638 + vertex 1.04821 1.51766 2.62617 + vertex 1.04364 1.51788 2.62636 + endloop + endfacet + facet normal 0.041642 0.00399931 0.999125 + outer loop + vertex 1.04835 1.51269 2.62619 + vertex 1.04821 1.51766 2.62617 + vertex 1.04368 1.51287 2.62638 + endloop + endfacet + facet normal 0.0414481 -0.00104926 0.99914 + outer loop + vertex 1.04364 1.50786 2.62638 + vertex 1.04835 1.51269 2.62619 + vertex 1.04368 1.51287 2.62638 + endloop + endfacet + facet normal 0.0411177 -0.000726468 0.999154 + outer loop + vertex 1.04837 1.5077 2.62618 + vertex 1.04835 1.51269 2.62619 + vertex 1.04364 1.50786 2.62638 + endloop + endfacet + facet normal 0.0409645 -0.00513011 0.999147 + outer loop + vertex 1.04361 1.50285 2.62635 + vertex 1.04837 1.5077 2.62618 + vertex 1.04364 1.50786 2.62638 + endloop + endfacet + facet normal 0.0402104 -0.0051251 0.999178 + outer loop + vertex 1.04361 1.50285 2.62635 + vertex 1.04364 1.50786 2.62638 + vertex 1.03853 1.50274 2.62656 + endloop + endfacet + facet normal 0.0402878 -0.00890973 0.999148 + outer loop + vertex 1.03852 1.49774 2.62651 + vertex 1.04361 1.50285 2.62635 + vertex 1.03853 1.50274 2.62656 + endloop + endfacet + facet normal 0.0489319 -0.00892755 0.998762 + outer loop + vertex 1.03852 1.49774 2.62651 + vertex 1.03853 1.50274 2.62656 + vertex 1.03333 1.49759 2.62677 + endloop + endfacet + facet normal 0.0490261 -0.0121025 0.998724 + outer loop + vertex 1.03334 1.49259 2.62671 + vertex 1.03852 1.49774 2.62651 + vertex 1.03333 1.49759 2.62677 + endloop + endfacet + facet normal 0.0683957 -0.0120488 0.997586 + outer loop + vertex 1.03334 1.49259 2.62671 + vertex 1.03333 1.49759 2.62677 + vertex 1.02819 1.49246 2.62706 + endloop + endfacet + facet normal 0.0488637 -0.0119391 0.998734 + outer loop + vertex 1.03852 1.49272 2.62645 + vertex 1.03852 1.49774 2.62651 + vertex 1.03334 1.49259 2.62671 + endloop + endfacet + facet normal 0.0489476 -0.015292 0.998684 + outer loop + vertex 1.03336 1.48758 2.62663 + vertex 1.03852 1.49272 2.62645 + vertex 1.03334 1.49259 2.62671 + endloop + endfacet + facet normal 0.0690794 -0.015196 0.997495 + outer loop + vertex 1.03336 1.48758 2.62663 + vertex 1.03334 1.49259 2.62671 + vertex 1.0282 1.48746 2.62698 + endloop + endfacet + facet normal 0.0497899 -0.0161381 0.998629 + outer loop + vertex 1.03854 1.48771 2.62637 + vertex 1.03852 1.49272 2.62645 + vertex 1.03336 1.48758 2.62663 + endloop + endfacet + facet normal 0.0498805 -0.0198423 0.998558 + outer loop + vertex 1.0334 1.48257 2.62653 + vertex 1.03854 1.48771 2.62637 + vertex 1.03336 1.48758 2.62663 + endloop + endfacet + facet normal 0.0705025 -0.0196503 0.997318 + outer loop + vertex 1.0334 1.48257 2.62653 + vertex 1.03336 1.48758 2.62663 + vertex 1.02821 1.48245 2.62689 + endloop + endfacet + facet normal 0.0705867 -0.0236738 0.997225 + outer loop + vertex 1.02825 1.47744 2.62677 + vertex 1.0334 1.48257 2.62653 + vertex 1.02821 1.48245 2.62689 + endloop + endfacet + facet normal 0.0717034 -0.0248025 0.997118 + outer loop + vertex 1.03347 1.4776 2.6264 + vertex 1.0334 1.48257 2.62653 + vertex 1.02825 1.47744 2.62677 + endloop + endfacet + facet normal 0.0717914 -0.0278904 0.99703 + outer loop + vertex 1.02831 1.47249 2.62663 + vertex 1.03347 1.4776 2.6264 + vertex 1.02825 1.47744 2.62677 + endloop + endfacet + facet normal 0.10426 -0.0273927 0.994173 + outer loop + vertex 1.02831 1.47249 2.62663 + vertex 1.02825 1.47744 2.62677 + vertex 1.02314 1.47237 2.62716 + endloop + endfacet + facet normal 0.0734828 -0.029605 0.996857 + outer loop + vertex 1.03351 1.47271 2.62625 + vertex 1.03347 1.4776 2.6264 + vertex 1.02831 1.47249 2.62663 + endloop + endfacet + facet normal 0.0735723 -0.0319246 0.996779 + outer loop + vertex 1.02835 1.46763 2.62647 + vertex 1.03351 1.47271 2.62625 + vertex 1.02831 1.47249 2.62663 + endloop + endfacet + facet normal 0.075832 -0.034234 0.996533 + outer loop + vertex 1.03331 1.46791 2.6261 + vertex 1.03351 1.47271 2.62625 + vertex 1.02835 1.46763 2.62647 + endloop + endfacet + facet normal 0.0535031 -0.033317 0.998012 + outer loop + vertex 1.03331 1.46791 2.6261 + vertex 1.0387 1.47279 2.62597 + vertex 1.03351 1.47271 2.62625 + endloop + endfacet + facet normal 0.053469 -0.0308893 0.998092 + outer loop + vertex 1.0387 1.47279 2.62597 + vertex 1.03865 1.47782 2.62613 + vertex 1.03351 1.47271 2.62625 + endloop + endfacet + facet normal 0.0430482 -0.0310117 0.998592 + outer loop + vertex 1.04369 1.4782 2.62593 + vertex 1.03865 1.47782 2.62613 + vertex 1.0387 1.47279 2.62597 + endloop + endfacet + facet normal 0.0435115 -0.0314385 0.998558 + outer loop + vertex 1.04294 1.47433 2.62584 + vertex 1.04369 1.4782 2.62593 + vertex 1.0387 1.47279 2.62597 + endloop + endfacet + facet normal 0.0449853 -0.0355155 0.998356 + outer loop + vertex 1.04294 1.47433 2.62584 + vertex 1.0387 1.47279 2.62597 + vertex 1.04121 1.47062 2.62578 + endloop + endfacet + facet normal 0.0460693 -0.0360189 0.998289 + outer loop + vertex 1.04522 1.47342 2.6257 + vertex 1.04294 1.47433 2.62584 + vertex 1.04121 1.47062 2.62578 + endloop + endfacet + facet normal 0.0465309 -0.0366821 0.998243 + outer loop + vertex 1.04357 1.46825 2.62559 + vertex 1.04522 1.47342 2.6257 + vertex 1.04121 1.47062 2.62578 + endloop + endfacet + facet normal 0.0467349 -0.0364792 0.998241 + outer loop + vertex 1.03956 1.46699 2.62573 + vertex 1.04357 1.46825 2.62559 + vertex 1.04121 1.47062 2.62578 + endloop + endfacet + facet normal 0.0473936 -0.0367777 0.998199 + outer loop + vertex 1.04121 1.47062 2.62578 + vertex 1.03721 1.46782 2.62587 + vertex 1.03956 1.46699 2.62573 + endloop + endfacet + facet normal 0.047231 -0.0372328 0.99819 + outer loop + vertex 1.03956 1.46699 2.62573 + vertex 1.03721 1.46782 2.62587 + vertex 1.0369 1.46478 2.62577 + endloop + endfacet + facet normal 0.0472327 -0.0372348 0.99819 + outer loop + vertex 1.03956 1.46699 2.62573 + vertex 1.0369 1.46478 2.62577 + vertex 1.0389 1.46316 2.62562 + endloop + endfacet + facet normal 0.0477045 -0.0366516 0.998189 + outer loop + vertex 1.0389 1.46316 2.62562 + vertex 1.0369 1.46478 2.62577 + vertex 1.03539 1.46206 2.62574 + endloop + endfacet + facet normal 0.0478706 -0.0371836 0.998161 + outer loop + vertex 1.03539 1.46206 2.62574 + vertex 1.03508 1.45878 2.62564 + vertex 1.0389 1.46316 2.62562 + endloop + endfacet + facet normal 0.0499323 -0.0389823 0.997992 + outer loop + vertex 1.0389 1.46316 2.62562 + vertex 1.03508 1.45878 2.62564 + vertex 1.03869 1.45811 2.62543 + endloop + endfacet + facet normal 0.0588542 -0.0382062 0.997535 + outer loop + vertex 1.03539 1.46206 2.62574 + vertex 1.03272 1.45968 2.62581 + vertex 1.03508 1.45878 2.62564 + endloop + endfacet + facet normal 0.0593573 -0.036889 0.997555 + outer loop + vertex 1.03508 1.45878 2.62564 + vertex 1.03272 1.45968 2.62581 + vertex 1.03121 1.45582 2.62576 + endloop + endfacet + facet normal 0.0625874 -0.0411288 0.997192 + outer loop + vertex 1.0338 1.45353 2.6255 + vertex 1.03508 1.45878 2.62564 + vertex 1.03121 1.45582 2.62576 + endloop + endfacet + facet normal 0.0636709 -0.039904 0.997173 + outer loop + vertex 1.02994 1.45209 2.62569 + vertex 1.0338 1.45353 2.6255 + vertex 1.03121 1.45582 2.62576 + endloop + endfacet + facet normal 0.0955498 -0.0507485 0.99413 + outer loop + vertex 1.03121 1.45582 2.62576 + vertex 1.02728 1.45261 2.62597 + vertex 1.02994 1.45209 2.62569 + endloop + endfacet + facet normal 0.0964377 -0.0463326 0.99426 + outer loop + vertex 1.02994 1.45209 2.62569 + vertex 1.02728 1.45261 2.62597 + vertex 1.02741 1.44937 2.62581 + endloop + endfacet + facet normal 0.0877909 -0.0382336 0.995405 + outer loop + vertex 1.02994 1.45209 2.62569 + vertex 1.02741 1.44937 2.62581 + vertex 1.0301 1.44884 2.62555 + endloop + endfacet + facet normal 0.134452 -0.0446326 0.989914 + outer loop + vertex 1.02741 1.44937 2.62581 + vertex 1.02728 1.45261 2.62597 + vertex 1.02332 1.44752 2.62628 + endloop + endfacet + facet normal 0.134906 -0.0456603 0.989806 + outer loop + vertex 1.02741 1.44937 2.62581 + vertex 1.02332 1.44752 2.62628 + vertex 1.02639 1.44551 2.62577 + endloop + endfacet + facet normal 0.0894062 -0.0431722 0.995059 + outer loop + vertex 1.02852 1.45786 2.62609 + vertex 1.02728 1.45261 2.62597 + vertex 1.03121 1.45582 2.62576 + endloop + endfacet + facet normal 0.13084 -0.0528034 0.989996 + outer loop + vertex 1.02728 1.45261 2.62597 + vertex 1.02852 1.45786 2.62609 + vertex 1.02319 1.45264 2.62651 + endloop + endfacet + facet normal 0.086251 -0.0473587 0.995147 + outer loop + vertex 1.03272 1.45968 2.62581 + vertex 1.02852 1.45786 2.62609 + vertex 1.03121 1.45582 2.62576 + endloop + endfacet + facet normal 0.08503 -0.0444972 0.995384 + outer loop + vertex 1.03272 1.45968 2.62581 + vertex 1.03327 1.46338 2.62593 + vertex 1.02852 1.45786 2.62609 + endloop + endfacet + facet normal 0.0798139 -0.0399928 0.996007 + outer loop + vertex 1.03327 1.46338 2.62593 + vertex 1.02838 1.46285 2.6263 + vertex 1.02852 1.45786 2.62609 + endloop + endfacet + facet normal 0.0796398 -0.0383419 0.996086 + outer loop + vertex 1.03327 1.46338 2.62593 + vertex 1.03331 1.46791 2.6261 + vertex 1.02838 1.46285 2.6263 + endloop + endfacet + facet normal 0.0578354 -0.038205 0.997595 + outer loop + vertex 1.03721 1.46782 2.62587 + vertex 1.03331 1.46791 2.6261 + vertex 1.03327 1.46338 2.62593 + endloop + endfacet + facet normal 0.0613908 -0.0410562 0.997269 + outer loop + vertex 1.03539 1.46206 2.62574 + vertex 1.03327 1.46338 2.62593 + vertex 1.03272 1.45968 2.62581 + endloop + endfacet + facet normal 0.0599233 -0.0434103 0.997259 + outer loop + vertex 1.0369 1.46478 2.62577 + vertex 1.03327 1.46338 2.62593 + vertex 1.03539 1.46206 2.62574 + endloop + endfacet + facet normal 0.0579767 -0.0383306 0.997582 + outer loop + vertex 1.0369 1.46478 2.62577 + vertex 1.03721 1.46782 2.62587 + vertex 1.03327 1.46338 2.62593 + endloop + endfacet + facet normal 0.0469565 -0.0371874 0.998204 + outer loop + vertex 1.03956 1.46699 2.62573 + vertex 1.0389 1.46316 2.62562 + vertex 1.04357 1.46825 2.62559 + endloop + endfacet + facet normal 0.04813 -0.0382658 0.998108 + outer loop + vertex 1.04357 1.46825 2.62559 + vertex 1.0389 1.46316 2.62562 + vertex 1.04339 1.46289 2.62539 + endloop + endfacet + facet normal 0.0516809 -0.0383205 0.997928 + outer loop + vertex 1.04357 1.46825 2.62559 + vertex 1.04878 1.47292 2.6255 + vertex 1.04522 1.47342 2.6257 + endloop + endfacet + facet normal 0.0518881 -0.03686 0.997972 + outer loop + vertex 1.04922 1.47784 2.62565 + vertex 1.04522 1.47342 2.6257 + vertex 1.04878 1.47292 2.6255 + endloop + endfacet + facet normal 0.0533703 -0.0369898 0.997889 + outer loop + vertex 1.04878 1.47292 2.6255 + vertex 1.0535 1.47776 2.62542 + vertex 1.04922 1.47784 2.62565 + endloop + endfacet + facet normal 0.0534432 -0.0334752 0.99801 + outer loop + vertex 1.05365 1.48292 2.62559 + vertex 1.04922 1.47784 2.62565 + vertex 1.0535 1.47776 2.62542 + endloop + endfacet + facet normal 0.0560807 -0.0357805 0.997785 + outer loop + vertex 1.05015 1.48171 2.62574 + vertex 1.04922 1.47784 2.62565 + vertex 1.05365 1.48292 2.62559 + endloop + endfacet + facet normal 0.0542375 -0.0304319 0.998064 + outer loop + vertex 1.05365 1.48292 2.62559 + vertex 1.05176 1.48466 2.62574 + vertex 1.05015 1.48171 2.62574 + endloop + endfacet + facet normal 0.0475184 -0.0267723 0.998512 + outer loop + vertex 1.05176 1.48466 2.62574 + vertex 1.04823 1.48332 2.62588 + vertex 1.05015 1.48171 2.62574 + endloop + endfacet + facet normal 0.0466662 -0.0277889 0.998524 + outer loop + vertex 1.05015 1.48171 2.62574 + vertex 1.04823 1.48332 2.62588 + vertex 1.04747 1.47956 2.62581 + endloop + endfacet + facet normal 0.0413488 -0.0267313 0.998787 + outer loop + vertex 1.04747 1.47956 2.62581 + vertex 1.04823 1.48332 2.62588 + vertex 1.04369 1.4782 2.62593 + endloop + endfacet + facet normal 0.0426925 -0.030509 0.998622 + outer loop + vertex 1.04747 1.47956 2.62581 + vertex 1.04369 1.4782 2.62593 + vertex 1.04573 1.47665 2.62579 + endloop + endfacet + facet normal 0.0514794 -0.0357733 0.998033 + outer loop + vertex 1.04922 1.47784 2.62565 + vertex 1.04747 1.47956 2.62581 + vertex 1.04573 1.47665 2.62579 + endloop + endfacet + facet normal 0.0414118 -0.0267873 0.998783 + outer loop + vertex 1.04823 1.48332 2.62588 + vertex 1.04358 1.48299 2.62606 + vertex 1.04369 1.4782 2.62593 + endloop + endfacet + facet normal 0.0410942 -0.0223075 0.998906 + outer loop + vertex 1.04823 1.48332 2.62588 + vertex 1.04812 1.4879 2.62598 + vertex 1.04358 1.48299 2.62606 + endloop + endfacet + facet normal 0.0407744 -0.0220121 0.998926 + outer loop + vertex 1.04358 1.48299 2.62606 + vertex 1.04812 1.4879 2.62598 + vertex 1.04356 1.48784 2.62617 + endloop + endfacet + facet normal 0.0419868 -0.022005 0.998876 + outer loop + vertex 1.04358 1.48299 2.62606 + vertex 1.04356 1.48784 2.62617 + vertex 1.03859 1.48274 2.62626 + endloop + endfacet + facet normal 0.0421938 -0.0262433 0.998765 + outer loop + vertex 1.03865 1.47782 2.62613 + vertex 1.04358 1.48299 2.62606 + vertex 1.03859 1.48274 2.62626 + endloop + endfacet + facet normal 0.0522605 -0.0261006 0.998292 + outer loop + vertex 1.03865 1.47782 2.62613 + vertex 1.03859 1.48274 2.62626 + vertex 1.03347 1.4776 2.6264 + endloop + endfacet + facet normal 0.0512688 -0.0251107 0.998369 + outer loop + vertex 1.03347 1.4776 2.6264 + vertex 1.03859 1.48274 2.62626 + vertex 1.0334 1.48257 2.62653 + endloop + endfacet + facet normal 0.0411643 -0.0212029 0.998927 + outer loop + vertex 1.03859 1.48274 2.62626 + vertex 1.04356 1.48784 2.62617 + vertex 1.03854 1.48771 2.62637 + endloop + endfacet + facet normal 0.0410508 -0.0168856 0.999014 + outer loop + vertex 1.04356 1.48784 2.62617 + vertex 1.04358 1.49281 2.62625 + vertex 1.03854 1.48771 2.62637 + endloop + endfacet + facet normal 0.040499 -0.0168835 0.999037 + outer loop + vertex 1.04356 1.48784 2.62617 + vertex 1.04822 1.49269 2.62606 + vertex 1.04358 1.49281 2.62625 + endloop + endfacet + facet normal 0.0406096 -0.0126318 0.999095 + outer loop + vertex 1.04822 1.49269 2.62606 + vertex 1.04832 1.49766 2.62612 + vertex 1.04358 1.49281 2.62625 + endloop + endfacet + facet normal 0.0402309 -0.0122614 0.999115 + outer loop + vertex 1.04358 1.49281 2.62625 + vertex 1.04832 1.49766 2.62612 + vertex 1.0436 1.49783 2.62631 + endloop + endfacet + facet normal 0.0402767 -0.0122615 0.999113 + outer loop + vertex 1.04358 1.49281 2.62625 + vertex 1.0436 1.49783 2.62631 + vertex 1.03852 1.49272 2.62645 + endloop + endfacet + facet normal 0.0403727 -0.00839523 0.999149 + outer loop + vertex 1.04832 1.49766 2.62612 + vertex 1.04835 1.50268 2.62616 + vertex 1.0436 1.49783 2.62631 + endloop + endfacet + facet normal 0.0405171 -0.00853709 0.999142 + outer loop + vertex 1.0436 1.49783 2.62631 + vertex 1.04835 1.50268 2.62616 + vertex 1.04361 1.50285 2.62635 + endloop + endfacet + facet normal 0.0461484 -0.00843325 0.998899 + outer loop + vertex 1.04832 1.49766 2.62612 + vertex 1.05253 1.502 2.62596 + vertex 1.04835 1.50268 2.62616 + endloop + endfacet + facet normal 0.0467154 -0.00490544 0.998896 + outer loop + vertex 1.05253 1.502 2.62596 + vertex 1.05255 1.50701 2.62598 + vertex 1.04835 1.50268 2.62616 + endloop + endfacet + facet normal 0.04665 -0.00484192 0.9989 + outer loop + vertex 1.04835 1.50268 2.62616 + vertex 1.05255 1.50701 2.62598 + vertex 1.04837 1.5077 2.62618 + endloop + endfacet + facet normal 0.045784 -0.0127294 0.99887 + outer loop + vertex 1.04822 1.49269 2.62606 + vertex 1.05243 1.49702 2.62592 + vertex 1.04832 1.49766 2.62612 + endloop + endfacet + facet normal 0.0458474 -0.012791 0.998867 + outer loop + vertex 1.05219 1.49219 2.62587 + vertex 1.05243 1.49702 2.62592 + vertex 1.04822 1.49269 2.62606 + endloop + endfacet + facet normal 0.0452973 -0.0171878 0.998826 + outer loop + vertex 1.04812 1.4879 2.62598 + vertex 1.05219 1.49219 2.62587 + vertex 1.04822 1.49269 2.62606 + endloop + endfacet + facet normal 0.0407162 -0.0170927 0.999025 + outer loop + vertex 1.04812 1.4879 2.62598 + vertex 1.04822 1.49269 2.62606 + vertex 1.04356 1.48784 2.62617 + endloop + endfacet + facet normal 0.045347 -0.0222008 0.998725 + outer loop + vertex 1.05183 1.48781 2.62581 + vertex 1.04812 1.4879 2.62598 + vertex 1.04823 1.48332 2.62588 + endloop + endfacet + facet normal 0.0459955 -0.0227222 0.998683 + outer loop + vertex 1.05176 1.48466 2.62574 + vertex 1.05183 1.48781 2.62581 + vertex 1.04823 1.48332 2.62588 + endloop + endfacet + facet normal 0.0523495 -0.034885 0.998019 + outer loop + vertex 1.05015 1.48171 2.62574 + vertex 1.04747 1.47956 2.62581 + vertex 1.04922 1.47784 2.62565 + endloop + endfacet + facet normal 0.0518838 -0.0355403 0.998021 + outer loop + vertex 1.05325 1.47265 2.62525 + vertex 1.0535 1.47776 2.62542 + vertex 1.04878 1.47292 2.6255 + endloop + endfacet + facet normal 0.0518315 -0.0368089 0.997977 + outer loop + vertex 1.04573 1.47665 2.62579 + vertex 1.04522 1.47342 2.6257 + vertex 1.04922 1.47784 2.62565 + endloop + endfacet + facet normal 0.0508061 -0.0373436 0.99801 + outer loop + vertex 1.0483 1.46777 2.62533 + vertex 1.04878 1.47292 2.6255 + vertex 1.04357 1.46825 2.62559 + endloop + endfacet + facet normal 0.0461107 -0.0359148 0.998291 + outer loop + vertex 1.04573 1.47665 2.62579 + vertex 1.04294 1.47433 2.62584 + vertex 1.04522 1.47342 2.6257 + endloop + endfacet + facet normal 0.0458291 -0.0345373 0.998352 + outer loop + vertex 1.0387 1.47279 2.62597 + vertex 1.03721 1.46782 2.62587 + vertex 1.04121 1.47062 2.62578 + endloop + endfacet + facet normal 0.0421818 -0.0311828 0.998623 + outer loop + vertex 1.04573 1.47665 2.62579 + vertex 1.04369 1.4782 2.62593 + vertex 1.04294 1.47433 2.62584 + endloop + endfacet + facet normal 0.0427314 -0.0267574 0.998728 + outer loop + vertex 1.04369 1.4782 2.62593 + vertex 1.04358 1.48299 2.62606 + vertex 1.03865 1.47782 2.62613 + endloop + endfacet + facet normal 0.0578375 -0.0381213 0.997598 + outer loop + vertex 1.03721 1.46782 2.62587 + vertex 1.0387 1.47279 2.62597 + vertex 1.03331 1.46791 2.6261 + endloop + endfacet + facet normal 0.0524122 -0.0298262 0.99818 + outer loop + vertex 1.03351 1.47271 2.62625 + vertex 1.03865 1.47782 2.62613 + vertex 1.03347 1.4776 2.6264 + endloop + endfacet + facet normal 0.0511414 -0.0211052 0.998468 + outer loop + vertex 1.03859 1.48274 2.62626 + vertex 1.03854 1.48771 2.62637 + vertex 1.0334 1.48257 2.62653 + endloop + endfacet + facet normal 0.0403389 -0.0161812 0.999055 + outer loop + vertex 1.03854 1.48771 2.62637 + vertex 1.04358 1.49281 2.62625 + vertex 1.03852 1.49272 2.62645 + endloop + endfacet + facet normal 0.0399694 -0.0119557 0.999129 + outer loop + vertex 1.03852 1.49272 2.62645 + vertex 1.0436 1.49783 2.62631 + vertex 1.03852 1.49774 2.62651 + endloop + endfacet + facet normal 0.0488352 -0.00882997 0.998768 + outer loop + vertex 1.03333 1.49759 2.62677 + vertex 1.03853 1.50274 2.62656 + vertex 1.03334 1.50257 2.62681 + endloop + endfacet + facet normal 0.0677035 -0.00885462 0.997666 + outer loop + vertex 1.03333 1.49759 2.62677 + vertex 1.03334 1.50257 2.62681 + vertex 1.02817 1.49744 2.62712 + endloop + endfacet + facet normal 0.0399133 -0.0085359 0.999167 + outer loop + vertex 1.0436 1.49783 2.62631 + vertex 1.04361 1.50285 2.62635 + vertex 1.03852 1.49774 2.62651 + endloop + endfacet + facet normal 0.0407551 -0.00567038 0.999153 + outer loop + vertex 1.03853 1.50274 2.62656 + vertex 1.04364 1.50786 2.62638 + vertex 1.03858 1.50775 2.62658 + endloop + endfacet + facet normal 0.0406537 -0.0048245 0.999162 + outer loop + vertex 1.04835 1.50268 2.62616 + vertex 1.04837 1.5077 2.62618 + vertex 1.04361 1.50285 2.62635 + endloop + endfacet + facet normal 0.0473685 -0.000706076 0.998877 + outer loop + vertex 1.04837 1.5077 2.62618 + vertex 1.05251 1.512 2.62599 + vertex 1.04835 1.51269 2.62619 + endloop + endfacet + facet normal 0.048154 0.00405989 0.998832 + outer loop + vertex 1.05251 1.512 2.62599 + vertex 1.05235 1.51695 2.62598 + vertex 1.04835 1.51269 2.62619 + endloop + endfacet + facet normal 0.0480277 0.00417869 0.998837 + outer loop + vertex 1.04835 1.51269 2.62619 + vertex 1.05235 1.51695 2.62598 + vertex 1.04821 1.51766 2.62617 + endloop + endfacet + facet normal 0.0406538 -0.00104377 0.999173 + outer loop + vertex 1.04364 1.50786 2.62638 + vertex 1.04368 1.51287 2.62638 + vertex 1.03858 1.50775 2.62658 + endloop + endfacet + facet normal 0.0487337 -0.00575346 0.998795 + outer loop + vertex 1.03853 1.50274 2.62656 + vertex 1.03858 1.50775 2.62658 + vertex 1.03334 1.50257 2.62681 + endloop + endfacet + facet normal 0.0489981 -0.00152849 0.998798 + outer loop + vertex 1.03339 1.50758 2.62684 + vertex 1.03867 1.51278 2.62659 + vertex 1.03348 1.51262 2.62684 + endloop + endfacet + facet normal 0.0482881 0.0118365 0.998763 + outer loop + vertex 1.03358 1.51771 2.62681 + vertex 1.03869 1.52286 2.62651 + vertex 1.03364 1.52281 2.62675 + endloop + endfacet + facet normal 0.0487919 0.0184828 0.998638 + outer loop + vertex 1.03364 1.52281 2.62675 + vertex 1.03851 1.52774 2.62642 + vertex 1.03365 1.52787 2.62666 + endloop + endfacet + facet normal 0.050091 0.0240624 0.998455 + outer loop + vertex 1.03365 1.52787 2.62666 + vertex 1.03833 1.53257 2.62631 + vertex 1.03352 1.5329 2.62654 + endloop + endfacet + facet normal 0.052579 0.0285046 0.99821 + outer loop + vertex 1.03352 1.5329 2.62654 + vertex 1.0378 1.53752 2.62619 + vertex 1.03306 1.53775 2.62643 + endloop + endfacet + facet normal 0.0584694 0.0307203 0.997816 + outer loop + vertex 1.03306 1.53775 2.62643 + vertex 1.03656 1.54274 2.62607 + vertex 1.0321 1.54164 2.62636 + endloop + endfacet + facet normal 0.0575683 0.0343387 0.997751 + outer loop + vertex 1.03292 1.54655 2.62615 + vertex 1.0321 1.54164 2.62636 + vertex 1.03656 1.54274 2.62607 + endloop + endfacet + facet normal 0.0975588 0.0267271 0.994871 + outer loop + vertex 1.02849 1.53273 2.6269 + vertex 1.02833 1.53755 2.62679 + vertex 1.02338 1.53248 2.62741 + endloop + endfacet + facet normal 0.097994 0.0180532 0.995023 + outer loop + vertex 1.0233 1.52742 2.62751 + vertex 1.02849 1.53273 2.6269 + vertex 1.02338 1.53248 2.62741 + endloop + endfacet + facet normal 0.0945582 0.0140598 0.99542 + outer loop + vertex 1.0232 1.52234 2.62759 + vertex 1.0285 1.52769 2.62701 + vertex 1.0233 1.52742 2.62751 + endloop + endfacet + facet normal 0.0929113 0.00873604 0.995636 + outer loop + vertex 1.02312 1.51729 2.62764 + vertex 1.02842 1.52259 2.6271 + vertex 1.0232 1.52234 2.62759 + endloop + endfacet + facet normal 0.091667 0.0040321 0.995782 + outer loop + vertex 1.02307 1.51227 2.62767 + vertex 1.02832 1.5175 2.62716 + vertex 1.02312 1.51729 2.62764 + endloop + endfacet + facet normal 0.0914802 -0.000519213 0.995807 + outer loop + vertex 1.02306 1.50728 2.62766 + vertex 1.02824 1.51243 2.62719 + vertex 1.02307 1.51227 2.62767 + endloop + endfacet + facet normal 0.0924994 -0.00477791 0.995701 + outer loop + vertex 1.02307 1.50231 2.62764 + vertex 1.02819 1.50741 2.62719 + vertex 1.02306 1.50728 2.62766 + endloop + endfacet + facet normal 0.0936942 -0.00598749 0.995583 + outer loop + vertex 1.02817 1.50241 2.62716 + vertex 1.02819 1.50741 2.62719 + vertex 1.02307 1.50231 2.62764 + endloop + endfacet + facet normal 0.067859 -0.00901207 0.997654 + outer loop + vertex 1.02817 1.49744 2.62712 + vertex 1.03334 1.50257 2.62681 + vertex 1.02817 1.50241 2.62716 + endloop + endfacet + facet normal 0.0677746 -0.0114221 0.997635 + outer loop + vertex 1.02819 1.49246 2.62706 + vertex 1.03333 1.49759 2.62677 + vertex 1.02817 1.49744 2.62712 + endloop + endfacet + facet normal 0.068457 -0.0145682 0.997548 + outer loop + vertex 1.0282 1.48746 2.62698 + vertex 1.03334 1.49259 2.62671 + vertex 1.02819 1.49246 2.62706 + endloop + endfacet + facet normal 0.069143 -0.0182777 0.997439 + outer loop + vertex 1.02821 1.48245 2.62689 + vertex 1.03336 1.48758 2.62663 + vertex 1.0282 1.48746 2.62698 + endloop + endfacet + facet normal 0.102902 -0.0233532 0.994417 + outer loop + vertex 1.02825 1.47744 2.62677 + vertex 1.02821 1.48245 2.62689 + vertex 1.02312 1.47738 2.6273 + endloop + endfacet + facet normal 0.102927 -0.0260367 0.994348 + outer loop + vertex 1.02314 1.47237 2.62716 + vertex 1.02825 1.47744 2.62677 + vertex 1.02312 1.47738 2.6273 + endloop + endfacet + facet normal 0.104281 -0.0284343 0.994141 + outer loop + vertex 1.0232 1.46742 2.62702 + vertex 1.02831 1.47249 2.62663 + vertex 1.02314 1.47237 2.62716 + endloop + endfacet + facet normal 0.107338 -0.031549 0.993722 + outer loop + vertex 1.02835 1.46763 2.62647 + vertex 1.02831 1.47249 2.62663 + vertex 1.0232 1.46742 2.62702 + endloop + endfacet + facet normal 0.0758536 -0.0346427 0.996517 + outer loop + vertex 1.02838 1.46285 2.6263 + vertex 1.03331 1.46791 2.6261 + vertex 1.02835 1.46763 2.62647 + endloop + endfacet + facet normal 0.115487 -0.0388612 0.992549 + outer loop + vertex 1.02852 1.45786 2.62609 + vertex 1.02838 1.46285 2.6263 + vertex 1.02331 1.45763 2.62668 + endloop + endfacet + facet normal 0.115406 -0.0368201 0.992636 + outer loop + vertex 1.02319 1.45264 2.62651 + vertex 1.02852 1.45786 2.62609 + vertex 1.02331 1.45763 2.62668 + endloop + endfacet + facet normal 0.130987 -0.0419009 0.990498 + outer loop + vertex 1.02728 1.45261 2.62597 + vertex 1.02319 1.45264 2.62651 + vertex 1.02332 1.44752 2.62628 + endloop + endfacet + facet normal 0.138085 -0.0407509 0.989582 + outer loop + vertex 1.02332 1.44752 2.62628 + vertex 1.02228 1.442 2.6262 + vertex 1.02639 1.44551 2.62577 + endloop + endfacet + facet normal 0.104602 -0.0497551 0.993269 + outer loop + vertex 1.02859 1.43859 2.62522 + vertex 1.02961 1.44418 2.6254 + vertex 1.02559 1.44086 2.62565 + endloop + endfacet + facet normal 0.08873 -0.0335386 0.995491 + outer loop + vertex 1.0301 1.44884 2.62555 + vertex 1.02741 1.44937 2.62581 + vertex 1.02639 1.44551 2.62577 + endloop + endfacet + facet normal 0.074538 -0.0471065 0.996105 + outer loop + vertex 1.03353 1.4431 2.62505 + vertex 1.03382 1.44829 2.62528 + vertex 1.02961 1.44418 2.6254 + endloop + endfacet + facet normal 0.0635448 -0.0395633 0.997194 + outer loop + vertex 1.02994 1.45209 2.62569 + vertex 1.0301 1.44884 2.62555 + vertex 1.0338 1.45353 2.6255 + endloop + endfacet + facet normal 0.0599011 -0.0475329 0.997072 + outer loop + vertex 1.03827 1.44769 2.62498 + vertex 1.03837 1.45287 2.62522 + vertex 1.03382 1.44829 2.62528 + endloop + endfacet + facet normal 0.0500936 -0.0381142 0.998017 + outer loop + vertex 1.0338 1.45353 2.6255 + vertex 1.03869 1.45811 2.62543 + vertex 1.03508 1.45878 2.62564 + endloop + endfacet + facet normal 0.0544677 -0.0466121 0.997427 + outer loop + vertex 1.04316 1.45254 2.62494 + vertex 1.04323 1.45768 2.62518 + vertex 1.03837 1.45287 2.62522 + endloop + endfacet + facet normal 0.0480897 -0.0389106 0.998085 + outer loop + vertex 1.03869 1.45811 2.62543 + vertex 1.04339 1.46289 2.62539 + vertex 1.0389 1.46316 2.62562 + endloop + endfacet + facet normal 0.0541378 -0.0439443 0.997566 + outer loop + vertex 1.04815 1.45753 2.62491 + vertex 1.04816 1.46261 2.62513 + vertex 1.04323 1.45768 2.62518 + endloop + endfacet + facet normal 0.0507034 -0.0383485 0.997977 + outer loop + vertex 1.04339 1.46289 2.62539 + vertex 1.0483 1.46777 2.62533 + vertex 1.04357 1.46825 2.62559 + endloop + endfacet + facet normal 0.052988 -0.040983 0.997754 + outer loop + vertex 1.05314 1.46255 2.62486 + vertex 1.05313 1.46758 2.62507 + vertex 1.04816 1.46261 2.62513 + endloop + endfacet + facet normal 0.0517673 -0.0374318 0.997957 + outer loop + vertex 1.0483 1.46777 2.62533 + vertex 1.05325 1.47265 2.62525 + vertex 1.04878 1.47292 2.6255 + endloop + endfacet + facet normal 0.0443418 -0.0383807 0.998279 + outer loop + vertex 1.05816 1.46754 2.62485 + vertex 1.05814 1.47253 2.62504 + vertex 1.05313 1.46758 2.62507 + endloop + endfacet + facet normal 0.0431753 -0.0351369 0.998449 + outer loop + vertex 1.05325 1.47265 2.62525 + vertex 1.05818 1.47759 2.62521 + vertex 1.0535 1.47776 2.62542 + endloop + endfacet + facet normal 0.0432928 -0.0321011 0.998547 + outer loop + vertex 1.05818 1.47759 2.62521 + vertex 1.05827 1.48279 2.62538 + vertex 1.0535 1.47776 2.62542 + endloop + endfacet + facet normal 0.0305652 -0.036276 0.998874 + outer loop + vertex 1.06328 1.47253 2.62488 + vertex 1.06324 1.4775 2.62506 + vertex 1.05814 1.47253 2.62504 + endloop + endfacet + facet normal 0.0283934 -0.0318828 0.999088 + outer loop + vertex 1.05818 1.47759 2.62521 + vertex 1.06323 1.48254 2.62523 + vertex 1.05827 1.48279 2.62538 + endloop + endfacet + facet normal 0.0315943 -0.0338967 0.998926 + outer loop + vertex 1.06847 1.47757 2.6249 + vertex 1.06844 1.48253 2.62507 + vertex 1.06324 1.4775 2.62506 + endloop + endfacet + facet normal 0.0804083 -0.0300176 0.99631 + outer loop + vertex 1.06844 1.48253 2.62507 + vertex 1.07349 1.48762 2.62481 + vertex 1.0684 1.48749 2.62522 + endloop + endfacet + facet normal 0.0803198 -0.026056 0.996429 + outer loop + vertex 1.07349 1.48762 2.62481 + vertex 1.07346 1.49253 2.62494 + vertex 1.0684 1.48749 2.62522 + endloop + endfacet + facet normal 0.214792 -0.0130649 0.976572 + outer loop + vertex 1.07346 1.49253 2.62494 + vertex 1.07802 1.49769 2.62401 + vertex 1.07341 1.49745 2.62502 + endloop + endfacet + facet normal 0.214427 -0.00550373 0.976725 + outer loop + vertex 1.07802 1.49769 2.62401 + vertex 1.07801 1.50266 2.62404 + vertex 1.07341 1.49745 2.62502 + endloop + endfacet + facet normal 0.216015 0.00198887 0.976388 + outer loop + vertex 1.07798 1.50766 2.62403 + vertex 1.07798 1.51268 2.62403 + vertex 1.07334 1.50735 2.62506 + endloop + endfacet + facet normal 0.211922 0.00853209 0.977249 + outer loop + vertex 1.07796 1.51769 2.624 + vertex 1.07796 1.5227 2.62396 + vertex 1.07331 1.5174 2.62501 + endloop + endfacet + facet normal 0.0764927 0.0197063 0.996875 + outer loop + vertex 1.07334 1.52241 2.62495 + vertex 1.07336 1.52742 2.62485 + vertex 1.06837 1.52239 2.62534 + endloop + endfacet + facet normal 0.0765177 0.0151987 0.996952 + outer loop + vertex 1.06838 1.51741 2.62541 + vertex 1.07334 1.52241 2.62495 + vertex 1.06837 1.52239 2.62534 + endloop + endfacet + facet normal 0.0261386 0.00846095 0.999623 + outer loop + vertex 1.06838 1.5124 2.62545 + vertex 1.06838 1.51741 2.62541 + vertex 1.06377 1.51305 2.62557 + endloop + endfacet + facet normal 0.0808978 0.00315526 0.996717 + outer loop + vertex 1.06838 1.5074 2.62547 + vertex 1.07332 1.51236 2.62505 + vertex 1.06838 1.5124 2.62545 + endloop + endfacet + facet normal 0.0248079 -0.00167979 0.999691 + outer loop + vertex 1.0684 1.50243 2.62546 + vertex 1.06838 1.5074 2.62547 + vertex 1.06378 1.50309 2.62558 + endloop + endfacet + facet normal 0.0797263 -0.00811313 0.996784 + outer loop + vertex 1.0684 1.49747 2.62542 + vertex 1.07337 1.50238 2.62506 + vertex 1.0684 1.50243 2.62546 + endloop + endfacet + facet normal 0.0265679 -0.015236 0.999531 + outer loop + vertex 1.06838 1.49248 2.62534 + vertex 1.0684 1.49747 2.62542 + vertex 1.06344 1.49295 2.62548 + endloop + endfacet + facet normal 0.0259815 -0.021324 0.999435 + outer loop + vertex 1.06325 1.4877 2.62538 + vertex 1.06838 1.49248 2.62534 + vertex 1.06344 1.49295 2.62548 + endloop + endfacet + facet normal 0.0285651 -0.0284829 0.999186 + outer loop + vertex 1.06323 1.48254 2.62523 + vertex 1.06325 1.4877 2.62538 + vertex 1.05827 1.48279 2.62538 + endloop + endfacet + facet normal 0.0444749 -0.0332243 0.998458 + outer loop + vertex 1.0535 1.47776 2.62542 + vertex 1.05827 1.48279 2.62538 + vertex 1.05365 1.48292 2.62559 + endloop + endfacet + facet normal 0.0558881 -0.0286309 0.998026 + outer loop + vertex 1.05427 1.48705 2.62567 + vertex 1.05176 1.48466 2.62574 + vertex 1.05365 1.48292 2.62559 + endloop + endfacet + facet normal 0.0503584 -0.0228174 0.998471 + outer loop + vertex 1.05427 1.48705 2.62567 + vertex 1.05183 1.48781 2.62581 + vertex 1.05176 1.48466 2.62574 + endloop + endfacet + facet normal 0.0454717 -0.0173537 0.998815 + outer loop + vertex 1.05183 1.48781 2.62581 + vertex 1.05219 1.49219 2.62587 + vertex 1.04812 1.4879 2.62598 + endloop + endfacet + facet normal 0.0418227 -0.0184085 0.998955 + outer loop + vertex 1.05821 1.48838 2.62553 + vertex 1.05935 1.49425 2.62559 + vertex 1.0554 1.49101 2.62569 + endloop + endfacet + facet normal 0.0190521 -0.00975669 0.999771 + outer loop + vertex 1.05935 1.49425 2.62559 + vertex 1.0637 1.4981 2.62554 + vertex 1.05971 1.49935 2.62563 + endloop + endfacet + facet normal 0.0481964 -0.0129046 0.998755 + outer loop + vertex 1.05243 1.49702 2.62592 + vertex 1.05219 1.49219 2.62587 + vertex 1.05596 1.49585 2.62574 + endloop + endfacet + facet normal 0.0464069 -0.00868443 0.998885 + outer loop + vertex 1.05243 1.49702 2.62592 + vertex 1.05253 1.502 2.62596 + vertex 1.04832 1.49766 2.62612 + endloop + endfacet + facet normal 0.0378554 -0.00564283 0.999267 + outer loop + vertex 1.05971 1.49935 2.62563 + vertex 1.05981 1.50434 2.62566 + vertex 1.05618 1.50081 2.62577 + endloop + endfacet + facet normal 0.0197464 -0.00145607 0.999804 + outer loop + vertex 1.05981 1.50434 2.62566 + vertex 1.06379 1.50808 2.62558 + vertex 1.05982 1.50932 2.62566 + endloop + endfacet + facet normal 0.0493257 -0.00491602 0.998771 + outer loop + vertex 1.05255 1.50701 2.62598 + vertex 1.05253 1.502 2.62596 + vertex 1.05625 1.5058 2.6258 + endloop + endfacet + facet normal 0.0473284 -0.000667345 0.998879 + outer loop + vertex 1.05255 1.50701 2.62598 + vertex 1.05251 1.512 2.62599 + vertex 1.04837 1.5077 2.62618 + endloop + endfacet + facet normal 0.0400648 0.00340215 0.999191 + outer loop + vertex 1.05982 1.50932 2.62566 + vertex 1.05975 1.51428 2.62565 + vertex 1.05622 1.51079 2.6258 + endloop + endfacet + facet normal 0.0233609 0.00752663 0.999699 + outer loop + vertex 1.05975 1.51428 2.62565 + vertex 1.06372 1.51801 2.62553 + vertex 1.05957 1.51919 2.62562 + endloop + endfacet + facet normal 0.0512708 0.00416342 0.998676 + outer loop + vertex 1.05235 1.51695 2.62598 + vertex 1.05251 1.512 2.62599 + vertex 1.0561 1.51572 2.62579 + endloop + endfacet + facet normal 0.0489716 0.00965706 0.998753 + outer loop + vertex 1.05235 1.51695 2.62598 + vertex 1.05185 1.52192 2.62595 + vertex 1.04821 1.51766 2.62617 + endloop + endfacet + facet normal 0.0518208 0.0170822 0.99851 + outer loop + vertex 1.05067 1.52724 2.62592 + vertex 1.05185 1.52192 2.62595 + vertex 1.05497 1.52551 2.62573 + endloop + endfacet + facet normal 0.0440705 0.0138886 0.998932 + outer loop + vertex 1.05957 1.51919 2.62562 + vertex 1.05912 1.52414 2.62557 + vertex 1.05574 1.52062 2.62576 + endloop + endfacet + facet normal 0.0287332 0.0194293 0.999398 + outer loop + vertex 1.06357 1.52293 2.62546 + vertex 1.06329 1.5279 2.62537 + vertex 1.05912 1.52414 2.62557 + endloop + endfacet + facet normal 0.0300644 0.0267981 0.999189 + outer loop + vertex 1.06833 1.52734 2.62524 + vertex 1.0683 1.53229 2.62511 + vertex 1.06329 1.5279 2.62537 + endloop + endfacet + facet normal 0.0715899 0.0317643 0.996928 + outer loop + vertex 1.0683 1.53229 2.62511 + vertex 1.07342 1.53742 2.62457 + vertex 1.06832 1.53722 2.62495 + endloop + endfacet + facet normal 0.0692145 0.0362888 0.996942 + outer loop + vertex 1.06832 1.53722 2.62495 + vertex 1.07346 1.54246 2.6244 + vertex 1.06834 1.54219 2.62476 + endloop + endfacet + facet normal 0.0692408 0.0358118 0.996957 + outer loop + vertex 1.07346 1.54246 2.6244 + vertex 1.0735 1.54753 2.62421 + vertex 1.06834 1.54219 2.62476 + endloop + endfacet + facet normal 0.058005 0.0456956 0.99727 + outer loop + vertex 1.06837 1.54724 2.62456 + vertex 1.07353 1.55258 2.62401 + vertex 1.06843 1.55233 2.62432 + endloop + endfacet + facet normal 0.177357 0.0285958 0.983731 + outer loop + vertex 1.07802 1.54779 2.62339 + vertex 1.07802 1.5528 2.62325 + vertex 1.0735 1.54753 2.62421 + endloop + endfacet + facet normal 0.0579936 0.045917 0.99726 + outer loop + vertex 1.07353 1.55258 2.62401 + vertex 1.07355 1.5576 2.62378 + vertex 1.06843 1.55233 2.62432 + endloop + endfacet + facet normal 0.0321936 0.0460688 0.998419 + outer loop + vertex 1.06837 1.54724 2.62456 + vertex 1.06843 1.55233 2.62432 + vertex 1.06308 1.54714 2.62473 + endloop + endfacet + facet normal 0.0322957 0.040953 0.998639 + outer loop + vertex 1.06312 1.54218 2.62493 + vertex 1.06837 1.54724 2.62456 + vertex 1.06308 1.54714 2.62473 + endloop + endfacet + facet normal 0.0337413 0.0359495 0.998784 + outer loop + vertex 1.06327 1.53743 2.6251 + vertex 1.06312 1.54218 2.62493 + vertex 1.0585 1.53794 2.62524 + endloop + endfacet + facet normal 0.0330565 0.0295128 0.999018 + outer loop + vertex 1.05924 1.53407 2.62533 + vertex 1.06327 1.53743 2.6251 + vertex 1.0585 1.53794 2.62524 + endloop + endfacet + facet normal 0.0309523 0.0296277 0.999082 + outer loop + vertex 1.05815 1.52954 2.6255 + vertex 1.06326 1.53278 2.62525 + vertex 1.05924 1.53407 2.62533 + endloop + endfacet + facet normal 0.0478006 0.0193882 0.998669 + outer loop + vertex 1.05386 1.5296 2.6257 + vertex 1.05497 1.52551 2.62573 + vertex 1.05815 1.52954 2.6255 + endloop + endfacet + facet normal 0.0533423 0.0208908 0.998358 + outer loop + vertex 1.05497 1.52551 2.62573 + vertex 1.05386 1.5296 2.6257 + vertex 1.05067 1.52724 2.62592 + endloop + endfacet + facet normal 0.0467347 0.0241282 0.998616 + outer loop + vertex 1.04689 1.53172 2.62599 + vertex 1.04666 1.5266 2.62613 + vertex 1.05067 1.52724 2.62592 + endloop + endfacet + facet normal 0.0529384 0.0294132 0.998165 + outer loop + vertex 1.04988 1.53464 2.62578 + vertex 1.05117 1.53157 2.6258 + vertex 1.05427 1.53425 2.62556 + endloop + endfacet + facet normal 0.0392833 0.0286894 0.998816 + outer loop + vertex 1.04284 1.53618 2.62602 + vertex 1.04219 1.53146 2.62619 + vertex 1.04689 1.53172 2.62599 + endloop + endfacet + facet normal 0.0385748 0.0325202 0.998726 + outer loop + vertex 1.04119 1.54124 2.62592 + vertex 1.04284 1.53618 2.62602 + vertex 1.04546 1.54026 2.62579 + endloop + endfacet + facet normal 0.038825 0.0336197 0.99868 + outer loop + vertex 1.04546 1.54026 2.62579 + vertex 1.04382 1.54391 2.62573 + vertex 1.04119 1.54124 2.62592 + endloop + endfacet + facet normal 0.0483542 0.0336923 0.998262 + outer loop + vertex 1.04988 1.53464 2.62578 + vertex 1.05021 1.5388 2.62562 + vertex 1.04705 1.5365 2.62585 + endloop + endfacet + facet normal 0.051448 0.0343101 0.998086 + outer loop + vertex 1.05461 1.53907 2.62538 + vertex 1.05341 1.54308 2.62531 + vertex 1.05021 1.5388 2.62562 + endloop + endfacet + facet normal 0.0484156 0.0390627 0.998063 + outer loop + vertex 1.05816 1.54252 2.6251 + vertex 1.05792 1.54731 2.62492 + vertex 1.05341 1.54308 2.62531 + endloop + endfacet + facet normal 0.0407364 0.0441144 0.998196 + outer loop + vertex 1.05792 1.54731 2.62492 + vertex 1.06314 1.55221 2.62449 + vertex 1.05795 1.55226 2.6247 + endloop + endfacet + facet normal 0.0407947 0.0517823 0.997825 + outer loop + vertex 1.06314 1.55221 2.62449 + vertex 1.06324 1.55729 2.62423 + vertex 1.05795 1.55226 2.6247 + endloop + endfacet + facet normal 0.0468055 0.0526632 0.997515 + outer loop + vertex 1.05805 1.55723 2.62445 + vertex 1.06332 1.56236 2.62394 + vertex 1.05812 1.56226 2.62419 + endloop + endfacet + facet normal 0.0310343 0.0573694 0.997871 + outer loop + vertex 1.0685 1.5574 2.62406 + vertex 1.06856 1.56244 2.62376 + vertex 1.06324 1.55729 2.62423 + endloop + endfacet + facet normal 0.0345711 0.0604531 0.997572 + outer loop + vertex 1.06332 1.56236 2.62394 + vertex 1.06861 1.56749 2.62344 + vertex 1.0634 1.56744 2.62363 + endloop + endfacet + facet normal 0.0466468 0.0596075 0.997131 + outer loop + vertex 1.07356 1.56259 2.62352 + vertex 1.0736 1.56759 2.62322 + vertex 1.06856 1.56244 2.62376 + endloop + endfacet + facet normal 0.0405533 0.0683327 0.996838 + outer loop + vertex 1.06861 1.56749 2.62344 + vertex 1.07367 1.57263 2.62288 + vertex 1.06869 1.57257 2.62309 + endloop + endfacet + facet normal 0.131089 0.0539932 0.989899 + outer loop + vertex 1.07797 1.56772 2.62263 + vertex 1.07803 1.57276 2.62235 + vertex 1.0736 1.56759 2.62322 + endloop + endfacet + facet normal 0.0405267 0.069963 0.996726 + outer loop + vertex 1.07367 1.57263 2.62288 + vertex 1.07367 1.57767 2.62253 + vertex 1.06869 1.57257 2.62309 + endloop + endfacet + facet normal 0.0344727 0.0684378 0.99706 + outer loop + vertex 1.06861 1.56749 2.62344 + vertex 1.06869 1.57257 2.62309 + vertex 1.0634 1.56744 2.62363 + endloop + endfacet + facet normal 0.0466482 0.0602418 0.997093 + outer loop + vertex 1.06332 1.56236 2.62394 + vertex 1.0634 1.56744 2.62363 + vertex 1.05812 1.56226 2.62419 + endloop + endfacet + facet normal 0.0549428 0.0525231 0.997107 + outer loop + vertex 1.05805 1.55723 2.62445 + vertex 1.05812 1.56226 2.62419 + vertex 1.053 1.55719 2.62474 + endloop + endfacet + facet normal 0.05501 0.0464863 0.997403 + outer loop + vertex 1.05309 1.55246 2.62495 + vertex 1.05805 1.55723 2.62445 + vertex 1.053 1.55719 2.62474 + endloop + endfacet + facet normal 0.053157 0.0419113 0.997706 + outer loop + vertex 1.05305 1.54782 2.62515 + vertex 1.05309 1.55246 2.62495 + vertex 1.04921 1.54883 2.62531 + endloop + endfacet + facet normal 0.0516147 0.0360289 0.998017 + outer loop + vertex 1.04826 1.54427 2.62552 + vertex 1.05305 1.54782 2.62515 + vertex 1.04921 1.54883 2.62531 + endloop + endfacet + facet normal 0.043741 0.0358174 0.998401 + outer loop + vertex 1.04382 1.54391 2.62573 + vertex 1.04546 1.54026 2.62579 + vertex 1.04826 1.54427 2.62552 + endloop + endfacet + facet normal 0.0380706 0.0343614 0.998684 + outer loop + vertex 1.04382 1.54391 2.62573 + vertex 1.04046 1.54558 2.6258 + vertex 1.04119 1.54124 2.62592 + endloop + endfacet + facet normal 0.046397 0.0392322 0.998152 + outer loop + vertex 1.04456 1.54815 2.62555 + vertex 1.04836 1.5526 2.62519 + vertex 1.04355 1.55315 2.6254 + endloop + endfacet + facet normal 0.0420364 0.0356672 0.998479 + outer loop + vertex 1.04046 1.54558 2.6258 + vertex 1.03986 1.54986 2.62567 + vertex 1.03715 1.54723 2.62588 + endloop + endfacet + facet normal 0.057329 0.0341092 0.997772 + outer loop + vertex 1.03715 1.54723 2.62588 + vertex 1.03292 1.54655 2.62615 + vertex 1.03656 1.54274 2.62607 + endloop + endfacet + facet normal 0.0798023 0.0403543 0.995994 + outer loop + vertex 1.03292 1.54655 2.62615 + vertex 1.03123 1.55215 2.62606 + vertex 1.02791 1.54728 2.62652 + endloop + endfacet + facet normal 0.0473382 0.0357518 0.998239 + outer loop + vertex 1.03447 1.55465 2.62575 + vertex 1.03572 1.55091 2.62582 + vertex 1.0386 1.55471 2.62555 + endloop + endfacet + facet normal 0.0865593 0.0380728 0.995519 + outer loop + vertex 1.02768 1.55624 2.62621 + vertex 1.02688 1.55133 2.62647 + vertex 1.03123 1.55215 2.62606 + endloop + endfacet + facet normal 0.0900418 0.0377251 0.995223 + outer loop + vertex 1.02613 1.562 2.62613 + vertex 1.02768 1.55624 2.62621 + vertex 1.03064 1.56055 2.62578 + endloop + endfacet + facet normal 0.0929079 0.0467674 0.994576 + outer loop + vertex 1.03064 1.56055 2.62578 + vertex 1.0295 1.56456 2.6257 + vertex 1.02613 1.562 2.62613 + endloop + endfacet + facet normal 0.061038 0.0356785 0.997498 + outer loop + vertex 1.03447 1.55465 2.62575 + vertex 1.03516 1.55889 2.62555 + vertex 1.03186 1.5566 2.62584 + endloop + endfacet + facet normal 0.070051 0.0403087 0.996729 + outer loop + vertex 1.0295 1.56456 2.6257 + vertex 1.03064 1.56055 2.62578 + vertex 1.03366 1.56453 2.6254 + endloop + endfacet + facet normal 0.0700715 0.0445048 0.996549 + outer loop + vertex 1.0295 1.56456 2.6257 + vertex 1.03366 1.56453 2.6254 + vertex 1.03038 1.56884 2.62544 + endloop + endfacet + facet normal 0.0715473 0.0456306 0.996393 + outer loop + vertex 1.03038 1.56884 2.62544 + vertex 1.03366 1.56453 2.6254 + vertex 1.03459 1.56909 2.62513 + endloop + endfacet + facet normal 0.0712875 0.0497129 0.996216 + outer loop + vertex 1.03459 1.56909 2.62513 + vertex 1.03372 1.57303 2.625 + vertex 1.03038 1.56884 2.62544 + endloop + endfacet + facet normal 0.077316 0.0448957 0.995995 + outer loop + vertex 1.03038 1.56884 2.62544 + vertex 1.03372 1.57303 2.625 + vertex 1.0293 1.57407 2.62529 + endloop + endfacet + facet normal 0.0934498 0.0482046 0.994456 + outer loop + vertex 1.03038 1.56884 2.62544 + vertex 1.0293 1.57407 2.62529 + vertex 1.02606 1.57052 2.62577 + endloop + endfacet + facet normal 0.0899224 0.0389789 0.995186 + outer loop + vertex 1.027 1.56656 2.62584 + vertex 1.03038 1.56884 2.62544 + vertex 1.02606 1.57052 2.62577 + endloop + endfacet + facet normal 0.121687 0.0464528 0.991481 + outer loop + vertex 1.02606 1.57052 2.62577 + vertex 1.02285 1.56615 2.62637 + vertex 1.027 1.56656 2.62584 + endloop + endfacet + facet normal 0.1223 0.040516 0.991666 + outer loop + vertex 1.027 1.56656 2.62584 + vertex 1.02285 1.56615 2.62637 + vertex 1.02613 1.562 2.62613 + endloop + endfacet + facet normal 0.0933631 0.0461667 0.994561 + outer loop + vertex 1.027 1.56656 2.62584 + vertex 1.02613 1.562 2.62613 + vertex 1.0295 1.56456 2.6257 + endloop + endfacet + facet normal 0.0888909 0.0405206 0.995217 + outer loop + vertex 1.0295 1.56456 2.6257 + vertex 1.03038 1.56884 2.62544 + vertex 1.027 1.56656 2.62584 + endloop + endfacet + facet normal 0.0972334 0.0447253 0.994256 + outer loop + vertex 1.02606 1.57052 2.62577 + vertex 1.0293 1.57407 2.62529 + vertex 1.02505 1.57535 2.62565 + endloop + endfacet + facet normal 0.128271 0.051115 0.990421 + outer loop + vertex 1.02505 1.57535 2.62565 + vertex 1.02183 1.5716 2.62626 + vertex 1.02606 1.57052 2.62577 + endloop + endfacet + facet normal 0.0991655 0.0512583 0.99375 + outer loop + vertex 1.0293 1.57407 2.62529 + vertex 1.02833 1.57943 2.62511 + vertex 1.02505 1.57535 2.62565 + endloop + endfacet + facet normal 0.101912 0.04902 0.993585 + outer loop + vertex 1.02416 1.57934 2.62554 + vertex 1.02505 1.57535 2.62565 + vertex 1.02833 1.57943 2.62511 + endloop + endfacet + facet normal 0.0820124 0.048232 0.995464 + outer loop + vertex 1.0293 1.57407 2.62529 + vertex 1.0332 1.57788 2.62478 + vertex 1.02833 1.57943 2.62511 + endloop + endfacet + facet normal 0.0843019 0.0555632 0.99489 + outer loop + vertex 1.0332 1.57788 2.62478 + vertex 1.03316 1.58274 2.62452 + vertex 1.02833 1.57943 2.62511 + endloop + endfacet + facet normal 0.0837028 0.0564351 0.994891 + outer loop + vertex 1.02833 1.57943 2.62511 + vertex 1.03316 1.58274 2.62452 + vertex 1.02948 1.58398 2.62476 + endloop + endfacet + facet normal 0.100751 0.0520424 0.99355 + outer loop + vertex 1.02518 1.58362 2.62521 + vertex 1.02833 1.57943 2.62511 + vertex 1.02948 1.58398 2.62476 + endloop + endfacet + facet normal 0.100251 0.0576026 0.993293 + outer loop + vertex 1.02948 1.58398 2.62476 + vertex 1.02864 1.58788 2.62462 + vertex 1.02518 1.58362 2.62521 + endloop + endfacet + facet normal 0.109149 0.0503229 0.992751 + outer loop + vertex 1.02518 1.58362 2.62521 + vertex 1.02864 1.58788 2.62462 + vertex 1.02413 1.58883 2.62506 + endloop + endfacet + facet normal 0.110732 0.0581067 0.99215 + outer loop + vertex 1.02864 1.58788 2.62462 + vertex 1.02816 1.59275 2.62438 + vertex 1.02413 1.58883 2.62506 + endloop + endfacet + facet normal 0.117526 0.0510604 0.991756 + outer loop + vertex 1.02413 1.58883 2.62506 + vertex 1.02816 1.59275 2.62438 + vertex 1.02321 1.59423 2.62489 + endloop + endfacet + facet normal 0.12008 0.0598837 0.990956 + outer loop + vertex 1.02816 1.59275 2.62438 + vertex 1.02821 1.59771 2.62408 + vertex 1.02321 1.59423 2.62489 + endloop + endfacet + facet normal 0.0990239 0.0602469 0.99326 + outer loop + vertex 1.02816 1.59275 2.62438 + vertex 1.03314 1.59725 2.62361 + vertex 1.02821 1.59771 2.62408 + endloop + endfacet + facet normal 0.0995265 0.066125 0.992835 + outer loop + vertex 1.03314 1.59725 2.62361 + vertex 1.03333 1.60234 2.62326 + vertex 1.02821 1.59771 2.62408 + endloop + endfacet + facet normal 0.103076 0.0621799 0.992728 + outer loop + vertex 1.02821 1.59771 2.62408 + vertex 1.03333 1.60234 2.62326 + vertex 1.02843 1.60253 2.62375 + endloop + endfacet + facet normal 0.118863 0.0613496 0.991014 + outer loop + vertex 1.02821 1.59771 2.62408 + vertex 1.02843 1.60253 2.62375 + vertex 1.02449 1.59889 2.62445 + endloop + endfacet + facet normal 0.10326 0.0680098 0.992327 + outer loop + vertex 1.03333 1.60234 2.62326 + vertex 1.03349 1.60742 2.62289 + vertex 1.02843 1.60253 2.62375 + endloop + endfacet + facet normal 0.107934 0.0631416 0.992151 + outer loop + vertex 1.02843 1.60253 2.62375 + vertex 1.03349 1.60742 2.62289 + vertex 1.02846 1.60744 2.62344 + endloop + endfacet + facet normal 0.126166 0.0629051 0.990013 + outer loop + vertex 1.02843 1.60253 2.62375 + vertex 1.02846 1.60744 2.62344 + vertex 1.02384 1.6029 2.62431 + endloop + endfacet + facet normal 0.107909 0.0708158 0.991635 + outer loop + vertex 1.03349 1.60742 2.62289 + vertex 1.0335 1.61246 2.62253 + vertex 1.02846 1.60744 2.62344 + endloop + endfacet + facet normal 0.112944 0.0657217 0.991425 + outer loop + vertex 1.02846 1.60744 2.62344 + vertex 1.0335 1.61246 2.62253 + vertex 1.0285 1.61252 2.6231 + endloop + endfacet + facet normal 0.132843 0.0653933 0.988978 + outer loop + vertex 1.02846 1.60744 2.62344 + vertex 1.0285 1.61252 2.6231 + vertex 1.02364 1.60784 2.62406 + endloop + endfacet + facet normal 0.139505 0.0583703 0.9885 + outer loop + vertex 1.02364 1.60784 2.62406 + vertex 1.0285 1.61252 2.6231 + vertex 1.0236 1.61293 2.62376 + endloop + endfacet + facet normal 0.14018 0.0674648 0.987825 + outer loop + vertex 1.0285 1.61252 2.6231 + vertex 1.02842 1.61755 2.62276 + vertex 1.0236 1.61293 2.62376 + endloop + endfacet + facet normal 0.119457 0.0673462 0.990553 + outer loop + vertex 1.0285 1.61252 2.6231 + vertex 1.03327 1.61735 2.62219 + vertex 1.02842 1.61755 2.62276 + endloop + endfacet + facet normal 0.119707 0.0748399 0.989984 + outer loop + vertex 1.03327 1.61735 2.62219 + vertex 1.03278 1.62207 2.62189 + vertex 1.02842 1.61755 2.62276 + endloop + endfacet + facet normal 0.12559 0.0690993 0.989673 + outer loop + vertex 1.02842 1.61755 2.62276 + vertex 1.03278 1.62207 2.62189 + vertex 1.02812 1.62236 2.62247 + endloop + endfacet + facet normal 0.148974 0.0703696 0.986334 + outer loop + vertex 1.02842 1.61755 2.62276 + vertex 1.02812 1.62236 2.62247 + vertex 1.0235 1.61803 2.62347 + endloop + endfacet + facet normal 0.12602 0.0772481 0.989015 + outer loop + vertex 1.03278 1.62207 2.62189 + vertex 1.03166 1.62608 2.62172 + vertex 1.02812 1.62236 2.62247 + endloop + endfacet + facet normal 0.132372 0.0711243 0.988645 + outer loop + vertex 1.02812 1.62236 2.62247 + vertex 1.03166 1.62608 2.62172 + vertex 1.02774 1.62699 2.62218 + endloop + endfacet + facet normal 0.155305 0.0728026 0.98518 + outer loop + vertex 1.02812 1.62236 2.62247 + vertex 1.02774 1.62699 2.62218 + vertex 1.02355 1.62295 2.62314 + endloop + endfacet + facet normal 0.13319 0.074812 0.988263 + outer loop + vertex 1.03166 1.62608 2.62172 + vertex 1.03179 1.63127 2.62131 + vertex 1.02774 1.62699 2.62218 + endloop + endfacet + facet normal 0.138357 0.069841 0.987917 + outer loop + vertex 1.02774 1.62699 2.62218 + vertex 1.03179 1.63127 2.62131 + vertex 1.02688 1.63094 2.62203 + endloop + endfacet + facet normal 0.162141 0.0748866 0.983922 + outer loop + vertex 1.02774 1.62699 2.62218 + vertex 1.02688 1.63094 2.62203 + vertex 1.02344 1.62749 2.62285 + endloop + endfacet + facet normal 0.137951 0.0751268 0.987586 + outer loop + vertex 1.02763 1.63591 2.62154 + vertex 1.02688 1.63094 2.62203 + vertex 1.03179 1.63127 2.62131 + endloop + endfacet + facet normal 0.143442 0.0801071 0.986411 + outer loop + vertex 1.0319 1.63628 2.62089 + vertex 1.02763 1.63591 2.62154 + vertex 1.03179 1.63127 2.62131 + endloop + endfacet + facet normal 0.118644 0.0809301 0.989633 + outer loop + vertex 1.0319 1.63628 2.62089 + vertex 1.03179 1.63127 2.62131 + vertex 1.03475 1.63437 2.62071 + endloop + endfacet + facet normal 0.113739 0.0735064 0.990788 + outer loop + vertex 1.03475 1.63437 2.62071 + vertex 1.03513 1.63862 2.62035 + vertex 1.0319 1.63628 2.62089 + endloop + endfacet + facet normal 0.116885 0.0691531 0.990735 + outer loop + vertex 1.0319 1.63628 2.62089 + vertex 1.03513 1.63862 2.62035 + vertex 1.03045 1.64033 2.62078 + endloop + endfacet + facet normal 0.119913 0.0777156 0.989738 + outer loop + vertex 1.03513 1.63862 2.62035 + vertex 1.03345 1.64436 2.6201 + vertex 1.03045 1.64033 2.62078 + endloop + endfacet + facet normal 0.125889 0.0732014 0.98934 + outer loop + vertex 1.02919 1.64436 2.62064 + vertex 1.03045 1.64033 2.62078 + vertex 1.03345 1.64436 2.6201 + endloop + endfacet + facet normal 0.125887 0.0734025 0.989325 + outer loop + vertex 1.02919 1.64436 2.62064 + vertex 1.03345 1.64436 2.6201 + vertex 1.03 1.6487 2.62022 + endloop + endfacet + facet normal 0.150604 0.0684952 0.986218 + outer loop + vertex 1.02919 1.64436 2.62064 + vertex 1.03 1.6487 2.62022 + vertex 1.0266 1.64637 2.6209 + endloop + endfacet + facet normal 0.158267 0.0785875 0.984264 + outer loop + vertex 1.0266 1.64637 2.6209 + vertex 1.02592 1.64183 2.62137 + vertex 1.02919 1.64436 2.62064 + endloop + endfacet + facet normal 0.198432 0.0718164 0.97748 + outer loop + vertex 1.0266 1.64637 2.6209 + vertex 1.02257 1.6462 2.62173 + vertex 1.02592 1.64183 2.62137 + endloop + endfacet + facet normal 0.153941 0.0635674 0.986033 + outer loop + vertex 1.0266 1.64637 2.6209 + vertex 1.03 1.6487 2.62022 + vertex 1.02545 1.65034 2.62082 + endloop + endfacet + facet normal 0.12728 0.0745193 0.989064 + outer loop + vertex 1.03 1.6487 2.62022 + vertex 1.03345 1.64436 2.6201 + vertex 1.03449 1.649 2.61962 + endloop + endfacet + facet normal 0.126998 0.0782229 0.988814 + outer loop + vertex 1.03449 1.649 2.61962 + vertex 1.03368 1.65305 2.6194 + vertex 1.03 1.6487 2.62022 + endloop + endfacet + facet normal 0.134854 0.0714726 0.988284 + outer loop + vertex 1.03 1.6487 2.62022 + vertex 1.03368 1.65305 2.6194 + vertex 1.02864 1.65436 2.61999 + endloop + endfacet + facet normal 0.137193 0.080906 0.987235 + outer loop + vertex 1.03368 1.65305 2.6194 + vertex 1.03358 1.65791 2.61901 + vertex 1.02864 1.65436 2.61999 + endloop + endfacet + facet normal 0.121287 0.0807485 0.989328 + outer loop + vertex 1.03368 1.65305 2.6194 + vertex 1.03844 1.65742 2.61846 + vertex 1.03358 1.65791 2.61901 + endloop + endfacet + facet normal 0.121994 0.0886562 0.988563 + outer loop + vertex 1.03844 1.65742 2.61846 + vertex 1.03842 1.66238 2.61802 + vertex 1.03358 1.65791 2.61901 + endloop + endfacet + facet normal 0.125588 0.0847446 0.988456 + outer loop + vertex 1.03358 1.65791 2.61901 + vertex 1.03842 1.66238 2.61802 + vertex 1.03368 1.66268 2.61859 + endloop + endfacet + facet normal 0.137861 0.0843573 0.986853 + outer loop + vertex 1.03358 1.65791 2.61901 + vertex 1.03368 1.66268 2.61859 + vertex 1.02981 1.65905 2.61944 + endloop + endfacet + facet normal 0.125955 0.0918946 0.987771 + outer loop + vertex 1.03842 1.66238 2.61802 + vertex 1.03818 1.6672 2.6176 + vertex 1.03368 1.66268 2.61859 + endloop + endfacet + facet normal 0.13196 0.0858529 0.98753 + outer loop + vertex 1.03368 1.66268 2.61859 + vertex 1.03818 1.6672 2.6176 + vertex 1.03347 1.66747 2.6182 + endloop + endfacet + facet normal 0.145341 0.0862591 0.985614 + outer loop + vertex 1.03368 1.66268 2.61859 + vertex 1.03347 1.66747 2.6182 + vertex 1.02911 1.66305 2.61923 + endloop + endfacet + facet normal 0.132274 0.0926397 0.986875 + outer loop + vertex 1.03818 1.6672 2.6176 + vertex 1.03772 1.67194 2.61722 + vertex 1.03347 1.66747 2.6182 + endloop + endfacet + facet normal 0.119582 0.0915573 0.988594 + outer loop + vertex 1.03818 1.6672 2.6176 + vertex 1.04174 1.67106 2.61681 + vertex 1.03772 1.67194 2.61722 + endloop + endfacet + facet normal 0.119902 0.0931056 0.98841 + outer loop + vertex 1.04174 1.67106 2.61681 + vertex 1.04164 1.67634 2.61633 + vertex 1.03772 1.67194 2.61722 + endloop + endfacet + facet normal 0.124259 0.0891856 0.988234 + outer loop + vertex 1.03772 1.67194 2.61722 + vertex 1.04164 1.67634 2.61633 + vertex 1.03666 1.67603 2.61698 + endloop + endfacet + facet normal 0.139668 0.0930664 0.985815 + outer loop + vertex 1.03772 1.67194 2.61722 + vertex 1.03666 1.67603 2.61698 + vertex 1.03311 1.67229 2.61784 + endloop + endfacet + facet normal 0.139227 0.0859519 0.986523 + outer loop + vertex 1.03347 1.66747 2.6182 + vertex 1.03772 1.67194 2.61722 + vertex 1.03311 1.67229 2.61784 + endloop + endfacet + facet normal 0.154393 0.0869321 0.984178 + outer loop + vertex 1.03347 1.66747 2.6182 + vertex 1.03311 1.67229 2.61784 + vertex 1.02875 1.66794 2.6189 + endloop + endfacet + facet normal 0.147319 0.0857041 0.985369 + outer loop + vertex 1.03311 1.67229 2.61784 + vertex 1.03666 1.67603 2.61698 + vertex 1.03271 1.67702 2.61748 + endloop + endfacet + facet normal 0.165382 0.0869857 0.982386 + outer loop + vertex 1.03311 1.67229 2.61784 + vertex 1.03271 1.67702 2.61748 + vertex 1.02845 1.67298 2.61856 + endloop + endfacet + facet normal 0.148133 0.0891728 0.984939 + outer loop + vertex 1.03666 1.67603 2.61698 + vertex 1.03683 1.68126 2.61648 + vertex 1.03271 1.67702 2.61748 + endloop + endfacet + facet normal 0.152605 0.0847723 0.984645 + outer loop + vertex 1.03271 1.67702 2.61748 + vertex 1.03683 1.68126 2.61648 + vertex 1.03192 1.681 2.61726 + endloop + endfacet + facet normal 0.172244 0.0884828 0.981072 + outer loop + vertex 1.03271 1.67702 2.61748 + vertex 1.03192 1.681 2.61726 + vertex 1.02836 1.67778 2.61818 + endloop + endfacet + facet normal 0.152374 0.0882936 0.984371 + outer loop + vertex 1.03266 1.68586 2.61671 + vertex 1.03192 1.681 2.61726 + vertex 1.03683 1.68126 2.61648 + endloop + endfacet + facet normal 0.124181 0.0902616 0.988146 + outer loop + vertex 1.03683 1.68126 2.61648 + vertex 1.03666 1.67603 2.61698 + vertex 1.04164 1.67634 2.61633 + endloop + endfacet + facet normal 0.131527 0.0974943 0.986507 + outer loop + vertex 1.04137 1.68123 2.61588 + vertex 1.03683 1.68126 2.61648 + vertex 1.04164 1.67634 2.61633 + endloop + endfacet + facet normal 0.109738 0.0965148 0.989264 + outer loop + vertex 1.04137 1.68123 2.61588 + vertex 1.04164 1.67634 2.61633 + vertex 1.04444 1.6794 2.61572 + endloop + endfacet + facet normal 0.107007 0.0918599 0.990006 + outer loop + vertex 1.04444 1.6794 2.61572 + vertex 1.04437 1.68397 2.6153 + vertex 1.04137 1.68123 2.61588 + endloop + endfacet + facet normal 0.110132 0.0884179 0.989976 + outer loop + vertex 1.0398 1.68438 2.61577 + vertex 1.04137 1.68123 2.61588 + vertex 1.04437 1.68397 2.6153 + endloop + endfacet + facet normal 0.110332 0.090937 0.989726 + outer loop + vertex 1.0398 1.68438 2.61577 + vertex 1.04437 1.68397 2.6153 + vertex 1.04019 1.68861 2.61534 + endloop + endfacet + facet normal 0.115755 0.0958198 0.988645 + outer loop + vertex 1.04019 1.68861 2.61534 + vertex 1.04437 1.68397 2.6153 + vertex 1.04464 1.68885 2.6148 + endloop + endfacet + facet normal 0.100936 0.0968033 0.990172 + outer loop + vertex 1.04437 1.68397 2.6153 + vertex 1.04856 1.68777 2.6145 + vertex 1.04464 1.68885 2.6148 + endloop + endfacet + facet normal 0.102056 0.101045 0.989633 + outer loop + vertex 1.04856 1.68777 2.6145 + vertex 1.04842 1.69245 2.61404 + vertex 1.04464 1.68885 2.6148 + endloop + endfacet + facet normal 0.10748 0.0953637 0.989623 + outer loop + vertex 1.04464 1.68885 2.6148 + vertex 1.04842 1.69245 2.61404 + vertex 1.04364 1.69296 2.61451 + endloop + endfacet + facet normal 0.108105 0.101947 0.988898 + outer loop + vertex 1.04842 1.69245 2.61404 + vertex 1.04836 1.69733 2.61354 + vertex 1.04364 1.69296 2.61451 + endloop + endfacet + facet normal 0.100582 0.101946 0.989692 + outer loop + vertex 1.04842 1.69245 2.61404 + vertex 1.05335 1.69723 2.61304 + vertex 1.04836 1.69733 2.61354 + endloop + endfacet + facet normal 0.100615 0.105395 0.989327 + outer loop + vertex 1.05335 1.69723 2.61304 + vertex 1.0532 1.70212 2.61254 + vertex 1.04836 1.69733 2.61354 + endloop + endfacet + facet normal 0.102759 0.10323 0.989335 + outer loop + vertex 1.04836 1.69733 2.61354 + vertex 1.0532 1.70212 2.61254 + vertex 1.04839 1.70228 2.61302 + endloop + endfacet + facet normal 0.112412 0.103076 0.988301 + outer loop + vertex 1.04836 1.69733 2.61354 + vertex 1.04839 1.70228 2.61302 + vertex 1.04351 1.69784 2.61404 + endloop + endfacet + facet normal 0.102825 0.106082 0.989027 + outer loop + vertex 1.0532 1.70212 2.61254 + vertex 1.05281 1.70686 2.61207 + vertex 1.04839 1.70228 2.61302 + endloop + endfacet + facet normal 0.105475 0.103519 0.989019 + outer loop + vertex 1.04839 1.70228 2.61302 + vertex 1.05281 1.70686 2.61207 + vertex 1.04818 1.70707 2.61254 + endloop + endfacet + facet normal 0.105612 0.107542 0.988575 + outer loop + vertex 1.05281 1.70686 2.61207 + vertex 1.05169 1.71088 2.61175 + vertex 1.04818 1.70707 2.61254 + endloop + endfacet + facet normal 0.0988328 0.105714 0.989473 + outer loop + vertex 1.05281 1.70686 2.61207 + vertex 1.0566 1.71118 2.61123 + vertex 1.05169 1.71088 2.61175 + endloop + endfacet + facet normal 0.098827 0.105794 0.989465 + outer loop + vertex 1.05148 1.71606 2.61122 + vertex 1.05169 1.71088 2.61175 + vertex 1.0566 1.71118 2.61123 + endloop + endfacet + facet normal 0.102376 0.109512 0.988699 + outer loop + vertex 1.05611 1.71591 2.61076 + vertex 1.05148 1.71606 2.61122 + vertex 1.0566 1.71118 2.61123 + endloop + endfacet + facet normal 0.101015 0.109386 0.988853 + outer loop + vertex 1.05611 1.71591 2.61076 + vertex 1.0566 1.71118 2.61123 + vertex 1.05928 1.71411 2.61063 + endloop + endfacet + facet normal 0.103053 0.113032 0.988233 + outer loop + vertex 1.05928 1.71411 2.61063 + vertex 1.05904 1.71867 2.61014 + vertex 1.05611 1.71591 2.61076 + endloop + endfacet + facet normal 0.102611 0.113498 0.988225 + outer loop + vertex 1.05421 1.71904 2.61059 + vertex 1.05611 1.71591 2.61076 + vertex 1.05904 1.71867 2.61014 + endloop + endfacet + facet normal 0.10217 0.106744 0.989023 + outer loop + vertex 1.05421 1.71904 2.61059 + vertex 1.05904 1.71867 2.61014 + vertex 1.054 1.72367 2.61012 + endloop + endfacet + facet normal 0.102873 0.106769 0.988948 + outer loop + vertex 1.05421 1.71904 2.61059 + vertex 1.054 1.72367 2.61012 + vertex 1.05101 1.72086 2.61073 + endloop + endfacet + facet normal 0.105194 0.110908 0.988248 + outer loop + vertex 1.05101 1.72086 2.61073 + vertex 1.05148 1.71606 2.61122 + vertex 1.05421 1.71904 2.61059 + endloop + endfacet + facet normal 0.12145 0.112305 0.986224 + outer loop + vertex 1.05101 1.72086 2.61073 + vertex 1.04639 1.72103 2.61128 + vertex 1.05148 1.71606 2.61122 + endloop + endfacet + facet normal 0.104953 0.104561 0.988965 + outer loop + vertex 1.04918 1.72407 2.61059 + vertex 1.05101 1.72086 2.61073 + vertex 1.054 1.72367 2.61012 + endloop + endfacet + facet normal 0.111542 0.113386 0.98727 + outer loop + vertex 1.05928 1.71411 2.61063 + vertex 1.06405 1.71371 2.61014 + vertex 1.05904 1.71867 2.61014 + endloop + endfacet + facet normal 0.108689 0.110505 0.987915 + outer loop + vertex 1.05904 1.71867 2.61014 + vertex 1.06405 1.71371 2.61014 + vertex 1.0643 1.71859 2.60957 + endloop + endfacet + facet normal 0.108651 0.102405 0.988791 + outer loop + vertex 1.0643 1.71859 2.60957 + vertex 1.06346 1.72258 2.60925 + vertex 1.05904 1.71867 2.61014 + endloop + endfacet + facet normal 0.105632 0.105816 0.988759 + outer loop + vertex 1.05904 1.71867 2.61014 + vertex 1.06346 1.72258 2.60925 + vertex 1.05927 1.72359 2.60959 + endloop + endfacet + facet normal 0.101493 0.106062 0.989166 + outer loop + vertex 1.054 1.72367 2.61012 + vertex 1.05904 1.71867 2.61014 + vertex 1.05927 1.72359 2.60959 + endloop + endfacet + facet normal 0.10145 0.099013 0.989901 + outer loop + vertex 1.05927 1.72359 2.60959 + vertex 1.05839 1.72756 2.60928 + vertex 1.054 1.72367 2.61012 + endloop + endfacet + facet normal 0.101801 0.0990878 0.989858 + outer loop + vertex 1.05927 1.72359 2.60959 + vertex 1.06328 1.72725 2.60881 + vertex 1.05839 1.72756 2.60928 + endloop + endfacet + facet normal 0.103629 0.0970911 0.989866 + outer loop + vertex 1.06346 1.72258 2.60925 + vertex 1.06328 1.72725 2.60881 + vertex 1.05927 1.72359 2.60959 + endloop + endfacet + facet normal 0.105455 0.0971417 0.989668 + outer loop + vertex 1.06346 1.72258 2.60925 + vertex 1.06827 1.72712 2.60829 + vertex 1.06328 1.72725 2.60881 + endloop + endfacet + facet normal 0.107656 0.0948069 0.989657 + outer loop + vertex 1.06833 1.72223 2.60875 + vertex 1.06827 1.72712 2.60829 + vertex 1.06346 1.72258 2.60925 + endloop + endfacet + facet normal 0.101008 0.0948025 0.990359 + outer loop + vertex 1.06833 1.72223 2.60875 + vertex 1.07331 1.7271 2.60777 + vertex 1.06827 1.72712 2.60829 + endloop + endfacet + facet normal 0.0994083 0.0964403 0.990362 + outer loop + vertex 1.07329 1.72206 2.60827 + vertex 1.07331 1.7271 2.60777 + vertex 1.06833 1.72223 2.60875 + endloop + endfacet + facet normal 0.108113 0.102298 0.988861 + outer loop + vertex 1.0643 1.71859 2.60957 + vertex 1.06833 1.72223 2.60875 + vertex 1.06346 1.72258 2.60925 + endloop + endfacet + facet normal 0.10899 0.10133 0.988865 + outer loop + vertex 1.06844 1.71755 2.60922 + vertex 1.06833 1.72223 2.60875 + vertex 1.0643 1.71859 2.60957 + endloop + endfacet + facet normal 0.111709 0.115744 0.986977 + outer loop + vertex 1.05928 1.71411 2.61063 + vertex 1.06115 1.711 2.61079 + vertex 1.06405 1.71371 2.61014 + endloop + endfacet + facet normal 0.11256 0.114837 0.986987 + outer loop + vertex 1.06429 1.70918 2.61064 + vertex 1.06405 1.71371 2.61014 + vertex 1.06115 1.711 2.61079 + endloop + endfacet + facet normal 0.10889 0.108425 0.988123 + outer loop + vertex 1.06115 1.711 2.61079 + vertex 1.06162 1.70629 2.61125 + vertex 1.06429 1.70918 2.61064 + endloop + endfacet + facet normal 0.108376 0.1089 0.988127 + outer loop + vertex 1.06612 1.70607 2.61078 + vertex 1.06429 1.70918 2.61064 + vertex 1.06162 1.70629 2.61125 + endloop + endfacet + facet normal 0.108466 0.111241 0.987857 + outer loop + vertex 1.06612 1.70607 2.61078 + vertex 1.06162 1.70629 2.61125 + vertex 1.06661 1.70138 2.61126 + endloop + endfacet + facet normal 0.106647 0.111073 0.988073 + outer loop + vertex 1.06612 1.70607 2.61078 + vertex 1.06661 1.70138 2.61126 + vertex 1.06927 1.70423 2.61065 + endloop + endfacet + facet normal 0.108353 0.114034 0.98755 + outer loop + vertex 1.06927 1.70423 2.61065 + vertex 1.06903 1.70873 2.61016 + vertex 1.06612 1.70607 2.61078 + endloop + endfacet + facet normal 0.102227 0.115198 0.988068 + outer loop + vertex 1.07116 1.70112 2.61082 + vertex 1.06927 1.70423 2.61065 + vertex 1.06661 1.70138 2.61126 + endloop + endfacet + facet normal 0.104634 0.107358 0.988699 + outer loop + vertex 1.06162 1.70629 2.61125 + vertex 1.06179 1.70113 2.61179 + vertex 1.06661 1.70138 2.61126 + endloop + endfacet + facet normal 0.104699 0.106297 0.988807 + outer loop + vertex 1.06285 1.69705 2.61212 + vertex 1.06661 1.70138 2.61126 + vertex 1.06179 1.70113 2.61179 + endloop + endfacet + facet normal 0.0997819 0.105081 0.989445 + outer loop + vertex 1.06285 1.69705 2.61212 + vertex 1.06179 1.70113 2.61179 + vertex 1.0582 1.69717 2.61258 + endloop + endfacet + facet normal 0.0997801 0.104963 0.989458 + outer loop + vertex 1.05834 1.69224 2.61309 + vertex 1.06285 1.69705 2.61212 + vertex 1.0582 1.69717 2.61258 + endloop + endfacet + facet normal 0.0964563 0.104906 0.989793 + outer loop + vertex 1.05834 1.69224 2.61309 + vertex 1.0582 1.69717 2.61258 + vertex 1.05332 1.69222 2.61358 + endloop + endfacet + facet normal 0.0964695 0.103875 0.989901 + outer loop + vertex 1.05335 1.68737 2.61408 + vertex 1.05834 1.69224 2.61309 + vertex 1.05332 1.69222 2.61358 + endloop + endfacet + facet normal 0.095323 0.103879 0.990011 + outer loop + vertex 1.05335 1.68737 2.61408 + vertex 1.05332 1.69222 2.61358 + vertex 1.04856 1.68777 2.6145 + endloop + endfacet + facet normal 0.0950823 0.100631 0.99037 + outer loop + vertex 1.04939 1.68379 2.61483 + vertex 1.05335 1.68737 2.61408 + vertex 1.04856 1.68777 2.6145 + endloop + endfacet + facet normal 0.0932024 0.102702 0.990336 + outer loop + vertex 1.05349 1.6827 2.61455 + vertex 1.05335 1.68737 2.61408 + vertex 1.04939 1.68379 2.61483 + endloop + endfacet + facet normal 0.0918874 0.0975944 0.990975 + outer loop + vertex 1.0492 1.67893 2.61532 + vertex 1.05349 1.6827 2.61455 + vertex 1.04939 1.68379 2.61483 + endloop + endfacet + facet normal 0.0970004 0.0973521 0.990512 + outer loop + vertex 1.04437 1.68397 2.6153 + vertex 1.0492 1.67893 2.61532 + vertex 1.04939 1.68379 2.61483 + endloop + endfacet + facet normal 0.0892697 0.100561 0.990918 + outer loop + vertex 1.0544 1.67873 2.61487 + vertex 1.05349 1.6827 2.61455 + vertex 1.0492 1.67893 2.61532 + endloop + endfacet + facet normal 0.0891734 0.0971948 0.991262 + outer loop + vertex 1.0492 1.67893 2.61532 + vertex 1.05424 1.67389 2.61536 + vertex 1.0544 1.67873 2.61487 + endloop + endfacet + facet normal 0.0933729 0.0970211 0.990893 + outer loop + vertex 1.05424 1.67389 2.61536 + vertex 1.05853 1.67768 2.61459 + vertex 1.0544 1.67873 2.61487 + endloop + endfacet + facet normal 0.0944432 0.10137 0.990356 + outer loop + vertex 1.05853 1.67768 2.61459 + vertex 1.05835 1.68234 2.61413 + vertex 1.0544 1.67873 2.61487 + endloop + endfacet + facet normal 0.0985973 0.10149 0.989939 + outer loop + vertex 1.05853 1.67768 2.61459 + vertex 1.06329 1.6822 2.61365 + vertex 1.05835 1.68234 2.61413 + endloop + endfacet + facet normal 0.0986408 0.103992 0.989675 + outer loop + vertex 1.06329 1.6822 2.61365 + vertex 1.06331 1.68724 2.61312 + vertex 1.05835 1.68234 2.61413 + endloop + endfacet + facet normal 0.0986762 0.103956 0.989675 + outer loop + vertex 1.05835 1.68234 2.61413 + vertex 1.06331 1.68724 2.61312 + vertex 1.0583 1.68721 2.61362 + endloop + endfacet + facet normal 0.0943493 0.103953 0.990097 + outer loop + vertex 1.05835 1.68234 2.61413 + vertex 1.0583 1.68721 2.61362 + vertex 1.05349 1.6827 2.61455 + endloop + endfacet + facet normal 0.0986533 0.105314 0.989533 + outer loop + vertex 1.06331 1.68724 2.61312 + vertex 1.06317 1.6922 2.6126 + vertex 1.0583 1.68721 2.61362 + endloop + endfacet + facet normal 0.0992145 0.104767 0.989535 + outer loop + vertex 1.0583 1.68721 2.61362 + vertex 1.06317 1.6922 2.6126 + vertex 1.05834 1.69224 2.61309 + endloop + endfacet + facet normal 0.100392 0.105345 0.989355 + outer loop + vertex 1.06331 1.68724 2.61312 + vertex 1.06781 1.69208 2.61215 + vertex 1.06317 1.6922 2.6126 + endloop + endfacet + facet normal 0.100416 0.106876 0.989189 + outer loop + vertex 1.06781 1.69208 2.61215 + vertex 1.06676 1.69619 2.61181 + vertex 1.06317 1.6922 2.6126 + endloop + endfacet + facet normal 0.101789 0.105638 0.989181 + outer loop + vertex 1.06317 1.6922 2.6126 + vertex 1.06676 1.69619 2.61181 + vertex 1.06285 1.69705 2.61212 + endloop + endfacet + facet normal 0.0950364 0.105554 0.989862 + outer loop + vertex 1.06781 1.69208 2.61215 + vertex 1.07167 1.69641 2.61131 + vertex 1.06676 1.69619 2.61181 + endloop + endfacet + facet normal 0.0948896 0.108206 0.98959 + outer loop + vertex 1.06661 1.70138 2.61126 + vertex 1.06676 1.69619 2.61181 + vertex 1.07167 1.69641 2.61131 + endloop + endfacet + facet normal 0.0925836 0.107738 0.989859 + outer loop + vertex 1.07182 1.6912 2.61187 + vertex 1.07167 1.69641 2.61131 + vertex 1.06781 1.69208 2.61215 + endloop + endfacet + facet normal 0.0922531 0.10616 0.99006 + outer loop + vertex 1.06816 1.68721 2.61264 + vertex 1.07182 1.6912 2.61187 + vertex 1.06781 1.69208 2.61215 + endloop + endfacet + facet normal 0.089707 0.108486 0.990042 + outer loop + vertex 1.07291 1.68705 2.61222 + vertex 1.07182 1.6912 2.61187 + vertex 1.06816 1.68721 2.61264 + endloop + endfacet + facet normal 0.0896259 0.105016 0.990424 + outer loop + vertex 1.06833 1.68223 2.61315 + vertex 1.07291 1.68705 2.61222 + vertex 1.06816 1.68721 2.61264 + endloop + endfacet + facet normal 0.0978247 0.105209 0.989627 + outer loop + vertex 1.06833 1.68223 2.61315 + vertex 1.06816 1.68721 2.61264 + vertex 1.06329 1.6822 2.61365 + endloop + endfacet + facet normal 0.0978753 0.101727 0.989986 + outer loop + vertex 1.06336 1.67735 2.61414 + vertex 1.06833 1.68223 2.61315 + vertex 1.06329 1.6822 2.61365 + endloop + endfacet + facet normal 0.0962921 0.103337 0.989974 + outer loop + vertex 1.06831 1.67719 2.61368 + vertex 1.06833 1.68223 2.61315 + vertex 1.06336 1.67735 2.61414 + endloop + endfacet + facet normal 0.0961952 0.0990533 0.990422 + outer loop + vertex 1.0635 1.67276 2.61459 + vertex 1.06831 1.67719 2.61368 + vertex 1.06336 1.67735 2.61414 + endloop + endfacet + facet normal 0.0983641 0.0990982 0.990204 + outer loop + vertex 1.0635 1.67276 2.61459 + vertex 1.06336 1.67735 2.61414 + vertex 1.05941 1.67376 2.61489 + endloop + endfacet + facet normal 0.097797 0.0966964 0.990498 + outer loop + vertex 1.05917 1.66908 2.61537 + vertex 1.0635 1.67276 2.61459 + vertex 1.05941 1.67376 2.61489 + endloop + endfacet + facet normal 0.0924724 0.0970174 0.990978 + outer loop + vertex 1.05424 1.67389 2.61536 + vertex 1.05917 1.66908 2.61537 + vertex 1.05941 1.67376 2.61489 + endloop + endfacet + facet normal 0.0920516 0.0965859 0.991059 + outer loop + vertex 1.05457 1.66936 2.61577 + vertex 1.05917 1.66908 2.61537 + vertex 1.05424 1.67389 2.61536 + endloop + endfacet + facet normal 0.0866276 0.096239 0.991581 + outer loop + vertex 1.05457 1.66936 2.61577 + vertex 1.05424 1.67389 2.61536 + vertex 1.0514 1.67116 2.61588 + endloop + endfacet + facet normal 0.0857005 0.0945959 0.99182 + outer loop + vertex 1.0514 1.67116 2.61588 + vertex 1.05187 1.66643 2.61629 + vertex 1.05457 1.66936 2.61577 + endloop + endfacet + facet normal 0.0864629 0.0938957 0.99182 + outer loop + vertex 1.05642 1.66633 2.6159 + vertex 1.05457 1.66936 2.61577 + vertex 1.05187 1.66643 2.61629 + endloop + endfacet + facet normal 0.0864783 0.0949468 0.991719 + outer loop + vertex 1.05642 1.66633 2.6159 + vertex 1.05187 1.66643 2.61629 + vertex 1.05679 1.6617 2.61631 + endloop + endfacet + facet normal 0.0910596 0.0952825 0.991277 + outer loop + vertex 1.05642 1.66633 2.6159 + vertex 1.05679 1.6617 2.61631 + vertex 1.05941 1.66473 2.61578 + endloop + endfacet + facet normal 0.0921057 0.0972676 0.990987 + outer loop + vertex 1.05941 1.66473 2.61578 + vertex 1.05917 1.66908 2.61537 + vertex 1.05642 1.66633 2.6159 + endloop + endfacet + facet normal 0.0906234 0.0971996 0.99113 + outer loop + vertex 1.05941 1.66473 2.61578 + vertex 1.06362 1.66482 2.61539 + vertex 1.05917 1.66908 2.61537 + endloop + endfacet + facet normal 0.0953552 0.102136 0.99019 + outer loop + vertex 1.05917 1.66908 2.61537 + vertex 1.06362 1.66482 2.61539 + vertex 1.06425 1.66898 2.61489 + endloop + endfacet + facet normal 0.0906603 0.0959541 0.991248 + outer loop + vertex 1.05941 1.66473 2.61578 + vertex 1.06127 1.66183 2.61589 + vertex 1.06362 1.66482 2.61539 + endloop + endfacet + facet normal 0.0904428 0.0958157 0.991282 + outer loop + vertex 1.06127 1.66183 2.61589 + vertex 1.05941 1.66473 2.61578 + vertex 1.05679 1.6617 2.61631 + endloop + endfacet + facet normal 0.0903138 0.0992042 0.99096 + outer loop + vertex 1.06127 1.66183 2.61589 + vertex 1.05679 1.6617 2.61631 + vertex 1.06132 1.65744 2.61632 + endloop + endfacet + facet normal 0.0849976 0.0991846 0.991432 + outer loop + vertex 1.06127 1.66183 2.61589 + vertex 1.06132 1.65744 2.61632 + vertex 1.06513 1.6601 2.61573 + endloop + endfacet + facet normal 0.0827383 0.102397 0.991297 + outer loop + vertex 1.06683 1.65532 2.61608 + vertex 1.06513 1.6601 2.61573 + vertex 1.06132 1.65744 2.61632 + endloop + endfacet + facet normal 0.0801574 0.0955874 0.992188 + outer loop + vertex 1.06275 1.65224 2.61671 + vertex 1.06683 1.65532 2.61608 + vertex 1.06132 1.65744 2.61632 + endloop + endfacet + facet normal 0.0866366 0.0973151 0.991476 + outer loop + vertex 1.06275 1.65224 2.61671 + vertex 1.06132 1.65744 2.61632 + vertex 1.05807 1.65253 2.61709 + endloop + endfacet + facet normal 0.086469 0.0941938 0.991792 + outer loop + vertex 1.0585 1.64758 2.61752 + vertex 1.06275 1.65224 2.61671 + vertex 1.05807 1.65253 2.61709 + endloop + endfacet + facet normal 0.0842788 0.0940239 0.991996 + outer loop + vertex 1.0585 1.64758 2.61752 + vertex 1.05807 1.65253 2.61709 + vertex 1.05347 1.64737 2.61797 + endloop + endfacet + facet normal 0.0844096 0.0913564 0.992234 + outer loop + vertex 1.05333 1.6422 2.61846 + vertex 1.0585 1.64758 2.61752 + vertex 1.05347 1.64737 2.61797 + endloop + endfacet + facet normal 0.0807686 0.0914848 0.992526 + outer loop + vertex 1.05333 1.6422 2.61846 + vertex 1.05347 1.64737 2.61797 + vertex 1.04817 1.64209 2.61889 + endloop + endfacet + facet normal 0.0808526 0.088671 0.992774 + outer loop + vertex 1.04815 1.63724 2.61932 + vertex 1.05333 1.6422 2.61846 + vertex 1.04817 1.64209 2.61889 + endloop + endfacet + facet normal 0.0790193 0.0886902 0.99292 + outer loop + vertex 1.04815 1.63724 2.61932 + vertex 1.04817 1.64209 2.61889 + vertex 1.04339 1.63767 2.61966 + endloop + endfacet + facet normal 0.0787843 0.0858397 0.993189 + outer loop + vertex 1.04424 1.63372 2.61994 + vertex 1.04815 1.63724 2.61932 + vertex 1.04339 1.63767 2.61966 + endloop + endfacet + facet normal 0.0803493 0.0861659 0.993035 + outer loop + vertex 1.04424 1.63372 2.61994 + vertex 1.04339 1.63767 2.61966 + vertex 1.03929 1.63393 2.62032 + endloop + endfacet + facet normal 0.0802735 0.0840214 0.993225 + outer loop + vertex 1.03929 1.63393 2.62032 + vertex 1.04411 1.62893 2.62035 + vertex 1.04424 1.63372 2.61994 + endloop + endfacet + facet normal 0.0761118 0.0841673 0.993541 + outer loop + vertex 1.04411 1.62893 2.62035 + vertex 1.04831 1.63262 2.61972 + vertex 1.04424 1.63372 2.61994 + endloop + endfacet + facet normal 0.0740549 0.086499 0.993496 + outer loop + vertex 1.04924 1.62873 2.61999 + vertex 1.04831 1.63262 2.61972 + vertex 1.04411 1.62893 2.62035 + endloop + endfacet + facet normal 0.0739813 0.0841944 0.993699 + outer loop + vertex 1.04411 1.62893 2.62035 + vertex 1.04915 1.62397 2.6204 + vertex 1.04924 1.62873 2.61999 + endloop + endfacet + facet normal 0.078846 0.0840734 0.993335 + outer loop + vertex 1.04915 1.62397 2.6204 + vertex 1.05332 1.62765 2.61976 + vertex 1.04924 1.62873 2.61999 + endloop + endfacet + facet normal 0.079648 0.0871558 0.993006 + outer loop + vertex 1.05332 1.62765 2.61976 + vertex 1.05313 1.63225 2.61937 + vertex 1.04924 1.62873 2.61999 + endloop + endfacet + facet normal 0.0837323 0.0872919 0.992658 + outer loop + vertex 1.05332 1.62765 2.61976 + vertex 1.05813 1.63211 2.61896 + vertex 1.05313 1.63225 2.61937 + endloop + endfacet + facet normal 0.0837627 0.0888567 0.992516 + outer loop + vertex 1.05813 1.63211 2.61896 + vertex 1.05831 1.63723 2.61848 + vertex 1.05313 1.63225 2.61937 + endloop + endfacet + facet normal 0.0841295 0.0884759 0.992519 + outer loop + vertex 1.05313 1.63225 2.61937 + vertex 1.05831 1.63723 2.61848 + vertex 1.05314 1.6371 2.61893 + endloop + endfacet + facet normal 0.0792264 0.0885161 0.992919 + outer loop + vertex 1.05313 1.63225 2.61937 + vertex 1.05314 1.6371 2.61893 + vertex 1.04831 1.63262 2.61972 + endloop + endfacet + facet normal 0.0798713 0.0878215 0.992929 + outer loop + vertex 1.04831 1.63262 2.61972 + vertex 1.05314 1.6371 2.61893 + vertex 1.04815 1.63724 2.61932 + endloop + endfacet + facet normal 0.0840906 0.0896534 0.992417 + outer loop + vertex 1.05831 1.63723 2.61848 + vertex 1.05849 1.64243 2.618 + vertex 1.05314 1.6371 2.61893 + endloop + endfacet + facet normal 0.0842901 0.0894533 0.992418 + outer loop + vertex 1.05314 1.6371 2.61893 + vertex 1.05849 1.64243 2.618 + vertex 1.05333 1.6422 2.61846 + endloop + endfacet + facet normal 0.0852257 0.0896047 0.992324 + outer loop + vertex 1.05831 1.63723 2.61848 + vertex 1.06353 1.64258 2.61755 + vertex 1.05849 1.64243 2.618 + endloop + endfacet + facet normal 0.085129 0.0921999 0.992095 + outer loop + vertex 1.06353 1.64258 2.61755 + vertex 1.06327 1.64749 2.61712 + vertex 1.05849 1.64243 2.618 + endloop + endfacet + facet normal 0.0858013 0.0915645 0.992096 + outer loop + vertex 1.05849 1.64243 2.618 + vertex 1.06327 1.64749 2.61712 + vertex 1.0585 1.64758 2.61752 + endloop + endfacet + facet normal 0.078598 0.0919048 0.992661 + outer loop + vertex 1.06353 1.64258 2.61755 + vertex 1.06784 1.64718 2.61679 + vertex 1.06327 1.64749 2.61712 + endloop + endfacet + facet normal 0.0788083 0.0954448 0.99231 + outer loop + vertex 1.06784 1.64718 2.61679 + vertex 1.06669 1.65103 2.61651 + vertex 1.06327 1.64749 2.61712 + endloop + endfacet + facet normal 0.0801099 0.09419 0.992326 + outer loop + vertex 1.06327 1.64749 2.61712 + vertex 1.06669 1.65103 2.61651 + vertex 1.06275 1.65224 2.61671 + endloop + endfacet + facet normal 0.064169 0.0911921 0.993764 + outer loop + vertex 1.06784 1.64718 2.61679 + vertex 1.07151 1.65104 2.61619 + vertex 1.06669 1.65103 2.61651 + endloop + endfacet + facet normal 0.0641238 0.0958719 0.993326 + outer loop + vertex 1.06683 1.65532 2.61608 + vertex 1.06669 1.65103 2.61651 + vertex 1.07151 1.65104 2.61619 + endloop + endfacet + facet normal 0.0650379 0.0903681 0.993783 + outer loop + vertex 1.07175 1.6462 2.61662 + vertex 1.07151 1.65104 2.61619 + vertex 1.06784 1.64718 2.61679 + endloop + endfacet + facet normal 0.0654567 0.0920585 0.9936 + outer loop + vertex 1.06835 1.6425 2.61719 + vertex 1.07175 1.6462 2.61662 + vertex 1.06784 1.64718 2.61679 + endloop + endfacet + facet normal 0.0617634 0.0954363 0.993518 + outer loop + vertex 1.07293 1.64222 2.61693 + vertex 1.07175 1.6462 2.61662 + vertex 1.06835 1.6425 2.61719 + endloop + endfacet + facet normal 0.0617218 0.0946732 0.993593 + outer loop + vertex 1.06859 1.63755 2.61764 + vertex 1.07293 1.64222 2.61693 + vertex 1.06835 1.6425 2.61719 + endloop + endfacet + facet normal 0.0730041 0.0951479 0.992783 + outer loop + vertex 1.06859 1.63755 2.61764 + vertex 1.06835 1.6425 2.61719 + vertex 1.0635 1.63742 2.61803 + endloop + endfacet + facet normal 0.0731116 0.0918037 0.99309 + outer loop + vertex 1.06331 1.63221 2.61852 + vertex 1.06859 1.63755 2.61764 + vertex 1.0635 1.63742 2.61803 + endloop + endfacet + facet normal 0.0811841 0.0914639 0.992494 + outer loop + vertex 1.06331 1.63221 2.61852 + vertex 1.0635 1.63742 2.61803 + vertex 1.05813 1.63211 2.61896 + endloop + endfacet + facet normal 0.0812753 0.0879533 0.992803 + outer loop + vertex 1.05813 1.62726 2.61939 + vertex 1.06331 1.63221 2.61852 + vertex 1.05813 1.63211 2.61896 + endloop + endfacet + facet normal 0.0783884 0.0909698 0.992764 + outer loop + vertex 1.06314 1.62711 2.61901 + vertex 1.06331 1.63221 2.61852 + vertex 1.05813 1.62726 2.61939 + endloop + endfacet + facet normal 0.0683139 0.0965262 0.992983 + outer loop + vertex 1.06851 1.63239 2.61815 + vertex 1.06859 1.63755 2.61764 + vertex 1.06331 1.63221 2.61852 + endloop + endfacet + facet normal 0.0771223 0.0912202 0.99284 + outer loop + vertex 1.0635 1.63742 2.61803 + vertex 1.06835 1.6425 2.61719 + vertex 1.06353 1.64258 2.61755 + endloop + endfacet + facet normal 0.0592753 0.0969309 0.993524 + outer loop + vertex 1.07337 1.6375 2.61736 + vertex 1.07293 1.64222 2.61693 + vertex 1.06859 1.63755 2.61764 + endloop + endfacet + facet normal 0.0656363 0.0965587 0.993161 + outer loop + vertex 1.07293 1.64222 2.61693 + vertex 1.07655 1.64636 2.61629 + vertex 1.07175 1.6462 2.61662 + endloop + endfacet + facet normal 0.0771428 0.0932634 0.992648 + outer loop + vertex 1.06835 1.6425 2.61719 + vertex 1.06784 1.64718 2.61679 + vertex 1.06353 1.64258 2.61755 + endloop + endfacet + facet normal 0.0836638 0.091127 0.992319 + outer loop + vertex 1.0635 1.63742 2.61803 + vertex 1.06353 1.64258 2.61755 + vertex 1.05831 1.63723 2.61848 + endloop + endfacet + facet normal 0.0837662 0.0888565 0.992516 + outer loop + vertex 1.05813 1.63211 2.61896 + vertex 1.0635 1.63742 2.61803 + vertex 1.05831 1.63723 2.61848 + endloop + endfacet + facet normal 0.0831275 0.0879424 0.992651 + outer loop + vertex 1.05813 1.62726 2.61939 + vertex 1.05813 1.63211 2.61896 + vertex 1.05332 1.62765 2.61976 + endloop + endfacet + facet normal 0.0829685 0.0857655 0.992855 + outer loop + vertex 1.05426 1.62376 2.62001 + vertex 1.05813 1.62726 2.61939 + vertex 1.05332 1.62765 2.61976 + endloop + endfacet + facet normal 0.0828883 0.0858542 0.992854 + outer loop + vertex 1.05837 1.62269 2.61976 + vertex 1.05813 1.62726 2.61939 + vertex 1.05426 1.62376 2.62001 + endloop + endfacet + facet normal 0.0783155 0.0846726 0.993326 + outer loop + vertex 1.05426 1.62376 2.62001 + vertex 1.05332 1.62765 2.61976 + vertex 1.04915 1.62397 2.6204 + endloop + endfacet + facet normal 0.0782681 0.0832591 0.99345 + outer loop + vertex 1.04915 1.62397 2.6204 + vertex 1.05422 1.61901 2.62041 + vertex 1.05426 1.62376 2.62001 + endloop + endfacet + facet normal 0.0783681 0.0833613 0.993433 + outer loop + vertex 1.0495 1.61948 2.62075 + vertex 1.05422 1.61901 2.62041 + vertex 1.04915 1.62397 2.6204 + endloop + endfacet + facet normal 0.0712093 0.0828501 0.994015 + outer loop + vertex 1.0495 1.61948 2.62075 + vertex 1.04915 1.62397 2.6204 + vertex 1.04631 1.62129 2.62082 + endloop + endfacet + facet normal 0.0675444 0.0763899 0.994788 + outer loop + vertex 1.04631 1.62129 2.62082 + vertex 1.04681 1.61659 2.62115 + vertex 1.0495 1.61948 2.62075 + endloop + endfacet + facet normal 0.067885 0.0760733 0.994789 + outer loop + vertex 1.0514 1.61635 2.62086 + vertex 1.0495 1.61948 2.62075 + vertex 1.04681 1.61659 2.62115 + endloop + endfacet + facet normal 0.067853 0.0753829 0.994843 + outer loop + vertex 1.0514 1.61635 2.62086 + vertex 1.04681 1.61659 2.62115 + vertex 1.05187 1.61162 2.62118 + endloop + endfacet + facet normal 0.0755238 0.0761068 0.994235 + outer loop + vertex 1.0514 1.61635 2.62086 + vertex 1.05187 1.61162 2.62118 + vertex 1.05458 1.6145 2.62076 + endloop + endfacet + facet normal 0.0788042 0.0817764 0.99353 + outer loop + vertex 1.05458 1.6145 2.62076 + vertex 1.05422 1.61901 2.62041 + vertex 1.0514 1.61635 2.62086 + endloop + endfacet + facet normal 0.0755337 0.0760974 0.994235 + outer loop + vertex 1.05647 1.61134 2.62085 + vertex 1.05458 1.6145 2.62076 + vertex 1.05187 1.61162 2.62118 + endloop + endfacet + facet normal 0.0757296 0.07971 0.993937 + outer loop + vertex 1.05647 1.61134 2.62085 + vertex 1.05187 1.61162 2.62118 + vertex 1.05689 1.60661 2.6212 + endloop + endfacet + facet normal 0.0756061 0.0796998 0.993948 + outer loop + vertex 1.05647 1.61134 2.62085 + vertex 1.05689 1.60661 2.6212 + vertex 1.05966 1.60954 2.62076 + endloop + endfacet + facet normal 0.0757366 0.0799319 0.993919 + outer loop + vertex 1.05966 1.60954 2.62076 + vertex 1.05933 1.61405 2.62042 + vertex 1.05647 1.61134 2.62085 + endloop + endfacet + facet normal 0.0730749 0.0820905 0.993942 + outer loop + vertex 1.06149 1.60647 2.62088 + vertex 1.05966 1.60954 2.62076 + vertex 1.05689 1.60661 2.6212 + endloop + endfacet + facet normal 0.0731329 0.0845516 0.993732 + outer loop + vertex 1.06149 1.60647 2.62088 + vertex 1.05689 1.60661 2.6212 + vertex 1.0618 1.60181 2.62125 + endloop + endfacet + facet normal 0.0537573 0.0833748 0.995067 + outer loop + vertex 1.06149 1.60647 2.62088 + vertex 1.0618 1.60181 2.62125 + vertex 1.0646 1.60494 2.62084 + endloop + endfacet + facet normal 0.0512949 0.078383 0.995603 + outer loop + vertex 1.0646 1.60494 2.62084 + vertex 1.06439 1.60934 2.6205 + vertex 1.06149 1.60647 2.62088 + endloop + endfacet + facet normal 0.0330073 0.0775653 0.996441 + outer loop + vertex 1.0646 1.60494 2.62084 + vertex 1.06898 1.6052 2.62067 + vertex 1.06439 1.60934 2.6205 + endloop + endfacet + facet normal 0.0328433 0.0802015 0.996237 + outer loop + vertex 1.0646 1.60494 2.62084 + vertex 1.06651 1.60203 2.62101 + vertex 1.06898 1.6052 2.62067 + endloop + endfacet + facet normal 0.0469539 0.089436 0.994885 + outer loop + vertex 1.06651 1.60203 2.62101 + vertex 1.0646 1.60494 2.62084 + vertex 1.0618 1.60181 2.62125 + endloop + endfacet + facet normal 0.0474868 0.0792826 0.99572 + outer loop + vertex 1.06651 1.60203 2.62101 + vertex 1.0618 1.60181 2.62125 + vertex 1.06646 1.59753 2.62137 + endloop + endfacet + facet normal 0.028337 0.079589 0.996425 + outer loop + vertex 1.06651 1.60203 2.62101 + vertex 1.06646 1.59753 2.62137 + vertex 1.07059 1.60044 2.62102 + endloop + endfacet + facet normal 0.0312059 0.0755395 0.996654 + outer loop + vertex 1.07227 1.59559 2.62133 + vertex 1.07059 1.60044 2.62102 + vertex 1.06646 1.59753 2.62137 + endloop + endfacet + facet normal 0.0293952 0.0701198 0.997105 + outer loop + vertex 1.06783 1.59223 2.6217 + vertex 1.07227 1.59559 2.62133 + vertex 1.06646 1.59753 2.62137 + endloop + endfacet + facet normal 0.045433 0.0742384 0.996205 + outer loop + vertex 1.06783 1.59223 2.6217 + vertex 1.06646 1.59753 2.62137 + vertex 1.06303 1.59264 2.62189 + endloop + endfacet + facet normal 0.0452456 0.0719335 0.996383 + outer loop + vertex 1.06353 1.58776 2.62222 + vertex 1.06783 1.59223 2.6217 + vertex 1.06303 1.59264 2.62189 + endloop + endfacet + facet normal 0.0620225 0.0735841 0.995359 + outer loop + vertex 1.06353 1.58776 2.62222 + vertex 1.06303 1.59264 2.62189 + vertex 1.05861 1.58778 2.62252 + endloop + endfacet + facet normal 0.0620225 0.070074 0.995612 + outer loop + vertex 1.05858 1.58271 2.62288 + vertex 1.06353 1.58776 2.62222 + vertex 1.05861 1.58778 2.62252 + endloop + endfacet + facet normal 0.0647523 0.0700495 0.99544 + outer loop + vertex 1.05858 1.58271 2.62288 + vertex 1.05861 1.58778 2.62252 + vertex 1.05349 1.58254 2.62322 + endloop + endfacet + facet normal 0.0649158 0.0657806 0.99572 + outer loop + vertex 1.05332 1.57741 2.62358 + vertex 1.05858 1.58271 2.62288 + vertex 1.05349 1.58254 2.62322 + endloop + endfacet + facet normal 0.058585 0.0660214 0.996097 + outer loop + vertex 1.05332 1.57741 2.62358 + vertex 1.05349 1.58254 2.62322 + vertex 1.04816 1.57719 2.62389 + endloop + endfacet + facet normal 0.0588017 0.0613094 0.996385 + outer loop + vertex 1.04804 1.57211 2.62421 + vertex 1.05332 1.57741 2.62358 + vertex 1.04816 1.57719 2.62389 + endloop + endfacet + facet normal 0.053353 0.0614541 0.996683 + outer loop + vertex 1.04804 1.57211 2.62421 + vertex 1.04816 1.57719 2.62389 + vertex 1.04298 1.57211 2.62448 + endloop + endfacet + facet normal 0.0533727 0.0561695 0.996994 + outer loop + vertex 1.04301 1.56719 2.62476 + vertex 1.04804 1.57211 2.62421 + vertex 1.04298 1.57211 2.62448 + endloop + endfacet + facet normal 0.0526118 0.0561674 0.997034 + outer loop + vertex 1.04301 1.56719 2.62476 + vertex 1.04298 1.57211 2.62448 + vertex 1.03826 1.56779 2.62498 + endloop + endfacet + facet normal 0.0518259 0.0498012 0.997414 + outer loop + vertex 1.03856 1.56305 2.6252 + vertex 1.04301 1.56719 2.62476 + vertex 1.03826 1.56779 2.62498 + endloop + endfacet + facet normal 0.0493434 0.0524601 0.997403 + outer loop + vertex 1.04319 1.56244 2.625 + vertex 1.04301 1.56719 2.62476 + vertex 1.03856 1.56305 2.6252 + endloop + endfacet + facet normal 0.0558013 0.0526827 0.997051 + outer loop + vertex 1.03826 1.56779 2.62498 + vertex 1.04298 1.57211 2.62448 + vertex 1.03821 1.57246 2.62473 + endloop + endfacet + facet normal 0.0602385 0.0527119 0.996791 + outer loop + vertex 1.03826 1.56779 2.62498 + vertex 1.03821 1.57246 2.62473 + vertex 1.03459 1.56909 2.62513 + endloop + endfacet + facet normal 0.0562342 0.0587923 0.996685 + outer loop + vertex 1.04298 1.57211 2.62448 + vertex 1.04302 1.57708 2.62419 + vertex 1.03821 1.57246 2.62473 + endloop + endfacet + facet normal 0.0602394 0.0546166 0.996689 + outer loop + vertex 1.03821 1.57246 2.62473 + vertex 1.04302 1.57708 2.62419 + vertex 1.03802 1.57722 2.62448 + endloop + endfacet + facet normal 0.0652413 0.0548008 0.996364 + outer loop + vertex 1.03821 1.57246 2.62473 + vertex 1.03802 1.57722 2.62448 + vertex 1.03372 1.57303 2.625 + endloop + endfacet + facet normal 0.0604023 0.0608405 0.996318 + outer loop + vertex 1.04302 1.57708 2.62419 + vertex 1.04312 1.58212 2.62387 + vertex 1.03802 1.57722 2.62448 + endloop + endfacet + facet normal 0.0634286 0.0576915 0.996317 + outer loop + vertex 1.03802 1.57722 2.62448 + vertex 1.04312 1.58212 2.62387 + vertex 1.03799 1.58218 2.6242 + endloop + endfacet + facet normal 0.0703411 0.0577163 0.995852 + outer loop + vertex 1.03802 1.57722 2.62448 + vertex 1.03799 1.58218 2.6242 + vertex 1.0332 1.57788 2.62478 + endloop + endfacet + facet normal 0.0693921 0.0505332 0.996309 + outer loop + vertex 1.03372 1.57303 2.625 + vertex 1.03802 1.57722 2.62448 + vertex 1.0332 1.57788 2.62478 + endloop + endfacet + facet normal 0.0634769 0.063919 0.995934 + outer loop + vertex 1.04312 1.58212 2.62387 + vertex 1.04328 1.58723 2.62354 + vertex 1.03799 1.58218 2.6242 + endloop + endfacet + facet normal 0.0653521 0.0619552 0.995937 + outer loop + vertex 1.03799 1.58218 2.6242 + vertex 1.04328 1.58723 2.62354 + vertex 1.03809 1.58716 2.62388 + endloop + endfacet + facet normal 0.0730322 0.0617665 0.995415 + outer loop + vertex 1.03799 1.58218 2.6242 + vertex 1.03809 1.58716 2.62388 + vertex 1.03316 1.58274 2.62452 + endloop + endfacet + facet normal 0.0750348 0.0595306 0.995402 + outer loop + vertex 1.03316 1.58274 2.62452 + vertex 1.03809 1.58716 2.62388 + vertex 1.03323 1.58743 2.62423 + endloop + endfacet + facet normal 0.0753475 0.0656313 0.994995 + outer loop + vertex 1.03809 1.58716 2.62388 + vertex 1.03823 1.59219 2.62354 + vertex 1.03323 1.58743 2.62423 + endloop + endfacet + facet normal 0.0787025 0.0621073 0.994962 + outer loop + vertex 1.03323 1.58743 2.62423 + vertex 1.03823 1.59219 2.62354 + vertex 1.0331 1.59222 2.62394 + endloop + endfacet + facet normal 0.0891883 0.0623471 0.994062 + outer loop + vertex 1.03323 1.58743 2.62423 + vertex 1.0331 1.59222 2.62394 + vertex 1.02864 1.58788 2.62462 + endloop + endfacet + facet normal 0.0787006 0.0686467 0.994532 + outer loop + vertex 1.03823 1.59219 2.62354 + vertex 1.03836 1.5973 2.62318 + vertex 1.0331 1.59222 2.62394 + endloop + endfacet + facet normal 0.0828466 0.0643487 0.994483 + outer loop + vertex 1.0331 1.59222 2.62394 + vertex 1.03836 1.5973 2.62318 + vertex 1.03314 1.59725 2.62361 + endloop + endfacet + facet normal 0.0827609 0.0702823 0.994088 + outer loop + vertex 1.03836 1.5973 2.62318 + vertex 1.03851 1.60246 2.6228 + vertex 1.03314 1.59725 2.62361 + endloop + endfacet + facet normal 0.0722052 0.0706412 0.994885 + outer loop + vertex 1.03836 1.5973 2.62318 + vertex 1.04364 1.60265 2.62241 + vertex 1.03851 1.60246 2.6228 + endloop + endfacet + facet normal 0.0720341 0.0746444 0.994605 + outer loop + vertex 1.04364 1.60265 2.62241 + vertex 1.04344 1.60757 2.62206 + vertex 1.03851 1.60246 2.6228 + endloop + endfacet + facet normal 0.0745753 0.0721904 0.994599 + outer loop + vertex 1.03851 1.60246 2.6228 + vertex 1.04344 1.60757 2.62206 + vertex 1.03856 1.60754 2.62243 + endloop + endfacet + facet normal 0.0860724 0.0720012 0.993684 + outer loop + vertex 1.03851 1.60246 2.6228 + vertex 1.03856 1.60754 2.62243 + vertex 1.03333 1.60234 2.62326 + endloop + endfacet + facet normal 0.0745414 0.0755776 0.99435 + outer loop + vertex 1.04344 1.60757 2.62206 + vertex 1.04304 1.61233 2.62173 + vertex 1.03856 1.60754 2.62243 + endloop + endfacet + facet normal 0.0761691 0.074053 0.994341 + outer loop + vertex 1.03856 1.60754 2.62243 + vertex 1.04304 1.61233 2.62173 + vertex 1.03838 1.61245 2.62207 + endloop + endfacet + facet normal 0.0893161 0.0744624 0.993216 + outer loop + vertex 1.03856 1.60754 2.62243 + vertex 1.03838 1.61245 2.62207 + vertex 1.03349 1.60742 2.62289 + endloop + endfacet + facet normal 0.0762361 0.0774323 0.994079 + outer loop + vertex 1.04304 1.61233 2.62173 + vertex 1.04193 1.61636 2.6215 + vertex 1.03838 1.61245 2.62207 + endloop + endfacet + facet normal 0.0791221 0.07481 0.994054 + outer loop + vertex 1.03838 1.61245 2.62207 + vertex 1.04193 1.61636 2.6215 + vertex 1.03794 1.61718 2.62175 + endloop + endfacet + facet normal 0.0928846 0.0760168 0.992771 + outer loop + vertex 1.03838 1.61245 2.62207 + vertex 1.03794 1.61718 2.62175 + vertex 1.0335 1.61246 2.62253 + endloop + endfacet + facet normal 0.0959403 0.0731326 0.992697 + outer loop + vertex 1.0335 1.61246 2.62253 + vertex 1.03794 1.61718 2.62175 + vertex 1.03327 1.61735 2.62219 + endloop + endfacet + facet normal 0.0960947 0.0785123 0.992271 + outer loop + vertex 1.03794 1.61718 2.62175 + vertex 1.0368 1.62122 2.62154 + vertex 1.03327 1.61735 2.62219 + endloop + endfacet + facet normal 0.0803548 0.0741928 0.994001 + outer loop + vertex 1.03794 1.61718 2.62175 + vertex 1.04171 1.62148 2.62113 + vertex 1.0368 1.62122 2.62154 + endloop + endfacet + facet normal 0.0802897 0.0752759 0.993925 + outer loop + vertex 1.03663 1.62639 2.62117 + vertex 1.0368 1.62122 2.62154 + vertex 1.04171 1.62148 2.62113 + endloop + endfacet + facet normal 0.085576 0.0807675 0.993053 + outer loop + vertex 1.04122 1.62623 2.62078 + vertex 1.03663 1.62639 2.62117 + vertex 1.04171 1.62148 2.62113 + endloop + endfacet + facet normal 0.0706654 0.0793134 0.994342 + outer loop + vertex 1.04122 1.62623 2.62078 + vertex 1.04171 1.62148 2.62113 + vertex 1.04441 1.6244 2.6207 + endloop + endfacet + facet normal 0.0719457 0.081561 0.994068 + outer loop + vertex 1.04441 1.6244 2.6207 + vertex 1.04411 1.62893 2.62035 + vertex 1.04122 1.62623 2.62078 + endloop + endfacet + facet normal 0.0743301 0.0790213 0.994098 + outer loop + vertex 1.03938 1.62939 2.62067 + vertex 1.04122 1.62623 2.62078 + vertex 1.04411 1.62893 2.62035 + endloop + endfacet + facet normal 0.0688231 0.0810108 0.994334 + outer loop + vertex 1.04631 1.62129 2.62082 + vertex 1.04441 1.6244 2.6207 + vertex 1.04171 1.62148 2.62113 + endloop + endfacet + facet normal 0.0857086 0.0855883 0.992637 + outer loop + vertex 1.04122 1.62623 2.62078 + vertex 1.03938 1.62939 2.62067 + vertex 1.03663 1.62639 2.62117 + endloop + endfacet + facet normal 0.0899887 0.0816497 0.99259 + outer loop + vertex 1.03631 1.63122 2.6208 + vertex 1.03663 1.62639 2.62117 + vertex 1.03938 1.62939 2.62067 + endloop + endfacet + facet normal 0.088096 0.0784388 0.993019 + outer loop + vertex 1.03938 1.62939 2.62067 + vertex 1.03929 1.63393 2.62032 + vertex 1.03631 1.63122 2.6208 + endloop + endfacet + facet normal 0.0916297 0.0745605 0.992998 + outer loop + vertex 1.03475 1.63437 2.62071 + vertex 1.03631 1.63122 2.6208 + vertex 1.03929 1.63393 2.62032 + endloop + endfacet + facet normal 0.0917294 0.0756751 0.992904 + outer loop + vertex 1.03475 1.63437 2.62071 + vertex 1.03929 1.63393 2.62032 + vertex 1.03513 1.63862 2.62035 + endloop + endfacet + facet normal 0.0978112 0.0810699 0.991897 + outer loop + vertex 1.03513 1.63862 2.62035 + vertex 1.03929 1.63393 2.62032 + vertex 1.03951 1.63879 2.6199 + endloop + endfacet + facet normal 0.0978198 0.0808836 0.991912 + outer loop + vertex 1.03951 1.63879 2.6199 + vertex 1.03847 1.64288 2.61967 + vertex 1.03513 1.63862 2.62035 + endloop + endfacet + facet normal 0.106648 0.0739071 0.991546 + outer loop + vertex 1.03513 1.63862 2.62035 + vertex 1.03847 1.64288 2.61967 + vertex 1.03345 1.64436 2.6201 + endloop + endfacet + facet normal 0.108624 0.0808695 0.990788 + outer loop + vertex 1.03847 1.64288 2.61967 + vertex 1.03833 1.64776 2.61929 + vertex 1.03345 1.64436 2.6201 + endloop + endfacet + facet normal 0.0968234 0.080608 0.992032 + outer loop + vertex 1.03847 1.64288 2.61967 + vertex 1.04323 1.64722 2.61885 + vertex 1.03833 1.64776 2.61929 + endloop + endfacet + facet normal 0.0975093 0.0873788 0.991391 + outer loop + vertex 1.04323 1.64722 2.61885 + vertex 1.0434 1.65228 2.61839 + vertex 1.03833 1.64776 2.61929 + endloop + endfacet + facet normal 0.101763 0.0826046 0.991373 + outer loop + vertex 1.03833 1.64776 2.61929 + vertex 1.0434 1.65228 2.61839 + vertex 1.03847 1.65255 2.61887 + endloop + endfacet + facet normal 0.10208 0.0894534 0.990746 + outer loop + vertex 1.0434 1.65228 2.61839 + vertex 1.04347 1.65731 2.61793 + vertex 1.03847 1.65255 2.61887 + endloop + endfacet + facet normal 0.106454 0.0848421 0.990691 + outer loop + vertex 1.03847 1.65255 2.61887 + vertex 1.04347 1.65731 2.61793 + vertex 1.03844 1.65742 2.61846 + endloop + endfacet + facet normal 0.10656 0.092432 0.990001 + outer loop + vertex 1.04347 1.65731 2.61793 + vertex 1.04327 1.6622 2.61749 + vertex 1.03844 1.65742 2.61846 + endloop + endfacet + facet normal 0.0961001 0.0921154 0.9911 + outer loop + vertex 1.04347 1.65731 2.61793 + vertex 1.04802 1.66204 2.61705 + vertex 1.04327 1.6622 2.61749 + endloop + endfacet + facet normal 0.0962161 0.096699 0.990652 + outer loop + vertex 1.04802 1.66204 2.61705 + vertex 1.04691 1.66612 2.61676 + vertex 1.04327 1.6622 2.61749 + endloop + endfacet + facet normal 0.0990537 0.0940646 0.990626 + outer loop + vertex 1.04327 1.6622 2.61749 + vertex 1.04691 1.66612 2.61676 + vertex 1.04286 1.66698 2.61708 + endloop + endfacet + facet normal 0.110372 0.0949363 0.989346 + outer loop + vertex 1.04327 1.6622 2.61749 + vertex 1.04286 1.66698 2.61708 + vertex 1.03842 1.66238 2.61802 + endloop + endfacet + facet normal 0.0991766 0.0946696 0.990556 + outer loop + vertex 1.04691 1.66612 2.61676 + vertex 1.04675 1.67137 2.61627 + vertex 1.04286 1.66698 2.61708 + endloop + endfacet + facet normal 0.100965 0.0930774 0.990526 + outer loop + vertex 1.04286 1.66698 2.61708 + vertex 1.04675 1.67137 2.61627 + vertex 1.04174 1.67106 2.61681 + endloop + endfacet + facet normal 0.0881021 0.0944427 0.991624 + outer loop + vertex 1.04675 1.67137 2.61627 + vertex 1.04691 1.66612 2.61676 + vertex 1.05187 1.66643 2.61629 + endloop + endfacet + facet normal 0.0880941 0.0945557 0.991614 + outer loop + vertex 1.04802 1.66204 2.61705 + vertex 1.05187 1.66643 2.61629 + vertex 1.04691 1.66612 2.61676 + endloop + endfacet + facet normal 0.0877745 0.0948364 0.991616 + outer loop + vertex 1.05202 1.66123 2.61677 + vertex 1.05187 1.66643 2.61629 + vertex 1.04802 1.66204 2.61705 + endloop + endfacet + facet normal 0.0876416 0.0941504 0.991693 + outer loop + vertex 1.04837 1.65722 2.61747 + vertex 1.05202 1.66123 2.61677 + vertex 1.04802 1.66204 2.61705 + endloop + endfacet + facet normal 0.0857913 0.0958342 0.991693 + outer loop + vertex 1.05305 1.65716 2.61707 + vertex 1.05202 1.66123 2.61677 + vertex 1.04837 1.65722 2.61747 + endloop + endfacet + facet normal 0.08578 0.0931802 0.991947 + outer loop + vertex 1.04847 1.65228 2.61793 + vertex 1.05305 1.65716 2.61707 + vertex 1.04837 1.65722 2.61747 + endloop + endfacet + facet normal 0.0899809 0.0932368 0.99157 + outer loop + vertex 1.04847 1.65228 2.61793 + vertex 1.04837 1.65722 2.61747 + vertex 1.0434 1.65228 2.61839 + endloop + endfacet + facet normal 0.083797 0.0950343 0.991941 + outer loop + vertex 1.05336 1.65235 2.61751 + vertex 1.05305 1.65716 2.61707 + vertex 1.04847 1.65228 2.61793 + endloop + endfacet + facet normal 0.0838715 0.0917065 0.992248 + outer loop + vertex 1.04834 1.64716 2.61841 + vertex 1.05336 1.65235 2.61751 + vertex 1.04847 1.65228 2.61793 + endloop + endfacet + facet normal 0.0862232 0.0916273 0.992053 + outer loop + vertex 1.04834 1.64716 2.61841 + vertex 1.04847 1.65228 2.61793 + vertex 1.04323 1.64722 2.61885 + endloop + endfacet + facet normal 0.0862078 0.0860708 0.992552 + outer loop + vertex 1.04324 1.64233 2.61928 + vertex 1.04834 1.64716 2.61841 + vertex 1.04323 1.64722 2.61885 + endloop + endfacet + facet normal 0.0823953 0.0900874 0.99252 + outer loop + vertex 1.04817 1.64209 2.61889 + vertex 1.04834 1.64716 2.61841 + vertex 1.04324 1.64233 2.61928 + endloop + endfacet + facet normal 0.0819902 0.0935249 0.992235 + outer loop + vertex 1.05347 1.64737 2.61797 + vertex 1.05336 1.65235 2.61751 + vertex 1.04834 1.64716 2.61841 + endloop + endfacet + facet normal 0.0848756 0.0950944 0.991843 + outer loop + vertex 1.05336 1.65235 2.61751 + vertex 1.0569 1.65654 2.6168 + vertex 1.05305 1.65716 2.61707 + endloop + endfacet + facet normal 0.0851429 0.0968344 0.991652 + outer loop + vertex 1.0569 1.65654 2.6168 + vertex 1.05679 1.6617 2.61631 + vertex 1.05305 1.65716 2.61707 + endloop + endfacet + facet normal 0.084711 0.0952335 0.991844 + outer loop + vertex 1.05807 1.65253 2.61709 + vertex 1.0569 1.65654 2.6168 + vertex 1.05336 1.65235 2.61751 + endloop + endfacet + facet normal 0.0862247 0.0959406 0.991645 + outer loop + vertex 1.05305 1.65716 2.61707 + vertex 1.05679 1.6617 2.61631 + vertex 1.05202 1.66123 2.61677 + endloop + endfacet + facet normal 0.0863458 0.094809 0.991744 + outer loop + vertex 1.05187 1.66643 2.61629 + vertex 1.05202 1.66123 2.61677 + vertex 1.05679 1.6617 2.61631 + endloop + endfacet + facet normal 0.0935926 0.0945301 0.991113 + outer loop + vertex 1.04837 1.65722 2.61747 + vertex 1.04802 1.66204 2.61705 + vertex 1.04347 1.65731 2.61793 + endloop + endfacet + facet normal 0.0935511 0.0896484 0.99157 + outer loop + vertex 1.0434 1.65228 2.61839 + vertex 1.04837 1.65722 2.61747 + vertex 1.04347 1.65731 2.61793 + endloop + endfacet + facet normal 0.0900244 0.0876881 0.992072 + outer loop + vertex 1.04323 1.64722 2.61885 + vertex 1.04847 1.65228 2.61793 + vertex 1.0434 1.65228 2.61839 + endloop + endfacet + facet normal 0.091874 0.0860402 0.992046 + outer loop + vertex 1.04324 1.64233 2.61928 + vertex 1.04323 1.64722 2.61885 + vertex 1.03847 1.64288 2.61967 + endloop + endfacet + facet normal 0.0911348 0.0792288 0.992682 + outer loop + vertex 1.03951 1.63879 2.6199 + vertex 1.04324 1.64233 2.61928 + vertex 1.03847 1.64288 2.61967 + endloop + endfacet + facet normal 0.0853214 0.08535 0.992691 + outer loop + vertex 1.04339 1.63767 2.61966 + vertex 1.04324 1.64233 2.61928 + vertex 1.03951 1.63879 2.6199 + endloop + endfacet + facet normal 0.113908 0.0854774 0.989807 + outer loop + vertex 1.03631 1.63122 2.6208 + vertex 1.03475 1.63437 2.62071 + vertex 1.03179 1.63127 2.62131 + endloop + endfacet + facet normal 0.113904 0.0830357 0.990016 + outer loop + vertex 1.03631 1.63122 2.6208 + vertex 1.03179 1.63127 2.62131 + vertex 1.03663 1.62639 2.62117 + endloop + endfacet + facet normal 0.106576 0.075736 0.991416 + outer loop + vertex 1.03179 1.63127 2.62131 + vertex 1.03166 1.62608 2.62172 + vertex 1.03663 1.62639 2.62117 + endloop + endfacet + facet normal 0.102505 0.0758797 0.991834 + outer loop + vertex 1.0368 1.62122 2.62154 + vertex 1.03663 1.62639 2.62117 + vertex 1.03278 1.62207 2.62189 + endloop + endfacet + facet normal 0.0792011 0.0752075 0.994018 + outer loop + vertex 1.04193 1.61636 2.6215 + vertex 1.04171 1.62148 2.62113 + vertex 1.03794 1.61718 2.62175 + endloop + endfacet + facet normal 0.0669776 0.0747553 0.99495 + outer loop + vertex 1.04171 1.62148 2.62113 + vertex 1.04193 1.61636 2.6215 + vertex 1.04681 1.61659 2.62115 + endloop + endfacet + facet normal 0.0669685 0.0749328 0.994937 + outer loop + vertex 1.04304 1.61233 2.62173 + vertex 1.04681 1.61659 2.62115 + vertex 1.04193 1.61636 2.6215 + endloop + endfacet + facet normal 0.0669454 0.0749533 0.994937 + outer loop + vertex 1.047 1.61147 2.62153 + vertex 1.04681 1.61659 2.62115 + vertex 1.04304 1.61233 2.62173 + endloop + endfacet + facet normal 0.0669508 0.0749787 0.994935 + outer loop + vertex 1.04344 1.60757 2.62206 + vertex 1.047 1.61147 2.62153 + vertex 1.04304 1.61233 2.62173 + endloop + endfacet + facet normal 0.0659481 0.0758922 0.994933 + outer loop + vertex 1.04808 1.6074 2.62176 + vertex 1.047 1.61147 2.62153 + vertex 1.04344 1.60757 2.62206 + endloop + endfacet + facet normal 0.067399 0.0762713 0.994807 + outer loop + vertex 1.04808 1.6074 2.62176 + vertex 1.05187 1.61162 2.62118 + vertex 1.047 1.61147 2.62153 + endloop + endfacet + facet normal 0.0665033 0.0770744 0.994805 + outer loop + vertex 1.05201 1.60645 2.62157 + vertex 1.05187 1.61162 2.62118 + vertex 1.04808 1.6074 2.62176 + endloop + endfacet + facet normal 0.0662027 0.075794 0.994923 + outer loop + vertex 1.04849 1.60262 2.6221 + vertex 1.05201 1.60645 2.62157 + vertex 1.04808 1.6074 2.62176 + endloop + endfacet + facet normal 0.0645837 0.0756619 0.99504 + outer loop + vertex 1.04849 1.60262 2.6221 + vertex 1.04808 1.6074 2.62176 + vertex 1.04364 1.60265 2.62241 + endloop + endfacet + facet normal 0.0645819 0.0734173 0.995208 + outer loop + vertex 1.04361 1.59754 2.62279 + vertex 1.04849 1.60262 2.6221 + vertex 1.04364 1.60265 2.62241 + endloop + endfacet + facet normal 0.0630281 0.0749107 0.995196 + outer loop + vertex 1.0487 1.5977 2.62246 + vertex 1.04849 1.60262 2.6221 + vertex 1.04361 1.59754 2.62279 + endloop + endfacet + facet normal 0.0631491 0.0715262 0.995438 + outer loop + vertex 1.04347 1.59238 2.62317 + vertex 1.0487 1.5977 2.62246 + vertex 1.04361 1.59754 2.62279 + endloop + endfacet + facet normal 0.0672269 0.0713946 0.99518 + outer loop + vertex 1.04347 1.59238 2.62317 + vertex 1.04361 1.59754 2.62279 + vertex 1.03823 1.59219 2.62354 + endloop + endfacet + facet normal 0.0617724 0.0728818 0.995426 + outer loop + vertex 1.04867 1.5926 2.62283 + vertex 1.0487 1.5977 2.62246 + vertex 1.04347 1.59238 2.62317 + endloop + endfacet + facet normal 0.0619841 0.068303 0.995737 + outer loop + vertex 1.04328 1.58723 2.62354 + vertex 1.04867 1.5926 2.62283 + vertex 1.04347 1.59238 2.62317 + endloop + endfacet + facet normal 0.0607248 0.0695666 0.995727 + outer loop + vertex 1.04852 1.58745 2.6232 + vertex 1.04867 1.5926 2.62283 + vertex 1.04328 1.58723 2.62354 + endloop + endfacet + facet normal 0.0640639 0.0694544 0.995526 + outer loop + vertex 1.04852 1.58745 2.6232 + vertex 1.05368 1.59271 2.6225 + vertex 1.04867 1.5926 2.62283 + endloop + endfacet + facet normal 0.0639597 0.0735598 0.995238 + outer loop + vertex 1.05368 1.59271 2.6225 + vertex 1.05349 1.59759 2.62215 + vertex 1.04867 1.5926 2.62283 + endloop + endfacet + facet normal 0.0698744 0.07376 0.994825 + outer loop + vertex 1.05368 1.59271 2.6225 + vertex 1.05802 1.59738 2.62185 + vertex 1.05349 1.59759 2.62215 + endloop + endfacet + facet normal 0.0700001 0.0767079 0.994593 + outer loop + vertex 1.05802 1.59738 2.62185 + vertex 1.05698 1.60143 2.62161 + vertex 1.05349 1.59759 2.62215 + endloop + endfacet + facet normal 0.0703874 0.0763548 0.994593 + outer loop + vertex 1.05349 1.59759 2.62215 + vertex 1.05698 1.60143 2.62161 + vertex 1.05311 1.60238 2.62181 + endloop + endfacet + facet normal 0.06475 0.0759349 0.995008 + outer loop + vertex 1.05349 1.59759 2.62215 + vertex 1.05311 1.60238 2.62181 + vertex 1.0487 1.5977 2.62246 + endloop + endfacet + facet normal 0.0712399 0.0799011 0.994254 + outer loop + vertex 1.05698 1.60143 2.62161 + vertex 1.05689 1.60661 2.6212 + vertex 1.05311 1.60238 2.62181 + endloop + endfacet + facet normal 0.0732203 0.0781308 0.994251 + outer loop + vertex 1.05311 1.60238 2.62181 + vertex 1.05689 1.60661 2.6212 + vertex 1.05201 1.60645 2.62157 + endloop + endfacet + facet normal 0.0688356 0.076417 0.994697 + outer loop + vertex 1.05802 1.59738 2.62185 + vertex 1.0618 1.60181 2.62125 + vertex 1.05698 1.60143 2.62161 + endloop + endfacet + facet normal 0.0668231 0.0781367 0.994701 + outer loop + vertex 1.06182 1.59662 2.62166 + vertex 1.0618 1.60181 2.62125 + vertex 1.05802 1.59738 2.62185 + endloop + endfacet + facet normal 0.0662153 0.0750087 0.994982 + outer loop + vertex 1.0584 1.59265 2.62218 + vertex 1.06182 1.59662 2.62166 + vertex 1.05802 1.59738 2.62185 + endloop + endfacet + facet normal 0.0633315 0.0774937 0.994979 + outer loop + vertex 1.06303 1.59264 2.62189 + vertex 1.06182 1.59662 2.62166 + vertex 1.0584 1.59265 2.62218 + endloop + endfacet + facet normal 0.0683556 0.0751701 0.994825 + outer loop + vertex 1.0584 1.59265 2.62218 + vertex 1.05802 1.59738 2.62185 + vertex 1.05368 1.59271 2.6225 + endloop + endfacet + facet normal 0.0683266 0.0707972 0.995148 + outer loop + vertex 1.05364 1.58766 2.62286 + vertex 1.0584 1.59265 2.62218 + vertex 1.05368 1.59271 2.6225 + endloop + endfacet + facet normal 0.0665309 0.0725069 0.995146 + outer loop + vertex 1.05861 1.58778 2.62252 + vertex 1.0584 1.59265 2.62218 + vertex 1.05364 1.58766 2.62286 + endloop + endfacet + facet normal 0.062622 0.0708696 0.995518 + outer loop + vertex 1.05364 1.58766 2.62286 + vertex 1.05368 1.59271 2.6225 + vertex 1.04852 1.58745 2.6232 + endloop + endfacet + facet normal 0.0628224 0.066261 0.995823 + outer loop + vertex 1.04833 1.5823 2.62356 + vertex 1.05364 1.58766 2.62286 + vertex 1.04852 1.58745 2.6232 + endloop + endfacet + facet normal 0.0585803 0.0664374 0.996069 + outer loop + vertex 1.04833 1.5823 2.62356 + vertex 1.04852 1.58745 2.6232 + vertex 1.04312 1.58212 2.62387 + endloop + endfacet + facet normal 0.0606826 0.068383 0.995812 + outer loop + vertex 1.05349 1.58254 2.62322 + vertex 1.05364 1.58766 2.62286 + vertex 1.04833 1.5823 2.62356 + endloop + endfacet + facet normal 0.0646965 0.0728493 0.995242 + outer loop + vertex 1.04867 1.5926 2.62283 + vertex 1.05349 1.59759 2.62215 + vertex 1.0487 1.5977 2.62246 + endloop + endfacet + facet normal 0.0657305 0.0750127 0.995014 + outer loop + vertex 1.0487 1.5977 2.62246 + vertex 1.05311 1.60238 2.62181 + vertex 1.04849 1.60262 2.6221 + endloop + endfacet + facet normal 0.0657864 0.076176 0.994922 + outer loop + vertex 1.05311 1.60238 2.62181 + vertex 1.05201 1.60645 2.62157 + vertex 1.04849 1.60262 2.6221 + endloop + endfacet + facet normal 0.0659014 0.0744299 0.995046 + outer loop + vertex 1.04364 1.60265 2.62241 + vertex 1.04808 1.6074 2.62176 + vertex 1.04344 1.60757 2.62206 + endloop + endfacet + facet normal 0.0694476 0.0733625 0.994884 + outer loop + vertex 1.04361 1.59754 2.62279 + vertex 1.04364 1.60265 2.62241 + vertex 1.03836 1.5973 2.62318 + endloop + endfacet + facet normal 0.0696726 0.0689354 0.995185 + outer loop + vertex 1.03823 1.59219 2.62354 + vertex 1.04361 1.59754 2.62279 + vertex 1.03836 1.5973 2.62318 + endloop + endfacet + facet normal 0.0674566 0.0658867 0.995544 + outer loop + vertex 1.03809 1.58716 2.62388 + vertex 1.04347 1.59238 2.62317 + vertex 1.03823 1.59219 2.62354 + endloop + endfacet + facet normal 0.0652357 0.0681721 0.995538 + outer loop + vertex 1.04328 1.58723 2.62354 + vertex 1.04347 1.59238 2.62317 + vertex 1.03809 1.58716 2.62388 + endloop + endfacet + facet normal 0.0609809 0.0640079 0.996084 + outer loop + vertex 1.04312 1.58212 2.62387 + vertex 1.04852 1.58745 2.6232 + vertex 1.04328 1.58723 2.62354 + endloop + endfacet + facet normal 0.0587961 0.060876 0.996412 + outer loop + vertex 1.04302 1.57708 2.62419 + vertex 1.04833 1.5823 2.62356 + vertex 1.04312 1.58212 2.62387 + endloop + endfacet + facet normal 0.0558292 0.0638829 0.996395 + outer loop + vertex 1.04816 1.57719 2.62389 + vertex 1.04833 1.5823 2.62356 + vertex 1.04302 1.57708 2.62419 + endloop + endfacet + facet normal 0.0516496 0.0579332 0.996983 + outer loop + vertex 1.04799 1.56708 2.62451 + vertex 1.04804 1.57211 2.62421 + vertex 1.04301 1.56719 2.62476 + endloop + endfacet + facet normal 0.0559619 0.0587958 0.9967 + outer loop + vertex 1.04298 1.57211 2.62448 + vertex 1.04816 1.57719 2.62389 + vertex 1.04302 1.57708 2.62419 + endloop + endfacet + facet normal 0.0571283 0.0629752 0.996379 + outer loop + vertex 1.05317 1.57229 2.62391 + vertex 1.05332 1.57741 2.62358 + vertex 1.04804 1.57211 2.62421 + endloop + endfacet + facet normal 0.0609185 0.0636973 0.996108 + outer loop + vertex 1.04816 1.57719 2.62389 + vertex 1.05349 1.58254 2.62322 + vertex 1.04833 1.5823 2.62356 + endloop + endfacet + facet normal 0.062853 0.0678273 0.995715 + outer loop + vertex 1.05845 1.57759 2.62324 + vertex 1.05858 1.58271 2.62288 + vertex 1.05332 1.57741 2.62358 + endloop + endfacet + facet normal 0.0666618 0.0681863 0.995443 + outer loop + vertex 1.05349 1.58254 2.62322 + vertex 1.05861 1.58778 2.62252 + vertex 1.05364 1.58766 2.62286 + endloop + endfacet + facet normal 0.0602293 0.0718287 0.995597 + outer loop + vertex 1.06364 1.58275 2.62257 + vertex 1.06353 1.58776 2.62222 + vertex 1.05858 1.58271 2.62288 + endloop + endfacet + facet normal 0.0633418 0.0723841 0.995363 + outer loop + vertex 1.05861 1.58778 2.62252 + vertex 1.06303 1.59264 2.62189 + vertex 1.0584 1.59265 2.62218 + endloop + endfacet + facet normal 0.0462682 0.0709513 0.996406 + outer loop + vertex 1.06834 1.58747 2.62202 + vertex 1.06783 1.59223 2.6217 + vertex 1.06353 1.58776 2.62222 + endloop + endfacet + facet normal 0.0475322 0.0727679 0.996216 + outer loop + vertex 1.06303 1.59264 2.62189 + vertex 1.06646 1.59753 2.62137 + vertex 1.06182 1.59662 2.62166 + endloop + endfacet + facet normal 0.0464525 0.0781604 0.995858 + outer loop + vertex 1.0618 1.60181 2.62125 + vertex 1.06182 1.59662 2.62166 + vertex 1.06646 1.59753 2.62137 + endloop + endfacet + facet normal 0.0685438 0.079869 0.994446 + outer loop + vertex 1.05689 1.60661 2.6212 + vertex 1.05698 1.60143 2.62161 + vertex 1.0618 1.60181 2.62125 + endloop + endfacet + facet normal 0.0570535 0.0725726 0.99573 + outer loop + vertex 1.05966 1.60954 2.62076 + vertex 1.06149 1.60647 2.62088 + vertex 1.06439 1.60934 2.6205 + endloop + endfacet + facet normal 0.0732543 0.0772283 0.994319 + outer loop + vertex 1.05187 1.61162 2.62118 + vertex 1.05201 1.60645 2.62157 + vertex 1.05689 1.60661 2.6212 + endloop + endfacet + facet normal 0.0779888 0.0775601 0.993933 + outer loop + vertex 1.05458 1.6145 2.62076 + vertex 1.05647 1.61134 2.62085 + vertex 1.05933 1.61405 2.62042 + endloop + endfacet + facet normal 0.0674462 0.074969 0.994902 + outer loop + vertex 1.04681 1.61659 2.62115 + vertex 1.047 1.61147 2.62153 + vertex 1.05187 1.61162 2.62118 + endloop + endfacet + facet normal 0.0686574 0.0765014 0.994703 + outer loop + vertex 1.04631 1.62129 2.62082 + vertex 1.04171 1.62148 2.62113 + vertex 1.04681 1.61659 2.62115 + endloop + endfacet + facet normal 0.0714425 0.0826036 0.994018 + outer loop + vertex 1.04441 1.6244 2.6207 + vertex 1.04631 1.62129 2.62082 + vertex 1.04915 1.62397 2.6204 + endloop + endfacet + facet normal 0.0782733 0.0823402 0.993526 + outer loop + vertex 1.0495 1.61948 2.62075 + vertex 1.0514 1.61635 2.62086 + vertex 1.05422 1.61901 2.62041 + endloop + endfacet + facet normal 0.0713491 0.0815252 0.994114 + outer loop + vertex 1.04441 1.6244 2.6207 + vertex 1.04915 1.62397 2.6204 + vertex 1.04411 1.62893 2.62035 + endloop + endfacet + facet normal 0.0791674 0.0876876 0.992997 + outer loop + vertex 1.04924 1.62873 2.61999 + vertex 1.05313 1.63225 2.61937 + vertex 1.04831 1.63262 2.61972 + endloop + endfacet + facet normal 0.0742584 0.0782319 0.994166 + outer loop + vertex 1.03938 1.62939 2.62067 + vertex 1.04411 1.62893 2.62035 + vertex 1.03929 1.63393 2.62032 + endloop + endfacet + facet normal 0.0843197 0.0818052 0.993075 + outer loop + vertex 1.03929 1.63393 2.62032 + vertex 1.04339 1.63767 2.61966 + vertex 1.03951 1.63879 2.6199 + endloop + endfacet + facet normal 0.0770619 0.0877475 0.993158 + outer loop + vertex 1.04831 1.63262 2.61972 + vertex 1.04815 1.63724 2.61932 + vertex 1.04424 1.63372 2.61994 + endloop + endfacet + facet normal 0.0821925 0.0852698 0.992962 + outer loop + vertex 1.04339 1.63767 2.61966 + vertex 1.04817 1.64209 2.61889 + vertex 1.04324 1.64233 2.61928 + endloop + endfacet + facet normal 0.0799122 0.0896504 0.992762 + outer loop + vertex 1.05314 1.6371 2.61893 + vertex 1.05333 1.6422 2.61846 + vertex 1.04815 1.63724 2.61932 + endloop + endfacet + facet normal 0.0821527 0.0900975 0.992539 + outer loop + vertex 1.04817 1.64209 2.61889 + vertex 1.05347 1.64737 2.61797 + vertex 1.04834 1.64716 2.61841 + endloop + endfacet + facet normal 0.0841785 0.0915787 0.992233 + outer loop + vertex 1.05849 1.64243 2.618 + vertex 1.0585 1.64758 2.61752 + vertex 1.05333 1.6422 2.61846 + endloop + endfacet + facet normal 0.0847912 0.0935673 0.991996 + outer loop + vertex 1.05347 1.64737 2.61797 + vertex 1.05807 1.65253 2.61709 + vertex 1.05336 1.65235 2.61751 + endloop + endfacet + facet normal 0.085834 0.094772 0.991792 + outer loop + vertex 1.06327 1.64749 2.61712 + vertex 1.06275 1.65224 2.61671 + vertex 1.0585 1.64758 2.61752 + endloop + endfacet + facet normal 0.0882511 0.0962403 0.991438 + outer loop + vertex 1.05807 1.65253 2.61709 + vertex 1.06132 1.65744 2.61632 + vertex 1.0569 1.65654 2.6168 + endloop + endfacet + facet normal 0.0804263 0.0952336 0.992201 + outer loop + vertex 1.06669 1.65103 2.61651 + vertex 1.06683 1.65532 2.61608 + vertex 1.06275 1.65224 2.61671 + endloop + endfacet + facet normal 0.0881173 0.0968711 0.991389 + outer loop + vertex 1.05679 1.6617 2.61631 + vertex 1.0569 1.65654 2.6168 + vertex 1.06132 1.65744 2.61632 + endloop + endfacet + facet normal 0.0884965 0.0948514 0.99155 + outer loop + vertex 1.0514 1.67116 2.61588 + vertex 1.04675 1.67137 2.61627 + vertex 1.05187 1.66643 2.61629 + endloop + endfacet + facet normal 0.0885931 0.0975717 0.991277 + outer loop + vertex 1.0514 1.67116 2.61588 + vertex 1.04948 1.67433 2.61574 + vertex 1.04675 1.67137 2.61627 + endloop + endfacet + facet normal 0.0900673 0.0962147 0.991277 + outer loop + vertex 1.04628 1.6762 2.61584 + vertex 1.04675 1.67137 2.61627 + vertex 1.04948 1.67433 2.61574 + endloop + endfacet + facet normal 0.0890963 0.0945367 0.991526 + outer loop + vertex 1.04948 1.67433 2.61574 + vertex 1.0492 1.67893 2.61532 + vertex 1.04628 1.6762 2.61584 + endloop + endfacet + facet normal 0.0912098 0.0922738 0.991547 + outer loop + vertex 1.04444 1.6794 2.61572 + vertex 1.04628 1.6762 2.61584 + vertex 1.0492 1.67893 2.61532 + endloop + endfacet + facet normal 0.105454 0.0975728 0.989626 + outer loop + vertex 1.04628 1.6762 2.61584 + vertex 1.04164 1.67634 2.61633 + vertex 1.04675 1.67137 2.61627 + endloop + endfacet + facet normal 0.0865336 0.0963366 0.99158 + outer loop + vertex 1.04948 1.67433 2.61574 + vertex 1.0514 1.67116 2.61588 + vertex 1.05424 1.67389 2.61536 + endloop + endfacet + facet normal 0.0920881 0.0972853 0.990987 + outer loop + vertex 1.05457 1.66936 2.61577 + vertex 1.05642 1.66633 2.6159 + vertex 1.05917 1.66908 2.61537 + endloop + endfacet + facet normal 0.0953307 0.0995905 0.990451 + outer loop + vertex 1.06425 1.66898 2.61489 + vertex 1.0635 1.67276 2.61459 + vertex 1.05917 1.66908 2.61537 + endloop + endfacet + facet normal 0.0918981 0.0989352 0.990841 + outer loop + vertex 1.06425 1.66898 2.61489 + vertex 1.06833 1.67238 2.61418 + vertex 1.0635 1.67276 2.61459 + endloop + endfacet + facet normal 0.0850915 0.107054 0.990605 + outer loop + vertex 1.06844 1.66773 2.61467 + vertex 1.06833 1.67238 2.61418 + vertex 1.06425 1.66898 2.61489 + endloop + endfacet + facet normal 0.0982243 0.0992519 0.990203 + outer loop + vertex 1.05941 1.67376 2.61489 + vertex 1.06336 1.67735 2.61414 + vertex 1.05853 1.67768 2.61459 + endloop + endfacet + facet normal 0.0922078 0.103369 0.99036 + outer loop + vertex 1.06833 1.67238 2.61418 + vertex 1.06831 1.67719 2.61368 + vertex 1.0635 1.67276 2.61459 + endloop + endfacet + facet normal 0.0833608 0.103413 0.991139 + outer loop + vertex 1.06833 1.67238 2.61418 + vertex 1.07337 1.67716 2.61325 + vertex 1.06831 1.67719 2.61368 + endloop + endfacet + facet normal 0.0833456 0.107702 0.990683 + outer loop + vertex 1.07337 1.67716 2.61325 + vertex 1.07325 1.68214 2.61272 + vertex 1.06831 1.67719 2.61368 + endloop + endfacet + facet normal 0.0734568 0.107542 0.991483 + outer loop + vertex 1.07337 1.67716 2.61325 + vertex 1.07801 1.68201 2.61238 + vertex 1.07325 1.68214 2.61272 + endloop + endfacet + facet normal 0.0734859 0.109033 0.991318 + outer loop + vertex 1.07801 1.68201 2.61238 + vertex 1.077 1.68618 2.612 + vertex 1.07325 1.68214 2.61272 + endloop + endfacet + facet normal 0.0765249 0.106224 0.991393 + outer loop + vertex 1.07325 1.68214 2.61272 + vertex 1.077 1.68618 2.612 + vertex 1.07291 1.68705 2.61222 + endloop + endfacet + facet normal 0.076343 0.105336 0.991502 + outer loop + vertex 1.077 1.68618 2.612 + vertex 1.07693 1.69145 2.61145 + vertex 1.07291 1.68705 2.61222 + endloop + endfacet + facet normal 0.0797429 0.105352 0.991233 + outer loop + vertex 1.07693 1.69145 2.61145 + vertex 1.077 1.68618 2.612 + vertex 1.08203 1.68664 2.61155 + endloop + endfacet + facet normal 0.0792441 0.110374 0.990726 + outer loop + vertex 1.07801 1.68201 2.61238 + vertex 1.08203 1.68664 2.61155 + vertex 1.077 1.68618 2.612 + endloop + endfacet + facet normal 0.0725177 0.108434 0.991455 + outer loop + vertex 1.07824 1.67713 2.6129 + vertex 1.07801 1.68201 2.61238 + vertex 1.07337 1.67716 2.61325 + endloop + endfacet + facet normal 0.0773548 0.109715 0.990948 + outer loop + vertex 1.07332 1.67214 2.61381 + vertex 1.07337 1.67716 2.61325 + vertex 1.06833 1.67238 2.61418 + endloop + endfacet + facet normal 0.0876179 0.103458 0.990767 + outer loop + vertex 1.06831 1.67719 2.61368 + vertex 1.07325 1.68214 2.61272 + vertex 1.06833 1.68223 2.61315 + endloop + endfacet + facet normal 0.0876432 0.106894 0.9904 + outer loop + vertex 1.07325 1.68214 2.61272 + vertex 1.07291 1.68705 2.61222 + vertex 1.06833 1.68223 2.61315 + endloop + endfacet + facet normal 0.0765495 0.105148 0.991506 + outer loop + vertex 1.07291 1.68705 2.61222 + vertex 1.07693 1.69145 2.61145 + vertex 1.07182 1.6912 2.61187 + endloop + endfacet + facet normal 0.0990746 0.106573 0.989357 + outer loop + vertex 1.06816 1.68721 2.61264 + vertex 1.06781 1.69208 2.61215 + vertex 1.06331 1.68724 2.61312 + endloop + endfacet + facet normal 0.0990836 0.103986 0.989631 + outer loop + vertex 1.06329 1.6822 2.61365 + vertex 1.06816 1.68721 2.61264 + vertex 1.06331 1.68724 2.61312 + endloop + endfacet + facet normal 0.0983699 0.101729 0.989937 + outer loop + vertex 1.06336 1.67735 2.61414 + vertex 1.06329 1.6822 2.61365 + vertex 1.05853 1.67768 2.61459 + endloop + endfacet + facet normal 0.0924881 0.0980203 0.990877 + outer loop + vertex 1.05941 1.67376 2.61489 + vertex 1.05853 1.67768 2.61459 + vertex 1.05424 1.67389 2.61536 + endloop + endfacet + facet normal 0.0863685 0.0943956 0.991781 + outer loop + vertex 1.04948 1.67433 2.61574 + vertex 1.05424 1.67389 2.61536 + vertex 1.0492 1.67893 2.61532 + endloop + endfacet + facet normal 0.0942007 0.101634 0.990352 + outer loop + vertex 1.0544 1.67873 2.61487 + vertex 1.05835 1.68234 2.61413 + vertex 1.05349 1.6827 2.61455 + endloop + endfacet + facet normal 0.0954824 0.10275 0.990114 + outer loop + vertex 1.05349 1.6827 2.61455 + vertex 1.0583 1.68721 2.61362 + vertex 1.05335 1.68737 2.61408 + endloop + endfacet + facet normal 0.0955305 0.104836 0.989891 + outer loop + vertex 1.0583 1.68721 2.61362 + vertex 1.05834 1.69224 2.61309 + vertex 1.05335 1.68737 2.61408 + endloop + endfacet + facet normal 0.09693 0.104439 0.989796 + outer loop + vertex 1.05332 1.69222 2.61358 + vertex 1.0582 1.69717 2.61258 + vertex 1.05335 1.69723 2.61304 + endloop + endfacet + facet normal 0.0969319 0.105501 0.989684 + outer loop + vertex 1.0582 1.69717 2.61258 + vertex 1.05786 1.70197 2.6121 + vertex 1.05335 1.69723 2.61304 + endloop + endfacet + facet normal 0.099212 0.105495 0.989458 + outer loop + vertex 1.06317 1.6922 2.6126 + vertex 1.06285 1.69705 2.61212 + vertex 1.05834 1.69224 2.61309 + endloop + endfacet + facet normal 0.0991662 0.105639 0.989448 + outer loop + vertex 1.0582 1.69717 2.61258 + vertex 1.06179 1.70113 2.61179 + vertex 1.05786 1.70197 2.6121 + endloop + endfacet + facet normal 0.102352 0.108342 0.988831 + outer loop + vertex 1.06676 1.69619 2.61181 + vertex 1.06661 1.70138 2.61126 + vertex 1.06285 1.69705 2.61212 + endloop + endfacet + facet normal 0.0994933 0.107245 0.989242 + outer loop + vertex 1.06179 1.70113 2.61179 + vertex 1.06162 1.70629 2.61125 + vertex 1.05786 1.70197 2.6121 + endloop + endfacet + facet normal 0.0999462 0.10685 0.989239 + outer loop + vertex 1.05786 1.70197 2.6121 + vertex 1.06162 1.70629 2.61125 + vertex 1.05679 1.70603 2.61177 + endloop + endfacet + facet normal 0.0971347 0.106136 0.989596 + outer loop + vertex 1.05786 1.70197 2.6121 + vertex 1.05679 1.70603 2.61177 + vertex 1.0532 1.70212 2.61254 + endloop + endfacet + facet normal 0.0999567 0.106689 0.989255 + outer loop + vertex 1.0566 1.71118 2.61123 + vertex 1.05679 1.70603 2.61177 + vertex 1.06162 1.70629 2.61125 + endloop + endfacet + facet normal 0.097784 0.106633 0.989478 + outer loop + vertex 1.05679 1.70603 2.61177 + vertex 1.0566 1.71118 2.61123 + vertex 1.05281 1.70686 2.61207 + endloop + endfacet + facet normal 0.111434 0.110675 0.98759 + outer loop + vertex 1.06429 1.70918 2.61064 + vertex 1.06612 1.70607 2.61078 + vertex 1.06903 1.70873 2.61016 + endloop + endfacet + facet normal 0.10096 0.10772 0.989042 + outer loop + vertex 1.06115 1.711 2.61079 + vertex 1.0566 1.71118 2.61123 + vertex 1.06162 1.70629 2.61125 + endloop + endfacet + facet normal 0.101007 0.109393 0.988853 + outer loop + vertex 1.06115 1.711 2.61079 + vertex 1.05928 1.71411 2.61063 + vertex 1.0566 1.71118 2.61123 + endloop + endfacet + facet normal 0.102464 0.113411 0.988251 + outer loop + vertex 1.05611 1.71591 2.61076 + vertex 1.05421 1.71904 2.61059 + vertex 1.05148 1.71606 2.61122 + endloop + endfacet + facet normal 0.110631 0.106131 0.988179 + outer loop + vertex 1.05169 1.71088 2.61175 + vertex 1.05148 1.71606 2.61122 + vertex 1.0477 1.71176 2.61211 + endloop + endfacet + facet normal 0.114128 0.103044 0.988108 + outer loop + vertex 1.0477 1.71176 2.61211 + vertex 1.05148 1.71606 2.61122 + vertex 1.04655 1.7158 2.61182 + endloop + endfacet + facet normal 0.0975995 0.10571 0.989596 + outer loop + vertex 1.0532 1.70212 2.61254 + vertex 1.05679 1.70603 2.61177 + vertex 1.05281 1.70686 2.61207 + endloop + endfacet + facet normal 0.0971177 0.105325 0.989684 + outer loop + vertex 1.05335 1.69723 2.61304 + vertex 1.05786 1.70197 2.6121 + vertex 1.0532 1.70212 2.61254 + endloop + endfacet + facet normal 0.0981883 0.104418 0.989675 + outer loop + vertex 1.05332 1.69222 2.61358 + vertex 1.05335 1.69723 2.61304 + vertex 1.04842 1.69245 2.61404 + endloop + endfacet + facet normal 0.0980628 0.100958 0.990046 + outer loop + vertex 1.04856 1.68777 2.6145 + vertex 1.05332 1.69222 2.61358 + vertex 1.04842 1.69245 2.61404 + endloop + endfacet + facet normal 0.0970951 0.101028 0.990134 + outer loop + vertex 1.04939 1.68379 2.61483 + vertex 1.04856 1.68777 2.6145 + vertex 1.04437 1.68397 2.6153 + endloop + endfacet + facet normal 0.0911626 0.0917601 0.991599 + outer loop + vertex 1.04444 1.6794 2.61572 + vertex 1.0492 1.67893 2.61532 + vertex 1.04437 1.68397 2.6153 + endloop + endfacet + facet normal 0.105508 0.100391 0.989338 + outer loop + vertex 1.04628 1.6762 2.61584 + vertex 1.04444 1.6794 2.61572 + vertex 1.04164 1.67634 2.61633 + endloop + endfacet + facet normal 0.131517 0.0989466 0.986363 + outer loop + vertex 1.04137 1.68123 2.61588 + vertex 1.0398 1.68438 2.61577 + vertex 1.03683 1.68126 2.61648 + endloop + endfacet + facet normal 0.136612 0.0940335 0.986152 + outer loop + vertex 1.03694 1.68624 2.61599 + vertex 1.03683 1.68126 2.61648 + vertex 1.0398 1.68438 2.61577 + endloop + endfacet + facet normal 0.100974 0.0929552 0.990537 + outer loop + vertex 1.04164 1.67634 2.61633 + vertex 1.04174 1.67106 2.61681 + vertex 1.04675 1.67137 2.61627 + endloop + endfacet + facet normal 0.114163 0.0965816 0.988756 + outer loop + vertex 1.04286 1.66698 2.61708 + vertex 1.04174 1.67106 2.61681 + vertex 1.03818 1.6672 2.6176 + endloop + endfacet + facet normal 0.113982 0.0914322 0.989267 + outer loop + vertex 1.03842 1.66238 2.61802 + vertex 1.04286 1.66698 2.61708 + vertex 1.03818 1.6672 2.6176 + endloop + endfacet + facet normal 0.110202 0.0887311 0.989941 + outer loop + vertex 1.03844 1.65742 2.61846 + vertex 1.04327 1.6622 2.61749 + vertex 1.03842 1.66238 2.61802 + endloop + endfacet + facet normal 0.11758 0.0848007 0.989436 + outer loop + vertex 1.03847 1.65255 2.61887 + vertex 1.03844 1.65742 2.61846 + vertex 1.03368 1.65305 2.6194 + endloop + endfacet + facet normal 0.116778 0.0762432 0.990227 + outer loop + vertex 1.03449 1.649 2.61962 + vertex 1.03847 1.65255 2.61887 + vertex 1.03368 1.65305 2.6194 + endloop + endfacet + facet normal 0.111443 0.0822372 0.990362 + outer loop + vertex 1.03833 1.64776 2.61929 + vertex 1.03847 1.65255 2.61887 + vertex 1.03449 1.649 2.61962 + endloop + endfacet + facet normal 0.110273 0.0785089 0.990796 + outer loop + vertex 1.03345 1.64436 2.6201 + vertex 1.03833 1.64776 2.61929 + vertex 1.03449 1.649 2.61962 + endloop + endfacet + facet normal 0.155424 0.0822975 0.984414 + outer loop + vertex 1.03045 1.64033 2.62078 + vertex 1.02919 1.64436 2.62064 + vertex 1.02592 1.64183 2.62137 + endloop + endfacet + facet normal 0.152437 0.0727922 0.985629 + outer loop + vertex 1.02592 1.64183 2.62137 + vertex 1.02763 1.63591 2.62154 + vertex 1.03045 1.64033 2.62078 + endloop + endfacet + facet normal 0.179426 0.0804587 0.980476 + outer loop + vertex 1.02763 1.63591 2.62154 + vertex 1.02592 1.64183 2.62137 + vertex 1.02273 1.63712 2.62234 + endloop + endfacet + facet normal 0.143587 0.0786057 0.986511 + outer loop + vertex 1.03045 1.64033 2.62078 + vertex 1.02763 1.63591 2.62154 + vertex 1.0319 1.63628 2.62089 + endloop + endfacet + facet normal 0.174558 0.0690525 0.982223 + outer loop + vertex 1.02688 1.63094 2.62203 + vertex 1.02763 1.63591 2.62154 + vertex 1.02317 1.63213 2.6226 + endloop + endfacet + facet normal 0.106839 0.0719942 0.991666 + outer loop + vertex 1.03278 1.62207 2.62189 + vertex 1.03663 1.62639 2.62117 + vertex 1.03166 1.62608 2.62172 + endloop + endfacet + facet normal 0.10195 0.0731389 0.992097 + outer loop + vertex 1.03327 1.61735 2.62219 + vertex 1.0368 1.62122 2.62154 + vertex 1.03278 1.62207 2.62189 + endloop + endfacet + facet normal 0.112967 0.0738164 0.990853 + outer loop + vertex 1.0335 1.61246 2.62253 + vertex 1.03327 1.61735 2.62219 + vertex 1.0285 1.61252 2.6231 + endloop + endfacet + facet normal 0.0929033 0.0709639 0.993143 + outer loop + vertex 1.03349 1.60742 2.62289 + vertex 1.03838 1.61245 2.62207 + vertex 1.0335 1.61246 2.62253 + endloop + endfacet + facet normal 0.0895035 0.0685425 0.993625 + outer loop + vertex 1.03333 1.60234 2.62326 + vertex 1.03856 1.60754 2.62243 + vertex 1.03349 1.60742 2.62289 + endloop + endfacet + facet normal 0.0862266 0.066698 0.99404 + outer loop + vertex 1.03314 1.59725 2.62361 + vertex 1.03851 1.60246 2.6228 + vertex 1.03333 1.60234 2.62326 + endloop + endfacet + facet normal 0.0954898 0.0641718 0.99336 + outer loop + vertex 1.0331 1.59222 2.62394 + vertex 1.03314 1.59725 2.62361 + vertex 1.02816 1.59275 2.62438 + endloop + endfacet + facet normal 0.0947233 0.0566224 0.993892 + outer loop + vertex 1.02864 1.58788 2.62462 + vertex 1.0331 1.59222 2.62394 + vertex 1.02816 1.59275 2.62438 + endloop + endfacet + facet normal 0.0885254 0.0551102 0.994548 + outer loop + vertex 1.02948 1.58398 2.62476 + vertex 1.03323 1.58743 2.62423 + vertex 1.02864 1.58788 2.62462 + endloop + endfacet + facet normal 0.0846607 0.05933 0.994642 + outer loop + vertex 1.03316 1.58274 2.62452 + vertex 1.03323 1.58743 2.62423 + vertex 1.02948 1.58398 2.62476 + endloop + endfacet + facet normal 0.0723303 0.0555028 0.995835 + outer loop + vertex 1.0332 1.57788 2.62478 + vertex 1.03799 1.58218 2.6242 + vertex 1.03316 1.58274 2.62452 + endloop + endfacet + facet normal 0.0788383 0.0514992 0.995556 + outer loop + vertex 1.03372 1.57303 2.625 + vertex 1.0332 1.57788 2.62478 + vertex 1.0293 1.57407 2.62529 + endloop + endfacet + facet normal 0.0644311 0.0482043 0.996757 + outer loop + vertex 1.03459 1.56909 2.62513 + vertex 1.03821 1.57246 2.62473 + vertex 1.03372 1.57303 2.625 + endloop + endfacet + facet normal 0.058687 0.048295 0.997108 + outer loop + vertex 1.03366 1.56453 2.6254 + vertex 1.03826 1.56779 2.62498 + vertex 1.03459 1.56909 2.62513 + endloop + endfacet + facet normal 0.0573756 0.05014 0.997093 + outer loop + vertex 1.03856 1.56305 2.6252 + vertex 1.03826 1.56779 2.62498 + vertex 1.03366 1.56453 2.6254 + endloop + endfacet + facet normal 0.0473031 0.0379416 0.99816 + outer loop + vertex 1.03447 1.55465 2.62575 + vertex 1.0386 1.55471 2.62555 + vertex 1.03516 1.55889 2.62555 + endloop + endfacet + facet normal 0.0441155 0.041953 0.998145 + outer loop + vertex 1.04355 1.55315 2.6254 + vertex 1.04326 1.55784 2.62521 + vertex 1.0386 1.55471 2.62555 + endloop + endfacet + facet normal 0.0484516 0.0455326 0.997787 + outer loop + vertex 1.03951 1.55908 2.62533 + vertex 1.04319 1.56244 2.625 + vertex 1.03856 1.56305 2.6252 + endloop + endfacet + facet normal 0.0493265 0.0479902 0.997629 + outer loop + vertex 1.04803 1.55728 2.625 + vertex 1.04797 1.56213 2.62477 + vertex 1.04326 1.55784 2.62521 + endloop + endfacet + facet normal 0.0515465 0.0525384 0.997288 + outer loop + vertex 1.04319 1.56244 2.625 + vertex 1.04799 1.56708 2.62451 + vertex 1.04301 1.56719 2.62476 + endloop + endfacet + facet normal 0.0562 0.053773 0.99697 + outer loop + vertex 1.053 1.56214 2.62449 + vertex 1.05307 1.56719 2.62421 + vertex 1.04797 1.56213 2.62477 + endloop + endfacet + facet normal 0.0573205 0.0578596 0.996678 + outer loop + vertex 1.04799 1.56708 2.62451 + vertex 1.05317 1.57229 2.62391 + vertex 1.04804 1.57211 2.62421 + endloop + endfacet + facet normal 0.0598464 0.0601052 0.996396 + outer loop + vertex 1.0582 1.56735 2.6239 + vertex 1.05831 1.57246 2.62358 + vertex 1.05307 1.56719 2.62421 + endloop + endfacet + facet normal 0.0630514 0.0627842 0.996033 + outer loop + vertex 1.05317 1.57229 2.62391 + vertex 1.05845 1.57759 2.62324 + vertex 1.05332 1.57741 2.62358 + endloop + endfacet + facet normal 0.0543389 0.0679125 0.99621 + outer loop + vertex 1.0635 1.57254 2.62329 + vertex 1.0636 1.57766 2.62294 + vertex 1.05831 1.57246 2.62358 + endloop + endfacet + facet normal 0.0602723 0.0679043 0.99587 + outer loop + vertex 1.05845 1.57759 2.62324 + vertex 1.06364 1.58275 2.62257 + vertex 1.05858 1.58271 2.62288 + endloop + endfacet + facet normal 0.0414426 0.0735112 0.996433 + outer loop + vertex 1.06873 1.57765 2.62272 + vertex 1.06866 1.58266 2.62236 + vertex 1.0636 1.57766 2.62294 + endloop + endfacet + facet normal 0.0463033 0.0715591 0.996361 + outer loop + vertex 1.06364 1.58275 2.62257 + vertex 1.06834 1.58747 2.62202 + vertex 1.06353 1.58776 2.62222 + endloop + endfacet + facet normal 0.0352251 0.0716164 0.99681 + outer loop + vertex 1.07342 1.58252 2.6222 + vertex 1.07297 1.58718 2.62188 + vertex 1.06866 1.58266 2.62236 + endloop + endfacet + facet normal 0.0342373 0.0697139 0.996979 + outer loop + vertex 1.06834 1.58747 2.62202 + vertex 1.07191 1.59105 2.62164 + vertex 1.06783 1.59223 2.6217 + endloop + endfacet + facet normal 0.0630645 0.0767652 0.995053 + outer loop + vertex 1.07667 1.58652 2.6217 + vertex 1.07668 1.59157 2.62131 + vertex 1.07297 1.58718 2.62188 + endloop + endfacet + facet normal 0.0329851 0.0653995 0.997314 + outer loop + vertex 1.07191 1.59105 2.62164 + vertex 1.07227 1.59559 2.62133 + vertex 1.06783 1.59223 2.6217 + endloop + endfacet + facet normal 0.0663883 0.0725228 0.995155 + outer loop + vertex 1.0765 1.59606 2.62102 + vertex 1.07463 1.59888 2.62094 + vertex 1.07227 1.59559 2.62133 + endloop + endfacet + facet normal 0.462344 0.183406 0.867525 + outer loop + vertex 1.07926 1.5947 2.62059 + vertex 1.08066 1.59193 2.62043 + vertex 1.08239 1.59444 2.61898 + endloop + endfacet + facet normal 0.197638 0.158852 0.967318 + outer loop + vertex 1.07463 1.59888 2.62094 + vertex 1.0765 1.59606 2.62102 + vertex 1.079 1.5989 2.62004 + endloop + endfacet + facet normal 0.0521964 0.0826889 0.995208 + outer loop + vertex 1.07463 1.59888 2.62094 + vertex 1.07059 1.60044 2.62102 + vertex 1.07227 1.59559 2.62133 + endloop + endfacet + facet normal 0.029572 0.0827439 0.996132 + outer loop + vertex 1.07059 1.60044 2.62102 + vertex 1.06898 1.6052 2.62067 + vertex 1.06651 1.60203 2.62101 + endloop + endfacet + facet normal 0.151561 0.0989535 0.983482 + outer loop + vertex 1.07476 1.60315 2.62048 + vertex 1.07811 1.60749 2.61953 + vertex 1.07358 1.60815 2.62016 + endloop + endfacet + facet normal 0.0535169 0.0995856 0.993589 + outer loop + vertex 1.06953 1.60936 2.62029 + vertex 1.07326 1.61262 2.61977 + vertex 1.0686 1.61297 2.61998 + endloop + endfacet + facet normal 0.1489 0.0785622 0.985727 + outer loop + vertex 1.07811 1.60749 2.61953 + vertex 1.07772 1.61221 2.61921 + vertex 1.07358 1.60815 2.62016 + endloop + endfacet + facet normal 0.28012 0.0807369 0.956564 + outer loop + vertex 1.07772 1.61221 2.61921 + vertex 1.08174 1.61667 2.61766 + vertex 1.0777 1.61714 2.6188 + endloop + endfacet + facet normal 0.277598 0.0528068 0.959245 + outer loop + vertex 1.08174 1.61667 2.61766 + vertex 1.08186 1.62182 2.61734 + vertex 1.0777 1.61714 2.6188 + endloop + endfacet + facet normal 0.105462 0.0820883 0.991029 + outer loop + vertex 1.07782 1.62223 2.61836 + vertex 1.07803 1.6274 2.61791 + vertex 1.07317 1.62223 2.61885 + endloop + endfacet + facet normal 0.105378 0.0922988 0.99014 + outer loop + vertex 1.0731 1.61726 2.61932 + vertex 1.07782 1.62223 2.61836 + vertex 1.07317 1.62223 2.61885 + endloop + endfacet + facet normal 0.0533152 0.0966362 0.993891 + outer loop + vertex 1.07326 1.61262 2.61977 + vertex 1.0731 1.61726 2.61932 + vertex 1.0686 1.61297 2.61998 + endloop + endfacet + facet normal 0.039596 0.096067 0.994587 + outer loop + vertex 1.06953 1.60936 2.62029 + vertex 1.0686 1.61297 2.61998 + vertex 1.06439 1.60934 2.6205 + endloop + endfacet + facet normal 0.0572879 0.0786785 0.995253 + outer loop + vertex 1.05966 1.60954 2.62076 + vertex 1.06439 1.60934 2.6205 + vertex 1.05933 1.61405 2.62042 + endloop + endfacet + facet normal 0.0539912 0.0865311 0.994785 + outer loop + vertex 1.0645 1.61391 2.62009 + vertex 1.06829 1.61739 2.61958 + vertex 1.06347 1.61772 2.61981 + endloop + endfacet + facet normal 0.0783562 0.0817436 0.993568 + outer loop + vertex 1.05458 1.6145 2.62076 + vertex 1.05933 1.61405 2.62042 + vertex 1.05422 1.61901 2.62041 + endloop + endfacet + facet normal 0.0822143 0.0832032 0.993135 + outer loop + vertex 1.05422 1.61901 2.62041 + vertex 1.05837 1.62269 2.61976 + vertex 1.05426 1.62376 2.62001 + endloop + endfacet + facet normal 0.0711588 0.0869764 0.993666 + outer loop + vertex 1.06347 1.61772 2.61981 + vertex 1.06318 1.62228 2.61943 + vertex 1.05935 1.6188 2.62001 + endloop + endfacet + facet normal 0.0782612 0.0856488 0.993247 + outer loop + vertex 1.05837 1.62269 2.61976 + vertex 1.06314 1.62711 2.61901 + vertex 1.05813 1.62726 2.61939 + endloop + endfacet + facet normal 0.0598266 0.0931429 0.993854 + outer loop + vertex 1.06817 1.62215 2.61914 + vertex 1.06831 1.6272 2.61866 + vertex 1.06318 1.62228 2.61943 + endloop + endfacet + facet normal 0.0685233 0.0913765 0.993456 + outer loop + vertex 1.06314 1.62711 2.61901 + vertex 1.06851 1.63239 2.61815 + vertex 1.06331 1.63221 2.61852 + endloop + endfacet + facet normal 0.0568175 0.0973303 0.993629 + outer loop + vertex 1.07337 1.62738 2.61835 + vertex 1.07351 1.63255 2.61784 + vertex 1.06831 1.6272 2.61866 + endloop + endfacet + facet normal 0.0592744 0.0967274 0.993544 + outer loop + vertex 1.06851 1.63239 2.61815 + vertex 1.07337 1.6375 2.61736 + vertex 1.06859 1.63755 2.61764 + endloop + endfacet + facet normal 0.0850228 0.0900468 0.992302 + outer loop + vertex 1.07812 1.63252 2.61745 + vertex 1.07777 1.63741 2.61703 + vertex 1.07351 1.63255 2.61784 + endloop + endfacet + facet normal 0.0645008 0.0973944 0.993154 + outer loop + vertex 1.07337 1.6375 2.61736 + vertex 1.07669 1.6414 2.61676 + vertex 1.07293 1.64222 2.61693 + endloop + endfacet + facet normal 0.175112 0.0801725 0.981279 + outer loop + vertex 1.08178 1.63694 2.61636 + vertex 1.08064 1.64206 2.61614 + vertex 1.07777 1.63741 2.61703 + endloop + endfacet + facet normal 0.0645291 0.0975258 0.993139 + outer loop + vertex 1.07669 1.6414 2.61676 + vertex 1.07655 1.64636 2.61629 + vertex 1.07293 1.64222 2.61693 + endloop + endfacet + facet normal 0.133954 0.0819674 0.987592 + outer loop + vertex 1.08102 1.64624 2.61569 + vertex 1.07942 1.64922 2.61566 + vertex 1.07655 1.64636 2.61629 + endloop + endfacet + facet normal 0.0658779 0.0904042 0.993724 + outer loop + vertex 1.07151 1.65104 2.61619 + vertex 1.07175 1.6462 2.61662 + vertex 1.07655 1.64636 2.61629 + endloop + endfacet + facet normal 0.0641609 0.0959123 0.99332 + outer loop + vertex 1.07101 1.65548 2.6158 + vertex 1.06683 1.65532 2.61608 + vertex 1.07151 1.65104 2.61619 + endloop + endfacet + facet normal 0.0638542 0.102911 0.992639 + outer loop + vertex 1.07101 1.65548 2.6158 + vertex 1.06907 1.65837 2.61562 + vertex 1.06683 1.65532 2.61608 + endloop + endfacet + facet normal 0.116642 0.126394 0.985099 + outer loop + vertex 1.07427 1.65391 2.61575 + vertex 1.07621 1.6509 2.61591 + vertex 1.07917 1.65381 2.61518 + endloop + endfacet + facet normal 0.241124 0.0468529 0.969363 + outer loop + vertex 1.08389 1.65393 2.614 + vertex 1.08304 1.65784 2.61402 + vertex 1.07917 1.65381 2.61518 + endloop + endfacet + facet normal 0.0944511 0.0919623 0.991273 + outer loop + vertex 1.07939 1.65877 2.61476 + vertex 1.07853 1.66269 2.61448 + vertex 1.07415 1.65843 2.6153 + endloop + endfacet + facet normal 0.0627051 0.102153 0.99279 + outer loop + vertex 1.06907 1.65837 2.61562 + vertex 1.07101 1.65548 2.6158 + vertex 1.07415 1.65843 2.6153 + endloop + endfacet + facet normal 0.0703826 0.0981116 0.992683 + outer loop + vertex 1.06907 1.65837 2.61562 + vertex 1.06513 1.6601 2.61573 + vertex 1.06683 1.65532 2.61608 + endloop + endfacet + facet normal 0.0854042 0.100102 0.991305 + outer loop + vertex 1.06513 1.6601 2.61573 + vertex 1.06362 1.66482 2.61539 + vertex 1.06127 1.66183 2.61589 + endloop + endfacet + facet normal 0.0841803 0.103936 0.991015 + outer loop + vertex 1.06362 1.66482 2.61539 + vertex 1.06844 1.66773 2.61467 + vertex 1.06425 1.66898 2.61489 + endloop + endfacet + facet normal 0.0622986 0.115946 0.9913 + outer loop + vertex 1.07453 1.66339 2.61475 + vertex 1.07353 1.6673 2.61436 + vertex 1.06944 1.66264 2.61516 + endloop + endfacet + facet normal 0.0772441 0.106925 0.991262 + outer loop + vertex 1.06844 1.66773 2.61467 + vertex 1.07332 1.67214 2.61381 + vertex 1.06833 1.67238 2.61418 + endloop + endfacet + facet normal 0.0763202 0.111489 0.990831 + outer loop + vertex 1.0784 1.66734 2.61398 + vertex 1.07833 1.67219 2.61344 + vertex 1.07353 1.6673 2.61436 + endloop + endfacet + facet normal 0.0725151 0.109804 0.991305 + outer loop + vertex 1.07332 1.67214 2.61381 + vertex 1.07824 1.67713 2.6129 + vertex 1.07337 1.67716 2.61325 + endloop + endfacet + facet normal 0.125956 0.0872376 0.988193 + outer loop + vertex 1.0829 1.67231 2.61285 + vertex 1.08274 1.67732 2.61242 + vertex 1.07833 1.67219 2.61344 + endloop + endfacet + facet normal 0.237398 0.089036 0.967323 + outer loop + vertex 1.0829 1.67231 2.61285 + vertex 1.08669 1.67741 2.61145 + vertex 1.08274 1.67732 2.61242 + endloop + endfacet + facet normal 0.238721 0.0549127 0.969534 + outer loop + vertex 1.08669 1.67741 2.61145 + vertex 1.08581 1.68259 2.61137 + vertex 1.08274 1.67732 2.61242 + endloop + endfacet + facet normal 0.28483 0.0509621 0.957222 + outer loop + vertex 1.08674 1.6722 2.61171 + vertex 1.08669 1.67741 2.61145 + vertex 1.0829 1.67231 2.61285 + endloop + endfacet + facet normal 0.285077 0.0842266 0.954797 + outer loop + vertex 1.08278 1.66726 2.61333 + vertex 1.08674 1.6722 2.61171 + vertex 1.0829 1.67231 2.61285 + endloop + endfacet + facet normal 0.080864 0.108758 0.990774 + outer loop + vertex 1.07824 1.67713 2.6129 + vertex 1.08184 1.68137 2.61214 + vertex 1.07801 1.68201 2.61238 + endloop + endfacet + facet normal 0.080894 0.108946 0.990751 + outer loop + vertex 1.08184 1.68137 2.61214 + vertex 1.08203 1.68664 2.61155 + vertex 1.07801 1.68201 2.61238 + endloop + endfacet + facet normal 0.0794797 0.105074 0.991283 + outer loop + vertex 1.08188 1.69132 2.61106 + vertex 1.07693 1.69145 2.61145 + vertex 1.08203 1.68664 2.61155 + endloop + endfacet + facet normal 0.365278 0.204707 0.908112 + outer loop + vertex 1.08505 1.68951 2.61079 + vertex 1.0864 1.68663 2.61089 + vertex 1.08903 1.68865 2.60938 + endloop + endfacet + facet normal 0.139832 0.145043 0.979495 + outer loop + vertex 1.07988 1.69441 2.61089 + vertex 1.08188 1.69132 2.61106 + vertex 1.08469 1.69404 2.61026 + endloop + endfacet + facet normal 0.0795088 0.106625 0.991115 + outer loop + vertex 1.08188 1.69132 2.61106 + vertex 1.07988 1.69441 2.61089 + vertex 1.07693 1.69145 2.61145 + endloop + endfacet + facet normal 0.0764184 0.107447 0.99127 + outer loop + vertex 1.07167 1.69641 2.61131 + vertex 1.07182 1.6912 2.61187 + vertex 1.07693 1.69145 2.61145 + endloop + endfacet + facet normal 0.102249 0.115695 0.988008 + outer loop + vertex 1.07116 1.70112 2.61082 + vertex 1.06661 1.70138 2.61126 + vertex 1.07167 1.69641 2.61131 + endloop + endfacet + facet normal 0.0884006 0.106932 0.990329 + outer loop + vertex 1.06927 1.70423 2.61065 + vertex 1.07116 1.70112 2.61082 + vertex 1.07416 1.70378 2.61026 + endloop + endfacet + facet normal 0.0758751 0.116438 0.990296 + outer loop + vertex 1.07444 1.6993 2.61075 + vertex 1.07645 1.69619 2.61096 + vertex 1.07947 1.69892 2.61041 + endloop + endfacet + facet normal 0.107299 0.0964386 0.989539 + outer loop + vertex 1.08466 1.69889 2.60985 + vertex 1.08359 1.70271 2.60959 + vertex 1.07947 1.69892 2.61041 + endloop + endfacet + facet normal 0.193313 0.119656 0.973813 + outer loop + vertex 1.08466 1.69889 2.60985 + vertex 1.08784 1.70239 2.60879 + vertex 1.08359 1.70271 2.60959 + endloop + endfacet + facet normal 0.0823651 0.123133 0.988966 + outer loop + vertex 1.07952 1.70369 2.60987 + vertex 1.08326 1.70728 2.60911 + vertex 1.07851 1.70757 2.60947 + endloop + endfacet + facet normal 0.191527 0.0862114 0.977694 + outer loop + vertex 1.08784 1.70239 2.60879 + vertex 1.08764 1.70715 2.60841 + vertex 1.08359 1.70271 2.60959 + endloop + endfacet + facet normal 0.0816295 0.108558 0.990733 + outer loop + vertex 1.08326 1.70728 2.60911 + vertex 1.08317 1.71211 2.60859 + vertex 1.07851 1.70757 2.60947 + endloop + endfacet + facet normal 0.0739949 0.12104 0.989886 + outer loop + vertex 1.07952 1.70369 2.60987 + vertex 1.07851 1.70757 2.60947 + vertex 1.07416 1.70378 2.61026 + endloop + endfacet + facet normal 0.0889154 0.113204 0.989585 + outer loop + vertex 1.06927 1.70423 2.61065 + vertex 1.07416 1.70378 2.61026 + vertex 1.06903 1.70873 2.61016 + endloop + endfacet + facet normal 0.0750589 0.114134 0.990626 + outer loop + vertex 1.07431 1.70858 2.60966 + vertex 1.07831 1.7122 2.60894 + vertex 1.07342 1.71252 2.60927 + endloop + endfacet + facet normal 0.0747799 0.109343 0.991187 + outer loop + vertex 1.07831 1.7122 2.60894 + vertex 1.0783 1.71706 2.6084 + vertex 1.07342 1.71252 2.60927 + endloop + endfacet + facet normal 0.0752915 0.108797 0.991209 + outer loop + vertex 1.07342 1.71252 2.60927 + vertex 1.0783 1.71706 2.6084 + vertex 1.07331 1.71719 2.60877 + endloop + endfacet + facet normal 0.0663465 0.109393 0.991782 + outer loop + vertex 1.07831 1.7122 2.60894 + vertex 1.08331 1.71717 2.60806 + vertex 1.0783 1.71706 2.6084 + endloop + endfacet + facet normal 0.0666462 0.0991919 0.992834 + outer loop + vertex 1.08331 1.71717 2.60806 + vertex 1.08338 1.72228 2.60754 + vertex 1.0783 1.71706 2.6084 + endloop + endfacet + facet normal 0.0603176 0.105319 0.992608 + outer loop + vertex 1.0783 1.71706 2.6084 + vertex 1.08338 1.72228 2.60754 + vertex 1.07837 1.72211 2.60786 + endloop + endfacet + facet normal 0.0942883 0.0985782 0.990652 + outer loop + vertex 1.08331 1.71717 2.60806 + vertex 1.08802 1.72231 2.6071 + vertex 1.08338 1.72228 2.60754 + endloop + endfacet + facet normal 0.111779 0.114806 0.987079 + outer loop + vertex 1.06429 1.70918 2.61064 + vertex 1.06903 1.70873 2.61016 + vertex 1.06405 1.71371 2.61014 + endloop + endfacet + facet normal 0.111152 0.110348 0.987658 + outer loop + vertex 1.06405 1.71371 2.61014 + vertex 1.06844 1.71755 2.60922 + vertex 1.0643 1.71859 2.60957 + endloop + endfacet + facet normal 0.0950545 0.109091 0.989477 + outer loop + vertex 1.07342 1.71252 2.60927 + vertex 1.07331 1.71719 2.60877 + vertex 1.06926 1.71357 2.60956 + endloop + endfacet + facet normal 0.0995284 0.101193 0.989876 + outer loop + vertex 1.06844 1.71755 2.60922 + vertex 1.07329 1.72206 2.60827 + vertex 1.06833 1.72223 2.60875 + endloop + endfacet + facet normal 0.0752281 0.105005 0.991622 + outer loop + vertex 1.0783 1.71706 2.6084 + vertex 1.07837 1.72211 2.60786 + vertex 1.07331 1.71719 2.60877 + endloop + endfacet + facet normal 0.0819219 0.0966598 0.99194 + outer loop + vertex 1.07329 1.72206 2.60827 + vertex 1.07821 1.72707 2.60737 + vertex 1.07331 1.7271 2.60777 + endloop + endfacet + facet normal 0.0631114 0.0918134 0.993774 + outer loop + vertex 1.07821 1.72707 2.60737 + vertex 1.0818 1.73124 2.60676 + vertex 1.07784 1.73192 2.60695 + endloop + endfacet + facet normal 0.0819249 0.0931276 0.992278 + outer loop + vertex 1.07821 1.72707 2.60737 + vertex 1.07784 1.73192 2.60695 + vertex 1.07331 1.7271 2.60777 + endloop + endfacet + facet normal 0.0851402 0.0901087 0.992286 + outer loop + vertex 1.07331 1.7271 2.60777 + vertex 1.07784 1.73192 2.60695 + vertex 1.07314 1.73209 2.60734 + endloop + endfacet + facet normal 0.10103 0.0905084 0.990758 + outer loop + vertex 1.07331 1.7271 2.60777 + vertex 1.07314 1.73209 2.60734 + vertex 1.06827 1.72712 2.60829 + endloop + endfacet + facet normal 0.102512 0.0890505 0.990738 + outer loop + vertex 1.06827 1.72712 2.60829 + vertex 1.07314 1.73209 2.60734 + vertex 1.06827 1.73217 2.60783 + endloop + endfacet + facet normal 0.105328 0.089026 0.990445 + outer loop + vertex 1.06827 1.72712 2.60829 + vertex 1.06827 1.73217 2.60783 + vertex 1.06328 1.72725 2.60881 + endloop + endfacet + facet normal 0.104016 0.0903608 0.990462 + outer loop + vertex 1.06328 1.72725 2.60881 + vertex 1.06827 1.73217 2.60783 + vertex 1.06322 1.73212 2.60837 + endloop + endfacet + facet normal 0.101331 0.0903518 0.990741 + outer loop + vertex 1.06328 1.72725 2.60881 + vertex 1.06322 1.73212 2.60837 + vertex 1.05839 1.72756 2.60928 + endloop + endfacet + facet normal 0.100084 0.0916757 0.990747 + outer loop + vertex 1.05839 1.72756 2.60928 + vertex 1.06322 1.73212 2.60837 + vertex 1.05821 1.73221 2.60887 + endloop + endfacet + facet normal 0.0984042 0.0916266 0.990919 + outer loop + vertex 1.05839 1.72756 2.60928 + vertex 1.05821 1.73221 2.60887 + vertex 1.05423 1.72859 2.6096 + endloop + endfacet + facet normal 0.10043 0.100161 0.98989 + outer loop + vertex 1.054 1.72367 2.61012 + vertex 1.05839 1.72756 2.60928 + vertex 1.05423 1.72859 2.6096 + endloop + endfacet + facet normal 0.107301 0.099771 0.989208 + outer loop + vertex 1.04916 1.72872 2.61013 + vertex 1.054 1.72367 2.61012 + vertex 1.05423 1.72859 2.6096 + endloop + endfacet + facet normal 0.107173 0.0909381 0.990073 + outer loop + vertex 1.05423 1.72859 2.6096 + vertex 1.05339 1.73258 2.60932 + vertex 1.04916 1.72872 2.61013 + endloop + endfacet + facet normal 0.100294 0.0895498 0.99092 + outer loop + vertex 1.05423 1.72859 2.6096 + vertex 1.05821 1.73221 2.60887 + vertex 1.05339 1.73258 2.60932 + endloop + endfacet + facet normal 0.0998205 0.0825552 0.991575 + outer loop + vertex 1.05821 1.73221 2.60887 + vertex 1.05821 1.73708 2.60846 + vertex 1.05339 1.73258 2.60932 + endloop + endfacet + facet normal 0.102552 0.07962 0.991536 + outer loop + vertex 1.05339 1.73258 2.60932 + vertex 1.05821 1.73708 2.60846 + vertex 1.05324 1.73726 2.60896 + endloop + endfacet + facet normal 0.10661 0.0797154 0.9911 + outer loop + vertex 1.05339 1.73258 2.60932 + vertex 1.05324 1.73726 2.60896 + vertex 1.04948 1.73366 2.60965 + endloop + endfacet + facet normal 0.102407 0.0741734 0.991973 + outer loop + vertex 1.05821 1.73708 2.60846 + vertex 1.05836 1.74214 2.60807 + vertex 1.05324 1.73726 2.60896 + endloop + endfacet + facet normal 0.108219 0.0680482 0.991795 + outer loop + vertex 1.05324 1.73726 2.60896 + vertex 1.05836 1.74214 2.60807 + vertex 1.05324 1.74218 2.60862 + endloop + endfacet + facet normal 0.115416 0.0679941 0.990987 + outer loop + vertex 1.05324 1.73726 2.60896 + vertex 1.05324 1.74218 2.60862 + vertex 1.04858 1.73775 2.60947 + endloop + endfacet + facet normal 0.108219 0.0675596 0.991829 + outer loop + vertex 1.05836 1.74214 2.60807 + vertex 1.05845 1.7472 2.60771 + vertex 1.05324 1.74218 2.60862 + endloop + endfacet + facet normal 0.114706 0.0607665 0.991539 + outer loop + vertex 1.05324 1.74218 2.60862 + vertex 1.05845 1.7472 2.60771 + vertex 1.05337 1.74728 2.6083 + endloop + endfacet + facet normal 0.125187 0.0604167 0.990292 + outer loop + vertex 1.05324 1.74218 2.60862 + vertex 1.05337 1.74728 2.6083 + vertex 1.04833 1.74273 2.60921 + endloop + endfacet + facet normal 0.114746 0.0655271 0.991231 + outer loop + vertex 1.05845 1.7472 2.60771 + vertex 1.05832 1.75209 2.6074 + vertex 1.05337 1.74728 2.6083 + endloop + endfacet + facet normal 0.119792 0.0602791 0.990967 + outer loop + vertex 1.05337 1.74728 2.6083 + vertex 1.05832 1.75209 2.6074 + vertex 1.05345 1.75231 2.60798 + endloop + endfacet + facet normal 0.135687 0.0598804 0.988941 + outer loop + vertex 1.05337 1.74728 2.6083 + vertex 1.05345 1.75231 2.60798 + vertex 1.04836 1.74786 2.60895 + endloop + endfacet + facet normal 0.12012 0.0690617 0.990354 + outer loop + vertex 1.05832 1.75209 2.6074 + vertex 1.05796 1.75684 2.60712 + vertex 1.05345 1.75231 2.60798 + endloop + endfacet + facet normal 0.121956 0.0672175 0.990257 + outer loop + vertex 1.05345 1.75231 2.60798 + vertex 1.05796 1.75684 2.60712 + vertex 1.0533 1.75711 2.60767 + endloop + endfacet + facet normal 0.141941 0.0677029 0.987557 + outer loop + vertex 1.05345 1.75231 2.60798 + vertex 1.0533 1.75711 2.60767 + vertex 1.04866 1.75285 2.60863 + endloop + endfacet + facet normal 0.122517 0.0790327 0.989315 + outer loop + vertex 1.05796 1.75684 2.60712 + vertex 1.05686 1.7609 2.60693 + vertex 1.0533 1.75711 2.60767 + endloop + endfacet + facet normal 0.122434 0.0791114 0.989319 + outer loop + vertex 1.0533 1.75711 2.60767 + vertex 1.05686 1.7609 2.60693 + vertex 1.05285 1.76178 2.60735 + endloop + endfacet + facet normal 0.143401 0.0809255 0.98635 + outer loop + vertex 1.0533 1.75711 2.60767 + vertex 1.05285 1.76178 2.60735 + vertex 1.04875 1.75755 2.6083 + endloop + endfacet + facet normal 0.124392 0.0885121 0.988277 + outer loop + vertex 1.05686 1.7609 2.60693 + vertex 1.05675 1.76622 2.60647 + vertex 1.05285 1.76178 2.60735 + endloop + endfacet + facet normal 0.120753 0.0917436 0.988434 + outer loop + vertex 1.05285 1.76178 2.60735 + vertex 1.05675 1.76622 2.60647 + vertex 1.05169 1.76585 2.60712 + endloop + endfacet + facet normal 0.141444 0.097453 0.985138 + outer loop + vertex 1.05285 1.76178 2.60735 + vertex 1.05169 1.76585 2.60712 + vertex 1.04826 1.76216 2.60798 + endloop + endfacet + facet normal 0.11951 0.106459 0.987109 + outer loop + vertex 1.05162 1.77116 2.60655 + vertex 1.05169 1.76585 2.60712 + vertex 1.05675 1.76622 2.60647 + endloop + endfacet + facet normal 0.116379 0.103201 0.987829 + outer loop + vertex 1.05639 1.77116 2.60599 + vertex 1.05162 1.77116 2.60655 + vertex 1.05675 1.76622 2.60647 + endloop + endfacet + facet normal 0.102251 0.102327 0.989482 + outer loop + vertex 1.05639 1.77116 2.60599 + vertex 1.05675 1.76622 2.60647 + vertex 1.05961 1.76937 2.60584 + endloop + endfacet + facet normal 0.10819 0.113162 0.987669 + outer loop + vertex 1.05961 1.76937 2.60584 + vertex 1.05944 1.77403 2.60533 + vertex 1.05639 1.77116 2.60599 + endloop + endfacet + facet normal 0.108851 0.112458 0.987676 + outer loop + vertex 1.05458 1.77436 2.60583 + vertex 1.05639 1.77116 2.60599 + vertex 1.05944 1.77403 2.60533 + endloop + endfacet + facet normal 0.109155 0.117967 0.987 + outer loop + vertex 1.05458 1.77436 2.60583 + vertex 1.05944 1.77403 2.60533 + vertex 1.05462 1.77898 2.60527 + endloop + endfacet + facet normal 0.118149 0.117767 0.985988 + outer loop + vertex 1.05458 1.77436 2.60583 + vertex 1.05462 1.77898 2.60527 + vertex 1.05143 1.77608 2.606 + endloop + endfacet + facet normal 0.117063 0.115737 0.986358 + outer loop + vertex 1.05143 1.77608 2.606 + vertex 1.05162 1.77116 2.60655 + vertex 1.05458 1.77436 2.60583 + endloop + endfacet + facet normal 0.134549 0.116185 0.984072 + outer loop + vertex 1.05143 1.77608 2.606 + vertex 1.04676 1.77605 2.60664 + vertex 1.05162 1.77116 2.60655 + endloop + endfacet + facet normal 0.134436 0.12105 0.983501 + outer loop + vertex 1.05143 1.77608 2.606 + vertex 1.04986 1.77919 2.60583 + vertex 1.04676 1.77605 2.60664 + endloop + endfacet + facet normal 0.121144 0.114478 0.986012 + outer loop + vertex 1.04986 1.77919 2.60583 + vertex 1.05143 1.77608 2.606 + vertex 1.05462 1.77898 2.60527 + endloop + endfacet + facet normal 0.121199 0.116381 0.985782 + outer loop + vertex 1.04986 1.77919 2.60583 + vertex 1.05462 1.77898 2.60527 + vertex 1.05035 1.78351 2.60526 + endloop + endfacet + facet normal 0.113445 0.122127 0.98601 + outer loop + vertex 1.05462 1.77898 2.60527 + vertex 1.05944 1.77403 2.60533 + vertex 1.05972 1.77895 2.60469 + endloop + endfacet + facet normal 0.10782 0.122526 0.986591 + outer loop + vertex 1.05944 1.77403 2.60533 + vertex 1.06375 1.77785 2.60438 + vertex 1.05972 1.77895 2.60469 + endloop + endfacet + facet normal 0.106994 0.123452 0.986566 + outer loop + vertex 1.06464 1.77388 2.60478 + vertex 1.06375 1.77785 2.60438 + vertex 1.05944 1.77403 2.60533 + endloop + endfacet + facet normal 0.106808 0.111855 0.987968 + outer loop + vertex 1.05944 1.77403 2.60533 + vertex 1.06441 1.76894 2.60537 + vertex 1.06464 1.77388 2.60478 + endloop + endfacet + facet normal 0.109143 0.111718 0.987728 + outer loop + vertex 1.06441 1.76894 2.60537 + vertex 1.06872 1.77275 2.60446 + vertex 1.06464 1.77388 2.60478 + endloop + endfacet + facet normal 0.111558 0.120821 0.986386 + outer loop + vertex 1.06872 1.77275 2.60446 + vertex 1.06848 1.77738 2.60392 + vertex 1.06464 1.77388 2.60478 + endloop + endfacet + facet normal 0.110464 0.120781 0.986514 + outer loop + vertex 1.06872 1.77275 2.60446 + vertex 1.07326 1.77707 2.60342 + vertex 1.06848 1.77738 2.60392 + endloop + endfacet + facet normal 0.110774 0.126753 0.98573 + outer loop + vertex 1.07326 1.77707 2.60342 + vertex 1.07302 1.78185 2.60284 + vertex 1.06848 1.77738 2.60392 + endloop + endfacet + facet normal 0.109137 0.128406 0.985698 + outer loop + vertex 1.06848 1.77738 2.60392 + vertex 1.07302 1.78185 2.60284 + vertex 1.06823 1.78213 2.60333 + endloop + endfacet + facet normal 0.109189 0.128408 0.985692 + outer loop + vertex 1.06848 1.77738 2.60392 + vertex 1.06823 1.78213 2.60333 + vertex 1.06375 1.77785 2.60438 + endloop + endfacet + facet normal 0.108968 0.128638 0.985687 + outer loop + vertex 1.06375 1.77785 2.60438 + vertex 1.06823 1.78213 2.60333 + vertex 1.06346 1.78242 2.60382 + endloop + endfacet + facet normal 0.109431 0.128661 0.985632 + outer loop + vertex 1.06375 1.77785 2.60438 + vertex 1.06346 1.78242 2.60382 + vertex 1.05972 1.77895 2.60469 + endloop + endfacet + facet normal 0.111026 0.126954 0.985675 + outer loop + vertex 1.05972 1.77895 2.60469 + vertex 1.06346 1.78242 2.60382 + vertex 1.05884 1.78286 2.60428 + endloop + endfacet + facet normal 0.113402 0.127457 0.98534 + outer loop + vertex 1.05972 1.77895 2.60469 + vertex 1.05884 1.78286 2.60428 + vertex 1.05462 1.77898 2.60527 + endloop + endfacet + facet normal 0.117311 0.123221 0.985421 + outer loop + vertex 1.05462 1.77898 2.60527 + vertex 1.05884 1.78286 2.60428 + vertex 1.05497 1.78392 2.60461 + endloop + endfacet + facet normal 0.12751 0.122344 0.984263 + outer loop + vertex 1.05035 1.78351 2.60526 + vertex 1.05462 1.77898 2.60527 + vertex 1.05497 1.78392 2.60461 + endloop + endfacet + facet normal 0.127434 0.123075 0.984181 + outer loop + vertex 1.05497 1.78392 2.60461 + vertex 1.05387 1.78795 2.60425 + vertex 1.05035 1.78351 2.60526 + endloop + endfacet + facet normal 0.136058 0.116171 0.983866 + outer loop + vertex 1.05035 1.78351 2.60526 + vertex 1.05387 1.78795 2.60425 + vertex 1.04867 1.78921 2.60482 + endloop + endfacet + facet normal 0.144325 0.118495 0.98241 + outer loop + vertex 1.05035 1.78351 2.60526 + vertex 1.04867 1.78921 2.60482 + vertex 1.04536 1.78493 2.60582 + endloop + endfacet + facet normal 0.141561 0.108197 0.983999 + outer loop + vertex 1.04686 1.78097 2.60604 + vertex 1.05035 1.78351 2.60526 + vertex 1.04536 1.78493 2.60582 + endloop + endfacet + facet normal 0.160853 0.11531 0.980219 + outer loop + vertex 1.04536 1.78493 2.60582 + vertex 1.04245 1.78063 2.60681 + vertex 1.04686 1.78097 2.60604 + endloop + endfacet + facet normal 0.16078 0.116091 0.980139 + outer loop + vertex 1.04686 1.78097 2.60604 + vertex 1.04245 1.78063 2.60681 + vertex 1.04676 1.77605 2.60664 + endloop + endfacet + facet normal 0.138609 0.116927 0.98342 + outer loop + vertex 1.04686 1.78097 2.60604 + vertex 1.04676 1.77605 2.60664 + vertex 1.04986 1.77919 2.60583 + endloop + endfacet + facet normal 0.173915 0.106225 0.979015 + outer loop + vertex 1.04063 1.78631 2.60651 + vertex 1.04245 1.78063 2.60681 + vertex 1.04536 1.78493 2.60582 + endloop + endfacet + facet normal 0.177473 0.119564 0.976836 + outer loop + vertex 1.04536 1.78493 2.60582 + vertex 1.04403 1.78887 2.60558 + vertex 1.04063 1.78631 2.60651 + endloop + endfacet + facet normal 0.137096 0.114315 0.983939 + outer loop + vertex 1.04986 1.77919 2.60583 + vertex 1.05035 1.78351 2.60526 + vertex 1.04686 1.78097 2.60604 + endloop + endfacet + facet normal 0.15299 0.111655 0.9819 + outer loop + vertex 1.04403 1.78887 2.60558 + vertex 1.04536 1.78493 2.60582 + vertex 1.04867 1.78921 2.60482 + endloop + endfacet + facet normal 0.152941 0.112211 0.981844 + outer loop + vertex 1.04403 1.78887 2.60558 + vertex 1.04867 1.78921 2.60482 + vertex 1.04505 1.79339 2.60491 + endloop + endfacet + facet normal 0.157234 0.115942 0.980732 + outer loop + vertex 1.04505 1.79339 2.60491 + vertex 1.04867 1.78921 2.60482 + vertex 1.0498 1.79396 2.60408 + endloop + endfacet + facet normal 0.156762 0.119415 0.980391 + outer loop + vertex 1.0498 1.79396 2.60408 + vertex 1.04879 1.79791 2.60376 + vertex 1.04505 1.79339 2.60491 + endloop + endfacet + facet normal 0.168765 0.10928 0.97958 + outer loop + vertex 1.04505 1.79339 2.60491 + vertex 1.04879 1.79791 2.60376 + vertex 1.04367 1.79915 2.6045 + endloop + endfacet + facet normal 0.171351 0.121069 0.977743 + outer loop + vertex 1.04879 1.79791 2.60376 + vertex 1.04824 1.80256 2.60328 + vertex 1.04367 1.79915 2.6045 + endloop + endfacet + facet normal 0.154803 0.119403 0.980703 + outer loop + vertex 1.04879 1.79791 2.60376 + vertex 1.05265 1.80171 2.60269 + vertex 1.04824 1.80256 2.60328 + endloop + endfacet + facet normal 0.156103 0.127014 0.97954 + outer loop + vertex 1.05265 1.80171 2.60269 + vertex 1.05146 1.80572 2.60236 + vertex 1.04824 1.80256 2.60328 + endloop + endfacet + facet normal 0.162448 0.120508 0.979331 + outer loop + vertex 1.04824 1.80256 2.60328 + vertex 1.05146 1.80572 2.60236 + vertex 1.04773 1.80702 2.60281 + endloop + endfacet + facet normal 0.175579 0.121758 0.976907 + outer loop + vertex 1.04824 1.80256 2.60328 + vertex 1.04773 1.80702 2.60281 + vertex 1.04468 1.80393 2.60375 + endloop + endfacet + facet normal 0.164432 0.126593 0.978231 + outer loop + vertex 1.05146 1.80572 2.60236 + vertex 1.05143 1.81091 2.60169 + vertex 1.04773 1.80702 2.60281 + endloop + endfacet + facet normal 0.172892 0.118411 0.977797 + outer loop + vertex 1.04773 1.80702 2.60281 + vertex 1.05143 1.81091 2.60169 + vertex 1.04655 1.81093 2.60255 + endloop + endfacet + facet normal 0.189316 0.123088 0.974171 + outer loop + vertex 1.04773 1.80702 2.60281 + vertex 1.04655 1.81093 2.60255 + vertex 1.04357 1.80775 2.60353 + endloop + endfacet + facet normal 0.172866 0.119908 0.977619 + outer loop + vertex 1.04708 1.81617 2.60181 + vertex 1.04655 1.81093 2.60255 + vertex 1.05143 1.81091 2.60169 + endloop + endfacet + facet normal 0.188732 0.133135 0.972962 + outer loop + vertex 1.05147 1.8157 2.60103 + vertex 1.04708 1.81617 2.60181 + vertex 1.05143 1.81091 2.60169 + endloop + endfacet + facet normal 0.159123 0.134111 0.978107 + outer loop + vertex 1.05147 1.8157 2.60103 + vertex 1.05143 1.81091 2.60169 + vertex 1.05446 1.81405 2.60077 + endloop + endfacet + facet normal 0.15675 0.129684 0.979087 + outer loop + vertex 1.05446 1.81405 2.60077 + vertex 1.05468 1.8187 2.60012 + vertex 1.05147 1.8157 2.60103 + endloop + endfacet + facet normal 0.160573 0.125568 0.979004 + outer loop + vertex 1.0505 1.81832 2.60085 + vertex 1.05147 1.8157 2.60103 + vertex 1.05468 1.8187 2.60012 + endloop + endfacet + facet normal 0.138304 0.13092 0.981699 + outer loop + vertex 1.05446 1.81405 2.60077 + vertex 1.05946 1.81387 2.60009 + vertex 1.05468 1.8187 2.60012 + endloop + endfacet + facet normal 0.143486 0.136063 0.980254 + outer loop + vertex 1.05468 1.8187 2.60012 + vertex 1.05946 1.81387 2.60009 + vertex 1.05984 1.81893 2.59933 + endloop + endfacet + facet normal 0.143275 0.139277 0.979834 + outer loop + vertex 1.05984 1.81893 2.59933 + vertex 1.05892 1.82284 2.59891 + vertex 1.05468 1.8187 2.60012 + endloop + endfacet + facet normal 0.148254 0.134171 0.979806 + outer loop + vertex 1.05468 1.8187 2.60012 + vertex 1.05892 1.82284 2.59891 + vertex 1.05495 1.82376 2.59938 + endloop + endfacet + facet normal 0.176096 0.13202 0.97548 + outer loop + vertex 1.04957 1.82262 2.60051 + vertex 1.05468 1.8187 2.60012 + vertex 1.05495 1.82376 2.59938 + endloop + endfacet + facet normal 0.175801 0.133298 0.975359 + outer loop + vertex 1.05495 1.82376 2.59938 + vertex 1.05378 1.82782 2.59904 + vertex 1.04957 1.82262 2.60051 + endloop + endfacet + facet normal 0.187293 0.123746 0.974478 + outer loop + vertex 1.04957 1.82262 2.60051 + vertex 1.05378 1.82782 2.59904 + vertex 1.04874 1.8293 2.59982 + endloop + endfacet + facet normal 0.189272 0.131248 0.973114 + outer loop + vertex 1.05378 1.82782 2.59904 + vertex 1.05335 1.83259 2.59848 + vertex 1.04874 1.8293 2.59982 + endloop + endfacet + facet normal 0.15798 0.128468 0.97905 + outer loop + vertex 1.05495 1.82376 2.59938 + vertex 1.05838 1.82724 2.59837 + vertex 1.05378 1.82782 2.59904 + endloop + endfacet + facet normal 0.158767 0.135937 0.977913 + outer loop + vertex 1.05838 1.82724 2.59837 + vertex 1.05772 1.83171 2.59786 + vertex 1.05378 1.82782 2.59904 + endloop + endfacet + facet normal 0.164972 0.129589 0.977748 + outer loop + vertex 1.05378 1.82782 2.59904 + vertex 1.05772 1.83171 2.59786 + vertex 1.05335 1.83259 2.59848 + endloop + endfacet + facet normal 0.166278 0.136879 0.976533 + outer loop + vertex 1.05772 1.83171 2.59786 + vertex 1.05657 1.83572 2.59749 + vertex 1.05335 1.83259 2.59848 + endloop + endfacet + facet normal 0.17493 0.127856 0.976244 + outer loop + vertex 1.05335 1.83259 2.59848 + vertex 1.05657 1.83572 2.59749 + vertex 1.05288 1.83704 2.59798 + endloop + endfacet + facet normal 0.177115 0.134423 0.974967 + outer loop + vertex 1.05657 1.83572 2.59749 + vertex 1.05647 1.8409 2.59679 + vertex 1.05288 1.83704 2.59798 + endloop + endfacet + facet normal 0.149949 0.134504 0.979502 + outer loop + vertex 1.05647 1.8409 2.59679 + vertex 1.05657 1.83572 2.59749 + vertex 1.06159 1.83585 2.5967 + endloop + endfacet + facet normal 0.161422 0.146198 0.975996 + outer loop + vertex 1.06132 1.84079 2.59601 + vertex 1.05647 1.8409 2.59679 + vertex 1.06159 1.83585 2.5967 + endloop + endfacet + facet normal 0.137887 0.14546 0.979708 + outer loop + vertex 1.06132 1.84079 2.59601 + vertex 1.06159 1.83585 2.5967 + vertex 1.06468 1.83908 2.59579 + endloop + endfacet + facet normal 0.138072 0.145832 0.979627 + outer loop + vertex 1.06468 1.83908 2.59579 + vertex 1.06462 1.84391 2.59508 + vertex 1.06132 1.84079 2.59601 + endloop + endfacet + facet normal 0.142917 0.140724 0.979679 + outer loop + vertex 1.05953 1.84407 2.5958 + vertex 1.06132 1.84079 2.59601 + vertex 1.06462 1.84391 2.59508 + endloop + endfacet + facet normal 0.142921 0.141098 0.979625 + outer loop + vertex 1.05953 1.84407 2.5958 + vertex 1.06462 1.84391 2.59508 + vertex 1.05974 1.84892 2.59507 + endloop + endfacet + facet normal 0.150643 0.148611 0.977354 + outer loop + vertex 1.05974 1.84892 2.59507 + vertex 1.06462 1.84391 2.59508 + vertex 1.06487 1.84893 2.59428 + endloop + endfacet + facet normal 0.150666 0.147678 0.977492 + outer loop + vertex 1.06487 1.84893 2.59428 + vertex 1.06385 1.85284 2.59384 + vertex 1.05974 1.84892 2.59507 + endloop + endfacet + facet normal 0.141133 0.145384 0.979257 + outer loop + vertex 1.06487 1.84893 2.59428 + vertex 1.06818 1.85209 2.59333 + vertex 1.06385 1.85284 2.59384 + endloop + endfacet + facet normal 0.141815 0.149812 0.978491 + outer loop + vertex 1.06818 1.85209 2.59333 + vertex 1.06748 1.85647 2.59276 + vertex 1.06385 1.85284 2.59384 + endloop + endfacet + facet normal 0.147869 0.143754 0.978504 + outer loop + vertex 1.06385 1.85284 2.59384 + vertex 1.06748 1.85647 2.59276 + vertex 1.06322 1.85717 2.5933 + endloop + endfacet + facet normal 0.155925 0.144742 0.977106 + outer loop + vertex 1.06385 1.85284 2.59384 + vertex 1.06322 1.85717 2.5933 + vertex 1.06012 1.85395 2.59427 + endloop + endfacet + facet normal 0.148752 0.149916 0.977445 + outer loop + vertex 1.06748 1.85647 2.59276 + vertex 1.06628 1.86038 2.59234 + vertex 1.06322 1.85717 2.5933 + endloop + endfacet + facet normal 0.155751 0.14321 0.97736 + outer loop + vertex 1.06322 1.85717 2.5933 + vertex 1.06628 1.86038 2.59234 + vertex 1.06245 1.86154 2.59279 + endloop + endfacet + facet normal 0.166301 0.144842 0.975379 + outer loop + vertex 1.06322 1.85717 2.5933 + vertex 1.06245 1.86154 2.59279 + vertex 1.05895 1.85782 2.59393 + endloop + endfacet + facet normal 0.176775 0.134876 0.974966 + outer loop + vertex 1.05895 1.85782 2.59393 + vertex 1.06245 1.86154 2.59279 + vertex 1.0581 1.86242 2.59345 + endloop + endfacet + facet normal 0.178879 0.146953 0.972835 + outer loop + vertex 1.06245 1.86154 2.59279 + vertex 1.06127 1.86553 2.5924 + vertex 1.0581 1.86242 2.59345 + endloop + endfacet + facet normal 0.164176 0.142909 0.976024 + outer loop + vertex 1.06245 1.86154 2.59279 + vertex 1.0662 1.86554 2.59157 + vertex 1.06127 1.86553 2.5924 + endloop + endfacet + facet normal 0.164199 0.142069 0.976143 + outer loop + vertex 1.06131 1.87071 2.59164 + vertex 1.06127 1.86553 2.5924 + vertex 1.0662 1.86554 2.59157 + endloop + endfacet + facet normal 0.176657 0.153922 0.972163 + outer loop + vertex 1.06605 1.87053 2.59081 + vertex 1.06131 1.87071 2.59164 + vertex 1.0662 1.86554 2.59157 + endloop + endfacet + facet normal 0.154422 0.153829 0.975956 + outer loop + vertex 1.06605 1.87053 2.59081 + vertex 1.0662 1.86554 2.59157 + vertex 1.06932 1.86875 2.59057 + endloop + endfacet + facet normal 0.152777 0.150694 0.976704 + outer loop + vertex 1.06932 1.86875 2.59057 + vertex 1.06942 1.87367 2.58979 + vertex 1.06605 1.87053 2.59081 + endloop + endfacet + facet normal 0.158638 0.144415 0.976718 + outer loop + vertex 1.06441 1.87386 2.59058 + vertex 1.06605 1.87053 2.59081 + vertex 1.06942 1.87367 2.58979 + endloop + endfacet + facet normal 0.158594 0.141264 0.977186 + outer loop + vertex 1.06441 1.87386 2.59058 + vertex 1.06942 1.87367 2.58979 + vertex 1.06467 1.87876 2.58983 + endloop + endfacet + facet normal 0.132716 0.151525 0.979503 + outer loop + vertex 1.06932 1.86875 2.59057 + vertex 1.07444 1.86868 2.58989 + vertex 1.06942 1.87367 2.58979 + endloop + endfacet + facet normal 0.142358 0.161155 0.976608 + outer loop + vertex 1.06942 1.87367 2.58979 + vertex 1.07444 1.86868 2.58989 + vertex 1.07464 1.87371 2.58903 + endloop + endfacet + facet normal 0.120987 0.162496 0.979264 + outer loop + vertex 1.07444 1.86868 2.58989 + vertex 1.07867 1.87261 2.58871 + vertex 1.07464 1.87371 2.58903 + endloop + endfacet + facet normal 0.121565 0.164757 0.978814 + outer loop + vertex 1.07867 1.87261 2.58871 + vertex 1.07783 1.87703 2.58807 + vertex 1.07464 1.87371 2.58903 + endloop + endfacet + facet normal 0.12929 0.157425 0.979031 + outer loop + vertex 1.07464 1.87371 2.58903 + vertex 1.07783 1.87703 2.58807 + vertex 1.07343 1.87746 2.58858 + endloop + endfacet + facet normal 0.111745 0.163093 0.980262 + outer loop + vertex 1.07867 1.87261 2.58871 + vertex 1.08248 1.87645 2.58764 + vertex 1.07783 1.87703 2.58807 + endloop + endfacet + facet normal 0.111797 0.163564 0.980178 + outer loop + vertex 1.08248 1.87645 2.58764 + vertex 1.08108 1.88167 2.58693 + vertex 1.07783 1.87703 2.58807 + endloop + endfacet + facet normal 0.119504 0.158156 0.980156 + outer loop + vertex 1.07783 1.87703 2.58807 + vertex 1.08108 1.88167 2.58693 + vertex 1.07639 1.88072 2.58765 + endloop + endfacet + facet normal 0.108873 0.162842 0.980627 + outer loop + vertex 1.08248 1.87645 2.58764 + vertex 1.08697 1.87989 2.58657 + vertex 1.08108 1.88167 2.58693 + endloop + endfacet + facet normal 0.110065 0.166947 0.979803 + outer loop + vertex 1.08697 1.87989 2.58657 + vertex 1.08548 1.88489 2.58588 + vertex 1.08108 1.88167 2.58693 + endloop + endfacet + facet normal 0.112609 0.163557 0.980086 + outer loop + vertex 1.08131 1.88632 2.58612 + vertex 1.08108 1.88167 2.58693 + vertex 1.08548 1.88489 2.58588 + endloop + endfacet + facet normal 0.113118 0.165085 0.979771 + outer loop + vertex 1.08548 1.88489 2.58588 + vertex 1.08408 1.88979 2.58522 + vertex 1.08131 1.88632 2.58612 + endloop + endfacet + facet normal 0.117774 0.161385 0.979839 + outer loop + vertex 1.07949 1.88931 2.58585 + vertex 1.08131 1.88632 2.58612 + vertex 1.08408 1.88979 2.58522 + endloop + endfacet + facet normal 0.117903 0.160359 0.979992 + outer loop + vertex 1.07949 1.88931 2.58585 + vertex 1.08408 1.88979 2.58522 + vertex 1.07958 1.89402 2.58507 + endloop + endfacet + facet normal 0.122768 0.165484 0.978541 + outer loop + vertex 1.07958 1.89402 2.58507 + vertex 1.08408 1.88979 2.58522 + vertex 1.08475 1.89409 2.58441 + endloop + endfacet + facet normal 0.122534 0.172515 0.977356 + outer loop + vertex 1.08475 1.89409 2.58441 + vertex 1.08373 1.89774 2.58389 + vertex 1.07958 1.89402 2.58507 + endloop + endfacet + facet normal 0.125551 0.169201 0.977552 + outer loop + vertex 1.07958 1.89402 2.58507 + vertex 1.08373 1.89774 2.58389 + vertex 1.07983 1.89886 2.5842 + endloop + endfacet + facet normal 0.126699 0.173436 0.976661 + outer loop + vertex 1.08373 1.89774 2.58389 + vertex 1.08289 1.90205 2.58324 + vertex 1.07983 1.89886 2.5842 + endloop + endfacet + facet normal 0.13249 0.167925 0.976856 + outer loop + vertex 1.07983 1.89886 2.5842 + vertex 1.08289 1.90205 2.58324 + vertex 1.0786 1.90254 2.58373 + endloop + endfacet + facet normal 0.132868 0.171942 0.976106 + outer loop + vertex 1.08289 1.90205 2.58324 + vertex 1.08145 1.90573 2.58278 + vertex 1.0786 1.90254 2.58373 + endloop + endfacet + facet normal 0.141355 0.164388 0.976215 + outer loop + vertex 1.0786 1.90254 2.58373 + vertex 1.08145 1.90573 2.58278 + vertex 1.0778 1.9068 2.58313 + endloop + endfacet + facet normal 0.14098 0.163009 0.9765 + outer loop + vertex 1.08145 1.90573 2.58278 + vertex 1.08142 1.91088 2.58193 + vertex 1.0778 1.9068 2.58313 + endloop + endfacet + facet normal 0.148883 0.155993 0.976473 + outer loop + vertex 1.0778 1.9068 2.58313 + vertex 1.08142 1.91088 2.58193 + vertex 1.07649 1.91062 2.58272 + endloop + endfacet + facet normal 0.167023 0.161792 0.972588 + outer loop + vertex 1.0778 1.9068 2.58313 + vertex 1.07649 1.91062 2.58272 + vertex 1.07354 1.90759 2.58373 + endloop + endfacet + facet normal 0.148855 0.156359 0.976419 + outer loop + vertex 1.07648 1.91574 2.5819 + vertex 1.07649 1.91062 2.58272 + vertex 1.08142 1.91088 2.58193 + endloop + endfacet + facet normal 0.159656 0.167339 0.972886 + outer loop + vertex 1.08137 1.91577 2.5811 + vertex 1.07648 1.91574 2.5819 + vertex 1.08142 1.91088 2.58193 + endloop + endfacet + facet normal 0.138241 0.167669 0.976103 + outer loop + vertex 1.08137 1.91577 2.5811 + vertex 1.08142 1.91088 2.58193 + vertex 1.0846 1.91433 2.58089 + endloop + endfacet + facet normal 0.139368 0.170287 0.975489 + outer loop + vertex 1.0846 1.91433 2.58089 + vertex 1.08465 1.91901 2.58006 + vertex 1.08137 1.91577 2.5811 + endloop + endfacet + facet normal 0.145151 0.164492 0.97564 + outer loop + vertex 1.07968 1.91895 2.58081 + vertex 1.08137 1.91577 2.5811 + vertex 1.08465 1.91901 2.58006 + endloop + endfacet + facet normal 0.145085 0.16629 0.975345 + outer loop + vertex 1.07968 1.91895 2.58081 + vertex 1.08465 1.91901 2.58006 + vertex 1.07979 1.92375 2.57997 + endloop + endfacet + facet normal 0.155155 0.176536 0.971989 + outer loop + vertex 1.07979 1.92375 2.57997 + vertex 1.08465 1.91901 2.58006 + vertex 1.08481 1.92373 2.57918 + endloop + endfacet + facet normal 0.155062 0.180468 0.971281 + outer loop + vertex 1.08481 1.92373 2.57918 + vertex 1.08352 1.92739 2.5787 + vertex 1.07979 1.92375 2.57997 + endloop + endfacet + facet normal 0.164154 0.171212 0.971463 + outer loop + vertex 1.07979 1.92375 2.57997 + vertex 1.08352 1.92739 2.5787 + vertex 1.07986 1.92869 2.57909 + endloop + endfacet + facet normal 0.187266 0.170186 0.967455 + outer loop + vertex 1.07538 1.92834 2.58002 + vertex 1.07979 1.92375 2.57997 + vertex 1.07986 1.92869 2.57909 + endloop + endfacet + facet normal 0.17422 0.157586 0.972015 + outer loop + vertex 1.07488 1.92385 2.58084 + vertex 1.07979 1.92375 2.57997 + vertex 1.07538 1.92834 2.58002 + endloop + endfacet + facet normal 0.174227 0.156793 0.972142 + outer loop + vertex 1.07488 1.92385 2.58084 + vertex 1.07642 1.92062 2.58108 + vertex 1.07979 1.92375 2.57997 + endloop + endfacet + facet normal 0.16638 0.165245 0.972117 + outer loop + vertex 1.07968 1.91895 2.58081 + vertex 1.07979 1.92375 2.57997 + vertex 1.07642 1.92062 2.58108 + endloop + endfacet + facet normal 0.166282 0.165045 0.972168 + outer loop + vertex 1.07642 1.92062 2.58108 + vertex 1.07648 1.91574 2.5819 + vertex 1.07968 1.91895 2.58081 + endloop + endfacet + facet normal 0.196952 0.16446 0.966521 + outer loop + vertex 1.07642 1.92062 2.58108 + vertex 1.07168 1.92078 2.58202 + vertex 1.07648 1.91574 2.5819 + endloop + endfacet + facet normal 0.182924 0.151018 0.971459 + outer loop + vertex 1.07168 1.92078 2.58202 + vertex 1.07169 1.91592 2.58278 + vertex 1.07648 1.91574 2.5819 + endloop + endfacet + facet normal 0.182902 0.148935 0.971785 + outer loop + vertex 1.07275 1.9121 2.58316 + vertex 1.07648 1.91574 2.5819 + vertex 1.07169 1.91592 2.58278 + endloop + endfacet + facet normal 0.176336 0.155709 0.971936 + outer loop + vertex 1.07649 1.91062 2.58272 + vertex 1.07648 1.91574 2.5819 + vertex 1.07275 1.9121 2.58316 + endloop + endfacet + facet normal 0.19695 0.167182 0.966054 + outer loop + vertex 1.07642 1.92062 2.58108 + vertex 1.07488 1.92385 2.58084 + vertex 1.07168 1.92078 2.58202 + endloop + endfacet + facet normal 0.164619 0.172618 0.971135 + outer loop + vertex 1.08352 1.92739 2.5787 + vertex 1.08263 1.93167 2.57809 + vertex 1.07986 1.92869 2.57909 + endloop + endfacet + facet normal 0.178496 0.159644 0.970903 + outer loop + vertex 1.07986 1.92869 2.57909 + vertex 1.08263 1.93167 2.57809 + vertex 1.07834 1.93257 2.57873 + endloop + endfacet + facet normal 0.179381 0.164574 0.969916 + outer loop + vertex 1.08263 1.93167 2.57809 + vertex 1.0813 1.93553 2.57769 + vertex 1.07834 1.93257 2.57873 + endloop + endfacet + facet normal 0.168072 0.160959 0.972545 + outer loop + vertex 1.08263 1.93167 2.57809 + vertex 1.08628 1.93551 2.57683 + vertex 1.0813 1.93553 2.57769 + endloop + endfacet + facet normal 0.16815 0.157737 0.973059 + outer loop + vertex 1.08153 1.94057 2.57683 + vertex 1.0813 1.93553 2.57769 + vertex 1.08628 1.93551 2.57683 + endloop + endfacet + facet normal 0.182342 0.171062 0.96824 + outer loop + vertex 1.08629 1.9405 2.57595 + vertex 1.08153 1.94057 2.57683 + vertex 1.08628 1.93551 2.57683 + endloop + endfacet + facet normal 0.164868 0.171608 0.971272 + outer loop + vertex 1.08629 1.9405 2.57595 + vertex 1.08628 1.93551 2.57683 + vertex 1.08952 1.93884 2.57569 + endloop + endfacet + facet normal 0.164338 0.170533 0.971551 + outer loop + vertex 1.08952 1.93884 2.57569 + vertex 1.08965 1.94368 2.57482 + vertex 1.08629 1.9405 2.57595 + endloop + endfacet + facet normal 0.149686 0.171323 0.973778 + outer loop + vertex 1.08952 1.93884 2.57569 + vertex 1.09451 1.93891 2.57491 + vertex 1.08965 1.94368 2.57482 + endloop + endfacet + facet normal 0.160962 0.18273 0.969897 + outer loop + vertex 1.08965 1.94368 2.57482 + vertex 1.09451 1.93891 2.57491 + vertex 1.09465 1.9437 2.57398 + endloop + endfacet + facet normal 0.160968 0.18257 0.969927 + outer loop + vertex 1.09465 1.9437 2.57398 + vertex 1.09333 1.94736 2.57352 + vertex 1.08965 1.94368 2.57482 + endloop + endfacet + facet normal 0.17046 0.173106 0.97004 + outer loop + vertex 1.08965 1.94368 2.57482 + vertex 1.09333 1.94736 2.57352 + vertex 1.08965 1.94862 2.57394 + endloop + endfacet + facet normal 0.185479 0.172631 0.967366 + outer loop + vertex 1.08521 1.94815 2.57487 + vertex 1.08965 1.94368 2.57482 + vertex 1.08965 1.94862 2.57394 + endloop + endfacet + facet normal 0.186332 0.166383 0.968296 + outer loop + vertex 1.08965 1.94862 2.57394 + vertex 1.08799 1.95247 2.5736 + vertex 1.08521 1.94815 2.57487 + endloop + endfacet + facet normal 0.184215 0.165518 0.968849 + outer loop + vertex 1.08965 1.94862 2.57394 + vertex 1.09246 1.95165 2.57288 + vertex 1.08799 1.95247 2.5736 + endloop + endfacet + facet normal 0.185159 0.171753 0.967583 + outer loop + vertex 1.09246 1.95165 2.57288 + vertex 1.09119 1.95667 2.57224 + vertex 1.08799 1.95247 2.5736 + endloop + endfacet + facet normal 0.175931 0.169687 0.969667 + outer loop + vertex 1.09246 1.95165 2.57288 + vertex 1.09666 1.95458 2.57161 + vertex 1.09119 1.95667 2.57224 + endloop + endfacet + facet normal 0.167393 0.181613 0.969018 + outer loop + vertex 1.09623 1.95012 2.57252 + vertex 1.09666 1.95458 2.57161 + vertex 1.09246 1.95165 2.57288 + endloop + endfacet + facet normal 0.165283 0.176071 0.970402 + outer loop + vertex 1.09333 1.94736 2.57352 + vertex 1.09623 1.95012 2.57252 + vertex 1.09246 1.95165 2.57288 + endloop + endfacet + facet normal 0.156311 0.185405 0.97015 + outer loop + vertex 1.09754 1.94652 2.573 + vertex 1.09623 1.95012 2.57252 + vertex 1.09333 1.94736 2.57352 + endloop + endfacet + facet normal 0.151048 0.183647 0.971318 + outer loop + vertex 1.09754 1.94652 2.573 + vertex 1.10118 1.95025 2.57173 + vertex 1.09623 1.95012 2.57252 + endloop + endfacet + facet normal 0.146092 0.188421 0.971161 + outer loop + vertex 1.10126 1.9453 2.57267 + vertex 1.10118 1.95025 2.57173 + vertex 1.09754 1.94652 2.573 + endloop + endfacet + facet normal 0.14546 0.186354 0.971655 + outer loop + vertex 1.09839 1.94241 2.57366 + vertex 1.10126 1.9453 2.57267 + vertex 1.09754 1.94652 2.573 + endloop + endfacet + facet normal 0.149304 0.187039 0.97094 + outer loop + vertex 1.09839 1.94241 2.57366 + vertex 1.09754 1.94652 2.573 + vertex 1.09465 1.9437 2.57398 + endloop + endfacet + facet normal 0.142214 0.189531 0.971521 + outer loop + vertex 1.1026 1.94167 2.57319 + vertex 1.10126 1.9453 2.57267 + vertex 1.09839 1.94241 2.57366 + endloop + endfacet + facet normal 0.141996 0.188098 0.971831 + outer loop + vertex 1.0996 1.9389 2.57416 + vertex 1.1026 1.94167 2.57319 + vertex 1.09839 1.94241 2.57366 + endloop + endfacet + facet normal 0.143469 0.188558 0.971526 + outer loop + vertex 1.0996 1.9389 2.57416 + vertex 1.09839 1.94241 2.57366 + vertex 1.09451 1.93891 2.57491 + endloop + endfacet + facet normal 0.14349 0.18774 0.971681 + outer loop + vertex 1.09451 1.93891 2.57491 + vertex 1.09903 1.93462 2.57507 + vertex 1.0996 1.9389 2.57416 + endloop + endfacet + facet normal 0.139809 0.188314 0.972107 + outer loop + vertex 1.09903 1.93462 2.57507 + vertex 1.10341 1.93749 2.57388 + vertex 1.0996 1.9389 2.57416 + endloop + endfacet + facet normal 0.138577 0.190117 0.971932 + outer loop + vertex 1.10484 1.93267 2.57463 + vertex 1.10341 1.93749 2.57388 + vertex 1.09903 1.93462 2.57507 + endloop + endfacet + facet normal 0.138322 0.189315 0.972125 + outer loop + vertex 1.09903 1.93462 2.57507 + vertex 1.10038 1.92964 2.57585 + vertex 1.10484 1.93267 2.57463 + endloop + endfacet + facet normal 0.137703 0.190192 0.972042 + outer loop + vertex 1.10038 1.92964 2.57585 + vertex 1.10446 1.92821 2.57555 + vertex 1.10484 1.93267 2.57463 + endloop + endfacet + facet normal 0.135835 0.190395 0.972265 + outer loop + vertex 1.10446 1.92821 2.57555 + vertex 1.10941 1.92865 2.57477 + vertex 1.10484 1.93267 2.57463 + endloop + endfacet + facet normal 0.138763 0.193692 0.971199 + outer loop + vertex 1.10484 1.93267 2.57463 + vertex 1.10941 1.92865 2.57477 + vertex 1.10958 1.9334 2.5738 + endloop + endfacet + facet normal 0.139208 0.191267 0.971616 + outer loop + vertex 1.10958 1.9334 2.5738 + vertex 1.10796 1.93701 2.57332 + vertex 1.10484 1.93267 2.57463 + endloop + endfacet + facet normal 0.136279 0.190041 0.972272 + outer loop + vertex 1.10958 1.9334 2.5738 + vertex 1.11253 1.93651 2.57278 + vertex 1.10796 1.93701 2.57332 + endloop + endfacet + facet normal 0.136456 0.192146 0.971833 + outer loop + vertex 1.11253 1.93651 2.57278 + vertex 1.11094 1.94148 2.57202 + vertex 1.10796 1.93701 2.57332 + endloop + endfacet + facet normal 0.139341 0.190214 0.971804 + outer loop + vertex 1.10796 1.93701 2.57332 + vertex 1.11094 1.94148 2.57202 + vertex 1.1063 1.94064 2.57285 + endloop + endfacet + facet normal 0.140206 0.190583 0.971607 + outer loop + vertex 1.10796 1.93701 2.57332 + vertex 1.1063 1.94064 2.57285 + vertex 1.10341 1.93749 2.57388 + endloop + endfacet + facet normal 0.140912 0.189943 0.97163 + outer loop + vertex 1.10341 1.93749 2.57388 + vertex 1.1063 1.94064 2.57285 + vertex 1.1026 1.94167 2.57319 + endloop + endfacet + facet normal 0.141076 0.190579 0.971482 + outer loop + vertex 1.1063 1.94064 2.57285 + vertex 1.10617 1.94567 2.57188 + vertex 1.1026 1.94167 2.57319 + endloop + endfacet + facet normal 0.139264 0.190582 0.971743 + outer loop + vertex 1.10617 1.94567 2.57188 + vertex 1.1063 1.94064 2.57285 + vertex 1.11094 1.94148 2.57202 + endloop + endfacet + facet normal 0.141221 0.19279 0.971024 + outer loop + vertex 1.11114 1.94611 2.57107 + vertex 1.10617 1.94567 2.57188 + vertex 1.11094 1.94148 2.57202 + endloop + endfacet + facet normal 0.134171 0.193273 0.971928 + outer loop + vertex 1.11114 1.94611 2.57107 + vertex 1.11094 1.94148 2.57202 + vertex 1.11532 1.94458 2.5708 + endloop + endfacet + facet normal 0.134343 0.193766 0.971806 + outer loop + vertex 1.11532 1.94458 2.5708 + vertex 1.11389 1.94958 2.57 + vertex 1.11114 1.94611 2.57107 + endloop + endfacet + facet normal 0.139049 0.190061 0.971876 + outer loop + vertex 1.1093 1.94914 2.57074 + vertex 1.11114 1.94611 2.57107 + vertex 1.11389 1.94958 2.57 + endloop + endfacet + facet normal 0.138974 0.190661 0.971769 + outer loop + vertex 1.1093 1.94914 2.57074 + vertex 1.11389 1.94958 2.57 + vertex 1.10928 1.95384 2.56982 + endloop + endfacet + facet normal 0.142086 0.190586 0.971333 + outer loop + vertex 1.1093 1.94914 2.57074 + vertex 1.10928 1.95384 2.56982 + vertex 1.10604 1.95054 2.57095 + endloop + endfacet + facet normal 0.142146 0.190732 0.971296 + outer loop + vertex 1.10604 1.95054 2.57095 + vertex 1.10617 1.94567 2.57188 + vertex 1.1093 1.94914 2.57074 + endloop + endfacet + facet normal 0.144462 0.190724 0.970956 + outer loop + vertex 1.10604 1.95054 2.57095 + vertex 1.10118 1.95025 2.57173 + vertex 1.10617 1.94567 2.57188 + endloop + endfacet + facet normal 0.144316 0.192368 0.970653 + outer loop + vertex 1.10604 1.95054 2.57095 + vertex 1.10433 1.95365 2.57058 + vertex 1.10118 1.95025 2.57173 + endloop + endfacet + facet normal 0.145765 0.19104 0.970699 + outer loop + vertex 1.10109 1.95507 2.57079 + vertex 1.10118 1.95025 2.57173 + vertex 1.10433 1.95365 2.57058 + endloop + endfacet + facet normal 0.145586 0.190616 0.970809 + outer loop + vertex 1.10433 1.95365 2.57058 + vertex 1.10436 1.95836 2.56965 + vertex 1.10109 1.95507 2.57079 + endloop + endfacet + facet normal 0.149107 0.187153 0.970949 + outer loop + vertex 1.09938 1.9581 2.57047 + vertex 1.10109 1.95507 2.57079 + vertex 1.10436 1.95836 2.56965 + endloop + endfacet + facet normal 0.149092 0.187331 0.970916 + outer loop + vertex 1.09938 1.9581 2.57047 + vertex 1.10436 1.95836 2.56965 + vertex 1.09988 1.96254 2.56954 + endloop + endfacet + facet normal 0.153819 0.192343 0.969198 + outer loop + vertex 1.09988 1.96254 2.56954 + vertex 1.10436 1.95836 2.56965 + vertex 1.10434 1.96307 2.56872 + endloop + endfacet + facet normal 0.153781 0.192597 0.969153 + outer loop + vertex 1.10434 1.96307 2.56872 + vertex 1.10287 1.96667 2.56824 + vertex 1.09988 1.96254 2.56954 + endloop + endfacet + facet normal 0.145444 0.189462 0.971056 + outer loop + vertex 1.10434 1.96307 2.56872 + vertex 1.10667 1.96567 2.56787 + vertex 1.10287 1.96667 2.56824 + endloop + endfacet + facet normal 0.145723 0.190625 0.970787 + outer loop + vertex 1.10667 1.96567 2.56787 + vertex 1.10645 1.97054 2.56694 + vertex 1.10287 1.96667 2.56824 + endloop + endfacet + facet normal 0.152644 0.184284 0.970948 + outer loop + vertex 1.10287 1.96667 2.56824 + vertex 1.10645 1.97054 2.56694 + vertex 1.10141 1.97047 2.56775 + endloop + endfacet + facet normal 0.166902 0.189357 0.967619 + outer loop + vertex 1.10287 1.96667 2.56824 + vertex 1.10141 1.97047 2.56775 + vertex 1.09839 1.96752 2.56885 + endloop + endfacet + facet normal 0.177881 0.178214 0.96778 + outer loop + vertex 1.09839 1.96752 2.56885 + vertex 1.10141 1.97047 2.56775 + vertex 1.09769 1.97197 2.56816 + endloop + endfacet + facet normal 0.178442 0.179709 0.9674 + outer loop + vertex 1.10141 1.97047 2.56775 + vertex 1.10138 1.9755 2.56682 + vertex 1.09769 1.97197 2.56816 + endloop + endfacet + facet normal 0.189787 0.167844 0.967372 + outer loop + vertex 1.09769 1.97197 2.56816 + vertex 1.10138 1.9755 2.56682 + vertex 1.09665 1.97574 2.56771 + endloop + endfacet + facet normal 0.207357 0.172202 0.96299 + outer loop + vertex 1.09769 1.97197 2.56816 + vertex 1.09665 1.97574 2.56771 + vertex 1.09431 1.9734 2.56863 + endloop + endfacet + facet normal 0.206856 0.170905 0.963329 + outer loop + vertex 1.09363 1.96913 2.56953 + vertex 1.09769 1.97197 2.56816 + vertex 1.09431 1.9734 2.56863 + endloop + endfacet + facet normal 0.220514 0.158795 0.962371 + outer loop + vertex 1.09431 1.9734 2.56863 + vertex 1.09665 1.97574 2.56771 + vertex 1.09297 1.97712 2.56832 + endloop + endfacet + facet normal 0.189765 0.166594 0.967593 + outer loop + vertex 1.09643 1.98068 2.5669 + vertex 1.09665 1.97574 2.56771 + vertex 1.10138 1.9755 2.56682 + endloop + endfacet + facet normal 0.152808 0.180364 0.971658 + outer loop + vertex 1.10138 1.9755 2.56682 + vertex 1.10141 1.97047 2.56775 + vertex 1.10645 1.97054 2.56694 + endloop + endfacet + facet normal 0.167765 0.195507 0.966246 + outer loop + vertex 1.10632 1.9754 2.56598 + vertex 1.10138 1.9755 2.56682 + vertex 1.10645 1.97054 2.56694 + endloop + endfacet + facet normal 0.145777 0.195618 0.969785 + outer loop + vertex 1.10632 1.9754 2.56598 + vertex 1.10645 1.97054 2.56694 + vertex 1.10966 1.9738 2.5658 + endloop + endfacet + facet normal 0.147569 0.199512 0.96872 + outer loop + vertex 1.10966 1.9738 2.5658 + vertex 1.10956 1.97861 2.56483 + vertex 1.10632 1.9754 2.56598 + endloop + endfacet + facet normal 0.154583 0.192551 0.969035 + outer loop + vertex 1.10456 1.97865 2.56562 + vertex 1.10632 1.9754 2.56598 + vertex 1.10956 1.97861 2.56483 + endloop + endfacet + facet normal 0.154619 0.19104 0.969328 + outer loop + vertex 1.10456 1.97865 2.56562 + vertex 1.10956 1.97861 2.56483 + vertex 1.10445 1.98351 2.56468 + endloop + endfacet + facet normal 0.169785 0.206697 0.963561 + outer loop + vertex 1.10445 1.98351 2.56468 + vertex 1.10956 1.97861 2.56483 + vertex 1.10934 1.98332 2.56386 + endloop + endfacet + facet normal 0.169789 0.20811 0.963256 + outer loop + vertex 1.10934 1.98332 2.56386 + vertex 1.10794 1.98694 2.56332 + vertex 1.10445 1.98351 2.56468 + endloop + endfacet + facet normal 0.154254 0.202672 0.967021 + outer loop + vertex 1.10934 1.98332 2.56386 + vertex 1.11159 1.98585 2.56297 + vertex 1.10794 1.98694 2.56332 + endloop + endfacet + facet normal 0.153358 0.199423 0.967839 + outer loop + vertex 1.11159 1.98585 2.56297 + vertex 1.1113 1.99067 2.56202 + vertex 1.10794 1.98694 2.56332 + endloop + endfacet + facet normal 0.141268 0.199071 0.969749 + outer loop + vertex 1.1113 1.99067 2.56202 + vertex 1.11159 1.98585 2.56297 + vertex 1.11602 1.9865 2.56219 + endloop + endfacet + facet normal 0.146561 0.204996 0.967728 + outer loop + vertex 1.11622 1.99104 2.5612 + vertex 1.1113 1.99067 2.56202 + vertex 1.11602 1.9865 2.56219 + endloop + endfacet + facet normal 0.144351 0.205159 0.968025 + outer loop + vertex 1.11622 1.99104 2.5612 + vertex 1.11602 1.9865 2.56219 + vertex 1.12035 1.98963 2.56088 + endloop + endfacet + facet normal 0.146643 0.204243 0.967874 + outer loop + vertex 1.11622 1.99104 2.5612 + vertex 1.11441 1.99402 2.56084 + vertex 1.1113 1.99067 2.56202 + endloop + endfacet + facet normal 0.143601 0.202492 0.968698 + outer loop + vertex 1.11441 1.99402 2.56084 + vertex 1.11622 1.99104 2.5612 + vertex 1.119 1.99458 2.56004 + endloop + endfacet + facet normal 0.145349 0.191062 0.970757 + outer loop + vertex 1.11441 1.99402 2.56084 + vertex 1.119 1.99458 2.56004 + vertex 1.11447 1.9988 2.55989 + endloop + endfacet + facet normal 0.149063 0.195004 0.969409 + outer loop + vertex 1.11447 1.9988 2.55989 + vertex 1.119 1.99458 2.56004 + vertex 1.11956 1.99888 2.55909 + endloop + endfacet + facet normal 0.149257 0.190759 0.970223 + outer loop + vertex 1.11956 1.99888 2.55909 + vertex 1.11833 2.00236 2.5586 + vertex 1.11447 1.9988 2.55989 + endloop + endfacet + facet normal 0.152829 0.191898 0.969442 + outer loop + vertex 1.11956 1.99888 2.55909 + vertex 1.12253 2.00159 2.55809 + vertex 1.11833 2.00236 2.5586 + endloop + endfacet + facet normal 0.152069 0.187045 0.97051 + outer loop + vertex 1.12253 2.00159 2.55809 + vertex 1.12117 2.00521 2.5576 + vertex 1.11833 2.00236 2.5586 + endloop + endfacet + facet normal 0.15218 0.186935 0.970513 + outer loop + vertex 1.11833 2.00236 2.5586 + vertex 1.12117 2.00521 2.5576 + vertex 1.11747 2.00644 2.55795 + endloop + endfacet + facet normal 0.151637 0.186837 0.970617 + outer loop + vertex 1.11833 2.00236 2.5586 + vertex 1.11747 2.00644 2.55795 + vertex 1.1146 2.00362 2.55894 + endloop + endfacet + facet normal 0.151788 0.18567 0.970818 + outer loop + vertex 1.12117 2.00521 2.5576 + vertex 1.1211 2.01015 2.55667 + vertex 1.11747 2.00644 2.55795 + endloop + endfacet + facet normal 0.154946 0.182605 0.9709 + outer loop + vertex 1.11747 2.00644 2.55795 + vertex 1.1211 2.01015 2.55667 + vertex 1.11618 2.01003 2.55748 + endloop + endfacet + facet normal 0.157416 0.183419 0.970349 + outer loop + vertex 1.11747 2.00644 2.55795 + vertex 1.11618 2.01003 2.55748 + vertex 1.11329 2.00728 2.55847 + endloop + endfacet + facet normal 0.168818 0.171533 0.970606 + outer loop + vertex 1.11329 2.00728 2.55847 + vertex 1.11618 2.01003 2.55748 + vertex 1.11248 2.01159 2.55785 + endloop + endfacet + facet normal 0.163418 0.185486 0.968963 + outer loop + vertex 1.1211 2.01015 2.55667 + vertex 1.12117 2.00521 2.5576 + vertex 1.12609 2.00536 2.55675 + endloop + endfacet + facet normal 0.163093 0.190824 0.967981 + outer loop + vertex 1.12253 2.00159 2.55809 + vertex 1.12609 2.00536 2.55675 + vertex 1.12117 2.00521 2.5576 + endloop + endfacet + facet normal 0.164101 0.189873 0.967997 + outer loop + vertex 1.12623 2.00034 2.55771 + vertex 1.12609 2.00536 2.55675 + vertex 1.12253 2.00159 2.55809 + endloop + endfacet + facet normal 0.164998 0.192743 0.967278 + outer loop + vertex 1.12333 1.99743 2.55878 + vertex 1.12623 2.00034 2.55771 + vertex 1.12253 2.00159 2.55809 + endloop + endfacet + facet normal 0.153731 0.190931 0.969491 + outer loop + vertex 1.12333 1.99743 2.55878 + vertex 1.12253 2.00159 2.55809 + vertex 1.11956 1.99888 2.55909 + endloop + endfacet + facet normal 0.139818 0.207103 0.968276 + outer loop + vertex 1.11314 1.98233 2.5635 + vertex 1.11602 1.9865 2.56219 + vertex 1.11159 1.98585 2.56297 + endloop + endfacet + facet normal 0.13902 0.207653 0.968274 + outer loop + vertex 1.11758 1.9816 2.56302 + vertex 1.11602 1.9865 2.56219 + vertex 1.11314 1.98233 2.5635 + endloop + endfacet + facet normal 0.144139 0.209103 0.967212 + outer loop + vertex 1.11758 1.9816 2.56302 + vertex 1.12177 1.9846 2.56174 + vertex 1.11602 1.9865 2.56219 + endloop + endfacet + facet normal 0.14625 0.209708 0.966764 + outer loop + vertex 1.11314 1.98233 2.5635 + vertex 1.11159 1.98585 2.56297 + vertex 1.10934 1.98332 2.56386 + endloop + endfacet + facet normal 0.145457 0.206381 0.9676 + outer loop + vertex 1.10956 1.97861 2.56483 + vertex 1.11314 1.98233 2.5635 + vertex 1.10934 1.98332 2.56386 + endloop + endfacet + facet normal 0.142477 0.209191 0.96744 + outer loop + vertex 1.11465 1.97869 2.56406 + vertex 1.11314 1.98233 2.5635 + vertex 1.10956 1.97861 2.56483 + endloop + endfacet + facet normal 0.142798 0.202318 0.968853 + outer loop + vertex 1.10956 1.97861 2.56483 + vertex 1.11461 1.97398 2.56505 + vertex 1.11465 1.97869 2.56406 + endloop + endfacet + facet normal 0.140573 0.202402 0.969161 + outer loop + vertex 1.11461 1.97398 2.56505 + vertex 1.11841 1.97746 2.56377 + vertex 1.11465 1.97869 2.56406 + endloop + endfacet + facet normal 0.141515 0.205458 0.96838 + outer loop + vertex 1.11841 1.97746 2.56377 + vertex 1.11758 1.9816 2.56302 + vertex 1.11465 1.97869 2.56406 + endloop + endfacet + facet normal 0.143029 0.199793 0.969343 + outer loop + vertex 1.11961 1.97401 2.56431 + vertex 1.11841 1.97746 2.56377 + vertex 1.11461 1.97398 2.56505 + endloop + endfacet + facet normal 0.147267 0.201129 0.968431 + outer loop + vertex 1.11961 1.97401 2.56431 + vertex 1.1226 1.97665 2.5633 + vertex 1.11841 1.97746 2.56377 + endloop + endfacet + facet normal 0.147431 0.202102 0.968204 + outer loop + vertex 1.1226 1.97665 2.5633 + vertex 1.12137 1.98016 2.56276 + vertex 1.11841 1.97746 2.56377 + endloop + endfacet + facet normal 0.143907 0.205858 0.967943 + outer loop + vertex 1.11841 1.97746 2.56377 + vertex 1.12137 1.98016 2.56276 + vertex 1.11758 1.9816 2.56302 + endloop + endfacet + facet normal 0.144772 0.208258 0.9673 + outer loop + vertex 1.12137 1.98016 2.56276 + vertex 1.12177 1.9846 2.56174 + vertex 1.11758 1.9816 2.56302 + endloop + endfacet + facet normal 0.151113 0.203265 0.967392 + outer loop + vertex 1.1226 1.97665 2.5633 + vertex 1.12634 1.98036 2.56194 + vertex 1.12137 1.98016 2.56276 + endloop + endfacet + facet normal 0.149437 0.204924 0.967303 + outer loop + vertex 1.12635 1.9754 2.56299 + vertex 1.12634 1.98036 2.56194 + vertex 1.1226 1.97665 2.5633 + endloop + endfacet + facet normal 0.147908 0.199992 0.968569 + outer loop + vertex 1.1234 1.9725 2.56404 + vertex 1.12635 1.9754 2.56299 + vertex 1.1226 1.97665 2.5633 + endloop + endfacet + facet normal 0.144328 0.203561 0.968366 + outer loop + vertex 1.12787 1.9717 2.56354 + vertex 1.12635 1.9754 2.56299 + vertex 1.1234 1.9725 2.56404 + endloop + endfacet + facet normal 0.143931 0.200955 0.968969 + outer loop + vertex 1.12489 1.96767 2.56482 + vertex 1.12787 1.9717 2.56354 + vertex 1.1234 1.9725 2.56404 + endloop + endfacet + facet normal 0.144687 0.201164 0.968813 + outer loop + vertex 1.12489 1.96767 2.56482 + vertex 1.1234 1.9725 2.56404 + vertex 1.11912 1.96977 2.56524 + endloop + endfacet + facet normal 0.142679 0.195338 0.970302 + outer loop + vertex 1.11912 1.96977 2.56524 + vertex 1.1205 1.96477 2.56605 + vertex 1.12489 1.96767 2.56482 + endloop + endfacet + facet normal 0.139547 0.19989 0.96983 + outer loop + vertex 1.1205 1.96477 2.56605 + vertex 1.12462 1.96327 2.56577 + vertex 1.12489 1.96767 2.56482 + endloop + endfacet + facet normal 0.138361 0.196483 0.970696 + outer loop + vertex 1.12462 1.96327 2.56577 + vertex 1.1205 1.96477 2.56605 + vertex 1.12189 1.9597 2.56687 + endloop + endfacet + facet normal 0.13891 0.196616 0.970591 + outer loop + vertex 1.12189 1.9597 2.56687 + vertex 1.1205 1.96477 2.56605 + vertex 1.11612 1.96172 2.56729 + endloop + endfacet + facet normal 0.136653 0.189819 0.972263 + outer loop + vertex 1.11756 1.9567 2.56807 + vertex 1.12189 1.9597 2.56687 + vertex 1.11612 1.96172 2.56729 + endloop + endfacet + facet normal 0.140006 0.19068 0.971617 + outer loop + vertex 1.11756 1.9567 2.56807 + vertex 1.11612 1.96172 2.56729 + vertex 1.11306 1.95754 2.56855 + endloop + endfacet + facet normal 0.139818 0.189524 0.97187 + outer loop + vertex 1.1144 1.95391 2.56907 + vertex 1.11756 1.9567 2.56807 + vertex 1.11306 1.95754 2.56855 + endloop + endfacet + facet normal 0.140746 0.189838 0.971675 + outer loop + vertex 1.1144 1.95391 2.56907 + vertex 1.11306 1.95754 2.56855 + vertex 1.10928 1.95384 2.56982 + endloop + endfacet + facet normal 0.140478 0.190107 0.971661 + outer loop + vertex 1.10928 1.95384 2.56982 + vertex 1.11306 1.95754 2.56855 + vertex 1.10926 1.9585 2.56892 + endloop + endfacet + facet normal 0.141076 0.190094 0.971577 + outer loop + vertex 1.10436 1.95836 2.56965 + vertex 1.10928 1.95384 2.56982 + vertex 1.10926 1.9585 2.56892 + endloop + endfacet + facet normal 0.140938 0.192487 0.971126 + outer loop + vertex 1.10926 1.9585 2.56892 + vertex 1.10798 1.96207 2.56839 + vertex 1.10436 1.95836 2.56965 + endloop + endfacet + facet normal 0.138516 0.191694 0.971631 + outer loop + vertex 1.10926 1.9585 2.56892 + vertex 1.11163 1.96109 2.56806 + vertex 1.10798 1.96207 2.56839 + endloop + endfacet + facet normal 0.138596 0.192021 0.971555 + outer loop + vertex 1.11163 1.96109 2.56806 + vertex 1.11147 1.96593 2.56713 + vertex 1.10798 1.96207 2.56839 + endloop + endfacet + facet normal 0.138078 0.192484 0.971537 + outer loop + vertex 1.10798 1.96207 2.56839 + vertex 1.11147 1.96593 2.56713 + vertex 1.10667 1.96567 2.56787 + endloop + endfacet + facet normal 0.140483 0.192031 0.971282 + outer loop + vertex 1.11147 1.96593 2.56713 + vertex 1.11163 1.96109 2.56806 + vertex 1.11612 1.96172 2.56729 + endloop + endfacet + facet normal 0.140443 0.189952 0.971696 + outer loop + vertex 1.11306 1.95754 2.56855 + vertex 1.11163 1.96109 2.56806 + vertex 1.10926 1.9585 2.56892 + endloop + endfacet + facet normal 0.135903 0.193855 0.971571 + outer loop + vertex 1.1183 1.95235 2.56883 + vertex 1.11756 1.9567 2.56807 + vertex 1.1144 1.95391 2.56907 + endloop + endfacet + facet normal 0.135631 0.193147 0.97175 + outer loop + vertex 1.11389 1.94958 2.57 + vertex 1.1183 1.95235 2.56883 + vertex 1.1144 1.95391 2.56907 + endloop + endfacet + facet normal 0.130422 0.201064 0.970857 + outer loop + vertex 1.11977 1.94751 2.56964 + vertex 1.1183 1.95235 2.56883 + vertex 1.11389 1.94958 2.57 + endloop + endfacet + facet normal 0.125293 0.199659 0.971822 + outer loop + vertex 1.11977 1.94751 2.56964 + vertex 1.12283 1.95158 2.56841 + vertex 1.1183 1.95235 2.56883 + endloop + endfacet + facet normal 0.125494 0.200997 0.97152 + outer loop + vertex 1.12283 1.95158 2.56841 + vertex 1.12144 1.9552 2.56784 + vertex 1.1183 1.95235 2.56883 + endloop + endfacet + facet normal 0.122793 0.20004 0.972063 + outer loop + vertex 1.12283 1.95158 2.56841 + vertex 1.12645 1.95561 2.56712 + vertex 1.12144 1.9552 2.56784 + endloop + endfacet + facet normal 0.123243 0.195988 0.972831 + outer loop + vertex 1.12189 1.9597 2.56687 + vertex 1.12144 1.9552 2.56784 + vertex 1.12645 1.95561 2.56712 + endloop + endfacet + facet normal 0.13049 0.203913 0.970254 + outer loop + vertex 1.12642 1.96032 2.56614 + vertex 1.12189 1.9597 2.56687 + vertex 1.12645 1.95561 2.56712 + endloop + endfacet + facet normal 0.130949 0.203903 0.970194 + outer loop + vertex 1.12642 1.96032 2.56614 + vertex 1.12645 1.95561 2.56712 + vertex 1.1296 1.95911 2.56596 + endloop + endfacet + facet normal 0.131562 0.205572 0.969758 + outer loop + vertex 1.1296 1.95911 2.56596 + vertex 1.12958 1.96367 2.565 + vertex 1.12642 1.96032 2.56614 + endloop + endfacet + facet normal 0.133458 0.203821 0.969869 + outer loop + vertex 1.12462 1.96327 2.56577 + vertex 1.12642 1.96032 2.56614 + vertex 1.12958 1.96367 2.565 + endloop + endfacet + facet normal 0.13384 0.200395 0.97053 + outer loop + vertex 1.12462 1.96327 2.56577 + vertex 1.12958 1.96367 2.565 + vertex 1.12489 1.96767 2.56482 + endloop + endfacet + facet normal 0.136874 0.203904 0.969375 + outer loop + vertex 1.12489 1.96767 2.56482 + vertex 1.12958 1.96367 2.565 + vertex 1.12943 1.9682 2.56406 + endloop + endfacet + facet normal 0.134695 0.200585 0.970373 + outer loop + vertex 1.13134 1.9562 2.56632 + vertex 1.1296 1.95911 2.56596 + vertex 1.12645 1.95561 2.56712 + endloop + endfacet + facet normal 0.130764 0.20226 0.970563 + outer loop + vertex 1.12642 1.96032 2.56614 + vertex 1.12462 1.96327 2.56577 + vertex 1.12189 1.9597 2.56687 + endloop + endfacet + facet normal 0.115656 0.206298 0.97163 + outer loop + vertex 1.12662 1.95087 2.56811 + vertex 1.12645 1.95561 2.56712 + vertex 1.12283 1.95158 2.56841 + endloop + endfacet + facet normal 0.115834 0.207357 0.971383 + outer loop + vertex 1.12438 1.94813 2.56896 + vertex 1.12662 1.95087 2.56811 + vertex 1.12283 1.95158 2.56841 + endloop + endfacet + facet normal 0.116875 0.206521 0.971437 + outer loop + vertex 1.12818 1.94749 2.56864 + vertex 1.12662 1.95087 2.56811 + vertex 1.12438 1.94813 2.56896 + endloop + endfacet + facet normal 0.13982 0.206501 0.968405 + outer loop + vertex 1.12645 1.95561 2.56712 + vertex 1.12662 1.95087 2.56811 + vertex 1.13098 1.95176 2.56729 + endloop + endfacet + facet normal 0.115256 0.207116 0.971503 + outer loop + vertex 1.12438 1.94813 2.56896 + vertex 1.12283 1.95158 2.56841 + vertex 1.11977 1.94751 2.56964 + endloop + endfacet + facet normal 0.115506 0.205589 0.971798 + outer loop + vertex 1.11977 1.94751 2.56964 + vertex 1.12455 1.9436 2.5699 + vertex 1.12438 1.94813 2.56896 + endloop + endfacet + facet normal 0.110586 0.199703 0.973596 + outer loop + vertex 1.11952 1.94311 2.57057 + vertex 1.12455 1.9436 2.5699 + vertex 1.11977 1.94751 2.56964 + endloop + endfacet + facet normal 0.122711 0.198743 0.972339 + outer loop + vertex 1.11532 1.94458 2.5708 + vertex 1.11952 1.94311 2.57057 + vertex 1.11977 1.94751 2.56964 + endloop + endfacet + facet normal 0.122103 0.19694 0.972782 + outer loop + vertex 1.11952 1.94311 2.57057 + vertex 1.11532 1.94458 2.5708 + vertex 1.11681 1.93957 2.57163 + endloop + endfacet + facet normal 0.11168 0.204817 0.972408 + outer loop + vertex 1.12139 1.94021 2.57097 + vertex 1.11952 1.94311 2.57057 + vertex 1.11681 1.93957 2.57163 + endloop + endfacet + facet normal 0.111825 0.203946 0.972575 + outer loop + vertex 1.12139 1.94021 2.57097 + vertex 1.11681 1.93957 2.57163 + vertex 1.1214 1.93555 2.57194 + endloop + endfacet + facet normal 0.105997 0.204066 0.973202 + outer loop + vertex 1.12139 1.94021 2.57097 + vertex 1.1214 1.93555 2.57194 + vertex 1.1246 1.93905 2.57086 + endloop + endfacet + facet normal 0.106924 0.206706 0.972543 + outer loop + vertex 1.1246 1.93905 2.57086 + vertex 1.12455 1.9436 2.5699 + vertex 1.12139 1.94021 2.57097 + endloop + endfacet + facet normal 0.104811 0.196135 0.974959 + outer loop + vertex 1.11681 1.93957 2.57163 + vertex 1.11638 1.93514 2.57256 + vertex 1.1214 1.93555 2.57194 + endloop + endfacet + facet normal 0.104652 0.197652 0.97467 + outer loop + vertex 1.11757 1.93161 2.57315 + vertex 1.1214 1.93555 2.57194 + vertex 1.11638 1.93514 2.57256 + endloop + endfacet + facet normal 0.115244 0.200925 0.972804 + outer loop + vertex 1.11757 1.93161 2.57315 + vertex 1.11638 1.93514 2.57256 + vertex 1.11331 1.93233 2.57351 + endloop + endfacet + facet normal 0.11461 0.196651 0.973752 + outer loop + vertex 1.11444 1.92884 2.57408 + vertex 1.11757 1.93161 2.57315 + vertex 1.11331 1.93233 2.57351 + endloop + endfacet + facet normal 0.126263 0.200105 0.971605 + outer loop + vertex 1.11444 1.92884 2.57408 + vertex 1.11331 1.93233 2.57351 + vertex 1.10941 1.92865 2.57477 + endloop + endfacet + facet normal 0.126399 0.198015 0.972015 + outer loop + vertex 1.10941 1.92865 2.57477 + vertex 1.11389 1.9246 2.57502 + vertex 1.11444 1.92884 2.57408 + endloop + endfacet + facet normal 0.108163 0.203705 0.973039 + outer loop + vertex 1.11836 1.92747 2.57393 + vertex 1.11757 1.93161 2.57315 + vertex 1.11444 1.92884 2.57408 + endloop + endfacet + facet normal 0.123097 0.192584 0.973529 + outer loop + vertex 1.11331 1.93233 2.57351 + vertex 1.11638 1.93514 2.57256 + vertex 1.11253 1.93651 2.57278 + endloop + endfacet + facet normal 0.123562 0.193945 0.9732 + outer loop + vertex 1.11638 1.93514 2.57256 + vertex 1.11681 1.93957 2.57163 + vertex 1.11253 1.93651 2.57278 + endloop + endfacet + facet normal 0.126942 0.18939 0.973662 + outer loop + vertex 1.11253 1.93651 2.57278 + vertex 1.11681 1.93957 2.57163 + vertex 1.11094 1.94148 2.57202 + endloop + endfacet + facet normal 0.110077 0.20384 0.972796 + outer loop + vertex 1.11952 1.94311 2.57057 + vertex 1.12139 1.94021 2.57097 + vertex 1.12455 1.9436 2.5699 + endloop + endfacet + facet normal 0.13257 0.193388 0.972125 + outer loop + vertex 1.1183 1.95235 2.56883 + vertex 1.12144 1.9552 2.56784 + vertex 1.11756 1.9567 2.56807 + endloop + endfacet + facet normal 0.140812 0.19009 0.971616 + outer loop + vertex 1.11306 1.95754 2.56855 + vertex 1.11612 1.96172 2.56729 + vertex 1.11163 1.96109 2.56806 + endloop + endfacet + facet normal 0.133087 0.19477 0.971778 + outer loop + vertex 1.12144 1.9552 2.56784 + vertex 1.12189 1.9597 2.56687 + vertex 1.11756 1.9567 2.56807 + endloop + endfacet + facet normal 0.14388 0.19563 0.970066 + outer loop + vertex 1.1205 1.96477 2.56605 + vertex 1.11912 1.96977 2.56524 + vertex 1.1164 1.96632 2.56634 + endloop + endfacet + facet normal 0.142471 0.191698 0.971058 + outer loop + vertex 1.1164 1.96632 2.56634 + vertex 1.11612 1.96172 2.56729 + vertex 1.1205 1.96477 2.56605 + endloop + endfacet + facet normal 0.140346 0.191881 0.971331 + outer loop + vertex 1.1164 1.96632 2.56634 + vertex 1.11147 1.96593 2.56713 + vertex 1.11612 1.96172 2.56729 + endloop + endfacet + facet normal 0.14024 0.192857 0.971153 + outer loop + vertex 1.1164 1.96632 2.56634 + vertex 1.11462 1.96932 2.566 + vertex 1.11147 1.96593 2.56713 + endloop + endfacet + facet normal 0.144419 0.195206 0.970071 + outer loop + vertex 1.11462 1.96932 2.566 + vertex 1.1164 1.96632 2.56634 + vertex 1.11912 1.96977 2.56524 + endloop + endfacet + facet normal 0.136498 0.206419 0.968896 + outer loop + vertex 1.12943 1.9682 2.56406 + vertex 1.12787 1.9717 2.56354 + vertex 1.12489 1.96767 2.56482 + endloop + endfacet + facet normal 0.135606 0.20605 0.9691 + outer loop + vertex 1.12943 1.9682 2.56406 + vertex 1.13164 1.97091 2.56318 + vertex 1.12787 1.9717 2.56354 + endloop + endfacet + facet normal 0.136071 0.20853 0.968504 + outer loop + vertex 1.13164 1.97091 2.56318 + vertex 1.13139 1.97576 2.56217 + vertex 1.12787 1.9717 2.56354 + endloop + endfacet + facet normal 0.13694 0.204973 0.969141 + outer loop + vertex 1.13319 1.96748 2.56369 + vertex 1.13164 1.97091 2.56318 + vertex 1.12943 1.9682 2.56406 + endloop + endfacet + facet normal 0.142633 0.202925 0.96875 + outer loop + vertex 1.12787 1.9717 2.56354 + vertex 1.13139 1.97576 2.56217 + vertex 1.12635 1.9754 2.56299 + endloop + endfacet + facet normal 0.148249 0.200046 0.968506 + outer loop + vertex 1.1234 1.9725 2.56404 + vertex 1.1226 1.97665 2.5633 + vertex 1.11961 1.97401 2.56431 + endloop + endfacet + facet normal 0.147227 0.197366 0.969211 + outer loop + vertex 1.11912 1.96977 2.56524 + vertex 1.1234 1.9725 2.56404 + vertex 1.11961 1.97401 2.56431 + endloop + endfacet + facet normal 0.143097 0.197954 0.96971 + outer loop + vertex 1.11461 1.97398 2.56505 + vertex 1.11912 1.96977 2.56524 + vertex 1.11961 1.97401 2.56431 + endloop + endfacet + facet normal 0.140237 0.199575 0.969795 + outer loop + vertex 1.10966 1.9738 2.5658 + vertex 1.11461 1.97398 2.56505 + vertex 1.10956 1.97861 2.56483 + endloop + endfacet + facet normal 0.139052 0.207884 0.968219 + outer loop + vertex 1.11465 1.97869 2.56406 + vertex 1.11758 1.9816 2.56302 + vertex 1.11314 1.98233 2.5635 + endloop + endfacet + facet normal 0.167713 0.199237 0.965493 + outer loop + vertex 1.10632 1.9754 2.56598 + vertex 1.10456 1.97865 2.56562 + vertex 1.10138 1.9755 2.56682 + endloop + endfacet + facet normal 0.138244 0.190488 0.971907 + outer loop + vertex 1.10645 1.97054 2.56694 + vertex 1.10667 1.96567 2.56787 + vertex 1.11147 1.96593 2.56713 + endloop + endfacet + facet normal 0.141644 0.19415 0.970692 + outer loop + vertex 1.11139 1.9707 2.56619 + vertex 1.10645 1.97054 2.56694 + vertex 1.11147 1.96593 2.56713 + endloop + endfacet + facet normal 0.138792 0.194182 0.971097 + outer loop + vertex 1.11139 1.9707 2.56619 + vertex 1.11147 1.96593 2.56713 + vertex 1.11462 1.96932 2.566 + endloop + endfacet + facet normal 0.141281 0.199966 0.969564 + outer loop + vertex 1.11139 1.9707 2.56619 + vertex 1.10966 1.9738 2.5658 + vertex 1.10645 1.97054 2.56694 + endloop + endfacet + facet normal 0.140969 0.193444 0.970931 + outer loop + vertex 1.10798 1.96207 2.56839 + vertex 1.10667 1.96567 2.56787 + vertex 1.10434 1.96307 2.56872 + endloop + endfacet + facet normal 0.140768 0.19265 0.971118 + outer loop + vertex 1.10436 1.95836 2.56965 + vertex 1.10798 1.96207 2.56839 + vertex 1.10434 1.96307 2.56872 + endloop + endfacet + facet normal 0.141688 0.190754 0.971359 + outer loop + vertex 1.10433 1.95365 2.57058 + vertex 1.10928 1.95384 2.56982 + vertex 1.10436 1.95836 2.56965 + endloop + endfacet + facet normal 0.141673 0.190985 0.971315 + outer loop + vertex 1.10433 1.95365 2.57058 + vertex 1.10604 1.95054 2.57095 + vertex 1.10928 1.95384 2.56982 + endloop + endfacet + facet normal 0.140637 0.192433 0.97118 + outer loop + vertex 1.10928 1.95384 2.56982 + vertex 1.11389 1.94958 2.57 + vertex 1.1144 1.95391 2.56907 + endloop + endfacet + facet normal 0.127364 0.191974 0.9731 + outer loop + vertex 1.11389 1.94958 2.57 + vertex 1.11532 1.94458 2.5708 + vertex 1.11977 1.94751 2.56964 + endloop + endfacet + facet normal 0.12993 0.199032 0.971341 + outer loop + vertex 1.11681 1.93957 2.57163 + vertex 1.11532 1.94458 2.5708 + vertex 1.11094 1.94148 2.57202 + endloop + endfacet + facet normal 0.141384 0.191412 0.971273 + outer loop + vertex 1.11114 1.94611 2.57107 + vertex 1.1093 1.94914 2.57074 + vertex 1.10617 1.94567 2.57188 + endloop + endfacet + facet normal 0.132045 0.193992 0.972076 + outer loop + vertex 1.11331 1.93233 2.57351 + vertex 1.11253 1.93651 2.57278 + vertex 1.10958 1.9334 2.5738 + endloop + endfacet + facet normal 0.132074 0.194098 0.972051 + outer loop + vertex 1.10941 1.92865 2.57477 + vertex 1.11331 1.93233 2.57351 + vertex 1.10958 1.9334 2.5738 + endloop + endfacet + facet normal 0.136389 0.185667 0.973101 + outer loop + vertex 1.10446 1.92821 2.57555 + vertex 1.10619 1.92532 2.57586 + vertex 1.10941 1.92865 2.57477 + endloop + endfacet + facet normal 0.133209 0.188689 0.97296 + outer loop + vertex 1.10929 1.92411 2.57567 + vertex 1.10941 1.92865 2.57477 + vertex 1.10619 1.92532 2.57586 + endloop + endfacet + facet normal 0.13136 0.183752 0.974156 + outer loop + vertex 1.10619 1.92532 2.57586 + vertex 1.10622 1.92061 2.57675 + vertex 1.10929 1.92411 2.57567 + endloop + endfacet + facet normal 0.125401 0.188928 0.973951 + outer loop + vertex 1.11109 1.92115 2.57601 + vertex 1.10929 1.92411 2.57567 + vertex 1.10622 1.92061 2.57675 + endloop + endfacet + facet normal 0.125979 0.184746 0.974679 + outer loop + vertex 1.11109 1.92115 2.57601 + vertex 1.10622 1.92061 2.57675 + vertex 1.11086 1.91651 2.57692 + endloop + endfacet + facet normal 0.106511 0.186128 0.976735 + outer loop + vertex 1.11109 1.92115 2.57601 + vertex 1.11086 1.91651 2.57692 + vertex 1.11533 1.91965 2.57584 + endloop + endfacet + facet normal 0.103021 0.190911 0.976186 + outer loop + vertex 1.11683 1.91465 2.57665 + vertex 1.11533 1.91965 2.57584 + vertex 1.11086 1.91651 2.57692 + endloop + endfacet + facet normal 0.0999936 0.18085 0.978414 + outer loop + vertex 1.1123 1.91133 2.57773 + vertex 1.11683 1.91465 2.57665 + vertex 1.11086 1.91651 2.57692 + endloop + endfacet + facet normal 0.109309 0.183211 0.976978 + outer loop + vertex 1.1123 1.91133 2.57773 + vertex 1.11086 1.91651 2.57692 + vertex 1.10764 1.91208 2.57811 + endloop + endfacet + facet normal 0.109578 0.185093 0.976593 + outer loop + vertex 1.1085 1.90769 2.57885 + vertex 1.1123 1.91133 2.57773 + vertex 1.10764 1.91208 2.57811 + endloop + endfacet + facet normal 0.122485 0.187283 0.97464 + outer loop + vertex 1.1085 1.90769 2.57885 + vertex 1.10764 1.91208 2.57811 + vertex 1.10449 1.90903 2.57909 + endloop + endfacet + facet normal 0.123386 0.190108 0.973979 + outer loop + vertex 1.10388 1.90471 2.58002 + vertex 1.1085 1.90769 2.57885 + vertex 1.10449 1.90903 2.57909 + endloop + endfacet + facet normal 0.139226 0.187521 0.972343 + outer loop + vertex 1.09949 1.90875 2.57986 + vertex 1.10388 1.90471 2.58002 + vertex 1.10449 1.90903 2.57909 + endloop + endfacet + facet normal 0.139812 0.18041 0.973604 + outer loop + vertex 1.10449 1.90903 2.57909 + vertex 1.10335 1.91253 2.57861 + vertex 1.09949 1.90875 2.57986 + endloop + endfacet + facet normal 0.141692 0.178514 0.973682 + outer loop + vertex 1.09949 1.90875 2.57986 + vertex 1.10335 1.91253 2.57861 + vertex 1.09972 1.91347 2.57897 + endloop + endfacet + facet normal 0.138427 0.178754 0.974107 + outer loop + vertex 1.095 1.91279 2.57976 + vertex 1.09949 1.90875 2.57986 + vertex 1.09972 1.91347 2.57897 + endloop + endfacet + facet normal 0.138801 0.176547 0.974456 + outer loop + vertex 1.09972 1.91347 2.57897 + vertex 1.09832 1.917 2.57853 + vertex 1.095 1.91279 2.57976 + endloop + endfacet + facet normal 0.137014 0.177955 0.974453 + outer loop + vertex 1.095 1.91279 2.57976 + vertex 1.09832 1.917 2.57853 + vertex 1.09372 1.91777 2.57903 + endloop + endfacet + facet normal 0.133024 0.177037 0.975173 + outer loop + vertex 1.095 1.91279 2.57976 + vertex 1.09372 1.91777 2.57903 + vertex 1.08918 1.9148 2.58019 + endloop + endfacet + facet normal 0.133609 0.176171 0.97525 + outer loop + vertex 1.08918 1.9148 2.58019 + vertex 1.09372 1.91777 2.57903 + vertex 1.08974 1.91909 2.57934 + endloop + endfacet + facet normal 0.135568 0.175872 0.975034 + outer loop + vertex 1.08465 1.91901 2.58006 + vertex 1.08918 1.9148 2.58019 + vertex 1.08974 1.91909 2.57934 + endloop + endfacet + facet normal 0.135321 0.181793 0.973981 + outer loop + vertex 1.08974 1.91909 2.57934 + vertex 1.08853 1.92255 2.57886 + vertex 1.08465 1.91901 2.58006 + endloop + endfacet + facet normal 0.134759 0.181611 0.974093 + outer loop + vertex 1.08974 1.91909 2.57934 + vertex 1.09283 1.92206 2.57836 + vertex 1.08853 1.92255 2.57886 + endloop + endfacet + facet normal 0.135056 0.184983 0.973417 + outer loop + vertex 1.09283 1.92206 2.57836 + vertex 1.09135 1.92562 2.57789 + vertex 1.08853 1.92255 2.57886 + endloop + endfacet + facet normal 0.137422 0.182834 0.973492 + outer loop + vertex 1.08853 1.92255 2.57886 + vertex 1.09135 1.92562 2.57789 + vertex 1.0877 1.92663 2.57821 + endloop + endfacet + facet normal 0.141124 0.183476 0.972841 + outer loop + vertex 1.08853 1.92255 2.57886 + vertex 1.0877 1.92663 2.57821 + vertex 1.08481 1.92373 2.57918 + endloop + endfacet + facet normal 0.137803 0.184318 0.973158 + outer loop + vertex 1.09135 1.92562 2.57789 + vertex 1.09127 1.93069 2.57694 + vertex 1.0877 1.92663 2.57821 + endloop + endfacet + facet normal 0.143806 0.179068 0.97327 + outer loop + vertex 1.0877 1.92663 2.57821 + vertex 1.09127 1.93069 2.57694 + vertex 1.08635 1.93036 2.57772 + endloop + endfacet + facet normal 0.147246 0.180221 0.972543 + outer loop + vertex 1.0877 1.92663 2.57821 + vertex 1.08635 1.93036 2.57772 + vertex 1.08352 1.92739 2.5787 + endloop + endfacet + facet normal 0.144487 0.171766 0.974484 + outer loop + vertex 1.08628 1.93551 2.57683 + vertex 1.08635 1.93036 2.57772 + vertex 1.09127 1.93069 2.57694 + endloop + endfacet + facet normal 0.156125 0.183718 0.970501 + outer loop + vertex 1.0912 1.93562 2.57602 + vertex 1.08628 1.93551 2.57683 + vertex 1.09127 1.93069 2.57694 + endloop + endfacet + facet normal 0.144036 0.183878 0.972339 + outer loop + vertex 1.0912 1.93562 2.57602 + vertex 1.09127 1.93069 2.57694 + vertex 1.09445 1.93416 2.57581 + endloop + endfacet + facet normal 0.143447 0.182511 0.972683 + outer loop + vertex 1.09445 1.93416 2.57581 + vertex 1.09451 1.93891 2.57491 + vertex 1.0912 1.93562 2.57602 + endloop + endfacet + facet normal 0.139107 0.188345 0.972201 + outer loop + vertex 1.09626 1.93112 2.57614 + vertex 1.09445 1.93416 2.57581 + vertex 1.09127 1.93069 2.57694 + endloop + endfacet + facet normal 0.139191 0.187612 0.972331 + outer loop + vertex 1.09626 1.93112 2.57614 + vertex 1.09127 1.93069 2.57694 + vertex 1.09597 1.92647 2.57708 + endloop + endfacet + facet normal 0.136193 0.187868 0.972706 + outer loop + vertex 1.09626 1.93112 2.57614 + vertex 1.09597 1.92647 2.57708 + vertex 1.10038 1.92964 2.57585 + endloop + endfacet + facet normal 0.137055 0.186708 0.972808 + outer loop + vertex 1.10176 1.92463 2.57662 + vertex 1.10038 1.92964 2.57585 + vertex 1.09597 1.92647 2.57708 + endloop + endfacet + facet normal 0.136554 0.185044 0.973197 + outer loop + vertex 1.0974 1.92137 2.57785 + vertex 1.10176 1.92463 2.57662 + vertex 1.09597 1.92647 2.57708 + endloop + endfacet + facet normal 0.136465 0.185022 0.973213 + outer loop + vertex 1.0974 1.92137 2.57785 + vertex 1.09597 1.92647 2.57708 + vertex 1.09283 1.92206 2.57836 + endloop + endfacet + facet normal 0.135984 0.181325 0.973976 + outer loop + vertex 1.09372 1.91777 2.57903 + vertex 1.0974 1.92137 2.57785 + vertex 1.09283 1.92206 2.57836 + endloop + endfacet + facet normal 0.138542 0.182464 0.973403 + outer loop + vertex 1.10134 1.92012 2.57752 + vertex 1.10176 1.92463 2.57662 + vertex 1.0974 1.92137 2.57785 + endloop + endfacet + facet normal 0.137835 0.180086 0.973946 + outer loop + vertex 1.09832 1.917 2.57853 + vertex 1.10134 1.92012 2.57752 + vertex 1.0974 1.92137 2.57785 + endloop + endfacet + facet normal 0.140379 0.177641 0.974031 + outer loop + vertex 1.10259 1.91659 2.57799 + vertex 1.10134 1.92012 2.57752 + vertex 1.09832 1.917 2.57853 + endloop + endfacet + facet normal 0.137477 0.176694 0.974617 + outer loop + vertex 1.10259 1.91659 2.57799 + vertex 1.10622 1.92061 2.57675 + vertex 1.10134 1.92012 2.57752 + endloop + endfacet + facet normal 0.137005 0.177117 0.974607 + outer loop + vertex 1.10621 1.91569 2.57764 + vertex 1.10622 1.92061 2.57675 + vertex 1.10259 1.91659 2.57799 + endloop + endfacet + facet normal 0.136663 0.175621 0.974926 + outer loop + vertex 1.10335 1.91253 2.57861 + vertex 1.10621 1.91569 2.57764 + vertex 1.10259 1.91659 2.57799 + endloop + endfacet + facet normal 0.131834 0.179953 0.974801 + outer loop + vertex 1.10764 1.91208 2.57811 + vertex 1.10621 1.91569 2.57764 + vertex 1.10335 1.91253 2.57861 + endloop + endfacet + facet normal 0.136718 0.182674 0.973621 + outer loop + vertex 1.10176 1.92463 2.57662 + vertex 1.10134 1.92012 2.57752 + vertex 1.10622 1.92061 2.57675 + endloop + endfacet + facet normal 0.138009 0.187724 0.972478 + outer loop + vertex 1.09445 1.93416 2.57581 + vertex 1.09626 1.93112 2.57614 + vertex 1.09903 1.93462 2.57507 + endloop + endfacet + facet normal 0.13622 0.184334 0.973378 + outer loop + vertex 1.09127 1.93069 2.57694 + vertex 1.09135 1.92562 2.57789 + vertex 1.09597 1.92647 2.57708 + endloop + endfacet + facet normal 0.136004 0.185351 0.973215 + outer loop + vertex 1.09283 1.92206 2.57836 + vertex 1.09597 1.92647 2.57708 + vertex 1.09135 1.92562 2.57789 + endloop + endfacet + facet normal 0.135181 0.18118 0.974115 + outer loop + vertex 1.09372 1.91777 2.57903 + vertex 1.09283 1.92206 2.57836 + vertex 1.08974 1.91909 2.57934 + endloop + endfacet + facet normal 0.137309 0.17999 0.974038 + outer loop + vertex 1.09832 1.917 2.57853 + vertex 1.0974 1.92137 2.57785 + vertex 1.09372 1.91777 2.57903 + endloop + endfacet + facet normal 0.140341 0.177118 0.974132 + outer loop + vertex 1.09972 1.91347 2.57897 + vertex 1.10259 1.91659 2.57799 + vertex 1.09832 1.917 2.57853 + endloop + endfacet + facet normal 0.137911 0.178187 0.974284 + outer loop + vertex 1.09458 1.90833 2.58064 + vertex 1.09949 1.90875 2.57986 + vertex 1.095 1.91279 2.57976 + endloop + endfacet + facet normal 0.130507 0.179047 0.975146 + outer loop + vertex 1.09052 1.9098 2.58091 + vertex 1.09458 1.90833 2.58064 + vertex 1.095 1.91279 2.57976 + endloop + endfacet + facet normal 0.129705 0.176719 0.975678 + outer loop + vertex 1.09458 1.90833 2.58064 + vertex 1.09052 1.9098 2.58091 + vertex 1.09187 1.90472 2.58165 + endloop + endfacet + facet normal 0.1297 0.176723 0.975678 + outer loop + vertex 1.0963 1.90541 2.58094 + vertex 1.09458 1.90833 2.58064 + vertex 1.09187 1.90472 2.58165 + endloop + endfacet + facet normal 0.129398 0.178384 0.975416 + outer loop + vertex 1.0963 1.90541 2.58094 + vertex 1.09187 1.90472 2.58165 + vertex 1.09626 1.90067 2.58181 + endloop + endfacet + facet normal 0.135827 0.178186 0.974577 + outer loop + vertex 1.0963 1.90541 2.58094 + vertex 1.09626 1.90067 2.58181 + vertex 1.09935 1.9042 2.58073 + endloop + endfacet + facet normal 0.137119 0.181578 0.97377 + outer loop + vertex 1.09935 1.9042 2.58073 + vertex 1.09949 1.90875 2.57986 + vertex 1.0963 1.90541 2.58094 + endloop + endfacet + facet normal 0.13318 0.180488 0.974519 + outer loop + vertex 1.1011 1.90127 2.58104 + vertex 1.09935 1.9042 2.58073 + vertex 1.09626 1.90067 2.58181 + endloop + endfacet + facet normal 0.133091 0.181088 0.97442 + outer loop + vertex 1.1011 1.90127 2.58104 + vertex 1.09626 1.90067 2.58181 + vertex 1.10085 1.89667 2.58193 + endloop + endfacet + facet normal 0.122916 0.18186 0.975612 + outer loop + vertex 1.1011 1.90127 2.58104 + vertex 1.10085 1.89667 2.58193 + vertex 1.10524 1.89977 2.58079 + endloop + endfacet + facet normal 0.125078 0.188098 0.974153 + outer loop + vertex 1.10524 1.89977 2.58079 + vertex 1.10388 1.90471 2.58002 + vertex 1.1011 1.90127 2.58104 + endloop + endfacet + facet normal 0.113269 0.185169 0.976157 + outer loop + vertex 1.10388 1.90471 2.58002 + vertex 1.10524 1.89977 2.58079 + vertex 1.10983 1.9027 2.5797 + endloop + endfacet + facet normal 0.108971 0.191625 0.9754 + outer loop + vertex 1.10524 1.89977 2.58079 + vertex 1.10946 1.89829 2.58061 + vertex 1.10983 1.9027 2.5797 + endloop + endfacet + facet normal 0.10636 0.183983 0.977158 + outer loop + vertex 1.10946 1.89829 2.58061 + vertex 1.10524 1.89977 2.58079 + vertex 1.10671 1.89479 2.58157 + endloop + endfacet + facet normal 0.0977625 0.190626 0.976783 + outer loop + vertex 1.11132 1.8954 2.58099 + vertex 1.10946 1.89829 2.58061 + vertex 1.10671 1.89479 2.58157 + endloop + endfacet + facet normal 0.118879 0.187364 0.975071 + outer loop + vertex 1.10671 1.89479 2.58157 + vertex 1.10524 1.89977 2.58079 + vertex 1.10085 1.89667 2.58193 + endloop + endfacet + facet normal 0.113675 0.170374 0.978801 + outer loop + vertex 1.10229 1.89154 2.58265 + vertex 1.10671 1.89479 2.58157 + vertex 1.10085 1.89667 2.58193 + endloop + endfacet + facet normal 0.126899 0.173775 0.976575 + outer loop + vertex 1.10229 1.89154 2.58265 + vertex 1.10085 1.89667 2.58193 + vertex 1.09772 1.89213 2.58314 + endloop + endfacet + facet normal 0.126309 0.168287 0.977612 + outer loop + vertex 1.09872 1.88777 2.58376 + vertex 1.10229 1.89154 2.58265 + vertex 1.09772 1.89213 2.58314 + endloop + endfacet + facet normal 0.128727 0.168785 0.977211 + outer loop + vertex 1.09872 1.88777 2.58376 + vertex 1.09772 1.89213 2.58314 + vertex 1.0948 1.88867 2.58412 + endloop + endfacet + facet normal 0.128952 0.169851 0.976996 + outer loop + vertex 1.09475 1.8836 2.58501 + vertex 1.09872 1.88777 2.58376 + vertex 1.0948 1.88867 2.58412 + endloop + endfacet + facet normal 0.120706 0.170111 0.978004 + outer loop + vertex 1.08999 1.88786 2.58486 + vertex 1.09475 1.8836 2.58501 + vertex 1.0948 1.88867 2.58412 + endloop + endfacet + facet normal 0.121313 0.166926 0.978478 + outer loop + vertex 1.0948 1.88867 2.58412 + vertex 1.09329 1.89222 2.5837 + vertex 1.08999 1.88786 2.58486 + endloop + endfacet + facet normal 0.119225 0.168507 0.978463 + outer loop + vertex 1.08999 1.88786 2.58486 + vertex 1.09329 1.89222 2.5837 + vertex 1.08871 1.89278 2.58417 + endloop + endfacet + facet normal 0.114803 0.167463 0.979171 + outer loop + vertex 1.08999 1.88786 2.58486 + vertex 1.08871 1.89278 2.58417 + vertex 1.08408 1.88979 2.58522 + endloop + endfacet + facet normal 0.119462 0.170805 0.978036 + outer loop + vertex 1.09329 1.89222 2.5837 + vertex 1.09241 1.89642 2.58308 + vertex 1.08871 1.89278 2.58417 + endloop + endfacet + facet normal 0.118927 0.171339 0.978008 + outer loop + vertex 1.08871 1.89278 2.58417 + vertex 1.09241 1.89642 2.58308 + vertex 1.08811 1.897 2.5835 + endloop + endfacet + facet normal 0.116607 0.171056 0.978337 + outer loop + vertex 1.08871 1.89278 2.58417 + vertex 1.08811 1.897 2.5835 + vertex 1.08475 1.89409 2.58441 + endloop + endfacet + facet normal 0.119243 0.174075 0.977486 + outer loop + vertex 1.09241 1.89642 2.58308 + vertex 1.09135 1.9001 2.58255 + vertex 1.08811 1.897 2.5835 + endloop + endfacet + facet normal 0.118798 0.174532 0.977459 + outer loop + vertex 1.08811 1.897 2.5835 + vertex 1.09135 1.9001 2.58255 + vertex 1.08744 1.90137 2.5828 + endloop + endfacet + facet normal 0.117145 0.174318 0.977696 + outer loop + vertex 1.08811 1.897 2.5835 + vertex 1.08744 1.90137 2.5828 + vertex 1.08373 1.89774 2.58389 + endloop + endfacet + facet normal 0.119587 0.177092 0.976902 + outer loop + vertex 1.09135 1.9001 2.58255 + vertex 1.09187 1.90472 2.58165 + vertex 1.08744 1.90137 2.5828 + endloop + endfacet + facet normal 0.122442 0.173422 0.977207 + outer loop + vertex 1.08744 1.90137 2.5828 + vertex 1.09187 1.90472 2.58165 + vertex 1.0861 1.90659 2.58204 + endloop + endfacet + facet normal 0.119351 0.172702 0.977716 + outer loop + vertex 1.08744 1.90137 2.5828 + vertex 1.0861 1.90659 2.58204 + vertex 1.08289 1.90205 2.58324 + endloop + endfacet + facet normal 0.127238 0.17618 0.9761 + outer loop + vertex 1.09241 1.89642 2.58308 + vertex 1.09626 1.90067 2.58181 + vertex 1.09135 1.9001 2.58255 + endloop + endfacet + facet normal 0.126413 0.176919 0.976073 + outer loop + vertex 1.0962 1.89569 2.58272 + vertex 1.09626 1.90067 2.58181 + vertex 1.09241 1.89642 2.58308 + endloop + endfacet + facet normal 0.125547 0.171941 0.977074 + outer loop + vertex 1.09329 1.89222 2.5837 + vertex 1.0962 1.89569 2.58272 + vertex 1.09241 1.89642 2.58308 + endloop + endfacet + facet normal 0.127829 0.17004 0.977111 + outer loop + vertex 1.09772 1.89213 2.58314 + vertex 1.0962 1.89569 2.58272 + vertex 1.09329 1.89222 2.5837 + endloop + endfacet + facet normal 0.11893 0.168146 0.978561 + outer loop + vertex 1.08967 1.88345 2.58565 + vertex 1.09475 1.8836 2.58501 + vertex 1.08999 1.88786 2.58486 + endloop + endfacet + facet normal 0.111803 0.168788 0.979291 + outer loop + vertex 1.08548 1.88489 2.58588 + vertex 1.08967 1.88345 2.58565 + vertex 1.08999 1.88786 2.58486 + endloop + endfacet + facet normal 0.118688 0.172912 0.97776 + outer loop + vertex 1.08967 1.88345 2.58565 + vertex 1.09149 1.88052 2.58595 + vertex 1.09475 1.8836 2.58501 + endloop + endfacet + facet normal 0.117531 0.174112 0.977687 + outer loop + vertex 1.09459 1.87893 2.58586 + vertex 1.09475 1.8836 2.58501 + vertex 1.09149 1.88052 2.58595 + endloop + endfacet + facet normal 0.115246 0.169587 0.978754 + outer loop + vertex 1.09149 1.88052 2.58595 + vertex 1.0914 1.87581 2.58678 + vertex 1.09459 1.87893 2.58586 + endloop + endfacet + facet normal 0.114126 0.170709 0.97869 + outer loop + vertex 1.09549 1.87629 2.58622 + vertex 1.09459 1.87893 2.58586 + vertex 1.0914 1.87581 2.58678 + endloop + endfacet + facet normal 0.114015 0.171504 0.978564 + outer loop + vertex 1.09549 1.87629 2.58622 + vertex 1.0914 1.87581 2.58678 + vertex 1.09585 1.87209 2.58691 + endloop + endfacet + facet normal 0.11276 0.170016 0.978969 + outer loop + vertex 1.0914 1.87581 2.58678 + vertex 1.09135 1.87067 2.58768 + vertex 1.09585 1.87209 2.58691 + endloop + endfacet + facet normal 0.113917 0.16661 0.97942 + outer loop + vertex 1.09267 1.86678 2.58819 + vertex 1.09585 1.87209 2.58691 + vertex 1.09135 1.87067 2.58768 + endloop + endfacet + facet normal 0.110027 0.165378 0.980074 + outer loop + vertex 1.09267 1.86678 2.58819 + vertex 1.09135 1.87067 2.58768 + vertex 1.08821 1.86705 2.58864 + endloop + endfacet + facet normal 0.10996 0.163893 0.980331 + outer loop + vertex 1.0888 1.86274 2.58929 + vertex 1.09267 1.86678 2.58819 + vertex 1.08821 1.86705 2.58864 + endloop + endfacet + facet normal 0.105345 0.163354 0.980927 + outer loop + vertex 1.0888 1.86274 2.58929 + vertex 1.08821 1.86705 2.58864 + vertex 1.08474 1.86396 2.58953 + endloop + endfacet + facet normal 0.104575 0.160702 0.981447 + outer loop + vertex 1.08406 1.85976 2.59029 + vertex 1.0888 1.86274 2.58929 + vertex 1.08474 1.86396 2.58953 + endloop + endfacet + facet normal 0.102093 0.16114 0.981637 + outer loop + vertex 1.07947 1.8639 2.59008 + vertex 1.08406 1.85976 2.59029 + vertex 1.08474 1.86396 2.58953 + endloop + endfacet + facet normal 0.101951 0.16602 0.980838 + outer loop + vertex 1.08474 1.86396 2.58953 + vertex 1.08378 1.86764 2.589 + vertex 1.07947 1.8639 2.59008 + endloop + endfacet + facet normal 0.103396 0.164391 0.980961 + outer loop + vertex 1.07947 1.8639 2.59008 + vertex 1.08378 1.86764 2.589 + vertex 1.07978 1.86874 2.58924 + endloop + endfacet + facet normal 0.116566 0.163332 0.979661 + outer loop + vertex 1.07444 1.86868 2.58989 + vertex 1.07947 1.8639 2.59008 + vertex 1.07978 1.86874 2.58924 + endloop + endfacet + facet normal 0.110115 0.156606 0.981503 + outer loop + vertex 1.07442 1.86383 2.59066 + vertex 1.07947 1.8639 2.59008 + vertex 1.07444 1.86868 2.58989 + endloop + endfacet + facet normal 0.110139 0.155854 0.981621 + outer loop + vertex 1.07442 1.86383 2.59066 + vertex 1.07622 1.86072 2.59095 + vertex 1.07947 1.8639 2.59008 + endloop + endfacet + facet normal 0.106989 0.159021 0.981461 + outer loop + vertex 1.07949 1.85931 2.59083 + vertex 1.07947 1.8639 2.59008 + vertex 1.07622 1.86072 2.59095 + endloop + endfacet + facet normal 0.10722 0.159566 0.981347 + outer loop + vertex 1.07622 1.86072 2.59095 + vertex 1.0764 1.85589 2.59172 + vertex 1.07949 1.85931 2.59083 + endloop + endfacet + facet normal 0.103477 0.162901 0.981201 + outer loop + vertex 1.08137 1.85639 2.59111 + vertex 1.07949 1.85931 2.59083 + vertex 1.0764 1.85589 2.59172 + endloop + endfacet + facet normal 0.103833 0.15995 0.981649 + outer loop + vertex 1.08137 1.85639 2.59111 + vertex 1.0764 1.85589 2.59172 + vertex 1.08116 1.85176 2.59189 + endloop + endfacet + facet normal 0.0983255 0.160286 0.982161 + outer loop + vertex 1.08137 1.85639 2.59111 + vertex 1.08116 1.85176 2.59189 + vertex 1.08546 1.85503 2.59093 + endloop + endfacet + facet normal 0.0987981 0.161741 0.981875 + outer loop + vertex 1.08546 1.85503 2.59093 + vertex 1.08406 1.85976 2.59029 + vertex 1.08137 1.85639 2.59111 + endloop + endfacet + facet normal 0.103608 0.16307 0.981159 + outer loop + vertex 1.08406 1.85976 2.59029 + vertex 1.08546 1.85503 2.59093 + vertex 1.08987 1.85797 2.58997 + endloop + endfacet + facet normal 0.100699 0.167301 0.98075 + outer loop + vertex 1.08546 1.85503 2.59093 + vertex 1.08943 1.85382 2.59072 + vertex 1.08987 1.85797 2.58997 + endloop + endfacet + facet normal 0.100286 0.167351 0.980784 + outer loop + vertex 1.08943 1.85382 2.59072 + vertex 1.09401 1.85452 2.59014 + vertex 1.08987 1.85797 2.58997 + endloop + endfacet + facet normal 0.106347 0.174538 0.978891 + outer loop + vertex 1.08987 1.85797 2.58997 + vertex 1.09401 1.85452 2.59014 + vertex 1.09474 1.85868 2.58931 + endloop + endfacet + facet normal 0.107685 0.16661 0.980125 + outer loop + vertex 1.09474 1.85868 2.58931 + vertex 1.09359 1.86223 2.58884 + vertex 1.08987 1.85797 2.58997 + endloop + endfacet + facet normal 0.110753 0.163965 0.980229 + outer loop + vertex 1.08987 1.85797 2.58997 + vertex 1.09359 1.86223 2.58884 + vertex 1.0888 1.86274 2.58929 + endloop + endfacet + facet normal 0.10612 0.166138 0.980376 + outer loop + vertex 1.09474 1.85868 2.58931 + vertex 1.09811 1.8619 2.5884 + vertex 1.09359 1.86223 2.58884 + endloop + endfacet + facet normal 0.106198 0.167524 0.980131 + outer loop + vertex 1.09811 1.8619 2.5884 + vertex 1.09737 1.86643 2.58771 + vertex 1.09359 1.86223 2.58884 + endloop + endfacet + facet normal 0.11098 0.16326 0.980321 + outer loop + vertex 1.09359 1.86223 2.58884 + vertex 1.09737 1.86643 2.58771 + vertex 1.09267 1.86678 2.58819 + endloop + endfacet + facet normal 0.0994509 0.166566 0.981002 + outer loop + vertex 1.09811 1.8619 2.5884 + vertex 1.10132 1.86539 2.58749 + vertex 1.09737 1.86643 2.58771 + endloop + endfacet + facet normal 0.100101 0.16915 0.980494 + outer loop + vertex 1.10132 1.86539 2.58749 + vertex 1.1017 1.87049 2.58657 + vertex 1.09737 1.86643 2.58771 + endloop + endfacet + facet normal 0.10297 0.166157 0.980708 + outer loop + vertex 1.09737 1.86643 2.58771 + vertex 1.1017 1.87049 2.58657 + vertex 1.09585 1.87209 2.58691 + endloop + endfacet + facet normal 0.106039 0.177874 0.978323 + outer loop + vertex 1.1017 1.87049 2.58657 + vertex 1.09963 1.87776 2.58547 + vertex 1.09585 1.87209 2.58691 + endloop + endfacet + facet normal 0.0988695 0.175999 0.979413 + outer loop + vertex 1.10453 1.87428 2.5856 + vertex 1.09963 1.87776 2.58547 + vertex 1.1017 1.87049 2.58657 + endloop + endfacet + facet normal 0.10394 0.183052 0.977593 + outer loop + vertex 1.09963 1.87776 2.58547 + vertex 1.10453 1.87428 2.5856 + vertex 1.1059 1.87818 2.58473 + endloop + endfacet + facet normal 0.10329 0.190435 0.976251 + outer loop + vertex 1.1059 1.87818 2.58473 + vertex 1.10407 1.88249 2.58408 + vertex 1.09963 1.87776 2.58547 + endloop + endfacet + facet normal 0.112174 0.182266 0.97683 + outer loop + vertex 1.09963 1.87776 2.58547 + vertex 1.10407 1.88249 2.58408 + vertex 1.09997 1.88369 2.58433 + endloop + endfacet + facet normal 0.124979 0.181278 0.975458 + outer loop + vertex 1.09475 1.8836 2.58501 + vertex 1.09963 1.87776 2.58547 + vertex 1.09997 1.88369 2.58433 + endloop + endfacet + facet normal 0.111957 0.18149 0.976999 + outer loop + vertex 1.10407 1.88249 2.58408 + vertex 1.10314 1.88705 2.58334 + vertex 1.09997 1.88369 2.58433 + endloop + endfacet + facet normal 0.121841 0.172312 0.977478 + outer loop + vertex 1.09997 1.88369 2.58433 + vertex 1.10314 1.88705 2.58334 + vertex 1.09872 1.88777 2.58376 + endloop + endfacet + facet normal 0.1013 0.179575 0.978515 + outer loop + vertex 1.10407 1.88249 2.58408 + vertex 1.10751 1.88646 2.58299 + vertex 1.10314 1.88705 2.58334 + endloop + endfacet + facet normal 0.101252 0.179185 0.978591 + outer loop + vertex 1.10751 1.88646 2.58299 + vertex 1.10628 1.89024 2.58243 + vertex 1.10314 1.88705 2.58334 + endloop + endfacet + facet normal 0.110218 0.170518 0.979171 + outer loop + vertex 1.10314 1.88705 2.58334 + vertex 1.10628 1.89024 2.58243 + vertex 1.10229 1.89154 2.58265 + endloop + endfacet + facet normal 0.0962173 0.177671 0.979375 + outer loop + vertex 1.10751 1.88646 2.58299 + vertex 1.11128 1.89069 2.58186 + vertex 1.10628 1.89024 2.58243 + endloop + endfacet + facet normal 0.0964771 0.175279 0.97978 + outer loop + vertex 1.10671 1.89479 2.58157 + vertex 1.10628 1.89024 2.58243 + vertex 1.11128 1.89069 2.58186 + endloop + endfacet + facet normal 0.0950321 0.184916 0.978149 + outer loop + vertex 1.10857 1.88221 2.58369 + vertex 1.10751 1.88646 2.58299 + vertex 1.10407 1.88249 2.58408 + endloop + endfacet + facet normal 0.0893135 0.170104 0.98137 + outer loop + vertex 1.1017 1.87049 2.58657 + vertex 1.10132 1.86539 2.58749 + vertex 1.10589 1.86654 2.58687 + endloop + endfacet + facet normal 0.092936 0.173867 0.980374 + outer loop + vertex 1.10636 1.87106 2.58603 + vertex 1.1017 1.87049 2.58657 + vertex 1.10589 1.86654 2.58687 + endloop + endfacet + facet normal 0.0919062 0.18113 0.979155 + outer loop + vertex 1.10636 1.87106 2.58603 + vertex 1.10453 1.87428 2.5856 + vertex 1.1017 1.87049 2.58657 + endloop + endfacet + facet normal 0.105658 0.18858 0.976357 + outer loop + vertex 1.10453 1.87428 2.5856 + vertex 1.10636 1.87106 2.58603 + vertex 1.10919 1.87449 2.58506 + endloop + endfacet + facet normal 0.0889955 0.176046 0.980351 + outer loop + vertex 1.10256 1.86172 2.58803 + vertex 1.10132 1.86539 2.58749 + vertex 1.09811 1.8619 2.5884 + endloop + endfacet + facet normal 0.0955423 0.176982 0.979566 + outer loop + vertex 1.0987 1.85771 2.5891 + vertex 1.09811 1.8619 2.5884 + vertex 1.09474 1.85868 2.58931 + endloop + endfacet + facet normal 0.100247 0.167577 0.980749 + outer loop + vertex 1.08943 1.85382 2.59072 + vertex 1.09133 1.85118 2.59098 + vertex 1.09401 1.85452 2.59014 + endloop + endfacet + facet normal 0.09687 0.165223 0.981487 + outer loop + vertex 1.09133 1.85118 2.59098 + vertex 1.08943 1.85382 2.59072 + vertex 1.08689 1.85026 2.59157 + endloop + endfacet + facet normal 0.0971082 0.164176 0.98164 + outer loop + vertex 1.09133 1.85118 2.59098 + vertex 1.08689 1.85026 2.59157 + vertex 1.09112 1.8467 2.59175 + endloop + endfacet + facet normal 0.0905811 0.164579 0.982196 + outer loop + vertex 1.09133 1.85118 2.59098 + vertex 1.09112 1.8467 2.59175 + vertex 1.09537 1.84991 2.59082 + endloop + endfacet + facet normal 0.0886839 0.167031 0.981955 + outer loop + vertex 1.09693 1.84504 2.59151 + vertex 1.09537 1.84991 2.59082 + vertex 1.09112 1.8467 2.59175 + endloop + endfacet + facet normal 0.0853656 0.155073 0.984208 + outer loop + vertex 1.09238 1.84156 2.59245 + vertex 1.09693 1.84504 2.59151 + vertex 1.09112 1.8467 2.59175 + endloop + endfacet + facet normal 0.0932245 0.15687 0.983209 + outer loop + vertex 1.09238 1.84156 2.59245 + vertex 1.09112 1.8467 2.59175 + vertex 1.08759 1.84183 2.59286 + endloop + endfacet + facet normal 0.0929399 0.150146 0.984286 + outer loop + vertex 1.08826 1.83731 2.59349 + vertex 1.09238 1.84156 2.59245 + vertex 1.08759 1.84183 2.59286 + endloop + endfacet + facet normal 0.0970159 0.150681 0.983811 + outer loop + vertex 1.08826 1.83731 2.59349 + vertex 1.08759 1.84183 2.59286 + vertex 1.08356 1.83741 2.59394 + endloop + endfacet + facet normal 0.0969803 0.146529 0.984441 + outer loop + vertex 1.08456 1.83374 2.59439 + vertex 1.08826 1.83731 2.59349 + vertex 1.08356 1.83741 2.59394 + endloop + endfacet + facet normal 0.0983758 0.146883 0.98425 + outer loop + vertex 1.08456 1.83374 2.59439 + vertex 1.08356 1.83741 2.59394 + vertex 1.07968 1.83291 2.595 + endloop + endfacet + facet normal 0.0985192 0.14611 0.98435 + outer loop + vertex 1.07968 1.83291 2.595 + vertex 1.08373 1.82935 2.59512 + vertex 1.08456 1.83374 2.59439 + endloop + endfacet + facet normal 0.092915 0.147229 0.984729 + outer loop + vertex 1.08373 1.82935 2.59512 + vertex 1.08861 1.83272 2.59416 + vertex 1.08456 1.83374 2.59439 + endloop + endfacet + facet normal 0.0954377 0.142639 0.985163 + outer loop + vertex 1.07919 1.82866 2.59566 + vertex 1.08373 1.82935 2.59512 + vertex 1.07968 1.83291 2.595 + endloop + endfacet + facet normal 0.103702 0.141582 0.98448 + outer loop + vertex 1.07537 1.82998 2.59587 + vertex 1.07919 1.82866 2.59566 + vertex 1.07968 1.83291 2.595 + endloop + endfacet + facet normal 0.10307 0.142492 0.984415 + outer loop + vertex 1.07407 1.83479 2.59531 + vertex 1.07537 1.82998 2.59587 + vertex 1.07968 1.83291 2.595 + endloop + endfacet + facet normal 0.104559 0.147072 0.983584 + outer loop + vertex 1.07968 1.83291 2.595 + vertex 1.0788 1.83781 2.59436 + vertex 1.07407 1.83479 2.59531 + endloop + endfacet + facet normal 0.102659 0.149971 0.983346 + outer loop + vertex 1.07407 1.83479 2.59531 + vertex 1.0788 1.83781 2.59436 + vertex 1.07481 1.83906 2.59458 + endloop + endfacet + facet normal 0.111942 0.148227 0.982597 + outer loop + vertex 1.06963 1.83905 2.59517 + vertex 1.07407 1.83479 2.59531 + vertex 1.07481 1.83906 2.59458 + endloop + endfacet + facet normal 0.111778 0.156612 0.981315 + outer loop + vertex 1.07481 1.83906 2.59458 + vertex 1.07389 1.84277 2.5941 + vertex 1.06963 1.83905 2.59517 + endloop + endfacet + facet normal 0.114127 0.153964 0.981463 + outer loop + vertex 1.06963 1.83905 2.59517 + vertex 1.07389 1.84277 2.5941 + vertex 1.06989 1.84385 2.59439 + endloop + endfacet + facet normal 0.129578 0.152836 0.97972 + outer loop + vertex 1.06462 1.84391 2.59508 + vertex 1.06963 1.83905 2.59517 + vertex 1.06989 1.84385 2.59439 + endloop + endfacet + facet normal 0.129558 0.155091 0.979368 + outer loop + vertex 1.06989 1.84385 2.59439 + vertex 1.06882 1.84772 2.59392 + vertex 1.06462 1.84391 2.59508 + endloop + endfacet + facet normal 0.134442 0.149756 0.97954 + outer loop + vertex 1.06462 1.84391 2.59508 + vertex 1.06882 1.84772 2.59392 + vertex 1.06487 1.84893 2.59428 + endloop + endfacet + facet normal 0.120152 0.152674 0.980946 + outer loop + vertex 1.06989 1.84385 2.59439 + vertex 1.07326 1.84707 2.59348 + vertex 1.06882 1.84772 2.59392 + endloop + endfacet + facet normal 0.120646 0.156506 0.980281 + outer loop + vertex 1.07326 1.84707 2.59348 + vertex 1.07255 1.85146 2.59286 + vertex 1.06882 1.84772 2.59392 + endloop + endfacet + facet normal 0.126505 0.150711 0.98045 + outer loop + vertex 1.06882 1.84772 2.59392 + vertex 1.07255 1.85146 2.59286 + vertex 1.06818 1.85209 2.59333 + endloop + endfacet + facet normal 0.126979 0.154498 0.979799 + outer loop + vertex 1.07255 1.85146 2.59286 + vertex 1.07136 1.85539 2.5924 + vertex 1.06818 1.85209 2.59333 + endloop + endfacet + facet normal 0.117109 0.151709 0.981463 + outer loop + vertex 1.07255 1.85146 2.59286 + vertex 1.0764 1.85589 2.59172 + vertex 1.07136 1.85539 2.5924 + endloop + endfacet + facet normal 0.116977 0.152835 0.981304 + outer loop + vertex 1.0713 1.86058 2.5916 + vertex 1.07136 1.85539 2.5924 + vertex 1.0764 1.85589 2.59172 + endloop + endfacet + facet normal 0.134199 0.152699 0.979119 + outer loop + vertex 1.07136 1.85539 2.5924 + vertex 1.0713 1.86058 2.5916 + vertex 1.06748 1.85647 2.59276 + endloop + endfacet + facet normal 0.112134 0.156016 0.981369 + outer loop + vertex 1.07642 1.85063 2.59255 + vertex 1.0764 1.85589 2.59172 + vertex 1.07255 1.85146 2.59286 + endloop + endfacet + facet normal 0.111988 0.155281 0.981502 + outer loop + vertex 1.07326 1.84707 2.59348 + vertex 1.07642 1.85063 2.59255 + vertex 1.07255 1.85146 2.59286 + endloop + endfacet + facet normal 0.106327 0.160258 0.981332 + outer loop + vertex 1.07775 1.84679 2.59304 + vertex 1.07642 1.85063 2.59255 + vertex 1.07326 1.84707 2.59348 + endloop + endfacet + facet normal 0.106167 0.156737 0.981918 + outer loop + vertex 1.07389 1.84277 2.5941 + vertex 1.07775 1.84679 2.59304 + vertex 1.07326 1.84707 2.59348 + endloop + endfacet + facet normal 0.10364 0.159136 0.981802 + outer loop + vertex 1.07846 1.84229 2.59369 + vertex 1.07775 1.84679 2.59304 + vertex 1.07389 1.84277 2.5941 + endloop + endfacet + facet normal 0.103235 0.154641 0.982562 + outer loop + vertex 1.07481 1.83906 2.59458 + vertex 1.07846 1.84229 2.59369 + vertex 1.07389 1.84277 2.5941 + endloop + endfacet + facet normal 0.097046 0.158216 0.982624 + outer loop + vertex 1.07846 1.84229 2.59369 + vertex 1.08246 1.84649 2.59262 + vertex 1.07775 1.84679 2.59304 + endloop + endfacet + facet normal 0.097139 0.16016 0.9823 + outer loop + vertex 1.08246 1.84649 2.59262 + vertex 1.08116 1.85176 2.59189 + vertex 1.07775 1.84679 2.59304 + endloop + endfacet + facet normal 0.0959274 0.159883 0.982464 + outer loop + vertex 1.08246 1.84649 2.59262 + vertex 1.08689 1.85026 2.59157 + vertex 1.08116 1.85176 2.59189 + endloop + endfacet + facet normal 0.095218 0.1607 0.9824 + outer loop + vertex 1.08642 1.84559 2.59238 + vertex 1.08689 1.85026 2.59157 + vertex 1.08246 1.84649 2.59262 + endloop + endfacet + facet normal 0.0944851 0.157313 0.983018 + outer loop + vertex 1.08297 1.84186 2.59331 + vertex 1.08642 1.84559 2.59238 + vertex 1.08246 1.84649 2.59262 + endloop + endfacet + facet normal 0.0966259 0.155362 0.983121 + outer loop + vertex 1.08759 1.84183 2.59286 + vertex 1.08642 1.84559 2.59238 + vertex 1.08297 1.84186 2.59331 + endloop + endfacet + facet normal 0.0976907 0.15761 0.982657 + outer loop + vertex 1.08297 1.84186 2.59331 + vertex 1.08246 1.84649 2.59262 + vertex 1.07846 1.84229 2.59369 + endloop + endfacet + facet normal 0.0973584 0.153553 0.983332 + outer loop + vertex 1.0788 1.83781 2.59436 + vertex 1.08297 1.84186 2.59331 + vertex 1.07846 1.84229 2.59369 + endloop + endfacet + facet normal 0.0995395 0.151337 0.983458 + outer loop + vertex 1.08356 1.83741 2.59394 + vertex 1.08297 1.84186 2.59331 + vertex 1.0788 1.83781 2.59436 + endloop + endfacet + facet normal 0.100001 0.158202 0.98233 + outer loop + vertex 1.07775 1.84679 2.59304 + vertex 1.08116 1.85176 2.59189 + vertex 1.07642 1.85063 2.59255 + endloop + endfacet + facet normal 0.115129 0.157877 0.980724 + outer loop + vertex 1.07389 1.84277 2.5941 + vertex 1.07326 1.84707 2.59348 + vertex 1.06989 1.84385 2.59439 + endloop + endfacet + facet normal 0.110534 0.146772 0.982975 + outer loop + vertex 1.06967 1.83445 2.59586 + vertex 1.07407 1.83479 2.59531 + vertex 1.06963 1.83905 2.59517 + endloop + endfacet + facet normal 0.120503 0.146695 0.981814 + outer loop + vertex 1.06967 1.83445 2.59586 + vertex 1.06963 1.83905 2.59517 + vertex 1.06649 1.83594 2.59603 + endloop + endfacet + facet normal 0.119573 0.144659 0.98223 + outer loop + vertex 1.06649 1.83594 2.59603 + vertex 1.06662 1.83108 2.59672 + vertex 1.06967 1.83445 2.59586 + endloop + endfacet + facet normal 0.117038 0.146945 0.982196 + outer loop + vertex 1.07146 1.83147 2.59609 + vertex 1.06967 1.83445 2.59586 + vertex 1.06662 1.83108 2.59672 + endloop + endfacet + facet normal 0.11744 0.142835 0.982754 + outer loop + vertex 1.07146 1.83147 2.59609 + vertex 1.06662 1.83108 2.59672 + vertex 1.07119 1.82683 2.5968 + endloop + endfacet + facet normal 0.109489 0.143425 0.983586 + outer loop + vertex 1.07146 1.83147 2.59609 + vertex 1.07119 1.82683 2.5968 + vertex 1.07537 1.82998 2.59587 + endloop + endfacet + facet normal 0.10899 0.144076 0.983546 + outer loop + vertex 1.07677 1.82517 2.59642 + vertex 1.07537 1.82998 2.59587 + vertex 1.07119 1.82683 2.5968 + endloop + endfacet + facet normal 0.108212 0.141345 0.984028 + outer loop + vertex 1.07242 1.82151 2.59743 + vertex 1.07677 1.82517 2.59642 + vertex 1.07119 1.82683 2.5968 + endloop + endfacet + facet normal 0.113547 0.142487 0.983262 + outer loop + vertex 1.07242 1.82151 2.59743 + vertex 1.07119 1.82683 2.5968 + vertex 1.06773 1.8219 2.59791 + endloop + endfacet + facet normal 0.113403 0.140382 0.983582 + outer loop + vertex 1.06839 1.81728 2.59849 + vertex 1.07242 1.82151 2.59743 + vertex 1.06773 1.8219 2.59791 + endloop + endfacet + facet normal 0.118592 0.141036 0.982876 + outer loop + vertex 1.06839 1.81728 2.59849 + vertex 1.06773 1.8219 2.59791 + vertex 1.06379 1.81781 2.59897 + endloop + endfacet + facet normal 0.118247 0.137611 0.983403 + outer loop + vertex 1.06476 1.81384 2.59941 + vertex 1.06839 1.81728 2.59849 + vertex 1.06379 1.81781 2.59897 + endloop + endfacet + facet normal 0.125733 0.139313 0.982234 + outer loop + vertex 1.06476 1.81384 2.59941 + vertex 1.06379 1.81781 2.59897 + vertex 1.05946 1.81387 2.60009 + endloop + endfacet + facet normal 0.125776 0.135487 0.982763 + outer loop + vertex 1.05946 1.81387 2.60009 + vertex 1.06445 1.80882 2.60014 + vertex 1.06476 1.81384 2.59941 + endloop + endfacet + facet normal 0.116097 0.136242 0.983849 + outer loop + vertex 1.06445 1.80882 2.60014 + vertex 1.06879 1.8127 2.59909 + vertex 1.06476 1.81384 2.59941 + endloop + endfacet + facet normal 0.114567 0.137937 0.983793 + outer loop + vertex 1.06971 1.80879 2.59953 + vertex 1.06879 1.8127 2.59909 + vertex 1.06445 1.80882 2.60014 + endloop + endfacet + facet normal 0.114595 0.135378 0.984145 + outer loop + vertex 1.06445 1.80882 2.60014 + vertex 1.06938 1.80402 2.60023 + vertex 1.06971 1.80879 2.59953 + endloop + endfacet + facet normal 0.108059 0.13593 0.984808 + outer loop + vertex 1.06938 1.80402 2.60023 + vertex 1.07375 1.8078 2.59923 + vertex 1.06971 1.80879 2.59953 + endloop + endfacet + facet normal 0.108514 0.137877 0.984487 + outer loop + vertex 1.07375 1.8078 2.59923 + vertex 1.07344 1.81229 2.59863 + vertex 1.06971 1.80879 2.59953 + endloop + endfacet + facet normal 0.102637 0.137554 0.985162 + outer loop + vertex 1.07375 1.8078 2.59923 + vertex 1.07817 1.81205 2.59817 + vertex 1.07344 1.81229 2.59863 + endloop + endfacet + facet normal 0.10278 0.141325 0.984613 + outer loop + vertex 1.07817 1.81205 2.59817 + vertex 1.07757 1.81675 2.59756 + vertex 1.07344 1.81229 2.59863 + endloop + endfacet + facet normal 0.104334 0.139892 0.984655 + outer loop + vertex 1.07344 1.81229 2.59863 + vertex 1.07757 1.81675 2.59756 + vertex 1.07293 1.81681 2.59805 + endloop + endfacet + facet normal 0.109772 0.140419 0.983988 + outer loop + vertex 1.07344 1.81229 2.59863 + vertex 1.07293 1.81681 2.59805 + vertex 1.06879 1.8127 2.59909 + endloop + endfacet + facet normal 0.1115 0.138692 0.984039 + outer loop + vertex 1.06879 1.8127 2.59909 + vertex 1.07293 1.81681 2.59805 + vertex 1.06839 1.81728 2.59849 + endloop + endfacet + facet normal 0.104327 0.143872 0.984082 + outer loop + vertex 1.07757 1.81675 2.59756 + vertex 1.07637 1.82055 2.59713 + vertex 1.07293 1.81681 2.59805 + endloop + endfacet + facet normal 0.106959 0.14147 0.984147 + outer loop + vertex 1.07293 1.81681 2.59805 + vertex 1.07637 1.82055 2.59713 + vertex 1.07242 1.82151 2.59743 + endloop + endfacet + facet normal 0.0977825 0.141904 0.985039 + outer loop + vertex 1.07757 1.81675 2.59756 + vertex 1.08102 1.8216 2.59652 + vertex 1.07637 1.82055 2.59713 + endloop + endfacet + facet normal 0.0973922 0.143517 0.984844 + outer loop + vertex 1.07677 1.82517 2.59642 + vertex 1.07637 1.82055 2.59713 + vertex 1.08102 1.8216 2.59652 + endloop + endfacet + facet normal 0.100119 0.146737 0.984096 + outer loop + vertex 1.08108 1.82598 2.59586 + vertex 1.07677 1.82517 2.59642 + vertex 1.08102 1.8216 2.59652 + endloop + endfacet + facet normal 0.0874372 0.147098 0.98525 + outer loop + vertex 1.08108 1.82598 2.59586 + vertex 1.08102 1.8216 2.59652 + vertex 1.08514 1.82469 2.59569 + endloop + endfacet + facet normal 0.0877349 0.14806 0.985079 + outer loop + vertex 1.08514 1.82469 2.59569 + vertex 1.08373 1.82935 2.59512 + vertex 1.08108 1.82598 2.59586 + endloop + endfacet + facet normal 0.100416 0.145283 0.984281 + outer loop + vertex 1.08108 1.82598 2.59586 + vertex 1.07919 1.82866 2.59566 + vertex 1.07677 1.82517 2.59642 + endloop + endfacet + facet normal 0.0941228 0.144495 0.985019 + outer loop + vertex 1.08242 1.8165 2.59713 + vertex 1.08102 1.8216 2.59652 + vertex 1.07757 1.81675 2.59756 + endloop + endfacet + facet normal 0.0939689 0.14034 0.985634 + outer loop + vertex 1.07817 1.81205 2.59817 + vertex 1.08242 1.8165 2.59713 + vertex 1.07757 1.81675 2.59756 + endloop + endfacet + facet normal 0.0939381 0.140369 0.985633 + outer loop + vertex 1.08295 1.81178 2.59776 + vertex 1.08242 1.8165 2.59713 + vertex 1.07817 1.81205 2.59817 + endloop + endfacet + facet normal 0.0937868 0.13684 0.986143 + outer loop + vertex 1.07845 1.80738 2.5988 + vertex 1.08295 1.81178 2.59776 + vertex 1.07817 1.81205 2.59817 + endloop + endfacet + facet normal 0.0930869 0.137547 0.986111 + outer loop + vertex 1.08326 1.80704 2.59839 + vertex 1.08295 1.81178 2.59776 + vertex 1.07845 1.80738 2.5988 + endloop + endfacet + facet normal 0.0929206 0.134727 0.986516 + outer loop + vertex 1.07865 1.80276 2.59941 + vertex 1.08326 1.80704 2.59839 + vertex 1.07845 1.80738 2.5988 + endloop + endfacet + facet normal 0.10227 0.135001 0.985553 + outer loop + vertex 1.07865 1.80276 2.59941 + vertex 1.07845 1.80738 2.5988 + vertex 1.07454 1.80402 2.59966 + endloop + endfacet + facet normal 0.102423 0.135514 0.985467 + outer loop + vertex 1.07385 1.79978 2.60032 + vertex 1.07865 1.80276 2.59941 + vertex 1.07454 1.80402 2.59966 + endloop + endfacet + facet normal 0.10838 0.134473 0.984973 + outer loop + vertex 1.06938 1.80402 2.60023 + vertex 1.07385 1.79978 2.60032 + vertex 1.07454 1.80402 2.59966 + endloop + endfacet + facet normal 0.108894 0.135012 0.984842 + outer loop + vertex 1.0695 1.79954 2.60083 + vertex 1.07385 1.79978 2.60032 + vertex 1.06938 1.80402 2.60023 + endloop + endfacet + facet normal 0.111761 0.135046 0.984516 + outer loop + vertex 1.0695 1.79954 2.60083 + vertex 1.06938 1.80402 2.60023 + vertex 1.06638 1.80101 2.60098 + endloop + endfacet + facet normal 0.111865 0.135271 0.984473 + outer loop + vertex 1.06638 1.80101 2.60098 + vertex 1.06661 1.79622 2.60161 + vertex 1.0695 1.79954 2.60083 + endloop + endfacet + facet normal 0.11134 0.135728 0.98447 + outer loop + vertex 1.07138 1.79662 2.60102 + vertex 1.0695 1.79954 2.60083 + vertex 1.06661 1.79622 2.60161 + endloop + endfacet + facet normal 0.111458 0.134546 0.984619 + outer loop + vertex 1.07138 1.79662 2.60102 + vertex 1.06661 1.79622 2.60161 + vertex 1.07127 1.79202 2.60166 + endloop + endfacet + facet normal 0.10876 0.13465 0.984906 + outer loop + vertex 1.07138 1.79662 2.60102 + vertex 1.07127 1.79202 2.60166 + vertex 1.07537 1.795 2.6008 + endloop + endfacet + facet normal 0.108674 0.134435 0.984945 + outer loop + vertex 1.07537 1.795 2.6008 + vertex 1.07385 1.79978 2.60032 + vertex 1.07138 1.79662 2.60102 + endloop + endfacet + facet normal 0.099375 0.131614 0.986307 + outer loop + vertex 1.07385 1.79978 2.60032 + vertex 1.07537 1.795 2.6008 + vertex 1.07968 1.79768 2.60001 + endloop + endfacet + facet normal 0.0988804 0.132392 0.986253 + outer loop + vertex 1.07537 1.795 2.6008 + vertex 1.07937 1.79342 2.60061 + vertex 1.07968 1.79768 2.60001 + endloop + endfacet + facet normal 0.0994108 0.133762 0.986015 + outer loop + vertex 1.07937 1.79342 2.60061 + vertex 1.07537 1.795 2.6008 + vertex 1.07703 1.79015 2.60129 + endloop + endfacet + facet normal 0.10747 0.136395 0.984808 + outer loop + vertex 1.07703 1.79015 2.60129 + vertex 1.07537 1.795 2.6008 + vertex 1.07127 1.79202 2.60166 + endloop + endfacet + facet normal 0.110299 0.133267 0.984923 + outer loop + vertex 1.06661 1.79622 2.60161 + vertex 1.06656 1.79092 2.60234 + vertex 1.07127 1.79202 2.60166 + endloop + endfacet + facet normal 0.110402 0.132852 0.984968 + outer loop + vertex 1.06773 1.78694 2.60274 + vertex 1.07127 1.79202 2.60166 + vertex 1.06656 1.79092 2.60234 + endloop + endfacet + facet normal 0.110169 0.132787 0.985003 + outer loop + vertex 1.06773 1.78694 2.60274 + vertex 1.06656 1.79092 2.60234 + vertex 1.06305 1.78697 2.60326 + endloop + endfacet + facet normal 0.110186 0.130585 0.985295 + outer loop + vertex 1.06346 1.78242 2.60382 + vertex 1.06773 1.78694 2.60274 + vertex 1.06305 1.78697 2.60326 + endloop + endfacet + facet normal 0.112139 0.131038 0.985015 + outer loop + vertex 1.06305 1.78697 2.60326 + vertex 1.06656 1.79092 2.60234 + vertex 1.06265 1.79161 2.60269 + endloop + endfacet + facet normal 0.115028 0.131246 0.984654 + outer loop + vertex 1.06305 1.78697 2.60326 + vertex 1.06265 1.79161 2.60269 + vertex 1.05853 1.7874 2.60373 + endloop + endfacet + facet normal 0.114705 0.127231 0.985218 + outer loop + vertex 1.05884 1.78286 2.60428 + vertex 1.06305 1.78697 2.60326 + vertex 1.05853 1.7874 2.60373 + endloop + endfacet + facet normal 0.118802 0.127563 0.98469 + outer loop + vertex 1.05853 1.7874 2.60373 + vertex 1.06265 1.79161 2.60269 + vertex 1.05812 1.79198 2.60319 + endloop + endfacet + facet normal 0.124239 0.127971 0.983965 + outer loop + vertex 1.05853 1.7874 2.60373 + vertex 1.05812 1.79198 2.60319 + vertex 1.05387 1.78795 2.60425 + endloop + endfacet + facet normal 0.128803 0.123169 0.983991 + outer loop + vertex 1.05387 1.78795 2.60425 + vertex 1.05812 1.79198 2.60319 + vertex 1.05358 1.79274 2.60369 + endloop + endfacet + facet normal 0.129668 0.128928 0.98314 + outer loop + vertex 1.05812 1.79198 2.60319 + vertex 1.05771 1.79661 2.60264 + vertex 1.05358 1.79274 2.60369 + endloop + endfacet + facet normal 0.134035 0.12428 0.983153 + outer loop + vertex 1.05358 1.79274 2.60369 + vertex 1.05771 1.79661 2.60264 + vertex 1.05332 1.79724 2.60315 + endloop + endfacet + facet normal 0.141323 0.124578 0.982094 + outer loop + vertex 1.05358 1.79274 2.60369 + vertex 1.05332 1.79724 2.60315 + vertex 1.0498 1.79396 2.60408 + endloop + endfacet + facet normal 0.134692 0.129473 0.982392 + outer loop + vertex 1.05771 1.79661 2.60264 + vertex 1.0566 1.80061 2.60226 + vertex 1.05332 1.79724 2.60315 + endloop + endfacet + facet normal 0.140219 0.124064 0.982317 + outer loop + vertex 1.05332 1.79724 2.60315 + vertex 1.0566 1.80061 2.60226 + vertex 1.05265 1.80171 2.60269 + endloop + endfacet + facet normal 0.141532 0.129089 0.981481 + outer loop + vertex 1.0566 1.80061 2.60226 + vertex 1.05645 1.80585 2.60159 + vertex 1.05265 1.80171 2.60269 + endloop + endfacet + facet normal 0.127604 0.128945 0.983408 + outer loop + vertex 1.05645 1.80585 2.60159 + vertex 1.0566 1.80061 2.60226 + vertex 1.06161 1.8009 2.60157 + endloop + endfacet + facet normal 0.133881 0.135497 0.981691 + outer loop + vertex 1.0613 1.8058 2.60094 + vertex 1.05645 1.80585 2.60159 + vertex 1.06161 1.8009 2.60157 + endloop + endfacet + facet normal 0.121355 0.134914 0.983398 + outer loop + vertex 1.0613 1.8058 2.60094 + vertex 1.06161 1.8009 2.60157 + vertex 1.06457 1.80409 2.60077 + endloop + endfacet + facet normal 0.120627 0.133488 0.983682 + outer loop + vertex 1.06457 1.80409 2.60077 + vertex 1.06445 1.80882 2.60014 + vertex 1.0613 1.8058 2.60094 + endloop + endfacet + facet normal 0.12285 0.131179 0.983717 + outer loop + vertex 1.05945 1.80904 2.60074 + vertex 1.0613 1.8058 2.60094 + vertex 1.06445 1.80882 2.60014 + endloop + endfacet + facet normal 0.118545 0.137516 0.98338 + outer loop + vertex 1.06638 1.80101 2.60098 + vertex 1.06457 1.80409 2.60077 + vertex 1.06161 1.8009 2.60157 + endloop + endfacet + facet normal 0.133866 0.137325 0.981439 + outer loop + vertex 1.0613 1.8058 2.60094 + vertex 1.05945 1.80904 2.60074 + vertex 1.05645 1.80585 2.60159 + endloop + endfacet + facet normal 0.127701 0.127639 0.983565 + outer loop + vertex 1.05771 1.79661 2.60264 + vertex 1.06161 1.8009 2.60157 + vertex 1.0566 1.80061 2.60226 + endloop + endfacet + facet normal 0.123524 0.13145 0.983597 + outer loop + vertex 1.06164 1.79563 2.60227 + vertex 1.06161 1.8009 2.60157 + vertex 1.05771 1.79661 2.60264 + endloop + endfacet + facet normal 0.114934 0.131547 0.984625 + outer loop + vertex 1.06161 1.8009 2.60157 + vertex 1.06164 1.79563 2.60227 + vertex 1.06661 1.79622 2.60161 + endloop + endfacet + facet normal 0.115 0.131055 0.984682 + outer loop + vertex 1.06265 1.79161 2.60269 + vertex 1.06661 1.79622 2.60161 + vertex 1.06164 1.79563 2.60227 + endloop + endfacet + facet normal 0.122818 0.12844 0.984083 + outer loop + vertex 1.05812 1.79198 2.60319 + vertex 1.06164 1.79563 2.60227 + vertex 1.05771 1.79661 2.60264 + endloop + endfacet + facet normal 0.1191 0.132018 0.984066 + outer loop + vertex 1.06265 1.79161 2.60269 + vertex 1.06164 1.79563 2.60227 + vertex 1.05812 1.79198 2.60319 + endloop + endfacet + facet normal 0.109335 0.133599 0.984986 + outer loop + vertex 1.0726 1.78666 2.60224 + vertex 1.07127 1.79202 2.60166 + vertex 1.06773 1.78694 2.60274 + endloop + endfacet + facet normal 0.106379 0.132912 0.985402 + outer loop + vertex 1.0726 1.78666 2.60224 + vertex 1.07703 1.79015 2.60129 + vertex 1.07127 1.79202 2.60166 + endloop + endfacet + facet normal 0.105939 0.133463 0.985375 + outer loop + vertex 1.07669 1.78559 2.60194 + vertex 1.07703 1.79015 2.60129 + vertex 1.0726 1.78666 2.60224 + endloop + endfacet + facet normal 0.112488 0.133213 0.984683 + outer loop + vertex 1.06656 1.79092 2.60234 + vertex 1.06661 1.79622 2.60161 + vertex 1.06265 1.79161 2.60269 + endloop + endfacet + facet normal 0.118627 0.135488 0.983652 + outer loop + vertex 1.06638 1.80101 2.60098 + vertex 1.06161 1.8009 2.60157 + vertex 1.06661 1.79622 2.60161 + endloop + endfacet + facet normal 0.112672 0.134142 0.984536 + outer loop + vertex 1.06457 1.80409 2.60077 + vertex 1.06638 1.80101 2.60098 + vertex 1.06938 1.80402 2.60023 + endloop + endfacet + facet normal 0.108949 0.13422 0.984944 + outer loop + vertex 1.0695 1.79954 2.60083 + vertex 1.07138 1.79662 2.60102 + vertex 1.07385 1.79978 2.60032 + endloop + endfacet + facet normal 0.101344 0.137219 0.985343 + outer loop + vertex 1.07968 1.79768 2.60001 + vertex 1.07865 1.80276 2.59941 + vertex 1.07385 1.79978 2.60032 + endloop + endfacet + facet normal 0.0902656 0.135143 0.986706 + outer loop + vertex 1.07968 1.79768 2.60001 + vertex 1.08363 1.80227 2.59902 + vertex 1.07865 1.80276 2.59941 + endloop + endfacet + facet normal 0.081285 0.142802 0.986408 + outer loop + vertex 1.08466 1.79841 2.59949 + vertex 1.08363 1.80227 2.59902 + vertex 1.07968 1.79768 2.60001 + endloop + endfacet + facet normal 0.0810171 0.14448 0.986185 + outer loop + vertex 1.07968 1.79768 2.60001 + vertex 1.08427 1.79366 2.60022 + vertex 1.08466 1.79841 2.59949 + endloop + endfacet + facet normal 0.0722806 0.134601 0.98826 + outer loop + vertex 1.07937 1.79342 2.60061 + vertex 1.08427 1.79366 2.60022 + vertex 1.07968 1.79768 2.60001 + endloop + endfacet + facet normal 0.0728876 0.124597 0.989527 + outer loop + vertex 1.07937 1.79342 2.60061 + vertex 1.08127 1.79063 2.60082 + vertex 1.08427 1.79366 2.60022 + endloop + endfacet + facet normal 0.0624682 0.134784 0.988904 + outer loop + vertex 1.08441 1.7894 2.60079 + vertex 1.08427 1.79366 2.60022 + vertex 1.08127 1.79063 2.60082 + endloop + endfacet + facet normal 0.0639321 0.138542 0.988291 + outer loop + vertex 1.08127 1.79063 2.60082 + vertex 1.08165 1.78617 2.60142 + vertex 1.08441 1.7894 2.60079 + endloop + endfacet + facet normal 0.0928975 0.140646 0.985692 + outer loop + vertex 1.08127 1.79063 2.60082 + vertex 1.07703 1.79015 2.60129 + vertex 1.08165 1.78617 2.60142 + endloop + endfacet + facet normal 0.0880033 0.134999 0.98693 + outer loop + vertex 1.07703 1.79015 2.60129 + vertex 1.07669 1.78559 2.60194 + vertex 1.08165 1.78617 2.60142 + endloop + endfacet + facet normal 0.0888595 0.128409 0.987732 + outer loop + vertex 1.07766 1.78166 2.60237 + vertex 1.08165 1.78617 2.60142 + vertex 1.07669 1.78559 2.60194 + endloop + endfacet + facet normal 0.104618 0.132074 0.985704 + outer loop + vertex 1.07766 1.78166 2.60237 + vertex 1.07669 1.78559 2.60194 + vertex 1.07302 1.78185 2.60284 + endloop + endfacet + facet normal 0.105401 0.131309 0.985722 + outer loop + vertex 1.07302 1.78185 2.60284 + vertex 1.07669 1.78559 2.60194 + vertex 1.0726 1.78666 2.60224 + endloop + endfacet + facet normal 0.0871659 0.129896 0.987689 + outer loop + vertex 1.08164 1.78106 2.6021 + vertex 1.08165 1.78617 2.60142 + vertex 1.07766 1.78166 2.60237 + endloop + endfacet + facet normal 0.0866027 0.125923 0.988253 + outer loop + vertex 1.07803 1.77692 2.60294 + vertex 1.08164 1.78106 2.6021 + vertex 1.07766 1.78166 2.60237 + endloop + endfacet + facet normal 0.103912 0.12705 0.986438 + outer loop + vertex 1.07803 1.77692 2.60294 + vertex 1.07766 1.78166 2.60237 + vertex 1.07326 1.77707 2.60342 + endloop + endfacet + facet normal 0.103758 0.118381 0.987532 + outer loop + vertex 1.07344 1.77227 2.60398 + vertex 1.07803 1.77692 2.60294 + vertex 1.07326 1.77707 2.60342 + endloop + endfacet + facet normal 0.103113 0.119018 0.987523 + outer loop + vertex 1.07829 1.77206 2.6035 + vertex 1.07803 1.77692 2.60294 + vertex 1.07344 1.77227 2.60398 + endloop + endfacet + facet normal 0.102687 0.106123 0.989037 + outer loop + vertex 1.07364 1.76759 2.60446 + vertex 1.07829 1.77206 2.6035 + vertex 1.07344 1.77227 2.60398 + endloop + endfacet + facet normal 0.114703 0.106507 0.987674 + outer loop + vertex 1.07364 1.76759 2.60446 + vertex 1.07344 1.77227 2.60398 + vertex 1.06958 1.76873 2.60481 + endloop + endfacet + facet normal 0.111945 0.0962975 0.989037 + outer loop + vertex 1.0693 1.76379 2.60532 + vertex 1.07364 1.76759 2.60446 + vertex 1.06958 1.76873 2.60481 + endloop + endfacet + facet normal 0.110676 0.0963839 0.989172 + outer loop + vertex 1.06441 1.76894 2.60537 + vertex 1.0693 1.76379 2.60532 + vertex 1.06958 1.76873 2.60481 + endloop + endfacet + facet normal 0.115339 0.100805 0.988198 + outer loop + vertex 1.06463 1.76428 2.60582 + vertex 1.0693 1.76379 2.60532 + vertex 1.06441 1.76894 2.60537 + endloop + endfacet + facet normal 0.109477 0.100598 0.988886 + outer loop + vertex 1.06463 1.76428 2.60582 + vertex 1.06441 1.76894 2.60537 + vertex 1.06147 1.76615 2.60598 + endloop + endfacet + facet normal 0.100043 0.0844442 0.991393 + outer loop + vertex 1.06147 1.76615 2.60598 + vertex 1.06183 1.76125 2.60636 + vertex 1.06463 1.76428 2.60582 + endloop + endfacet + facet normal 0.102644 0.0820265 0.99133 + outer loop + vertex 1.06639 1.76107 2.6059 + vertex 1.06463 1.76428 2.60582 + vertex 1.06183 1.76125 2.60636 + endloop + endfacet + facet normal 0.102303 0.071705 0.992166 + outer loop + vertex 1.06639 1.76107 2.6059 + vertex 1.06183 1.76125 2.60636 + vertex 1.0666 1.75635 2.60622 + endloop + endfacet + facet normal 0.108538 0.0719421 0.991486 + outer loop + vertex 1.06639 1.76107 2.6059 + vertex 1.0666 1.75635 2.60622 + vertex 1.06936 1.75918 2.60571 + endloop + endfacet + facet normal 0.11687 0.0853132 0.989476 + outer loop + vertex 1.06936 1.75918 2.60571 + vertex 1.0693 1.76379 2.60532 + vertex 1.06639 1.76107 2.6059 + endloop + endfacet + facet normal 0.114189 0.0853019 0.98979 + outer loop + vertex 1.06936 1.75918 2.60571 + vertex 1.07393 1.75873 2.60523 + vertex 1.0693 1.76379 2.60532 + endloop + endfacet + facet normal 0.113141 0.0843386 0.989993 + outer loop + vertex 1.0693 1.76379 2.60532 + vertex 1.07393 1.75873 2.60523 + vertex 1.07445 1.76357 2.60475 + endloop + endfacet + facet normal 0.112892 0.070991 0.991068 + outer loop + vertex 1.06936 1.75918 2.60571 + vertex 1.07086 1.75608 2.60577 + vertex 1.07393 1.75873 2.60523 + endloop + endfacet + facet normal 0.112218 0.0717756 0.991088 + outer loop + vertex 1.07366 1.75409 2.60559 + vertex 1.07393 1.75873 2.60523 + vertex 1.07086 1.75608 2.60577 + endloop + endfacet + facet normal 0.110039 0.0686536 0.991553 + outer loop + vertex 1.07086 1.75608 2.60577 + vertex 1.07071 1.7518 2.60608 + vertex 1.07366 1.75409 2.60559 + endloop + endfacet + facet normal 0.106233 0.0735864 0.991615 + outer loop + vertex 1.0753 1.75009 2.60571 + vertex 1.07366 1.75409 2.60559 + vertex 1.07071 1.7518 2.60608 + endloop + endfacet + facet normal 0.0895546 0.0668294 0.993737 + outer loop + vertex 1.07366 1.75409 2.60559 + vertex 1.0753 1.75009 2.60571 + vertex 1.07812 1.75401 2.60519 + endloop + endfacet + facet normal 0.0768156 0.0760533 0.99414 + outer loop + vertex 1.08015 1.74834 2.60547 + vertex 1.07812 1.75401 2.60519 + vertex 1.0753 1.75009 2.60571 + endloop + endfacet + facet normal 0.065742 0.0721452 0.995225 + outer loop + vertex 1.08015 1.74834 2.60547 + vertex 1.08349 1.75264 2.60494 + vertex 1.07812 1.75401 2.60519 + endloop + endfacet + facet normal 0.0582134 0.0779863 0.995253 + outer loop + vertex 1.08471 1.74866 2.60518 + vertex 1.08349 1.75264 2.60494 + vertex 1.08015 1.74834 2.60547 + endloop + endfacet + facet normal 0.110549 0.0686315 0.991498 + outer loop + vertex 1.07086 1.75608 2.60577 + vertex 1.0666 1.75635 2.60622 + vertex 1.07071 1.7518 2.60608 + endloop + endfacet + facet normal 0.110398 0.0684945 0.991524 + outer loop + vertex 1.0666 1.75635 2.60622 + vertex 1.06666 1.75123 2.60657 + vertex 1.07071 1.7518 2.60608 + endloop + endfacet + facet normal 0.105845 0.0684785 0.992022 + outer loop + vertex 1.06666 1.75123 2.60657 + vertex 1.0666 1.75635 2.60622 + vertex 1.06295 1.75198 2.60691 + endloop + endfacet + facet normal 0.105329 0.0689143 0.992047 + outer loop + vertex 1.06295 1.75198 2.60691 + vertex 1.0666 1.75635 2.60622 + vertex 1.06194 1.75602 2.60674 + endloop + endfacet + facet normal 0.107084 0.0693453 0.991829 + outer loop + vertex 1.06295 1.75198 2.60691 + vertex 1.06194 1.75602 2.60674 + vertex 1.05832 1.75209 2.6074 + endloop + endfacet + facet normal 0.110619 0.0699028 0.991402 + outer loop + vertex 1.07086 1.75608 2.60577 + vertex 1.06936 1.75918 2.60571 + vertex 1.0666 1.75635 2.60622 + endloop + endfacet + facet normal 0.104922 0.0742651 0.991704 + outer loop + vertex 1.06183 1.76125 2.60636 + vertex 1.06194 1.75602 2.60674 + vertex 1.0666 1.75635 2.60622 + endloop + endfacet + facet normal 0.103798 0.0846847 0.990987 + outer loop + vertex 1.06147 1.76615 2.60598 + vertex 1.05675 1.76622 2.60647 + vertex 1.06183 1.76125 2.60636 + endloop + endfacet + facet normal 0.10735 0.102841 0.988888 + outer loop + vertex 1.05961 1.76937 2.60584 + vertex 1.06147 1.76615 2.60598 + vertex 1.06441 1.76894 2.60537 + endloop + endfacet + facet normal 0.114141 0.088246 0.989538 + outer loop + vertex 1.06463 1.76428 2.60582 + vertex 1.06639 1.76107 2.6059 + vertex 1.0693 1.76379 2.60532 + endloop + endfacet + facet normal 0.113453 0.094573 0.989032 + outer loop + vertex 1.07445 1.76357 2.60475 + vertex 1.07364 1.76759 2.60446 + vertex 1.0693 1.76379 2.60532 + endloop + endfacet + facet normal 0.100961 0.0921803 0.990611 + outer loop + vertex 1.07445 1.76357 2.60475 + vertex 1.07846 1.7672 2.60401 + vertex 1.07364 1.76759 2.60446 + endloop + endfacet + facet normal 0.0985055 0.094894 0.990602 + outer loop + vertex 1.07854 1.76253 2.60445 + vertex 1.07846 1.7672 2.60401 + vertex 1.07445 1.76357 2.60475 + endloop + endfacet + facet normal 0.111766 0.109702 0.987661 + outer loop + vertex 1.06958 1.76873 2.60481 + vertex 1.07344 1.77227 2.60398 + vertex 1.06872 1.77275 2.60446 + endloop + endfacet + facet normal 0.101988 0.10685 0.989031 + outer loop + vertex 1.07846 1.7672 2.60401 + vertex 1.07829 1.77206 2.6035 + vertex 1.07364 1.76759 2.60446 + endloop + endfacet + facet normal 0.0786863 0.106301 0.991216 + outer loop + vertex 1.07846 1.7672 2.60401 + vertex 1.08335 1.77208 2.6031 + vertex 1.07829 1.77206 2.6035 + endloop + endfacet + facet normal 0.0784863 0.120435 0.989614 + outer loop + vertex 1.08335 1.77208 2.6031 + vertex 1.08288 1.77705 2.60253 + vertex 1.07829 1.77206 2.6035 + endloop + endfacet + facet normal 0.0770638 0.107918 0.991168 + outer loop + vertex 1.08341 1.76706 2.60364 + vertex 1.08335 1.77208 2.6031 + vertex 1.07846 1.7672 2.60401 + endloop + endfacet + facet normal 0.0810694 0.118079 0.989689 + outer loop + vertex 1.07829 1.77206 2.6035 + vertex 1.08288 1.77705 2.60253 + vertex 1.07803 1.77692 2.60294 + endloop + endfacet + facet normal 0.080581 0.131144 0.988083 + outer loop + vertex 1.08288 1.77705 2.60253 + vertex 1.08164 1.78106 2.6021 + vertex 1.07803 1.77692 2.60294 + endloop + endfacet + facet normal 0.0932095 0.138208 0.986007 + outer loop + vertex 1.08127 1.79063 2.60082 + vertex 1.07937 1.79342 2.60061 + vertex 1.07703 1.79015 2.60129 + endloop + endfacet + facet normal 0.102706 0.134498 0.985577 + outer loop + vertex 1.07454 1.80402 2.59966 + vertex 1.07845 1.80738 2.5988 + vertex 1.07375 1.8078 2.59923 + endloop + endfacet + facet normal 0.0904553 0.137347 0.986384 + outer loop + vertex 1.08363 1.80227 2.59902 + vertex 1.08326 1.80704 2.59839 + vertex 1.07865 1.80276 2.59941 + endloop + endfacet + facet normal 0.0778364 0.136735 0.987545 + outer loop + vertex 1.08326 1.80704 2.59839 + vertex 1.08762 1.81156 2.59742 + vertex 1.08295 1.81178 2.59776 + endloop + endfacet + facet normal 0.0779911 0.140981 0.986936 + outer loop + vertex 1.08762 1.81156 2.59742 + vertex 1.08658 1.81546 2.59694 + vertex 1.08295 1.81178 2.59776 + endloop + endfacet + facet normal 0.0614875 0.136777 0.988692 + outer loop + vertex 1.08762 1.81156 2.59742 + vertex 1.09164 1.81608 2.59654 + vertex 1.08658 1.81546 2.59694 + endloop + endfacet + facet normal 0.060658 0.137504 0.988642 + outer loop + vertex 1.0916 1.81096 2.59726 + vertex 1.09164 1.81608 2.59654 + vertex 1.08762 1.81156 2.59742 + endloop + endfacet + facet normal 0.0607752 0.138309 0.988523 + outer loop + vertex 1.08805 1.80687 2.59805 + vertex 1.0916 1.81096 2.59726 + vertex 1.08762 1.81156 2.59742 + endloop + endfacet + facet normal 0.0565428 0.141934 0.98826 + outer loop + vertex 1.09275 1.80697 2.59777 + vertex 1.0916 1.81096 2.59726 + vertex 1.08805 1.80687 2.59805 + endloop + endfacet + facet normal 0.0618531 0.137486 0.988571 + outer loop + vertex 1.09164 1.81608 2.59654 + vertex 1.0916 1.81096 2.59726 + vertex 1.09623 1.8122 2.5968 + endloop + endfacet + facet normal 0.0599952 0.135312 0.988985 + outer loop + vertex 1.0965 1.81669 2.59617 + vertex 1.09164 1.81608 2.59654 + vertex 1.09623 1.8122 2.5968 + endloop + endfacet + facet normal 0.0749933 0.139443 0.987386 + outer loop + vertex 1.08805 1.80687 2.59805 + vertex 1.08762 1.81156 2.59742 + vertex 1.08326 1.80704 2.59839 + endloop + endfacet + facet normal 0.0749138 0.136332 0.987827 + outer loop + vertex 1.08363 1.80227 2.59902 + vertex 1.08805 1.80687 2.59805 + vertex 1.08326 1.80704 2.59839 + endloop + endfacet + facet normal 0.0672063 0.143645 0.987345 + outer loop + vertex 1.08845 1.80222 2.5987 + vertex 1.08805 1.80687 2.59805 + vertex 1.08363 1.80227 2.59902 + endloop + endfacet + facet normal 0.0800119 0.139012 0.987053 + outer loop + vertex 1.08295 1.81178 2.59776 + vertex 1.08658 1.81546 2.59694 + vertex 1.08242 1.8165 2.59713 + endloop + endfacet + facet normal 0.0805373 0.141177 0.986703 + outer loop + vertex 1.08658 1.81546 2.59694 + vertex 1.08687 1.81997 2.59628 + vertex 1.08242 1.8165 2.59713 + endloop + endfacet + facet normal 0.0806859 0.14099 0.986718 + outer loop + vertex 1.08242 1.8165 2.59713 + vertex 1.08687 1.81997 2.59628 + vertex 1.08102 1.8216 2.59652 + endloop + endfacet + facet normal 0.102914 0.137269 0.985173 + outer loop + vertex 1.07845 1.80738 2.5988 + vertex 1.07817 1.81205 2.59817 + vertex 1.07375 1.8078 2.59923 + endloop + endfacet + facet normal 0.108362 0.135583 0.984822 + outer loop + vertex 1.07454 1.80402 2.59966 + vertex 1.07375 1.8078 2.59923 + vertex 1.06938 1.80402 2.60023 + endloop + endfacet + facet normal 0.112673 0.133412 0.984635 + outer loop + vertex 1.06457 1.80409 2.60077 + vertex 1.06938 1.80402 2.60023 + vertex 1.06445 1.80882 2.60014 + endloop + endfacet + facet normal 0.109512 0.136825 0.984523 + outer loop + vertex 1.06971 1.80879 2.59953 + vertex 1.07344 1.81229 2.59863 + vertex 1.06879 1.8127 2.59909 + endloop + endfacet + facet normal 0.12289 0.132644 0.983516 + outer loop + vertex 1.05945 1.80904 2.60074 + vertex 1.06445 1.80882 2.60014 + vertex 1.05946 1.81387 2.60009 + endloop + endfacet + facet normal 0.116856 0.139069 0.983364 + outer loop + vertex 1.06879 1.8127 2.59909 + vertex 1.06839 1.81728 2.59849 + vertex 1.06476 1.81384 2.59941 + endloop + endfacet + facet normal 0.120209 0.139481 0.982901 + outer loop + vertex 1.06379 1.81781 2.59897 + vertex 1.06773 1.8219 2.59791 + vertex 1.06329 1.82225 2.5984 + endloop + endfacet + facet normal 0.127999 0.140212 0.981813 + outer loop + vertex 1.06379 1.81781 2.59897 + vertex 1.06329 1.82225 2.5984 + vertex 1.05984 1.81893 2.59933 + endloop + endfacet + facet normal 0.120387 0.142313 0.982473 + outer loop + vertex 1.06773 1.8219 2.59791 + vertex 1.06653 1.82582 2.59749 + vertex 1.06329 1.82225 2.5984 + endloop + endfacet + facet normal 0.123462 0.13953 0.982491 + outer loop + vertex 1.06329 1.82225 2.5984 + vertex 1.06653 1.82582 2.59749 + vertex 1.06273 1.82668 2.59784 + endloop + endfacet + facet normal 0.131849 0.140431 0.981272 + outer loop + vertex 1.06329 1.82225 2.5984 + vertex 1.06273 1.82668 2.59784 + vertex 1.05892 1.82284 2.59891 + endloop + endfacet + facet normal 0.136194 0.136121 0.981286 + outer loop + vertex 1.05892 1.82284 2.59891 + vertex 1.06273 1.82668 2.59784 + vertex 1.05838 1.82724 2.59837 + endloop + endfacet + facet normal 0.136641 0.140245 0.980643 + outer loop + vertex 1.06273 1.82668 2.59784 + vertex 1.06163 1.83062 2.59743 + vertex 1.05838 1.82724 2.59837 + endloop + endfacet + facet normal 0.127066 0.137733 0.982285 + outer loop + vertex 1.06273 1.82668 2.59784 + vertex 1.06662 1.83108 2.59672 + vertex 1.06163 1.83062 2.59743 + endloop + endfacet + facet normal 0.123711 0.140702 0.982292 + outer loop + vertex 1.06653 1.82582 2.59749 + vertex 1.06662 1.83108 2.59672 + vertex 1.06273 1.82668 2.59784 + endloop + endfacet + facet normal 0.111784 0.141914 0.983547 + outer loop + vertex 1.07293 1.81681 2.59805 + vertex 1.07242 1.82151 2.59743 + vertex 1.06839 1.81728 2.59849 + endloop + endfacet + facet normal 0.115716 0.140958 0.98323 + outer loop + vertex 1.06773 1.8219 2.59791 + vertex 1.07119 1.82683 2.5968 + vertex 1.06653 1.82582 2.59749 + endloop + endfacet + facet normal 0.107202 0.142527 0.983968 + outer loop + vertex 1.07637 1.82055 2.59713 + vertex 1.07677 1.82517 2.59642 + vertex 1.07242 1.82151 2.59743 + endloop + endfacet + facet normal 0.11571 0.140985 0.983227 + outer loop + vertex 1.06662 1.83108 2.59672 + vertex 1.06653 1.82582 2.59749 + vertex 1.07119 1.82683 2.5968 + endloop + endfacet + facet normal 0.133284 0.144776 0.980446 + outer loop + vertex 1.06649 1.83594 2.59603 + vertex 1.06159 1.83585 2.5967 + vertex 1.06662 1.83108 2.59672 + endloop + endfacet + facet normal 0.127018 0.138168 0.98223 + outer loop + vertex 1.06159 1.83585 2.5967 + vertex 1.06163 1.83062 2.59743 + vertex 1.06662 1.83108 2.59672 + endloop + endfacet + facet normal 0.144215 0.137981 0.979879 + outer loop + vertex 1.06163 1.83062 2.59743 + vertex 1.06159 1.83585 2.5967 + vertex 1.05772 1.83171 2.59786 + endloop + endfacet + facet normal 0.12288 0.144318 0.981872 + outer loop + vertex 1.06468 1.83908 2.59579 + vertex 1.06649 1.83594 2.59603 + vertex 1.06963 1.83905 2.59517 + endloop + endfacet + facet normal 0.11086 0.143337 0.983445 + outer loop + vertex 1.06967 1.83445 2.59586 + vertex 1.07146 1.83147 2.59609 + vertex 1.07407 1.83479 2.59531 + endloop + endfacet + facet normal 0.103862 0.153945 0.982606 + outer loop + vertex 1.0788 1.83781 2.59436 + vertex 1.07846 1.84229 2.59369 + vertex 1.07481 1.83906 2.59458 + endloop + endfacet + facet normal 0.109773 0.144189 0.983443 + outer loop + vertex 1.07537 1.82998 2.59587 + vertex 1.07407 1.83479 2.59531 + vertex 1.07146 1.83147 2.59609 + endloop + endfacet + facet normal 0.104086 0.142731 0.984273 + outer loop + vertex 1.07919 1.82866 2.59566 + vertex 1.07537 1.82998 2.59587 + vertex 1.07677 1.82517 2.59642 + endloop + endfacet + facet normal 0.0955543 0.141937 0.985253 + outer loop + vertex 1.07919 1.82866 2.59566 + vertex 1.08108 1.82598 2.59586 + vertex 1.08373 1.82935 2.59512 + endloop + endfacet + facet normal 0.099181 0.146195 0.984271 + outer loop + vertex 1.07968 1.83291 2.595 + vertex 1.08356 1.83741 2.59394 + vertex 1.0788 1.83781 2.59436 + endloop + endfacet + facet normal 0.0935844 0.149996 0.984247 + outer loop + vertex 1.08861 1.83272 2.59416 + vertex 1.08826 1.83731 2.59349 + vertex 1.08456 1.83374 2.59439 + endloop + endfacet + facet normal 0.0904831 0.149806 0.984566 + outer loop + vertex 1.08861 1.83272 2.59416 + vertex 1.09289 1.83687 2.59313 + vertex 1.08826 1.83731 2.59349 + endloop + endfacet + facet normal 0.0966606 0.151002 0.983796 + outer loop + vertex 1.08356 1.83741 2.59394 + vertex 1.08759 1.84183 2.59286 + vertex 1.08297 1.84186 2.59331 + endloop + endfacet + facet normal 0.0906892 0.152301 0.984165 + outer loop + vertex 1.09289 1.83687 2.59313 + vertex 1.09238 1.84156 2.59245 + vertex 1.08826 1.83731 2.59349 + endloop + endfacet + facet normal 0.0847366 0.151746 0.984781 + outer loop + vertex 1.09289 1.83687 2.59313 + vertex 1.09647 1.84042 2.59227 + vertex 1.09238 1.84156 2.59245 + endloop + endfacet + facet normal 0.0803895 0.156051 0.984472 + outer loop + vertex 1.09753 1.83653 2.59281 + vertex 1.09647 1.84042 2.59227 + vertex 1.09289 1.83687 2.59313 + endloop + endfacet + facet normal 0.0804132 0.156433 0.98441 + outer loop + vertex 1.09356 1.83231 2.5938 + vertex 1.09753 1.83653 2.59281 + vertex 1.09289 1.83687 2.59313 + endloop + endfacet + facet normal 0.0744889 0.161907 0.983991 + outer loop + vertex 1.09816 1.83208 2.59349 + vertex 1.09753 1.83653 2.59281 + vertex 1.09356 1.83231 2.5938 + endloop + endfacet + facet normal 0.0876966 0.157904 0.983553 + outer loop + vertex 1.09753 1.83653 2.59281 + vertex 1.1015 1.84091 2.59175 + vertex 1.09647 1.84042 2.59227 + endloop + endfacet + facet normal 0.0880786 0.15454 0.984053 + outer loop + vertex 1.09693 1.84504 2.59151 + vertex 1.09647 1.84042 2.59227 + vertex 1.1015 1.84091 2.59175 + endloop + endfacet + facet normal 0.0956995 0.155091 0.983254 + outer loop + vertex 1.08759 1.84183 2.59286 + vertex 1.09112 1.8467 2.59175 + vertex 1.08642 1.84559 2.59238 + endloop + endfacet + facet normal 0.0855652 0.154819 0.98423 + outer loop + vertex 1.09647 1.84042 2.59227 + vertex 1.09693 1.84504 2.59151 + vertex 1.09238 1.84156 2.59245 + endloop + endfacet + facet normal 0.0942423 0.160812 0.982475 + outer loop + vertex 1.08689 1.85026 2.59157 + vertex 1.08642 1.84559 2.59238 + vertex 1.09112 1.8467 2.59175 + endloop + endfacet + facet normal 0.0995364 0.16334 0.981536 + outer loop + vertex 1.08943 1.85382 2.59072 + vertex 1.08546 1.85503 2.59093 + vertex 1.08689 1.85026 2.59157 + endloop + endfacet + facet normal 0.0965898 0.162514 0.981967 + outer loop + vertex 1.08689 1.85026 2.59157 + vertex 1.08546 1.85503 2.59093 + vertex 1.08116 1.85176 2.59189 + endloop + endfacet + facet normal 0.100522 0.156172 0.982602 + outer loop + vertex 1.0764 1.85589 2.59172 + vertex 1.07642 1.85063 2.59255 + vertex 1.08116 1.85176 2.59189 + endloop + endfacet + facet normal 0.100047 0.160752 0.981911 + outer loop + vertex 1.07949 1.85931 2.59083 + vertex 1.08137 1.85639 2.59111 + vertex 1.08406 1.85976 2.59029 + endloop + endfacet + facet normal 0.123488 0.159866 0.979384 + outer loop + vertex 1.07622 1.86072 2.59095 + vertex 1.0713 1.86058 2.5916 + vertex 1.0764 1.85589 2.59172 + endloop + endfacet + facet normal 0.123326 0.163206 0.978854 + outer loop + vertex 1.07622 1.86072 2.59095 + vertex 1.07442 1.86383 2.59066 + vertex 1.0713 1.86058 2.5916 + endloop + endfacet + facet normal 0.104338 0.167979 0.980253 + outer loop + vertex 1.08378 1.86764 2.589 + vertex 1.08318 1.87195 2.58833 + vertex 1.07978 1.86874 2.58924 + endloop + endfacet + facet normal 0.107301 0.164894 0.980457 + outer loop + vertex 1.07978 1.86874 2.58924 + vertex 1.08318 1.87195 2.58833 + vertex 1.07867 1.87261 2.58871 + endloop + endfacet + facet normal 0.102834 0.167799 0.980443 + outer loop + vertex 1.08378 1.86764 2.589 + vertex 1.08756 1.8714 2.58796 + vertex 1.08318 1.87195 2.58833 + endloop + endfacet + facet normal 0.102941 0.168787 0.980262 + outer loop + vertex 1.08756 1.8714 2.58796 + vertex 1.0865 1.87523 2.58742 + vertex 1.08318 1.87195 2.58833 + endloop + endfacet + facet normal 0.104949 0.166794 0.98039 + outer loop + vertex 1.08318 1.87195 2.58833 + vertex 1.0865 1.87523 2.58742 + vertex 1.08248 1.87645 2.58764 + endloop + endfacet + facet normal 0.10739 0.169927 0.979588 + outer loop + vertex 1.08756 1.8714 2.58796 + vertex 1.0914 1.87581 2.58678 + vertex 1.0865 1.87523 2.58742 + endloop + endfacet + facet normal 0.107761 0.167246 0.980008 + outer loop + vertex 1.08697 1.87989 2.58657 + vertex 1.0865 1.87523 2.58742 + vertex 1.0914 1.87581 2.58678 + endloop + endfacet + facet normal 0.10292 0.167714 0.980449 + outer loop + vertex 1.08821 1.86705 2.58864 + vertex 1.08756 1.8714 2.58796 + vertex 1.08378 1.86764 2.589 + endloop + endfacet + facet normal 0.100237 0.159113 0.982159 + outer loop + vertex 1.07949 1.85931 2.59083 + vertex 1.08406 1.85976 2.59029 + vertex 1.07947 1.8639 2.59008 + endloop + endfacet + facet normal 0.103428 0.162465 0.981279 + outer loop + vertex 1.08987 1.85797 2.58997 + vertex 1.0888 1.86274 2.58929 + vertex 1.08406 1.85976 2.59029 + endloop + endfacet + facet normal 0.102743 0.166212 0.980723 + outer loop + vertex 1.08474 1.86396 2.58953 + vertex 1.08821 1.86705 2.58864 + vertex 1.08378 1.86764 2.589 + endloop + endfacet + facet normal 0.110685 0.163206 0.980364 + outer loop + vertex 1.09359 1.86223 2.58884 + vertex 1.09267 1.86678 2.58819 + vertex 1.0888 1.86274 2.58929 + endloop + endfacet + facet normal 0.106738 0.168206 0.979956 + outer loop + vertex 1.08821 1.86705 2.58864 + vertex 1.09135 1.87067 2.58768 + vertex 1.08756 1.8714 2.58796 + endloop + endfacet + facet normal 0.11126 0.168209 0.979452 + outer loop + vertex 1.09737 1.86643 2.58771 + vertex 1.09585 1.87209 2.58691 + vertex 1.09267 1.86678 2.58819 + endloop + endfacet + facet normal 0.107095 0.170182 0.979576 + outer loop + vertex 1.09135 1.87067 2.58768 + vertex 1.0914 1.87581 2.58678 + vertex 1.08756 1.8714 2.58796 + endloop + endfacet + facet normal 0.110129 0.169783 0.979309 + outer loop + vertex 1.09149 1.88052 2.58595 + vertex 1.08697 1.87989 2.58657 + vertex 1.0914 1.87581 2.58678 + endloop + endfacet + facet normal 0.116274 0.174181 0.977825 + outer loop + vertex 1.09459 1.87893 2.58586 + vertex 1.09963 1.87776 2.58547 + vertex 1.09475 1.8836 2.58501 + endloop + endfacet + facet normal 0.110421 0.167956 0.979591 + outer loop + vertex 1.09149 1.88052 2.58595 + vertex 1.08967 1.88345 2.58565 + vertex 1.08697 1.87989 2.58657 + endloop + endfacet + facet normal 0.125301 0.173285 0.976868 + outer loop + vertex 1.09997 1.88369 2.58433 + vertex 1.09872 1.88777 2.58376 + vertex 1.09475 1.8836 2.58501 + endloop + endfacet + facet normal 0.12783 0.169539 0.977198 + outer loop + vertex 1.0948 1.88867 2.58412 + vertex 1.09772 1.89213 2.58314 + vertex 1.09329 1.89222 2.5837 + endloop + endfacet + facet normal 0.121861 0.172456 0.97745 + outer loop + vertex 1.10314 1.88705 2.58334 + vertex 1.10229 1.89154 2.58265 + vertex 1.09872 1.88777 2.58376 + endloop + endfacet + facet normal 0.130656 0.171174 0.976539 + outer loop + vertex 1.09772 1.89213 2.58314 + vertex 1.10085 1.89667 2.58193 + vertex 1.0962 1.89569 2.58272 + endloop + endfacet + facet normal 0.111198 0.173647 0.97851 + outer loop + vertex 1.10628 1.89024 2.58243 + vertex 1.10671 1.89479 2.58157 + vertex 1.10229 1.89154 2.58265 + endloop + endfacet + facet normal 0.129329 0.176818 0.97571 + outer loop + vertex 1.09626 1.90067 2.58181 + vertex 1.0962 1.89569 2.58272 + vertex 1.10085 1.89667 2.58193 + endloop + endfacet + facet normal 0.133971 0.18094 0.974327 + outer loop + vertex 1.09935 1.9042 2.58073 + vertex 1.1011 1.90127 2.58104 + vertex 1.10388 1.90471 2.58002 + endloop + endfacet + facet normal 0.127252 0.176078 0.976116 + outer loop + vertex 1.09187 1.90472 2.58165 + vertex 1.09135 1.9001 2.58255 + vertex 1.09626 1.90067 2.58181 + endloop + endfacet + facet normal 0.122961 0.175093 0.976843 + outer loop + vertex 1.09187 1.90472 2.58165 + vertex 1.09052 1.9098 2.58091 + vertex 1.0861 1.90659 2.58204 + endloop + endfacet + facet normal 0.125815 0.171268 0.977158 + outer loop + vertex 1.0864 1.9113 2.58118 + vertex 1.0861 1.90659 2.58204 + vertex 1.09052 1.9098 2.58091 + endloop + endfacet + facet normal 0.132718 0.170677 0.976348 + outer loop + vertex 1.0864 1.9113 2.58118 + vertex 1.08142 1.91088 2.58193 + vertex 1.0861 1.90659 2.58204 + endloop + endfacet + facet normal 0.13758 0.181143 0.973786 + outer loop + vertex 1.09458 1.90833 2.58064 + vertex 1.0963 1.90541 2.58094 + vertex 1.09949 1.90875 2.57986 + endloop + endfacet + facet normal 0.141179 0.176351 0.97415 + outer loop + vertex 1.10335 1.91253 2.57861 + vertex 1.10259 1.91659 2.57799 + vertex 1.09972 1.91347 2.57897 + endloop + endfacet + facet normal 0.133857 0.181757 0.97419 + outer loop + vertex 1.09935 1.9042 2.58073 + vertex 1.10388 1.90471 2.58002 + vertex 1.09949 1.90875 2.57986 + endloop + endfacet + facet normal 0.117629 0.198621 0.972992 + outer loop + vertex 1.10983 1.9027 2.5797 + vertex 1.1085 1.90769 2.57885 + vertex 1.10388 1.90471 2.58002 + endloop + endfacet + facet normal 0.13167 0.177978 0.975186 + outer loop + vertex 1.10449 1.90903 2.57909 + vertex 1.10764 1.91208 2.57811 + vertex 1.10335 1.91253 2.57861 + endloop + endfacet + facet normal 0.101484 0.193306 0.975876 + outer loop + vertex 1.11323 1.90694 2.57851 + vertex 1.1123 1.91133 2.57773 + vertex 1.1085 1.90769 2.57885 + endloop + endfacet + facet normal 0.119946 0.175536 0.977139 + outer loop + vertex 1.10764 1.91208 2.57811 + vertex 1.11086 1.91651 2.57692 + vertex 1.10621 1.91569 2.57764 + endloop + endfacet + facet normal 0.119541 0.177546 0.976825 + outer loop + vertex 1.10622 1.92061 2.57675 + vertex 1.10621 1.91569 2.57764 + vertex 1.11086 1.91651 2.57692 + endloop + endfacet + facet normal 0.119021 0.185218 0.975463 + outer loop + vertex 1.10929 1.92411 2.57567 + vertex 1.11109 1.92115 2.57601 + vertex 1.11389 1.9246 2.57502 + endloop + endfacet + facet normal 0.137588 0.18363 0.973319 + outer loop + vertex 1.10619 1.92532 2.57586 + vertex 1.10176 1.92463 2.57662 + vertex 1.10622 1.92061 2.57675 + endloop + endfacet + facet normal 0.118465 0.189419 0.974724 + outer loop + vertex 1.10929 1.92411 2.57567 + vertex 1.11389 1.9246 2.57502 + vertex 1.10941 1.92865 2.57477 + endloop + endfacet + facet normal 0.137136 0.186092 0.972915 + outer loop + vertex 1.10619 1.92532 2.57586 + vertex 1.10446 1.92821 2.57555 + vertex 1.10176 1.92463 2.57662 + endloop + endfacet + facet normal 0.136499 0.186572 0.972913 + outer loop + vertex 1.10446 1.92821 2.57555 + vertex 1.10038 1.92964 2.57585 + vertex 1.10176 1.92463 2.57662 + endloop + endfacet + facet normal 0.13654 0.188884 0.972461 + outer loop + vertex 1.10038 1.92964 2.57585 + vertex 1.09903 1.93462 2.57507 + vertex 1.09626 1.93112 2.57614 + endloop + endfacet + facet normal 0.140204 0.190551 0.971614 + outer loop + vertex 1.10484 1.93267 2.57463 + vertex 1.10796 1.93701 2.57332 + vertex 1.10341 1.93749 2.57388 + endloop + endfacet + facet normal 0.138654 0.182698 0.973343 + outer loop + vertex 1.09445 1.93416 2.57581 + vertex 1.09903 1.93462 2.57507 + vertex 1.09451 1.93891 2.57491 + endloop + endfacet + facet normal 0.140347 0.18985 0.97173 + outer loop + vertex 1.10341 1.93749 2.57388 + vertex 1.1026 1.94167 2.57319 + vertex 1.0996 1.9389 2.57416 + endloop + endfacet + facet normal 0.142249 0.189544 0.971513 + outer loop + vertex 1.1026 1.94167 2.57319 + vertex 1.10617 1.94567 2.57188 + vertex 1.10126 1.9453 2.57267 + endloop + endfacet + facet normal 0.142362 0.188461 0.971707 + outer loop + vertex 1.10118 1.95025 2.57173 + vertex 1.10126 1.9453 2.57267 + vertex 1.10617 1.94567 2.57188 + endloop + endfacet + facet normal 0.151048 0.183647 0.971318 + outer loop + vertex 1.09666 1.95458 2.57161 + vertex 1.09623 1.95012 2.57252 + vertex 1.10118 1.95025 2.57173 + endloop + endfacet + facet normal 0.172436 0.159627 0.972001 + outer loop + vertex 1.0848 1.94371 2.57567 + vertex 1.08965 1.94368 2.57482 + vertex 1.08521 1.94815 2.57487 + endloop + endfacet + facet normal 0.172379 0.162058 0.971608 + outer loop + vertex 1.0848 1.94371 2.57567 + vertex 1.08629 1.9405 2.57595 + vertex 1.08965 1.94368 2.57482 + endloop + endfacet + facet normal 0.182418 0.166492 0.969022 + outer loop + vertex 1.08629 1.9405 2.57595 + vertex 1.0848 1.94371 2.57567 + vertex 1.08153 1.94057 2.57683 + endloop + endfacet + facet normal 0.171747 0.177179 0.969077 + outer loop + vertex 1.09333 1.94736 2.57352 + vertex 1.09246 1.95165 2.57288 + vertex 1.08965 1.94862 2.57394 + endloop + endfacet + facet normal 0.155506 0.18075 0.971158 + outer loop + vertex 1.09465 1.9437 2.57398 + vertex 1.09754 1.94652 2.573 + vertex 1.09333 1.94736 2.57352 + endloop + endfacet + facet normal 0.14815 0.183467 0.971798 + outer loop + vertex 1.09451 1.93891 2.57491 + vertex 1.09839 1.94241 2.57366 + vertex 1.09465 1.9437 2.57398 + endloop + endfacet + facet normal 0.149473 0.176511 0.972883 + outer loop + vertex 1.08952 1.93884 2.57569 + vertex 1.0912 1.93562 2.57602 + vertex 1.09451 1.93891 2.57491 + endloop + endfacet + facet normal 0.156318 0.179904 0.971184 + outer loop + vertex 1.0912 1.93562 2.57602 + vertex 1.08952 1.93884 2.57569 + vertex 1.08628 1.93551 2.57683 + endloop + endfacet + facet normal 0.189477 0.156133 0.969392 + outer loop + vertex 1.0813 1.93553 2.57769 + vertex 1.08153 1.94057 2.57683 + vertex 1.07764 1.93708 2.57815 + endloop + endfacet + facet normal 0.156899 0.1716 0.972592 + outer loop + vertex 1.08635 1.93036 2.57772 + vertex 1.08628 1.93551 2.57683 + vertex 1.08263 1.93167 2.57809 + endloop + endfacet + facet normal 0.156768 0.171202 0.972684 + outer loop + vertex 1.08352 1.92739 2.5787 + vertex 1.08635 1.93036 2.57772 + vertex 1.08263 1.93167 2.57809 + endloop + endfacet + facet normal 0.14687 0.177818 0.973042 + outer loop + vertex 1.08481 1.92373 2.57918 + vertex 1.0877 1.92663 2.57821 + vertex 1.08352 1.92739 2.5787 + endloop + endfacet + facet normal 0.139332 0.177477 0.974212 + outer loop + vertex 1.08465 1.91901 2.58006 + vertex 1.08853 1.92255 2.57886 + vertex 1.08481 1.92373 2.57918 + endloop + endfacet + facet normal 0.130607 0.17058 0.97665 + outer loop + vertex 1.0846 1.91433 2.58089 + vertex 1.08918 1.9148 2.58019 + vertex 1.08465 1.91901 2.58006 + endloop + endfacet + facet normal 0.132468 0.172956 0.975981 + outer loop + vertex 1.0864 1.9113 2.58118 + vertex 1.0846 1.91433 2.58089 + vertex 1.08142 1.91088 2.58193 + endloop + endfacet + facet normal 0.159504 0.171798 0.972134 + outer loop + vertex 1.08137 1.91577 2.5811 + vertex 1.07968 1.91895 2.58081 + vertex 1.07648 1.91574 2.5819 + endloop + endfacet + facet normal 0.125872 0.163272 0.978518 + outer loop + vertex 1.08142 1.91088 2.58193 + vertex 1.08145 1.90573 2.58278 + vertex 1.0861 1.90659 2.58204 + endloop + endfacet + facet normal 0.124697 0.168935 0.977707 + outer loop + vertex 1.08289 1.90205 2.58324 + vertex 1.0861 1.90659 2.58204 + vertex 1.08145 1.90573 2.58278 + endloop + endfacet + facet normal 0.119281 0.172171 0.977818 + outer loop + vertex 1.08373 1.89774 2.58389 + vertex 1.08744 1.90137 2.5828 + vertex 1.08289 1.90205 2.58324 + endloop + endfacet + facet normal 0.116645 0.171013 0.97834 + outer loop + vertex 1.08475 1.89409 2.58441 + vertex 1.08811 1.897 2.5835 + vertex 1.08373 1.89774 2.58389 + endloop + endfacet + facet normal 0.115253 0.166787 0.979234 + outer loop + vertex 1.08408 1.88979 2.58522 + vertex 1.08871 1.89278 2.58417 + vertex 1.08475 1.89409 2.58441 + endloop + endfacet + facet normal 0.127701 0.167248 0.97761 + outer loop + vertex 1.08131 1.88632 2.58612 + vertex 1.07949 1.88931 2.58585 + vertex 1.07636 1.88587 2.58685 + endloop + endfacet + facet normal 0.11414 0.165355 0.979607 + outer loop + vertex 1.08408 1.88979 2.58522 + vertex 1.08548 1.88489 2.58588 + vertex 1.08999 1.88786 2.58486 + endloop + endfacet + facet normal 0.128246 0.162482 0.978342 + outer loop + vertex 1.08131 1.88632 2.58612 + vertex 1.07636 1.88587 2.58685 + vertex 1.08108 1.88167 2.58693 + endloop + endfacet + facet normal 0.111305 0.167289 0.979605 + outer loop + vertex 1.08967 1.88345 2.58565 + vertex 1.08548 1.88489 2.58588 + vertex 1.08697 1.87989 2.58657 + endloop + endfacet + facet normal 0.105169 0.167551 0.980238 + outer loop + vertex 1.0865 1.87523 2.58742 + vertex 1.08697 1.87989 2.58657 + vertex 1.08248 1.87645 2.58764 + endloop + endfacet + facet normal 0.107601 0.167153 0.980042 + outer loop + vertex 1.08318 1.87195 2.58833 + vertex 1.08248 1.87645 2.58764 + vertex 1.07867 1.87261 2.58871 + endloop + endfacet + facet normal 0.116443 0.167312 0.979004 + outer loop + vertex 1.07978 1.86874 2.58924 + vertex 1.07867 1.87261 2.58871 + vertex 1.07444 1.86868 2.58989 + endloop + endfacet + facet normal 0.132722 0.150558 0.979652 + outer loop + vertex 1.06932 1.86875 2.59057 + vertex 1.07109 1.86549 2.59083 + vertex 1.07444 1.86868 2.58989 + endloop + endfacet + facet normal 0.127266 0.156242 0.979485 + outer loop + vertex 1.07442 1.86383 2.59066 + vertex 1.07444 1.86868 2.58989 + vertex 1.07109 1.86549 2.59083 + endloop + endfacet + facet normal 0.128335 0.158438 0.978993 + outer loop + vertex 1.07109 1.86549 2.59083 + vertex 1.0713 1.86058 2.5916 + vertex 1.07442 1.86383 2.59066 + endloop + endfacet + facet normal 0.149032 0.158868 0.975987 + outer loop + vertex 1.07109 1.86549 2.59083 + vertex 1.0662 1.86554 2.59157 + vertex 1.0713 1.86058 2.5916 + endloop + endfacet + facet normal 0.13979 0.149388 0.978847 + outer loop + vertex 1.0662 1.86554 2.59157 + vertex 1.06628 1.86038 2.59234 + vertex 1.0713 1.86058 2.5916 + endloop + endfacet + facet normal 0.149029 0.159075 0.975954 + outer loop + vertex 1.07109 1.86549 2.59083 + vertex 1.06932 1.86875 2.59057 + vertex 1.0662 1.86554 2.59157 + endloop + endfacet + facet normal 0.176648 0.153004 0.972309 + outer loop + vertex 1.06605 1.87053 2.59081 + vertex 1.06441 1.87386 2.59058 + vertex 1.06131 1.87071 2.59164 + endloop + endfacet + facet normal 0.188272 0.141265 0.971904 + outer loop + vertex 1.06127 1.86553 2.5924 + vertex 1.06131 1.87071 2.59164 + vertex 1.05764 1.86702 2.59289 + endloop + endfacet + facet normal 0.157445 0.149271 0.976181 + outer loop + vertex 1.06628 1.86038 2.59234 + vertex 1.0662 1.86554 2.59157 + vertex 1.06245 1.86154 2.59279 + endloop + endfacet + facet normal 0.13991 0.147391 0.979133 + outer loop + vertex 1.06748 1.85647 2.59276 + vertex 1.0713 1.86058 2.5916 + vertex 1.06628 1.86038 2.59234 + endloop + endfacet + facet normal 0.133128 0.148604 0.979895 + outer loop + vertex 1.06818 1.85209 2.59333 + vertex 1.07136 1.85539 2.5924 + vertex 1.06748 1.85647 2.59276 + endloop + endfacet + facet normal 0.135028 0.151773 0.979149 + outer loop + vertex 1.06882 1.84772 2.59392 + vertex 1.06818 1.85209 2.59333 + vertex 1.06487 1.84893 2.59428 + endloop + endfacet + facet normal 0.122861 0.14595 0.981633 + outer loop + vertex 1.06468 1.83908 2.59579 + vertex 1.06963 1.83905 2.59517 + vertex 1.06462 1.84391 2.59508 + endloop + endfacet + facet normal 0.133084 0.150033 0.979683 + outer loop + vertex 1.06649 1.83594 2.59603 + vertex 1.06468 1.83908 2.59579 + vertex 1.06159 1.83585 2.5967 + endloop + endfacet + facet normal 0.161407 0.150559 0.975336 + outer loop + vertex 1.06132 1.84079 2.59601 + vertex 1.05953 1.84407 2.5958 + vertex 1.05647 1.8409 2.59679 + endloop + endfacet + facet normal 0.150042 0.132504 0.97976 + outer loop + vertex 1.05772 1.83171 2.59786 + vertex 1.06159 1.83585 2.5967 + vertex 1.05657 1.83572 2.59749 + endloop + endfacet + facet normal 0.143171 0.133951 0.980591 + outer loop + vertex 1.05838 1.82724 2.59837 + vertex 1.06163 1.83062 2.59743 + vertex 1.05772 1.83171 2.59786 + endloop + endfacet + facet normal 0.148947 0.137433 0.979248 + outer loop + vertex 1.05892 1.82284 2.59891 + vertex 1.05838 1.82724 2.59837 + vertex 1.05495 1.82376 2.59938 + endloop + endfacet + facet normal 0.131412 0.13668 0.98186 + outer loop + vertex 1.05984 1.81893 2.59933 + vertex 1.06329 1.82225 2.5984 + vertex 1.05892 1.82284 2.59891 + endloop + endfacet + facet normal 0.1273 0.137603 0.982273 + outer loop + vertex 1.05946 1.81387 2.60009 + vertex 1.06379 1.81781 2.59897 + vertex 1.05984 1.81893 2.59933 + endloop + endfacet + facet normal 0.138291 0.130175 0.981799 + outer loop + vertex 1.05446 1.81405 2.60077 + vertex 1.05616 1.81082 2.60095 + vertex 1.05946 1.81387 2.60009 + endloop + endfacet + facet normal 0.136251 0.132383 0.981789 + outer loop + vertex 1.05945 1.80904 2.60074 + vertex 1.05946 1.81387 2.60009 + vertex 1.05616 1.81082 2.60095 + endloop + endfacet + facet normal 0.137204 0.134184 0.981412 + outer loop + vertex 1.05616 1.81082 2.60095 + vertex 1.05645 1.80585 2.60159 + vertex 1.05945 1.80904 2.60074 + endloop + endfacet + facet normal 0.154567 0.13487 0.978733 + outer loop + vertex 1.05616 1.81082 2.60095 + vertex 1.05143 1.81091 2.60169 + vertex 1.05645 1.80585 2.60159 + endloop + endfacet + facet normal 0.154558 0.138555 0.97822 + outer loop + vertex 1.05616 1.81082 2.60095 + vertex 1.05446 1.81405 2.60077 + vertex 1.05143 1.81091 2.60169 + endloop + endfacet + facet normal 0.188929 0.135627 0.97258 + outer loop + vertex 1.05147 1.8157 2.60103 + vertex 1.0505 1.81832 2.60085 + vertex 1.04708 1.81617 2.60181 + endloop + endfacet + facet normal 0.207549 0.115525 0.971379 + outer loop + vertex 1.04655 1.81093 2.60255 + vertex 1.04708 1.81617 2.60181 + vertex 1.04288 1.81233 2.60317 + endloop + endfacet + facet normal 0.146537 0.126868 0.981036 + outer loop + vertex 1.05143 1.81091 2.60169 + vertex 1.05146 1.80572 2.60236 + vertex 1.05645 1.80585 2.60159 + endloop + endfacet + facet normal 0.146645 0.124347 0.981342 + outer loop + vertex 1.05265 1.80171 2.60269 + vertex 1.05645 1.80585 2.60159 + vertex 1.05146 1.80572 2.60236 + endloop + endfacet + facet normal 0.149096 0.125241 0.980859 + outer loop + vertex 1.05332 1.79724 2.60315 + vertex 1.05265 1.80171 2.60269 + vertex 1.04879 1.79791 2.60376 + endloop + endfacet + facet normal 0.148082 0.117322 0.981992 + outer loop + vertex 1.0498 1.79396 2.60408 + vertex 1.05332 1.79724 2.60315 + vertex 1.04879 1.79791 2.60376 + endloop + endfacet + facet normal 0.140033 0.120366 0.982803 + outer loop + vertex 1.04867 1.78921 2.60482 + vertex 1.05358 1.79274 2.60369 + vertex 1.0498 1.79396 2.60408 + endloop + endfacet + facet normal 0.137715 0.12357 0.982733 + outer loop + vertex 1.05387 1.78795 2.60425 + vertex 1.05358 1.79274 2.60369 + vertex 1.04867 1.78921 2.60482 + endloop + endfacet + facet normal 0.123635 0.122096 0.984788 + outer loop + vertex 1.05497 1.78392 2.60461 + vertex 1.05853 1.7874 2.60373 + vertex 1.05387 1.78795 2.60425 + endloop + endfacet + facet normal 0.118407 0.127426 0.984755 + outer loop + vertex 1.05884 1.78286 2.60428 + vertex 1.05853 1.7874 2.60373 + vertex 1.05497 1.78392 2.60461 + endloop + endfacet + facet normal 0.111327 0.130671 0.985156 + outer loop + vertex 1.06346 1.78242 2.60382 + vertex 1.06305 1.78697 2.60326 + vertex 1.05884 1.78286 2.60428 + endloop + endfacet + facet normal 0.109105 0.131603 0.98528 + outer loop + vertex 1.06823 1.78213 2.60333 + vertex 1.06773 1.78694 2.60274 + vertex 1.06346 1.78242 2.60382 + endloop + endfacet + facet normal 0.109251 0.131616 0.985262 + outer loop + vertex 1.06823 1.78213 2.60333 + vertex 1.0726 1.78666 2.60224 + vertex 1.06773 1.78694 2.60274 + endloop + endfacet + facet normal 0.109279 0.13159 0.985263 + outer loop + vertex 1.07302 1.78185 2.60284 + vertex 1.0726 1.78666 2.60224 + vertex 1.06823 1.78213 2.60333 + endloop + endfacet + facet normal 0.104464 0.126523 0.986448 + outer loop + vertex 1.07326 1.77707 2.60342 + vertex 1.07766 1.78166 2.60237 + vertex 1.07302 1.78185 2.60284 + endloop + endfacet + facet normal 0.112552 0.11859 0.986544 + outer loop + vertex 1.07344 1.77227 2.60398 + vertex 1.07326 1.77707 2.60342 + vertex 1.06872 1.77275 2.60446 + endloop + endfacet + facet normal 0.111061 0.10956 0.987756 + outer loop + vertex 1.06958 1.76873 2.60481 + vertex 1.06872 1.77275 2.60446 + vertex 1.06441 1.76894 2.60537 + endloop + endfacet + facet normal 0.108798 0.123833 0.986321 + outer loop + vertex 1.06464 1.77388 2.60478 + vertex 1.06848 1.77738 2.60392 + vertex 1.06375 1.77785 2.60438 + endloop + endfacet + facet normal 0.108146 0.113161 0.987673 + outer loop + vertex 1.05961 1.76937 2.60584 + vertex 1.06441 1.76894 2.60537 + vertex 1.05944 1.77403 2.60533 + endloop + endfacet + facet normal 0.103869 0.100851 0.989465 + outer loop + vertex 1.06147 1.76615 2.60598 + vertex 1.05961 1.76937 2.60584 + vertex 1.05675 1.76622 2.60647 + endloop + endfacet + facet normal 0.116203 0.116536 0.986365 + outer loop + vertex 1.05639 1.77116 2.60599 + vertex 1.05458 1.77436 2.60583 + vertex 1.05162 1.77116 2.60655 + endloop + endfacet + facet normal 0.138825 0.106417 0.984583 + outer loop + vertex 1.05169 1.76585 2.60712 + vertex 1.05162 1.77116 2.60655 + vertex 1.04769 1.76689 2.60757 + endloop + endfacet + facet normal 0.107346 0.0883313 0.99029 + outer loop + vertex 1.05675 1.76622 2.60647 + vertex 1.05686 1.7609 2.60693 + vertex 1.06183 1.76125 2.60636 + endloop + endfacet + facet normal 0.108379 0.0752993 0.991254 + outer loop + vertex 1.05796 1.75684 2.60712 + vertex 1.06183 1.76125 2.60636 + vertex 1.05686 1.7609 2.60693 + endloop + endfacet + facet normal 0.109481 0.0743233 0.991206 + outer loop + vertex 1.06194 1.75602 2.60674 + vertex 1.06183 1.76125 2.60636 + vertex 1.05796 1.75684 2.60712 + endloop + endfacet + facet normal 0.108286 0.0682316 0.991775 + outer loop + vertex 1.05832 1.75209 2.6074 + vertex 1.06194 1.75602 2.60674 + vertex 1.05796 1.75684 2.60712 + endloop + endfacet + facet normal 0.107021 0.0653754 0.992105 + outer loop + vertex 1.05845 1.7472 2.60771 + vertex 1.06295 1.75198 2.60691 + vertex 1.05832 1.75209 2.6074 + endloop + endfacet + facet normal 0.105172 0.0671285 0.992186 + outer loop + vertex 1.06329 1.74722 2.6072 + vertex 1.06295 1.75198 2.60691 + vertex 1.05845 1.7472 2.60771 + endloop + endfacet + facet normal 0.105588 0.067155 0.99214 + outer loop + vertex 1.06329 1.74722 2.6072 + vertex 1.06666 1.75123 2.60657 + vertex 1.06295 1.75198 2.60691 + endloop + endfacet + facet normal 0.106281 0.0665671 0.992105 + outer loop + vertex 1.06785 1.7471 2.60672 + vertex 1.06666 1.75123 2.60657 + vertex 1.06329 1.74722 2.6072 + endloop + endfacet + facet normal 0.106342 0.0698243 0.991875 + outer loop + vertex 1.06342 1.74227 2.60753 + vertex 1.06785 1.7471 2.60672 + vertex 1.06329 1.74722 2.6072 + endloop + endfacet + facet normal 0.102996 0.0697591 0.992233 + outer loop + vertex 1.06342 1.74227 2.60753 + vertex 1.06329 1.74722 2.6072 + vertex 1.05836 1.74214 2.60807 + endloop + endfacet + facet normal 0.105209 0.0708708 0.991922 + outer loop + vertex 1.06821 1.74207 2.60704 + vertex 1.06785 1.7471 2.60672 + vertex 1.06342 1.74227 2.60753 + endloop + endfacet + facet normal 0.105374 0.0759069 0.991531 + outer loop + vertex 1.06332 1.73716 2.60793 + vertex 1.06821 1.74207 2.60704 + vertex 1.06342 1.74227 2.60753 + endloop + endfacet + facet normal 0.101003 0.0760242 0.991977 + outer loop + vertex 1.06332 1.73716 2.60793 + vertex 1.06342 1.74227 2.60753 + vertex 1.05821 1.73708 2.60846 + endloop + endfacet + facet normal 0.104161 0.0771203 0.991566 + outer loop + vertex 1.06821 1.73713 2.60742 + vertex 1.06821 1.74207 2.60704 + vertex 1.06332 1.73716 2.60793 + endloop + endfacet + facet normal 0.104144 0.0833089 0.991067 + outer loop + vertex 1.06322 1.73212 2.60837 + vertex 1.06821 1.73713 2.60742 + vertex 1.06332 1.73716 2.60793 + endloop + endfacet + facet normal 0.105855 0.077106 0.991388 + outer loop + vertex 1.06821 1.73713 2.60742 + vertex 1.07208 1.74105 2.6067 + vertex 1.06821 1.74207 2.60704 + endloop + endfacet + facet normal 0.105042 0.0739205 0.991717 + outer loop + vertex 1.07208 1.74105 2.6067 + vertex 1.07276 1.74595 2.60627 + vertex 1.06821 1.74207 2.60704 + endloop + endfacet + facet normal 0.0913805 0.0759171 0.992918 + outer loop + vertex 1.07276 1.74595 2.60627 + vertex 1.07208 1.74105 2.6067 + vertex 1.07697 1.74126 2.60624 + endloop + endfacet + facet normal 0.0913018 0.0775163 0.992802 + outer loop + vertex 1.07286 1.73695 2.60695 + vertex 1.07697 1.74126 2.60624 + vertex 1.07208 1.74105 2.6067 + endloop + endfacet + facet normal 0.0891273 0.0795951 0.992835 + outer loop + vertex 1.07681 1.73605 2.60667 + vertex 1.07697 1.74126 2.60624 + vertex 1.07286 1.73695 2.60695 + endloop + endfacet + facet normal 0.0899875 0.0835186 0.992435 + outer loop + vertex 1.07314 1.73209 2.60734 + vertex 1.07681 1.73605 2.60667 + vertex 1.07286 1.73695 2.60695 + endloop + endfacet + facet normal 0.103247 0.079696 0.991458 + outer loop + vertex 1.07286 1.73695 2.60695 + vertex 1.07208 1.74105 2.6067 + vertex 1.06821 1.73713 2.60742 + endloop + endfacet + facet normal 0.10336 0.0833058 0.991149 + outer loop + vertex 1.06827 1.73217 2.60783 + vertex 1.07286 1.73695 2.60695 + vertex 1.06821 1.73713 2.60742 + endloop + endfacet + facet normal 0.107505 0.0710204 0.991665 + outer loop + vertex 1.06821 1.74207 2.60704 + vertex 1.07276 1.74595 2.60627 + vertex 1.06785 1.7471 2.60672 + endloop + endfacet + facet normal 0.107226 0.0697904 0.991782 + outer loop + vertex 1.07276 1.74595 2.60627 + vertex 1.07071 1.7518 2.60608 + vertex 1.06785 1.7471 2.60672 + endloop + endfacet + facet normal 0.104508 0.0688499 0.992138 + outer loop + vertex 1.07071 1.7518 2.60608 + vertex 1.07276 1.74595 2.60627 + vertex 1.0753 1.75009 2.60571 + endloop + endfacet + facet normal 0.0978987 0.0729553 0.992519 + outer loop + vertex 1.0753 1.75009 2.60571 + vertex 1.07276 1.74595 2.60627 + vertex 1.07694 1.74609 2.60585 + endloop + endfacet + facet normal 0.110505 0.0677661 0.991563 + outer loop + vertex 1.06785 1.7471 2.60672 + vertex 1.07071 1.7518 2.60608 + vertex 1.06666 1.75123 2.60657 + endloop + endfacet + facet normal 0.105166 0.0676415 0.992152 + outer loop + vertex 1.05836 1.74214 2.60807 + vertex 1.06329 1.74722 2.6072 + vertex 1.05845 1.7472 2.60771 + endloop + endfacet + facet normal 0.102852 0.0741572 0.991928 + outer loop + vertex 1.05821 1.73708 2.60846 + vertex 1.06342 1.74227 2.60753 + vertex 1.05836 1.74214 2.60807 + endloop + endfacet + facet normal 0.100854 0.082546 0.991471 + outer loop + vertex 1.05821 1.73221 2.60887 + vertex 1.06332 1.73716 2.60793 + vertex 1.05821 1.73708 2.60846 + endloop + endfacet + facet normal 0.100003 0.0834286 0.991483 + outer loop + vertex 1.06322 1.73212 2.60837 + vertex 1.06332 1.73716 2.60793 + vertex 1.05821 1.73221 2.60887 + endloop + endfacet + facet normal 0.104144 0.0833084 0.991067 + outer loop + vertex 1.06827 1.73217 2.60783 + vertex 1.06821 1.73713 2.60742 + vertex 1.06322 1.73212 2.60837 + endloop + endfacet + facet normal 0.102477 0.0841564 0.991169 + outer loop + vertex 1.07314 1.73209 2.60734 + vertex 1.07286 1.73695 2.60695 + vertex 1.06827 1.73217 2.60783 + endloop + endfacet + facet normal 0.0850823 0.0880608 0.992475 + outer loop + vertex 1.07784 1.73192 2.60695 + vertex 1.07681 1.73605 2.60667 + vertex 1.07314 1.73209 2.60734 + endloop + endfacet + facet normal 0.0631461 0.0827565 0.994567 + outer loop + vertex 1.07784 1.73192 2.60695 + vertex 1.08178 1.73647 2.60632 + vertex 1.07681 1.73605 2.60667 + endloop + endfacet + facet normal 0.061793 0.0839286 0.994554 + outer loop + vertex 1.0818 1.73124 2.60676 + vertex 1.08178 1.73647 2.60632 + vertex 1.07784 1.73192 2.60695 + endloop + endfacet + facet normal 0.0615295 0.0839292 0.99457 + outer loop + vertex 1.08178 1.73647 2.60632 + vertex 1.0818 1.73124 2.60676 + vertex 1.08636 1.73234 2.60639 + endloop + endfacet + facet normal 0.0639577 0.0866161 0.994187 + outer loop + vertex 1.08654 1.7367 2.60599 + vertex 1.08178 1.73647 2.60632 + vertex 1.08636 1.73234 2.60639 + endloop + endfacet + facet normal 0.196056 0.0553126 0.979031 + outer loop + vertex 1.09176 1.72662 2.60594 + vertex 1.09102 1.73106 2.60583 + vertex 1.08766 1.72721 2.60672 + endloop + endfacet + facet normal 0.137233 0.0829596 0.987059 + outer loop + vertex 1.08654 1.7367 2.60599 + vertex 1.08636 1.73234 2.60639 + vertex 1.09027 1.73528 2.60559 + endloop + endfacet + facet normal 0.140893 0.0929696 0.98565 + outer loop + vertex 1.09027 1.73528 2.60559 + vertex 1.08894 1.73988 2.60535 + vertex 1.08654 1.7367 2.60599 + endloop + endfacet + facet normal 0.114602 0.113162 0.986945 + outer loop + vertex 1.08464 1.73956 2.60589 + vertex 1.08654 1.7367 2.60599 + vertex 1.08894 1.73988 2.60535 + endloop + endfacet + facet normal 0.0643208 0.0800168 0.994716 + outer loop + vertex 1.08654 1.7367 2.60599 + vertex 1.08464 1.73956 2.60589 + vertex 1.08178 1.73647 2.60632 + endloop + endfacet + facet normal 0.0633445 0.0805288 0.994737 + outer loop + vertex 1.07697 1.74126 2.60624 + vertex 1.07681 1.73605 2.60667 + vertex 1.08178 1.73647 2.60632 + endloop + endfacet + facet normal 0.0975495 0.0814574 0.991892 + outer loop + vertex 1.07694 1.74609 2.60585 + vertex 1.07276 1.74595 2.60627 + vertex 1.07697 1.74126 2.60624 + endloop + endfacet + facet normal 0.0719856 0.0624569 0.995448 + outer loop + vertex 1.07694 1.74609 2.60585 + vertex 1.08015 1.74834 2.60547 + vertex 1.0753 1.75009 2.60571 + endloop + endfacet + facet normal 0.0601143 0.0832777 0.994712 + outer loop + vertex 1.07986 1.74416 2.60579 + vertex 1.08151 1.74112 2.60594 + vertex 1.08454 1.74398 2.60552 + endloop + endfacet + facet normal 0.106745 0.0589739 0.992536 + outer loop + vertex 1.08952 1.74407 2.60498 + vertex 1.08861 1.74776 2.60486 + vertex 1.08454 1.74398 2.60552 + endloop + endfacet + facet normal 0.0807401 0.0847609 0.993125 + outer loop + vertex 1.08471 1.74866 2.60518 + vertex 1.08825 1.75224 2.60459 + vertex 1.08349 1.75264 2.60494 + endloop + endfacet + facet normal 0.20235 0.0482182 0.978126 + outer loop + vertex 1.09291 1.74731 2.60399 + vertex 1.0927 1.75195 2.6038 + vertex 1.08861 1.74776 2.60486 + endloop + endfacet + facet normal 0.0801541 0.0772643 0.993783 + outer loop + vertex 1.08825 1.75224 2.60459 + vertex 1.08809 1.75703 2.60423 + vertex 1.08349 1.75264 2.60494 + endloop + endfacet + facet normal 0.0896259 0.0732431 0.993279 + outer loop + vertex 1.07366 1.75409 2.60559 + vertex 1.07812 1.75401 2.60519 + vertex 1.07393 1.75873 2.60523 + endloop + endfacet + facet normal 0.096384 0.0862787 0.991598 + outer loop + vertex 1.07393 1.75873 2.60523 + vertex 1.07854 1.76253 2.60445 + vertex 1.07445 1.76357 2.60475 + endloop + endfacet + facet normal 0.0707057 0.0889736 0.993521 + outer loop + vertex 1.08321 1.75745 2.60455 + vertex 1.08339 1.76222 2.60411 + vertex 1.07915 1.75862 2.60474 + endloop + endfacet + facet normal 0.0767851 0.0946762 0.992542 + outer loop + vertex 1.07854 1.76253 2.60445 + vertex 1.08341 1.76706 2.60364 + vertex 1.07846 1.7672 2.60401 + endloop + endfacet + facet normal 0.0689674 0.0920587 0.993362 + outer loop + vertex 1.08824 1.76207 2.60379 + vertex 1.08839 1.76714 2.60331 + vertex 1.08339 1.76222 2.60411 + endloop + endfacet + facet normal 0.0588163 0.10783 0.992428 + outer loop + vertex 1.08341 1.76706 2.60364 + vertex 1.08825 1.77207 2.60281 + vertex 1.08335 1.77208 2.6031 + endloop + endfacet + facet normal 0.0587854 0.115563 0.991559 + outer loop + vertex 1.08825 1.77207 2.60281 + vertex 1.08786 1.77694 2.60226 + vertex 1.08335 1.77208 2.6031 + endloop + endfacet + facet normal 0.055618 0.118477 0.991398 + outer loop + vertex 1.08335 1.77208 2.6031 + vertex 1.08786 1.77694 2.60226 + vertex 1.08288 1.77705 2.60253 + endloop + endfacet + facet normal 0.0557472 0.126799 0.990361 + outer loop + vertex 1.08786 1.77694 2.60226 + vertex 1.08648 1.78223 2.60166 + vertex 1.08288 1.77705 2.60253 + endloop + endfacet + facet normal 0.0588087 0.124681 0.990452 + outer loop + vertex 1.08288 1.77705 2.60253 + vertex 1.08648 1.78223 2.60166 + vertex 1.08164 1.78106 2.6021 + endloop + endfacet + facet normal 0.0574112 0.130221 0.989821 + outer loop + vertex 1.08165 1.78617 2.60142 + vertex 1.08164 1.78106 2.6021 + vertex 1.08648 1.78223 2.60166 + endloop + endfacet + facet normal 0.058322 0.131325 0.989622 + outer loop + vertex 1.08647 1.78668 2.60107 + vertex 1.08165 1.78617 2.60142 + vertex 1.08648 1.78223 2.60166 + endloop + endfacet + facet normal 0.047298 0.131364 0.990205 + outer loop + vertex 1.08647 1.78668 2.60107 + vertex 1.08648 1.78223 2.60166 + vertex 1.09071 1.78529 2.60105 + endloop + endfacet + facet normal 0.0567983 0.144569 0.987863 + outer loop + vertex 1.08647 1.78668 2.60107 + vertex 1.08441 1.7894 2.60079 + vertex 1.08165 1.78617 2.60142 + endloop + endfacet + facet normal 0.0457346 0.136398 0.989598 + outer loop + vertex 1.08441 1.7894 2.60079 + vertex 1.08647 1.78668 2.60107 + vertex 1.08894 1.78983 2.60052 + endloop + endfacet + facet normal 0.0482971 0.134413 0.989748 + outer loop + vertex 1.09071 1.78529 2.60105 + vertex 1.08894 1.78983 2.60052 + vertex 1.08647 1.78668 2.60107 + endloop + endfacet + facet normal 0.093919 0.151539 0.983979 + outer loop + vertex 1.08894 1.78983 2.60052 + vertex 1.09071 1.78529 2.60105 + vertex 1.09487 1.78799 2.60024 + endloop + endfacet + facet normal 0.0573178 0.127191 0.990221 + outer loop + vertex 1.08786 1.77694 2.60226 + vertex 1.09231 1.78062 2.60153 + vertex 1.08648 1.78223 2.60166 + endloop + endfacet + facet normal 0.106188 0.0841612 0.990778 + outer loop + vertex 1.09303 1.76713 2.60281 + vertex 1.09278 1.77213 2.60242 + vertex 1.08839 1.76714 2.60331 + endloop + endfacet + facet normal 0.208357 0.0879639 0.974089 + outer loop + vertex 1.09303 1.76713 2.60281 + vertex 1.09684 1.77182 2.60157 + vertex 1.09278 1.77213 2.60242 + endloop + endfacet + facet normal 0.06172 0.115773 0.991356 + outer loop + vertex 1.08825 1.77207 2.60281 + vertex 1.09183 1.77605 2.60212 + vertex 1.08786 1.77694 2.60226 + endloop + endfacet + facet normal 0.207299 0.0693707 0.975815 + outer loop + vertex 1.09684 1.77182 2.60157 + vertex 1.09593 1.777 2.6014 + vertex 1.09278 1.77213 2.60242 + endloop + endfacet + facet normal 0.0627919 0.120677 0.990704 + outer loop + vertex 1.09183 1.77605 2.60212 + vertex 1.09231 1.78062 2.60153 + vertex 1.08786 1.77694 2.60226 + endloop + endfacet + facet normal 0.0554402 0.120308 0.991187 + outer loop + vertex 1.09231 1.78062 2.60153 + vertex 1.09071 1.78529 2.60105 + vertex 1.08648 1.78223 2.60166 + endloop + endfacet + facet normal 0.277808 0.19028 0.941603 + outer loop + vertex 1.09478 1.78389 2.60084 + vertex 1.09642 1.78119 2.6009 + vertex 1.09897 1.78395 2.5996 + endloop + endfacet + facet normal 0.0815863 0.110645 0.990506 + outer loop + vertex 1.09487 1.78799 2.60024 + vertex 1.09362 1.79284 2.5998 + vertex 1.08894 1.78983 2.60052 + endloop + endfacet + facet normal 0.0459434 0.134356 0.989868 + outer loop + vertex 1.08441 1.7894 2.60079 + vertex 1.08894 1.78983 2.60052 + vertex 1.08427 1.79366 2.60022 + endloop + endfacet + facet normal 0.0533737 0.155132 0.986451 + outer loop + vertex 1.0895 1.79397 2.59992 + vertex 1.09334 1.79736 2.59918 + vertex 1.08868 1.79766 2.59938 + endloop + endfacet + facet normal 0.0671995 0.139225 0.987978 + outer loop + vertex 1.08466 1.79841 2.59949 + vertex 1.08845 1.80222 2.5987 + vertex 1.08363 1.80227 2.59902 + endloop + endfacet + facet normal 0.0531134 0.150729 0.987147 + outer loop + vertex 1.09334 1.79736 2.59918 + vertex 1.09317 1.8021 2.59846 + vertex 1.08868 1.79766 2.59938 + endloop + endfacet + facet normal 0.0565156 0.142824 0.988133 + outer loop + vertex 1.08845 1.80222 2.5987 + vertex 1.09275 1.80697 2.59777 + vertex 1.08805 1.80687 2.59805 + endloop + endfacet + facet normal 0.0918792 0.132099 0.986969 + outer loop + vertex 1.09775 1.80187 2.59806 + vertex 1.09745 1.80691 2.59742 + vertex 1.09317 1.8021 2.59846 + endloop + endfacet + facet normal 0.184375 0.135923 0.973412 + outer loop + vertex 1.09775 1.80187 2.59806 + vertex 1.10166 1.80631 2.59671 + vertex 1.09745 1.80691 2.59742 + endloop + endfacet + facet normal 0.0603151 0.142974 0.987887 + outer loop + vertex 1.09275 1.80697 2.59777 + vertex 1.09623 1.8122 2.5968 + vertex 1.0916 1.81096 2.59726 + endloop + endfacet + facet normal 0.180297 0.101423 0.978369 + outer loop + vertex 1.10166 1.80631 2.59671 + vertex 1.10104 1.81097 2.59634 + vertex 1.09745 1.80691 2.59742 + endloop + endfacet + facet normal 0.11874 0.131111 0.984231 + outer loop + vertex 1.0965 1.81669 2.59617 + vertex 1.09623 1.8122 2.5968 + vertex 1.10033 1.81533 2.59589 + endloop + endfacet + facet normal 0.123678 0.145521 0.981594 + outer loop + vertex 1.10033 1.81533 2.59589 + vertex 1.09899 1.8199 2.59538 + vertex 1.0965 1.81669 2.59617 + endloop + endfacet + facet normal 0.365497 0.105383 0.924828 + outer loop + vertex 1.10418 1.81784 2.59444 + vertex 1.10726 1.82176 2.59277 + vertex 1.10338 1.82274 2.5942 + endloop + endfacet + facet normal 0.355281 0.0530346 0.933254 + outer loop + vertex 1.10726 1.82176 2.59277 + vertex 1.10697 1.82642 2.59262 + vertex 1.10338 1.82274 2.5942 + endloop + endfacet + facet normal 0.095034 0.167675 0.981251 + outer loop + vertex 1.09457 1.81942 2.59589 + vertex 1.0965 1.81669 2.59617 + vertex 1.09899 1.8199 2.59538 + endloop + endfacet + facet normal 0.0589738 0.142855 0.987985 + outer loop + vertex 1.0965 1.81669 2.59617 + vertex 1.09457 1.81942 2.59589 + vertex 1.09164 1.81608 2.59654 + endloop + endfacet + facet normal 0.0607117 0.14263 0.987912 + outer loop + vertex 1.08687 1.81997 2.59628 + vertex 1.08658 1.81546 2.59694 + vertex 1.09164 1.81608 2.59654 + endloop + endfacet + facet normal 0.0644958 0.156581 0.985557 + outer loop + vertex 1.08932 1.82332 2.59559 + vertex 1.09132 1.82058 2.5959 + vertex 1.09445 1.82375 2.59519 + endloop + endfacet + facet normal 0.0836746 0.151999 0.984832 + outer loop + vertex 1.08687 1.81997 2.59628 + vertex 1.08514 1.82469 2.59569 + vertex 1.08102 1.8216 2.59652 + endloop + endfacet + facet normal 0.0835473 0.156844 0.984083 + outer loop + vertex 1.09356 1.83231 2.5938 + vertex 1.09289 1.83687 2.59313 + vertex 1.08861 1.83272 2.59416 + endloop + endfacet + facet normal 0.0643923 0.15766 0.985392 + outer loop + vertex 1.08932 1.82332 2.59559 + vertex 1.09445 1.82375 2.59519 + vertex 1.08969 1.82765 2.59487 + endloop + endfacet + facet normal 0.0804836 0.159999 0.983831 + outer loop + vertex 1.09964 1.82407 2.59471 + vertex 1.09873 1.82775 2.59419 + vertex 1.09445 1.82375 2.59519 + endloop + endfacet + facet normal 0.0746668 0.166552 0.983202 + outer loop + vertex 1.09477 1.82852 2.59435 + vertex 1.09816 1.83208 2.59349 + vertex 1.09356 1.83231 2.5938 + endloop + endfacet + facet normal 0.12823 0.146753 0.980827 + outer loop + vertex 1.10307 1.82725 2.59369 + vertex 1.10248 1.83183 2.59309 + vertex 1.09873 1.82775 2.59419 + endloop + endfacet + facet normal 0.219651 0.156108 0.963008 + outer loop + vertex 1.10307 1.82725 2.59369 + vertex 1.10662 1.83133 2.59222 + vertex 1.10248 1.83183 2.59309 + endloop + endfacet + facet normal 0.0878356 0.163603 0.982608 + outer loop + vertex 1.09816 1.83208 2.59349 + vertex 1.10134 1.83576 2.59259 + vertex 1.09753 1.83653 2.59281 + endloop + endfacet + facet normal 0.216871 0.124209 0.968266 + outer loop + vertex 1.10662 1.83133 2.59222 + vertex 1.10558 1.83668 2.59177 + vertex 1.10248 1.83183 2.59309 + endloop + endfacet + facet normal 0.0868835 0.158629 0.983508 + outer loop + vertex 1.10134 1.83576 2.59259 + vertex 1.1015 1.84091 2.59175 + vertex 1.09753 1.83653 2.59281 + endloop + endfacet + facet normal 0.0857247 0.151971 0.98466 + outer loop + vertex 1.10144 1.84564 2.59102 + vertex 1.09693 1.84504 2.59151 + vertex 1.1015 1.84091 2.59175 + endloop + endfacet + facet normal 0.0838227 0.164834 0.982753 + outer loop + vertex 1.10144 1.84564 2.59102 + vertex 1.09952 1.84852 2.5907 + vertex 1.09693 1.84504 2.59151 + endloop + endfacet + facet normal 0.260773 0.195461 0.945406 + outer loop + vertex 1.10461 1.84421 2.59083 + vertex 1.10615 1.84119 2.59103 + vertex 1.10896 1.84398 2.58968 + endloop + endfacet + facet normal 0.191214 0.105591 0.975852 + outer loop + vertex 1.10923 1.84882 2.58916 + vertex 1.10835 1.85272 2.58891 + vertex 1.1045 1.84878 2.5901 + endloop + endfacet + facet normal 0.109877 0.181605 0.977214 + outer loop + vertex 1.09952 1.84852 2.5907 + vertex 1.10144 1.84564 2.59102 + vertex 1.1045 1.84878 2.5901 + endloop + endfacet + facet normal 0.0831149 0.165354 0.982726 + outer loop + vertex 1.09952 1.84852 2.5907 + vertex 1.09537 1.84991 2.59082 + vertex 1.09693 1.84504 2.59151 + endloop + endfacet + facet normal 0.0932125 0.173155 0.980474 + outer loop + vertex 1.09537 1.84991 2.59082 + vertex 1.09401 1.85452 2.59014 + vertex 1.09133 1.85118 2.59098 + endloop + endfacet + facet normal 0.0954502 0.17659 0.979645 + outer loop + vertex 1.09401 1.85452 2.59014 + vertex 1.0987 1.85771 2.5891 + vertex 1.09474 1.85868 2.58931 + endloop + endfacet + facet normal 0.0867658 0.177269 0.98033 + outer loop + vertex 1.10471 1.85369 2.58932 + vertex 1.10347 1.85739 2.58876 + vertex 1.09987 1.85286 2.5899 + endloop + endfacet + facet normal 0.0889991 0.176183 0.980326 + outer loop + vertex 1.0987 1.85771 2.5891 + vertex 1.10256 1.86172 2.58803 + vertex 1.09811 1.8619 2.5884 + endloop + endfacet + facet normal 0.110234 0.168229 0.979565 + outer loop + vertex 1.10789 1.85716 2.5883 + vertex 1.10717 1.86163 2.58762 + vertex 1.10347 1.85739 2.58876 + endloop + endfacet + facet normal 0.0877955 0.175668 0.980527 + outer loop + vertex 1.10256 1.86172 2.58803 + vertex 1.10589 1.86654 2.58687 + vertex 1.10132 1.86539 2.58749 + endloop + endfacet + facet normal 0.170022 0.143255 0.974972 + outer loop + vertex 1.11142 1.86104 2.58696 + vertex 1.11068 1.86546 2.58644 + vertex 1.10717 1.86163 2.58762 + endloop + endfacet + facet normal 0.118073 0.170861 0.978195 + outer loop + vertex 1.10636 1.87106 2.58603 + vertex 1.10589 1.86654 2.58687 + vertex 1.11011 1.86977 2.5858 + endloop + endfacet + facet normal 0.120051 0.176829 0.976893 + outer loop + vertex 1.11011 1.86977 2.5858 + vertex 1.10919 1.87449 2.58506 + vertex 1.10636 1.87106 2.58603 + endloop + endfacet + facet normal 0.290451 0.14067 0.946494 + outer loop + vertex 1.11423 1.87259 2.58437 + vertex 1.11742 1.87667 2.58278 + vertex 1.11343 1.87761 2.58386 + endloop + endfacet + facet normal 0.284515 0.108419 0.952521 + outer loop + vertex 1.11742 1.87667 2.58278 + vertex 1.11674 1.8814 2.58244 + vertex 1.11343 1.87761 2.58386 + endloop + endfacet + facet normal 0.220049 0.167937 0.960924 + outer loop + vertex 1.11343 1.87761 2.58386 + vertex 1.11674 1.8814 2.58244 + vertex 1.11269 1.88205 2.58326 + endloop + endfacet + facet normal 0.37495 0.0663102 0.92467 + outer loop + vertex 1.11813 1.87282 2.58277 + vertex 1.11742 1.87667 2.58278 + vertex 1.11423 1.87259 2.58437 + endloop + endfacet + facet normal 0.106076 0.182281 0.977508 + outer loop + vertex 1.10453 1.87428 2.5856 + vertex 1.10919 1.87449 2.58506 + vertex 1.1059 1.87818 2.58473 + endloop + endfacet + facet normal 0.0951354 0.187187 0.977707 + outer loop + vertex 1.1059 1.87818 2.58473 + vertex 1.10857 1.88221 2.58369 + vertex 1.10407 1.88249 2.58408 + endloop + endfacet + facet normal 0.14928 0.158121 0.97607 + outer loop + vertex 1.11343 1.87761 2.58386 + vertex 1.11269 1.88205 2.58326 + vertex 1.10993 1.87877 2.58421 + endloop + endfacet + facet normal 0.0948406 0.184872 0.978176 + outer loop + vertex 1.10857 1.88221 2.58369 + vertex 1.11126 1.88568 2.58278 + vertex 1.10751 1.88646 2.58299 + endloop + endfacet + facet normal 0.216661 0.140293 0.966114 + outer loop + vertex 1.11674 1.8814 2.58244 + vertex 1.11548 1.88658 2.58198 + vertex 1.11269 1.88205 2.58326 + endloop + endfacet + facet normal 0.0938459 0.179742 0.979227 + outer loop + vertex 1.11126 1.88568 2.58278 + vertex 1.11128 1.89069 2.58186 + vertex 1.10751 1.88646 2.58299 + endloop + endfacet + facet normal 0.0995891 0.17868 0.978854 + outer loop + vertex 1.11132 1.8954 2.58099 + vertex 1.10671 1.89479 2.58157 + vertex 1.11128 1.89069 2.58186 + endloop + endfacet + facet normal 0.106984 0.196287 0.974693 + outer loop + vertex 1.10946 1.89829 2.58061 + vertex 1.11132 1.8954 2.58099 + vertex 1.11462 1.89864 2.57998 + endloop + endfacet + facet normal 0.213433 0.207005 0.954775 + outer loop + vertex 1.11455 1.89404 2.58086 + vertex 1.11605 1.89104 2.58118 + vertex 1.11919 1.89392 2.57985 + endloop + endfacet + facet normal 0.233519 0.16433 0.958365 + outer loop + vertex 1.11978 1.89892 2.57912 + vertex 1.12322 1.90227 2.57771 + vertex 1.11861 1.90263 2.57877 + endloop + endfacet + facet normal 0.231371 0.114596 0.966093 + outer loop + vertex 1.12322 1.90227 2.57771 + vertex 1.12143 1.90602 2.57769 + vertex 1.11861 1.90263 2.57877 + endloop + endfacet + facet normal 0.147118 0.186388 0.971399 + outer loop + vertex 1.11861 1.90263 2.57877 + vertex 1.12143 1.90602 2.57769 + vertex 1.1177 1.90667 2.57813 + endloop + endfacet + facet normal 0.107397 0.191788 0.975543 + outer loop + vertex 1.10946 1.89829 2.58061 + vertex 1.11462 1.89864 2.57998 + vertex 1.10983 1.9027 2.5797 + endloop + endfacet + facet normal 0.101698 0.194803 0.975556 + outer loop + vertex 1.10983 1.9027 2.5797 + vertex 1.11323 1.90694 2.57851 + vertex 1.1085 1.90769 2.57885 + endloop + endfacet + facet normal 0.114625 0.17993 0.976978 + outer loop + vertex 1.11861 1.90263 2.57877 + vertex 1.1177 1.90667 2.57813 + vertex 1.11474 1.90344 2.57907 + endloop + endfacet + facet normal 0.095584 0.192193 0.976691 + outer loop + vertex 1.11323 1.90694 2.57851 + vertex 1.11638 1.91013 2.57757 + vertex 1.1123 1.91133 2.57773 + endloop + endfacet + facet normal 0.146204 0.180345 0.972677 + outer loop + vertex 1.12143 1.90602 2.57769 + vertex 1.12133 1.91083 2.57681 + vertex 1.1177 1.90667 2.57813 + endloop + endfacet + facet normal 0.0944359 0.188169 0.977586 + outer loop + vertex 1.11638 1.91013 2.57757 + vertex 1.11683 1.91465 2.57665 + vertex 1.1123 1.91133 2.57773 + endloop + endfacet + facet normal 0.109441 0.189302 0.975801 + outer loop + vertex 1.12141 1.91537 2.576 + vertex 1.11959 1.9182 2.57566 + vertex 1.11683 1.91465 2.57665 + endloop + endfacet + facet normal 0.36826 0.203667 0.907141 + outer loop + vertex 1.1243 1.91417 2.57566 + vertex 1.12566 1.91145 2.57572 + vertex 1.12783 1.91416 2.57423 + endloop + endfacet + facet normal 0.165355 0.223184 0.960649 + outer loop + vertex 1.11959 1.9182 2.57566 + vertex 1.12141 1.91537 2.576 + vertex 1.12449 1.91858 2.57473 + endloop + endfacet + facet normal 0.106217 0.191783 0.975673 + outer loop + vertex 1.11959 1.9182 2.57566 + vertex 1.11533 1.91965 2.57584 + vertex 1.11683 1.91465 2.57665 + endloop + endfacet + facet normal 0.108969 0.193256 0.975078 + outer loop + vertex 1.11533 1.91965 2.57584 + vertex 1.11389 1.9246 2.57502 + vertex 1.11109 1.92115 2.57601 + endloop + endfacet + facet normal 0.107201 0.200899 0.973729 + outer loop + vertex 1.11389 1.9246 2.57502 + vertex 1.11836 1.92747 2.57393 + vertex 1.11444 1.92884 2.57408 + endloop + endfacet + facet normal 0.139151 0.172449 0.97514 + outer loop + vertex 1.1248 1.9235 2.57388 + vertex 1.12306 1.9271 2.57349 + vertex 1.1199 1.92265 2.57473 + endloop + endfacet + facet normal 0.0999075 0.202369 0.9742 + outer loop + vertex 1.11836 1.92747 2.57393 + vertex 1.12136 1.93064 2.57297 + vertex 1.11757 1.93161 2.57315 + endloop + endfacet + facet normal 0.169096 0.169201 0.970967 + outer loop + vertex 1.12757 1.9271 2.57271 + vertex 1.12591 1.93179 2.57218 + vertex 1.12306 1.9271 2.57349 + endloop + endfacet + facet normal 0.0998595 0.202173 0.974245 + outer loop + vertex 1.12136 1.93064 2.57297 + vertex 1.1214 1.93555 2.57194 + vertex 1.11757 1.93161 2.57315 + endloop + endfacet + facet normal 0.107829 0.20243 0.973342 + outer loop + vertex 1.12634 1.93621 2.57126 + vertex 1.1246 1.93905 2.57086 + vertex 1.1214 1.93555 2.57194 + endloop + endfacet + facet normal 0.145558 0.224134 0.963627 + outer loop + vertex 1.1246 1.93905 2.57086 + vertex 1.12634 1.93621 2.57126 + vertex 1.129 1.93963 2.57006 + endloop + endfacet + facet normal 0.148601 0.206027 0.967197 + outer loop + vertex 1.1246 1.93905 2.57086 + vertex 1.129 1.93963 2.57006 + vertex 1.12455 1.9436 2.5699 + endloop + endfacet + facet normal 0.116737 0.205604 0.971648 + outer loop + vertex 1.12455 1.9436 2.5699 + vertex 1.12818 1.94749 2.56864 + vertex 1.12438 1.94813 2.56896 + endloop + endfacet + facet normal 0.226962 0.156756 0.961205 + outer loop + vertex 1.13323 1.94257 2.56852 + vertex 1.13252 1.94702 2.56796 + vertex 1.12959 1.944 2.56915 + endloop + endfacet + facet normal 0.137706 0.215361 0.966777 + outer loop + vertex 1.12818 1.94749 2.56864 + vertex 1.13098 1.95176 2.56729 + vertex 1.12662 1.95087 2.56811 + endloop + endfacet + facet normal 0.134698 0.200564 0.970377 + outer loop + vertex 1.13134 1.9562 2.56632 + vertex 1.12645 1.95561 2.56712 + vertex 1.13098 1.95176 2.56729 + endloop + endfacet + facet normal 0.16522 0.217836 0.961899 + outer loop + vertex 1.1296 1.95911 2.56596 + vertex 1.13134 1.9562 2.56632 + vertex 1.13401 1.95969 2.56507 + endloop + endfacet + facet normal 0.167483 0.204568 0.964418 + outer loop + vertex 1.1296 1.95911 2.56596 + vertex 1.13401 1.95969 2.56507 + vertex 1.12958 1.96367 2.565 + endloop + endfacet + facet normal 0.136759 0.203904 0.969392 + outer loop + vertex 1.12958 1.96367 2.565 + vertex 1.13319 1.96748 2.56369 + vertex 1.12943 1.9682 2.56406 + endloop + endfacet + facet normal 0.23071 0.157334 0.960218 + outer loop + vertex 1.13823 1.96262 2.56351 + vertex 1.13752 1.96697 2.56297 + vertex 1.13458 1.96399 2.56416 + endloop + endfacet + facet normal 0.320266 0.168636 0.932197 + outer loop + vertex 1.13823 1.96262 2.56351 + vertex 1.14148 1.96597 2.56179 + vertex 1.13752 1.96697 2.56297 + endloop + endfacet + facet normal 0.151118 0.210868 0.965763 + outer loop + vertex 1.13319 1.96748 2.56369 + vertex 1.136 1.97174 2.56232 + vertex 1.13164 1.97091 2.56318 + endloop + endfacet + facet normal 0.311267 0.120655 0.942632 + outer loop + vertex 1.14148 1.96597 2.56179 + vertex 1.14071 1.97037 2.56148 + vertex 1.13752 1.96697 2.56297 + endloop + endfacet + facet normal 0.15158 0.208835 0.966132 + outer loop + vertex 1.13139 1.97576 2.56217 + vertex 1.13164 1.97091 2.56318 + vertex 1.136 1.97174 2.56232 + endloop + endfacet + facet normal 0.169954 0.226994 0.958952 + outer loop + vertex 1.1346 1.97919 2.56093 + vertex 1.13638 1.97619 2.56132 + vertex 1.13901 1.97961 2.56005 + endloop + endfacet + facet normal 0.142406 0.205119 0.968322 + outer loop + vertex 1.12634 1.98036 2.56194 + vertex 1.12635 1.9754 2.56299 + vertex 1.13139 1.97576 2.56217 + endloop + endfacet + facet normal 0.153017 0.216429 0.964233 + outer loop + vertex 1.12954 1.98378 2.56068 + vertex 1.1313 1.98063 2.56111 + vertex 1.13448 1.98384 2.55988 + endloop + endfacet + facet normal 0.150807 0.207536 0.966533 + outer loop + vertex 1.12177 1.9846 2.56174 + vertex 1.12137 1.98016 2.56276 + vertex 1.12634 1.98036 2.56194 + endloop + endfacet + facet normal 0.161181 0.212002 0.963886 + outer loop + vertex 1.12446 1.9882 2.56054 + vertex 1.12627 1.9852 2.5609 + vertex 1.12944 1.98846 2.55965 + endloop + endfacet + facet normal 0.143334 0.206513 0.967888 + outer loop + vertex 1.12177 1.9846 2.56174 + vertex 1.12035 1.98963 2.56088 + vertex 1.11602 1.9865 2.56219 + endloop + endfacet + facet normal 0.143512 0.202562 0.968697 + outer loop + vertex 1.12035 1.98963 2.56088 + vertex 1.119 1.99458 2.56004 + vertex 1.11622 1.99104 2.5612 + endloop + endfacet + facet normal 0.154871 0.194091 0.968681 + outer loop + vertex 1.119 1.99458 2.56004 + vertex 1.12333 1.99743 2.55878 + vertex 1.11956 1.99888 2.55909 + endloop + endfacet + facet normal 0.16615 0.191606 0.967306 + outer loop + vertex 1.12772 1.99665 2.55818 + vertex 1.12623 2.00034 2.55771 + vertex 1.12333 1.99743 2.55878 + endloop + endfacet + facet normal 0.172297 0.193887 0.965775 + outer loop + vertex 1.12772 1.99665 2.55818 + vertex 1.13118 2.00043 2.55681 + vertex 1.12623 2.00034 2.55771 + endloop + endfacet + facet normal 0.168902 0.196981 0.965749 + outer loop + vertex 1.13147 1.99561 2.55774 + vertex 1.13118 2.00043 2.55681 + vertex 1.12772 1.99665 2.55818 + endloop + endfacet + facet normal 0.170009 0.201448 0.964633 + outer loop + vertex 1.12923 1.99312 2.55865 + vertex 1.13147 1.99561 2.55774 + vertex 1.12772 1.99665 2.55818 + endloop + endfacet + facet normal 0.161469 0.208733 0.964551 + outer loop + vertex 1.12446 1.9882 2.56054 + vertex 1.12944 1.98846 2.55965 + vertex 1.12476 1.99262 2.55953 + endloop + endfacet + facet normal 0.163991 0.206841 0.964533 + outer loop + vertex 1.13289 1.992 2.55827 + vertex 1.13147 1.99561 2.55774 + vertex 1.12923 1.99312 2.55865 + endloop + endfacet + facet normal 0.158344 0.204832 0.965904 + outer loop + vertex 1.13289 1.992 2.55827 + vertex 1.13633 1.99552 2.55696 + vertex 1.13147 1.99561 2.55774 + endloop + endfacet + facet normal 0.153127 0.209854 0.965667 + outer loop + vertex 1.13663 1.99072 2.55796 + vertex 1.13633 1.99552 2.55696 + vertex 1.13289 1.992 2.55827 + endloop + endfacet + facet normal 0.155295 0.216654 0.963818 + outer loop + vertex 1.13429 1.98841 2.55885 + vertex 1.13663 1.99072 2.55796 + vertex 1.13289 1.992 2.55827 + endloop + endfacet + facet normal 0.153061 0.215484 0.964437 + outer loop + vertex 1.12954 1.98378 2.56068 + vertex 1.13448 1.98384 2.55988 + vertex 1.12944 1.98846 2.55965 + endloop + endfacet + facet normal 0.15041 0.221455 0.963501 + outer loop + vertex 1.13803 1.98714 2.55856 + vertex 1.13663 1.99072 2.55796 + vertex 1.13429 1.98841 2.55885 + endloop + endfacet + facet normal 0.159748 0.224744 0.961234 + outer loop + vertex 1.13803 1.98714 2.55856 + vertex 1.14139 1.99067 2.55718 + vertex 1.13663 1.99072 2.55796 + endloop + endfacet + facet normal 0.170859 0.22032 0.960347 + outer loop + vertex 1.1346 1.97919 2.56093 + vertex 1.13901 1.97961 2.56005 + vertex 1.13448 1.98384 2.55988 + endloop + endfacet + facet normal 0.255804 0.141344 0.95634 + outer loop + vertex 1.1441 1.97752 2.55899 + vertex 1.14296 1.9824 2.55858 + vertex 1.13901 1.97961 2.56005 + endloop + endfacet + facet normal 0.170833 0.223049 0.959721 + outer loop + vertex 1.13935 1.98369 2.55913 + vertex 1.14162 1.98597 2.55819 + vertex 1.13803 1.98714 2.55856 + endloop + endfacet + facet normal 0.16882 0.216285 0.961624 + outer loop + vertex 1.14162 1.98597 2.55819 + vertex 1.14139 1.99067 2.55718 + vertex 1.13803 1.98714 2.55856 + endloop + endfacet + facet normal 0.212429 0.18284 0.959919 + outer loop + vertex 1.14603 1.99065 2.55615 + vertex 1.14456 1.99377 2.55588 + vertex 1.14139 1.99067 2.55718 + endloop + endfacet + facet normal 0.160123 0.210036 0.964492 + outer loop + vertex 1.13633 1.99552 2.55696 + vertex 1.13663 1.99072 2.55796 + vertex 1.14139 1.99067 2.55718 + endloop + endfacet + facet normal 0.173548 0.220926 0.959725 + outer loop + vertex 1.13952 1.99868 2.55576 + vertex 1.14131 1.99544 2.55618 + vertex 1.14446 1.99858 2.55489 + endloop + endfacet + facet normal 0.158467 0.196692 0.967575 + outer loop + vertex 1.13118 2.00043 2.55681 + vertex 1.13147 1.99561 2.55774 + vertex 1.13633 1.99552 2.55696 + endloop + endfacet + facet normal 0.163171 0.197567 0.966614 + outer loop + vertex 1.13435 2.00367 2.55557 + vertex 1.13612 2.00038 2.55595 + vertex 1.13937 2.00349 2.55476 + endloop + endfacet + facet normal 0.172511 0.189819 0.966545 + outer loop + vertex 1.12609 2.00536 2.55675 + vertex 1.12623 2.00034 2.55771 + vertex 1.13118 2.00043 2.55681 + endloop + endfacet + facet normal 0.162384 0.184415 0.969341 + outer loop + vertex 1.12597 2.01036 2.55581 + vertex 1.1211 2.01015 2.55667 + vertex 1.12609 2.00536 2.55675 + endloop + endfacet + facet normal 0.181557 0.186384 0.965556 + outer loop + vertex 1.12928 2.00869 2.55553 + vertex 1.13102 2.00539 2.55584 + vertex 1.13427 2.0085 2.55463 + endloop + endfacet + facet normal 0.184575 0.192749 0.963732 + outer loop + vertex 1.13784 2.01187 2.55327 + vertex 1.13648 2.01559 2.55279 + vertex 1.13411 2.01328 2.5537 + endloop + endfacet + facet normal 0.169798 0.197826 0.965419 + outer loop + vertex 1.1392 2.00819 2.55379 + vertex 1.14155 2.01052 2.55289 + vertex 1.13784 2.01187 2.55327 + endloop + endfacet + facet normal 0.169966 0.198327 0.965286 + outer loop + vertex 1.14155 2.01052 2.55289 + vertex 1.14131 2.01539 2.55194 + vertex 1.13784 2.01187 2.55327 + endloop + endfacet + facet normal 0.163155 0.19241 0.967656 + outer loop + vertex 1.13435 2.00367 2.55557 + vertex 1.13937 2.00349 2.55476 + vertex 1.13427 2.0085 2.55463 + endloop + endfacet + facet normal 0.159244 0.208323 0.965009 + outer loop + vertex 1.14289 2.0069 2.55345 + vertex 1.14155 2.01052 2.55289 + vertex 1.1392 2.00819 2.55379 + endloop + endfacet + facet normal 0.163756 0.209825 0.963928 + outer loop + vertex 1.14289 2.0069 2.55345 + vertex 1.14624 2.01053 2.5521 + vertex 1.14155 2.01052 2.55289 + endloop + endfacet + facet normal 0.173857 0.20443 0.963318 + outer loop + vertex 1.13952 1.99868 2.55576 + vertex 1.14446 1.99858 2.55489 + vertex 1.13937 2.00349 2.55476 + endloop + endfacet + facet normal 0.236942 0.14428 0.960751 + outer loop + vertex 1.14924 1.99847 2.55372 + vertex 1.14787 2.00223 2.5535 + vertex 1.14446 1.99858 2.55489 + endloop + endfacet + facet normal 0.319692 0.172633 0.931662 + outer loop + vertex 1.14924 1.99847 2.55372 + vertex 1.15175 2.00135 2.55233 + vertex 1.14787 2.00223 2.5535 + endloop + endfacet + facet normal 0.164374 0.212119 0.963321 + outer loop + vertex 1.14426 2.00332 2.55401 + vertex 1.14643 2.00578 2.5531 + vertex 1.14289 2.0069 2.55345 + endloop + endfacet + facet normal 0.315577 0.146742 0.937485 + outer loop + vertex 1.15175 2.00135 2.55233 + vertex 1.15034 2.00624 2.55204 + vertex 1.14787 2.00223 2.5535 + endloop + endfacet + facet normal 0.163719 0.209859 0.963927 + outer loop + vertex 1.14643 2.00578 2.5531 + vertex 1.14624 2.01053 2.5521 + vertex 1.14289 2.0069 2.55345 + endloop + endfacet + facet normal 0.199146 0.187709 0.961824 + outer loop + vertex 1.1509 2.01057 2.55112 + vertex 1.14948 2.0137 2.55081 + vertex 1.14624 2.01053 2.5521 + endloop + endfacet + facet normal 0.164175 0.198237 0.966307 + outer loop + vertex 1.14131 2.01539 2.55194 + vertex 1.14155 2.01052 2.55289 + vertex 1.14624 2.01053 2.5521 + endloop + endfacet + facet normal 0.18593 0.20359 0.961239 + outer loop + vertex 1.1411 2.02031 2.55094 + vertex 1.13619 2.02045 2.55185 + vertex 1.14131 2.01539 2.55194 + endloop + endfacet + facet normal 0.173345 0.210507 0.962101 + outer loop + vertex 1.14447 2.01859 2.55069 + vertex 1.14623 2.01533 2.55109 + vertex 1.14942 2.01851 2.54982 + endloop + endfacet + facet normal 0.192197 0.17072 0.966393 + outer loop + vertex 1.15438 2.01849 2.54883 + vertex 1.15297 2.02202 2.54849 + vertex 1.14942 2.01851 2.54982 + endloop + endfacet + facet normal 0.183148 0.217038 0.958828 + outer loop + vertex 1.15297 2.02202 2.54849 + vertex 1.15632 2.02561 2.54704 + vertex 1.15163 2.02544 2.54797 + endloop + endfacet + facet normal 0.213119 0.188992 0.958573 + outer loop + vertex 1.15659 2.02105 2.54788 + vertex 1.15632 2.02561 2.54704 + vertex 1.15297 2.02202 2.54849 + endloop + endfacet + facet normal 0.287257 0.189796 0.938862 + outer loop + vertex 1.15632 2.02561 2.54704 + vertex 1.15659 2.02105 2.54788 + vertex 1.16039 2.02179 2.54656 + endloop + endfacet + facet normal 0.233641 0.129582 0.963649 + outer loop + vertex 1.16088 2.02583 2.5459 + vertex 1.15632 2.02561 2.54704 + vertex 1.16039 2.02179 2.54656 + endloop + endfacet + facet normal 0.359698 0.108171 0.926777 + outer loop + vertex 1.16088 2.02583 2.5459 + vertex 1.16039 2.02179 2.54656 + vertex 1.16352 2.02392 2.5451 + endloop + endfacet + facet normal 0.351701 0.0952307 0.931256 + outer loop + vertex 1.16352 2.02392 2.5451 + vertex 1.16409 2.02866 2.5444 + vertex 1.16088 2.02583 2.5459 + endloop + endfacet + facet normal 0.230249 0.170976 0.957994 + outer loop + vertex 1.16088 2.02583 2.5459 + vertex 1.15945 2.02877 2.54572 + vertex 1.15632 2.02561 2.54704 + endloop + endfacet + facet normal 0.195268 0.205945 0.958883 + outer loop + vertex 1.15629 2.03012 2.54608 + vertex 1.15632 2.02561 2.54704 + vertex 1.15945 2.02877 2.54572 + endloop + endfacet + facet normal 0.198483 0.214157 0.956421 + outer loop + vertex 1.15945 2.02877 2.54572 + vertex 1.15936 2.03333 2.54472 + vertex 1.15629 2.03012 2.54608 + endloop + endfacet + facet normal 0.27191 0.211658 0.938758 + outer loop + vertex 1.15945 2.02877 2.54572 + vertex 1.16409 2.02866 2.5444 + vertex 1.15936 2.03333 2.54472 + endloop + endfacet + facet normal 0.168848 0.206772 0.963709 + outer loop + vertex 1.15629 2.03012 2.54608 + vertex 1.15185 2.02964 2.54695 + vertex 1.15632 2.02561 2.54704 + endloop + endfacet + facet normal 0.272634 0.190788 0.943012 + outer loop + vertex 1.15945 2.02877 2.54572 + vertex 1.16088 2.02583 2.5459 + vertex 1.16409 2.02866 2.5444 + endloop + endfacet + facet normal 0.182753 0.222064 0.957752 + outer loop + vertex 1.15185 2.02964 2.54695 + vertex 1.15163 2.02544 2.54797 + vertex 1.15632 2.02561 2.54704 + endloop + endfacet + facet normal 0.166227 0.219568 0.961331 + outer loop + vertex 1.1492 2.02321 2.54888 + vertex 1.1478 2.02693 2.54828 + vertex 1.14423 2.02345 2.54969 + endloop + endfacet + facet normal 0.180418 0.202439 0.962532 + outer loop + vertex 1.13927 2.02361 2.55058 + vertex 1.1411 2.02031 2.55094 + vertex 1.14423 2.02345 2.54969 + endloop + endfacet + facet normal 0.185914 0.205295 0.96088 + outer loop + vertex 1.1411 2.02031 2.55094 + vertex 1.13927 2.02361 2.55058 + vertex 1.13619 2.02045 2.55185 + endloop + endfacet + facet normal 0.180376 0.206443 0.961689 + outer loop + vertex 1.13104 2.03009 2.55081 + vertex 1.12673 2.02965 2.55171 + vertex 1.13118 2.02537 2.5518 + endloop + endfacet + facet normal 0.179959 0.209408 0.961126 + outer loop + vertex 1.13104 2.03009 2.55081 + vertex 1.12935 2.03305 2.55048 + vertex 1.12673 2.02965 2.55171 + endloop + endfacet + facet normal 0.192316 0.207044 0.959243 + outer loop + vertex 1.1342 2.02856 2.55053 + vertex 1.13594 2.02535 2.55087 + vertex 1.13898 2.02838 2.54961 + endloop + endfacet + facet normal 0.187819 0.215914 0.958178 + outer loop + vertex 1.1438 2.02837 2.54867 + vertex 1.14186 2.03151 2.54834 + vertex 1.13898 2.02838 2.54961 + endloop + endfacet + facet normal 0.191807 0.211746 0.958318 + outer loop + vertex 1.1387 2.03306 2.54863 + vertex 1.14165 2.03616 2.54735 + vertex 1.13701 2.03619 2.54827 + endloop + endfacet + facet normal 0.19163 0.216368 0.957321 + outer loop + vertex 1.13673 2.04082 2.54728 + vertex 1.13701 2.03619 2.54827 + vertex 1.14165 2.03616 2.54735 + endloop + endfacet + facet normal 0.188395 0.212977 0.958722 + outer loop + vertex 1.1415 2.04073 2.54636 + vertex 1.13673 2.04082 2.54728 + vertex 1.14165 2.03616 2.54735 + endloop + endfacet + facet normal 0.187107 0.21612 0.958271 + outer loop + vertex 1.13978 2.04386 2.54599 + vertex 1.1415 2.04073 2.54636 + vertex 1.14455 2.04379 2.54508 + endloop + endfacet + facet normal 0.187239 0.217715 0.957884 + outer loop + vertex 1.15298 2.04211 2.54381 + vertex 1.15169 2.04575 2.54323 + vertex 1.14928 2.04356 2.5442 + endloop + endfacet + facet normal 0.179766 0.22417 0.957827 + outer loop + vertex 1.15682 2.04098 2.54335 + vertex 1.15645 2.04581 2.54229 + vertex 1.15298 2.04211 2.54381 + endloop + endfacet + facet normal 0.176652 0.230574 0.956885 + outer loop + vertex 1.15445 2.03302 2.5457 + vertex 1.15936 2.03333 2.54472 + vertex 1.15454 2.03735 2.54464 + endloop + endfacet + facet normal 0.168069 0.231187 0.958283 + outer loop + vertex 1.15895 2.03806 2.54368 + vertex 1.16121 2.04171 2.54241 + vertex 1.15682 2.04098 2.54335 + endloop + endfacet + facet normal 0.180852 0.245163 0.952464 + outer loop + vertex 1.16936 2.04295 2.5407 + vertex 1.17098 2.04018 2.54111 + vertex 1.17419 2.04329 2.5397 + endloop + endfacet + facet normal 0.164067 0.244926 0.955559 + outer loop + vertex 1.1667 2.03974 2.54197 + vertex 1.16533 2.04448 2.54099 + vertex 1.16121 2.04171 2.54241 + endloop + endfacet + facet normal 0.169676 0.239333 0.955997 + outer loop + vertex 1.16533 2.04448 2.54099 + vertex 1.16386 2.04939 2.54002 + vertex 1.16129 2.04607 2.54131 + endloop + endfacet + facet normal 0.186286 0.23349 0.954348 + outer loop + vertex 1.16386 2.04939 2.54002 + vertex 1.16781 2.05197 2.53862 + vertex 1.16409 2.05348 2.53898 + endloop + endfacet + facet normal 0.176166 0.242516 0.954019 + outer loop + vertex 1.17172 2.05078 2.5382 + vertex 1.17119 2.0556 2.53707 + vertex 1.16781 2.05197 2.53862 + endloop + endfacet + facet normal 0.160545 0.254457 0.953665 + outer loop + vertex 1.17392 2.04788 2.5386 + vertex 1.17613 2.05151 2.53726 + vertex 1.17172 2.05078 2.5382 + endloop + endfacet + facet normal 0.179898 0.25309 0.950569 + outer loop + vertex 1.16936 2.04295 2.5407 + vertex 1.17419 2.04329 2.5397 + vertex 1.16948 2.0472 2.53955 + endloop + endfacet + facet normal 0.149863 0.260951 0.953649 + outer loop + vertex 1.17786 2.04689 2.53826 + vertex 1.17613 2.05151 2.53726 + vertex 1.17392 2.04788 2.5386 + endloop + endfacet + facet normal 0.153651 0.262164 0.952712 + outer loop + vertex 1.17786 2.04689 2.53826 + vertex 1.18171 2.04963 2.53688 + vertex 1.17613 2.05151 2.53726 + endloop + endfacet + facet normal 0.309165 0.179516 0.933912 + outer loop + vertex 1.17388 2.03877 2.54067 + vertex 1.17826 2.03909 2.53916 + vertex 1.17419 2.04329 2.5397 + endloop + endfacet + facet normal 0.157014 0.203595 0.966383 + outer loop + vertex 1.17905 2.0435 2.53878 + vertex 1.18149 2.04574 2.53791 + vertex 1.17786 2.04689 2.53826 + endloop + endfacet + facet normal 0.168326 0.242849 0.955348 + outer loop + vertex 1.18149 2.04574 2.53791 + vertex 1.18171 2.04963 2.53688 + vertex 1.17786 2.04689 2.53826 + endloop + endfacet + facet normal 0.156029 0.269689 0.950222 + outer loop + vertex 1.18171 2.04963 2.53688 + vertex 1.1802 2.05429 2.53581 + vertex 1.17613 2.05151 2.53726 + endloop + endfacet + facet normal 0.161024 0.251986 0.95424 + outer loop + vertex 1.1802 2.05429 2.53581 + vertex 1.17856 2.0592 2.53479 + vertex 1.17605 2.05585 2.53609 + endloop + endfacet + facet normal 0.182025 0.236452 0.954441 + outer loop + vertex 1.17856 2.0592 2.53479 + vertex 1.18271 2.06185 2.53334 + vertex 1.17863 2.06348 2.53371 + endloop + endfacet + facet normal 0.177486 0.245801 0.952933 + outer loop + vertex 1.18677 2.06029 2.53298 + vertex 1.18681 2.06456 2.53188 + vertex 1.18271 2.06185 2.53334 + endloop + endfacet + facet normal 0.169722 0.246212 0.95424 + outer loop + vertex 1.18681 2.06456 2.53188 + vertex 1.18677 2.06029 2.53298 + vertex 1.1914 2.06065 2.53207 + endloop + endfacet + facet normal 0.167504 0.263759 0.949933 + outer loop + vertex 1.18862 2.05744 2.53345 + vertex 1.1914 2.06065 2.53207 + vertex 1.18677 2.06029 2.53298 + endloop + endfacet + facet normal 0.177336 0.27251 0.945669 + outer loop + vertex 1.18424 2.05278 2.53557 + vertex 1.18884 2.05303 2.53463 + vertex 1.1843 2.05697 2.53435 + endloop + endfacet + facet normal 0.156605 0.272878 0.949217 + outer loop + vertex 1.19173 2.05624 2.53328 + vertex 1.1914 2.06065 2.53207 + vertex 1.18862 2.05744 2.53345 + endloop + endfacet + facet normal 0.165111 0.242019 0.95612 + outer loop + vertex 1.19354 2.05332 2.53371 + vertex 1.19603 2.05672 2.53242 + vertex 1.19173 2.05624 2.53328 + endloop + endfacet + facet normal 0.283327 0.213811 0.934885 + outer loop + vertex 1.18873 2.04861 2.53568 + vertex 1.19311 2.04876 2.53432 + vertex 1.18884 2.05303 2.53463 + endloop + endfacet + facet normal 0.192524 0.221813 0.955894 + outer loop + vertex 1.19758 2.05184 2.53324 + vertex 1.19603 2.05672 2.53242 + vertex 1.19354 2.05332 2.53371 + endloop + endfacet + facet normal 0.149995 0.210099 0.966106 + outer loop + vertex 1.19758 2.05184 2.53324 + vertex 1.20161 2.05461 2.53201 + vertex 1.19603 2.05672 2.53242 + endloop + endfacet + facet normal 0.186678 0.15825 0.969592 + outer loop + vertex 1.20164 2.05054 2.53267 + vertex 1.20161 2.05461 2.53201 + vertex 1.19758 2.05184 2.53324 + endloop + endfacet + facet normal 0.227668 0.253209 0.940241 + outer loop + vertex 1.20408 2.05774 2.53073 + vertex 1.20581 2.05491 2.53108 + vertex 1.20875 2.05783 2.52958 + endloop + endfacet + facet normal 0.168875 0.263222 0.94984 + outer loop + vertex 1.20161 2.05461 2.53201 + vertex 1.20008 2.05939 2.53096 + vertex 1.19603 2.05672 2.53242 + endloop + endfacet + facet normal 0.15616 0.28022 0.947149 + outer loop + vertex 1.20008 2.05939 2.53096 + vertex 1.19848 2.06427 2.52978 + vertex 1.19603 2.06098 2.53115 + endloop + endfacet + facet normal 0.177422 0.26021 0.949111 + outer loop + vertex 1.19848 2.06427 2.52978 + vertex 1.20259 2.06692 2.52828 + vertex 1.19854 2.06851 2.5286 + endloop + endfacet + facet normal 0.171619 0.260713 0.95004 + outer loop + vertex 1.20662 2.06533 2.52799 + vertex 1.20668 2.06957 2.52681 + vertex 1.20259 2.06692 2.52828 + endloop + endfacet + facet normal 0.170443 0.268435 0.948099 + outer loop + vertex 1.20844 2.0624 2.52849 + vertex 1.21123 2.06563 2.52708 + vertex 1.20662 2.06533 2.52799 + endloop + endfacet + facet normal 0.224976 0.285306 0.931658 + outer loop + vertex 1.20408 2.05774 2.53073 + vertex 1.20875 2.05783 2.52958 + vertex 1.20415 2.06199 2.52941 + endloop + endfacet + facet normal 0.175397 0.264276 0.948364 + outer loop + vertex 1.2115 2.06112 2.52828 + vertex 1.21123 2.06563 2.52708 + vertex 1.20844 2.0624 2.52849 + endloop + endfacet + facet normal 0.183261 0.193947 0.963743 + outer loop + vertex 1.21345 2.05808 2.52852 + vertex 1.21581 2.06162 2.52736 + vertex 1.2115 2.06112 2.52828 + endloop + endfacet + facet normal 0.327864 0.15756 0.931494 + outer loop + vertex 1.20887 2.0533 2.5303 + vertex 1.21385 2.05332 2.52854 + vertex 1.20875 2.05783 2.52958 + endloop + endfacet + facet normal 0.184722 0.192948 0.963664 + outer loop + vertex 1.21765 2.05672 2.52799 + vertex 1.21581 2.06162 2.52736 + vertex 1.21345 2.05808 2.52852 + endloop + endfacet + facet normal 0.12622 0.172771 0.976841 + outer loop + vertex 1.21765 2.05672 2.52799 + vertex 1.22164 2.05944 2.52699 + vertex 1.21581 2.06162 2.52736 + endloop + endfacet + facet normal 0.142904 0.148921 0.978469 + outer loop + vertex 1.22198 2.0554 2.52756 + vertex 1.22164 2.05944 2.52699 + vertex 1.21765 2.05672 2.52799 + endloop + endfacet + facet normal 0.120003 0.147457 0.981762 + outer loop + vertex 1.22164 2.05944 2.52699 + vertex 1.22198 2.0554 2.52756 + vertex 1.22687 2.05578 2.52691 + endloop + endfacet + facet normal 0.144782 0.183025 0.972389 + outer loop + vertex 1.22604 2.05979 2.52628 + vertex 1.22164 2.05944 2.52699 + vertex 1.22687 2.05578 2.52691 + endloop + endfacet + facet normal 0.113324 0.177339 0.977604 + outer loop + vertex 1.22604 2.05979 2.52628 + vertex 1.22687 2.05578 2.52691 + vertex 1.22943 2.05841 2.52613 + endloop + endfacet + facet normal 0.16551 0.309926 0.936244 + outer loop + vertex 1.22943 2.05841 2.52613 + vertex 1.2288 2.06284 2.52478 + vertex 1.22604 2.05979 2.52628 + endloop + endfacet + facet normal 0.212163 0.313329 0.925641 + outer loop + vertex 1.22943 2.05841 2.52613 + vertex 1.2342 2.05839 2.52505 + vertex 1.2288 2.06284 2.52478 + endloop + endfacet + facet normal 0.215345 0.261925 0.940756 + outer loop + vertex 1.22943 2.05841 2.52613 + vertex 1.23138 2.05586 2.5264 + vertex 1.2342 2.05839 2.52505 + endloop + endfacet + facet normal 0.133419 0.281998 0.950093 + outer loop + vertex 1.22604 2.05979 2.52628 + vertex 1.22395 2.0627 2.52571 + vertex 1.22164 2.05944 2.52699 + endloop + endfacet + facet normal 0.10729 0.183103 0.977222 + outer loop + vertex 1.23138 2.05586 2.5264 + vertex 1.22943 2.05841 2.52613 + vertex 1.22687 2.05578 2.52691 + endloop + endfacet + facet normal 0.328172 -0.362094 0.872463 + outer loop + vertex 1.23437 2.0545 2.52571 + vertex 1.23478 2.05236 2.52467 + vertex 1.23876 2.05407 2.52389 + endloop + endfacet + facet normal 0.0871022 -0.108156 0.990311 + outer loop + vertex 1.25429 2.05299 2.5217 + vertex 1.25157 2.05671 2.52235 + vertex 1.2495 2.05323 2.52215 + endloop + endfacet + facet normal 0.0409058 -0.141658 0.98907 + outer loop + vertex 1.25429 2.05299 2.5217 + vertex 1.25744 2.0552 2.52189 + vertex 1.25157 2.05671 2.52235 + endloop + endfacet + facet normal 0.0880944 -0.207827 0.974191 + outer loop + vertex 1.25832 2.05233 2.5212 + vertex 1.25744 2.0552 2.52189 + vertex 1.25429 2.05299 2.5217 + endloop + endfacet + facet normal 0.0653302 -0.214866 0.974456 + outer loop + vertex 1.25744 2.0552 2.52189 + vertex 1.25832 2.05233 2.5212 + vertex 1.26137 2.05306 2.52116 + endloop + endfacet + facet normal 0.166605 0.179358 0.969574 + outer loop + vertex 1.24714 2.05589 2.52305 + vertex 1.24627 2.06035 2.52237 + vertex 1.24306 2.05676 2.52359 + endloop + endfacet + facet normal 0.164843 0.316651 0.934109 + outer loop + vertex 1.24885 2.06369 2.52088 + vertex 1.25092 2.06084 2.52148 + vertex 1.25321 2.06418 2.51994 + endloop + endfacet + facet normal 0.171734 0.297714 0.939081 + outer loop + vertex 1.24576 2.06488 2.52103 + vertex 1.24152 2.06438 2.52197 + vertex 1.24627 2.06035 2.52237 + endloop + endfacet + facet normal 0.171793 0.297384 0.939175 + outer loop + vertex 1.24576 2.06488 2.52103 + vertex 1.24387 2.06778 2.52046 + vertex 1.24152 2.06438 2.52197 + endloop + endfacet + facet normal 0.17704 0.293814 0.939324 + outer loop + vertex 1.24387 2.06778 2.52046 + vertex 1.23983 2.0693 2.52074 + vertex 1.24152 2.06438 2.52197 + endloop + endfacet + facet normal 0.16237 0.289765 0.943224 + outer loop + vertex 1.24152 2.06438 2.52197 + vertex 1.23983 2.0693 2.52074 + vertex 1.23584 2.06658 2.52227 + endloop + endfacet + facet normal 0.172388 0.254868 0.951486 + outer loop + vertex 1.2358 2.07086 2.52101 + vertex 1.23396 2.07369 2.52059 + vertex 1.23117 2.07058 2.52192 + endloop + endfacet + facet normal 0.163993 0.301184 0.939359 + outer loop + vertex 1.23357 2.06308 2.52379 + vertex 1.23584 2.06658 2.52227 + vertex 1.2315 2.06612 2.52317 + endloop + endfacet + facet normal 0.179257 0.309343 0.933902 + outer loop + vertex 1.2288 2.06284 2.52478 + vertex 1.2315 2.06612 2.52317 + vertex 1.22834 2.0674 2.52335 + endloop + endfacet + facet normal 0.170273 0.305853 0.936729 + outer loop + vertex 1.22395 2.0627 2.52571 + vertex 1.22604 2.05979 2.52628 + vertex 1.2288 2.06284 2.52478 + endloop + endfacet + facet normal 0.154195 0.267645 0.951099 + outer loop + vertex 1.22395 2.0627 2.52571 + vertex 1.21984 2.06435 2.52591 + vertex 1.22164 2.05944 2.52699 + endloop + endfacet + facet normal 0.160613 0.269637 0.949473 + outer loop + vertex 1.22164 2.05944 2.52699 + vertex 1.21984 2.06435 2.52591 + vertex 1.21581 2.06162 2.52736 + endloop + endfacet + facet normal 0.172005 0.264238 0.948995 + outer loop + vertex 1.21123 2.06563 2.52708 + vertex 1.2115 2.06112 2.52828 + vertex 1.21581 2.06162 2.52736 + endloop + endfacet + facet normal 0.174591 0.271155 0.946569 + outer loop + vertex 1.21403 2.06882 2.52566 + vertex 1.21582 2.06596 2.52614 + vertex 1.21833 2.06924 2.52474 + endloop + endfacet + facet normal 0.171348 0.26073 0.950084 + outer loop + vertex 1.20668 2.06957 2.52681 + vertex 1.20662 2.06533 2.52799 + vertex 1.21123 2.06563 2.52708 + endloop + endfacet + facet normal 0.177701 0.251952 0.951285 + outer loop + vertex 1.20917 2.07284 2.52549 + vertex 1.21099 2.07001 2.5259 + vertex 1.21381 2.07313 2.52454 + endloop + endfacet + facet normal 0.177804 0.24817 0.952259 + outer loop + vertex 1.20668 2.06957 2.52681 + vertex 1.20513 2.07442 2.52584 + vertex 1.20102 2.07179 2.5273 + endloop + endfacet + facet normal 0.18322 0.248892 0.951043 + outer loop + vertex 1.20513 2.07442 2.52584 + vertex 1.20355 2.07926 2.52488 + vertex 1.20107 2.07601 2.52621 + endloop + endfacet + facet normal 0.179568 0.257024 0.949576 + outer loop + vertex 1.20355 2.07926 2.52488 + vertex 1.20765 2.08186 2.5234 + vertex 1.2036 2.08345 2.52374 + endloop + endfacet + facet normal 0.180181 0.261124 0.94834 + outer loop + vertex 1.21171 2.08028 2.52307 + vertex 1.21172 2.08448 2.52191 + vertex 1.20765 2.08186 2.5234 + endloop + endfacet + facet normal 0.181198 0.253847 0.95012 + outer loop + vertex 1.21356 2.07745 2.52347 + vertex 1.21634 2.08058 2.5221 + vertex 1.21171 2.08028 2.52307 + endloop + endfacet + facet normal 0.17831 0.24656 0.952583 + outer loop + vertex 1.20917 2.07284 2.52549 + vertex 1.21381 2.07313 2.52454 + vertex 1.20923 2.07703 2.52439 + endloop + endfacet + facet normal 0.183135 0.25216 0.950198 + outer loop + vertex 1.21665 2.07625 2.52319 + vertex 1.21634 2.08058 2.5221 + vertex 1.21356 2.07745 2.52347 + endloop + endfacet + facet normal 0.182049 0.252138 0.950413 + outer loop + vertex 1.21634 2.08058 2.5221 + vertex 1.21665 2.07625 2.52319 + vertex 1.22095 2.07669 2.52225 + endloop + endfacet + facet normal 0.177106 0.254519 0.950712 + outer loop + vertex 1.21403 2.06882 2.52566 + vertex 1.21833 2.06924 2.52474 + vertex 1.21381 2.07313 2.52454 + endloop + endfacet + facet normal 0.176463 0.270518 0.946404 + outer loop + vertex 1.22398 2.06699 2.52433 + vertex 1.22248 2.07187 2.52322 + vertex 1.21833 2.06924 2.52474 + endloop + endfacet + facet normal 0.182693 0.247933 0.951395 + outer loop + vertex 1.21846 2.07343 2.52358 + vertex 1.22095 2.07669 2.52225 + vertex 1.21665 2.07625 2.52319 + endloop + endfacet + facet normal 0.181921 0.249653 0.951093 + outer loop + vertex 1.2265 2.0703 2.52286 + vertex 1.22659 2.07451 2.52174 + vertex 1.22248 2.07187 2.52322 + endloop + endfacet + facet normal 0.1807 0.250566 0.951086 + outer loop + vertex 1.22094 2.08086 2.52115 + vertex 1.21634 2.08058 2.5221 + vertex 1.22095 2.07669 2.52225 + endloop + endfacet + facet normal 0.18146 0.261235 0.948066 + outer loop + vertex 1.21907 2.08369 2.52073 + vertex 1.22094 2.08086 2.52115 + vertex 1.22325 2.08404 2.51983 + endloop + endfacet + facet normal 0.177828 0.268853 0.946623 + outer loop + vertex 1.22325 2.08404 2.51983 + vertex 1.22662 2.08634 2.51855 + vertex 1.22336 2.08801 2.51869 + endloop + endfacet + facet normal 0.176729 0.27071 0.9463 + outer loop + vertex 1.22639 2.09084 2.5173 + vertex 1.22662 2.08634 2.51855 + vertex 1.23122 2.08672 2.51758 + endloop + endfacet + facet normal 0.174857 0.254878 0.951032 + outer loop + vertex 1.22904 2.07776 2.52044 + vertex 1.23372 2.07796 2.51953 + vertex 1.22891 2.08209 2.51931 + endloop + endfacet + facet normal 0.173114 0.266545 0.948148 + outer loop + vertex 1.23351 2.08247 2.51836 + vertex 1.23693 2.08477 2.51709 + vertex 1.23122 2.08672 2.51758 + endloop + endfacet + facet normal 0.175488 0.275113 0.94526 + outer loop + vertex 1.23926 2.08795 2.51574 + vertex 1.24115 2.08513 2.51621 + vertex 1.2439 2.08821 2.51481 + endloop + endfacet + facet normal 0.174989 0.27254 0.946098 + outer loop + vertex 1.23693 2.08477 2.51709 + vertex 1.23519 2.08949 2.51605 + vertex 1.23122 2.08672 2.51758 + endloop + endfacet + facet normal 0.176091 0.273305 0.945672 + outer loop + vertex 1.23519 2.08949 2.51605 + vertex 1.2335 2.0943 2.51497 + vertex 1.23108 2.09105 2.51636 + endloop + endfacet + facet normal 0.181675 0.270743 0.945353 + outer loop + vertex 1.2335 2.0943 2.51497 + vertex 1.23757 2.09689 2.51345 + vertex 1.23351 2.09847 2.51378 + endloop + endfacet + facet normal 0.181349 0.274789 0.944248 + outer loop + vertex 1.24164 2.09531 2.51313 + vertex 1.24161 2.09949 2.51192 + vertex 1.23757 2.09689 2.51345 + endloop + endfacet + facet normal 0.179264 0.27876 0.943482 + outer loop + vertex 1.24353 2.0925 2.5136 + vertex 1.24627 2.09558 2.51217 + vertex 1.24164 2.09531 2.51313 + endloop + endfacet + facet normal 0.175281 0.276982 0.944753 + outer loop + vertex 1.23926 2.08795 2.51574 + vertex 1.2439 2.08821 2.51481 + vertex 1.23922 2.0921 2.51453 + endloop + endfacet + facet normal 0.177182 0.280546 0.943345 + outer loop + vertex 1.24665 2.09129 2.51337 + vertex 1.24627 2.09558 2.51217 + vertex 1.24353 2.0925 2.5136 + endloop + endfacet + facet normal 0.175521 0.282426 0.943095 + outer loop + vertex 1.24856 2.08849 2.51385 + vertex 1.25096 2.09171 2.51244 + vertex 1.24665 2.09129 2.51337 + endloop + endfacet + facet normal 0.172579 0.276395 0.945422 + outer loop + vertex 1.24426 2.0839 2.516 + vertex 1.24858 2.08435 2.51508 + vertex 1.2439 2.08821 2.51481 + endloop + endfacet + facet normal 0.174436 0.28322 0.943058 + outer loop + vertex 1.25263 2.08697 2.51356 + vertex 1.25096 2.09171 2.51244 + vertex 1.24856 2.08849 2.51385 + endloop + endfacet + facet normal 0.171829 0.278846 0.944838 + outer loop + vertex 1.25418 2.08233 2.51465 + vertex 1.25668 2.08546 2.51327 + vertex 1.25263 2.08697 2.51356 + endloop + endfacet + facet normal 0.173386 0.269862 0.94716 + outer loop + vertex 1.25023 2.07964 2.51612 + vertex 1.24858 2.08435 2.51508 + vertex 1.24618 2.08107 2.51645 + endloop + endfacet + facet normal 0.166508 0.251882 0.953326 + outer loop + vertex 1.25417 2.07831 2.51578 + vertex 1.25023 2.07964 2.51612 + vertex 1.25185 2.0751 2.51704 + endloop + endfacet + facet normal 0.173741 0.267919 0.947646 + outer loop + vertex 1.25418 2.08233 2.51465 + vertex 1.25835 2.07883 2.51487 + vertex 1.25846 2.08272 2.51375 + endloop + endfacet + facet normal 0.173178 0.252897 0.951868 + outer loop + vertex 1.25835 2.07883 2.51487 + vertex 1.25994 2.0743 2.51579 + vertex 1.26388 2.07712 2.51432 + endloop + endfacet + facet normal 0.167452 0.254572 0.952446 + outer loop + vertex 1.26148 2.06954 2.51679 + vertex 1.25994 2.0743 2.51579 + vertex 1.25594 2.0716 2.51721 + endloop + endfacet + facet normal 0.169356 0.249835 0.953363 + outer loop + vertex 1.25607 2.07565 2.51614 + vertex 1.25417 2.07831 2.51578 + vertex 1.25185 2.0751 2.51704 + endloop + endfacet + facet normal 0.171435 0.245943 0.954003 + outer loop + vertex 1.25162 2.07118 2.51809 + vertex 1.25185 2.0751 2.51704 + vertex 1.24844 2.07264 2.51828 + endloop + endfacet + facet normal 0.16947 0.248505 0.95369 + outer loop + vertex 1.24844 2.07264 2.51828 + vertex 1.25185 2.0751 2.51704 + vertex 1.24626 2.07678 2.51759 + endloop + endfacet + facet normal 0.171544 0.249494 0.953061 + outer loop + vertex 1.24844 2.07264 2.51828 + vertex 1.24626 2.07678 2.51759 + vertex 1.24383 2.07213 2.51925 + endloop + endfacet + facet normal 0.16792 0.299255 0.939281 + outer loop + vertex 1.24885 2.06369 2.52088 + vertex 1.25321 2.06418 2.51994 + vertex 1.24857 2.06812 2.51952 + endloop + endfacet + facet normal 0.16147 0.26763 0.949895 + outer loop + vertex 1.25734 2.06685 2.51831 + vertex 1.25594 2.0716 2.51721 + vertex 1.25329 2.06841 2.51856 + endloop + endfacet + facet normal 0.178081 0.316024 0.931888 + outer loop + vertex 1.25905 2.06192 2.51965 + vertex 1.26143 2.06527 2.51807 + vertex 1.25734 2.06685 2.51831 + endloop + endfacet + facet normal 0.158673 0.320737 0.933783 + outer loop + vertex 1.25518 2.05937 2.52126 + vertex 1.25321 2.06418 2.51994 + vertex 1.25092 2.06084 2.52148 + endloop + endfacet + facet normal 0.118541 0.210253 0.970434 + outer loop + vertex 1.25938 2.05782 2.52109 + vertex 1.25518 2.05937 2.52126 + vertex 1.25744 2.0552 2.52189 + endloop + endfacet + facet normal 0.348977 -0.371295 0.860439 + outer loop + vertex 1.26414 2.0542 2.52066 + vertex 1.26442 2.05216 2.51966 + vertex 1.26844 2.05394 2.5188 + endloop + endfacet + facet normal 0.185672 0.222035 0.957197 + outer loop + vertex 1.27295 2.05689 2.51837 + vertex 1.27104 2.06166 2.51763 + vertex 1.26871 2.05816 2.51889 + endloop + endfacet + facet normal 0.0892646 -0.140191 0.986092 + outer loop + vertex 1.28353 2.0517 2.51645 + vertex 1.28207 2.05576 2.51715 + vertex 1.2794 2.05265 2.51695 + endloop + endfacet + facet normal -0.0172574 -0.178101 0.983861 + outer loop + vertex 1.28207 2.05576 2.51715 + vertex 1.28353 2.0517 2.51645 + vertex 1.28799 2.05173 2.51653 + endloop + endfacet + facet normal 0.153046 0.163168 0.974655 + outer loop + vertex 1.27729 2.05553 2.51791 + vertex 1.2769 2.05963 2.51729 + vertex 1.27295 2.05689 2.51837 + endloop + endfacet + facet normal 0.151233 0.28606 0.946202 + outer loop + vertex 1.28108 2.06015 2.51646 + vertex 1.27906 2.06298 2.51593 + vertex 1.2769 2.05963 2.51729 + endloop + endfacet + facet normal 0.1788 0.303747 0.935825 + outer loop + vertex 1.27906 2.06298 2.51593 + vertex 1.28108 2.06015 2.51646 + vertex 1.28368 2.06328 2.51495 + endloop + endfacet + facet normal 0.182222 0.302518 0.935563 + outer loop + vertex 1.28368 2.06328 2.51495 + vertex 1.28837 2.05936 2.5153 + vertex 1.28836 2.06357 2.51394 + endloop + endfacet + facet normal 0.120106 0.199791 0.97245 + outer loop + vertex 1.28647 2.05603 2.51655 + vertex 1.2842 2.05892 2.51624 + vertex 1.28207 2.05576 2.51715 + endloop + endfacet + facet normal 0.158791 0.268824 0.95001 + outer loop + vertex 1.28837 2.05936 2.5153 + vertex 1.29051 2.05466 2.51627 + vertex 1.29397 2.05733 2.51494 + endloop + endfacet + facet normal 0.13236 0.0409387 0.990356 + outer loop + vertex 1.28647 2.05603 2.51655 + vertex 1.28207 2.05576 2.51715 + vertex 1.28799 2.05173 2.51653 + endloop + endfacet + facet normal 0.126042 0.307777 0.943073 + outer loop + vertex 1.29051 2.05466 2.51627 + vertex 1.29434 2.05335 2.51619 + vertex 1.29397 2.05733 2.51494 + endloop + endfacet + facet normal 0.157129 0.251373 0.955051 + outer loop + vertex 1.29434 2.05335 2.51619 + vertex 1.29661 2.05096 2.51645 + vertex 1.2985 2.05385 2.51537 + endloop + endfacet + facet normal 0.159413 0.249882 0.955064 + outer loop + vertex 1.30037 2.04984 2.51611 + vertex 1.2985 2.05385 2.51537 + vertex 1.29661 2.05096 2.51645 + endloop + endfacet + facet normal 0.148498 0.325662 0.933752 + outer loop + vertex 1.2985 2.05385 2.51537 + vertex 1.30246 2.05671 2.51375 + vertex 1.29835 2.05796 2.51396 + endloop + endfacet + facet normal 0.146565 0.311588 0.938846 + outer loop + vertex 1.30657 2.05548 2.51351 + vertex 1.30649 2.05979 2.5121 + vertex 1.30246 2.05671 2.51375 + endloop + endfacet + facet normal 0.169676 0.236099 0.9568 + outer loop + vertex 1.30867 2.05272 2.51382 + vertex 1.31096 2.05634 2.51252 + vertex 1.30657 2.05548 2.51351 + endloop + endfacet + facet normal 0.368713 0.144968 0.918169 + outer loop + vertex 1.30391 2.04855 2.51551 + vertex 1.30833 2.04853 2.51374 + vertex 1.30418 2.05204 2.51485 + endloop + endfacet + facet normal 0.188677 0.223828 0.956191 + outer loop + vertex 1.31278 2.05172 2.51324 + vertex 1.31096 2.05634 2.51252 + vertex 1.30867 2.05272 2.51382 + endloop + endfacet + facet normal 0.160499 0.160029 0.973977 + outer loop + vertex 1.31697 2.05055 2.51275 + vertex 1.31657 2.0547 2.51213 + vertex 1.31278 2.05172 2.51324 + endloop + endfacet + facet normal 0.121396 0.15716 0.980084 + outer loop + vertex 1.31657 2.0547 2.51213 + vertex 1.31697 2.05055 2.51275 + vertex 1.32131 2.05121 2.5121 + endloop + endfacet + facet normal -0.119276 0.0746683 0.990049 + outer loop + vertex 1.32781 2.04661 2.5122 + vertex 1.32682 2.04977 2.51185 + vertex 1.32443 2.04649 2.51181 + endloop + endfacet + facet normal 0.0597724 0.130201 0.989684 + outer loop + vertex 1.32682 2.04977 2.51185 + vertex 1.32781 2.04661 2.5122 + vertex 1.33138 2.04675 2.51197 + endloop + endfacet + facet normal 0.108926 0.203581 0.97298 + outer loop + vertex 1.33067 2.05043 2.51128 + vertex 1.32682 2.04977 2.51185 + vertex 1.33138 2.04675 2.51197 + endloop + endfacet + facet normal 0.0913728 0.200678 0.975387 + outer loop + vertex 1.33067 2.05043 2.51128 + vertex 1.33138 2.04675 2.51197 + vertex 1.33486 2.0492 2.51114 + endloop + endfacet + facet normal 0.0830908 0.21189 0.973755 + outer loop + vertex 1.33718 2.04512 2.51183 + vertex 1.33486 2.0492 2.51114 + vertex 1.33138 2.04675 2.51197 + endloop + endfacet + facet normal -0.0216151 -0.163945 0.986233 + outer loop + vertex 1.33386 2.04308 2.51142 + vertex 1.33718 2.04512 2.51183 + vertex 1.33138 2.04675 2.51197 + endloop + endfacet + facet normal 0.0153903 -0.221835 0.974963 + outer loop + vertex 1.338 2.04216 2.51114 + vertex 1.33718 2.04512 2.51183 + vertex 1.33386 2.04308 2.51142 + endloop + endfacet + facet normal 0.0254527 -0.219133 0.975363 + outer loop + vertex 1.33718 2.04512 2.51183 + vertex 1.338 2.04216 2.51114 + vertex 1.34113 2.04289 2.51122 + endloop + endfacet + facet normal 0.102119 -0.0879151 0.99088 + outer loop + vertex 1.34116 2.04535 2.51144 + vertex 1.33718 2.04512 2.51183 + vertex 1.34113 2.04289 2.51122 + endloop + endfacet + facet normal 0.199932 -0.0877522 0.975872 + outer loop + vertex 1.34116 2.04535 2.51144 + vertex 1.34113 2.04289 2.51122 + vertex 1.34391 2.044 2.51075 + endloop + endfacet + facet normal 0.32445 0.192224 0.926165 + outer loop + vertex 1.34391 2.044 2.51075 + vertex 1.34377 2.04785 2.51001 + vertex 1.34116 2.04535 2.51144 + endloop + endfacet + facet normal 0.439514 0.187404 0.878469 + outer loop + vertex 1.34391 2.044 2.51075 + vertex 1.34821 2.04336 2.50874 + vertex 1.34377 2.04785 2.51001 + endloop + endfacet + facet normal 0.2189 -0.0577993 0.974034 + outer loop + vertex 1.34377 2.04785 2.51001 + vertex 1.34821 2.04336 2.50874 + vertex 1.34853 2.04803 2.50895 + endloop + endfacet + facet normal 0.111734 -0.0512557 0.992415 + outer loop + vertex 1.34821 2.04336 2.50874 + vertex 1.35271 2.04692 2.50842 + vertex 1.34853 2.04803 2.50895 + endloop + endfacet + facet normal 0.349667 -0.363593 0.863443 + outer loop + vertex 1.34391 2.044 2.51075 + vertex 1.34417 2.04174 2.5097 + vertex 1.34821 2.04336 2.50874 + endloop + endfacet + facet normal 0.299197 -0.375785 0.877078 + outer loop + vertex 1.34417 2.04174 2.5097 + vertex 1.34391 2.044 2.51075 + vertex 1.34113 2.04289 2.51122 + endloop + endfacet + facet normal 0.163747 0.214887 0.962814 + outer loop + vertex 1.32072 2.05548 2.51125 + vertex 1.31657 2.0547 2.51213 + vertex 1.32131 2.05121 2.5121 + endloop + endfacet + facet normal 0.164335 0.305019 0.93806 + outer loop + vertex 1.31863 2.05818 2.51074 + vertex 1.32072 2.05548 2.51125 + vertex 1.32298 2.05892 2.50974 + endloop + endfacet + facet normal 0.159499 0.297807 0.941207 + outer loop + vertex 1.32298 2.05892 2.50974 + vertex 1.32724 2.06168 2.50814 + vertex 1.32321 2.06314 2.50836 + endloop + endfacet + facet normal 0.138955 0.283773 0.94877 + outer loop + vertex 1.33288 2.05767 2.50843 + vertex 1.33603 2.06072 2.50706 + vertex 1.3312 2.06039 2.50786 + endloop + endfacet + facet normal 0.14575 0.315281 0.937739 + outer loop + vertex 1.32849 2.05305 2.51072 + vertex 1.33275 2.05366 2.50985 + vertex 1.32849 2.05714 2.50935 + endloop + endfacet + facet normal 0.128982 0.29341 0.947246 + outer loop + vertex 1.3362 2.05618 2.50844 + vertex 1.33603 2.06072 2.50706 + vertex 1.33288 2.05767 2.50843 + endloop + endfacet + facet normal 0.128102 0.329873 0.935293 + outer loop + vertex 1.33486 2.0492 2.51114 + vertex 1.33275 2.05366 2.50985 + vertex 1.33067 2.05043 2.51128 + endloop + endfacet + facet normal 0.0836269 0.212176 0.973647 + outer loop + vertex 1.33912 2.04777 2.51108 + vertex 1.33486 2.0492 2.51114 + vertex 1.33718 2.04512 2.51183 + endloop + endfacet + facet normal 0.0835827 0.212208 0.973644 + outer loop + vertex 1.34116 2.04535 2.51144 + vertex 1.33912 2.04777 2.51108 + vertex 1.33718 2.04512 2.51183 + endloop + endfacet + facet normal 0.210013 0.311621 0.926708 + outer loop + vertex 1.33912 2.04777 2.51108 + vertex 1.34116 2.04535 2.51144 + vertex 1.34377 2.04785 2.51001 + endloop + endfacet + facet normal 0.127426 0.331237 0.934903 + outer loop + vertex 1.33866 2.05194 2.50961 + vertex 1.34097 2.05671 2.5076 + vertex 1.3362 2.05618 2.50844 + endloop + endfacet + facet normal 0.114867 0.300405 0.94687 + outer loop + vertex 1.34906 2.05837 2.50593 + vertex 1.35104 2.05584 2.50649 + vertex 1.3534 2.05932 2.5051 + endloop + endfacet + facet normal 0.1326 0.303326 0.943616 + outer loop + vertex 1.34674 2.05505 2.50733 + vertex 1.34501 2.0596 2.50611 + vertex 1.34097 2.05671 2.5076 + endloop + endfacet + facet normal 0.131054 0.275016 0.952466 + outer loop + vertex 1.34501 2.0596 2.50611 + vertex 1.34334 2.06429 2.50498 + vertex 1.34087 2.06105 2.50626 + endloop + endfacet + facet normal 0.141418 0.270522 0.95227 + outer loop + vertex 1.34334 2.06429 2.50498 + vertex 1.34748 2.06693 2.50362 + vertex 1.34335 2.06834 2.50383 + endloop + endfacet + facet normal 0.135296 0.277912 0.951031 + outer loop + vertex 1.35156 2.06571 2.50339 + vertex 1.35158 2.06982 2.50219 + vertex 1.34748 2.06693 2.50362 + endloop + endfacet + facet normal 0.119834 0.2782 0.953019 + outer loop + vertex 1.35353 2.06322 2.50387 + vertex 1.35597 2.06671 2.50255 + vertex 1.35156 2.06571 2.50339 + endloop + endfacet + facet normal 0.118346 0.287652 0.950395 + outer loop + vertex 1.34906 2.05837 2.50593 + vertex 1.3534 2.05932 2.5051 + vertex 1.34907 2.0624 2.50471 + endloop + endfacet + facet normal 0.106934 0.286826 0.951996 + outer loop + vertex 1.35752 2.06243 2.50366 + vertex 1.35597 2.06671 2.50255 + vertex 1.35353 2.06322 2.50387 + endloop + endfacet + facet normal 0.0945066 0.275136 0.956749 + outer loop + vertex 1.35976 2.05446 2.50598 + vertex 1.35499 2.05507 2.50628 + vertex 1.35616 2.05081 2.50739 + endloop + endfacet + facet normal 0.116199 0.280125 0.952905 + outer loop + vertex 1.35616 2.05081 2.50739 + vertex 1.35499 2.05507 2.50628 + vertex 1.35099 2.05174 2.50775 + endloop + endfacet + facet normal 0.0961101 0.30005 0.94907 + outer loop + vertex 1.35855 2.05843 2.50482 + vertex 1.36226 2.06158 2.50345 + vertex 1.35752 2.06243 2.50366 + endloop + endfacet + facet normal 0.0815527 0.30103 0.950121 + outer loop + vertex 1.36623 2.06062 2.50341 + vertex 1.36652 2.06455 2.50214 + vertex 1.36226 2.06158 2.50345 + endloop + endfacet + facet normal 0.0643043 0.302547 0.950963 + outer loop + vertex 1.36652 2.06455 2.50214 + vertex 1.36623 2.06062 2.50341 + vertex 1.37094 2.06161 2.50278 + endloop + endfacet + facet normal 0.0484602 0.310618 0.949299 + outer loop + vertex 1.37352 2.05705 2.50414 + vertex 1.37638 2.06115 2.50265 + vertex 1.37094 2.06161 2.50278 + endloop + endfacet + facet normal 0.0636476 0.32021 0.945206 + outer loop + vertex 1.36458 2.05405 2.50571 + vertex 1.36948 2.05361 2.50552 + vertex 1.36803 2.0575 2.50431 + endloop + endfacet + facet normal 0.0529242 0.343914 0.937509 + outer loop + vertex 1.37358 2.05311 2.50548 + vertex 1.36948 2.05361 2.50552 + vertex 1.37124 2.04941 2.50696 + endloop + endfacet + facet normal 0.040586 0.319989 0.946551 + outer loop + vertex 1.37352 2.05705 2.50414 + vertex 1.37802 2.05433 2.50487 + vertex 1.37823 2.0581 2.50359 + endloop + endfacet + facet normal 0.0426289 0.349777 0.935863 + outer loop + vertex 1.37568 2.05083 2.50623 + vertex 1.37358 2.05311 2.50548 + vertex 1.37124 2.04941 2.50696 + endloop + endfacet + facet normal 0.0392968 0.358578 0.932672 + outer loop + vertex 1.37568 2.05083 2.50623 + vertex 1.37124 2.04941 2.50696 + vertex 1.37586 2.0466 2.50785 + endloop + endfacet + facet normal 0.0781147 0.270374 0.959581 + outer loop + vertex 1.38329 2.04247 2.50859 + vertex 1.38622 2.04563 2.50746 + vertex 1.38133 2.04606 2.50774 + endloop + endfacet + facet normal 0.382835 0.353662 0.85344 + outer loop + vertex 1.37956 2.0379 2.51031 + vertex 1.38316 2.03802 2.50865 + vertex 1.37841 2.04121 2.50946 + endloop + endfacet + facet normal 0.396353 -0.393619 0.829439 + outer loop + vertex 1.37956 2.0379 2.51031 + vertex 1.37986 2.03657 2.50953 + vertex 1.38316 2.03802 2.50865 + endloop + endfacet + facet normal 0.467219 -0.363735 0.805855 + outer loop + vertex 1.37986 2.03657 2.50953 + vertex 1.37956 2.0379 2.51031 + vertex 1.37853 2.03689 2.51045 + endloop + endfacet + facet normal 0.125772 0.228357 0.965419 + outer loop + vertex 1.38747 2.04131 2.50832 + vertex 1.38622 2.04563 2.50746 + vertex 1.38329 2.04247 2.50859 + endloop + endfacet + facet normal 0.0704149 0.226077 0.971561 + outer loop + vertex 1.39149 2.04036 2.50825 + vertex 1.39133 2.04464 2.50727 + vertex 1.38747 2.04131 2.50832 + endloop + endfacet + facet normal 0.0794143 0.119645 0.989635 + outer loop + vertex 1.39367 2.03778 2.50839 + vertex 1.39574 2.04155 2.50776 + vertex 1.39149 2.04036 2.50825 + endloop + endfacet + facet normal 0.0441858 0.138972 0.98931 + outer loop + vertex 1.39772 2.03708 2.5083 + vertex 1.39574 2.04155 2.50776 + vertex 1.39367 2.03778 2.50839 + endloop + endfacet + facet normal 0.0284043 0.165895 0.985734 + outer loop + vertex 1.40261 2.0364 2.50828 + vertex 1.40109 2.04052 2.50763 + vertex 1.39772 2.03708 2.5083 + endloop + endfacet + facet normal 0.0689942 0.177859 0.981634 + outer loop + vertex 1.40678 2.03571 2.50811 + vertex 1.40649 2.03959 2.50743 + vertex 1.40261 2.0364 2.50828 + endloop + endfacet + facet normal 0.0902158 0.179123 0.979682 + outer loop + vertex 1.40649 2.03959 2.50743 + vertex 1.40678 2.03571 2.50811 + vertex 1.41127 2.03677 2.5075 + endloop + endfacet + facet normal -0.0255743 -0.0511361 0.998364 + outer loop + vertex 1.4195 2.03147 2.50705 + vertex 1.41681 2.03569 2.5072 + vertex 1.41413 2.03273 2.50698 + endloop + endfacet + facet normal -0.00552024 -0.0383918 0.999248 + outer loop + vertex 1.4195 2.03147 2.50705 + vertex 1.42187 2.03465 2.50719 + vertex 1.41681 2.03569 2.5072 + endloop + endfacet + facet normal 0.0560002 0.260181 0.963935 + outer loop + vertex 1.42187 2.03465 2.50719 + vertex 1.41969 2.03891 2.50616 + vertex 1.41681 2.03569 2.5072 + endloop + endfacet + facet normal -0.152831 0.0720853 0.98562 + outer loop + vertex 1.42274 2.03157 2.50755 + vertex 1.42187 2.03465 2.50719 + vertex 1.4195 2.03147 2.50705 + endloop + endfacet + facet normal 0.0375565 0.126781 0.991219 + outer loop + vertex 1.42187 2.03465 2.50719 + vertex 1.42274 2.03157 2.50755 + vertex 1.42619 2.03199 2.50736 + endloop + endfacet + facet normal 0.0873889 0.233485 0.968426 + outer loop + vertex 1.41969 2.03891 2.50616 + vertex 1.41486 2.03994 2.50635 + vertex 1.41681 2.03569 2.5072 + endloop + endfacet + facet normal 0.12524 0.238048 0.963145 + outer loop + vertex 1.41076 2.04077 2.50658 + vertex 1.40649 2.03959 2.50743 + vertex 1.41127 2.03677 2.5075 + endloop + endfacet + facet normal 0.116048 0.345158 0.931342 + outer loop + vertex 1.40858 2.04315 2.50597 + vertex 1.41076 2.04077 2.50658 + vertex 1.41297 2.04425 2.50501 + endloop + endfacet + facet normal 0.101546 0.342686 0.933946 + outer loop + vertex 1.41297 2.04425 2.50501 + vertex 1.41723 2.04724 2.50345 + vertex 1.41311 2.0483 2.50352 + endloop + endfacet + facet normal 0.0942159 0.308349 0.946596 + outer loop + vertex 1.42207 2.04631 2.50327 + vertex 1.421 2.05035 2.50207 + vertex 1.41723 2.04724 2.50345 + endloop + endfacet + facet normal 0.10307 0.329923 0.938364 + outer loop + vertex 1.4236 2.04205 2.5046 + vertex 1.42613 2.04556 2.50309 + vertex 1.42207 2.04631 2.50327 + endloop + endfacet + facet normal 0.1077 0.335115 0.936001 + outer loop + vertex 1.41486 2.03994 2.50635 + vertex 1.41969 2.03891 2.50616 + vertex 1.41831 2.04313 2.50481 + endloop + endfacet + facet normal 0.0824489 0.272394 0.958647 + outer loop + vertex 1.42359 2.03805 2.50607 + vertex 1.41969 2.03891 2.50616 + vertex 1.42187 2.03465 2.50719 + endloop + endfacet + facet normal 0.104353 0.342521 0.933697 + outer loop + vertex 1.4236 2.04205 2.5046 + vertex 1.4279 2.03914 2.50519 + vertex 1.42807 2.04317 2.5037 + endloop + endfacet + facet normal 0.0543705 0.285941 0.956703 + outer loop + vertex 1.42568 2.03565 2.50667 + vertex 1.42359 2.03805 2.50607 + vertex 1.42187 2.03465 2.50719 + endloop + endfacet + facet normal 0.105925 0.332468 0.937147 + outer loop + vertex 1.4279 2.03914 2.50519 + vertex 1.42975 2.03487 2.5065 + vertex 1.43325 2.03806 2.50497 + endloop + endfacet + facet normal 0.080772 0.196029 0.977266 + outer loop + vertex 1.42568 2.03565 2.50667 + vertex 1.42187 2.03465 2.50719 + vertex 1.42619 2.03199 2.50736 + endloop + endfacet + facet normal 0.0770197 0.213464 0.97391 + outer loop + vertex 1.43471 2.03395 2.50631 + vertex 1.42975 2.03487 2.5065 + vertex 1.43163 2.03107 2.50718 + endloop + endfacet + facet normal 0.143147 0.29526 0.944633 + outer loop + vertex 1.43873 2.03316 2.50614 + vertex 1.44114 2.03095 2.50647 + vertex 1.44293 2.03416 2.50519 + endloop + endfacet + facet normal 0.0787283 0.211712 0.974156 + outer loop + vertex 1.43712 2.03019 2.50693 + vertex 1.43471 2.03395 2.50631 + vertex 1.43163 2.03107 2.50718 + endloop + endfacet + facet normal 0.0988698 0.339397 0.935433 + outer loop + vertex 1.42975 2.03487 2.5065 + vertex 1.43471 2.03395 2.50631 + vertex 1.43325 2.03806 2.50497 + endloop + endfacet + facet normal 0.113177 0.34176 0.932948 + outer loop + vertex 1.43325 2.03806 2.50497 + vertex 1.43701 2.04131 2.50332 + vertex 1.43212 2.04232 2.50355 + endloop + endfacet + facet normal 0.113144 0.303811 0.94599 + outer loop + vertex 1.44102 2.04048 2.50311 + vertex 1.44122 2.04447 2.50181 + vertex 1.43701 2.04131 2.50332 + endloop + endfacet + facet normal 0.104216 0.322822 0.940704 + outer loop + vertex 1.4429 2.03808 2.50372 + vertex 1.44545 2.04161 2.50223 + vertex 1.44102 2.04048 2.50311 + endloop + endfacet + facet normal 0.125987 0.351315 0.927742 + outer loop + vertex 1.43873 2.03316 2.50614 + vertex 1.44293 2.03416 2.50519 + vertex 1.43855 2.03698 2.50472 + endloop + endfacet + facet normal 0.111011 0.318243 0.941487 + outer loop + vertex 1.44691 2.03729 2.50352 + vertex 1.44545 2.04161 2.50223 + vertex 1.4429 2.03808 2.50372 + endloop + endfacet + facet normal 0.140193 0.296883 0.944567 + outer loop + vertex 1.44533 2.03002 2.50613 + vertex 1.44293 2.03416 2.50519 + vertex 1.44114 2.03095 2.50647 + endloop + endfacet + facet normal 0.0388322 0.0415925 0.99838 + outer loop + vertex 1.45011 2.02894 2.50599 + vertex 1.44533 2.03002 2.50613 + vertex 1.44845 2.02605 2.50618 + endloop + endfacet + facet normal -0.064629 0.100809 0.992804 + outer loop + vertex 1.45293 2.0256 2.50652 + vertex 1.45011 2.02894 2.50599 + vertex 1.44845 2.02605 2.50618 + endloop + endfacet + facet normal 0.0382353 0.185953 0.981814 + outer loop + vertex 1.4539 2.028 2.50602 + vertex 1.45011 2.02894 2.50599 + vertex 1.45293 2.0256 2.50652 + endloop + endfacet + facet normal 0.0755053 0.334965 0.939201 + outer loop + vertex 1.45011 2.02894 2.50599 + vertex 1.4539 2.028 2.50602 + vertex 1.45348 2.03186 2.50468 + endloop + endfacet + facet normal 0.115161 0.334154 0.935457 + outer loop + vertex 1.44821 2.03304 2.50488 + vertex 1.45177 2.03631 2.50327 + vertex 1.44691 2.03729 2.50352 + endloop + endfacet + facet normal 0.107685 0.310152 0.944569 + outer loop + vertex 1.45585 2.03545 2.50309 + vertex 1.45605 2.03952 2.50173 + vertex 1.45177 2.03631 2.50327 + endloop + endfacet + facet normal 0.0944309 0.335924 0.937143 + outer loop + vertex 1.45789 2.03287 2.50381 + vertex 1.46046 2.03645 2.50227 + vertex 1.45585 2.03545 2.50309 + endloop + endfacet + facet normal 0.0987515 0.336588 0.93646 + outer loop + vertex 1.4539 2.028 2.50602 + vertex 1.45809 2.02875 2.50531 + vertex 1.45348 2.03186 2.50468 + endloop + endfacet + facet normal 0.111749 0.280002 0.953473 + outer loop + vertex 1.4539 2.028 2.50602 + vertex 1.45625 2.02579 2.5064 + vertex 1.45809 2.02875 2.50531 + endloop + endfacet + facet normal 0.0238883 0.191618 0.981179 + outer loop + vertex 1.45625 2.02579 2.5064 + vertex 1.4539 2.028 2.50602 + vertex 1.45293 2.0256 2.50652 + endloop + endfacet + facet normal 0.041604 -0.121702 0.991694 + outer loop + vertex 1.45625 2.02579 2.5064 + vertex 1.45293 2.0256 2.50652 + vertex 1.45714 2.02318 2.50604 + endloop + endfacet + facet normal 0.0319063 -0.124987 0.991645 + outer loop + vertex 1.45625 2.02579 2.5064 + vertex 1.45714 2.02318 2.50604 + vertex 1.46007 2.02486 2.50616 + endloop + endfacet + facet normal 0.0321435 -0.125396 0.991586 + outer loop + vertex 1.46125 2.02256 2.50583 + vertex 1.46007 2.02486 2.50616 + vertex 1.45714 2.02318 2.50604 + endloop + endfacet + facet normal 0.098437 0.333281 0.937675 + outer loop + vertex 1.46213 2.03179 2.50375 + vertex 1.46046 2.03645 2.50227 + vertex 1.45789 2.03287 2.50381 + endloop + endfacet + facet normal 0.125454 0.271752 0.954155 + outer loop + vertex 1.46007 2.02486 2.50616 + vertex 1.45809 2.02875 2.50531 + vertex 1.45625 2.02579 2.5064 + endloop + endfacet + facet normal 0.120262 -0.0799653 0.989516 + outer loop + vertex 1.46367 2.02372 2.50563 + vertex 1.46007 2.02486 2.50616 + vertex 1.46125 2.02256 2.50583 + endloop + endfacet + facet normal 0.277172 -0.426623 0.860911 + outer loop + vertex 1.464 2.02198 2.50466 + vertex 1.46367 2.02372 2.50563 + vertex 1.46125 2.02256 2.50583 + endloop + endfacet + facet normal 0.328189 -0.41095 0.850536 + outer loop + vertex 1.46367 2.02372 2.50563 + vertex 1.464 2.02198 2.50466 + vertex 1.46811 2.02373 2.50392 + endloop + endfacet + facet normal 0.0968624 0.284859 0.953663 + outer loop + vertex 1.46392 2.02717 2.50495 + vertex 1.46638 2.03064 2.50366 + vertex 1.46213 2.03179 2.50375 + endloop + endfacet + facet normal 0.124219 0.328463 0.936313 + outer loop + vertex 1.46627 2.03493 2.50217 + vertex 1.46638 2.03064 2.50366 + vertex 1.47086 2.03152 2.50276 + endloop + endfacet + facet normal 0.101476 0.204972 0.973493 + outer loop + vertex 1.47263 2.0268 2.50356 + vertex 1.4765 2.0299 2.50251 + vertex 1.47086 2.03152 2.50276 + endloop + endfacet + facet normal 0.128209 0.172661 0.976601 + outer loop + vertex 1.47687 2.02551 2.50324 + vertex 1.4765 2.0299 2.50251 + vertex 1.47263 2.0268 2.50356 + endloop + endfacet + facet normal 0.108674 0.294011 0.949604 + outer loop + vertex 1.49118 2.02458 2.50236 + vertex 1.48941 2.02898 2.5012 + vertex 1.48608 2.0257 2.5026 + endloop + endfacet + facet normal 0.087329 0.145113 0.985554 + outer loop + vertex 1.49118 2.02458 2.50236 + vertex 1.49138 2.02073 2.50291 + vertex 1.49596 2.02164 2.50237 + endloop + endfacet + facet normal 0.0467013 -0.164778 0.985224 + outer loop + vertex 1.50321 2.01694 2.50134 + vertex 1.5021 2.0202 2.50194 + vertex 1.49867 2.01804 2.50174 + endloop + endfacet + facet normal -0.0480411 -0.195985 0.979429 + outer loop + vertex 1.5021 2.0202 2.50194 + vertex 1.50321 2.01694 2.50134 + vertex 1.5079 2.0167 2.50152 + endloop + endfacet + facet normal 0.115575 0.296388 0.948049 + outer loop + vertex 1.49338 2.0281 2.50099 + vertex 1.48941 2.02898 2.5012 + vertex 1.49118 2.02458 2.50236 + endloop + endfacet + facet normal 0.114262 0.288755 0.95056 + outer loop + vertex 1.48941 2.02898 2.5012 + vertex 1.48466 2.02997 2.50147 + vertex 1.48608 2.0257 2.5026 + endloop + endfacet + facet normal 0.0791856 0.278781 0.957084 + outer loop + vertex 1.48608 2.0257 2.5026 + vertex 1.48466 2.02997 2.50147 + vertex 1.48108 2.0266 2.50275 + endloop + endfacet + facet normal 0.070744 0.168926 0.983087 + outer loop + vertex 1.4765 2.0299 2.50251 + vertex 1.47687 2.02551 2.50324 + vertex 1.48108 2.0266 2.50275 + endloop + endfacet + facet normal 0.132417 0.322251 0.937347 + outer loop + vertex 1.47872 2.03347 2.50108 + vertex 1.48072 2.03088 2.50169 + vertex 1.48304 2.03441 2.50015 + endloop + endfacet + facet normal 0.128707 0.304765 0.943691 + outer loop + vertex 1.4765 2.0299 2.50251 + vertex 1.47477 2.03457 2.50124 + vertex 1.47086 2.03152 2.50276 + endloop + endfacet + facet normal 0.117756 0.31826 0.940662 + outer loop + vertex 1.47477 2.03457 2.50124 + vertex 1.47312 2.03911 2.49991 + vertex 1.47074 2.03576 2.50134 + endloop + endfacet + facet normal 0.125396 0.298736 0.946062 + outer loop + vertex 1.47312 2.03911 2.49991 + vertex 1.47717 2.04192 2.49849 + vertex 1.47311 2.04308 2.49866 + endloop + endfacet + facet normal 0.124554 0.285486 0.950255 + outer loop + vertex 1.48122 2.0408 2.49829 + vertex 1.48122 2.04481 2.49708 + vertex 1.47717 2.04192 2.49849 + endloop + endfacet + facet normal 0.119913 0.285656 0.9508 + outer loop + vertex 1.48122 2.04481 2.49708 + vertex 1.48122 2.0408 2.49829 + vertex 1.48561 2.04173 2.49746 + endloop + endfacet + facet normal 0.118186 0.28331 0.951718 + outer loop + vertex 1.48566 2.04568 2.49628 + vertex 1.48122 2.04481 2.49708 + vertex 1.48561 2.04173 2.49746 + endloop + endfacet + facet normal 0.117283 0.28701 0.950721 + outer loop + vertex 1.48566 2.04568 2.49628 + vertex 1.48363 2.0482 2.49576 + vertex 1.48122 2.04481 2.49708 + endloop + endfacet + facet normal 0.131969 0.323837 0.936864 + outer loop + vertex 1.47872 2.03347 2.50108 + vertex 1.48304 2.03441 2.50015 + vertex 1.47875 2.0375 2.49969 + endloop + endfacet + facet normal 0.125499 0.315575 0.940565 + outer loop + vertex 1.48826 2.03325 2.49984 + vertex 1.48718 2.03744 2.49858 + vertex 1.48304 2.03441 2.50015 + endloop + endfacet + facet normal 0.118293 0.291845 0.949122 + outer loop + vertex 1.48318 2.03833 2.49881 + vertex 1.48561 2.04173 2.49746 + vertex 1.48122 2.0408 2.49829 + endloop + endfacet + facet normal 0.116338 0.289609 0.950049 + outer loop + vertex 1.49202 2.03645 2.49829 + vertex 1.49088 2.0406 2.49716 + vertex 1.48718 2.03744 2.49858 + endloop + endfacet + facet normal 0.111237 0.288472 0.951005 + outer loop + vertex 1.49202 2.03645 2.49829 + vertex 1.49616 2.03952 2.49688 + vertex 1.49088 2.0406 2.49716 + endloop + endfacet + facet normal 0.110038 0.2821 0.953054 + outer loop + vertex 1.49616 2.03952 2.49688 + vertex 1.49447 2.0438 2.4958 + vertex 1.49088 2.0406 2.49716 + endloop + endfacet + facet normal 0.106478 0.280886 0.953816 + outer loop + vertex 1.4985 2.04297 2.4956 + vertex 1.49447 2.0438 2.4958 + vertex 1.49616 2.03952 2.49688 + endloop + endfacet + facet normal 0.108494 0.291638 0.950356 + outer loop + vertex 1.49447 2.0438 2.4958 + vertex 1.4985 2.04297 2.4956 + vertex 1.49841 2.047 2.49437 + endloop + endfacet + facet normal 0.110753 0.289096 0.950872 + outer loop + vertex 1.49313 2.04787 2.49472 + vertex 1.49447 2.0438 2.4958 + vertex 1.49841 2.047 2.49437 + endloop + endfacet + facet normal 0.111789 0.296313 0.948526 + outer loop + vertex 1.49841 2.047 2.49437 + vertex 1.49611 2.05068 2.49349 + vertex 1.49313 2.04787 2.49472 + endloop + endfacet + facet normal 0.113835 0.283506 0.95219 + outer loop + vertex 1.48566 2.04568 2.49628 + vertex 1.48561 2.04173 2.49746 + vertex 1.48966 2.04477 2.49607 + endloop + endfacet + facet normal 0.11491 0.288611 0.950526 + outer loop + vertex 1.48966 2.04477 2.49607 + vertex 1.488 2.04909 2.49496 + vertex 1.48566 2.04568 2.49628 + endloop + endfacet + facet normal 0.112542 0.295575 0.948667 + outer loop + vertex 1.49313 2.04787 2.49472 + vertex 1.49611 2.05068 2.49349 + vertex 1.49203 2.05198 2.49357 + endloop + endfacet + facet normal 0.117316 0.287034 0.950709 + outer loop + vertex 1.48363 2.0482 2.49576 + vertex 1.48566 2.04568 2.49628 + vertex 1.488 2.04909 2.49496 + endloop + endfacet + facet normal 0.117473 0.286881 0.950736 + outer loop + vertex 1.48363 2.0482 2.49576 + vertex 1.47957 2.04929 2.49594 + vertex 1.48122 2.04481 2.49708 + endloop + endfacet + facet normal 0.121954 0.288283 0.949748 + outer loop + vertex 1.48122 2.04481 2.49708 + vertex 1.47957 2.04929 2.49594 + vertex 1.47553 2.04637 2.49734 + endloop + endfacet + facet normal 0.120472 0.293061 0.948473 + outer loop + vertex 1.47112 2.04953 2.49693 + vertex 1.4711 2.04562 2.49814 + vertex 1.47553 2.04637 2.49734 + endloop + endfacet + facet normal 0.118607 0.29832 0.947068 + outer loop + vertex 1.47343 2.05292 2.49558 + vertex 1.47549 2.05039 2.49612 + vertex 1.47792 2.05379 2.49474 + endloop + endfacet + facet normal 0.114983 0.299154 0.947252 + outer loop + vertex 1.47112 2.04953 2.49693 + vertex 1.4694 2.05382 2.49578 + vertex 1.46597 2.05076 2.49716 + endloop + endfacet + facet normal 0.111308 0.302925 0.946492 + outer loop + vertex 1.4694 2.05382 2.49578 + vertex 1.4646 2.05479 2.49603 + vertex 1.46597 2.05076 2.49716 + endloop + endfacet + facet normal 0.111281 0.302778 0.946542 + outer loop + vertex 1.4646 2.05479 2.49603 + vertex 1.4694 2.05382 2.49578 + vertex 1.46806 2.05788 2.49464 + endloop + endfacet + facet normal 0.113039 0.301629 0.946701 + outer loop + vertex 1.46806 2.05788 2.49464 + vertex 1.47106 2.06065 2.4934 + vertex 1.46699 2.06197 2.49346 + endloop + endfacet + facet normal 0.1156 0.301042 0.946578 + outer loop + vertex 1.47114 2.06481 2.49206 + vertex 1.47106 2.06065 2.4934 + vertex 1.47568 2.06164 2.49252 + endloop + endfacet + facet normal 0.117675 0.302079 0.945992 + outer loop + vertex 1.47343 2.05292 2.49558 + vertex 1.47792 2.05379 2.49474 + vertex 1.47335 2.05696 2.4943 + endloop + endfacet + facet normal 0.118471 0.298887 0.946906 + outer loop + vertex 1.48363 2.05224 2.49451 + vertex 1.48212 2.05665 2.49331 + vertex 1.47792 2.05379 2.49474 + endloop + endfacet + facet normal 0.116529 0.30132 0.946376 + outer loop + vertex 1.47799 2.05797 2.4934 + vertex 1.48098 2.06073 2.49216 + vertex 1.47568 2.06164 2.49252 + endloop + endfacet + facet normal 0.116424 0.299572 0.946944 + outer loop + vertex 1.4861 2.05558 2.49316 + vertex 1.48614 2.05951 2.49191 + vertex 1.48212 2.05665 2.49331 + endloop + endfacet + facet normal 0.115333 0.300757 0.946702 + outer loop + vertex 1.48441 2.06379 2.49077 + vertex 1.47961 2.06476 2.49104 + vertex 1.48098 2.06073 2.49216 + endloop + endfacet + facet normal 0.115327 0.300726 0.946712 + outer loop + vertex 1.47961 2.06476 2.49104 + vertex 1.48441 2.06379 2.49077 + vertex 1.48306 2.06781 2.48966 + endloop + endfacet + facet normal 0.114499 0.301224 0.946654 + outer loop + vertex 1.48306 2.06781 2.48966 + vertex 1.48606 2.07055 2.48842 + vertex 1.48206 2.0718 2.4885 + endloop + endfacet + facet normal 0.113646 0.303331 0.946084 + outer loop + vertex 1.48621 2.07462 2.4871 + vertex 1.48606 2.07055 2.48842 + vertex 1.49066 2.07163 2.48752 + endloop + endfacet + facet normal 0.11403 0.302484 0.946309 + outer loop + vertex 1.49298 2.06798 2.48841 + vertex 1.49597 2.07077 2.48716 + vertex 1.49066 2.07163 2.48752 + endloop + endfacet + facet normal 0.113787 0.300124 0.947089 + outer loop + vertex 1.48845 2.06291 2.49056 + vertex 1.49293 2.0638 2.48974 + vertex 1.48834 2.06694 2.48929 + endloop + endfacet + facet normal 0.114736 0.30179 0.946445 + outer loop + vertex 1.49712 2.06667 2.48832 + vertex 1.49597 2.07077 2.48716 + vertex 1.49298 2.06798 2.48841 + endloop + endfacet + facet normal 0.116081 0.299483 0.947014 + outer loop + vertex 1.49865 2.06227 2.48953 + vertex 1.50112 2.06561 2.48817 + vertex 1.49712 2.06667 2.48832 + endloop + endfacet + facet normal 0.114371 0.299077 0.94735 + outer loop + vertex 1.49458 2.05933 2.49095 + vertex 1.49293 2.0638 2.48974 + vertex 1.49052 2.06041 2.4911 + endloop + endfacet + facet normal 0.115063 0.298904 0.947321 + outer loop + vertex 1.49864 2.05827 2.49079 + vertex 1.49458 2.05933 2.49095 + vertex 1.4962 2.05486 2.49216 + endloop + endfacet + facet normal 0.117392 0.298916 0.947031 + outer loop + vertex 1.49865 2.06227 2.48953 + vertex 1.503 2.05918 2.48996 + vertex 1.50309 2.06311 2.48871 + endloop + endfacet + facet normal 0.121973 0.300493 0.945953 + outer loop + vertex 1.503 2.05918 2.48996 + vertex 1.50467 2.0549 2.49111 + vertex 1.50811 2.05797 2.48969 + endloop + endfacet + facet normal 0.117635 0.300261 0.946576 + outer loop + vertex 1.506 2.05083 2.49223 + vertex 1.50467 2.0549 2.49111 + vertex 1.50072 2.05172 2.49261 + endloop + endfacet + facet normal 0.115425 0.298659 0.947354 + outer loop + vertex 1.50066 2.05577 2.49133 + vertex 1.49864 2.05827 2.49079 + vertex 1.4962 2.05486 2.49216 + endloop + endfacet + facet normal 0.113621 0.299022 0.947458 + outer loop + vertex 1.49611 2.05068 2.49349 + vertex 1.4962 2.05486 2.49216 + vertex 1.49203 2.05198 2.49357 + endloop + endfacet + facet normal 0.117798 0.301389 0.946197 + outer loop + vertex 1.50302 2.04805 2.49349 + vertex 1.506 2.05083 2.49223 + vertex 1.50072 2.05172 2.49261 + endloop + endfacet + facet normal 0.118408 0.294221 0.948374 + outer loop + vertex 1.50296 2.04389 2.49479 + vertex 1.50711 2.04674 2.49338 + vertex 1.50302 2.04805 2.49349 + endloop + endfacet + facet normal 0.117812 0.271764 0.955126 + outer loop + vertex 1.50616 2.03495 2.49699 + vertex 1.50459 2.03945 2.49591 + vertex 1.50052 2.0365 2.49725 + endloop + endfacet + facet normal 0.108161 0.279793 0.953948 + outer loop + vertex 1.50055 2.04051 2.49609 + vertex 1.4985 2.04297 2.4956 + vertex 1.49616 2.03952 2.49688 + endloop + endfacet + facet normal 0.110909 0.295373 0.948922 + outer loop + vertex 1.49798 2.03311 2.4986 + vertex 1.50052 2.0365 2.49725 + vertex 1.49605 2.03559 2.49805 + endloop + endfacet + facet normal 0.119053 0.289582 0.94972 + outer loop + vertex 1.50199 2.03203 2.49843 + vertex 1.50052 2.0365 2.49725 + vertex 1.49798 2.03311 2.4986 + endloop + endfacet + facet normal 0.139616 0.314133 0.939057 + outer loop + vertex 1.50347 2.02744 2.49974 + vertex 1.506 2.03086 2.49822 + vertex 1.50199 2.03203 2.49843 + endloop + endfacet + facet normal 0.140147 0.323463 0.935805 + outer loop + vertex 1.49963 2.02455 2.50131 + vertex 1.49784 2.02904 2.50002 + vertex 1.49548 2.0256 2.50157 + endloop + endfacet + facet normal 0.108677 0.20321 0.973085 + outer loop + vertex 1.50369 2.02335 2.50111 + vertex 1.49963 2.02455 2.50131 + vertex 1.5021 2.0202 2.50194 + endloop + endfacet + facet normal 0.148811 0.318129 0.936296 + outer loop + vertex 1.50347 2.02744 2.49974 + vertex 1.50794 2.02401 2.5002 + vertex 1.5079 2.02817 2.49879 + endloop + endfacet + facet normal 0.0880591 0.21355 0.972955 + outer loop + vertex 1.50618 2.02067 2.50147 + vertex 1.50369 2.02335 2.50111 + vertex 1.5021 2.0202 2.50194 + endloop + endfacet + facet normal 0.141447 0.289138 0.94678 + outer loop + vertex 1.50794 2.02401 2.5002 + vertex 1.51021 2.01952 2.50123 + vertex 1.51359 2.02231 2.49987 + endloop + endfacet + facet normal 0.107818 0.0607823 0.992311 + outer loop + vertex 1.50618 2.02067 2.50147 + vertex 1.5021 2.0202 2.50194 + vertex 1.5079 2.0167 2.50152 + endloop + endfacet + facet normal 0.076997 0.183794 0.979945 + outer loop + vertex 1.51404 2.01837 2.50114 + vertex 1.51021 2.01952 2.50123 + vertex 1.51293 2.016 2.50168 + endloop + endfacet + facet normal 0.0624173 0.190539 0.979693 + outer loop + vertex 1.51633 2.01608 2.50144 + vertex 1.51404 2.01837 2.50114 + vertex 1.51293 2.016 2.50168 + endloop + endfacet + facet normal 0.148434 0.273263 0.950418 + outer loop + vertex 1.51991 2.01503 2.50119 + vertex 1.51816 2.01898 2.50032 + vertex 1.51633 2.01608 2.50144 + endloop + endfacet + facet normal 0.138838 0.32433 0.9357 + outer loop + vertex 1.51816 2.01898 2.50032 + vertex 1.52215 2.02191 2.49872 + vertex 1.51801 2.02309 2.49892 + endloop + endfacet + facet normal 0.140963 0.299581 0.9436 + outer loop + vertex 1.52624 2.02069 2.49849 + vertex 1.52626 2.02503 2.49711 + vertex 1.52215 2.02191 2.49872 + endloop + endfacet + facet normal 0.137588 0.29974 0.944047 + outer loop + vertex 1.52626 2.02503 2.49711 + vertex 1.52624 2.02069 2.49849 + vertex 1.53072 2.02161 2.49755 + endloop + endfacet + facet normal 0.381124 0.189402 0.904915 + outer loop + vertex 1.52299 2.01355 2.50092 + vertex 1.52669 2.01208 2.49966 + vertex 1.52356 2.01702 2.49995 + endloop + endfacet + facet normal -0.0285539 0.226248 0.973651 + outer loop + vertex 1.53319 2.01167 2.49995 + vertex 1.53201 2.01653 2.49879 + vertex 1.52669 2.01208 2.49966 + endloop + endfacet + facet normal 0.15127 0.246533 0.957256 + outer loop + vertex 1.528 2.01761 2.49901 + vertex 1.53072 2.02161 2.49755 + vertex 1.52624 2.02069 2.49849 + endloop + endfacet + facet normal 0.134248 0.295969 0.945717 + outer loop + vertex 1.53637 2.02007 2.49723 + vertex 1.53474 2.02469 2.49601 + vertex 1.53072 2.02161 2.49755 + endloop + endfacet + facet normal 0.141857 0.29819 0.943907 + outer loop + vertex 1.53876 2.02354 2.49577 + vertex 1.53474 2.02469 2.49601 + vertex 1.53637 2.02007 2.49723 + endloop + endfacet + facet normal 0.139438 0.289133 0.947079 + outer loop + vertex 1.53474 2.02469 2.49601 + vertex 1.53876 2.02354 2.49577 + vertex 1.53866 2.02748 2.49458 + endloop + endfacet + facet normal 0.138423 0.290433 0.94683 + outer loop + vertex 1.53304 2.02915 2.49489 + vertex 1.53474 2.02469 2.49601 + vertex 1.53866 2.02748 2.49458 + endloop + endfacet + facet normal 0.148704 0.290257 0.945324 + outer loop + vertex 1.53637 2.02007 2.49723 + vertex 1.53615 2.01567 2.49861 + vertex 1.54066 2.01669 2.49759 + endloop + endfacet + facet normal 0.16489 0.23193 0.958655 + outer loop + vertex 1.53771 2.01271 2.49906 + vertex 1.54066 2.01669 2.49759 + vertex 1.53615 2.01567 2.49861 + endloop + endfacet + facet normal 0.361017 0.208541 0.908943 + outer loop + vertex 1.53267 2.00843 2.5009 + vertex 1.53632 2.00725 2.49972 + vertex 1.53319 2.01167 2.49995 + endloop + endfacet + facet normal 0.282258 -0.0821229 0.955817 + outer loop + vertex 1.53267 2.00843 2.5009 + vertex 1.53277 2.00728 2.50077 + vertex 1.53632 2.00725 2.49972 + endloop + endfacet + facet normal 0.180433 -0.0942728 0.979059 + outer loop + vertex 1.53277 2.00728 2.50077 + vertex 1.53267 2.00843 2.5009 + vertex 1.53126 2.00752 2.50107 + endloop + endfacet + facet normal 0.140587 0.249726 0.958056 + outer loop + vertex 1.54173 2.01174 2.49873 + vertex 1.54066 2.01669 2.49759 + vertex 1.53771 2.01271 2.49906 + endloop + endfacet + facet normal 0.12257 0.286325 0.95026 + outer loop + vertex 1.54596 2.01089 2.49843 + vertex 1.54623 2.01508 2.49714 + vertex 1.54173 2.01174 2.49873 + endloop + endfacet + facet normal 0.159371 0.29063 0.94347 + outer loop + vertex 1.54786 2.0083 2.49891 + vertex 1.55054 2.01173 2.4974 + vertex 1.54596 2.01089 2.49843 + endloop + endfacet + facet normal 0.141403 0.321116 0.936424 + outer loop + vertex 1.5436 2.00346 2.50109 + vertex 1.5477 2.00425 2.5002 + vertex 1.54323 2.00717 2.49987 + endloop + endfacet + facet normal 0.17337 0.280001 0.944215 + outer loop + vertex 1.55195 2.0071 2.49851 + vertex 1.55054 2.01173 2.4974 + vertex 1.54786 2.0083 2.49891 + endloop + endfacet + facet normal 0.180818 0.274761 0.944358 + outer loop + vertex 1.55351 2.00235 2.4996 + vertex 1.55605 2.00579 2.49811 + vertex 1.55195 2.0071 2.49851 + endloop + endfacet + facet normal 0.182549 0.268754 0.945752 + outer loop + vertex 1.54936 1.99974 2.50116 + vertex 1.5477 2.00425 2.5002 + vertex 1.54558 2.00119 2.50148 + endloop + endfacet + facet normal 0.166748 0.214598 0.962363 + outer loop + vertex 1.55344 1.99809 2.50082 + vertex 1.54936 1.99974 2.50116 + vertex 1.55113 1.99486 2.50194 + endloop + endfacet + facet normal 0.184108 0.268704 0.945464 + outer loop + vertex 1.55351 2.00235 2.4996 + vertex 1.55846 1.99838 2.49976 + vertex 1.55813 2.00297 2.49852 + endloop + endfacet + facet normal 0.140642 0.233211 0.962202 + outer loop + vertex 1.55541 1.99515 2.50124 + vertex 1.55344 1.99809 2.50082 + vertex 1.55113 1.99486 2.50194 + endloop + endfacet + facet normal -0.0924233 0.153388 0.983834 + outer loop + vertex 1.55144 1.9904 2.50267 + vertex 1.55113 1.99486 2.50194 + vertex 1.54756 1.99267 2.50195 + endloop + endfacet + facet normal 0.139152 0.242846 0.960032 + outer loop + vertex 1.55581 1.99065 2.50234 + vertex 1.5562 1.98609 2.50344 + vertex 1.56042 1.98686 2.50263 + endloop + endfacet + facet normal 0.159243 0.266539 0.950578 + outer loop + vertex 1.56052 1.99109 2.50143 + vertex 1.55581 1.99065 2.50234 + vertex 1.56042 1.98686 2.50263 + endloop + endfacet + facet normal 0.175766 0.26543 0.947973 + outer loop + vertex 1.56052 1.99109 2.50143 + vertex 1.56042 1.98686 2.50263 + vertex 1.56459 1.98974 2.50105 + endloop + endfacet + facet normal 0.175807 0.265567 0.947927 + outer loop + vertex 1.56459 1.98974 2.50105 + vertex 1.5631 1.99443 2.50001 + vertex 1.56052 1.99109 2.50143 + endloop + endfacet + facet normal 0.175849 0.265534 0.947929 + outer loop + vertex 1.55864 1.99391 2.50098 + vertex 1.56052 1.99109 2.50143 + vertex 1.5631 1.99443 2.50001 + endloop + endfacet + facet normal 0.175776 0.265966 0.947821 + outer loop + vertex 1.55864 1.99391 2.50098 + vertex 1.5631 1.99443 2.50001 + vertex 1.55846 1.99838 2.49976 + endloop + endfacet + facet normal 0.16069 0.256288 0.95315 + outer loop + vertex 1.56052 1.99109 2.50143 + vertex 1.55864 1.99391 2.50098 + vertex 1.55581 1.99065 2.50234 + endloop + endfacet + facet normal 0.133213 0.268948 0.953898 + outer loop + vertex 1.558 1.98333 2.50396 + vertex 1.56042 1.98686 2.50263 + vertex 1.5562 1.98609 2.50344 + endloop + endfacet + facet normal 0.147428 0.259382 0.954456 + outer loop + vertex 1.56197 1.98213 2.50368 + vertex 1.56042 1.98686 2.50263 + vertex 1.558 1.98333 2.50396 + endloop + endfacet + facet normal 0.185683 0.25855 0.947984 + outer loop + vertex 1.56602 1.9809 2.50322 + vertex 1.56608 1.98508 2.50206 + vertex 1.56197 1.98213 2.50368 + endloop + endfacet + facet normal 0.177451 0.247925 0.952389 + outer loop + vertex 1.56809 1.97812 2.50355 + vertex 1.57046 1.98161 2.5022 + vertex 1.56602 1.9809 2.50322 + endloop + endfacet + facet normal 0.172023 0.24841 0.953258 + outer loop + vertex 1.56843 1.97355 2.50468 + vertex 1.57202 1.97703 2.50313 + vertex 1.56809 1.97812 2.50355 + endloop + endfacet + facet normal 0.166176 0.236092 0.957416 + outer loop + vertex 1.5686 1.9691 2.50575 + vertex 1.57301 1.96947 2.5049 + vertex 1.56843 1.97355 2.50468 + endloop + endfacet + facet normal 0.166047 0.237105 0.957188 + outer loop + vertex 1.5686 1.9691 2.50575 + vertex 1.57045 1.96618 2.50615 + vertex 1.57301 1.96947 2.5049 + endloop + endfacet + facet normal 0.174929 0.242346 0.954289 + outer loop + vertex 1.57045 1.96618 2.50615 + vertex 1.5686 1.9691 2.50575 + vertex 1.5656 1.96586 2.50712 + endloop + endfacet + facet normal 0.175115 0.240691 0.954674 + outer loop + vertex 1.57045 1.96618 2.50615 + vertex 1.5656 1.96586 2.50712 + vertex 1.57045 1.96183 2.50725 + endloop + endfacet + facet normal 0.159141 0.241358 0.957298 + outer loop + vertex 1.57045 1.96618 2.50615 + vertex 1.57045 1.96183 2.50725 + vertex 1.57455 1.96458 2.50588 + endloop + endfacet + facet normal 0.16831 0.232608 0.957896 + outer loop + vertex 1.5656 1.96586 2.50712 + vertex 1.56601 1.96121 2.50818 + vertex 1.57045 1.96183 2.50725 + endloop + endfacet + facet normal 0.16816 0.233421 0.957725 + outer loop + vertex 1.56819 1.95823 2.50853 + vertex 1.57045 1.96183 2.50725 + vertex 1.56601 1.96121 2.50818 + endloop + endfacet + facet normal 0.173887 0.237379 0.955727 + outer loop + vertex 1.56819 1.95823 2.50853 + vertex 1.56601 1.96121 2.50818 + vertex 1.56364 1.95758 2.50951 + endloop + endfacet + facet normal 0.174381 0.234755 0.956285 + outer loop + vertex 1.56364 1.95758 2.50951 + vertex 1.56862 1.95341 2.50963 + vertex 1.56819 1.95823 2.50853 + endloop + endfacet + facet normal 0.160082 0.234072 0.95895 + outer loop + vertex 1.56862 1.95341 2.50963 + vertex 1.57213 1.95699 2.50817 + vertex 1.56819 1.95823 2.50853 + endloop + endfacet + facet normal 0.158826 0.235269 0.958866 + outer loop + vertex 1.5735 1.95332 2.50884 + vertex 1.57213 1.95699 2.50817 + vertex 1.56862 1.95341 2.50963 + endloop + endfacet + facet normal 0.158969 0.228063 0.960581 + outer loop + vertex 1.56862 1.95341 2.50963 + vertex 1.57363 1.94876 2.50991 + vertex 1.5735 1.95332 2.50884 + endloop + endfacet + facet normal 0.15811 0.228071 0.960721 + outer loop + vertex 1.57363 1.94876 2.50991 + vertex 1.57716 1.95205 2.50854 + vertex 1.5735 1.95332 2.50884 + endloop + endfacet + facet normal 0.159016 0.230874 0.959902 + outer loop + vertex 1.57716 1.95205 2.50854 + vertex 1.57591 1.95549 2.50792 + vertex 1.5735 1.95332 2.50884 + endloop + endfacet + facet normal 0.15647 0.230061 0.960515 + outer loop + vertex 1.57716 1.95205 2.50854 + vertex 1.5806 1.95553 2.50715 + vertex 1.57591 1.95549 2.50792 + endloop + endfacet + facet normal 0.157173 0.229384 0.960562 + outer loop + vertex 1.58078 1.95093 2.50822 + vertex 1.5806 1.95553 2.50715 + vertex 1.57716 1.95205 2.50854 + endloop + endfacet + facet normal 0.156265 0.226185 0.961468 + outer loop + vertex 1.57842 1.94862 2.50914 + vertex 1.58078 1.95093 2.50822 + vertex 1.57716 1.95205 2.50854 + endloop + endfacet + facet normal 0.150392 0.231981 0.961024 + outer loop + vertex 1.58229 1.94738 2.50884 + vertex 1.58078 1.95093 2.50822 + vertex 1.57842 1.94862 2.50914 + endloop + endfacet + facet normal 0.149721 0.22972 0.961672 + outer loop + vertex 1.57818 1.94451 2.51016 + vertex 1.58229 1.94738 2.50884 + vertex 1.57842 1.94862 2.50914 + endloop + endfacet + facet normal 0.159033 0.228834 0.960387 + outer loop + vertex 1.57363 1.94876 2.50991 + vertex 1.57818 1.94451 2.51016 + vertex 1.57842 1.94862 2.50914 + endloop + endfacet + facet normal 0.157469 0.227198 0.961033 + outer loop + vertex 1.57374 1.94414 2.51098 + vertex 1.57818 1.94451 2.51016 + vertex 1.57363 1.94876 2.50991 + endloop + endfacet + facet normal 0.156259 0.227213 0.961227 + outer loop + vertex 1.57374 1.94414 2.51098 + vertex 1.57363 1.94876 2.50991 + vertex 1.57054 1.94561 2.51115 + endloop + endfacet + facet normal 0.154999 0.224345 0.962104 + outer loop + vertex 1.57054 1.94561 2.51115 + vertex 1.57072 1.94088 2.51223 + vertex 1.57374 1.94414 2.51098 + endloop + endfacet + facet normal 0.155399 0.223981 0.962124 + outer loop + vertex 1.57558 1.94113 2.51138 + vertex 1.57374 1.94414 2.51098 + vertex 1.57072 1.94088 2.51223 + endloop + endfacet + facet normal 0.155211 0.226084 0.961663 + outer loop + vertex 1.57558 1.94113 2.51138 + vertex 1.57072 1.94088 2.51223 + vertex 1.57552 1.93676 2.51242 + endloop + endfacet + facet normal 0.155738 0.226058 0.961584 + outer loop + vertex 1.57558 1.94113 2.51138 + vertex 1.57552 1.93676 2.51242 + vertex 1.57963 1.93961 2.51109 + endloop + endfacet + facet normal 0.155944 0.226636 0.961414 + outer loop + vertex 1.57963 1.93961 2.51109 + vertex 1.57818 1.94451 2.51016 + vertex 1.57558 1.94113 2.51138 + endloop + endfacet + facet normal 0.152384 0.230642 0.961032 + outer loop + vertex 1.58101 1.93487 2.512 + vertex 1.57963 1.93961 2.51109 + vertex 1.57552 1.93676 2.51242 + endloop + endfacet + facet normal 0.14962 0.222075 0.963481 + outer loop + vertex 1.57706 1.93201 2.51328 + vertex 1.58101 1.93487 2.512 + vertex 1.57552 1.93676 2.51242 + endloop + endfacet + facet normal 0.157722 0.224372 0.961655 + outer loop + vertex 1.57706 1.93201 2.51328 + vertex 1.57552 1.93676 2.51242 + vertex 1.57322 1.93309 2.51365 + endloop + endfacet + facet normal 0.156726 0.220487 0.962716 + outer loop + vertex 1.57347 1.92841 2.51468 + vertex 1.57706 1.93201 2.51328 + vertex 1.57322 1.93309 2.51365 + endloop + endfacet + facet normal 0.153544 0.220434 0.963241 + outer loop + vertex 1.5688 1.93239 2.51452 + vertex 1.57347 1.92841 2.51468 + vertex 1.57322 1.93309 2.51365 + endloop + endfacet + facet normal 0.153431 0.220304 0.963289 + outer loop + vertex 1.56867 1.92806 2.51553 + vertex 1.57347 1.92841 2.51468 + vertex 1.5688 1.93239 2.51452 + endloop + endfacet + facet normal 0.155919 0.220145 0.962925 + outer loop + vertex 1.56459 1.92958 2.51584 + vertex 1.56867 1.92806 2.51553 + vertex 1.5688 1.93239 2.51452 + endloop + endfacet + facet normal 0.160427 0.213739 0.963628 + outer loop + vertex 1.5631 1.93453 2.51499 + vertex 1.56459 1.92958 2.51584 + vertex 1.5688 1.93239 2.51452 + endloop + endfacet + facet normal 0.165705 0.228748 0.959279 + outer loop + vertex 1.5688 1.93239 2.51452 + vertex 1.56723 1.93718 2.51365 + vertex 1.5631 1.93453 2.51499 + endloop + endfacet + facet normal 0.167382 0.226281 0.959573 + outer loop + vertex 1.5631 1.93453 2.51499 + vertex 1.56723 1.93718 2.51365 + vertex 1.56341 1.93866 2.51396 + endloop + endfacet + facet normal 0.198518 0.222671 0.954468 + outer loop + vertex 1.55844 1.93878 2.51497 + vertex 1.5631 1.93453 2.51499 + vertex 1.56341 1.93866 2.51396 + endloop + endfacet + facet normal 0.198467 0.224938 0.953946 + outer loop + vertex 1.56341 1.93866 2.51396 + vertex 1.56212 1.94215 2.51341 + vertex 1.55844 1.93878 2.51497 + endloop + endfacet + facet normal 0.201718 0.221453 0.95408 + outer loop + vertex 1.55844 1.93878 2.51497 + vertex 1.56212 1.94215 2.51341 + vertex 1.55829 1.94341 2.51393 + endloop + endfacet + facet normal 0.201056 0.21915 0.954751 + outer loop + vertex 1.56212 1.94215 2.51341 + vertex 1.56078 1.94566 2.51289 + vertex 1.55829 1.94341 2.51393 + endloop + endfacet + facet normal 0.200826 0.2194 0.954742 + outer loop + vertex 1.55829 1.94341 2.51393 + vertex 1.56078 1.94566 2.51289 + vertex 1.55684 1.94706 2.51339 + endloop + endfacet + facet normal 0.182468 0.212857 0.959894 + outer loop + vertex 1.55829 1.94341 2.51393 + vertex 1.55684 1.94706 2.51339 + vertex 1.55353 1.94313 2.5149 + endloop + endfacet + facet normal 0.200424 0.218128 0.955118 + outer loop + vertex 1.56078 1.94566 2.51289 + vertex 1.56095 1.94985 2.51189 + vertex 1.55684 1.94706 2.51339 + endloop + endfacet + facet normal 0.18235 0.243396 0.952632 + outer loop + vertex 1.55684 1.94706 2.51339 + vertex 1.56095 1.94985 2.51189 + vertex 1.5552 1.95171 2.51252 + endloop + endfacet + facet normal 0.151588 0.23398 0.960351 + outer loop + vertex 1.55684 1.94706 2.51339 + vertex 1.5552 1.95171 2.51252 + vertex 1.55299 1.94796 2.51378 + endloop + endfacet + facet normal 0.181956 0.219671 0.958455 + outer loop + vertex 1.56095 1.94985 2.51189 + vertex 1.56078 1.94566 2.51289 + vertex 1.5657 1.94553 2.51198 + endloop + endfacet + facet normal 0.185543 0.223576 0.956863 + outer loop + vertex 1.56553 1.95022 2.51092 + vertex 1.56095 1.94985 2.51189 + vertex 1.5657 1.94553 2.51198 + endloop + endfacet + facet normal 0.166493 0.223675 0.960338 + outer loop + vertex 1.56553 1.95022 2.51092 + vertex 1.5657 1.94553 2.51198 + vertex 1.56881 1.94873 2.5107 + endloop + endfacet + facet normal 0.167347 0.225642 0.95973 + outer loop + vertex 1.56881 1.94873 2.5107 + vertex 1.56862 1.95341 2.50963 + vertex 1.56553 1.95022 2.51092 + endloop + endfacet + facet normal 0.160828 0.229052 0.960036 + outer loop + vertex 1.57054 1.94561 2.51115 + vertex 1.56881 1.94873 2.5107 + vertex 1.5657 1.94553 2.51198 + endloop + endfacet + facet normal 0.185135 0.226828 0.956177 + outer loop + vertex 1.56553 1.95022 2.51092 + vertex 1.56359 1.95326 2.51057 + vertex 1.56095 1.94985 2.51189 + endloop + endfacet + facet normal 0.184806 0.227083 0.95618 + outer loop + vertex 1.56359 1.95326 2.51057 + vertex 1.5593 1.95476 2.51105 + vertex 1.56095 1.94985 2.51189 + endloop + endfacet + facet normal 0.18632 0.23184 0.954744 + outer loop + vertex 1.5593 1.95476 2.51105 + vertex 1.56359 1.95326 2.51057 + vertex 1.56364 1.95758 2.50951 + endloop + endfacet + facet normal 0.172551 0.232592 0.957145 + outer loop + vertex 1.56359 1.95326 2.51057 + vertex 1.56862 1.95341 2.50963 + vertex 1.56364 1.95758 2.50951 + endloop + endfacet + facet normal 0.173479 0.219808 0.959995 + outer loop + vertex 1.56359 1.95326 2.51057 + vertex 1.56553 1.95022 2.51092 + vertex 1.56862 1.95341 2.50963 + endloop + endfacet + facet normal 0.182046 0.212683 0.960013 + outer loop + vertex 1.56212 1.94215 2.51341 + vertex 1.5657 1.94553 2.51198 + vertex 1.56078 1.94566 2.51289 + endloop + endfacet + facet normal 0.177838 0.217069 0.95982 + outer loop + vertex 1.5659 1.94086 2.513 + vertex 1.5657 1.94553 2.51198 + vertex 1.56212 1.94215 2.51341 + endloop + endfacet + facet normal 0.1541 0.216942 0.963945 + outer loop + vertex 1.5657 1.94553 2.51198 + vertex 1.5659 1.94086 2.513 + vertex 1.57072 1.94088 2.51223 + endloop + endfacet + facet normal 0.153782 0.224509 0.962261 + outer loop + vertex 1.56723 1.93718 2.51365 + vertex 1.57072 1.94088 2.51223 + vertex 1.5659 1.94086 2.513 + endloop + endfacet + facet normal 0.168435 0.229193 0.958697 + outer loop + vertex 1.56723 1.93718 2.51365 + vertex 1.5659 1.94086 2.513 + vertex 1.56341 1.93866 2.51396 + endloop + endfacet + facet normal 0.152287 0.225883 0.962177 + outer loop + vertex 1.57114 1.93603 2.5133 + vertex 1.57072 1.94088 2.51223 + vertex 1.56723 1.93718 2.51365 + endloop + endfacet + facet normal 0.178244 0.218368 0.95945 + outer loop + vertex 1.56341 1.93866 2.51396 + vertex 1.5659 1.94086 2.513 + vertex 1.56212 1.94215 2.51341 + endloop + endfacet + facet normal 0.15201 0.224857 0.962462 + outer loop + vertex 1.5688 1.93239 2.51452 + vertex 1.57114 1.93603 2.5133 + vertex 1.56723 1.93718 2.51365 + endloop + endfacet + facet normal 0.152764 0.22437 0.962456 + outer loop + vertex 1.57322 1.93309 2.51365 + vertex 1.57114 1.93603 2.5133 + vertex 1.5688 1.93239 2.51452 + endloop + endfacet + facet normal 0.173097 0.217063 0.960688 + outer loop + vertex 1.56459 1.92958 2.51584 + vertex 1.5631 1.93453 2.51499 + vertex 1.56044 1.93116 2.51623 + endloop + endfacet + facet normal 0.17174 0.213233 0.961788 + outer loop + vertex 1.56044 1.93116 2.51623 + vertex 1.56027 1.9267 2.51725 + vertex 1.56459 1.92958 2.51584 + endloop + endfacet + facet normal 0.167784 0.218892 0.961215 + outer loop + vertex 1.56607 1.92464 2.51671 + vertex 1.56459 1.92958 2.51584 + vertex 1.56027 1.9267 2.51725 + endloop + endfacet + facet normal 0.185084 0.212212 0.959536 + outer loop + vertex 1.56044 1.93116 2.51623 + vertex 1.55545 1.93088 2.51726 + vertex 1.56027 1.9267 2.51725 + endloop + endfacet + facet normal 0.185723 0.212949 0.95925 + outer loop + vertex 1.55545 1.93088 2.51726 + vertex 1.55568 1.92624 2.51824 + vertex 1.56027 1.9267 2.51725 + endloop + endfacet + facet normal 0.186239 0.209285 0.959956 + outer loop + vertex 1.55721 1.92265 2.51873 + vertex 1.56027 1.9267 2.51725 + vertex 1.55568 1.92624 2.51824 + endloop + endfacet + facet normal 0.191621 0.21137 0.958438 + outer loop + vertex 1.55721 1.92265 2.51873 + vertex 1.55568 1.92624 2.51824 + vertex 1.55328 1.92384 2.51925 + endloop + endfacet + facet normal 0.173044 0.212812 0.961648 + outer loop + vertex 1.55568 1.92624 2.51824 + vertex 1.55545 1.93088 2.51726 + vertex 1.55197 1.92718 2.5187 + endloop + endfacet + facet normal 0.188128 0.205117 0.960487 + outer loop + vertex 1.55855 1.93419 2.51596 + vertex 1.56044 1.93116 2.51623 + vertex 1.5631 1.93453 2.51499 + endloop + endfacet + facet normal 0.154247 0.215383 0.964271 + outer loop + vertex 1.56867 1.92806 2.51553 + vertex 1.56459 1.92958 2.51584 + vertex 1.56607 1.92464 2.51671 + endloop + endfacet + facet normal 0.15022 0.218433 0.96422 + outer loop + vertex 1.57042 1.92517 2.51591 + vertex 1.56867 1.92806 2.51553 + vertex 1.56607 1.92464 2.51671 + endloop + endfacet + facet normal 0.151158 0.212432 0.965414 + outer loop + vertex 1.57042 1.92517 2.51591 + vertex 1.56607 1.92464 2.51671 + vertex 1.57049 1.9206 2.51691 + endloop + endfacet + facet normal 0.153403 0.212392 0.965068 + outer loop + vertex 1.57042 1.92517 2.51591 + vertex 1.57049 1.9206 2.51691 + vertex 1.57349 1.9239 2.5157 + endloop + endfacet + facet normal 0.155684 0.218193 0.963408 + outer loop + vertex 1.57349 1.9239 2.5157 + vertex 1.57347 1.92841 2.51468 + vertex 1.57042 1.92517 2.51591 + endloop + endfacet + facet normal 0.153083 0.218273 0.963806 + outer loop + vertex 1.57349 1.9239 2.5157 + vertex 1.57793 1.92434 2.5149 + vertex 1.57347 1.92841 2.51468 + endloop + endfacet + facet normal 0.155813 0.221203 0.9627 + outer loop + vertex 1.57347 1.92841 2.51468 + vertex 1.57793 1.92434 2.5149 + vertex 1.57826 1.92848 2.51389 + endloop + endfacet + facet normal 0.154318 0.209183 0.965623 + outer loop + vertex 1.57349 1.9239 2.5157 + vertex 1.57526 1.92091 2.51607 + vertex 1.57793 1.92434 2.5149 + endloop + endfacet + facet normal 0.155967 0.210103 0.965159 + outer loop + vertex 1.57526 1.92091 2.51607 + vertex 1.57349 1.9239 2.5157 + vertex 1.57049 1.9206 2.51691 + endloop + endfacet + facet normal 0.15604 0.209378 0.965304 + outer loop + vertex 1.57526 1.92091 2.51607 + vertex 1.57049 1.9206 2.51691 + vertex 1.57509 1.91642 2.51707 + endloop + endfacet + facet normal 0.147025 0.210005 0.966582 + outer loop + vertex 1.57526 1.92091 2.51607 + vertex 1.57509 1.91642 2.51707 + vertex 1.57936 1.91938 2.51578 + endloop + endfacet + facet normal 0.141207 0.218013 0.965676 + outer loop + vertex 1.58083 1.91454 2.51665 + vertex 1.57936 1.91938 2.51578 + vertex 1.57509 1.91642 2.51707 + endloop + endfacet + facet normal 0.157225 0.21066 0.964833 + outer loop + vertex 1.57049 1.9206 2.51691 + vertex 1.57066 1.91597 2.51789 + vertex 1.57509 1.91642 2.51707 + endloop + endfacet + facet normal 0.158587 0.200569 0.966759 + outer loop + vertex 1.57218 1.91236 2.51839 + vertex 1.57509 1.91642 2.51707 + vertex 1.57066 1.91597 2.51789 + endloop + endfacet + facet normal 0.157993 0.200338 0.966904 + outer loop + vertex 1.57218 1.91236 2.51839 + vertex 1.57066 1.91597 2.51789 + vertex 1.56839 1.91349 2.51878 + endloop + endfacet + facet normal 0.156785 0.195874 0.968014 + outer loop + vertex 1.56856 1.90868 2.51972 + vertex 1.57218 1.91236 2.51839 + vertex 1.56839 1.91349 2.51878 + endloop + endfacet + facet normal 0.155266 0.195866 0.968261 + outer loop + vertex 1.56358 1.91345 2.51955 + vertex 1.56856 1.90868 2.51972 + vertex 1.56839 1.91349 2.51878 + endloop + endfacet + facet normal 0.154793 0.207404 0.965931 + outer loop + vertex 1.56839 1.91349 2.51878 + vertex 1.56707 1.91703 2.51822 + vertex 1.56358 1.91345 2.51955 + endloop + endfacet + facet normal 0.160508 0.201278 0.966294 + outer loop + vertex 1.56362 1.90874 2.52053 + vertex 1.56856 1.90868 2.51972 + vertex 1.56358 1.91345 2.51955 + endloop + endfacet + facet normal 0.172172 0.200986 0.964345 + outer loop + vertex 1.56362 1.90874 2.52053 + vertex 1.56358 1.91345 2.51955 + vertex 1.56042 1.91023 2.52079 + endloop + endfacet + facet normal 0.172247 0.201154 0.964297 + outer loop + vertex 1.56042 1.91023 2.52079 + vertex 1.56052 1.90543 2.52177 + vertex 1.56362 1.90874 2.52053 + endloop + endfacet + facet normal 0.169978 0.203267 0.964256 + outer loop + vertex 1.56533 1.90551 2.52091 + vertex 1.56362 1.90874 2.52053 + vertex 1.56052 1.90543 2.52177 + endloop + endfacet + facet normal 0.170455 0.193977 0.966084 + outer loop + vertex 1.56533 1.90551 2.52091 + vertex 1.56052 1.90543 2.52177 + vertex 1.56551 1.90057 2.52187 + endloop + endfacet + facet normal 0.164379 0.193962 0.967139 + outer loop + vertex 1.56533 1.90551 2.52091 + vertex 1.56551 1.90057 2.52187 + vertex 1.56862 1.90381 2.52069 + endloop + endfacet + facet normal 0.164639 0.194481 0.966991 + outer loop + vertex 1.56862 1.90381 2.52069 + vertex 1.56856 1.90868 2.51972 + vertex 1.56533 1.90551 2.52091 + endloop + endfacet + facet normal 0.162181 0.194534 0.967395 + outer loop + vertex 1.56862 1.90381 2.52069 + vertex 1.57356 1.90372 2.51988 + vertex 1.56856 1.90868 2.51972 + endloop + endfacet + facet normal 0.159561 0.191921 0.968352 + outer loop + vertex 1.56856 1.90868 2.51972 + vertex 1.57356 1.90372 2.51988 + vertex 1.57368 1.90856 2.5189 + endloop + endfacet + facet normal 0.162267 0.18903 0.968472 + outer loop + vertex 1.56862 1.90381 2.52069 + vertex 1.57033 1.90054 2.52104 + vertex 1.57356 1.90372 2.51988 + endloop + endfacet + facet normal 0.163493 0.187794 0.968506 + outer loop + vertex 1.57351 1.89896 2.52081 + vertex 1.57356 1.90372 2.51988 + vertex 1.57033 1.90054 2.52104 + endloop + endfacet + facet normal 0.1661 0.193256 0.966986 + outer loop + vertex 1.57033 1.90054 2.52104 + vertex 1.57047 1.89576 2.52197 + vertex 1.57351 1.89896 2.52081 + endloop + endfacet + facet normal 0.16235 0.196791 0.96691 + outer loop + vertex 1.57528 1.89589 2.52114 + vertex 1.57351 1.89896 2.52081 + vertex 1.57047 1.89576 2.52197 + endloop + endfacet + facet normal 0.162142 0.200165 0.966253 + outer loop + vertex 1.57528 1.89589 2.52114 + vertex 1.57047 1.89576 2.52197 + vertex 1.57512 1.89144 2.52209 + endloop + endfacet + facet normal 0.15668 0.194332 0.968342 + outer loop + vertex 1.57047 1.89576 2.52197 + vertex 1.5707 1.89096 2.5229 + vertex 1.57512 1.89144 2.52209 + endloop + endfacet + facet normal 0.168276 0.194523 0.966356 + outer loop + vertex 1.5707 1.89096 2.5229 + vertex 1.57047 1.89576 2.52197 + vertex 1.56712 1.89208 2.5233 + endloop + endfacet + facet normal 0.167308 0.19113 0.967201 + outer loop + vertex 1.5684 1.88843 2.52379 + vertex 1.5707 1.89096 2.5229 + vertex 1.56712 1.89208 2.5233 + endloop + endfacet + facet normal 0.163496 0.189911 0.968092 + outer loop + vertex 1.5684 1.88843 2.52379 + vertex 1.56712 1.89208 2.5233 + vertex 1.56359 1.88842 2.52461 + endloop + endfacet + facet normal 0.163516 0.189345 0.9682 + outer loop + vertex 1.56359 1.88842 2.52461 + vertex 1.5685 1.88359 2.52473 + vertex 1.5684 1.88843 2.52379 + endloop + endfacet + facet normal 0.163113 0.188939 0.968347 + outer loop + vertex 1.56353 1.88366 2.52555 + vertex 1.5685 1.88359 2.52473 + vertex 1.56359 1.88842 2.52461 + endloop + endfacet + facet normal 0.160097 0.189072 0.968824 + outer loop + vertex 1.56353 1.88366 2.52555 + vertex 1.56359 1.88842 2.52461 + vertex 1.56038 1.88518 2.52577 + endloop + endfacet + facet normal 0.16069 0.190357 0.968475 + outer loop + vertex 1.56038 1.88518 2.52577 + vertex 1.56046 1.88035 2.52671 + vertex 1.56353 1.88366 2.52555 + endloop + endfacet + facet normal 0.160752 0.190299 0.968476 + outer loop + vertex 1.56523 1.88043 2.5259 + vertex 1.56353 1.88366 2.52555 + vertex 1.56046 1.88035 2.52671 + endloop + endfacet + facet normal 0.160616 0.193066 0.96795 + outer loop + vertex 1.56523 1.88043 2.5259 + vertex 1.56046 1.88035 2.52671 + vertex 1.56549 1.87552 2.52684 + endloop + endfacet + facet normal 0.165591 0.193161 0.967093 + outer loop + vertex 1.56523 1.88043 2.5259 + vertex 1.56549 1.87552 2.52684 + vertex 1.56854 1.87872 2.52568 + endloop + endfacet + facet normal 0.164177 0.190317 0.967897 + outer loop + vertex 1.56854 1.87872 2.52568 + vertex 1.5685 1.88359 2.52473 + vertex 1.56523 1.88043 2.5259 + endloop + endfacet + facet normal 0.167843 0.191024 0.967129 + outer loop + vertex 1.5703 1.87546 2.52602 + vertex 1.56854 1.87872 2.52568 + vertex 1.56549 1.87552 2.52684 + endloop + endfacet + facet normal 0.167665 0.198897 0.965572 + outer loop + vertex 1.5703 1.87546 2.52602 + vertex 1.56549 1.87552 2.52684 + vertex 1.57046 1.87075 2.52696 + endloop + endfacet + facet normal 0.150142 0.198885 0.968453 + outer loop + vertex 1.5703 1.87546 2.52602 + vertex 1.57046 1.87075 2.52696 + vertex 1.57353 1.87395 2.52582 + endloop + endfacet + facet normal 0.14582 0.189285 0.971034 + outer loop + vertex 1.57353 1.87395 2.52582 + vertex 1.57356 1.87867 2.5249 + vertex 1.5703 1.87546 2.52602 + endloop + endfacet + facet normal 0.136642 0.211589 0.96776 + outer loop + vertex 1.57537 1.87106 2.5262 + vertex 1.57353 1.87395 2.52582 + vertex 1.57046 1.87075 2.52696 + endloop + endfacet + facet normal 0.13703 0.207489 0.968592 + outer loop + vertex 1.57537 1.87106 2.5262 + vertex 1.57046 1.87075 2.52696 + vertex 1.57515 1.8667 2.52716 + endloop + endfacet + facet normal 0.065239 0.212467 0.974988 + outer loop + vertex 1.57537 1.87106 2.5262 + vertex 1.57515 1.8667 2.52716 + vertex 1.5795 1.87018 2.52611 + endloop + endfacet + facet normal 0.123466 0.19199 0.973599 + outer loop + vertex 1.57046 1.87075 2.52696 + vertex 1.57052 1.86579 2.52793 + vertex 1.57515 1.8667 2.52716 + endloop + endfacet + facet normal 0.16653 0.191303 0.967301 + outer loop + vertex 1.57052 1.86579 2.52793 + vertex 1.57046 1.87075 2.52696 + vertex 1.56685 1.86707 2.52831 + endloop + endfacet + facet normal 0.164285 0.184344 0.969034 + outer loop + vertex 1.56757 1.86264 2.52903 + vertex 1.57052 1.86579 2.52793 + vertex 1.56685 1.86707 2.52831 + endloop + endfacet + facet normal 0.170682 0.185168 0.967771 + outer loop + vertex 1.56757 1.86264 2.52903 + vertex 1.56685 1.86707 2.52831 + vertex 1.56272 1.86407 2.52961 + endloop + endfacet + facet normal 0.170289 0.183697 0.96812 + outer loop + vertex 1.56406 1.85927 2.53028 + vertex 1.56757 1.86264 2.52903 + vertex 1.56272 1.86407 2.52961 + endloop + endfacet + facet normal 0.167495 0.183006 0.968739 + outer loop + vertex 1.56406 1.85927 2.53028 + vertex 1.56272 1.86407 2.52961 + vertex 1.55966 1.85984 2.53094 + endloop + endfacet + facet normal 0.167634 0.184411 0.968448 + outer loop + vertex 1.56105 1.8563 2.53137 + vertex 1.56406 1.85927 2.53028 + vertex 1.55966 1.85984 2.53094 + endloop + endfacet + facet normal 0.159395 0.181418 0.970402 + outer loop + vertex 1.55966 1.85984 2.53094 + vertex 1.55671 1.85548 2.53224 + vertex 1.56105 1.8563 2.53137 + endloop + endfacet + facet normal 0.159423 0.181292 0.970421 + outer loop + vertex 1.56105 1.8563 2.53137 + vertex 1.55671 1.85548 2.53224 + vertex 1.56046 1.85173 2.53232 + endloop + endfacet + facet normal 0.173132 0.179107 0.968476 + outer loop + vertex 1.56105 1.8563 2.53137 + vertex 1.56046 1.85173 2.53232 + vertex 1.56473 1.85473 2.531 + endloop + endfacet + facet normal 0.17148 0.181404 0.968343 + outer loop + vertex 1.56588 1.8497 2.53174 + vertex 1.56473 1.85473 2.531 + vertex 1.56046 1.85173 2.53232 + endloop + endfacet + facet normal 0.172415 0.184094 0.967669 + outer loop + vertex 1.56175 1.84681 2.53303 + vertex 1.56588 1.8497 2.53174 + vertex 1.56046 1.85173 2.53232 + endloop + endfacet + facet normal 0.171312 0.185628 0.967571 + outer loop + vertex 1.56551 1.84525 2.53266 + vertex 1.56588 1.8497 2.53174 + vertex 1.56175 1.84681 2.53303 + endloop + endfacet + facet normal 0.169205 0.180218 0.968964 + outer loop + vertex 1.56261 1.84252 2.53368 + vertex 1.56551 1.84525 2.53266 + vertex 1.56175 1.84681 2.53303 + endloop + endfacet + facet normal 0.165767 0.179636 0.969666 + outer loop + vertex 1.56261 1.84252 2.53368 + vertex 1.56175 1.84681 2.53303 + vertex 1.55882 1.84393 2.53406 + endloop + endfacet + facet normal 0.164116 0.17488 0.970816 + outer loop + vertex 1.55888 1.83899 2.53494 + vertex 1.56261 1.84252 2.53368 + vertex 1.55882 1.84393 2.53406 + endloop + endfacet + facet normal 0.15805 0.174987 0.971802 + outer loop + vertex 1.55376 1.84396 2.53488 + vertex 1.55888 1.83899 2.53494 + vertex 1.55882 1.84393 2.53406 + endloop + endfacet + facet normal 0.157942 0.179819 0.970937 + outer loop + vertex 1.55882 1.84393 2.53406 + vertex 1.55736 1.84765 2.53361 + vertex 1.55376 1.84396 2.53488 + endloop + endfacet + facet normal 0.156266 0.181448 0.970905 + outer loop + vertex 1.55376 1.84396 2.53488 + vertex 1.55736 1.84765 2.53361 + vertex 1.55363 1.84867 2.53402 + endloop + endfacet + facet normal 0.174268 0.181366 0.967852 + outer loop + vertex 1.54865 1.84886 2.53488 + vertex 1.55376 1.84396 2.53488 + vertex 1.55363 1.84867 2.53402 + endloop + endfacet + facet normal 0.174312 0.188192 0.96654 + outer loop + vertex 1.55363 1.84867 2.53402 + vertex 1.5526 1.85233 2.53349 + vertex 1.54865 1.84886 2.53488 + endloop + endfacet + facet normal 0.17407 0.188465 0.96653 + outer loop + vertex 1.54865 1.84886 2.53488 + vertex 1.5526 1.85233 2.53349 + vertex 1.54875 1.85377 2.53391 + endloop + endfacet + facet normal 0.201288 0.186926 0.961531 + outer loop + vertex 1.54344 1.85386 2.535 + vertex 1.54865 1.84886 2.53488 + vertex 1.54875 1.85377 2.53391 + endloop + endfacet + facet normal 0.201349 0.184162 0.962051 + outer loop + vertex 1.54875 1.85377 2.53391 + vertex 1.54726 1.85764 2.53348 + vertex 1.54344 1.85386 2.535 + endloop + endfacet + facet normal 0.179549 0.176386 0.967807 + outer loop + vertex 1.54875 1.85377 2.53391 + vertex 1.55185 1.85679 2.53278 + vertex 1.54726 1.85764 2.53348 + endloop + endfacet + facet normal 0.179665 0.177151 0.967646 + outer loop + vertex 1.55185 1.85679 2.53278 + vertex 1.5502 1.86186 2.53216 + vertex 1.54726 1.85764 2.53348 + endloop + endfacet + facet normal 0.187721 0.171381 0.967155 + outer loop + vertex 1.54726 1.85764 2.53348 + vertex 1.5502 1.86186 2.53216 + vertex 1.54573 1.86133 2.53312 + endloop + endfacet + facet normal 0.190593 0.172499 0.966394 + outer loop + vertex 1.54726 1.85764 2.53348 + vertex 1.54573 1.86133 2.53312 + vertex 1.54334 1.85872 2.53406 + endloop + endfacet + facet normal 0.187158 0.175115 0.966595 + outer loop + vertex 1.54555 1.86611 2.53229 + vertex 1.54573 1.86133 2.53312 + vertex 1.5502 1.86186 2.53216 + endloop + endfacet + facet normal 0.188245 0.176317 0.966166 + outer loop + vertex 1.55055 1.86637 2.53127 + vertex 1.54555 1.86611 2.53229 + vertex 1.5502 1.86186 2.53216 + endloop + endfacet + facet normal 0.175777 0.17769 0.968261 + outer loop + vertex 1.55055 1.86637 2.53127 + vertex 1.5502 1.86186 2.53216 + vertex 1.55452 1.86487 2.53082 + endloop + endfacet + facet normal 0.178627 0.185795 0.966216 + outer loop + vertex 1.55452 1.86487 2.53082 + vertex 1.55336 1.86983 2.53008 + vertex 1.55055 1.86637 2.53127 + endloop + endfacet + facet normal 0.192856 0.174059 0.965666 + outer loop + vertex 1.54874 1.86944 2.53108 + vertex 1.55055 1.86637 2.53127 + vertex 1.55336 1.86983 2.53008 + endloop + endfacet + facet normal 0.191398 0.186104 0.963707 + outer loop + vertex 1.54874 1.86944 2.53108 + vertex 1.55336 1.86983 2.53008 + vertex 1.54874 1.87409 2.53018 + endloop + endfacet + facet normal 0.201418 0.185712 0.961739 + outer loop + vertex 1.54874 1.86944 2.53108 + vertex 1.54874 1.87409 2.53018 + vertex 1.54546 1.87084 2.53149 + endloop + endfacet + facet normal 0.193859 0.16659 0.966781 + outer loop + vertex 1.54546 1.87084 2.53149 + vertex 1.54555 1.86611 2.53229 + vertex 1.54874 1.86944 2.53108 + endloop + endfacet + facet normal 0.108426 0.167197 0.979943 + outer loop + vertex 1.54546 1.87084 2.53149 + vertex 1.54093 1.87045 2.53206 + vertex 1.54555 1.86611 2.53229 + endloop + endfacet + facet normal 0.206002 0.18104 0.961659 + outer loop + vertex 1.54378 1.87382 2.53129 + vertex 1.54546 1.87084 2.53149 + vertex 1.54874 1.87409 2.53018 + endloop + endfacet + facet normal 0.1986 0.193977 0.960693 + outer loop + vertex 1.54874 1.87409 2.53018 + vertex 1.55336 1.86983 2.53008 + vertex 1.55391 1.87412 2.5291 + endloop + endfacet + facet normal 0.198232 0.201772 0.959162 + outer loop + vertex 1.55391 1.87412 2.5291 + vertex 1.55263 1.87764 2.52863 + vertex 1.54874 1.87409 2.53018 + endloop + endfacet + facet normal 0.201743 0.197955 0.959226 + outer loop + vertex 1.54874 1.87409 2.53018 + vertex 1.55263 1.87764 2.52863 + vertex 1.54878 1.87888 2.52918 + endloop + endfacet + facet normal 0.178407 0.199047 0.963614 + outer loop + vertex 1.54388 1.8784 2.53019 + vertex 1.54874 1.87409 2.53018 + vertex 1.54878 1.87888 2.52918 + endloop + endfacet + facet normal 0.181411 0.176381 0.967461 + outer loop + vertex 1.54878 1.87888 2.52918 + vertex 1.54723 1.88258 2.5288 + vertex 1.54388 1.8784 2.53019 + endloop + endfacet + facet normal 0.201843 0.18437 0.961908 + outer loop + vertex 1.54878 1.87888 2.52918 + vertex 1.55174 1.88186 2.52799 + vertex 1.54723 1.88258 2.5288 + endloop + endfacet + facet normal 0.200674 0.174717 0.963952 + outer loop + vertex 1.55174 1.88186 2.52799 + vertex 1.55015 1.88691 2.5274 + vertex 1.54723 1.88258 2.5288 + endloop + endfacet + facet normal 0.19187 0.17221 0.966193 + outer loop + vertex 1.55174 1.88186 2.52799 + vertex 1.55594 1.88477 2.52664 + vertex 1.55015 1.88691 2.5274 + endloop + endfacet + facet normal 0.186673 0.179587 0.965868 + outer loop + vertex 1.55558 1.88031 2.52753 + vertex 1.55594 1.88477 2.52664 + vertex 1.55174 1.88186 2.52799 + endloop + endfacet + facet normal 0.188968 0.185747 0.964256 + outer loop + vertex 1.55263 1.87764 2.52863 + vertex 1.55558 1.88031 2.52753 + vertex 1.55174 1.88186 2.52799 + endloop + endfacet + facet normal 0.178254 0.197468 0.963967 + outer loop + vertex 1.55689 1.87675 2.52802 + vertex 1.55558 1.88031 2.52753 + vertex 1.55263 1.87764 2.52863 + endloop + endfacet + facet normal 0.198746 0.187462 0.961955 + outer loop + vertex 1.55263 1.87764 2.52863 + vertex 1.55174 1.88186 2.52799 + vertex 1.54878 1.87888 2.52918 + endloop + endfacet + facet normal 0.177837 0.195077 0.96453 + outer loop + vertex 1.55391 1.87412 2.5291 + vertex 1.55689 1.87675 2.52802 + vertex 1.55263 1.87764 2.52863 + endloop + endfacet + facet normal 0.171933 0.201651 0.964249 + outer loop + vertex 1.55774 1.87261 2.52874 + vertex 1.55689 1.87675 2.52802 + vertex 1.55391 1.87412 2.5291 + endloop + endfacet + facet normal 0.160247 0.199684 0.966668 + outer loop + vertex 1.55774 1.87261 2.52874 + vertex 1.56063 1.87546 2.52767 + vertex 1.55689 1.87675 2.52802 + endloop + endfacet + facet normal 0.15882 0.195269 0.967805 + outer loop + vertex 1.56063 1.87546 2.52767 + vertex 1.56046 1.88035 2.52671 + vertex 1.55689 1.87675 2.52802 + endloop + endfacet + facet normal 0.162074 0.192069 0.967906 + outer loop + vertex 1.55689 1.87675 2.52802 + vertex 1.56046 1.88035 2.52671 + vertex 1.55558 1.88031 2.52753 + endloop + endfacet + facet normal 0.162448 0.182322 0.969726 + outer loop + vertex 1.55594 1.88477 2.52664 + vertex 1.55558 1.88031 2.52753 + vertex 1.56046 1.88035 2.52671 + endloop + endfacet + facet normal 0.159499 0.200431 0.966637 + outer loop + vertex 1.56213 1.87178 2.52818 + vertex 1.56063 1.87546 2.52767 + vertex 1.55774 1.87261 2.52874 + endloop + endfacet + facet normal 0.158832 0.196205 0.967614 + outer loop + vertex 1.55896 1.86782 2.52951 + vertex 1.56213 1.87178 2.52818 + vertex 1.55774 1.87261 2.52874 + endloop + endfacet + facet normal 0.15952 0.195655 0.967612 + outer loop + vertex 1.56342 1.86833 2.52867 + vertex 1.56213 1.87178 2.52818 + vertex 1.55896 1.86782 2.52951 + endloop + endfacet + facet normal 0.160713 0.187598 0.969009 + outer loop + vertex 1.55896 1.86782 2.52951 + vertex 1.56272 1.86407 2.52961 + vertex 1.56342 1.86833 2.52867 + endloop + endfacet + facet normal 0.16185 0.18873 0.9686 + outer loop + vertex 1.55827 1.86337 2.53049 + vertex 1.56272 1.86407 2.52961 + vertex 1.55896 1.86782 2.52951 + endloop + endfacet + facet normal 0.165308 0.197627 0.966239 + outer loop + vertex 1.56342 1.86833 2.52867 + vertex 1.56581 1.87074 2.52777 + vertex 1.56213 1.87178 2.52818 + endloop + endfacet + facet normal 0.165596 0.19875 0.965959 + outer loop + vertex 1.56581 1.87074 2.52777 + vertex 1.56549 1.87552 2.52684 + vertex 1.56213 1.87178 2.52818 + endloop + endfacet + facet normal 0.172043 0.191018 0.966392 + outer loop + vertex 1.56685 1.86707 2.52831 + vertex 1.56581 1.87074 2.52777 + vertex 1.56342 1.86833 2.52867 + endloop + endfacet + facet normal 0.16247 0.201545 0.965911 + outer loop + vertex 1.56213 1.87178 2.52818 + vertex 1.56549 1.87552 2.52684 + vertex 1.56063 1.87546 2.52767 + endloop + endfacet + facet normal 0.170788 0.198561 0.965093 + outer loop + vertex 1.55336 1.86983 2.53008 + vertex 1.55774 1.87261 2.52874 + vertex 1.55391 1.87412 2.5291 + endloop + endfacet + facet normal 0.170622 0.198811 0.965071 + outer loop + vertex 1.55896 1.86782 2.52951 + vertex 1.55774 1.87261 2.52874 + vertex 1.55336 1.86983 2.53008 + endloop + endfacet + facet normal 0.165387 0.183133 0.969077 + outer loop + vertex 1.55336 1.86983 2.53008 + vertex 1.55452 1.86487 2.53082 + vertex 1.55896 1.86782 2.52951 + endloop + endfacet + facet normal 0.161504 0.188794 0.968645 + outer loop + vertex 1.55452 1.86487 2.53082 + vertex 1.55827 1.86337 2.53049 + vertex 1.55896 1.86782 2.52951 + endloop + endfacet + facet normal 0.159418 0.18324 0.970056 + outer loop + vertex 1.55827 1.86337 2.53049 + vertex 1.55452 1.86487 2.53082 + vertex 1.55526 1.86033 2.53156 + endloop + endfacet + facet normal 0.170736 0.184732 0.967845 + outer loop + vertex 1.55526 1.86033 2.53156 + vertex 1.55452 1.86487 2.53082 + vertex 1.5502 1.86186 2.53216 + endloop + endfacet + facet normal 0.188645 0.171648 0.966928 + outer loop + vertex 1.55055 1.86637 2.53127 + vertex 1.54874 1.86944 2.53108 + vertex 1.54555 1.86611 2.53229 + endloop + endfacet + facet normal 0.174148 0.175049 0.969036 + outer loop + vertex 1.54573 1.86133 2.53312 + vertex 1.54555 1.86611 2.53229 + vertex 1.54198 1.86233 2.53361 + endloop + endfacet + facet normal 0.167672 0.173584 0.97044 + outer loop + vertex 1.55185 1.85679 2.53278 + vertex 1.55526 1.86033 2.53156 + vertex 1.5502 1.86186 2.53216 + endloop + endfacet + facet normal 0.157854 0.183022 0.970353 + outer loop + vertex 1.55671 1.85548 2.53224 + vertex 1.55526 1.86033 2.53156 + vertex 1.55185 1.85679 2.53278 + endloop + endfacet + facet normal 0.157523 0.181675 0.97066 + outer loop + vertex 1.5526 1.85233 2.53349 + vertex 1.55671 1.85548 2.53224 + vertex 1.55185 1.85679 2.53278 + endloop + endfacet + facet normal 0.156157 0.183413 0.970554 + outer loop + vertex 1.55611 1.8511 2.53316 + vertex 1.55671 1.85548 2.53224 + vertex 1.5526 1.85233 2.53349 + endloop + endfacet + facet normal 0.16079 0.182652 0.96994 + outer loop + vertex 1.55671 1.85548 2.53224 + vertex 1.55611 1.8511 2.53316 + vertex 1.56046 1.85173 2.53232 + endloop + endfacet + facet normal 0.160476 0.184443 0.969654 + outer loop + vertex 1.55736 1.84765 2.53361 + vertex 1.56046 1.85173 2.53232 + vertex 1.55611 1.8511 2.53316 + endloop + endfacet + facet normal 0.163596 0.182055 0.969584 + outer loop + vertex 1.56175 1.84681 2.53303 + vertex 1.56046 1.85173 2.53232 + vertex 1.55736 1.84765 2.53361 + endloop + endfacet + facet normal 0.172409 0.183702 0.967744 + outer loop + vertex 1.5526 1.85233 2.53349 + vertex 1.55185 1.85679 2.53278 + vertex 1.54875 1.85377 2.53391 + endloop + endfacet + facet normal 0.156235 0.183653 0.970496 + outer loop + vertex 1.55363 1.84867 2.53402 + vertex 1.55611 1.8511 2.53316 + vertex 1.5526 1.85233 2.53349 + endloop + endfacet + facet normal 0.172284 0.179298 0.968592 + outer loop + vertex 1.54874 1.84407 2.53575 + vertex 1.55376 1.84396 2.53488 + vertex 1.54865 1.84886 2.53488 + endloop + endfacet + facet normal 0.200548 0.178847 0.963221 + outer loop + vertex 1.54874 1.84407 2.53575 + vertex 1.54865 1.84886 2.53488 + vertex 1.54532 1.84574 2.53615 + endloop + endfacet + facet normal 0.201153 0.180173 0.962847 + outer loop + vertex 1.54532 1.84574 2.53615 + vertex 1.5455 1.84077 2.53705 + vertex 1.54874 1.84407 2.53575 + endloop + endfacet + facet normal 0.197338 0.180171 0.963637 + outer loop + vertex 1.54532 1.84574 2.53615 + vertex 1.54039 1.84563 2.53718 + vertex 1.5455 1.84077 2.53705 + endloop + endfacet + facet normal 0.188999 0.171296 0.966921 + outer loop + vertex 1.54039 1.84563 2.53718 + vertex 1.54052 1.84047 2.53807 + vertex 1.5455 1.84077 2.53705 + endloop + endfacet + facet normal 0.189299 0.168099 0.967424 + outer loop + vertex 1.5419 1.83684 2.53843 + vertex 1.5455 1.84077 2.53705 + vertex 1.54052 1.84047 2.53807 + endloop + endfacet + facet normal 0.0924984 0.133044 0.986784 + outer loop + vertex 1.5419 1.83684 2.53843 + vertex 1.54052 1.84047 2.53807 + vertex 1.53783 1.83705 2.53879 + endloop + endfacet + facet normal 0.187793 0.169497 0.967473 + outer loop + vertex 1.54563 1.83577 2.5379 + vertex 1.5455 1.84077 2.53705 + vertex 1.5419 1.83684 2.53843 + endloop + endfacet + facet normal 0.186707 0.165253 0.968417 + outer loop + vertex 1.54274 1.83276 2.53897 + vertex 1.54563 1.83577 2.5379 + vertex 1.5419 1.83684 2.53843 + endloop + endfacet + facet normal 0.133771 0.155798 0.978689 + outer loop + vertex 1.54274 1.83276 2.53897 + vertex 1.5419 1.83684 2.53843 + vertex 1.53914 1.83358 2.53933 + endloop + endfacet + facet normal 0.190353 0.161705 0.968306 + outer loop + vertex 1.54698 1.83204 2.53825 + vertex 1.54563 1.83577 2.5379 + vertex 1.54274 1.83276 2.53897 + endloop + endfacet + facet normal 0.190799 0.164988 0.967665 + outer loop + vertex 1.54401 1.82914 2.53934 + vertex 1.54698 1.83204 2.53825 + vertex 1.54274 1.83276 2.53897 + endloop + endfacet + facet normal 0.163351 0.156009 0.974155 + outer loop + vertex 1.54401 1.82914 2.53934 + vertex 1.54274 1.83276 2.53897 + vertex 1.53894 1.82877 2.54024 + endloop + endfacet + facet normal 0.161589 0.173732 0.971446 + outer loop + vertex 1.53894 1.82877 2.54024 + vertex 1.54389 1.82426 2.54023 + vertex 1.54401 1.82914 2.53934 + endloop + endfacet + facet normal 0.189804 0.172165 0.966609 + outer loop + vertex 1.54389 1.82426 2.54023 + vertex 1.5478 1.82781 2.53883 + vertex 1.54401 1.82914 2.53934 + endloop + endfacet + facet normal 0.189805 0.172164 0.966609 + outer loop + vertex 1.54908 1.82407 2.53924 + vertex 1.5478 1.82781 2.53883 + vertex 1.54389 1.82426 2.54023 + endloop + endfacet + facet normal 0.189785 0.165256 0.967818 + outer loop + vertex 1.54389 1.82426 2.54023 + vertex 1.54899 1.81918 2.54009 + vertex 1.54908 1.82407 2.53924 + endloop + endfacet + facet normal 0.168384 0.166308 0.971591 + outer loop + vertex 1.54899 1.81918 2.54009 + vertex 1.55283 1.82266 2.53883 + vertex 1.54908 1.82407 2.53924 + endloop + endfacet + facet normal 0.169855 0.170492 0.970609 + outer loop + vertex 1.55283 1.82266 2.53883 + vertex 1.55205 1.82689 2.53823 + vertex 1.54908 1.82407 2.53924 + endloop + endfacet + facet normal 0.161311 0.169153 0.972299 + outer loop + vertex 1.55283 1.82266 2.53883 + vertex 1.55573 1.82559 2.53784 + vertex 1.55205 1.82689 2.53823 + endloop + endfacet + facet normal 0.161674 0.170254 0.972047 + outer loop + vertex 1.55573 1.82559 2.53784 + vertex 1.5557 1.83076 2.53694 + vertex 1.55205 1.82689 2.53823 + endloop + endfacet + facet normal 0.163312 0.168705 0.972043 + outer loop + vertex 1.55205 1.82689 2.53823 + vertex 1.5557 1.83076 2.53694 + vertex 1.55073 1.83069 2.53779 + endloop + endfacet + facet normal 0.174244 0.172191 0.96953 + outer loop + vertex 1.55205 1.82689 2.53823 + vertex 1.55073 1.83069 2.53779 + vertex 1.5478 1.82781 2.53883 + endloop + endfacet + facet normal 0.180129 0.166195 0.969501 + outer loop + vertex 1.5478 1.82781 2.53883 + vertex 1.55073 1.83069 2.53779 + vertex 1.54698 1.83204 2.53825 + endloop + endfacet + facet normal 0.180489 0.167286 0.969247 + outer loop + vertex 1.55073 1.83069 2.53779 + vertex 1.55066 1.83582 2.53692 + vertex 1.54698 1.83204 2.53825 + endloop + endfacet + facet normal 0.16336 0.167543 0.972236 + outer loop + vertex 1.55066 1.83582 2.53692 + vertex 1.55073 1.83069 2.53779 + vertex 1.5557 1.83076 2.53694 + endloop + endfacet + facet normal 0.167652 0.17181 0.97076 + outer loop + vertex 1.55564 1.83582 2.53606 + vertex 1.55066 1.83582 2.53692 + vertex 1.5557 1.83076 2.53694 + endloop + endfacet + facet normal 0.160549 0.171926 0.971939 + outer loop + vertex 1.55564 1.83582 2.53606 + vertex 1.5557 1.83076 2.53694 + vertex 1.55892 1.8341 2.53582 + endloop + endfacet + facet normal 0.162396 0.175589 0.970977 + outer loop + vertex 1.55892 1.8341 2.53582 + vertex 1.55888 1.83899 2.53494 + vertex 1.55564 1.83582 2.53606 + endloop + endfacet + facet normal 0.159998 0.178023 0.970932 + outer loop + vertex 1.55389 1.83912 2.53574 + vertex 1.55564 1.83582 2.53606 + vertex 1.55888 1.83899 2.53494 + endloop + endfacet + facet normal 0.165113 0.175532 0.970529 + outer loop + vertex 1.55892 1.8341 2.53582 + vertex 1.5638 1.83401 2.53501 + vertex 1.55888 1.83899 2.53494 + endloop + endfacet + facet normal 0.164296 0.174728 0.970813 + outer loop + vertex 1.55888 1.83899 2.53494 + vertex 1.5638 1.83401 2.53501 + vertex 1.56393 1.83881 2.53412 + endloop + endfacet + facet normal 0.165168 0.170564 0.971405 + outer loop + vertex 1.55892 1.8341 2.53582 + vertex 1.56058 1.83082 2.53611 + vertex 1.5638 1.83401 2.53501 + endloop + endfacet + facet normal 0.166534 0.169186 0.971413 + outer loop + vertex 1.56373 1.82924 2.53585 + vertex 1.5638 1.83401 2.53501 + vertex 1.56058 1.83082 2.53611 + endloop + endfacet + facet normal 0.165923 0.167912 0.971738 + outer loop + vertex 1.56058 1.83082 2.53611 + vertex 1.56058 1.82584 2.53697 + vertex 1.56373 1.82924 2.53585 + endloop + endfacet + facet normal 0.164587 0.169153 0.97175 + outer loop + vertex 1.56547 1.8261 2.5361 + vertex 1.56373 1.82924 2.53585 + vertex 1.56058 1.82584 2.53697 + endloop + endfacet + facet normal 0.164447 0.170888 0.97147 + outer loop + vertex 1.56547 1.8261 2.5361 + vertex 1.56058 1.82584 2.53697 + vertex 1.56518 1.82147 2.53696 + endloop + endfacet + facet normal 0.134504 0.173508 0.975604 + outer loop + vertex 1.56547 1.8261 2.5361 + vertex 1.56518 1.82147 2.53696 + vertex 1.56949 1.82455 2.53582 + endloop + endfacet + facet normal 0.16148 0.16777 0.972511 + outer loop + vertex 1.56058 1.82584 2.53697 + vertex 1.56058 1.82073 2.53785 + vertex 1.56518 1.82147 2.53696 + endloop + endfacet + facet normal 0.162835 0.160524 0.973507 + outer loop + vertex 1.56201 1.81705 2.53822 + vertex 1.56518 1.82147 2.53696 + vertex 1.56058 1.82073 2.53785 + endloop + endfacet + facet normal 0.168109 0.162438 0.972293 + outer loop + vertex 1.56201 1.81705 2.53822 + vertex 1.56058 1.82073 2.53785 + vertex 1.55775 1.81766 2.53886 + endloop + endfacet + facet normal 0.167868 0.160349 0.972681 + outer loop + vertex 1.55899 1.81398 2.53925 + vertex 1.56201 1.81705 2.53822 + vertex 1.55775 1.81766 2.53886 + endloop + endfacet + facet normal 0.16568 0.159663 0.973169 + outer loop + vertex 1.55899 1.81398 2.53925 + vertex 1.55775 1.81766 2.53886 + vertex 1.55396 1.8141 2.54009 + endloop + endfacet + facet normal 0.165675 0.162131 0.972762 + outer loop + vertex 1.55396 1.8141 2.54009 + vertex 1.55885 1.80905 2.54009 + vertex 1.55899 1.81398 2.53925 + endloop + endfacet + facet normal 0.167467 0.163867 0.972164 + outer loop + vertex 1.55398 1.80927 2.5409 + vertex 1.55885 1.80905 2.54009 + vertex 1.55396 1.8141 2.54009 + endloop + endfacet + facet normal 0.161407 0.164018 0.973163 + outer loop + vertex 1.55398 1.80927 2.5409 + vertex 1.55396 1.8141 2.54009 + vertex 1.55075 1.811 2.54114 + endloop + endfacet + facet normal 0.15769 0.156815 0.974958 + outer loop + vertex 1.55075 1.811 2.54114 + vertex 1.55085 1.80596 2.54194 + vertex 1.55398 1.80927 2.5409 + endloop + endfacet + facet normal 0.157343 0.157143 0.974961 + outer loop + vertex 1.55566 1.806 2.54115 + vertex 1.55398 1.80927 2.5409 + vertex 1.55085 1.80596 2.54194 + endloop + endfacet + facet normal 0.171844 0.156712 0.97258 + outer loop + vertex 1.55075 1.811 2.54114 + vertex 1.54581 1.81101 2.54201 + vertex 1.55085 1.80596 2.54194 + endloop + endfacet + facet normal 0.160793 0.145654 0.976182 + outer loop + vertex 1.54581 1.81101 2.54201 + vertex 1.5459 1.80582 2.54277 + vertex 1.55085 1.80596 2.54194 + endloop + endfacet + facet normal 0.160862 0.144337 0.976366 + outer loop + vertex 1.54709 1.80201 2.54314 + vertex 1.55085 1.80596 2.54194 + vertex 1.5459 1.80582 2.54277 + endloop + endfacet + facet normal 0.178256 0.149417 0.972574 + outer loop + vertex 1.54709 1.80201 2.54314 + vertex 1.5459 1.80582 2.54277 + vertex 1.54279 1.80282 2.5438 + endloop + endfacet + facet normal 0.176826 0.140537 0.974157 + outer loop + vertex 1.5438 1.79913 2.54415 + vertex 1.54709 1.80201 2.54314 + vertex 1.54279 1.80282 2.5438 + endloop + endfacet + facet normal 0.20513 0.147631 0.967536 + outer loop + vertex 1.5438 1.79913 2.54415 + vertex 1.54279 1.80282 2.5438 + vertex 1.53852 1.79915 2.54527 + endloop + endfacet + facet normal 0.199387 0.154394 0.967681 + outer loop + vertex 1.53852 1.79915 2.54527 + vertex 1.54279 1.80282 2.5438 + vertex 1.53894 1.80404 2.5444 + endloop + endfacet + facet normal 0.196775 0.145207 0.969636 + outer loop + vertex 1.54279 1.80282 2.5438 + vertex 1.54208 1.80707 2.54331 + vertex 1.53894 1.80404 2.5444 + endloop + endfacet + facet normal 0.196692 0.145295 0.96964 + outer loop + vertex 1.53894 1.80404 2.5444 + vertex 1.54208 1.80707 2.54331 + vertex 1.5377 1.80775 2.5441 + endloop + endfacet + facet normal 0.17529 0.138574 0.974716 + outer loop + vertex 1.53894 1.80404 2.5444 + vertex 1.5377 1.80775 2.5441 + vertex 1.5339 1.80363 2.54537 + endloop + endfacet + facet normal 0.195962 0.139384 0.970655 + outer loop + vertex 1.54208 1.80707 2.54331 + vertex 1.5407 1.8109 2.54304 + vertex 1.5377 1.80775 2.5441 + endloop + endfacet + facet normal 0.184055 0.150916 0.971261 + outer loop + vertex 1.5377 1.80775 2.5441 + vertex 1.5407 1.8109 2.54304 + vertex 1.53685 1.81207 2.54359 + endloop + endfacet + facet normal 0.128653 0.141193 0.981587 + outer loop + vertex 1.5377 1.80775 2.5441 + vertex 1.53685 1.81207 2.54359 + vertex 1.53405 1.80869 2.54444 + endloop + endfacet + facet normal 0.183715 0.14968 0.971517 + outer loop + vertex 1.5407 1.8109 2.54304 + vertex 1.54059 1.81612 2.54226 + vertex 1.53685 1.81207 2.54359 + endloop + endfacet + facet normal 0.167516 0.164839 0.971991 + outer loop + vertex 1.53685 1.81207 2.54359 + vertex 1.54059 1.81612 2.54226 + vertex 1.53548 1.81588 2.54318 + endloop + endfacet + facet normal 0.0624929 0.12907 0.989664 + outer loop + vertex 1.53685 1.81207 2.54359 + vertex 1.53548 1.81588 2.54318 + vertex 1.53275 1.81244 2.5438 + endloop + endfacet + facet normal 0.166801 0.174425 0.97044 + outer loop + vertex 1.5356 1.82084 2.54227 + vertex 1.53548 1.81588 2.54318 + vertex 1.54059 1.81612 2.54226 + endloop + endfacet + facet normal 0.147909 0.154441 0.976868 + outer loop + vertex 1.54046 1.82117 2.54148 + vertex 1.5356 1.82084 2.54227 + vertex 1.54059 1.81612 2.54226 + endloop + endfacet + facet normal 0.201037 0.154323 0.967351 + outer loop + vertex 1.54046 1.82117 2.54148 + vertex 1.54059 1.81612 2.54226 + vertex 1.54389 1.81945 2.54104 + endloop + endfacet + facet normal 0.20503 0.162839 0.965115 + outer loop + vertex 1.54389 1.81945 2.54104 + vertex 1.54389 1.82426 2.54023 + vertex 1.54046 1.82117 2.54148 + endloop + endfacet + facet normal 0.197705 0.171028 0.965226 + outer loop + vertex 1.53873 1.82428 2.54128 + vertex 1.54046 1.82117 2.54148 + vertex 1.54389 1.82426 2.54023 + endloop + endfacet + facet normal 0.187957 0.1634 0.96849 + outer loop + vertex 1.54389 1.81945 2.54104 + vertex 1.54899 1.81918 2.54009 + vertex 1.54389 1.82426 2.54023 + endloop + endfacet + facet normal 0.187667 0.150064 0.970702 + outer loop + vertex 1.54389 1.81945 2.54104 + vertex 1.54569 1.8161 2.54121 + vertex 1.54899 1.81918 2.54009 + endloop + endfacet + facet normal 0.180913 0.15734 0.970832 + outer loop + vertex 1.54904 1.81431 2.54088 + vertex 1.54899 1.81918 2.54009 + vertex 1.54569 1.8161 2.54121 + endloop + endfacet + facet normal 0.181046 0.157599 0.970765 + outer loop + vertex 1.54569 1.8161 2.54121 + vertex 1.54581 1.81101 2.54201 + vertex 1.54904 1.81431 2.54088 + endloop + endfacet + facet normal 0.199223 0.157488 0.967216 + outer loop + vertex 1.54569 1.8161 2.54121 + vertex 1.54059 1.81612 2.54226 + vertex 1.54581 1.81101 2.54201 + endloop + endfacet + facet normal 0.162756 0.157692 0.973983 + outer loop + vertex 1.54904 1.81431 2.54088 + vertex 1.55396 1.8141 2.54009 + vertex 1.54899 1.81918 2.54009 + endloop + endfacet + facet normal 0.166831 0.161678 0.97264 + outer loop + vertex 1.54899 1.81918 2.54009 + vertex 1.55396 1.8141 2.54009 + vertex 1.55406 1.81896 2.53926 + endloop + endfacet + facet normal 0.199262 0.15611 0.967432 + outer loop + vertex 1.54569 1.8161 2.54121 + vertex 1.54389 1.81945 2.54104 + vertex 1.54059 1.81612 2.54226 + endloop + endfacet + facet normal 0.191664 0.149617 0.96999 + outer loop + vertex 1.54059 1.81612 2.54226 + vertex 1.5407 1.8109 2.54304 + vertex 1.54581 1.81101 2.54201 + endloop + endfacet + facet normal 0.19223 0.138102 0.971584 + outer loop + vertex 1.54208 1.80707 2.54331 + vertex 1.54581 1.81101 2.54201 + vertex 1.5407 1.8109 2.54304 + endloop + endfacet + facet normal 0.175588 0.141963 0.974174 + outer loop + vertex 1.54753 1.79763 2.5437 + vertex 1.54709 1.80201 2.54314 + vertex 1.5438 1.79913 2.54415 + endloop + endfacet + facet normal 0.156085 0.140493 0.977701 + outer loop + vertex 1.54753 1.79763 2.5437 + vertex 1.5508 1.80073 2.54273 + vertex 1.54709 1.80201 2.54314 + endloop + endfacet + facet normal 0.158163 0.146917 0.976422 + outer loop + vertex 1.5508 1.80073 2.54273 + vertex 1.55085 1.80596 2.54194 + vertex 1.54709 1.80201 2.54314 + endloop + endfacet + facet normal 0.158252 0.146914 0.976408 + outer loop + vertex 1.55085 1.80596 2.54194 + vertex 1.5508 1.80073 2.54273 + vertex 1.55577 1.80091 2.5419 + endloop + endfacet + facet normal 0.158788 0.137889 0.977636 + outer loop + vertex 1.55189 1.79674 2.54312 + vertex 1.55577 1.80091 2.5419 + vertex 1.5508 1.80073 2.54273 + endloop + endfacet + facet normal 0.160415 0.136357 0.977586 + outer loop + vertex 1.55574 1.79559 2.54264 + vertex 1.55577 1.80091 2.5419 + vertex 1.55189 1.79674 2.54312 + endloop + endfacet + facet normal 0.156887 0.12358 0.979854 + outer loop + vertex 1.55257 1.7923 2.54357 + vertex 1.55574 1.79559 2.54264 + vertex 1.55189 1.79674 2.54312 + endloop + endfacet + facet normal 0.159639 0.123953 0.979362 + outer loop + vertex 1.55257 1.7923 2.54357 + vertex 1.55189 1.79674 2.54312 + vertex 1.54817 1.79306 2.54419 + endloop + endfacet + facet normal 0.157915 0.112738 0.980996 + outer loop + vertex 1.54942 1.78909 2.54444 + vertex 1.55257 1.7923 2.54357 + vertex 1.54817 1.79306 2.54419 + endloop + endfacet + facet normal 0.17243 0.117096 0.978037 + outer loop + vertex 1.54942 1.78909 2.54444 + vertex 1.54817 1.79306 2.54419 + vertex 1.54489 1.78873 2.54529 + endloop + endfacet + facet normal 0.173449 0.106737 0.979042 + outer loop + vertex 1.54489 1.78873 2.54529 + vertex 1.54887 1.78418 2.54508 + vertex 1.54942 1.78909 2.54444 + endloop + endfacet + facet normal 0.15843 0.108694 0.981369 + outer loop + vertex 1.54887 1.78418 2.54508 + vertex 1.55311 1.78795 2.54398 + vertex 1.54942 1.78909 2.54444 + endloop + endfacet + facet normal 0.160861 0.105936 0.981275 + outer loop + vertex 1.55383 1.7841 2.54427 + vertex 1.55311 1.78795 2.54398 + vertex 1.54887 1.78418 2.54508 + endloop + endfacet + facet normal 0.160862 0.105654 0.981306 + outer loop + vertex 1.54887 1.78418 2.54508 + vertex 1.55279 1.77942 2.54495 + vertex 1.55383 1.7841 2.54427 + endloop + endfacet + facet normal 0.156447 0.106717 0.981904 + outer loop + vertex 1.55279 1.77942 2.54495 + vertex 1.55759 1.78264 2.54383 + vertex 1.55383 1.7841 2.54427 + endloop + endfacet + facet normal 0.156709 0.107429 0.981785 + outer loop + vertex 1.55759 1.78264 2.54383 + vertex 1.55738 1.78715 2.54337 + vertex 1.55383 1.7841 2.54427 + endloop + endfacet + facet normal 0.149819 0.10723 0.982881 + outer loop + vertex 1.55759 1.78264 2.54383 + vertex 1.56177 1.78646 2.54278 + vertex 1.55738 1.78715 2.54337 + endloop + endfacet + facet normal 0.151159 0.117025 0.981558 + outer loop + vertex 1.56177 1.78646 2.54278 + vertex 1.56075 1.79049 2.54245 + vertex 1.55738 1.78715 2.54337 + endloop + endfacet + facet normal 0.15671 0.111386 0.981344 + outer loop + vertex 1.55738 1.78715 2.54337 + vertex 1.56075 1.79049 2.54245 + vertex 1.55686 1.7916 2.54295 + endloop + endfacet + facet normal 0.160421 0.125457 0.979043 + outer loop + vertex 1.56075 1.79049 2.54245 + vertex 1.56079 1.7958 2.54177 + vertex 1.55686 1.7916 2.54295 + endloop + endfacet + facet normal 0.165151 0.120978 0.97882 + outer loop + vertex 1.55686 1.7916 2.54295 + vertex 1.56079 1.7958 2.54177 + vertex 1.55574 1.79559 2.54264 + endloop + endfacet + facet normal 0.133328 0.126181 0.983007 + outer loop + vertex 1.56079 1.7958 2.54177 + vertex 1.56075 1.79049 2.54245 + vertex 1.56589 1.79108 2.54168 + endloop + endfacet + facet normal 0.135022 0.113152 0.984361 + outer loop + vertex 1.56177 1.78646 2.54278 + vertex 1.56589 1.79108 2.54168 + vertex 1.56075 1.79049 2.54245 + endloop + endfacet + facet normal 0.139877 0.118163 0.983093 + outer loop + vertex 1.56217 1.78181 2.54328 + vertex 1.56177 1.78646 2.54278 + vertex 1.55759 1.78264 2.54383 + endloop + endfacet + facet normal 0.154472 0.109652 0.981893 + outer loop + vertex 1.55794 1.77784 2.54431 + vertex 1.55759 1.78264 2.54383 + vertex 1.55279 1.77942 2.54495 + endloop + endfacet + facet normal 0.155329 0.112629 0.981421 + outer loop + vertex 1.5546 1.77355 2.54533 + vertex 1.55794 1.77784 2.54431 + vertex 1.55279 1.77942 2.54495 + endloop + endfacet + facet normal 0.16243 0.114724 0.980028 + outer loop + vertex 1.5546 1.77355 2.54533 + vertex 1.55279 1.77942 2.54495 + vertex 1.54971 1.77517 2.54595 + endloop + endfacet + facet normal 0.164646 0.121897 0.978791 + outer loop + vertex 1.55125 1.77101 2.54621 + vertex 1.5546 1.77355 2.54533 + vertex 1.54971 1.77517 2.54595 + endloop + endfacet + facet normal 0.169908 0.123771 0.977656 + outer loop + vertex 1.54971 1.77517 2.54595 + vertex 1.54684 1.77062 2.54703 + vertex 1.55125 1.77101 2.54621 + endloop + endfacet + facet normal 0.16861 0.135714 0.976295 + outer loop + vertex 1.55125 1.77101 2.54621 + vertex 1.54684 1.77062 2.54703 + vertex 1.55108 1.76591 2.54695 + endloop + endfacet + facet normal 0.169153 0.135683 0.976206 + outer loop + vertex 1.55125 1.77101 2.54621 + vertex 1.55108 1.76591 2.54695 + vertex 1.55418 1.76917 2.54596 + endloop + endfacet + facet normal 0.1658 0.138914 0.976326 + outer loop + vertex 1.55568 1.76601 2.54616 + vertex 1.55418 1.76917 2.54596 + vertex 1.55108 1.76591 2.54695 + endloop + endfacet + facet normal 0.165414 0.147244 0.97517 + outer loop + vertex 1.55568 1.76601 2.54616 + vertex 1.55108 1.76591 2.54695 + vertex 1.55575 1.76114 2.54688 + endloop + endfacet + facet normal 0.146849 0.147413 0.978113 + outer loop + vertex 1.55568 1.76601 2.54616 + vertex 1.55575 1.76114 2.54688 + vertex 1.55868 1.76453 2.54593 + endloop + endfacet + facet normal 0.13997 0.133052 0.981176 + outer loop + vertex 1.55868 1.76453 2.54593 + vertex 1.55873 1.76904 2.54531 + vertex 1.55568 1.76601 2.54616 + endloop + endfacet + facet normal 0.0953114 0.134301 0.986346 + outer loop + vertex 1.55868 1.76453 2.54593 + vertex 1.56293 1.76502 2.54545 + vertex 1.55873 1.76904 2.54531 + endloop + endfacet + facet normal 0.0950486 0.136346 0.986091 + outer loop + vertex 1.55868 1.76453 2.54593 + vertex 1.56047 1.76164 2.54616 + vertex 1.56293 1.76502 2.54545 + endloop + endfacet + facet normal 0.0743534 0.151339 0.985682 + outer loop + vertex 1.5645 1.76059 2.54601 + vertex 1.56293 1.76502 2.54545 + vertex 1.56047 1.76164 2.54616 + endloop + endfacet + facet normal 0.0753665 0.155311 0.984986 + outer loop + vertex 1.56047 1.76164 2.54616 + vertex 1.56027 1.75709 2.54689 + vertex 1.5645 1.76059 2.54601 + endloop + endfacet + facet normal 0.134012 0.15184 0.979278 + outer loop + vertex 1.56047 1.76164 2.54616 + vertex 1.55575 1.76114 2.54688 + vertex 1.56027 1.75709 2.54689 + endloop + endfacet + facet normal 0.125313 0.142135 0.981883 + outer loop + vertex 1.55575 1.76114 2.54688 + vertex 1.55566 1.75588 2.54765 + vertex 1.56027 1.75709 2.54689 + endloop + endfacet + facet normal 0.12775 0.133358 0.9828 + outer loop + vertex 1.55686 1.75201 2.54802 + vertex 1.56027 1.75709 2.54689 + vertex 1.55566 1.75588 2.54765 + endloop + endfacet + facet normal 0.148923 0.13959 0.978947 + outer loop + vertex 1.55686 1.75201 2.54802 + vertex 1.55566 1.75588 2.54765 + vertex 1.55243 1.75251 2.54862 + endloop + endfacet + facet normal 0.147766 0.127311 0.980794 + outer loop + vertex 1.55299 1.74792 2.54914 + vertex 1.55686 1.75201 2.54802 + vertex 1.55243 1.75251 2.54862 + endloop + endfacet + facet normal 0.140563 0.13418 0.980937 + outer loop + vertex 1.55759 1.7474 2.54855 + vertex 1.55686 1.75201 2.54802 + vertex 1.55299 1.74792 2.54914 + endloop + endfacet + facet normal 0.155501 0.133252 0.978807 + outer loop + vertex 1.55243 1.75251 2.54862 + vertex 1.55566 1.75588 2.54765 + vertex 1.55203 1.75691 2.54809 + endloop + endfacet + facet normal 0.162463 0.133736 0.97761 + outer loop + vertex 1.55243 1.75251 2.54862 + vertex 1.55203 1.75691 2.54809 + vertex 1.5488 1.75395 2.54903 + endloop + endfacet + facet normal 0.160887 0.129524 0.978437 + outer loop + vertex 1.54791 1.74938 2.54978 + vertex 1.55243 1.75251 2.54862 + vertex 1.5488 1.75395 2.54903 + endloop + endfacet + facet normal 0.164511 0.128732 0.977939 + outer loop + vertex 1.54372 1.75414 2.54986 + vertex 1.54791 1.74938 2.54978 + vertex 1.5488 1.75395 2.54903 + endloop + endfacet + facet normal 0.164607 0.135381 0.977024 + outer loop + vertex 1.5488 1.75395 2.54903 + vertex 1.54784 1.75766 2.54868 + vertex 1.54372 1.75414 2.54986 + endloop + endfacet + facet normal 0.162199 0.138197 0.977033 + outer loop + vertex 1.54372 1.75414 2.54986 + vertex 1.54784 1.75766 2.54868 + vertex 1.54406 1.759 2.54912 + endloop + endfacet + facet normal 0.180927 0.136408 0.973991 + outer loop + vertex 1.53882 1.75919 2.55006 + vertex 1.54372 1.75414 2.54986 + vertex 1.54406 1.759 2.54912 + endloop + endfacet + facet normal 0.181013 0.145433 0.972668 + outer loop + vertex 1.54406 1.759 2.54912 + vertex 1.54292 1.76277 2.54877 + vertex 1.53882 1.75919 2.55006 + endloop + endfacet + facet normal 0.179221 0.147496 0.97269 + outer loop + vertex 1.53882 1.75919 2.55006 + vertex 1.54292 1.76277 2.54877 + vertex 1.53904 1.76417 2.54927 + endloop + endfacet + facet normal 0.197295 0.146169 0.969386 + outer loop + vertex 1.53363 1.76421 2.55036 + vertex 1.53882 1.75919 2.55006 + vertex 1.53904 1.76417 2.54927 + endloop + endfacet + facet normal 0.197533 0.135097 0.970943 + outer loop + vertex 1.53904 1.76417 2.54927 + vertex 1.53796 1.76813 2.54894 + vertex 1.53363 1.76421 2.55036 + endloop + endfacet + facet normal 0.180995 0.130891 0.974735 + outer loop + vertex 1.53904 1.76417 2.54927 + vertex 1.54247 1.76719 2.54823 + vertex 1.53796 1.76813 2.54894 + endloop + endfacet + facet normal 0.17961 0.123314 0.975979 + outer loop + vertex 1.54247 1.76719 2.54823 + vertex 1.54178 1.7719 2.54776 + vertex 1.53796 1.76813 2.54894 + endloop + endfacet + facet normal 0.182328 0.120517 0.975824 + outer loop + vertex 1.53796 1.76813 2.54894 + vertex 1.54178 1.7719 2.54776 + vertex 1.53733 1.77253 2.54851 + endloop + endfacet + facet normal 0.175478 0.119665 0.977184 + outer loop + vertex 1.53796 1.76813 2.54894 + vertex 1.53733 1.77253 2.54851 + vertex 1.53391 1.76923 2.54953 + endloop + endfacet + facet normal 0.180978 0.108931 0.977436 + outer loop + vertex 1.54178 1.7719 2.54776 + vertex 1.54051 1.77595 2.54754 + vertex 1.53733 1.77253 2.54851 + endloop + endfacet + facet normal 0.181533 0.108403 0.977392 + outer loop + vertex 1.53733 1.77253 2.54851 + vertex 1.54051 1.77595 2.54754 + vertex 1.53674 1.77687 2.54814 + endloop + endfacet + facet normal 0.156201 0.105397 0.982086 + outer loop + vertex 1.53733 1.77253 2.54851 + vertex 1.53674 1.77687 2.54814 + vertex 1.53284 1.77299 2.54918 + endloop + endfacet + facet normal 0.180255 0.102615 0.978253 + outer loop + vertex 1.54051 1.77595 2.54754 + vertex 1.54089 1.78111 2.54693 + vertex 1.53674 1.77687 2.54814 + endloop + endfacet + facet normal 0.178944 0.103925 0.978355 + outer loop + vertex 1.53674 1.77687 2.54814 + vertex 1.54089 1.78111 2.54693 + vertex 1.53592 1.78068 2.54789 + endloop + endfacet + facet normal 0.105512 0.0887385 0.990451 + outer loop + vertex 1.53674 1.77687 2.54814 + vertex 1.53592 1.78068 2.54789 + vertex 1.53231 1.77719 2.54858 + endloop + endfacet + facet normal 0.180319 0.0905001 0.979436 + outer loop + vertex 1.53681 1.78559 2.54727 + vertex 1.53592 1.78068 2.54789 + vertex 1.54089 1.78111 2.54693 + endloop + endfacet + facet normal 0.195512 0.104648 0.975102 + outer loop + vertex 1.54138 1.78613 2.54629 + vertex 1.53681 1.78559 2.54727 + vertex 1.54089 1.78111 2.54693 + endloop + endfacet + facet normal 0.201459 0.10392 0.973969 + outer loop + vertex 1.54138 1.78613 2.54629 + vertex 1.54089 1.78111 2.54693 + vertex 1.54428 1.78433 2.54588 + endloop + endfacet + facet normal 0.201879 0.104637 0.973805 + outer loop + vertex 1.54428 1.78433 2.54588 + vertex 1.54489 1.78873 2.54529 + vertex 1.54138 1.78613 2.54629 + endloop + endfacet + facet normal 0.203045 0.103039 0.973733 + outer loop + vertex 1.54138 1.78613 2.54629 + vertex 1.54489 1.78873 2.54529 + vertex 1.53981 1.79021 2.54619 + endloop + endfacet + facet normal 0.208264 0.123117 0.970293 + outer loop + vertex 1.54489 1.78873 2.54529 + vertex 1.54292 1.79453 2.54497 + vertex 1.53981 1.79021 2.54619 + endloop + endfacet + facet normal 0.217213 0.116362 0.969164 + outer loop + vertex 1.53813 1.79432 2.54607 + vertex 1.53981 1.79021 2.54619 + vertex 1.54292 1.79453 2.54497 + endloop + endfacet + facet normal 0.194452 0.11148 0.974557 + outer loop + vertex 1.54545 1.7812 2.54601 + vertex 1.54428 1.78433 2.54588 + vertex 1.54089 1.78111 2.54693 + endloop + endfacet + facet normal 0.194482 0.11077 0.974632 + outer loop + vertex 1.54545 1.7812 2.54601 + vertex 1.54089 1.78111 2.54693 + vertex 1.54488 1.77662 2.54664 + endloop + endfacet + facet normal 0.17969 0.11296 0.977216 + outer loop + vertex 1.54545 1.7812 2.54601 + vertex 1.54488 1.77662 2.54664 + vertex 1.54827 1.77935 2.54571 + endloop + endfacet + facet normal 0.175023 0.105602 0.978885 + outer loop + vertex 1.54827 1.77935 2.54571 + vertex 1.54887 1.78418 2.54508 + vertex 1.54545 1.7812 2.54601 + endloop + endfacet + facet normal 0.175119 0.118692 0.977367 + outer loop + vertex 1.54971 1.77517 2.54595 + vertex 1.54827 1.77935 2.54571 + vertex 1.54488 1.77662 2.54664 + endloop + endfacet + facet normal 0.175784 0.104713 0.978844 + outer loop + vertex 1.54428 1.78433 2.54588 + vertex 1.54545 1.7812 2.54601 + vertex 1.54887 1.78418 2.54508 + endloop + endfacet + facet normal 0.196077 0.100396 0.975435 + outer loop + vertex 1.53981 1.79021 2.54619 + vertex 1.53681 1.78559 2.54727 + vertex 1.54138 1.78613 2.54629 + endloop + endfacet + facet normal 0.184997 0.102164 0.977414 + outer loop + vertex 1.54089 1.78111 2.54693 + vertex 1.54051 1.77595 2.54754 + vertex 1.54488 1.77662 2.54664 + endloop + endfacet + facet normal 0.183709 0.109758 0.976834 + outer loop + vertex 1.54178 1.7719 2.54776 + vertex 1.54488 1.77662 2.54664 + vertex 1.54051 1.77595 2.54754 + endloop + endfacet + facet normal 0.170727 0.118603 0.978154 + outer loop + vertex 1.54684 1.77062 2.54703 + vertex 1.54488 1.77662 2.54664 + vertex 1.54178 1.7719 2.54776 + endloop + endfacet + facet normal 0.171574 0.122294 0.977551 + outer loop + vertex 1.54247 1.76719 2.54823 + vertex 1.54684 1.77062 2.54703 + vertex 1.54178 1.7719 2.54776 + endloop + endfacet + facet normal 0.164861 0.130849 0.977599 + outer loop + vertex 1.54616 1.76572 2.5478 + vertex 1.54684 1.77062 2.54703 + vertex 1.54247 1.76719 2.54823 + endloop + endfacet + facet normal 0.166886 0.136263 0.976515 + outer loop + vertex 1.54292 1.76277 2.54877 + vertex 1.54616 1.76572 2.5478 + vertex 1.54247 1.76719 2.54823 + endloop + endfacet + facet normal 0.162882 0.14067 0.976566 + outer loop + vertex 1.54721 1.76194 2.54817 + vertex 1.54616 1.76572 2.5478 + vertex 1.54292 1.76277 2.54877 + endloop + endfacet + facet normal 0.162894 0.140673 0.976564 + outer loop + vertex 1.54721 1.76194 2.54817 + vertex 1.55108 1.76591 2.54695 + vertex 1.54616 1.76572 2.5478 + endloop + endfacet + facet normal 0.161269 0.142265 0.976603 + outer loop + vertex 1.55092 1.76073 2.54773 + vertex 1.55108 1.76591 2.54695 + vertex 1.54721 1.76194 2.54817 + endloop + endfacet + facet normal 0.160569 0.139948 0.977053 + outer loop + vertex 1.54784 1.75766 2.54868 + vertex 1.55092 1.76073 2.54773 + vertex 1.54721 1.76194 2.54817 + endloop + endfacet + facet normal 0.162194 0.138304 0.977018 + outer loop + vertex 1.55203 1.75691 2.54809 + vertex 1.55092 1.76073 2.54773 + vertex 1.54784 1.75766 2.54868 + endloop + endfacet + facet normal 0.160864 0.137942 0.977289 + outer loop + vertex 1.55203 1.75691 2.54809 + vertex 1.55575 1.76114 2.54688 + vertex 1.55092 1.76073 2.54773 + endloop + endfacet + facet normal 0.175687 0.136965 0.974872 + outer loop + vertex 1.54292 1.76277 2.54877 + vertex 1.54247 1.76719 2.54823 + vertex 1.53904 1.76417 2.54927 + endloop + endfacet + facet normal 0.162819 0.140295 0.976631 + outer loop + vertex 1.54406 1.759 2.54912 + vertex 1.54721 1.76194 2.54817 + vertex 1.54292 1.76277 2.54877 + endloop + endfacet + facet normal 0.185055 0.14046 0.972638 + outer loop + vertex 1.53881 1.75437 2.55076 + vertex 1.54372 1.75414 2.54986 + vertex 1.53882 1.75919 2.55006 + endloop + endfacet + facet normal 0.213617 0.139552 0.966899 + outer loop + vertex 1.53881 1.75437 2.55076 + vertex 1.53882 1.75919 2.55006 + vertex 1.5355 1.7561 2.55124 + endloop + endfacet + facet normal 0.212766 0.137805 0.967337 + outer loop + vertex 1.5355 1.7561 2.55124 + vertex 1.53552 1.75111 2.55195 + vertex 1.53881 1.75437 2.55076 + endloop + endfacet + facet normal 0.208531 0.142176 0.967626 + outer loop + vertex 1.54034 1.75117 2.5509 + vertex 1.53881 1.75437 2.55076 + vertex 1.53552 1.75111 2.55195 + endloop + endfacet + facet normal 0.209036 0.130285 0.96919 + outer loop + vertex 1.54034 1.75117 2.5509 + vertex 1.53552 1.75111 2.55195 + vertex 1.5399 1.74666 2.5516 + endloop + endfacet + facet normal 0.186546 0.133131 0.973384 + outer loop + vertex 1.54034 1.75117 2.5509 + vertex 1.5399 1.74666 2.5516 + vertex 1.54336 1.74931 2.55058 + endloop + endfacet + facet normal 0.185145 0.130763 0.973973 + outer loop + vertex 1.54336 1.74931 2.55058 + vertex 1.54372 1.75414 2.54986 + vertex 1.54034 1.75117 2.5509 + endloop + endfacet + facet normal 0.185607 0.134364 0.973394 + outer loop + vertex 1.54484 1.7452 2.55086 + vertex 1.54336 1.74931 2.55058 + vertex 1.5399 1.74666 2.5516 + endloop + endfacet + facet normal 0.201408 0.122553 0.971811 + outer loop + vertex 1.53552 1.75111 2.55195 + vertex 1.53548 1.74595 2.55261 + vertex 1.5399 1.74666 2.5516 + endloop + endfacet + facet normal 0.203676 0.138044 0.969257 + outer loop + vertex 1.5355 1.7561 2.55124 + vertex 1.53064 1.75595 2.55229 + vertex 1.53552 1.75111 2.55195 + endloop + endfacet + facet normal 0.192575 0.126597 0.973082 + outer loop + vertex 1.53064 1.75595 2.55229 + vertex 1.53063 1.75058 2.55299 + vertex 1.53552 1.75111 2.55195 + endloop + endfacet + facet normal 0.194288 0.113315 0.974378 + outer loop + vertex 1.53176 1.74667 2.55322 + vertex 1.53552 1.75111 2.55195 + vertex 1.53063 1.75058 2.55299 + endloop + endfacet + facet normal 0.0599744 0.075916 0.995309 + outer loop + vertex 1.53176 1.74667 2.55322 + vertex 1.53063 1.75058 2.55299 + vertex 1.52762 1.74689 2.55345 + endloop + endfacet + facet normal 0.183015 0.123166 0.975364 + outer loop + vertex 1.53548 1.74595 2.55261 + vertex 1.53552 1.75111 2.55195 + vertex 1.53176 1.74667 2.55322 + endloop + endfacet + facet normal 0.181707 0.115344 0.976565 + outer loop + vertex 1.53245 1.74237 2.5536 + vertex 1.53548 1.74595 2.55261 + vertex 1.53176 1.74667 2.55322 + endloop + endfacet + facet normal 0.0860152 0.10117 0.991144 + outer loop + vertex 1.53245 1.74237 2.5536 + vertex 1.53176 1.74667 2.55322 + vertex 1.52824 1.74235 2.55396 + endloop + endfacet + facet normal 0.05835 0.12899 0.989928 + outer loop + vertex 1.53063 1.75058 2.55299 + vertex 1.53064 1.75595 2.55229 + vertex 1.52715 1.75157 2.55306 + endloop + endfacet + facet normal 0.212808 0.14044 0.966948 + outer loop + vertex 1.53366 1.75938 2.55117 + vertex 1.5355 1.7561 2.55124 + vertex 1.53882 1.75919 2.55006 + endloop + endfacet + facet normal 0.184861 0.13109 0.973983 + outer loop + vertex 1.53881 1.75437 2.55076 + vertex 1.54034 1.75117 2.5509 + vertex 1.54372 1.75414 2.54986 + endloop + endfacet + facet normal 0.162874 0.140235 0.97663 + outer loop + vertex 1.54784 1.75766 2.54868 + vertex 1.54721 1.76194 2.54817 + vertex 1.54406 1.759 2.54912 + endloop + endfacet + facet normal 0.168626 0.132378 0.97675 + outer loop + vertex 1.54336 1.74931 2.55058 + vertex 1.54791 1.74938 2.54978 + vertex 1.54372 1.75414 2.54986 + endloop + endfacet + facet normal 0.161622 0.134659 0.977622 + outer loop + vertex 1.5488 1.75395 2.54903 + vertex 1.55203 1.75691 2.54809 + vertex 1.54784 1.75766 2.54868 + endloop + endfacet + facet normal 0.108165 0.146603 0.983264 + outer loop + vertex 1.56174 1.75194 2.5475 + vertex 1.56027 1.75709 2.54689 + vertex 1.55686 1.75201 2.54802 + endloop + endfacet + facet normal 0.157504 0.140926 0.977411 + outer loop + vertex 1.55566 1.75588 2.54765 + vertex 1.55575 1.76114 2.54688 + vertex 1.55203 1.75691 2.54809 + endloop + endfacet + facet normal 0.133047 0.159368 0.978213 + outer loop + vertex 1.56047 1.76164 2.54616 + vertex 1.55868 1.76453 2.54593 + vertex 1.55575 1.76114 2.54688 + endloop + endfacet + facet normal 0.160397 0.142313 0.976739 + outer loop + vertex 1.55108 1.76591 2.54695 + vertex 1.55092 1.76073 2.54773 + vertex 1.55575 1.76114 2.54688 + endloop + endfacet + facet normal 0.144063 0.128905 0.981137 + outer loop + vertex 1.55418 1.76917 2.54596 + vertex 1.55568 1.76601 2.54616 + vertex 1.55873 1.76904 2.54531 + endloop + endfacet + facet normal 0.144043 0.126889 0.981402 + outer loop + vertex 1.55418 1.76917 2.54596 + vertex 1.55873 1.76904 2.54531 + vertex 1.5546 1.77355 2.54533 + endloop + endfacet + facet normal 0.163481 0.131071 0.977801 + outer loop + vertex 1.54684 1.77062 2.54703 + vertex 1.54616 1.76572 2.5478 + vertex 1.55108 1.76591 2.54695 + endloop + endfacet + facet normal 0.175507 0.120098 0.977125 + outer loop + vertex 1.54488 1.77662 2.54664 + vertex 1.54684 1.77062 2.54703 + vertex 1.54971 1.77517 2.54595 + endloop + endfacet + facet normal 0.162496 0.124736 0.978793 + outer loop + vertex 1.55418 1.76917 2.54596 + vertex 1.5546 1.77355 2.54533 + vertex 1.55125 1.77101 2.54621 + endloop + endfacet + facet normal 0.162676 0.114542 0.980008 + outer loop + vertex 1.54827 1.77935 2.54571 + vertex 1.54971 1.77517 2.54595 + vertex 1.55279 1.77942 2.54495 + endloop + endfacet + facet normal 0.148928 0.117701 0.981818 + outer loop + vertex 1.55907 1.77378 2.54463 + vertex 1.55794 1.77784 2.54431 + vertex 1.5546 1.77355 2.54533 + endloop + endfacet + facet normal 0.162923 0.107367 0.98078 + outer loop + vertex 1.54827 1.77935 2.54571 + vertex 1.55279 1.77942 2.54495 + vertex 1.54887 1.78418 2.54508 + endloop + endfacet + facet normal 0.158348 0.1055 0.981731 + outer loop + vertex 1.55383 1.7841 2.54427 + vertex 1.55738 1.78715 2.54337 + vertex 1.55311 1.78795 2.54398 + endloop + endfacet + facet normal 0.159385 0.111655 0.980882 + outer loop + vertex 1.55738 1.78715 2.54337 + vertex 1.55686 1.7916 2.54295 + vertex 1.55311 1.78795 2.54398 + endloop + endfacet + facet normal 0.159565 0.111467 0.980874 + outer loop + vertex 1.55311 1.78795 2.54398 + vertex 1.55686 1.7916 2.54295 + vertex 1.55257 1.7923 2.54357 + endloop + endfacet + facet normal 0.175843 0.108862 0.97838 + outer loop + vertex 1.54428 1.78433 2.54588 + vertex 1.54887 1.78418 2.54508 + vertex 1.54489 1.78873 2.54529 + endloop + endfacet + facet normal 0.17758 0.11308 0.977588 + outer loop + vertex 1.54489 1.78873 2.54529 + vertex 1.54817 1.79306 2.54419 + vertex 1.54292 1.79453 2.54497 + endloop + endfacet + facet normal 0.181903 0.1301 0.974672 + outer loop + vertex 1.54817 1.79306 2.54419 + vertex 1.54753 1.79763 2.5437 + vertex 1.54292 1.79453 2.54497 + endloop + endfacet + facet normal 0.174973 0.140326 0.974522 + outer loop + vertex 1.54292 1.79453 2.54497 + vertex 1.54753 1.79763 2.5437 + vertex 1.5438 1.79913 2.54415 + endloop + endfacet + facet normal 0.205489 0.133591 0.969499 + outer loop + vertex 1.53852 1.79915 2.54527 + vertex 1.54292 1.79453 2.54497 + vertex 1.5438 1.79913 2.54415 + endloop + endfacet + facet normal 0.159224 0.111431 0.980934 + outer loop + vertex 1.55311 1.78795 2.54398 + vertex 1.55257 1.7923 2.54357 + vertex 1.54942 1.78909 2.54444 + endloop + endfacet + facet normal 0.156612 0.127037 0.979456 + outer loop + vertex 1.54817 1.79306 2.54419 + vertex 1.55189 1.79674 2.54312 + vertex 1.54753 1.79763 2.5437 + endloop + endfacet + facet normal 0.160756 0.119814 0.979695 + outer loop + vertex 1.55686 1.7916 2.54295 + vertex 1.55574 1.79559 2.54264 + vertex 1.55257 1.7923 2.54357 + endloop + endfacet + facet normal 0.158586 0.137838 0.977676 + outer loop + vertex 1.55189 1.79674 2.54312 + vertex 1.5508 1.80073 2.54273 + vertex 1.54753 1.79763 2.5437 + endloop + endfacet + facet normal 0.184015 0.14339 0.972408 + outer loop + vertex 1.54279 1.80282 2.5438 + vertex 1.5459 1.80582 2.54277 + vertex 1.54208 1.80707 2.54331 + endloop + endfacet + facet normal 0.184631 0.145442 0.971987 + outer loop + vertex 1.5459 1.80582 2.54277 + vertex 1.54581 1.81101 2.54201 + vertex 1.54208 1.80707 2.54331 + endloop + endfacet + facet normal 0.171577 0.16691 0.970929 + outer loop + vertex 1.55075 1.811 2.54114 + vertex 1.54904 1.81431 2.54088 + vertex 1.54581 1.81101 2.54201 + endloop + endfacet + facet normal 0.162826 0.162552 0.973172 + outer loop + vertex 1.54904 1.81431 2.54088 + vertex 1.55075 1.811 2.54114 + vertex 1.55396 1.8141 2.54009 + endloop + endfacet + facet normal 0.163639 0.161832 0.973156 + outer loop + vertex 1.55396 1.8141 2.54009 + vertex 1.55775 1.81766 2.53886 + vertex 1.55406 1.81896 2.53926 + endloop + endfacet + facet normal 0.164265 0.163724 0.972734 + outer loop + vertex 1.55775 1.81766 2.53886 + vertex 1.55698 1.82184 2.53828 + vertex 1.55406 1.81896 2.53926 + endloop + endfacet + facet normal 0.161717 0.166308 0.972723 + outer loop + vertex 1.55406 1.81896 2.53926 + vertex 1.55698 1.82184 2.53828 + vertex 1.55283 1.82266 2.53883 + endloop + endfacet + facet normal 0.165848 0.162339 0.972698 + outer loop + vertex 1.56285 1.81271 2.5388 + vertex 1.56201 1.81705 2.53822 + vertex 1.55899 1.81398 2.53925 + endloop + endfacet + facet normal 0.151024 0.159832 0.975523 + outer loop + vertex 1.56285 1.81271 2.5388 + vertex 1.56654 1.81633 2.53764 + vertex 1.56201 1.81705 2.53822 + endloop + endfacet + facet normal 0.166369 0.164052 0.972321 + outer loop + vertex 1.55775 1.81766 2.53886 + vertex 1.56058 1.82073 2.53785 + vertex 1.55698 1.82184 2.53828 + endloop + endfacet + facet normal 0.152157 0.168304 0.973921 + outer loop + vertex 1.56654 1.81633 2.53764 + vertex 1.56518 1.82147 2.53696 + vertex 1.56201 1.81705 2.53822 + endloop + endfacet + facet normal 0.167368 0.167603 0.971544 + outer loop + vertex 1.56058 1.82073 2.53785 + vertex 1.56058 1.82584 2.53697 + vertex 1.55698 1.82184 2.53828 + endloop + endfacet + facet normal 0.165362 0.169416 0.971573 + outer loop + vertex 1.55698 1.82184 2.53828 + vertex 1.56058 1.82584 2.53697 + vertex 1.55573 1.82559 2.53784 + endloop + endfacet + facet normal 0.146335 0.159433 0.976303 + outer loop + vertex 1.56373 1.82924 2.53585 + vertex 1.56547 1.8261 2.5361 + vertex 1.56823 1.82956 2.53512 + endloop + endfacet + facet normal 0.163102 0.167988 0.972203 + outer loop + vertex 1.56058 1.83082 2.53611 + vertex 1.5557 1.83076 2.53694 + vertex 1.56058 1.82584 2.53697 + endloop + endfacet + facet normal 0.163037 0.169534 0.971945 + outer loop + vertex 1.56058 1.83082 2.53611 + vertex 1.55892 1.8341 2.53582 + vertex 1.5557 1.83076 2.53694 + endloop + endfacet + facet normal 0.167356 0.181728 0.969003 + outer loop + vertex 1.55564 1.83582 2.53606 + vertex 1.55389 1.83912 2.53574 + vertex 1.55066 1.83582 2.53692 + endloop + endfacet + facet normal 0.17064 0.178516 0.969027 + outer loop + vertex 1.55053 1.84082 2.53602 + vertex 1.55066 1.83582 2.53692 + vertex 1.55389 1.83912 2.53574 + endloop + endfacet + facet normal 0.169884 0.176956 0.969446 + outer loop + vertex 1.55389 1.83912 2.53574 + vertex 1.55376 1.84396 2.53488 + vertex 1.55053 1.84082 2.53602 + endloop + endfacet + facet normal 0.195263 0.17831 0.964405 + outer loop + vertex 1.55053 1.84082 2.53602 + vertex 1.5455 1.84077 2.53705 + vertex 1.55066 1.83582 2.53692 + endloop + endfacet + facet normal 0.194895 0.186359 0.962957 + outer loop + vertex 1.55053 1.84082 2.53602 + vertex 1.54874 1.84407 2.53575 + vertex 1.5455 1.84077 2.53705 + endloop + endfacet + facet normal 0.1653 0.170169 0.971452 + outer loop + vertex 1.5557 1.83076 2.53694 + vertex 1.55573 1.82559 2.53784 + vertex 1.56058 1.82584 2.53697 + endloop + endfacet + facet normal 0.162073 0.1684 0.972303 + outer loop + vertex 1.55698 1.82184 2.53828 + vertex 1.55573 1.82559 2.53784 + vertex 1.55283 1.82266 2.53883 + endloop + endfacet + facet normal 0.166924 0.167912 0.971567 + outer loop + vertex 1.55406 1.81896 2.53926 + vertex 1.55283 1.82266 2.53883 + vertex 1.54899 1.81918 2.54009 + endloop + endfacet + facet normal 0.173257 0.166923 0.970628 + outer loop + vertex 1.54908 1.82407 2.53924 + vertex 1.55205 1.82689 2.53823 + vertex 1.5478 1.82781 2.53883 + endloop + endfacet + facet normal 0.188331 0.167534 0.967711 + outer loop + vertex 1.5478 1.82781 2.53883 + vertex 1.54698 1.83204 2.53825 + vertex 1.54401 1.82914 2.53934 + endloop + endfacet + facet normal 0.187248 0.160654 0.969086 + outer loop + vertex 1.54698 1.83204 2.53825 + vertex 1.55066 1.83582 2.53692 + vertex 1.54563 1.83577 2.5379 + endloop + endfacet + facet normal 0.186878 0.169503 0.967649 + outer loop + vertex 1.5455 1.84077 2.53705 + vertex 1.54563 1.83577 2.5379 + vertex 1.55066 1.83582 2.53692 + endloop + endfacet + facet normal 0.060908 0.17091 0.983402 + outer loop + vertex 1.54052 1.84047 2.53807 + vertex 1.54039 1.84563 2.53718 + vertex 1.537 1.84146 2.53812 + endloop + endfacet + facet normal 0.205512 0.173523 0.963148 + outer loop + vertex 1.54347 1.84901 2.53596 + vertex 1.54532 1.84574 2.53615 + vertex 1.54865 1.84886 2.53488 + endloop + endfacet + facet normal 0.172336 0.174448 0.969468 + outer loop + vertex 1.54874 1.84407 2.53575 + vertex 1.55053 1.84082 2.53602 + vertex 1.55376 1.84396 2.53488 + endloop + endfacet + facet normal 0.156698 0.183187 0.970509 + outer loop + vertex 1.55736 1.84765 2.53361 + vertex 1.55611 1.8511 2.53316 + vertex 1.55363 1.84867 2.53402 + endloop + endfacet + facet normal 0.160001 0.176984 0.971121 + outer loop + vertex 1.55389 1.83912 2.53574 + vertex 1.55888 1.83899 2.53494 + vertex 1.55376 1.84396 2.53488 + endloop + endfacet + facet normal 0.164296 0.174692 0.970819 + outer loop + vertex 1.56393 1.83881 2.53412 + vertex 1.56261 1.84252 2.53368 + vertex 1.55888 1.83899 2.53494 + endloop + endfacet + facet normal 0.166516 0.175423 0.970309 + outer loop + vertex 1.56393 1.83881 2.53412 + vertex 1.5668 1.84163 2.53312 + vertex 1.56261 1.84252 2.53368 + endloop + endfacet + facet normal 0.160366 0.181666 0.970196 + outer loop + vertex 1.56766 1.8375 2.53375 + vertex 1.5668 1.84163 2.53312 + vertex 1.56393 1.83881 2.53412 + endloop + endfacet + facet normal 0.163565 0.181864 0.969625 + outer loop + vertex 1.55882 1.84393 2.53406 + vertex 1.56175 1.84681 2.53303 + vertex 1.55736 1.84765 2.53361 + endloop + endfacet + facet normal 0.167695 0.181808 0.968929 + outer loop + vertex 1.5668 1.84163 2.53312 + vertex 1.56551 1.84525 2.53266 + vertex 1.56261 1.84252 2.53368 + endloop + endfacet + facet normal 0.157285 0.182869 0.970474 + outer loop + vertex 1.55526 1.86033 2.53156 + vertex 1.55671 1.85548 2.53224 + vertex 1.55966 1.85984 2.53094 + endloop + endfacet + facet normal 0.15747 0.185151 0.970011 + outer loop + vertex 1.55966 1.85984 2.53094 + vertex 1.55827 1.86337 2.53049 + vertex 1.55526 1.86033 2.53156 + endloop + endfacet + facet normal 0.173067 0.178944 0.968518 + outer loop + vertex 1.56473 1.85473 2.531 + vertex 1.56406 1.85927 2.53028 + vertex 1.56105 1.8563 2.53137 + endloop + endfacet + facet normal 0.162201 0.186881 0.9689 + outer loop + vertex 1.55827 1.86337 2.53049 + vertex 1.55966 1.85984 2.53094 + vertex 1.56272 1.86407 2.52961 + endloop + endfacet + facet normal 0.168991 0.185038 0.968093 + outer loop + vertex 1.56906 1.85764 2.52972 + vertex 1.56757 1.86264 2.52903 + vertex 1.56406 1.85927 2.53028 + endloop + endfacet + facet normal 0.170251 0.185746 0.967736 + outer loop + vertex 1.56272 1.86407 2.52961 + vertex 1.56685 1.86707 2.52831 + vertex 1.56342 1.86833 2.52867 + endloop + endfacet + facet normal 0.154054 0.19387 0.968856 + outer loop + vertex 1.57216 1.86206 2.52841 + vertex 1.57052 1.86579 2.52793 + vertex 1.56757 1.86264 2.52903 + endloop + endfacet + facet normal 0.167897 0.189971 0.967327 + outer loop + vertex 1.56685 1.86707 2.52831 + vertex 1.57046 1.87075 2.52696 + vertex 1.56581 1.87074 2.52777 + endloop + endfacet + facet normal 0.0972833 0.187871 0.977364 + outer loop + vertex 1.57353 1.87395 2.52582 + vertex 1.57537 1.87106 2.5262 + vertex 1.57809 1.87464 2.52524 + endloop + endfacet + facet normal 0.167583 0.198813 0.965603 + outer loop + vertex 1.56549 1.87552 2.52684 + vertex 1.56581 1.87074 2.52777 + vertex 1.57046 1.87075 2.52696 + endloop + endfacet + facet normal 0.152115 0.182985 0.971276 + outer loop + vertex 1.56854 1.87872 2.52568 + vertex 1.5703 1.87546 2.52602 + vertex 1.57356 1.87867 2.5249 + endloop + endfacet + facet normal 0.162759 0.195274 0.967149 + outer loop + vertex 1.56046 1.88035 2.52671 + vertex 1.56063 1.87546 2.52767 + vertex 1.56549 1.87552 2.52684 + endloop + endfacet + facet normal 0.170217 0.190214 0.966874 + outer loop + vertex 1.56038 1.88518 2.52577 + vertex 1.55594 1.88477 2.52664 + vertex 1.56046 1.88035 2.52671 + endloop + endfacet + facet normal 0.170324 0.189366 0.967021 + outer loop + vertex 1.56038 1.88518 2.52577 + vertex 1.55867 1.88828 2.52547 + vertex 1.55594 1.88477 2.52664 + endloop + endfacet + facet normal 0.183069 0.179326 0.966606 + outer loop + vertex 1.55867 1.88828 2.52547 + vertex 1.55459 1.88995 2.52593 + vertex 1.55594 1.88477 2.52664 + endloop + endfacet + facet normal 0.184014 0.181814 0.965962 + outer loop + vertex 1.55459 1.88995 2.52593 + vertex 1.55867 1.88828 2.52547 + vertex 1.55907 1.89279 2.52454 + endloop + endfacet + facet normal 0.163543 0.184284 0.969171 + outer loop + vertex 1.55867 1.88828 2.52547 + vertex 1.56359 1.88842 2.52461 + vertex 1.55907 1.89279 2.52454 + endloop + endfacet + facet normal 0.168299 0.18918 0.967412 + outer loop + vertex 1.55907 1.89279 2.52454 + vertex 1.56359 1.88842 2.52461 + vertex 1.56356 1.89319 2.52368 + endloop + endfacet + facet normal 0.16763 0.194677 0.966437 + outer loop + vertex 1.56356 1.89319 2.52368 + vertex 1.56211 1.8968 2.52321 + vertex 1.55907 1.89279 2.52454 + endloop + endfacet + facet normal 0.164899 0.193665 0.96711 + outer loop + vertex 1.56356 1.89319 2.52368 + vertex 1.56581 1.89572 2.52279 + vertex 1.56211 1.8968 2.52321 + endloop + endfacet + facet normal 0.165154 0.194625 0.966874 + outer loop + vertex 1.56581 1.89572 2.52279 + vertex 1.56551 1.90057 2.52187 + vertex 1.56211 1.8968 2.52321 + endloop + endfacet + facet normal 0.167427 0.19258 0.966893 + outer loop + vertex 1.56211 1.8968 2.52321 + vertex 1.56551 1.90057 2.52187 + vertex 1.56063 1.90056 2.52272 + endloop + endfacet + facet normal 0.175402 0.195457 0.964899 + outer loop + vertex 1.56211 1.8968 2.52321 + vertex 1.56063 1.90056 2.52272 + vertex 1.55771 1.89774 2.52382 + endloop + endfacet + facet normal 0.174328 0.189549 0.966272 + outer loop + vertex 1.55907 1.89279 2.52454 + vertex 1.56211 1.8968 2.52321 + vertex 1.55771 1.89774 2.52382 + endloop + endfacet + facet normal 0.187434 0.19271 0.963188 + outer loop + vertex 1.55907 1.89279 2.52454 + vertex 1.55771 1.89774 2.52382 + vertex 1.55327 1.89499 2.52523 + endloop + endfacet + facet normal 0.185833 0.195193 0.962998 + outer loop + vertex 1.55327 1.89499 2.52523 + vertex 1.55771 1.89774 2.52382 + vertex 1.55388 1.89925 2.52425 + endloop + endfacet + facet normal 0.183728 0.189386 0.964561 + outer loop + vertex 1.55771 1.89774 2.52382 + vertex 1.55692 1.9019 2.52315 + vertex 1.55388 1.89925 2.52425 + endloop + endfacet + facet normal 0.182628 0.190632 0.964524 + outer loop + vertex 1.55388 1.89925 2.52425 + vertex 1.55692 1.9019 2.52315 + vertex 1.55264 1.90262 2.52382 + endloop + endfacet + facet normal 0.150241 0.179727 0.972176 + outer loop + vertex 1.55388 1.89925 2.52425 + vertex 1.55264 1.90262 2.52382 + vertex 1.54864 1.89881 2.52514 + endloop + endfacet + facet normal 0.181707 0.183824 0.966018 + outer loop + vertex 1.55692 1.9019 2.52315 + vertex 1.55562 1.90537 2.52273 + vertex 1.55264 1.90262 2.52382 + endloop + endfacet + facet normal 0.176772 0.189135 0.965909 + outer loop + vertex 1.55264 1.90262 2.52382 + vertex 1.55562 1.90537 2.52273 + vertex 1.55174 1.90665 2.52319 + endloop + endfacet + facet normal 0.178283 0.194174 0.96463 + outer loop + vertex 1.55562 1.90537 2.52273 + vertex 1.55594 1.90973 2.5218 + vertex 1.55174 1.90665 2.52319 + endloop + endfacet + facet normal 0.184549 0.185849 0.965092 + outer loop + vertex 1.55174 1.90665 2.52319 + vertex 1.55594 1.90973 2.5218 + vertex 1.55016 1.91152 2.52256 + endloop + endfacet + facet normal 0.079177 0.154144 0.984871 + outer loop + vertex 1.55174 1.90665 2.52319 + vertex 1.55016 1.91152 2.52256 + vertex 1.54717 1.90685 2.52353 + endloop + endfacet + facet normal 0.186789 0.19326 0.963203 + outer loop + vertex 1.55594 1.90973 2.5218 + vertex 1.55562 1.90537 2.52273 + vertex 1.56052 1.90543 2.52177 + endloop + endfacet + facet normal 0.187163 0.185686 0.964619 + outer loop + vertex 1.55692 1.9019 2.52315 + vertex 1.56052 1.90543 2.52177 + vertex 1.55562 1.90537 2.52273 + endloop + endfacet + facet normal 0.182174 0.190759 0.964585 + outer loop + vertex 1.56063 1.90056 2.52272 + vertex 1.56052 1.90543 2.52177 + vertex 1.55692 1.9019 2.52315 + endloop + endfacet + facet normal 0.181612 0.189059 0.965025 + outer loop + vertex 1.55771 1.89774 2.52382 + vertex 1.56063 1.90056 2.52272 + vertex 1.55692 1.9019 2.52315 + endloop + endfacet + facet normal 0.168448 0.194717 0.966287 + outer loop + vertex 1.56551 1.90057 2.52187 + vertex 1.56581 1.89572 2.52279 + vertex 1.57047 1.89576 2.52197 + endloop + endfacet + facet normal 0.165291 0.193318 0.967113 + outer loop + vertex 1.56712 1.89208 2.5233 + vertex 1.56581 1.89572 2.52279 + vertex 1.56356 1.89319 2.52368 + endloop + endfacet + facet normal 0.163453 0.18577 0.968903 + outer loop + vertex 1.55867 1.88828 2.52547 + vertex 1.56038 1.88518 2.52577 + vertex 1.56359 1.88842 2.52461 + endloop + endfacet + facet normal 0.163068 0.191449 0.967862 + outer loop + vertex 1.56353 1.88366 2.52555 + vertex 1.56523 1.88043 2.5259 + vertex 1.5685 1.88359 2.52473 + endloop + endfacet + facet normal 0.16415 0.189287 0.968104 + outer loop + vertex 1.56359 1.88842 2.52461 + vertex 1.56712 1.89208 2.5233 + vertex 1.56356 1.89319 2.52368 + endloop + endfacet + facet normal 0.165943 0.19237 0.96719 + outer loop + vertex 1.57219 1.8873 2.52337 + vertex 1.5707 1.89096 2.5229 + vertex 1.5684 1.88843 2.52379 + endloop + endfacet + facet normal 0.168464 0.194352 0.966358 + outer loop + vertex 1.56712 1.89208 2.5233 + vertex 1.57047 1.89576 2.52197 + vertex 1.56581 1.89572 2.52279 + endloop + endfacet + facet normal 0.136462 0.182553 0.97368 + outer loop + vertex 1.57351 1.89896 2.52081 + vertex 1.57528 1.89589 2.52114 + vertex 1.57804 1.89938 2.5201 + endloop + endfacet + facet normal 0.167013 0.193253 0.96683 + outer loop + vertex 1.57033 1.90054 2.52104 + vertex 1.56551 1.90057 2.52187 + vertex 1.57047 1.89576 2.52197 + endloop + endfacet + facet normal 0.167063 0.191403 0.967189 + outer loop + vertex 1.57033 1.90054 2.52104 + vertex 1.56862 1.90381 2.52069 + vertex 1.56551 1.90057 2.52187 + endloop + endfacet + facet normal 0.167486 0.190952 0.967205 + outer loop + vertex 1.56052 1.90543 2.52177 + vertex 1.56063 1.90056 2.52272 + vertex 1.56551 1.90057 2.52187 + endloop + endfacet + facet normal 0.160563 0.198585 0.966842 + outer loop + vertex 1.56362 1.90874 2.52053 + vertex 1.56533 1.90551 2.52091 + vertex 1.56856 1.90868 2.51972 + endloop + endfacet + facet normal 0.159551 0.193195 0.968101 + outer loop + vertex 1.57368 1.90856 2.5189 + vertex 1.57218 1.91236 2.51839 + vertex 1.56856 1.90868 2.51972 + endloop + endfacet + facet normal 0.15544 0.191701 0.969066 + outer loop + vertex 1.57368 1.90856 2.5189 + vertex 1.57666 1.91142 2.51785 + vertex 1.57218 1.91236 2.51839 + endloop + endfacet + facet normal 0.149838 0.197437 0.968797 + outer loop + vertex 1.5775 1.90722 2.51858 + vertex 1.57666 1.91142 2.51785 + vertex 1.57368 1.90856 2.5189 + endloop + endfacet + facet normal 0.151413 0.206271 0.966709 + outer loop + vertex 1.56839 1.91349 2.51878 + vertex 1.57066 1.91597 2.51789 + vertex 1.56707 1.91703 2.51822 + endloop + endfacet + facet normal 0.157232 0.201547 0.966776 + outer loop + vertex 1.57666 1.91142 2.51785 + vertex 1.57509 1.91642 2.51707 + vertex 1.57218 1.91236 2.51839 + endloop + endfacet + facet normal 0.134117 0.195003 0.97159 + outer loop + vertex 1.57666 1.91142 2.51785 + vertex 1.58083 1.91454 2.51665 + vertex 1.57509 1.91642 2.51707 + endloop + endfacet + facet normal 0.152602 0.210656 0.965576 + outer loop + vertex 1.57066 1.91597 2.51789 + vertex 1.57049 1.9206 2.51691 + vertex 1.56707 1.91703 2.51822 + endloop + endfacet + facet normal 0.150229 0.212892 0.965458 + outer loop + vertex 1.56707 1.91703 2.51822 + vertex 1.57049 1.9206 2.51691 + vertex 1.56585 1.92046 2.51766 + endloop + endfacet + facet normal 0.15286 0.213735 0.964858 + outer loop + vertex 1.56707 1.91703 2.51822 + vertex 1.56585 1.92046 2.51766 + vertex 1.56348 1.9181 2.51856 + endloop + endfacet + facet normal 0.151892 0.210176 0.965792 + outer loop + vertex 1.56358 1.91345 2.51955 + vertex 1.56707 1.91703 2.51822 + vertex 1.56348 1.9181 2.51856 + endloop + endfacet + facet normal 0.178269 0.209814 0.961352 + outer loop + vertex 1.55888 1.91771 2.5195 + vertex 1.56358 1.91345 2.51955 + vertex 1.56348 1.9181 2.51856 + endloop + endfacet + facet normal 0.177584 0.215242 0.960278 + outer loop + vertex 1.56348 1.9181 2.51856 + vertex 1.562 1.92172 2.51802 + vertex 1.55888 1.91771 2.5195 + endloop + endfacet + facet normal 0.18321 0.210843 0.960197 + outer loop + vertex 1.55888 1.91771 2.5195 + vertex 1.562 1.92172 2.51802 + vertex 1.55721 1.92265 2.51873 + endloop + endfacet + facet normal 0.203874 0.216949 0.954656 + outer loop + vertex 1.55888 1.91771 2.5195 + vertex 1.55721 1.92265 2.51873 + vertex 1.55297 1.91971 2.5203 + endloop + endfacet + facet normal 0.183316 0.211518 0.960029 + outer loop + vertex 1.562 1.92172 2.51802 + vertex 1.56027 1.9267 2.51725 + vertex 1.55721 1.92265 2.51873 + endloop + endfacet + facet normal 0.163337 0.205321 0.964969 + outer loop + vertex 1.562 1.92172 2.51802 + vertex 1.56607 1.92464 2.51671 + vertex 1.56027 1.9267 2.51725 + endloop + endfacet + facet normal 0.159273 0.210763 0.964474 + outer loop + vertex 1.56585 1.92046 2.51766 + vertex 1.56607 1.92464 2.51671 + vertex 1.562 1.92172 2.51802 + endloop + endfacet + facet normal 0.175862 0.207172 0.962368 + outer loop + vertex 1.55861 1.91328 2.5205 + vertex 1.56358 1.91345 2.51955 + vertex 1.55888 1.91771 2.5195 + endloop + endfacet + facet normal 0.206697 0.204048 0.956891 + outer loop + vertex 1.55443 1.91478 2.52108 + vertex 1.55861 1.91328 2.5205 + vertex 1.55888 1.91771 2.5195 + endloop + endfacet + facet normal 0.158488 0.208188 0.965163 + outer loop + vertex 1.56348 1.9181 2.51856 + vertex 1.56585 1.92046 2.51766 + vertex 1.562 1.92172 2.51802 + endloop + endfacet + facet normal 0.150317 0.211529 0.965743 + outer loop + vertex 1.56607 1.92464 2.51671 + vertex 1.56585 1.92046 2.51766 + vertex 1.57049 1.9206 2.51691 + endloop + endfacet + facet normal 0.153436 0.22026 0.963298 + outer loop + vertex 1.56867 1.92806 2.51553 + vertex 1.57042 1.92517 2.51591 + vertex 1.57347 1.92841 2.51468 + endloop + endfacet + facet normal 0.155803 0.221385 0.96266 + outer loop + vertex 1.57826 1.92848 2.51389 + vertex 1.57706 1.93201 2.51328 + vertex 1.57347 1.92841 2.51468 + endloop + endfacet + facet normal 0.147279 0.21882 0.964586 + outer loop + vertex 1.57826 1.92848 2.51389 + vertex 1.58073 1.93074 2.513 + vertex 1.57706 1.93201 2.51328 + endloop + endfacet + facet normal 0.135456 0.231285 0.96341 + outer loop + vertex 1.58212 1.9273 2.51363 + vertex 1.58073 1.93074 2.513 + vertex 1.57826 1.92848 2.51389 + endloop + endfacet + facet normal 0.15517 0.225981 0.961694 + outer loop + vertex 1.57322 1.93309 2.51365 + vertex 1.57552 1.93676 2.51242 + vertex 1.57114 1.93603 2.5133 + endloop + endfacet + facet normal 0.148718 0.223263 0.963347 + outer loop + vertex 1.58073 1.93074 2.513 + vertex 1.58101 1.93487 2.512 + vertex 1.57706 1.93201 2.51328 + endloop + endfacet + facet normal 0.106858 0.227204 0.967967 + outer loop + vertex 1.58101 1.93487 2.512 + vertex 1.58073 1.93074 2.513 + vertex 1.58516 1.93156 2.51232 + endloop + endfacet + facet normal 0.155161 0.226026 0.961685 + outer loop + vertex 1.57072 1.94088 2.51223 + vertex 1.57114 1.93603 2.5133 + vertex 1.57552 1.93676 2.51242 + endloop + endfacet + facet normal 0.16109 0.224349 0.961102 + outer loop + vertex 1.57054 1.94561 2.51115 + vertex 1.5657 1.94553 2.51198 + vertex 1.57072 1.94088 2.51223 + endloop + endfacet + facet normal 0.156601 0.226887 0.961248 + outer loop + vertex 1.56881 1.94873 2.5107 + vertex 1.57054 1.94561 2.51115 + vertex 1.57363 1.94876 2.50991 + endloop + endfacet + facet normal 0.157703 0.225295 0.961443 + outer loop + vertex 1.57374 1.94414 2.51098 + vertex 1.57558 1.94113 2.51138 + vertex 1.57818 1.94451 2.51016 + endloop + endfacet + facet normal 0.159047 0.227095 0.960797 + outer loop + vertex 1.57842 1.94862 2.50914 + vertex 1.57716 1.95205 2.50854 + vertex 1.57363 1.94876 2.50991 + endloop + endfacet + facet normal 0.156656 0.225632 0.961535 + outer loop + vertex 1.56881 1.94873 2.5107 + vertex 1.57363 1.94876 2.50991 + vertex 1.56862 1.95341 2.50963 + endloop + endfacet + facet normal 0.155828 0.234292 0.959596 + outer loop + vertex 1.5735 1.95332 2.50884 + vertex 1.57591 1.95549 2.50792 + vertex 1.57213 1.95699 2.50817 + endloop + endfacet + facet normal 0.15685 0.236995 0.958765 + outer loop + vertex 1.57591 1.95549 2.50792 + vertex 1.5761 1.95965 2.50686 + vertex 1.57213 1.95699 2.50817 + endloop + endfacet + facet normal 0.157113 0.236627 0.958814 + outer loop + vertex 1.57213 1.95699 2.50817 + vertex 1.5761 1.95965 2.50686 + vertex 1.57045 1.96183 2.50725 + endloop + endfacet + facet normal 0.176312 0.235775 0.95568 + outer loop + vertex 1.56364 1.95758 2.50951 + vertex 1.56601 1.96121 2.50818 + vertex 1.562 1.96228 2.50866 + endloop + endfacet + facet normal 0.162913 0.231716 0.959045 + outer loop + vertex 1.56364 1.95758 2.50951 + vertex 1.562 1.96228 2.50866 + vertex 1.55781 1.95934 2.51008 + endloop + endfacet + facet normal 0.161164 0.237852 0.957837 + outer loop + vertex 1.57213 1.95699 2.50817 + vertex 1.57045 1.96183 2.50725 + vertex 1.56819 1.95823 2.50853 + endloop + endfacet + facet normal 0.175646 0.232933 0.956499 + outer loop + vertex 1.56601 1.96121 2.50818 + vertex 1.5656 1.96586 2.50712 + vertex 1.562 1.96228 2.50866 + endloop + endfacet + facet normal 0.171895 0.236612 0.956278 + outer loop + vertex 1.562 1.96228 2.50866 + vertex 1.5656 1.96586 2.50712 + vertex 1.5607 1.96569 2.50805 + endloop + endfacet + facet normal 0.179495 0.219721 0.958908 + outer loop + vertex 1.56543 1.97035 2.50606 + vertex 1.56354 1.97319 2.50576 + vertex 1.56098 1.96974 2.50703 + endloop + endfacet + facet normal 0.142719 0.22677 0.963435 + outer loop + vertex 1.562 1.96228 2.50866 + vertex 1.5607 1.96569 2.50805 + vertex 1.55816 1.96334 2.50898 + endloop + endfacet + facet normal 0.148743 0.250659 0.95658 + outer loop + vertex 1.55781 1.95934 2.51008 + vertex 1.562 1.96228 2.50866 + vertex 1.55816 1.96334 2.50898 + endloop + endfacet + facet normal 0.169518 0.25602 0.951692 + outer loop + vertex 1.55781 1.95934 2.51008 + vertex 1.5593 1.95476 2.51105 + vertex 1.56364 1.95758 2.50951 + endloop + endfacet + facet normal 0.176958 0.224798 0.958202 + outer loop + vertex 1.56095 1.94985 2.51189 + vertex 1.5593 1.95476 2.51105 + vertex 1.5552 1.95171 2.51252 + endloop + endfacet + facet normal 0.0327518 0.259148 0.965282 + outer loop + vertex 1.5552 1.95592 2.51144 + vertex 1.5534 1.95825 2.51087 + vertex 1.55136 1.95468 2.5119 + endloop + endfacet + facet normal 0.0714782 0.280214 0.957273 + outer loop + vertex 1.55299 1.94796 2.51378 + vertex 1.5552 1.95171 2.51252 + vertex 1.55115 1.95065 2.51313 + endloop + endfacet + facet normal 0.152411 0.237975 0.959239 + outer loop + vertex 1.55353 1.94313 2.5149 + vertex 1.55684 1.94706 2.51339 + vertex 1.55299 1.94796 2.51378 + endloop + endfacet + facet normal 0.18158 0.221707 0.958058 + outer loop + vertex 1.55353 1.94313 2.5149 + vertex 1.55844 1.93878 2.51497 + vertex 1.55829 1.94341 2.51393 + endloop + endfacet + facet normal 0.187485 0.210611 0.959423 + outer loop + vertex 1.55855 1.93419 2.51596 + vertex 1.5631 1.93453 2.51499 + vertex 1.55844 1.93878 2.51497 + endloop + endfacet + facet normal 0.185906 0.203791 0.961201 + outer loop + vertex 1.56044 1.93116 2.51623 + vertex 1.55855 1.93419 2.51596 + vertex 1.55545 1.93088 2.51726 + endloop + endfacet + facet normal 0.11436 0.153981 0.981434 + outer loop + vertex 1.55529 1.93557 2.51632 + vertex 1.55359 1.93855 2.51605 + vertex 1.55079 1.93525 2.5169 + endloop + endfacet + facet normal 0.127513 0.254352 0.958669 + outer loop + vertex 1.55197 1.92718 2.5187 + vertex 1.55545 1.93088 2.51726 + vertex 1.55062 1.9306 2.51798 + endloop + endfacet + facet normal 0.176083 0.22673 0.957908 + outer loop + vertex 1.55328 1.92384 2.51925 + vertex 1.55568 1.92624 2.51824 + vertex 1.55197 1.92718 2.5187 + endloop + endfacet + facet normal 0.195993 0.227845 0.953768 + outer loop + vertex 1.55297 1.91971 2.5203 + vertex 1.55721 1.92265 2.51873 + vertex 1.55328 1.92384 2.51925 + endloop + endfacet + facet normal 0.202053 0.210858 0.956407 + outer loop + vertex 1.55297 1.91971 2.5203 + vertex 1.55443 1.91478 2.52108 + vertex 1.55888 1.91771 2.5195 + endloop + endfacet + facet normal 0.186359 0.192392 0.96346 + outer loop + vertex 1.55594 1.90973 2.5218 + vertex 1.55443 1.91478 2.52108 + vertex 1.55016 1.91152 2.52256 + endloop + endfacet + facet normal 0.102694 0.162365 0.981372 + outer loop + vertex 1.55032 1.91618 2.52168 + vertex 1.54858 1.91903 2.52139 + vertex 1.54606 1.91553 2.52223 + endloop + endfacet + facet normal 0.0702211 0.159824 0.984645 + outer loop + vertex 1.54717 1.90685 2.52353 + vertex 1.55016 1.91152 2.52256 + vertex 1.54585 1.91055 2.52302 + endloop + endfacet + facet normal 0.0804072 0.195015 0.977499 + outer loop + vertex 1.54873 1.90339 2.52409 + vertex 1.55174 1.90665 2.52319 + vertex 1.54717 1.90685 2.52353 + endloop + endfacet + facet normal 0.102908 0.174734 0.979223 + outer loop + vertex 1.55264 1.90262 2.52382 + vertex 1.55174 1.90665 2.52319 + vertex 1.54873 1.90339 2.52409 + endloop + endfacet + facet normal 0.111038 0.219801 0.969205 + outer loop + vertex 1.54864 1.89881 2.52514 + vertex 1.55264 1.90262 2.52382 + vertex 1.54873 1.90339 2.52409 + endloop + endfacet + facet normal 0.147714 0.201823 0.968219 + outer loop + vertex 1.54864 1.89881 2.52514 + vertex 1.55327 1.89499 2.52523 + vertex 1.55388 1.89925 2.52425 + endloop + endfacet + facet normal 0.183768 0.182191 0.965938 + outer loop + vertex 1.55327 1.89499 2.52523 + vertex 1.55459 1.88995 2.52593 + vertex 1.55907 1.89279 2.52454 + endloop + endfacet + facet normal 0.195209 0.18211 0.963706 + outer loop + vertex 1.55594 1.88477 2.52664 + vertex 1.55459 1.88995 2.52593 + vertex 1.55015 1.88691 2.5274 + endloop + endfacet + facet normal 0.170127 0.170716 0.970522 + outer loop + vertex 1.55041 1.89156 2.5265 + vertex 1.54859 1.89449 2.52631 + vertex 1.54553 1.89094 2.52747 + endloop + endfacet + facet normal 0.187985 0.183571 0.964864 + outer loop + vertex 1.54723 1.88258 2.5288 + vertex 1.55015 1.88691 2.5274 + vertex 1.54566 1.88617 2.52842 + endloop + endfacet + facet normal 0.145265 0.166009 0.975366 + outer loop + vertex 1.54723 1.88258 2.5288 + vertex 1.54566 1.88617 2.52842 + vertex 1.54361 1.88323 2.52922 + endloop + endfacet + facet normal 0.073798 0.215656 0.973677 + outer loop + vertex 1.54361 1.88323 2.52922 + vertex 1.54566 1.88617 2.52842 + vertex 1.54226 1.88683 2.52853 + endloop + endfacet + facet normal 0.150703 0.201137 0.967901 + outer loop + vertex 1.54388 1.8784 2.53019 + vertex 1.54723 1.88258 2.5288 + vertex 1.54361 1.88323 2.52922 + endloop + endfacet + facet normal 0.201651 0.225274 0.953199 + outer loop + vertex 1.54378 1.87382 2.53129 + vertex 1.54874 1.87409 2.53018 + vertex 1.54388 1.8784 2.53019 + endloop + endfacet + facet normal 0.112282 0.129838 0.985157 + outer loop + vertex 1.54546 1.87084 2.53149 + vertex 1.54378 1.87382 2.53129 + vertex 1.54093 1.87045 2.53206 + endloop + endfacet + facet normal -0.188612 0.20378 0.960677 + outer loop + vertex 1.54102 1.87496 2.53141 + vertex 1.53974 1.87758 2.5306 + vertex 1.53836 1.87425 2.53104 + endloop + endfacet + facet normal 0.132119 0.191971 0.972467 + outer loop + vertex 1.54093 1.87045 2.53206 + vertex 1.54068 1.86581 2.53301 + vertex 1.54555 1.86611 2.53229 + endloop + endfacet + facet normal 0.129908 0.216261 0.967654 + outer loop + vertex 1.54198 1.86233 2.53361 + vertex 1.54555 1.86611 2.53229 + vertex 1.54068 1.86581 2.53301 + endloop + endfacet + facet normal 0.176613 0.185394 0.966663 + outer loop + vertex 1.54334 1.85872 2.53406 + vertex 1.54573 1.86133 2.53312 + vertex 1.54198 1.86233 2.53361 + endloop + endfacet + facet normal 0.194981 0.19063 0.962103 + outer loop + vertex 1.54344 1.85386 2.535 + vertex 1.54726 1.85764 2.53348 + vertex 1.54334 1.85872 2.53406 + endloop + endfacet + facet normal 0.205322 0.191168 0.959843 + outer loop + vertex 1.54347 1.84901 2.53596 + vertex 1.54865 1.84886 2.53488 + vertex 1.54344 1.85386 2.535 + endloop + endfacet + facet normal 0.197957 0.169388 0.965464 + outer loop + vertex 1.54532 1.84574 2.53615 + vertex 1.54347 1.84901 2.53596 + vertex 1.54039 1.84563 2.53718 + endloop + endfacet + facet normal 0.102732 0.146916 0.9838 + outer loop + vertex 1.54013 1.85068 2.53636 + vertex 1.53843 1.85386 2.53607 + vertex 1.53596 1.85057 2.53681 + endloop + endfacet + facet normal 0.0831676 0.153112 0.984703 + outer loop + vertex 1.537 1.84146 2.53812 + vertex 1.54039 1.84563 2.53718 + vertex 1.53593 1.84551 2.53758 + endloop + endfacet + facet normal 0.0578436 0.160009 0.985419 + outer loop + vertex 1.53783 1.83705 2.53879 + vertex 1.54052 1.84047 2.53807 + vertex 1.537 1.84146 2.53812 + endloop + endfacet + facet normal 0.0945604 0.188748 0.977462 + outer loop + vertex 1.53914 1.83358 2.53933 + vertex 1.5419 1.83684 2.53843 + vertex 1.53783 1.83705 2.53879 + endloop + endfacet + facet normal 0.138718 0.179425 0.973943 + outer loop + vertex 1.53894 1.82877 2.54024 + vertex 1.54274 1.83276 2.53897 + vertex 1.53914 1.83358 2.53933 + endloop + endfacet + facet normal 0.196293 0.211867 0.957383 + outer loop + vertex 1.53873 1.82428 2.54128 + vertex 1.54389 1.82426 2.54023 + vertex 1.53894 1.82877 2.54024 + endloop + endfacet + facet normal 0.148813 0.14457 0.97824 + outer loop + vertex 1.54046 1.82117 2.54148 + vertex 1.53873 1.82428 2.54128 + vertex 1.5356 1.82084 2.54227 + endloop + endfacet + facet normal -0.111693 0.264381 0.957929 + outer loop + vertex 1.5356 1.82541 2.54143 + vertex 1.53411 1.82778 2.54061 + vertex 1.53192 1.82415 2.54135 + endloop + endfacet + facet normal 0.00369008 0.18067 0.983537 + outer loop + vertex 1.53548 1.81588 2.54318 + vertex 1.5356 1.82084 2.54227 + vertex 1.53199 1.81693 2.543 + endloop + endfacet + facet normal 0.00219788 0.175841 0.984416 + outer loop + vertex 1.53275 1.81244 2.5438 + vertex 1.53548 1.81588 2.54318 + vertex 1.53199 1.81693 2.543 + endloop + endfacet + facet normal 0.0674345 0.191164 0.979239 + outer loop + vertex 1.53405 1.80869 2.54444 + vertex 1.53685 1.81207 2.54359 + vertex 1.53275 1.81244 2.5438 + endloop + endfacet + facet normal 0.136581 0.174365 0.975163 + outer loop + vertex 1.5339 1.80363 2.54537 + vertex 1.5377 1.80775 2.5441 + vertex 1.53405 1.80869 2.54444 + endloop + endfacet + facet normal 0.173266 0.157441 0.972209 + outer loop + vertex 1.5339 1.80363 2.54537 + vertex 1.53852 1.79915 2.54527 + vertex 1.53894 1.80404 2.5444 + endloop + endfacet + facet normal 0.215327 0.143184 0.965988 + outer loop + vertex 1.53813 1.79432 2.54607 + vertex 1.54292 1.79453 2.54497 + vertex 1.53852 1.79915 2.54527 + endloop + endfacet + facet normal 0.206279 0.111998 0.972063 + outer loop + vertex 1.53981 1.79021 2.54619 + vertex 1.53813 1.79432 2.54607 + vertex 1.5348 1.79143 2.54711 + endloop + endfacet + facet normal 0.120272 0.108328 0.986813 + outer loop + vertex 1.53507 1.79601 2.54654 + vertex 1.53363 1.79899 2.54639 + vertex 1.53107 1.79566 2.54707 + endloop + endfacet + facet normal 0.202778 0.0958243 0.974525 + outer loop + vertex 1.5348 1.79143 2.54711 + vertex 1.53681 1.78559 2.54727 + vertex 1.53981 1.79021 2.54619 + endloop + endfacet + facet normal 0.0675333 0.112452 0.99136 + outer loop + vertex 1.53592 1.78068 2.54789 + vertex 1.53681 1.78559 2.54727 + vertex 1.53217 1.78171 2.54802 + endloop + endfacet + facet normal 0.0707967 0.124522 0.989688 + outer loop + vertex 1.53231 1.77719 2.54858 + vertex 1.53592 1.78068 2.54789 + vertex 1.53217 1.78171 2.54802 + endloop + endfacet + facet normal 0.109426 0.152547 0.98222 + outer loop + vertex 1.53284 1.77299 2.54918 + vertex 1.53674 1.77687 2.54814 + vertex 1.53231 1.77719 2.54858 + endloop + endfacet + facet normal 0.158847 0.13714 0.977732 + outer loop + vertex 1.53391 1.76923 2.54953 + vertex 1.53733 1.77253 2.54851 + vertex 1.53284 1.77299 2.54918 + endloop + endfacet + facet normal 0.183206 0.151076 0.971397 + outer loop + vertex 1.53363 1.76421 2.55036 + vertex 1.53796 1.76813 2.54894 + vertex 1.53391 1.76923 2.54953 + endloop + endfacet + facet normal 0.212847 0.162606 0.96346 + outer loop + vertex 1.53366 1.75938 2.55117 + vertex 1.53882 1.75919 2.55006 + vertex 1.53363 1.76421 2.55036 + endloop + endfacet + facet normal 0.203827 0.13545 0.969592 + outer loop + vertex 1.5355 1.7561 2.55124 + vertex 1.53366 1.75938 2.55117 + vertex 1.53064 1.75595 2.55229 + endloop + endfacet + facet normal 0.0893745 0.121656 0.98854 + outer loop + vertex 1.53033 1.76104 2.55162 + vertex 1.52856 1.76414 2.5514 + vertex 1.52622 1.76087 2.55201 + endloop + endfacet + facet normal 0.0856589 0.107352 0.990524 + outer loop + vertex 1.52715 1.75157 2.55306 + vertex 1.53064 1.75595 2.55229 + vertex 1.52621 1.75572 2.55269 + endloop + endfacet + facet normal 0.0464117 0.0869528 0.995131 + outer loop + vertex 1.52762 1.74689 2.55345 + vertex 1.53063 1.75058 2.55299 + vertex 1.52715 1.75157 2.55306 + endloop + endfacet + facet normal 0.0620905 0.120619 0.990755 + outer loop + vertex 1.52824 1.74235 2.55396 + vertex 1.53176 1.74667 2.55322 + vertex 1.52762 1.74689 2.55345 + endloop + endfacet + facet normal 0.0851639 0.160912 0.983288 + outer loop + vertex 1.52925 1.73869 2.55447 + vertex 1.53245 1.74237 2.5536 + vertex 1.52824 1.74235 2.55396 + endloop + endfacet + facet normal 0.187166 0.110604 0.976082 + outer loop + vertex 1.53682 1.74201 2.5528 + vertex 1.53548 1.74595 2.55261 + vertex 1.53245 1.74237 2.5536 + endloop + endfacet + facet normal 0.202642 0.115694 0.972395 + outer loop + vertex 1.53682 1.74201 2.5528 + vertex 1.5399 1.74666 2.5516 + vertex 1.53548 1.74595 2.55261 + endloop + endfacet + facet normal 0.191132 0.12368 0.973741 + outer loop + vertex 1.54189 1.7408 2.55196 + vertex 1.5399 1.74666 2.5516 + vertex 1.53682 1.74201 2.5528 + endloop + endfacet + facet normal 0.18926 0.114879 0.975184 + outer loop + vertex 1.53738 1.73741 2.55323 + vertex 1.54189 1.7408 2.55196 + vertex 1.53682 1.74201 2.5528 + endloop + endfacet + facet normal 0.188225 0.116267 0.97522 + outer loop + vertex 1.54104 1.73594 2.5527 + vertex 1.54189 1.7408 2.55196 + vertex 1.53738 1.73741 2.55323 + endloop + endfacet + facet normal 0.1894 0.119429 0.97461 + outer loop + vertex 1.53743 1.73291 2.55377 + vertex 1.54104 1.73594 2.5527 + vertex 1.53738 1.73741 2.55323 + endloop + endfacet + facet normal 0.187365 0.121877 0.9747 + outer loop + vertex 1.54185 1.73196 2.55304 + vertex 1.54104 1.73594 2.5527 + vertex 1.53743 1.73291 2.55377 + endloop + endfacet + facet normal 0.186755 0.118609 0.97522 + outer loop + vertex 1.53798 1.72827 2.55423 + vertex 1.54185 1.73196 2.55304 + vertex 1.53743 1.73291 2.55377 + endloop + endfacet + facet normal 0.185528 0.119918 0.975294 + outer loop + vertex 1.54247 1.72747 2.55347 + vertex 1.54185 1.73196 2.55304 + vertex 1.53798 1.72827 2.55423 + endloop + endfacet + facet normal 0.172058 0.119039 0.977868 + outer loop + vertex 1.54185 1.73196 2.55304 + vertex 1.54599 1.73604 2.55182 + vertex 1.54104 1.73594 2.5527 + endloop + endfacet + facet normal 0.199689 0.119288 0.972571 + outer loop + vertex 1.53743 1.73291 2.55377 + vertex 1.53738 1.73741 2.55323 + vertex 1.5337 1.7343 2.55437 + endloop + endfacet + facet normal 0.203329 0.129941 0.97045 + outer loop + vertex 1.53266 1.72958 2.55522 + vertex 1.53743 1.73291 2.55377 + vertex 1.5337 1.7343 2.55437 + endloop + endfacet + facet normal 0.106632 0.0740482 0.991537 + outer loop + vertex 1.52959 1.72521 2.55643 + vertex 1.52804 1.72904 2.55631 + vertex 1.52524 1.72627 2.55681 + endloop + endfacet + facet normal -0.201332 0.196381 0.959635 + outer loop + vertex 1.5255 1.73024 2.55646 + vertex 1.5244 1.73268 2.55573 + vertex 1.52304 1.72953 2.55609 + endloop + endfacet + facet normal 0.0883336 0.144762 0.985516 + outer loop + vertex 1.52669 1.7118 2.55813 + vertex 1.53092 1.7161 2.55712 + vertex 1.52587 1.71585 2.55761 + endloop + endfacet + facet normal 0.109661 0.123951 0.98621 + outer loop + vertex 1.53065 1.71087 2.55781 + vertex 1.53092 1.7161 2.55712 + vertex 1.52669 1.7118 2.55813 + endloop + endfacet + facet normal 0.114406 0.145511 0.98272 + outer loop + vertex 1.52741 1.70741 2.5587 + vertex 1.53065 1.71087 2.55781 + vertex 1.52669 1.7118 2.55813 + endloop + endfacet + facet normal 0.166058 0.0967973 0.981354 + outer loop + vertex 1.53181 1.70696 2.558 + vertex 1.53065 1.71087 2.55781 + vertex 1.52741 1.70741 2.5587 + endloop + endfacet + facet normal 0.167864 0.118829 0.978622 + outer loop + vertex 1.52799 1.7031 2.55912 + vertex 1.53181 1.70696 2.558 + vertex 1.52741 1.70741 2.5587 + endloop + endfacet + facet normal 0.196209 0.0900955 0.976414 + outer loop + vertex 1.53245 1.70254 2.55828 + vertex 1.53181 1.70696 2.558 + vertex 1.52799 1.7031 2.55912 + endloop + endfacet + facet normal 0.198219 0.105996 0.97441 + outer loop + vertex 1.53181 1.70696 2.558 + vertex 1.53561 1.71116 2.55677 + vertex 1.53065 1.71087 2.55781 + endloop + endfacet + facet normal 0.110879 0.112075 0.987494 + outer loop + vertex 1.52799 1.7031 2.55912 + vertex 1.52741 1.70741 2.5587 + vertex 1.5242 1.70381 2.55947 + endloop + endfacet + facet normal 0.216322 0.149517 0.964805 + outer loop + vertex 1.52285 1.69394 2.56122 + vertex 1.52755 1.69445 2.56009 + vertex 1.52357 1.69873 2.56032 + endloop + endfacet + facet normal 0.212805 0.087652 0.973155 + outer loop + vertex 1.53302 1.69317 2.55901 + vertex 1.53271 1.69799 2.55864 + vertex 1.52755 1.69445 2.56009 + endloop + endfacet + facet normal 0.196901 0.0968444 0.975629 + outer loop + vertex 1.52877 1.69928 2.55935 + vertex 1.53245 1.70254 2.55828 + vertex 1.52799 1.7031 2.55912 + endloop + endfacet + facet normal 0.189997 0.0946234 0.977214 + outer loop + vertex 1.53728 1.69701 2.55785 + vertex 1.53683 1.70187 2.55747 + vertex 1.53271 1.69799 2.55864 + endloop + endfacet + facet normal 0.201664 0.0908034 0.975237 + outer loop + vertex 1.53245 1.70254 2.55828 + vertex 1.53558 1.70595 2.55731 + vertex 1.53181 1.70696 2.558 + endloop + endfacet + facet normal 0.177092 0.102378 0.978855 + outer loop + vertex 1.54164 1.70068 2.55672 + vertex 1.53981 1.70653 2.55644 + vertex 1.53683 1.70187 2.55747 + endloop + endfacet + facet normal 0.204016 0.100581 0.973787 + outer loop + vertex 1.53558 1.70595 2.55731 + vertex 1.53561 1.71116 2.55677 + vertex 1.53181 1.70696 2.558 + endloop + endfacet + facet normal 0.171321 0.108396 0.979234 + outer loop + vertex 1.54312 1.70915 2.55554 + vertex 1.54452 1.70503 2.55575 + vertex 1.54766 1.70924 2.55473 + endloop + endfacet + facet normal 0.157448 0.108705 0.981526 + outer loop + vertex 1.55288 1.70782 2.55405 + vertex 1.55265 1.71264 2.55356 + vertex 1.54766 1.70924 2.55473 + endloop + endfacet + facet normal 0.157551 0.112291 0.981106 + outer loop + vertex 1.54877 1.71395 2.55402 + vertex 1.5524 1.71713 2.55307 + vertex 1.54801 1.71784 2.55369 + endloop + endfacet + facet normal 0.125183 0.119436 0.984918 + outer loop + vertex 1.55745 1.71214 2.55301 + vertex 1.5569 1.71686 2.5525 + vertex 1.55265 1.71264 2.55356 + endloop + endfacet + facet normal 0.0979878 0.120398 0.987878 + outer loop + vertex 1.55559 1.72597 2.55155 + vertex 1.55564 1.72072 2.55218 + vertex 1.56032 1.72196 2.55157 + endloop + endfacet + facet normal 0.158252 0.117259 0.980411 + outer loop + vertex 1.5524 1.71713 2.55307 + vertex 1.55181 1.72158 2.55263 + vertex 1.54801 1.71784 2.55369 + endloop + endfacet + facet normal 0.167504 0.114083 0.979248 + outer loop + vertex 1.54877 1.71395 2.55402 + vertex 1.54801 1.71784 2.55369 + vertex 1.5436 1.71408 2.55489 + endloop + endfacet + facet normal 0.180119 0.112352 0.977207 + outer loop + vertex 1.53881 1.71436 2.55574 + vertex 1.54022 1.71109 2.55585 + vertex 1.5436 1.71408 2.55489 + endloop + endfacet + facet normal 0.195429 0.118834 0.973492 + outer loop + vertex 1.54022 1.71109 2.55585 + vertex 1.53881 1.71436 2.55574 + vertex 1.53561 1.71116 2.55677 + endloop + endfacet + facet normal 0.197277 0.117742 0.973251 + outer loop + vertex 1.53092 1.7161 2.55712 + vertex 1.53065 1.71087 2.55781 + vertex 1.53561 1.71116 2.55677 + endloop + endfacet + facet normal 0.202143 0.110482 0.973104 + outer loop + vertex 1.53424 1.7194 2.5561 + vertex 1.53573 1.71615 2.55616 + vertex 1.53906 1.7192 2.55512 + endloop + endfacet + facet normal 0.202235 0.115768 0.97247 + outer loop + vertex 1.53424 1.7194 2.5561 + vertex 1.53906 1.7192 2.55512 + vertex 1.53469 1.72386 2.55547 + endloop + endfacet + facet normal 0.0921158 0.0824014 0.992333 + outer loop + vertex 1.52687 1.72081 2.55711 + vertex 1.52587 1.71585 2.55761 + vertex 1.53092 1.7161 2.55712 + endloop + endfacet + facet normal 0.109366 0.0857036 0.9903 + outer loop + vertex 1.52524 1.72627 2.55681 + vertex 1.52687 1.72081 2.55711 + vertex 1.52959 1.72521 2.55643 + endloop + endfacet + facet normal 0.209198 0.114875 0.971102 + outer loop + vertex 1.53424 1.7194 2.5561 + vertex 1.53469 1.72386 2.55547 + vertex 1.53119 1.72122 2.55654 + endloop + endfacet + facet normal 0.214637 0.117264 0.969629 + outer loop + vertex 1.52804 1.72904 2.55631 + vertex 1.52959 1.72521 2.55643 + vertex 1.53266 1.72958 2.55522 + endloop + endfacet + facet normal 0.209619 0.12085 0.970286 + outer loop + vertex 1.53798 1.72827 2.55423 + vertex 1.53743 1.73291 2.55377 + vertex 1.53266 1.72958 2.55522 + endloop + endfacet + facet normal 0.178672 0.120476 0.976505 + outer loop + vertex 1.54415 1.71911 2.5542 + vertex 1.54314 1.72305 2.5539 + vertex 1.53906 1.7192 2.55512 + endloop + endfacet + facet normal 0.184479 0.113058 0.976312 + outer loop + vertex 1.53933 1.72425 2.55444 + vertex 1.54247 1.72747 2.55347 + vertex 1.53798 1.72827 2.55423 + endloop + endfacet + facet normal 0.16548 0.11925 0.978977 + outer loop + vertex 1.54749 1.72225 2.55326 + vertex 1.5468 1.72673 2.55283 + vertex 1.54314 1.72305 2.5539 + endloop + endfacet + facet normal 0.169939 0.118031 0.97836 + outer loop + vertex 1.54247 1.72747 2.55347 + vertex 1.54569 1.73076 2.55252 + vertex 1.54185 1.73196 2.55304 + endloop + endfacet + facet normal 0.161974 0.122563 0.979154 + outer loop + vertex 1.55065 1.72558 2.55233 + vertex 1.55065 1.73092 2.55167 + vertex 1.5468 1.72673 2.55283 + endloop + endfacet + facet normal 0.170649 0.120492 0.977937 + outer loop + vertex 1.54569 1.73076 2.55252 + vertex 1.54599 1.73604 2.55182 + vertex 1.54185 1.73196 2.55304 + endloop + endfacet + facet normal 0.156873 0.117624 0.980589 + outer loop + vertex 1.54915 1.73923 2.55088 + vertex 1.55057 1.73598 2.55104 + vertex 1.55376 1.73888 2.55018 + endloop + endfacet + facet normal 0.17204 0.119494 0.977816 + outer loop + vertex 1.54189 1.7408 2.55196 + vertex 1.54104 1.73594 2.5527 + vertex 1.54599 1.73604 2.55182 + endloop + endfacet + facet normal 0.181931 0.120702 0.975875 + outer loop + vertex 1.5399 1.74666 2.5516 + vertex 1.54189 1.7408 2.55196 + vertex 1.54484 1.7452 2.55086 + endloop + endfacet + facet normal 0.168599 0.123763 0.977884 + outer loop + vertex 1.54915 1.73923 2.55088 + vertex 1.54969 1.74359 2.55023 + vertex 1.5463 1.74112 2.55113 + endloop + endfacet + facet normal 0.168772 0.128555 0.977236 + outer loop + vertex 1.54336 1.74931 2.55058 + vertex 1.54484 1.7452 2.55086 + vertex 1.54791 1.74938 2.54978 + endloop + endfacet + facet normal 0.161454 0.128712 0.978451 + outer loop + vertex 1.55299 1.74792 2.54914 + vertex 1.55243 1.75251 2.54862 + vertex 1.54791 1.74938 2.54978 + endloop + endfacet + facet normal 0.157294 0.125416 0.979556 + outer loop + vertex 1.54915 1.73923 2.55088 + vertex 1.55376 1.73888 2.55018 + vertex 1.54969 1.74359 2.55023 + endloop + endfacet + facet normal 0.125927 0.132901 0.983097 + outer loop + vertex 1.55875 1.73874 2.54956 + vertex 1.55795 1.74277 2.54912 + vertex 1.55376 1.73888 2.55018 + endloop + endfacet + facet normal 0.139392 0.121866 0.98271 + outer loop + vertex 1.55414 1.74388 2.54947 + vertex 1.55759 1.7474 2.54855 + vertex 1.55299 1.74792 2.54914 + endloop + endfacet + facet normal 0.0863252 0.137475 0.986736 + outer loop + vertex 1.56263 1.74231 2.54877 + vertex 1.56236 1.74711 2.54813 + vertex 1.55795 1.74277 2.54912 + endloop + endfacet + facet normal 0.108185 0.129645 0.985641 + outer loop + vertex 1.55759 1.7474 2.54855 + vertex 1.56174 1.75194 2.5475 + vertex 1.55686 1.75201 2.54802 + endloop + endfacet + facet normal 0.0481861 0.144528 0.988327 + outer loop + vertex 1.56738 1.74706 2.54789 + vertex 1.56685 1.75181 2.54722 + vertex 1.56236 1.74711 2.54813 + endloop + endfacet + facet normal 0.0234147 0.145988 0.989009 + outer loop + vertex 1.57182 1.75165 2.54713 + vertex 1.57091 1.75595 2.54651 + vertex 1.56685 1.75181 2.54722 + endloop + endfacet + facet normal 0.0232925 0.141971 0.989597 + outer loop + vertex 1.56738 1.74706 2.54789 + vertex 1.57182 1.75165 2.54713 + vertex 1.56685 1.75181 2.54722 + endloop + endfacet + facet normal 0.0250014 0.140349 0.989786 + outer loop + vertex 1.57222 1.74705 2.54777 + vertex 1.57182 1.75165 2.54713 + vertex 1.56738 1.74706 2.54789 + endloop + endfacet + facet normal 0.0250003 0.140858 0.989714 + outer loop + vertex 1.5675 1.74212 2.54859 + vertex 1.57222 1.74705 2.54777 + vertex 1.56738 1.74706 2.54789 + endloop + endfacet + facet normal 0.0317009 0.134567 0.990397 + outer loop + vertex 1.57243 1.74214 2.54843 + vertex 1.57222 1.74705 2.54777 + vertex 1.5675 1.74212 2.54859 + endloop + endfacet + facet normal 0.0316644 0.138765 0.989819 + outer loop + vertex 1.56756 1.73731 2.54926 + vertex 1.57243 1.74214 2.54843 + vertex 1.5675 1.74212 2.54859 + endloop + endfacet + facet normal 0.0369294 0.133549 0.990354 + outer loop + vertex 1.57241 1.73714 2.54911 + vertex 1.57243 1.74214 2.54843 + vertex 1.56756 1.73731 2.54926 + endloop + endfacet + facet normal 0.0370076 0.136026 0.990014 + outer loop + vertex 1.56763 1.73284 2.54987 + vertex 1.57241 1.73714 2.54911 + vertex 1.56756 1.73731 2.54926 + endloop + endfacet + facet normal 0.0399189 0.132842 0.990333 + outer loop + vertex 1.5726 1.73252 2.54972 + vertex 1.57241 1.73714 2.54911 + vertex 1.56763 1.73284 2.54987 + endloop + endfacet + facet normal 0.0399933 0.134049 0.990167 + outer loop + vertex 1.56824 1.7287 2.55041 + vertex 1.5726 1.73252 2.54972 + vertex 1.56763 1.73284 2.54987 + endloop + endfacet + facet normal 0.0435928 0.130005 0.990555 + outer loop + vertex 1.57335 1.72834 2.55023 + vertex 1.5726 1.73252 2.54972 + vertex 1.56824 1.7287 2.55041 + endloop + endfacet + facet normal 0.0440071 0.136415 0.989674 + outer loop + vertex 1.56824 1.7287 2.55041 + vertex 1.56946 1.72485 2.55089 + vertex 1.57335 1.72834 2.55023 + endloop + endfacet + facet normal 0.043334 0.137151 0.989602 + outer loop + vertex 1.56946 1.72485 2.55089 + vertex 1.57421 1.72448 2.55073 + vertex 1.57335 1.72834 2.55023 + endloop + endfacet + facet normal 0.0430666 0.133482 0.990115 + outer loop + vertex 1.57421 1.72448 2.55073 + vertex 1.56946 1.72485 2.55089 + vertex 1.57068 1.72106 2.55134 + endloop + endfacet + facet normal 0.0181006 0.125708 0.991902 + outer loop + vertex 1.57068 1.72106 2.55134 + vertex 1.56946 1.72485 2.55089 + vertex 1.5658 1.72127 2.55141 + endloop + endfacet + facet normal 0.0178191 0.118955 0.99274 + outer loop + vertex 1.56691 1.71696 2.5519 + vertex 1.57068 1.72106 2.55134 + vertex 1.5658 1.72127 2.55141 + endloop + endfacet + facet normal 0.021356 0.115748 0.993049 + outer loop + vertex 1.57168 1.71692 2.55181 + vertex 1.57068 1.72106 2.55134 + vertex 1.56691 1.71696 2.5519 + endloop + endfacet + facet normal 0.0213722 0.118548 0.992718 + outer loop + vertex 1.56748 1.71229 2.55245 + vertex 1.57168 1.71692 2.55181 + vertex 1.56691 1.71696 2.5519 + endloop + endfacet + facet normal 0.0302757 0.110565 0.993408 + outer loop + vertex 1.57233 1.71219 2.55231 + vertex 1.57168 1.71692 2.55181 + vertex 1.56748 1.71229 2.55245 + endloop + endfacet + facet normal 0.0304107 0.118145 0.992531 + outer loop + vertex 1.56759 1.70728 2.55304 + vertex 1.57233 1.71219 2.55231 + vertex 1.56748 1.71229 2.55245 + endloop + endfacet + facet normal 0.0325703 0.116088 0.992705 + outer loop + vertex 1.57237 1.70712 2.5529 + vertex 1.57233 1.71219 2.55231 + vertex 1.56759 1.70728 2.55304 + endloop + endfacet + facet normal 0.0325612 0.115785 0.99274 + outer loop + vertex 1.56747 1.70218 2.55364 + vertex 1.57237 1.70712 2.5529 + vertex 1.56759 1.70728 2.55304 + endloop + endfacet + facet normal 0.0366349 0.111786 0.993057 + outer loop + vertex 1.57223 1.70216 2.55347 + vertex 1.57237 1.70712 2.5529 + vertex 1.56747 1.70218 2.55364 + endloop + endfacet + facet normal 0.0366344 0.106908 0.993594 + outer loop + vertex 1.56735 1.69718 2.55418 + vertex 1.57223 1.70216 2.55347 + vertex 1.56747 1.70218 2.55364 + endloop + endfacet + facet normal 0.0487959 0.095067 0.994274 + outer loop + vertex 1.57235 1.6972 2.55394 + vertex 1.57223 1.70216 2.55347 + vertex 1.56735 1.69718 2.55418 + endloop + endfacet + facet normal 0.0487738 0.0975378 0.994036 + outer loop + vertex 1.56741 1.69222 2.55467 + vertex 1.57235 1.6972 2.55394 + vertex 1.56735 1.69718 2.55418 + endloop + endfacet + facet normal 0.0524519 0.0939128 0.994198 + outer loop + vertex 1.57258 1.69206 2.55441 + vertex 1.57235 1.6972 2.55394 + vertex 1.56741 1.69222 2.55467 + endloop + endfacet + facet normal 0.0525235 0.0966045 0.993936 + outer loop + vertex 1.56781 1.68724 2.55513 + vertex 1.57258 1.69206 2.55441 + vertex 1.56741 1.69222 2.55467 + endloop + endfacet + facet normal 0.080144 0.134136 0.987717 + outer loop + vertex 1.5726 1.73252 2.54972 + vertex 1.57718 1.73685 2.54876 + vertex 1.57241 1.73714 2.54911 + endloop + endfacet + facet normal 0.0796855 0.125131 0.988935 + outer loop + vertex 1.57718 1.73685 2.54876 + vertex 1.57721 1.74195 2.54811 + vertex 1.57241 1.73714 2.54911 + endloop + endfacet + facet normal 0.0902215 0.123603 0.988222 + outer loop + vertex 1.57747 1.73228 2.5493 + vertex 1.57718 1.73685 2.54876 + vertex 1.5726 1.73252 2.54972 + endloop + endfacet + facet normal 0.0907662 0.137996 0.986265 + outer loop + vertex 1.57335 1.72834 2.55023 + vertex 1.57747 1.73228 2.5493 + vertex 1.5726 1.73252 2.54972 + endloop + endfacet + facet normal 0.0715077 0.1332 0.988506 + outer loop + vertex 1.57241 1.73714 2.54911 + vertex 1.57721 1.74195 2.54811 + vertex 1.57243 1.74214 2.54843 + endloop + endfacet + facet normal 0.0710386 0.117892 0.990482 + outer loop + vertex 1.57721 1.74195 2.54811 + vertex 1.57678 1.74707 2.54753 + vertex 1.57243 1.74214 2.54843 + endloop + endfacet + facet normal 0.05116 0.135273 0.989487 + outer loop + vertex 1.57243 1.74214 2.54843 + vertex 1.57678 1.74707 2.54753 + vertex 1.57222 1.74705 2.54777 + endloop + endfacet + facet normal 0.0512829 0.12369 0.990995 + outer loop + vertex 1.57678 1.74707 2.54753 + vertex 1.57572 1.75095 2.5471 + vertex 1.57222 1.74705 2.54777 + endloop + endfacet + facet normal 0.0318267 0.140904 0.989512 + outer loop + vertex 1.57222 1.74705 2.54777 + vertex 1.57572 1.75095 2.5471 + vertex 1.57182 1.75165 2.54713 + endloop + endfacet + facet normal 0.0329433 0.147175 0.988562 + outer loop + vertex 1.57572 1.75095 2.5471 + vertex 1.57617 1.75523 2.54645 + vertex 1.57182 1.75165 2.54713 + endloop + endfacet + facet normal 0.0324036 0.147816 0.988484 + outer loop + vertex 1.57182 1.75165 2.54713 + vertex 1.57617 1.75523 2.54645 + vertex 1.57091 1.75595 2.54651 + endloop + endfacet + facet normal 0.0321793 0.146147 0.988739 + outer loop + vertex 1.57617 1.75523 2.54645 + vertex 1.57456 1.75943 2.54588 + vertex 1.57091 1.75595 2.54651 + endloop + endfacet + facet normal 0.0675309 0.15921 0.984932 + outer loop + vertex 1.57871 1.75863 2.54573 + vertex 1.57456 1.75943 2.54588 + vertex 1.57617 1.75523 2.54645 + endloop + endfacet + facet normal 0.0694229 0.169331 0.983111 + outer loop + vertex 1.57456 1.75943 2.54588 + vertex 1.57871 1.75863 2.54573 + vertex 1.57901 1.76267 2.54501 + endloop + endfacet + facet normal 0.07213 0.165734 0.983529 + outer loop + vertex 1.57338 1.7634 2.5453 + vertex 1.57456 1.75943 2.54588 + vertex 1.57901 1.76267 2.54501 + endloop + endfacet + facet normal 0.0685991 0.136549 0.988255 + outer loop + vertex 1.57901 1.76267 2.54501 + vertex 1.57768 1.76744 2.54444 + vertex 1.57338 1.7634 2.5453 + endloop + endfacet + facet normal 0.0523862 0.153463 0.986765 + outer loop + vertex 1.57338 1.7634 2.5453 + vertex 1.57768 1.76744 2.54444 + vertex 1.57254 1.7676 2.54469 + endloop + endfacet + facet normal 0.0519142 0.134128 0.989603 + outer loop + vertex 1.57768 1.76744 2.54444 + vertex 1.57725 1.77215 2.54383 + vertex 1.57254 1.7676 2.54469 + endloop + endfacet + facet normal 0.03815 0.148125 0.988233 + outer loop + vertex 1.57254 1.7676 2.54469 + vertex 1.57725 1.77215 2.54383 + vertex 1.57235 1.77211 2.54402 + endloop + endfacet + facet normal 0.038371 0.130856 0.990659 + outer loop + vertex 1.57725 1.77215 2.54383 + vertex 1.57717 1.77694 2.5432 + vertex 1.57235 1.77211 2.54402 + endloop + endfacet + facet normal 0.0253226 0.143652 0.989304 + outer loop + vertex 1.57235 1.77211 2.54402 + vertex 1.57717 1.77694 2.5432 + vertex 1.57244 1.77695 2.54332 + endloop + endfacet + facet normal 0.0253302 0.132022 0.990923 + outer loop + vertex 1.57717 1.77694 2.5432 + vertex 1.57731 1.78186 2.54254 + vertex 1.57244 1.77695 2.54332 + endloop + endfacet + facet normal 0.0170527 0.140093 0.989992 + outer loop + vertex 1.57244 1.77695 2.54332 + vertex 1.57731 1.78186 2.54254 + vertex 1.57235 1.7821 2.54259 + endloop + endfacet + facet normal 0.0165385 0.129139 0.991489 + outer loop + vertex 1.57731 1.78186 2.54254 + vertex 1.57718 1.78691 2.54188 + vertex 1.57235 1.7821 2.54259 + endloop + endfacet + facet normal 0.00788872 0.137669 0.990447 + outer loop + vertex 1.57235 1.7821 2.54259 + vertex 1.57718 1.78691 2.54188 + vertex 1.57141 1.7879 2.54179 + endloop + endfacet + facet normal 0.00593555 0.126357 0.991967 + outer loop + vertex 1.57141 1.7879 2.54179 + vertex 1.57718 1.78691 2.54188 + vertex 1.57705 1.79157 2.54129 + endloop + endfacet + facet normal -0.0335524 0.185503 0.982071 + outer loop + vertex 1.57357 1.79191 2.54111 + vertex 1.57141 1.7879 2.54179 + vertex 1.57705 1.79157 2.54129 + endloop + endfacet + facet normal -0.0374589 0.147952 0.988285 + outer loop + vertex 1.57357 1.79191 2.54111 + vertex 1.57705 1.79157 2.54129 + vertex 1.57576 1.79393 2.54089 + endloop + endfacet + facet normal -0.024202 0.133866 0.990704 + outer loop + vertex 1.57576 1.79393 2.54089 + vertex 1.57254 1.79503 2.54066 + vertex 1.57357 1.79191 2.54111 + endloop + endfacet + facet normal -0.0171729 0.153905 0.987936 + outer loop + vertex 1.57576 1.79393 2.54089 + vertex 1.5773 1.79737 2.54038 + vertex 1.57254 1.79503 2.54066 + endloop + endfacet + facet normal -0.0626765 0.173588 0.982822 + outer loop + vertex 1.57576 1.79393 2.54089 + vertex 1.57832 1.7948 2.5409 + vertex 1.5773 1.79737 2.54038 + endloop + endfacet + facet normal -0.0514521 0.140397 0.988757 + outer loop + vertex 1.57832 1.7948 2.5409 + vertex 1.57576 1.79393 2.54089 + vertex 1.57705 1.79157 2.54129 + endloop + endfacet + facet normal 0.0150508 0.126604 0.991839 + outer loop + vertex 1.57718 1.78691 2.54188 + vertex 1.58136 1.79089 2.54131 + vertex 1.57705 1.79157 2.54129 + endloop + endfacet + facet normal 0.0327331 0.146533 0.988664 + outer loop + vertex 1.56949 1.75995 2.54594 + vertex 1.5645 1.76059 2.54601 + vertex 1.56576 1.75632 2.54661 + endloop + endfacet + facet normal 0.0731775 0.15789 0.984742 + outer loop + vertex 1.56576 1.75632 2.54661 + vertex 1.5645 1.76059 2.54601 + vertex 1.56027 1.75709 2.54689 + endloop + endfacet + facet normal 0.0703338 0.136364 0.988159 + outer loop + vertex 1.56174 1.75194 2.5475 + vertex 1.56576 1.75632 2.54661 + vertex 1.56027 1.75709 2.54689 + endloop + endfacet + facet normal 0.0335917 0.153292 0.98761 + outer loop + vertex 1.5645 1.76059 2.54601 + vertex 1.56949 1.75995 2.54594 + vertex 1.56819 1.76388 2.54538 + endloop + endfacet + facet normal 0.044596 0.141192 0.988977 + outer loop + vertex 1.56293 1.76502 2.54545 + vertex 1.5645 1.76059 2.54601 + vertex 1.56819 1.76388 2.54538 + endloop + endfacet + facet normal 0.0266486 0.147464 0.988708 + outer loop + vertex 1.56759 1.76796 2.54477 + vertex 1.57235 1.77211 2.54402 + vertex 1.56753 1.77226 2.54413 + endloop + endfacet + facet normal 0.0265386 0.143624 0.989276 + outer loop + vertex 1.57235 1.77211 2.54402 + vertex 1.57244 1.77695 2.54332 + vertex 1.56753 1.77226 2.54413 + endloop + endfacet + facet normal 0.0303474 0.139713 0.989727 + outer loop + vertex 1.56753 1.77226 2.54413 + vertex 1.57244 1.77695 2.54332 + vertex 1.56744 1.77694 2.54347 + endloop + endfacet + facet normal 0.0303436 0.140284 0.989646 + outer loop + vertex 1.57244 1.77695 2.54332 + vertex 1.57235 1.7821 2.54259 + vertex 1.56744 1.77694 2.54347 + endloop + endfacet + facet normal 0.0372928 0.133781 0.990309 + outer loop + vertex 1.56744 1.77694 2.54347 + vertex 1.57235 1.7821 2.54259 + vertex 1.56709 1.78185 2.54282 + endloop + endfacet + facet normal 0.138315 0.108716 0.984403 + outer loop + vertex 1.55794 1.77784 2.54431 + vertex 1.56217 1.78181 2.54328 + vertex 1.55759 1.78264 2.54383 + endloop + endfacet + facet normal 0.0737569 0.136129 0.987942 + outer loop + vertex 1.56744 1.77694 2.54347 + vertex 1.56709 1.78185 2.54282 + vertex 1.56262 1.77721 2.54379 + endloop + endfacet + facet normal 0.114095 0.116345 0.986634 + outer loop + vertex 1.56217 1.78181 2.54328 + vertex 1.56588 1.78579 2.54238 + vertex 1.56177 1.78646 2.54278 + endloop + endfacet + facet normal 0.0368472 0.142177 0.989155 + outer loop + vertex 1.57235 1.7821 2.54259 + vertex 1.57141 1.7879 2.54179 + vertex 1.56709 1.78185 2.54282 + endloop + endfacet + facet normal 0.116157 0.130077 0.984676 + outer loop + vertex 1.56588 1.78579 2.54238 + vertex 1.56589 1.79108 2.54168 + vertex 1.56177 1.78646 2.54278 + endloop + endfacet + facet normal 0.151289 0.145683 0.977695 + outer loop + vertex 1.56561 1.7958 2.54102 + vertex 1.56079 1.7958 2.54177 + vertex 1.56589 1.79108 2.54168 + endloop + endfacet + facet normal 0.0347311 0.129836 0.990927 + outer loop + vertex 1.56868 1.79437 2.54088 + vertex 1.57055 1.79192 2.54114 + vertex 1.57254 1.79503 2.54066 + endloop + endfacet + facet normal 0.110188 0.120213 0.986614 + outer loop + vertex 1.56382 1.79903 2.54083 + vertex 1.56561 1.7958 2.54102 + vertex 1.5686 1.79892 2.54031 + endloop + endfacet + facet normal 0.15136 0.142383 0.97817 + outer loop + vertex 1.56561 1.7958 2.54102 + vertex 1.56382 1.79903 2.54083 + vertex 1.56079 1.7958 2.54177 + endloop + endfacet + facet normal 0.164199 0.136252 0.976972 + outer loop + vertex 1.55577 1.80091 2.5419 + vertex 1.55574 1.79559 2.54264 + vertex 1.56079 1.7958 2.54177 + endloop + endfacet + facet normal 0.157696 0.146371 0.976579 + outer loop + vertex 1.55566 1.806 2.54115 + vertex 1.55085 1.80596 2.54194 + vertex 1.55577 1.80091 2.5419 + endloop + endfacet + facet normal 0.167438 0.162128 0.97246 + outer loop + vertex 1.55398 1.80927 2.5409 + vertex 1.55566 1.806 2.54115 + vertex 1.55885 1.80905 2.54009 + endloop + endfacet + facet normal 0.160407 0.141157 0.976906 + outer loop + vertex 1.55886 1.80422 2.54089 + vertex 1.5606 1.80087 2.54108 + vertex 1.56375 1.80391 2.54013 + endloop + endfacet + facet normal 0.165784 0.162126 0.972744 + outer loop + vertex 1.55885 1.80905 2.54009 + vertex 1.56285 1.81271 2.5388 + vertex 1.55899 1.81398 2.53925 + endloop + endfacet + facet normal 0.124603 0.173468 0.976925 + outer loop + vertex 1.56791 1.8077 2.53897 + vertex 1.56726 1.81197 2.5383 + vertex 1.56395 1.80886 2.53927 + endloop + endfacet + facet normal 0.122052 0.164318 0.978827 + outer loop + vertex 1.56375 1.80391 2.54013 + vertex 1.56791 1.8077 2.53897 + vertex 1.56395 1.80886 2.53927 + endloop + endfacet + facet normal 0.117992 0.160053 0.980031 + outer loop + vertex 1.56654 1.81633 2.53764 + vertex 1.57096 1.81988 2.53653 + vertex 1.56518 1.82147 2.53696 + endloop + endfacet + facet normal 0.12486 0.186594 0.97447 + outer loop + vertex 1.57096 1.81988 2.53653 + vertex 1.56949 1.82455 2.53582 + vertex 1.56518 1.82147 2.53696 + endloop + endfacet + facet normal 0.0561021 0.200465 0.978093 + outer loop + vertex 1.57515 1.82116 2.53602 + vertex 1.57334 1.82337 2.53568 + vertex 1.57096 1.81988 2.53653 + endloop + endfacet + facet normal 0.0914461 0.176884 0.979974 + outer loop + vertex 1.57334 1.82337 2.53568 + vertex 1.56949 1.82455 2.53582 + vertex 1.57096 1.81988 2.53653 + endloop + endfacet + facet normal 0.133196 0.169965 0.976407 + outer loop + vertex 1.56949 1.82455 2.53582 + vertex 1.56823 1.82956 2.53512 + vertex 1.56547 1.8261 2.5361 + endloop + endfacet + facet normal 0.0408271 0.176335 0.983483 + outer loop + vertex 1.57389 1.82766 2.53493 + vertex 1.57783 1.83228 2.53394 + vertex 1.57291 1.83265 2.53407 + endloop + endfacet + facet normal 0.0420288 0.193282 0.980243 + outer loop + vertex 1.57783 1.83228 2.53394 + vertex 1.57694 1.83697 2.53305 + vertex 1.57291 1.83265 2.53407 + endloop + endfacet + facet normal 0.0528531 0.183497 0.981598 + outer loop + vertex 1.57291 1.83265 2.53407 + vertex 1.57694 1.83697 2.53305 + vertex 1.57204 1.83706 2.5333 + endloop + endfacet + facet normal 0.145329 0.17007 0.974657 + outer loop + vertex 1.56373 1.82924 2.53585 + vertex 1.56823 1.82956 2.53512 + vertex 1.5638 1.83401 2.53501 + endloop + endfacet + facet normal 0.158193 0.175073 0.971764 + outer loop + vertex 1.5638 1.83401 2.53501 + vertex 1.56766 1.8375 2.53375 + vertex 1.56393 1.83881 2.53412 + endloop + endfacet + facet normal 0.100029 0.191904 0.976303 + outer loop + vertex 1.57291 1.83265 2.53407 + vertex 1.57204 1.83706 2.5333 + vertex 1.56887 1.83392 2.53424 + endloop + endfacet + facet normal 0.139337 0.177902 0.974133 + outer loop + vertex 1.56766 1.8375 2.53375 + vertex 1.57048 1.84061 2.53278 + vertex 1.5668 1.84163 2.53312 + endloop + endfacet + facet normal 0.0530145 0.199771 0.978407 + outer loop + vertex 1.57694 1.83697 2.53305 + vertex 1.57515 1.84193 2.53214 + vertex 1.57204 1.83706 2.5333 + endloop + endfacet + facet normal 0.141718 0.187236 0.972038 + outer loop + vertex 1.57048 1.84061 2.53278 + vertex 1.57034 1.84554 2.53185 + vertex 1.5668 1.84163 2.53312 + endloop + endfacet + facet normal 0.15311 0.177012 0.972226 + outer loop + vertex 1.5668 1.84163 2.53312 + vertex 1.57034 1.84554 2.53185 + vertex 1.56551 1.84525 2.53266 + endloop + endfacet + facet normal 0.152153 0.187816 0.970348 + outer loop + vertex 1.56588 1.8497 2.53174 + vertex 1.56551 1.84525 2.53266 + vertex 1.57034 1.84554 2.53185 + endloop + endfacet + facet normal 0.161537 0.197774 0.966846 + outer loop + vertex 1.57021 1.85017 2.53092 + vertex 1.56588 1.8497 2.53174 + vertex 1.57034 1.84554 2.53185 + endloop + endfacet + facet normal 0.163123 0.186597 0.9688 + outer loop + vertex 1.57021 1.85017 2.53092 + vertex 1.56853 1.85318 2.53063 + vertex 1.56588 1.8497 2.53174 + endloop + endfacet + facet normal 0.170203 0.181151 0.968615 + outer loop + vertex 1.56853 1.85318 2.53063 + vertex 1.56473 1.85473 2.531 + vertex 1.56588 1.8497 2.53174 + endloop + endfacet + facet normal 0.168325 0.176255 0.969846 + outer loop + vertex 1.56473 1.85473 2.531 + vertex 1.56853 1.85318 2.53063 + vertex 1.56906 1.85764 2.52972 + endloop + endfacet + facet normal 0.125725 0.16662 0.977973 + outer loop + vertex 1.56853 1.85318 2.53063 + vertex 1.57021 1.85017 2.53092 + vertex 1.57347 1.85355 2.52993 + endloop + endfacet + facet normal 0.0498007 0.185075 0.981462 + outer loop + vertex 1.57329 1.84898 2.53079 + vertex 1.57513 1.8463 2.5312 + vertex 1.57776 1.84988 2.53039 + endloop + endfacet + facet normal 0.124125 0.182626 0.975316 + outer loop + vertex 1.56853 1.85318 2.53063 + vertex 1.57347 1.85355 2.52993 + vertex 1.56906 1.85764 2.52972 + endloop + endfacet + facet normal 0.152746 0.18067 0.97161 + outer loop + vertex 1.56906 1.85764 2.52972 + vertex 1.57216 1.86206 2.52841 + vertex 1.56757 1.86264 2.52903 + endloop + endfacet + facet normal 0.0674863 0.202156 0.977025 + outer loop + vertex 1.57776 1.85757 2.52882 + vertex 1.57691 1.8619 2.52799 + vertex 1.57377 1.85836 2.52893 + endloop + endfacet + facet normal 0.125633 0.182219 0.975199 + outer loop + vertex 1.57216 1.86206 2.52841 + vertex 1.57515 1.8667 2.52716 + vertex 1.57052 1.86579 2.52793 + endloop + endfacet + facet normal 0.0267848 0.209782 0.977381 + outer loop + vertex 1.58186 1.86171 2.52789 + vertex 1.58073 1.86607 2.52699 + vertex 1.57691 1.8619 2.52799 + endloop + endfacet + facet normal 0.0262506 0.194719 0.980508 + outer loop + vertex 1.57776 1.85757 2.52882 + vertex 1.58186 1.86171 2.52789 + vertex 1.57691 1.8619 2.52799 + endloop + endfacet + facet normal 0.0164954 0.203982 0.978836 + outer loop + vertex 1.58244 1.85727 2.52881 + vertex 1.58186 1.86171 2.52789 + vertex 1.57776 1.85757 2.52882 + endloop + endfacet + facet normal 0.0160377 0.196688 0.980335 + outer loop + vertex 1.57867 1.85398 2.52953 + vertex 1.58244 1.85727 2.52881 + vertex 1.57776 1.85757 2.52882 + endloop + endfacet + facet normal 0.0108689 0.202371 0.979249 + outer loop + vertex 1.58272 1.85294 2.5297 + vertex 1.58244 1.85727 2.52881 + vertex 1.57867 1.85398 2.52953 + endloop + endfacet + facet normal 0.0650823 0.211714 0.975162 + outer loop + vertex 1.5795 1.87018 2.52611 + vertex 1.57809 1.87464 2.52524 + vertex 1.57537 1.87106 2.5262 + endloop + endfacet + facet normal 0.0968012 0.190658 0.976872 + outer loop + vertex 1.57353 1.87395 2.52582 + vertex 1.57809 1.87464 2.52524 + vertex 1.57356 1.87867 2.5249 + endloop + endfacet + facet normal 0.0646071 0.2021 0.977231 + outer loop + vertex 1.57881 1.87882 2.52428 + vertex 1.58216 1.88205 2.52339 + vertex 1.5776 1.88226 2.52364 + endloop + endfacet + facet normal 0.0652984 0.222167 0.97282 + outer loop + vertex 1.58216 1.88205 2.52339 + vertex 1.5807 1.88542 2.52271 + vertex 1.5776 1.88226 2.52364 + endloop + endfacet + facet normal 0.0908049 0.198058 0.975975 + outer loop + vertex 1.5776 1.88226 2.52364 + vertex 1.5807 1.88542 2.52271 + vertex 1.57673 1.88648 2.52287 + endloop + endfacet + facet normal 0.151957 0.190587 0.969838 + outer loop + vertex 1.56854 1.87872 2.52568 + vertex 1.57356 1.87867 2.5249 + vertex 1.5685 1.88359 2.52473 + endloop + endfacet + facet normal 0.165118 0.189326 0.967932 + outer loop + vertex 1.5685 1.88359 2.52473 + vertex 1.57219 1.8873 2.52337 + vertex 1.5684 1.88843 2.52379 + endloop + endfacet + facet normal 0.12565 0.204323 0.970806 + outer loop + vertex 1.5776 1.88226 2.52364 + vertex 1.57673 1.88648 2.52287 + vertex 1.57368 1.88349 2.52389 + endloop + endfacet + facet normal 0.157407 0.189164 0.969247 + outer loop + vertex 1.57219 1.8873 2.52337 + vertex 1.57512 1.89144 2.52209 + vertex 1.5707 1.89096 2.5229 + endloop + endfacet + facet normal 0.0925067 0.20462 0.974461 + outer loop + vertex 1.5807 1.88542 2.52271 + vertex 1.58086 1.88985 2.52177 + vertex 1.57673 1.88648 2.52287 + endloop + endfacet + facet normal 0.123605 0.202669 0.971415 + outer loop + vertex 1.57528 1.89589 2.52114 + vertex 1.57512 1.89144 2.52209 + vertex 1.57932 1.89447 2.52092 + endloop + endfacet + facet normal 0.120914 0.19474 0.973373 + outer loop + vertex 1.57932 1.89447 2.52092 + vertex 1.57804 1.89938 2.5201 + vertex 1.57528 1.89589 2.52114 + endloop + endfacet + facet normal 0.0328599 0.199309 0.979386 + outer loop + vertex 1.58374 1.89771 2.51997 + vertex 1.58765 1.90223 2.51892 + vertex 1.58274 1.90255 2.51902 + endloop + endfacet + facet normal 0.0336085 0.211494 0.976801 + outer loop + vertex 1.58765 1.90223 2.51892 + vertex 1.58681 1.90676 2.51797 + vertex 1.58274 1.90255 2.51902 + endloop + endfacet + facet normal 0.043777 0.202026 0.978401 + outer loop + vertex 1.58274 1.90255 2.51902 + vertex 1.58681 1.90676 2.51797 + vertex 1.58192 1.90679 2.51818 + endloop + endfacet + facet normal 0.0437389 0.217944 0.974981 + outer loop + vertex 1.58681 1.90676 2.51797 + vertex 1.58521 1.91143 2.517 + vertex 1.58192 1.90679 2.51818 + endloop + endfacet + facet normal 0.135702 0.188904 0.972574 + outer loop + vertex 1.57351 1.89896 2.52081 + vertex 1.57804 1.89938 2.5201 + vertex 1.57356 1.90372 2.51988 + endloop + endfacet + facet normal 0.148225 0.192536 0.970031 + outer loop + vertex 1.57356 1.90372 2.51988 + vertex 1.5775 1.90722 2.51858 + vertex 1.57368 1.90856 2.5189 + endloop + endfacet + facet normal 0.087595 0.209611 0.973853 + outer loop + vertex 1.58274 1.90255 2.51902 + vertex 1.58192 1.90679 2.51818 + vertex 1.5787 1.90371 2.51913 + endloop + endfacet + facet normal 0.126968 0.193579 0.972834 + outer loop + vertex 1.5775 1.90722 2.51858 + vertex 1.58048 1.91014 2.51761 + vertex 1.57666 1.91142 2.51785 + endloop + endfacet + facet normal 0.129382 0.201105 0.970988 + outer loop + vertex 1.58048 1.91014 2.51761 + vertex 1.58083 1.91454 2.51665 + vertex 1.57666 1.91142 2.51785 + endloop + endfacet + facet normal 0.0836266 0.232988 0.968877 + outer loop + vertex 1.58536 1.9156 2.51601 + vertex 1.58343 1.91812 2.51557 + vertex 1.58083 1.91454 2.51665 + endloop + endfacet + facet normal 0.114788 0.210917 0.970741 + outer loop + vertex 1.58343 1.91812 2.51557 + vertex 1.57936 1.91938 2.51578 + vertex 1.58083 1.91454 2.51665 + endloop + endfacet + facet normal 0.148365 0.213787 0.965548 + outer loop + vertex 1.57936 1.91938 2.51578 + vertex 1.57793 1.92434 2.5149 + vertex 1.57526 1.92091 2.51607 + endloop + endfacet + facet normal 0.133289 0.223692 0.965503 + outer loop + vertex 1.57793 1.92434 2.5149 + vertex 1.58212 1.9273 2.51363 + vertex 1.57826 1.92848 2.51389 + endloop + endfacet + facet normal 0.0630323 0.236591 0.969563 + outer loop + vertex 1.58863 1.92347 2.51402 + vertex 1.58699 1.92696 2.51328 + vertex 1.58374 1.92253 2.51457 + endloop + endfacet + facet normal 0.108125 0.221331 0.969186 + outer loop + vertex 1.58212 1.9273 2.51363 + vertex 1.58516 1.93156 2.51232 + vertex 1.58073 1.93074 2.513 + endloop + endfacet + facet normal 0.0339855 0.237644 0.970758 + outer loop + vertex 1.59188 1.92677 2.51315 + vertex 1.59056 1.93092 2.51218 + vertex 1.58699 1.92696 2.51328 + endloop + endfacet + facet normal 0.0230507 0.237961 0.971001 + outer loop + vertex 1.59439 1.93473 2.51116 + vertex 1.5894 1.93511 2.51119 + vertex 1.59056 1.93092 2.51218 + endloop + endfacet + facet normal 0.0236787 0.246506 0.968852 + outer loop + vertex 1.5894 1.93511 2.51119 + vertex 1.59439 1.93473 2.51116 + vertex 1.59327 1.93878 2.51016 + endloop + endfacet + facet normal 0.116294 0.238631 0.964122 + outer loop + vertex 1.58539 1.93573 2.51126 + vertex 1.58101 1.93487 2.512 + vertex 1.58516 1.93156 2.51232 + endloop + endfacet + facet normal 0.031937 0.238313 0.970663 + outer loop + vertex 1.58804 1.9394 2.51018 + vertex 1.5894 1.93511 2.51119 + vertex 1.59327 1.93878 2.51016 + endloop + endfacet + facet normal 0.033988 0.255809 0.96613 + outer loop + vertex 1.59327 1.93878 2.51016 + vertex 1.59257 1.94278 2.50912 + vertex 1.58804 1.9394 2.51018 + endloop + endfacet + facet normal 0.0367166 0.252406 0.966924 + outer loop + vertex 1.58804 1.9394 2.51018 + vertex 1.59257 1.94278 2.50912 + vertex 1.58866 1.94349 2.50909 + endloop + endfacet + facet normal 0.0370455 0.254211 0.966439 + outer loop + vertex 1.59257 1.94278 2.50912 + vertex 1.59187 1.94668 2.50812 + vertex 1.58866 1.94349 2.50909 + endloop + endfacet + facet normal 0.0613532 0.231187 0.970973 + outer loop + vertex 1.58866 1.94349 2.50909 + vertex 1.59187 1.94668 2.50812 + vertex 1.58711 1.94691 2.50837 + endloop + endfacet + facet normal 0.115213 0.243266 0.963093 + outer loop + vertex 1.58539 1.93573 2.51126 + vertex 1.58356 1.93831 2.51083 + vertex 1.58101 1.93487 2.512 + endloop + endfacet + facet normal 0.137735 0.226955 0.964116 + outer loop + vertex 1.58356 1.93831 2.51083 + vertex 1.57963 1.93961 2.51109 + vertex 1.58101 1.93487 2.512 + endloop + endfacet + facet normal 0.0947708 0.245023 0.964874 + outer loop + vertex 1.58866 1.94349 2.50909 + vertex 1.58711 1.94691 2.50837 + vertex 1.5839 1.94263 2.50977 + endloop + endfacet + facet normal 0.134059 0.225694 0.96493 + outer loop + vertex 1.58229 1.94738 2.50884 + vertex 1.58524 1.95164 2.50743 + vertex 1.58078 1.95093 2.50822 + endloop + endfacet + facet normal 0.0619141 0.247908 0.966803 + outer loop + vertex 1.59187 1.94668 2.50812 + vertex 1.59069 1.95073 2.50716 + vertex 1.58711 1.94691 2.50837 + endloop + endfacet + facet normal 0.133345 0.229324 0.964173 + outer loop + vertex 1.5806 1.95553 2.50715 + vertex 1.58078 1.95093 2.50822 + vertex 1.58524 1.95164 2.50743 + endloop + endfacet + facet normal 0.124048 0.232451 0.964665 + outer loop + vertex 1.5836 1.95883 2.50588 + vertex 1.58542 1.956 2.50633 + vertex 1.58801 1.95953 2.50514 + endloop + endfacet + facet normal 0.156141 0.237054 0.958867 + outer loop + vertex 1.5761 1.95965 2.50686 + vertex 1.57591 1.95549 2.50792 + vertex 1.5806 1.95553 2.50715 + endloop + endfacet + facet normal 0.152138 0.237475 0.959406 + outer loop + vertex 1.57864 1.96299 2.50562 + vertex 1.58048 1.96006 2.50606 + vertex 1.58349 1.96331 2.50477 + endloop + endfacet + facet normal 0.158941 0.241636 0.957261 + outer loop + vertex 1.5761 1.95965 2.50686 + vertex 1.57455 1.96458 2.50588 + vertex 1.57045 1.96183 2.50725 + endloop + endfacet + facet normal 0.159441 0.242173 0.957043 + outer loop + vertex 1.57455 1.96458 2.50588 + vertex 1.57301 1.96947 2.5049 + vertex 1.57045 1.96618 2.50615 + endloop + endfacet + facet normal 0.157628 0.243656 0.956967 + outer loop + vertex 1.57301 1.96947 2.5049 + vertex 1.57706 1.97206 2.50357 + vertex 1.57327 1.97354 2.50382 + endloop + endfacet + facet normal 0.157087 0.245457 0.956595 + outer loop + vertex 1.58098 1.97088 2.50323 + vertex 1.58056 1.97558 2.50209 + vertex 1.57706 1.97206 2.50357 + endloop + endfacet + facet normal 0.154583 0.243953 0.957388 + outer loop + vertex 1.58313 1.96794 2.50363 + vertex 1.58539 1.97155 2.50235 + vertex 1.58098 1.97088 2.50323 + endloop + endfacet + facet normal 0.151512 0.243343 0.958034 + outer loop + vertex 1.57864 1.96299 2.50562 + vertex 1.58349 1.96331 2.50477 + vertex 1.57868 1.96731 2.50452 + endloop + endfacet + facet normal 0.145611 0.249552 0.957351 + outer loop + vertex 1.58706 1.96683 2.50332 + vertex 1.58539 1.97155 2.50235 + vertex 1.58313 1.96794 2.50363 + endloop + endfacet + facet normal 0.122453 0.240629 0.962862 + outer loop + vertex 1.5836 1.95883 2.50588 + vertex 1.58801 1.95953 2.50514 + vertex 1.58349 1.96331 2.50477 + endloop + endfacet + facet normal 0.0767359 0.271626 0.959339 + outer loop + vertex 1.59332 1.95856 2.50499 + vertex 1.59218 1.96255 2.50395 + vertex 1.58801 1.95953 2.50514 + endloop + endfacet + facet normal 0.0371008 0.261668 0.964445 + outer loop + vertex 1.59332 1.95856 2.50499 + vertex 1.5971 1.96241 2.5038 + vertex 1.59218 1.96255 2.50395 + endloop + endfacet + facet normal 0.0297674 0.268387 0.962851 + outer loop + vertex 1.59832 1.95832 2.5049 + vertex 1.5971 1.96241 2.5038 + vertex 1.59332 1.95856 2.50499 + endloop + endfacet + facet normal 0.0291514 0.254281 0.966691 + outer loop + vertex 1.59332 1.95856 2.50499 + vertex 1.59453 1.95449 2.50603 + vertex 1.59832 1.95832 2.5049 + endloop + endfacet + facet normal 0.0211145 0.261721 0.964913 + outer loop + vertex 1.59453 1.95449 2.50603 + vertex 1.59942 1.9544 2.50594 + vertex 1.59832 1.95832 2.5049 + endloop + endfacet + facet normal 0.0210115 0.253737 0.967045 + outer loop + vertex 1.59942 1.9544 2.50594 + vertex 1.59453 1.95449 2.50603 + vertex 1.59562 1.95051 2.50705 + endloop + endfacet + facet normal 0.0335754 0.256877 0.965861 + outer loop + vertex 1.59562 1.95051 2.50705 + vertex 1.59453 1.95449 2.50603 + vertex 1.59069 1.95073 2.50716 + endloop + endfacet + facet normal 0.0329527 0.240244 0.970153 + outer loop + vertex 1.59187 1.94668 2.50812 + vertex 1.59562 1.95051 2.50705 + vertex 1.59069 1.95073 2.50716 + endloop + endfacet + facet normal 0.112488 0.25014 0.961653 + outer loop + vertex 1.58834 1.96343 2.50406 + vertex 1.59082 1.96569 2.50318 + vertex 1.58706 1.96683 2.50332 + endloop + endfacet + facet normal 0.037376 0.27594 0.960448 + outer loop + vertex 1.5971 1.96241 2.5038 + vertex 1.59529 1.96678 2.50262 + vertex 1.59218 1.96255 2.50395 + endloop + endfacet + facet normal 0.114122 0.255728 0.959989 + outer loop + vertex 1.59082 1.96569 2.50318 + vertex 1.59101 1.96975 2.50208 + vertex 1.58706 1.96683 2.50332 + endloop + endfacet + facet normal 0.124207 0.242958 0.962052 + outer loop + vertex 1.58706 1.96683 2.50332 + vertex 1.59101 1.96975 2.50208 + vertex 1.58539 1.97155 2.50235 + endloop + endfacet + facet normal 0.130465 0.263407 0.955822 + outer loop + vertex 1.59101 1.96975 2.50208 + vertex 1.58949 1.97441 2.501 + vertex 1.58539 1.97155 2.50235 + endloop + endfacet + facet normal 0.073013 0.278752 0.957584 + outer loop + vertex 1.59537 1.97078 2.50144 + vertex 1.59349 1.97322 2.50088 + vertex 1.59101 1.96975 2.50208 + endloop + endfacet + facet normal 0.10575 0.256476 0.960748 + outer loop + vertex 1.59349 1.97322 2.50088 + vertex 1.58949 1.97441 2.501 + vertex 1.59101 1.96975 2.50208 + endloop + endfacet + facet normal 0.139489 0.25022 0.958088 + outer loop + vertex 1.58949 1.97441 2.501 + vertex 1.5879 1.97928 2.49996 + vertex 1.58537 1.97588 2.50121 + endloop + endfacet + facet normal 0.122806 0.256141 0.958807 + outer loop + vertex 1.5879 1.97928 2.49996 + vertex 1.59212 1.9823 2.49861 + vertex 1.58793 1.9835 2.49882 + endloop + endfacet + facet normal 0.124679 0.263046 0.956693 + outer loop + vertex 1.59212 1.9823 2.49861 + vertex 1.59038 1.98696 2.49756 + vertex 1.58793 1.9835 2.49882 + endloop + endfacet + facet normal 0.0528671 0.270644 0.961227 + outer loop + vertex 1.59856 1.97849 2.4992 + vertex 1.59707 1.98174 2.49837 + vertex 1.59376 1.97754 2.49974 + endloop + endfacet + facet normal 0.0958855 0.253636 0.962536 + outer loop + vertex 1.59212 1.9823 2.49861 + vertex 1.5957 1.98584 2.49732 + vertex 1.59038 1.98696 2.49756 + endloop + endfacet + facet normal 0.0588269 0.268504 0.961481 + outer loop + vertex 1.59943 1.98945 2.49608 + vertex 1.59454 1.99004 2.49622 + vertex 1.5957 1.98584 2.49732 + endloop + endfacet + facet normal 0.100811 0.278436 0.95515 + outer loop + vertex 1.5957 1.98584 2.49732 + vertex 1.59454 1.99004 2.49622 + vertex 1.59038 1.98696 2.49756 + endloop + endfacet + facet normal 0.142373 0.256479 0.956006 + outer loop + vertex 1.58577 1.9907 2.49724 + vertex 1.58605 1.98633 2.49837 + vertex 1.59038 1.98696 2.49756 + endloop + endfacet + facet normal 0.133803 0.257986 0.956839 + outer loop + vertex 1.58864 1.99383 2.49591 + vertex 1.59048 1.99107 2.49639 + vertex 1.59297 1.99448 2.49512 + endloop + endfacet + facet normal 0.161765 0.259319 0.952148 + outer loop + vertex 1.58108 1.99465 2.49696 + vertex 1.58106 1.99045 2.49811 + vertex 1.58577 1.9907 2.49724 + endloop + endfacet + facet normal 0.160638 0.255598 0.953344 + outer loop + vertex 1.58359 1.99794 2.49564 + vertex 1.58549 1.99506 2.49609 + vertex 1.58846 1.99825 2.49474 + endloop + endfacet + facet normal 0.157781 0.256923 0.953465 + outer loop + vertex 1.58108 1.99465 2.49696 + vertex 1.57943 1.99949 2.49593 + vertex 1.57535 1.99674 2.49735 + endloop + endfacet + facet normal 0.15852 0.257478 0.953193 + outer loop + vertex 1.57943 1.99949 2.49593 + vertex 1.5778 2.00429 2.4949 + vertex 1.57531 2.00098 2.49621 + endloop + endfacet + facet normal 0.159822 0.259944 0.952306 + outer loop + vertex 1.5778 2.00429 2.4949 + vertex 1.58194 2.00701 2.49347 + vertex 1.57788 2.00843 2.49376 + endloop + endfacet + facet normal 0.162283 0.260979 0.951606 + outer loop + vertex 1.58599 2.00565 2.49315 + vertex 1.58598 2.00984 2.492 + vertex 1.58194 2.00701 2.49347 + endloop + endfacet + facet normal 0.159612 0.255332 0.953588 + outer loop + vertex 1.58809 2.00282 2.49355 + vertex 1.59039 2.00632 2.49223 + vertex 1.58599 2.00565 2.49315 + endloop + endfacet + facet normal 0.160427 0.257512 0.952865 + outer loop + vertex 1.58359 1.99794 2.49564 + vertex 1.58846 1.99825 2.49474 + vertex 1.5836 2.00221 2.49449 + endloop + endfacet + facet normal 0.153087 0.259582 0.95351 + outer loop + vertex 1.592 2.00175 2.49322 + vertex 1.59039 2.00632 2.49223 + vertex 1.58809 2.00282 2.49355 + endloop + endfacet + facet normal 0.133696 0.258538 0.956704 + outer loop + vertex 1.58864 1.99383 2.49591 + vertex 1.59297 1.99448 2.49512 + vertex 1.58846 1.99825 2.49474 + endloop + endfacet + facet normal 0.0869756 0.29072 0.952847 + outer loop + vertex 1.59817 1.99348 2.49496 + vertex 1.59704 1.99743 2.49385 + vertex 1.59297 1.99448 2.49512 + endloop + endfacet + facet normal 0.122838 0.258589 0.958145 + outer loop + vertex 1.59328 1.99837 2.49397 + vertex 1.59571 2.0006 2.49305 + vertex 1.592 2.00175 2.49322 + endloop + endfacet + facet normal 0.045708 0.287043 0.956827 + outer loop + vertex 1.60181 1.99717 2.49371 + vertex 1.60011 2.0015 2.49249 + vertex 1.59704 1.99743 2.49385 + endloop + endfacet + facet normal 0.123747 0.26164 0.9572 + outer loop + vertex 1.59571 2.0006 2.49305 + vertex 1.5959 2.00461 2.49193 + vertex 1.592 2.00175 2.49322 + endloop + endfacet + facet normal 0.130707 0.252784 0.958653 + outer loop + vertex 1.592 2.00175 2.49322 + vertex 1.5959 2.00461 2.49193 + vertex 1.59039 2.00632 2.49223 + endloop + endfacet + facet normal 0.136828 0.273709 0.95203 + outer loop + vertex 1.5959 2.00461 2.49193 + vertex 1.59437 2.0092 2.49083 + vertex 1.59039 2.00632 2.49223 + endloop + endfacet + facet normal 0.0816286 0.286662 0.954548 + outer loop + vertex 1.60031 2.00555 2.49127 + vertex 1.59836 2.00804 2.49069 + vertex 1.5959 2.00461 2.49193 + endloop + endfacet + facet normal 0.111268 0.266426 0.957411 + outer loop + vertex 1.59836 2.00804 2.49069 + vertex 1.59437 2.0092 2.49083 + vertex 1.5959 2.00461 2.49193 + endloop + endfacet + facet normal 0.158437 0.261132 0.952212 + outer loop + vertex 1.58598 2.00984 2.492 + vertex 1.58599 2.00565 2.49315 + vertex 1.59039 2.00632 2.49223 + endloop + endfacet + facet normal 0.155905 0.263173 0.952068 + outer loop + vertex 1.58835 2.01324 2.49065 + vertex 1.59036 2.01049 2.49108 + vertex 1.5928 2.01387 2.48975 + endloop + endfacet + facet normal 0.161282 0.266006 0.950384 + outer loop + vertex 1.58598 2.00984 2.492 + vertex 1.5844 2.01448 2.49097 + vertex 1.58045 2.01166 2.49243 + endloop + endfacet + facet normal 0.160967 0.271687 0.948829 + outer loop + vertex 1.5844 2.01448 2.49097 + vertex 1.5828 2.01899 2.48995 + vertex 1.58051 2.01572 2.49128 + endloop + endfacet + facet normal 0.161096 0.274938 0.94787 + outer loop + vertex 1.5828 2.01899 2.48995 + vertex 1.58611 2.02149 2.48866 + vertex 1.58293 2.02291 2.48879 + endloop + endfacet + facet normal 0.163008 0.277167 0.946893 + outer loop + vertex 1.58587 2.0259 2.48741 + vertex 1.58611 2.02149 2.48866 + vertex 1.5906 2.02215 2.4877 + endloop + endfacet + facet normal 0.162619 0.276691 0.947099 + outer loop + vertex 1.59053 2.02632 2.48649 + vertex 1.58587 2.0259 2.48741 + vertex 1.5906 2.02215 2.4877 + endloop + endfacet + facet normal 0.158451 0.276817 0.947769 + outer loop + vertex 1.59053 2.02632 2.48649 + vertex 1.5906 2.02215 2.4877 + vertex 1.59455 2.02505 2.48619 + endloop + endfacet + facet normal 0.162777 0.27559 0.947393 + outer loop + vertex 1.59053 2.02632 2.48649 + vertex 1.58867 2.02903 2.48602 + vertex 1.58587 2.0259 2.48741 + endloop + endfacet + facet normal 0.154277 0.271603 0.949964 + outer loop + vertex 1.58835 2.01324 2.49065 + vertex 1.5928 2.01387 2.48975 + vertex 1.58828 2.01747 2.48945 + endloop + endfacet + facet normal 0.126677 0.291593 0.948117 + outer loop + vertex 1.59849 2.01216 2.48951 + vertex 1.59703 2.01662 2.48834 + vertex 1.5928 2.01387 2.48975 + endloop + endfacet + facet normal 0.0943741 0.282686 0.954559 + outer loop + vertex 1.59849 2.01216 2.48951 + vertex 1.60114 2.01563 2.48822 + vertex 1.59703 2.01662 2.48834 + endloop + endfacet + facet normal 0.150457 0.272436 0.950337 + outer loop + vertex 1.59291 2.01814 2.48848 + vertex 1.59591 2.02082 2.48724 + vertex 1.5906 2.02215 2.4877 + endloop + endfacet + facet normal 0.152948 0.283722 0.94663 + outer loop + vertex 1.59591 2.02082 2.48724 + vertex 1.59455 2.02505 2.48619 + vertex 1.5906 2.02215 2.4877 + endloop + endfacet + facet normal 0.096836 0.293324 0.951096 + outer loop + vertex 1.60114 2.01563 2.48822 + vertex 1.60112 2.0196 2.487 + vertex 1.59703 2.01662 2.48834 + endloop + endfacet + facet normal 0.134078 0.27874 0.950961 + outer loop + vertex 1.59933 2.02382 2.48588 + vertex 1.59455 2.02505 2.48619 + vertex 1.59591 2.02082 2.48724 + endloop + endfacet + facet normal 0.136109 0.287355 0.948104 + outer loop + vertex 1.59455 2.02505 2.48619 + vertex 1.59933 2.02382 2.48588 + vertex 1.59799 2.02797 2.48481 + endloop + endfacet + facet normal 0.128693 0.280128 0.951297 + outer loop + vertex 1.59799 2.02797 2.48481 + vertex 1.60095 2.0307 2.48361 + vertex 1.5969 2.03215 2.48373 + endloop + endfacet + facet normal 0.131108 0.287066 0.948896 + outer loop + vertex 1.60095 2.0307 2.48361 + vertex 1.60102 2.03491 2.48232 + vertex 1.5969 2.03215 2.48373 + endloop + endfacet + facet normal 0.097541 0.305857 0.947068 + outer loop + vertex 1.60539 2.03592 2.48154 + vertex 1.60345 2.03832 2.48097 + vertex 1.60102 2.03491 2.48232 + endloop + endfacet + facet normal 0.127298 0.285662 0.949838 + outer loop + vertex 1.60345 2.03832 2.48097 + vertex 1.59949 2.03941 2.48117 + vertex 1.60102 2.03491 2.48232 + endloop + endfacet + facet normal 0.102648 0.284081 0.95329 + outer loop + vertex 1.60373 2.04248 2.47971 + vertex 1.60707 2.04656 2.47814 + vertex 1.60205 2.04705 2.47853 + endloop + endfacet + facet normal 0.157837 0.281823 0.946395 + outer loop + vertex 1.59368 2.04336 2.48097 + vertex 1.59795 2.04398 2.48007 + vertex 1.59367 2.04744 2.47975 + endloop + endfacet + facet normal 0.161201 0.285338 0.944773 + outer loop + vertex 1.59367 2.04744 2.47975 + vertex 1.59593 2.05064 2.4784 + vertex 1.5921 2.05205 2.47863 + endloop + endfacet + facet normal 0.142864 0.29167 0.94579 + outer loop + vertex 1.60205 2.04705 2.47853 + vertex 1.60028 2.05145 2.47744 + vertex 1.59792 2.04802 2.47886 + endloop + endfacet + facet normal 0.151168 0.28932 0.945221 + outer loop + vertex 1.59829 2.05802 2.47572 + vertex 1.60031 2.05543 2.47619 + vertex 1.60269 2.05886 2.47476 + endloop + endfacet + facet normal 0.16265 0.292201 0.942424 + outer loop + vertex 1.59431 2.05925 2.47603 + vertex 1.59829 2.05802 2.47572 + vertex 1.59823 2.0622 2.47444 + endloop + endfacet + facet normal 0.161858 0.293165 0.942261 + outer loop + vertex 1.59262 2.06373 2.47492 + vertex 1.59431 2.05925 2.47603 + vertex 1.59823 2.0622 2.47444 + endloop + endfacet + facet normal 0.162083 0.294091 0.941934 + outer loop + vertex 1.59823 2.0622 2.47444 + vertex 1.59611 2.0661 2.47358 + vertex 1.59262 2.06373 2.47492 + endloop + endfacet + facet normal 0.162555 0.289265 0.943346 + outer loop + vertex 1.59593 2.05064 2.4784 + vertex 1.59594 2.0547 2.47715 + vertex 1.5921 2.05205 2.47863 + endloop + endfacet + facet normal 0.164023 0.286126 0.944049 + outer loop + vertex 1.59367 2.04744 2.47975 + vertex 1.5921 2.05205 2.47863 + vertex 1.58838 2.04961 2.48001 + endloop + endfacet + facet normal 0.192026 0.303504 0.93328 + outer loop + vertex 1.58426 2.04937 2.48094 + vertex 1.58838 2.04961 2.48001 + vertex 1.58373 2.05368 2.47965 + endloop + endfacet + facet normal 0.194613 0.282354 0.939363 + outer loop + vertex 1.58426 2.04937 2.48094 + vertex 1.58615 2.04638 2.48145 + vertex 1.58838 2.04961 2.48001 + endloop + endfacet + facet normal 0.185471 0.288658 0.939296 + outer loop + vertex 1.58997 2.04477 2.48119 + vertex 1.58838 2.04961 2.48001 + vertex 1.58615 2.04638 2.48145 + endloop + endfacet + facet normal 0.162665 0.282666 0.945325 + outer loop + vertex 1.58838 2.04961 2.48001 + vertex 1.58997 2.04477 2.48119 + vertex 1.59367 2.04744 2.47975 + endloop + endfacet + facet normal 0.159962 0.292687 0.942734 + outer loop + vertex 1.58826 2.05366 2.47879 + vertex 1.5905 2.05662 2.47749 + vertex 1.58641 2.0564 2.47825 + endloop + endfacet + facet normal 0.15968 0.295337 0.941954 + outer loop + vertex 1.58628 2.06011 2.47712 + vertex 1.58641 2.0564 2.47825 + vertex 1.5905 2.05662 2.47749 + endloop + endfacet + facet normal 0.306441 0.459891 0.833423 + outer loop + vertex 1.57931 2.05394 2.48113 + vertex 1.58373 2.05368 2.47965 + vertex 1.57872 2.05766 2.47929 + endloop + endfacet + facet normal 0.159454 0.322452 0.933059 + outer loop + vertex 1.57872 2.05766 2.47929 + vertex 1.58079 2.06183 2.4775 + vertex 1.57628 2.06158 2.47836 + endloop + endfacet + facet normal 0.160407 0.295326 0.941834 + outer loop + vertex 1.58641 2.0564 2.47825 + vertex 1.58628 2.06011 2.47712 + vertex 1.5832 2.05798 2.47831 + endloop + endfacet + facet normal 0.157086 0.297867 0.941594 + outer loop + vertex 1.58051 2.06568 2.47633 + vertex 1.58079 2.06183 2.4775 + vertex 1.58445 2.06443 2.47606 + endloop + endfacet + facet normal 0.156352 0.295339 0.942512 + outer loop + vertex 1.58445 2.06443 2.47606 + vertex 1.58271 2.06881 2.47498 + vertex 1.58051 2.06568 2.47633 + endloop + endfacet + facet normal 0.158891 0.298237 0.941174 + outer loop + vertex 1.58824 2.06723 2.47456 + vertex 1.5907 2.07168 2.47273 + vertex 1.58617 2.07114 2.47367 + endloop + endfacet + facet normal 0.157944 0.294413 0.942536 + outer loop + vertex 1.57846 2.06826 2.47586 + vertex 1.58271 2.06881 2.47498 + vertex 1.57833 2.07234 2.47461 + endloop + endfacet + facet normal 0.161145 0.29587 0.941538 + outer loop + vertex 1.57833 2.07234 2.47461 + vertex 1.58066 2.07691 2.47278 + vertex 1.57612 2.07636 2.47373 + endloop + endfacet + facet normal 0.159064 0.298999 0.940903 + outer loop + vertex 1.58617 2.07114 2.47367 + vertex 1.58632 2.07519 2.47235 + vertex 1.58285 2.07286 2.47368 + endloop + endfacet + facet normal 0.162601 0.298391 0.940491 + outer loop + vertex 1.58864 2.07839 2.47094 + vertex 1.58464 2.07972 2.47121 + vertex 1.58632 2.07519 2.47235 + endloop + endfacet + facet normal 0.160952 0.29694 0.941234 + outer loop + vertex 1.57578 2.08078 2.47239 + vertex 1.57612 2.07636 2.47373 + vertex 1.58066 2.07691 2.47278 + endloop + endfacet + facet normal 0.158088 0.296945 0.941718 + outer loop + vertex 1.57539 2.08502 2.47112 + vertex 1.57111 2.08443 2.47203 + vertex 1.57578 2.08078 2.47239 + endloop + endfacet + facet normal 0.157644 0.299169 0.941088 + outer loop + vertex 1.57539 2.08502 2.47112 + vertex 1.57346 2.0877 2.47059 + vertex 1.57111 2.08443 2.47203 + endloop + endfacet + facet normal 0.158846 0.294441 0.942376 + outer loop + vertex 1.57856 2.0839 2.47094 + vertex 1.58052 2.08113 2.47147 + vertex 1.58299 2.08437 2.47004 + endloop + endfacet + facet normal 0.159091 0.289463 0.943876 + outer loop + vertex 1.58869 2.08238 2.46969 + vertex 1.58714 2.08697 2.46855 + vertex 1.58299 2.08437 2.47004 + endloop + endfacet + facet normal 0.159616 0.307386 0.938103 + outer loop + vertex 1.58304 2.08841 2.46878 + vertex 1.58541 2.09148 2.46737 + vertex 1.58122 2.09103 2.46823 + endloop + endfacet + facet normal 0.146885 0.30993 0.939344 + outer loop + vertex 1.57826 2.0881 2.46966 + vertex 1.58122 2.09103 2.46823 + vertex 1.57803 2.09232 2.46831 + endloop + endfacet + facet normal 0.156936 0.298711 0.941351 + outer loop + vertex 1.57346 2.0877 2.47059 + vertex 1.57539 2.08502 2.47112 + vertex 1.57826 2.0881 2.46966 + endloop + endfacet + facet normal 0.155681 0.300532 0.94098 + outer loop + vertex 1.57346 2.0877 2.47059 + vertex 1.56936 2.08886 2.4709 + vertex 1.57111 2.08443 2.47203 + endloop + endfacet + facet normal 0.16203 0.33993 0.926387 + outer loop + vertex 1.57339 2.09184 2.46923 + vertex 1.57599 2.09573 2.46735 + vertex 1.57061 2.09678 2.46791 + endloop + endfacet + facet normal 0.147732 0.335588 0.930353 + outer loop + vertex 1.56287 2.09413 2.47022 + vertex 1.56625 2.09635 2.46889 + vertex 1.56315 2.09779 2.46886 + endloop + endfacet + facet normal 0.153052 0.310506 0.938169 + outer loop + vertex 1.56287 2.09413 2.47022 + vertex 1.56456 2.08999 2.47132 + vertex 1.56787 2.09302 2.46978 + endloop + endfacet + facet normal 0.140616 0.308522 0.940766 + outer loop + vertex 1.56067 2.09093 2.47163 + vertex 1.55869 2.09343 2.4711 + vertex 1.55644 2.09022 2.47249 + endloop + endfacet + facet normal 0.143653 0.305131 0.941413 + outer loop + vertex 1.55842 2.08251 2.47469 + vertex 1.56074 2.08702 2.47287 + vertex 1.55629 2.08628 2.47379 + endloop + endfacet + facet normal 0.138097 0.30836 0.941192 + outer loop + vertex 1.54858 2.0833 2.4759 + vertex 1.55063 2.08071 2.47645 + vertex 1.55286 2.08391 2.47508 + endloop + endfacet + facet normal 0.13426 0.307293 0.942096 + outer loop + vertex 1.54858 2.0833 2.4759 + vertex 1.54459 2.08446 2.47609 + vertex 1.54633 2.0801 2.47727 + endloop + endfacet + facet normal 0.134065 0.308336 0.941783 + outer loop + vertex 1.54459 2.08446 2.47609 + vertex 1.54283 2.08885 2.47491 + vertex 1.54055 2.08561 2.47629 + endloop + endfacet + facet normal 0.133847 0.306514 0.942409 + outer loop + vertex 1.54283 2.08885 2.47491 + vertex 1.54633 2.09116 2.47366 + vertex 1.54297 2.09281 2.4736 + endloop + endfacet + facet normal 0.133268 0.306557 0.942477 + outer loop + vertex 1.53837 2.09225 2.47443 + vertex 1.54283 2.08885 2.47491 + vertex 1.54297 2.09281 2.4736 + endloop + endfacet + facet normal 0.13223 0.312389 0.940706 + outer loop + vertex 1.54297 2.09281 2.4736 + vertex 1.54077 2.09659 2.47265 + vertex 1.53837 2.09225 2.47443 + endloop + endfacet + facet normal 0.132267 0.312408 0.940695 + outer loop + vertex 1.54297 2.09281 2.4736 + vertex 1.54643 2.09511 2.47235 + vertex 1.54077 2.09659 2.47265 + endloop + endfacet + facet normal 0.134969 0.308771 0.941512 + outer loop + vertex 1.54633 2.09116 2.47366 + vertex 1.54643 2.09511 2.47235 + vertex 1.54297 2.09281 2.4736 + endloop + endfacet + facet normal 0.141619 0.335314 0.931401 + outer loop + vertex 1.55278 2.09889 2.47005 + vertex 1.55473 2.09456 2.47132 + vertex 1.55856 2.09743 2.4697 + endloop + endfacet + facet normal 0.153662 0.388486 0.908552 + outer loop + vertex 1.55856 2.09743 2.4697 + vertex 1.55584 2.10215 2.46814 + vertex 1.55278 2.09889 2.47005 + endloop + endfacet + facet normal 0.163219 0.380521 0.910255 + outer loop + vertex 1.55278 2.09889 2.47005 + vertex 1.55584 2.10215 2.46814 + vertex 1.55214 2.10203 2.46886 + endloop + endfacet + facet normal 0.134794 0.377051 0.916331 + outer loop + vertex 1.54827 2.10195 2.46946 + vertex 1.55278 2.09889 2.47005 + vertex 1.55214 2.10203 2.46886 + endloop + endfacet + facet normal 0.132281 0.328905 0.935053 + outer loop + vertex 1.55074 2.09571 2.47153 + vertex 1.54859 2.09824 2.47094 + vertex 1.54643 2.09511 2.47235 + endloop + endfacet + facet normal 0.128392 0.331429 0.934703 + outer loop + vertex 1.54859 2.09824 2.47094 + vertex 1.54449 2.0994 2.4711 + vertex 1.54643 2.09511 2.47235 + endloop + endfacet + facet normal 0.137721 0.334909 0.932131 + outer loop + vertex 1.54643 2.09511 2.47235 + vertex 1.54449 2.0994 2.4711 + vertex 1.54077 2.09659 2.47265 + endloop + endfacet + facet normal 0.136058 0.310328 0.940843 + outer loop + vertex 1.53837 2.09225 2.47443 + vertex 1.54077 2.09659 2.47265 + vertex 1.53626 2.096 2.4735 + endloop + endfacet + facet normal 0.133352 0.309016 0.941661 + outer loop + vertex 1.53837 2.09225 2.47443 + vertex 1.53626 2.096 2.4735 + vertex 1.53277 2.09367 2.47476 + endloop + endfacet + facet normal 0.131392 0.312191 0.940889 + outer loop + vertex 1.52842 2.09293 2.47562 + vertex 1.53277 2.09367 2.47476 + vertex 1.5284 2.09697 2.47427 + endloop + endfacet + facet normal 0.135234 0.329982 0.93425 + outer loop + vertex 1.53302 2.0975 2.47346 + vertex 1.53628 2.09981 2.47217 + vertex 1.53123 2.10083 2.47254 + endloop + endfacet + facet normal 0.129683 0.312257 0.941105 + outer loop + vertex 1.52439 2.09385 2.47586 + vertex 1.52842 2.09293 2.47562 + vertex 1.5284 2.09697 2.47427 + endloop + endfacet + facet normal 0.125171 0.31392 0.941162 + outer loop + vertex 1.52439 2.09385 2.47586 + vertex 1.51954 2.09483 2.47618 + vertex 1.52096 2.09079 2.47734 + endloop + endfacet + facet normal 0.124382 0.313694 0.941342 + outer loop + vertex 1.52096 2.09079 2.47734 + vertex 1.51954 2.09483 2.47618 + vertex 1.51567 2.09178 2.47771 + endloop + endfacet + facet normal 0.121438 0.321958 0.938933 + outer loop + vertex 1.51133 2.09481 2.47723 + vertex 1.51116 2.09102 2.47855 + vertex 1.51567 2.09178 2.47771 + endloop + endfacet + facet normal 0.119194 0.322139 0.939159 + outer loop + vertex 1.51116 2.09102 2.47855 + vertex 1.51133 2.09481 2.47723 + vertex 1.50792 2.09246 2.47847 + endloop + endfacet + facet normal 0.116083 0.320816 0.940001 + outer loop + vertex 1.51352 2.09807 2.47584 + vertex 1.51555 2.09568 2.47641 + vertex 1.5178 2.09893 2.47502 + endloop + endfacet + facet normal 0.115129 0.325373 0.938551 + outer loop + vertex 1.50951 2.09891 2.47604 + vertex 1.51352 2.09807 2.47584 + vertex 1.51346 2.10204 2.47447 + endloop + endfacet + facet normal 0.115677 0.324101 0.938923 + outer loop + vertex 1.50466 2.09984 2.47632 + vertex 1.50951 2.09891 2.47604 + vertex 1.50795 2.10297 2.47483 + endloop + endfacet + facet normal 0.116386 0.325739 0.938269 + outer loop + vertex 1.50792 2.09246 2.47847 + vertex 1.51133 2.09481 2.47723 + vertex 1.50622 2.09579 2.47753 + endloop + endfacet + facet normal 0.118746 0.321153 0.939553 + outer loop + vertex 1.50771 2.08867 2.47979 + vertex 1.51116 2.09102 2.47855 + vertex 1.50792 2.09246 2.47847 + endloop + endfacet + facet normal 0.118736 0.318173 0.940568 + outer loop + vertex 1.5034 2.08792 2.48059 + vertex 1.50547 2.08543 2.48117 + vertex 1.50771 2.08867 2.47979 + endloop + endfacet + facet normal 0.113277 0.318122 0.941258 + outer loop + vertex 1.5034 2.08792 2.48059 + vertex 1.49938 2.08883 2.48077 + vertex 1.50114 2.08458 2.48199 + endloop + endfacet + facet normal 0.115053 0.318738 0.940834 + outer loop + vertex 1.50114 2.08458 2.48199 + vertex 1.49938 2.08883 2.48077 + vertex 1.49598 2.08579 2.48221 + endloop + endfacet + facet normal 0.113537 0.320272 0.940497 + outer loop + vertex 1.49938 2.08883 2.48077 + vertex 1.49454 2.08976 2.48103 + vertex 1.49598 2.08579 2.48221 + endloop + endfacet + facet normal 0.114737 0.322688 0.939526 + outer loop + vertex 1.49454 2.08976 2.48103 + vertex 1.49269 2.09386 2.47985 + vertex 1.49054 2.09056 2.48125 + endloop + endfacet + facet normal 0.117132 0.321227 0.939731 + outer loop + vertex 1.49269 2.09386 2.47985 + vertex 1.49611 2.09626 2.47861 + vertex 1.49287 2.0977 2.47852 + endloop + endfacet + facet normal 0.114346 0.324797 0.938846 + outer loop + vertex 1.50331 2.09192 2.47922 + vertex 1.50073 2.09678 2.47786 + vertex 1.49781 2.0929 2.47955 + endloop + endfacet + facet normal 0.116346 0.319503 0.940415 + outer loop + vertex 1.49611 2.09626 2.47861 + vertex 1.49635 2.10007 2.47728 + vertex 1.49287 2.0977 2.47852 + endloop + endfacet + facet normal 0.119339 0.316512 0.941052 + outer loop + vertex 1.50066 2.10077 2.4765 + vertex 1.49863 2.10329 2.47591 + vertex 1.49635 2.10007 2.47728 + endloop + endfacet + facet normal 0.121784 0.314882 0.941285 + outer loop + vertex 1.49863 2.10329 2.47591 + vertex 1.49461 2.10439 2.47606 + vertex 1.49635 2.10007 2.47728 + endloop + endfacet + facet normal 0.122747 0.318896 0.939808 + outer loop + vertex 1.49461 2.10439 2.47606 + vertex 1.49273 2.10873 2.47483 + vertex 1.49057 2.10544 2.47623 + endloop + endfacet + facet normal 0.131801 0.352496 0.926485 + outer loop + vertex 1.49853 2.10735 2.47454 + vertex 1.5013 2.11105 2.47273 + vertex 1.49593 2.11215 2.47308 + endloop + endfacet + facet normal 0.122669 0.318944 0.939802 + outer loop + vertex 1.48849 2.1079 2.47567 + vertex 1.49057 2.10544 2.47623 + vertex 1.49273 2.10873 2.47483 + endloop + endfacet + facet normal 0.11264 0.31668 0.941821 + outer loop + vertex 1.48849 2.1079 2.47567 + vertex 1.48444 2.10881 2.47585 + vertex 1.48622 2.10458 2.47705 + endloop + endfacet + facet normal 0.112407 0.320418 0.940583 + outer loop + vertex 1.48444 2.10881 2.47585 + vertex 1.47951 2.10979 2.4761 + vertex 1.48105 2.10584 2.47727 + endloop + endfacet + facet normal 0.116987 0.355914 0.927167 + outer loop + vertex 1.47951 2.10979 2.4761 + vertex 1.47729 2.11381 2.47484 + vertex 1.47547 2.11053 2.47633 + endloop + endfacet + facet normal 0.122493 0.418835 0.899763 + outer loop + vertex 1.4828 2.1128 2.47454 + vertex 1.48608 2.11569 2.47275 + vertex 1.48094 2.11663 2.47301 + endloop + endfacet + facet normal 0.1232 0.352658 0.927607 + outer loop + vertex 1.47324 2.1127 2.4758 + vertex 1.47547 2.11053 2.47633 + vertex 1.47729 2.11381 2.47484 + endloop + endfacet + facet normal 0.0949059 0.33256 0.938294 + outer loop + vertex 1.47324 2.1127 2.4758 + vertex 1.4693 2.1135 2.47591 + vertex 1.47122 2.1095 2.47714 + endloop + endfacet + facet normal 0.0997659 0.335932 0.936588 + outer loop + vertex 1.4693 2.1135 2.47591 + vertex 1.46447 2.11461 2.47603 + vertex 1.46605 2.11067 2.47728 + endloop + endfacet + facet normal 0.103096 0.337027 0.935833 + outer loop + vertex 1.46605 2.11067 2.47728 + vertex 1.46447 2.11461 2.47603 + vertex 1.46073 2.11155 2.47754 + endloop + endfacet + facet normal 0.101454 0.316286 0.943223 + outer loop + vertex 1.46308 2.10797 2.47849 + vertex 1.46073 2.11155 2.47754 + vertex 1.45843 2.1069 2.47935 + endloop + endfacet + facet normal 0.104886 0.318118 0.942231 + outer loop + vertex 1.45447 2.10375 2.48086 + vertex 1.45848 2.10292 2.48069 + vertex 1.45843 2.1069 2.47935 + endloop + endfacet + facet normal 0.105986 0.323837 0.940158 + outer loop + vertex 1.45447 2.10375 2.48086 + vertex 1.44964 2.1047 2.48107 + vertex 1.45102 2.10074 2.48228 + endloop + endfacet + facet normal 0.10516 0.323602 0.940331 + outer loop + vertex 1.45102 2.10074 2.48228 + vertex 1.44964 2.1047 2.48107 + vertex 1.44571 2.10159 2.48258 + endloop + endfacet + facet normal 0.101229 0.32885 0.938941 + outer loop + vertex 1.44119 2.10449 2.48205 + vertex 1.4411 2.10054 2.48345 + vertex 1.44571 2.10159 2.48258 + endloop + endfacet + facet normal 0.0970147 0.324374 0.940941 + outer loop + vertex 1.44352 2.10791 2.48062 + vertex 1.44559 2.10553 2.48123 + vertex 1.44797 2.10893 2.47982 + endloop + endfacet + facet normal 0.0954343 0.329473 0.939329 + outer loop + vertex 1.44119 2.10449 2.48205 + vertex 1.43946 2.10862 2.48078 + vertex 1.43609 2.10551 2.48222 + endloop + endfacet + facet normal 0.0923806 0.329073 0.939775 + outer loop + vertex 1.43462 2.10927 2.48103 + vertex 1.43946 2.10862 2.48078 + vertex 1.43797 2.11254 2.47955 + endloop + endfacet + facet normal 0.0969017 0.32477 0.940816 + outer loop + vertex 1.44352 2.10791 2.48062 + vertex 1.44797 2.10893 2.47982 + vertex 1.44348 2.11196 2.47923 + endloop + endfacet + facet normal 0.101698 0.314913 0.943656 + outer loop + vertex 1.45314 2.10774 2.47965 + vertex 1.45215 2.11171 2.47843 + vertex 1.44797 2.10893 2.47982 + endloop + endfacet + facet normal 0.0939475 0.33285 0.938288 + outer loop + vertex 1.44823 2.11288 2.47845 + vertex 1.45105 2.11555 2.47722 + vertex 1.44628 2.11606 2.47752 + endloop + endfacet + facet normal 0.105841 0.323015 0.940457 + outer loop + vertex 1.45616 2.1105 2.4784 + vertex 1.4561 2.11452 2.47702 + vertex 1.45215 2.11171 2.47843 + endloop + endfacet + facet normal 0.0965552 0.363578 0.926546 + outer loop + vertex 1.45105 2.11555 2.47722 + vertex 1.44923 2.11913 2.47601 + vertex 1.44628 2.11606 2.47752 + endloop + endfacet + facet normal 0.0888922 0.370067 0.924743 + outer loop + vertex 1.44923 2.11913 2.47601 + vertex 1.44451 2.11984 2.47618 + vertex 1.44628 2.11606 2.47752 + endloop + endfacet + facet normal 0.0913358 0.370993 0.924133 + outer loop + vertex 1.44628 2.11606 2.47752 + vertex 1.44451 2.11984 2.47618 + vertex 1.44081 2.11664 2.47783 + endloop + endfacet + facet normal 0.09401 0.330618 0.939071 + outer loop + vertex 1.43797 2.11254 2.47955 + vertex 1.44081 2.11664 2.47783 + vertex 1.43617 2.11574 2.47861 + endloop + endfacet + facet normal 0.0925091 0.329893 0.939475 + outer loop + vertex 1.43797 2.11254 2.47955 + vertex 1.43617 2.11574 2.47861 + vertex 1.43321 2.11305 2.47984 + endloop + endfacet + facet normal 0.101519 0.347412 0.932201 + outer loop + vertex 1.43231 2.11688 2.47861 + vertex 1.43626 2.1196 2.47716 + vertex 1.43113 2.12076 2.47729 + endloop + endfacet + facet normal 0.108237 0.335232 0.935898 + outer loop + vertex 1.42374 2.117 2.47946 + vertex 1.42589 2.12159 2.47757 + vertex 1.42142 2.12056 2.47846 + endloop + endfacet + facet normal 0.0997018 0.322673 0.941245 + outer loop + vertex 1.41482 2.11483 2.48115 + vertex 1.41973 2.11385 2.48096 + vertex 1.41839 2.11785 2.47973 + endloop + endfacet + facet normal 0.0990861 0.328901 0.939152 + outer loop + vertex 1.42379 2.11302 2.48082 + vertex 1.41973 2.11385 2.48096 + vertex 1.4214 2.10967 2.48225 + endloop + endfacet + facet normal 0.0980898 0.328572 0.939372 + outer loop + vertex 1.4214 2.10967 2.48225 + vertex 1.41973 2.11385 2.48096 + vertex 1.41622 2.11086 2.48237 + endloop + endfacet + facet normal 0.0984052 0.324435 0.940775 + outer loop + vertex 1.42374 2.117 2.47946 + vertex 1.42819 2.11407 2.48001 + vertex 1.42836 2.11807 2.47861 + endloop + endfacet + facet normal 0.0972459 0.327575 0.939808 + outer loop + vertex 1.42819 2.11407 2.48001 + vertex 1.42982 2.10994 2.48128 + vertex 1.43321 2.11305 2.47984 + endloop + endfacet + facet normal 0.0967564 0.333223 0.93787 + outer loop + vertex 1.43129 2.10604 2.48251 + vertex 1.42982 2.10994 2.48128 + vertex 1.42583 2.10666 2.48286 + endloop + endfacet + facet normal 0.0986907 0.329161 0.939102 + outer loop + vertex 1.42581 2.11065 2.48144 + vertex 1.42379 2.11302 2.48082 + vertex 1.4214 2.10967 2.48225 + endloop + endfacet + facet normal 0.0983854 0.330873 0.938532 + outer loop + vertex 1.42295 2.1026 2.48459 + vertex 1.42583 2.10666 2.48286 + vertex 1.42114 2.1058 2.48365 + endloop + endfacet + facet normal 0.0972682 0.330331 0.93884 + outer loop + vertex 1.42295 2.1026 2.48459 + vertex 1.42114 2.1058 2.48365 + vertex 1.4182 2.10315 2.48489 + endloop + endfacet + facet normal 0.0988483 0.332008 0.938083 + outer loop + vertex 1.41725 2.10697 2.48364 + vertex 1.4214 2.10967 2.48225 + vertex 1.41622 2.11086 2.48237 + endloop + endfacet + facet normal 0.100352 0.326197 0.93996 + outer loop + vertex 1.41973 2.11385 2.48096 + vertex 1.41482 2.11483 2.48115 + vertex 1.41622 2.11086 2.48237 + endloop + endfacet + facet normal 0.0994609 0.329512 0.938898 + outer loop + vertex 1.40623 2.11452 2.48216 + vertex 1.40617 2.11056 2.48356 + vertex 1.41085 2.1117 2.48266 + endloop + endfacet + facet normal 0.101102 0.323706 0.940741 + outer loop + vertex 1.40861 2.11799 2.48073 + vertex 1.41071 2.11565 2.48131 + vertex 1.41311 2.11902 2.4799 + endloop + endfacet + facet normal 0.0870236 0.340903 0.936062 + outer loop + vertex 1.40447 2.11859 2.4809 + vertex 1.40861 2.11799 2.48073 + vertex 1.40857 2.12188 2.47932 + endloop + endfacet + facet normal 0.0840381 0.330215 0.940157 + outer loop + vertex 1.40617 2.11056 2.48356 + vertex 1.40623 2.11452 2.48216 + vertex 1.40197 2.11148 2.48361 + endloop + endfacet + facet normal 0.0852852 0.336067 0.937969 + outer loop + vertex 1.40319 2.10773 2.48484 + vertex 1.40617 2.11056 2.48356 + vertex 1.40197 2.11148 2.48361 + endloop + endfacet + facet normal 0.0941373 0.333691 0.937971 + outer loop + vertex 1.40319 2.10773 2.48484 + vertex 1.40467 2.10392 2.48605 + vertex 1.40859 2.10711 2.48452 + endloop + endfacet + facet normal 0.0974719 0.325513 0.9405 + outer loop + vertex 1.40877 2.10322 2.48587 + vertex 1.40467 2.10392 2.48605 + vertex 1.40653 2.09989 2.48725 + endloop + endfacet + facet normal 0.101692 0.320553 0.941756 + outer loop + vertex 1.4062 2.09615 2.48856 + vertex 1.40653 2.09989 2.48725 + vertex 1.40303 2.0975 2.48844 + endloop + endfacet + facet normal 0.101398 0.31988 0.942017 + outer loop + vertex 1.40274 2.09378 2.48974 + vertex 1.4062 2.09615 2.48856 + vertex 1.40303 2.0975 2.48844 + endloop + endfacet + facet normal 0.0989551 0.321907 0.941586 + outer loop + vertex 1.39849 2.09288 2.49049 + vertex 1.40057 2.0905 2.49109 + vertex 1.40274 2.09378 2.48974 + endloop + endfacet + facet normal 0.0776745 0.327112 0.941788 + outer loop + vertex 1.39849 2.09288 2.49049 + vertex 1.39443 2.09354 2.4906 + vertex 1.39623 2.08943 2.49188 + endloop + endfacet + facet normal 0.0747435 0.33554 0.939056 + outer loop + vertex 1.39843 2.09679 2.48913 + vertex 1.40138 2.10069 2.4875 + vertex 1.3962 2.10113 2.48775 + endloop + endfacet + facet normal 0.0547361 0.344729 0.937105 + outer loop + vertex 1.39048 2.10564 2.48643 + vertex 1.38615 2.10447 2.48711 + vertex 1.39056 2.10176 2.48785 + endloop + endfacet + facet normal 0.0531728 0.345187 0.937026 + outer loop + vertex 1.39288 2.1091 2.48504 + vertex 1.39461 2.10511 2.48641 + vertex 1.39821 2.10838 2.485 + endloop + endfacet + facet normal 0.0524337 0.33958 0.939115 + outer loop + vertex 1.39821 2.10838 2.485 + vertex 1.39718 2.11214 2.4837 + vertex 1.39288 2.1091 2.48504 + endloop + endfacet + facet normal 0.0484241 0.344549 0.937518 + outer loop + vertex 1.39288 2.1091 2.48504 + vertex 1.39718 2.11214 2.4837 + vertex 1.39314 2.11291 2.48362 + endloop + endfacet + facet normal 0.0480164 0.342477 0.938298 + outer loop + vertex 1.39718 2.11214 2.4837 + vertex 1.39609 2.11575 2.48243 + vertex 1.39314 2.11291 2.48362 + endloop + endfacet + facet normal 0.0618985 0.336673 0.939585 + outer loop + vertex 1.39461 2.10511 2.48641 + vertex 1.39966 2.10455 2.48627 + vertex 1.39821 2.10838 2.485 + endloop + endfacet + facet normal 0.0623802 0.341402 0.937845 + outer loop + vertex 1.39966 2.10455 2.48627 + vertex 1.39461 2.10511 2.48641 + vertex 1.3962 2.10113 2.48775 + endloop + endfacet + facet normal 0.0449335 0.345306 0.937414 + outer loop + vertex 1.39314 2.11291 2.48362 + vertex 1.39609 2.11575 2.48243 + vertex 1.39125 2.11597 2.48259 + endloop + endfacet + facet normal 0.0450826 0.349752 0.935757 + outer loop + vertex 1.39609 2.11575 2.48243 + vertex 1.39456 2.11937 2.48115 + vertex 1.39125 2.11597 2.48259 + endloop + endfacet + facet normal 0.0450696 0.349763 0.935753 + outer loop + vertex 1.39456 2.11937 2.48115 + vertex 1.38962 2.11982 2.48122 + vertex 1.39125 2.11597 2.48259 + endloop + endfacet + facet normal 0.0662875 0.357276 0.931644 + outer loop + vertex 1.39125 2.11597 2.48259 + vertex 1.38962 2.11982 2.48122 + vertex 1.38575 2.11649 2.48278 + endloop + endfacet + facet normal 0.046393 0.365132 0.929799 + outer loop + vertex 1.38962 2.11982 2.48122 + vertex 1.39456 2.11937 2.48115 + vertex 1.39291 2.12313 2.47976 + endloop + endfacet + facet normal 0.0577743 0.355216 0.932997 + outer loop + vertex 1.38757 2.12383 2.47982 + vertex 1.38962 2.11982 2.48122 + vertex 1.39291 2.12313 2.47976 + endloop + endfacet + facet normal 0.0350602 0.360941 0.93193 + outer loop + vertex 1.39291 2.12313 2.47976 + vertex 1.39456 2.11937 2.48115 + vertex 1.3979 2.12275 2.47972 + endloop + endfacet + facet normal 0.0406792 0.356088 0.933566 + outer loop + vertex 1.39456 2.11937 2.48115 + vertex 1.39949 2.11905 2.48106 + vertex 1.3979 2.12275 2.47972 + endloop + endfacet + facet normal 0.0474346 0.358545 0.932307 + outer loop + vertex 1.3979 2.12275 2.47972 + vertex 1.39949 2.11905 2.48106 + vertex 1.40297 2.12245 2.47958 + endloop + endfacet + facet normal 0.0490586 0.39232 0.91852 + outer loop + vertex 1.40297 2.12245 2.47958 + vertex 1.40106 2.12611 2.47812 + vertex 1.3979 2.12275 2.47972 + endloop + endfacet + facet normal 0.062837 0.344695 0.936609 + outer loop + vertex 1.39949 2.11905 2.48106 + vertex 1.40447 2.11859 2.4809 + vertex 1.40297 2.12245 2.47958 + endloop + endfacet + facet normal 0.0624499 0.339892 0.938389 + outer loop + vertex 1.40447 2.11859 2.4809 + vertex 1.39949 2.11905 2.48106 + vertex 1.40091 2.11528 2.48234 + endloop + endfacet + facet normal 0.040204 0.348 0.936632 + outer loop + vertex 1.39949 2.11905 2.48106 + vertex 1.39456 2.11937 2.48115 + vertex 1.39609 2.11575 2.48243 + endloop + endfacet + facet normal 0.0524877 0.336747 0.940131 + outer loop + vertex 1.40091 2.11528 2.48234 + vertex 1.39949 2.11905 2.48106 + vertex 1.39609 2.11575 2.48243 + endloop + endfacet + facet normal 0.053129 0.343768 0.93755 + outer loop + vertex 1.39718 2.11214 2.4837 + vertex 1.40091 2.11528 2.48234 + vertex 1.39609 2.11575 2.48243 + endloop + endfacet + facet normal 0.067508 0.34013 0.937952 + outer loop + vertex 1.38445 2.10849 2.48578 + vertex 1.38843 2.10786 2.48572 + vertex 1.38838 2.11184 2.48429 + endloop + endfacet + facet normal 0.0876355 0.330167 0.939845 + outer loop + vertex 1.38445 2.10849 2.48578 + vertex 1.3797 2.10917 2.48599 + vertex 1.38118 2.10538 2.48718 + endloop + endfacet + facet normal 0.105067 0.330151 0.938063 + outer loop + vertex 1.37494 2.10991 2.48626 + vertex 1.3797 2.10917 2.48599 + vertex 1.37823 2.11301 2.4848 + endloop + endfacet + facet normal 0.0938719 0.333945 0.937907 + outer loop + vertex 1.38294 2.11241 2.48451 + vertex 1.38575 2.11649 2.48278 + vertex 1.38113 2.11566 2.48354 + endloop + endfacet + facet normal 0.0937225 0.334578 0.937696 + outer loop + vertex 1.38134 2.11954 2.48213 + vertex 1.38113 2.11566 2.48354 + vertex 1.38575 2.11649 2.48278 + endloop + endfacet + facet normal 0.113132 0.316486 0.941827 + outer loop + vertex 1.36887 2.11319 2.48585 + vertex 1.37323 2.11413 2.48501 + vertex 1.36873 2.11727 2.48449 + endloop + endfacet + facet normal 0.119004 0.322349 0.939111 + outer loop + vertex 1.37731 2.11689 2.48356 + vertex 1.37631 2.12085 2.48233 + vertex 1.37338 2.11819 2.48361 + endloop + endfacet + facet normal 0.118615 0.312043 0.942635 + outer loop + vertex 1.36873 2.11727 2.48449 + vertex 1.37109 2.12184 2.48268 + vertex 1.36657 2.12099 2.48353 + endloop + endfacet + facet normal 0.123788 0.30653 0.943778 + outer loop + vertex 1.36301 2.11859 2.48478 + vertex 1.36657 2.12099 2.48353 + vertex 1.36328 2.12246 2.48349 + endloop + endfacet + facet normal 0.130822 0.306737 0.942761 + outer loop + vertex 1.35862 2.11797 2.48559 + vertex 1.36071 2.11534 2.48615 + vertex 1.36301 2.11859 2.48478 + endloop + endfacet + facet normal 0.147568 0.307794 0.93994 + outer loop + vertex 1.35862 2.11797 2.48559 + vertex 1.35461 2.11918 2.48582 + vertex 1.3564 2.11478 2.48698 + endloop + endfacet + facet normal 0.15218 0.300265 0.941638 + outer loop + vertex 1.35461 2.11918 2.48582 + vertex 1.35283 2.12362 2.48469 + vertex 1.35066 2.12036 2.48608 + endloop + endfacet + facet normal 0.141072 0.306283 0.941429 + outer loop + vertex 1.35858 2.12208 2.48428 + vertex 1.36158 2.12583 2.48261 + vertex 1.35621 2.12705 2.48302 + endloop + endfacet + facet normal 0.15497 0.298454 0.941759 + outer loop + vertex 1.34866 2.12296 2.48559 + vertex 1.35066 2.12036 2.48608 + vertex 1.35283 2.12362 2.48469 + endloop + endfacet + facet normal 0.158178 0.299554 0.940876 + outer loop + vertex 1.34866 2.12296 2.48559 + vertex 1.34475 2.12419 2.48586 + vertex 1.34645 2.11979 2.48697 + endloop + endfacet + facet normal 0.15747 0.299328 0.941066 + outer loop + vertex 1.34645 2.11979 2.48697 + vertex 1.34475 2.12419 2.48586 + vertex 1.34095 2.12139 2.48738 + endloop + endfacet + facet normal 0.15771 0.296432 0.941943 + outer loop + vertex 1.33657 2.12487 2.48702 + vertex 1.33643 2.1209 2.48829 + vertex 1.34095 2.12139 2.48738 + endloop + endfacet + facet normal 0.161281 0.305791 0.938339 + outer loop + vertex 1.33875 2.12804 2.48563 + vertex 1.34082 2.12544 2.48612 + vertex 1.34291 2.12863 2.48472 + endloop + endfacet + facet normal 0.156342 0.329318 0.931186 + outer loop + vertex 1.33875 2.12804 2.48563 + vertex 1.34291 2.12863 2.48472 + vertex 1.33853 2.13186 2.48432 + endloop + endfacet + facet normal 0.153259 0.325373 0.933083 + outer loop + vertex 1.33853 2.13186 2.48432 + vertex 1.34291 2.12863 2.48472 + vertex 1.34237 2.1319 2.48367 + endloop + endfacet + facet normal 0.14878 0.386955 0.910017 + outer loop + vertex 1.34237 2.1319 2.48367 + vertex 1.34163 2.13496 2.48249 + vertex 1.33853 2.13186 2.48432 + endloop + endfacet + facet normal 0.163582 0.329323 0.929939 + outer loop + vertex 1.33475 2.12923 2.48591 + vertex 1.33875 2.12804 2.48563 + vertex 1.33853 2.13186 2.48432 + endloop + endfacet + facet normal 0.167776 0.305997 0.937132 + outer loop + vertex 1.33077 2.13041 2.48622 + vertex 1.32664 2.12984 2.48715 + vertex 1.33104 2.12644 2.48747 + endloop + endfacet + facet normal 0.157033 0.337617 0.928093 + outer loop + vertex 1.33264 2.1336 2.48468 + vertex 1.33475 2.12923 2.48591 + vertex 1.33853 2.13186 2.48432 + endloop + endfacet + facet normal 0.163903 0.324775 0.931481 + outer loop + vertex 1.33077 2.13041 2.48622 + vertex 1.32856 2.13285 2.48576 + vertex 1.32664 2.12984 2.48715 + endloop + endfacet + facet normal 0.162368 0.325724 0.931419 + outer loop + vertex 1.32856 2.13285 2.48576 + vertex 1.32466 2.13406 2.48602 + vertex 1.32664 2.12984 2.48715 + endloop + endfacet + facet normal 0.167264 0.302 0.938519 + outer loop + vertex 1.31878 2.12715 2.48939 + vertex 1.32115 2.13146 2.48758 + vertex 1.31669 2.13104 2.48851 + endloop + endfacet + facet normal 0.166002 0.301418 0.938931 + outer loop + vertex 1.31878 2.12715 2.48939 + vertex 1.31669 2.13104 2.48851 + vertex 1.31323 2.12878 2.48985 + endloop + endfacet + facet normal 0.167103 0.297844 0.939875 + outer loop + vertex 1.30895 2.12823 2.49079 + vertex 1.31096 2.1256 2.49126 + vertex 1.31323 2.12878 2.48985 + endloop + endfacet + facet normal 0.167181 0.29848 0.93966 + outer loop + vertex 1.30895 2.12823 2.49079 + vertex 1.30503 2.12941 2.49111 + vertex 1.30671 2.12503 2.4922 + endloop + endfacet + facet normal 0.171937 0.308771 0.935467 + outer loop + vertex 1.30503 2.12941 2.49111 + vertex 1.30331 2.13376 2.48999 + vertex 1.30112 2.13058 2.49144 + endloop + endfacet + facet normal 0.165645 0.329251 0.929599 + outer loop + vertex 1.30331 2.13376 2.48999 + vertex 1.30665 2.13601 2.4886 + vertex 1.30339 2.13759 2.48862 + endloop + endfacet + facet normal 0.161951 0.330018 0.929978 + outer loop + vertex 1.31335 2.13274 2.48854 + vertex 1.311 2.13653 2.4876 + vertex 1.30883 2.13223 2.4895 + endloop + endfacet + facet normal 0.163553 0.330865 0.929397 + outer loop + vertex 1.31335 2.13274 2.48854 + vertex 1.31661 2.13497 2.48717 + vertex 1.311 2.13653 2.4876 + endloop + endfacet + facet normal 0.180239 0.326089 0.927998 + outer loop + vertex 1.29505 2.13458 2.49126 + vertex 1.29907 2.13322 2.49095 + vertex 1.29883 2.13734 2.48955 + endloop + endfacet + facet normal 0.176732 0.306553 0.935303 + outer loop + vertex 1.29686 2.13011 2.49238 + vertex 1.29505 2.13458 2.49126 + vertex 1.29129 2.13202 2.49281 + endloop + endfacet + facet normal 0.175409 0.318656 0.931499 + outer loop + vertex 1.29101 2.13599 2.49157 + vertex 1.28894 2.13871 2.49103 + vertex 1.28651 2.13571 2.49251 + endloop + endfacet + facet normal 0.174766 0.299527 0.937945 + outer loop + vertex 1.29334 2.12802 2.4937 + vertex 1.29129 2.13202 2.49281 + vertex 1.28848 2.12801 2.49461 + endloop + endfacet + facet normal 0.176472 0.297302 0.938333 + outer loop + vertex 1.2839 2.12774 2.49556 + vertex 1.28585 2.12498 2.49607 + vertex 1.28848 2.12801 2.49461 + endloop + endfacet + facet normal 0.177457 0.297767 0.938 + outer loop + vertex 1.2839 2.12774 2.49556 + vertex 1.2799 2.12914 2.49587 + vertex 1.28169 2.12462 2.49696 + endloop + endfacet + facet normal 0.180025 0.299727 0.936886 + outer loop + vertex 1.2799 2.12914 2.49587 + vertex 1.27823 2.13362 2.49476 + vertex 1.27597 2.13049 2.49619 + endloop + endfacet + facet normal 0.175907 0.301747 0.937019 + outer loop + vertex 1.28752 2.13188 2.49356 + vertex 1.28651 2.13571 2.49251 + vertex 1.28374 2.13173 2.49431 + endloop + endfacet + facet normal 0.177397 0.303275 0.936245 + outer loop + vertex 1.27823 2.13362 2.49476 + vertex 1.28176 2.13568 2.49342 + vertex 1.27846 2.13749 2.49346 + endloop + endfacet + facet normal 0.181798 0.298473 0.936944 + outer loop + vertex 1.27397 2.1332 2.49572 + vertex 1.27597 2.13049 2.49619 + vertex 1.27823 2.13362 2.49476 + endloop + endfacet + facet normal 0.18555 0.297838 0.93641 + outer loop + vertex 1.27397 2.1332 2.49572 + vertex 1.27002 2.13458 2.49606 + vertex 1.27173 2.13006 2.49716 + endloop + endfacet + facet normal 0.189051 0.301954 0.93439 + outer loop + vertex 1.27002 2.13458 2.49606 + vertex 1.26805 2.13921 2.49496 + vertex 1.26605 2.13598 2.49641 + endloop + endfacet + facet normal 0.182395 0.318421 0.930236 + outer loop + vertex 1.27382 2.13737 2.4944 + vertex 1.27658 2.14102 2.49261 + vertex 1.27114 2.14254 2.49316 + endloop + endfacet + facet normal 0.189491 0.314486 0.930157 + outer loop + vertex 1.26409 2.13871 2.49594 + vertex 1.26805 2.13921 2.49496 + vertex 1.26346 2.1428 2.49468 + endloop + endfacet + facet normal 0.195906 0.367677 0.909084 + outer loop + vertex 1.26652 2.14609 2.49272 + vertex 1.26733 2.14267 2.49393 + vertex 1.27114 2.14254 2.49316 + endloop + endfacet + facet normal 0.197923 0.313212 0.92883 + outer loop + vertex 1.25904 2.14271 2.49566 + vertex 1.26104 2.13994 2.49616 + vertex 1.26346 2.1428 2.49468 + endloop + endfacet + facet normal 0.18474 0.304684 0.934365 + outer loop + vertex 1.26104 2.13994 2.49616 + vertex 1.25904 2.14271 2.49566 + vertex 1.25688 2.13969 2.49707 + endloop + endfacet + facet normal 0.187064 0.30305 0.934435 + outer loop + vertex 1.25904 2.14271 2.49566 + vertex 1.25493 2.1443 2.49596 + vertex 1.25688 2.13969 2.49707 + endloop + endfacet + facet normal 0.192052 0.304774 0.932861 + outer loop + vertex 1.25688 2.13969 2.49707 + vertex 1.25493 2.1443 2.49596 + vertex 1.25119 2.14171 2.49758 + endloop + endfacet + facet normal 0.19261 0.336158 0.9219 + outer loop + vertex 1.25082 2.14591 2.49632 + vertex 1.2486 2.14858 2.49581 + vertex 1.24632 2.14576 2.49731 + endloop + endfacet + facet normal 0.188974 0.278296 0.941722 + outer loop + vertex 1.24883 2.13722 2.49938 + vertex 1.25119 2.14171 2.49758 + vertex 1.2467 2.14134 2.49859 + endloop + endfacet + facet normal 0.189009 0.278312 0.94171 + outer loop + vertex 1.24883 2.13722 2.49938 + vertex 1.2467 2.14134 2.49859 + vertex 1.24334 2.13902 2.49995 + endloop + endfacet + facet normal 0.191959 0.274356 0.942274 + outer loop + vertex 1.24334 2.13902 2.49995 + vertex 1.2467 2.14134 2.49859 + vertex 1.24349 2.14298 2.49877 + endloop + endfacet + facet normal 0.189021 0.278353 0.941696 + outer loop + vertex 1.24334 2.13902 2.49995 + vertex 1.24501 2.13438 2.50099 + vertex 1.24883 2.13722 2.49938 + endloop + endfacet + facet normal 0.188874 0.288815 0.93857 + outer loop + vertex 1.2467 2.12987 2.50203 + vertex 1.24501 2.13438 2.50099 + vertex 1.2412 2.13159 2.50261 + endloop + endfacet + facet normal 0.196547 0.277778 0.940324 + outer loop + vertex 1.24104 2.13581 2.50136 + vertex 1.23918 2.13866 2.50091 + vertex 1.23644 2.13568 2.50236 + endloop + endfacet + facet normal 0.191743 0.287537 0.93838 + outer loop + vertex 1.23898 2.12704 2.50446 + vertex 1.2412 2.13159 2.50261 + vertex 1.23669 2.1312 2.50365 + endloop + endfacet + facet normal 0.191509 0.287424 0.938462 + outer loop + vertex 1.23898 2.12704 2.50446 + vertex 1.23669 2.1312 2.50365 + vertex 1.23333 2.12903 2.505 + endloop + endfacet + facet normal 0.19333 0.280127 0.940294 + outer loop + vertex 1.22911 2.12888 2.50592 + vertex 1.23333 2.12903 2.505 + vertex 1.22874 2.13322 2.5047 + endloop + endfacet + facet normal 0.195975 0.277951 0.940392 + outer loop + vertex 1.23342 2.13294 2.5038 + vertex 1.23644 2.13568 2.50236 + vertex 1.23182 2.13583 2.50328 + endloop + endfacet + facet normal 0.196091 0.27044 0.942555 + outer loop + vertex 1.2241 2.13333 2.50563 + vertex 1.22874 2.13322 2.5047 + vertex 1.22367 2.13782 2.50443 + endloop + endfacet + facet normal 0.198433 0.269429 0.942355 + outer loop + vertex 1.23182 2.13583 2.50328 + vertex 1.23198 2.13979 2.50211 + vertex 1.22853 2.13772 2.50343 + endloop + endfacet + facet normal 0.197174 0.306851 0.931109 + outer loop + vertex 1.22614 2.14616 2.50154 + vertex 1.22408 2.14891 2.50107 + vertex 1.22168 2.1459 2.50257 + endloop + endfacet + facet normal 0.200974 0.263271 0.943556 + outer loop + vertex 1.22367 2.13782 2.50443 + vertex 1.22644 2.14199 2.50268 + vertex 1.22271 2.1419 2.5035 + endloop + endfacet + facet normal 0.19637 0.268005 0.943192 + outer loop + vertex 1.21904 2.13763 2.50545 + vertex 1.22093 2.13476 2.50587 + vertex 1.22367 2.13782 2.50443 + endloop + endfacet + facet normal 0.202029 0.264985 0.942851 + outer loop + vertex 1.21904 2.13763 2.50545 + vertex 1.21507 2.1392 2.50586 + vertex 1.21667 2.1344 2.50687 + endloop + endfacet + facet normal 0.203163 0.255062 0.94534 + outer loop + vertex 1.21507 2.1392 2.50586 + vertex 1.21337 2.14401 2.50493 + vertex 1.21112 2.14082 2.50627 + endloop + endfacet + facet normal 0.207956 0.265031 0.941548 + outer loop + vertex 1.21895 2.14179 2.50433 + vertex 1.22168 2.1459 2.50257 + vertex 1.2169 2.14599 2.5036 + endloop + endfacet + facet normal 0.199171 0.340795 0.918798 + outer loop + vertex 1.21342 2.14811 2.50372 + vertex 1.21683 2.14994 2.5023 + vertex 1.21126 2.152 2.50274 + endloop + endfacet + facet normal 0.216832 0.282834 0.934339 + outer loop + vertex 1.20406 2.14839 2.50573 + vertex 1.20603 2.14536 2.50619 + vertex 1.20855 2.14835 2.5047 + endloop + endfacet + facet normal 0.207328 0.277227 0.938169 + outer loop + vertex 1.20603 2.14536 2.50619 + vertex 1.20406 2.14839 2.50573 + vertex 1.20146 2.14545 2.50718 + endloop + endfacet + facet normal 0.213147 0.252045 0.94395 + outer loop + vertex 1.1986 2.14264 2.50857 + vertex 1.20146 2.14545 2.50718 + vertex 1.19677 2.14576 2.50815 + endloop + endfacet + facet normal 0.210912 0.250841 0.944772 + outer loop + vertex 1.1986 2.14264 2.50857 + vertex 1.19677 2.14576 2.50815 + vertex 1.19376 2.14307 2.50954 + endloop + endfacet + facet normal 0.215859 0.274188 0.937137 + outer loop + vertex 1.189 2.1434 2.51054 + vertex 1.19376 2.14307 2.50954 + vertex 1.18839 2.14793 2.50935 + endloop + endfacet + facet normal 0.196954 0.321545 0.926185 + outer loop + vertex 1.19338 2.14767 2.50835 + vertex 1.19666 2.14965 2.50696 + vertex 1.19159 2.15138 2.50744 + endloop + endfacet + facet normal 0.226269 0.278286 0.933466 + outer loop + vertex 1.18378 2.14764 2.51056 + vertex 1.18581 2.14488 2.51089 + vertex 1.18839 2.14793 2.50935 + endloop + endfacet + facet normal 0.195969 0.274448 0.941422 + outer loop + vertex 1.18378 2.14764 2.51056 + vertex 1.17983 2.14907 2.51097 + vertex 1.18166 2.14448 2.51192 + endloop + endfacet + facet normal 0.21489 0.280744 0.935417 + outer loop + vertex 1.18166 2.14448 2.51192 + vertex 1.17983 2.14907 2.51097 + vertex 1.17619 2.14657 2.51255 + endloop + endfacet + facet normal 0.209165 0.255729 0.94385 + outer loop + vertex 1.17382 2.14347 2.51392 + vertex 1.17619 2.14657 2.51255 + vertex 1.17197 2.1463 2.51356 + endloop + endfacet + facet normal 0.191575 0.267303 0.944377 + outer loop + vertex 1.16904 2.1435 2.51494 + vertex 1.17197 2.1463 2.51356 + vertex 1.16864 2.14791 2.51378 + endloop + endfacet + facet normal 0.225813 0.235003 0.9454 + outer loop + vertex 1.16438 2.14373 2.516 + vertex 1.16629 2.14052 2.51634 + vertex 1.16904 2.1435 2.51494 + endloop + endfacet + facet normal 0.242458 0.244178 0.938931 + outer loop + vertex 1.16629 2.14052 2.51634 + vertex 1.16438 2.14373 2.516 + vertex 1.16173 2.14082 2.51744 + endloop + endfacet + facet normal 0.255076 0.288695 0.922817 + outer loop + vertex 1.16118 2.14541 2.51642 + vertex 1.15916 2.14821 2.5161 + vertex 1.15707 2.14538 2.51757 + endloop + endfacet + facet normal 0.267632 0.205372 0.941379 + outer loop + vertex 1.15904 2.1379 2.51884 + vertex 1.16173 2.14082 2.51744 + vertex 1.1571 2.1412 2.51868 + endloop + endfacet + facet normal 0.258853 0.193659 0.946304 + outer loop + vertex 1.15487 2.13379 2.52094 + vertex 1.15933 2.13323 2.51983 + vertex 1.15503 2.13794 2.52004 + endloop + endfacet + facet normal 0.259242 0.199401 0.945004 + outer loop + vertex 1.15487 2.13379 2.52094 + vertex 1.15639 2.1305 2.52121 + vertex 1.15933 2.13323 2.51983 + endloop + endfacet + facet normal 0.284449 0.210239 0.935355 + outer loop + vertex 1.15639 2.1305 2.52121 + vertex 1.15487 2.13379 2.52094 + vertex 1.15191 2.13113 2.52244 + endloop + endfacet + facet normal 0.255951 0.216514 0.942131 + outer loop + vertex 1.16212 2.1361 2.51842 + vertex 1.16173 2.14082 2.51744 + vertex 1.15904 2.1379 2.51884 + endloop + endfacet + facet normal 0.22541 0.225609 0.947782 + outer loop + vertex 1.16384 2.13287 2.51878 + vertex 1.16663 2.13591 2.51739 + vertex 1.16212 2.1361 2.51842 + endloop + endfacet + facet normal 0.217389 0.242998 0.945354 + outer loop + vertex 1.1641 2.12837 2.51988 + vertex 1.16693 2.13131 2.51847 + vertex 1.16384 2.13287 2.51878 + endloop + endfacet + facet normal 0.215474 0.238995 0.946812 + outer loop + vertex 1.15951 2.12859 2.52087 + vertex 1.16125 2.12539 2.52128 + vertex 1.1641 2.12837 2.51988 + endloop + endfacet + facet normal 0.22624 0.244363 0.942922 + outer loop + vertex 1.16125 2.12539 2.52128 + vertex 1.15951 2.12859 2.52087 + vertex 1.15664 2.12576 2.52229 + endloop + endfacet + facet normal 0.220048 0.230224 0.947932 + outer loop + vertex 1.15699 2.12099 2.52336 + vertex 1.15664 2.12576 2.52229 + vertex 1.15386 2.12272 2.52367 + endloop + endfacet + facet normal 0.225139 0.240104 0.944279 + outer loop + vertex 1.15421 2.1181 2.52476 + vertex 1.15699 2.12099 2.52336 + vertex 1.15386 2.12272 2.52367 + endloop + endfacet + facet normal 0.204455 0.248096 0.946914 + outer loop + vertex 1.15448 2.11356 2.52589 + vertex 1.15912 2.11343 2.52493 + vertex 1.15421 2.1181 2.52476 + endloop + endfacet + facet normal 0.213823 0.259792 0.941694 + outer loop + vertex 1.15628 2.11046 2.52634 + vertex 1.15448 2.11356 2.52589 + vertex 1.15159 2.11074 2.52733 + endloop + endfacet + facet normal 0.261124 0.247966 0.932913 + outer loop + vertex 1.15126 2.11535 2.52617 + vertex 1.14966 2.11853 2.52577 + vertex 1.14672 2.1159 2.52729 + endloop + endfacet + facet normal 0.232427 0.232799 0.944342 + outer loop + vertex 1.14883 2.10777 2.52874 + vertex 1.15159 2.11074 2.52733 + vertex 1.14685 2.11108 2.52841 + endloop + endfacet + facet normal 0.21652 0.241512 0.945934 + outer loop + vertex 1.14921 2.10321 2.52982 + vertex 1.152 2.10609 2.52844 + vertex 1.14883 2.10777 2.52874 + endloop + endfacet + facet normal 0.211279 0.236412 0.948404 + outer loop + vertex 1.14921 2.10321 2.52982 + vertex 1.15424 2.09834 2.52991 + vertex 1.15383 2.10293 2.52886 + endloop + endfacet + facet normal 0.211166 0.230563 0.949868 + outer loop + vertex 1.15131 2.09541 2.53125 + vertex 1.14948 2.09865 2.53087 + vertex 1.14656 2.0958 2.53221 + endloop + endfacet + facet normal 0.20224 0.229568 0.952049 + outer loop + vertex 1.15463 2.09366 2.53096 + vertex 1.15936 2.09365 2.52996 + vertex 1.15424 2.09834 2.52991 + endloop + endfacet + facet normal 0.211047 0.22702 0.950747 + outer loop + vertex 1.15131 2.09541 2.53125 + vertex 1.14656 2.0958 2.53221 + vertex 1.15167 2.09072 2.53229 + endloop + endfacet + facet normal 0.199778 0.215754 0.955792 + outer loop + vertex 1.14656 2.0958 2.53221 + vertex 1.14692 2.09104 2.53321 + vertex 1.15167 2.09072 2.53229 + endloop + endfacet + facet normal 0.199993 0.225738 0.953439 + outer loop + vertex 1.14874 2.08777 2.5336 + vertex 1.15167 2.09072 2.53229 + vertex 1.14692 2.09104 2.53321 + endloop + endfacet + facet normal 0.207011 0.229369 0.951071 + outer loop + vertex 1.14874 2.08777 2.5336 + vertex 1.14692 2.09104 2.53321 + vertex 1.14406 2.0881 2.53454 + endloop + endfacet + facet normal 0.202232 0.229737 0.95201 + outer loop + vertex 1.15463 2.09366 2.53096 + vertex 1.15642 2.09052 2.53134 + vertex 1.15936 2.09365 2.52996 + endloop + endfacet + facet normal 0.2029 0.234384 0.950734 + outer loop + vertex 1.15936 2.09365 2.52996 + vertex 1.16383 2.0894 2.53005 + vertex 1.16409 2.09348 2.52899 + endloop + endfacet + facet normal 0.194717 0.238568 0.951404 + outer loop + vertex 1.16383 2.0894 2.53005 + vertex 1.16528 2.08454 2.53097 + vertex 1.16933 2.08718 2.52948 + endloop + endfacet + facet normal 0.191937 0.245774 0.950134 + outer loop + vertex 1.16681 2.07965 2.53193 + vertex 1.16528 2.08454 2.53097 + vertex 1.16124 2.08184 2.53249 + endloop + endfacet + facet normal 0.199468 0.23525 0.951246 + outer loop + vertex 1.16134 2.0861 2.53138 + vertex 1.15956 2.08904 2.53103 + vertex 1.15667 2.08597 2.53239 + endloop + endfacet + facet normal 0.195653 0.241263 0.950533 + outer loop + vertex 1.15878 2.07851 2.53384 + vertex 1.16124 2.08184 2.53249 + vertex 1.15697 2.08142 2.53347 + endloop + endfacet + facet normal 0.1966 0.241812 0.950198 + outer loop + vertex 1.15878 2.07851 2.53384 + vertex 1.15697 2.08142 2.53347 + vertex 1.15409 2.07842 2.53483 + endloop + endfacet + facet normal 0.195453 0.243242 0.950069 + outer loop + vertex 1.14942 2.07852 2.53576 + vertex 1.15123 2.07542 2.53619 + vertex 1.15409 2.07842 2.53483 + endloop + endfacet + facet normal 0.194638 0.242805 0.950348 + outer loop + vertex 1.15123 2.07542 2.53619 + vertex 1.14942 2.07852 2.53576 + vertex 1.14649 2.07562 2.53711 + endloop + endfacet + facet normal 0.204656 0.241011 0.948699 + outer loop + vertex 1.1461 2.08025 2.53601 + vertex 1.14427 2.08348 2.53558 + vertex 1.14126 2.08053 2.53698 + endloop + endfacet + facet normal 0.205608 0.231389 0.950886 + outer loop + vertex 1.14171 2.07563 2.53807 + vertex 1.14126 2.08053 2.53698 + vertex 1.13772 2.07704 2.53859 + endloop + endfacet + facet normal 0.205758 0.231869 0.950737 + outer loop + vertex 1.13945 2.07216 2.53941 + vertex 1.14171 2.07563 2.53807 + vertex 1.13772 2.07704 2.53859 + endloop + endfacet + facet normal 0.213814 0.234333 0.948352 + outer loop + vertex 1.13945 2.07216 2.53941 + vertex 1.13772 2.07704 2.53859 + vertex 1.13459 2.07397 2.54006 + endloop + endfacet + facet normal 0.191195 0.242155 0.951212 + outer loop + vertex 1.14688 2.07103 2.5382 + vertex 1.14649 2.07562 2.53711 + vertex 1.1437 2.07255 2.53845 + endloop + endfacet + facet normal 0.189722 0.238873 0.952337 + outer loop + vertex 1.144 2.06801 2.53953 + vertex 1.14688 2.07103 2.5382 + vertex 1.1437 2.07255 2.53845 + endloop + endfacet + facet normal 0.188844 0.232703 0.954037 + outer loop + vertex 1.13927 2.06796 2.54048 + vertex 1.14103 2.06499 2.54085 + vertex 1.144 2.06801 2.53953 + endloop + endfacet + facet normal 0.197774 0.224996 0.954077 + outer loop + vertex 1.13927 2.06796 2.54048 + vertex 1.13547 2.06952 2.5409 + vertex 1.13672 2.06466 2.54178 + endloop + endfacet + facet normal 0.282839 0.205434 0.936909 + outer loop + vertex 1.13033 2.07502 2.541 + vertex 1.12756 2.07106 2.54271 + vertex 1.13179 2.07127 2.54138 + endloop + endfacet + facet normal 0.319 0.177655 0.930955 + outer loop + vertex 1.12605 2.07664 2.54216 + vertex 1.12756 2.07106 2.54271 + vertex 1.13033 2.07502 2.541 + endloop + endfacet + facet normal 0.324976 0.197934 0.924777 + outer loop + vertex 1.13033 2.07502 2.541 + vertex 1.12921 2.07872 2.5406 + vertex 1.12605 2.07664 2.54216 + endloop + endfacet + facet normal 0.292166 0.189341 0.937437 + outer loop + vertex 1.12921 2.07872 2.5406 + vertex 1.13033 2.07502 2.541 + vertex 1.13308 2.07875 2.53939 + endloop + endfacet + facet normal 0.293014 0.175827 0.939802 + outer loop + vertex 1.12921 2.07872 2.5406 + vertex 1.13308 2.07875 2.53939 + vertex 1.12994 2.08275 2.53962 + endloop + endfacet + facet normal 0.313672 0.19263 0.929787 + outer loop + vertex 1.12994 2.08275 2.53962 + vertex 1.13308 2.07875 2.53939 + vertex 1.13362 2.08284 2.53836 + endloop + endfacet + facet normal 0.314998 0.176514 0.932534 + outer loop + vertex 1.13362 2.08284 2.53836 + vertex 1.13226 2.08595 2.53823 + vertex 1.12994 2.08275 2.53962 + endloop + endfacet + facet normal 0.218027 0.229209 0.948645 + outer loop + vertex 1.13672 2.06466 2.54178 + vertex 1.13547 2.06952 2.5409 + vertex 1.13142 2.0669 2.54246 + endloop + endfacet + facet normal 0.183385 0.219985 0.958111 + outer loop + vertex 1.13672 2.06466 2.54178 + vertex 1.13643 2.06047 2.5428 + vertex 1.14122 2.0603 2.54192 + endloop + endfacet + facet normal 0.189482 0.222753 0.956283 + outer loop + vertex 1.13776 2.05693 2.54336 + vertex 1.13643 2.06047 2.5428 + vertex 1.13405 2.05829 2.54378 + endloop + endfacet + facet normal 0.188903 0.221018 0.9568 + outer loop + vertex 1.13435 2.05355 2.54481 + vertex 1.13776 2.05693 2.54336 + vertex 1.13405 2.05829 2.54378 + endloop + endfacet + facet normal 0.185899 0.221322 0.957318 + outer loop + vertex 1.13435 2.05355 2.54481 + vertex 1.13955 2.04859 2.54495 + vertex 1.13923 2.05331 2.54392 + endloop + endfacet + facet normal 0.186993 0.220216 0.95736 + outer loop + vertex 1.13978 2.04386 2.54599 + vertex 1.14455 2.04379 2.54508 + vertex 1.13955 2.04859 2.54495 + endloop + endfacet + facet normal 0.188307 0.216735 0.957897 + outer loop + vertex 1.1415 2.04073 2.54636 + vertex 1.13978 2.04386 2.54599 + vertex 1.13673 2.04082 2.54728 + endloop + endfacet + facet normal 0.191365 0.225769 0.955201 + outer loop + vertex 1.13644 2.04552 2.54626 + vertex 1.13459 2.04874 2.54587 + vertex 1.13149 2.04567 2.54722 + endloop + endfacet + facet normal 0.195074 0.218238 0.9562 + outer loop + vertex 1.13195 2.04075 2.54825 + vertex 1.13149 2.04567 2.54722 + vertex 1.12792 2.04212 2.54876 + endloop + endfacet + facet normal 0.191586 0.216367 0.95733 + outer loop + vertex 1.13701 2.03619 2.54827 + vertex 1.13673 2.04082 2.54728 + vertex 1.13387 2.03768 2.54856 + endloop + endfacet + facet normal 0.190543 0.214034 0.958062 + outer loop + vertex 1.13406 2.03311 2.54955 + vertex 1.13701 2.03619 2.54827 + vertex 1.13387 2.03768 2.54856 + endloop + endfacet + facet normal 0.187818 0.213627 0.958691 + outer loop + vertex 1.12935 2.03305 2.55048 + vertex 1.13104 2.03009 2.55081 + vertex 1.13406 2.03311 2.54955 + endloop + endfacet + facet normal 0.1825 0.207429 0.961076 + outer loop + vertex 1.12935 2.03305 2.55048 + vertex 1.12558 2.03454 2.55088 + vertex 1.12673 2.02965 2.55171 + endloop + endfacet + facet normal 0.183207 0.207566 0.960912 + outer loop + vertex 1.12673 2.02965 2.55171 + vertex 1.12558 2.03454 2.55088 + vertex 1.12131 2.03165 2.55232 + endloop + endfacet + facet normal 0.190735 0.196796 0.961713 + outer loop + vertex 1.12194 2.03617 2.55127 + vertex 1.12131 2.03165 2.55232 + vertex 1.12558 2.03454 2.55088 + endloop + endfacet + facet normal 0.216964 0.192046 0.957102 + outer loop + vertex 1.12194 2.03617 2.55127 + vertex 1.11766 2.03573 2.55233 + vertex 1.12131 2.03165 2.55232 + endloop + endfacet + facet normal 0.193774 0.204107 0.959579 + outer loop + vertex 1.12558 2.03454 2.55088 + vertex 1.12476 2.03899 2.5501 + vertex 1.12194 2.03617 2.55127 + endloop + endfacet + facet normal 0.21134 0.186503 0.959454 + outer loop + vertex 1.12194 2.03617 2.55127 + vertex 1.12476 2.03899 2.5501 + vertex 1.12037 2.03992 2.55088 + endloop + endfacet + facet normal 0.193695 0.213698 0.957505 + outer loop + vertex 1.12963 2.03725 2.5495 + vertex 1.13195 2.04075 2.54825 + vertex 1.12792 2.04212 2.54876 + endloop + endfacet + facet normal 0.202025 0.211312 0.956312 + outer loop + vertex 1.12792 2.04212 2.54876 + vertex 1.13149 2.04567 2.54722 + vertex 1.1265 2.04608 2.54818 + endloop + endfacet + facet normal 0.201813 0.205955 0.957525 + outer loop + vertex 1.12647 2.05083 2.54716 + vertex 1.1265 2.04608 2.54818 + vertex 1.13149 2.04567 2.54722 + endloop + endfacet + facet normal 0.302834 0.163736 0.938873 + outer loop + vertex 1.11608 2.04563 2.55098 + vertex 1.11488 2.04876 2.55082 + vertex 1.11182 2.04615 2.55226 + endloop + endfacet + facet normal 0.237958 0.176079 0.955182 + outer loop + vertex 1.11889 2.04376 2.55052 + vertex 1.12303 2.04386 2.54947 + vertex 1.11908 2.04837 2.54962 + endloop + endfacet + facet normal 0.302932 0.165304 0.938566 + outer loop + vertex 1.11608 2.04563 2.55098 + vertex 1.11182 2.04615 2.55226 + vertex 1.11567 2.0413 2.55188 + endloop + endfacet + facet normal 0.237521 0.182447 0.954095 + outer loop + vertex 1.11889 2.04376 2.55052 + vertex 1.12037 2.03992 2.55088 + vertex 1.12303 2.04386 2.54947 + endloop + endfacet + facet normal 0.217422 0.188859 0.957633 + outer loop + vertex 1.12037 2.03992 2.55088 + vertex 1.11766 2.03573 2.55233 + vertex 1.12194 2.03617 2.55127 + endloop + endfacet + facet normal 0.199229 0.176134 0.963994 + outer loop + vertex 1.11766 2.03573 2.55233 + vertex 1.11688 2.03129 2.5533 + vertex 1.12131 2.03165 2.55232 + endloop + endfacet + facet normal 0.179789 0.197477 0.96368 + outer loop + vertex 1.12263 2.02666 2.55309 + vertex 1.12673 2.02965 2.55171 + vertex 1.12131 2.03165 2.55232 + endloop + endfacet + facet normal 0.171137 0.203053 0.964096 + outer loop + vertex 1.12406 2.02301 2.55361 + vertex 1.12641 2.02542 2.55268 + vertex 1.12263 2.02666 2.55309 + endloop + endfacet + facet normal 0.164383 0.193581 0.967215 + outer loop + vertex 1.1193 2.01801 2.55544 + vertex 1.12421 2.0183 2.55455 + vertex 1.11967 2.02244 2.55449 + endloop + endfacet + facet normal 0.171244 0.20295 0.964099 + outer loop + vertex 1.12769 2.02193 2.55319 + vertex 1.12641 2.02542 2.55268 + vertex 1.12406 2.02301 2.55361 + endloop + endfacet + facet normal 0.180213 0.199252 0.963235 + outer loop + vertex 1.12903 2.01832 2.55368 + vertex 1.13138 2.02067 2.55276 + vertex 1.12769 2.02193 2.55319 + endloop + endfacet + facet normal 0.184113 0.189946 0.964377 + outer loop + vertex 1.1292 2.01354 2.55459 + vertex 1.13275 2.01699 2.55324 + vertex 1.12903 2.01832 2.55368 + endloop + endfacet + facet normal 0.1758 0.191544 0.965611 + outer loop + vertex 1.12425 2.01357 2.55549 + vertex 1.12597 2.01036 2.55581 + vertex 1.1292 2.01354 2.55459 + endloop + endfacet + facet normal 0.16236 0.184732 0.969285 + outer loop + vertex 1.12597 2.01036 2.55581 + vertex 1.12425 2.01357 2.55549 + vertex 1.1211 2.01015 2.55667 + endloop + endfacet + facet normal 0.155151 0.178755 0.971584 + outer loop + vertex 1.11663 2.01448 2.55659 + vertex 1.11618 2.01003 2.55748 + vertex 1.1211 2.01015 2.55667 + endloop + endfacet + facet normal 0.164257 0.194936 0.966964 + outer loop + vertex 1.1193 2.01801 2.55544 + vertex 1.12103 2.01501 2.55575 + vertex 1.12421 2.0183 2.55455 + endloop + endfacet + facet normal 0.17425 0.19245 0.965712 + outer loop + vertex 1.11545 2.01948 2.55584 + vertex 1.1193 2.01801 2.55544 + vertex 1.11967 2.02244 2.55449 + endloop + endfacet + facet normal 0.170871 0.176725 0.969315 + outer loop + vertex 1.11618 2.01003 2.55748 + vertex 1.11663 2.01448 2.55659 + vertex 1.11248 2.01159 2.55785 + endloop + endfacet + facet normal 0.205721 0.152735 0.966618 + outer loop + vertex 1.10971 2.00858 2.55891 + vertex 1.11248 2.01159 2.55785 + vertex 1.10821 2.01245 2.55862 + endloop + endfacet + facet normal 0.20153 0.150616 0.967833 + outer loop + vertex 1.10482 2.00369 2.56081 + vertex 1.10963 2.00359 2.55982 + vertex 1.10549 2.00816 2.55997 + endloop + endfacet + facet normal 0.201454 0.156465 0.96692 + outer loop + vertex 1.10482 2.00369 2.56081 + vertex 1.10622 2.00039 2.56105 + vertex 1.10963 2.00359 2.55982 + endloop + endfacet + facet normal 0.2324 0.168964 0.957832 + outer loop + vertex 1.10622 2.00039 2.56105 + vertex 1.10482 2.00369 2.56081 + vertex 1.10157 2.00063 2.56214 + endloop + endfacet + facet normal 0.18323 0.173815 0.967582 + outer loop + vertex 1.11329 2.00728 2.55847 + vertex 1.11248 2.01159 2.55785 + vertex 1.10971 2.00858 2.55891 + endloop + endfacet + facet normal 0.157062 0.181384 0.970789 + outer loop + vertex 1.1146 2.00362 2.55894 + vertex 1.11747 2.00644 2.55795 + vertex 1.11329 2.00728 2.55847 + endloop + endfacet + facet normal 0.151964 0.187875 0.970366 + outer loop + vertex 1.11447 1.9988 2.55989 + vertex 1.11833 2.00236 2.5586 + vertex 1.1146 2.00362 2.55894 + endloop + endfacet + facet normal 0.178508 0.193623 0.964699 + outer loop + vertex 1.11114 1.99545 2.56107 + vertex 1.10945 1.99868 2.56073 + vertex 1.10629 1.99549 2.56196 + endloop + endfacet + facet normal 0.161066 0.192535 0.967982 + outer loop + vertex 1.10794 1.98694 2.56332 + vertex 1.1113 1.99067 2.56202 + vertex 1.10656 1.99062 2.56282 + endloop + endfacet + facet normal 0.178626 0.198555 0.963675 + outer loop + vertex 1.10794 1.98694 2.56332 + vertex 1.10656 1.99062 2.56282 + vertex 1.10426 1.98828 2.56373 + endloop + endfacet + facet normal 0.17879 0.199046 0.963543 + outer loop + vertex 1.10445 1.98351 2.56468 + vertex 1.10794 1.98694 2.56332 + vertex 1.10426 1.98828 2.56373 + endloop + endfacet + facet normal 0.192788 0.178531 0.964862 + outer loop + vertex 1.09952 1.98379 2.56561 + vertex 1.10124 1.98041 2.56589 + vertex 1.10445 1.98351 2.56468 + endloop + endfacet + facet normal 0.18094 0.190775 0.964814 + outer loop + vertex 1.10456 1.97865 2.56562 + vertex 1.10445 1.98351 2.56468 + vertex 1.10124 1.98041 2.56589 + endloop + endfacet + facet normal 0.179329 0.187607 0.965735 + outer loop + vertex 1.10124 1.98041 2.56589 + vertex 1.10138 1.9755 2.56682 + vertex 1.10456 1.97865 2.56562 + endloop + endfacet + facet normal 0.21129 0.187275 0.959315 + outer loop + vertex 1.10124 1.98041 2.56589 + vertex 1.09643 1.98068 2.5669 + vertex 1.10138 1.9755 2.56682 + endloop + endfacet + facet normal 0.211294 0.187539 0.959262 + outer loop + vertex 1.10124 1.98041 2.56589 + vertex 1.09952 1.98379 2.56561 + vertex 1.09643 1.98068 2.5669 + endloop + endfacet + facet normal 0.245489 0.174658 0.953535 + outer loop + vertex 1.09626 1.98566 2.56602 + vertex 1.0946 1.98898 2.56583 + vertex 1.0916 1.98599 2.56715 + endloop + endfacet + facet normal 0.247731 0.163678 0.954902 + outer loop + vertex 1.09158 1.98113 2.56799 + vertex 1.0916 1.98599 2.56715 + vertex 1.08851 1.98312 2.56845 + endloop + endfacet + facet normal 0.22323 0.166906 0.96037 + outer loop + vertex 1.09665 1.97574 2.56771 + vertex 1.09643 1.98068 2.5669 + vertex 1.09297 1.97712 2.56832 + endloop + endfacet + facet normal 0.231206 0.162389 0.959257 + outer loop + vertex 1.09431 1.9734 2.56863 + vertex 1.09297 1.97712 2.56832 + vertex 1.09014 1.97315 2.56968 + endloop + endfacet + facet normal 0.230846 0.166126 0.958703 + outer loop + vertex 1.09014 1.97315 2.56968 + vertex 1.09363 1.96913 2.56953 + vertex 1.09431 1.9734 2.56863 + endloop + endfacet + facet normal 0.227793 0.159874 0.960495 + outer loop + vertex 1.0905 1.96503 2.57094 + vertex 1.08938 1.96877 2.57058 + vertex 1.08588 1.96614 2.57185 + endloop + endfacet + facet normal 0.199753 0.180913 0.963 + outer loop + vertex 1.09839 1.96752 2.56885 + vertex 1.09769 1.97197 2.56816 + vertex 1.09363 1.96913 2.56953 + endloop + endfacet + facet normal 0.165989 0.183662 0.968874 + outer loop + vertex 1.09988 1.96254 2.56954 + vertex 1.10287 1.96667 2.56824 + vertex 1.09839 1.96752 2.56885 + endloop + endfacet + facet normal 0.168632 0.184565 0.968245 + outer loop + vertex 1.09553 1.95962 2.57085 + vertex 1.09938 1.9581 2.57047 + vertex 1.09988 1.96254 2.56954 + endloop + endfacet + facet normal 0.181804 0.186317 0.965522 + outer loop + vertex 1.09666 1.95458 2.57161 + vertex 1.09553 1.95962 2.57085 + vertex 1.09119 1.95667 2.57224 + endloop + endfacet + facet normal 0.213718 0.164333 0.962974 + outer loop + vertex 1.0905 1.96503 2.57094 + vertex 1.08753 1.96075 2.57232 + vertex 1.09185 1.96126 2.57128 + endloop + endfacet + facet normal 0.200163 0.159988 0.966612 + outer loop + vertex 1.08799 1.95247 2.5736 + vertex 1.09119 1.95667 2.57224 + vertex 1.08669 1.95629 2.57323 + endloop + endfacet + facet normal 0.209871 0.151071 0.965987 + outer loop + vertex 1.0802 1.94958 2.57568 + vertex 1.07741 1.94534 2.57695 + vertex 1.08178 1.94551 2.57598 + endloop + endfacet + facet normal 0.236054 0.129475 0.963076 + outer loop + vertex 1.07349 1.94232 2.57832 + vertex 1.07741 1.94534 2.57695 + vertex 1.07259 1.94704 2.5779 + endloop + endfacet + facet normal 0.227779 0.140387 0.963539 + outer loop + vertex 1.07689 1.94084 2.57773 + vertex 1.07741 1.94534 2.57695 + vertex 1.07349 1.94232 2.57832 + endloop + endfacet + facet normal 0.197036 0.147657 0.969213 + outer loop + vertex 1.07764 1.93708 2.57815 + vertex 1.08153 1.94057 2.57683 + vertex 1.07689 1.94084 2.57773 + endloop + endfacet + facet normal 0.18899 0.154893 0.969686 + outer loop + vertex 1.07834 1.93257 2.57873 + vertex 1.0813 1.93553 2.57769 + vertex 1.07764 1.93708 2.57815 + endloop + endfacet + facet normal 0.188034 0.163155 0.968516 + outer loop + vertex 1.07986 1.92869 2.57909 + vertex 1.07834 1.93257 2.57873 + vertex 1.07538 1.92834 2.58002 + endloop + endfacet + facet normal 0.243096 0.148382 0.958586 + outer loop + vertex 1.07042 1.92985 2.5809 + vertex 1.06764 1.92565 2.58226 + vertex 1.07184 1.92572 2.58118 + endloop + endfacet + facet normal 0.270959 0.133887 0.953234 + outer loop + vertex 1.06697 1.92119 2.58308 + vertex 1.06764 1.92565 2.58226 + vertex 1.06428 1.92327 2.58355 + endloop + endfacet + facet normal 0.273384 0.137283 0.952058 + outer loop + vertex 1.06352 1.91894 2.58439 + vertex 1.06697 1.92119 2.58308 + vertex 1.06428 1.92327 2.58355 + endloop + endfacet + facet normal 0.265915 0.148957 0.952419 + outer loop + vertex 1.06803 1.9173 2.58339 + vertex 1.06697 1.92119 2.58308 + vertex 1.06352 1.91894 2.58439 + endloop + endfacet + facet normal 0.214145 0.140525 0.966641 + outer loop + vertex 1.06928 1.91356 2.58365 + vertex 1.07169 1.91592 2.58278 + vertex 1.06803 1.9173 2.58339 + endloop + endfacet + facet normal 0.220765 0.134044 0.966072 + outer loop + vertex 1.06432 1.90894 2.58549 + vertex 1.06868 1.90911 2.58447 + vertex 1.06511 1.91338 2.58469 + endloop + endfacet + facet normal 0.201506 0.153677 0.967356 + outer loop + vertex 1.07275 1.9121 2.58316 + vertex 1.07169 1.91592 2.58278 + vertex 1.06928 1.91356 2.58365 + endloop + endfacet + facet normal 0.17552 0.153491 0.972437 + outer loop + vertex 1.07354 1.90759 2.58373 + vertex 1.07649 1.91062 2.58272 + vertex 1.07275 1.9121 2.58316 + endloop + endfacet + facet normal 0.166076 0.155851 0.973719 + outer loop + vertex 1.07498 1.90373 2.5841 + vertex 1.0778 1.9068 2.58313 + vertex 1.07354 1.90759 2.58373 + endloop + endfacet + facet normal 0.15454 0.166518 0.973853 + outer loop + vertex 1.0786 1.90254 2.58373 + vertex 1.0778 1.9068 2.58313 + vertex 1.07498 1.90373 2.5841 + endloop + endfacet + facet normal 0.154471 0.166294 0.973902 + outer loop + vertex 1.07479 1.89881 2.58497 + vertex 1.0786 1.90254 2.58373 + vertex 1.07498 1.90373 2.5841 + endloop + endfacet + facet normal 0.14809 0.172753 0.973769 + outer loop + vertex 1.07983 1.89886 2.5842 + vertex 1.0786 1.90254 2.58373 + vertex 1.07479 1.89881 2.58497 + endloop + endfacet + facet normal 0.14828 0.167491 0.974659 + outer loop + vertex 1.07479 1.89881 2.58497 + vertex 1.07958 1.89402 2.58507 + vertex 1.07983 1.89886 2.5842 + endloop + endfacet + facet normal 0.158313 0.163083 0.973828 + outer loop + vertex 1.07627 1.89076 2.58606 + vertex 1.07461 1.89397 2.58579 + vertex 1.0714 1.89068 2.58686 + endloop + endfacet + facet normal 0.169992 0.148129 0.974249 + outer loop + vertex 1.07146 1.88552 2.58764 + vertex 1.0714 1.89068 2.58686 + vertex 1.06774 1.8868 2.58809 + endloop + endfacet + facet normal 0.120475 0.153792 0.980731 + outer loop + vertex 1.07636 1.88587 2.58685 + vertex 1.07639 1.88072 2.58765 + vertex 1.08108 1.88167 2.58693 + endloop + endfacet + facet normal 0.12963 0.161868 0.978261 + outer loop + vertex 1.07783 1.87703 2.58807 + vertex 1.07639 1.88072 2.58765 + vertex 1.07343 1.87746 2.58858 + endloop + endfacet + facet normal 0.142352 0.16136 0.976575 + outer loop + vertex 1.07464 1.87371 2.58903 + vertex 1.07343 1.87746 2.58858 + vertex 1.06942 1.87367 2.58979 + endloop + endfacet + facet normal 0.158949 0.145631 0.976487 + outer loop + vertex 1.06969 1.87868 2.58896 + vertex 1.07272 1.88173 2.58802 + vertex 1.06854 1.88247 2.58859 + endloop + endfacet + facet normal 0.168115 0.14224 0.975451 + outer loop + vertex 1.06854 1.88247 2.58859 + vertex 1.07146 1.88552 2.58764 + vertex 1.06774 1.8868 2.58809 + endloop + endfacet + facet normal 0.177568 0.140912 0.973968 + outer loop + vertex 1.06774 1.8868 2.58809 + vertex 1.0714 1.89068 2.58686 + vertex 1.06642 1.89065 2.58778 + endloop + endfacet + facet normal 0.199531 0.138951 0.96999 + outer loop + vertex 1.06491 1.88377 2.58906 + vertex 1.06345 1.88766 2.5888 + vertex 1.06045 1.88349 2.59002 + endloop + endfacet + facet normal 0.199474 0.139594 0.969909 + outer loop + vertex 1.06045 1.88349 2.59002 + vertex 1.06467 1.87876 2.58983 + vertex 1.06491 1.88377 2.58906 + endloop + endfacet + facet normal 0.188421 0.129606 0.973499 + outer loop + vertex 1.05987 1.87899 2.59073 + vertex 1.06467 1.87876 2.58983 + vertex 1.06045 1.88349 2.59002 + endloop + endfacet + facet normal 0.188472 0.131771 0.973198 + outer loop + vertex 1.05987 1.87899 2.59073 + vertex 1.06128 1.87569 2.5909 + vertex 1.06467 1.87876 2.58983 + endloop + endfacet + facet normal 0.181633 0.139423 0.973432 + outer loop + vertex 1.06441 1.87386 2.59058 + vertex 1.06467 1.87876 2.58983 + vertex 1.06128 1.87569 2.5909 + endloop + endfacet + facet normal 0.184728 0.144965 0.972039 + outer loop + vertex 1.06128 1.87569 2.5909 + vertex 1.06131 1.87071 2.59164 + vertex 1.06441 1.87386 2.59058 + endloop + endfacet + facet normal 0.2221 0.144035 0.964327 + outer loop + vertex 1.06128 1.87569 2.5909 + vertex 1.05677 1.87596 2.5919 + vertex 1.06131 1.87071 2.59164 + endloop + endfacet + facet normal 0.222143 0.145681 0.964069 + outer loop + vertex 1.06128 1.87569 2.5909 + vertex 1.05987 1.87899 2.59073 + vertex 1.05677 1.87596 2.5919 + endloop + endfacet + facet normal 0.298146 0.123154 0.946542 + outer loop + vertex 1.05566 1.8853 2.59101 + vertex 1.05286 1.88122 2.59242 + vertex 1.05697 1.88103 2.59116 + endloop + endfacet + facet normal 0.19813 0.122912 0.972439 + outer loop + vertex 1.05677 1.87596 2.5919 + vertex 1.05674 1.87092 2.59254 + vertex 1.06131 1.87071 2.59164 + endloop + endfacet + facet normal 0.198289 0.13111 0.971335 + outer loop + vertex 1.05764 1.86702 2.59289 + vertex 1.06131 1.87071 2.59164 + vertex 1.05674 1.87092 2.59254 + endloop + endfacet + facet normal 0.187177 0.138393 0.972529 + outer loop + vertex 1.0581 1.86242 2.59345 + vertex 1.06127 1.86553 2.5924 + vertex 1.05764 1.86702 2.59289 + endloop + endfacet + facet normal 0.247042 0.107592 0.963013 + outer loop + vertex 1.05103 1.85516 2.596 + vertex 1.05445 1.85872 2.59472 + vertex 1.05004 1.86003 2.59571 + endloop + endfacet + facet normal 0.197351 0.138239 0.970537 + outer loop + vertex 1.05895 1.85782 2.59393 + vertex 1.0581 1.86242 2.59345 + vertex 1.05445 1.85872 2.59472 + endloop + endfacet + facet normal 0.165157 0.13581 0.976872 + outer loop + vertex 1.06012 1.85395 2.59427 + vertex 1.06322 1.85717 2.5933 + vertex 1.05895 1.85782 2.59393 + endloop + endfacet + facet normal 0.155377 0.142746 0.977487 + outer loop + vertex 1.05974 1.84892 2.59507 + vertex 1.06385 1.85284 2.59384 + vertex 1.06012 1.85395 2.59427 + endloop + endfacet + facet normal 0.205654 0.148691 0.967263 + outer loop + vertex 1.05631 1.84586 2.59609 + vertex 1.05488 1.84908 2.5959 + vertex 1.05174 1.84609 2.59703 + endloop + endfacet + facet normal 0.188461 0.123646 0.974266 + outer loop + vertex 1.05288 1.83704 2.59798 + vertex 1.05647 1.8409 2.59679 + vertex 1.05162 1.84093 2.59773 + endloop + endfacet + facet normal 0.193784 0.129434 0.972468 + outer loop + vertex 1.05335 1.83259 2.59848 + vertex 1.05288 1.83704 2.59798 + vertex 1.04988 1.834 2.59898 + endloop + endfacet + facet normal 0.192672 0.126475 0.973078 + outer loop + vertex 1.04874 1.8293 2.59982 + vertex 1.05335 1.83259 2.59848 + vertex 1.04988 1.834 2.59898 + endloop + endfacet + facet normal 0.212043 0.126292 0.969066 + outer loop + vertex 1.04957 1.82262 2.60051 + vertex 1.04874 1.8293 2.59982 + vertex 1.0452 1.82586 2.60104 + endloop + endfacet + facet normal 0.22212 0.140624 0.964825 + outer loop + vertex 1.0452 1.82586 2.60104 + vertex 1.04295 1.82147 2.6022 + vertex 1.04957 1.82262 2.60051 + endloop + endfacet + facet normal 0.228534 0.107829 0.967546 + outer loop + vertex 1.04957 1.82262 2.60051 + vertex 1.04295 1.82147 2.6022 + vertex 1.04708 1.81617 2.60181 + endloop + endfacet + facet normal 0.22148 0.102165 0.969798 + outer loop + vertex 1.04295 1.82147 2.6022 + vertex 1.04201 1.81645 2.60294 + vertex 1.04708 1.81617 2.60181 + endloop + endfacet + facet normal 0.22141 0.0998674 0.970054 + outer loop + vertex 1.04288 1.81233 2.60317 + vertex 1.04708 1.81617 2.60181 + vertex 1.04201 1.81645 2.60294 + endloop + endfacet + facet normal 0.20493 0.108042 0.972795 + outer loop + vertex 1.04357 1.80775 2.60353 + vertex 1.04655 1.81093 2.60255 + vertex 1.04288 1.81233 2.60317 + endloop + endfacet + facet normal 0.18736 0.109926 0.976121 + outer loop + vertex 1.04468 1.80393 2.60375 + vertex 1.04773 1.80702 2.60281 + vertex 1.04357 1.80775 2.60353 + endloop + endfacet + facet normal 0.174028 0.117467 0.977709 + outer loop + vertex 1.04367 1.79915 2.6045 + vertex 1.04824 1.80256 2.60328 + vertex 1.04468 1.80393 2.60375 + endloop + endfacet + facet normal 0.269303 0.117191 0.955899 + outer loop + vertex 1.04022 1.79476 2.60569 + vertex 1.03916 1.79885 2.60549 + vertex 1.0358 1.79638 2.60674 + endloop + endfacet + facet normal 0.259861 0.0876331 0.961661 + outer loop + vertex 1.0358 1.79638 2.60674 + vertex 1.03728 1.79053 2.60687 + vertex 1.04022 1.79476 2.60569 + endloop + endfacet + facet normal 0.233496 0.107277 0.966422 + outer loop + vertex 1.04022 1.79476 2.60569 + vertex 1.03728 1.79053 2.60687 + vertex 1.0413 1.79074 2.60588 + endloop + endfacet + facet normal 0.219856 0.0962184 0.970776 + outer loop + vertex 1.03763 1.78218 2.6076 + vertex 1.04063 1.78631 2.60651 + vertex 1.03673 1.786 2.60743 + endloop + endfacet + facet normal 0.197246 0.113468 0.973765 + outer loop + vertex 1.04245 1.78063 2.60681 + vertex 1.04063 1.78631 2.60651 + vertex 1.03763 1.78218 2.6076 + endloop + endfacet + facet normal 0.193599 0.101029 0.975865 + outer loop + vertex 1.03804 1.77737 2.60802 + vertex 1.04245 1.78063 2.60681 + vertex 1.03763 1.78218 2.6076 + endloop + endfacet + facet normal 0.191756 0.10356 0.975964 + outer loop + vertex 1.04184 1.77587 2.60743 + vertex 1.04245 1.78063 2.60681 + vertex 1.03804 1.77737 2.60802 + endloop + endfacet + facet normal 0.168289 0.118743 0.97856 + outer loop + vertex 1.04326 1.76768 2.60817 + vertex 1.0429 1.7721 2.60769 + vertex 1.0397 1.76897 2.60862 + endloop + endfacet + facet normal 0.191163 0.101951 0.976249 + outer loop + vertex 1.03865 1.77271 2.60839 + vertex 1.04184 1.77587 2.60743 + vertex 1.03804 1.77737 2.60802 + endloop + endfacet + facet normal 0.153632 0.109307 0.982064 + outer loop + vertex 1.04245 1.78063 2.60681 + vertex 1.04184 1.77587 2.60743 + vertex 1.04676 1.77605 2.60664 + endloop + endfacet + facet normal 0.1333 0.114936 0.984389 + outer loop + vertex 1.04676 1.77605 2.60664 + vertex 1.04662 1.77094 2.60726 + vertex 1.05162 1.77116 2.60655 + endloop + endfacet + facet normal 0.133515 0.111349 0.984772 + outer loop + vertex 1.04769 1.76689 2.60757 + vertex 1.05162 1.77116 2.60655 + vertex 1.04662 1.77094 2.60726 + endloop + endfacet + facet normal 0.137535 0.101128 0.985321 + outer loop + vertex 1.04826 1.76216 2.60798 + vertex 1.05169 1.76585 2.60712 + vertex 1.04769 1.76689 2.60757 + endloop + endfacet + facet normal 0.140502 0.0837744 0.98653 + outer loop + vertex 1.04875 1.75755 2.6083 + vertex 1.05285 1.76178 2.60735 + vertex 1.04826 1.76216 2.60798 + endloop + endfacet + facet normal 0.142239 0.0673736 0.987537 + outer loop + vertex 1.04866 1.75285 2.60863 + vertex 1.0533 1.75711 2.60767 + vertex 1.04875 1.75755 2.6083 + endloop + endfacet + facet normal 0.140562 0.0542314 0.988585 + outer loop + vertex 1.04836 1.74786 2.60895 + vertex 1.05345 1.75231 2.60798 + vertex 1.04866 1.75285 2.60863 + endloop + endfacet + facet normal 0.134626 0.0498424 0.989642 + outer loop + vertex 1.04833 1.74273 2.60921 + vertex 1.05337 1.74728 2.6083 + vertex 1.04836 1.74786 2.60895 + endloop + endfacet + facet normal 0.124925 0.0578977 0.990475 + outer loop + vertex 1.04858 1.73775 2.60947 + vertex 1.05324 1.74218 2.60862 + vertex 1.04833 1.74273 2.60921 + endloop + endfacet + facet normal 0.115636 0.0702446 0.990805 + outer loop + vertex 1.04948 1.73366 2.60965 + vertex 1.05324 1.73726 2.60896 + vertex 1.04858 1.73775 2.60947 + endloop + endfacet + facet normal 0.109042 0.0888931 0.990054 + outer loop + vertex 1.04916 1.72872 2.61013 + vertex 1.05339 1.73258 2.60932 + vertex 1.04948 1.73366 2.60965 + endloop + endfacet + facet normal 0.104417 0.0970025 0.989792 + outer loop + vertex 1.04918 1.72407 2.61059 + vertex 1.054 1.72367 2.61012 + vertex 1.04916 1.72872 2.61013 + endloop + endfacet + facet normal 0.121484 0.113874 0.98604 + outer loop + vertex 1.05101 1.72086 2.61073 + vertex 1.04918 1.72407 2.61059 + vertex 1.04639 1.72103 2.61128 + endloop + endfacet + facet normal 0.151189 0.106034 0.982801 + outer loop + vertex 1.04609 1.72592 2.61078 + vertex 1.04458 1.72913 2.61066 + vertex 1.0416 1.72603 2.61146 + endloop + endfacet + facet normal 0.114024 0.104663 0.98795 + outer loop + vertex 1.04639 1.72103 2.61128 + vertex 1.04655 1.7158 2.61182 + vertex 1.05148 1.71606 2.61122 + endloop + endfacet + facet normal 0.128104 0.106854 0.985988 + outer loop + vertex 1.0477 1.71176 2.61211 + vertex 1.04655 1.7158 2.61182 + vertex 1.04312 1.71212 2.61266 + endloop + endfacet + facet normal 0.110066 0.103425 0.988529 + outer loop + vertex 1.04818 1.70707 2.61254 + vertex 1.05169 1.71088 2.61175 + vertex 1.0477 1.71176 2.61211 + endloop + endfacet + facet normal 0.116566 0.103874 0.987736 + outer loop + vertex 1.04839 1.70228 2.61302 + vertex 1.04818 1.70707 2.61254 + vertex 1.04361 1.7026 2.61355 + endloop + endfacet + facet normal 0.11629 0.0988153 0.988287 + outer loop + vertex 1.04351 1.69784 2.61404 + vertex 1.04839 1.70228 2.61302 + vertex 1.04361 1.7026 2.61355 + endloop + endfacet + facet normal 0.11192 0.0978192 0.988891 + outer loop + vertex 1.04364 1.69296 2.61451 + vertex 1.04836 1.69733 2.61354 + vertex 1.04351 1.69784 2.61404 + endloop + endfacet + facet normal 0.115662 0.0972908 0.988512 + outer loop + vertex 1.04464 1.68885 2.6148 + vertex 1.04364 1.69296 2.61451 + vertex 1.04019 1.68861 2.61534 + endloop + endfacet + facet normal 0.13312 0.0885488 0.987136 + outer loop + vertex 1.0398 1.68438 2.61577 + vertex 1.04019 1.68861 2.61534 + vertex 1.03694 1.68624 2.61599 + endloop + endfacet + facet normal 0.157792 0.0932623 0.983058 + outer loop + vertex 1.03694 1.68624 2.61599 + vertex 1.03266 1.68586 2.61671 + vertex 1.03683 1.68126 2.61648 + endloop + endfacet + facet normal 0.187648 0.0918057 0.977936 + outer loop + vertex 1.03266 1.68586 2.61671 + vertex 1.03086 1.69165 2.61652 + vertex 1.02779 1.68701 2.61754 + endloop + endfacet + facet normal 0.146507 0.0886037 0.985233 + outer loop + vertex 1.03416 1.69423 2.61569 + vertex 1.03546 1.69023 2.61585 + vertex 1.03854 1.69433 2.61503 + endloop + endfacet + facet normal 0.170203 0.084554 0.981775 + outer loop + vertex 1.03416 1.69423 2.61569 + vertex 1.03505 1.69864 2.61515 + vertex 1.03154 1.6962 2.61597 + endloop + endfacet + facet normal 0.184429 0.0840705 0.979244 + outer loop + vertex 1.02935 1.70424 2.6157 + vertex 1.03042 1.70021 2.61585 + vertex 1.03376 1.7044 2.61486 + endloop + endfacet + facet normal 0.148224 0.0930738 0.984564 + outer loop + vertex 1.03966 1.69903 2.61442 + vertex 1.03885 1.70309 2.61416 + vertex 1.03505 1.69864 2.61515 + endloop + endfacet + facet normal 0.141322 0.0928773 0.985597 + outer loop + vertex 1.03885 1.70309 2.61416 + vertex 1.04344 1.70738 2.6131 + vertex 1.03872 1.70797 2.61372 + endloop + endfacet + facet normal 0.159754 0.0953246 0.982544 + outer loop + vertex 1.03872 1.70797 2.61372 + vertex 1.03864 1.71266 2.61328 + vertex 1.03498 1.70916 2.61421 + endloop + endfacet + facet normal 0.154126 0.0955741 0.983418 + outer loop + vertex 1.03864 1.71266 2.61328 + vertex 1.0426 1.71676 2.61226 + vertex 1.03812 1.71721 2.61292 + endloop + endfacet + facet normal 0.162637 0.0957884 0.982025 + outer loop + vertex 1.03812 1.71721 2.61292 + vertex 1.04145 1.72078 2.61202 + vertex 1.03756 1.72185 2.61256 + endloop + endfacet + facet normal 0.163718 0.100034 0.981422 + outer loop + vertex 1.04145 1.72078 2.61202 + vertex 1.0416 1.72603 2.61146 + vertex 1.03756 1.72185 2.61256 + endloop + endfacet + facet normal 0.196202 0.0829867 0.977046 + outer loop + vertex 1.03671 1.72588 2.61233 + vertex 1.03772 1.73076 2.61171 + vertex 1.03316 1.72745 2.61291 + endloop + endfacet + facet normal 0.148137 0.079677 0.985752 + outer loop + vertex 1.04458 1.72913 2.61066 + vertex 1.04518 1.73341 2.61023 + vertex 1.04185 1.73107 2.61092 + endloop + endfacet + facet normal 0.190822 0.0697053 0.979147 + outer loop + vertex 1.03678 1.73628 2.6115 + vertex 1.03772 1.73076 2.61171 + vertex 1.04081 1.73519 2.61079 + endloop + endfacet + facet normal 0.200974 0.071357 0.976994 + outer loop + vertex 1.03772 1.73076 2.61171 + vertex 1.03678 1.73628 2.6115 + vertex 1.0332 1.73227 2.61253 + endloop + endfacet + facet normal 0.202027 0.0747698 0.976522 + outer loop + vertex 1.03316 1.72745 2.61291 + vertex 1.03772 1.73076 2.61171 + vertex 1.0332 1.73227 2.61253 + endloop + endfacet + facet normal 0.197427 0.085939 0.976543 + outer loop + vertex 1.03311 1.72265 2.61334 + vertex 1.03671 1.72588 2.61233 + vertex 1.03316 1.72745 2.61291 + endloop + endfacet + facet normal 0.213154 0.0895934 0.972902 + outer loop + vertex 1.03361 1.71786 2.61367 + vertex 1.03311 1.72265 2.61334 + vertex 1.02912 1.71888 2.61456 + endloop + endfacet + facet normal 0.374026 0.0499398 0.926073 + outer loop + vertex 1.02107 1.72241 2.61711 + vertex 1.0218 1.71711 2.6171 + vertex 1.02492 1.72022 2.61567 + endloop + endfacet + facet normal 0.258064 0.0821093 0.962632 + outer loop + vertex 1.0297 1.71389 2.61483 + vertex 1.02912 1.71888 2.61456 + vertex 1.02555 1.71533 2.61582 + endloop + endfacet + facet normal 0.196333 0.0803781 0.977237 + outer loop + vertex 1.03051 1.70865 2.6151 + vertex 1.03416 1.7131 2.614 + vertex 1.0297 1.71389 2.61483 + endloop + endfacet + facet normal 0.184334 0.0859852 0.979095 + outer loop + vertex 1.02935 1.70424 2.6157 + vertex 1.03376 1.7044 2.61486 + vertex 1.03051 1.70865 2.6151 + endloop + endfacet + facet normal 0.233021 0.0966162 0.96766 + outer loop + vertex 1.03042 1.70021 2.61585 + vertex 1.02935 1.70424 2.6157 + vertex 1.02602 1.70186 2.61674 + endloop + endfacet + facet normal 0.3051 0.078738 0.94906 + outer loop + vertex 1.02619 1.7104 2.616 + vertex 1.0231 1.70647 2.61732 + vertex 1.02689 1.70632 2.61612 + endloop + endfacet + facet normal 0.226168 0.0764931 0.97108 + outer loop + vertex 1.02602 1.70186 2.61674 + vertex 1.02747 1.69598 2.61687 + vertex 1.03042 1.70021 2.61585 + endloop + endfacet + facet normal 0.20584 0.0816717 0.975172 + outer loop + vertex 1.02747 1.69598 2.61687 + vertex 1.02671 1.69107 2.61744 + vertex 1.03086 1.69165 2.61652 + endloop + endfacet + facet normal 0.206257 0.0789152 0.97531 + outer loop + vertex 1.02779 1.68701 2.61754 + vertex 1.03086 1.69165 2.61652 + vertex 1.02671 1.69107 2.61744 + endloop + endfacet + facet normal 0.184748 0.0782797 0.979664 + outer loop + vertex 1.02836 1.68232 2.61781 + vertex 1.03266 1.68586 2.61671 + vertex 1.02779 1.68701 2.61754 + endloop + endfacet + facet normal 0.180572 0.0834736 0.980013 + outer loop + vertex 1.03192 1.681 2.61726 + vertex 1.03266 1.68586 2.61671 + vertex 1.02836 1.68232 2.61781 + endloop + endfacet + facet normal 0.179481 0.0803408 0.980475 + outer loop + vertex 1.02836 1.67778 2.61818 + vertex 1.03192 1.681 2.61726 + vertex 1.02836 1.68232 2.61781 + endloop + endfacet + facet normal 0.171054 0.0808792 0.981936 + outer loop + vertex 1.02845 1.67298 2.61856 + vertex 1.03271 1.67702 2.61748 + vertex 1.02836 1.67778 2.61818 + endloop + endfacet + facet normal 0.164069 0.077042 0.983436 + outer loop + vertex 1.02875 1.66794 2.6189 + vertex 1.03311 1.67229 2.61784 + vertex 1.02845 1.67298 2.61856 + endloop + endfacet + facet normal 0.153625 0.0779443 0.98505 + outer loop + vertex 1.02911 1.66305 2.61923 + vertex 1.03347 1.66747 2.6182 + vertex 1.02875 1.66794 2.6189 + endloop + endfacet + facet normal 0.144709 0.0769812 0.986475 + outer loop + vertex 1.02981 1.65905 2.61944 + vertex 1.03368 1.66268 2.61859 + vertex 1.02911 1.66305 2.61923 + endloop + endfacet + facet normal 0.136959 0.0812329 0.98724 + outer loop + vertex 1.02864 1.65436 2.61999 + vertex 1.03358 1.65791 2.61901 + vertex 1.02981 1.65905 2.61944 + endloop + endfacet + facet normal 0.158569 0.0769969 0.984341 + outer loop + vertex 1.03 1.6487 2.62022 + vertex 1.02864 1.65436 2.61999 + vertex 1.02545 1.65034 2.62082 + endloop + endfacet + facet normal 0.198183 0.0762457 0.977195 + outer loop + vertex 1.02545 1.65034 2.62082 + vertex 1.02257 1.6462 2.62173 + vertex 1.0266 1.64637 2.6209 + endloop + endfacet + facet normal 0.196633 0.0704016 0.977946 + outer loop + vertex 1.02257 1.6462 2.62173 + vertex 1.02176 1.64129 2.62224 + vertex 1.02592 1.64183 2.62137 + endloop + endfacet + facet normal 0.196949 0.0681105 0.978045 + outer loop + vertex 1.02273 1.63712 2.62234 + vertex 1.02592 1.64183 2.62137 + vertex 1.02176 1.64129 2.62224 + endloop + endfacet + facet normal 0.176347 0.0668921 0.982053 + outer loop + vertex 1.02317 1.63213 2.6226 + vertex 1.02763 1.63591 2.62154 + vertex 1.02273 1.63712 2.62234 + endloop + endfacet + facet normal 0.172972 0.0638192 0.982857 + outer loop + vertex 1.02344 1.62749 2.62285 + vertex 1.02688 1.63094 2.62203 + vertex 1.02317 1.63213 2.6226 + endloop + endfacet + facet normal 0.161282 0.0664926 0.984666 + outer loop + vertex 1.02355 1.62295 2.62314 + vertex 1.02774 1.62699 2.62218 + vertex 1.02344 1.62749 2.62285 + endloop + endfacet + facet normal 0.154342 0.0645486 0.985907 + outer loop + vertex 1.0235 1.61803 2.62347 + vertex 1.02812 1.62236 2.62247 + vertex 1.02355 1.62295 2.62314 + endloop + endfacet + facet normal 0.14802 0.0591437 0.987214 + outer loop + vertex 1.0236 1.61293 2.62376 + vertex 1.02842 1.61755 2.62276 + vertex 1.0235 1.61803 2.62347 + endloop + endfacet + facet normal 0.132188 0.056697 0.989602 + outer loop + vertex 1.02384 1.6029 2.62431 + vertex 1.02846 1.60744 2.62344 + vertex 1.02364 1.60784 2.62406 + endloop + endfacet + facet normal 0.125521 0.0540488 0.990618 + outer loop + vertex 1.02449 1.59889 2.62445 + vertex 1.02843 1.60253 2.62375 + vertex 1.02384 1.6029 2.62431 + endloop + endfacet + facet normal 0.118925 0.061551 0.990994 + outer loop + vertex 1.02321 1.59423 2.62489 + vertex 1.02821 1.59771 2.62408 + vertex 1.02449 1.59889 2.62445 + endloop + endfacet + facet normal 0.152156 0.0568358 0.986721 + outer loop + vertex 1.02413 1.58883 2.62506 + vertex 1.02321 1.59423 2.62489 + vertex 1.01989 1.59016 2.62564 + endloop + endfacet + facet normal 0.101814 0.0528457 0.993399 + outer loop + vertex 1.02416 1.57934 2.62554 + vertex 1.02833 1.57943 2.62511 + vertex 1.02518 1.58362 2.62521 + endloop + endfacet + facet normal 0.139823 0.0572644 0.988519 + outer loop + vertex 1.02505 1.57535 2.62565 + vertex 1.02416 1.57934 2.62554 + vertex 1.02077 1.57689 2.62617 + endloop + endfacet + facet normal 0.19097 0.0530596 0.980161 + outer loop + vertex 1.02088 1.58529 2.62572 + vertex 1.01776 1.58114 2.62656 + vertex 1.02175 1.58132 2.62577 + endloop + endfacet + facet normal 0.135494 0.044832 0.989763 + outer loop + vertex 1.02077 1.57689 2.62617 + vertex 1.02183 1.5716 2.62626 + vertex 1.02505 1.57535 2.62565 + endloop + endfacet + facet normal 0.126279 0.0430289 0.991061 + outer loop + vertex 1.02183 1.5716 2.62626 + vertex 1.02285 1.56615 2.62637 + vertex 1.02606 1.57052 2.62577 + endloop + endfacet + facet normal 0.124796 0.0425128 0.991271 + outer loop + vertex 1.02285 1.56615 2.62637 + vertex 1.02179 1.56125 2.62671 + vertex 1.02613 1.562 2.62613 + endloop + endfacet + facet normal 0.125565 0.0381563 0.991351 + outer loop + vertex 1.02273 1.55719 2.62675 + vertex 1.02613 1.562 2.62613 + vertex 1.02179 1.56125 2.62671 + endloop + endfacet + facet normal 0.154895 0.038305 0.987188 + outer loop + vertex 1.02309 1.55227 2.62688 + vertex 1.02273 1.55719 2.62675 + vertex 1.01845 1.55269 2.62759 + endloop + endfacet + facet normal 0.139214 0.0181119 0.990097 + outer loop + vertex 1.01839 1.53249 2.62809 + vertex 1.02345 1.53752 2.62729 + vertex 1.01848 1.53759 2.62799 + endloop + endfacet + facet normal 0.133165 -0.00640789 0.991073 + outer loop + vertex 1.01826 1.4925 2.62822 + vertex 1.02309 1.49735 2.6276 + vertex 1.01825 1.49746 2.62826 + endloop + endfacet + facet normal 0.136671 -0.00979296 0.990568 + outer loop + vertex 1.01826 1.48753 2.62817 + vertex 1.02311 1.49238 2.62755 + vertex 1.01826 1.4925 2.62822 + endloop + endfacet + facet normal 0.139296 -0.0117752 0.990181 + outer loop + vertex 1.01826 1.48255 2.62811 + vertex 1.02312 1.4874 2.62749 + vertex 1.01826 1.48753 2.62817 + endloop + endfacet + facet normal 0.143391 -0.0175967 0.98951 + outer loop + vertex 1.01825 1.47754 2.62803 + vertex 1.02312 1.4824 2.62741 + vertex 1.01826 1.48255 2.62811 + endloop + endfacet + facet normal 0.156326 -0.0286391 0.98729 + outer loop + vertex 1.01831 1.45759 2.6275 + vertex 1.02326 1.46252 2.62686 + vertex 1.01827 1.46253 2.62765 + endloop + endfacet + facet normal 0.249068 -0.0419735 0.967576 + outer loop + vertex 1.01975 1.41432 2.62517 + vertex 1.01991 1.41891 2.62533 + vertex 1.01647 1.41577 2.62608 + endloop + endfacet + facet normal 0.355513 -0.0356891 0.93399 + outer loop + vertex 1.01282 1.41275 2.62731 + vertex 1.01249 1.40763 2.62724 + vertex 1.01604 1.41089 2.62601 + endloop + endfacet + facet normal 0.273549 -0.0483758 0.960641 + outer loop + vertex 1.01941 1.40434 2.62477 + vertex 1.01955 1.40935 2.62498 + vertex 1.0158 1.40587 2.62588 + endloop + endfacet + facet normal 0.376371 -0.0357416 0.925779 + outer loop + vertex 1.01231 1.40261 2.62713 + vertex 1.01215 1.39766 2.627 + vertex 1.01563 1.40088 2.62571 + endloop + endfacet + facet normal 0.295737 -0.0528087 0.953809 + outer loop + vertex 1.01896 1.39419 2.62436 + vertex 1.01926 1.39932 2.62455 + vertex 1.01541 1.39592 2.62556 + endloop + endfacet + facet normal 0.39796 -0.0251407 0.917058 + outer loop + vertex 1.01432 1.38727 2.62549 + vertex 1.01228 1.38496 2.62631 + vertex 1.01486 1.38395 2.62516 + endloop + endfacet +endsolid diff --git a/noether_examples/meshes/outputsBackDoor/output_8.stl b/noether_examples/meshes/outputsBackDoor/output_8.stl new file mode 100644 index 00000000..44067af2 --- /dev/null +++ b/noether_examples/meshes/outputsBackDoor/output_8.stl @@ -0,0 +1,73306 @@ +solid ascii + facet normal 0.080072 -0.171746 0.981882 + outer loop + vertex 1.57383 1.33809 2.55542 + vertex 1.57135 1.33754 2.55552 + vertex 1.57192 1.3338 2.55482 + endloop + endfacet + facet normal 0.235031 -0.235379 0.943057 + outer loop + vertex 1.57383 1.33809 2.55542 + vertex 1.57192 1.3338 2.55482 + vertex 1.57752 1.33869 2.55465 + endloop + endfacet + facet normal 0.222815 -0.130757 0.966052 + outer loop + vertex 1.57383 1.33809 2.55542 + vertex 1.57752 1.33869 2.55465 + vertex 1.57511 1.3416 2.5556 + endloop + endfacet + facet normal 0.150876 -0.105499 0.982907 + outer loop + vertex 1.57511 1.3416 2.5556 + vertex 1.5726 1.34003 2.55582 + vertex 1.57383 1.33809 2.55542 + endloop + endfacet + facet normal 0.119212 -0.0536481 0.991418 + outer loop + vertex 1.5721 1.34377 2.55608 + vertex 1.5726 1.34003 2.55582 + vertex 1.57511 1.3416 2.5556 + endloop + endfacet + facet normal 0.112264 -0.0633083 0.99166 + outer loop + vertex 1.57563 1.34612 2.55583 + vertex 1.5721 1.34377 2.55608 + vertex 1.57511 1.3416 2.5556 + endloop + endfacet + facet normal 0.23403 -0.0761533 0.969242 + outer loop + vertex 1.57511 1.3416 2.5556 + vertex 1.57878 1.34435 2.55493 + vertex 1.57563 1.34612 2.55583 + endloop + endfacet + facet normal 0.237461 -0.0698671 0.968881 + outer loop + vertex 1.57878 1.34435 2.55493 + vertex 1.57914 1.34933 2.5552 + vertex 1.57563 1.34612 2.55583 + endloop + endfacet + facet normal 0.234083 -0.0659473 0.969977 + outer loop + vertex 1.57563 1.34612 2.55583 + vertex 1.57914 1.34933 2.5552 + vertex 1.576 1.35069 2.55605 + endloop + endfacet + facet normal 0.133237 -0.0587445 0.989342 + outer loop + vertex 1.576 1.35069 2.55605 + vertex 1.57313 1.34815 2.55629 + vertex 1.57563 1.34612 2.55583 + endloop + endfacet + facet normal 0.124789 -0.0490861 0.990968 + outer loop + vertex 1.57299 1.35281 2.55653 + vertex 1.57313 1.34815 2.55629 + vertex 1.576 1.35069 2.55605 + endloop + endfacet + facet normal 0.118339 -0.0582909 0.991261 + outer loop + vertex 1.57654 1.35443 2.55621 + vertex 1.57299 1.35281 2.55653 + vertex 1.576 1.35069 2.55605 + endloop + endfacet + facet normal 0.237353 -0.0747346 0.968544 + outer loop + vertex 1.57925 1.35389 2.5555 + vertex 1.57654 1.35443 2.55621 + vertex 1.576 1.35069 2.55605 + endloop + endfacet + facet normal 0.236645 -0.078185 0.968445 + outer loop + vertex 1.5788 1.35715 2.55587 + vertex 1.57654 1.35443 2.55621 + vertex 1.57925 1.35389 2.5555 + endloop + endfacet + facet normal 0.287761 -0.0695124 0.955176 + outer loop + vertex 1.5788 1.35715 2.55587 + vertex 1.57925 1.35389 2.5555 + vertex 1.58272 1.35872 2.55481 + endloop + endfacet + facet normal 0.288455 -0.0714922 0.954821 + outer loop + vertex 1.5788 1.35715 2.55587 + vertex 1.58272 1.35872 2.55481 + vertex 1.57966 1.36104 2.5559 + endloop + endfacet + facet normal 0.20648 -0.0534408 0.97699 + outer loop + vertex 1.57966 1.36104 2.5559 + vertex 1.57608 1.35764 2.55647 + vertex 1.5788 1.35715 2.55587 + endloop + endfacet + facet normal 0.214385 -0.0621279 0.974771 + outer loop + vertex 1.57628 1.36216 2.55672 + vertex 1.57608 1.35764 2.55647 + vertex 1.57966 1.36104 2.5559 + endloop + endfacet + facet normal 0.214346 -0.0622452 0.974772 + outer loop + vertex 1.5803 1.36587 2.55607 + vertex 1.57628 1.36216 2.55672 + vertex 1.57966 1.36104 2.5559 + endloop + endfacet + facet normal 0.289683 -0.0715001 0.954448 + outer loop + vertex 1.57966 1.36104 2.5559 + vertex 1.58377 1.36448 2.55491 + vertex 1.5803 1.36587 2.55607 + endloop + endfacet + facet normal 0.291223 -0.0675165 0.95427 + outer loop + vertex 1.58377 1.36448 2.55491 + vertex 1.58424 1.36949 2.55512 + vertex 1.5803 1.36587 2.55607 + endloop + endfacet + facet normal 0.294135 -0.0709858 0.953124 + outer loop + vertex 1.5803 1.36587 2.55607 + vertex 1.58424 1.36949 2.55512 + vertex 1.58087 1.37066 2.55625 + endloop + endfacet + facet normal 0.223027 -0.0632727 0.972757 + outer loop + vertex 1.58087 1.37066 2.55625 + vertex 1.57674 1.36712 2.55697 + vertex 1.5803 1.36587 2.55607 + endloop + endfacet + facet normal 0.230002 -0.0718663 0.970533 + outer loop + vertex 1.57765 1.37277 2.55717 + vertex 1.57674 1.36712 2.55697 + vertex 1.58087 1.37066 2.55625 + endloop + endfacet + facet normal 0.236803 -0.0611298 0.969633 + outer loop + vertex 1.58163 1.3745 2.55631 + vertex 1.57765 1.37277 2.55717 + vertex 1.58087 1.37066 2.55625 + endloop + endfacet + facet normal 0.305525 -0.0743743 0.949275 + outer loop + vertex 1.58439 1.374 2.55538 + vertex 1.58163 1.3745 2.55631 + vertex 1.58087 1.37066 2.55625 + endloop + endfacet + facet normal 0.30737 -0.0644097 0.949408 + outer loop + vertex 1.58389 1.37721 2.55576 + vertex 1.58163 1.3745 2.55631 + vertex 1.58439 1.374 2.55538 + endloop + endfacet + facet normal 0.323885 -0.0612078 0.944115 + outer loop + vertex 1.58389 1.37721 2.55576 + vertex 1.58439 1.374 2.55538 + vertex 1.58768 1.37873 2.55456 + endloop + endfacet + facet normal 0.322511 -0.0572418 0.944833 + outer loop + vertex 1.58389 1.37721 2.55576 + vertex 1.58768 1.37873 2.55456 + vertex 1.5846 1.38109 2.55575 + endloop + endfacet + facet normal 0.298133 -0.0528171 0.953062 + outer loop + vertex 1.5846 1.38109 2.55575 + vertex 1.58111 1.37769 2.55666 + vertex 1.58389 1.37721 2.55576 + endloop + endfacet + facet normal 0.302983 -0.0582901 0.951212 + outer loop + vertex 1.5812 1.38221 2.55691 + vertex 1.58111 1.37769 2.55666 + vertex 1.5846 1.38109 2.55575 + endloop + endfacet + facet normal 0.303859 -0.0555255 0.951098 + outer loop + vertex 1.58503 1.38598 2.5559 + vertex 1.5812 1.38221 2.55691 + vertex 1.5846 1.38109 2.55575 + endloop + endfacet + facet normal 0.322243 -0.0569722 0.944941 + outer loop + vertex 1.5846 1.38109 2.55575 + vertex 1.58852 1.3845 2.55462 + vertex 1.58503 1.38598 2.5559 + endloop + endfacet + facet normal 0.322928 -0.0552448 0.94481 + outer loop + vertex 1.58852 1.3845 2.55462 + vertex 1.58893 1.38968 2.55478 + vertex 1.58503 1.38598 2.5559 + endloop + endfacet + facet normal 0.321579 -0.0536549 0.945361 + outer loop + vertex 1.58503 1.38598 2.5559 + vertex 1.58893 1.38968 2.55478 + vertex 1.58536 1.39094 2.55607 + endloop + endfacet + facet normal 0.306112 -0.052799 0.95053 + outer loop + vertex 1.58536 1.39094 2.55607 + vertex 1.58142 1.3871 2.55713 + vertex 1.58503 1.38598 2.5559 + endloop + endfacet + facet normal 0.303508 -0.0498497 0.951524 + outer loop + vertex 1.58175 1.39215 2.55729 + vertex 1.58142 1.3871 2.55713 + vertex 1.58536 1.39094 2.55607 + endloop + endfacet + facet normal 0.304358 -0.0471712 0.951389 + outer loop + vertex 1.58577 1.39576 2.55618 + vertex 1.58175 1.39215 2.55729 + vertex 1.58536 1.39094 2.55607 + endloop + endfacet + facet normal 0.319286 -0.0483173 0.946426 + outer loop + vertex 1.58536 1.39094 2.55607 + vertex 1.58917 1.39461 2.55497 + vertex 1.58577 1.39576 2.55618 + endloop + endfacet + facet normal 0.319525 -0.0475664 0.946383 + outer loop + vertex 1.58917 1.39461 2.55497 + vertex 1.58925 1.39912 2.55517 + vertex 1.58577 1.39576 2.55618 + endloop + endfacet + facet normal 0.316949 -0.0445946 0.947394 + outer loop + vertex 1.58925 1.39912 2.55517 + vertex 1.58646 1.3996 2.55613 + vertex 1.58577 1.39576 2.55618 + endloop + endfacet + facet normal 0.30616 -0.0425912 0.951027 + outer loop + vertex 1.58646 1.3996 2.55613 + vertex 1.58253 1.39781 2.55731 + vertex 1.58577 1.39576 2.55618 + endloop + endfacet + facet normal 0.306957 -0.0445737 0.950679 + outer loop + vertex 1.58646 1.3996 2.55613 + vertex 1.58593 1.40275 2.55645 + vertex 1.58253 1.39781 2.55731 + endloop + endfacet + facet normal 0.308183 -0.0454961 0.950239 + outer loop + vertex 1.58593 1.40275 2.55645 + vertex 1.58204 1.40291 2.55772 + vertex 1.58253 1.39781 2.55731 + endloop + endfacet + facet normal 0.272722 -0.0497196 0.960807 + outer loop + vertex 1.58253 1.39781 2.55731 + vertex 1.58204 1.40291 2.55772 + vertex 1.57758 1.39805 2.55873 + endloop + endfacet + facet normal 0.272223 -0.0581515 0.960475 + outer loop + vertex 1.57752 1.39285 2.55843 + vertex 1.58253 1.39781 2.55731 + vertex 1.57758 1.39805 2.55873 + endloop + endfacet + facet normal 0.191428 -0.0583148 0.979773 + outer loop + vertex 1.57752 1.39285 2.55843 + vertex 1.57758 1.39805 2.55873 + vertex 1.57252 1.39304 2.55942 + endloop + endfacet + facet normal 0.19104 -0.0664606 0.97933 + outer loop + vertex 1.57262 1.38788 2.55905 + vertex 1.57752 1.39285 2.55843 + vertex 1.57252 1.39304 2.55942 + endloop + endfacet + facet normal 0.173277 -0.0484124 0.983683 + outer loop + vertex 1.57735 1.38775 2.55821 + vertex 1.57752 1.39285 2.55843 + vertex 1.57262 1.38788 2.55905 + endloop + endfacet + facet normal 0.172799 -0.0613899 0.983042 + outer loop + vertex 1.57265 1.38292 2.55874 + vertex 1.57735 1.38775 2.55821 + vertex 1.57262 1.38788 2.55905 + endloop + endfacet + facet normal 0.167772 -0.0563708 0.984213 + outer loop + vertex 1.57723 1.38279 2.55795 + vertex 1.57735 1.38775 2.55821 + vertex 1.57265 1.38292 2.55874 + endloop + endfacet + facet normal 0.167264 -0.0700058 0.983424 + outer loop + vertex 1.57265 1.37799 2.55839 + vertex 1.57723 1.38279 2.55795 + vertex 1.57265 1.38292 2.55874 + endloop + endfacet + facet normal 0.162193 -0.0650561 0.984612 + outer loop + vertex 1.57722 1.37788 2.55762 + vertex 1.57723 1.38279 2.55795 + vertex 1.57265 1.37799 2.55839 + endloop + endfacet + facet normal 0.161794 -0.0761032 0.983886 + outer loop + vertex 1.57269 1.373 2.55799 + vertex 1.57722 1.37788 2.55762 + vertex 1.57265 1.37799 2.55839 + endloop + endfacet + facet normal 0.159464 -0.0738954 0.984434 + outer loop + vertex 1.57765 1.37277 2.55717 + vertex 1.57722 1.37788 2.55762 + vertex 1.57269 1.373 2.55799 + endloop + endfacet + facet normal 0.159252 -0.0775669 0.984186 + outer loop + vertex 1.57254 1.36788 2.55761 + vertex 1.57765 1.37277 2.55717 + vertex 1.57269 1.373 2.55799 + endloop + endfacet + facet normal 0.238022 -0.0659925 0.969015 + outer loop + vertex 1.58111 1.37769 2.55666 + vertex 1.57722 1.37788 2.55762 + vertex 1.57765 1.37277 2.55717 + endloop + endfacet + facet normal 0.24475 -0.0640415 0.967469 + outer loop + vertex 1.57722 1.37788 2.55762 + vertex 1.5812 1.38221 2.55691 + vertex 1.57723 1.38279 2.55795 + endloop + endfacet + facet normal 0.246153 -0.0548491 0.967678 + outer loop + vertex 1.5812 1.38221 2.55691 + vertex 1.58142 1.3871 2.55713 + vertex 1.57723 1.38279 2.55795 + endloop + endfacet + facet normal 0.248618 -0.0573935 0.9669 + outer loop + vertex 1.57723 1.38279 2.55795 + vertex 1.58142 1.3871 2.55713 + vertex 1.57735 1.38775 2.55821 + endloop + endfacet + facet normal 0.253666 -0.0504351 0.965976 + outer loop + vertex 1.57735 1.38775 2.55821 + vertex 1.58175 1.39215 2.55729 + vertex 1.57752 1.39285 2.55843 + endloop + endfacet + facet normal 0.230445 -0.0993639 0.967999 + outer loop + vertex 1.57252 1.39304 2.55942 + vertex 1.57758 1.39805 2.55873 + vertex 1.5726 1.39841 2.55995 + endloop + endfacet + facet normal 0.233042 -0.0700202 0.969943 + outer loop + vertex 1.57758 1.39805 2.55873 + vertex 1.57765 1.40321 2.55909 + vertex 1.5726 1.39841 2.55995 + endloop + endfacet + facet normal 0.279381 -0.12191 0.95241 + outer loop + vertex 1.5726 1.39841 2.55995 + vertex 1.57765 1.40321 2.55909 + vertex 1.57387 1.40354 2.56024 + endloop + endfacet + facet normal 0.286094 -0.0588309 0.956394 + outer loop + vertex 1.5774 1.40855 2.55949 + vertex 1.57387 1.40354 2.56024 + vertex 1.57765 1.40321 2.55909 + endloop + endfacet + facet normal 0.307208 -0.0573513 0.949913 + outer loop + vertex 1.57765 1.40321 2.55909 + vertex 1.58196 1.40793 2.55798 + vertex 1.5774 1.40855 2.55949 + endloop + endfacet + facet normal 0.30975 -0.0389003 0.950022 + outer loop + vertex 1.58196 1.40793 2.55798 + vertex 1.5821 1.41314 2.55815 + vertex 1.5774 1.40855 2.55949 + endloop + endfacet + facet normal 0.312204 -0.0416786 0.9491 + outer loop + vertex 1.5774 1.40855 2.55949 + vertex 1.5821 1.41314 2.55815 + vertex 1.57823 1.41441 2.55947 + endloop + endfacet + facet normal 0.277401 -0.0367146 0.960052 + outer loop + vertex 1.5774 1.40855 2.55949 + vertex 1.57823 1.41441 2.55947 + vertex 1.57429 1.41088 2.56048 + endloop + endfacet + facet normal 0.279811 -0.0332508 0.959479 + outer loop + vertex 1.57358 1.40684 2.56055 + vertex 1.5774 1.40855 2.55949 + vertex 1.57429 1.41088 2.56048 + endloop + endfacet + facet normal 0.176996 -0.0147021 0.984102 + outer loop + vertex 1.57429 1.41088 2.56048 + vertex 1.57109 1.4076 2.561 + vertex 1.57358 1.40684 2.56055 + endloop + endfacet + facet normal 0.174064 -0.0245708 0.984428 + outer loop + vertex 1.57358 1.40684 2.56055 + vertex 1.57109 1.4076 2.561 + vertex 1.57148 1.40428 2.56085 + endloop + endfacet + facet normal 0.227986 -0.0703086 0.971123 + outer loop + vertex 1.57358 1.40684 2.56055 + vertex 1.57148 1.40428 2.56085 + vertex 1.57387 1.40354 2.56024 + endloop + endfacet + facet normal 0.179865 -0.0175873 0.983534 + outer loop + vertex 1.57103 1.41233 2.5611 + vertex 1.57109 1.4076 2.561 + vertex 1.57429 1.41088 2.56048 + endloop + endfacet + facet normal 0.175541 -0.0275387 0.984087 + outer loop + vertex 1.57467 1.41592 2.56055 + vertex 1.57103 1.41233 2.5611 + vertex 1.57429 1.41088 2.56048 + endloop + endfacet + facet normal 0.185508 -0.0379507 0.98191 + outer loop + vertex 1.5712 1.41739 2.56126 + vertex 1.57103 1.41233 2.5611 + vertex 1.57467 1.41592 2.56055 + endloop + endfacet + facet normal 0.184622 -0.0400802 0.981992 + outer loop + vertex 1.57493 1.42101 2.56071 + vertex 1.5712 1.41739 2.56126 + vertex 1.57467 1.41592 2.56055 + endloop + endfacet + facet normal 0.278586 -0.0441788 0.959395 + outer loop + vertex 1.57467 1.41592 2.56055 + vertex 1.57856 1.41962 2.55959 + vertex 1.57493 1.42101 2.56071 + endloop + endfacet + facet normal 0.279474 -0.041725 0.959246 + outer loop + vertex 1.57856 1.41962 2.55959 + vertex 1.57876 1.42466 2.55975 + vertex 1.57493 1.42101 2.56071 + endloop + endfacet + facet normal 0.282156 -0.0447773 0.958323 + outer loop + vertex 1.57493 1.42101 2.56071 + vertex 1.57876 1.42466 2.55975 + vertex 1.57512 1.42601 2.56089 + endloop + endfacet + facet normal 0.194992 -0.0422479 0.979894 + outer loop + vertex 1.57512 1.42601 2.56089 + vertex 1.57139 1.42228 2.56147 + vertex 1.57493 1.42101 2.56071 + endloop + endfacet + facet normal 0.191321 -0.0384336 0.980775 + outer loop + vertex 1.57141 1.42715 2.56166 + vertex 1.57139 1.42228 2.56147 + vertex 1.57512 1.42601 2.56089 + endloop + endfacet + facet normal 0.191405 -0.0381548 0.980769 + outer loop + vertex 1.57528 1.431 2.56105 + vertex 1.57141 1.42715 2.56166 + vertex 1.57512 1.42601 2.56089 + endloop + endfacet + facet normal 0.282373 -0.0403666 0.958455 + outer loop + vertex 1.57512 1.42601 2.56089 + vertex 1.57891 1.42964 2.55992 + vertex 1.57528 1.431 2.56105 + endloop + endfacet + facet normal 0.283698 -0.0366201 0.958214 + outer loop + vertex 1.57891 1.42964 2.55992 + vertex 1.57908 1.43463 2.56006 + vertex 1.57528 1.431 2.56105 + endloop + endfacet + facet normal 0.282807 -0.0356061 0.958516 + outer loop + vertex 1.57528 1.431 2.56105 + vertex 1.57908 1.43463 2.56006 + vertex 1.57543 1.43597 2.56119 + endloop + endfacet + facet normal 0.191306 -0.0334437 0.980961 + outer loop + vertex 1.57543 1.43597 2.56119 + vertex 1.57152 1.43214 2.56182 + vertex 1.57528 1.431 2.56105 + endloop + endfacet + facet normal 0.191646 -0.0338043 0.980882 + outer loop + vertex 1.57165 1.43711 2.56197 + vertex 1.57152 1.43214 2.56182 + vertex 1.57543 1.43597 2.56119 + endloop + endfacet + facet normal 0.193373 -0.0279289 0.980728 + outer loop + vertex 1.57556 1.4409 2.56131 + vertex 1.57165 1.43711 2.56197 + vertex 1.57543 1.43597 2.56119 + endloop + endfacet + facet normal 0.284993 -0.029717 0.958069 + outer loop + vertex 1.57543 1.43597 2.56119 + vertex 1.57922 1.4396 2.56018 + vertex 1.57556 1.4409 2.56131 + endloop + endfacet + facet normal 0.286965 -0.0237547 0.957646 + outer loop + vertex 1.57922 1.4396 2.56018 + vertex 1.5793 1.44452 2.56027 + vertex 1.57556 1.4409 2.56131 + endloop + endfacet + facet normal 0.287316 -0.0241493 0.957531 + outer loop + vertex 1.57556 1.4409 2.56131 + vertex 1.5793 1.44452 2.56027 + vertex 1.5757 1.44576 2.56139 + endloop + endfacet + facet normal 0.198836 -0.0219323 0.979787 + outer loop + vertex 1.5757 1.44576 2.56139 + vertex 1.57177 1.44203 2.5621 + vertex 1.57556 1.4409 2.56131 + endloop + endfacet + facet normal 0.201256 -0.0245875 0.97923 + outer loop + vertex 1.572 1.44703 2.56218 + vertex 1.57177 1.44203 2.5621 + vertex 1.5757 1.44576 2.56139 + endloop + endfacet + facet normal 0.203028 -0.0192437 0.978984 + outer loop + vertex 1.57598 1.45052 2.56142 + vertex 1.572 1.44703 2.56218 + vertex 1.5757 1.44576 2.56139 + endloop + endfacet + facet normal 0.291003 -0.0243783 0.956411 + outer loop + vertex 1.5757 1.44576 2.56139 + vertex 1.57937 1.44934 2.56036 + vertex 1.57598 1.45052 2.56142 + endloop + endfacet + facet normal 0.20997 -0.0275389 0.97732 + outer loop + vertex 1.57269 1.45265 2.56219 + vertex 1.572 1.44703 2.56218 + vertex 1.57598 1.45052 2.56142 + endloop + endfacet + facet normal 0.214332 -0.0205225 0.976545 + outer loop + vertex 1.57661 1.45435 2.56136 + vertex 1.57269 1.45265 2.56219 + vertex 1.57598 1.45052 2.56142 + endloop + endfacet + facet normal 0.301372 -0.0349777 0.952865 + outer loop + vertex 1.57936 1.45383 2.56047 + vertex 1.57661 1.45435 2.56136 + vertex 1.57598 1.45052 2.56142 + endloop + endfacet + facet normal 0.302595 -0.0282159 0.952701 + outer loop + vertex 1.5788 1.45706 2.56075 + vertex 1.57661 1.45435 2.56136 + vertex 1.57936 1.45383 2.56047 + endloop + endfacet + facet normal 0.331446 -0.0223706 0.943209 + outer loop + vertex 1.5788 1.45706 2.56075 + vertex 1.57936 1.45383 2.56047 + vertex 1.58251 1.45859 2.55948 + endloop + endfacet + facet normal 0.330408 -0.0195058 0.943637 + outer loop + vertex 1.5788 1.45706 2.56075 + vertex 1.58251 1.45859 2.55948 + vertex 1.57942 1.46098 2.56061 + endloop + endfacet + facet normal 0.287703 -0.0122959 0.957641 + outer loop + vertex 1.57942 1.46098 2.56061 + vertex 1.57602 1.45756 2.56159 + vertex 1.5788 1.45706 2.56075 + endloop + endfacet + facet normal 0.293192 -0.0182541 0.955879 + outer loop + vertex 1.57601 1.46212 2.56168 + vertex 1.57602 1.45756 2.56159 + vertex 1.57942 1.46098 2.56061 + endloop + endfacet + facet normal 0.293632 -0.0168427 0.95577 + outer loop + vertex 1.57972 1.46593 2.56061 + vertex 1.57601 1.46212 2.56168 + vertex 1.57942 1.46098 2.56061 + endloop + endfacet + facet normal 0.330936 -0.0191177 0.943459 + outer loop + vertex 1.57942 1.46098 2.56061 + vertex 1.58321 1.4644 2.55935 + vertex 1.57972 1.46593 2.56061 + endloop + endfacet + facet normal 0.33214 -0.0160702 0.943093 + outer loop + vertex 1.58321 1.4644 2.55935 + vertex 1.58344 1.46959 2.55936 + vertex 1.57972 1.46593 2.56061 + endloop + endfacet + facet normal 0.332795 -0.0168197 0.942849 + outer loop + vertex 1.57972 1.46593 2.56061 + vertex 1.58344 1.46959 2.55936 + vertex 1.57984 1.47097 2.56065 + endloop + endfacet + facet normal 0.297247 -0.016077 0.954665 + outer loop + vertex 1.57984 1.47097 2.56065 + vertex 1.5761 1.46708 2.56175 + vertex 1.57972 1.46593 2.56061 + endloop + endfacet + facet normal 0.29857 -0.0174721 0.954228 + outer loop + vertex 1.57616 1.47209 2.56183 + vertex 1.5761 1.46708 2.56175 + vertex 1.57984 1.47097 2.56065 + endloop + endfacet + facet normal 0.299603 -0.0138151 0.953964 + outer loop + vertex 1.57989 1.47598 2.56071 + vertex 1.57616 1.47209 2.56183 + vertex 1.57984 1.47097 2.56065 + endloop + endfacet + facet normal 0.335159 -0.0140195 0.942057 + outer loop + vertex 1.57984 1.47097 2.56065 + vertex 1.58351 1.47462 2.5594 + vertex 1.57989 1.47598 2.56071 + endloop + endfacet + facet normal 0.336291 -0.0106548 0.941698 + outer loop + vertex 1.58351 1.47462 2.5594 + vertex 1.58353 1.4796 2.55945 + vertex 1.57989 1.47598 2.56071 + endloop + endfacet + facet normal 0.337206 -0.0116933 0.941358 + outer loop + vertex 1.57989 1.47598 2.56071 + vertex 1.58353 1.4796 2.55945 + vertex 1.57992 1.48097 2.56076 + endloop + endfacet + facet normal 0.30143 -0.0115498 0.953418 + outer loop + vertex 1.57992 1.48097 2.56076 + vertex 1.5762 1.47709 2.56189 + vertex 1.57989 1.47598 2.56071 + endloop + endfacet + facet normal 0.302803 -0.0130047 0.952964 + outer loop + vertex 1.57624 1.48209 2.56195 + vertex 1.5762 1.47709 2.56189 + vertex 1.57992 1.48097 2.56076 + endloop + endfacet + facet normal 0.303609 -0.0101206 0.952743 + outer loop + vertex 1.57997 1.48596 2.5608 + vertex 1.57624 1.48209 2.56195 + vertex 1.57992 1.48097 2.56076 + endloop + endfacet + facet normal 0.338528 -0.0103219 0.9409 + outer loop + vertex 1.57992 1.48097 2.56076 + vertex 1.58356 1.48458 2.55949 + vertex 1.57997 1.48596 2.5608 + endloop + endfacet + facet normal 0.339378 -0.00783019 0.940618 + outer loop + vertex 1.58356 1.48458 2.55949 + vertex 1.5836 1.48957 2.55952 + vertex 1.57997 1.48596 2.5608 + endloop + endfacet + facet normal 0.338312 -0.00661938 0.941011 + outer loop + vertex 1.57997 1.48596 2.5608 + vertex 1.5836 1.48957 2.55952 + vertex 1.58 1.49095 2.56082 + endloop + endfacet + facet normal 0.30429 -0.00644011 0.952558 + outer loop + vertex 1.58 1.49095 2.56082 + vertex 1.57627 1.48708 2.56199 + vertex 1.57997 1.48596 2.5608 + endloop + endfacet + facet normal 0.303807 -0.00592816 0.952715 + outer loop + vertex 1.57629 1.49207 2.56201 + vertex 1.57627 1.48708 2.56199 + vertex 1.58 1.49095 2.56082 + endloop + endfacet + facet normal 0.304325 -0.00404811 0.95256 + outer loop + vertex 1.58002 1.49595 2.56084 + vertex 1.57629 1.49207 2.56201 + vertex 1.58 1.49095 2.56082 + endloop + endfacet + facet normal 0.337435 -0.00415441 0.94134 + outer loop + vertex 1.58 1.49095 2.56082 + vertex 1.58363 1.49457 2.55954 + vertex 1.58002 1.49595 2.56084 + endloop + endfacet + facet normal 0.337486 -0.00400552 0.941322 + outer loop + vertex 1.58363 1.49457 2.55954 + vertex 1.58364 1.49957 2.55955 + vertex 1.58002 1.49595 2.56084 + endloop + endfacet + facet normal 0.336766 -0.00319116 0.941583 + outer loop + vertex 1.58002 1.49595 2.56084 + vertex 1.58364 1.49957 2.55955 + vertex 1.58003 1.50095 2.56085 + endloop + endfacet + facet normal 0.304439 -0.00314096 0.952527 + outer loop + vertex 1.58003 1.50095 2.56085 + vertex 1.5763 1.49708 2.56203 + vertex 1.58002 1.49595 2.56084 + endloop + endfacet + facet normal 0.303206 -0.00183383 0.952923 + outer loop + vertex 1.57631 1.50207 2.56204 + vertex 1.5763 1.49708 2.56203 + vertex 1.58003 1.50095 2.56085 + endloop + endfacet + facet normal 0.30303 -0.00247739 0.952978 + outer loop + vertex 1.58004 1.50595 2.56086 + vertex 1.57631 1.50207 2.56204 + vertex 1.58003 1.50095 2.56085 + endloop + endfacet + facet normal 0.335884 -0.00248939 0.9419 + outer loop + vertex 1.58003 1.50095 2.56085 + vertex 1.58365 1.50456 2.55957 + vertex 1.58004 1.50595 2.56086 + endloop + endfacet + facet normal 0.335882 -0.00249395 0.941901 + outer loop + vertex 1.58365 1.50456 2.55957 + vertex 1.58365 1.50955 2.55959 + vertex 1.58004 1.50595 2.56086 + endloop + endfacet + facet normal 0.334649 -0.00110282 0.942342 + outer loop + vertex 1.58004 1.50595 2.56086 + vertex 1.58365 1.50955 2.55959 + vertex 1.58003 1.51094 2.56087 + endloop + endfacet + facet normal 0.302376 -0.00114227 0.953188 + outer loop + vertex 1.58003 1.51094 2.56087 + vertex 1.57631 1.50706 2.56205 + vertex 1.58004 1.50595 2.56086 + endloop + endfacet + facet normal 0.302316 -0.00107937 0.953207 + outer loop + vertex 1.57631 1.51206 2.56205 + vertex 1.57631 1.50706 2.56205 + vertex 1.58003 1.51094 2.56087 + endloop + endfacet + facet normal 0.302803 0.000698 0.953053 + outer loop + vertex 1.58003 1.51593 2.56087 + vertex 1.57631 1.51206 2.56205 + vertex 1.58003 1.51094 2.56087 + endloop + endfacet + facet normal 0.333621 0.000743391 0.942707 + outer loop + vertex 1.58003 1.51094 2.56087 + vertex 1.58364 1.51454 2.55959 + vertex 1.58003 1.51593 2.56087 + endloop + endfacet + facet normal 0.333824 0.00133963 0.942634 + outer loop + vertex 1.58364 1.51454 2.55959 + vertex 1.58363 1.51953 2.55959 + vertex 1.58003 1.51593 2.56087 + endloop + endfacet + facet normal 0.33333 0.00189472 0.942808 + outer loop + vertex 1.58003 1.51593 2.56087 + vertex 1.58363 1.51953 2.55959 + vertex 1.58002 1.52092 2.56086 + endloop + endfacet + facet normal 0.302366 0.00186844 0.95319 + outer loop + vertex 1.58002 1.52092 2.56086 + vertex 1.57631 1.51705 2.56205 + vertex 1.58003 1.51593 2.56087 + endloop + endfacet + facet normal 0.301834 0.00243103 0.953357 + outer loop + vertex 1.5763 1.52204 2.56204 + vertex 1.57631 1.51705 2.56205 + vertex 1.58002 1.52092 2.56086 + endloop + endfacet + facet normal 0.301815 0.00236039 0.953364 + outer loop + vertex 1.58001 1.52591 2.56085 + vertex 1.5763 1.52204 2.56204 + vertex 1.58002 1.52092 2.56086 + endloop + endfacet + facet normal 0.333491 0.00238094 0.94275 + outer loop + vertex 1.58002 1.52092 2.56086 + vertex 1.58362 1.52452 2.55958 + vertex 1.58001 1.52591 2.56085 + endloop + endfacet + facet normal 0.333902 0.00358559 0.942601 + outer loop + vertex 1.58362 1.52452 2.55958 + vertex 1.58361 1.52952 2.55956 + vertex 1.58001 1.52591 2.56085 + endloop + endfacet + facet normal 0.333745 0.00376205 0.942656 + outer loop + vertex 1.58001 1.52591 2.56085 + vertex 1.58361 1.52952 2.55956 + vertex 1.58 1.53091 2.56084 + endloop + endfacet + facet normal 0.300849 0.00367418 0.953665 + outer loop + vertex 1.58 1.53091 2.56084 + vertex 1.57629 1.52703 2.56202 + vertex 1.58001 1.52591 2.56085 + endloop + endfacet + facet normal 0.299748 0.00483257 0.954006 + outer loop + vertex 1.57627 1.53202 2.562 + vertex 1.57629 1.52703 2.56202 + vertex 1.58 1.53091 2.56084 + endloop + endfacet + facet normal 0.300204 0.00651509 0.953853 + outer loop + vertex 1.57996 1.53589 2.56081 + vertex 1.57627 1.53202 2.562 + vertex 1.58 1.53091 2.56084 + endloop + endfacet + facet normal 0.333973 0.00669226 0.942559 + outer loop + vertex 1.58 1.53091 2.56084 + vertex 1.58358 1.53451 2.55954 + vertex 1.57996 1.53589 2.56081 + endloop + endfacet + facet normal 0.335005 0.00975128 0.942166 + outer loop + vertex 1.58358 1.53451 2.55954 + vertex 1.58353 1.5395 2.55951 + vertex 1.57996 1.53589 2.56081 + endloop + endfacet + facet normal 0.33445 0.0103701 0.942356 + outer loop + vertex 1.57996 1.53589 2.56081 + vertex 1.58353 1.5395 2.55951 + vertex 1.57992 1.54088 2.56077 + endloop + endfacet + facet normal 0.30076 0.0101735 0.953646 + outer loop + vertex 1.57992 1.54088 2.56077 + vertex 1.57624 1.53701 2.56197 + vertex 1.57996 1.53589 2.56081 + endloop + endfacet + facet normal 0.299635 0.0113496 0.953986 + outer loop + vertex 1.57621 1.542 2.56192 + vertex 1.57624 1.53701 2.56197 + vertex 1.57992 1.54088 2.56077 + endloop + endfacet + facet normal 0.300218 0.013488 0.953775 + outer loop + vertex 1.57987 1.54588 2.56072 + vertex 1.57621 1.542 2.56192 + vertex 1.57992 1.54088 2.56077 + endloop + endfacet + facet normal 0.335041 0.0136637 0.942104 + outer loop + vertex 1.57992 1.54088 2.56077 + vertex 1.58348 1.54449 2.55945 + vertex 1.57987 1.54588 2.56072 + endloop + endfacet + facet normal 0.335839 0.0160287 0.941783 + outer loop + vertex 1.58348 1.54449 2.55945 + vertex 1.58344 1.54948 2.55938 + vertex 1.57987 1.54588 2.56072 + endloop + endfacet + facet normal 0.335332 0.0165923 0.941954 + outer loop + vertex 1.57987 1.54588 2.56072 + vertex 1.58344 1.54948 2.55938 + vertex 1.57981 1.55088 2.56065 + endloop + endfacet + facet normal 0.298769 0.0162777 0.954187 + outer loop + vertex 1.57981 1.55088 2.56065 + vertex 1.57617 1.54701 2.56186 + vertex 1.57987 1.54588 2.56072 + endloop + endfacet + facet normal 0.297166 0.0179303 0.954657 + outer loop + vertex 1.57608 1.55202 2.56179 + vertex 1.57617 1.54701 2.56186 + vertex 1.57981 1.55088 2.56065 + endloop + endfacet + facet normal 0.29724 0.0181986 0.954629 + outer loop + vertex 1.57967 1.55587 2.5606 + vertex 1.57608 1.55202 2.56179 + vertex 1.57981 1.55088 2.56065 + endloop + endfacet + facet normal 0.333479 0.0190963 0.942564 + outer loop + vertex 1.57981 1.55088 2.56065 + vertex 1.58336 1.5545 2.55932 + vertex 1.57967 1.55587 2.5606 + endloop + endfacet + facet normal 0.333171 0.0181462 0.942692 + outer loop + vertex 1.58336 1.5545 2.55932 + vertex 1.58316 1.55951 2.5593 + vertex 1.57967 1.55587 2.5606 + endloop + endfacet + facet normal 0.329688 0.0218913 0.943836 + outer loop + vertex 1.57967 1.55587 2.5606 + vertex 1.58316 1.55951 2.5593 + vertex 1.57941 1.56069 2.56058 + endloop + endfacet + facet normal 0.294653 0.0200951 0.955393 + outer loop + vertex 1.57941 1.56069 2.56058 + vertex 1.57591 1.55704 2.56174 + vertex 1.57967 1.55587 2.5606 + endloop + endfacet + facet normal 0.286257 0.0288887 0.957717 + outer loop + vertex 1.57572 1.56242 2.56163 + vertex 1.57591 1.55704 2.56174 + vertex 1.57941 1.56069 2.56058 + endloop + endfacet + facet normal 0.282151 0.0192418 0.959177 + outer loop + vertex 1.57941 1.56069 2.56058 + vertex 1.57921 1.56411 2.56057 + vertex 1.57572 1.56242 2.56163 + endloop + endfacet + facet normal 0.327879 0.0219088 0.944466 + outer loop + vertex 1.57921 1.56411 2.56057 + vertex 1.57941 1.56069 2.56058 + vertex 1.58257 1.5647 2.55939 + endloop + endfacet + facet normal 0.326112 0.0325229 0.944772 + outer loop + vertex 1.57921 1.56411 2.56057 + vertex 1.58257 1.5647 2.55939 + vertex 1.57902 1.56831 2.56049 + endloop + endfacet + facet normal 0.320184 0.0260278 0.946998 + outer loop + vertex 1.57902 1.56831 2.56049 + vertex 1.58257 1.5647 2.55939 + vertex 1.5835 1.56911 2.55895 + endloop + endfacet + facet normal 0.321706 0.0169156 0.946689 + outer loop + vertex 1.5835 1.56911 2.55895 + vertex 1.58302 1.57295 2.55905 + vertex 1.57902 1.56831 2.56049 + endloop + endfacet + facet normal 0.325843 0.0129264 0.945335 + outer loop + vertex 1.57902 1.56831 2.56049 + vertex 1.58302 1.57295 2.55905 + vertex 1.57928 1.5744 2.56032 + endloop + endfacet + facet normal 0.292086 0.0146729 0.95628 + outer loop + vertex 1.57902 1.56831 2.56049 + vertex 1.57928 1.5744 2.56032 + vertex 1.57581 1.57159 2.56142 + endloop + endfacet + facet normal 0.262708 -0.016553 0.964733 + outer loop + vertex 1.57581 1.57159 2.56142 + vertex 1.5728 1.56667 2.56215 + vertex 1.57902 1.56831 2.56049 + endloop + endfacet + facet normal 0.246143 0.0493937 0.967974 + outer loop + vertex 1.57902 1.56831 2.56049 + vertex 1.5728 1.56667 2.56215 + vertex 1.57572 1.56242 2.56163 + endloop + endfacet + facet normal 0.213605 0.0259537 0.976575 + outer loop + vertex 1.5728 1.56667 2.56215 + vertex 1.5712 1.56148 2.56264 + vertex 1.57572 1.56242 2.56163 + endloop + endfacet + facet normal 0.212884 0.029458 0.976633 + outer loop + vertex 1.57179 1.55749 2.56263 + vertex 1.57572 1.56242 2.56163 + vertex 1.5712 1.56148 2.56264 + endloop + endfacet + facet normal 0.213332 0.0153458 0.976859 + outer loop + vertex 1.57198 1.57202 2.56225 + vertex 1.5728 1.56667 2.56215 + vertex 1.57581 1.57159 2.56142 + endloop + endfacet + facet normal 0.213336 0.0153857 0.976858 + outer loop + vertex 1.57565 1.57598 2.56139 + vertex 1.57198 1.57202 2.56225 + vertex 1.57581 1.57159 2.56142 + endloop + endfacet + facet normal 0.203446 0.0249727 0.978768 + outer loop + vertex 1.57176 1.57697 2.56217 + vertex 1.57198 1.57202 2.56225 + vertex 1.57565 1.57598 2.56139 + endloop + endfacet + facet normal 0.203589 0.0255747 0.978722 + outer loop + vertex 1.57552 1.58085 2.56129 + vertex 1.57176 1.57697 2.56217 + vertex 1.57565 1.57598 2.56139 + endloop + endfacet + facet normal 0.284986 0.0273776 0.958141 + outer loop + vertex 1.57565 1.57598 2.56139 + vertex 1.5792 1.57946 2.56023 + vertex 1.57552 1.58085 2.56129 + endloop + endfacet + facet normal 0.285934 0.0301521 0.957775 + outer loop + vertex 1.5792 1.57946 2.56023 + vertex 1.57905 1.58444 2.56012 + vertex 1.57552 1.58085 2.56129 + endloop + endfacet + facet normal 0.280983 0.0354474 0.959058 + outer loop + vertex 1.57552 1.58085 2.56129 + vertex 1.57905 1.58444 2.56012 + vertex 1.57537 1.58582 2.56115 + endloop + endfacet + facet normal 0.196425 0.0335246 0.979946 + outer loop + vertex 1.57537 1.58582 2.56115 + vertex 1.57164 1.58194 2.56203 + vertex 1.57552 1.58085 2.56129 + endloop + endfacet + facet normal 0.19257 0.0373695 0.980572 + outer loop + vertex 1.57153 1.58694 2.56186 + vertex 1.57164 1.58194 2.56203 + vertex 1.57537 1.58582 2.56115 + endloop + endfacet + facet normal 0.19245 0.036934 0.980611 + outer loop + vertex 1.57522 1.59082 2.56099 + vertex 1.57153 1.58694 2.56186 + vertex 1.57537 1.58582 2.56115 + endloop + endfacet + facet normal 0.279114 0.0389353 0.959468 + outer loop + vertex 1.57537 1.58582 2.56115 + vertex 1.57889 1.58943 2.55998 + vertex 1.57522 1.59082 2.56099 + endloop + endfacet + facet normal 0.278668 0.037624 0.95965 + outer loop + vertex 1.57889 1.58943 2.55998 + vertex 1.57876 1.59444 2.55982 + vertex 1.57522 1.59082 2.56099 + endloop + endfacet + facet normal 0.278349 0.0379615 0.959729 + outer loop + vertex 1.57522 1.59082 2.56099 + vertex 1.57876 1.59444 2.55982 + vertex 1.57511 1.59583 2.56082 + endloop + endfacet + facet normal 0.189841 0.0367922 0.981125 + outer loop + vertex 1.57511 1.59583 2.56082 + vertex 1.57142 1.59194 2.56168 + vertex 1.57522 1.59082 2.56099 + endloop + endfacet + facet normal 0.187824 0.038774 0.981437 + outer loop + vertex 1.57136 1.59694 2.56149 + vertex 1.57142 1.59194 2.56168 + vertex 1.57511 1.59583 2.56082 + endloop + endfacet + facet normal 0.186802 0.0351158 0.98177 + outer loop + vertex 1.57502 1.60082 2.56066 + vertex 1.57136 1.59694 2.56149 + vertex 1.57511 1.59583 2.56082 + endloop + endfacet + facet normal 0.279512 0.0360134 0.959466 + outer loop + vertex 1.57511 1.59583 2.56082 + vertex 1.57868 1.59944 2.55965 + vertex 1.57502 1.60082 2.56066 + endloop + endfacet + facet normal 0.279466 0.0358761 0.959485 + outer loop + vertex 1.57868 1.59944 2.55965 + vertex 1.57853 1.60437 2.5595 + vertex 1.57502 1.60082 2.56066 + endloop + endfacet + facet normal 0.273709 0.042025 0.960894 + outer loop + vertex 1.57502 1.60082 2.56066 + vertex 1.57853 1.60437 2.5595 + vertex 1.57474 1.60574 2.56052 + endloop + endfacet + facet normal 0.182645 0.0373191 0.98247 + outer loop + vertex 1.57474 1.60574 2.56052 + vertex 1.57125 1.60192 2.56132 + vertex 1.57502 1.60082 2.56066 + endloop + endfacet + facet normal 0.172107 0.0472317 0.983945 + outer loop + vertex 1.57078 1.60683 2.56117 + vertex 1.57125 1.60192 2.56132 + vertex 1.57474 1.60574 2.56052 + endloop + endfacet + facet normal 0.170388 0.0406411 0.984539 + outer loop + vertex 1.57399 1.61051 2.56046 + vertex 1.57078 1.60683 2.56117 + vertex 1.57474 1.60574 2.56052 + endloop + endfacet + facet normal 0.259477 0.0543251 0.96422 + outer loop + vertex 1.57474 1.60574 2.56052 + vertex 1.57812 1.60929 2.55941 + vertex 1.57399 1.61051 2.56046 + endloop + endfacet + facet normal 0.259195 0.0532601 0.964355 + outer loop + vertex 1.57812 1.60929 2.55941 + vertex 1.57709 1.61447 2.5594 + vertex 1.57399 1.61051 2.56046 + endloop + endfacet + facet normal 0.248228 0.0624861 0.966684 + outer loop + vertex 1.57288 1.61431 2.5605 + vertex 1.57399 1.61051 2.56046 + vertex 1.57709 1.61447 2.5594 + endloop + endfacet + facet normal 0.246845 0.0876654 0.965082 + outer loop + vertex 1.57288 1.61431 2.5605 + vertex 1.57709 1.61447 2.5594 + vertex 1.57324 1.6187 2.56001 + endloop + endfacet + facet normal 0.233066 0.0744613 0.969606 + outer loop + vertex 1.57324 1.6187 2.56001 + vertex 1.57709 1.61447 2.5594 + vertex 1.57826 1.61883 2.55879 + endloop + endfacet + facet normal 0.233844 0.0551286 0.97071 + outer loop + vertex 1.57826 1.61883 2.55879 + vertex 1.57758 1.62283 2.55872 + vertex 1.57324 1.6187 2.56001 + endloop + endfacet + facet normal 0.221451 0.0687762 0.972743 + outer loop + vertex 1.57324 1.6187 2.56001 + vertex 1.57758 1.62283 2.55872 + vertex 1.5736 1.6237 2.55957 + endloop + endfacet + facet normal 0.218304 0.0527336 0.974455 + outer loop + vertex 1.57758 1.62283 2.55872 + vertex 1.57716 1.62754 2.55857 + vertex 1.5736 1.6237 2.55957 + endloop + endfacet + facet normal 0.192103 0.0779632 0.978273 + outer loop + vertex 1.5736 1.6237 2.55957 + vertex 1.57716 1.62754 2.55857 + vertex 1.57254 1.62753 2.55947 + endloop + endfacet + facet normal 0.192469 0.0532658 0.979856 + outer loop + vertex 1.57716 1.62754 2.55857 + vertex 1.57693 1.63233 2.55835 + vertex 1.57254 1.62753 2.55947 + endloop + endfacet + facet normal 0.177958 0.0669985 0.981755 + outer loop + vertex 1.57254 1.62753 2.55947 + vertex 1.57693 1.63233 2.55835 + vertex 1.5723 1.63238 2.55918 + endloop + endfacet + facet normal 0.177945 0.0538184 0.982568 + outer loop + vertex 1.57693 1.63233 2.55835 + vertex 1.57691 1.6373 2.55808 + vertex 1.5723 1.63238 2.55918 + endloop + endfacet + facet normal 0.169691 0.061781 0.983559 + outer loop + vertex 1.5723 1.63238 2.55918 + vertex 1.57691 1.6373 2.55808 + vertex 1.57232 1.63734 2.55887 + endloop + endfacet + facet normal 0.169705 0.0508585 0.984182 + outer loop + vertex 1.57691 1.6373 2.55808 + vertex 1.57671 1.64221 2.55786 + vertex 1.57232 1.63734 2.55887 + endloop + endfacet + facet normal 0.157289 0.0623388 0.985583 + outer loop + vertex 1.57232 1.63734 2.55887 + vertex 1.57671 1.64221 2.55786 + vertex 1.57228 1.64218 2.55857 + endloop + endfacet + facet normal 0.15746 0.0507424 0.986221 + outer loop + vertex 1.57671 1.64221 2.55786 + vertex 1.57602 1.64621 2.55777 + vertex 1.57228 1.64218 2.55857 + endloop + endfacet + facet normal 0.136989 0.0701674 0.988084 + outer loop + vertex 1.57228 1.64218 2.55857 + vertex 1.57602 1.64621 2.55777 + vertex 1.57238 1.64708 2.55821 + endloop + endfacet + facet normal 0.141045 0.0882589 0.986061 + outer loop + vertex 1.57602 1.64621 2.55777 + vertex 1.57724 1.65119 2.55715 + vertex 1.57238 1.64708 2.55821 + endloop + endfacet + facet normal 0.154861 0.0717233 0.985329 + outer loop + vertex 1.57238 1.64708 2.55821 + vertex 1.57724 1.65119 2.55715 + vertex 1.57244 1.65224 2.55782 + endloop + endfacet + facet normal 0.152425 0.0598306 0.986502 + outer loop + vertex 1.57724 1.65119 2.55715 + vertex 1.57655 1.65671 2.55692 + vertex 1.57244 1.65224 2.55782 + endloop + endfacet + facet normal 0.142366 0.0692408 0.987389 + outer loop + vertex 1.57244 1.65224 2.55782 + vertex 1.57655 1.65671 2.55692 + vertex 1.57222 1.65741 2.55749 + endloop + endfacet + facet normal 0.140957 0.0597512 0.988211 + outer loop + vertex 1.57655 1.65671 2.55692 + vertex 1.57601 1.66182 2.55669 + vertex 1.57222 1.65741 2.55749 + endloop + endfacet + facet normal 0.124885 0.0737663 0.989425 + outer loop + vertex 1.57222 1.65741 2.55749 + vertex 1.57601 1.66182 2.55669 + vertex 1.57187 1.66233 2.55717 + endloop + endfacet + facet normal 0.124093 0.0667273 0.990024 + outer loop + vertex 1.57601 1.66182 2.55669 + vertex 1.57518 1.66706 2.55644 + vertex 1.57187 1.66233 2.55717 + endloop + endfacet + facet normal 0.0966975 0.0860896 0.991584 + outer loop + vertex 1.57187 1.66233 2.55717 + vertex 1.57518 1.66706 2.55644 + vertex 1.57106 1.66629 2.55691 + endloop + endfacet + facet normal 0.097835 0.0802308 0.991963 + outer loop + vertex 1.57194 1.67121 2.55642 + vertex 1.57106 1.66629 2.55691 + vertex 1.57518 1.66706 2.55644 + endloop + endfacet + facet normal 0.208491 0.0793831 0.974797 + outer loop + vertex 1.57518 1.66706 2.55644 + vertex 1.57601 1.66182 2.55669 + vertex 1.57928 1.66551 2.55569 + endloop + endfacet + facet normal 0.199817 0.0547567 0.978302 + outer loop + vertex 1.57928 1.66551 2.55569 + vertex 1.57861 1.66952 2.5556 + vertex 1.57518 1.66706 2.55644 + endloop + endfacet + facet normal 0.290494 0.0694858 0.954351 + outer loop + vertex 1.57861 1.66952 2.5556 + vertex 1.57928 1.66551 2.55569 + vertex 1.58239 1.66941 2.55446 + endloop + endfacet + facet normal 0.290519 0.0741923 0.953989 + outer loop + vertex 1.57861 1.66952 2.5556 + vertex 1.58239 1.66941 2.55446 + vertex 1.57965 1.67381 2.55495 + endloop + endfacet + facet normal 0.292607 0.0755738 0.953242 + outer loop + vertex 1.57965 1.67381 2.55495 + vertex 1.58239 1.66941 2.55446 + vertex 1.58358 1.67374 2.55375 + endloop + endfacet + facet normal 0.292649 0.0688853 0.953736 + outer loop + vertex 1.58358 1.67374 2.55375 + vertex 1.58288 1.67788 2.55366 + vertex 1.57965 1.67381 2.55495 + endloop + endfacet + facet normal 0.275616 0.083634 0.957623 + outer loop + vertex 1.57965 1.67381 2.55495 + vertex 1.58288 1.67788 2.55366 + vertex 1.5786 1.67901 2.5548 + endloop + endfacet + facet normal 0.272616 0.0703143 0.95955 + outer loop + vertex 1.58288 1.67788 2.55366 + vertex 1.58211 1.6829 2.55351 + vertex 1.5786 1.67901 2.5548 + endloop + endfacet + facet normal 0.249675 0.0924183 0.963909 + outer loop + vertex 1.5786 1.67901 2.5548 + vertex 1.58211 1.6829 2.55351 + vertex 1.57736 1.68393 2.55464 + endloop + endfacet + facet normal 0.245297 0.0689901 0.96699 + outer loop + vertex 1.58211 1.6829 2.55351 + vertex 1.58167 1.68775 2.55328 + vertex 1.57736 1.68393 2.55464 + endloop + endfacet + facet normal 0.234472 0.0818299 0.968673 + outer loop + vertex 1.57736 1.68393 2.55464 + vertex 1.58167 1.68775 2.55328 + vertex 1.57822 1.68848 2.55405 + endloop + endfacet + facet normal 0.233026 0.0740382 0.969648 + outer loop + vertex 1.58167 1.68775 2.55328 + vertex 1.58105 1.69147 2.55314 + vertex 1.57822 1.68848 2.55405 + endloop + endfacet + facet normal 0.201311 0.105384 0.973842 + outer loop + vertex 1.57822 1.68848 2.55405 + vertex 1.58105 1.69147 2.55314 + vertex 1.5775 1.69209 2.55381 + endloop + endfacet + facet normal 0.201486 0.106574 0.973676 + outer loop + vertex 1.58105 1.69147 2.55314 + vertex 1.58213 1.69609 2.55241 + vertex 1.5775 1.69209 2.55381 + endloop + endfacet + facet normal 0.209799 0.096694 0.972951 + outer loop + vertex 1.5775 1.69209 2.55381 + vertex 1.58213 1.69609 2.55241 + vertex 1.57724 1.69705 2.55337 + endloop + endfacet + facet normal 0.2066 0.078171 0.975298 + outer loop + vertex 1.58213 1.69609 2.55241 + vertex 1.58123 1.70163 2.55216 + vertex 1.57724 1.69705 2.55337 + endloop + endfacet + facet normal 0.194515 0.0891024 0.976844 + outer loop + vertex 1.57724 1.69705 2.55337 + vertex 1.58123 1.70163 2.55216 + vertex 1.57676 1.70214 2.55301 + endloop + endfacet + facet normal 0.194185 0.0855598 0.977227 + outer loop + vertex 1.58123 1.70163 2.55216 + vertex 1.58026 1.70712 2.55187 + vertex 1.57676 1.70214 2.55301 + endloop + endfacet + facet normal 0.174603 0.0998492 0.979563 + outer loop + vertex 1.57676 1.70214 2.55301 + vertex 1.58026 1.70712 2.55187 + vertex 1.57601 1.70624 2.55272 + endloop + endfacet + facet normal 0.173779 0.103615 0.979319 + outer loop + vertex 1.57719 1.71123 2.55198 + vertex 1.57601 1.70624 2.55272 + vertex 1.58026 1.70712 2.55187 + endloop + endfacet + facet normal 0.185313 0.112298 0.976242 + outer loop + vertex 1.58132 1.7117 2.55114 + vertex 1.57719 1.71123 2.55198 + vertex 1.58026 1.70712 2.55187 + endloop + endfacet + facet normal 0.261678 0.0920718 0.960754 + outer loop + vertex 1.58132 1.7117 2.55114 + vertex 1.58026 1.70712 2.55187 + vertex 1.58367 1.70963 2.5507 + endloop + endfacet + facet normal 0.279473 0.113865 0.953378 + outer loop + vertex 1.58367 1.70963 2.5507 + vertex 1.58466 1.71392 2.5499 + vertex 1.58132 1.7117 2.55114 + endloop + endfacet + facet normal 0.273739 0.1228 0.953933 + outer loop + vertex 1.58132 1.7117 2.55114 + vertex 1.58466 1.71392 2.5499 + vertex 1.58044 1.71565 2.55089 + endloop + endfacet + facet normal 0.265934 0.10115 0.95867 + outer loop + vertex 1.58466 1.71392 2.5499 + vertex 1.58353 1.71916 2.54966 + vertex 1.58044 1.71565 2.55089 + endloop + endfacet + facet normal 0.245346 0.120423 0.961927 + outer loop + vertex 1.58044 1.71565 2.55089 + vertex 1.58353 1.71916 2.54966 + vertex 1.5793 1.72017 2.55062 + endloop + endfacet + facet normal 0.16752 0.101831 0.980595 + outer loop + vertex 1.5793 1.72017 2.55062 + vertex 1.57618 1.71646 2.55153 + vertex 1.58044 1.71565 2.55089 + endloop + endfacet + facet normal 0.170092 0.117107 0.978445 + outer loop + vertex 1.57618 1.71646 2.55153 + vertex 1.57719 1.71123 2.55198 + vertex 1.58044 1.71565 2.55089 + endloop + endfacet + facet normal 0.144411 0.121634 0.982014 + outer loop + vertex 1.57511 1.72071 2.55116 + vertex 1.57618 1.71646 2.55153 + vertex 1.5793 1.72017 2.55062 + endloop + endfacet + facet normal 0.142669 0.106037 0.984074 + outer loop + vertex 1.5793 1.72017 2.55062 + vertex 1.57793 1.72361 2.55044 + vertex 1.57511 1.72071 2.55116 + endloop + endfacet + facet normal 0.211279 0.132564 0.968395 + outer loop + vertex 1.57793 1.72361 2.55044 + vertex 1.5793 1.72017 2.55062 + vertex 1.58221 1.72418 2.54943 + endloop + endfacet + facet normal 0.210876 0.135134 0.968127 + outer loop + vertex 1.57793 1.72361 2.55044 + vertex 1.58221 1.72418 2.54943 + vertex 1.57865 1.72772 2.54971 + endloop + endfacet + facet normal 0.201309 0.125246 0.971488 + outer loop + vertex 1.57865 1.72772 2.54971 + vertex 1.58221 1.72418 2.54943 + vertex 1.5832 1.72849 2.54867 + endloop + endfacet + facet normal 0.204069 0.110603 0.972688 + outer loop + vertex 1.5832 1.72849 2.54867 + vertex 1.58213 1.73218 2.54847 + vertex 1.57865 1.72772 2.54971 + endloop + endfacet + facet normal 0.176029 0.133207 0.975331 + outer loop + vertex 1.57865 1.72772 2.54971 + vertex 1.58213 1.73218 2.54847 + vertex 1.57747 1.73228 2.5493 + endloop + endfacet + facet normal 0.176086 0.10163 0.979114 + outer loop + vertex 1.58213 1.73218 2.54847 + vertex 1.58093 1.73595 2.5483 + vertex 1.57747 1.73228 2.5493 + endloop + endfacet + facet normal 0.150125 0.126461 0.980546 + outer loop + vertex 1.57747 1.73228 2.5493 + vertex 1.58093 1.73595 2.5483 + vertex 1.57718 1.73685 2.54876 + endloop + endfacet + facet normal 0.150623 0.128738 0.980173 + outer loop + vertex 1.58093 1.73595 2.5483 + vertex 1.58212 1.74096 2.54746 + vertex 1.57718 1.73685 2.54876 + endloop + endfacet + facet normal 0.154981 0.1235 0.980168 + outer loop + vertex 1.57718 1.73685 2.54876 + vertex 1.58212 1.74096 2.54746 + vertex 1.57721 1.74195 2.54811 + endloop + endfacet + facet normal 0.151534 0.104558 0.982906 + outer loop + vertex 1.58212 1.74096 2.54746 + vertex 1.58125 1.7466 2.54699 + vertex 1.57721 1.74195 2.54811 + endloop + endfacet + facet normal 0.131449 0.122211 0.983761 + outer loop + vertex 1.57721 1.74195 2.54811 + vertex 1.58125 1.7466 2.54699 + vertex 1.57678 1.74707 2.54753 + endloop + endfacet + facet normal 0.130581 0.112514 0.985033 + outer loop + vertex 1.58125 1.7466 2.54699 + vertex 1.57997 1.75188 2.54656 + vertex 1.57678 1.74707 2.54753 + endloop + endfacet + facet normal 0.096221 0.135492 0.986095 + outer loop + vertex 1.57678 1.74707 2.54753 + vertex 1.57997 1.75188 2.54656 + vertex 1.57572 1.75095 2.5471 + endloop + endfacet + facet normal 0.0951479 0.140073 0.985559 + outer loop + vertex 1.57617 1.75523 2.54645 + vertex 1.57572 1.75095 2.5471 + vertex 1.57997 1.75188 2.54656 + endloop + endfacet + facet normal 0.0938275 0.138587 0.985896 + outer loop + vertex 1.58041 1.75605 2.54593 + vertex 1.57617 1.75523 2.54645 + vertex 1.57997 1.75188 2.54656 + endloop + endfacet + facet normal 0.175489 0.128569 0.97605 + outer loop + vertex 1.58041 1.75605 2.54593 + vertex 1.57997 1.75188 2.54656 + vertex 1.58324 1.75452 2.54562 + endloop + endfacet + facet normal 0.19035 0.157549 0.968992 + outer loop + vertex 1.58324 1.75452 2.54562 + vertex 1.58346 1.75894 2.54486 + vertex 1.58041 1.75605 2.54593 + endloop + endfacet + facet normal 0.16418 0.185171 0.968895 + outer loop + vertex 1.57871 1.75863 2.54573 + vertex 1.58041 1.75605 2.54593 + vertex 1.58346 1.75894 2.54486 + endloop + endfacet + facet normal 0.166553 0.160307 0.972914 + outer loop + vertex 1.57871 1.75863 2.54573 + vertex 1.58346 1.75894 2.54486 + vertex 1.57901 1.76267 2.54501 + endloop + endfacet + facet normal 0.261375 0.151353 0.953297 + outer loop + vertex 1.58324 1.75452 2.54562 + vertex 1.5873 1.75444 2.54452 + vertex 1.58346 1.75894 2.54486 + endloop + endfacet + facet normal 0.244073 0.136052 0.960166 + outer loop + vertex 1.58346 1.75894 2.54486 + vertex 1.5873 1.75444 2.54452 + vertex 1.58817 1.75868 2.5437 + endloop + endfacet + facet normal 0.243729 0.119439 0.962461 + outer loop + vertex 1.58817 1.75868 2.5437 + vertex 1.58723 1.76254 2.54346 + vertex 1.58346 1.75894 2.54486 + endloop + endfacet + facet normal 0.232378 0.131784 0.963656 + outer loop + vertex 1.58346 1.75894 2.54486 + vertex 1.58723 1.76254 2.54346 + vertex 1.5836 1.76355 2.5442 + endloop + endfacet + facet normal 0.228359 0.115029 0.966758 + outer loop + vertex 1.58723 1.76254 2.54346 + vertex 1.58609 1.76623 2.54329 + vertex 1.5836 1.76355 2.5442 + endloop + endfacet + facet normal 0.200219 0.141996 0.969407 + outer loop + vertex 1.5836 1.76355 2.5442 + vertex 1.58609 1.76623 2.54329 + vertex 1.58251 1.76717 2.54389 + endloop + endfacet + facet normal 0.197693 0.131061 0.971463 + outer loop + vertex 1.58609 1.76623 2.54329 + vertex 1.58695 1.77088 2.54249 + vertex 1.58251 1.76717 2.54389 + endloop + endfacet + facet normal 0.198599 0.129961 0.971426 + outer loop + vertex 1.58251 1.76717 2.54389 + vertex 1.58695 1.77088 2.54249 + vertex 1.58205 1.77195 2.54335 + endloop + endfacet + facet normal 0.192295 0.0971906 0.976512 + outer loop + vertex 1.58695 1.77088 2.54249 + vertex 1.58604 1.77647 2.54211 + vertex 1.58205 1.77195 2.54335 + endloop + endfacet + facet normal 0.173891 0.113861 0.97816 + outer loop + vertex 1.58205 1.77195 2.54335 + vertex 1.58604 1.77647 2.54211 + vertex 1.58163 1.77696 2.54284 + endloop + endfacet + facet normal 0.171836 0.0909739 0.980916 + outer loop + vertex 1.58604 1.77647 2.54211 + vertex 1.5852 1.78199 2.54175 + vertex 1.58163 1.77696 2.54284 + endloop + endfacet + facet normal 0.138895 0.114937 0.983615 + outer loop + vertex 1.58163 1.77696 2.54284 + vertex 1.5852 1.78199 2.54175 + vertex 1.58096 1.78103 2.54246 + endloop + endfacet + facet normal 0.141486 0.104152 0.984446 + outer loop + vertex 1.58219 1.78598 2.54176 + vertex 1.58096 1.78103 2.54246 + vertex 1.5852 1.78199 2.54175 + endloop + endfacet + facet normal 0.14035 0.103292 0.984699 + outer loop + vertex 1.58636 1.78664 2.54109 + vertex 1.58219 1.78598 2.54176 + vertex 1.5852 1.78199 2.54175 + endloop + endfacet + facet normal 0.231855 0.0783887 0.969587 + outer loop + vertex 1.58636 1.78664 2.54109 + vertex 1.5852 1.78199 2.54175 + vertex 1.58869 1.78464 2.5407 + endloop + endfacet + facet normal 0.249961 0.100767 0.962998 + outer loop + vertex 1.58869 1.78464 2.5407 + vertex 1.58973 1.78892 2.53998 + vertex 1.58636 1.78664 2.54109 + endloop + endfacet + facet normal 0.241045 0.114306 0.963759 + outer loop + vertex 1.58636 1.78664 2.54109 + vertex 1.58973 1.78892 2.53998 + vertex 1.58553 1.79041 2.54086 + endloop + endfacet + facet normal 0.234099 0.0922884 0.967823 + outer loop + vertex 1.58973 1.78892 2.53998 + vertex 1.58862 1.79399 2.53977 + vertex 1.58553 1.79041 2.54086 + endloop + endfacet + facet normal 0.209662 0.114338 0.971066 + outer loop + vertex 1.58553 1.79041 2.54086 + vertex 1.58862 1.79399 2.53977 + vertex 1.58453 1.79452 2.54059 + endloop + endfacet + facet normal 0.118877 0.0933844 0.988508 + outer loop + vertex 1.58453 1.79452 2.54059 + vertex 1.58136 1.79089 2.54131 + vertex 1.58553 1.79041 2.54086 + endloop + endfacet + facet normal 0.120607 0.110084 0.986578 + outer loop + vertex 1.58136 1.79089 2.54131 + vertex 1.58219 1.78598 2.54176 + vertex 1.58553 1.79041 2.54086 + endloop + endfacet + facet normal 0.0984169 0.111347 0.988896 + outer loop + vertex 1.58089 1.79448 2.54095 + vertex 1.58136 1.79089 2.54131 + vertex 1.58453 1.79452 2.54059 + endloop + endfacet + facet normal 0.0981861 0.121475 0.987726 + outer loop + vertex 1.58453 1.79452 2.54059 + vertex 1.58327 1.79733 2.54037 + vertex 1.58089 1.79448 2.54095 + endloop + endfacet + facet normal 0.168238 0.151625 0.974015 + outer loop + vertex 1.58327 1.79733 2.54037 + vertex 1.58453 1.79452 2.54059 + vertex 1.58723 1.79866 2.53947 + endloop + endfacet + facet normal 0.147997 0.207041 0.967073 + outer loop + vertex 1.58327 1.79733 2.54037 + vertex 1.58723 1.79866 2.53947 + vertex 1.58301 1.80123 2.53957 + endloop + endfacet + facet normal 0.12127 0.162651 0.979203 + outer loop + vertex 1.58301 1.80123 2.53957 + vertex 1.58723 1.79866 2.53947 + vertex 1.58813 1.80309 2.53863 + endloop + endfacet + facet normal 0.125844 0.15072 0.980534 + outer loop + vertex 1.58813 1.80309 2.53863 + vertex 1.58708 1.80687 2.53818 + vertex 1.58301 1.80123 2.53957 + endloop + endfacet + facet normal 0.0924375 0.1748 0.980255 + outer loop + vertex 1.58301 1.80123 2.53957 + vertex 1.58708 1.80687 2.53818 + vertex 1.58234 1.80677 2.53865 + endloop + endfacet + facet normal 0.093564 0.142896 0.985305 + outer loop + vertex 1.58708 1.80687 2.53818 + vertex 1.5859 1.81084 2.53772 + vertex 1.58234 1.80677 2.53865 + endloop + endfacet + facet normal 0.210509 0.122911 0.969834 + outer loop + vertex 1.58862 1.79399 2.53977 + vertex 1.58723 1.79866 2.53947 + vertex 1.58453 1.79452 2.54059 + endloop + endfacet + facet normal 0.244836 0.13251 0.960467 + outer loop + vertex 1.58862 1.79399 2.53977 + vertex 1.5918 1.79766 2.53845 + vertex 1.58723 1.79866 2.53947 + endloop + endfacet + facet normal 0.279974 0.0999957 0.954785 + outer loop + vertex 1.59281 1.79284 2.53866 + vertex 1.5918 1.79766 2.53845 + vertex 1.58862 1.79399 2.53977 + endloop + endfacet + facet normal 0.296959 0.103335 0.949282 + outer loop + vertex 1.59281 1.79284 2.53866 + vertex 1.59606 1.79642 2.53725 + vertex 1.5918 1.79766 2.53845 + endloop + endfacet + facet normal 0.2804 0.101844 0.954465 + outer loop + vertex 1.58973 1.78892 2.53998 + vertex 1.59281 1.79284 2.53866 + vertex 1.58862 1.79399 2.53977 + endloop + endfacet + facet normal 0.296123 0.0875885 0.951125 + outer loop + vertex 1.58869 1.78464 2.5407 + vertex 1.5925 1.78446 2.53953 + vertex 1.58973 1.78892 2.53998 + endloop + endfacet + facet normal 0.29807 0.0888733 0.950398 + outer loop + vertex 1.58973 1.78892 2.53998 + vertex 1.5925 1.78446 2.53953 + vertex 1.5936 1.78875 2.53878 + endloop + endfacet + facet normal 0.311016 0.0849176 0.946603 + outer loop + vertex 1.5925 1.78446 2.53953 + vertex 1.59595 1.78665 2.5382 + vertex 1.5936 1.78875 2.53878 + endloop + endfacet + facet normal 0.308722 0.0820686 0.947605 + outer loop + vertex 1.59595 1.78665 2.5382 + vertex 1.59711 1.79105 2.53744 + vertex 1.5936 1.78875 2.53878 + endloop + endfacet + facet normal 0.300786 0.0845662 0.949935 + outer loop + vertex 1.59711 1.79105 2.53744 + vertex 1.59595 1.78665 2.5382 + vertex 1.59994 1.78667 2.53693 + endloop + endfacet + facet normal 0.297204 0.0821001 0.951278 + outer loop + vertex 1.60112 1.79109 2.53618 + vertex 1.59711 1.79105 2.53744 + vertex 1.59994 1.78667 2.53693 + endloop + endfacet + facet normal 0.290399 0.0842517 0.95319 + outer loop + vertex 1.60112 1.79109 2.53618 + vertex 1.59994 1.78667 2.53693 + vertex 1.6035 1.78912 2.53563 + endloop + endfacet + facet normal 0.291356 0.085529 0.952784 + outer loop + vertex 1.6035 1.78912 2.53563 + vertex 1.60459 1.79351 2.5349 + vertex 1.60112 1.79109 2.53618 + endloop + endfacet + facet normal 0.288497 0.0898719 0.953254 + outer loop + vertex 1.60112 1.79109 2.53618 + vertex 1.60459 1.79351 2.5349 + vertex 1.60029 1.79512 2.53606 + endloop + endfacet + facet normal 0.292496 0.102384 0.95077 + outer loop + vertex 1.60459 1.79351 2.5349 + vertex 1.60339 1.79864 2.53472 + vertex 1.60029 1.79512 2.53606 + endloop + endfacet + facet normal 0.284084 0.100519 0.953516 + outer loop + vertex 1.60459 1.79351 2.5349 + vertex 1.60752 1.79759 2.5336 + vertex 1.60339 1.79864 2.53472 + endloop + endfacet + facet normal 0.284834 0.0999293 0.953354 + outer loop + vertex 1.60855 1.79366 2.53371 + vertex 1.60752 1.79759 2.5336 + vertex 1.60459 1.79351 2.5349 + endloop + endfacet + facet normal 0.285645 0.0868932 0.954388 + outer loop + vertex 1.60459 1.79351 2.5349 + vertex 1.60748 1.78924 2.53443 + vertex 1.60855 1.79366 2.53371 + endloop + endfacet + facet normal 0.284506 0.0872204 0.954698 + outer loop + vertex 1.60748 1.78924 2.53443 + vertex 1.61099 1.79171 2.53316 + vertex 1.60855 1.79366 2.53371 + endloop + endfacet + facet normal 0.289999 0.0947293 0.952327 + outer loop + vertex 1.61099 1.79171 2.53316 + vertex 1.61192 1.79615 2.53243 + vertex 1.60855 1.79366 2.53371 + endloop + endfacet + facet normal 0.285944 0.0957677 0.953449 + outer loop + vertex 1.61192 1.79615 2.53243 + vertex 1.61099 1.79171 2.53316 + vertex 1.61495 1.79178 2.53196 + endloop + endfacet + facet normal 0.284913 0.0950129 0.953833 + outer loop + vertex 1.61596 1.7962 2.53122 + vertex 1.61192 1.79615 2.53243 + vertex 1.61495 1.79178 2.53196 + endloop + endfacet + facet normal 0.282602 0.0956454 0.954457 + outer loop + vertex 1.61596 1.7962 2.53122 + vertex 1.61495 1.79178 2.53196 + vertex 1.61846 1.79419 2.53068 + endloop + endfacet + facet normal 0.28823 0.103286 0.951975 + outer loop + vertex 1.61846 1.79419 2.53068 + vertex 1.61937 1.79863 2.52992 + vertex 1.61596 1.7962 2.53122 + endloop + endfacet + facet normal 0.284271 0.109129 0.952513 + outer loop + vertex 1.61596 1.7962 2.53122 + vertex 1.61937 1.79863 2.52992 + vertex 1.61487 1.80023 2.53108 + endloop + endfacet + facet normal 0.287657 0.120336 0.950143 + outer loop + vertex 1.61937 1.79863 2.52992 + vertex 1.6178 1.80426 2.52969 + vertex 1.61487 1.80023 2.53108 + endloop + endfacet + facet normal 0.286885 0.120952 0.950299 + outer loop + vertex 1.61375 1.80425 2.53091 + vertex 1.61487 1.80023 2.53108 + vertex 1.6178 1.80426 2.52969 + endloop + endfacet + facet normal 0.286412 0.133361 0.94878 + outer loop + vertex 1.61375 1.80425 2.53091 + vertex 1.6178 1.80426 2.52969 + vertex 1.61459 1.80856 2.53005 + endloop + endfacet + facet normal 0.287155 0.133176 0.948581 + outer loop + vertex 1.61375 1.80425 2.53091 + vertex 1.61459 1.80856 2.53005 + vertex 1.6112 1.80624 2.5314 + endloop + endfacet + facet normal 0.282225 0.126259 0.951004 + outer loop + vertex 1.6112 1.80624 2.5314 + vertex 1.61036 1.80179 2.53224 + vertex 1.61375 1.80425 2.53091 + endloop + endfacet + facet normal 0.282393 0.126218 0.950959 + outer loop + vertex 1.6112 1.80624 2.5314 + vertex 1.60713 1.80624 2.53261 + vertex 1.61036 1.80179 2.53224 + endloop + endfacet + facet normal 0.285462 0.128547 0.94973 + outer loop + vertex 1.60713 1.80624 2.53261 + vertex 1.60617 1.80165 2.53352 + vertex 1.61036 1.80179 2.53224 + endloop + endfacet + facet normal 0.286432 0.114075 0.951285 + outer loop + vertex 1.60752 1.79759 2.5336 + vertex 1.61036 1.80179 2.53224 + vertex 1.60617 1.80165 2.53352 + endloop + endfacet + facet normal 0.286915 0.114233 0.951121 + outer loop + vertex 1.60752 1.79759 2.5336 + vertex 1.60617 1.80165 2.53352 + vertex 1.60339 1.79864 2.53472 + endloop + endfacet + facet normal 0.282459 0.118648 0.951913 + outer loop + vertex 1.60339 1.79864 2.53472 + vertex 1.60617 1.80165 2.53352 + vertex 1.60243 1.80392 2.53435 + endloop + endfacet + facet normal 0.294688 0.120593 0.947954 + outer loop + vertex 1.60339 1.79864 2.53472 + vertex 1.60243 1.80392 2.53435 + vertex 1.59927 1.8 2.53583 + endloop + endfacet + facet normal 0.290274 0.104514 0.951219 + outer loop + vertex 1.60029 1.79512 2.53606 + vertex 1.60339 1.79864 2.53472 + vertex 1.59927 1.8 2.53583 + endloop + endfacet + facet normal 0.300809 0.106537 0.947715 + outer loop + vertex 1.59927 1.8 2.53583 + vertex 1.59606 1.79642 2.53725 + vertex 1.60029 1.79512 2.53606 + endloop + endfacet + facet normal 0.296782 0.110485 0.948532 + outer loop + vertex 1.59494 1.80179 2.53698 + vertex 1.59606 1.79642 2.53725 + vertex 1.59927 1.8 2.53583 + endloop + endfacet + facet normal 0.300555 0.12123 0.946029 + outer loop + vertex 1.59927 1.8 2.53583 + vertex 1.59839 1.80407 2.53559 + vertex 1.59494 1.80179 2.53698 + endloop + endfacet + facet normal 0.296895 0.126998 0.946427 + outer loop + vertex 1.5959 1.80619 2.53608 + vertex 1.59494 1.80179 2.53698 + vertex 1.59839 1.80407 2.53559 + endloop + endfacet + facet normal 0.30129 0.132676 0.944257 + outer loop + vertex 1.59839 1.80407 2.53559 + vertex 1.59923 1.80849 2.5347 + vertex 1.5959 1.80619 2.53608 + endloop + endfacet + facet normal 0.298175 0.137363 0.944576 + outer loop + vertex 1.5959 1.80619 2.53608 + vertex 1.59923 1.80849 2.5347 + vertex 1.5948 1.81026 2.53584 + endloop + endfacet + facet normal 0.279492 0.132721 0.950931 + outer loop + vertex 1.5948 1.81026 2.53584 + vertex 1.59184 1.8061 2.53729 + vertex 1.5959 1.80619 2.53608 + endloop + endfacet + facet normal 0.258499 0.148925 0.954463 + outer loop + vertex 1.59028 1.81173 2.53683 + vertex 1.59184 1.8061 2.53729 + vertex 1.5948 1.81026 2.53584 + endloop + endfacet + facet normal 0.252547 0.127425 0.959157 + outer loop + vertex 1.5948 1.81026 2.53584 + vertex 1.59361 1.81433 2.53561 + vertex 1.59028 1.81173 2.53683 + endloop + endfacet + facet normal 0.246359 0.135579 0.959649 + outer loop + vertex 1.59098 1.81625 2.53602 + vertex 1.59028 1.81173 2.53683 + vertex 1.59361 1.81433 2.53561 + endloop + endfacet + facet normal 0.260336 0.156104 0.952815 + outer loop + vertex 1.59361 1.81433 2.53561 + vertex 1.59412 1.81847 2.53479 + vertex 1.59098 1.81625 2.53602 + endloop + endfacet + facet normal 0.244657 0.178444 0.953048 + outer loop + vertex 1.59098 1.81625 2.53602 + vertex 1.59412 1.81847 2.53479 + vertex 1.58968 1.81979 2.53569 + endloop + endfacet + facet normal 0.16002 0.149377 0.975746 + outer loop + vertex 1.58968 1.81979 2.53569 + vertex 1.58671 1.81559 2.53682 + vertex 1.59098 1.81625 2.53602 + endloop + endfacet + facet normal 0.126999 0.172975 0.976704 + outer loop + vertex 1.58535 1.82007 2.5362 + vertex 1.58671 1.81559 2.53682 + vertex 1.58968 1.81979 2.53569 + endloop + endfacet + facet normal 0.126082 0.153149 0.980127 + outer loop + vertex 1.58968 1.81979 2.53569 + vertex 1.58809 1.82306 2.53538 + vertex 1.58535 1.82007 2.5362 + endloop + endfacet + facet normal 0.197512 0.186212 0.962452 + outer loop + vertex 1.58809 1.82306 2.53538 + vertex 1.58968 1.81979 2.53569 + vertex 1.59241 1.82368 2.53437 + endloop + endfacet + facet normal 0.196652 0.190985 0.961693 + outer loop + vertex 1.58809 1.82306 2.53538 + vertex 1.59241 1.82368 2.53437 + vertex 1.58846 1.8271 2.5345 + endloop + endfacet + facet normal 0.17621 0.167096 0.970067 + outer loop + vertex 1.58846 1.8271 2.5345 + vertex 1.59241 1.82368 2.53437 + vertex 1.59294 1.8282 2.5335 + endloop + endfacet + facet normal 0.181641 0.146999 0.972316 + outer loop + vertex 1.59294 1.8282 2.5335 + vertex 1.59125 1.83118 2.53336 + vertex 1.58846 1.8271 2.5345 + endloop + endfacet + facet normal 0.124723 0.186523 0.974502 + outer loop + vertex 1.58846 1.8271 2.5345 + vertex 1.59125 1.83118 2.53336 + vertex 1.58733 1.83182 2.53374 + endloop + endfacet + facet normal 0.124421 0.184414 0.974941 + outer loop + vertex 1.59125 1.83118 2.53336 + vertex 1.59179 1.8359 2.5324 + vertex 1.58733 1.83182 2.53374 + endloop + endfacet + facet normal 0.1227 0.186255 0.97481 + outer loop + vertex 1.58733 1.83182 2.53374 + vertex 1.59179 1.8359 2.5324 + vertex 1.58669 1.83662 2.53291 + endloop + endfacet + facet normal 0.118721 0.153579 0.980978 + outer loop + vertex 1.59179 1.8359 2.5324 + vertex 1.59003 1.84142 2.53175 + vertex 1.58669 1.83662 2.53291 + endloop + endfacet + facet normal 0.0752944 0.183675 0.980099 + outer loop + vertex 1.58669 1.83662 2.53291 + vertex 1.59003 1.84142 2.53175 + vertex 1.58549 1.84049 2.53227 + endloop + endfacet + facet normal 0.0776292 0.173179 0.981826 + outer loop + vertex 1.58654 1.84464 2.53146 + vertex 1.58549 1.84049 2.53227 + vertex 1.59003 1.84142 2.53175 + endloop + endfacet + facet normal 0.0752359 0.170643 0.982456 + outer loop + vertex 1.59051 1.84561 2.53099 + vertex 1.58654 1.84464 2.53146 + vertex 1.59003 1.84142 2.53175 + endloop + endfacet + facet normal 0.16892 0.158331 0.97283 + outer loop + vertex 1.59051 1.84561 2.53099 + vertex 1.59003 1.84142 2.53175 + vertex 1.59333 1.84428 2.53071 + endloop + endfacet + facet normal 0.186646 0.197893 0.96229 + outer loop + vertex 1.59333 1.84428 2.53071 + vertex 1.59333 1.84853 2.52984 + vertex 1.59051 1.84561 2.53099 + endloop + endfacet + facet normal 0.146251 0.236367 0.960594 + outer loop + vertex 1.5889 1.84785 2.53068 + vertex 1.59051 1.84561 2.53099 + vertex 1.59333 1.84853 2.52984 + endloop + endfacet + facet normal 0.145211 0.241707 0.959423 + outer loop + vertex 1.5889 1.84785 2.53068 + vertex 1.59333 1.84853 2.52984 + vertex 1.58823 1.85167 2.52982 + endloop + endfacet + facet normal 0.0714068 0.185087 0.980124 + outer loop + vertex 1.59051 1.84561 2.53099 + vertex 1.5889 1.84785 2.53068 + vertex 1.58654 1.84464 2.53146 + endloop + endfacet + facet normal 0.187288 0.173736 0.966819 + outer loop + vertex 1.59003 1.84142 2.53175 + vertex 1.59179 1.8359 2.5324 + vertex 1.59481 1.84037 2.53101 + endloop + endfacet + facet normal 0.181649 0.143655 0.972814 + outer loop + vertex 1.59481 1.84037 2.53101 + vertex 1.59333 1.84428 2.53071 + vertex 1.59003 1.84142 2.53175 + endloop + endfacet + facet normal 0.254837 0.169754 0.951967 + outer loop + vertex 1.59333 1.84428 2.53071 + vertex 1.59481 1.84037 2.53101 + vertex 1.59746 1.84434 2.5296 + endloop + endfacet + facet normal 0.25326 0.194817 0.947579 + outer loop + vertex 1.59333 1.84428 2.53071 + vertex 1.59746 1.84434 2.5296 + vertex 1.59333 1.84853 2.52984 + endloop + endfacet + facet normal 0.230014 0.171339 0.957986 + outer loop + vertex 1.59333 1.84853 2.52984 + vertex 1.59746 1.84434 2.5296 + vertex 1.59789 1.84857 2.52874 + endloop + endfacet + facet normal 0.230644 0.158131 0.960103 + outer loop + vertex 1.59789 1.84857 2.52874 + vertex 1.59661 1.85161 2.52854 + vertex 1.59333 1.84853 2.52984 + endloop + endfacet + facet normal 0.206969 0.183615 0.960963 + outer loop + vertex 1.59333 1.84853 2.52984 + vertex 1.59661 1.85161 2.52854 + vertex 1.59348 1.85307 2.52894 + endloop + endfacet + facet normal 0.20588 0.181085 0.961676 + outer loop + vertex 1.59661 1.85161 2.52854 + vertex 1.59713 1.856 2.52761 + vertex 1.59348 1.85307 2.52894 + endloop + endfacet + facet normal 0.190846 0.199557 0.961122 + outer loop + vertex 1.59348 1.85307 2.52894 + vertex 1.59713 1.856 2.52761 + vertex 1.59202 1.85682 2.52845 + endloop + endfacet + facet normal 0.185082 0.153869 0.970602 + outer loop + vertex 1.59713 1.856 2.52761 + vertex 1.59521 1.86167 2.52707 + vertex 1.59202 1.85682 2.52845 + endloop + endfacet + facet normal 0.137524 0.185789 0.972918 + outer loop + vertex 1.59202 1.85682 2.52845 + vertex 1.59521 1.86167 2.52707 + vertex 1.59064 1.86065 2.52791 + endloop + endfacet + facet normal 0.139745 0.176917 0.974254 + outer loop + vertex 1.59159 1.86542 2.52691 + vertex 1.59064 1.86065 2.52791 + vertex 1.59521 1.86167 2.52707 + endloop + endfacet + facet normal 0.134626 0.17204 0.975847 + outer loop + vertex 1.59595 1.86623 2.52617 + vertex 1.59159 1.86542 2.52691 + vertex 1.59521 1.86167 2.52707 + endloop + endfacet + facet normal 0.225532 0.154554 0.961898 + outer loop + vertex 1.59595 1.86623 2.52617 + vertex 1.59521 1.86167 2.52707 + vertex 1.59862 1.86441 2.52583 + endloop + endfacet + facet normal 0.240922 0.178554 0.953978 + outer loop + vertex 1.59862 1.86441 2.52583 + vertex 1.59918 1.86852 2.52492 + vertex 1.59595 1.86623 2.52617 + endloop + endfacet + facet normal 0.226664 0.198477 0.953536 + outer loop + vertex 1.59595 1.86623 2.52617 + vertex 1.59918 1.86852 2.52492 + vertex 1.59477 1.86965 2.52574 + endloop + endfacet + facet normal 0.223418 0.183031 0.957384 + outer loop + vertex 1.59918 1.86852 2.52492 + vertex 1.59745 1.87352 2.52437 + vertex 1.59477 1.86965 2.52574 + endloop + endfacet + facet normal 0.186363 0.209545 0.959875 + outer loop + vertex 1.59332 1.87267 2.52536 + vertex 1.59477 1.86965 2.52574 + vertex 1.59745 1.87352 2.52437 + endloop + endfacet + facet normal 0.175814 0.251442 0.95177 + outer loop + vertex 1.59332 1.87267 2.52536 + vertex 1.59745 1.87352 2.52437 + vertex 1.59286 1.87645 2.52444 + endloop + endfacet + facet normal 0.115867 0.177959 0.977193 + outer loop + vertex 1.59477 1.86965 2.52574 + vertex 1.59332 1.87267 2.52536 + vertex 1.59079 1.86983 2.52618 + endloop + endfacet + facet normal 0.116019 0.184102 0.976036 + outer loop + vertex 1.59079 1.86983 2.52618 + vertex 1.59159 1.86542 2.52691 + vertex 1.59477 1.86965 2.52574 + endloop + endfacet + facet normal 0.252446 0.192074 0.948356 + outer loop + vertex 1.59918 1.86852 2.52492 + vertex 1.6016 1.87173 2.52363 + vertex 1.59745 1.87352 2.52437 + endloop + endfacet + facet normal 0.247602 0.179288 0.952129 + outer loop + vertex 1.6016 1.87173 2.52363 + vertex 1.60214 1.87623 2.52264 + vertex 1.59745 1.87352 2.52437 + endloop + endfacet + facet normal 0.244176 0.185085 0.951904 + outer loop + vertex 1.59745 1.87352 2.52437 + vertex 1.60214 1.87623 2.52264 + vertex 1.59783 1.87802 2.5234 + endloop + endfacet + facet normal 0.141804 0.19775 0.969941 + outer loop + vertex 1.59286 1.87645 2.52444 + vertex 1.59745 1.87352 2.52437 + vertex 1.59783 1.87802 2.5234 + endloop + endfacet + facet normal 0.147158 0.182258 0.972176 + outer loop + vertex 1.59783 1.87802 2.5234 + vertex 1.59588 1.88099 2.52314 + vertex 1.59286 1.87645 2.52444 + endloop + endfacet + facet normal 0.0811156 0.225718 0.97081 + outer loop + vertex 1.59286 1.87645 2.52444 + vertex 1.59588 1.88099 2.52314 + vertex 1.59178 1.88149 2.52336 + endloop + endfacet + facet normal 0.0795828 0.211665 0.974097 + outer loop + vertex 1.59588 1.88099 2.52314 + vertex 1.59582 1.88593 2.52207 + vertex 1.59178 1.88149 2.52336 + endloop + endfacet + facet normal 0.0611204 0.227789 0.97179 + outer loop + vertex 1.59178 1.88149 2.52336 + vertex 1.59582 1.88593 2.52207 + vertex 1.59054 1.88537 2.52253 + endloop + endfacet + facet normal 0.0648452 0.197961 0.978063 + outer loop + vertex 1.5916 1.88965 2.52159 + vertex 1.59054 1.88537 2.52253 + vertex 1.59582 1.88593 2.52207 + endloop + endfacet + facet normal 0.0592712 0.191842 0.979634 + outer loop + vertex 1.59586 1.8905 2.52117 + vertex 1.5916 1.88965 2.52159 + vertex 1.59582 1.88593 2.52207 + endloop + endfacet + facet normal 0.142678 0.189394 0.97148 + outer loop + vertex 1.59586 1.8905 2.52117 + vertex 1.59582 1.88593 2.52207 + vertex 1.59895 1.88927 2.52096 + endloop + endfacet + facet normal 0.152293 0.214522 0.964773 + outer loop + vertex 1.59895 1.88927 2.52096 + vertex 1.59873 1.89361 2.52003 + vertex 1.59586 1.8905 2.52117 + endloop + endfacet + facet normal 0.123026 0.240712 0.962768 + outer loop + vertex 1.59402 1.89294 2.5208 + vertex 1.59586 1.8905 2.52117 + vertex 1.59873 1.89361 2.52003 + endloop + endfacet + facet normal 0.0586842 0.194538 0.979138 + outer loop + vertex 1.59586 1.8905 2.52117 + vertex 1.59402 1.89294 2.5208 + vertex 1.5916 1.88965 2.52159 + endloop + endfacet + facet normal 0.185168 0.206271 0.960815 + outer loop + vertex 1.59783 1.87802 2.5234 + vertex 1.60021 1.88192 2.5221 + vertex 1.59588 1.88099 2.52314 + endloop + endfacet + facet normal 0.184239 0.20993 0.960201 + outer loop + vertex 1.59582 1.88593 2.52207 + vertex 1.59588 1.88099 2.52314 + vertex 1.60021 1.88192 2.5221 + endloop + endfacet + facet normal 0.161575 0.185171 0.969332 + outer loop + vertex 1.60048 1.88628 2.52122 + vertex 1.59582 1.88593 2.52207 + vertex 1.60021 1.88192 2.5221 + endloop + endfacet + facet normal 0.246771 0.176633 0.95284 + outer loop + vertex 1.60048 1.88628 2.52122 + vertex 1.60021 1.88192 2.5221 + vertex 1.6034 1.88441 2.52082 + endloop + endfacet + facet normal 0.255351 0.19108 0.947779 + outer loop + vertex 1.6034 1.88441 2.52082 + vertex 1.60342 1.88896 2.51989 + vertex 1.60048 1.88628 2.52122 + endloop + endfacet + facet normal 0.240239 0.207869 0.948196 + outer loop + vertex 1.59895 1.88927 2.52096 + vertex 1.60048 1.88628 2.52122 + vertex 1.60342 1.88896 2.51989 + endloop + endfacet + facet normal 0.240342 0.215063 0.946564 + outer loop + vertex 1.59895 1.88927 2.52096 + vertex 1.60342 1.88896 2.51989 + vertex 1.59873 1.89361 2.52003 + endloop + endfacet + facet normal 0.294672 0.18863 0.936796 + outer loop + vertex 1.6034 1.88441 2.52082 + vertex 1.60746 1.88414 2.51959 + vertex 1.60342 1.88896 2.51989 + endloop + endfacet + facet normal 0.28319 0.178675 0.942273 + outer loop + vertex 1.60342 1.88896 2.51989 + vertex 1.60746 1.88414 2.51959 + vertex 1.60782 1.88839 2.51868 + endloop + endfacet + facet normal 0.282531 0.169634 0.94414 + outer loop + vertex 1.60782 1.88839 2.51868 + vertex 1.60657 1.89155 2.51848 + vertex 1.60342 1.88896 2.51989 + endloop + endfacet + facet normal 0.2746 0.179544 0.944648 + outer loop + vertex 1.60342 1.88896 2.51989 + vertex 1.60657 1.89155 2.51848 + vertex 1.60361 1.89354 2.51897 + endloop + endfacet + facet normal 0.211171 0.185246 0.959735 + outer loop + vertex 1.59873 1.89361 2.52003 + vertex 1.60342 1.88896 2.51989 + vertex 1.60361 1.89354 2.51897 + endloop + endfacet + facet normal 0.211603 0.166065 0.963144 + outer loop + vertex 1.60361 1.89354 2.51897 + vertex 1.60225 1.89746 2.51859 + vertex 1.59873 1.89361 2.52003 + endloop + endfacet + facet normal 0.191138 0.185095 0.963953 + outer loop + vertex 1.59873 1.89361 2.52003 + vertex 1.60225 1.89746 2.51859 + vertex 1.5984 1.89833 2.51919 + endloop + endfacet + facet normal 0.187245 0.164541 0.968435 + outer loop + vertex 1.60225 1.89746 2.51859 + vertex 1.60072 1.90123 2.51824 + vertex 1.5984 1.89833 2.51919 + endloop + endfacet + facet normal 0.140141 0.202439 0.969216 + outer loop + vertex 1.5984 1.89833 2.51919 + vertex 1.60072 1.90123 2.51824 + vertex 1.59695 1.90182 2.51867 + endloop + endfacet + facet normal 0.139544 0.197852 0.970248 + outer loop + vertex 1.60072 1.90123 2.51824 + vertex 1.60084 1.90609 2.51724 + vertex 1.59695 1.90182 2.51867 + endloop + endfacet + facet normal 0.124118 0.211629 0.969437 + outer loop + vertex 1.59695 1.90182 2.51867 + vertex 1.60084 1.90609 2.51724 + vertex 1.59585 1.90548 2.51801 + endloop + endfacet + facet normal 0.127184 0.191118 0.973292 + outer loop + vertex 1.59685 1.91019 2.51695 + vertex 1.59585 1.90548 2.51801 + vertex 1.60084 1.90609 2.51724 + endloop + endfacet + facet normal 0.118879 0.183215 0.975859 + outer loop + vertex 1.60134 1.91096 2.51626 + vertex 1.59685 1.91019 2.51695 + vertex 1.60084 1.90609 2.51724 + endloop + endfacet + facet normal 0.206888 0.171622 0.963194 + outer loop + vertex 1.60134 1.91096 2.51626 + vertex 1.60084 1.90609 2.51724 + vertex 1.60413 1.90933 2.51595 + endloop + endfacet + facet normal 0.219194 0.194015 0.956197 + outer loop + vertex 1.60413 1.90933 2.51595 + vertex 1.60452 1.91338 2.51504 + vertex 1.60134 1.91096 2.51626 + endloop + endfacet + facet normal 0.204179 0.213325 0.955408 + outer loop + vertex 1.60134 1.91096 2.51626 + vertex 1.60452 1.91338 2.51504 + vertex 1.60001 1.91443 2.51577 + endloop + endfacet + facet normal 0.201078 0.196999 0.959562 + outer loop + vertex 1.60452 1.91338 2.51504 + vertex 1.60254 1.9184 2.51442 + vertex 1.60001 1.91443 2.51577 + endloop + endfacet + facet normal 0.160501 0.223464 0.961407 + outer loop + vertex 1.59846 1.91747 2.51532 + vertex 1.60001 1.91443 2.51577 + vertex 1.60254 1.9184 2.51442 + endloop + endfacet + facet normal 0.149526 0.263321 0.95305 + outer loop + vertex 1.59846 1.91747 2.51532 + vertex 1.60254 1.9184 2.51442 + vertex 1.59786 1.92131 2.51435 + endloop + endfacet + facet normal 0.0983273 0.194044 0.976053 + outer loop + vertex 1.60001 1.91443 2.51577 + vertex 1.59846 1.91747 2.51532 + vertex 1.59597 1.91465 2.51613 + endloop + endfacet + facet normal 0.0984904 0.198372 0.975166 + outer loop + vertex 1.59597 1.91465 2.51613 + vertex 1.59685 1.91019 2.51695 + vertex 1.60001 1.91443 2.51577 + endloop + endfacet + facet normal 0.118845 0.183385 0.975831 + outer loop + vertex 1.60001 1.91443 2.51577 + vertex 1.59685 1.91019 2.51695 + vertex 1.60134 1.91096 2.51626 + endloop + endfacet + facet normal 0.236704 0.191786 0.952465 + outer loop + vertex 1.60084 1.90609 2.51724 + vertex 1.60072 1.90123 2.51824 + vertex 1.6049 1.90168 2.51711 + endloop + endfacet + facet normal 0.21941 0.175618 0.959697 + outer loop + vertex 1.60532 1.9062 2.51619 + vertex 1.60084 1.90609 2.51724 + vertex 1.6049 1.90168 2.51711 + endloop + endfacet + facet normal 0.279505 0.167111 0.94549 + outer loop + vertex 1.60532 1.9062 2.51619 + vertex 1.6049 1.90168 2.51711 + vertex 1.60815 1.9042 2.51571 + endloop + endfacet + facet normal 0.284478 0.174824 0.942608 + outer loop + vertex 1.60815 1.9042 2.51571 + vertex 1.60835 1.90893 2.51477 + vertex 1.60532 1.9062 2.51619 + endloop + endfacet + facet normal 0.280812 0.179049 0.942914 + outer loop + vertex 1.60413 1.90933 2.51595 + vertex 1.60532 1.9062 2.51619 + vertex 1.60835 1.90893 2.51477 + endloop + endfacet + facet normal 0.281032 0.184763 0.941745 + outer loop + vertex 1.60413 1.90933 2.51595 + vertex 1.60835 1.90893 2.51477 + vertex 1.60452 1.91338 2.51504 + endloop + endfacet + facet normal 0.272273 0.17699 0.945802 + outer loop + vertex 1.60452 1.91338 2.51504 + vertex 1.60835 1.90893 2.51477 + vertex 1.60836 1.91352 2.51391 + endloop + endfacet + facet normal 0.272044 0.179689 0.945359 + outer loop + vertex 1.60836 1.91352 2.51391 + vertex 1.60674 1.91672 2.51377 + vertex 1.60452 1.91338 2.51504 + endloop + endfacet + facet normal 0.232163 0.208104 0.950154 + outer loop + vertex 1.60452 1.91338 2.51504 + vertex 1.60674 1.91672 2.51377 + vertex 1.60254 1.9184 2.51442 + endloop + endfacet + facet normal 0.2283 0.197207 0.953409 + outer loop + vertex 1.60674 1.91672 2.51377 + vertex 1.60712 1.92122 2.51275 + vertex 1.60254 1.9184 2.51442 + endloop + endfacet + facet normal 0.223627 0.204545 0.95297 + outer loop + vertex 1.60254 1.9184 2.51442 + vertex 1.60712 1.92122 2.51275 + vertex 1.60276 1.92287 2.51341 + endloop + endfacet + facet normal 0.219276 0.191642 0.956656 + outer loop + vertex 1.60712 1.92122 2.51275 + vertex 1.6051 1.92668 2.51211 + vertex 1.60276 1.92287 2.51341 + endloop + endfacet + facet normal 0.159019 0.229788 0.960162 + outer loop + vertex 1.60276 1.92287 2.51341 + vertex 1.6051 1.92668 2.51211 + vertex 1.60079 1.92565 2.51308 + endloop + endfacet + facet normal 0.158498 0.231634 0.959804 + outer loop + vertex 1.60101 1.92995 2.512 + vertex 1.60079 1.92565 2.51308 + vertex 1.6051 1.92668 2.51211 + endloop + endfacet + facet normal 0.138149 0.206465 0.968652 + outer loop + vertex 1.6053 1.9309 2.51119 + vertex 1.60101 1.92995 2.512 + vertex 1.6051 1.92668 2.51211 + endloop + endfacet + facet normal 0.223636 0.199077 0.954125 + outer loop + vertex 1.6053 1.9309 2.51119 + vertex 1.6051 1.92668 2.51211 + vertex 1.60826 1.9293 2.51083 + endloop + endfacet + facet normal 0.231404 0.214621 0.948889 + outer loop + vertex 1.60826 1.9293 2.51083 + vertex 1.60822 1.93376 2.50983 + vertex 1.6053 1.9309 2.51119 + endloop + endfacet + facet normal 0.197352 0.248963 0.948193 + outer loop + vertex 1.60358 1.93353 2.51085 + vertex 1.6053 1.9309 2.51119 + vertex 1.60822 1.93376 2.50983 + endloop + endfacet + facet normal 0.198836 0.234471 0.951571 + outer loop + vertex 1.60358 1.93353 2.51085 + vertex 1.60822 1.93376 2.50983 + vertex 1.60377 1.93752 2.50983 + endloop + endfacet + facet normal 0.17537 0.206643 0.962572 + outer loop + vertex 1.60377 1.93752 2.50983 + vertex 1.60822 1.93376 2.50983 + vertex 1.60813 1.93823 2.50888 + endloop + endfacet + facet normal 0.175329 0.206847 0.962535 + outer loop + vertex 1.60813 1.93823 2.50888 + vertex 1.60641 1.94108 2.50859 + vertex 1.60377 1.93752 2.50983 + endloop + endfacet + facet normal 0.134698 0.236837 0.962167 + outer loop + vertex 1.60377 1.93752 2.50983 + vertex 1.60641 1.94108 2.50859 + vertex 1.60232 1.94204 2.50892 + endloop + endfacet + facet normal 0.134215 0.234572 0.962789 + outer loop + vertex 1.60641 1.94108 2.50859 + vertex 1.60674 1.94543 2.50748 + vertex 1.60232 1.94204 2.50892 + endloop + endfacet + facet normal 0.223827 0.224071 0.948522 + outer loop + vertex 1.60674 1.94543 2.50748 + vertex 1.60641 1.94108 2.50859 + vertex 1.61105 1.94131 2.50744 + endloop + endfacet + facet normal 0.207549 0.206942 0.956085 + outer loop + vertex 1.61118 1.94594 2.5064 + vertex 1.60674 1.94543 2.50748 + vertex 1.61105 1.94131 2.50744 + endloop + endfacet + facet normal 0.26641 0.20227 0.942397 + outer loop + vertex 1.61118 1.94594 2.5064 + vertex 1.61105 1.94131 2.50744 + vertex 1.61409 1.94413 2.50597 + endloop + endfacet + facet normal 0.269856 0.208353 0.940089 + outer loop + vertex 1.61409 1.94413 2.50597 + vertex 1.61428 1.94826 2.505 + vertex 1.61118 1.94594 2.5064 + endloop + endfacet + facet normal 0.25825 0.223691 0.939824 + outer loop + vertex 1.61118 1.94594 2.5064 + vertex 1.61428 1.94826 2.505 + vertex 1.60957 1.94967 2.50596 + endloop + endfacet + facet normal 0.254438 0.207736 0.944514 + outer loop + vertex 1.61428 1.94826 2.505 + vertex 1.61213 1.95359 2.50441 + vertex 1.60957 1.94967 2.50596 + endloop + endfacet + facet normal 0.224095 0.228635 0.947369 + outer loop + vertex 1.60789 1.95323 2.5055 + vertex 1.60957 1.94967 2.50596 + vertex 1.61213 1.95359 2.50441 + endloop + endfacet + facet normal 0.222613 0.239285 0.945085 + outer loop + vertex 1.60789 1.95323 2.5055 + vertex 1.61213 1.95359 2.50441 + vertex 1.60839 1.95724 2.50437 + endloop + endfacet + facet normal 0.202614 0.218903 0.954478 + outer loop + vertex 1.60839 1.95724 2.50437 + vertex 1.61213 1.95359 2.50441 + vertex 1.6122 1.95724 2.50356 + endloop + endfacet + facet normal 0.201965 0.232351 0.951432 + outer loop + vertex 1.6122 1.95724 2.50356 + vertex 1.61206 1.96091 2.50269 + vertex 1.60839 1.95724 2.50437 + endloop + endfacet + facet normal 0.181588 0.252292 0.95046 + outer loop + vertex 1.60839 1.95724 2.50437 + vertex 1.61206 1.96091 2.50269 + vertex 1.60686 1.96185 2.50343 + endloop + endfacet + facet normal 0.176109 0.213991 0.96083 + outer loop + vertex 1.61206 1.96091 2.50269 + vertex 1.60978 1.96619 2.50193 + vertex 1.60686 1.96185 2.50343 + endloop + endfacet + facet normal 0.1231 0.249612 0.96049 + outer loop + vertex 1.60686 1.96185 2.50343 + vertex 1.60978 1.96619 2.50193 + vertex 1.60529 1.96543 2.50271 + endloop + endfacet + facet normal 0.125231 0.239394 0.962812 + outer loop + vertex 1.60625 1.96941 2.50159 + vertex 1.60529 1.96543 2.50271 + vertex 1.60978 1.96619 2.50193 + endloop + endfacet + facet normal 0.117963 0.231722 0.965603 + outer loop + vertex 1.61014 1.97028 2.50091 + vertex 1.60625 1.96941 2.50159 + vertex 1.60978 1.96619 2.50193 + endloop + endfacet + facet normal 0.197589 0.221945 0.954829 + outer loop + vertex 1.61014 1.97028 2.50091 + vertex 1.60978 1.96619 2.50193 + vertex 1.61294 1.96891 2.50065 + endloop + endfacet + facet normal 0.210321 0.249865 0.945163 + outer loop + vertex 1.61294 1.96891 2.50065 + vertex 1.61297 1.97313 2.49952 + vertex 1.61014 1.97028 2.50091 + endloop + endfacet + facet normal 0.176445 0.282321 0.942954 + outer loop + vertex 1.60857 1.97258 2.50051 + vertex 1.61014 1.97028 2.50091 + vertex 1.61297 1.97313 2.49952 + endloop + endfacet + facet normal 0.173793 0.296501 0.939086 + outer loop + vertex 1.60857 1.97258 2.50051 + vertex 1.61297 1.97313 2.49952 + vertex 1.60779 1.97633 2.49947 + endloop + endfacet + facet normal 0.13715 0.23754 0.961647 + outer loop + vertex 1.60779 1.97633 2.49947 + vertex 1.61297 1.97313 2.49952 + vertex 1.61275 1.97774 2.49842 + endloop + endfacet + facet normal 0.140264 0.227985 0.963509 + outer loop + vertex 1.61275 1.97774 2.49842 + vertex 1.61065 1.98049 2.49807 + vertex 1.60779 1.97633 2.49947 + endloop + endfacet + facet normal 0.214044 0.203122 0.955472 + outer loop + vertex 1.61458 1.96503 2.5011 + vertex 1.61294 1.96891 2.50065 + vertex 1.60978 1.96619 2.50193 + endloop + endfacet + facet normal 0.264759 0.222535 0.938286 + outer loop + vertex 1.61294 1.96891 2.50065 + vertex 1.61458 1.96503 2.5011 + vertex 1.61706 1.96884 2.4995 + endloop + endfacet + facet normal 0.263578 0.246227 0.932684 + outer loop + vertex 1.61294 1.96891 2.50065 + vertex 1.61706 1.96884 2.4995 + vertex 1.61297 1.97313 2.49952 + endloop + endfacet + facet normal 0.238166 0.221922 0.94553 + outer loop + vertex 1.61297 1.97313 2.49952 + vertex 1.61706 1.96884 2.4995 + vertex 1.6171 1.97255 2.49862 + endloop + endfacet + facet normal 0.238658 0.227856 0.943994 + outer loop + vertex 1.6171 1.97255 2.49862 + vertex 1.61715 1.97622 2.49772 + vertex 1.61297 1.97313 2.49952 + endloop + endfacet + facet normal 0.231276 0.237534 0.943445 + outer loop + vertex 1.61297 1.97313 2.49952 + vertex 1.61715 1.97622 2.49772 + vertex 1.61275 1.97774 2.49842 + endloop + endfacet + facet normal 0.225461 0.217948 0.949561 + outer loop + vertex 1.61715 1.97622 2.49772 + vertex 1.61496 1.98147 2.49704 + vertex 1.61275 1.97774 2.49842 + endloop + endfacet + facet normal 0.171827 0.250778 0.952673 + outer loop + vertex 1.61275 1.97774 2.49842 + vertex 1.61496 1.98147 2.49704 + vertex 1.61065 1.98049 2.49807 + endloop + endfacet + facet normal 0.170902 0.254113 0.951955 + outer loop + vertex 1.61088 1.98468 2.49691 + vertex 1.61065 1.98049 2.49807 + vertex 1.61496 1.98147 2.49704 + endloop + endfacet + facet normal 0.152884 0.231633 0.960715 + outer loop + vertex 1.61515 1.98557 2.49602 + vertex 1.61088 1.98468 2.49691 + vertex 1.61496 1.98147 2.49704 + endloop + endfacet + facet normal 0.233601 0.224181 0.946136 + outer loop + vertex 1.61515 1.98557 2.49602 + vertex 1.61496 1.98147 2.49704 + vertex 1.61803 1.98401 2.49568 + endloop + endfacet + facet normal 0.241778 0.240571 0.940037 + outer loop + vertex 1.61803 1.98401 2.49568 + vertex 1.6181 1.98836 2.49455 + vertex 1.61515 1.98557 2.49602 + endloop + endfacet + facet normal 0.209646 0.27382 0.938654 + outer loop + vertex 1.61347 1.98821 2.49562 + vertex 1.61515 1.98557 2.49602 + vertex 1.6181 1.98836 2.49455 + endloop + endfacet + facet normal 0.210265 0.267306 0.940391 + outer loop + vertex 1.61347 1.98821 2.49562 + vertex 1.6181 1.98836 2.49455 + vertex 1.61356 1.99222 2.49446 + endloop + endfacet + facet normal 0.18469 0.23753 0.953661 + outer loop + vertex 1.61356 1.99222 2.49446 + vertex 1.6181 1.98836 2.49455 + vertex 1.61795 1.99299 2.49342 + endloop + endfacet + facet normal 0.185502 0.233924 0.954394 + outer loop + vertex 1.61795 1.99299 2.49342 + vertex 1.61584 1.99584 2.49313 + vertex 1.61356 1.99222 2.49446 + endloop + endfacet + facet normal 0.217988 0.256673 0.941595 + outer loop + vertex 1.61795 1.99299 2.49342 + vertex 1.61992 1.99647 2.49202 + vertex 1.61584 1.99584 2.49313 + endloop + endfacet + facet normal 0.215834 0.266578 0.939336 + outer loop + vertex 1.61583 1.99983 2.492 + vertex 1.61584 1.99584 2.49313 + vertex 1.61992 1.99647 2.49202 + endloop + endfacet + facet normal 0.19471 0.240877 0.950824 + outer loop + vertex 1.61995 2.00051 2.49099 + vertex 1.61583 1.99983 2.492 + vertex 1.61992 1.99647 2.49202 + endloop + endfacet + facet normal 0.255766 0.236955 0.937249 + outer loop + vertex 1.61995 2.00051 2.49099 + vertex 1.61992 1.99647 2.49202 + vertex 1.62285 1.9989 2.4906 + endloop + endfacet + facet normal 0.259857 0.245122 0.934018 + outer loop + vertex 1.62285 1.9989 2.4906 + vertex 1.62274 2.00321 2.4895 + vertex 1.61995 2.00051 2.49099 + endloop + endfacet + facet normal 0.237712 0.267812 0.933686 + outer loop + vertex 1.61827 2.00317 2.49065 + vertex 1.61995 2.00051 2.49099 + vertex 1.62274 2.00321 2.4895 + endloop + endfacet + facet normal 0.238201 0.261461 0.93536 + outer loop + vertex 1.61827 2.00317 2.49065 + vertex 1.62274 2.00321 2.4895 + vertex 1.61855 2.0071 2.48948 + endloop + endfacet + facet normal 0.215713 0.237316 0.947179 + outer loop + vertex 1.61855 2.0071 2.48948 + vertex 1.62274 2.00321 2.4895 + vertex 1.6224 2.00706 2.48862 + endloop + endfacet + facet normal 0.21523 0.248244 0.944485 + outer loop + vertex 1.6224 2.00706 2.48862 + vertex 1.62215 2.01071 2.48771 + vertex 1.61855 2.0071 2.48948 + endloop + endfacet + facet normal 0.196926 0.266136 0.943606 + outer loop + vertex 1.61855 2.0071 2.48948 + vertex 1.62215 2.01071 2.48771 + vertex 1.61691 2.01188 2.48848 + endloop + endfacet + facet normal 0.190941 0.232829 0.953589 + outer loop + vertex 1.62215 2.01071 2.48771 + vertex 1.62024 2.01548 2.48693 + vertex 1.61691 2.01188 2.48848 + endloop + endfacet + facet normal 0.144523 0.274479 0.95067 + outer loop + vertex 1.61691 2.01188 2.48848 + vertex 1.62024 2.01548 2.48693 + vertex 1.61526 2.01652 2.48739 + endloop + endfacet + facet normal 0.140483 0.251957 0.957488 + outer loop + vertex 1.62024 2.01548 2.48693 + vertex 1.61929 2.01967 2.48597 + vertex 1.61526 2.01652 2.48739 + endloop + endfacet + facet normal 0.20095 0.262608 0.943746 + outer loop + vertex 1.6229 2.01831 2.48558 + vertex 1.61929 2.01967 2.48597 + vertex 1.62024 2.01548 2.48693 + endloop + endfacet + facet normal 0.204355 0.272689 0.940149 + outer loop + vertex 1.61929 2.01967 2.48597 + vertex 1.6229 2.01831 2.48558 + vertex 1.62308 2.02231 2.48438 + endloop + endfacet + facet normal 0.182839 0.301072 0.935909 + outer loop + vertex 1.61783 2.02384 2.48491 + vertex 1.61929 2.01967 2.48597 + vertex 1.62308 2.02231 2.48438 + endloop + endfacet + facet normal 0.171357 0.25626 0.951298 + outer loop + vertex 1.62308 2.02231 2.48438 + vertex 1.62121 2.02635 2.48363 + vertex 1.61783 2.02384 2.48491 + endloop + endfacet + facet normal 0.144828 0.289344 0.946206 + outer loop + vertex 1.61783 2.02384 2.48491 + vertex 1.62121 2.02635 2.48363 + vertex 1.61783 2.02774 2.48372 + endloop + endfacet + facet normal 0.143216 0.285319 0.947672 + outer loop + vertex 1.62121 2.02635 2.48363 + vertex 1.62094 2.03081 2.48232 + vertex 1.61783 2.02774 2.48372 + endloop + endfacet + facet normal 0.275689 0.248377 0.928603 + outer loop + vertex 1.62215 2.01071 2.48771 + vertex 1.6224 2.00706 2.48862 + vertex 1.62632 2.00647 2.48761 + endloop + endfacet + facet normal 0.26207 0.234817 0.936045 + outer loop + vertex 1.62623 2.01096 2.48651 + vertex 1.62215 2.01071 2.48771 + vertex 1.62632 2.00647 2.48761 + endloop + endfacet + facet normal 0.291111 0.233343 0.927796 + outer loop + vertex 1.62623 2.01096 2.48651 + vertex 1.62632 2.00647 2.48761 + vertex 1.62914 2.00908 2.48607 + endloop + endfacet + facet normal 0.292792 0.236219 0.926538 + outer loop + vertex 1.62914 2.00908 2.48607 + vertex 1.62922 2.01311 2.48501 + vertex 1.62623 2.01096 2.48651 + endloop + endfacet + facet normal 0.288905 0.241523 0.926391 + outer loop + vertex 1.62623 2.01096 2.48651 + vertex 1.62922 2.01311 2.48501 + vertex 1.62462 2.01468 2.48604 + endloop + endfacet + facet normal 0.288043 0.238257 0.927505 + outer loop + vertex 1.62922 2.01311 2.48501 + vertex 1.62696 2.01844 2.48435 + vertex 1.62462 2.01468 2.48604 + endloop + endfacet + facet normal 0.273437 0.248168 0.929325 + outer loop + vertex 1.6229 2.01831 2.48558 + vertex 1.62462 2.01468 2.48604 + vertex 1.62696 2.01844 2.48435 + endloop + endfacet + facet normal 0.271611 0.265225 0.925139 + outer loop + vertex 1.6229 2.01831 2.48558 + vertex 1.62696 2.01844 2.48435 + vertex 1.62308 2.02231 2.48438 + endloop + endfacet + facet normal 0.253472 0.246963 0.935287 + outer loop + vertex 1.62308 2.02231 2.48438 + vertex 1.62696 2.01844 2.48435 + vertex 1.62676 2.02216 2.48342 + endloop + endfacet + facet normal 0.253072 0.260963 0.931586 + outer loop + vertex 1.62676 2.02216 2.48342 + vertex 1.626 2.02618 2.4825 + vertex 1.62308 2.02231 2.48438 + endloop + endfacet + facet normal 0.22905 0.27944 0.932443 + outer loop + vertex 1.62308 2.02231 2.48438 + vertex 1.626 2.02618 2.4825 + vertex 1.62121 2.02635 2.48363 + endloop + endfacet + facet normal 0.228841 0.285515 0.930652 + outer loop + vertex 1.62094 2.03081 2.48232 + vertex 1.62121 2.02635 2.48363 + vertex 1.626 2.02618 2.4825 + endloop + endfacet + facet normal 0.19586 0.250136 0.948194 + outer loop + vertex 1.62558 2.03084 2.48136 + vertex 1.62094 2.03081 2.48232 + vertex 1.626 2.02618 2.4825 + endloop + endfacet + facet normal 0.258706 0.251955 0.932518 + outer loop + vertex 1.62558 2.03084 2.48136 + vertex 1.626 2.02618 2.4825 + vertex 1.62876 2.02903 2.48096 + endloop + endfacet + facet normal 0.262422 0.259153 0.929502 + outer loop + vertex 1.62876 2.02903 2.48096 + vertex 1.62834 2.03356 2.47982 + vertex 1.62558 2.03084 2.48136 + endloop + endfacet + facet normal 0.246208 0.275514 0.929233 + outer loop + vertex 1.62373 2.0339 2.48094 + vertex 1.62558 2.03084 2.48136 + vertex 1.62834 2.03356 2.47982 + endloop + endfacet + facet normal 0.246213 0.293776 0.923621 + outer loop + vertex 1.62373 2.0339 2.48094 + vertex 1.62834 2.03356 2.47982 + vertex 1.62324 2.03811 2.47973 + endloop + endfacet + facet normal 0.209669 0.253312 0.94439 + outer loop + vertex 1.62324 2.03811 2.47973 + vertex 1.62834 2.03356 2.47982 + vertex 1.62794 2.03813 2.47868 + endloop + endfacet + facet normal 0.209867 0.250026 0.945221 + outer loop + vertex 1.62794 2.03813 2.47868 + vertex 1.6261 2.04124 2.47827 + vertex 1.62324 2.03811 2.47973 + endloop + endfacet + facet normal 0.179584 0.277144 0.943897 + outer loop + vertex 1.62324 2.03811 2.47973 + vertex 1.6261 2.04124 2.47827 + vertex 1.62276 2.0425 2.47853 + endloop + endfacet + facet normal 0.17947 0.276816 0.944015 + outer loop + vertex 1.6261 2.04124 2.47827 + vertex 1.62571 2.04562 2.47706 + vertex 1.62276 2.0425 2.47853 + endloop + endfacet + facet normal 0.143029 0.309467 0.940092 + outer loop + vertex 1.62276 2.0425 2.47853 + vertex 1.62571 2.04562 2.47706 + vertex 1.62082 2.04512 2.47797 + endloop + endfacet + facet normal 0.145767 0.292071 0.945223 + outer loop + vertex 1.62101 2.04922 2.47667 + vertex 1.62082 2.04512 2.47797 + vertex 1.62571 2.04562 2.47706 + endloop + endfacet + facet normal 0.120075 0.259783 0.958173 + outer loop + vertex 1.62531 2.05009 2.4759 + vertex 1.62101 2.04922 2.47667 + vertex 1.62571 2.04562 2.47706 + endloop + endfacet + facet normal 0.200825 0.263255 0.943592 + outer loop + vertex 1.62531 2.05009 2.4759 + vertex 1.62571 2.04562 2.47706 + vertex 1.62843 2.04865 2.47563 + endloop + endfacet + facet normal 0.208709 0.281688 0.936532 + outer loop + vertex 1.62843 2.04865 2.47563 + vertex 1.6279 2.05292 2.47447 + vertex 1.62531 2.05009 2.4759 + endloop + endfacet + facet normal 0.270907 0.284681 0.919547 + outer loop + vertex 1.62843 2.04865 2.47563 + vertex 1.63286 2.04811 2.47449 + vertex 1.6279 2.05292 2.47447 + endloop + endfacet + facet normal 0.240068 0.253013 0.937204 + outer loop + vertex 1.6279 2.05292 2.47447 + vertex 1.63286 2.04811 2.47449 + vertex 1.63197 2.05229 2.47359 + endloop + endfacet + facet normal 0.24143 0.268156 0.932633 + outer loop + vertex 1.63197 2.05229 2.47359 + vertex 1.6311 2.05638 2.47264 + vertex 1.6279 2.05292 2.47447 + endloop + endfacet + facet normal 0.227246 0.281158 0.932368 + outer loop + vertex 1.6279 2.05292 2.47447 + vertex 1.6311 2.05638 2.47264 + vertex 1.62704 2.05687 2.47348 + endloop + endfacet + facet normal 0.228924 0.31233 0.921978 + outer loop + vertex 1.62605 2.06076 2.47242 + vertex 1.62704 2.05687 2.47348 + vertex 1.6311 2.05638 2.47264 + endloop + endfacet + facet normal 0.184088 0.261887 0.947379 + outer loop + vertex 1.63057 2.06088 2.4715 + vertex 1.62605 2.06076 2.47242 + vertex 1.6311 2.05638 2.47264 + endloop + endfacet + facet normal 0.251218 0.265682 0.930754 + outer loop + vertex 1.63057 2.06088 2.4715 + vertex 1.6311 2.05638 2.47264 + vertex 1.63377 2.05909 2.47115 + endloop + endfacet + facet normal 0.2581 0.279216 0.924891 + outer loop + vertex 1.63377 2.05909 2.47115 + vertex 1.63328 2.06354 2.46994 + vertex 1.63057 2.06088 2.4715 + endloop + endfacet + facet normal 0.238259 0.298938 0.92405 + outer loop + vertex 1.6287 2.06384 2.47103 + vertex 1.63057 2.06088 2.4715 + vertex 1.63328 2.06354 2.46994 + endloop + endfacet + facet normal 0.237934 0.322121 0.916311 + outer loop + vertex 1.6287 2.06384 2.47103 + vertex 1.63328 2.06354 2.46994 + vertex 1.62812 2.06799 2.46972 + endloop + endfacet + facet normal 0.196783 0.275543 0.940932 + outer loop + vertex 1.62812 2.06799 2.46972 + vertex 1.63328 2.06354 2.46994 + vertex 1.63281 2.06804 2.46872 + endloop + endfacet + facet normal 0.196847 0.274607 0.941192 + outer loop + vertex 1.63281 2.06804 2.46872 + vertex 1.631 2.07096 2.46825 + vertex 1.62812 2.06799 2.46972 + endloop + endfacet + facet normal 0.161913 0.306922 0.937861 + outer loop + vertex 1.62812 2.06799 2.46972 + vertex 1.631 2.07096 2.46825 + vertex 1.62765 2.07232 2.46839 + endloop + endfacet + facet normal 0.161069 0.304738 0.938718 + outer loop + vertex 1.631 2.07096 2.46825 + vertex 1.63103 2.07475 2.46702 + vertex 1.62765 2.07232 2.46839 + endloop + endfacet + facet normal 0.13527 0.336711 0.931841 + outer loop + vertex 1.62765 2.07232 2.46839 + vertex 1.63103 2.07475 2.46702 + vertex 1.62584 2.07559 2.46746 + endloop + endfacet + facet normal 0.128785 0.28771 0.949019 + outer loop + vertex 1.63103 2.07475 2.46702 + vertex 1.62915 2.07895 2.466 + vertex 1.62584 2.07559 2.46746 + endloop + endfacet + facet normal 0.183603 0.267969 0.945771 + outer loop + vertex 1.63057 2.06088 2.4715 + vertex 1.6287 2.06384 2.47103 + vertex 1.62605 2.06076 2.47242 + endloop + endfacet + facet normal 0.285705 0.274196 0.918253 + outer loop + vertex 1.6311 2.05638 2.47264 + vertex 1.63197 2.05229 2.47359 + vertex 1.63609 2.05132 2.4726 + endloop + endfacet + facet normal 0.265988 0.254619 0.929742 + outer loop + vertex 1.6356 2.05585 2.4715 + vertex 1.6311 2.05638 2.47264 + vertex 1.63609 2.05132 2.4726 + endloop + endfacet + facet normal 0.288625 0.255382 0.922754 + outer loop + vertex 1.6356 2.05585 2.4715 + vertex 1.63609 2.05132 2.4726 + vertex 1.63876 2.05388 2.47106 + endloop + endfacet + facet normal 0.290731 0.259167 0.921036 + outer loop + vertex 1.63876 2.05388 2.47106 + vertex 1.63833 2.05843 2.46991 + vertex 1.6356 2.05585 2.4715 + endloop + endfacet + facet normal 0.287599 0.262497 0.921077 + outer loop + vertex 1.63377 2.05909 2.47115 + vertex 1.6356 2.05585 2.4715 + vertex 1.63833 2.05843 2.46991 + endloop + endfacet + facet normal 0.288653 0.280037 0.915565 + outer loop + vertex 1.63377 2.05909 2.47115 + vertex 1.63833 2.05843 2.46991 + vertex 1.63328 2.06354 2.46994 + endloop + endfacet + facet normal 0.265836 0.251283 0.930692 + outer loop + vertex 1.6356 2.05585 2.4715 + vertex 1.63377 2.05909 2.47115 + vertex 1.6311 2.05638 2.47264 + endloop + endfacet + facet normal 0.283407 0.25927 0.923287 + outer loop + vertex 1.63286 2.04811 2.47449 + vertex 1.63609 2.05132 2.4726 + vertex 1.63197 2.05229 2.47359 + endloop + endfacet + facet normal 0.287291 0.255307 0.923191 + outer loop + vertex 1.63696 2.04712 2.47349 + vertex 1.63609 2.05132 2.4726 + vertex 1.63286 2.04811 2.47449 + endloop + endfacet + facet normal 0.286988 0.253435 0.923801 + outer loop + vertex 1.63286 2.04811 2.47449 + vertex 1.63783 2.0429 2.47438 + vertex 1.63696 2.04712 2.47349 + endloop + endfacet + facet normal 0.289005 0.2537 0.923099 + outer loop + vertex 1.63783 2.0429 2.47438 + vertex 1.64106 2.04615 2.47247 + vertex 1.63696 2.04712 2.47349 + endloop + endfacet + facet normal 0.287738 0.254986 0.923141 + outer loop + vertex 1.6419 2.04198 2.47337 + vertex 1.64106 2.04615 2.47247 + vertex 1.63783 2.0429 2.47438 + endloop + endfacet + facet normal 0.287898 0.256084 0.922787 + outer loop + vertex 1.63783 2.0429 2.47438 + vertex 1.64257 2.0379 2.47429 + vertex 1.6419 2.04198 2.47337 + endloop + endfacet + facet normal 0.282631 0.255619 0.924542 + outer loop + vertex 1.64257 2.0379 2.47429 + vertex 1.64593 2.04112 2.47237 + vertex 1.6419 2.04198 2.47337 + endloop + endfacet + facet normal 0.28332 0.251702 0.925406 + outer loop + vertex 1.63829 2.03835 2.47548 + vertex 1.64257 2.0379 2.47429 + vertex 1.63783 2.0429 2.47438 + endloop + endfacet + facet normal 0.288861 0.251839 0.923654 + outer loop + vertex 1.63829 2.03835 2.47548 + vertex 1.63783 2.0429 2.47438 + vertex 1.63522 2.04025 2.47592 + endloop + endfacet + facet normal 0.28856 0.251298 0.923895 + outer loop + vertex 1.63522 2.04025 2.47592 + vertex 1.63554 2.03576 2.47704 + vertex 1.63829 2.03835 2.47548 + endloop + endfacet + facet normal 0.286667 0.253324 0.923931 + outer loop + vertex 1.63988 2.03528 2.47583 + vertex 1.63829 2.03835 2.47548 + vertex 1.63554 2.03576 2.47704 + endloop + endfacet + facet normal 0.282106 0.251333 0.925877 + outer loop + vertex 1.63522 2.04025 2.47592 + vertex 1.63072 2.04086 2.47713 + vertex 1.63554 2.03576 2.47704 + endloop + endfacet + facet normal 0.288885 0.257815 0.921996 + outer loop + vertex 1.63072 2.04086 2.47713 + vertex 1.63113 2.03628 2.47828 + vertex 1.63554 2.03576 2.47704 + endloop + endfacet + facet normal 0.288554 0.249192 0.924467 + outer loop + vertex 1.63288 2.03302 2.47861 + vertex 1.63554 2.03576 2.47704 + vertex 1.63113 2.03628 2.47828 + endloop + endfacet + facet normal 0.289789 0.247961 0.924412 + outer loop + vertex 1.6359 2.03121 2.47815 + vertex 1.63554 2.03576 2.47704 + vertex 1.63288 2.03302 2.47861 + endloop + endfacet + facet normal 0.288841 0.246171 0.925187 + outer loop + vertex 1.63327 2.02842 2.47971 + vertex 1.6359 2.03121 2.47815 + vertex 1.63288 2.03302 2.47861 + endloop + endfacet + facet normal 0.276711 0.246032 0.928924 + outer loop + vertex 1.62834 2.03356 2.47982 + vertex 1.63327 2.02842 2.47971 + vertex 1.63288 2.03302 2.47861 + endloop + endfacet + facet normal 0.276589 0.243331 0.929671 + outer loop + vertex 1.63288 2.03302 2.47861 + vertex 1.63113 2.03628 2.47828 + vertex 1.62834 2.03356 2.47982 + endloop + endfacet + facet normal 0.287707 0.247273 0.925246 + outer loop + vertex 1.63786 2.02794 2.47842 + vertex 1.6359 2.03121 2.47815 + vertex 1.63327 2.02842 2.47971 + endloop + endfacet + facet normal 0.287604 0.243539 0.926268 + outer loop + vertex 1.63327 2.02842 2.47971 + vertex 1.63821 2.02313 2.47957 + vertex 1.63786 2.02794 2.47842 + endloop + endfacet + facet normal 0.279773 0.243538 0.928664 + outer loop + vertex 1.63821 2.02313 2.47957 + vertex 1.64212 2.02587 2.47767 + vertex 1.63786 2.02794 2.47842 + endloop + endfacet + facet normal 0.281304 0.247213 0.927229 + outer loop + vertex 1.64212 2.02587 2.47767 + vertex 1.63982 2.03125 2.47694 + vertex 1.63786 2.02794 2.47842 + endloop + endfacet + facet normal 0.278192 0.246052 0.928476 + outer loop + vertex 1.63982 2.03125 2.47694 + vertex 1.64212 2.02587 2.47767 + vertex 1.64446 2.02961 2.47598 + endloop + endfacet + facet normal 0.280106 0.243077 0.928684 + outer loop + vertex 1.64233 2.02208 2.4786 + vertex 1.64212 2.02587 2.47767 + vertex 1.63821 2.02313 2.47957 + endloop + endfacet + facet normal 0.2798 0.241378 0.929219 + outer loop + vertex 1.63821 2.02313 2.47957 + vertex 1.64289 2.018 2.47949 + vertex 1.64233 2.02208 2.4786 + endloop + endfacet + facet normal 0.27863 0.241298 0.929592 + outer loop + vertex 1.64289 2.018 2.47949 + vertex 1.64632 2.02128 2.47761 + vertex 1.64233 2.02208 2.4786 + endloop + endfacet + facet normal 0.279421 0.240459 0.929572 + outer loop + vertex 1.64692 2.01717 2.4785 + vertex 1.64632 2.02128 2.47761 + vertex 1.64289 2.018 2.47949 + endloop + endfacet + facet normal 0.2794 0.240299 0.929619 + outer loop + vertex 1.64289 2.018 2.47949 + vertex 1.64755 2.01304 2.47937 + vertex 1.64692 2.01717 2.4785 + endloop + endfacet + facet normal 0.282965 0.240601 0.928462 + outer loop + vertex 1.64755 2.01304 2.47937 + vertex 1.65096 2.0163 2.47749 + vertex 1.64692 2.01717 2.4785 + endloop + endfacet + facet normal 0.28335 0.24019 0.928451 + outer loop + vertex 1.65155 2.0122 2.47837 + vertex 1.65096 2.0163 2.47749 + vertex 1.64755 2.01304 2.47937 + endloop + endfacet + facet normal 0.283514 0.241404 0.928086 + outer loop + vertex 1.64755 2.01304 2.47937 + vertex 1.65182 2.00839 2.47928 + vertex 1.65155 2.0122 2.47837 + endloop + endfacet + facet normal 0.28563 0.241401 0.927438 + outer loop + vertex 1.65182 2.00839 2.47928 + vertex 1.6557 2.01111 2.47738 + vertex 1.65155 2.0122 2.47837 + endloop + endfacet + facet normal 0.284965 0.242324 0.927402 + outer loop + vertex 1.65611 2.00627 2.47852 + vertex 1.6557 2.01111 2.47738 + vertex 1.65182 2.00839 2.47928 + endloop + endfacet + facet normal 0.284496 0.241216 0.927835 + outer loop + vertex 1.65417 2.00295 2.47997 + vertex 1.65611 2.00627 2.47852 + vertex 1.65182 2.00839 2.47928 + endloop + endfacet + facet normal 0.283415 0.240804 0.928272 + outer loop + vertex 1.65417 2.00295 2.47997 + vertex 1.65182 2.00839 2.47928 + vertex 1.64952 2.00465 2.48095 + endloop + endfacet + facet normal 0.282904 0.239067 0.928877 + outer loop + vertex 1.65117 2.00078 2.48144 + vertex 1.65417 2.00295 2.47997 + vertex 1.64952 2.00465 2.48095 + endloop + endfacet + facet normal 0.280408 0.238133 0.929873 + outer loop + vertex 1.64952 2.00465 2.48095 + vertex 1.6471 2.00094 2.48263 + vertex 1.65117 2.00078 2.48144 + endloop + endfacet + facet normal 0.280608 0.231946 0.931375 + outer loop + vertex 1.65117 2.00078 2.48144 + vertex 1.6471 2.00094 2.48263 + vertex 1.65108 1.99627 2.4826 + endloop + endfacet + facet normal 0.281019 0.231909 0.931261 + outer loop + vertex 1.65117 2.00078 2.48144 + vertex 1.65108 1.99627 2.4826 + vertex 1.65405 1.99889 2.48105 + endloop + endfacet + facet normal 0.282538 0.230176 0.931231 + outer loop + vertex 1.65556 1.99576 2.48136 + vertex 1.65405 1.99889 2.48105 + vertex 1.65108 1.99627 2.4826 + endloop + endfacet + facet normal 0.282319 0.225043 0.932551 + outer loop + vertex 1.65556 1.99576 2.48136 + vertex 1.65108 1.99627 2.4826 + vertex 1.65581 1.99108 2.48242 + endloop + endfacet + facet normal 0.28568 0.225001 0.931537 + outer loop + vertex 1.65556 1.99576 2.48136 + vertex 1.65581 1.99108 2.48242 + vertex 1.65864 1.99385 2.48088 + endloop + endfacet + facet normal 0.288559 0.230192 0.929379 + outer loop + vertex 1.65864 1.99385 2.48088 + vertex 1.65843 1.99843 2.47981 + vertex 1.65556 1.99576 2.48136 + endloop + endfacet + facet normal 0.290709 0.230137 0.928722 + outer loop + vertex 1.65864 1.99385 2.48088 + vertex 1.66321 1.99325 2.4796 + vertex 1.65843 1.99843 2.47981 + endloop + endfacet + facet normal 0.288573 0.228119 0.929886 + outer loop + vertex 1.65843 1.99843 2.47981 + vertex 1.66321 1.99325 2.4796 + vertex 1.66291 1.99811 2.4785 + endloop + endfacet + facet normal 0.288571 0.233523 0.928544 + outer loop + vertex 1.66291 1.99811 2.4785 + vertex 1.66098 2.00139 2.47827 + vertex 1.65843 1.99843 2.47981 + endloop + endfacet + facet normal 0.286073 0.235784 0.928745 + outer loop + vertex 1.65843 1.99843 2.47981 + vertex 1.66098 2.00139 2.47827 + vertex 1.65807 2.003 2.47876 + endloop + endfacet + facet normal 0.285749 0.235782 0.928846 + outer loop + vertex 1.65417 2.00295 2.47997 + vertex 1.65843 1.99843 2.47981 + vertex 1.65807 2.003 2.47876 + endloop + endfacet + facet normal 0.286999 0.236986 0.928154 + outer loop + vertex 1.65405 1.99889 2.48105 + vertex 1.65843 1.99843 2.47981 + vertex 1.65417 2.00295 2.47997 + endloop + endfacet + facet normal 0.288305 0.240364 0.926879 + outer loop + vertex 1.66098 2.00139 2.47827 + vertex 1.66058 2.00595 2.47722 + vertex 1.65807 2.003 2.47876 + endloop + endfacet + facet normal 0.286927 0.241593 0.926988 + outer loop + vertex 1.65807 2.003 2.47876 + vertex 1.66058 2.00595 2.47722 + vertex 1.65611 2.00627 2.47852 + endloop + endfacet + facet normal 0.289518 0.240383 0.926496 + outer loop + vertex 1.66058 2.00595 2.47722 + vertex 1.66098 2.00139 2.47827 + vertex 1.66484 2.00146 2.47705 + endloop + endfacet + facet normal 0.287012 0.237952 0.927903 + outer loop + vertex 1.66489 2.00552 2.47599 + vertex 1.66058 2.00595 2.47722 + vertex 1.66484 2.00146 2.47705 + endloop + endfacet + facet normal 0.287914 0.237874 0.927643 + outer loop + vertex 1.66489 2.00552 2.47599 + vertex 1.66484 2.00146 2.47705 + vertex 1.66775 2.00365 2.47558 + endloop + endfacet + facet normal 0.288932 0.239596 0.926883 + outer loop + vertex 1.66775 2.00365 2.47558 + vertex 1.66764 2.00812 2.47446 + vertex 1.66489 2.00552 2.47599 + endloop + endfacet + facet normal 0.287366 0.241286 0.926931 + outer loop + vertex 1.66337 2.0086 2.47566 + vertex 1.66489 2.00552 2.47599 + vertex 1.66764 2.00812 2.47446 + endloop + endfacet + facet normal 0.287334 0.24044 0.927161 + outer loop + vertex 1.66337 2.0086 2.47566 + vertex 1.66764 2.00812 2.47446 + vertex 1.66318 2.01313 2.47455 + endloop + endfacet + facet normal 0.285544 0.240498 0.927699 + outer loop + vertex 1.66337 2.0086 2.47566 + vertex 1.66318 2.01313 2.47455 + vertex 1.66032 2.01047 2.47612 + endloop + endfacet + facet normal 0.286348 0.24196 0.927071 + outer loop + vertex 1.66032 2.01047 2.47612 + vertex 1.66058 2.00595 2.47722 + vertex 1.66337 2.0086 2.47566 + endloop + endfacet + facet normal 0.286522 0.241957 0.927018 + outer loop + vertex 1.66032 2.01047 2.47612 + vertex 1.6557 2.01111 2.47738 + vertex 1.66058 2.00595 2.47722 + endloop + endfacet + facet normal 0.286434 0.24054 0.927414 + outer loop + vertex 1.66032 2.01047 2.47612 + vertex 1.65859 2.01374 2.4758 + vertex 1.6557 2.01111 2.47738 + endloop + endfacet + facet normal 0.286797 0.240138 0.927406 + outer loop + vertex 1.65543 2.01569 2.47627 + vertex 1.6557 2.01111 2.47738 + vertex 1.65859 2.01374 2.4758 + endloop + endfacet + facet normal 0.285635 0.238048 0.928303 + outer loop + vertex 1.65859 2.01374 2.4758 + vertex 1.65822 2.01839 2.47472 + vertex 1.65543 2.01569 2.47627 + endloop + endfacet + facet normal 0.285355 0.238344 0.928313 + outer loop + vertex 1.6537 2.01895 2.47597 + vertex 1.65543 2.01569 2.47627 + vertex 1.65822 2.01839 2.47472 + endloop + endfacet + facet normal 0.285424 0.239783 0.927921 + outer loop + vertex 1.6537 2.01895 2.47597 + vertex 1.65822 2.01839 2.47472 + vertex 1.65344 2.02343 2.47489 + endloop + endfacet + facet normal 0.285149 0.239788 0.928004 + outer loop + vertex 1.6537 2.01895 2.47597 + vertex 1.65344 2.02343 2.47489 + vertex 1.65063 2.02082 2.47643 + endloop + endfacet + facet normal 0.284597 0.238777 0.928434 + outer loop + vertex 1.65063 2.02082 2.47643 + vertex 1.65096 2.0163 2.47749 + vertex 1.6537 2.01895 2.47597 + endloop + endfacet + facet normal 0.280914 0.238772 0.929556 + outer loop + vertex 1.65063 2.02082 2.47643 + vertex 1.64632 2.02128 2.47761 + vertex 1.65096 2.0163 2.47749 + endloop + endfacet + facet normal 0.280943 0.239657 0.92932 + outer loop + vertex 1.65063 2.02082 2.47643 + vertex 1.64907 2.0239 2.47611 + vertex 1.64632 2.02128 2.47761 + endloop + endfacet + facet normal 0.279209 0.241495 0.929366 + outer loop + vertex 1.64616 2.02577 2.4765 + vertex 1.64632 2.02128 2.47761 + vertex 1.64907 2.0239 2.47611 + endloop + endfacet + facet normal 0.281531 0.245484 0.92762 + outer loop + vertex 1.64907 2.0239 2.47611 + vertex 1.64914 2.02793 2.47502 + vertex 1.64616 2.02577 2.4765 + endloop + endfacet + facet normal 0.279686 0.247957 0.92752 + outer loop + vertex 1.64616 2.02577 2.4765 + vertex 1.64914 2.02793 2.47502 + vertex 1.64446 2.02961 2.47598 + endloop + endfacet + facet normal 0.276948 0.246898 0.928623 + outer loop + vertex 1.64446 2.02961 2.47598 + vertex 1.64212 2.02587 2.47767 + vertex 1.64616 2.02577 2.4765 + endloop + endfacet + facet normal 0.280574 0.251073 0.926413 + outer loop + vertex 1.64914 2.02793 2.47502 + vertex 1.6468 2.03333 2.47426 + vertex 1.64446 2.02961 2.47598 + endloop + endfacet + facet normal 0.279996 0.251468 0.92648 + outer loop + vertex 1.64276 2.03344 2.47545 + vertex 1.64446 2.02961 2.47598 + vertex 1.6468 2.03333 2.47426 + endloop + endfacet + facet normal 0.279887 0.25375 0.925891 + outer loop + vertex 1.64276 2.03344 2.47545 + vertex 1.6468 2.03333 2.47426 + vertex 1.64257 2.0379 2.47429 + endloop + endfacet + facet normal 0.281457 0.2537 0.925429 + outer loop + vertex 1.64276 2.03344 2.47545 + vertex 1.64257 2.0379 2.47429 + vertex 1.63988 2.03528 2.47583 + endloop + endfacet + facet normal 0.281112 0.254888 0.925207 + outer loop + vertex 1.64257 2.0379 2.47429 + vertex 1.6468 2.03333 2.47426 + vertex 1.64656 2.03709 2.4733 + endloop + endfacet + facet normal 0.28137 0.256946 0.924559 + outer loop + vertex 1.64656 2.03709 2.4733 + vertex 1.64593 2.04112 2.47237 + vertex 1.64257 2.0379 2.47429 + endloop + endfacet + facet normal 0.283106 0.257089 0.923989 + outer loop + vertex 1.64593 2.04112 2.47237 + vertex 1.64656 2.03709 2.4733 + vertex 1.65068 2.03604 2.47233 + endloop + endfacet + facet normal 0.282971 0.256962 0.924066 + outer loop + vertex 1.65031 2.04056 2.47119 + vertex 1.64593 2.04112 2.47237 + vertex 1.65068 2.03604 2.47233 + endloop + endfacet + facet normal 0.284495 0.256968 0.923596 + outer loop + vertex 1.65031 2.04056 2.47119 + vertex 1.65068 2.03604 2.47233 + vertex 1.65342 2.03867 2.47076 + endloop + endfacet + facet normal 0.284762 0.257457 0.923378 + outer loop + vertex 1.65342 2.03867 2.47076 + vertex 1.65294 2.04316 2.46965 + vertex 1.65031 2.04056 2.47119 + endloop + endfacet + facet normal 0.284487 0.257739 0.923384 + outer loop + vertex 1.64857 2.04373 2.47084 + vertex 1.65031 2.04056 2.47119 + vertex 1.65294 2.04316 2.46965 + endloop + endfacet + facet normal 0.284417 0.256363 0.923788 + outer loop + vertex 1.64857 2.04373 2.47084 + vertex 1.65294 2.04316 2.46965 + vertex 1.64823 2.04819 2.4697 + endloop + endfacet + facet normal 0.284364 0.256313 0.923818 + outer loop + vertex 1.64823 2.04819 2.4697 + vertex 1.65294 2.04316 2.46965 + vertex 1.65231 2.04718 2.46873 + endloop + endfacet + facet normal 0.28423 0.255522 0.924079 + outer loop + vertex 1.65231 2.04718 2.46873 + vertex 1.65208 2.05092 2.46777 + vertex 1.64823 2.04819 2.4697 + endloop + endfacet + facet normal 0.283779 0.256138 0.924047 + outer loop + vertex 1.64823 2.04819 2.4697 + vertex 1.65208 2.05092 2.46777 + vertex 1.64783 2.05293 2.46851 + endloop + endfacet + facet normal 0.284843 0.258774 0.922985 + outer loop + vertex 1.65208 2.05092 2.46777 + vertex 1.64976 2.05624 2.46699 + vertex 1.64783 2.05293 2.46851 + endloop + endfacet + facet normal 0.285335 0.255503 0.923744 + outer loop + vertex 1.65208 2.05092 2.46777 + vertex 1.65231 2.04718 2.46873 + vertex 1.65629 2.04635 2.46773 + endloop + endfacet + facet normal 0.284695 0.25491 0.924105 + outer loop + vertex 1.65611 2.05078 2.46656 + vertex 1.65208 2.05092 2.46777 + vertex 1.65629 2.04635 2.46773 + endloop + endfacet + facet normal 0.28557 0.254878 0.923844 + outer loop + vertex 1.65611 2.05078 2.46656 + vertex 1.65629 2.04635 2.46773 + vertex 1.65902 2.04892 2.46618 + endloop + endfacet + facet normal 0.285599 0.254927 0.923821 + outer loop + vertex 1.65902 2.04892 2.46618 + vertex 1.65909 2.05292 2.46505 + vertex 1.65611 2.05078 2.46656 + endloop + endfacet + facet normal 0.284585 0.25629 0.923757 + outer loop + vertex 1.65611 2.05078 2.46656 + vertex 1.65909 2.05292 2.46505 + vertex 1.65441 2.05461 2.46602 + endloop + endfacet + facet normal 0.285558 0.259717 0.922498 + outer loop + vertex 1.65909 2.05292 2.46505 + vertex 1.65673 2.0583 2.46427 + vertex 1.65441 2.05461 2.46602 + endloop + endfacet + facet normal 0.283444 0.261165 0.922742 + outer loop + vertex 1.6527 2.05842 2.46547 + vertex 1.65441 2.05461 2.46602 + vertex 1.65673 2.0583 2.46427 + endloop + endfacet + facet normal 0.283034 0.269309 0.920524 + outer loop + vertex 1.6527 2.05842 2.46547 + vertex 1.65673 2.0583 2.46427 + vertex 1.65249 2.06282 2.46425 + endloop + endfacet + facet normal 0.28241 0.269332 0.920709 + outer loop + vertex 1.6527 2.05842 2.46547 + vertex 1.65249 2.06282 2.46425 + vertex 1.6498 2.06022 2.46583 + endloop + endfacet + facet normal 0.280095 0.265223 0.922607 + outer loop + vertex 1.6498 2.06022 2.46583 + vertex 1.64976 2.05624 2.46699 + vertex 1.6527 2.05842 2.46547 + endloop + endfacet + facet normal 0.28225 0.26503 0.922005 + outer loop + vertex 1.6498 2.06022 2.46583 + vertex 1.64547 2.06062 2.46705 + vertex 1.64976 2.05624 2.46699 + endloop + endfacet + facet normal 0.282555 0.265331 0.921825 + outer loop + vertex 1.64547 2.06062 2.46705 + vertex 1.64586 2.05614 2.46822 + vertex 1.64976 2.05624 2.46699 + endloop + endfacet + facet normal 0.283133 0.259873 0.923202 + outer loop + vertex 1.64783 2.05293 2.46851 + vertex 1.64976 2.05624 2.46699 + vertex 1.64586 2.05614 2.46822 + endloop + endfacet + facet normal 0.283824 0.260268 0.922878 + outer loop + vertex 1.64783 2.05293 2.46851 + vertex 1.64586 2.05614 2.46822 + vertex 1.64326 2.05331 2.46981 + endloop + endfacet + facet normal 0.284305 0.259815 0.922858 + outer loop + vertex 1.64326 2.05331 2.46981 + vertex 1.64586 2.05614 2.46822 + vertex 1.64284 2.05785 2.46867 + endloop + endfacet + facet normal 0.289013 0.259882 0.921376 + outer loop + vertex 1.63833 2.05843 2.46991 + vertex 1.64326 2.05331 2.46981 + vertex 1.64284 2.05785 2.46867 + endloop + endfacet + facet normal 0.289214 0.26419 0.920086 + outer loop + vertex 1.64284 2.05785 2.46867 + vertex 1.64108 2.06106 2.4683 + vertex 1.63833 2.05843 2.46991 + endloop + endfacet + facet normal 0.288605 0.263887 0.920364 + outer loop + vertex 1.64284 2.05785 2.46867 + vertex 1.64547 2.06062 2.46705 + vertex 1.64108 2.06106 2.4683 + endloop + endfacet + facet normal 0.288699 0.27008 0.918537 + outer loop + vertex 1.64062 2.06565 2.46709 + vertex 1.64108 2.06106 2.4683 + vertex 1.64547 2.06062 2.46705 + endloop + endfacet + facet normal 0.291034 0.272346 0.91713 + outer loop + vertex 1.64512 2.06505 2.46584 + vertex 1.64062 2.06565 2.46709 + vertex 1.64547 2.06062 2.46705 + endloop + endfacet + facet normal 0.283093 0.272398 0.919596 + outer loop + vertex 1.64512 2.06505 2.46584 + vertex 1.64547 2.06062 2.46705 + vertex 1.64819 2.06324 2.46543 + endloop + endfacet + facet normal 0.283267 0.272728 0.919445 + outer loop + vertex 1.64819 2.06324 2.46543 + vertex 1.64774 2.06771 2.46424 + vertex 1.64512 2.06505 2.46584 + endloop + endfacet + facet normal 0.286012 0.269997 0.919402 + outer loop + vertex 1.6433 2.0683 2.46545 + vertex 1.64512 2.06505 2.46584 + vertex 1.64774 2.06771 2.46424 + endloop + endfacet + facet normal 0.285876 0.267133 0.92028 + outer loop + vertex 1.6433 2.0683 2.46545 + vertex 1.64774 2.06771 2.46424 + vertex 1.64274 2.07288 2.4643 + endloop + endfacet + facet normal 0.290452 0.267317 0.918792 + outer loop + vertex 1.6433 2.0683 2.46545 + vertex 1.64274 2.07288 2.4643 + vertex 1.64012 2.07025 2.46589 + endloop + endfacet + facet normal 0.292508 0.271047 0.917046 + outer loop + vertex 1.64012 2.07025 2.46589 + vertex 1.64062 2.06565 2.46709 + vertex 1.6433 2.0683 2.46545 + endloop + endfacet + facet normal 0.279449 0.270726 0.921203 + outer loop + vertex 1.64012 2.07025 2.46589 + vertex 1.63562 2.0707 2.46712 + vertex 1.64062 2.06565 2.46709 + endloop + endfacet + facet normal 0.290183 0.281381 0.914669 + outer loop + vertex 1.63562 2.0707 2.46712 + vertex 1.63606 2.06625 2.46835 + vertex 1.64062 2.06565 2.46709 + endloop + endfacet + facet normal 0.289775 0.27248 0.917488 + outer loop + vertex 1.63791 2.06299 2.46874 + vertex 1.64062 2.06565 2.46709 + vertex 1.63606 2.06625 2.46835 + endloop + endfacet + facet normal 0.272665 0.263733 0.925256 + outer loop + vertex 1.63791 2.06299 2.46874 + vertex 1.63606 2.06625 2.46835 + vertex 1.63328 2.06354 2.46994 + endloop + endfacet + facet normal 0.260332 0.280924 0.923747 + outer loop + vertex 1.63606 2.06625 2.46835 + vertex 1.63562 2.0707 2.46712 + vertex 1.63281 2.06804 2.46872 + endloop + endfacet + facet normal 0.258802 0.277854 0.925105 + outer loop + vertex 1.63328 2.06354 2.46994 + vertex 1.63606 2.06625 2.46835 + vertex 1.63281 2.06804 2.46872 + endloop + endfacet + facet normal 0.242171 0.299567 0.922829 + outer loop + vertex 1.63281 2.06804 2.46872 + vertex 1.63562 2.0707 2.46712 + vertex 1.631 2.07096 2.46825 + endloop + endfacet + facet normal 0.242181 0.299081 0.922984 + outer loop + vertex 1.63103 2.07475 2.46702 + vertex 1.631 2.07096 2.46825 + vertex 1.63562 2.0707 2.46712 + endloop + endfacet + facet normal 0.214669 0.268317 0.939108 + outer loop + vertex 1.63514 2.07517 2.46596 + vertex 1.63103 2.07475 2.46702 + vertex 1.63562 2.0707 2.46712 + endloop + endfacet + facet normal 0.269081 0.270318 0.924405 + outer loop + vertex 1.63514 2.07517 2.46596 + vertex 1.63562 2.0707 2.46712 + vertex 1.63827 2.07351 2.46553 + endloop + endfacet + facet normal 0.269769 0.271775 0.923777 + outer loop + vertex 1.63827 2.07351 2.46553 + vertex 1.63773 2.07788 2.4644 + vertex 1.63514 2.07517 2.46596 + endloop + endfacet + facet normal 0.248376 0.292018 0.923599 + outer loop + vertex 1.63319 2.07796 2.4656 + vertex 1.63514 2.07517 2.46596 + vertex 1.63773 2.07788 2.4644 + endloop + endfacet + facet normal 0.24771 0.302601 0.920365 + outer loop + vertex 1.63319 2.07796 2.4656 + vertex 1.63773 2.07788 2.4644 + vertex 1.63305 2.0818 2.46437 + endloop + endfacet + facet normal 0.22129 0.271185 0.936744 + outer loop + vertex 1.63305 2.0818 2.46437 + vertex 1.63773 2.07788 2.4644 + vertex 1.63684 2.08191 2.46344 + endloop + endfacet + facet normal 0.21437 0.337005 0.916773 + outer loop + vertex 1.63684 2.08191 2.46344 + vertex 1.63578 2.08578 2.46227 + vertex 1.63305 2.0818 2.46437 + endloop + endfacet + facet normal 0.197618 0.348246 0.916336 + outer loop + vertex 1.63305 2.0818 2.46437 + vertex 1.63578 2.08578 2.46227 + vertex 1.63087 2.08551 2.46343 + endloop + endfacet + facet normal 0.285284 0.349042 0.892627 + outer loop + vertex 1.63578 2.08578 2.46227 + vertex 1.63684 2.08191 2.46344 + vertex 1.64077 2.08121 2.46247 + endloop + endfacet + facet normal 0.279244 0.279661 0.918593 + outer loop + vertex 1.63773 2.07788 2.4644 + vertex 1.64077 2.08121 2.46247 + vertex 1.63684 2.08191 2.46344 + endloop + endfacet + facet normal 0.283675 0.275536 0.918482 + outer loop + vertex 1.64181 2.07711 2.46337 + vertex 1.64077 2.08121 2.46247 + vertex 1.63773 2.07788 2.4644 + endloop + endfacet + facet normal 0.282388 0.26356 0.922385 + outer loop + vertex 1.63773 2.07788 2.4644 + vertex 1.64274 2.07288 2.4643 + vertex 1.64181 2.07711 2.46337 + endloop + endfacet + facet normal 0.294703 0.265329 0.918015 + outer loop + vertex 1.64274 2.07288 2.4643 + vertex 1.64589 2.07607 2.46236 + vertex 1.64181 2.07711 2.46337 + endloop + endfacet + facet normal 0.296787 0.277783 0.913649 + outer loop + vertex 1.64077 2.08121 2.46247 + vertex 1.64181 2.07711 2.46337 + vertex 1.64589 2.07607 2.46236 + endloop + endfacet + facet normal 0.298742 0.279757 0.912409 + outer loop + vertex 1.64501 2.08049 2.4613 + vertex 1.64077 2.08121 2.46247 + vertex 1.64589 2.07607 2.46236 + endloop + endfacet + facet normal 0.297385 0.279605 0.912898 + outer loop + vertex 1.64501 2.08049 2.4613 + vertex 1.64589 2.07607 2.46236 + vertex 1.64824 2.07854 2.46084 + endloop + endfacet + facet normal 0.318806 0.319943 0.892188 + outer loop + vertex 1.64824 2.07854 2.46084 + vertex 1.64698 2.08274 2.45978 + vertex 1.64501 2.08049 2.4613 + endloop + endfacet + facet normal 0.292532 0.314777 0.902962 + outer loop + vertex 1.64824 2.07854 2.46084 + vertex 1.65275 2.07799 2.45957 + vertex 1.64698 2.08274 2.45978 + endloop + endfacet + facet normal 0.291837 0.28735 0.912283 + outer loop + vertex 1.64824 2.07854 2.46084 + vertex 1.65034 2.07539 2.46116 + vertex 1.65275 2.07799 2.45957 + endloop + endfacet + facet normal 0.284727 0.294004 0.91241 + outer loop + vertex 1.65355 2.07351 2.46076 + vertex 1.65275 2.07799 2.45957 + vertex 1.65034 2.07539 2.46116 + endloop + endfacet + facet normal 0.27534 0.276087 0.92085 + outer loop + vertex 1.65034 2.07539 2.46116 + vertex 1.65099 2.07095 2.4623 + vertex 1.65355 2.07351 2.46076 + endloop + endfacet + facet normal 0.273259 0.278162 0.920845 + outer loop + vertex 1.65544 2.07039 2.46115 + vertex 1.65355 2.07351 2.46076 + vertex 1.65099 2.07095 2.4623 + endloop + endfacet + facet normal 0.272868 0.269592 0.923506 + outer loop + vertex 1.65544 2.07039 2.46115 + vertex 1.65099 2.07095 2.4623 + vertex 1.65588 2.06599 2.4623 + endloop + endfacet + facet normal 0.270931 0.269546 0.924089 + outer loop + vertex 1.65544 2.07039 2.46115 + vertex 1.65588 2.06599 2.4623 + vertex 1.65856 2.06858 2.46076 + endloop + endfacet + facet normal 0.273645 0.274722 0.921763 + outer loop + vertex 1.65856 2.06858 2.46076 + vertex 1.65802 2.07297 2.45961 + vertex 1.65544 2.07039 2.46115 + endloop + endfacet + facet normal 0.277558 0.274883 0.920544 + outer loop + vertex 1.65856 2.06858 2.46076 + vertex 1.66297 2.06806 2.45959 + vertex 1.65802 2.07297 2.45961 + endloop + endfacet + facet normal 0.270903 0.268148 0.924504 + outer loop + vertex 1.65802 2.07297 2.45961 + vertex 1.66297 2.06806 2.45959 + vertex 1.66214 2.07213 2.45865 + endloop + endfacet + facet normal 0.274987 0.301978 0.912793 + outer loop + vertex 1.66214 2.07213 2.45865 + vertex 1.66114 2.07605 2.45765 + vertex 1.65802 2.07297 2.45961 + endloop + endfacet + facet normal 0.28348 0.293489 0.912964 + outer loop + vertex 1.65802 2.07297 2.45961 + vertex 1.66114 2.07605 2.45765 + vertex 1.65713 2.07689 2.45863 + endloop + endfacet + facet normal 0.270829 0.291725 0.917359 + outer loop + vertex 1.65275 2.07799 2.45957 + vertex 1.65802 2.07297 2.45961 + vertex 1.65713 2.07689 2.45863 + endloop + endfacet + facet normal 0.280161 0.348597 0.894422 + outer loop + vertex 1.65713 2.07689 2.45863 + vertex 1.65628 2.08041 2.45752 + vertex 1.65275 2.07799 2.45957 + endloop + endfacet + facet normal 0.283052 0.344839 0.894968 + outer loop + vertex 1.65275 2.07799 2.45957 + vertex 1.65628 2.08041 2.45752 + vertex 1.65107 2.08342 2.45801 + endloop + endfacet + facet normal 0.322567 0.352354 0.87852 + outer loop + vertex 1.64698 2.08274 2.45978 + vertex 1.65275 2.07799 2.45957 + vertex 1.65107 2.08342 2.45801 + endloop + endfacet + facet normal 0.289879 0.349801 0.890848 + outer loop + vertex 1.65628 2.08041 2.45752 + vertex 1.65713 2.07689 2.45863 + vertex 1.66114 2.07605 2.45765 + endloop + endfacet + facet normal 0.292936 0.304905 0.906213 + outer loop + vertex 1.66114 2.07605 2.45765 + vertex 1.66214 2.07213 2.45865 + vertex 1.66617 2.07127 2.45763 + endloop + endfacet + facet normal 0.290577 0.302417 0.907805 + outer loop + vertex 1.66534 2.07557 2.45647 + vertex 1.66114 2.07605 2.45765 + vertex 1.66617 2.07127 2.45763 + endloop + endfacet + facet normal 0.301053 0.303417 0.904049 + outer loop + vertex 1.66534 2.07557 2.45647 + vertex 1.66617 2.07127 2.45763 + vertex 1.66851 2.07378 2.45601 + endloop + endfacet + facet normal 0.335602 0.374741 0.864257 + outer loop + vertex 1.66851 2.07378 2.45601 + vertex 1.66711 2.0778 2.45481 + vertex 1.66534 2.07557 2.45647 + endloop + endfacet + facet normal 0.324074 0.372348 0.869674 + outer loop + vertex 1.66851 2.07378 2.45601 + vertex 1.67288 2.0732 2.45463 + vertex 1.66711 2.0778 2.45481 + endloop + endfacet + facet normal 0.323641 0.317488 0.891324 + outer loop + vertex 1.66851 2.07378 2.45601 + vertex 1.67053 2.07071 2.45637 + vertex 1.67288 2.0732 2.45463 + endloop + endfacet + facet normal 0.322719 0.31837 0.891343 + outer loop + vertex 1.67365 2.06882 2.45592 + vertex 1.67288 2.0732 2.45463 + vertex 1.67053 2.07071 2.45637 + endloop + endfacet + facet normal 0.300978 0.277569 0.912342 + outer loop + vertex 1.67053 2.07071 2.45637 + vertex 1.67109 2.06626 2.45754 + vertex 1.67365 2.06882 2.45592 + endloop + endfacet + facet normal 0.298881 0.279691 0.912383 + outer loop + vertex 1.67546 2.06564 2.4563 + vertex 1.67365 2.06882 2.45592 + vertex 1.67109 2.06626 2.45754 + endloop + endfacet + facet normal 0.298142 0.265725 0.916789 + outer loop + vertex 1.67546 2.06564 2.4563 + vertex 1.67109 2.06626 2.45754 + vertex 1.67595 2.06114 2.45745 + endloop + endfacet + facet normal 0.29321 0.265602 0.918414 + outer loop + vertex 1.67546 2.06564 2.4563 + vertex 1.67595 2.06114 2.45745 + vertex 1.67855 2.06373 2.45587 + endloop + endfacet + facet normal 0.301358 0.280398 0.911351 + outer loop + vertex 1.67855 2.06373 2.45587 + vertex 1.67804 2.06814 2.45468 + vertex 1.67546 2.06564 2.4563 + endloop + endfacet + facet normal 0.288748 0.280083 0.915521 + outer loop + vertex 1.67855 2.06373 2.45587 + vertex 1.68297 2.06313 2.45466 + vertex 1.67804 2.06814 2.45468 + endloop + endfacet + facet normal 0.285774 0.277155 0.917343 + outer loop + vertex 1.67804 2.06814 2.45468 + vertex 1.68297 2.06313 2.45466 + vertex 1.68213 2.06721 2.45369 + endloop + endfacet + facet normal 0.283572 0.276884 0.918108 + outer loop + vertex 1.68297 2.06313 2.45466 + vertex 1.68612 2.06628 2.45273 + vertex 1.68213 2.06721 2.45369 + endloop + endfacet + facet normal 0.283159 0.277298 0.91811 + outer loop + vertex 1.68706 2.06222 2.45367 + vertex 1.68612 2.06628 2.45273 + vertex 1.68297 2.06313 2.45466 + endloop + endfacet + facet normal 0.281287 0.264002 0.922594 + outer loop + vertex 1.68297 2.06313 2.45466 + vertex 1.68791 2.05807 2.4546 + vertex 1.68706 2.06222 2.45367 + endloop + endfacet + facet normal 0.280701 0.263928 0.922794 + outer loop + vertex 1.68791 2.05807 2.4546 + vertex 1.69112 2.0613 2.4527 + vertex 1.68706 2.06222 2.45367 + endloop + endfacet + facet normal 0.280481 0.26415 0.922798 + outer loop + vertex 1.69201 2.05716 2.45361 + vertex 1.69112 2.0613 2.4527 + vertex 1.68791 2.05807 2.4546 + endloop + endfacet + facet normal 0.280658 0.265402 0.922385 + outer loop + vertex 1.68791 2.05807 2.4546 + vertex 1.69287 2.05302 2.45454 + vertex 1.69201 2.05716 2.45361 + endloop + endfacet + facet normal 0.278664 0.26514 0.923064 + outer loop + vertex 1.69287 2.05302 2.45454 + vertex 1.6961 2.05626 2.45264 + vertex 1.69201 2.05716 2.45361 + endloop + endfacet + facet normal 0.277864 0.265942 0.923075 + outer loop + vertex 1.69695 2.05215 2.45356 + vertex 1.6961 2.05626 2.45264 + vertex 1.69287 2.05302 2.45454 + endloop + endfacet + facet normal 0.277632 0.264199 0.923645 + outer loop + vertex 1.69287 2.05302 2.45454 + vertex 1.69779 2.04802 2.45449 + vertex 1.69695 2.05215 2.45356 + endloop + endfacet + facet normal 0.289515 0.265673 0.919564 + outer loop + vertex 1.69779 2.04802 2.45449 + vertex 1.70094 2.05132 2.45255 + vertex 1.69695 2.05215 2.45356 + endloop + endfacet + facet normal 0.291787 0.263458 0.919484 + outer loop + vertex 1.70168 2.04726 2.45348 + vertex 1.70094 2.05132 2.45255 + vertex 1.69779 2.04802 2.45449 + endloop + endfacet + facet normal 0.289584 0.244073 0.92551 + outer loop + vertex 1.69779 2.04802 2.45449 + vertex 1.70251 2.04297 2.45435 + vertex 1.70168 2.04726 2.45348 + endloop + endfacet + facet normal 0.339417 0.24985 0.906847 + outer loop + vertex 1.70251 2.04297 2.45435 + vertex 1.70521 2.04667 2.45232 + vertex 1.70168 2.04726 2.45348 + endloop + endfacet + facet normal 0.31155 0.264978 0.912537 + outer loop + vertex 1.69827 2.04353 2.45563 + vertex 1.70251 2.04297 2.45435 + vertex 1.69779 2.04802 2.45449 + endloop + endfacet + facet normal 0.283002 0.264277 0.921991 + outer loop + vertex 1.69827 2.04353 2.45563 + vertex 1.69779 2.04802 2.45449 + vertex 1.69519 2.04537 2.45605 + endloop + endfacet + facet normal 0.280311 0.259251 0.924237 + outer loop + vertex 1.69519 2.04537 2.45605 + vertex 1.69555 2.04087 2.45721 + vertex 1.69827 2.04353 2.45563 + endloop + endfacet + facet normal 0.284327 0.255088 0.924169 + outer loop + vertex 1.69988 2.04042 2.45599 + vertex 1.69827 2.04353 2.45563 + vertex 1.69555 2.04087 2.45721 + endloop + endfacet + facet normal 0.284008 0.242753 0.927583 + outer loop + vertex 1.69988 2.04042 2.45599 + vertex 1.69555 2.04087 2.45721 + vertex 1.69985 2.03636 2.45707 + endloop + endfacet + facet normal 0.317507 0.23977 0.917442 + outer loop + vertex 1.69988 2.04042 2.45599 + vertex 1.69985 2.03636 2.45707 + vertex 1.70265 2.03841 2.45556 + endloop + endfacet + facet normal 0.295977 0.25436 0.920705 + outer loop + vertex 1.69555 2.04087 2.45721 + vertex 1.696 2.03631 2.45832 + vertex 1.69985 2.03636 2.45707 + endloop + endfacet + facet normal 0.296668 0.246774 0.922546 + outer loop + vertex 1.69792 2.03307 2.45857 + vertex 1.69985 2.03636 2.45707 + vertex 1.696 2.03631 2.45832 + endloop + endfacet + facet normal 0.288533 0.242249 0.926318 + outer loop + vertex 1.69792 2.03307 2.45857 + vertex 1.696 2.03631 2.45832 + vertex 1.69341 2.03338 2.45989 + endloop + endfacet + facet normal 0.288572 0.235797 0.927969 + outer loop + vertex 1.69341 2.03338 2.45989 + vertex 1.69807 2.02838 2.45972 + vertex 1.69792 2.03307 2.45857 + endloop + endfacet + facet normal 0.324792 0.234099 0.916356 + outer loop + vertex 1.69807 2.02838 2.45972 + vertex 1.70192 2.03102 2.45768 + vertex 1.69792 2.03307 2.45857 + endloop + endfacet + facet normal 0.322833 0.229468 0.918218 + outer loop + vertex 1.70192 2.03102 2.45768 + vertex 1.69985 2.03636 2.45707 + vertex 1.69792 2.03307 2.45857 + endloop + endfacet + facet normal 0.301878 0.248479 0.920396 + outer loop + vertex 1.69364 2.02891 2.46103 + vertex 1.69807 2.02838 2.45972 + vertex 1.69341 2.03338 2.45989 + endloop + endfacet + facet normal 0.284749 0.24894 0.925715 + outer loop + vertex 1.69364 2.02891 2.46103 + vertex 1.69341 2.03338 2.45989 + vertex 1.69059 2.03075 2.46147 + endloop + endfacet + facet normal 0.284419 0.24833 0.925979 + outer loop + vertex 1.69059 2.03075 2.46147 + vertex 1.69088 2.02634 2.46256 + vertex 1.69364 2.02891 2.46103 + endloop + endfacet + facet normal 0.287867 0.244593 0.925909 + outer loop + vertex 1.69522 2.02583 2.46135 + vertex 1.69364 2.02891 2.46103 + vertex 1.69088 2.02634 2.46256 + endloop + endfacet + facet normal 0.287699 0.240533 0.927024 + outer loop + vertex 1.69522 2.02583 2.46135 + vertex 1.69088 2.02634 2.46256 + vertex 1.69515 2.02184 2.4624 + endloop + endfacet + facet normal 0.313736 0.238006 0.919197 + outer loop + vertex 1.69522 2.02583 2.46135 + vertex 1.69515 2.02184 2.4624 + vertex 1.6981 2.02392 2.46086 + endloop + endfacet + facet normal 0.313656 0.237868 0.91926 + outer loop + vertex 1.6981 2.02392 2.46086 + vertex 1.69807 2.02838 2.45972 + vertex 1.69522 2.02583 2.46135 + endloop + endfacet + facet normal 0.298308 0.250796 0.920931 + outer loop + vertex 1.69088 2.02634 2.46256 + vertex 1.6916 2.02224 2.46344 + vertex 1.69515 2.02184 2.4624 + endloop + endfacet + facet normal 0.298244 0.248566 0.921556 + outer loop + vertex 1.69242 2.01797 2.46433 + vertex 1.69515 2.02184 2.4624 + vertex 1.6916 2.02224 2.46344 + endloop + endfacet + facet normal 0.281712 0.246569 0.927277 + outer loop + vertex 1.68771 2.02295 2.46444 + vertex 1.69242 2.01797 2.46433 + vertex 1.6916 2.02224 2.46344 + endloop + endfacet + facet normal 0.285801 0.250488 0.924972 + outer loop + vertex 1.6882 2.01841 2.46552 + vertex 1.69242 2.01797 2.46433 + vertex 1.68771 2.02295 2.46444 + endloop + endfacet + facet normal 0.277475 0.250213 0.927578 + outer loop + vertex 1.6882 2.01841 2.46552 + vertex 1.68771 2.02295 2.46444 + vertex 1.68514 2.02024 2.46594 + endloop + endfacet + facet normal 0.277546 0.250345 0.927521 + outer loop + vertex 1.68514 2.02024 2.46594 + vertex 1.68547 2.01577 2.46704 + vertex 1.6882 2.01841 2.46552 + endloop + endfacet + facet normal 0.274584 0.253432 0.927565 + outer loop + vertex 1.68978 2.01535 2.46588 + vertex 1.6882 2.01841 2.46552 + vertex 1.68547 2.01577 2.46704 + endloop + endfacet + facet normal 0.274506 0.25019 0.928467 + outer loop + vertex 1.68978 2.01535 2.46588 + vertex 1.68547 2.01577 2.46704 + vertex 1.68972 2.01135 2.46698 + endloop + endfacet + facet normal 0.284885 0.249249 0.925589 + outer loop + vertex 1.68978 2.01535 2.46588 + vertex 1.68972 2.01135 2.46698 + vertex 1.69254 2.01344 2.46555 + endloop + endfacet + facet normal 0.288972 0.255695 0.922559 + outer loop + vertex 1.69254 2.01344 2.46555 + vertex 1.69242 2.01797 2.46433 + vertex 1.68978 2.01535 2.46588 + endloop + endfacet + facet normal 0.328053 0.253295 0.910067 + outer loop + vertex 1.69254 2.01344 2.46555 + vertex 1.69605 2.01299 2.46441 + vertex 1.69242 2.01797 2.46433 + endloop + endfacet + facet normal 0.318731 0.246592 0.915206 + outer loop + vertex 1.69242 2.01797 2.46433 + vertex 1.69605 2.01299 2.46441 + vertex 1.69758 2.01686 2.46283 + endloop + endfacet + facet normal 0.327845 0.247245 0.911805 + outer loop + vertex 1.69254 2.01344 2.46555 + vertex 1.69416 2.00962 2.466 + vertex 1.69605 2.01299 2.46441 + endloop + endfacet + facet normal 0.295548 0.235161 0.925933 + outer loop + vertex 1.69416 2.00962 2.466 + vertex 1.69254 2.01344 2.46555 + vertex 1.68972 2.01135 2.46698 + endloop + endfacet + facet normal 0.273052 0.248782 0.929274 + outer loop + vertex 1.68547 2.01577 2.46704 + vertex 1.68584 2.01127 2.46814 + vertex 1.68972 2.01135 2.46698 + endloop + endfacet + facet normal 0.273149 0.24773 0.929526 + outer loop + vertex 1.6878 2.00804 2.46843 + vertex 1.68972 2.01135 2.46698 + vertex 1.68584 2.01127 2.46814 + endloop + endfacet + facet normal 0.269243 0.245515 0.931252 + outer loop + vertex 1.6878 2.00804 2.46843 + vertex 1.68584 2.01127 2.46814 + vertex 1.68318 2.00837 2.46968 + endloop + endfacet + facet normal 0.269233 0.236237 0.933652 + outer loop + vertex 1.68318 2.00837 2.46968 + vertex 1.68811 2.00322 2.46955 + vertex 1.6878 2.00804 2.46843 + endloop + endfacet + facet normal 0.281615 0.236196 0.930003 + outer loop + vertex 1.68811 2.00322 2.46955 + vertex 1.69192 2.00607 2.46768 + vertex 1.6878 2.00804 2.46843 + endloop + endfacet + facet normal 0.283264 0.234018 0.930052 + outer loop + vertex 1.69207 2.00235 2.46857 + vertex 1.69192 2.00607 2.46768 + vertex 1.68811 2.00322 2.46955 + endloop + endfacet + facet normal 0.280257 0.214094 0.935746 + outer loop + vertex 1.68811 2.00322 2.46955 + vertex 1.6926 1.99811 2.46938 + vertex 1.69207 2.00235 2.46857 + endloop + endfacet + facet normal 0.336522 0.217322 0.916256 + outer loop + vertex 1.6926 1.99811 2.46938 + vertex 1.69549 2.00181 2.46744 + vertex 1.69207 2.00235 2.46857 + endloop + endfacet + facet normal 0.301165 0.232784 0.924722 + outer loop + vertex 1.68832 1.99864 2.47064 + vertex 1.6926 1.99811 2.46938 + vertex 1.68811 2.00322 2.46955 + endloop + endfacet + facet normal 0.275709 0.233466 0.932458 + outer loop + vertex 1.68832 1.99864 2.47064 + vertex 1.68811 2.00322 2.46955 + vertex 1.68526 2.00047 2.47109 + endloop + endfacet + facet normal 0.274644 0.231488 0.933265 + outer loop + vertex 1.68526 2.00047 2.47109 + vertex 1.68552 1.99591 2.47214 + vertex 1.68832 1.99864 2.47064 + endloop + endfacet + facet normal 0.2785 0.227441 0.933118 + outer loop + vertex 1.68986 1.9955 2.47095 + vertex 1.68832 1.99864 2.47064 + vertex 1.68552 1.99591 2.47214 + endloop + endfacet + facet normal 0.278418 0.22433 0.933895 + outer loop + vertex 1.68986 1.9955 2.47095 + vertex 1.68552 1.99591 2.47214 + vertex 1.68981 1.99138 2.47195 + endloop + endfacet + facet normal 0.285723 0.231408 0.929953 + outer loop + vertex 1.68552 1.99591 2.47214 + vertex 1.68592 1.99131 2.47316 + vertex 1.68981 1.99138 2.47195 + endloop + endfacet + facet normal 0.2858 0.230537 0.930146 + outer loop + vertex 1.68787 1.98804 2.47338 + vertex 1.68981 1.99138 2.47195 + vertex 1.68592 1.99131 2.47316 + endloop + endfacet + facet normal 0.27858 0.226449 0.933335 + outer loop + vertex 1.68787 1.98804 2.47338 + vertex 1.68592 1.99131 2.47316 + vertex 1.68323 1.98839 2.47468 + endloop + endfacet + facet normal 0.278556 0.223274 0.934107 + outer loop + vertex 1.68323 1.98839 2.47468 + vertex 1.688 1.98328 2.47447 + vertex 1.68787 1.98804 2.47338 + endloop + endfacet + facet normal 0.30701 0.222063 0.925437 + outer loop + vertex 1.688 1.98328 2.47447 + vertex 1.69191 1.98602 2.47252 + vertex 1.68787 1.98804 2.47338 + endloop + endfacet + facet normal 0.287791 0.232098 0.929143 + outer loop + vertex 1.68351 1.98374 2.47575 + vertex 1.688 1.98328 2.47447 + vertex 1.68323 1.98839 2.47468 + endloop + endfacet + facet normal 0.275078 0.232204 0.932959 + outer loop + vertex 1.68351 1.98374 2.47575 + vertex 1.68323 1.98839 2.47468 + vertex 1.68035 1.98564 2.47621 + endloop + endfacet + facet normal 0.2746 0.231318 0.93332 + outer loop + vertex 1.68035 1.98564 2.47621 + vertex 1.68062 1.98103 2.47727 + vertex 1.68351 1.98374 2.47575 + endloop + endfacet + facet normal 0.277323 0.228376 0.93324 + outer loop + vertex 1.68508 1.98059 2.47605 + vertex 1.68351 1.98374 2.47575 + vertex 1.68062 1.98103 2.47727 + endloop + endfacet + facet normal 0.277057 0.219445 0.935459 + outer loop + vertex 1.68508 1.98059 2.47605 + vertex 1.68062 1.98103 2.47727 + vertex 1.6849 1.97647 2.47707 + endloop + endfacet + facet normal 0.295114 0.217417 0.930396 + outer loop + vertex 1.68508 1.98059 2.47605 + vertex 1.6849 1.97647 2.47707 + vertex 1.68794 1.9787 2.47559 + endloop + endfacet + facet normal 0.29784 0.222034 0.928435 + outer loop + vertex 1.68794 1.9787 2.47559 + vertex 1.688 1.98328 2.47447 + vertex 1.68508 1.98059 2.47605 + endloop + endfacet + facet normal 0.285251 0.227321 0.931105 + outer loop + vertex 1.68062 1.98103 2.47727 + vertex 1.68102 1.97637 2.47829 + vertex 1.6849 1.97647 2.47707 + endloop + endfacet + facet normal 0.285791 0.221424 0.93236 + outer loop + vertex 1.68288 1.97309 2.4785 + vertex 1.6849 1.97647 2.47707 + vertex 1.68102 1.97637 2.47829 + endloop + endfacet + facet normal 0.300487 0.211649 0.930007 + outer loop + vertex 1.68686 1.97108 2.47767 + vertex 1.6849 1.97647 2.47707 + vertex 1.68288 1.97309 2.4785 + endloop + endfacet + facet normal 0.301478 0.213966 0.929155 + outer loop + vertex 1.68294 1.96835 2.47957 + vertex 1.68686 1.97108 2.47767 + vertex 1.68288 1.97309 2.4785 + endloop + endfacet + facet normal 0.281101 0.215082 0.935266 + outer loop + vertex 1.6784 1.97338 2.47977 + vertex 1.68294 1.96835 2.47957 + vertex 1.68288 1.97309 2.4785 + endloop + endfacet + facet normal 0.281098 0.218887 0.934384 + outer loop + vertex 1.68288 1.97309 2.4785 + vertex 1.68102 1.97637 2.47829 + vertex 1.6784 1.97338 2.47977 + endloop + endfacet + facet normal 0.275795 0.223741 0.934814 + outer loop + vertex 1.6784 1.97338 2.47977 + vertex 1.68102 1.97637 2.47829 + vertex 1.67807 1.97801 2.47877 + endloop + endfacet + facet normal 0.277082 0.223751 0.934431 + outer loop + vertex 1.67413 1.97794 2.47995 + vertex 1.6784 1.97338 2.47977 + vertex 1.67807 1.97801 2.47877 + endloop + endfacet + facet normal 0.276648 0.228952 0.933299 + outer loop + vertex 1.67807 1.97801 2.47877 + vertex 1.67607 1.98134 2.47854 + vertex 1.67413 1.97794 2.47995 + endloop + endfacet + facet normal 0.279399 0.227219 0.932903 + outer loop + vertex 1.67413 1.97794 2.47995 + vertex 1.67607 1.98134 2.47854 + vertex 1.67177 1.98347 2.47931 + endloop + endfacet + facet normal 0.282119 0.228254 0.931831 + outer loop + vertex 1.67413 1.97794 2.47995 + vertex 1.67177 1.98347 2.47931 + vertex 1.66946 1.97969 2.48094 + endloop + endfacet + facet normal 0.281183 0.22516 0.932866 + outer loop + vertex 1.67112 1.97574 2.48139 + vertex 1.67413 1.97794 2.47995 + vertex 1.66946 1.97969 2.48094 + endloop + endfacet + facet normal 0.284345 0.226351 0.931618 + outer loop + vertex 1.66946 1.97969 2.48094 + vertex 1.66704 1.97593 2.48258 + vertex 1.67112 1.97574 2.48139 + endloop + endfacet + facet normal 0.284407 0.223535 0.932279 + outer loop + vertex 1.67112 1.97574 2.48139 + vertex 1.66704 1.97593 2.48258 + vertex 1.67103 1.97121 2.4825 + endloop + endfacet + facet normal 0.280224 0.223912 0.933455 + outer loop + vertex 1.67112 1.97574 2.48139 + vertex 1.67103 1.97121 2.4825 + vertex 1.67402 1.97382 2.48098 + endloop + endfacet + facet normal 0.280615 0.223459 0.933446 + outer loop + vertex 1.67551 1.97068 2.48128 + vertex 1.67402 1.97382 2.48098 + vertex 1.67103 1.97121 2.4825 + endloop + endfacet + facet normal 0.280462 0.220314 0.934239 + outer loop + vertex 1.67551 1.97068 2.48128 + vertex 1.67103 1.97121 2.4825 + vertex 1.67564 1.96611 2.48232 + endloop + endfacet + facet normal 0.27979 0.220339 0.934435 + outer loop + vertex 1.67551 1.97068 2.48128 + vertex 1.67564 1.96611 2.48232 + vertex 1.67852 1.96882 2.48082 + endloop + endfacet + facet normal 0.28024 0.221152 0.934108 + outer loop + vertex 1.67852 1.96882 2.48082 + vertex 1.6784 1.97338 2.47977 + vertex 1.67551 1.97068 2.48128 + endloop + endfacet + facet normal 0.28017 0.219925 0.934418 + outer loop + vertex 1.68002 1.96569 2.4811 + vertex 1.67852 1.96882 2.48082 + vertex 1.67564 1.96611 2.48232 + endloop + endfacet + facet normal 0.28013 0.218496 0.934765 + outer loop + vertex 1.68002 1.96569 2.4811 + vertex 1.67564 1.96611 2.48232 + vertex 1.67989 1.96158 2.4821 + endloop + endfacet + facet normal 0.290657 0.217444 0.931792 + outer loop + vertex 1.68002 1.96569 2.4811 + vertex 1.67989 1.96158 2.4821 + vertex 1.68289 1.96381 2.48065 + endloop + endfacet + facet normal 0.291395 0.218695 0.931269 + outer loop + vertex 1.68289 1.96381 2.48065 + vertex 1.68294 1.96835 2.47957 + vertex 1.68002 1.96569 2.4811 + endloop + endfacet + facet normal 0.320341 0.21624 0.922292 + outer loop + vertex 1.68289 1.96381 2.48065 + vertex 1.68682 1.96373 2.4793 + vertex 1.68294 1.96835 2.47957 + endloop + endfacet + facet normal 0.301705 0.200047 0.932178 + outer loop + vertex 1.68294 1.96835 2.47957 + vertex 1.68682 1.96373 2.4793 + vertex 1.68672 1.96748 2.47853 + endloop + endfacet + facet normal 0.320252 0.217902 0.921931 + outer loop + vertex 1.68289 1.96381 2.48065 + vertex 1.68446 1.95988 2.48103 + vertex 1.68682 1.96373 2.4793 + endloop + endfacet + facet normal 0.34686 0.199181 0.916523 + outer loop + vertex 1.68887 1.95797 2.47978 + vertex 1.68682 1.96373 2.4793 + vertex 1.68446 1.95988 2.48103 + endloop + endfacet + facet normal 0.355122 0.224191 0.907539 + outer loop + vertex 1.68588 1.95601 2.48143 + vertex 1.68887 1.95797 2.47978 + vertex 1.68446 1.95988 2.48103 + endloop + endfacet + facet normal 0.311799 0.210259 0.926592 + outer loop + vertex 1.68446 1.95988 2.48103 + vertex 1.682 1.9562 2.4827 + vertex 1.68588 1.95601 2.48143 + endloop + endfacet + facet normal 0.312041 0.1983 0.929143 + outer loop + vertex 1.68588 1.95601 2.48143 + vertex 1.682 1.9562 2.4827 + vertex 1.68535 1.95197 2.48247 + endloop + endfacet + facet normal 0.354705 0.189243 0.915626 + outer loop + vertex 1.68588 1.95601 2.48143 + vertex 1.68535 1.95197 2.48247 + vertex 1.68832 1.95389 2.48093 + endloop + endfacet + facet normal 0.325377 0.209224 0.922147 + outer loop + vertex 1.682 1.9562 2.4827 + vertex 1.68195 1.95254 2.48354 + vertex 1.68535 1.95197 2.48247 + endloop + endfacet + facet normal 0.323932 0.193239 0.926136 + outer loop + vertex 1.68207 1.94869 2.48431 + vertex 1.68535 1.95197 2.48247 + vertex 1.68195 1.95254 2.48354 + endloop + endfacet + facet normal 0.299545 0.219347 0.928525 + outer loop + vertex 1.67989 1.96158 2.4821 + vertex 1.682 1.9562 2.4827 + vertex 1.68446 1.95988 2.48103 + endloop + endfacet + facet normal 0.287152 0.21504 0.933435 + outer loop + vertex 1.682 1.9562 2.4827 + vertex 1.67989 1.96158 2.4821 + vertex 1.67791 1.95818 2.4835 + endloop + endfacet + facet normal 0.286084 0.212456 0.934355 + outer loop + vertex 1.67804 1.95339 2.48455 + vertex 1.682 1.9562 2.4827 + vertex 1.67791 1.95818 2.4835 + endloop + endfacet + facet normal 0.277202 0.212772 0.936956 + outer loop + vertex 1.6734 1.95845 2.48477 + vertex 1.67804 1.95339 2.48455 + vertex 1.67791 1.95818 2.4835 + endloop + endfacet + facet normal 0.277177 0.217393 0.935902 + outer loop + vertex 1.67791 1.95818 2.4835 + vertex 1.67599 1.96146 2.4833 + vertex 1.6734 1.95845 2.48477 + endloop + endfacet + facet normal 0.277872 0.216767 0.935841 + outer loop + vertex 1.6734 1.95845 2.48477 + vertex 1.67599 1.96146 2.4833 + vertex 1.67305 1.9631 2.4838 + endloop + endfacet + facet normal 0.281247 0.216814 0.934822 + outer loop + vertex 1.66914 1.96302 2.48499 + vertex 1.6734 1.95845 2.48477 + vertex 1.67305 1.9631 2.4838 + endloop + endfacet + facet normal 0.281118 0.218372 0.934498 + outer loop + vertex 1.67305 1.9631 2.4838 + vertex 1.67113 1.96641 2.4836 + vertex 1.66914 1.96302 2.48499 + endloop + endfacet + facet normal 0.28316 0.217045 0.934191 + outer loop + vertex 1.66914 1.96302 2.48499 + vertex 1.67113 1.96641 2.4836 + vertex 1.66693 1.96853 2.48438 + endloop + endfacet + facet normal 0.28451 0.217527 0.933668 + outer loop + vertex 1.66914 1.96302 2.48499 + vertex 1.66693 1.96853 2.48438 + vertex 1.66449 1.96478 2.486 + endloop + endfacet + facet normal 0.283181 0.213222 0.935064 + outer loop + vertex 1.66612 1.96082 2.48641 + vertex 1.66914 1.96302 2.48499 + vertex 1.66449 1.96478 2.486 + endloop + endfacet + facet normal 0.284059 0.213548 0.934723 + outer loop + vertex 1.66449 1.96478 2.486 + vertex 1.66204 1.96102 2.4876 + vertex 1.66612 1.96082 2.48641 + endloop + endfacet + facet normal 0.284097 0.211171 0.935252 + outer loop + vertex 1.66612 1.96082 2.48641 + vertex 1.66204 1.96102 2.4876 + vertex 1.66605 1.95624 2.48747 + endloop + endfacet + facet normal 0.280933 0.211428 0.936149 + outer loop + vertex 1.66612 1.96082 2.48641 + vertex 1.66605 1.95624 2.48747 + vertex 1.66902 1.95888 2.48598 + endloop + endfacet + facet normal 0.280318 0.212134 0.936174 + outer loop + vertex 1.67053 1.95572 2.48624 + vertex 1.66902 1.95888 2.48598 + vertex 1.66605 1.95624 2.48747 + endloop + endfacet + facet normal 0.28017 0.209259 0.936865 + outer loop + vertex 1.67053 1.95572 2.48624 + vertex 1.66605 1.95624 2.48747 + vertex 1.67067 1.9511 2.48723 + endloop + endfacet + facet normal 0.275009 0.209427 0.938355 + outer loop + vertex 1.67053 1.95572 2.48624 + vertex 1.67067 1.9511 2.48723 + vertex 1.67356 1.95385 2.48577 + endloop + endfacet + facet normal 0.277063 0.213132 0.936916 + outer loop + vertex 1.67356 1.95385 2.48577 + vertex 1.6734 1.95845 2.48477 + vertex 1.67053 1.95572 2.48624 + endloop + endfacet + facet normal 0.274364 0.210124 0.938388 + outer loop + vertex 1.67507 1.95069 2.48604 + vertex 1.67356 1.95385 2.48577 + vertex 1.67067 1.9511 2.48723 + endloop + endfacet + facet normal 0.274211 0.204991 0.939567 + outer loop + vertex 1.67507 1.95069 2.48604 + vertex 1.67067 1.9511 2.48723 + vertex 1.67483 1.94655 2.48701 + endloop + endfacet + facet normal 0.276906 0.204672 0.938846 + outer loop + vertex 1.67507 1.95069 2.48604 + vertex 1.67483 1.94655 2.48701 + vertex 1.67797 1.94878 2.4856 + endloop + endfacet + facet normal 0.27959 0.209168 0.937058 + outer loop + vertex 1.67797 1.94878 2.4856 + vertex 1.67804 1.95339 2.48455 + vertex 1.67507 1.95069 2.48604 + endloop + endfacet + facet normal 0.298149 0.207647 0.93166 + outer loop + vertex 1.67797 1.94878 2.4856 + vertex 1.68207 1.94869 2.48431 + vertex 1.67804 1.95339 2.48455 + endloop + endfacet + facet normal 0.28326 0.194541 0.939105 + outer loop + vertex 1.67804 1.95339 2.48455 + vertex 1.68207 1.94869 2.48431 + vertex 1.68195 1.95254 2.48354 + endloop + endfacet + facet normal 0.298273 0.204627 0.932288 + outer loop + vertex 1.67797 1.94878 2.4856 + vertex 1.67948 1.94482 2.48598 + vertex 1.68207 1.94869 2.48431 + endloop + endfacet + facet normal 0.314553 0.192535 0.929509 + outer loop + vertex 1.68399 1.94304 2.48483 + vertex 1.68207 1.94869 2.48431 + vertex 1.67948 1.94482 2.48598 + endloop + endfacet + facet normal 0.318446 0.205009 0.925507 + outer loop + vertex 1.68087 1.94093 2.48637 + vertex 1.68399 1.94304 2.48483 + vertex 1.67948 1.94482 2.48598 + endloop + endfacet + facet normal 0.288967 0.195613 0.937141 + outer loop + vertex 1.67948 1.94482 2.48598 + vertex 1.67673 1.94106 2.48762 + vertex 1.68087 1.94093 2.48637 + endloop + endfacet + facet normal 0.281893 0.201209 0.938111 + outer loop + vertex 1.67483 1.94655 2.48701 + vertex 1.67673 1.94106 2.48762 + vertex 1.67948 1.94482 2.48598 + endloop + endfacet + facet normal 0.277747 0.199942 0.939617 + outer loop + vertex 1.67673 1.94106 2.48762 + vertex 1.67483 1.94655 2.48701 + vertex 1.67262 1.94321 2.48838 + endloop + endfacet + facet normal 0.277019 0.198349 0.940169 + outer loop + vertex 1.67225 1.93871 2.48943 + vertex 1.67673 1.94106 2.48762 + vertex 1.67262 1.94321 2.48838 + endloop + endfacet + facet normal 0.278907 0.194876 0.940337 + outer loop + vertex 1.67638 1.93658 2.48865 + vertex 1.67673 1.94106 2.48762 + vertex 1.67225 1.93871 2.48943 + endloop + endfacet + facet normal 0.277736 0.192282 0.941217 + outer loop + vertex 1.67424 1.93309 2.48999 + vertex 1.67638 1.93658 2.48865 + vertex 1.67225 1.93871 2.48943 + endloop + endfacet + facet normal 0.281239 0.193394 0.939949 + outer loop + vertex 1.67424 1.93309 2.48999 + vertex 1.67225 1.93871 2.48943 + vertex 1.66954 1.93485 2.49104 + endloop + endfacet + facet normal 0.280823 0.192045 0.94035 + outer loop + vertex 1.6711 1.93081 2.4914 + vertex 1.67424 1.93309 2.48999 + vertex 1.66954 1.93485 2.49104 + endloop + endfacet + facet normal 0.280426 0.191905 0.940497 + outer loop + vertex 1.66954 1.93485 2.49104 + vertex 1.66684 1.931 2.49263 + vertex 1.6711 1.93081 2.4914 + endloop + endfacet + facet normal 0.280504 0.184822 0.941891 + outer loop + vertex 1.6711 1.93081 2.4914 + vertex 1.66684 1.931 2.49263 + vertex 1.67095 1.92616 2.49235 + endloop + endfacet + facet normal 0.280444 0.184828 0.941908 + outer loop + vertex 1.6711 1.93081 2.4914 + vertex 1.67095 1.92616 2.49235 + vertex 1.67395 1.92889 2.49093 + endloop + endfacet + facet normal 0.283196 0.181696 0.941693 + outer loop + vertex 1.6752 1.92583 2.49114 + vertex 1.67395 1.92889 2.49093 + vertex 1.67095 1.92616 2.49235 + endloop + endfacet + facet normal 0.283089 0.176669 0.942682 + outer loop + vertex 1.6752 1.92583 2.49114 + vertex 1.67095 1.92616 2.49235 + vertex 1.67483 1.92166 2.49203 + endloop + endfacet + facet normal 0.302289 0.17376 0.937245 + outer loop + vertex 1.6752 1.92583 2.49114 + vertex 1.67483 1.92166 2.49203 + vertex 1.67793 1.92394 2.49061 + endloop + endfacet + facet normal 0.30512 0.178328 0.935468 + outer loop + vertex 1.67793 1.92394 2.49061 + vertex 1.6782 1.9285 2.48965 + vertex 1.6752 1.92583 2.49114 + endloop + endfacet + facet normal 0.286595 0.179799 0.941029 + outer loop + vertex 1.67095 1.92616 2.49235 + vertex 1.67095 1.92153 2.49324 + vertex 1.67483 1.92166 2.49203 + endloop + endfacet + facet normal 0.286643 0.179227 0.941124 + outer loop + vertex 1.67255 1.91827 2.49337 + vertex 1.67483 1.92166 2.49203 + vertex 1.67095 1.92153 2.49324 + endloop + endfacet + facet normal 0.280563 0.176341 0.943498 + outer loop + vertex 1.67255 1.91827 2.49337 + vertex 1.67095 1.92153 2.49324 + vertex 1.66812 1.9185 2.49465 + endloop + endfacet + facet normal 0.280554 0.178763 0.943045 + outer loop + vertex 1.66812 1.9185 2.49465 + vertex 1.67214 1.91372 2.49436 + vertex 1.67255 1.91827 2.49337 + endloop + endfacet + facet normal 0.299056 0.175977 0.937869 + outer loop + vertex 1.67214 1.91372 2.49436 + vertex 1.67654 1.91607 2.49251 + vertex 1.67255 1.91827 2.49337 + endloop + endfacet + facet normal 0.296581 0.180546 0.937786 + outer loop + vertex 1.67615 1.91157 2.4935 + vertex 1.67654 1.91607 2.49251 + vertex 1.67214 1.91372 2.49436 + endloop + endfacet + facet normal 0.298186 0.184005 0.936604 + outer loop + vertex 1.67411 1.90807 2.49484 + vertex 1.67615 1.91157 2.4935 + vertex 1.67214 1.91372 2.49436 + endloop + endfacet + facet normal 0.287974 0.18077 0.940422 + outer loop + vertex 1.67411 1.90807 2.49484 + vertex 1.67214 1.91372 2.49436 + vertex 1.66948 1.90981 2.49592 + endloop + endfacet + facet normal 0.290952 0.190449 0.937591 + outer loop + vertex 1.67105 1.90577 2.49625 + vertex 1.67411 1.90807 2.49484 + vertex 1.66948 1.90981 2.49592 + endloop + endfacet + facet normal 0.282157 0.187306 0.940906 + outer loop + vertex 1.66948 1.90981 2.49592 + vertex 1.6668 1.90594 2.49749 + vertex 1.67105 1.90577 2.49625 + endloop + endfacet + facet normal 0.282188 0.18539 0.941276 + outer loop + vertex 1.67105 1.90577 2.49625 + vertex 1.6668 1.90594 2.49749 + vertex 1.67083 1.90115 2.49723 + endloop + endfacet + facet normal 0.291523 0.184389 0.938624 + outer loop + vertex 1.67105 1.90577 2.49625 + vertex 1.67083 1.90115 2.49723 + vertex 1.67386 1.90386 2.49576 + endloop + endfacet + facet normal 0.294689 0.1807 0.938353 + outer loop + vertex 1.67503 1.90079 2.49598 + vertex 1.67386 1.90386 2.49576 + vertex 1.67083 1.90115 2.49723 + endloop + endfacet + facet normal 0.294642 0.178933 0.938706 + outer loop + vertex 1.67503 1.90079 2.49598 + vertex 1.67083 1.90115 2.49723 + vertex 1.6745 1.89659 2.49695 + endloop + endfacet + facet normal 0.321387 0.173688 0.930883 + outer loop + vertex 1.67503 1.90079 2.49598 + vertex 1.6745 1.89659 2.49695 + vertex 1.67754 1.89879 2.49549 + endloop + endfacet + facet normal 0.330783 0.18694 0.925006 + outer loop + vertex 1.67754 1.89879 2.49549 + vertex 1.678 1.90337 2.4944 + vertex 1.67503 1.90079 2.49598 + endloop + endfacet + facet normal 0.297259 0.181114 0.937462 + outer loop + vertex 1.67083 1.90115 2.49723 + vertex 1.67059 1.89651 2.4982 + vertex 1.6745 1.89659 2.49695 + endloop + endfacet + facet normal 0.297466 0.178369 0.937922 + outer loop + vertex 1.672 1.89257 2.49851 + vertex 1.6745 1.89659 2.49695 + vertex 1.67059 1.89651 2.4982 + endloop + endfacet + facet normal 0.284758 0.174189 0.94264 + outer loop + vertex 1.672 1.89257 2.49851 + vertex 1.67059 1.89651 2.4982 + vertex 1.66746 1.89399 2.49961 + endloop + endfacet + facet normal 0.285549 0.17738 0.941806 + outer loop + vertex 1.66946 1.88842 2.50006 + vertex 1.672 1.89257 2.49851 + vertex 1.66746 1.89399 2.49961 + endloop + endfacet + facet normal 0.2809 0.175848 0.94349 + outer loop + vertex 1.66946 1.88842 2.50006 + vertex 1.66746 1.89399 2.49961 + vertex 1.66475 1.89007 2.50115 + endloop + endfacet + facet normal 0.281992 0.179648 0.942447 + outer loop + vertex 1.66617 1.88604 2.50149 + vertex 1.66946 1.88842 2.50006 + vertex 1.66475 1.89007 2.50115 + endloop + endfacet + facet normal 0.277706 0.178263 0.943982 + outer loop + vertex 1.66475 1.89007 2.50115 + vertex 1.66195 1.88616 2.50272 + vertex 1.66617 1.88604 2.50149 + endloop + endfacet + facet normal 0.277719 0.177717 0.944081 + outer loop + vertex 1.66617 1.88604 2.50149 + vertex 1.66195 1.88616 2.50272 + vertex 1.66598 1.88133 2.50244 + endloop + endfacet + facet normal 0.282974 0.177209 0.942615 + outer loop + vertex 1.66617 1.88604 2.50149 + vertex 1.66598 1.88133 2.50244 + vertex 1.66901 1.88408 2.50101 + endloop + endfacet + facet normal 0.284703 0.175231 0.942464 + outer loop + vertex 1.67026 1.88096 2.50122 + vertex 1.66901 1.88408 2.50101 + vertex 1.66598 1.88133 2.50244 + endloop + endfacet + facet normal 0.284649 0.173561 0.942789 + outer loop + vertex 1.67026 1.88096 2.50122 + vertex 1.66598 1.88133 2.50244 + vertex 1.66993 1.87676 2.50209 + endloop + endfacet + facet normal 0.30268 0.171074 0.937613 + outer loop + vertex 1.67026 1.88096 2.50122 + vertex 1.66993 1.87676 2.50209 + vertex 1.67301 1.87904 2.50068 + endloop + endfacet + facet normal 0.305283 0.175274 0.935992 + outer loop + vertex 1.67301 1.87904 2.50068 + vertex 1.67333 1.88362 2.49972 + vertex 1.67026 1.88096 2.50122 + endloop + endfacet + facet normal 0.28832 0.176861 0.941059 + outer loop + vertex 1.66598 1.88133 2.50244 + vertex 1.66603 1.87666 2.5033 + vertex 1.66993 1.87676 2.50209 + endloop + endfacet + facet normal 0.28846 0.175029 0.941358 + outer loop + vertex 1.66769 1.87336 2.5034 + vertex 1.66993 1.87676 2.50209 + vertex 1.66603 1.87666 2.5033 + endloop + endfacet + facet normal 0.281594 0.171659 0.944054 + outer loop + vertex 1.66769 1.87336 2.5034 + vertex 1.66603 1.87666 2.5033 + vertex 1.66323 1.87363 2.50469 + endloop + endfacet + facet normal 0.281589 0.170791 0.944213 + outer loop + vertex 1.66323 1.87363 2.50469 + vertex 1.66724 1.86879 2.50437 + vertex 1.66769 1.87336 2.5034 + endloop + endfacet + facet normal 0.297627 0.16826 0.939738 + outer loop + vertex 1.66724 1.86879 2.50437 + vertex 1.6717 1.87118 2.50253 + vertex 1.66769 1.87336 2.5034 + endloop + endfacet + facet normal 0.296673 0.17003 0.939721 + outer loop + vertex 1.67119 1.8667 2.5035 + vertex 1.6717 1.87118 2.50253 + vertex 1.66724 1.86879 2.50437 + endloop + endfacet + facet normal 0.295926 0.168398 0.94025 + outer loop + vertex 1.66893 1.86325 2.50483 + vertex 1.67119 1.8667 2.5035 + vertex 1.66724 1.86879 2.50437 + endloop + endfacet + facet normal 0.2873 0.166034 0.943341 + outer loop + vertex 1.66893 1.86325 2.50483 + vertex 1.66724 1.86879 2.50437 + vertex 1.66445 1.86484 2.50591 + endloop + endfacet + facet normal 0.288864 0.171419 0.941899 + outer loop + vertex 1.66577 1.86092 2.50622 + vertex 1.66893 1.86325 2.50483 + vertex 1.66445 1.86484 2.50591 + endloop + endfacet + facet normal 0.277131 0.167801 0.946066 + outer loop + vertex 1.66445 1.86484 2.50591 + vertex 1.66174 1.86088 2.50741 + vertex 1.66577 1.86092 2.50622 + endloop + endfacet + facet normal 0.277213 0.16633 0.946302 + outer loop + vertex 1.66577 1.86092 2.50622 + vertex 1.66174 1.86088 2.50741 + vertex 1.66521 1.85672 2.50712 + endloop + endfacet + facet normal 0.289061 0.164063 0.943147 + outer loop + vertex 1.66577 1.86092 2.50622 + vertex 1.66521 1.85672 2.50712 + vertex 1.66841 1.85902 2.50574 + endloop + endfacet + facet normal 0.293918 0.157091 0.942833 + outer loop + vertex 1.66962 1.85512 2.50601 + vertex 1.66841 1.85902 2.50574 + vertex 1.66521 1.85672 2.50712 + endloop + endfacet + facet normal 0.297173 0.168099 0.93991 + outer loop + vertex 1.66521 1.85672 2.50712 + vertex 1.66673 1.85131 2.50761 + vertex 1.66962 1.85512 2.50601 + endloop + endfacet + facet normal 0.304468 0.162056 0.938636 + outer loop + vertex 1.66962 1.85512 2.50601 + vertex 1.66673 1.85131 2.50761 + vertex 1.67077 1.85121 2.50632 + endloop + endfacet + facet normal 0.354189 0.175156 0.918624 + outer loop + vertex 1.67077 1.85121 2.50632 + vertex 1.67397 1.85323 2.5047 + vertex 1.66962 1.85512 2.50601 + endloop + endfacet + facet normal 0.345177 0.148817 0.926664 + outer loop + vertex 1.67397 1.85323 2.5047 + vertex 1.6724 1.85906 2.50435 + vertex 1.66962 1.85512 2.50601 + endloop + endfacet + facet normal 0.362541 0.161371 0.917891 + outer loop + vertex 1.67312 1.84907 2.50576 + vertex 1.67397 1.85323 2.5047 + vertex 1.67077 1.85121 2.50632 + endloop + endfacet + facet normal 0.349277 0.144715 0.925777 + outer loop + vertex 1.67077 1.85121 2.50632 + vertex 1.67007 1.84702 2.50723 + vertex 1.67312 1.84907 2.50576 + endloop + endfacet + facet normal 0.30465 0.155229 0.93973 + outer loop + vertex 1.67077 1.85121 2.50632 + vertex 1.66673 1.85131 2.50761 + vertex 1.67007 1.84702 2.50723 + endloop + endfacet + facet normal 0.310647 0.160145 0.936938 + outer loop + vertex 1.66673 1.85131 2.50761 + vertex 1.66621 1.84681 2.50855 + vertex 1.67007 1.84702 2.50723 + endloop + endfacet + facet normal 0.310547 0.161118 0.936804 + outer loop + vertex 1.66787 1.84359 2.50855 + vertex 1.67007 1.84702 2.50723 + vertex 1.66621 1.84681 2.50855 + endloop + endfacet + facet normal 0.292277 0.151723 0.944222 + outer loop + vertex 1.66787 1.84359 2.50855 + vertex 1.66621 1.84681 2.50855 + vertex 1.66395 1.84327 2.50982 + endloop + endfacet + facet normal 0.292925 0.146298 0.944877 + outer loop + vertex 1.66395 1.84327 2.50982 + vertex 1.66757 1.83893 2.50937 + vertex 1.66787 1.84359 2.50855 + endloop + endfacet + facet normal 0.3416 0.140422 0.929296 + outer loop + vertex 1.66757 1.83893 2.50937 + vertex 1.67126 1.8419 2.50756 + vertex 1.66787 1.84359 2.50855 + endloop + endfacet + facet normal 0.350489 0.12841 0.927722 + outer loop + vertex 1.6724 1.83648 2.50788 + vertex 1.67126 1.8419 2.50756 + vertex 1.66757 1.83893 2.50937 + endloop + endfacet + facet normal 0.36281 0.158442 0.918295 + outer loop + vertex 1.66904 1.83321 2.50978 + vertex 1.6724 1.83648 2.50788 + vertex 1.66757 1.83893 2.50937 + endloop + endfacet + facet normal 0.316265 0.147814 0.937085 + outer loop + vertex 1.66904 1.83321 2.50978 + vertex 1.66757 1.83893 2.50937 + vertex 1.66466 1.835 2.51097 + endloop + endfacet + facet normal 0.320703 0.161177 0.933366 + outer loop + vertex 1.6658 1.83107 2.51126 + vertex 1.66904 1.83321 2.50978 + vertex 1.66466 1.835 2.51097 + endloop + endfacet + facet normal 0.286418 0.152176 0.945942 + outer loop + vertex 1.66466 1.835 2.51097 + vertex 1.66176 1.83105 2.51248 + vertex 1.6658 1.83107 2.51126 + endloop + endfacet + facet normal 0.286847 0.143028 0.947239 + outer loop + vertex 1.6658 1.83107 2.51126 + vertex 1.66176 1.83105 2.51248 + vertex 1.66496 1.82678 2.51216 + endloop + endfacet + facet normal 0.315712 0.135651 0.939108 + outer loop + vertex 1.6658 1.83107 2.51126 + vertex 1.66496 1.82678 2.51216 + vertex 1.66825 1.82907 2.51072 + endloop + endfacet + facet normal 0.289934 0.145436 0.945932 + outer loop + vertex 1.66176 1.83105 2.51248 + vertex 1.66099 1.82667 2.51339 + vertex 1.66496 1.82678 2.51216 + endloop + endfacet + facet normal 0.290138 0.14246 0.946322 + outer loop + vertex 1.66213 1.82275 2.51363 + vertex 1.66496 1.82678 2.51216 + vertex 1.66099 1.82667 2.51339 + endloop + endfacet + facet normal 0.280066 0.139726 0.949758 + outer loop + vertex 1.66213 1.82275 2.51363 + vertex 1.66099 1.82667 2.51339 + vertex 1.65764 1.82421 2.51474 + endloop + endfacet + facet normal 0.280886 0.142777 0.949062 + outer loop + vertex 1.65936 1.81861 2.51508 + vertex 1.66213 1.82275 2.51363 + vertex 1.65764 1.82421 2.51474 + endloop + endfacet + facet normal 0.281147 0.142852 0.948973 + outer loop + vertex 1.65936 1.81861 2.51508 + vertex 1.65764 1.82421 2.51474 + vertex 1.65477 1.82025 2.51619 + endloop + endfacet + facet normal 0.281912 0.145411 0.948357 + outer loop + vertex 1.656 1.81628 2.51643 + vertex 1.65936 1.81861 2.51508 + vertex 1.65477 1.82025 2.51619 + endloop + endfacet + facet normal 0.282445 0.145565 0.948175 + outer loop + vertex 1.65477 1.82025 2.51619 + vertex 1.65189 1.81637 2.51764 + vertex 1.656 1.81628 2.51643 + endloop + endfacet + facet normal 0.28245 0.145329 0.94821 + outer loop + vertex 1.656 1.81628 2.51643 + vertex 1.65189 1.81637 2.51764 + vertex 1.65541 1.81197 2.51727 + endloop + endfacet + facet normal 0.283924 0.145048 0.947812 + outer loop + vertex 1.656 1.81628 2.51643 + vertex 1.65541 1.81197 2.51727 + vertex 1.65869 1.81422 2.51594 + endloop + endfacet + facet normal 0.285537 0.142628 0.947695 + outer loop + vertex 1.65989 1.81024 2.51618 + vertex 1.65869 1.81422 2.51594 + vertex 1.65541 1.81197 2.51727 + endloop + endfacet + facet normal 0.285661 0.143007 0.947601 + outer loop + vertex 1.65541 1.81197 2.51727 + vertex 1.65689 1.80636 2.51767 + vertex 1.65989 1.81024 2.51618 + endloop + endfacet + facet normal 0.288184 0.140885 0.947154 + outer loop + vertex 1.65989 1.81024 2.51618 + vertex 1.65689 1.80636 2.51767 + vertex 1.66103 1.80626 2.51643 + endloop + endfacet + facet normal 0.307617 0.146032 0.940238 + outer loop + vertex 1.66103 1.80626 2.51643 + vertex 1.66424 1.80855 2.51502 + vertex 1.65989 1.81024 2.51618 + endloop + endfacet + facet normal 0.304543 0.136395 0.942682 + outer loop + vertex 1.66424 1.80855 2.51502 + vertex 1.66282 1.81407 2.51468 + vertex 1.65989 1.81024 2.51618 + endloop + endfacet + facet normal 0.316462 0.132996 0.939236 + outer loop + vertex 1.66352 1.80427 2.51587 + vertex 1.66424 1.80855 2.51502 + vertex 1.66103 1.80626 2.51643 + endloop + endfacet + facet normal 0.309632 0.123475 0.942805 + outer loop + vertex 1.66103 1.80626 2.51643 + vertex 1.66014 1.80192 2.51729 + vertex 1.66352 1.80427 2.51587 + endloop + endfacet + facet normal 0.288393 0.129012 0.948781 + outer loop + vertex 1.66103 1.80626 2.51643 + vertex 1.65689 1.80636 2.51767 + vertex 1.66014 1.80192 2.51729 + endloop + endfacet + facet normal 0.291332 0.131259 0.947574 + outer loop + vertex 1.65689 1.80636 2.51767 + vertex 1.65605 1.80172 2.51857 + vertex 1.66014 1.80192 2.51729 + endloop + endfacet + facet normal 0.292322 0.119031 0.948883 + outer loop + vertex 1.65732 1.79775 2.51868 + vertex 1.66014 1.80192 2.51729 + vertex 1.65605 1.80172 2.51857 + endloop + endfacet + facet normal 0.28144 0.115652 0.952584 + outer loop + vertex 1.65732 1.79775 2.51868 + vertex 1.65605 1.80172 2.51857 + vertex 1.6533 1.79868 2.51975 + endloop + endfacet + facet normal 0.275534 0.121383 0.953597 + outer loop + vertex 1.6533 1.79868 2.51975 + vertex 1.65605 1.80172 2.51857 + vertex 1.6523 1.80393 2.51937 + endloop + endfacet + facet normal 0.279157 0.121992 0.952465 + outer loop + vertex 1.6533 1.79868 2.51975 + vertex 1.6523 1.80393 2.51937 + vertex 1.64919 1.79995 2.52079 + endloop + endfacet + facet normal 0.274802 0.105215 0.955727 + outer loop + vertex 1.65019 1.79513 2.52104 + vertex 1.6533 1.79868 2.51975 + vertex 1.64919 1.79995 2.52079 + endloop + endfacet + facet normal 0.279808 0.106177 0.954167 + outer loop + vertex 1.64919 1.79995 2.52079 + vertex 1.64599 1.79632 2.52214 + vertex 1.65019 1.79513 2.52104 + endloop + endfacet + facet normal 0.276583 0.0925907 0.956519 + outer loop + vertex 1.64599 1.79632 2.52214 + vertex 1.64703 1.79103 2.52235 + vertex 1.65019 1.79513 2.52104 + endloop + endfacet + facet normal 0.274808 0.0940785 0.956886 + outer loop + vertex 1.65019 1.79513 2.52104 + vertex 1.64703 1.79103 2.52235 + vertex 1.651 1.79116 2.5212 + endloop + endfacet + facet normal 0.274876 0.0940916 0.956865 + outer loop + vertex 1.651 1.79116 2.5212 + vertex 1.65447 1.79357 2.51996 + vertex 1.65019 1.79513 2.52104 + endloop + endfacet + facet normal 0.277573 0.102603 0.95521 + outer loop + vertex 1.65447 1.79357 2.51996 + vertex 1.6533 1.79868 2.51975 + vertex 1.65019 1.79513 2.52104 + endloop + endfacet + facet normal 0.279079 0.10293 0.954736 + outer loop + vertex 1.65447 1.79357 2.51996 + vertex 1.65732 1.79775 2.51868 + vertex 1.6533 1.79868 2.51975 + endloop + endfacet + facet normal 0.285214 0.0983507 0.953405 + outer loop + vertex 1.65847 1.79385 2.51874 + vertex 1.65732 1.79775 2.51868 + vertex 1.65447 1.79357 2.51996 + endloop + endfacet + facet normal 0.286045 0.0893561 0.954041 + outer loop + vertex 1.65447 1.79357 2.51996 + vertex 1.65754 1.78913 2.51946 + vertex 1.65847 1.79385 2.51874 + endloop + endfacet + facet normal 0.319594 0.0812564 0.944064 + outer loop + vertex 1.65754 1.78913 2.51946 + vertex 1.66169 1.79202 2.5178 + vertex 1.65847 1.79385 2.51874 + endloop + endfacet + facet normal 0.321919 0.0859779 0.942855 + outer loop + vertex 1.66169 1.79202 2.5178 + vertex 1.66121 1.79684 2.51753 + vertex 1.65847 1.79385 2.51874 + endloop + endfacet + facet normal 0.321266 0.0786559 0.943717 + outer loop + vertex 1.66228 1.78654 2.51806 + vertex 1.66169 1.79202 2.5178 + vertex 1.65754 1.78913 2.51946 + endloop + endfacet + facet normal 0.331426 0.10026 0.938139 + outer loop + vertex 1.65832 1.78361 2.51977 + vertex 1.66228 1.78654 2.51806 + vertex 1.65754 1.78913 2.51946 + endloop + endfacet + facet normal 0.285838 0.0947015 0.953587 + outer loop + vertex 1.65832 1.78361 2.51977 + vertex 1.65754 1.78913 2.51946 + vertex 1.65417 1.7851 2.52087 + endloop + endfacet + facet normal 0.289448 0.106503 0.95125 + outer loop + vertex 1.6551 1.78022 2.52113 + vertex 1.65832 1.78361 2.51977 + vertex 1.65417 1.7851 2.52087 + endloop + endfacet + facet normal 0.270193 0.10315 0.957265 + outer loop + vertex 1.65417 1.7851 2.52087 + vertex 1.65086 1.78146 2.52219 + vertex 1.6551 1.78022 2.52113 + endloop + endfacet + facet normal 0.274702 0.0987588 0.956444 + outer loop + vertex 1.64984 1.78676 2.52194 + vertex 1.65086 1.78146 2.52219 + vertex 1.65417 1.7851 2.52087 + endloop + endfacet + facet normal 0.272703 0.0928025 0.957612 + outer loop + vertex 1.65417 1.7851 2.52087 + vertex 1.6534 1.78918 2.52069 + vertex 1.64984 1.78676 2.52194 + endloop + endfacet + facet normal 0.274851 0.0894844 0.957314 + outer loop + vertex 1.651 1.79116 2.5212 + vertex 1.64984 1.78676 2.52194 + vertex 1.6534 1.78918 2.52069 + endloop + endfacet + facet normal 0.270236 0.0979648 0.957797 + outer loop + vertex 1.65086 1.78146 2.52219 + vertex 1.64984 1.78676 2.52194 + vertex 1.64661 1.7826 2.52328 + endloop + endfacet + facet normal 0.273895 0.0948839 0.957068 + outer loop + vertex 1.64661 1.7826 2.52328 + vertex 1.64984 1.78676 2.52194 + vertex 1.64585 1.78662 2.52309 + endloop + endfacet + facet normal 0.28139 0.0961868 0.954761 + outer loop + vertex 1.64661 1.7826 2.52328 + vertex 1.64585 1.78662 2.52309 + vertex 1.64229 1.78415 2.52439 + endloop + endfacet + facet normal 0.282716 0.100471 0.953927 + outer loop + vertex 1.64332 1.77888 2.52464 + vertex 1.64661 1.7826 2.52328 + vertex 1.64229 1.78415 2.52439 + endloop + endfacet + facet normal 0.285414 0.100953 0.953073 + outer loop + vertex 1.64332 1.77888 2.52464 + vertex 1.64229 1.78415 2.52439 + vertex 1.63911 1.78006 2.52578 + endloop + endfacet + facet normal 0.287485 0.109919 0.951457 + outer loop + vertex 1.64008 1.77526 2.52604 + vertex 1.64332 1.77888 2.52464 + vertex 1.63911 1.78006 2.52578 + endloop + endfacet + facet normal 0.289251 0.110246 0.950884 + outer loop + vertex 1.63911 1.78006 2.52578 + vertex 1.63599 1.77655 2.52714 + vertex 1.64008 1.77526 2.52604 + endloop + endfacet + facet normal 0.291359 0.118306 0.94927 + outer loop + vertex 1.63599 1.77655 2.52714 + vertex 1.63692 1.7713 2.5275 + vertex 1.64008 1.77526 2.52604 + endloop + endfacet + facet normal 0.290073 0.119428 0.949523 + outer loop + vertex 1.64008 1.77526 2.52604 + vertex 1.63692 1.7713 2.5275 + vertex 1.64096 1.77124 2.52628 + endloop + endfacet + facet normal 0.283963 0.118208 0.951521 + outer loop + vertex 1.64096 1.77124 2.52628 + vertex 1.64444 1.7736 2.52495 + vertex 1.64008 1.77526 2.52604 + endloop + endfacet + facet normal 0.281819 0.121493 0.951744 + outer loop + vertex 1.64349 1.76922 2.52579 + vertex 1.64444 1.7736 2.52495 + vertex 1.64096 1.77124 2.52628 + endloop + endfacet + facet normal 0.284766 0.12552 0.950344 + outer loop + vertex 1.64096 1.77124 2.52628 + vertex 1.64012 1.7668 2.52711 + vertex 1.64349 1.76922 2.52579 + endloop + endfacet + facet normal 0.283433 0.127451 0.950485 + outer loop + vertex 1.64463 1.76519 2.52599 + vertex 1.64349 1.76922 2.52579 + vertex 1.64012 1.7668 2.52711 + endloop + endfacet + facet normal 0.281774 0.121982 0.951695 + outer loop + vertex 1.64012 1.7668 2.52711 + vertex 1.64175 1.76114 2.52736 + vertex 1.64463 1.76519 2.52599 + endloop + endfacet + facet normal 0.280135 0.123255 0.952015 + outer loop + vertex 1.64463 1.76519 2.52599 + vertex 1.64175 1.76114 2.52736 + vertex 1.64582 1.76111 2.52617 + endloop + endfacet + facet normal 0.26791 0.119877 0.955957 + outer loop + vertex 1.64582 1.76111 2.52617 + vertex 1.64924 1.76353 2.5249 + vertex 1.64463 1.76519 2.52599 + endloop + endfacet + facet normal 0.270015 0.126703 0.954483 + outer loop + vertex 1.64924 1.76353 2.5249 + vertex 1.64759 1.76923 2.52461 + vertex 1.64463 1.76519 2.52599 + endloop + endfacet + facet normal 0.261852 0.124477 0.957047 + outer loop + vertex 1.64924 1.76353 2.5249 + vertex 1.65222 1.76764 2.52355 + vertex 1.64759 1.76923 2.52461 + endloop + endfacet + facet normal 0.262914 0.128091 0.956279 + outer loop + vertex 1.65222 1.76764 2.52355 + vertex 1.65106 1.77171 2.52333 + vertex 1.64759 1.76923 2.52461 + endloop + endfacet + facet normal 0.263929 0.126628 0.956194 + outer loop + vertex 1.64759 1.76923 2.52461 + vertex 1.65106 1.77171 2.52333 + vertex 1.64848 1.77369 2.52378 + endloop + endfacet + facet normal 0.273272 0.124344 0.953866 + outer loop + vertex 1.64444 1.7736 2.52495 + vertex 1.64759 1.76923 2.52461 + vertex 1.64848 1.77369 2.52378 + endloop + endfacet + facet normal 0.273643 0.117374 0.954643 + outer loop + vertex 1.64848 1.77369 2.52378 + vertex 1.64758 1.77774 2.52354 + vertex 1.64444 1.7736 2.52495 + endloop + endfacet + facet normal 0.278232 0.113594 0.953773 + outer loop + vertex 1.64444 1.7736 2.52495 + vertex 1.64758 1.77774 2.52354 + vertex 1.64332 1.77888 2.52464 + endloop + endfacet + facet normal 0.265918 0.115792 0.957016 + outer loop + vertex 1.64848 1.77369 2.52378 + vertex 1.65201 1.77615 2.5225 + vertex 1.64758 1.77774 2.52354 + endloop + endfacet + facet normal 0.264797 0.112172 0.957758 + outer loop + vertex 1.65201 1.77615 2.5225 + vertex 1.65086 1.78146 2.52219 + vertex 1.64758 1.77774 2.52354 + endloop + endfacet + facet normal 0.271919 0.105441 0.956526 + outer loop + vertex 1.64758 1.77774 2.52354 + vertex 1.65086 1.78146 2.52219 + vertex 1.64661 1.7826 2.52328 + endloop + endfacet + facet normal 0.272797 0.113766 0.955321 + outer loop + vertex 1.65086 1.78146 2.52219 + vertex 1.65201 1.77615 2.5225 + vertex 1.6551 1.78022 2.52113 + endloop + endfacet + facet normal 0.269287 0.116638 0.955971 + outer loop + vertex 1.6551 1.78022 2.52113 + vertex 1.65201 1.77615 2.5225 + vertex 1.65603 1.77624 2.52136 + endloop + endfacet + facet normal 0.298359 0.122878 0.946511 + outer loop + vertex 1.65603 1.77624 2.52136 + vertex 1.65928 1.77853 2.52003 + vertex 1.6551 1.78022 2.52113 + endloop + endfacet + facet normal 0.291861 0.104016 0.950788 + outer loop + vertex 1.65928 1.77853 2.52003 + vertex 1.65832 1.78361 2.51977 + vertex 1.6551 1.78022 2.52113 + endloop + endfacet + facet normal 0.329501 0.110429 0.937675 + outer loop + vertex 1.65928 1.77853 2.52003 + vertex 1.66159 1.78196 2.51882 + vertex 1.65832 1.78361 2.51977 + endloop + endfacet + facet normal 0.354627 0.0909702 0.930572 + outer loop + vertex 1.66287 1.77887 2.51863 + vertex 1.66159 1.78196 2.51882 + vertex 1.65928 1.77853 2.52003 + endloop + endfacet + facet normal 0.353564 0.100151 0.930034 + outer loop + vertex 1.65928 1.77853 2.52003 + vertex 1.66239 1.77432 2.5193 + vertex 1.66287 1.77887 2.51863 + endloop + endfacet + facet normal 0.362807 0.107739 0.925615 + outer loop + vertex 1.65855 1.77427 2.52082 + vertex 1.66239 1.77432 2.5193 + vertex 1.65928 1.77853 2.52003 + endloop + endfacet + facet normal 0.361829 0.125233 0.923795 + outer loop + vertex 1.65855 1.77427 2.52082 + vertex 1.65966 1.77024 2.52093 + vertex 1.66239 1.77432 2.5193 + endloop + endfacet + facet normal 0.394905 0.0990352 0.913369 + outer loop + vertex 1.6638 1.76852 2.51932 + vertex 1.66239 1.77432 2.5193 + vertex 1.65966 1.77024 2.52093 + endloop + endfacet + facet normal 0.408065 0.141519 0.901917 + outer loop + vertex 1.66077 1.7662 2.52106 + vertex 1.6638 1.76852 2.51932 + vertex 1.65966 1.77024 2.52093 + endloop + endfacet + facet normal 0.323195 0.119468 0.938761 + outer loop + vertex 1.65966 1.77024 2.52093 + vertex 1.65681 1.76612 2.52243 + vertex 1.66077 1.7662 2.52106 + endloop + endfacet + facet normal 0.323521 0.113776 0.939356 + outer loop + vertex 1.66077 1.7662 2.52106 + vertex 1.65681 1.76612 2.52243 + vertex 1.65987 1.76182 2.5219 + endloop + endfacet + facet normal 0.326224 0.115848 0.938167 + outer loop + vertex 1.65681 1.76612 2.52243 + vertex 1.65603 1.76162 2.52326 + vertex 1.65987 1.76182 2.5219 + endloop + endfacet + facet normal 0.326128 0.116959 0.938062 + outer loop + vertex 1.65703 1.75774 2.5234 + vertex 1.65987 1.76182 2.5219 + vertex 1.65603 1.76162 2.52326 + endloop + endfacet + facet normal 0.279351 0.105565 0.954369 + outer loop + vertex 1.65703 1.75774 2.5234 + vertex 1.65603 1.76162 2.52326 + vertex 1.65261 1.75909 2.52454 + endloop + endfacet + facet normal 0.282041 0.116119 0.952349 + outer loop + vertex 1.65412 1.75351 2.52477 + vertex 1.65703 1.75774 2.5234 + vertex 1.65261 1.75909 2.52454 + endloop + endfacet + facet normal 0.302405 0.100694 0.947846 + outer loop + vertex 1.65813 1.75387 2.52346 + vertex 1.65703 1.75774 2.5234 + vertex 1.65412 1.75351 2.52477 + endloop + endfacet + facet normal 0.302575 0.0991969 0.94795 + outer loop + vertex 1.65412 1.75351 2.52477 + vertex 1.65717 1.74924 2.52424 + vertex 1.65813 1.75387 2.52346 + endloop + endfacet + facet normal 0.309238 0.104299 0.945248 + outer loop + vertex 1.6532 1.74903 2.52557 + vertex 1.65717 1.74924 2.52424 + vertex 1.65412 1.75351 2.52477 + endloop + endfacet + facet normal 0.272467 0.113647 0.95543 + outer loop + vertex 1.6532 1.74903 2.52557 + vertex 1.65412 1.75351 2.52477 + vertex 1.65069 1.75094 2.52606 + endloop + endfacet + facet normal 0.270367 0.110638 0.956379 + outer loop + vertex 1.65069 1.75094 2.52606 + vertex 1.64974 1.74654 2.52683 + vertex 1.6532 1.74903 2.52557 + endloop + endfacet + facet normal 0.274991 0.103908 0.955815 + outer loop + vertex 1.65406 1.74503 2.52575 + vertex 1.6532 1.74903 2.52557 + vertex 1.64974 1.74654 2.52683 + endloop + endfacet + facet normal 0.277349 0.111749 0.954248 + outer loop + vertex 1.64974 1.74654 2.52683 + vertex 1.65089 1.74134 2.52711 + vertex 1.65406 1.74503 2.52575 + endloop + endfacet + facet normal 0.287885 0.101953 0.952223 + outer loop + vertex 1.65406 1.74503 2.52575 + vertex 1.65089 1.74134 2.52711 + vertex 1.65504 1.7402 2.52598 + endloop + endfacet + facet normal 0.332151 0.110218 0.936765 + outer loop + vertex 1.65504 1.7402 2.52598 + vertex 1.65808 1.74382 2.52447 + vertex 1.65406 1.74503 2.52575 + endloop + endfacet + facet normal 0.328368 0.0943312 0.939828 + outer loop + vertex 1.65808 1.74382 2.52447 + vertex 1.65717 1.74924 2.52424 + vertex 1.65406 1.74503 2.52575 + endloop + endfacet + facet normal 0.356996 0.0866645 0.930077 + outer loop + vertex 1.65904 1.73852 2.5246 + vertex 1.65808 1.74382 2.52447 + vertex 1.65504 1.7402 2.52598 + endloop + endfacet + facet normal 0.366479 0.114843 0.923311 + outer loop + vertex 1.65588 1.73622 2.52614 + vertex 1.65904 1.73852 2.5246 + vertex 1.65504 1.7402 2.52598 + endloop + endfacet + facet normal 0.298776 0.101613 0.948898 + outer loop + vertex 1.65504 1.7402 2.52598 + vertex 1.65199 1.73607 2.52738 + vertex 1.65588 1.73622 2.52614 + endloop + endfacet + facet normal 0.299054 0.0974025 0.949252 + outer loop + vertex 1.65588 1.73622 2.52614 + vertex 1.65199 1.73607 2.52738 + vertex 1.6548 1.73183 2.52693 + endloop + endfacet + facet normal 0.360252 0.0787559 0.929525 + outer loop + vertex 1.65588 1.73622 2.52614 + vertex 1.6548 1.73183 2.52693 + vertex 1.6581 1.7342 2.52545 + endloop + endfacet + facet normal 0.29874 0.097182 0.949373 + outer loop + vertex 1.65199 1.73607 2.52738 + vertex 1.65091 1.73161 2.52817 + vertex 1.6548 1.73183 2.52693 + endloop + endfacet + facet normal 0.298373 0.101675 0.949018 + outer loop + vertex 1.65167 1.72765 2.52836 + vertex 1.6548 1.73183 2.52693 + vertex 1.65091 1.73161 2.52817 + endloop + endfacet + facet normal 0.27079 0.096801 0.957759 + outer loop + vertex 1.65167 1.72765 2.52836 + vertex 1.65091 1.73161 2.52817 + vertex 1.64733 1.72912 2.52944 + endloop + endfacet + facet normal 0.272689 0.103295 0.956541 + outer loop + vertex 1.64842 1.72387 2.52969 + vertex 1.65167 1.72765 2.52836 + vertex 1.64733 1.72912 2.52944 + endloop + endfacet + facet normal 0.266744 0.102152 0.958338 + outer loop + vertex 1.64842 1.72387 2.52969 + vertex 1.64733 1.72912 2.52944 + vertex 1.64416 1.72498 2.53076 + endloop + endfacet + facet normal 0.266288 0.100075 0.958684 + outer loop + vertex 1.64518 1.72015 2.53098 + vertex 1.64842 1.72387 2.52969 + vertex 1.64416 1.72498 2.53076 + endloop + endfacet + facet normal 0.273251 0.101437 0.95658 + outer loop + vertex 1.64416 1.72498 2.53076 + vertex 1.64093 1.72134 2.53207 + vertex 1.64518 1.72015 2.53098 + endloop + endfacet + facet normal 0.272002 0.0961806 0.957478 + outer loop + vertex 1.64093 1.72134 2.53207 + vertex 1.642 1.71606 2.5323 + vertex 1.64518 1.72015 2.53098 + endloop + endfacet + facet normal 0.269524 0.0982607 0.957967 + outer loop + vertex 1.64518 1.72015 2.53098 + vertex 1.642 1.71606 2.5323 + vertex 1.64598 1.71617 2.53117 + endloop + endfacet + facet normal 0.269246 0.0982084 0.958051 + outer loop + vertex 1.64598 1.71617 2.53117 + vertex 1.64947 1.71869 2.52993 + vertex 1.64518 1.72015 2.53098 + endloop + endfacet + facet normal 0.271463 0.0949832 0.95775 + outer loop + vertex 1.64833 1.71428 2.53069 + vertex 1.64947 1.71869 2.52993 + vertex 1.64598 1.71617 2.53117 + endloop + endfacet + facet normal 0.270178 0.093251 0.958284 + outer loop + vertex 1.64598 1.71617 2.53117 + vertex 1.6448 1.71183 2.53192 + vertex 1.64833 1.71428 2.53069 + endloop + endfacet + facet normal 0.274089 0.0873572 0.957729 + outer loop + vertex 1.649 1.71028 2.53086 + vertex 1.64833 1.71428 2.53069 + vertex 1.6448 1.71183 2.53192 + endloop + endfacet + facet normal 0.275627 0.0921628 0.956836 + outer loop + vertex 1.6448 1.71183 2.53192 + vertex 1.64573 1.70666 2.53215 + vertex 1.649 1.71028 2.53086 + endloop + endfacet + facet normal 0.282091 0.0858597 0.955538 + outer loop + vertex 1.649 1.71028 2.53086 + vertex 1.64573 1.70666 2.53215 + vertex 1.64977 1.70538 2.53107 + endloop + endfacet + facet normal 0.315215 0.0905878 0.944687 + outer loop + vertex 1.64977 1.70538 2.53107 + vertex 1.653 1.70896 2.52965 + vertex 1.649 1.71028 2.53086 + endloop + endfacet + facet normal 0.311974 0.0788994 0.946809 + outer loop + vertex 1.653 1.70896 2.52965 + vertex 1.65229 1.71446 2.52943 + vertex 1.649 1.71028 2.53086 + endloop + endfacet + facet normal 0.326644 0.0791323 0.941829 + outer loop + vertex 1.65374 1.70378 2.52983 + vertex 1.653 1.70896 2.52965 + vertex 1.64977 1.70538 2.53107 + endloop + endfacet + facet normal 0.330665 0.0909903 0.939352 + outer loop + vertex 1.65053 1.7005 2.53128 + vertex 1.65374 1.70378 2.52983 + vertex 1.64977 1.70538 2.53107 + endloop + endfacet + facet normal 0.287765 0.0849345 0.953927 + outer loop + vertex 1.64977 1.70538 2.53107 + vertex 1.64658 1.70183 2.53235 + vertex 1.65053 1.7005 2.53128 + endloop + endfacet + facet normal 0.288357 0.0869823 0.953564 + outer loop + vertex 1.64658 1.70183 2.53235 + vertex 1.64723 1.69657 2.53264 + vertex 1.65053 1.7005 2.53128 + endloop + endfacet + facet normal 0.287973 0.0873346 0.953648 + outer loop + vertex 1.65053 1.7005 2.53128 + vertex 1.64723 1.69657 2.53264 + vertex 1.65123 1.6965 2.53143 + endloop + endfacet + facet normal 0.340215 0.0957853 0.935456 + outer loop + vertex 1.65123 1.6965 2.53143 + vertex 1.6545 1.69857 2.53003 + vertex 1.65053 1.7005 2.53128 + endloop + endfacet + facet normal 0.339654 0.0967426 0.935562 + outer loop + vertex 1.6535 1.69447 2.53082 + vertex 1.6545 1.69857 2.53003 + vertex 1.65123 1.6965 2.53143 + endloop + endfacet + facet normal 0.320624 0.0728344 0.944402 + outer loop + vertex 1.65123 1.6965 2.53143 + vertex 1.65008 1.69209 2.53217 + vertex 1.6535 1.69447 2.53082 + endloop + endfacet + facet normal 0.32337 0.0685391 0.943787 + outer loop + vertex 1.65417 1.69043 2.53089 + vertex 1.6535 1.69447 2.53082 + vertex 1.65008 1.69209 2.53217 + endloop + endfacet + facet normal 0.328203 0.0826151 0.940988 + outer loop + vertex 1.65008 1.69209 2.53217 + vertex 1.65096 1.68675 2.53233 + vertex 1.65417 1.69043 2.53089 + endloop + endfacet + facet normal 0.339759 0.0712912 0.937807 + outer loop + vertex 1.65417 1.69043 2.53089 + vertex 1.65096 1.68675 2.53233 + vertex 1.65478 1.68547 2.53104 + endloop + endfacet + facet normal 0.413559 0.0795226 0.906998 + outer loop + vertex 1.65478 1.68547 2.53104 + vertex 1.65786 1.68912 2.52931 + vertex 1.65417 1.69043 2.53089 + endloop + endfacet + facet normal 0.412687 0.0762368 0.907677 + outer loop + vertex 1.65786 1.68912 2.52931 + vertex 1.65704 1.69446 2.52924 + vertex 1.65417 1.69043 2.53089 + endloop + endfacet + facet normal 0.427436 0.065309 0.901683 + outer loop + vertex 1.65827 1.68407 2.52949 + vertex 1.65786 1.68912 2.52931 + vertex 1.65478 1.68547 2.53104 + endloop + endfacet + facet normal 0.425884 0.0602621 0.902769 + outer loop + vertex 1.6551 1.68053 2.53122 + vertex 1.65827 1.68407 2.52949 + vertex 1.65478 1.68547 2.53104 + endloop + endfacet + facet normal 0.356311 0.0568475 0.932637 + outer loop + vertex 1.65478 1.68547 2.53104 + vertex 1.65153 1.68192 2.5325 + vertex 1.6551 1.68053 2.53122 + endloop + endfacet + facet normal 0.355624 0.0547196 0.933026 + outer loop + vertex 1.65153 1.68192 2.5325 + vertex 1.65165 1.6772 2.53273 + vertex 1.6551 1.68053 2.53122 + endloop + endfacet + facet normal 0.315057 0.0544008 0.947512 + outer loop + vertex 1.65165 1.6772 2.53273 + vertex 1.65153 1.68192 2.5325 + vertex 1.64856 1.67895 2.53366 + endloop + endfacet + facet normal 0.312894 0.0500602 0.948468 + outer loop + vertex 1.64738 1.67429 2.53429 + vertex 1.65165 1.6772 2.53273 + vertex 1.64856 1.67895 2.53366 + endloop + endfacet + facet normal 0.282145 0.0590299 0.957554 + outer loop + vertex 1.6445 1.67865 2.53487 + vertex 1.64738 1.67429 2.53429 + vertex 1.64856 1.67895 2.53366 + endloop + endfacet + facet normal 0.281444 0.0673214 0.957213 + outer loop + vertex 1.64856 1.67895 2.53366 + vertex 1.64771 1.68296 2.53362 + vertex 1.6445 1.67865 2.53487 + endloop + endfacet + facet normal 0.277311 0.0706816 0.958177 + outer loop + vertex 1.6445 1.67865 2.53487 + vertex 1.64771 1.68296 2.53362 + vertex 1.64365 1.68395 2.53473 + endloop + endfacet + facet normal 0.280784 0.0712138 0.957125 + outer loop + vertex 1.6445 1.67865 2.53487 + vertex 1.64365 1.68395 2.53473 + vertex 1.64026 1.68024 2.536 + endloop + endfacet + facet normal 0.278896 0.065497 0.958085 + outer loop + vertex 1.64089 1.67615 2.53609 + vertex 1.6445 1.67865 2.53487 + vertex 1.64026 1.68024 2.536 + endloop + endfacet + facet normal 0.285838 0.0665259 0.955966 + outer loop + vertex 1.64026 1.68024 2.536 + vertex 1.6369 1.67594 2.5373 + vertex 1.64089 1.67615 2.53609 + endloop + endfacet + facet normal 0.286156 0.0616908 0.956195 + outer loop + vertex 1.64089 1.67615 2.53609 + vertex 1.6369 1.67594 2.5373 + vertex 1.6397 1.67173 2.53673 + endloop + endfacet + facet normal 0.279823 0.0636479 0.957939 + outer loop + vertex 1.64089 1.67615 2.53609 + vertex 1.6397 1.67173 2.53673 + vertex 1.64326 1.67419 2.53553 + endloop + endfacet + facet normal 0.281023 0.0618037 0.957709 + outer loop + vertex 1.6439 1.67017 2.5356 + vertex 1.64326 1.67419 2.53553 + vertex 1.6397 1.67173 2.53673 + endloop + endfacet + facet normal 0.286133 0.0625909 0.956143 + outer loop + vertex 1.64326 1.67419 2.53553 + vertex 1.6439 1.67017 2.5356 + vertex 1.64738 1.67429 2.53429 + endloop + endfacet + facet normal 0.294049 0.0552658 0.954191 + outer loop + vertex 1.64806 1.66878 2.5344 + vertex 1.64738 1.67429 2.53429 + vertex 1.6439 1.67017 2.5356 + endloop + endfacet + facet normal 0.296274 0.0629652 0.953025 + outer loop + vertex 1.64442 1.66531 2.53576 + vertex 1.64806 1.66878 2.5344 + vertex 1.6439 1.67017 2.5356 + endloop + endfacet + facet normal 0.280817 0.0614628 0.957791 + outer loop + vertex 1.6439 1.67017 2.5356 + vertex 1.64043 1.66661 2.53685 + vertex 1.64442 1.66531 2.53576 + endloop + endfacet + facet normal 0.280946 0.0619135 0.957724 + outer loop + vertex 1.64043 1.66661 2.53685 + vertex 1.64083 1.66172 2.53705 + vertex 1.64442 1.66531 2.53576 + endloop + endfacet + facet normal 0.28112 0.0617262 0.957686 + outer loop + vertex 1.64442 1.66531 2.53576 + vertex 1.64083 1.66172 2.53705 + vertex 1.64471 1.66042 2.53599 + endloop + endfacet + facet normal 0.298973 0.0625485 0.952209 + outer loop + vertex 1.64471 1.66042 2.53599 + vertex 1.64827 1.66378 2.53465 + vertex 1.64442 1.66531 2.53576 + endloop + endfacet + facet normal 0.302341 0.0586653 0.951393 + outer loop + vertex 1.64842 1.65903 2.5349 + vertex 1.64827 1.66378 2.53465 + vertex 1.64471 1.66042 2.53599 + endloop + endfacet + facet normal 0.280779 0.0605714 0.957859 + outer loop + vertex 1.64083 1.66172 2.53705 + vertex 1.64112 1.65675 2.53728 + vertex 1.64471 1.66042 2.53599 + endloop + endfacet + facet normal 0.283344 0.0578536 0.957272 + outer loop + vertex 1.64471 1.66042 2.53599 + vertex 1.64112 1.65675 2.53728 + vertex 1.64504 1.65546 2.53619 + endloop + endfacet + facet normal 0.302406 0.058866 0.95136 + outer loop + vertex 1.64504 1.65546 2.53619 + vertex 1.64842 1.65903 2.5349 + vertex 1.64471 1.66042 2.53599 + endloop + endfacet + facet normal 0.31404 0.0467367 0.948259 + outer loop + vertex 1.64892 1.65419 2.53497 + vertex 1.64842 1.65903 2.5349 + vertex 1.64504 1.65546 2.53619 + endloop + endfacet + facet normal 0.316537 0.055594 0.94695 + outer loop + vertex 1.64559 1.65048 2.5363 + vertex 1.64892 1.65419 2.53497 + vertex 1.64504 1.65546 2.53619 + endloop + endfacet + facet normal 0.28812 0.052636 0.956147 + outer loop + vertex 1.64504 1.65546 2.53619 + vertex 1.64153 1.65165 2.53746 + vertex 1.64559 1.65048 2.5363 + endloop + endfacet + facet normal 0.288728 0.0550565 0.955827 + outer loop + vertex 1.64153 1.65165 2.53746 + vertex 1.64226 1.64627 2.53755 + vertex 1.64559 1.65048 2.5363 + endloop + endfacet + facet normal 0.290601 0.053431 0.955351 + outer loop + vertex 1.64559 1.65048 2.5363 + vertex 1.64226 1.64627 2.53755 + vertex 1.64623 1.6464 2.53634 + endloop + endfacet + facet normal 0.335053 0.0601923 0.940274 + outer loop + vertex 1.64623 1.6464 2.53634 + vertex 1.64967 1.64891 2.53495 + vertex 1.64559 1.65048 2.5363 + endloop + endfacet + facet normal 0.337308 0.0567799 0.939681 + outer loop + vertex 1.6485 1.64445 2.53564 + vertex 1.64967 1.64891 2.53495 + vertex 1.64623 1.6464 2.53634 + endloop + endfacet + facet normal 0.325182 0.0407967 0.944771 + outer loop + vertex 1.64623 1.6464 2.53634 + vertex 1.64498 1.64198 2.53696 + vertex 1.6485 1.64445 2.53564 + endloop + endfacet + facet normal 0.290663 0.0520491 0.955409 + outer loop + vertex 1.64623 1.6464 2.53634 + vertex 1.64226 1.64627 2.53755 + vertex 1.64498 1.64198 2.53696 + endloop + endfacet + facet normal 0.285996 0.0488709 0.956984 + outer loop + vertex 1.64226 1.64627 2.53755 + vertex 1.64099 1.6418 2.53816 + vertex 1.64498 1.64198 2.53696 + endloop + endfacet + facet normal 0.285898 0.0506639 0.95692 + outer loop + vertex 1.64162 1.63781 2.53818 + vertex 1.64498 1.64198 2.53696 + vertex 1.64099 1.6418 2.53816 + endloop + endfacet + facet normal 0.279737 0.0496942 0.95879 + outer loop + vertex 1.64162 1.63781 2.53818 + vertex 1.64099 1.6418 2.53816 + vertex 1.63736 1.63933 2.53935 + endloop + endfacet + facet normal 0.278838 0.0468707 0.959194 + outer loop + vertex 1.6381 1.63412 2.53938 + vertex 1.64162 1.63781 2.53818 + vertex 1.63736 1.63933 2.53935 + endloop + endfacet + facet normal 0.286996 0.0480171 0.956728 + outer loop + vertex 1.6381 1.63412 2.53938 + vertex 1.63736 1.63933 2.53935 + vertex 1.63405 1.63519 2.54055 + endloop + endfacet + facet normal 0.28607 0.0440032 0.957198 + outer loop + vertex 1.63457 1.63036 2.54061 + vertex 1.6381 1.63412 2.53938 + vertex 1.63405 1.63519 2.54055 + endloop + endfacet + facet normal 0.297413 0.0451848 0.953679 + outer loop + vertex 1.63405 1.63519 2.54055 + vertex 1.63062 1.63158 2.54179 + vertex 1.63457 1.63036 2.54061 + endloop + endfacet + facet normal 0.296601 0.0421608 0.954071 + outer loop + vertex 1.63062 1.63158 2.54179 + vertex 1.631 1.62669 2.54189 + vertex 1.63457 1.63036 2.54061 + endloop + endfacet + facet normal 0.297559 0.0411401 0.953816 + outer loop + vertex 1.63457 1.63036 2.54061 + vertex 1.631 1.62669 2.54189 + vertex 1.63477 1.62549 2.54076 + endloop + endfacet + facet normal 0.284265 0.0407248 0.95788 + outer loop + vertex 1.63477 1.62549 2.54076 + vertex 1.63847 1.62921 2.5395 + vertex 1.63457 1.63036 2.54061 + endloop + endfacet + facet normal 0.283971 0.041042 0.957954 + outer loop + vertex 1.63859 1.62429 2.53968 + vertex 1.63847 1.62921 2.5395 + vertex 1.63477 1.62549 2.54076 + endloop + endfacet + facet normal 0.283127 0.0380122 0.958329 + outer loop + vertex 1.63479 1.62056 2.54095 + vertex 1.63859 1.62429 2.53968 + vertex 1.63477 1.62549 2.54076 + endloop + endfacet + facet normal 0.297185 0.0378857 0.954068 + outer loop + vertex 1.63477 1.62549 2.54076 + vertex 1.63108 1.62179 2.54206 + vertex 1.63479 1.62056 2.54095 + endloop + endfacet + facet normal 0.296619 0.0359569 0.954319 + outer loop + vertex 1.63108 1.62179 2.54206 + vertex 1.63105 1.61682 2.54225 + vertex 1.63479 1.62056 2.54095 + endloop + endfacet + facet normal 0.29638 0.0362184 0.954383 + outer loop + vertex 1.63479 1.62056 2.54095 + vertex 1.63105 1.61682 2.54225 + vertex 1.63482 1.61553 2.54113 + endloop + endfacet + facet normal 0.282513 0.0362776 0.958577 + outer loop + vertex 1.63482 1.61553 2.54113 + vertex 1.63863 1.61927 2.53987 + vertex 1.63479 1.62056 2.54095 + endloop + endfacet + facet normal 0.282752 0.0360133 0.958517 + outer loop + vertex 1.63873 1.61416 2.54003 + vertex 1.63863 1.61927 2.53987 + vertex 1.63482 1.61553 2.54113 + endloop + endfacet + facet normal 0.282553 0.035376 0.958599 + outer loop + vertex 1.63503 1.61045 2.54126 + vertex 1.63873 1.61416 2.54003 + vertex 1.63482 1.61553 2.54113 + endloop + endfacet + facet normal 0.295555 0.0358156 0.954654 + outer loop + vertex 1.63482 1.61553 2.54113 + vertex 1.63114 1.61178 2.54241 + vertex 1.63503 1.61045 2.54126 + endloop + endfacet + facet normal 0.295491 0.0356059 0.954682 + outer loop + vertex 1.63114 1.61178 2.54241 + vertex 1.63151 1.60666 2.54249 + vertex 1.63503 1.61045 2.54126 + endloop + endfacet + facet normal 0.295307 0.0357936 0.954732 + outer loop + vertex 1.63503 1.61045 2.54126 + vertex 1.63151 1.60666 2.54249 + vertex 1.63552 1.60544 2.54129 + endloop + endfacet + facet normal 0.283029 0.0346259 0.958486 + outer loop + vertex 1.63552 1.60544 2.54129 + vertex 1.63902 1.60909 2.54013 + vertex 1.63503 1.61045 2.54126 + endloop + endfacet + facet normal 0.284634 0.0329507 0.95807 + outer loop + vertex 1.63976 1.60384 2.54009 + vertex 1.63902 1.60909 2.54013 + vertex 1.63552 1.60544 2.54129 + endloop + endfacet + facet normal 0.284824 0.0335105 0.957994 + outer loop + vertex 1.6361 1.60137 2.54126 + vertex 1.63976 1.60384 2.54009 + vertex 1.63552 1.60544 2.54129 + endloop + endfacet + facet normal 0.296431 0.0352139 0.954405 + outer loop + vertex 1.63552 1.60544 2.54129 + vertex 1.6322 1.60131 2.54248 + vertex 1.6361 1.60137 2.54126 + endloop + endfacet + facet normal 0.296457 0.0341693 0.954435 + outer loop + vertex 1.6361 1.60137 2.54126 + vertex 1.6322 1.60131 2.54248 + vertex 1.63484 1.597 2.54181 + endloop + endfacet + facet normal 0.29064 0.0360608 0.956153 + outer loop + vertex 1.6361 1.60137 2.54126 + vertex 1.63484 1.597 2.54181 + vertex 1.63847 1.59939 2.54062 + endloop + endfacet + facet normal 0.292548 0.0329381 0.955683 + outer loop + vertex 1.63902 1.59534 2.54059 + vertex 1.63847 1.59939 2.54062 + vertex 1.63484 1.597 2.54181 + endloop + endfacet + facet normal 0.291899 0.0311134 0.955943 + outer loop + vertex 1.63484 1.597 2.54181 + vertex 1.6355 1.59177 2.54178 + vertex 1.63902 1.59534 2.54059 + endloop + endfacet + facet normal 0.293246 0.029658 0.955577 + outer loop + vertex 1.63902 1.59534 2.54059 + vertex 1.6355 1.59177 2.54178 + vertex 1.6394 1.59044 2.54062 + endloop + endfacet + facet normal 0.29511 0.0297973 0.954998 + outer loop + vertex 1.6394 1.59044 2.54062 + vertex 1.64303 1.59389 2.5394 + vertex 1.63902 1.59534 2.54059 + endloop + endfacet + facet normal 0.294632 0.0283142 0.955191 + outer loop + vertex 1.64303 1.59389 2.5394 + vertex 1.64277 1.59949 2.53931 + vertex 1.63902 1.59534 2.54059 + endloop + endfacet + facet normal 0.322314 0.0294401 0.946175 + outer loop + vertex 1.64303 1.59389 2.5394 + vertex 1.64751 1.59687 2.53778 + vertex 1.64277 1.59949 2.53931 + endloop + endfacet + facet normal 0.314899 0.0143886 0.949016 + outer loop + vertex 1.64751 1.59687 2.53778 + vertex 1.64776 1.60293 2.5376 + vertex 1.64277 1.59949 2.53931 + endloop + endfacet + facet normal 0.313843 0.0160825 0.949339 + outer loop + vertex 1.64277 1.59949 2.53931 + vertex 1.64776 1.60293 2.5376 + vertex 1.64398 1.60433 2.53883 + endloop + endfacet + facet normal 0.283744 0.0245293 0.958586 + outer loop + vertex 1.63976 1.60384 2.54009 + vertex 1.64277 1.59949 2.53931 + vertex 1.64398 1.60433 2.53883 + endloop + endfacet + facet normal 0.283608 0.0257199 0.958595 + outer loop + vertex 1.64398 1.60433 2.53883 + vertex 1.64298 1.60808 2.53902 + vertex 1.63976 1.60384 2.54009 + endloop + endfacet + facet normal 0.295737 0.0291698 0.954824 + outer loop + vertex 1.64398 1.60433 2.53883 + vertex 1.64684 1.60761 2.53784 + vertex 1.64298 1.60808 2.53902 + endloop + endfacet + facet normal 0.295194 0.0239236 0.955138 + outer loop + vertex 1.64684 1.60761 2.53784 + vertex 1.64588 1.61126 2.53805 + vertex 1.64298 1.60808 2.53902 + endloop + endfacet + facet normal 0.285623 0.0334769 0.957757 + outer loop + vertex 1.64298 1.60808 2.53902 + vertex 1.64588 1.61126 2.53805 + vertex 1.64268 1.61273 2.53895 + endloop + endfacet + facet normal 0.276561 0.0329472 0.960431 + outer loop + vertex 1.64298 1.60808 2.53902 + vertex 1.64268 1.61273 2.53895 + vertex 1.63902 1.60909 2.54013 + endloop + endfacet + facet normal 0.275226 0.0343955 0.960764 + outer loop + vertex 1.63902 1.60909 2.54013 + vertex 1.64268 1.61273 2.53895 + vertex 1.63873 1.61416 2.54003 + endloop + endfacet + facet normal 0.275729 0.0359438 0.960563 + outer loop + vertex 1.64268 1.61273 2.53895 + vertex 1.64267 1.61786 2.53876 + vertex 1.63873 1.61416 2.54003 + endloop + endfacet + facet normal 0.295932 0.0357735 0.954539 + outer loop + vertex 1.64268 1.61273 2.53895 + vertex 1.64705 1.61609 2.53747 + vertex 1.64267 1.61786 2.53876 + endloop + endfacet + facet normal 0.295805 0.0354193 0.954592 + outer loop + vertex 1.64705 1.61609 2.53747 + vertex 1.64654 1.62173 2.53742 + vertex 1.64267 1.61786 2.53876 + endloop + endfacet + facet normal 0.294076 0.0373091 0.955054 + outer loop + vertex 1.64267 1.61786 2.53876 + vertex 1.64654 1.62173 2.53742 + vertex 1.64252 1.62305 2.5386 + endloop + endfacet + facet normal 0.276043 0.0369444 0.960435 + outer loop + vertex 1.64267 1.61786 2.53876 + vertex 1.64252 1.62305 2.5386 + vertex 1.63863 1.61927 2.53987 + endloop + endfacet + facet normal 0.274999 0.0381017 0.960689 + outer loop + vertex 1.63863 1.61927 2.53987 + vertex 1.64252 1.62305 2.5386 + vertex 1.63859 1.62429 2.53968 + endloop + endfacet + facet normal 0.275671 0.040482 0.960399 + outer loop + vertex 1.64252 1.62305 2.5386 + vertex 1.6424 1.62807 2.53843 + vertex 1.63859 1.62429 2.53968 + endloop + endfacet + facet normal 0.291552 0.0407057 0.955689 + outer loop + vertex 1.64252 1.62305 2.5386 + vertex 1.64629 1.62689 2.53729 + vertex 1.6424 1.62807 2.53843 + endloop + endfacet + facet normal 0.292182 0.0430607 0.955393 + outer loop + vertex 1.64629 1.62689 2.53729 + vertex 1.64608 1.63186 2.53713 + vertex 1.6424 1.62807 2.53843 + endloop + endfacet + facet normal 0.289814 0.0455678 0.955998 + outer loop + vertex 1.6424 1.62807 2.53843 + vertex 1.64608 1.63186 2.53713 + vertex 1.64215 1.63297 2.53827 + endloop + endfacet + facet normal 0.27631 0.0450099 0.960014 + outer loop + vertex 1.6424 1.62807 2.53843 + vertex 1.64215 1.63297 2.53827 + vertex 1.63847 1.62921 2.5395 + endloop + endfacet + facet normal 0.277071 0.0442064 0.959832 + outer loop + vertex 1.63847 1.62921 2.5395 + vertex 1.64215 1.63297 2.53827 + vertex 1.6381 1.63412 2.53938 + endloop + endfacet + facet normal 0.290436 0.0480848 0.955686 + outer loop + vertex 1.64608 1.63186 2.53713 + vertex 1.64569 1.63678 2.537 + vertex 1.64215 1.63297 2.53827 + endloop + endfacet + facet normal 0.28956 0.0489725 0.955906 + outer loop + vertex 1.64215 1.63297 2.53827 + vertex 1.64569 1.63678 2.537 + vertex 1.64162 1.63781 2.53818 + endloop + endfacet + facet normal 0.337075 0.0514072 0.940073 + outer loop + vertex 1.64569 1.63678 2.537 + vertex 1.64608 1.63186 2.53713 + vertex 1.64952 1.63558 2.53569 + endloop + endfacet + facet normal 0.335954 0.0471658 0.940697 + outer loop + vertex 1.64905 1.64044 2.53562 + vertex 1.64569 1.63678 2.537 + vertex 1.64952 1.63558 2.53569 + endloop + endfacet + facet normal 0.405696 0.0533654 0.912449 + outer loop + vertex 1.64952 1.63558 2.53569 + vertex 1.65276 1.6392 2.53404 + vertex 1.64905 1.64044 2.53562 + endloop + endfacet + facet normal 0.342407 0.0458379 0.938433 + outer loop + vertex 1.64952 1.63558 2.53569 + vertex 1.64608 1.63186 2.53713 + vertex 1.64979 1.63064 2.53584 + endloop + endfacet + facet normal 0.412851 0.0488531 0.909488 + outer loop + vertex 1.64979 1.63064 2.53584 + vertex 1.65305 1.6342 2.53416 + vertex 1.64952 1.63558 2.53569 + endloop + endfacet + facet normal 0.412127 0.0464836 0.90994 + outer loop + vertex 1.65305 1.6342 2.53416 + vertex 1.65276 1.6392 2.53404 + vertex 1.64952 1.63558 2.53569 + endloop + endfacet + facet normal 0.420807 0.0400569 0.906266 + outer loop + vertex 1.65326 1.6292 2.53429 + vertex 1.65305 1.6342 2.53416 + vertex 1.64979 1.63064 2.53584 + endloop + endfacet + facet normal 0.421891 0.0433608 0.905609 + outer loop + vertex 1.65004 1.62561 2.53596 + vertex 1.65326 1.6292 2.53429 + vertex 1.64979 1.63064 2.53584 + endloop + endfacet + facet normal 0.346036 0.0403972 0.937351 + outer loop + vertex 1.64979 1.63064 2.53584 + vertex 1.64629 1.62689 2.53729 + vertex 1.65004 1.62561 2.53596 + endloop + endfacet + facet normal 0.345903 0.0399332 0.93742 + outer loop + vertex 1.64629 1.62689 2.53729 + vertex 1.64654 1.62173 2.53742 + vertex 1.65004 1.62561 2.53596 + endloop + endfacet + facet normal 0.34948 0.0362714 0.936242 + outer loop + vertex 1.65004 1.62561 2.53596 + vertex 1.64654 1.62173 2.53742 + vertex 1.65046 1.62053 2.536 + endloop + endfacet + facet normal 0.431134 0.0427475 0.901275 + outer loop + vertex 1.65046 1.62053 2.536 + vertex 1.65357 1.62412 2.53434 + vertex 1.65004 1.62561 2.53596 + endloop + endfacet + facet normal 0.442155 0.0309293 0.896405 + outer loop + vertex 1.65415 1.61871 2.53424 + vertex 1.65357 1.62412 2.53434 + vertex 1.65046 1.62053 2.536 + endloop + endfacet + facet normal 0.450618 0.0532052 0.89113 + outer loop + vertex 1.651 1.61639 2.53598 + vertex 1.65415 1.61871 2.53424 + vertex 1.65046 1.62053 2.536 + endloop + endfacet + facet normal 0.350815 0.0399 0.935594 + outer loop + vertex 1.65046 1.62053 2.536 + vertex 1.64705 1.61609 2.53747 + vertex 1.651 1.61639 2.53598 + endloop + endfacet + facet normal 0.350524 0.0434222 0.935546 + outer loop + vertex 1.651 1.61639 2.53598 + vertex 1.64705 1.61609 2.53747 + vertex 1.64976 1.61196 2.53664 + endloop + endfacet + facet normal 0.423632 0.0185519 0.905644 + outer loop + vertex 1.651 1.61639 2.53598 + vertex 1.64976 1.61196 2.53664 + vertex 1.65302 1.61436 2.53507 + endloop + endfacet + facet normal 0.334539 0.0316785 0.941849 + outer loop + vertex 1.64705 1.61609 2.53747 + vertex 1.64588 1.61126 2.53805 + vertex 1.64976 1.61196 2.53664 + endloop + endfacet + facet normal 0.451121 0.0523671 0.890925 + outer loop + vertex 1.65302 1.61436 2.53507 + vertex 1.65415 1.61871 2.53424 + vertex 1.651 1.61639 2.53598 + endloop + endfacet + facet normal 0.428824 0.0357658 0.90268 + outer loop + vertex 1.65357 1.62412 2.53434 + vertex 1.65326 1.6292 2.53429 + vertex 1.65004 1.62561 2.53596 + endloop + endfacet + facet normal 0.342062 0.044593 0.938619 + outer loop + vertex 1.64608 1.63186 2.53713 + vertex 1.64629 1.62689 2.53729 + vertex 1.64979 1.63064 2.53584 + endloop + endfacet + facet normal 0.294229 0.0378345 0.954986 + outer loop + vertex 1.64654 1.62173 2.53742 + vertex 1.64629 1.62689 2.53729 + vertex 1.64252 1.62305 2.5386 + endloop + endfacet + facet normal 0.350485 0.0401899 0.935706 + outer loop + vertex 1.64654 1.62173 2.53742 + vertex 1.64705 1.61609 2.53747 + vertex 1.65046 1.62053 2.536 + endloop + endfacet + facet normal 0.290016 0.044112 0.956005 + outer loop + vertex 1.64588 1.61126 2.53805 + vertex 1.64705 1.61609 2.53747 + vertex 1.64268 1.61273 2.53895 + endloop + endfacet + facet normal 0.33401 0.034797 0.941927 + outer loop + vertex 1.64684 1.60761 2.53784 + vertex 1.64976 1.61196 2.53664 + vertex 1.64588 1.61126 2.53805 + endloop + endfacet + facet normal 0.347606 0.0243715 0.937324 + outer loop + vertex 1.65047 1.60736 2.5365 + vertex 1.64976 1.61196 2.53664 + vertex 1.64684 1.60761 2.53784 + endloop + endfacet + facet normal 0.347389 0.0203248 0.937501 + outer loop + vertex 1.65047 1.60736 2.5365 + vertex 1.64684 1.60761 2.53784 + vertex 1.64776 1.60293 2.5376 + endloop + endfacet + facet normal 0.290367 0.0295002 0.956461 + outer loop + vertex 1.63847 1.59939 2.54062 + vertex 1.64277 1.59949 2.53931 + vertex 1.63976 1.60384 2.54009 + endloop + endfacet + facet normal 0.31277 0.0128442 0.949742 + outer loop + vertex 1.64776 1.60293 2.5376 + vertex 1.64684 1.60761 2.53784 + vertex 1.64398 1.60433 2.53883 + endloop + endfacet + facet normal 0.319398 0.034263 0.947001 + outer loop + vertex 1.64615 1.59206 2.53841 + vertex 1.64751 1.59687 2.53778 + vertex 1.64303 1.59389 2.5394 + endloop + endfacet + facet normal 0.316146 0.0280002 0.948297 + outer loop + vertex 1.64312 1.58908 2.53951 + vertex 1.64615 1.59206 2.53841 + vertex 1.64303 1.59389 2.5394 + endloop + endfacet + facet normal 0.327096 0.0155774 0.944863 + outer loop + vertex 1.6468 1.58805 2.53825 + vertex 1.64615 1.59206 2.53841 + vertex 1.64312 1.58908 2.53951 + endloop + endfacet + facet normal 0.328513 0.021427 0.944256 + outer loop + vertex 1.64338 1.58434 2.53952 + vertex 1.6468 1.58805 2.53825 + vertex 1.64312 1.58908 2.53951 + endloop + endfacet + facet normal 0.301147 0.0199295 0.953369 + outer loop + vertex 1.64338 1.58434 2.53952 + vertex 1.64312 1.58908 2.53951 + vertex 1.63959 1.58556 2.54069 + endloop + endfacet + facet normal 0.301365 0.0206896 0.953284 + outer loop + vertex 1.6397 1.58063 2.54077 + vertex 1.64338 1.58434 2.53952 + vertex 1.63959 1.58556 2.54069 + endloop + endfacet + facet normal 0.2927 0.020542 0.955984 + outer loop + vertex 1.63959 1.58556 2.54069 + vertex 1.63591 1.58188 2.5419 + vertex 1.6397 1.58063 2.54077 + endloop + endfacet + facet normal 0.291933 0.0179438 0.95627 + outer loop + vertex 1.63591 1.58188 2.5419 + vertex 1.63592 1.5769 2.54199 + vertex 1.6397 1.58063 2.54077 + endloop + endfacet + facet normal 0.292778 0.0170106 0.956029 + outer loop + vertex 1.6397 1.58063 2.54077 + vertex 1.63592 1.5769 2.54199 + vertex 1.63977 1.57561 2.54084 + endloop + endfacet + facet normal 0.308353 0.0171661 0.951117 + outer loop + vertex 1.63977 1.57561 2.54084 + vertex 1.64363 1.57936 2.53952 + vertex 1.6397 1.58063 2.54077 + endloop + endfacet + facet normal 0.313161 0.0116872 0.949628 + outer loop + vertex 1.64374 1.57412 2.53955 + vertex 1.64363 1.57936 2.53952 + vertex 1.63977 1.57561 2.54084 + endloop + endfacet + facet normal 0.314408 0.0153938 0.949163 + outer loop + vertex 1.63981 1.57056 2.54091 + vertex 1.64374 1.57412 2.53955 + vertex 1.63977 1.57561 2.54084 + endloop + endfacet + facet normal 0.292184 0.0153311 0.956239 + outer loop + vertex 1.63977 1.57561 2.54084 + vertex 1.63597 1.5719 2.54206 + vertex 1.63981 1.57056 2.54091 + endloop + endfacet + facet normal 0.291372 0.0127583 0.956525 + outer loop + vertex 1.63597 1.5719 2.54206 + vertex 1.63605 1.5669 2.5421 + vertex 1.63981 1.57056 2.54091 + endloop + endfacet + facet normal 0.290425 0.0138205 0.956798 + outer loop + vertex 1.63981 1.57056 2.54091 + vertex 1.63605 1.5669 2.5421 + vertex 1.63985 1.56557 2.54097 + endloop + endfacet + facet normal 0.310451 0.0138997 0.950488 + outer loop + vertex 1.63985 1.56557 2.54097 + vertex 1.64353 1.56897 2.53971 + vertex 1.63981 1.57056 2.54091 + endloop + endfacet + facet normal 0.310087 0.0143354 0.9506 + outer loop + vertex 1.64346 1.56418 2.53981 + vertex 1.64353 1.56897 2.53971 + vertex 1.63985 1.56557 2.54097 + endloop + endfacet + facet normal 0.308241 0.00898388 0.951266 + outer loop + vertex 1.63994 1.56062 2.54098 + vertex 1.64346 1.56418 2.53981 + vertex 1.63985 1.56557 2.54097 + endloop + endfacet + facet normal 0.29003 0.00867959 0.956978 + outer loop + vertex 1.63985 1.56557 2.54097 + vertex 1.63614 1.5619 2.54212 + vertex 1.63994 1.56062 2.54098 + endloop + endfacet + facet normal 0.28947 0.00686051 0.957163 + outer loop + vertex 1.63614 1.5619 2.54212 + vertex 1.63619 1.55689 2.54214 + vertex 1.63994 1.56062 2.54098 + endloop + endfacet + facet normal 0.291861 0.00423879 0.956451 + outer loop + vertex 1.63994 1.56062 2.54098 + vertex 1.63619 1.55689 2.54214 + vertex 1.64001 1.55562 2.54098 + endloop + endfacet + facet normal 0.315973 0.00459725 0.948757 + outer loop + vertex 1.64001 1.55562 2.54098 + vertex 1.64366 1.55938 2.53975 + vertex 1.63994 1.56062 2.54098 + endloop + endfacet + facet normal 0.32038 -0.000169427 0.947289 + outer loop + vertex 1.64376 1.55439 2.53971 + vertex 1.64366 1.55938 2.53975 + vertex 1.64001 1.55562 2.54098 + endloop + endfacet + facet normal 0.320878 0.00152737 0.947119 + outer loop + vertex 1.64001 1.55058 2.54099 + vertex 1.64376 1.55439 2.53971 + vertex 1.64001 1.55562 2.54098 + endloop + endfacet + facet normal 0.295191 0.00152459 0.955437 + outer loop + vertex 1.64001 1.55562 2.54098 + vertex 1.6362 1.55186 2.54217 + vertex 1.64001 1.55058 2.54099 + endloop + endfacet + facet normal 0.295668 0.00308663 0.955286 + outer loop + vertex 1.6362 1.55186 2.54217 + vertex 1.63618 1.54684 2.54219 + vertex 1.64001 1.55058 2.54099 + endloop + endfacet + facet normal 0.298649 -0.000262262 0.954363 + outer loop + vertex 1.64001 1.55058 2.54099 + vertex 1.63618 1.54684 2.54219 + vertex 1.63998 1.54555 2.541 + endloop + endfacet + facet normal 0.322933 -0.000417267 0.946422 + outer loop + vertex 1.63998 1.54555 2.541 + vertex 1.64376 1.54936 2.53971 + vertex 1.64001 1.55058 2.54099 + endloop + endfacet + facet normal 0.325388 -0.00313697 0.945575 + outer loop + vertex 1.64372 1.54433 2.53971 + vertex 1.64376 1.54936 2.53971 + vertex 1.63998 1.54555 2.541 + endloop + endfacet + facet normal 0.325787 -0.00177018 0.945442 + outer loop + vertex 1.63996 1.54052 2.541 + vertex 1.64372 1.54433 2.53971 + vertex 1.63998 1.54555 2.541 + endloop + endfacet + facet normal 0.301586 -0.0016758 0.953438 + outer loop + vertex 1.63998 1.54555 2.541 + vertex 1.63617 1.54184 2.5422 + vertex 1.63996 1.54052 2.541 + endloop + endfacet + facet normal 0.302066 -0.000151379 0.953287 + outer loop + vertex 1.63617 1.54184 2.5422 + vertex 1.63616 1.53684 2.5422 + vertex 1.63996 1.54052 2.541 + endloop + endfacet + facet normal 0.302928 -0.00113085 0.953013 + outer loop + vertex 1.63996 1.54052 2.541 + vertex 1.63616 1.53684 2.5422 + vertex 1.63996 1.5355 2.54099 + endloop + endfacet + facet normal 0.326493 -0.00113705 0.945199 + outer loop + vertex 1.63996 1.5355 2.54099 + vertex 1.64371 1.5393 2.5397 + vertex 1.63996 1.54052 2.541 + endloop + endfacet + facet normal 0.32539 8.47812e-05 0.94558 + outer loop + vertex 1.64371 1.53426 2.5397 + vertex 1.64371 1.5393 2.5397 + vertex 1.63996 1.5355 2.54099 + endloop + endfacet + facet normal 0.325872 0.0017144 0.945412 + outer loop + vertex 1.63996 1.5305 2.541 + vertex 1.64371 1.53426 2.5397 + vertex 1.63996 1.5355 2.54099 + endloop + endfacet + facet normal 0.302335 0.00169919 0.9532 + outer loop + vertex 1.63996 1.5355 2.54099 + vertex 1.63617 1.53185 2.5422 + vertex 1.63996 1.5305 2.541 + endloop + endfacet + facet normal 0.302279 0.00152398 0.953218 + outer loop + vertex 1.63617 1.53185 2.5422 + vertex 1.63618 1.52686 2.54221 + vertex 1.63996 1.5305 2.541 + endloop + endfacet + facet normal 0.300987 0.00300456 0.953624 + outer loop + vertex 1.63996 1.5305 2.541 + vertex 1.63618 1.52686 2.54221 + vertex 1.63997 1.52551 2.54101 + endloop + endfacet + facet normal 0.324585 0.00299563 0.945852 + outer loop + vertex 1.63997 1.52551 2.54101 + vertex 1.64371 1.52926 2.53972 + vertex 1.63996 1.5305 2.541 + endloop + endfacet + facet normal 0.322814 0.00496857 0.946449 + outer loop + vertex 1.64371 1.52427 2.53974 + vertex 1.64371 1.52926 2.53972 + vertex 1.63997 1.52551 2.54101 + endloop + endfacet + facet normal 0.322085 0.00248812 0.946708 + outer loop + vertex 1.63997 1.52053 2.54103 + vertex 1.64371 1.52427 2.53974 + vertex 1.63997 1.52551 2.54101 + endloop + endfacet + facet normal 0.299796 0.00250076 0.954 + outer loop + vertex 1.63997 1.52551 2.54101 + vertex 1.63618 1.52187 2.54221 + vertex 1.63997 1.52053 2.54103 + endloop + endfacet + facet normal 0.29938 0.00121296 0.954133 + outer loop + vertex 1.63618 1.52187 2.54221 + vertex 1.63619 1.51689 2.54222 + vertex 1.63997 1.52053 2.54103 + endloop + endfacet + facet normal 0.299085 0.00154989 0.954225 + outer loop + vertex 1.63997 1.52053 2.54103 + vertex 1.63619 1.51689 2.54222 + vertex 1.63997 1.51555 2.54103 + endloop + endfacet + facet normal 0.321477 0.00156404 0.946916 + outer loop + vertex 1.63997 1.51555 2.54103 + vertex 1.64371 1.5193 2.53976 + vertex 1.63997 1.52053 2.54103 + endloop + endfacet + facet normal 0.321001 0.00209174 0.947077 + outer loop + vertex 1.64372 1.51433 2.53977 + vertex 1.64371 1.5193 2.53976 + vertex 1.63997 1.51555 2.54103 + endloop + endfacet + facet normal 0.321139 0.00256369 0.947029 + outer loop + vertex 1.63999 1.51057 2.54104 + vertex 1.64372 1.51433 2.53977 + vertex 1.63997 1.51555 2.54103 + endloop + endfacet + facet normal 0.297838 0.00249448 0.954613 + outer loop + vertex 1.63997 1.51555 2.54103 + vertex 1.6362 1.5119 2.54222 + vertex 1.63999 1.51057 2.54104 + endloop + endfacet + facet normal 0.297819 0.00243387 0.954619 + outer loop + vertex 1.6362 1.5119 2.54222 + vertex 1.63621 1.5069 2.54223 + vertex 1.63999 1.51057 2.54104 + endloop + endfacet + facet normal 0.296641 0.00376527 0.954982 + outer loop + vertex 1.63999 1.51057 2.54104 + vertex 1.63621 1.5069 2.54223 + vertex 1.64002 1.50558 2.54105 + endloop + endfacet + facet normal 0.319735 0.0038785 0.947499 + outer loop + vertex 1.64002 1.50558 2.54105 + vertex 1.64374 1.50934 2.53978 + vertex 1.63999 1.51057 2.54104 + endloop + endfacet + facet normal 0.320412 0.00313425 0.947273 + outer loop + vertex 1.64376 1.50436 2.53979 + vertex 1.64374 1.50934 2.53978 + vertex 1.64002 1.50558 2.54105 + endloop + endfacet + facet normal 0.320389 0.00305723 0.947281 + outer loop + vertex 1.64005 1.50059 2.54106 + vertex 1.64376 1.50436 2.53979 + vertex 1.64002 1.50558 2.54105 + endloop + endfacet + facet normal 0.295966 0.00293519 0.955194 + outer loop + vertex 1.64002 1.50558 2.54105 + vertex 1.63624 1.50191 2.54223 + vertex 1.64005 1.50059 2.54106 + endloop + endfacet + facet normal 0.295423 0.00121517 0.955366 + outer loop + vertex 1.63624 1.50191 2.54223 + vertex 1.63625 1.49692 2.54224 + vertex 1.64005 1.50059 2.54106 + endloop + endfacet + facet normal 0.296516 -2.25566e-05 0.955028 + outer loop + vertex 1.64005 1.50059 2.54106 + vertex 1.63625 1.49692 2.54224 + vertex 1.64006 1.4956 2.54105 + endloop + endfacet + facet normal 0.322109 3.62264e-05 0.946702 + outer loop + vertex 1.64006 1.4956 2.54105 + vertex 1.64378 1.49938 2.53979 + vertex 1.64005 1.50059 2.54106 + endloop + endfacet + facet normal 0.325118 -0.00327865 0.945668 + outer loop + vertex 1.64378 1.49438 2.53977 + vertex 1.64378 1.49938 2.53979 + vertex 1.64006 1.4956 2.54105 + endloop + endfacet + facet normal 0.325052 -0.00350306 0.94569 + outer loop + vertex 1.64004 1.49062 2.54104 + vertex 1.64378 1.49438 2.53977 + vertex 1.64006 1.4956 2.54105 + endloop + endfacet + facet normal 0.297702 -0.00345834 0.954653 + outer loop + vertex 1.64006 1.4956 2.54105 + vertex 1.63625 1.49193 2.54223 + vertex 1.64004 1.49062 2.54104 + endloop + endfacet + facet normal 0.297416 -0.00436735 0.954738 + outer loop + vertex 1.63625 1.49193 2.54223 + vertex 1.63623 1.48694 2.54221 + vertex 1.64004 1.49062 2.54104 + endloop + endfacet + facet normal 0.298428 -0.00552051 0.954416 + outer loop + vertex 1.64004 1.49062 2.54104 + vertex 1.63623 1.48694 2.54221 + vertex 1.64002 1.48565 2.54102 + endloop + endfacet + facet normal 0.325383 -0.00564098 0.945566 + outer loop + vertex 1.64002 1.48565 2.54102 + vertex 1.64376 1.48939 2.53976 + vertex 1.64004 1.49062 2.54104 + endloop + endfacet + facet normal 0.324599 -0.00476621 0.94584 + outer loop + vertex 1.64373 1.48442 2.53974 + vertex 1.64376 1.48939 2.53976 + vertex 1.64002 1.48565 2.54102 + endloop + endfacet + facet normal 0.324324 -0.00569256 0.945929 + outer loop + vertex 1.63998 1.48067 2.541 + vertex 1.64373 1.48442 2.53974 + vertex 1.64002 1.48565 2.54102 + endloop + endfacet + facet normal 0.298595 -0.00556093 0.954364 + outer loop + vertex 1.64002 1.48565 2.54102 + vertex 1.6362 1.48196 2.54219 + vertex 1.63998 1.48067 2.541 + endloop + endfacet + facet normal 0.298681 -0.00528415 0.954338 + outer loop + vertex 1.6362 1.48196 2.54219 + vertex 1.63617 1.47697 2.54217 + vertex 1.63998 1.48067 2.541 + endloop + endfacet + facet normal 0.298538 -0.00512273 0.954384 + outer loop + vertex 1.63998 1.48067 2.541 + vertex 1.63617 1.47697 2.54217 + vertex 1.63995 1.47569 2.54098 + endloop + endfacet + facet normal 0.322947 -0.00524529 0.946402 + outer loop + vertex 1.63995 1.47569 2.54098 + vertex 1.64371 1.47945 2.53972 + vertex 1.63998 1.48067 2.541 + endloop + endfacet + facet normal 0.322649 -0.00491308 0.946506 + outer loop + vertex 1.64368 1.47447 2.53971 + vertex 1.64371 1.47945 2.53972 + vertex 1.63995 1.47569 2.54098 + endloop + endfacet + facet normal 0.322541 -0.00528059 0.946541 + outer loop + vertex 1.63992 1.47069 2.54097 + vertex 1.64368 1.47447 2.53971 + vertex 1.63995 1.47569 2.54098 + endloop + endfacet + facet normal 0.29806 -0.00514273 0.954533 + outer loop + vertex 1.63995 1.47569 2.54098 + vertex 1.63614 1.47197 2.54215 + vertex 1.63992 1.47069 2.54097 + endloop + endfacet + facet normal 0.297577 -0.00669582 0.954674 + outer loop + vertex 1.63614 1.47197 2.54215 + vertex 1.63611 1.46697 2.54213 + vertex 1.63992 1.47069 2.54097 + endloop + endfacet + facet normal 0.296898 -0.00593203 0.954891 + outer loop + vertex 1.63992 1.47069 2.54097 + vertex 1.63611 1.46697 2.54213 + vertex 1.63988 1.46569 2.54095 + endloop + endfacet + facet normal 0.320415 -0.00610842 0.947258 + outer loop + vertex 1.63988 1.46569 2.54095 + vertex 1.64364 1.46947 2.5397 + vertex 1.63992 1.47069 2.54097 + endloop + endfacet + facet normal 0.319072 -0.00462048 0.947719 + outer loop + vertex 1.6436 1.46446 2.53969 + vertex 1.64364 1.46947 2.5397 + vertex 1.63988 1.46569 2.54095 + endloop + endfacet + facet normal 0.318534 -0.00642785 0.94789 + outer loop + vertex 1.63983 1.46068 2.54093 + vertex 1.6436 1.46446 2.53969 + vertex 1.63988 1.46569 2.54095 + endloop + endfacet + facet normal 0.295595 -0.00623162 0.955293 + outer loop + vertex 1.63988 1.46569 2.54095 + vertex 1.63606 1.46197 2.54211 + vertex 1.63983 1.46068 2.54093 + endloop + endfacet + facet normal 0.295287 -0.00721431 0.955381 + outer loop + vertex 1.63606 1.46197 2.54211 + vertex 1.63603 1.45698 2.54208 + vertex 1.63983 1.46068 2.54093 + endloop + endfacet + facet normal 0.295036 -0.00693205 0.955461 + outer loop + vertex 1.63983 1.46068 2.54093 + vertex 1.63603 1.45698 2.54208 + vertex 1.63979 1.4557 2.54091 + endloop + endfacet + facet normal 0.318129 -0.00704948 0.948021 + outer loop + vertex 1.63979 1.4557 2.54091 + vertex 1.64355 1.45946 2.53967 + vertex 1.63983 1.46068 2.54093 + endloop + endfacet + facet normal 0.319237 -0.00828149 0.947639 + outer loop + vertex 1.64355 1.45449 2.53963 + vertex 1.64355 1.45946 2.53967 + vertex 1.63979 1.4557 2.54091 + endloop + endfacet + facet normal 0.318792 -0.00981198 0.947774 + outer loop + vertex 1.6398 1.45076 2.54085 + vertex 1.64355 1.45449 2.53963 + vertex 1.63979 1.4557 2.54091 + endloop + endfacet + facet normal 0.296558 -0.00989177 0.954963 + outer loop + vertex 1.63979 1.4557 2.54091 + vertex 1.63602 1.45202 2.54204 + vertex 1.6398 1.45076 2.54085 + endloop + endfacet + facet normal 0.296164 -0.0111777 0.955072 + outer loop + vertex 1.63602 1.45202 2.54204 + vertex 1.63601 1.44708 2.54199 + vertex 1.6398 1.45076 2.54085 + endloop + endfacet + facet normal 0.298494 -0.0138064 0.954312 + outer loop + vertex 1.6398 1.45076 2.54085 + vertex 1.63601 1.44708 2.54199 + vertex 1.63979 1.44583 2.54079 + endloop + endfacet + facet normal 0.321841 -0.0137323 0.946694 + outer loop + vertex 1.63979 1.44583 2.54079 + vertex 1.64364 1.44953 2.53953 + vertex 1.6398 1.45076 2.54085 + endloop + endfacet + facet normal 0.323238 -0.0153545 0.946193 + outer loop + vertex 1.64358 1.44449 2.53947 + vertex 1.64364 1.44953 2.53953 + vertex 1.63979 1.44583 2.54079 + endloop + endfacet + facet normal 0.321977 -0.0192745 0.946551 + outer loop + vertex 1.63971 1.44087 2.54071 + vertex 1.64358 1.44449 2.53947 + vertex 1.63979 1.44583 2.54079 + endloop + endfacet + facet normal 0.299796 -0.0190133 0.953814 + outer loop + vertex 1.63979 1.44583 2.54079 + vertex 1.63595 1.4421 2.54192 + vertex 1.63971 1.44087 2.54071 + endloop + endfacet + facet normal 0.298564 -0.0230768 0.954111 + outer loop + vertex 1.63595 1.4421 2.54192 + vertex 1.63585 1.43707 2.54183 + vertex 1.63971 1.44087 2.54071 + endloop + endfacet + facet normal 0.298998 -0.0235613 0.953963 + outer loop + vertex 1.63971 1.44087 2.54071 + vertex 1.63585 1.43707 2.54183 + vertex 1.63955 1.4359 2.54064 + endloop + endfacet + facet normal 0.317814 -0.0240773 0.947847 + outer loop + vertex 1.63955 1.4359 2.54064 + vertex 1.64336 1.43942 2.53945 + vertex 1.63971 1.44087 2.54071 + endloop + endfacet + facet normal 0.316879 -0.0229483 0.948188 + outer loop + vertex 1.64311 1.43425 2.53941 + vertex 1.64336 1.43942 2.53945 + vertex 1.63955 1.4359 2.54064 + endloop + endfacet + facet normal 0.314503 -0.0285455 0.948827 + outer loop + vertex 1.63925 1.43101 2.54059 + vertex 1.64311 1.43425 2.53941 + vertex 1.63955 1.4359 2.54064 + endloop + endfacet + facet normal 0.29778 -0.0276029 0.954235 + outer loop + vertex 1.63955 1.4359 2.54064 + vertex 1.63576 1.43212 2.54171 + vertex 1.63925 1.43101 2.54059 + endloop + endfacet + facet normal 0.2971 -0.0298938 0.954378 + outer loop + vertex 1.63576 1.43212 2.54171 + vertex 1.63577 1.42759 2.54157 + vertex 1.63925 1.43101 2.54059 + endloop + endfacet + facet normal 0.295427 -0.0280229 0.954954 + outer loop + vertex 1.63925 1.43101 2.54059 + vertex 1.63577 1.42759 2.54157 + vertex 1.63863 1.42715 2.54067 + endloop + endfacet + facet normal 0.30661 -0.0298972 0.951366 + outer loop + vertex 1.63863 1.42715 2.54067 + vertex 1.64249 1.42844 2.53947 + vertex 1.63925 1.43101 2.54059 + endloop + endfacet + facet normal 0.305502 -0.0261654 0.951832 + outer loop + vertex 1.63863 1.42715 2.54067 + vertex 1.63919 1.42388 2.5404 + vertex 1.64249 1.42844 2.53947 + endloop + endfacet + facet normal 0.300297 -0.0220475 0.953591 + outer loop + vertex 1.64249 1.42844 2.53947 + vertex 1.63919 1.42388 2.5404 + vertex 1.64288 1.42313 2.53922 + endloop + endfacet + facet normal 0.330169 -0.0194216 0.943722 + outer loop + vertex 1.64288 1.42313 2.53922 + vertex 1.64728 1.42669 2.53775 + vertex 1.64249 1.42844 2.53947 + endloop + endfacet + facet normal 0.331836 -0.014384 0.943227 + outer loop + vertex 1.64728 1.42669 2.53775 + vertex 1.6469 1.43241 2.53798 + vertex 1.64249 1.42844 2.53947 + endloop + endfacet + facet normal 0.342095 -0.0272859 0.939269 + outer loop + vertex 1.64249 1.42844 2.53947 + vertex 1.6469 1.43241 2.53798 + vertex 1.64311 1.43425 2.53941 + endloop + endfacet + facet normal 0.34695 -0.0161049 0.937745 + outer loop + vertex 1.6469 1.43241 2.53798 + vertex 1.64695 1.43771 2.53805 + vertex 1.64311 1.43425 2.53941 + endloop + endfacet + facet normal 0.319754 -0.00499042 0.947488 + outer loop + vertex 1.64615 1.42179 2.53811 + vertex 1.64728 1.42669 2.53775 + vertex 1.64288 1.42313 2.53922 + endloop + endfacet + facet normal 0.312665 -0.0240914 0.949558 + outer loop + vertex 1.64292 1.41835 2.53909 + vertex 1.64615 1.42179 2.53811 + vertex 1.64288 1.42313 2.53922 + endloop + endfacet + facet normal 0.296369 -0.024392 0.954762 + outer loop + vertex 1.64292 1.41835 2.53909 + vertex 1.64288 1.42313 2.53922 + vertex 1.63915 1.41936 2.54028 + endloop + endfacet + facet normal 0.294841 -0.0304633 0.95506 + outer loop + vertex 1.63905 1.41454 2.54016 + vertex 1.64292 1.41835 2.53909 + vertex 1.63915 1.41936 2.54028 + endloop + endfacet + facet normal 0.290288 -0.0304 0.956456 + outer loop + vertex 1.63905 1.41454 2.54016 + vertex 1.63915 1.41936 2.54028 + vertex 1.63534 1.41571 2.54132 + endloop + endfacet + facet normal 0.289188 -0.0340949 0.956665 + outer loop + vertex 1.63517 1.41081 2.5412 + vertex 1.63905 1.41454 2.54016 + vertex 1.63534 1.41571 2.54132 + endloop + endfacet + facet normal 0.294793 -0.0342418 0.954947 + outer loop + vertex 1.63534 1.41571 2.54132 + vertex 1.63146 1.41206 2.54239 + vertex 1.63517 1.41081 2.5412 + endloop + endfacet + facet normal 0.294036 -0.0366356 0.955092 + outer loop + vertex 1.63146 1.41206 2.54239 + vertex 1.63132 1.40712 2.54224 + vertex 1.63517 1.41081 2.5412 + endloop + endfacet + facet normal 0.294223 -0.0368488 0.955026 + outer loop + vertex 1.63517 1.41081 2.5412 + vertex 1.63132 1.40712 2.54224 + vertex 1.63507 1.40588 2.54104 + endloop + endfacet + facet normal 0.288541 -0.0367841 0.956761 + outer loop + vertex 1.63507 1.40588 2.54104 + vertex 1.63895 1.40961 2.54001 + vertex 1.63517 1.41081 2.5412 + endloop + endfacet + facet normal 0.288076 -0.0362563 0.956921 + outer loop + vertex 1.63883 1.40463 2.53986 + vertex 1.63895 1.40961 2.54001 + vertex 1.63507 1.40588 2.54104 + endloop + endfacet + facet normal 0.287462 -0.0382158 0.957029 + outer loop + vertex 1.63495 1.4009 2.54088 + vertex 1.63883 1.40463 2.53986 + vertex 1.63507 1.40588 2.54104 + endloop + endfacet + facet normal 0.294074 -0.0383061 0.955015 + outer loop + vertex 1.63507 1.40588 2.54104 + vertex 1.63119 1.40212 2.54208 + vertex 1.63495 1.4009 2.54088 + endloop + endfacet + facet normal 0.293724 -0.0394389 0.955076 + outer loop + vertex 1.63119 1.40212 2.54208 + vertex 1.63103 1.39705 2.54192 + vertex 1.63495 1.4009 2.54088 + endloop + endfacet + facet normal 0.294214 -0.0399855 0.954903 + outer loop + vertex 1.63495 1.4009 2.54088 + vertex 1.63103 1.39705 2.54192 + vertex 1.63475 1.39588 2.54073 + endloop + endfacet + facet normal 0.286079 -0.0397412 0.957382 + outer loop + vertex 1.63475 1.39588 2.54073 + vertex 1.63869 1.39962 2.53971 + vertex 1.63495 1.4009 2.54088 + endloop + endfacet + facet normal 0.286216 -0.0398986 0.957334 + outer loop + vertex 1.63839 1.39447 2.53958 + vertex 1.63869 1.39962 2.53971 + vertex 1.63475 1.39588 2.54073 + endloop + endfacet + facet normal 0.285325 -0.0423217 0.957496 + outer loop + vertex 1.63437 1.39098 2.54062 + vertex 1.63839 1.39447 2.53958 + vertex 1.63475 1.39588 2.54073 + endloop + endfacet + facet normal 0.294975 -0.0430054 0.954537 + outer loop + vertex 1.63475 1.39588 2.54073 + vertex 1.63086 1.39206 2.54176 + vertex 1.63437 1.39098 2.54062 + endloop + endfacet + facet normal 0.294358 -0.0451026 0.95463 + outer loop + vertex 1.63086 1.39206 2.54176 + vertex 1.6308 1.38752 2.54156 + vertex 1.63437 1.39098 2.54062 + endloop + endfacet + facet normal 0.296187 -0.0471707 0.953964 + outer loop + vertex 1.63437 1.39098 2.54062 + vertex 1.6308 1.38752 2.54156 + vertex 1.63367 1.38709 2.54065 + endloop + endfacet + facet normal 0.286001 -0.045297 0.957158 + outer loop + vertex 1.63367 1.38709 2.54065 + vertex 1.63758 1.38871 2.53956 + vertex 1.63437 1.39098 2.54062 + endloop + endfacet + facet normal 0.287324 -0.0488786 0.956585 + outer loop + vertex 1.63367 1.38709 2.54065 + vertex 1.6342 1.38389 2.54033 + vertex 1.63758 1.38871 2.53956 + endloop + endfacet + facet normal 0.285705 -0.0476546 0.957132 + outer loop + vertex 1.63758 1.38871 2.53956 + vertex 1.6342 1.38389 2.54033 + vertex 1.63799 1.38351 2.53918 + endloop + endfacet + facet normal 0.280392 -0.0481862 0.958675 + outer loop + vertex 1.63799 1.38351 2.53918 + vertex 1.64209 1.38792 2.5382 + vertex 1.63758 1.38871 2.53956 + endloop + endfacet + facet normal 0.281214 -0.0434747 0.95866 + outer loop + vertex 1.64209 1.38792 2.5382 + vertex 1.64225 1.39316 2.53839 + vertex 1.63758 1.38871 2.53956 + endloop + endfacet + facet normal 0.281102 -0.0433479 0.958698 + outer loop + vertex 1.63758 1.38871 2.53956 + vertex 1.64225 1.39316 2.53839 + vertex 1.63839 1.39447 2.53958 + endloop + endfacet + facet normal 0.282735 -0.0382963 0.958433 + outer loop + vertex 1.64225 1.39316 2.53839 + vertex 1.64251 1.39836 2.53852 + vertex 1.63839 1.39447 2.53958 + endloop + endfacet + facet normal 0.298739 -0.0389487 0.95354 + outer loop + vertex 1.64225 1.39316 2.53839 + vertex 1.64636 1.39722 2.53727 + vertex 1.64251 1.39836 2.53852 + endloop + endfacet + facet normal 0.300864 -0.0313452 0.953152 + outer loop + vertex 1.64636 1.39722 2.53727 + vertex 1.64647 1.40223 2.5374 + vertex 1.64251 1.39836 2.53852 + endloop + endfacet + facet normal 0.304466 -0.0354035 0.951865 + outer loop + vertex 1.64251 1.39836 2.53852 + vertex 1.64647 1.40223 2.5374 + vertex 1.64265 1.40341 2.53866 + endloop + endfacet + facet normal 0.285527 -0.0350149 0.957731 + outer loop + vertex 1.64251 1.39836 2.53852 + vertex 1.64265 1.40341 2.53866 + vertex 1.63869 1.39962 2.53971 + endloop + endfacet + facet normal 0.287702 -0.0374959 0.956986 + outer loop + vertex 1.63869 1.39962 2.53971 + vertex 1.64265 1.40341 2.53866 + vertex 1.63883 1.40463 2.53986 + endloop + endfacet + facet normal 0.28897 -0.0333273 0.956758 + outer loop + vertex 1.64265 1.40341 2.53866 + vertex 1.6428 1.40842 2.5388 + vertex 1.63883 1.40463 2.53986 + endloop + endfacet + facet normal 0.31092 -0.0337706 0.949836 + outer loop + vertex 1.64265 1.40341 2.53866 + vertex 1.64661 1.40723 2.5375 + vertex 1.6428 1.40842 2.5388 + endloop + endfacet + facet normal 0.312182 -0.0294589 0.949565 + outer loop + vertex 1.64661 1.40723 2.5375 + vertex 1.64685 1.41228 2.53758 + vertex 1.6428 1.40842 2.5388 + endloop + endfacet + facet normal 0.315181 -0.032963 0.948459 + outer loop + vertex 1.6428 1.40842 2.5388 + vertex 1.64685 1.41228 2.53758 + vertex 1.64297 1.41348 2.53891 + endloop + endfacet + facet normal 0.292728 -0.0323443 0.955649 + outer loop + vertex 1.6428 1.40842 2.5388 + vertex 1.64297 1.41348 2.53891 + vertex 1.63895 1.40961 2.54001 + endloop + endfacet + facet normal 0.294436 -0.0342902 0.955056 + outer loop + vertex 1.63895 1.40961 2.54001 + vertex 1.64297 1.41348 2.53891 + vertex 1.63905 1.41454 2.54016 + endloop + endfacet + facet normal 0.316751 -0.0275208 0.948109 + outer loop + vertex 1.64685 1.41228 2.53758 + vertex 1.64733 1.41775 2.53758 + vertex 1.64297 1.41348 2.53891 + endloop + endfacet + facet normal 0.319308 -0.0304245 0.947163 + outer loop + vertex 1.64297 1.41348 2.53891 + vertex 1.64733 1.41775 2.53758 + vertex 1.64292 1.41835 2.53909 + endloop + endfacet + facet normal 0.306417 -0.0286141 0.951467 + outer loop + vertex 1.64647 1.40223 2.5374 + vertex 1.64661 1.40723 2.5375 + vertex 1.64265 1.40341 2.53866 + endloop + endfacet + facet normal 0.295709 -0.0355902 0.954615 + outer loop + vertex 1.64623 1.39216 2.53712 + vertex 1.64636 1.39722 2.53727 + vertex 1.64225 1.39316 2.53839 + endloop + endfacet + facet normal 0.338472 -0.0362296 0.940279 + outer loop + vertex 1.64636 1.39722 2.53727 + vertex 1.64623 1.39216 2.53712 + vertex 1.65005 1.39608 2.5359 + endloop + endfacet + facet normal 0.341263 -0.0263159 0.939599 + outer loop + vertex 1.65013 1.40106 2.53601 + vertex 1.64636 1.39722 2.53727 + vertex 1.65005 1.39608 2.5359 + endloop + endfacet + facet normal 0.409696 -0.0267442 0.91183 + outer loop + vertex 1.65005 1.39608 2.5359 + vertex 1.65352 1.39968 2.53444 + vertex 1.65013 1.40106 2.53601 + endloop + endfacet + facet normal 0.41298 -0.0172469 0.910577 + outer loop + vertex 1.65352 1.39968 2.53444 + vertex 1.65357 1.40464 2.53451 + vertex 1.65013 1.40106 2.53601 + endloop + endfacet + facet normal 0.406388 -0.0229075 0.913414 + outer loop + vertex 1.65347 1.39468 2.53434 + vertex 1.65352 1.39968 2.53444 + vertex 1.65005 1.39608 2.5359 + endloop + endfacet + facet normal 0.402464 -0.0339894 0.914805 + outer loop + vertex 1.64993 1.39108 2.53576 + vertex 1.65347 1.39468 2.53434 + vertex 1.65005 1.39608 2.5359 + endloop + endfacet + facet normal 0.400133 -0.0312592 0.915924 + outer loop + vertex 1.65333 1.38962 2.53423 + vertex 1.65347 1.39468 2.53434 + vertex 1.64993 1.39108 2.53576 + endloop + endfacet + facet normal 0.395653 -0.0432545 0.917381 + outer loop + vertex 1.6497 1.38605 2.53563 + vertex 1.65333 1.38962 2.53423 + vertex 1.64993 1.39108 2.53576 + endloop + endfacet + facet normal 0.330788 -0.0409396 0.942817 + outer loop + vertex 1.64993 1.39108 2.53576 + vertex 1.64608 1.3871 2.53694 + vertex 1.6497 1.38605 2.53563 + endloop + endfacet + facet normal 0.329328 -0.0462728 0.943081 + outer loop + vertex 1.64608 1.3871 2.53694 + vertex 1.64592 1.38219 2.53676 + vertex 1.6497 1.38605 2.53563 + endloop + endfacet + facet normal 0.325634 -0.0422187 0.944553 + outer loop + vertex 1.6497 1.38605 2.53563 + vertex 1.64592 1.38219 2.53676 + vertex 1.64929 1.38116 2.53555 + endloop + endfacet + facet normal 0.387641 -0.0469996 0.920612 + outer loop + vertex 1.64929 1.38116 2.53555 + vertex 1.653 1.38442 2.53415 + vertex 1.6497 1.38605 2.53563 + endloop + endfacet + facet normal 0.383761 -0.0417984 0.922486 + outer loop + vertex 1.65219 1.37868 2.53423 + vertex 1.653 1.38442 2.53415 + vertex 1.64929 1.38116 2.53555 + endloop + endfacet + facet normal 0.378409 -0.0490402 0.924339 + outer loop + vertex 1.64862 1.37732 2.53562 + vertex 1.65219 1.37868 2.53423 + vertex 1.64929 1.38116 2.53555 + endloop + endfacet + facet normal 0.316349 -0.037637 0.947896 + outer loop + vertex 1.64929 1.38116 2.53555 + vertex 1.64584 1.37772 2.53656 + vertex 1.64862 1.37732 2.53562 + endloop + endfacet + facet normal 0.315185 -0.045782 0.947925 + outer loop + vertex 1.64862 1.37732 2.53562 + vertex 1.64584 1.37772 2.53656 + vertex 1.64637 1.37458 2.53623 + endloop + endfacet + facet normal 0.328944 -0.0582587 0.942551 + outer loop + vertex 1.64862 1.37732 2.53562 + vertex 1.64637 1.37458 2.53623 + vertex 1.64908 1.3741 2.53526 + endloop + endfacet + facet normal 0.327682 -0.0653571 0.942525 + outer loop + vertex 1.64908 1.3741 2.53526 + vertex 1.64637 1.37458 2.53623 + vertex 1.64563 1.37071 2.53622 + endloop + endfacet + facet normal 0.319257 -0.0558011 0.946024 + outer loop + vertex 1.64895 1.36958 2.53504 + vertex 1.64908 1.3741 2.53526 + vertex 1.64563 1.37071 2.53622 + endloop + endfacet + facet normal 0.317433 -0.0614514 0.946287 + outer loop + vertex 1.64518 1.36587 2.53606 + vertex 1.64895 1.36958 2.53504 + vertex 1.64563 1.37071 2.53622 + endloop + endfacet + facet normal 0.284637 -0.0587109 0.956836 + outer loop + vertex 1.64563 1.37071 2.53622 + vertex 1.64155 1.3671 2.53722 + vertex 1.64518 1.36587 2.53606 + endloop + endfacet + facet normal 0.283803 -0.0612628 0.956924 + outer loop + vertex 1.64155 1.3671 2.53722 + vertex 1.64114 1.362 2.53701 + vertex 1.64518 1.36587 2.53606 + endloop + endfacet + facet normal 0.282504 -0.0597919 0.957401 + outer loop + vertex 1.64518 1.36587 2.53606 + vertex 1.64114 1.362 2.53701 + vertex 1.64482 1.36096 2.53586 + endloop + endfacet + facet normal 0.310022 -0.0614475 0.948742 + outer loop + vertex 1.64482 1.36096 2.53586 + vertex 1.64871 1.3647 2.53483 + vertex 1.64518 1.36587 2.53606 + endloop + endfacet + facet normal 0.30622 -0.0570801 0.950248 + outer loop + vertex 1.64832 1.35963 2.53465 + vertex 1.64871 1.3647 2.53483 + vertex 1.64482 1.36096 2.53586 + endloop + endfacet + facet normal 0.303706 -0.0640493 0.950611 + outer loop + vertex 1.64436 1.35619 2.53569 + vertex 1.64832 1.35963 2.53465 + vertex 1.64482 1.36096 2.53586 + endloop + endfacet + facet normal 0.280733 -0.0621061 0.957774 + outer loop + vertex 1.64482 1.36096 2.53586 + vertex 1.64089 1.35717 2.53677 + vertex 1.64436 1.35619 2.53569 + endloop + endfacet + facet normal 0.280013 -0.0646907 0.957814 + outer loop + vertex 1.64089 1.35717 2.53677 + vertex 1.64077 1.35277 2.53651 + vertex 1.64436 1.35619 2.53569 + endloop + endfacet + facet normal 0.278049 -0.062448 0.958535 + outer loop + vertex 1.64436 1.35619 2.53569 + vertex 1.64077 1.35277 2.53651 + vertex 1.64362 1.35239 2.53565 + endloop + endfacet + facet normal 0.295558 -0.0658226 0.953055 + outer loop + vertex 1.64362 1.35239 2.53565 + vertex 1.64751 1.35396 2.53456 + vertex 1.64436 1.35619 2.53569 + endloop + endfacet + facet normal 0.293675 -0.0605151 0.953988 + outer loop + vertex 1.64362 1.35239 2.53565 + vertex 1.64413 1.34919 2.53529 + vertex 1.64751 1.35396 2.53456 + endloop + endfacet + facet normal 0.294813 -0.0613838 0.953581 + outer loop + vertex 1.64751 1.35396 2.53456 + vertex 1.64413 1.34919 2.53529 + vertex 1.64799 1.34872 2.53407 + endloop + endfacet + facet normal 0.330957 -0.0569677 0.941925 + outer loop + vertex 1.64799 1.34872 2.53407 + vertex 1.65198 1.35322 2.53294 + vertex 1.64751 1.35396 2.53456 + endloop + endfacet + facet normal 0.331567 -0.0532746 0.941926 + outer loop + vertex 1.65198 1.35322 2.53294 + vertex 1.65202 1.35837 2.53322 + vertex 1.64751 1.35396 2.53456 + endloop + endfacet + facet normal 0.341722 -0.0649944 0.937551 + outer loop + vertex 1.64751 1.35396 2.53456 + vertex 1.65202 1.35837 2.53322 + vertex 1.64832 1.35963 2.53465 + endloop + endfacet + facet normal 0.345537 -0.0531168 0.9369 + outer loop + vertex 1.65202 1.35837 2.53322 + vertex 1.65229 1.3635 2.53341 + vertex 1.64832 1.35963 2.53465 + endloop + endfacet + facet normal 0.329546 -0.055573 0.942503 + outer loop + vertex 1.65254 1.34801 2.53244 + vertex 1.65198 1.35322 2.53294 + vertex 1.64799 1.34872 2.53407 + endloop + endfacet + facet normal 0.328541 -0.0619189 0.942458 + outer loop + vertex 1.64785 1.34352 2.53378 + vertex 1.65254 1.34801 2.53244 + vertex 1.64799 1.34872 2.53407 + endloop + endfacet + facet normal 0.292186 -0.0616201 0.954374 + outer loop + vertex 1.64785 1.34352 2.53378 + vertex 1.64799 1.34872 2.53407 + vertex 1.64397 1.3446 2.53503 + endloop + endfacet + facet normal 0.290425 -0.0680713 0.954473 + outer loop + vertex 1.64353 1.33954 2.53481 + vertex 1.64785 1.34352 2.53378 + vertex 1.64397 1.3446 2.53503 + endloop + endfacet + facet normal 0.279462 -0.0672669 0.957798 + outer loop + vertex 1.64353 1.33954 2.53481 + vertex 1.64397 1.3446 2.53503 + vertex 1.63998 1.34094 2.53594 + endloop + endfacet + facet normal 0.278433 -0.0699656 0.957904 + outer loop + vertex 1.63947 1.33616 2.53574 + vertex 1.64353 1.33954 2.53481 + vertex 1.63998 1.34094 2.53594 + endloop + endfacet + facet normal 0.284657 -0.0705508 0.95603 + outer loop + vertex 1.63998 1.34094 2.53594 + vertex 1.636 1.33723 2.53685 + vertex 1.63947 1.33616 2.53574 + endloop + endfacet + facet normal 0.284012 -0.0726629 0.956063 + outer loop + vertex 1.636 1.33723 2.53685 + vertex 1.63586 1.33277 2.53655 + vertex 1.63947 1.33616 2.53574 + endloop + endfacet + facet normal 0.287072 -0.0762013 0.954873 + outer loop + vertex 1.63947 1.33616 2.53574 + vertex 1.63586 1.33277 2.53655 + vertex 1.63871 1.33237 2.53567 + endloop + endfacet + facet normal 0.280493 -0.074935 0.956927 + outer loop + vertex 1.63871 1.33237 2.53567 + vertex 1.64261 1.33388 2.53464 + vertex 1.63947 1.33616 2.53574 + endloop + endfacet + facet normal 0.28206 -0.0795357 0.956094 + outer loop + vertex 1.63871 1.33237 2.53567 + vertex 1.63915 1.32915 2.53527 + vertex 1.64261 1.33388 2.53464 + endloop + endfacet + facet normal 0.280726 -0.0784964 0.956573 + outer loop + vertex 1.64261 1.33388 2.53464 + vertex 1.63915 1.32915 2.53527 + vertex 1.64291 1.32865 2.53412 + endloop + endfacet + facet normal 0.281114 -0.078463 0.956462 + outer loop + vertex 1.64291 1.32865 2.53412 + vertex 1.64711 1.33302 2.53325 + vertex 1.64261 1.33388 2.53464 + endloop + endfacet + facet normal 0.282541 -0.0712343 0.956607 + outer loop + vertex 1.64711 1.33302 2.53325 + vertex 1.64738 1.33821 2.53356 + vertex 1.64261 1.33388 2.53464 + endloop + endfacet + facet normal 0.285112 -0.0743118 0.955609 + outer loop + vertex 1.64261 1.33388 2.53464 + vertex 1.64738 1.33821 2.53356 + vertex 1.64353 1.33954 2.53481 + endloop + endfacet + facet normal 0.305959 -0.0720201 0.949317 + outer loop + vertex 1.64711 1.33302 2.53325 + vertex 1.65134 1.33715 2.5322 + vertex 1.64738 1.33821 2.53356 + endloop + endfacet + facet normal 0.309207 -0.0596871 0.94912 + outer loop + vertex 1.65134 1.33715 2.5322 + vertex 1.65173 1.34227 2.53239 + vertex 1.64738 1.33821 2.53356 + endloop + endfacet + facet normal 0.315723 -0.0674357 0.946452 + outer loop + vertex 1.64738 1.33821 2.53356 + vertex 1.65173 1.34227 2.53239 + vertex 1.64785 1.34352 2.53378 + endloop + endfacet + facet normal 0.299285 -0.0645096 0.951981 + outer loop + vertex 1.6511 1.33224 2.53194 + vertex 1.65134 1.33715 2.5322 + vertex 1.64711 1.33302 2.53325 + endloop + endfacet + facet normal 0.296871 -0.0766456 0.951837 + outer loop + vertex 1.64709 1.32799 2.53285 + vertex 1.6511 1.33224 2.53194 + vertex 1.64711 1.33302 2.53325 + endloop + endfacet + facet normal 0.290791 -0.0703871 0.954194 + outer loop + vertex 1.651 1.32777 2.53164 + vertex 1.6511 1.33224 2.53194 + vertex 1.64709 1.32799 2.53285 + endloop + endfacet + facet normal 0.289736 -0.0843225 0.953385 + outer loop + vertex 1.651 1.32777 2.53164 + vertex 1.64709 1.32799 2.53285 + vertex 1.64742 1.32286 2.53229 + endloop + endfacet + facet normal 0.289783 -0.0843595 0.953367 + outer loop + vertex 1.6515 1.32464 2.53121 + vertex 1.651 1.32777 2.53164 + vertex 1.64742 1.32286 2.53229 + endloop + endfacet + facet normal 0.295026 -0.0980894 0.950441 + outer loop + vertex 1.6515 1.32464 2.53121 + vertex 1.64742 1.32286 2.53229 + vertex 1.65057 1.32078 2.5311 + endloop + endfacet + facet normal 0.355331 -0.112011 0.928005 + outer loop + vertex 1.65426 1.32418 2.5301 + vertex 1.6515 1.32464 2.53121 + vertex 1.65057 1.32078 2.5311 + endloop + endfacet + facet normal 0.348275 -0.103263 0.931687 + outer loop + vertex 1.65375 1.31943 2.52976 + vertex 1.65426 1.32418 2.5301 + vertex 1.65057 1.32078 2.5311 + endloop + endfacet + facet normal 0.348039 -0.103844 0.931711 + outer loop + vertex 1.64976 1.3161 2.53089 + vertex 1.65375 1.31943 2.52976 + vertex 1.65057 1.32078 2.5311 + endloop + endfacet + facet normal 0.296357 -0.0957797 0.950262 + outer loop + vertex 1.65057 1.32078 2.5311 + vertex 1.64642 1.31725 2.53204 + vertex 1.64976 1.3161 2.53089 + endloop + endfacet + facet normal 0.296595 -0.095086 0.950258 + outer loop + vertex 1.64642 1.31725 2.53204 + vertex 1.64606 1.31269 2.5317 + vertex 1.64976 1.3161 2.53089 + endloop + endfacet + facet normal 0.291138 -0.088627 0.952567 + outer loop + vertex 1.64976 1.3161 2.53089 + vertex 1.64606 1.31269 2.5317 + vertex 1.64888 1.31234 2.5308 + endloop + endfacet + facet normal 0.336925 -0.0988865 0.936324 + outer loop + vertex 1.64888 1.31234 2.5308 + vertex 1.6526 1.31381 2.52962 + vertex 1.64976 1.3161 2.53089 + endloop + endfacet + facet normal 0.334688 -0.092062 0.937821 + outer loop + vertex 1.64888 1.31234 2.5308 + vertex 1.64923 1.30918 2.53037 + vertex 1.6526 1.31381 2.52962 + endloop + endfacet + facet normal 0.331882 -0.0898312 0.939034 + outer loop + vertex 1.6526 1.31381 2.52962 + vertex 1.64923 1.30918 2.53037 + vertex 1.6527 1.30864 2.52909 + endloop + endfacet + facet normal 0.330739 -0.0965439 0.938771 + outer loop + vertex 1.64881 1.30456 2.53004 + vertex 1.6527 1.30864 2.52909 + vertex 1.64923 1.30918 2.53037 + endloop + endfacet + facet normal 0.292988 -0.0939519 0.951489 + outer loop + vertex 1.64881 1.30456 2.53004 + vertex 1.64923 1.30918 2.53037 + vertex 1.64559 1.30576 2.53115 + endloop + endfacet + facet normal 0.2918 -0.0971732 0.95153 + outer loop + vertex 1.64481 1.30107 2.53091 + vertex 1.64881 1.30456 2.53004 + vertex 1.64559 1.30576 2.53115 + endloop + endfacet + facet normal 0.280332 -0.0954629 0.955144 + outer loop + vertex 1.64559 1.30576 2.53115 + vertex 1.64145 1.30222 2.53201 + vertex 1.64481 1.30107 2.53091 + endloop + endfacet + facet normal 0.279703 -0.0973042 0.955143 + outer loop + vertex 1.64145 1.30222 2.53201 + vertex 1.64106 1.29764 2.53166 + vertex 1.64481 1.30107 2.53091 + endloop + endfacet + facet normal 0.280207 -0.0979013 0.954934 + outer loop + vertex 1.64481 1.30107 2.53091 + vertex 1.64106 1.29764 2.53166 + vertex 1.64391 1.29724 2.53078 + endloop + endfacet + facet normal 0.285651 -0.0991332 0.953193 + outer loop + vertex 1.64391 1.29724 2.53078 + vertex 1.6478 1.29893 2.52979 + vertex 1.64481 1.30107 2.53091 + endloop + endfacet + facet normal 0.285498 -0.0987282 0.953281 + outer loop + vertex 1.64391 1.29724 2.53078 + vertex 1.64425 1.29407 2.53035 + vertex 1.6478 1.29893 2.52979 + endloop + endfacet + facet normal 0.280571 -0.0949213 0.955128 + outer loop + vertex 1.6478 1.29893 2.52979 + vertex 1.64425 1.29407 2.53035 + vertex 1.648 1.29371 2.52922 + endloop + endfacet + facet normal 0.303941 -0.0932498 0.948116 + outer loop + vertex 1.648 1.29371 2.52922 + vertex 1.65214 1.29826 2.52834 + vertex 1.6478 1.29893 2.52979 + endloop + endfacet + facet normal 0.305497 -0.0839285 0.948487 + outer loop + vertex 1.65214 1.29826 2.52834 + vertex 1.65238 1.30349 2.52872 + vertex 1.6478 1.29893 2.52979 + endloop + endfacet + facet normal 0.318939 -0.0988081 0.942611 + outer loop + vertex 1.6478 1.29893 2.52979 + vertex 1.65238 1.30349 2.52872 + vertex 1.64881 1.30456 2.53004 + endloop + endfacet + facet normal 0.293753 -0.0831924 0.952254 + outer loop + vertex 1.65212 1.29318 2.5279 + vertex 1.65214 1.29826 2.52834 + vertex 1.648 1.29371 2.52922 + endloop + endfacet + facet normal 0.291702 -0.0972827 0.951549 + outer loop + vertex 1.64777 1.28852 2.52876 + vertex 1.65212 1.29318 2.5279 + vertex 1.648 1.29371 2.52922 + endloop + endfacet + facet normal 0.275822 -0.0969919 0.956303 + outer loop + vertex 1.64777 1.28852 2.52876 + vertex 1.648 1.29371 2.52922 + vertex 1.6438 1.28945 2.52999 + endloop + endfacet + facet normal 0.274165 -0.103764 0.956068 + outer loop + vertex 1.64273 1.28388 2.5297 + vertex 1.64777 1.28852 2.52876 + vertex 1.6438 1.28945 2.52999 + endloop + endfacet + facet normal 0.277723 -0.104386 0.954973 + outer loop + vertex 1.64273 1.28388 2.5297 + vertex 1.6438 1.28945 2.52999 + vertex 1.63966 1.28607 2.53083 + endloop + endfacet + facet normal 0.2769 -0.105598 0.955079 + outer loop + vertex 1.63872 1.28233 2.53069 + vertex 1.64273 1.28388 2.5297 + vertex 1.63966 1.28607 2.53083 + endloop + endfacet + facet normal 0.288153 -0.108281 0.951443 + outer loop + vertex 1.63966 1.28607 2.53083 + vertex 1.63592 1.28277 2.53159 + vertex 1.63872 1.28233 2.53069 + endloop + endfacet + facet normal 0.288284 -0.107544 0.951487 + outer loop + vertex 1.63872 1.28233 2.53069 + vertex 1.63592 1.28277 2.53159 + vertex 1.63628 1.27968 2.53113 + endloop + endfacet + facet normal 0.285338 -0.104639 0.952698 + outer loop + vertex 1.63872 1.28233 2.53069 + vertex 1.63628 1.27968 2.53113 + vertex 1.63908 1.27918 2.53023 + endloop + endfacet + facet normal 0.285458 -0.104021 0.95273 + outer loop + vertex 1.63908 1.27918 2.53023 + vertex 1.63628 1.27968 2.53113 + vertex 1.63537 1.27591 2.53099 + endloop + endfacet + facet normal 0.286734 -0.1056 0.952172 + outer loop + vertex 1.63868 1.27461 2.52985 + vertex 1.63908 1.27918 2.53023 + vertex 1.63537 1.27591 2.53099 + endloop + endfacet + facet normal 0.286753 -0.105552 0.952172 + outer loop + vertex 1.63459 1.27131 2.53071 + vertex 1.63868 1.27461 2.52985 + vertex 1.63537 1.27591 2.53099 + endloop + endfacet + facet normal 0.291344 -0.106245 0.9507 + outer loop + vertex 1.63537 1.27591 2.53099 + vertex 1.63128 1.27248 2.53186 + vertex 1.63459 1.27131 2.53071 + endloop + endfacet + facet normal 0.290794 -0.107789 0.950695 + outer loop + vertex 1.63128 1.27248 2.53186 + vertex 1.63087 1.26797 2.53147 + vertex 1.63459 1.27131 2.53071 + endloop + endfacet + facet normal 0.290218 -0.107087 0.95095 + outer loop + vertex 1.63459 1.27131 2.53071 + vertex 1.63087 1.26797 2.53147 + vertex 1.63365 1.26755 2.53058 + endloop + endfacet + facet normal 0.289149 -0.106834 0.951304 + outer loop + vertex 1.63365 1.26755 2.53058 + vertex 1.63764 1.26903 2.52953 + vertex 1.63459 1.27131 2.53071 + endloop + endfacet + facet normal 0.290142 -0.109972 0.950644 + outer loop + vertex 1.63365 1.26755 2.53058 + vertex 1.63388 1.26421 2.53012 + vertex 1.63764 1.26903 2.52953 + endloop + endfacet + facet normal 0.291029 -0.110708 0.950287 + outer loop + vertex 1.63764 1.26903 2.52953 + vertex 1.63388 1.26421 2.53012 + vertex 1.63777 1.26359 2.52886 + endloop + endfacet + facet normal 0.284414 -0.111108 0.952241 + outer loop + vertex 1.63777 1.26359 2.52886 + vertex 1.64238 1.26828 2.52803 + vertex 1.63764 1.26903 2.52953 + endloop + endfacet + facet normal 0.284313 -0.111672 0.952206 + outer loop + vertex 1.64238 1.26828 2.52803 + vertex 1.64267 1.27357 2.52856 + vertex 1.63764 1.26903 2.52953 + endloop + endfacet + facet normal 0.279925 -0.106408 0.954106 + outer loop + vertex 1.63764 1.26903 2.52953 + vertex 1.64267 1.27357 2.52856 + vertex 1.63868 1.27461 2.52985 + endloop + endfacet + facet normal 0.279482 -0.108045 0.954052 + outer loop + vertex 1.64267 1.27357 2.52856 + vertex 1.64292 1.2787 2.52907 + vertex 1.63868 1.27461 2.52985 + endloop + endfacet + facet normal 0.271767 -0.107882 0.956297 + outer loop + vertex 1.64267 1.27357 2.52856 + vertex 1.64718 1.27807 2.52779 + vertex 1.64292 1.2787 2.52907 + endloop + endfacet + facet normal 0.272021 -0.106359 0.956395 + outer loop + vertex 1.64718 1.27807 2.52779 + vertex 1.64743 1.28321 2.52829 + vertex 1.64292 1.2787 2.52907 + endloop + endfacet + facet normal 0.271657 -0.105969 0.956542 + outer loop + vertex 1.64292 1.2787 2.52907 + vertex 1.64743 1.28321 2.52829 + vertex 1.64273 1.28388 2.5297 + endloop + endfacet + facet normal 0.276627 -0.105621 0.955155 + outer loop + vertex 1.64273 1.28388 2.5297 + vertex 1.63908 1.27918 2.53023 + vertex 1.64292 1.2787 2.52907 + endloop + endfacet + facet normal 0.27789 -0.106483 0.954693 + outer loop + vertex 1.64718 1.27807 2.52779 + vertex 1.6515 1.28239 2.52701 + vertex 1.64743 1.28321 2.52829 + endloop + endfacet + facet normal 0.279758 -0.0978127 0.955075 + outer loop + vertex 1.6515 1.28239 2.52701 + vertex 1.65248 1.28801 2.5273 + vertex 1.64743 1.28321 2.52829 + endloop + endfacet + facet normal 0.283496 -0.102059 0.953527 + outer loop + vertex 1.64743 1.28321 2.52829 + vertex 1.65248 1.28801 2.5273 + vertex 1.64777 1.28852 2.52876 + endloop + endfacet + facet normal 0.312979 -0.103012 0.944157 + outer loop + vertex 1.65248 1.28801 2.5273 + vertex 1.6515 1.28239 2.52701 + vertex 1.65557 1.28591 2.52605 + endloop + endfacet + facet normal 0.317202 -0.0963655 0.943449 + outer loop + vertex 1.65645 1.28978 2.52615 + vertex 1.65248 1.28801 2.5273 + vertex 1.65557 1.28591 2.52605 + endloop + endfacet + facet normal 0.403915 -0.115253 0.907507 + outer loop + vertex 1.65893 1.28911 2.52496 + vertex 1.65645 1.28978 2.52615 + vertex 1.65557 1.28591 2.52605 + endloop + endfacet + facet normal 0.391682 -0.0999248 0.914658 + outer loop + vertex 1.65848 1.28447 2.52464 + vertex 1.65893 1.28911 2.52496 + vertex 1.65557 1.28591 2.52605 + endloop + endfacet + facet normal 0.385925 -0.112551 0.915639 + outer loop + vertex 1.65478 1.28123 2.5258 + vertex 1.65848 1.28447 2.52464 + vertex 1.65557 1.28591 2.52605 + endloop + endfacet + facet normal 0.378064 -0.101966 0.920147 + outer loop + vertex 1.65743 1.27888 2.52445 + vertex 1.65848 1.28447 2.52464 + vertex 1.65478 1.28123 2.5258 + endloop + endfacet + facet normal 0.368033 -0.114737 0.922707 + outer loop + vertex 1.65386 1.27742 2.5257 + vertex 1.65743 1.27888 2.52445 + vertex 1.65478 1.28123 2.5258 + endloop + endfacet + facet normal 0.303191 -0.0997511 0.947695 + outer loop + vertex 1.65478 1.28123 2.5258 + vertex 1.6511 1.27782 2.52662 + vertex 1.65386 1.27742 2.5257 + endloop + endfacet + facet normal 0.301594 -0.109355 0.947145 + outer loop + vertex 1.65386 1.27742 2.5257 + vertex 1.6511 1.27782 2.52662 + vertex 1.65141 1.27468 2.52616 + endloop + endfacet + facet normal 0.314448 -0.121869 0.941419 + outer loop + vertex 1.65386 1.27742 2.5257 + vertex 1.65141 1.27468 2.52616 + vertex 1.65397 1.27408 2.52523 + endloop + endfacet + facet normal 0.312813 -0.128379 0.941099 + outer loop + vertex 1.65397 1.27408 2.52523 + vertex 1.65141 1.27468 2.52616 + vertex 1.65025 1.27091 2.52603 + endloop + endfacet + facet normal 0.302911 -0.115538 0.94599 + outer loop + vertex 1.65293 1.2688 2.52492 + vertex 1.65397 1.27408 2.52523 + vertex 1.65025 1.27091 2.52603 + endloop + endfacet + facet normal 0.297641 -0.122631 0.946769 + outer loop + vertex 1.64912 1.26716 2.5259 + vertex 1.65293 1.2688 2.52492 + vertex 1.65025 1.27091 2.52603 + endloop + endfacet + facet normal 0.281223 -0.117877 0.952375 + outer loop + vertex 1.65025 1.27091 2.52603 + vertex 1.64638 1.26776 2.52678 + vertex 1.64912 1.26716 2.5259 + endloop + endfacet + facet normal 0.281398 -0.117131 0.952416 + outer loop + vertex 1.64912 1.26716 2.5259 + vertex 1.64638 1.26776 2.52678 + vertex 1.64659 1.26447 2.52632 + endloop + endfacet + facet normal 0.279776 -0.1155 0.953092 + outer loop + vertex 1.64912 1.26716 2.5259 + vertex 1.64659 1.26447 2.52632 + vertex 1.64936 1.26401 2.52545 + endloop + endfacet + facet normal 0.28001 -0.114257 0.953174 + outer loop + vertex 1.64936 1.26401 2.52545 + vertex 1.64659 1.26447 2.52632 + vertex 1.64558 1.2607 2.52616 + endloop + endfacet + facet normal 0.278383 -0.112246 0.953889 + outer loop + vertex 1.64887 1.25946 2.52506 + vertex 1.64936 1.26401 2.52545 + vertex 1.64558 1.2607 2.52616 + endloop + endfacet + facet normal 0.277916 -0.113483 0.953879 + outer loop + vertex 1.64473 1.25611 2.52586 + vertex 1.64887 1.25946 2.52506 + vertex 1.64558 1.2607 2.52616 + endloop + endfacet + facet normal 0.283689 -0.114426 0.952065 + outer loop + vertex 1.64558 1.2607 2.52616 + vertex 1.6414 1.25732 2.527 + vertex 1.64473 1.25611 2.52586 + endloop + endfacet + facet normal 0.283511 -0.114912 0.952059 + outer loop + vertex 1.6414 1.25732 2.527 + vertex 1.64096 1.2528 2.52659 + vertex 1.64473 1.25611 2.52586 + endloop + endfacet + facet normal 0.284192 -0.115756 0.951754 + outer loop + vertex 1.64473 1.25611 2.52586 + vertex 1.64096 1.2528 2.52659 + vertex 1.64375 1.25234 2.5257 + endloop + endfacet + facet normal 0.277182 -0.114028 0.954027 + outer loop + vertex 1.64375 1.25234 2.5257 + vertex 1.64774 1.25389 2.52472 + vertex 1.64473 1.25611 2.52586 + endloop + endfacet + facet normal 0.277473 -0.114898 0.953838 + outer loop + vertex 1.64375 1.25234 2.5257 + vertex 1.64394 1.24902 2.52524 + vertex 1.64774 1.25389 2.52472 + endloop + endfacet + facet normal 0.277869 -0.115224 0.953684 + outer loop + vertex 1.64774 1.25389 2.52472 + vertex 1.64394 1.24902 2.52524 + vertex 1.64776 1.24852 2.52407 + endloop + endfacet + facet normal 0.277679 -0.115232 0.953738 + outer loop + vertex 1.64776 1.24852 2.52407 + vertex 1.65237 1.25327 2.5233 + vertex 1.64774 1.25389 2.52472 + endloop + endfacet + facet normal 0.278458 -0.110248 0.9541 + outer loop + vertex 1.65237 1.25327 2.5233 + vertex 1.65276 1.25859 2.5238 + vertex 1.64774 1.25389 2.52472 + endloop + endfacet + facet normal 0.281685 -0.113964 0.952715 + outer loop + vertex 1.64774 1.25389 2.52472 + vertex 1.65276 1.25859 2.5238 + vertex 1.64887 1.25946 2.52506 + endloop + endfacet + facet normal 0.283158 -0.107823 0.952993 + outer loop + vertex 1.65276 1.25859 2.5238 + vertex 1.65303 1.2637 2.5243 + vertex 1.64887 1.25946 2.52506 + endloop + endfacet + facet normal 0.311481 -0.108451 0.944043 + outer loop + vertex 1.65276 1.25859 2.5238 + vertex 1.65704 1.26326 2.52293 + vertex 1.65303 1.2637 2.5243 + endloop + endfacet + facet normal 0.313455 -0.0935104 0.944988 + outer loop + vertex 1.65704 1.26326 2.52293 + vertex 1.65709 1.26827 2.52341 + vertex 1.65303 1.2637 2.5243 + endloop + endfacet + facet normal 0.327191 -0.106909 0.938891 + outer loop + vertex 1.65303 1.2637 2.5243 + vertex 1.65709 1.26827 2.52341 + vertex 1.65293 1.2688 2.52492 + endloop + endfacet + facet normal 0.288511 -0.109164 0.951233 + outer loop + vertex 1.65293 1.2688 2.52492 + vertex 1.64936 1.26401 2.52545 + vertex 1.65303 1.2637 2.5243 + endloop + endfacet + facet normal 0.328547 -0.0977525 0.939415 + outer loop + vertex 1.65709 1.26827 2.52341 + vertex 1.65735 1.27347 2.52386 + vertex 1.65293 1.2688 2.52492 + endloop + endfacet + facet normal 0.302479 -0.099465 0.947952 + outer loop + vertex 1.65738 1.25816 2.52228 + vertex 1.65704 1.26326 2.52293 + vertex 1.65276 1.25859 2.5238 + endloop + endfacet + facet normal 0.301097 -0.11122 0.947085 + outer loop + vertex 1.65237 1.25327 2.5233 + vertex 1.65738 1.25816 2.52228 + vertex 1.65276 1.25859 2.5238 + endloop + endfacet + facet normal 0.294262 -0.103599 0.950093 + outer loop + vertex 1.6564 1.25253 2.52197 + vertex 1.65738 1.25816 2.52228 + vertex 1.65237 1.25327 2.5233 + endloop + endfacet + facet normal 0.291938 -0.115123 0.949483 + outer loop + vertex 1.65208 1.24809 2.52276 + vertex 1.6564 1.25253 2.52197 + vertex 1.65237 1.25327 2.5233 + endloop + endfacet + facet normal 0.287086 -0.110025 0.951565 + outer loop + vertex 1.65598 1.24796 2.52157 + vertex 1.6564 1.25253 2.52197 + vertex 1.65208 1.24809 2.52276 + endloop + endfacet + facet normal 0.286454 -0.11982 0.950572 + outer loop + vertex 1.65598 1.24796 2.52157 + vertex 1.65208 1.24809 2.52276 + vertex 1.65227 1.24307 2.52207 + endloop + endfacet + facet normal 0.285959 -0.119423 0.950771 + outer loop + vertex 1.65629 1.24484 2.52109 + vertex 1.65598 1.24796 2.52157 + vertex 1.65227 1.24307 2.52207 + endloop + endfacet + facet normal 0.288057 -0.124913 0.949431 + outer loop + vertex 1.65629 1.24484 2.52109 + vertex 1.65227 1.24307 2.52207 + vertex 1.65516 1.2411 2.52094 + endloop + endfacet + facet normal 0.334451 -0.138152 0.932232 + outer loop + vertex 1.65889 1.24425 2.52007 + vertex 1.65629 1.24484 2.52109 + vertex 1.65516 1.2411 2.52094 + endloop + endfacet + facet normal 0.323278 -0.123254 0.938243 + outer loop + vertex 1.65792 1.23891 2.5197 + vertex 1.65889 1.24425 2.52007 + vertex 1.65516 1.2411 2.52094 + endloop + endfacet + facet normal 0.315533 -0.133682 0.939451 + outer loop + vertex 1.654 1.23737 2.5208 + vertex 1.65792 1.23891 2.5197 + vertex 1.65516 1.2411 2.52094 + endloop + endfacet + facet normal 0.284211 -0.124378 0.95066 + outer loop + vertex 1.65516 1.2411 2.52094 + vertex 1.65128 1.23793 2.52168 + vertex 1.654 1.23737 2.5208 + endloop + endfacet + facet normal 0.283328 -0.128268 0.950407 + outer loop + vertex 1.654 1.23737 2.5208 + vertex 1.65128 1.23793 2.52168 + vertex 1.65141 1.2347 2.52121 + endloop + endfacet + facet normal 0.286333 -0.131391 0.949078 + outer loop + vertex 1.654 1.23737 2.5208 + vertex 1.65141 1.2347 2.52121 + vertex 1.65408 1.23406 2.52031 + endloop + endfacet + facet normal 0.285645 -0.134028 0.948917 + outer loop + vertex 1.65408 1.23406 2.52031 + vertex 1.65141 1.2347 2.52121 + vertex 1.65021 1.23098 2.52104 + endloop + endfacet + facet normal 0.282186 -0.129284 0.950608 + outer loop + vertex 1.65294 1.22879 2.51993 + vertex 1.65408 1.23406 2.52031 + vertex 1.65021 1.23098 2.52104 + endloop + endfacet + facet normal 0.279181 -0.133196 0.950956 + outer loop + vertex 1.64903 1.22728 2.52087 + vertex 1.65294 1.22879 2.51993 + vertex 1.65021 1.23098 2.52104 + endloop + endfacet + facet normal 0.278454 -0.132976 0.9512 + outer loop + vertex 1.65021 1.23098 2.52104 + vertex 1.64632 1.22789 2.52175 + vertex 1.64903 1.22728 2.52087 + endloop + endfacet + facet normal 0.278262 -0.133752 0.951147 + outer loop + vertex 1.64903 1.22728 2.52087 + vertex 1.64632 1.22789 2.52175 + vertex 1.64646 1.22463 2.52125 + endloop + endfacet + facet normal 0.277982 -0.133461 0.95127 + outer loop + vertex 1.64903 1.22728 2.52087 + vertex 1.64646 1.22463 2.52125 + vertex 1.64911 1.22399 2.52039 + endloop + endfacet + facet normal 0.277838 -0.13401 0.951235 + outer loop + vertex 1.64911 1.22399 2.52039 + vertex 1.64646 1.22463 2.52125 + vertex 1.64526 1.22091 2.52108 + endloop + endfacet + facet normal 0.28008 -0.137051 0.950143 + outer loop + vertex 1.64799 1.21875 2.51996 + vertex 1.64911 1.22399 2.52039 + vertex 1.64526 1.22091 2.52108 + endloop + endfacet + facet normal 0.280055 -0.137084 0.950146 + outer loop + vertex 1.64407 1.21719 2.52089 + vertex 1.64799 1.21875 2.51996 + vertex 1.64526 1.22091 2.52108 + endloop + endfacet + facet normal 0.283692 -0.138187 0.948906 + outer loop + vertex 1.64526 1.22091 2.52108 + vertex 1.64139 1.21783 2.52179 + vertex 1.64407 1.21719 2.52089 + endloop + endfacet + facet normal 0.283329 -0.139587 0.94881 + outer loop + vertex 1.64407 1.21719 2.52089 + vertex 1.64139 1.21783 2.52179 + vertex 1.64149 1.21457 2.52127 + endloop + endfacet + facet normal 0.285592 -0.141963 0.947778 + outer loop + vertex 1.64407 1.21719 2.52089 + vertex 1.64149 1.21457 2.52127 + vertex 1.64413 1.21392 2.52039 + endloop + endfacet + facet normal 0.285072 -0.143895 0.947643 + outer loop + vertex 1.64413 1.21392 2.52039 + vertex 1.64149 1.21457 2.52127 + vertex 1.64028 1.21089 2.52108 + endloop + endfacet + facet normal 0.286719 -0.146175 0.946797 + outer loop + vertex 1.64298 1.20874 2.51993 + vertex 1.64413 1.21392 2.52039 + vertex 1.64028 1.21089 2.52108 + endloop + endfacet + facet normal 0.286609 -0.146319 0.946808 + outer loop + vertex 1.63908 1.20722 2.52088 + vertex 1.64298 1.20874 2.51993 + vertex 1.64028 1.21089 2.52108 + endloop + endfacet + facet normal 0.28514 -0.145865 0.947322 + outer loop + vertex 1.64028 1.21089 2.52108 + vertex 1.6364 1.20788 2.52179 + vertex 1.63908 1.20722 2.52088 + endloop + endfacet + facet normal 0.284672 -0.147592 0.947195 + outer loop + vertex 1.63908 1.20722 2.52088 + vertex 1.6364 1.20788 2.52179 + vertex 1.6365 1.20464 2.52125 + endloop + endfacet + facet normal 0.287062 -0.150146 0.946072 + outer loop + vertex 1.63908 1.20722 2.52088 + vertex 1.6365 1.20464 2.52125 + vertex 1.63911 1.20398 2.52035 + endloop + endfacet + facet normal 0.28643 -0.152412 0.945901 + outer loop + vertex 1.63911 1.20398 2.52035 + vertex 1.6365 1.20464 2.52125 + vertex 1.63526 1.20098 2.52104 + endloop + endfacet + facet normal 0.286797 -0.152928 0.945706 + outer loop + vertex 1.63795 1.19885 2.51988 + vertex 1.63911 1.20398 2.52035 + vertex 1.63526 1.20098 2.52104 + endloop + endfacet + facet normal 0.28597 -0.154009 0.945781 + outer loop + vertex 1.63403 1.19734 2.52082 + vertex 1.63795 1.19885 2.51988 + vertex 1.63526 1.20098 2.52104 + endloop + endfacet + facet normal 0.281642 -0.152637 0.947301 + outer loop + vertex 1.63526 1.20098 2.52104 + vertex 1.63135 1.19796 2.52171 + vertex 1.63403 1.19734 2.52082 + endloop + endfacet + facet normal 0.281136 -0.154592 0.947135 + outer loop + vertex 1.63403 1.19734 2.52082 + vertex 1.63135 1.19796 2.52171 + vertex 1.63142 1.19476 2.52117 + endloop + endfacet + facet normal 0.282868 -0.156453 0.946313 + outer loop + vertex 1.63403 1.19734 2.52082 + vertex 1.63142 1.19476 2.52117 + vertex 1.63404 1.19411 2.52028 + endloop + endfacet + facet normal 0.282753 -0.156869 0.946278 + outer loop + vertex 1.63404 1.19411 2.52028 + vertex 1.63142 1.19476 2.52117 + vertex 1.63015 1.1911 2.52094 + endloop + endfacet + facet normal 0.280683 -0.153956 0.947372 + outer loop + vertex 1.63287 1.18896 2.51979 + vertex 1.63404 1.19411 2.52028 + vertex 1.63015 1.1911 2.52094 + endloop + endfacet + facet normal 0.281181 -0.1533 0.947331 + outer loop + vertex 1.62891 1.18744 2.52072 + vertex 1.63287 1.18896 2.51979 + vertex 1.63015 1.1911 2.52094 + endloop + endfacet + facet normal 0.281302 -0.153339 0.947289 + outer loop + vertex 1.63015 1.1911 2.52094 + vertex 1.62623 1.18801 2.52161 + vertex 1.62891 1.18744 2.52072 + endloop + endfacet + facet normal 0.282478 -0.148468 0.947715 + outer loop + vertex 1.62891 1.18744 2.52072 + vertex 1.62623 1.18801 2.52161 + vertex 1.62631 1.1848 2.52108 + endloop + endfacet + facet normal 0.279307 -0.145136 0.94917 + outer loop + vertex 1.62891 1.18744 2.52072 + vertex 1.62631 1.1848 2.52108 + vertex 1.62896 1.18417 2.5202 + endloop + endfacet + facet normal 0.280968 -0.138841 0.949621 + outer loop + vertex 1.62896 1.18417 2.5202 + vertex 1.62631 1.1848 2.52108 + vertex 1.62509 1.18107 2.5209 + endloop + endfacet + facet normal 0.278587 -0.135603 0.95079 + outer loop + vertex 1.62783 1.17892 2.51978 + vertex 1.62896 1.18417 2.5202 + vertex 1.62509 1.18107 2.5209 + endloop + endfacet + facet normal 0.281718 -0.131434 0.950452 + outer loop + vertex 1.62389 1.17733 2.52073 + vertex 1.62783 1.17892 2.51978 + vertex 1.62509 1.18107 2.5209 + endloop + endfacet + facet normal 0.280582 -0.131087 0.950836 + outer loop + vertex 1.62509 1.18107 2.5209 + vertex 1.62122 1.17795 2.52161 + vertex 1.62389 1.17733 2.52073 + endloop + endfacet + facet normal 0.283514 -0.135044 0.949412 + outer loop + vertex 1.62228 1.18313 2.52203 + vertex 1.62122 1.17795 2.52161 + vertex 1.62509 1.18107 2.5209 + endloop + endfacet + facet normal 0.278506 -0.134146 0.95102 + outer loop + vertex 1.62122 1.17795 2.52161 + vertex 1.62228 1.18313 2.52203 + vertex 1.61733 1.17833 2.5228 + endloop + endfacet + facet normal 0.279859 -0.123661 0.952044 + outer loop + vertex 1.62122 1.17795 2.52161 + vertex 1.61733 1.17833 2.5228 + vertex 1.61737 1.17314 2.52211 + endloop + endfacet + facet normal 0.282576 -0.125957 0.950939 + outer loop + vertex 1.62133 1.17468 2.52114 + vertex 1.62122 1.17795 2.52161 + vertex 1.61737 1.17314 2.52211 + endloop + endfacet + facet normal 0.280838 -0.120724 0.952132 + outer loop + vertex 1.62133 1.17468 2.52114 + vertex 1.61737 1.17314 2.52211 + vertex 1.62017 1.17097 2.52101 + endloop + endfacet + facet normal 0.280834 -0.120723 0.952134 + outer loop + vertex 1.62398 1.17404 2.52028 + vertex 1.62133 1.17468 2.52114 + vertex 1.62017 1.17097 2.52101 + endloop + endfacet + facet normal 0.280422 -0.120165 0.952326 + outer loop + vertex 1.62297 1.16886 2.51992 + vertex 1.62398 1.17404 2.52028 + vertex 1.62017 1.17097 2.52101 + endloop + endfacet + facet normal 0.281323 -0.118915 0.952217 + outer loop + vertex 1.61907 1.16731 2.52088 + vertex 1.62297 1.16886 2.51992 + vertex 1.62017 1.17097 2.52101 + endloop + endfacet + facet normal 0.282997 -0.119397 0.95166 + outer loop + vertex 1.62017 1.17097 2.52101 + vertex 1.61638 1.16796 2.52176 + vertex 1.61907 1.16731 2.52088 + endloop + endfacet + facet normal 0.283181 -0.118679 0.951695 + outer loop + vertex 1.61907 1.16731 2.52088 + vertex 1.61638 1.16796 2.52176 + vertex 1.6166 1.16472 2.52129 + endloop + endfacet + facet normal 0.284837 -0.120373 0.950988 + outer loop + vertex 1.61907 1.16731 2.52088 + vertex 1.6166 1.16472 2.52129 + vertex 1.61934 1.16419 2.52041 + endloop + endfacet + facet normal 0.28241 -0.11859 0.951935 + outer loop + vertex 1.61737 1.17314 2.52211 + vertex 1.61638 1.16796 2.52176 + vertex 1.62017 1.17097 2.52101 + endloop + endfacet + facet normal 0.287707 -0.119487 0.950235 + outer loop + vertex 1.61638 1.16796 2.52176 + vertex 1.61737 1.17314 2.52211 + vertex 1.61245 1.1685 2.52302 + endloop + endfacet + facet normal 0.288073 -0.117228 0.950406 + outer loop + vertex 1.61638 1.16796 2.52176 + vertex 1.61245 1.1685 2.52302 + vertex 1.61259 1.16317 2.52232 + endloop + endfacet + facet normal 0.289037 -0.118036 0.950013 + outer loop + vertex 1.6166 1.16472 2.52129 + vertex 1.61638 1.16796 2.52176 + vertex 1.61259 1.16317 2.52232 + endloop + endfacet + facet normal 0.291341 -0.125072 0.948408 + outer loop + vertex 1.6166 1.16472 2.52129 + vertex 1.61259 1.16317 2.52232 + vertex 1.61561 1.16099 2.52111 + endloop + endfacet + facet normal 0.284207 -0.123294 0.950802 + outer loop + vertex 1.61934 1.16419 2.52041 + vertex 1.6166 1.16472 2.52129 + vertex 1.61561 1.16099 2.52111 + endloop + endfacet + facet normal 0.289554 -0.130087 0.948281 + outer loop + vertex 1.61883 1.15966 2.51994 + vertex 1.61934 1.16419 2.52041 + vertex 1.61561 1.16099 2.52111 + endloop + endfacet + facet normal 0.287269 -0.135578 0.948206 + outer loop + vertex 1.61469 1.15643 2.52073 + vertex 1.61883 1.15966 2.51994 + vertex 1.61561 1.16099 2.52111 + endloop + endfacet + facet normal 0.297586 -0.13737 0.94476 + outer loop + vertex 1.61561 1.16099 2.52111 + vertex 1.61147 1.15767 2.52193 + vertex 1.61469 1.15643 2.52073 + endloop + endfacet + facet normal 0.281695 -0.129467 0.950729 + outer loop + vertex 1.61883 1.15966 2.51994 + vertex 1.62311 1.16379 2.51923 + vertex 1.61934 1.16419 2.52041 + endloop + endfacet + facet normal 0.282768 -0.121415 0.951473 + outer loop + vertex 1.62297 1.16886 2.51992 + vertex 1.61934 1.16419 2.52041 + vertex 1.62311 1.16379 2.51923 + endloop + endfacet + facet normal 0.281457 -0.121503 0.95185 + outer loop + vertex 1.62311 1.16379 2.51923 + vertex 1.62759 1.16847 2.51851 + vertex 1.62297 1.16886 2.51992 + endloop + endfacet + facet normal 0.281711 -0.119272 0.952057 + outer loop + vertex 1.62759 1.16847 2.51851 + vertex 1.6278 1.17365 2.51909 + vertex 1.62297 1.16886 2.51992 + endloop + endfacet + facet normal 0.285821 -0.1193 0.950828 + outer loop + vertex 1.62759 1.16847 2.51851 + vertex 1.6322 1.17338 2.51774 + vertex 1.6278 1.17365 2.51909 + endloop + endfacet + facet normal 0.285229 -0.12567 0.950185 + outer loop + vertex 1.6322 1.17338 2.51774 + vertex 1.63246 1.17856 2.51834 + vertex 1.6278 1.17365 2.51909 + endloop + endfacet + facet normal 0.286002 -0.126454 0.949849 + outer loop + vertex 1.6278 1.17365 2.51909 + vertex 1.63246 1.17856 2.51834 + vertex 1.62783 1.17892 2.51978 + endloop + endfacet + facet normal 0.282157 -0.12658 0.950981 + outer loop + vertex 1.62783 1.17892 2.51978 + vertex 1.62398 1.17404 2.52028 + vertex 1.6278 1.17365 2.51909 + endloop + endfacet + facet normal 0.279197 -0.12412 0.952178 + outer loop + vertex 1.62389 1.17733 2.52073 + vertex 1.62398 1.17404 2.52028 + vertex 1.62783 1.17892 2.51978 + endloop + endfacet + facet normal 0.291435 -0.125759 0.948288 + outer loop + vertex 1.6322 1.17338 2.51774 + vertex 1.6371 1.17836 2.51689 + vertex 1.63246 1.17856 2.51834 + endloop + endfacet + facet normal 0.28864 -0.122794 0.949531 + outer loop + vertex 1.63607 1.17318 2.51654 + vertex 1.6371 1.17836 2.51689 + vertex 1.6322 1.17338 2.51774 + endloop + endfacet + facet normal 0.289262 -0.115237 0.950288 + outer loop + vertex 1.63607 1.17318 2.51654 + vertex 1.6322 1.17338 2.51774 + vertex 1.63228 1.16818 2.51708 + endloop + endfacet + facet normal 0.285258 -0.112023 0.951882 + outer loop + vertex 1.63623 1.16992 2.5161 + vertex 1.63607 1.17318 2.51654 + vertex 1.63228 1.16818 2.51708 + endloop + endfacet + facet normal 0.284641 -0.110404 0.952256 + outer loop + vertex 1.63623 1.16992 2.5161 + vertex 1.63228 1.16818 2.51708 + vertex 1.63512 1.16612 2.51599 + endloop + endfacet + facet normal 0.29077 -0.112124 0.950201 + outer loop + vertex 1.63891 1.16926 2.5152 + vertex 1.63623 1.16992 2.5161 + vertex 1.63512 1.16612 2.51599 + endloop + endfacet + facet normal 0.295837 -0.118831 0.947818 + outer loop + vertex 1.63791 1.16393 2.51485 + vertex 1.63891 1.16926 2.5152 + vertex 1.63512 1.16612 2.51599 + endloop + endfacet + facet normal 0.294429 -0.120728 0.948017 + outer loop + vertex 1.63401 1.16236 2.51586 + vertex 1.63791 1.16393 2.51485 + vertex 1.63512 1.16612 2.51599 + endloop + endfacet + facet normal 0.282053 -0.117213 0.952212 + outer loop + vertex 1.63512 1.16612 2.51599 + vertex 1.63131 1.16296 2.51673 + vertex 1.63401 1.16236 2.51586 + endloop + endfacet + facet normal 0.279491 -0.127903 0.951591 + outer loop + vertex 1.63401 1.16236 2.51586 + vertex 1.63131 1.16296 2.51673 + vertex 1.63146 1.15971 2.51625 + endloop + endfacet + facet normal 0.291231 -0.139978 0.946357 + outer loop + vertex 1.63401 1.16236 2.51586 + vertex 1.63146 1.15971 2.51625 + vertex 1.63411 1.1591 2.51535 + endloop + endfacet + facet normal 0.288123 -0.15208 0.94544 + outer loop + vertex 1.63411 1.1591 2.51535 + vertex 1.63146 1.15971 2.51625 + vertex 1.63026 1.15605 2.51603 + endloop + endfacet + facet normal 0.276697 -0.148557 0.949405 + outer loop + vertex 1.63146 1.15971 2.51625 + vertex 1.62744 1.15815 2.51718 + vertex 1.63026 1.15605 2.51603 + endloop + endfacet + facet normal 0.270093 -0.128723 0.954191 + outer loop + vertex 1.63146 1.15971 2.51625 + vertex 1.63131 1.16296 2.51673 + vertex 1.62744 1.15815 2.51718 + endloop + endfacet + facet normal 0.274711 -0.132612 0.952338 + outer loop + vertex 1.63131 1.16296 2.51673 + vertex 1.62741 1.16332 2.51791 + vertex 1.62744 1.15815 2.51718 + endloop + endfacet + facet normal 0.278738 -0.132424 0.951193 + outer loop + vertex 1.62744 1.15815 2.51718 + vertex 1.62741 1.16332 2.51791 + vertex 1.62278 1.15869 2.51862 + endloop + endfacet + facet normal 0.276218 -0.149432 0.949407 + outer loop + vertex 1.62237 1.15347 2.51792 + vertex 1.62744 1.15815 2.51718 + vertex 1.62278 1.15869 2.51862 + endloop + endfacet + facet normal 0.285157 -0.149765 0.946708 + outer loop + vertex 1.62237 1.15347 2.51792 + vertex 1.62278 1.15869 2.51862 + vertex 1.61757 1.15405 2.51946 + endloop + endfacet + facet normal 0.283195 -0.162173 0.945252 + outer loop + vertex 1.61764 1.14867 2.51851 + vertex 1.62237 1.15347 2.51792 + vertex 1.61757 1.15405 2.51946 + endloop + endfacet + facet normal 0.292978 -0.161533 0.942375 + outer loop + vertex 1.61757 1.15405 2.51946 + vertex 1.61308 1.14879 2.51995 + vertex 1.61764 1.14867 2.51851 + endloop + endfacet + facet normal 0.297004 -0.165143 0.940487 + outer loop + vertex 1.61348 1.15263 2.5205 + vertex 1.61308 1.14879 2.51995 + vertex 1.61757 1.15405 2.51946 + endloop + endfacet + facet normal 0.29312 -0.151342 0.944021 + outer loop + vertex 1.61348 1.15263 2.5205 + vertex 1.61757 1.15405 2.51946 + vertex 1.61469 1.15643 2.52073 + endloop + endfacet + facet normal 0.299978 -0.153367 0.941537 + outer loop + vertex 1.61469 1.15643 2.52073 + vertex 1.6109 1.15329 2.52143 + vertex 1.61348 1.15263 2.5205 + endloop + endfacet + facet normal 0.29782 -0.161015 0.940945 + outer loop + vertex 1.61348 1.15263 2.5205 + vertex 1.6109 1.15329 2.52143 + vertex 1.61091 1.15029 2.52091 + endloop + endfacet + facet normal 0.292099 -0.161333 0.942682 + outer loop + vertex 1.61091 1.15029 2.52091 + vertex 1.6109 1.15329 2.52143 + vertex 1.60725 1.14881 2.52179 + endloop + endfacet + facet normal 0.29343 -0.165255 0.941589 + outer loop + vertex 1.61091 1.15029 2.52091 + vertex 1.60725 1.14881 2.52179 + vertex 1.60951 1.14751 2.52086 + endloop + endfacet + facet normal 0.299537 -0.168291 0.939125 + outer loop + vertex 1.61308 1.14879 2.51995 + vertex 1.61091 1.15029 2.52091 + vertex 1.60951 1.14751 2.52086 + endloop + endfacet + facet normal 0.300322 -0.171028 0.938379 + outer loop + vertex 1.60951 1.14751 2.52086 + vertex 1.60925 1.14422 2.52034 + vertex 1.61308 1.14879 2.51995 + endloop + endfacet + facet normal 0.298259 -0.169213 0.939366 + outer loop + vertex 1.61308 1.14879 2.51995 + vertex 1.60925 1.14422 2.52034 + vertex 1.61298 1.14381 2.51908 + endloop + endfacet + facet normal 0.292406 -0.169411 0.941169 + outer loop + vertex 1.61298 1.14381 2.51908 + vertex 1.61764 1.14867 2.51851 + vertex 1.61308 1.14879 2.51995 + endloop + endfacet + facet normal 0.292954 -0.169967 0.940898 + outer loop + vertex 1.61737 1.1436 2.51768 + vertex 1.61764 1.14867 2.51851 + vertex 1.61298 1.14381 2.51908 + endloop + endfacet + facet normal 0.292654 -0.173112 0.940418 + outer loop + vertex 1.61265 1.13864 2.51823 + vertex 1.61737 1.1436 2.51768 + vertex 1.61298 1.14381 2.51908 + endloop + endfacet + facet normal 0.296821 -0.17316 0.939102 + outer loop + vertex 1.61265 1.13864 2.51823 + vertex 1.61298 1.14381 2.51908 + vertex 1.60778 1.13879 2.5198 + endloop + endfacet + facet normal 0.295861 -0.184689 0.937207 + outer loop + vertex 1.60768 1.13339 2.51877 + vertex 1.61265 1.13864 2.51823 + vertex 1.60778 1.13879 2.5198 + endloop + endfacet + facet normal 0.280843 -0.185289 0.941698 + outer loop + vertex 1.60778 1.13879 2.5198 + vertex 1.60285 1.13315 2.52016 + vertex 1.60768 1.13339 2.51877 + endloop + endfacet + facet normal 0.280499 -0.216107 0.93521 + outer loop + vertex 1.60268 1.12818 2.51907 + vertex 1.60768 1.13339 2.51877 + vertex 1.60285 1.13315 2.52016 + endloop + endfacet + facet normal 0.208493 -0.217686 0.95349 + outer loop + vertex 1.60285 1.13315 2.52016 + vertex 1.59789 1.12828 2.52013 + vertex 1.60268 1.12818 2.51907 + endloop + endfacet + facet normal 0.206863 -0.240909 0.948246 + outer loop + vertex 1.59768 1.12324 2.5189 + vertex 1.60268 1.12818 2.51907 + vertex 1.59789 1.12828 2.52013 + endloop + endfacet + facet normal 0.166429 -0.200518 0.96545 + outer loop + vertex 1.60267 1.12323 2.51804 + vertex 1.60268 1.12818 2.51907 + vertex 1.59768 1.12324 2.5189 + endloop + endfacet + facet normal 0.166659 -0.194289 0.966683 + outer loop + vertex 1.59821 1.11838 2.51783 + vertex 1.60267 1.12323 2.51804 + vertex 1.59768 1.12324 2.5189 + endloop + endfacet + facet normal 0.251866 -0.197091 0.94748 + outer loop + vertex 1.60267 1.12323 2.51804 + vertex 1.60738 1.1283 2.51784 + vertex 1.60268 1.12818 2.51907 + endloop + endfacet + facet normal 0.235674 -0.181737 0.954688 + outer loop + vertex 1.60737 1.12354 2.51694 + vertex 1.60738 1.1283 2.51784 + vertex 1.60267 1.12323 2.51804 + endloop + endfacet + facet normal 0.235421 -0.169942 0.95692 + outer loop + vertex 1.60737 1.12354 2.51694 + vertex 1.60267 1.12323 2.51804 + vertex 1.60297 1.11832 2.51709 + endloop + endfacet + facet normal 0.229452 -0.164844 0.959259 + outer loop + vertex 1.60687 1.11973 2.5164 + vertex 1.60737 1.12354 2.51694 + vertex 1.60297 1.11832 2.51709 + endloop + endfacet + facet normal 0.229045 -0.163566 0.959575 + outer loop + vertex 1.60687 1.11973 2.5164 + vertex 1.60297 1.11832 2.51709 + vertex 1.60535 1.11595 2.51612 + endloop + endfacet + facet normal 0.284622 -0.184542 0.94071 + outer loop + vertex 1.60926 1.1189 2.51552 + vertex 1.60687 1.11973 2.5164 + vertex 1.60535 1.11595 2.51612 + endloop + endfacet + facet normal 0.293058 -0.196778 0.935626 + outer loop + vertex 1.60775 1.1136 2.51488 + vertex 1.60926 1.1189 2.51552 + vertex 1.60535 1.11595 2.51612 + endloop + endfacet + facet normal 0.284523 -0.205891 0.936299 + outer loop + vertex 1.6037 1.11222 2.5158 + vertex 1.60775 1.1136 2.51488 + vertex 1.60535 1.11595 2.51612 + endloop + endfacet + facet normal 0.225541 -0.181605 0.957158 + outer loop + vertex 1.60535 1.11595 2.51612 + vertex 1.60165 1.11355 2.51654 + vertex 1.6037 1.11222 2.5158 + endloop + endfacet + facet normal 0.20704 -0.209158 0.955713 + outer loop + vertex 1.6037 1.11222 2.5158 + vertex 1.60165 1.11355 2.51654 + vertex 1.60102 1.11041 2.51599 + endloop + endfacet + facet normal 0.24534 -0.268229 0.931591 + outer loop + vertex 1.6037 1.11222 2.5158 + vertex 1.60102 1.11041 2.51599 + vertex 1.60269 1.10839 2.51497 + endloop + endfacet + facet normal 0.303773 -0.279172 0.910925 + outer loop + vertex 1.6037 1.11222 2.5158 + vertex 1.60269 1.10839 2.51497 + vertex 1.60775 1.1136 2.51488 + endloop + endfacet + facet normal 0.24212 -0.218724 0.945271 + outer loop + vertex 1.60775 1.1136 2.51488 + vertex 1.60269 1.10839 2.51497 + vertex 1.60766 1.10833 2.51368 + endloop + endfacet + facet normal 0.291825 -0.216484 0.931651 + outer loop + vertex 1.60766 1.10833 2.51368 + vertex 1.61264 1.1135 2.51332 + vertex 1.60775 1.1136 2.51488 + endloop + endfacet + facet normal 0.29385 -0.19211 0.936347 + outer loop + vertex 1.61264 1.1135 2.51332 + vertex 1.61299 1.11859 2.51425 + vertex 1.60775 1.1136 2.51488 + endloop + endfacet + facet normal 0.298105 -0.192159 0.934991 + outer loop + vertex 1.61264 1.1135 2.51332 + vertex 1.61742 1.11852 2.51283 + vertex 1.61299 1.11859 2.51425 + endloop + endfacet + facet normal 0.298557 -0.185945 0.936103 + outer loop + vertex 1.61742 1.11852 2.51283 + vertex 1.61776 1.12358 2.51372 + vertex 1.61299 1.11859 2.51425 + endloop + endfacet + facet normal 0.295809 -0.183172 0.937521 + outer loop + vertex 1.61299 1.11859 2.51425 + vertex 1.61776 1.12358 2.51372 + vertex 1.61315 1.12351 2.51516 + endloop + endfacet + facet normal 0.301468 -0.183031 0.935744 + outer loop + vertex 1.61315 1.12351 2.51516 + vertex 1.60926 1.1189 2.51552 + vertex 1.61299 1.11859 2.51425 + endloop + endfacet + facet normal 0.297677 -0.17969 0.937603 + outer loop + vertex 1.60953 1.12215 2.51605 + vertex 1.60926 1.1189 2.51552 + vertex 1.61315 1.12351 2.51516 + endloop + endfacet + facet normal 0.296959 -0.177337 0.938279 + outer loop + vertex 1.61315 1.12351 2.51516 + vertex 1.61102 1.12499 2.51612 + vertex 1.60953 1.12215 2.51605 + endloop + endfacet + facet normal 0.278792 -0.167982 0.945546 + outer loop + vertex 1.61102 1.12499 2.51612 + vertex 1.60737 1.12354 2.51694 + vertex 1.60953 1.12215 2.51605 + endloop + endfacet + facet normal 0.282998 -0.180605 0.941963 + outer loop + vertex 1.61102 1.12499 2.51612 + vertex 1.61125 1.12816 2.51666 + vertex 1.60737 1.12354 2.51694 + endloop + endfacet + facet normal 0.296025 -0.180881 0.937897 + outer loop + vertex 1.61372 1.12737 2.51573 + vertex 1.61125 1.12816 2.51666 + vertex 1.61102 1.12499 2.51612 + endloop + endfacet + facet normal 0.295221 -0.183184 0.937704 + outer loop + vertex 1.61526 1.13117 2.51598 + vertex 1.61125 1.12816 2.51666 + vertex 1.61372 1.12737 2.51573 + endloop + endfacet + facet normal 0.293224 -0.182421 0.938479 + outer loop + vertex 1.61372 1.12737 2.51573 + vertex 1.6178 1.12886 2.51474 + vertex 1.61526 1.13117 2.51598 + endloop + endfacet + facet normal 0.292822 -0.182883 0.938514 + outer loop + vertex 1.6178 1.12886 2.51474 + vertex 1.61923 1.13411 2.51532 + vertex 1.61526 1.13117 2.51598 + endloop + endfacet + facet normal 0.291692 -0.181206 0.939191 + outer loop + vertex 1.61923 1.13411 2.51532 + vertex 1.61681 1.13498 2.51624 + vertex 1.61526 1.13117 2.51598 + endloop + endfacet + facet normal 0.295047 -0.182482 0.937895 + outer loop + vertex 1.61681 1.13498 2.51624 + vertex 1.61265 1.13337 2.51723 + vertex 1.61526 1.13117 2.51598 + endloop + endfacet + facet normal 0.293954 -0.179038 0.938902 + outer loop + vertex 1.61681 1.13498 2.51624 + vertex 1.61732 1.13879 2.5168 + vertex 1.61265 1.13337 2.51723 + endloop + endfacet + facet normal 0.2937 -0.178809 0.939025 + outer loop + vertex 1.61732 1.13879 2.5168 + vertex 1.61265 1.13864 2.51823 + vertex 1.61265 1.13337 2.51723 + endloop + endfacet + facet normal 0.290341 -0.178733 0.940083 + outer loop + vertex 1.61948 1.13734 2.51586 + vertex 1.61732 1.13879 2.5168 + vertex 1.61681 1.13498 2.51624 + endloop + endfacet + facet normal 0.290116 -0.179072 0.940088 + outer loop + vertex 1.62093 1.14011 2.51594 + vertex 1.61732 1.13879 2.5168 + vertex 1.61948 1.13734 2.51586 + endloop + endfacet + facet normal 0.286222 -0.17709 0.941656 + outer loop + vertex 1.62306 1.13859 2.51501 + vertex 1.62093 1.14011 2.51594 + vertex 1.61948 1.13734 2.51586 + endloop + endfacet + facet normal 0.287195 -0.180521 0.940708 + outer loop + vertex 1.61948 1.13734 2.51586 + vertex 1.61923 1.13411 2.51532 + vertex 1.62306 1.13859 2.51501 + endloop + endfacet + facet normal 0.287321 -0.180634 0.940648 + outer loop + vertex 1.62306 1.13859 2.51501 + vertex 1.61923 1.13411 2.51532 + vertex 1.62293 1.13368 2.5141 + endloop + endfacet + facet normal 0.282503 -0.180775 0.942079 + outer loop + vertex 1.62293 1.13368 2.5141 + vertex 1.62766 1.13858 2.51363 + vertex 1.62306 1.13859 2.51501 + endloop + endfacet + facet normal 0.282685 -0.177413 0.942663 + outer loop + vertex 1.62767 1.14389 2.51462 + vertex 1.62306 1.13859 2.51501 + vertex 1.62766 1.13858 2.51363 + endloop + endfacet + facet normal 0.279707 -0.177573 0.943521 + outer loop + vertex 1.62766 1.13858 2.51363 + vertex 1.63254 1.14363 2.51313 + vertex 1.62767 1.14389 2.51462 + endloop + endfacet + facet normal 0.28024 -0.172313 0.944338 + outer loop + vertex 1.63254 1.14363 2.51313 + vertex 1.63285 1.14877 2.51398 + vertex 1.62767 1.14389 2.51462 + endloop + endfacet + facet normal 0.281561 -0.173805 0.943671 + outer loop + vertex 1.62767 1.14389 2.51462 + vertex 1.63285 1.14877 2.51398 + vertex 1.629 1.14917 2.5152 + endloop + endfacet + facet normal 0.281987 -0.173897 0.943527 + outer loop + vertex 1.62767 1.14389 2.51462 + vertex 1.629 1.14917 2.5152 + vertex 1.62503 1.14617 2.51583 + endloop + endfacet + facet normal 0.281515 -0.174462 0.943564 + outer loop + vertex 1.62357 1.14243 2.51558 + vertex 1.62767 1.14389 2.51462 + vertex 1.62503 1.14617 2.51583 + endloop + endfacet + facet normal 0.284523 -0.175561 0.942457 + outer loop + vertex 1.62503 1.14617 2.51583 + vertex 1.62112 1.14327 2.51647 + vertex 1.62357 1.14243 2.51558 + endloop + endfacet + facet normal 0.284534 -0.175531 0.942459 + outer loop + vertex 1.62357 1.14243 2.51558 + vertex 1.62112 1.14327 2.51647 + vertex 1.62093 1.14011 2.51594 + endloop + endfacet + facet normal 0.28239 -0.172423 0.943677 + outer loop + vertex 1.62235 1.14831 2.51702 + vertex 1.62112 1.14327 2.51647 + vertex 1.62503 1.14617 2.51583 + endloop + endfacet + facet normal 0.281612 -0.173424 0.943726 + outer loop + vertex 1.62638 1.14984 2.5161 + vertex 1.62235 1.14831 2.51702 + vertex 1.62503 1.14617 2.51583 + endloop + endfacet + facet normal 0.279347 -0.166294 0.945681 + outer loop + vertex 1.62638 1.14984 2.5161 + vertex 1.62634 1.15304 2.51668 + vertex 1.62235 1.14831 2.51702 + endloop + endfacet + facet normal 0.277739 -0.164886 0.9464 + outer loop + vertex 1.62634 1.15304 2.51668 + vertex 1.62237 1.15347 2.51792 + vertex 1.62235 1.14831 2.51702 + endloop + endfacet + facet normal 0.278426 -0.166352 0.945942 + outer loop + vertex 1.62902 1.15241 2.51578 + vertex 1.62634 1.15304 2.51668 + vertex 1.62638 1.14984 2.5161 + endloop + endfacet + facet normal 0.282457 -0.170738 0.943963 + outer loop + vertex 1.62902 1.15241 2.51578 + vertex 1.62638 1.14984 2.5161 + vertex 1.629 1.14917 2.5152 + endloop + endfacet + facet normal 0.288145 -0.170472 0.942291 + outer loop + vertex 1.62902 1.15241 2.51578 + vertex 1.629 1.14917 2.5152 + vertex 1.63298 1.15395 2.51485 + endloop + endfacet + facet normal 0.285504 -0.162292 0.944536 + outer loop + vertex 1.62902 1.15241 2.51578 + vertex 1.63298 1.15395 2.51485 + vertex 1.63026 1.15605 2.51603 + endloop + endfacet + facet normal 0.290589 -0.155488 0.94413 + outer loop + vertex 1.63298 1.15395 2.51485 + vertex 1.63411 1.1591 2.51535 + vertex 1.63026 1.15605 2.51603 + endloop + endfacet + facet normal 0.29213 -0.155777 0.943607 + outer loop + vertex 1.63298 1.15395 2.51485 + vertex 1.63789 1.15868 2.51411 + vertex 1.63411 1.1591 2.51535 + endloop + endfacet + facet normal 0.286738 -0.149773 0.946229 + outer loop + vertex 1.6376 1.15359 2.51339 + vertex 1.63789 1.15868 2.51411 + vertex 1.63298 1.15395 2.51485 + endloop + endfacet + facet normal 0.284827 -0.165736 0.944143 + outer loop + vertex 1.63285 1.14877 2.51398 + vertex 1.6376 1.15359 2.51339 + vertex 1.63298 1.15395 2.51485 + endloop + endfacet + facet normal 0.280802 -0.161535 0.946074 + outer loop + vertex 1.63729 1.14857 2.51262 + vertex 1.6376 1.15359 2.51339 + vertex 1.63285 1.14877 2.51398 + endloop + endfacet + facet normal 0.282613 -0.161561 0.945531 + outer loop + vertex 1.63729 1.14857 2.51262 + vertex 1.64225 1.15335 2.51196 + vertex 1.6376 1.15359 2.51339 + endloop + endfacet + facet normal 0.284106 -0.145244 0.947728 + outer loop + vertex 1.64225 1.15335 2.51196 + vertex 1.64214 1.15827 2.51275 + vertex 1.6376 1.15359 2.51339 + endloop + endfacet + facet normal 0.286093 -0.145107 0.947151 + outer loop + vertex 1.64596 1.15808 2.51156 + vertex 1.64214 1.15827 2.51275 + vertex 1.64225 1.15335 2.51196 + endloop + endfacet + facet normal 0.279551 -0.139731 0.949909 + outer loop + vertex 1.64623 1.15503 2.51104 + vertex 1.64596 1.15808 2.51156 + vertex 1.64225 1.15335 2.51196 + endloop + endfacet + facet normal 0.284807 -0.154318 0.946082 + outer loop + vertex 1.64623 1.15503 2.51104 + vertex 1.64225 1.15335 2.51196 + vertex 1.645 1.15132 2.5108 + endloop + endfacet + facet normal 0.29155 -0.156405 0.943682 + outer loop + vertex 1.64888 1.15436 2.5101 + vertex 1.64623 1.15503 2.51104 + vertex 1.645 1.15132 2.5108 + endloop + endfacet + facet normal 0.296042 -0.162719 0.941213 + outer loop + vertex 1.64763 1.14898 2.50957 + vertex 1.64888 1.15436 2.5101 + vertex 1.645 1.15132 2.5108 + endloop + endfacet + facet normal 0.292296 -0.167147 0.941608 + outer loop + vertex 1.64357 1.14753 2.51057 + vertex 1.64763 1.14898 2.50957 + vertex 1.645 1.15132 2.5108 + endloop + endfacet + facet normal 0.286335 -0.165044 0.943807 + outer loop + vertex 1.645 1.15132 2.5108 + vertex 1.64109 1.14832 2.51146 + vertex 1.64357 1.14753 2.51057 + endloop + endfacet + facet normal 0.284432 -0.170556 0.943403 + outer loop + vertex 1.64357 1.14753 2.51057 + vertex 1.64109 1.14832 2.51146 + vertex 1.64091 1.14515 2.51094 + endloop + endfacet + facet normal 0.29194 -0.179595 0.939423 + outer loop + vertex 1.64357 1.14753 2.51057 + vertex 1.64091 1.14515 2.51094 + vertex 1.64304 1.14365 2.50999 + endloop + endfacet + facet normal 0.2892 -0.183531 0.93951 + outer loop + vertex 1.64304 1.14365 2.50999 + vertex 1.64091 1.14515 2.51094 + vertex 1.63942 1.14234 2.51085 + endloop + endfacet + facet normal 0.290019 -0.186316 0.93871 + outer loop + vertex 1.63942 1.14234 2.51085 + vertex 1.63915 1.13911 2.51029 + vertex 1.64304 1.14365 2.50999 + endloop + endfacet + facet normal 0.287319 -0.183918 0.940012 + outer loop + vertex 1.64304 1.14365 2.50999 + vertex 1.63915 1.13911 2.51029 + vertex 1.64289 1.13871 2.50907 + endloop + endfacet + facet normal 0.290136 -0.183843 0.939161 + outer loop + vertex 1.64289 1.13871 2.50907 + vertex 1.64761 1.1436 2.50857 + vertex 1.64304 1.14365 2.50999 + endloop + endfacet + facet normal 0.290681 -0.175159 0.940651 + outer loop + vertex 1.64763 1.14898 2.50957 + vertex 1.64304 1.14365 2.50999 + vertex 1.64761 1.1436 2.50857 + endloop + endfacet + facet normal 0.286959 -0.175347 0.941758 + outer loop + vertex 1.64761 1.1436 2.50857 + vertex 1.6524 1.14847 2.50802 + vertex 1.64763 1.14898 2.50957 + endloop + endfacet + facet normal 0.28885 -0.162791 0.943432 + outer loop + vertex 1.6524 1.14847 2.50802 + vertex 1.65278 1.15375 2.50881 + vertex 1.64763 1.14898 2.50957 + endloop + endfacet + facet normal 0.27664 -0.162457 0.947142 + outer loop + vertex 1.6524 1.14847 2.50802 + vertex 1.65753 1.15316 2.50733 + vertex 1.65278 1.15375 2.50881 + endloop + endfacet + facet normal 0.281931 -0.168637 0.944498 + outer loop + vertex 1.65638 1.14804 2.50676 + vertex 1.65753 1.15316 2.50733 + vertex 1.6524 1.14847 2.50802 + endloop + endfacet + facet normal 0.28102 -0.174666 0.943674 + outer loop + vertex 1.65638 1.14804 2.50676 + vertex 1.6524 1.14847 2.50802 + vertex 1.65234 1.14329 2.50708 + endloop + endfacet + facet normal 0.282426 -0.175901 0.943024 + outer loop + vertex 1.65639 1.14485 2.50616 + vertex 1.65638 1.14804 2.50676 + vertex 1.65234 1.14329 2.50708 + endloop + endfacet + facet normal 0.282254 -0.175368 0.943175 + outer loop + vertex 1.65639 1.14485 2.50616 + vertex 1.65234 1.14329 2.50708 + vertex 1.65503 1.14117 2.50588 + endloop + endfacet + facet normal 0.27992 -0.174569 0.944018 + outer loop + vertex 1.659 1.14419 2.50526 + vertex 1.65639 1.14485 2.50616 + vertex 1.65503 1.14117 2.50588 + endloop + endfacet + facet normal 0.280084 -0.174805 0.943926 + outer loop + vertex 1.65766 1.13891 2.50468 + vertex 1.659 1.14419 2.50526 + vertex 1.65503 1.14117 2.50588 + endloop + endfacet + facet normal 0.281219 -0.173446 0.943839 + outer loop + vertex 1.65357 1.13741 2.50562 + vertex 1.65766 1.13891 2.50468 + vertex 1.65503 1.14117 2.50588 + endloop + endfacet + facet normal 0.281099 -0.173403 0.943883 + outer loop + vertex 1.65503 1.14117 2.50588 + vertex 1.6511 1.13822 2.50651 + vertex 1.65357 1.13741 2.50562 + endloop + endfacet + facet normal 0.281229 -0.173035 0.943911 + outer loop + vertex 1.65357 1.13741 2.50562 + vertex 1.6511 1.13822 2.50651 + vertex 1.65091 1.13506 2.50599 + endloop + endfacet + facet normal 0.284171 -0.176596 0.94237 + outer loop + vertex 1.65357 1.13741 2.50562 + vertex 1.65091 1.13506 2.50599 + vertex 1.65304 1.13357 2.50506 + endloop + endfacet + facet normal 0.283499 -0.17757 0.942389 + outer loop + vertex 1.65304 1.13357 2.50506 + vertex 1.65091 1.13506 2.50599 + vertex 1.64945 1.13227 2.5059 + endloop + endfacet + facet normal 0.285568 -0.184578 0.940416 + outer loop + vertex 1.64945 1.13227 2.5059 + vertex 1.64918 1.12906 2.50535 + vertex 1.65304 1.13357 2.50506 + endloop + endfacet + facet normal 0.285926 -0.184897 0.940244 + outer loop + vertex 1.65304 1.13357 2.50506 + vertex 1.64918 1.12906 2.50535 + vertex 1.65288 1.12868 2.50415 + endloop + endfacet + facet normal 0.28475 -0.184923 0.940596 + outer loop + vertex 1.65288 1.12868 2.50415 + vertex 1.65763 1.1336 2.50368 + vertex 1.65304 1.13357 2.50506 + endloop + endfacet + facet normal 0.285034 -0.17903 0.94165 + outer loop + vertex 1.65766 1.13891 2.50468 + vertex 1.65304 1.13357 2.50506 + vertex 1.65763 1.1336 2.50368 + endloop + endfacet + facet normal 0.282647 -0.179151 0.942346 + outer loop + vertex 1.65763 1.1336 2.50368 + vertex 1.66248 1.13864 2.50318 + vertex 1.65766 1.13891 2.50468 + endloop + endfacet + facet normal 0.283029 -0.17547 0.942923 + outer loop + vertex 1.66248 1.13864 2.50318 + vertex 1.66278 1.14374 2.50404 + vertex 1.65766 1.13891 2.50468 + endloop + endfacet + facet normal 0.289528 -0.175509 0.940941 + outer loop + vertex 1.66248 1.13864 2.50318 + vertex 1.66704 1.14344 2.50267 + vertex 1.66278 1.14374 2.50404 + endloop + endfacet + facet normal 0.290905 -0.163685 0.942646 + outer loop + vertex 1.66704 1.14344 2.50267 + vertex 1.66735 1.14834 2.50343 + vertex 1.66278 1.14374 2.50404 + endloop + endfacet + facet normal 0.298749 -0.172025 0.938699 + outer loop + vertex 1.66278 1.14374 2.50404 + vertex 1.66735 1.14834 2.50343 + vertex 1.66299 1.1489 2.50492 + endloop + endfacet + facet normal 0.283532 -0.172183 0.943378 + outer loop + vertex 1.66299 1.1489 2.50492 + vertex 1.659 1.14419 2.50526 + vertex 1.66278 1.14374 2.50404 + endloop + endfacet + facet normal 0.287616 -0.175771 0.941478 + outer loop + vertex 1.65905 1.14742 2.50585 + vertex 1.659 1.14419 2.50526 + vertex 1.66299 1.1489 2.50492 + endloop + endfacet + facet normal 0.287919 -0.176746 0.941203 + outer loop + vertex 1.65905 1.14742 2.50585 + vertex 1.66299 1.1489 2.50492 + vertex 1.66034 1.15103 2.50613 + endloop + endfacet + facet normal 0.279996 -0.174144 0.944074 + outer loop + vertex 1.66034 1.15103 2.50613 + vertex 1.65638 1.14804 2.50676 + vertex 1.65905 1.14742 2.50585 + endloop + endfacet + facet normal 0.294164 -0.168709 0.940747 + outer loop + vertex 1.66299 1.1489 2.50492 + vertex 1.66426 1.15404 2.50545 + vertex 1.66034 1.15103 2.50613 + endloop + endfacet + facet normal 0.298011 -0.174219 0.938529 + outer loop + vertex 1.66426 1.15404 2.50545 + vertex 1.66162 1.15466 2.5064 + vertex 1.66034 1.15103 2.50613 + endloop + endfacet + facet normal 0.275661 -0.166923 0.946651 + outer loop + vertex 1.66162 1.15466 2.5064 + vertex 1.65753 1.15316 2.50733 + vertex 1.66034 1.15103 2.50613 + endloop + endfacet + facet normal 0.269589 -0.147213 0.951657 + outer loop + vertex 1.66162 1.15466 2.5064 + vertex 1.6615 1.1579 2.50693 + vertex 1.65753 1.15316 2.50733 + endloop + endfacet + facet normal 0.285889 -0.145858 0.947097 + outer loop + vertex 1.66424 1.15728 2.50601 + vertex 1.6615 1.1579 2.50693 + vertex 1.66162 1.15466 2.5064 + endloop + endfacet + facet normal 0.301219 -0.162273 0.939646 + outer loop + vertex 1.66424 1.15728 2.50601 + vertex 1.66162 1.15466 2.5064 + vertex 1.66426 1.15404 2.50545 + endloop + endfacet + facet normal 0.342069 -0.159712 0.926002 + outer loop + vertex 1.66424 1.15728 2.50601 + vertex 1.66426 1.15404 2.50545 + vertex 1.6681 1.15889 2.50486 + endloop + endfacet + facet normal 0.326007 -0.146014 0.934023 + outer loop + vertex 1.6681 1.15889 2.50486 + vertex 1.66426 1.15404 2.50545 + vertex 1.66793 1.15354 2.50409 + endloop + endfacet + facet normal 0.367704 -0.145087 0.918555 + outer loop + vertex 1.66793 1.15354 2.50409 + vertex 1.67273 1.15837 2.50293 + vertex 1.6681 1.15889 2.50486 + endloop + endfacet + facet normal 0.340727 -0.114787 0.933128 + outer loop + vertex 1.67181 1.15263 2.50256 + vertex 1.67273 1.15837 2.50293 + vertex 1.66793 1.15354 2.50409 + endloop + endfacet + facet normal 0.330648 -0.154258 0.931062 + outer loop + vertex 1.66735 1.14834 2.50343 + vertex 1.67181 1.15263 2.50256 + vertex 1.66793 1.15354 2.50409 + endloop + endfacet + facet normal 0.317313 -0.138989 0.93808 + outer loop + vertex 1.67125 1.14768 2.50202 + vertex 1.67181 1.15263 2.50256 + vertex 1.66735 1.14834 2.50343 + endloop + endfacet + facet normal 0.320989 -0.174314 0.930903 + outer loop + vertex 1.66299 1.1489 2.50492 + vertex 1.66793 1.15354 2.50409 + vertex 1.66426 1.15404 2.50545 + endloop + endfacet + facet normal 0.30209 -0.152342 0.941028 + outer loop + vertex 1.66735 1.14834 2.50343 + vertex 1.66793 1.15354 2.50409 + vertex 1.66299 1.1489 2.50492 + endloop + endfacet + facet normal 0.312229 -0.163973 0.935749 + outer loop + vertex 1.66704 1.14344 2.50267 + vertex 1.67125 1.14768 2.50202 + vertex 1.66735 1.14834 2.50343 + endloop + endfacet + facet normal 0.303186 -0.154288 0.940358 + outer loop + vertex 1.67085 1.14332 2.50143 + vertex 1.67125 1.14768 2.50202 + vertex 1.66704 1.14344 2.50267 + endloop + endfacet + facet normal 0.301752 -0.171949 0.937752 + outer loop + vertex 1.67085 1.14332 2.50143 + vertex 1.66704 1.14344 2.50267 + vertex 1.66719 1.1388 2.50178 + endloop + endfacet + facet normal 0.29763 -0.168465 0.9397 + outer loop + vertex 1.67089 1.14027 2.50087 + vertex 1.67085 1.14332 2.50143 + vertex 1.66719 1.1388 2.50178 + endloop + endfacet + facet normal 0.299985 -0.175683 0.937627 + outer loop + vertex 1.67089 1.14027 2.50087 + vertex 1.66719 1.1388 2.50178 + vertex 1.66946 1.13744 2.5008 + endloop + endfacet + facet normal 0.333311 -0.192169 0.923025 + outer loop + vertex 1.67299 1.13883 2.49981 + vertex 1.67089 1.14027 2.50087 + vertex 1.66946 1.13744 2.5008 + endloop + endfacet + facet normal 0.333397 -0.19245 0.922935 + outer loop + vertex 1.66946 1.13744 2.5008 + vertex 1.66917 1.13421 2.50023 + vertex 1.67299 1.13883 2.49981 + endloop + endfacet + facet normal 0.323356 -0.183669 0.928281 + outer loop + vertex 1.67299 1.13883 2.49981 + vertex 1.66917 1.13421 2.50023 + vertex 1.67285 1.13386 2.49887 + endloop + endfacet + facet normal 0.321598 -0.195369 0.926502 + outer loop + vertex 1.66766 1.12893 2.49964 + vertex 1.67285 1.13386 2.49887 + vertex 1.66917 1.13421 2.50023 + endloop + endfacet + facet normal 0.300913 -0.190321 0.934467 + outer loop + vertex 1.66766 1.12893 2.49964 + vertex 1.66917 1.13421 2.50023 + vertex 1.66512 1.13118 2.50092 + endloop + endfacet + facet normal 0.297412 -0.194422 0.934744 + outer loop + vertex 1.66353 1.12741 2.50064 + vertex 1.66766 1.12893 2.49964 + vertex 1.66512 1.13118 2.50092 + endloop + endfacet + facet normal 0.289091 -0.191164 0.938021 + outer loop + vertex 1.66512 1.13118 2.50092 + vertex 1.66107 1.12822 2.50156 + vertex 1.66353 1.12741 2.50064 + endloop + endfacet + facet normal 0.288566 -0.192597 0.937889 + outer loop + vertex 1.66353 1.12741 2.50064 + vertex 1.66107 1.12822 2.50156 + vertex 1.66082 1.12509 2.50099 + endloop + endfacet + facet normal 0.288012 -0.191903 0.938202 + outer loop + vertex 1.66353 1.12741 2.50064 + vertex 1.66082 1.12509 2.50099 + vertex 1.66297 1.12363 2.50003 + endloop + endfacet + facet normal 0.287229 -0.193057 0.938205 + outer loop + vertex 1.66297 1.12363 2.50003 + vertex 1.66082 1.12509 2.50099 + vertex 1.65936 1.12236 2.50088 + endloop + endfacet + facet normal 0.286497 -0.190466 0.938958 + outer loop + vertex 1.65936 1.12236 2.50088 + vertex 1.65911 1.11918 2.50031 + vertex 1.66297 1.12363 2.50003 + endloop + endfacet + facet normal 0.284378 -0.188561 0.939986 + outer loop + vertex 1.66297 1.12363 2.50003 + vertex 1.65911 1.11918 2.50031 + vertex 1.66282 1.11877 2.4991 + endloop + endfacet + facet normal 0.290847 -0.188389 0.938039 + outer loop + vertex 1.66282 1.11877 2.4991 + vertex 1.66754 1.12366 2.49862 + vertex 1.66297 1.12363 2.50003 + endloop + endfacet + facet normal 0.290906 -0.187207 0.938257 + outer loop + vertex 1.66766 1.12893 2.49964 + vertex 1.66297 1.12363 2.50003 + vertex 1.66754 1.12366 2.49862 + endloop + endfacet + facet normal 0.306726 -0.186597 0.933328 + outer loop + vertex 1.66754 1.12366 2.49862 + vertex 1.67236 1.12866 2.49804 + vertex 1.66766 1.12893 2.49964 + endloop + endfacet + facet normal 0.297794 -0.177462 0.93799 + outer loop + vertex 1.67226 1.12348 2.49709 + vertex 1.67236 1.12866 2.49804 + vertex 1.66754 1.12366 2.49862 + endloop + endfacet + facet normal 0.297182 -0.184204 0.936884 + outer loop + vertex 1.66721 1.11862 2.49774 + vertex 1.67226 1.12348 2.49709 + vertex 1.66754 1.12366 2.49862 + endloop + endfacet + facet normal 0.290938 -0.177273 0.940175 + outer loop + vertex 1.671 1.11839 2.49652 + vertex 1.67226 1.12348 2.49709 + vertex 1.66721 1.11862 2.49774 + endloop + endfacet + facet normal 0.29013 -0.184435 0.939047 + outer loop + vertex 1.671 1.11839 2.49652 + vertex 1.66721 1.11862 2.49774 + vertex 1.66714 1.11385 2.49682 + endloop + endfacet + facet normal 0.287093 -0.181755 0.940501 + outer loop + vertex 1.67081 1.11524 2.49597 + vertex 1.671 1.11839 2.49652 + vertex 1.66714 1.11385 2.49682 + endloop + endfacet + facet normal 0.288364 -0.18584 0.939314 + outer loop + vertex 1.67081 1.11524 2.49597 + vertex 1.66714 1.11385 2.49682 + vertex 1.66933 1.11245 2.49587 + endloop + endfacet + facet normal 0.302901 -0.193294 0.933214 + outer loop + vertex 1.67297 1.11376 2.49496 + vertex 1.67081 1.11524 2.49597 + vertex 1.66933 1.11245 2.49587 + endloop + endfacet + facet normal 0.303182 -0.194282 0.932917 + outer loop + vertex 1.66933 1.11245 2.49587 + vertex 1.66907 1.10923 2.49528 + vertex 1.67297 1.11376 2.49496 + endloop + endfacet + facet normal 0.298097 -0.189732 0.935489 + outer loop + vertex 1.67297 1.11376 2.49496 + vertex 1.66907 1.10923 2.49528 + vertex 1.67284 1.10877 2.49399 + endloop + endfacet + facet normal 0.315974 -0.189066 0.929739 + outer loop + vertex 1.67284 1.10877 2.49399 + vertex 1.67749 1.11368 2.49341 + vertex 1.67297 1.11376 2.49496 + endloop + endfacet + facet normal 0.316808 -0.177996 0.931639 + outer loop + vertex 1.67756 1.11912 2.49443 + vertex 1.67297 1.11376 2.49496 + vertex 1.67749 1.11368 2.49341 + endloop + endfacet + facet normal 0.330038 -0.190027 0.924643 + outer loop + vertex 1.67349 1.11762 2.49557 + vertex 1.67297 1.11376 2.49496 + vertex 1.67756 1.11912 2.49443 + endloop + endfacet + facet normal 0.328734 -0.185429 0.92604 + outer loop + vertex 1.67349 1.11762 2.49557 + vertex 1.67756 1.11912 2.49443 + vertex 1.67495 1.12142 2.49581 + endloop + endfacet + facet normal 0.303136 -0.17623 0.93651 + outer loop + vertex 1.67495 1.12142 2.49581 + vertex 1.671 1.11839 2.49652 + vertex 1.67349 1.11762 2.49557 + endloop + endfacet + facet normal 0.307575 -0.180598 0.934228 + outer loop + vertex 1.67746 1.10839 2.4924 + vertex 1.67749 1.11368 2.49341 + vertex 1.67284 1.10877 2.49399 + endloop + endfacet + facet normal 0.306137 -0.191237 0.932582 + outer loop + vertex 1.67237 1.10358 2.49308 + vertex 1.67746 1.10839 2.4924 + vertex 1.67284 1.10877 2.49399 + endloop + endfacet + facet normal 0.291134 -0.19073 0.937477 + outer loop + vertex 1.67237 1.10358 2.49308 + vertex 1.67284 1.10877 2.49399 + vertex 1.66762 1.10396 2.49463 + endloop + endfacet + facet normal 0.29014 -0.198087 0.936259 + outer loop + vertex 1.66764 1.09866 2.49351 + vertex 1.67237 1.10358 2.49308 + vertex 1.66762 1.10396 2.49463 + endloop + endfacet + facet normal 0.28722 -0.198276 0.937119 + outer loop + vertex 1.66762 1.10396 2.49463 + vertex 1.66296 1.09872 2.49495 + vertex 1.66764 1.09866 2.49351 + endloop + endfacet + facet normal 0.286781 -0.204371 0.935943 + outer loop + vertex 1.66287 1.09381 2.49391 + vertex 1.66764 1.09866 2.49351 + vertex 1.66296 1.09872 2.49495 + endloop + endfacet + facet normal 0.287436 -0.204342 0.935748 + outer loop + vertex 1.66296 1.09872 2.49495 + vertex 1.65906 1.09431 2.49519 + vertex 1.66287 1.09381 2.49391 + endloop + endfacet + facet normal 0.286602 -0.208798 0.93502 + outer loop + vertex 1.65758 1.08911 2.49448 + vertex 1.66287 1.09381 2.49391 + vertex 1.65906 1.09431 2.49519 + endloop + endfacet + facet normal 0.285563 -0.208553 0.935393 + outer loop + vertex 1.65758 1.08911 2.49448 + vertex 1.65906 1.09431 2.49519 + vertex 1.65503 1.09144 2.49578 + endloop + endfacet + facet normal 0.284702 -0.209518 0.935439 + outer loop + vertex 1.65342 1.08772 2.49544 + vertex 1.65758 1.08911 2.49448 + vertex 1.65503 1.09144 2.49578 + endloop + endfacet + facet normal 0.28544 -0.212323 0.934582 + outer loop + vertex 1.65342 1.08772 2.49544 + vertex 1.65269 1.08374 2.49476 + vertex 1.65758 1.08911 2.49448 + endloop + endfacet + facet normal 0.282754 -0.209802 0.935966 + outer loop + vertex 1.65758 1.08911 2.49448 + vertex 1.65269 1.08374 2.49476 + vertex 1.65752 1.08379 2.49331 + endloop + endfacet + facet normal 0.284796 -0.209693 0.935372 + outer loop + vertex 1.65752 1.08379 2.49331 + vertex 1.66236 1.08869 2.49293 + vertex 1.65758 1.08911 2.49448 + endloop + endfacet + facet normal 0.283133 -0.207983 0.936258 + outer loop + vertex 1.66226 1.08383 2.49188 + vertex 1.66236 1.08869 2.49293 + vertex 1.65752 1.08379 2.49331 + endloop + endfacet + facet normal 0.283109 -0.208434 0.936165 + outer loop + vertex 1.66226 1.08383 2.49188 + vertex 1.65752 1.08379 2.49331 + vertex 1.65753 1.07858 2.49214 + endloop + endfacet + facet normal 0.280901 -0.206393 0.937281 + outer loop + vertex 1.66171 1.08008 2.49122 + vertex 1.66226 1.08383 2.49188 + vertex 1.65753 1.07858 2.49214 + endloop + endfacet + facet normal 0.281156 -0.207271 0.937011 + outer loop + vertex 1.66171 1.08008 2.49122 + vertex 1.65753 1.07858 2.49214 + vertex 1.66013 1.07636 2.49087 + endloop + endfacet + facet normal 0.281362 -0.207352 0.936932 + outer loop + vertex 1.66414 1.07921 2.4903 + vertex 1.66171 1.08008 2.49122 + vertex 1.66013 1.07636 2.49087 + endloop + endfacet + facet normal 0.283776 -0.211079 0.93537 + outer loop + vertex 1.66264 1.07405 2.48959 + vertex 1.66414 1.07921 2.4903 + vertex 1.66013 1.07636 2.49087 + endloop + endfacet + facet normal 0.283322 -0.211583 0.935394 + outer loop + vertex 1.6585 1.07263 2.49052 + vertex 1.66264 1.07405 2.48959 + vertex 1.66013 1.07636 2.49087 + endloop + endfacet + facet normal 0.281027 -0.210669 0.936292 + outer loop + vertex 1.66013 1.07636 2.49087 + vertex 1.65607 1.07349 2.49144 + vertex 1.6585 1.07263 2.49052 + endloop + endfacet + facet normal 0.279952 -0.213394 0.935997 + outer loop + vertex 1.6585 1.07263 2.49052 + vertex 1.65607 1.07349 2.49144 + vertex 1.65572 1.07032 2.49083 + endloop + endfacet + facet normal 0.284155 -0.218804 0.933478 + outer loop + vertex 1.6585 1.07263 2.49052 + vertex 1.65572 1.07032 2.49083 + vertex 1.65774 1.06866 2.48982 + endloop + endfacet + facet normal 0.277598 -0.213271 0.936725 + outer loop + vertex 1.65572 1.07032 2.49083 + vertex 1.65607 1.07349 2.49144 + vertex 1.65203 1.06903 2.49163 + endloop + endfacet + facet normal 0.279194 -0.218955 0.934938 + outer loop + vertex 1.65572 1.07032 2.49083 + vertex 1.65203 1.06903 2.49163 + vertex 1.65396 1.06742 2.49068 + endloop + endfacet + facet normal 0.282469 -0.220866 0.933504 + outer loop + vertex 1.65774 1.06866 2.48982 + vertex 1.65572 1.07032 2.49083 + vertex 1.65396 1.06742 2.49068 + endloop + endfacet + facet normal 0.282798 -0.222158 0.933098 + outer loop + vertex 1.65396 1.06742 2.49068 + vertex 1.65296 1.06349 2.49004 + vertex 1.65774 1.06866 2.48982 + endloop + endfacet + facet normal 0.281444 -0.220875 0.933811 + outer loop + vertex 1.65774 1.06866 2.48982 + vertex 1.65296 1.06349 2.49004 + vertex 1.65763 1.06363 2.48867 + endloop + endfacet + facet normal 0.282963 -0.220806 0.933368 + outer loop + vertex 1.65763 1.06363 2.48867 + vertex 1.66257 1.06877 2.48838 + vertex 1.65774 1.06866 2.48982 + endloop + endfacet + facet normal 0.283129 -0.216911 0.934231 + outer loop + vertex 1.66264 1.07405 2.48959 + vertex 1.65774 1.06866 2.48982 + vertex 1.66257 1.06877 2.48838 + endloop + endfacet + facet normal 0.281947 -0.216974 0.934574 + outer loop + vertex 1.66257 1.06877 2.48838 + vertex 1.66746 1.07384 2.48809 + vertex 1.66264 1.07405 2.48959 + endloop + endfacet + facet normal 0.282457 -0.212095 0.935539 + outer loop + vertex 1.66746 1.07384 2.48809 + vertex 1.66785 1.0788 2.48909 + vertex 1.66264 1.07405 2.48959 + endloop + endfacet + facet normal 0.281187 -0.212073 0.935927 + outer loop + vertex 1.66746 1.07384 2.48809 + vertex 1.67225 1.07864 2.48774 + vertex 1.66785 1.0788 2.48909 + endloop + endfacet + facet normal 0.281851 -0.205136 0.937272 + outer loop + vertex 1.67225 1.07864 2.48774 + vertex 1.67262 1.0836 2.48871 + vertex 1.66785 1.0788 2.48909 + endloop + endfacet + facet normal 0.283197 -0.206529 0.93656 + outer loop + vertex 1.66785 1.0788 2.48909 + vertex 1.67262 1.0836 2.48871 + vertex 1.66805 1.08359 2.49009 + endloop + endfacet + facet normal 0.281632 -0.206561 0.937025 + outer loop + vertex 1.66805 1.08359 2.49009 + vertex 1.66414 1.07921 2.4903 + vertex 1.66785 1.0788 2.48909 + endloop + endfacet + facet normal 0.281263 -0.206223 0.93721 + outer loop + vertex 1.66443 1.08236 2.49091 + vertex 1.66414 1.07921 2.4903 + vertex 1.66805 1.08359 2.49009 + endloop + endfacet + facet normal 0.281161 -0.205848 0.937323 + outer loop + vertex 1.66805 1.08359 2.49009 + vertex 1.66593 1.08507 2.49105 + vertex 1.66443 1.08236 2.49091 + endloop + endfacet + facet normal 0.2821 -0.206346 0.936932 + outer loop + vertex 1.66593 1.08507 2.49105 + vertex 1.66226 1.08383 2.49188 + vertex 1.66443 1.08236 2.49091 + endloop + endfacet + facet normal 0.282307 -0.207117 0.936699 + outer loop + vertex 1.66593 1.08507 2.49105 + vertex 1.6662 1.08822 2.49167 + vertex 1.66226 1.08383 2.49188 + endloop + endfacet + facet normal 0.282171 -0.207113 0.936741 + outer loop + vertex 1.66864 1.08735 2.49074 + vertex 1.6662 1.08822 2.49167 + vertex 1.66593 1.08507 2.49105 + endloop + endfacet + facet normal 0.282525 -0.206222 0.936831 + outer loop + vertex 1.67025 1.09109 2.49108 + vertex 1.6662 1.08822 2.49167 + vertex 1.66864 1.08735 2.49074 + endloop + endfacet + facet normal 0.288647 -0.208624 0.93443 + outer loop + vertex 1.66864 1.08735 2.49074 + vertex 1.67275 1.08882 2.4898 + vertex 1.67025 1.09109 2.49108 + endloop + endfacet + facet normal 0.292119 -0.204672 0.934225 + outer loop + vertex 1.67275 1.08882 2.4898 + vertex 1.67427 1.09402 2.49046 + vertex 1.67025 1.09109 2.49108 + endloop + endfacet + facet normal 0.295765 -0.210184 0.931851 + outer loop + vertex 1.67427 1.09402 2.49046 + vertex 1.67185 1.09484 2.49141 + vertex 1.67025 1.09109 2.49108 + endloop + endfacet + facet normal 0.283382 -0.205337 0.936766 + outer loop + vertex 1.67185 1.09484 2.49141 + vertex 1.66766 1.0934 2.49237 + vertex 1.67025 1.09109 2.49108 + endloop + endfacet + facet normal 0.281519 -0.198614 0.938776 + outer loop + vertex 1.67185 1.09484 2.49141 + vertex 1.67236 1.09866 2.49207 + vertex 1.66766 1.0934 2.49237 + endloop + endfacet + facet normal 0.285345 -0.202141 0.936866 + outer loop + vertex 1.67236 1.09866 2.49207 + vertex 1.66764 1.09866 2.49351 + vertex 1.66766 1.0934 2.49237 + endloop + endfacet + facet normal 0.290502 -0.199323 0.935884 + outer loop + vertex 1.67457 1.09719 2.49107 + vertex 1.67236 1.09866 2.49207 + vertex 1.67185 1.09484 2.49141 + endloop + endfacet + facet normal 0.293781 -0.19439 0.935898 + outer loop + vertex 1.67604 1.09998 2.49119 + vertex 1.67236 1.09866 2.49207 + vertex 1.67457 1.09719 2.49107 + endloop + endfacet + facet normal 0.326274 -0.21093 0.921441 + outer loop + vertex 1.67812 1.09855 2.49013 + vertex 1.67604 1.09998 2.49119 + vertex 1.67457 1.09719 2.49107 + endloop + endfacet + facet normal 0.325428 -0.208055 0.922394 + outer loop + vertex 1.67457 1.09719 2.49107 + vertex 1.67427 1.09402 2.49046 + vertex 1.67812 1.09855 2.49013 + endloop + endfacet + facet normal 0.31721 -0.200757 0.926863 + outer loop + vertex 1.67812 1.09855 2.49013 + vertex 1.67427 1.09402 2.49046 + vertex 1.67793 1.09369 2.48914 + endloop + endfacet + facet normal 0.352636 -0.199575 0.914231 + outer loop + vertex 1.67793 1.09369 2.48914 + vertex 1.68236 1.0986 2.4885 + vertex 1.67812 1.09855 2.49013 + endloop + endfacet + facet normal 0.353462 -0.185821 0.916807 + outer loop + vertex 1.68259 1.1039 2.48948 + vertex 1.67812 1.09855 2.49013 + vertex 1.68236 1.0986 2.4885 + endloop + endfacet + facet normal 0.37452 -0.204945 0.904286 + outer loop + vertex 1.67869 1.10238 2.49076 + vertex 1.67812 1.09855 2.49013 + vertex 1.68259 1.1039 2.48948 + endloop + endfacet + facet normal 0.373 -0.199501 0.90613 + outer loop + vertex 1.67869 1.10238 2.49076 + vertex 1.68259 1.1039 2.48948 + vertex 1.68014 1.10621 2.491 + endloop + endfacet + facet normal 0.325024 -0.182695 0.927891 + outer loop + vertex 1.68014 1.10621 2.491 + vertex 1.67622 1.10319 2.49178 + vertex 1.67869 1.10238 2.49076 + endloop + endfacet + facet normal 0.322636 -0.18934 0.927392 + outer loop + vertex 1.67869 1.10238 2.49076 + vertex 1.67622 1.10319 2.49178 + vertex 1.67604 1.09998 2.49119 + endloop + endfacet + facet normal 0.328703 -0.188072 0.925518 + outer loop + vertex 1.67746 1.10839 2.4924 + vertex 1.67622 1.10319 2.49178 + vertex 1.68014 1.10621 2.491 + endloop + endfacet + facet normal 0.332654 -0.182969 0.925129 + outer loop + vertex 1.68147 1.11 2.49127 + vertex 1.67746 1.10839 2.4924 + vertex 1.68014 1.10621 2.491 + endloop + endfacet + facet normal 0.397085 -0.203471 0.894943 + outer loop + vertex 1.68398 1.10933 2.49001 + vertex 1.68147 1.11 2.49127 + vertex 1.68014 1.10621 2.491 + endloop + endfacet + facet normal 0.329897 -0.174247 0.927796 + outer loop + vertex 1.68147 1.11 2.49127 + vertex 1.6814 1.11333 2.49192 + vertex 1.67746 1.10839 2.4924 + endloop + endfacet + facet normal 0.335447 -0.178947 0.924907 + outer loop + vertex 1.6814 1.11333 2.49192 + vertex 1.67749 1.11368 2.49341 + vertex 1.67746 1.10839 2.4924 + endloop + endfacet + facet normal 0.338637 -0.156353 0.927835 + outer loop + vertex 1.6814 1.11333 2.49192 + vertex 1.68237 1.11865 2.49246 + vertex 1.67749 1.11368 2.49341 + endloop + endfacet + facet normal 0.356509 -0.1759 0.917584 + outer loop + vertex 1.67749 1.11368 2.49341 + vertex 1.68237 1.11865 2.49246 + vertex 1.67756 1.11912 2.49443 + endloop + endfacet + facet normal 0.359165 -0.15816 0.919775 + outer loop + vertex 1.68237 1.11865 2.49246 + vertex 1.68228 1.12391 2.49341 + vertex 1.67756 1.11912 2.49443 + endloop + endfacet + facet normal 0.428001 -0.151755 0.890947 + outer loop + vertex 1.68576 1.12349 2.49166 + vertex 1.68228 1.12391 2.49341 + vertex 1.68237 1.11865 2.49246 + endloop + endfacet + facet normal 0.408816 -0.136423 0.902363 + outer loop + vertex 1.6861 1.12024 2.49102 + vertex 1.68576 1.12349 2.49166 + vertex 1.68237 1.11865 2.49246 + endloop + endfacet + facet normal 0.411792 -0.145974 0.89951 + outer loop + vertex 1.6861 1.12024 2.49102 + vertex 1.68237 1.11865 2.49246 + vertex 1.68507 1.11646 2.49088 + endloop + endfacet + facet normal 0.52553 -0.174464 0.832695 + outer loop + vertex 1.68826 1.11948 2.4895 + vertex 1.6861 1.12024 2.49102 + vertex 1.68507 1.11646 2.49088 + endloop + endfacet + facet normal 0.502843 -0.141305 0.852749 + outer loop + vertex 1.6874 1.11422 2.48913 + vertex 1.68826 1.11948 2.4895 + vertex 1.68507 1.11646 2.49088 + endloop + endfacet + facet normal 0.477019 -0.174825 0.86133 + outer loop + vertex 1.68397 1.11269 2.49072 + vertex 1.6874 1.11422 2.48913 + vertex 1.68507 1.11646 2.49088 + endloop + endfacet + facet normal 0.388722 -0.151294 0.908849 + outer loop + vertex 1.68507 1.11646 2.49088 + vertex 1.6814 1.11333 2.49192 + vertex 1.68397 1.11269 2.49072 + endloop + endfacet + facet normal 0.383793 -0.169146 0.907796 + outer loop + vertex 1.68397 1.11269 2.49072 + vertex 1.6814 1.11333 2.49192 + vertex 1.68147 1.11 2.49127 + endloop + endfacet + facet normal 0.401762 -0.188271 0.896182 + outer loop + vertex 1.68397 1.11269 2.49072 + vertex 1.68147 1.11 2.49127 + vertex 1.68398 1.10933 2.49001 + endloop + endfacet + facet normal 0.478557 -0.180326 0.85934 + outer loop + vertex 1.68397 1.11269 2.49072 + vertex 1.68398 1.10933 2.49001 + vertex 1.6874 1.11422 2.48913 + endloop + endfacet + facet normal 0.447926 -0.155088 0.880517 + outer loop + vertex 1.6874 1.11422 2.48913 + vertex 1.68398 1.10933 2.49001 + vertex 1.68771 1.10882 2.48802 + endloop + endfacet + facet normal 0.439865 -0.196908 0.876211 + outer loop + vertex 1.68259 1.1039 2.48948 + vertex 1.68771 1.10882 2.48802 + vertex 1.68398 1.10933 2.49001 + endloop + endfacet + facet normal 0.407291 -0.155929 0.899889 + outer loop + vertex 1.68658 1.10311 2.48754 + vertex 1.68771 1.10882 2.48802 + vertex 1.68259 1.1039 2.48948 + endloop + endfacet + facet normal 0.400534 -0.18431 0.897554 + outer loop + vertex 1.68236 1.0986 2.4885 + vertex 1.68658 1.10311 2.48754 + vertex 1.68259 1.1039 2.48948 + endloop + endfacet + facet normal 0.382804 -0.165312 0.908919 + outer loop + vertex 1.68609 1.09849 2.48691 + vertex 1.68658 1.10311 2.48754 + vertex 1.68236 1.0986 2.4885 + endloop + endfacet + facet normal 0.381447 -0.17962 0.906771 + outer loop + vertex 1.68609 1.09849 2.48691 + vertex 1.68236 1.0986 2.4885 + vertex 1.68245 1.09353 2.48746 + endloop + endfacet + facet normal 0.369532 -0.170104 0.913515 + outer loop + vertex 1.68632 1.09531 2.48622 + vertex 1.68609 1.09849 2.48691 + vertex 1.68245 1.09353 2.48746 + endloop + endfacet + facet normal 0.368638 -0.167586 0.914342 + outer loop + vertex 1.68632 1.09531 2.48622 + vertex 1.68245 1.09353 2.48746 + vertex 1.68517 1.0915 2.48599 + endloop + endfacet + facet normal 0.360488 -0.179286 0.915372 + outer loop + vertex 1.68245 1.09353 2.48746 + vertex 1.68138 1.08828 2.48685 + vertex 1.68517 1.0915 2.48599 + endloop + endfacet + facet normal 0.34907 -0.163857 0.92266 + outer loop + vertex 1.68517 1.0915 2.48599 + vertex 1.68138 1.08828 2.48685 + vertex 1.68401 1.08773 2.48576 + endloop + endfacet + facet normal 0.413286 -0.18177 0.892275 + outer loop + vertex 1.68401 1.08773 2.48576 + vertex 1.68758 1.08925 2.48442 + vertex 1.68517 1.0915 2.48599 + endloop + endfacet + facet normal 0.421636 -0.171533 0.890393 + outer loop + vertex 1.68758 1.08925 2.48442 + vertex 1.68867 1.09452 2.48491 + vertex 1.68517 1.0915 2.48599 + endloop + endfacet + facet normal 0.430533 -0.184285 0.883561 + outer loop + vertex 1.68867 1.09452 2.48491 + vertex 1.68632 1.09531 2.48622 + vertex 1.68517 1.0915 2.48599 + endloop + endfacet + facet normal 0.416246 -0.191746 0.888804 + outer loop + vertex 1.68401 1.08773 2.48576 + vertex 1.68397 1.08447 2.48507 + vertex 1.68758 1.08925 2.48442 + endloop + endfacet + facet normal 0.4013 -0.179201 0.898246 + outer loop + vertex 1.68758 1.08925 2.48442 + vertex 1.68397 1.08447 2.48507 + vertex 1.68742 1.08408 2.48345 + endloop + endfacet + facet normal 0.345341 -0.178844 0.921279 + outer loop + vertex 1.68401 1.08773 2.48576 + vertex 1.68138 1.08828 2.48685 + vertex 1.68144 1.08504 2.4862 + endloop + endfacet + facet normal 0.361565 -0.195904 0.911533 + outer loop + vertex 1.68401 1.08773 2.48576 + vertex 1.68144 1.08504 2.4862 + vertex 1.68397 1.08447 2.48507 + endloop + endfacet + facet normal 0.43405 -0.113233 0.893744 + outer loop + vertex 1.68576 1.12349 2.49166 + vertex 1.68588 1.12812 2.49219 + vertex 1.68228 1.12391 2.49341 + endloop + endfacet + facet normal 0.398316 -0.164674 0.902345 + outer loop + vertex 1.68237 1.11865 2.49246 + vertex 1.6814 1.11333 2.49192 + vertex 1.68507 1.11646 2.49088 + endloop + endfacet + facet normal 0.384897 -0.185551 0.904116 + outer loop + vertex 1.68259 1.1039 2.48948 + vertex 1.68398 1.10933 2.49001 + vertex 1.68014 1.10621 2.491 + endloop + endfacet + facet normal 0.332672 -0.201531 0.921257 + outer loop + vertex 1.67869 1.10238 2.49076 + vertex 1.67604 1.09998 2.49119 + vertex 1.67812 1.09855 2.49013 + endloop + endfacet + facet normal 0.336522 -0.183842 0.923556 + outer loop + vertex 1.68245 1.09353 2.48746 + vertex 1.68236 1.0986 2.4885 + vertex 1.67793 1.09369 2.48914 + endloop + endfacet + facet normal 0.335521 -0.194138 0.921811 + outer loop + vertex 1.67744 1.08854 2.48823 + vertex 1.68245 1.09353 2.48746 + vertex 1.67793 1.09369 2.48914 + endloop + endfacet + facet normal 0.300433 -0.192956 0.934081 + outer loop + vertex 1.67744 1.08854 2.48823 + vertex 1.67793 1.09369 2.48914 + vertex 1.67275 1.08882 2.4898 + endloop + endfacet + facet normal 0.299403 -0.201659 0.932573 + outer loop + vertex 1.67262 1.0836 2.48871 + vertex 1.67744 1.08854 2.48823 + vertex 1.67275 1.08882 2.4898 + endloop + endfacet + facet normal 0.290669 -0.192685 0.937222 + outer loop + vertex 1.67737 1.08339 2.48719 + vertex 1.67744 1.08854 2.48823 + vertex 1.67262 1.0836 2.48871 + endloop + endfacet + facet normal 0.313049 -0.191575 0.930215 + outer loop + vertex 1.68138 1.08828 2.48685 + vertex 1.67744 1.08854 2.48823 + vertex 1.67737 1.08339 2.48719 + endloop + endfacet + facet normal 0.302531 -0.182599 0.935485 + outer loop + vertex 1.68144 1.08504 2.4862 + vertex 1.68138 1.08828 2.48685 + vertex 1.67737 1.08339 2.48719 + endloop + endfacet + facet normal 0.307223 -0.196876 0.93105 + outer loop + vertex 1.68144 1.08504 2.4862 + vertex 1.67737 1.08339 2.48719 + vertex 1.68008 1.08135 2.48587 + endloop + endfacet + facet normal 0.356786 -0.213236 0.909524 + outer loop + vertex 1.68397 1.08447 2.48507 + vertex 1.68144 1.08504 2.4862 + vertex 1.68008 1.08135 2.48587 + endloop + endfacet + facet normal 0.350292 -0.203954 0.914165 + outer loop + vertex 1.6826 1.07915 2.48441 + vertex 1.68397 1.08447 2.48507 + vertex 1.68008 1.08135 2.48587 + endloop + endfacet + facet normal 0.339295 -0.217279 0.915242 + outer loop + vertex 1.67853 1.07758 2.48555 + vertex 1.6826 1.07915 2.48441 + vertex 1.68008 1.08135 2.48587 + endloop + endfacet + facet normal 0.302101 -0.20332 0.931341 + outer loop + vertex 1.68008 1.08135 2.48587 + vertex 1.67606 1.07837 2.48652 + vertex 1.67853 1.07758 2.48555 + endloop + endfacet + facet normal 0.298906 -0.21217 0.930397 + outer loop + vertex 1.67853 1.07758 2.48555 + vertex 1.67606 1.07837 2.48652 + vertex 1.67574 1.07521 2.4859 + endloop + endfacet + facet normal 0.304969 -0.219878 0.926632 + outer loop + vertex 1.67853 1.07758 2.48555 + vertex 1.67574 1.07521 2.4859 + vertex 1.67778 1.07364 2.48486 + endloop + endfacet + facet normal 0.300273 -0.225987 0.926696 + outer loop + vertex 1.67778 1.07364 2.48486 + vertex 1.67574 1.07521 2.4859 + vertex 1.67402 1.07234 2.48576 + endloop + endfacet + facet normal 0.299581 -0.223387 0.92755 + outer loop + vertex 1.67402 1.07234 2.48576 + vertex 1.67316 1.06858 2.48513 + vertex 1.67778 1.07364 2.48486 + endloop + endfacet + facet normal 0.292256 -0.216482 0.931516 + outer loop + vertex 1.67778 1.07364 2.48486 + vertex 1.67316 1.06858 2.48513 + vertex 1.67764 1.06867 2.48375 + endloop + endfacet + facet normal 0.319022 -0.215308 0.922967 + outer loop + vertex 1.67764 1.06867 2.48375 + vertex 1.6824 1.07376 2.48329 + vertex 1.67778 1.07364 2.48486 + endloop + endfacet + facet normal 0.319519 -0.204284 0.925298 + outer loop + vertex 1.6826 1.07915 2.48441 + vertex 1.67778 1.07364 2.48486 + vertex 1.6824 1.07376 2.48329 + endloop + endfacet + facet normal 0.364832 -0.202571 0.90877 + outer loop + vertex 1.6824 1.07376 2.48329 + vertex 1.68739 1.07888 2.48243 + vertex 1.6826 1.07915 2.48441 + endloop + endfacet + facet normal 0.367346 -0.182079 0.912088 + outer loop + vertex 1.68739 1.07888 2.48243 + vertex 1.68742 1.08408 2.48345 + vertex 1.6826 1.07915 2.48441 + endloop + endfacet + facet normal 0.339899 -0.175702 0.923903 + outer loop + vertex 1.68632 1.07356 2.48181 + vertex 1.68739 1.07888 2.48243 + vertex 1.6824 1.07376 2.48329 + endloop + endfacet + facet normal 0.33701 -0.200993 0.919797 + outer loop + vertex 1.68632 1.07356 2.48181 + vertex 1.6824 1.07376 2.48329 + vertex 1.68232 1.06858 2.48219 + endloop + endfacet + facet normal 0.306262 -0.202733 0.930109 + outer loop + vertex 1.68232 1.06858 2.48219 + vertex 1.6824 1.07376 2.48329 + vertex 1.67764 1.06867 2.48375 + endloop + endfacet + facet normal 0.305121 -0.216074 0.927477 + outer loop + vertex 1.67723 1.06374 2.48273 + vertex 1.68232 1.06858 2.48219 + vertex 1.67764 1.06867 2.48375 + endloop + endfacet + facet normal 0.287575 -0.215783 0.933134 + outer loop + vertex 1.67723 1.06374 2.48273 + vertex 1.67764 1.06867 2.48375 + vertex 1.67285 1.06382 2.4841 + endloop + endfacet + facet normal 0.286919 -0.2237 0.93147 + outer loop + vertex 1.67242 1.0589 2.48305 + vertex 1.67723 1.06374 2.48273 + vertex 1.67285 1.06382 2.4841 + endloop + endfacet + facet normal 0.283755 -0.223633 0.932454 + outer loop + vertex 1.67242 1.0589 2.48305 + vertex 1.67285 1.06382 2.4841 + vertex 1.66759 1.05905 2.48456 + endloop + endfacet + facet normal 0.283288 -0.228437 0.931431 + outer loop + vertex 1.66752 1.05386 2.48331 + vertex 1.67242 1.0589 2.48305 + vertex 1.66759 1.05905 2.48456 + endloop + endfacet + facet normal 0.285878 -0.228288 0.930676 + outer loop + vertex 1.66759 1.05905 2.48456 + vertex 1.6627 1.05371 2.48475 + vertex 1.66752 1.05386 2.48331 + endloop + endfacet + facet normal 0.285765 -0.231189 0.929994 + outer loop + vertex 1.66265 1.04869 2.48352 + vertex 1.66752 1.05386 2.48331 + vertex 1.6627 1.05371 2.48475 + endloop + endfacet + facet normal 0.286496 -0.231144 0.929781 + outer loop + vertex 1.6627 1.05371 2.48475 + vertex 1.65793 1.04858 2.48495 + vertex 1.66265 1.04869 2.48352 + endloop + endfacet + facet normal 0.286483 -0.231417 0.929717 + outer loop + vertex 1.65774 1.04363 2.48378 + vertex 1.66265 1.04869 2.48352 + vertex 1.65793 1.04858 2.48495 + endloop + endfacet + facet normal 0.286322 -0.231422 0.929765 + outer loop + vertex 1.65793 1.04858 2.48495 + vertex 1.6532 1.04357 2.48515 + vertex 1.65774 1.04363 2.48378 + endloop + endfacet + facet normal 0.286347 -0.230969 0.92987 + outer loop + vertex 1.65288 1.03883 2.48408 + vertex 1.65774 1.04363 2.48378 + vertex 1.6532 1.04357 2.48515 + endloop + endfacet + facet normal 0.287278 -0.230967 0.929583 + outer loop + vertex 1.6532 1.04357 2.48515 + vertex 1.64913 1.03916 2.48532 + vertex 1.65288 1.03883 2.48408 + endloop + endfacet + facet normal 0.287062 -0.232375 0.929299 + outer loop + vertex 1.64761 1.0341 2.48452 + vertex 1.65288 1.03883 2.48408 + vertex 1.64913 1.03916 2.48532 + endloop + endfacet + facet normal 0.28834 -0.232686 0.928826 + outer loop + vertex 1.64761 1.0341 2.48452 + vertex 1.64913 1.03916 2.48532 + vertex 1.64508 1.03634 2.48587 + endloop + endfacet + facet normal 0.28807 -0.232995 0.928832 + outer loop + vertex 1.64346 1.03269 2.48546 + vertex 1.64761 1.0341 2.48452 + vertex 1.64508 1.03634 2.48587 + endloop + endfacet + facet normal 0.284615 -0.231616 0.930241 + outer loop + vertex 1.64508 1.03634 2.48587 + vertex 1.64103 1.03354 2.48641 + vertex 1.64346 1.03269 2.48546 + endloop + endfacet + facet normal 0.283471 -0.234463 0.929877 + outer loop + vertex 1.64346 1.03269 2.48546 + vertex 1.64103 1.03354 2.48641 + vertex 1.64068 1.03046 2.48574 + endloop + endfacet + facet normal 0.287285 -0.239527 0.927413 + outer loop + vertex 1.64346 1.03269 2.48546 + vertex 1.64068 1.03046 2.48574 + vertex 1.64273 1.02883 2.48469 + endloop + endfacet + facet normal 0.285381 -0.241904 0.927384 + outer loop + vertex 1.64273 1.02883 2.48469 + vertex 1.64068 1.03046 2.48574 + vertex 1.63894 1.02766 2.48555 + endloop + endfacet + facet normal 0.284761 -0.239255 0.928261 + outer loop + vertex 1.63894 1.02766 2.48555 + vertex 1.63795 1.02376 2.48484 + vertex 1.64273 1.02883 2.48469 + endloop + endfacet + facet normal 0.284938 -0.239425 0.928163 + outer loop + vertex 1.64273 1.02883 2.48469 + vertex 1.63795 1.02376 2.48484 + vertex 1.64269 1.02388 2.48342 + endloop + endfacet + facet normal 0.28651 -0.239319 0.927706 + outer loop + vertex 1.64269 1.02388 2.48342 + vertex 1.64755 1.02899 2.48324 + vertex 1.64273 1.02883 2.48469 + endloop + endfacet + facet normal 0.286612 -0.236752 0.928333 + outer loop + vertex 1.64761 1.0341 2.48452 + vertex 1.64273 1.02883 2.48469 + vertex 1.64755 1.02899 2.48324 + endloop + endfacet + facet normal 0.287131 -0.23672 0.928181 + outer loop + vertex 1.64755 1.02899 2.48324 + vertex 1.65245 1.034 2.483 + vertex 1.64761 1.0341 2.48452 + endloop + endfacet + facet normal 0.285839 -0.235419 0.92891 + outer loop + vertex 1.65231 1.02919 2.48183 + vertex 1.65245 1.034 2.483 + vertex 1.64755 1.02899 2.48324 + endloop + endfacet + facet normal 0.285769 -0.237674 0.928357 + outer loop + vertex 1.65231 1.02919 2.48183 + vertex 1.64755 1.02899 2.48324 + vertex 1.64744 1.02402 2.482 + endloop + endfacet + facet normal 0.285131 -0.237062 0.92871 + outer loop + vertex 1.65124 1.02523 2.48114 + vertex 1.65231 1.02919 2.48183 + vertex 1.64744 1.02402 2.482 + endloop + endfacet + facet normal 0.285301 -0.237764 0.928478 + outer loop + vertex 1.65124 1.02523 2.48114 + vertex 1.64744 1.02402 2.482 + vertex 1.64927 1.02217 2.48096 + endloop + endfacet + facet normal 0.286434 -0.238465 0.927949 + outer loop + vertex 1.65306 1.02341 2.48011 + vertex 1.65124 1.02523 2.48114 + vertex 1.64927 1.02217 2.48096 + endloop + endfacet + facet normal 0.287078 -0.241041 0.927084 + outer loop + vertex 1.64927 1.02217 2.48096 + vertex 1.64831 1.0184 2.48028 + vertex 1.65306 1.02341 2.48011 + endloop + endfacet + facet normal 0.288215 -0.242141 0.926445 + outer loop + vertex 1.65306 1.02341 2.48011 + vertex 1.64831 1.0184 2.48028 + vertex 1.65283 1.01853 2.47891 + endloop + endfacet + facet normal 0.286055 -0.242198 0.927099 + outer loop + vertex 1.65283 1.01853 2.47891 + vertex 1.6578 1.02358 2.47869 + vertex 1.65306 1.02341 2.48011 + endloop + endfacet + facet normal 0.28614 -0.239915 0.927666 + outer loop + vertex 1.65796 1.02861 2.47995 + vertex 1.65306 1.02341 2.48011 + vertex 1.6578 1.02358 2.47869 + endloop + endfacet + facet normal 0.283517 -0.240027 0.928442 + outer loop + vertex 1.6578 1.02358 2.47869 + vertex 1.66271 1.02876 2.47853 + vertex 1.65796 1.02861 2.47995 + endloop + endfacet + facet normal 0.283668 -0.236348 0.92934 + outer loop + vertex 1.66274 1.03375 2.47979 + vertex 1.65796 1.02861 2.47995 + vertex 1.66271 1.02876 2.47853 + endloop + endfacet + facet normal 0.282948 -0.236396 0.929547 + outer loop + vertex 1.66271 1.02876 2.47853 + vertex 1.66758 1.0339 2.47836 + vertex 1.66274 1.03375 2.47979 + endloop + endfacet + facet normal 0.283135 -0.231725 0.930666 + outer loop + vertex 1.66762 1.03904 2.47962 + vertex 1.66274 1.03375 2.47979 + vertex 1.66758 1.0339 2.47836 + endloop + endfacet + facet normal 0.281564 -0.231823 0.931118 + outer loop + vertex 1.66758 1.0339 2.47836 + vertex 1.67247 1.0389 2.47812 + vertex 1.66762 1.03904 2.47962 + endloop + endfacet + facet normal 0.281849 -0.228851 0.931766 + outer loop + vertex 1.67247 1.0389 2.47812 + vertex 1.6729 1.04375 2.47919 + vertex 1.66762 1.03904 2.47962 + endloop + endfacet + facet normal 0.280457 -0.227217 0.932586 + outer loop + vertex 1.66762 1.03904 2.47962 + vertex 1.6729 1.04375 2.47919 + vertex 1.66915 1.04408 2.4804 + endloop + endfacet + facet normal 0.282868 -0.227813 0.931712 + outer loop + vertex 1.66762 1.03904 2.47962 + vertex 1.66915 1.04408 2.4804 + vertex 1.66509 1.04128 2.48094 + endloop + endfacet + facet normal 0.282776 -0.227919 0.931714 + outer loop + vertex 1.66346 1.03763 2.48054 + vertex 1.66762 1.03904 2.47962 + vertex 1.66509 1.04128 2.48094 + endloop + endfacet + facet normal 0.28319 -0.228085 0.931547 + outer loop + vertex 1.66509 1.04128 2.48094 + vertex 1.66105 1.03849 2.48149 + vertex 1.66346 1.03763 2.48054 + endloop + endfacet + facet normal 0.282565 -0.22964 0.931355 + outer loop + vertex 1.66346 1.03763 2.48054 + vertex 1.66105 1.03849 2.48149 + vertex 1.6607 1.03539 2.48083 + endloop + endfacet + facet normal 0.284844 -0.232641 0.929915 + outer loop + vertex 1.66346 1.03763 2.48054 + vertex 1.6607 1.03539 2.48083 + vertex 1.66274 1.03375 2.47979 + endloop + endfacet + facet normal 0.283725 -0.234029 0.929909 + outer loop + vertex 1.66274 1.03375 2.47979 + vertex 1.6607 1.03539 2.48083 + vertex 1.65896 1.03256 2.48065 + endloop + endfacet + facet normal 0.28289 -0.233543 0.930285 + outer loop + vertex 1.6607 1.03539 2.48083 + vertex 1.65702 1.03417 2.48164 + vertex 1.65896 1.03256 2.48065 + endloop + endfacet + facet normal 0.282379 -0.234158 0.930286 + outer loop + vertex 1.65896 1.03256 2.48065 + vertex 1.65702 1.03417 2.48164 + vertex 1.65612 1.03045 2.48098 + endloop + endfacet + facet normal 0.284396 -0.237091 0.928928 + outer loop + vertex 1.65896 1.03256 2.48065 + vertex 1.65612 1.03045 2.48098 + vertex 1.65796 1.02861 2.47995 + endloop + endfacet + facet normal 0.284307 -0.237182 0.928932 + outer loop + vertex 1.65796 1.02861 2.47995 + vertex 1.65612 1.03045 2.48098 + vertex 1.65415 1.02741 2.4808 + endloop + endfacet + facet normal 0.284596 -0.23736 0.928798 + outer loop + vertex 1.65612 1.03045 2.48098 + vertex 1.65231 1.02919 2.48183 + vertex 1.65415 1.02741 2.4808 + endloop + endfacet + facet normal 0.283843 -0.234422 0.929774 + outer loop + vertex 1.65612 1.03045 2.48098 + vertex 1.65702 1.03417 2.48164 + vertex 1.65231 1.02919 2.48183 + endloop + endfacet + facet normal 0.28186 -0.229608 0.931577 + outer loop + vertex 1.6607 1.03539 2.48083 + vertex 1.66105 1.03849 2.48149 + vertex 1.65702 1.03417 2.48164 + endloop + endfacet + facet normal 0.284046 -0.231684 0.930398 + outer loop + vertex 1.66105 1.03849 2.48149 + vertex 1.65729 1.03876 2.4827 + vertex 1.65702 1.03417 2.48164 + endloop + endfacet + facet normal 0.285043 -0.231672 0.930096 + outer loop + vertex 1.65702 1.03417 2.48164 + vertex 1.65729 1.03876 2.4827 + vertex 1.65245 1.034 2.483 + endloop + endfacet + facet normal 0.286165 -0.232851 0.929457 + outer loop + vertex 1.65245 1.034 2.483 + vertex 1.65729 1.03876 2.4827 + vertex 1.65288 1.03883 2.48408 + endloop + endfacet + facet normal 0.284407 -0.229088 0.93093 + outer loop + vertex 1.66105 1.03849 2.48149 + vertex 1.66257 1.04351 2.48226 + vertex 1.65729 1.03876 2.4827 + endloop + endfacet + facet normal 0.285995 -0.230942 0.929985 + outer loop + vertex 1.65729 1.03876 2.4827 + vertex 1.66257 1.04351 2.48226 + vertex 1.65774 1.04363 2.48378 + endloop + endfacet + facet normal 0.283717 -0.228918 0.931183 + outer loop + vertex 1.66257 1.04351 2.48226 + vertex 1.66105 1.03849 2.48149 + vertex 1.66509 1.04128 2.48094 + endloop + endfacet + facet normal 0.284697 -0.227794 0.931159 + outer loop + vertex 1.66673 1.04496 2.48134 + vertex 1.66257 1.04351 2.48226 + vertex 1.66509 1.04128 2.48094 + endloop + endfacet + facet normal 0.285436 -0.230476 0.930272 + outer loop + vertex 1.66673 1.04496 2.48134 + vertex 1.66749 1.04888 2.48208 + vertex 1.66257 1.04351 2.48226 + endloop + endfacet + facet normal 0.285925 -0.230933 0.930009 + outer loop + vertex 1.66749 1.04888 2.48208 + vertex 1.66265 1.04869 2.48352 + vertex 1.66257 1.04351 2.48226 + endloop + endfacet + facet normal 0.2846 -0.230368 0.930555 + outer loop + vertex 1.66954 1.04725 2.48105 + vertex 1.66749 1.04888 2.48208 + vertex 1.66673 1.04496 2.48134 + endloop + endfacet + facet normal 0.282098 -0.227106 0.932118 + outer loop + vertex 1.66954 1.04725 2.48105 + vertex 1.66673 1.04496 2.48134 + vertex 1.66915 1.04408 2.4804 + endloop + endfacet + facet normal 0.280274 -0.226997 0.932695 + outer loop + vertex 1.66954 1.04725 2.48105 + vertex 1.66915 1.04408 2.4804 + vertex 1.67323 1.04847 2.48024 + endloop + endfacet + facet normal 0.280999 -0.229794 0.931791 + outer loop + vertex 1.67323 1.04847 2.48024 + vertex 1.67132 1.05014 2.48122 + vertex 1.66954 1.04725 2.48105 + endloop + endfacet + facet normal 0.280994 -0.229801 0.931791 + outer loop + vertex 1.67418 1.05227 2.48089 + vertex 1.67132 1.05014 2.48122 + vertex 1.67323 1.04847 2.48024 + endloop + endfacet + facet normal 0.287949 -0.231127 0.929336 + outer loop + vertex 1.67418 1.05227 2.48089 + vertex 1.67323 1.04847 2.48024 + vertex 1.67796 1.05351 2.48003 + endloop + endfacet + facet normal 0.28892 -0.234959 0.928073 + outer loop + vertex 1.67796 1.05351 2.48003 + vertex 1.67611 1.05528 2.48105 + vertex 1.67418 1.05227 2.48089 + endloop + endfacet + facet normal 0.282783 -0.231172 0.93091 + outer loop + vertex 1.67611 1.05528 2.48105 + vertex 1.6723 1.05403 2.4819 + vertex 1.67418 1.05227 2.48089 + endloop + endfacet + facet normal 0.28161 -0.226547 0.932401 + outer loop + vertex 1.67611 1.05528 2.48105 + vertex 1.67701 1.05906 2.48169 + vertex 1.6723 1.05403 2.4819 + endloop + endfacet + facet normal 0.283764 -0.228613 0.931243 + outer loop + vertex 1.67701 1.05906 2.48169 + vertex 1.67242 1.0589 2.48305 + vertex 1.6723 1.05403 2.4819 + endloop + endfacet + facet normal 0.288794 -0.227819 0.929891 + outer loop + vertex 1.67895 1.05744 2.48069 + vertex 1.67701 1.05906 2.48169 + vertex 1.67611 1.05528 2.48105 + endloop + endfacet + facet normal 0.292071 -0.22384 0.929833 + outer loop + vertex 1.6807 1.06036 2.48085 + vertex 1.67701 1.05906 2.48169 + vertex 1.67895 1.05744 2.48069 + endloop + endfacet + facet normal 0.314593 -0.236743 0.91923 + outer loop + vertex 1.68268 1.05873 2.47975 + vertex 1.6807 1.06036 2.48085 + vertex 1.67895 1.05744 2.48069 + endloop + endfacet + facet normal 0.314479 -0.236302 0.919383 + outer loop + vertex 1.67895 1.05744 2.48069 + vertex 1.67796 1.05351 2.48003 + vertex 1.68268 1.05873 2.47975 + endloop + endfacet + facet normal 0.299565 -0.222343 0.927806 + outer loop + vertex 1.68268 1.05873 2.47975 + vertex 1.67796 1.05351 2.48003 + vertex 1.68262 1.05372 2.47857 + endloop + endfacet + facet normal 0.329419 -0.220452 0.918087 + outer loop + vertex 1.68262 1.05372 2.47857 + vertex 1.68717 1.0588 2.47815 + vertex 1.68268 1.05873 2.47975 + endloop + endfacet + facet normal 0.330327 -0.205225 0.921285 + outer loop + vertex 1.68745 1.06413 2.47925 + vertex 1.68268 1.05873 2.47975 + vertex 1.68717 1.0588 2.47815 + endloop + endfacet + facet normal 0.375681 -0.204033 0.90401 + outer loop + vertex 1.68717 1.0588 2.47815 + vertex 1.69152 1.0632 2.47734 + vertex 1.68745 1.06413 2.47925 + endloop + endfacet + facet normal 0.383236 -0.176504 0.906629 + outer loop + vertex 1.69152 1.0632 2.47734 + vertex 1.69271 1.0689 2.47795 + vertex 1.68745 1.06413 2.47925 + endloop + endfacet + facet normal 0.411647 -0.213444 0.885996 + outer loop + vertex 1.68745 1.06413 2.47925 + vertex 1.69271 1.0689 2.47795 + vertex 1.6889 1.06957 2.47988 + endloop + endfacet + facet normal 0.36912 -0.204459 0.906613 + outer loop + vertex 1.68745 1.06413 2.47925 + vertex 1.6889 1.06957 2.47988 + vertex 1.68499 1.0665 2.48078 + endloop + endfacet + facet normal 0.355555 -0.219724 0.908461 + outer loop + vertex 1.68345 1.06272 2.48047 + vertex 1.68745 1.06413 2.47925 + vertex 1.68499 1.0665 2.48078 + endloop + endfacet + facet normal 0.318546 -0.206104 0.92523 + outer loop + vertex 1.68499 1.0665 2.48078 + vertex 1.68101 1.06352 2.48149 + vertex 1.68345 1.06272 2.48047 + endloop + endfacet + facet normal 0.314381 -0.217322 0.924087 + outer loop + vertex 1.68345 1.06272 2.48047 + vertex 1.68101 1.06352 2.48149 + vertex 1.6807 1.06036 2.48085 + endloop + endfacet + facet normal 0.322209 -0.22727 0.918983 + outer loop + vertex 1.68345 1.06272 2.48047 + vertex 1.6807 1.06036 2.48085 + vertex 1.68268 1.05873 2.47975 + endloop + endfacet + facet normal 0.322061 -0.211367 0.922822 + outer loop + vertex 1.68232 1.06858 2.48219 + vertex 1.68101 1.06352 2.48149 + vertex 1.68499 1.0665 2.48078 + endloop + endfacet + facet normal 0.358514 -0.231644 0.904328 + outer loop + vertex 1.68345 1.06272 2.48047 + vertex 1.68268 1.05873 2.47975 + vertex 1.68745 1.06413 2.47925 + endloop + endfacet + facet normal 0.419738 -0.17857 0.889906 + outer loop + vertex 1.69242 1.07432 2.47918 + vertex 1.6889 1.06957 2.47988 + vertex 1.69271 1.0689 2.47795 + endloop + endfacet + facet normal 0.35382 -0.179858 0.917858 + outer loop + vertex 1.69094 1.05858 2.47666 + vertex 1.69152 1.0632 2.47734 + vertex 1.68717 1.0588 2.47815 + endloop + endfacet + facet normal 0.351303 -0.200415 0.91456 + outer loop + vertex 1.69094 1.05858 2.47666 + vertex 1.68717 1.0588 2.47815 + vertex 1.6873 1.05402 2.47706 + endloop + endfacet + facet normal 0.335789 -0.187269 0.923134 + outer loop + vertex 1.69091 1.05543 2.47603 + vertex 1.69094 1.05858 2.47666 + vertex 1.6873 1.05402 2.47706 + endloop + endfacet + facet normal 0.336884 -0.190896 0.921991 + outer loop + vertex 1.69091 1.05543 2.47603 + vertex 1.6873 1.05402 2.47706 + vertex 1.68952 1.05262 2.47596 + endloop + endfacet + facet normal 0.390047 -0.216484 0.894985 + outer loop + vertex 1.69288 1.05382 2.47478 + vertex 1.69091 1.05543 2.47603 + vertex 1.68952 1.05262 2.47596 + endloop + endfacet + facet normal 0.391189 -0.221338 0.893297 + outer loop + vertex 1.68952 1.05262 2.47596 + vertex 1.68923 1.04938 2.47528 + vertex 1.69288 1.05382 2.47478 + endloop + endfacet + facet normal 0.373009 -0.205058 0.904884 + outer loop + vertex 1.69288 1.05382 2.47478 + vertex 1.68923 1.04938 2.47528 + vertex 1.69271 1.04892 2.47374 + endloop + endfacet + facet normal 0.367879 -0.230296 0.900904 + outer loop + vertex 1.68774 1.04412 2.47454 + vertex 1.69271 1.04892 2.47374 + vertex 1.68923 1.04938 2.47528 + endloop + endfacet + facet normal 0.345541 -0.204742 0.915796 + outer loop + vertex 1.69262 1.04374 2.47262 + vertex 1.69271 1.04892 2.47374 + vertex 1.68774 1.04412 2.47454 + endloop + endfacet + facet normal 0.343517 -0.218636 0.913342 + outer loop + vertex 1.68751 1.03875 2.47335 + vertex 1.69262 1.04374 2.47262 + vertex 1.68774 1.04412 2.47454 + endloop + endfacet + facet normal 0.305856 -0.219895 0.926336 + outer loop + vertex 1.68774 1.04412 2.47454 + vertex 1.68281 1.03867 2.47488 + vertex 1.68751 1.03875 2.47335 + endloop + endfacet + facet normal 0.305227 -0.230789 0.92389 + outer loop + vertex 1.68271 1.03363 2.47365 + vertex 1.68751 1.03875 2.47335 + vertex 1.68281 1.03867 2.47488 + endloop + endfacet + facet normal 0.287169 -0.231779 0.929415 + outer loop + vertex 1.68281 1.03867 2.47488 + vertex 1.678 1.03349 2.47508 + vertex 1.68271 1.03363 2.47365 + endloop + endfacet + facet normal 0.286883 -0.23854 0.927791 + outer loop + vertex 1.67774 1.02851 2.47388 + vertex 1.68271 1.03363 2.47365 + vertex 1.678 1.03349 2.47508 + endloop + endfacet + facet normal 0.28451 -0.238591 0.928509 + outer loop + vertex 1.678 1.03349 2.47508 + vertex 1.6731 1.0283 2.47524 + vertex 1.67774 1.02851 2.47388 + endloop + endfacet + facet normal 0.284357 -0.244136 0.927113 + outer loop + vertex 1.67278 1.02352 2.47408 + vertex 1.67774 1.02851 2.47388 + vertex 1.6731 1.0283 2.47524 + endloop + endfacet + facet normal 0.285332 -0.24413 0.926815 + outer loop + vertex 1.6731 1.0283 2.47524 + vertex 1.66835 1.02331 2.47539 + vertex 1.67278 1.02352 2.47408 + endloop + endfacet + facet normal 0.285242 -0.247405 0.925974 + outer loop + vertex 1.66797 1.01873 2.47428 + vertex 1.67278 1.02352 2.47408 + vertex 1.66835 1.02331 2.47539 + endloop + endfacet + facet normal 0.284249 -0.247397 0.926281 + outer loop + vertex 1.66835 1.02331 2.47539 + vertex 1.66426 1.019 2.47549 + vertex 1.66797 1.01873 2.47428 + endloop + endfacet + facet normal 0.28434 -0.246773 0.92642 + outer loop + vertex 1.66267 1.01404 2.47466 + vertex 1.66797 1.01873 2.47428 + vertex 1.66426 1.019 2.47549 + endloop + endfacet + facet normal 0.284386 -0.246785 0.926403 + outer loop + vertex 1.66267 1.01404 2.47466 + vertex 1.66426 1.019 2.47549 + vertex 1.66017 1.01625 2.47602 + endloop + endfacet + facet normal 0.285248 -0.245808 0.926397 + outer loop + vertex 1.6585 1.01264 2.47557 + vertex 1.66267 1.01404 2.47466 + vertex 1.66017 1.01625 2.47602 + endloop + endfacet + facet normal 0.288318 -0.247073 0.92511 + outer loop + vertex 1.66017 1.01625 2.47602 + vertex 1.65609 1.01349 2.47655 + vertex 1.6585 1.01264 2.47557 + endloop + endfacet + facet normal 0.28921 -0.244889 0.925412 + outer loop + vertex 1.6585 1.01264 2.47557 + vertex 1.65609 1.01349 2.47655 + vertex 1.65571 1.01041 2.47586 + endloop + endfacet + facet normal 0.288546 -0.244003 0.925853 + outer loop + vertex 1.6585 1.01264 2.47557 + vertex 1.65571 1.01041 2.47586 + vertex 1.65775 1.00878 2.47479 + endloop + endfacet + facet normal 0.288922 -0.243536 0.925858 + outer loop + vertex 1.65775 1.00878 2.47479 + vertex 1.65571 1.01041 2.47586 + vertex 1.65396 1.00759 2.47566 + endloop + endfacet + facet normal 0.289814 -0.247278 0.924587 + outer loop + vertex 1.65396 1.00759 2.47566 + vertex 1.65297 1.00368 2.47492 + vertex 1.65775 1.00878 2.47479 + endloop + endfacet + facet normal 0.288508 -0.246035 0.925327 + outer loop + vertex 1.65775 1.00878 2.47479 + vertex 1.65297 1.00368 2.47492 + vertex 1.6577 1.00384 2.47349 + endloop + endfacet + facet normal 0.286916 -0.24614 0.925794 + outer loop + vertex 1.6577 1.00384 2.47349 + vertex 1.66258 1.00897 2.47334 + vertex 1.65775 1.00878 2.47479 + endloop + endfacet + facet normal 0.286933 -0.245684 0.92591 + outer loop + vertex 1.66267 1.01404 2.47466 + vertex 1.65775 1.00878 2.47479 + vertex 1.66258 1.00897 2.47334 + endloop + endfacet + facet normal 0.284116 -0.245845 0.926735 + outer loop + vertex 1.66258 1.00897 2.47334 + vertex 1.66753 1.01398 2.47315 + vertex 1.66267 1.01404 2.47466 + endloop + endfacet + facet normal 0.284806 -0.246542 0.926338 + outer loop + vertex 1.66735 1.00917 2.47193 + vertex 1.66753 1.01398 2.47315 + vertex 1.66258 1.00897 2.47334 + endloop + endfacet + facet normal 0.284771 -0.247603 0.926066 + outer loop + vertex 1.66735 1.00917 2.47193 + vertex 1.66258 1.00897 2.47334 + vertex 1.66244 1.00403 2.47207 + endloop + endfacet + facet normal 0.282815 -0.24662 0.926927 + outer loop + vertex 1.67224 1.01425 2.47179 + vertex 1.66753 1.01398 2.47315 + vertex 1.66735 1.00917 2.47193 + endloop + endfacet + facet normal 0.282833 -0.24556 0.927203 + outer loop + vertex 1.67224 1.01425 2.47179 + vertex 1.67244 1.01887 2.47295 + vertex 1.66753 1.01398 2.47315 + endloop + endfacet + facet normal 0.283689 -0.24644 0.926708 + outer loop + vertex 1.66753 1.01398 2.47315 + vertex 1.67244 1.01887 2.47295 + vertex 1.66797 1.01873 2.47428 + endloop + endfacet + facet normal 0.2831 -0.245551 0.927124 + outer loop + vertex 1.67696 1.01917 2.47165 + vertex 1.67244 1.01887 2.47295 + vertex 1.67224 1.01425 2.47179 + endloop + endfacet + facet normal 0.282815 -0.245273 0.927285 + outer loop + vertex 1.67605 1.01552 2.47096 + vertex 1.67696 1.01917 2.47165 + vertex 1.67224 1.01425 2.47179 + endloop + endfacet + facet normal 0.282894 -0.245577 0.92718 + outer loop + vertex 1.67605 1.01552 2.47096 + vertex 1.67224 1.01425 2.47179 + vertex 1.6741 1.01253 2.47077 + endloop + endfacet + facet normal 0.284012 -0.246274 0.926653 + outer loop + vertex 1.67791 1.01372 2.46992 + vertex 1.67605 1.01552 2.47096 + vertex 1.6741 1.01253 2.47077 + endloop + endfacet + facet normal 0.284622 -0.248868 0.925773 + outer loop + vertex 1.6741 1.01253 2.47077 + vertex 1.67301 1.00856 2.47004 + vertex 1.67791 1.01372 2.46992 + endloop + endfacet + facet normal 0.283555 -0.247842 0.926375 + outer loop + vertex 1.67791 1.01372 2.46992 + vertex 1.67301 1.00856 2.47004 + vertex 1.67776 1.00873 2.46863 + endloop + endfacet + facet normal 0.283469 -0.249984 0.925826 + outer loop + vertex 1.67281 1.00357 2.46875 + vertex 1.67776 1.00873 2.46863 + vertex 1.67301 1.00856 2.47004 + endloop + endfacet + facet normal 0.282685 -0.249221 0.926271 + outer loop + vertex 1.67767 1.00375 2.46731 + vertex 1.67776 1.00873 2.46863 + vertex 1.67281 1.00357 2.46875 + endloop + endfacet + facet normal 0.282618 -0.250881 0.925843 + outer loop + vertex 1.67767 1.00375 2.46731 + vertex 1.67281 1.00357 2.46875 + vertex 1.67267 0.998466 2.46741 + endloop + endfacet + facet normal 0.281436 -0.249749 0.926509 + outer loop + vertex 1.67688 0.999868 2.46651 + vertex 1.67767 1.00375 2.46731 + vertex 1.67267 0.998466 2.46741 + endloop + endfacet + facet normal 0.282072 -0.252218 0.925647 + outer loop + vertex 1.67688 0.999868 2.46651 + vertex 1.67267 0.998466 2.46741 + vertex 1.67519 0.996264 2.46604 + endloop + endfacet + facet normal 0.281618 -0.252736 0.925643 + outer loop + vertex 1.67267 0.998466 2.46741 + vertex 1.67108 0.993537 2.46655 + vertex 1.67519 0.996264 2.46604 + endloop + endfacet + facet normal 0.282965 -0.254954 0.924624 + outer loop + vertex 1.67519 0.996264 2.46604 + vertex 1.67108 0.993537 2.46655 + vertex 1.6735 0.992687 2.46557 + endloop + endfacet + facet normal 0.284048 -0.255404 0.924167 + outer loop + vertex 1.6735 0.992687 2.46557 + vertex 1.67767 0.994044 2.46467 + vertex 1.67519 0.996264 2.46604 + endloop + endfacet + facet normal 0.284478 -0.254925 0.924168 + outer loop + vertex 1.67767 0.994044 2.46467 + vertex 1.67927 0.998976 2.46553 + vertex 1.67519 0.996264 2.46604 + endloop + endfacet + facet normal 0.284967 -0.259097 0.922856 + outer loop + vertex 1.6735 0.992687 2.46557 + vertex 1.6727 0.988867 2.46474 + vertex 1.67767 0.994044 2.46467 + endloop + endfacet + facet normal 0.285001 -0.25913 0.922836 + outer loop + vertex 1.67767 0.994044 2.46467 + vertex 1.6727 0.988867 2.46474 + vertex 1.67751 0.989025 2.4633 + endloop + endfacet + facet normal 0.284269 -0.259166 0.923052 + outer loop + vertex 1.67751 0.989025 2.4633 + vertex 1.68248 0.99397 2.46316 + vertex 1.67767 0.994044 2.46467 + endloop + endfacet + facet normal 0.284756 -0.253929 0.924356 + outer loop + vertex 1.68248 0.99397 2.46316 + vertex 1.68296 0.998712 2.46432 + vertex 1.67767 0.994044 2.46467 + endloop + endfacet + facet normal 0.285912 -0.255296 0.923622 + outer loop + vertex 1.67767 0.994044 2.46467 + vertex 1.68296 0.998712 2.46432 + vertex 1.67927 0.998976 2.46553 + endloop + endfacet + facet normal 0.286472 -0.251486 0.924494 + outer loop + vertex 1.68335 1.00328 2.46544 + vertex 1.67927 0.998976 2.46553 + vertex 1.68296 0.998712 2.46432 + endloop + endfacet + facet normal 0.292766 -0.251532 0.922507 + outer loop + vertex 1.68296 0.998712 2.46432 + vertex 1.68776 1.00357 2.46412 + vertex 1.68335 1.00328 2.46544 + endloop + endfacet + facet normal 0.292798 -0.249289 0.923106 + outer loop + vertex 1.68812 1.00832 2.46529 + vertex 1.68335 1.00328 2.46544 + vertex 1.68776 1.00357 2.46412 + endloop + endfacet + facet normal 0.30992 -0.249207 0.917521 + outer loop + vertex 1.68776 1.00357 2.46412 + vertex 1.69265 1.00866 2.46385 + vertex 1.68812 1.00832 2.46529 + endloop + endfacet + facet normal 0.309946 -0.246096 0.918352 + outer loop + vertex 1.693 1.0136 2.46505 + vertex 1.68812 1.00832 2.46529 + vertex 1.69265 1.00866 2.46385 + endloop + endfacet + facet normal 0.342015 -0.245658 0.907016 + outer loop + vertex 1.69265 1.00866 2.46385 + vertex 1.69733 1.0137 2.46345 + vertex 1.693 1.0136 2.46505 + endloop + endfacet + facet normal 0.342967 -0.231197 0.910451 + outer loop + vertex 1.69769 1.01877 2.4646 + vertex 1.693 1.0136 2.46505 + vertex 1.69733 1.0137 2.46345 + endloop + endfacet + facet normal 0.371773 -0.258952 0.891476 + outer loop + vertex 1.6941 1.01762 2.46577 + vertex 1.693 1.0136 2.46505 + vertex 1.69769 1.01877 2.4646 + endloop + endfacet + facet normal 0.370152 -0.250892 0.89445 + outer loop + vertex 1.69769 1.01877 2.4646 + vertex 1.6958 1.02056 2.46588 + vertex 1.6941 1.01762 2.46577 + endloop + endfacet + facet normal 0.326581 -0.226566 0.917613 + outer loop + vertex 1.6958 1.02056 2.46588 + vertex 1.69213 1.01925 2.46687 + vertex 1.6941 1.01762 2.46577 + endloop + endfacet + facet normal 0.318764 -0.236225 0.917926 + outer loop + vertex 1.6941 1.01762 2.46577 + vertex 1.69213 1.01925 2.46687 + vertex 1.69128 1.01543 2.46618 + endloop + endfacet + facet normal 0.323722 -0.215788 0.921216 + outer loop + vertex 1.6958 1.02056 2.46588 + vertex 1.69593 1.02366 2.46656 + vertex 1.69213 1.01925 2.46687 + endloop + endfacet + facet normal 0.375044 -0.213806 0.902014 + outer loop + vertex 1.69848 1.02289 2.46532 + vertex 1.69593 1.02366 2.46656 + vertex 1.6958 1.02056 2.46588 + endloop + endfacet + facet normal 0.387772 -0.230753 0.892405 + outer loop + vertex 1.69848 1.02289 2.46532 + vertex 1.6958 1.02056 2.46588 + vertex 1.69769 1.01877 2.4646 + endloop + endfacet + facet normal 0.441429 -0.236317 0.865618 + outer loop + vertex 1.69848 1.02289 2.46532 + vertex 1.69769 1.01877 2.4646 + vertex 1.70251 1.02409 2.46359 + endloop + endfacet + facet normal 0.43686 -0.206895 0.875413 + outer loop + vertex 1.69848 1.02289 2.46532 + vertex 1.70251 1.02409 2.46359 + vertex 1.6997 1.02677 2.46563 + endloop + endfacet + facet normal 0.461383 -0.176728 0.869421 + outer loop + vertex 1.70251 1.02409 2.46359 + vertex 1.70332 1.02991 2.46435 + vertex 1.6997 1.02677 2.46563 + endloop + endfacet + facet normal 0.473303 -0.194632 0.859129 + outer loop + vertex 1.6997 1.02677 2.46563 + vertex 1.70332 1.02991 2.46435 + vertex 1.70056 1.03146 2.46622 + endloop + endfacet + facet normal 0.403368 -0.186397 0.895852 + outer loop + vertex 1.70056 1.03146 2.46622 + vertex 1.6966 1.02808 2.4673 + vertex 1.6997 1.02677 2.46563 + endloop + endfacet + facet normal 0.393861 -0.208229 0.895273 + outer loop + vertex 1.6966 1.02808 2.4673 + vertex 1.69593 1.02366 2.46656 + vertex 1.6997 1.02677 2.46563 + endloop + endfacet + facet normal 0.417009 -0.205806 0.885295 + outer loop + vertex 1.69774 1.0336 2.46804 + vertex 1.6966 1.02808 2.4673 + vertex 1.70056 1.03146 2.46622 + endloop + endfacet + facet normal 0.434262 -0.180673 0.882482 + outer loop + vertex 1.70148 1.03529 2.46655 + vertex 1.69774 1.0336 2.46804 + vertex 1.70056 1.03146 2.46622 + endloop + endfacet + facet normal 0.514262 -0.195647 0.835019 + outer loop + vertex 1.70373 1.03453 2.46499 + vertex 1.70148 1.03529 2.46655 + vertex 1.70056 1.03146 2.46622 + endloop + endfacet + facet normal 0.434417 -0.181174 0.882302 + outer loop + vertex 1.70148 1.03529 2.46655 + vertex 1.70115 1.03853 2.46738 + vertex 1.69774 1.0336 2.46804 + endloop + endfacet + facet normal 0.455357 -0.197582 0.868108 + outer loop + vertex 1.70115 1.03853 2.46738 + vertex 1.69751 1.03899 2.4694 + vertex 1.69774 1.0336 2.46804 + endloop + endfacet + facet normal 0.395929 -0.206867 0.894677 + outer loop + vertex 1.69751 1.03899 2.4694 + vertex 1.69322 1.03362 2.47005 + vertex 1.69774 1.0336 2.46804 + endloop + endfacet + facet normal 0.421291 -0.229211 0.877483 + outer loop + vertex 1.69381 1.03753 2.47079 + vertex 1.69322 1.03362 2.47005 + vertex 1.69751 1.03899 2.4694 + endloop + endfacet + facet normal 0.416578 -0.210784 0.884326 + outer loop + vertex 1.69381 1.03753 2.47079 + vertex 1.69751 1.03899 2.4694 + vertex 1.69525 1.04148 2.47105 + endloop + endfacet + facet normal 0.359463 -0.19184 0.913227 + outer loop + vertex 1.69525 1.04148 2.47105 + vertex 1.69138 1.0384 2.47193 + vertex 1.69381 1.03753 2.47079 + endloop + endfacet + facet normal 0.353838 -0.206226 0.912288 + outer loop + vertex 1.69381 1.03753 2.47079 + vertex 1.69138 1.0384 2.47193 + vertex 1.69116 1.03509 2.47126 + endloop + endfacet + facet normal 0.367032 -0.202879 0.907815 + outer loop + vertex 1.69262 1.04374 2.47262 + vertex 1.69138 1.0384 2.47193 + vertex 1.69525 1.04148 2.47105 + endloop + endfacet + facet normal 0.376907 -0.190475 0.906455 + outer loop + vertex 1.69655 1.04538 2.47133 + vertex 1.69262 1.04374 2.47262 + vertex 1.69525 1.04148 2.47105 + endloop + endfacet + facet normal 0.439374 -0.209058 0.873639 + outer loop + vertex 1.69879 1.04441 2.46998 + vertex 1.69655 1.04538 2.47133 + vertex 1.69525 1.04148 2.47105 + endloop + endfacet + facet normal 0.4479 -0.189489 0.873773 + outer loop + vertex 1.69884 1.04793 2.47071 + vertex 1.69655 1.04538 2.47133 + vertex 1.69879 1.04441 2.46998 + endloop + endfacet + facet normal 0.532661 -0.181069 0.826732 + outer loop + vertex 1.69884 1.04793 2.47071 + vertex 1.69879 1.04441 2.46998 + vertex 1.7018 1.04866 2.46896 + endloop + endfacet + facet normal 0.51064 -0.161203 0.844547 + outer loop + vertex 1.7018 1.04866 2.46896 + vertex 1.69879 1.04441 2.46998 + vertex 1.70153 1.04322 2.46809 + endloop + endfacet + facet normal 0.491814 -0.206514 0.845855 + outer loop + vertex 1.69751 1.03899 2.4694 + vertex 1.70153 1.04322 2.46809 + vertex 1.69879 1.04441 2.46998 + endloop + endfacet + facet normal 0.435289 -0.175977 0.882924 + outer loop + vertex 1.69884 1.04793 2.47071 + vertex 1.69635 1.04864 2.47208 + vertex 1.69655 1.04538 2.47133 + endloop + endfacet + facet normal 0.375417 -0.185595 0.908084 + outer loop + vertex 1.69655 1.04538 2.47133 + vertex 1.69635 1.04864 2.47208 + vertex 1.69262 1.04374 2.47262 + endloop + endfacet + facet normal 0.394486 -0.201377 0.896565 + outer loop + vertex 1.69635 1.04864 2.47208 + vertex 1.69271 1.04892 2.47374 + vertex 1.69262 1.04374 2.47262 + endloop + endfacet + facet normal 0.398117 -0.176347 0.900225 + outer loop + vertex 1.69635 1.04864 2.47208 + vertex 1.69661 1.05322 2.47286 + vertex 1.69271 1.04892 2.47374 + endloop + endfacet + facet normal 0.422875 -0.202272 0.883325 + outer loop + vertex 1.69271 1.04892 2.47374 + vertex 1.69661 1.05322 2.47286 + vertex 1.69288 1.05382 2.47478 + endloop + endfacet + facet normal 0.430284 -0.167709 0.886977 + outer loop + vertex 1.69685 1.05862 2.47377 + vertex 1.69288 1.05382 2.47478 + vertex 1.69661 1.05322 2.47286 + endloop + endfacet + facet normal 0.464457 -0.201056 0.862471 + outer loop + vertex 1.69338 1.05775 2.47543 + vertex 1.69288 1.05382 2.47478 + vertex 1.69685 1.05862 2.47377 + endloop + endfacet + facet normal 0.461678 -0.17724 0.86916 + outer loop + vertex 1.69338 1.05775 2.47543 + vertex 1.69685 1.05862 2.47377 + vertex 1.69461 1.06169 2.47558 + endloop + endfacet + facet normal 0.400167 -0.15946 0.902462 + outer loop + vertex 1.69461 1.06169 2.47558 + vertex 1.69094 1.05858 2.47666 + vertex 1.69338 1.05775 2.47543 + endloop + endfacet + facet normal 0.39171 -0.183348 0.901635 + outer loop + vertex 1.69338 1.05775 2.47543 + vertex 1.69094 1.05858 2.47666 + vertex 1.69091 1.05543 2.47603 + endloop + endfacet + facet normal 0.417179 -0.183814 0.890042 + outer loop + vertex 1.69152 1.0632 2.47734 + vertex 1.69094 1.05858 2.47666 + vertex 1.69461 1.06169 2.47558 + endloop + endfacet + facet normal 0.426495 -0.164138 0.889472 + outer loop + vertex 1.69552 1.06652 2.47604 + vertex 1.69152 1.0632 2.47734 + vertex 1.69461 1.06169 2.47558 + endloop + endfacet + facet normal 0.517394 -0.176466 0.837355 + outer loop + vertex 1.69461 1.06169 2.47558 + vertex 1.69854 1.06471 2.47379 + vertex 1.69552 1.06652 2.47604 + endloop + endfacet + facet normal 0.440512 -0.185358 0.878403 + outer loop + vertex 1.69271 1.0689 2.47795 + vertex 1.69152 1.0632 2.47734 + vertex 1.69552 1.06652 2.47604 + endloop + endfacet + facet normal 0.455986 -0.164142 0.87472 + outer loop + vertex 1.69632 1.07038 2.47634 + vertex 1.69271 1.0689 2.47795 + vertex 1.69552 1.06652 2.47604 + endloop + endfacet + facet normal 0.558772 -0.180366 0.80947 + outer loop + vertex 1.69856 1.06962 2.47463 + vertex 1.69632 1.07038 2.47634 + vertex 1.69552 1.06652 2.47604 + endloop + endfacet + facet normal 0.533434 -0.144669 0.833378 + outer loop + vertex 1.69854 1.06471 2.47379 + vertex 1.69856 1.06962 2.47463 + vertex 1.69552 1.06652 2.47604 + endloop + endfacet + facet normal 0.451897 -0.148882 0.879558 + outer loop + vertex 1.69632 1.07038 2.47634 + vertex 1.69589 1.07363 2.47711 + vertex 1.69271 1.0689 2.47795 + endloop + endfacet + facet normal 0.477483 -0.169207 0.862195 + outer loop + vertex 1.69589 1.07363 2.47711 + vertex 1.69242 1.07432 2.47918 + vertex 1.69271 1.0689 2.47795 + endloop + endfacet + facet normal 0.487038 -0.127022 0.864094 + outer loop + vertex 1.69589 1.07363 2.47711 + vertex 1.69609 1.07828 2.47769 + vertex 1.69242 1.07432 2.47918 + endloop + endfacet + facet normal 0.52235 -0.170477 0.835516 + outer loop + vertex 1.69242 1.07432 2.47918 + vertex 1.69609 1.07828 2.47769 + vertex 1.69339 1.07958 2.47964 + endloop + endfacet + facet normal 0.455979 -0.161736 0.875171 + outer loop + vertex 1.69242 1.07432 2.47918 + vertex 1.69339 1.07958 2.47964 + vertex 1.69006 1.07673 2.48085 + endloop + endfacet + facet normal 0.436954 -0.184041 0.880454 + outer loop + vertex 1.68891 1.07294 2.48063 + vertex 1.69242 1.07432 2.47918 + vertex 1.69006 1.07673 2.48085 + endloop + endfacet + facet normal 0.468892 -0.181338 0.86444 + outer loop + vertex 1.69339 1.07958 2.47964 + vertex 1.69118 1.08055 2.48104 + vertex 1.69006 1.07673 2.48085 + endloop + endfacet + facet normal 0.401842 -0.163466 0.901001 + outer loop + vertex 1.69118 1.08055 2.48104 + vertex 1.68739 1.07888 2.48243 + vertex 1.69006 1.07673 2.48085 + endloop + endfacet + facet normal 0.387532 -0.182989 0.903512 + outer loop + vertex 1.68739 1.07888 2.48243 + vertex 1.68632 1.07356 2.48181 + vertex 1.69006 1.07673 2.48085 + endloop + endfacet + facet normal 0.376292 -0.167383 0.911256 + outer loop + vertex 1.69006 1.07673 2.48085 + vertex 1.68632 1.07356 2.48181 + vertex 1.68891 1.07294 2.48063 + endloop + endfacet + facet normal 0.399805 -0.157162 0.903026 + outer loop + vertex 1.69118 1.08055 2.48104 + vertex 1.69093 1.08378 2.48172 + vertex 1.68739 1.07888 2.48243 + endloop + endfacet + facet normal 0.424962 -0.177545 0.887629 + outer loop + vertex 1.69093 1.08378 2.48172 + vertex 1.68742 1.08408 2.48345 + vertex 1.68739 1.07888 2.48243 + endloop + endfacet + facet normal 0.428924 -0.149669 0.890855 + outer loop + vertex 1.69093 1.08378 2.48172 + vertex 1.69118 1.08833 2.48236 + vertex 1.68742 1.08408 2.48345 + endloop + endfacet + facet normal 0.453853 -0.176161 0.87349 + outer loop + vertex 1.68742 1.08408 2.48345 + vertex 1.69118 1.08833 2.48236 + vertex 1.68758 1.08925 2.48442 + endloop + endfacet + facet normal 0.460045 -0.15399 0.87444 + outer loop + vertex 1.69118 1.08833 2.48236 + vertex 1.69159 1.09338 2.48303 + vertex 1.68758 1.08925 2.48442 + endloop + endfacet + facet normal 0.481902 -0.180997 0.857327 + outer loop + vertex 1.68758 1.08925 2.48442 + vertex 1.69159 1.09338 2.48303 + vertex 1.68867 1.09452 2.48491 + endloop + endfacet + facet normal 0.490875 -0.157345 0.856904 + outer loop + vertex 1.69185 1.09879 2.48388 + vertex 1.68867 1.09452 2.48491 + vertex 1.69159 1.09338 2.48303 + endloop + endfacet + facet normal 0.500924 -0.166659 0.849294 + outer loop + vertex 1.68865 1.09794 2.4856 + vertex 1.68867 1.09452 2.48491 + vertex 1.69185 1.09879 2.48388 + endloop + endfacet + facet normal 0.500456 -0.162816 0.850315 + outer loop + vertex 1.68865 1.09794 2.4856 + vertex 1.69185 1.09879 2.48388 + vertex 1.68962 1.10175 2.48575 + endloop + endfacet + facet normal 0.42619 -0.145532 0.892851 + outer loop + vertex 1.68962 1.10175 2.48575 + vertex 1.68609 1.09849 2.48691 + vertex 1.68865 1.09794 2.4856 + endloop + endfacet + facet normal 0.422252 -0.161756 0.89193 + outer loop + vertex 1.68865 1.09794 2.4856 + vertex 1.68609 1.09849 2.48691 + vertex 1.68632 1.09531 2.48622 + endloop + endfacet + facet normal 0.442762 -0.167712 0.880815 + outer loop + vertex 1.68658 1.10311 2.48754 + vertex 1.68609 1.09849 2.48691 + vertex 1.68962 1.10175 2.48575 + endloop + endfacet + facet normal 0.450429 -0.149702 0.880172 + outer loop + vertex 1.69045 1.10652 2.48614 + vertex 1.68658 1.10311 2.48754 + vertex 1.68962 1.10175 2.48575 + endloop + endfacet + facet normal 0.540693 -0.160929 0.825683 + outer loop + vertex 1.68962 1.10175 2.48575 + vertex 1.69335 1.10472 2.48389 + vertex 1.69045 1.10652 2.48614 + endloop + endfacet + facet normal 0.560023 -0.121993 0.819446 + outer loop + vertex 1.69335 1.10472 2.48389 + vertex 1.69342 1.10973 2.48459 + vertex 1.69045 1.10652 2.48614 + endloop + endfacet + facet normal 0.57989 -0.14936 0.800886 + outer loop + vertex 1.69342 1.10973 2.48459 + vertex 1.69125 1.11045 2.48629 + vertex 1.69045 1.10652 2.48614 + endloop + endfacet + facet normal 0.4604 -0.164213 0.872391 + outer loop + vertex 1.68771 1.10882 2.48802 + vertex 1.68658 1.10311 2.48754 + vertex 1.69045 1.10652 2.48614 + endloop + endfacet + facet normal 0.482816 -0.131993 0.865718 + outer loop + vertex 1.69125 1.11045 2.48629 + vertex 1.68771 1.10882 2.48802 + vertex 1.69045 1.10652 2.48614 + endloop + endfacet + facet normal 0.472389 -0.0987874 0.875837 + outer loop + vertex 1.69125 1.11045 2.48629 + vertex 1.69088 1.11386 2.48688 + vertex 1.68771 1.10882 2.48802 + endloop + endfacet + facet normal 0.527113 -0.141746 0.83789 + outer loop + vertex 1.69088 1.11386 2.48688 + vertex 1.6874 1.11422 2.48913 + vertex 1.68771 1.10882 2.48802 + endloop + endfacet + facet normal 0.535174 -0.0818678 0.840765 + outer loop + vertex 1.69088 1.11386 2.48688 + vertex 1.69098 1.11873 2.48729 + vertex 1.6874 1.11422 2.48913 + endloop + endfacet + facet normal 0.596439 -0.151992 0.788136 + outer loop + vertex 1.6874 1.11422 2.48913 + vertex 1.69098 1.11873 2.48729 + vertex 1.68826 1.11948 2.4895 + endloop + endfacet + facet normal 0.527084 -0.135606 0.838924 + outer loop + vertex 1.69185 1.09879 2.48388 + vertex 1.69335 1.10472 2.48389 + vertex 1.68962 1.10175 2.48575 + endloop + endfacet + facet normal 0.43409 -0.174148 0.883877 + outer loop + vertex 1.68865 1.09794 2.4856 + vertex 1.68632 1.09531 2.48622 + vertex 1.68867 1.09452 2.48491 + endloop + endfacet + facet normal 0.498785 -0.141746 0.855056 + outer loop + vertex 1.69685 1.05862 2.47377 + vertex 1.69854 1.06471 2.47379 + vertex 1.69461 1.06169 2.47558 + endloop + endfacet + facet normal 0.403736 -0.198383 0.893108 + outer loop + vertex 1.69338 1.05775 2.47543 + vertex 1.69091 1.05543 2.47603 + vertex 1.69288 1.05382 2.47478 + endloop + endfacet + facet normal 0.430655 -0.195837 0.881013 + outer loop + vertex 1.69751 1.03899 2.4694 + vertex 1.69879 1.04441 2.46998 + vertex 1.69525 1.04148 2.47105 + endloop + endfacet + facet normal 0.370043 -0.225996 0.901107 + outer loop + vertex 1.69381 1.03753 2.47079 + vertex 1.69116 1.03509 2.47126 + vertex 1.69322 1.03362 2.47005 + endloop + endfacet + facet normal 0.460745 -0.169041 0.871286 + outer loop + vertex 1.70115 1.03853 2.46738 + vertex 1.70153 1.04322 2.46809 + vertex 1.69751 1.03899 2.4694 + endloop + endfacet + facet normal 0.489911 -0.161931 0.856601 + outer loop + vertex 1.70332 1.02991 2.46435 + vertex 1.70373 1.03453 2.46499 + vertex 1.70056 1.03146 2.46622 + endloop + endfacet + facet normal 0.399427 -0.192392 0.89635 + outer loop + vertex 1.70251 1.02409 2.46359 + vertex 1.69769 1.01877 2.4646 + vertex 1.70164 1.01819 2.46272 + endloop + endfacet + facet normal 0.391274 -0.23021 0.891015 + outer loop + vertex 1.69733 1.0137 2.46345 + vertex 1.70164 1.01819 2.46272 + vertex 1.69769 1.01877 2.4646 + endloop + endfacet + facet normal 0.366358 -0.20356 0.907935 + outer loop + vertex 1.70114 1.01364 2.4619 + vertex 1.70164 1.01819 2.46272 + vertex 1.69733 1.0137 2.46345 + endloop + endfacet + facet normal 0.382562 -0.191989 0.903763 + outer loop + vertex 1.6997 1.02677 2.46563 + vertex 1.69593 1.02366 2.46656 + vertex 1.69848 1.02289 2.46532 + endloop + endfacet + facet normal 0.328863 -0.250643 0.910509 + outer loop + vertex 1.6941 1.01762 2.46577 + vertex 1.69128 1.01543 2.46618 + vertex 1.693 1.0136 2.46505 + endloop + endfacet + facet normal 0.321775 -0.257342 0.911173 + outer loop + vertex 1.68929 1.01231 2.466 + vertex 1.68812 1.00832 2.46529 + vertex 1.693 1.0136 2.46505 + endloop + endfacet + facet normal 0.321844 -0.257615 0.911071 + outer loop + vertex 1.693 1.0136 2.46505 + vertex 1.69128 1.01543 2.46618 + vertex 1.68929 1.01231 2.466 + endloop + endfacet + facet normal 0.297669 -0.24294 0.923241 + outer loop + vertex 1.69128 1.01543 2.46618 + vertex 1.68744 1.01413 2.46708 + vertex 1.68929 1.01231 2.466 + endloop + endfacet + facet normal 0.294551 -0.246189 0.92338 + outer loop + vertex 1.68929 1.01231 2.466 + vertex 1.68744 1.01413 2.46708 + vertex 1.68636 1.01008 2.46634 + endloop + endfacet + facet normal 0.285793 -0.244435 0.926593 + outer loop + vertex 1.68636 1.01008 2.46634 + vertex 1.68744 1.01413 2.46708 + vertex 1.68253 1.00888 2.46721 + endloop + endfacet + facet normal 0.286697 -0.248256 0.925297 + outer loop + vertex 1.68636 1.01008 2.46634 + vertex 1.68253 1.00888 2.46721 + vertex 1.68435 1.00701 2.46614 + endloop + endfacet + facet normal 0.296686 -0.254466 0.920448 + outer loop + vertex 1.68812 1.00832 2.46529 + vertex 1.68636 1.01008 2.46634 + vertex 1.68435 1.00701 2.46614 + endloop + endfacet + facet normal 0.286059 -0.248895 0.925323 + outer loop + vertex 1.68435 1.00701 2.46614 + vertex 1.68253 1.00888 2.46721 + vertex 1.68149 1.00492 2.46646 + endloop + endfacet + facet normal 0.287345 -0.25079 0.924412 + outer loop + vertex 1.68435 1.00701 2.46614 + vertex 1.68149 1.00492 2.46646 + vertex 1.68335 1.00328 2.46544 + endloop + endfacet + facet normal 0.286683 -0.251543 0.924413 + outer loop + vertex 1.68335 1.00328 2.46544 + vertex 1.68149 1.00492 2.46646 + vertex 1.6797 1.00208 2.46624 + endloop + endfacet + facet normal 0.282846 -0.249259 0.926212 + outer loop + vertex 1.68149 1.00492 2.46646 + vertex 1.67767 1.00375 2.46731 + vertex 1.6797 1.00208 2.46624 + endloop + endfacet + facet normal 0.282608 -0.248225 0.926562 + outer loop + vertex 1.68149 1.00492 2.46646 + vertex 1.68253 1.00888 2.46721 + vertex 1.67767 1.00375 2.46731 + endloop + endfacet + facet normal 0.287991 -0.246522 0.925358 + outer loop + vertex 1.68744 1.01413 2.46708 + vertex 1.68267 1.0139 2.4685 + vertex 1.68253 1.00888 2.46721 + endloop + endfacet + facet normal 0.283699 -0.246732 0.926627 + outer loop + vertex 1.68253 1.00888 2.46721 + vertex 1.68267 1.0139 2.4685 + vertex 1.67776 1.00873 2.46863 + endloop + endfacet + facet normal 0.284792 -0.247784 0.926011 + outer loop + vertex 1.67776 1.00873 2.46863 + vertex 1.68267 1.0139 2.4685 + vertex 1.67791 1.01372 2.46992 + endloop + endfacet + facet normal 0.284874 -0.245594 0.926569 + outer loop + vertex 1.68272 1.01884 2.46979 + vertex 1.67791 1.01372 2.46992 + vertex 1.68267 1.0139 2.4685 + endloop + endfacet + facet normal 0.292005 -0.245127 0.924471 + outer loop + vertex 1.68267 1.0139 2.4685 + vertex 1.68751 1.01905 2.46833 + vertex 1.68272 1.01884 2.46979 + endloop + endfacet + facet normal 0.292127 -0.241557 0.925371 + outer loop + vertex 1.68765 1.02412 2.46962 + vertex 1.68272 1.01884 2.46979 + vertex 1.68751 1.01905 2.46833 + endloop + endfacet + facet normal 0.314814 -0.240346 0.918219 + outer loop + vertex 1.68751 1.01905 2.46833 + vertex 1.69219 1.02386 2.46799 + vertex 1.68765 1.02412 2.46962 + endloop + endfacet + facet normal 0.316869 -0.224552 0.921504 + outer loop + vertex 1.69219 1.02386 2.46799 + vertex 1.69285 1.02875 2.46896 + vertex 1.68765 1.02412 2.46962 + endloop + endfacet + facet normal 0.340028 -0.252764 0.90581 + outer loop + vertex 1.68765 1.02412 2.46962 + vertex 1.69285 1.02875 2.46896 + vertex 1.68928 1.02916 2.47041 + endloop + endfacet + facet normal 0.307253 -0.244365 0.919718 + outer loop + vertex 1.68765 1.02412 2.46962 + vertex 1.68928 1.02916 2.47041 + vertex 1.68519 1.02633 2.47102 + endloop + endfacet + facet normal 0.300637 -0.251842 0.919888 + outer loop + vertex 1.68349 1.02269 2.47058 + vertex 1.68765 1.02412 2.46962 + vertex 1.68519 1.02633 2.47102 + endloop + endfacet + facet normal 0.286335 -0.245912 0.926034 + outer loop + vertex 1.68519 1.02633 2.47102 + vertex 1.68106 1.0235 2.47155 + vertex 1.68349 1.02269 2.47058 + endloop + endfacet + facet normal 0.285844 -0.247172 0.925851 + outer loop + vertex 1.68349 1.02269 2.47058 + vertex 1.68106 1.0235 2.47155 + vertex 1.68066 1.02044 2.47085 + endloop + endfacet + facet normal 0.285828 -0.247151 0.925861 + outer loop + vertex 1.68349 1.02269 2.47058 + vertex 1.68066 1.02044 2.47085 + vertex 1.68272 1.01884 2.46979 + endloop + endfacet + facet normal 0.28582 -0.247162 0.925861 + outer loop + vertex 1.68272 1.01884 2.46979 + vertex 1.68066 1.02044 2.47085 + vertex 1.6789 1.01761 2.47065 + endloop + endfacet + facet normal 0.283556 -0.245822 0.926913 + outer loop + vertex 1.68066 1.02044 2.47085 + vertex 1.67696 1.01917 2.47165 + vertex 1.6789 1.01761 2.47065 + endloop + endfacet + facet normal 0.28389 -0.247066 0.92648 + outer loop + vertex 1.68066 1.02044 2.47085 + vertex 1.68106 1.0235 2.47155 + vertex 1.67696 1.01917 2.47165 + endloop + endfacet + facet normal 0.282526 -0.245761 0.927243 + outer loop + vertex 1.68106 1.0235 2.47155 + vertex 1.67726 1.02368 2.47275 + vertex 1.67696 1.01917 2.47165 + endloop + endfacet + facet normal 0.282817 -0.243294 0.927805 + outer loop + vertex 1.68106 1.0235 2.47155 + vertex 1.68262 1.02848 2.47238 + vertex 1.67726 1.02368 2.47275 + endloop + endfacet + facet normal 0.282591 -0.243031 0.927943 + outer loop + vertex 1.67726 1.02368 2.47275 + vertex 1.68262 1.02848 2.47238 + vertex 1.67774 1.02851 2.47388 + endloop + endfacet + facet normal 0.285052 -0.243858 0.926973 + outer loop + vertex 1.68262 1.02848 2.47238 + vertex 1.68106 1.0235 2.47155 + vertex 1.68519 1.02633 2.47102 + endloop + endfacet + facet normal 0.286254 -0.24243 0.926977 + outer loop + vertex 1.68686 1.02997 2.47146 + vertex 1.68262 1.02848 2.47238 + vertex 1.68519 1.02633 2.47102 + endloop + endfacet + facet normal 0.281589 -0.225648 0.932626 + outer loop + vertex 1.68686 1.02997 2.47146 + vertex 1.68745 1.03378 2.4722 + vertex 1.68262 1.02848 2.47238 + endloop + endfacet + facet normal 0.29107 -0.234464 0.927526 + outer loop + vertex 1.68745 1.03378 2.4722 + vertex 1.68271 1.03363 2.47365 + vertex 1.68262 1.02848 2.47238 + endloop + endfacet + facet normal 0.301978 -0.227455 0.925783 + outer loop + vertex 1.68964 1.03228 2.47112 + vertex 1.68745 1.03378 2.4722 + vertex 1.68686 1.02997 2.47146 + endloop + endfacet + facet normal 0.315804 -0.245454 0.916526 + outer loop + vertex 1.68964 1.03228 2.47112 + vertex 1.68686 1.02997 2.47146 + vertex 1.68928 1.02916 2.47041 + endloop + endfacet + facet normal 0.361357 -0.246762 0.899182 + outer loop + vertex 1.68964 1.03228 2.47112 + vertex 1.68928 1.02916 2.47041 + vertex 1.69322 1.03362 2.47005 + endloop + endfacet + facet normal 0.359771 -0.240724 0.901452 + outer loop + vertex 1.69322 1.03362 2.47005 + vertex 1.69116 1.03509 2.47126 + vertex 1.68964 1.03228 2.47112 + endloop + endfacet + facet normal 0.310399 -0.215245 0.925917 + outer loop + vertex 1.69116 1.03509 2.47126 + vertex 1.68745 1.03378 2.4722 + vertex 1.68964 1.03228 2.47112 + endloop + endfacet + facet normal 0.307993 -0.206429 0.928724 + outer loop + vertex 1.69116 1.03509 2.47126 + vertex 1.69138 1.0384 2.47193 + vertex 1.68745 1.03378 2.4722 + endloop + endfacet + facet normal 0.318909 -0.216067 0.922829 + outer loop + vertex 1.69138 1.0384 2.47193 + vertex 1.68751 1.03875 2.47335 + vertex 1.68745 1.03378 2.4722 + endloop + endfacet + facet normal 0.312732 -0.2532 0.915472 + outer loop + vertex 1.68928 1.02916 2.47041 + vertex 1.68686 1.02997 2.47146 + vertex 1.68519 1.02633 2.47102 + endloop + endfacet + facet normal 0.344239 -0.230768 0.91008 + outer loop + vertex 1.69322 1.03362 2.47005 + vertex 1.68928 1.02916 2.47041 + vertex 1.69285 1.02875 2.46896 + endloop + endfacet + facet normal 0.303792 -0.229187 0.924761 + outer loop + vertex 1.69213 1.01925 2.46687 + vertex 1.69219 1.02386 2.46799 + vertex 1.68751 1.01905 2.46833 + endloop + endfacet + facet normal 0.303425 -0.240457 0.922016 + outer loop + vertex 1.69213 1.01925 2.46687 + vertex 1.68751 1.01905 2.46833 + vertex 1.68744 1.01413 2.46708 + endloop + endfacet + facet normal 0.299887 -0.248956 0.920917 + outer loop + vertex 1.68349 1.02269 2.47058 + vertex 1.68272 1.01884 2.46979 + vertex 1.68765 1.02412 2.46962 + endloop + endfacet + facet normal 0.285607 -0.246292 0.926158 + outer loop + vertex 1.6789 1.01761 2.47065 + vertex 1.67791 1.01372 2.46992 + vertex 1.68272 1.01884 2.46979 + endloop + endfacet + facet normal 0.288136 -0.241409 0.92666 + outer loop + vertex 1.68744 1.01413 2.46708 + vertex 1.68751 1.01905 2.46833 + vertex 1.68267 1.0139 2.4685 + endloop + endfacet + facet normal 0.294956 -0.23252 0.926788 + outer loop + vertex 1.69128 1.01543 2.46618 + vertex 1.69213 1.01925 2.46687 + vertex 1.68744 1.01413 2.46708 + endloop + endfacet + facet normal 0.298827 -0.252272 0.920359 + outer loop + vertex 1.68929 1.01231 2.466 + vertex 1.68636 1.01008 2.46634 + vertex 1.68812 1.00832 2.46529 + endloop + endfacet + facet normal 0.299704 -0.239097 0.923586 + outer loop + vertex 1.69217 1.00385 2.46276 + vertex 1.69265 1.00866 2.46385 + vertex 1.68776 1.00357 2.46412 + endloop + endfacet + facet normal 0.299581 -0.246884 0.921575 + outer loop + vertex 1.6874 0.998898 2.46298 + vertex 1.69217 1.00385 2.46276 + vertex 1.68776 1.00357 2.46412 + endloop + endfacet + facet normal 0.290173 -0.237565 0.927018 + outer loop + vertex 1.69191 0.999277 2.46167 + vertex 1.69217 1.00385 2.46276 + vertex 1.6874 0.998898 2.46298 + endloop + endfacet + facet normal 0.290258 -0.250015 0.923712 + outer loop + vertex 1.69191 0.999277 2.46167 + vertex 1.6874 0.998898 2.46298 + vertex 1.68717 0.994261 2.4618 + endloop + endfacet + facet normal 0.282541 -0.242609 0.928069 + outer loop + vertex 1.69099 0.995555 2.46098 + vertex 1.69191 0.999277 2.46167 + vertex 1.68717 0.994261 2.4618 + endloop + endfacet + facet normal 0.285271 -0.252982 0.924457 + outer loop + vertex 1.69099 0.995555 2.46098 + vertex 1.68717 0.994261 2.4618 + vertex 1.68902 0.992552 2.46076 + endloop + endfacet + facet normal 0.297871 -0.260807 0.918288 + outer loop + vertex 1.69285 0.993779 2.45987 + vertex 1.69099 0.995555 2.46098 + vertex 1.68902 0.992552 2.46076 + endloop + endfacet + facet normal 0.298367 -0.262914 0.917526 + outer loop + vertex 1.68902 0.992552 2.46076 + vertex 1.68793 0.988631 2.45999 + vertex 1.69285 0.993779 2.45987 + endloop + endfacet + facet normal 0.28949 -0.254307 0.92278 + outer loop + vertex 1.69285 0.993779 2.45987 + vertex 1.68793 0.988631 2.45999 + vertex 1.69268 0.988855 2.45856 + endloop + endfacet + facet normal 0.312211 -0.253196 0.915651 + outer loop + vertex 1.69268 0.988855 2.45856 + vertex 1.6975 0.993894 2.45832 + vertex 1.69285 0.993779 2.45987 + endloop + endfacet + facet normal 0.312831 -0.242657 0.918289 + outer loop + vertex 1.69769 0.998971 2.45959 + vertex 1.69285 0.993779 2.45987 + vertex 1.6975 0.993894 2.45832 + endloop + endfacet + facet normal 0.331509 -0.260666 0.906728 + outer loop + vertex 1.69386 0.997708 2.46063 + vertex 1.69285 0.993779 2.45987 + vertex 1.69769 0.998971 2.45959 + endloop + endfacet + facet normal 0.330308 -0.255462 0.908645 + outer loop + vertex 1.69769 0.998971 2.45959 + vertex 1.69562 1.00063 2.46081 + vertex 1.69386 0.997708 2.46063 + endloop + endfacet + facet normal 0.300727 -0.238584 0.923386 + outer loop + vertex 1.69562 1.00063 2.46081 + vertex 1.69191 0.999277 2.46167 + vertex 1.69386 0.997708 2.46063 + endloop + endfacet + facet normal 0.298052 -0.229193 0.926626 + outer loop + vertex 1.69562 1.00063 2.46081 + vertex 1.69594 1.0038 2.46149 + vertex 1.69191 0.999277 2.46167 + endloop + endfacet + facet normal 0.299703 -0.240873 0.923124 + outer loop + vertex 1.69732 0.989036 2.45711 + vertex 1.6975 0.993894 2.45832 + vertex 1.69268 0.988855 2.45856 + endloop + endfacet + facet normal 0.299084 -0.255769 0.91931 + outer loop + vertex 1.69732 0.989036 2.45711 + vertex 1.69268 0.988855 2.45856 + vertex 1.69254 0.983988 2.45726 + endloop + endfacet + facet normal 0.290332 -0.24732 0.924413 + outer loop + vertex 1.69638 0.985196 2.45637 + vertex 1.69732 0.989036 2.45711 + vertex 1.69254 0.983988 2.45726 + endloop + endfacet + facet normal 0.293433 -0.260572 0.919782 + outer loop + vertex 1.69638 0.985196 2.45637 + vertex 1.69254 0.983988 2.45726 + vertex 1.69438 0.98219 2.45616 + endloop + endfacet + facet normal 0.321005 -0.277885 0.905392 + outer loop + vertex 1.69817 0.983457 2.45521 + vertex 1.69638 0.985196 2.45637 + vertex 1.69438 0.98219 2.45616 + endloop + endfacet + facet normal 0.320941 -0.277613 0.905499 + outer loop + vertex 1.69438 0.98219 2.45616 + vertex 1.69323 0.978288 2.45537 + vertex 1.69817 0.983457 2.45521 + endloop + endfacet + facet normal 0.30701 -0.264029 0.914349 + outer loop + vertex 1.69817 0.983457 2.45521 + vertex 1.69323 0.978288 2.45537 + vertex 1.6979 0.978587 2.45389 + endloop + endfacet + facet normal 0.342569 -0.262646 0.902033 + outer loop + vertex 1.6979 0.978587 2.45389 + vertex 1.70267 0.983745 2.45358 + vertex 1.69817 0.983457 2.45521 + endloop + endfacet + facet normal 0.342971 -0.250787 0.905249 + outer loop + vertex 1.70297 0.988744 2.45485 + vertex 1.69817 0.983457 2.45521 + vertex 1.70267 0.983745 2.45358 + endloop + endfacet + facet normal 0.371491 -0.277995 0.88584 + outer loop + vertex 1.69926 0.987362 2.45598 + vertex 1.69817 0.983457 2.45521 + vertex 1.70297 0.988744 2.45485 + endloop + endfacet + facet normal 0.369391 -0.269508 0.889334 + outer loop + vertex 1.70297 0.988744 2.45485 + vertex 1.70105 0.990333 2.45613 + vertex 1.69926 0.987362 2.45598 + endloop + endfacet + facet normal 0.323686 -0.24325 0.914362 + outer loop + vertex 1.70105 0.990333 2.45613 + vertex 1.69732 0.989036 2.45711 + vertex 1.69926 0.987362 2.45598 + endloop + endfacet + facet normal 0.320463 -0.230699 0.918739 + outer loop + vertex 1.70105 0.990333 2.45613 + vertex 1.70137 0.993632 2.45685 + vertex 1.69732 0.989036 2.45711 + endloop + endfacet + facet normal 0.320141 -0.241064 0.916187 + outer loop + vertex 1.70245 0.978871 2.45237 + vertex 1.70267 0.983745 2.45358 + vertex 1.6979 0.978587 2.45389 + endloop + endfacet + facet normal 0.31978 -0.255435 0.912411 + outer loop + vertex 1.70245 0.978871 2.45237 + vertex 1.6979 0.978587 2.45389 + vertex 1.69777 0.97373 2.45258 + endloop + endfacet + facet normal 0.30355 -0.240258 0.922027 + outer loop + vertex 1.70159 0.975021 2.45166 + vertex 1.70245 0.978871 2.45237 + vertex 1.69777 0.97373 2.45258 + endloop + endfacet + facet normal 0.306901 -0.253511 0.917357 + outer loop + vertex 1.70159 0.975021 2.45166 + vertex 1.69777 0.97373 2.45258 + vertex 1.69981 0.972149 2.45146 + endloop + endfacet + facet normal 0.339758 -0.272704 0.90011 + outer loop + vertex 1.70344 0.973464 2.45048 + vertex 1.70159 0.975021 2.45166 + vertex 1.69981 0.972149 2.45146 + endloop + endfacet + facet normal 0.341786 -0.28071 0.896875 + outer loop + vertex 1.69981 0.972149 2.45146 + vertex 1.69934 0.969042 2.45066 + vertex 1.70344 0.973464 2.45048 + endloop + endfacet + facet normal 0.337087 -0.276225 0.90004 + outer loop + vertex 1.70344 0.973464 2.45048 + vertex 1.69934 0.969042 2.45066 + vertex 1.70306 0.968813 2.4492 + endloop + endfacet + facet normal 0.329844 -0.319344 0.888382 + outer loop + vertex 1.69769 0.964103 2.4495 + vertex 1.70306 0.968813 2.4492 + vertex 1.69934 0.969042 2.45066 + endloop + endfacet + facet normal 0.332298 -0.319901 0.887266 + outer loop + vertex 1.69769 0.964103 2.4495 + vertex 1.69934 0.969042 2.45066 + vertex 1.69521 0.966288 2.45122 + endloop + endfacet + facet normal 0.332261 -0.319943 0.887265 + outer loop + vertex 1.69349 0.962776 2.45059 + vertex 1.69769 0.964103 2.4495 + vertex 1.69521 0.966288 2.45122 + endloop + endfacet + facet normal 0.313604 -0.312452 0.896675 + outer loop + vertex 1.69521 0.966288 2.45122 + vertex 1.6912 0.963708 2.45172 + vertex 1.69349 0.962776 2.45059 + endloop + endfacet + facet normal 0.312296 -0.286163 0.90586 + outer loop + vertex 1.69934 0.969042 2.45066 + vertex 1.69695 0.969878 2.45175 + vertex 1.69521 0.966288 2.45122 + endloop + endfacet + facet normal 0.315202 -0.279325 0.906987 + outer loop + vertex 1.69981 0.972149 2.45146 + vertex 1.69695 0.969878 2.45175 + vertex 1.69934 0.969042 2.45066 + endloop + endfacet + facet normal 0.329687 -0.319157 0.888507 + outer loop + vertex 1.70262 0.963924 2.4476 + vertex 1.70306 0.968813 2.4492 + vertex 1.69769 0.964103 2.4495 + endloop + endfacet + facet normal 0.339636 -0.318851 0.884862 + outer loop + vertex 1.70747 0.968973 2.44756 + vertex 1.70306 0.968813 2.4492 + vertex 1.70262 0.963924 2.4476 + endloop + endfacet + facet normal 0.318826 -0.298758 0.899496 + outer loop + vertex 1.70652 0.965096 2.44661 + vertex 1.70747 0.968973 2.44756 + vertex 1.70262 0.963924 2.4476 + endloop + endfacet + facet normal 0.33616 -0.393319 0.855743 + outer loop + vertex 1.70652 0.965096 2.44661 + vertex 1.70262 0.963924 2.4476 + vertex 1.70461 0.962042 2.44596 + endloop + endfacet + facet normal 0.399726 -0.423904 0.812727 + outer loop + vertex 1.70843 0.963553 2.44487 + vertex 1.70652 0.965096 2.44661 + vertex 1.70461 0.962042 2.44596 + endloop + endfacet + facet normal 0.344437 -0.251974 0.904363 + outer loop + vertex 1.70747 0.968973 2.44756 + vertex 1.70773 0.973752 2.4488 + vertex 1.70306 0.968813 2.4492 + endloop + endfacet + facet normal 0.367889 -0.275478 0.888127 + outer loop + vertex 1.70306 0.968813 2.4492 + vertex 1.70773 0.973752 2.4488 + vertex 1.70344 0.973464 2.45048 + endloop + endfacet + facet normal 0.369198 -0.243245 0.896953 + outer loop + vertex 1.70798 0.978678 2.45003 + vertex 1.70344 0.973464 2.45048 + vertex 1.70773 0.973752 2.4488 + endloop + endfacet + facet normal 0.399094 -0.271105 0.875914 + outer loop + vertex 1.70437 0.977218 2.45122 + vertex 1.70344 0.973464 2.45048 + vertex 1.70798 0.978678 2.45003 + endloop + endfacet + facet normal 0.396463 -0.261167 0.880119 + outer loop + vertex 1.70798 0.978678 2.45003 + vertex 1.70609 0.980251 2.45135 + vertex 1.70437 0.977218 2.45122 + endloop + endfacet + facet normal 0.344859 -0.23326 0.909209 + outer loop + vertex 1.70609 0.980251 2.45135 + vertex 1.70245 0.978871 2.45237 + vertex 1.70437 0.977218 2.45122 + endloop + endfacet + facet normal 0.342117 -0.223456 0.912701 + outer loop + vertex 1.70609 0.980251 2.45135 + vertex 1.70639 0.983618 2.45206 + vertex 1.70245 0.978871 2.45237 + endloop + endfacet + facet normal 0.360277 -0.239229 0.901649 + outer loop + vertex 1.70639 0.983618 2.45206 + vertex 1.70267 0.983745 2.45358 + vertex 1.70245 0.978871 2.45237 + endloop + endfacet + facet normal 0.362986 -0.216212 0.906363 + outer loop + vertex 1.70639 0.983618 2.45206 + vertex 1.70757 0.988891 2.45284 + vertex 1.70267 0.983745 2.45358 + endloop + endfacet + facet normal 0.393819 -0.248681 0.884909 + outer loop + vertex 1.70267 0.983745 2.45358 + vertex 1.70757 0.988891 2.45284 + vertex 1.70297 0.988744 2.45485 + endloop + endfacet + facet normal 0.39515 -0.230172 0.889313 + outer loop + vertex 1.70746 0.994206 2.45427 + vertex 1.70297 0.988744 2.45485 + vertex 1.70757 0.988891 2.45284 + endloop + endfacet + facet normal 0.426163 -0.258015 0.867072 + outer loop + vertex 1.70378 0.992779 2.45566 + vertex 1.70297 0.988744 2.45485 + vertex 1.70746 0.994206 2.45427 + endloop + endfacet + facet normal 0.420896 -0.235846 0.875913 + outer loop + vertex 1.70378 0.992779 2.45566 + vertex 1.70746 0.994206 2.45427 + vertex 1.70527 0.996664 2.45598 + endloop + endfacet + facet normal 0.369724 -0.218411 0.903106 + outer loop + vertex 1.70527 0.996664 2.45598 + vertex 1.70137 0.993632 2.45685 + vertex 1.70378 0.992779 2.45566 + endloop + endfacet + facet normal 0.36458 -0.231347 0.901976 + outer loop + vertex 1.70378 0.992779 2.45566 + vertex 1.70137 0.993632 2.45685 + vertex 1.70105 0.990333 2.45613 + endloop + endfacet + facet normal 0.375432 -0.227042 0.898612 + outer loop + vertex 1.7026 0.998897 2.45766 + vertex 1.70137 0.993632 2.45685 + vertex 1.70527 0.996664 2.45598 + endloop + endfacet + facet normal 0.384747 -0.215122 0.897604 + outer loop + vertex 1.70658 1.00046 2.45633 + vertex 1.7026 0.998897 2.45766 + vertex 1.70527 0.996664 2.45598 + endloop + endfacet + facet normal 0.444001 -0.232453 0.865349 + outer loop + vertex 1.70878 0.999497 2.45494 + vertex 1.70658 1.00046 2.45633 + vertex 1.70527 0.996664 2.45598 + endloop + endfacet + facet normal 0.453047 -0.212439 0.865805 + outer loop + vertex 1.70884 1.00295 2.45576 + vertex 1.70658 1.00046 2.45633 + vertex 1.70878 0.999497 2.45494 + endloop + endfacet + facet normal 0.438627 -0.196747 0.876868 + outer loop + vertex 1.70884 1.00295 2.45576 + vertex 1.70633 1.00376 2.4572 + vertex 1.70658 1.00046 2.45633 + endloop + endfacet + facet normal 0.449164 -0.165986 0.877895 + outer loop + vertex 1.70963 1.00672 2.45607 + vertex 1.70633 1.00376 2.4572 + vertex 1.70884 1.00295 2.45576 + endloop + endfacet + facet normal 0.466826 -0.19113 0.863448 + outer loop + vertex 1.70683 1.00851 2.45798 + vertex 1.70633 1.00376 2.4572 + vertex 1.70963 1.00672 2.45607 + endloop + endfacet + facet normal 0.382511 -0.207005 0.900464 + outer loop + vertex 1.70658 1.00046 2.45633 + vertex 1.70633 1.00376 2.4572 + vertex 1.7026 0.998897 2.45766 + endloop + endfacet + facet normal 0.397328 -0.219289 0.891091 + outer loop + vertex 1.70633 1.00376 2.4572 + vertex 1.70236 1.00435 2.45911 + vertex 1.7026 0.998897 2.45766 + endloop + endfacet + facet normal 0.403614 -0.18969 0.895049 + outer loop + vertex 1.70633 1.00376 2.4572 + vertex 1.70683 1.00851 2.45798 + vertex 1.70236 1.00435 2.45911 + endloop + endfacet + facet normal 0.428281 -0.221377 0.876109 + outer loop + vertex 1.70236 1.00435 2.45911 + vertex 1.70683 1.00851 2.45798 + vertex 1.70378 1.00973 2.45978 + endloop + endfacet + facet normal 0.390373 -0.213793 0.89549 + outer loop + vertex 1.70236 1.00435 2.45911 + vertex 1.70378 1.00973 2.45978 + vertex 1.69994 1.00681 2.46076 + endloop + endfacet + facet normal 0.373137 -0.232554 0.898158 + outer loop + vertex 1.6984 1.00301 2.46041 + vertex 1.70236 1.00435 2.45911 + vertex 1.69994 1.00681 2.46076 + endloop + endfacet + facet normal 0.402559 -0.233276 0.885172 + outer loop + vertex 1.70378 1.00973 2.45978 + vertex 1.7013 1.01053 2.46112 + vertex 1.69994 1.00681 2.46076 + endloop + endfacet + facet normal 0.411147 -0.209889 0.887077 + outer loop + vertex 1.70385 1.01313 2.46055 + vertex 1.7013 1.01053 2.46112 + vertex 1.70378 1.00973 2.45978 + endloop + endfacet + facet normal 0.4903 -0.202483 0.847707 + outer loop + vertex 1.70385 1.01313 2.46055 + vertex 1.70378 1.00973 2.45978 + vertex 1.7076 1.01434 2.45867 + endloop + endfacet + facet normal 0.488946 -0.193943 0.850481 + outer loop + vertex 1.70385 1.01313 2.46055 + vertex 1.7076 1.01434 2.45867 + vertex 1.70479 1.01688 2.46087 + endloop + endfacet + facet normal 0.521984 -0.148362 0.839953 + outer loop + vertex 1.7076 1.01434 2.45867 + vertex 1.70815 1.02002 2.45933 + vertex 1.70479 1.01688 2.46087 + endloop + endfacet + facet normal 0.544965 -0.183742 0.818078 + outer loop + vertex 1.70479 1.01688 2.46087 + vertex 1.70815 1.02002 2.45933 + vertex 1.70548 1.02153 2.46145 + endloop + endfacet + facet normal 0.566267 -0.138316 0.812534 + outer loop + vertex 1.70815 1.02002 2.45933 + vertex 1.70844 1.0245 2.45989 + vertex 1.70548 1.02153 2.46145 + endloop + endfacet + facet normal 0.594544 -0.181917 0.783213 + outer loop + vertex 1.70844 1.0245 2.45989 + vertex 1.70633 1.02532 2.46168 + vertex 1.70548 1.02153 2.46145 + endloop + endfacet + facet normal 0.451906 -0.163596 0.876937 + outer loop + vertex 1.7076 1.01434 2.45867 + vertex 1.70378 1.00973 2.45978 + vertex 1.70683 1.00851 2.45798 + endloop + endfacet + facet normal 0.436099 -0.220022 0.872587 + outer loop + vertex 1.70746 0.994206 2.45427 + vertex 1.70878 0.999497 2.45494 + vertex 1.70527 0.996664 2.45598 + endloop + endfacet + facet normal 0.382146 -0.253528 0.888644 + outer loop + vertex 1.70378 0.992779 2.45566 + vertex 1.70105 0.990333 2.45613 + vertex 1.70297 0.988744 2.45485 + endloop + endfacet + facet normal 0.301341 -0.260581 0.917219 + outer loop + vertex 1.69981 0.972149 2.45146 + vertex 1.69777 0.97373 2.45258 + vertex 1.69695 0.969878 2.45175 + endloop + endfacet + facet normal 0.28983 -0.259029 0.921359 + outer loop + vertex 1.69695 0.969878 2.45175 + vertex 1.69777 0.97373 2.45258 + vertex 1.69276 0.968453 2.45267 + endloop + endfacet + facet normal 0.294973 -0.278966 0.913876 + outer loop + vertex 1.69695 0.969878 2.45175 + vertex 1.69276 0.968453 2.45267 + vertex 1.69521 0.966288 2.45122 + endloop + endfacet + facet normal 0.294552 -0.279438 0.913868 + outer loop + vertex 1.69276 0.968453 2.45267 + vertex 1.6912 0.963708 2.45172 + vertex 1.69521 0.966288 2.45122 + endloop + endfacet + facet normal 0.286313 -0.277367 0.917111 + outer loop + vertex 1.6912 0.963708 2.45172 + vertex 1.69276 0.968453 2.45267 + vertex 1.68749 0.963811 2.45291 + endloop + endfacet + facet normal 0.282444 -0.309823 0.907874 + outer loop + vertex 1.6912 0.963708 2.45172 + vertex 1.68749 0.963811 2.45291 + vertex 1.68761 0.960204 2.45164 + endloop + endfacet + facet normal 0.2818 -0.309905 0.908046 + outer loop + vertex 1.68761 0.960204 2.45164 + vertex 1.68749 0.963811 2.45291 + vertex 1.68272 0.958693 2.45264 + endloop + endfacet + facet normal 0.280792 -0.308998 0.908667 + outer loop + vertex 1.68272 0.958693 2.45264 + vertex 1.68749 0.963811 2.45291 + vertex 1.68293 0.963482 2.45421 + endloop + endfacet + facet normal 0.292954 -0.308344 0.905042 + outer loop + vertex 1.68272 0.958693 2.45264 + vertex 1.68293 0.963482 2.45421 + vertex 1.67799 0.958754 2.45419 + endloop + endfacet + facet normal 0.283909 -0.298928 0.911064 + outer loop + vertex 1.67799 0.958754 2.45419 + vertex 1.68293 0.963482 2.45421 + vertex 1.67843 0.963298 2.45555 + endloop + endfacet + facet normal 0.302505 -0.298924 0.905061 + outer loop + vertex 1.67843 0.963298 2.45555 + vertex 1.67427 0.959095 2.45555 + vertex 1.67799 0.958754 2.45419 + endloop + endfacet + facet normal 0.294396 -0.340041 0.893142 + outer loop + vertex 1.67272 0.954409 2.45428 + vertex 1.67799 0.958754 2.45419 + vertex 1.67427 0.959095 2.45555 + endloop + endfacet + facet normal 0.331177 -0.347856 0.877108 + outer loop + vertex 1.67272 0.954409 2.45428 + vertex 1.67427 0.959095 2.45555 + vertex 1.67026 0.956575 2.45607 + endloop + endfacet + facet normal 0.327204 -0.352177 0.876874 + outer loop + vertex 1.66845 0.953176 2.45537 + vertex 1.67272 0.954409 2.45428 + vertex 1.67026 0.956575 2.45607 + endloop + endfacet + facet normal 0.302351 -0.296039 0.90606 + outer loop + vertex 1.67427 0.959095 2.45555 + vertex 1.67193 0.959969 2.45662 + vertex 1.67026 0.956575 2.45607 + endloop + endfacet + facet normal 0.301295 -0.295601 0.906555 + outer loop + vertex 1.67193 0.959969 2.45662 + vertex 1.66786 0.958626 2.45753 + vertex 1.67026 0.956575 2.45607 + endloop + endfacet + facet normal 0.303658 -0.292901 0.906642 + outer loop + vertex 1.66786 0.958626 2.45753 + vertex 1.66678 0.954632 2.4566 + vertex 1.67026 0.956575 2.45607 + endloop + endfacet + facet normal 0.333003 -0.354615 0.873703 + outer loop + vertex 1.67026 0.956575 2.45607 + vertex 1.66678 0.954632 2.4566 + vertex 1.66845 0.953176 2.45537 + endloop + endfacet + facet normal 0.297276 -0.291742 0.909128 + outer loop + vertex 1.66678 0.954632 2.4566 + vertex 1.66786 0.958626 2.45753 + vertex 1.66271 0.953634 2.45761 + endloop + endfacet + facet normal 0.291 -0.285192 0.913227 + outer loop + vertex 1.66271 0.953634 2.45761 + vertex 1.66786 0.958626 2.45753 + vertex 1.66297 0.958494 2.45905 + endloop + endfacet + facet normal 0.293781 -0.285088 0.912369 + outer loop + vertex 1.66271 0.953634 2.45761 + vertex 1.66297 0.958494 2.45905 + vertex 1.65798 0.953649 2.45914 + endloop + endfacet + facet normal 0.288886 -0.332792 0.897661 + outer loop + vertex 1.66271 0.953634 2.45761 + vertex 1.65798 0.953649 2.45914 + vertex 1.65761 0.949068 2.45756 + endloop + endfacet + facet normal 0.298799 -0.332503 0.894517 + outer loop + vertex 1.65761 0.949068 2.45756 + vertex 1.65798 0.953649 2.45914 + vertex 1.65324 0.949054 2.45902 + endloop + endfacet + facet normal 0.287457 -0.278498 0.91641 + outer loop + vertex 1.65798 0.953649 2.45914 + vertex 1.66297 0.958494 2.45905 + vertex 1.65827 0.958273 2.46046 + endloop + endfacet + facet normal 0.293675 -0.278338 0.914485 + outer loop + vertex 1.65827 0.958273 2.46046 + vertex 1.65346 0.953485 2.46054 + vertex 1.65798 0.953649 2.45914 + endloop + endfacet + facet normal 0.290877 -0.324481 0.900057 + outer loop + vertex 1.65324 0.949054 2.45902 + vertex 1.65798 0.953649 2.45914 + vertex 1.65346 0.953485 2.46054 + endloop + endfacet + facet normal 0.316113 -0.323007 0.892042 + outer loop + vertex 1.65346 0.953485 2.46054 + vertex 1.64947 0.949201 2.46041 + vertex 1.65324 0.949054 2.45902 + endloop + endfacet + facet normal 0.311981 -0.319237 0.89485 + outer loop + vertex 1.64977 0.952317 2.46141 + vertex 1.64947 0.949201 2.46041 + vertex 1.65346 0.953485 2.46054 + endloop + endfacet + facet normal 0.302224 -0.275078 0.912684 + outer loop + vertex 1.65346 0.953485 2.46054 + vertex 1.65157 0.955085 2.46165 + vertex 1.64977 0.952317 2.46141 + endloop + endfacet + facet normal 0.302747 -0.275394 0.912416 + outer loop + vertex 1.65157 0.955085 2.46165 + vertex 1.64777 0.953864 2.46254 + vertex 1.64977 0.952317 2.46141 + endloop + endfacet + facet normal 0.299117 -0.279954 0.912225 + outer loop + vertex 1.64977 0.952317 2.46141 + vertex 1.64777 0.953864 2.46254 + vertex 1.64701 0.950085 2.46163 + endloop + endfacet + facet normal 0.296263 -0.279632 0.913255 + outer loop + vertex 1.64701 0.950085 2.46163 + vertex 1.64777 0.953864 2.46254 + vertex 1.64296 0.948637 2.4625 + endloop + endfacet + facet normal 0.311073 -0.335555 0.889177 + outer loop + vertex 1.64701 0.950085 2.46163 + vertex 1.64296 0.948637 2.4625 + vertex 1.64548 0.946402 2.46078 + endloop + endfacet + facet normal 0.319933 -0.338278 0.884992 + outer loop + vertex 1.64947 0.949201 2.46041 + vertex 1.64701 0.950085 2.46163 + vertex 1.64548 0.946402 2.46078 + endloop + endfacet + facet normal 0.320074 -0.325763 0.889624 + outer loop + vertex 1.64296 0.948637 2.4625 + vertex 1.64192 0.944385 2.46132 + vertex 1.64548 0.946402 2.46078 + endloop + endfacet + facet normal 0.270285 -0.318809 0.908464 + outer loop + vertex 1.64192 0.944385 2.46132 + vertex 1.64296 0.948637 2.4625 + vertex 1.63798 0.943791 2.46229 + endloop + endfacet + facet normal 0.270757 -0.319281 0.908158 + outer loop + vertex 1.63798 0.943791 2.46229 + vertex 1.64296 0.948637 2.4625 + vertex 1.63797 0.948496 2.46394 + endloop + endfacet + facet normal 0.199153 -0.325077 0.92448 + outer loop + vertex 1.63798 0.943791 2.46229 + vertex 1.63797 0.948496 2.46394 + vertex 1.63307 0.944113 2.46346 + endloop + endfacet + facet normal 0.230304 -0.357748 0.904973 + outer loop + vertex 1.63307 0.944113 2.46346 + vertex 1.63797 0.948496 2.46394 + vertex 1.633 0.948413 2.46517 + endloop + endfacet + facet normal 0.234149 -0.301473 0.924277 + outer loop + vertex 1.63815 0.953119 2.4654 + vertex 1.633 0.948413 2.46517 + vertex 1.63797 0.948496 2.46394 + endloop + endfacet + facet normal 0.289282 -0.298866 0.909393 + outer loop + vertex 1.63797 0.948496 2.46394 + vertex 1.64295 0.953494 2.464 + vertex 1.63815 0.953119 2.4654 + endloop + endfacet + facet normal 0.289651 -0.264494 0.919861 + outer loop + vertex 1.64316 0.958317 2.46532 + vertex 1.63815 0.953119 2.4654 + vertex 1.64295 0.953494 2.464 + endloop + endfacet + facet normal 0.298114 -0.264162 0.917249 + outer loop + vertex 1.64295 0.953494 2.464 + vertex 1.6479 0.958632 2.46387 + vertex 1.64316 0.958317 2.46532 + endloop + endfacet + facet normal 0.2982 -0.259562 0.918534 + outer loop + vertex 1.64814 0.963489 2.46517 + vertex 1.64316 0.958317 2.46532 + vertex 1.6479 0.958632 2.46387 + endloop + endfacet + facet normal 0.291704 -0.259779 0.920556 + outer loop + vertex 1.6479 0.958632 2.46387 + vertex 1.65286 0.9637 2.46373 + vertex 1.64814 0.963489 2.46517 + endloop + endfacet + facet normal 0.291465 -0.265972 0.918862 + outer loop + vertex 1.65308 0.968539 2.46506 + vertex 1.64814 0.963489 2.46517 + vertex 1.65286 0.9637 2.46373 + endloop + endfacet + facet normal 0.28923 -0.266061 0.919542 + outer loop + vertex 1.65286 0.9637 2.46373 + vertex 1.65781 0.968764 2.46364 + vertex 1.65308 0.968539 2.46506 + endloop + endfacet + facet normal 0.289148 -0.268311 0.918914 + outer loop + vertex 1.65799 0.973595 2.46499 + vertex 1.65308 0.968539 2.46506 + vertex 1.65781 0.968764 2.46364 + endloop + endfacet + facet normal 0.291366 -0.268204 0.918244 + outer loop + vertex 1.65781 0.968764 2.46364 + vertex 1.66273 0.973863 2.46357 + vertex 1.65799 0.973595 2.46499 + endloop + endfacet + facet normal 0.291408 -0.266708 0.918666 + outer loop + vertex 1.66292 0.978722 2.46492 + vertex 1.65799 0.973595 2.46499 + vertex 1.66273 0.973863 2.46357 + endloop + endfacet + facet normal 0.291188 -0.266719 0.918733 + outer loop + vertex 1.66273 0.973863 2.46357 + vertex 1.66766 0.978968 2.46349 + vertex 1.66292 0.978722 2.46492 + endloop + endfacet + facet normal 0.291251 -0.264766 0.919278 + outer loop + vertex 1.66785 0.983842 2.46483 + vertex 1.66292 0.978722 2.46492 + vertex 1.66766 0.978968 2.46349 + endloop + endfacet + facet normal 0.287853 -0.264916 0.920304 + outer loop + vertex 1.66766 0.978968 2.46349 + vertex 1.67259 0.984018 2.4634 + vertex 1.66785 0.983842 2.46483 + endloop + endfacet + facet normal 0.287957 -0.262609 0.920933 + outer loop + vertex 1.6727 0.988867 2.46474 + vertex 1.66785 0.983842 2.46483 + vertex 1.67259 0.984018 2.4634 + endloop + endfacet + facet normal 0.290668 -0.267693 0.918615 + outer loop + vertex 1.67239 0.979182 2.46205 + vertex 1.67259 0.984018 2.4634 + vertex 1.66766 0.978968 2.46349 + endloop + endfacet + facet normal 0.290604 -0.269316 0.91816 + outer loop + vertex 1.67239 0.979182 2.46205 + vertex 1.66766 0.978968 2.46349 + vertex 1.66746 0.974127 2.46213 + endloop + endfacet + facet normal 0.293698 -0.272364 0.916275 + outer loop + vertex 1.67127 0.9753 2.46126 + vertex 1.67239 0.979182 2.46205 + vertex 1.66746 0.974127 2.46213 + endloop + endfacet + facet normal 0.293265 -0.270425 0.916988 + outer loop + vertex 1.67127 0.9753 2.46126 + vertex 1.66746 0.974127 2.46213 + vertex 1.66926 0.972317 2.46102 + endloop + endfacet + facet normal 0.287393 -0.266693 0.919935 + outer loop + vertex 1.67308 0.97346 2.46016 + vertex 1.67127 0.9753 2.46126 + vertex 1.66926 0.972317 2.46102 + endloop + endfacet + facet normal 0.286801 -0.263981 0.920902 + outer loop + vertex 1.66926 0.972317 2.46102 + vertex 1.66815 0.968392 2.46024 + vertex 1.67308 0.97346 2.46016 + endloop + endfacet + facet normal 0.288011 -0.26517 0.920182 + outer loop + vertex 1.67308 0.97346 2.46016 + vertex 1.66815 0.968392 2.46024 + vertex 1.67289 0.968598 2.45881 + endloop + endfacet + facet normal 0.282788 -0.265399 0.921734 + outer loop + vertex 1.67289 0.968598 2.45881 + vertex 1.67785 0.973649 2.45875 + vertex 1.67308 0.97346 2.46016 + endloop + endfacet + facet normal 0.282688 -0.267762 0.921081 + outer loop + vertex 1.67803 0.978491 2.4601 + vertex 1.67308 0.97346 2.46016 + vertex 1.67785 0.973649 2.45875 + endloop + endfacet + facet normal 0.279895 -0.267885 0.921898 + outer loop + vertex 1.67785 0.973649 2.45875 + vertex 1.68281 0.978695 2.45871 + vertex 1.67803 0.978491 2.4601 + endloop + endfacet + facet normal 0.279946 -0.266539 0.922273 + outer loop + vertex 1.68298 0.983531 2.46005 + vertex 1.67803 0.978491 2.4601 + vertex 1.68281 0.978695 2.45871 + endloop + endfacet + facet normal 0.281237 -0.26648 0.921897 + outer loop + vertex 1.68281 0.978695 2.45871 + vertex 1.68777 0.983763 2.45866 + vertex 1.68298 0.983531 2.46005 + endloop + endfacet + facet normal 0.28138 -0.261973 0.923144 + outer loop + vertex 1.68793 0.988631 2.45999 + vertex 1.68298 0.983531 2.46005 + vertex 1.68777 0.983763 2.45866 + endloop + endfacet + facet normal 0.285101 -0.265609 0.920961 + outer loop + vertex 1.68408 0.987421 2.46084 + vertex 1.68298 0.983531 2.46005 + vertex 1.68793 0.988631 2.45999 + endloop + endfacet + facet normal 0.284353 -0.262428 0.922103 + outer loop + vertex 1.68793 0.988631 2.45999 + vertex 1.68609 0.990416 2.46107 + vertex 1.68408 0.987421 2.46084 + endloop + endfacet + facet normal 0.282 -0.260937 0.923249 + outer loop + vertex 1.68609 0.990416 2.46107 + vertex 1.68226 0.989207 2.4619 + vertex 1.68408 0.987421 2.46084 + endloop + endfacet + facet normal 0.280799 -0.262173 0.923264 + outer loop + vertex 1.68408 0.987421 2.46084 + vertex 1.68226 0.989207 2.4619 + vertex 1.68115 0.985333 2.46113 + endloop + endfacet + facet normal 0.281839 -0.262394 0.922884 + outer loop + vertex 1.68115 0.985333 2.46113 + vertex 1.68226 0.989207 2.4619 + vertex 1.67733 0.984191 2.46198 + endloop + endfacet + facet normal 0.282872 -0.267089 0.921221 + outer loop + vertex 1.68115 0.985333 2.46113 + vertex 1.67733 0.984191 2.46198 + vertex 1.67914 0.982369 2.46089 + endloop + endfacet + facet normal 0.281618 -0.266286 0.921837 + outer loop + vertex 1.68298 0.983531 2.46005 + vertex 1.68115 0.985333 2.46113 + vertex 1.67914 0.982369 2.46089 + endloop + endfacet + facet normal 0.281988 -0.267976 0.921234 + outer loop + vertex 1.67914 0.982369 2.46089 + vertex 1.67733 0.984191 2.46198 + vertex 1.67622 0.980317 2.46119 + endloop + endfacet + facet normal 0.28253 -0.268808 0.920825 + outer loop + vertex 1.67914 0.982369 2.46089 + vertex 1.67622 0.980317 2.46119 + vertex 1.67803 0.978491 2.4601 + endloop + endfacet + facet normal 0.282522 -0.268817 0.920825 + outer loop + vertex 1.67803 0.978491 2.4601 + vertex 1.67622 0.980317 2.46119 + vertex 1.67419 0.977359 2.46095 + endloop + endfacet + facet normal 0.287309 -0.271896 0.918437 + outer loop + vertex 1.67622 0.980317 2.46119 + vertex 1.67239 0.979182 2.46205 + vertex 1.67419 0.977359 2.46095 + endloop + endfacet + facet normal 0.286678 -0.268967 0.919496 + outer loop + vertex 1.67622 0.980317 2.46119 + vertex 1.67733 0.984191 2.46198 + vertex 1.67239 0.979182 2.46205 + endloop + endfacet + facet normal 0.283322 -0.263865 0.922011 + outer loop + vertex 1.68226 0.989207 2.4619 + vertex 1.67751 0.989025 2.4633 + vertex 1.67733 0.984191 2.46198 + endloop + endfacet + facet normal 0.285802 -0.263759 0.921275 + outer loop + vertex 1.67733 0.984191 2.46198 + vertex 1.67751 0.989025 2.4633 + vertex 1.67259 0.984018 2.4634 + endloop + endfacet + facet normal 0.280591 -0.255048 0.925321 + outer loop + vertex 1.68609 0.990416 2.46107 + vertex 1.68717 0.994261 2.4618 + vertex 1.68226 0.989207 2.4619 + endloop + endfacet + facet normal 0.284019 -0.258415 0.923339 + outer loop + vertex 1.68717 0.994261 2.4618 + vertex 1.68248 0.99397 2.46316 + vertex 1.68226 0.989207 2.4619 + endloop + endfacet + facet normal 0.282757 -0.265122 0.921824 + outer loop + vertex 1.68408 0.987421 2.46084 + vertex 1.68115 0.985333 2.46113 + vertex 1.68298 0.983531 2.46005 + endloop + endfacet + facet normal 0.279172 -0.264452 0.923108 + outer loop + vertex 1.6876 0.978909 2.45732 + vertex 1.68777 0.983763 2.45866 + vertex 1.68281 0.978695 2.45871 + endloop + endfacet + facet normal 0.27907 -0.267322 0.922312 + outer loop + vertex 1.6876 0.978909 2.45732 + vertex 1.68281 0.978695 2.45871 + vertex 1.68264 0.973846 2.45735 + endloop + endfacet + facet normal 0.278661 -0.26692 0.922552 + outer loop + vertex 1.6865 0.975005 2.45653 + vertex 1.6876 0.978909 2.45732 + vertex 1.68264 0.973846 2.45735 + endloop + endfacet + facet normal 0.278839 -0.267714 0.922268 + outer loop + vertex 1.6865 0.975005 2.45653 + vertex 1.68264 0.973846 2.45735 + vertex 1.68446 0.972022 2.45628 + endloop + endfacet + facet normal 0.28282 -0.270269 0.920309 + outer loop + vertex 1.68826 0.973202 2.45545 + vertex 1.6865 0.975005 2.45653 + vertex 1.68446 0.972022 2.45628 + endloop + endfacet + facet normal 0.282596 -0.269303 0.92066 + outer loop + vertex 1.68446 0.972022 2.45628 + vertex 1.68328 0.968168 2.45551 + vertex 1.68826 0.973202 2.45545 + endloop + endfacet + facet normal 0.281583 -0.268294 0.921265 + outer loop + vertex 1.68826 0.973202 2.45545 + vertex 1.68328 0.968168 2.45551 + vertex 1.68792 0.968421 2.45416 + endloop + endfacet + facet normal 0.288983 -0.2682 0.918998 + outer loop + vertex 1.68792 0.968421 2.45416 + vertex 1.69296 0.973441 2.45404 + vertex 1.68826 0.973202 2.45545 + endloop + endfacet + facet normal 0.289006 -0.267494 0.919197 + outer loop + vertex 1.69323 0.978288 2.45537 + vertex 1.68826 0.973202 2.45545 + vertex 1.69296 0.973441 2.45404 + endloop + endfacet + facet normal 0.293401 -0.271836 0.916526 + outer loop + vertex 1.68942 0.977088 2.45623 + vertex 1.68826 0.973202 2.45545 + vertex 1.69323 0.978288 2.45537 + endloop + endfacet + facet normal 0.29396 -0.274258 0.915625 + outer loop + vertex 1.69323 0.978288 2.45537 + vertex 1.69145 0.980078 2.45648 + vertex 1.68942 0.977088 2.45623 + endloop + endfacet + facet normal 0.282723 -0.267099 0.921263 + outer loop + vertex 1.69145 0.980078 2.45648 + vertex 1.6876 0.978909 2.45732 + vertex 1.68942 0.977088 2.45623 + endloop + endfacet + facet normal 0.281586 -0.262068 0.923055 + outer loop + vertex 1.69145 0.980078 2.45648 + vertex 1.69254 0.983988 2.45726 + vertex 1.6876 0.978909 2.45732 + endloop + endfacet + facet normal 0.286549 -0.265721 0.920479 + outer loop + vertex 1.69276 0.968453 2.45267 + vertex 1.69296 0.973441 2.45404 + vertex 1.68792 0.968421 2.45416 + endloop + endfacet + facet normal 0.281343 -0.276597 0.91888 + outer loop + vertex 1.68293 0.963482 2.45421 + vertex 1.68792 0.968421 2.45416 + vertex 1.68328 0.968168 2.45551 + endloop + endfacet + facet normal 0.279117 -0.268497 0.921956 + outer loop + vertex 1.68446 0.972022 2.45628 + vertex 1.68152 0.969941 2.45656 + vertex 1.68328 0.968168 2.45551 + endloop + endfacet + facet normal 0.279329 -0.268285 0.921954 + outer loop + vertex 1.68328 0.968168 2.45551 + vertex 1.68152 0.969941 2.45656 + vertex 1.67949 0.966987 2.45631 + endloop + endfacet + facet normal 0.28013 -0.271697 0.920711 + outer loop + vertex 1.67949 0.966987 2.45631 + vertex 1.67843 0.963298 2.45555 + vertex 1.68328 0.968168 2.45551 + endloop + endfacet + facet normal 0.285731 -0.272882 0.918637 + outer loop + vertex 1.67949 0.966987 2.45631 + vertex 1.6766 0.964938 2.45661 + vertex 1.67843 0.963298 2.45555 + endloop + endfacet + facet normal 0.288131 -0.270223 0.918673 + outer loop + vertex 1.67843 0.963298 2.45555 + vertex 1.6766 0.964938 2.45661 + vertex 1.67475 0.962135 2.45636 + endloop + endfacet + facet normal 0.289537 -0.271089 0.917975 + outer loop + vertex 1.6766 0.964938 2.45661 + vertex 1.67277 0.963761 2.45746 + vertex 1.67475 0.962135 2.45636 + endloop + endfacet + facet normal 0.290699 -0.269706 0.918016 + outer loop + vertex 1.67475 0.962135 2.45636 + vertex 1.67277 0.963761 2.45746 + vertex 1.67193 0.959969 2.45662 + endloop + endfacet + facet normal 0.289065 -0.268999 0.918739 + outer loop + vertex 1.6766 0.964938 2.45661 + vertex 1.67768 0.968792 2.45739 + vertex 1.67277 0.963761 2.45746 + endloop + endfacet + facet normal 0.284352 -0.264369 0.921549 + outer loop + vertex 1.67768 0.968792 2.45739 + vertex 1.67289 0.968598 2.45881 + vertex 1.67277 0.963761 2.45746 + endloop + endfacet + facet normal 0.290337 -0.264022 0.919781 + outer loop + vertex 1.67277 0.963761 2.45746 + vertex 1.67289 0.968598 2.45881 + vertex 1.66795 0.963527 2.45892 + endloop + endfacet + facet normal 0.290281 -0.265637 0.919334 + outer loop + vertex 1.67277 0.963761 2.45746 + vertex 1.66795 0.963527 2.45892 + vertex 1.66786 0.958626 2.45753 + endloop + endfacet + facet normal 0.28227 -0.267614 0.921253 + outer loop + vertex 1.67949 0.966987 2.45631 + vertex 1.67768 0.968792 2.45739 + vertex 1.6766 0.964938 2.45661 + endloop + endfacet + facet normal 0.280721 -0.269184 0.921269 + outer loop + vertex 1.68152 0.969941 2.45656 + vertex 1.67768 0.968792 2.45739 + vertex 1.67949 0.966987 2.45631 + endloop + endfacet + facet normal 0.280514 -0.268245 0.921605 + outer loop + vertex 1.68152 0.969941 2.45656 + vertex 1.68264 0.973846 2.45735 + vertex 1.67768 0.968792 2.45739 + endloop + endfacet + facet normal 0.279323 -0.26707 0.922308 + outer loop + vertex 1.68264 0.973846 2.45735 + vertex 1.67785 0.973649 2.45875 + vertex 1.67768 0.968792 2.45739 + endloop + endfacet + facet normal 0.283475 -0.269622 0.920297 + outer loop + vertex 1.68942 0.977088 2.45623 + vertex 1.6865 0.975005 2.45653 + vertex 1.68826 0.973202 2.45545 + endloop + endfacet + facet normal 0.278695 -0.267858 0.92227 + outer loop + vertex 1.68446 0.972022 2.45628 + vertex 1.68264 0.973846 2.45735 + vertex 1.68152 0.969941 2.45656 + endloop + endfacet + facet normal 0.282171 -0.267654 0.921271 + outer loop + vertex 1.68942 0.977088 2.45623 + vertex 1.6876 0.978909 2.45732 + vertex 1.6865 0.975005 2.45653 + endloop + endfacet + facet normal 0.2838 -0.264234 0.921758 + outer loop + vertex 1.69254 0.983988 2.45726 + vertex 1.68777 0.983763 2.45866 + vertex 1.6876 0.978909 2.45732 + endloop + endfacet + facet normal 0.282165 -0.268732 0.920959 + outer loop + vertex 1.67914 0.982369 2.46089 + vertex 1.67803 0.978491 2.4601 + vertex 1.68298 0.983531 2.46005 + endloop + endfacet + facet normal 0.279314 -0.26731 0.922241 + outer loop + vertex 1.68264 0.973846 2.45735 + vertex 1.68281 0.978695 2.45871 + vertex 1.67785 0.973649 2.45875 + endloop + endfacet + facet normal 0.282187 -0.267265 0.921379 + outer loop + vertex 1.67419 0.977359 2.46095 + vertex 1.67308 0.97346 2.46016 + vertex 1.67803 0.978491 2.4601 + endloop + endfacet + facet normal 0.284249 -0.266845 0.920867 + outer loop + vertex 1.67768 0.968792 2.45739 + vertex 1.67785 0.973649 2.45875 + vertex 1.67289 0.968598 2.45881 + endloop + endfacet + facet normal 0.28814 -0.261856 0.92109 + outer loop + vertex 1.66795 0.963527 2.45892 + vertex 1.67289 0.968598 2.45881 + vertex 1.66815 0.968392 2.46024 + endloop + endfacet + facet normal 0.290039 -0.261776 0.920516 + outer loop + vertex 1.66815 0.968392 2.46024 + vertex 1.66322 0.963297 2.46034 + vertex 1.66795 0.963527 2.45892 + endloop + endfacet + facet normal 0.289988 -0.263296 0.920099 + outer loop + vertex 1.66297 0.958494 2.45905 + vertex 1.66795 0.963527 2.45892 + vertex 1.66322 0.963297 2.46034 + endloop + endfacet + facet normal 0.291623 -0.263326 0.919574 + outer loop + vertex 1.66435 0.967212 2.46111 + vertex 1.66322 0.963297 2.46034 + vertex 1.66815 0.968392 2.46024 + endloop + endfacet + facet normal 0.291927 -0.264656 0.919095 + outer loop + vertex 1.66815 0.968392 2.46024 + vertex 1.66635 0.970223 2.46134 + vertex 1.66435 0.967212 2.46111 + endloop + endfacet + facet normal 0.293907 -0.265895 0.918106 + outer loop + vertex 1.66635 0.970223 2.46134 + vertex 1.66255 0.969022 2.46221 + vertex 1.66435 0.967212 2.46111 + endloop + endfacet + facet normal 0.293143 -0.266669 0.918126 + outer loop + vertex 1.66435 0.967212 2.46111 + vertex 1.66255 0.969022 2.46221 + vertex 1.66145 0.965097 2.46142 + endloop + endfacet + facet normal 0.289995 -0.266027 0.919311 + outer loop + vertex 1.66145 0.965097 2.46142 + vertex 1.66255 0.969022 2.46221 + vertex 1.65762 0.963913 2.46229 + endloop + endfacet + facet normal 0.289827 -0.26529 0.919577 + outer loop + vertex 1.66145 0.965097 2.46142 + vertex 1.65762 0.963913 2.46229 + vertex 1.65942 0.962093 2.46119 + endloop + endfacet + facet normal 0.289087 -0.264818 0.919946 + outer loop + vertex 1.66322 0.963297 2.46034 + vertex 1.66145 0.965097 2.46142 + vertex 1.65942 0.962093 2.46119 + endloop + endfacet + facet normal 0.288962 -0.264288 0.920137 + outer loop + vertex 1.65942 0.962093 2.46119 + vertex 1.65827 0.958273 2.46046 + vertex 1.66322 0.963297 2.46034 + endloop + endfacet + facet normal 0.287489 -0.26395 0.920696 + outer loop + vertex 1.65942 0.962093 2.46119 + vertex 1.65648 0.960008 2.46151 + vertex 1.65827 0.958273 2.46046 + endloop + endfacet + facet normal 0.288948 -0.266176 0.919597 + outer loop + vertex 1.65942 0.962093 2.46119 + vertex 1.65762 0.963913 2.46229 + vertex 1.65648 0.960008 2.46151 + endloop + endfacet + facet normal 0.292688 -0.26698 0.918181 + outer loop + vertex 1.65648 0.960008 2.46151 + vertex 1.65762 0.963913 2.46229 + vertex 1.65264 0.958869 2.4624 + endloop + endfacet + facet normal 0.292932 -0.268126 0.917769 + outer loop + vertex 1.65648 0.960008 2.46151 + vertex 1.65264 0.958869 2.4624 + vertex 1.65446 0.957094 2.46131 + endloop + endfacet + facet normal 0.287146 -0.264305 0.920701 + outer loop + vertex 1.65827 0.958273 2.46046 + vertex 1.65648 0.960008 2.46151 + vertex 1.65446 0.957094 2.46131 + endloop + endfacet + facet normal 0.294826 -0.266169 0.917732 + outer loop + vertex 1.65446 0.957094 2.46131 + vertex 1.65264 0.958869 2.4624 + vertex 1.65157 0.955085 2.46165 + endloop + endfacet + facet normal 0.290963 -0.265255 0.919228 + outer loop + vertex 1.65762 0.963913 2.46229 + vertex 1.65286 0.9637 2.46373 + vertex 1.65264 0.958869 2.4624 + endloop + endfacet + facet normal 0.290867 -0.267678 0.918556 + outer loop + vertex 1.65762 0.963913 2.46229 + vertex 1.65781 0.968764 2.46364 + vertex 1.65286 0.9637 2.46373 + endloop + endfacet + facet normal 0.291652 -0.267643 0.918317 + outer loop + vertex 1.66255 0.969022 2.46221 + vertex 1.65781 0.968764 2.46364 + vertex 1.65762 0.963913 2.46229 + endloop + endfacet + facet normal 0.294694 -0.269287 0.916864 + outer loop + vertex 1.66635 0.970223 2.46134 + vertex 1.66746 0.974127 2.46213 + vertex 1.66255 0.969022 2.46221 + endloop + endfacet + facet normal 0.293736 -0.268357 0.917444 + outer loop + vertex 1.66746 0.974127 2.46213 + vertex 1.66273 0.973863 2.46357 + vertex 1.66255 0.969022 2.46221 + endloop + endfacet + facet normal 0.290763 -0.263141 0.919899 + outer loop + vertex 1.66435 0.967212 2.46111 + vertex 1.66145 0.965097 2.46142 + vertex 1.66322 0.963297 2.46034 + endloop + endfacet + facet normal 0.291606 -0.264977 0.919105 + outer loop + vertex 1.66926 0.972317 2.46102 + vertex 1.66635 0.970223 2.46134 + vertex 1.66815 0.968392 2.46024 + endloop + endfacet + facet normal 0.286013 -0.26807 0.919965 + outer loop + vertex 1.67419 0.977359 2.46095 + vertex 1.67127 0.9753 2.46126 + vertex 1.67308 0.97346 2.46016 + endloop + endfacet + facet normal 0.294446 -0.269236 0.916959 + outer loop + vertex 1.66926 0.972317 2.46102 + vertex 1.66746 0.974127 2.46213 + vertex 1.66635 0.970223 2.46134 + endloop + endfacet + facet normal 0.288035 -0.27117 0.918424 + outer loop + vertex 1.67419 0.977359 2.46095 + vertex 1.67239 0.979182 2.46205 + vertex 1.67127 0.9753 2.46126 + endloop + endfacet + facet normal 0.285612 -0.267907 0.920137 + outer loop + vertex 1.67733 0.984191 2.46198 + vertex 1.67259 0.984018 2.4634 + vertex 1.67239 0.979182 2.46205 + endloop + endfacet + facet normal 0.288798 -0.262375 0.920736 + outer loop + vertex 1.66402 0.982655 2.46569 + vertex 1.66292 0.978722 2.46492 + vertex 1.66785 0.983842 2.46483 + endloop + endfacet + facet normal 0.288176 -0.259668 0.921698 + outer loop + vertex 1.66785 0.983842 2.46483 + vertex 1.66601 0.985631 2.46591 + vertex 1.66402 0.982655 2.46569 + endloop + endfacet + facet normal 0.287182 -0.259038 0.922185 + outer loop + vertex 1.66601 0.985631 2.46591 + vertex 1.66219 0.984354 2.46674 + vertex 1.66402 0.982655 2.46569 + endloop + endfacet + facet normal 0.28737 -0.258834 0.922184 + outer loop + vertex 1.66402 0.982655 2.46569 + vertex 1.66219 0.984354 2.46674 + vertex 1.66109 0.980516 2.46601 + endloop + endfacet + facet normal 0.286056 -0.25855 0.922672 + outer loop + vertex 1.66109 0.980516 2.46601 + vertex 1.66219 0.984354 2.46674 + vertex 1.65727 0.97929 2.46685 + endloop + endfacet + facet normal 0.28647 -0.260255 0.922064 + outer loop + vertex 1.66109 0.980516 2.46601 + vertex 1.65727 0.97929 2.46685 + vertex 1.65907 0.9775 2.46578 + endloop + endfacet + facet normal 0.290028 -0.262501 0.920314 + outer loop + vertex 1.66292 0.978722 2.46492 + vertex 1.66109 0.980516 2.46601 + vertex 1.65907 0.9775 2.46578 + endloop + endfacet + facet normal 0.285788 -0.260952 0.922079 + outer loop + vertex 1.65907 0.9775 2.46578 + vertex 1.65727 0.97929 2.46685 + vertex 1.65616 0.975394 2.46609 + endloop + endfacet + facet normal 0.289078 -0.265853 0.91965 + outer loop + vertex 1.65907 0.9775 2.46578 + vertex 1.65616 0.975394 2.46609 + vertex 1.65799 0.973595 2.46499 + endloop + endfacet + facet normal 0.288442 -0.266503 0.919661 + outer loop + vertex 1.65799 0.973595 2.46499 + vertex 1.65616 0.975394 2.46609 + vertex 1.65417 0.972418 2.46585 + endloop + endfacet + facet normal 0.28615 -0.265058 0.920794 + outer loop + vertex 1.65616 0.975394 2.46609 + vertex 1.65236 0.974243 2.46694 + vertex 1.65417 0.972418 2.46585 + endloop + endfacet + facet normal 0.285806 -0.265403 0.920802 + outer loop + vertex 1.65417 0.972418 2.46585 + vertex 1.65236 0.974243 2.46694 + vertex 1.65127 0.97036 2.46616 + endloop + endfacet + facet normal 0.287272 -0.267631 0.9197 + outer loop + vertex 1.65417 0.972418 2.46585 + vertex 1.65127 0.97036 2.46616 + vertex 1.65308 0.968539 2.46506 + endloop + endfacet + facet normal 0.287939 -0.266962 0.919686 + outer loop + vertex 1.65308 0.968539 2.46506 + vertex 1.65127 0.97036 2.46616 + vertex 1.64927 0.967402 2.46592 + endloop + endfacet + facet normal 0.293189 -0.270308 0.917046 + outer loop + vertex 1.65127 0.97036 2.46616 + vertex 1.64746 0.969198 2.46703 + vertex 1.64927 0.967402 2.46592 + endloop + endfacet + facet normal 0.295393 -0.268052 0.917001 + outer loop + vertex 1.64927 0.967402 2.46592 + vertex 1.64746 0.969198 2.46703 + vertex 1.64635 0.965318 2.46625 + endloop + endfacet + facet normal 0.291615 -0.262312 0.919866 + outer loop + vertex 1.64927 0.967402 2.46592 + vertex 1.64635 0.965318 2.46625 + vertex 1.64814 0.963489 2.46517 + endloop + endfacet + facet normal 0.294964 -0.258969 0.919745 + outer loop + vertex 1.64814 0.963489 2.46517 + vertex 1.64635 0.965318 2.46625 + vertex 1.64432 0.962293 2.46605 + endloop + endfacet + facet normal 0.303078 -0.264143 0.915627 + outer loop + vertex 1.64635 0.965318 2.46625 + vertex 1.64251 0.964049 2.46716 + vertex 1.64432 0.962293 2.46605 + endloop + endfacet + facet normal 0.305411 -0.261692 0.915555 + outer loop + vertex 1.64432 0.962293 2.46605 + vertex 1.64251 0.964049 2.46716 + vertex 1.64139 0.960103 2.46641 + endloop + endfacet + facet normal 0.302516 -0.257469 0.917711 + outer loop + vertex 1.64432 0.962293 2.46605 + vertex 1.64139 0.960103 2.46641 + vertex 1.64316 0.958317 2.46532 + endloop + endfacet + facet normal 0.302081 -0.257913 0.91773 + outer loop + vertex 1.64316 0.958317 2.46532 + vertex 1.64139 0.960103 2.46641 + vertex 1.63934 0.957 2.46621 + endloop + endfacet + facet normal 0.288331 -0.249263 0.924518 + outer loop + vertex 1.64139 0.960103 2.46641 + vertex 1.63759 0.958846 2.46725 + vertex 1.63934 0.957 2.46621 + endloop + endfacet + facet normal 0.281783 -0.255621 0.924801 + outer loop + vertex 1.63934 0.957 2.46621 + vertex 1.63759 0.958846 2.46725 + vertex 1.63644 0.954859 2.4665 + endloop + endfacet + facet normal 0.298998 -0.28071 0.912032 + outer loop + vertex 1.63934 0.957 2.46621 + vertex 1.63644 0.954859 2.4665 + vertex 1.63815 0.953119 2.4654 + endloop + endfacet + facet normal 0.2802 -0.299239 0.91211 + outer loop + vertex 1.63815 0.953119 2.4654 + vertex 1.63644 0.954859 2.4665 + vertex 1.63435 0.951956 2.46619 + endloop + endfacet + facet normal 0.225605 -0.26277 0.938112 + outer loop + vertex 1.63644 0.954859 2.4665 + vertex 1.63285 0.95412 2.46716 + vertex 1.63435 0.951956 2.46619 + endloop + endfacet + facet normal 0.222501 -0.242128 0.944388 + outer loop + vertex 1.63644 0.954859 2.4665 + vertex 1.63759 0.958846 2.46725 + vertex 1.63285 0.95412 2.46716 + endloop + endfacet + facet normal 0.252133 -0.27155 0.928811 + outer loop + vertex 1.63759 0.958846 2.46725 + vertex 1.63299 0.958763 2.46848 + vertex 1.63285 0.95412 2.46716 + endloop + endfacet + facet normal 0.252313 -0.268294 0.929708 + outer loop + vertex 1.63759 0.958846 2.46725 + vertex 1.63775 0.963686 2.4686 + vertex 1.63299 0.958763 2.46848 + endloop + endfacet + facet normal 0.277916 -0.292654 0.914941 + outer loop + vertex 1.63299 0.958763 2.46848 + vertex 1.63775 0.963686 2.4686 + vertex 1.63293 0.963439 2.46999 + endloop + endfacet + facet normal 0.177247 -0.301044 0.936993 + outer loop + vertex 1.63293 0.963439 2.46999 + vertex 1.62792 0.958668 2.46941 + vertex 1.63299 0.958763 2.46848 + endloop + endfacet + facet normal 0.17781 -0.285919 0.941612 + outer loop + vertex 1.62921 0.954901 2.46802 + vertex 1.63299 0.958763 2.46848 + vertex 1.62792 0.958668 2.46941 + endloop + endfacet + facet normal 0.165149 -0.274204 0.947385 + outer loop + vertex 1.63285 0.95412 2.46716 + vertex 1.63299 0.958763 2.46848 + vertex 1.62921 0.954901 2.46802 + endloop + endfacet + facet normal 0.155868 -0.307791 0.9386 + outer loop + vertex 1.63285 0.95412 2.46716 + vertex 1.62921 0.954901 2.46802 + vertex 1.62817 0.950806 2.46685 + endloop + endfacet + facet normal 0.238124 -0.360772 0.901743 + outer loop + vertex 1.62902 0.962666 2.47071 + vertex 1.62792 0.958668 2.46941 + vertex 1.63293 0.963439 2.46999 + endloop + endfacet + facet normal 0.235461 -0.338626 0.910983 + outer loop + vertex 1.63293 0.963439 2.46999 + vertex 1.63126 0.965412 2.47116 + vertex 1.62902 0.962666 2.47071 + endloop + endfacet + facet normal 0.171071 -0.291027 0.941296 + outer loop + vertex 1.63126 0.965412 2.47116 + vertex 1.6282 0.965265 2.47167 + vertex 1.62902 0.962666 2.47071 + endloop + endfacet + facet normal 0.106711 -0.312364 0.94395 + outer loop + vertex 1.62902 0.962666 2.47071 + vertex 1.6282 0.965265 2.47167 + vertex 1.62519 0.961514 2.47076 + endloop + endfacet + facet normal 0.170974 -0.235831 0.956635 + outer loop + vertex 1.63126 0.965412 2.47116 + vertex 1.63242 0.969228 2.47189 + vertex 1.6282 0.965265 2.47167 + endloop + endfacet + facet normal 0.192722 -0.258459 0.946603 + outer loop + vertex 1.63242 0.969228 2.47189 + vertex 1.62792 0.969042 2.47275 + vertex 1.6282 0.965265 2.47167 + endloop + endfacet + facet normal 0.192805 -0.250075 0.948835 + outer loop + vertex 1.63242 0.969228 2.47189 + vertex 1.63256 0.973746 2.47305 + vertex 1.62792 0.969042 2.47275 + endloop + endfacet + facet normal 0.214501 -0.270792 0.938435 + outer loop + vertex 1.62792 0.969042 2.47275 + vertex 1.63256 0.973746 2.47305 + vertex 1.62782 0.973371 2.47403 + endloop + endfacet + facet normal 0.214399 -0.26556 0.939953 + outer loop + vertex 1.63256 0.973746 2.47305 + vertex 1.63283 0.978331 2.47429 + vertex 1.62782 0.973371 2.47403 + endloop + endfacet + facet normal 0.252779 -0.303163 0.918801 + outer loop + vertex 1.62782 0.973371 2.47403 + vertex 1.63283 0.978331 2.47429 + vertex 1.62819 0.977991 2.47545 + endloop + endfacet + facet normal 0.143305 -0.301819 0.942533 + outer loop + vertex 1.62819 0.977991 2.47545 + vertex 1.62266 0.97334 2.4748 + vertex 1.62782 0.973371 2.47403 + endloop + endfacet + facet normal 0.252922 -0.27274 0.928247 + outer loop + vertex 1.63328 0.983046 2.47555 + vertex 1.62819 0.977991 2.47545 + vertex 1.63283 0.978331 2.47429 + endloop + endfacet + facet normal 0.297857 -0.273384 0.914627 + outer loop + vertex 1.63283 0.978331 2.47429 + vertex 1.63783 0.983492 2.4742 + vertex 1.63328 0.983046 2.47555 + endloop + endfacet + facet normal 0.297589 -0.251278 0.921032 + outer loop + vertex 1.63822 0.988288 2.47538 + vertex 1.63328 0.983046 2.47555 + vertex 1.63783 0.983492 2.4742 + endloop + endfacet + facet normal 0.294788 -0.251269 0.921935 + outer loop + vertex 1.63783 0.983492 2.4742 + vertex 1.64287 0.98856 2.47397 + vertex 1.63822 0.988288 2.47538 + endloop + endfacet + facet normal 0.294864 -0.247749 0.922863 + outer loop + vertex 1.64315 0.993436 2.47519 + vertex 1.63822 0.988288 2.47538 + vertex 1.64287 0.98856 2.47397 + endloop + endfacet + facet normal 0.285344 -0.247919 0.925805 + outer loop + vertex 1.64287 0.98856 2.47397 + vertex 1.6479 0.9936 2.47377 + vertex 1.64315 0.993436 2.47519 + endloop + endfacet + facet normal 0.285244 -0.250309 0.925192 + outer loop + vertex 1.64808 0.998544 2.47505 + vertex 1.64315 0.993436 2.47519 + vertex 1.6479 0.9936 2.47377 + endloop + endfacet + facet normal 0.285295 -0.250307 0.925177 + outer loop + vertex 1.6479 0.9936 2.47377 + vertex 1.65282 0.998713 2.47363 + vertex 1.64808 0.998544 2.47505 + endloop + endfacet + facet normal 0.285347 -0.249041 0.925503 + outer loop + vertex 1.65297 1.00368 2.47492 + vertex 1.64808 0.998544 2.47505 + vertex 1.65282 0.998713 2.47363 + endloop + endfacet + facet normal 0.288905 -0.252478 0.923466 + outer loop + vertex 1.64918 1.00251 2.47579 + vertex 1.64808 0.998544 2.47505 + vertex 1.65297 1.00368 2.47492 + endloop + endfacet + facet normal 0.288152 -0.249207 0.924589 + outer loop + vertex 1.65297 1.00368 2.47492 + vertex 1.65113 1.0055 2.47599 + vertex 1.64918 1.00251 2.47579 + endloop + endfacet + facet normal 0.285994 -0.247867 0.925618 + outer loop + vertex 1.65113 1.0055 2.47599 + vertex 1.64733 1.00429 2.47684 + vertex 1.64918 1.00251 2.47579 + endloop + endfacet + facet normal 0.284167 -0.249789 0.925664 + outer loop + vertex 1.64918 1.00251 2.47579 + vertex 1.64733 1.00429 2.47684 + vertex 1.64628 1.00039 2.47611 + endloop + endfacet + facet normal 0.28813 -0.250595 0.924221 + outer loop + vertex 1.64628 1.00039 2.47611 + vertex 1.64733 1.00429 2.47684 + vertex 1.64246 0.999192 2.47698 + endloop + endfacet + facet normal 0.289336 -0.255735 0.922434 + outer loop + vertex 1.64628 1.00039 2.47611 + vertex 1.64246 0.999192 2.47698 + vertex 1.64427 0.997373 2.4759 + endloop + endfacet + facet normal 0.284559 -0.252719 0.924748 + outer loop + vertex 1.64808 0.998544 2.47505 + vertex 1.64628 1.00039 2.47611 + vertex 1.64427 0.997373 2.4759 + endloop + endfacet + facet normal 0.290577 -0.254471 0.922393 + outer loop + vertex 1.64427 0.997373 2.4759 + vertex 1.64246 0.999192 2.47698 + vertex 1.64137 0.995263 2.47623 + endloop + endfacet + facet normal 0.287247 -0.24952 0.924786 + outer loop + vertex 1.64427 0.997373 2.4759 + vertex 1.64137 0.995263 2.47623 + vertex 1.64315 0.993436 2.47519 + endloop + endfacet + facet normal 0.290095 -0.246672 0.924661 + outer loop + vertex 1.64315 0.993436 2.47519 + vertex 1.64137 0.995263 2.47623 + vertex 1.63938 0.99224 2.47605 + endloop + endfacet + facet normal 0.300901 -0.253494 0.919347 + outer loop + vertex 1.64137 0.995263 2.47623 + vertex 1.63757 0.994019 2.47713 + vertex 1.63938 0.99224 2.47605 + endloop + endfacet + facet normal 0.304333 -0.249924 0.919195 + outer loop + vertex 1.63938 0.99224 2.47605 + vertex 1.63757 0.994019 2.47713 + vertex 1.6365 0.990075 2.47642 + endloop + endfacet + facet normal 0.30068 -0.244636 0.921816 + outer loop + vertex 1.63938 0.99224 2.47605 + vertex 1.6365 0.990075 2.47642 + vertex 1.63822 0.988288 2.47538 + endloop + endfacet + facet normal 0.302939 -0.242375 0.921674 + outer loop + vertex 1.63822 0.988288 2.47538 + vertex 1.6365 0.990075 2.47642 + vertex 1.6345 0.986987 2.47626 + endloop + endfacet + facet normal 0.294607 -0.237186 0.925716 + outer loop + vertex 1.6365 0.990075 2.47642 + vertex 1.63272 0.988782 2.47729 + vertex 1.6345 0.986987 2.47626 + endloop + endfacet + facet normal 0.291636 -0.240222 0.925874 + outer loop + vertex 1.6345 0.986987 2.47626 + vertex 1.63272 0.988782 2.47729 + vertex 1.63166 0.984801 2.47659 + endloop + endfacet + facet normal 0.30625 -0.260825 0.915522 + outer loop + vertex 1.6345 0.986987 2.47626 + vertex 1.63166 0.984801 2.47659 + vertex 1.63328 0.983046 2.47555 + endloop + endfacet + facet normal 0.294309 -0.272202 0.916127 + outer loop + vertex 1.63328 0.983046 2.47555 + vertex 1.63166 0.984801 2.47659 + vertex 1.62961 0.98178 2.47635 + endloop + endfacet + facet normal 0.23776 -0.236042 0.942207 + outer loop + vertex 1.63166 0.984801 2.47659 + vertex 1.62798 0.983781 2.47726 + vertex 1.62961 0.98178 2.47635 + endloop + endfacet + facet normal 0.217375 -0.252943 0.942745 + outer loop + vertex 1.62961 0.98178 2.47635 + vertex 1.62798 0.983781 2.47726 + vertex 1.6268 0.979944 2.47651 + endloop + endfacet + facet normal 0.255052 -0.31311 0.914828 + outer loop + vertex 1.62961 0.98178 2.47635 + vertex 1.6268 0.979944 2.47651 + vertex 1.62819 0.977991 2.47545 + endloop + endfacet + facet normal 0.139523 -0.232877 0.962446 + outer loop + vertex 1.6268 0.979944 2.47651 + vertex 1.62798 0.983781 2.47726 + vertex 1.62369 0.979892 2.47694 + endloop + endfacet + facet normal 0.138229 -0.292782 0.946135 + outer loop + vertex 1.6268 0.979944 2.47651 + vertex 1.62369 0.979892 2.47694 + vertex 1.62436 0.977268 2.47603 + endloop + endfacet + facet normal 0.205313 -0.348412 0.914579 + outer loop + vertex 1.62819 0.977991 2.47545 + vertex 1.6268 0.979944 2.47651 + vertex 1.62436 0.977268 2.47603 + endloop + endfacet + facet normal 0.208466 -0.373868 0.90375 + outer loop + vertex 1.62436 0.977268 2.47603 + vertex 1.62266 0.97334 2.4748 + vertex 1.62819 0.977991 2.47545 + endloop + endfacet + facet normal 0.0894996 -0.33342 0.938521 + outer loop + vertex 1.62436 0.977268 2.47603 + vertex 1.62039 0.976206 2.47604 + vertex 1.62266 0.97334 2.4748 + endloop + endfacet + facet normal 0.082579 -0.307546 0.947943 + outer loop + vertex 1.62436 0.977268 2.47603 + vertex 1.62369 0.979892 2.47694 + vertex 1.62039 0.976206 2.47604 + endloop + endfacet + facet normal 0.168495 -0.263785 0.949751 + outer loop + vertex 1.62798 0.983781 2.47726 + vertex 1.62326 0.983774 2.4781 + vertex 1.62369 0.979892 2.47694 + endloop + endfacet + facet normal 0.168826 -0.256504 0.951685 + outer loop + vertex 1.62798 0.983781 2.47726 + vertex 1.62789 0.988513 2.47855 + vertex 1.62326 0.983774 2.4781 + endloop + endfacet + facet normal 0.195944 -0.281806 0.939251 + outer loop + vertex 1.62326 0.983774 2.4781 + vertex 1.62789 0.988513 2.47855 + vertex 1.62259 0.988442 2.47964 + endloop + endfacet + facet normal 0.195872 -0.283371 0.938795 + outer loop + vertex 1.62795 0.993418 2.48002 + vertex 1.62259 0.988442 2.47964 + vertex 1.62789 0.988513 2.47855 + endloop + endfacet + facet normal 0.285307 -0.278016 0.917228 + outer loop + vertex 1.62789 0.988513 2.47855 + vertex 1.6328 0.993674 2.47859 + vertex 1.62795 0.993418 2.48002 + endloop + endfacet + facet normal 0.285939 -0.257169 0.923094 + outer loop + vertex 1.63293 0.998638 2.47993 + vertex 1.62795 0.993418 2.48002 + vertex 1.6328 0.993674 2.47859 + endloop + endfacet + facet normal 0.303555 -0.256167 0.917733 + outer loop + vertex 1.6328 0.993674 2.47859 + vertex 1.6377 0.998919 2.47843 + vertex 1.63293 0.998638 2.47993 + endloop + endfacet + facet normal 0.303817 -0.24532 0.920605 + outer loop + vertex 1.63775 1.00386 2.47973 + vertex 1.63293 0.998638 2.47993 + vertex 1.6377 0.998919 2.47843 + endloop + endfacet + facet normal 0.293182 -0.246057 0.923851 + outer loop + vertex 1.6377 0.998919 2.47843 + vertex 1.64259 1.00408 2.47826 + vertex 1.63775 1.00386 2.47973 + endloop + endfacet + facet normal 0.293185 -0.245957 0.923877 + outer loop + vertex 1.64269 1.00913 2.47957 + vertex 1.63775 1.00386 2.47973 + vertex 1.64259 1.00408 2.47826 + endloop + endfacet + facet normal 0.287604 -0.246281 0.925543 + outer loop + vertex 1.64259 1.00408 2.47826 + vertex 1.6475 1.00903 2.47805 + vertex 1.64269 1.00913 2.47957 + endloop + endfacet + facet normal 0.287623 -0.246083 0.92559 + outer loop + vertex 1.6475 1.00903 2.47805 + vertex 1.64796 1.01378 2.47917 + vertex 1.64269 1.00913 2.47957 + endloop + endfacet + facet normal 0.287815 -0.246311 0.925469 + outer loop + vertex 1.64269 1.00913 2.47957 + vertex 1.64796 1.01378 2.47917 + vertex 1.64426 1.01409 2.4804 + endloop + endfacet + facet normal 0.288159 -0.246398 0.925339 + outer loop + vertex 1.64269 1.00913 2.47957 + vertex 1.64426 1.01409 2.4804 + vertex 1.64019 1.01135 2.48094 + endloop + endfacet + facet normal 0.288897 -0.245563 0.925331 + outer loop + vertex 1.63852 1.00775 2.4805 + vertex 1.64269 1.00913 2.47957 + vertex 1.64019 1.01135 2.48094 + endloop + endfacet + facet normal 0.297322 -0.249023 0.921731 + outer loop + vertex 1.64019 1.01135 2.48094 + vertex 1.63609 1.00856 2.48151 + vertex 1.63852 1.00775 2.4805 + endloop + endfacet + facet normal 0.298727 -0.245468 0.92223 + outer loop + vertex 1.63852 1.00775 2.4805 + vertex 1.63609 1.00856 2.48151 + vertex 1.63571 1.00549 2.48081 + endloop + endfacet + facet normal 0.295942 -0.24174 0.924111 + outer loop + vertex 1.63852 1.00775 2.4805 + vertex 1.63571 1.00549 2.48081 + vertex 1.63775 1.00386 2.47973 + endloop + endfacet + facet normal 0.300244 -0.23635 0.924117 + outer loop + vertex 1.63775 1.00386 2.47973 + vertex 1.63571 1.00549 2.48081 + vertex 1.63394 1.00261 2.48065 + endloop + endfacet + facet normal 0.303227 -0.238102 0.922692 + outer loop + vertex 1.63571 1.00549 2.48081 + vertex 1.63203 1.00416 2.48168 + vertex 1.63394 1.00261 2.48065 + endloop + endfacet + facet normal 0.305197 -0.235665 0.922668 + outer loop + vertex 1.63394 1.00261 2.48065 + vertex 1.63203 1.00416 2.48168 + vertex 1.63111 1.00045 2.48104 + endloop + endfacet + facet normal 0.312031 -0.245482 0.91781 + outer loop + vertex 1.63394 1.00261 2.48065 + vertex 1.63111 1.00045 2.48104 + vertex 1.63293 0.998638 2.47993 + endloop + endfacet + facet normal 0.308638 -0.248993 0.918011 + outer loop + vertex 1.63293 0.998638 2.47993 + vertex 1.63111 1.00045 2.48104 + vertex 1.62915 0.997403 2.48087 + endloop + endfacet + facet normal 0.277416 -0.22974 0.932877 + outer loop + vertex 1.63111 1.00045 2.48104 + vertex 1.62746 0.999256 2.48183 + vertex 1.62915 0.997403 2.48087 + endloop + endfacet + facet normal 0.266217 -0.240254 0.933492 + outer loop + vertex 1.62915 0.997403 2.48087 + vertex 1.62746 0.999256 2.48183 + vertex 1.62635 0.995433 2.48116 + endloop + endfacet + facet normal 0.293879 -0.282674 0.913089 + outer loop + vertex 1.62915 0.997403 2.48087 + vertex 1.62635 0.995433 2.48116 + vertex 1.62795 0.993418 2.48002 + endloop + endfacet + facet normal 0.254922 -0.314391 0.914425 + outer loop + vertex 1.62795 0.993418 2.48002 + vertex 1.62635 0.995433 2.48116 + vertex 1.62404 0.992569 2.48082 + endloop + endfacet + facet normal 0.197537 -0.271342 0.941994 + outer loop + vertex 1.62635 0.995433 2.48116 + vertex 1.62329 0.995181 2.48173 + vertex 1.62404 0.992569 2.48082 + endloop + endfacet + facet normal 0.134776 -0.291068 0.947161 + outer loop + vertex 1.62404 0.992569 2.48082 + vertex 1.62329 0.995181 2.48173 + vertex 1.62016 0.991297 2.48098 + endloop + endfacet + facet normal 0.143469 -0.31883 0.93689 + outer loop + vertex 1.62404 0.992569 2.48082 + vertex 1.62016 0.991297 2.48098 + vertex 1.62259 0.988442 2.47964 + endloop + endfacet + facet normal 0.195967 -0.223449 0.954813 + outer loop + vertex 1.62635 0.995433 2.48116 + vertex 1.62746 0.999256 2.48183 + vertex 1.62329 0.995181 2.48173 + endloop + endfacet + facet normal 0.21705 -0.244814 0.944963 + outer loop + vertex 1.62746 0.999256 2.48183 + vertex 1.62299 0.998953 2.48278 + vertex 1.62329 0.995181 2.48173 + endloop + endfacet + facet normal 0.216954 -0.237467 0.946858 + outer loop + vertex 1.62746 0.999256 2.48183 + vertex 1.62752 1.00372 2.48293 + vertex 1.62299 0.998953 2.48278 + endloop + endfacet + facet normal 0.23451 -0.253845 0.938386 + outer loop + vertex 1.62299 0.998953 2.48278 + vertex 1.62752 1.00372 2.48293 + vertex 1.62282 1.00332 2.484 + endloop + endfacet + facet normal 0.234421 -0.249931 0.939458 + outer loop + vertex 1.62752 1.00372 2.48293 + vertex 1.62774 1.00836 2.48411 + vertex 1.62282 1.00332 2.484 + endloop + endfacet + facet normal 0.270873 -0.285127 0.919419 + outer loop + vertex 1.62282 1.00332 2.484 + vertex 1.62774 1.00836 2.48411 + vertex 1.62309 1.00801 2.48537 + endloop + endfacet + facet normal 0.271037 -0.253246 0.928658 + outer loop + vertex 1.62812 1.0132 2.48532 + vertex 1.62309 1.00801 2.48537 + vertex 1.62774 1.00836 2.48411 + endloop + endfacet + facet normal 0.301546 -0.253255 0.919202 + outer loop + vertex 1.62774 1.00836 2.48411 + vertex 1.63277 1.01353 2.48389 + vertex 1.62812 1.0132 2.48532 + endloop + endfacet + facet normal 0.301731 -0.234421 0.924124 + outer loop + vertex 1.63305 1.01855 2.48507 + vertex 1.62812 1.0132 2.48532 + vertex 1.63277 1.01353 2.48389 + endloop + endfacet + facet normal 0.292878 -0.234578 0.926928 + outer loop + vertex 1.63277 1.01353 2.48389 + vertex 1.6378 1.01872 2.48361 + vertex 1.63305 1.01855 2.48507 + endloop + endfacet + facet normal 0.292846 -0.235396 0.926731 + outer loop + vertex 1.63795 1.02376 2.48484 + vertex 1.63305 1.01855 2.48507 + vertex 1.6378 1.01872 2.48361 + endloop + endfacet + facet normal 0.285093 -0.227924 0.931006 + outer loop + vertex 1.63415 1.02259 2.48572 + vertex 1.63305 1.01855 2.48507 + vertex 1.63795 1.02376 2.48484 + endloop + endfacet + facet normal 0.287089 -0.236465 0.928259 + outer loop + vertex 1.63795 1.02376 2.48484 + vertex 1.63611 1.02559 2.48588 + vertex 1.63415 1.02259 2.48572 + endloop + endfacet + facet normal 0.29822 -0.243433 0.922933 + outer loop + vertex 1.63611 1.02559 2.48588 + vertex 1.6323 1.02425 2.48676 + vertex 1.63415 1.02259 2.48572 + endloop + endfacet + facet normal 0.302783 -0.238231 0.922805 + outer loop + vertex 1.63415 1.02259 2.48572 + vertex 1.6323 1.02425 2.48676 + vertex 1.63126 1.02038 2.4861 + endloop + endfacet + facet normal 0.304257 -0.238531 0.922242 + outer loop + vertex 1.63126 1.02038 2.4861 + vertex 1.6323 1.02425 2.48676 + vertex 1.62748 1.01899 2.48699 + endloop + endfacet + facet normal 0.300536 -0.225482 0.926734 + outer loop + vertex 1.63126 1.02038 2.4861 + vertex 1.62748 1.01899 2.48699 + vertex 1.62928 1.01725 2.48598 + endloop + endfacet + facet normal 0.301665 -0.226177 0.926198 + outer loop + vertex 1.63305 1.01855 2.48507 + vertex 1.63126 1.02038 2.4861 + vertex 1.62928 1.01725 2.48598 + endloop + endfacet + facet normal 0.301661 -0.224278 0.92666 + outer loop + vertex 1.62928 1.01725 2.48598 + vertex 1.62748 1.01899 2.48699 + vertex 1.62644 1.01499 2.48636 + endloop + endfacet + facet normal 0.312259 -0.238827 0.919487 + outer loop + vertex 1.62928 1.01725 2.48598 + vertex 1.62644 1.01499 2.48636 + vertex 1.62812 1.0132 2.48532 + endloop + endfacet + facet normal 0.304739 -0.246207 0.920063 + outer loop + vertex 1.62812 1.0132 2.48532 + vertex 1.62644 1.01499 2.48636 + vertex 1.62444 1.0119 2.48619 + endloop + endfacet + facet normal 0.256586 -0.216347 0.941997 + outer loop + vertex 1.62644 1.01499 2.48636 + vertex 1.6228 1.01388 2.48709 + vertex 1.62444 1.0119 2.48619 + endloop + endfacet + facet normal 0.238466 -0.231824 0.943075 + outer loop + vertex 1.62444 1.0119 2.48619 + vertex 1.6228 1.01388 2.48709 + vertex 1.62167 1.00998 2.48642 + endloop + endfacet + facet normal 0.275422 -0.28848 0.917018 + outer loop + vertex 1.62444 1.0119 2.48619 + vertex 1.62167 1.00998 2.48642 + vertex 1.62309 1.00801 2.48537 + endloop + endfacet + facet normal 0.227481 -0.323834 0.918359 + outer loop + vertex 1.62309 1.00801 2.48537 + vertex 1.62167 1.00998 2.48642 + vertex 1.61929 1.00722 2.48604 + endloop + endfacet + facet normal 0.232195 -0.357972 0.904401 + outer loop + vertex 1.61929 1.00722 2.48604 + vertex 1.61766 1.00321 2.48487 + vertex 1.62309 1.00801 2.48537 + endloop + endfacet + facet normal 0.164978 -0.286117 0.943885 + outer loop + vertex 1.62309 1.00801 2.48537 + vertex 1.61766 1.00321 2.48487 + vertex 1.62282 1.00332 2.484 + endloop + endfacet + facet normal 0.164961 -0.286698 0.943712 + outer loop + vertex 1.61825 0.998651 2.48338 + vertex 1.62282 1.00332 2.484 + vertex 1.61766 1.00321 2.48487 + endloop + endfacet + facet normal 0.138481 -0.262325 0.954991 + outer loop + vertex 1.62299 0.998953 2.48278 + vertex 1.62282 1.00332 2.484 + vertex 1.61825 0.998651 2.48338 + endloop + endfacet + facet normal 0.104415 -0.317293 0.942562 + outer loop + vertex 1.61929 1.00722 2.48604 + vertex 1.61537 1.00609 2.48609 + vertex 1.61766 1.00321 2.48487 + endloop + endfacet + facet normal 0.0958483 -0.286914 0.953149 + outer loop + vertex 1.61929 1.00722 2.48604 + vertex 1.6186 1.00987 2.4869 + vertex 1.61537 1.00609 2.48609 + endloop + endfacet + facet normal 0.159314 -0.269463 0.949741 + outer loop + vertex 1.62167 1.00998 2.48642 + vertex 1.6186 1.00987 2.4869 + vertex 1.61929 1.00722 2.48604 + endloop + endfacet + facet normal 0.159438 -0.212497 0.964067 + outer loop + vertex 1.62167 1.00998 2.48642 + vertex 1.6228 1.01388 2.48709 + vertex 1.6186 1.00987 2.4869 + endloop + endfacet + facet normal 0.18507 -0.238783 0.953274 + outer loop + vertex 1.6228 1.01388 2.48709 + vertex 1.61815 1.01382 2.48798 + vertex 1.6186 1.00987 2.4869 + endloop + endfacet + facet normal 0.185207 -0.234507 0.954309 + outer loop + vertex 1.6228 1.01388 2.48709 + vertex 1.62267 1.01867 2.4883 + vertex 1.61815 1.01382 2.48798 + endloop + endfacet + facet normal 0.209119 -0.256063 0.94377 + outer loop + vertex 1.61815 1.01382 2.48798 + vertex 1.62267 1.01867 2.4883 + vertex 1.6174 1.01859 2.48944 + endloop + endfacet + facet normal 0.209055 -0.257572 0.943373 + outer loop + vertex 1.62263 1.02379 2.4897 + vertex 1.6174 1.01859 2.48944 + vertex 1.62267 1.01867 2.4883 + endloop + endfacet + facet normal 0.286737 -0.251844 0.924314 + outer loop + vertex 1.62267 1.01867 2.4883 + vertex 1.62756 1.0238 2.48818 + vertex 1.62263 1.02379 2.4897 + endloop + endfacet + facet normal 0.28783 -0.236875 0.927924 + outer loop + vertex 1.62756 1.0238 2.48818 + vertex 1.62796 1.02865 2.48929 + vertex 1.62263 1.02379 2.4897 + endloop + endfacet + facet normal 0.301622 -0.252732 0.919321 + outer loop + vertex 1.62263 1.02379 2.4897 + vertex 1.62796 1.02865 2.48929 + vertex 1.62426 1.02886 2.49056 + endloop + endfacet + facet normal 0.292889 -0.25051 0.922746 + outer loop + vertex 1.62263 1.02379 2.4897 + vertex 1.62426 1.02886 2.49056 + vertex 1.62039 1.02623 2.49108 + endloop + endfacet + facet normal 0.266909 -0.274965 0.923663 + outer loop + vertex 1.61848 1.02274 2.49059 + vertex 1.62263 1.02379 2.4897 + vertex 1.62039 1.02623 2.49108 + endloop + endfacet + facet normal 0.222227 -0.252969 0.941606 + outer loop + vertex 1.62039 1.02623 2.49108 + vertex 1.61714 1.02455 2.49139 + vertex 1.61848 1.02274 2.49059 + endloop + endfacet + facet normal 0.156779 -0.300595 0.940778 + outer loop + vertex 1.61848 1.02274 2.49059 + vertex 1.61714 1.02455 2.49139 + vertex 1.61488 1.02135 2.49075 + endloop + endfacet + facet normal 0.15695 -0.301059 0.940601 + outer loop + vertex 1.61848 1.02274 2.49059 + vertex 1.61488 1.02135 2.49075 + vertex 1.6174 1.01859 2.48944 + endloop + endfacet + facet normal 0.209488 -0.226455 0.951227 + outer loop + vertex 1.61813 1.0286 2.49214 + vertex 1.61714 1.02455 2.49139 + vertex 1.62039 1.02623 2.49108 + endloop + endfacet + facet normal 0.222984 -0.213542 0.951146 + outer loop + vertex 1.62197 1.02976 2.4915 + vertex 1.61813 1.0286 2.49214 + vertex 1.62039 1.02623 2.49108 + endloop + endfacet + facet normal 0.221511 -0.207784 0.952764 + outer loop + vertex 1.62197 1.02976 2.4915 + vertex 1.62269 1.0337 2.49219 + vertex 1.61813 1.0286 2.49214 + endloop + endfacet + facet normal 0.241877 -0.22588 0.943649 + outer loop + vertex 1.62269 1.0337 2.49219 + vertex 1.61778 1.03352 2.49341 + vertex 1.61813 1.0286 2.49214 + endloop + endfacet + facet normal 0.143735 -0.23723 0.960761 + outer loop + vertex 1.61813 1.0286 2.49214 + vertex 1.61778 1.03352 2.49341 + vertex 1.61326 1.02886 2.49293 + endloop + endfacet + facet normal 0.143414 -0.240675 0.959952 + outer loop + vertex 1.61387 1.02469 2.49179 + vertex 1.61813 1.0286 2.49214 + vertex 1.61326 1.02886 2.49293 + endloop + endfacet + facet normal 0.110869 -0.206262 0.972195 + outer loop + vertex 1.61714 1.02455 2.49139 + vertex 1.61813 1.0286 2.49214 + vertex 1.61387 1.02469 2.49179 + endloop + endfacet + facet normal 0.106399 -0.268321 0.957436 + outer loop + vertex 1.61714 1.02455 2.49139 + vertex 1.61387 1.02469 2.49179 + vertex 1.61488 1.02135 2.49075 + endloop + endfacet + facet normal 0.0565273 -0.283286 0.957368 + outer loop + vertex 1.61488 1.02135 2.49075 + vertex 1.61387 1.02469 2.49179 + vertex 1.61042 1.02098 2.4909 + endloop + endfacet + facet normal 0.0574433 -0.295883 0.953495 + outer loop + vertex 1.61042 1.02098 2.4909 + vertex 1.61179 1.01739 2.4897 + vertex 1.61488 1.02135 2.49075 + endloop + endfacet + facet normal 0.167439 -0.259276 0.951178 + outer loop + vertex 1.61326 1.02886 2.49293 + vertex 1.61778 1.03352 2.49341 + vertex 1.61243 1.03379 2.49442 + endloop + endfacet + facet normal 0.166652 -0.267232 0.949112 + outer loop + vertex 1.61767 1.03847 2.49482 + vertex 1.61243 1.03379 2.49442 + vertex 1.61778 1.03352 2.49341 + endloop + endfacet + facet normal 0.235401 -0.340981 0.91012 + outer loop + vertex 1.61382 1.0378 2.49556 + vertex 1.61243 1.03379 2.49442 + vertex 1.61767 1.03847 2.49482 + endloop + endfacet + facet normal 0.232637 -0.313529 0.920641 + outer loop + vertex 1.61767 1.03847 2.49482 + vertex 1.61588 1.04032 2.4959 + vertex 1.61382 1.0378 2.49556 + endloop + endfacet + facet normal 0.160124 -0.258833 0.952557 + outer loop + vertex 1.61588 1.04032 2.4959 + vertex 1.61293 1.04037 2.49641 + vertex 1.61382 1.0378 2.49556 + endloop + endfacet + facet normal 0.101549 -0.279784 0.954677 + outer loop + vertex 1.61382 1.0378 2.49556 + vertex 1.61293 1.04037 2.49641 + vertex 1.61009 1.03695 2.49571 + endloop + endfacet + facet normal 0.162768 -0.212459 0.963518 + outer loop + vertex 1.61588 1.04032 2.4959 + vertex 1.61635 1.04346 2.49652 + vertex 1.61293 1.04037 2.49641 + endloop + endfacet + facet normal 0.175237 -0.22603 0.958229 + outer loop + vertex 1.61635 1.04346 2.49652 + vertex 1.61286 1.04421 2.49733 + vertex 1.61293 1.04037 2.49641 + endloop + endfacet + facet normal 0.183934 -0.191617 0.964081 + outer loop + vertex 1.61635 1.04346 2.49652 + vertex 1.61772 1.04839 2.49724 + vertex 1.61286 1.04421 2.49733 + endloop + endfacet + facet normal 0.217619 -0.231057 0.94829 + outer loop + vertex 1.61286 1.04421 2.49733 + vertex 1.61772 1.04839 2.49724 + vertex 1.61276 1.04874 2.49846 + endloop + endfacet + facet normal 0.218115 -0.227009 0.949154 + outer loop + vertex 1.61772 1.04839 2.49724 + vertex 1.61762 1.05351 2.49848 + vertex 1.61276 1.04874 2.49846 + endloop + endfacet + facet normal 0.252717 -0.26209 0.931366 + outer loop + vertex 1.61276 1.04874 2.49846 + vertex 1.61762 1.05351 2.49848 + vertex 1.61259 1.05352 2.49985 + endloop + endfacet + facet normal 0.254595 -0.234743 0.938124 + outer loop + vertex 1.61765 1.0587 2.49977 + vertex 1.61259 1.05352 2.49985 + vertex 1.61762 1.05351 2.49848 + endloop + endfacet + facet normal 0.290236 -0.23248 0.928287 + outer loop + vertex 1.61762 1.05351 2.49848 + vertex 1.62258 1.05866 2.49822 + vertex 1.61765 1.0587 2.49977 + endloop + endfacet + facet normal 0.291507 -0.216119 0.931835 + outer loop + vertex 1.62258 1.05866 2.49822 + vertex 1.62299 1.06364 2.49925 + vertex 1.61765 1.0587 2.49977 + endloop + endfacet + facet normal 0.292375 -0.217113 0.931332 + outer loop + vertex 1.61765 1.0587 2.49977 + vertex 1.62299 1.06364 2.49925 + vertex 1.61923 1.06395 2.5005 + endloop + endfacet + facet normal 0.294835 -0.217729 0.930412 + outer loop + vertex 1.61765 1.0587 2.49977 + vertex 1.61923 1.06395 2.5005 + vertex 1.61522 1.06103 2.50109 + endloop + endfacet + facet normal 0.290211 -0.222709 0.930687 + outer loop + vertex 1.61352 1.05731 2.50073 + vertex 1.61765 1.0587 2.49977 + vertex 1.61522 1.06103 2.50109 + endloop + endfacet + facet normal 0.242402 -0.202607 0.948784 + outer loop + vertex 1.61522 1.06103 2.50109 + vertex 1.61148 1.05866 2.50153 + vertex 1.61352 1.05731 2.50073 + endloop + endfacet + facet normal 0.226812 -0.22542 0.947493 + outer loop + vertex 1.61352 1.05731 2.50073 + vertex 1.61148 1.05866 2.50153 + vertex 1.61082 1.0555 2.50094 + endloop + endfacet + facet normal 0.260338 -0.278113 0.924596 + outer loop + vertex 1.61352 1.05731 2.50073 + vertex 1.61082 1.0555 2.50094 + vertex 1.61259 1.05352 2.49985 + endloop + endfacet + facet normal 0.243335 -0.204186 0.948207 + outer loop + vertex 1.61291 1.06344 2.5022 + vertex 1.61148 1.05866 2.50153 + vertex 1.61522 1.06103 2.50109 + endloop + endfacet + facet normal 0.252622 -0.195082 0.947694 + outer loop + vertex 1.61685 1.06482 2.50143 + vertex 1.61291 1.06344 2.5022 + vertex 1.61522 1.06103 2.50109 + endloop + endfacet + facet normal 0.255821 -0.206045 0.944511 + outer loop + vertex 1.61685 1.06482 2.50143 + vertex 1.61757 1.06876 2.5021 + vertex 1.61291 1.06344 2.5022 + endloop + endfacet + facet normal 0.262918 -0.212326 0.941165 + outer loop + vertex 1.61757 1.06876 2.5021 + vertex 1.61266 1.06847 2.5034 + vertex 1.61291 1.06344 2.5022 + endloop + endfacet + facet normal 0.262881 -0.222406 0.938845 + outer loop + vertex 1.61757 1.06876 2.5021 + vertex 1.61757 1.07362 2.50325 + vertex 1.61266 1.06847 2.5034 + endloop + endfacet + facet normal 0.280604 -0.23958 0.929442 + outer loop + vertex 1.61266 1.06847 2.5034 + vertex 1.61757 1.07362 2.50325 + vertex 1.61266 1.07376 2.50476 + endloop + endfacet + facet normal 0.198156 -0.244662 0.949144 + outer loop + vertex 1.61266 1.07376 2.50476 + vertex 1.60737 1.06849 2.50451 + vertex 1.61266 1.06847 2.5034 + endloop + endfacet + facet normal 0.198515 -0.237978 0.950767 + outer loop + vertex 1.60815 1.06349 2.5031 + vertex 1.61266 1.06847 2.5034 + vertex 1.60737 1.06849 2.50451 + endloop + endfacet + facet normal 0.178917 -0.220703 0.95879 + outer loop + vertex 1.61291 1.06344 2.5022 + vertex 1.61266 1.06847 2.5034 + vertex 1.60815 1.06349 2.5031 + endloop + endfacet + facet normal 0.180009 -0.198423 0.963444 + outer loop + vertex 1.60889 1.05982 2.5022 + vertex 1.61291 1.06344 2.5022 + vertex 1.60815 1.06349 2.5031 + endloop + endfacet + facet normal 0.16727 -0.184265 0.968539 + outer loop + vertex 1.61148 1.05866 2.50153 + vertex 1.61291 1.06344 2.5022 + vertex 1.60889 1.05982 2.5022 + endloop + endfacet + facet normal 0.146998 -0.226335 0.962893 + outer loop + vertex 1.61148 1.05866 2.50153 + vertex 1.60889 1.05982 2.5022 + vertex 1.60776 1.0559 2.50145 + endloop + endfacet + facet normal 0.134897 -0.210138 0.968321 + outer loop + vertex 1.61082 1.0555 2.50094 + vertex 1.61148 1.05866 2.50153 + vertex 1.60776 1.0559 2.50145 + endloop + endfacet + facet normal 0.127243 -0.255734 0.958337 + outer loop + vertex 1.61082 1.0555 2.50094 + vertex 1.60776 1.0559 2.50145 + vertex 1.60883 1.05312 2.50057 + endloop + endfacet + facet normal 0.211459 -0.32085 0.923223 + outer loop + vertex 1.61259 1.05352 2.49985 + vertex 1.61082 1.0555 2.50094 + vertex 1.60883 1.05312 2.50057 + endloop + endfacet + facet normal 0.268698 -0.31372 0.910704 + outer loop + vertex 1.60852 1.07273 2.50563 + vertex 1.60737 1.06849 2.50451 + vertex 1.61266 1.07376 2.50476 + endloop + endfacet + facet normal 0.259239 -0.25905 0.930424 + outer loop + vertex 1.60852 1.07273 2.50563 + vertex 1.61266 1.07376 2.50476 + vertex 1.61042 1.07625 2.50608 + endloop + endfacet + facet normal 0.208257 -0.23397 0.949677 + outer loop + vertex 1.61042 1.07625 2.50608 + vertex 1.60717 1.07455 2.50638 + vertex 1.60852 1.07273 2.50563 + endloop + endfacet + facet normal 0.138152 -0.285241 0.948447 + outer loop + vertex 1.60852 1.07273 2.50563 + vertex 1.60717 1.07455 2.50638 + vertex 1.60489 1.07136 2.50575 + endloop + endfacet + facet normal 0.190692 -0.198171 0.961439 + outer loop + vertex 1.60809 1.07857 2.50702 + vertex 1.60717 1.07455 2.50638 + vertex 1.61042 1.07625 2.50608 + endloop + endfacet + facet normal 0.202157 -0.186664 0.9614 + outer loop + vertex 1.61195 1.07982 2.50645 + vertex 1.60809 1.07857 2.50702 + vertex 1.61042 1.07625 2.50608 + endloop + endfacet + facet normal 0.277265 -0.216157 0.936163 + outer loop + vertex 1.61428 1.07893 2.50556 + vertex 1.61195 1.07982 2.50645 + vertex 1.61042 1.07625 2.50608 + endloop + endfacet + facet normal 0.284362 -0.19912 0.937811 + outer loop + vertex 1.61463 1.08218 2.50614 + vertex 1.61195 1.07982 2.50645 + vertex 1.61428 1.07893 2.50556 + endloop + endfacet + facet normal 0.301919 -0.20002 0.932114 + outer loop + vertex 1.61463 1.08218 2.50614 + vertex 1.61428 1.07893 2.50556 + vertex 1.61826 1.0835 2.50525 + endloop + endfacet + facet normal 0.299268 -0.190897 0.934878 + outer loop + vertex 1.61826 1.0835 2.50525 + vertex 1.61631 1.08515 2.50621 + vertex 1.61463 1.08218 2.50614 + endloop + endfacet + facet normal 0.273733 -0.176711 0.945433 + outer loop + vertex 1.61631 1.08515 2.50621 + vertex 1.61257 1.08371 2.50702 + vertex 1.61463 1.08218 2.50614 + endloop + endfacet + facet normal 0.279477 -0.194591 0.940227 + outer loop + vertex 1.61631 1.08515 2.50621 + vertex 1.6171 1.08891 2.50675 + vertex 1.61257 1.08371 2.50702 + endloop + endfacet + facet normal 0.28189 -0.196755 0.939056 + outer loop + vertex 1.6171 1.08891 2.50675 + vertex 1.61249 1.08847 2.50805 + vertex 1.61257 1.08371 2.50702 + endloop + endfacet + facet normal 0.219479 -0.201149 0.954656 + outer loop + vertex 1.61257 1.08371 2.50702 + vertex 1.61249 1.08847 2.50805 + vertex 1.60773 1.08333 2.50806 + endloop + endfacet + facet normal 0.219158 -0.191353 0.956741 + outer loop + vertex 1.61257 1.08371 2.50702 + vertex 1.60773 1.08333 2.50806 + vertex 1.60809 1.07857 2.50702 + endloop + endfacet + facet normal 0.235757 -0.216277 0.94744 + outer loop + vertex 1.60773 1.08333 2.50806 + vertex 1.61249 1.08847 2.50805 + vertex 1.60766 1.08814 2.50917 + endloop + endfacet + facet normal 0.235716 -0.213392 0.948104 + outer loop + vertex 1.61249 1.08847 2.50805 + vertex 1.61271 1.09335 2.50909 + vertex 1.60766 1.08814 2.50917 + endloop + endfacet + facet normal 0.267816 -0.244677 0.931884 + outer loop + vertex 1.60766 1.08814 2.50917 + vertex 1.61271 1.09335 2.50909 + vertex 1.60805 1.09308 2.51036 + endloop + endfacet + facet normal 0.268033 -0.213352 0.939489 + outer loop + vertex 1.61295 1.09834 2.51016 + vertex 1.60805 1.09308 2.51036 + vertex 1.61271 1.09335 2.50909 + endloop + endfacet + facet normal 0.299516 -0.212859 0.930044 + outer loop + vertex 1.61271 1.09335 2.50909 + vertex 1.61768 1.09862 2.50869 + vertex 1.61295 1.09834 2.51016 + endloop + endfacet + facet normal 0.29968 -0.192521 0.934413 + outer loop + vertex 1.61779 1.10393 2.50975 + vertex 1.61295 1.09834 2.51016 + vertex 1.61768 1.09862 2.50869 + endloop + endfacet + facet normal 0.29432 -0.192739 0.93607 + outer loop + vertex 1.61768 1.09862 2.50869 + vertex 1.62261 1.10374 2.5082 + vertex 1.61779 1.10393 2.50975 + endloop + endfacet + facet normal 0.294577 -0.190072 0.936535 + outer loop + vertex 1.62261 1.10374 2.5082 + vertex 1.62296 1.10878 2.50911 + vertex 1.61779 1.10393 2.50975 + endloop + endfacet + facet normal 0.290359 -0.185278 0.93881 + outer loop + vertex 1.61779 1.10393 2.50975 + vertex 1.62296 1.10878 2.50911 + vertex 1.61924 1.10919 2.51034 + endloop + endfacet + facet normal 0.295925 -0.186588 0.93681 + outer loop + vertex 1.61779 1.10393 2.50975 + vertex 1.61924 1.10919 2.51034 + vertex 1.61528 1.10621 2.511 + endloop + endfacet + facet normal 0.298585 -0.18353 0.93657 + outer loop + vertex 1.61372 1.10237 2.51075 + vertex 1.61779 1.10393 2.50975 + vertex 1.61528 1.10621 2.511 + endloop + endfacet + facet normal 0.285956 -0.178711 0.941431 + outer loop + vertex 1.61528 1.10621 2.511 + vertex 1.61133 1.10317 2.51162 + vertex 1.61372 1.10237 2.51075 + endloop + endfacet + facet normal 0.286919 -0.176054 0.941638 + outer loop + vertex 1.61372 1.10237 2.51075 + vertex 1.61133 1.10317 2.51162 + vertex 1.61104 1.09994 2.51111 + endloop + endfacet + facet normal 0.30266 -0.194715 0.932997 + outer loop + vertex 1.61372 1.10237 2.51075 + vertex 1.61104 1.09994 2.51111 + vertex 1.61295 1.09834 2.51016 + endloop + endfacet + facet normal 0.296038 -0.202866 0.933385 + outer loop + vertex 1.61295 1.09834 2.51016 + vertex 1.61104 1.09994 2.51111 + vertex 1.60932 1.097 2.51101 + endloop + endfacet + facet normal 0.243718 -0.173159 0.954263 + outer loop + vertex 1.61104 1.09994 2.51111 + vertex 1.60758 1.09877 2.51178 + vertex 1.60932 1.097 2.51101 + endloop + endfacet + facet normal 0.231023 -0.186004 0.955003 + outer loop + vertex 1.60932 1.097 2.51101 + vertex 1.60758 1.09877 2.51178 + vertex 1.60665 1.09505 2.51128 + endloop + endfacet + facet normal 0.270708 -0.243726 0.931297 + outer loop + vertex 1.60932 1.097 2.51101 + vertex 1.60665 1.09505 2.51128 + vertex 1.60805 1.09308 2.51036 + endloop + endfacet + facet normal 0.227055 -0.276098 0.933925 + outer loop + vertex 1.60805 1.09308 2.51036 + vertex 1.60665 1.09505 2.51128 + vertex 1.6043 1.09223 2.51102 + endloop + endfacet + facet normal 0.23329 -0.314037 0.920302 + outer loop + vertex 1.6043 1.09223 2.51102 + vertex 1.60248 1.08807 2.51006 + vertex 1.60805 1.09308 2.51036 + endloop + endfacet + facet normal 0.167036 -0.242427 0.955682 + outer loop + vertex 1.60805 1.09308 2.51036 + vertex 1.60248 1.08807 2.51006 + vertex 1.60766 1.08814 2.50917 + endloop + endfacet + facet normal 0.16703 -0.242658 0.955625 + outer loop + vertex 1.60273 1.08317 2.50877 + vertex 1.60766 1.08814 2.50917 + vertex 1.60248 1.08807 2.51006 + endloop + endfacet + facet normal 0.144871 -0.221339 0.964376 + outer loop + vertex 1.60773 1.08333 2.50806 + vertex 1.60766 1.08814 2.50917 + vertex 1.60273 1.08317 2.50877 + endloop + endfacet + facet normal 0.144871 -0.222164 0.964187 + outer loop + vertex 1.60324 1.07871 2.50767 + vertex 1.60773 1.08333 2.50806 + vertex 1.60273 1.08317 2.50877 + endloop + endfacet + facet normal 0.123397 -0.201932 0.971595 + outer loop + vertex 1.60809 1.07857 2.50702 + vertex 1.60773 1.08333 2.50806 + vertex 1.60324 1.07871 2.50767 + endloop + endfacet + facet normal 0.107341 -0.267472 0.957568 + outer loop + vertex 1.6043 1.09223 2.51102 + vertex 1.60038 1.09097 2.51111 + vertex 1.60248 1.08807 2.51006 + endloop + endfacet + facet normal 0.0968335 -0.233955 0.967413 + outer loop + vertex 1.6043 1.09223 2.51102 + vertex 1.60361 1.09483 2.51171 + vertex 1.60038 1.09097 2.51111 + endloop + endfacet + facet normal 0.153803 -0.217874 0.963782 + outer loop + vertex 1.60665 1.09505 2.51128 + vertex 1.60361 1.09483 2.51171 + vertex 1.6043 1.09223 2.51102 + endloop + endfacet + facet normal 0.151674 -0.168808 0.973909 + outer loop + vertex 1.60665 1.09505 2.51128 + vertex 1.60758 1.09877 2.51178 + vertex 1.60361 1.09483 2.51171 + endloop + endfacet + facet normal 0.170736 -0.187883 0.967238 + outer loop + vertex 1.60758 1.09877 2.51178 + vertex 1.60316 1.0987 2.51255 + vertex 1.60361 1.09483 2.51171 + endloop + endfacet + facet normal 0.170836 -0.181884 0.968366 + outer loop + vertex 1.60758 1.09877 2.51178 + vertex 1.60753 1.10334 2.51265 + vertex 1.60316 1.0987 2.51255 + endloop + endfacet + facet normal 0.194255 -0.203736 0.959561 + outer loop + vertex 1.60316 1.0987 2.51255 + vertex 1.60753 1.10334 2.51265 + vertex 1.60268 1.10338 2.51364 + endloop + endfacet + facet normal 0.194274 -0.203351 0.959639 + outer loop + vertex 1.60753 1.10334 2.51265 + vertex 1.60766 1.10833 2.51368 + vertex 1.60268 1.10338 2.51364 + endloop + endfacet + facet normal 0.271627 -0.20156 0.941059 + outer loop + vertex 1.60753 1.10334 2.51265 + vertex 1.61267 1.10833 2.51223 + vertex 1.60766 1.10833 2.51368 + endloop + endfacet + facet normal 0.248584 -0.176877 0.952324 + outer loop + vertex 1.61133 1.10317 2.51162 + vertex 1.61267 1.10833 2.51223 + vertex 1.60753 1.10334 2.51265 + endloop + endfacet + facet normal 0.248485 -0.177987 0.952143 + outer loop + vertex 1.61133 1.10317 2.51162 + vertex 1.60753 1.10334 2.51265 + vertex 1.60758 1.09877 2.51178 + endloop + endfacet + facet normal 0.243985 -0.174078 0.954028 + outer loop + vertex 1.61104 1.09994 2.51111 + vertex 1.61133 1.10317 2.51162 + vertex 1.60758 1.09877 2.51178 + endloop + endfacet + facet normal 0.291292 -0.186253 0.938328 + outer loop + vertex 1.61267 1.10833 2.51223 + vertex 1.61133 1.10317 2.51162 + vertex 1.61528 1.10621 2.511 + endloop + endfacet + facet normal 0.29205 -0.185289 0.938283 + outer loop + vertex 1.61681 1.11001 2.51127 + vertex 1.61267 1.10833 2.51223 + vertex 1.61528 1.10621 2.511 + endloop + endfacet + facet normal 0.294513 -0.192633 0.936031 + outer loop + vertex 1.61681 1.11001 2.51127 + vertex 1.61733 1.11375 2.51188 + vertex 1.61267 1.10833 2.51223 + endloop + endfacet + facet normal 0.297075 -0.194917 0.934748 + outer loop + vertex 1.61733 1.11375 2.51188 + vertex 1.61264 1.1135 2.51332 + vertex 1.61267 1.10833 2.51223 + endloop + endfacet + facet normal 0.297655 -0.192893 0.934983 + outer loop + vertex 1.6195 1.11237 2.51091 + vertex 1.61733 1.11375 2.51188 + vertex 1.61681 1.11001 2.51127 + endloop + endfacet + facet normal 0.295012 -0.189651 0.936483 + outer loop + vertex 1.6195 1.11237 2.51091 + vertex 1.61681 1.11001 2.51127 + vertex 1.61924 1.10919 2.51034 + endloop + endfacet + facet normal 0.289939 -0.189532 0.93809 + outer loop + vertex 1.6195 1.11237 2.51091 + vertex 1.61924 1.10919 2.51034 + vertex 1.6231 1.11362 2.51005 + endloop + endfacet + facet normal 0.290321 -0.1909 0.937694 + outer loop + vertex 1.6231 1.11362 2.51005 + vertex 1.62096 1.11511 2.51101 + vertex 1.6195 1.11237 2.51091 + endloop + endfacet + facet normal 0.29022 -0.191046 0.937696 + outer loop + vertex 1.62364 1.11742 2.51065 + vertex 1.62096 1.11511 2.51101 + vertex 1.6231 1.11362 2.51005 + endloop + endfacet + facet normal 0.28643 -0.190704 0.93893 + outer loop + vertex 1.62364 1.11742 2.51065 + vertex 1.6231 1.11362 2.51005 + vertex 1.62774 1.11887 2.5097 + endloop + endfacet + facet normal 0.286285 -0.190202 0.939076 + outer loop + vertex 1.62364 1.11742 2.51065 + vertex 1.62774 1.11887 2.5097 + vertex 1.62518 1.12118 2.51094 + endloop + endfacet + facet normal 0.291059 -0.192022 0.937237 + outer loop + vertex 1.62518 1.12118 2.51094 + vertex 1.6212 1.11825 2.51158 + vertex 1.62364 1.11742 2.51065 + endloop + endfacet + facet normal 0.288894 -0.188787 0.938563 + outer loop + vertex 1.6226 1.12341 2.51219 + vertex 1.6212 1.11825 2.51158 + vertex 1.62518 1.12118 2.51094 + endloop + endfacet + facet normal 0.288043 -0.189802 0.93862 + outer loop + vertex 1.62674 1.12496 2.51123 + vertex 1.6226 1.12341 2.51219 + vertex 1.62518 1.12118 2.51094 + endloop + endfacet + facet normal 0.285873 -0.188973 0.93945 + outer loop + vertex 1.62917 1.12409 2.51032 + vertex 1.62674 1.12496 2.51123 + vertex 1.62518 1.12118 2.51094 + endloop + endfacet + facet normal 0.285908 -0.188882 0.939457 + outer loop + vertex 1.62943 1.1273 2.51088 + vertex 1.62674 1.12496 2.51123 + vertex 1.62917 1.12409 2.51032 + endloop + endfacet + facet normal 0.284814 -0.188852 0.939796 + outer loop + vertex 1.62943 1.1273 2.51088 + vertex 1.62917 1.12409 2.51032 + vertex 1.63305 1.12856 2.51004 + endloop + endfacet + facet normal 0.284552 -0.187921 0.940062 + outer loop + vertex 1.63305 1.12856 2.51004 + vertex 1.6309 1.13005 2.51099 + vertex 1.62943 1.1273 2.51088 + endloop + endfacet + facet normal 0.284678 -0.187986 0.94001 + outer loop + vertex 1.6309 1.13005 2.51099 + vertex 1.62726 1.12873 2.51183 + vertex 1.62943 1.1273 2.51088 + endloop + endfacet + facet normal 0.284326 -0.186801 0.940353 + outer loop + vertex 1.6309 1.13005 2.51099 + vertex 1.63114 1.1332 2.51154 + vertex 1.62726 1.12873 2.51183 + endloop + endfacet + facet normal 0.282708 -0.185349 0.941128 + outer loop + vertex 1.63114 1.1332 2.51154 + vertex 1.62735 1.13351 2.51274 + vertex 1.62726 1.12873 2.51183 + endloop + endfacet + facet normal 0.285362 -0.185248 0.940346 + outer loop + vertex 1.62726 1.12873 2.51183 + vertex 1.62735 1.13351 2.51274 + vertex 1.62261 1.12861 2.51321 + endloop + endfacet + facet normal 0.28534 -0.185948 0.940215 + outer loop + vertex 1.62726 1.12873 2.51183 + vertex 1.62261 1.12861 2.51321 + vertex 1.6226 1.12341 2.51219 + endloop + endfacet + facet normal 0.291393 -0.185604 0.938425 + outer loop + vertex 1.6226 1.12341 2.51219 + vertex 1.62261 1.12861 2.51321 + vertex 1.61776 1.12358 2.51372 + endloop + endfacet + facet normal 0.288905 -0.183077 0.93969 + outer loop + vertex 1.61776 1.12358 2.51372 + vertex 1.62261 1.12861 2.51321 + vertex 1.6178 1.12886 2.51474 + endloop + endfacet + facet normal 0.288862 -0.18349 0.939622 + outer loop + vertex 1.62261 1.12861 2.51321 + vertex 1.62293 1.13368 2.5141 + vertex 1.6178 1.12886 2.51474 + endloop + endfacet + facet normal 0.283582 -0.183437 0.94124 + outer loop + vertex 1.62261 1.12861 2.51321 + vertex 1.62735 1.13351 2.51274 + vertex 1.62293 1.13368 2.5141 + endloop + endfacet + facet normal 0.28281 -0.184568 0.941251 + outer loop + vertex 1.63114 1.1332 2.51154 + vertex 1.63254 1.13838 2.51213 + vertex 1.62735 1.13351 2.51274 + endloop + endfacet + facet normal 0.280513 -0.181973 0.942443 + outer loop + vertex 1.62735 1.13351 2.51274 + vertex 1.63254 1.13838 2.51213 + vertex 1.62766 1.13858 2.51363 + endloop + endfacet + facet normal 0.282074 -0.184398 0.941505 + outer loop + vertex 1.63254 1.13838 2.51213 + vertex 1.63114 1.1332 2.51154 + vertex 1.63514 1.13614 2.51092 + endloop + endfacet + facet normal 0.281276 -0.185352 0.941556 + outer loop + vertex 1.63671 1.13995 2.5112 + vertex 1.63254 1.13838 2.51213 + vertex 1.63514 1.13614 2.51092 + endloop + endfacet + facet normal 0.284377 -0.186544 0.940389 + outer loop + vertex 1.63915 1.13911 2.51029 + vertex 1.63671 1.13995 2.5112 + vertex 1.63514 1.13614 2.51092 + endloop + endfacet + facet normal 0.284633 -0.186922 0.940236 + outer loop + vertex 1.63771 1.13385 2.50968 + vertex 1.63915 1.13911 2.51029 + vertex 1.63514 1.13614 2.51092 + endloop + endfacet + facet normal 0.284407 -0.187185 0.940252 + outer loop + vertex 1.63359 1.13237 2.51064 + vertex 1.63771 1.13385 2.50968 + vertex 1.63514 1.13614 2.51092 + endloop + endfacet + facet normal 0.28458 -0.187776 0.940082 + outer loop + vertex 1.63359 1.13237 2.51064 + vertex 1.63305 1.12856 2.51004 + vertex 1.63771 1.13385 2.50968 + endloop + endfacet + facet normal 0.282974 -0.186309 0.940859 + outer loop + vertex 1.63771 1.13385 2.50968 + vertex 1.63305 1.12856 2.51004 + vertex 1.63768 1.12857 2.50865 + endloop + endfacet + facet normal 0.282575 -0.18633 0.940974 + outer loop + vertex 1.63768 1.12857 2.50865 + vertex 1.64257 1.1336 2.50818 + vertex 1.63771 1.13385 2.50968 + endloop + endfacet + facet normal 0.282912 -0.183047 0.941517 + outer loop + vertex 1.64257 1.1336 2.50818 + vertex 1.64289 1.13871 2.50907 + vertex 1.63771 1.13385 2.50968 + endloop + endfacet + facet normal 0.284841 -0.183065 0.940932 + outer loop + vertex 1.64257 1.1336 2.50818 + vertex 1.64731 1.13852 2.5077 + vertex 1.64289 1.13871 2.50907 + endloop + endfacet + facet normal 0.279253 -0.18295 0.942628 + outer loop + vertex 1.64258 1.12837 2.50716 + vertex 1.64257 1.1336 2.50818 + vertex 1.63768 1.12857 2.50865 + endloop + endfacet + facet normal 0.278843 -0.187383 0.941878 + outer loop + vertex 1.63736 1.12351 2.50774 + vertex 1.64258 1.12837 2.50716 + vertex 1.63768 1.12857 2.50865 + endloop + endfacet + facet normal 0.281841 -0.187415 0.940979 + outer loop + vertex 1.63736 1.12351 2.50774 + vertex 1.63768 1.12857 2.50865 + vertex 1.63291 1.12368 2.5091 + endloop + endfacet + facet normal 0.281698 -0.189001 0.940705 + outer loop + vertex 1.63257 1.11861 2.50819 + vertex 1.63736 1.12351 2.50774 + vertex 1.63291 1.12368 2.5091 + endloop + endfacet + facet normal 0.283855 -0.189027 0.940051 + outer loop + vertex 1.63257 1.11861 2.50819 + vertex 1.63291 1.12368 2.5091 + vertex 1.62774 1.11887 2.5097 + endloop + endfacet + facet normal 0.283749 -0.190019 0.939882 + outer loop + vertex 1.62769 1.11362 2.50865 + vertex 1.63257 1.11861 2.50819 + vertex 1.62774 1.11887 2.5097 + endloop + endfacet + facet normal 0.282899 -0.189149 0.940314 + outer loop + vertex 1.63254 1.11342 2.50715 + vertex 1.63257 1.11861 2.50819 + vertex 1.62769 1.11362 2.50865 + endloop + endfacet + facet normal 0.28282 -0.189972 0.940172 + outer loop + vertex 1.62736 1.10859 2.50773 + vertex 1.63254 1.11342 2.50715 + vertex 1.62769 1.11362 2.50865 + endloop + endfacet + facet normal 0.286156 -0.19001 0.939154 + outer loop + vertex 1.62736 1.10859 2.50773 + vertex 1.62769 1.11362 2.50865 + vertex 1.62296 1.10878 2.50911 + endloop + endfacet + facet normal 0.285607 -0.189447 0.939435 + outer loop + vertex 1.62296 1.10878 2.50911 + vertex 1.62769 1.11362 2.50865 + vertex 1.6231 1.11362 2.51005 + endloop + endfacet + facet normal 0.282968 -0.19014 0.940094 + outer loop + vertex 1.63112 1.10826 2.50654 + vertex 1.63254 1.11342 2.50715 + vertex 1.62736 1.10859 2.50773 + endloop + endfacet + facet normal 0.282585 -0.192874 0.939652 + outer loop + vertex 1.63112 1.10826 2.50654 + vertex 1.62736 1.10859 2.50773 + vertex 1.62724 1.10385 2.5068 + endloop + endfacet + facet normal 0.283111 -0.19335 0.939396 + outer loop + vertex 1.63087 1.10512 2.50597 + vertex 1.63112 1.10826 2.50654 + vertex 1.62724 1.10385 2.5068 + endloop + endfacet + facet normal 0.284992 -0.199982 0.937436 + outer loop + vertex 1.63087 1.10512 2.50597 + vertex 1.62724 1.10385 2.5068 + vertex 1.6294 1.10241 2.50583 + endloop + endfacet + facet normal 0.286634 -0.20084 0.936752 + outer loop + vertex 1.63303 1.10363 2.50498 + vertex 1.63087 1.10512 2.50597 + vertex 1.6294 1.10241 2.50583 + endloop + endfacet + facet normal 0.287315 -0.2034 0.935991 + outer loop + vertex 1.6294 1.10241 2.50583 + vertex 1.62915 1.09925 2.50522 + vertex 1.63303 1.10363 2.50498 + endloop + endfacet + facet normal 0.286374 -0.202541 0.936465 + outer loop + vertex 1.63303 1.10363 2.50498 + vertex 1.62915 1.09925 2.50522 + vertex 1.63295 1.09874 2.50395 + endloop + endfacet + facet normal 0.287337 -0.202497 0.93618 + outer loop + vertex 1.63295 1.09874 2.50395 + vertex 1.63773 1.10365 2.50354 + vertex 1.63303 1.10363 2.50498 + endloop + endfacet + facet normal 0.287532 -0.199115 0.936845 + outer loop + vertex 1.63769 1.1089 2.50467 + vertex 1.63303 1.10363 2.50498 + vertex 1.63773 1.10365 2.50354 + endloop + endfacet + facet normal 0.285875 -0.19923 0.937328 + outer loop + vertex 1.63773 1.10365 2.50354 + vertex 1.64255 1.10871 2.50315 + vertex 1.63769 1.1089 2.50467 + endloop + endfacet + facet normal 0.286104 -0.196844 0.937762 + outer loop + vertex 1.64255 1.10871 2.50315 + vertex 1.64288 1.11373 2.5041 + vertex 1.63769 1.1089 2.50467 + endloop + endfacet + facet normal 0.283334 -0.193697 0.939257 + outer loop + vertex 1.63769 1.1089 2.50467 + vertex 1.64288 1.11373 2.5041 + vertex 1.63914 1.11412 2.50531 + endloop + endfacet + facet normal 0.284896 -0.194061 0.938709 + outer loop + vertex 1.63769 1.1089 2.50467 + vertex 1.63914 1.11412 2.50531 + vertex 1.63512 1.11118 2.50592 + endloop + endfacet + facet normal 0.285852 -0.19295 0.938647 + outer loop + vertex 1.63356 1.10742 2.50563 + vertex 1.63769 1.1089 2.50467 + vertex 1.63512 1.11118 2.50592 + endloop + endfacet + facet normal 0.283524 -0.192052 0.939537 + outer loop + vertex 1.63512 1.11118 2.50592 + vertex 1.63112 1.10826 2.50654 + vertex 1.63356 1.10742 2.50563 + endloop + endfacet + facet normal 0.282154 -0.18997 0.940373 + outer loop + vertex 1.63914 1.11412 2.50531 + vertex 1.6367 1.11497 2.50622 + vertex 1.63512 1.11118 2.50592 + endloop + endfacet + facet normal 0.282104 -0.189951 0.940391 + outer loop + vertex 1.6367 1.11497 2.50622 + vertex 1.63254 1.11342 2.50715 + vertex 1.63512 1.11118 2.50592 + endloop + endfacet + facet normal 0.281966 -0.189505 0.940523 + outer loop + vertex 1.6367 1.11497 2.50622 + vertex 1.63725 1.11874 2.50681 + vertex 1.63254 1.11342 2.50715 + endloop + endfacet + facet normal 0.281196 -0.189431 0.940768 + outer loop + vertex 1.63942 1.11733 2.50588 + vertex 1.63725 1.11874 2.50681 + vertex 1.6367 1.11497 2.50622 + endloop + endfacet + facet normal 0.280375 -0.190684 0.94076 + outer loop + vertex 1.64091 1.12008 2.50599 + vertex 1.63725 1.11874 2.50681 + vertex 1.63942 1.11733 2.50588 + endloop + endfacet + facet normal 0.280076 -0.190526 0.940881 + outer loop + vertex 1.64304 1.11859 2.50505 + vertex 1.64091 1.12008 2.50599 + vertex 1.63942 1.11733 2.50588 + endloop + endfacet + facet normal 0.280023 -0.190339 0.940935 + outer loop + vertex 1.63942 1.11733 2.50588 + vertex 1.63914 1.11412 2.50531 + vertex 1.64304 1.11859 2.50505 + endloop + endfacet + facet normal 0.279067 -0.191975 0.940886 + outer loop + vertex 1.64362 1.12239 2.50566 + vertex 1.64091 1.12008 2.50599 + vertex 1.64304 1.11859 2.50505 + endloop + endfacet + facet normal 0.281213 -0.19219 0.940203 + outer loop + vertex 1.64362 1.12239 2.50566 + vertex 1.64304 1.11859 2.50505 + vertex 1.64772 1.12385 2.50473 + endloop + endfacet + facet normal 0.280994 -0.191441 0.940422 + outer loop + vertex 1.64362 1.12239 2.50566 + vertex 1.64772 1.12385 2.50473 + vertex 1.64518 1.12613 2.50595 + endloop + endfacet + facet normal 0.277894 -0.190237 0.941586 + outer loop + vertex 1.64518 1.12613 2.50595 + vertex 1.64117 1.12321 2.50655 + vertex 1.64362 1.12239 2.50566 + endloop + endfacet + facet normal 0.275524 -0.186693 0.942991 + outer loop + vertex 1.64258 1.12837 2.50716 + vertex 1.64117 1.12321 2.50655 + vertex 1.64518 1.12613 2.50595 + endloop + endfacet + facet normal 0.276004 -0.18612 0.942964 + outer loop + vertex 1.64675 1.12991 2.50624 + vertex 1.64258 1.12837 2.50716 + vertex 1.64518 1.12613 2.50595 + endloop + endfacet + facet normal 0.279532 -0.187486 0.941653 + outer loop + vertex 1.64918 1.12906 2.50535 + vertex 1.64675 1.12991 2.50624 + vertex 1.64518 1.12613 2.50595 + endloop + endfacet + facet normal 0.273543 -0.178129 0.945222 + outer loop + vertex 1.64675 1.12991 2.50624 + vertex 1.64726 1.13371 2.50681 + vertex 1.64258 1.12837 2.50716 + endloop + endfacet + facet normal 0.275699 -0.178319 0.944559 + outer loop + vertex 1.64945 1.13227 2.5059 + vertex 1.64726 1.13371 2.50681 + vertex 1.64675 1.12991 2.50624 + endloop + endfacet + facet normal 0.281671 -0.190664 0.940377 + outer loop + vertex 1.64772 1.12385 2.50473 + vertex 1.64918 1.12906 2.50535 + vertex 1.64518 1.12613 2.50595 + endloop + endfacet + facet normal 0.282696 -0.193551 0.939479 + outer loop + vertex 1.64772 1.12385 2.50473 + vertex 1.64304 1.11859 2.50505 + vertex 1.64765 1.11862 2.50367 + endloop + endfacet + facet normal 0.28474 -0.193455 0.938882 + outer loop + vertex 1.64765 1.11862 2.50367 + vertex 1.65253 1.12362 2.50323 + vertex 1.64772 1.12385 2.50473 + endloop + endfacet + facet normal 0.284944 -0.191467 0.939227 + outer loop + vertex 1.65253 1.12362 2.50323 + vertex 1.65288 1.12868 2.50415 + vertex 1.64772 1.12385 2.50473 + endloop + endfacet + facet normal 0.286018 -0.191482 0.938897 + outer loop + vertex 1.65253 1.12362 2.50323 + vertex 1.65729 1.12852 2.50278 + vertex 1.65288 1.12868 2.50415 + endloop + endfacet + facet normal 0.286885 -0.192365 0.938452 + outer loop + vertex 1.65718 1.12376 2.50183 + vertex 1.65729 1.12852 2.50278 + vertex 1.65253 1.12362 2.50323 + endloop + endfacet + facet normal 0.286847 -0.193647 0.9382 + outer loop + vertex 1.65718 1.12376 2.50183 + vertex 1.65253 1.12362 2.50323 + vertex 1.65252 1.11846 2.50216 + endloop + endfacet + facet normal 0.285844 -0.192734 0.938694 + outer loop + vertex 1.65667 1.12003 2.50122 + vertex 1.65718 1.12376 2.50183 + vertex 1.65252 1.11846 2.50216 + endloop + endfacet + facet normal 0.285342 -0.191116 0.939178 + outer loop + vertex 1.65667 1.12003 2.50122 + vertex 1.65252 1.11846 2.50216 + vertex 1.65513 1.11626 2.50092 + endloop + endfacet + facet normal 0.284848 -0.190928 0.939366 + outer loop + vertex 1.65911 1.11918 2.50031 + vertex 1.65667 1.12003 2.50122 + vertex 1.65513 1.11626 2.50092 + endloop + endfacet + facet normal 0.28422 -0.189993 0.939745 + outer loop + vertex 1.65765 1.11393 2.49969 + vertex 1.65911 1.11918 2.50031 + vertex 1.65513 1.11626 2.50092 + endloop + endfacet + facet normal 0.282504 -0.191922 0.939871 + outer loop + vertex 1.65354 1.11245 2.50062 + vertex 1.65765 1.11393 2.49969 + vertex 1.65513 1.11626 2.50092 + endloop + endfacet + facet normal 0.282493 -0.191918 0.939875 + outer loop + vertex 1.65513 1.11626 2.50092 + vertex 1.65111 1.11331 2.50153 + vertex 1.65354 1.11245 2.50062 + endloop + endfacet + facet normal 0.281541 -0.194387 0.939653 + outer loop + vertex 1.65354 1.11245 2.50062 + vertex 1.65111 1.11331 2.50153 + vertex 1.65079 1.11009 2.50096 + endloop + endfacet + facet normal 0.281675 -0.194552 0.939579 + outer loop + vertex 1.65354 1.11245 2.50062 + vertex 1.65079 1.11009 2.50096 + vertex 1.65283 1.10847 2.50001 + endloop + endfacet + facet normal 0.283336 -0.194766 0.939035 + outer loop + vertex 1.65354 1.11245 2.50062 + vertex 1.65283 1.10847 2.50001 + vertex 1.65765 1.11393 2.49969 + endloop + endfacet + facet normal 0.279341 -0.19112 0.940979 + outer loop + vertex 1.65765 1.11393 2.49969 + vertex 1.65283 1.10847 2.50001 + vertex 1.65756 1.1086 2.49863 + endloop + endfacet + facet normal 0.281792 -0.191021 0.940268 + outer loop + vertex 1.65756 1.1086 2.49863 + vertex 1.66247 1.1137 2.4982 + vertex 1.65765 1.11393 2.49969 + endloop + endfacet + facet normal 0.28213 -0.187689 0.940838 + outer loop + vertex 1.66247 1.1137 2.4982 + vertex 1.66282 1.11877 2.4991 + vertex 1.65765 1.11393 2.49969 + endloop + endfacet + facet normal 0.286291 -0.187746 0.939568 + outer loop + vertex 1.66247 1.1137 2.4982 + vertex 1.66721 1.11862 2.49774 + vertex 1.66282 1.11877 2.4991 + endloop + endfacet + facet normal 0.280674 -0.189895 0.940831 + outer loop + vertex 1.66245 1.10848 2.49715 + vertex 1.66247 1.1137 2.4982 + vertex 1.65756 1.1086 2.49863 + endloop + endfacet + facet normal 0.280442 -0.192851 0.940298 + outer loop + vertex 1.65723 1.10355 2.4977 + vertex 1.66245 1.10848 2.49715 + vertex 1.65756 1.1086 2.49863 + endloop + endfacet + facet normal 0.277557 -0.19282 0.94116 + outer loop + vertex 1.65723 1.10355 2.4977 + vertex 1.65756 1.1086 2.49863 + vertex 1.65272 1.10351 2.49902 + endloop + endfacet + facet normal 0.277428 -0.195556 0.940634 + outer loop + vertex 1.65249 1.09857 2.49806 + vertex 1.65723 1.10355 2.4977 + vertex 1.65272 1.10351 2.49902 + endloop + endfacet + facet normal 0.276086 -0.19557 0.941025 + outer loop + vertex 1.65249 1.09857 2.49806 + vertex 1.65272 1.10351 2.49902 + vertex 1.648 1.09856 2.49937 + endloop + endfacet + facet normal 0.275971 -0.197671 0.94062 + outer loop + vertex 1.64757 1.09356 2.49845 + vertex 1.65249 1.09857 2.49806 + vertex 1.648 1.09856 2.49937 + endloop + endfacet + facet normal 0.278877 -0.197759 0.939744 + outer loop + vertex 1.64757 1.09356 2.49845 + vertex 1.648 1.09856 2.49937 + vertex 1.64279 1.09369 2.4999 + endloop + endfacet + facet normal 0.27864 -0.20055 0.939223 + outer loop + vertex 1.64266 1.08858 2.49884 + vertex 1.64757 1.09356 2.49845 + vertex 1.64279 1.09369 2.4999 + endloop + endfacet + facet normal 0.284378 -0.200347 0.937545 + outer loop + vertex 1.64279 1.09369 2.4999 + vertex 1.63816 1.08844 2.50018 + vertex 1.64266 1.08858 2.49884 + endloop + endfacet + facet normal 0.284231 -0.205199 0.936539 + outer loop + vertex 1.63799 1.08369 2.49919 + vertex 1.64266 1.08858 2.49884 + vertex 1.63816 1.08844 2.50018 + endloop + endfacet + facet normal 0.288157 -0.205101 0.935361 + outer loop + vertex 1.63816 1.08844 2.50018 + vertex 1.63431 1.08403 2.5004 + vertex 1.63799 1.08369 2.49919 + endloop + endfacet + facet normal 0.287415 -0.209978 0.934506 + outer loop + vertex 1.63281 1.07887 2.4997 + vertex 1.63799 1.08369 2.49919 + vertex 1.63431 1.08403 2.5004 + endloop + endfacet + facet normal 0.289235 -0.21042 0.933845 + outer loop + vertex 1.63281 1.07887 2.4997 + vertex 1.63431 1.08403 2.5004 + vertex 1.63032 1.08118 2.50099 + endloop + endfacet + facet normal 0.288302 -0.211456 0.9339 + outer loop + vertex 1.62869 1.07743 2.50064 + vertex 1.63281 1.07887 2.4997 + vertex 1.63032 1.08118 2.50099 + endloop + endfacet + facet normal 0.289463 -0.211918 0.933436 + outer loop + vertex 1.63032 1.08118 2.50099 + vertex 1.62626 1.0783 2.5016 + vertex 1.62869 1.07743 2.50064 + endloop + endfacet + facet normal 0.288425 -0.214514 0.933164 + outer loop + vertex 1.62869 1.07743 2.50064 + vertex 1.62626 1.0783 2.5016 + vertex 1.6259 1.07513 2.50098 + endloop + endfacet + facet normal 0.289811 -0.21631 0.932319 + outer loop + vertex 1.62869 1.07743 2.50064 + vertex 1.6259 1.07513 2.50098 + vertex 1.62795 1.07351 2.49997 + endloop + endfacet + facet normal 0.288762 -0.217644 0.932334 + outer loop + vertex 1.62795 1.07351 2.49997 + vertex 1.6259 1.07513 2.50098 + vertex 1.62418 1.07228 2.50085 + endloop + endfacet + facet normal 0.287953 -0.214461 0.933322 + outer loop + vertex 1.62418 1.07228 2.50085 + vertex 1.62331 1.06849 2.50024 + vertex 1.62795 1.07351 2.49997 + endloop + endfacet + facet normal 0.287383 -0.213917 0.933622 + outer loop + vertex 1.62795 1.07351 2.49997 + vertex 1.62331 1.06849 2.50024 + vertex 1.62786 1.06855 2.49886 + endloop + endfacet + facet normal 0.286249 -0.213972 0.933958 + outer loop + vertex 1.62786 1.06855 2.49886 + vertex 1.63275 1.07362 2.49852 + vertex 1.62795 1.07351 2.49997 + endloop + endfacet + facet normal 0.286282 -0.213156 0.934134 + outer loop + vertex 1.63281 1.07887 2.4997 + vertex 1.62795 1.07351 2.49997 + vertex 1.63275 1.07362 2.49852 + endloop + endfacet + facet normal 0.287279 -0.213101 0.933841 + outer loop + vertex 1.63275 1.07362 2.49852 + vertex 1.63763 1.07874 2.49819 + vertex 1.63281 1.07887 2.4997 + endloop + endfacet + facet normal 0.28553 -0.211375 0.934769 + outer loop + vertex 1.63759 1.0738 2.49708 + vertex 1.63763 1.07874 2.49819 + vertex 1.63275 1.07362 2.49852 + endloop + endfacet + facet normal 0.285493 -0.212702 0.934479 + outer loop + vertex 1.63759 1.0738 2.49708 + vertex 1.63275 1.07362 2.49852 + vertex 1.63272 1.0684 2.49734 + endloop + endfacet + facet normal 0.283296 -0.210668 0.935608 + outer loop + vertex 1.63688 1.06985 2.49641 + vertex 1.63759 1.0738 2.49708 + vertex 1.63272 1.0684 2.49734 + endloop + endfacet + facet normal 0.284092 -0.213504 0.934724 + outer loop + vertex 1.63688 1.06985 2.49641 + vertex 1.63272 1.0684 2.49734 + vertex 1.63526 1.06613 2.49605 + endloop + endfacet + facet normal 0.28521 -0.213946 0.934282 + outer loop + vertex 1.63927 1.06897 2.49548 + vertex 1.63688 1.06985 2.49641 + vertex 1.63526 1.06613 2.49605 + endloop + endfacet + facet normal 0.28738 -0.217291 0.932844 + outer loop + vertex 1.63776 1.06385 2.49475 + vertex 1.63927 1.06897 2.49548 + vertex 1.63526 1.06613 2.49605 + endloop + endfacet + facet normal 0.286334 -0.218465 0.932891 + outer loop + vertex 1.63365 1.06243 2.49568 + vertex 1.63776 1.06385 2.49475 + vertex 1.63526 1.06613 2.49605 + endloop + endfacet + facet normal 0.285706 -0.218217 0.933142 + outer loop + vertex 1.63526 1.06613 2.49605 + vertex 1.63124 1.06331 2.49662 + vertex 1.63365 1.06243 2.49568 + endloop + endfacet + facet normal 0.284706 -0.220675 0.932869 + outer loop + vertex 1.63365 1.06243 2.49568 + vertex 1.63124 1.06331 2.49662 + vertex 1.6309 1.06016 2.49598 + endloop + endfacet + facet normal 0.28639 -0.222861 0.931834 + outer loop + vertex 1.63365 1.06243 2.49568 + vertex 1.6309 1.06016 2.49598 + vertex 1.63293 1.05854 2.49497 + endloop + endfacet + facet normal 0.285737 -0.223679 0.931838 + outer loop + vertex 1.63293 1.05854 2.49497 + vertex 1.6309 1.06016 2.49598 + vertex 1.62919 1.05733 2.49583 + endloop + endfacet + facet normal 0.284705 -0.219558 0.933133 + outer loop + vertex 1.62919 1.05733 2.49583 + vertex 1.62831 1.05357 2.49521 + vertex 1.63293 1.05854 2.49497 + endloop + endfacet + facet normal 0.286924 -0.221675 0.931952 + outer loop + vertex 1.63293 1.05854 2.49497 + vertex 1.62831 1.05357 2.49521 + vertex 1.63283 1.05362 2.49383 + endloop + endfacet + facet normal 0.28577 -0.221732 0.932293 + outer loop + vertex 1.63283 1.05362 2.49383 + vertex 1.63771 1.05864 2.49353 + vertex 1.63293 1.05854 2.49497 + endloop + endfacet + facet normal 0.285789 -0.221344 0.93238 + outer loop + vertex 1.63776 1.06385 2.49475 + vertex 1.63293 1.05854 2.49497 + vertex 1.63771 1.05864 2.49353 + endloop + endfacet + facet normal 0.285719 -0.221348 0.9324 + outer loop + vertex 1.63771 1.05864 2.49353 + vertex 1.64261 1.06373 2.49323 + vertex 1.63776 1.06385 2.49475 + endloop + endfacet + facet normal 0.286045 -0.217659 0.933168 + outer loop + vertex 1.64261 1.06373 2.49323 + vertex 1.64299 1.06868 2.49427 + vertex 1.63776 1.06385 2.49475 + endloop + endfacet + facet normal 0.283096 -0.217627 0.934075 + outer loop + vertex 1.64261 1.06373 2.49323 + vertex 1.64748 1.06876 2.49293 + vertex 1.64299 1.06868 2.49427 + endloop + endfacet + facet normal 0.283286 -0.213432 0.934984 + outer loop + vertex 1.64748 1.06876 2.49293 + vertex 1.64774 1.07361 2.49396 + vertex 1.64299 1.06868 2.49427 + endloop + endfacet + facet normal 0.282398 -0.212547 0.935454 + outer loop + vertex 1.64299 1.06868 2.49427 + vertex 1.64774 1.07361 2.49396 + vertex 1.64327 1.07345 2.49527 + endloop + endfacet + facet normal 0.28587 -0.212531 0.934403 + outer loop + vertex 1.64327 1.07345 2.49527 + vertex 1.63927 1.06897 2.49548 + vertex 1.64299 1.06868 2.49427 + endloop + endfacet + facet normal 0.28545 -0.212146 0.934619 + outer loop + vertex 1.63964 1.07218 2.49609 + vertex 1.63927 1.06897 2.49548 + vertex 1.64327 1.07345 2.49527 + endloop + endfacet + facet normal 0.284644 -0.209251 0.935517 + outer loop + vertex 1.64327 1.07345 2.49527 + vertex 1.64137 1.0751 2.49622 + vertex 1.63964 1.07218 2.49609 + endloop + endfacet + facet normal 0.285697 -0.209854 0.935061 + outer loop + vertex 1.64137 1.0751 2.49622 + vertex 1.63759 1.0738 2.49708 + vertex 1.63964 1.07218 2.49609 + endloop + endfacet + facet normal 0.286151 -0.211502 0.934551 + outer loop + vertex 1.64137 1.0751 2.49622 + vertex 1.64231 1.079 2.49681 + vertex 1.63759 1.0738 2.49708 + endloop + endfacet + facet normal 0.285173 -0.211317 0.934891 + outer loop + vertex 1.64417 1.07728 2.49586 + vertex 1.64231 1.079 2.49681 + vertex 1.64137 1.0751 2.49622 + endloop + endfacet + facet normal 0.284403 -0.212177 0.934931 + outer loop + vertex 1.64607 1.08032 2.49597 + vertex 1.64231 1.079 2.49681 + vertex 1.64417 1.07728 2.49586 + endloop + endfacet + facet normal 0.281249 -0.210264 0.936316 + outer loop + vertex 1.64792 1.07854 2.49501 + vertex 1.64607 1.08032 2.49597 + vertex 1.64417 1.07728 2.49586 + endloop + endfacet + facet normal 0.280987 -0.209279 0.936615 + outer loop + vertex 1.64417 1.07728 2.49586 + vertex 1.64327 1.07345 2.49527 + vertex 1.64792 1.07854 2.49501 + endloop + endfacet + facet normal 0.280587 -0.210975 0.936355 + outer loop + vertex 1.64889 1.0825 2.49561 + vertex 1.64607 1.08032 2.49597 + vertex 1.64792 1.07854 2.49501 + endloop + endfacet + facet normal 0.280876 -0.211031 0.936256 + outer loop + vertex 1.64889 1.0825 2.49561 + vertex 1.64792 1.07854 2.49501 + vertex 1.65269 1.08374 2.49476 + endloop + endfacet + facet normal 0.281357 -0.212887 0.935691 + outer loop + vertex 1.65269 1.08374 2.49476 + vertex 1.65063 1.0854 2.49575 + vertex 1.64889 1.0825 2.49561 + endloop + endfacet + facet normal 0.280789 -0.212558 0.935936 + outer loop + vertex 1.65063 1.0854 2.49575 + vertex 1.64696 1.08407 2.49655 + vertex 1.64889 1.0825 2.49561 + endloop + endfacet + facet normal 0.280518 -0.210694 0.936439 + outer loop + vertex 1.65269 1.08374 2.49476 + vertex 1.64792 1.07854 2.49501 + vertex 1.65262 1.07868 2.49364 + endloop + endfacet + facet normal 0.280518 -0.210702 0.936437 + outer loop + vertex 1.64774 1.07361 2.49396 + vertex 1.65262 1.07868 2.49364 + vertex 1.64792 1.07854 2.49501 + endloop + endfacet + facet normal 0.280318 -0.210502 0.936542 + outer loop + vertex 1.65226 1.0737 2.49263 + vertex 1.65262 1.07868 2.49364 + vertex 1.64774 1.07361 2.49396 + endloop + endfacet + facet normal 0.280554 -0.210505 0.936471 + outer loop + vertex 1.65226 1.0737 2.49263 + vertex 1.65753 1.07858 2.49214 + vertex 1.65262 1.07868 2.49364 + endloop + endfacet + facet normal 0.278891 -0.208615 0.93739 + outer loop + vertex 1.65607 1.07349 2.49144 + vertex 1.65753 1.07858 2.49214 + vertex 1.65226 1.0737 2.49263 + endloop + endfacet + facet normal 0.281281 -0.211947 0.935927 + outer loop + vertex 1.64889 1.0825 2.49561 + vertex 1.64696 1.08407 2.49655 + vertex 1.64607 1.08032 2.49597 + endloop + endfacet + facet normal 0.284505 -0.212538 0.934818 + outer loop + vertex 1.64607 1.08032 2.49597 + vertex 1.64696 1.08407 2.49655 + vertex 1.64231 1.079 2.49681 + endloop + endfacet + facet normal 0.282793 -0.210924 0.935703 + outer loop + vertex 1.64696 1.08407 2.49655 + vertex 1.64244 1.08376 2.49785 + vertex 1.64231 1.079 2.49681 + endloop + endfacet + facet normal 0.285993 -0.210807 0.934756 + outer loop + vertex 1.64231 1.079 2.49681 + vertex 1.64244 1.08376 2.49785 + vertex 1.63763 1.07874 2.49819 + endloop + endfacet + facet normal 0.285285 -0.210101 0.935131 + outer loop + vertex 1.63763 1.07874 2.49819 + vertex 1.64244 1.08376 2.49785 + vertex 1.63799 1.08369 2.49919 + endloop + endfacet + facet normal 0.282782 -0.208581 0.936231 + outer loop + vertex 1.64696 1.08407 2.49655 + vertex 1.64717 1.08866 2.49751 + vertex 1.64244 1.08376 2.49785 + endloop + endfacet + facet normal 0.280692 -0.20649 0.937323 + outer loop + vertex 1.64244 1.08376 2.49785 + vertex 1.64717 1.08866 2.49751 + vertex 1.64266 1.08858 2.49884 + endloop + endfacet + facet normal 0.278784 -0.208639 0.937416 + outer loop + vertex 1.65098 1.08853 2.49635 + vertex 1.64717 1.08866 2.49751 + vertex 1.64696 1.08407 2.49655 + endloop + endfacet + facet normal 0.279127 -0.204978 0.938122 + outer loop + vertex 1.65098 1.08853 2.49635 + vertex 1.65243 1.09355 2.49701 + vertex 1.64717 1.08866 2.49751 + endloop + endfacet + facet normal 0.277139 -0.202729 0.939199 + outer loop + vertex 1.64717 1.08866 2.49751 + vertex 1.65243 1.09355 2.49701 + vertex 1.64757 1.09356 2.49845 + endloop + endfacet + facet normal 0.279023 -0.204953 0.938158 + outer loop + vertex 1.65243 1.09355 2.49701 + vertex 1.65098 1.08853 2.49635 + vertex 1.65503 1.09144 2.49578 + endloop + endfacet + facet normal 0.27924 -0.204681 0.938153 + outer loop + vertex 1.6566 1.09516 2.49612 + vertex 1.65243 1.09355 2.49701 + vertex 1.65503 1.09144 2.49578 + endloop + endfacet + facet normal 0.277445 -0.199075 0.93989 + outer loop + vertex 1.6566 1.09516 2.49612 + vertex 1.65713 1.09885 2.49675 + vertex 1.65243 1.09355 2.49701 + endloop + endfacet + facet normal 0.277457 -0.199086 0.939884 + outer loop + vertex 1.65713 1.09885 2.49675 + vertex 1.65249 1.09857 2.49806 + vertex 1.65243 1.09355 2.49701 + endloop + endfacet + facet normal 0.280613 -0.199358 0.938889 + outer loop + vertex 1.65931 1.09748 2.49581 + vertex 1.65713 1.09885 2.49675 + vertex 1.6566 1.09516 2.49612 + endloop + endfacet + facet normal 0.285014 -0.204833 0.936382 + outer loop + vertex 1.65931 1.09748 2.49581 + vertex 1.6566 1.09516 2.49612 + vertex 1.65906 1.09431 2.49519 + endloop + endfacet + facet normal 0.281174 -0.198478 0.938908 + outer loop + vertex 1.66079 1.10021 2.49594 + vertex 1.65713 1.09885 2.49675 + vertex 1.65931 1.09748 2.49581 + endloop + endfacet + facet normal 0.287144 -0.201586 0.936435 + outer loop + vertex 1.66296 1.09872 2.49495 + vertex 1.66079 1.10021 2.49594 + vertex 1.65931 1.09748 2.49581 + endloop + endfacet + facet normal 0.287949 -0.200415 0.93644 + outer loop + vertex 1.66349 1.10252 2.4956 + vertex 1.66079 1.10021 2.49594 + vertex 1.66296 1.09872 2.49495 + endloop + endfacet + facet normal 0.284486 -0.196079 0.938414 + outer loop + vertex 1.66349 1.10252 2.4956 + vertex 1.66103 1.10333 2.49652 + vertex 1.66079 1.10021 2.49594 + endloop + endfacet + facet normal 0.284686 -0.195533 0.938467 + outer loop + vertex 1.66505 1.10628 2.49591 + vertex 1.66103 1.10333 2.49652 + vertex 1.66349 1.10252 2.4956 + endloop + endfacet + facet normal 0.288735 -0.197086 0.936904 + outer loop + vertex 1.66349 1.10252 2.4956 + vertex 1.66762 1.10396 2.49463 + vertex 1.66505 1.10628 2.49591 + endloop + endfacet + facet normal 0.289943 -0.1957 0.936822 + outer loop + vertex 1.66762 1.10396 2.49463 + vertex 1.66907 1.10923 2.49528 + vertex 1.66505 1.10628 2.49591 + endloop + endfacet + facet normal 0.290049 -0.195858 0.936756 + outer loop + vertex 1.66907 1.10923 2.49528 + vertex 1.66662 1.11007 2.49622 + vertex 1.66505 1.10628 2.49591 + endloop + endfacet + facet normal 0.28317 -0.193229 0.939403 + outer loop + vertex 1.66662 1.11007 2.49622 + vertex 1.66245 1.10848 2.49715 + vertex 1.66505 1.10628 2.49591 + endloop + endfacet + facet normal 0.28164 -0.188373 0.940848 + outer loop + vertex 1.66662 1.11007 2.49622 + vertex 1.66714 1.11385 2.49682 + vertex 1.66245 1.10848 2.49715 + endloop + endfacet + facet normal 0.283153 -0.193249 0.939404 + outer loop + vertex 1.66245 1.10848 2.49715 + vertex 1.66103 1.10333 2.49652 + vertex 1.66505 1.10628 2.49591 + endloop + endfacet + facet normal 0.280416 -0.195994 0.939656 + outer loop + vertex 1.66079 1.10021 2.49594 + vertex 1.66103 1.10333 2.49652 + vertex 1.65713 1.09885 2.49675 + endloop + endfacet + facet normal 0.279853 -0.195491 0.939929 + outer loop + vertex 1.66103 1.10333 2.49652 + vertex 1.65723 1.10355 2.4977 + vertex 1.65713 1.09885 2.49675 + endloop + endfacet + facet normal 0.284125 -0.209858 0.935539 + outer loop + vertex 1.64417 1.07728 2.49586 + vertex 1.64137 1.0751 2.49622 + vertex 1.64327 1.07345 2.49527 + endloop + endfacet + facet normal 0.282449 -0.210654 0.935867 + outer loop + vertex 1.64792 1.07854 2.49501 + vertex 1.64327 1.07345 2.49527 + vertex 1.64774 1.07361 2.49396 + endloop + endfacet + facet normal 0.28019 -0.213464 0.93591 + outer loop + vertex 1.64748 1.06876 2.49293 + vertex 1.65226 1.0737 2.49263 + vertex 1.64774 1.07361 2.49396 + endloop + endfacet + facet normal 0.2806 -0.213874 0.935693 + outer loop + vertex 1.65203 1.06903 2.49163 + vertex 1.65226 1.0737 2.49263 + vertex 1.64748 1.06876 2.49293 + endloop + endfacet + facet normal 0.280571 -0.218693 0.934587 + outer loop + vertex 1.65203 1.06903 2.49163 + vertex 1.64748 1.06876 2.49293 + vertex 1.64733 1.06398 2.49186 + endloop + endfacet + facet normal 0.281674 -0.219742 0.934009 + outer loop + vertex 1.65112 1.06528 2.49102 + vertex 1.65203 1.06903 2.49163 + vertex 1.64733 1.06398 2.49186 + endloop + endfacet + facet normal 0.282398 -0.222403 0.93316 + outer loop + vertex 1.65112 1.06528 2.49102 + vertex 1.64733 1.06398 2.49186 + vertex 1.6492 1.06225 2.49088 + endloop + endfacet + facet normal 0.280943 -0.221511 0.933811 + outer loop + vertex 1.65296 1.06349 2.49004 + vertex 1.65112 1.06528 2.49102 + vertex 1.6492 1.06225 2.49088 + endloop + endfacet + facet normal 0.280879 -0.221262 0.93389 + outer loop + vertex 1.6492 1.06225 2.49088 + vertex 1.64827 1.05844 2.49026 + vertex 1.65296 1.06349 2.49004 + endloop + endfacet + facet normal 0.281548 -0.221899 0.933537 + outer loop + vertex 1.65296 1.06349 2.49004 + vertex 1.64827 1.05844 2.49026 + vertex 1.65273 1.0586 2.48895 + endloop + endfacet + facet normal 0.281534 -0.222348 0.933434 + outer loop + vertex 1.64796 1.05373 2.48923 + vertex 1.65273 1.0586 2.48895 + vertex 1.64827 1.05844 2.49026 + endloop + endfacet + facet normal 0.284005 -0.222345 0.932687 + outer loop + vertex 1.64827 1.05844 2.49026 + vertex 1.64424 1.05401 2.49043 + vertex 1.64796 1.05373 2.48923 + endloop + endfacet + facet normal 0.283718 -0.22438 0.932286 + outer loop + vertex 1.64272 1.04895 2.48967 + vertex 1.64796 1.05373 2.48923 + vertex 1.64424 1.05401 2.49043 + endloop + endfacet + facet normal 0.285993 -0.224937 0.931456 + outer loop + vertex 1.64272 1.04895 2.48967 + vertex 1.64424 1.05401 2.49043 + vertex 1.64021 1.05121 2.49099 + endloop + endfacet + facet normal 0.285638 -0.225338 0.931469 + outer loop + vertex 1.63861 1.04756 2.49059 + vertex 1.64272 1.04895 2.48967 + vertex 1.64021 1.05121 2.49099 + endloop + endfacet + facet normal 0.286948 -0.225858 0.93094 + outer loop + vertex 1.64021 1.05121 2.49099 + vertex 1.6362 1.04843 2.49155 + vertex 1.63861 1.04756 2.49059 + endloop + endfacet + facet normal 0.286491 -0.226969 0.93081 + outer loop + vertex 1.63861 1.04756 2.49059 + vertex 1.6362 1.04843 2.49155 + vertex 1.63585 1.04531 2.4909 + endloop + endfacet + facet normal 0.287707 -0.228565 0.930045 + outer loop + vertex 1.63861 1.04756 2.49059 + vertex 1.63585 1.04531 2.4909 + vertex 1.63785 1.04364 2.48987 + endloop + endfacet + facet normal 0.287281 -0.229077 0.93005 + outer loop + vertex 1.63785 1.04364 2.48987 + vertex 1.63585 1.04531 2.4909 + vertex 1.63411 1.04245 2.49073 + endloop + endfacet + facet normal 0.286896 -0.227504 0.930555 + outer loop + vertex 1.63411 1.04245 2.49073 + vertex 1.63307 1.0385 2.49008 + vertex 1.63785 1.04364 2.48987 + endloop + endfacet + facet normal 0.287816 -0.228381 0.930056 + outer loop + vertex 1.63785 1.04364 2.48987 + vertex 1.63307 1.0385 2.49008 + vertex 1.6377 1.03865 2.48869 + endloop + endfacet + facet normal 0.284966 -0.228496 0.930905 + outer loop + vertex 1.6377 1.03865 2.48869 + vertex 1.64264 1.04375 2.48843 + vertex 1.63785 1.04364 2.48987 + endloop + endfacet + facet normal 0.285033 -0.227073 0.931233 + outer loop + vertex 1.64272 1.04895 2.48967 + vertex 1.63785 1.04364 2.48987 + vertex 1.64264 1.04375 2.48843 + endloop + endfacet + facet normal 0.283976 -0.22713 0.931542 + outer loop + vertex 1.64264 1.04375 2.48843 + vertex 1.64756 1.04884 2.48817 + vertex 1.64272 1.04895 2.48967 + endloop + endfacet + facet normal 0.283863 -0.227018 0.931603 + outer loop + vertex 1.64748 1.04394 2.487 + vertex 1.64756 1.04884 2.48817 + vertex 1.64264 1.04375 2.48843 + endloop + endfacet + facet normal 0.283837 -0.227893 0.931398 + outer loop + vertex 1.64748 1.04394 2.487 + vertex 1.64264 1.04375 2.48843 + vertex 1.64255 1.03856 2.48718 + endloop + endfacet + facet normal 0.283834 -0.22789 0.931399 + outer loop + vertex 1.64672 1.04003 2.48627 + vertex 1.64748 1.04394 2.487 + vertex 1.64255 1.03856 2.48718 + endloop + endfacet + facet normal 0.28399 -0.228448 0.931215 + outer loop + vertex 1.64672 1.04003 2.48627 + vertex 1.64255 1.03856 2.48718 + vertex 1.64508 1.03634 2.48587 + endloop + endfacet + facet normal 0.285126 -0.228059 0.930963 + outer loop + vertex 1.64952 1.04234 2.48598 + vertex 1.64748 1.04394 2.487 + vertex 1.64672 1.04003 2.48627 + endloop + endfacet + facet normal 0.286179 -0.229419 0.930305 + outer loop + vertex 1.64952 1.04234 2.48598 + vertex 1.64672 1.04003 2.48627 + vertex 1.64913 1.03916 2.48532 + endloop + endfacet + facet normal 0.28465 -0.228664 0.93096 + outer loop + vertex 1.65129 1.04523 2.48615 + vertex 1.64748 1.04394 2.487 + vertex 1.64952 1.04234 2.48598 + endloop + endfacet + facet normal 0.285552 -0.229192 0.930554 + outer loop + vertex 1.6532 1.04357 2.48515 + vertex 1.65129 1.04523 2.48615 + vertex 1.64952 1.04234 2.48598 + endloop + endfacet + facet normal 0.284681 -0.2302 0.930572 + outer loop + vertex 1.65415 1.04738 2.48581 + vertex 1.65129 1.04523 2.48615 + vertex 1.6532 1.04357 2.48515 + endloop + endfacet + facet normal 0.283768 -0.228888 0.931174 + outer loop + vertex 1.65415 1.04738 2.48581 + vertex 1.65228 1.0491 2.4868 + vertex 1.65129 1.04523 2.48615 + endloop + endfacet + facet normal 0.283136 -0.229588 0.931194 + outer loop + vertex 1.65608 1.05038 2.48596 + vertex 1.65228 1.0491 2.4868 + vertex 1.65415 1.04738 2.48581 + endloop + endfacet + facet normal 0.285302 -0.230929 0.930201 + outer loop + vertex 1.65793 1.04858 2.48495 + vertex 1.65608 1.05038 2.48596 + vertex 1.65415 1.04738 2.48581 + endloop + endfacet + facet normal 0.285114 -0.231127 0.93021 + outer loop + vertex 1.65892 1.0525 2.48562 + vertex 1.65608 1.05038 2.48596 + vertex 1.65793 1.04858 2.48495 + endloop + endfacet + facet normal 0.282437 -0.227258 0.931978 + outer loop + vertex 1.65892 1.0525 2.48562 + vertex 1.65698 1.0541 2.48659 + vertex 1.65608 1.05038 2.48596 + endloop + endfacet + facet normal 0.28254 -0.227133 0.931977 + outer loop + vertex 1.66067 1.05537 2.48579 + vertex 1.65698 1.0541 2.48659 + vertex 1.65892 1.0525 2.48562 + endloop + endfacet + facet normal 0.286303 -0.229336 0.930288 + outer loop + vertex 1.6627 1.05371 2.48475 + vertex 1.66067 1.05537 2.48579 + vertex 1.65892 1.0525 2.48562 + endloop + endfacet + facet normal 0.286948 -0.228542 0.930285 + outer loop + vertex 1.66344 1.05763 2.48549 + vertex 1.66067 1.05537 2.48579 + vertex 1.6627 1.05371 2.48475 + endloop + endfacet + facet normal 0.283271 -0.223734 0.932577 + outer loop + vertex 1.66344 1.05763 2.48549 + vertex 1.66102 1.05848 2.48643 + vertex 1.66067 1.05537 2.48579 + endloop + endfacet + facet normal 0.283597 -0.222911 0.932675 + outer loop + vertex 1.66507 1.06132 2.48587 + vertex 1.66102 1.05848 2.48643 + vertex 1.66344 1.05763 2.48549 + endloop + endfacet + facet normal 0.284655 -0.223335 0.932252 + outer loop + vertex 1.66344 1.05763 2.48549 + vertex 1.66759 1.05905 2.48456 + vertex 1.66507 1.06132 2.48587 + endloop + endfacet + facet normal 0.284456 -0.22356 0.932258 + outer loop + vertex 1.66759 1.05905 2.48456 + vertex 1.66913 1.06416 2.48532 + vertex 1.66507 1.06132 2.48587 + endloop + endfacet + facet normal 0.282553 -0.220595 0.933543 + outer loop + vertex 1.66913 1.06416 2.48532 + vertex 1.66672 1.06504 2.48625 + vertex 1.66507 1.06132 2.48587 + endloop + endfacet + facet normal 0.282548 -0.220593 0.933544 + outer loop + vertex 1.66672 1.06504 2.48625 + vertex 1.66252 1.06354 2.48717 + vertex 1.66507 1.06132 2.48587 + endloop + endfacet + facet normal 0.282299 -0.220883 0.933551 + outer loop + vertex 1.66252 1.06354 2.48717 + vertex 1.66102 1.05848 2.48643 + vertex 1.66507 1.06132 2.48587 + endloop + endfacet + facet normal 0.281075 -0.220584 0.933991 + outer loop + vertex 1.66102 1.05848 2.48643 + vertex 1.66252 1.06354 2.48717 + vertex 1.65723 1.0587 2.48762 + endloop + endfacet + facet normal 0.280797 -0.222908 0.933523 + outer loop + vertex 1.66102 1.05848 2.48643 + vertex 1.65723 1.0587 2.48762 + vertex 1.65698 1.0541 2.48659 + endloop + endfacet + facet normal 0.28095 -0.222906 0.933477 + outer loop + vertex 1.65698 1.0541 2.48659 + vertex 1.65723 1.0587 2.48762 + vertex 1.65245 1.05382 2.48789 + endloop + endfacet + facet normal 0.280929 -0.225742 0.932802 + outer loop + vertex 1.65698 1.0541 2.48659 + vertex 1.65245 1.05382 2.48789 + vertex 1.65228 1.0491 2.4868 + endloop + endfacet + facet normal 0.282679 -0.225686 0.932287 + outer loop + vertex 1.65228 1.0491 2.4868 + vertex 1.65245 1.05382 2.48789 + vertex 1.64756 1.04884 2.48817 + endloop + endfacet + facet normal 0.281871 -0.224868 0.932729 + outer loop + vertex 1.64756 1.04884 2.48817 + vertex 1.65245 1.05382 2.48789 + vertex 1.64796 1.05373 2.48923 + endloop + endfacet + facet normal 0.280838 -0.222792 0.933538 + outer loop + vertex 1.65245 1.05382 2.48789 + vertex 1.65723 1.0587 2.48762 + vertex 1.65273 1.0586 2.48895 + endloop + endfacet + facet normal 0.280902 -0.221395 0.933851 + outer loop + vertex 1.65723 1.0587 2.48762 + vertex 1.65763 1.06363 2.48867 + vertex 1.65273 1.0586 2.48895 + endloop + endfacet + facet normal 0.281796 -0.221409 0.933579 + outer loop + vertex 1.65723 1.0587 2.48762 + vertex 1.66252 1.06354 2.48717 + vertex 1.65763 1.06363 2.48867 + endloop + endfacet + facet normal 0.28235 -0.219898 0.933768 + outer loop + vertex 1.66672 1.06504 2.48625 + vertex 1.66743 1.06894 2.48696 + vertex 1.66252 1.06354 2.48717 + endloop + endfacet + facet normal 0.282207 -0.219765 0.933843 + outer loop + vertex 1.66743 1.06894 2.48696 + vertex 1.66257 1.06877 2.48838 + vertex 1.66252 1.06354 2.48717 + endloop + endfacet + facet normal 0.282153 -0.219874 0.933834 + outer loop + vertex 1.66951 1.06736 2.48596 + vertex 1.66743 1.06894 2.48696 + vertex 1.66672 1.06504 2.48625 + endloop + endfacet + facet normal 0.281889 -0.220221 0.933832 + outer loop + vertex 1.67123 1.07023 2.48611 + vertex 1.66743 1.06894 2.48696 + vertex 1.66951 1.06736 2.48596 + endloop + endfacet + facet normal 0.284372 -0.22165 0.93274 + outer loop + vertex 1.67316 1.06858 2.48513 + vertex 1.67123 1.07023 2.48611 + vertex 1.66951 1.06736 2.48596 + endloop + endfacet + facet normal 0.284079 -0.22054 0.933092 + outer loop + vertex 1.66951 1.06736 2.48596 + vertex 1.66913 1.06416 2.48532 + vertex 1.67316 1.06858 2.48513 + endloop + endfacet + facet normal 0.283938 -0.220409 0.933166 + outer loop + vertex 1.67316 1.06858 2.48513 + vertex 1.66913 1.06416 2.48532 + vertex 1.67285 1.06382 2.4841 + endloop + endfacet + facet normal 0.281273 -0.217927 0.934555 + outer loop + vertex 1.67123 1.07023 2.48611 + vertex 1.67205 1.07395 2.48673 + vertex 1.66743 1.06894 2.48696 + endloop + endfacet + facet normal 0.280717 -0.217402 0.934845 + outer loop + vertex 1.67205 1.07395 2.48673 + vertex 1.66746 1.07384 2.48809 + vertex 1.66743 1.06894 2.48696 + endloop + endfacet + facet normal 0.283091 -0.218224 0.933937 + outer loop + vertex 1.67402 1.07234 2.48576 + vertex 1.67205 1.07395 2.48673 + vertex 1.67123 1.07023 2.48611 + endloop + endfacet + facet normal 0.282609 -0.220458 0.933558 + outer loop + vertex 1.66951 1.06736 2.48596 + vertex 1.66672 1.06504 2.48625 + vertex 1.66913 1.06416 2.48532 + endloop + endfacet + facet normal 0.281588 -0.223652 0.933107 + outer loop + vertex 1.66067 1.05537 2.48579 + vertex 1.66102 1.05848 2.48643 + vertex 1.65698 1.0541 2.48659 + endloop + endfacet + facet normal 0.282519 -0.227273 0.931949 + outer loop + vertex 1.65608 1.05038 2.48596 + vertex 1.65698 1.0541 2.48659 + vertex 1.65228 1.0491 2.4868 + endloop + endfacet + facet normal 0.284762 -0.229083 0.930823 + outer loop + vertex 1.65129 1.04523 2.48615 + vertex 1.65228 1.0491 2.4868 + vertex 1.64748 1.04394 2.487 + endloop + endfacet + facet normal 0.282658 -0.227081 0.931954 + outer loop + vertex 1.65228 1.0491 2.4868 + vertex 1.64756 1.04884 2.48817 + vertex 1.64748 1.04394 2.487 + endloop + endfacet + facet normal 0.284333 -0.227866 0.931253 + outer loop + vertex 1.64255 1.03856 2.48718 + vertex 1.64264 1.04375 2.48843 + vertex 1.6377 1.03865 2.48869 + endloop + endfacet + facet normal 0.284193 -0.229495 0.930895 + outer loop + vertex 1.63726 1.03376 2.48761 + vertex 1.64255 1.03856 2.48718 + vertex 1.6377 1.03865 2.48869 + endloop + endfacet + facet normal 0.28979 -0.229609 0.92914 + outer loop + vertex 1.63726 1.03376 2.48761 + vertex 1.6377 1.03865 2.48869 + vertex 1.63278 1.03362 2.48898 + endloop + endfacet + facet normal 0.28971 -0.231554 0.928682 + outer loop + vertex 1.63247 1.02887 2.48789 + vertex 1.63726 1.03376 2.48761 + vertex 1.63278 1.03362 2.48898 + endloop + endfacet + facet normal 0.298512 -0.231508 0.925902 + outer loop + vertex 1.63247 1.02887 2.48789 + vertex 1.63278 1.03362 2.48898 + vertex 1.62796 1.02865 2.48929 + endloop + endfacet + facet normal 0.29692 -0.229905 0.926813 + outer loop + vertex 1.62796 1.02865 2.48929 + vertex 1.63278 1.03362 2.48898 + vertex 1.62833 1.03338 2.49035 + endloop + endfacet + facet normal 0.296968 -0.227542 0.92738 + outer loop + vertex 1.63307 1.0385 2.49008 + vertex 1.62833 1.03338 2.49035 + vertex 1.63278 1.03362 2.48898 + endloop + endfacet + facet normal 0.292545 -0.223317 0.92981 + outer loop + vertex 1.62932 1.03725 2.49096 + vertex 1.62833 1.03338 2.49035 + vertex 1.63307 1.0385 2.49008 + endloop + endfacet + facet normal 0.293393 -0.2266 0.928748 + outer loop + vertex 1.63307 1.0385 2.49008 + vertex 1.63127 1.04031 2.49109 + vertex 1.62932 1.03725 2.49096 + endloop + endfacet + facet normal 0.298753 -0.229907 0.926223 + outer loop + vertex 1.63127 1.04031 2.49109 + vertex 1.62745 1.03897 2.492 + vertex 1.62932 1.03725 2.49096 + endloop + endfacet + facet normal 0.300886 -0.227524 0.926121 + outer loop + vertex 1.62932 1.03725 2.49096 + vertex 1.62745 1.03897 2.492 + vertex 1.62646 1.03503 2.49135 + endloop + endfacet + facet normal 0.287575 -0.225002 0.930954 + outer loop + vertex 1.62646 1.03503 2.49135 + vertex 1.62745 1.03897 2.492 + vertex 1.62269 1.0337 2.49219 + endloop + endfacet + facet normal 0.283832 -0.211687 0.935215 + outer loop + vertex 1.62646 1.03503 2.49135 + vertex 1.62269 1.0337 2.49219 + vertex 1.62468 1.03206 2.49121 + endloop + endfacet + facet normal 0.301195 -0.221747 0.927421 + outer loop + vertex 1.62833 1.03338 2.49035 + vertex 1.62646 1.03503 2.49135 + vertex 1.62468 1.03206 2.49121 + endloop + endfacet + facet normal 0.30312 -0.228523 0.925146 + outer loop + vertex 1.62468 1.03206 2.49121 + vertex 1.62426 1.02886 2.49056 + vertex 1.62833 1.03338 2.49035 + endloop + endfacet + facet normal 0.290449 -0.227727 0.929397 + outer loop + vertex 1.62468 1.03206 2.49121 + vertex 1.62197 1.02976 2.4915 + vertex 1.62426 1.02886 2.49056 + endloop + endfacet + facet normal 0.29914 -0.231346 0.92574 + outer loop + vertex 1.63127 1.04031 2.49109 + vertex 1.63217 1.04407 2.49174 + vertex 1.62745 1.03897 2.492 + endloop + endfacet + facet normal 0.295589 -0.227954 0.92772 + outer loop + vertex 1.63217 1.04407 2.49174 + vertex 1.62755 1.04383 2.49316 + vertex 1.62745 1.03897 2.492 + endloop + endfacet + facet normal 0.295647 -0.225373 0.928332 + outer loop + vertex 1.63217 1.04407 2.49174 + vertex 1.63241 1.04872 2.49279 + vertex 1.62755 1.04383 2.49316 + endloop + endfacet + facet normal 0.291664 -0.22124 0.930583 + outer loop + vertex 1.62755 1.04383 2.49316 + vertex 1.63241 1.04872 2.49279 + vertex 1.62799 1.04877 2.49419 + endloop + endfacet + facet normal 0.297121 -0.221352 0.928828 + outer loop + vertex 1.62755 1.04383 2.49316 + vertex 1.62799 1.04877 2.49419 + vertex 1.62267 1.04383 2.49472 + endloop + endfacet + facet normal 0.296284 -0.233347 0.926156 + outer loop + vertex 1.62262 1.03865 2.49343 + vertex 1.62755 1.04383 2.49316 + vertex 1.62267 1.04383 2.49472 + endloop + endfacet + facet normal 0.270903 -0.234935 0.933497 + outer loop + vertex 1.62267 1.04383 2.49472 + vertex 1.61767 1.03847 2.49482 + vertex 1.62262 1.03865 2.49343 + endloop + endfacet + facet normal 0.270051 -0.258805 0.927412 + outer loop + vertex 1.61778 1.03352 2.49341 + vertex 1.62262 1.03865 2.49343 + vertex 1.61767 1.03847 2.49482 + endloop + endfacet + facet normal 0.312101 -0.273737 0.909759 + outer loop + vertex 1.61854 1.04232 2.49568 + vertex 1.61767 1.03847 2.49482 + vertex 1.62267 1.04383 2.49472 + endloop + endfacet + facet normal 0.297015 -0.22023 0.929129 + outer loop + vertex 1.61854 1.04232 2.49568 + vertex 1.62267 1.04383 2.49472 + vertex 1.6202 1.04608 2.49604 + endloop + endfacet + facet normal 0.254862 -0.203248 0.945376 + outer loop + vertex 1.6202 1.04608 2.49604 + vertex 1.61635 1.04346 2.49652 + vertex 1.61854 1.04232 2.49568 + endloop + endfacet + facet normal 0.298329 -0.218747 0.929059 + outer loop + vertex 1.62267 1.04383 2.49472 + vertex 1.62424 1.04905 2.49544 + vertex 1.6202 1.04608 2.49604 + endloop + endfacet + facet normal 0.293046 -0.210866 0.932555 + outer loop + vertex 1.62424 1.04905 2.49544 + vertex 1.62184 1.04988 2.49638 + vertex 1.6202 1.04608 2.49604 + endloop + endfacet + facet normal 0.266749 -0.200415 0.942698 + outer loop + vertex 1.62184 1.04988 2.49638 + vertex 1.61772 1.04839 2.49724 + vertex 1.6202 1.04608 2.49604 + endloop + endfacet + facet normal 0.27048 -0.212988 0.93887 + outer loop + vertex 1.62184 1.04988 2.49638 + vertex 1.62256 1.0538 2.49707 + vertex 1.61772 1.04839 2.49724 + endloop + endfacet + facet normal 0.295493 -0.216149 0.930571 + outer loop + vertex 1.62465 1.0523 2.49605 + vertex 1.62256 1.0538 2.49707 + vertex 1.62184 1.04988 2.49638 + endloop + endfacet + facet normal 0.293573 -0.218812 0.930557 + outer loop + vertex 1.6264 1.05521 2.49619 + vertex 1.62256 1.0538 2.49707 + vertex 1.62465 1.0523 2.49605 + endloop + endfacet + facet normal 0.290451 -0.217003 0.931959 + outer loop + vertex 1.62831 1.05357 2.49521 + vertex 1.6264 1.05521 2.49619 + vertex 1.62465 1.0523 2.49605 + endloop + endfacet + facet normal 0.289132 -0.212173 0.93348 + outer loop + vertex 1.62465 1.0523 2.49605 + vertex 1.62424 1.04905 2.49544 + vertex 1.62831 1.05357 2.49521 + endloop + endfacet + facet normal 0.293982 -0.216675 0.930928 + outer loop + vertex 1.62831 1.05357 2.49521 + vertex 1.62424 1.04905 2.49544 + vertex 1.62799 1.04877 2.49419 + endloop + endfacet + facet normal 0.29532 -0.224801 0.928574 + outer loop + vertex 1.6264 1.05521 2.49619 + vertex 1.62722 1.0589 2.49682 + vertex 1.62256 1.0538 2.49707 + endloop + endfacet + facet normal 0.292326 -0.221988 0.930197 + outer loop + vertex 1.62722 1.0589 2.49682 + vertex 1.62258 1.05866 2.49822 + vertex 1.62256 1.0538 2.49707 + endloop + endfacet + facet normal 0.29238 -0.21879 0.930938 + outer loop + vertex 1.62722 1.0589 2.49682 + vertex 1.62745 1.06359 2.49785 + vertex 1.62258 1.05866 2.49822 + endloop + endfacet + facet normal 0.285898 -0.218912 0.93292 + outer loop + vertex 1.63124 1.06331 2.49662 + vertex 1.62745 1.06359 2.49785 + vertex 1.62722 1.0589 2.49682 + endloop + endfacet + facet normal 0.286407 -0.215182 0.933632 + outer loop + vertex 1.63124 1.06331 2.49662 + vertex 1.63272 1.0684 2.49734 + vertex 1.62745 1.06359 2.49785 + endloop + endfacet + facet normal 0.284937 -0.213482 0.934471 + outer loop + vertex 1.62745 1.06359 2.49785 + vertex 1.63272 1.0684 2.49734 + vertex 1.62786 1.06855 2.49886 + endloop + endfacet + facet normal 0.289946 -0.213579 0.932907 + outer loop + vertex 1.62745 1.06359 2.49785 + vertex 1.62786 1.06855 2.49886 + vertex 1.62299 1.06364 2.49925 + endloop + endfacet + facet normal 0.290586 -0.224034 0.930252 + outer loop + vertex 1.62919 1.05733 2.49583 + vertex 1.62722 1.0589 2.49682 + vertex 1.6264 1.05521 2.49619 + endloop + endfacet + facet normal 0.292461 -0.212387 0.932394 + outer loop + vertex 1.62465 1.0523 2.49605 + vertex 1.62184 1.04988 2.49638 + vertex 1.62424 1.04905 2.49544 + endloop + endfacet + facet normal 0.291019 -0.228186 0.929107 + outer loop + vertex 1.62745 1.03897 2.492 + vertex 1.62755 1.04383 2.49316 + vertex 1.62262 1.03865 2.49343 + endloop + endfacet + facet normal 0.291019 -0.228177 0.929109 + outer loop + vertex 1.62745 1.03897 2.492 + vertex 1.62262 1.03865 2.49343 + vertex 1.62269 1.0337 2.49219 + endloop + endfacet + facet normal 0.29385 -0.217628 0.930747 + outer loop + vertex 1.62267 1.04383 2.49472 + vertex 1.62799 1.04877 2.49419 + vertex 1.62424 1.04905 2.49544 + endloop + endfacet + facet normal 0.291659 -0.2213 0.930571 + outer loop + vertex 1.63241 1.04872 2.49279 + vertex 1.63283 1.05362 2.49383 + vertex 1.62799 1.04877 2.49419 + endloop + endfacet + facet normal 0.286285 -0.221197 0.932262 + outer loop + vertex 1.63241 1.04872 2.49279 + vertex 1.63768 1.05346 2.4923 + vertex 1.63283 1.05362 2.49383 + endloop + endfacet + facet normal 0.28892 -0.224285 0.93071 + outer loop + vertex 1.6362 1.04843 2.49155 + vertex 1.63768 1.05346 2.4923 + vertex 1.63241 1.04872 2.49279 + endloop + endfacet + facet normal 0.28875 -0.225497 0.93047 + outer loop + vertex 1.6362 1.04843 2.49155 + vertex 1.63241 1.04872 2.49279 + vertex 1.63217 1.04407 2.49174 + endloop + endfacet + facet normal 0.292831 -0.230229 0.928033 + outer loop + vertex 1.63411 1.04245 2.49073 + vertex 1.63217 1.04407 2.49174 + vertex 1.63127 1.04031 2.49109 + endloop + endfacet + facet normal 0.29877 -0.224555 0.92753 + outer loop + vertex 1.62932 1.03725 2.49096 + vertex 1.62646 1.03503 2.49135 + vertex 1.62833 1.03338 2.49035 + endloop + endfacet + facet normal 0.292508 -0.234393 0.927092 + outer loop + vertex 1.637 1.02922 2.48655 + vertex 1.63726 1.03376 2.48761 + vertex 1.63247 1.02887 2.48789 + endloop + endfacet + facet normal 0.292514 -0.238159 0.92613 + outer loop + vertex 1.637 1.02922 2.48655 + vertex 1.63247 1.02887 2.48789 + vertex 1.6323 1.02425 2.48676 + endloop + endfacet + facet normal 0.299281 -0.237888 0.924035 + outer loop + vertex 1.6323 1.02425 2.48676 + vertex 1.63247 1.02887 2.48789 + vertex 1.62756 1.0238 2.48818 + endloop + endfacet + facet normal 0.283711 -0.234521 0.929789 + outer loop + vertex 1.64103 1.03354 2.48641 + vertex 1.63726 1.03376 2.48761 + vertex 1.637 1.02922 2.48655 + endloop + endfacet + facet normal 0.284322 -0.229643 0.930819 + outer loop + vertex 1.64103 1.03354 2.48641 + vertex 1.64255 1.03856 2.48718 + vertex 1.63726 1.03376 2.48761 + endloop + endfacet + facet normal 0.287845 -0.227644 0.930227 + outer loop + vertex 1.63278 1.03362 2.48898 + vertex 1.6377 1.03865 2.48869 + vertex 1.63307 1.0385 2.49008 + endloop + endfacet + facet normal 0.291601 -0.228459 0.928857 + outer loop + vertex 1.63411 1.04245 2.49073 + vertex 1.63127 1.04031 2.49109 + vertex 1.63307 1.0385 2.49008 + endloop + endfacet + facet normal 0.291667 -0.231633 0.92805 + outer loop + vertex 1.63585 1.04531 2.4909 + vertex 1.63217 1.04407 2.49174 + vertex 1.63411 1.04245 2.49073 + endloop + endfacet + facet normal 0.290487 -0.227139 0.929529 + outer loop + vertex 1.63585 1.04531 2.4909 + vertex 1.6362 1.04843 2.49155 + vertex 1.63217 1.04407 2.49174 + endloop + endfacet + facet normal 0.28543 -0.223448 0.931987 + outer loop + vertex 1.63768 1.05346 2.4923 + vertex 1.6362 1.04843 2.49155 + vertex 1.64021 1.05121 2.49099 + endloop + endfacet + facet normal 0.285488 -0.223381 0.931986 + outer loop + vertex 1.64183 1.05488 2.49137 + vertex 1.63768 1.05346 2.4923 + vertex 1.64021 1.05121 2.49099 + endloop + endfacet + facet normal 0.285108 -0.221978 0.932437 + outer loop + vertex 1.64183 1.05488 2.49137 + vertex 1.64257 1.0588 2.49208 + vertex 1.63768 1.05346 2.4923 + endloop + endfacet + facet normal 0.285352 -0.222206 0.932308 + outer loop + vertex 1.64257 1.0588 2.49208 + vertex 1.63771 1.05864 2.49353 + vertex 1.63768 1.05346 2.4923 + endloop + endfacet + facet normal 0.285017 -0.221966 0.932468 + outer loop + vertex 1.64462 1.05719 2.49107 + vertex 1.64257 1.0588 2.49208 + vertex 1.64183 1.05488 2.49137 + endloop + endfacet + facet normal 0.285206 -0.22221 0.932352 + outer loop + vertex 1.64462 1.05719 2.49107 + vertex 1.64183 1.05488 2.49137 + vertex 1.64424 1.05401 2.49043 + endloop + endfacet + facet normal 0.285082 -0.221884 0.932467 + outer loop + vertex 1.64637 1.06009 2.49122 + vertex 1.64257 1.0588 2.49208 + vertex 1.64462 1.05719 2.49107 + endloop + endfacet + facet normal 0.283449 -0.220937 0.93319 + outer loop + vertex 1.64827 1.05844 2.49026 + vertex 1.64637 1.06009 2.49122 + vertex 1.64462 1.05719 2.49107 + endloop + endfacet + facet normal 0.285169 -0.222209 0.932364 + outer loop + vertex 1.64637 1.06009 2.49122 + vertex 1.64733 1.06398 2.49186 + vertex 1.64257 1.0588 2.49208 + endloop + endfacet + facet normal 0.283999 -0.221104 0.932983 + outer loop + vertex 1.64733 1.06398 2.49186 + vertex 1.64261 1.06373 2.49323 + vertex 1.64257 1.0588 2.49208 + endloop + endfacet + facet normal 0.286451 -0.228402 0.930472 + outer loop + vertex 1.63861 1.04756 2.49059 + vertex 1.63785 1.04364 2.48987 + vertex 1.64272 1.04895 2.48967 + endloop + endfacet + facet normal 0.284835 -0.223121 0.932248 + outer loop + vertex 1.64424 1.05401 2.49043 + vertex 1.64183 1.05488 2.49137 + vertex 1.64021 1.05121 2.49099 + endloop + endfacet + facet normal 0.284173 -0.224903 0.932021 + outer loop + vertex 1.64756 1.04884 2.48817 + vertex 1.64796 1.05373 2.48923 + vertex 1.64272 1.04895 2.48967 + endloop + endfacet + facet normal 0.283774 -0.22213 0.932808 + outer loop + vertex 1.64462 1.05719 2.49107 + vertex 1.64424 1.05401 2.49043 + vertex 1.64827 1.05844 2.49026 + endloop + endfacet + facet normal 0.281967 -0.222784 0.9332 + outer loop + vertex 1.65245 1.05382 2.48789 + vertex 1.65273 1.0586 2.48895 + vertex 1.64796 1.05373 2.48923 + endloop + endfacet + facet normal 0.28285 -0.221635 0.933206 + outer loop + vertex 1.6492 1.06225 2.49088 + vertex 1.64637 1.06009 2.49122 + vertex 1.64827 1.05844 2.49026 + endloop + endfacet + facet normal 0.282957 -0.221786 0.933138 + outer loop + vertex 1.6492 1.06225 2.49088 + vertex 1.64733 1.06398 2.49186 + vertex 1.64637 1.06009 2.49122 + endloop + endfacet + facet normal 0.284038 -0.218569 0.933568 + outer loop + vertex 1.64733 1.06398 2.49186 + vertex 1.64748 1.06876 2.49293 + vertex 1.64261 1.06373 2.49323 + endloop + endfacet + facet normal 0.285392 -0.221023 0.932577 + outer loop + vertex 1.64257 1.0588 2.49208 + vertex 1.64261 1.06373 2.49323 + vertex 1.63771 1.05864 2.49353 + endloop + endfacet + facet normal 0.286191 -0.222154 0.932063 + outer loop + vertex 1.63768 1.05346 2.4923 + vertex 1.63771 1.05864 2.49353 + vertex 1.63283 1.05362 2.49383 + endloop + endfacet + facet normal 0.287205 -0.216659 0.933044 + outer loop + vertex 1.62799 1.04877 2.49419 + vertex 1.63283 1.05362 2.49383 + vertex 1.62831 1.05357 2.49521 + endloop + endfacet + facet normal 0.287832 -0.220104 0.932044 + outer loop + vertex 1.62919 1.05733 2.49583 + vertex 1.6264 1.05521 2.49619 + vertex 1.62831 1.05357 2.49521 + endloop + endfacet + facet normal 0.289247 -0.225716 0.930262 + outer loop + vertex 1.6309 1.06016 2.49598 + vertex 1.62722 1.0589 2.49682 + vertex 1.62919 1.05733 2.49583 + endloop + endfacet + facet normal 0.287931 -0.220818 0.931845 + outer loop + vertex 1.6309 1.06016 2.49598 + vertex 1.63124 1.06331 2.49662 + vertex 1.62722 1.0589 2.49682 + endloop + endfacet + facet normal 0.287572 -0.223009 0.931434 + outer loop + vertex 1.63365 1.06243 2.49568 + vertex 1.63293 1.05854 2.49497 + vertex 1.63776 1.06385 2.49475 + endloop + endfacet + facet normal 0.285273 -0.216781 0.933609 + outer loop + vertex 1.63776 1.06385 2.49475 + vertex 1.64299 1.06868 2.49427 + vertex 1.63927 1.06897 2.49548 + endloop + endfacet + facet normal 0.285935 -0.212172 0.934465 + outer loop + vertex 1.63964 1.07218 2.49609 + vertex 1.63688 1.06985 2.49641 + vertex 1.63927 1.06897 2.49548 + endloop + endfacet + facet normal 0.28328 -0.214433 0.934757 + outer loop + vertex 1.63272 1.0684 2.49734 + vertex 1.63124 1.06331 2.49662 + vertex 1.63526 1.06613 2.49605 + endloop + endfacet + facet normal 0.284905 -0.210867 0.935075 + outer loop + vertex 1.63964 1.07218 2.49609 + vertex 1.63759 1.0738 2.49708 + vertex 1.63688 1.06985 2.49641 + endloop + endfacet + facet normal 0.285987 -0.211349 0.934635 + outer loop + vertex 1.64231 1.079 2.49681 + vertex 1.63763 1.07874 2.49819 + vertex 1.63759 1.0738 2.49708 + endloop + endfacet + facet normal 0.285007 -0.212731 0.934621 + outer loop + vertex 1.63272 1.0684 2.49734 + vertex 1.63275 1.07362 2.49852 + vertex 1.62786 1.06855 2.49886 + endloop + endfacet + facet normal 0.287531 -0.21108 0.934222 + outer loop + vertex 1.62299 1.06364 2.49925 + vertex 1.62786 1.06855 2.49886 + vertex 1.62331 1.06849 2.50024 + endloop + endfacet + facet normal 0.29017 -0.214847 0.932546 + outer loop + vertex 1.62418 1.07228 2.50085 + vertex 1.62138 1.07015 2.50123 + vertex 1.62331 1.06849 2.50024 + endloop + endfacet + facet normal 0.291791 -0.212918 0.932483 + outer loop + vertex 1.62331 1.06849 2.50024 + vertex 1.62138 1.07015 2.50123 + vertex 1.61963 1.06723 2.50111 + endloop + endfacet + facet normal 0.29064 -0.20868 0.933799 + outer loop + vertex 1.61963 1.06723 2.50111 + vertex 1.61923 1.06395 2.5005 + vertex 1.62331 1.06849 2.50024 + endloop + endfacet + facet normal 0.289967 -0.208639 0.934018 + outer loop + vertex 1.61963 1.06723 2.50111 + vertex 1.61685 1.06482 2.50143 + vertex 1.61923 1.06395 2.5005 + endloop + endfacet + facet normal 0.290438 -0.212134 0.933083 + outer loop + vertex 1.62138 1.07015 2.50123 + vertex 1.61757 1.06876 2.5021 + vertex 1.61963 1.06723 2.50111 + endloop + endfacet + facet normal 0.292691 -0.219859 0.930588 + outer loop + vertex 1.62138 1.07015 2.50123 + vertex 1.62221 1.07385 2.50184 + vertex 1.61757 1.06876 2.5021 + endloop + endfacet + facet normal 0.2938 -0.220042 0.930195 + outer loop + vertex 1.62418 1.07228 2.50085 + vertex 1.62221 1.07385 2.50184 + vertex 1.62138 1.07015 2.50123 + endloop + endfacet + facet normal 0.293502 -0.220418 0.9302 + outer loop + vertex 1.6259 1.07513 2.50098 + vertex 1.62221 1.07385 2.50184 + vertex 1.62418 1.07228 2.50085 + endloop + endfacet + facet normal 0.291955 -0.214688 0.932025 + outer loop + vertex 1.6259 1.07513 2.50098 + vertex 1.62626 1.0783 2.5016 + vertex 1.62221 1.07385 2.50184 + endloop + endfacet + facet normal 0.291556 -0.214313 0.932237 + outer loop + vertex 1.62626 1.0783 2.5016 + vertex 1.62244 1.07857 2.50285 + vertex 1.62221 1.07385 2.50184 + endloop + endfacet + facet normal 0.293379 -0.214283 0.931671 + outer loop + vertex 1.62221 1.07385 2.50184 + vertex 1.62244 1.07857 2.50285 + vertex 1.61757 1.07362 2.50325 + endloop + endfacet + facet normal 0.295887 -0.216859 0.930281 + outer loop + vertex 1.61757 1.07362 2.50325 + vertex 1.62244 1.07857 2.50285 + vertex 1.61799 1.07862 2.50428 + endloop + endfacet + facet normal 0.296926 -0.202982 0.933077 + outer loop + vertex 1.62244 1.07857 2.50285 + vertex 1.62283 1.08359 2.50382 + vertex 1.61799 1.07862 2.50428 + endloop + endfacet + facet normal 0.29606 -0.202096 0.933545 + outer loop + vertex 1.61799 1.07862 2.50428 + vertex 1.62283 1.08359 2.50382 + vertex 1.61826 1.0835 2.50525 + endloop + endfacet + facet normal 0.29634 -0.195534 0.934852 + outer loop + vertex 1.62284 1.08864 2.50487 + vertex 1.61826 1.0835 2.50525 + vertex 1.62283 1.08359 2.50382 + endloop + endfacet + facet normal 0.286804 -0.196092 0.937706 + outer loop + vertex 1.62283 1.08359 2.50382 + vertex 1.62768 1.08869 2.50341 + vertex 1.62284 1.08864 2.50487 + endloop + endfacet + facet normal 0.286659 -0.199016 0.937134 + outer loop + vertex 1.62768 1.09403 2.50454 + vertex 1.62284 1.08864 2.50487 + vertex 1.62768 1.08869 2.50341 + endloop + endfacet + facet normal 0.284396 -0.199152 0.937794 + outer loop + vertex 1.62768 1.08869 2.50341 + vertex 1.63246 1.0936 2.503 + vertex 1.62768 1.09403 2.50454 + endloop + endfacet + facet normal 0.28413 -0.200991 0.937482 + outer loop + vertex 1.63246 1.0936 2.503 + vertex 1.63295 1.09874 2.50395 + vertex 1.62768 1.09403 2.50454 + endloop + endfacet + facet normal 0.285984 -0.201058 0.936904 + outer loop + vertex 1.63246 1.0936 2.503 + vertex 1.63773 1.09834 2.5024 + vertex 1.63295 1.09874 2.50395 + endloop + endfacet + facet normal 0.283794 -0.198472 0.93812 + outer loop + vertex 1.6363 1.09311 2.50173 + vertex 1.63773 1.09834 2.5024 + vertex 1.63246 1.0936 2.503 + endloop + endfacet + facet normal 0.283902 -0.197872 0.938214 + outer loop + vertex 1.6363 1.09311 2.50173 + vertex 1.63246 1.0936 2.503 + vertex 1.63242 1.0887 2.50198 + endloop + endfacet + facet normal 0.283142 -0.197183 0.938589 + outer loop + vertex 1.63607 1.08992 2.50113 + vertex 1.6363 1.09311 2.50173 + vertex 1.63242 1.0887 2.50198 + endloop + endfacet + facet normal 0.283454 -0.198351 0.938249 + outer loop + vertex 1.63607 1.08992 2.50113 + vertex 1.63242 1.0887 2.50198 + vertex 1.6346 1.0872 2.501 + endloop + endfacet + facet normal 0.285921 -0.199625 0.937229 + outer loop + vertex 1.63816 1.08844 2.50018 + vertex 1.63607 1.08992 2.50113 + vertex 1.6346 1.0872 2.501 + endloop + endfacet + facet normal 0.282911 -0.199135 0.938246 + outer loop + vertex 1.6346 1.0872 2.501 + vertex 1.63242 1.0887 2.50198 + vertex 1.63191 1.08492 2.50133 + endloop + endfacet + facet normal 0.286947 -0.20424 0.935921 + outer loop + vertex 1.6346 1.0872 2.501 + vertex 1.63191 1.08492 2.50133 + vertex 1.63431 1.08403 2.5004 + endloop + endfacet + facet normal 0.283568 -0.199188 0.938037 + outer loop + vertex 1.63191 1.08492 2.50133 + vertex 1.63242 1.0887 2.50198 + vertex 1.62773 1.08344 2.50228 + endloop + endfacet + facet normal 0.28537 -0.205526 0.936121 + outer loop + vertex 1.63191 1.08492 2.50133 + vertex 1.62773 1.08344 2.50228 + vertex 1.63032 1.08118 2.50099 + endloop + endfacet + facet normal 0.28535 -0.205549 0.936122 + outer loop + vertex 1.62773 1.08344 2.50228 + vertex 1.62626 1.0783 2.5016 + vertex 1.63032 1.08118 2.50099 + endloop + endfacet + facet normal 0.283128 -0.198782 0.938256 + outer loop + vertex 1.63242 1.0887 2.50198 + vertex 1.62768 1.08869 2.50341 + vertex 1.62773 1.08344 2.50228 + endloop + endfacet + facet normal 0.284178 -0.197197 0.938273 + outer loop + vertex 1.63873 1.0922 2.50081 + vertex 1.6363 1.09311 2.50173 + vertex 1.63607 1.08992 2.50113 + endloop + endfacet + facet normal 0.286016 -0.199491 0.937229 + outer loop + vertex 1.63873 1.0922 2.50081 + vertex 1.63607 1.08992 2.50113 + vertex 1.63816 1.08844 2.50018 + endloop + endfacet + facet normal 0.28417 -0.197219 0.938271 + outer loop + vertex 1.64028 1.09597 2.50113 + vertex 1.6363 1.09311 2.50173 + vertex 1.63873 1.0922 2.50081 + endloop + endfacet + facet normal 0.282323 -0.196516 0.938976 + outer loop + vertex 1.63873 1.0922 2.50081 + vertex 1.64279 1.09369 2.4999 + vertex 1.64028 1.09597 2.50113 + endloop + endfacet + facet normal 0.281944 -0.196946 0.938999 + outer loop + vertex 1.64279 1.09369 2.4999 + vertex 1.6443 1.09889 2.50053 + vertex 1.64028 1.09597 2.50113 + endloop + endfacet + facet normal 0.281791 -0.196716 0.939094 + outer loop + vertex 1.6443 1.09889 2.50053 + vertex 1.6419 1.09979 2.50144 + vertex 1.64028 1.09597 2.50113 + endloop + endfacet + facet normal 0.285695 -0.198248 0.937591 + outer loop + vertex 1.6419 1.09979 2.50144 + vertex 1.63773 1.09834 2.5024 + vertex 1.64028 1.09597 2.50113 + endloop + endfacet + facet normal 0.286413 -0.200829 0.936822 + outer loop + vertex 1.6419 1.09979 2.50144 + vertex 1.64258 1.10376 2.50208 + vertex 1.63773 1.09834 2.5024 + endloop + endfacet + facet normal 0.286672 -0.201068 0.936692 + outer loop + vertex 1.64258 1.10376 2.50208 + vertex 1.63773 1.10365 2.50354 + vertex 1.63773 1.09834 2.5024 + endloop + endfacet + facet normal 0.285203 -0.198795 0.937625 + outer loop + vertex 1.63773 1.09834 2.5024 + vertex 1.6363 1.09311 2.50173 + vertex 1.64028 1.09597 2.50113 + endloop + endfacet + facet normal 0.283177 -0.19791 0.938426 + outer loop + vertex 1.63242 1.0887 2.50198 + vertex 1.63246 1.0936 2.503 + vertex 1.62768 1.08869 2.50341 + endloop + endfacet + facet normal 0.28558 -0.198013 0.937675 + outer loop + vertex 1.62354 1.09265 2.50551 + vertex 1.62284 1.08864 2.50487 + vertex 1.62768 1.09403 2.50454 + endloop + endfacet + facet normal 0.287299 -0.204541 0.935747 + outer loop + vertex 1.62354 1.09265 2.50551 + vertex 1.62768 1.09403 2.50454 + vertex 1.62515 1.09641 2.50584 + endloop + endfacet + facet normal 0.297629 -0.208599 0.931614 + outer loop + vertex 1.62515 1.09641 2.50584 + vertex 1.62111 1.09348 2.50647 + vertex 1.62354 1.09265 2.50551 + endloop + endfacet + facet normal 0.298058 -0.207475 0.931727 + outer loop + vertex 1.62354 1.09265 2.50551 + vertex 1.62111 1.09348 2.50647 + vertex 1.62077 1.0903 2.50587 + endloop + endfacet + facet normal 0.302933 -0.207692 0.930105 + outer loop + vertex 1.62077 1.0903 2.50587 + vertex 1.62111 1.09348 2.50647 + vertex 1.6171 1.08891 2.50675 + endloop + endfacet + facet normal 0.300599 -0.199987 0.932548 + outer loop + vertex 1.62077 1.0903 2.50587 + vertex 1.6171 1.08891 2.50675 + vertex 1.61907 1.08737 2.50579 + endloop + endfacet + facet normal 0.293327 -0.195871 0.935732 + outer loop + vertex 1.62284 1.08864 2.50487 + vertex 1.62077 1.0903 2.50587 + vertex 1.61907 1.08737 2.50579 + endloop + endfacet + facet normal 0.3009 -0.205845 0.931175 + outer loop + vertex 1.62111 1.09348 2.50647 + vertex 1.6173 1.0936 2.50773 + vertex 1.6171 1.08891 2.50675 + endloop + endfacet + facet normal 0.300877 -0.206088 0.931129 + outer loop + vertex 1.62111 1.09348 2.50647 + vertex 1.62257 1.09859 2.50713 + vertex 1.6173 1.0936 2.50773 + endloop + endfacet + facet normal 0.29771 -0.202526 0.932926 + outer loop + vertex 1.6173 1.0936 2.50773 + vertex 1.62257 1.09859 2.50713 + vertex 1.61768 1.09862 2.50869 + endloop + endfacet + facet normal 0.295067 -0.204702 0.933291 + outer loop + vertex 1.62257 1.09859 2.50713 + vertex 1.62111 1.09348 2.50647 + vertex 1.62515 1.09641 2.50584 + endloop + endfacet + facet normal 0.293925 -0.206085 0.933347 + outer loop + vertex 1.62671 1.10014 2.50617 + vertex 1.62257 1.09859 2.50713 + vertex 1.62515 1.09641 2.50584 + endloop + endfacet + facet normal 0.287852 -0.203746 0.93575 + outer loop + vertex 1.62915 1.09925 2.50522 + vertex 1.62671 1.10014 2.50617 + vertex 1.62515 1.09641 2.50584 + endloop + endfacet + facet normal 0.292218 -0.200411 0.935117 + outer loop + vertex 1.62671 1.10014 2.50617 + vertex 1.62724 1.10385 2.5068 + vertex 1.62257 1.09859 2.50713 + endloop + endfacet + facet normal 0.288626 -0.197106 0.936933 + outer loop + vertex 1.62724 1.10385 2.5068 + vertex 1.62261 1.10374 2.5082 + vertex 1.62257 1.09859 2.50713 + endloop + endfacet + facet normal 0.287922 -0.203855 0.935705 + outer loop + vertex 1.62768 1.09403 2.50454 + vertex 1.62915 1.09925 2.50522 + vertex 1.62515 1.09641 2.50584 + endloop + endfacet + facet normal 0.29113 -0.198684 0.935825 + outer loop + vertex 1.62354 1.09265 2.50551 + vertex 1.62077 1.0903 2.50587 + vertex 1.62284 1.08864 2.50487 + endloop + endfacet + facet normal 0.28908 -0.198353 0.93653 + outer loop + vertex 1.62773 1.08344 2.50228 + vertex 1.62768 1.08869 2.50341 + vertex 1.62283 1.08359 2.50382 + endloop + endfacet + facet normal 0.292206 -0.191695 0.936947 + outer loop + vertex 1.61907 1.08737 2.50579 + vertex 1.61826 1.0835 2.50525 + vertex 1.62284 1.08864 2.50487 + endloop + endfacet + facet normal 0.288678 -0.202858 0.935689 + outer loop + vertex 1.62244 1.07857 2.50285 + vertex 1.62773 1.08344 2.50228 + vertex 1.62283 1.08359 2.50382 + endloop + endfacet + facet normal 0.292486 -0.207243 0.933543 + outer loop + vertex 1.62626 1.0783 2.5016 + vertex 1.62773 1.08344 2.50228 + vertex 1.62244 1.07857 2.50285 + endloop + endfacet + facet normal 0.28964 -0.216288 0.932378 + outer loop + vertex 1.62869 1.07743 2.50064 + vertex 1.62795 1.07351 2.49997 + vertex 1.63281 1.07887 2.4997 + endloop + endfacet + facet normal 0.286281 -0.205882 0.935765 + outer loop + vertex 1.63431 1.08403 2.5004 + vertex 1.63191 1.08492 2.50133 + vertex 1.63032 1.08118 2.50099 + endloop + endfacet + facet normal 0.287543 -0.210124 0.934434 + outer loop + vertex 1.63763 1.07874 2.49819 + vertex 1.63799 1.08369 2.49919 + vertex 1.63281 1.07887 2.4997 + endloop + endfacet + facet normal 0.287209 -0.204248 0.935838 + outer loop + vertex 1.6346 1.0872 2.501 + vertex 1.63431 1.08403 2.5004 + vertex 1.63816 1.08844 2.50018 + endloop + endfacet + facet normal 0.285458 -0.206417 0.935899 + outer loop + vertex 1.64244 1.08376 2.49785 + vertex 1.64266 1.08858 2.49884 + vertex 1.63799 1.08369 2.49919 + endloop + endfacet + facet normal 0.283133 -0.199217 0.938162 + outer loop + vertex 1.63873 1.0922 2.50081 + vertex 1.63816 1.08844 2.50018 + vertex 1.64279 1.09369 2.4999 + endloop + endfacet + facet normal 0.280846 -0.202812 0.938079 + outer loop + vertex 1.64717 1.08866 2.49751 + vertex 1.64757 1.09356 2.49845 + vertex 1.64266 1.08858 2.49884 + endloop + endfacet + facet normal 0.277087 -0.195743 0.940695 + outer loop + vertex 1.64279 1.09369 2.4999 + vertex 1.648 1.09856 2.49937 + vertex 1.6443 1.09889 2.50053 + endloop + endfacet + facet normal 0.277065 -0.195899 0.940669 + outer loop + vertex 1.64828 1.1034 2.5003 + vertex 1.6443 1.09889 2.50053 + vertex 1.648 1.09856 2.49937 + endloop + endfacet + facet normal 0.278167 -0.1969 0.940135 + outer loop + vertex 1.64468 1.10216 2.5011 + vertex 1.6443 1.09889 2.50053 + vertex 1.64828 1.1034 2.5003 + endloop + endfacet + facet normal 0.27853 -0.198204 0.939753 + outer loop + vertex 1.64828 1.1034 2.5003 + vertex 1.64637 1.10506 2.50122 + vertex 1.64468 1.10216 2.5011 + endloop + endfacet + facet normal 0.28391 -0.201246 0.937494 + outer loop + vertex 1.64637 1.10506 2.50122 + vertex 1.64258 1.10376 2.50208 + vertex 1.64468 1.10216 2.5011 + endloop + endfacet + facet normal 0.284405 -0.200593 0.937484 + outer loop + vertex 1.64468 1.10216 2.5011 + vertex 1.64258 1.10376 2.50208 + vertex 1.6419 1.09979 2.50144 + endloop + endfacet + facet normal 0.283449 -0.199575 0.937991 + outer loop + vertex 1.64637 1.10506 2.50122 + vertex 1.64714 1.10882 2.50178 + vertex 1.64258 1.10376 2.50208 + endloop + endfacet + facet normal 0.284158 -0.200234 0.937636 + outer loop + vertex 1.64714 1.10882 2.50178 + vertex 1.64255 1.10871 2.50315 + vertex 1.64258 1.10376 2.50208 + endloop + endfacet + facet normal 0.284274 -0.196922 0.938301 + outer loop + vertex 1.64714 1.10882 2.50178 + vertex 1.64731 1.11359 2.50273 + vertex 1.64255 1.10871 2.50315 + endloop + endfacet + facet normal 0.282961 -0.196953 0.938692 + outer loop + vertex 1.65111 1.11331 2.50153 + vertex 1.64731 1.11359 2.50273 + vertex 1.64714 1.10882 2.50178 + endloop + endfacet + facet normal 0.280077 -0.194322 0.940104 + outer loop + vertex 1.65079 1.11009 2.50096 + vertex 1.65111 1.11331 2.50153 + vertex 1.64714 1.10882 2.50178 + endloop + endfacet + facet normal 0.281031 -0.197718 0.939111 + outer loop + vertex 1.65079 1.11009 2.50096 + vertex 1.64714 1.10882 2.50178 + vertex 1.64911 1.10719 2.50085 + endloop + endfacet + facet normal 0.279761 -0.197001 0.939641 + outer loop + vertex 1.65283 1.10847 2.50001 + vertex 1.65079 1.11009 2.50096 + vertex 1.64911 1.10719 2.50085 + endloop + endfacet + facet normal 0.279996 -0.197847 0.939393 + outer loop + vertex 1.64911 1.10719 2.50085 + vertex 1.64828 1.1034 2.5003 + vertex 1.65283 1.10847 2.50001 + endloop + endfacet + facet normal 0.276459 -0.194582 0.941121 + outer loop + vertex 1.65283 1.10847 2.50001 + vertex 1.64828 1.1034 2.5003 + vertex 1.65272 1.10351 2.49902 + endloop + endfacet + facet normal 0.283424 -0.193368 0.939297 + outer loop + vertex 1.65111 1.11331 2.50153 + vertex 1.65252 1.11846 2.50216 + vertex 1.64731 1.11359 2.50273 + endloop + endfacet + facet normal 0.284917 -0.195062 0.938495 + outer loop + vertex 1.64731 1.11359 2.50273 + vertex 1.65252 1.11846 2.50216 + vertex 1.64765 1.11862 2.50367 + endloop + endfacet + facet normal 0.284336 -0.195055 0.938673 + outer loop + vertex 1.64731 1.11359 2.50273 + vertex 1.64765 1.11862 2.50367 + vertex 1.64288 1.11373 2.5041 + endloop + endfacet + facet normal 0.279961 -0.199036 0.939152 + outer loop + vertex 1.64911 1.10719 2.50085 + vertex 1.64714 1.10882 2.50178 + vertex 1.64637 1.10506 2.50122 + endloop + endfacet + facet normal 0.278981 -0.197675 0.939731 + outer loop + vertex 1.64911 1.10719 2.50085 + vertex 1.64637 1.10506 2.50122 + vertex 1.64828 1.1034 2.5003 + endloop + endfacet + facet normal 0.281629 -0.197113 0.939059 + outer loop + vertex 1.64468 1.10216 2.5011 + vertex 1.6419 1.09979 2.50144 + vertex 1.6443 1.09889 2.50053 + endloop + endfacet + facet normal 0.277358 -0.19909 0.939913 + outer loop + vertex 1.65243 1.09355 2.49701 + vertex 1.65249 1.09857 2.49806 + vertex 1.64757 1.09356 2.49845 + endloop + endfacet + facet normal 0.276416 -0.195897 0.940861 + outer loop + vertex 1.648 1.09856 2.49937 + vertex 1.65272 1.10351 2.49902 + vertex 1.64828 1.1034 2.5003 + endloop + endfacet + facet normal 0.277452 -0.19558 0.940621 + outer loop + vertex 1.65713 1.09885 2.49675 + vertex 1.65723 1.10355 2.4977 + vertex 1.65249 1.09857 2.49806 + endloop + endfacet + facet normal 0.280177 -0.192554 0.940438 + outer loop + vertex 1.66103 1.10333 2.49652 + vertex 1.66245 1.10848 2.49715 + vertex 1.65723 1.10355 2.4977 + endloop + endfacet + facet normal 0.283179 -0.189761 0.940107 + outer loop + vertex 1.66714 1.11385 2.49682 + vertex 1.66247 1.1137 2.4982 + vertex 1.66245 1.10848 2.49715 + endloop + endfacet + facet normal 0.279238 -0.194482 0.940321 + outer loop + vertex 1.65272 1.10351 2.49902 + vertex 1.65756 1.1086 2.49863 + vertex 1.65283 1.10847 2.50001 + endloop + endfacet + facet normal 0.283477 -0.193381 0.939279 + outer loop + vertex 1.65252 1.11846 2.50216 + vertex 1.65111 1.11331 2.50153 + vertex 1.65513 1.11626 2.50092 + endloop + endfacet + facet normal 0.286978 -0.192828 0.938329 + outer loop + vertex 1.65936 1.12236 2.50088 + vertex 1.65718 1.12376 2.50183 + vertex 1.65667 1.12003 2.50122 + endloop + endfacet + facet normal 0.286627 -0.192375 0.938529 + outer loop + vertex 1.66107 1.12822 2.50156 + vertex 1.65729 1.12852 2.50278 + vertex 1.65718 1.12376 2.50183 + endloop + endfacet + facet normal 0.287057 -0.189111 0.939061 + outer loop + vertex 1.66107 1.12822 2.50156 + vertex 1.66251 1.13341 2.50216 + vertex 1.65729 1.12852 2.50278 + endloop + endfacet + facet normal 0.284868 -0.186628 0.940224 + outer loop + vertex 1.65729 1.12852 2.50278 + vertex 1.66251 1.13341 2.50216 + vertex 1.65763 1.1336 2.50368 + endloop + endfacet + facet normal 0.285034 -0.193754 0.938731 + outer loop + vertex 1.65252 1.11846 2.50216 + vertex 1.65253 1.12362 2.50323 + vertex 1.64765 1.11862 2.50367 + endloop + endfacet + facet normal 0.282704 -0.193388 0.93951 + outer loop + vertex 1.64288 1.11373 2.5041 + vertex 1.64765 1.11862 2.50367 + vertex 1.64304 1.11859 2.50505 + endloop + endfacet + facet normal 0.277824 -0.190424 0.941569 + outer loop + vertex 1.64362 1.12239 2.50566 + vertex 1.64117 1.12321 2.50655 + vertex 1.64091 1.12008 2.50599 + endloop + endfacet + facet normal 0.280318 -0.190491 0.940816 + outer loop + vertex 1.64091 1.12008 2.50599 + vertex 1.64117 1.12321 2.50655 + vertex 1.63725 1.11874 2.50681 + endloop + endfacet + facet normal 0.278734 -0.189059 0.941575 + outer loop + vertex 1.64117 1.12321 2.50655 + vertex 1.63736 1.12351 2.50774 + vertex 1.63725 1.11874 2.50681 + endloop + endfacet + facet normal 0.281987 -0.190407 0.940334 + outer loop + vertex 1.63942 1.11733 2.50588 + vertex 1.6367 1.11497 2.50622 + vertex 1.63914 1.11412 2.50531 + endloop + endfacet + facet normal 0.283385 -0.193371 0.939309 + outer loop + vertex 1.64304 1.11859 2.50505 + vertex 1.63914 1.11412 2.50531 + vertex 1.64288 1.11373 2.5041 + endloop + endfacet + facet normal 0.284181 -0.196827 0.93835 + outer loop + vertex 1.64255 1.10871 2.50315 + vertex 1.64731 1.11359 2.50273 + vertex 1.64288 1.11373 2.5041 + endloop + endfacet + facet normal 0.286709 -0.200057 0.936897 + outer loop + vertex 1.64258 1.10376 2.50208 + vertex 1.64255 1.10871 2.50315 + vertex 1.63773 1.10365 2.50354 + endloop + endfacet + facet normal 0.287675 -0.199245 0.936774 + outer loop + vertex 1.63356 1.10742 2.50563 + vertex 1.63303 1.10363 2.50498 + vertex 1.63769 1.1089 2.50467 + endloop + endfacet + facet normal 0.28773 -0.19925 0.936755 + outer loop + vertex 1.63356 1.10742 2.50563 + vertex 1.63087 1.10512 2.50597 + vertex 1.63303 1.10363 2.50498 + endloop + endfacet + facet normal 0.285977 -0.201111 0.936894 + outer loop + vertex 1.63773 1.09834 2.5024 + vertex 1.63773 1.10365 2.50354 + vertex 1.63295 1.09874 2.50395 + endloop + endfacet + facet normal 0.286203 -0.203454 0.93632 + outer loop + vertex 1.62768 1.09403 2.50454 + vertex 1.63295 1.09874 2.50395 + vertex 1.62915 1.09925 2.50522 + endloop + endfacet + facet normal 0.287986 -0.203413 0.935782 + outer loop + vertex 1.6294 1.10241 2.50583 + vertex 1.62671 1.10014 2.50617 + vertex 1.62915 1.09925 2.50522 + endloop + endfacet + facet normal 0.28512 -0.199791 0.937438 + outer loop + vertex 1.6294 1.10241 2.50583 + vertex 1.62724 1.10385 2.5068 + vertex 1.62671 1.10014 2.50617 + endloop + endfacet + facet normal 0.283032 -0.193348 0.93942 + outer loop + vertex 1.63356 1.10742 2.50563 + vertex 1.63112 1.10826 2.50654 + vertex 1.63087 1.10512 2.50597 + endloop + endfacet + facet normal 0.288784 -0.192661 0.937809 + outer loop + vertex 1.62724 1.10385 2.5068 + vertex 1.62736 1.10859 2.50773 + vertex 1.62261 1.10374 2.5082 + endloop + endfacet + facet normal 0.282114 -0.189939 0.940391 + outer loop + vertex 1.63254 1.11342 2.50715 + vertex 1.63112 1.10826 2.50654 + vertex 1.63512 1.11118 2.50592 + endloop + endfacet + facet normal 0.28165 -0.189215 0.940676 + outer loop + vertex 1.63725 1.11874 2.50681 + vertex 1.63257 1.11861 2.50819 + vertex 1.63254 1.11342 2.50715 + endloop + endfacet + facet normal 0.284173 -0.189391 0.939881 + outer loop + vertex 1.62774 1.11887 2.5097 + vertex 1.63291 1.12368 2.5091 + vertex 1.62917 1.12409 2.51032 + endloop + endfacet + facet normal 0.281657 -0.18896 0.940725 + outer loop + vertex 1.63725 1.11874 2.50681 + vertex 1.63736 1.12351 2.50774 + vertex 1.63257 1.11861 2.50819 + endloop + endfacet + facet normal 0.278937 -0.18749 0.941829 + outer loop + vertex 1.64117 1.12321 2.50655 + vertex 1.64258 1.12837 2.50716 + vertex 1.63736 1.12351 2.50774 + endloop + endfacet + facet normal 0.278886 -0.182971 0.942732 + outer loop + vertex 1.64726 1.13371 2.50681 + vertex 1.64257 1.1336 2.50818 + vertex 1.64258 1.12837 2.50716 + endloop + endfacet + facet normal 0.279055 -0.177215 0.943781 + outer loop + vertex 1.64726 1.13371 2.50681 + vertex 1.64731 1.13852 2.5077 + vertex 1.64257 1.1336 2.50818 + endloop + endfacet + facet normal 0.282111 -0.177081 0.942898 + outer loop + vertex 1.6511 1.13822 2.50651 + vertex 1.64731 1.13852 2.5077 + vertex 1.64726 1.13371 2.50681 + endloop + endfacet + facet normal 0.282345 -0.175229 0.943174 + outer loop + vertex 1.6511 1.13822 2.50651 + vertex 1.65234 1.14329 2.50708 + vertex 1.64731 1.13852 2.5077 + endloop + endfacet + facet normal 0.285583 -0.178868 0.941514 + outer loop + vertex 1.64731 1.13852 2.5077 + vertex 1.65234 1.14329 2.50708 + vertex 1.64761 1.1436 2.50857 + endloop + endfacet + facet normal 0.282861 -0.188458 0.940464 + outer loop + vertex 1.63291 1.12368 2.5091 + vertex 1.63768 1.12857 2.50865 + vertex 1.63305 1.12856 2.51004 + endloop + endfacet + facet normal 0.279671 -0.180213 0.943031 + outer loop + vertex 1.63671 1.13995 2.5112 + vertex 1.63724 1.14377 2.51177 + vertex 1.63254 1.13838 2.51213 + endloop + endfacet + facet normal 0.278149 -0.178837 0.943743 + outer loop + vertex 1.63724 1.14377 2.51177 + vertex 1.63254 1.14363 2.51313 + vertex 1.63254 1.13838 2.51213 + endloop + endfacet + facet normal 0.278332 -0.170809 0.945175 + outer loop + vertex 1.63724 1.14377 2.51177 + vertex 1.63729 1.14857 2.51262 + vertex 1.63254 1.14363 2.51313 + endloop + endfacet + facet normal 0.278109 -0.170818 0.945239 + outer loop + vertex 1.64109 1.14832 2.51146 + vertex 1.63729 1.14857 2.51262 + vertex 1.63724 1.14377 2.51177 + endloop + endfacet + facet normal 0.279645 -0.18021 0.943039 + outer loop + vertex 1.63942 1.14234 2.51085 + vertex 1.63724 1.14377 2.51177 + vertex 1.63671 1.13995 2.5112 + endloop + endfacet + facet normal 0.283792 -0.186949 0.940485 + outer loop + vertex 1.63514 1.13614 2.51092 + vertex 1.63114 1.1332 2.51154 + vertex 1.63359 1.13237 2.51064 + endloop + endfacet + facet normal 0.28385 -0.186791 0.940499 + outer loop + vertex 1.63359 1.13237 2.51064 + vertex 1.63114 1.1332 2.51154 + vertex 1.6309 1.13005 2.51099 + endloop + endfacet + facet normal 0.284648 -0.187782 0.94006 + outer loop + vertex 1.63359 1.13237 2.51064 + vertex 1.6309 1.13005 2.51099 + vertex 1.63305 1.12856 2.51004 + endloop + endfacet + facet normal 0.28433 -0.188416 0.94003 + outer loop + vertex 1.63305 1.12856 2.51004 + vertex 1.62917 1.12409 2.51032 + vertex 1.63291 1.12368 2.5091 + endloop + endfacet + facet normal 0.284904 -0.187643 0.940011 + outer loop + vertex 1.62943 1.1273 2.51088 + vertex 1.62726 1.12873 2.51183 + vertex 1.62674 1.12496 2.51123 + endloop + endfacet + facet normal 0.287451 -0.187867 0.93919 + outer loop + vertex 1.62674 1.12496 2.51123 + vertex 1.62726 1.12873 2.51183 + vertex 1.6226 1.12341 2.51219 + endloop + endfacet + facet normal 0.295242 -0.190245 0.93629 + outer loop + vertex 1.6212 1.11825 2.51158 + vertex 1.6226 1.12341 2.51219 + vertex 1.61742 1.11852 2.51283 + endloop + endfacet + facet normal 0.295119 -0.191234 0.936127 + outer loop + vertex 1.6212 1.11825 2.51158 + vertex 1.61742 1.11852 2.51283 + vertex 1.61733 1.11375 2.51188 + endloop + endfacet + facet normal 0.296157 -0.192163 0.935609 + outer loop + vertex 1.62096 1.11511 2.51101 + vertex 1.6212 1.11825 2.51158 + vertex 1.61733 1.11375 2.51188 + endloop + endfacet + facet normal 0.286517 -0.189936 0.939059 + outer loop + vertex 1.62774 1.11887 2.5097 + vertex 1.62917 1.12409 2.51032 + vertex 1.62518 1.12118 2.51094 + endloop + endfacet + facet normal 0.28558 -0.189926 0.939347 + outer loop + vertex 1.62774 1.11887 2.5097 + vertex 1.6231 1.11362 2.51005 + vertex 1.62769 1.11362 2.50865 + endloop + endfacet + facet normal 0.291041 -0.19207 0.937232 + outer loop + vertex 1.62364 1.11742 2.51065 + vertex 1.6212 1.11825 2.51158 + vertex 1.62096 1.11511 2.51101 + endloop + endfacet + facet normal 0.296786 -0.194254 0.934978 + outer loop + vertex 1.62096 1.11511 2.51101 + vertex 1.61733 1.11375 2.51188 + vertex 1.6195 1.11237 2.51091 + endloop + endfacet + facet normal 0.296072 -0.186803 0.936721 + outer loop + vertex 1.61924 1.10919 2.51034 + vertex 1.61681 1.11001 2.51127 + vertex 1.61528 1.10621 2.511 + endloop + endfacet + facet normal 0.28971 -0.189326 0.938203 + outer loop + vertex 1.6231 1.11362 2.51005 + vertex 1.61924 1.10919 2.51034 + vertex 1.62296 1.10878 2.50911 + endloop + endfacet + facet normal 0.28616 -0.189967 0.939162 + outer loop + vertex 1.62261 1.10374 2.5082 + vertex 1.62736 1.10859 2.50773 + vertex 1.62296 1.10878 2.50911 + endloop + endfacet + facet normal 0.298111 -0.196584 0.934069 + outer loop + vertex 1.62257 1.09859 2.50713 + vertex 1.62261 1.10374 2.5082 + vertex 1.61768 1.09862 2.50869 + endloop + endfacet + facet normal 0.302005 -0.194624 0.933228 + outer loop + vertex 1.61372 1.10237 2.51075 + vertex 1.61295 1.09834 2.51016 + vertex 1.61779 1.10393 2.50975 + endloop + endfacet + facet normal 0.288897 -0.202397 0.935721 + outer loop + vertex 1.6173 1.0936 2.50773 + vertex 1.61768 1.09862 2.50869 + vertex 1.61271 1.09335 2.50909 + endloop + endfacet + facet normal 0.310969 -0.25417 0.915804 + outer loop + vertex 1.60932 1.097 2.51101 + vertex 1.60805 1.09308 2.51036 + vertex 1.61295 1.09834 2.51016 + endloop + endfacet + facet normal 0.288787 -0.212613 0.933487 + outer loop + vertex 1.61249 1.08847 2.50805 + vertex 1.6173 1.0936 2.50773 + vertex 1.61271 1.09335 2.50909 + endloop + endfacet + facet normal 0.282203 -0.206233 0.936925 + outer loop + vertex 1.6171 1.08891 2.50675 + vertex 1.6173 1.0936 2.50773 + vertex 1.61249 1.08847 2.50805 + endloop + endfacet + facet normal 0.301977 -0.198193 0.932486 + outer loop + vertex 1.61907 1.08737 2.50579 + vertex 1.6171 1.08891 2.50675 + vertex 1.61631 1.08515 2.50621 + endloop + endfacet + facet normal 0.297869 -0.192607 0.934974 + outer loop + vertex 1.61907 1.08737 2.50579 + vertex 1.61631 1.08515 2.50621 + vertex 1.61826 1.0835 2.50525 + endloop + endfacet + facet normal 0.304144 -0.202036 0.930955 + outer loop + vertex 1.61826 1.0835 2.50525 + vertex 1.61428 1.07893 2.50556 + vertex 1.61799 1.07862 2.50428 + endloop + endfacet + facet normal 0.299162 -0.235514 0.924681 + outer loop + vertex 1.61266 1.07376 2.50476 + vertex 1.61799 1.07862 2.50428 + vertex 1.61428 1.07893 2.50556 + endloop + endfacet + facet normal 0.270001 -0.181795 0.945542 + outer loop + vertex 1.61463 1.08218 2.50614 + vertex 1.61257 1.08371 2.50702 + vertex 1.61195 1.07982 2.50645 + endloop + endfacet + facet normal 0.198308 -0.173166 0.964721 + outer loop + vertex 1.61195 1.07982 2.50645 + vertex 1.61257 1.08371 2.50702 + vertex 1.60809 1.07857 2.50702 + endloop + endfacet + facet normal 0.287774 -0.232633 0.929015 + outer loop + vertex 1.61266 1.07376 2.50476 + vertex 1.61428 1.07893 2.50556 + vertex 1.61042 1.07625 2.50608 + endloop + endfacet + facet normal 0.139263 -0.288281 0.947365 + outer loop + vertex 1.60852 1.07273 2.50563 + vertex 1.60489 1.07136 2.50575 + vertex 1.60737 1.06849 2.50451 + endloop + endfacet + facet normal 0.282771 -0.216624 0.934406 + outer loop + vertex 1.61757 1.07362 2.50325 + vertex 1.61799 1.07862 2.50428 + vertex 1.61266 1.07376 2.50476 + endloop + endfacet + facet normal 0.293265 -0.220396 0.93028 + outer loop + vertex 1.62221 1.07385 2.50184 + vertex 1.61757 1.07362 2.50325 + vertex 1.61757 1.06876 2.5021 + endloop + endfacet + facet normal 0.291566 -0.210608 0.933077 + outer loop + vertex 1.61963 1.06723 2.50111 + vertex 1.61757 1.06876 2.5021 + vertex 1.61685 1.06482 2.50143 + endloop + endfacet + facet normal 0.289526 -0.209731 0.93391 + outer loop + vertex 1.61923 1.06395 2.5005 + vertex 1.61685 1.06482 2.50143 + vertex 1.61522 1.06103 2.50109 + endloop + endfacet + facet normal 0.293235 -0.211083 0.932447 + outer loop + vertex 1.62331 1.06849 2.50024 + vertex 1.61923 1.06395 2.5005 + vertex 1.62299 1.06364 2.49925 + endloop + endfacet + facet normal 0.289753 -0.216086 0.932389 + outer loop + vertex 1.62258 1.05866 2.49822 + vertex 1.62745 1.06359 2.49785 + vertex 1.62299 1.06364 2.49925 + endloop + endfacet + facet normal 0.280458 -0.222784 0.933654 + outer loop + vertex 1.62256 1.0538 2.49707 + vertex 1.62258 1.05866 2.49822 + vertex 1.61762 1.05351 2.49848 + endloop + endfacet + facet normal 0.306254 -0.285628 0.908089 + outer loop + vertex 1.61352 1.05731 2.50073 + vertex 1.61259 1.05352 2.49985 + vertex 1.61765 1.0587 2.49977 + endloop + endfacet + facet normal 0.280464 -0.222096 0.933817 + outer loop + vertex 1.62256 1.0538 2.49707 + vertex 1.61762 1.05351 2.49848 + vertex 1.61772 1.04839 2.49724 + endloop + endfacet + facet normal 0.258652 -0.209259 0.943032 + outer loop + vertex 1.61772 1.04839 2.49724 + vertex 1.61635 1.04346 2.49652 + vertex 1.6202 1.04608 2.49604 + endloop + endfacet + facet normal 0.245093 -0.220973 0.943981 + outer loop + vertex 1.61854 1.04232 2.49568 + vertex 1.61635 1.04346 2.49652 + vertex 1.61588 1.04032 2.4959 + endloop + endfacet + facet normal 0.279213 -0.268993 0.921783 + outer loop + vertex 1.61854 1.04232 2.49568 + vertex 1.61588 1.04032 2.4959 + vertex 1.61767 1.03847 2.49482 + endloop + endfacet + facet normal 0.107229 -0.306545 0.945797 + outer loop + vertex 1.61382 1.0378 2.49556 + vertex 1.61009 1.03695 2.49571 + vertex 1.61243 1.03379 2.49442 + endloop + endfacet + facet normal 0.241736 -0.232148 0.942163 + outer loop + vertex 1.62269 1.0337 2.49219 + vertex 1.62262 1.03865 2.49343 + vertex 1.61778 1.03352 2.49341 + endloop + endfacet + facet normal 0.280711 -0.215508 0.935285 + outer loop + vertex 1.62468 1.03206 2.49121 + vertex 1.62269 1.0337 2.49219 + vertex 1.62197 1.02976 2.4915 + endloop + endfacet + facet normal 0.285611 -0.238783 0.928121 + outer loop + vertex 1.62426 1.02886 2.49056 + vertex 1.62197 1.02976 2.4915 + vertex 1.62039 1.02623 2.49108 + endloop + endfacet + facet normal 0.304652 -0.229942 0.924291 + outer loop + vertex 1.62833 1.03338 2.49035 + vertex 1.62426 1.02886 2.49056 + vertex 1.62796 1.02865 2.48929 + endloop + endfacet + facet normal 0.298367 -0.236973 0.924565 + outer loop + vertex 1.62756 1.0238 2.48818 + vertex 1.63247 1.02887 2.48789 + vertex 1.62796 1.02865 2.48929 + endloop + endfacet + facet normal 0.269712 -0.235398 0.933725 + outer loop + vertex 1.62748 1.01899 2.48699 + vertex 1.62756 1.0238 2.48818 + vertex 1.62267 1.01867 2.4883 + endloop + endfacet + facet normal 0.275124 -0.322176 0.90582 + outer loop + vertex 1.61848 1.02274 2.49059 + vertex 1.6174 1.01859 2.48944 + vertex 1.62263 1.02379 2.4897 + endloop + endfacet + facet normal 0.269709 -0.227432 0.935698 + outer loop + vertex 1.62748 1.01899 2.48699 + vertex 1.62267 1.01867 2.4883 + vertex 1.6228 1.01388 2.48709 + endloop + endfacet + facet normal 0.256252 -0.214989 0.942398 + outer loop + vertex 1.62644 1.01499 2.48636 + vertex 1.62748 1.01899 2.48699 + vertex 1.6228 1.01388 2.48709 + endloop + endfacet + facet normal 0.299217 -0.233775 0.925104 + outer loop + vertex 1.6323 1.02425 2.48676 + vertex 1.62756 1.0238 2.48818 + vertex 1.62748 1.01899 2.48699 + endloop + endfacet + facet normal 0.298314 -0.243778 0.922812 + outer loop + vertex 1.63611 1.02559 2.48588 + vertex 1.637 1.02922 2.48655 + vertex 1.6323 1.02425 2.48676 + endloop + endfacet + facet normal 0.286051 -0.241567 0.927265 + outer loop + vertex 1.63894 1.02766 2.48555 + vertex 1.637 1.02922 2.48655 + vertex 1.63611 1.02559 2.48588 + endloop + endfacet + facet normal 0.297386 -0.230547 0.926504 + outer loop + vertex 1.63415 1.02259 2.48572 + vertex 1.63126 1.02038 2.4861 + vertex 1.63305 1.01855 2.48507 + endloop + endfacet + facet normal 0.29646 -0.238156 0.924875 + outer loop + vertex 1.63766 1.01355 2.48232 + vertex 1.6378 1.01872 2.48361 + vertex 1.63277 1.01353 2.48389 + endloop + endfacet + facet normal 0.296232 -0.241289 0.924135 + outer loop + vertex 1.63229 1.00867 2.48277 + vertex 1.63766 1.01355 2.48232 + vertex 1.63277 1.01353 2.48389 + endloop + endfacet + facet normal 0.299669 -0.245271 0.921976 + outer loop + vertex 1.63609 1.00856 2.48151 + vertex 1.63766 1.01355 2.48232 + vertex 1.63229 1.00867 2.48277 + endloop + endfacet + facet normal 0.300133 -0.240846 0.922991 + outer loop + vertex 1.63609 1.00856 2.48151 + vertex 1.63229 1.00867 2.48277 + vertex 1.63203 1.00416 2.48168 + endloop + endfacet + facet normal 0.28163 -0.241152 0.928725 + outer loop + vertex 1.63203 1.00416 2.48168 + vertex 1.63229 1.00867 2.48277 + vertex 1.62752 1.00372 2.48293 + endloop + endfacet + facet normal 0.287315 -0.23861 0.92764 + outer loop + vertex 1.64264 1.01888 2.48216 + vertex 1.6378 1.01872 2.48361 + vertex 1.63766 1.01355 2.48232 + endloop + endfacet + facet normal 0.290415 -0.241556 0.92591 + outer loop + vertex 1.64187 1.01498 2.48138 + vertex 1.64264 1.01888 2.48216 + vertex 1.63766 1.01355 2.48232 + endloop + endfacet + facet normal 0.291753 -0.246655 0.924144 + outer loop + vertex 1.64187 1.01498 2.48138 + vertex 1.63766 1.01355 2.48232 + vertex 1.64019 1.01135 2.48094 + endloop + endfacet + facet normal 0.284618 -0.240809 0.927903 + outer loop + vertex 1.64467 1.01721 2.4811 + vertex 1.64264 1.01888 2.48216 + vertex 1.64187 1.01498 2.48138 + endloop + endfacet + facet normal 0.287306 -0.244404 0.926133 + outer loop + vertex 1.64467 1.01721 2.4811 + vertex 1.64187 1.01498 2.48138 + vertex 1.64426 1.01409 2.4804 + endloop + endfacet + facet normal 0.287913 -0.24444 0.925935 + outer loop + vertex 1.64467 1.01721 2.4811 + vertex 1.64426 1.01409 2.4804 + vertex 1.64831 1.0184 2.48028 + endloop + endfacet + facet normal 0.28712 -0.241266 0.927013 + outer loop + vertex 1.64831 1.0184 2.48028 + vertex 1.64643 1.02007 2.4813 + vertex 1.64467 1.01721 2.4811 + endloop + endfacet + facet normal 0.28518 -0.240128 0.927907 + outer loop + vertex 1.64643 1.02007 2.4813 + vertex 1.64264 1.01888 2.48216 + vertex 1.64467 1.01721 2.4811 + endloop + endfacet + facet normal 0.284638 -0.237847 0.92866 + outer loop + vertex 1.64643 1.02007 2.4813 + vertex 1.64744 1.02402 2.482 + vertex 1.64264 1.01888 2.48216 + endloop + endfacet + facet normal 0.284847 -0.238046 0.928545 + outer loop + vertex 1.64744 1.02402 2.482 + vertex 1.64269 1.02388 2.48342 + vertex 1.64264 1.01888 2.48216 + endloop + endfacet + facet normal 0.287344 -0.237889 0.927816 + outer loop + vertex 1.64264 1.01888 2.48216 + vertex 1.64269 1.02388 2.48342 + vertex 1.6378 1.01872 2.48361 + endloop + endfacet + facet normal 0.304554 -0.237104 0.922512 + outer loop + vertex 1.62928 1.01725 2.48598 + vertex 1.62812 1.0132 2.48532 + vertex 1.63305 1.01855 2.48507 + endloop + endfacet + facet normal 0.289376 -0.241128 0.926347 + outer loop + vertex 1.63229 1.00867 2.48277 + vertex 1.63277 1.01353 2.48389 + vertex 1.62774 1.00836 2.48411 + endloop + endfacet + facet normal 0.318886 -0.299837 0.899116 + outer loop + vertex 1.62444 1.0119 2.48619 + vertex 1.62309 1.00801 2.48537 + vertex 1.62812 1.0132 2.48532 + endloop + endfacet + facet normal 0.289318 -0.248713 0.924358 + outer loop + vertex 1.62752 1.00372 2.48293 + vertex 1.63229 1.00867 2.48277 + vertex 1.62774 1.00836 2.48411 + endloop + endfacet + facet normal 0.281457 -0.234195 0.930556 + outer loop + vertex 1.63203 1.00416 2.48168 + vertex 1.62752 1.00372 2.48293 + vertex 1.62746 0.999256 2.48183 + endloop + endfacet + facet normal 0.277631 -0.230575 0.932607 + outer loop + vertex 1.63111 1.00045 2.48104 + vertex 1.63203 1.00416 2.48168 + vertex 1.62746 0.999256 2.48183 + endloop + endfacet + facet normal 0.305355 -0.245784 0.919972 + outer loop + vertex 1.63571 1.00549 2.48081 + vertex 1.63609 1.00856 2.48151 + vertex 1.63203 1.00416 2.48168 + endloop + endfacet + facet normal 0.294149 -0.243882 0.92412 + outer loop + vertex 1.63766 1.01355 2.48232 + vertex 1.63609 1.00856 2.48151 + vertex 1.64019 1.01135 2.48094 + endloop + endfacet + facet normal 0.287155 -0.244759 0.926086 + outer loop + vertex 1.64426 1.01409 2.4804 + vertex 1.64187 1.01498 2.48138 + vertex 1.64019 1.01135 2.48094 + endloop + endfacet + facet normal 0.288081 -0.244601 0.92584 + outer loop + vertex 1.64831 1.0184 2.48028 + vertex 1.64426 1.01409 2.4804 + vertex 1.64796 1.01378 2.47917 + endloop + endfacet + facet normal 0.288408 -0.246101 0.925341 + outer loop + vertex 1.6475 1.00903 2.47805 + vertex 1.65234 1.01375 2.47779 + vertex 1.64796 1.01378 2.47917 + endloop + endfacet + facet normal 0.288498 -0.24502 0.925599 + outer loop + vertex 1.65234 1.01375 2.47779 + vertex 1.65283 1.01853 2.47891 + vertex 1.64796 1.01378 2.47917 + endloop + endfacet + facet normal 0.287825 -0.245002 0.925813 + outer loop + vertex 1.65234 1.01375 2.47779 + vertex 1.65767 1.01845 2.47738 + vertex 1.65283 1.01853 2.47891 + endloop + endfacet + facet normal 0.289561 -0.247061 0.924724 + outer loop + vertex 1.65609 1.01349 2.47655 + vertex 1.65767 1.01845 2.47738 + vertex 1.65234 1.01375 2.47779 + endloop + endfacet + facet normal 0.289802 -0.245359 0.925102 + outer loop + vertex 1.65609 1.01349 2.47655 + vertex 1.65234 1.01375 2.47779 + vertex 1.65204 1.0092 2.47668 + endloop + endfacet + facet normal 0.287727 -0.24538 0.925744 + outer loop + vertex 1.65204 1.0092 2.47668 + vertex 1.65234 1.01375 2.47779 + vertex 1.6475 1.00903 2.47805 + endloop + endfacet + facet normal 0.287679 -0.246586 0.925438 + outer loop + vertex 1.65204 1.0092 2.47668 + vertex 1.6475 1.00903 2.47805 + vertex 1.64733 1.00429 2.47684 + endloop + endfacet + facet normal 0.287896 -0.246577 0.925373 + outer loop + vertex 1.64733 1.00429 2.47684 + vertex 1.6475 1.00903 2.47805 + vertex 1.64259 1.00408 2.47826 + endloop + endfacet + facet normal 0.287644 -0.240679 0.927003 + outer loop + vertex 1.63852 1.00775 2.4805 + vertex 1.63775 1.00386 2.47973 + vertex 1.64269 1.00913 2.47957 + endloop + endfacet + facet normal 0.297013 -0.249765 0.921629 + outer loop + vertex 1.64246 0.999192 2.47698 + vertex 1.64259 1.00408 2.47826 + vertex 1.6377 0.998919 2.47843 + endloop + endfacet + facet normal 0.296955 -0.252188 0.920988 + outer loop + vertex 1.64246 0.999192 2.47698 + vertex 1.6377 0.998919 2.47843 + vertex 1.63757 0.994019 2.47713 + endloop + endfacet + facet normal 0.302027 -0.243626 0.921643 + outer loop + vertex 1.63394 1.00261 2.48065 + vertex 1.63293 0.998638 2.47993 + vertex 1.63775 1.00386 2.47973 + endloop + endfacet + facet normal 0.299235 -0.252059 0.920285 + outer loop + vertex 1.63757 0.994019 2.47713 + vertex 1.6377 0.998919 2.47843 + vertex 1.6328 0.993674 2.47859 + endloop + endfacet + facet normal 0.299255 -0.25013 0.920805 + outer loop + vertex 1.63757 0.994019 2.47713 + vertex 1.6328 0.993674 2.47859 + vertex 1.63272 0.988782 2.47729 + endloop + endfacet + facet normal 0.317734 -0.287821 0.90344 + outer loop + vertex 1.62915 0.997403 2.48087 + vertex 1.62795 0.993418 2.48002 + vertex 1.63293 0.998638 2.47993 + endloop + endfacet + facet normal 0.258475 -0.252587 0.932411 + outer loop + vertex 1.63272 0.988782 2.47729 + vertex 1.6328 0.993674 2.47859 + vertex 1.62789 0.988513 2.47855 + endloop + endfacet + facet normal 0.259578 -0.348994 0.900457 + outer loop + vertex 1.62404 0.992569 2.48082 + vertex 1.62259 0.988442 2.47964 + vertex 1.62795 0.993418 2.48002 + endloop + endfacet + facet normal 0.258514 -0.249784 0.933155 + outer loop + vertex 1.63272 0.988782 2.47729 + vertex 1.62789 0.988513 2.47855 + vertex 1.62798 0.983781 2.47726 + endloop + endfacet + facet normal 0.236098 -0.228561 0.944467 + outer loop + vertex 1.63166 0.984801 2.47659 + vertex 1.63272 0.988782 2.47729 + vertex 1.62798 0.983781 2.47726 + endloop + endfacet + facet normal 0.297588 -0.248558 0.92177 + outer loop + vertex 1.6365 0.990075 2.47642 + vertex 1.63757 0.994019 2.47713 + vertex 1.63272 0.988782 2.47729 + endloop + endfacet + facet normal 0.30169 -0.256741 0.918187 + outer loop + vertex 1.64137 0.995263 2.47623 + vertex 1.64246 0.999192 2.47698 + vertex 1.63757 0.994019 2.47713 + endloop + endfacet + facet normal 0.287774 -0.250249 0.924425 + outer loop + vertex 1.64733 1.00429 2.47684 + vertex 1.64259 1.00408 2.47826 + vertex 1.64246 0.999192 2.47698 + endloop + endfacet + facet normal 0.28506 -0.244027 0.926926 + outer loop + vertex 1.65113 1.0055 2.47599 + vertex 1.65204 1.0092 2.47668 + vertex 1.64733 1.00429 2.47684 + endloop + endfacet + facet normal 0.288136 -0.244577 0.925829 + outer loop + vertex 1.65396 1.00759 2.47566 + vertex 1.65204 1.0092 2.47668 + vertex 1.65113 1.0055 2.47599 + endloop + endfacet + facet normal 0.285508 -0.251771 0.924714 + outer loop + vertex 1.64918 1.00251 2.47579 + vertex 1.64628 1.00039 2.47611 + vertex 1.64808 0.998544 2.47505 + endloop + endfacet + facet normal 0.283904 -0.248946 0.925972 + outer loop + vertex 1.65274 0.993766 2.47233 + vertex 1.65282 0.998713 2.47363 + vertex 1.6479 0.9936 2.47377 + endloop + endfacet + facet normal 0.283758 -0.252367 0.925091 + outer loop + vertex 1.65274 0.993766 2.47233 + vertex 1.6479 0.9936 2.47377 + vertex 1.64775 0.988521 2.47243 + endloop + endfacet + facet normal 0.283698 -0.252309 0.925125 + outer loop + vertex 1.65196 0.989894 2.47151 + vertex 1.65274 0.993766 2.47233 + vertex 1.64775 0.988521 2.47243 + endloop + endfacet + facet normal 0.285914 -0.261214 0.921965 + outer loop + vertex 1.65196 0.989894 2.47151 + vertex 1.64775 0.988521 2.47243 + vertex 1.65025 0.986308 2.47102 + endloop + endfacet + facet normal 0.287752 -0.26198 0.921176 + outer loop + vertex 1.65433 0.989008 2.47052 + vertex 1.65196 0.989894 2.47151 + vertex 1.65025 0.986308 2.47102 + endloop + endfacet + facet normal 0.288299 -0.262887 0.920747 + outer loop + vertex 1.65271 0.984099 2.46962 + vertex 1.65433 0.989008 2.47052 + vertex 1.65025 0.986308 2.47102 + endloop + endfacet + facet normal 0.287046 -0.264278 0.92074 + outer loop + vertex 1.64856 0.982749 2.47053 + vertex 1.65271 0.984099 2.46962 + vertex 1.65025 0.986308 2.47102 + endloop + endfacet + facet normal 0.290961 -0.265903 0.919041 + outer loop + vertex 1.65025 0.986308 2.47102 + vertex 1.64615 0.983613 2.47154 + vertex 1.64856 0.982749 2.47053 + endloop + endfacet + facet normal 0.291492 -0.26465 0.919235 + outer loop + vertex 1.64856 0.982749 2.47053 + vertex 1.64615 0.983613 2.47154 + vertex 1.64575 0.980573 2.4708 + endloop + endfacet + facet normal 0.288238 -0.260159 0.92154 + outer loop + vertex 1.64856 0.982749 2.47053 + vertex 1.64575 0.980573 2.4708 + vertex 1.64776 0.978928 2.4697 + endloop + endfacet + facet normal 0.291491 -0.25623 0.921618 + outer loop + vertex 1.64776 0.978928 2.4697 + vertex 1.64575 0.980573 2.4708 + vertex 1.64396 0.977771 2.47058 + endloop + endfacet + facet normal 0.290478 -0.251707 0.923183 + outer loop + vertex 1.64396 0.977771 2.47058 + vertex 1.6429 0.973843 2.46984 + vertex 1.64776 0.978928 2.4697 + endloop + endfacet + facet normal 0.297609 -0.258633 0.918988 + outer loop + vertex 1.64776 0.978928 2.4697 + vertex 1.6429 0.973843 2.46984 + vertex 1.64764 0.974047 2.46837 + endloop + endfacet + facet normal 0.287649 -0.259209 0.921992 + outer loop + vertex 1.64764 0.974047 2.46837 + vertex 1.65255 0.97909 2.46825 + vertex 1.64776 0.978928 2.4697 + endloop + endfacet + facet normal 0.287546 -0.261391 0.921408 + outer loop + vertex 1.65271 0.984099 2.46962 + vertex 1.64776 0.978928 2.4697 + vertex 1.65255 0.97909 2.46825 + endloop + endfacet + facet normal 0.287764 -0.26138 0.921343 + outer loop + vertex 1.65255 0.97909 2.46825 + vertex 1.65751 0.984051 2.46811 + vertex 1.65271 0.984099 2.46962 + endloop + endfacet + facet normal 0.287894 -0.259946 0.921708 + outer loop + vertex 1.65751 0.984051 2.46811 + vertex 1.65801 0.988761 2.46928 + vertex 1.65271 0.984099 2.46962 + endloop + endfacet + facet normal 0.289318 -0.259982 0.921252 + outer loop + vertex 1.65751 0.984051 2.46811 + vertex 1.66245 0.988939 2.46794 + vertex 1.65801 0.988761 2.46928 + endloop + endfacet + facet normal 0.289481 -0.255986 0.922319 + outer loop + vertex 1.66245 0.988939 2.46794 + vertex 1.66282 0.993546 2.4691 + vertex 1.65801 0.988761 2.46928 + endloop + endfacet + facet normal 0.287039 -0.255986 0.923082 + outer loop + vertex 1.66245 0.988939 2.46794 + vertex 1.66729 0.993728 2.46776 + vertex 1.66282 0.993546 2.4691 + endloop + endfacet + facet normal 0.287161 -0.252823 0.923915 + outer loop + vertex 1.66729 0.993728 2.46776 + vertex 1.66778 0.998494 2.46892 + vertex 1.66282 0.993546 2.4691 + endloop + endfacet + facet normal 0.286829 -0.252482 0.924111 + outer loop + vertex 1.66282 0.993546 2.4691 + vertex 1.66778 0.998494 2.46892 + vertex 1.66313 0.998256 2.47029 + endloop + endfacet + facet normal 0.29167 -0.252426 0.92261 + outer loop + vertex 1.66313 0.998256 2.47029 + vertex 1.6584 0.993301 2.47043 + vertex 1.66282 0.993546 2.4691 + endloop + endfacet + facet normal 0.291526 -0.258087 0.921088 + outer loop + vertex 1.65801 0.988761 2.46928 + vertex 1.66282 0.993546 2.4691 + vertex 1.6584 0.993301 2.47043 + endloop + endfacet + facet normal 0.291765 -0.258088 0.921012 + outer loop + vertex 1.6584 0.993301 2.47043 + vertex 1.65433 0.989008 2.47052 + vertex 1.65801 0.988761 2.46928 + endloop + endfacet + facet normal 0.293573 -0.259821 0.91995 + outer loop + vertex 1.65477 0.992105 2.47125 + vertex 1.65433 0.989008 2.47052 + vertex 1.6584 0.993301 2.47043 + endloop + endfacet + facet normal 0.29194 -0.25327 0.922293 + outer loop + vertex 1.6584 0.993301 2.47043 + vertex 1.65655 0.994941 2.47147 + vertex 1.65477 0.992105 2.47125 + endloop + endfacet + facet normal 0.285698 -0.249586 0.925248 + outer loop + vertex 1.65655 0.994941 2.47147 + vertex 1.65274 0.993766 2.47233 + vertex 1.65477 0.992105 2.47125 + endloop + endfacet + facet normal 0.285069 -0.246875 0.926169 + outer loop + vertex 1.65655 0.994941 2.47147 + vertex 1.65756 0.998873 2.47221 + vertex 1.65274 0.993766 2.47233 + endloop + endfacet + facet normal 0.290022 -0.247816 0.924378 + outer loop + vertex 1.65938 0.997026 2.47114 + vertex 1.65756 0.998873 2.47221 + vertex 1.65655 0.994941 2.47147 + endloop + endfacet + facet normal 0.289877 -0.247963 0.924384 + outer loop + vertex 1.66135 1.00004 2.47133 + vertex 1.65756 0.998873 2.47221 + vertex 1.65938 0.997026 2.47114 + endloop + endfacet + facet normal 0.290051 -0.248071 0.9243 + outer loop + vertex 1.66313 0.998256 2.47029 + vertex 1.66135 1.00004 2.47133 + vertex 1.65938 0.997026 2.47114 + endloop + endfacet + facet normal 0.288842 -0.249302 0.924348 + outer loop + vertex 1.66425 1.00219 2.471 + vertex 1.66135 1.00004 2.47133 + vertex 1.66313 0.998256 2.47029 + endloop + endfacet + facet normal 0.284675 -0.24839 0.925885 + outer loop + vertex 1.66425 1.00219 2.471 + vertex 1.66313 0.998256 2.47029 + vertex 1.66806 1.00339 2.47016 + endloop + endfacet + facet normal 0.284817 -0.248983 0.925682 + outer loop + vertex 1.66806 1.00339 2.47016 + vertex 1.66627 1.00523 2.4712 + vertex 1.66425 1.00219 2.471 + endloop + endfacet + facet normal 0.287363 -0.250585 0.924462 + outer loop + vertex 1.66627 1.00523 2.4712 + vertex 1.66244 1.00403 2.47207 + vertex 1.66425 1.00219 2.471 + endloop + endfacet + facet normal 0.287219 -0.24998 0.92467 + outer loop + vertex 1.66627 1.00523 2.4712 + vertex 1.66735 1.00917 2.47193 + vertex 1.66244 1.00403 2.47207 + endloop + endfacet + facet normal 0.288761 -0.249184 0.924405 + outer loop + vertex 1.66425 1.00219 2.471 + vertex 1.66244 1.00403 2.47207 + vertex 1.66135 1.00004 2.47133 + endloop + endfacet + facet normal 0.290228 -0.249486 0.923864 + outer loop + vertex 1.66135 1.00004 2.47133 + vertex 1.66244 1.00403 2.47207 + vertex 1.65756 0.998873 2.47221 + endloop + endfacet + facet normal 0.288242 -0.247577 0.924998 + outer loop + vertex 1.66244 1.00403 2.47207 + vertex 1.6577 1.00384 2.47349 + vertex 1.65756 0.998873 2.47221 + endloop + endfacet + facet normal 0.287081 -0.247635 0.925344 + outer loop + vertex 1.65756 0.998873 2.47221 + vertex 1.6577 1.00384 2.47349 + vertex 1.65282 0.998713 2.47363 + endloop + endfacet + facet normal 0.292952 -0.252126 0.922286 + outer loop + vertex 1.65938 0.997026 2.47114 + vertex 1.65655 0.994941 2.47147 + vertex 1.6584 0.993301 2.47043 + endloop + endfacet + facet normal 0.290964 -0.25174 0.923021 + outer loop + vertex 1.65938 0.997026 2.47114 + vertex 1.6584 0.993301 2.47043 + vertex 1.66313 0.998256 2.47029 + endloop + endfacet + facet normal 0.286881 -0.250541 0.924624 + outer loop + vertex 1.66806 1.00339 2.47016 + vertex 1.66313 0.998256 2.47029 + vertex 1.66778 0.998494 2.46892 + endloop + endfacet + facet normal 0.283619 -0.252731 0.925034 + outer loop + vertex 1.66729 0.993728 2.46776 + vertex 1.67267 0.998466 2.46741 + vertex 1.66778 0.998494 2.46892 + endloop + endfacet + facet normal 0.286617 -0.255549 0.923334 + outer loop + vertex 1.66697 0.989261 2.46663 + vertex 1.66729 0.993728 2.46776 + vertex 1.66245 0.988939 2.46794 + endloop + endfacet + facet normal 0.286596 -0.257882 0.922691 + outer loop + vertex 1.66697 0.989261 2.46663 + vertex 1.66245 0.988939 2.46794 + vertex 1.66219 0.984354 2.46674 + endloop + endfacet + facet normal 0.287267 -0.257867 0.922487 + outer loop + vertex 1.66219 0.984354 2.46674 + vertex 1.66245 0.988939 2.46794 + vertex 1.65751 0.984051 2.46811 + endloop + endfacet + facet normal 0.286158 -0.259744 0.922305 + outer loop + vertex 1.65727 0.97929 2.46685 + vertex 1.65751 0.984051 2.46811 + vertex 1.65255 0.97909 2.46825 + endloop + endfacet + facet normal 0.286083 -0.261692 0.921778 + outer loop + vertex 1.65727 0.97929 2.46685 + vertex 1.65255 0.97909 2.46825 + vertex 1.65236 0.974243 2.46694 + endloop + endfacet + facet normal 0.289994 -0.261522 0.920603 + outer loop + vertex 1.65236 0.974243 2.46694 + vertex 1.65255 0.97909 2.46825 + vertex 1.64764 0.974047 2.46837 + endloop + endfacet + facet normal 0.28988 -0.264275 0.919852 + outer loop + vertex 1.65236 0.974243 2.46694 + vertex 1.64764 0.974047 2.46837 + vertex 1.64746 0.969198 2.46703 + endloop + endfacet + facet normal 0.300816 -0.263762 0.916482 + outer loop + vertex 1.64746 0.969198 2.46703 + vertex 1.64764 0.974047 2.46837 + vertex 1.6427 0.968902 2.46851 + endloop + endfacet + facet normal 0.300753 -0.266289 0.915772 + outer loop + vertex 1.64746 0.969198 2.46703 + vertex 1.6427 0.968902 2.46851 + vertex 1.64251 0.964049 2.46716 + endloop + endfacet + facet normal 0.29855 -0.266395 0.916462 + outer loop + vertex 1.64251 0.964049 2.46716 + vertex 1.6427 0.968902 2.46851 + vertex 1.63775 0.963686 2.4686 + endloop + endfacet + facet normal 0.306595 -0.274128 0.911511 + outer loop + vertex 1.63775 0.963686 2.4686 + vertex 1.6427 0.968902 2.46851 + vertex 1.63792 0.968569 2.47002 + endloop + endfacet + facet normal 0.306881 -0.260135 0.915507 + outer loop + vertex 1.6429 0.973843 2.46984 + vertex 1.63792 0.968569 2.47002 + vertex 1.6427 0.968902 2.46851 + endloop + endfacet + facet normal 0.309358 -0.262523 0.913991 + outer loop + vertex 1.63906 0.972593 2.47078 + vertex 1.63792 0.968569 2.47002 + vertex 1.6429 0.973843 2.46984 + endloop + endfacet + facet normal 0.306497 -0.250467 0.918328 + outer loop + vertex 1.6429 0.973843 2.46984 + vertex 1.64107 0.975656 2.47095 + vertex 1.63906 0.972593 2.47078 + endloop + endfacet + facet normal 0.301273 -0.247179 0.920944 + outer loop + vertex 1.64107 0.975656 2.47095 + vertex 1.63724 0.97427 2.47183 + vertex 1.63906 0.972593 2.47078 + endloop + endfacet + facet normal 0.30092 -0.247569 0.920954 + outer loop + vertex 1.63906 0.972593 2.47078 + vertex 1.63724 0.97427 2.47183 + vertex 1.63612 0.970372 2.47115 + endloop + endfacet + facet normal 0.260675 -0.238609 0.935476 + outer loop + vertex 1.63612 0.970372 2.47115 + vertex 1.63724 0.97427 2.47183 + vertex 1.63242 0.969228 2.47189 + endloop + endfacet + facet normal 0.261373 -0.241471 0.934546 + outer loop + vertex 1.63612 0.970372 2.47115 + vertex 1.63242 0.969228 2.47189 + vertex 1.63408 0.967308 2.47093 + endloop + endfacet + facet normal 0.30544 -0.269287 0.913341 + outer loop + vertex 1.63792 0.968569 2.47002 + vertex 1.63612 0.970372 2.47115 + vertex 1.63408 0.967308 2.47093 + endloop + endfacet + facet normal 0.315213 -0.311182 0.896553 + outer loop + vertex 1.63408 0.967308 2.47093 + vertex 1.63293 0.963439 2.46999 + vertex 1.63792 0.968569 2.47002 + endloop + endfacet + facet normal 0.304205 -0.25776 0.917071 + outer loop + vertex 1.64107 0.975656 2.47095 + vertex 1.64203 0.979314 2.47166 + vertex 1.63724 0.97427 2.47183 + endloop + endfacet + facet normal 0.299484 -0.253178 0.919897 + outer loop + vertex 1.64203 0.979314 2.47166 + vertex 1.63746 0.978839 2.47302 + vertex 1.63724 0.97427 2.47183 + endloop + endfacet + facet normal 0.270339 -0.254047 0.928643 + outer loop + vertex 1.63724 0.97427 2.47183 + vertex 1.63746 0.978839 2.47302 + vertex 1.63256 0.973746 2.47305 + endloop + endfacet + facet normal 0.299604 -0.259412 0.918119 + outer loop + vertex 1.64203 0.979314 2.47166 + vertex 1.64236 0.983786 2.47282 + vertex 1.63746 0.978839 2.47302 + endloop + endfacet + facet normal 0.297255 -0.257029 0.919552 + outer loop + vertex 1.63746 0.978839 2.47302 + vertex 1.64236 0.983786 2.47282 + vertex 1.63783 0.983492 2.4742 + endloop + endfacet + facet normal 0.296664 -0.259444 0.919064 + outer loop + vertex 1.64615 0.983613 2.47154 + vertex 1.64236 0.983786 2.47282 + vertex 1.64203 0.979314 2.47166 + endloop + endfacet + facet normal 0.296337 -0.262018 0.91844 + outer loop + vertex 1.64615 0.983613 2.47154 + vertex 1.64775 0.988521 2.47243 + vertex 1.64236 0.983786 2.47282 + endloop + endfacet + facet normal 0.289294 -0.253621 0.923031 + outer loop + vertex 1.64236 0.983786 2.47282 + vertex 1.64775 0.988521 2.47243 + vertex 1.64287 0.98856 2.47397 + endloop + endfacet + facet normal 0.305514 -0.258005 0.916567 + outer loop + vertex 1.64396 0.977771 2.47058 + vertex 1.64203 0.979314 2.47166 + vertex 1.64107 0.975656 2.47095 + endloop + endfacet + facet normal 0.311601 -0.262988 0.913095 + outer loop + vertex 1.63906 0.972593 2.47078 + vertex 1.63612 0.970372 2.47115 + vertex 1.63792 0.968569 2.47002 + endloop + endfacet + facet normal 0.297531 -0.260556 0.91847 + outer loop + vertex 1.6427 0.968902 2.46851 + vertex 1.64764 0.974047 2.46837 + vertex 1.6429 0.973843 2.46984 + endloop + endfacet + facet normal 0.302937 -0.254161 0.918494 + outer loop + vertex 1.64396 0.977771 2.47058 + vertex 1.64107 0.975656 2.47095 + vertex 1.6429 0.973843 2.46984 + endloop + endfacet + facet normal 0.301887 -0.262482 0.916498 + outer loop + vertex 1.64575 0.980573 2.4708 + vertex 1.64203 0.979314 2.47166 + vertex 1.64396 0.977771 2.47058 + endloop + endfacet + facet normal 0.302574 -0.265202 0.915487 + outer loop + vertex 1.64575 0.980573 2.4708 + vertex 1.64615 0.983613 2.47154 + vertex 1.64203 0.979314 2.47166 + endloop + endfacet + facet normal 0.285955 -0.259853 0.922337 + outer loop + vertex 1.64856 0.982749 2.47053 + vertex 1.64776 0.978928 2.4697 + vertex 1.65271 0.984099 2.46962 + endloop + endfacet + facet normal 0.29096 -0.263575 0.919712 + outer loop + vertex 1.65271 0.984099 2.46962 + vertex 1.65801 0.988761 2.46928 + vertex 1.65433 0.989008 2.47052 + endloop + endfacet + facet normal 0.288822 -0.25952 0.921537 + outer loop + vertex 1.65477 0.992105 2.47125 + vertex 1.65196 0.989894 2.47151 + vertex 1.65433 0.989008 2.47052 + endloop + endfacet + facet normal 0.287258 -0.2597 0.921976 + outer loop + vertex 1.64775 0.988521 2.47243 + vertex 1.64615 0.983613 2.47154 + vertex 1.65025 0.986308 2.47102 + endloop + endfacet + facet normal 0.28347 -0.252279 0.925203 + outer loop + vertex 1.65477 0.992105 2.47125 + vertex 1.65274 0.993766 2.47233 + vertex 1.65196 0.989894 2.47151 + endloop + endfacet + facet normal 0.287032 -0.248754 0.925059 + outer loop + vertex 1.65756 0.998873 2.47221 + vertex 1.65282 0.998713 2.47363 + vertex 1.65274 0.993766 2.47233 + endloop + endfacet + facet normal 0.283641 -0.248738 0.926109 + outer loop + vertex 1.64427 0.997373 2.4759 + vertex 1.64315 0.993436 2.47519 + vertex 1.64808 0.998544 2.47505 + endloop + endfacet + facet normal 0.289425 -0.252087 0.92341 + outer loop + vertex 1.64775 0.988521 2.47243 + vertex 1.6479 0.9936 2.47377 + vertex 1.64287 0.98856 2.47397 + endloop + endfacet + facet normal 0.288975 -0.241983 0.926249 + outer loop + vertex 1.63938 0.99224 2.47605 + vertex 1.63822 0.988288 2.47538 + vertex 1.64315 0.993436 2.47519 + endloop + endfacet + facet normal 0.297312 -0.253845 0.920417 + outer loop + vertex 1.64236 0.983786 2.47282 + vertex 1.64287 0.98856 2.47397 + vertex 1.63783 0.983492 2.4742 + endloop + endfacet + facet normal 0.307909 -0.261221 0.914853 + outer loop + vertex 1.6345 0.986987 2.47626 + vertex 1.63328 0.983046 2.47555 + vertex 1.63822 0.988288 2.47538 + endloop + endfacet + facet normal 0.281164 -0.257033 0.924598 + outer loop + vertex 1.63746 0.978839 2.47302 + vertex 1.63783 0.983492 2.4742 + vertex 1.63283 0.978331 2.47429 + endloop + endfacet + facet normal 0.308499 -0.327986 0.89289 + outer loop + vertex 1.62961 0.98178 2.47635 + vertex 1.62819 0.977991 2.47545 + vertex 1.63328 0.983046 2.47555 + endloop + endfacet + facet normal 0.281395 -0.264729 0.922353 + outer loop + vertex 1.63256 0.973746 2.47305 + vertex 1.63746 0.978839 2.47302 + vertex 1.63283 0.978331 2.47429 + endloop + endfacet + facet normal 0.270091 -0.247661 0.930438 + outer loop + vertex 1.63724 0.97427 2.47183 + vertex 1.63256 0.973746 2.47305 + vertex 1.63242 0.969228 2.47189 + endloop + endfacet + facet normal 0.246389 -0.254727 0.935097 + outer loop + vertex 1.63408 0.967308 2.47093 + vertex 1.63242 0.969228 2.47189 + vertex 1.63126 0.965412 2.47116 + endloop + endfacet + facet normal 0.277207 -0.303523 0.911609 + outer loop + vertex 1.63408 0.967308 2.47093 + vertex 1.63126 0.965412 2.47116 + vertex 1.63293 0.963439 2.46999 + endloop + endfacet + facet normal 0.114078 -0.337247 0.934479 + outer loop + vertex 1.62902 0.962666 2.47071 + vertex 1.62519 0.961514 2.47076 + vertex 1.62792 0.958668 2.46941 + endloop + endfacet + facet normal 0.278505 -0.275598 0.920044 + outer loop + vertex 1.63792 0.968569 2.47002 + vertex 1.63293 0.963439 2.46999 + vertex 1.63775 0.963686 2.4686 + endloop + endfacet + facet normal 0.298553 -0.266109 0.916544 + outer loop + vertex 1.64251 0.964049 2.46716 + vertex 1.63775 0.963686 2.4686 + vertex 1.63759 0.958846 2.46725 + endloop + endfacet + facet normal 0.290681 -0.258581 0.921217 + outer loop + vertex 1.64139 0.960103 2.46641 + vertex 1.64251 0.964049 2.46716 + vertex 1.63759 0.958846 2.46725 + endloop + endfacet + facet normal 0.304481 -0.269924 0.913473 + outer loop + vertex 1.64635 0.965318 2.46625 + vertex 1.64746 0.969198 2.46703 + vertex 1.64251 0.964049 2.46716 + endloop + endfacet + facet normal 0.292404 -0.266757 0.918336 + outer loop + vertex 1.65127 0.97036 2.46616 + vertex 1.65236 0.974243 2.46694 + vertex 1.64746 0.969198 2.46703 + endloop + endfacet + facet normal 0.285205 -0.260829 0.922294 + outer loop + vertex 1.65616 0.975394 2.46609 + vertex 1.65727 0.97929 2.46685 + vertex 1.65236 0.974243 2.46694 + endloop + endfacet + facet normal 0.287237 -0.259713 0.921978 + outer loop + vertex 1.66219 0.984354 2.46674 + vertex 1.65751 0.984051 2.46811 + vertex 1.65727 0.97929 2.46685 + endloop + endfacet + facet normal 0.286984 -0.258265 0.922464 + outer loop + vertex 1.66601 0.985631 2.46591 + vertex 1.66697 0.989261 2.46663 + vertex 1.66219 0.984354 2.46674 + endloop + endfacet + facet normal 0.285465 -0.257974 0.923017 + outer loop + vertex 1.66889 0.987701 2.4656 + vertex 1.66697 0.989261 2.46663 + vertex 1.66601 0.985631 2.46591 + endloop + endfacet + facet normal 0.284979 -0.258561 0.923002 + outer loop + vertex 1.67068 0.990491 2.46583 + vertex 1.66697 0.989261 2.46663 + vertex 1.66889 0.987701 2.4656 + endloop + endfacet + facet normal 0.285246 -0.258722 0.922875 + outer loop + vertex 1.6727 0.988867 2.46474 + vertex 1.67068 0.990491 2.46583 + vertex 1.66889 0.987701 2.4656 + endloop + endfacet + facet normal 0.285608 -0.260318 0.922314 + outer loop + vertex 1.66889 0.987701 2.4656 + vertex 1.66785 0.983842 2.46483 + vertex 1.6727 0.988867 2.46474 + endloop + endfacet + facet normal 0.28432 -0.255972 0.923926 + outer loop + vertex 1.67068 0.990491 2.46583 + vertex 1.67108 0.993537 2.46655 + vertex 1.66697 0.989261 2.46663 + endloop + endfacet + facet normal 0.283903 -0.255567 0.924167 + outer loop + vertex 1.67108 0.993537 2.46655 + vertex 1.66729 0.993728 2.46776 + vertex 1.66697 0.989261 2.46663 + endloop + endfacet + facet normal 0.287242 -0.260638 0.921716 + outer loop + vertex 1.66889 0.987701 2.4656 + vertex 1.66601 0.985631 2.46591 + vertex 1.66785 0.983842 2.46483 + endloop + endfacet + facet normal 0.289923 -0.262609 0.920316 + outer loop + vertex 1.66402 0.982655 2.46569 + vertex 1.66109 0.980516 2.46601 + vertex 1.66292 0.978722 2.46492 + endloop + endfacet + facet normal 0.293711 -0.269181 0.917211 + outer loop + vertex 1.66746 0.974127 2.46213 + vertex 1.66766 0.978968 2.46349 + vertex 1.66273 0.973863 2.46357 + endloop + endfacet + facet normal 0.290911 -0.266225 0.918964 + outer loop + vertex 1.65907 0.9775 2.46578 + vertex 1.65799 0.973595 2.46499 + vertex 1.66292 0.978722 2.46492 + endloop + endfacet + facet normal 0.291627 -0.268458 0.918087 + outer loop + vertex 1.66255 0.969022 2.46221 + vertex 1.66273 0.973863 2.46357 + vertex 1.65781 0.968764 2.46364 + endloop + endfacet + facet normal 0.288769 -0.26794 0.919141 + outer loop + vertex 1.65417 0.972418 2.46585 + vertex 1.65308 0.968539 2.46506 + vertex 1.65799 0.973595 2.46499 + endloop + endfacet + facet normal 0.286691 -0.261248 0.921715 + outer loop + vertex 1.64927 0.967402 2.46592 + vertex 1.64814 0.963489 2.46517 + vertex 1.65308 0.968539 2.46506 + endloop + endfacet + facet normal 0.296966 -0.26502 0.917374 + outer loop + vertex 1.65264 0.958869 2.4624 + vertex 1.65286 0.9637 2.46373 + vertex 1.6479 0.958632 2.46387 + endloop + endfacet + facet normal 0.297016 -0.263598 0.917768 + outer loop + vertex 1.65264 0.958869 2.4624 + vertex 1.6479 0.958632 2.46387 + vertex 1.64777 0.953864 2.46254 + endloop + endfacet + facet normal 0.294194 -0.255636 0.920924 + outer loop + vertex 1.64432 0.962293 2.46605 + vertex 1.64316 0.958317 2.46532 + vertex 1.64814 0.963489 2.46517 + endloop + endfacet + facet normal 0.297508 -0.263569 0.917616 + outer loop + vertex 1.64777 0.953864 2.46254 + vertex 1.6479 0.958632 2.46387 + vertex 1.64295 0.953494 2.464 + endloop + endfacet + facet normal 0.30845 -0.282825 0.908223 + outer loop + vertex 1.63934 0.957 2.46621 + vertex 1.63815 0.953119 2.4654 + vertex 1.64316 0.958317 2.46532 + endloop + endfacet + facet normal 0.294438 -0.365375 0.883067 + outer loop + vertex 1.63435 0.951956 2.46619 + vertex 1.633 0.948413 2.46517 + vertex 1.63815 0.953119 2.4654 + endloop + endfacet + facet normal 0.230652 -0.34841 0.908521 + outer loop + vertex 1.63435 0.951956 2.46619 + vertex 1.63147 0.950373 2.46631 + vertex 1.633 0.948413 2.46517 + endloop + endfacet + facet normal 0.196275 -0.283362 0.938713 + outer loop + vertex 1.63435 0.951956 2.46619 + vertex 1.63285 0.95412 2.46716 + vertex 1.63147 0.950373 2.46631 + endloop + endfacet + facet normal 0.272996 -0.28278 0.919516 + outer loop + vertex 1.64296 0.948637 2.4625 + vertex 1.64295 0.953494 2.464 + vertex 1.63797 0.948496 2.46394 + endloop + endfacet + facet normal 0.297303 -0.280584 0.912625 + outer loop + vertex 1.64777 0.953864 2.46254 + vertex 1.64295 0.953494 2.464 + vertex 1.64296 0.948637 2.4625 + endloop + endfacet + facet normal 0.300884 -0.267431 0.915396 + outer loop + vertex 1.65157 0.955085 2.46165 + vertex 1.65264 0.958869 2.4624 + vertex 1.64777 0.953864 2.46254 + endloop + endfacet + facet normal 0.301227 -0.276246 0.912661 + outer loop + vertex 1.65446 0.957094 2.46131 + vertex 1.65157 0.955085 2.46165 + vertex 1.65346 0.953485 2.46054 + endloop + endfacet + facet normal 0.328839 -0.318973 0.888888 + outer loop + vertex 1.64977 0.952317 2.46141 + vertex 1.64701 0.950085 2.46163 + vertex 1.64947 0.949201 2.46041 + endloop + endfacet + facet normal 0.289343 -0.273945 0.917189 + outer loop + vertex 1.65446 0.957094 2.46131 + vertex 1.65346 0.953485 2.46054 + vertex 1.65827 0.958273 2.46046 + endloop + endfacet + facet normal 0.288028 -0.263353 0.920698 + outer loop + vertex 1.66322 0.963297 2.46034 + vertex 1.65827 0.958273 2.46046 + vertex 1.66297 0.958494 2.45905 + endloop + endfacet + facet normal 0.292189 -0.265512 0.918765 + outer loop + vertex 1.66786 0.958626 2.45753 + vertex 1.66795 0.963527 2.45892 + vertex 1.66297 0.958494 2.45905 + endloop + endfacet + facet normal 0.295162 -0.270345 0.916402 + outer loop + vertex 1.67193 0.959969 2.45662 + vertex 1.67277 0.963761 2.45746 + vertex 1.66786 0.958626 2.45753 + endloop + endfacet + facet normal 0.30515 -0.289833 0.907128 + outer loop + vertex 1.67475 0.962135 2.45636 + vertex 1.67193 0.959969 2.45662 + vertex 1.67427 0.959095 2.45555 + endloop + endfacet + facet normal 0.292499 -0.289018 0.911544 + outer loop + vertex 1.67475 0.962135 2.45636 + vertex 1.67427 0.959095 2.45555 + vertex 1.67843 0.963298 2.45555 + endloop + endfacet + facet normal 0.284994 -0.276563 0.917764 + outer loop + vertex 1.68328 0.968168 2.45551 + vertex 1.67843 0.963298 2.45555 + vertex 1.68293 0.963482 2.45421 + endloop + endfacet + facet normal 0.281357 -0.276611 0.918871 + outer loop + vertex 1.68749 0.963811 2.45291 + vertex 1.68792 0.968421 2.45416 + vertex 1.68293 0.963482 2.45421 + endloop + endfacet + facet normal 0.285705 -0.276655 0.917516 + outer loop + vertex 1.68749 0.963811 2.45291 + vertex 1.69276 0.968453 2.45267 + vertex 1.68792 0.968421 2.45416 + endloop + endfacet + facet normal 0.296363 -0.265292 0.917491 + outer loop + vertex 1.69777 0.97373 2.45258 + vertex 1.69296 0.973441 2.45404 + vertex 1.69276 0.968453 2.45267 + endloop + endfacet + facet normal 0.335032 -0.245065 0.909779 + outer loop + vertex 1.70437 0.977218 2.45122 + vertex 1.70245 0.978871 2.45237 + vertex 1.70159 0.975021 2.45166 + endloop + endfacet + facet normal 0.347716 -0.263088 0.899933 + outer loop + vertex 1.70437 0.977218 2.45122 + vertex 1.70159 0.975021 2.45166 + vertex 1.70344 0.973464 2.45048 + endloop + endfacet + facet normal 0.296568 -0.256804 0.919836 + outer loop + vertex 1.69777 0.97373 2.45258 + vertex 1.6979 0.978587 2.45389 + vertex 1.69296 0.973441 2.45404 + endloop + endfacet + facet normal 0.306936 -0.266942 0.913528 + outer loop + vertex 1.69296 0.973441 2.45404 + vertex 1.6979 0.978587 2.45389 + vertex 1.69323 0.978288 2.45537 + endloop + endfacet + facet normal 0.295905 -0.272296 0.915585 + outer loop + vertex 1.69438 0.98219 2.45616 + vertex 1.69145 0.980078 2.45648 + vertex 1.69323 0.978288 2.45537 + endloop + endfacet + facet normal 0.328631 -0.26984 0.90509 + outer loop + vertex 1.69926 0.987362 2.45598 + vertex 1.69638 0.985196 2.45637 + vertex 1.69817 0.983457 2.45521 + endloop + endfacet + facet normal 0.29028 -0.263845 0.91985 + outer loop + vertex 1.69438 0.98219 2.45616 + vertex 1.69254 0.983988 2.45726 + vertex 1.69145 0.980078 2.45648 + endloop + endfacet + facet normal 0.316394 -0.251837 0.914589 + outer loop + vertex 1.69926 0.987362 2.45598 + vertex 1.69732 0.989036 2.45711 + vertex 1.69638 0.985196 2.45637 + endloop + endfacet + facet normal 0.284053 -0.256534 0.923853 + outer loop + vertex 1.69254 0.983988 2.45726 + vertex 1.69268 0.988855 2.45856 + vertex 1.68777 0.983763 2.45866 + endloop + endfacet + facet normal 0.330075 -0.239485 0.913071 + outer loop + vertex 1.70137 0.993632 2.45685 + vertex 1.6975 0.993894 2.45832 + vertex 1.69732 0.989036 2.45711 + endloop + endfacet + facet normal 0.289244 -0.261606 0.920815 + outer loop + vertex 1.68777 0.983763 2.45866 + vertex 1.69268 0.988855 2.45856 + vertex 1.68793 0.988631 2.45999 + endloop + endfacet + facet normal 0.286257 -0.260449 0.922076 + outer loop + vertex 1.68902 0.992552 2.46076 + vertex 1.68609 0.990416 2.46107 + vertex 1.68793 0.988631 2.45999 + endloop + endfacet + facet normal 0.302866 -0.255484 0.91815 + outer loop + vertex 1.69386 0.997708 2.46063 + vertex 1.69099 0.995555 2.46098 + vertex 1.69285 0.993779 2.45987 + endloop + endfacet + facet normal 0.282925 -0.255539 0.924475 + outer loop + vertex 1.68902 0.992552 2.46076 + vertex 1.68717 0.994261 2.4618 + vertex 1.68609 0.990416 2.46107 + endloop + endfacet + facet normal 0.295613 -0.244952 0.923369 + outer loop + vertex 1.69386 0.997708 2.46063 + vertex 1.69191 0.999277 2.46167 + vertex 1.69099 0.995555 2.46098 + endloop + endfacet + facet normal 0.284154 -0.250183 0.925562 + outer loop + vertex 1.68717 0.994261 2.4618 + vertex 1.6874 0.998898 2.46298 + vertex 1.68248 0.99397 2.46316 + endloop + endfacet + facet normal 0.306889 -0.237265 0.921697 + outer loop + vertex 1.69594 1.0038 2.46149 + vertex 1.69217 1.00385 2.46276 + vertex 1.69191 0.999277 2.46167 + endloop + endfacet + facet normal 0.308265 -0.221268 0.92521 + outer loop + vertex 1.69594 1.0038 2.46149 + vertex 1.69727 1.00879 2.46224 + vertex 1.69217 1.00385 2.46276 + endloop + endfacet + facet normal 0.324985 -0.239614 0.914861 + outer loop + vertex 1.69217 1.00385 2.46276 + vertex 1.69727 1.00879 2.46224 + vertex 1.69265 1.00866 2.46385 + endloop + endfacet + facet normal 0.325538 -0.229515 0.91725 + outer loop + vertex 1.69727 1.00879 2.46224 + vertex 1.69733 1.0137 2.46345 + vertex 1.69265 1.00866 2.46385 + endloop + endfacet + facet normal 0.296179 -0.252548 0.921139 + outer loop + vertex 1.68435 1.00701 2.46614 + vertex 1.68335 1.00328 2.46544 + vertex 1.68812 1.00832 2.46529 + endloop + endfacet + facet normal 0.288165 -0.246874 0.92521 + outer loop + vertex 1.6874 0.998898 2.46298 + vertex 1.68776 1.00357 2.46412 + vertex 1.68296 0.998712 2.46432 + endloop + endfacet + facet normal 0.286731 -0.251735 0.924346 + outer loop + vertex 1.6797 1.00208 2.46624 + vertex 1.67927 0.998976 2.46553 + vertex 1.68335 1.00328 2.46544 + endloop + endfacet + facet normal 0.287906 -0.254005 0.923359 + outer loop + vertex 1.68248 0.99397 2.46316 + vertex 1.6874 0.998898 2.46298 + vertex 1.68296 0.998712 2.46432 + endloop + endfacet + facet normal 0.283549 -0.25843 0.923479 + outer loop + vertex 1.68226 0.989207 2.4619 + vertex 1.68248 0.99397 2.46316 + vertex 1.67751 0.989025 2.4633 + endloop + endfacet + facet normal 0.284827 -0.26279 0.921854 + outer loop + vertex 1.67259 0.984018 2.4634 + vertex 1.67751 0.989025 2.4633 + vertex 1.6727 0.988867 2.46474 + endloop + endfacet + facet normal 0.284941 -0.259094 0.922864 + outer loop + vertex 1.6735 0.992687 2.46557 + vertex 1.67068 0.990491 2.46583 + vertex 1.6727 0.988867 2.46474 + endloop + endfacet + facet normal 0.282586 -0.255877 0.924485 + outer loop + vertex 1.6735 0.992687 2.46557 + vertex 1.67108 0.993537 2.46655 + vertex 1.67068 0.990491 2.46583 + endloop + endfacet + facet normal 0.284178 -0.253391 0.924682 + outer loop + vertex 1.67108 0.993537 2.46655 + vertex 1.67267 0.998466 2.46741 + vertex 1.66729 0.993728 2.46776 + endloop + endfacet + facet normal 0.282341 -0.249868 0.926202 + outer loop + vertex 1.6797 1.00208 2.46624 + vertex 1.67767 1.00375 2.46731 + vertex 1.67688 0.999868 2.46651 + endloop + endfacet + facet normal 0.283775 -0.250825 0.925505 + outer loop + vertex 1.67267 0.998466 2.46741 + vertex 1.67281 1.00357 2.46875 + vertex 1.66778 0.998494 2.46892 + endloop + endfacet + facet normal 0.283558 -0.250606 0.92563 + outer loop + vertex 1.66778 0.998494 2.46892 + vertex 1.67281 1.00357 2.46875 + vertex 1.66806 1.00339 2.47016 + endloop + endfacet + facet normal 0.283583 -0.24998 0.925792 + outer loop + vertex 1.67301 1.00856 2.47004 + vertex 1.66806 1.00339 2.47016 + vertex 1.67281 1.00357 2.46875 + endloop + endfacet + facet normal 0.283614 -0.25001 0.925774 + outer loop + vertex 1.66918 1.00737 2.47088 + vertex 1.66806 1.00339 2.47016 + vertex 1.67301 1.00856 2.47004 + endloop + endfacet + facet normal 0.283754 -0.25004 0.925723 + outer loop + vertex 1.66918 1.00737 2.47088 + vertex 1.66627 1.00523 2.4712 + vertex 1.66806 1.00339 2.47016 + endloop + endfacet + facet normal 0.283134 -0.249128 0.926159 + outer loop + vertex 1.66918 1.00737 2.47088 + vertex 1.66735 1.00917 2.47193 + vertex 1.66627 1.00523 2.4712 + endloop + endfacet + facet normal 0.283592 -0.249168 0.926008 + outer loop + vertex 1.68253 1.00888 2.46721 + vertex 1.67776 1.00873 2.46863 + vertex 1.67767 1.00375 2.46731 + endloop + endfacet + facet normal 0.284086 -0.248757 0.925967 + outer loop + vertex 1.6741 1.01253 2.47077 + vertex 1.67119 1.0104 2.47109 + vertex 1.67301 1.00856 2.47004 + endloop + endfacet + facet normal 0.284239 -0.246036 0.926647 + outer loop + vertex 1.6789 1.01761 2.47065 + vertex 1.67605 1.01552 2.47096 + vertex 1.67791 1.01372 2.46992 + endloop + endfacet + facet normal 0.282334 -0.246188 0.927189 + outer loop + vertex 1.6741 1.01253 2.47077 + vertex 1.67224 1.01425 2.47179 + vertex 1.67119 1.0104 2.47109 + endloop + endfacet + facet normal 0.283847 -0.245463 0.926919 + outer loop + vertex 1.6789 1.01761 2.47065 + vertex 1.67696 1.01917 2.47165 + vertex 1.67605 1.01552 2.47096 + endloop + endfacet + facet normal 0.283098 -0.245757 0.92707 + outer loop + vertex 1.67696 1.01917 2.47165 + vertex 1.67726 1.02368 2.47275 + vertex 1.67244 1.01887 2.47295 + endloop + endfacet + facet normal 0.283176 -0.245836 0.927025 + outer loop + vertex 1.67244 1.01887 2.47295 + vertex 1.67726 1.02368 2.47275 + vertex 1.67278 1.02352 2.47408 + endloop + endfacet + facet normal 0.288247 -0.247431 0.925036 + outer loop + vertex 1.66244 1.00403 2.47207 + vertex 1.66258 1.00897 2.47334 + vertex 1.6577 1.00384 2.47349 + endloop + endfacet + facet normal 0.288388 -0.248897 0.924599 + outer loop + vertex 1.65282 0.998713 2.47363 + vertex 1.6577 1.00384 2.47349 + vertex 1.65297 1.00368 2.47492 + endloop + endfacet + facet normal 0.289997 -0.247312 0.924521 + outer loop + vertex 1.65396 1.00759 2.47566 + vertex 1.65113 1.0055 2.47599 + vertex 1.65297 1.00368 2.47492 + endloop + endfacet + facet normal 0.288982 -0.243571 0.925831 + outer loop + vertex 1.65571 1.01041 2.47586 + vertex 1.65204 1.0092 2.47668 + vertex 1.65396 1.00759 2.47566 + endloop + endfacet + facet normal 0.289318 -0.244895 0.925377 + outer loop + vertex 1.65571 1.01041 2.47586 + vertex 1.65609 1.01349 2.47655 + vertex 1.65204 1.0092 2.47668 + endloop + endfacet + facet normal 0.288078 -0.246684 0.925288 + outer loop + vertex 1.65767 1.01845 2.47738 + vertex 1.65609 1.01349 2.47655 + vertex 1.66017 1.01625 2.47602 + endloop + endfacet + facet normal 0.286693 -0.248264 0.925296 + outer loop + vertex 1.66187 1.01988 2.47646 + vertex 1.65767 1.01845 2.47738 + vertex 1.66017 1.01625 2.47602 + endloop + endfacet + facet normal 0.286184 -0.24632 0.925973 + outer loop + vertex 1.66187 1.01988 2.47646 + vertex 1.66267 1.02377 2.47725 + vertex 1.65767 1.01845 2.47738 + endloop + endfacet + facet normal 0.284029 -0.244262 0.92718 + outer loop + vertex 1.66267 1.02377 2.47725 + vertex 1.6578 1.02358 2.47869 + vertex 1.65767 1.01845 2.47738 + endloop + endfacet + facet normal 0.282677 -0.245851 0.927174 + outer loop + vertex 1.66471 1.02211 2.47619 + vertex 1.66267 1.02377 2.47725 + vertex 1.66187 1.01988 2.47646 + endloop + endfacet + facet normal 0.284475 -0.248272 0.925978 + outer loop + vertex 1.66471 1.02211 2.47619 + vertex 1.66187 1.01988 2.47646 + vertex 1.66426 1.019 2.47549 + endloop + endfacet + facet normal 0.282786 -0.245718 0.927176 + outer loop + vertex 1.6665 1.02496 2.4764 + vertex 1.66267 1.02377 2.47725 + vertex 1.66471 1.02211 2.47619 + endloop + endfacet + facet normal 0.284868 -0.24696 0.926208 + outer loop + vertex 1.66835 1.02331 2.47539 + vertex 1.6665 1.02496 2.4764 + vertex 1.66471 1.02211 2.47619 + endloop + endfacet + facet normal 0.285907 -0.245787 0.9262 + outer loop + vertex 1.66935 1.02705 2.47608 + vertex 1.6665 1.02496 2.4764 + vertex 1.66835 1.02331 2.47539 + endloop + endfacet + facet normal 0.281968 -0.240007 0.928919 + outer loop + vertex 1.66935 1.02705 2.47608 + vertex 1.6675 1.02891 2.47711 + vertex 1.6665 1.02496 2.4764 + endloop + endfacet + facet normal 0.282902 -0.239054 0.928881 + outer loop + vertex 1.67132 1.03009 2.47626 + vertex 1.6675 1.02891 2.47711 + vertex 1.66935 1.02705 2.47608 + endloop + endfacet + facet normal 0.28604 -0.240999 0.927416 + outer loop + vertex 1.6731 1.0283 2.47524 + vertex 1.67132 1.03009 2.47626 + vertex 1.66935 1.02705 2.47608 + endloop + endfacet + facet normal 0.286874 -0.240148 0.927379 + outer loop + vertex 1.67422 1.03227 2.47592 + vertex 1.67132 1.03009 2.47626 + vertex 1.6731 1.0283 2.47524 + endloop + endfacet + facet normal 0.283935 -0.235931 0.929364 + outer loop + vertex 1.67422 1.03227 2.47592 + vertex 1.67236 1.03406 2.47695 + vertex 1.67132 1.03009 2.47626 + endloop + endfacet + facet normal 0.282071 -0.235559 0.930026 + outer loop + vertex 1.67132 1.03009 2.47626 + vertex 1.67236 1.03406 2.47695 + vertex 1.6675 1.02891 2.47711 + endloop + endfacet + facet normal 0.282504 -0.235974 0.929789 + outer loop + vertex 1.67236 1.03406 2.47695 + vertex 1.66758 1.0339 2.47836 + vertex 1.6675 1.02891 2.47711 + endloop + endfacet + facet normal 0.281407 -0.239901 0.929117 + outer loop + vertex 1.6665 1.02496 2.4764 + vertex 1.6675 1.02891 2.47711 + vertex 1.66267 1.02377 2.47725 + endloop + endfacet + facet normal 0.282314 -0.240767 0.928617 + outer loop + vertex 1.6675 1.02891 2.47711 + vertex 1.66271 1.02876 2.47853 + vertex 1.66267 1.02377 2.47725 + endloop + endfacet + facet normal 0.284654 -0.243519 0.927184 + outer loop + vertex 1.6585 1.01264 2.47557 + vertex 1.65775 1.00878 2.47479 + vertex 1.66267 1.01404 2.47466 + endloop + endfacet + facet normal 0.284811 -0.247478 0.926087 + outer loop + vertex 1.66426 1.019 2.47549 + vertex 1.66187 1.01988 2.47646 + vertex 1.66017 1.01625 2.47602 + endloop + endfacet + facet normal 0.284064 -0.246447 0.926591 + outer loop + vertex 1.66753 1.01398 2.47315 + vertex 1.66797 1.01873 2.47428 + vertex 1.66267 1.01404 2.47466 + endloop + endfacet + facet normal 0.285211 -0.248323 0.925738 + outer loop + vertex 1.66471 1.02211 2.47619 + vertex 1.66426 1.019 2.47549 + vertex 1.66835 1.02331 2.47539 + endloop + endfacet + facet normal 0.283716 -0.245836 0.92686 + outer loop + vertex 1.67244 1.01887 2.47295 + vertex 1.67278 1.02352 2.47408 + vertex 1.66797 1.01873 2.47428 + endloop + endfacet + facet normal 0.287337 -0.246072 0.925681 + outer loop + vertex 1.66935 1.02705 2.47608 + vertex 1.66835 1.02331 2.47539 + vertex 1.6731 1.0283 2.47524 + endloop + endfacet + facet normal 0.283289 -0.24305 0.927725 + outer loop + vertex 1.67726 1.02368 2.47275 + vertex 1.67774 1.02851 2.47388 + vertex 1.67278 1.02352 2.47408 + endloop + endfacet + facet normal 0.285915 -0.23994 0.927729 + outer loop + vertex 1.67422 1.03227 2.47592 + vertex 1.6731 1.0283 2.47524 + vertex 1.678 1.03349 2.47508 + endloop + endfacet + facet normal 0.285236 -0.2372 0.928642 + outer loop + vertex 1.678 1.03349 2.47508 + vertex 1.67617 1.03531 2.4761 + vertex 1.67422 1.03227 2.47592 + endloop + endfacet + facet normal 0.283656 -0.236226 0.929374 + outer loop + vertex 1.67617 1.03531 2.4761 + vertex 1.67236 1.03406 2.47695 + vertex 1.67422 1.03227 2.47592 + endloop + endfacet + facet normal 0.283159 -0.234267 0.930022 + outer loop + vertex 1.67617 1.03531 2.4761 + vertex 1.67707 1.03905 2.47677 + vertex 1.67236 1.03406 2.47695 + endloop + endfacet + facet normal 0.281764 -0.232921 0.930783 + outer loop + vertex 1.67707 1.03905 2.47677 + vertex 1.67247 1.0389 2.47812 + vertex 1.67236 1.03406 2.47695 + endloop + endfacet + facet normal 0.281906 -0.229069 0.931695 + outer loop + vertex 1.67707 1.03905 2.47677 + vertex 1.67732 1.04369 2.47783 + vertex 1.67247 1.0389 2.47812 + endloop + endfacet + facet normal 0.283661 -0.229045 0.931169 + outer loop + vertex 1.68113 1.04345 2.47661 + vertex 1.67732 1.04369 2.47783 + vertex 1.67707 1.03905 2.47677 + endloop + endfacet + facet normal 0.282795 -0.228229 0.931632 + outer loop + vertex 1.68077 1.0403 2.47595 + vertex 1.68113 1.04345 2.47661 + vertex 1.67707 1.03905 2.47677 + endloop + endfacet + facet normal 0.284287 -0.233848 0.929783 + outer loop + vertex 1.68077 1.0403 2.47595 + vertex 1.67707 1.03905 2.47677 + vertex 1.67901 1.03744 2.47577 + endloop + endfacet + facet normal 0.294656 -0.239906 0.924999 + outer loop + vertex 1.68281 1.03867 2.47488 + vertex 1.68077 1.0403 2.47595 + vertex 1.67901 1.03744 2.47577 + endloop + endfacet + facet normal 0.299146 -0.234289 0.924997 + outer loop + vertex 1.68359 1.04263 2.47563 + vertex 1.68077 1.0403 2.47595 + vertex 1.68281 1.03867 2.47488 + endloop + endfacet + facet normal 0.294926 -0.228797 0.927723 + outer loop + vertex 1.68359 1.04263 2.47563 + vertex 1.68113 1.04345 2.47661 + vertex 1.68077 1.0403 2.47595 + endloop + endfacet + facet normal 0.297315 -0.222573 0.928475 + outer loop + vertex 1.68524 1.0464 2.47601 + vertex 1.68113 1.04345 2.47661 + vertex 1.68359 1.04263 2.47563 + endloop + endfacet + facet normal 0.323289 -0.232801 0.917217 + outer loop + vertex 1.68359 1.04263 2.47563 + vertex 1.68774 1.04412 2.47454 + vertex 1.68524 1.0464 2.47601 + endloop + endfacet + facet normal 0.332347 -0.222439 0.916551 + outer loop + vertex 1.68774 1.04412 2.47454 + vertex 1.68923 1.04938 2.47528 + vertex 1.68524 1.0464 2.47601 + endloop + endfacet + facet normal 0.33771 -0.230582 0.91257 + outer loop + vertex 1.68923 1.04938 2.47528 + vertex 1.68683 1.0502 2.47638 + vertex 1.68524 1.0464 2.47601 + endloop + endfacet + facet normal 0.30179 -0.217054 0.928338 + outer loop + vertex 1.68683 1.0502 2.47638 + vertex 1.68262 1.04857 2.47736 + vertex 1.68524 1.0464 2.47601 + endloop + endfacet + facet normal 0.297452 -0.203144 0.932875 + outer loop + vertex 1.68683 1.0502 2.47638 + vertex 1.6873 1.05402 2.47706 + vertex 1.68262 1.04857 2.47736 + endloop + endfacet + facet normal 0.31232 -0.216324 0.925019 + outer loop + vertex 1.6873 1.05402 2.47706 + vertex 1.68262 1.05372 2.47857 + vertex 1.68262 1.04857 2.47736 + endloop + endfacet + facet normal 0.29054 -0.217911 0.931719 + outer loop + vertex 1.68262 1.04857 2.47736 + vertex 1.68262 1.05372 2.47857 + vertex 1.67776 1.04859 2.47888 + endloop + endfacet + facet normal 0.289997 -0.225477 0.930087 + outer loop + vertex 1.67732 1.04369 2.47783 + vertex 1.68262 1.04857 2.47736 + vertex 1.67776 1.04859 2.47888 + endloop + endfacet + facet normal 0.28198 -0.225296 0.932593 + outer loop + vertex 1.67732 1.04369 2.47783 + vertex 1.67776 1.04859 2.47888 + vertex 1.6729 1.04375 2.47919 + endloop + endfacet + facet normal 0.283794 -0.227185 0.931584 + outer loop + vertex 1.6729 1.04375 2.47919 + vertex 1.67776 1.04859 2.47888 + vertex 1.67323 1.04847 2.48024 + endloop + endfacet + facet normal 0.297306 -0.222559 0.928481 + outer loop + vertex 1.68262 1.04857 2.47736 + vertex 1.68113 1.04345 2.47661 + vertex 1.68524 1.0464 2.47601 + endloop + endfacet + facet normal 0.284868 -0.219616 0.93307 + outer loop + vertex 1.68113 1.04345 2.47661 + vertex 1.68262 1.04857 2.47736 + vertex 1.67732 1.04369 2.47783 + endloop + endfacet + facet normal 0.283839 -0.234387 0.929784 + outer loop + vertex 1.67901 1.03744 2.47577 + vertex 1.67707 1.03905 2.47677 + vertex 1.67617 1.03531 2.4761 + endloop + endfacet + facet normal 0.285558 -0.236869 0.928628 + outer loop + vertex 1.67901 1.03744 2.47577 + vertex 1.67617 1.03531 2.4761 + vertex 1.678 1.03349 2.47508 + endloop + endfacet + facet normal 0.283226 -0.234899 0.929842 + outer loop + vertex 1.68262 1.02848 2.47238 + vertex 1.68271 1.03363 2.47365 + vertex 1.67774 1.02851 2.47388 + endloop + endfacet + facet normal 0.294327 -0.238575 0.925448 + outer loop + vertex 1.67901 1.03744 2.47577 + vertex 1.678 1.03349 2.47508 + vertex 1.68281 1.03867 2.47488 + endloop + endfacet + facet normal 0.291746 -0.217692 0.931394 + outer loop + vertex 1.68745 1.03378 2.4722 + vertex 1.68751 1.03875 2.47335 + vertex 1.68271 1.03363 2.47365 + endloop + endfacet + facet normal 0.324545 -0.237509 0.915565 + outer loop + vertex 1.68359 1.04263 2.47563 + vertex 1.68281 1.03867 2.47488 + vertex 1.68774 1.04412 2.47454 + endloop + endfacet + facet normal 0.322135 -0.194857 0.926423 + outer loop + vertex 1.69138 1.0384 2.47193 + vertex 1.69262 1.04374 2.47262 + vertex 1.68751 1.03875 2.47335 + endloop + endfacet + facet normal 0.341353 -0.221165 0.913545 + outer loop + vertex 1.68952 1.05262 2.47596 + vertex 1.68683 1.0502 2.47638 + vertex 1.68923 1.04938 2.47528 + endloop + endfacet + facet normal 0.328109 -0.204936 0.922142 + outer loop + vertex 1.68952 1.05262 2.47596 + vertex 1.6873 1.05402 2.47706 + vertex 1.68683 1.0502 2.47638 + endloop + endfacet + facet normal 0.312418 -0.20442 0.927689 + outer loop + vertex 1.6873 1.05402 2.47706 + vertex 1.68717 1.0588 2.47815 + vertex 1.68262 1.05372 2.47857 + endloop + endfacet + facet normal 0.299444 -0.226635 0.926806 + outer loop + vertex 1.67776 1.04859 2.47888 + vertex 1.68262 1.05372 2.47857 + vertex 1.67796 1.05351 2.48003 + endloop + endfacet + facet normal 0.290049 -0.216553 0.932189 + outer loop + vertex 1.6807 1.06036 2.48085 + vertex 1.68101 1.06352 2.48149 + vertex 1.67701 1.05906 2.48169 + endloop + endfacet + facet normal 0.294358 -0.220524 0.929904 + outer loop + vertex 1.68101 1.06352 2.48149 + vertex 1.67723 1.06374 2.48273 + vertex 1.67701 1.05906 2.48169 + endloop + endfacet + facet normal 0.29171 -0.231974 0.927951 + outer loop + vertex 1.67895 1.05744 2.48069 + vertex 1.67611 1.05528 2.48105 + vertex 1.67796 1.05351 2.48003 + endloop + endfacet + facet normal 0.283796 -0.227134 0.931595 + outer loop + vertex 1.67796 1.05351 2.48003 + vertex 1.67323 1.04847 2.48024 + vertex 1.67776 1.04859 2.47888 + endloop + endfacet + facet normal 0.282303 -0.231694 0.930926 + outer loop + vertex 1.67418 1.05227 2.48089 + vertex 1.6723 1.05403 2.4819 + vertex 1.67132 1.05014 2.48122 + endloop + endfacet + facet normal 0.283907 -0.231999 0.930362 + outer loop + vertex 1.67132 1.05014 2.48122 + vertex 1.6723 1.05403 2.4819 + vertex 1.66749 1.04888 2.48208 + endloop + endfacet + facet normal 0.28338 -0.231497 0.930647 + outer loop + vertex 1.6723 1.05403 2.4819 + vertex 1.66752 1.05386 2.48331 + vertex 1.66749 1.04888 2.48208 + endloop + endfacet + facet normal 0.28376 -0.231421 0.930551 + outer loop + vertex 1.67132 1.05014 2.48122 + vertex 1.66749 1.04888 2.48208 + vertex 1.66954 1.04725 2.48105 + endloop + endfacet + facet normal 0.282226 -0.226796 0.932155 + outer loop + vertex 1.66915 1.04408 2.4804 + vertex 1.66673 1.04496 2.48134 + vertex 1.66509 1.04128 2.48094 + endloop + endfacet + facet normal 0.280463 -0.227177 0.932594 + outer loop + vertex 1.67323 1.04847 2.48024 + vertex 1.66915 1.04408 2.4804 + vertex 1.6729 1.04375 2.47919 + endloop + endfacet + facet normal 0.281694 -0.228848 0.931814 + outer loop + vertex 1.67247 1.0389 2.47812 + vertex 1.67732 1.04369 2.47783 + vertex 1.6729 1.04375 2.47919 + endloop + endfacet + facet normal 0.282616 -0.232881 0.930535 + outer loop + vertex 1.67236 1.03406 2.47695 + vertex 1.67247 1.0389 2.47812 + vertex 1.66758 1.0339 2.47836 + endloop + endfacet + facet normal 0.284002 -0.232539 0.930198 + outer loop + vertex 1.66346 1.03763 2.48054 + vertex 1.66274 1.03375 2.47979 + vertex 1.66762 1.03904 2.47962 + endloop + endfacet + facet normal 0.28251 -0.235974 0.929787 + outer loop + vertex 1.6675 1.02891 2.47711 + vertex 1.66758 1.0339 2.47836 + vertex 1.66271 1.02876 2.47853 + endloop + endfacet + facet normal 0.284467 -0.237104 0.928903 + outer loop + vertex 1.65896 1.03256 2.48065 + vertex 1.65796 1.02861 2.47995 + vertex 1.66274 1.03375 2.47979 + endloop + endfacet + facet normal 0.28416 -0.240648 0.928085 + outer loop + vertex 1.66267 1.02377 2.47725 + vertex 1.66271 1.02876 2.47853 + vertex 1.6578 1.02358 2.47869 + endloop + endfacet + facet normal 0.284612 -0.23845 0.928514 + outer loop + vertex 1.65415 1.02741 2.4808 + vertex 1.65306 1.02341 2.48011 + vertex 1.65796 1.02861 2.47995 + endloop + endfacet + facet normal 0.287909 -0.24407 0.926033 + outer loop + vertex 1.65767 1.01845 2.47738 + vertex 1.6578 1.02358 2.47869 + vertex 1.65283 1.01853 2.47891 + endloop + endfacet + facet normal 0.288101 -0.244601 0.925834 + outer loop + vertex 1.64796 1.01378 2.47917 + vertex 1.65283 1.01853 2.47891 + vertex 1.64831 1.0184 2.48028 + endloop + endfacet + facet normal 0.287284 -0.24108 0.92701 + outer loop + vertex 1.64927 1.02217 2.48096 + vertex 1.64643 1.02007 2.4813 + vertex 1.64831 1.0184 2.48028 + endloop + endfacet + facet normal 0.286136 -0.23877 0.927963 + outer loop + vertex 1.65415 1.02741 2.4808 + vertex 1.65124 1.02523 2.48114 + vertex 1.65306 1.02341 2.48011 + endloop + endfacet + facet normal 0.285127 -0.237941 0.928486 + outer loop + vertex 1.64927 1.02217 2.48096 + vertex 1.64744 1.02402 2.482 + vertex 1.64643 1.02007 2.4813 + endloop + endfacet + facet normal 0.284919 -0.237019 0.928786 + outer loop + vertex 1.65415 1.02741 2.4808 + vertex 1.65231 1.02919 2.48183 + vertex 1.65124 1.02523 2.48114 + endloop + endfacet + facet normal 0.284912 -0.235458 0.929185 + outer loop + vertex 1.65702 1.03417 2.48164 + vertex 1.65245 1.034 2.483 + vertex 1.65231 1.02919 2.48183 + endloop + endfacet + facet normal 0.28486 -0.237721 0.928625 + outer loop + vertex 1.64744 1.02402 2.482 + vertex 1.64755 1.02899 2.48324 + vertex 1.64269 1.02388 2.48342 + endloop + endfacet + facet normal 0.285118 -0.235726 0.929054 + outer loop + vertex 1.6378 1.01872 2.48361 + vertex 1.64269 1.02388 2.48342 + vertex 1.63795 1.02376 2.48484 + endloop + endfacet + facet normal 0.284449 -0.239195 0.928372 + outer loop + vertex 1.63894 1.02766 2.48555 + vertex 1.63611 1.02559 2.48588 + vertex 1.63795 1.02376 2.48484 + endloop + endfacet + facet normal 0.285649 -0.242062 0.92726 + outer loop + vertex 1.64068 1.03046 2.48574 + vertex 1.637 1.02922 2.48655 + vertex 1.63894 1.02766 2.48555 + endloop + endfacet + facet normal 0.28366 -0.234472 0.929817 + outer loop + vertex 1.64068 1.03046 2.48574 + vertex 1.64103 1.03354 2.48641 + vertex 1.637 1.02922 2.48655 + endloop + endfacet + facet normal 0.283192 -0.229365 0.931232 + outer loop + vertex 1.64255 1.03856 2.48718 + vertex 1.64103 1.03354 2.48641 + vertex 1.64508 1.03634 2.48587 + endloop + endfacet + facet normal 0.289885 -0.23984 0.926522 + outer loop + vertex 1.64346 1.03269 2.48546 + vertex 1.64273 1.02883 2.48469 + vertex 1.64761 1.0341 2.48452 + endloop + endfacet + facet normal 0.286213 -0.229337 0.930315 + outer loop + vertex 1.64913 1.03916 2.48532 + vertex 1.64672 1.04003 2.48627 + vertex 1.64508 1.03634 2.48587 + endloop + endfacet + facet normal 0.287488 -0.232875 0.929042 + outer loop + vertex 1.65245 1.034 2.483 + vertex 1.65288 1.03883 2.48408 + vertex 1.64761 1.0341 2.48452 + endloop + endfacet + facet normal 0.285603 -0.229388 0.93049 + outer loop + vertex 1.64952 1.04234 2.48598 + vertex 1.64913 1.03916 2.48532 + vertex 1.6532 1.04357 2.48515 + endloop + endfacet + facet normal 0.286328 -0.230949 0.929881 + outer loop + vertex 1.65729 1.03876 2.4827 + vertex 1.65774 1.04363 2.48378 + vertex 1.65288 1.03883 2.48408 + endloop + endfacet + facet normal 0.285145 -0.230287 0.930409 + outer loop + vertex 1.65415 1.04738 2.48581 + vertex 1.6532 1.04357 2.48515 + vertex 1.65793 1.04858 2.48495 + endloop + endfacet + facet normal 0.285996 -0.230929 0.929988 + outer loop + vertex 1.66257 1.04351 2.48226 + vertex 1.66265 1.04869 2.48352 + vertex 1.65774 1.04363 2.48378 + endloop + endfacet + facet normal 0.286822 -0.231454 0.929603 + outer loop + vertex 1.65892 1.0525 2.48562 + vertex 1.65793 1.04858 2.48495 + vertex 1.6627 1.05371 2.48475 + endloop + endfacet + facet normal 0.285912 -0.231331 0.929914 + outer loop + vertex 1.66749 1.04888 2.48208 + vertex 1.66752 1.05386 2.48331 + vertex 1.66265 1.04869 2.48352 + endloop + endfacet + facet normal 0.286024 -0.228425 0.930598 + outer loop + vertex 1.66344 1.05763 2.48549 + vertex 1.6627 1.05371 2.48475 + vertex 1.66759 1.05905 2.48456 + endloop + endfacet + facet normal 0.283478 -0.228626 0.931327 + outer loop + vertex 1.6723 1.05403 2.4819 + vertex 1.67242 1.0589 2.48305 + vertex 1.66752 1.05386 2.48331 + endloop + endfacet + facet normal 0.283485 -0.22332 0.932612 + outer loop + vertex 1.66759 1.05905 2.48456 + vertex 1.67285 1.06382 2.4841 + vertex 1.66913 1.06416 2.48532 + endloop + endfacet + facet normal 0.284036 -0.22073 0.93306 + outer loop + vertex 1.67701 1.05906 2.48169 + vertex 1.67723 1.06374 2.48273 + vertex 1.67242 1.0589 2.48305 + endloop + endfacet + facet normal 0.296107 -0.205991 0.932678 + outer loop + vertex 1.68101 1.06352 2.48149 + vertex 1.68232 1.06858 2.48219 + vertex 1.67723 1.06374 2.48273 + endloop + endfacet + facet normal 0.292065 -0.220391 0.930659 + outer loop + vertex 1.67285 1.06382 2.4841 + vertex 1.67764 1.06867 2.48375 + vertex 1.67316 1.06858 2.48513 + endloop + endfacet + facet normal 0.284987 -0.220921 0.932725 + outer loop + vertex 1.67402 1.07234 2.48576 + vertex 1.67123 1.07023 2.48611 + vertex 1.67316 1.06858 2.48513 + endloop + endfacet + facet normal 0.284284 -0.216749 0.933918 + outer loop + vertex 1.67574 1.07521 2.4859 + vertex 1.67205 1.07395 2.48673 + vertex 1.67402 1.07234 2.48576 + endloop + endfacet + facet normal 0.282859 -0.211539 0.935544 + outer loop + vertex 1.67574 1.07521 2.4859 + vertex 1.67606 1.07837 2.48652 + vertex 1.67205 1.07395 2.48673 + endloop + endfacet + facet normal 0.283116 -0.211778 0.935412 + outer loop + vertex 1.67606 1.07837 2.48652 + vertex 1.67225 1.07864 2.48774 + vertex 1.67205 1.07395 2.48673 + endloop + endfacet + facet normal 0.284646 -0.19984 0.937572 + outer loop + vertex 1.67606 1.07837 2.48652 + vertex 1.67737 1.08339 2.48719 + vertex 1.67225 1.07864 2.48774 + endloop + endfacet + facet normal 0.341351 -0.224441 0.912746 + outer loop + vertex 1.67853 1.07758 2.48555 + vertex 1.67778 1.07364 2.48486 + vertex 1.6826 1.07915 2.48441 + endloop + endfacet + facet normal 0.302276 -0.203581 0.931227 + outer loop + vertex 1.67737 1.08339 2.48719 + vertex 1.67606 1.07837 2.48652 + vertex 1.68008 1.08135 2.48587 + endloop + endfacet + facet normal 0.315356 -0.172136 0.933231 + outer loop + vertex 1.68138 1.08828 2.48685 + vertex 1.68245 1.09353 2.48746 + vertex 1.67744 1.08854 2.48823 + endloop + endfacet + facet normal 0.292369 -0.189501 0.937342 + outer loop + vertex 1.67604 1.09998 2.49119 + vertex 1.67622 1.10319 2.49178 + vertex 1.67236 1.09866 2.49207 + endloop + endfacet + facet normal 0.296457 -0.193118 0.935317 + outer loop + vertex 1.67622 1.10319 2.49178 + vertex 1.67237 1.10358 2.49308 + vertex 1.67236 1.09866 2.49207 + endloop + endfacet + facet normal 0.296882 -0.207253 0.932152 + outer loop + vertex 1.67457 1.09719 2.49107 + vertex 1.67185 1.09484 2.49141 + vertex 1.67427 1.09402 2.49046 + endloop + endfacet + facet normal 0.315732 -0.210441 0.925218 + outer loop + vertex 1.67275 1.08882 2.4898 + vertex 1.67793 1.09369 2.48914 + vertex 1.67427 1.09402 2.49046 + endloop + endfacet + facet normal 0.288046 -0.206535 0.935079 + outer loop + vertex 1.66864 1.08735 2.49074 + vertex 1.66805 1.08359 2.49009 + vertex 1.67275 1.08882 2.4898 + endloop + endfacet + facet normal 0.282562 -0.206279 0.936807 + outer loop + vertex 1.66766 1.0934 2.49237 + vertex 1.6662 1.08822 2.49167 + vertex 1.67025 1.09109 2.49108 + endloop + endfacet + facet normal 0.283503 -0.2065 0.936474 + outer loop + vertex 1.6662 1.08822 2.49167 + vertex 1.66766 1.0934 2.49237 + vertex 1.66236 1.08869 2.49293 + endloop + endfacet + facet normal 0.283958 -0.207042 0.936217 + outer loop + vertex 1.66236 1.08869 2.49293 + vertex 1.66766 1.0934 2.49237 + vertex 1.66287 1.09381 2.49391 + endloop + endfacet + facet normal 0.281169 -0.205837 0.937323 + outer loop + vertex 1.66864 1.08735 2.49074 + vertex 1.66593 1.08507 2.49105 + vertex 1.66805 1.08359 2.49009 + endloop + endfacet + facet normal 0.283442 -0.20227 0.937415 + outer loop + vertex 1.67275 1.08882 2.4898 + vertex 1.66805 1.08359 2.49009 + vertex 1.67262 1.0836 2.48871 + endloop + endfacet + facet normal 0.289378 -0.205243 0.934952 + outer loop + vertex 1.67225 1.07864 2.48774 + vertex 1.67737 1.08339 2.48719 + vertex 1.67262 1.0836 2.48871 + endloop + endfacet + facet normal 0.280944 -0.211823 0.936056 + outer loop + vertex 1.67205 1.07395 2.48673 + vertex 1.67225 1.07864 2.48774 + vertex 1.66746 1.07384 2.48809 + endloop + endfacet + facet normal 0.282283 -0.217309 0.934394 + outer loop + vertex 1.66743 1.06894 2.48696 + vertex 1.66746 1.07384 2.48809 + vertex 1.66257 1.06877 2.48838 + endloop + endfacet + facet normal 0.281928 -0.219781 0.933923 + outer loop + vertex 1.66252 1.06354 2.48717 + vertex 1.66257 1.06877 2.48838 + vertex 1.65763 1.06363 2.48867 + endloop + endfacet + facet normal 0.281406 -0.221902 0.933579 + outer loop + vertex 1.65273 1.0586 2.48895 + vertex 1.65763 1.06363 2.48867 + vertex 1.65296 1.06349 2.49004 + endloop + endfacet + facet normal 0.28072 -0.221747 0.933823 + outer loop + vertex 1.65396 1.06742 2.49068 + vertex 1.65112 1.06528 2.49102 + vertex 1.65296 1.06349 2.49004 + endloop + endfacet + facet normal 0.278957 -0.21924 0.934942 + outer loop + vertex 1.65396 1.06742 2.49068 + vertex 1.65203 1.06903 2.49163 + vertex 1.65112 1.06528 2.49102 + endloop + endfacet + facet normal 0.27828 -0.213905 0.936379 + outer loop + vertex 1.65607 1.07349 2.49144 + vertex 1.65226 1.0737 2.49263 + vertex 1.65203 1.06903 2.49163 + endloop + endfacet + facet normal 0.285327 -0.218959 0.933084 + outer loop + vertex 1.6585 1.07263 2.49052 + vertex 1.65774 1.06866 2.48982 + vertex 1.66264 1.07405 2.48959 + endloop + endfacet + facet normal 0.280996 -0.210405 0.93636 + outer loop + vertex 1.66264 1.07405 2.48959 + vertex 1.66785 1.0788 2.48909 + vertex 1.66414 1.07921 2.4903 + endloop + endfacet + facet normal 0.281804 -0.20624 0.937044 + outer loop + vertex 1.66443 1.08236 2.49091 + vertex 1.66171 1.08008 2.49122 + vertex 1.66414 1.07921 2.4903 + endloop + endfacet + facet normal 0.279837 -0.208841 0.937057 + outer loop + vertex 1.65753 1.07858 2.49214 + vertex 1.65607 1.07349 2.49144 + vertex 1.66013 1.07636 2.49087 + endloop + endfacet + facet normal 0.282001 -0.20649 0.93693 + outer loop + vertex 1.66443 1.08236 2.49091 + vertex 1.66226 1.08383 2.49188 + vertex 1.66171 1.08008 2.49122 + endloop + endfacet + facet normal 0.280709 -0.208593 0.936852 + outer loop + vertex 1.65753 1.07858 2.49214 + vertex 1.65752 1.08379 2.49331 + vertex 1.65262 1.07868 2.49364 + endloop + endfacet + facet normal 0.283242 -0.207979 0.936226 + outer loop + vertex 1.6662 1.08822 2.49167 + vertex 1.66236 1.08869 2.49293 + vertex 1.66226 1.08383 2.49188 + endloop + endfacet + facet normal 0.282714 -0.210583 0.935803 + outer loop + vertex 1.65262 1.07868 2.49364 + vertex 1.65752 1.08379 2.49331 + vertex 1.65269 1.08374 2.49476 + endloop + endfacet + facet normal 0.282147 -0.211901 0.935677 + outer loop + vertex 1.65342 1.08772 2.49544 + vertex 1.65063 1.0854 2.49575 + vertex 1.65269 1.08374 2.49476 + endloop + endfacet + facet normal 0.284322 -0.206645 0.936194 + outer loop + vertex 1.65906 1.09431 2.49519 + vertex 1.6566 1.09516 2.49612 + vertex 1.65503 1.09144 2.49578 + endloop + endfacet + facet normal 0.285174 -0.207092 0.935836 + outer loop + vertex 1.66236 1.08869 2.49293 + vertex 1.66287 1.09381 2.49391 + vertex 1.65758 1.08911 2.49448 + endloop + endfacet + facet normal 0.288034 -0.204887 0.935445 + outer loop + vertex 1.65931 1.09748 2.49581 + vertex 1.65906 1.09431 2.49519 + vertex 1.66296 1.09872 2.49495 + endloop + endfacet + facet normal 0.284652 -0.202188 0.937066 + outer loop + vertex 1.66766 1.0934 2.49237 + vertex 1.66764 1.09866 2.49351 + vertex 1.66287 1.09381 2.49391 + endloop + endfacet + facet normal 0.289703 -0.200561 0.935867 + outer loop + vertex 1.66349 1.10252 2.4956 + vertex 1.66296 1.09872 2.49495 + vertex 1.66762 1.10396 2.49463 + endloop + endfacet + facet normal 0.285841 -0.193758 0.938484 + outer loop + vertex 1.67236 1.09866 2.49207 + vertex 1.67237 1.10358 2.49308 + vertex 1.66764 1.09866 2.49351 + endloop + endfacet + facet normal 0.298141 -0.182138 0.936983 + outer loop + vertex 1.67622 1.10319 2.49178 + vertex 1.67746 1.10839 2.4924 + vertex 1.67237 1.10358 2.49308 + endloop + endfacet + facet normal 0.296778 -0.197277 0.934347 + outer loop + vertex 1.66762 1.10396 2.49463 + vertex 1.67284 1.10877 2.49399 + vertex 1.66907 1.10923 2.49528 + endloop + endfacet + facet normal 0.290747 -0.194013 0.936923 + outer loop + vertex 1.66933 1.11245 2.49587 + vertex 1.66662 1.11007 2.49622 + vertex 1.66907 1.10923 2.49528 + endloop + endfacet + facet normal 0.306398 -0.188143 0.933125 + outer loop + vertex 1.67349 1.11762 2.49557 + vertex 1.67081 1.11524 2.49597 + vertex 1.67297 1.11376 2.49496 + endloop + endfacet + facet normal 0.286473 -0.188792 0.939303 + outer loop + vertex 1.66933 1.11245 2.49587 + vertex 1.66714 1.11385 2.49682 + vertex 1.66662 1.11007 2.49622 + endloop + endfacet + facet normal 0.301243 -0.181835 0.936049 + outer loop + vertex 1.67349 1.11762 2.49557 + vertex 1.671 1.11839 2.49652 + vertex 1.67081 1.11524 2.49597 + endloop + endfacet + facet normal 0.283293 -0.184726 0.941074 + outer loop + vertex 1.66714 1.11385 2.49682 + vertex 1.66721 1.11862 2.49774 + vertex 1.66247 1.1137 2.4982 + endloop + endfacet + facet normal 0.28661 -0.184082 0.940196 + outer loop + vertex 1.66721 1.11862 2.49774 + vertex 1.66754 1.12366 2.49862 + vertex 1.66282 1.11877 2.4991 + endloop + endfacet + facet normal 0.284152 -0.189977 0.939769 + outer loop + vertex 1.65765 1.11393 2.49969 + vertex 1.66282 1.11877 2.4991 + vertex 1.65911 1.11918 2.50031 + endloop + endfacet + facet normal 0.285037 -0.190432 0.939409 + outer loop + vertex 1.65936 1.12236 2.50088 + vertex 1.65667 1.12003 2.50122 + vertex 1.65911 1.11918 2.50031 + endloop + endfacet + facet normal 0.28693 -0.192902 0.938328 + outer loop + vertex 1.66082 1.12509 2.50099 + vertex 1.65718 1.12376 2.50183 + vertex 1.65936 1.12236 2.50088 + endloop + endfacet + facet normal 0.286828 -0.192557 0.93843 + outer loop + vertex 1.66082 1.12509 2.50099 + vertex 1.66107 1.12822 2.50156 + vertex 1.65718 1.12376 2.50183 + endloop + endfacet + facet normal 0.287844 -0.189296 0.938783 + outer loop + vertex 1.66251 1.13341 2.50216 + vertex 1.66107 1.12822 2.50156 + vertex 1.66512 1.13118 2.50092 + endloop + endfacet + facet normal 0.288183 -0.188886 0.938761 + outer loop + vertex 1.66672 1.135 2.50119 + vertex 1.66251 1.13341 2.50216 + vertex 1.66512 1.13118 2.50092 + endloop + endfacet + facet normal 0.285501 -0.180281 0.941269 + outer loop + vertex 1.66672 1.135 2.50119 + vertex 1.66719 1.1388 2.50178 + vertex 1.66251 1.13341 2.50216 + endloop + endfacet + facet normal 0.287102 -0.181726 0.940504 + outer loop + vertex 1.66719 1.1388 2.50178 + vertex 1.66248 1.13864 2.50318 + vertex 1.66251 1.13341 2.50216 + endloop + endfacet + facet normal 0.296913 -0.192738 0.935251 + outer loop + vertex 1.66353 1.12741 2.50064 + vertex 1.66297 1.12363 2.50003 + vertex 1.66766 1.12893 2.49964 + endloop + endfacet + facet normal 0.304153 -0.19513 0.932425 + outer loop + vertex 1.66917 1.13421 2.50023 + vertex 1.66672 1.135 2.50119 + vertex 1.66512 1.13118 2.50092 + endloop + endfacet + facet normal 0.307532 -0.179311 0.93449 + outer loop + vertex 1.67236 1.12866 2.49804 + vertex 1.67285 1.13386 2.49887 + vertex 1.66766 1.12893 2.49964 + endloop + endfacet + facet normal 0.305399 -0.191671 0.932734 + outer loop + vertex 1.66946 1.13744 2.5008 + vertex 1.66672 1.135 2.50119 + vertex 1.66917 1.13421 2.50023 + endloop + endfacet + facet normal 0.296719 -0.18112 0.937632 + outer loop + vertex 1.66946 1.13744 2.5008 + vertex 1.66719 1.1388 2.50178 + vertex 1.66672 1.135 2.50119 + endloop + endfacet + facet normal 0.287272 -0.173249 0.942051 + outer loop + vertex 1.66719 1.1388 2.50178 + vertex 1.66704 1.14344 2.50267 + vertex 1.66248 1.13864 2.50318 + endloop + endfacet + facet normal 0.285305 -0.181836 0.94103 + outer loop + vertex 1.66251 1.13341 2.50216 + vertex 1.66248 1.13864 2.50318 + vertex 1.65763 1.1336 2.50368 + endloop + endfacet + facet normal 0.286452 -0.186649 0.939738 + outer loop + vertex 1.65729 1.12852 2.50278 + vertex 1.65763 1.1336 2.50368 + vertex 1.65288 1.12868 2.50415 + endloop + endfacet + facet normal 0.284918 -0.191438 0.939241 + outer loop + vertex 1.64772 1.12385 2.50473 + vertex 1.65288 1.12868 2.50415 + vertex 1.64918 1.12906 2.50535 + endloop + endfacet + facet normal 0.280702 -0.184418 0.941911 + outer loop + vertex 1.64945 1.13227 2.5059 + vertex 1.64675 1.12991 2.50624 + vertex 1.64918 1.12906 2.50535 + endloop + endfacet + facet normal 0.278027 -0.17477 0.94454 + outer loop + vertex 1.65091 1.13506 2.50599 + vertex 1.64726 1.13371 2.50681 + vertex 1.64945 1.13227 2.5059 + endloop + endfacet + facet normal 0.277482 -0.172995 0.945027 + outer loop + vertex 1.65091 1.13506 2.50599 + vertex 1.6511 1.13822 2.50651 + vertex 1.64726 1.13371 2.50681 + endloop + endfacet + facet normal 0.282115 -0.17641 0.943022 + outer loop + vertex 1.65357 1.13741 2.50562 + vertex 1.65304 1.13357 2.50506 + vertex 1.65766 1.13891 2.50468 + endloop + endfacet + facet normal 0.283006 -0.175443 0.942936 + outer loop + vertex 1.65766 1.13891 2.50468 + vertex 1.66278 1.14374 2.50404 + vertex 1.659 1.14419 2.50526 + endloop + endfacet + facet normal 0.279484 -0.176084 0.943866 + outer loop + vertex 1.65905 1.14742 2.50585 + vertex 1.65639 1.14485 2.50616 + vertex 1.659 1.14419 2.50526 + endloop + endfacet + facet normal 0.282358 -0.175232 0.943169 + outer loop + vertex 1.65234 1.14329 2.50708 + vertex 1.6511 1.13822 2.50651 + vertex 1.65503 1.14117 2.50588 + endloop + endfacet + facet normal 0.279476 -0.176075 0.94387 + outer loop + vertex 1.65905 1.14742 2.50585 + vertex 1.65638 1.14804 2.50676 + vertex 1.65639 1.14485 2.50616 + endloop + endfacet + facet normal 0.275317 -0.167388 0.946669 + outer loop + vertex 1.65753 1.15316 2.50733 + vertex 1.65638 1.14804 2.50676 + vertex 1.66034 1.15103 2.50613 + endloop + endfacet + facet normal 0.286095 -0.174449 0.942188 + outer loop + vertex 1.65234 1.14329 2.50708 + vertex 1.6524 1.14847 2.50802 + vertex 1.64761 1.1436 2.50857 + endloop + endfacet + facet normal 0.285235 -0.178866 0.94162 + outer loop + vertex 1.64731 1.13852 2.5077 + vertex 1.64761 1.1436 2.50857 + vertex 1.64289 1.13871 2.50907 + endloop + endfacet + facet normal 0.286776 -0.187421 0.939485 + outer loop + vertex 1.63771 1.13385 2.50968 + vertex 1.64289 1.13871 2.50907 + vertex 1.63915 1.13911 2.51029 + endloop + endfacet + facet normal 0.284528 -0.186142 0.940423 + outer loop + vertex 1.63942 1.14234 2.51085 + vertex 1.63671 1.13995 2.5112 + vertex 1.63915 1.13911 2.51029 + endloop + endfacet + facet normal 0.280423 -0.179018 0.943035 + outer loop + vertex 1.64091 1.14515 2.51094 + vertex 1.63724 1.14377 2.51177 + vertex 1.63942 1.14234 2.51085 + endloop + endfacet + facet normal 0.277734 -0.170489 0.945409 + outer loop + vertex 1.64091 1.14515 2.51094 + vertex 1.64109 1.14832 2.51146 + vertex 1.63724 1.14377 2.51177 + endloop + endfacet + facet normal 0.296012 -0.179957 0.938079 + outer loop + vertex 1.64357 1.14753 2.51057 + vertex 1.64304 1.14365 2.50999 + vertex 1.64763 1.14898 2.50957 + endloop + endfacet + facet normal 0.287295 -0.160988 0.944216 + outer loop + vertex 1.64763 1.14898 2.50957 + vertex 1.65278 1.15375 2.50881 + vertex 1.64888 1.15436 2.5101 + endloop + endfacet + facet normal 0.290614 -0.143543 0.946012 + outer loop + vertex 1.65273 1.15912 2.50964 + vertex 1.64888 1.15436 2.5101 + vertex 1.65278 1.15375 2.50881 + endloop + endfacet + facet normal 0.276454 -0.144323 0.950128 + outer loop + vertex 1.65278 1.15375 2.50881 + vertex 1.65747 1.15841 2.50816 + vertex 1.65273 1.15912 2.50964 + endloop + endfacet + facet normal 0.279055 -0.129664 0.951481 + outer loop + vertex 1.65747 1.15841 2.50816 + vertex 1.65777 1.16364 2.50878 + vertex 1.65273 1.15912 2.50964 + endloop + endfacet + facet normal 0.27418 -0.123818 0.953674 + outer loop + vertex 1.65273 1.15912 2.50964 + vertex 1.65777 1.16364 2.50878 + vertex 1.6538 1.16461 2.51005 + endloop + endfacet + facet normal 0.28911 -0.126373 0.948918 + outer loop + vertex 1.65273 1.15912 2.50964 + vertex 1.6538 1.16461 2.51005 + vertex 1.6497 1.16133 2.51086 + endloop + endfacet + facet normal 0.288154 -0.127735 0.949026 + outer loop + vertex 1.64874 1.15765 2.51066 + vertex 1.65273 1.15912 2.50964 + vertex 1.6497 1.16133 2.51086 + endloop + endfacet + facet normal 0.289021 -0.127946 0.948734 + outer loop + vertex 1.6497 1.16133 2.51086 + vertex 1.64596 1.15808 2.51156 + vertex 1.64874 1.15765 2.51066 + endloop + endfacet + facet normal 0.288907 -0.127804 0.948788 + outer loop + vertex 1.6464 1.1625 2.51202 + vertex 1.64596 1.15808 2.51156 + vertex 1.6497 1.16133 2.51086 + endloop + endfacet + facet normal 0.291777 -0.119855 0.948947 + outer loop + vertex 1.65051 1.16585 2.51118 + vertex 1.6464 1.1625 2.51202 + vertex 1.6497 1.16133 2.51086 + endloop + endfacet + facet normal 0.291509 -0.119492 0.949076 + outer loop + vertex 1.64747 1.168 2.51239 + vertex 1.6464 1.1625 2.51202 + vertex 1.65051 1.16585 2.51118 + endloop + endfacet + facet normal 0.293012 -0.117271 0.94889 + outer loop + vertex 1.65149 1.16957 2.51134 + vertex 1.64747 1.168 2.51239 + vertex 1.65051 1.16585 2.51118 + endloop + endfacet + facet normal 0.28087 -0.114243 0.952922 + outer loop + vertex 1.65426 1.16909 2.51047 + vertex 1.65149 1.16957 2.51134 + vertex 1.65051 1.16585 2.51118 + endloop + endfacet + facet normal 0.283691 -0.117785 0.951655 + outer loop + vertex 1.6538 1.16461 2.51005 + vertex 1.65426 1.16909 2.51047 + vertex 1.65051 1.16585 2.51118 + endloop + endfacet + facet normal 0.271907 -0.116911 0.955196 + outer loop + vertex 1.6538 1.16461 2.51005 + vertex 1.65805 1.16872 2.50934 + vertex 1.65426 1.16909 2.51047 + endloop + endfacet + facet normal 0.271129 -0.123152 0.954632 + outer loop + vertex 1.65798 1.17379 2.51002 + vertex 1.65426 1.16909 2.51047 + vertex 1.65805 1.16872 2.50934 + endloop + endfacet + facet normal 0.276894 -0.122864 0.953013 + outer loop + vertex 1.65805 1.16872 2.50934 + vertex 1.66254 1.17329 2.50863 + vertex 1.65798 1.17379 2.51002 + endloop + endfacet + facet normal 0.275998 -0.129396 0.952408 + outer loop + vertex 1.66254 1.17329 2.50863 + vertex 1.66292 1.17857 2.50924 + vertex 1.65798 1.17379 2.51002 + endloop + endfacet + facet normal 0.283524 -0.137713 0.949025 + outer loop + vertex 1.65798 1.17379 2.51002 + vertex 1.66292 1.17857 2.50924 + vertex 1.65918 1.17898 2.51041 + endloop + endfacet + facet normal 0.268785 -0.134665 0.95374 + outer loop + vertex 1.65798 1.17379 2.51002 + vertex 1.65918 1.17898 2.51041 + vertex 1.65525 1.17592 2.51109 + endloop + endfacet + facet normal 0.271557 -0.130969 0.953469 + outer loop + vertex 1.65401 1.1722 2.51093 + vertex 1.65798 1.17379 2.51002 + vertex 1.65525 1.17592 2.51109 + endloop + endfacet + facet normal 0.283694 -0.13481 0.949391 + outer loop + vertex 1.65525 1.17592 2.51109 + vertex 1.65132 1.17283 2.51182 + vertex 1.65401 1.1722 2.51093 + endloop + endfacet + facet normal 0.286108 -0.125395 0.949957 + outer loop + vertex 1.65401 1.1722 2.51093 + vertex 1.65132 1.17283 2.51182 + vertex 1.65149 1.16957 2.51134 + endloop + endfacet + facet normal 0.284745 -0.136272 0.948868 + outer loop + vertex 1.65252 1.17821 2.51223 + vertex 1.65132 1.17283 2.51182 + vertex 1.65525 1.17592 2.51109 + endloop + endfacet + facet normal 0.278822 -0.143644 0.949539 + outer loop + vertex 1.65669 1.17977 2.51125 + vertex 1.65252 1.17821 2.51223 + vertex 1.65525 1.17592 2.51109 + endloop + endfacet + facet normal 0.282778 -0.156215 0.946379 + outer loop + vertex 1.65669 1.17977 2.51125 + vertex 1.65718 1.18365 2.51174 + vertex 1.65252 1.17821 2.51223 + endloop + endfacet + facet normal 0.272091 -0.14664 0.951033 + outer loop + vertex 1.65718 1.18365 2.51174 + vertex 1.65245 1.18359 2.51308 + vertex 1.65252 1.17821 2.51223 + endloop + endfacet + facet normal 0.279849 -0.146184 0.948849 + outer loop + vertex 1.65252 1.17821 2.51223 + vertex 1.65245 1.18359 2.51308 + vertex 1.64768 1.17875 2.51375 + endloop + endfacet + facet normal 0.274523 -0.140599 0.951246 + outer loop + vertex 1.64768 1.17875 2.51375 + vertex 1.65245 1.18359 2.51308 + vertex 1.64763 1.18408 2.51455 + endloop + endfacet + facet normal 0.278505 -0.140398 0.950117 + outer loop + vertex 1.64763 1.18408 2.51455 + vertex 1.64371 1.17937 2.515 + vertex 1.64768 1.17875 2.51375 + endloop + endfacet + facet normal 0.274525 -0.13692 0.951782 + outer loop + vertex 1.64362 1.18267 2.5155 + vertex 1.64371 1.17937 2.515 + vertex 1.64763 1.18408 2.51455 + endloop + endfacet + facet normal 0.278716 -0.151111 0.948411 + outer loop + vertex 1.64362 1.18267 2.5155 + vertex 1.64763 1.18408 2.51455 + vertex 1.64486 1.18629 2.51571 + endloop + endfacet + facet normal 0.277416 -0.152801 0.948521 + outer loop + vertex 1.64763 1.18408 2.51455 + vertex 1.64877 1.18925 2.51505 + vertex 1.64486 1.18629 2.51571 + endloop + endfacet + facet normal 0.279115 -0.155237 0.947627 + outer loop + vertex 1.64877 1.18925 2.51505 + vertex 1.64612 1.18993 2.51594 + vertex 1.64486 1.18629 2.51571 + endloop + endfacet + facet normal 0.287326 -0.157884 0.944731 + outer loop + vertex 1.64612 1.18993 2.51594 + vertex 1.64213 1.18831 2.51688 + vertex 1.64486 1.18629 2.51571 + endloop + endfacet + facet normal 0.289886 -0.15432 0.944538 + outer loop + vertex 1.64213 1.18831 2.51688 + vertex 1.64098 1.18325 2.51641 + vertex 1.64486 1.18629 2.51571 + endloop + endfacet + facet normal 0.29284 -0.154898 0.943531 + outer loop + vertex 1.64098 1.18325 2.51641 + vertex 1.64213 1.18831 2.51688 + vertex 1.63715 1.18346 2.51763 + endloop + endfacet + facet normal 0.294271 -0.140097 0.945398 + outer loop + vertex 1.64098 1.18325 2.51641 + vertex 1.63715 1.18346 2.51763 + vertex 1.6371 1.17836 2.51689 + endloop + endfacet + facet normal 0.290291 -0.140234 0.946607 + outer loop + vertex 1.6371 1.17836 2.51689 + vertex 1.63715 1.18346 2.51763 + vertex 1.63246 1.17856 2.51834 + endloop + endfacet + facet normal 0.288363 -0.138262 0.947486 + outer loop + vertex 1.63246 1.17856 2.51834 + vertex 1.63715 1.18346 2.51763 + vertex 1.63278 1.18374 2.519 + endloop + endfacet + facet normal 0.284701 -0.138178 0.948605 + outer loop + vertex 1.63246 1.17856 2.51834 + vertex 1.63278 1.18374 2.519 + vertex 1.62783 1.17892 2.51978 + endloop + endfacet + facet normal 0.287174 -0.149923 0.946073 + outer loop + vertex 1.63715 1.18346 2.51763 + vertex 1.63749 1.18857 2.51834 + vertex 1.63278 1.18374 2.519 + endloop + endfacet + facet normal 0.284968 -0.147625 0.947101 + outer loop + vertex 1.63278 1.18374 2.519 + vertex 1.63749 1.18857 2.51834 + vertex 1.63287 1.18896 2.51979 + endloop + endfacet + facet normal 0.281518 -0.147714 0.948118 + outer loop + vertex 1.63287 1.18896 2.51979 + vertex 1.62896 1.18417 2.5202 + vertex 1.63278 1.18374 2.519 + endloop + endfacet + facet normal 0.284178 -0.153975 0.946327 + outer loop + vertex 1.63749 1.18857 2.51834 + vertex 1.63784 1.19368 2.51907 + vertex 1.63287 1.18896 2.51979 + endloop + endfacet + facet normal 0.286222 -0.154025 0.945702 + outer loop + vertex 1.63749 1.18857 2.51834 + vertex 1.64221 1.19338 2.51769 + vertex 1.63784 1.19368 2.51907 + endloop + endfacet + facet normal 0.286176 -0.154441 0.945648 + outer loop + vertex 1.64221 1.19338 2.51769 + vertex 1.64254 1.19845 2.51842 + vertex 1.63784 1.19368 2.51907 + endloop + endfacet + facet normal 0.286395 -0.154671 0.945545 + outer loop + vertex 1.63784 1.19368 2.51907 + vertex 1.64254 1.19845 2.51842 + vertex 1.63795 1.19885 2.51988 + endloop + endfacet + facet normal 0.284906 -0.154708 0.945988 + outer loop + vertex 1.63795 1.19885 2.51988 + vertex 1.63404 1.19411 2.52028 + vertex 1.63784 1.19368 2.51907 + endloop + endfacet + facet normal 0.286663 -0.152526 0.945812 + outer loop + vertex 1.64254 1.19845 2.51842 + vertex 1.64288 1.20356 2.51914 + vertex 1.63795 1.19885 2.51988 + endloop + endfacet + facet normal 0.283397 -0.152449 0.946808 + outer loop + vertex 1.64254 1.19845 2.51842 + vertex 1.64727 1.20326 2.51778 + vertex 1.64288 1.20356 2.51914 + endloop + endfacet + facet normal 0.283509 -0.151419 0.94694 + outer loop + vertex 1.64727 1.20326 2.51778 + vertex 1.64759 1.20835 2.5185 + vertex 1.64288 1.20356 2.51914 + endloop + endfacet + facet normal 0.282126 -0.149971 0.947583 + outer loop + vertex 1.64288 1.20356 2.51914 + vertex 1.64759 1.20835 2.5185 + vertex 1.64298 1.20874 2.51993 + endloop + endfacet + facet normal 0.287536 -0.149836 0.945977 + outer loop + vertex 1.64298 1.20874 2.51993 + vertex 1.63911 1.20398 2.52035 + vertex 1.64288 1.20356 2.51914 + endloop + endfacet + facet normal 0.282504 -0.146884 0.947954 + outer loop + vertex 1.64759 1.20835 2.5185 + vertex 1.64792 1.21351 2.5192 + vertex 1.64298 1.20874 2.51993 + endloop + endfacet + facet normal 0.274464 -0.146702 0.950341 + outer loop + vertex 1.64759 1.20835 2.5185 + vertex 1.65235 1.21319 2.51787 + vertex 1.64792 1.21351 2.5192 + endloop + endfacet + facet normal 0.274962 -0.142061 0.950902 + outer loop + vertex 1.65235 1.21319 2.51787 + vertex 1.6526 1.21833 2.51857 + vertex 1.64792 1.21351 2.5192 + endloop + endfacet + facet normal 0.274881 -0.141978 0.950938 + outer loop + vertex 1.64792 1.21351 2.5192 + vertex 1.6526 1.21833 2.51857 + vertex 1.64799 1.21875 2.51996 + endloop + endfacet + facet normal 0.281317 -0.141798 0.949081 + outer loop + vertex 1.64799 1.21875 2.51996 + vertex 1.64413 1.21392 2.52039 + vertex 1.64792 1.21351 2.5192 + endloop + endfacet + facet normal 0.275626 -0.135994 0.951596 + outer loop + vertex 1.6526 1.21833 2.51857 + vertex 1.65286 1.22351 2.51923 + vertex 1.64799 1.21875 2.51996 + endloop + endfacet + facet normal 0.278855 -0.136033 0.95065 + outer loop + vertex 1.6526 1.21833 2.51857 + vertex 1.65713 1.22308 2.51792 + vertex 1.65286 1.22351 2.51923 + endloop + endfacet + facet normal 0.280394 -0.124305 0.951802 + outer loop + vertex 1.65713 1.22308 2.51792 + vertex 1.65734 1.22812 2.51851 + vertex 1.65286 1.22351 2.51923 + endloop + endfacet + facet normal 0.286818 -0.130981 0.948989 + outer loop + vertex 1.65286 1.22351 2.51923 + vertex 1.65734 1.22812 2.51851 + vertex 1.65294 1.22879 2.51993 + endloop + endfacet + facet normal 0.276665 -0.131222 0.951965 + outer loop + vertex 1.65294 1.22879 2.51993 + vertex 1.64911 1.22399 2.52039 + vertex 1.65286 1.22351 2.51923 + endloop + endfacet + facet normal 0.28895 -0.118889 0.949933 + outer loop + vertex 1.65734 1.22812 2.51851 + vertex 1.65783 1.23345 2.51903 + vertex 1.65294 1.22879 2.51993 + endloop + endfacet + facet normal 0.323518 -0.12095 0.93846 + outer loop + vertex 1.65734 1.22812 2.51851 + vertex 1.66175 1.23243 2.51755 + vertex 1.65783 1.23345 2.51903 + endloop + endfacet + facet normal 0.329845 -0.0972695 0.939011 + outer loop + vertex 1.66175 1.23243 2.51755 + vertex 1.66267 1.23824 2.51783 + vertex 1.65783 1.23345 2.51903 + endloop + endfacet + facet normal 0.349333 -0.11937 0.929364 + outer loop + vertex 1.65783 1.23345 2.51903 + vertex 1.66267 1.23824 2.51783 + vertex 1.65792 1.23891 2.5197 + endloop + endfacet + facet normal 0.303622 -0.120559 0.945135 + outer loop + vertex 1.65792 1.23891 2.5197 + vertex 1.65408 1.23406 2.52031 + vertex 1.65783 1.23345 2.51903 + endloop + endfacet + facet normal 0.35168 -0.105104 0.930201 + outer loop + vertex 1.66267 1.23824 2.51783 + vertex 1.6624 1.24363 2.51854 + vertex 1.65792 1.23891 2.5197 + endloop + endfacet + facet normal 0.311229 -0.107051 0.944286 + outer loop + vertex 1.66128 1.22741 2.51714 + vertex 1.66175 1.23243 2.51755 + vertex 1.65734 1.22812 2.51851 + endloop + endfacet + facet normal 0.307747 -0.124445 0.943295 + outer loop + vertex 1.65713 1.22308 2.51792 + vertex 1.66128 1.22741 2.51714 + vertex 1.65734 1.22812 2.51851 + endloop + endfacet + facet normal 0.298334 -0.114674 0.947548 + outer loop + vertex 1.66104 1.22297 2.51667 + vertex 1.66128 1.22741 2.51714 + vertex 1.65713 1.22308 2.51792 + endloop + endfacet + facet normal 0.297316 -0.131092 0.945737 + outer loop + vertex 1.66104 1.22297 2.51667 + vertex 1.65713 1.22308 2.51792 + vertex 1.65736 1.21809 2.51715 + endloop + endfacet + facet normal 0.291109 -0.126155 0.948336 + outer loop + vertex 1.66143 1.21991 2.51615 + vertex 1.66104 1.22297 2.51667 + vertex 1.65736 1.21809 2.51715 + endloop + endfacet + facet normal 0.295379 -0.137313 0.945461 + outer loop + vertex 1.66143 1.21991 2.51615 + vertex 1.65736 1.21809 2.51715 + vertex 1.66027 1.21618 2.51596 + endloop + endfacet + facet normal 0.364071 -0.157211 0.918007 + outer loop + vertex 1.66407 1.21938 2.51501 + vertex 1.66143 1.21991 2.51615 + vertex 1.66027 1.21618 2.51596 + endloop + endfacet + facet normal 0.34915 -0.136872 0.927017 + outer loop + vertex 1.66292 1.21401 2.51465 + vertex 1.66407 1.21938 2.51501 + vertex 1.66027 1.21618 2.51596 + endloop + endfacet + facet normal 0.337971 -0.151619 0.928864 + outer loop + vertex 1.65906 1.21247 2.5158 + vertex 1.66292 1.21401 2.51465 + vertex 1.66027 1.21618 2.51596 + endloop + endfacet + facet normal 0.28681 -0.135713 0.948326 + outer loop + vertex 1.66027 1.21618 2.51596 + vertex 1.65633 1.21297 2.5167 + vertex 1.65906 1.21247 2.5158 + endloop + endfacet + facet normal 0.284741 -0.145477 0.947501 + outer loop + vertex 1.65906 1.21247 2.5158 + vertex 1.65633 1.21297 2.5167 + vertex 1.65641 1.20979 2.51619 + endloop + endfacet + facet normal 0.290895 -0.151978 0.944607 + outer loop + vertex 1.65906 1.21247 2.5158 + vertex 1.65641 1.20979 2.51619 + vertex 1.65905 1.20922 2.51528 + endloop + endfacet + facet normal 0.289126 -0.159121 0.943974 + outer loop + vertex 1.65905 1.20922 2.51528 + vertex 1.65641 1.20979 2.51619 + vertex 1.65513 1.20613 2.51596 + endloop + endfacet + facet normal 0.281668 -0.148779 0.947907 + outer loop + vertex 1.65784 1.20401 2.51482 + vertex 1.65905 1.20922 2.51528 + vertex 1.65513 1.20613 2.51596 + endloop + endfacet + facet normal 0.276144 -0.156067 0.948361 + outer loop + vertex 1.65387 1.20248 2.51573 + vertex 1.65784 1.20401 2.51482 + vertex 1.65513 1.20613 2.51596 + endloop + endfacet + facet normal 0.273269 -0.155134 0.949346 + outer loop + vertex 1.65513 1.20613 2.51596 + vertex 1.65118 1.20302 2.51659 + vertex 1.65387 1.20248 2.51573 + endloop + endfacet + facet normal 0.273324 -0.154899 0.949368 + outer loop + vertex 1.65387 1.20248 2.51573 + vertex 1.65118 1.20302 2.51659 + vertex 1.65124 1.19986 2.51606 + endloop + endfacet + facet normal 0.270281 -0.151675 0.950759 + outer loop + vertex 1.65387 1.20248 2.51573 + vertex 1.65124 1.19986 2.51606 + vertex 1.65391 1.19923 2.5152 + endloop + endfacet + facet normal 0.272378 -0.153906 0.949802 + outer loop + vertex 1.65233 1.20809 2.51708 + vertex 1.65118 1.20302 2.51659 + vertex 1.65513 1.20613 2.51596 + endloop + endfacet + facet normal 0.278865 -0.15517 0.947711 + outer loop + vertex 1.65118 1.20302 2.51659 + vertex 1.65233 1.20809 2.51708 + vertex 1.64727 1.20326 2.51778 + endloop + endfacet + facet normal 0.278991 -0.153915 0.947879 + outer loop + vertex 1.65118 1.20302 2.51659 + vertex 1.64727 1.20326 2.51778 + vertex 1.64721 1.19819 2.51697 + endloop + endfacet + facet normal 0.279652 -0.154481 0.947592 + outer loop + vertex 1.65124 1.19986 2.51606 + vertex 1.65118 1.20302 2.51659 + vertex 1.64721 1.19819 2.51697 + endloop + endfacet + facet normal 0.279496 -0.154038 0.94771 + outer loop + vertex 1.65124 1.19986 2.51606 + vertex 1.64721 1.19819 2.51697 + vertex 1.64999 1.19618 2.51583 + endloop + endfacet + facet normal 0.270417 -0.151153 0.950803 + outer loop + vertex 1.65391 1.19923 2.5152 + vertex 1.65124 1.19986 2.51606 + vertex 1.64999 1.19618 2.51583 + endloop + endfacet + facet normal 0.271741 -0.152992 0.950132 + outer loop + vertex 1.65275 1.19401 2.51469 + vertex 1.65391 1.19923 2.5152 + vertex 1.64999 1.19618 2.51583 + endloop + endfacet + facet normal 0.271386 -0.153459 0.950158 + outer loop + vertex 1.64874 1.19252 2.51559 + vertex 1.65275 1.19401 2.51469 + vertex 1.64999 1.19618 2.51583 + endloop + endfacet + facet normal 0.281011 -0.156539 0.946852 + outer loop + vertex 1.64999 1.19618 2.51583 + vertex 1.64608 1.19311 2.51648 + vertex 1.64874 1.19252 2.51559 + endloop + endfacet + facet normal 0.28074 -0.157606 0.946755 + outer loop + vertex 1.64874 1.19252 2.51559 + vertex 1.64608 1.19311 2.51648 + vertex 1.64612 1.18993 2.51594 + endloop + endfacet + facet normal 0.272223 -0.156103 0.949488 + outer loop + vertex 1.64874 1.19252 2.51559 + vertex 1.64877 1.18925 2.51505 + vertex 1.65275 1.19401 2.51469 + endloop + endfacet + facet normal 0.270923 -0.154975 0.950044 + outer loop + vertex 1.65275 1.19401 2.51469 + vertex 1.64877 1.18925 2.51505 + vertex 1.65269 1.18877 2.51385 + endloop + endfacet + facet normal 0.267376 -0.155091 0.951029 + outer loop + vertex 1.65269 1.18877 2.51385 + vertex 1.65748 1.19361 2.51329 + vertex 1.65275 1.19401 2.51469 + endloop + endfacet + facet normal 0.267931 -0.150573 0.951599 + outer loop + vertex 1.65748 1.19361 2.51329 + vertex 1.65775 1.19877 2.51403 + vertex 1.65275 1.19401 2.51469 + endloop + endfacet + facet normal 0.280461 -0.150693 0.947963 + outer loop + vertex 1.65748 1.19361 2.51329 + vertex 1.66206 1.19842 2.5127 + vertex 1.65775 1.19877 2.51403 + endloop + endfacet + facet normal 0.282098 -0.1368 0.949582 + outer loop + vertex 1.66206 1.19842 2.5127 + vertex 1.66224 1.20342 2.51337 + vertex 1.65775 1.19877 2.51403 + endloop + endfacet + facet normal 0.292282 -0.147309 0.944919 + outer loop + vertex 1.65775 1.19877 2.51403 + vertex 1.66224 1.20342 2.51337 + vertex 1.65784 1.20401 2.51482 + endloop + endfacet + facet normal 0.27049 -0.147892 0.951296 + outer loop + vertex 1.65784 1.20401 2.51482 + vertex 1.65391 1.19923 2.5152 + vertex 1.65775 1.19877 2.51403 + endloop + endfacet + facet normal 0.294678 -0.132906 0.946309 + outer loop + vertex 1.66224 1.20342 2.51337 + vertex 1.66265 1.20861 2.51397 + vertex 1.65784 1.20401 2.51482 + endloop + endfacet + facet normal 0.276189 -0.146383 0.94989 + outer loop + vertex 1.66224 1.19346 2.51188 + vertex 1.66206 1.19842 2.5127 + vertex 1.65748 1.19361 2.51329 + endloop + endfacet + facet normal 0.275536 -0.155428 0.948642 + outer loop + vertex 1.65721 1.18851 2.51254 + vertex 1.66224 1.19346 2.51188 + vertex 1.65748 1.19361 2.51329 + endloop + endfacet + facet normal 0.272229 -0.151861 0.950174 + outer loop + vertex 1.66108 1.18834 2.5114 + vertex 1.66224 1.19346 2.51188 + vertex 1.65721 1.18851 2.51254 + endloop + endfacet + facet normal 0.271768 -0.157215 0.949434 + outer loop + vertex 1.66108 1.18834 2.5114 + vertex 1.65721 1.18851 2.51254 + vertex 1.65718 1.18365 2.51174 + endloop + endfacet + facet normal 0.274677 -0.159726 0.948177 + outer loop + vertex 1.66088 1.18513 2.51092 + vertex 1.66108 1.18834 2.5114 + vertex 1.65718 1.18365 2.51174 + endloop + endfacet + facet normal 0.274537 -0.159315 0.948287 + outer loop + vertex 1.66088 1.18513 2.51092 + vertex 1.65718 1.18365 2.51174 + vertex 1.65939 1.18224 2.51086 + endloop + endfacet + facet normal 0.292484 -0.168432 0.94132 + outer loop + vertex 1.66296 1.18363 2.51 + vertex 1.66088 1.18513 2.51092 + vertex 1.65939 1.18224 2.51086 + endloop + endfacet + facet normal 0.28645 -0.149776 0.946316 + outer loop + vertex 1.65939 1.18224 2.51086 + vertex 1.65918 1.17898 2.51041 + vertex 1.66296 1.18363 2.51 + endloop + endfacet + facet normal 0.271455 -0.149417 0.950782 + outer loop + vertex 1.65939 1.18224 2.51086 + vertex 1.65669 1.17977 2.51125 + vertex 1.65918 1.17898 2.51041 + endloop + endfacet + facet normal 0.296735 -0.162392 0.941051 + outer loop + vertex 1.66352 1.18759 2.51051 + vertex 1.66088 1.18513 2.51092 + vertex 1.66296 1.18363 2.51 + endloop + endfacet + facet normal 0.353501 -0.167767 0.920267 + outer loop + vertex 1.66352 1.18759 2.51051 + vertex 1.66296 1.18363 2.51 + vertex 1.66725 1.18894 2.50932 + endloop + endfacet + facet normal 0.35472 -0.172289 0.918961 + outer loop + vertex 1.66352 1.18759 2.51051 + vertex 1.66725 1.18894 2.50932 + vertex 1.66495 1.19145 2.51068 + endloop + endfacet + facet normal 0.297319 -0.152105 0.942584 + outer loop + vertex 1.66495 1.19145 2.51068 + vertex 1.66108 1.18834 2.5114 + vertex 1.66352 1.18759 2.51051 + endloop + endfacet + facet normal 0.301295 -0.157538 0.940427 + outer loop + vertex 1.66224 1.19346 2.51188 + vertex 1.66108 1.18834 2.5114 + vertex 1.66495 1.19145 2.51068 + endloop + endfacet + facet normal 0.305262 -0.151972 0.940064 + outer loop + vertex 1.66622 1.19525 2.51088 + vertex 1.66224 1.19346 2.51188 + vertex 1.66495 1.19145 2.51068 + endloop + endfacet + facet normal 0.388908 -0.178144 0.903889 + outer loop + vertex 1.66854 1.19439 2.50972 + vertex 1.66622 1.19525 2.51088 + vertex 1.66495 1.19145 2.51068 + endloop + endfacet + facet normal 0.298976 -0.135429 0.944602 + outer loop + vertex 1.66622 1.19525 2.51088 + vertex 1.66592 1.19831 2.51142 + vertex 1.66224 1.19346 2.51188 + endloop + endfacet + facet normal 0.309149 -0.143571 0.940114 + outer loop + vertex 1.66592 1.19831 2.51142 + vertex 1.66206 1.19842 2.5127 + vertex 1.66224 1.19346 2.51188 + endloop + endfacet + facet normal 0.310759 -0.119062 0.943002 + outer loop + vertex 1.66592 1.19831 2.51142 + vertex 1.66613 1.2027 2.5119 + vertex 1.66206 1.19842 2.5127 + endloop + endfacet + facet normal 0.327515 -0.136442 0.934942 + outer loop + vertex 1.66206 1.19842 2.5127 + vertex 1.66613 1.2027 2.5119 + vertex 1.66224 1.20342 2.51337 + endloop + endfacet + facet normal 0.332194 -0.113923 0.936306 + outer loop + vertex 1.66613 1.2027 2.5119 + vertex 1.66644 1.20763 2.51239 + vertex 1.66224 1.20342 2.51337 + endloop + endfacet + facet normal 0.372338 -0.154171 0.915203 + outer loop + vertex 1.66725 1.18894 2.50932 + vertex 1.66854 1.19439 2.50972 + vertex 1.66495 1.19145 2.51068 + endloop + endfacet + facet normal 0.326933 -0.144589 0.933921 + outer loop + vertex 1.66725 1.18894 2.50932 + vertex 1.66296 1.18363 2.51 + vertex 1.66722 1.18348 2.50849 + endloop + endfacet + facet normal 0.326941 -0.144485 0.933934 + outer loop + vertex 1.66292 1.17857 2.50924 + vertex 1.66722 1.18348 2.50849 + vertex 1.66296 1.18363 2.51 + endloop + endfacet + facet normal 0.313239 -0.131467 0.940531 + outer loop + vertex 1.66755 1.17819 2.50764 + vertex 1.66722 1.18348 2.50849 + vertex 1.66292 1.17857 2.50924 + endloop + endfacet + facet normal 0.294715 -0.160054 0.942086 + outer loop + vertex 1.66352 1.18759 2.51051 + vertex 1.66108 1.18834 2.5114 + vertex 1.66088 1.18513 2.51092 + endloop + endfacet + facet normal 0.26762 -0.155345 0.950919 + outer loop + vertex 1.65721 1.18851 2.51254 + vertex 1.65748 1.19361 2.51329 + vertex 1.65269 1.18877 2.51385 + endloop + endfacet + facet normal 0.267827 -0.153194 0.95121 + outer loop + vertex 1.65245 1.18359 2.51308 + vertex 1.65721 1.18851 2.51254 + vertex 1.65269 1.18877 2.51385 + endloop + endfacet + facet normal 0.269761 -0.152613 0.950757 + outer loop + vertex 1.65275 1.19401 2.51469 + vertex 1.65775 1.19877 2.51403 + vertex 1.65391 1.19923 2.5152 + endloop + endfacet + facet normal 0.279355 -0.154238 0.947719 + outer loop + vertex 1.64721 1.19819 2.51697 + vertex 1.64608 1.19311 2.51648 + vertex 1.64999 1.19618 2.51583 + endloop + endfacet + facet normal 0.285438 -0.155405 0.945714 + outer loop + vertex 1.64608 1.19311 2.51648 + vertex 1.64721 1.19819 2.51697 + vertex 1.64221 1.19338 2.51769 + endloop + endfacet + facet normal 0.285399 -0.155756 0.945668 + outer loop + vertex 1.64608 1.19311 2.51648 + vertex 1.64221 1.19338 2.51769 + vertex 1.64213 1.18831 2.51688 + endloop + endfacet + facet normal 0.274628 -0.151425 0.949553 + outer loop + vertex 1.65387 1.20248 2.51573 + vertex 1.65391 1.19923 2.5152 + vertex 1.65784 1.20401 2.51482 + endloop + endfacet + facet normal 0.314484 -0.155452 0.936448 + outer loop + vertex 1.65784 1.20401 2.51482 + vertex 1.66265 1.20861 2.51397 + vertex 1.65905 1.20922 2.51528 + endloop + endfacet + facet normal 0.318868 -0.133503 0.93835 + outer loop + vertex 1.66292 1.21401 2.51465 + vertex 1.65905 1.20922 2.51528 + vertex 1.66265 1.20861 2.51397 + endloop + endfacet + facet normal 0.272532 -0.153681 0.949794 + outer loop + vertex 1.65641 1.20979 2.51619 + vertex 1.65233 1.20809 2.51708 + vertex 1.65513 1.20613 2.51596 + endloop + endfacet + facet normal 0.269968 -0.146521 0.951656 + outer loop + vertex 1.65641 1.20979 2.51619 + vertex 1.65633 1.21297 2.5167 + vertex 1.65233 1.20809 2.51708 + endloop + endfacet + facet normal 0.271789 -0.148078 0.950896 + outer loop + vertex 1.65633 1.21297 2.5167 + vertex 1.65235 1.21319 2.51787 + vertex 1.65233 1.20809 2.51708 + endloop + endfacet + facet normal 0.272601 -0.13931 0.951988 + outer loop + vertex 1.65633 1.21297 2.5167 + vertex 1.65736 1.21809 2.51715 + vertex 1.65235 1.21319 2.51787 + endloop + endfacet + facet normal 0.337332 -0.149595 0.929424 + outer loop + vertex 1.65906 1.21247 2.5158 + vertex 1.65905 1.20922 2.51528 + vertex 1.66292 1.21401 2.51465 + endloop + endfacet + facet normal 0.291975 -0.142654 0.945728 + outer loop + vertex 1.65736 1.21809 2.51715 + vertex 1.65633 1.21297 2.5167 + vertex 1.66027 1.21618 2.51596 + endloop + endfacet + facet normal 0.275906 -0.133046 0.951932 + outer loop + vertex 1.65736 1.21809 2.51715 + vertex 1.65713 1.22308 2.51792 + vertex 1.6526 1.21833 2.51857 + endloop + endfacet + facet normal 0.27513 -0.142063 0.950853 + outer loop + vertex 1.65235 1.21319 2.51787 + vertex 1.65736 1.21809 2.51715 + vertex 1.6526 1.21833 2.51857 + endloop + endfacet + facet normal 0.275644 -0.14793 0.949809 + outer loop + vertex 1.65233 1.20809 2.51708 + vertex 1.65235 1.21319 2.51787 + vertex 1.64759 1.20835 2.5185 + endloop + endfacet + facet normal 0.275336 -0.151242 0.949377 + outer loop + vertex 1.64727 1.20326 2.51778 + vertex 1.65233 1.20809 2.51708 + vertex 1.64759 1.20835 2.5185 + endloop + endfacet + facet normal 0.284606 -0.153714 0.946241 + outer loop + vertex 1.64721 1.19819 2.51697 + vertex 1.64727 1.20326 2.51778 + vertex 1.64254 1.19845 2.51842 + endloop + endfacet + facet normal 0.284539 -0.154407 0.946148 + outer loop + vertex 1.64221 1.19338 2.51769 + vertex 1.64721 1.19819 2.51697 + vertex 1.64254 1.19845 2.51842 + endloop + endfacet + facet normal 0.287804 -0.155678 0.944951 + outer loop + vertex 1.64213 1.18831 2.51688 + vertex 1.64221 1.19338 2.51769 + vertex 1.63749 1.18857 2.51834 + endloop + endfacet + facet normal 0.288359 -0.149951 0.945708 + outer loop + vertex 1.63715 1.18346 2.51763 + vertex 1.64213 1.18831 2.51688 + vertex 1.63749 1.18857 2.51834 + endloop + endfacet + facet normal 0.287095 -0.15721 0.944913 + outer loop + vertex 1.64612 1.18993 2.51594 + vertex 1.64608 1.19311 2.51648 + vertex 1.64213 1.18831 2.51688 + endloop + endfacet + facet normal 0.278981 -0.155713 0.947588 + outer loop + vertex 1.64874 1.19252 2.51559 + vertex 1.64612 1.18993 2.51594 + vertex 1.64877 1.18925 2.51505 + endloop + endfacet + facet normal 0.271448 -0.151672 0.950427 + outer loop + vertex 1.64763 1.18408 2.51455 + vertex 1.65269 1.18877 2.51385 + vertex 1.64877 1.18925 2.51505 + endloop + endfacet + facet normal 0.284005 -0.136248 0.949093 + outer loop + vertex 1.64362 1.18267 2.5155 + vertex 1.64104 1.18007 2.5159 + vertex 1.64371 1.17937 2.515 + endloop + endfacet + facet normal 0.286908 -0.125874 0.949652 + outer loop + vertex 1.64371 1.17937 2.515 + vertex 1.64104 1.18007 2.5159 + vertex 1.63987 1.17635 2.51576 + endloop + endfacet + facet normal 0.293752 -0.127933 0.947282 + outer loop + vertex 1.64104 1.18007 2.5159 + vertex 1.6371 1.17836 2.51689 + vertex 1.63987 1.17635 2.51576 + endloop + endfacet + facet normal 0.272793 -0.153214 0.949794 + outer loop + vertex 1.65245 1.18359 2.51308 + vertex 1.65269 1.18877 2.51385 + vertex 1.64763 1.18408 2.51455 + endloop + endfacet + facet normal 0.271782 -0.157215 0.94943 + outer loop + vertex 1.65718 1.18365 2.51174 + vertex 1.65721 1.18851 2.51254 + vertex 1.65245 1.18359 2.51308 + endloop + endfacet + facet normal 0.276825 -0.155688 0.948224 + outer loop + vertex 1.65939 1.18224 2.51086 + vertex 1.65718 1.18365 2.51174 + vertex 1.65669 1.17977 2.51125 + endloop + endfacet + facet normal 0.289455 -0.137207 0.947307 + outer loop + vertex 1.65132 1.17283 2.51182 + vertex 1.65252 1.17821 2.51223 + vertex 1.64738 1.17339 2.51311 + endloop + endfacet + facet normal 0.292072 -0.121704 0.948621 + outer loop + vertex 1.65132 1.17283 2.51182 + vertex 1.64738 1.17339 2.51311 + vertex 1.64747 1.168 2.51239 + endloop + endfacet + facet normal 0.294504 -0.121563 0.947887 + outer loop + vertex 1.64747 1.168 2.51239 + vertex 1.64738 1.17339 2.51311 + vertex 1.64279 1.16867 2.51393 + endloop + endfacet + facet normal 0.294632 -0.120798 0.947945 + outer loop + vertex 1.64245 1.16334 2.51335 + vertex 1.64747 1.168 2.51239 + vertex 1.64279 1.16867 2.51393 + endloop + endfacet + facet normal 0.296106 -0.120841 0.94748 + outer loop + vertex 1.64245 1.16334 2.51335 + vertex 1.64279 1.16867 2.51393 + vertex 1.63791 1.16393 2.51485 + endloop + endfacet + facet normal 0.293904 -0.134732 0.946292 + outer loop + vertex 1.63789 1.15868 2.51411 + vertex 1.64245 1.16334 2.51335 + vertex 1.63791 1.16393 2.51485 + endloop + endfacet + facet normal 0.295224 -0.13468 0.945888 + outer loop + vertex 1.63791 1.16393 2.51485 + vertex 1.63411 1.1591 2.51535 + vertex 1.63789 1.15868 2.51411 + endloop + endfacet + facet normal 0.290902 -0.131568 0.947663 + outer loop + vertex 1.64214 1.15827 2.51275 + vertex 1.64245 1.16334 2.51335 + vertex 1.63789 1.15868 2.51411 + endloop + endfacet + facet normal 0.291147 -0.131574 0.947587 + outer loop + vertex 1.64214 1.15827 2.51275 + vertex 1.6464 1.1625 2.51202 + vertex 1.64245 1.16334 2.51335 + endloop + endfacet + facet normal 0.290064 -0.116914 0.949839 + outer loop + vertex 1.64279 1.16867 2.51393 + vertex 1.64738 1.17339 2.51311 + vertex 1.64269 1.17408 2.51462 + endloop + endfacet + facet normal 0.294373 -0.116668 0.948543 + outer loop + vertex 1.64269 1.17408 2.51462 + vertex 1.63891 1.16926 2.5152 + vertex 1.64279 1.16867 2.51393 + endloop + endfacet + facet normal 0.288132 -0.111471 0.951081 + outer loop + vertex 1.63874 1.17262 2.51565 + vertex 1.63891 1.16926 2.5152 + vertex 1.64269 1.17408 2.51462 + endloop + endfacet + facet normal 0.289521 -0.115881 0.950131 + outer loop + vertex 1.63874 1.17262 2.51565 + vertex 1.64269 1.17408 2.51462 + vertex 1.63987 1.17635 2.51576 + endloop + endfacet + facet normal 0.290236 -0.116091 0.949887 + outer loop + vertex 1.63987 1.17635 2.51576 + vertex 1.63607 1.17318 2.51654 + vertex 1.63874 1.17262 2.51565 + endloop + endfacet + facet normal 0.296361 -0.124163 0.946971 + outer loop + vertex 1.6371 1.17836 2.51689 + vertex 1.63607 1.17318 2.51654 + vertex 1.63987 1.17635 2.51576 + endloop + endfacet + facet normal 0.28448 -0.122497 0.950824 + outer loop + vertex 1.64269 1.17408 2.51462 + vertex 1.64371 1.17937 2.515 + vertex 1.63987 1.17635 2.51576 + endloop + endfacet + facet normal 0.281858 -0.12205 0.951661 + outer loop + vertex 1.64269 1.17408 2.51462 + vertex 1.64768 1.17875 2.51375 + vertex 1.64371 1.17937 2.515 + endloop + endfacet + facet normal 0.287966 -0.129094 0.948899 + outer loop + vertex 1.64738 1.17339 2.51311 + vertex 1.64768 1.17875 2.51375 + vertex 1.64269 1.17408 2.51462 + endloop + endfacet + facet normal 0.282317 -0.128981 0.950611 + outer loop + vertex 1.64738 1.17339 2.51311 + vertex 1.65252 1.17821 2.51223 + vertex 1.64768 1.17875 2.51375 + endloop + endfacet + facet normal 0.273975 -0.141897 0.951211 + outer loop + vertex 1.65918 1.17898 2.51041 + vertex 1.65669 1.17977 2.51125 + vertex 1.65525 1.17592 2.51109 + endloop + endfacet + facet normal 0.282306 -0.146246 0.948112 + outer loop + vertex 1.66296 1.18363 2.51 + vertex 1.65918 1.17898 2.51041 + vertex 1.66292 1.17857 2.50924 + endloop + endfacet + facet normal 0.31333 -0.130696 0.940608 + outer loop + vertex 1.66254 1.17329 2.50863 + vertex 1.66755 1.17819 2.50764 + vertex 1.66292 1.17857 2.50924 + endloop + endfacet + facet normal 0.299496 -0.115207 0.947116 + outer loop + vertex 1.66655 1.17249 2.50726 + vertex 1.66755 1.17819 2.50764 + vertex 1.66254 1.17329 2.50863 + endloop + endfacet + facet normal 0.298466 -0.119938 0.946854 + outer loop + vertex 1.66226 1.16815 2.50806 + vertex 1.66655 1.17249 2.50726 + vertex 1.66254 1.17329 2.50863 + endloop + endfacet + facet normal 0.290105 -0.110986 0.950537 + outer loop + vertex 1.66617 1.16789 2.50684 + vertex 1.66655 1.17249 2.50726 + vertex 1.66226 1.16815 2.50806 + endloop + endfacet + facet normal 0.289291 -0.11952 0.94975 + outer loop + vertex 1.66617 1.16789 2.50684 + vertex 1.66226 1.16815 2.50806 + vertex 1.66248 1.16308 2.50736 + endloop + endfacet + facet normal 0.288501 -0.118878 0.950071 + outer loop + vertex 1.66651 1.16475 2.50634 + vertex 1.66617 1.16789 2.50684 + vertex 1.66248 1.16308 2.50736 + endloop + endfacet + facet normal 0.291584 -0.127618 0.947994 + outer loop + vertex 1.66651 1.16475 2.50634 + vertex 1.66248 1.16308 2.50736 + vertex 1.6654 1.16101 2.50618 + endloop + endfacet + facet normal 0.354192 -0.145155 0.923839 + outer loop + vertex 1.66909 1.16419 2.50527 + vertex 1.66651 1.16475 2.50634 + vertex 1.6654 1.16101 2.50618 + endloop + endfacet + facet normal 0.288338 -0.132393 0.948332 + outer loop + vertex 1.66248 1.16308 2.50736 + vertex 1.6615 1.1579 2.50693 + vertex 1.6654 1.16101 2.50618 + endloop + endfacet + facet normal 0.28903 -0.133344 0.947988 + outer loop + vertex 1.6654 1.16101 2.50618 + vertex 1.6615 1.1579 2.50693 + vertex 1.66424 1.15728 2.50601 + endloop + endfacet + facet normal 0.338112 -0.147767 0.929433 + outer loop + vertex 1.66424 1.15728 2.50601 + vertex 1.6681 1.15889 2.50486 + vertex 1.6654 1.16101 2.50618 + endloop + endfacet + facet normal 0.346989 -0.135586 0.928017 + outer loop + vertex 1.6681 1.15889 2.50486 + vertex 1.66909 1.16419 2.50527 + vertex 1.6654 1.16101 2.50618 + endloop + endfacet + facet normal 0.403481 -0.144289 0.903539 + outer loop + vertex 1.6681 1.15889 2.50486 + vertex 1.67249 1.16369 2.50367 + vertex 1.66909 1.16419 2.50527 + endloop + endfacet + facet normal 0.409374 -0.11054 0.905645 + outer loop + vertex 1.67243 1.16902 2.50435 + vertex 1.66909 1.16419 2.50527 + vertex 1.67249 1.16369 2.50367 + endloop + endfacet + facet normal 0.426121 -0.123935 0.896137 + outer loop + vertex 1.66893 1.16749 2.5058 + vertex 1.66909 1.16419 2.50527 + vertex 1.67243 1.16902 2.50435 + endloop + endfacet + facet normal 0.357381 -0.131929 0.924594 + outer loop + vertex 1.66893 1.16749 2.5058 + vertex 1.66651 1.16475 2.50634 + vertex 1.66909 1.16419 2.50527 + endloop + endfacet + facet normal 0.372578 -0.111631 0.921262 + outer loop + vertex 1.67273 1.15837 2.50293 + vertex 1.67249 1.16369 2.50367 + vertex 1.6681 1.15889 2.50486 + endloop + endfacet + facet normal 0.336401 -0.111359 0.935112 + outer loop + vertex 1.66893 1.16749 2.5058 + vertex 1.66617 1.16789 2.50684 + vertex 1.66651 1.16475 2.50634 + endloop + endfacet + facet normal 0.273835 -0.120803 0.95416 + outer loop + vertex 1.66248 1.16308 2.50736 + vertex 1.66226 1.16815 2.50806 + vertex 1.65777 1.16364 2.50878 + endloop + endfacet + facet normal 0.272562 -0.129522 0.95338 + outer loop + vertex 1.65747 1.15841 2.50816 + vertex 1.66248 1.16308 2.50736 + vertex 1.65777 1.16364 2.50878 + endloop + endfacet + facet normal 0.272882 -0.12989 0.953239 + outer loop + vertex 1.6615 1.1579 2.50693 + vertex 1.66248 1.16308 2.50736 + vertex 1.65747 1.15841 2.50816 + endloop + endfacet + facet normal 0.270095 -0.147655 0.951445 + outer loop + vertex 1.6615 1.1579 2.50693 + vertex 1.65747 1.15841 2.50816 + vertex 1.65753 1.15316 2.50733 + endloop + endfacet + facet normal 0.273429 -0.120371 0.954331 + outer loop + vertex 1.65777 1.16364 2.50878 + vertex 1.66226 1.16815 2.50806 + vertex 1.65805 1.16872 2.50934 + endloop + endfacet + facet normal 0.273584 -0.119395 0.954409 + outer loop + vertex 1.66226 1.16815 2.50806 + vertex 1.66254 1.17329 2.50863 + vertex 1.65805 1.16872 2.50934 + endloop + endfacet + facet normal 0.2679 -0.120473 0.955885 + outer loop + vertex 1.65401 1.1722 2.51093 + vertex 1.65426 1.16909 2.51047 + vertex 1.65798 1.17379 2.51002 + endloop + endfacet + facet normal 0.279936 -0.119057 0.952608 + outer loop + vertex 1.65401 1.1722 2.51093 + vertex 1.65149 1.16957 2.51134 + vertex 1.65426 1.16909 2.51047 + endloop + endfacet + facet normal 0.295394 -0.124515 0.947227 + outer loop + vertex 1.65149 1.16957 2.51134 + vertex 1.65132 1.17283 2.51182 + vertex 1.64747 1.168 2.51239 + endloop + endfacet + facet normal 0.293863 -0.119897 0.948298 + outer loop + vertex 1.6464 1.1625 2.51202 + vertex 1.64747 1.168 2.51239 + vertex 1.64245 1.16334 2.51335 + endloop + endfacet + facet normal 0.283398 -0.118553 0.951646 + outer loop + vertex 1.6497 1.16133 2.51086 + vertex 1.6538 1.16461 2.51005 + vertex 1.65051 1.16585 2.51118 + endloop + endfacet + facet normal 0.275067 -0.120409 0.953855 + outer loop + vertex 1.65777 1.16364 2.50878 + vertex 1.65805 1.16872 2.50934 + vertex 1.6538 1.16461 2.51005 + endloop + endfacet + facet normal 0.2791 -0.147155 0.94892 + outer loop + vertex 1.65753 1.15316 2.50733 + vertex 1.65747 1.15841 2.50816 + vertex 1.65278 1.15375 2.50881 + endloop + endfacet + facet normal 0.293846 -0.146295 0.944591 + outer loop + vertex 1.64874 1.15765 2.51066 + vertex 1.64888 1.15436 2.5101 + vertex 1.65273 1.15912 2.50964 + endloop + endfacet + facet normal 0.294374 -0.146246 0.944434 + outer loop + vertex 1.64874 1.15765 2.51066 + vertex 1.64623 1.15503 2.51104 + vertex 1.64888 1.15436 2.5101 + endloop + endfacet + facet normal 0.281763 -0.158561 0.946292 + outer loop + vertex 1.64225 1.15335 2.51196 + vertex 1.64109 1.14832 2.51146 + vertex 1.645 1.15132 2.5108 + endloop + endfacet + facet normal 0.287045 -0.138729 0.947818 + outer loop + vertex 1.64874 1.15765 2.51066 + vertex 1.64596 1.15808 2.51156 + vertex 1.64623 1.15503 2.51104 + endloop + endfacet + facet normal 0.287597 -0.127717 0.949198 + outer loop + vertex 1.64596 1.15808 2.51156 + vertex 1.6464 1.1625 2.51202 + vertex 1.64214 1.15827 2.51275 + endloop + endfacet + facet normal 0.279483 -0.158114 0.947042 + outer loop + vertex 1.64109 1.14832 2.51146 + vertex 1.64225 1.15335 2.51196 + vertex 1.63729 1.14857 2.51262 + endloop + endfacet + facet normal 0.288517 -0.149798 0.945684 + outer loop + vertex 1.6376 1.15359 2.51339 + vertex 1.64214 1.15827 2.51275 + vertex 1.63789 1.15868 2.51411 + endloop + endfacet + facet normal 0.27997 -0.16054 0.94649 + outer loop + vertex 1.63026 1.15605 2.51603 + vertex 1.62634 1.15304 2.51668 + vertex 1.62902 1.15241 2.51578 + endloop + endfacet + facet normal 0.274068 -0.152186 0.949593 + outer loop + vertex 1.62744 1.15815 2.51718 + vertex 1.62634 1.15304 2.51668 + vertex 1.63026 1.15605 2.51603 + endloop + endfacet + facet normal 0.288011 -0.173585 0.941763 + outer loop + vertex 1.62112 1.14327 2.51647 + vertex 1.62235 1.14831 2.51702 + vertex 1.61737 1.1436 2.51768 + endloop + endfacet + facet normal 0.287883 -0.174531 0.941627 + outer loop + vertex 1.62112 1.14327 2.51647 + vertex 1.61737 1.1436 2.51768 + vertex 1.61732 1.13879 2.5168 + endloop + endfacet + facet normal 0.281674 -0.173445 0.943704 + outer loop + vertex 1.629 1.14917 2.5152 + vertex 1.62638 1.14984 2.5161 + vertex 1.62503 1.14617 2.51583 + endloop + endfacet + facet normal 0.282742 -0.165789 0.94476 + outer loop + vertex 1.63298 1.15395 2.51485 + vertex 1.629 1.14917 2.5152 + vertex 1.63285 1.14877 2.51398 + endloop + endfacet + facet normal 0.279814 -0.172308 0.944465 + outer loop + vertex 1.63254 1.14363 2.51313 + vertex 1.63729 1.14857 2.51262 + vertex 1.63285 1.14877 2.51398 + endloop + endfacet + facet normal 0.280812 -0.178694 0.942981 + outer loop + vertex 1.63254 1.13838 2.51213 + vertex 1.63254 1.14363 2.51313 + vertex 1.62766 1.13858 2.51363 + endloop + endfacet + facet normal 0.282271 -0.177039 0.942858 + outer loop + vertex 1.62357 1.14243 2.51558 + vertex 1.62306 1.13859 2.51501 + vertex 1.62767 1.14389 2.51462 + endloop + endfacet + facet normal 0.283713 -0.182004 0.941478 + outer loop + vertex 1.62735 1.13351 2.51274 + vertex 1.62766 1.13858 2.51363 + vertex 1.62293 1.13368 2.5141 + endloop + endfacet + facet normal 0.28603 -0.177363 0.941663 + outer loop + vertex 1.62357 1.14243 2.51558 + vertex 1.62093 1.14011 2.51594 + vertex 1.62306 1.13859 2.51501 + endloop + endfacet + facet normal 0.289069 -0.175579 0.941069 + outer loop + vertex 1.62093 1.14011 2.51594 + vertex 1.62112 1.14327 2.51647 + vertex 1.61732 1.13879 2.5168 + endloop + endfacet + facet normal 0.29191 -0.180647 0.939231 + outer loop + vertex 1.61948 1.13734 2.51586 + vertex 1.61681 1.13498 2.51624 + vertex 1.61923 1.13411 2.51532 + endloop + endfacet + facet normal 0.287169 -0.181572 0.940513 + outer loop + vertex 1.6178 1.12886 2.51474 + vertex 1.62293 1.13368 2.5141 + vertex 1.61923 1.13411 2.51532 + endloop + endfacet + facet normal 0.292398 -0.179625 0.939275 + outer loop + vertex 1.61372 1.12737 2.51573 + vertex 1.61315 1.12351 2.51516 + vertex 1.6178 1.12886 2.51474 + endloop + endfacet + facet normal 0.294882 -0.182686 0.937908 + outer loop + vertex 1.61265 1.13337 2.51723 + vertex 1.61125 1.12816 2.51666 + vertex 1.61526 1.13117 2.51598 + endloop + endfacet + facet normal 0.281778 -0.179679 0.942506 + outer loop + vertex 1.61125 1.12816 2.51666 + vertex 1.61265 1.13337 2.51723 + vertex 1.60738 1.1283 2.51784 + endloop + endfacet + facet normal 0.289625 -0.188312 0.938433 + outer loop + vertex 1.60738 1.1283 2.51784 + vertex 1.61265 1.13337 2.51723 + vertex 1.60768 1.13339 2.51877 + endloop + endfacet + facet normal 0.295219 -0.179898 0.93834 + outer loop + vertex 1.61372 1.12737 2.51573 + vertex 1.61102 1.12499 2.51612 + vertex 1.61315 1.12351 2.51516 + endloop + endfacet + facet normal 0.295827 -0.182736 0.9376 + outer loop + vertex 1.6178 1.12886 2.51474 + vertex 1.61315 1.12351 2.51516 + vertex 1.61776 1.12358 2.51372 + endloop + endfacet + facet normal 0.291369 -0.185872 0.938379 + outer loop + vertex 1.61742 1.11852 2.51283 + vertex 1.6226 1.12341 2.51219 + vertex 1.61776 1.12358 2.51372 + endloop + endfacet + facet normal 0.297104 -0.191153 0.935516 + outer loop + vertex 1.61733 1.11375 2.51188 + vertex 1.61742 1.11852 2.51283 + vertex 1.61264 1.1135 2.51332 + endloop + endfacet + facet normal 0.271905 -0.19659 0.94203 + outer loop + vertex 1.61267 1.10833 2.51223 + vertex 1.61264 1.1135 2.51332 + vertex 1.60766 1.10833 2.51368 + endloop + endfacet + facet normal 0.239945 -0.249098 0.938284 + outer loop + vertex 1.60268 1.10338 2.51364 + vertex 1.60766 1.10833 2.51368 + vertex 1.60269 1.10839 2.51497 + endloop + endfacet + facet normal 0.299373 -0.1983 0.933302 + outer loop + vertex 1.60775 1.1136 2.51488 + vertex 1.61299 1.11859 2.51425 + vertex 1.60926 1.1189 2.51552 + endloop + endfacet + facet normal 0.286581 -0.179357 0.941118 + outer loop + vertex 1.60953 1.12215 2.51605 + vertex 1.60687 1.11973 2.5164 + vertex 1.60926 1.1189 2.51552 + endloop + endfacet + facet normal 0.220112 -0.172726 0.960061 + outer loop + vertex 1.60297 1.11832 2.51709 + vertex 1.60165 1.11355 2.51654 + vertex 1.60535 1.11595 2.51612 + endloop + endfacet + facet normal 0.277976 -0.169261 0.945558 + outer loop + vertex 1.60953 1.12215 2.51605 + vertex 1.60737 1.12354 2.51694 + vertex 1.60687 1.11973 2.5164 + endloop + endfacet + facet normal 0.281788 -0.179553 0.942526 + outer loop + vertex 1.61125 1.12816 2.51666 + vertex 1.60738 1.1283 2.51784 + vertex 1.60737 1.12354 2.51694 + endloop + endfacet + facet normal 0.276514 -0.286701 0.917247 + outer loop + vertex 1.59919 1.13199 2.52091 + vertex 1.59789 1.12828 2.52013 + vertex 1.60285 1.13315 2.52016 + endloop + endfacet + facet normal 0.262332 -0.228916 0.937432 + outer loop + vertex 1.60285 1.13315 2.52016 + vertex 1.60093 1.13478 2.5211 + vertex 1.59919 1.13199 2.52091 + endloop + endfacet + facet normal 0.178737 -0.178782 0.967517 + outer loop + vertex 1.60093 1.13478 2.5211 + vertex 1.59758 1.13406 2.52159 + vertex 1.59919 1.13199 2.52091 + endloop + endfacet + facet normal 0.152746 -0.199154 0.967991 + outer loop + vertex 1.59919 1.13199 2.52091 + vertex 1.59758 1.13406 2.52159 + vertex 1.59648 1.13047 2.52102 + endloop + endfacet + facet normal 0.175446 -0.160967 0.971241 + outer loop + vertex 1.60093 1.13478 2.5211 + vertex 1.60127 1.13807 2.52158 + vertex 1.59758 1.13406 2.52159 + endloop + endfacet + facet normal 0.184487 -0.169313 0.968141 + outer loop + vertex 1.60127 1.13807 2.52158 + vertex 1.59769 1.13849 2.52234 + vertex 1.59758 1.13406 2.52159 + endloop + endfacet + facet normal 0.187624 -0.147964 0.971032 + outer loop + vertex 1.60127 1.13807 2.52158 + vertex 1.60262 1.14328 2.52211 + vertex 1.59769 1.13849 2.52234 + endloop + endfacet + facet normal 0.210472 -0.171963 0.962357 + outer loop + vertex 1.59769 1.13849 2.52234 + vertex 1.60262 1.14328 2.52211 + vertex 1.59766 1.14317 2.52318 + endloop + endfacet + facet normal 0.210406 -0.175839 0.96167 + outer loop + vertex 1.60262 1.14328 2.52211 + vertex 1.60252 1.14836 2.52307 + vertex 1.59766 1.14317 2.52318 + endloop + endfacet + facet normal 0.226705 -0.191267 0.954998 + outer loop + vertex 1.59766 1.14317 2.52318 + vertex 1.60252 1.14836 2.52307 + vertex 1.59767 1.14814 2.52417 + endloop + endfacet + facet normal 0.22671 -0.176949 0.957753 + outer loop + vertex 1.60252 1.14836 2.52307 + vertex 1.60266 1.15338 2.52396 + vertex 1.59767 1.14814 2.52417 + endloop + endfacet + facet normal 0.264011 -0.213157 0.940671 + outer loop + vertex 1.59767 1.14814 2.52417 + vertex 1.60266 1.15338 2.52396 + vertex 1.59795 1.15323 2.52525 + endloop + endfacet + facet normal 0.26504 -0.161417 0.95063 + outer loop + vertex 1.60278 1.1588 2.52485 + vertex 1.59795 1.15323 2.52525 + vertex 1.60266 1.15338 2.52396 + endloop + endfacet + facet normal 0.297817 -0.160628 0.941012 + outer loop + vertex 1.60266 1.15338 2.52396 + vertex 1.60749 1.15841 2.52329 + vertex 1.60278 1.1588 2.52485 + endloop + endfacet + facet normal 0.284086 -0.146565 0.94753 + outer loop + vertex 1.60713 1.15338 2.52262 + vertex 1.60749 1.15841 2.52329 + vertex 1.60266 1.15338 2.52396 + endloop + endfacet + facet normal 0.296285 -0.146935 0.943729 + outer loop + vertex 1.60713 1.15338 2.52262 + vertex 1.61147 1.15767 2.52193 + vertex 1.60749 1.15841 2.52329 + endloop + endfacet + facet normal 0.295316 -0.14588 0.944197 + outer loop + vertex 1.6109 1.15329 2.52143 + vertex 1.61147 1.15767 2.52193 + vertex 1.60713 1.15338 2.52262 + endloop + endfacet + facet normal 0.326391 -0.2168 0.920036 + outer loop + vertex 1.59888 1.15725 2.52587 + vertex 1.59795 1.15323 2.52525 + vertex 1.60278 1.1588 2.52485 + endloop + endfacet + facet normal 0.280935 -0.208908 0.936714 + outer loop + vertex 1.59888 1.15725 2.52587 + vertex 1.59633 1.15507 2.52614 + vertex 1.59795 1.15323 2.52525 + endloop + endfacet + facet normal 0.222395 -0.137131 0.965265 + outer loop + vertex 1.59888 1.15725 2.52587 + vertex 1.59662 1.1583 2.52654 + vertex 1.59633 1.15507 2.52614 + endloop + endfacet + facet normal 0.282719 -0.175817 0.942952 + outer loop + vertex 1.60252 1.14836 2.52307 + vertex 1.60713 1.15338 2.52262 + vertex 1.60266 1.15338 2.52396 + endloop + endfacet + facet normal 0.271299 -0.164878 0.948268 + outer loop + vertex 1.60725 1.14881 2.52179 + vertex 1.60713 1.15338 2.52262 + vertex 1.60252 1.14836 2.52307 + endloop + endfacet + facet normal 0.271608 -0.171838 0.946943 + outer loop + vertex 1.60725 1.14881 2.52179 + vertex 1.60252 1.14836 2.52307 + vertex 1.60262 1.14328 2.52211 + endloop + endfacet + facet normal 0.264487 -0.165694 0.950049 + outer loop + vertex 1.6068 1.14505 2.52126 + vertex 1.60725 1.14881 2.52179 + vertex 1.60262 1.14328 2.52211 + endloop + endfacet + facet normal 0.262462 -0.160187 0.951553 + outer loop + vertex 1.6068 1.14505 2.52126 + vertex 1.60262 1.14328 2.52211 + vertex 1.60524 1.14111 2.52103 + endloop + endfacet + facet normal 0.294122 -0.172098 0.940146 + outer loop + vertex 1.60925 1.14422 2.52034 + vertex 1.6068 1.14505 2.52126 + vertex 1.60524 1.14111 2.52103 + endloop + endfacet + facet normal 0.294999 -0.173339 0.939643 + outer loop + vertex 1.60778 1.13879 2.5198 + vertex 1.60925 1.14422 2.52034 + vertex 1.60524 1.14111 2.52103 + endloop + endfacet + facet normal 0.294556 -0.173847 0.939688 + outer loop + vertex 1.60363 1.13715 2.5208 + vertex 1.60778 1.13879 2.5198 + vertex 1.60524 1.14111 2.52103 + endloop + endfacet + facet normal 0.254709 -0.158516 0.953937 + outer loop + vertex 1.60524 1.14111 2.52103 + vertex 1.60127 1.13807 2.52158 + vertex 1.60363 1.13715 2.5208 + endloop + endfacet + facet normal 0.258986 -0.164489 0.951772 + outer loop + vertex 1.60262 1.14328 2.52211 + vertex 1.60127 1.13807 2.52158 + vertex 1.60524 1.14111 2.52103 + endloop + endfacet + facet normal 0.251507 -0.166339 0.953455 + outer loop + vertex 1.60363 1.13715 2.5208 + vertex 1.60127 1.13807 2.52158 + vertex 1.60093 1.13478 2.5211 + endloop + endfacet + facet normal 0.282994 -0.204362 0.937097 + outer loop + vertex 1.60363 1.13715 2.5208 + vertex 1.60093 1.13478 2.5211 + vertex 1.60285 1.13315 2.52016 + endloop + endfacet + facet normal 0.186952 -0.261631 0.946889 + outer loop + vertex 1.59919 1.13199 2.52091 + vertex 1.59648 1.13047 2.52102 + vertex 1.59789 1.12828 2.52013 + endloop + endfacet + facet normal 0.252109 -0.188066 0.949248 + outer loop + vertex 1.60738 1.1283 2.51784 + vertex 1.60768 1.13339 2.51877 + vertex 1.60268 1.12818 2.51907 + endloop + endfacet + facet normal 0.305371 -0.207501 0.92935 + outer loop + vertex 1.60363 1.13715 2.5208 + vertex 1.60285 1.13315 2.52016 + vertex 1.60778 1.13879 2.5198 + endloop + endfacet + facet normal 0.290173 -0.179008 0.940083 + outer loop + vertex 1.61265 1.13337 2.51723 + vertex 1.61265 1.13864 2.51823 + vertex 1.60768 1.13339 2.51877 + endloop + endfacet + facet normal 0.293805 -0.174272 0.939844 + outer loop + vertex 1.61732 1.13879 2.5168 + vertex 1.61737 1.1436 2.51768 + vertex 1.61265 1.13864 2.51823 + endloop + endfacet + facet normal 0.284786 -0.169947 0.943406 + outer loop + vertex 1.61737 1.1436 2.51768 + vertex 1.62235 1.14831 2.51702 + vertex 1.61764 1.14867 2.51851 + endloop + endfacet + facet normal 0.297516 -0.173934 0.938739 + outer loop + vertex 1.60778 1.13879 2.5198 + vertex 1.61298 1.14381 2.51908 + vertex 1.60925 1.14422 2.52034 + endloop + endfacet + facet normal 0.294563 -0.170879 0.94023 + outer loop + vertex 1.60951 1.14751 2.52086 + vertex 1.6068 1.14505 2.52126 + vertex 1.60925 1.14422 2.52034 + endloop + endfacet + facet normal 0.291962 -0.167807 0.941594 + outer loop + vertex 1.60951 1.14751 2.52086 + vertex 1.60725 1.14881 2.52179 + vertex 1.6068 1.14505 2.52126 + endloop + endfacet + facet normal 0.294123 -0.163055 0.941756 + outer loop + vertex 1.6109 1.15329 2.52143 + vertex 1.60713 1.15338 2.52262 + vertex 1.60725 1.14881 2.52179 + endloop + endfacet + facet normal 0.294245 -0.14578 0.944547 + outer loop + vertex 1.61147 1.15767 2.52193 + vertex 1.6109 1.15329 2.52143 + vertex 1.61469 1.15643 2.52073 + endloop + endfacet + facet normal 0.295928 -0.147775 0.94371 + outer loop + vertex 1.61757 1.15405 2.51946 + vertex 1.61883 1.15966 2.51994 + vertex 1.61469 1.15643 2.52073 + endloop + endfacet + facet normal 0.301495 -0.165402 0.939012 + outer loop + vertex 1.61348 1.15263 2.5205 + vertex 1.61091 1.15029 2.52091 + vertex 1.61308 1.14879 2.51995 + endloop + endfacet + facet normal 0.285444 -0.164527 0.944168 + outer loop + vertex 1.62235 1.14831 2.51702 + vertex 1.62237 1.15347 2.51792 + vertex 1.61764 1.14867 2.51851 + endloop + endfacet + facet normal 0.281098 -0.144853 0.948684 + outer loop + vertex 1.61757 1.15405 2.51946 + vertex 1.62278 1.15869 2.51862 + vertex 1.61883 1.15966 2.51994 + endloop + endfacet + facet normal 0.279454 -0.15318 0.947861 + outer loop + vertex 1.62634 1.15304 2.51668 + vertex 1.62744 1.15815 2.51718 + vertex 1.62237 1.15347 2.51792 + endloop + endfacet + facet normal 0.278646 -0.132325 0.951234 + outer loop + vertex 1.62278 1.15869 2.51862 + vertex 1.62741 1.16332 2.51791 + vertex 1.62311 1.16379 2.51923 + endloop + endfacet + facet normal 0.276828 -0.11508 0.954004 + outer loop + vertex 1.63131 1.16296 2.51673 + vertex 1.63228 1.16818 2.51708 + vertex 1.62741 1.16332 2.51791 + endloop + endfacet + facet normal 0.281721 -0.120329 0.951921 + outer loop + vertex 1.62741 1.16332 2.51791 + vertex 1.63228 1.16818 2.51708 + vertex 1.62759 1.16847 2.51851 + endloop + endfacet + facet normal 0.300715 -0.139247 0.943494 + outer loop + vertex 1.63401 1.16236 2.51586 + vertex 1.63411 1.1591 2.51535 + vertex 1.63791 1.16393 2.51485 + endloop + endfacet + facet normal 0.294046 -0.118535 0.948413 + outer loop + vertex 1.63791 1.16393 2.51485 + vertex 1.64279 1.16867 2.51393 + vertex 1.63891 1.16926 2.5152 + endloop + endfacet + facet normal 0.291005 -0.111218 0.950235 + outer loop + vertex 1.63874 1.17262 2.51565 + vertex 1.63623 1.16992 2.5161 + vertex 1.63891 1.16926 2.5152 + endloop + endfacet + facet normal 0.280941 -0.115752 0.952719 + outer loop + vertex 1.63228 1.16818 2.51708 + vertex 1.63131 1.16296 2.51673 + vertex 1.63512 1.16612 2.51599 + endloop + endfacet + facet normal 0.291277 -0.111491 0.95012 + outer loop + vertex 1.63874 1.17262 2.51565 + vertex 1.63607 1.17318 2.51654 + vertex 1.63623 1.16992 2.5161 + endloop + endfacet + facet normal 0.282143 -0.11561 0.952381 + outer loop + vertex 1.63228 1.16818 2.51708 + vertex 1.6322 1.17338 2.51774 + vertex 1.62759 1.16847 2.51851 + endloop + endfacet + facet normal 0.280309 -0.120327 0.952338 + outer loop + vertex 1.62741 1.16332 2.51791 + vertex 1.62759 1.16847 2.51851 + vertex 1.62311 1.16379 2.51923 + endloop + endfacet + facet normal 0.284418 -0.132495 0.949501 + outer loop + vertex 1.62278 1.15869 2.51862 + vertex 1.62311 1.16379 2.51923 + vertex 1.61883 1.15966 2.51994 + endloop + endfacet + facet normal 0.290014 -0.126989 0.94856 + outer loop + vertex 1.61259 1.16317 2.52232 + vertex 1.61147 1.15767 2.52193 + vertex 1.61561 1.16099 2.52111 + endloop + endfacet + facet normal 0.300126 -0.128798 0.945164 + outer loop + vertex 1.61147 1.15767 2.52193 + vertex 1.61259 1.16317 2.52232 + vertex 1.60749 1.15841 2.52329 + endloop + endfacet + facet normal 0.297622 -0.125878 0.946349 + outer loop + vertex 1.60749 1.15841 2.52329 + vertex 1.61259 1.16317 2.52232 + vertex 1.60787 1.16378 2.52389 + endloop + endfacet + facet normal 0.302019 -0.126032 0.944934 + outer loop + vertex 1.60749 1.15841 2.52329 + vertex 1.60787 1.16378 2.52389 + vertex 1.60278 1.1588 2.52485 + endloop + endfacet + facet normal 0.304863 -0.129195 0.943593 + outer loop + vertex 1.60278 1.1588 2.52485 + vertex 1.60787 1.16378 2.52389 + vertex 1.60397 1.16437 2.52522 + endloop + endfacet + facet normal 0.306952 -0.129593 0.942861 + outer loop + vertex 1.60278 1.1588 2.52485 + vertex 1.60397 1.16437 2.52522 + vertex 1.60023 1.16118 2.52601 + endloop + endfacet + facet normal 0.300786 -0.136697 0.943844 + outer loop + vertex 1.59888 1.15725 2.52587 + vertex 1.60278 1.1588 2.52485 + vertex 1.60023 1.16118 2.52601 + endloop + endfacet + facet normal 0.233148 -0.114204 0.965712 + outer loop + vertex 1.60023 1.16118 2.52601 + vertex 1.59662 1.1583 2.52654 + vertex 1.59888 1.15725 2.52587 + endloop + endfacet + facet normal 0.23168 -0.112262 0.966293 + outer loop + vertex 1.59744 1.16325 2.52692 + vertex 1.59662 1.1583 2.52654 + vertex 1.60023 1.16118 2.52601 + endloop + endfacet + facet normal 0.239342 -0.10163 0.965602 + outer loop + vertex 1.60131 1.16503 2.52614 + vertex 1.59744 1.16325 2.52692 + vertex 1.60023 1.16118 2.52601 + endloop + endfacet + facet normal 0.243982 -0.112759 0.963202 + outer loop + vertex 1.60131 1.16503 2.52614 + vertex 1.60097 1.16815 2.52659 + vertex 1.59744 1.16325 2.52692 + endloop + endfacet + facet normal 0.248287 -0.115964 0.96172 + outer loop + vertex 1.60097 1.16815 2.52659 + vertex 1.59707 1.16813 2.5276 + vertex 1.59744 1.16325 2.52692 + endloop + endfacet + facet normal 0.167932 -0.12423 0.977939 + outer loop + vertex 1.59744 1.16325 2.52692 + vertex 1.59707 1.16813 2.5276 + vertex 1.59263 1.16324 2.52774 + endloop + endfacet + facet normal 0.18391 -0.138899 0.97308 + outer loop + vertex 1.59263 1.16324 2.52774 + vertex 1.59707 1.16813 2.5276 + vertex 1.59249 1.16813 2.52846 + endloop + endfacet + facet normal 0.184309 -0.122981 0.975144 + outer loop + vertex 1.59707 1.16813 2.5276 + vertex 1.59734 1.17312 2.52818 + vertex 1.59249 1.16813 2.52846 + endloop + endfacet + facet normal 0.210112 -0.1486 0.966318 + outer loop + vertex 1.59249 1.16813 2.52846 + vertex 1.59734 1.17312 2.52818 + vertex 1.59262 1.17325 2.52922 + endloop + endfacet + facet normal 0.211017 -0.132758 0.968425 + outer loop + vertex 1.59734 1.17312 2.52818 + vertex 1.5977 1.17831 2.52881 + vertex 1.59262 1.17325 2.52922 + endloop + endfacet + facet normal 0.241208 -0.164069 0.956504 + outer loop + vertex 1.59262 1.17325 2.52922 + vertex 1.5977 1.17831 2.52881 + vertex 1.59289 1.17865 2.53008 + endloop + endfacet + facet normal 0.243684 -0.140456 0.95963 + outer loop + vertex 1.5977 1.17831 2.52881 + vertex 1.59807 1.18348 2.52947 + vertex 1.59289 1.17865 2.53008 + endloop + endfacet + facet normal 0.273211 -0.173803 0.946123 + outer loop + vertex 1.59289 1.17865 2.53008 + vertex 1.59807 1.18348 2.52947 + vertex 1.59441 1.18384 2.5306 + endloop + endfacet + facet normal 0.293438 -0.142151 0.94535 + outer loop + vertex 1.5977 1.17831 2.52881 + vertex 1.60249 1.18327 2.52807 + vertex 1.59807 1.18348 2.52947 + endloop + endfacet + facet normal 0.283879 -0.132272 0.949693 + outer loop + vertex 1.60251 1.17808 2.52734 + vertex 1.60249 1.18327 2.52807 + vertex 1.5977 1.17831 2.52881 + endloop + endfacet + facet normal 0.310061 -0.131043 0.941642 + outer loop + vertex 1.60636 1.18298 2.52675 + vertex 1.60249 1.18327 2.52807 + vertex 1.60251 1.17808 2.52734 + endloop + endfacet + facet normal 0.31313 -0.133624 0.940263 + outer loop + vertex 1.60652 1.17979 2.52625 + vertex 1.60636 1.18298 2.52675 + vertex 1.60251 1.17808 2.52734 + endloop + endfacet + facet normal 0.307467 -0.117823 0.944236 + outer loop + vertex 1.60652 1.17979 2.52625 + vertex 1.60251 1.17808 2.52734 + vertex 1.60552 1.17605 2.52611 + endloop + endfacet + facet normal 0.301666 -0.116336 0.946289 + outer loop + vertex 1.60924 1.17927 2.52532 + vertex 1.60652 1.17979 2.52625 + vertex 1.60552 1.17605 2.52611 + endloop + endfacet + facet normal 0.302599 -0.117527 0.945844 + outer loop + vertex 1.60878 1.17477 2.52491 + vertex 1.60924 1.17927 2.52532 + vertex 1.60552 1.17605 2.52611 + endloop + endfacet + facet normal 0.304276 -0.113243 0.945829 + outer loop + vertex 1.60469 1.17151 2.52583 + vertex 1.60878 1.17477 2.52491 + vertex 1.60552 1.17605 2.52611 + endloop + endfacet + facet normal 0.298267 -0.112277 0.947856 + outer loop + vertex 1.60552 1.17605 2.52611 + vertex 1.60138 1.1726 2.527 + vertex 1.60469 1.17151 2.52583 + endloop + endfacet + facet normal 0.297684 -0.114021 0.947831 + outer loop + vertex 1.60138 1.1726 2.527 + vertex 1.60097 1.16815 2.52659 + vertex 1.60469 1.17151 2.52583 + endloop + endfacet + facet normal 0.291639 -0.106706 0.950558 + outer loop + vertex 1.60469 1.17151 2.52583 + vertex 1.60097 1.16815 2.52659 + vertex 1.60375 1.16776 2.5257 + endloop + endfacet + facet normal 0.305292 -0.109967 0.945888 + outer loop + vertex 1.60375 1.16776 2.5257 + vertex 1.60774 1.16924 2.52458 + vertex 1.60469 1.17151 2.52583 + endloop + endfacet + facet normal 0.305837 -0.111721 0.945506 + outer loop + vertex 1.60375 1.16776 2.5257 + vertex 1.60397 1.16437 2.52522 + vertex 1.60774 1.16924 2.52458 + endloop + endfacet + facet normal 0.298713 -0.1125 0.947689 + outer loop + vertex 1.60375 1.16776 2.5257 + vertex 1.60131 1.16503 2.52614 + vertex 1.60397 1.16437 2.52522 + endloop + endfacet + facet normal 0.303629 -0.112342 0.946144 + outer loop + vertex 1.60774 1.16924 2.52458 + vertex 1.60878 1.17477 2.52491 + vertex 1.60469 1.17151 2.52583 + endloop + endfacet + facet normal 0.292074 -0.110391 0.950003 + outer loop + vertex 1.60774 1.16924 2.52458 + vertex 1.61274 1.17376 2.52357 + vertex 1.60878 1.17477 2.52491 + endloop + endfacet + facet normal 0.289469 -0.120135 0.949619 + outer loop + vertex 1.61274 1.17376 2.52357 + vertex 1.61303 1.17884 2.52413 + vertex 1.60878 1.17477 2.52491 + endloop + endfacet + facet normal 0.279319 -0.119901 0.952683 + outer loop + vertex 1.61274 1.17376 2.52357 + vertex 1.61733 1.17833 2.5228 + vertex 1.61303 1.17884 2.52413 + endloop + endfacet + facet normal 0.277402 -0.132983 0.951506 + outer loop + vertex 1.61733 1.17833 2.5228 + vertex 1.61756 1.18345 2.52345 + vertex 1.61303 1.17884 2.52413 + endloop + endfacet + facet normal 0.275581 -0.131072 0.9523 + outer loop + vertex 1.61303 1.17884 2.52413 + vertex 1.61756 1.18345 2.52345 + vertex 1.61292 1.18388 2.52485 + endloop + endfacet + facet normal 0.284064 -0.130541 0.949877 + outer loop + vertex 1.61292 1.18388 2.52485 + vertex 1.60924 1.17927 2.52532 + vertex 1.61303 1.17884 2.52413 + endloop + endfacet + facet normal 0.279418 -0.126644 0.951781 + outer loop + vertex 1.60901 1.18239 2.5258 + vertex 1.60924 1.17927 2.52532 + vertex 1.61292 1.18388 2.52485 + endloop + endfacet + facet normal 0.283359 -0.13878 0.948919 + outer loop + vertex 1.60901 1.18239 2.5258 + vertex 1.61292 1.18388 2.52485 + vertex 1.61017 1.186 2.52598 + endloop + endfacet + facet normal 0.306525 -0.145788 0.940632 + outer loop + vertex 1.61017 1.186 2.52598 + vertex 1.60636 1.18298 2.52675 + vertex 1.60901 1.18239 2.5258 + endloop + endfacet + facet normal 0.304758 -0.143317 0.941585 + outer loop + vertex 1.60743 1.18812 2.52719 + vertex 1.60636 1.18298 2.52675 + vertex 1.61017 1.186 2.52598 + endloop + endfacet + facet normal 0.299037 -0.151056 0.94221 + outer loop + vertex 1.6114 1.18965 2.52618 + vertex 1.60743 1.18812 2.52719 + vertex 1.61017 1.186 2.52598 + endloop + endfacet + facet normal 0.281349 -0.145452 0.948518 + outer loop + vertex 1.61401 1.18898 2.5253 + vertex 1.6114 1.18965 2.52618 + vertex 1.61017 1.186 2.52598 + endloop + endfacet + facet normal 0.279506 -0.152072 0.948024 + outer loop + vertex 1.61401 1.19225 2.52582 + vertex 1.6114 1.18965 2.52618 + vertex 1.61401 1.18898 2.5253 + endloop + endfacet + facet normal 0.272433 -0.152388 0.950031 + outer loop + vertex 1.61401 1.19225 2.52582 + vertex 1.61401 1.18898 2.5253 + vertex 1.61798 1.1938 2.52493 + endloop + endfacet + facet normal 0.274192 -0.157674 0.948661 + outer loop + vertex 1.61401 1.19225 2.52582 + vertex 1.61798 1.1938 2.52493 + vertex 1.61537 1.19601 2.52606 + endloop + endfacet + facet normal 0.28349 -0.160816 0.945395 + outer loop + vertex 1.61537 1.19601 2.52606 + vertex 1.6114 1.19294 2.52673 + vertex 1.61401 1.19225 2.52582 + endloop + endfacet + facet normal 0.280584 -0.156712 0.94695 + outer loop + vertex 1.61269 1.1983 2.52723 + vertex 1.6114 1.19294 2.52673 + vertex 1.61537 1.19601 2.52606 + endloop + endfacet + facet normal 0.279542 -0.157978 0.947048 + outer loop + vertex 1.61684 1.19985 2.52626 + vertex 1.61269 1.1983 2.52723 + vertex 1.61537 1.19601 2.52606 + endloop + endfacet + facet normal 0.275828 -0.156629 0.94836 + outer loop + vertex 1.61928 1.19902 2.52541 + vertex 1.61684 1.19985 2.52626 + vertex 1.61537 1.19601 2.52606 + endloop + endfacet + facet normal 0.276411 -0.155016 0.948455 + outer loop + vertex 1.61949 1.20227 2.52589 + vertex 1.61684 1.19985 2.52626 + vertex 1.61928 1.19902 2.52541 + endloop + endfacet + facet normal 0.279002 -0.155067 0.947688 + outer loop + vertex 1.61949 1.20227 2.52589 + vertex 1.61928 1.19902 2.52541 + vertex 1.62304 1.20357 2.52505 + endloop + endfacet + facet normal 0.278048 -0.151961 0.948471 + outer loop + vertex 1.62304 1.20357 2.52505 + vertex 1.62085 1.20505 2.52593 + vertex 1.61949 1.20227 2.52589 + endloop + endfacet + facet normal 0.275655 -0.150802 0.949354 + outer loop + vertex 1.62085 1.20505 2.52593 + vertex 1.61723 1.20364 2.52676 + vertex 1.61949 1.20227 2.52589 + endloop + endfacet + facet normal 0.274281 -0.146652 0.950402 + outer loop + vertex 1.62085 1.20505 2.52593 + vertex 1.62081 1.20804 2.5264 + vertex 1.61723 1.20364 2.52676 + endloop + endfacet + facet normal 0.275854 -0.147987 0.949739 + outer loop + vertex 1.62081 1.20804 2.5264 + vertex 1.61706 1.20826 2.52753 + vertex 1.61723 1.20364 2.52676 + endloop + endfacet + facet normal 0.278328 -0.147778 0.94905 + outer loop + vertex 1.61723 1.20364 2.52676 + vertex 1.61706 1.20826 2.52753 + vertex 1.61257 1.2036 2.52812 + endloop + endfacet + facet normal 0.278143 -0.15313 0.948255 + outer loop + vertex 1.61723 1.20364 2.52676 + vertex 1.61257 1.2036 2.52812 + vertex 1.61269 1.1983 2.52723 + endloop + endfacet + facet normal 0.286128 -0.152576 0.945966 + outer loop + vertex 1.61269 1.1983 2.52723 + vertex 1.61257 1.2036 2.52812 + vertex 1.60785 1.19878 2.52877 + endloop + endfacet + facet normal 0.286205 -0.152011 0.946034 + outer loop + vertex 1.60745 1.19342 2.52803 + vertex 1.61269 1.1983 2.52723 + vertex 1.60785 1.19878 2.52877 + endloop + endfacet + facet normal 0.295996 -0.152305 0.942968 + outer loop + vertex 1.60745 1.19342 2.52803 + vertex 1.60785 1.19878 2.52877 + vertex 1.60265 1.19393 2.52962 + endloop + endfacet + facet normal 0.293752 -0.149703 0.944086 + outer loop + vertex 1.60265 1.19393 2.52962 + vertex 1.60785 1.19878 2.52877 + vertex 1.60392 1.19935 2.53008 + endloop + endfacet + facet normal 0.294335 -0.149822 0.943886 + outer loop + vertex 1.60265 1.19393 2.52962 + vertex 1.60392 1.19935 2.53008 + vertex 1.6 1.1963 2.53082 + endloop + endfacet + facet normal 0.294811 -0.149259 0.943826 + outer loop + vertex 1.59857 1.19245 2.53066 + vertex 1.60265 1.19393 2.52962 + vertex 1.6 1.1963 2.53082 + endloop + endfacet + facet normal 0.272811 -0.14139 0.951621 + outer loop + vertex 1.6 1.1963 2.53082 + vertex 1.59611 1.19319 2.53148 + vertex 1.59857 1.19245 2.53066 + endloop + endfacet + facet normal 0.274171 -0.137138 0.951853 + outer loop + vertex 1.59857 1.19245 2.53066 + vertex 1.59611 1.19319 2.53148 + vertex 1.59595 1.18998 2.53106 + endloop + endfacet + facet normal 0.27687 -0.140198 0.950625 + outer loop + vertex 1.59857 1.19245 2.53066 + vertex 1.59595 1.18998 2.53106 + vertex 1.59812 1.18848 2.5302 + endloop + endfacet + facet normal 0.276348 -0.140974 0.950662 + outer loop + vertex 1.59812 1.18848 2.5302 + vertex 1.59595 1.18998 2.53106 + vertex 1.59457 1.18707 2.53103 + endloop + endfacet + facet normal 0.276285 -0.140791 0.950707 + outer loop + vertex 1.59457 1.18707 2.53103 + vertex 1.59441 1.18384 2.5306 + vertex 1.59812 1.18848 2.5302 + endloop + endfacet + facet normal 0.277585 -0.141877 0.950167 + outer loop + vertex 1.59812 1.18848 2.5302 + vertex 1.59441 1.18384 2.5306 + vertex 1.59807 1.18348 2.52947 + endloop + endfacet + facet normal 0.29645 -0.141242 0.944547 + outer loop + vertex 1.59807 1.18348 2.52947 + vertex 1.6027 1.18847 2.52876 + vertex 1.59812 1.18848 2.5302 + endloop + endfacet + facet normal 0.29629 -0.144758 0.944064 + outer loop + vertex 1.60265 1.19393 2.52962 + vertex 1.59812 1.18848 2.5302 + vertex 1.6027 1.18847 2.52876 + endloop + endfacet + facet normal 0.297085 -0.144712 0.943822 + outer loop + vertex 1.6027 1.18847 2.52876 + vertex 1.60745 1.19342 2.52803 + vertex 1.60265 1.19393 2.52962 + endloop + endfacet + facet normal 0.302378 -0.150161 0.941286 + outer loop + vertex 1.60743 1.18812 2.52719 + vertex 1.60745 1.19342 2.52803 + vertex 1.6027 1.18847 2.52876 + endloop + endfacet + facet normal 0.303689 -0.138549 0.942644 + outer loop + vertex 1.60249 1.18327 2.52807 + vertex 1.60743 1.18812 2.52719 + vertex 1.6027 1.18847 2.52876 + endloop + endfacet + facet normal 0.293809 -0.150543 0.943935 + outer loop + vertex 1.6114 1.19294 2.52673 + vertex 1.60745 1.19342 2.52803 + vertex 1.60743 1.18812 2.52719 + endloop + endfacet + facet normal 0.293752 -0.138557 0.945786 + outer loop + vertex 1.60249 1.18327 2.52807 + vertex 1.6027 1.18847 2.52876 + vertex 1.59807 1.18348 2.52947 + endloop + endfacet + facet normal 0.228843 -0.140077 0.963332 + outer loop + vertex 1.59457 1.18707 2.53103 + vertex 1.59206 1.1847 2.53128 + vertex 1.59441 1.18384 2.5306 + endloop + endfacet + facet normal 0.211366 -0.120902 0.969901 + outer loop + vertex 1.59457 1.18707 2.53103 + vertex 1.59241 1.18851 2.53168 + vertex 1.59206 1.1847 2.53128 + endloop + endfacet + facet normal 0.131206 -0.115164 0.984643 + outer loop + vertex 1.59206 1.1847 2.53128 + vertex 1.59241 1.18851 2.53168 + vertex 1.58826 1.18345 2.53164 + endloop + endfacet + facet normal 0.133393 -0.122149 0.983507 + outer loop + vertex 1.59206 1.1847 2.53128 + vertex 1.58826 1.18345 2.53164 + vertex 1.5907 1.18115 2.53102 + endloop + endfacet + facet normal 0.223126 -0.15492 0.9624 + outer loop + vertex 1.59441 1.18384 2.5306 + vertex 1.59206 1.1847 2.53128 + vertex 1.5907 1.18115 2.53102 + endloop + endfacet + facet normal 0.121289 -0.134975 0.983398 + outer loop + vertex 1.58826 1.18345 2.53164 + vertex 1.58749 1.17948 2.53119 + vertex 1.5907 1.18115 2.53102 + endloop + endfacet + facet normal 0.1322 -0.156498 0.978791 + outer loop + vertex 1.5907 1.18115 2.53102 + vertex 1.58749 1.17948 2.53119 + vertex 1.58884 1.17767 2.53072 + endloop + endfacet + facet normal 0.19695 -0.189698 0.961886 + outer loop + vertex 1.58884 1.17767 2.53072 + vertex 1.59289 1.17865 2.53008 + vertex 1.5907 1.18115 2.53102 + endloop + endfacet + facet normal 0.227979 -0.161948 0.960103 + outer loop + vertex 1.59289 1.17865 2.53008 + vertex 1.59441 1.18384 2.5306 + vertex 1.5907 1.18115 2.53102 + endloop + endfacet + facet normal 0.150229 -0.130736 0.979969 + outer loop + vertex 1.59241 1.18851 2.53168 + vertex 1.58771 1.18822 2.53236 + vertex 1.58826 1.18345 2.53164 + endloop + endfacet + facet normal 0.150693 -0.141965 0.978334 + outer loop + vertex 1.59241 1.18851 2.53168 + vertex 1.59228 1.19324 2.53238 + vertex 1.58771 1.18822 2.53236 + endloop + endfacet + facet normal 0.16735 -0.15711 0.973299 + outer loop + vertex 1.58771 1.18822 2.53236 + vertex 1.59228 1.19324 2.53238 + vertex 1.58752 1.1931 2.53318 + endloop + endfacet + facet normal 0.167353 -0.158309 0.973104 + outer loop + vertex 1.59228 1.19324 2.53238 + vertex 1.59251 1.19821 2.53315 + vertex 1.58752 1.1931 2.53318 + endloop + endfacet + facet normal 0.185895 -0.176451 0.966596 + outer loop + vertex 1.58752 1.1931 2.53318 + vertex 1.59251 1.19821 2.53315 + vertex 1.58753 1.1982 2.53411 + endloop + endfacet + facet normal 0.186124 -0.169468 0.967801 + outer loop + vertex 1.59251 1.19821 2.53315 + vertex 1.59267 1.20325 2.534 + vertex 1.58753 1.1982 2.53411 + endloop + endfacet + facet normal 0.21991 -0.20423 0.953902 + outer loop + vertex 1.58753 1.1982 2.53411 + vertex 1.59267 1.20325 2.534 + vertex 1.58779 1.2033 2.53514 + endloop + endfacet + facet normal 0.221816 -0.168021 0.960503 + outer loop + vertex 1.59276 1.20851 2.53491 + vertex 1.58779 1.2033 2.53514 + vertex 1.59267 1.20325 2.534 + endloop + endfacet + facet normal 0.276561 -0.16654 0.946456 + outer loop + vertex 1.59267 1.20325 2.534 + vertex 1.59761 1.20835 2.53346 + vertex 1.59276 1.20851 2.53491 + endloop + endfacet + facet normal 0.278538 -0.140089 0.950153 + outer loop + vertex 1.59761 1.20835 2.53346 + vertex 1.59791 1.21355 2.53414 + vertex 1.59276 1.20851 2.53491 + endloop + endfacet + facet normal 0.288221 -0.15068 0.945634 + outer loop + vertex 1.59276 1.20851 2.53491 + vertex 1.59791 1.21355 2.53414 + vertex 1.59404 1.2139 2.53537 + endloop + endfacet + facet normal 0.26969 -0.146775 0.951696 + outer loop + vertex 1.59276 1.20851 2.53491 + vertex 1.59404 1.2139 2.53537 + vertex 1.59023 1.21084 2.53598 + endloop + endfacet + facet normal 0.260446 -0.15724 0.952598 + outer loop + vertex 1.58877 1.2071 2.53576 + vertex 1.59276 1.20851 2.53491 + vertex 1.59023 1.21084 2.53598 + endloop + endfacet + facet normal 0.192195 -0.131685 0.972481 + outer loop + vertex 1.59023 1.21084 2.53598 + vertex 1.58667 1.20845 2.53636 + vertex 1.58877 1.2071 2.53576 + endloop + endfacet + facet normal 0.176752 -0.155416 0.971908 + outer loop + vertex 1.58877 1.2071 2.53576 + vertex 1.58667 1.20845 2.53636 + vertex 1.58617 1.2053 2.53595 + endloop + endfacet + facet normal 0.214158 -0.211271 0.953677 + outer loop + vertex 1.58877 1.2071 2.53576 + vertex 1.58617 1.2053 2.53595 + vertex 1.58779 1.2033 2.53514 + endloop + endfacet + facet normal 0.192535 -0.132213 0.972343 + outer loop + vertex 1.58771 1.21316 2.5368 + vertex 1.58667 1.20845 2.53636 + vertex 1.59023 1.21084 2.53598 + endloop + endfacet + facet normal 0.201152 -0.122676 0.971848 + outer loop + vertex 1.59144 1.21459 2.5362 + vertex 1.58771 1.21316 2.5368 + vertex 1.59023 1.21084 2.53598 + endloop + endfacet + facet normal 0.203272 -0.128743 0.970621 + outer loop + vertex 1.59144 1.21459 2.5362 + vertex 1.59134 1.21789 2.53666 + vertex 1.58771 1.21316 2.5368 + endloop + endfacet + facet normal 0.20395 -0.12927 0.970409 + outer loop + vertex 1.59134 1.21789 2.53666 + vertex 1.58741 1.21806 2.53751 + vertex 1.58771 1.21316 2.5368 + endloop + endfacet + facet normal 0.204114 -0.126939 0.970682 + outer loop + vertex 1.59134 1.21789 2.53666 + vertex 1.5924 1.22305 2.53711 + vertex 1.58741 1.21806 2.53751 + endloop + endfacet + facet normal 0.22361 -0.147028 0.963525 + outer loop + vertex 1.58741 1.21806 2.53751 + vertex 1.5924 1.22305 2.53711 + vertex 1.58749 1.22309 2.53826 + endloop + endfacet + facet normal 0.223656 -0.145917 0.963684 + outer loop + vertex 1.5924 1.22305 2.53711 + vertex 1.59238 1.22815 2.53789 + vertex 1.58749 1.22309 2.53826 + endloop + endfacet + facet normal 0.236248 -0.158455 0.958686 + outer loop + vertex 1.58749 1.22309 2.53826 + vertex 1.59238 1.22815 2.53789 + vertex 1.58761 1.22821 2.53908 + endloop + endfacet + facet normal 0.237031 -0.142324 0.96102 + outer loop + vertex 1.59238 1.22815 2.53789 + vertex 1.59267 1.23328 2.53858 + vertex 1.58761 1.22821 2.53908 + endloop + endfacet + facet normal 0.259937 -0.166135 0.951227 + outer loop + vertex 1.58761 1.22821 2.53908 + vertex 1.59267 1.23328 2.53858 + vertex 1.5878 1.23358 2.53996 + endloop + endfacet + facet normal 0.262953 -0.135745 0.955212 + outer loop + vertex 1.59267 1.23328 2.53858 + vertex 1.59298 1.23848 2.53923 + vertex 1.5878 1.23358 2.53996 + endloop + endfacet + facet normal 0.28494 -0.160525 0.945009 + outer loop + vertex 1.5878 1.23358 2.53996 + vertex 1.59298 1.23848 2.53923 + vertex 1.58919 1.23884 2.54044 + endloop + endfacet + facet normal 0.254838 -0.153458 0.954729 + outer loop + vertex 1.5878 1.23358 2.53996 + vertex 1.58919 1.23884 2.54044 + vertex 1.58553 1.23606 2.54097 + endloop + endfacet + facet normal 0.224294 -0.182479 0.957284 + outer loop + vertex 1.58377 1.23258 2.54072 + vertex 1.5878 1.23358 2.53996 + vertex 1.58553 1.23606 2.54097 + endloop + endfacet + facet normal 0.162826 -0.152738 0.974761 + outer loop + vertex 1.58553 1.23606 2.54097 + vertex 1.5824 1.23437 2.54123 + vertex 1.58377 1.23258 2.54072 + endloop + endfacet + facet normal 0.110979 -0.192343 0.975032 + outer loop + vertex 1.58377 1.23258 2.54072 + vertex 1.5824 1.23437 2.54123 + vertex 1.58016 1.23119 2.54085 + endloop + endfacet + facet normal 0.111701 -0.194261 0.974569 + outer loop + vertex 1.58377 1.23258 2.54072 + vertex 1.58016 1.23119 2.54085 + vertex 1.5824 1.22832 2.54002 + endloop + endfacet + facet normal 0.148327 -0.124985 0.981008 + outer loop + vertex 1.58302 1.23829 2.54163 + vertex 1.5824 1.23437 2.54123 + vertex 1.58553 1.23606 2.54097 + endloop + endfacet + facet normal 0.156136 -0.116132 0.980885 + outer loop + vertex 1.58667 1.23954 2.5412 + vertex 1.58302 1.23829 2.54163 + vertex 1.58553 1.23606 2.54097 + endloop + endfacet + facet normal 0.153986 -0.109492 0.981988 + outer loop + vertex 1.58667 1.23954 2.5412 + vertex 1.5865 1.24281 2.54159 + vertex 1.58302 1.23829 2.54163 + endloop + endfacet + facet normal 0.158251 -0.112786 0.980936 + outer loop + vertex 1.5865 1.24281 2.54159 + vertex 1.58256 1.24307 2.54225 + vertex 1.58302 1.23829 2.54163 + endloop + endfacet + facet normal 0.158899 -0.104857 0.981711 + outer loop + vertex 1.5865 1.24281 2.54159 + vertex 1.58742 1.24799 2.54199 + vertex 1.58256 1.24307 2.54225 + endloop + endfacet + facet normal 0.182691 -0.128664 0.974715 + outer loop + vertex 1.58256 1.24307 2.54225 + vertex 1.58742 1.24799 2.54199 + vertex 1.58253 1.24803 2.54292 + endloop + endfacet + facet normal 0.182651 -0.129916 0.974556 + outer loop + vertex 1.58742 1.24799 2.54199 + vertex 1.58723 1.25297 2.54269 + vertex 1.58253 1.24803 2.54292 + endloop + endfacet + facet normal 0.192042 -0.139001 0.971493 + outer loop + vertex 1.58253 1.24803 2.54292 + vertex 1.58723 1.25297 2.54269 + vertex 1.58258 1.25307 2.54363 + endloop + endfacet + facet normal 0.192721 -0.124166 0.973366 + outer loop + vertex 1.58723 1.25297 2.54269 + vertex 1.58754 1.25799 2.54327 + vertex 1.58258 1.25307 2.54363 + endloop + endfacet + facet normal 0.206659 -0.138559 0.968552 + outer loop + vertex 1.58258 1.25307 2.54363 + vertex 1.58754 1.25799 2.54327 + vertex 1.58264 1.2582 2.54435 + endloop + endfacet + facet normal 0.207606 -0.124884 0.970208 + outer loop + vertex 1.58754 1.25799 2.54327 + vertex 1.58774 1.26318 2.5439 + vertex 1.58264 1.2582 2.54435 + endloop + endfacet + facet normal 0.24109 -0.160389 0.957158 + outer loop + vertex 1.58264 1.2582 2.54435 + vertex 1.58774 1.26318 2.5439 + vertex 1.58277 1.26331 2.54517 + endloop + endfacet + facet normal 0.243005 -0.128455 0.961482 + outer loop + vertex 1.58763 1.26864 2.54465 + vertex 1.58277 1.26331 2.54517 + vertex 1.58774 1.26318 2.5439 + endloop + endfacet + facet normal 0.293799 -0.125488 0.947594 + outer loop + vertex 1.58774 1.26318 2.5439 + vertex 1.59251 1.26819 2.54308 + vertex 1.58763 1.26864 2.54465 + endloop + endfacet + facet normal 0.296188 -0.105208 0.949318 + outer loop + vertex 1.59251 1.26819 2.54308 + vertex 1.59278 1.27353 2.54359 + vertex 1.58763 1.26864 2.54465 + endloop + endfacet + facet normal 0.300497 -0.110163 0.947399 + outer loop + vertex 1.58763 1.26864 2.54465 + vertex 1.59278 1.27353 2.54359 + vertex 1.58883 1.27447 2.54495 + endloop + endfacet + facet normal 0.283026 -0.106862 0.95314 + outer loop + vertex 1.58763 1.26864 2.54465 + vertex 1.58883 1.27447 2.54495 + vertex 1.58478 1.27108 2.54577 + endloop + endfacet + facet normal 0.276981 -0.11433 0.954049 + outer loop + vertex 1.58356 1.26718 2.54566 + vertex 1.58763 1.26864 2.54465 + vertex 1.58478 1.27108 2.54577 + endloop + endfacet + facet normal 0.206528 -0.0928386 0.974026 + outer loop + vertex 1.58478 1.27108 2.54577 + vertex 1.58126 1.26832 2.54626 + vertex 1.58356 1.26718 2.54566 + endloop + endfacet + facet normal 0.195166 -0.115712 0.97392 + outer loop + vertex 1.58356 1.26718 2.54566 + vertex 1.58126 1.26832 2.54626 + vertex 1.58099 1.26523 2.54594 + endloop + endfacet + facet normal 0.233671 -0.169059 0.957506 + outer loop + vertex 1.58356 1.26718 2.54566 + vertex 1.58099 1.26523 2.54594 + vertex 1.58277 1.26331 2.54517 + endloop + endfacet + facet normal 0.207068 -0.0935598 0.973843 + outer loop + vertex 1.58172 1.27252 2.54656 + vertex 1.58126 1.26832 2.54626 + vertex 1.58478 1.27108 2.54577 + endloop + endfacet + facet normal 0.208697 -0.0900788 0.973823 + outer loop + vertex 1.58557 1.27582 2.54604 + vertex 1.58172 1.27252 2.54656 + vertex 1.58478 1.27108 2.54577 + endloop + endfacet + facet normal 0.215091 -0.097895 0.971675 + outer loop + vertex 1.58247 1.27789 2.54694 + vertex 1.58172 1.27252 2.54656 + vertex 1.58557 1.27582 2.54604 + endloop + endfacet + facet normal 0.217056 -0.0949032 0.971535 + outer loop + vertex 1.58645 1.2797 2.54623 + vertex 1.58247 1.27789 2.54694 + vertex 1.58557 1.27582 2.54604 + endloop + endfacet + facet normal 0.285412 -0.109371 0.952144 + outer loop + vertex 1.58924 1.2792 2.54533 + vertex 1.58645 1.2797 2.54623 + vertex 1.58557 1.27582 2.54604 + endloop + endfacet + facet normal 0.278104 -0.100794 0.955248 + outer loop + vertex 1.58883 1.27447 2.54495 + vertex 1.58924 1.2792 2.54533 + vertex 1.58557 1.27582 2.54604 + endloop + endfacet + facet normal 0.303503 -0.102331 0.94732 + outer loop + vertex 1.58883 1.27447 2.54495 + vertex 1.59303 1.27874 2.54407 + vertex 1.58924 1.2792 2.54533 + endloop + endfacet + facet normal 0.303195 -0.104499 0.947181 + outer loop + vertex 1.59284 1.28397 2.54471 + vertex 1.58924 1.2792 2.54533 + vertex 1.59303 1.27874 2.54407 + endloop + endfacet + facet normal 0.30119 -0.104648 0.947805 + outer loop + vertex 1.59303 1.27874 2.54407 + vertex 1.59743 1.28326 2.54317 + vertex 1.59284 1.28397 2.54471 + endloop + endfacet + facet normal 0.301221 -0.104469 0.947814 + outer loop + vertex 1.59743 1.28326 2.54317 + vertex 1.59778 1.2885 2.54363 + vertex 1.59284 1.28397 2.54471 + endloop + endfacet + facet normal 0.300554 -0.103672 0.948114 + outer loop + vertex 1.59284 1.28397 2.54471 + vertex 1.59778 1.2885 2.54363 + vertex 1.59389 1.28952 2.54498 + endloop + endfacet + facet normal 0.307057 -0.104797 0.945904 + outer loop + vertex 1.59284 1.28397 2.54471 + vertex 1.59389 1.28952 2.54498 + vertex 1.58983 1.28621 2.54593 + endloop + endfacet + facet normal 0.305978 -0.106341 0.946081 + outer loop + vertex 1.58888 1.28244 2.54581 + vertex 1.59284 1.28397 2.54471 + vertex 1.58983 1.28621 2.54593 + endloop + endfacet + facet normal 0.276931 -0.0993254 0.955742 + outer loop + vertex 1.58983 1.28621 2.54593 + vertex 1.58609 1.28286 2.54667 + vertex 1.58888 1.28244 2.54581 + endloop + endfacet + facet normal 0.276515 -0.101814 0.955601 + outer loop + vertex 1.58888 1.28244 2.54581 + vertex 1.58609 1.28286 2.54667 + vertex 1.58645 1.2797 2.54623 + endloop + endfacet + facet normal 0.2838 -0.107623 0.952825 + outer loop + vertex 1.58654 1.28738 2.54704 + vertex 1.58609 1.28286 2.54667 + vertex 1.58983 1.28621 2.54593 + endloop + endfacet + facet normal 0.28595 -0.101596 0.952843 + outer loop + vertex 1.59066 1.29083 2.54617 + vertex 1.58654 1.28738 2.54704 + vertex 1.58983 1.28621 2.54593 + endloop + endfacet + facet normal 0.288721 -0.105217 0.951614 + outer loop + vertex 1.5876 1.29286 2.54733 + vertex 1.58654 1.28738 2.54704 + vertex 1.59066 1.29083 2.54617 + endloop + endfacet + facet normal 0.293665 -0.0973749 0.950936 + outer loop + vertex 1.59159 1.29461 2.54627 + vertex 1.5876 1.29286 2.54733 + vertex 1.59066 1.29083 2.54617 + endloop + endfacet + facet normal 0.308758 -0.100951 0.945768 + outer loop + vertex 1.59433 1.2941 2.54533 + vertex 1.59159 1.29461 2.54627 + vertex 1.59066 1.29083 2.54617 + endloop + endfacet + facet normal 0.308838 -0.10105 0.945731 + outer loop + vertex 1.59389 1.28952 2.54498 + vertex 1.59433 1.2941 2.54533 + vertex 1.59066 1.29083 2.54617 + endloop + endfacet + facet normal 0.299419 -0.100394 0.948825 + outer loop + vertex 1.59389 1.28952 2.54498 + vertex 1.59806 1.29362 2.5441 + vertex 1.59433 1.2941 2.54533 + endloop + endfacet + facet normal 0.299485 -0.099946 0.948852 + outer loop + vertex 1.59789 1.29882 2.5447 + vertex 1.59433 1.2941 2.54533 + vertex 1.59806 1.29362 2.5441 + endloop + endfacet + facet normal 0.287549 -0.100751 0.952452 + outer loop + vertex 1.59806 1.29362 2.5441 + vertex 1.60247 1.2981 2.54324 + vertex 1.59789 1.29882 2.5447 + endloop + endfacet + facet normal 0.287437 -0.101394 0.952418 + outer loop + vertex 1.60247 1.2981 2.54324 + vertex 1.60283 1.30339 2.54369 + vertex 1.59789 1.29882 2.5447 + endloop + endfacet + facet normal 0.286363 -0.100134 0.952874 + outer loop + vertex 1.59789 1.29882 2.5447 + vertex 1.60283 1.30339 2.54369 + vertex 1.59893 1.30439 2.54497 + endloop + endfacet + facet normal 0.296888 -0.101934 0.949456 + outer loop + vertex 1.59789 1.29882 2.5447 + vertex 1.59893 1.30439 2.54497 + vertex 1.59489 1.30105 2.54588 + endloop + endfacet + facet normal 0.298919 -0.0990217 0.949127 + outer loop + vertex 1.59398 1.29728 2.54577 + vertex 1.59789 1.29882 2.5447 + vertex 1.59489 1.30105 2.54588 + endloop + endfacet + facet normal 0.309256 -0.101415 0.945556 + outer loop + vertex 1.59489 1.30105 2.54588 + vertex 1.59122 1.29772 2.54672 + vertex 1.59398 1.29728 2.54577 + endloop + endfacet + facet normal 0.309759 -0.0985459 0.945694 + outer loop + vertex 1.59398 1.29728 2.54577 + vertex 1.59122 1.29772 2.54672 + vertex 1.59159 1.29461 2.54627 + endloop + endfacet + facet normal 0.308023 -0.0999142 0.946118 + outer loop + vertex 1.59162 1.30225 2.54707 + vertex 1.59122 1.29772 2.54672 + vertex 1.59489 1.30105 2.54588 + endloop + endfacet + facet normal 0.307095 -0.102463 0.946147 + outer loop + vertex 1.59568 1.30569 2.54612 + vertex 1.59162 1.30225 2.54707 + vertex 1.59489 1.30105 2.54588 + endloop + endfacet + facet normal 0.305772 -0.100728 0.946762 + outer loop + vertex 1.59261 1.30783 2.54734 + vertex 1.59162 1.30225 2.54707 + vertex 1.59568 1.30569 2.54612 + endloop + endfacet + facet normal 0.303317 -0.104461 0.947147 + outer loop + vertex 1.59661 1.30948 2.54624 + vertex 1.59261 1.30783 2.54734 + vertex 1.59568 1.30569 2.54612 + endloop + endfacet + facet normal 0.29209 -0.101843 0.950953 + outer loop + vertex 1.59938 1.30899 2.54534 + vertex 1.59661 1.30948 2.54624 + vertex 1.59568 1.30569 2.54612 + endloop + endfacet + facet normal 0.294446 -0.104726 0.949912 + outer loop + vertex 1.59893 1.30439 2.54497 + vertex 1.59938 1.30899 2.54534 + vertex 1.59568 1.30569 2.54612 + endloop + endfacet + facet normal 0.291304 -0.105898 0.950751 + outer loop + vertex 1.59903 1.31214 2.5458 + vertex 1.59661 1.30948 2.54624 + vertex 1.59938 1.30899 2.54534 + endloop + endfacet + facet normal 0.286439 -0.106638 0.952145 + outer loop + vertex 1.59903 1.31214 2.5458 + vertex 1.59938 1.30899 2.54534 + vertex 1.60296 1.31373 2.54479 + endloop + endfacet + facet normal 0.28588 -0.105034 0.952492 + outer loop + vertex 1.59903 1.31214 2.5458 + vertex 1.60296 1.31373 2.54479 + vertex 1.59992 1.31591 2.54595 + endloop + endfacet + facet normal 0.292063 -0.106415 0.95046 + outer loop + vertex 1.59992 1.31591 2.54595 + vertex 1.59622 1.31263 2.54672 + vertex 1.59903 1.31214 2.5458 + endloop + endfacet + facet normal 0.287583 -0.1009 0.952426 + outer loop + vertex 1.59658 1.31723 2.54709 + vertex 1.59622 1.31263 2.54672 + vertex 1.59992 1.31591 2.54595 + endloop + endfacet + facet normal 0.28835 -0.0989365 0.9524 + outer loop + vertex 1.60066 1.32055 2.5462 + vertex 1.59658 1.31723 2.54709 + vertex 1.59992 1.31591 2.54595 + endloop + endfacet + facet normal 0.283596 -0.0982543 0.953897 + outer loop + vertex 1.59992 1.31591 2.54595 + vertex 1.60397 1.31929 2.54509 + vertex 1.60066 1.32055 2.5462 + endloop + endfacet + facet normal 0.285237 -0.0938958 0.953847 + outer loop + vertex 1.60397 1.31929 2.54509 + vertex 1.60435 1.32389 2.54543 + vertex 1.60066 1.32055 2.5462 + endloop + endfacet + facet normal 0.282293 -0.0903647 0.955063 + outer loop + vertex 1.60435 1.32389 2.54543 + vertex 1.60153 1.32434 2.5463 + vertex 1.60066 1.32055 2.5462 + endloop + endfacet + facet normal 0.283634 -0.0906606 0.954637 + outer loop + vertex 1.60153 1.32434 2.5463 + vertex 1.59754 1.32281 2.54734 + vertex 1.60066 1.32055 2.5462 + endloop + endfacet + facet normal 0.280384 -0.0809542 0.956468 + outer loop + vertex 1.60153 1.32434 2.5463 + vertex 1.60108 1.32754 2.54671 + vertex 1.59754 1.32281 2.54734 + endloop + endfacet + facet normal 0.282969 -0.0830162 0.95553 + outer loop + vertex 1.60108 1.32754 2.54671 + vertex 1.59718 1.32807 2.54791 + vertex 1.59754 1.32281 2.54734 + endloop + endfacet + facet normal 0.295791 -0.0817318 0.95175 + outer loop + vertex 1.59754 1.32281 2.54734 + vertex 1.59718 1.32807 2.54791 + vertex 1.59297 1.32371 2.54884 + endloop + endfacet + facet normal 0.294081 -0.0900496 0.951529 + outer loop + vertex 1.59266 1.31842 2.54844 + vertex 1.59754 1.32281 2.54734 + vertex 1.59297 1.32371 2.54884 + endloop + endfacet + facet normal 0.308762 -0.0905572 0.946819 + outer loop + vertex 1.59266 1.31842 2.54844 + vertex 1.59297 1.32371 2.54884 + vertex 1.58877 1.31968 2.54983 + endloop + endfacet + facet normal 0.306641 -0.0971311 0.946856 + outer loop + vertex 1.58772 1.31395 2.54958 + vertex 1.59266 1.31842 2.54844 + vertex 1.58877 1.31968 2.54983 + endloop + endfacet + facet normal 0.302537 -0.0964424 0.948246 + outer loop + vertex 1.58772 1.31395 2.54958 + vertex 1.58877 1.31968 2.54983 + vertex 1.58468 1.31635 2.55079 + endloop + endfacet + facet normal 0.300196 -0.0996293 0.94866 + outer loop + vertex 1.58373 1.31243 2.55068 + vertex 1.58772 1.31395 2.54958 + vertex 1.58468 1.31635 2.55079 + endloop + endfacet + facet normal 0.248567 -0.0875348 0.964651 + outer loop + vertex 1.58468 1.31635 2.55079 + vertex 1.58098 1.3129 2.55143 + vertex 1.58373 1.31243 2.55068 + endloop + endfacet + facet normal 0.248571 -0.0875124 0.964652 + outer loop + vertex 1.58373 1.31243 2.55068 + vertex 1.58098 1.3129 2.55143 + vertex 1.58131 1.30965 2.55105 + endloop + endfacet + facet normal 0.268991 -0.106233 0.957266 + outer loop + vertex 1.58373 1.31243 2.55068 + vertex 1.58131 1.30965 2.55105 + vertex 1.58397 1.30895 2.55023 + endloop + endfacet + facet normal 0.267346 -0.112207 0.957045 + outer loop + vertex 1.58397 1.30895 2.55023 + vertex 1.58131 1.30965 2.55105 + vertex 1.58027 1.30579 2.55089 + endloop + endfacet + facet normal 0.176725 -0.0887443 0.980251 + outer loop + vertex 1.58131 1.30965 2.55105 + vertex 1.57762 1.30809 2.55158 + vertex 1.58027 1.30579 2.55089 + endloop + endfacet + facet normal 0.179714 -0.0962583 0.978998 + outer loop + vertex 1.58131 1.30965 2.55105 + vertex 1.58098 1.3129 2.55143 + vertex 1.57762 1.30809 2.55158 + endloop + endfacet + facet normal 0.1715 -0.0904401 0.981024 + outer loop + vertex 1.58098 1.3129 2.55143 + vertex 1.57714 1.31296 2.55211 + vertex 1.57762 1.30809 2.55158 + endloop + endfacet + facet normal 0.171518 -0.0898668 0.981074 + outer loop + vertex 1.58098 1.3129 2.55143 + vertex 1.58138 1.3175 2.55178 + vertex 1.57714 1.31296 2.55211 + endloop + endfacet + facet normal 0.178035 -0.0960827 0.979322 + outer loop + vertex 1.57714 1.31296 2.55211 + vertex 1.58138 1.3175 2.55178 + vertex 1.57734 1.31801 2.55257 + endloop + endfacet + facet normal 0.180068 -0.0813194 0.980287 + outer loop + vertex 1.58138 1.3175 2.55178 + vertex 1.58242 1.32308 2.55206 + vertex 1.57734 1.31801 2.55257 + endloop + endfacet + facet normal 0.195286 -0.097018 0.975936 + outer loop + vertex 1.57734 1.31801 2.55257 + vertex 1.58242 1.32308 2.55206 + vertex 1.57761 1.32311 2.55302 + endloop + endfacet + facet normal 0.195437 -0.0912201 0.976465 + outer loop + vertex 1.58242 1.32308 2.55206 + vertex 1.58215 1.32804 2.55257 + vertex 1.57761 1.32311 2.55302 + endloop + endfacet + facet normal 0.194668 -0.090491 0.976686 + outer loop + vertex 1.57761 1.32311 2.55302 + vertex 1.58215 1.32804 2.55257 + vertex 1.57763 1.32809 2.55348 + endloop + endfacet + facet normal 0.19497 -0.0794064 0.97759 + outer loop + vertex 1.58215 1.32804 2.55257 + vertex 1.58218 1.33284 2.55296 + vertex 1.57763 1.32809 2.55348 + endloop + endfacet + facet normal 0.207951 -0.0922331 0.973781 + outer loop + vertex 1.57763 1.32809 2.55348 + vertex 1.58218 1.33284 2.55296 + vertex 1.57752 1.33319 2.55399 + endloop + endfacet + facet normal 0.209131 -0.0789015 0.974699 + outer loop + vertex 1.58218 1.33284 2.55296 + vertex 1.58226 1.33782 2.55334 + vertex 1.57752 1.33319 2.55399 + endloop + endfacet + facet normal 0.243585 -0.115846 0.962936 + outer loop + vertex 1.57752 1.33319 2.55399 + vertex 1.58226 1.33782 2.55334 + vertex 1.57752 1.33869 2.55465 + endloop + endfacet + facet normal 0.251226 -0.077021 0.964859 + outer loop + vertex 1.58226 1.33782 2.55334 + vertex 1.58265 1.34309 2.55366 + vertex 1.57752 1.33869 2.55465 + endloop + endfacet + facet normal 0.276554 -0.108781 0.954822 + outer loop + vertex 1.57752 1.33869 2.55465 + vertex 1.58265 1.34309 2.55366 + vertex 1.57878 1.34435 2.55493 + endloop + endfacet + facet normal 0.288723 -0.0712571 0.954757 + outer loop + vertex 1.58265 1.34309 2.55366 + vertex 1.58298 1.34837 2.55396 + vertex 1.57878 1.34435 2.55493 + endloop + endfacet + facet normal 0.290126 -0.0728525 0.954211 + outer loop + vertex 1.57878 1.34435 2.55493 + vertex 1.58298 1.34837 2.55396 + vertex 1.57914 1.34933 2.5552 + endloop + endfacet + facet normal 0.291293 -0.0681652 0.954202 + outer loop + vertex 1.58298 1.34837 2.55396 + vertex 1.58299 1.35344 2.55432 + vertex 1.57914 1.34933 2.5552 + endloop + endfacet + facet normal 0.293011 -0.0699129 0.95355 + outer loop + vertex 1.57914 1.34933 2.5552 + vertex 1.58299 1.35344 2.55432 + vertex 1.57925 1.35389 2.5555 + endloop + endfacet + facet normal 0.309158 -0.0678062 0.94859 + outer loop + vertex 1.58298 1.34837 2.55396 + vertex 1.58713 1.35283 2.55292 + vertex 1.58299 1.35344 2.55432 + endloop + endfacet + facet normal 0.308826 -0.069931 0.948544 + outer loop + vertex 1.58713 1.35283 2.55292 + vertex 1.58719 1.35789 2.55328 + vertex 1.58299 1.35344 2.55432 + endloop + endfacet + facet normal 0.310577 -0.0717522 0.947836 + outer loop + vertex 1.58299 1.35344 2.55432 + vertex 1.58719 1.35789 2.55328 + vertex 1.58272 1.35872 2.55481 + endloop + endfacet + facet normal 0.310567 -0.0718031 0.947836 + outer loop + vertex 1.58719 1.35789 2.55328 + vertex 1.58764 1.36324 2.55354 + vertex 1.58272 1.35872 2.55481 + endloop + endfacet + facet normal 0.313139 -0.0749086 0.946748 + outer loop + vertex 1.58272 1.35872 2.55481 + vertex 1.58764 1.36324 2.55354 + vertex 1.58377 1.36448 2.55491 + endloop + endfacet + facet normal 0.315218 -0.0682082 0.946565 + outer loop + vertex 1.58764 1.36324 2.55354 + vertex 1.58806 1.36855 2.55378 + vertex 1.58377 1.36448 2.55491 + endloop + endfacet + facet normal 0.308923 -0.0678063 0.948667 + outer loop + vertex 1.58764 1.36324 2.55354 + vertex 1.59251 1.36778 2.55227 + vertex 1.58806 1.36855 2.55378 + endloop + endfacet + facet normal 0.310189 -0.0606182 0.94874 + outer loop + vertex 1.59251 1.36778 2.55227 + vertex 1.59211 1.3729 2.55273 + vertex 1.58806 1.36855 2.55378 + endloop + endfacet + facet normal 0.311683 -0.0621507 0.948151 + outer loop + vertex 1.58806 1.36855 2.55378 + vertex 1.59211 1.3729 2.55273 + vertex 1.58808 1.37355 2.5541 + endloop + endfacet + facet normal 0.318225 -0.0620399 0.945983 + outer loop + vertex 1.58806 1.36855 2.55378 + vertex 1.58808 1.37355 2.5541 + vertex 1.58424 1.36949 2.55512 + endloop + endfacet + facet normal 0.320337 -0.0642535 0.945122 + outer loop + vertex 1.58424 1.36949 2.55512 + vertex 1.58808 1.37355 2.5541 + vertex 1.58439 1.374 2.55538 + endloop + endfacet + facet normal 0.312307 -0.0583658 0.948187 + outer loop + vertex 1.59211 1.3729 2.55273 + vertex 1.59205 1.37788 2.55306 + vertex 1.58808 1.37355 2.5541 + endloop + endfacet + facet normal 0.313728 -0.0598026 0.947628 + outer loop + vertex 1.58808 1.37355 2.5541 + vertex 1.59205 1.37788 2.55306 + vertex 1.58768 1.37873 2.55456 + endloop + endfacet + facet normal 0.314231 -0.0572111 0.947621 + outer loop + vertex 1.59205 1.37788 2.55306 + vertex 1.59227 1.3831 2.5533 + vertex 1.58768 1.37873 2.55456 + endloop + endfacet + facet normal 0.313142 -0.0559406 0.948057 + outer loop + vertex 1.58768 1.37873 2.55456 + vertex 1.59227 1.3831 2.5533 + vertex 1.58852 1.3845 2.55462 + endloop + endfacet + facet normal 0.313236 -0.0556747 0.948042 + outer loop + vertex 1.59227 1.3831 2.5533 + vertex 1.59274 1.38846 2.55346 + vertex 1.58852 1.3845 2.55462 + endloop + endfacet + facet normal 0.299006 -0.0545526 0.952691 + outer loop + vertex 1.59227 1.3831 2.5533 + vertex 1.59654 1.38715 2.55219 + vertex 1.59274 1.38846 2.55346 + endloop + endfacet + facet normal 0.299509 -0.0530225 0.952619 + outer loop + vertex 1.59654 1.38715 2.55219 + vertex 1.5974 1.39286 2.55224 + vertex 1.59274 1.38846 2.55346 + endloop + endfacet + facet normal 0.298863 -0.0522714 0.952863 + outer loop + vertex 1.59274 1.38846 2.55346 + vertex 1.5974 1.39286 2.55224 + vertex 1.59299 1.39366 2.55367 + endloop + endfacet + facet normal 0.31279 -0.0527423 0.948357 + outer loop + vertex 1.59274 1.38846 2.55346 + vertex 1.59299 1.39366 2.55367 + vertex 1.58893 1.38968 2.55478 + endloop + endfacet + facet normal 0.311558 -0.0513523 0.948838 + outer loop + vertex 1.58893 1.38968 2.55478 + vertex 1.59299 1.39366 2.55367 + vertex 1.58917 1.39461 2.55497 + endloop + endfacet + facet normal 0.311991 -0.0495581 0.948792 + outer loop + vertex 1.59299 1.39366 2.55367 + vertex 1.59295 1.39864 2.55394 + vertex 1.58917 1.39461 2.55497 + endloop + endfacet + facet normal 0.300244 -0.0498584 0.952559 + outer loop + vertex 1.59299 1.39366 2.55367 + vertex 1.59698 1.39796 2.55264 + vertex 1.59295 1.39864 2.55394 + endloop + endfacet + facet normal 0.300535 -0.0481315 0.952556 + outer loop + vertex 1.59698 1.39796 2.55264 + vertex 1.59693 1.40293 2.5529 + vertex 1.59295 1.39864 2.55394 + endloop + endfacet + facet normal 0.300175 -0.0477664 0.952687 + outer loop + vertex 1.59295 1.39864 2.55394 + vertex 1.59693 1.40293 2.5529 + vertex 1.59254 1.40382 2.55433 + endloop + endfacet + facet normal 0.310143 -0.0467507 0.94954 + outer loop + vertex 1.59254 1.40382 2.55433 + vertex 1.58925 1.39912 2.55517 + vertex 1.59295 1.39864 2.55394 + endloop + endfacet + facet normal 0.309154 -0.0459939 0.949899 + outer loop + vertex 1.58873 1.40231 2.55549 + vertex 1.58925 1.39912 2.55517 + vertex 1.59254 1.40382 2.55433 + endloop + endfacet + facet normal 0.307786 -0.0420482 0.950526 + outer loop + vertex 1.58873 1.40231 2.55549 + vertex 1.59254 1.40382 2.55433 + vertex 1.58943 1.40615 2.55544 + endloop + endfacet + facet normal 0.315159 -0.0434181 0.948045 + outer loop + vertex 1.58943 1.40615 2.55544 + vertex 1.58593 1.40275 2.55645 + vertex 1.58873 1.40231 2.55549 + endloop + endfacet + facet normal 0.312126 -0.0399557 0.9492 + outer loop + vertex 1.58596 1.40723 2.55663 + vertex 1.58593 1.40275 2.55645 + vertex 1.58943 1.40615 2.55544 + endloop + endfacet + facet normal 0.312308 -0.0393312 0.949166 + outer loop + vertex 1.58979 1.411 2.55552 + vertex 1.58596 1.40723 2.55663 + vertex 1.58943 1.40615 2.55544 + endloop + endfacet + facet normal 0.30278 -0.0386642 0.952276 + outer loop + vertex 1.58943 1.40615 2.55544 + vertex 1.59335 1.40953 2.55433 + vertex 1.58979 1.411 2.55552 + endloop + endfacet + facet normal 0.30267 -0.0389504 0.952299 + outer loop + vertex 1.59335 1.40953 2.55433 + vertex 1.59365 1.41466 2.55444 + vertex 1.58979 1.411 2.55552 + endloop + endfacet + facet normal 0.300022 -0.0358764 0.953257 + outer loop + vertex 1.58979 1.411 2.55552 + vertex 1.59365 1.41466 2.55444 + vertex 1.58996 1.41595 2.55565 + endloop + endfacet + facet normal 0.30996 -0.0361215 0.950063 + outer loop + vertex 1.58996 1.41595 2.55565 + vertex 1.58607 1.41214 2.55678 + vertex 1.58979 1.411 2.55552 + endloop + endfacet + facet normal 0.308806 -0.0348204 0.950488 + outer loop + vertex 1.58619 1.41715 2.55692 + vertex 1.58607 1.41214 2.55678 + vertex 1.58996 1.41595 2.55565 + endloop + endfacet + facet normal 0.308701 -0.0351733 0.950509 + outer loop + vertex 1.59004 1.42089 2.55581 + vertex 1.58619 1.41715 2.55692 + vertex 1.58996 1.41595 2.55565 + endloop + endfacet + facet normal 0.298878 -0.0351111 0.953645 + outer loop + vertex 1.58996 1.41595 2.55565 + vertex 1.59378 1.41963 2.55459 + vertex 1.59004 1.42089 2.55581 + endloop + endfacet + facet normal 0.298827 -0.0352742 0.953655 + outer loop + vertex 1.59378 1.41963 2.55459 + vertex 1.59388 1.42456 2.55474 + vertex 1.59004 1.42089 2.55581 + endloop + endfacet + facet normal 0.298857 -0.0353095 0.953644 + outer loop + vertex 1.59004 1.42089 2.55581 + vertex 1.59388 1.42456 2.55474 + vertex 1.59011 1.42578 2.55597 + endloop + endfacet + facet normal 0.309534 -0.0353378 0.950232 + outer loop + vertex 1.59011 1.42578 2.55597 + vertex 1.58628 1.42211 2.55708 + vertex 1.59004 1.42089 2.55581 + endloop + endfacet + facet normal 0.310953 -0.0369762 0.949706 + outer loop + vertex 1.58635 1.42702 2.55725 + vertex 1.58628 1.42211 2.55708 + vertex 1.59011 1.42578 2.55597 + endloop + endfacet + facet normal 0.311528 -0.0351046 0.949588 + outer loop + vertex 1.59019 1.43068 2.55612 + vertex 1.58635 1.42702 2.55725 + vertex 1.59011 1.42578 2.55597 + endloop + endfacet + facet normal 0.299631 -0.0350066 0.953413 + outer loop + vertex 1.59011 1.42578 2.55597 + vertex 1.59399 1.4295 2.55489 + vertex 1.59019 1.43068 2.55612 + endloop + endfacet + facet normal 0.300286 -0.0327602 0.953286 + outer loop + vertex 1.59399 1.4295 2.55489 + vertex 1.59409 1.43444 2.55503 + vertex 1.59019 1.43068 2.55612 + endloop + endfacet + facet normal 0.300782 -0.0333243 0.953111 + outer loop + vertex 1.59019 1.43068 2.55612 + vertex 1.59409 1.43444 2.55503 + vertex 1.59036 1.43558 2.55624 + endloop + endfacet + facet normal 0.313154 -0.0336467 0.949106 + outer loop + vertex 1.59036 1.43558 2.55624 + vertex 1.58647 1.43193 2.5574 + vertex 1.59019 1.43068 2.55612 + endloop + endfacet + facet normal 0.313088 -0.0335678 0.949131 + outer loop + vertex 1.58675 1.43698 2.55748 + vertex 1.58647 1.43193 2.5574 + vertex 1.59036 1.43558 2.55624 + endloop + endfacet + facet normal 0.313962 -0.0311296 0.948925 + outer loop + vertex 1.59069 1.44041 2.55629 + vertex 1.58675 1.43698 2.55748 + vertex 1.59036 1.43558 2.55624 + endloop + endfacet + facet normal 0.301585 -0.0303138 0.952957 + outer loop + vertex 1.59036 1.43558 2.55624 + vertex 1.5942 1.43932 2.55515 + vertex 1.59069 1.44041 2.55629 + endloop + endfacet + facet normal 0.302443 -0.0273433 0.952775 + outer loop + vertex 1.5942 1.43932 2.55515 + vertex 1.59422 1.44387 2.55527 + vertex 1.59069 1.44041 2.55629 + endloop + endfacet + facet normal 0.301533 -0.0263243 0.953092 + outer loop + vertex 1.59422 1.44387 2.55527 + vertex 1.59134 1.44428 2.55619 + vertex 1.59069 1.44041 2.55629 + endloop + endfacet + facet normal 0.311854 -0.0281374 0.949713 + outer loop + vertex 1.59134 1.44428 2.55619 + vertex 1.58748 1.44262 2.55741 + vertex 1.59069 1.44041 2.55629 + endloop + endfacet + facet normal 0.309532 -0.0220641 0.950633 + outer loop + vertex 1.59134 1.44428 2.55619 + vertex 1.59074 1.44745 2.55646 + vertex 1.58748 1.44262 2.55741 + endloop + endfacet + facet normal 0.311134 -0.0232533 0.950082 + outer loop + vertex 1.59074 1.44745 2.55646 + vertex 1.58697 1.44771 2.5577 + vertex 1.58748 1.44262 2.55741 + endloop + endfacet + facet normal 0.325396 -0.0215566 0.945332 + outer loop + vertex 1.58748 1.44262 2.55741 + vertex 1.58697 1.44771 2.5577 + vertex 1.58311 1.44346 2.55893 + endloop + endfacet + facet normal 0.324567 -0.0261875 0.9455 + outer loop + vertex 1.58301 1.43836 2.55883 + vertex 1.58748 1.44262 2.55741 + vertex 1.58311 1.44346 2.55893 + endloop + endfacet + facet normal 0.327239 -0.0262231 0.944578 + outer loop + vertex 1.58301 1.43836 2.55883 + vertex 1.58311 1.44346 2.55893 + vertex 1.57922 1.4396 2.56018 + endloop + endfacet + facet normal 0.325966 -0.0304439 0.944891 + outer loop + vertex 1.57908 1.43463 2.56006 + vertex 1.58301 1.43836 2.55883 + vertex 1.57922 1.4396 2.56018 + endloop + endfacet + facet normal 0.328248 -0.0331378 0.94401 + outer loop + vertex 1.58276 1.43326 2.55874 + vertex 1.58301 1.43836 2.55883 + vertex 1.57908 1.43463 2.56006 + endloop + endfacet + facet normal 0.327359 -0.0331004 0.94432 + outer loop + vertex 1.58276 1.43326 2.55874 + vertex 1.58675 1.43698 2.55748 + vertex 1.58301 1.43836 2.55883 + endloop + endfacet + facet normal 0.328239 -0.0305041 0.944102 + outer loop + vertex 1.58675 1.43698 2.55748 + vertex 1.58748 1.44262 2.55741 + vertex 1.58301 1.43836 2.55883 + endloop + endfacet + facet normal 0.324725 -0.0208761 0.945578 + outer loop + vertex 1.58311 1.44346 2.55893 + vertex 1.58697 1.44771 2.5577 + vertex 1.58306 1.44842 2.55906 + endloop + endfacet + facet normal 0.326253 -0.0208447 0.945053 + outer loop + vertex 1.58311 1.44346 2.55893 + vertex 1.58306 1.44842 2.55906 + vertex 1.5793 1.44452 2.56027 + endloop + endfacet + facet normal 0.326961 -0.0216097 0.944791 + outer loop + vertex 1.5793 1.44452 2.56027 + vertex 1.58306 1.44842 2.55906 + vertex 1.57937 1.44934 2.56036 + endloop + endfacet + facet normal 0.327263 -0.0202916 0.944715 + outer loop + vertex 1.58306 1.44842 2.55906 + vertex 1.58298 1.45336 2.5592 + vertex 1.57937 1.44934 2.56036 + endloop + endfacet + facet normal 0.330251 -0.0233007 0.943606 + outer loop + vertex 1.57937 1.44934 2.56036 + vertex 1.58298 1.45336 2.5592 + vertex 1.57936 1.45383 2.56047 + endloop + endfacet + facet normal 0.325431 -0.0203361 0.945347 + outer loop + vertex 1.58306 1.44842 2.55906 + vertex 1.58689 1.45264 2.55784 + vertex 1.58298 1.45336 2.5592 + endloop + endfacet + facet normal 0.325461 -0.0201604 0.945341 + outer loop + vertex 1.58689 1.45264 2.55784 + vertex 1.58684 1.45772 2.55796 + vertex 1.58298 1.45336 2.5592 + endloop + endfacet + facet normal 0.3273 -0.0219804 0.944665 + outer loop + vertex 1.58298 1.45336 2.5592 + vertex 1.58684 1.45772 2.55796 + vertex 1.58251 1.45859 2.55948 + endloop + endfacet + facet normal 0.32781 -0.0192576 0.944548 + outer loop + vertex 1.58684 1.45772 2.55796 + vertex 1.58694 1.46298 2.55803 + vertex 1.58251 1.45859 2.55948 + endloop + endfacet + facet normal 0.327113 -0.0184695 0.944805 + outer loop + vertex 1.58251 1.45859 2.55948 + vertex 1.58694 1.46298 2.55803 + vertex 1.58321 1.4644 2.55935 + endloop + endfacet + facet normal 0.32793 -0.0160865 0.944565 + outer loop + vertex 1.58694 1.46298 2.55803 + vertex 1.58713 1.46822 2.55805 + vertex 1.58321 1.4644 2.55935 + endloop + endfacet + facet normal 0.31245 -0.0155429 0.949807 + outer loop + vertex 1.58694 1.46298 2.55803 + vertex 1.59093 1.46699 2.55679 + vertex 1.58713 1.46822 2.55805 + endloop + endfacet + facet normal 0.313396 -0.0123458 0.949542 + outer loop + vertex 1.59093 1.46699 2.55679 + vertex 1.59097 1.472 2.55684 + vertex 1.58713 1.46822 2.55805 + endloop + endfacet + facet normal 0.312768 -0.0116404 0.949758 + outer loop + vertex 1.58713 1.46822 2.55805 + vertex 1.59097 1.472 2.55684 + vertex 1.5872 1.47326 2.55809 + endloop + endfacet + facet normal 0.329116 -0.011811 0.944216 + outer loop + vertex 1.58713 1.46822 2.55805 + vertex 1.5872 1.47326 2.55809 + vertex 1.58344 1.46959 2.55936 + endloop + endfacet + facet normal 0.330016 -0.0128437 0.943888 + outer loop + vertex 1.58344 1.46959 2.55936 + vertex 1.5872 1.47326 2.55809 + vertex 1.58351 1.47462 2.5594 + endloop + endfacet + facet normal 0.331186 -0.00930243 0.94352 + outer loop + vertex 1.5872 1.47326 2.55809 + vertex 1.58721 1.47824 2.55814 + vertex 1.58351 1.47462 2.5594 + endloop + endfacet + facet normal 0.314357 -0.00932379 0.949259 + outer loop + vertex 1.5872 1.47326 2.55809 + vertex 1.59097 1.47696 2.55688 + vertex 1.58721 1.47824 2.55814 + endloop + endfacet + facet normal 0.315124 -0.00682713 0.949026 + outer loop + vertex 1.59097 1.47696 2.55688 + vertex 1.59097 1.48193 2.55692 + vertex 1.58721 1.47824 2.55814 + endloop + endfacet + facet normal 0.303524 -0.00685304 0.952799 + outer loop + vertex 1.59097 1.48193 2.55692 + vertex 1.59097 1.47696 2.55688 + vertex 1.59476 1.48071 2.5557 + endloop + endfacet + facet normal 0.303765 -0.0060326 0.952728 + outer loop + vertex 1.59477 1.48569 2.55573 + vertex 1.59097 1.48193 2.55692 + vertex 1.59476 1.48071 2.5557 + endloop + endfacet + facet normal 0.300808 -0.00602911 0.953666 + outer loop + vertex 1.59476 1.48071 2.5557 + vertex 1.59856 1.48447 2.55453 + vertex 1.59477 1.48569 2.55573 + endloop + endfacet + facet normal 0.300872 -0.00581265 0.953647 + outer loop + vertex 1.59856 1.48447 2.55453 + vertex 1.59858 1.48947 2.55455 + vertex 1.59477 1.48569 2.55573 + endloop + endfacet + facet normal 0.301661 -0.00668701 0.953392 + outer loop + vertex 1.59477 1.48569 2.55573 + vertex 1.59858 1.48947 2.55455 + vertex 1.5948 1.49068 2.55575 + endloop + endfacet + facet normal 0.304752 -0.00670163 0.952408 + outer loop + vertex 1.5948 1.49068 2.55575 + vertex 1.591 1.48691 2.55695 + vertex 1.59477 1.48569 2.55573 + endloop + endfacet + facet normal 0.305228 -0.0072309 0.952252 + outer loop + vertex 1.59103 1.4919 2.55697 + vertex 1.591 1.48691 2.55695 + vertex 1.5948 1.49068 2.55575 + endloop + endfacet + facet normal 0.305429 -0.00654777 0.952192 + outer loop + vertex 1.59484 1.49568 2.55578 + vertex 1.59103 1.4919 2.55697 + vertex 1.5948 1.49068 2.55575 + endloop + endfacet + facet normal 0.302115 -0.00652889 0.953249 + outer loop + vertex 1.5948 1.49068 2.55575 + vertex 1.59861 1.49447 2.55457 + vertex 1.59484 1.49568 2.55578 + endloop + endfacet + facet normal 0.302439 -0.00542312 0.953153 + outer loop + vertex 1.59861 1.49447 2.55457 + vertex 1.59864 1.49946 2.55459 + vertex 1.59484 1.49568 2.55578 + endloop + endfacet + facet normal 0.302606 -0.00560798 0.953099 + outer loop + vertex 1.59484 1.49568 2.55578 + vertex 1.59864 1.49946 2.55459 + vertex 1.59486 1.50067 2.5558 + endloop + endfacet + facet normal 0.305724 -0.00562032 0.952103 + outer loop + vertex 1.59486 1.50067 2.5558 + vertex 1.59106 1.49689 2.557 + vertex 1.59484 1.49568 2.55578 + endloop + endfacet + facet normal 0.305234 -0.00507548 0.952264 + outer loop + vertex 1.59108 1.50189 2.55702 + vertex 1.59106 1.49689 2.557 + vertex 1.59486 1.50067 2.5558 + endloop + endfacet + facet normal 0.305732 -0.00337117 0.952112 + outer loop + vertex 1.59488 1.50566 2.55581 + vertex 1.59108 1.50189 2.55702 + vertex 1.59486 1.50067 2.5558 + endloop + endfacet + facet normal 0.303659 -0.00336872 0.952775 + outer loop + vertex 1.59486 1.50067 2.5558 + vertex 1.59866 1.50445 2.5546 + vertex 1.59488 1.50566 2.55581 + endloop + endfacet + facet normal 0.304606 -0.000111084 0.952478 + outer loop + vertex 1.59866 1.50445 2.5546 + vertex 1.59866 1.50944 2.5546 + vertex 1.59488 1.50566 2.55581 + endloop + endfacet + facet normal 0.305326 -0.000905506 0.952247 + outer loop + vertex 1.59488 1.50566 2.55581 + vertex 1.59866 1.50944 2.5546 + vertex 1.59487 1.51065 2.55582 + endloop + endfacet + facet normal 0.306831 -0.00090354 0.951763 + outer loop + vertex 1.59487 1.51065 2.55582 + vertex 1.59108 1.50688 2.55704 + vertex 1.59488 1.50566 2.55581 + endloop + endfacet + facet normal 0.307397 -0.00153033 0.95158 + outer loop + vertex 1.59108 1.51187 2.55705 + vertex 1.59108 1.50688 2.55704 + vertex 1.59487 1.51065 2.55582 + endloop + endfacet + facet normal 0.308268 0.00147672 0.951298 + outer loop + vertex 1.59486 1.51565 2.55582 + vertex 1.59108 1.51187 2.55705 + vertex 1.59487 1.51065 2.55582 + endloop + endfacet + facet normal 0.307496 0.00147491 0.951548 + outer loop + vertex 1.59487 1.51065 2.55582 + vertex 1.59864 1.51444 2.55459 + vertex 1.59486 1.51565 2.55582 + endloop + endfacet + facet normal 0.308192 0.00388448 0.951316 + outer loop + vertex 1.59864 1.51444 2.55459 + vertex 1.59863 1.51943 2.55458 + vertex 1.59486 1.51565 2.55582 + endloop + endfacet + facet normal 0.309426 0.00252485 0.95092 + outer loop + vertex 1.59486 1.51565 2.55582 + vertex 1.59863 1.51943 2.55458 + vertex 1.59485 1.52064 2.55581 + endloop + endfacet + facet normal 0.309731 0.00252541 0.950821 + outer loop + vertex 1.59485 1.52064 2.55581 + vertex 1.59106 1.51686 2.55705 + vertex 1.59486 1.51565 2.55582 + endloop + endfacet + facet normal 0.310321 0.00187178 0.95063 + outer loop + vertex 1.59106 1.52185 2.55704 + vertex 1.59106 1.51686 2.55705 + vertex 1.59485 1.52064 2.55581 + endloop + endfacet + facet normal 0.310503 0.0025011 0.950569 + outer loop + vertex 1.59484 1.52563 2.5558 + vertex 1.59106 1.52185 2.55704 + vertex 1.59485 1.52064 2.55581 + endloop + endfacet + facet normal 0.31048 0.00250108 0.950577 + outer loop + vertex 1.59485 1.52064 2.55581 + vertex 1.59861 1.52442 2.55457 + vertex 1.59484 1.52563 2.5558 + endloop + endfacet + facet normal 0.31038 0.00215322 0.95061 + outer loop + vertex 1.59861 1.52442 2.55457 + vertex 1.59861 1.52941 2.55456 + vertex 1.59484 1.52563 2.5558 + endloop + endfacet + facet normal 0.309673 0.00293275 0.950839 + outer loop + vertex 1.59484 1.52563 2.5558 + vertex 1.59861 1.52941 2.55456 + vertex 1.59482 1.53062 2.55578 + endloop + endfacet + facet normal 0.310386 0.00293407 0.950606 + outer loop + vertex 1.59482 1.53062 2.55578 + vertex 1.59105 1.52685 2.55703 + vertex 1.59484 1.52563 2.5558 + endloop + endfacet + facet normal 0.309001 0.00446609 0.951051 + outer loop + vertex 1.59103 1.53184 2.55701 + vertex 1.59105 1.52685 2.55703 + vertex 1.59482 1.53062 2.55578 + endloop + endfacet + facet normal 0.309364 0.00572604 0.950926 + outer loop + vertex 1.59479 1.53562 2.55576 + vertex 1.59103 1.53184 2.55701 + vertex 1.59482 1.53062 2.55578 + endloop + endfacet + facet normal 0.307513 0.00571671 0.951527 + outer loop + vertex 1.59482 1.53062 2.55578 + vertex 1.59859 1.5344 2.55455 + vertex 1.59479 1.53562 2.55576 + endloop + endfacet + facet normal 0.307778 0.00663764 0.951435 + outer loop + vertex 1.59859 1.5344 2.55455 + vertex 1.59855 1.5394 2.55452 + vertex 1.59479 1.53562 2.55576 + endloop + endfacet + facet normal 0.304796 0.00990205 0.952366 + outer loop + vertex 1.59479 1.53562 2.55576 + vertex 1.59855 1.5394 2.55452 + vertex 1.59473 1.54061 2.55573 + endloop + endfacet + facet normal 0.3078 0.00993091 0.951399 + outer loop + vertex 1.59473 1.54061 2.55573 + vertex 1.59099 1.53683 2.55698 + vertex 1.59479 1.53562 2.55576 + endloop + endfacet + facet normal 0.305626 0.0123105 0.952072 + outer loop + vertex 1.59092 1.54182 2.55694 + vertex 1.59099 1.53683 2.55698 + vertex 1.59473 1.54061 2.55573 + endloop + endfacet + facet normal 0.306107 0.0140011 0.951894 + outer loop + vertex 1.59466 1.5456 2.55568 + vertex 1.59092 1.54182 2.55694 + vertex 1.59473 1.54061 2.55573 + endloop + endfacet + facet normal 0.302262 0.013955 0.953123 + outer loop + vertex 1.59473 1.54061 2.55573 + vertex 1.59848 1.54439 2.55449 + vertex 1.59466 1.5456 2.55568 + endloop + endfacet + facet normal 0.302137 0.0135128 0.953169 + outer loop + vertex 1.59848 1.54439 2.55449 + vertex 1.59841 1.54938 2.55444 + vertex 1.59466 1.5456 2.55568 + endloop + endfacet + facet normal 0.300646 0.0151381 0.953616 + outer loop + vertex 1.59466 1.5456 2.55568 + vertex 1.59841 1.54938 2.55444 + vertex 1.5946 1.55058 2.55562 + endloop + endfacet + facet normal 0.304895 0.0151712 0.952265 + outer loop + vertex 1.5946 1.55058 2.55562 + vertex 1.59086 1.54681 2.55688 + vertex 1.59466 1.5456 2.55568 + endloop + endfacet + facet normal 0.304223 0.0159047 0.952468 + outer loop + vertex 1.59082 1.5518 2.55681 + vertex 1.59086 1.54681 2.55688 + vertex 1.5946 1.55058 2.55562 + endloop + endfacet + facet normal 0.303844 0.014588 0.95261 + outer loop + vertex 1.59458 1.55557 2.55555 + vertex 1.59082 1.5518 2.55681 + vertex 1.5946 1.55058 2.55562 + endloop + endfacet + facet normal 0.299375 0.0145939 0.954024 + outer loop + vertex 1.5946 1.55058 2.55562 + vertex 1.59837 1.55436 2.55438 + vertex 1.59458 1.55557 2.55555 + endloop + endfacet + facet normal 0.298914 0.0129903 0.954192 + outer loop + vertex 1.59837 1.55436 2.55438 + vertex 1.59836 1.55934 2.55432 + vertex 1.59458 1.55557 2.55555 + endloop + endfacet + facet normal 0.297968 0.0140283 0.954473 + outer loop + vertex 1.59458 1.55557 2.55555 + vertex 1.59836 1.55934 2.55432 + vertex 1.59458 1.56057 2.55548 + endloop + endfacet + facet normal 0.302637 0.0140126 0.953003 + outer loop + vertex 1.59458 1.56057 2.55548 + vertex 1.59081 1.5568 2.55673 + vertex 1.59458 1.55557 2.55555 + endloop + endfacet + facet normal 0.30164 0.0151074 0.953302 + outer loop + vertex 1.59075 1.56183 2.55667 + vertex 1.59081 1.5568 2.55673 + vertex 1.59458 1.56057 2.55548 + endloop + endfacet + facet normal 0.301671 0.0152152 0.953291 + outer loop + vertex 1.59447 1.5656 2.55543 + vertex 1.59075 1.56183 2.55667 + vertex 1.59458 1.56057 2.55548 + endloop + endfacet + facet normal 0.296608 0.0151201 0.95488 + outer loop + vertex 1.59458 1.56057 2.55548 + vertex 1.59833 1.56435 2.55425 + vertex 1.59447 1.5656 2.55543 + endloop + endfacet + facet normal 0.296949 0.0162929 0.954754 + outer loop + vertex 1.59833 1.56435 2.55425 + vertex 1.59814 1.56942 2.55423 + vertex 1.59447 1.5656 2.55543 + endloop + endfacet + facet normal 0.295758 0.017546 0.955102 + outer loop + vertex 1.59447 1.5656 2.55543 + vertex 1.59814 1.56942 2.55423 + vertex 1.59412 1.57058 2.55545 + endloop + endfacet + facet normal 0.300501 0.017886 0.953614 + outer loop + vertex 1.59412 1.57058 2.55545 + vertex 1.59053 1.56686 2.55665 + vertex 1.59447 1.5656 2.55543 + endloop + endfacet + facet normal 0.299723 0.0187084 0.953843 + outer loop + vertex 1.58998 1.57209 2.55672 + vertex 1.59053 1.56686 2.55665 + vertex 1.59412 1.57058 2.55545 + endloop + endfacet + facet normal 0.300587 0.0213667 0.953515 + outer loop + vertex 1.59412 1.57058 2.55545 + vertex 1.5936 1.57465 2.55552 + vertex 1.58998 1.57209 2.55672 + endloop + endfacet + facet normal 0.299325 0.0233195 0.953866 + outer loop + vertex 1.59128 1.57655 2.5562 + vertex 1.58998 1.57209 2.55672 + vertex 1.5936 1.57465 2.55552 + endloop + endfacet + facet normal 0.309907 0.0198469 0.95056 + outer loop + vertex 1.59128 1.57655 2.5562 + vertex 1.58724 1.57623 2.55753 + vertex 1.58998 1.57209 2.55672 + endloop + endfacet + facet normal 0.311821 0.0212371 0.949903 + outer loop + vertex 1.58724 1.57623 2.55753 + vertex 1.58611 1.57167 2.558 + vertex 1.58998 1.57209 2.55672 + endloop + endfacet + facet normal 0.311963 0.0198819 0.949886 + outer loop + vertex 1.58664 1.56793 2.55791 + vertex 1.58998 1.57209 2.55672 + vertex 1.58611 1.57167 2.558 + endloop + endfacet + facet normal 0.32383 0.0216696 0.945867 + outer loop + vertex 1.58664 1.56793 2.55791 + vertex 1.58611 1.57167 2.558 + vertex 1.5835 1.56911 2.55895 + endloop + endfacet + facet normal 0.327072 0.0169173 0.944848 + outer loop + vertex 1.58611 1.57167 2.558 + vertex 1.58724 1.57623 2.55753 + vertex 1.58302 1.57295 2.55905 + endloop + endfacet + facet normal 0.325052 0.0198124 0.945489 + outer loop + vertex 1.58302 1.57295 2.55905 + vertex 1.58724 1.57623 2.55753 + vertex 1.583 1.57796 2.55895 + endloop + endfacet + facet normal 0.327479 0.0266168 0.944484 + outer loop + vertex 1.58724 1.57623 2.55753 + vertex 1.58667 1.5817 2.55757 + vertex 1.583 1.57796 2.55895 + endloop + endfacet + facet normal 0.326857 0.0272997 0.944679 + outer loop + vertex 1.583 1.57796 2.55895 + vertex 1.58667 1.5817 2.55757 + vertex 1.58277 1.58304 2.55888 + endloop + endfacet + facet normal 0.3291 0.0273923 0.943898 + outer loop + vertex 1.583 1.57796 2.55895 + vertex 1.58277 1.58304 2.55888 + vertex 1.5792 1.57946 2.56023 + endloop + endfacet + facet normal 0.326972 0.0212379 0.944795 + outer loop + vertex 1.57928 1.5744 2.56032 + vertex 1.583 1.57796 2.55895 + vertex 1.5792 1.57946 2.56023 + endloop + endfacet + facet normal 0.328298 0.0321297 0.944028 + outer loop + vertex 1.58667 1.5817 2.55757 + vertex 1.58636 1.58677 2.55751 + vertex 1.58277 1.58304 2.55888 + endloop + endfacet + facet normal 0.326821 0.0337228 0.944484 + outer loop + vertex 1.58277 1.58304 2.55888 + vertex 1.58636 1.58677 2.55751 + vertex 1.58258 1.58805 2.55877 + endloop + endfacet + facet normal 0.326601 0.0337161 0.944561 + outer loop + vertex 1.58277 1.58304 2.55888 + vertex 1.58258 1.58805 2.55877 + vertex 1.57905 1.58444 2.56012 + endloop + endfacet + facet normal 0.323106 0.0375279 0.945619 + outer loop + vertex 1.57905 1.58444 2.56012 + vertex 1.58258 1.58805 2.55877 + vertex 1.57889 1.58943 2.55998 + endloop + endfacet + facet normal 0.323247 0.0379637 0.945553 + outer loop + vertex 1.58258 1.58805 2.55877 + vertex 1.58245 1.59305 2.55861 + vertex 1.57889 1.58943 2.55998 + endloop + endfacet + facet normal 0.32585 0.0380003 0.944658 + outer loop + vertex 1.58258 1.58805 2.55877 + vertex 1.58621 1.59177 2.55737 + vertex 1.58245 1.59305 2.55861 + endloop + endfacet + facet normal 0.32595 0.0383424 0.944609 + outer loop + vertex 1.58621 1.59177 2.55737 + vertex 1.58614 1.59676 2.55719 + vertex 1.58245 1.59305 2.55861 + endloop + endfacet + facet normal 0.325915 0.0383816 0.94462 + outer loop + vertex 1.58245 1.59305 2.55861 + vertex 1.58614 1.59676 2.55719 + vertex 1.58238 1.59805 2.55844 + endloop + endfacet + facet normal 0.322957 0.0383734 0.945635 + outer loop + vertex 1.58245 1.59305 2.55861 + vertex 1.58238 1.59805 2.55844 + vertex 1.57876 1.59444 2.55982 + endloop + endfacet + facet normal 0.323569 0.0376895 0.945454 + outer loop + vertex 1.57876 1.59444 2.55982 + vertex 1.58238 1.59805 2.55844 + vertex 1.57868 1.59944 2.55965 + endloop + endfacet + facet normal 0.323243 0.036693 0.945604 + outer loop + vertex 1.58238 1.59805 2.55844 + vertex 1.58229 1.60297 2.55827 + vertex 1.57868 1.59944 2.55965 + endloop + endfacet + facet normal 0.327372 0.0367213 0.944182 + outer loop + vertex 1.58238 1.59805 2.55844 + vertex 1.58608 1.6017 2.55701 + vertex 1.58229 1.60297 2.55827 + endloop + endfacet + facet normal 0.327648 0.0376842 0.944048 + outer loop + vertex 1.58608 1.6017 2.55701 + vertex 1.58583 1.60651 2.5569 + vertex 1.58229 1.60297 2.55827 + endloop + endfacet + facet normal 0.327986 0.0373058 0.943946 + outer loop + vertex 1.58229 1.60297 2.55827 + vertex 1.58583 1.60651 2.5569 + vertex 1.58205 1.60775 2.55817 + endloop + endfacet + facet normal 0.323302 0.0371097 0.945568 + outer loop + vertex 1.58229 1.60297 2.55827 + vertex 1.58205 1.60775 2.55817 + vertex 1.57853 1.60437 2.5595 + endloop + endfacet + facet normal 0.317534 0.0437811 0.947236 + outer loop + vertex 1.57853 1.60437 2.5595 + vertex 1.58205 1.60775 2.55817 + vertex 1.57812 1.60929 2.55941 + endloop + endfacet + facet normal 0.31722 0.0428626 0.947383 + outer loop + vertex 1.58205 1.60775 2.55817 + vertex 1.58184 1.61262 2.55802 + vertex 1.57812 1.60929 2.55941 + endloop + endfacet + facet normal 0.324659 0.0431018 0.944848 + outer loop + vertex 1.58205 1.60775 2.55817 + vertex 1.58524 1.61079 2.55694 + vertex 1.58184 1.61262 2.55802 + endloop + endfacet + facet normal 0.322944 0.039478 0.945594 + outer loop + vertex 1.58524 1.61079 2.55694 + vertex 1.58683 1.61675 2.55614 + vertex 1.58184 1.61262 2.55802 + endloop + endfacet + facet normal 0.315418 0.0495104 0.94766 + outer loop + vertex 1.58184 1.61262 2.55802 + vertex 1.58683 1.61675 2.55614 + vertex 1.5813 1.61678 2.55798 + endloop + endfacet + facet normal 0.296902 0.0471412 0.953744 + outer loop + vertex 1.58184 1.61262 2.55802 + vertex 1.5813 1.61678 2.55798 + vertex 1.57709 1.61447 2.5594 + endloop + endfacet + facet normal 0.315401 0.051111 0.947581 + outer loop + vertex 1.58239 1.6213 2.55737 + vertex 1.5813 1.61678 2.55798 + vertex 1.58683 1.61675 2.55614 + endloop + endfacet + facet normal 0.311798 0.0472247 0.948974 + outer loop + vertex 1.58606 1.62172 2.55615 + vertex 1.58239 1.6213 2.55737 + vertex 1.58683 1.61675 2.55614 + endloop + endfacet + facet normal 0.311397 0.0471623 0.949109 + outer loop + vertex 1.58683 1.61675 2.55614 + vertex 1.58955 1.62343 2.55492 + vertex 1.58606 1.62172 2.55615 + endloop + endfacet + facet normal 0.312055 0.0457097 0.948964 + outer loop + vertex 1.58606 1.62172 2.55615 + vertex 1.58955 1.62343 2.55492 + vertex 1.58554 1.6255 2.55614 + endloop + endfacet + facet normal 0.312815 0.0473673 0.948632 + outer loop + vertex 1.58955 1.62343 2.55492 + vertex 1.58902 1.62915 2.55481 + vertex 1.58554 1.6255 2.55614 + endloop + endfacet + facet normal 0.314955 0.0451032 0.948034 + outer loop + vertex 1.58554 1.6255 2.55614 + vertex 1.58902 1.62915 2.55481 + vertex 1.58511 1.63061 2.55604 + endloop + endfacet + facet normal 0.307345 0.044505 0.950557 + outer loop + vertex 1.58511 1.63061 2.55604 + vertex 1.58144 1.62667 2.55741 + vertex 1.58554 1.6255 2.55614 + endloop + endfacet + facet normal 0.308368 0.0487054 0.95002 + outer loop + vertex 1.58144 1.62667 2.55741 + vertex 1.58239 1.6213 2.55737 + vertex 1.58554 1.6255 2.55614 + endloop + endfacet + facet normal 0.283319 0.0441965 0.958007 + outer loop + vertex 1.58239 1.6213 2.55737 + vertex 1.58144 1.62667 2.55741 + vertex 1.57758 1.62283 2.55872 + endloop + endfacet + facet normal 0.305435 0.0464623 0.951079 + outer loop + vertex 1.58115 1.63174 2.55725 + vertex 1.58144 1.62667 2.55741 + vertex 1.58511 1.63061 2.55604 + endloop + endfacet + facet normal 0.305109 0.0451396 0.951247 + outer loop + vertex 1.58494 1.6357 2.55585 + vertex 1.58115 1.63174 2.55725 + vertex 1.58511 1.63061 2.55604 + endloop + endfacet + facet normal 0.31793 0.0453936 0.947027 + outer loop + vertex 1.58511 1.63061 2.55604 + vertex 1.58871 1.63436 2.55465 + vertex 1.58494 1.6357 2.55585 + endloop + endfacet + facet normal 0.319541 0.050643 0.946218 + outer loop + vertex 1.58871 1.63436 2.55465 + vertex 1.58847 1.63934 2.55446 + vertex 1.58494 1.6357 2.55585 + endloop + endfacet + facet normal 0.32066 0.049437 0.945903 + outer loop + vertex 1.58494 1.6357 2.55585 + vertex 1.58847 1.63934 2.55446 + vertex 1.58474 1.64066 2.55566 + endloop + endfacet + facet normal 0.305399 0.0490096 0.950962 + outer loop + vertex 1.58474 1.64066 2.55566 + vertex 1.58109 1.63677 2.55703 + vertex 1.58494 1.6357 2.55585 + endloop + endfacet + facet normal 0.303687 0.0507784 0.951418 + outer loop + vertex 1.58087 1.64179 2.55683 + vertex 1.58109 1.63677 2.55703 + vertex 1.58474 1.64066 2.55566 + endloop + endfacet + facet normal 0.304724 0.0549008 0.950857 + outer loop + vertex 1.58426 1.64552 2.55553 + vertex 1.58087 1.64179 2.55683 + vertex 1.58474 1.64066 2.55566 + endloop + endfacet + facet normal 0.32312 0.0565504 0.944667 + outer loop + vertex 1.58474 1.64066 2.55566 + vertex 1.58801 1.64411 2.55433 + vertex 1.58426 1.64552 2.55553 + endloop + endfacet + facet normal 0.324993 0.062385 0.943656 + outer loop + vertex 1.58801 1.64411 2.55433 + vertex 1.58746 1.64931 2.55418 + vertex 1.58426 1.64552 2.55553 + endloop + endfacet + facet normal 0.325109 0.0622753 0.943624 + outer loop + vertex 1.58362 1.64956 2.55548 + vertex 1.58426 1.64552 2.55553 + vertex 1.58746 1.64931 2.55418 + endloop + endfacet + facet normal 0.325375 0.0691601 0.943053 + outer loop + vertex 1.58362 1.64956 2.55548 + vertex 1.58746 1.64931 2.55418 + vertex 1.58468 1.65388 2.5548 + endloop + endfacet + facet normal 0.312225 0.0730516 0.947195 + outer loop + vertex 1.58362 1.64956 2.55548 + vertex 1.58468 1.65388 2.5548 + vertex 1.58132 1.65162 2.55608 + endloop + endfacet + facet normal 0.299137 0.0568881 0.952513 + outer loop + vertex 1.58132 1.65162 2.55608 + vertex 1.58019 1.64708 2.55671 + vertex 1.58362 1.64956 2.55548 + endloop + endfacet + facet normal 0.244067 0.0726513 0.967033 + outer loop + vertex 1.58132 1.65162 2.55608 + vertex 1.57724 1.65119 2.55715 + vertex 1.58019 1.64708 2.55671 + endloop + endfacet + facet normal 0.244939 0.0652003 0.967344 + outer loop + vertex 1.58061 1.65566 2.55599 + vertex 1.57724 1.65119 2.55715 + vertex 1.58132 1.65162 2.55608 + endloop + endfacet + facet normal 0.310272 0.0761811 0.94759 + outer loop + vertex 1.58132 1.65162 2.55608 + vertex 1.58468 1.65388 2.5548 + vertex 1.58061 1.65566 2.55599 + endloop + endfacet + facet normal 0.306321 0.0657732 0.949653 + outer loop + vertex 1.58468 1.65388 2.5548 + vertex 1.58381 1.65918 2.55471 + vertex 1.58061 1.65566 2.55599 + endloop + endfacet + facet normal 0.302537 0.0695558 0.950596 + outer loop + vertex 1.58061 1.65566 2.55599 + vertex 1.58381 1.65918 2.55471 + vertex 1.57994 1.66061 2.55584 + endloop + endfacet + facet normal 0.23707 0.0612555 0.969559 + outer loop + vertex 1.57994 1.66061 2.55584 + vertex 1.57655 1.65671 2.55692 + vertex 1.58061 1.65566 2.55599 + endloop + endfacet + facet normal 0.301127 0.0651434 0.951356 + outer loop + vertex 1.58381 1.65918 2.55471 + vertex 1.58316 1.66418 2.55458 + vertex 1.57994 1.66061 2.55584 + endloop + endfacet + facet normal 0.295899 0.0703055 0.952628 + outer loop + vertex 1.57994 1.66061 2.55584 + vertex 1.58316 1.66418 2.55458 + vertex 1.57928 1.66551 2.55569 + endloop + endfacet + facet normal 0.320989 0.067572 0.944669 + outer loop + vertex 1.58381 1.65918 2.55471 + vertex 1.58708 1.6628 2.55334 + vertex 1.58316 1.66418 2.55458 + endloop + endfacet + facet normal 0.320594 0.066246 0.944897 + outer loop + vertex 1.58708 1.6628 2.55334 + vertex 1.58649 1.66767 2.55321 + vertex 1.58316 1.66418 2.55458 + endloop + endfacet + facet normal 0.317843 0.0691565 0.945618 + outer loop + vertex 1.58316 1.66418 2.55458 + vertex 1.58649 1.66767 2.55321 + vertex 1.58239 1.66941 2.55446 + endloop + endfacet + facet normal 0.316899 0.0665806 0.946119 + outer loop + vertex 1.58649 1.66767 2.55321 + vertex 1.5859 1.67169 2.55312 + vertex 1.58239 1.66941 2.55446 + endloop + endfacet + facet normal 0.311181 0.0657798 0.948071 + outer loop + vertex 1.58649 1.66767 2.55321 + vertex 1.58984 1.67177 2.55182 + vertex 1.5859 1.67169 2.55312 + endloop + endfacet + facet normal 0.311168 0.0661042 0.948053 + outer loop + vertex 1.58717 1.67614 2.55239 + vertex 1.5859 1.67169 2.55312 + vertex 1.58984 1.67177 2.55182 + endloop + endfacet + facet normal 0.305855 0.0625978 0.950018 + outer loop + vertex 1.59115 1.67621 2.55111 + vertex 1.58717 1.67614 2.55239 + vertex 1.58984 1.67177 2.55182 + endloop + endfacet + facet normal 0.296982 0.0656277 0.952625 + outer loop + vertex 1.59115 1.67621 2.55111 + vertex 1.58984 1.67177 2.55182 + vertex 1.59347 1.67423 2.55052 + endloop + endfacet + facet normal 0.293272 0.0608441 0.954091 + outer loop + vertex 1.59347 1.67423 2.55052 + vertex 1.59474 1.67868 2.54985 + vertex 1.59115 1.67621 2.55111 + endloop + endfacet + facet normal 0.292818 0.0615519 0.954185 + outer loop + vertex 1.59115 1.67621 2.55111 + vertex 1.59474 1.67868 2.54985 + vertex 1.59052 1.68033 2.55103 + endloop + endfacet + facet normal 0.294847 0.0674638 0.95316 + outer loop + vertex 1.59474 1.67868 2.54985 + vertex 1.59393 1.68403 2.54972 + vertex 1.59052 1.68033 2.55103 + endloop + endfacet + facet normal 0.296537 0.0657575 0.952755 + outer loop + vertex 1.59052 1.68033 2.55103 + vertex 1.59393 1.68403 2.54972 + vertex 1.58985 1.68539 2.55089 + endloop + endfacet + facet normal 0.305275 0.0668329 0.949916 + outer loop + vertex 1.58985 1.68539 2.55089 + vertex 1.58637 1.68159 2.55228 + vertex 1.59052 1.68033 2.55103 + endloop + endfacet + facet normal 0.304671 0.0644917 0.950272 + outer loop + vertex 1.58637 1.68159 2.55228 + vertex 1.58717 1.67614 2.55239 + vertex 1.59052 1.68033 2.55103 + endloop + endfacet + facet normal 0.307491 0.0648822 0.949336 + outer loop + vertex 1.58717 1.67614 2.55239 + vertex 1.58637 1.68159 2.55228 + vertex 1.58288 1.67788 2.55366 + endloop + endfacet + facet normal 0.304981 0.0671291 0.94999 + outer loop + vertex 1.58576 1.68676 2.55211 + vertex 1.58637 1.68159 2.55228 + vertex 1.58985 1.68539 2.55089 + endloop + endfacet + facet normal 0.306209 0.0714293 0.949281 + outer loop + vertex 1.58922 1.69041 2.55072 + vertex 1.58576 1.68676 2.55211 + vertex 1.58985 1.68539 2.55089 + endloop + endfacet + facet normal 0.30129 0.0708733 0.950895 + outer loop + vertex 1.58985 1.68539 2.55089 + vertex 1.59324 1.68912 2.54954 + vertex 1.58922 1.69041 2.55072 + endloop + endfacet + facet normal 0.30398 0.0807667 0.949249 + outer loop + vertex 1.59324 1.68912 2.54954 + vertex 1.59246 1.69441 2.54934 + vertex 1.58922 1.69041 2.55072 + endloop + endfacet + facet normal 0.308292 0.0769067 0.948178 + outer loop + vertex 1.58863 1.69448 2.55058 + vertex 1.58922 1.69041 2.55072 + vertex 1.59246 1.69441 2.54934 + endloop + endfacet + facet normal 0.308205 0.0878486 0.947255 + outer loop + vertex 1.58863 1.69448 2.55058 + vertex 1.59246 1.69441 2.54934 + vertex 1.58973 1.69879 2.54982 + endloop + endfacet + facet normal 0.312561 0.0865098 0.94595 + outer loop + vertex 1.58863 1.69448 2.55058 + vertex 1.58973 1.69879 2.54982 + vertex 1.58631 1.6965 2.55116 + endloop + endfacet + facet normal 0.305915 0.0780472 0.948854 + outer loop + vertex 1.58631 1.6965 2.55116 + vertex 1.58508 1.69205 2.55192 + vertex 1.58863 1.69448 2.55058 + endloop + endfacet + facet normal 0.27823 0.0870352 0.956563 + outer loop + vertex 1.58631 1.6965 2.55116 + vertex 1.58213 1.69609 2.55241 + vertex 1.58508 1.69205 2.55192 + endloop + endfacet + facet normal 0.278482 0.0848551 0.956686 + outer loop + vertex 1.5855 1.70055 2.55104 + vertex 1.58213 1.69609 2.55241 + vertex 1.58631 1.6965 2.55116 + endloop + endfacet + facet normal 0.309842 0.0908403 0.946438 + outer loop + vertex 1.58631 1.6965 2.55116 + vertex 1.58973 1.69879 2.54982 + vertex 1.5855 1.70055 2.55104 + endloop + endfacet + facet normal 0.311298 0.0949603 0.945556 + outer loop + vertex 1.58973 1.69879 2.54982 + vertex 1.58861 1.70411 2.54966 + vertex 1.5855 1.70055 2.55104 + endloop + endfacet + facet normal 0.310173 0.0960423 0.945816 + outer loop + vertex 1.5855 1.70055 2.55104 + vertex 1.58861 1.70411 2.54966 + vertex 1.58451 1.70551 2.55086 + endloop + endfacet + facet normal 0.274406 0.0893026 0.957458 + outer loop + vertex 1.58451 1.70551 2.55086 + vertex 1.58123 1.70163 2.55216 + vertex 1.5855 1.70055 2.55104 + endloop + endfacet + facet normal 0.311419 0.100407 0.944953 + outer loop + vertex 1.58861 1.70411 2.54966 + vertex 1.58746 1.70943 2.54947 + vertex 1.58451 1.70551 2.55086 + endloop + endfacet + facet normal 0.312696 0.0993338 0.944645 + outer loop + vertex 1.58367 1.70963 2.5507 + vertex 1.58451 1.70551 2.55086 + vertex 1.58746 1.70943 2.54947 + endloop + endfacet + facet normal 0.311438 0.100411 0.944947 + outer loop + vertex 1.58861 1.70411 2.54966 + vertex 1.5917 1.70761 2.54827 + vertex 1.58746 1.70943 2.54947 + endloop + endfacet + facet normal 0.312819 0.104195 0.94408 + outer loop + vertex 1.5917 1.70761 2.54827 + vertex 1.59084 1.71163 2.54811 + vertex 1.58746 1.70943 2.54947 + endloop + endfacet + facet normal 0.313205 0.103567 0.944022 + outer loop + vertex 1.58746 1.70943 2.54947 + vertex 1.59084 1.71163 2.54811 + vertex 1.58849 1.71371 2.54866 + endloop + endfacet + facet normal 0.311998 0.103924 0.944382 + outer loop + vertex 1.58466 1.71392 2.5499 + vertex 1.58746 1.70943 2.54947 + vertex 1.58849 1.71371 2.54866 + endloop + endfacet + facet normal 0.311882 0.097083 0.945148 + outer loop + vertex 1.58849 1.71371 2.54866 + vertex 1.58772 1.7178 2.54849 + vertex 1.58466 1.71392 2.5499 + endloop + endfacet + facet normal 0.305292 0.0959347 0.947414 + outer loop + vertex 1.58849 1.71371 2.54866 + vertex 1.59198 1.71603 2.5473 + vertex 1.58772 1.7178 2.54849 + endloop + endfacet + facet normal 0.305031 0.0952035 0.947572 + outer loop + vertex 1.59198 1.71603 2.5473 + vertex 1.59099 1.72141 2.54708 + vertex 1.58772 1.7178 2.54849 + endloop + endfacet + facet normal 0.301242 0.098962 0.948398 + outer loop + vertex 1.58772 1.7178 2.54849 + vertex 1.59099 1.72141 2.54708 + vertex 1.58674 1.72271 2.54829 + endloop + endfacet + facet normal 0.296865 0.0981475 0.949862 + outer loop + vertex 1.58772 1.7178 2.54849 + vertex 1.58674 1.72271 2.54829 + vertex 1.58353 1.71916 2.54966 + endloop + endfacet + facet normal 0.277633 0.116949 0.953542 + outer loop + vertex 1.58353 1.71916 2.54966 + vertex 1.58674 1.72271 2.54829 + vertex 1.58221 1.72418 2.54943 + endloop + endfacet + facet normal 0.272121 0.0970255 0.957359 + outer loop + vertex 1.58674 1.72271 2.54829 + vertex 1.58585 1.72673 2.54814 + vertex 1.58221 1.72418 2.54943 + endloop + endfacet + facet normal 0.295734 0.101953 0.949814 + outer loop + vertex 1.58674 1.72271 2.54829 + vertex 1.58992 1.72682 2.54686 + vertex 1.58585 1.72673 2.54814 + endloop + endfacet + facet normal 0.295558 0.105507 0.949481 + outer loop + vertex 1.58683 1.73119 2.54734 + vertex 1.58585 1.72673 2.54814 + vertex 1.58992 1.72682 2.54686 + endloop + endfacet + facet normal 0.292491 0.103205 0.950683 + outer loop + vertex 1.59093 1.73128 2.54607 + vertex 1.58683 1.73119 2.54734 + vertex 1.58992 1.72682 2.54686 + endloop + endfacet + facet normal 0.296135 0.102203 0.949663 + outer loop + vertex 1.59093 1.73128 2.54607 + vertex 1.58992 1.72682 2.54686 + vertex 1.59342 1.7292 2.54551 + endloop + endfacet + facet normal 0.296208 0.102301 0.949629 + outer loop + vertex 1.59342 1.7292 2.54551 + vertex 1.5943 1.73367 2.54476 + vertex 1.59093 1.73128 2.54607 + endloop + endfacet + facet normal 0.295653 0.10313 0.949712 + outer loop + vertex 1.59093 1.73128 2.54607 + vertex 1.5943 1.73367 2.54476 + vertex 1.58987 1.73537 2.54595 + endloop + endfacet + facet normal 0.296855 0.106801 0.948931 + outer loop + vertex 1.5943 1.73367 2.54476 + vertex 1.59279 1.73939 2.54459 + vertex 1.58987 1.73537 2.54595 + endloop + endfacet + facet normal 0.301001 0.103467 0.947994 + outer loop + vertex 1.58884 1.7395 2.54583 + vertex 1.58987 1.73537 2.54595 + vertex 1.59279 1.73939 2.54459 + endloop + endfacet + facet normal 0.300988 0.105578 0.947765 + outer loop + vertex 1.58884 1.7395 2.54583 + vertex 1.59279 1.73939 2.54459 + vertex 1.5898 1.74388 2.54504 + endloop + endfacet + facet normal 0.290824 0.108309 0.950627 + outer loop + vertex 1.58884 1.7395 2.54583 + vertex 1.5898 1.74388 2.54504 + vertex 1.58639 1.74151 2.54635 + endloop + endfacet + facet normal 0.282904 0.0977309 0.954156 + outer loop + vertex 1.58639 1.74151 2.54635 + vertex 1.58537 1.73682 2.54713 + vertex 1.58884 1.7395 2.54583 + endloop + endfacet + facet normal 0.236817 0.109607 0.965352 + outer loop + vertex 1.58639 1.74151 2.54635 + vertex 1.58212 1.74096 2.54746 + vertex 1.58537 1.73682 2.54713 + endloop + endfacet + facet normal 0.237993 0.10163 0.965935 + outer loop + vertex 1.58556 1.74561 2.54612 + vertex 1.58212 1.74096 2.54746 + vertex 1.58639 1.74151 2.54635 + endloop + endfacet + facet normal 0.288973 0.111112 0.950867 + outer loop + vertex 1.58639 1.74151 2.54635 + vertex 1.5898 1.74388 2.54504 + vertex 1.58556 1.74561 2.54612 + endloop + endfacet + facet normal 0.287405 0.106666 0.951851 + outer loop + vertex 1.5898 1.74388 2.54504 + vertex 1.58867 1.74918 2.54478 + vertex 1.58556 1.74561 2.54612 + endloop + endfacet + facet normal 0.275679 0.117712 0.954015 + outer loop + vertex 1.58556 1.74561 2.54612 + vertex 1.58867 1.74918 2.54478 + vertex 1.58448 1.75053 2.54583 + endloop + endfacet + facet normal 0.220362 0.106523 0.969584 + outer loop + vertex 1.58448 1.75053 2.54583 + vertex 1.58125 1.7466 2.54699 + vertex 1.58556 1.74561 2.54612 + endloop + endfacet + facet normal 0.275997 0.118878 0.953779 + outer loop + vertex 1.58867 1.74918 2.54478 + vertex 1.5873 1.75444 2.54452 + vertex 1.58448 1.75053 2.54583 + endloop + endfacet + facet normal 0.292905 0.122984 0.948199 + outer loop + vertex 1.58867 1.74918 2.54478 + vertex 1.59179 1.75261 2.54337 + vertex 1.5873 1.75444 2.54452 + endloop + endfacet + facet normal 0.290683 0.1166 0.949688 + outer loop + vertex 1.59179 1.75261 2.54337 + vertex 1.59085 1.75661 2.54317 + vertex 1.5873 1.75444 2.54452 + endloop + endfacet + facet normal 0.29594 0.117746 0.947922 + outer loop + vertex 1.59179 1.75261 2.54337 + vertex 1.5949 1.75663 2.5419 + vertex 1.59085 1.75661 2.54317 + endloop + endfacet + facet normal 0.295836 0.120458 0.947613 + outer loop + vertex 1.59177 1.76103 2.54232 + vertex 1.59085 1.75661 2.54317 + vertex 1.5949 1.75663 2.5419 + endloop + endfacet + facet normal 0.29327 0.118533 0.948653 + outer loop + vertex 1.59588 1.76104 2.54105 + vertex 1.59177 1.76103 2.54232 + vertex 1.5949 1.75663 2.5419 + endloop + endfacet + facet normal 0.288678 0.11979 0.949903 + outer loop + vertex 1.59588 1.76104 2.54105 + vertex 1.5949 1.75663 2.5419 + vertex 1.5984 1.75904 2.54054 + endloop + endfacet + facet normal 0.288146 0.119056 0.950156 + outer loop + vertex 1.5984 1.75904 2.54054 + vertex 1.59926 1.7635 2.53972 + vertex 1.59588 1.76104 2.54105 + endloop + endfacet + facet normal 0.289704 0.116808 0.949962 + outer loop + vertex 1.59588 1.76104 2.54105 + vertex 1.59926 1.7635 2.53972 + vertex 1.59478 1.76514 2.54088 + endloop + endfacet + facet normal 0.290943 0.120822 0.949081 + outer loop + vertex 1.59926 1.7635 2.53972 + vertex 1.59769 1.7692 2.53947 + vertex 1.59478 1.76514 2.54088 + endloop + endfacet + facet normal 0.297259 0.11583 0.947745 + outer loop + vertex 1.59368 1.76927 2.54072 + vertex 1.59478 1.76514 2.54088 + vertex 1.59769 1.7692 2.53947 + endloop + endfacet + facet normal 0.297367 0.110385 0.948361 + outer loop + vertex 1.59368 1.76927 2.54072 + vertex 1.59769 1.7692 2.53947 + vertex 1.59461 1.77371 2.53991 + endloop + endfacet + facet normal 0.295846 0.110781 0.94879 + outer loop + vertex 1.59368 1.76927 2.54072 + vertex 1.59461 1.77371 2.53991 + vertex 1.59116 1.7713 2.54127 + endloop + endfacet + facet normal 0.294516 0.108963 0.949414 + outer loop + vertex 1.59116 1.7713 2.54127 + vertex 1.59025 1.76669 2.54208 + vertex 1.59368 1.76927 2.54072 + endloop + endfacet + facet normal 0.265365 0.116094 0.957133 + outer loop + vertex 1.59116 1.7713 2.54127 + vertex 1.58695 1.77088 2.54249 + vertex 1.59025 1.76669 2.54208 + endloop + endfacet + facet normal 0.267409 0.0994912 0.958433 + outer loop + vertex 1.59031 1.77544 2.54108 + vertex 1.58695 1.77088 2.54249 + vertex 1.59116 1.7713 2.54127 + endloop + endfacet + facet normal 0.299288 0.105572 0.948304 + outer loop + vertex 1.59116 1.7713 2.54127 + vertex 1.59461 1.77371 2.53991 + vertex 1.59031 1.77544 2.54108 + endloop + endfacet + facet normal 0.296507 0.0974804 0.950043 + outer loop + vertex 1.59461 1.77371 2.53991 + vertex 1.59352 1.77909 2.5397 + vertex 1.59031 1.77544 2.54108 + endloop + endfacet + facet normal 0.298527 0.0955431 0.949607 + outer loop + vertex 1.59031 1.77544 2.54108 + vertex 1.59352 1.77909 2.5397 + vertex 1.58943 1.78047 2.54085 + endloop + endfacet + facet normal 0.254562 0.0884789 0.963 + outer loop + vertex 1.58943 1.78047 2.54085 + vertex 1.58604 1.77647 2.54211 + vertex 1.59031 1.77544 2.54108 + endloop + endfacet + facet normal 0.296035 0.0868419 0.951221 + outer loop + vertex 1.59352 1.77909 2.5397 + vertex 1.5925 1.78446 2.53953 + vertex 1.58943 1.78047 2.54085 + endloop + endfacet + facet normal 0.310801 0.0894758 0.946254 + outer loop + vertex 1.59352 1.77909 2.5397 + vertex 1.59671 1.78261 2.53832 + vertex 1.5925 1.78446 2.53953 + endloop + endfacet + facet normal 0.306863 0.0933971 0.94716 + outer loop + vertex 1.59765 1.77772 2.5385 + vertex 1.59671 1.78261 2.53832 + vertex 1.59352 1.77909 2.5397 + endloop + endfacet + facet normal 0.29996 0.0921661 0.949489 + outer loop + vertex 1.59765 1.77772 2.5385 + vertex 1.60089 1.78135 2.53712 + vertex 1.59671 1.78261 2.53832 + endloop + endfacet + facet normal 0.298684 0.0871082 0.950368 + outer loop + vertex 1.60089 1.78135 2.53712 + vertex 1.59994 1.78667 2.53693 + vertex 1.59671 1.78261 2.53832 + endloop + endfacet + facet normal 0.291502 0.0858971 0.952706 + outer loop + vertex 1.59994 1.78667 2.53693 + vertex 1.60089 1.78135 2.53712 + vertex 1.60423 1.78507 2.53577 + endloop + endfacet + facet normal 0.288007 0.0892971 0.953456 + outer loop + vertex 1.60423 1.78507 2.53577 + vertex 1.60089 1.78135 2.53712 + vertex 1.6051 1.78015 2.53596 + endloop + endfacet + facet normal 0.285091 0.0888149 0.954377 + outer loop + vertex 1.6051 1.78015 2.53596 + vertex 1.60843 1.78389 2.53462 + vertex 1.60423 1.78507 2.53577 + endloop + endfacet + facet normal 0.284106 0.0846484 0.955049 + outer loop + vertex 1.60843 1.78389 2.53462 + vertex 1.60748 1.78924 2.53443 + vertex 1.60423 1.78507 2.53577 + endloop + endfacet + facet normal 0.286175 0.0828874 0.954586 + outer loop + vertex 1.6035 1.78912 2.53563 + vertex 1.60423 1.78507 2.53577 + vertex 1.60748 1.78924 2.53443 + endloop + endfacet + facet normal 0.279866 0.0938465 0.955441 + outer loop + vertex 1.60946 1.77851 2.53485 + vertex 1.60843 1.78389 2.53462 + vertex 1.6051 1.78015 2.53596 + endloop + endfacet + facet normal 0.281868 0.0999782 0.95423 + outer loop + vertex 1.60594 1.77606 2.53614 + vertex 1.60946 1.77851 2.53485 + vertex 1.6051 1.78015 2.53596 + endloop + endfacet + facet normal 0.28647 0.100853 0.952766 + outer loop + vertex 1.6051 1.78015 2.53596 + vertex 1.60196 1.776 2.53735 + vertex 1.60594 1.77606 2.53614 + endloop + endfacet + facet normal 0.290052 0.0978826 0.951992 + outer loop + vertex 1.60089 1.78135 2.53712 + vertex 1.60196 1.776 2.53735 + vertex 1.6051 1.78015 2.53596 + endloop + endfacet + facet normal 0.293453 0.098513 0.950884 + outer loop + vertex 1.60196 1.776 2.53735 + vertex 1.60089 1.78135 2.53712 + vertex 1.59765 1.77772 2.5385 + endloop + endfacet + facet normal 0.308628 0.0997818 0.945935 + outer loop + vertex 1.59461 1.77371 2.53991 + vertex 1.59765 1.77772 2.5385 + vertex 1.59352 1.77909 2.5397 + endloop + endfacet + facet normal 0.303577 0.104017 0.947112 + outer loop + vertex 1.59852 1.77364 2.53867 + vertex 1.59765 1.77772 2.5385 + vertex 1.59461 1.77371 2.53991 + endloop + endfacet + facet normal 0.294728 0.102243 0.950096 + outer loop + vertex 1.59852 1.77364 2.53867 + vertex 1.60196 1.776 2.53735 + vertex 1.59765 1.77772 2.5385 + endloop + endfacet + facet normal 0.289338 0.110499 0.950828 + outer loop + vertex 1.60102 1.77158 2.53815 + vertex 1.60196 1.776 2.53735 + vertex 1.59852 1.77364 2.53867 + endloop + endfacet + facet normal 0.294171 0.116944 0.948571 + outer loop + vertex 1.59769 1.7692 2.53947 + vertex 1.60102 1.77158 2.53815 + vertex 1.59852 1.77364 2.53867 + endloop + endfacet + facet normal 0.289316 0.124081 0.949157 + outer loop + vertex 1.60216 1.76754 2.53833 + vertex 1.60102 1.77158 2.53815 + vertex 1.59769 1.7692 2.53947 + endloop + endfacet + facet normal 0.281758 0.122059 0.95169 + outer loop + vertex 1.60216 1.76754 2.53833 + vertex 1.60508 1.77158 2.53694 + vertex 1.60102 1.77158 2.53815 + endloop + endfacet + facet normal 0.278945 0.124267 0.952233 + outer loop + vertex 1.60668 1.76595 2.53721 + vertex 1.60508 1.77158 2.53694 + vertex 1.60216 1.76754 2.53833 + endloop + endfacet + facet normal 0.278846 0.123934 0.952305 + outer loop + vertex 1.60331 1.76351 2.53852 + vertex 1.60668 1.76595 2.53721 + vertex 1.60216 1.76754 2.53833 + endloop + endfacet + facet normal 0.28205 0.124794 0.951249 + outer loop + vertex 1.60331 1.76351 2.53852 + vertex 1.60216 1.76754 2.53833 + vertex 1.59926 1.7635 2.53972 + endloop + endfacet + facet normal 0.282158 0.1219 0.951592 + outer loop + vertex 1.59926 1.7635 2.53972 + vertex 1.60238 1.75914 2.53935 + vertex 1.60331 1.76351 2.53852 + endloop + endfacet + facet normal 0.276772 0.123315 0.95299 + outer loop + vertex 1.60238 1.75914 2.53935 + vertex 1.60584 1.76155 2.53803 + vertex 1.60331 1.76351 2.53852 + endloop + endfacet + facet normal 0.277728 0.121885 0.952896 + outer loop + vertex 1.60674 1.75758 2.53828 + vertex 1.60584 1.76155 2.53803 + vertex 1.60238 1.75914 2.53935 + endloop + endfacet + facet normal 0.276714 0.11856 0.95361 + outer loop + vertex 1.60349 1.75392 2.53968 + vertex 1.60674 1.75758 2.53828 + vertex 1.60238 1.75914 2.53935 + endloop + endfacet + facet normal 0.279703 0.119139 0.952666 + outer loop + vertex 1.60349 1.75392 2.53968 + vertex 1.60238 1.75914 2.53935 + vertex 1.59926 1.75503 2.54078 + endloop + endfacet + facet normal 0.278701 0.114464 0.953532 + outer loop + vertex 1.60023 1.75024 2.54107 + vertex 1.60349 1.75392 2.53968 + vertex 1.59926 1.75503 2.54078 + endloop + endfacet + facet normal 0.285648 0.115721 0.951322 + outer loop + vertex 1.59926 1.75503 2.54078 + vertex 1.59601 1.75137 2.5422 + vertex 1.60023 1.75024 2.54107 + endloop + endfacet + facet normal 0.284496 0.11044 0.952295 + outer loop + vertex 1.59601 1.75137 2.5422 + vertex 1.59709 1.74612 2.54249 + vertex 1.60023 1.75024 2.54107 + endloop + endfacet + facet normal 0.282089 0.112438 0.952777 + outer loop + vertex 1.60023 1.75024 2.54107 + vertex 1.59709 1.74612 2.54249 + vertex 1.60108 1.74625 2.54129 + endloop + endfacet + facet normal 0.277939 0.111621 0.954092 + outer loop + vertex 1.60108 1.74625 2.54129 + vertex 1.60459 1.74869 2.53998 + vertex 1.60023 1.75024 2.54107 + endloop + endfacet + facet normal 0.278807 0.110319 0.95399 + outer loop + vertex 1.60361 1.74427 2.54078 + vertex 1.60459 1.74869 2.53998 + vertex 1.60108 1.74625 2.54129 + endloop + endfacet + facet normal 0.278406 0.109759 0.954171 + outer loop + vertex 1.60108 1.74625 2.54129 + vertex 1.60018 1.74177 2.54207 + vertex 1.60361 1.74427 2.54078 + endloop + endfacet + facet normal 0.279642 0.107987 0.954012 + outer loop + vertex 1.6047 1.74019 2.54092 + vertex 1.60361 1.74427 2.54078 + vertex 1.60018 1.74177 2.54207 + endloop + endfacet + facet normal 0.279558 0.107701 0.954069 + outer loop + vertex 1.60018 1.74177 2.54207 + vertex 1.60173 1.73607 2.54226 + vertex 1.6047 1.74019 2.54092 + endloop + endfacet + facet normal 0.280504 0.106954 0.953875 + outer loop + vertex 1.6047 1.74019 2.54092 + vertex 1.60173 1.73607 2.54226 + vertex 1.6058 1.73611 2.54106 + endloop + endfacet + facet normal 0.279967 0.106815 0.954049 + outer loop + vertex 1.6058 1.73611 2.54106 + vertex 1.60923 1.73859 2.53977 + vertex 1.6047 1.74019 2.54092 + endloop + endfacet + facet normal 0.28009 0.107219 0.953967 + outer loop + vertex 1.60923 1.73859 2.53977 + vertex 1.6077 1.74431 2.53958 + vertex 1.6047 1.74019 2.54092 + endloop + endfacet + facet normal 0.279889 0.107167 0.954032 + outer loop + vertex 1.60923 1.73859 2.53977 + vertex 1.61222 1.74269 2.53843 + vertex 1.6077 1.74431 2.53958 + endloop + endfacet + facet normal 0.280225 0.108268 0.953809 + outer loop + vertex 1.61222 1.74269 2.53843 + vertex 1.61112 1.74678 2.53829 + vertex 1.6077 1.74431 2.53958 + endloop + endfacet + facet normal 0.279569 0.109222 0.953893 + outer loop + vertex 1.6077 1.74431 2.53958 + vertex 1.61112 1.74678 2.53829 + vertex 1.6086 1.74879 2.5388 + endloop + endfacet + facet normal 0.27825 0.109547 0.954241 + outer loop + vertex 1.60459 1.74869 2.53998 + vertex 1.6077 1.74431 2.53958 + vertex 1.6086 1.74879 2.5388 + endloop + endfacet + facet normal 0.278048 0.113282 0.953864 + outer loop + vertex 1.6086 1.74879 2.5388 + vertex 1.60772 1.7528 2.53858 + vertex 1.60459 1.74869 2.53998 + endloop + endfacet + facet normal 0.277099 0.114068 0.954046 + outer loop + vertex 1.60459 1.74869 2.53998 + vertex 1.60772 1.7528 2.53858 + vertex 1.60349 1.75392 2.53968 + endloop + endfacet + facet normal 0.27983 0.113638 0.9533 + outer loop + vertex 1.6086 1.74879 2.5388 + vertex 1.61209 1.75119 2.53749 + vertex 1.60772 1.7528 2.53858 + endloop + endfacet + facet normal 0.280386 0.11541 0.952924 + outer loop + vertex 1.61209 1.75119 2.53749 + vertex 1.61097 1.75645 2.53718 + vertex 1.60772 1.7528 2.53858 + endloop + endfacet + facet normal 0.27816 0.11754 0.953316 + outer loop + vertex 1.60772 1.7528 2.53858 + vertex 1.61097 1.75645 2.53718 + vertex 1.60674 1.75758 2.53828 + endloop + endfacet + facet normal 0.27888 0.120817 0.952696 + outer loop + vertex 1.61097 1.75645 2.53718 + vertex 1.60984 1.76165 2.53686 + vertex 1.60674 1.75758 2.53828 + endloop + endfacet + facet normal 0.278508 0.120743 0.952814 + outer loop + vertex 1.60984 1.76165 2.53686 + vertex 1.61097 1.75645 2.53718 + vertex 1.61421 1.76008 2.53578 + endloop + endfacet + facet normal 0.278844 0.121844 0.952575 + outer loop + vertex 1.61421 1.76008 2.53578 + vertex 1.61331 1.76405 2.53553 + vertex 1.60984 1.76165 2.53686 + endloop + endfacet + facet normal 0.27691 0.124753 0.952763 + outer loop + vertex 1.61076 1.766 2.53602 + vertex 1.60984 1.76165 2.53686 + vertex 1.61331 1.76405 2.53553 + endloop + endfacet + facet normal 0.277311 0.125325 0.952571 + outer loop + vertex 1.61331 1.76405 2.53553 + vertex 1.61416 1.76845 2.53471 + vertex 1.61076 1.766 2.53602 + endloop + endfacet + facet normal 0.27706 0.125689 0.952597 + outer loop + vertex 1.61076 1.766 2.53602 + vertex 1.61416 1.76845 2.53471 + vertex 1.60961 1.77 2.53582 + endloop + endfacet + facet normal 0.276767 0.125609 0.952692 + outer loop + vertex 1.60961 1.77 2.53582 + vertex 1.60668 1.76595 2.53721 + vertex 1.61076 1.766 2.53602 + endloop + endfacet + facet normal 0.275752 0.121172 0.953561 + outer loop + vertex 1.61416 1.76845 2.53471 + vertex 1.61257 1.77408 2.53445 + vertex 1.60961 1.77 2.53582 + endloop + endfacet + facet normal 0.275944 0.121021 0.953524 + outer loop + vertex 1.60847 1.77405 2.53564 + vertex 1.60961 1.77 2.53582 + vertex 1.61257 1.77408 2.53445 + endloop + endfacet + facet normal 0.276453 0.10862 0.954869 + outer loop + vertex 1.60847 1.77405 2.53564 + vertex 1.61257 1.77408 2.53445 + vertex 1.60946 1.77851 2.53485 + endloop + endfacet + facet normal 0.276061 0.108724 0.954971 + outer loop + vertex 1.60847 1.77405 2.53564 + vertex 1.60946 1.77851 2.53485 + vertex 1.60594 1.77606 2.53614 + endloop + endfacet + facet normal 0.281504 0.116196 0.952499 + outer loop + vertex 1.60594 1.77606 2.53614 + vertex 1.60508 1.77158 2.53694 + vertex 1.60847 1.77405 2.53564 + endloop + endfacet + facet normal 0.285826 0.115156 0.951337 + outer loop + vertex 1.60594 1.77606 2.53614 + vertex 1.60196 1.776 2.53735 + vertex 1.60508 1.77158 2.53694 + endloop + endfacet + facet normal 0.279867 0.11114 0.953584 + outer loop + vertex 1.60946 1.77851 2.53485 + vertex 1.61257 1.77408 2.53445 + vertex 1.61348 1.77858 2.53366 + endloop + endfacet + facet normal 0.280835 0.1109 0.953327 + outer loop + vertex 1.61257 1.77408 2.53445 + vertex 1.616 1.77655 2.53315 + vertex 1.61348 1.77858 2.53366 + endloop + endfacet + facet normal 0.276175 0.104564 0.955402 + outer loop + vertex 1.616 1.77655 2.53315 + vertex 1.61701 1.78102 2.53237 + vertex 1.61348 1.77858 2.53366 + endloop + endfacet + facet normal 0.281059 0.0971852 0.954757 + outer loop + vertex 1.61348 1.77858 2.53366 + vertex 1.61701 1.78102 2.53237 + vertex 1.61265 1.78269 2.53348 + endloop + endfacet + facet normal 0.280506 0.0970813 0.95493 + outer loop + vertex 1.61348 1.77858 2.53366 + vertex 1.61265 1.78269 2.53348 + vertex 1.60946 1.77851 2.53485 + endloop + endfacet + facet normal 0.283595 0.0945078 0.954276 + outer loop + vertex 1.60946 1.77851 2.53485 + vertex 1.61265 1.78269 2.53348 + vertex 1.60843 1.78389 2.53462 + endloop + endfacet + facet normal 0.281957 0.0877289 0.955408 + outer loop + vertex 1.61265 1.78269 2.53348 + vertex 1.61177 1.78763 2.53329 + vertex 1.60843 1.78389 2.53462 + endloop + endfacet + facet normal 0.28499 0.0847966 0.954772 + outer loop + vertex 1.60843 1.78389 2.53462 + vertex 1.61177 1.78763 2.53329 + vertex 1.60748 1.78924 2.53443 + endloop + endfacet + facet normal 0.283869 0.0880478 0.954812 + outer loop + vertex 1.61265 1.78269 2.53348 + vertex 1.61597 1.78641 2.53215 + vertex 1.61177 1.78763 2.53329 + endloop + endfacet + facet normal 0.283901 0.0881783 0.95479 + outer loop + vertex 1.61597 1.78641 2.53215 + vertex 1.61495 1.79178 2.53196 + vertex 1.61177 1.78763 2.53329 + endloop + endfacet + facet normal 0.284163 0.0882251 0.954708 + outer loop + vertex 1.61495 1.79178 2.53196 + vertex 1.61597 1.78641 2.53215 + vertex 1.61928 1.79012 2.53083 + endloop + endfacet + facet normal 0.283467 0.0888981 0.954853 + outer loop + vertex 1.61928 1.79012 2.53083 + vertex 1.61597 1.78641 2.53215 + vertex 1.62018 1.78519 2.53102 + endloop + endfacet + facet normal 0.285557 0.0892559 0.954196 + outer loop + vertex 1.62018 1.78519 2.53102 + vertex 1.62348 1.78889 2.52968 + vertex 1.61928 1.79012 2.53083 + endloop + endfacet + facet normal 0.286109 0.0914901 0.953819 + outer loop + vertex 1.62348 1.78889 2.52968 + vertex 1.62244 1.79424 2.52948 + vertex 1.61928 1.79012 2.53083 + endloop + endfacet + facet normal 0.28589 0.0916735 0.953867 + outer loop + vertex 1.61846 1.79419 2.53068 + vertex 1.61928 1.79012 2.53083 + vertex 1.62244 1.79424 2.52948 + endloop + endfacet + facet normal 0.285645 0.0914056 0.953967 + outer loop + vertex 1.62348 1.78889 2.52968 + vertex 1.62677 1.79259 2.52834 + vertex 1.62244 1.79424 2.52948 + endloop + endfacet + facet normal 0.286816 0.0949656 0.953267 + outer loop + vertex 1.62677 1.79259 2.52834 + vertex 1.62595 1.79665 2.52819 + vertex 1.62244 1.79424 2.52948 + endloop + endfacet + facet normal 0.281933 0.102418 0.953952 + outer loop + vertex 1.62244 1.79424 2.52948 + vertex 1.62595 1.79665 2.52819 + vertex 1.62344 1.79864 2.52871 + endloop + endfacet + facet normal 0.282905 0.102153 0.953693 + outer loop + vertex 1.61937 1.79863 2.52992 + vertex 1.62244 1.79424 2.52948 + vertex 1.62344 1.79864 2.52871 + endloop + endfacet + facet normal 0.288993 0.0953819 0.952568 + outer loop + vertex 1.62677 1.79259 2.52834 + vertex 1.62993 1.79673 2.52697 + vertex 1.62595 1.79665 2.52819 + endloop + endfacet + facet normal 0.28823 0.11102 0.951104 + outer loop + vertex 1.62685 1.8011 2.5274 + vertex 1.62595 1.79665 2.52819 + vertex 1.62993 1.79673 2.52697 + endloop + endfacet + facet normal 0.284775 0.108449 0.95244 + outer loop + vertex 1.63091 1.80115 2.52617 + vertex 1.62685 1.8011 2.5274 + vertex 1.62993 1.79673 2.52697 + endloop + endfacet + facet normal 0.285471 0.10826 0.952253 + outer loop + vertex 1.63091 1.80115 2.52617 + vertex 1.62993 1.79673 2.52697 + vertex 1.63342 1.79916 2.52565 + endloop + endfacet + facet normal 0.292491 0.117949 0.948966 + outer loop + vertex 1.63342 1.79916 2.52565 + vertex 1.6343 1.80357 2.52483 + vertex 1.63091 1.80115 2.52617 + endloop + endfacet + facet normal 0.286691 0.126436 0.949643 + outer loop + vertex 1.63091 1.80115 2.52617 + vertex 1.6343 1.80357 2.52483 + vertex 1.62979 1.80514 2.52598 + endloop + endfacet + facet normal 0.289105 0.134705 0.947773 + outer loop + vertex 1.6343 1.80357 2.52483 + vertex 1.63266 1.80915 2.52454 + vertex 1.62979 1.80514 2.52598 + endloop + endfacet + facet normal 0.286855 0.136469 0.948204 + outer loop + vertex 1.62859 1.80914 2.52577 + vertex 1.62979 1.80514 2.52598 + vertex 1.63266 1.80915 2.52454 + endloop + endfacet + facet normal 0.286494 0.144812 0.947075 + outer loop + vertex 1.62859 1.80914 2.52577 + vertex 1.63266 1.80915 2.52454 + vertex 1.62928 1.81354 2.52489 + endloop + endfacet + facet normal 0.285087 0.145108 0.947454 + outer loop + vertex 1.62859 1.80914 2.52577 + vertex 1.62928 1.81354 2.52489 + vertex 1.62593 1.81113 2.52627 + endloop + endfacet + facet normal 0.28162 0.140026 0.949254 + outer loop + vertex 1.62593 1.81113 2.52627 + vertex 1.62522 1.80671 2.52713 + vertex 1.62859 1.80914 2.52577 + endloop + endfacet + facet normal 0.283962 0.139531 0.948629 + outer loop + vertex 1.62593 1.81113 2.52627 + vertex 1.62187 1.81109 2.52749 + vertex 1.62522 1.80671 2.52713 + endloop + endfacet + facet normal 0.284174 0.1397 0.948541 + outer loop + vertex 1.62187 1.81109 2.52749 + vertex 1.62115 1.80668 2.52835 + vertex 1.62522 1.80671 2.52713 + endloop + endfacet + facet normal 0.284641 0.129545 0.949841 + outer loop + vertex 1.62233 1.80267 2.52855 + vertex 1.62522 1.80671 2.52713 + vertex 1.62115 1.80668 2.52835 + endloop + endfacet + facet normal 0.28472 0.129567 0.949814 + outer loop + vertex 1.62233 1.80267 2.52855 + vertex 1.62115 1.80668 2.52835 + vertex 1.6178 1.80426 2.52969 + endloop + endfacet + facet normal 0.282158 0.133243 0.95007 + outer loop + vertex 1.6178 1.80426 2.52969 + vertex 1.62115 1.80668 2.52835 + vertex 1.61855 1.80865 2.52885 + endloop + endfacet + facet normal 0.28617 0.128347 0.949544 + outer loop + vertex 1.62685 1.8011 2.5274 + vertex 1.62522 1.80671 2.52713 + vertex 1.62233 1.80267 2.52855 + endloop + endfacet + facet normal 0.283221 0.118255 0.951736 + outer loop + vertex 1.62344 1.79864 2.52871 + vertex 1.62685 1.8011 2.5274 + vertex 1.62233 1.80267 2.52855 + endloop + endfacet + facet normal 0.282352 0.118027 0.952022 + outer loop + vertex 1.62344 1.79864 2.52871 + vertex 1.62233 1.80267 2.52855 + vertex 1.61937 1.79863 2.52992 + endloop + endfacet + facet normal 0.282087 0.127234 0.950915 + outer loop + vertex 1.62522 1.80671 2.52713 + vertex 1.62685 1.8011 2.5274 + vertex 1.62979 1.80514 2.52598 + endloop + endfacet + facet normal 0.286293 0.139242 0.947971 + outer loop + vertex 1.62115 1.80668 2.52835 + vertex 1.62187 1.81109 2.52749 + vertex 1.61855 1.80865 2.52885 + endloop + endfacet + facet normal 0.284625 0.141595 0.948124 + outer loop + vertex 1.61855 1.80865 2.52885 + vertex 1.62187 1.81109 2.52749 + vertex 1.6174 1.81255 2.52861 + endloop + endfacet + facet normal 0.284804 0.141644 0.948063 + outer loop + vertex 1.61855 1.80865 2.52885 + vertex 1.6174 1.81255 2.52861 + vertex 1.61459 1.80856 2.53005 + endloop + endfacet + facet normal 0.284555 0.141836 0.948109 + outer loop + vertex 1.61459 1.80856 2.53005 + vertex 1.6174 1.81255 2.52861 + vertex 1.61326 1.81363 2.52969 + endloop + endfacet + facet normal 0.285374 0.145847 0.947254 + outer loop + vertex 1.6174 1.81255 2.52861 + vertex 1.61594 1.8166 2.52843 + vertex 1.61326 1.81363 2.52969 + endloop + endfacet + facet normal 0.283652 0.14751 0.947514 + outer loop + vertex 1.61326 1.81363 2.52969 + vertex 1.61594 1.8166 2.52843 + vertex 1.61205 1.81891 2.52923 + endloop + endfacet + facet normal 0.282899 0.147359 0.947762 + outer loop + vertex 1.61326 1.81363 2.52969 + vertex 1.61205 1.81891 2.52923 + vertex 1.6091 1.81493 2.53073 + endloop + endfacet + facet normal 0.282109 0.144277 0.948472 + outer loop + vertex 1.61026 1.81018 2.53111 + vertex 1.61326 1.81363 2.52969 + vertex 1.6091 1.81493 2.53073 + endloop + endfacet + facet normal 0.281778 0.144206 0.948581 + outer loop + vertex 1.6091 1.81493 2.53073 + vertex 1.60612 1.81146 2.53214 + vertex 1.61026 1.81018 2.53111 + endloop + endfacet + facet normal 0.280549 0.139341 0.949672 + outer loop + vertex 1.60612 1.81146 2.53214 + vertex 1.60713 1.80624 2.53261 + vertex 1.61026 1.81018 2.53111 + endloop + endfacet + facet normal 0.285889 0.140226 0.947947 + outer loop + vertex 1.60713 1.80624 2.53261 + vertex 1.60612 1.81146 2.53214 + vertex 1.6034 1.80848 2.53341 + endloop + endfacet + facet normal 0.283622 0.13598 0.949246 + outer loop + vertex 1.60243 1.80392 2.53435 + vertex 1.60713 1.80624 2.53261 + vertex 1.6034 1.80848 2.53341 + endloop + endfacet + facet normal 0.29384 0.133261 0.94652 + outer loop + vertex 1.59923 1.80849 2.5347 + vertex 1.60243 1.80392 2.53435 + vertex 1.6034 1.80848 2.53341 + endloop + endfacet + facet normal 0.293473 0.142742 0.945251 + outer loop + vertex 1.6034 1.80848 2.53341 + vertex 1.60196 1.81256 2.53324 + vertex 1.59923 1.80849 2.5347 + endloop + endfacet + facet normal 0.297981 0.139386 0.944341 + outer loop + vertex 1.59923 1.80849 2.5347 + vertex 1.60196 1.81256 2.53324 + vertex 1.59751 1.81416 2.5344 + endloop + endfacet + facet normal 0.300188 0.146852 0.942508 + outer loop + vertex 1.60196 1.81256 2.53324 + vertex 1.60064 1.81656 2.53303 + vertex 1.59751 1.81416 2.5344 + endloop + endfacet + facet normal 0.301087 0.145624 0.942412 + outer loop + vertex 1.59751 1.81416 2.5344 + vertex 1.60064 1.81656 2.53303 + vertex 1.59796 1.81844 2.5336 + endloop + endfacet + facet normal 0.29497 0.146601 0.944193 + outer loop + vertex 1.59412 1.81847 2.53479 + vertex 1.59751 1.81416 2.5344 + vertex 1.59796 1.81844 2.5336 + endloop + endfacet + facet normal 0.294981 0.146306 0.944236 + outer loop + vertex 1.59796 1.81844 2.5336 + vertex 1.5965 1.8217 2.53355 + vertex 1.59412 1.81847 2.53479 + endloop + endfacet + facet normal 0.271079 0.165424 0.948236 + outer loop + vertex 1.59412 1.81847 2.53479 + vertex 1.5965 1.8217 2.53355 + vertex 1.59241 1.82368 2.53437 + endloop + endfacet + facet normal 0.266586 0.154842 0.951292 + outer loop + vertex 1.5965 1.8217 2.53355 + vertex 1.59706 1.82627 2.53265 + vertex 1.59241 1.82368 2.53437 + endloop + endfacet + facet normal 0.29732 0.149404 0.943016 + outer loop + vertex 1.59706 1.82627 2.53265 + vertex 1.5965 1.8217 2.53355 + vertex 1.60094 1.82132 2.53221 + endloop + endfacet + facet normal 0.295223 0.147678 0.943946 + outer loop + vertex 1.6013 1.8261 2.53135 + vertex 1.59706 1.82627 2.53265 + vertex 1.60094 1.82132 2.53221 + endloop + endfacet + facet normal 0.293957 0.14784 0.944316 + outer loop + vertex 1.6013 1.8261 2.53135 + vertex 1.60094 1.82132 2.53221 + vertex 1.60408 1.82408 2.5308 + endloop + endfacet + facet normal 0.294471 0.148622 0.944033 + outer loop + vertex 1.60408 1.82408 2.5308 + vertex 1.60458 1.82845 2.52996 + vertex 1.6013 1.8261 2.53135 + endloop + endfacet + facet normal 0.296354 0.145895 0.943869 + outer loop + vertex 1.6013 1.8261 2.53135 + vertex 1.60458 1.82845 2.52996 + vertex 1.59996 1.83028 2.53112 + endloop + endfacet + facet normal 0.298209 0.151511 0.942399 + outer loop + vertex 1.60458 1.82845 2.52996 + vertex 1.60274 1.83417 2.52962 + vertex 1.59996 1.83028 2.53112 + endloop + endfacet + facet normal 0.303524 0.147307 0.941368 + outer loop + vertex 1.59875 1.83439 2.53087 + vertex 1.59996 1.83028 2.53112 + vertex 1.60274 1.83417 2.52962 + endloop + endfacet + facet normal 0.303546 0.152687 0.940503 + outer loop + vertex 1.59875 1.83439 2.53087 + vertex 1.60274 1.83417 2.52962 + vertex 1.5994 1.83873 2.52996 + endloop + endfacet + facet normal 0.288287 0.155874 0.944772 + outer loop + vertex 1.59875 1.83439 2.53087 + vertex 1.5994 1.83873 2.52996 + vertex 1.59612 1.83643 2.53134 + endloop + endfacet + facet normal 0.281472 0.146285 0.948353 + outer loop + vertex 1.59612 1.83643 2.53134 + vertex 1.59545 1.83196 2.53223 + vertex 1.59875 1.83439 2.53087 + endloop + endfacet + facet normal 0.217506 0.15887 0.963043 + outer loop + vertex 1.59612 1.83643 2.53134 + vertex 1.59179 1.8359 2.5324 + vertex 1.59545 1.83196 2.53223 + endloop + endfacet + facet normal 0.278459 0.170138 0.945258 + outer loop + vertex 1.59612 1.83643 2.53134 + vertex 1.5994 1.83873 2.52996 + vertex 1.59481 1.84037 2.53101 + endloop + endfacet + facet normal 0.303608 0.152735 0.940476 + outer loop + vertex 1.5994 1.83873 2.52996 + vertex 1.60274 1.83417 2.52962 + vertex 1.60341 1.83852 2.5287 + endloop + endfacet + facet normal 0.30361 0.153287 0.940385 + outer loop + vertex 1.60341 1.83852 2.5287 + vertex 1.60214 1.84259 2.52844 + vertex 1.5994 1.83873 2.52996 + endloop + endfacet + facet normal 0.292777 0.161783 0.942395 + outer loop + vertex 1.5994 1.83873 2.52996 + vertex 1.60214 1.84259 2.52844 + vertex 1.59746 1.84434 2.5296 + endloop + endfacet + facet normal 0.290229 0.153532 0.944561 + outer loop + vertex 1.60214 1.84259 2.52844 + vertex 1.60073 1.84669 2.52821 + vertex 1.59746 1.84434 2.5296 + endloop + endfacet + facet normal 0.297882 0.156007 0.941769 + outer loop + vertex 1.60214 1.84259 2.52844 + vertex 1.60483 1.84657 2.52693 + vertex 1.60073 1.84669 2.52821 + endloop + endfacet + facet normal 0.297751 0.162042 0.94079 + outer loop + vertex 1.60103 1.85136 2.52731 + vertex 1.60073 1.84669 2.52821 + vertex 1.60483 1.84657 2.52693 + endloop + endfacet + facet normal 0.293282 0.158338 0.942823 + outer loop + vertex 1.60531 1.85092 2.52605 + vertex 1.60103 1.85136 2.52731 + vertex 1.60483 1.84657 2.52693 + endloop + endfacet + facet normal 0.28936 0.158995 0.943923 + outer loop + vertex 1.60531 1.85092 2.52605 + vertex 1.60483 1.84657 2.52693 + vertex 1.60809 1.84895 2.52553 + endloop + endfacet + facet normal 0.288247 0.157257 0.944555 + outer loop + vertex 1.60809 1.84895 2.52553 + vertex 1.6084 1.8537 2.52465 + vertex 1.60531 1.85092 2.52605 + endloop + endfacet + facet normal 0.289471 0.155825 0.944418 + outer loop + vertex 1.60414 1.85412 2.52588 + vertex 1.60531 1.85092 2.52605 + vertex 1.6084 1.8537 2.52465 + endloop + endfacet + facet normal 0.289656 0.159715 0.943711 + outer loop + vertex 1.60414 1.85412 2.52588 + vertex 1.6084 1.8537 2.52465 + vertex 1.60459 1.8585 2.525 + endloop + endfacet + facet normal 0.292892 0.159195 0.9428 + outer loop + vertex 1.60414 1.85412 2.52588 + vertex 1.60459 1.8585 2.525 + vertex 1.60137 1.85612 2.52641 + endloop + endfacet + facet normal 0.292275 0.158252 0.94315 + outer loop + vertex 1.60137 1.85612 2.52641 + vertex 1.60103 1.85136 2.52731 + vertex 1.60414 1.85412 2.52588 + endloop + endfacet + facet normal 0.264412 0.161682 0.95076 + outer loop + vertex 1.60137 1.85612 2.52641 + vertex 1.59713 1.856 2.52761 + vertex 1.60103 1.85136 2.52731 + endloop + endfacet + facet normal 0.264961 0.15389 0.9519 + outer loop + vertex 1.59994 1.8603 2.52613 + vertex 1.59713 1.856 2.52761 + vertex 1.60137 1.85612 2.52641 + endloop + endfacet + facet normal 0.290783 0.162144 0.94295 + outer loop + vertex 1.60137 1.85612 2.52641 + vertex 1.60459 1.8585 2.525 + vertex 1.59994 1.8603 2.52613 + endloop + endfacet + facet normal 0.289829 0.159185 0.943747 + outer loop + vertex 1.60459 1.8585 2.525 + vertex 1.60261 1.86426 2.52464 + vertex 1.59994 1.8603 2.52613 + endloop + endfacet + facet normal 0.28813 0.160445 0.944054 + outer loop + vertex 1.59862 1.86441 2.52583 + vertex 1.59994 1.8603 2.52613 + vertex 1.60261 1.86426 2.52464 + endloop + endfacet + facet normal 0.296389 0.16129 0.94135 + outer loop + vertex 1.60459 1.8585 2.525 + vertex 1.60717 1.86249 2.52351 + vertex 1.60261 1.86426 2.52464 + endloop + endfacet + facet normal 0.297906 0.16606 0.94004 + outer loop + vertex 1.60717 1.86249 2.52351 + vertex 1.60573 1.86661 2.52324 + vertex 1.60261 1.86426 2.52464 + endloop + endfacet + facet normal 0.29961 0.16372 0.939909 + outer loop + vertex 1.60261 1.86426 2.52464 + vertex 1.60573 1.86661 2.52324 + vertex 1.60304 1.86854 2.52376 + endloop + endfacet + facet normal 0.283973 0.166196 0.944319 + outer loop + vertex 1.59918 1.86852 2.52492 + vertex 1.60261 1.86426 2.52464 + vertex 1.60304 1.86854 2.52376 + endloop + endfacet + facet normal 0.299353 0.163322 0.94006 + outer loop + vertex 1.60573 1.86661 2.52324 + vertex 1.60604 1.87132 2.52232 + vertex 1.60304 1.86854 2.52376 + endloop + endfacet + facet normal 0.292961 0.170589 0.940783 + outer loop + vertex 1.60304 1.86854 2.52376 + vertex 1.60604 1.87132 2.52232 + vertex 1.6016 1.87173 2.52363 + endloop + endfacet + facet normal 0.29036 0.164422 0.942686 + outer loop + vertex 1.60604 1.87132 2.52232 + vertex 1.60573 1.86661 2.52324 + vertex 1.6098 1.86652 2.522 + endloop + endfacet + facet normal 0.292704 0.166331 0.941625 + outer loop + vertex 1.6103 1.87083 2.52108 + vertex 1.60604 1.87132 2.52232 + vertex 1.6098 1.86652 2.522 + endloop + endfacet + facet normal 0.281986 0.168203 0.944559 + outer loop + vertex 1.6103 1.87083 2.52108 + vertex 1.6098 1.86652 2.522 + vertex 1.61306 1.8689 2.5206 + endloop + endfacet + facet normal 0.282193 0.168529 0.944439 + outer loop + vertex 1.61306 1.8689 2.5206 + vertex 1.6134 1.8736 2.51966 + vertex 1.6103 1.87083 2.52108 + endloop + endfacet + facet normal 0.28586 0.164239 0.944092 + outer loop + vertex 1.60916 1.87401 2.52088 + vertex 1.6103 1.87083 2.52108 + vertex 1.6134 1.8736 2.51966 + endloop + endfacet + facet normal 0.285981 0.167144 0.943545 + outer loop + vertex 1.60916 1.87401 2.52088 + vertex 1.6134 1.8736 2.51966 + vertex 1.60961 1.87835 2.51997 + endloop + endfacet + facet normal 0.296116 0.165503 0.940704 + outer loop + vertex 1.60916 1.87401 2.52088 + vertex 1.60961 1.87835 2.51997 + vertex 1.60641 1.87605 2.52138 + endloop + endfacet + facet normal 0.294973 0.163803 0.941361 + outer loop + vertex 1.60641 1.87605 2.52138 + vertex 1.60604 1.87132 2.52232 + vertex 1.60916 1.87401 2.52088 + endloop + endfacet + facet normal 0.285408 0.165095 0.944079 + outer loop + vertex 1.60641 1.87605 2.52138 + vertex 1.60214 1.87623 2.52264 + vertex 1.60604 1.87132 2.52232 + endloop + endfacet + facet normal 0.285421 0.16349 0.944355 + outer loop + vertex 1.60494 1.88024 2.5211 + vertex 1.60214 1.87623 2.52264 + vertex 1.60641 1.87605 2.52138 + endloop + endfacet + facet normal 0.264439 0.179351 0.947579 + outer loop + vertex 1.60021 1.88192 2.5221 + vertex 1.60214 1.87623 2.52264 + vertex 1.60494 1.88024 2.5211 + endloop + endfacet + facet normal 0.29528 0.166697 0.940756 + outer loop + vertex 1.60641 1.87605 2.52138 + vertex 1.60961 1.87835 2.51997 + vertex 1.60494 1.88024 2.5211 + endloop + endfacet + facet normal 0.290916 0.171233 0.941301 + outer loop + vertex 1.60961 1.87835 2.51997 + vertex 1.6134 1.8736 2.51966 + vertex 1.61364 1.87827 2.51874 + endloop + endfacet + facet normal 0.290816 0.174334 0.940762 + outer loop + vertex 1.61364 1.87827 2.51874 + vertex 1.61214 1.88233 2.51845 + vertex 1.60961 1.87835 2.51997 + endloop + endfacet + facet normal 0.295459 0.171053 0.939917 + outer loop + vertex 1.60961 1.87835 2.51997 + vertex 1.61214 1.88233 2.51845 + vertex 1.60746 1.88414 2.51959 + endloop + endfacet + facet normal 0.296918 0.171559 0.939365 + outer loop + vertex 1.60961 1.87835 2.51997 + vertex 1.60746 1.88414 2.51959 + vertex 1.60494 1.88024 2.5211 + endloop + endfacet + facet normal 0.297347 0.177012 0.938217 + outer loop + vertex 1.61214 1.88233 2.51845 + vertex 1.61063 1.8864 2.51816 + vertex 1.60746 1.88414 2.51959 + endloop + endfacet + facet normal 0.290339 0.174587 0.940863 + outer loop + vertex 1.61214 1.88233 2.51845 + vertex 1.61472 1.88636 2.51691 + vertex 1.61063 1.8864 2.51816 + endloop + endfacet + facet normal 0.29034 0.174572 0.940865 + outer loop + vertex 1.6109 1.89107 2.51721 + vertex 1.61063 1.8864 2.51816 + vertex 1.61472 1.88636 2.51691 + endloop + endfacet + facet normal 0.29208 0.176037 0.940053 + outer loop + vertex 1.61517 1.89067 2.51596 + vertex 1.6109 1.89107 2.51721 + vertex 1.61472 1.88636 2.51691 + endloop + endfacet + facet normal 0.282895 0.177541 0.942576 + outer loop + vertex 1.61517 1.89067 2.51596 + vertex 1.61472 1.88636 2.51691 + vertex 1.61796 1.88878 2.51548 + endloop + endfacet + facet normal 0.281589 0.175418 0.943364 + outer loop + vertex 1.61796 1.88878 2.51548 + vertex 1.6182 1.89348 2.51453 + vertex 1.61517 1.89067 2.51596 + endloop + endfacet + facet normal 0.283872 0.172844 0.943155 + outer loop + vertex 1.61396 1.89379 2.51575 + vertex 1.61517 1.89067 2.51596 + vertex 1.6182 1.89348 2.51453 + endloop + endfacet + facet normal 0.283839 0.171219 0.943461 + outer loop + vertex 1.61396 1.89379 2.51575 + vertex 1.6182 1.89348 2.51453 + vertex 1.61431 1.89805 2.51487 + endloop + endfacet + facet normal 0.292765 0.169964 0.940958 + outer loop + vertex 1.61396 1.89379 2.51575 + vertex 1.61431 1.89805 2.51487 + vertex 1.61118 1.89574 2.51626 + endloop + endfacet + facet normal 0.29459 0.172855 0.939861 + outer loop + vertex 1.61118 1.89574 2.51626 + vertex 1.6109 1.89107 2.51721 + vertex 1.61396 1.89379 2.51575 + endloop + endfacet + facet normal 0.294694 0.172843 0.93983 + outer loop + vertex 1.61118 1.89574 2.51626 + vertex 1.60703 1.89588 2.51754 + vertex 1.6109 1.89107 2.51721 + endloop + endfacet + facet normal 0.295465 0.173488 0.939469 + outer loop + vertex 1.60703 1.89588 2.51754 + vertex 1.60657 1.89155 2.51848 + vertex 1.6109 1.89107 2.51721 + endloop + endfacet + facet normal 0.294806 0.167617 0.940741 + outer loop + vertex 1.60967 1.89994 2.51599 + vertex 1.60703 1.89588 2.51754 + vertex 1.61118 1.89574 2.51626 + endloop + endfacet + facet normal 0.285902 0.174021 0.942325 + outer loop + vertex 1.6049 1.90168 2.51711 + vertex 1.60703 1.89588 2.51754 + vertex 1.60967 1.89994 2.51599 + endloop + endfacet + facet normal 0.26358 0.166423 0.950173 + outer loop + vertex 1.60703 1.89588 2.51754 + vertex 1.6049 1.90168 2.51711 + vertex 1.60225 1.89746 2.51859 + endloop + endfacet + facet normal 0.294518 0.16752 0.940849 + outer loop + vertex 1.61118 1.89574 2.51626 + vertex 1.61431 1.89805 2.51487 + vertex 1.60967 1.89994 2.51599 + endloop + endfacet + facet normal 0.295564 0.170626 0.939962 + outer loop + vertex 1.61431 1.89805 2.51487 + vertex 1.61239 1.90388 2.51442 + vertex 1.60967 1.89994 2.51599 + endloop + endfacet + facet normal 0.298548 0.168356 0.939428 + outer loop + vertex 1.60815 1.9042 2.51571 + vertex 1.60967 1.89994 2.51599 + vertex 1.61239 1.90388 2.51442 + endloop + endfacet + facet normal 0.292055 0.169567 0.94125 + outer loop + vertex 1.61431 1.89805 2.51487 + vertex 1.61657 1.90144 2.51356 + vertex 1.61239 1.90388 2.51442 + endloop + endfacet + facet normal 0.2926 0.170629 0.940888 + outer loop + vertex 1.61657 1.90144 2.51356 + vertex 1.61695 1.90606 2.5126 + vertex 1.61239 1.90388 2.51442 + endloop + endfacet + facet normal 0.290967 0.173958 0.940785 + outer loop + vertex 1.61239 1.90388 2.51442 + vertex 1.61695 1.90606 2.5126 + vertex 1.61276 1.90849 2.51345 + endloop + endfacet + facet normal 0.298098 0.17296 0.938734 + outer loop + vertex 1.60835 1.90893 2.51477 + vertex 1.61239 1.90388 2.51442 + vertex 1.61276 1.90849 2.51345 + endloop + endfacet + facet normal 0.298139 0.173951 0.938538 + outer loop + vertex 1.61276 1.90849 2.51345 + vertex 1.61112 1.91183 2.51335 + vertex 1.60835 1.90893 2.51477 + endloop + endfacet + facet normal 0.294511 0.172218 0.940002 + outer loop + vertex 1.61276 1.90849 2.51345 + vertex 1.61503 1.91181 2.51213 + vertex 1.61112 1.91183 2.51335 + endloop + endfacet + facet normal 0.294337 0.175992 0.939358 + outer loop + vertex 1.61116 1.91644 2.51248 + vertex 1.61112 1.91183 2.51335 + vertex 1.61503 1.91181 2.51213 + endloop + endfacet + facet normal 0.292991 0.174819 0.939997 + outer loop + vertex 1.61539 1.916 2.51124 + vertex 1.61116 1.91644 2.51248 + vertex 1.61503 1.91181 2.51213 + endloop + endfacet + facet normal 0.287003 0.17568 0.941683 + outer loop + vertex 1.61539 1.916 2.51124 + vertex 1.61503 1.91181 2.51213 + vertex 1.6182 1.91405 2.51075 + endloop + endfacet + facet normal 0.287717 0.176817 0.941252 + outer loop + vertex 1.6182 1.91405 2.51075 + vertex 1.61839 1.9187 2.50982 + vertex 1.61539 1.916 2.51124 + endloop + endfacet + facet normal 0.289486 0.174769 0.941092 + outer loop + vertex 1.61416 1.91911 2.51104 + vertex 1.61539 1.916 2.51124 + vertex 1.61839 1.9187 2.50982 + endloop + endfacet + facet normal 0.289683 0.179973 0.94005 + outer loop + vertex 1.61416 1.91911 2.51104 + vertex 1.61839 1.9187 2.50982 + vertex 1.61449 1.92331 2.51013 + endloop + endfacet + facet normal 0.292111 0.182106 0.938887 + outer loop + vertex 1.61449 1.92331 2.51013 + vertex 1.61839 1.9187 2.50982 + vertex 1.61838 1.92329 2.50893 + endloop + endfacet + facet normal 0.291939 0.185482 0.93828 + outer loop + vertex 1.61838 1.92329 2.50893 + vertex 1.61673 1.9266 2.50879 + vertex 1.61449 1.92331 2.51013 + endloop + endfacet + facet normal 0.29064 0.18645 0.938491 + outer loop + vertex 1.61449 1.92331 2.51013 + vertex 1.61673 1.9266 2.50879 + vertex 1.61252 1.92904 2.50961 + endloop + endfacet + facet normal 0.291722 0.188565 0.937732 + outer loop + vertex 1.61673 1.9266 2.50879 + vertex 1.61707 1.93115 2.50777 + vertex 1.61252 1.92904 2.50961 + endloop + endfacet + facet normal 0.289978 0.192167 0.937542 + outer loop + vertex 1.61252 1.92904 2.50961 + vertex 1.61707 1.93115 2.50777 + vertex 1.61283 1.93356 2.50858 + endloop + endfacet + facet normal 0.290897 0.19401 0.936877 + outer loop + vertex 1.61707 1.93115 2.50777 + vertex 1.6151 1.93685 2.5072 + vertex 1.61283 1.93356 2.50858 + endloop + endfacet + facet normal 0.284711 0.198674 0.9378 + outer loop + vertex 1.61283 1.93356 2.50858 + vertex 1.6151 1.93685 2.5072 + vertex 1.6111 1.93682 2.50842 + endloop + endfacet + facet normal 0.284079 0.208108 0.935944 + outer loop + vertex 1.61105 1.94131 2.50744 + vertex 1.6111 1.93682 2.50842 + vertex 1.6151 1.93685 2.5072 + endloop + endfacet + facet normal 0.274461 0.199126 0.940755 + outer loop + vertex 1.61541 1.94103 2.50622 + vertex 1.61105 1.94131 2.50744 + vertex 1.6151 1.93685 2.5072 + endloop + endfacet + facet normal 0.289564 0.197066 0.936652 + outer loop + vertex 1.61541 1.94103 2.50622 + vertex 1.6151 1.93685 2.5072 + vertex 1.61826 1.93904 2.50576 + endloop + endfacet + facet normal 0.291312 0.199826 0.935525 + outer loop + vertex 1.61826 1.93904 2.50576 + vertex 1.61834 1.94367 2.50475 + vertex 1.61541 1.94103 2.50622 + endloop + endfacet + facet normal 0.291161 0.199999 0.935535 + outer loop + vertex 1.61409 1.94413 2.50597 + vertex 1.61541 1.94103 2.50622 + vertex 1.61834 1.94367 2.50475 + endloop + endfacet + facet normal 0.291407 0.205968 0.934162 + outer loop + vertex 1.61409 1.94413 2.50597 + vertex 1.61834 1.94367 2.50475 + vertex 1.61428 1.94826 2.505 + endloop + endfacet + facet normal 0.290238 0.2049 0.934761 + outer loop + vertex 1.61428 1.94826 2.505 + vertex 1.61834 1.94367 2.50475 + vertex 1.61817 1.94829 2.50379 + endloop + endfacet + facet normal 0.290192 0.205554 0.934631 + outer loop + vertex 1.61817 1.94829 2.50379 + vertex 1.61632 1.95164 2.50363 + vertex 1.61428 1.94826 2.505 + endloop + endfacet + facet normal 0.291537 0.206271 0.934055 + outer loop + vertex 1.61817 1.94829 2.50379 + vertex 1.62079 1.95124 2.50232 + vertex 1.61632 1.95164 2.50363 + endloop + endfacet + facet normal 0.29164 0.21083 0.933004 + outer loop + vertex 1.61619 1.95643 2.50258 + vertex 1.61632 1.95164 2.50363 + vertex 1.62079 1.95124 2.50232 + endloop + endfacet + facet normal 0.288842 0.208278 0.934447 + outer loop + vertex 1.62068 1.95584 2.50133 + vertex 1.61619 1.95643 2.50258 + vertex 1.62079 1.95124 2.50232 + endloop + endfacet + facet normal 0.287085 0.208349 0.934972 + outer loop + vertex 1.62068 1.95584 2.50133 + vertex 1.62079 1.95124 2.50232 + vertex 1.62368 1.95392 2.50083 + endloop + endfacet + facet normal 0.286237 0.206869 0.935561 + outer loop + vertex 1.62368 1.95392 2.50083 + vertex 1.62357 1.9585 2.49985 + vertex 1.62068 1.95584 2.50133 + endloop + endfacet + facet normal 0.288125 0.204761 0.935445 + outer loop + vertex 1.61918 1.95907 2.50108 + vertex 1.62068 1.95584 2.50133 + vertex 1.62357 1.9585 2.49985 + endloop + endfacet + facet normal 0.288424 0.209559 0.934289 + outer loop + vertex 1.61918 1.95907 2.50108 + vertex 1.62357 1.9585 2.49985 + vertex 1.6193 1.96326 2.5001 + endloop + endfacet + facet normal 0.287129 0.209683 0.93466 + outer loop + vertex 1.61918 1.95907 2.50108 + vertex 1.6193 1.96326 2.5001 + vertex 1.61626 1.96107 2.50153 + endloop + endfacet + facet normal 0.286062 0.207958 0.935373 + outer loop + vertex 1.61626 1.96107 2.50153 + vertex 1.61619 1.95643 2.50258 + vertex 1.61918 1.95907 2.50108 + endloop + endfacet + facet normal 0.252774 0.210441 0.944362 + outer loop + vertex 1.61626 1.96107 2.50153 + vertex 1.61206 1.96091 2.50269 + vertex 1.61619 1.95643 2.50258 + endloop + endfacet + facet normal 0.252903 0.209047 0.944637 + outer loop + vertex 1.61458 1.96503 2.5011 + vertex 1.61206 1.96091 2.50269 + vertex 1.61626 1.96107 2.50153 + endloop + endfacet + facet normal 0.280069 0.219442 0.934562 + outer loop + vertex 1.61626 1.96107 2.50153 + vertex 1.6193 1.96326 2.5001 + vertex 1.61458 1.96503 2.5011 + endloop + endfacet + facet normal 0.289671 0.210712 0.933644 + outer loop + vertex 1.6193 1.96326 2.5001 + vertex 1.62357 1.9585 2.49985 + vertex 1.62327 1.96317 2.49889 + endloop + endfacet + facet normal 0.289597 0.212438 0.933276 + outer loop + vertex 1.62327 1.96317 2.49889 + vertex 1.62132 1.96662 2.49871 + vertex 1.6193 1.96326 2.5001 + endloop + endfacet + facet normal 0.28488 0.215576 0.934008 + outer loop + vertex 1.6193 1.96326 2.5001 + vertex 1.62132 1.96662 2.49871 + vertex 1.61706 1.96884 2.4995 + endloop + endfacet + facet normal 0.28521 0.216305 0.933738 + outer loop + vertex 1.62132 1.96662 2.49871 + vertex 1.62118 1.97147 2.49763 + vertex 1.61706 1.96884 2.4995 + endloop + endfacet + facet normal 0.286502 0.216257 0.933354 + outer loop + vertex 1.62118 1.97147 2.49763 + vertex 1.62132 1.96662 2.49871 + vertex 1.62594 1.96611 2.49741 + endloop + endfacet + facet normal 0.290095 0.219524 0.931479 + outer loop + vertex 1.62568 1.97081 2.49639 + vertex 1.62118 1.97147 2.49763 + vertex 1.62594 1.96611 2.49741 + endloop + endfacet + facet normal 0.281645 0.219604 0.93405 + outer loop + vertex 1.62568 1.97081 2.49639 + vertex 1.62594 1.96611 2.49741 + vertex 1.62877 1.96888 2.49591 + endloop + endfacet + facet normal 0.282593 0.221293 0.933365 + outer loop + vertex 1.62877 1.96888 2.49591 + vertex 1.62854 1.97348 2.49489 + vertex 1.62568 1.97081 2.49639 + endloop + endfacet + facet normal 0.285915 0.217645 0.933211 + outer loop + vertex 1.62415 1.97404 2.4961 + vertex 1.62568 1.97081 2.49639 + vertex 1.62854 1.97348 2.49489 + endloop + endfacet + facet normal 0.278142 0.221364 0.934684 + outer loop + vertex 1.62877 1.96888 2.49591 + vertex 1.63329 1.96843 2.49467 + vertex 1.62854 1.97348 2.49489 + endloop + endfacet + facet normal 0.279913 0.22307 0.93375 + outer loop + vertex 1.62854 1.97348 2.49489 + vertex 1.63329 1.96843 2.49467 + vertex 1.63294 1.97309 2.49366 + endloop + endfacet + facet normal 0.277948 0.223049 0.934341 + outer loop + vertex 1.63329 1.96843 2.49467 + vertex 1.63596 1.97138 2.49317 + vertex 1.63294 1.97309 2.49366 + endloop + endfacet + facet normal 0.278621 0.224385 0.933821 + outer loop + vertex 1.63596 1.97138 2.49317 + vertex 1.6356 1.97599 2.49217 + vertex 1.63294 1.97309 2.49366 + endloop + endfacet + facet normal 0.281841 0.224425 0.932845 + outer loop + vertex 1.6356 1.97599 2.49217 + vertex 1.63596 1.97138 2.49317 + vertex 1.63988 1.97147 2.49196 + endloop + endfacet + facet normal 0.280505 0.223127 0.933559 + outer loop + vertex 1.63995 1.97559 2.49096 + vertex 1.6356 1.97599 2.49217 + vertex 1.63988 1.97147 2.49196 + endloop + endfacet + facet normal 0.282551 0.222956 0.932982 + outer loop + vertex 1.63995 1.97559 2.49096 + vertex 1.63988 1.97147 2.49196 + vertex 1.64284 1.9737 2.49054 + endloop + endfacet + facet normal 0.283282 0.224189 0.932465 + outer loop + vertex 1.64284 1.9737 2.49054 + vertex 1.64274 1.97824 2.48948 + vertex 1.63995 1.97559 2.49096 + endloop + endfacet + facet normal 0.28227 0.225283 0.932508 + outer loop + vertex 1.63841 1.97871 2.49067 + vertex 1.63995 1.97559 2.49096 + vertex 1.64274 1.97824 2.48948 + endloop + endfacet + facet normal 0.282258 0.224991 0.932582 + outer loop + vertex 1.63841 1.97871 2.49067 + vertex 1.64274 1.97824 2.48948 + vertex 1.63828 1.98327 2.48961 + endloop + endfacet + facet normal 0.280899 0.225043 0.93298 + outer loop + vertex 1.63841 1.97871 2.49067 + vertex 1.63828 1.98327 2.48961 + vertex 1.63537 1.98056 2.49114 + endloop + endfacet + facet normal 0.280579 0.224454 0.933218 + outer loop + vertex 1.63537 1.98056 2.49114 + vertex 1.6356 1.97599 2.49217 + vertex 1.63841 1.97871 2.49067 + endloop + endfacet + facet normal 0.282236 0.224427 0.932725 + outer loop + vertex 1.63537 1.98056 2.49114 + vertex 1.63086 1.98105 2.49239 + vertex 1.6356 1.97599 2.49217 + endloop + endfacet + facet normal 0.278605 0.220942 0.934646 + outer loop + vertex 1.63086 1.98105 2.49239 + vertex 1.63121 1.97633 2.4934 + vertex 1.6356 1.97599 2.49217 + endloop + endfacet + facet normal 0.278636 0.224371 0.93382 + outer loop + vertex 1.63294 1.97309 2.49366 + vertex 1.6356 1.97599 2.49217 + vertex 1.63121 1.97633 2.4934 + endloop + endfacet + facet normal 0.279953 0.225026 0.933268 + outer loop + vertex 1.63294 1.97309 2.49366 + vertex 1.63121 1.97633 2.4934 + vertex 1.62854 1.97348 2.49489 + endloop + endfacet + facet normal 0.282956 0.222096 0.933065 + outer loop + vertex 1.62854 1.97348 2.49489 + vertex 1.63121 1.97633 2.4934 + vertex 1.62819 1.97812 2.49389 + endloop + endfacet + facet normal 0.291597 0.22216 0.930385 + outer loop + vertex 1.62427 1.97819 2.4951 + vertex 1.62854 1.97348 2.49489 + vertex 1.62819 1.97812 2.49389 + endloop + endfacet + facet normal 0.291786 0.218321 0.931234 + outer loop + vertex 1.62819 1.97812 2.49389 + vertex 1.62627 1.98152 2.49369 + vertex 1.62427 1.97819 2.4951 + endloop + endfacet + facet normal 0.294344 0.216614 0.930828 + outer loop + vertex 1.62427 1.97819 2.4951 + vertex 1.62627 1.98152 2.49369 + vertex 1.62208 1.98379 2.49449 + endloop + endfacet + facet normal 0.291104 0.215483 0.932108 + outer loop + vertex 1.62427 1.97819 2.4951 + vertex 1.62208 1.98379 2.49449 + vertex 1.61964 1.98007 2.49611 + endloop + endfacet + facet normal 0.28505 0.219816 0.932967 + outer loop + vertex 1.61803 1.98401 2.49568 + vertex 1.61964 1.98007 2.49611 + vertex 1.62208 1.98379 2.49449 + endloop + endfacet + facet normal 0.294605 0.21717 0.930615 + outer loop + vertex 1.62627 1.98152 2.49369 + vertex 1.62615 1.98636 2.4926 + vertex 1.62208 1.98379 2.49449 + endloop + endfacet + facet normal 0.293381 0.219073 0.930556 + outer loop + vertex 1.62208 1.98379 2.49449 + vertex 1.62615 1.98636 2.4926 + vertex 1.62212 1.9875 2.4936 + endloop + endfacet + facet normal 0.266743 0.221162 0.938049 + outer loop + vertex 1.6181 1.98836 2.49455 + vertex 1.62208 1.98379 2.49449 + vertex 1.62212 1.9875 2.4936 + endloop + endfacet + facet normal 0.267777 0.228207 0.936065 + outer loop + vertex 1.62212 1.9875 2.4936 + vertex 1.62217 1.99118 2.49269 + vertex 1.6181 1.98836 2.49455 + endloop + endfacet + facet normal 0.294819 0.225976 0.928448 + outer loop + vertex 1.62217 1.99118 2.49269 + vertex 1.62212 1.9875 2.4936 + vertex 1.62615 1.98636 2.4926 + endloop + endfacet + facet normal 0.289327 0.221376 0.93128 + outer loop + vertex 1.62625 1.99092 2.49149 + vertex 1.62217 1.99118 2.49269 + vertex 1.62615 1.98636 2.4926 + endloop + endfacet + facet normal 0.293354 0.221009 0.930107 + outer loop + vertex 1.62625 1.99092 2.49149 + vertex 1.62615 1.98636 2.4926 + vertex 1.62912 1.9889 2.49106 + endloop + endfacet + facet normal 0.29378 0.22168 0.929813 + outer loop + vertex 1.62912 1.9889 2.49106 + vertex 1.62925 1.99305 2.49003 + vertex 1.62625 1.99092 2.49149 + endloop + endfacet + facet normal 0.292157 0.223941 0.929782 + outer loop + vertex 1.62625 1.99092 2.49149 + vertex 1.62925 1.99305 2.49003 + vertex 1.62458 1.99494 2.49104 + endloop + endfacet + facet normal 0.293403 0.227728 0.928469 + outer loop + vertex 1.62925 1.99305 2.49003 + vertex 1.6269 1.99868 2.48939 + vertex 1.62458 1.99494 2.49104 + endloop + endfacet + facet normal 0.289816 0.230182 0.92899 + outer loop + vertex 1.62285 1.9989 2.4906 + vertex 1.62458 1.99494 2.49104 + vertex 1.6269 1.99868 2.48939 + endloop + endfacet + facet normal 0.290146 0.226517 0.929788 + outer loop + vertex 1.62925 1.99305 2.49003 + vertex 1.63119 1.99642 2.4886 + vertex 1.6269 1.99868 2.48939 + endloop + endfacet + facet normal 0.29206 0.230722 0.928153 + outer loop + vertex 1.63119 1.99642 2.4886 + vertex 1.63085 2.00134 2.48749 + vertex 1.6269 1.99868 2.48939 + endloop + endfacet + facet normal 0.291266 0.231873 0.928116 + outer loop + vertex 1.6269 1.99868 2.48939 + vertex 1.63085 2.00134 2.48749 + vertex 1.62669 2.00251 2.4885 + endloop + endfacet + facet normal 0.277032 0.232108 0.932405 + outer loop + vertex 1.62274 2.00321 2.4895 + vertex 1.6269 1.99868 2.48939 + vertex 1.62669 2.00251 2.4885 + endloop + endfacet + facet normal 0.277448 0.236085 0.931282 + outer loop + vertex 1.62669 2.00251 2.4885 + vertex 1.62632 2.00647 2.48761 + vertex 1.62274 2.00321 2.4895 + endloop + endfacet + facet normal 0.292203 0.236445 0.926667 + outer loop + vertex 1.62632 2.00647 2.48761 + vertex 1.62669 2.00251 2.4885 + vertex 1.63085 2.00134 2.48749 + endloop + endfacet + facet normal 0.291195 0.235542 0.927214 + outer loop + vertex 1.63068 2.0059 2.48638 + vertex 1.62632 2.00647 2.48761 + vertex 1.63085 2.00134 2.48749 + endloop + endfacet + facet normal 0.289698 0.2356 0.927668 + outer loop + vertex 1.63068 2.0059 2.48638 + vertex 1.63085 2.00134 2.48749 + vertex 1.63377 2.00393 2.48592 + endloop + endfacet + facet normal 0.290641 0.237246 0.926953 + outer loop + vertex 1.63377 2.00393 2.48592 + vertex 1.63353 2.00847 2.48483 + vertex 1.63068 2.0059 2.48638 + endloop + endfacet + facet normal 0.293227 0.234334 0.92688 + outer loop + vertex 1.62914 2.00908 2.48607 + vertex 1.63068 2.0059 2.48638 + vertex 1.63353 2.00847 2.48483 + endloop + endfacet + facet normal 0.29334 0.236166 0.926379 + outer loop + vertex 1.62914 2.00908 2.48607 + vertex 1.63353 2.00847 2.48483 + vertex 1.62922 2.01311 2.48501 + endloop + endfacet + facet normal 0.297437 0.240057 0.924069 + outer loop + vertex 1.62922 2.01311 2.48501 + vertex 1.63353 2.00847 2.48483 + vertex 1.63314 2.01303 2.48377 + endloop + endfacet + facet normal 0.297475 0.239365 0.924236 + outer loop + vertex 1.63314 2.01303 2.48377 + vertex 1.63116 2.01639 2.48354 + vertex 1.62922 2.01311 2.48501 + endloop + endfacet + facet normal 0.295142 0.240904 0.924585 + outer loop + vertex 1.62922 2.01311 2.48501 + vertex 1.63116 2.01639 2.48354 + vertex 1.62696 2.01844 2.48435 + endloop + endfacet + facet normal 0.295679 0.242204 0.924073 + outer loop + vertex 1.63116 2.01639 2.48354 + vertex 1.63077 2.02119 2.48241 + vertex 1.62696 2.01844 2.48435 + endloop + endfacet + facet normal 0.293517 0.242195 0.924764 + outer loop + vertex 1.63077 2.02119 2.48241 + vertex 1.63116 2.01639 2.48354 + vertex 1.63573 2.01586 2.48223 + endloop + endfacet + facet normal 0.293935 0.242591 0.924528 + outer loop + vertex 1.63535 2.0205 2.48113 + vertex 1.63077 2.02119 2.48241 + vertex 1.63573 2.01586 2.48223 + endloop + endfacet + facet normal 0.286334 0.242531 0.926926 + outer loop + vertex 1.63535 2.0205 2.48113 + vertex 1.63573 2.01586 2.48223 + vertex 1.63847 2.01854 2.48068 + endloop + endfacet + facet normal 0.285425 0.240921 0.927626 + outer loop + vertex 1.63847 2.01854 2.48068 + vertex 1.63821 2.02313 2.47957 + vertex 1.63535 2.0205 2.48113 + endloop + endfacet + facet normal 0.28472 0.244212 0.926982 + outer loop + vertex 1.6402 2.0153 2.481 + vertex 1.63847 2.01854 2.48068 + vertex 1.63573 2.01586 2.48223 + endloop + endfacet + facet normal 0.279441 0.241613 0.929266 + outer loop + vertex 1.63847 2.01854 2.48068 + vertex 1.6402 2.0153 2.481 + vertex 1.64289 2.018 2.47949 + endloop + endfacet + facet normal 0.293924 0.242446 0.924569 + outer loop + vertex 1.63535 2.0205 2.48113 + vertex 1.63362 2.0238 2.48082 + vertex 1.63077 2.02119 2.48241 + endloop + endfacet + facet normal 0.292832 0.243653 0.924599 + outer loop + vertex 1.6305 2.02576 2.48129 + vertex 1.63077 2.02119 2.48241 + vertex 1.63362 2.0238 2.48082 + endloop + endfacet + facet normal 0.292629 0.243292 0.924758 + outer loop + vertex 1.63362 2.0238 2.48082 + vertex 1.63327 2.02842 2.47971 + vertex 1.6305 2.02576 2.48129 + endloop + endfacet + facet normal 0.289975 0.246108 0.924849 + outer loop + vertex 1.62876 2.02903 2.48096 + vertex 1.6305 2.02576 2.48129 + vertex 1.63327 2.02842 2.47971 + endloop + endfacet + facet normal 0.273177 0.243936 0.930521 + outer loop + vertex 1.6305 2.02576 2.48129 + vertex 1.626 2.02618 2.4825 + vertex 1.63077 2.02119 2.48241 + endloop + endfacet + facet normal 0.287051 0.239131 0.927587 + outer loop + vertex 1.63362 2.0238 2.48082 + vertex 1.63535 2.0205 2.48113 + vertex 1.63821 2.02313 2.47957 + endloop + endfacet + facet normal 0.293328 0.23704 0.926159 + outer loop + vertex 1.63314 2.01303 2.48377 + vertex 1.63573 2.01586 2.48223 + vertex 1.63116 2.01639 2.48354 + endloop + endfacet + facet normal 0.290222 0.239997 0.926376 + outer loop + vertex 1.63618 2.01121 2.48329 + vertex 1.63573 2.01586 2.48223 + vertex 1.63314 2.01303 2.48377 + endloop + endfacet + facet normal 0.282386 0.239801 0.928845 + outer loop + vertex 1.63573 2.01586 2.48223 + vertex 1.63618 2.01121 2.48329 + vertex 1.64055 2.0108 2.48207 + endloop + endfacet + facet normal 0.284609 0.241955 0.927607 + outer loop + vertex 1.6402 2.0153 2.481 + vertex 1.63573 2.01586 2.48223 + vertex 1.64055 2.0108 2.48207 + endloop + endfacet + facet normal 0.279581 0.241929 0.929142 + outer loop + vertex 1.6402 2.0153 2.481 + vertex 1.64055 2.0108 2.48207 + vertex 1.64326 2.01347 2.48056 + endloop + endfacet + facet normal 0.279422 0.241633 0.929267 + outer loop + vertex 1.64326 2.01347 2.48056 + vertex 1.64289 2.018 2.47949 + vertex 1.6402 2.0153 2.481 + endloop + endfacet + facet normal 0.27996 0.241538 0.92913 + outer loop + vertex 1.64488 2.01039 2.48087 + vertex 1.64326 2.01347 2.48056 + vertex 1.64055 2.0108 2.48207 + endloop + endfacet + facet normal 0.279936 0.240441 0.929421 + outer loop + vertex 1.64488 2.01039 2.48087 + vertex 1.64055 2.0108 2.48207 + vertex 1.64487 2.00633 2.48193 + endloop + endfacet + facet normal 0.280796 0.240378 0.929178 + outer loop + vertex 1.64488 2.01039 2.48087 + vertex 1.64487 2.00633 2.48193 + vertex 1.6478 2.00853 2.48047 + endloop + endfacet + facet normal 0.281376 0.241383 0.928742 + outer loop + vertex 1.6478 2.00853 2.48047 + vertex 1.64755 2.01304 2.47937 + vertex 1.64488 2.01039 2.48087 + endloop + endfacet + facet normal 0.28119 0.239864 0.929192 + outer loop + vertex 1.64952 2.00465 2.48095 + vertex 1.6478 2.00853 2.48047 + vertex 1.64487 2.00633 2.48193 + endloop + endfacet + facet normal 0.280302 0.240802 0.929217 + outer loop + vertex 1.64055 2.0108 2.48207 + vertex 1.64096 2.00624 2.48313 + vertex 1.64487 2.00633 2.48193 + endloop + endfacet + facet normal 0.28048 0.238889 0.929657 + outer loop + vertex 1.64289 2.00298 2.48338 + vertex 1.64487 2.00633 2.48193 + vertex 1.64096 2.00624 2.48313 + endloop + endfacet + facet normal 0.281172 0.239277 0.929349 + outer loop + vertex 1.64289 2.00298 2.48338 + vertex 1.64096 2.00624 2.48313 + vertex 1.6383 2.00336 2.48467 + endloop + endfacet + facet normal 0.281125 0.234666 0.930538 + outer loop + vertex 1.6383 2.00336 2.48467 + vertex 1.64301 1.99825 2.48454 + vertex 1.64289 2.00298 2.48338 + endloop + endfacet + facet normal 0.279967 0.23472 0.930873 + outer loop + vertex 1.64301 1.99825 2.48454 + vertex 1.6471 2.00094 2.48263 + vertex 1.64289 2.00298 2.48338 + endloop + endfacet + facet normal 0.281451 0.238258 0.929526 + outer loop + vertex 1.6471 2.00094 2.48263 + vertex 1.64487 2.00633 2.48193 + vertex 1.64289 2.00298 2.48338 + endloop + endfacet + facet normal 0.282056 0.235536 0.930036 + outer loop + vertex 1.63856 1.99873 2.48577 + vertex 1.64301 1.99825 2.48454 + vertex 1.6383 2.00336 2.48467 + endloop + endfacet + facet normal 0.284705 0.235495 0.929239 + outer loop + vertex 1.63856 1.99873 2.48577 + vertex 1.6383 2.00336 2.48467 + vertex 1.63547 2.00064 2.48623 + endloop + endfacet + facet normal 0.282724 0.231939 0.930737 + outer loop + vertex 1.63547 2.00064 2.48623 + vertex 1.63569 1.99604 2.48731 + vertex 1.63856 1.99873 2.48577 + endloop + endfacet + facet normal 0.28284 0.231814 0.930733 + outer loop + vertex 1.64006 1.9956 2.48609 + vertex 1.63856 1.99873 2.48577 + vertex 1.63569 1.99604 2.48731 + endloop + endfacet + facet normal 0.2827 0.226952 0.931973 + outer loop + vertex 1.64006 1.9956 2.48609 + vertex 1.63569 1.99604 2.48731 + vertex 1.63994 1.99151 2.48712 + endloop + endfacet + facet normal 0.28157 0.227066 0.932287 + outer loop + vertex 1.64006 1.9956 2.48609 + vertex 1.63994 1.99151 2.48712 + vertex 1.64293 1.99373 2.48568 + endloop + endfacet + facet normal 0.283251 0.229893 0.931084 + outer loop + vertex 1.64293 1.99373 2.48568 + vertex 1.64301 1.99825 2.48454 + vertex 1.64006 1.9956 2.48609 + endloop + endfacet + facet normal 0.281895 0.230015 0.931466 + outer loop + vertex 1.64293 1.99373 2.48568 + vertex 1.64699 1.99358 2.48449 + vertex 1.64301 1.99825 2.48454 + endloop + endfacet + facet normal 0.279584 0.228036 0.932648 + outer loop + vertex 1.64301 1.99825 2.48454 + vertex 1.64699 1.99358 2.48449 + vertex 1.64704 1.99727 2.48357 + endloop + endfacet + facet normal 0.280571 0.233831 0.930915 + outer loop + vertex 1.64704 1.99727 2.48357 + vertex 1.6471 2.00094 2.48263 + vertex 1.64301 1.99825 2.48454 + endloop + endfacet + facet normal 0.281579 0.22787 0.932088 + outer loop + vertex 1.64699 1.99358 2.48449 + vertex 1.65108 1.99627 2.4826 + vertex 1.64704 1.99727 2.48357 + endloop + endfacet + facet normal 0.282257 0.226866 0.932128 + outer loop + vertex 1.65121 1.99147 2.48372 + vertex 1.65108 1.99627 2.4826 + vertex 1.64699 1.99358 2.48449 + endloop + endfacet + facet normal 0.281309 0.224663 0.932948 + outer loop + vertex 1.64922 1.9881 2.48514 + vertex 1.65121 1.99147 2.48372 + vertex 1.64699 1.99358 2.48449 + endloop + endfacet + facet normal 0.282551 0.225113 0.932464 + outer loop + vertex 1.64922 1.9881 2.48514 + vertex 1.64699 1.99358 2.48449 + vertex 1.64457 1.98982 2.48613 + endloop + endfacet + facet normal 0.282537 0.223864 0.932769 + outer loop + vertex 1.65316 1.98814 2.48393 + vertex 1.65121 1.99147 2.48372 + vertex 1.64922 1.9881 2.48514 + endloop + endfacet + facet normal 0.282626 0.222704 0.93302 + outer loop + vertex 1.64922 1.9881 2.48514 + vertex 1.65353 1.98352 2.48492 + vertex 1.65316 1.98814 2.48393 + endloop + endfacet + facet normal 0.285228 0.222742 0.932218 + outer loop + vertex 1.65353 1.98352 2.48492 + vertex 1.65619 1.98637 2.48343 + vertex 1.65316 1.98814 2.48393 + endloop + endfacet + facet normal 0.285581 0.223423 0.931947 + outer loop + vertex 1.65619 1.98637 2.48343 + vertex 1.65581 1.99108 2.48242 + vertex 1.65316 1.98814 2.48393 + endloop + endfacet + facet normal 0.287683 0.223452 0.931294 + outer loop + vertex 1.65581 1.99108 2.48242 + vertex 1.65619 1.98637 2.48343 + vertex 1.66056 1.98598 2.48217 + endloop + endfacet + facet normal 0.286664 0.222478 0.931841 + outer loop + vertex 1.66031 1.99057 2.48115 + vertex 1.65581 1.99108 2.48242 + vertex 1.66056 1.98598 2.48217 + endloop + endfacet + facet normal 0.29031 0.222424 0.930724 + outer loop + vertex 1.66031 1.99057 2.48115 + vertex 1.66056 1.98598 2.48217 + vertex 1.66335 1.98867 2.48066 + endloop + endfacet + facet normal 0.291488 0.224538 0.929848 + outer loop + vertex 1.66335 1.98867 2.48066 + vertex 1.66321 1.99325 2.4796 + vertex 1.66031 1.99057 2.48115 + endloop + endfacet + facet normal 0.29059 0.224574 0.930121 + outer loop + vertex 1.66335 1.98867 2.48066 + vertex 1.66764 1.98816 2.47944 + vertex 1.66321 1.99325 2.4796 + endloop + endfacet + facet normal 0.291078 0.225007 0.929863 + outer loop + vertex 1.66321 1.99325 2.4796 + vertex 1.66764 1.98816 2.47944 + vertex 1.66729 1.99218 2.47858 + endloop + endfacet + facet normal 0.291472 0.22712 0.929226 + outer loop + vertex 1.66729 1.99218 2.47858 + vertex 1.66714 1.99599 2.4777 + vertex 1.66321 1.99325 2.4796 + endloop + endfacet + facet normal 0.290328 0.227157 0.929575 + outer loop + vertex 1.66714 1.99599 2.4777 + vertex 1.66729 1.99218 2.47858 + vertex 1.67123 1.99131 2.47756 + endloop + endfacet + facet normal 0.290906 0.227671 0.929268 + outer loop + vertex 1.67116 1.9958 2.47648 + vertex 1.66714 1.99599 2.4777 + vertex 1.67123 1.99131 2.47756 + endloop + endfacet + facet normal 0.288425 0.22781 0.930007 + outer loop + vertex 1.67116 1.9958 2.47648 + vertex 1.67123 1.99131 2.47756 + vertex 1.67404 1.99388 2.47606 + endloop + endfacet + facet normal 0.289014 0.22879 0.929584 + outer loop + vertex 1.67404 1.99388 2.47606 + vertex 1.67411 1.99797 2.47503 + vertex 1.67116 1.9958 2.47648 + endloop + endfacet + facet normal 0.288623 0.229317 0.929576 + outer loop + vertex 1.67116 1.9958 2.47648 + vertex 1.67411 1.99797 2.47503 + vertex 1.66946 1.99973 2.47604 + endloop + endfacet + facet normal 0.290097 0.234182 0.927902 + outer loop + vertex 1.67411 1.99797 2.47503 + vertex 1.67176 2.00348 2.47438 + vertex 1.66946 1.99973 2.47604 + endloop + endfacet + facet normal 0.289525 0.234568 0.927983 + outer loop + vertex 1.66775 2.00365 2.47558 + vertex 1.66946 1.99973 2.47604 + vertex 1.67176 2.00348 2.47438 + endloop + endfacet + facet normal 0.285323 0.232372 0.929835 + outer loop + vertex 1.67411 1.99797 2.47503 + vertex 1.67605 2.00134 2.47359 + vertex 1.67176 2.00348 2.47438 + endloop + endfacet + facet normal 0.286906 0.236057 0.928419 + outer loop + vertex 1.67605 2.00134 2.47359 + vertex 1.67569 2.00621 2.47247 + vertex 1.67176 2.00348 2.47438 + endloop + endfacet + facet normal 0.285768 0.237655 0.928362 + outer loop + vertex 1.67176 2.00348 2.47438 + vertex 1.67569 2.00621 2.47247 + vertex 1.67157 2.00728 2.47346 + endloop + endfacet + facet normal 0.287189 0.237623 0.927932 + outer loop + vertex 1.66764 2.00812 2.47446 + vertex 1.67176 2.00348 2.47438 + vertex 1.67157 2.00728 2.47346 + endloop + endfacet + facet normal 0.2875 0.239914 0.927246 + outer loop + vertex 1.67157 2.00728 2.47346 + vertex 1.6712 2.01126 2.47255 + vertex 1.66764 2.00812 2.47446 + endloop + endfacet + facet normal 0.287324 0.240115 0.927249 + outer loop + vertex 1.66764 2.00812 2.47446 + vertex 1.6712 2.01126 2.47255 + vertex 1.66727 2.01209 2.47355 + endloop + endfacet + facet normal 0.287129 0.238675 0.927681 + outer loop + vertex 1.6671 2.01588 2.47263 + vertex 1.66727 2.01209 2.47355 + vertex 1.6712 2.01126 2.47255 + endloop + endfacet + facet normal 0.288189 0.239626 0.927106 + outer loop + vertex 1.67112 2.01573 2.47142 + vertex 1.6671 2.01588 2.47263 + vertex 1.6712 2.01126 2.47255 + endloop + endfacet + facet normal 0.287549 0.239663 0.927296 + outer loop + vertex 1.67112 2.01573 2.47142 + vertex 1.6712 2.01126 2.47255 + vertex 1.67401 2.01384 2.47101 + endloop + endfacet + facet normal 0.28793 0.240305 0.927011 + outer loop + vertex 1.67401 2.01384 2.47101 + vertex 1.67409 2.01789 2.46993 + vertex 1.67112 2.01573 2.47142 + endloop + endfacet + facet normal 0.288884 0.239019 0.927047 + outer loop + vertex 1.67112 2.01573 2.47142 + vertex 1.67409 2.01789 2.46993 + vertex 1.66944 2.01962 2.47094 + endloop + endfacet + facet normal 0.289613 0.24147 0.926184 + outer loop + vertex 1.67409 2.01789 2.46993 + vertex 1.67176 2.02335 2.46924 + vertex 1.66944 2.01962 2.47094 + endloop + endfacet + facet normal 0.289091 0.241275 0.926398 + outer loop + vertex 1.67409 2.01789 2.46993 + vertex 1.67605 2.0212 2.46846 + vertex 1.67176 2.02335 2.46924 + endloop + endfacet + facet normal 0.29023 0.243933 0.925345 + outer loop + vertex 1.67605 2.0212 2.46846 + vertex 1.67563 2.02604 2.46731 + vertex 1.67176 2.02335 2.46924 + endloop + endfacet + facet normal 0.289869 0.244439 0.925325 + outer loop + vertex 1.67176 2.02335 2.46924 + vertex 1.67563 2.02604 2.46731 + vertex 1.67153 2.02714 2.46831 + endloop + endfacet + facet normal 0.2888 0.244455 0.925655 + outer loop + vertex 1.66756 2.028 2.46932 + vertex 1.67176 2.02335 2.46924 + vertex 1.67153 2.02714 2.46831 + endloop + endfacet + facet normal 0.289543 0.249877 0.923973 + outer loop + vertex 1.67153 2.02714 2.46831 + vertex 1.67093 2.03118 2.4674 + vertex 1.66756 2.028 2.46932 + endloop + endfacet + facet normal 0.290912 0.249976 0.923516 + outer loop + vertex 1.67093 2.03118 2.4674 + vertex 1.67153 2.02714 2.46831 + vertex 1.67563 2.02604 2.46731 + endloop + endfacet + facet normal 0.288051 0.247332 0.925123 + outer loop + vertex 1.67535 2.03057 2.46619 + vertex 1.67093 2.03118 2.4674 + vertex 1.67563 2.02604 2.46731 + endloop + endfacet + facet normal 0.287503 0.24734 0.925292 + outer loop + vertex 1.67535 2.03057 2.46619 + vertex 1.67563 2.02604 2.46731 + vertex 1.67842 2.02866 2.46575 + endloop + endfacet + facet normal 0.28891 0.249858 0.924176 + outer loop + vertex 1.67842 2.02866 2.46575 + vertex 1.67814 2.03317 2.46461 + vertex 1.67535 2.03057 2.46619 + endloop + endfacet + facet normal 0.287805 0.251054 0.924197 + outer loop + vertex 1.67362 2.03378 2.46586 + vertex 1.67535 2.03057 2.46619 + vertex 1.67814 2.03317 2.46461 + endloop + endfacet + facet normal 0.288045 0.255551 0.922889 + outer loop + vertex 1.67362 2.03378 2.46586 + vertex 1.67814 2.03317 2.46461 + vertex 1.67318 2.03834 2.46473 + endloop + endfacet + facet normal 0.288169 0.255553 0.92285 + outer loop + vertex 1.67362 2.03378 2.46586 + vertex 1.67318 2.03834 2.46473 + vertex 1.67051 2.03567 2.46631 + endloop + endfacet + facet normal 0.286738 0.25292 0.92402 + outer loop + vertex 1.67051 2.03567 2.46631 + vertex 1.67093 2.03118 2.4674 + vertex 1.67362 2.03378 2.46586 + endloop + endfacet + facet normal 0.285909 0.252905 0.924281 + outer loop + vertex 1.67051 2.03567 2.46631 + vertex 1.66606 2.03626 2.46752 + vertex 1.67093 2.03118 2.4674 + endloop + endfacet + facet normal 0.28888 0.255798 0.922559 + outer loop + vertex 1.66606 2.03626 2.46752 + vertex 1.66691 2.03208 2.46841 + vertex 1.67093 2.03118 2.4674 + endloop + endfacet + facet normal 0.288229 0.251285 0.924002 + outer loop + vertex 1.66756 2.028 2.46932 + vertex 1.67093 2.03118 2.4674 + vertex 1.66691 2.03208 2.46841 + endloop + endfacet + facet normal 0.285692 0.251066 0.924849 + outer loop + vertex 1.66284 2.03297 2.46943 + vertex 1.66756 2.028 2.46932 + vertex 1.66691 2.03208 2.46841 + endloop + endfacet + facet normal 0.288896 0.254145 0.923011 + outer loop + vertex 1.6633 2.02847 2.47053 + vertex 1.66756 2.028 2.46932 + vertex 1.66284 2.03297 2.46943 + endloop + endfacet + facet normal 0.28679 0.254095 0.923682 + outer loop + vertex 1.6633 2.02847 2.47053 + vertex 1.66284 2.03297 2.46943 + vertex 1.66024 2.0303 2.47097 + endloop + endfacet + facet normal 0.283858 0.248614 0.926075 + outer loop + vertex 1.66024 2.0303 2.47097 + vertex 1.66053 2.02583 2.47208 + vertex 1.6633 2.02847 2.47053 + endloop + endfacet + facet normal 0.285418 0.246953 0.92604 + outer loop + vertex 1.66487 2.0254 2.47086 + vertex 1.6633 2.02847 2.47053 + vertex 1.66053 2.02583 2.47208 + endloop + endfacet + facet normal 0.285286 0.241234 0.927587 + outer loop + vertex 1.66487 2.0254 2.47086 + vertex 1.66053 2.02583 2.47208 + vertex 1.6648 2.02134 2.47194 + endloop + endfacet + facet normal 0.287912 0.240991 0.926839 + outer loop + vertex 1.66487 2.0254 2.47086 + vertex 1.6648 2.02134 2.47194 + vertex 1.66774 2.02353 2.47045 + endloop + endfacet + facet normal 0.290941 0.246142 0.924537 + outer loop + vertex 1.66774 2.02353 2.47045 + vertex 1.66756 2.028 2.46932 + vertex 1.66487 2.0254 2.47086 + endloop + endfacet + facet normal 0.290658 0.246152 0.924623 + outer loop + vertex 1.66774 2.02353 2.47045 + vertex 1.67176 2.02335 2.46924 + vertex 1.66756 2.028 2.46932 + endloop + endfacet + facet normal 0.290842 0.240631 0.926017 + outer loop + vertex 1.66774 2.02353 2.47045 + vertex 1.66944 2.01962 2.47094 + vertex 1.67176 2.02335 2.46924 + endloop + endfacet + facet normal 0.288782 0.239839 0.926867 + outer loop + vertex 1.66944 2.01962 2.47094 + vertex 1.66774 2.02353 2.47045 + vertex 1.6648 2.02134 2.47194 + endloop + endfacet + facet normal 0.286527 0.242438 0.926891 + outer loop + vertex 1.66053 2.02583 2.47208 + vertex 1.66086 2.02129 2.47317 + vertex 1.6648 2.02134 2.47194 + endloop + endfacet + facet normal 0.286859 0.238581 0.927788 + outer loop + vertex 1.66283 2.01798 2.47341 + vertex 1.6648 2.02134 2.47194 + vertex 1.66086 2.02129 2.47317 + endloop + endfacet + facet normal 0.285547 0.237841 0.928383 + outer loop + vertex 1.66283 2.01798 2.47341 + vertex 1.66086 2.02129 2.47317 + vertex 1.65822 2.01839 2.47472 + endloop + endfacet + facet normal 0.285548 0.23793 0.92836 + outer loop + vertex 1.65822 2.01839 2.47472 + vertex 1.66318 2.01313 2.47455 + vertex 1.66283 2.01798 2.47341 + endloop + endfacet + facet normal 0.287255 0.237927 0.927834 + outer loop + vertex 1.66318 2.01313 2.47455 + vertex 1.6671 2.01588 2.47263 + vertex 1.66283 2.01798 2.47341 + endloop + endfacet + facet normal 0.284783 0.238563 0.928432 + outer loop + vertex 1.65822 2.01839 2.47472 + vertex 1.66086 2.02129 2.47317 + vertex 1.65784 2.02302 2.47365 + endloop + endfacet + facet normal 0.287386 0.238239 0.927713 + outer loop + vertex 1.6671 2.01588 2.47263 + vertex 1.6648 2.02134 2.47194 + vertex 1.66283 2.01798 2.47341 + endloop + endfacet + facet normal 0.288426 0.238625 0.927291 + outer loop + vertex 1.6648 2.02134 2.47194 + vertex 1.6671 2.01588 2.47263 + vertex 1.66944 2.01962 2.47094 + endloop + endfacet + facet normal 0.286757 0.242438 0.92682 + outer loop + vertex 1.66086 2.02129 2.47317 + vertex 1.66053 2.02583 2.47208 + vertex 1.65784 2.02302 2.47365 + endloop + endfacet + facet normal 0.285679 0.243498 0.926874 + outer loop + vertex 1.65784 2.02302 2.47365 + vertex 1.66053 2.02583 2.47208 + vertex 1.65614 2.02621 2.47333 + endloop + endfacet + facet normal 0.284232 0.242791 0.927504 + outer loop + vertex 1.65784 2.02302 2.47365 + vertex 1.65614 2.02621 2.47333 + vertex 1.65344 2.02343 2.47489 + endloop + endfacet + facet normal 0.282908 0.244109 0.927564 + outer loop + vertex 1.65344 2.02343 2.47489 + vertex 1.65614 2.02621 2.47333 + vertex 1.65312 2.02795 2.4738 + endloop + endfacet + facet normal 0.28295 0.244109 0.927551 + outer loop + vertex 1.64914 2.02793 2.47502 + vertex 1.65344 2.02343 2.47489 + vertex 1.65312 2.02795 2.4738 + endloop + endfacet + facet normal 0.282484 0.249974 0.926129 + outer loop + vertex 1.65312 2.02795 2.4738 + vertex 1.65112 2.03124 2.47352 + vertex 1.64914 2.02793 2.47502 + endloop + endfacet + facet normal 0.284672 0.25122 0.925122 + outer loop + vertex 1.65312 2.02795 2.4738 + vertex 1.65574 2.03081 2.47222 + vertex 1.65112 2.03124 2.47352 + endloop + endfacet + facet normal 0.284724 0.255282 0.923993 + outer loop + vertex 1.65068 2.03604 2.47233 + vertex 1.65112 2.03124 2.47352 + vertex 1.65574 2.03081 2.47222 + endloop + endfacet + facet normal 0.28446 0.255024 0.924146 + outer loop + vertex 1.65526 2.03543 2.47109 + vertex 1.65068 2.03604 2.47233 + vertex 1.65574 2.03081 2.47222 + endloop + endfacet + facet normal 0.284078 0.255014 0.924266 + outer loop + vertex 1.65526 2.03543 2.47109 + vertex 1.65574 2.03081 2.47222 + vertex 1.65843 2.03351 2.47064 + endloop + endfacet + facet normal 0.285397 0.257451 0.923184 + outer loop + vertex 1.65843 2.03351 2.47064 + vertex 1.65785 2.03809 2.46955 + vertex 1.65526 2.03543 2.47109 + endloop + endfacet + facet normal 0.285472 0.257376 0.923181 + outer loop + vertex 1.65342 2.03867 2.47076 + vertex 1.65526 2.03543 2.47109 + vertex 1.65785 2.03809 2.46955 + endloop + endfacet + facet normal 0.285477 0.257477 0.923151 + outer loop + vertex 1.65342 2.03867 2.47076 + vertex 1.65785 2.03809 2.46955 + vertex 1.65294 2.04316 2.46965 + endloop + endfacet + facet normal 0.285849 0.257841 0.922935 + outer loop + vertex 1.65294 2.04316 2.46965 + vertex 1.65785 2.03809 2.46955 + vertex 1.65697 2.04227 2.46865 + endloop + endfacet + facet normal 0.285623 0.25622 0.923456 + outer loop + vertex 1.65697 2.04227 2.46865 + vertex 1.65629 2.04635 2.46773 + vertex 1.65294 2.04316 2.46965 + endloop + endfacet + facet normal 0.284645 0.256131 0.923782 + outer loop + vertex 1.65629 2.04635 2.46773 + vertex 1.65697 2.04227 2.46865 + vertex 1.66106 2.04137 2.46764 + endloop + endfacet + facet normal 0.285238 0.256706 0.92344 + outer loop + vertex 1.66061 2.04585 2.46653 + vertex 1.65629 2.04635 2.46773 + vertex 1.66106 2.04137 2.46764 + endloop + endfacet + facet normal 0.284856 0.256697 0.92356 + outer loop + vertex 1.66061 2.04585 2.46653 + vertex 1.66106 2.04137 2.46764 + vertex 1.66371 2.04399 2.46609 + endloop + endfacet + facet normal 0.284343 0.255743 0.923983 + outer loop + vertex 1.66371 2.04399 2.46609 + vertex 1.66342 2.04843 2.46496 + vertex 1.66061 2.04585 2.46653 + endloop + endfacet + facet normal 0.284888 0.255145 0.92398 + outer loop + vertex 1.65902 2.04892 2.46618 + vertex 1.66061 2.04585 2.46653 + vertex 1.66342 2.04843 2.46496 + endloop + endfacet + facet normal 0.285459 0.255728 0.923643 + outer loop + vertex 1.66371 2.04399 2.46609 + vertex 1.66826 2.04341 2.46485 + vertex 1.66342 2.04843 2.46496 + endloop + endfacet + facet normal 0.287011 0.257242 0.922741 + outer loop + vertex 1.66342 2.04843 2.46496 + vertex 1.66826 2.04341 2.46485 + vertex 1.66788 2.04795 2.4637 + endloop + endfacet + facet normal 0.286976 0.255946 0.923112 + outer loop + vertex 1.66788 2.04795 2.4637 + vertex 1.66612 2.05117 2.46336 + vertex 1.66342 2.04843 2.46496 + endloop + endfacet + facet normal 0.287478 0.255443 0.923095 + outer loop + vertex 1.66342 2.04843 2.46496 + vertex 1.66612 2.05117 2.46336 + vertex 1.66306 2.05294 2.46382 + endloop + endfacet + facet normal 0.285335 0.255436 0.923762 + outer loop + vertex 1.65909 2.05292 2.46505 + vertex 1.66342 2.04843 2.46496 + vertex 1.66306 2.05294 2.46382 + endloop + endfacet + facet normal 0.285189 0.257199 0.923318 + outer loop + vertex 1.66306 2.05294 2.46382 + vertex 1.66105 2.05622 2.46353 + vertex 1.65909 2.05292 2.46505 + endloop + endfacet + facet normal 0.287523 0.258533 0.922221 + outer loop + vertex 1.66306 2.05294 2.46382 + vertex 1.66565 2.05578 2.46222 + vertex 1.66105 2.05622 2.46353 + endloop + endfacet + facet normal 0.287556 0.261045 0.921502 + outer loop + vertex 1.66063 2.06099 2.46231 + vertex 1.66105 2.05622 2.46353 + vertex 1.66565 2.05578 2.46222 + endloop + endfacet + facet normal 0.283665 0.257246 0.923774 + outer loop + vertex 1.66519 2.0604 2.46107 + vertex 1.66063 2.06099 2.46231 + vertex 1.66565 2.05578 2.46222 + endloop + endfacet + facet normal 0.289863 0.25738 0.921811 + outer loop + vertex 1.66519 2.0604 2.46107 + vertex 1.66565 2.05578 2.46222 + vertex 1.66832 2.05848 2.46062 + endloop + endfacet + facet normal 0.290255 0.258095 0.921487 + outer loop + vertex 1.66832 2.05848 2.46062 + vertex 1.66784 2.06302 2.4595 + vertex 1.66519 2.0604 2.46107 + endloop + endfacet + facet normal 0.28821 0.260196 0.921538 + outer loop + vertex 1.66341 2.0636 2.46072 + vertex 1.66519 2.0604 2.46107 + vertex 1.66784 2.06302 2.4595 + endloop + endfacet + facet normal 0.288363 0.263274 0.920616 + outer loop + vertex 1.66341 2.0636 2.46072 + vertex 1.66784 2.06302 2.4595 + vertex 1.66297 2.06806 2.45959 + endloop + endfacet + facet normal 0.281298 0.263145 0.922836 + outer loop + vertex 1.66341 2.0636 2.46072 + vertex 1.66297 2.06806 2.45959 + vertex 1.66032 2.06545 2.46114 + endloop + endfacet + facet normal 0.280386 0.261452 0.923595 + outer loop + vertex 1.66032 2.06545 2.46114 + vertex 1.66063 2.06099 2.46231 + vertex 1.66341 2.0636 2.46072 + endloop + endfacet + facet normal 0.274325 0.261509 0.925396 + outer loop + vertex 1.66032 2.06545 2.46114 + vertex 1.65588 2.06599 2.4623 + vertex 1.66063 2.06099 2.46231 + endloop + endfacet + facet normal 0.281929 0.268699 0.921041 + outer loop + vertex 1.65588 2.06599 2.4623 + vertex 1.65649 2.06202 2.46327 + vertex 1.66063 2.06099 2.46231 + endloop + endfacet + facet normal 0.28123 0.264619 0.922435 + outer loop + vertex 1.65673 2.0583 2.46427 + vertex 1.66063 2.06099 2.46231 + vertex 1.65649 2.06202 2.46327 + endloop + endfacet + facet normal 0.278525 0.268451 0.922149 + outer loop + vertex 1.65649 2.06202 2.46327 + vertex 1.65588 2.06599 2.4623 + vertex 1.65249 2.06282 2.46425 + endloop + endfacet + facet normal 0.27475 0.272461 0.922105 + outer loop + vertex 1.65249 2.06282 2.46425 + vertex 1.65588 2.06599 2.4623 + vertex 1.65183 2.06684 2.46326 + endloop + endfacet + facet normal 0.280084 0.272911 0.920365 + outer loop + vertex 1.64774 2.06771 2.46424 + vertex 1.65249 2.06282 2.46425 + vertex 1.65183 2.06684 2.46326 + endloop + endfacet + facet normal 0.27996 0.271981 0.920678 + outer loop + vertex 1.65183 2.06684 2.46326 + vertex 1.65099 2.07095 2.4623 + vertex 1.64774 2.06771 2.46424 + endloop + endfacet + facet normal 0.280789 0.271145 0.920672 + outer loop + vertex 1.64774 2.06771 2.46424 + vertex 1.65099 2.07095 2.4623 + vertex 1.64688 2.07189 2.46328 + endloop + endfacet + facet normal 0.282962 0.258005 0.923778 + outer loop + vertex 1.66297 2.06806 2.45959 + vertex 1.66784 2.06302 2.4595 + vertex 1.66704 2.06719 2.45858 + endloop + endfacet + facet normal 0.285067 0.273928 0.918531 + outer loop + vertex 1.66704 2.06719 2.45858 + vertex 1.66617 2.07127 2.45763 + vertex 1.66297 2.06806 2.45959 + endloop + endfacet + facet normal 0.297848 0.275603 0.913964 + outer loop + vertex 1.66617 2.07127 2.45763 + vertex 1.66704 2.06719 2.45858 + vertex 1.67109 2.06626 2.45754 + endloop + endfacet + facet normal 0.295549 0.259445 0.919423 + outer loop + vertex 1.66784 2.06302 2.4595 + vertex 1.67109 2.06626 2.45754 + vertex 1.66704 2.06719 2.45858 + endloop + endfacet + facet normal 0.292951 0.262093 0.919504 + outer loop + vertex 1.67189 2.06209 2.45848 + vertex 1.67109 2.06626 2.45754 + vertex 1.66784 2.06302 2.4595 + endloop + endfacet + facet normal 0.292379 0.258166 0.920796 + outer loop + vertex 1.66784 2.06302 2.4595 + vertex 1.67274 2.05787 2.45939 + vertex 1.67189 2.06209 2.45848 + endloop + endfacet + facet normal 0.292362 0.25815 0.920806 + outer loop + vertex 1.66832 2.05848 2.46062 + vertex 1.67274 2.05787 2.45939 + vertex 1.66784 2.06302 2.4595 + endloop + endfacet + facet normal 0.292333 0.257617 0.920964 + outer loop + vertex 1.66832 2.05848 2.46062 + vertex 1.67013 2.05523 2.46096 + vertex 1.67274 2.05787 2.45939 + endloop + endfacet + facet normal 0.291579 0.258374 0.920991 + outer loop + vertex 1.67326 2.05331 2.4605 + vertex 1.67274 2.05787 2.45939 + vertex 1.67013 2.05523 2.46096 + endloop + endfacet + facet normal 0.29157 0.258357 0.920999 + outer loop + vertex 1.67013 2.05523 2.46096 + vertex 1.67059 2.05065 2.4621 + vertex 1.67326 2.05331 2.4605 + endloop + endfacet + facet normal 0.290605 0.258338 0.921309 + outer loop + vertex 1.67013 2.05523 2.46096 + vertex 1.66565 2.05578 2.46222 + vertex 1.67059 2.05065 2.4621 + endloop + endfacet + facet normal 0.289832 0.257584 0.921764 + outer loop + vertex 1.66565 2.05578 2.46222 + vertex 1.66612 2.05117 2.46336 + vertex 1.67059 2.05065 2.4621 + endloop + endfacet + facet normal 0.290536 0.256701 0.921788 + outer loop + vertex 1.67013 2.05523 2.46096 + vertex 1.66832 2.05848 2.46062 + vertex 1.66565 2.05578 2.46222 + endloop + endfacet + facet normal 0.283698 0.257915 0.923577 + outer loop + vertex 1.66519 2.0604 2.46107 + vertex 1.66341 2.0636 2.46072 + vertex 1.66063 2.06099 2.46231 + endloop + endfacet + facet normal 0.283834 0.261014 0.922665 + outer loop + vertex 1.66105 2.05622 2.46353 + vertex 1.66063 2.06099 2.46231 + vertex 1.65673 2.0583 2.46427 + endloop + endfacet + facet normal 0.288561 0.257556 0.92217 + outer loop + vertex 1.66612 2.05117 2.46336 + vertex 1.66565 2.05578 2.46222 + vertex 1.66306 2.05294 2.46382 + endloop + endfacet + facet normal 0.289824 0.257364 0.921827 + outer loop + vertex 1.66788 2.04795 2.4637 + vertex 1.67059 2.05065 2.4621 + vertex 1.66612 2.05117 2.46336 + endloop + endfacet + facet normal 0.288774 0.258436 0.921857 + outer loop + vertex 1.671 2.04609 2.46325 + vertex 1.67059 2.05065 2.4621 + vertex 1.66788 2.04795 2.4637 + endloop + endfacet + facet normal 0.287944 0.258428 0.922119 + outer loop + vertex 1.67059 2.05065 2.4621 + vertex 1.671 2.04609 2.46325 + vertex 1.67538 2.04567 2.462 + endloop + endfacet + facet normal 0.290264 0.260685 0.920755 + outer loop + vertex 1.67506 2.0501 2.46085 + vertex 1.67059 2.05065 2.4621 + vertex 1.67538 2.04567 2.462 + endloop + endfacet + facet normal 0.290225 0.259733 0.921036 + outer loop + vertex 1.67506 2.0501 2.46085 + vertex 1.67326 2.05331 2.4605 + vertex 1.67059 2.05065 2.4621 + endloop + endfacet + facet normal 0.288654 0.258933 0.921755 + outer loop + vertex 1.67326 2.05331 2.4605 + vertex 1.67506 2.0501 2.46085 + vertex 1.67766 2.05276 2.45928 + endloop + endfacet + facet normal 0.288625 0.258266 0.921951 + outer loop + vertex 1.67326 2.05331 2.4605 + vertex 1.67766 2.05276 2.45928 + vertex 1.67274 2.05787 2.45939 + endloop + endfacet + facet normal 0.291981 0.261534 0.919971 + outer loop + vertex 1.67274 2.05787 2.45939 + vertex 1.67766 2.05276 2.45928 + vertex 1.6768 2.05694 2.45836 + endloop + endfacet + facet normal 0.291833 0.260518 0.920307 + outer loop + vertex 1.6768 2.05694 2.45836 + vertex 1.67595 2.06114 2.45745 + vertex 1.67274 2.05787 2.45939 + endloop + endfacet + facet normal 0.293977 0.258363 0.920231 + outer loop + vertex 1.67274 2.05787 2.45939 + vertex 1.67595 2.06114 2.45745 + vertex 1.67189 2.06209 2.45848 + endloop + endfacet + facet normal 0.287704 0.259998 0.921753 + outer loop + vertex 1.67595 2.06114 2.45745 + vertex 1.6768 2.05694 2.45836 + vertex 1.68087 2.05603 2.45735 + endloop + endfacet + facet normal 0.291225 0.263427 0.919671 + outer loop + vertex 1.68034 2.06054 2.45623 + vertex 1.67595 2.06114 2.45745 + vertex 1.68087 2.05603 2.45735 + endloop + endfacet + facet normal 0.287005 0.263269 0.921041 + outer loop + vertex 1.68034 2.06054 2.45623 + vertex 1.68087 2.05603 2.45735 + vertex 1.68346 2.05865 2.4558 + endloop + endfacet + facet normal 0.288204 0.265475 0.920033 + outer loop + vertex 1.68346 2.05865 2.4558 + vertex 1.68297 2.06313 2.45466 + vertex 1.68034 2.06054 2.45623 + endloop + endfacet + facet normal 0.285783 0.264496 0.92107 + outer loop + vertex 1.68529 2.05545 2.45615 + vertex 1.68346 2.05865 2.4558 + vertex 1.68087 2.05603 2.45735 + endloop + endfacet + facet normal 0.285819 0.265246 0.920843 + outer loop + vertex 1.68529 2.05545 2.45615 + vertex 1.68087 2.05603 2.45735 + vertex 1.68578 2.05099 2.45728 + endloop + endfacet + facet normal 0.28264 0.265151 0.921851 + outer loop + vertex 1.68529 2.05545 2.45615 + vertex 1.68578 2.05099 2.45728 + vertex 1.68843 2.05358 2.45572 + endloop + endfacet + facet normal 0.281764 0.263519 0.922587 + outer loop + vertex 1.68843 2.05358 2.45572 + vertex 1.68791 2.05807 2.4546 + vertex 1.68529 2.05545 2.45615 + endloop + endfacet + facet normal 0.281533 0.266293 0.921861 + outer loop + vertex 1.69024 2.0504 2.45609 + vertex 1.68843 2.05358 2.45572 + vertex 1.68578 2.05099 2.45728 + endloop + endfacet + facet normal 0.281502 0.265703 0.92204 + outer loop + vertex 1.69024 2.0504 2.45609 + vertex 1.68578 2.05099 2.45728 + vertex 1.69058 2.04594 2.45727 + endloop + endfacet + facet normal 0.277136 0.265719 0.923357 + outer loop + vertex 1.69024 2.0504 2.45609 + vertex 1.69058 2.04594 2.45727 + vertex 1.69338 2.04854 2.45568 + endloop + endfacet + facet normal 0.277373 0.266164 0.923158 + outer loop + vertex 1.69338 2.04854 2.45568 + vertex 1.69287 2.05302 2.45454 + vertex 1.69024 2.0504 2.45609 + endloop + endfacet + facet normal 0.276861 0.266015 0.923355 + outer loop + vertex 1.69519 2.04537 2.45605 + vertex 1.69338 2.04854 2.45568 + vertex 1.69058 2.04594 2.45727 + endloop + endfacet + facet normal 0.279998 0.264271 0.922909 + outer loop + vertex 1.68578 2.05099 2.45728 + vertex 1.68642 2.04699 2.45823 + vertex 1.69058 2.04594 2.45727 + endloop + endfacet + facet normal 0.279511 0.261467 0.923856 + outer loop + vertex 1.68666 2.04326 2.45921 + vertex 1.69058 2.04594 2.45727 + vertex 1.68642 2.04699 2.45823 + endloop + endfacet + facet normal 0.281326 0.261444 0.923311 + outer loop + vertex 1.6824 2.04782 2.45922 + vertex 1.68666 2.04326 2.45921 + vertex 1.68642 2.04699 2.45823 + endloop + endfacet + facet normal 0.281259 0.261382 0.923349 + outer loop + vertex 1.6826 2.04341 2.46041 + vertex 1.68666 2.04326 2.45921 + vertex 1.6824 2.04782 2.45922 + endloop + endfacet + facet normal 0.28294 0.261324 0.922851 + outer loop + vertex 1.6826 2.04341 2.46041 + vertex 1.6824 2.04782 2.45922 + vertex 1.6797 2.04524 2.46078 + endloop + endfacet + facet normal 0.283368 0.260875 0.922847 + outer loop + vertex 1.67811 2.04827 2.46041 + vertex 1.6797 2.04524 2.46078 + vertex 1.6824 2.04782 2.45922 + endloop + endfacet + facet normal 0.283362 0.260621 0.922921 + outer loop + vertex 1.67811 2.04827 2.46041 + vertex 1.6824 2.04782 2.45922 + vertex 1.67766 2.05276 2.45928 + endloop + endfacet + facet normal 0.286062 0.263237 0.921344 + outer loop + vertex 1.67766 2.05276 2.45928 + vertex 1.6824 2.04782 2.45922 + vertex 1.68172 2.05188 2.45827 + endloop + endfacet + facet normal 0.28601 0.262844 0.921472 + outer loop + vertex 1.68172 2.05188 2.45827 + vertex 1.68087 2.05603 2.45735 + vertex 1.67766 2.05276 2.45928 + endloop + endfacet + facet normal 0.283056 0.262967 0.922349 + outer loop + vertex 1.6824 2.04782 2.45922 + vertex 1.68578 2.05099 2.45728 + vertex 1.68172 2.05188 2.45827 + endloop + endfacet + facet normal 0.281385 0.25829 0.92418 + outer loop + vertex 1.6826 2.04341 2.46041 + vertex 1.68433 2.03958 2.46095 + vertex 1.68666 2.04326 2.45921 + endloop + endfacet + facet normal 0.281543 0.258182 0.924162 + outer loop + vertex 1.68905 2.03786 2.46 + vertex 1.68666 2.04326 2.45921 + vertex 1.68433 2.03958 2.46095 + endloop + endfacet + facet normal 0.280574 0.254833 0.925385 + outer loop + vertex 1.68605 2.03572 2.46149 + vertex 1.68905 2.03786 2.46 + vertex 1.68433 2.03958 2.46095 + endloop + endfacet + facet normal 0.282126 0.255439 0.924746 + outer loop + vertex 1.68433 2.03958 2.46095 + vertex 1.68201 2.03588 2.46268 + vertex 1.68605 2.03572 2.46149 + endloop + endfacet + facet normal 0.282262 0.251795 0.925704 + outer loop + vertex 1.68605 2.03572 2.46149 + vertex 1.68201 2.03588 2.46268 + vertex 1.68624 2.03125 2.46265 + endloop + endfacet + facet normal 0.28034 0.25186 0.92627 + outer loop + vertex 1.68605 2.03572 2.46149 + vertex 1.68624 2.03125 2.46265 + vertex 1.689 2.03383 2.46112 + endloop + endfacet + facet normal 0.280991 0.251159 0.926263 + outer loop + vertex 1.69059 2.03075 2.46147 + vertex 1.689 2.03383 2.46112 + vertex 1.68624 2.03125 2.46265 + endloop + endfacet + facet normal 0.28304 0.25251 0.925271 + outer loop + vertex 1.68201 2.03588 2.46268 + vertex 1.68224 2.03211 2.46364 + vertex 1.68624 2.03125 2.46265 + endloop + endfacet + facet normal 0.28258 0.249165 0.926318 + outer loop + vertex 1.68287 2.02803 2.46455 + vertex 1.68624 2.03125 2.46265 + vertex 1.68224 2.03211 2.46364 + endloop + endfacet + facet normal 0.284821 0.249343 0.925584 + outer loop + vertex 1.67814 2.03317 2.46461 + vertex 1.68287 2.02803 2.46455 + vertex 1.68224 2.03211 2.46364 + endloop + endfacet + facet normal 0.28221 0.249556 0.926326 + outer loop + vertex 1.6869 2.02715 2.46356 + vertex 1.68624 2.03125 2.46265 + vertex 1.68287 2.02803 2.46455 + endloop + endfacet + facet normal 0.282141 0.249074 0.926476 + outer loop + vertex 1.68287 2.02803 2.46455 + vertex 1.68771 2.02295 2.46444 + vertex 1.6869 2.02715 2.46356 + endloop + endfacet + facet normal 0.282069 0.249065 0.926501 + outer loop + vertex 1.68771 2.02295 2.46444 + vertex 1.69088 2.02634 2.46256 + vertex 1.6869 2.02715 2.46356 + endloop + endfacet + facet normal 0.279596 0.246616 0.927905 + outer loop + vertex 1.68333 2.02347 2.46562 + vertex 1.68771 2.02295 2.46444 + vertex 1.68287 2.02803 2.46455 + endloop + endfacet + facet normal 0.284263 0.246751 0.926449 + outer loop + vertex 1.68333 2.02347 2.46562 + vertex 1.68287 2.02803 2.46455 + vertex 1.68019 2.0254 2.46607 + endloop + endfacet + facet normal 0.283922 0.246132 0.926718 + outer loop + vertex 1.68019 2.0254 2.46607 + vertex 1.68065 2.02076 2.46716 + vertex 1.68333 2.02347 2.46562 + endloop + endfacet + facet normal 0.281198 0.248891 0.926812 + outer loop + vertex 1.68514 2.02024 2.46594 + vertex 1.68333 2.02347 2.46562 + vertex 1.68065 2.02076 2.46716 + endloop + endfacet + facet normal 0.287689 0.246228 0.92553 + outer loop + vertex 1.68019 2.0254 2.46607 + vertex 1.67563 2.02604 2.46731 + vertex 1.68065 2.02076 2.46716 + endloop + endfacet + facet normal 0.285177 0.245804 0.92642 + outer loop + vertex 1.67842 2.02866 2.46575 + vertex 1.68019 2.0254 2.46607 + vertex 1.68287 2.02803 2.46455 + endloop + endfacet + facet normal 0.28213 0.249549 0.926352 + outer loop + vertex 1.68624 2.03125 2.46265 + vertex 1.6869 2.02715 2.46356 + vertex 1.69088 2.02634 2.46256 + endloop + endfacet + facet normal 0.285387 0.252478 0.924559 + outer loop + vertex 1.68224 2.03211 2.46364 + vertex 1.68201 2.03588 2.46268 + vertex 1.67814 2.03317 2.46461 + endloop + endfacet + facet normal 0.284292 0.253985 0.924483 + outer loop + vertex 1.67814 2.03317 2.46461 + vertex 1.68201 2.03588 2.46268 + vertex 1.67774 2.03795 2.46343 + endloop + endfacet + facet normal 0.285458 0.256801 0.923345 + outer loop + vertex 1.68201 2.03588 2.46268 + vertex 1.67966 2.04125 2.46191 + vertex 1.67774 2.03795 2.46343 + endloop + endfacet + facet normal 0.285234 0.256945 0.923375 + outer loop + vertex 1.67774 2.03795 2.46343 + vertex 1.67966 2.04125 2.46191 + vertex 1.67576 2.04118 2.46314 + endloop + endfacet + facet normal 0.286477 0.257653 0.922792 + outer loop + vertex 1.67774 2.03795 2.46343 + vertex 1.67576 2.04118 2.46314 + vertex 1.67318 2.03834 2.46473 + endloop + endfacet + facet normal 0.286379 0.257745 0.922797 + outer loop + vertex 1.67318 2.03834 2.46473 + vertex 1.67576 2.04118 2.46314 + vertex 1.67274 2.0429 2.4636 + endloop + endfacet + facet normal 0.287438 0.257764 0.922462 + outer loop + vertex 1.66826 2.04341 2.46485 + vertex 1.67318 2.03834 2.46473 + vertex 1.67274 2.0429 2.4636 + endloop + endfacet + facet normal 0.287445 0.25797 0.922403 + outer loop + vertex 1.67274 2.0429 2.4636 + vertex 1.671 2.04609 2.46325 + vertex 1.66826 2.04341 2.46485 + endloop + endfacet + facet normal 0.287941 0.258217 0.922179 + outer loop + vertex 1.67274 2.0429 2.4636 + vertex 1.67538 2.04567 2.462 + vertex 1.671 2.04609 2.46325 + endloop + endfacet + facet normal 0.287324 0.257651 0.92253 + outer loop + vertex 1.6687 2.03888 2.46598 + vertex 1.67318 2.03834 2.46473 + vertex 1.66826 2.04341 2.46485 + endloop + endfacet + facet normal 0.285452 0.257615 0.92312 + outer loop + vertex 1.6687 2.03888 2.46598 + vertex 1.66826 2.04341 2.46485 + vertex 1.66552 2.04078 2.46643 + endloop + endfacet + facet normal 0.285049 0.256865 0.923454 + outer loop + vertex 1.66552 2.04078 2.46643 + vertex 1.66606 2.03626 2.46752 + vertex 1.6687 2.03888 2.46598 + endloop + endfacet + facet normal 0.284547 0.256844 0.923615 + outer loop + vertex 1.66552 2.04078 2.46643 + vertex 1.66106 2.04137 2.46764 + vertex 1.66606 2.03626 2.46752 + endloop + endfacet + facet normal 0.285401 0.257691 0.923115 + outer loop + vertex 1.66106 2.04137 2.46764 + vertex 1.66195 2.03718 2.46854 + vertex 1.66606 2.03626 2.46752 + endloop + endfacet + facet normal 0.285234 0.256535 0.923489 + outer loop + vertex 1.66284 2.03297 2.46943 + vertex 1.66606 2.03626 2.46752 + vertex 1.66195 2.03718 2.46854 + endloop + endfacet + facet normal 0.284782 0.256472 0.923646 + outer loop + vertex 1.65785 2.03809 2.46955 + vertex 1.66284 2.03297 2.46943 + vertex 1.66195 2.03718 2.46854 + endloop + endfacet + facet normal 0.284947 0.257628 0.923273 + outer loop + vertex 1.66195 2.03718 2.46854 + vertex 1.66106 2.04137 2.46764 + vertex 1.65785 2.03809 2.46955 + endloop + endfacet + facet normal 0.287051 0.259084 0.922213 + outer loop + vertex 1.67576 2.04118 2.46314 + vertex 1.67538 2.04567 2.462 + vertex 1.67274 2.0429 2.4636 + endloop + endfacet + facet normal 0.285029 0.259071 0.922844 + outer loop + vertex 1.67538 2.04567 2.462 + vertex 1.67576 2.04118 2.46314 + vertex 1.67966 2.04125 2.46191 + endloop + endfacet + facet normal 0.281416 0.253697 0.925442 + outer loop + vertex 1.689 2.03383 2.46112 + vertex 1.68905 2.03786 2.46 + vertex 1.68605 2.03572 2.46149 + endloop + endfacet + facet normal 0.282228 0.253624 0.925215 + outer loop + vertex 1.689 2.03383 2.46112 + vertex 1.69341 2.03338 2.45989 + vertex 1.68905 2.03786 2.46 + endloop + endfacet + facet normal 0.278706 0.250155 0.927225 + outer loop + vertex 1.68905 2.03786 2.46 + vertex 1.69341 2.03338 2.45989 + vertex 1.69302 2.03793 2.45878 + endloop + endfacet + facet normal 0.278126 0.256528 0.925656 + outer loop + vertex 1.69302 2.03793 2.45878 + vertex 1.69101 2.04118 2.45849 + vertex 1.68905 2.03786 2.46 + endloop + endfacet + facet normal 0.27865 0.25683 0.925415 + outer loop + vertex 1.69302 2.03793 2.45878 + vertex 1.69555 2.04087 2.45721 + vertex 1.69101 2.04118 2.45849 + endloop + endfacet + facet normal 0.278603 0.261264 0.924187 + outer loop + vertex 1.69058 2.04594 2.45727 + vertex 1.69101 2.04118 2.45849 + vertex 1.69555 2.04087 2.45721 + endloop + endfacet + facet normal 0.277788 0.256746 0.925697 + outer loop + vertex 1.68905 2.03786 2.46 + vertex 1.69101 2.04118 2.45849 + vertex 1.68666 2.04326 2.45921 + endloop + endfacet + facet normal 0.279648 0.261275 0.923868 + outer loop + vertex 1.69101 2.04118 2.45849 + vertex 1.69058 2.04594 2.45727 + vertex 1.68666 2.04326 2.45921 + endloop + endfacet + facet normal 0.281705 0.26441 0.92235 + outer loop + vertex 1.68642 2.04699 2.45823 + vertex 1.68578 2.05099 2.45728 + vertex 1.6824 2.04782 2.45922 + endloop + endfacet + facet normal 0.278701 0.264822 0.923144 + outer loop + vertex 1.68843 2.05358 2.45572 + vertex 1.69024 2.0504 2.45609 + vertex 1.69287 2.05302 2.45454 + endloop + endfacet + facet normal 0.282986 0.262462 0.922514 + outer loop + vertex 1.68087 2.05603 2.45735 + vertex 1.68172 2.05188 2.45827 + vertex 1.68578 2.05099 2.45728 + endloop + endfacet + facet normal 0.282496 0.262778 0.922575 + outer loop + vertex 1.68346 2.05865 2.4558 + vertex 1.68529 2.05545 2.45615 + vertex 1.68791 2.05807 2.4546 + endloop + endfacet + facet normal 0.287848 0.261009 0.921422 + outer loop + vertex 1.67766 2.05276 2.45928 + vertex 1.68087 2.05603 2.45735 + vertex 1.6768 2.05694 2.45836 + endloop + endfacet + facet normal 0.28688 0.2607 0.921811 + outer loop + vertex 1.67811 2.04827 2.46041 + vertex 1.67766 2.05276 2.45928 + vertex 1.67506 2.0501 2.46085 + endloop + endfacet + facet normal 0.288142 0.257247 0.922387 + outer loop + vertex 1.66826 2.04341 2.46485 + vertex 1.671 2.04609 2.46325 + vertex 1.66788 2.04795 2.4637 + endloop + endfacet + facet normal 0.285545 0.257518 0.923119 + outer loop + vertex 1.66371 2.04399 2.46609 + vertex 1.66552 2.04078 2.46643 + vertex 1.66826 2.04341 2.46485 + endloop + endfacet + facet normal 0.284555 0.257006 0.923567 + outer loop + vertex 1.66552 2.04078 2.46643 + vertex 1.66371 2.04399 2.46609 + vertex 1.66106 2.04137 2.46764 + endloop + endfacet + facet normal 0.284867 0.257707 0.923275 + outer loop + vertex 1.65785 2.03809 2.46955 + vertex 1.66106 2.04137 2.46764 + vertex 1.65697 2.04227 2.46865 + endloop + endfacet + facet normal 0.285791 0.25747 0.923056 + outer loop + vertex 1.65843 2.03351 2.47064 + vertex 1.66284 2.03297 2.46943 + vertex 1.65785 2.03809 2.46955 + endloop + endfacet + facet normal 0.28451 0.254575 0.924254 + outer loop + vertex 1.66024 2.0303 2.47097 + vertex 1.65843 2.03351 2.47064 + vertex 1.65574 2.03081 2.47222 + endloop + endfacet + facet normal 0.28456 0.2569 0.923595 + outer loop + vertex 1.65526 2.03543 2.47109 + vertex 1.65342 2.03867 2.47076 + vertex 1.65068 2.03604 2.47233 + endloop + endfacet + facet normal 0.282436 0.255252 0.924704 + outer loop + vertex 1.65112 2.03124 2.47352 + vertex 1.65068 2.03604 2.47233 + vertex 1.6468 2.03333 2.47426 + endloop + endfacet + facet normal 0.285925 0.250037 0.925056 + outer loop + vertex 1.65614 2.02621 2.47333 + vertex 1.65574 2.03081 2.47222 + vertex 1.65312 2.02795 2.4738 + endloop + endfacet + facet normal 0.285751 0.250035 0.92511 + outer loop + vertex 1.65574 2.03081 2.47222 + vertex 1.65614 2.02621 2.47333 + vertex 1.66053 2.02583 2.47208 + endloop + endfacet + facet normal 0.28429 0.248609 0.925944 + outer loop + vertex 1.66024 2.0303 2.47097 + vertex 1.65574 2.03081 2.47222 + vertex 1.66053 2.02583 2.47208 + endloop + endfacet + facet normal 0.285693 0.255184 0.923721 + outer loop + vertex 1.65843 2.03351 2.47064 + vertex 1.66024 2.0303 2.47097 + vertex 1.66284 2.03297 2.46943 + endloop + endfacet + facet normal 0.288722 0.248484 0.924605 + outer loop + vertex 1.6633 2.02847 2.47053 + vertex 1.66487 2.0254 2.47086 + vertex 1.66756 2.028 2.46932 + endloop + endfacet + facet normal 0.286304 0.255467 0.923454 + outer loop + vertex 1.66691 2.03208 2.46841 + vertex 1.66606 2.03626 2.46752 + vertex 1.66284 2.03297 2.46943 + endloop + endfacet + facet normal 0.286062 0.25583 0.923428 + outer loop + vertex 1.67051 2.03567 2.46631 + vertex 1.6687 2.03888 2.46598 + vertex 1.66606 2.03626 2.46752 + endloop + endfacet + facet normal 0.287278 0.256459 0.922876 + outer loop + vertex 1.6687 2.03888 2.46598 + vertex 1.67051 2.03567 2.46631 + vertex 1.67318 2.03834 2.46473 + endloop + endfacet + facet normal 0.286454 0.254002 0.923811 + outer loop + vertex 1.67318 2.03834 2.46473 + vertex 1.67814 2.03317 2.46461 + vertex 1.67774 2.03795 2.46343 + endloop + endfacet + facet normal 0.285433 0.24991 0.925242 + outer loop + vertex 1.67842 2.02866 2.46575 + vertex 1.68287 2.02803 2.46455 + vertex 1.67814 2.03317 2.46461 + endloop + endfacet + facet normal 0.287742 0.247082 0.925286 + outer loop + vertex 1.68019 2.0254 2.46607 + vertex 1.67842 2.02866 2.46575 + vertex 1.67563 2.02604 2.46731 + endloop + endfacet + facet normal 0.288287 0.251291 0.923982 + outer loop + vertex 1.67535 2.03057 2.46619 + vertex 1.67362 2.03378 2.46586 + vertex 1.67093 2.03118 2.4674 + endloop + endfacet + facet normal 0.285258 0.243877 0.926905 + outer loop + vertex 1.67563 2.02604 2.46731 + vertex 1.67605 2.0212 2.46846 + vertex 1.68065 2.02076 2.46716 + endloop + endfacet + facet normal 0.285206 0.241294 0.927596 + outer loop + vertex 1.67805 2.01789 2.46871 + vertex 1.68065 2.02076 2.46716 + vertex 1.67605 2.0212 2.46846 + endloop + endfacet + facet normal 0.287265 0.242466 0.926655 + outer loop + vertex 1.67805 2.01789 2.46871 + vertex 1.67605 2.0212 2.46846 + vertex 1.67409 2.01789 2.46993 + endloop + endfacet + facet normal 0.287163 0.243833 0.926328 + outer loop + vertex 1.67409 2.01789 2.46993 + vertex 1.67839 2.01336 2.46979 + vertex 1.67805 2.01789 2.46871 + endloop + endfacet + facet normal 0.281704 0.243827 0.928004 + outer loop + vertex 1.67839 2.01336 2.46979 + vertex 1.68109 2.01614 2.46824 + vertex 1.67805 2.01789 2.46871 + endloop + endfacet + facet normal 0.278512 0.246997 0.928129 + outer loop + vertex 1.68281 2.01296 2.46857 + vertex 1.68109 2.01614 2.46824 + vertex 1.67839 2.01336 2.46979 + endloop + endfacet + facet normal 0.278486 0.245306 0.928585 + outer loop + vertex 1.67839 2.01336 2.46979 + vertex 1.68318 2.00837 2.46968 + vertex 1.68281 2.01296 2.46857 + endloop + endfacet + facet normal 0.274808 0.241724 0.930618 + outer loop + vertex 1.67858 2.00888 2.4709 + vertex 1.68318 2.00837 2.46968 + vertex 1.67839 2.01336 2.46979 + endloop + endfacet + facet normal 0.282164 0.241517 0.928468 + outer loop + vertex 1.67858 2.00888 2.4709 + vertex 1.67839 2.01336 2.46979 + vertex 1.67552 2.01074 2.47134 + endloop + endfacet + facet normal 0.281524 0.240348 0.928966 + outer loop + vertex 1.67552 2.01074 2.47134 + vertex 1.67569 2.00621 2.47247 + vertex 1.67858 2.00888 2.4709 + endloop + endfacet + facet normal 0.280677 0.241276 0.928981 + outer loop + vertex 1.68032 2.00562 2.47122 + vertex 1.67858 2.00888 2.4709 + vertex 1.67569 2.00621 2.47247 + endloop + endfacet + facet normal 0.280445 0.236952 0.930164 + outer loop + vertex 1.68032 2.00562 2.47122 + vertex 1.67569 2.00621 2.47247 + vertex 1.68069 2.00094 2.4723 + endloop + endfacet + facet normal 0.272385 0.236867 0.932577 + outer loop + vertex 1.68032 2.00562 2.47122 + vertex 1.68069 2.00094 2.4723 + vertex 1.68352 2.00371 2.47077 + endloop + endfacet + facet normal 0.27372 0.239344 0.931554 + outer loop + vertex 1.68352 2.00371 2.47077 + vertex 1.68318 2.00837 2.46968 + vertex 1.68032 2.00562 2.47122 + endloop + endfacet + facet normal 0.272276 0.236979 0.932581 + outer loop + vertex 1.68526 2.00047 2.47109 + vertex 1.68352 2.00371 2.47077 + vertex 1.68069 2.00094 2.4723 + endloop + endfacet + facet normal 0.286488 0.240166 0.927494 + outer loop + vertex 1.67552 2.01074 2.47134 + vertex 1.6712 2.01126 2.47255 + vertex 1.67569 2.00621 2.47247 + endloop + endfacet + facet normal 0.28387 0.239628 0.928437 + outer loop + vertex 1.67401 2.01384 2.47101 + vertex 1.67552 2.01074 2.47134 + vertex 1.67839 2.01336 2.46979 + endloop + endfacet + facet normal 0.274677 0.238336 0.93153 + outer loop + vertex 1.67858 2.00888 2.4709 + vertex 1.68032 2.00562 2.47122 + vertex 1.68318 2.00837 2.46968 + endloop + endfacet + facet normal 0.27496 0.24523 0.929655 + outer loop + vertex 1.68281 2.01296 2.46857 + vertex 1.68547 2.01577 2.46704 + vertex 1.68109 2.01614 2.46824 + endloop + endfacet + facet normal 0.274948 0.244168 0.929938 + outer loop + vertex 1.68065 2.02076 2.46716 + vertex 1.68109 2.01614 2.46824 + vertex 1.68547 2.01577 2.46704 + endloop + endfacet + facet normal 0.281963 0.244333 0.927792 + outer loop + vertex 1.68109 2.01614 2.46824 + vertex 1.68065 2.02076 2.46716 + vertex 1.67805 2.01789 2.46871 + endloop + endfacet + facet normal 0.283907 0.24069 0.928151 + outer loop + vertex 1.67401 2.01384 2.47101 + vertex 1.67839 2.01336 2.46979 + vertex 1.67409 2.01789 2.46993 + endloop + endfacet + facet normal 0.286516 0.240803 0.92732 + outer loop + vertex 1.67552 2.01074 2.47134 + vertex 1.67401 2.01384 2.47101 + vertex 1.6712 2.01126 2.47255 + endloop + endfacet + facet normal 0.288221 0.238765 0.927319 + outer loop + vertex 1.66944 2.01962 2.47094 + vertex 1.6671 2.01588 2.47263 + vertex 1.67112 2.01573 2.47142 + endloop + endfacet + facet normal 0.286711 0.238687 0.927807 + outer loop + vertex 1.66727 2.01209 2.47355 + vertex 1.6671 2.01588 2.47263 + vertex 1.66318 2.01313 2.47455 + endloop + endfacet + facet normal 0.286179 0.239889 0.927661 + outer loop + vertex 1.6712 2.01126 2.47255 + vertex 1.67157 2.00728 2.47346 + vertex 1.67569 2.00621 2.47247 + endloop + endfacet + facet normal 0.279489 0.236031 0.930685 + outer loop + vertex 1.67569 2.00621 2.47247 + vertex 1.67605 2.00134 2.47359 + vertex 1.68069 2.00094 2.4723 + endloop + endfacet + facet normal 0.279408 0.230773 0.932027 + outer loop + vertex 1.67806 1.99799 2.47382 + vertex 1.68069 2.00094 2.4723 + vertex 1.67605 2.00134 2.47359 + endloop + endfacet + facet normal 0.277752 0.23231 0.932141 + outer loop + vertex 1.68111 1.99625 2.47335 + vertex 1.68069 2.00094 2.4723 + vertex 1.67806 1.99799 2.47382 + endloop + endfacet + facet normal 0.27735 0.231523 0.932456 + outer loop + vertex 1.67843 1.9934 2.47485 + vertex 1.68111 1.99625 2.47335 + vertex 1.67806 1.99799 2.47382 + endloop + endfacet + facet normal 0.283981 0.231597 0.93044 + outer loop + vertex 1.67411 1.99797 2.47503 + vertex 1.67843 1.9934 2.47485 + vertex 1.67806 1.99799 2.47382 + endloop + endfacet + facet normal 0.275468 0.233354 0.932557 + outer loop + vertex 1.68286 1.99303 2.47363 + vertex 1.68111 1.99625 2.47335 + vertex 1.67843 1.9934 2.47485 + endloop + endfacet + facet normal 0.275435 0.231178 0.933109 + outer loop + vertex 1.67843 1.9934 2.47485 + vertex 1.68323 1.98839 2.47468 + vertex 1.68286 1.99303 2.47363 + endloop + endfacet + facet normal 0.274646 0.230409 0.933532 + outer loop + vertex 1.67863 1.98889 2.4759 + vertex 1.68323 1.98839 2.47468 + vertex 1.67843 1.9934 2.47485 + endloop + endfacet + facet normal 0.278919 0.230315 0.932287 + outer loop + vertex 1.67863 1.98889 2.4759 + vertex 1.67843 1.9934 2.47485 + vertex 1.67556 1.99077 2.47636 + endloop + endfacet + facet normal 0.279578 0.231512 0.931793 + outer loop + vertex 1.67556 1.99077 2.47636 + vertex 1.67571 1.98623 2.47744 + vertex 1.67863 1.98889 2.4759 + endloop + endfacet + facet normal 0.277433 0.233895 0.931839 + outer loop + vertex 1.68035 1.98564 2.47621 + vertex 1.67863 1.98889 2.4759 + vertex 1.67571 1.98623 2.47744 + endloop + endfacet + facet normal 0.286906 0.23124 0.929631 + outer loop + vertex 1.67556 1.99077 2.47636 + vertex 1.67123 1.99131 2.47756 + vertex 1.67571 1.98623 2.47744 + endloop + endfacet + facet normal 0.281593 0.226487 0.932421 + outer loop + vertex 1.67123 1.99131 2.47756 + vertex 1.67157 1.9873 2.47843 + vertex 1.67571 1.98623 2.47744 + endloop + endfacet + facet normal 0.281915 0.228202 0.931905 + outer loop + vertex 1.67177 1.98347 2.47931 + vertex 1.67571 1.98623 2.47744 + vertex 1.67157 1.9873 2.47843 + endloop + endfacet + facet normal 0.288805 0.228074 0.929825 + outer loop + vertex 1.66764 1.98816 2.47944 + vertex 1.67177 1.98347 2.47931 + vertex 1.67157 1.9873 2.47843 + endloop + endfacet + facet normal 0.285275 0.224911 0.931683 + outer loop + vertex 1.66775 1.98363 2.4805 + vertex 1.67177 1.98347 2.47931 + vertex 1.66764 1.98816 2.47944 + endloop + endfacet + facet normal 0.289077 0.224741 0.930552 + outer loop + vertex 1.66775 1.98363 2.4805 + vertex 1.66764 1.98816 2.47944 + vertex 1.66487 1.98553 2.48094 + endloop + endfacet + facet normal 0.289022 0.224649 0.930591 + outer loop + vertex 1.66487 1.98553 2.48094 + vertex 1.66483 1.98141 2.48195 + vertex 1.66775 1.98363 2.4805 + endloop + endfacet + facet normal 0.287268 0.226951 0.930575 + outer loop + vertex 1.66946 1.97969 2.48094 + vertex 1.66775 1.98363 2.4805 + vertex 1.66483 1.98141 2.48195 + endloop + endfacet + facet normal 0.289932 0.224574 0.930326 + outer loop + vertex 1.66487 1.98553 2.48094 + vertex 1.66056 1.98598 2.48217 + vertex 1.66483 1.98141 2.48195 + endloop + endfacet + facet normal 0.288652 0.223345 0.931019 + outer loop + vertex 1.66056 1.98598 2.48217 + vertex 1.66093 1.98135 2.48317 + vertex 1.66483 1.98141 2.48195 + endloop + endfacet + facet normal 0.288589 0.22411 0.930855 + outer loop + vertex 1.66285 1.97804 2.48337 + vertex 1.66483 1.98141 2.48195 + vertex 1.66093 1.98135 2.48317 + endloop + endfacet + facet normal 0.287614 0.223571 0.931286 + outer loop + vertex 1.66285 1.97804 2.48337 + vertex 1.66093 1.98135 2.48317 + vertex 1.65827 1.97844 2.48469 + endloop + endfacet + facet normal 0.287611 0.223419 0.931324 + outer loop + vertex 1.65827 1.97844 2.48469 + vertex 1.66296 1.97327 2.48448 + vertex 1.66285 1.97804 2.48337 + endloop + endfacet + facet normal 0.286589 0.223465 0.931628 + outer loop + vertex 1.66296 1.97327 2.48448 + vertex 1.66704 1.97593 2.48258 + vertex 1.66285 1.97804 2.48337 + endloop + endfacet + facet normal 0.286529 0.223555 0.931624 + outer loop + vertex 1.66699 1.97224 2.48349 + vertex 1.66704 1.97593 2.48258 + vertex 1.66296 1.97327 2.48448 + endloop + endfacet + facet normal 0.285924 0.220243 0.932599 + outer loop + vertex 1.66296 1.97327 2.48448 + vertex 1.66693 1.96853 2.48438 + vertex 1.66699 1.97224 2.48349 + endloop + endfacet + facet normal 0.284011 0.220402 0.933145 + outer loop + vertex 1.66693 1.96853 2.48438 + vertex 1.67103 1.97121 2.4825 + vertex 1.66699 1.97224 2.48349 + endloop + endfacet + facet normal 0.286004 0.220311 0.932558 + outer loop + vertex 1.66287 1.96873 2.48558 + vertex 1.66693 1.96853 2.48438 + vertex 1.66296 1.97327 2.48448 + endloop + endfacet + facet normal 0.287693 0.220161 0.932074 + outer loop + vertex 1.66287 1.96873 2.48558 + vertex 1.66296 1.97327 2.48448 + vertex 1.66001 1.97063 2.48601 + endloop + endfacet + facet normal 0.285569 0.216642 0.933551 + outer loop + vertex 1.66001 1.97063 2.48601 + vertex 1.65987 1.96652 2.48701 + vertex 1.66287 1.96873 2.48558 + endloop + endfacet + facet normal 0.285814 0.216311 0.933552 + outer loop + vertex 1.66449 1.96478 2.486 + vertex 1.66287 1.96873 2.48558 + vertex 1.65987 1.96652 2.48701 + endloop + endfacet + facet normal 0.285373 0.216662 0.933606 + outer loop + vertex 1.66001 1.97063 2.48601 + vertex 1.65565 1.97107 2.48725 + vertex 1.65987 1.96652 2.48701 + endloop + endfacet + facet normal 0.28578 0.21705 0.933391 + outer loop + vertex 1.65565 1.97107 2.48725 + vertex 1.656 1.96641 2.48822 + vertex 1.65987 1.96652 2.48701 + endloop + endfacet + facet normal 0.286121 0.213282 0.934155 + outer loop + vertex 1.65786 1.96312 2.4884 + vertex 1.65987 1.96652 2.48701 + vertex 1.656 1.96641 2.48822 + endloop + endfacet + facet normal 0.285764 0.213087 0.934309 + outer loop + vertex 1.65786 1.96312 2.4884 + vertex 1.656 1.96641 2.48822 + vertex 1.6534 1.96341 2.4897 + endloop + endfacet + facet normal 0.285768 0.211393 0.934692 + outer loop + vertex 1.6534 1.96341 2.4897 + vertex 1.65795 1.95833 2.48946 + vertex 1.65786 1.96312 2.4884 + endloop + endfacet + facet normal 0.285065 0.211426 0.9349 + outer loop + vertex 1.65795 1.95833 2.48946 + vertex 1.66204 1.96102 2.4876 + vertex 1.65786 1.96312 2.4884 + endloop + endfacet + facet normal 0.285462 0.210832 0.934912 + outer loop + vertex 1.66199 1.95729 2.48846 + vertex 1.66204 1.96102 2.4876 + vertex 1.65795 1.95833 2.48946 + endloop + endfacet + facet normal 0.285042 0.208571 0.935548 + outer loop + vertex 1.65795 1.95833 2.48946 + vertex 1.66194 1.95352 2.48931 + vertex 1.66199 1.95729 2.48846 + endloop + endfacet + facet normal 0.283419 0.208698 0.936012 + outer loop + vertex 1.66194 1.95352 2.48931 + vertex 1.66605 1.95624 2.48747 + vertex 1.66199 1.95729 2.48846 + endloop + endfacet + facet normal 0.28415 0.207607 0.936033 + outer loop + vertex 1.66617 1.95137 2.48851 + vertex 1.66605 1.95624 2.48747 + vertex 1.66194 1.95352 2.48931 + endloop + endfacet + facet normal 0.283231 0.205523 0.936771 + outer loop + vertex 1.66411 1.94793 2.48989 + vertex 1.66617 1.95137 2.48851 + vertex 1.66194 1.95352 2.48931 + endloop + endfacet + facet normal 0.287747 0.207098 0.935047 + outer loop + vertex 1.66411 1.94793 2.48989 + vertex 1.66194 1.95352 2.48931 + vertex 1.65944 1.94971 2.49093 + endloop + endfacet + facet normal 0.287165 0.205216 0.93564 + outer loop + vertex 1.66105 1.94568 2.49132 + vertex 1.66411 1.94793 2.48989 + vertex 1.65944 1.94971 2.49093 + endloop + endfacet + facet normal 0.288656 0.205755 0.935063 + outer loop + vertex 1.65944 1.94971 2.49093 + vertex 1.65682 1.94589 2.49258 + vertex 1.66105 1.94568 2.49132 + endloop + endfacet + facet normal 0.288701 0.202417 0.935777 + outer loop + vertex 1.66105 1.94568 2.49132 + vertex 1.65682 1.94589 2.49258 + vertex 1.66093 1.94111 2.49234 + endloop + endfacet + facet normal 0.287795 0.202499 0.936039 + outer loop + vertex 1.66105 1.94568 2.49132 + vertex 1.66093 1.94111 2.49234 + vertex 1.66389 1.94378 2.49086 + endloop + endfacet + facet normal 0.288678 0.201489 0.935984 + outer loop + vertex 1.66517 1.94075 2.49111 + vertex 1.66389 1.94378 2.49086 + vertex 1.66093 1.94111 2.49234 + endloop + endfacet + facet normal 0.283612 0.199508 0.937956 + outer loop + vertex 1.66389 1.94378 2.49086 + vertex 1.66517 1.94075 2.49111 + vertex 1.66814 1.94344 2.48964 + endloop + endfacet + facet normal 0.283681 0.204076 0.936951 + outer loop + vertex 1.66389 1.94378 2.49086 + vertex 1.66814 1.94344 2.48964 + vertex 1.66411 1.94793 2.48989 + endloop + endfacet + facet normal 0.282847 0.203303 0.937371 + outer loop + vertex 1.66411 1.94793 2.48989 + vertex 1.66814 1.94344 2.48964 + vertex 1.66803 1.94804 2.48868 + endloop + endfacet + facet normal 0.27677 0.203515 0.939138 + outer loop + vertex 1.66814 1.94344 2.48964 + vertex 1.6709 1.94644 2.48818 + vertex 1.66803 1.94804 2.48868 + endloop + endfacet + facet normal 0.277431 0.204848 0.938653 + outer loop + vertex 1.6709 1.94644 2.48818 + vertex 1.67067 1.9511 2.48723 + vertex 1.66803 1.94804 2.48868 + endloop + endfacet + facet normal 0.278608 0.203776 0.938538 + outer loop + vertex 1.66803 1.94804 2.48868 + vertex 1.67067 1.9511 2.48723 + vertex 1.66617 1.95137 2.48851 + endloop + endfacet + facet normal 0.276658 0.203623 0.939147 + outer loop + vertex 1.67262 1.94321 2.48838 + vertex 1.6709 1.94644 2.48818 + vertex 1.66814 1.94344 2.48964 + endloop + endfacet + facet normal 0.276694 0.198396 0.940255 + outer loop + vertex 1.66814 1.94344 2.48964 + vertex 1.67225 1.93871 2.48943 + vertex 1.67262 1.94321 2.48838 + endloop + endfacet + facet normal 0.289961 0.203531 0.935146 + outer loop + vertex 1.65682 1.94589 2.49258 + vertex 1.65651 1.9414 2.49365 + vertex 1.66093 1.94111 2.49234 + endloop + endfacet + facet normal 0.289953 0.19951 0.936015 + outer loop + vertex 1.65818 1.93817 2.49382 + vertex 1.66093 1.94111 2.49234 + vertex 1.65651 1.9414 2.49365 + endloop + endfacet + facet normal 0.286319 0.197707 0.937515 + outer loop + vertex 1.65818 1.93817 2.49382 + vertex 1.65651 1.9414 2.49365 + vertex 1.65429 1.9381 2.49502 + endloop + endfacet + facet normal 0.286735 0.192166 0.938539 + outer loop + vertex 1.65429 1.9381 2.49502 + vertex 1.65822 1.93362 2.49474 + vertex 1.65818 1.93817 2.49382 + endloop + endfacet + facet normal 0.288506 0.192074 0.938015 + outer loop + vertex 1.65822 1.93362 2.49474 + vertex 1.66097 1.93658 2.49329 + vertex 1.65818 1.93817 2.49382 + endloop + endfacet + facet normal 0.289186 0.191406 0.937942 + outer loop + vertex 1.66263 1.93332 2.49344 + vertex 1.66097 1.93658 2.49329 + vertex 1.65822 1.93362 2.49474 + endloop + endfacet + facet normal 0.289148 0.18559 0.939122 + outer loop + vertex 1.65822 1.93362 2.49474 + vertex 1.66229 1.92877 2.49445 + vertex 1.66263 1.93332 2.49344 + endloop + endfacet + facet normal 0.284791 0.186186 0.940334 + outer loop + vertex 1.66229 1.92877 2.49445 + vertex 1.66684 1.931 2.49263 + vertex 1.66263 1.93332 2.49344 + endloop + endfacet + facet normal 0.287953 0.192701 0.938056 + outer loop + vertex 1.66684 1.931 2.49263 + vertex 1.66486 1.93663 2.49208 + vertex 1.66263 1.93332 2.49344 + endloop + endfacet + facet normal 0.285946 0.183914 0.940431 + outer loop + vertex 1.66649 1.92643 2.49363 + vertex 1.66684 1.931 2.49263 + vertex 1.66229 1.92877 2.49445 + endloop + endfacet + facet normal 0.283466 0.178862 0.942155 + outer loop + vertex 1.66422 1.92305 2.49495 + vertex 1.66649 1.92643 2.49363 + vertex 1.66229 1.92877 2.49445 + endloop + endfacet + facet normal 0.28885 0.180504 0.940204 + outer loop + vertex 1.66422 1.92305 2.49495 + vertex 1.66229 1.92877 2.49445 + vertex 1.65957 1.9249 2.49603 + endloop + endfacet + facet normal 0.287852 0.177488 0.941084 + outer loop + vertex 1.66106 1.92079 2.49634 + vertex 1.66422 1.92305 2.49495 + vertex 1.65957 1.9249 2.49603 + endloop + endfacet + facet normal 0.292529 0.179055 0.939344 + outer loop + vertex 1.65957 1.9249 2.49603 + vertex 1.65685 1.92103 2.49761 + vertex 1.66106 1.92079 2.49634 + endloop + endfacet + facet normal 0.292528 0.180711 0.939027 + outer loop + vertex 1.66106 1.92079 2.49634 + vertex 1.65685 1.92103 2.49761 + vertex 1.66089 1.91613 2.49729 + endloop + endfacet + facet normal 0.290661 0.180892 0.939571 + outer loop + vertex 1.66106 1.92079 2.49634 + vertex 1.66089 1.91613 2.49729 + vertex 1.66387 1.91883 2.49585 + endloop + endfacet + facet normal 0.289992 0.181662 0.93963 + outer loop + vertex 1.66511 1.91576 2.49606 + vertex 1.66387 1.91883 2.49585 + vertex 1.66089 1.91613 2.49729 + endloop + endfacet + facet normal 0.290066 0.184093 0.939134 + outer loop + vertex 1.66511 1.91576 2.49606 + vertex 1.66089 1.91613 2.49729 + vertex 1.66481 1.91159 2.49697 + endloop + endfacet + facet normal 0.283648 0.184941 0.940925 + outer loop + vertex 1.66511 1.91576 2.49606 + vertex 1.66481 1.91159 2.49697 + vertex 1.66793 1.91385 2.49559 + endloop + endfacet + facet normal 0.280525 0.179855 0.942846 + outer loop + vertex 1.66793 1.91385 2.49559 + vertex 1.66812 1.9185 2.49465 + vertex 1.66511 1.91576 2.49606 + endloop + endfacet + facet normal 0.282873 0.186023 0.940945 + outer loop + vertex 1.66948 1.90981 2.49592 + vertex 1.66793 1.91385 2.49559 + vertex 1.66481 1.91159 2.49697 + endloop + endfacet + facet normal 0.288982 0.183121 0.939658 + outer loop + vertex 1.66089 1.91613 2.49729 + vertex 1.66092 1.91153 2.49818 + vertex 1.66481 1.91159 2.49697 + endloop + endfacet + facet normal 0.288897 0.184354 0.939443 + outer loop + vertex 1.6626 1.90825 2.49831 + vertex 1.66481 1.91159 2.49697 + vertex 1.66092 1.91153 2.49818 + endloop + endfacet + facet normal 0.290689 0.185246 0.938714 + outer loop + vertex 1.6626 1.90825 2.49831 + vertex 1.66092 1.91153 2.49818 + vertex 1.65819 1.90855 2.49962 + endloop + endfacet + facet normal 0.290673 0.183592 0.939044 + outer loop + vertex 1.65819 1.90855 2.49962 + vertex 1.66225 1.90371 2.49931 + vertex 1.6626 1.90825 2.49831 + endloop + endfacet + facet normal 0.28367 0.184573 0.940991 + outer loop + vertex 1.66225 1.90371 2.49931 + vertex 1.6668 1.90594 2.49749 + vertex 1.6626 1.90825 2.49831 + endloop + endfacet + facet normal 0.283284 0.185334 0.940958 + outer loop + vertex 1.6664 1.90143 2.49851 + vertex 1.6668 1.90594 2.49749 + vertex 1.66225 1.90371 2.49931 + endloop + endfacet + facet normal 0.280844 0.180303 0.942665 + outer loop + vertex 1.66399 1.89815 2.49985 + vertex 1.6664 1.90143 2.49851 + vertex 1.66225 1.90371 2.49931 + endloop + endfacet + facet normal 0.28187 0.180589 0.942304 + outer loop + vertex 1.66399 1.89815 2.49985 + vertex 1.66225 1.90371 2.49931 + vertex 1.65947 1.89988 2.50087 + endloop + endfacet + facet normal 0.280401 0.175978 0.943614 + outer loop + vertex 1.66077 1.89595 2.50122 + vertex 1.66399 1.89815 2.49985 + vertex 1.65947 1.89988 2.50087 + endloop + endfacet + facet normal 0.281375 0.176271 0.943269 + outer loop + vertex 1.65947 1.89988 2.50087 + vertex 1.65663 1.89608 2.50243 + vertex 1.66077 1.89595 2.50122 + endloop + endfacet + facet normal 0.281364 0.176816 0.94317 + outer loop + vertex 1.66077 1.89595 2.50122 + vertex 1.65663 1.89608 2.50243 + vertex 1.66021 1.89174 2.50217 + endloop + endfacet + facet normal 0.278458 0.177374 0.943928 + outer loop + vertex 1.66077 1.89595 2.50122 + vertex 1.66021 1.89174 2.50217 + vertex 1.66344 1.89398 2.5008 + endloop + endfacet + facet normal 0.277869 0.178231 0.94394 + outer loop + vertex 1.66475 1.89007 2.50115 + vertex 1.66344 1.89398 2.5008 + vertex 1.66021 1.89174 2.50217 + endloop + endfacet + facet normal 0.279949 0.175611 0.943816 + outer loop + vertex 1.65663 1.89608 2.50243 + vertex 1.65614 1.89158 2.50341 + vertex 1.66021 1.89174 2.50217 + endloop + endfacet + facet normal 0.279843 0.176835 0.943619 + outer loop + vertex 1.65789 1.8883 2.50351 + vertex 1.66021 1.89174 2.50217 + vertex 1.65614 1.89158 2.50341 + endloop + endfacet + facet normal 0.281638 0.177766 0.94291 + outer loop + vertex 1.65789 1.8883 2.50351 + vertex 1.65614 1.89158 2.50341 + vertex 1.65383 1.88813 2.50475 + endloop + endfacet + facet normal 0.281561 0.178609 0.942774 + outer loop + vertex 1.65383 1.88813 2.50475 + vertex 1.65744 1.88379 2.50449 + vertex 1.65789 1.8883 2.50351 + endloop + endfacet + facet normal 0.278418 0.179103 0.943613 + outer loop + vertex 1.65744 1.88379 2.50449 + vertex 1.66195 1.88616 2.50272 + vertex 1.65789 1.8883 2.50351 + endloop + endfacet + facet normal 0.278726 0.17853 0.943631 + outer loop + vertex 1.66152 1.88159 2.50371 + vertex 1.66195 1.88616 2.50272 + vertex 1.65744 1.88379 2.50449 + endloop + endfacet + facet normal 0.278303 0.177639 0.943924 + outer loop + vertex 1.65927 1.87821 2.505 + vertex 1.66152 1.88159 2.50371 + vertex 1.65744 1.88379 2.50449 + endloop + endfacet + facet normal 0.28114 0.178479 0.942924 + outer loop + vertex 1.65927 1.87821 2.505 + vertex 1.65744 1.88379 2.50449 + vertex 1.65466 1.87997 2.50605 + endloop + endfacet + facet normal 0.280403 0.176162 0.943579 + outer loop + vertex 1.65612 1.87594 2.50637 + vertex 1.65927 1.87821 2.505 + vertex 1.65466 1.87997 2.50605 + endloop + endfacet + facet normal 0.283133 0.177071 0.942593 + outer loop + vertex 1.65466 1.87997 2.50605 + vertex 1.65189 1.87612 2.5076 + vertex 1.65612 1.87594 2.50637 + endloop + endfacet + facet normal 0.283178 0.173388 0.943264 + outer loop + vertex 1.65612 1.87594 2.50637 + vertex 1.65189 1.87612 2.5076 + vertex 1.65588 1.87126 2.5073 + endloop + endfacet + facet normal 0.279908 0.173731 0.944176 + outer loop + vertex 1.65612 1.87594 2.50637 + vertex 1.65588 1.87126 2.5073 + vertex 1.65895 1.874 2.50588 + endloop + endfacet + facet normal 0.280489 0.173057 0.944128 + outer loop + vertex 1.6602 1.87086 2.50609 + vertex 1.65895 1.874 2.50588 + vertex 1.65588 1.87126 2.5073 + endloop + endfacet + facet normal 0.280331 0.168889 0.944929 + outer loop + vertex 1.6602 1.87086 2.50609 + vertex 1.65588 1.87126 2.5073 + vertex 1.65975 1.86652 2.507 + endloop + endfacet + facet normal 0.278285 0.169216 0.945475 + outer loop + vertex 1.6602 1.87086 2.50609 + vertex 1.65975 1.86652 2.507 + vertex 1.66302 1.8689 2.50561 + endloop + endfacet + facet normal 0.279821 0.171648 0.944583 + outer loop + vertex 1.66302 1.8689 2.50561 + vertex 1.66323 1.87363 2.50469 + vertex 1.6602 1.87086 2.50609 + endloop + endfacet + facet normal 0.278671 0.168676 0.945458 + outer loop + vertex 1.66445 1.86484 2.50591 + vertex 1.66302 1.8689 2.50561 + vertex 1.65975 1.86652 2.507 + endloop + endfacet + facet normal 0.280642 0.169152 0.94479 + outer loop + vertex 1.65588 1.87126 2.5073 + vertex 1.65566 1.86653 2.50821 + vertex 1.65975 1.86652 2.507 + endloop + endfacet + facet normal 0.280829 0.16509 0.945453 + outer loop + vertex 1.65712 1.86244 2.50849 + vertex 1.65975 1.86652 2.507 + vertex 1.65566 1.86653 2.50821 + endloop + endfacet + facet normal 0.284185 0.166206 0.944253 + outer loop + vertex 1.65712 1.86244 2.50849 + vertex 1.65566 1.86653 2.50821 + vertex 1.6525 1.86403 2.5096 + endloop + endfacet + facet normal 0.283156 0.162556 0.945198 + outer loop + vertex 1.65447 1.85837 2.50998 + vertex 1.65712 1.86244 2.50849 + vertex 1.6525 1.86403 2.5096 + endloop + endfacet + facet normal 0.28643 0.163617 0.944027 + outer loop + vertex 1.65447 1.85837 2.50998 + vertex 1.6525 1.86403 2.5096 + vertex 1.64979 1.86009 2.51111 + endloop + endfacet + facet normal 0.285513 0.160594 0.944824 + outer loop + vertex 1.65119 1.856 2.51138 + vertex 1.65447 1.85837 2.50998 + vertex 1.64979 1.86009 2.51111 + endloop + endfacet + facet normal 0.287851 0.161339 0.943987 + outer loop + vertex 1.64979 1.86009 2.51111 + vertex 1.64696 1.85616 2.51264 + vertex 1.65119 1.856 2.51138 + endloop + endfacet + facet normal 0.28785 0.161455 0.943968 + outer loop + vertex 1.65119 1.856 2.51138 + vertex 1.64696 1.85616 2.51264 + vertex 1.65089 1.85125 2.51228 + endloop + endfacet + facet normal 0.285487 0.161732 0.944637 + outer loop + vertex 1.65119 1.856 2.51138 + vertex 1.65089 1.85125 2.51228 + vertex 1.65398 1.85403 2.51087 + endloop + endfacet + facet normal 0.283983 0.163486 0.944789 + outer loop + vertex 1.65517 1.85086 2.51106 + vertex 1.65398 1.85403 2.51087 + vertex 1.65089 1.85125 2.51228 + endloop + endfacet + facet normal 0.283978 0.163365 0.944811 + outer loop + vertex 1.65517 1.85086 2.51106 + vertex 1.65089 1.85125 2.51228 + vertex 1.65472 1.84653 2.51195 + endloop + endfacet + facet normal 0.276858 0.164503 0.946725 + outer loop + vertex 1.65517 1.85086 2.51106 + vertex 1.65472 1.84653 2.51195 + vertex 1.65797 1.84893 2.51058 + endloop + endfacet + facet normal 0.276346 0.163688 0.947016 + outer loop + vertex 1.65797 1.84893 2.51058 + vertex 1.65829 1.85365 2.50967 + vertex 1.65517 1.85086 2.51106 + endloop + endfacet + facet normal 0.272671 0.16413 0.948004 + outer loop + vertex 1.65797 1.84893 2.51058 + vertex 1.66221 1.84887 2.50937 + vertex 1.65829 1.85365 2.50967 + endloop + endfacet + facet normal 0.273565 0.164888 0.947615 + outer loop + vertex 1.65829 1.85365 2.50967 + vertex 1.66221 1.84887 2.50937 + vertex 1.66276 1.85339 2.50843 + endloop + endfacet + facet normal 0.273579 0.166559 0.947319 + outer loop + vertex 1.66276 1.85339 2.50843 + vertex 1.66131 1.85656 2.50829 + vertex 1.65829 1.85365 2.50967 + endloop + endfacet + facet normal 0.274967 0.165059 0.947179 + outer loop + vertex 1.65829 1.85365 2.50967 + vertex 1.66131 1.85656 2.50829 + vertex 1.65857 1.85836 2.50877 + endloop + endfacet + facet normal 0.280811 0.164411 0.945576 + outer loop + vertex 1.65447 1.85837 2.50998 + vertex 1.65829 1.85365 2.50967 + vertex 1.65857 1.85836 2.50877 + endloop + endfacet + facet normal 0.278286 0.162295 0.946688 + outer loop + vertex 1.65398 1.85403 2.51087 + vertex 1.65829 1.85365 2.50967 + vertex 1.65447 1.85837 2.50998 + endloop + endfacet + facet normal 0.27515 0.165368 0.947072 + outer loop + vertex 1.66131 1.85656 2.50829 + vertex 1.66174 1.86088 2.50741 + vertex 1.65857 1.85836 2.50877 + endloop + endfacet + facet normal 0.277009 0.162961 0.946948 + outer loop + vertex 1.65857 1.85836 2.50877 + vertex 1.66174 1.86088 2.50741 + vertex 1.65712 1.86244 2.50849 + endloop + endfacet + facet normal 0.275758 0.16752 0.946517 + outer loop + vertex 1.66276 1.85339 2.50843 + vertex 1.66521 1.85672 2.50712 + vertex 1.66131 1.85656 2.50829 + endloop + endfacet + facet normal 0.280266 0.16371 0.945859 + outer loop + vertex 1.66221 1.84887 2.50937 + vertex 1.66673 1.85131 2.50761 + vertex 1.66276 1.85339 2.50843 + endloop + endfacet + facet normal 0.272674 0.164021 0.948022 + outer loop + vertex 1.65797 1.84893 2.51058 + vertex 1.6594 1.84489 2.51087 + vertex 1.66221 1.84887 2.50937 + endloop + endfacet + facet normal 0.275855 0.161585 0.94752 + outer loop + vertex 1.66395 1.84327 2.50982 + vertex 1.66221 1.84887 2.50937 + vertex 1.6594 1.84489 2.51087 + endloop + endfacet + facet normal 0.276357 0.163288 0.947082 + outer loop + vertex 1.66073 1.84092 2.51116 + vertex 1.66395 1.84327 2.50982 + vertex 1.6594 1.84489 2.51087 + endloop + endfacet + facet normal 0.273716 0.162469 0.947989 + outer loop + vertex 1.6594 1.84489 2.51087 + vertex 1.65666 1.8409 2.51234 + vertex 1.66073 1.84092 2.51116 + endloop + endfacet + facet normal 0.273923 0.158182 0.948654 + outer loop + vertex 1.66073 1.84092 2.51116 + vertex 1.65666 1.8409 2.51234 + vertex 1.66009 1.83657 2.51207 + endloop + endfacet + facet normal 0.27775 0.157413 0.947669 + outer loop + vertex 1.66073 1.84092 2.51116 + vertex 1.66009 1.83657 2.51207 + vertex 1.66343 1.83896 2.5107 + endloop + endfacet + facet normal 0.281136 0.15256 0.947464 + outer loop + vertex 1.66466 1.835 2.51097 + vertex 1.66343 1.83896 2.5107 + vertex 1.66009 1.83657 2.51207 + endloop + endfacet + facet normal 0.274838 0.158931 0.948264 + outer loop + vertex 1.65666 1.8409 2.51234 + vertex 1.65602 1.83652 2.51326 + vertex 1.66009 1.83657 2.51207 + endloop + endfacet + facet normal 0.275046 0.155158 0.948829 + outer loop + vertex 1.65722 1.83256 2.51356 + vertex 1.66009 1.83657 2.51207 + vertex 1.65602 1.83652 2.51326 + endloop + endfacet + facet normal 0.278933 0.156235 0.947516 + outer loop + vertex 1.65722 1.83256 2.51356 + vertex 1.65602 1.83652 2.51326 + vertex 1.65267 1.83413 2.51464 + endloop + endfacet + facet normal 0.277237 0.150303 0.948972 + outer loop + vertex 1.65431 1.82857 2.51504 + vertex 1.65722 1.83256 2.51356 + vertex 1.65267 1.83413 2.51464 + endloop + endfacet + facet normal 0.283632 0.152038 0.946804 + outer loop + vertex 1.65431 1.82857 2.51504 + vertex 1.65267 1.83413 2.51464 + vertex 1.64978 1.83021 2.51614 + endloop + endfacet + facet normal 0.282067 0.14686 0.948088 + outer loop + vertex 1.65095 1.82623 2.5164 + vertex 1.65431 1.82857 2.51504 + vertex 1.64978 1.83021 2.51614 + endloop + endfacet + facet normal 0.285925 0.147914 0.946767 + outer loop + vertex 1.64978 1.83021 2.51614 + vertex 1.64684 1.82634 2.51763 + vertex 1.65095 1.82623 2.5164 + endloop + endfacet + facet normal 0.285965 0.145926 0.947064 + outer loop + vertex 1.65095 1.82623 2.5164 + vertex 1.64684 1.82634 2.51763 + vertex 1.65031 1.82194 2.51726 + endloop + endfacet + facet normal 0.282967 0.146535 0.94787 + outer loop + vertex 1.65095 1.82623 2.5164 + vertex 1.65031 1.82194 2.51726 + vertex 1.65358 1.82421 2.51593 + endloop + endfacet + facet normal 0.282977 0.14652 0.947869 + outer loop + vertex 1.65477 1.82025 2.51619 + vertex 1.65358 1.82421 2.51593 + vertex 1.65031 1.82194 2.51726 + endloop + endfacet + facet normal 0.285754 0.145751 0.947154 + outer loop + vertex 1.64684 1.82634 2.51763 + vertex 1.64628 1.82178 2.5185 + vertex 1.65031 1.82194 2.51726 + endloop + endfacet + facet normal 0.285823 0.14488 0.947267 + outer loop + vertex 1.64796 1.81846 2.5185 + vertex 1.65031 1.82194 2.51726 + vertex 1.64628 1.82178 2.5185 + endloop + endfacet + facet normal 0.28601 0.144975 0.947196 + outer loop + vertex 1.64796 1.81846 2.5185 + vertex 1.64628 1.82178 2.5185 + vertex 1.64393 1.81827 2.51975 + endloop + endfacet + facet normal 0.286012 0.144942 0.9472 + outer loop + vertex 1.64393 1.81827 2.51975 + vertex 1.64744 1.81388 2.51936 + vertex 1.64796 1.81846 2.5185 + endloop + endfacet + facet normal 0.284154 0.145251 0.947712 + outer loop + vertex 1.64744 1.81388 2.51936 + vertex 1.65189 1.81637 2.51764 + vertex 1.64796 1.81846 2.5185 + endloop + endfacet + facet normal 0.284264 0.145053 0.94771 + outer loop + vertex 1.65137 1.81181 2.5185 + vertex 1.65189 1.81637 2.51764 + vertex 1.64744 1.81388 2.51936 + endloop + endfacet + facet normal 0.282875 0.142061 0.948578 + outer loop + vertex 1.64899 1.80829 2.51973 + vertex 1.65137 1.81181 2.5185 + vertex 1.64744 1.81388 2.51936 + endloop + endfacet + facet normal 0.285219 0.142657 0.947786 + outer loop + vertex 1.64899 1.80829 2.51973 + vertex 1.64744 1.81388 2.51936 + vertex 1.64456 1.80994 2.52082 + endloop + endfacet + facet normal 0.283305 0.136548 0.949259 + outer loop + vertex 1.64571 1.80596 2.52105 + vertex 1.64899 1.80829 2.51973 + vertex 1.64456 1.80994 2.52082 + endloop + endfacet + facet normal 0.285348 0.1371 0.948567 + outer loop + vertex 1.64456 1.80994 2.52082 + vertex 1.64169 1.80597 2.52226 + vertex 1.64571 1.80596 2.52105 + endloop + endfacet + facet normal 0.285812 0.124294 0.950191 + outer loop + vertex 1.64571 1.80596 2.52105 + vertex 1.64169 1.80597 2.52226 + vertex 1.64483 1.80161 2.52188 + endloop + endfacet + facet normal 0.280008 0.125766 0.951724 + outer loop + vertex 1.64571 1.80596 2.52105 + vertex 1.64483 1.80161 2.52188 + vertex 1.64826 1.80396 2.52056 + endloop + endfacet + facet normal 0.283334 0.120722 0.951393 + outer loop + vertex 1.64919 1.79995 2.52079 + vertex 1.64826 1.80396 2.52056 + vertex 1.64483 1.80161 2.52188 + endloop + endfacet + facet normal 0.278861 0.107078 0.954343 + outer loop + vertex 1.64483 1.80161 2.52188 + vertex 1.64599 1.79632 2.52214 + vertex 1.64919 1.79995 2.52079 + endloop + endfacet + facet normal 0.287697 0.10888 0.951512 + outer loop + vertex 1.64599 1.79632 2.52214 + vertex 1.64483 1.80161 2.52188 + vertex 1.64176 1.79753 2.52328 + endloop + endfacet + facet normal 0.284202 0.0941714 0.954128 + outer loop + vertex 1.64273 1.79262 2.52347 + vertex 1.64599 1.79632 2.52214 + vertex 1.64176 1.79753 2.52328 + endloop + endfacet + facet normal 0.29027 0.0952916 0.952188 + outer loop + vertex 1.64273 1.79262 2.52347 + vertex 1.64176 1.79753 2.52328 + vertex 1.63849 1.79384 2.52464 + endloop + endfacet + facet normal 0.288423 0.0876121 0.953486 + outer loop + vertex 1.63948 1.78847 2.52484 + vertex 1.64273 1.79262 2.52347 + vertex 1.63849 1.79384 2.52464 + endloop + endfacet + facet normal 0.292508 0.0883183 0.952176 + outer loop + vertex 1.63948 1.78847 2.52484 + vertex 1.63849 1.79384 2.52464 + vertex 1.63518 1.79013 2.526 + endloop + endfacet + facet normal 0.292034 0.086896 0.952452 + outer loop + vertex 1.63593 1.78604 2.52615 + vertex 1.63948 1.78847 2.52484 + vertex 1.63518 1.79013 2.526 + endloop + endfacet + facet normal 0.293223 0.0871004 0.952068 + outer loop + vertex 1.63518 1.79013 2.526 + vertex 1.63197 1.78598 2.52737 + vertex 1.63593 1.78604 2.52615 + endloop + endfacet + facet normal 0.292094 0.08806 0.952327 + outer loop + vertex 1.63098 1.79137 2.52718 + vertex 1.63197 1.78598 2.52737 + vertex 1.63518 1.79013 2.526 + endloop + endfacet + facet normal 0.291062 0.0878818 0.952659 + outer loop + vertex 1.63197 1.78598 2.52737 + vertex 1.63098 1.79137 2.52718 + vertex 1.62768 1.78765 2.52853 + endloop + endfacet + facet normal 0.291881 0.0903153 0.952181 + outer loop + vertex 1.62847 1.78355 2.52868 + vertex 1.63197 1.78598 2.52737 + vertex 1.62768 1.78765 2.52853 + endloop + endfacet + facet normal 0.28982 0.0899408 0.952846 + outer loop + vertex 1.62847 1.78355 2.52868 + vertex 1.62768 1.78765 2.52853 + vertex 1.62451 1.78351 2.52989 + endloop + endfacet + facet normal 0.289423 0.100686 0.951891 + outer loop + vertex 1.62451 1.78351 2.52989 + vertex 1.62752 1.77909 2.52944 + vertex 1.62847 1.78355 2.52868 + endloop + endfacet + facet normal 0.293511 0.0996178 0.950751 + outer loop + vertex 1.62752 1.77909 2.52944 + vertex 1.6309 1.78155 2.52813 + vertex 1.62847 1.78355 2.52868 + endloop + endfacet + facet normal 0.29002 0.10469 0.951277 + outer loop + vertex 1.6319 1.77761 2.52826 + vertex 1.6309 1.78155 2.52813 + vertex 1.62752 1.77909 2.52944 + endloop + endfacet + facet normal 0.292489 0.11341 0.94952 + outer loop + vertex 1.62905 1.77344 2.52964 + vertex 1.6319 1.77761 2.52826 + vertex 1.62752 1.77909 2.52944 + endloop + endfacet + facet normal 0.285686 0.111647 0.951797 + outer loop + vertex 1.62905 1.77344 2.52964 + vertex 1.62752 1.77909 2.52944 + vertex 1.62457 1.77501 2.5308 + endloop + endfacet + facet normal 0.287857 0.119036 0.950247 + outer loop + vertex 1.62567 1.77098 2.53097 + vertex 1.62905 1.77344 2.52964 + vertex 1.62457 1.77501 2.5308 + endloop + endfacet + facet normal 0.285205 0.118344 0.951132 + outer loop + vertex 1.62457 1.77501 2.5308 + vertex 1.62163 1.77094 2.53219 + vertex 1.62567 1.77098 2.53097 + endloop + endfacet + facet normal 0.285011 0.12264 0.950646 + outer loop + vertex 1.62567 1.77098 2.53097 + vertex 1.62163 1.77094 2.53219 + vertex 1.62476 1.76661 2.53181 + endloop + endfacet + facet normal 0.28661 0.122223 0.950219 + outer loop + vertex 1.62567 1.77098 2.53097 + vertex 1.62476 1.76661 2.53181 + vertex 1.6282 1.76899 2.53046 + endloop + endfacet + facet normal 0.286317 0.122665 0.95025 + outer loop + vertex 1.62911 1.76498 2.53071 + vertex 1.6282 1.76899 2.53046 + vertex 1.62476 1.76661 2.53181 + endloop + endfacet + facet normal 0.285884 0.121298 0.950556 + outer loop + vertex 1.62476 1.76661 2.53181 + vertex 1.62592 1.76137 2.53213 + vertex 1.62911 1.76498 2.53071 + endloop + endfacet + facet normal 0.286334 0.12087 0.950475 + outer loop + vertex 1.62911 1.76498 2.53071 + vertex 1.62592 1.76137 2.53213 + vertex 1.63013 1.76019 2.53101 + endloop + endfacet + facet normal 0.287841 0.12116 0.949983 + outer loop + vertex 1.63013 1.76019 2.53101 + vertex 1.63322 1.76371 2.52962 + vertex 1.62911 1.76498 2.53071 + endloop + endfacet + facet normal 0.288438 0.123503 0.9495 + outer loop + vertex 1.63322 1.76371 2.52962 + vertex 1.63225 1.76896 2.52923 + vertex 1.62911 1.76498 2.53071 + endloop + endfacet + facet normal 0.289689 0.123703 0.949093 + outer loop + vertex 1.63322 1.76371 2.52962 + vertex 1.63597 1.76671 2.5284 + vertex 1.63225 1.76896 2.52923 + endloop + endfacet + facet normal 0.289963 0.12421 0.948943 + outer loop + vertex 1.63597 1.76671 2.5284 + vertex 1.63692 1.7713 2.5275 + vertex 1.63225 1.76896 2.52923 + endloop + endfacet + facet normal 0.291102 0.121895 0.948895 + outer loop + vertex 1.63225 1.76896 2.52923 + vertex 1.63692 1.7713 2.5275 + vertex 1.63322 1.77356 2.52835 + endloop + endfacet + facet normal 0.290467 0.122062 0.949068 + outer loop + vertex 1.62905 1.77344 2.52964 + vertex 1.63225 1.76896 2.52923 + vertex 1.63322 1.77356 2.52835 + endloop + endfacet + facet normal 0.288882 0.120871 0.949704 + outer loop + vertex 1.6282 1.76899 2.53046 + vertex 1.63225 1.76896 2.52923 + vertex 1.62905 1.77344 2.52964 + endloop + endfacet + facet normal 0.289902 0.124225 0.94896 + outer loop + vertex 1.63692 1.7713 2.5275 + vertex 1.63597 1.76671 2.5284 + vertex 1.64012 1.7668 2.52711 + endloop + endfacet + facet normal 0.289952 0.123337 0.94906 + outer loop + vertex 1.63733 1.76265 2.52851 + vertex 1.64012 1.7668 2.52711 + vertex 1.63597 1.76671 2.5284 + endloop + endfacet + facet normal 0.290032 0.123363 0.949032 + outer loop + vertex 1.63733 1.76265 2.52851 + vertex 1.63597 1.76671 2.5284 + vertex 1.63322 1.76371 2.52962 + endloop + endfacet + facet normal 0.289418 0.120386 0.949602 + outer loop + vertex 1.63444 1.7586 2.5299 + vertex 1.63733 1.76265 2.52851 + vertex 1.63322 1.76371 2.52962 + endloop + endfacet + facet normal 0.289634 0.120216 0.949558 + outer loop + vertex 1.6384 1.75871 2.52868 + vertex 1.63733 1.76265 2.52851 + vertex 1.63444 1.7586 2.5299 + endloop + endfacet + facet normal 0.289929 0.115175 0.950093 + outer loop + vertex 1.63444 1.7586 2.5299 + vertex 1.63744 1.7543 2.52951 + vertex 1.6384 1.75871 2.52868 + endloop + endfacet + facet normal 0.287485 0.115831 0.950755 + outer loop + vertex 1.63744 1.7543 2.52951 + vertex 1.64093 1.75668 2.52816 + vertex 1.6384 1.75871 2.52868 + endloop + endfacet + facet normal 0.289086 0.118017 0.950001 + outer loop + vertex 1.64093 1.75668 2.52816 + vertex 1.64175 1.76114 2.52736 + vertex 1.6384 1.75871 2.52868 + endloop + endfacet + facet normal 0.281481 0.119791 0.95206 + outer loop + vertex 1.64175 1.76114 2.52736 + vertex 1.64093 1.75668 2.52816 + vertex 1.64502 1.75661 2.52696 + endloop + endfacet + facet normal 0.281591 0.113858 0.952755 + outer loop + vertex 1.64188 1.75251 2.52838 + vertex 1.64502 1.75661 2.52696 + vertex 1.64093 1.75668 2.52816 + endloop + endfacet + facet normal 0.278307 0.116592 0.95339 + outer loop + vertex 1.64653 1.75078 2.52723 + vertex 1.64502 1.75661 2.52696 + vertex 1.64188 1.75251 2.52838 + endloop + endfacet + facet normal 0.275914 0.109137 0.954966 + outer loop + vertex 1.64267 1.74769 2.5287 + vertex 1.64653 1.75078 2.52723 + vertex 1.64188 1.75251 2.52838 + endloop + endfacet + facet normal 0.285689 0.110531 0.951927 + outer loop + vertex 1.64267 1.74769 2.5287 + vertex 1.64188 1.75251 2.52838 + vertex 1.63854 1.74898 2.52979 + endloop + endfacet + facet normal 0.284644 0.10655 0.952694 + outer loop + vertex 1.63964 1.74372 2.53005 + vertex 1.64267 1.74769 2.5287 + vertex 1.63854 1.74898 2.52979 + endloop + endfacet + facet normal 0.289703 0.107527 0.951057 + outer loop + vertex 1.63964 1.74372 2.53005 + vertex 1.63854 1.74898 2.52979 + vertex 1.63529 1.74542 2.53118 + endloop + endfacet + facet normal 0.288878 0.105058 0.951584 + outer loop + vertex 1.63614 1.74136 2.53137 + vertex 1.63964 1.74372 2.53005 + vertex 1.63529 1.74542 2.53118 + endloop + endfacet + facet normal 0.292498 0.105761 0.9504 + outer loop + vertex 1.63529 1.74542 2.53118 + vertex 1.63208 1.74144 2.53262 + vertex 1.63614 1.74136 2.53137 + endloop + endfacet + facet normal 0.292515 0.10447 0.950537 + outer loop + vertex 1.63614 1.74136 2.53137 + vertex 1.63208 1.74144 2.53262 + vertex 1.63523 1.73686 2.53215 + endloop + endfacet + facet normal 0.29004 0.10509 0.951227 + outer loop + vertex 1.63614 1.74136 2.53137 + vertex 1.63523 1.73686 2.53215 + vertex 1.63867 1.73932 2.53083 + endloop + endfacet + facet normal 0.290113 0.104984 0.951217 + outer loop + vertex 1.63972 1.73522 2.53096 + vertex 1.63867 1.73932 2.53083 + vertex 1.63523 1.73686 2.53215 + endloop + endfacet + facet normal 0.289122 0.101796 0.951865 + outer loop + vertex 1.63523 1.73686 2.53215 + vertex 1.63672 1.73113 2.53231 + vertex 1.63972 1.73522 2.53096 + endloop + endfacet + facet normal 0.288769 0.10208 0.951941 + outer loop + vertex 1.63972 1.73522 2.53096 + vertex 1.63672 1.73113 2.53231 + vertex 1.64074 1.73111 2.53109 + endloop + endfacet + facet normal 0.276953 0.0992673 0.955742 + outer loop + vertex 1.64074 1.73111 2.53109 + vertex 1.64427 1.73356 2.52982 + vertex 1.63972 1.73522 2.53096 + endloop + endfacet + facet normal 0.278806 0.105125 0.954576 + outer loop + vertex 1.64427 1.73356 2.52982 + vertex 1.64285 1.7394 2.52959 + vertex 1.63972 1.73522 2.53096 + endloop + endfacet + facet normal 0.268919 0.102853 0.957655 + outer loop + vertex 1.64427 1.73356 2.52982 + vertex 1.64754 1.73771 2.52845 + vertex 1.64285 1.7394 2.52959 + endloop + endfacet + facet normal 0.27078 0.108819 0.956471 + outer loop + vertex 1.64754 1.73771 2.52845 + vertex 1.64675 1.74251 2.52813 + vertex 1.64285 1.7394 2.52959 + endloop + endfacet + facet normal 0.270293 0.10946 0.956535 + outer loop + vertex 1.64285 1.7394 2.52959 + vertex 1.64675 1.74251 2.52813 + vertex 1.64354 1.7439 2.52887 + endloop + endfacet + facet normal 0.282307 0.107105 0.953326 + outer loop + vertex 1.63964 1.74372 2.53005 + vertex 1.64285 1.7394 2.52959 + vertex 1.64354 1.7439 2.52887 + endloop + endfacet + facet normal 0.281388 0.106384 0.953679 + outer loop + vertex 1.63867 1.73932 2.53083 + vertex 1.64285 1.7394 2.52959 + vertex 1.63964 1.74372 2.53005 + endloop + endfacet + facet normal 0.270917 0.111089 0.956171 + outer loop + vertex 1.64675 1.74251 2.52813 + vertex 1.64586 1.74627 2.52794 + vertex 1.64354 1.7439 2.52887 + endloop + endfacet + facet normal 0.274826 0.107004 0.955521 + outer loop + vertex 1.64354 1.7439 2.52887 + vertex 1.64586 1.74627 2.52794 + vertex 1.64267 1.74769 2.5287 + endloop + endfacet + facet normal 0.266257 0.110064 0.957598 + outer loop + vertex 1.64675 1.74251 2.52813 + vertex 1.64974 1.74654 2.52683 + vertex 1.64586 1.74627 2.52794 + endloop + endfacet + facet normal 0.26615 0.111179 0.957498 + outer loop + vertex 1.64653 1.75078 2.52723 + vertex 1.64586 1.74627 2.52794 + vertex 1.64974 1.74654 2.52683 + endloop + endfacet + facet normal 0.266489 0.10819 0.957746 + outer loop + vertex 1.64754 1.73771 2.52845 + vertex 1.65089 1.74134 2.52711 + vertex 1.64675 1.74251 2.52813 + endloop + endfacet + facet normal 0.269445 0.105275 0.957244 + outer loop + vertex 1.65199 1.73607 2.52738 + vertex 1.65089 1.74134 2.52711 + vertex 1.64754 1.73771 2.52845 + endloop + endfacet + facet normal 0.269699 0.106063 0.957086 + outer loop + vertex 1.64844 1.73357 2.52866 + vertex 1.65199 1.73607 2.52738 + vertex 1.64754 1.73771 2.52845 + endloop + endfacet + facet normal 0.266014 0.105322 0.958198 + outer loop + vertex 1.64844 1.73357 2.52866 + vertex 1.64754 1.73771 2.52845 + vertex 1.64427 1.73356 2.52982 + endloop + endfacet + facet normal 0.266109 0.102248 0.958505 + outer loop + vertex 1.64427 1.73356 2.52982 + vertex 1.64733 1.72912 2.52944 + vertex 1.64844 1.73357 2.52866 + endloop + endfacet + facet normal 0.266807 0.102752 0.958257 + outer loop + vertex 1.64326 1.72905 2.53058 + vertex 1.64733 1.72912 2.52944 + vertex 1.64427 1.73356 2.52982 + endloop + endfacet + facet normal 0.276322 0.100217 0.955826 + outer loop + vertex 1.64326 1.72905 2.53058 + vertex 1.64427 1.73356 2.52982 + vertex 1.64074 1.73111 2.53109 + endloop + endfacet + facet normal 0.278787 0.103493 0.95476 + outer loop + vertex 1.64074 1.73111 2.53109 + vertex 1.63977 1.72668 2.53185 + vertex 1.64326 1.72905 2.53058 + endloop + endfacet + facet normal 0.278174 0.104437 0.954836 + outer loop + vertex 1.64416 1.72498 2.53076 + vertex 1.64326 1.72905 2.53058 + vertex 1.63977 1.72668 2.53185 + endloop + endfacet + facet normal 0.288797 0.100836 0.952065 + outer loop + vertex 1.64074 1.73111 2.53109 + vertex 1.63672 1.73113 2.53231 + vertex 1.63977 1.72668 2.53185 + endloop + endfacet + facet normal 0.290278 0.101907 0.951501 + outer loop + vertex 1.63672 1.73113 2.53231 + vertex 1.63581 1.72668 2.53306 + vertex 1.63977 1.72668 2.53185 + endloop + endfacet + facet normal 0.290382 0.0982277 0.951856 + outer loop + vertex 1.63669 1.72261 2.53321 + vertex 1.63977 1.72668 2.53185 + vertex 1.63581 1.72668 2.53306 + endloop + endfacet + facet normal 0.295519 0.0992731 0.950165 + outer loop + vertex 1.63669 1.72261 2.53321 + vertex 1.63581 1.72668 2.53306 + vertex 1.63237 1.7243 2.53438 + endloop + endfacet + facet normal 0.294208 0.0953674 0.950971 + outer loop + vertex 1.63345 1.71895 2.53458 + vertex 1.63669 1.72261 2.53321 + vertex 1.63237 1.7243 2.53438 + endloop + endfacet + facet normal 0.294923 0.0955028 0.950736 + outer loop + vertex 1.63345 1.71895 2.53458 + vertex 1.63237 1.7243 2.53438 + vertex 1.62922 1.72019 2.53577 + endloop + endfacet + facet normal 0.294308 0.0929734 0.951178 + outer loop + vertex 1.63017 1.71527 2.53596 + vertex 1.63345 1.71895 2.53458 + vertex 1.62922 1.72019 2.53577 + endloop + endfacet + facet normal 0.292186 0.0925888 0.951869 + outer loop + vertex 1.62922 1.72019 2.53577 + vertex 1.62594 1.71648 2.53714 + vertex 1.63017 1.71527 2.53596 + endloop + endfacet + facet normal 0.292058 0.0920546 0.95196 + outer loop + vertex 1.62594 1.71648 2.53714 + vertex 1.62698 1.71114 2.53734 + vertex 1.63017 1.71527 2.53596 + endloop + endfacet + facet normal 0.292149 0.0919774 0.95194 + outer loop + vertex 1.63017 1.71527 2.53596 + vertex 1.62698 1.71114 2.53734 + vertex 1.63095 1.71121 2.53611 + endloop + endfacet + facet normal 0.29344 0.0922079 0.95152 + outer loop + vertex 1.63095 1.71121 2.53611 + vertex 1.63448 1.71361 2.53479 + vertex 1.63017 1.71527 2.53596 + endloop + endfacet + facet normal 0.293312 0.092408 0.95154 + outer loop + vertex 1.63332 1.7092 2.53557 + vertex 1.63448 1.71361 2.53479 + vertex 1.63095 1.71121 2.53611 + endloop + endfacet + facet normal 0.293189 0.0922478 0.951594 + outer loop + vertex 1.63095 1.71121 2.53611 + vertex 1.62982 1.70678 2.53689 + vertex 1.63332 1.7092 2.53557 + endloop + endfacet + facet normal 0.292956 0.0926047 0.951631 + outer loop + vertex 1.63412 1.70513 2.53573 + vertex 1.63332 1.7092 2.53557 + vertex 1.62982 1.70678 2.53689 + endloop + endfacet + facet normal 0.292894 0.0924174 0.951668 + outer loop + vertex 1.62982 1.70678 2.53689 + vertex 1.63089 1.70142 2.53708 + vertex 1.63412 1.70513 2.53573 + endloop + endfacet + facet normal 0.293434 0.0919045 0.951551 + outer loop + vertex 1.63412 1.70513 2.53573 + vertex 1.63089 1.70142 2.53708 + vertex 1.63511 1.7002 2.5359 + endloop + endfacet + facet normal 0.289525 0.0911612 0.95282 + outer loop + vertex 1.63511 1.7002 2.5359 + vertex 1.63835 1.70395 2.53455 + vertex 1.63412 1.70513 2.53573 + endloop + endfacet + facet normal 0.289961 0.0930389 0.952505 + outer loop + vertex 1.63835 1.70395 2.53455 + vertex 1.63731 1.70927 2.53435 + vertex 1.63412 1.70513 2.53573 + endloop + endfacet + facet normal 0.282129 0.0916106 0.954993 + outer loop + vertex 1.63835 1.70395 2.53455 + vertex 1.6416 1.7077 2.53323 + vertex 1.63731 1.70927 2.53435 + endloop + endfacet + facet normal 0.283186 0.0949642 0.954352 + outer loop + vertex 1.6416 1.7077 2.53323 + vertex 1.64085 1.71169 2.53306 + vertex 1.63731 1.70927 2.53435 + endloop + endfacet + facet normal 0.283026 0.0952102 0.954375 + outer loop + vertex 1.63731 1.70927 2.53435 + vertex 1.64085 1.71169 2.53306 + vertex 1.63848 1.71366 2.53357 + endloop + endfacet + facet normal 0.290463 0.0928811 0.952368 + outer loop + vertex 1.63448 1.71361 2.53479 + vertex 1.63731 1.70927 2.53435 + vertex 1.63848 1.71366 2.53357 + endloop + endfacet + facet normal 0.290411 0.0942535 0.952249 + outer loop + vertex 1.63848 1.71366 2.53357 + vertex 1.63769 1.7177 2.53341 + vertex 1.63448 1.71361 2.53479 + endloop + endfacet + facet normal 0.291805 0.0930571 0.95194 + outer loop + vertex 1.63448 1.71361 2.53479 + vertex 1.63769 1.7177 2.53341 + vertex 1.63345 1.71895 2.53458 + endloop + endfacet + facet normal 0.28112 0.0925522 0.955199 + outer loop + vertex 1.63848 1.71366 2.53357 + vertex 1.642 1.71606 2.5323 + vertex 1.63769 1.7177 2.53341 + endloop + endfacet + facet normal 0.281067 0.0926338 0.955207 + outer loop + vertex 1.64085 1.71169 2.53306 + vertex 1.642 1.71606 2.5323 + vertex 1.63848 1.71366 2.53357 + endloop + endfacet + facet normal 0.272519 0.0952694 0.957422 + outer loop + vertex 1.642 1.71606 2.5323 + vertex 1.64085 1.71169 2.53306 + vertex 1.6448 1.71183 2.53192 + endloop + endfacet + facet normal 0.272644 0.0931187 0.957598 + outer loop + vertex 1.6416 1.7077 2.53323 + vertex 1.6448 1.71183 2.53192 + vertex 1.64085 1.71169 2.53306 + endloop + endfacet + facet normal 0.281902 0.0918236 0.955039 + outer loop + vertex 1.64255 1.70291 2.53341 + vertex 1.6416 1.7077 2.53323 + vertex 1.63835 1.70395 2.53455 + endloop + endfacet + facet normal 0.281325 0.0889925 0.955477 + outer loop + vertex 1.63946 1.6986 2.53473 + vertex 1.64255 1.70291 2.53341 + vertex 1.63835 1.70395 2.53455 + endloop + endfacet + facet normal 0.281212 0.0890813 0.955502 + outer loop + vertex 1.64364 1.69882 2.53348 + vertex 1.64255 1.70291 2.53341 + vertex 1.63946 1.6986 2.53473 + endloop + endfacet + facet normal 0.281543 0.0844795 0.955823 + outer loop + vertex 1.63946 1.6986 2.53473 + vertex 1.64236 1.69416 2.53426 + vertex 1.64364 1.69882 2.53348 + endloop + endfacet + facet normal 0.277469 0.0857786 0.956898 + outer loop + vertex 1.64236 1.69416 2.53426 + vertex 1.64723 1.69657 2.53264 + vertex 1.64364 1.69882 2.53348 + endloop + endfacet + facet normal 0.279015 0.0825473 0.956732 + outer loop + vertex 1.64594 1.69191 2.53341 + vertex 1.64723 1.69657 2.53264 + vertex 1.64236 1.69416 2.53426 + endloop + endfacet + facet normal 0.277825 0.0804584 0.957256 + outer loop + vertex 1.64292 1.68887 2.53455 + vertex 1.64594 1.69191 2.53341 + vertex 1.64236 1.69416 2.53426 + endloop + endfacet + facet normal 0.285861 0.0811772 0.954827 + outer loop + vertex 1.64292 1.68887 2.53455 + vertex 1.64236 1.69416 2.53426 + vertex 1.63893 1.69015 2.53563 + endloop + endfacet + facet normal 0.284406 0.0758887 0.955695 + outer loop + vertex 1.63958 1.68523 2.53583 + vertex 1.64292 1.68887 2.53455 + vertex 1.63893 1.69015 2.53563 + endloop + endfacet + facet normal 0.292645 0.0768719 0.953126 + outer loop + vertex 1.63893 1.69015 2.53563 + vertex 1.63554 1.68656 2.53696 + vertex 1.63958 1.68523 2.53583 + endloop + endfacet + facet normal 0.290889 0.0706652 0.954144 + outer loop + vertex 1.63554 1.68656 2.53696 + vertex 1.63616 1.68146 2.53715 + vertex 1.63958 1.68523 2.53583 + endloop + endfacet + facet normal 0.289937 0.071606 0.954363 + outer loop + vertex 1.63958 1.68523 2.53583 + vertex 1.63616 1.68146 2.53715 + vertex 1.64026 1.68024 2.536 + endloop + endfacet + facet normal 0.29693 0.0713272 0.952232 + outer loop + vertex 1.63616 1.68146 2.53715 + vertex 1.63554 1.68656 2.53696 + vertex 1.6321 1.68283 2.53831 + endloop + endfacet + facet normal 0.295289 0.0656875 0.953147 + outer loop + vertex 1.6326 1.67775 2.53851 + vertex 1.63616 1.68146 2.53715 + vertex 1.6321 1.68283 2.53831 + endloop + endfacet + facet normal 0.297036 0.0658353 0.952594 + outer loop + vertex 1.6326 1.67775 2.53851 + vertex 1.6321 1.68283 2.53831 + vertex 1.62857 1.67914 2.53967 + endloop + endfacet + facet normal 0.295936 0.0621525 0.953184 + outer loop + vertex 1.62902 1.67409 2.53986 + vertex 1.6326 1.67775 2.53851 + vertex 1.62857 1.67914 2.53967 + endloop + endfacet + facet normal 0.294716 0.0620569 0.953568 + outer loop + vertex 1.62902 1.67409 2.53986 + vertex 1.62857 1.67914 2.53967 + vertex 1.62499 1.67542 2.54102 + endloop + endfacet + facet normal 0.294149 0.0600681 0.95387 + outer loop + vertex 1.62552 1.67041 2.54117 + vertex 1.62902 1.67409 2.53986 + vertex 1.62499 1.67542 2.54102 + endloop + endfacet + facet normal 0.29157 0.0598197 0.954677 + outer loop + vertex 1.62499 1.67542 2.54102 + vertex 1.62141 1.67157 2.54235 + vertex 1.62552 1.67041 2.54117 + endloop + endfacet + facet normal 0.291545 0.0597179 0.954691 + outer loop + vertex 1.62141 1.67157 2.54235 + vertex 1.6221 1.66607 2.54249 + vertex 1.62552 1.67041 2.54117 + endloop + endfacet + facet normal 0.292072 0.0592614 0.954559 + outer loop + vertex 1.62552 1.67041 2.54117 + vertex 1.6221 1.66607 2.54249 + vertex 1.62615 1.66632 2.54123 + endloop + endfacet + facet normal 0.295075 0.0597049 0.953607 + outer loop + vertex 1.62615 1.66632 2.54123 + vertex 1.62974 1.66881 2.53996 + vertex 1.62552 1.67041 2.54117 + endloop + endfacet + facet normal 0.29505 0.0597429 0.953612 + outer loop + vertex 1.62853 1.66439 2.54062 + vertex 1.62974 1.66881 2.53996 + vertex 1.62615 1.66632 2.54123 + endloop + endfacet + facet normal 0.294589 0.0591164 0.953794 + outer loop + vertex 1.62615 1.66632 2.54123 + vertex 1.62492 1.66188 2.54189 + vertex 1.62853 1.66439 2.54062 + endloop + endfacet + facet normal 0.294338 0.059503 0.953847 + outer loop + vertex 1.62912 1.66038 2.54068 + vertex 1.62853 1.66439 2.54062 + vertex 1.62492 1.66188 2.54189 + endloop + endfacet + facet normal 0.29458 0.0602762 0.953724 + outer loop + vertex 1.62492 1.66188 2.54189 + vertex 1.6256 1.6567 2.542 + vertex 1.62912 1.66038 2.54068 + endloop + endfacet + facet normal 0.295716 0.0590897 0.953447 + outer loop + vertex 1.62912 1.66038 2.54068 + vertex 1.6256 1.6567 2.542 + vertex 1.62959 1.65544 2.54084 + endloop + endfacet + facet normal 0.295532 0.0590741 0.953505 + outer loop + vertex 1.62959 1.65544 2.54084 + vertex 1.63318 1.65927 2.53949 + vertex 1.62912 1.66038 2.54068 + endloop + endfacet + facet normal 0.295711 0.059843 0.953401 + outer loop + vertex 1.63318 1.65927 2.53949 + vertex 1.63255 1.66462 2.53935 + vertex 1.62912 1.66038 2.54068 + endloop + endfacet + facet normal 0.291677 0.059402 0.954671 + outer loop + vertex 1.63318 1.65927 2.53949 + vertex 1.63685 1.66298 2.53814 + vertex 1.63255 1.66462 2.53935 + endloop + endfacet + facet normal 0.292336 0.0613658 0.954345 + outer loop + vertex 1.63685 1.66298 2.53814 + vertex 1.63655 1.6677 2.53793 + vertex 1.63255 1.66462 2.53935 + endloop + endfacet + facet normal 0.292473 0.0611736 0.954315 + outer loop + vertex 1.63255 1.66462 2.53935 + vertex 1.63655 1.6677 2.53793 + vertex 1.63355 1.66903 2.53876 + endloop + endfacet + facet normal 0.296661 0.0600561 0.953093 + outer loop + vertex 1.62974 1.66881 2.53996 + vertex 1.63255 1.66462 2.53935 + vertex 1.63355 1.66903 2.53876 + endloop + endfacet + facet normal 0.296724 0.0591727 0.953128 + outer loop + vertex 1.63355 1.66903 2.53876 + vertex 1.63293 1.67283 2.53872 + vertex 1.62974 1.66881 2.53996 + endloop + endfacet + facet normal 0.296404 0.0594519 0.95321 + outer loop + vertex 1.62974 1.66881 2.53996 + vertex 1.63293 1.67283 2.53872 + vertex 1.62902 1.67409 2.53986 + endloop + endfacet + facet normal 0.294505 0.0588178 0.953838 + outer loop + vertex 1.63355 1.66903 2.53876 + vertex 1.63593 1.67141 2.53788 + vertex 1.63293 1.67283 2.53872 + endloop + endfacet + facet normal 0.294827 0.0595875 0.953691 + outer loop + vertex 1.63593 1.67141 2.53788 + vertex 1.6369 1.67594 2.5373 + vertex 1.63293 1.67283 2.53872 + endloop + endfacet + facet normal 0.293817 0.0609792 0.953915 + outer loop + vertex 1.63293 1.67283 2.53872 + vertex 1.6369 1.67594 2.5373 + vertex 1.6326 1.67775 2.53851 + endloop + endfacet + facet normal 0.292433 0.0610731 0.954334 + outer loop + vertex 1.63655 1.6677 2.53793 + vertex 1.63593 1.67141 2.53788 + vertex 1.63355 1.66903 2.53876 + endloop + endfacet + facet normal 0.286393 0.0600944 0.956226 + outer loop + vertex 1.63655 1.6677 2.53793 + vertex 1.6397 1.67173 2.53673 + vertex 1.63593 1.67141 2.53788 + endloop + endfacet + facet normal 0.290797 0.0603467 0.95488 + outer loop + vertex 1.63718 1.658 2.53836 + vertex 1.63685 1.66298 2.53814 + vertex 1.63318 1.65927 2.53949 + endloop + endfacet + facet normal 0.290163 0.0580452 0.955215 + outer loop + vertex 1.63353 1.6542 2.5397 + vertex 1.63718 1.658 2.53836 + vertex 1.63318 1.65927 2.53949 + endloop + endfacet + facet normal 0.289899 0.058322 0.955279 + outer loop + vertex 1.63749 1.65295 2.53857 + vertex 1.63718 1.658 2.53836 + vertex 1.63353 1.6542 2.5397 + endloop + endfacet + facet normal 0.28885 0.0545163 0.955821 + outer loop + vertex 1.63393 1.64908 2.53987 + vertex 1.63749 1.65295 2.53857 + vertex 1.63353 1.6542 2.5397 + endloop + endfacet + facet normal 0.296661 0.055046 0.953395 + outer loop + vertex 1.63393 1.64908 2.53987 + vertex 1.63353 1.6542 2.5397 + vertex 1.62995 1.65039 2.54103 + endloop + endfacet + facet normal 0.295839 0.0521815 0.953811 + outer loop + vertex 1.63047 1.64532 2.54114 + vertex 1.63393 1.64908 2.53987 + vertex 1.62995 1.65039 2.54103 + endloop + endfacet + facet normal 0.299535 0.0525361 0.952638 + outer loop + vertex 1.62995 1.65039 2.54103 + vertex 1.62646 1.64653 2.54234 + vertex 1.63047 1.64532 2.54114 + endloop + endfacet + facet normal 0.299126 0.0509664 0.952851 + outer loop + vertex 1.62646 1.64653 2.54234 + vertex 1.62718 1.6411 2.54241 + vertex 1.63047 1.64532 2.54114 + endloop + endfacet + facet normal 0.300725 0.049587 0.952421 + outer loop + vertex 1.63047 1.64532 2.54114 + vertex 1.62718 1.6411 2.54241 + vertex 1.63109 1.64118 2.54117 + endloop + endfacet + facet normal 0.295484 0.0488187 0.9541 + outer loop + vertex 1.63109 1.64118 2.54117 + vertex 1.63463 1.64366 2.53994 + vertex 1.63047 1.64532 2.54114 + endloop + endfacet + facet normal 0.296508 0.0472381 0.953861 + outer loop + vertex 1.63341 1.63919 2.54054 + vertex 1.63463 1.64366 2.53994 + vertex 1.63109 1.64118 2.54117 + endloop + endfacet + facet normal 0.297805 0.048903 0.953373 + outer loop + vertex 1.63109 1.64118 2.54117 + vertex 1.62987 1.63677 2.54177 + vertex 1.63341 1.63919 2.54054 + endloop + endfacet + facet normal 0.288226 0.0498325 0.956265 + outer loop + vertex 1.63341 1.63919 2.54054 + vertex 1.63736 1.63933 2.53935 + vertex 1.63463 1.64366 2.53994 + endloop + endfacet + facet normal 0.286271 0.0485109 0.95692 + outer loop + vertex 1.63463 1.64366 2.53994 + vertex 1.63736 1.63933 2.53935 + vertex 1.63861 1.64377 2.53875 + endloop + endfacet + facet normal 0.286161 0.051362 0.956804 + outer loop + vertex 1.63861 1.64377 2.53875 + vertex 1.638 1.64789 2.53871 + vertex 1.63463 1.64366 2.53994 + endloop + endfacet + facet normal 0.287253 0.0504133 0.956527 + outer loop + vertex 1.63463 1.64366 2.53994 + vertex 1.638 1.64789 2.53871 + vertex 1.63393 1.64908 2.53987 + endloop + endfacet + facet normal 0.279614 0.0504158 0.958788 + outer loop + vertex 1.63861 1.64377 2.53875 + vertex 1.64226 1.64627 2.53755 + vertex 1.638 1.64789 2.53871 + endloop + endfacet + facet normal 0.300779 0.0479627 0.952487 + outer loop + vertex 1.63109 1.64118 2.54117 + vertex 1.62718 1.6411 2.54241 + vertex 1.62987 1.63677 2.54177 + endloop + endfacet + facet normal 0.302044 0.0488143 0.952043 + outer loop + vertex 1.62718 1.6411 2.54241 + vertex 1.62587 1.6367 2.54305 + vertex 1.62987 1.63677 2.54177 + endloop + endfacet + facet normal 0.302107 0.0466174 0.952133 + outer loop + vertex 1.62646 1.63274 2.54305 + vertex 1.62987 1.63677 2.54177 + vertex 1.62587 1.6367 2.54305 + endloop + endfacet + facet normal 0.300821 0.0464273 0.95255 + outer loop + vertex 1.62646 1.63274 2.54305 + vertex 1.62587 1.6367 2.54305 + vertex 1.62198 1.63455 2.54438 + endloop + endfacet + facet normal 0.300546 0.045655 0.952674 + outer loop + vertex 1.62256 1.62929 2.54445 + vertex 1.62646 1.63274 2.54305 + vertex 1.62198 1.63455 2.54438 + endloop + endfacet + facet normal 0.297608 0.0453434 0.953611 + outer loop + vertex 1.62256 1.62929 2.54445 + vertex 1.62198 1.63455 2.54438 + vertex 1.61663 1.63112 2.54621 + endloop + endfacet + facet normal 0.297645 0.0454779 0.953593 + outer loop + vertex 1.619 1.62539 2.54575 + vertex 1.62256 1.62929 2.54445 + vertex 1.61663 1.63112 2.54621 + endloop + endfacet + facet normal 0.296894 0.0451464 0.953843 + outer loop + vertex 1.61663 1.63112 2.54621 + vertex 1.6151 1.62562 2.54695 + vertex 1.619 1.62539 2.54575 + endloop + endfacet + facet normal 0.296804 0.0429149 0.953974 + outer loop + vertex 1.6151 1.62562 2.54695 + vertex 1.61577 1.62153 2.54692 + vertex 1.619 1.62539 2.54575 + endloop + endfacet + facet normal 0.29891 0.040979 0.953401 + outer loop + vertex 1.619 1.62539 2.54575 + vertex 1.61577 1.62153 2.54692 + vertex 1.61975 1.62051 2.54572 + endloop + endfacet + facet normal 0.299904 0.0411336 0.953082 + outer loop + vertex 1.61975 1.62051 2.54572 + vertex 1.62338 1.62424 2.54442 + vertex 1.619 1.62539 2.54575 + endloop + endfacet + facet normal 0.302487 0.0383779 0.952381 + outer loop + vertex 1.62364 1.61931 2.54453 + vertex 1.62338 1.62424 2.54442 + vertex 1.61975 1.62051 2.54572 + endloop + endfacet + facet normal 0.302128 0.0370385 0.952548 + outer loop + vertex 1.6199 1.6156 2.54586 + vertex 1.62364 1.61931 2.54453 + vertex 1.61975 1.62051 2.54572 + endloop + endfacet + facet normal 0.300592 0.0370071 0.953035 + outer loop + vertex 1.61975 1.62051 2.54572 + vertex 1.61608 1.61679 2.54702 + vertex 1.6199 1.6156 2.54586 + endloop + endfacet + facet normal 0.300468 0.0365558 0.953091 + outer loop + vertex 1.61608 1.61679 2.54702 + vertex 1.61612 1.61186 2.5472 + vertex 1.6199 1.6156 2.54586 + endloop + endfacet + facet normal 0.302285 0.0345414 0.952592 + outer loop + vertex 1.6199 1.6156 2.54586 + vertex 1.61612 1.61186 2.5472 + vertex 1.6199 1.6106 2.54605 + endloop + endfacet + facet normal 0.303652 0.0345249 0.952157 + outer loop + vertex 1.6199 1.6106 2.54605 + vertex 1.62364 1.61434 2.54472 + vertex 1.6199 1.6156 2.54586 + endloop + endfacet + facet normal 0.303927 0.0342231 0.952081 + outer loop + vertex 1.62369 1.60931 2.54488 + vertex 1.62364 1.61434 2.54472 + vertex 1.6199 1.6106 2.54605 + endloop + endfacet + facet normal 0.304207 0.0351608 0.951957 + outer loop + vertex 1.62005 1.60553 2.54618 + vertex 1.62369 1.60931 2.54488 + vertex 1.6199 1.6106 2.54605 + endloop + endfacet + facet normal 0.302852 0.0351302 0.95239 + outer loop + vertex 1.6199 1.6106 2.54605 + vertex 1.61618 1.60682 2.54737 + vertex 1.62005 1.60553 2.54618 + endloop + endfacet + facet normal 0.303248 0.0364806 0.952213 + outer loop + vertex 1.61618 1.60682 2.54737 + vertex 1.61646 1.60167 2.54748 + vertex 1.62005 1.60553 2.54618 + endloop + endfacet + facet normal 0.30306 0.0366731 0.952266 + outer loop + vertex 1.62005 1.60553 2.54618 + vertex 1.61646 1.60167 2.54748 + vertex 1.62052 1.60047 2.54623 + endloop + endfacet + facet normal 0.304045 0.0367609 0.951948 + outer loop + vertex 1.62052 1.60047 2.54623 + vertex 1.62403 1.6042 2.54496 + vertex 1.62005 1.60553 2.54618 + endloop + endfacet + facet normal 0.303654 0.0371658 0.952057 + outer loop + vertex 1.62472 1.59883 2.54495 + vertex 1.62403 1.6042 2.54496 + vertex 1.62052 1.60047 2.54623 + endloop + endfacet + facet normal 0.303686 0.037258 0.952044 + outer loop + vertex 1.62112 1.59635 2.5462 + vertex 1.62472 1.59883 2.54495 + vertex 1.62052 1.60047 2.54623 + endloop + endfacet + facet normal 0.303401 0.037216 0.952136 + outer loop + vertex 1.62052 1.60047 2.54623 + vertex 1.6171 1.59612 2.54749 + vertex 1.62112 1.59635 2.5462 + endloop + endfacet + facet normal 0.303534 0.0350673 0.952175 + outer loop + vertex 1.62112 1.59635 2.5462 + vertex 1.6171 1.59612 2.54749 + vertex 1.61988 1.5919 2.54676 + endloop + endfacet + facet normal 0.303486 0.0350823 0.95219 + outer loop + vertex 1.62112 1.59635 2.5462 + vertex 1.61988 1.5919 2.54676 + vertex 1.62345 1.59439 2.54553 + endloop + endfacet + facet normal 0.305424 0.0320434 0.951677 + outer loop + vertex 1.62402 1.59037 2.54548 + vertex 1.62345 1.59439 2.54553 + vertex 1.61988 1.5919 2.54676 + endloop + endfacet + facet normal 0.304701 0.0298246 0.951981 + outer loop + vertex 1.61988 1.5919 2.54676 + vertex 1.62051 1.58673 2.54672 + vertex 1.62402 1.59037 2.54548 + endloop + endfacet + facet normal 0.307698 0.0266414 0.951111 + outer loop + vertex 1.62402 1.59037 2.54548 + vertex 1.62051 1.58673 2.54672 + vertex 1.62446 1.5855 2.54547 + endloop + endfacet + facet normal 0.306073 0.0264945 0.951639 + outer loop + vertex 1.62446 1.5855 2.54547 + vertex 1.62804 1.58927 2.54422 + vertex 1.62402 1.59037 2.54548 + endloop + endfacet + facet normal 0.307011 0.030387 0.951221 + outer loop + vertex 1.62804 1.58927 2.54422 + vertex 1.62739 1.5945 2.54426 + vertex 1.62402 1.59037 2.54548 + endloop + endfacet + facet normal 0.303526 0.0299464 0.952353 + outer loop + vertex 1.62804 1.58927 2.54422 + vertex 1.63153 1.59291 2.54299 + vertex 1.62739 1.5945 2.54426 + endloop + endfacet + facet normal 0.304587 0.0330634 0.95191 + outer loop + vertex 1.63153 1.59291 2.54299 + vertex 1.63095 1.59691 2.54304 + vertex 1.62739 1.5945 2.54426 + endloop + endfacet + facet normal 0.303127 0.035417 0.952292 + outer loop + vertex 1.62739 1.5945 2.54426 + vertex 1.63095 1.59691 2.54304 + vertex 1.62866 1.5989 2.54369 + endloop + endfacet + facet normal 0.303861 0.0351758 0.952067 + outer loop + vertex 1.62472 1.59883 2.54495 + vertex 1.62739 1.5945 2.54426 + vertex 1.62866 1.5989 2.54369 + endloop + endfacet + facet normal 0.303806 0.0372733 0.952004 + outer loop + vertex 1.62866 1.5989 2.54369 + vertex 1.62806 1.60299 2.54373 + vertex 1.62472 1.59883 2.54495 + endloop + endfacet + facet normal 0.302163 0.0370267 0.952537 + outer loop + vertex 1.62866 1.5989 2.54369 + vertex 1.6322 1.60131 2.54248 + vertex 1.62806 1.60299 2.54373 + endloop + endfacet + facet normal 0.302157 0.0370108 0.952539 + outer loop + vertex 1.6322 1.60131 2.54248 + vertex 1.63151 1.60666 2.54249 + vertex 1.62806 1.60299 2.54373 + endloop + endfacet + facet normal 0.302577 0.0365786 0.952423 + outer loop + vertex 1.62806 1.60299 2.54373 + vertex 1.63151 1.60666 2.54249 + vertex 1.62756 1.60801 2.54369 + endloop + endfacet + facet normal 0.30376 0.036694 0.952042 + outer loop + vertex 1.62806 1.60299 2.54373 + vertex 1.62756 1.60801 2.54369 + vertex 1.62403 1.6042 2.54496 + endloop + endfacet + facet normal 0.304705 0.0357309 0.951776 + outer loop + vertex 1.62403 1.6042 2.54496 + vertex 1.62756 1.60801 2.54369 + vertex 1.62369 1.60931 2.54488 + endloop + endfacet + facet normal 0.30451 0.0350682 0.951863 + outer loop + vertex 1.62756 1.60801 2.54369 + vertex 1.62736 1.61307 2.54357 + vertex 1.62369 1.60931 2.54488 + endloop + endfacet + facet normal 0.303401 0.0350337 0.952219 + outer loop + vertex 1.62756 1.60801 2.54369 + vertex 1.63114 1.61178 2.54241 + vertex 1.62736 1.61307 2.54357 + endloop + endfacet + facet normal 0.303486 0.035313 0.952181 + outer loop + vertex 1.63114 1.61178 2.54241 + vertex 1.63105 1.61682 2.54225 + vertex 1.62736 1.61307 2.54357 + endloop + endfacet + facet normal 0.304177 0.0345647 0.951988 + outer loop + vertex 1.62736 1.61307 2.54357 + vertex 1.63105 1.61682 2.54225 + vertex 1.62737 1.61807 2.54338 + endloop + endfacet + facet normal 0.305395 0.0345473 0.951599 + outer loop + vertex 1.62736 1.61307 2.54357 + vertex 1.62737 1.61807 2.54338 + vertex 1.62364 1.61434 2.54472 + endloop + endfacet + facet normal 0.304862 0.0351345 0.951748 + outer loop + vertex 1.62364 1.61434 2.54472 + vertex 1.62737 1.61807 2.54338 + vertex 1.62364 1.61931 2.54453 + endloop + endfacet + facet normal 0.305255 0.0364796 0.951572 + outer loop + vertex 1.62737 1.61807 2.54338 + vertex 1.62735 1.62301 2.5432 + vertex 1.62364 1.61931 2.54453 + endloop + endfacet + facet normal 0.303936 0.0364908 0.951993 + outer loop + vertex 1.62737 1.61807 2.54338 + vertex 1.63108 1.62179 2.54206 + vertex 1.62735 1.62301 2.5432 + endloop + endfacet + facet normal 0.304478 0.0383724 0.951746 + outer loop + vertex 1.63108 1.62179 2.54206 + vertex 1.631 1.62669 2.54189 + vertex 1.62735 1.62301 2.5432 + endloop + endfacet + facet normal 0.302711 0.0402963 0.95223 + outer loop + vertex 1.62735 1.62301 2.5432 + vertex 1.631 1.62669 2.54189 + vertex 1.62705 1.62791 2.54309 + endloop + endfacet + facet normal 0.30402 0.0403689 0.95181 + outer loop + vertex 1.62735 1.62301 2.5432 + vertex 1.62705 1.62791 2.54309 + vertex 1.62338 1.62424 2.54442 + endloop + endfacet + facet normal 0.301582 0.043045 0.952468 + outer loop + vertex 1.62338 1.62424 2.54442 + vertex 1.62705 1.62791 2.54309 + vertex 1.62256 1.62929 2.54445 + endloop + endfacet + facet normal 0.305062 0.0359813 0.951653 + outer loop + vertex 1.62345 1.59439 2.54553 + vertex 1.62739 1.5945 2.54426 + vertex 1.62472 1.59883 2.54495 + endloop + endfacet + facet normal 0.303152 0.0354486 0.952283 + outer loop + vertex 1.63095 1.59691 2.54304 + vertex 1.6322 1.60131 2.54248 + vertex 1.62866 1.5989 2.54369 + endloop + endfacet + facet normal 0.300067 0.0323998 0.953368 + outer loop + vertex 1.63153 1.59291 2.54299 + vertex 1.63484 1.597 2.54181 + vertex 1.63095 1.59691 2.54304 + endloop + endfacet + facet normal 0.30561 0.0277494 0.951752 + outer loop + vertex 1.63198 1.58804 2.54299 + vertex 1.63153 1.59291 2.54299 + vertex 1.62804 1.58927 2.54422 + endloop + endfacet + facet normal 0.304407 0.0233794 0.952255 + outer loop + vertex 1.62834 1.5843 2.54425 + vertex 1.63198 1.58804 2.54299 + vertex 1.62804 1.58927 2.54422 + endloop + endfacet + facet normal 0.305923 0.0217547 0.951808 + outer loop + vertex 1.63214 1.5831 2.54305 + vertex 1.63198 1.58804 2.54299 + vertex 1.62834 1.5843 2.54425 + endloop + endfacet + facet normal 0.304923 0.0182086 0.952203 + outer loop + vertex 1.62839 1.57933 2.54432 + vertex 1.63214 1.5831 2.54305 + vertex 1.62834 1.5843 2.54425 + endloop + endfacet + facet normal 0.310206 0.0182392 0.950494 + outer loop + vertex 1.62839 1.57933 2.54432 + vertex 1.62834 1.5843 2.54425 + vertex 1.62462 1.58055 2.54553 + endloop + endfacet + facet normal 0.309742 0.0166254 0.950675 + outer loop + vertex 1.62463 1.57558 2.54562 + vertex 1.62839 1.57933 2.54432 + vertex 1.62462 1.58055 2.54553 + endloop + endfacet + facet normal 0.311604 0.0166178 0.950067 + outer loop + vertex 1.62462 1.58055 2.54553 + vertex 1.62088 1.57682 2.54682 + vertex 1.62463 1.57558 2.54562 + endloop + endfacet + facet normal 0.311441 0.0160631 0.95013 + outer loop + vertex 1.62088 1.57682 2.54682 + vertex 1.62088 1.57184 2.54691 + vertex 1.62463 1.57558 2.54562 + endloop + endfacet + facet normal 0.313389 0.0139043 0.949523 + outer loop + vertex 1.62463 1.57558 2.54562 + vertex 1.62088 1.57184 2.54691 + vertex 1.62463 1.57059 2.54569 + endloop + endfacet + facet normal 0.311062 0.0139145 0.950288 + outer loop + vertex 1.62463 1.57059 2.54569 + vertex 1.62838 1.57435 2.54441 + vertex 1.62463 1.57558 2.54562 + endloop + endfacet + facet normal 0.312243 0.0126108 0.949919 + outer loop + vertex 1.6284 1.56935 2.54446 + vertex 1.62838 1.57435 2.54441 + vertex 1.62463 1.57059 2.54569 + endloop + endfacet + facet normal 0.311917 0.0114969 0.95004 + outer loop + vertex 1.62467 1.56559 2.54573 + vertex 1.6284 1.56935 2.54446 + vertex 1.62463 1.57059 2.54569 + endloop + endfacet + facet normal 0.314931 0.0115133 0.949045 + outer loop + vertex 1.62463 1.57059 2.54569 + vertex 1.62091 1.56685 2.54697 + vertex 1.62467 1.56559 2.54573 + endloop + endfacet + facet normal 0.314558 0.0102596 0.949183 + outer loop + vertex 1.62091 1.56685 2.54697 + vertex 1.62095 1.56185 2.54701 + vertex 1.62467 1.56559 2.54573 + endloop + endfacet + facet normal 0.315813 0.00887436 0.94878 + outer loop + vertex 1.62467 1.56559 2.54573 + vertex 1.62095 1.56185 2.54701 + vertex 1.62473 1.5606 2.54576 + endloop + endfacet + facet normal 0.312528 0.00884536 0.949867 + outer loop + vertex 1.62473 1.5606 2.54576 + vertex 1.62847 1.56436 2.5445 + vertex 1.62467 1.56559 2.54573 + endloop + endfacet + facet normal 0.31325 0.00804858 0.949637 + outer loop + vertex 1.62852 1.55936 2.54452 + vertex 1.62847 1.56436 2.5445 + vertex 1.62473 1.5606 2.54576 + endloop + endfacet + facet normal 0.313106 0.00755177 0.949688 + outer loop + vertex 1.62476 1.55561 2.54579 + vertex 1.62852 1.55936 2.54452 + vertex 1.62473 1.5606 2.54576 + endloop + endfacet + facet normal 0.316131 0.00756881 0.948685 + outer loop + vertex 1.62473 1.5606 2.54576 + vertex 1.621 1.55686 2.54704 + vertex 1.62476 1.55561 2.54579 + endloop + endfacet + facet normal 0.31612 0.00753128 0.948689 + outer loop + vertex 1.621 1.55686 2.54704 + vertex 1.62103 1.55187 2.54707 + vertex 1.62476 1.55561 2.54579 + endloop + endfacet + facet normal 0.315851 0.00782936 0.948776 + outer loop + vertex 1.62476 1.55561 2.54579 + vertex 1.62103 1.55187 2.54707 + vertex 1.62479 1.55062 2.54582 + endloop + endfacet + facet normal 0.313474 0.00782236 0.949565 + outer loop + vertex 1.62479 1.55062 2.54582 + vertex 1.62855 1.55437 2.54455 + vertex 1.62476 1.55561 2.54579 + endloop + endfacet + facet normal 0.313521 0.00777062 0.94955 + outer loop + vertex 1.62857 1.54938 2.54459 + vertex 1.62855 1.55437 2.54455 + vertex 1.62479 1.55062 2.54582 + endloop + endfacet + facet normal 0.313786 0.00867339 0.949454 + outer loop + vertex 1.62482 1.54563 2.54586 + vertex 1.62857 1.54938 2.54459 + vertex 1.62479 1.55062 2.54582 + endloop + endfacet + facet normal 0.315761 0.00867946 0.948799 + outer loop + vertex 1.62479 1.55062 2.54582 + vertex 1.62106 1.54688 2.5471 + vertex 1.62482 1.54563 2.54586 + endloop + endfacet + facet normal 0.315723 0.0085513 0.948813 + outer loop + vertex 1.62106 1.54688 2.5471 + vertex 1.62109 1.54189 2.54713 + vertex 1.62482 1.54563 2.54586 + endloop + endfacet + facet normal 0.316241 0.00797871 0.948645 + outer loop + vertex 1.62482 1.54563 2.54586 + vertex 1.62109 1.54189 2.54713 + vertex 1.62485 1.54065 2.54589 + endloop + endfacet + facet normal 0.315141 0.00797427 0.949011 + outer loop + vertex 1.62485 1.54065 2.54589 + vertex 1.62859 1.54439 2.54462 + vertex 1.62482 1.54563 2.54586 + endloop + endfacet + facet normal 0.316957 0.00595948 0.948421 + outer loop + vertex 1.62861 1.53941 2.54464 + vertex 1.62859 1.54439 2.54462 + vertex 1.62485 1.54065 2.54589 + endloop + endfacet + facet normal 0.316855 0.00561206 0.948457 + outer loop + vertex 1.62487 1.53566 2.54591 + vertex 1.62861 1.53941 2.54464 + vertex 1.62485 1.54065 2.54589 + endloop + endfacet + facet normal 0.317244 0.0056135 0.948327 + outer loop + vertex 1.62485 1.54065 2.54589 + vertex 1.62112 1.5369 2.54716 + vertex 1.62487 1.53566 2.54591 + endloop + endfacet + facet normal 0.316946 0.00460082 0.948433 + outer loop + vertex 1.62112 1.5369 2.54716 + vertex 1.62114 1.53191 2.54718 + vertex 1.62487 1.53566 2.54591 + endloop + endfacet + facet normal 0.318122 0.00329974 0.948044 + outer loop + vertex 1.62487 1.53566 2.54591 + vertex 1.62114 1.53191 2.54718 + vertex 1.62489 1.53068 2.54592 + endloop + endfacet + facet normal 0.318961 0.00330207 0.947762 + outer loop + vertex 1.62489 1.53068 2.54592 + vertex 1.62863 1.53443 2.54465 + vertex 1.62487 1.53566 2.54591 + endloop + endfacet + facet normal 0.320242 0.0018845 0.947334 + outer loop + vertex 1.62864 1.52945 2.54466 + vertex 1.62863 1.53443 2.54465 + vertex 1.62489 1.53068 2.54592 + endloop + endfacet + facet normal 0.320212 0.00178398 0.947344 + outer loop + vertex 1.6249 1.52568 2.54593 + vertex 1.62864 1.52945 2.54466 + vertex 1.62489 1.53068 2.54592 + endloop + endfacet + facet normal 0.319029 0.0017813 0.947743 + outer loop + vertex 1.62489 1.53068 2.54592 + vertex 1.62115 1.52691 2.54719 + vertex 1.6249 1.52568 2.54593 + endloop + endfacet + facet normal 0.319087 0.00197832 0.947723 + outer loop + vertex 1.62115 1.52691 2.54719 + vertex 1.62117 1.52192 2.54719 + vertex 1.6249 1.52568 2.54593 + endloop + endfacet + facet normal 0.319968 0.00100428 0.947428 + outer loop + vertex 1.6249 1.52568 2.54593 + vertex 1.62117 1.52192 2.54719 + vertex 1.62491 1.52069 2.54593 + endloop + endfacet + facet normal 0.320852 0.00100608 0.947129 + outer loop + vertex 1.62491 1.52069 2.54593 + vertex 1.62865 1.52446 2.54466 + vertex 1.6249 1.52568 2.54593 + endloop + endfacet + facet normal 0.321237 0.000581272 0.946999 + outer loop + vertex 1.62866 1.51947 2.54466 + vertex 1.62865 1.52446 2.54466 + vertex 1.62491 1.52069 2.54593 + endloop + endfacet + facet normal 0.321143 0.000262234 0.947031 + outer loop + vertex 1.62492 1.5157 2.54593 + vertex 1.62866 1.51947 2.54466 + vertex 1.62491 1.52069 2.54593 + endloop + endfacet + facet normal 0.320705 0.000261739 0.947179 + outer loop + vertex 1.62491 1.52069 2.54593 + vertex 1.62118 1.51693 2.5472 + vertex 1.62492 1.5157 2.54593 + endloop + endfacet + facet normal 0.320587 -0.000138499 0.947219 + outer loop + vertex 1.62118 1.51693 2.5472 + vertex 1.62119 1.51194 2.54719 + vertex 1.62492 1.5157 2.54593 + endloop + endfacet + facet normal 0.321071 -0.000673697 0.947055 + outer loop + vertex 1.62492 1.5157 2.54593 + vertex 1.62119 1.51194 2.54719 + vertex 1.62492 1.5107 2.54593 + endloop + endfacet + facet normal 0.320945 -0.000673651 0.947098 + outer loop + vertex 1.62492 1.5107 2.54593 + vertex 1.62866 1.51447 2.54466 + vertex 1.62492 1.5157 2.54593 + endloop + endfacet + facet normal 0.320721 -0.000425786 0.947174 + outer loop + vertex 1.62865 1.50948 2.54466 + vertex 1.62866 1.51447 2.54466 + vertex 1.62492 1.5107 2.54593 + endloop + endfacet + facet normal 0.32043 -0.00141099 0.947271 + outer loop + vertex 1.62491 1.50571 2.54592 + vertex 1.62865 1.50948 2.54466 + vertex 1.62492 1.5107 2.54593 + endloop + endfacet + facet normal 0.320766 -0.00141152 0.947157 + outer loop + vertex 1.62492 1.5107 2.54593 + vertex 1.62118 1.50695 2.54719 + vertex 1.62491 1.50571 2.54592 + endloop + endfacet + facet normal 0.320578 -0.00204646 0.94722 + outer loop + vertex 1.62118 1.50695 2.54719 + vertex 1.62117 1.50195 2.54718 + vertex 1.62491 1.50571 2.54592 + endloop + endfacet + facet normal 0.320353 -0.00179715 0.947297 + outer loop + vertex 1.62491 1.50571 2.54592 + vertex 1.62117 1.50195 2.54718 + vertex 1.6249 1.50072 2.54592 + endloop + endfacet + facet normal 0.319172 -0.00179499 0.947695 + outer loop + vertex 1.6249 1.50072 2.54592 + vertex 1.62865 1.50448 2.54466 + vertex 1.62491 1.50571 2.54592 + endloop + endfacet + facet normal 0.318189 -0.000703172 0.948027 + outer loop + vertex 1.62865 1.49949 2.54466 + vertex 1.62865 1.50448 2.54466 + vertex 1.6249 1.50072 2.54592 + endloop + endfacet + facet normal 0.317634 -0.00257784 0.94821 + outer loop + vertex 1.62488 1.49573 2.54591 + vertex 1.62865 1.49949 2.54466 + vertex 1.6249 1.50072 2.54592 + endloop + endfacet + facet normal 0.319836 -0.00258209 0.947469 + outer loop + vertex 1.6249 1.50072 2.54592 + vertex 1.62116 1.49696 2.54717 + vertex 1.62488 1.49573 2.54591 + endloop + endfacet + facet normal 0.319511 -0.00367209 0.947576 + outer loop + vertex 1.62116 1.49696 2.54717 + vertex 1.62114 1.49197 2.54716 + vertex 1.62488 1.49573 2.54591 + endloop + endfacet + facet normal 0.319509 -0.00367033 0.947576 + outer loop + vertex 1.62488 1.49573 2.54591 + vertex 1.62114 1.49197 2.54716 + vertex 1.62487 1.49074 2.54589 + endloop + endfacet + facet normal 0.316442 -0.00366315 0.948605 + outer loop + vertex 1.62487 1.49074 2.54589 + vertex 1.62864 1.49449 2.54465 + vertex 1.62488 1.49573 2.54591 + endloop + endfacet + facet normal 0.316305 -0.00351057 0.948651 + outer loop + vertex 1.62863 1.4895 2.54464 + vertex 1.62864 1.49449 2.54465 + vertex 1.62487 1.49074 2.54589 + endloop + endfacet + facet normal 0.31604 -0.00440233 0.948736 + outer loop + vertex 1.62485 1.48574 2.54588 + vertex 1.62863 1.4895 2.54464 + vertex 1.62487 1.49074 2.54589 + endloop + endfacet + facet normal 0.319049 -0.00441019 0.947728 + outer loop + vertex 1.62487 1.49074 2.54589 + vertex 1.62112 1.48698 2.54714 + vertex 1.62485 1.48574 2.54588 + endloop + endfacet + facet normal 0.318952 -0.00473538 0.947759 + outer loop + vertex 1.62112 1.48698 2.54714 + vertex 1.6211 1.48199 2.54712 + vertex 1.62485 1.48574 2.54588 + endloop + endfacet + facet normal 0.318602 -0.00434681 0.947878 + outer loop + vertex 1.62485 1.48574 2.54588 + vertex 1.6211 1.48199 2.54712 + vertex 1.62483 1.48075 2.54586 + endloop + endfacet + facet normal 0.315705 -0.00433979 0.948848 + outer loop + vertex 1.62483 1.48075 2.54586 + vertex 1.62861 1.4845 2.54462 + vertex 1.62485 1.48574 2.54588 + endloop + endfacet + facet normal 0.315717 -0.00435385 0.948843 + outer loop + vertex 1.62859 1.47951 2.5446 + vertex 1.62861 1.4845 2.54462 + vertex 1.62483 1.48075 2.54586 + endloop + endfacet + facet normal 0.315652 -0.00457076 0.948864 + outer loop + vertex 1.62481 1.47575 2.54584 + vertex 1.62859 1.47951 2.5446 + vertex 1.62483 1.48075 2.54586 + endloop + endfacet + facet normal 0.317807 -0.00457552 0.948144 + outer loop + vertex 1.62483 1.48075 2.54586 + vertex 1.62108 1.47699 2.5471 + vertex 1.62481 1.47575 2.54584 + endloop + endfacet + facet normal 0.317361 -0.00606447 0.948286 + outer loop + vertex 1.62108 1.47699 2.5471 + vertex 1.62105 1.47199 2.54708 + vertex 1.62481 1.47575 2.54584 + endloop + endfacet + facet normal 0.317387 -0.0060942 0.948276 + outer loop + vertex 1.62481 1.47575 2.54584 + vertex 1.62105 1.47199 2.54708 + vertex 1.62479 1.47075 2.54582 + endloop + endfacet + facet normal 0.315487 -0.00608811 0.948911 + outer loop + vertex 1.62479 1.47075 2.54582 + vertex 1.62857 1.47451 2.54458 + vertex 1.62481 1.47575 2.54584 + endloop + endfacet + facet normal 0.315839 -0.00648198 0.948791 + outer loop + vertex 1.62854 1.46951 2.54456 + vertex 1.62857 1.47451 2.54458 + vertex 1.62479 1.47075 2.54582 + endloop + endfacet + facet normal 0.315189 -0.00865149 0.94899 + outer loop + vertex 1.62475 1.46575 2.54578 + vertex 1.62854 1.46951 2.54456 + vertex 1.62479 1.47075 2.54582 + endloop + endfacet + facet normal 0.316996 -0.00866017 0.948387 + outer loop + vertex 1.62479 1.47075 2.54582 + vertex 1.62102 1.46699 2.54704 + vertex 1.62475 1.46575 2.54578 + endloop + endfacet + facet normal 0.31645 -0.0104708 0.948551 + outer loop + vertex 1.62102 1.46699 2.54704 + vertex 1.62098 1.46201 2.547 + vertex 1.62475 1.46575 2.54578 + endloop + endfacet + facet normal 0.316547 -0.0105801 0.948518 + outer loop + vertex 1.62475 1.46575 2.54578 + vertex 1.62098 1.46201 2.547 + vertex 1.62472 1.46077 2.54574 + endloop + endfacet + facet normal 0.315053 -0.0105735 0.949015 + outer loop + vertex 1.62472 1.46077 2.54574 + vertex 1.6285 1.46451 2.54453 + vertex 1.62475 1.46575 2.54578 + endloop + endfacet + facet normal 0.314373 -0.00980987 0.949249 + outer loop + vertex 1.62847 1.45953 2.54448 + vertex 1.6285 1.46451 2.54453 + vertex 1.62472 1.46077 2.54574 + endloop + endfacet + facet normal 0.3141 -0.0107143 0.949329 + outer loop + vertex 1.6247 1.4558 2.54569 + vertex 1.62847 1.45953 2.54448 + vertex 1.62472 1.46077 2.54574 + endloop + endfacet + facet normal 0.315457 -0.0107152 0.948879 + outer loop + vertex 1.62472 1.46077 2.54574 + vertex 1.62096 1.45705 2.54695 + vertex 1.6247 1.4558 2.54569 + endloop + endfacet + facet normal 0.315197 -0.0115722 0.948956 + outer loop + vertex 1.62096 1.45705 2.54695 + vertex 1.62094 1.45208 2.54689 + vertex 1.6247 1.4558 2.54569 + endloop + endfacet + facet normal 0.314396 -0.0106741 0.949232 + outer loop + vertex 1.6247 1.4558 2.54569 + vertex 1.62094 1.45208 2.54689 + vertex 1.6247 1.45084 2.54564 + endloop + endfacet + facet normal 0.312652 -0.0106805 0.949808 + outer loop + vertex 1.6247 1.45084 2.54564 + vertex 1.62846 1.45456 2.54444 + vertex 1.6247 1.4558 2.54569 + endloop + endfacet + facet normal 0.311889 -0.00982427 0.950068 + outer loop + vertex 1.62846 1.44959 2.54439 + vertex 1.62846 1.45456 2.54444 + vertex 1.6247 1.45084 2.54564 + endloop + endfacet + facet normal 0.310882 -0.013162 0.950357 + outer loop + vertex 1.62468 1.44585 2.54557 + vertex 1.62846 1.44959 2.54439 + vertex 1.6247 1.45084 2.54564 + endloop + endfacet + facet normal 0.313316 -0.0131602 0.949558 + outer loop + vertex 1.6247 1.45084 2.54564 + vertex 1.6209 1.44705 2.54684 + vertex 1.62468 1.44585 2.54557 + endloop + endfacet + facet normal 0.311919 -0.0179594 0.949939 + outer loop + vertex 1.6209 1.44705 2.54684 + vertex 1.62083 1.44199 2.54676 + vertex 1.62468 1.44585 2.54557 + endloop + endfacet + facet normal 0.312689 -0.018811 0.949669 + outer loop + vertex 1.62468 1.44585 2.54557 + vertex 1.62083 1.44199 2.54676 + vertex 1.62457 1.44086 2.54551 + endloop + endfacet + facet normal 0.309725 -0.0187593 0.950641 + outer loop + vertex 1.62457 1.44086 2.54551 + vertex 1.62842 1.4446 2.54433 + vertex 1.62468 1.44585 2.54557 + endloop + endfacet + facet normal 0.310692 -0.0198597 0.950303 + outer loop + vertex 1.62819 1.43946 2.5443 + vertex 1.62842 1.4446 2.54433 + vertex 1.62457 1.44086 2.54551 + endloop + endfacet + facet normal 0.309051 -0.0244744 0.95073 + outer loop + vertex 1.62426 1.43597 2.54548 + vertex 1.62819 1.43946 2.5443 + vertex 1.62457 1.44086 2.54551 + endloop + endfacet + facet normal 0.311778 -0.0246427 0.949835 + outer loop + vertex 1.62457 1.44086 2.54551 + vertex 1.62075 1.43703 2.54666 + vertex 1.62426 1.43597 2.54548 + endloop + endfacet + facet normal 0.310579 -0.0289197 0.950107 + outer loop + vertex 1.62075 1.43703 2.54666 + vertex 1.62075 1.43251 2.54653 + vertex 1.62426 1.43597 2.54548 + endloop + endfacet + facet normal 0.310227 -0.028524 0.950234 + outer loop + vertex 1.62426 1.43597 2.54548 + vertex 1.62075 1.43251 2.54653 + vertex 1.62361 1.43209 2.54558 + endloop + endfacet + facet normal 0.308921 -0.0282919 0.950667 + outer loop + vertex 1.62361 1.43209 2.54558 + vertex 1.62746 1.43371 2.54438 + vertex 1.62426 1.43597 2.54548 + endloop + endfacet + facet normal 0.309844 -0.0307712 0.950289 + outer loop + vertex 1.62361 1.43209 2.54558 + vertex 1.62417 1.42888 2.54529 + vertex 1.62746 1.43371 2.54438 + endloop + endfacet + facet normal 0.307624 -0.029113 0.951062 + outer loop + vertex 1.62746 1.43371 2.54438 + vertex 1.62417 1.42888 2.54529 + vertex 1.62794 1.42849 2.54406 + endloop + endfacet + facet normal 0.30325 -0.0295981 0.952451 + outer loop + vertex 1.62794 1.42849 2.54406 + vertex 1.63186 1.43291 2.54295 + vertex 1.62746 1.43371 2.54438 + endloop + endfacet + facet normal 0.303795 -0.0264375 0.95237 + outer loop + vertex 1.63186 1.43291 2.54295 + vertex 1.63196 1.43813 2.54306 + vertex 1.62746 1.43371 2.54438 + endloop + endfacet + facet normal 0.302572 -0.0250625 0.952797 + outer loop + vertex 1.62746 1.43371 2.54438 + vertex 1.63196 1.43813 2.54306 + vertex 1.62819 1.43946 2.5443 + endloop + endfacet + facet normal 0.303859 -0.0211181 0.952483 + outer loop + vertex 1.63196 1.43813 2.54306 + vertex 1.63217 1.44331 2.54311 + vertex 1.62819 1.43946 2.5443 + endloop + endfacet + facet normal 0.295167 -0.0208036 0.955219 + outer loop + vertex 1.63196 1.43813 2.54306 + vertex 1.63595 1.4421 2.54192 + vertex 1.63217 1.44331 2.54311 + endloop + endfacet + facet normal 0.296422 -0.0165796 0.954913 + outer loop + vertex 1.63595 1.4421 2.54192 + vertex 1.63601 1.44708 2.54199 + vertex 1.63217 1.44331 2.54311 + endloop + endfacet + facet normal 0.294586 -0.0145257 0.955515 + outer loop + vertex 1.63217 1.44331 2.54311 + vertex 1.63601 1.44708 2.54199 + vertex 1.63224 1.44833 2.54317 + endloop + endfacet + facet normal 0.303981 -0.014619 0.952566 + outer loop + vertex 1.63217 1.44331 2.54311 + vertex 1.63224 1.44833 2.54317 + vertex 1.62842 1.4446 2.54433 + endloop + endfacet + facet normal 0.303072 -0.0135948 0.952871 + outer loop + vertex 1.62842 1.4446 2.54433 + vertex 1.63224 1.44833 2.54317 + vertex 1.62846 1.44959 2.54439 + endloop + endfacet + facet normal 0.304234 -0.00980957 0.952547 + outer loop + vertex 1.63224 1.44833 2.54317 + vertex 1.63224 1.45329 2.54322 + vertex 1.62846 1.44959 2.54439 + endloop + endfacet + facet normal 0.294416 -0.00983428 0.955627 + outer loop + vertex 1.63224 1.44833 2.54317 + vertex 1.63602 1.45202 2.54204 + vertex 1.63224 1.45329 2.54322 + endloop + endfacet + facet normal 0.295029 -0.00785574 0.955456 + outer loop + vertex 1.63602 1.45202 2.54204 + vertex 1.63603 1.45698 2.54208 + vertex 1.63224 1.45329 2.54322 + endloop + endfacet + facet normal 0.295258 -0.00811365 0.955383 + outer loop + vertex 1.63224 1.45329 2.54322 + vertex 1.63603 1.45698 2.54208 + vertex 1.63225 1.45826 2.54326 + endloop + endfacet + facet normal 0.304811 -0.00810773 0.952378 + outer loop + vertex 1.63224 1.45329 2.54322 + vertex 1.63225 1.45826 2.54326 + vertex 1.62846 1.45456 2.54444 + endloop + endfacet + facet normal 0.306043 -0.00949591 0.95197 + outer loop + vertex 1.62846 1.45456 2.54444 + vertex 1.63225 1.45826 2.54326 + vertex 1.62847 1.45953 2.54448 + endloop + endfacet + facet normal 0.306347 -0.00850175 0.951882 + outer loop + vertex 1.63225 1.45826 2.54326 + vertex 1.63228 1.46325 2.54329 + vertex 1.62847 1.45953 2.54448 + endloop + endfacet + facet normal 0.296643 -0.00846252 0.954951 + outer loop + vertex 1.63225 1.45826 2.54326 + vertex 1.63606 1.46197 2.54211 + vertex 1.63228 1.46325 2.54329 + endloop + endfacet + facet normal 0.297025 -0.00724138 0.954842 + outer loop + vertex 1.63606 1.46197 2.54211 + vertex 1.63611 1.46697 2.54213 + vertex 1.63228 1.46325 2.54329 + endloop + endfacet + facet normal 0.298074 -0.0084273 0.954505 + outer loop + vertex 1.63228 1.46325 2.54329 + vertex 1.63611 1.46697 2.54213 + vertex 1.63232 1.46826 2.54332 + endloop + endfacet + facet normal 0.307878 -0.00848403 0.951388 + outer loop + vertex 1.63228 1.46325 2.54329 + vertex 1.63232 1.46826 2.54332 + vertex 1.6285 1.46451 2.54453 + endloop + endfacet + facet normal 0.308321 -0.00898309 0.95124 + outer loop + vertex 1.6285 1.46451 2.54453 + vertex 1.63232 1.46826 2.54332 + vertex 1.62854 1.46951 2.54456 + endloop + endfacet + facet normal 0.308937 -0.00695281 0.951057 + outer loop + vertex 1.63232 1.46826 2.54332 + vertex 1.63235 1.47326 2.54335 + vertex 1.62854 1.46951 2.54456 + endloop + endfacet + facet normal 0.298789 -0.00690359 0.954294 + outer loop + vertex 1.63232 1.46826 2.54332 + vertex 1.63614 1.47197 2.54215 + vertex 1.63235 1.47326 2.54335 + endloop + endfacet + facet normal 0.299212 -0.00554113 0.954171 + outer loop + vertex 1.63614 1.47197 2.54215 + vertex 1.63617 1.47697 2.54217 + vertex 1.63235 1.47326 2.54335 + endloop + endfacet + facet normal 0.298904 -0.00519277 0.954269 + outer loop + vertex 1.63235 1.47326 2.54335 + vertex 1.63617 1.47697 2.54217 + vertex 1.63238 1.47825 2.54337 + endloop + endfacet + facet normal 0.308862 -0.00523062 0.951093 + outer loop + vertex 1.63235 1.47326 2.54335 + vertex 1.63238 1.47825 2.54337 + vertex 1.62857 1.47451 2.54458 + endloop + endfacet + facet normal 0.308472 -0.00479193 0.951221 + outer loop + vertex 1.62857 1.47451 2.54458 + vertex 1.63238 1.47825 2.54337 + vertex 1.62859 1.47951 2.5446 + endloop + endfacet + facet normal 0.308459 -0.0048348 0.951225 + outer loop + vertex 1.63238 1.47825 2.54337 + vertex 1.6324 1.48325 2.54339 + vertex 1.62859 1.47951 2.5446 + endloop + endfacet + facet normal 0.298447 -0.00479985 0.954414 + outer loop + vertex 1.63238 1.47825 2.54337 + vertex 1.6362 1.48196 2.54219 + vertex 1.6324 1.48325 2.54339 + endloop + endfacet + facet normal 0.298258 -0.00540994 0.95447 + outer loop + vertex 1.6362 1.48196 2.54219 + vertex 1.63623 1.48694 2.54221 + vertex 1.6324 1.48325 2.54339 + endloop + endfacet + facet normal 0.297627 -0.0046923 0.954671 + outer loop + vertex 1.6324 1.48325 2.54339 + vertex 1.63623 1.48694 2.54221 + vertex 1.63242 1.48824 2.54341 + endloop + endfacet + facet normal 0.307897 -0.00472451 0.951408 + outer loop + vertex 1.6324 1.48325 2.54339 + vertex 1.63242 1.48824 2.54341 + vertex 1.62861 1.4845 2.54462 + endloop + endfacet + facet normal 0.307331 -0.00408601 0.951594 + outer loop + vertex 1.62861 1.4845 2.54462 + vertex 1.63242 1.48824 2.54341 + vertex 1.62863 1.4895 2.54464 + endloop + endfacet + facet normal 0.30755 -0.00335973 0.951526 + outer loop + vertex 1.63242 1.48824 2.54341 + vertex 1.63243 1.49323 2.54342 + vertex 1.62863 1.4895 2.54464 + endloop + endfacet + facet normal 0.296826 -0.0033404 0.954926 + outer loop + vertex 1.63242 1.48824 2.54341 + vertex 1.63625 1.49193 2.54223 + vertex 1.63243 1.49323 2.54342 + endloop + endfacet + facet normal 0.297382 -0.0015593 0.954757 + outer loop + vertex 1.63625 1.49193 2.54223 + vertex 1.63625 1.49692 2.54224 + vertex 1.63243 1.49323 2.54342 + endloop + endfacet + facet normal 0.29713 -0.00127334 0.954836 + outer loop + vertex 1.63243 1.49323 2.54342 + vertex 1.63625 1.49692 2.54224 + vertex 1.63243 1.49822 2.54343 + endloop + endfacet + facet normal 0.308342 -0.00127035 0.951275 + outer loop + vertex 1.63243 1.49323 2.54342 + vertex 1.63243 1.49822 2.54343 + vertex 1.62864 1.49449 2.54465 + endloop + endfacet + facet normal 0.308851 -0.00184249 0.951109 + outer loop + vertex 1.62864 1.49449 2.54465 + vertex 1.63243 1.49822 2.54343 + vertex 1.62865 1.49949 2.54466 + endloop + endfacet + facet normal 0.309612 0.000683891 0.950863 + outer loop + vertex 1.63243 1.49822 2.54343 + vertex 1.63243 1.50322 2.54342 + vertex 1.62865 1.49949 2.54466 + endloop + endfacet + facet normal 0.298401 0.000666383 0.95444 + outer loop + vertex 1.63243 1.49822 2.54343 + vertex 1.63624 1.50191 2.54223 + vertex 1.63243 1.50322 2.54342 + endloop + endfacet + facet normal 0.299007 0.00260307 0.954247 + outer loop + vertex 1.63624 1.50191 2.54223 + vertex 1.63621 1.5069 2.54223 + vertex 1.63243 1.50322 2.54342 + endloop + endfacet + facet normal 0.300243 0.00120571 0.953862 + outer loop + vertex 1.63243 1.50322 2.54342 + vertex 1.63621 1.5069 2.54223 + vertex 1.63242 1.50822 2.54342 + endloop + endfacet + facet normal 0.311425 0.00122261 0.95027 + outer loop + vertex 1.63243 1.50322 2.54342 + vertex 1.63242 1.50822 2.54342 + vertex 1.62865 1.50448 2.54466 + endloop + endfacet + facet normal 0.312922 -0.00045018 0.949779 + outer loop + vertex 1.62865 1.50448 2.54466 + vertex 1.63242 1.50822 2.54342 + vertex 1.62865 1.50948 2.54466 + endloop + endfacet + facet normal 0.313258 0.000662088 0.949668 + outer loop + vertex 1.63242 1.50822 2.54342 + vertex 1.63241 1.51321 2.54342 + vertex 1.62865 1.50948 2.54466 + endloop + endfacet + facet normal 0.302215 0.000654662 0.95324 + outer loop + vertex 1.63242 1.50822 2.54342 + vertex 1.6362 1.5119 2.54222 + vertex 1.63241 1.51321 2.54342 + endloop + endfacet + facet normal 0.302391 0.00121067 0.953183 + outer loop + vertex 1.6362 1.5119 2.54222 + vertex 1.63619 1.51689 2.54222 + vertex 1.63241 1.51321 2.54342 + endloop + endfacet + facet normal 0.303113 0.000393907 0.952955 + outer loop + vertex 1.63241 1.51321 2.54342 + vertex 1.63619 1.51689 2.54222 + vertex 1.63241 1.51821 2.54342 + endloop + endfacet + facet normal 0.314476 0.000399265 0.949265 + outer loop + vertex 1.63241 1.51321 2.54342 + vertex 1.63241 1.51821 2.54342 + vertex 1.62866 1.51447 2.54466 + endloop + endfacet + facet normal 0.314659 0.000195767 0.949205 + outer loop + vertex 1.62866 1.51447 2.54466 + vertex 1.63241 1.51821 2.54342 + vertex 1.62866 1.51947 2.54466 + endloop + endfacet + facet normal 0.314889 0.000957571 0.949128 + outer loop + vertex 1.63241 1.51821 2.54342 + vertex 1.6324 1.5232 2.54341 + vertex 1.62866 1.51947 2.54466 + endloop + endfacet + facet normal 0.303611 0.000946653 0.952796 + outer loop + vertex 1.63241 1.51821 2.54342 + vertex 1.63618 1.52187 2.54221 + vertex 1.6324 1.5232 2.54341 + endloop + endfacet + facet normal 0.303833 0.00164574 0.952724 + outer loop + vertex 1.63618 1.52187 2.54221 + vertex 1.63618 1.52686 2.54221 + vertex 1.6324 1.5232 2.54341 + endloop + endfacet + facet normal 0.304461 0.000933558 0.952524 + outer loop + vertex 1.6324 1.5232 2.54341 + vertex 1.63618 1.52686 2.54221 + vertex 1.6324 1.52819 2.54341 + endloop + endfacet + facet normal 0.315349 0.000950765 0.948975 + outer loop + vertex 1.6324 1.5232 2.54341 + vertex 1.6324 1.52819 2.54341 + vertex 1.62865 1.52446 2.54466 + endloop + endfacet + facet normal 0.315261 0.00104844 0.949004 + outer loop + vertex 1.62865 1.52446 2.54466 + vertex 1.6324 1.52819 2.54341 + vertex 1.62864 1.52945 2.54466 + endloop + endfacet + facet normal 0.315257 0.00103411 0.949006 + outer loop + vertex 1.6324 1.52819 2.54341 + vertex 1.63239 1.53317 2.54341 + vertex 1.62864 1.52945 2.54466 + endloop + endfacet + facet normal 0.3051 0.00101538 0.95232 + outer loop + vertex 1.6324 1.52819 2.54341 + vertex 1.63617 1.53185 2.5422 + vertex 1.63239 1.53317 2.54341 + endloop + endfacet + facet normal 0.30492 0.00044769 0.952378 + outer loop + vertex 1.63617 1.53185 2.5422 + vertex 1.63616 1.53684 2.5422 + vertex 1.63239 1.53317 2.54341 + endloop + endfacet + facet normal 0.304198 0.00126616 0.952608 + outer loop + vertex 1.63239 1.53317 2.54341 + vertex 1.63616 1.53684 2.5422 + vertex 1.63238 1.53816 2.54341 + endloop + endfacet + facet normal 0.31433 0.00128319 0.949313 + outer loop + vertex 1.63239 1.53317 2.54341 + vertex 1.63238 1.53816 2.54341 + vertex 1.62863 1.53443 2.54465 + endloop + endfacet + facet normal 0.312555 0.00326607 0.949894 + outer loop + vertex 1.62863 1.53443 2.54465 + vertex 1.63238 1.53816 2.54341 + vertex 1.62861 1.53941 2.54464 + endloop + endfacet + facet normal 0.31238 0.00268428 0.949953 + outer loop + vertex 1.63238 1.53816 2.54341 + vertex 1.63237 1.54314 2.54339 + vertex 1.62861 1.53941 2.54464 + endloop + endfacet + facet normal 0.301253 0.00267822 0.953541 + outer loop + vertex 1.63238 1.53816 2.54341 + vertex 1.63617 1.54184 2.5422 + vertex 1.63237 1.54314 2.54339 + endloop + endfacet + facet normal 0.300776 0.0011444 0.953694 + outer loop + vertex 1.63617 1.54184 2.5422 + vertex 1.63618 1.54684 2.54219 + vertex 1.63237 1.54314 2.54339 + endloop + endfacet + facet normal 0.297635 0.00469243 0.954668 + outer loop + vertex 1.63237 1.54314 2.54339 + vertex 1.63618 1.54684 2.54219 + vertex 1.63237 1.54813 2.54337 + endloop + endfacet + facet normal 0.309091 0.0046742 0.951021 + outer loop + vertex 1.63237 1.54314 2.54339 + vertex 1.63237 1.54813 2.54337 + vertex 1.62859 1.54439 2.54462 + endloop + endfacet + facet normal 0.306698 0.00735466 0.951779 + outer loop + vertex 1.62859 1.54439 2.54462 + vertex 1.63237 1.54813 2.54337 + vertex 1.62857 1.54938 2.54459 + endloop + endfacet + facet normal 0.306311 0.00605142 0.951912 + outer loop + vertex 1.63237 1.54813 2.54337 + vertex 1.63237 1.55313 2.54334 + vertex 1.62857 1.54938 2.54459 + endloop + endfacet + facet normal 0.294473 0.00607636 0.95564 + outer loop + vertex 1.63237 1.54813 2.54337 + vertex 1.6362 1.55186 2.54217 + vertex 1.63237 1.55313 2.54334 + endloop + endfacet + facet normal 0.294142 0.00497312 0.955749 + outer loop + vertex 1.6362 1.55186 2.54217 + vertex 1.63619 1.55689 2.54214 + vertex 1.63237 1.55313 2.54334 + endloop + endfacet + facet normal 0.29248 0.00681962 0.956247 + outer loop + vertex 1.63237 1.55313 2.54334 + vertex 1.63619 1.55689 2.54214 + vertex 1.63235 1.55814 2.54331 + endloop + endfacet + facet normal 0.304509 0.00684171 0.952485 + outer loop + vertex 1.63237 1.55313 2.54334 + vertex 1.63235 1.55814 2.54331 + vertex 1.62855 1.55437 2.54455 + endloop + endfacet + facet normal 0.304121 0.00727311 0.952606 + outer loop + vertex 1.62855 1.55437 2.54455 + vertex 1.63235 1.55814 2.54331 + vertex 1.62852 1.55936 2.54452 + endloop + endfacet + facet normal 0.304268 0.00778492 0.952555 + outer loop + vertex 1.63235 1.55814 2.54331 + vertex 1.6323 1.56314 2.54328 + vertex 1.62852 1.55936 2.54452 + endloop + endfacet + facet normal 0.291795 0.0076642 0.95645 + outer loop + vertex 1.63235 1.55814 2.54331 + vertex 1.63614 1.5619 2.54212 + vertex 1.6323 1.56314 2.54328 + endloop + endfacet + facet normal 0.292405 0.00974732 0.956245 + outer loop + vertex 1.63614 1.5619 2.54212 + vertex 1.63605 1.5669 2.5421 + vertex 1.6323 1.56314 2.54328 + endloop + endfacet + facet normal 0.292558 0.00958134 0.9562 + outer loop + vertex 1.6323 1.56314 2.54328 + vertex 1.63605 1.5669 2.5421 + vertex 1.63221 1.56814 2.54326 + endloop + endfacet + facet normal 0.304622 0.00975992 0.952423 + outer loop + vertex 1.6323 1.56314 2.54328 + vertex 1.63221 1.56814 2.54326 + vertex 1.62847 1.56436 2.5445 + endloop + endfacet + facet normal 0.304171 0.0102523 0.952562 + outer loop + vertex 1.62847 1.56436 2.5445 + vertex 1.63221 1.56814 2.54326 + vertex 1.6284 1.56935 2.54446 + endloop + endfacet + facet normal 0.304756 0.0123014 0.952351 + outer loop + vertex 1.63221 1.56814 2.54326 + vertex 1.63215 1.57313 2.54321 + vertex 1.6284 1.56935 2.54446 + endloop + endfacet + facet normal 0.294029 0.0122014 0.955719 + outer loop + vertex 1.63221 1.56814 2.54326 + vertex 1.63597 1.5719 2.54206 + vertex 1.63215 1.57313 2.54321 + endloop + endfacet + facet normal 0.294921 0.0152709 0.9554 + outer loop + vertex 1.63597 1.5719 2.54206 + vertex 1.63592 1.5769 2.54199 + vertex 1.63215 1.57313 2.54321 + endloop + endfacet + facet normal 0.295393 0.0147535 0.955262 + outer loop + vertex 1.63215 1.57313 2.54321 + vertex 1.63592 1.5769 2.54199 + vertex 1.63215 1.57812 2.54314 + endloop + endfacet + facet normal 0.305095 0.0147182 0.952208 + outer loop + vertex 1.63215 1.57313 2.54321 + vertex 1.63215 1.57812 2.54314 + vertex 1.62838 1.57435 2.54441 + endloop + endfacet + facet normal 0.304921 0.0149094 0.952261 + outer loop + vertex 1.62838 1.57435 2.54441 + vertex 1.63215 1.57812 2.54314 + vertex 1.62839 1.57933 2.54432 + endloop + endfacet + facet normal 0.297141 0.00307921 0.954829 + outer loop + vertex 1.63618 1.54684 2.54219 + vertex 1.6362 1.55186 2.54217 + vertex 1.63237 1.54813 2.54337 + endloop + endfacet + facet normal 0.296375 -0.026344 0.954708 + outer loop + vertex 1.63186 1.43291 2.54295 + vertex 1.63585 1.43707 2.54183 + vertex 1.63196 1.43813 2.54306 + endloop + endfacet + facet normal 0.297588 -0.0276175 0.954295 + outer loop + vertex 1.63576 1.43212 2.54171 + vertex 1.63585 1.43707 2.54183 + vertex 1.63186 1.43291 2.54295 + endloop + endfacet + facet normal 0.297216 -0.0295476 0.954353 + outer loop + vertex 1.63198 1.42787 2.54276 + vertex 1.63576 1.43212 2.54171 + vertex 1.63186 1.43291 2.54295 + endloop + endfacet + facet normal 0.302984 -0.0293391 0.952544 + outer loop + vertex 1.63198 1.42787 2.54276 + vertex 1.63186 1.43291 2.54295 + vertex 1.62794 1.42849 2.54406 + endloop + endfacet + facet normal 0.302816 -0.0304821 0.952562 + outer loop + vertex 1.62805 1.42348 2.54387 + vertex 1.63198 1.42787 2.54276 + vertex 1.62794 1.42849 2.54406 + endloop + endfacet + facet normal 0.306925 -0.0303399 0.95125 + outer loop + vertex 1.62805 1.42348 2.54387 + vertex 1.62794 1.42849 2.54406 + vertex 1.62414 1.42435 2.54516 + endloop + endfacet + facet normal 0.30659 -0.031934 0.951306 + outer loop + vertex 1.62402 1.41947 2.54503 + vertex 1.62805 1.42348 2.54387 + vertex 1.62414 1.42435 2.54516 + endloop + endfacet + facet normal 0.307981 -0.0319554 0.950856 + outer loop + vertex 1.62402 1.41947 2.54503 + vertex 1.62414 1.42435 2.54516 + vertex 1.6203 1.42066 2.54628 + endloop + endfacet + facet normal 0.307381 -0.033969 0.95098 + outer loop + vertex 1.62014 1.41577 2.54615 + vertex 1.62402 1.41947 2.54503 + vertex 1.6203 1.42066 2.54628 + endloop + endfacet + facet normal 0.306674 -0.033952 0.951209 + outer loop + vertex 1.6203 1.42066 2.54628 + vertex 1.61642 1.41704 2.5474 + vertex 1.62014 1.41577 2.54615 + endloop + endfacet + facet normal 0.305848 -0.0365193 0.95138 + outer loop + vertex 1.61642 1.41704 2.5474 + vertex 1.61631 1.41211 2.54725 + vertex 1.62014 1.41577 2.54615 + endloop + endfacet + facet normal 0.306136 -0.0368526 0.951274 + outer loop + vertex 1.62014 1.41577 2.54615 + vertex 1.61631 1.41211 2.54725 + vertex 1.62006 1.41087 2.54599 + endloop + endfacet + facet normal 0.306703 -0.036856 0.951092 + outer loop + vertex 1.62006 1.41087 2.54599 + vertex 1.62391 1.41455 2.54489 + vertex 1.62014 1.41577 2.54615 + endloop + endfacet + facet normal 0.306702 -0.0368549 0.951092 + outer loop + vertex 1.62381 1.40963 2.54473 + vertex 1.62391 1.41455 2.54489 + vertex 1.62006 1.41087 2.54599 + endloop + endfacet + facet normal 0.305999 -0.0391254 0.951227 + outer loop + vertex 1.61996 1.40592 2.54582 + vertex 1.62381 1.40963 2.54473 + vertex 1.62006 1.41087 2.54599 + endloop + endfacet + facet normal 0.304974 -0.0391162 0.951557 + outer loop + vertex 1.62006 1.41087 2.54599 + vertex 1.61619 1.40712 2.54708 + vertex 1.61996 1.40592 2.54582 + endloop + endfacet + facet normal 0.304377 -0.0410933 0.951665 + outer loop + vertex 1.61619 1.40712 2.54708 + vertex 1.61603 1.40206 2.54691 + vertex 1.61996 1.40592 2.54582 + endloop + endfacet + facet normal 0.303407 -0.0400053 0.952021 + outer loop + vertex 1.61996 1.40592 2.54582 + vertex 1.61603 1.40206 2.54691 + vertex 1.61976 1.4009 2.54567 + endloop + endfacet + facet normal 0.305101 -0.0400556 0.951477 + outer loop + vertex 1.61976 1.4009 2.54567 + vertex 1.62368 1.40466 2.54457 + vertex 1.61996 1.40592 2.54582 + endloop + endfacet + facet normal 0.304686 -0.0395778 0.95163 + outer loop + vertex 1.62336 1.3995 2.54446 + vertex 1.62368 1.40466 2.54457 + vertex 1.61976 1.4009 2.54567 + endloop + endfacet + facet normal 0.304307 -0.0406188 0.951708 + outer loop + vertex 1.61937 1.39596 2.54558 + vertex 1.62336 1.3995 2.54446 + vertex 1.61976 1.4009 2.54567 + endloop + endfacet + facet normal 0.302105 -0.0404584 0.952416 + outer loop + vertex 1.61976 1.4009 2.54567 + vertex 1.61587 1.39705 2.54674 + vertex 1.61937 1.39596 2.54558 + endloop + endfacet + facet normal 0.301565 -0.0423 0.952507 + outer loop + vertex 1.61587 1.39705 2.54674 + vertex 1.61581 1.39248 2.54656 + vertex 1.61937 1.39596 2.54558 + endloop + endfacet + facet normal 0.300768 -0.0414043 0.952798 + outer loop + vertex 1.61937 1.39596 2.54558 + vertex 1.61581 1.39248 2.54656 + vertex 1.61867 1.39205 2.54564 + endloop + endfacet + facet normal 0.303941 -0.0419897 0.951765 + outer loop + vertex 1.61867 1.39205 2.54564 + vertex 1.62255 1.39371 2.54447 + vertex 1.61937 1.39596 2.54558 + endloop + endfacet + facet normal 0.305057 -0.044944 0.951273 + outer loop + vertex 1.61867 1.39205 2.54564 + vertex 1.61921 1.38888 2.54531 + vertex 1.62255 1.39371 2.54447 + endloop + endfacet + facet normal 0.30385 -0.044035 0.951702 + outer loop + vertex 1.62255 1.39371 2.54447 + vertex 1.61921 1.38888 2.54531 + vertex 1.62297 1.38853 2.54409 + endloop + endfacet + facet normal 0.303379 -0.0440845 0.95185 + outer loop + vertex 1.62297 1.38853 2.54409 + vertex 1.62696 1.39291 2.54303 + vertex 1.62255 1.39371 2.54447 + endloop + endfacet + facet normal 0.303888 -0.0412375 0.951815 + outer loop + vertex 1.62696 1.39291 2.54303 + vertex 1.62713 1.39815 2.5432 + vertex 1.62255 1.39371 2.54447 + endloop + endfacet + facet normal 0.30353 -0.0408297 0.951947 + outer loop + vertex 1.62255 1.39371 2.54447 + vertex 1.62713 1.39815 2.5432 + vertex 1.62336 1.3995 2.54446 + endloop + endfacet + facet normal 0.304001 -0.0394285 0.951855 + outer loop + vertex 1.62713 1.39815 2.5432 + vertex 1.62742 1.40337 2.54332 + vertex 1.62336 1.3995 2.54446 + endloop + endfacet + facet normal 0.300251 -0.0392531 0.953052 + outer loop + vertex 1.62713 1.39815 2.5432 + vertex 1.63119 1.40212 2.54208 + vertex 1.62742 1.40337 2.54332 + endloop + endfacet + facet normal 0.300591 -0.0381602 0.952989 + outer loop + vertex 1.63119 1.40212 2.54208 + vertex 1.63132 1.40712 2.54224 + vertex 1.62742 1.40337 2.54332 + endloop + endfacet + facet normal 0.300531 -0.0380923 0.953011 + outer loop + vertex 1.62742 1.40337 2.54332 + vertex 1.63132 1.40712 2.54224 + vertex 1.62757 1.40838 2.54348 + endloop + endfacet + facet normal 0.304548 -0.0381786 0.951732 + outer loop + vertex 1.62742 1.40337 2.54332 + vertex 1.62757 1.40838 2.54348 + vertex 1.62368 1.40466 2.54457 + endloop + endfacet + facet normal 0.30492 -0.0386086 0.951595 + outer loop + vertex 1.62368 1.40466 2.54457 + vertex 1.62757 1.40838 2.54348 + vertex 1.62381 1.40963 2.54473 + endloop + endfacet + facet normal 0.305467 -0.0368619 0.951489 + outer loop + vertex 1.62757 1.40838 2.54348 + vertex 1.62771 1.41332 2.54362 + vertex 1.62381 1.40963 2.54473 + endloop + endfacet + facet normal 0.300978 -0.0367827 0.952921 + outer loop + vertex 1.62757 1.40838 2.54348 + vertex 1.63146 1.41206 2.54239 + vertex 1.62771 1.41332 2.54362 + endloop + endfacet + facet normal 0.301777 -0.034259 0.952763 + outer loop + vertex 1.63146 1.41206 2.54239 + vertex 1.63173 1.41708 2.54248 + vertex 1.62771 1.41332 2.54362 + endloop + endfacet + facet normal 0.301736 -0.0342103 0.952778 + outer loop + vertex 1.62771 1.41332 2.54362 + vertex 1.63173 1.41708 2.54248 + vertex 1.62794 1.41838 2.54373 + endloop + endfacet + facet normal 0.306198 -0.0343819 0.951347 + outer loop + vertex 1.62771 1.41332 2.54362 + vertex 1.62794 1.41838 2.54373 + vertex 1.62391 1.41455 2.54489 + endloop + endfacet + facet normal 0.305969 -0.0341165 0.95143 + outer loop + vertex 1.62391 1.41455 2.54489 + vertex 1.62794 1.41838 2.54373 + vertex 1.62402 1.41947 2.54503 + endloop + endfacet + facet normal 0.302384 -0.0321896 0.952642 + outer loop + vertex 1.63173 1.41708 2.54248 + vertex 1.63248 1.42273 2.54244 + vertex 1.62794 1.41838 2.54373 + endloop + endfacet + facet normal 0.302075 -0.0318339 0.952752 + outer loop + vertex 1.62794 1.41838 2.54373 + vertex 1.63248 1.42273 2.54244 + vertex 1.62805 1.42348 2.54387 + endloop + endfacet + facet normal 0.295402 -0.031243 0.954862 + outer loop + vertex 1.63248 1.42273 2.54244 + vertex 1.63173 1.41708 2.54248 + vertex 1.63568 1.42052 2.54137 + endloop + endfacet + facet normal 0.296275 -0.0298702 0.954635 + outer loop + vertex 1.63635 1.4244 2.54129 + vertex 1.63248 1.42273 2.54244 + vertex 1.63568 1.42052 2.54137 + endloop + endfacet + facet normal 0.293521 -0.0293761 0.955501 + outer loop + vertex 1.63919 1.42388 2.5404 + vertex 1.63635 1.4244 2.54129 + vertex 1.63568 1.42052 2.54137 + endloop + endfacet + facet normal 0.291877 -0.0274945 0.956061 + outer loop + vertex 1.63915 1.41936 2.54028 + vertex 1.63919 1.42388 2.5404 + vertex 1.63568 1.42052 2.54137 + endloop + endfacet + facet normal 0.29618 -0.0296232 0.954673 + outer loop + vertex 1.63635 1.4244 2.54129 + vertex 1.63577 1.42759 2.54157 + vertex 1.63248 1.42273 2.54244 + endloop + endfacet + facet normal 0.297512 -0.0306029 0.954228 + outer loop + vertex 1.63577 1.42759 2.54157 + vertex 1.63198 1.42787 2.54276 + vertex 1.63248 1.42273 2.54244 + endloop + endfacet + facet normal 0.295435 -0.0312847 0.95485 + outer loop + vertex 1.63568 1.42052 2.54137 + vertex 1.63173 1.41708 2.54248 + vertex 1.63534 1.41571 2.54132 + endloop + endfacet + facet normal 0.300138 -0.0411523 0.953008 + outer loop + vertex 1.62696 1.39291 2.54303 + vertex 1.63103 1.39705 2.54192 + vertex 1.62713 1.39815 2.5432 + endloop + endfacet + facet normal 0.300711 -0.0417709 0.9528 + outer loop + vertex 1.63086 1.39206 2.54176 + vertex 1.63103 1.39705 2.54192 + vertex 1.62696 1.39291 2.54303 + endloop + endfacet + facet normal 0.300208 -0.0441765 0.95285 + outer loop + vertex 1.62702 1.38787 2.54277 + vertex 1.63086 1.39206 2.54176 + vertex 1.62696 1.39291 2.54303 + endloop + endfacet + facet normal 0.303381 -0.0440864 0.951849 + outer loop + vertex 1.62702 1.38787 2.54277 + vertex 1.62696 1.39291 2.54303 + vertex 1.62297 1.38853 2.54409 + endloop + endfacet + facet normal 0.302828 -0.0475379 0.951859 + outer loop + vertex 1.62305 1.38357 2.54382 + vertex 1.62702 1.38787 2.54277 + vertex 1.62297 1.38853 2.54409 + endloop + endfacet + facet normal 0.302998 -0.0475325 0.951805 + outer loop + vertex 1.62305 1.38357 2.54382 + vertex 1.62297 1.38853 2.54409 + vertex 1.61915 1.38442 2.54511 + endloop + endfacet + facet normal 0.302252 -0.0510137 0.951862 + outer loop + vertex 1.619 1.3796 2.5449 + vertex 1.62305 1.38357 2.54382 + vertex 1.61915 1.38442 2.54511 + endloop + endfacet + facet normal 0.299612 -0.0509657 0.952699 + outer loop + vertex 1.619 1.3796 2.5449 + vertex 1.61915 1.38442 2.54511 + vertex 1.61528 1.38073 2.54613 + endloop + endfacet + facet normal 0.298661 -0.0542345 0.952817 + outer loop + vertex 1.61505 1.37587 2.54592 + vertex 1.619 1.3796 2.5449 + vertex 1.61528 1.38073 2.54613 + endloop + endfacet + facet normal 0.294608 -0.054098 0.954086 + outer loop + vertex 1.61528 1.38073 2.54613 + vertex 1.61127 1.37699 2.54715 + vertex 1.61505 1.37587 2.54592 + endloop + endfacet + facet normal 0.293677 -0.0573576 0.954182 + outer loop + vertex 1.61127 1.37699 2.54715 + vertex 1.61108 1.37205 2.54691 + vertex 1.61505 1.37587 2.54592 + endloop + endfacet + facet normal 0.294012 -0.0577382 0.954056 + outer loop + vertex 1.61505 1.37587 2.54592 + vertex 1.61108 1.37205 2.54691 + vertex 1.61481 1.37102 2.5457 + endloop + endfacet + facet normal 0.298171 -0.0578869 0.952756 + outer loop + vertex 1.61481 1.37102 2.5457 + vertex 1.61878 1.37468 2.54468 + vertex 1.61505 1.37587 2.54592 + endloop + endfacet + facet normal 0.299194 -0.0591068 0.95236 + outer loop + vertex 1.61839 1.36963 2.54449 + vertex 1.61878 1.37468 2.54468 + vertex 1.61481 1.37102 2.5457 + endloop + endfacet + facet normal 0.298475 -0.0610606 0.952462 + outer loop + vertex 1.61439 1.36629 2.54553 + vertex 1.61839 1.36963 2.54449 + vertex 1.61481 1.37102 2.5457 + endloop + endfacet + facet normal 0.293389 -0.060672 0.954066 + outer loop + vertex 1.61481 1.37102 2.5457 + vertex 1.61091 1.36726 2.54666 + vertex 1.61439 1.36629 2.54553 + endloop + endfacet + facet normal 0.2929 -0.0624647 0.954101 + outer loop + vertex 1.61091 1.36726 2.54666 + vertex 1.61079 1.36287 2.54641 + vertex 1.61439 1.36629 2.54553 + endloop + endfacet + facet normal 0.291876 -0.0612878 0.95449 + outer loop + vertex 1.61439 1.36629 2.54553 + vertex 1.61079 1.36287 2.54641 + vertex 1.61366 1.36252 2.54551 + endloop + endfacet + facet normal 0.298612 -0.0625918 0.95232 + outer loop + vertex 1.61366 1.36252 2.54551 + vertex 1.61756 1.36402 2.54439 + vertex 1.61439 1.36629 2.54553 + endloop + endfacet + facet normal 0.298827 -0.0632375 0.95221 + outer loop + vertex 1.61366 1.36252 2.54551 + vertex 1.61417 1.35932 2.54514 + vertex 1.61756 1.36402 2.54439 + endloop + endfacet + facet normal 0.299344 -0.0636407 0.952021 + outer loop + vertex 1.61756 1.36402 2.54439 + vertex 1.61417 1.35932 2.54514 + vertex 1.61801 1.35877 2.54389 + endloop + endfacet + facet normal 0.302325 -0.0632953 0.951101 + outer loop + vertex 1.61801 1.35877 2.54389 + vertex 1.62204 1.36311 2.5429 + vertex 1.61756 1.36402 2.54439 + endloop + endfacet + facet normal 0.302381 -0.0630206 0.951102 + outer loop + vertex 1.62204 1.36311 2.5429 + vertex 1.62216 1.36824 2.54321 + vertex 1.61756 1.36402 2.54439 + endloop + endfacet + facet normal 0.301738 -0.0622491 0.951356 + outer loop + vertex 1.61756 1.36402 2.54439 + vertex 1.62216 1.36824 2.54321 + vertex 1.61839 1.36963 2.54449 + endloop + endfacet + facet normal 0.302443 -0.0602653 0.95126 + outer loop + vertex 1.62216 1.36824 2.54321 + vertex 1.62252 1.37337 2.54341 + vertex 1.61839 1.36963 2.54449 + endloop + endfacet + facet normal 0.302374 -0.0602613 0.951283 + outer loop + vertex 1.62216 1.36824 2.54321 + vertex 1.62626 1.37205 2.54214 + vertex 1.62252 1.37337 2.54341 + endloop + endfacet + facet normal 0.303383 -0.057264 0.951147 + outer loop + vertex 1.62626 1.37205 2.54214 + vertex 1.62665 1.37712 2.54232 + vertex 1.62252 1.37337 2.54341 + endloop + endfacet + facet normal 0.30228 -0.0559266 0.951577 + outer loop + vertex 1.62252 1.37337 2.54341 + vertex 1.62665 1.37712 2.54232 + vertex 1.62288 1.37849 2.5436 + endloop + endfacet + facet normal 0.302726 -0.0559528 0.951434 + outer loop + vertex 1.62252 1.37337 2.54341 + vertex 1.62288 1.37849 2.5436 + vertex 1.61878 1.37468 2.54468 + endloop + endfacet + facet normal 0.301807 -0.0548621 0.951789 + outer loop + vertex 1.61878 1.37468 2.54468 + vertex 1.62288 1.37849 2.5436 + vertex 1.619 1.3796 2.5449 + endloop + endfacet + facet normal 0.303476 -0.0524686 0.951394 + outer loop + vertex 1.62665 1.37712 2.54232 + vertex 1.62747 1.38275 2.54237 + vertex 1.62288 1.37849 2.5436 + endloop + endfacet + facet normal 0.302697 -0.0515445 0.951692 + outer loop + vertex 1.62288 1.37849 2.5436 + vertex 1.62747 1.38275 2.54237 + vertex 1.62305 1.38357 2.54382 + endloop + endfacet + facet normal 0.300071 -0.0519848 0.952499 + outer loop + vertex 1.62747 1.38275 2.54237 + vertex 1.62665 1.37712 2.54232 + vertex 1.63064 1.3805 2.54125 + endloop + endfacet + facet normal 0.300988 -0.0505848 0.952285 + outer loop + vertex 1.63134 1.38434 2.54123 + vertex 1.62747 1.38275 2.54237 + vertex 1.63064 1.3805 2.54125 + endloop + endfacet + facet normal 0.294526 -0.0493855 0.954367 + outer loop + vertex 1.6342 1.38389 2.54033 + vertex 1.63134 1.38434 2.54123 + vertex 1.63064 1.3805 2.54125 + endloop + endfacet + facet normal 0.295656 -0.0506856 0.953949 + outer loop + vertex 1.63412 1.3794 2.54011 + vertex 1.6342 1.38389 2.54033 + vertex 1.63064 1.3805 2.54125 + endloop + endfacet + facet normal 0.294805 -0.0534847 0.954059 + outer loop + vertex 1.63023 1.3757 2.54111 + vertex 1.63412 1.3794 2.54011 + vertex 1.63064 1.3805 2.54125 + endloop + endfacet + facet normal 0.295364 -0.054129 0.95385 + outer loop + vertex 1.63391 1.37452 2.5399 + vertex 1.63412 1.3794 2.54011 + vertex 1.63023 1.3757 2.54111 + endloop + endfacet + facet normal 0.294255 -0.057742 0.953981 + outer loop + vertex 1.6299 1.37079 2.54091 + vertex 1.63391 1.37452 2.5399 + vertex 1.63023 1.3757 2.54111 + endloop + endfacet + facet normal 0.301337 -0.0581141 0.951745 + outer loop + vertex 1.63023 1.3757 2.54111 + vertex 1.62626 1.37205 2.54214 + vertex 1.6299 1.37079 2.54091 + endloop + endfacet + facet normal 0.300308 -0.0612074 0.951876 + outer loop + vertex 1.62626 1.37205 2.54214 + vertex 1.62599 1.36713 2.54191 + vertex 1.6299 1.37079 2.54091 + endloop + endfacet + facet normal 0.300422 -0.0613411 0.951832 + outer loop + vertex 1.6299 1.37079 2.54091 + vertex 1.62599 1.36713 2.54191 + vertex 1.62947 1.36595 2.54074 + endloop + endfacet + facet normal 0.293338 -0.0607825 0.954075 + outer loop + vertex 1.62947 1.36595 2.54074 + vertex 1.63355 1.36943 2.5397 + vertex 1.6299 1.37079 2.54091 + endloop + endfacet + facet normal 0.293228 -0.0606404 0.954117 + outer loop + vertex 1.63265 1.3637 2.53962 + vertex 1.63355 1.36943 2.5397 + vertex 1.62947 1.36595 2.54074 + endloop + endfacet + facet normal 0.292246 -0.0621298 0.954323 + outer loop + vertex 1.62873 1.3621 2.54071 + vertex 1.63265 1.3637 2.53962 + vertex 1.62947 1.36595 2.54074 + endloop + endfacet + facet normal 0.299879 -0.063568 0.951857 + outer loop + vertex 1.62947 1.36595 2.54074 + vertex 1.62588 1.36259 2.54164 + vertex 1.62873 1.3621 2.54071 + endloop + endfacet + facet normal 0.299964 -0.0630837 0.951862 + outer loop + vertex 1.62873 1.3621 2.54071 + vertex 1.62588 1.36259 2.54164 + vertex 1.6264 1.35939 2.54127 + endloop + endfacet + facet normal 0.297214 -0.06051 0.952892 + outer loop + vertex 1.62873 1.3621 2.54071 + vertex 1.6264 1.35939 2.54127 + vertex 1.62923 1.35892 2.54035 + endloop + endfacet + facet normal 0.297318 -0.059893 0.952898 + outer loop + vertex 1.62923 1.35892 2.54035 + vertex 1.6264 1.35939 2.54127 + vertex 1.62566 1.35555 2.54126 + endloop + endfacet + facet normal 0.29737 -0.0599531 0.952878 + outer loop + vertex 1.62911 1.35446 2.54011 + vertex 1.62923 1.35892 2.54035 + vertex 1.62566 1.35555 2.54126 + endloop + endfacet + facet normal 0.297103 -0.0608206 0.952906 + outer loop + vertex 1.62522 1.35076 2.54109 + vertex 1.62911 1.35446 2.54011 + vertex 1.62566 1.35555 2.54126 + endloop + endfacet + facet normal 0.30004 -0.0610602 0.951971 + outer loop + vertex 1.62566 1.35555 2.54126 + vertex 1.62163 1.35216 2.54231 + vertex 1.62522 1.35076 2.54109 + endloop + endfacet + facet normal 0.299159 -0.063433 0.952093 + outer loop + vertex 1.62163 1.35216 2.54231 + vertex 1.62121 1.34706 2.5421 + vertex 1.62522 1.35076 2.54109 + endloop + endfacet + facet normal 0.298759 -0.0629579 0.95225 + outer loop + vertex 1.62522 1.35076 2.54109 + vertex 1.62121 1.34706 2.5421 + vertex 1.62489 1.34589 2.54087 + endloop + endfacet + facet normal 0.296727 -0.0628511 0.952892 + outer loop + vertex 1.62489 1.34589 2.54087 + vertex 1.62889 1.34963 2.53987 + vertex 1.62522 1.35076 2.54109 + endloop + endfacet + facet normal 0.296865 -0.0630131 0.952838 + outer loop + vertex 1.62853 1.34459 2.53965 + vertex 1.62889 1.34963 2.53987 + vertex 1.62489 1.34589 2.54087 + endloop + endfacet + facet normal 0.296084 -0.0652764 0.952929 + outer loop + vertex 1.62448 1.34113 2.54067 + vertex 1.62853 1.34459 2.53965 + vertex 1.62489 1.34589 2.54087 + endloop + endfacet + facet normal 0.297039 -0.0653482 0.952626 + outer loop + vertex 1.62489 1.34589 2.54087 + vertex 1.62098 1.34219 2.54184 + vertex 1.62448 1.34113 2.54067 + endloop + endfacet + facet normal 0.296008 -0.0688408 0.952702 + outer loop + vertex 1.62098 1.34219 2.54184 + vertex 1.62089 1.33774 2.54154 + vertex 1.62448 1.34113 2.54067 + endloop + endfacet + facet normal 0.294681 -0.0673026 0.953223 + outer loop + vertex 1.62448 1.34113 2.54067 + vertex 1.62089 1.33774 2.54154 + vertex 1.62375 1.33733 2.54063 + endloop + endfacet + facet normal 0.295491 -0.067455 0.952961 + outer loop + vertex 1.62375 1.33733 2.54063 + vertex 1.62765 1.3389 2.53953 + vertex 1.62448 1.34113 2.54067 + endloop + endfacet + facet normal 0.296588 -0.0705816 0.952394 + outer loop + vertex 1.62375 1.33733 2.54063 + vertex 1.6242 1.33412 2.54025 + vertex 1.62765 1.3389 2.53953 + endloop + endfacet + facet normal 0.29543 -0.0696816 0.95282 + outer loop + vertex 1.62765 1.3389 2.53953 + vertex 1.6242 1.33412 2.54025 + vertex 1.62794 1.33366 2.53906 + endloop + endfacet + facet normal 0.293772 -0.0698208 0.953322 + outer loop + vertex 1.62794 1.33366 2.53906 + vertex 1.6321 1.33808 2.5381 + vertex 1.62765 1.3389 2.53953 + endloop + endfacet + facet normal 0.294442 -0.0662677 0.953369 + outer loop + vertex 1.6321 1.33808 2.5381 + vertex 1.63247 1.3434 2.53835 + vertex 1.62765 1.3389 2.53953 + endloop + endfacet + facet normal 0.293743 -0.0654458 0.953641 + outer loop + vertex 1.62765 1.3389 2.53953 + vertex 1.63247 1.3434 2.53835 + vertex 1.62853 1.34459 2.53965 + endloop + endfacet + facet normal 0.294251 -0.0637188 0.953602 + outer loop + vertex 1.63247 1.3434 2.53835 + vertex 1.63284 1.34868 2.53859 + vertex 1.62853 1.34459 2.53965 + endloop + endfacet + facet normal 0.287885 -0.0633716 0.955566 + outer loop + vertex 1.63247 1.3434 2.53835 + vertex 1.63732 1.34795 2.53719 + vertex 1.63284 1.34868 2.53859 + endloop + endfacet + facet normal 0.287963 -0.0629071 0.955573 + outer loop + vertex 1.63732 1.34795 2.53719 + vertex 1.63697 1.35302 2.53763 + vertex 1.63284 1.34868 2.53859 + endloop + endfacet + facet normal 0.287198 -0.0621165 0.955855 + outer loop + vertex 1.63284 1.34868 2.53859 + vertex 1.63697 1.35302 2.53763 + vertex 1.63294 1.35366 2.53889 + endloop + endfacet + facet normal 0.293629 -0.0621348 0.953898 + outer loop + vertex 1.63284 1.34868 2.53859 + vertex 1.63294 1.35366 2.53889 + vertex 1.62889 1.34963 2.53987 + endloop + endfacet + facet normal 0.292478 -0.0608727 0.954333 + outer loop + vertex 1.62889 1.34963 2.53987 + vertex 1.63294 1.35366 2.53889 + vertex 1.62911 1.35446 2.54011 + endloop + endfacet + facet normal 0.292432 -0.061095 0.954333 + outer loop + vertex 1.63294 1.35366 2.53889 + vertex 1.63299 1.35854 2.53918 + vertex 1.62911 1.35446 2.54011 + endloop + endfacet + facet normal 0.28517 -0.061158 0.956524 + outer loop + vertex 1.63294 1.35366 2.53889 + vertex 1.63702 1.35787 2.53794 + vertex 1.63299 1.35854 2.53918 + endloop + endfacet + facet normal 0.285008 -0.0621141 0.956511 + outer loop + vertex 1.63702 1.35787 2.53794 + vertex 1.63715 1.36289 2.53823 + vertex 1.63299 1.35854 2.53918 + endloop + endfacet + facet normal 0.284366 -0.0614485 0.956745 + outer loop + vertex 1.63299 1.35854 2.53918 + vertex 1.63715 1.36289 2.53823 + vertex 1.63265 1.3637 2.53962 + endloop + endfacet + facet normal 0.291166 -0.0608406 0.954736 + outer loop + vertex 1.63265 1.3637 2.53962 + vertex 1.62923 1.35892 2.54035 + vertex 1.63299 1.35854 2.53918 + endloop + endfacet + facet normal 0.284561 -0.0603796 0.956755 + outer loop + vertex 1.63715 1.36289 2.53823 + vertex 1.63754 1.36823 2.53845 + vertex 1.63265 1.3637 2.53962 + endloop + endfacet + facet normal 0.277656 -0.0599665 0.958807 + outer loop + vertex 1.63715 1.36289 2.53823 + vertex 1.64155 1.3671 2.53722 + vertex 1.63754 1.36823 2.53845 + endloop + endfacet + facet normal 0.27821 -0.0579641 0.95877 + outer loop + vertex 1.64155 1.3671 2.53722 + vertex 1.64244 1.37283 2.5373 + vertex 1.63754 1.36823 2.53845 + endloop + endfacet + facet normal 0.27718 -0.0567756 0.959139 + outer loop + vertex 1.63754 1.36823 2.53845 + vertex 1.64244 1.37283 2.5373 + vertex 1.6379 1.37355 2.53866 + endloop + endfacet + facet normal 0.28412 -0.0571613 0.957083 + outer loop + vertex 1.63754 1.36823 2.53845 + vertex 1.6379 1.37355 2.53866 + vertex 1.63355 1.36943 2.5397 + endloop + endfacet + facet normal 0.284219 -0.0572748 0.957047 + outer loop + vertex 1.63355 1.36943 2.5397 + vertex 1.6379 1.37355 2.53866 + vertex 1.63391 1.37452 2.5399 + endloop + endfacet + facet normal 0.285073 -0.0537372 0.956998 + outer loop + vertex 1.6379 1.37355 2.53866 + vertex 1.63798 1.37857 2.53892 + vertex 1.63391 1.37452 2.5399 + endloop + endfacet + facet normal 0.278186 -0.0537245 0.959024 + outer loop + vertex 1.6379 1.37355 2.53866 + vertex 1.64205 1.37794 2.5377 + vertex 1.63798 1.37857 2.53892 + endloop + endfacet + facet normal 0.278734 -0.0502619 0.959052 + outer loop + vertex 1.64205 1.37794 2.5377 + vertex 1.64205 1.38286 2.53796 + vertex 1.63798 1.37857 2.53892 + endloop + endfacet + facet normal 0.279552 -0.0511025 0.95877 + outer loop + vertex 1.63798 1.37857 2.53892 + vertex 1.64205 1.38286 2.53796 + vertex 1.63799 1.38351 2.53918 + endloop + endfacet + facet normal 0.285759 -0.0510215 0.956942 + outer loop + vertex 1.63798 1.37857 2.53892 + vertex 1.63799 1.38351 2.53918 + vertex 1.63412 1.3794 2.54011 + endloop + endfacet + facet normal 0.288488 -0.0501229 0.956171 + outer loop + vertex 1.64205 1.37794 2.5377 + vertex 1.64592 1.38219 2.53676 + vertex 1.64205 1.38286 2.53796 + endloop + endfacet + facet normal 0.28481 -0.0464894 0.957456 + outer loop + vertex 1.64584 1.37772 2.53656 + vertex 1.64592 1.38219 2.53676 + vertex 1.64205 1.37794 2.5377 + endloop + endfacet + facet normal 0.284393 -0.0526105 0.957263 + outer loop + vertex 1.64584 1.37772 2.53656 + vertex 1.64205 1.37794 2.5377 + vertex 1.64244 1.37283 2.5373 + endloop + endfacet + facet normal 0.27774 -0.0532701 0.959178 + outer loop + vertex 1.64244 1.37283 2.5373 + vertex 1.64205 1.37794 2.5377 + vertex 1.6379 1.37355 2.53866 + endloop + endfacet + facet normal 0.278233 -0.0620501 0.958507 + outer loop + vertex 1.63702 1.35787 2.53794 + vertex 1.64114 1.362 2.53701 + vertex 1.63715 1.36289 2.53823 + endloop + endfacet + facet normal 0.279097 -0.0629832 0.958195 + outer loop + vertex 1.64089 1.35717 2.53677 + vertex 1.64114 1.362 2.53701 + vertex 1.63702 1.35787 2.53794 + endloop + endfacet + facet normal 0.27906 -0.0631835 0.958193 + outer loop + vertex 1.63697 1.35302 2.53763 + vertex 1.64089 1.35717 2.53677 + vertex 1.63702 1.35787 2.53794 + endloop + endfacet + facet normal 0.287035 -0.0631177 0.955838 + outer loop + vertex 1.63697 1.35302 2.53763 + vertex 1.63702 1.35787 2.53794 + vertex 1.63294 1.35366 2.53889 + endloop + endfacet + facet normal 0.280628 -0.0636008 0.957707 + outer loop + vertex 1.64077 1.35277 2.53651 + vertex 1.63697 1.35302 2.53763 + vertex 1.63732 1.34795 2.53719 + endloop + endfacet + facet normal 0.28023 -0.0632965 0.957844 + outer loop + vertex 1.64127 1.34966 2.53615 + vertex 1.64077 1.35277 2.53651 + vertex 1.63732 1.34795 2.53719 + endloop + endfacet + facet normal 0.280378 -0.0636824 0.957775 + outer loop + vertex 1.64127 1.34966 2.53615 + vertex 1.63732 1.34795 2.53719 + vertex 1.6405 1.34578 2.53612 + endloop + endfacet + facet normal 0.277737 -0.0631649 0.958578 + outer loop + vertex 1.64413 1.34919 2.53529 + vertex 1.64127 1.34966 2.53615 + vertex 1.6405 1.34578 2.53612 + endloop + endfacet + facet normal 0.278258 -0.0637656 0.958387 + outer loop + vertex 1.64397 1.3446 2.53503 + vertex 1.64413 1.34919 2.53529 + vertex 1.6405 1.34578 2.53612 + endloop + endfacet + facet normal 0.280449 -0.0635724 0.957761 + outer loop + vertex 1.63732 1.34795 2.53719 + vertex 1.63641 1.34225 2.53708 + vertex 1.6405 1.34578 2.53612 + endloop + endfacet + facet normal 0.282118 -0.0656775 0.957129 + outer loop + vertex 1.6405 1.34578 2.53612 + vertex 1.63641 1.34225 2.53708 + vertex 1.63998 1.34094 2.53594 + endloop + endfacet + facet normal 0.289227 -0.0649286 0.955056 + outer loop + vertex 1.63641 1.34225 2.53708 + vertex 1.63732 1.34795 2.53719 + vertex 1.63247 1.3434 2.53835 + endloop + endfacet + facet normal 0.28893 -0.0659641 0.955075 + outer loop + vertex 1.6321 1.33808 2.5381 + vertex 1.63641 1.34225 2.53708 + vertex 1.63247 1.3434 2.53835 + endloop + endfacet + facet normal 0.290396 -0.0676153 0.954515 + outer loop + vertex 1.636 1.33723 2.53685 + vertex 1.63641 1.34225 2.53708 + vertex 1.6321 1.33808 2.5381 + endloop + endfacet + facet normal 0.289712 -0.0707412 0.954496 + outer loop + vertex 1.63204 1.33303 2.53774 + vertex 1.636 1.33723 2.53685 + vertex 1.6321 1.33808 2.5381 + endloop + endfacet + facet normal 0.294629 -0.0706996 0.952993 + outer loop + vertex 1.63204 1.33303 2.53774 + vertex 1.6321 1.33808 2.5381 + vertex 1.62794 1.33366 2.53906 + endloop + endfacet + facet normal 0.29368 -0.076509 0.952837 + outer loop + vertex 1.62777 1.32848 2.53869 + vertex 1.63204 1.33303 2.53774 + vertex 1.62794 1.33366 2.53906 + endloop + endfacet + facet normal 0.295549 -0.0765322 0.952257 + outer loop + vertex 1.62777 1.32848 2.53869 + vertex 1.62794 1.33366 2.53906 + vertex 1.62386 1.32945 2.53999 + endloop + endfacet + facet normal 0.293761 -0.083683 0.952209 + outer loop + vertex 1.62289 1.32381 2.53979 + vertex 1.62777 1.32848 2.53869 + vertex 1.62386 1.32945 2.53999 + endloop + endfacet + facet normal 0.295547 -0.0839701 0.951631 + outer loop + vertex 1.62289 1.32381 2.53979 + vertex 1.62386 1.32945 2.53999 + vertex 1.61981 1.326 2.54094 + endloop + endfacet + facet normal 0.293079 -0.0876658 0.952061 + outer loop + vertex 1.61894 1.32216 2.54085 + vertex 1.62289 1.32381 2.53979 + vertex 1.61981 1.326 2.54094 + endloop + endfacet + facet normal 0.28979 -0.0869409 0.953133 + outer loop + vertex 1.61981 1.326 2.54094 + vertex 1.6161 1.32259 2.54176 + vertex 1.61894 1.32216 2.54085 + endloop + endfacet + facet normal 0.288705 -0.0934927 0.952842 + outer loop + vertex 1.61894 1.32216 2.54085 + vertex 1.6161 1.32259 2.54176 + vertex 1.61651 1.31943 2.54132 + endloop + endfacet + facet normal 0.290853 -0.095548 0.951985 + outer loop + vertex 1.61894 1.32216 2.54085 + vertex 1.61651 1.31943 2.54132 + vertex 1.61932 1.31898 2.54042 + endloop + endfacet + facet normal 0.290014 -0.100304 0.951752 + outer loop + vertex 1.61932 1.31898 2.54042 + vertex 1.61651 1.31943 2.54132 + vertex 1.6156 1.31561 2.5412 + endloop + endfacet + facet normal 0.288289 -0.0982311 0.952491 + outer loop + vertex 1.61891 1.31436 2.54006 + vertex 1.61932 1.31898 2.54042 + vertex 1.6156 1.31561 2.5412 + endloop + endfacet + facet normal 0.287305 -0.100865 0.952514 + outer loop + vertex 1.61483 1.31094 2.54093 + vertex 1.61891 1.31436 2.54006 + vertex 1.6156 1.31561 2.5412 + endloop + endfacet + facet normal 0.285465 -0.100594 0.953095 + outer loop + vertex 1.6156 1.31561 2.5412 + vertex 1.61148 1.31215 2.54206 + vertex 1.61483 1.31094 2.54093 + endloop + endfacet + facet normal 0.285065 -0.101703 0.953097 + outer loop + vertex 1.61148 1.31215 2.54206 + vertex 1.6111 1.30757 2.54169 + vertex 1.61483 1.31094 2.54093 + endloop + endfacet + facet normal 0.282995 -0.0992133 0.953976 + outer loop + vertex 1.61483 1.31094 2.54093 + vertex 1.6111 1.30757 2.54169 + vertex 1.61394 1.30715 2.5408 + endloop + endfacet + facet normal 0.284684 -0.0995921 0.953434 + outer loop + vertex 1.61394 1.30715 2.5408 + vertex 1.6179 1.30877 2.53979 + vertex 1.61483 1.31094 2.54093 + endloop + endfacet + facet normal 0.284046 -0.0977987 0.95381 + outer loop + vertex 1.61394 1.30715 2.5408 + vertex 1.61431 1.30399 2.54037 + vertex 1.6179 1.30877 2.53979 + endloop + endfacet + facet normal 0.284041 -0.0977945 0.953812 + outer loop + vertex 1.6179 1.30877 2.53979 + vertex 1.61431 1.30399 2.54037 + vertex 1.61809 1.30359 2.5392 + endloop + endfacet + facet normal 0.286695 -0.0976089 0.953036 + outer loop + vertex 1.61809 1.30359 2.5392 + vertex 1.62248 1.3081 2.53834 + vertex 1.6179 1.30877 2.53979 + endloop + endfacet + facet normal 0.286775 -0.0971203 0.953062 + outer loop + vertex 1.62248 1.3081 2.53834 + vertex 1.62283 1.3134 2.53878 + vertex 1.6179 1.30877 2.53979 + endloop + endfacet + facet normal 0.288336 -0.0989259 0.952405 + outer loop + vertex 1.6179 1.30877 2.53979 + vertex 1.62283 1.3134 2.53878 + vertex 1.61891 1.31436 2.54006 + endloop + endfacet + facet normal 0.289053 -0.0960915 0.952478 + outer loop + vertex 1.62283 1.3134 2.53878 + vertex 1.62309 1.31858 2.53922 + vertex 1.61891 1.31436 2.54006 + endloop + endfacet + facet normal 0.291289 -0.0961465 0.951791 + outer loop + vertex 1.62283 1.3134 2.53878 + vertex 1.62722 1.31796 2.5379 + vertex 1.62309 1.31858 2.53922 + endloop + endfacet + facet normal 0.292162 -0.0908943 0.95204 + outer loop + vertex 1.62722 1.31796 2.5379 + vertex 1.62746 1.32315 2.53832 + vertex 1.62309 1.31858 2.53922 + endloop + endfacet + facet normal 0.293094 -0.0918621 0.95166 + outer loop + vertex 1.62309 1.31858 2.53922 + vertex 1.62746 1.32315 2.53832 + vertex 1.62289 1.32381 2.53979 + endloop + endfacet + facet normal 0.292037 -0.0919373 0.951978 + outer loop + vertex 1.62289 1.32381 2.53979 + vertex 1.61932 1.31898 2.54042 + vertex 1.62309 1.31858 2.53922 + endloop + endfacet + facet normal 0.293254 -0.0909184 0.951702 + outer loop + vertex 1.62722 1.31796 2.5379 + vertex 1.63141 1.32225 2.53702 + vertex 1.62746 1.32315 2.53832 + endloop + endfacet + facet normal 0.294607 -0.0851519 0.951817 + outer loop + vertex 1.63141 1.32225 2.53702 + vertex 1.63237 1.32789 2.53722 + vertex 1.62746 1.32315 2.53832 + endloop + endfacet + facet normal 0.293826 -0.0842709 0.952137 + outer loop + vertex 1.62746 1.32315 2.53832 + vertex 1.63237 1.32789 2.53722 + vertex 1.62777 1.32848 2.53869 + endloop + endfacet + facet normal 0.291551 -0.0846663 0.952801 + outer loop + vertex 1.63237 1.32789 2.53722 + vertex 1.63141 1.32225 2.53702 + vertex 1.63548 1.32576 2.53608 + endloop + endfacet + facet normal 0.292784 -0.0827501 0.952591 + outer loop + vertex 1.63635 1.32964 2.53615 + vertex 1.63237 1.32789 2.53722 + vertex 1.63548 1.32576 2.53608 + endloop + endfacet + facet normal 0.286511 -0.0813898 0.954613 + outer loop + vertex 1.63915 1.32915 2.53527 + vertex 1.63635 1.32964 2.53615 + vertex 1.63548 1.32576 2.53608 + endloop + endfacet + facet normal 0.288771 -0.0840533 0.953702 + outer loop + vertex 1.63879 1.32446 2.53496 + vertex 1.63915 1.32915 2.53527 + vertex 1.63548 1.32576 2.53608 + endloop + endfacet + facet normal 0.287681 -0.0868934 0.953776 + outer loop + vertex 1.63474 1.32102 2.53587 + vertex 1.63879 1.32446 2.53496 + vertex 1.63548 1.32576 2.53608 + endloop + endfacet + facet normal 0.290398 -0.0904019 0.952626 + outer loop + vertex 1.63781 1.3188 2.53473 + vertex 1.63879 1.32446 2.53496 + vertex 1.63474 1.32102 2.53587 + endloop + endfacet + facet normal 0.289636 -0.0915167 0.952752 + outer loop + vertex 1.63386 1.31719 2.53577 + vertex 1.63781 1.3188 2.53473 + vertex 1.63474 1.32102 2.53587 + endloop + endfacet + facet normal 0.294093 -0.0925008 0.95129 + outer loop + vertex 1.63474 1.32102 2.53587 + vertex 1.63104 1.31763 2.53669 + vertex 1.63386 1.31719 2.53577 + endloop + endfacet + facet normal 0.293699 -0.0948133 0.951184 + outer loop + vertex 1.63386 1.31719 2.53577 + vertex 1.63104 1.31763 2.53669 + vertex 1.63144 1.31446 2.53625 + endloop + endfacet + facet normal 0.293987 -0.0950892 0.951068 + outer loop + vertex 1.63386 1.31719 2.53577 + vertex 1.63144 1.31446 2.53625 + vertex 1.63424 1.31399 2.53534 + endloop + endfacet + facet normal 0.293775 -0.0962502 0.951016 + outer loop + vertex 1.63424 1.31399 2.53534 + vertex 1.63144 1.31446 2.53625 + vertex 1.63054 1.31065 2.53614 + endloop + endfacet + facet normal 0.292635 -0.0948745 0.951506 + outer loop + vertex 1.63384 1.30938 2.535 + vertex 1.63424 1.31399 2.53534 + vertex 1.63054 1.31065 2.53614 + endloop + endfacet + facet normal 0.292325 -0.0956938 0.951519 + outer loop + vertex 1.62978 1.30599 2.5359 + vertex 1.63384 1.30938 2.535 + vertex 1.63054 1.31065 2.53614 + endloop + endfacet + facet normal 0.291559 -0.095581 0.951766 + outer loop + vertex 1.63054 1.31065 2.53614 + vertex 1.62644 1.3072 2.53705 + vertex 1.62978 1.30599 2.5359 + endloop + endfacet + facet normal 0.291386 -0.0960613 0.95177 + outer loop + vertex 1.62644 1.3072 2.53705 + vertex 1.62607 1.30264 2.5367 + vertex 1.62978 1.30599 2.5359 + endloop + endfacet + facet normal 0.290272 -0.0947147 0.952245 + outer loop + vertex 1.62978 1.30599 2.5359 + vertex 1.62607 1.30264 2.5367 + vertex 1.6289 1.30222 2.5358 + endloop + endfacet + facet normal 0.291273 -0.0949395 0.951917 + outer loop + vertex 1.6289 1.30222 2.5358 + vertex 1.63284 1.3038 2.53475 + vertex 1.62978 1.30599 2.5359 + endloop + endfacet + facet normal 0.291654 -0.0960357 0.951691 + outer loop + vertex 1.6289 1.30222 2.5358 + vertex 1.62927 1.29905 2.53536 + vertex 1.63284 1.3038 2.53475 + endloop + endfacet + facet normal 0.291097 -0.0955902 0.951906 + outer loop + vertex 1.63284 1.3038 2.53475 + vertex 1.62927 1.29905 2.53536 + vertex 1.63303 1.29861 2.53417 + endloop + endfacet + facet normal 0.288058 -0.0958041 0.952808 + outer loop + vertex 1.63303 1.29861 2.53417 + vertex 1.63744 1.3031 2.53329 + vertex 1.63284 1.3038 2.53475 + endloop + endfacet + facet normal 0.288293 -0.0944027 0.952877 + outer loop + vertex 1.63744 1.3031 2.53329 + vertex 1.63776 1.3084 2.53372 + vertex 1.63284 1.3038 2.53475 + endloop + endfacet + facet normal 0.287967 -0.0940226 0.953013 + outer loop + vertex 1.63284 1.3038 2.53475 + vertex 1.63776 1.3084 2.53372 + vertex 1.63384 1.30938 2.535 + endloop + endfacet + facet normal 0.28799 -0.0939345 0.953015 + outer loop + vertex 1.63776 1.3084 2.53372 + vertex 1.63801 1.31356 2.53415 + vertex 1.63384 1.30938 2.535 + endloop + endfacet + facet normal 0.282015 -0.093805 0.954813 + outer loop + vertex 1.63776 1.3084 2.53372 + vertex 1.64218 1.31294 2.53286 + vertex 1.63801 1.31356 2.53415 + endloop + endfacet + facet normal 0.281928 -0.0943361 0.954786 + outer loop + vertex 1.64218 1.31294 2.53286 + vertex 1.64241 1.31811 2.5333 + vertex 1.63801 1.31356 2.53415 + endloop + endfacet + facet normal 0.281808 -0.094211 0.954834 + outer loop + vertex 1.63801 1.31356 2.53415 + vertex 1.64241 1.31811 2.5333 + vertex 1.63781 1.3188 2.53473 + endloop + endfacet + facet normal 0.288746 -0.0937202 0.952808 + outer loop + vertex 1.63781 1.3188 2.53473 + vertex 1.63424 1.31399 2.53534 + vertex 1.63801 1.31356 2.53415 + endloop + endfacet + facet normal 0.282318 -0.0911273 0.954983 + outer loop + vertex 1.64241 1.31811 2.5333 + vertex 1.64273 1.32345 2.53371 + vertex 1.63781 1.3188 2.53473 + endloop + endfacet + facet normal 0.278048 -0.0909714 0.95625 + outer loop + vertex 1.64241 1.31811 2.5333 + vertex 1.64742 1.32286 2.53229 + vertex 1.64273 1.32345 2.53371 + endloop + endfacet + facet normal 0.279965 -0.0931555 0.95548 + outer loop + vertex 1.64642 1.31725 2.53204 + vertex 1.64742 1.32286 2.53229 + vertex 1.64241 1.31811 2.5333 + endloop + endfacet + facet normal 0.279712 -0.0942908 0.955443 + outer loop + vertex 1.64218 1.31294 2.53286 + vertex 1.64642 1.31725 2.53204 + vertex 1.64241 1.31811 2.5333 + endloop + endfacet + facet normal 0.28187 -0.0936531 0.954871 + outer loop + vertex 1.64244 1.30781 2.53228 + vertex 1.64218 1.31294 2.53286 + vertex 1.63776 1.3084 2.53372 + endloop + endfacet + facet normal 0.279603 -0.0938437 0.955518 + outer loop + vertex 1.64606 1.31269 2.5317 + vertex 1.64218 1.31294 2.53286 + vertex 1.64244 1.30781 2.53228 + endloop + endfacet + facet normal 0.279367 -0.0936582 0.955606 + outer loop + vertex 1.64649 1.30959 2.53127 + vertex 1.64606 1.31269 2.5317 + vertex 1.64244 1.30781 2.53228 + endloop + endfacet + facet normal 0.279852 -0.0949111 0.95534 + outer loop + vertex 1.64649 1.30959 2.53127 + vertex 1.64244 1.30781 2.53228 + vertex 1.64559 1.30576 2.53115 + endloop + endfacet + facet normal 0.281797 -0.0941605 0.954842 + outer loop + vertex 1.63744 1.3031 2.53329 + vertex 1.64244 1.30781 2.53228 + vertex 1.63776 1.3084 2.53372 + endloop + endfacet + facet normal 0.282843 -0.0953642 0.954414 + outer loop + vertex 1.64145 1.30222 2.53201 + vertex 1.64244 1.30781 2.53228 + vertex 1.63744 1.3031 2.53329 + endloop + endfacet + facet normal 0.282645 -0.0962182 0.954387 + outer loop + vertex 1.63719 1.29796 2.53285 + vertex 1.64145 1.30222 2.53201 + vertex 1.63744 1.3031 2.53329 + endloop + endfacet + facet normal 0.288577 -0.0963539 0.952596 + outer loop + vertex 1.63719 1.29796 2.53285 + vertex 1.63744 1.3031 2.53329 + vertex 1.63303 1.29861 2.53417 + endloop + endfacet + facet normal 0.28825 -0.0982496 0.952501 + outer loop + vertex 1.63277 1.29345 2.53372 + vertex 1.63719 1.29796 2.53285 + vertex 1.63303 1.29861 2.53417 + endloop + endfacet + facet normal 0.291181 -0.098324 0.951602 + outer loop + vertex 1.63277 1.29345 2.53372 + vertex 1.63303 1.29861 2.53417 + vertex 1.62886 1.29444 2.53502 + endloop + endfacet + facet normal 0.290666 -0.100305 0.951552 + outer loop + vertex 1.62784 1.28887 2.53474 + vertex 1.63277 1.29345 2.53372 + vertex 1.62886 1.29444 2.53502 + endloop + endfacet + facet normal 0.29014 -0.100217 0.951722 + outer loop + vertex 1.62784 1.28887 2.53474 + vertex 1.62886 1.29444 2.53502 + vertex 1.62478 1.29104 2.5359 + endloop + endfacet + facet normal 0.289713 -0.100853 0.951785 + outer loop + vertex 1.62389 1.28727 2.53577 + vertex 1.62784 1.28887 2.53474 + vertex 1.62478 1.29104 2.5359 + endloop + endfacet + facet normal 0.285639 -0.0999356 0.953112 + outer loop + vertex 1.62478 1.29104 2.5359 + vertex 1.62106 1.2877 2.53667 + vertex 1.62389 1.28727 2.53577 + endloop + endfacet + facet normal 0.285381 -0.101467 0.953028 + outer loop + vertex 1.62389 1.28727 2.53577 + vertex 1.62106 1.2877 2.53667 + vertex 1.62147 1.28458 2.53621 + endloop + endfacet + facet normal 0.287079 -0.103109 0.952341 + outer loop + vertex 1.62389 1.28727 2.53577 + vertex 1.62147 1.28458 2.53621 + vertex 1.62427 1.28413 2.53532 + endloop + endfacet + facet normal 0.286773 -0.104829 0.952246 + outer loop + vertex 1.62427 1.28413 2.53532 + vertex 1.62147 1.28458 2.53621 + vertex 1.62056 1.2808 2.53607 + endloop + endfacet + facet normal 0.286821 -0.104887 0.952225 + outer loop + vertex 1.62386 1.27956 2.53494 + vertex 1.62427 1.28413 2.53532 + vertex 1.62056 1.2808 2.53607 + endloop + endfacet + facet normal 0.286271 -0.106342 0.952229 + outer loop + vertex 1.61977 1.27617 2.53579 + vertex 1.62386 1.27956 2.53494 + vertex 1.62056 1.2808 2.53607 + endloop + endfacet + facet normal 0.281585 -0.105628 0.953705 + outer loop + vertex 1.62056 1.2808 2.53607 + vertex 1.61642 1.27736 2.53691 + vertex 1.61977 1.27617 2.53579 + endloop + endfacet + facet normal 0.280903 -0.107541 0.953692 + outer loop + vertex 1.61642 1.27736 2.53691 + vertex 1.616 1.27281 2.53652 + vertex 1.61977 1.27617 2.53579 + endloop + endfacet + facet normal 0.280398 -0.106928 0.95391 + outer loop + vertex 1.61977 1.27617 2.53579 + vertex 1.616 1.27281 2.53652 + vertex 1.6188 1.27237 2.53565 + endloop + endfacet + facet normal 0.286717 -0.108461 0.951856 + outer loop + vertex 1.6188 1.27237 2.53565 + vertex 1.62276 1.27395 2.53463 + vertex 1.61977 1.27617 2.53579 + endloop + endfacet + facet normal 0.287778 -0.111568 0.951176 + outer loop + vertex 1.6188 1.27237 2.53565 + vertex 1.61898 1.26905 2.53521 + vertex 1.62276 1.27395 2.53463 + endloop + endfacet + facet normal 0.287285 -0.111164 0.951373 + outer loop + vertex 1.62276 1.27395 2.53463 + vertex 1.61898 1.26905 2.53521 + vertex 1.62278 1.26858 2.534 + endloop + endfacet + facet normal 0.290237 -0.111052 0.950489 + outer loop + vertex 1.62278 1.26858 2.534 + vertex 1.62733 1.2733 2.53316 + vertex 1.62276 1.27395 2.53463 + endloop + endfacet + facet normal 0.290688 -0.1083 0.950669 + outer loop + vertex 1.62733 1.2733 2.53316 + vertex 1.62774 1.27859 2.53364 + vertex 1.62276 1.27395 2.53463 + endloop + endfacet + facet normal 0.290664 -0.108272 0.950679 + outer loop + vertex 1.62276 1.27395 2.53463 + vertex 1.62774 1.27859 2.53364 + vertex 1.62386 1.27956 2.53494 + endloop + endfacet + facet normal 0.291261 -0.105969 0.950756 + outer loop + vertex 1.62774 1.27859 2.53364 + vertex 1.62803 1.28372 2.53412 + vertex 1.62386 1.27956 2.53494 + endloop + endfacet + facet normal 0.292711 -0.106007 0.950307 + outer loop + vertex 1.62774 1.27859 2.53364 + vertex 1.63213 1.2831 2.53279 + vertex 1.62803 1.28372 2.53412 + endloop + endfacet + facet normal 0.292968 -0.104502 0.950394 + outer loop + vertex 1.63213 1.2831 2.53279 + vertex 1.63241 1.28819 2.53327 + vertex 1.62803 1.28372 2.53412 + endloop + endfacet + facet normal 0.291449 -0.102892 0.951037 + outer loop + vertex 1.62803 1.28372 2.53412 + vertex 1.63241 1.28819 2.53327 + vertex 1.62784 1.28887 2.53474 + endloop + endfacet + facet normal 0.290769 -0.102942 0.95124 + outer loop + vertex 1.62784 1.28887 2.53474 + vertex 1.62427 1.28413 2.53532 + vertex 1.62803 1.28372 2.53412 + endloop + endfacet + facet normal 0.291215 -0.104458 0.950938 + outer loop + vertex 1.63213 1.2831 2.53279 + vertex 1.63634 1.28728 2.53196 + vertex 1.63241 1.28819 2.53327 + endloop + endfacet + facet normal 0.29134 -0.103939 0.950956 + outer loop + vertex 1.63634 1.28728 2.53196 + vertex 1.63739 1.29281 2.53225 + vertex 1.63241 1.28819 2.53327 + endloop + endfacet + facet normal 0.289168 -0.101389 0.951894 + outer loop + vertex 1.63241 1.28819 2.53327 + vertex 1.63739 1.29281 2.53225 + vertex 1.63277 1.29345 2.53372 + endloop + endfacet + facet normal 0.284607 -0.102766 0.95312 + outer loop + vertex 1.63739 1.29281 2.53225 + vertex 1.63634 1.28728 2.53196 + vertex 1.64049 1.29069 2.53109 + endloop + endfacet + facet normal 0.284603 -0.102772 0.953121 + outer loop + vertex 1.64144 1.2945 2.53122 + vertex 1.63739 1.29281 2.53225 + vertex 1.64049 1.29069 2.53109 + endloop + endfacet + facet normal 0.278651 -0.101334 0.955031 + outer loop + vertex 1.64425 1.29407 2.53035 + vertex 1.64144 1.2945 2.53122 + vertex 1.64049 1.29069 2.53109 + endloop + endfacet + facet normal 0.278491 -0.10114 0.955099 + outer loop + vertex 1.6438 1.28945 2.52999 + vertex 1.64425 1.29407 2.53035 + vertex 1.64049 1.29069 2.53109 + endloop + endfacet + facet normal 0.283573 -0.0999143 0.953731 + outer loop + vertex 1.64144 1.2945 2.53122 + vertex 1.64106 1.29764 2.53166 + vertex 1.63739 1.29281 2.53225 + endloop + endfacet + facet normal 0.283635 -0.0999649 0.953707 + outer loop + vertex 1.64106 1.29764 2.53166 + vertex 1.63719 1.29796 2.53285 + vertex 1.63739 1.29281 2.53225 + endloop + endfacet + facet normal 0.286645 -0.105475 0.952213 + outer loop + vertex 1.64049 1.29069 2.53109 + vertex 1.63634 1.28728 2.53196 + vertex 1.63966 1.28607 2.53083 + endloop + endfacet + facet normal 0.293162 -0.10658 0.950104 + outer loop + vertex 1.63592 1.28277 2.53159 + vertex 1.63634 1.28728 2.53196 + vertex 1.63213 1.2831 2.53279 + endloop + endfacet + facet normal 0.293141 -0.10677 0.950089 + outer loop + vertex 1.63592 1.28277 2.53159 + vertex 1.63213 1.2831 2.53279 + vertex 1.63231 1.278 2.53216 + endloop + endfacet + facet normal 0.293415 -0.10675 0.950006 + outer loop + vertex 1.63231 1.278 2.53216 + vertex 1.63213 1.2831 2.53279 + vertex 1.62774 1.27859 2.53364 + endloop + endfacet + facet normal 0.293163 -0.10842 0.949895 + outer loop + vertex 1.62733 1.2733 2.53316 + vertex 1.63231 1.278 2.53216 + vertex 1.62774 1.27859 2.53364 + endloop + endfacet + facet normal 0.291915 -0.106984 0.950442 + outer loop + vertex 1.63128 1.27248 2.53186 + vertex 1.63231 1.278 2.53216 + vertex 1.62733 1.2733 2.53316 + endloop + endfacet + facet normal 0.291324 -0.109648 0.95032 + outer loop + vertex 1.62704 1.26815 2.53266 + vertex 1.63128 1.27248 2.53186 + vertex 1.62733 1.2733 2.53316 + endloop + endfacet + facet normal 0.288822 -0.109578 0.951091 + outer loop + vertex 1.62704 1.26815 2.53266 + vertex 1.62733 1.2733 2.53316 + vertex 1.62278 1.26858 2.534 + endloop + endfacet + facet normal 0.288431 -0.112658 0.95085 + outer loop + vertex 1.62258 1.26338 2.53345 + vertex 1.62704 1.26815 2.53266 + vertex 1.62278 1.26858 2.534 + endloop + endfacet + facet normal 0.285349 -0.112642 0.951781 + outer loop + vertex 1.62258 1.26338 2.53345 + vertex 1.62278 1.26858 2.534 + vertex 1.61798 1.26379 2.53487 + endloop + endfacet + facet normal 0.285086 -0.114931 0.951586 + outer loop + vertex 1.61811 1.25867 2.53422 + vertex 1.62258 1.26338 2.53345 + vertex 1.61798 1.26379 2.53487 + endloop + endfacet + facet normal 0.282403 -0.115102 0.952365 + outer loop + vertex 1.61798 1.26379 2.53487 + vertex 1.61431 1.25901 2.53539 + vertex 1.61811 1.25867 2.53422 + endloop + endfacet + facet normal 0.282082 -0.117858 0.952124 + outer loop + vertex 1.61383 1.25449 2.53497 + vertex 1.61811 1.25867 2.53422 + vertex 1.61431 1.25901 2.53539 + endloop + endfacet + facet normal 0.278752 -0.117598 0.953136 + outer loop + vertex 1.61383 1.25449 2.53497 + vertex 1.61431 1.25901 2.53539 + vertex 1.61053 1.25573 2.53609 + endloop + endfacet + facet normal 0.278182 -0.119094 0.953117 + outer loop + vertex 1.60969 1.25122 2.53577 + vertex 1.61383 1.25449 2.53497 + vertex 1.61053 1.25573 2.53609 + endloop + endfacet + facet normal 0.277609 -0.119 0.953295 + outer loop + vertex 1.61053 1.25573 2.53609 + vertex 1.60638 1.25239 2.53688 + vertex 1.60969 1.25122 2.53577 + endloop + endfacet + facet normal 0.277426 -0.119508 0.953285 + outer loop + vertex 1.60638 1.25239 2.53688 + vertex 1.60593 1.24798 2.53646 + vertex 1.60969 1.25122 2.53577 + endloop + endfacet + facet normal 0.279513 -0.122129 0.952343 + outer loop + vertex 1.60969 1.25122 2.53577 + vertex 1.60593 1.24798 2.53646 + vertex 1.60871 1.24754 2.53558 + endloop + endfacet + facet normal 0.278833 -0.121959 0.952564 + outer loop + vertex 1.60871 1.24754 2.53558 + vertex 1.61273 1.24898 2.53459 + vertex 1.60969 1.25122 2.53577 + endloop + endfacet + facet normal 0.279652 -0.124656 0.951975 + outer loop + vertex 1.60871 1.24754 2.53558 + vertex 1.60891 1.24425 2.53509 + vertex 1.61273 1.24898 2.53459 + endloop + endfacet + facet normal 0.279578 -0.124593 0.952005 + outer loop + vertex 1.61273 1.24898 2.53459 + vertex 1.60891 1.24425 2.53509 + vertex 1.61283 1.24359 2.53386 + endloop + endfacet + facet normal 0.279993 -0.124569 0.951886 + outer loop + vertex 1.61283 1.24359 2.53386 + vertex 1.61747 1.24824 2.5331 + vertex 1.61273 1.24898 2.53459 + endloop + endfacet + facet normal 0.280645 -0.120964 0.952159 + outer loop + vertex 1.61747 1.24824 2.5331 + vertex 1.61781 1.25354 2.53367 + vertex 1.61273 1.24898 2.53459 + endloop + endfacet + facet normal 0.280834 -0.121192 0.952074 + outer loop + vertex 1.61273 1.24898 2.53459 + vertex 1.61781 1.25354 2.53367 + vertex 1.61383 1.25449 2.53497 + endloop + endfacet + facet normal 0.282218 -0.121013 0.951687 + outer loop + vertex 1.61747 1.24824 2.5331 + vertex 1.62246 1.25295 2.53222 + vertex 1.61781 1.25354 2.53367 + endloop + endfacet + facet normal 0.282878 -0.116655 0.952036 + outer loop + vertex 1.62246 1.25295 2.53222 + vertex 1.62241 1.25821 2.53288 + vertex 1.61781 1.25354 2.53367 + endloop + endfacet + facet normal 0.283745 -0.117573 0.951664 + outer loop + vertex 1.61781 1.25354 2.53367 + vertex 1.62241 1.25821 2.53288 + vertex 1.61811 1.25867 2.53422 + endloop + endfacet + facet normal 0.283968 -0.116606 0.951717 + outer loop + vertex 1.6263 1.25787 2.53168 + vertex 1.62241 1.25821 2.53288 + vertex 1.62246 1.25295 2.53222 + endloop + endfacet + facet normal 0.282137 -0.115095 0.952445 + outer loop + vertex 1.62644 1.25456 2.53123 + vertex 1.6263 1.25787 2.53168 + vertex 1.62246 1.25295 2.53222 + endloop + endfacet + facet normal 0.283455 -0.118886 0.951588 + outer loop + vertex 1.62644 1.25456 2.53123 + vertex 1.62246 1.25295 2.53222 + vertex 1.62528 1.25079 2.53111 + endloop + endfacet + facet normal 0.288032 -0.120246 0.950041 + outer loop + vertex 1.62908 1.25394 2.53035 + vertex 1.62644 1.25456 2.53123 + vertex 1.62528 1.25079 2.53111 + endloop + endfacet + facet normal 0.287801 -0.119941 0.95015 + outer loop + vertex 1.62806 1.2487 2.53 + vertex 1.62908 1.25394 2.53035 + vertex 1.62528 1.25079 2.53111 + endloop + endfacet + facet normal 0.286363 -0.121957 0.950328 + outer loop + vertex 1.62416 1.24707 2.53097 + vertex 1.62806 1.2487 2.53 + vertex 1.62528 1.25079 2.53111 + endloop + endfacet + facet normal 0.282927 -0.120966 0.951483 + outer loop + vertex 1.62528 1.25079 2.53111 + vertex 1.62144 1.24769 2.53186 + vertex 1.62416 1.24707 2.53097 + endloop + endfacet + facet normal 0.28246 -0.122874 0.951377 + outer loop + vertex 1.62416 1.24707 2.53097 + vertex 1.62144 1.24769 2.53186 + vertex 1.62165 1.24443 2.53137 + endloop + endfacet + facet normal 0.279583 -0.123176 0.952188 + outer loop + vertex 1.62165 1.24443 2.53137 + vertex 1.62144 1.24769 2.53186 + vertex 1.61758 1.24288 2.53237 + endloop + endfacet + facet normal 0.280259 -0.125252 0.951718 + outer loop + vertex 1.62165 1.24443 2.53137 + vertex 1.61758 1.24288 2.53237 + vertex 1.62063 1.2407 2.53118 + endloop + endfacet + facet normal 0.278974 -0.127126 0.951847 + outer loop + vertex 1.61758 1.24288 2.53237 + vertex 1.61646 1.23737 2.53196 + vertex 1.62063 1.2407 2.53118 + endloop + endfacet + facet normal 0.278968 -0.127119 0.95185 + outer loop + vertex 1.62063 1.2407 2.53118 + vertex 1.61646 1.23737 2.53196 + vertex 1.61977 1.23618 2.53083 + endloop + endfacet + facet normal 0.281338 -0.127515 0.951099 + outer loop + vertex 1.61977 1.23618 2.53083 + vertex 1.62391 1.23947 2.53005 + vertex 1.62063 1.2407 2.53118 + endloop + endfacet + facet normal 0.282288 -0.125037 0.951146 + outer loop + vertex 1.62391 1.23947 2.53005 + vertex 1.62441 1.24396 2.53049 + vertex 1.62063 1.2407 2.53118 + endloop + endfacet + facet normal 0.283019 -0.125955 0.950808 + outer loop + vertex 1.62441 1.24396 2.53049 + vertex 1.62165 1.24443 2.53137 + vertex 1.62063 1.2407 2.53118 + endloop + endfacet + facet normal 0.283427 -0.123857 0.950962 + outer loop + vertex 1.62416 1.24707 2.53097 + vertex 1.62165 1.24443 2.53137 + vertex 1.62441 1.24396 2.53049 + endloop + endfacet + facet normal 0.284582 -0.125221 0.950438 + outer loop + vertex 1.62391 1.23947 2.53005 + vertex 1.62818 1.24364 2.52932 + vertex 1.62441 1.24396 2.53049 + endloop + endfacet + facet normal 0.284966 -0.121867 0.950759 + outer loop + vertex 1.62806 1.2487 2.53 + vertex 1.62441 1.24396 2.53049 + vertex 1.62818 1.24364 2.52932 + endloop + endfacet + facet normal 0.287828 -0.121685 0.94992 + outer loop + vertex 1.62818 1.24364 2.52932 + vertex 1.63264 1.24832 2.52857 + vertex 1.62806 1.2487 2.53 + endloop + endfacet + facet normal 0.288243 -0.118008 0.950258 + outer loop + vertex 1.63264 1.24832 2.52857 + vertex 1.63285 1.25351 2.52915 + vertex 1.62806 1.2487 2.53 + endloop + endfacet + facet normal 0.290273 -0.118021 0.949638 + outer loop + vertex 1.63264 1.24832 2.52857 + vertex 1.63711 1.25304 2.52779 + vertex 1.63285 1.25351 2.52915 + endloop + endfacet + facet normal 0.290614 -0.11548 0.949846 + outer loop + vertex 1.63711 1.25304 2.52779 + vertex 1.63742 1.25821 2.52832 + vertex 1.63285 1.25351 2.52915 + endloop + endfacet + facet normal 0.291269 -0.116164 0.949562 + outer loop + vertex 1.63285 1.25351 2.52915 + vertex 1.63742 1.25821 2.52832 + vertex 1.63287 1.25886 2.52979 + endloop + endfacet + facet normal 0.291065 -0.116171 0.949624 + outer loop + vertex 1.63287 1.25886 2.52979 + vertex 1.62908 1.25394 2.53035 + vertex 1.63285 1.25351 2.52915 + endloop + endfacet + facet normal 0.292336 -0.11721 0.949106 + outer loop + vertex 1.62898 1.25728 2.5308 + vertex 1.62908 1.25394 2.53035 + vertex 1.63287 1.25886 2.52979 + endloop + endfacet + facet normal 0.291104 -0.113644 0.949918 + outer loop + vertex 1.62898 1.25728 2.5308 + vertex 1.63287 1.25886 2.52979 + vertex 1.63011 1.26108 2.53091 + endloop + endfacet + facet normal 0.286619 -0.112362 0.951433 + outer loop + vertex 1.63011 1.26108 2.53091 + vertex 1.6263 1.25787 2.53168 + vertex 1.62898 1.25728 2.5308 + endloop + endfacet + facet normal 0.286644 -0.112395 0.951421 + outer loop + vertex 1.62724 1.2631 2.53201 + vertex 1.6263 1.25787 2.53168 + vertex 1.63011 1.26108 2.53091 + endloop + endfacet + facet normal 0.287838 -0.110616 0.951269 + outer loop + vertex 1.63118 1.26486 2.53102 + vertex 1.62724 1.2631 2.53201 + vertex 1.63011 1.26108 2.53091 + endloop + endfacet + facet normal 0.290765 -0.11142 0.950285 + outer loop + vertex 1.63388 1.26421 2.53012 + vertex 1.63118 1.26486 2.53102 + vertex 1.63011 1.26108 2.53091 + endloop + endfacet + facet normal 0.287234 -0.109055 0.951632 + outer loop + vertex 1.63118 1.26486 2.53102 + vertex 1.63087 1.26797 2.53147 + vertex 1.62724 1.2631 2.53201 + endloop + endfacet + facet normal 0.289268 -0.110657 0.950831 + outer loop + vertex 1.63087 1.26797 2.53147 + vertex 1.62704 1.26815 2.53266 + vertex 1.62724 1.2631 2.53201 + endloop + endfacet + facet normal 0.291777 -0.112756 0.949817 + outer loop + vertex 1.63287 1.25886 2.52979 + vertex 1.63388 1.26421 2.53012 + vertex 1.63011 1.26108 2.53091 + endloop + endfacet + facet normal 0.291677 -0.113679 0.949738 + outer loop + vertex 1.63742 1.25821 2.52832 + vertex 1.63777 1.26359 2.52886 + vertex 1.63287 1.25886 2.52979 + endloop + endfacet + facet normal 0.287595 -0.113537 0.950999 + outer loop + vertex 1.63742 1.25821 2.52832 + vertex 1.6425 1.26289 2.52734 + vertex 1.63777 1.26359 2.52886 + endloop + endfacet + facet normal 0.289049 -0.115252 0.950351 + outer loop + vertex 1.6414 1.25732 2.527 + vertex 1.6425 1.26289 2.52734 + vertex 1.63742 1.25821 2.52832 + endloop + endfacet + facet normal 0.289005 -0.115435 0.950342 + outer loop + vertex 1.63711 1.25304 2.52779 + vertex 1.6414 1.25732 2.527 + vertex 1.63742 1.25821 2.52832 + endloop + endfacet + facet normal 0.28849 -0.116211 0.950404 + outer loop + vertex 1.6373 1.24798 2.52711 + vertex 1.63711 1.25304 2.52779 + vertex 1.63264 1.24832 2.52857 + endloop + endfacet + facet normal 0.288163 -0.119412 0.950107 + outer loop + vertex 1.63246 1.24316 2.52797 + vertex 1.6373 1.24798 2.52711 + vertex 1.63264 1.24832 2.52857 + endloop + endfacet + facet normal 0.285848 -0.116909 0.951117 + outer loop + vertex 1.63636 1.24277 2.52675 + vertex 1.6373 1.24798 2.52711 + vertex 1.63246 1.24316 2.52797 + endloop + endfacet + facet normal 0.285121 -0.122603 0.950618 + outer loop + vertex 1.63636 1.24277 2.52675 + vertex 1.63246 1.24316 2.52797 + vertex 1.63252 1.2379 2.52728 + endloop + endfacet + facet normal 0.283001 -0.120842 0.951477 + outer loop + vertex 1.63657 1.23951 2.52628 + vertex 1.63636 1.24277 2.52675 + vertex 1.63252 1.2379 2.52728 + endloop + endfacet + facet normal 0.284846 -0.126245 0.950224 + outer loop + vertex 1.63657 1.23951 2.52628 + vertex 1.63252 1.2379 2.52728 + vertex 1.63555 1.23575 2.52608 + endloop + endfacet + facet normal 0.283475 -0.128254 0.950365 + outer loop + vertex 1.63252 1.2379 2.52728 + vertex 1.63137 1.2324 2.52688 + vertex 1.63555 1.23575 2.52608 + endloop + endfacet + facet normal 0.285361 -0.130823 0.94945 + outer loop + vertex 1.63555 1.23575 2.52608 + vertex 1.63137 1.2324 2.52688 + vertex 1.63461 1.23117 2.52573 + endloop + endfacet + facet normal 0.288393 -0.13137 0.948457 + outer loop + vertex 1.63461 1.23117 2.52573 + vertex 1.63878 1.23449 2.52492 + vertex 1.63555 1.23575 2.52608 + endloop + endfacet + facet normal 0.289656 -0.128178 0.948509 + outer loop + vertex 1.63878 1.23449 2.52492 + vertex 1.63932 1.23903 2.52538 + vertex 1.63555 1.23575 2.52608 + endloop + endfacet + facet normal 0.288944 -0.127289 0.948846 + outer loop + vertex 1.63932 1.23903 2.52538 + vertex 1.63657 1.23951 2.52628 + vertex 1.63555 1.23575 2.52608 + endloop + endfacet + facet normal 0.287315 -0.127976 0.949248 + outer loop + vertex 1.63878 1.23449 2.52492 + vertex 1.64308 1.23868 2.52419 + vertex 1.63932 1.23903 2.52538 + endloop + endfacet + facet normal 0.287896 -0.123236 0.949699 + outer loop + vertex 1.64296 1.24378 2.52489 + vertex 1.63932 1.23903 2.52538 + vertex 1.64308 1.23868 2.52419 + endloop + endfacet + facet normal 0.280065 -0.123732 0.951974 + outer loop + vertex 1.64308 1.23868 2.52419 + vertex 1.64756 1.24334 2.52348 + vertex 1.64296 1.24378 2.52489 + endloop + endfacet + facet normal 0.280538 -0.119878 0.952327 + outer loop + vertex 1.64756 1.24334 2.52348 + vertex 1.64776 1.24852 2.52407 + vertex 1.64296 1.24378 2.52489 + endloop + endfacet + facet normal 0.276557 -0.119858 0.953494 + outer loop + vertex 1.64756 1.24334 2.52348 + vertex 1.65208 1.24809 2.52276 + vertex 1.64776 1.24852 2.52407 + endloop + endfacet + facet normal 0.281448 -0.125153 0.95138 + outer loop + vertex 1.64736 1.23824 2.52286 + vertex 1.64756 1.24334 2.52348 + vertex 1.64308 1.23868 2.52419 + endloop + endfacet + facet normal 0.28105 -0.128128 0.951101 + outer loop + vertex 1.64271 1.23357 2.52361 + vertex 1.64736 1.23824 2.52286 + vertex 1.64308 1.23868 2.52419 + endloop + endfacet + facet normal 0.281793 -0.128919 0.950775 + outer loop + vertex 1.64738 1.23307 2.52216 + vertex 1.64736 1.23824 2.52286 + vertex 1.64271 1.23357 2.52361 + endloop + endfacet + facet normal 0.281442 -0.131514 0.950523 + outer loop + vertex 1.64232 1.22829 2.52299 + vertex 1.64738 1.23307 2.52216 + vertex 1.64271 1.23357 2.52361 + endloop + endfacet + facet normal 0.286412 -0.131704 0.949011 + outer loop + vertex 1.64232 1.22829 2.52299 + vertex 1.64271 1.23357 2.52361 + vertex 1.6375 1.22883 2.52452 + endloop + endfacet + facet normal 0.285914 -0.135162 0.948675 + outer loop + vertex 1.63764 1.22342 2.52371 + vertex 1.64232 1.22829 2.52299 + vertex 1.6375 1.22883 2.52452 + endloop + endfacet + facet normal 0.28489 -0.135233 0.948973 + outer loop + vertex 1.6375 1.22883 2.52452 + vertex 1.63308 1.22352 2.5251 + vertex 1.63764 1.22342 2.52371 + endloop + endfacet + facet normal 0.284722 -0.13811 0.948609 + outer loop + vertex 1.63318 1.21871 2.52436 + vertex 1.63764 1.22342 2.52371 + vertex 1.63308 1.22352 2.5251 + endloop + endfacet + facet normal 0.281655 -0.138312 0.949495 + outer loop + vertex 1.63308 1.22352 2.5251 + vertex 1.62951 1.21907 2.52551 + vertex 1.63318 1.21871 2.52436 + endloop + endfacet + facet normal 0.281349 -0.14066 0.94924 + outer loop + vertex 1.62885 1.21454 2.52503 + vertex 1.63318 1.21871 2.52436 + vertex 1.62951 1.21907 2.52551 + endloop + endfacet + facet normal 0.280966 -0.140234 0.949417 + outer loop + vertex 1.6328 1.21362 2.52373 + vertex 1.63318 1.21871 2.52436 + vertex 1.62885 1.21454 2.52503 + endloop + endfacet + facet normal 0.280075 -0.143671 0.949166 + outer loop + vertex 1.62754 1.2089 2.52456 + vertex 1.6328 1.21362 2.52373 + vertex 1.62885 1.21454 2.52503 + endloop + endfacet + facet normal 0.280068 -0.143669 0.949169 + outer loop + vertex 1.62754 1.2089 2.52456 + vertex 1.62885 1.21454 2.52503 + vertex 1.62463 1.21121 2.52577 + endloop + endfacet + facet normal 0.279233 -0.144763 0.949248 + outer loop + vertex 1.62341 1.20741 2.52555 + vertex 1.62754 1.2089 2.52456 + vertex 1.62463 1.21121 2.52577 + endloop + endfacet + facet normal 0.277251 -0.144168 0.94992 + outer loop + vertex 1.62463 1.21121 2.52577 + vertex 1.62081 1.20804 2.5264 + vertex 1.62341 1.20741 2.52555 + endloop + endfacet + facet normal 0.276652 -0.143391 0.950212 + outer loop + vertex 1.6214 1.21244 2.5269 + vertex 1.62081 1.20804 2.5264 + vertex 1.62463 1.21121 2.52577 + endloop + endfacet + facet normal 0.277433 -0.14141 0.950281 + outer loop + vertex 1.62566 1.21583 2.52616 + vertex 1.6214 1.21244 2.5269 + vertex 1.62463 1.21121 2.52577 + endloop + endfacet + facet normal 0.277162 -0.141041 0.950415 + outer loop + vertex 1.62273 1.21811 2.52735 + vertex 1.6214 1.21244 2.5269 + vertex 1.62566 1.21583 2.52616 + endloop + endfacet + facet normal 0.277794 -0.140195 0.950356 + outer loop + vertex 1.62693 1.21973 2.52636 + vertex 1.62273 1.21811 2.52735 + vertex 1.62566 1.21583 2.52616 + endloop + endfacet + facet normal 0.277513 -0.139338 0.950564 + outer loop + vertex 1.62693 1.21973 2.52636 + vertex 1.62724 1.22354 2.52683 + vertex 1.62273 1.21811 2.52735 + endloop + endfacet + facet normal 0.27825 -0.139982 0.950253 + outer loop + vertex 1.62724 1.22354 2.52683 + vertex 1.62258 1.22352 2.52819 + vertex 1.62273 1.21811 2.52735 + endloop + endfacet + facet normal 0.277222 -0.140055 0.950543 + outer loop + vertex 1.62273 1.21811 2.52735 + vertex 1.62258 1.22352 2.52819 + vertex 1.61784 1.21866 2.52886 + endloop + endfacet + facet normal 0.277073 -0.141078 0.950435 + outer loop + vertex 1.61741 1.21331 2.52819 + vertex 1.62273 1.21811 2.52735 + vertex 1.61784 1.21866 2.52886 + endloop + endfacet + facet normal 0.277753 -0.141107 0.950233 + outer loop + vertex 1.61741 1.21331 2.52819 + vertex 1.61784 1.21866 2.52886 + vertex 1.61276 1.21397 2.52965 + endloop + endfacet + facet normal 0.277533 -0.142377 0.950108 + outer loop + vertex 1.61274 1.20871 2.52886 + vertex 1.61741 1.21331 2.52819 + vertex 1.61276 1.21397 2.52965 + endloop + endfacet + facet normal 0.283238 -0.142153 0.948456 + outer loop + vertex 1.61276 1.21397 2.52965 + vertex 1.60889 1.20926 2.5301 + vertex 1.61274 1.20871 2.52886 + endloop + endfacet + facet normal 0.282828 -0.1445 0.948224 + outer loop + vertex 1.60784 1.20409 2.52962 + vertex 1.61274 1.20871 2.52886 + vertex 1.60889 1.20926 2.5301 + endloop + endfacet + facet normal 0.294462 -0.146514 0.944365 + outer loop + vertex 1.60784 1.20409 2.52962 + vertex 1.60889 1.20926 2.5301 + vertex 1.60509 1.20629 2.53082 + endloop + endfacet + facet normal 0.294097 -0.146992 0.944405 + outer loop + vertex 1.60389 1.20266 2.53063 + vertex 1.60784 1.20409 2.52962 + vertex 1.60509 1.20629 2.53082 + endloop + endfacet + facet normal 0.298131 -0.14824 0.942944 + outer loop + vertex 1.60509 1.20629 2.53082 + vertex 1.60126 1.20322 2.53155 + vertex 1.60389 1.20266 2.53063 + endloop + endfacet + facet normal 0.297314 -0.151637 0.942661 + outer loop + vertex 1.60389 1.20266 2.53063 + vertex 1.60126 1.20322 2.53155 + vertex 1.60131 1.20005 2.53102 + endloop + endfacet + facet normal 0.298282 -0.152669 0.942189 + outer loop + vertex 1.60389 1.20266 2.53063 + vertex 1.60131 1.20005 2.53102 + vertex 1.60392 1.19935 2.53008 + endloop + endfacet + facet normal 0.283057 -0.152557 0.946892 + outer loop + vertex 1.60131 1.20005 2.53102 + vertex 1.60126 1.20322 2.53155 + vertex 1.59731 1.19828 2.53193 + endloop + endfacet + facet normal 0.281846 -0.149376 0.94776 + outer loop + vertex 1.60131 1.20005 2.53102 + vertex 1.59731 1.19828 2.53193 + vertex 1.6 1.1963 2.53082 + endloop + endfacet + facet normal 0.286016 -0.155026 0.945601 + outer loop + vertex 1.60126 1.20322 2.53155 + vertex 1.59736 1.20329 2.53274 + vertex 1.59731 1.19828 2.53193 + endloop + endfacet + facet normal 0.245406 -0.156463 0.956711 + outer loop + vertex 1.59731 1.19828 2.53193 + vertex 1.59736 1.20329 2.53274 + vertex 1.59251 1.19821 2.53315 + endloop + endfacet + facet normal 0.286722 -0.143533 0.9472 + outer loop + vertex 1.60126 1.20322 2.53155 + vertex 1.60234 1.20828 2.53199 + vertex 1.59736 1.20329 2.53274 + endloop + endfacet + facet normal 0.291585 -0.148738 0.94491 + outer loop + vertex 1.59736 1.20329 2.53274 + vertex 1.60234 1.20828 2.53199 + vertex 1.59761 1.20835 2.53346 + endloop + endfacet + facet normal 0.292177 -0.138533 0.946277 + outer loop + vertex 1.60234 1.20828 2.53199 + vertex 1.60234 1.21336 2.53273 + vertex 1.59761 1.20835 2.53346 + endloop + endfacet + facet normal 0.294994 -0.13841 0.945421 + outer loop + vertex 1.60617 1.21315 2.53151 + vertex 1.60234 1.21336 2.53273 + vertex 1.60234 1.20828 2.53199 + endloop + endfacet + facet normal 0.296253 -0.139455 0.944874 + outer loop + vertex 1.60626 1.20994 2.53101 + vertex 1.60617 1.21315 2.53151 + vertex 1.60234 1.20828 2.53199 + endloop + endfacet + facet normal 0.297512 -0.142952 0.943955 + outer loop + vertex 1.60626 1.20994 2.53101 + vertex 1.60234 1.20828 2.53199 + vertex 1.60509 1.20629 2.53082 + endloop + endfacet + facet normal 0.290269 -0.139891 0.946665 + outer loop + vertex 1.60879 1.21254 2.53061 + vertex 1.60617 1.21315 2.53151 + vertex 1.60626 1.20994 2.53101 + endloop + endfacet + facet normal 0.290571 -0.140208 0.946525 + outer loop + vertex 1.60879 1.21254 2.53061 + vertex 1.60626 1.20994 2.53101 + vertex 1.60889 1.20926 2.5301 + endloop + endfacet + facet normal 0.289927 -0.14122 0.946572 + outer loop + vertex 1.60999 1.21622 2.53079 + vertex 1.60617 1.21315 2.53151 + vertex 1.60879 1.21254 2.53061 + endloop + endfacet + facet normal 0.281014 -0.138473 0.949661 + outer loop + vertex 1.60879 1.21254 2.53061 + vertex 1.61276 1.21397 2.52965 + vertex 1.60999 1.21622 2.53079 + endloop + endfacet + facet normal 0.279722 -0.140131 0.949799 + outer loop + vertex 1.61276 1.21397 2.52965 + vertex 1.61387 1.21925 2.5301 + vertex 1.60999 1.21622 2.53079 + endloop + endfacet + facet normal 0.278387 -0.138266 0.950465 + outer loop + vertex 1.61387 1.21925 2.5301 + vertex 1.61121 1.21994 2.53098 + vertex 1.60999 1.21622 2.53079 + endloop + endfacet + facet normal 0.285547 -0.140482 0.948012 + outer loop + vertex 1.61121 1.21994 2.53098 + vertex 1.60726 1.21828 2.53192 + vertex 1.60999 1.21622 2.53079 + endloop + endfacet + facet normal 0.285613 -0.140664 0.947966 + outer loop + vertex 1.61121 1.21994 2.53098 + vertex 1.61116 1.22316 2.53147 + vertex 1.60726 1.21828 2.53192 + endloop + endfacet + facet normal 0.282909 -0.138402 0.949109 + outer loop + vertex 1.61116 1.22316 2.53147 + vertex 1.6073 1.22339 2.53265 + vertex 1.60726 1.21828 2.53192 + endloop + endfacet + facet normal 0.290669 -0.138133 0.9468 + outer loop + vertex 1.60726 1.21828 2.53192 + vertex 1.6073 1.22339 2.53265 + vertex 1.60262 1.21851 2.53338 + endloop + endfacet + facet normal 0.290943 -0.134954 0.947175 + outer loop + vertex 1.60234 1.21336 2.53273 + vertex 1.60726 1.21828 2.53192 + vertex 1.60262 1.21851 2.53338 + endloop + endfacet + facet normal 0.29439 -0.135003 0.946102 + outer loop + vertex 1.60234 1.21336 2.53273 + vertex 1.60262 1.21851 2.53338 + vertex 1.59791 1.21355 2.53414 + endloop + endfacet + facet normal 0.294345 -0.134956 0.946123 + outer loop + vertex 1.59791 1.21355 2.53414 + vertex 1.60262 1.21851 2.53338 + vertex 1.59796 1.21886 2.53488 + endloop + endfacet + facet normal 0.294248 -0.135827 0.946028 + outer loop + vertex 1.60262 1.21851 2.53338 + vertex 1.60291 1.22369 2.53403 + vertex 1.59796 1.21886 2.53488 + endloop + endfacet + facet normal 0.294906 -0.136555 0.945719 + outer loop + vertex 1.59796 1.21886 2.53488 + vertex 1.60291 1.22369 2.53403 + vertex 1.59909 1.22413 2.53529 + endloop + endfacet + facet normal 0.291088 -0.135837 0.947004 + outer loop + vertex 1.59796 1.21886 2.53488 + vertex 1.59909 1.22413 2.53529 + vertex 1.59521 1.22104 2.53604 + endloop + endfacet + facet normal 0.290801 -0.136216 0.947037 + outer loop + vertex 1.59399 1.21727 2.53587 + vertex 1.59796 1.21886 2.53488 + vertex 1.59521 1.22104 2.53604 + endloop + endfacet + facet normal 0.257136 -0.125808 0.958151 + outer loop + vertex 1.59521 1.22104 2.53604 + vertex 1.59134 1.21789 2.53666 + vertex 1.59399 1.21727 2.53587 + endloop + endfacet + facet normal 0.290509 -0.135353 0.947251 + outer loop + vertex 1.59399 1.21727 2.53587 + vertex 1.59404 1.2139 2.53537 + vertex 1.59796 1.21886 2.53488 + endloop + endfacet + facet normal 0.268486 -0.13664 0.953543 + outer loop + vertex 1.59399 1.21727 2.53587 + vertex 1.59144 1.21459 2.5362 + vertex 1.59404 1.2139 2.53537 + endloop + endfacet + facet normal 0.295942 -0.142543 0.94451 + outer loop + vertex 1.59909 1.22413 2.53529 + vertex 1.59645 1.22478 2.53621 + vertex 1.59521 1.22104 2.53604 + endloop + endfacet + facet normal 0.269402 -0.134189 0.953633 + outer loop + vertex 1.59645 1.22478 2.53621 + vertex 1.5924 1.22305 2.53711 + vertex 1.59521 1.22104 2.53604 + endloop + endfacet + facet normal 0.272057 -0.141329 0.951846 + outer loop + vertex 1.59645 1.22478 2.53621 + vertex 1.59637 1.22799 2.53671 + vertex 1.5924 1.22305 2.53711 + endloop + endfacet + facet normal 0.295471 -0.139699 0.945082 + outer loop + vertex 1.59904 1.22741 2.53579 + vertex 1.59637 1.22799 2.53671 + vertex 1.59645 1.22478 2.53621 + endloop + endfacet + facet normal 0.296434 -0.140719 0.944629 + outer loop + vertex 1.59904 1.22741 2.53579 + vertex 1.59645 1.22478 2.53621 + vertex 1.59909 1.22413 2.53529 + endloop + endfacet + facet normal 0.29846 -0.140593 0.94401 + outer loop + vertex 1.59904 1.22741 2.53579 + vertex 1.59909 1.22413 2.53529 + vertex 1.60295 1.22892 2.53478 + endloop + endfacet + facet normal 0.297187 -0.136638 0.944992 + outer loop + vertex 1.59904 1.22741 2.53579 + vertex 1.60295 1.22892 2.53478 + vertex 1.60023 1.23109 2.53595 + endloop + endfacet + facet normal 0.298127 -0.135396 0.944875 + outer loop + vertex 1.60295 1.22892 2.53478 + vertex 1.60404 1.23415 2.53519 + vertex 1.60023 1.23109 2.53595 + endloop + endfacet + facet normal 0.294861 -0.130914 0.94653 + outer loop + vertex 1.60404 1.23415 2.53519 + vertex 1.60141 1.23482 2.5361 + vertex 1.60023 1.23109 2.53595 + endloop + endfacet + facet normal 0.298341 -0.131971 0.945292 + outer loop + vertex 1.60141 1.23482 2.5361 + vertex 1.59745 1.23313 2.53711 + vertex 1.60023 1.23109 2.53595 + endloop + endfacet + facet normal 0.295764 -0.135659 0.945579 + outer loop + vertex 1.59745 1.23313 2.53711 + vertex 1.59637 1.22799 2.53671 + vertex 1.60023 1.23109 2.53595 + endloop + endfacet + facet normal 0.275878 -0.131988 0.952088 + outer loop + vertex 1.59637 1.22799 2.53671 + vertex 1.59745 1.23313 2.53711 + vertex 1.59238 1.22815 2.53789 + endloop + endfacet + facet normal 0.29717 -0.128726 0.946107 + outer loop + vertex 1.60141 1.23482 2.5361 + vertex 1.60131 1.23807 2.53657 + vertex 1.59745 1.23313 2.53711 + endloop + endfacet + facet normal 0.297821 -0.129264 0.945829 + outer loop + vertex 1.60131 1.23807 2.53657 + vertex 1.59743 1.23828 2.53782 + vertex 1.59745 1.23313 2.53711 + endloop + endfacet + facet normal 0.287115 -0.129747 0.949068 + outer loop + vertex 1.59745 1.23313 2.53711 + vertex 1.59743 1.23828 2.53782 + vertex 1.59267 1.23328 2.53858 + endloop + endfacet + facet normal 0.298197 -0.124974 0.946288 + outer loop + vertex 1.60131 1.23807 2.53657 + vertex 1.60229 1.24321 2.53694 + vertex 1.59743 1.23828 2.53782 + endloop + endfacet + facet normal 0.294758 -0.121315 0.94784 + outer loop + vertex 1.59743 1.23828 2.53782 + vertex 1.60229 1.24321 2.53694 + vertex 1.59763 1.24342 2.53842 + endloop + endfacet + facet normal 0.294909 -0.121315 0.947793 + outer loop + vertex 1.59743 1.23828 2.53782 + vertex 1.59763 1.24342 2.53842 + vertex 1.59298 1.23848 2.53923 + endloop + endfacet + facet normal 0.29828 -0.124733 0.946293 + outer loop + vertex 1.59298 1.23848 2.53923 + vertex 1.59763 1.24342 2.53842 + vertex 1.593 1.24378 2.53992 + endloop + endfacet + facet normal 0.298989 -0.118137 0.946916 + outer loop + vertex 1.59763 1.24342 2.53842 + vertex 1.59784 1.24861 2.539 + vertex 1.593 1.24378 2.53992 + endloop + endfacet + facet normal 0.301007 -0.120333 0.945999 + outer loop + vertex 1.593 1.24378 2.53992 + vertex 1.59784 1.24861 2.539 + vertex 1.59405 1.24913 2.54027 + endloop + endfacet + facet normal 0.288044 -0.118084 0.950309 + outer loop + vertex 1.593 1.24378 2.53992 + vertex 1.59405 1.24913 2.54027 + vertex 1.59025 1.24597 2.54103 + endloop + endfacet + facet normal 0.288696 -0.117221 0.950218 + outer loop + vertex 1.58911 1.24215 2.54091 + vertex 1.593 1.24378 2.53992 + vertex 1.59025 1.24597 2.54103 + endloop + endfacet + facet normal 0.228447 -0.0998027 0.968427 + outer loop + vertex 1.59025 1.24597 2.54103 + vertex 1.5865 1.24281 2.54159 + vertex 1.58911 1.24215 2.54091 + endloop + endfacet + facet normal 0.292288 -0.12724 0.947828 + outer loop + vertex 1.58911 1.24215 2.54091 + vertex 1.58919 1.23884 2.54044 + vertex 1.593 1.24378 2.53992 + endloop + endfacet + facet normal 0.253482 -0.129711 0.958604 + outer loop + vertex 1.58911 1.24215 2.54091 + vertex 1.58667 1.23954 2.5412 + vertex 1.58919 1.23884 2.54044 + endloop + endfacet + facet normal 0.294733 -0.126894 0.947117 + outer loop + vertex 1.59405 1.24913 2.54027 + vertex 1.5914 1.24978 2.54118 + vertex 1.59025 1.24597 2.54103 + endloop + endfacet + facet normal 0.246662 -0.113094 0.96248 + outer loop + vertex 1.5914 1.24978 2.54118 + vertex 1.58742 1.24799 2.54199 + vertex 1.59025 1.24597 2.54103 + endloop + endfacet + facet normal 0.251659 -0.125521 0.959642 + outer loop + vertex 1.5914 1.24978 2.54118 + vertex 1.59115 1.2529 2.54166 + vertex 1.58742 1.24799 2.54199 + endloop + endfacet + facet normal 0.291609 -0.120743 0.948886 + outer loop + vertex 1.5939 1.25247 2.54076 + vertex 1.59115 1.2529 2.54166 + vertex 1.5914 1.24978 2.54118 + endloop + endfacet + facet normal 0.29245 -0.116096 0.949207 + outer loop + vertex 1.59489 1.25621 2.54091 + vertex 1.59115 1.2529 2.54166 + vertex 1.5939 1.25247 2.54076 + endloop + endfacet + facet normal 0.305062 -0.119266 0.944835 + outer loop + vertex 1.5939 1.25247 2.54076 + vertex 1.59784 1.25395 2.53967 + vertex 1.59489 1.25621 2.54091 + endloop + endfacet + facet normal 0.30693 -0.11668 0.944553 + outer loop + vertex 1.59784 1.25395 2.53967 + vertex 1.59894 1.2595 2.54 + vertex 1.59489 1.25621 2.54091 + endloop + endfacet + facet normal 0.304814 -0.113783 0.945591 + outer loop + vertex 1.59489 1.25621 2.54091 + vertex 1.59894 1.2595 2.54 + vertex 1.59572 1.26078 2.54119 + endloop + endfacet + facet normal 0.298675 -0.1128 0.947665 + outer loop + vertex 1.59572 1.26078 2.54119 + vertex 1.59163 1.25737 2.54208 + vertex 1.59489 1.25621 2.54091 + endloop + endfacet + facet normal 0.299575 -0.113989 0.947239 + outer loop + vertex 1.59269 1.26288 2.5424 + vertex 1.59163 1.25737 2.54208 + vertex 1.59572 1.26078 2.54119 + endloop + endfacet + facet normal 0.303664 -0.10775 0.946667 + outer loop + vertex 1.59669 1.26457 2.54131 + vertex 1.59269 1.26288 2.5424 + vertex 1.59572 1.26078 2.54119 + endloop + endfacet + facet normal 0.303277 -0.107656 0.946802 + outer loop + vertex 1.59939 1.26405 2.54039 + vertex 1.59669 1.26457 2.54131 + vertex 1.59572 1.26078 2.54119 + endloop + endfacet + facet normal 0.303314 -0.107479 0.94681 + outer loop + vertex 1.59912 1.26724 2.54084 + vertex 1.59669 1.26457 2.54131 + vertex 1.59939 1.26405 2.54039 + endloop + endfacet + facet normal 0.289011 -0.109293 0.951067 + outer loop + vertex 1.59912 1.26724 2.54084 + vertex 1.59939 1.26405 2.54039 + vertex 1.60299 1.2688 2.53984 + endloop + endfacet + facet normal 0.288954 -0.10913 0.951103 + outer loop + vertex 1.59912 1.26724 2.54084 + vertex 1.60299 1.2688 2.53984 + vertex 1.60019 1.27097 2.54094 + endloop + endfacet + facet normal 0.304689 -0.113493 0.945666 + outer loop + vertex 1.60019 1.27097 2.54094 + vertex 1.59646 1.26784 2.54177 + vertex 1.59912 1.26724 2.54084 + endloop + endfacet + facet normal 0.299886 -0.107157 0.947938 + outer loop + vertex 1.59737 1.27307 2.54207 + vertex 1.59646 1.26784 2.54177 + vertex 1.60019 1.27097 2.54094 + endloop + endfacet + facet normal 0.297422 -0.110669 0.94831 + outer loop + vertex 1.60127 1.27471 2.54104 + vertex 1.59737 1.27307 2.54207 + vertex 1.60019 1.27097 2.54094 + endloop + endfacet + facet normal 0.284568 -0.107098 0.952655 + outer loop + vertex 1.60394 1.27407 2.54017 + vertex 1.60127 1.27471 2.54104 + vertex 1.60019 1.27097 2.54094 + endloop + endfacet + facet normal 0.284212 -0.108499 0.952602 + outer loop + vertex 1.60374 1.27739 2.54061 + vertex 1.60127 1.27471 2.54104 + vertex 1.60394 1.27407 2.54017 + endloop + endfacet + facet normal 0.278886 -0.109022 0.954116 + outer loop + vertex 1.60374 1.27739 2.54061 + vertex 1.60394 1.27407 2.54017 + vertex 1.60773 1.27894 2.53962 + endloop + endfacet + facet normal 0.278331 -0.107366 0.954465 + outer loop + vertex 1.60374 1.27739 2.54061 + vertex 1.60773 1.27894 2.53962 + vertex 1.60471 1.28119 2.54075 + endloop + endfacet + facet normal 0.284389 -0.108835 0.952511 + outer loop + vertex 1.60471 1.28119 2.54075 + vertex 1.60097 1.27786 2.54149 + vertex 1.60374 1.27739 2.54061 + endloop + endfacet + facet normal 0.281674 -0.105531 0.953689 + outer loop + vertex 1.60139 1.28238 2.54186 + vertex 1.60097 1.27786 2.54149 + vertex 1.60471 1.28119 2.54075 + endloop + endfacet + facet normal 0.28147 -0.106096 0.953687 + outer loop + vertex 1.60551 1.28581 2.54103 + vertex 1.60139 1.28238 2.54186 + vertex 1.60471 1.28119 2.54075 + endloop + endfacet + facet normal 0.277772 -0.105526 0.954834 + outer loop + vertex 1.60471 1.28119 2.54075 + vertex 1.60882 1.28456 2.53993 + vertex 1.60551 1.28581 2.54103 + endloop + endfacet + facet normal 0.278205 -0.104382 0.954833 + outer loop + vertex 1.60882 1.28456 2.53993 + vertex 1.60925 1.28914 2.5403 + vertex 1.60551 1.28581 2.54103 + endloop + endfacet + facet normal 0.278162 -0.10433 0.954851 + outer loop + vertex 1.60925 1.28914 2.5403 + vertex 1.60643 1.28959 2.54117 + vertex 1.60551 1.28581 2.54103 + endloop + endfacet + facet normal 0.280113 -0.104782 0.954231 + outer loop + vertex 1.60643 1.28959 2.54117 + vertex 1.60241 1.28789 2.54217 + vertex 1.60551 1.28581 2.54103 + endloop + endfacet + facet normal 0.279156 -0.102188 0.954793 + outer loop + vertex 1.60643 1.28959 2.54117 + vertex 1.60604 1.29268 2.54162 + vertex 1.60241 1.28789 2.54217 + endloop + endfacet + facet normal 0.28012 -0.102962 0.954427 + outer loop + vertex 1.60604 1.29268 2.54162 + vertex 1.6022 1.29298 2.54278 + vertex 1.60241 1.28789 2.54217 + endloop + endfacet + facet normal 0.288358 -0.102342 0.952038 + outer loop + vertex 1.60241 1.28789 2.54217 + vertex 1.6022 1.29298 2.54278 + vertex 1.59778 1.2885 2.54363 + endloop + endfacet + facet normal 0.287822 -0.10177 0.952261 + outer loop + vertex 1.59778 1.2885 2.54363 + vertex 1.6022 1.29298 2.54278 + vertex 1.59806 1.29362 2.5441 + endloop + endfacet + facet normal 0.280347 -0.100716 0.9546 + outer loop + vertex 1.60604 1.29268 2.54162 + vertex 1.60644 1.2972 2.54198 + vertex 1.6022 1.29298 2.54278 + endloop + endfacet + facet normal 0.280579 -0.100966 0.954506 + outer loop + vertex 1.6022 1.29298 2.54278 + vertex 1.60644 1.2972 2.54198 + vertex 1.60247 1.2981 2.54324 + endloop + endfacet + facet normal 0.280816 -0.0999653 0.954541 + outer loop + vertex 1.60644 1.2972 2.54198 + vertex 1.60747 1.30275 2.54226 + vertex 1.60247 1.2981 2.54324 + endloop + endfacet + facet normal 0.279488 -0.0997405 0.954954 + outer loop + vertex 1.60747 1.30275 2.54226 + vertex 1.60644 1.2972 2.54198 + vertex 1.61058 1.30065 2.54113 + endloop + endfacet + facet normal 0.280512 -0.0981558 0.954818 + outer loop + vertex 1.6115 1.30444 2.54124 + vertex 1.60747 1.30275 2.54226 + vertex 1.61058 1.30065 2.54113 + endloop + endfacet + facet normal 0.281815 -0.0984593 0.954403 + outer loop + vertex 1.61431 1.30399 2.54037 + vertex 1.6115 1.30444 2.54124 + vertex 1.61058 1.30065 2.54113 + endloop + endfacet + facet normal 0.281502 -0.0980809 0.954535 + outer loop + vertex 1.61389 1.29942 2.54002 + vertex 1.61431 1.30399 2.54037 + vertex 1.61058 1.30065 2.54113 + endloop + endfacet + facet normal 0.28103 -0.0993589 0.954542 + outer loop + vertex 1.60979 1.29603 2.54088 + vertex 1.61389 1.29942 2.54002 + vertex 1.61058 1.30065 2.54113 + endloop + endfacet + facet normal 0.281202 -0.0995856 0.954468 + outer loop + vertex 1.61286 1.29387 2.53975 + vertex 1.61389 1.29942 2.54002 + vertex 1.60979 1.29603 2.54088 + endloop + endfacet + facet normal 0.280414 -0.100765 0.954576 + outer loop + vertex 1.60888 1.29228 2.54075 + vertex 1.61286 1.29387 2.53975 + vertex 1.60979 1.29603 2.54088 + endloop + endfacet + facet normal 0.278105 -0.100227 0.955307 + outer loop + vertex 1.60979 1.29603 2.54088 + vertex 1.60604 1.29268 2.54162 + vertex 1.60888 1.29228 2.54075 + endloop + endfacet + facet normal 0.281055 -0.102614 0.95419 + outer loop + vertex 1.60888 1.29228 2.54075 + vertex 1.60925 1.28914 2.5403 + vertex 1.61286 1.29387 2.53975 + endloop + endfacet + facet normal 0.279973 -0.101739 0.954601 + outer loop + vertex 1.61286 1.29387 2.53975 + vertex 1.60925 1.28914 2.5403 + vertex 1.61305 1.28871 2.53914 + endloop + endfacet + facet normal 0.282126 -0.101589 0.953983 + outer loop + vertex 1.61305 1.28871 2.53914 + vertex 1.61747 1.29317 2.53831 + vertex 1.61286 1.29387 2.53975 + endloop + endfacet + facet normal 0.282564 -0.099 0.954126 + outer loop + vertex 1.61747 1.29317 2.53831 + vertex 1.61782 1.29845 2.53876 + vertex 1.61286 1.29387 2.53975 + endloop + endfacet + facet normal 0.285066 -0.0991032 0.953371 + outer loop + vertex 1.61747 1.29317 2.53831 + vertex 1.62245 1.29782 2.5373 + vertex 1.61782 1.29845 2.53876 + endloop + endfacet + facet normal 0.285309 -0.0975295 0.95346 + outer loop + vertex 1.62245 1.29782 2.5373 + vertex 1.62223 1.30296 2.5379 + vertex 1.61782 1.29845 2.53876 + endloop + endfacet + facet normal 0.285908 -0.0981615 0.953216 + outer loop + vertex 1.61782 1.29845 2.53876 + vertex 1.62223 1.30296 2.5379 + vertex 1.61809 1.30359 2.5392 + endloop + endfacet + facet normal 0.283851 -0.0981077 0.953836 + outer loop + vertex 1.61782 1.29845 2.53876 + vertex 1.61809 1.30359 2.5392 + vertex 1.61389 1.29942 2.54002 + endloop + endfacet + facet normal 0.288101 -0.0973147 0.952643 + outer loop + vertex 1.62607 1.30264 2.5367 + vertex 1.62223 1.30296 2.5379 + vertex 1.62245 1.29782 2.5373 + endloop + endfacet + facet normal 0.286739 -0.0962275 0.953164 + outer loop + vertex 1.62647 1.29951 2.53626 + vertex 1.62607 1.30264 2.5367 + vertex 1.62245 1.29782 2.5373 + endloop + endfacet + facet normal 0.287208 -0.0975108 0.952892 + outer loop + vertex 1.62647 1.29951 2.53626 + vertex 1.62245 1.29782 2.5373 + vertex 1.62556 1.2957 2.53615 + endloop + endfacet + facet normal 0.290297 -0.0982218 0.951882 + outer loop + vertex 1.62927 1.29905 2.53536 + vertex 1.62647 1.29951 2.53626 + vertex 1.62556 1.2957 2.53615 + endloop + endfacet + facet normal 0.289982 -0.0978405 0.952018 + outer loop + vertex 1.62886 1.29444 2.53502 + vertex 1.62927 1.29905 2.53536 + vertex 1.62556 1.2957 2.53615 + endloop + endfacet + facet normal 0.286425 -0.0987164 0.953004 + outer loop + vertex 1.62245 1.29782 2.5373 + vertex 1.62144 1.29225 2.53703 + vertex 1.62556 1.2957 2.53615 + endloop + endfacet + facet normal 0.28653 -0.0988538 0.952958 + outer loop + vertex 1.62556 1.2957 2.53615 + vertex 1.62144 1.29225 2.53703 + vertex 1.62478 1.29104 2.5359 + endloop + endfacet + facet normal 0.284452 -0.0983879 0.953628 + outer loop + vertex 1.62144 1.29225 2.53703 + vertex 1.62245 1.29782 2.5373 + vertex 1.61747 1.29317 2.53831 + endloop + endfacet + facet normal 0.283783 -0.101143 0.953539 + outer loop + vertex 1.61721 1.28804 2.53784 + vertex 1.62144 1.29225 2.53703 + vertex 1.61747 1.29317 2.53831 + endloop + endfacet + facet normal 0.28289 -0.100175 0.953907 + outer loop + vertex 1.62106 1.2877 2.53667 + vertex 1.62144 1.29225 2.53703 + vertex 1.61721 1.28804 2.53784 + endloop + endfacet + facet normal 0.282584 -0.102888 0.953709 + outer loop + vertex 1.62106 1.2877 2.53667 + vertex 1.61721 1.28804 2.53784 + vertex 1.61744 1.28291 2.53722 + endloop + endfacet + facet normal 0.2803 -0.103067 0.954363 + outer loop + vertex 1.61744 1.28291 2.53722 + vertex 1.61721 1.28804 2.53784 + vertex 1.61277 1.28355 2.53866 + endloop + endfacet + facet normal 0.279811 -0.106168 0.954167 + outer loop + vertex 1.61239 1.27823 2.53818 + vertex 1.61744 1.28291 2.53722 + vertex 1.61277 1.28355 2.53866 + endloop + endfacet + facet normal 0.277796 -0.106078 0.954765 + outer loop + vertex 1.61239 1.27823 2.53818 + vertex 1.61277 1.28355 2.53866 + vertex 1.60773 1.27894 2.53962 + endloop + endfacet + facet normal 0.277295 -0.108997 0.954582 + outer loop + vertex 1.60778 1.27355 2.53899 + vertex 1.61239 1.27823 2.53818 + vertex 1.60773 1.27894 2.53962 + endloop + endfacet + facet normal 0.276755 -0.108427 0.954804 + outer loop + vertex 1.61211 1.27305 2.53768 + vertex 1.61239 1.27823 2.53818 + vertex 1.60778 1.27355 2.53899 + endloop + endfacet + facet normal 0.276418 -0.110854 0.954623 + outer loop + vertex 1.60761 1.26832 2.53843 + vertex 1.61211 1.27305 2.53768 + vertex 1.60778 1.27355 2.53899 + endloop + endfacet + facet normal 0.279828 -0.11086 0.953628 + outer loop + vertex 1.60761 1.26832 2.53843 + vertex 1.60778 1.27355 2.53899 + vertex 1.60299 1.2688 2.53984 + endloop + endfacet + facet normal 0.279778 -0.111255 0.953597 + outer loop + vertex 1.60315 1.26365 2.53919 + vertex 1.60761 1.26832 2.53843 + vertex 1.60299 1.2688 2.53984 + endloop + endfacet + facet normal 0.280616 -0.112112 0.95325 + outer loop + vertex 1.60744 1.26313 2.53787 + vertex 1.60761 1.26832 2.53843 + vertex 1.60315 1.26365 2.53919 + endloop + endfacet + facet normal 0.280566 -0.112461 0.953224 + outer loop + vertex 1.60285 1.25851 2.53867 + vertex 1.60744 1.26313 2.53787 + vertex 1.60315 1.26365 2.53919 + endloop + endfacet + facet normal 0.293314 -0.112814 0.949336 + outer loop + vertex 1.60285 1.25851 2.53867 + vertex 1.60315 1.26365 2.53919 + vertex 1.59894 1.2595 2.54 + endloop + endfacet + facet normal 0.290619 -0.109856 0.950512 + outer loop + vertex 1.59894 1.2595 2.54 + vertex 1.60315 1.26365 2.53919 + vertex 1.59939 1.26405 2.54039 + endloop + endfacet + facet normal 0.281584 -0.113546 0.952795 + outer loop + vertex 1.6075 1.25787 2.53722 + vertex 1.60744 1.26313 2.53787 + vertex 1.60285 1.25851 2.53867 + endloop + endfacet + facet normal 0.281238 -0.115714 0.952636 + outer loop + vertex 1.60242 1.25324 2.53816 + vertex 1.6075 1.25787 2.53722 + vertex 1.60285 1.25851 2.53867 + endloop + endfacet + facet normal 0.294815 -0.116409 0.948437 + outer loop + vertex 1.60242 1.25324 2.53816 + vertex 1.60285 1.25851 2.53867 + vertex 1.59784 1.25395 2.53967 + endloop + endfacet + facet normal 0.294274 -0.119444 0.948228 + outer loop + vertex 1.59784 1.24861 2.539 + vertex 1.60242 1.25324 2.53816 + vertex 1.59784 1.25395 2.53967 + endloop + endfacet + facet normal 0.293558 -0.118677 0.948546 + outer loop + vertex 1.60211 1.24817 2.53762 + vertex 1.60242 1.25324 2.53816 + vertex 1.59784 1.24861 2.539 + endloop + endfacet + facet normal 0.283121 -0.118373 0.951751 + outer loop + vertex 1.60211 1.24817 2.53762 + vertex 1.60638 1.25239 2.53688 + vertex 1.60242 1.25324 2.53816 + endloop + endfacet + facet normal 0.283198 -0.118037 0.95177 + outer loop + vertex 1.60638 1.25239 2.53688 + vertex 1.6075 1.25787 2.53722 + vertex 1.60242 1.25324 2.53816 + endloop + endfacet + facet normal 0.275816 -0.113812 0.954449 + outer loop + vertex 1.61134 1.26274 2.53669 + vertex 1.60744 1.26313 2.53787 + vertex 1.6075 1.25787 2.53722 + endloop + endfacet + facet normal 0.27506 -0.113184 0.954742 + outer loop + vertex 1.61154 1.25949 2.53625 + vertex 1.61134 1.26274 2.53669 + vertex 1.6075 1.25787 2.53722 + endloop + endfacet + facet normal 0.276151 -0.116327 0.954048 + outer loop + vertex 1.61154 1.25949 2.53625 + vertex 1.6075 1.25787 2.53722 + vertex 1.61053 1.25573 2.53609 + endloop + endfacet + facet normal 0.276163 -0.113075 0.954436 + outer loop + vertex 1.61406 1.26217 2.53584 + vertex 1.61134 1.26274 2.53669 + vertex 1.61154 1.25949 2.53625 + endloop + endfacet + facet normal 0.278424 -0.115342 0.953507 + outer loop + vertex 1.61406 1.26217 2.53584 + vertex 1.61154 1.25949 2.53625 + vertex 1.61431 1.25901 2.53539 + endloop + endfacet + facet normal 0.276395 -0.112059 0.954489 + outer loop + vertex 1.61517 1.2659 2.53596 + vertex 1.61134 1.26274 2.53669 + vertex 1.61406 1.26217 2.53584 + endloop + endfacet + facet normal 0.281678 -0.113582 0.952763 + outer loop + vertex 1.61406 1.26217 2.53584 + vertex 1.61798 1.26379 2.53487 + vertex 1.61517 1.2659 2.53596 + endloop + endfacet + facet normal 0.281816 -0.11339 0.952745 + outer loop + vertex 1.61798 1.26379 2.53487 + vertex 1.61898 1.26905 2.53521 + vertex 1.61517 1.2659 2.53596 + endloop + endfacet + facet normal 0.282172 -0.113859 0.952583 + outer loop + vertex 1.61898 1.26905 2.53521 + vertex 1.61629 1.26966 2.53607 + vertex 1.61517 1.2659 2.53596 + endloop + endfacet + facet normal 0.276752 -0.112299 0.954357 + outer loop + vertex 1.61629 1.26966 2.53607 + vertex 1.6123 1.26796 2.53703 + vertex 1.61517 1.2659 2.53596 + endloop + endfacet + facet normal 0.275879 -0.109964 0.954882 + outer loop + vertex 1.61629 1.26966 2.53607 + vertex 1.616 1.27281 2.53652 + vertex 1.6123 1.26796 2.53703 + endloop + endfacet + facet normal 0.276409 -0.11039 0.954679 + outer loop + vertex 1.616 1.27281 2.53652 + vertex 1.61211 1.27305 2.53768 + vertex 1.6123 1.26796 2.53703 + endloop + endfacet + facet normal 0.276669 -0.11242 0.954367 + outer loop + vertex 1.6123 1.26796 2.53703 + vertex 1.61134 1.26274 2.53669 + vertex 1.61517 1.2659 2.53596 + endloop + endfacet + facet normal 0.276003 -0.11231 0.954573 + outer loop + vertex 1.61134 1.26274 2.53669 + vertex 1.6123 1.26796 2.53703 + vertex 1.60744 1.26313 2.53787 + endloop + endfacet + facet normal 0.275818 -0.11211 0.95465 + outer loop + vertex 1.60744 1.26313 2.53787 + vertex 1.6123 1.26796 2.53703 + vertex 1.60761 1.26832 2.53843 + endloop + endfacet + facet normal 0.278673 -0.109607 0.954111 + outer loop + vertex 1.60299 1.2688 2.53984 + vertex 1.60778 1.27355 2.53899 + vertex 1.60394 1.27407 2.54017 + endloop + endfacet + facet normal 0.275992 -0.110421 0.954796 + outer loop + vertex 1.6123 1.26796 2.53703 + vertex 1.61211 1.27305 2.53768 + vertex 1.60761 1.26832 2.53843 + endloop + endfacet + facet normal 0.277798 -0.108454 0.954498 + outer loop + vertex 1.61211 1.27305 2.53768 + vertex 1.61642 1.27736 2.53691 + vertex 1.61239 1.27823 2.53818 + endloop + endfacet + facet normal 0.278353 -0.106734 0.95453 + outer loop + vertex 1.60773 1.27894 2.53962 + vertex 1.61277 1.28355 2.53866 + vertex 1.60882 1.28456 2.53993 + endloop + endfacet + facet normal 0.279097 -0.103924 0.954623 + outer loop + vertex 1.61277 1.28355 2.53866 + vertex 1.61305 1.28871 2.53914 + vertex 1.60882 1.28456 2.53993 + endloop + endfacet + facet normal 0.278637 -0.104801 0.954661 + outer loop + vertex 1.61642 1.27736 2.53691 + vertex 1.61744 1.28291 2.53722 + vertex 1.61239 1.27823 2.53818 + endloop + endfacet + facet normal 0.281155 -0.103977 0.954013 + outer loop + vertex 1.61277 1.28355 2.53866 + vertex 1.61721 1.28804 2.53784 + vertex 1.61305 1.28871 2.53914 + endloop + endfacet + facet normal 0.281664 -0.101096 0.954173 + outer loop + vertex 1.61721 1.28804 2.53784 + vertex 1.61747 1.29317 2.53831 + vertex 1.61305 1.28871 2.53914 + endloop + endfacet + facet normal 0.28338 -0.0999585 0.953784 + outer loop + vertex 1.61286 1.29387 2.53975 + vertex 1.61782 1.29845 2.53876 + vertex 1.61389 1.29942 2.54002 + endloop + endfacet + facet normal 0.281021 -0.0995507 0.954524 + outer loop + vertex 1.6115 1.30444 2.54124 + vertex 1.6111 1.30757 2.54169 + vertex 1.60747 1.30275 2.54226 + endloop + endfacet + facet normal 0.283156 -0.101256 0.953714 + outer loop + vertex 1.6111 1.30757 2.54169 + vertex 1.60726 1.30791 2.54287 + vertex 1.60747 1.30275 2.54226 + endloop + endfacet + facet normal 0.281809 -0.101357 0.954102 + outer loop + vertex 1.60747 1.30275 2.54226 + vertex 1.60726 1.30791 2.54287 + vertex 1.60283 1.30339 2.54369 + endloop + endfacet + facet normal 0.283851 -0.10351 0.953265 + outer loop + vertex 1.60283 1.30339 2.54369 + vertex 1.60726 1.30791 2.54287 + vertex 1.60312 1.30855 2.54417 + endloop + endfacet + facet normal 0.283752 -0.104087 0.953232 + outer loop + vertex 1.60726 1.30791 2.54287 + vertex 1.60752 1.31306 2.54335 + vertex 1.60312 1.30855 2.54417 + endloop + endfacet + facet normal 0.285632 -0.106064 0.952452 + outer loop + vertex 1.60312 1.30855 2.54417 + vertex 1.60752 1.31306 2.54335 + vertex 1.60296 1.31373 2.54479 + endloop + endfacet + facet normal 0.286171 -0.102812 0.952647 + outer loop + vertex 1.60752 1.31306 2.54335 + vertex 1.60787 1.31836 2.54382 + vertex 1.60296 1.31373 2.54479 + endloop + endfacet + facet normal 0.286213 -0.102861 0.952629 + outer loop + vertex 1.60296 1.31373 2.54479 + vertex 1.60787 1.31836 2.54382 + vertex 1.60397 1.31929 2.54509 + endloop + endfacet + facet normal 0.287983 -0.0957434 0.952837 + outer loop + vertex 1.60787 1.31836 2.54382 + vertex 1.60812 1.32353 2.54426 + vertex 1.60397 1.31929 2.54509 + endloop + endfacet + facet normal 0.286303 -0.0939603 0.953521 + outer loop + vertex 1.60397 1.31929 2.54509 + vertex 1.60812 1.32353 2.54426 + vertex 1.60435 1.32389 2.54543 + endloop + endfacet + facet normal 0.287307 -0.0851485 0.954046 + outer loop + vertex 1.6079 1.32876 2.54479 + vertex 1.60435 1.32389 2.54543 + vertex 1.60812 1.32353 2.54426 + endloop + endfacet + facet normal 0.287957 -0.0851015 0.953855 + outer loop + vertex 1.60812 1.32353 2.54426 + vertex 1.61249 1.32813 2.54335 + vertex 1.6079 1.32876 2.54479 + endloop + endfacet + facet normal 0.288888 -0.0788961 0.954106 + outer loop + vertex 1.61249 1.32813 2.54335 + vertex 1.6128 1.33349 2.5437 + vertex 1.6079 1.32876 2.54479 + endloop + endfacet + facet normal 0.288575 -0.0785446 0.95423 + outer loop + vertex 1.6079 1.32876 2.54479 + vertex 1.6128 1.33349 2.5437 + vertex 1.60887 1.33444 2.54497 + endloop + endfacet + facet normal 0.284628 -0.0779086 0.955467 + outer loop + vertex 1.6079 1.32876 2.54479 + vertex 1.60887 1.33444 2.54497 + vertex 1.6048 1.33093 2.5459 + endloop + endfacet + facet normal 0.284242 -0.0784938 0.955534 + outer loop + vertex 1.60394 1.32706 2.54583 + vertex 1.6079 1.32876 2.54479 + vertex 1.6048 1.33093 2.5459 + endloop + endfacet + facet normal 0.279753 -0.0775197 0.956937 + outer loop + vertex 1.6048 1.33093 2.5459 + vertex 1.60108 1.32754 2.54671 + vertex 1.60394 1.32706 2.54583 + endloop + endfacet + facet normal 0.27912 -0.0767675 0.957183 + outer loop + vertex 1.60141 1.33221 2.54699 + vertex 1.60108 1.32754 2.54671 + vertex 1.6048 1.33093 2.5459 + endloop + endfacet + facet normal 0.279528 -0.0756632 0.957151 + outer loop + vertex 1.60552 1.33569 2.54606 + vertex 1.60141 1.33221 2.54699 + vertex 1.6048 1.33093 2.5459 + endloop + endfacet + facet normal 0.278593 -0.0744604 0.957519 + outer loop + vertex 1.60237 1.33786 2.54715 + vertex 1.60141 1.33221 2.54699 + vertex 1.60552 1.33569 2.54606 + endloop + endfacet + facet normal 0.278504 -0.074597 0.957534 + outer loop + vertex 1.60638 1.33958 2.54611 + vertex 1.60237 1.33786 2.54715 + vertex 1.60552 1.33569 2.54606 + endloop + endfacet + facet normal 0.284235 -0.07583 0.955751 + outer loop + vertex 1.60922 1.33914 2.54524 + vertex 1.60638 1.33958 2.54611 + vertex 1.60552 1.33569 2.54606 + endloop + endfacet + facet normal 0.283653 -0.0751526 0.955977 + outer loop + vertex 1.60887 1.33444 2.54497 + vertex 1.60922 1.33914 2.54524 + vertex 1.60552 1.33569 2.54606 + endloop + endfacet + facet normal 0.290174 -0.0755134 0.95399 + outer loop + vertex 1.60887 1.33444 2.54497 + vertex 1.61297 1.3387 2.54406 + vertex 1.60922 1.33914 2.54524 + endloop + endfacet + facet normal 0.290671 -0.0716576 0.954136 + outer loop + vertex 1.61266 1.34393 2.54455 + vertex 1.60922 1.33914 2.54524 + vertex 1.61297 1.3387 2.54406 + endloop + endfacet + facet normal 0.29496 -0.0712821 0.952847 + outer loop + vertex 1.61297 1.3387 2.54406 + vertex 1.61708 1.34305 2.54311 + vertex 1.61266 1.34393 2.54455 + endloop + endfacet + facet normal 0.295789 -0.0671598 0.952889 + outer loop + vertex 1.61708 1.34305 2.54311 + vertex 1.61735 1.34824 2.5434 + vertex 1.61266 1.34393 2.54455 + endloop + endfacet + facet normal 0.296313 -0.067784 0.952683 + outer loop + vertex 1.61266 1.34393 2.54455 + vertex 1.61735 1.34824 2.5434 + vertex 1.61357 1.34962 2.54467 + endloop + endfacet + facet normal 0.291677 -0.067079 0.954162 + outer loop + vertex 1.61266 1.34393 2.54455 + vertex 1.61357 1.34962 2.54467 + vertex 1.6095 1.34617 2.54567 + endloop + endfacet + facet normal 0.290405 -0.0689985 0.954413 + outer loop + vertex 1.60876 1.34235 2.54562 + vertex 1.61266 1.34393 2.54455 + vertex 1.6095 1.34617 2.54567 + endloop + endfacet + facet normal 0.281487 -0.0672963 0.957202 + outer loop + vertex 1.6095 1.34617 2.54567 + vertex 1.60587 1.3427 2.54649 + vertex 1.60876 1.34235 2.54562 + endloop + endfacet + facet normal 0.281079 -0.0703624 0.957102 + outer loop + vertex 1.60876 1.34235 2.54562 + vertex 1.60587 1.3427 2.54649 + vertex 1.60638 1.33958 2.54611 + endloop + endfacet + facet normal 0.282261 -0.0681781 0.956912 + outer loop + vertex 1.606 1.34716 2.54677 + vertex 1.60587 1.3427 2.54649 + vertex 1.6095 1.34617 2.54567 + endloop + endfacet + facet normal 0.283035 -0.0653952 0.956878 + outer loop + vertex 1.61 1.35098 2.54585 + vertex 1.606 1.34716 2.54677 + vertex 1.6095 1.34617 2.54567 + endloop + endfacet + facet normal 0.283847 -0.066319 0.956573 + outer loop + vertex 1.60639 1.35216 2.547 + vertex 1.606 1.34716 2.54677 + vertex 1.61 1.35098 2.54585 + endloop + endfacet + facet normal 0.284491 -0.0642887 0.956521 + outer loop + vertex 1.61052 1.35585 2.54602 + vertex 1.60639 1.35216 2.547 + vertex 1.61 1.35098 2.54585 + endloop + endfacet + facet normal 0.291839 -0.0649937 0.954257 + outer loop + vertex 1.61 1.35098 2.54585 + vertex 1.61401 1.35471 2.54488 + vertex 1.61052 1.35585 2.54602 + endloop + endfacet + facet normal 0.292123 -0.0641046 0.95423 + outer loop + vertex 1.61401 1.35471 2.54488 + vertex 1.61417 1.35932 2.54514 + vertex 1.61052 1.35585 2.54602 + endloop + endfacet + facet normal 0.29331 -0.0654693 0.953773 + outer loop + vertex 1.61417 1.35932 2.54514 + vertex 1.6113 1.35976 2.54605 + vertex 1.61052 1.35585 2.54602 + endloop + endfacet + facet normal 0.286504 -0.0641426 0.95593 + outer loop + vertex 1.6113 1.35976 2.54605 + vertex 1.60731 1.35792 2.54713 + vertex 1.61052 1.35585 2.54602 + endloop + endfacet + facet normal 0.286306 -0.0636616 0.956021 + outer loop + vertex 1.6113 1.35976 2.54605 + vertex 1.61079 1.36287 2.54641 + vertex 1.60731 1.35792 2.54713 + endloop + endfacet + facet normal 0.287601 -0.0646395 0.955567 + outer loop + vertex 1.61079 1.36287 2.54641 + vertex 1.60699 1.36304 2.54757 + vertex 1.60731 1.35792 2.54713 + endloop + endfacet + facet normal 0.284576 -0.064904 0.956454 + outer loop + vertex 1.60731 1.35792 2.54713 + vertex 1.60699 1.36304 2.54757 + vertex 1.60269 1.35846 2.54853 + endloop + endfacet + facet normal 0.284267 -0.0673545 0.956376 + outer loop + vertex 1.60238 1.35308 2.54825 + vertex 1.60731 1.35792 2.54713 + vertex 1.60269 1.35846 2.54853 + endloop + endfacet + facet normal 0.283649 -0.0673284 0.956562 + outer loop + vertex 1.60238 1.35308 2.54825 + vertex 1.60269 1.35846 2.54853 + vertex 1.5978 1.35376 2.54966 + endloop + endfacet + facet normal 0.283383 -0.0690515 0.956518 + outer loop + vertex 1.59808 1.34856 2.5492 + vertex 1.60238 1.35308 2.54825 + vertex 1.5978 1.35376 2.54966 + endloop + endfacet + facet normal 0.28797 -0.0686785 0.955174 + outer loop + vertex 1.5978 1.35376 2.54966 + vertex 1.59434 1.34895 2.55035 + vertex 1.59808 1.34856 2.5492 + endloop + endfacet + facet normal 0.288101 -0.0675576 0.955214 + outer loop + vertex 1.59418 1.34449 2.55008 + vertex 1.59808 1.34856 2.5492 + vertex 1.59434 1.34895 2.55035 + endloop + endfacet + facet normal 0.290024 -0.0695588 0.954488 + outer loop + vertex 1.59798 1.34362 2.54887 + vertex 1.59808 1.34856 2.5492 + vertex 1.59418 1.34449 2.55008 + endloop + endfacet + facet normal 0.290239 -0.068622 0.954491 + outer loop + vertex 1.59393 1.33967 2.54982 + vertex 1.59798 1.34362 2.54887 + vertex 1.59418 1.34449 2.55008 + endloop + endfacet + facet normal 0.305337 -0.0691657 0.949729 + outer loop + vertex 1.59393 1.33967 2.54982 + vertex 1.59418 1.34449 2.55008 + vertex 1.59032 1.34084 2.55106 + endloop + endfacet + facet normal 0.305926 -0.067286 0.949675 + outer loop + vertex 1.58998 1.33604 2.55083 + vertex 1.59393 1.33967 2.54982 + vertex 1.59032 1.34084 2.55106 + endloop + endfacet + facet normal 0.308864 -0.0674474 0.948712 + outer loop + vertex 1.59032 1.34084 2.55106 + vertex 1.58636 1.33707 2.55208 + vertex 1.58998 1.33604 2.55083 + endloop + endfacet + facet normal 0.308203 -0.0698182 0.948755 + outer loop + vertex 1.58636 1.33707 2.55208 + vertex 1.58613 1.33234 2.55181 + vertex 1.58998 1.33604 2.55083 + endloop + endfacet + facet normal 0.308866 -0.0705827 0.948483 + outer loop + vertex 1.58998 1.33604 2.55083 + vertex 1.58613 1.33234 2.55181 + vertex 1.58951 1.33134 2.55063 + endloop + endfacet + facet normal 0.309579 -0.0706438 0.948246 + outer loop + vertex 1.58951 1.33134 2.55063 + vertex 1.59353 1.33466 2.54957 + vertex 1.58998 1.33604 2.55083 + endloop + endfacet + facet normal 0.313432 -0.0758468 0.946577 + outer loop + vertex 1.59262 1.32901 2.54941 + vertex 1.59353 1.33466 2.54957 + vertex 1.58951 1.33134 2.55063 + endloop + endfacet + facet normal 0.313918 -0.075146 0.946472 + outer loop + vertex 1.58873 1.3276 2.55059 + vertex 1.59262 1.32901 2.54941 + vertex 1.58951 1.33134 2.55063 + endloop + endfacet + facet normal 0.308423 -0.0740188 0.948365 + outer loop + vertex 1.58951 1.33134 2.55063 + vertex 1.58597 1.32802 2.55152 + vertex 1.58873 1.3276 2.55059 + endloop + endfacet + facet normal 0.307529 -0.079556 0.948207 + outer loop + vertex 1.58873 1.3276 2.55059 + vertex 1.58597 1.32802 2.55152 + vertex 1.58639 1.32493 2.55113 + endloop + endfacet + facet normal 0.314747 -0.0865052 0.945225 + outer loop + vertex 1.58873 1.3276 2.55059 + vertex 1.58639 1.32493 2.55113 + vertex 1.58915 1.32437 2.55016 + endloop + endfacet + facet normal 0.312333 -0.0978255 0.944922 + outer loop + vertex 1.58915 1.32437 2.55016 + vertex 1.58639 1.32493 2.55113 + vertex 1.58548 1.32108 2.55103 + endloop + endfacet + facet normal 0.307544 -0.0919262 0.947083 + outer loop + vertex 1.58877 1.31968 2.54983 + vertex 1.58915 1.32437 2.55016 + vertex 1.58548 1.32108 2.55103 + endloop + endfacet + facet normal 0.265055 -0.0871529 0.960287 + outer loop + vertex 1.58639 1.32493 2.55113 + vertex 1.58242 1.32308 2.55206 + vertex 1.58548 1.32108 2.55103 + endloop + endfacet + facet normal 0.264916 -0.0868214 0.960355 + outer loop + vertex 1.58639 1.32493 2.55113 + vertex 1.58597 1.32802 2.55152 + vertex 1.58242 1.32308 2.55206 + endloop + endfacet + facet normal 0.317253 -0.0860782 0.944426 + outer loop + vertex 1.58873 1.3276 2.55059 + vertex 1.58915 1.32437 2.55016 + vertex 1.59262 1.32901 2.54941 + endloop + endfacet + facet normal 0.311967 -0.0817695 0.946568 + outer loop + vertex 1.59262 1.32901 2.54941 + vertex 1.58915 1.32437 2.55016 + vertex 1.59297 1.32371 2.54884 + endloop + endfacet + facet normal 0.295223 -0.0730995 0.952628 + outer loop + vertex 1.59262 1.32901 2.54941 + vertex 1.59747 1.33336 2.54825 + vertex 1.59353 1.33466 2.54957 + endloop + endfacet + facet normal 0.295173 -0.073255 0.952631 + outer loop + vertex 1.59747 1.33336 2.54825 + vertex 1.59784 1.33863 2.54854 + vertex 1.59353 1.33466 2.54957 + endloop + endfacet + facet normal 0.292685 -0.0702947 0.953621 + outer loop + vertex 1.59353 1.33466 2.54957 + vertex 1.59784 1.33863 2.54854 + vertex 1.59393 1.33967 2.54982 + endloop + endfacet + facet normal 0.281495 -0.0725215 0.956818 + outer loop + vertex 1.59747 1.33336 2.54825 + vertex 1.60237 1.33786 2.54715 + vertex 1.59784 1.33863 2.54854 + endloop + endfacet + facet normal 0.281696 -0.0713814 0.956845 + outer loop + vertex 1.60237 1.33786 2.54715 + vertex 1.60202 1.34294 2.54763 + vertex 1.59784 1.33863 2.54854 + endloop + endfacet + facet normal 0.281371 -0.0710414 0.956966 + outer loop + vertex 1.59784 1.33863 2.54854 + vertex 1.60202 1.34294 2.54763 + vertex 1.59798 1.34362 2.54887 + endloop + endfacet + facet normal 0.281684 -0.0692412 0.957006 + outer loop + vertex 1.60202 1.34294 2.54763 + vertex 1.60212 1.34788 2.54796 + vertex 1.59798 1.34362 2.54887 + endloop + endfacet + facet normal 0.279338 -0.0692401 0.957693 + outer loop + vertex 1.60202 1.34294 2.54763 + vertex 1.606 1.34716 2.54677 + vertex 1.60212 1.34788 2.54796 + endloop + endfacet + facet normal 0.277972 -0.0717355 0.957907 + outer loop + vertex 1.60587 1.3427 2.54649 + vertex 1.60202 1.34294 2.54763 + vertex 1.60237 1.33786 2.54715 + endloop + endfacet + facet normal 0.298517 -0.0771252 0.951283 + outer loop + vertex 1.59718 1.32807 2.54791 + vertex 1.59747 1.33336 2.54825 + vertex 1.59262 1.32901 2.54941 + endloop + endfacet + facet normal 0.283471 -0.0765944 0.955917 + outer loop + vertex 1.59718 1.32807 2.54791 + vertex 1.60141 1.33221 2.54699 + vertex 1.59747 1.33336 2.54825 + endloop + endfacet + facet normal 0.308011 -0.0735331 0.948537 + outer loop + vertex 1.58613 1.33234 2.55181 + vertex 1.58597 1.32802 2.55152 + vertex 1.58951 1.33134 2.55063 + endloop + endfacet + facet normal 0.263961 -0.0727735 0.961784 + outer loop + vertex 1.58597 1.32802 2.55152 + vertex 1.58613 1.33234 2.55181 + vertex 1.58215 1.32804 2.55257 + endloop + endfacet + facet normal 0.271019 -0.068697 0.960119 + outer loop + vertex 1.58613 1.33234 2.55181 + vertex 1.58636 1.33707 2.55208 + vertex 1.58218 1.33284 2.55296 + endloop + endfacet + facet normal 0.308329 -0.0668255 0.94893 + outer loop + vertex 1.5867 1.34204 2.55232 + vertex 1.58636 1.33707 2.55208 + vertex 1.59032 1.34084 2.55106 + endloop + endfacet + facet normal 0.308763 -0.0654726 0.948883 + outer loop + vertex 1.59076 1.34558 2.55124 + vertex 1.5867 1.34204 2.55232 + vertex 1.59032 1.34084 2.55106 + endloop + endfacet + facet normal 0.308129 -0.0646638 0.949144 + outer loop + vertex 1.58754 1.3477 2.55243 + vertex 1.5867 1.34204 2.55232 + vertex 1.59076 1.34558 2.55124 + endloop + endfacet + facet normal 0.307823 -0.0651647 0.94921 + outer loop + vertex 1.5915 1.3494 2.55126 + vertex 1.58754 1.3477 2.55243 + vertex 1.59076 1.34558 2.55124 + endloop + endfacet + facet normal 0.296746 -0.0630252 0.952875 + outer loop + vertex 1.59434 1.34895 2.55035 + vertex 1.5915 1.3494 2.55126 + vertex 1.59076 1.34558 2.55124 + endloop + endfacet + facet normal 0.300806 -0.0677508 0.951276 + outer loop + vertex 1.59418 1.34449 2.55008 + vertex 1.59434 1.34895 2.55035 + vertex 1.59076 1.34558 2.55124 + endloop + endfacet + facet normal 0.296186 -0.0664732 0.952814 + outer loop + vertex 1.59385 1.35212 2.55072 + vertex 1.5915 1.3494 2.55126 + vertex 1.59434 1.34895 2.55035 + endloop + endfacet + facet normal 0.299104 -0.0692104 0.951707 + outer loop + vertex 1.59385 1.35212 2.55072 + vertex 1.59099 1.35253 2.55165 + vertex 1.5915 1.3494 2.55126 + endloop + endfacet + facet normal 0.29871 -0.0717829 0.95164 + outer loop + vertex 1.59463 1.35595 2.55077 + vertex 1.59099 1.35253 2.55165 + vertex 1.59385 1.35212 2.55072 + endloop + endfacet + facet normal 0.287807 -0.0696223 0.955154 + outer loop + vertex 1.59385 1.35212 2.55072 + vertex 1.5978 1.35376 2.54966 + vertex 1.59463 1.35595 2.55077 + endloop + endfacet + facet normal 0.288138 -0.0691128 0.955092 + outer loop + vertex 1.5978 1.35376 2.54966 + vertex 1.59873 1.35947 2.54979 + vertex 1.59463 1.35595 2.55077 + endloop + endfacet + facet normal 0.288261 -0.0692698 0.955043 + outer loop + vertex 1.59463 1.35595 2.55077 + vertex 1.59873 1.35947 2.54979 + vertex 1.59517 1.36077 2.55096 + endloop + endfacet + facet normal 0.296662 -0.070115 0.952405 + outer loop + vertex 1.59517 1.36077 2.55096 + vertex 1.59114 1.35703 2.55194 + vertex 1.59463 1.35595 2.55077 + endloop + endfacet + facet normal 0.296332 -0.0697237 0.952537 + outer loop + vertex 1.59158 1.36206 2.55217 + vertex 1.59114 1.35703 2.55194 + vertex 1.59517 1.36077 2.55096 + endloop + endfacet + facet normal 0.297064 -0.0676216 0.95246 + outer loop + vertex 1.59571 1.3656 2.55113 + vertex 1.59158 1.36206 2.55217 + vertex 1.59517 1.36077 2.55096 + endloop + endfacet + facet normal 0.288553 -0.0667741 0.955133 + outer loop + vertex 1.59517 1.36077 2.55096 + vertex 1.59915 1.36449 2.55001 + vertex 1.59571 1.3656 2.55113 + endloop + endfacet + facet normal 0.289481 -0.0638022 0.955055 + outer loop + vertex 1.59915 1.36449 2.55001 + vertex 1.59931 1.36902 2.55027 + vertex 1.59571 1.3656 2.55113 + endloop + endfacet + facet normal 0.288402 -0.062565 0.955463 + outer loop + vertex 1.59931 1.36902 2.55027 + vertex 1.59646 1.36945 2.55116 + vertex 1.59571 1.3656 2.55113 + endloop + endfacet + facet normal 0.296845 -0.064188 0.952766 + outer loop + vertex 1.59646 1.36945 2.55116 + vertex 1.59251 1.36778 2.55227 + vertex 1.59571 1.3656 2.55113 + endloop + endfacet + facet normal 0.295 -0.0592525 0.953658 + outer loop + vertex 1.59646 1.36945 2.55116 + vertex 1.59591 1.3726 2.55152 + vertex 1.59251 1.36778 2.55227 + endloop + endfacet + facet normal 0.289229 -0.0604581 0.955349 + outer loop + vertex 1.59878 1.3722 2.55063 + vertex 1.59591 1.3726 2.55152 + vertex 1.59646 1.36945 2.55116 + endloop + endfacet + facet normal 0.289521 -0.0584463 0.955385 + outer loop + vertex 1.59947 1.37603 2.55065 + vertex 1.59591 1.3726 2.55152 + vertex 1.59878 1.3722 2.55063 + endloop + endfacet + facet normal 0.286716 -0.0579449 0.956262 + outer loop + vertex 1.59878 1.3722 2.55063 + vertex 1.60266 1.37378 2.54956 + vertex 1.59947 1.37603 2.55065 + endloop + endfacet + facet normal 0.287411 -0.056887 0.956117 + outer loop + vertex 1.60266 1.37378 2.54956 + vertex 1.60351 1.37948 2.54964 + vertex 1.59947 1.37603 2.55065 + endloop + endfacet + facet normal 0.287077 -0.0564597 0.956242 + outer loop + vertex 1.59947 1.37603 2.55065 + vertex 1.60351 1.37948 2.54964 + vertex 1.59987 1.38086 2.55082 + endloop + endfacet + facet normal 0.290034 -0.056674 0.955337 + outer loop + vertex 1.59987 1.38086 2.55082 + vertex 1.59595 1.37707 2.55178 + vertex 1.59947 1.37603 2.55065 + endloop + endfacet + facet normal 0.290153 -0.0568074 0.955293 + outer loop + vertex 1.59615 1.382 2.55201 + vertex 1.59595 1.37707 2.55178 + vertex 1.59987 1.38086 2.55082 + endloop + endfacet + facet normal 0.290719 -0.0548869 0.955233 + outer loop + vertex 1.60018 1.38582 2.55101 + vertex 1.59615 1.382 2.55201 + vertex 1.59987 1.38086 2.55082 + endloop + endfacet + facet normal 0.288222 -0.0547607 0.955997 + outer loop + vertex 1.59987 1.38086 2.55082 + vertex 1.60389 1.38462 2.54982 + vertex 1.60018 1.38582 2.55101 + endloop + endfacet + facet normal 0.28921 -0.0515869 0.955875 + outer loop + vertex 1.60389 1.38462 2.54982 + vertex 1.6041 1.38956 2.55002 + vertex 1.60018 1.38582 2.55101 + endloop + endfacet + facet normal 0.289806 -0.0522693 0.955657 + outer loop + vertex 1.60018 1.38582 2.55101 + vertex 1.6041 1.38956 2.55002 + vertex 1.60059 1.39068 2.55115 + endloop + endfacet + facet normal 0.291463 -0.0523948 0.955146 + outer loop + vertex 1.60059 1.39068 2.55115 + vertex 1.59654 1.38715 2.55219 + vertex 1.60018 1.38582 2.55101 + endloop + endfacet + facet normal 0.29081 -0.0489771 0.955527 + outer loop + vertex 1.6041 1.38956 2.55002 + vertex 1.60416 1.3941 2.55024 + vertex 1.60059 1.39068 2.55115 + endloop + endfacet + facet normal 0.291562 -0.0498363 0.955253 + outer loop + vertex 1.60416 1.3941 2.55024 + vertex 1.6013 1.39454 2.55114 + vertex 1.60059 1.39068 2.55115 + endloop + endfacet + facet normal 0.292122 -0.04994 0.955076 + outer loop + vertex 1.6013 1.39454 2.55114 + vertex 1.5974 1.39286 2.55224 + vertex 1.60059 1.39068 2.55115 + endloop + endfacet + facet normal 0.291196 -0.0475135 0.955483 + outer loop + vertex 1.6013 1.39454 2.55114 + vertex 1.60077 1.39766 2.55145 + vertex 1.5974 1.39286 2.55224 + endloop + endfacet + facet normal 0.293975 -0.0496208 0.954524 + outer loop + vertex 1.60077 1.39766 2.55145 + vertex 1.59698 1.39796 2.55264 + vertex 1.5974 1.39286 2.55224 + endloop + endfacet + facet normal 0.294182 -0.0471656 0.954585 + outer loop + vertex 1.60077 1.39766 2.55145 + vertex 1.60084 1.40212 2.55165 + vertex 1.59698 1.39796 2.55264 + endloop + endfacet + facet normal 0.293838 -0.0471641 0.954691 + outer loop + vertex 1.60084 1.40212 2.55165 + vertex 1.60077 1.39766 2.55145 + vertex 1.60435 1.4011 2.55052 + endloop + endfacet + facet normal 0.294522 -0.044705 0.954598 + outer loop + vertex 1.60476 1.40594 2.55062 + vertex 1.60084 1.40212 2.55165 + vertex 1.60435 1.4011 2.55052 + endloop + endfacet + facet normal 0.296594 -0.0448658 0.953949 + outer loop + vertex 1.60435 1.4011 2.55052 + vertex 1.60836 1.40455 2.54944 + vertex 1.60476 1.40594 2.55062 + endloop + endfacet + facet normal 0.297458 -0.0424836 0.953789 + outer loop + vertex 1.60836 1.40455 2.54944 + vertex 1.60868 1.40966 2.54956 + vertex 1.60476 1.40594 2.55062 + endloop + endfacet + facet normal 0.297447 -0.0424709 0.953793 + outer loop + vertex 1.60476 1.40594 2.55062 + vertex 1.60868 1.40966 2.54956 + vertex 1.60496 1.4109 2.55078 + endloop + endfacet + facet normal 0.296092 -0.0424287 0.954217 + outer loop + vertex 1.60496 1.4109 2.55078 + vertex 1.60102 1.40704 2.55183 + vertex 1.60476 1.40594 2.55062 + endloop + endfacet + facet normal 0.295988 -0.0423127 0.954254 + outer loop + vertex 1.60118 1.41208 2.552 + vertex 1.60102 1.40704 2.55183 + vertex 1.60496 1.4109 2.55078 + endloop + endfacet + facet normal 0.296987 -0.0389408 0.954087 + outer loop + vertex 1.60506 1.41585 2.55095 + vertex 1.60118 1.41208 2.552 + vertex 1.60496 1.4109 2.55078 + endloop + endfacet + facet normal 0.298441 -0.038954 0.953633 + outer loop + vertex 1.60496 1.4109 2.55078 + vertex 1.60882 1.41463 2.54972 + vertex 1.60506 1.41585 2.55095 + endloop + endfacet + facet normal 0.299346 -0.0360031 0.953465 + outer loop + vertex 1.60882 1.41463 2.54972 + vertex 1.60892 1.41956 2.54988 + vertex 1.60506 1.41585 2.55095 + endloop + endfacet + facet normal 0.29935 -0.0360077 0.953464 + outer loop + vertex 1.60506 1.41585 2.55095 + vertex 1.60892 1.41956 2.54988 + vertex 1.60515 1.42075 2.55111 + endloop + endfacet + facet normal 0.297261 -0.0359932 0.954118 + outer loop + vertex 1.60515 1.42075 2.55111 + vertex 1.60129 1.41708 2.55217 + vertex 1.60506 1.41585 2.55095 + endloop + endfacet + facet normal 0.297448 -0.0362087 0.954051 + outer loop + vertex 1.60141 1.422 2.55232 + vertex 1.60129 1.41708 2.55217 + vertex 1.60515 1.42075 2.55111 + endloop + endfacet + facet normal 0.297815 -0.0350437 0.95398 + outer loop + vertex 1.60531 1.42562 2.55123 + vertex 1.60141 1.422 2.55232 + vertex 1.60515 1.42075 2.55111 + endloop + endfacet + facet normal 0.300326 -0.0351085 0.95319 + outer loop + vertex 1.60515 1.42075 2.55111 + vertex 1.60904 1.42448 2.55002 + vertex 1.60531 1.42562 2.55123 + endloop + endfacet + facet normal 0.300561 -0.0342934 0.953146 + outer loop + vertex 1.60904 1.42448 2.55002 + vertex 1.60916 1.42932 2.55015 + vertex 1.60531 1.42562 2.55123 + endloop + endfacet + facet normal 0.300767 -0.0345298 0.953072 + outer loop + vertex 1.60531 1.42562 2.55123 + vertex 1.60916 1.42932 2.55015 + vertex 1.60566 1.43039 2.5513 + endloop + endfacet + facet normal 0.297808 -0.0343256 0.954008 + outer loop + vertex 1.60566 1.43039 2.5513 + vertex 1.60169 1.42701 2.55241 + vertex 1.60531 1.42562 2.55123 + endloop + endfacet + facet normal 0.296761 -0.0329742 0.954382 + outer loop + vertex 1.60245 1.43262 2.55237 + vertex 1.60169 1.42701 2.55241 + vertex 1.60566 1.43039 2.5513 + endloop + endfacet + facet normal 0.297106 -0.0324345 0.954294 + outer loop + vertex 1.60633 1.43423 2.55122 + vertex 1.60245 1.43262 2.55237 + vertex 1.60566 1.43039 2.5513 + endloop + endfacet + facet normal 0.3013 -0.0331925 0.952951 + outer loop + vertex 1.60919 1.43382 2.5503 + vertex 1.60633 1.43423 2.55122 + vertex 1.60566 1.43039 2.5513 + endloop + endfacet + facet normal 0.301705 -0.0302989 0.95292 + outer loop + vertex 1.60861 1.43701 2.55059 + vertex 1.60633 1.43423 2.55122 + vertex 1.60919 1.43382 2.5503 + endloop + endfacet + facet normal 0.30634 -0.029335 0.95147 + outer loop + vertex 1.60861 1.43701 2.55059 + vertex 1.60919 1.43382 2.5503 + vertex 1.61245 1.43867 2.5494 + endloop + endfacet + facet normal 0.304461 -0.0244449 0.952211 + outer loop + vertex 1.60861 1.43701 2.55059 + vertex 1.61245 1.43867 2.5494 + vertex 1.60925 1.44092 2.55048 + endloop + endfacet + facet normal 0.299182 -0.0235346 0.953906 + outer loop + vertex 1.60925 1.44092 2.55048 + vertex 1.60575 1.43741 2.55149 + vertex 1.60861 1.43701 2.55059 + endloop + endfacet + facet normal 0.299981 -0.0244121 0.953633 + outer loop + vertex 1.60575 1.44195 2.55161 + vertex 1.60575 1.43741 2.55149 + vertex 1.60925 1.44092 2.55048 + endloop + endfacet + facet normal 0.300967 -0.0208097 0.953407 + outer loop + vertex 1.60956 1.44584 2.55049 + vertex 1.60575 1.44195 2.55161 + vertex 1.60925 1.44092 2.55048 + endloop + endfacet + facet normal 0.304631 -0.021037 0.952238 + outer loop + vertex 1.60925 1.44092 2.55048 + vertex 1.61316 1.44445 2.54931 + vertex 1.60956 1.44584 2.55049 + endloop + endfacet + facet normal 0.305861 -0.0175793 0.951914 + outer loop + vertex 1.61316 1.44445 2.54931 + vertex 1.6134 1.44961 2.54933 + vertex 1.60956 1.44584 2.55049 + endloop + endfacet + facet normal 0.306289 -0.0180604 0.951767 + outer loop + vertex 1.60956 1.44584 2.55049 + vertex 1.6134 1.44961 2.54933 + vertex 1.60969 1.45085 2.55054 + endloop + endfacet + facet normal 0.30271 -0.0179811 0.952913 + outer loop + vertex 1.60969 1.45085 2.55054 + vertex 1.60583 1.44691 2.5517 + vertex 1.60956 1.44584 2.55049 + endloop + endfacet + facet normal 0.303779 -0.0191329 0.95255 + outer loop + vertex 1.60589 1.45198 2.55178 + vertex 1.60583 1.44691 2.5517 + vertex 1.60969 1.45085 2.55054 + endloop + endfacet + facet normal 0.304632 -0.0160223 0.952335 + outer loop + vertex 1.60974 1.45585 2.55061 + vertex 1.60589 1.45198 2.55178 + vertex 1.60969 1.45085 2.55054 + endloop + endfacet + facet normal 0.3081 -0.0160443 0.951219 + outer loop + vertex 1.60969 1.45085 2.55054 + vertex 1.61348 1.45462 2.54938 + vertex 1.60974 1.45585 2.55061 + endloop + endfacet + facet normal 0.308865 -0.0135177 0.95101 + outer loop + vertex 1.61348 1.45462 2.54938 + vertex 1.61351 1.45957 2.54944 + vertex 1.60974 1.45585 2.55061 + endloop + endfacet + facet normal 0.309482 -0.0142088 0.950799 + outer loop + vertex 1.60974 1.45585 2.55061 + vertex 1.61351 1.45957 2.54944 + vertex 1.60977 1.46081 2.55068 + endloop + endfacet + facet normal 0.306031 -0.0142017 0.951916 + outer loop + vertex 1.60977 1.46081 2.55068 + vertex 1.60596 1.45705 2.55185 + vertex 1.60974 1.45585 2.55061 + endloop + endfacet + facet normal 0.306653 -0.0148978 0.951705 + outer loop + vertex 1.60601 1.46206 2.55191 + vertex 1.60596 1.45705 2.55185 + vertex 1.60977 1.46081 2.55068 + endloop + endfacet + facet normal 0.307389 -0.0124739 0.951502 + outer loop + vertex 1.6098 1.46577 2.55073 + vertex 1.60601 1.46206 2.55191 + vertex 1.60977 1.46081 2.55068 + endloop + endfacet + facet normal 0.310477 -0.0124768 0.950499 + outer loop + vertex 1.60977 1.46081 2.55068 + vertex 1.61353 1.46452 2.5495 + vertex 1.6098 1.46577 2.55073 + endloop + endfacet + facet normal 0.311105 -0.010418 0.950318 + outer loop + vertex 1.61353 1.46452 2.5495 + vertex 1.61356 1.46949 2.54954 + vertex 1.6098 1.46577 2.55073 + endloop + endfacet + facet normal 0.311511 -0.0108723 0.95018 + outer loop + vertex 1.6098 1.46577 2.55073 + vertex 1.61356 1.46949 2.54954 + vertex 1.60982 1.47074 2.55078 + endloop + endfacet + facet normal 0.308855 -0.010866 0.951047 + outer loop + vertex 1.60982 1.47074 2.55078 + vertex 1.60604 1.46703 2.55197 + vertex 1.6098 1.46577 2.55073 + endloop + endfacet + facet normal 0.309374 -0.0114497 0.950872 + outer loop + vertex 1.60607 1.47199 2.55202 + vertex 1.60604 1.46703 2.55197 + vertex 1.60982 1.47074 2.55078 + endloop + endfacet + facet normal 0.310005 -0.00937623 0.950689 + outer loop + vertex 1.60986 1.47573 2.55082 + vertex 1.60607 1.47199 2.55202 + vertex 1.60982 1.47074 2.55078 + endloop + endfacet + facet normal 0.312702 -0.0093887 0.949805 + outer loop + vertex 1.60982 1.47074 2.55078 + vertex 1.6136 1.47448 2.54958 + vertex 1.60986 1.47573 2.55082 + endloop + endfacet + facet normal 0.313305 -0.00740321 0.949624 + outer loop + vertex 1.6136 1.47448 2.54958 + vertex 1.61363 1.47948 2.5496 + vertex 1.60986 1.47573 2.55082 + endloop + endfacet + facet normal 0.31365 -0.00778836 0.949507 + outer loop + vertex 1.60986 1.47573 2.55082 + vertex 1.61363 1.47948 2.5496 + vertex 1.6099 1.48073 2.55085 + endloop + endfacet + facet normal 0.310692 -0.00777218 0.950479 + outer loop + vertex 1.6099 1.48073 2.55085 + vertex 1.6061 1.47698 2.55206 + vertex 1.60986 1.47573 2.55082 + endloop + endfacet + facet normal 0.310583 -0.00764966 0.950516 + outer loop + vertex 1.60613 1.48198 2.55209 + vertex 1.6061 1.47698 2.55206 + vertex 1.6099 1.48073 2.55085 + endloop + endfacet + facet normal 0.310958 -0.00640764 0.950402 + outer loop + vertex 1.60993 1.48573 2.55087 + vertex 1.60613 1.48198 2.55209 + vertex 1.6099 1.48073 2.55085 + endloop + endfacet + facet normal 0.314016 -0.00642081 0.949396 + outer loop + vertex 1.6099 1.48073 2.55085 + vertex 1.61366 1.48448 2.54963 + vertex 1.60993 1.48573 2.55087 + endloop + endfacet + facet normal 0.314372 -0.00524751 0.949285 + outer loop + vertex 1.61366 1.48448 2.54963 + vertex 1.61369 1.48948 2.54965 + vertex 1.60993 1.48573 2.55087 + endloop + endfacet + facet normal 0.314215 -0.00507244 0.949338 + outer loop + vertex 1.60993 1.48573 2.55087 + vertex 1.61369 1.48948 2.54965 + vertex 1.60995 1.49073 2.55089 + endloop + endfacet + facet normal 0.310627 -0.0050627 0.950519 + outer loop + vertex 1.60995 1.49073 2.55089 + vertex 1.60616 1.48698 2.55211 + vertex 1.60993 1.48573 2.55087 + endloop + endfacet + facet normal 0.31068 -0.00512245 0.950501 + outer loop + vertex 1.60618 1.49198 2.55213 + vertex 1.60616 1.48698 2.55211 + vertex 1.60995 1.49073 2.55089 + endloop + endfacet + facet normal 0.311027 -0.00397125 0.950393 + outer loop + vertex 1.60996 1.49572 2.55091 + vertex 1.60618 1.49198 2.55213 + vertex 1.60995 1.49073 2.55089 + endloop + endfacet + facet normal 0.31441 -0.00397671 0.949279 + outer loop + vertex 1.60995 1.49073 2.55089 + vertex 1.6137 1.49447 2.54966 + vertex 1.60996 1.49572 2.55091 + endloop + endfacet + facet normal 0.314691 -0.00305006 0.949189 + outer loop + vertex 1.6137 1.49447 2.54966 + vertex 1.61371 1.49946 2.54968 + vertex 1.60996 1.49572 2.55091 + endloop + endfacet + facet normal 0.314528 -0.00286856 0.949244 + outer loop + vertex 1.60996 1.49572 2.55091 + vertex 1.61371 1.49946 2.54968 + vertex 1.60997 1.50071 2.55092 + endloop + endfacet + facet normal 0.311933 -0.00286606 0.9501 + outer loop + vertex 1.60997 1.50071 2.55092 + vertex 1.6062 1.49697 2.55215 + vertex 1.60996 1.49572 2.55091 + endloop + endfacet + facet normal 0.311978 -0.00291596 0.950085 + outer loop + vertex 1.60621 1.50197 2.55216 + vertex 1.6062 1.49697 2.55215 + vertex 1.60997 1.50071 2.55092 + endloop + endfacet + facet normal 0.312447 -0.00136012 0.949934 + outer loop + vertex 1.60997 1.5057 2.55093 + vertex 1.60621 1.50197 2.55216 + vertex 1.60997 1.50071 2.55092 + endloop + endfacet + facet normal 0.314232 -0.00135985 0.949345 + outer loop + vertex 1.60997 1.50071 2.55092 + vertex 1.61372 1.50445 2.54969 + vertex 1.60997 1.5057 2.55093 + endloop + endfacet + facet normal 0.314489 -0.000507948 0.949261 + outer loop + vertex 1.61372 1.50445 2.54969 + vertex 1.61371 1.50944 2.54969 + vertex 1.60997 1.5057 2.55093 + endloop + endfacet + facet normal 0.313025 0.00111745 0.949744 + outer loop + vertex 1.60997 1.5057 2.55093 + vertex 1.61371 1.50944 2.54969 + vertex 1.60996 1.51069 2.55093 + endloop + endfacet + facet normal 0.312117 0.00111523 0.950043 + outer loop + vertex 1.60996 1.51069 2.55093 + vertex 1.60621 1.50696 2.55216 + vertex 1.60997 1.5057 2.55093 + endloop + endfacet + facet normal 0.310607 0.00279353 0.950534 + outer loop + vertex 1.60619 1.51195 2.55215 + vertex 1.60621 1.50696 2.55216 + vertex 1.60996 1.51069 2.55093 + endloop + endfacet + facet normal 0.310894 0.00375126 0.950437 + outer loop + vertex 1.60993 1.51569 2.55091 + vertex 1.60619 1.51195 2.55215 + vertex 1.60996 1.51069 2.55093 + endloop + endfacet + facet normal 0.311188 0.00375262 0.950341 + outer loop + vertex 1.60996 1.51069 2.55093 + vertex 1.61369 1.51443 2.54969 + vertex 1.60993 1.51569 2.55091 + endloop + endfacet + facet normal 0.311071 0.00336478 0.950381 + outer loop + vertex 1.61369 1.51443 2.54969 + vertex 1.61367 1.51942 2.54968 + vertex 1.60993 1.51569 2.55091 + endloop + endfacet + facet normal 0.30953 0.00506909 0.950876 + outer loop + vertex 1.60993 1.51569 2.55091 + vertex 1.61367 1.51942 2.54968 + vertex 1.6099 1.52068 2.5509 + endloop + endfacet + facet normal 0.309679 0.00506988 0.950828 + outer loop + vertex 1.6099 1.52068 2.5509 + vertex 1.60616 1.51694 2.55214 + vertex 1.60993 1.51569 2.55091 + endloop + endfacet + facet normal 0.309134 0.0056717 0.951001 + outer loop + vertex 1.60613 1.52193 2.55211 + vertex 1.60616 1.51694 2.55214 + vertex 1.6099 1.52068 2.5509 + endloop + endfacet + facet normal 0.30885 0.00472211 0.951099 + outer loop + vertex 1.60987 1.52567 2.55088 + vertex 1.60613 1.52193 2.55211 + vertex 1.6099 1.52068 2.5509 + endloop + endfacet + facet normal 0.308569 0.00472106 0.95119 + outer loop + vertex 1.6099 1.52068 2.5509 + vertex 1.61364 1.52442 2.54967 + vertex 1.60987 1.52567 2.55088 + endloop + endfacet + facet normal 0.308307 0.00384569 0.951279 + outer loop + vertex 1.61364 1.52442 2.54967 + vertex 1.61362 1.52941 2.54965 + vertex 1.60987 1.52567 2.55088 + endloop + endfacet + facet normal 0.308626 0.00349218 0.951177 + outer loop + vertex 1.60987 1.52567 2.55088 + vertex 1.61362 1.52941 2.54965 + vertex 1.60986 1.53066 2.55087 + endloop + endfacet + facet normal 0.309138 0.00349297 0.951011 + outer loop + vertex 1.60986 1.53066 2.55087 + vertex 1.60612 1.52692 2.5521 + vertex 1.60987 1.52567 2.55088 + endloop + endfacet + facet normal 0.310129 0.0023958 0.950692 + outer loop + vertex 1.60611 1.53192 2.55209 + vertex 1.60612 1.52692 2.5521 + vertex 1.60986 1.53066 2.55087 + endloop + endfacet + facet normal 0.310306 0.00298525 0.950632 + outer loop + vertex 1.60985 1.53565 2.55085 + vertex 1.60611 1.53192 2.55209 + vertex 1.60986 1.53066 2.55087 + endloop + endfacet + facet normal 0.309304 0.00298437 0.950959 + outer loop + vertex 1.60986 1.53066 2.55087 + vertex 1.61361 1.5344 2.54964 + vertex 1.60985 1.53565 2.55085 + endloop + endfacet + facet normal 0.309898 0.00496555 0.950757 + outer loop + vertex 1.61361 1.5344 2.54964 + vertex 1.6136 1.53939 2.54961 + vertex 1.60985 1.53565 2.55085 + endloop + endfacet + facet normal 0.310225 0.00460324 0.950652 + outer loop + vertex 1.60985 1.53565 2.55085 + vertex 1.6136 1.53939 2.54961 + vertex 1.60984 1.54065 2.55083 + endloop + endfacet + facet normal 0.311088 0.00460473 0.95037 + outer loop + vertex 1.60984 1.54065 2.55083 + vertex 1.6061 1.53691 2.55208 + vertex 1.60985 1.53565 2.55085 + endloop + endfacet + facet normal 0.310703 0.00503124 0.950494 + outer loop + vertex 1.60607 1.5419 2.55206 + vertex 1.6061 1.53691 2.55208 + vertex 1.60984 1.54065 2.55083 + endloop + endfacet + facet normal 0.311178 0.00661781 0.950329 + outer loop + vertex 1.60981 1.54564 2.55081 + vertex 1.60607 1.5419 2.55206 + vertex 1.60984 1.54065 2.55083 + endloop + endfacet + facet normal 0.31088 0.00661677 0.950426 + outer loop + vertex 1.60984 1.54065 2.55083 + vertex 1.61357 1.54439 2.54959 + vertex 1.60981 1.54564 2.55081 + endloop + endfacet + facet normal 0.311177 0.00761392 0.950321 + outer loop + vertex 1.61357 1.54439 2.54959 + vertex 1.61355 1.54938 2.54956 + vertex 1.60981 1.54564 2.55081 + endloop + endfacet + facet normal 0.310698 0.00814309 0.950474 + outer loop + vertex 1.60981 1.54564 2.55081 + vertex 1.61355 1.54938 2.54956 + vertex 1.60978 1.55064 2.55078 + endloop + endfacet + facet normal 0.309818 0.00813837 0.950761 + outer loop + vertex 1.60978 1.55064 2.55078 + vertex 1.60603 1.5469 2.55203 + vertex 1.60981 1.54564 2.55081 + endloop + endfacet + facet normal 0.308293 0.00982522 0.951241 + outer loop + vertex 1.60598 1.55189 2.55199 + vertex 1.60603 1.5469 2.55203 + vertex 1.60978 1.55064 2.55078 + endloop + endfacet + facet normal 0.308026 0.00892282 0.951336 + outer loop + vertex 1.60973 1.55563 2.55074 + vertex 1.60598 1.55189 2.55199 + vertex 1.60978 1.55064 2.55078 + endloop + endfacet + facet normal 0.309801 0.00893375 0.950759 + outer loop + vertex 1.60978 1.55064 2.55078 + vertex 1.61351 1.55438 2.54953 + vertex 1.60973 1.55563 2.55074 + endloop + endfacet + facet normal 0.30966 0.0084598 0.95081 + outer loop + vertex 1.61351 1.55438 2.54953 + vertex 1.61347 1.55937 2.54949 + vertex 1.60973 1.55563 2.55074 + endloop + endfacet + facet normal 0.308349 0.00990712 0.951222 + outer loop + vertex 1.60973 1.55563 2.55074 + vertex 1.61347 1.55937 2.54949 + vertex 1.6097 1.56062 2.5507 + endloop + endfacet + facet normal 0.306564 0.00990093 0.951799 + outer loop + vertex 1.6097 1.56062 2.5507 + vertex 1.60594 1.55688 2.55195 + vertex 1.60973 1.55563 2.55074 + endloop + endfacet + facet normal 0.305264 0.0113416 0.9522 + outer loop + vertex 1.60593 1.56186 2.5519 + vertex 1.60594 1.55688 2.55195 + vertex 1.6097 1.56062 2.5507 + endloop + endfacet + facet normal 0.305457 0.0119959 0.95213 + outer loop + vertex 1.60969 1.5656 2.55064 + vertex 1.60593 1.56186 2.5519 + vertex 1.6097 1.56062 2.5507 + endloop + endfacet + facet normal 0.307316 0.0119928 0.951532 + outer loop + vertex 1.6097 1.56062 2.5507 + vertex 1.61344 1.56436 2.54945 + vertex 1.60969 1.5656 2.55064 + endloop + endfacet + facet normal 0.307828 0.0137224 0.951343 + outer loop + vertex 1.61344 1.56436 2.54945 + vertex 1.61343 1.56935 2.54938 + vertex 1.60969 1.5656 2.55064 + endloop + endfacet + facet normal 0.306419 0.015273 0.951774 + outer loop + vertex 1.60969 1.5656 2.55064 + vertex 1.61343 1.56935 2.54938 + vertex 1.60967 1.57058 2.55057 + endloop + endfacet + facet normal 0.304702 0.0152716 0.952325 + outer loop + vertex 1.60967 1.57058 2.55057 + vertex 1.60592 1.56684 2.55183 + vertex 1.60969 1.5656 2.55064 + endloop + endfacet + facet normal 0.303117 0.0170178 0.952801 + outer loop + vertex 1.60583 1.57182 2.55177 + vertex 1.60592 1.56684 2.55183 + vertex 1.60967 1.57058 2.55057 + endloop + endfacet + facet normal 0.303655 0.0188731 0.952595 + outer loop + vertex 1.60952 1.57556 2.55052 + vertex 1.60583 1.57182 2.55177 + vertex 1.60967 1.57058 2.55057 + endloop + endfacet + facet normal 0.305278 0.0189157 0.952075 + outer loop + vertex 1.60967 1.57058 2.55057 + vertex 1.61337 1.57433 2.54931 + vertex 1.60952 1.57556 2.55052 + endloop + endfacet + facet normal 0.305724 0.020487 0.9519 + outer loop + vertex 1.61337 1.57433 2.54931 + vertex 1.61315 1.57937 2.54927 + vertex 1.60952 1.57556 2.55052 + endloop + endfacet + facet normal 0.30375 0.022561 0.952485 + outer loop + vertex 1.60952 1.57556 2.55052 + vertex 1.61315 1.57937 2.54927 + vertex 1.60913 1.5805 2.55053 + endloop + endfacet + facet normal 0.302374 0.0224517 0.952925 + outer loop + vertex 1.60913 1.5805 2.55053 + vertex 1.60557 1.57681 2.55174 + vertex 1.60952 1.57556 2.55052 + endloop + endfacet + facet normal 0.299955 0.0250139 0.953625 + outer loop + vertex 1.60497 1.58202 2.55179 + vertex 1.60557 1.57681 2.55174 + vertex 1.60913 1.5805 2.55053 + endloop + endfacet + facet normal 0.300139 0.02558 0.953553 + outer loop + vertex 1.60913 1.5805 2.55053 + vertex 1.60859 1.58455 2.55059 + vertex 1.60497 1.58202 2.55179 + endloop + endfacet + facet normal 0.298206 0.0285937 0.954073 + outer loop + vertex 1.60626 1.58647 2.55126 + vertex 1.60497 1.58202 2.55179 + vertex 1.60859 1.58455 2.55059 + endloop + endfacet + facet normal 0.299858 0.0307989 0.953486 + outer loop + vertex 1.60859 1.58455 2.55059 + vertex 1.60986 1.58897 2.55005 + vertex 1.60626 1.58647 2.55126 + endloop + endfacet + facet normal 0.297907 0.0338636 0.953994 + outer loop + vertex 1.60626 1.58647 2.55126 + vertex 1.60986 1.58897 2.55005 + vertex 1.60568 1.59055 2.5513 + endloop + endfacet + facet normal 0.295379 0.0334982 0.954793 + outer loop + vertex 1.60568 1.59055 2.5513 + vertex 1.60222 1.58622 2.55252 + vertex 1.60626 1.58647 2.55126 + endloop + endfacet + facet normal 0.294522 0.0342497 0.955031 + outer loop + vertex 1.6016 1.59173 2.55251 + vertex 1.60222 1.58622 2.55252 + vertex 1.60568 1.59055 2.5513 + endloop + endfacet + facet normal 0.295055 0.0363558 0.954788 + outer loop + vertex 1.6052 1.59557 2.55125 + vertex 1.6016 1.59173 2.55251 + vertex 1.60568 1.59055 2.5513 + endloop + endfacet + facet normal 0.296718 0.0365094 0.954267 + outer loop + vertex 1.60568 1.59055 2.5513 + vertex 1.60919 1.59423 2.55006 + vertex 1.6052 1.59557 2.55125 + endloop + endfacet + facet normal 0.297026 0.0375436 0.954131 + outer loop + vertex 1.60919 1.59423 2.55006 + vertex 1.60882 1.5993 2.54998 + vertex 1.6052 1.59557 2.55125 + endloop + endfacet + facet normal 0.296477 0.0381252 0.954279 + outer loop + vertex 1.6052 1.59557 2.55125 + vertex 1.60882 1.5993 2.54998 + vertex 1.60496 1.6006 2.55113 + endloop + endfacet + facet normal 0.294827 0.0380579 0.954793 + outer loop + vertex 1.60496 1.6006 2.55113 + vertex 1.6013 1.59684 2.55241 + vertex 1.6052 1.59557 2.55125 + endloop + endfacet + facet normal 0.294656 0.0382401 0.954838 + outer loop + vertex 1.60118 1.60184 2.55224 + vertex 1.6013 1.59684 2.55241 + vertex 1.60496 1.6006 2.55113 + endloop + endfacet + facet normal 0.294724 0.0384759 0.954808 + outer loop + vertex 1.60487 1.60558 2.55095 + vertex 1.60118 1.60184 2.55224 + vertex 1.60496 1.6006 2.55113 + endloop + endfacet + facet normal 0.295933 0.0384851 0.954433 + outer loop + vertex 1.60496 1.6006 2.55113 + vertex 1.60864 1.60434 2.54983 + vertex 1.60487 1.60558 2.55095 + endloop + endfacet + facet normal 0.295729 0.0377812 0.954525 + outer loop + vertex 1.60864 1.60434 2.54983 + vertex 1.60857 1.60933 2.54966 + vertex 1.60487 1.60558 2.55095 + endloop + endfacet + facet normal 0.294611 0.0389882 0.954822 + outer loop + vertex 1.60487 1.60558 2.55095 + vertex 1.60857 1.60933 2.54966 + vertex 1.6048 1.61052 2.55077 + endloop + endfacet + facet normal 0.294357 0.0389876 0.9549 + outer loop + vertex 1.6048 1.61052 2.55077 + vertex 1.60114 1.60679 2.55205 + vertex 1.60487 1.60558 2.55095 + endloop + endfacet + facet normal 0.293073 0.040362 0.955238 + outer loop + vertex 1.60101 1.6117 2.55188 + vertex 1.60114 1.60679 2.55205 + vertex 1.6048 1.61052 2.55077 + endloop + endfacet + facet normal 0.293322 0.0412661 0.955123 + outer loop + vertex 1.60458 1.61543 2.55063 + vertex 1.60101 1.6117 2.55188 + vertex 1.6048 1.61052 2.55077 + endloop + endfacet + facet normal 0.29273 0.0412449 0.955305 + outer loop + vertex 1.6048 1.61052 2.55077 + vertex 1.60847 1.61427 2.54949 + vertex 1.60458 1.61543 2.55063 + endloop + endfacet + facet normal 0.29287 0.0417805 0.955239 + outer loop + vertex 1.60847 1.61427 2.54949 + vertex 1.60814 1.6192 2.54937 + vertex 1.60458 1.61543 2.55063 + endloop + endfacet + facet normal 0.29063 0.0440909 0.955819 + outer loop + vertex 1.60458 1.61543 2.55063 + vertex 1.60814 1.6192 2.54937 + vertex 1.60406 1.6203 2.55056 + endloop + endfacet + facet normal 0.291868 0.044217 0.955436 + outer loop + vertex 1.60406 1.6203 2.55056 + vertex 1.60064 1.61664 2.55178 + vertex 1.60458 1.61543 2.55063 + endloop + endfacet + facet normal 0.290348 0.0457649 0.955826 + outer loop + vertex 1.59991 1.62185 2.55175 + vertex 1.60064 1.61664 2.55178 + vertex 1.60406 1.6203 2.55056 + endloop + endfacet + facet normal 0.290459 0.0461007 0.955776 + outer loop + vertex 1.60406 1.6203 2.55056 + vertex 1.60339 1.62431 2.55057 + vertex 1.59991 1.62185 2.55175 + endloop + endfacet + facet normal 0.289724 0.0472218 0.955945 + outer loop + vertex 1.60106 1.62628 2.55118 + vertex 1.59991 1.62185 2.55175 + vertex 1.60339 1.62431 2.55057 + endloop + endfacet + facet normal 0.289208 0.0465506 0.956134 + outer loop + vertex 1.60339 1.62431 2.55057 + vertex 1.6046 1.62874 2.54999 + vertex 1.60106 1.62628 2.55118 + endloop + endfacet + facet normal 0.288776 0.0472172 0.956232 + outer loop + vertex 1.60106 1.62628 2.55118 + vertex 1.6046 1.62874 2.54999 + vertex 1.60045 1.6304 2.55116 + endloop + endfacet + facet normal 0.291358 0.0475945 0.955429 + outer loop + vertex 1.60045 1.6304 2.55116 + vertex 1.59722 1.62617 2.55236 + vertex 1.60106 1.62628 2.55118 + endloop + endfacet + facet normal 0.291129 0.0477865 0.95549 + outer loop + vertex 1.59649 1.63161 2.55231 + vertex 1.59722 1.62617 2.55236 + vertex 1.60045 1.6304 2.55116 + endloop + endfacet + facet normal 0.291412 0.0488503 0.955349 + outer loop + vertex 1.59998 1.63547 2.55105 + vertex 1.59649 1.63161 2.55231 + vertex 1.60045 1.6304 2.55116 + endloop + endfacet + facet normal 0.288224 0.0485743 0.95633 + outer loop + vertex 1.60045 1.6304 2.55116 + vertex 1.60393 1.63409 2.54993 + vertex 1.59998 1.63547 2.55105 + endloop + endfacet + facet normal 0.28871 0.0501581 0.956102 + outer loop + vertex 1.60393 1.63409 2.54993 + vertex 1.60357 1.63923 2.54976 + vertex 1.59998 1.63547 2.55105 + endloop + endfacet + facet normal 0.287377 0.0515428 0.95643 + outer loop + vertex 1.59998 1.63547 2.55105 + vertex 1.60357 1.63923 2.54976 + vertex 1.59965 1.64051 2.55087 + endloop + endfacet + facet normal 0.29096 0.0517352 0.955335 + outer loop + vertex 1.59965 1.64051 2.55087 + vertex 1.59609 1.63675 2.55216 + vertex 1.59998 1.63547 2.55105 + endloop + endfacet + facet normal 0.289334 0.053411 0.955737 + outer loop + vertex 1.59571 1.64176 2.552 + vertex 1.59609 1.63675 2.55216 + vertex 1.59965 1.64051 2.55087 + endloop + endfacet + facet normal 0.289952 0.0556573 0.955421 + outer loop + vertex 1.59917 1.64541 2.55073 + vertex 1.59571 1.64176 2.552 + vertex 1.59965 1.64051 2.55087 + endloop + endfacet + facet normal 0.286434 0.0553451 0.9565 + outer loop + vertex 1.59965 1.64051 2.55087 + vertex 1.60319 1.6443 2.54959 + vertex 1.59917 1.64541 2.55073 + endloop + endfacet + facet normal 0.287004 0.0577257 0.956188 + outer loop + vertex 1.60319 1.6443 2.54959 + vertex 1.60252 1.64954 2.54948 + vertex 1.59917 1.64541 2.55073 + endloop + endfacet + facet normal 0.285714 0.0588703 0.956505 + outer loop + vertex 1.59856 1.6494 2.55067 + vertex 1.59917 1.64541 2.55073 + vertex 1.60252 1.64954 2.54948 + endloop + endfacet + facet normal 0.28555 0.0622941 0.956337 + outer loop + vertex 1.59856 1.6494 2.55067 + vertex 1.60252 1.64954 2.54948 + vertex 1.59979 1.6538 2.55002 + endloop + endfacet + facet normal 0.286049 0.0621339 0.956199 + outer loop + vertex 1.59856 1.6494 2.55067 + vertex 1.59979 1.6538 2.55002 + vertex 1.59619 1.65139 2.55125 + endloop + endfacet + facet normal 0.286643 0.0629137 0.95597 + outer loop + vertex 1.59619 1.65139 2.55125 + vertex 1.59497 1.64699 2.55191 + vertex 1.59856 1.6494 2.55067 + endloop + endfacet + facet normal 0.293369 0.0607618 0.954066 + outer loop + vertex 1.59619 1.65139 2.55125 + vertex 1.59214 1.65146 2.55249 + vertex 1.59497 1.64699 2.55191 + endloop + endfacet + facet normal 0.298811 0.064455 0.952133 + outer loop + vertex 1.59214 1.65146 2.55249 + vertex 1.5909 1.6469 2.55319 + vertex 1.59497 1.64699 2.55191 + endloop + endfacet + facet normal 0.299032 0.0587209 0.952435 + outer loop + vertex 1.59178 1.64284 2.55316 + vertex 1.59497 1.64699 2.55191 + vertex 1.5909 1.6469 2.55319 + endloop + endfacet + facet normal 0.314738 0.0621461 0.947142 + outer loop + vertex 1.59178 1.64284 2.55316 + vertex 1.5909 1.6469 2.55319 + vertex 1.58801 1.64411 2.55433 + endloop + endfacet + facet normal 0.31295 0.0559216 0.948122 + outer loop + vertex 1.58847 1.63934 2.55446 + vertex 1.59178 1.64284 2.55316 + vertex 1.58801 1.64411 2.55433 + endloop + endfacet + facet normal 0.312889 0.0559845 0.948138 + outer loop + vertex 1.59224 1.63803 2.5533 + vertex 1.59178 1.64284 2.55316 + vertex 1.58847 1.63934 2.55446 + endloop + endfacet + facet normal 0.297882 0.0546877 0.953035 + outer loop + vertex 1.59224 1.63803 2.5533 + vertex 1.59571 1.64176 2.552 + vertex 1.59178 1.64284 2.55316 + endloop + endfacet + facet normal 0.29887 0.0588585 0.952477 + outer loop + vertex 1.59571 1.64176 2.552 + vertex 1.59497 1.64699 2.55191 + vertex 1.59178 1.64284 2.55316 + endloop + endfacet + facet normal 0.314172 0.0595664 0.947496 + outer loop + vertex 1.5909 1.6469 2.55319 + vertex 1.59214 1.65146 2.55249 + vertex 1.58746 1.64931 2.55418 + endloop + endfacet + facet normal 0.309021 0.0714474 0.948368 + outer loop + vertex 1.58746 1.64931 2.55418 + vertex 1.59214 1.65146 2.55249 + vertex 1.58863 1.65381 2.55346 + endloop + endfacet + facet normal 0.306864 0.0678216 0.949334 + outer loop + vertex 1.59214 1.65146 2.55249 + vertex 1.59158 1.65672 2.55229 + vertex 1.58863 1.65381 2.55346 + endloop + endfacet + facet normal 0.309139 0.0652846 0.948773 + outer loop + vertex 1.58863 1.65381 2.55346 + vertex 1.59158 1.65672 2.55229 + vertex 1.58771 1.65795 2.55347 + endloop + endfacet + facet normal 0.322507 0.068242 0.944104 + outer loop + vertex 1.58863 1.65381 2.55346 + vertex 1.58771 1.65795 2.55347 + vertex 1.58468 1.65388 2.5548 + endloop + endfacet + facet normal 0.309552 0.0668192 0.948532 + outer loop + vertex 1.59158 1.65672 2.55229 + vertex 1.59103 1.66157 2.55213 + vertex 1.58771 1.65795 2.55347 + endloop + endfacet + facet normal 0.311082 0.0652759 0.948139 + outer loop + vertex 1.58771 1.65795 2.55347 + vertex 1.59103 1.66157 2.55213 + vertex 1.58708 1.6628 2.55334 + endloop + endfacet + facet normal 0.311271 0.0659979 0.948027 + outer loop + vertex 1.59103 1.66157 2.55213 + vertex 1.59052 1.66651 2.55196 + vertex 1.58708 1.6628 2.55334 + endloop + endfacet + facet normal 0.295846 0.0645898 0.953049 + outer loop + vertex 1.59052 1.66651 2.55196 + vertex 1.59103 1.66157 2.55213 + vertex 1.59455 1.66531 2.55079 + endloop + endfacet + facet normal 0.295867 0.0646717 0.953037 + outer loop + vertex 1.59403 1.6702 2.55062 + vertex 1.59052 1.66651 2.55196 + vertex 1.59455 1.66531 2.55079 + endloop + endfacet + facet normal 0.286226 0.0637668 0.956038 + outer loop + vertex 1.59455 1.66531 2.55079 + vertex 1.5981 1.66913 2.54947 + vertex 1.59403 1.6702 2.55062 + endloop + endfacet + facet normal 0.28605 0.0629877 0.956142 + outer loop + vertex 1.5981 1.66913 2.54947 + vertex 1.59743 1.67438 2.54933 + vertex 1.59403 1.6702 2.55062 + endloop + endfacet + facet normal 0.28592 0.0631023 0.956173 + outer loop + vertex 1.59347 1.67423 2.55052 + vertex 1.59403 1.6702 2.55062 + vertex 1.59743 1.67438 2.54933 + endloop + endfacet + facet normal 0.283117 0.0626347 0.957038 + outer loop + vertex 1.5981 1.66913 2.54947 + vertex 1.60162 1.67284 2.54819 + vertex 1.59743 1.67438 2.54933 + endloop + endfacet + facet normal 0.283121 0.0626474 0.957036 + outer loop + vertex 1.60162 1.67284 2.54819 + vertex 1.60104 1.67686 2.5481 + vertex 1.59743 1.67438 2.54933 + endloop + endfacet + facet normal 0.2828 0.0631457 0.957098 + outer loop + vertex 1.59743 1.67438 2.54933 + vertex 1.60104 1.67686 2.5481 + vertex 1.5987 1.6788 2.54866 + endloop + endfacet + facet normal 0.284771 0.0624962 0.956556 + outer loop + vertex 1.59474 1.67868 2.54985 + vertex 1.59743 1.67438 2.54933 + vertex 1.5987 1.6788 2.54866 + endloop + endfacet + facet normal 0.284544 0.0672294 0.956303 + outer loop + vertex 1.5987 1.6788 2.54866 + vertex 1.59804 1.68286 2.54857 + vertex 1.59474 1.67868 2.54985 + endloop + endfacet + facet normal 0.282338 0.0668809 0.956981 + outer loop + vertex 1.5987 1.6788 2.54866 + vertex 1.60228 1.68128 2.54743 + vertex 1.59804 1.68286 2.54857 + endloop + endfacet + facet normal 0.283728 0.0711469 0.956262 + outer loop + vertex 1.60228 1.68128 2.54743 + vertex 1.60142 1.68656 2.54729 + vertex 1.59804 1.68286 2.54857 + endloop + endfacet + facet normal 0.282382 0.0724812 0.95656 + outer loop + vertex 1.59804 1.68286 2.54857 + vertex 1.60142 1.68656 2.54729 + vertex 1.59731 1.68781 2.54841 + endloop + endfacet + facet normal 0.287503 0.0731838 0.95498 + outer loop + vertex 1.59804 1.68286 2.54857 + vertex 1.59731 1.68781 2.54841 + vertex 1.59393 1.68403 2.54972 + endloop + endfacet + facet normal 0.288566 0.07215 0.954738 + outer loop + vertex 1.59393 1.68403 2.54972 + vertex 1.59731 1.68781 2.54841 + vertex 1.59324 1.68912 2.54954 + endloop + endfacet + facet normal 0.29094 0.0806975 0.953332 + outer loop + vertex 1.59731 1.68781 2.54841 + vertex 1.5966 1.69272 2.54821 + vertex 1.59324 1.68912 2.54954 + endloop + endfacet + facet normal 0.283544 0.0797305 0.955639 + outer loop + vertex 1.59731 1.68781 2.54841 + vertex 1.60069 1.69158 2.54709 + vertex 1.5966 1.69272 2.54821 + endloop + endfacet + facet normal 0.285278 0.0870769 0.954481 + outer loop + vertex 1.60069 1.69158 2.54709 + vertex 1.59986 1.6968 2.54686 + vertex 1.5966 1.69272 2.54821 + endloop + endfacet + facet normal 0.285318 0.0870416 0.954472 + outer loop + vertex 1.5966 1.69272 2.54821 + vertex 1.59986 1.6968 2.54686 + vertex 1.59594 1.69671 2.54804 + endloop + endfacet + facet normal 0.295743 0.0886252 0.951147 + outer loop + vertex 1.5966 1.69272 2.54821 + vertex 1.59594 1.69671 2.54804 + vertex 1.59246 1.69441 2.54934 + endloop + endfacet + facet normal 0.294175 0.0911424 0.951396 + outer loop + vertex 1.59246 1.69441 2.54934 + vertex 1.59594 1.69671 2.54804 + vertex 1.59361 1.69871 2.54857 + endloop + endfacet + facet normal 0.293924 0.0908201 0.951504 + outer loop + vertex 1.59594 1.69671 2.54804 + vertex 1.59706 1.70107 2.54728 + vertex 1.59361 1.69871 2.54857 + endloop + endfacet + facet normal 0.2927 0.092717 0.951699 + outer loop + vertex 1.59361 1.69871 2.54857 + vertex 1.59706 1.70107 2.54728 + vertex 1.59276 1.70274 2.54844 + endloop + endfacet + facet normal 0.306958 0.0955519 0.946914 + outer loop + vertex 1.59361 1.69871 2.54857 + vertex 1.59276 1.70274 2.54844 + vertex 1.58973 1.69879 2.54982 + endloop + endfacet + facet normal 0.294696 0.0986858 0.950482 + outer loop + vertex 1.59706 1.70107 2.54728 + vertex 1.59593 1.70637 2.54708 + vertex 1.59276 1.70274 2.54844 + endloop + endfacet + facet normal 0.295025 0.0983715 0.950412 + outer loop + vertex 1.59276 1.70274 2.54844 + vertex 1.59593 1.70637 2.54708 + vertex 1.5917 1.70761 2.54827 + endloop + endfacet + facet normal 0.295488 0.100273 0.95007 + outer loop + vertex 1.59593 1.70637 2.54708 + vertex 1.59481 1.71168 2.54687 + vertex 1.5917 1.70761 2.54827 + endloop + endfacet + facet normal 0.283936 0.0979947 0.953823 + outer loop + vertex 1.59481 1.71168 2.54687 + vertex 1.59593 1.70637 2.54708 + vertex 1.59916 1.71009 2.54574 + endloop + endfacet + facet normal 0.283919 0.0979408 0.953833 + outer loop + vertex 1.59916 1.71009 2.54574 + vertex 1.59834 1.71414 2.54557 + vertex 1.59481 1.71168 2.54687 + endloop + endfacet + facet normal 0.283696 0.098276 0.953865 + outer loop + vertex 1.59595 1.7161 2.54608 + vertex 1.59481 1.71168 2.54687 + vertex 1.59834 1.71414 2.54557 + endloop + endfacet + facet normal 0.281625 0.0955147 0.954759 + outer loop + vertex 1.59834 1.71414 2.54557 + vertex 1.5995 1.71856 2.54478 + vertex 1.59595 1.7161 2.54608 + endloop + endfacet + facet normal 0.282859 0.0936391 0.95458 + outer loop + vertex 1.59595 1.7161 2.54608 + vertex 1.5995 1.71856 2.54478 + vertex 1.5952 1.72016 2.5459 + endloop + endfacet + facet normal 0.291873 0.0951713 0.95171 + outer loop + vertex 1.5952 1.72016 2.5459 + vertex 1.59198 1.71603 2.5473 + vertex 1.59595 1.7161 2.54608 + endloop + endfacet + facet normal 0.284076 0.0974412 0.953837 + outer loop + vertex 1.5995 1.71856 2.54478 + vertex 1.59849 1.72386 2.54454 + vertex 1.5952 1.72016 2.5459 + endloop + endfacet + facet normal 0.286148 0.095448 0.95342 + outer loop + vertex 1.5952 1.72016 2.5459 + vertex 1.59849 1.72386 2.54454 + vertex 1.59427 1.72509 2.54568 + endloop + endfacet + facet normal 0.294912 0.096973 0.950591 + outer loop + vertex 1.59427 1.72509 2.54568 + vertex 1.59099 1.72141 2.54708 + vertex 1.5952 1.72016 2.5459 + endloop + endfacet + facet normal 0.295359 0.0965378 0.950496 + outer loop + vertex 1.58992 1.72682 2.54686 + vertex 1.59099 1.72141 2.54708 + vertex 1.59427 1.72509 2.54568 + endloop + endfacet + facet normal 0.28748 0.100923 0.952455 + outer loop + vertex 1.59849 1.72386 2.54454 + vertex 1.59739 1.7292 2.54431 + vertex 1.59427 1.72509 2.54568 + endloop + endfacet + facet normal 0.289162 0.0995276 0.952092 + outer loop + vertex 1.59342 1.7292 2.54551 + vertex 1.59427 1.72509 2.54568 + vertex 1.59739 1.7292 2.54431 + endloop + endfacet + facet normal 0.282431 0.0999459 0.954067 + outer loop + vertex 1.59849 1.72386 2.54454 + vertex 1.60175 1.72755 2.54319 + vertex 1.59739 1.7292 2.54431 + endloop + endfacet + facet normal 0.28366 0.103715 0.9533 + outer loop + vertex 1.60175 1.72755 2.54319 + vertex 1.60085 1.73159 2.54302 + vertex 1.59739 1.7292 2.54431 + endloop + endfacet + facet normal 0.282557 0.105387 0.953444 + outer loop + vertex 1.59739 1.7292 2.54431 + vertex 1.60085 1.73159 2.54302 + vertex 1.59833 1.73361 2.54354 + endloop + endfacet + facet normal 0.288663 0.103796 0.951788 + outer loop + vertex 1.5943 1.73367 2.54476 + vertex 1.59739 1.7292 2.54431 + vertex 1.59833 1.73361 2.54354 + endloop + endfacet + facet normal 0.288587 0.107975 0.951346 + outer loop + vertex 1.59833 1.73361 2.54354 + vertex 1.59722 1.73769 2.54341 + vertex 1.5943 1.73367 2.54476 + endloop + endfacet + facet normal 0.282933 0.106502 0.953208 + outer loop + vertex 1.59833 1.73361 2.54354 + vertex 1.60173 1.73607 2.54226 + vertex 1.59722 1.73769 2.54341 + endloop + endfacet + facet normal 0.283147 0.106191 0.95318 + outer loop + vertex 1.60085 1.73159 2.54302 + vertex 1.60173 1.73607 2.54226 + vertex 1.59833 1.73361 2.54354 + endloop + endfacet + facet normal 0.281608 0.106562 0.953594 + outer loop + vertex 1.60173 1.73607 2.54226 + vertex 1.60085 1.73159 2.54302 + vertex 1.60485 1.73168 2.54183 + endloop + endfacet + facet normal 0.281768 0.103322 0.953903 + outer loop + vertex 1.60175 1.72755 2.54319 + vertex 1.60485 1.73168 2.54183 + vertex 1.60085 1.73159 2.54302 + endloop + endfacet + facet normal 0.281585 0.103472 0.953941 + outer loop + vertex 1.60598 1.72638 2.54207 + vertex 1.60485 1.73168 2.54183 + vertex 1.60175 1.72755 2.54319 + endloop + endfacet + facet normal 0.280865 0.100333 0.954488 + outer loop + vertex 1.60271 1.72269 2.54342 + vertex 1.60598 1.72638 2.54207 + vertex 1.60175 1.72755 2.54319 + endloop + endfacet + facet normal 0.280958 0.100245 0.95447 + outer loop + vertex 1.60702 1.72112 2.54232 + vertex 1.60598 1.72638 2.54207 + vertex 1.60271 1.72269 2.54342 + endloop + endfacet + facet normal 0.280278 0.0980909 0.954894 + outer loop + vertex 1.60349 1.71869 2.5436 + vertex 1.60702 1.72112 2.54232 + vertex 1.60271 1.72269 2.54342 + endloop + endfacet + facet normal 0.279714 0.0979896 0.95507 + outer loop + vertex 1.60349 1.71869 2.5436 + vertex 1.60271 1.72269 2.54342 + vertex 1.5995 1.71856 2.54478 + endloop + endfacet + facet normal 0.279808 0.0963294 0.955211 + outer loop + vertex 1.5995 1.71856 2.54478 + vertex 1.60235 1.71427 2.54438 + vertex 1.60349 1.71869 2.5436 + endloop + endfacet + facet normal 0.280126 0.0962327 0.955128 + outer loop + vertex 1.60235 1.71427 2.54438 + vertex 1.60588 1.71673 2.5431 + vertex 1.60349 1.71869 2.5436 + endloop + endfacet + facet normal 0.280388 0.0958373 0.955091 + outer loop + vertex 1.6067 1.71267 2.54326 + vertex 1.60588 1.71673 2.5431 + vertex 1.60235 1.71427 2.54438 + endloop + endfacet + facet normal 0.280683 0.0967703 0.95491 + outer loop + vertex 1.60345 1.70894 2.5446 + vertex 1.6067 1.71267 2.54326 + vertex 1.60235 1.71427 2.54438 + endloop + endfacet + facet normal 0.280048 0.0966478 0.955109 + outer loop + vertex 1.60345 1.70894 2.5446 + vertex 1.60235 1.71427 2.54438 + vertex 1.59916 1.71009 2.54574 + endloop + endfacet + facet normal 0.280228 0.0974486 0.954974 + outer loop + vertex 1.6002 1.7052 2.54593 + vertex 1.60345 1.70894 2.5446 + vertex 1.59916 1.71009 2.54574 + endloop + endfacet + facet normal 0.280917 0.0968017 0.954838 + outer loop + vertex 1.60455 1.70361 2.54481 + vertex 1.60345 1.70894 2.5446 + vertex 1.6002 1.7052 2.54593 + endloop + endfacet + facet normal 0.280782 0.0963718 0.954921 + outer loop + vertex 1.60104 1.70117 2.54609 + vertex 1.60455 1.70361 2.54481 + vertex 1.6002 1.7052 2.54593 + endloop + endfacet + facet normal 0.282916 0.0967898 0.954249 + outer loop + vertex 1.6002 1.7052 2.54593 + vertex 1.59706 1.70107 2.54728 + vertex 1.60104 1.70117 2.54609 + endloop + endfacet + facet normal 0.283148 0.0922369 0.954631 + outer loop + vertex 1.60104 1.70117 2.54609 + vertex 1.59706 1.70107 2.54728 + vertex 1.59986 1.6968 2.54686 + endloop + endfacet + facet normal 0.280034 0.0932218 0.955453 + outer loop + vertex 1.60104 1.70117 2.54609 + vertex 1.59986 1.6968 2.54686 + vertex 1.60341 1.69923 2.54559 + endloop + endfacet + facet normal 0.281904 0.0903414 0.95518 + outer loop + vertex 1.60408 1.69523 2.54577 + vertex 1.60341 1.69923 2.54559 + vertex 1.59986 1.6968 2.54686 + endloop + endfacet + facet normal 0.282511 0.0904349 0.954992 + outer loop + vertex 1.60341 1.69923 2.54559 + vertex 1.60408 1.69523 2.54577 + vertex 1.60737 1.69933 2.5444 + endloop + endfacet + facet normal 0.282275 0.0950026 0.954618 + outer loop + vertex 1.60341 1.69923 2.54559 + vertex 1.60737 1.69933 2.5444 + vertex 1.60455 1.70361 2.54481 + endloop + endfacet + facet normal 0.281857 0.0947131 0.95477 + outer loop + vertex 1.60455 1.70361 2.54481 + vertex 1.60737 1.69933 2.5444 + vertex 1.60855 1.70372 2.54362 + endloop + endfacet + facet normal 0.281757 0.0966591 0.954605 + outer loop + vertex 1.60855 1.70372 2.54362 + vertex 1.60772 1.70776 2.54346 + vertex 1.60455 1.70361 2.54481 + endloop + endfacet + facet normal 0.283825 0.0970555 0.953952 + outer loop + vertex 1.60855 1.70372 2.54362 + vertex 1.61206 1.70616 2.54233 + vertex 1.60772 1.70776 2.54346 + endloop + endfacet + facet normal 0.283359 0.0955974 0.954237 + outer loop + vertex 1.61206 1.70616 2.54233 + vertex 1.61096 1.71149 2.54212 + vertex 1.60772 1.70776 2.54346 + endloop + endfacet + facet normal 0.282481 0.0964245 0.954414 + outer loop + vertex 1.60772 1.70776 2.54346 + vertex 1.61096 1.71149 2.54212 + vertex 1.6067 1.71267 2.54326 + endloop + endfacet + facet normal 0.282181 0.0951393 0.954632 + outer loop + vertex 1.61096 1.71149 2.54212 + vertex 1.60987 1.71683 2.54191 + vertex 1.6067 1.71267 2.54326 + endloop + endfacet + facet normal 0.282459 0.0951926 0.954545 + outer loop + vertex 1.60987 1.71683 2.54191 + vertex 1.61096 1.71149 2.54212 + vertex 1.6142 1.7152 2.54079 + endloop + endfacet + facet normal 0.282179 0.0943318 0.954713 + outer loop + vertex 1.6142 1.7152 2.54079 + vertex 1.61338 1.71925 2.54063 + vertex 1.60987 1.71683 2.54191 + endloop + endfacet + facet normal 0.280849 0.096355 0.954903 + outer loop + vertex 1.61099 1.72123 2.54114 + vertex 1.60987 1.71683 2.54191 + vertex 1.61338 1.71925 2.54063 + endloop + endfacet + facet normal 0.281563 0.0972991 0.954597 + outer loop + vertex 1.61338 1.71925 2.54063 + vertex 1.61452 1.72363 2.53985 + vertex 1.61099 1.72123 2.54114 + endloop + endfacet + facet normal 0.280042 0.0996431 0.954802 + outer loop + vertex 1.61099 1.72123 2.54114 + vertex 1.61452 1.72363 2.53985 + vertex 1.6102 1.72522 2.54095 + endloop + endfacet + facet normal 0.280089 0.0996516 0.954788 + outer loop + vertex 1.6102 1.72522 2.54095 + vertex 1.60702 1.72112 2.54232 + vertex 1.61099 1.72123 2.54114 + endloop + endfacet + facet normal 0.280638 0.101514 0.95443 + outer loop + vertex 1.61452 1.72363 2.53985 + vertex 1.61348 1.72889 2.5396 + vertex 1.6102 1.72522 2.54095 + endloop + endfacet + facet normal 0.279357 0.102749 0.954674 + outer loop + vertex 1.6102 1.72522 2.54095 + vertex 1.61348 1.72889 2.5396 + vertex 1.60923 1.73006 2.54072 + endloop + endfacet + facet normal 0.280336 0.102931 0.954367 + outer loop + vertex 1.60923 1.73006 2.54072 + vertex 1.60598 1.72638 2.54207 + vertex 1.6102 1.72522 2.54095 + endloop + endfacet + facet normal 0.279831 0.104816 0.95431 + outer loop + vertex 1.61348 1.72889 2.5396 + vertex 1.61236 1.73418 2.53935 + vertex 1.60923 1.73006 2.54072 + endloop + endfacet + facet normal 0.279659 0.104958 0.954345 + outer loop + vertex 1.60833 1.7341 2.54053 + vertex 1.60923 1.73006 2.54072 + vertex 1.61236 1.73418 2.53935 + endloop + endfacet + facet normal 0.279594 0.10631 0.954214 + outer loop + vertex 1.60833 1.7341 2.54053 + vertex 1.61236 1.73418 2.53935 + vertex 1.60923 1.73859 2.53977 + endloop + endfacet + facet normal 0.279657 0.106357 0.954191 + outer loop + vertex 1.60923 1.73859 2.53977 + vertex 1.61236 1.73418 2.53935 + vertex 1.61332 1.73861 2.53857 + endloop + endfacet + facet normal 0.279263 0.106462 0.954295 + outer loop + vertex 1.61236 1.73418 2.53935 + vertex 1.61586 1.73661 2.53805 + vertex 1.61332 1.73861 2.53857 + endloop + endfacet + facet normal 0.280271 0.107857 0.953842 + outer loop + vertex 1.61586 1.73661 2.53805 + vertex 1.61674 1.7411 2.53728 + vertex 1.61332 1.73861 2.53857 + endloop + endfacet + facet normal 0.280453 0.107594 0.953818 + outer loop + vertex 1.61332 1.73861 2.53857 + vertex 1.61674 1.7411 2.53728 + vertex 1.61222 1.74269 2.53843 + endloop + endfacet + facet normal 0.28093 0.10918 0.953498 + outer loop + vertex 1.61674 1.7411 2.53728 + vertex 1.6152 1.7468 2.53709 + vertex 1.61222 1.74269 2.53843 + endloop + endfacet + facet normal 0.282352 0.109549 0.953035 + outer loop + vertex 1.6152 1.7468 2.53709 + vertex 1.61674 1.7411 2.53728 + vertex 1.6197 1.74521 2.53594 + endloop + endfacet + facet normal 0.282746 0.110853 0.952768 + outer loop + vertex 1.6197 1.74521 2.53594 + vertex 1.6186 1.74926 2.53579 + vertex 1.6152 1.7468 2.53709 + endloop + endfacet + facet normal 0.282361 0.11141 0.952817 + outer loop + vertex 1.61609 1.75127 2.5363 + vertex 1.6152 1.7468 2.53709 + vertex 1.6186 1.74926 2.53579 + endloop + endfacet + facet normal 0.283948 0.113586 0.952088 + outer loop + vertex 1.6186 1.74926 2.53579 + vertex 1.61957 1.75365 2.53498 + vertex 1.61609 1.75127 2.5363 + endloop + endfacet + facet normal 0.283069 0.114925 0.952189 + outer loop + vertex 1.61609 1.75127 2.5363 + vertex 1.61957 1.75365 2.53498 + vertex 1.61521 1.75528 2.53608 + endloop + endfacet + facet normal 0.281557 0.114621 0.952674 + outer loop + vertex 1.61521 1.75528 2.53608 + vertex 1.61209 1.75119 2.53749 + vertex 1.61609 1.75127 2.5363 + endloop + endfacet + facet normal 0.283545 0.116416 0.951866 + outer loop + vertex 1.61957 1.75365 2.53498 + vertex 1.61846 1.75891 2.53467 + vertex 1.61521 1.75528 2.53608 + endloop + endfacet + facet normal 0.281626 0.118265 0.952208 + outer loop + vertex 1.61521 1.75528 2.53608 + vertex 1.61846 1.75891 2.53467 + vertex 1.61421 1.76008 2.53578 + endloop + endfacet + facet normal 0.282134 0.120517 0.951775 + outer loop + vertex 1.61846 1.75891 2.53467 + vertex 1.61732 1.76414 2.53434 + vertex 1.61421 1.76008 2.53578 + endloop + endfacet + facet normal 0.282111 0.120512 0.951783 + outer loop + vertex 1.61846 1.75891 2.53467 + vertex 1.62169 1.76254 2.53325 + vertex 1.61732 1.76414 2.53434 + endloop + endfacet + facet normal 0.282312 0.121162 0.95164 + outer loop + vertex 1.62169 1.76254 2.53325 + vertex 1.62079 1.76652 2.53301 + vertex 1.61732 1.76414 2.53434 + endloop + endfacet + facet normal 0.281026 0.123105 0.951772 + outer loop + vertex 1.61732 1.76414 2.53434 + vertex 1.62079 1.76652 2.53301 + vertex 1.61825 1.76849 2.5335 + endloop + endfacet + facet normal 0.278801 0.123694 0.95235 + outer loop + vertex 1.61416 1.76845 2.53471 + vertex 1.61732 1.76414 2.53434 + vertex 1.61825 1.76849 2.5335 + endloop + endfacet + facet normal 0.278873 0.12206 0.952539 + outer loop + vertex 1.61825 1.76849 2.5335 + vertex 1.61712 1.7725 2.53332 + vertex 1.61416 1.76845 2.53471 + endloop + endfacet + facet normal 0.28127 0.1227 0.951752 + outer loop + vertex 1.61825 1.76849 2.5335 + vertex 1.62163 1.77094 2.53219 + vertex 1.61712 1.7725 2.53332 + endloop + endfacet + facet normal 0.279369 0.11621 0.953126 + outer loop + vertex 1.62163 1.77094 2.53219 + vertex 1.62008 1.77659 2.53195 + vertex 1.61712 1.7725 2.53332 + endloop + endfacet + facet normal 0.278855 0.116617 0.953226 + outer loop + vertex 1.61712 1.7725 2.53332 + vertex 1.62008 1.77659 2.53195 + vertex 1.616 1.77655 2.53315 + endloop + endfacet + facet normal 0.281007 0.123079 0.951781 + outer loop + vertex 1.62079 1.76652 2.53301 + vertex 1.62163 1.77094 2.53219 + vertex 1.61825 1.76849 2.5335 + endloop + endfacet + facet normal 0.284517 0.121619 0.950925 + outer loop + vertex 1.62169 1.76254 2.53325 + vertex 1.62476 1.76661 2.53181 + vertex 1.62079 1.76652 2.53301 + endloop + endfacet + facet normal 0.283915 0.118781 0.951464 + outer loop + vertex 1.62269 1.75773 2.53355 + vertex 1.62169 1.76254 2.53325 + vertex 1.61846 1.75891 2.53467 + endloop + endfacet + facet normal 0.284593 0.118909 0.951245 + outer loop + vertex 1.62269 1.75773 2.53355 + vertex 1.62592 1.76137 2.53213 + vertex 1.62169 1.76254 2.53325 + endloop + endfacet + facet normal 0.285768 0.117786 0.951033 + outer loop + vertex 1.62703 1.75612 2.53244 + vertex 1.62592 1.76137 2.53213 + vertex 1.62269 1.75773 2.53355 + endloop + endfacet + facet normal 0.285174 0.115894 0.951443 + outer loop + vertex 1.62356 1.75371 2.53378 + vertex 1.62703 1.75612 2.53244 + vertex 1.62269 1.75773 2.53355 + endloop + endfacet + facet normal 0.284181 0.115698 0.951764 + outer loop + vertex 1.62356 1.75371 2.53378 + vertex 1.62269 1.75773 2.53355 + vertex 1.61957 1.75365 2.53498 + endloop + endfacet + facet normal 0.284299 0.113141 0.952036 + outer loop + vertex 1.61957 1.75365 2.53498 + vertex 1.62265 1.74929 2.53458 + vertex 1.62356 1.75371 2.53378 + endloop + endfacet + facet normal 0.285262 0.112896 0.951778 + outer loop + vertex 1.62265 1.74929 2.53458 + vertex 1.62603 1.75175 2.53327 + vertex 1.62356 1.75371 2.53378 + endloop + endfacet + facet normal 0.286315 0.111376 0.95164 + outer loop + vertex 1.62705 1.74782 2.53342 + vertex 1.62603 1.75175 2.53327 + vertex 1.62265 1.74929 2.53458 + endloop + endfacet + facet normal 0.286256 0.111165 0.951683 + outer loop + vertex 1.6242 1.74363 2.53477 + vertex 1.62705 1.74782 2.53342 + vertex 1.62265 1.74929 2.53458 + endloop + endfacet + facet normal 0.285296 0.110913 0.952 + outer loop + vertex 1.6242 1.74363 2.53477 + vertex 1.62265 1.74929 2.53458 + vertex 1.6197 1.74521 2.53594 + endloop + endfacet + facet normal 0.285216 0.110642 0.952056 + outer loop + vertex 1.6208 1.74115 2.53608 + vertex 1.6242 1.74363 2.53477 + vertex 1.6197 1.74521 2.53594 + endloop + endfacet + facet normal 0.28577 0.109844 0.951982 + outer loop + vertex 1.62333 1.73914 2.53555 + vertex 1.6242 1.74363 2.53477 + vertex 1.6208 1.74115 2.53608 + endloop + endfacet + facet normal 0.28413 0.107592 0.95273 + outer loop + vertex 1.6208 1.74115 2.53608 + vertex 1.61986 1.73672 2.53686 + vertex 1.62333 1.73914 2.53555 + endloop + endfacet + facet normal 0.285056 0.1062 0.952609 + outer loop + vertex 1.62421 1.73508 2.53574 + vertex 1.62333 1.73914 2.53555 + vertex 1.61986 1.73672 2.53686 + endloop + endfacet + facet normal 0.28497 0.105934 0.952665 + outer loop + vertex 1.61986 1.73672 2.53686 + vertex 1.62099 1.73142 2.53711 + vertex 1.62421 1.73508 2.53574 + endloop + endfacet + facet normal 0.286613 0.104369 0.952344 + outer loop + vertex 1.62421 1.73508 2.53574 + vertex 1.62099 1.73142 2.53711 + vertex 1.62519 1.73023 2.53597 + endloop + endfacet + facet normal 0.29043 0.105084 0.951109 + outer loop + vertex 1.62519 1.73023 2.53597 + vertex 1.6283 1.73377 2.53463 + vertex 1.62421 1.73508 2.53574 + endloop + endfacet + facet normal 0.290654 0.105924 0.950947 + outer loop + vertex 1.6283 1.73377 2.53463 + vertex 1.62738 1.7391 2.53432 + vertex 1.62421 1.73508 2.53574 + endloop + endfacet + facet normal 0.292393 0.106192 0.950384 + outer loop + vertex 1.6283 1.73377 2.53463 + vertex 1.63107 1.73679 2.53345 + vertex 1.62738 1.7391 2.53432 + endloop + endfacet + facet normal 0.292431 0.10626 0.950365 + outer loop + vertex 1.63107 1.73679 2.53345 + vertex 1.63208 1.74144 2.53262 + vertex 1.62738 1.7391 2.53432 + endloop + endfacet + facet normal 0.2918 0.107561 0.950412 + outer loop + vertex 1.62738 1.7391 2.53432 + vertex 1.63208 1.74144 2.53262 + vertex 1.62837 1.74374 2.53349 + endloop + endfacet + facet normal 0.288518 0.108424 0.951316 + outer loop + vertex 1.6242 1.74363 2.53477 + vertex 1.62738 1.7391 2.53432 + vertex 1.62837 1.74374 2.53349 + endloop + endfacet + facet normal 0.291664 0.107315 0.950482 + outer loop + vertex 1.63208 1.74144 2.53262 + vertex 1.63117 1.74675 2.5323 + vertex 1.62837 1.74374 2.53349 + endloop + endfacet + facet normal 0.289234 0.109759 0.950945 + outer loop + vertex 1.62837 1.74374 2.53349 + vertex 1.63117 1.74675 2.5323 + vertex 1.62705 1.74782 2.53342 + endloop + endfacet + facet normal 0.289299 0.110066 0.95089 + outer loop + vertex 1.63117 1.74675 2.5323 + vertex 1.62999 1.75188 2.53206 + vertex 1.62705 1.74782 2.53342 + endloop + endfacet + facet normal 0.288948 0.109991 0.951005 + outer loop + vertex 1.62999 1.75188 2.53206 + vertex 1.63117 1.74675 2.5323 + vertex 1.63431 1.75026 2.53093 + endloop + endfacet + facet normal 0.289112 0.110505 0.950896 + outer loop + vertex 1.63431 1.75026 2.53093 + vertex 1.63345 1.75426 2.53073 + vertex 1.62999 1.75188 2.53206 + endloop + endfacet + facet normal 0.287548 0.112876 0.951091 + outer loop + vertex 1.63101 1.75622 2.53124 + vertex 1.62999 1.75188 2.53206 + vertex 1.63345 1.75426 2.53073 + endloop + endfacet + facet normal 0.289586 0.115656 0.950139 + outer loop + vertex 1.63345 1.75426 2.53073 + vertex 1.63444 1.7586 2.5299 + vertex 1.63101 1.75622 2.53124 + endloop + endfacet + facet normal 0.28808 0.117926 0.950318 + outer loop + vertex 1.63101 1.75622 2.53124 + vertex 1.63444 1.7586 2.5299 + vertex 1.63013 1.76019 2.53101 + endloop + endfacet + facet normal 0.285941 0.117493 0.951017 + outer loop + vertex 1.63013 1.76019 2.53101 + vertex 1.62703 1.75612 2.53244 + vertex 1.63101 1.75622 2.53124 + endloop + endfacet + facet normal 0.28618 0.113265 0.951458 + outer loop + vertex 1.63101 1.75622 2.53124 + vertex 1.62703 1.75612 2.53244 + vertex 1.62999 1.75188 2.53206 + endloop + endfacet + facet normal 0.287189 0.114005 0.951065 + outer loop + vertex 1.62703 1.75612 2.53244 + vertex 1.62603 1.75175 2.53327 + vertex 1.62999 1.75188 2.53206 + endloop + endfacet + facet normal 0.290507 0.110784 0.950438 + outer loop + vertex 1.63345 1.75426 2.53073 + vertex 1.63431 1.75026 2.53093 + vertex 1.63744 1.7543 2.52951 + endloop + endfacet + facet normal 0.290384 0.110889 0.950464 + outer loop + vertex 1.63854 1.74898 2.52979 + vertex 1.63744 1.7543 2.52951 + vertex 1.63431 1.75026 2.53093 + endloop + endfacet + facet normal 0.291071 0.107931 0.950594 + outer loop + vertex 1.63431 1.75026 2.53093 + vertex 1.63117 1.74675 2.5323 + vertex 1.63529 1.74542 2.53118 + endloop + endfacet + facet normal 0.294562 0.104029 0.949953 + outer loop + vertex 1.63237 1.73267 2.53349 + vertex 1.63107 1.73679 2.53345 + vertex 1.6283 1.73377 2.53463 + endloop + endfacet + facet normal 0.294413 0.103356 0.950073 + outer loop + vertex 1.62946 1.72862 2.53484 + vertex 1.63237 1.73267 2.53349 + vertex 1.6283 1.73377 2.53463 + endloop + endfacet + facet normal 0.295806 0.102251 0.94976 + outer loop + vertex 1.63337 1.7287 2.53361 + vertex 1.63237 1.73267 2.53349 + vertex 1.62946 1.72862 2.53484 + endloop + endfacet + facet normal 0.295939 0.0994848 0.950012 + outer loop + vertex 1.62946 1.72862 2.53484 + vertex 1.63237 1.7243 2.53438 + vertex 1.63337 1.7287 2.53361 + endloop + endfacet + facet normal 0.295617 0.0992546 0.950136 + outer loop + vertex 1.62841 1.72425 2.53562 + vertex 1.63237 1.7243 2.53438 + vertex 1.62946 1.72862 2.53484 + endloop + endfacet + facet normal 0.293902 0.0997519 0.950616 + outer loop + vertex 1.62841 1.72425 2.53562 + vertex 1.62946 1.72862 2.53484 + vertex 1.62602 1.72624 2.53615 + endloop + endfacet + facet normal 0.29096 0.0958494 0.951922 + outer loop + vertex 1.62602 1.72624 2.53615 + vertex 1.6249 1.72183 2.53694 + vertex 1.62841 1.72425 2.53562 + endloop + endfacet + facet normal 0.292115 0.0940805 0.951744 + outer loop + vertex 1.62922 1.72019 2.53577 + vertex 1.62841 1.72425 2.53562 + vertex 1.6249 1.72183 2.53694 + endloop + endfacet + facet normal 0.287913 0.0967709 0.952755 + outer loop + vertex 1.62602 1.72624 2.53615 + vertex 1.62204 1.72614 2.53736 + vertex 1.6249 1.72183 2.53694 + endloop + endfacet + facet normal 0.288209 0.0969777 0.952644 + outer loop + vertex 1.62204 1.72614 2.53736 + vertex 1.6209 1.72174 2.53815 + vertex 1.6249 1.72183 2.53694 + endloop + endfacet + facet normal 0.288387 0.0932657 0.952961 + outer loop + vertex 1.62171 1.71768 2.53831 + vertex 1.6249 1.72183 2.53694 + vertex 1.6209 1.72174 2.53815 + endloop + endfacet + facet normal 0.285257 0.0926844 0.953959 + outer loop + vertex 1.62171 1.71768 2.53831 + vertex 1.6209 1.72174 2.53815 + vertex 1.61737 1.71932 2.53944 + endloop + endfacet + facet normal 0.285412 0.0931597 0.953866 + outer loop + vertex 1.61845 1.71399 2.53964 + vertex 1.62171 1.71768 2.53831 + vertex 1.61737 1.71932 2.53944 + endloop + endfacet + facet normal 0.284661 0.0930179 0.954105 + outer loop + vertex 1.61845 1.71399 2.53964 + vertex 1.61737 1.71932 2.53944 + vertex 1.6142 1.7152 2.54079 + endloop + endfacet + facet normal 0.284875 0.0939047 0.953954 + outer loop + vertex 1.6152 1.71029 2.54098 + vertex 1.61845 1.71399 2.53964 + vertex 1.6142 1.7152 2.54079 + endloop + endfacet + facet normal 0.286033 0.092803 0.953715 + outer loop + vertex 1.61952 1.70866 2.53984 + vertex 1.61845 1.71399 2.53964 + vertex 1.6152 1.71029 2.54098 + endloop + endfacet + facet normal 0.286711 0.0948778 0.953307 + outer loop + vertex 1.61602 1.70625 2.54113 + vertex 1.61952 1.70866 2.53984 + vertex 1.6152 1.71029 2.54098 + endloop + endfacet + facet normal 0.28582 0.0947081 0.953592 + outer loop + vertex 1.6152 1.71029 2.54098 + vertex 1.61206 1.70616 2.54233 + vertex 1.61602 1.70625 2.54113 + endloop + endfacet + facet normal 0.285791 0.0953127 0.95354 + outer loop + vertex 1.61602 1.70625 2.54113 + vertex 1.61206 1.70616 2.54233 + vertex 1.61489 1.70184 2.54191 + endloop + endfacet + facet normal 0.286902 0.0949748 0.95324 + outer loop + vertex 1.61602 1.70625 2.54113 + vertex 1.61489 1.70184 2.54191 + vertex 1.61841 1.70426 2.54061 + endloop + endfacet + facet normal 0.287483 0.0940877 0.953153 + outer loop + vertex 1.61921 1.70019 2.54077 + vertex 1.61841 1.70426 2.54061 + vertex 1.61489 1.70184 2.54191 + endloop + endfacet + facet normal 0.28694 0.0924376 0.953478 + outer loop + vertex 1.61489 1.70184 2.54191 + vertex 1.6159 1.69644 2.54213 + vertex 1.61921 1.70019 2.54077 + endloop + endfacet + facet normal 0.288055 0.0913688 0.953245 + outer loop + vertex 1.61921 1.70019 2.54077 + vertex 1.6159 1.69644 2.54213 + vertex 1.62019 1.69522 2.54095 + endloop + endfacet + facet normal 0.289257 0.0915934 0.952859 + outer loop + vertex 1.62019 1.69522 2.54095 + vertex 1.62345 1.69896 2.5396 + vertex 1.61921 1.70019 2.54077 + endloop + endfacet + facet normal 0.289704 0.0934293 0.952545 + outer loop + vertex 1.62345 1.69896 2.5396 + vertex 1.62237 1.70432 2.53941 + vertex 1.61921 1.70019 2.54077 + endloop + endfacet + facet normal 0.29034 0.0935503 0.95234 + outer loop + vertex 1.62345 1.69896 2.5396 + vertex 1.62667 1.70266 2.53826 + vertex 1.62237 1.70432 2.53941 + endloop + endfacet + facet normal 0.29016 0.0930086 0.952448 + outer loop + vertex 1.62667 1.70266 2.53826 + vertex 1.62586 1.70672 2.53811 + vertex 1.62237 1.70432 2.53941 + endloop + endfacet + facet normal 0.289915 0.0933836 0.952486 + outer loop + vertex 1.62237 1.70432 2.53941 + vertex 1.62586 1.70672 2.53811 + vertex 1.62348 1.70872 2.53864 + endloop + endfacet + facet normal 0.288197 0.0938995 0.952956 + outer loop + vertex 1.61952 1.70866 2.53984 + vertex 1.62237 1.70432 2.53941 + vertex 1.62348 1.70872 2.53864 + endloop + endfacet + facet normal 0.288262 0.0923415 0.953089 + outer loop + vertex 1.62348 1.70872 2.53864 + vertex 1.62268 1.71277 2.53849 + vertex 1.61952 1.70866 2.53984 + endloop + endfacet + facet normal 0.289863 0.0926385 0.952574 + outer loop + vertex 1.62348 1.70872 2.53864 + vertex 1.62698 1.71114 2.53734 + vertex 1.62268 1.71277 2.53849 + endloop + endfacet + facet normal 0.288665 0.0942245 0.952782 + outer loop + vertex 1.61841 1.70426 2.54061 + vertex 1.62237 1.70432 2.53941 + vertex 1.61952 1.70866 2.53984 + endloop + endfacet + facet normal 0.289625 0.0930039 0.952611 + outer loop + vertex 1.62586 1.70672 2.53811 + vertex 1.62698 1.71114 2.53734 + vertex 1.62348 1.70872 2.53864 + endloop + endfacet + facet normal 0.291795 0.0923462 0.952012 + outer loop + vertex 1.62698 1.71114 2.53734 + vertex 1.62586 1.70672 2.53811 + vertex 1.62982 1.70678 2.53689 + endloop + endfacet + facet normal 0.291756 0.0933093 0.951931 + outer loop + vertex 1.62667 1.70266 2.53826 + vertex 1.62982 1.70678 2.53689 + vertex 1.62586 1.70672 2.53811 + endloop + endfacet + facet normal 0.291708 0.0922523 0.952048 + outer loop + vertex 1.62769 1.69772 2.53842 + vertex 1.62667 1.70266 2.53826 + vertex 1.62345 1.69896 2.5396 + endloop + endfacet + facet normal 0.291187 0.0901283 0.952411 + outer loop + vertex 1.62456 1.69359 2.53977 + vertex 1.62769 1.69772 2.53842 + vertex 1.62345 1.69896 2.5396 + endloop + endfacet + facet normal 0.292313 0.089189 0.952155 + outer loop + vertex 1.62853 1.69366 2.53855 + vertex 1.62769 1.69772 2.53842 + vertex 1.62456 1.69359 2.53977 + endloop + endfacet + facet normal 0.292571 0.0829049 0.952643 + outer loop + vertex 1.62456 1.69359 2.53977 + vertex 1.62735 1.68931 2.53929 + vertex 1.62853 1.69366 2.53855 + endloop + endfacet + facet normal 0.293314 0.0826689 0.952435 + outer loop + vertex 1.62735 1.68931 2.53929 + vertex 1.63088 1.6917 2.53799 + vertex 1.62853 1.69366 2.53855 + endloop + endfacet + facet normal 0.296191 0.0864585 0.951208 + outer loop + vertex 1.63088 1.6917 2.53799 + vertex 1.63199 1.69607 2.53725 + vertex 1.62853 1.69366 2.53855 + endloop + endfacet + facet normal 0.29683 0.0862658 0.951026 + outer loop + vertex 1.63199 1.69607 2.53725 + vertex 1.63088 1.6917 2.53799 + vertex 1.63476 1.69179 2.53677 + endloop + endfacet + facet normal 0.294611 0.0847366 0.951853 + outer loop + vertex 1.63593 1.69615 2.53602 + vertex 1.63199 1.69607 2.53725 + vertex 1.63476 1.69179 2.53677 + endloop + endfacet + facet normal 0.291593 0.0856899 0.952697 + outer loop + vertex 1.63593 1.69615 2.53602 + vertex 1.63476 1.69179 2.53677 + vertex 1.6383 1.69416 2.53548 + endloop + endfacet + facet normal 0.291355 0.0853779 0.952797 + outer loop + vertex 1.6383 1.69416 2.53548 + vertex 1.63946 1.6986 2.53473 + vertex 1.63593 1.69615 2.53602 + endloop + endfacet + facet normal 0.28931 0.0884913 0.953136 + outer loop + vertex 1.63593 1.69615 2.53602 + vertex 1.63946 1.6986 2.53473 + vertex 1.63511 1.7002 2.5359 + endloop + endfacet + facet normal 0.293559 0.0825833 0.952367 + outer loop + vertex 1.63893 1.69015 2.53563 + vertex 1.6383 1.69416 2.53548 + vertex 1.63476 1.69179 2.53677 + endloop + endfacet + facet normal 0.294405 0.08947 0.951484 + outer loop + vertex 1.63511 1.7002 2.5359 + vertex 1.63199 1.69607 2.53725 + vertex 1.63593 1.69615 2.53602 + endloop + endfacet + facet normal 0.297172 0.0788326 0.951564 + outer loop + vertex 1.63151 1.68773 2.53813 + vertex 1.63476 1.69179 2.53677 + vertex 1.63088 1.6917 2.53799 + endloop + endfacet + facet normal 0.297606 0.0784505 0.95146 + outer loop + vertex 1.63554 1.68656 2.53696 + vertex 1.63476 1.69179 2.53677 + vertex 1.63151 1.68773 2.53813 + endloop + endfacet + facet normal 0.295879 0.078641 0.951983 + outer loop + vertex 1.63151 1.68773 2.53813 + vertex 1.63088 1.6917 2.53799 + vertex 1.62735 1.68931 2.53929 + endloop + endfacet + facet normal 0.294582 0.0746929 0.952703 + outer loop + vertex 1.62808 1.68412 2.53947 + vertex 1.63151 1.68773 2.53813 + vertex 1.62735 1.68931 2.53929 + endloop + endfacet + facet normal 0.294222 0.0746464 0.952818 + outer loop + vertex 1.62808 1.68412 2.53947 + vertex 1.62735 1.68931 2.53929 + vertex 1.62405 1.68521 2.54063 + endloop + endfacet + facet normal 0.292897 0.0688675 0.953661 + outer loop + vertex 1.62458 1.68038 2.54081 + vertex 1.62808 1.68412 2.53947 + vertex 1.62405 1.68521 2.54063 + endloop + endfacet + facet normal 0.291066 0.0686877 0.954234 + outer loop + vertex 1.62405 1.68521 2.54063 + vertex 1.62058 1.68159 2.54195 + vertex 1.62458 1.68038 2.54081 + endloop + endfacet + facet normal 0.289941 0.0643871 0.954876 + outer loop + vertex 1.62058 1.68159 2.54195 + vertex 1.62099 1.67665 2.54216 + vertex 1.62458 1.68038 2.54081 + endloop + endfacet + facet normal 0.291027 0.0632482 0.954622 + outer loop + vertex 1.62458 1.68038 2.54081 + vertex 1.62099 1.67665 2.54216 + vertex 1.62499 1.67542 2.54102 + endloop + endfacet + facet normal 0.288717 0.0643006 0.955253 + outer loop + vertex 1.62099 1.67665 2.54216 + vertex 1.62058 1.68159 2.54195 + vertex 1.61696 1.67795 2.54329 + endloop + endfacet + facet normal 0.288073 0.0619963 0.955599 + outer loop + vertex 1.61734 1.67291 2.5435 + vertex 1.62099 1.67665 2.54216 + vertex 1.61696 1.67795 2.54329 + endloop + endfacet + facet normal 0.287055 0.0619321 0.95591 + outer loop + vertex 1.61734 1.67291 2.5435 + vertex 1.61696 1.67795 2.54329 + vertex 1.61328 1.67426 2.54463 + endloop + endfacet + facet normal 0.287006 0.0617634 0.955936 + outer loop + vertex 1.61369 1.66917 2.54484 + vertex 1.61734 1.67291 2.5435 + vertex 1.61328 1.67426 2.54463 + endloop + endfacet + facet normal 0.286133 0.0617031 0.956201 + outer loop + vertex 1.61369 1.66917 2.54484 + vertex 1.61328 1.67426 2.54463 + vertex 1.6097 1.67046 2.54595 + endloop + endfacet + facet normal 0.286537 0.0631333 0.955987 + outer loop + vertex 1.61012 1.66544 2.54615 + vertex 1.61369 1.66917 2.54484 + vertex 1.6097 1.67046 2.54595 + endloop + endfacet + facet normal 0.2853 0.0630448 0.956363 + outer loop + vertex 1.6097 1.67046 2.54595 + vertex 1.60613 1.6667 2.54726 + vertex 1.61012 1.66544 2.54615 + endloop + endfacet + facet normal 0.28574 0.0646515 0.956124 + outer loop + vertex 1.60613 1.6667 2.54726 + vertex 1.60662 1.66165 2.54746 + vertex 1.61012 1.66544 2.54615 + endloop + endfacet + facet normal 0.287231 0.0631537 0.955777 + outer loop + vertex 1.61012 1.66544 2.54615 + vertex 1.60662 1.66165 2.54746 + vertex 1.61069 1.66049 2.54631 + endloop + endfacet + facet normal 0.288557 0.0632917 0.955369 + outer loop + vertex 1.61069 1.66049 2.54631 + vertex 1.61414 1.66411 2.54503 + vertex 1.61012 1.66544 2.54615 + endloop + endfacet + facet normal 0.287484 0.0641845 0.955632 + outer loop + vertex 1.60662 1.66165 2.54746 + vertex 1.60736 1.65636 2.54759 + vertex 1.61069 1.66049 2.54631 + endloop + endfacet + facet normal 0.288806 0.0630197 0.955311 + outer loop + vertex 1.61069 1.66049 2.54631 + vertex 1.60736 1.65636 2.54759 + vertex 1.61131 1.65648 2.54639 + endloop + endfacet + facet normal 0.286041 0.0639921 0.956078 + outer loop + vertex 1.60736 1.65636 2.54759 + vertex 1.60662 1.66165 2.54746 + vertex 1.60313 1.65795 2.54875 + endloop + endfacet + facet normal 0.286199 0.0644707 0.955999 + outer loop + vertex 1.60378 1.65391 2.54883 + vertex 1.60736 1.65636 2.54759 + vertex 1.60313 1.65795 2.54875 + endloop + endfacet + facet normal 0.283999 0.0641349 0.956677 + outer loop + vertex 1.60378 1.65391 2.54883 + vertex 1.60313 1.65795 2.54875 + vertex 1.59979 1.6538 2.55002 + endloop + endfacet + facet normal 0.284123 0.06132 0.956825 + outer loop + vertex 1.59979 1.6538 2.55002 + vertex 1.60252 1.64954 2.54948 + vertex 1.60378 1.65391 2.54883 + endloop + endfacet + facet normal 0.28583 0.0607609 0.956352 + outer loop + vertex 1.60252 1.64954 2.54948 + vertex 1.60611 1.65198 2.54825 + vertex 1.60378 1.65391 2.54883 + endloop + endfacet + facet normal 0.286995 0.0589291 0.956118 + outer loop + vertex 1.60669 1.64797 2.54832 + vertex 1.60611 1.65198 2.54825 + vertex 1.60252 1.64954 2.54948 + endloop + endfacet + facet normal 0.289301 0.0592511 0.955403 + outer loop + vertex 1.60669 1.64797 2.54832 + vertex 1.61005 1.6521 2.54705 + vertex 1.60611 1.65198 2.54825 + endloop + endfacet + facet normal 0.289166 0.0621213 0.955261 + outer loop + vertex 1.60736 1.65636 2.54759 + vertex 1.60611 1.65198 2.54825 + vertex 1.61005 1.6521 2.54705 + endloop + endfacet + facet normal 0.288856 0.0619121 0.955369 + outer loop + vertex 1.61131 1.65648 2.54639 + vertex 1.60736 1.65636 2.54759 + vertex 1.61005 1.6521 2.54705 + endloop + endfacet + facet normal 0.290259 0.0614466 0.954973 + outer loop + vertex 1.61131 1.65648 2.54639 + vertex 1.61005 1.6521 2.54705 + vertex 1.61365 1.65454 2.5458 + endloop + endfacet + facet normal 0.290824 0.0605555 0.954858 + outer loop + vertex 1.61424 1.6505 2.54588 + vertex 1.61365 1.65454 2.5458 + vertex 1.61005 1.6521 2.54705 + endloop + endfacet + facet normal 0.290305 0.0590157 0.955113 + outer loop + vertex 1.61005 1.6521 2.54705 + vertex 1.61075 1.64679 2.54717 + vertex 1.61424 1.6505 2.54588 + endloop + endfacet + facet normal 0.291123 0.0581766 0.954915 + outer loop + vertex 1.61424 1.6505 2.54588 + vertex 1.61075 1.64679 2.54717 + vertex 1.61483 1.64543 2.54601 + endloop + endfacet + facet normal 0.291811 0.0582509 0.954701 + outer loop + vertex 1.61483 1.64543 2.54601 + vertex 1.61834 1.64928 2.5447 + vertex 1.61424 1.6505 2.54588 + endloop + endfacet + facet normal 0.2923 0.0601589 0.954433 + outer loop + vertex 1.61834 1.64928 2.5447 + vertex 1.61766 1.65473 2.54456 + vertex 1.61424 1.6505 2.54588 + endloop + endfacet + facet normal 0.291959 0.0601189 0.954539 + outer loop + vertex 1.61834 1.64928 2.5447 + vertex 1.62198 1.65302 2.54335 + vertex 1.61766 1.65473 2.54456 + endloop + endfacet + facet normal 0.292078 0.0604593 0.954482 + outer loop + vertex 1.62198 1.65302 2.54335 + vertex 1.6217 1.65782 2.54313 + vertex 1.61766 1.65473 2.54456 + endloop + endfacet + facet normal 0.291221 0.0616651 0.954666 + outer loop + vertex 1.61766 1.65473 2.54456 + vertex 1.6217 1.65782 2.54313 + vertex 1.61868 1.65915 2.54396 + endloop + endfacet + facet normal 0.291166 0.06168 0.954682 + outer loop + vertex 1.61486 1.6589 2.54515 + vertex 1.61766 1.65473 2.54456 + vertex 1.61868 1.65915 2.54396 + endloop + endfacet + facet normal 0.291216 0.0610362 0.954708 + outer loop + vertex 1.61868 1.65915 2.54396 + vertex 1.61806 1.66291 2.54391 + vertex 1.61486 1.6589 2.54515 + endloop + endfacet + facet normal 0.290763 0.060964 0.954851 + outer loop + vertex 1.61868 1.65915 2.54396 + vertex 1.62109 1.66154 2.54308 + vertex 1.61806 1.66291 2.54391 + endloop + endfacet + facet normal 0.29045 0.0601816 0.954996 + outer loop + vertex 1.62109 1.66154 2.54308 + vertex 1.6221 1.66607 2.54249 + vertex 1.61806 1.66291 2.54391 + endloop + endfacet + facet normal 0.290239 0.0604717 0.955042 + outer loop + vertex 1.61806 1.66291 2.54391 + vertex 1.6221 1.66607 2.54249 + vertex 1.61774 1.6678 2.5437 + endloop + endfacet + facet normal 0.289684 0.0604424 0.955212 + outer loop + vertex 1.61806 1.66291 2.54391 + vertex 1.61774 1.6678 2.5437 + vertex 1.61414 1.66411 2.54503 + endloop + endfacet + facet normal 0.2901 0.0620118 0.954985 + outer loop + vertex 1.61486 1.6589 2.54515 + vertex 1.61806 1.66291 2.54391 + vertex 1.61414 1.66411 2.54503 + endloop + endfacet + facet normal 0.289828 0.0619757 0.95507 + outer loop + vertex 1.61486 1.6589 2.54515 + vertex 1.61414 1.66411 2.54503 + vertex 1.61069 1.66049 2.54631 + endloop + endfacet + facet normal 0.2886 0.0615943 0.955467 + outer loop + vertex 1.61414 1.66411 2.54503 + vertex 1.61774 1.6678 2.5437 + vertex 1.61369 1.66917 2.54484 + endloop + endfacet + facet normal 0.291861 0.0598159 0.954589 + outer loop + vertex 1.6221 1.66607 2.54249 + vertex 1.62109 1.66154 2.54308 + vertex 1.62492 1.66188 2.54189 + endloop + endfacet + facet normal 0.291748 0.0609574 0.954551 + outer loop + vertex 1.6217 1.65782 2.54313 + vertex 1.62492 1.66188 2.54189 + vertex 1.62109 1.66154 2.54308 + endloop + endfacet + facet normal 0.29163 0.0620144 0.954519 + outer loop + vertex 1.61365 1.65454 2.5458 + vertex 1.61766 1.65473 2.54456 + vertex 1.61486 1.6589 2.54515 + endloop + endfacet + facet normal 0.290872 0.0622586 0.954734 + outer loop + vertex 1.61365 1.65454 2.5458 + vertex 1.61486 1.6589 2.54515 + vertex 1.61131 1.65648 2.54639 + endloop + endfacet + facet normal 0.290892 0.060823 0.954821 + outer loop + vertex 1.6217 1.65782 2.54313 + vertex 1.62109 1.66154 2.54308 + vertex 1.61868 1.65915 2.54396 + endloop + endfacet + facet normal 0.292892 0.0604968 0.95423 + outer loop + vertex 1.62198 1.65302 2.54335 + vertex 1.6256 1.6567 2.542 + vertex 1.6217 1.65782 2.54313 + endloop + endfacet + facet normal 0.294741 0.05852 0.953784 + outer loop + vertex 1.626 1.65167 2.54219 + vertex 1.6256 1.6567 2.542 + vertex 1.62198 1.65302 2.54335 + endloop + endfacet + facet normal 0.294566 0.057918 0.953874 + outer loop + vertex 1.62243 1.64789 2.54352 + vertex 1.626 1.65167 2.54219 + vertex 1.62198 1.65302 2.54335 + endloop + endfacet + facet normal 0.29765 0.0547291 0.953105 + outer loop + vertex 1.62646 1.64653 2.54234 + vertex 1.626 1.65167 2.54219 + vertex 1.62243 1.64789 2.54352 + endloop + endfacet + facet normal 0.297414 0.0539306 0.953224 + outer loop + vertex 1.623 1.6428 2.54363 + vertex 1.62646 1.64653 2.54234 + vertex 1.62243 1.64789 2.54352 + endloop + endfacet + facet normal 0.296418 0.053826 0.95354 + outer loop + vertex 1.623 1.6428 2.54363 + vertex 1.62243 1.64789 2.54352 + vertex 1.61892 1.64406 2.54483 + endloop + endfacet + facet normal 0.296109 0.0526771 0.9537 + outer loop + vertex 1.6197 1.63875 2.54488 + vertex 1.623 1.6428 2.54363 + vertex 1.61892 1.64406 2.54483 + endloop + endfacet + facet normal 0.29488 0.0525012 0.954091 + outer loop + vertex 1.6197 1.63875 2.54488 + vertex 1.61892 1.64406 2.54483 + vertex 1.61553 1.64028 2.54608 + endloop + endfacet + facet normal 0.294516 0.0513786 0.954264 + outer loop + vertex 1.61652 1.63616 2.546 + vertex 1.6197 1.63875 2.54488 + vertex 1.61553 1.64028 2.54608 + endloop + endfacet + facet normal 0.2914 0.0506134 0.955262 + outer loop + vertex 1.61553 1.64028 2.54608 + vertex 1.61234 1.63582 2.54729 + vertex 1.61652 1.63616 2.546 + endloop + endfacet + facet normal 0.29176 0.0465308 0.955359 + outer loop + vertex 1.61652 1.63616 2.546 + vertex 1.61234 1.63582 2.54729 + vertex 1.61663 1.63112 2.54621 + endloop + endfacet + facet normal 0.29314 0.0479008 0.954869 + outer loop + vertex 1.61234 1.63582 2.54729 + vertex 1.61139 1.63116 2.54782 + vertex 1.61663 1.63112 2.54621 + endloop + endfacet + facet normal 0.293149 0.0464492 0.954938 + outer loop + vertex 1.61183 1.62732 2.54787 + vertex 1.61663 1.63112 2.54621 + vertex 1.61139 1.63116 2.54782 + endloop + endfacet + facet normal 0.29065 0.046175 0.955715 + outer loop + vertex 1.61183 1.62732 2.54787 + vertex 1.61139 1.63116 2.54782 + vertex 1.60857 1.62888 2.54879 + endloop + endfacet + facet normal 0.290349 0.0454749 0.95584 + outer loop + vertex 1.60747 1.62449 2.54933 + vertex 1.61183 1.62732 2.54787 + vertex 1.60857 1.62888 2.54879 + endloop + endfacet + facet normal 0.288485 0.0460053 0.956379 + outer loop + vertex 1.6046 1.62874 2.54999 + vertex 1.60747 1.62449 2.54933 + vertex 1.60857 1.62888 2.54879 + endloop + endfacet + facet normal 0.288419 0.0474438 0.956328 + outer loop + vertex 1.60857 1.62888 2.54879 + vertex 1.60796 1.63275 2.54878 + vertex 1.6046 1.62874 2.54999 + endloop + endfacet + facet normal 0.288145 0.0476948 0.956398 + outer loop + vertex 1.6046 1.62874 2.54999 + vertex 1.60796 1.63275 2.54878 + vertex 1.60393 1.63409 2.54993 + endloop + endfacet + facet normal 0.28861 0.0492827 0.956178 + outer loop + vertex 1.60796 1.63275 2.54878 + vertex 1.60764 1.63778 2.54862 + vertex 1.60393 1.63409 2.54993 + endloop + endfacet + facet normal 0.289546 0.0493324 0.955892 + outer loop + vertex 1.60796 1.63275 2.54878 + vertex 1.61234 1.63582 2.54729 + vertex 1.60764 1.63778 2.54862 + endloop + endfacet + facet normal 0.290172 0.0510259 0.955613 + outer loop + vertex 1.61234 1.63582 2.54729 + vertex 1.61133 1.64155 2.54729 + vertex 1.60764 1.63778 2.54862 + endloop + endfacet + facet normal 0.288843 0.0524399 0.955939 + outer loop + vertex 1.60764 1.63778 2.54862 + vertex 1.61133 1.64155 2.54729 + vertex 1.6072 1.64298 2.54846 + endloop + endfacet + facet normal 0.288589 0.0524208 0.956017 + outer loop + vertex 1.60764 1.63778 2.54862 + vertex 1.6072 1.64298 2.54846 + vertex 1.60357 1.63923 2.54976 + endloop + endfacet + facet normal 0.287369 0.0537044 0.956313 + outer loop + vertex 1.60357 1.63923 2.54976 + vertex 1.6072 1.64298 2.54846 + vertex 1.60319 1.6443 2.54959 + endloop + endfacet + facet normal 0.288069 0.0561303 0.955963 + outer loop + vertex 1.6072 1.64298 2.54846 + vertex 1.60669 1.64797 2.54832 + vertex 1.60319 1.6443 2.54959 + endloop + endfacet + facet normal 0.288971 0.0562145 0.955686 + outer loop + vertex 1.6072 1.64298 2.54846 + vertex 1.61075 1.64679 2.54717 + vertex 1.60669 1.64797 2.54832 + endloop + endfacet + facet normal 0.289754 0.055421 0.955495 + outer loop + vertex 1.61133 1.64155 2.54729 + vertex 1.61075 1.64679 2.54717 + vertex 1.6072 1.64298 2.54846 + endloop + endfacet + facet normal 0.2908 0.0447297 0.955738 + outer loop + vertex 1.61181 1.6227 2.54809 + vertex 1.61183 1.62732 2.54787 + vertex 1.60747 1.62449 2.54933 + endloop + endfacet + facet normal 0.290744 0.0445779 0.955762 + outer loop + vertex 1.60814 1.6192 2.54937 + vertex 1.61181 1.6227 2.54809 + vertex 1.60747 1.62449 2.54933 + endloop + endfacet + facet normal 0.293046 0.0419517 0.955178 + outer loop + vertex 1.61217 1.61796 2.54819 + vertex 1.61181 1.6227 2.54809 + vertex 1.60814 1.6192 2.54937 + endloop + endfacet + facet normal 0.294186 0.04203 0.954824 + outer loop + vertex 1.61217 1.61796 2.54819 + vertex 1.61577 1.62153 2.54692 + vertex 1.61181 1.6227 2.54809 + endloop + endfacet + facet normal 0.296799 0.0391481 0.954137 + outer loop + vertex 1.61608 1.61679 2.54702 + vertex 1.61577 1.62153 2.54692 + vertex 1.61217 1.61796 2.54819 + endloop + endfacet + facet normal 0.296779 0.0390694 0.954147 + outer loop + vertex 1.61232 1.61308 2.54834 + vertex 1.61608 1.61679 2.54702 + vertex 1.61217 1.61796 2.54819 + endloop + endfacet + facet normal 0.29551 0.0390418 0.954542 + outer loop + vertex 1.61232 1.61308 2.54834 + vertex 1.61217 1.61796 2.54819 + vertex 1.60847 1.61427 2.54949 + endloop + endfacet + facet normal 0.295549 0.0391879 0.954523 + outer loop + vertex 1.60857 1.60933 2.54966 + vertex 1.61232 1.61308 2.54834 + vertex 1.60847 1.61427 2.54949 + endloop + endfacet + facet normal 0.297545 0.0370042 0.95399 + outer loop + vertex 1.61236 1.6081 2.54852 + vertex 1.61232 1.61308 2.54834 + vertex 1.60857 1.60933 2.54966 + endloop + endfacet + facet normal 0.299169 0.036998 0.953482 + outer loop + vertex 1.61236 1.6081 2.54852 + vertex 1.61612 1.61186 2.5472 + vertex 1.61232 1.61308 2.54834 + endloop + endfacet + facet normal 0.300577 0.0354529 0.953098 + outer loop + vertex 1.61618 1.60682 2.54737 + vertex 1.61612 1.61186 2.5472 + vertex 1.61236 1.6081 2.54852 + endloop + endfacet + facet normal 0.301033 0.0369958 0.952896 + outer loop + vertex 1.61248 1.60304 2.54868 + vertex 1.61618 1.60682 2.54737 + vertex 1.61236 1.6081 2.54852 + endloop + endfacet + facet normal 0.29853 0.0369604 0.953684 + outer loop + vertex 1.61248 1.60304 2.54868 + vertex 1.61236 1.6081 2.54852 + vertex 1.60864 1.60434 2.54983 + endloop + endfacet + facet normal 0.298847 0.0380195 0.953544 + outer loop + vertex 1.60882 1.5993 2.54998 + vertex 1.61248 1.60304 2.54868 + vertex 1.60864 1.60434 2.54983 + endloop + endfacet + facet normal 0.299328 0.0375027 0.953413 + outer loop + vertex 1.6128 1.5979 2.54879 + vertex 1.61248 1.60304 2.54868 + vertex 1.60882 1.5993 2.54998 + endloop + endfacet + facet normal 0.299391 0.037703 0.953385 + outer loop + vertex 1.60919 1.59423 2.55006 + vertex 1.6128 1.5979 2.54879 + vertex 1.60882 1.5993 2.54998 + endloop + endfacet + facet normal 0.299909 0.0371453 0.953244 + outer loop + vertex 1.61308 1.59299 2.54889 + vertex 1.6128 1.5979 2.54879 + vertex 1.60919 1.59423 2.55006 + endloop + endfacet + facet normal 0.299318 0.0350351 0.95351 + outer loop + vertex 1.60986 1.58897 2.55005 + vertex 1.61308 1.59299 2.54889 + vertex 1.60919 1.59423 2.55006 + endloop + endfacet + facet normal 0.300404 0.0340756 0.953203 + outer loop + vertex 1.61366 1.5892 2.54884 + vertex 1.61308 1.59299 2.54889 + vertex 1.60986 1.58897 2.55005 + endloop + endfacet + facet normal 0.300737 0.0290119 0.953266 + outer loop + vertex 1.60986 1.58897 2.55005 + vertex 1.6126 1.58477 2.54931 + vertex 1.61366 1.5892 2.54884 + endloop + endfacet + facet normal 0.30369 0.0282084 0.952353 + outer loop + vertex 1.6126 1.58477 2.54931 + vertex 1.61664 1.58784 2.54793 + vertex 1.61366 1.5892 2.54884 + endloop + endfacet + facet normal 0.304855 0.031076 0.951892 + outer loop + vertex 1.61664 1.58784 2.54793 + vertex 1.61608 1.59158 2.54799 + vertex 1.61366 1.5892 2.54884 + endloop + endfacet + facet normal 0.30527 0.0311411 0.951756 + outer loop + vertex 1.61664 1.58784 2.54793 + vertex 1.61988 1.5919 2.54676 + vertex 1.61608 1.59158 2.54799 + endloop + endfacet + facet normal 0.305102 0.0261762 0.95196 + outer loop + vertex 1.61686 1.58307 2.54799 + vertex 1.61664 1.58784 2.54793 + vertex 1.6126 1.58477 2.54931 + endloop + endfacet + facet normal 0.304452 0.0243421 0.952217 + outer loop + vertex 1.61315 1.57937 2.54927 + vertex 1.61686 1.58307 2.54799 + vertex 1.6126 1.58477 2.54931 + endloop + endfacet + facet normal 0.306796 0.0217541 0.951527 + outer loop + vertex 1.61708 1.57807 2.54803 + vertex 1.61686 1.58307 2.54799 + vertex 1.61315 1.57937 2.54927 + endloop + endfacet + facet normal 0.30708 0.0217656 0.951435 + outer loop + vertex 1.61708 1.57807 2.54803 + vertex 1.62079 1.58178 2.54675 + vertex 1.61686 1.58307 2.54799 + endloop + endfacet + facet normal 0.307678 0.0238208 0.951192 + outer loop + vertex 1.62079 1.58178 2.54675 + vertex 1.62051 1.58673 2.54672 + vertex 1.61686 1.58307 2.54799 + endloop + endfacet + facet normal 0.309411 0.0191909 0.950735 + outer loop + vertex 1.62088 1.57682 2.54682 + vertex 1.62079 1.58178 2.54675 + vertex 1.61708 1.57807 2.54803 + endloop + endfacet + facet normal 0.309168 0.0183607 0.95083 + outer loop + vertex 1.61715 1.57309 2.54811 + vertex 1.62088 1.57682 2.54682 + vertex 1.61708 1.57807 2.54803 + endloop + endfacet + facet normal 0.308407 0.0183543 0.951078 + outer loop + vertex 1.61715 1.57309 2.54811 + vertex 1.61708 1.57807 2.54803 + vertex 1.61337 1.57433 2.54931 + endloop + endfacet + facet normal 0.308038 0.0170996 0.95122 + outer loop + vertex 1.61343 1.56935 2.54938 + vertex 1.61715 1.57309 2.54811 + vertex 1.61337 1.57433 2.54931 + endloop + endfacet + facet normal 0.309736 0.0152344 0.950701 + outer loop + vertex 1.61716 1.5681 2.54818 + vertex 1.61715 1.57309 2.54811 + vertex 1.61343 1.56935 2.54938 + endloop + endfacet + facet normal 0.310999 0.0152321 0.950288 + outer loop + vertex 1.61716 1.5681 2.54818 + vertex 1.62088 1.57184 2.54691 + vertex 1.61715 1.57309 2.54811 + endloop + endfacet + facet normal 0.312673 0.0133864 0.949767 + outer loop + vertex 1.62091 1.56685 2.54697 + vertex 1.62088 1.57184 2.54691 + vertex 1.61716 1.5681 2.54818 + endloop + endfacet + facet normal 0.312289 0.0121034 0.94991 + outer loop + vertex 1.61719 1.56311 2.54824 + vertex 1.62091 1.56685 2.54697 + vertex 1.61716 1.5681 2.54818 + endloop + endfacet + facet normal 0.31076 0.0120995 0.950411 + outer loop + vertex 1.61719 1.56311 2.54824 + vertex 1.61716 1.5681 2.54818 + vertex 1.61344 1.56436 2.54945 + endloop + endfacet + facet normal 0.31032 0.0106252 0.950573 + outer loop + vertex 1.61347 1.55937 2.54949 + vertex 1.61719 1.56311 2.54824 + vertex 1.61344 1.56436 2.54945 + endloop + endfacet + facet normal 0.311668 0.00914071 0.950147 + outer loop + vertex 1.61723 1.55812 2.54827 + vertex 1.61719 1.56311 2.54824 + vertex 1.61347 1.55937 2.54949 + endloop + endfacet + facet normal 0.313636 0.00915336 0.949499 + outer loop + vertex 1.61723 1.55812 2.54827 + vertex 1.62095 1.56185 2.54701 + vertex 1.61719 1.56311 2.54824 + endloop + endfacet + facet normal 0.314545 0.00814988 0.949208 + outer loop + vertex 1.621 1.55686 2.54704 + vertex 1.62095 1.56185 2.54701 + vertex 1.61723 1.55812 2.54827 + endloop + endfacet + facet normal 0.314378 0.00759106 0.949268 + outer loop + vertex 1.61727 1.55312 2.5483 + vertex 1.621 1.55686 2.54704 + vertex 1.61723 1.55812 2.54827 + endloop + endfacet + facet normal 0.312277 0.00757896 0.949961 + outer loop + vertex 1.61727 1.55312 2.5483 + vertex 1.61723 1.55812 2.54827 + vertex 1.61351 1.55438 2.54953 + endloop + endfacet + facet normal 0.312403 0.00800191 0.949916 + outer loop + vertex 1.61355 1.54938 2.54956 + vertex 1.61727 1.55312 2.5483 + vertex 1.61351 1.55438 2.54953 + endloop + endfacet + facet normal 0.31247 0.00792776 0.949894 + outer loop + vertex 1.6173 1.54813 2.54833 + vertex 1.61727 1.55312 2.5483 + vertex 1.61355 1.54938 2.54956 + endloop + endfacet + facet normal 0.314562 0.00793639 0.949204 + outer loop + vertex 1.6173 1.54813 2.54833 + vertex 1.62103 1.55187 2.54707 + vertex 1.61727 1.55312 2.5483 + endloop + endfacet + facet normal 0.314154 0.00838708 0.949335 + outer loop + vertex 1.62106 1.54688 2.5471 + vertex 1.62103 1.55187 2.54707 + vertex 1.6173 1.54813 2.54833 + endloop + endfacet + facet normal 0.314063 0.00808021 0.949368 + outer loop + vertex 1.61733 1.54314 2.54836 + vertex 1.62106 1.54688 2.5471 + vertex 1.6173 1.54813 2.54833 + endloop + endfacet + facet normal 0.311966 0.0080726 0.950059 + outer loop + vertex 1.61733 1.54314 2.54836 + vertex 1.6173 1.54813 2.54833 + vertex 1.61357 1.54439 2.54959 + endloop + endfacet + facet normal 0.311546 0.0066617 0.950208 + outer loop + vertex 1.6136 1.53939 2.54961 + vertex 1.61733 1.54314 2.54836 + vertex 1.61357 1.54439 2.54959 + endloop + endfacet + facet normal 0.311097 0.00715692 0.950351 + outer loop + vertex 1.61736 1.53815 2.54839 + vertex 1.61733 1.54314 2.54836 + vertex 1.6136 1.53939 2.54961 + endloop + endfacet + facet normal 0.313234 0.00716361 0.949649 + outer loop + vertex 1.61736 1.53815 2.54839 + vertex 1.62109 1.54189 2.54713 + vertex 1.61733 1.54314 2.54836 + endloop + endfacet + facet normal 0.313363 0.00702086 0.949607 + outer loop + vertex 1.62112 1.5369 2.54716 + vertex 1.62109 1.54189 2.54713 + vertex 1.61736 1.53815 2.54839 + endloop + endfacet + facet normal 0.312816 0.00517882 0.9498 + outer loop + vertex 1.61738 1.53315 2.54841 + vertex 1.62112 1.5369 2.54716 + vertex 1.61736 1.53815 2.54839 + endloop + endfacet + facet normal 0.310257 0.00517304 0.950639 + outer loop + vertex 1.61738 1.53315 2.54841 + vertex 1.61736 1.53815 2.54839 + vertex 1.61361 1.5344 2.54964 + endloop + endfacet + facet normal 0.30981 0.00367632 0.950791 + outer loop + vertex 1.61362 1.52941 2.54965 + vertex 1.61738 1.53315 2.54841 + vertex 1.61361 1.5344 2.54964 + endloop + endfacet + facet normal 0.309719 0.00377721 0.950821 + outer loop + vertex 1.61739 1.52816 2.54843 + vertex 1.61738 1.53315 2.54841 + vertex 1.61362 1.52941 2.54965 + endloop + endfacet + facet normal 0.313107 0.0037839 0.94971 + outer loop + vertex 1.61739 1.52816 2.54843 + vertex 1.62114 1.53191 2.54718 + vertex 1.61738 1.53315 2.54841 + endloop + endfacet + facet normal 0.313903 0.00290138 0.949451 + outer loop + vertex 1.62115 1.52691 2.54719 + vertex 1.62114 1.53191 2.54718 + vertex 1.61739 1.52816 2.54843 + endloop + endfacet + facet normal 0.313977 0.00314907 0.949425 + outer loop + vertex 1.61741 1.52317 2.54844 + vertex 1.62115 1.52691 2.54719 + vertex 1.61739 1.52816 2.54843 + endloop + endfacet + facet normal 0.310382 0.00313833 0.950607 + outer loop + vertex 1.61741 1.52317 2.54844 + vertex 1.61739 1.52816 2.54843 + vertex 1.61364 1.52442 2.54967 + endloop + endfacet + facet normal 0.310644 0.00401558 0.950518 + outer loop + vertex 1.61367 1.51942 2.54968 + vertex 1.61741 1.52317 2.54844 + vertex 1.61364 1.52442 2.54967 + endloop + endfacet + facet normal 0.311913 0.00261104 0.950107 + outer loop + vertex 1.61743 1.51817 2.54845 + vertex 1.61741 1.52317 2.54844 + vertex 1.61367 1.51942 2.54968 + endloop + endfacet + facet normal 0.315239 0.00262386 0.949009 + outer loop + vertex 1.61743 1.51817 2.54845 + vertex 1.62117 1.52192 2.54719 + vertex 1.61741 1.52317 2.54844 + endloop + endfacet + facet normal 0.316659 0.0010506 0.948539 + outer loop + vertex 1.62118 1.51693 2.5472 + vertex 1.62117 1.52192 2.54719 + vertex 1.61743 1.51817 2.54845 + endloop + endfacet + facet normal 0.316722 0.00126268 0.948518 + outer loop + vertex 1.61745 1.51318 2.54845 + vertex 1.62118 1.51693 2.5472 + vertex 1.61743 1.51817 2.54845 + endloop + endfacet + facet normal 0.314051 0.00125416 0.949405 + outer loop + vertex 1.61745 1.51318 2.54845 + vertex 1.61743 1.51817 2.54845 + vertex 1.61369 1.51443 2.54969 + endloop + endfacet + facet normal 0.314146 0.00157127 0.949373 + outer loop + vertex 1.61371 1.50944 2.54969 + vertex 1.61745 1.51318 2.54845 + vertex 1.61369 1.51443 2.54969 + endloop + endfacet + facet normal 0.315987 -0.000468562 0.948763 + outer loop + vertex 1.61745 1.50819 2.54844 + vertex 1.61745 1.51318 2.54845 + vertex 1.61371 1.50944 2.54969 + endloop + endfacet + facet normal 0.317892 -0.000465921 0.948127 + outer loop + vertex 1.61745 1.50819 2.54844 + vertex 1.62119 1.51194 2.54719 + vertex 1.61745 1.51318 2.54845 + endloop + endfacet + facet normal 0.318808 -0.00148163 0.947818 + outer loop + vertex 1.62118 1.50695 2.54719 + vertex 1.62119 1.51194 2.54719 + vertex 1.61745 1.50819 2.54844 + endloop + endfacet + facet normal 0.318774 -0.00159471 0.947829 + outer loop + vertex 1.61745 1.5032 2.54844 + vertex 1.62118 1.50695 2.54719 + vertex 1.61745 1.50819 2.54844 + endloop + endfacet + facet normal 0.316956 -0.00159394 0.948439 + outer loop + vertex 1.61745 1.5032 2.54844 + vertex 1.61745 1.50819 2.54844 + vertex 1.61372 1.50445 2.54969 + endloop + endfacet + facet normal 0.316837 -0.00198671 0.948478 + outer loop + vertex 1.61371 1.49946 2.54968 + vertex 1.61745 1.5032 2.54844 + vertex 1.61372 1.50445 2.54969 + endloop + endfacet + facet normal 0.317348 -0.00255451 0.948306 + outer loop + vertex 1.61744 1.49821 2.54843 + vertex 1.61745 1.5032 2.54844 + vertex 1.61371 1.49946 2.54968 + endloop + endfacet + facet normal 0.319025 -0.00255656 0.947743 + outer loop + vertex 1.61744 1.49821 2.54843 + vertex 1.62117 1.50195 2.54718 + vertex 1.61745 1.5032 2.54844 + endloop + endfacet + facet normal 0.319259 -0.00281613 0.947663 + outer loop + vertex 1.62116 1.49696 2.54717 + vertex 1.62117 1.50195 2.54718 + vertex 1.61744 1.49821 2.54843 + endloop + endfacet + facet normal 0.319088 -0.00338245 0.947719 + outer loop + vertex 1.61742 1.49322 2.54841 + vertex 1.62116 1.49696 2.54717 + vertex 1.61744 1.49821 2.54843 + endloop + endfacet + facet normal 0.317492 -0.00337939 0.948255 + outer loop + vertex 1.61742 1.49322 2.54841 + vertex 1.61744 1.49821 2.54843 + vertex 1.6137 1.49447 2.54966 + endloop + endfacet + facet normal 0.317275 -0.00409573 0.948325 + outer loop + vertex 1.61369 1.48948 2.54965 + vertex 1.61742 1.49322 2.54841 + vertex 1.6137 1.49447 2.54966 + endloop + endfacet + facet normal 0.317555 -0.00440724 0.94823 + outer loop + vertex 1.61741 1.48823 2.5484 + vertex 1.61742 1.49322 2.54841 + vertex 1.61369 1.48948 2.54965 + endloop + endfacet + facet normal 0.319125 -0.00441134 0.947702 + outer loop + vertex 1.61741 1.48823 2.5484 + vertex 1.62114 1.49197 2.54716 + vertex 1.61742 1.49322 2.54841 + endloop + endfacet + facet normal 0.319303 -0.00460935 0.947641 + outer loop + vertex 1.62112 1.48698 2.54714 + vertex 1.62114 1.49197 2.54716 + vertex 1.61741 1.48823 2.5484 + endloop + endfacet + facet normal 0.319119 -0.00522034 0.9477 + outer loop + vertex 1.61738 1.48324 2.54838 + vertex 1.62112 1.48698 2.54714 + vertex 1.61741 1.48823 2.5484 + endloop + endfacet + facet normal 0.317258 -0.00521369 0.948325 + outer loop + vertex 1.61738 1.48324 2.54838 + vertex 1.61741 1.48823 2.5484 + vertex 1.61366 1.48448 2.54963 + endloop + endfacet + facet normal 0.316876 -0.00647398 0.948445 + outer loop + vertex 1.61363 1.47948 2.5496 + vertex 1.61738 1.48324 2.54838 + vertex 1.61366 1.48448 2.54963 + endloop + endfacet + facet normal 0.316407 -0.00595285 0.948605 + outer loop + vertex 1.61735 1.47824 2.54835 + vertex 1.61738 1.48324 2.54838 + vertex 1.61363 1.47948 2.5496 + endloop + endfacet + facet normal 0.31831 -0.00596082 0.947968 + outer loop + vertex 1.61735 1.47824 2.54835 + vertex 1.6211 1.48199 2.54712 + vertex 1.61738 1.48324 2.54838 + endloop + endfacet + facet normal 0.317607 -0.00517976 0.948208 + outer loop + vertex 1.62108 1.47699 2.5471 + vertex 1.6211 1.48199 2.54712 + vertex 1.61735 1.47824 2.54835 + endloop + endfacet + facet normal 0.317159 -0.00666098 0.948349 + outer loop + vertex 1.61732 1.47324 2.54833 + vertex 1.62108 1.47699 2.5471 + vertex 1.61735 1.47824 2.54835 + endloop + endfacet + facet normal 0.315275 -0.00665306 0.948977 + outer loop + vertex 1.61732 1.47324 2.54833 + vertex 1.61735 1.47824 2.54835 + vertex 1.6136 1.47448 2.54958 + endloop + endfacet + facet normal 0.314629 -0.00878245 0.949174 + outer loop + vertex 1.61356 1.46949 2.54954 + vertex 1.61732 1.47324 2.54833 + vertex 1.6136 1.47448 2.54958 + endloop + endfacet + facet normal 0.314216 -0.00832255 0.949315 + outer loop + vertex 1.61729 1.46824 2.5483 + vertex 1.61732 1.47324 2.54833 + vertex 1.61356 1.46949 2.54954 + endloop + endfacet + facet normal 0.315934 -0.00832983 0.948745 + outer loop + vertex 1.61729 1.46824 2.5483 + vertex 1.62105 1.47199 2.54708 + vertex 1.61732 1.47324 2.54833 + endloop + endfacet + facet normal 0.315943 -0.00833957 0.948742 + outer loop + vertex 1.62102 1.46699 2.54704 + vertex 1.62105 1.47199 2.54708 + vertex 1.61729 1.46824 2.5483 + endloop + endfacet + facet normal 0.315341 -0.0103183 0.948922 + outer loop + vertex 1.61726 1.46327 2.54825 + vertex 1.62102 1.46699 2.54704 + vertex 1.61729 1.46824 2.5483 + endloop + endfacet + facet normal 0.313473 -0.0103112 0.949541 + outer loop + vertex 1.61726 1.46327 2.54825 + vertex 1.61729 1.46824 2.5483 + vertex 1.61353 1.46452 2.5495 + endloop + endfacet + facet normal 0.312927 -0.0120914 0.9497 + outer loop + vertex 1.61351 1.45957 2.54944 + vertex 1.61726 1.46327 2.54825 + vertex 1.61353 1.46452 2.5495 + endloop + endfacet + facet normal 0.312736 -0.0118775 0.949766 + outer loop + vertex 1.61723 1.45831 2.5482 + vertex 1.61726 1.46327 2.54825 + vertex 1.61351 1.45957 2.54944 + endloop + endfacet + facet normal 0.31504 -0.0118829 0.949004 + outer loop + vertex 1.61723 1.45831 2.5482 + vertex 1.62098 1.46201 2.547 + vertex 1.61726 1.46327 2.54825 + endloop + endfacet + facet normal 0.314781 -0.0115919 0.949093 + outer loop + vertex 1.62096 1.45705 2.54695 + vertex 1.62098 1.46201 2.547 + vertex 1.61723 1.45831 2.5482 + endloop + endfacet + facet normal 0.314436 -0.012713 0.949194 + outer loop + vertex 1.6172 1.45334 2.54814 + vertex 1.62096 1.45705 2.54695 + vertex 1.61723 1.45831 2.5482 + endloop + endfacet + facet normal 0.311499 -0.0127048 0.950162 + outer loop + vertex 1.6172 1.45334 2.54814 + vertex 1.61723 1.45831 2.5482 + vertex 1.61348 1.45462 2.54938 + endloop + endfacet + facet normal 0.310749 -0.0151003 0.950372 + outer loop + vertex 1.6134 1.44961 2.54933 + vertex 1.6172 1.45334 2.54814 + vertex 1.61348 1.45462 2.54938 + endloop + endfacet + facet normal 0.309707 -0.0139272 0.95073 + outer loop + vertex 1.61712 1.4483 2.5481 + vertex 1.6172 1.45334 2.54814 + vertex 1.6134 1.44961 2.54933 + endloop + endfacet + facet normal 0.312683 -0.0139645 0.949755 + outer loop + vertex 1.61712 1.4483 2.5481 + vertex 1.62094 1.45208 2.54689 + vertex 1.6172 1.45334 2.54814 + endloop + endfacet + facet normal 0.312209 -0.0134331 0.949918 + outer loop + vertex 1.6209 1.44705 2.54684 + vertex 1.62094 1.45208 2.54689 + vertex 1.61712 1.4483 2.5481 + endloop + endfacet + facet normal 0.310881 -0.0178271 0.950282 + outer loop + vertex 1.61693 1.44308 2.54806 + vertex 1.6209 1.44705 2.54684 + vertex 1.61712 1.4483 2.5481 + endloop + endfacet + facet normal 0.308533 -0.0177468 0.951048 + outer loop + vertex 1.61693 1.44308 2.54806 + vertex 1.61712 1.4483 2.5481 + vertex 1.61316 1.44445 2.54931 + endloop + endfacet + facet normal 0.306924 -0.0225718 0.951466 + outer loop + vertex 1.61245 1.43867 2.5494 + vertex 1.61693 1.44308 2.54806 + vertex 1.61316 1.44445 2.54931 + endloop + endfacet + facet normal 0.307609 -0.0233396 0.951226 + outer loop + vertex 1.61685 1.43786 2.54796 + vertex 1.61693 1.44308 2.54806 + vertex 1.61245 1.43867 2.5494 + endloop + endfacet + facet normal 0.306772 -0.0281378 0.951367 + outer loop + vertex 1.61294 1.43347 2.54909 + vertex 1.61685 1.43786 2.54796 + vertex 1.61245 1.43867 2.5494 + endloop + endfacet + facet normal 0.307402 -0.0287558 0.951145 + outer loop + vertex 1.61698 1.43283 2.54777 + vertex 1.61685 1.43786 2.54796 + vertex 1.61294 1.43347 2.54909 + endloop + endfacet + facet normal 0.306814 -0.0326468 0.95121 + outer loop + vertex 1.61305 1.42849 2.54888 + vertex 1.61698 1.43283 2.54777 + vertex 1.61294 1.43347 2.54909 + endloop + endfacet + facet normal 0.304238 -0.0327367 0.952033 + outer loop + vertex 1.61305 1.42849 2.54888 + vertex 1.61294 1.43347 2.54909 + vertex 1.60916 1.42932 2.55015 + endloop + endfacet + facet normal 0.304546 -0.0330465 0.951924 + outer loop + vertex 1.60916 1.42932 2.55015 + vertex 1.61294 1.43347 2.54909 + vertex 1.60919 1.43382 2.5503 + endloop + endfacet + facet normal 0.306574 -0.0324079 0.951295 + outer loop + vertex 1.61746 1.42771 2.54744 + vertex 1.61698 1.43283 2.54777 + vertex 1.61305 1.42849 2.54888 + endloop + endfacet + facet normal 0.306376 -0.0335608 0.951319 + outer loop + vertex 1.61293 1.42341 2.54874 + vertex 1.61746 1.42771 2.54744 + vertex 1.61305 1.42849 2.54888 + endloop + endfacet + facet normal 0.303146 -0.0335114 0.952355 + outer loop + vertex 1.61293 1.42341 2.54874 + vertex 1.61305 1.42849 2.54888 + vertex 1.60904 1.42448 2.55002 + endloop + endfacet + facet normal 0.302875 -0.0345516 0.952404 + outer loop + vertex 1.60892 1.41956 2.54988 + vertex 1.61293 1.42341 2.54874 + vertex 1.60904 1.42448 2.55002 + endloop + endfacet + facet normal 0.302296 -0.0338849 0.952612 + outer loop + vertex 1.61269 1.41834 2.54864 + vertex 1.61293 1.42341 2.54874 + vertex 1.60892 1.41956 2.54988 + endloop + endfacet + facet normal 0.304871 -0.0339878 0.951787 + outer loop + vertex 1.61269 1.41834 2.54864 + vertex 1.6167 1.42207 2.54749 + vertex 1.61293 1.42341 2.54874 + endloop + endfacet + facet normal 0.304699 -0.0337843 0.951849 + outer loop + vertex 1.61642 1.41704 2.5474 + vertex 1.6167 1.42207 2.54749 + vertex 1.61269 1.41834 2.54864 + endloop + endfacet + facet normal 0.303931 -0.0361533 0.952008 + outer loop + vertex 1.61256 1.41338 2.54849 + vertex 1.61642 1.41704 2.5474 + vertex 1.61269 1.41834 2.54864 + endloop + endfacet + facet normal 0.301721 -0.0361155 0.952712 + outer loop + vertex 1.61256 1.41338 2.54849 + vertex 1.61269 1.41834 2.54864 + vertex 1.60882 1.41463 2.54972 + endloop + endfacet + facet normal 0.300784 -0.039086 0.952891 + outer loop + vertex 1.60868 1.40966 2.54956 + vertex 1.61256 1.41338 2.54849 + vertex 1.60882 1.41463 2.54972 + endloop + endfacet + facet normal 0.301169 -0.0395289 0.952751 + outer loop + vertex 1.61241 1.40837 2.54833 + vertex 1.61256 1.41338 2.54849 + vertex 1.60868 1.40966 2.54956 + endloop + endfacet + facet normal 0.303252 -0.0395719 0.952088 + outer loop + vertex 1.61241 1.40837 2.54833 + vertex 1.61631 1.41211 2.54725 + vertex 1.61256 1.41338 2.54849 + endloop + endfacet + facet normal 0.303166 -0.0394737 0.95212 + outer loop + vertex 1.61619 1.40712 2.54708 + vertex 1.61631 1.41211 2.54725 + vertex 1.61241 1.40837 2.54833 + endloop + endfacet + facet normal 0.302355 -0.0420833 0.952266 + outer loop + vertex 1.61212 1.40318 2.54819 + vertex 1.61619 1.40712 2.54708 + vertex 1.61241 1.40837 2.54833 + endloop + endfacet + facet normal 0.299569 -0.0419544 0.953152 + outer loop + vertex 1.61212 1.40318 2.54819 + vertex 1.61241 1.40837 2.54833 + vertex 1.60836 1.40455 2.54944 + endloop + endfacet + facet normal 0.298662 -0.0445947 0.953316 + outer loop + vertex 1.60752 1.39885 2.54943 + vertex 1.61212 1.40318 2.54819 + vertex 1.60836 1.40455 2.54944 + endloop + endfacet + facet normal 0.297208 -0.0428997 0.953848 + outer loop + vertex 1.61195 1.39795 2.54801 + vertex 1.61212 1.40318 2.54819 + vertex 1.60752 1.39885 2.54943 + endloop + endfacet + facet normal 0.296773 -0.0450926 0.953883 + outer loop + vertex 1.60795 1.39364 2.54905 + vertex 1.61195 1.39795 2.54801 + vertex 1.60752 1.39885 2.54943 + endloop + endfacet + facet normal 0.293646 -0.0454198 0.954835 + outer loop + vertex 1.60752 1.39885 2.54943 + vertex 1.60416 1.3941 2.55024 + vertex 1.60795 1.39364 2.54905 + endloop + endfacet + facet normal 0.295181 -0.0465963 0.954304 + outer loop + vertex 1.60363 1.39728 2.55056 + vertex 1.60416 1.3941 2.55024 + vertex 1.60752 1.39885 2.54943 + endloop + endfacet + facet normal 0.294951 -0.0459498 0.954407 + outer loop + vertex 1.60363 1.39728 2.55056 + vertex 1.60752 1.39885 2.54943 + vertex 1.60435 1.4011 2.55052 + endloop + endfacet + facet normal 0.295538 -0.0438402 0.954325 + outer loop + vertex 1.61202 1.39288 2.54776 + vertex 1.61195 1.39795 2.54801 + vertex 1.60795 1.39364 2.54905 + endloop + endfacet + facet normal 0.294844 -0.0476295 0.954358 + outer loop + vertex 1.60802 1.38861 2.54878 + vertex 1.61202 1.39288 2.54776 + vertex 1.60795 1.39364 2.54905 + endloop + endfacet + facet normal 0.291976 -0.0477128 0.955235 + outer loop + vertex 1.60802 1.38861 2.54878 + vertex 1.60795 1.39364 2.54905 + vertex 1.6041 1.38956 2.55002 + endloop + endfacet + facet normal 0.293938 -0.0467038 0.954683 + outer loop + vertex 1.61246 1.38772 2.54737 + vertex 1.61202 1.39288 2.54776 + vertex 1.60802 1.38861 2.54878 + endloop + endfacet + facet normal 0.293114 -0.0508957 0.954722 + outer loop + vertex 1.6078 1.38342 2.54857 + vertex 1.61246 1.38772 2.54737 + vertex 1.60802 1.38861 2.54878 + endloop + endfacet + facet normal 0.290308 -0.0508121 0.955583 + outer loop + vertex 1.6078 1.38342 2.54857 + vertex 1.60802 1.38861 2.54878 + vertex 1.60389 1.38462 2.54982 + endloop + endfacet + facet normal 0.289242 -0.054416 0.955708 + outer loop + vertex 1.60351 1.37948 2.54964 + vertex 1.6078 1.38342 2.54857 + vertex 1.60389 1.38462 2.54982 + endloop + endfacet + facet normal 0.288616 -0.0536711 0.955939 + outer loop + vertex 1.60734 1.37812 2.54841 + vertex 1.6078 1.38342 2.54857 + vertex 1.60351 1.37948 2.54964 + endloop + endfacet + facet normal 0.290871 -0.0538444 0.955246 + outer loop + vertex 1.60734 1.37812 2.54841 + vertex 1.61163 1.38207 2.54733 + vertex 1.6078 1.38342 2.54857 + endloop + endfacet + facet normal 0.290644 -0.053575 0.95533 + outer loop + vertex 1.61127 1.37699 2.54715 + vertex 1.61163 1.38207 2.54733 + vertex 1.60734 1.37812 2.54841 + endloop + endfacet + facet normal 0.289692 -0.0569713 0.955423 + outer loop + vertex 1.60711 1.37293 2.54817 + vertex 1.61127 1.37699 2.54715 + vertex 1.60734 1.37812 2.54841 + endloop + endfacet + facet normal 0.287519 -0.0569058 0.956083 + outer loop + vertex 1.60711 1.37293 2.54817 + vertex 1.60734 1.37812 2.54841 + vertex 1.60266 1.37378 2.54956 + endloop + endfacet + facet normal 0.286935 -0.0599546 0.956072 + outer loop + vertex 1.60306 1.36862 2.54912 + vertex 1.60711 1.37293 2.54817 + vertex 1.60266 1.37378 2.54956 + endloop + endfacet + facet normal 0.287081 -0.0599399 0.956029 + outer loop + vertex 1.60266 1.37378 2.54956 + vertex 1.59931 1.36902 2.55027 + vertex 1.60306 1.36862 2.54912 + endloop + endfacet + facet normal 0.287289 -0.0603162 0.955943 + outer loop + vertex 1.60706 1.36794 2.54787 + vertex 1.60711 1.37293 2.54817 + vertex 1.60306 1.36862 2.54912 + endloop + endfacet + facet normal 0.286692 -0.063767 0.955898 + outer loop + vertex 1.60296 1.36364 2.54882 + vertex 1.60706 1.36794 2.54787 + vertex 1.60306 1.36862 2.54912 + endloop + endfacet + facet normal 0.286651 -0.063767 0.955911 + outer loop + vertex 1.60296 1.36364 2.54882 + vertex 1.60306 1.36862 2.54912 + vertex 1.59915 1.36449 2.55001 + endloop + endfacet + facet normal 0.28592 -0.0670427 0.955905 + outer loop + vertex 1.59873 1.35947 2.54979 + vertex 1.60296 1.36364 2.54882 + vertex 1.59915 1.36449 2.55001 + endloop + endfacet + facet normal 0.285321 -0.0663828 0.95613 + outer loop + vertex 1.60269 1.35846 2.54853 + vertex 1.60296 1.36364 2.54882 + vertex 1.59873 1.35947 2.54979 + endloop + endfacet + facet normal 0.286503 -0.0635719 0.955968 + outer loop + vertex 1.60699 1.36304 2.54757 + vertex 1.60706 1.36794 2.54787 + vertex 1.60296 1.36364 2.54882 + endloop + endfacet + facet normal 0.288869 -0.0635638 0.955256 + outer loop + vertex 1.60699 1.36304 2.54757 + vertex 1.61091 1.36726 2.54666 + vertex 1.60706 1.36794 2.54787 + endloop + endfacet + facet normal 0.28943 -0.0604498 0.955289 + outer loop + vertex 1.61091 1.36726 2.54666 + vertex 1.61108 1.37205 2.54691 + vertex 1.60706 1.36794 2.54787 + endloop + endfacet + facet normal 0.289289 -0.0603001 0.955341 + outer loop + vertex 1.60706 1.36794 2.54787 + vertex 1.61108 1.37205 2.54691 + vertex 1.60711 1.37293 2.54817 + endloop + endfacet + facet normal 0.292222 -0.0498355 0.955051 + outer loop + vertex 1.61163 1.38207 2.54733 + vertex 1.61246 1.38772 2.54737 + vertex 1.6078 1.38342 2.54857 + endloop + endfacet + facet normal 0.294777 -0.0502067 0.954246 + outer loop + vertex 1.61246 1.38772 2.54737 + vertex 1.61163 1.38207 2.54733 + vertex 1.61566 1.38549 2.54626 + endloop + endfacet + facet normal 0.296217 -0.0479829 0.953915 + outer loop + vertex 1.61636 1.3893 2.54624 + vertex 1.61246 1.38772 2.54737 + vertex 1.61566 1.38549 2.54626 + endloop + endfacet + facet normal 0.301688 -0.0489991 0.952147 + outer loop + vertex 1.61921 1.38888 2.54531 + vertex 1.61636 1.3893 2.54624 + vertex 1.61566 1.38549 2.54626 + endloop + endfacet + facet normal 0.300826 -0.0480061 0.95247 + outer loop + vertex 1.61915 1.38442 2.54511 + vertex 1.61921 1.38888 2.54531 + vertex 1.61566 1.38549 2.54626 + endloop + endfacet + facet normal 0.295125 -0.0449341 0.954401 + outer loop + vertex 1.61636 1.3893 2.54624 + vertex 1.61581 1.39248 2.54656 + vertex 1.61246 1.38772 2.54737 + endloop + endfacet + facet normal 0.295348 -0.0509472 0.95403 + outer loop + vertex 1.61566 1.38549 2.54626 + vertex 1.61163 1.38207 2.54733 + vertex 1.61528 1.38073 2.54613 + endloop + endfacet + facet normal 0.297008 -0.0463699 0.953749 + outer loop + vertex 1.61581 1.39248 2.54656 + vertex 1.61202 1.39288 2.54776 + vertex 1.61246 1.38772 2.54737 + endloop + endfacet + facet normal 0.29888 -0.0437422 0.953288 + outer loop + vertex 1.61202 1.39288 2.54776 + vertex 1.61587 1.39705 2.54674 + vertex 1.61195 1.39795 2.54801 + endloop + endfacet + facet normal 0.299405 -0.0413631 0.953229 + outer loop + vertex 1.61587 1.39705 2.54674 + vertex 1.61603 1.40206 2.54691 + vertex 1.61195 1.39795 2.54801 + endloop + endfacet + facet normal 0.300891 -0.0429821 0.952689 + outer loop + vertex 1.61195 1.39795 2.54801 + vertex 1.61603 1.40206 2.54691 + vertex 1.61212 1.40318 2.54819 + endloop + endfacet + facet normal 0.30539 -0.0324152 0.951675 + outer loop + vertex 1.6167 1.42207 2.54749 + vertex 1.61746 1.42771 2.54744 + vertex 1.61293 1.42341 2.54874 + endloop + endfacet + facet normal 0.307628 -0.0327239 0.950944 + outer loop + vertex 1.61746 1.42771 2.54744 + vertex 1.6167 1.42207 2.54749 + vertex 1.62064 1.42547 2.54633 + endloop + endfacet + facet normal 0.308243 -0.0317681 0.950777 + outer loop + vertex 1.62131 1.42933 2.54624 + vertex 1.61746 1.42771 2.54744 + vertex 1.62064 1.42547 2.54633 + endloop + endfacet + facet normal 0.309703 -0.0320344 0.950293 + outer loop + vertex 1.62417 1.42888 2.54529 + vertex 1.62131 1.42933 2.54624 + vertex 1.62064 1.42547 2.54633 + endloop + endfacet + facet normal 0.308677 -0.0308596 0.950666 + outer loop + vertex 1.62414 1.42435 2.54516 + vertex 1.62417 1.42888 2.54529 + vertex 1.62064 1.42547 2.54633 + endloop + endfacet + facet normal 0.308019 -0.0311645 0.95087 + outer loop + vertex 1.62131 1.42933 2.54624 + vertex 1.62075 1.43251 2.54653 + vertex 1.61746 1.42771 2.54744 + endloop + endfacet + facet normal 0.307222 -0.0322007 0.951093 + outer loop + vertex 1.62064 1.42547 2.54633 + vertex 1.6167 1.42207 2.54749 + vertex 1.6203 1.42066 2.54628 + endloop + endfacet + facet normal 0.309264 -0.032101 0.950434 + outer loop + vertex 1.62075 1.43251 2.54653 + vertex 1.61698 1.43283 2.54777 + vertex 1.61746 1.42771 2.54744 + endloop + endfacet + facet normal 0.309295 -0.0286851 0.950533 + outer loop + vertex 1.61698 1.43283 2.54777 + vertex 1.62075 1.43703 2.54666 + vertex 1.61685 1.43786 2.54796 + endloop + endfacet + facet normal 0.310222 -0.0240242 0.95036 + outer loop + vertex 1.62075 1.43703 2.54666 + vertex 1.62083 1.44199 2.54676 + vertex 1.61685 1.43786 2.54796 + endloop + endfacet + facet normal 0.309595 -0.0233562 0.950582 + outer loop + vertex 1.61685 1.43786 2.54796 + vertex 1.62083 1.44199 2.54676 + vertex 1.61693 1.44308 2.54806 + endloop + endfacet + facet normal 0.315043 0.00196729 0.949075 + outer loop + vertex 1.62117 1.52192 2.54719 + vertex 1.62115 1.52691 2.54719 + vertex 1.61741 1.52317 2.54844 + endloop + endfacet + facet normal 0.305526 0.0261937 0.951824 + outer loop + vertex 1.61686 1.58307 2.54799 + vertex 1.62051 1.58673 2.54672 + vertex 1.61664 1.58784 2.54793 + endloop + endfacet + facet normal 0.301942 0.0343175 0.952708 + outer loop + vertex 1.61366 1.5892 2.54884 + vertex 1.61608 1.59158 2.54799 + vertex 1.61308 1.59299 2.54889 + endloop + endfacet + facet normal 0.302869 0.0365308 0.952332 + outer loop + vertex 1.61608 1.59158 2.54799 + vertex 1.6171 1.59612 2.54749 + vertex 1.61308 1.59299 2.54889 + endloop + endfacet + facet normal 0.302339 0.0372715 0.952471 + outer loop + vertex 1.61308 1.59299 2.54889 + vertex 1.6171 1.59612 2.54749 + vertex 1.6128 1.5979 2.54879 + endloop + endfacet + facet normal 0.302333 0.0372551 0.952474 + outer loop + vertex 1.6171 1.59612 2.54749 + vertex 1.61646 1.60167 2.54748 + vertex 1.6128 1.5979 2.54879 + endloop + endfacet + facet normal 0.301967 0.0376468 0.952575 + outer loop + vertex 1.6128 1.5979 2.54879 + vertex 1.61646 1.60167 2.54748 + vertex 1.61248 1.60304 2.54868 + endloop + endfacet + facet normal 0.29251 0.0446996 0.955217 + outer loop + vertex 1.61181 1.6227 2.54809 + vertex 1.6151 1.62562 2.54695 + vertex 1.61183 1.62732 2.54787 + endloop + endfacet + facet normal 0.289569 0.0476235 0.955972 + outer loop + vertex 1.60857 1.62888 2.54879 + vertex 1.61139 1.63116 2.54782 + vertex 1.60796 1.63275 2.54878 + endloop + endfacet + facet normal 0.289993 0.0486466 0.955792 + outer loop + vertex 1.61139 1.63116 2.54782 + vertex 1.61234 1.63582 2.54729 + vertex 1.60796 1.63275 2.54878 + endloop + endfacet + facet normal 0.290746 0.0511271 0.955433 + outer loop + vertex 1.61133 1.64155 2.54729 + vertex 1.61234 1.63582 2.54729 + vertex 1.61553 1.64028 2.54608 + endloop + endfacet + facet normal 0.291571 0.054271 0.955008 + outer loop + vertex 1.61483 1.64543 2.54601 + vertex 1.61133 1.64155 2.54729 + vertex 1.61553 1.64028 2.54608 + endloop + endfacet + facet normal 0.295344 0.0502729 0.954067 + outer loop + vertex 1.61869 1.63507 2.54539 + vertex 1.6197 1.63875 2.54488 + vertex 1.61652 1.63616 2.546 + endloop + endfacet + facet normal 0.299285 0.0490306 0.952903 + outer loop + vertex 1.61869 1.63507 2.54539 + vertex 1.62198 1.63455 2.54438 + vertex 1.6197 1.63875 2.54488 + endloop + endfacet + facet normal 0.298204 0.0483986 0.953274 + outer loop + vertex 1.6197 1.63875 2.54488 + vertex 1.62198 1.63455 2.54438 + vertex 1.62355 1.63871 2.54368 + endloop + endfacet + facet normal 0.29859 0.0436915 0.953381 + outer loop + vertex 1.61869 1.63507 2.54539 + vertex 1.61663 1.63112 2.54621 + vertex 1.62198 1.63455 2.54438 + endloop + endfacet + facet normal 0.2929 0.054446 0.954592 + outer loop + vertex 1.61553 1.64028 2.54608 + vertex 1.61892 1.64406 2.54483 + vertex 1.61483 1.64543 2.54601 + endloop + endfacet + facet normal 0.29819 0.0508178 0.953153 + outer loop + vertex 1.62355 1.63871 2.54368 + vertex 1.623 1.6428 2.54363 + vertex 1.6197 1.63875 2.54488 + endloop + endfacet + facet normal 0.300179 0.0510798 0.952514 + outer loop + vertex 1.62355 1.63871 2.54368 + vertex 1.62718 1.6411 2.54241 + vertex 1.623 1.6428 2.54363 + endloop + endfacet + facet normal 0.293679 0.0565668 0.954229 + outer loop + vertex 1.61892 1.64406 2.54483 + vertex 1.62243 1.64789 2.54352 + vertex 1.61834 1.64928 2.5447 + endloop + endfacet + facet normal 0.294068 0.0578802 0.95403 + outer loop + vertex 1.62243 1.64789 2.54352 + vertex 1.62198 1.65302 2.54335 + vertex 1.61834 1.64928 2.5447 + endloop + endfacet + facet normal 0.293515 0.0565498 0.954281 + outer loop + vertex 1.61892 1.64406 2.54483 + vertex 1.61834 1.64928 2.5447 + vertex 1.61483 1.64543 2.54601 + endloop + endfacet + facet normal 0.290338 0.0554818 0.955314 + outer loop + vertex 1.61075 1.64679 2.54717 + vertex 1.61133 1.64155 2.54729 + vertex 1.61483 1.64543 2.54601 + endloop + endfacet + facet normal 0.291712 0.0606802 0.95458 + outer loop + vertex 1.61365 1.65454 2.5458 + vertex 1.61424 1.6505 2.54588 + vertex 1.61766 1.65473 2.54456 + endloop + endfacet + facet normal 0.289657 0.058935 0.955314 + outer loop + vertex 1.61075 1.64679 2.54717 + vertex 1.61005 1.6521 2.54705 + vertex 1.60669 1.64797 2.54832 + endloop + endfacet + facet normal 0.28298 0.0650288 0.956919 + outer loop + vertex 1.59979 1.6538 2.55002 + vertex 1.60313 1.65795 2.54875 + vertex 1.59904 1.65909 2.54988 + endloop + endfacet + facet normal 0.285299 0.0653434 0.956208 + outer loop + vertex 1.59979 1.6538 2.55002 + vertex 1.59904 1.65909 2.54988 + vertex 1.59555 1.65545 2.55117 + endloop + endfacet + facet normal 0.283087 0.0654739 0.956857 + outer loop + vertex 1.60313 1.65795 2.54875 + vertex 1.60257 1.66291 2.54857 + vertex 1.59904 1.65909 2.54988 + endloop + endfacet + facet normal 0.282525 0.0660372 0.956984 + outer loop + vertex 1.59904 1.65909 2.54988 + vertex 1.60257 1.66291 2.54857 + vertex 1.59855 1.66412 2.54968 + endloop + endfacet + facet normal 0.284522 0.0662046 0.956381 + outer loop + vertex 1.59904 1.65909 2.54988 + vertex 1.59855 1.66412 2.54968 + vertex 1.59499 1.66036 2.551 + endloop + endfacet + facet normal 0.28451 0.0661602 0.956387 + outer loop + vertex 1.59555 1.65545 2.55117 + vertex 1.59904 1.65909 2.54988 + vertex 1.59499 1.66036 2.551 + endloop + endfacet + facet normal 0.292313 0.0669667 0.953975 + outer loop + vertex 1.59499 1.66036 2.551 + vertex 1.59158 1.65672 2.55229 + vertex 1.59555 1.65545 2.55117 + endloop + endfacet + facet normal 0.285224 0.065484 0.956221 + outer loop + vertex 1.59499 1.66036 2.551 + vertex 1.59855 1.66412 2.54968 + vertex 1.59455 1.66531 2.55079 + endloop + endfacet + facet normal 0.282303 0.0651887 0.957108 + outer loop + vertex 1.60257 1.66291 2.54857 + vertex 1.60214 1.66791 2.54836 + vertex 1.59855 1.66412 2.54968 + endloop + endfacet + facet normal 0.282736 0.0647449 0.95701 + outer loop + vertex 1.59855 1.66412 2.54968 + vertex 1.60214 1.66791 2.54836 + vertex 1.5981 1.66913 2.54947 + endloop + endfacet + facet normal 0.283419 0.065269 0.956772 + outer loop + vertex 1.60257 1.66291 2.54857 + vertex 1.60613 1.6667 2.54726 + vertex 1.60214 1.66791 2.54836 + endloop + endfacet + facet normal 0.282982 0.0636169 0.957013 + outer loop + vertex 1.60613 1.6667 2.54726 + vertex 1.60568 1.67173 2.54706 + vertex 1.60214 1.66791 2.54836 + endloop + endfacet + facet normal 0.283137 0.0634604 0.956978 + outer loop + vertex 1.60214 1.66791 2.54836 + vertex 1.60568 1.67173 2.54706 + vertex 1.60162 1.67284 2.54819 + endloop + endfacet + facet normal 0.282947 0.0626495 0.957087 + outer loop + vertex 1.60568 1.67173 2.54706 + vertex 1.60499 1.67701 2.54692 + vertex 1.60162 1.67284 2.54819 + endloop + endfacet + facet normal 0.283864 0.0627621 0.956808 + outer loop + vertex 1.60499 1.67701 2.54692 + vertex 1.60568 1.67173 2.54706 + vertex 1.60919 1.67543 2.54577 + endloop + endfacet + facet normal 0.28391 0.0629005 0.956786 + outer loop + vertex 1.60919 1.67543 2.54577 + vertex 1.6086 1.67947 2.54568 + vertex 1.60499 1.67701 2.54692 + endloop + endfacet + facet normal 0.283004 0.0643157 0.95696 + outer loop + vertex 1.60624 1.68142 2.54625 + vertex 1.60499 1.67701 2.54692 + vertex 1.6086 1.67947 2.54568 + endloop + endfacet + facet normal 0.285024 0.0669863 0.956177 + outer loop + vertex 1.6086 1.67947 2.54568 + vertex 1.6098 1.68384 2.54502 + vertex 1.60624 1.68142 2.54625 + endloop + endfacet + facet normal 0.283019 0.070118 0.956548 + outer loop + vertex 1.60624 1.68142 2.54625 + vertex 1.6098 1.68384 2.54502 + vertex 1.60556 1.68543 2.54616 + endloop + endfacet + facet normal 0.282085 0.0699659 0.956835 + outer loop + vertex 1.60556 1.68543 2.54616 + vertex 1.60228 1.68128 2.54743 + vertex 1.60624 1.68142 2.54625 + endloop + endfacet + facet normal 0.284456 0.0744828 0.955791 + outer loop + vertex 1.6098 1.68384 2.54502 + vertex 1.60896 1.68904 2.54487 + vertex 1.60556 1.68543 2.54616 + endloop + endfacet + facet normal 0.282141 0.0768367 0.956291 + outer loop + vertex 1.60556 1.68543 2.54616 + vertex 1.60896 1.68904 2.54487 + vertex 1.60481 1.69034 2.54598 + endloop + endfacet + facet normal 0.282603 0.0769019 0.956149 + outer loop + vertex 1.60481 1.69034 2.54598 + vertex 1.60142 1.68656 2.54729 + vertex 1.60556 1.68543 2.54616 + endloop + endfacet + facet normal 0.280739 0.0787141 0.956551 + outer loop + vertex 1.60069 1.69158 2.54709 + vertex 1.60142 1.68656 2.54729 + vertex 1.60481 1.69034 2.54598 + endloop + endfacet + facet normal 0.282289 0.084743 0.955579 + outer loop + vertex 1.60408 1.69523 2.54577 + vertex 1.60069 1.69158 2.54709 + vertex 1.60481 1.69034 2.54598 + endloop + endfacet + facet normal 0.281984 0.0847015 0.955673 + outer loop + vertex 1.60481 1.69034 2.54598 + vertex 1.60823 1.69407 2.54465 + vertex 1.60408 1.69523 2.54577 + endloop + endfacet + facet normal 0.283778 0.0829273 0.955297 + outer loop + vertex 1.60896 1.68904 2.54487 + vertex 1.60823 1.69407 2.54465 + vertex 1.60481 1.69034 2.54598 + endloop + endfacet + facet normal 0.28342 0.0828803 0.955408 + outer loop + vertex 1.60896 1.68904 2.54487 + vertex 1.61244 1.69268 2.54352 + vertex 1.60823 1.69407 2.54465 + endloop + endfacet + facet normal 0.284911 0.0881331 0.954494 + outer loop + vertex 1.61244 1.69268 2.54352 + vertex 1.61164 1.6977 2.54329 + vertex 1.60823 1.69407 2.54465 + endloop + endfacet + facet normal 0.283232 0.0898405 0.954834 + outer loop + vertex 1.60823 1.69407 2.54465 + vertex 1.61164 1.6977 2.54329 + vertex 1.60737 1.69933 2.5444 + endloop + endfacet + facet normal 0.284148 0.0926051 0.954298 + outer loop + vertex 1.61164 1.6977 2.54329 + vertex 1.61093 1.70175 2.54311 + vertex 1.60737 1.69933 2.5444 + endloop + endfacet + facet normal 0.286355 0.0929651 0.953603 + outer loop + vertex 1.61164 1.6977 2.54329 + vertex 1.61489 1.70184 2.54191 + vertex 1.61093 1.70175 2.54311 + endloop + endfacet + facet normal 0.285926 0.0882802 0.954177 + outer loop + vertex 1.61244 1.69268 2.54352 + vertex 1.6159 1.69644 2.54213 + vertex 1.61164 1.6977 2.54329 + endloop + endfacet + facet normal 0.287459 0.0867565 0.953856 + outer loop + vertex 1.61694 1.69092 2.54232 + vertex 1.6159 1.69644 2.54213 + vertex 1.61244 1.69268 2.54352 + endloop + endfacet + facet normal 0.285613 0.0813495 0.954886 + outer loop + vertex 1.61297 1.68782 2.54377 + vertex 1.61694 1.69092 2.54232 + vertex 1.61244 1.69268 2.54352 + endloop + endfacet + facet normal 0.286875 0.0796246 0.954653 + outer loop + vertex 1.61605 1.68641 2.54296 + vertex 1.61694 1.69092 2.54232 + vertex 1.61297 1.68782 2.54377 + endloop + endfacet + facet normal 0.284568 0.0739061 0.955803 + outer loop + vertex 1.61364 1.68406 2.54386 + vertex 1.61605 1.68641 2.54296 + vertex 1.61297 1.68782 2.54377 + endloop + endfacet + facet normal 0.283715 0.0737601 0.956068 + outer loop + vertex 1.61364 1.68406 2.54386 + vertex 1.61297 1.68782 2.54377 + vertex 1.6098 1.68384 2.54502 + endloop + endfacet + facet normal 0.284248 0.0663665 0.956451 + outer loop + vertex 1.6098 1.68384 2.54502 + vertex 1.61263 1.67966 2.54447 + vertex 1.61364 1.68406 2.54386 + endloop + endfacet + facet normal 0.286052 0.0658801 0.955947 + outer loop + vertex 1.61263 1.67966 2.54447 + vertex 1.61667 1.6827 2.54305 + vertex 1.61364 1.68406 2.54386 + endloop + endfacet + facet normal 0.286724 0.0649245 0.955811 + outer loop + vertex 1.61696 1.67795 2.54329 + vertex 1.61667 1.6827 2.54305 + vertex 1.61263 1.67966 2.54447 + endloop + endfacet + facet normal 0.287817 0.0703262 0.9551 + outer loop + vertex 1.61667 1.6827 2.54305 + vertex 1.61605 1.68641 2.54296 + vertex 1.61364 1.68406 2.54386 + endloop + endfacet + facet normal 0.289428 0.0705845 0.954594 + outer loop + vertex 1.61667 1.6827 2.54305 + vertex 1.61987 1.68672 2.54178 + vertex 1.61605 1.68641 2.54296 + endloop + endfacet + facet normal 0.289438 0.0705762 0.954591 + outer loop + vertex 1.62058 1.68159 2.54195 + vertex 1.61987 1.68672 2.54178 + vertex 1.61667 1.6827 2.54305 + endloop + endfacet + facet normal 0.288611 0.0792106 0.954164 + outer loop + vertex 1.61694 1.69092 2.54232 + vertex 1.61605 1.68641 2.54296 + vertex 1.61987 1.68672 2.54178 + endloop + endfacet + facet normal 0.28787 0.078659 0.954434 + outer loop + vertex 1.62103 1.69112 2.54107 + vertex 1.61694 1.69092 2.54232 + vertex 1.61987 1.68672 2.54178 + endloop + endfacet + facet normal 0.288412 0.0784922 0.954284 + outer loop + vertex 1.62103 1.69112 2.54107 + vertex 1.61987 1.68672 2.54178 + vertex 1.62343 1.68918 2.54051 + endloop + endfacet + facet normal 0.29206 0.0834341 0.952754 + outer loop + vertex 1.62343 1.68918 2.54051 + vertex 1.62456 1.69359 2.53977 + vertex 1.62103 1.69112 2.54107 + endloop + endfacet + facet normal 0.289826 0.0868218 0.953133 + outer loop + vertex 1.62103 1.69112 2.54107 + vertex 1.62456 1.69359 2.53977 + vertex 1.62019 1.69522 2.54095 + endloop + endfacet + facet normal 0.290672 0.0750227 0.953877 + outer loop + vertex 1.62405 1.68521 2.54063 + vertex 1.62343 1.68918 2.54051 + vertex 1.61987 1.68672 2.54178 + endloop + endfacet + facet normal 0.287326 0.0863328 0.953934 + outer loop + vertex 1.62019 1.69522 2.54095 + vertex 1.61694 1.69092 2.54232 + vertex 1.62103 1.69112 2.54107 + endloop + endfacet + facet normal 0.284956 0.0812886 0.955087 + outer loop + vertex 1.61297 1.68782 2.54377 + vertex 1.61244 1.69268 2.54352 + vertex 1.60896 1.68904 2.54487 + endloop + endfacet + facet normal 0.283118 0.0742784 0.956204 + outer loop + vertex 1.6098 1.68384 2.54502 + vertex 1.61297 1.68782 2.54377 + vertex 1.60896 1.68904 2.54487 + endloop + endfacet + facet normal 0.285082 0.0669679 0.956161 + outer loop + vertex 1.6086 1.67947 2.54568 + vertex 1.61263 1.67966 2.54447 + vertex 1.6098 1.68384 2.54502 + endloop + endfacet + facet normal 0.282357 0.0645267 0.957137 + outer loop + vertex 1.60624 1.68142 2.54625 + vertex 1.60228 1.68128 2.54743 + vertex 1.60499 1.67701 2.54692 + endloop + endfacet + facet normal 0.282855 0.0648629 0.956967 + outer loop + vertex 1.60228 1.68128 2.54743 + vertex 1.60104 1.67686 2.5481 + vertex 1.60499 1.67701 2.54692 + endloop + endfacet + facet normal 0.285318 0.0630985 0.956354 + outer loop + vertex 1.6086 1.67947 2.54568 + vertex 1.60919 1.67543 2.54577 + vertex 1.61263 1.67966 2.54447 + endloop + endfacet + facet normal 0.285492 0.0629443 0.956312 + outer loop + vertex 1.61328 1.67426 2.54463 + vertex 1.61263 1.67966 2.54447 + vertex 1.60919 1.67543 2.54577 + endloop + endfacet + facet normal 0.284242 0.0623736 0.956722 + outer loop + vertex 1.60919 1.67543 2.54577 + vertex 1.60568 1.67173 2.54706 + vertex 1.6097 1.67046 2.54595 + endloop + endfacet + facet normal 0.287316 0.062726 0.95578 + outer loop + vertex 1.60611 1.65198 2.54825 + vertex 1.60736 1.65636 2.54759 + vertex 1.60378 1.65391 2.54883 + endloop + endfacet + facet normal 0.284452 0.0656161 0.956442 + outer loop + vertex 1.60313 1.65795 2.54875 + vertex 1.60662 1.66165 2.54746 + vertex 1.60257 1.66291 2.54857 + endloop + endfacet + facet normal 0.284154 0.0645186 0.956605 + outer loop + vertex 1.60662 1.66165 2.54746 + vertex 1.60613 1.6667 2.54726 + vertex 1.60257 1.66291 2.54857 + endloop + endfacet + facet normal 0.284618 0.0637443 0.956519 + outer loop + vertex 1.60568 1.67173 2.54706 + vertex 1.60613 1.6667 2.54726 + vertex 1.6097 1.67046 2.54595 + endloop + endfacet + facet normal 0.288058 0.0615529 0.955633 + outer loop + vertex 1.61414 1.66411 2.54503 + vertex 1.61369 1.66917 2.54484 + vertex 1.61012 1.66544 2.54615 + endloop + endfacet + facet normal 0.285377 0.0624773 0.956377 + outer loop + vertex 1.6097 1.67046 2.54595 + vertex 1.61328 1.67426 2.54463 + vertex 1.60919 1.67543 2.54577 + endloop + endfacet + facet normal 0.288258 0.0604398 0.955644 + outer loop + vertex 1.61774 1.6678 2.5437 + vertex 1.61734 1.67291 2.5435 + vertex 1.61369 1.66917 2.54484 + endloop + endfacet + facet normal 0.288997 0.0604893 0.955417 + outer loop + vertex 1.61774 1.6678 2.5437 + vertex 1.62141 1.67157 2.54235 + vertex 1.61734 1.67291 2.5435 + endloop + endfacet + facet normal 0.286059 0.0630076 0.956138 + outer loop + vertex 1.61328 1.67426 2.54463 + vertex 1.61696 1.67795 2.54329 + vertex 1.61263 1.67966 2.54447 + endloop + endfacet + facet normal 0.289113 0.0608935 0.955356 + outer loop + vertex 1.62141 1.67157 2.54235 + vertex 1.62099 1.67665 2.54216 + vertex 1.61734 1.67291 2.5435 + endloop + endfacet + facet normal 0.288082 0.0649854 0.955398 + outer loop + vertex 1.61696 1.67795 2.54329 + vertex 1.62058 1.68159 2.54195 + vertex 1.61667 1.6827 2.54305 + endloop + endfacet + facet normal 0.289274 0.0705553 0.954643 + outer loop + vertex 1.61987 1.68672 2.54178 + vertex 1.62058 1.68159 2.54195 + vertex 1.62405 1.68521 2.54063 + endloop + endfacet + facet normal 0.294451 0.0672819 0.953295 + outer loop + vertex 1.62857 1.67914 2.53967 + vertex 1.62808 1.68412 2.53947 + vertex 1.62458 1.68038 2.54081 + endloop + endfacet + facet normal 0.293352 0.0754161 0.953025 + outer loop + vertex 1.62343 1.68918 2.54051 + vertex 1.62405 1.68521 2.54063 + vertex 1.62735 1.68931 2.53929 + endloop + endfacet + facet normal 0.29691 0.0722802 0.952166 + outer loop + vertex 1.6321 1.68283 2.53831 + vertex 1.63151 1.68773 2.53813 + vertex 1.62808 1.68412 2.53947 + endloop + endfacet + facet normal 0.292947 0.0831659 0.952505 + outer loop + vertex 1.62343 1.68918 2.54051 + vertex 1.62735 1.68931 2.53929 + vertex 1.62456 1.69359 2.53977 + endloop + endfacet + facet normal 0.294163 0.0895539 0.951551 + outer loop + vertex 1.62853 1.69366 2.53855 + vertex 1.63199 1.69607 2.53725 + vertex 1.62769 1.69772 2.53842 + endloop + endfacet + facet normal 0.294586 0.0908375 0.951298 + outer loop + vertex 1.63199 1.69607 2.53725 + vertex 1.63089 1.70142 2.53708 + vertex 1.62769 1.69772 2.53842 + endloop + endfacet + facet normal 0.292852 0.0924757 0.951675 + outer loop + vertex 1.62769 1.69772 2.53842 + vertex 1.63089 1.70142 2.53708 + vertex 1.62667 1.70266 2.53826 + endloop + endfacet + facet normal 0.290868 0.0900659 0.952514 + outer loop + vertex 1.62456 1.69359 2.53977 + vertex 1.62345 1.69896 2.5396 + vertex 1.62019 1.69522 2.54095 + endloop + endfacet + facet normal 0.286928 0.0866621 0.954024 + outer loop + vertex 1.6159 1.69644 2.54213 + vertex 1.61694 1.69092 2.54232 + vertex 1.62019 1.69522 2.54095 + endloop + endfacet + facet normal 0.286965 0.0924419 0.95347 + outer loop + vertex 1.6159 1.69644 2.54213 + vertex 1.61489 1.70184 2.54191 + vertex 1.61164 1.6977 2.54329 + endloop + endfacet + facet normal 0.288662 0.0943043 0.952775 + outer loop + vertex 1.61841 1.70426 2.54061 + vertex 1.61921 1.70019 2.54077 + vertex 1.62237 1.70432 2.53941 + endloop + endfacet + facet normal 0.286231 0.0956176 0.953378 + outer loop + vertex 1.61206 1.70616 2.54233 + vertex 1.61093 1.70175 2.54311 + vertex 1.61489 1.70184 2.54191 + endloop + endfacet + facet normal 0.286766 0.094795 0.953299 + outer loop + vertex 1.61841 1.70426 2.54061 + vertex 1.61952 1.70866 2.53984 + vertex 1.61602 1.70625 2.54113 + endloop + endfacet + facet normal 0.287404 0.0930625 0.953278 + outer loop + vertex 1.61952 1.70866 2.53984 + vertex 1.62268 1.71277 2.53849 + vertex 1.61845 1.71399 2.53964 + endloop + endfacet + facet normal 0.287051 0.0915924 0.953526 + outer loop + vertex 1.62268 1.71277 2.53849 + vertex 1.62171 1.71768 2.53831 + vertex 1.61845 1.71399 2.53964 + endloop + endfacet + facet normal 0.28912 0.0919775 0.952864 + outer loop + vertex 1.62268 1.71277 2.53849 + vertex 1.62594 1.71648 2.53714 + vertex 1.62171 1.71768 2.53831 + endloop + endfacet + facet normal 0.28376 0.0949853 0.954179 + outer loop + vertex 1.61737 1.71932 2.53944 + vertex 1.6209 1.72174 2.53815 + vertex 1.61851 1.72371 2.53867 + endloop + endfacet + facet normal 0.281188 0.0957699 0.954862 + outer loop + vertex 1.61452 1.72363 2.53985 + vertex 1.61737 1.71932 2.53944 + vertex 1.61851 1.72371 2.53867 + endloop + endfacet + facet normal 0.280969 0.100338 0.954457 + outer loop + vertex 1.61851 1.72371 2.53867 + vertex 1.61772 1.72773 2.53848 + vertex 1.61452 1.72363 2.53985 + endloop + endfacet + facet normal 0.283776 0.100844 0.953573 + outer loop + vertex 1.61851 1.72371 2.53867 + vertex 1.62204 1.72614 2.53736 + vertex 1.61772 1.72773 2.53848 + endloop + endfacet + facet normal 0.284177 0.102115 0.953319 + outer loop + vertex 1.62204 1.72614 2.53736 + vertex 1.62099 1.73142 2.53711 + vertex 1.61772 1.72773 2.53848 + endloop + endfacet + facet normal 0.282059 0.104141 0.953728 + outer loop + vertex 1.61772 1.72773 2.53848 + vertex 1.62099 1.73142 2.53711 + vertex 1.61675 1.73257 2.53824 + endloop + endfacet + facet normal 0.280334 0.10382 0.954272 + outer loop + vertex 1.61772 1.72773 2.53848 + vertex 1.61675 1.73257 2.53824 + vertex 1.61348 1.72889 2.5396 + endloop + endfacet + facet normal 0.289252 0.0925352 0.95277 + outer loop + vertex 1.62594 1.71648 2.53714 + vertex 1.6249 1.72183 2.53694 + vertex 1.62171 1.71768 2.53831 + endloop + endfacet + facet normal 0.285818 0.0977133 0.953289 + outer loop + vertex 1.6209 1.72174 2.53815 + vertex 1.62204 1.72614 2.53736 + vertex 1.61851 1.72371 2.53867 + endloop + endfacet + facet normal 0.287685 0.101211 0.952362 + outer loop + vertex 1.62519 1.73023 2.53597 + vertex 1.62204 1.72614 2.53736 + vertex 1.62602 1.72624 2.53615 + endloop + endfacet + facet normal 0.292356 0.102108 0.950843 + outer loop + vertex 1.62602 1.72624 2.53615 + vertex 1.62946 1.72862 2.53484 + vertex 1.62519 1.73023 2.53597 + endloop + endfacet + facet normal 0.294831 0.102014 0.950088 + outer loop + vertex 1.63337 1.7287 2.53361 + vertex 1.63672 1.73113 2.53231 + vertex 1.63237 1.73267 2.53349 + endloop + endfacet + facet normal 0.294376 0.103971 0.950017 + outer loop + vertex 1.63237 1.73267 2.53349 + vertex 1.63523 1.73686 2.53215 + vertex 1.63107 1.73679 2.53345 + endloop + endfacet + facet normal 0.292638 0.10298 0.950662 + outer loop + vertex 1.62946 1.72862 2.53484 + vertex 1.6283 1.73377 2.53463 + vertex 1.62519 1.73023 2.53597 + endloop + endfacet + facet normal 0.286173 0.102482 0.952682 + outer loop + vertex 1.62099 1.73142 2.53711 + vertex 1.62204 1.72614 2.53736 + vertex 1.62519 1.73023 2.53597 + endloop + endfacet + facet normal 0.282347 0.105414 0.953503 + outer loop + vertex 1.62099 1.73142 2.53711 + vertex 1.61986 1.73672 2.53686 + vertex 1.61675 1.73257 2.53824 + endloop + endfacet + facet normal 0.281461 0.106139 0.953684 + outer loop + vertex 1.61675 1.73257 2.53824 + vertex 1.61986 1.73672 2.53686 + vertex 1.61586 1.73661 2.53805 + endloop + endfacet + facet normal 0.289335 0.107061 0.951222 + outer loop + vertex 1.62333 1.73914 2.53555 + vertex 1.62421 1.73508 2.53574 + vertex 1.62738 1.7391 2.53432 + endloop + endfacet + facet normal 0.282095 0.108122 0.953274 + outer loop + vertex 1.6208 1.74115 2.53608 + vertex 1.61674 1.7411 2.53728 + vertex 1.61986 1.73672 2.53686 + endloop + endfacet + facet normal 0.289292 0.108997 0.951015 + outer loop + vertex 1.62333 1.73914 2.53555 + vertex 1.62738 1.7391 2.53432 + vertex 1.6242 1.74363 2.53477 + endloop + endfacet + facet normal 0.288457 0.109513 0.951209 + outer loop + vertex 1.62837 1.74374 2.53349 + vertex 1.62705 1.74782 2.53342 + vertex 1.6242 1.74363 2.53477 + endloop + endfacet + facet normal 0.287335 0.11163 0.951303 + outer loop + vertex 1.62705 1.74782 2.53342 + vertex 1.62999 1.75188 2.53206 + vertex 1.62603 1.75175 2.53327 + endloop + endfacet + facet normal 0.286254 0.114267 0.951316 + outer loop + vertex 1.62603 1.75175 2.53327 + vertex 1.62703 1.75612 2.53244 + vertex 1.62356 1.75371 2.53378 + endloop + endfacet + facet normal 0.283364 0.116381 0.951925 + outer loop + vertex 1.61957 1.75365 2.53498 + vertex 1.62269 1.75773 2.53355 + vertex 1.61846 1.75891 2.53467 + endloop + endfacet + facet normal 0.284646 0.113398 0.951902 + outer loop + vertex 1.6186 1.74926 2.53579 + vertex 1.62265 1.74929 2.53458 + vertex 1.61957 1.75365 2.53498 + endloop + endfacet + facet normal 0.281708 0.111571 0.952991 + outer loop + vertex 1.61609 1.75127 2.5363 + vertex 1.61209 1.75119 2.53749 + vertex 1.6152 1.7468 2.53709 + endloop + endfacet + facet normal 0.281523 0.111433 0.953062 + outer loop + vertex 1.61209 1.75119 2.53749 + vertex 1.61112 1.74678 2.53829 + vertex 1.6152 1.7468 2.53709 + endloop + endfacet + facet normal 0.284726 0.111364 0.952118 + outer loop + vertex 1.6186 1.74926 2.53579 + vertex 1.6197 1.74521 2.53594 + vertex 1.62265 1.74929 2.53458 + endloop + endfacet + facet normal 0.282022 0.109809 0.953103 + outer loop + vertex 1.6197 1.74521 2.53594 + vertex 1.61674 1.7411 2.53728 + vertex 1.6208 1.74115 2.53608 + endloop + endfacet + facet normal 0.281381 0.107587 0.953546 + outer loop + vertex 1.61674 1.7411 2.53728 + vertex 1.61586 1.73661 2.53805 + vertex 1.61986 1.73672 2.53686 + endloop + endfacet + facet normal 0.279715 0.10578 0.954238 + outer loop + vertex 1.61675 1.73257 2.53824 + vertex 1.61586 1.73661 2.53805 + vertex 1.61236 1.73418 2.53935 + endloop + endfacet + facet normal 0.280718 0.105177 0.95401 + outer loop + vertex 1.60923 1.73006 2.54072 + vertex 1.60833 1.7341 2.54053 + vertex 1.60485 1.73168 2.54183 + endloop + endfacet + facet normal 0.280275 0.105844 0.954066 + outer loop + vertex 1.6058 1.73611 2.54106 + vertex 1.60485 1.73168 2.54183 + vertex 1.60833 1.7341 2.54053 + endloop + endfacet + facet normal 0.279385 0.104728 0.954451 + outer loop + vertex 1.61348 1.72889 2.5396 + vertex 1.61675 1.73257 2.53824 + vertex 1.61236 1.73418 2.53935 + endloop + endfacet + facet normal 0.279772 0.101356 0.954701 + outer loop + vertex 1.61452 1.72363 2.53985 + vertex 1.61772 1.72773 2.53848 + vertex 1.61348 1.72889 2.5396 + endloop + endfacet + facet normal 0.282825 0.0969117 0.954263 + outer loop + vertex 1.61338 1.71925 2.54063 + vertex 1.61737 1.71932 2.53944 + vertex 1.61452 1.72363 2.53985 + endloop + endfacet + facet normal 0.280252 0.0965345 0.95506 + outer loop + vertex 1.61099 1.72123 2.54114 + vertex 1.60702 1.72112 2.54232 + vertex 1.60987 1.71683 2.54191 + endloop + endfacet + facet normal 0.281107 0.0971321 0.954748 + outer loop + vertex 1.60702 1.72112 2.54232 + vertex 1.60588 1.71673 2.5431 + vertex 1.60987 1.71683 2.54191 + endloop + endfacet + facet normal 0.282928 0.0944745 0.954477 + outer loop + vertex 1.61338 1.71925 2.54063 + vertex 1.6142 1.7152 2.54079 + vertex 1.61737 1.71932 2.53944 + endloop + endfacet + facet normal 0.283999 0.0937363 0.954232 + outer loop + vertex 1.6142 1.7152 2.54079 + vertex 1.61096 1.71149 2.54212 + vertex 1.6152 1.71029 2.54098 + endloop + endfacet + facet normal 0.284491 0.0958152 0.953879 + outer loop + vertex 1.61096 1.71149 2.54212 + vertex 1.61206 1.70616 2.54233 + vertex 1.6152 1.71029 2.54098 + endloop + endfacet + facet normal 0.284408 0.0961711 0.953867 + outer loop + vertex 1.61093 1.70175 2.54311 + vertex 1.61206 1.70616 2.54233 + vertex 1.60855 1.70372 2.54362 + endloop + endfacet + facet normal 0.283026 0.0943438 0.954461 + outer loop + vertex 1.60737 1.69933 2.5444 + vertex 1.61093 1.70175 2.54311 + vertex 1.60855 1.70372 2.54362 + endloop + endfacet + facet normal 0.283198 0.0898355 0.954845 + outer loop + vertex 1.60823 1.69407 2.54465 + vertex 1.60737 1.69933 2.5444 + vertex 1.60408 1.69523 2.54577 + endloop + endfacet + facet normal 0.281539 0.0952284 0.954813 + outer loop + vertex 1.60341 1.69923 2.54559 + vertex 1.60455 1.70361 2.54481 + vertex 1.60104 1.70117 2.54609 + endloop + endfacet + facet normal 0.281459 0.0969073 0.954667 + outer loop + vertex 1.60455 1.70361 2.54481 + vertex 1.60772 1.70776 2.54346 + vertex 1.60345 1.70894 2.5446 + endloop + endfacet + facet normal 0.281295 0.0961938 0.954788 + outer loop + vertex 1.60772 1.70776 2.54346 + vertex 1.6067 1.71267 2.54326 + vertex 1.60345 1.70894 2.5446 + endloop + endfacet + facet normal 0.281164 0.0959852 0.954847 + outer loop + vertex 1.6067 1.71267 2.54326 + vertex 1.60987 1.71683 2.54191 + vertex 1.60588 1.71673 2.5431 + endloop + endfacet + facet normal 0.280858 0.097208 0.954814 + outer loop + vertex 1.60588 1.71673 2.5431 + vertex 1.60702 1.72112 2.54232 + vertex 1.60349 1.71869 2.5436 + endloop + endfacet + facet normal 0.279667 0.100008 0.954874 + outer loop + vertex 1.60598 1.72638 2.54207 + vertex 1.60702 1.72112 2.54232 + vertex 1.6102 1.72522 2.54095 + endloop + endfacet + facet normal 0.280082 0.103173 0.954416 + outer loop + vertex 1.60485 1.73168 2.54183 + vertex 1.60598 1.72638 2.54207 + vertex 1.60923 1.73006 2.54072 + endloop + endfacet + facet normal 0.281837 0.100513 0.954183 + outer loop + vertex 1.60271 1.72269 2.54342 + vertex 1.60175 1.72755 2.54319 + vertex 1.59849 1.72386 2.54454 + endloop + endfacet + facet normal 0.281003 0.0968998 0.954803 + outer loop + vertex 1.5995 1.71856 2.54478 + vertex 1.60271 1.72269 2.54342 + vertex 1.59849 1.72386 2.54454 + endloop + endfacet + facet normal 0.279558 0.0961554 0.955302 + outer loop + vertex 1.59834 1.71414 2.54557 + vertex 1.60235 1.71427 2.54438 + vertex 1.5995 1.71856 2.54478 + endloop + endfacet + facet normal 0.291846 0.0957832 0.951657 + outer loop + vertex 1.59595 1.7161 2.54608 + vertex 1.59198 1.71603 2.5473 + vertex 1.59481 1.71168 2.54687 + endloop + endfacet + facet normal 0.29514 0.0980561 0.950409 + outer loop + vertex 1.59198 1.71603 2.5473 + vertex 1.59084 1.71163 2.54811 + vertex 1.59481 1.71168 2.54687 + endloop + endfacet + facet normal 0.279505 0.0970988 0.955222 + outer loop + vertex 1.59834 1.71414 2.54557 + vertex 1.59916 1.71009 2.54574 + vertex 1.60235 1.71427 2.54438 + endloop + endfacet + facet normal 0.283768 0.0981521 0.953856 + outer loop + vertex 1.59916 1.71009 2.54574 + vertex 1.59593 1.70637 2.54708 + vertex 1.6002 1.7052 2.54593 + endloop + endfacet + facet normal 0.283371 0.0964121 0.954152 + outer loop + vertex 1.59593 1.70637 2.54708 + vertex 1.59706 1.70107 2.54728 + vertex 1.6002 1.7052 2.54593 + endloop + endfacet + facet normal 0.285005 0.093524 0.953952 + outer loop + vertex 1.59706 1.70107 2.54728 + vertex 1.59594 1.69671 2.54804 + vertex 1.59986 1.6968 2.54686 + endloop + endfacet + facet normal 0.280634 0.0864036 0.955918 + outer loop + vertex 1.59986 1.6968 2.54686 + vertex 1.60069 1.69158 2.54709 + vertex 1.60408 1.69523 2.54577 + endloop + endfacet + facet normal 0.284121 0.0791695 0.955514 + outer loop + vertex 1.60142 1.68656 2.54729 + vertex 1.60069 1.69158 2.54709 + vertex 1.59731 1.68781 2.54841 + endloop + endfacet + facet normal 0.28117 0.070755 0.957046 + outer loop + vertex 1.60142 1.68656 2.54729 + vertex 1.60228 1.68128 2.54743 + vertex 1.60556 1.68543 2.54616 + endloop + endfacet + facet normal 0.283863 0.0645386 0.95669 + outer loop + vertex 1.60104 1.67686 2.5481 + vertex 1.60228 1.68128 2.54743 + vertex 1.5987 1.6788 2.54866 + endloop + endfacet + facet normal 0.282973 0.0626268 0.957081 + outer loop + vertex 1.60162 1.67284 2.54819 + vertex 1.60499 1.67701 2.54692 + vertex 1.60104 1.67686 2.5481 + endloop + endfacet + facet normal 0.282382 0.0633892 0.957205 + outer loop + vertex 1.60214 1.66791 2.54836 + vertex 1.60162 1.67284 2.54819 + vertex 1.5981 1.66913 2.54947 + endloop + endfacet + facet normal 0.285081 0.064925 0.956302 + outer loop + vertex 1.59855 1.66412 2.54968 + vertex 1.5981 1.66913 2.54947 + vertex 1.59455 1.66531 2.55079 + endloop + endfacet + facet normal 0.297166 0.0633196 0.952724 + outer loop + vertex 1.58984 1.67177 2.55182 + vertex 1.59052 1.66651 2.55196 + vertex 1.59403 1.6702 2.55062 + endloop + endfacet + facet normal 0.2943 0.0661814 0.953419 + outer loop + vertex 1.59455 1.66531 2.55079 + vertex 1.59103 1.66157 2.55213 + vertex 1.59499 1.66036 2.551 + endloop + endfacet + facet normal 0.294043 0.0652023 0.953566 + outer loop + vertex 1.59103 1.66157 2.55213 + vertex 1.59158 1.65672 2.55229 + vertex 1.59499 1.66036 2.551 + endloop + endfacet + facet normal 0.292166 0.0664384 0.954057 + outer loop + vertex 1.59158 1.65672 2.55229 + vertex 1.59214 1.65146 2.55249 + vertex 1.59555 1.65545 2.55117 + endloop + endfacet + facet normal 0.293364 0.0653174 0.953767 + outer loop + vertex 1.59555 1.65545 2.55117 + vertex 1.59214 1.65146 2.55249 + vertex 1.59619 1.65139 2.55125 + endloop + endfacet + facet normal 0.284853 0.0640389 0.95643 + outer loop + vertex 1.59619 1.65139 2.55125 + vertex 1.59979 1.6538 2.55002 + vertex 1.59555 1.65545 2.55117 + endloop + endfacet + facet normal 0.288885 0.0593385 0.955523 + outer loop + vertex 1.59917 1.64541 2.55073 + vertex 1.59856 1.6494 2.55067 + vertex 1.59497 1.64699 2.55191 + endloop + endfacet + facet normal 0.28658 0.0576743 0.956319 + outer loop + vertex 1.60319 1.6443 2.54959 + vertex 1.60669 1.64797 2.54832 + vertex 1.60252 1.64954 2.54948 + endloop + endfacet + facet normal 0.288249 0.0574122 0.955833 + outer loop + vertex 1.59497 1.64699 2.55191 + vertex 1.59571 1.64176 2.552 + vertex 1.59917 1.64541 2.55073 + endloop + endfacet + facet normal 0.298543 0.0540142 0.952866 + outer loop + vertex 1.59609 1.63675 2.55216 + vertex 1.59571 1.64176 2.552 + vertex 1.59224 1.63803 2.5533 + endloop + endfacet + facet normal 0.297627 0.0508423 0.953327 + outer loop + vertex 1.59255 1.63298 2.55347 + vertex 1.59609 1.63675 2.55216 + vertex 1.59224 1.63803 2.5533 + endloop + endfacet + facet normal 0.310142 0.0514698 0.949296 + outer loop + vertex 1.59255 1.63298 2.55347 + vertex 1.59224 1.63803 2.5533 + vertex 1.58871 1.63436 2.55465 + endloop + endfacet + facet normal 0.308841 0.0473255 0.949935 + outer loop + vertex 1.58902 1.62915 2.55481 + vertex 1.59255 1.63298 2.55347 + vertex 1.58871 1.63436 2.55465 + endloop + endfacet + facet normal 0.30713 0.0490633 0.950402 + outer loop + vertex 1.59304 1.62783 2.55358 + vertex 1.59255 1.63298 2.55347 + vertex 1.58902 1.62915 2.55481 + endloop + endfacet + facet normal 0.297439 0.0482095 0.953523 + outer loop + vertex 1.59304 1.62783 2.55358 + vertex 1.59649 1.63161 2.55231 + vertex 1.59255 1.63298 2.55347 + endloop + endfacet + facet normal 0.298092 0.0503641 0.953207 + outer loop + vertex 1.59649 1.63161 2.55231 + vertex 1.59609 1.63675 2.55216 + vertex 1.59255 1.63298 2.55347 + endloop + endfacet + facet normal 0.288008 0.053746 0.956119 + outer loop + vertex 1.60357 1.63923 2.54976 + vertex 1.60319 1.6443 2.54959 + vertex 1.59965 1.64051 2.55087 + endloop + endfacet + facet normal 0.287857 0.0501078 0.956362 + outer loop + vertex 1.60393 1.63409 2.54993 + vertex 1.60764 1.63778 2.54862 + vertex 1.60357 1.63923 2.54976 + endloop + endfacet + facet normal 0.290412 0.0498382 0.955603 + outer loop + vertex 1.59609 1.63675 2.55216 + vertex 1.59649 1.63161 2.55231 + vertex 1.59998 1.63547 2.55105 + endloop + endfacet + facet normal 0.297074 0.0485738 0.953618 + outer loop + vertex 1.59722 1.62617 2.55236 + vertex 1.59649 1.63161 2.55231 + vertex 1.59304 1.62783 2.55358 + endloop + endfacet + facet normal 0.296483 0.0468789 0.953887 + outer loop + vertex 1.59373 1.6237 2.55356 + vertex 1.59722 1.62617 2.55236 + vertex 1.59304 1.62783 2.55358 + endloop + endfacet + facet normal 0.304834 0.0482863 0.951181 + outer loop + vertex 1.59373 1.6237 2.55356 + vertex 1.59304 1.62783 2.55358 + vertex 1.58955 1.62343 2.55492 + endloop + endfacet + facet normal 0.304901 0.0473656 0.951205 + outer loop + vertex 1.58955 1.62343 2.55492 + vertex 1.59269 1.61957 2.5541 + vertex 1.59373 1.6237 2.55356 + endloop + endfacet + facet normal 0.298333 0.0492813 0.953189 + outer loop + vertex 1.59269 1.61957 2.5541 + vertex 1.5961 1.62175 2.55292 + vertex 1.59373 1.6237 2.55356 + endloop + endfacet + facet normal 0.299356 0.0475563 0.952955 + outer loop + vertex 1.59665 1.6178 2.55295 + vertex 1.5961 1.62175 2.55292 + vertex 1.59269 1.61957 2.5541 + endloop + endfacet + facet normal 0.298119 0.0444366 0.953494 + outer loop + vertex 1.59277 1.61441 2.55432 + vertex 1.59665 1.6178 2.55295 + vertex 1.59269 1.61957 2.5541 + endloop + endfacet + facet normal 0.309093 0.0444671 0.949992 + outer loop + vertex 1.59277 1.61441 2.55432 + vertex 1.59269 1.61957 2.5541 + vertex 1.58683 1.61675 2.55614 + endloop + endfacet + facet normal 0.306636 0.0373614 0.951093 + outer loop + vertex 1.58909 1.61049 2.55566 + vertex 1.59277 1.61441 2.55432 + vertex 1.58683 1.61675 2.55614 + endloop + endfacet + facet normal 0.303502 0.0406014 0.951965 + outer loop + vertex 1.59342 1.60924 2.55433 + vertex 1.59277 1.61441 2.55432 + vertex 1.58909 1.61049 2.55566 + endloop + endfacet + facet normal 0.302667 0.0372926 0.952366 + outer loop + vertex 1.58976 1.60546 2.55564 + vertex 1.59342 1.60924 2.55433 + vertex 1.58909 1.61049 2.55566 + endloop + endfacet + facet normal 0.314692 0.038879 0.948397 + outer loop + vertex 1.58909 1.61049 2.55566 + vertex 1.58583 1.60651 2.5569 + vertex 1.58976 1.60546 2.55564 + endloop + endfacet + facet normal 0.316676 0.0370718 0.947809 + outer loop + vertex 1.58524 1.61079 2.55694 + vertex 1.58583 1.60651 2.5569 + vertex 1.58909 1.61049 2.55566 + endloop + endfacet + facet normal 0.300532 0.0395589 0.952951 + outer loop + vertex 1.59366 1.60427 2.55446 + vertex 1.59342 1.60924 2.55433 + vertex 1.58976 1.60546 2.55564 + endloop + endfacet + facet normal 0.300296 0.0386642 0.953062 + outer loop + vertex 1.58991 1.60052 2.5558 + vertex 1.59366 1.60427 2.55446 + vertex 1.58976 1.60546 2.55564 + endloop + endfacet + facet normal 0.312601 0.0389204 0.949087 + outer loop + vertex 1.58976 1.60546 2.55564 + vertex 1.58608 1.6017 2.55701 + vertex 1.58991 1.60052 2.5558 + endloop + endfacet + facet normal 0.312452 0.0383666 0.949159 + outer loop + vertex 1.58608 1.6017 2.55701 + vertex 1.58614 1.59676 2.55719 + vertex 1.58991 1.60052 2.5558 + endloop + endfacet + facet normal 0.312147 0.0387042 0.949245 + outer loop + vertex 1.58991 1.60052 2.5558 + vertex 1.58614 1.59676 2.55719 + vertex 1.58994 1.59555 2.55599 + endloop + endfacet + facet normal 0.299796 0.0387884 0.953215 + outer loop + vertex 1.58994 1.59555 2.55599 + vertex 1.5937 1.59932 2.55465 + vertex 1.58991 1.60052 2.5558 + endloop + endfacet + facet normal 0.300616 0.0378909 0.952992 + outer loop + vertex 1.59374 1.59433 2.55484 + vertex 1.5937 1.59932 2.55465 + vertex 1.58994 1.59555 2.55599 + endloop + endfacet + facet normal 0.300408 0.0371502 0.953087 + outer loop + vertex 1.59002 1.59056 2.55616 + vertex 1.59374 1.59433 2.55484 + vertex 1.58994 1.59555 2.55599 + endloop + endfacet + facet normal 0.313057 0.0372306 0.949004 + outer loop + vertex 1.58994 1.59555 2.55599 + vertex 1.58621 1.59177 2.55737 + vertex 1.59002 1.59056 2.55616 + endloop + endfacet + facet normal 0.312672 0.0358419 0.949185 + outer loop + vertex 1.58621 1.59177 2.55737 + vertex 1.58636 1.58677 2.55751 + vertex 1.59002 1.59056 2.55616 + endloop + endfacet + facet normal 0.313729 0.0347111 0.948878 + outer loop + vertex 1.59002 1.59056 2.55616 + vertex 1.58636 1.58677 2.55751 + vertex 1.59026 1.58555 2.55626 + endloop + endfacet + facet normal 0.300661 0.0341827 0.953118 + outer loop + vertex 1.59026 1.58555 2.55626 + vertex 1.5939 1.58931 2.55498 + vertex 1.59002 1.59056 2.55616 + endloop + endfacet + facet normal 0.301193 0.0336169 0.952971 + outer loop + vertex 1.59424 1.58427 2.55505 + vertex 1.5939 1.58931 2.55498 + vertex 1.59026 1.58555 2.55626 + endloop + endfacet + facet normal 0.300157 0.0299619 0.953419 + outer loop + vertex 1.59072 1.58059 2.55627 + vertex 1.59424 1.58427 2.55505 + vertex 1.59026 1.58555 2.55626 + endloop + endfacet + facet normal 0.312902 0.0311312 0.949275 + outer loop + vertex 1.59026 1.58555 2.55626 + vertex 1.58667 1.5817 2.55757 + vertex 1.59072 1.58059 2.55627 + endloop + endfacet + facet normal 0.300076 0.0300467 0.953442 + outer loop + vertex 1.59488 1.57905 2.55501 + vertex 1.59424 1.58427 2.55505 + vertex 1.59072 1.58059 2.55627 + endloop + endfacet + facet normal 0.294485 0.029347 0.955205 + outer loop + vertex 1.59488 1.57905 2.55501 + vertex 1.59815 1.58307 2.55388 + vertex 1.59424 1.58427 2.55505 + endloop + endfacet + facet normal 0.295433 0.0328276 0.954799 + outer loop + vertex 1.59815 1.58307 2.55388 + vertex 1.5979 1.58796 2.55379 + vertex 1.59424 1.58427 2.55505 + endloop + endfacet + facet normal 0.294458 0.0327835 0.955102 + outer loop + vertex 1.59815 1.58307 2.55388 + vertex 1.60222 1.58622 2.55252 + vertex 1.5979 1.58796 2.55379 + endloop + endfacet + facet normal 0.295539 0.0312626 0.954819 + outer loop + vertex 1.60115 1.58169 2.553 + vertex 1.60222 1.58622 2.55252 + vertex 1.59815 1.58307 2.55388 + endloop + endfacet + facet normal 0.294678 0.0291889 0.955151 + outer loop + vertex 1.5987 1.57929 2.55383 + vertex 1.60115 1.58169 2.553 + vertex 1.59815 1.58307 2.55388 + endloop + endfacet + facet normal 0.297131 0.026443 0.95447 + outer loop + vertex 1.60169 1.57794 2.55293 + vertex 1.60115 1.58169 2.553 + vertex 1.5987 1.57929 2.55383 + endloop + endfacet + facet normal 0.296102 0.0239172 0.954857 + outer loop + vertex 1.59761 1.57485 2.55428 + vertex 1.60169 1.57794 2.55293 + vertex 1.5987 1.57929 2.55383 + endloop + endfacet + facet normal 0.294996 0.0242213 0.955191 + outer loop + vertex 1.59488 1.57905 2.55501 + vertex 1.59761 1.57485 2.55428 + vertex 1.5987 1.57929 2.55383 + endloop + endfacet + facet normal 0.295716 0.0247315 0.954956 + outer loop + vertex 1.5936 1.57465 2.55552 + vertex 1.59761 1.57485 2.55428 + vertex 1.59488 1.57905 2.55501 + endloop + endfacet + facet normal 0.297243 0.0222716 0.954542 + outer loop + vertex 1.60188 1.57314 2.55298 + vertex 1.60169 1.57794 2.55293 + vertex 1.59761 1.57485 2.55428 + endloop + endfacet + facet normal 0.296524 0.0202807 0.95481 + outer loop + vertex 1.59814 1.56942 2.55423 + vertex 1.60188 1.57314 2.55298 + vertex 1.59761 1.57485 2.55428 + endloop + endfacet + facet normal 0.297998 0.018651 0.954384 + outer loop + vertex 1.60209 1.5681 2.55302 + vertex 1.60188 1.57314 2.55298 + vertex 1.59814 1.56942 2.55423 + endloop + endfacet + facet normal 0.299861 0.0187233 0.953799 + outer loop + vertex 1.60209 1.5681 2.55302 + vertex 1.60583 1.57182 2.55177 + vertex 1.60188 1.57314 2.55298 + endloop + endfacet + facet normal 0.300448 0.0206999 0.953574 + outer loop + vertex 1.60583 1.57182 2.55177 + vertex 1.60557 1.57681 2.55174 + vertex 1.60188 1.57314 2.55298 + endloop + endfacet + facet normal 0.298961 0.022336 0.954004 + outer loop + vertex 1.60188 1.57314 2.55298 + vertex 1.60557 1.57681 2.55174 + vertex 1.60169 1.57794 2.55293 + endloop + endfacet + facet normal 0.297861 0.0265525 0.95424 + outer loop + vertex 1.60169 1.57794 2.55293 + vertex 1.60497 1.58202 2.55179 + vertex 1.60115 1.58169 2.553 + endloop + endfacet + facet normal 0.297494 0.0307382 0.954229 + outer loop + vertex 1.60222 1.58622 2.55252 + vertex 1.60115 1.58169 2.553 + vertex 1.60497 1.58202 2.55179 + endloop + endfacet + facet normal 0.294665 0.0291869 0.955155 + outer loop + vertex 1.5987 1.57929 2.55383 + vertex 1.59815 1.58307 2.55388 + vertex 1.59488 1.57905 2.55501 + endloop + endfacet + facet normal 0.295061 0.0332314 0.9549 + outer loop + vertex 1.59424 1.58427 2.55505 + vertex 1.5979 1.58796 2.55379 + vertex 1.5939 1.58931 2.55498 + endloop + endfacet + facet normal 0.295723 0.0354387 0.954616 + outer loop + vertex 1.5979 1.58796 2.55379 + vertex 1.5976 1.59307 2.55369 + vertex 1.5939 1.58931 2.55498 + endloop + endfacet + facet normal 0.295106 0.0361043 0.954782 + outer loop + vertex 1.5939 1.58931 2.55498 + vertex 1.5976 1.59307 2.55369 + vertex 1.59374 1.59433 2.55484 + endloop + endfacet + facet normal 0.295494 0.0374445 0.95461 + outer loop + vertex 1.5976 1.59307 2.55369 + vertex 1.59747 1.5981 2.55354 + vertex 1.59374 1.59433 2.55484 + endloop + endfacet + facet normal 0.294032 0.0374201 0.955063 + outer loop + vertex 1.5976 1.59307 2.55369 + vertex 1.6013 1.59684 2.55241 + vertex 1.59747 1.5981 2.55354 + endloop + endfacet + facet normal 0.294496 0.0369233 0.954939 + outer loop + vertex 1.6016 1.59173 2.55251 + vertex 1.6013 1.59684 2.55241 + vertex 1.5976 1.59307 2.55369 + endloop + endfacet + facet normal 0.29403 0.0353522 0.955142 + outer loop + vertex 1.5979 1.58796 2.55379 + vertex 1.6016 1.59173 2.55251 + vertex 1.5976 1.59307 2.55369 + endloop + endfacet + facet normal 0.301244 0.0362472 0.952858 + outer loop + vertex 1.5939 1.58931 2.55498 + vertex 1.59374 1.59433 2.55484 + vertex 1.59002 1.59056 2.55616 + endloop + endfacet + facet normal 0.295064 0.0379112 0.954725 + outer loop + vertex 1.59374 1.59433 2.55484 + vertex 1.59747 1.5981 2.55354 + vertex 1.5937 1.59932 2.55465 + endloop + endfacet + facet normal 0.295214 0.0384346 0.954658 + outer loop + vertex 1.59747 1.5981 2.55354 + vertex 1.59744 1.60306 2.55335 + vertex 1.5937 1.59932 2.55465 + endloop + endfacet + facet normal 0.294573 0.039135 0.954827 + outer loop + vertex 1.5937 1.59932 2.55465 + vertex 1.59744 1.60306 2.55335 + vertex 1.59366 1.60427 2.55446 + endloop + endfacet + facet normal 0.294687 0.0395407 0.954775 + outer loop + vertex 1.59744 1.60306 2.55335 + vertex 1.59738 1.608 2.55316 + vertex 1.59366 1.60427 2.55446 + endloop + endfacet + facet normal 0.29362 0.0395388 0.955104 + outer loop + vertex 1.59744 1.60306 2.55335 + vertex 1.60114 1.60679 2.55205 + vertex 1.59738 1.608 2.55316 + endloop + endfacet + facet normal 0.29421 0.0388994 0.954949 + outer loop + vertex 1.60118 1.60184 2.55224 + vertex 1.60114 1.60679 2.55205 + vertex 1.59744 1.60306 2.55335 + endloop + endfacet + facet normal 0.294078 0.0384408 0.955008 + outer loop + vertex 1.59747 1.5981 2.55354 + vertex 1.60118 1.60184 2.55224 + vertex 1.59744 1.60306 2.55335 + endloop + endfacet + facet normal 0.299886 0.0391131 0.953173 + outer loop + vertex 1.5937 1.59932 2.55465 + vertex 1.59366 1.60427 2.55446 + vertex 1.58991 1.60052 2.5558 + endloop + endfacet + facet normal 0.294882 0.0393281 0.954724 + outer loop + vertex 1.59366 1.60427 2.55446 + vertex 1.59738 1.608 2.55316 + vertex 1.59342 1.60924 2.55433 + endloop + endfacet + facet normal 0.295452 0.0413804 0.954461 + outer loop + vertex 1.59738 1.608 2.55316 + vertex 1.5971 1.61293 2.55303 + vertex 1.59342 1.60924 2.55433 + endloop + endfacet + facet normal 0.293022 0.0412666 0.955215 + outer loop + vertex 1.59738 1.608 2.55316 + vertex 1.60101 1.6117 2.55188 + vertex 1.5971 1.61293 2.55303 + endloop + endfacet + facet normal 0.293565 0.0432339 0.954961 + outer loop + vertex 1.60101 1.6117 2.55188 + vertex 1.60064 1.61664 2.55178 + vertex 1.5971 1.61293 2.55303 + endloop + endfacet + facet normal 0.293021 0.0438018 0.955102 + outer loop + vertex 1.5971 1.61293 2.55303 + vertex 1.60064 1.61664 2.55178 + vertex 1.59665 1.6178 2.55295 + endloop + endfacet + facet normal 0.296913 0.0397829 0.954075 + outer loop + vertex 1.59342 1.60924 2.55433 + vertex 1.5971 1.61293 2.55303 + vertex 1.59277 1.61441 2.55432 + endloop + endfacet + facet normal 0.298259 0.0442613 0.953458 + outer loop + vertex 1.5971 1.61293 2.55303 + vertex 1.59665 1.6178 2.55295 + vertex 1.59277 1.61441 2.55432 + endloop + endfacet + facet normal 0.293097 0.0466967 0.954942 + outer loop + vertex 1.59665 1.6178 2.55295 + vertex 1.59991 1.62185 2.55175 + vertex 1.5961 1.62175 2.55292 + endloop + endfacet + facet normal 0.293055 0.0478416 0.954898 + outer loop + vertex 1.59722 1.62617 2.55236 + vertex 1.5961 1.62175 2.55292 + vertex 1.59991 1.62185 2.55175 + endloop + endfacet + facet normal 0.296514 0.0468329 0.95388 + outer loop + vertex 1.5961 1.62175 2.55292 + vertex 1.59722 1.62617 2.55236 + vertex 1.59373 1.6237 2.55356 + endloop + endfacet + facet normal 0.288982 0.0477962 0.95614 + outer loop + vertex 1.6046 1.62874 2.54999 + vertex 1.60393 1.63409 2.54993 + vertex 1.60045 1.6304 2.55116 + endloop + endfacet + facet normal 0.289226 0.0465451 0.956129 + outer loop + vertex 1.60339 1.62431 2.55057 + vertex 1.60747 1.62449 2.54933 + vertex 1.6046 1.62874 2.54999 + endloop + endfacet + facet normal 0.291392 0.046728 0.955462 + outer loop + vertex 1.60106 1.62628 2.55118 + vertex 1.59722 1.62617 2.55236 + vertex 1.59991 1.62185 2.55175 + endloop + endfacet + facet normal 0.28926 0.0458999 0.956149 + outer loop + vertex 1.60339 1.62431 2.55057 + vertex 1.60406 1.6203 2.55056 + vertex 1.60747 1.62449 2.54933 + endloop + endfacet + facet normal 0.293637 0.0462203 0.954799 + outer loop + vertex 1.60064 1.61664 2.55178 + vertex 1.59991 1.62185 2.55175 + vertex 1.59665 1.6178 2.55295 + endloop + endfacet + facet normal 0.290744 0.0445779 0.955762 + outer loop + vertex 1.60814 1.6192 2.54937 + vertex 1.60747 1.62449 2.54933 + vertex 1.60406 1.6203 2.55056 + endloop + endfacet + facet normal 0.293001 0.0417882 0.955198 + outer loop + vertex 1.60847 1.61427 2.54949 + vertex 1.61217 1.61796 2.54819 + vertex 1.60814 1.6192 2.54937 + endloop + endfacet + facet normal 0.291568 0.0430969 0.955579 + outer loop + vertex 1.60064 1.61664 2.55178 + vertex 1.60101 1.6117 2.55188 + vertex 1.60458 1.61543 2.55063 + endloop + endfacet + facet normal 0.293856 0.0403732 0.954997 + outer loop + vertex 1.60114 1.60679 2.55205 + vertex 1.60101 1.6117 2.55188 + vertex 1.59738 1.608 2.55316 + endloop + endfacet + facet normal 0.294664 0.0391786 0.954798 + outer loop + vertex 1.60857 1.60933 2.54966 + vertex 1.60847 1.61427 2.54949 + vertex 1.6048 1.61052 2.55077 + endloop + endfacet + facet normal 0.297769 0.0377855 0.95389 + outer loop + vertex 1.60864 1.60434 2.54983 + vertex 1.61236 1.6081 2.54852 + vertex 1.60857 1.60933 2.54966 + endloop + endfacet + facet normal 0.294331 0.038899 0.954911 + outer loop + vertex 1.60114 1.60679 2.55205 + vertex 1.60118 1.60184 2.55224 + vertex 1.60487 1.60558 2.55095 + endloop + endfacet + facet normal 0.294268 0.038235 0.954958 + outer loop + vertex 1.6013 1.59684 2.55241 + vertex 1.60118 1.60184 2.55224 + vertex 1.59747 1.5981 2.55354 + endloop + endfacet + facet normal 0.296427 0.0379542 0.954301 + outer loop + vertex 1.60882 1.5993 2.54998 + vertex 1.60864 1.60434 2.54983 + vertex 1.60496 1.6006 2.55113 + endloop + endfacet + facet normal 0.294501 0.0369235 0.954938 + outer loop + vertex 1.6013 1.59684 2.55241 + vertex 1.6016 1.59173 2.55251 + vertex 1.6052 1.59557 2.55125 + endloop + endfacet + facet normal 0.295005 0.0343036 0.95488 + outer loop + vertex 1.60222 1.58622 2.55252 + vertex 1.6016 1.59173 2.55251 + vertex 1.5979 1.58796 2.55379 + endloop + endfacet + facet normal 0.298257 0.0348995 0.953847 + outer loop + vertex 1.60986 1.58897 2.55005 + vertex 1.60919 1.59423 2.55006 + vertex 1.60568 1.59055 2.5513 + endloop + endfacet + facet normal 0.302186 0.0300455 0.952776 + outer loop + vertex 1.60859 1.58455 2.55059 + vertex 1.6126 1.58477 2.54931 + vertex 1.60986 1.58897 2.55005 + endloop + endfacet + facet normal 0.295651 0.0294231 0.954843 + outer loop + vertex 1.60626 1.58647 2.55126 + vertex 1.60222 1.58622 2.55252 + vertex 1.60497 1.58202 2.55179 + endloop + endfacet + facet normal 0.302428 0.0258951 0.95282 + outer loop + vertex 1.60859 1.58455 2.55059 + vertex 1.60913 1.5805 2.55053 + vertex 1.6126 1.58477 2.54931 + endloop + endfacet + facet normal 0.29964 0.0249768 0.953725 + outer loop + vertex 1.60557 1.57681 2.55174 + vertex 1.60497 1.58202 2.55179 + vertex 1.60169 1.57794 2.55293 + endloop + endfacet + facet normal 0.304186 0.0243144 0.952302 + outer loop + vertex 1.61315 1.57937 2.54927 + vertex 1.6126 1.58477 2.54931 + vertex 1.60913 1.5805 2.55053 + endloop + endfacet + facet normal 0.306431 0.0205159 0.951672 + outer loop + vertex 1.61337 1.57433 2.54931 + vertex 1.61708 1.57807 2.54803 + vertex 1.61315 1.57937 2.54927 + endloop + endfacet + facet normal 0.301901 0.0207742 0.953113 + outer loop + vertex 1.60557 1.57681 2.55174 + vertex 1.60583 1.57182 2.55177 + vertex 1.60952 1.57556 2.55052 + endloop + endfacet + facet normal 0.301428 0.0169945 0.953338 + outer loop + vertex 1.60592 1.56684 2.55183 + vertex 1.60583 1.57182 2.55177 + vertex 1.60209 1.5681 2.55302 + endloop + endfacet + facet normal 0.300788 0.014823 0.953576 + outer loop + vertex 1.60214 1.5631 2.55308 + vertex 1.60592 1.56684 2.55183 + vertex 1.60209 1.5681 2.55302 + endloop + endfacet + facet normal 0.298652 0.0148083 0.954247 + outer loop + vertex 1.60214 1.5631 2.55308 + vertex 1.60209 1.5681 2.55302 + vertex 1.59833 1.56435 2.55425 + endloop + endfacet + facet normal 0.298334 0.013732 0.954363 + outer loop + vertex 1.59836 1.55934 2.55432 + vertex 1.60214 1.5631 2.55308 + vertex 1.59833 1.56435 2.55425 + endloop + endfacet + facet normal 0.299414 0.0125371 0.954041 + outer loop + vertex 1.60215 1.55812 2.55314 + vertex 1.60214 1.5631 2.55308 + vertex 1.59836 1.55934 2.55432 + endloop + endfacet + facet normal 0.30177 0.0125284 0.953298 + outer loop + vertex 1.60215 1.55812 2.55314 + vertex 1.60593 1.56186 2.5519 + vertex 1.60214 1.5631 2.55308 + endloop + endfacet + facet normal 0.302037 0.0134364 0.953202 + outer loop + vertex 1.60593 1.56186 2.5519 + vertex 1.60592 1.56684 2.55183 + vertex 1.60214 1.5631 2.55308 + endloop + endfacet + facet normal 0.306952 0.0170928 0.951571 + outer loop + vertex 1.61343 1.56935 2.54938 + vertex 1.61337 1.57433 2.54931 + vertex 1.60967 1.57058 2.55057 + endloop + endfacet + facet normal 0.309286 0.0137205 0.95087 + outer loop + vertex 1.61344 1.56436 2.54945 + vertex 1.61716 1.5681 2.54818 + vertex 1.61343 1.56935 2.54938 + endloop + endfacet + facet normal 0.304162 0.0134305 0.952526 + outer loop + vertex 1.60592 1.56684 2.55183 + vertex 1.60593 1.56186 2.5519 + vertex 1.60969 1.5656 2.55064 + endloop + endfacet + facet normal 0.302835 0.0113441 0.952976 + outer loop + vertex 1.60594 1.55688 2.55195 + vertex 1.60593 1.56186 2.5519 + vertex 1.60215 1.55812 2.55314 + endloop + endfacet + facet normal 0.302984 0.0118525 0.952922 + outer loop + vertex 1.60217 1.55314 2.5532 + vertex 1.60594 1.55688 2.55195 + vertex 1.60215 1.55812 2.55314 + endloop + endfacet + facet normal 0.300577 0.0118485 0.953684 + outer loop + vertex 1.60217 1.55314 2.5532 + vertex 1.60215 1.55812 2.55314 + vertex 1.59837 1.55436 2.55438 + endloop + endfacet + facet normal 0.301103 0.0136659 0.953494 + outer loop + vertex 1.59841 1.54938 2.55444 + vertex 1.60217 1.55314 2.5532 + vertex 1.59837 1.55436 2.55438 + endloop + endfacet + facet normal 0.302541 0.0120819 0.95306 + outer loop + vertex 1.60223 1.54815 2.55324 + vertex 1.60217 1.55314 2.5532 + vertex 1.59841 1.54938 2.55444 + endloop + endfacet + facet normal 0.304828 0.0121012 0.952331 + outer loop + vertex 1.60223 1.54815 2.55324 + vertex 1.60598 1.55189 2.55199 + vertex 1.60217 1.55314 2.5532 + endloop + endfacet + facet normal 0.30432 0.0103708 0.952514 + outer loop + vertex 1.60598 1.55189 2.55199 + vertex 1.60594 1.55688 2.55195 + vertex 1.60217 1.55314 2.5532 + endloop + endfacet + facet normal 0.308561 0.0106199 0.951145 + outer loop + vertex 1.61347 1.55937 2.54949 + vertex 1.61344 1.56436 2.54945 + vertex 1.6097 1.56062 2.5507 + endloop + endfacet + facet normal 0.311468 0.00847049 0.950219 + outer loop + vertex 1.61351 1.55438 2.54953 + vertex 1.61723 1.55812 2.54827 + vertex 1.61347 1.55937 2.54949 + endloop + endfacet + facet normal 0.306706 0.0103837 0.951748 + outer loop + vertex 1.60594 1.55688 2.55195 + vertex 1.60598 1.55189 2.55199 + vertex 1.60973 1.55563 2.55074 + endloop + endfacet + facet normal 0.306895 0.00981433 0.951693 + outer loop + vertex 1.60603 1.5469 2.55203 + vertex 1.60598 1.55189 2.55199 + vertex 1.60223 1.54815 2.55324 + endloop + endfacet + facet normal 0.30714 0.0106452 0.951605 + outer loop + vertex 1.60229 1.54315 2.55328 + vertex 1.60603 1.5469 2.55203 + vertex 1.60223 1.54815 2.55324 + endloop + endfacet + facet normal 0.30559 0.01063 0.952104 + outer loop + vertex 1.60229 1.54315 2.55328 + vertex 1.60223 1.54815 2.55324 + vertex 1.59848 1.54439 2.55449 + endloop + endfacet + facet normal 0.305666 0.0108919 0.952076 + outer loop + vertex 1.59855 1.5394 2.55452 + vertex 1.60229 1.54315 2.55328 + vertex 1.59848 1.54439 2.55449 + endloop + endfacet + facet normal 0.308736 0.00751643 0.951118 + outer loop + vertex 1.60233 1.53816 2.5533 + vertex 1.60229 1.54315 2.55328 + vertex 1.59855 1.5394 2.55452 + endloop + endfacet + facet normal 0.309242 0.00752011 0.950954 + outer loop + vertex 1.60233 1.53816 2.5533 + vertex 1.60607 1.5419 2.55206 + vertex 1.60229 1.54315 2.55328 + endloop + endfacet + facet normal 0.309422 0.00812334 0.95089 + outer loop + vertex 1.60607 1.5419 2.55206 + vertex 1.60603 1.5469 2.55203 + vertex 1.60229 1.54315 2.55328 + endloop + endfacet + facet normal 0.310653 0.00799282 0.95049 + outer loop + vertex 1.61355 1.54938 2.54956 + vertex 1.61351 1.55438 2.54953 + vertex 1.60978 1.55064 2.55078 + endloop + endfacet + facet normal 0.312378 0.00761829 0.949927 + outer loop + vertex 1.61357 1.54439 2.54959 + vertex 1.6173 1.54813 2.54833 + vertex 1.61355 1.54938 2.54956 + endloop + endfacet + facet normal 0.309815 0.00812582 0.950762 + outer loop + vertex 1.60603 1.5469 2.55203 + vertex 1.60607 1.5419 2.55206 + vertex 1.60981 1.54564 2.55081 + endloop + endfacet + facet normal 0.311489 0.00503405 0.950236 + outer loop + vertex 1.6061 1.53691 2.55208 + vertex 1.60607 1.5419 2.55206 + vertex 1.60233 1.53816 2.5533 + endloop + endfacet + facet normal 0.311125 0.00381691 0.950361 + outer loop + vertex 1.60236 1.53317 2.55332 + vertex 1.6061 1.53691 2.55208 + vertex 1.60233 1.53816 2.5533 + endloop + endfacet + facet normal 0.311042 0.0038166 0.950388 + outer loop + vertex 1.60236 1.53317 2.55332 + vertex 1.60233 1.53816 2.5533 + vertex 1.59859 1.5344 2.55455 + endloop + endfacet + facet normal 0.310874 0.00324603 0.950446 + outer loop + vertex 1.59861 1.52941 2.55456 + vertex 1.60236 1.53317 2.55332 + vertex 1.59859 1.5344 2.55455 + endloop + endfacet + facet normal 0.312074 0.00192017 0.950056 + outer loop + vertex 1.60236 1.52818 2.55332 + vertex 1.60236 1.53317 2.55332 + vertex 1.59861 1.52941 2.55456 + endloop + endfacet + facet normal 0.311848 0.00191987 0.95013 + outer loop + vertex 1.60236 1.52818 2.55332 + vertex 1.60611 1.53192 2.55209 + vertex 1.60236 1.53317 2.55332 + endloop + endfacet + facet normal 0.312095 0.00274241 0.950047 + outer loop + vertex 1.60611 1.53192 2.55209 + vertex 1.6061 1.53691 2.55208 + vertex 1.60236 1.53317 2.55332 + endloop + endfacet + facet normal 0.310841 0.00665982 0.950439 + outer loop + vertex 1.6136 1.53939 2.54961 + vertex 1.61357 1.54439 2.54959 + vertex 1.60984 1.54065 2.55083 + endloop + endfacet + facet normal 0.310444 0.00496642 0.950579 + outer loop + vertex 1.61361 1.5344 2.54964 + vertex 1.61736 1.53815 2.54839 + vertex 1.6136 1.53939 2.54961 + endloop + endfacet + facet normal 0.310527 0.00273999 0.95056 + outer loop + vertex 1.6061 1.53691 2.55208 + vertex 1.60611 1.53192 2.55209 + vertex 1.60985 1.53565 2.55085 + endloop + endfacet + facet normal 0.311417 0.00239699 0.95027 + outer loop + vertex 1.60612 1.52692 2.5521 + vertex 1.60611 1.53192 2.55209 + vertex 1.60236 1.52818 2.55332 + endloop + endfacet + facet normal 0.311569 0.00290176 0.950219 + outer loop + vertex 1.60237 1.52318 2.55334 + vertex 1.60612 1.52692 2.5521 + vertex 1.60236 1.52818 2.55332 + endloop + endfacet + facet normal 0.311468 0.00290163 0.950252 + outer loop + vertex 1.60237 1.52318 2.55334 + vertex 1.60236 1.52818 2.55332 + vertex 1.59861 1.52442 2.55457 + endloop + endfacet + facet normal 0.311613 0.0033914 0.950203 + outer loop + vertex 1.59863 1.51943 2.55458 + vertex 1.60237 1.52318 2.55334 + vertex 1.59861 1.52442 2.55457 + endloop + endfacet + facet normal 0.310438 0.00468955 0.950582 + outer loop + vertex 1.60239 1.51819 2.55335 + vertex 1.60237 1.52318 2.55334 + vertex 1.59863 1.51943 2.55458 + endloop + endfacet + facet normal 0.31057 0.0046899 0.950539 + outer loop + vertex 1.60239 1.51819 2.55335 + vertex 1.60613 1.52193 2.55211 + vertex 1.60237 1.52318 2.55334 + endloop + endfacet + facet normal 0.310417 0.00417792 0.950591 + outer loop + vertex 1.60613 1.52193 2.55211 + vertex 1.60612 1.52692 2.5521 + vertex 1.60237 1.52318 2.55334 + endloop + endfacet + facet normal 0.308681 0.00367482 0.951159 + outer loop + vertex 1.61362 1.52941 2.54965 + vertex 1.61361 1.5344 2.54964 + vertex 1.60986 1.53066 2.55087 + endloop + endfacet + facet normal 0.30974 0.00384933 0.950813 + outer loop + vertex 1.61364 1.52442 2.54967 + vertex 1.61739 1.52816 2.54843 + vertex 1.61362 1.52941 2.54965 + endloop + endfacet + facet normal 0.309344 0.00417546 0.950941 + outer loop + vertex 1.60612 1.52692 2.5521 + vertex 1.60613 1.52193 2.55211 + vertex 1.60987 1.52567 2.55088 + endloop + endfacet + facet normal 0.309681 0.005674 0.950824 + outer loop + vertex 1.60616 1.51694 2.55214 + vertex 1.60613 1.52193 2.55211 + vertex 1.60239 1.51819 2.55335 + endloop + endfacet + facet normal 0.309542 0.00520981 0.950872 + outer loop + vertex 1.60242 1.5132 2.55337 + vertex 1.60616 1.51694 2.55214 + vertex 1.60239 1.51819 2.55335 + endloop + endfacet + facet normal 0.309007 0.00520793 0.951045 + outer loop + vertex 1.60242 1.5132 2.55337 + vertex 1.60239 1.51819 2.55335 + vertex 1.59864 1.51444 2.55459 + endloop + endfacet + facet normal 0.308272 0.00271553 0.951294 + outer loop + vertex 1.59866 1.50944 2.5546 + vertex 1.60242 1.5132 2.55337 + vertex 1.59864 1.51444 2.55459 + endloop + endfacet + facet normal 0.307668 0.00338325 0.951488 + outer loop + vertex 1.60243 1.50821 2.55339 + vertex 1.60242 1.5132 2.55337 + vertex 1.59866 1.50944 2.5546 + endloop + endfacet + facet normal 0.309141 0.00338719 0.95101 + outer loop + vertex 1.60243 1.50821 2.55339 + vertex 1.60619 1.51195 2.55215 + vertex 1.60242 1.5132 2.55337 + endloop + endfacet + facet normal 0.30965 0.00508999 0.950837 + outer loop + vertex 1.60619 1.51195 2.55215 + vertex 1.60616 1.51694 2.55214 + vertex 1.60242 1.5132 2.55337 + endloop + endfacet + facet normal 0.309212 0.00400935 0.950985 + outer loop + vertex 1.61367 1.51942 2.54968 + vertex 1.61364 1.52442 2.54967 + vertex 1.6099 1.52068 2.5509 + endloop + endfacet + facet normal 0.31214 0.00337012 0.95003 + outer loop + vertex 1.61369 1.51443 2.54969 + vertex 1.61743 1.51817 2.54845 + vertex 1.61367 1.51942 2.54968 + endloop + endfacet + facet normal 0.309685 0.00509015 0.950826 + outer loop + vertex 1.60616 1.51694 2.55214 + vertex 1.60619 1.51195 2.55215 + vertex 1.60993 1.51569 2.55091 + endloop + endfacet + facet normal 0.309678 0.00279089 0.950837 + outer loop + vertex 1.60621 1.50696 2.55216 + vertex 1.60619 1.51195 2.55215 + vertex 1.60243 1.50821 2.55339 + endloop + endfacet + facet normal 0.308862 6.75615e-05 0.951107 + outer loop + vertex 1.60244 1.50322 2.55339 + vertex 1.60621 1.50696 2.55216 + vertex 1.60243 1.50821 2.55339 + endloop + endfacet + facet normal 0.306475 6.74273e-05 0.951879 + outer loop + vertex 1.60244 1.50322 2.55339 + vertex 1.60243 1.50821 2.55339 + vertex 1.59866 1.50445 2.5546 + endloop + endfacet + facet normal 0.305552 -0.00304066 0.952171 + outer loop + vertex 1.59864 1.49946 2.55459 + vertex 1.60244 1.50322 2.55339 + vertex 1.59866 1.50445 2.5546 + endloop + endfacet + facet normal 0.305463 -0.00294212 0.952199 + outer loop + vertex 1.60242 1.49823 2.55338 + vertex 1.60244 1.50322 2.55339 + vertex 1.59864 1.49946 2.55459 + endloop + endfacet + facet normal 0.308589 -0.00294963 0.951191 + outer loop + vertex 1.60242 1.49823 2.55338 + vertex 1.60621 1.50197 2.55216 + vertex 1.60244 1.50322 2.55339 + endloop + endfacet + facet normal 0.309337 -0.000462724 0.950952 + outer loop + vertex 1.60621 1.50197 2.55216 + vertex 1.60621 1.50696 2.55216 + vertex 1.60244 1.50322 2.55339 + endloop + endfacet + facet normal 0.31316 0.00156791 0.949699 + outer loop + vertex 1.61371 1.50944 2.54969 + vertex 1.61369 1.51443 2.54969 + vertex 1.60996 1.51069 2.55093 + endloop + endfacet + facet normal 0.315976 -0.000506304 0.948767 + outer loop + vertex 1.61372 1.50445 2.54969 + vertex 1.61745 1.50819 2.54844 + vertex 1.61371 1.50944 2.54969 + endloop + endfacet + facet normal 0.311642 -0.000462053 0.950199 + outer loop + vertex 1.60621 1.50696 2.55216 + vertex 1.60621 1.50197 2.55216 + vertex 1.60997 1.5057 2.55093 + endloop + endfacet + facet normal 0.308554 -0.00291042 0.951202 + outer loop + vertex 1.6062 1.49697 2.55215 + vertex 1.60621 1.50197 2.55216 + vertex 1.60242 1.49823 2.55338 + endloop + endfacet + facet normal 0.307926 -0.00499695 0.951397 + outer loop + vertex 1.6024 1.49323 2.55336 + vertex 1.6062 1.49697 2.55215 + vertex 1.60242 1.49823 2.55338 + endloop + endfacet + facet normal 0.304318 -0.00498364 0.952558 + outer loop + vertex 1.6024 1.49323 2.55336 + vertex 1.60242 1.49823 2.55338 + vertex 1.59861 1.49447 2.55457 + endloop + endfacet + facet normal 0.303956 -0.00619879 0.952666 + outer loop + vertex 1.59858 1.48947 2.55455 + vertex 1.6024 1.49323 2.55336 + vertex 1.59861 1.49447 2.55457 + endloop + endfacet + facet normal 0.303265 -0.00542782 0.952891 + outer loop + vertex 1.60237 1.48823 2.55334 + vertex 1.6024 1.49323 2.55336 + vertex 1.59858 1.48947 2.55455 + endloop + endfacet + facet normal 0.307129 -0.00544209 0.951652 + outer loop + vertex 1.60237 1.48823 2.55334 + vertex 1.60618 1.49198 2.55213 + vertex 1.6024 1.49323 2.55336 + endloop + endfacet + facet normal 0.30743 -0.00444107 0.95156 + outer loop + vertex 1.60618 1.49198 2.55213 + vertex 1.6062 1.49697 2.55215 + vertex 1.6024 1.49323 2.55336 + endloop + endfacet + facet normal 0.314794 -0.00198591 0.949158 + outer loop + vertex 1.61371 1.49946 2.54968 + vertex 1.61372 1.50445 2.54969 + vertex 1.60997 1.50071 2.55092 + endloop + endfacet + facet normal 0.317198 -0.0030527 0.948355 + outer loop + vertex 1.6137 1.49447 2.54966 + vertex 1.61744 1.49821 2.54843 + vertex 1.61371 1.49946 2.54968 + endloop + endfacet + facet normal 0.311455 -0.00445057 0.95025 + outer loop + vertex 1.6062 1.49697 2.55215 + vertex 1.60618 1.49198 2.55213 + vertex 1.60996 1.49572 2.55091 + endloop + endfacet + facet normal 0.306835 -0.00511244 0.951749 + outer loop + vertex 1.60616 1.48698 2.55211 + vertex 1.60618 1.49198 2.55213 + vertex 1.60237 1.48823 2.55334 + endloop + endfacet + facet normal 0.30669 -0.00559508 0.951793 + outer loop + vertex 1.60235 1.48323 2.55332 + vertex 1.60616 1.48698 2.55211 + vertex 1.60237 1.48823 2.55334 + endloop + endfacet + facet normal 0.302935 -0.00558358 0.952995 + outer loop + vertex 1.60235 1.48323 2.55332 + vertex 1.60237 1.48823 2.55334 + vertex 1.59856 1.48447 2.55453 + endloop + endfacet + facet normal 0.302858 -0.00584167 0.953018 + outer loop + vertex 1.59854 1.47948 2.5545 + vertex 1.60235 1.48323 2.55332 + vertex 1.59856 1.48447 2.55453 + endloop + endfacet + facet normal 0.303516 -0.00657675 0.952804 + outer loop + vertex 1.60233 1.47824 2.55329 + vertex 1.60235 1.48323 2.55332 + vertex 1.59854 1.47948 2.5545 + endloop + endfacet + facet normal 0.303265 -0.00740855 0.952877 + outer loop + vertex 1.59853 1.47451 2.55447 + vertex 1.60233 1.47824 2.55329 + vertex 1.59854 1.47948 2.5545 + endloop + endfacet + facet normal 0.301317 -0.00740913 0.953495 + outer loop + vertex 1.59853 1.47451 2.55447 + vertex 1.59854 1.47948 2.5545 + vertex 1.59476 1.47574 2.55567 + endloop + endfacet + facet normal 0.300736 -0.00935547 0.953662 + outer loop + vertex 1.59475 1.47079 2.55562 + vertex 1.59853 1.47451 2.55447 + vertex 1.59476 1.47574 2.55567 + endloop + endfacet + facet normal 0.30318 -0.00934943 0.952887 + outer loop + vertex 1.59476 1.47574 2.55567 + vertex 1.59097 1.472 2.55684 + vertex 1.59475 1.47079 2.55562 + endloop + endfacet + facet normal 0.302518 -0.00861202 0.953105 + outer loop + vertex 1.59097 1.47696 2.55688 + vertex 1.59097 1.472 2.55684 + vertex 1.59476 1.47574 2.55567 + endloop + endfacet + facet normal 0.30199 -0.010756 0.95325 + outer loop + vertex 1.59852 1.46956 2.55441 + vertex 1.59853 1.47451 2.55447 + vertex 1.59475 1.47079 2.55562 + endloop + endfacet + facet normal 0.30119 -0.0134194 0.95347 + outer loop + vertex 1.59473 1.46583 2.55556 + vertex 1.59852 1.46956 2.55441 + vertex 1.59475 1.47079 2.55562 + endloop + endfacet + facet normal 0.303339 -0.0134218 0.952788 + outer loop + vertex 1.59475 1.47079 2.55562 + vertex 1.59093 1.46699 2.55679 + vertex 1.59473 1.46583 2.55556 + endloop + endfacet + facet normal 0.302531 -0.0162883 0.953 + outer loop + vertex 1.59093 1.46699 2.55679 + vertex 1.59086 1.46191 2.55672 + vertex 1.59473 1.46583 2.55556 + endloop + endfacet + facet normal 0.302987 -0.0167854 0.952847 + outer loop + vertex 1.59473 1.46583 2.55556 + vertex 1.59086 1.46191 2.55672 + vertex 1.59467 1.46084 2.55549 + endloop + endfacet + facet normal 0.301137 -0.0167723 0.953433 + outer loop + vertex 1.59467 1.46084 2.55549 + vertex 1.59849 1.46461 2.55435 + vertex 1.59473 1.46583 2.55556 + endloop + endfacet + facet normal 0.300784 -0.0163786 0.953552 + outer loop + vertex 1.59841 1.45961 2.55429 + vertex 1.59849 1.46461 2.55435 + vertex 1.59467 1.46084 2.55549 + endloop + endfacet + facet normal 0.300195 -0.0183258 0.953702 + outer loop + vertex 1.59454 1.45584 2.55543 + vertex 1.59841 1.45961 2.55429 + vertex 1.59467 1.46084 2.55549 + endloop + endfacet + facet normal 0.302081 -0.0183683 0.953105 + outer loop + vertex 1.59467 1.46084 2.55549 + vertex 1.59079 1.45686 2.55664 + vertex 1.59454 1.45584 2.55543 + endloop + endfacet + facet normal 0.301821 -0.0194077 0.953167 + outer loop + vertex 1.59079 1.45686 2.55664 + vertex 1.59072 1.45194 2.55657 + vertex 1.59454 1.45584 2.55543 + endloop + endfacet + facet normal 0.301612 -0.0191831 0.953238 + outer loop + vertex 1.59454 1.45584 2.55543 + vertex 1.59072 1.45194 2.55657 + vertex 1.59425 1.45097 2.55543 + endloop + endfacet + facet normal 0.29934 -0.0190455 0.953956 + outer loop + vertex 1.59425 1.45097 2.55543 + vertex 1.59818 1.45447 2.55427 + vertex 1.59454 1.45584 2.55543 + endloop + endfacet + facet normal 0.300028 -0.0198938 0.953723 + outer loop + vertex 1.59747 1.44871 2.55437 + vertex 1.59818 1.45447 2.55427 + vertex 1.59425 1.45097 2.55543 + endloop + endfacet + facet normal 0.299485 -0.0207431 0.953876 + outer loop + vertex 1.59362 1.44708 2.55554 + vertex 1.59747 1.44871 2.55437 + vertex 1.59425 1.45097 2.55543 + endloop + endfacet + facet normal 0.301862 -0.0211465 0.953117 + outer loop + vertex 1.59425 1.45097 2.55543 + vertex 1.59074 1.44745 2.55646 + vertex 1.59362 1.44708 2.55554 + endloop + endfacet + facet normal 0.300836 -0.024303 0.953366 + outer loop + vertex 1.59362 1.44708 2.55554 + vertex 1.59422 1.44387 2.55527 + vertex 1.59747 1.44871 2.55437 + endloop + endfacet + facet normal 0.29933 -0.0231964 0.953868 + outer loop + vertex 1.59747 1.44871 2.55437 + vertex 1.59422 1.44387 2.55527 + vertex 1.59796 1.44347 2.55409 + endloop + endfacet + facet normal 0.299646 -0.0231616 0.953769 + outer loop + vertex 1.59796 1.44347 2.55409 + vertex 1.60188 1.44784 2.55296 + vertex 1.59747 1.44871 2.55437 + endloop + endfacet + facet normal 0.300261 -0.0198658 0.95365 + outer loop + vertex 1.60188 1.44784 2.55296 + vertex 1.60197 1.4531 2.55304 + vertex 1.59747 1.44871 2.55437 + endloop + endfacet + facet normal 0.301765 -0.0198827 0.953175 + outer loop + vertex 1.60188 1.44784 2.55296 + vertex 1.60589 1.45198 2.55178 + vertex 1.60197 1.4531 2.55304 + endloop + endfacet + facet normal 0.302602 -0.0167191 0.952971 + outer loop + vertex 1.60589 1.45198 2.55178 + vertex 1.60596 1.45705 2.55185 + vertex 1.60197 1.4531 2.55304 + endloop + endfacet + facet normal 0.303266 -0.0174584 0.952746 + outer loop + vertex 1.60197 1.4531 2.55304 + vertex 1.60596 1.45705 2.55185 + vertex 1.60216 1.4583 2.55308 + endloop + endfacet + facet normal 0.301172 -0.0173849 0.953411 + outer loop + vertex 1.60197 1.4531 2.55304 + vertex 1.60216 1.4583 2.55308 + vertex 1.59818 1.45447 2.55427 + endloop + endfacet + facet normal 0.301638 -0.0179193 0.953254 + outer loop + vertex 1.59818 1.45447 2.55427 + vertex 1.60216 1.4583 2.55308 + vertex 1.59841 1.45961 2.55429 + endloop + endfacet + facet normal 0.302338 -0.0157473 0.953071 + outer loop + vertex 1.60216 1.4583 2.55308 + vertex 1.60225 1.46333 2.55313 + vertex 1.59841 1.45961 2.55429 + endloop + endfacet + facet normal 0.304848 -0.0157806 0.95227 + outer loop + vertex 1.60216 1.4583 2.55308 + vertex 1.60601 1.46206 2.55191 + vertex 1.60225 1.46333 2.55313 + endloop + endfacet + facet normal 0.305623 -0.0132856 0.95206 + outer loop + vertex 1.60601 1.46206 2.55191 + vertex 1.60604 1.46703 2.55197 + vertex 1.60225 1.46333 2.55313 + endloop + endfacet + facet normal 0.306201 -0.0139411 0.951865 + outer loop + vertex 1.60225 1.46333 2.55313 + vertex 1.60604 1.46703 2.55197 + vertex 1.60228 1.4683 2.5532 + endloop + endfacet + facet normal 0.303688 -0.0139347 0.95267 + outer loop + vertex 1.60225 1.46333 2.55313 + vertex 1.60228 1.4683 2.5532 + vertex 1.59849 1.46461 2.55435 + endloop + endfacet + facet normal 0.303937 -0.0142167 0.952586 + outer loop + vertex 1.59849 1.46461 2.55435 + vertex 1.60228 1.4683 2.5532 + vertex 1.59852 1.46956 2.55441 + endloop + endfacet + facet normal 0.304716 -0.0117007 0.952371 + outer loop + vertex 1.60228 1.4683 2.5532 + vertex 1.6023 1.47326 2.55325 + vertex 1.59852 1.46956 2.55441 + endloop + endfacet + facet normal 0.307202 -0.011704 0.951572 + outer loop + vertex 1.60228 1.4683 2.5532 + vertex 1.60607 1.47199 2.55202 + vertex 1.6023 1.47326 2.55325 + endloop + endfacet + facet normal 0.307867 -0.00953505 0.951382 + outer loop + vertex 1.60607 1.47199 2.55202 + vertex 1.6061 1.47698 2.55206 + vertex 1.6023 1.47326 2.55325 + endloop + endfacet + facet normal 0.307199 -0.00878174 0.951605 + outer loop + vertex 1.6023 1.47326 2.55325 + vertex 1.6061 1.47698 2.55206 + vertex 1.60233 1.47824 2.55329 + endloop + endfacet + facet normal 0.306973 -0.0114446 0.951649 + outer loop + vertex 1.60604 1.46703 2.55197 + vertex 1.60607 1.47199 2.55202 + vertex 1.60228 1.4683 2.5532 + endloop + endfacet + facet normal 0.304052 -0.0148795 0.952539 + outer loop + vertex 1.60596 1.45705 2.55185 + vertex 1.60601 1.46206 2.55191 + vertex 1.60216 1.4583 2.55308 + endloop + endfacet + facet normal 0.29916 -0.0226832 0.953933 + outer loop + vertex 1.60193 1.44273 2.55283 + vertex 1.60188 1.44784 2.55296 + vertex 1.59796 1.44347 2.55409 + endloop + endfacet + facet normal 0.298459 -0.026618 0.954051 + outer loop + vertex 1.59802 1.43847 2.55393 + vertex 1.60193 1.44273 2.55283 + vertex 1.59796 1.44347 2.55409 + endloop + endfacet + facet normal 0.298153 -0.0266243 0.954147 + outer loop + vertex 1.59802 1.43847 2.55393 + vertex 1.59796 1.44347 2.55409 + vertex 1.5942 1.43932 2.55515 + endloop + endfacet + facet normal 0.297376 -0.0303038 0.95428 + outer loop + vertex 1.59409 1.43444 2.55503 + vertex 1.59802 1.43847 2.55393 + vertex 1.5942 1.43932 2.55515 + endloop + endfacet + facet normal 0.296841 -0.0297332 0.954464 + outer loop + vertex 1.59804 1.43346 2.55377 + vertex 1.59802 1.43847 2.55393 + vertex 1.59409 1.43444 2.55503 + endloop + endfacet + facet normal 0.296633 -0.0297361 0.954528 + outer loop + vertex 1.59804 1.43346 2.55377 + vertex 1.60199 1.43775 2.55267 + vertex 1.59802 1.43847 2.55393 + endloop + endfacet + facet normal 0.296253 -0.0293514 0.954659 + outer loop + vertex 1.60245 1.43262 2.55237 + vertex 1.60199 1.43775 2.55267 + vertex 1.59804 1.43346 2.55377 + endloop + endfacet + facet normal 0.295703 -0.0323482 0.954732 + outer loop + vertex 1.5979 1.42836 2.55364 + vertex 1.60245 1.43262 2.55237 + vertex 1.59804 1.43346 2.55377 + endloop + endfacet + facet normal 0.295818 -0.0323503 0.954696 + outer loop + vertex 1.5979 1.42836 2.55364 + vertex 1.59804 1.43346 2.55377 + vertex 1.59399 1.4295 2.55489 + endloop + endfacet + facet normal 0.29526 -0.034378 0.954798 + outer loop + vertex 1.59388 1.42456 2.55474 + vertex 1.5979 1.42836 2.55364 + vertex 1.59399 1.4295 2.55489 + endloop + endfacet + facet normal 0.295235 -0.0343492 0.954807 + outer loop + vertex 1.59766 1.4233 2.55353 + vertex 1.5979 1.42836 2.55364 + vertex 1.59388 1.42456 2.55474 + endloop + endfacet + facet normal 0.295673 -0.0343673 0.954671 + outer loop + vertex 1.59766 1.4233 2.55353 + vertex 1.60169 1.42701 2.55241 + vertex 1.5979 1.42836 2.55364 + endloop + endfacet + facet normal 0.295986 -0.0347403 0.95456 + outer loop + vertex 1.60141 1.422 2.55232 + vertex 1.60169 1.42701 2.55241 + vertex 1.59766 1.4233 2.55353 + endloop + endfacet + facet normal 0.295714 -0.0355794 0.954614 + outer loop + vertex 1.59753 1.41834 2.55339 + vertex 1.60141 1.422 2.55232 + vertex 1.59766 1.4233 2.55353 + endloop + endfacet + facet normal 0.29525 -0.0355707 0.954758 + outer loop + vertex 1.59753 1.41834 2.55339 + vertex 1.59766 1.4233 2.55353 + vertex 1.59378 1.41963 2.55459 + endloop + endfacet + facet normal 0.295049 -0.036193 0.954796 + outer loop + vertex 1.59365 1.41466 2.55444 + vertex 1.59753 1.41834 2.55339 + vertex 1.59378 1.41963 2.55459 + endloop + endfacet + facet normal 0.296477 -0.0378382 0.95429 + outer loop + vertex 1.59738 1.41333 2.55323 + vertex 1.59753 1.41834 2.55339 + vertex 1.59365 1.41466 2.55444 + endloop + endfacet + facet normal 0.295722 -0.0378232 0.954525 + outer loop + vertex 1.59738 1.41333 2.55323 + vertex 1.60129 1.41708 2.55217 + vertex 1.59753 1.41834 2.55339 + endloop + endfacet + facet normal 0.296235 -0.0384096 0.954343 + outer loop + vertex 1.60118 1.41208 2.552 + vertex 1.60129 1.41708 2.55217 + vertex 1.59738 1.41333 2.55323 + endloop + endfacet + facet normal 0.295405 -0.0410933 0.954488 + outer loop + vertex 1.5971 1.40813 2.55309 + vertex 1.60118 1.41208 2.552 + vertex 1.59738 1.41333 2.55323 + endloop + endfacet + facet normal 0.298458 -0.0412285 0.953532 + outer loop + vertex 1.5971 1.40813 2.55309 + vertex 1.59738 1.41333 2.55323 + vertex 1.59335 1.40953 2.55433 + endloop + endfacet + facet normal 0.298032 -0.0424391 0.953612 + outer loop + vertex 1.59254 1.40382 2.55433 + vertex 1.5971 1.40813 2.55309 + vertex 1.59335 1.40953 2.55433 + endloop + endfacet + facet normal 0.296971 -0.029273 0.954438 + outer loop + vertex 1.60575 1.43741 2.55149 + vertex 1.60199 1.43775 2.55267 + vertex 1.60245 1.43262 2.55237 + endloop + endfacet + facet normal 0.297372 -0.0255214 0.95442 + outer loop + vertex 1.60199 1.43775 2.55267 + vertex 1.60193 1.44273 2.55283 + vertex 1.59802 1.43847 2.55393 + endloop + endfacet + facet normal 0.298489 -0.0254973 0.954072 + outer loop + vertex 1.60199 1.43775 2.55267 + vertex 1.60575 1.44195 2.55161 + vertex 1.60193 1.44273 2.55283 + endloop + endfacet + facet normal 0.299233 -0.0216139 0.953935 + outer loop + vertex 1.60575 1.44195 2.55161 + vertex 1.60583 1.44691 2.5517 + vertex 1.60193 1.44273 2.55283 + endloop + endfacet + facet normal 0.300258 -0.0226642 0.953589 + outer loop + vertex 1.60193 1.44273 2.55283 + vertex 1.60583 1.44691 2.5517 + vertex 1.60188 1.44784 2.55296 + endloop + endfacet + facet normal 0.300318 -0.0199309 0.953631 + outer loop + vertex 1.59747 1.44871 2.55437 + vertex 1.60197 1.4531 2.55304 + vertex 1.59818 1.45447 2.55427 + endloop + endfacet + facet normal 0.301274 -0.0205008 0.953317 + outer loop + vertex 1.59072 1.45194 2.55657 + vertex 1.59074 1.44745 2.55646 + vertex 1.59425 1.45097 2.55543 + endloop + endfacet + facet normal 0.311221 -0.0194933 0.950138 + outer loop + vertex 1.59072 1.45194 2.55657 + vertex 1.59079 1.45686 2.55664 + vertex 1.58689 1.45264 2.55784 + endloop + endfacet + facet normal 0.311107 -0.0201621 0.950161 + outer loop + vertex 1.58697 1.44771 2.5577 + vertex 1.59072 1.45194 2.55657 + vertex 1.58689 1.45264 2.55784 + endloop + endfacet + facet normal 0.299761 -0.0178356 0.953848 + outer loop + vertex 1.59818 1.45447 2.55427 + vertex 1.59841 1.45961 2.55429 + vertex 1.59454 1.45584 2.55543 + endloop + endfacet + facet normal 0.302916 -0.0164039 0.952876 + outer loop + vertex 1.59841 1.45961 2.55429 + vertex 1.60225 1.46333 2.55313 + vertex 1.59849 1.46461 2.55435 + endloop + endfacet + facet normal 0.302466 -0.0187819 0.952975 + outer loop + vertex 1.59086 1.46191 2.55672 + vertex 1.59079 1.45686 2.55664 + vertex 1.59467 1.46084 2.55549 + endloop + endfacet + facet normal 0.312397 -0.0188666 0.949764 + outer loop + vertex 1.59079 1.45686 2.55664 + vertex 1.59086 1.46191 2.55672 + vertex 1.58684 1.45772 2.55796 + endloop + endfacet + facet normal 0.301902 -0.0142135 0.953233 + outer loop + vertex 1.59849 1.46461 2.55435 + vertex 1.59852 1.46956 2.55441 + vertex 1.59473 1.46583 2.55556 + endloop + endfacet + facet normal 0.303878 -0.010755 0.95265 + outer loop + vertex 1.59852 1.46956 2.55441 + vertex 1.6023 1.47326 2.55325 + vertex 1.59853 1.47451 2.55447 + endloop + endfacet + facet normal 0.300456 -0.00645092 0.953774 + outer loop + vertex 1.59476 1.47574 2.55567 + vertex 1.59854 1.47948 2.5545 + vertex 1.59476 1.48071 2.5557 + endloop + endfacet + facet normal 0.304483 -0.00877523 0.952478 + outer loop + vertex 1.6023 1.47326 2.55325 + vertex 1.60233 1.47824 2.55329 + vertex 1.59853 1.47451 2.55447 + endloop + endfacet + facet normal 0.306611 -0.00658505 0.951812 + outer loop + vertex 1.60233 1.47824 2.55329 + vertex 1.60613 1.48198 2.55209 + vertex 1.60235 1.48323 2.55332 + endloop + endfacet + facet normal 0.306854 -0.00577857 0.951739 + outer loop + vertex 1.60613 1.48198 2.55209 + vertex 1.60616 1.48698 2.55211 + vertex 1.60235 1.48323 2.55332 + endloop + endfacet + facet normal 0.314512 -0.00409032 0.949245 + outer loop + vertex 1.61369 1.48948 2.54965 + vertex 1.6137 1.49447 2.54966 + vertex 1.60995 1.49073 2.55089 + endloop + endfacet + facet normal 0.317297 -0.00525702 0.948312 + outer loop + vertex 1.61366 1.48448 2.54963 + vertex 1.61741 1.48823 2.5484 + vertex 1.61369 1.48948 2.54965 + endloop + endfacet + facet normal 0.310407 -0.00579093 0.950586 + outer loop + vertex 1.60616 1.48698 2.55211 + vertex 1.60613 1.48198 2.55209 + vertex 1.60993 1.48573 2.55087 + endloop + endfacet + facet normal 0.307547 -0.00763615 0.951502 + outer loop + vertex 1.6061 1.47698 2.55206 + vertex 1.60613 1.48198 2.55209 + vertex 1.60233 1.47824 2.55329 + endloop + endfacet + facet normal 0.314052 -0.00646063 0.949384 + outer loop + vertex 1.61363 1.47948 2.5496 + vertex 1.61366 1.48448 2.54963 + vertex 1.6099 1.48073 2.55085 + endloop + endfacet + facet normal 0.315963 -0.00741744 0.948743 + outer loop + vertex 1.6136 1.47448 2.54958 + vertex 1.61735 1.47824 2.54835 + vertex 1.61363 1.47948 2.5496 + endloop + endfacet + facet normal 0.310155 -0.00954427 0.950638 + outer loop + vertex 1.6061 1.47698 2.55206 + vertex 1.60607 1.47199 2.55202 + vertex 1.60986 1.47573 2.55082 + endloop + endfacet + facet normal 0.31215 -0.0087715 0.949992 + outer loop + vertex 1.61356 1.46949 2.54954 + vertex 1.6136 1.47448 2.54958 + vertex 1.60982 1.47074 2.55078 + endloop + endfacet + facet normal 0.313575 -0.0104254 0.949506 + outer loop + vertex 1.61353 1.46452 2.5495 + vertex 1.61729 1.46824 2.5483 + vertex 1.61356 1.46949 2.54954 + endloop + endfacet + facet normal 0.308114 -0.0132903 0.951257 + outer loop + vertex 1.60604 1.46703 2.55197 + vertex 1.60601 1.46206 2.55191 + vertex 1.6098 1.46577 2.55073 + endloop + endfacet + facet normal 0.31013 -0.0120871 0.950617 + outer loop + vertex 1.61351 1.45957 2.54944 + vertex 1.61353 1.46452 2.5495 + vertex 1.60977 1.46081 2.55068 + endloop + endfacet + facet normal 0.312227 -0.0135248 0.949911 + outer loop + vertex 1.61348 1.45462 2.54938 + vertex 1.61723 1.45831 2.5482 + vertex 1.61351 1.45957 2.54944 + endloop + endfacet + facet normal 0.305289 -0.0167431 0.952113 + outer loop + vertex 1.60596 1.45705 2.55185 + vertex 1.60589 1.45198 2.55178 + vertex 1.60974 1.45585 2.55061 + endloop + endfacet + facet normal 0.301043 -0.0191137 0.953419 + outer loop + vertex 1.60583 1.44691 2.5517 + vertex 1.60589 1.45198 2.55178 + vertex 1.60188 1.44784 2.55296 + endloop + endfacet + facet normal 0.307213 -0.0150578 0.951522 + outer loop + vertex 1.6134 1.44961 2.54933 + vertex 1.61348 1.45462 2.54938 + vertex 1.60969 1.45085 2.55054 + endloop + endfacet + facet normal 0.308489 -0.0176975 0.951063 + outer loop + vertex 1.61316 1.44445 2.54931 + vertex 1.61712 1.4483 2.5481 + vertex 1.6134 1.44961 2.54933 + endloop + endfacet + facet normal 0.301736 -0.0216386 0.953146 + outer loop + vertex 1.60583 1.44691 2.5517 + vertex 1.60575 1.44195 2.55161 + vertex 1.60956 1.44584 2.55049 + endloop + endfacet + facet normal 0.2974 -0.0244289 0.95444 + outer loop + vertex 1.60575 1.43741 2.55149 + vertex 1.60575 1.44195 2.55161 + vertex 1.60199 1.43775 2.55267 + endloop + endfacet + facet normal 0.305763 -0.0224228 0.951844 + outer loop + vertex 1.61245 1.43867 2.5494 + vertex 1.61316 1.44445 2.54931 + vertex 1.60925 1.44092 2.55048 + endloop + endfacet + facet normal 0.304991 -0.0283416 0.951933 + outer loop + vertex 1.61245 1.43867 2.5494 + vertex 1.60919 1.43382 2.5503 + vertex 1.61294 1.43347 2.54909 + endloop + endfacet + facet normal 0.29864 -0.0275439 0.953968 + outer loop + vertex 1.60861 1.43701 2.55059 + vertex 1.60575 1.43741 2.55149 + vertex 1.60633 1.43423 2.55122 + endloop + endfacet + facet normal 0.295527 -0.0281939 0.954918 + outer loop + vertex 1.60633 1.43423 2.55122 + vertex 1.60575 1.43741 2.55149 + vertex 1.60245 1.43262 2.55237 + endloop + endfacet + facet normal 0.296166 -0.0328921 0.95457 + outer loop + vertex 1.60169 1.42701 2.55241 + vertex 1.60245 1.43262 2.55237 + vertex 1.5979 1.42836 2.55364 + endloop + endfacet + facet normal 0.301187 -0.0330644 0.952992 + outer loop + vertex 1.60916 1.42932 2.55015 + vertex 1.60919 1.43382 2.5503 + vertex 1.60566 1.43039 2.5513 + endloop + endfacet + facet normal 0.303908 -0.0343505 0.952082 + outer loop + vertex 1.60904 1.42448 2.55002 + vertex 1.61305 1.42849 2.54888 + vertex 1.60916 1.42932 2.55015 + endloop + endfacet + facet normal 0.297629 -0.0348233 0.954046 + outer loop + vertex 1.60169 1.42701 2.55241 + vertex 1.60141 1.422 2.55232 + vertex 1.60531 1.42562 2.55123 + endloop + endfacet + facet normal 0.296239 -0.0361906 0.954428 + outer loop + vertex 1.60129 1.41708 2.55217 + vertex 1.60141 1.422 2.55232 + vertex 1.59753 1.41834 2.55339 + endloop + endfacet + facet normal 0.299799 -0.0345026 0.953378 + outer loop + vertex 1.60892 1.41956 2.54988 + vertex 1.60904 1.42448 2.55002 + vertex 1.60515 1.42075 2.55111 + endloop + endfacet + facet normal 0.301643 -0.0360263 0.95274 + outer loop + vertex 1.60882 1.41463 2.54972 + vertex 1.61269 1.41834 2.54864 + vertex 1.60892 1.41956 2.54988 + endloop + endfacet + facet normal 0.29652 -0.0384131 0.954254 + outer loop + vertex 1.60129 1.41708 2.55217 + vertex 1.60118 1.41208 2.552 + vertex 1.60506 1.41585 2.55095 + endloop + endfacet + facet normal 0.296494 -0.0423234 0.954097 + outer loop + vertex 1.60102 1.40704 2.55183 + vertex 1.60118 1.41208 2.552 + vertex 1.5971 1.40813 2.55309 + endloop + endfacet + facet normal 0.295686 -0.0453528 0.954208 + outer loop + vertex 1.59693 1.40293 2.5529 + vertex 1.60102 1.40704 2.55183 + vertex 1.5971 1.40813 2.55309 + endloop + endfacet + facet normal 0.295832 -0.0455119 0.954155 + outer loop + vertex 1.60084 1.40212 2.55165 + vertex 1.60102 1.40704 2.55183 + vertex 1.59693 1.40293 2.5529 + endloop + endfacet + facet normal 0.298524 -0.0390481 0.953603 + outer loop + vertex 1.60868 1.40966 2.54956 + vertex 1.60882 1.41463 2.54972 + vertex 1.60496 1.4109 2.55078 + endloop + endfacet + facet normal 0.300153 -0.042636 0.952938 + outer loop + vertex 1.60836 1.40455 2.54944 + vertex 1.61241 1.40837 2.54833 + vertex 1.60868 1.40966 2.54956 + endloop + endfacet + facet normal 0.296089 -0.044221 0.954136 + outer loop + vertex 1.60752 1.39885 2.54943 + vertex 1.60836 1.40455 2.54944 + vertex 1.60435 1.4011 2.55052 + endloop + endfacet + facet normal 0.295227 -0.0454975 0.954343 + outer loop + vertex 1.60102 1.40704 2.55183 + vertex 1.60084 1.40212 2.55165 + vertex 1.60476 1.40594 2.55062 + endloop + endfacet + facet normal 0.292333 -0.0454461 0.955236 + outer loop + vertex 1.60435 1.4011 2.55052 + vertex 1.60077 1.39766 2.55145 + vertex 1.60363 1.39728 2.55056 + endloop + endfacet + facet normal 0.292076 -0.0473365 0.955223 + outer loop + vertex 1.60363 1.39728 2.55056 + vertex 1.60077 1.39766 2.55145 + vertex 1.6013 1.39454 2.55114 + endloop + endfacet + facet normal 0.291964 -0.0472335 0.955262 + outer loop + vertex 1.60363 1.39728 2.55056 + vertex 1.6013 1.39454 2.55114 + vertex 1.60416 1.3941 2.55024 + endloop + endfacet + facet normal 0.293201 -0.0489753 0.954796 + outer loop + vertex 1.6041 1.38956 2.55002 + vertex 1.60795 1.39364 2.54905 + vertex 1.60416 1.3941 2.55024 + endloop + endfacet + facet normal 0.291043 -0.0516413 0.955315 + outer loop + vertex 1.60389 1.38462 2.54982 + vertex 1.60802 1.38861 2.54878 + vertex 1.6041 1.38956 2.55002 + endloop + endfacet + facet normal 0.290628 -0.0547819 0.955267 + outer loop + vertex 1.59654 1.38715 2.55219 + vertex 1.59615 1.382 2.55201 + vertex 1.60018 1.38582 2.55101 + endloop + endfacet + facet normal 0.299543 -0.0570513 0.952376 + outer loop + vertex 1.59595 1.37707 2.55178 + vertex 1.59615 1.382 2.55201 + vertex 1.59205 1.37788 2.55306 + endloop + endfacet + facet normal 0.28785 -0.0543262 0.956133 + outer loop + vertex 1.60351 1.37948 2.54964 + vertex 1.60389 1.38462 2.54982 + vertex 1.59987 1.38086 2.55082 + endloop + endfacet + facet normal 0.287515 -0.056902 0.956084 + outer loop + vertex 1.60266 1.37378 2.54956 + vertex 1.60734 1.37812 2.54841 + vertex 1.60351 1.37948 2.54964 + endloop + endfacet + facet normal 0.287567 -0.0603084 0.95586 + outer loop + vertex 1.59878 1.3722 2.55063 + vertex 1.59931 1.36902 2.55027 + vertex 1.60266 1.37378 2.54956 + endloop + endfacet + facet normal 0.289525 -0.0584504 0.955384 + outer loop + vertex 1.59595 1.37707 2.55178 + vertex 1.59591 1.3726 2.55152 + vertex 1.59947 1.37603 2.55065 + endloop + endfacet + facet normal 0.29876 -0.0583796 0.952541 + outer loop + vertex 1.59591 1.3726 2.55152 + vertex 1.59595 1.37707 2.55178 + vertex 1.59211 1.3729 2.55273 + endloop + endfacet + facet normal 0.288798 -0.0600636 0.955504 + outer loop + vertex 1.59878 1.3722 2.55063 + vertex 1.59646 1.36945 2.55116 + vertex 1.59931 1.36902 2.55027 + endloop + endfacet + facet normal 0.28664 -0.0637559 0.955915 + outer loop + vertex 1.59915 1.36449 2.55001 + vertex 1.60306 1.36862 2.54912 + vertex 1.59931 1.36902 2.55027 + endloop + endfacet + facet normal 0.295742 -0.0659214 0.952991 + outer loop + vertex 1.59251 1.36778 2.55227 + vertex 1.59158 1.36206 2.55217 + vertex 1.59571 1.3656 2.55113 + endloop + endfacet + facet normal 0.307071 -0.0704994 0.949072 + outer loop + vertex 1.59114 1.35703 2.55194 + vertex 1.59158 1.36206 2.55217 + vertex 1.58719 1.35789 2.55328 + endloop + endfacet + facet normal 0.288968 -0.0672583 0.954973 + outer loop + vertex 1.59873 1.35947 2.54979 + vertex 1.59915 1.36449 2.55001 + vertex 1.59517 1.36077 2.55096 + endloop + endfacet + facet normal 0.296825 -0.0695792 0.952394 + outer loop + vertex 1.59114 1.35703 2.55194 + vertex 1.59099 1.35253 2.55165 + vertex 1.59463 1.35595 2.55077 + endloop + endfacet + facet normal 0.306969 -0.0697158 0.949163 + outer loop + vertex 1.59099 1.35253 2.55165 + vertex 1.59114 1.35703 2.55194 + vertex 1.58713 1.35283 2.55292 + endloop + endfacet + facet normal 0.30728 -0.0662636 0.949309 + outer loop + vertex 1.59099 1.35253 2.55165 + vertex 1.58713 1.35283 2.55292 + vertex 1.58754 1.3477 2.55243 + endloop + endfacet + facet normal 0.308616 -0.067298 0.948803 + outer loop + vertex 1.5915 1.3494 2.55126 + vertex 1.59099 1.35253 2.55165 + vertex 1.58754 1.3477 2.55243 + endloop + endfacet + facet normal 0.299286 -0.0634028 0.952054 + outer loop + vertex 1.5867 1.34204 2.55232 + vertex 1.58754 1.3477 2.55243 + vertex 1.58265 1.34309 2.55366 + endloop + endfacet + facet normal 0.282943 -0.0654829 0.956899 + outer loop + vertex 1.58636 1.33707 2.55208 + vertex 1.5867 1.34204 2.55232 + vertex 1.58226 1.33782 2.55334 + endloop + endfacet + facet normal 0.309315 -0.0713516 0.948279 + outer loop + vertex 1.59353 1.33466 2.54957 + vertex 1.59393 1.33967 2.54982 + vertex 1.58998 1.33604 2.55083 + endloop + endfacet + facet normal 0.301685 -0.0649095 0.951196 + outer loop + vertex 1.59032 1.34084 2.55106 + vertex 1.59418 1.34449 2.55008 + vertex 1.59076 1.34558 2.55124 + endloop + endfacet + facet normal 0.292468 -0.0711173 0.953627 + outer loop + vertex 1.59784 1.33863 2.54854 + vertex 1.59798 1.34362 2.54887 + vertex 1.59393 1.33967 2.54982 + endloop + endfacet + facet normal 0.281973 -0.0695457 0.956898 + outer loop + vertex 1.59798 1.34362 2.54887 + vertex 1.60212 1.34788 2.54796 + vertex 1.59808 1.34856 2.5492 + endloop + endfacet + facet normal 0.287262 -0.068132 0.955426 + outer loop + vertex 1.59385 1.35212 2.55072 + vertex 1.59434 1.34895 2.55035 + vertex 1.5978 1.35376 2.54966 + endloop + endfacet + facet normal 0.28226 -0.0678996 0.956932 + outer loop + vertex 1.60212 1.34788 2.54796 + vertex 1.60238 1.35308 2.54825 + vertex 1.59808 1.34856 2.5492 + endloop + endfacet + facet normal 0.28162 -0.0678783 0.957122 + outer loop + vertex 1.60212 1.34788 2.54796 + vertex 1.60639 1.35216 2.547 + vertex 1.60238 1.35308 2.54825 + endloop + endfacet + facet normal 0.284759 -0.0685848 0.956142 + outer loop + vertex 1.5978 1.35376 2.54966 + vertex 1.60269 1.35846 2.54853 + vertex 1.59873 1.35947 2.54979 + endloop + endfacet + facet normal 0.282256 -0.0651313 0.957126 + outer loop + vertex 1.60639 1.35216 2.547 + vertex 1.60731 1.35792 2.54713 + vertex 1.60238 1.35308 2.54825 + endloop + endfacet + facet normal 0.286058 -0.0664087 0.955908 + outer loop + vertex 1.60269 1.35846 2.54853 + vertex 1.60699 1.36304 2.54757 + vertex 1.60296 1.36364 2.54882 + endloop + endfacet + facet normal 0.291503 -0.0645981 0.954386 + outer loop + vertex 1.61357 1.34962 2.54467 + vertex 1.61401 1.35471 2.54488 + vertex 1.61 1.35098 2.54585 + endloop + endfacet + facet normal 0.2856 -0.0656414 0.956098 + outer loop + vertex 1.60731 1.35792 2.54713 + vertex 1.60639 1.35216 2.547 + vertex 1.61052 1.35585 2.54602 + endloop + endfacet + facet normal 0.279942 -0.0660676 0.957741 + outer loop + vertex 1.606 1.34716 2.54677 + vertex 1.60639 1.35216 2.547 + vertex 1.60212 1.34788 2.54796 + endloop + endfacet + facet normal 0.278251 -0.0681326 0.958089 + outer loop + vertex 1.60587 1.3427 2.54649 + vertex 1.606 1.34716 2.54677 + vertex 1.60202 1.34294 2.54763 + endloop + endfacet + facet normal 0.290941 -0.0661274 0.954453 + outer loop + vertex 1.6095 1.34617 2.54567 + vertex 1.61357 1.34962 2.54467 + vertex 1.61 1.35098 2.54585 + endloop + endfacet + facet normal 0.297497 -0.0644193 0.952547 + outer loop + vertex 1.61735 1.34824 2.5434 + vertex 1.61784 1.35356 2.5436 + vertex 1.61357 1.34962 2.54467 + endloop + endfacet + facet normal 0.298051 -0.0650804 0.952329 + outer loop + vertex 1.61357 1.34962 2.54467 + vertex 1.61784 1.35356 2.5436 + vertex 1.61401 1.35471 2.54488 + endloop + endfacet + facet normal 0.29853 -0.0634435 0.952289 + outer loop + vertex 1.61784 1.35356 2.5436 + vertex 1.61801 1.35877 2.54389 + vertex 1.61401 1.35471 2.54488 + endloop + endfacet + facet normal 0.302272 -0.063503 0.951104 + outer loop + vertex 1.61784 1.35356 2.5436 + vertex 1.6225 1.35786 2.54241 + vertex 1.61801 1.35877 2.54389 + endloop + endfacet + facet normal 0.301182 -0.062203 0.951536 + outer loop + vertex 1.62163 1.35216 2.54231 + vertex 1.6225 1.35786 2.54241 + vertex 1.61784 1.35356 2.5436 + endloop + endfacet + facet normal 0.300317 -0.0646454 0.951646 + outer loop + vertex 1.61735 1.34824 2.5434 + vertex 1.62163 1.35216 2.54231 + vertex 1.61784 1.35356 2.5436 + endloop + endfacet + facet normal 0.298189 -0.0672435 0.952135 + outer loop + vertex 1.61708 1.34305 2.54311 + vertex 1.62121 1.34706 2.5421 + vertex 1.61735 1.34824 2.5434 + endloop + endfacet + facet normal 0.297245 -0.0661751 0.952505 + outer loop + vertex 1.62098 1.34219 2.54184 + vertex 1.62121 1.34706 2.5421 + vertex 1.61708 1.34305 2.54311 + endloop + endfacet + facet normal 0.296316 -0.0703638 0.952495 + outer loop + vertex 1.61706 1.33804 2.54275 + vertex 1.62098 1.34219 2.54184 + vertex 1.61708 1.34305 2.54311 + endloop + endfacet + facet normal 0.294107 -0.0704063 0.953176 + outer loop + vertex 1.61706 1.33804 2.54275 + vertex 1.61708 1.34305 2.54311 + vertex 1.61297 1.3387 2.54406 + endloop + endfacet + facet normal 0.29336 -0.0748488 0.953067 + outer loop + vertex 1.6128 1.33349 2.5437 + vertex 1.61706 1.33804 2.54275 + vertex 1.61297 1.3387 2.54406 + endloop + endfacet + facet normal 0.292113 -0.0735794 0.953549 + outer loop + vertex 1.6174 1.33288 2.54224 + vertex 1.61706 1.33804 2.54275 + vertex 1.6128 1.33349 2.5437 + endloop + endfacet + facet normal 0.294417 -0.0733587 0.952857 + outer loop + vertex 1.62089 1.33774 2.54154 + vertex 1.61706 1.33804 2.54275 + vertex 1.6174 1.33288 2.54224 + endloop + endfacet + facet normal 0.291148 -0.0708468 0.954051 + outer loop + vertex 1.62139 1.3346 2.54116 + vertex 1.62089 1.33774 2.54154 + vertex 1.6174 1.33288 2.54224 + endloop + endfacet + facet normal 0.292526 -0.0744742 0.953353 + outer loop + vertex 1.62139 1.3346 2.54116 + vertex 1.6174 1.33288 2.54224 + vertex 1.62054 1.33072 2.54112 + endloop + endfacet + facet normal 0.294208 -0.0748374 0.952807 + outer loop + vertex 1.6242 1.33412 2.54025 + vertex 1.62139 1.3346 2.54116 + vertex 1.62054 1.33072 2.54112 + endloop + endfacet + facet normal 0.294844 -0.075589 0.952551 + outer loop + vertex 1.62386 1.32945 2.53999 + vertex 1.6242 1.33412 2.54025 + vertex 1.62054 1.33072 2.54112 + endloop + endfacet + facet normal 0.290135 -0.0781836 0.953787 + outer loop + vertex 1.6174 1.33288 2.54224 + vertex 1.61646 1.32722 2.54207 + vertex 1.62054 1.33072 2.54112 + endloop + endfacet + facet normal 0.291949 -0.0804989 0.95304 + outer loop + vertex 1.62054 1.33072 2.54112 + vertex 1.61646 1.32722 2.54207 + vertex 1.61981 1.326 2.54094 + endloop + endfacet + facet normal 0.290698 -0.0782727 0.953608 + outer loop + vertex 1.61646 1.32722 2.54207 + vertex 1.6174 1.33288 2.54224 + vertex 1.61249 1.32813 2.54335 + endloop + endfacet + facet normal 0.288781 -0.0864726 0.953482 + outer loop + vertex 1.61226 1.32293 2.54295 + vertex 1.61646 1.32722 2.54207 + vertex 1.61249 1.32813 2.54335 + endloop + endfacet + facet normal 0.289077 -0.0867852 0.953364 + outer loop + vertex 1.6161 1.32259 2.54176 + vertex 1.61646 1.32722 2.54207 + vertex 1.61226 1.32293 2.54295 + endloop + endfacet + facet normal 0.288069 -0.0962287 0.952762 + outer loop + vertex 1.6161 1.32259 2.54176 + vertex 1.61226 1.32293 2.54295 + vertex 1.61249 1.31774 2.54236 + endloop + endfacet + facet normal 0.28827 -0.0962131 0.952703 + outer loop + vertex 1.61249 1.31774 2.54236 + vertex 1.61226 1.32293 2.54295 + vertex 1.60787 1.31836 2.54382 + endloop + endfacet + facet normal 0.291602 -0.0723755 0.953798 + outer loop + vertex 1.60876 1.34235 2.54562 + vertex 1.60922 1.33914 2.54524 + vertex 1.61266 1.34393 2.54455 + endloop + endfacet + facet normal 0.284599 -0.0736175 0.955816 + outer loop + vertex 1.60876 1.34235 2.54562 + vertex 1.60638 1.33958 2.54611 + vertex 1.60922 1.33914 2.54524 + endloop + endfacet + facet normal 0.277185 -0.0711301 0.95818 + outer loop + vertex 1.60638 1.33958 2.54611 + vertex 1.60587 1.3427 2.54649 + vertex 1.60237 1.33786 2.54715 + endloop + endfacet + facet normal 0.283846 -0.0753016 0.955909 + outer loop + vertex 1.60141 1.33221 2.54699 + vertex 1.60237 1.33786 2.54715 + vertex 1.59747 1.33336 2.54825 + endloop + endfacet + facet normal 0.283274 -0.0761946 0.956007 + outer loop + vertex 1.6048 1.33093 2.5459 + vertex 1.60887 1.33444 2.54497 + vertex 1.60552 1.33569 2.54606 + endloop + endfacet + facet normal 0.289492 -0.0748008 0.954253 + outer loop + vertex 1.6128 1.33349 2.5437 + vertex 1.61297 1.3387 2.54406 + vertex 1.60887 1.33444 2.54497 + endloop + endfacet + facet normal 0.291331 -0.0789848 0.953356 + outer loop + vertex 1.61249 1.32813 2.54335 + vertex 1.6174 1.33288 2.54224 + vertex 1.6128 1.33349 2.5437 + endloop + endfacet + facet normal 0.2893 -0.0864836 0.953324 + outer loop + vertex 1.61226 1.32293 2.54295 + vertex 1.61249 1.32813 2.54335 + vertex 1.60812 1.32353 2.54426 + endloop + endfacet + facet normal 0.286502 -0.0845214 0.954344 + outer loop + vertex 1.60394 1.32706 2.54583 + vertex 1.60435 1.32389 2.54543 + vertex 1.6079 1.32876 2.54479 + endloop + endfacet + facet normal 0.287814 -0.0957396 0.952889 + outer loop + vertex 1.60787 1.31836 2.54382 + vertex 1.61226 1.32293 2.54295 + vertex 1.60812 1.32353 2.54426 + endloop + endfacet + facet normal 0.287257 -0.102855 0.952315 + outer loop + vertex 1.60752 1.31306 2.54335 + vertex 1.61249 1.31774 2.54236 + vertex 1.60787 1.31836 2.54382 + endloop + endfacet + facet normal 0.286108 -0.101532 0.952803 + outer loop + vertex 1.61148 1.31215 2.54206 + vertex 1.61249 1.31774 2.54236 + vertex 1.60752 1.31306 2.54335 + endloop + endfacet + facet normal 0.28548 -0.104127 0.952711 + outer loop + vertex 1.60726 1.30791 2.54287 + vertex 1.61148 1.31215 2.54206 + vertex 1.60752 1.31306 2.54335 + endloop + endfacet + facet normal 0.278951 -0.099037 0.955185 + outer loop + vertex 1.61058 1.30065 2.54113 + vertex 1.60644 1.2972 2.54198 + vertex 1.60979 1.29603 2.54088 + endloop + endfacet + facet normal 0.278404 -0.10059 0.955182 + outer loop + vertex 1.60644 1.2972 2.54198 + vertex 1.60604 1.29268 2.54162 + vertex 1.60979 1.29603 2.54088 + endloop + endfacet + facet normal 0.277756 -0.102418 0.955176 + outer loop + vertex 1.60888 1.29228 2.54075 + vertex 1.60604 1.29268 2.54162 + vertex 1.60643 1.28959 2.54117 + endloop + endfacet + facet normal 0.27839 -0.103033 0.954926 + outer loop + vertex 1.60888 1.29228 2.54075 + vertex 1.60643 1.28959 2.54117 + vertex 1.60925 1.28914 2.5403 + endloop + endfacet + facet normal 0.279601 -0.104476 0.954415 + outer loop + vertex 1.60882 1.28456 2.53993 + vertex 1.61305 1.28871 2.53914 + vertex 1.60925 1.28914 2.5403 + endloop + endfacet + facet normal 0.280273 -0.104532 0.954212 + outer loop + vertex 1.60241 1.28789 2.54217 + vertex 1.60139 1.28238 2.54186 + vertex 1.60551 1.28581 2.54103 + endloop + endfacet + facet normal 0.290009 -0.106163 0.951117 + outer loop + vertex 1.60139 1.28238 2.54186 + vertex 1.60241 1.28789 2.54217 + vertex 1.59743 1.28326 2.54317 + endloop + endfacet + facet normal 0.2905 -0.104062 0.9512 + outer loop + vertex 1.59718 1.27815 2.54269 + vertex 1.60139 1.28238 2.54186 + vertex 1.59743 1.28326 2.54317 + endloop + endfacet + facet normal 0.292523 -0.10624 0.950339 + outer loop + vertex 1.60097 1.27786 2.54149 + vertex 1.60139 1.28238 2.54186 + vertex 1.59718 1.27815 2.54269 + endloop + endfacet + facet normal 0.29271 -0.104384 0.950486 + outer loop + vertex 1.60097 1.27786 2.54149 + vertex 1.59718 1.27815 2.54269 + vertex 1.59737 1.27307 2.54207 + endloop + endfacet + facet normal 0.303377 -0.103577 0.947224 + outer loop + vertex 1.59737 1.27307 2.54207 + vertex 1.59718 1.27815 2.54269 + vertex 1.59278 1.27353 2.54359 + endloop + endfacet + facet normal 0.301286 -0.101412 0.948126 + outer loop + vertex 1.59278 1.27353 2.54359 + vertex 1.59718 1.27815 2.54269 + vertex 1.59303 1.27874 2.54407 + endloop + endfacet + facet normal 0.278731 -0.106801 0.954412 + outer loop + vertex 1.60773 1.27894 2.53962 + vertex 1.60882 1.28456 2.53993 + vertex 1.60471 1.28119 2.54075 + endloop + endfacet + facet normal 0.278779 -0.108934 0.954157 + outer loop + vertex 1.60773 1.27894 2.53962 + vertex 1.60394 1.27407 2.54017 + vertex 1.60778 1.27355 2.53899 + endloop + endfacet + facet normal 0.284414 -0.108699 0.952519 + outer loop + vertex 1.60374 1.27739 2.54061 + vertex 1.60097 1.27786 2.54149 + vertex 1.60127 1.27471 2.54104 + endloop + endfacet + facet normal 0.296135 -0.107122 0.94912 + outer loop + vertex 1.60127 1.27471 2.54104 + vertex 1.60097 1.27786 2.54149 + vertex 1.59737 1.27307 2.54207 + endloop + endfacet + facet normal 0.305635 -0.10805 0.945998 + outer loop + vertex 1.59646 1.26784 2.54177 + vertex 1.59737 1.27307 2.54207 + vertex 1.59251 1.26819 2.54308 + endloop + endfacet + facet normal 0.305339 -0.110615 0.945797 + outer loop + vertex 1.59646 1.26784 2.54177 + vertex 1.59251 1.26819 2.54308 + vertex 1.59269 1.26288 2.5424 + endloop + endfacet + facet normal 0.287551 -0.111041 0.951307 + outer loop + vertex 1.60299 1.2688 2.53984 + vertex 1.60394 1.27407 2.54017 + vertex 1.60019 1.27097 2.54094 + endloop + endfacet + facet normal 0.290532 -0.110515 0.950462 + outer loop + vertex 1.60299 1.2688 2.53984 + vertex 1.59939 1.26405 2.54039 + vertex 1.60315 1.26365 2.53919 + endloop + endfacet + facet normal 0.305595 -0.109741 0.945816 + outer loop + vertex 1.59912 1.26724 2.54084 + vertex 1.59646 1.26784 2.54177 + vertex 1.59669 1.26457 2.54131 + endloop + endfacet + facet normal 0.304426 -0.109871 0.946178 + outer loop + vertex 1.59669 1.26457 2.54131 + vertex 1.59646 1.26784 2.54177 + vertex 1.59269 1.26288 2.5424 + endloop + endfacet + facet normal 0.264084 -0.107811 0.958455 + outer loop + vertex 1.59163 1.25737 2.54208 + vertex 1.59269 1.26288 2.5424 + vertex 1.58754 1.25799 2.54327 + endloop + endfacet + facet normal 0.305939 -0.110948 0.945564 + outer loop + vertex 1.59894 1.2595 2.54 + vertex 1.59939 1.26405 2.54039 + vertex 1.59572 1.26078 2.54119 + endloop + endfacet + facet normal 0.292953 -0.114173 0.949285 + outer loop + vertex 1.59784 1.25395 2.53967 + vertex 1.60285 1.25851 2.53867 + vertex 1.59894 1.2595 2.54 + endloop + endfacet + facet normal 0.3064 -0.12353 0.943854 + outer loop + vertex 1.5939 1.25247 2.54076 + vertex 1.59405 1.24913 2.54027 + vertex 1.59784 1.25395 2.53967 + endloop + endfacet + facet normal 0.295945 -0.120417 0.947585 + outer loop + vertex 1.59163 1.25737 2.54208 + vertex 1.59115 1.2529 2.54166 + vertex 1.59489 1.25621 2.54091 + endloop + endfacet + facet normal 0.251796 -0.116932 0.96069 + outer loop + vertex 1.59115 1.2529 2.54166 + vertex 1.59163 1.25737 2.54208 + vertex 1.58723 1.25297 2.54269 + endloop + endfacet + facet normal 0.295364 -0.124507 0.947237 + outer loop + vertex 1.5939 1.25247 2.54076 + vertex 1.5914 1.24978 2.54118 + vertex 1.59405 1.24913 2.54027 + endloop + endfacet + facet normal 0.301195 -0.119164 0.946087 + outer loop + vertex 1.59784 1.25395 2.53967 + vertex 1.59405 1.24913 2.54027 + vertex 1.59784 1.24861 2.539 + endloop + endfacet + facet normal 0.293633 -0.118103 0.948595 + outer loop + vertex 1.59763 1.24342 2.53842 + vertex 1.60211 1.24817 2.53762 + vertex 1.59784 1.24861 2.539 + endloop + endfacet + facet normal 0.294905 -0.119396 0.948038 + outer loop + vertex 1.60229 1.24321 2.53694 + vertex 1.60211 1.24817 2.53762 + vertex 1.59763 1.24342 2.53842 + endloop + endfacet + facet normal 0.284638 -0.120176 0.951073 + outer loop + vertex 1.60593 1.24798 2.53646 + vertex 1.60211 1.24817 2.53762 + vertex 1.60229 1.24321 2.53694 + endloop + endfacet + facet normal 0.286821 -0.121936 0.950192 + outer loop + vertex 1.60622 1.24493 2.53598 + vertex 1.60593 1.24798 2.53646 + vertex 1.60229 1.24321 2.53694 + endloop + endfacet + facet normal 0.288437 -0.126227 0.949142 + outer loop + vertex 1.60622 1.24493 2.53598 + vertex 1.60229 1.24321 2.53694 + vertex 1.60511 1.24121 2.53582 + endloop + endfacet + facet normal 0.281015 -0.124116 0.951644 + outer loop + vertex 1.60891 1.24425 2.53509 + vertex 1.60622 1.24493 2.53598 + vertex 1.60511 1.24121 2.53582 + endloop + endfacet + facet normal 0.28357 -0.127605 0.950424 + outer loop + vertex 1.60787 1.23895 2.53469 + vertex 1.60891 1.24425 2.53509 + vertex 1.60511 1.24121 2.53582 + endloop + endfacet + facet normal 0.284414 -0.126519 0.950316 + outer loop + vertex 1.60395 1.23748 2.53567 + vertex 1.60787 1.23895 2.53469 + vertex 1.60511 1.24121 2.53582 + endloop + endfacet + facet normal 0.294638 -0.129532 0.946789 + outer loop + vertex 1.60511 1.24121 2.53582 + vertex 1.60131 1.23807 2.53657 + vertex 1.60395 1.23748 2.53567 + endloop + endfacet + facet normal 0.285547 -0.130072 0.949497 + outer loop + vertex 1.60395 1.23748 2.53567 + vertex 1.60404 1.23415 2.53519 + vertex 1.60787 1.23895 2.53469 + endloop + endfacet + facet normal 0.286349 -0.130747 0.949163 + outer loop + vertex 1.60787 1.23895 2.53469 + vertex 1.60404 1.23415 2.53519 + vertex 1.60784 1.23363 2.53397 + endloop + endfacet + facet normal 0.279486 -0.130976 0.951175 + outer loop + vertex 1.60784 1.23363 2.53397 + vertex 1.61246 1.23826 2.53325 + vertex 1.60787 1.23895 2.53469 + endloop + endfacet + facet normal 0.280038 -0.127872 0.951435 + outer loop + vertex 1.61246 1.23826 2.53325 + vertex 1.61283 1.24359 2.53386 + vertex 1.60787 1.23895 2.53469 + endloop + endfacet + facet normal 0.279061 -0.127837 0.951726 + outer loop + vertex 1.61246 1.23826 2.53325 + vertex 1.61758 1.24288 2.53237 + vertex 1.61283 1.24359 2.53386 + endloop + endfacet + facet normal 0.280071 -0.131603 0.950916 + outer loop + vertex 1.61212 1.23316 2.53264 + vertex 1.61246 1.23826 2.53325 + vertex 1.60784 1.23363 2.53397 + endloop + endfacet + facet normal 0.279558 -0.13524 0.950557 + outer loop + vertex 1.60757 1.22848 2.53332 + vertex 1.61212 1.23316 2.53264 + vertex 1.60784 1.23363 2.53397 + endloop + endfacet + facet normal 0.280065 -0.135766 0.950332 + outer loop + vertex 1.61224 1.22822 2.5319 + vertex 1.61212 1.23316 2.53264 + vertex 1.60757 1.22848 2.53332 + endloop + endfacet + facet normal 0.279852 -0.138092 0.95006 + outer loop + vertex 1.6073 1.22339 2.53265 + vertex 1.61224 1.22822 2.5319 + vertex 1.60757 1.22848 2.53332 + endloop + endfacet + facet normal 0.288069 -0.138201 0.947585 + outer loop + vertex 1.6073 1.22339 2.53265 + vertex 1.60757 1.22848 2.53332 + vertex 1.60291 1.22369 2.53403 + endloop + endfacet + facet normal 0.287584 -0.137697 0.947805 + outer loop + vertex 1.60291 1.22369 2.53403 + vertex 1.60757 1.22848 2.53332 + vertex 1.60295 1.22892 2.53478 + endloop + endfacet + facet normal 0.287885 -0.135351 0.948052 + outer loop + vertex 1.60757 1.22848 2.53332 + vertex 1.60784 1.23363 2.53397 + vertex 1.60295 1.22892 2.53478 + endloop + endfacet + facet normal 0.275918 -0.136035 0.951506 + outer loop + vertex 1.61598 1.23294 2.53149 + vertex 1.61212 1.23316 2.53264 + vertex 1.61224 1.22822 2.5319 + endloop + endfacet + facet normal 0.274889 -0.135183 0.951925 + outer loop + vertex 1.61622 1.2299 2.53099 + vertex 1.61598 1.23294 2.53149 + vertex 1.61224 1.22822 2.5319 + endloop + endfacet + facet normal 0.276736 -0.140258 0.950655 + outer loop + vertex 1.61622 1.2299 2.53099 + vertex 1.61224 1.22822 2.5319 + vertex 1.61504 1.22624 2.5308 + endloop + endfacet + facet normal 0.278309 -0.140739 0.950125 + outer loop + vertex 1.6189 1.22926 2.53011 + vertex 1.61622 1.2299 2.53099 + vertex 1.61504 1.22624 2.5308 + endloop + endfacet + facet normal 0.277847 -0.140096 0.950355 + outer loop + vertex 1.61781 1.22403 2.52966 + vertex 1.6189 1.22926 2.53011 + vertex 1.61504 1.22624 2.5308 + endloop + endfacet + facet normal 0.276688 -0.141611 0.950469 + outer loop + vertex 1.61381 1.22257 2.53061 + vertex 1.61781 1.22403 2.52966 + vertex 1.61504 1.22624 2.5308 + endloop + endfacet + facet normal 0.278389 -0.14215 0.949891 + outer loop + vertex 1.61504 1.22624 2.5308 + vertex 1.61116 1.22316 2.53147 + vertex 1.61381 1.22257 2.53061 + endloop + endfacet + facet normal 0.276288 -0.140319 0.950776 + outer loop + vertex 1.61381 1.22257 2.53061 + vertex 1.61387 1.21925 2.5301 + vertex 1.61781 1.22403 2.52966 + endloop + endfacet + facet normal 0.276248 -0.140284 0.950793 + outer loop + vertex 1.61781 1.22403 2.52966 + vertex 1.61387 1.21925 2.5301 + vertex 1.61784 1.21866 2.52886 + endloop + endfacet + facet normal 0.279204 -0.140341 0.949921 + outer loop + vertex 1.61781 1.22403 2.52966 + vertex 1.62276 1.22871 2.5289 + vertex 1.6189 1.22926 2.53011 + endloop + endfacet + facet normal 0.280164 -0.134803 0.95044 + outer loop + vertex 1.62276 1.23398 2.52964 + vertex 1.6189 1.22926 2.53011 + vertex 1.62276 1.22871 2.5289 + endloop + endfacet + facet normal 0.280597 -0.134786 0.950315 + outer loop + vertex 1.62276 1.22871 2.5289 + vertex 1.6274 1.23328 2.52817 + vertex 1.62276 1.23398 2.52964 + endloop + endfacet + facet normal 0.281711 -0.128597 0.950843 + outer loop + vertex 1.6274 1.23328 2.52817 + vertex 1.62785 1.23853 2.52875 + vertex 1.62276 1.23398 2.52964 + endloop + endfacet + facet normal 0.282207 -0.129196 0.950614 + outer loop + vertex 1.62276 1.23398 2.52964 + vertex 1.62785 1.23853 2.52875 + vertex 1.62391 1.23947 2.53005 + endloop + endfacet + facet normal 0.282658 -0.128646 0.950555 + outer loop + vertex 1.6274 1.23328 2.52817 + vertex 1.63252 1.2379 2.52728 + vertex 1.62785 1.23853 2.52875 + endloop + endfacet + facet normal 0.279707 -0.133818 0.950714 + outer loop + vertex 1.62706 1.22824 2.52756 + vertex 1.6274 1.23328 2.52817 + vertex 1.62276 1.22871 2.5289 + endloop + endfacet + facet normal 0.279043 -0.138547 0.950231 + outer loop + vertex 1.62258 1.22352 2.52819 + vertex 1.62706 1.22824 2.52756 + vertex 1.62276 1.22871 2.5289 + endloop + endfacet + facet normal 0.280708 -0.133848 0.950415 + outer loop + vertex 1.62706 1.22824 2.52756 + vertex 1.63137 1.2324 2.52688 + vertex 1.6274 1.23328 2.52817 + endloop + endfacet + facet normal 0.280547 -0.133669 0.950487 + outer loop + vertex 1.63081 1.22798 2.52642 + vertex 1.63137 1.2324 2.52688 + vertex 1.62706 1.22824 2.52756 + endloop + endfacet + facet normal 0.280139 -0.137676 0.950035 + outer loop + vertex 1.63081 1.22798 2.52642 + vertex 1.62706 1.22824 2.52756 + vertex 1.62724 1.22354 2.52683 + endloop + endfacet + facet normal 0.279239 -0.136919 0.95041 + outer loop + vertex 1.63085 1.22496 2.52597 + vertex 1.63081 1.22798 2.52642 + vertex 1.62724 1.22354 2.52683 + endloop + endfacet + facet normal 0.279756 -0.138455 0.950035 + outer loop + vertex 1.63085 1.22496 2.52597 + vertex 1.62724 1.22354 2.52683 + vertex 1.62952 1.22217 2.52596 + endloop + endfacet + facet normal 0.283435 -0.140198 0.948688 + outer loop + vertex 1.63308 1.22352 2.5251 + vertex 1.63085 1.22496 2.52597 + vertex 1.62952 1.22217 2.52596 + endloop + endfacet + facet normal 0.284596 -0.138357 0.948611 + outer loop + vertex 1.6334 1.22734 2.52556 + vertex 1.63085 1.22496 2.52597 + vertex 1.63308 1.22352 2.5251 + endloop + endfacet + facet normal 0.283165 -0.136707 0.949278 + outer loop + vertex 1.6334 1.22734 2.52556 + vertex 1.63081 1.22798 2.52642 + vertex 1.63085 1.22496 2.52597 + endloop + endfacet + facet normal 0.283948 -0.133786 0.94946 + outer loop + vertex 1.63461 1.23117 2.52573 + vertex 1.63081 1.22798 2.52642 + vertex 1.6334 1.22734 2.52556 + endloop + endfacet + facet normal 0.287548 -0.13486 0.948224 + outer loop + vertex 1.6334 1.22734 2.52556 + vertex 1.6375 1.22883 2.52452 + vertex 1.63461 1.23117 2.52573 + endloop + endfacet + facet normal 0.282799 -0.137065 0.949336 + outer loop + vertex 1.61875 1.2325 2.53062 + vertex 1.6189 1.22926 2.53011 + vertex 1.62276 1.23398 2.52964 + endloop + endfacet + facet normal 0.281053 -0.131487 0.950642 + outer loop + vertex 1.61875 1.2325 2.53062 + vertex 1.62276 1.23398 2.52964 + vertex 1.61977 1.23618 2.53083 + endloop + endfacet + facet normal 0.277622 -0.130605 0.951771 + outer loop + vertex 1.61977 1.23618 2.53083 + vertex 1.61598 1.23294 2.53149 + vertex 1.61875 1.2325 2.53062 + endloop + endfacet + facet normal 0.277627 -0.138554 0.950645 + outer loop + vertex 1.62258 1.22352 2.52819 + vertex 1.62276 1.22871 2.5289 + vertex 1.61781 1.22403 2.52966 + endloop + endfacet + facet normal 0.279187 -0.137388 0.950357 + outer loop + vertex 1.61875 1.2325 2.53062 + vertex 1.61622 1.2299 2.53099 + vertex 1.6189 1.22926 2.53011 + endloop + endfacet + facet normal 0.276866 -0.140069 0.950645 + outer loop + vertex 1.61224 1.22822 2.5319 + vertex 1.61116 1.22316 2.53147 + vertex 1.61504 1.22624 2.5308 + endloop + endfacet + facet normal 0.276824 -0.13494 0.951399 + outer loop + vertex 1.61875 1.2325 2.53062 + vertex 1.61598 1.23294 2.53149 + vertex 1.61622 1.2299 2.53099 + endloop + endfacet + facet normal 0.276414 -0.130563 0.952128 + outer loop + vertex 1.61598 1.23294 2.53149 + vertex 1.61646 1.23737 2.53196 + vertex 1.61212 1.23316 2.53264 + endloop + endfacet + facet normal 0.277279 -0.131516 0.951746 + outer loop + vertex 1.61212 1.23316 2.53264 + vertex 1.61646 1.23737 2.53196 + vertex 1.61246 1.23826 2.53325 + endloop + endfacet + facet normal 0.290195 -0.12364 0.948947 + outer loop + vertex 1.60229 1.24321 2.53694 + vertex 1.60131 1.23807 2.53657 + vertex 1.60511 1.24121 2.53582 + endloop + endfacet + facet normal 0.29479 -0.128911 0.946827 + outer loop + vertex 1.60395 1.23748 2.53567 + vertex 1.60131 1.23807 2.53657 + vertex 1.60141 1.23482 2.5361 + endloop + endfacet + facet normal 0.295271 -0.129405 0.946609 + outer loop + vertex 1.60395 1.23748 2.53567 + vertex 1.60141 1.23482 2.5361 + vertex 1.60404 1.23415 2.53519 + endloop + endfacet + facet normal 0.285947 -0.133187 0.948944 + outer loop + vertex 1.60295 1.22892 2.53478 + vertex 1.60784 1.23363 2.53397 + vertex 1.60404 1.23415 2.53519 + endloop + endfacet + facet normal 0.296274 -0.136356 0.945319 + outer loop + vertex 1.60023 1.23109 2.53595 + vertex 1.59637 1.22799 2.53671 + vertex 1.59904 1.22741 2.53579 + endloop + endfacet + facet normal 0.294774 -0.137449 0.94563 + outer loop + vertex 1.60295 1.22892 2.53478 + vertex 1.59909 1.22413 2.53529 + vertex 1.60291 1.22369 2.53403 + endloop + endfacet + facet normal 0.288323 -0.135724 0.947865 + outer loop + vertex 1.60262 1.21851 2.53338 + vertex 1.6073 1.22339 2.53265 + vertex 1.60291 1.22369 2.53403 + endloop + endfacet + facet normal 0.282643 -0.141141 0.948784 + outer loop + vertex 1.61116 1.22316 2.53147 + vertex 1.61224 1.22822 2.5319 + vertex 1.6073 1.22339 2.53265 + endloop + endfacet + facet normal 0.278653 -0.141085 0.949973 + outer loop + vertex 1.61381 1.22257 2.53061 + vertex 1.61116 1.22316 2.53147 + vertex 1.61121 1.21994 2.53098 + endloop + endfacet + facet normal 0.277833 -0.140222 0.95034 + outer loop + vertex 1.61381 1.22257 2.53061 + vertex 1.61121 1.21994 2.53098 + vertex 1.61387 1.21925 2.5301 + endloop + endfacet + facet normal 0.287451 -0.137852 0.947823 + outer loop + vertex 1.60726 1.21828 2.53192 + vertex 1.60617 1.21315 2.53151 + vertex 1.60999 1.21622 2.53079 + endloop + endfacet + facet normal 0.294917 -0.139237 0.945324 + outer loop + vertex 1.60617 1.21315 2.53151 + vertex 1.60726 1.21828 2.53192 + vertex 1.60234 1.21336 2.53273 + endloop + endfacet + facet normal 0.295931 -0.145224 0.944105 + outer loop + vertex 1.60234 1.20828 2.53199 + vertex 1.60126 1.20322 2.53155 + vertex 1.60509 1.20629 2.53082 + endloop + endfacet + facet normal 0.295833 -0.152813 0.942937 + outer loop + vertex 1.60389 1.20266 2.53063 + vertex 1.60392 1.19935 2.53008 + vertex 1.60784 1.20409 2.52962 + endloop + endfacet + facet normal 0.290403 -0.140805 0.946488 + outer loop + vertex 1.60889 1.20926 2.5301 + vertex 1.60626 1.20994 2.53101 + vertex 1.60509 1.20629 2.53082 + endloop + endfacet + facet normal 0.285403 -0.147434 0.947 + outer loop + vertex 1.61257 1.2036 2.52812 + vertex 1.61274 1.20871 2.52886 + vertex 1.60784 1.20409 2.52962 + endloop + endfacet + facet normal 0.281741 -0.140863 0.949094 + outer loop + vertex 1.60879 1.21254 2.53061 + vertex 1.60889 1.20926 2.5301 + vertex 1.61276 1.21397 2.52965 + endloop + endfacet + facet normal 0.278614 -0.143547 0.949615 + outer loop + vertex 1.61706 1.20826 2.52753 + vertex 1.61741 1.21331 2.52819 + vertex 1.61274 1.20871 2.52886 + endloop + endfacet + facet normal 0.276417 -0.143476 0.950267 + outer loop + vertex 1.61706 1.20826 2.52753 + vertex 1.6214 1.21244 2.5269 + vertex 1.61741 1.21331 2.52819 + endloop + endfacet + facet normal 0.276385 -0.139518 0.950866 + outer loop + vertex 1.61276 1.21397 2.52965 + vertex 1.61784 1.21866 2.52886 + vertex 1.61387 1.21925 2.5301 + endloop + endfacet + facet normal 0.277391 -0.140231 0.950468 + outer loop + vertex 1.61784 1.21866 2.52886 + vertex 1.62258 1.22352 2.52819 + vertex 1.61781 1.22403 2.52966 + endloop + endfacet + facet normal 0.278329 -0.137825 0.950546 + outer loop + vertex 1.62724 1.22354 2.52683 + vertex 1.62706 1.22824 2.52756 + vertex 1.62258 1.22352 2.52819 + endloop + endfacet + facet normal 0.279193 -0.139415 0.950061 + outer loop + vertex 1.62952 1.22217 2.52596 + vertex 1.62724 1.22354 2.52683 + vertex 1.62693 1.21973 2.52636 + endloop + endfacet + facet normal 0.277016 -0.14101 0.950462 + outer loop + vertex 1.6214 1.21244 2.5269 + vertex 1.62273 1.21811 2.52735 + vertex 1.61741 1.21331 2.52819 + endloop + endfacet + facet normal 0.280782 -0.149885 0.947996 + outer loop + vertex 1.62341 1.20741 2.52555 + vertex 1.62304 1.20357 2.52505 + vertex 1.62754 1.2089 2.52456 + endloop + endfacet + facet normal 0.278724 -0.148068 0.948888 + outer loop + vertex 1.62754 1.2089 2.52456 + vertex 1.62304 1.20357 2.52505 + vertex 1.62764 1.20348 2.52369 + endloop + endfacet + facet normal 0.279562 -0.148013 0.94865 + outer loop + vertex 1.62764 1.20348 2.52369 + vertex 1.6324 1.20834 2.52304 + vertex 1.62754 1.2089 2.52456 + endloop + endfacet + facet normal 0.279661 -0.148115 0.948605 + outer loop + vertex 1.63245 1.2031 2.52221 + vertex 1.6324 1.20834 2.52304 + vertex 1.62764 1.20348 2.52369 + endloop + endfacet + facet normal 0.279204 -0.151995 0.948126 + outer loop + vertex 1.62741 1.19829 2.52292 + vertex 1.63245 1.2031 2.52221 + vertex 1.62764 1.20348 2.52369 + endloop + endfacet + facet normal 0.277402 -0.151992 0.948655 + outer loop + vertex 1.62741 1.19829 2.52292 + vertex 1.62764 1.20348 2.52369 + vertex 1.62298 1.19859 2.52427 + endloop + endfacet + facet normal 0.27718 -0.154043 0.948389 + outer loop + vertex 1.62262 1.19342 2.52353 + vertex 1.62741 1.19829 2.52292 + vertex 1.62298 1.19859 2.52427 + endloop + endfacet + facet normal 0.274109 -0.153956 0.949295 + outer loop + vertex 1.62262 1.19342 2.52353 + vertex 1.62298 1.19859 2.52427 + vertex 1.61798 1.1938 2.52493 + endloop + endfacet + facet normal 0.274388 -0.15163 0.949589 + outer loop + vertex 1.61784 1.18858 2.52414 + vertex 1.62262 1.19342 2.52353 + vertex 1.61798 1.1938 2.52493 + endloop + endfacet + facet normal 0.274009 -0.151235 0.949761 + outer loop + vertex 1.62229 1.18827 2.52281 + vertex 1.62262 1.19342 2.52353 + vertex 1.61784 1.18858 2.52414 + endloop + endfacet + facet normal 0.274845 -0.143371 0.950739 + outer loop + vertex 1.61756 1.18345 2.52345 + vertex 1.62229 1.18827 2.52281 + vertex 1.61784 1.18858 2.52414 + endloop + endfacet + facet normal 0.276236 -0.144819 0.950116 + outer loop + vertex 1.62228 1.18313 2.52203 + vertex 1.62229 1.18827 2.52281 + vertex 1.61756 1.18345 2.52345 + endloop + endfacet + facet normal 0.276201 -0.156275 0.94831 + outer loop + vertex 1.61798 1.1938 2.52493 + vertex 1.62298 1.19859 2.52427 + vertex 1.61928 1.19902 2.52541 + endloop + endfacet + facet normal 0.277018 -0.153874 0.948464 + outer loop + vertex 1.62737 1.19313 2.5221 + vertex 1.62741 1.19829 2.52292 + vertex 1.62262 1.19342 2.52353 + endloop + endfacet + facet normal 0.277275 -0.151306 0.948802 + outer loop + vertex 1.62229 1.18827 2.52281 + vertex 1.62737 1.19313 2.5221 + vertex 1.62262 1.19342 2.52353 + endloop + endfacet + facet normal 0.279013 -0.153237 0.947982 + outer loop + vertex 1.62623 1.18801 2.52161 + vertex 1.62737 1.19313 2.5221 + vertex 1.62229 1.18827 2.52281 + endloop + endfacet + facet normal 0.2799 -0.144667 0.949067 + outer loop + vertex 1.62623 1.18801 2.52161 + vertex 1.62229 1.18827 2.52281 + vertex 1.62228 1.18313 2.52203 + endloop + endfacet + facet normal 0.278525 -0.153817 0.948032 + outer loop + vertex 1.63135 1.19796 2.52171 + vertex 1.62741 1.19829 2.52292 + vertex 1.62737 1.19313 2.5221 + endloop + endfacet + facet normal 0.278803 -0.151546 0.948316 + outer loop + vertex 1.63135 1.19796 2.52171 + vertex 1.63245 1.2031 2.52221 + vertex 1.62741 1.19829 2.52292 + endloop + endfacet + facet normal 0.28109 -0.148035 0.948195 + outer loop + vertex 1.6364 1.20788 2.52179 + vertex 1.6324 1.20834 2.52304 + vertex 1.63245 1.2031 2.52221 + endloop + endfacet + facet normal 0.28173 -0.143764 0.948662 + outer loop + vertex 1.6364 1.20788 2.52179 + vertex 1.63748 1.21305 2.52225 + vertex 1.6324 1.20834 2.52304 + endloop + endfacet + facet normal 0.28182 -0.143869 0.94862 + outer loop + vertex 1.6324 1.20834 2.52304 + vertex 1.63748 1.21305 2.52225 + vertex 1.6328 1.21362 2.52373 + endloop + endfacet + facet normal 0.28243 -0.139924 0.949028 + outer loop + vertex 1.63748 1.21305 2.52225 + vertex 1.63747 1.21825 2.52302 + vertex 1.6328 1.21362 2.52373 + endloop + endfacet + facet normal 0.283327 -0.139885 0.948767 + outer loop + vertex 1.64139 1.21783 2.52179 + vertex 1.63747 1.21825 2.52302 + vertex 1.63748 1.21305 2.52225 + endloop + endfacet + facet normal 0.283852 -0.136174 0.94915 + outer loop + vertex 1.64139 1.21783 2.52179 + vertex 1.64242 1.22302 2.52222 + vertex 1.63747 1.21825 2.52302 + endloop + endfacet + facet normal 0.284287 -0.136659 0.948949 + outer loop + vertex 1.63747 1.21825 2.52302 + vertex 1.64242 1.22302 2.52222 + vertex 1.63764 1.22342 2.52371 + endloop + endfacet + facet normal 0.278421 -0.153018 0.948192 + outer loop + vertex 1.62298 1.19859 2.52427 + vertex 1.62764 1.20348 2.52369 + vertex 1.62304 1.20357 2.52505 + endloop + endfacet + facet normal 0.278599 -0.141641 0.949905 + outer loop + vertex 1.62463 1.21121 2.52577 + vertex 1.62885 1.21454 2.52503 + vertex 1.62566 1.21583 2.52616 + endloop + endfacet + facet normal 0.28019 -0.143809 0.949112 + outer loop + vertex 1.6324 1.20834 2.52304 + vertex 1.6328 1.21362 2.52373 + vertex 1.62754 1.2089 2.52456 + endloop + endfacet + facet normal 0.282781 -0.140302 0.948868 + outer loop + vertex 1.6328 1.21362 2.52373 + vertex 1.63747 1.21825 2.52302 + vertex 1.63318 1.21871 2.52436 + endloop + endfacet + facet normal 0.283266 -0.139668 0.948817 + outer loop + vertex 1.62952 1.22217 2.52596 + vertex 1.62951 1.21907 2.52551 + vertex 1.63308 1.22352 2.5251 + endloop + endfacet + facet normal 0.28329 -0.136666 0.949247 + outer loop + vertex 1.63747 1.21825 2.52302 + vertex 1.63764 1.22342 2.52371 + vertex 1.63318 1.21871 2.52436 + endloop + endfacet + facet normal 0.288671 -0.138554 0.94735 + outer loop + vertex 1.6334 1.22734 2.52556 + vertex 1.63308 1.22352 2.5251 + vertex 1.6375 1.22883 2.52452 + endloop + endfacet + facet normal 0.284619 -0.13383 0.949253 + outer loop + vertex 1.64242 1.22302 2.52222 + vertex 1.64232 1.22829 2.52299 + vertex 1.63764 1.22342 2.52371 + endloop + endfacet + facet normal 0.282281 -0.133972 0.949931 + outer loop + vertex 1.64632 1.22789 2.52175 + vertex 1.64232 1.22829 2.52299 + vertex 1.64242 1.22302 2.52222 + endloop + endfacet + facet normal 0.286726 -0.132078 0.948864 + outer loop + vertex 1.6375 1.22883 2.52452 + vertex 1.64271 1.23357 2.52361 + vertex 1.63878 1.23449 2.52492 + endloop + endfacet + facet normal 0.282454 -0.132663 0.950063 + outer loop + vertex 1.64632 1.22789 2.52175 + vertex 1.64738 1.23307 2.52216 + vertex 1.64232 1.22829 2.52299 + endloop + endfacet + facet normal 0.277133 -0.129118 0.952116 + outer loop + vertex 1.65128 1.23793 2.52168 + vertex 1.64736 1.23824 2.52286 + vertex 1.64738 1.23307 2.52216 + endloop + endfacet + facet normal 0.277488 -0.125859 0.952449 + outer loop + vertex 1.65128 1.23793 2.52168 + vertex 1.65227 1.24307 2.52207 + vertex 1.64736 1.23824 2.52286 + endloop + endfacet + facet normal 0.276825 -0.125138 0.952737 + outer loop + vertex 1.64736 1.23824 2.52286 + vertex 1.65227 1.24307 2.52207 + vertex 1.64756 1.24334 2.52348 + endloop + endfacet + facet normal 0.288268 -0.123537 0.949547 + outer loop + vertex 1.63907 1.24219 2.52586 + vertex 1.63932 1.23903 2.52538 + vertex 1.64296 1.24378 2.52489 + endloop + endfacet + facet normal 0.286176 -0.11758 0.950936 + outer loop + vertex 1.63907 1.24219 2.52586 + vertex 1.64296 1.24378 2.52489 + vertex 1.64016 1.24591 2.526 + endloop + endfacet + facet normal 0.287392 -0.11792 0.950526 + outer loop + vertex 1.64016 1.24591 2.526 + vertex 1.63636 1.24277 2.52675 + vertex 1.63907 1.24219 2.52586 + endloop + endfacet + facet normal 0.285812 -0.118081 0.950983 + outer loop + vertex 1.64296 1.24378 2.52489 + vertex 1.64394 1.24902 2.52524 + vertex 1.64016 1.24591 2.526 + endloop + endfacet + facet normal 0.283061 -0.114429 0.952251 + outer loop + vertex 1.64394 1.24902 2.52524 + vertex 1.64125 1.24967 2.52612 + vertex 1.64016 1.24591 2.526 + endloop + endfacet + facet normal 0.287648 -0.115721 0.950719 + outer loop + vertex 1.64125 1.24967 2.52612 + vertex 1.6373 1.24798 2.52711 + vertex 1.64016 1.24591 2.526 + endloop + endfacet + facet normal 0.287417 -0.115094 0.950865 + outer loop + vertex 1.64125 1.24967 2.52612 + vertex 1.64096 1.2528 2.52659 + vertex 1.6373 1.24798 2.52711 + endloop + endfacet + facet normal 0.28767 -0.128368 0.949088 + outer loop + vertex 1.64271 1.23357 2.52361 + vertex 1.64308 1.23868 2.52419 + vertex 1.63878 1.23449 2.52492 + endloop + endfacet + facet normal 0.289284 -0.132597 0.948015 + outer loop + vertex 1.6375 1.22883 2.52452 + vertex 1.63878 1.23449 2.52492 + vertex 1.63461 1.23117 2.52573 + endloop + endfacet + facet normal 0.284119 -0.134007 0.949378 + outer loop + vertex 1.63137 1.2324 2.52688 + vertex 1.63081 1.22798 2.52642 + vertex 1.63461 1.23117 2.52573 + endloop + endfacet + facet normal 0.28212 -0.128003 0.950801 + outer loop + vertex 1.63137 1.2324 2.52688 + vertex 1.63252 1.2379 2.52728 + vertex 1.6274 1.23328 2.52817 + endloop + endfacet + facet normal 0.286804 -0.120433 0.950389 + outer loop + vertex 1.63907 1.24219 2.52586 + vertex 1.63636 1.24277 2.52675 + vertex 1.63657 1.23951 2.52628 + endloop + endfacet + facet normal 0.283625 -0.122677 0.951056 + outer loop + vertex 1.63252 1.2379 2.52728 + vertex 1.63246 1.24316 2.52797 + vertex 1.62785 1.23853 2.52875 + endloop + endfacet + facet normal 0.284956 -0.124101 0.950473 + outer loop + vertex 1.62785 1.23853 2.52875 + vertex 1.63246 1.24316 2.52797 + vertex 1.62818 1.24364 2.52932 + endloop + endfacet + facet normal 0.286733 -0.117049 0.950833 + outer loop + vertex 1.6373 1.24798 2.52711 + vertex 1.63636 1.24277 2.52675 + vertex 1.64016 1.24591 2.526 + endloop + endfacet + facet normal 0.28878 -0.116189 0.950319 + outer loop + vertex 1.64096 1.2528 2.52659 + vertex 1.63711 1.25304 2.52779 + vertex 1.6373 1.24798 2.52711 + endloop + endfacet + facet normal 0.285605 -0.119412 0.950879 + outer loop + vertex 1.63246 1.24316 2.52797 + vertex 1.63264 1.24832 2.52857 + vertex 1.62818 1.24364 2.52932 + endloop + endfacet + facet normal 0.283525 -0.124056 0.950907 + outer loop + vertex 1.62785 1.23853 2.52875 + vertex 1.62818 1.24364 2.52932 + vertex 1.62391 1.23947 2.53005 + endloop + endfacet + facet normal 0.282616 -0.129272 0.950482 + outer loop + vertex 1.62276 1.23398 2.52964 + vertex 1.62391 1.23947 2.53005 + vertex 1.61977 1.23618 2.53083 + endloop + endfacet + facet normal 0.277666 -0.13066 0.951751 + outer loop + vertex 1.61646 1.23737 2.53196 + vertex 1.61598 1.23294 2.53149 + vertex 1.61977 1.23618 2.53083 + endloop + endfacet + facet normal 0.278374 -0.127018 0.952037 + outer loop + vertex 1.61646 1.23737 2.53196 + vertex 1.61758 1.24288 2.53237 + vertex 1.61246 1.23826 2.53325 + endloop + endfacet + facet normal 0.280772 -0.124182 0.951707 + outer loop + vertex 1.62144 1.24769 2.53186 + vertex 1.61747 1.24824 2.5331 + vertex 1.61758 1.24288 2.53237 + endloop + endfacet + facet normal 0.286893 -0.123431 0.949978 + outer loop + vertex 1.62416 1.24707 2.53097 + vertex 1.62441 1.24396 2.53049 + vertex 1.62806 1.2487 2.53 + endloop + endfacet + facet normal 0.290467 -0.120402 0.94928 + outer loop + vertex 1.62806 1.2487 2.53 + vertex 1.63285 1.25351 2.52915 + vertex 1.62908 1.25394 2.53035 + endloop + endfacet + facet normal 0.28873 -0.117459 0.950178 + outer loop + vertex 1.62898 1.25728 2.5308 + vertex 1.62644 1.25456 2.53123 + vertex 1.62908 1.25394 2.53035 + endloop + endfacet + facet normal 0.282427 -0.120291 0.951717 + outer loop + vertex 1.62246 1.25295 2.53222 + vertex 1.62144 1.24769 2.53186 + vertex 1.62528 1.25079 2.53111 + endloop + endfacet + facet normal 0.286051 -0.114777 0.951315 + outer loop + vertex 1.62898 1.25728 2.5308 + vertex 1.6263 1.25787 2.53168 + vertex 1.62644 1.25456 2.53123 + endloop + endfacet + facet normal 0.284486 -0.112051 0.952109 + outer loop + vertex 1.6263 1.25787 2.53168 + vertex 1.62724 1.2631 2.53201 + vertex 1.62241 1.25821 2.53288 + endloop + endfacet + facet normal 0.286361 -0.114044 0.95131 + outer loop + vertex 1.62241 1.25821 2.53288 + vertex 1.62724 1.2631 2.53201 + vertex 1.62258 1.26338 2.53345 + endloop + endfacet + facet normal 0.281436 -0.120122 0.952032 + outer loop + vertex 1.62144 1.24769 2.53186 + vertex 1.62246 1.25295 2.53222 + vertex 1.61747 1.24824 2.5331 + endloop + endfacet + facet normal 0.279691 -0.124247 0.952017 + outer loop + vertex 1.61758 1.24288 2.53237 + vertex 1.61747 1.24824 2.5331 + vertex 1.61283 1.24359 2.53386 + endloop + endfacet + facet normal 0.279144 -0.126843 0.951835 + outer loop + vertex 1.60787 1.23895 2.53469 + vertex 1.61283 1.24359 2.53386 + vertex 1.60891 1.24425 2.53509 + endloop + endfacet + facet normal 0.280905 -0.124527 0.951623 + outer loop + vertex 1.60871 1.24754 2.53558 + vertex 1.60622 1.24493 2.53598 + vertex 1.60891 1.24425 2.53509 + endloop + endfacet + facet normal 0.279362 -0.122956 0.952281 + outer loop + vertex 1.60871 1.24754 2.53558 + vertex 1.60593 1.24798 2.53646 + vertex 1.60622 1.24493 2.53598 + endloop + endfacet + facet normal 0.284649 -0.120037 0.951087 + outer loop + vertex 1.60593 1.24798 2.53646 + vertex 1.60638 1.25239 2.53688 + vertex 1.60211 1.24817 2.53762 + endloop + endfacet + facet normal 0.275902 -0.116696 0.954076 + outer loop + vertex 1.6075 1.25787 2.53722 + vertex 1.60638 1.25239 2.53688 + vertex 1.61053 1.25573 2.53609 + endloop + endfacet + facet normal 0.279535 -0.120962 0.952485 + outer loop + vertex 1.61273 1.24898 2.53459 + vertex 1.61383 1.25449 2.53497 + vertex 1.60969 1.25122 2.53577 + endloop + endfacet + facet normal 0.278139 -0.116834 0.953409 + outer loop + vertex 1.61431 1.25901 2.53539 + vertex 1.61154 1.25949 2.53625 + vertex 1.61053 1.25573 2.53609 + endloop + endfacet + facet normal 0.281774 -0.117518 0.952257 + outer loop + vertex 1.61781 1.25354 2.53367 + vertex 1.61811 1.25867 2.53422 + vertex 1.61383 1.25449 2.53497 + endloop + endfacet + facet normal 0.282148 -0.114895 0.952466 + outer loop + vertex 1.61406 1.26217 2.53584 + vertex 1.61431 1.25901 2.53539 + vertex 1.61798 1.26379 2.53487 + endloop + endfacet + facet normal 0.284215 -0.114043 0.951954 + outer loop + vertex 1.62241 1.25821 2.53288 + vertex 1.62258 1.26338 2.53345 + vertex 1.61811 1.25867 2.53422 + endloop + endfacet + facet normal 0.286642 -0.110863 0.951602 + outer loop + vertex 1.62724 1.2631 2.53201 + vertex 1.62704 1.26815 2.53266 + vertex 1.62258 1.26338 2.53345 + endloop + endfacet + facet normal 0.286831 -0.114242 0.951145 + outer loop + vertex 1.61798 1.26379 2.53487 + vertex 1.62278 1.26858 2.534 + vertex 1.61898 1.26905 2.53521 + endloop + endfacet + facet normal 0.282612 -0.112045 0.952668 + outer loop + vertex 1.6188 1.27237 2.53565 + vertex 1.61629 1.26966 2.53607 + vertex 1.61898 1.26905 2.53521 + endloop + endfacet + facet normal 0.279961 -0.109422 0.953755 + outer loop + vertex 1.6188 1.27237 2.53565 + vertex 1.616 1.27281 2.53652 + vertex 1.61629 1.26966 2.53607 + endloop + endfacet + facet normal 0.276683 -0.107258 0.954957 + outer loop + vertex 1.616 1.27281 2.53652 + vertex 1.61642 1.27736 2.53691 + vertex 1.61211 1.27305 2.53768 + endloop + endfacet + facet normal 0.281291 -0.105242 0.953834 + outer loop + vertex 1.61744 1.28291 2.53722 + vertex 1.61642 1.27736 2.53691 + vertex 1.62056 1.2808 2.53607 + endloop + endfacet + facet normal 0.287275 -0.10767 0.951778 + outer loop + vertex 1.62276 1.27395 2.53463 + vertex 1.62386 1.27956 2.53494 + vertex 1.61977 1.27617 2.53579 + endloop + endfacet + facet normal 0.290482 -0.105124 0.951088 + outer loop + vertex 1.62386 1.27956 2.53494 + vertex 1.62803 1.28372 2.53412 + vertex 1.62427 1.28413 2.53532 + endloop + endfacet + facet normal 0.282222 -0.103795 0.953718 + outer loop + vertex 1.62147 1.28458 2.53621 + vertex 1.61744 1.28291 2.53722 + vertex 1.62056 1.2808 2.53607 + endloop + endfacet + facet normal 0.281614 -0.10211 0.954079 + outer loop + vertex 1.62147 1.28458 2.53621 + vertex 1.62106 1.2877 2.53667 + vertex 1.61744 1.28291 2.53722 + endloop + endfacet + facet normal 0.285987 -0.100357 0.952964 + outer loop + vertex 1.62144 1.29225 2.53703 + vertex 1.62106 1.2877 2.53667 + vertex 1.62478 1.29104 2.5359 + endloop + endfacet + facet normal 0.290318 -0.102581 0.951416 + outer loop + vertex 1.62389 1.28727 2.53577 + vertex 1.62427 1.28413 2.53532 + vertex 1.62784 1.28887 2.53474 + endloop + endfacet + facet normal 0.289435 -0.0992895 0.952034 + outer loop + vertex 1.62478 1.29104 2.5359 + vertex 1.62886 1.29444 2.53502 + vertex 1.62556 1.2957 2.53615 + endloop + endfacet + facet normal 0.291683 -0.101494 0.951115 + outer loop + vertex 1.63241 1.28819 2.53327 + vertex 1.63277 1.29345 2.53372 + vertex 1.62784 1.28887 2.53474 + endloop + endfacet + facet normal 0.289459 -0.0995338 0.952001 + outer loop + vertex 1.63739 1.29281 2.53225 + vertex 1.63719 1.29796 2.53285 + vertex 1.63277 1.29345 2.53372 + endloop + endfacet + facet normal 0.290785 -0.0978937 0.951767 + outer loop + vertex 1.62886 1.29444 2.53502 + vertex 1.63303 1.29861 2.53417 + vertex 1.62927 1.29905 2.53536 + endloop + endfacet + facet normal 0.290664 -0.0961911 0.951978 + outer loop + vertex 1.6289 1.30222 2.5358 + vertex 1.62647 1.29951 2.53626 + vertex 1.62927 1.29905 2.53536 + endloop + endfacet + facet normal 0.290115 -0.0956608 0.952199 + outer loop + vertex 1.6289 1.30222 2.5358 + vertex 1.62607 1.30264 2.5367 + vertex 1.62647 1.29951 2.53626 + endloop + endfacet + facet normal 0.288252 -0.0958803 0.952742 + outer loop + vertex 1.62607 1.30264 2.5367 + vertex 1.62644 1.3072 2.53705 + vertex 1.62223 1.30296 2.5379 + endloop + endfacet + facet normal 0.289348 -0.0970602 0.95229 + outer loop + vertex 1.62223 1.30296 2.5379 + vertex 1.62644 1.3072 2.53705 + vertex 1.62248 1.3081 2.53834 + endloop + endfacet + facet normal 0.289519 -0.0963391 0.952312 + outer loop + vertex 1.62644 1.3072 2.53705 + vertex 1.62744 1.31278 2.53731 + vertex 1.62248 1.3081 2.53834 + endloop + endfacet + facet normal 0.292515 -0.09683 0.951346 + outer loop + vertex 1.62744 1.31278 2.53731 + vertex 1.62644 1.3072 2.53705 + vertex 1.63054 1.31065 2.53614 + endloop + endfacet + facet normal 0.291499 -0.0946055 0.951881 + outer loop + vertex 1.63284 1.3038 2.53475 + vertex 1.63384 1.30938 2.535 + vertex 1.62978 1.30599 2.5359 + endloop + endfacet + facet normal 0.288626 -0.0946209 0.952755 + outer loop + vertex 1.63384 1.30938 2.535 + vertex 1.63801 1.31356 2.53415 + vertex 1.63424 1.31399 2.53534 + endloop + endfacet + facet normal 0.293006 -0.0960761 0.951271 + outer loop + vertex 1.63144 1.31446 2.53625 + vertex 1.62744 1.31278 2.53731 + vertex 1.63054 1.31065 2.53614 + endloop + endfacet + facet normal 0.292612 -0.0949961 0.951501 + outer loop + vertex 1.63144 1.31446 2.53625 + vertex 1.63104 1.31763 2.53669 + vertex 1.62744 1.31278 2.53731 + endloop + endfacet + facet normal 0.292926 -0.0952451 0.951379 + outer loop + vertex 1.63104 1.31763 2.53669 + vertex 1.62722 1.31796 2.5379 + vertex 1.62744 1.31278 2.53731 + endloop + endfacet + facet normal 0.292848 -0.0910179 0.951817 + outer loop + vertex 1.63141 1.32225 2.53702 + vertex 1.63104 1.31763 2.53669 + vertex 1.63474 1.32102 2.53587 + endloop + endfacet + facet normal 0.291063 -0.095553 0.95192 + outer loop + vertex 1.63386 1.31719 2.53577 + vertex 1.63424 1.31399 2.53534 + vertex 1.63781 1.3188 2.53473 + endloop + endfacet + facet normal 0.280259 -0.0887647 0.955812 + outer loop + vertex 1.63781 1.3188 2.53473 + vertex 1.64273 1.32345 2.53371 + vertex 1.63879 1.32446 2.53496 + endloop + endfacet + facet normal 0.281267 -0.084916 0.955865 + outer loop + vertex 1.64273 1.32345 2.53371 + vertex 1.64291 1.32865 2.53412 + vertex 1.63879 1.32446 2.53496 + endloop + endfacet + facet normal 0.278357 -0.0848803 0.95672 + outer loop + vertex 1.64273 1.32345 2.53371 + vertex 1.64709 1.32799 2.53285 + vertex 1.64291 1.32865 2.53412 + endloop + endfacet + facet normal 0.290823 -0.0776479 0.953621 + outer loop + vertex 1.63635 1.32964 2.53615 + vertex 1.63586 1.33277 2.53655 + vertex 1.63237 1.32789 2.53722 + endloop + endfacet + facet normal 0.291226 -0.0779569 0.953473 + outer loop + vertex 1.63586 1.33277 2.53655 + vertex 1.63204 1.33303 2.53774 + vertex 1.63237 1.32789 2.53722 + endloop + endfacet + facet normal 0.294011 -0.0878019 0.951761 + outer loop + vertex 1.63548 1.32576 2.53608 + vertex 1.63141 1.32225 2.53702 + vertex 1.63474 1.32102 2.53587 + endloop + endfacet + facet normal 0.293376 -0.0910481 0.951652 + outer loop + vertex 1.63104 1.31763 2.53669 + vertex 1.63141 1.32225 2.53702 + vertex 1.62722 1.31796 2.5379 + endloop + endfacet + facet normal 0.290598 -0.0954252 0.952075 + outer loop + vertex 1.62744 1.31278 2.53731 + vertex 1.62722 1.31796 2.5379 + vertex 1.62283 1.3134 2.53878 + endloop + endfacet + facet normal 0.290318 -0.097261 0.951975 + outer loop + vertex 1.62248 1.3081 2.53834 + vertex 1.62744 1.31278 2.53731 + vertex 1.62283 1.3134 2.53878 + endloop + endfacet + facet normal 0.286105 -0.0969877 0.953277 + outer loop + vertex 1.62223 1.30296 2.5379 + vertex 1.62248 1.3081 2.53834 + vertex 1.61809 1.30359 2.5392 + endloop + endfacet + facet normal 0.283983 -0.0982505 0.953782 + outer loop + vertex 1.61389 1.29942 2.54002 + vertex 1.61809 1.30359 2.5392 + vertex 1.61431 1.30399 2.54037 + endloop + endfacet + facet normal 0.281871 -0.0981404 0.95442 + outer loop + vertex 1.61394 1.30715 2.5408 + vertex 1.6115 1.30444 2.54124 + vertex 1.61431 1.30399 2.54037 + endloop + endfacet + facet normal 0.282994 -0.099221 0.953976 + outer loop + vertex 1.61394 1.30715 2.5408 + vertex 1.6111 1.30757 2.54169 + vertex 1.6115 1.30444 2.54124 + endloop + endfacet + facet normal 0.283119 -0.10159 0.953689 + outer loop + vertex 1.6111 1.30757 2.54169 + vertex 1.61148 1.31215 2.54206 + vertex 1.60726 1.30791 2.54287 + endloop + endfacet + facet normal 0.286198 -0.101546 0.952775 + outer loop + vertex 1.61249 1.31774 2.54236 + vertex 1.61148 1.31215 2.54206 + vertex 1.6156 1.31561 2.5412 + endloop + endfacet + facet normal 0.285452 -0.0984467 0.953323 + outer loop + vertex 1.6179 1.30877 2.53979 + vertex 1.61891 1.31436 2.54006 + vertex 1.61483 1.31094 2.54093 + endloop + endfacet + facet normal 0.291225 -0.0984203 0.951578 + outer loop + vertex 1.61891 1.31436 2.54006 + vertex 1.62309 1.31858 2.53922 + vertex 1.61932 1.31898 2.54042 + endloop + endfacet + facet normal 0.287396 -0.0997098 0.952608 + outer loop + vertex 1.61651 1.31943 2.54132 + vertex 1.61249 1.31774 2.54236 + vertex 1.6156 1.31561 2.5412 + endloop + endfacet + facet normal 0.285329 -0.0940618 0.953803 + outer loop + vertex 1.61651 1.31943 2.54132 + vertex 1.6161 1.32259 2.54176 + vertex 1.61249 1.31774 2.54236 + endloop + endfacet + facet normal 0.289687 -0.0868194 0.953176 + outer loop + vertex 1.61646 1.32722 2.54207 + vertex 1.6161 1.32259 2.54176 + vertex 1.61981 1.326 2.54094 + endloop + endfacet + facet normal 0.29564 -0.094782 0.950586 + outer loop + vertex 1.61894 1.32216 2.54085 + vertex 1.61932 1.31898 2.54042 + vertex 1.62289 1.32381 2.53979 + endloop + endfacet + facet normal 0.292963 -0.0806429 0.952717 + outer loop + vertex 1.61981 1.326 2.54094 + vertex 1.62386 1.32945 2.53999 + vertex 1.62054 1.33072 2.54112 + endloop + endfacet + facet normal 0.294292 -0.0842874 0.951992 + outer loop + vertex 1.62746 1.32315 2.53832 + vertex 1.62777 1.32848 2.53869 + vertex 1.62289 1.32381 2.53979 + endloop + endfacet + facet normal 0.29477 -0.077621 0.95241 + outer loop + vertex 1.63237 1.32789 2.53722 + vertex 1.63204 1.33303 2.53774 + vertex 1.62777 1.32848 2.53869 + endloop + endfacet + facet normal 0.294646 -0.0755781 0.952613 + outer loop + vertex 1.62386 1.32945 2.53999 + vertex 1.62794 1.33366 2.53906 + vertex 1.6242 1.33412 2.54025 + endloop + endfacet + facet normal 0.29491 -0.0708759 0.952893 + outer loop + vertex 1.62375 1.33733 2.54063 + vertex 1.62139 1.3346 2.54116 + vertex 1.6242 1.33412 2.54025 + endloop + endfacet + facet normal 0.294236 -0.0702452 0.953148 + outer loop + vertex 1.62375 1.33733 2.54063 + vertex 1.62089 1.33774 2.54154 + vertex 1.62139 1.3346 2.54116 + endloop + endfacet + facet normal 0.294836 -0.0688402 0.953065 + outer loop + vertex 1.62089 1.33774 2.54154 + vertex 1.62098 1.34219 2.54184 + vertex 1.61706 1.33804 2.54275 + endloop + endfacet + facet normal 0.296536 -0.065861 0.952748 + outer loop + vertex 1.62765 1.3389 2.53953 + vertex 1.62853 1.34459 2.53965 + vertex 1.62448 1.34113 2.54067 + endloop + endfacet + facet normal 0.293467 -0.0628163 0.953903 + outer loop + vertex 1.62853 1.34459 2.53965 + vertex 1.63284 1.34868 2.53859 + vertex 1.62889 1.34963 2.53987 + endloop + endfacet + facet normal 0.297766 -0.0661912 0.952341 + outer loop + vertex 1.62121 1.34706 2.5421 + vertex 1.62098 1.34219 2.54184 + vertex 1.62489 1.34589 2.54087 + endloop + endfacet + facet normal 0.299318 -0.0634439 0.952042 + outer loop + vertex 1.62121 1.34706 2.5421 + vertex 1.62163 1.35216 2.54231 + vertex 1.61735 1.34824 2.5434 + endloop + endfacet + facet normal 0.300877 -0.0621582 0.951635 + outer loop + vertex 1.6225 1.35786 2.54241 + vertex 1.62163 1.35216 2.54231 + vertex 1.62566 1.35555 2.54126 + endloop + endfacet + facet normal 0.297275 -0.0610195 0.95284 + outer loop + vertex 1.62889 1.34963 2.53987 + vertex 1.62911 1.35446 2.54011 + vertex 1.62522 1.35076 2.54109 + endloop + endfacet + facet normal 0.29127 -0.0598949 0.954764 + outer loop + vertex 1.62911 1.35446 2.54011 + vertex 1.63299 1.35854 2.53918 + vertex 1.62923 1.35892 2.54035 + endloop + endfacet + facet normal 0.301822 -0.0607578 0.951426 + outer loop + vertex 1.6264 1.35939 2.54127 + vertex 1.6225 1.35786 2.54241 + vertex 1.62566 1.35555 2.54126 + endloop + endfacet + facet normal 0.302447 -0.0625916 0.951109 + outer loop + vertex 1.6264 1.35939 2.54127 + vertex 1.62588 1.36259 2.54164 + vertex 1.6225 1.35786 2.54241 + endloop + endfacet + facet normal 0.303208 -0.0631819 0.950827 + outer loop + vertex 1.62588 1.36259 2.54164 + vertex 1.62204 1.36311 2.5429 + vertex 1.6225 1.35786 2.54241 + endloop + endfacet + facet normal 0.303174 -0.0634279 0.950822 + outer loop + vertex 1.62588 1.36259 2.54164 + vertex 1.62599 1.36713 2.54191 + vertex 1.62204 1.36311 2.5429 + endloop + endfacet + facet normal 0.292019 -0.0614976 0.954433 + outer loop + vertex 1.62873 1.3621 2.54071 + vertex 1.62923 1.35892 2.54035 + vertex 1.63265 1.3637 2.53962 + endloop + endfacet + facet normal 0.283531 -0.0591717 0.957136 + outer loop + vertex 1.63265 1.3637 2.53962 + vertex 1.63754 1.36823 2.53845 + vertex 1.63355 1.36943 2.5397 + endloop + endfacet + facet normal 0.299747 -0.0634132 0.951909 + outer loop + vertex 1.62599 1.36713 2.54191 + vertex 1.62588 1.36259 2.54164 + vertex 1.62947 1.36595 2.54074 + endloop + endfacet + facet normal 0.294374 -0.0578811 0.953936 + outer loop + vertex 1.63355 1.36943 2.5397 + vertex 1.63391 1.37452 2.5399 + vertex 1.6299 1.37079 2.54091 + endloop + endfacet + facet normal 0.285166 -0.0538392 0.956965 + outer loop + vertex 1.63391 1.37452 2.5399 + vertex 1.63798 1.37857 2.53892 + vertex 1.63412 1.3794 2.54011 + endloop + endfacet + facet normal 0.299935 -0.0476713 0.952768 + outer loop + vertex 1.63134 1.38434 2.54123 + vertex 1.6308 1.38752 2.54156 + vertex 1.62747 1.38275 2.54237 + endloop + endfacet + facet normal 0.300808 -0.0483343 0.952459 + outer loop + vertex 1.6308 1.38752 2.54156 + vertex 1.62702 1.38787 2.54277 + vertex 1.62747 1.38275 2.54237 + endloop + endfacet + facet normal 0.301622 -0.0540054 0.951897 + outer loop + vertex 1.63064 1.3805 2.54125 + vertex 1.62665 1.37712 2.54232 + vertex 1.63023 1.3757 2.54111 + endloop + endfacet + facet normal 0.300467 -0.0570704 0.952083 + outer loop + vertex 1.62665 1.37712 2.54232 + vertex 1.62626 1.37205 2.54214 + vertex 1.63023 1.3757 2.54111 + endloop + endfacet + facet normal 0.303272 -0.0613242 0.950929 + outer loop + vertex 1.62599 1.36713 2.54191 + vertex 1.62626 1.37205 2.54214 + vertex 1.62216 1.36824 2.54321 + endloop + endfacet + facet normal 0.302797 -0.063022 0.950969 + outer loop + vertex 1.62204 1.36311 2.5429 + vertex 1.62599 1.36713 2.54191 + vertex 1.62216 1.36824 2.54321 + endloop + endfacet + facet normal 0.302316 -0.063286 0.951105 + outer loop + vertex 1.6225 1.35786 2.54241 + vertex 1.62204 1.36311 2.5429 + vertex 1.61801 1.35877 2.54389 + endloop + endfacet + facet normal 0.299256 -0.0642285 0.952009 + outer loop + vertex 1.61401 1.35471 2.54488 + vertex 1.61801 1.35877 2.54389 + vertex 1.61417 1.35932 2.54514 + endloop + endfacet + facet normal 0.293502 -0.064274 0.953795 + outer loop + vertex 1.61366 1.36252 2.54551 + vertex 1.6113 1.35976 2.54605 + vertex 1.61417 1.35932 2.54514 + endloop + endfacet + facet normal 0.291706 -0.0626066 0.954457 + outer loop + vertex 1.61366 1.36252 2.54551 + vertex 1.61079 1.36287 2.54641 + vertex 1.6113 1.35976 2.54605 + endloop + endfacet + facet normal 0.287731 -0.0624182 0.955675 + outer loop + vertex 1.61079 1.36287 2.54641 + vertex 1.61091 1.36726 2.54666 + vertex 1.60699 1.36304 2.54757 + endloop + endfacet + facet normal 0.29909 -0.0618725 0.952217 + outer loop + vertex 1.61756 1.36402 2.54439 + vertex 1.61839 1.36963 2.54449 + vertex 1.61439 1.36629 2.54553 + endloop + endfacet + facet normal 0.301621 -0.0592623 0.951584 + outer loop + vertex 1.61839 1.36963 2.54449 + vertex 1.62252 1.37337 2.54341 + vertex 1.61878 1.37468 2.54468 + endloop + endfacet + facet normal 0.293261 -0.0605271 0.954115 + outer loop + vertex 1.61108 1.37205 2.54691 + vertex 1.61091 1.36726 2.54666 + vertex 1.61481 1.37102 2.5457 + endloop + endfacet + facet normal 0.28996 -0.0572721 0.955323 + outer loop + vertex 1.61108 1.37205 2.54691 + vertex 1.61127 1.37699 2.54715 + vertex 1.60711 1.37293 2.54817 + endloop + endfacet + facet normal 0.294352 -0.0537976 0.954182 + outer loop + vertex 1.61163 1.38207 2.54733 + vertex 1.61127 1.37699 2.54715 + vertex 1.61528 1.38073 2.54613 + endloop + endfacet + facet normal 0.299128 -0.0547778 0.952639 + outer loop + vertex 1.61878 1.37468 2.54468 + vertex 1.619 1.3796 2.5449 + vertex 1.61505 1.37587 2.54592 + endloop + endfacet + facet normal 0.299874 -0.0512686 0.9526 + outer loop + vertex 1.61528 1.38073 2.54613 + vertex 1.61915 1.38442 2.54511 + vertex 1.61566 1.38549 2.54626 + endloop + endfacet + facet normal 0.302724 -0.051545 0.951683 + outer loop + vertex 1.62288 1.37849 2.5436 + vertex 1.62305 1.38357 2.54382 + vertex 1.619 1.3796 2.5449 + endloop + endfacet + facet normal 0.303338 -0.0480539 0.951671 + outer loop + vertex 1.62747 1.38275 2.54237 + vertex 1.62702 1.38787 2.54277 + vertex 1.62305 1.38357 2.54382 + endloop + endfacet + facet normal 0.303455 -0.0479991 0.951636 + outer loop + vertex 1.61915 1.38442 2.54511 + vertex 1.62297 1.38853 2.54409 + vertex 1.61921 1.38888 2.54531 + endloop + endfacet + facet normal 0.302197 -0.045519 0.952158 + outer loop + vertex 1.61867 1.39205 2.54564 + vertex 1.61636 1.3893 2.54624 + vertex 1.61921 1.38888 2.54531 + endloop + endfacet + facet normal 0.300402 -0.0438723 0.952803 + outer loop + vertex 1.61867 1.39205 2.54564 + vertex 1.61581 1.39248 2.54656 + vertex 1.61636 1.3893 2.54624 + endloop + endfacet + facet normal 0.297455 -0.0423015 0.953798 + outer loop + vertex 1.61581 1.39248 2.54656 + vertex 1.61587 1.39705 2.54674 + vertex 1.61202 1.39288 2.54776 + endloop + endfacet + facet normal 0.304598 -0.0409815 0.951599 + outer loop + vertex 1.62255 1.39371 2.54447 + vertex 1.62336 1.3995 2.54446 + vertex 1.61937 1.39596 2.54558 + endloop + endfacet + facet normal 0.304103 -0.0395461 0.951818 + outer loop + vertex 1.62336 1.3995 2.54446 + vertex 1.62742 1.40337 2.54332 + vertex 1.62368 1.40466 2.54457 + endloop + endfacet + facet normal 0.302986 -0.0414399 0.952093 + outer loop + vertex 1.61603 1.40206 2.54691 + vertex 1.61587 1.39705 2.54674 + vertex 1.61976 1.4009 2.54567 + endloop + endfacet + facet normal 0.301427 -0.0410305 0.952606 + outer loop + vertex 1.61603 1.40206 2.54691 + vertex 1.61619 1.40712 2.54708 + vertex 1.61212 1.40318 2.54819 + endloop + endfacet + facet normal 0.305557 -0.038619 0.95139 + outer loop + vertex 1.62368 1.40466 2.54457 + vertex 1.62381 1.40963 2.54473 + vertex 1.61996 1.40592 2.54582 + endloop + endfacet + facet normal 0.305451 -0.0368431 0.951495 + outer loop + vertex 1.62381 1.40963 2.54473 + vertex 1.62771 1.41332 2.54362 + vertex 1.62391 1.41455 2.54489 + endloop + endfacet + facet normal 0.305312 -0.039501 0.951433 + outer loop + vertex 1.61631 1.41211 2.54725 + vertex 1.61619 1.40712 2.54708 + vertex 1.62006 1.41087 2.54599 + endloop + endfacet + facet normal 0.304227 -0.0364968 0.9519 + outer loop + vertex 1.61631 1.41211 2.54725 + vertex 1.61642 1.41704 2.5474 + vertex 1.61256 1.41338 2.54849 + endloop + endfacet + facet normal 0.30661 -0.0338763 0.951232 + outer loop + vertex 1.6167 1.42207 2.54749 + vertex 1.61642 1.41704 2.5474 + vertex 1.6203 1.42066 2.54628 + endloop + endfacet + facet normal 0.307526 -0.0341376 0.950927 + outer loop + vertex 1.62391 1.41455 2.54489 + vertex 1.62402 1.41947 2.54503 + vertex 1.62014 1.41577 2.54615 + endloop + endfacet + facet normal 0.308255 -0.0322707 0.950756 + outer loop + vertex 1.6203 1.42066 2.54628 + vertex 1.62414 1.42435 2.54516 + vertex 1.62064 1.42547 2.54633 + endloop + endfacet + facet normal 0.306552 -0.0318921 0.951319 + outer loop + vertex 1.62794 1.41838 2.54373 + vertex 1.62805 1.42348 2.54387 + vertex 1.62402 1.41947 2.54503 + endloop + endfacet + facet normal 0.302367 -0.0300398 0.952718 + outer loop + vertex 1.63248 1.42273 2.54244 + vertex 1.63198 1.42787 2.54276 + vertex 1.62805 1.42348 2.54387 + endloop + endfacet + facet normal 0.307443 -0.0308637 0.951066 + outer loop + vertex 1.62414 1.42435 2.54516 + vertex 1.62794 1.42849 2.54406 + vertex 1.62417 1.42888 2.54529 + endloop + endfacet + facet normal 0.309896 -0.0307604 0.950273 + outer loop + vertex 1.62361 1.43209 2.54558 + vertex 1.62131 1.42933 2.54624 + vertex 1.62417 1.42888 2.54529 + endloop + endfacet + facet normal 0.30991 -0.0307728 0.950268 + outer loop + vertex 1.62361 1.43209 2.54558 + vertex 1.62075 1.43251 2.54653 + vertex 1.62131 1.42933 2.54624 + endloop + endfacet + facet normal 0.309541 -0.0289287 0.950446 + outer loop + vertex 1.62075 1.43251 2.54653 + vertex 1.62075 1.43703 2.54666 + vertex 1.61698 1.43283 2.54777 + endloop + endfacet + facet normal 0.310344 -0.0260882 0.950266 + outer loop + vertex 1.62746 1.43371 2.54438 + vertex 1.62819 1.43946 2.5443 + vertex 1.62426 1.43597 2.54548 + endloop + endfacet + facet normal 0.302438 -0.0195017 0.952969 + outer loop + vertex 1.62819 1.43946 2.5443 + vertex 1.63217 1.44331 2.54311 + vertex 1.62842 1.4446 2.54433 + endloop + endfacet + facet normal 0.311228 -0.0240334 0.950031 + outer loop + vertex 1.62083 1.44199 2.54676 + vertex 1.62075 1.43703 2.54666 + vertex 1.62457 1.44086 2.54551 + endloop + endfacet + facet normal 0.310993 -0.0179511 0.950243 + outer loop + vertex 1.62083 1.44199 2.54676 + vertex 1.6209 1.44705 2.54684 + vertex 1.61693 1.44308 2.54806 + endloop + endfacet + facet normal 0.311303 -0.0136344 0.950213 + outer loop + vertex 1.62842 1.4446 2.54433 + vertex 1.62846 1.44959 2.54439 + vertex 1.62468 1.44585 2.54557 + endloop + endfacet + facet normal 0.304276 -0.00985684 0.952533 + outer loop + vertex 1.62846 1.44959 2.54439 + vertex 1.63224 1.45329 2.54322 + vertex 1.62846 1.45456 2.54444 + endloop + endfacet + facet normal 0.313565 -0.0134381 0.949472 + outer loop + vertex 1.62094 1.45208 2.54689 + vertex 1.6209 1.44705 2.54684 + vertex 1.6247 1.45084 2.54564 + endloop + endfacet + facet normal 0.313423 -0.0115719 0.949543 + outer loop + vertex 1.62094 1.45208 2.54689 + vertex 1.62096 1.45705 2.54695 + vertex 1.6172 1.45334 2.54814 + endloop + endfacet + facet normal 0.313011 -0.00949045 0.949702 + outer loop + vertex 1.62846 1.45456 2.54444 + vertex 1.62847 1.45953 2.54448 + vertex 1.6247 1.4558 2.54569 + endloop + endfacet + facet normal 0.307482 -0.00978224 0.951504 + outer loop + vertex 1.62847 1.45953 2.54448 + vertex 1.63228 1.46325 2.54329 + vertex 1.6285 1.46451 2.54453 + endloop + endfacet + facet normal 0.31624 -0.011595 0.948608 + outer loop + vertex 1.62098 1.46201 2.547 + vertex 1.62096 1.45705 2.54695 + vertex 1.62472 1.46077 2.54574 + endloop + endfacet + facet normal 0.315474 -0.0104665 0.948877 + outer loop + vertex 1.62098 1.46201 2.547 + vertex 1.62102 1.46699 2.54704 + vertex 1.61726 1.46327 2.54825 + endloop + endfacet + facet normal 0.31552 -0.00902174 0.948876 + outer loop + vertex 1.6285 1.46451 2.54453 + vertex 1.62854 1.46951 2.54456 + vertex 1.62475 1.46575 2.54578 + endloop + endfacet + facet normal 0.308492 -0.00645261 0.951205 + outer loop + vertex 1.62854 1.46951 2.54456 + vertex 1.63235 1.47326 2.54335 + vertex 1.62857 1.47451 2.54458 + endloop + endfacet + facet normal 0.316711 -0.00834286 0.948485 + outer loop + vertex 1.62105 1.47199 2.54708 + vertex 1.62102 1.46699 2.54704 + vertex 1.62479 1.47075 2.54582 + endloop + endfacet + facet normal 0.31662 -0.00606205 0.948533 + outer loop + vertex 1.62105 1.47199 2.54708 + vertex 1.62108 1.47699 2.5471 + vertex 1.61732 1.47324 2.54833 + endloop + endfacet + facet normal 0.315868 -0.0048117 0.948791 + outer loop + vertex 1.62857 1.47451 2.54458 + vertex 1.62859 1.47951 2.5446 + vertex 1.62481 1.47575 2.54584 + endloop + endfacet + facet normal 0.308015 -0.00433466 0.951372 + outer loop + vertex 1.62859 1.47951 2.5446 + vertex 1.6324 1.48325 2.54339 + vertex 1.62861 1.4845 2.54462 + endloop + endfacet + facet normal 0.318352 -0.00518188 0.947958 + outer loop + vertex 1.6211 1.48199 2.54712 + vertex 1.62108 1.47699 2.5471 + vertex 1.62483 1.48075 2.54586 + endloop + endfacet + facet normal 0.318681 -0.00473452 0.94785 + outer loop + vertex 1.6211 1.48199 2.54712 + vertex 1.62112 1.48698 2.54714 + vertex 1.61738 1.48324 2.54838 + endloop + endfacet + facet normal 0.315774 -0.00410577 0.948825 + outer loop + vertex 1.62861 1.4845 2.54462 + vertex 1.62863 1.4895 2.54464 + vertex 1.62485 1.48574 2.54588 + endloop + endfacet + facet normal 0.307671 -0.00349568 0.951486 + outer loop + vertex 1.62863 1.4895 2.54464 + vertex 1.63243 1.49323 2.54342 + vertex 1.62864 1.49449 2.54465 + endloop + endfacet + facet normal 0.319228 -0.00460913 0.947667 + outer loop + vertex 1.62114 1.49197 2.54716 + vertex 1.62112 1.48698 2.54714 + vertex 1.62487 1.49074 2.54589 + endloop + endfacet + facet normal 0.319349 -0.00367168 0.94763 + outer loop + vertex 1.62114 1.49197 2.54716 + vertex 1.62116 1.49696 2.54717 + vertex 1.61742 1.49322 2.54841 + endloop + endfacet + facet normal 0.31698 -0.00184997 0.94843 + outer loop + vertex 1.62864 1.49449 2.54465 + vertex 1.62865 1.49949 2.54466 + vertex 1.62488 1.49573 2.54591 + endloop + endfacet + facet normal 0.310846 -0.000698549 0.95046 + outer loop + vertex 1.62865 1.49949 2.54466 + vertex 1.63243 1.50322 2.54342 + vertex 1.62865 1.50448 2.54466 + endloop + endfacet + facet normal 0.320049 -0.00281774 0.947397 + outer loop + vertex 1.62117 1.50195 2.54718 + vertex 1.62116 1.49696 2.54717 + vertex 1.6249 1.50072 2.54592 + endloop + endfacet + facet normal 0.319179 -0.00204413 0.947692 + outer loop + vertex 1.62117 1.50195 2.54718 + vertex 1.62118 1.50695 2.54719 + vertex 1.61745 1.5032 2.54844 + endloop + endfacet + facet normal 0.319568 -0.000455467 0.947563 + outer loop + vertex 1.62865 1.50448 2.54466 + vertex 1.62865 1.50948 2.54466 + vertex 1.62491 1.50571 2.54592 + endloop + endfacet + facet normal 0.314229 -0.000421243 0.949347 + outer loop + vertex 1.62865 1.50948 2.54466 + vertex 1.63241 1.51321 2.54342 + vertex 1.62866 1.51447 2.54466 + endloop + endfacet + facet normal 0.320831 -0.00148272 0.947135 + outer loop + vertex 1.62119 1.51194 2.54719 + vertex 1.62118 1.50695 2.54719 + vertex 1.62492 1.5107 2.54593 + endloop + endfacet + facet normal 0.317989 -0.00014146 0.948094 + outer loop + vertex 1.62119 1.51194 2.54719 + vertex 1.62118 1.51693 2.5472 + vertex 1.61745 1.51318 2.54845 + endloop + endfacet + facet normal 0.321201 0.000197744 0.947011 + outer loop + vertex 1.62866 1.51447 2.54466 + vertex 1.62866 1.51947 2.54466 + vertex 1.62492 1.5157 2.54593 + endloop + endfacet + facet normal 0.315235 0.000572293 0.949014 + outer loop + vertex 1.62866 1.51947 2.54466 + vertex 1.6324 1.5232 2.54341 + vertex 1.62865 1.52446 2.54466 + endloop + endfacet + facet normal 0.319984 0.00105899 0.947422 + outer loop + vertex 1.62117 1.52192 2.54719 + vertex 1.62118 1.51693 2.5472 + vertex 1.62491 1.52069 2.54593 + endloop + endfacet + facet normal 0.320868 0.00105902 0.947123 + outer loop + vertex 1.62865 1.52446 2.54466 + vertex 1.62864 1.52945 2.54466 + vertex 1.6249 1.52568 2.54593 + endloop + endfacet + facet normal 0.314507 0.00187152 0.949253 + outer loop + vertex 1.62864 1.52945 2.54466 + vertex 1.63239 1.53317 2.54341 + vertex 1.62863 1.53443 2.54465 + endloop + endfacet + facet normal 0.318008 0.00291102 0.948084 + outer loop + vertex 1.62114 1.53191 2.54718 + vertex 1.62115 1.52691 2.54719 + vertex 1.62489 1.53068 2.54592 + endloop + endfacet + facet normal 0.313347 0.00459087 0.949628 + outer loop + vertex 1.62114 1.53191 2.54718 + vertex 1.62112 1.5369 2.54716 + vertex 1.61738 1.53315 2.54841 + endloop + endfacet + facet normal 0.318956 0.00328441 0.947764 + outer loop + vertex 1.62863 1.53443 2.54465 + vertex 1.62861 1.53941 2.54464 + vertex 1.62487 1.53566 2.54591 + endloop + endfacet + facet normal 0.30947 0.00594017 0.950891 + outer loop + vertex 1.62861 1.53941 2.54464 + vertex 1.63237 1.54314 2.54339 + vertex 1.62859 1.54439 2.54462 + endloop + endfacet + facet normal 0.315961 0.00703067 0.948746 + outer loop + vertex 1.62109 1.54189 2.54713 + vertex 1.62112 1.5369 2.54716 + vertex 1.62485 1.54065 2.54589 + endloop + endfacet + facet normal 0.313644 0.00854273 0.949502 + outer loop + vertex 1.62109 1.54189 2.54713 + vertex 1.62106 1.54688 2.5471 + vertex 1.61733 1.54314 2.54836 + endloop + endfacet + facet normal 0.314962 0.00736567 0.949076 + outer loop + vertex 1.62859 1.54439 2.54462 + vertex 1.62857 1.54938 2.54459 + vertex 1.62482 1.54563 2.54586 + endloop + endfacet + facet normal 0.304779 0.00776404 0.952391 + outer loop + vertex 1.62857 1.54938 2.54459 + vertex 1.63237 1.55313 2.54334 + vertex 1.62855 1.55437 2.54455 + endloop + endfacet + facet normal 0.316019 0.00839412 0.948716 + outer loop + vertex 1.62103 1.55187 2.54707 + vertex 1.62106 1.54688 2.5471 + vertex 1.62479 1.55062 2.54582 + endloop + endfacet + facet normal 0.314439 0.0075239 0.949248 + outer loop + vertex 1.62103 1.55187 2.54707 + vertex 1.621 1.55686 2.54704 + vertex 1.61727 1.55312 2.5483 + endloop + endfacet + facet normal 0.313324 0.00730945 0.949618 + outer loop + vertex 1.62855 1.55437 2.54455 + vertex 1.62852 1.55936 2.54452 + vertex 1.62476 1.55561 2.54579 + endloop + endfacet + facet normal 0.304109 0.00796018 0.952604 + outer loop + vertex 1.62852 1.55936 2.54452 + vertex 1.6323 1.56314 2.54328 + vertex 1.62847 1.56436 2.5445 + endloop + endfacet + facet normal 0.3156 0.00815713 0.948857 + outer loop + vertex 1.62095 1.56185 2.54701 + vertex 1.621 1.55686 2.54704 + vertex 1.62473 1.5606 2.54576 + endloop + endfacet + facet normal 0.313966 0.0102556 0.949379 + outer loop + vertex 1.62095 1.56185 2.54701 + vertex 1.62091 1.56685 2.54697 + vertex 1.61719 1.56311 2.54824 + endloop + endfacet + facet normal 0.312964 0.0103455 0.949709 + outer loop + vertex 1.62847 1.56436 2.5445 + vertex 1.6284 1.56935 2.54446 + vertex 1.62467 1.56559 2.54573 + endloop + endfacet + facet normal 0.304484 0.0125991 0.952434 + outer loop + vertex 1.6284 1.56935 2.54446 + vertex 1.63215 1.57313 2.54321 + vertex 1.62838 1.57435 2.54441 + endloop + endfacet + facet normal 0.313235 0.0133865 0.949581 + outer loop + vertex 1.62088 1.57184 2.54691 + vertex 1.62091 1.56685 2.54697 + vertex 1.62463 1.57059 2.54569 + endloop + endfacet + facet normal 0.311246 0.0160638 0.950193 + outer loop + vertex 1.62088 1.57184 2.54691 + vertex 1.62088 1.57682 2.54682 + vertex 1.61715 1.57309 2.54811 + endloop + endfacet + facet normal 0.309285 0.0191893 0.950776 + outer loop + vertex 1.62079 1.58178 2.54675 + vertex 1.62088 1.57682 2.54682 + vertex 1.62462 1.58055 2.54553 + endloop + endfacet + facet normal 0.309719 0.0207128 0.950603 + outer loop + vertex 1.62446 1.5855 2.54547 + vertex 1.62079 1.58178 2.54675 + vertex 1.62462 1.58055 2.54553 + endloop + endfacet + facet normal 0.311338 0.0148564 0.950183 + outer loop + vertex 1.62838 1.57435 2.54441 + vertex 1.62839 1.57933 2.54432 + vertex 1.62463 1.57558 2.54562 + endloop + endfacet + facet normal 0.307993 0.0206641 0.951164 + outer loop + vertex 1.62462 1.58055 2.54553 + vertex 1.62834 1.5843 2.54425 + vertex 1.62446 1.5855 2.54547 + endloop + endfacet + facet normal 0.305645 0.0174155 0.951986 + outer loop + vertex 1.63215 1.57812 2.54314 + vertex 1.63214 1.5831 2.54305 + vertex 1.62839 1.57933 2.54432 + endloop + endfacet + facet normal 0.296757 0.0174539 0.954793 + outer loop + vertex 1.63215 1.57812 2.54314 + vertex 1.63591 1.58188 2.5419 + vertex 1.63214 1.5831 2.54305 + endloop + endfacet + facet normal 0.297997 0.0217315 0.954319 + outer loop + vertex 1.63591 1.58188 2.5419 + vertex 1.63582 1.58682 2.54182 + vertex 1.63214 1.5831 2.54305 + endloop + endfacet + facet normal 0.298188 0.0215256 0.954265 + outer loop + vertex 1.63214 1.5831 2.54305 + vertex 1.63582 1.58682 2.54182 + vertex 1.63198 1.58804 2.54299 + endloop + endfacet + facet normal 0.299604 0.0265409 0.953694 + outer loop + vertex 1.63582 1.58682 2.54182 + vertex 1.6355 1.59177 2.54178 + vertex 1.63198 1.58804 2.54299 + endloop + endfacet + facet normal 0.299026 0.0271404 0.953859 + outer loop + vertex 1.63198 1.58804 2.54299 + vertex 1.6355 1.59177 2.54178 + vertex 1.63153 1.59291 2.54299 + endloop + endfacet + facet normal 0.308803 0.0236384 0.950832 + outer loop + vertex 1.62834 1.5843 2.54425 + vertex 1.62804 1.58927 2.54422 + vertex 1.62446 1.5855 2.54547 + endloop + endfacet + facet normal 0.30691 0.0237791 0.951441 + outer loop + vertex 1.62051 1.58673 2.54672 + vertex 1.62079 1.58178 2.54675 + vertex 1.62446 1.5855 2.54547 + endloop + endfacet + facet normal 0.306505 0.0300519 0.951394 + outer loop + vertex 1.62051 1.58673 2.54672 + vertex 1.61988 1.5919 2.54676 + vertex 1.61664 1.58784 2.54793 + endloop + endfacet + facet normal 0.305207 0.0320117 0.951748 + outer loop + vertex 1.62345 1.59439 2.54553 + vertex 1.62402 1.59037 2.54548 + vertex 1.62739 1.5945 2.54426 + endloop + endfacet + facet normal 0.304856 0.0360164 0.951717 + outer loop + vertex 1.6171 1.59612 2.54749 + vertex 1.61608 1.59158 2.54799 + vertex 1.61988 1.5919 2.54676 + endloop + endfacet + facet normal 0.304345 0.0362149 0.951873 + outer loop + vertex 1.62345 1.59439 2.54553 + vertex 1.62472 1.59883 2.54495 + vertex 1.62112 1.59635 2.5462 + endloop + endfacet + facet normal 0.303893 0.0371968 0.95198 + outer loop + vertex 1.62472 1.59883 2.54495 + vertex 1.62806 1.60299 2.54373 + vertex 1.62403 1.6042 2.54496 + endloop + endfacet + facet normal 0.303237 0.0373588 0.952183 + outer loop + vertex 1.61646 1.60167 2.54748 + vertex 1.6171 1.59612 2.54749 + vertex 1.62052 1.60047 2.54623 + endloop + endfacet + facet normal 0.301586 0.036402 0.952744 + outer loop + vertex 1.61646 1.60167 2.54748 + vertex 1.61618 1.60682 2.54737 + vertex 1.61248 1.60304 2.54868 + endloop + endfacet + facet normal 0.303725 0.0356706 0.952092 + outer loop + vertex 1.62403 1.6042 2.54496 + vertex 1.62369 1.60931 2.54488 + vertex 1.62005 1.60553 2.54618 + endloop + endfacet + facet normal 0.305298 0.0342233 0.951642 + outer loop + vertex 1.62369 1.60931 2.54488 + vertex 1.62736 1.61307 2.54357 + vertex 1.62364 1.61434 2.54472 + endloop + endfacet + facet normal 0.302554 0.0354525 0.952473 + outer loop + vertex 1.61612 1.61186 2.5472 + vertex 1.61618 1.60682 2.54737 + vertex 1.6199 1.6106 2.54605 + endloop + endfacet + facet normal 0.299045 0.0365586 0.953538 + outer loop + vertex 1.61612 1.61186 2.5472 + vertex 1.61608 1.61679 2.54702 + vertex 1.61232 1.61308 2.54834 + endloop + endfacet + facet normal 0.303836 0.0351484 0.952076 + outer loop + vertex 1.62364 1.61434 2.54472 + vertex 1.62364 1.61931 2.54453 + vertex 1.6199 1.6156 2.54586 + endloop + endfacet + facet normal 0.303493 0.0384238 0.952059 + outer loop + vertex 1.62364 1.61931 2.54453 + vertex 1.62735 1.62301 2.5432 + vertex 1.62338 1.62424 2.54442 + endloop + endfacet + facet normal 0.298524 0.0392487 0.953595 + outer loop + vertex 1.61577 1.62153 2.54692 + vertex 1.61608 1.61679 2.54702 + vertex 1.61975 1.62051 2.54572 + endloop + endfacet + facet normal 0.294308 0.0424981 0.954765 + outer loop + vertex 1.61577 1.62153 2.54692 + vertex 1.6151 1.62562 2.54695 + vertex 1.61181 1.6227 2.54809 + endloop + endfacet + facet normal 0.293257 0.0463008 0.954912 + outer loop + vertex 1.6151 1.62562 2.54695 + vertex 1.61663 1.63112 2.54621 + vertex 1.61183 1.62732 2.54787 + endloop + endfacet + facet normal 0.300289 0.0428313 0.952886 + outer loop + vertex 1.62338 1.62424 2.54442 + vertex 1.62256 1.62929 2.54445 + vertex 1.619 1.62539 2.54575 + endloop + endfacet + facet normal 0.301851 0.0440446 0.952337 + outer loop + vertex 1.62705 1.62791 2.54309 + vertex 1.62646 1.63274 2.54305 + vertex 1.62256 1.62929 2.54445 + endloop + endfacet + facet normal 0.302009 0.0440634 0.952286 + outer loop + vertex 1.62705 1.62791 2.54309 + vertex 1.63062 1.63158 2.54179 + vertex 1.62646 1.63274 2.54305 + endloop + endfacet + facet normal 0.30026 0.0475199 0.952673 + outer loop + vertex 1.62198 1.63455 2.54438 + vertex 1.62587 1.6367 2.54305 + vertex 1.62355 1.63871 2.54368 + endloop + endfacet + facet normal 0.302531 0.0462206 0.952018 + outer loop + vertex 1.63062 1.63158 2.54179 + vertex 1.62987 1.63677 2.54177 + vertex 1.62646 1.63274 2.54305 + endloop + endfacet + facet normal 0.301435 0.0490219 0.952226 + outer loop + vertex 1.62587 1.6367 2.54305 + vertex 1.62718 1.6411 2.54241 + vertex 1.62355 1.63871 2.54368 + endloop + endfacet + facet normal 0.300187 0.0511022 0.952511 + outer loop + vertex 1.62718 1.6411 2.54241 + vertex 1.62646 1.64653 2.54234 + vertex 1.623 1.6428 2.54363 + endloop + endfacet + facet normal 0.297347 0.0547049 0.953201 + outer loop + vertex 1.626 1.65167 2.54219 + vertex 1.62646 1.64653 2.54234 + vertex 1.62995 1.65039 2.54103 + endloop + endfacet + facet normal 0.29779 0.0562761 0.952971 + outer loop + vertex 1.62959 1.65544 2.54084 + vertex 1.626 1.65167 2.54219 + vertex 1.62995 1.65039 2.54103 + endloop + endfacet + facet normal 0.29645 0.0515673 0.953655 + outer loop + vertex 1.63463 1.64366 2.53994 + vertex 1.63393 1.64908 2.53987 + vertex 1.63047 1.64532 2.54114 + endloop + endfacet + facet normal 0.295591 0.056143 0.953664 + outer loop + vertex 1.62995 1.65039 2.54103 + vertex 1.63353 1.6542 2.5397 + vertex 1.62959 1.65544 2.54084 + endloop + endfacet + facet normal 0.288406 0.0549612 0.95593 + outer loop + vertex 1.638 1.64789 2.53871 + vertex 1.63749 1.65295 2.53857 + vertex 1.63393 1.64908 2.53987 + endloop + endfacet + facet normal 0.280644 0.0542486 0.958278 + outer loop + vertex 1.638 1.64789 2.53871 + vertex 1.64153 1.65165 2.53746 + vertex 1.63749 1.65295 2.53857 + endloop + endfacet + facet normal 0.281531 0.0573909 0.957834 + outer loop + vertex 1.64153 1.65165 2.53746 + vertex 1.64112 1.65675 2.53728 + vertex 1.63749 1.65295 2.53857 + endloop + endfacet + facet normal 0.281049 0.0578895 0.957946 + outer loop + vertex 1.63749 1.65295 2.53857 + vertex 1.64112 1.65675 2.53728 + vertex 1.63718 1.658 2.53836 + endloop + endfacet + facet normal 0.282485 0.0599002 0.9574 + outer loop + vertex 1.63718 1.658 2.53836 + vertex 1.64083 1.66172 2.53705 + vertex 1.63685 1.66298 2.53814 + endloop + endfacet + facet normal 0.283083 0.0620623 0.957085 + outer loop + vertex 1.64083 1.66172 2.53705 + vertex 1.64043 1.66661 2.53685 + vertex 1.63685 1.66298 2.53814 + endloop + endfacet + facet normal 0.284116 0.0609593 0.95685 + outer loop + vertex 1.63685 1.66298 2.53814 + vertex 1.64043 1.66661 2.53685 + vertex 1.63655 1.6677 2.53793 + endloop + endfacet + facet normal 0.284332 0.0618559 0.956728 + outer loop + vertex 1.64043 1.66661 2.53685 + vertex 1.6397 1.67173 2.53673 + vertex 1.63655 1.6677 2.53793 + endloop + endfacet + facet normal 0.296202 0.0583858 0.953339 + outer loop + vertex 1.63353 1.6542 2.5397 + vertex 1.63318 1.65927 2.53949 + vertex 1.62959 1.65544 2.54084 + endloop + endfacet + facet normal 0.295576 0.0585774 0.953522 + outer loop + vertex 1.6256 1.6567 2.542 + vertex 1.626 1.65167 2.54219 + vertex 1.62959 1.65544 2.54084 + endloop + endfacet + facet normal 0.292784 0.0600551 0.954291 + outer loop + vertex 1.6256 1.6567 2.542 + vertex 1.62492 1.66188 2.54189 + vertex 1.6217 1.65782 2.54313 + endloop + endfacet + facet normal 0.295852 0.059718 0.953365 + outer loop + vertex 1.62853 1.66439 2.54062 + vertex 1.62912 1.66038 2.54068 + vertex 1.63255 1.66462 2.53935 + endloop + endfacet + facet normal 0.295869 0.0594831 0.953375 + outer loop + vertex 1.62853 1.66439 2.54062 + vertex 1.63255 1.66462 2.53935 + vertex 1.62974 1.66881 2.53996 + endloop + endfacet + facet normal 0.292022 0.0599326 0.954532 + outer loop + vertex 1.62615 1.66632 2.54123 + vertex 1.6221 1.66607 2.54249 + vertex 1.62492 1.66188 2.54189 + endloop + endfacet + facet normal 0.289908 0.0595266 0.955202 + outer loop + vertex 1.6221 1.66607 2.54249 + vertex 1.62141 1.67157 2.54235 + vertex 1.61774 1.6678 2.5437 + endloop + endfacet + facet normal 0.290421 0.0609861 0.954953 + outer loop + vertex 1.62099 1.67665 2.54216 + vertex 1.62141 1.67157 2.54235 + vertex 1.62499 1.67542 2.54102 + endloop + endfacet + facet normal 0.294927 0.0592606 0.95368 + outer loop + vertex 1.62974 1.66881 2.53996 + vertex 1.62902 1.67409 2.53986 + vertex 1.62552 1.67041 2.54117 + endloop + endfacet + facet normal 0.293417 0.063417 0.953879 + outer loop + vertex 1.62499 1.67542 2.54102 + vertex 1.62857 1.67914 2.53967 + vertex 1.62458 1.68038 2.54081 + endloop + endfacet + facet normal 0.296877 0.0611484 0.952956 + outer loop + vertex 1.63293 1.67283 2.53872 + vertex 1.6326 1.67775 2.53851 + vertex 1.62902 1.67409 2.53986 + endloop + endfacet + facet normal 0.295563 0.0673757 0.952945 + outer loop + vertex 1.62857 1.67914 2.53967 + vertex 1.6321 1.68283 2.53831 + vertex 1.62808 1.68412 2.53947 + endloop + endfacet + facet normal 0.295479 0.0654891 0.953102 + outer loop + vertex 1.6369 1.67594 2.5373 + vertex 1.63616 1.68146 2.53715 + vertex 1.6326 1.67775 2.53851 + endloop + endfacet + facet normal 0.296074 0.0721894 0.952433 + outer loop + vertex 1.6321 1.68283 2.53831 + vertex 1.63554 1.68656 2.53696 + vertex 1.63151 1.68773 2.53813 + endloop + endfacet + facet normal 0.291877 0.077662 0.953298 + outer loop + vertex 1.63476 1.69179 2.53677 + vertex 1.63554 1.68656 2.53696 + vertex 1.63893 1.69015 2.53563 + endloop + endfacet + facet normal 0.283229 0.0770575 0.955952 + outer loop + vertex 1.64365 1.68395 2.53473 + vertex 1.64292 1.68887 2.53455 + vertex 1.63958 1.68523 2.53583 + endloop + endfacet + facet normal 0.277939 0.0763356 0.957561 + outer loop + vertex 1.64365 1.68395 2.53473 + vertex 1.64692 1.68775 2.53347 + vertex 1.64292 1.68887 2.53455 + endloop + endfacet + facet normal 0.285594 0.0814243 0.954885 + outer loop + vertex 1.6383 1.69416 2.53548 + vertex 1.63893 1.69015 2.53563 + vertex 1.64236 1.69416 2.53426 + endloop + endfacet + facet normal 0.278701 0.0795198 0.95708 + outer loop + vertex 1.64692 1.68775 2.53347 + vertex 1.64594 1.69191 2.53341 + vertex 1.64292 1.68887 2.53455 + endloop + endfacet + facet normal 0.285457 0.0871851 0.954418 + outer loop + vertex 1.6383 1.69416 2.53548 + vertex 1.64236 1.69416 2.53426 + vertex 1.63946 1.6986 2.53473 + endloop + endfacet + facet normal 0.273746 0.0903006 0.957554 + outer loop + vertex 1.64255 1.70291 2.53341 + vertex 1.64573 1.70666 2.53215 + vertex 1.6416 1.7077 2.53323 + endloop + endfacet + facet normal 0.275902 0.0883266 0.957119 + outer loop + vertex 1.64658 1.70183 2.53235 + vertex 1.64573 1.70666 2.53215 + vertex 1.64255 1.70291 2.53341 + endloop + endfacet + facet normal 0.275751 0.0876642 0.957223 + outer loop + vertex 1.64364 1.69882 2.53348 + vertex 1.64658 1.70183 2.53235 + vertex 1.64255 1.70291 2.53341 + endloop + endfacet + facet normal 0.290009 0.0907059 0.952716 + outer loop + vertex 1.63946 1.6986 2.53473 + vertex 1.63835 1.70395 2.53455 + vertex 1.63511 1.7002 2.5359 + endloop + endfacet + facet normal 0.293108 0.0905494 0.951782 + outer loop + vertex 1.63089 1.70142 2.53708 + vertex 1.63199 1.69607 2.53725 + vertex 1.63511 1.7002 2.5359 + endloop + endfacet + facet normal 0.292835 0.0924062 0.951687 + outer loop + vertex 1.63089 1.70142 2.53708 + vertex 1.62982 1.70678 2.53689 + vertex 1.62667 1.70266 2.53826 + endloop + endfacet + facet normal 0.290917 0.0922317 0.952292 + outer loop + vertex 1.63332 1.7092 2.53557 + vertex 1.63412 1.70513 2.53573 + vertex 1.63731 1.70927 2.53435 + endloop + endfacet + facet normal 0.290878 0.0931665 0.952213 + outer loop + vertex 1.63332 1.7092 2.53557 + vertex 1.63731 1.70927 2.53435 + vertex 1.63448 1.71361 2.53479 + endloop + endfacet + facet normal 0.292123 0.0925722 0.95189 + outer loop + vertex 1.63095 1.71121 2.53611 + vertex 1.62698 1.71114 2.53734 + vertex 1.62982 1.70678 2.53689 + endloop + endfacet + facet normal 0.289521 0.0915931 0.952779 + outer loop + vertex 1.62698 1.71114 2.53734 + vertex 1.62594 1.71648 2.53714 + vertex 1.62268 1.71277 2.53849 + endloop + endfacet + facet normal 0.291762 0.0929956 0.951959 + outer loop + vertex 1.6249 1.72183 2.53694 + vertex 1.62594 1.71648 2.53714 + vertex 1.62922 1.72019 2.53577 + endloop + endfacet + facet normal 0.293843 0.093425 0.951277 + outer loop + vertex 1.63448 1.71361 2.53479 + vertex 1.63345 1.71895 2.53458 + vertex 1.63017 1.71527 2.53596 + endloop + endfacet + facet normal 0.295795 0.0947669 0.950539 + outer loop + vertex 1.62841 1.72425 2.53562 + vertex 1.62922 1.72019 2.53577 + vertex 1.63237 1.7243 2.53438 + endloop + endfacet + facet normal 0.292729 0.0967974 0.951283 + outer loop + vertex 1.63769 1.7177 2.53341 + vertex 1.63669 1.72261 2.53321 + vertex 1.63345 1.71895 2.53458 + endloop + endfacet + facet normal 0.285876 0.0954977 0.953496 + outer loop + vertex 1.63769 1.7177 2.53341 + vertex 1.64093 1.72134 2.53207 + vertex 1.63669 1.72261 2.53321 + endloop + endfacet + facet normal 0.295256 0.0996741 0.950205 + outer loop + vertex 1.63237 1.7243 2.53438 + vertex 1.63581 1.72668 2.53306 + vertex 1.63337 1.7287 2.53361 + endloop + endfacet + facet normal 0.287218 0.10085 0.952541 + outer loop + vertex 1.64093 1.72134 2.53207 + vertex 1.63977 1.72668 2.53185 + vertex 1.63669 1.72261 2.53321 + endloop + endfacet + facet normal 0.295872 0.100497 0.949926 + outer loop + vertex 1.63581 1.72668 2.53306 + vertex 1.63672 1.73113 2.53231 + vertex 1.63337 1.7287 2.53361 + endloop + endfacet + facet normal 0.295223 0.103332 0.949824 + outer loop + vertex 1.63672 1.73113 2.53231 + vertex 1.63523 1.73686 2.53215 + vertex 1.63237 1.73267 2.53349 + endloop + endfacet + facet normal 0.28156 0.102878 0.954013 + outer loop + vertex 1.63867 1.73932 2.53083 + vertex 1.63972 1.73522 2.53096 + vertex 1.64285 1.7394 2.52959 + endloop + endfacet + facet normal 0.294292 0.105765 0.949845 + outer loop + vertex 1.63208 1.74144 2.53262 + vertex 1.63107 1.73679 2.53345 + vertex 1.63523 1.73686 2.53215 + endloop + endfacet + facet normal 0.290872 0.107196 0.950738 + outer loop + vertex 1.63117 1.74675 2.5323 + vertex 1.63208 1.74144 2.53262 + vertex 1.63529 1.74542 2.53118 + endloop + endfacet + facet normal 0.289409 0.104231 0.951514 + outer loop + vertex 1.63867 1.73932 2.53083 + vertex 1.63964 1.74372 2.53005 + vertex 1.63614 1.74136 2.53137 + endloop + endfacet + facet normal 0.289574 0.107654 0.951082 + outer loop + vertex 1.63529 1.74542 2.53118 + vertex 1.63854 1.74898 2.52979 + vertex 1.63431 1.75026 2.53093 + endloop + endfacet + facet normal 0.282196 0.10859 0.953191 + outer loop + vertex 1.64354 1.7439 2.52887 + vertex 1.64267 1.74769 2.5287 + vertex 1.63964 1.74372 2.53005 + endloop + endfacet + facet normal 0.286127 0.110085 0.951847 + outer loop + vertex 1.63854 1.74898 2.52979 + vertex 1.64188 1.75251 2.52838 + vertex 1.63744 1.7543 2.52951 + endloop + endfacet + facet normal 0.275746 0.109358 0.954989 + outer loop + vertex 1.64586 1.74627 2.52794 + vertex 1.64653 1.75078 2.52723 + vertex 1.64267 1.74769 2.5287 + endloop + endfacet + facet normal 0.268411 0.114178 0.956514 + outer loop + vertex 1.64502 1.75661 2.52696 + vertex 1.64653 1.75078 2.52723 + vertex 1.64961 1.75497 2.52587 + endloop + endfacet + facet normal 0.270265 0.120195 0.955254 + outer loop + vertex 1.64961 1.75497 2.52587 + vertex 1.64847 1.75904 2.52568 + vertex 1.64502 1.75661 2.52696 + endloop + endfacet + facet normal 0.269549 0.121247 0.955323 + outer loop + vertex 1.64582 1.76111 2.52617 + vertex 1.64502 1.75661 2.52696 + vertex 1.64847 1.75904 2.52568 + endloop + endfacet + facet normal 0.262382 0.118106 0.957709 + outer loop + vertex 1.64847 1.75904 2.52568 + vertex 1.64961 1.75497 2.52587 + vertex 1.65261 1.75909 2.52454 + endloop + endfacet + facet normal 0.262275 0.120682 0.957417 + outer loop + vertex 1.64847 1.75904 2.52568 + vertex 1.65261 1.75909 2.52454 + vertex 1.64924 1.76353 2.5249 + endloop + endfacet + facet normal 0.260426 0.119225 0.958104 + outer loop + vertex 1.64924 1.76353 2.5249 + vertex 1.65261 1.75909 2.52454 + vertex 1.65342 1.76356 2.52376 + endloop + endfacet + facet normal 0.269151 0.112788 0.956471 + outer loop + vertex 1.65412 1.75351 2.52477 + vertex 1.65261 1.75909 2.52454 + vertex 1.64961 1.75497 2.52587 + endloop + endfacet + facet normal 0.266396 0.115781 0.956884 + outer loop + vertex 1.64961 1.75497 2.52587 + vertex 1.64653 1.75078 2.52723 + vertex 1.65069 1.75094 2.52606 + endloop + endfacet + facet normal 0.287898 0.115197 0.950707 + outer loop + vertex 1.64188 1.75251 2.52838 + vertex 1.64093 1.75668 2.52816 + vertex 1.63744 1.7543 2.52951 + endloop + endfacet + facet normal 0.290308 0.115453 0.949943 + outer loop + vertex 1.63345 1.75426 2.53073 + vertex 1.63744 1.7543 2.52951 + vertex 1.63444 1.7586 2.5299 + endloop + endfacet + facet normal 0.287879 0.119763 0.950149 + outer loop + vertex 1.6384 1.75871 2.52868 + vertex 1.64175 1.76114 2.52736 + vertex 1.63733 1.76265 2.52851 + endloop + endfacet + facet normal 0.288801 0.120249 0.949807 + outer loop + vertex 1.63444 1.7586 2.5299 + vertex 1.63322 1.76371 2.52962 + vertex 1.63013 1.76019 2.53101 + endloop + endfacet + facet normal 0.285622 0.117758 0.95108 + outer loop + vertex 1.62592 1.76137 2.53213 + vertex 1.62703 1.75612 2.53244 + vertex 1.63013 1.76019 2.53101 + endloop + endfacet + facet normal 0.285099 0.121141 0.950812 + outer loop + vertex 1.62592 1.76137 2.53213 + vertex 1.62476 1.76661 2.53181 + vertex 1.62169 1.76254 2.53325 + endloop + endfacet + facet normal 0.288814 0.123179 0.949428 + outer loop + vertex 1.6282 1.76899 2.53046 + vertex 1.62911 1.76498 2.53071 + vertex 1.63225 1.76896 2.52923 + endloop + endfacet + facet normal 0.284483 0.12224 0.950856 + outer loop + vertex 1.62163 1.77094 2.53219 + vertex 1.62079 1.76652 2.53301 + vertex 1.62476 1.76661 2.53181 + endloop + endfacet + facet normal 0.285791 0.117881 0.951014 + outer loop + vertex 1.62008 1.77659 2.53195 + vertex 1.62163 1.77094 2.53219 + vertex 1.62457 1.77501 2.5308 + endloop + endfacet + facet normal 0.283501 0.110261 0.952612 + outer loop + vertex 1.62457 1.77501 2.5308 + vertex 1.62349 1.77906 2.53065 + vertex 1.62008 1.77659 2.53195 + endloop + endfacet + facet normal 0.286888 0.105341 0.952155 + outer loop + vertex 1.621 1.78109 2.53118 + vertex 1.62008 1.77659 2.53195 + vertex 1.62349 1.77906 2.53065 + endloop + endfacet + facet normal 0.282911 0.100003 0.953919 + outer loop + vertex 1.62349 1.77906 2.53065 + vertex 1.62451 1.78351 2.52989 + vertex 1.621 1.78109 2.53118 + endloop + endfacet + facet normal 0.286428 0.0946348 0.953417 + outer loop + vertex 1.621 1.78109 2.53118 + vertex 1.62451 1.78351 2.52989 + vertex 1.62018 1.78519 2.53102 + endloop + endfacet + facet normal 0.283493 0.0940864 0.954348 + outer loop + vertex 1.62018 1.78519 2.53102 + vertex 1.61701 1.78102 2.53237 + vertex 1.621 1.78109 2.53118 + endloop + endfacet + facet normal 0.282963 0.106323 0.953219 + outer loop + vertex 1.621 1.78109 2.53118 + vertex 1.61701 1.78102 2.53237 + vertex 1.62008 1.77659 2.53195 + endloop + endfacet + facet normal 0.286119 0.121538 0.950455 + outer loop + vertex 1.6282 1.76899 2.53046 + vertex 1.62905 1.77344 2.52964 + vertex 1.62567 1.77098 2.53097 + endloop + endfacet + facet normal 0.286481 0.111017 0.951632 + outer loop + vertex 1.62349 1.77906 2.53065 + vertex 1.62457 1.77501 2.5308 + vertex 1.62752 1.77909 2.52944 + endloop + endfacet + facet normal 0.290918 0.114595 0.94986 + outer loop + vertex 1.63322 1.77356 2.52835 + vertex 1.6319 1.77761 2.52826 + vertex 1.62905 1.77344 2.52964 + endloop + endfacet + facet normal 0.291955 0.114924 0.949502 + outer loop + vertex 1.63322 1.77356 2.52835 + vertex 1.63599 1.77655 2.52714 + vertex 1.6319 1.77761 2.52826 + endloop + endfacet + facet normal 0.290029 0.105801 0.951152 + outer loop + vertex 1.63599 1.77655 2.52714 + vertex 1.63484 1.78166 2.52692 + vertex 1.6319 1.77761 2.52826 + endloop + endfacet + facet normal 0.291094 0.10495 0.950921 + outer loop + vertex 1.6319 1.77761 2.52826 + vertex 1.63484 1.78166 2.52692 + vertex 1.6309 1.78155 2.52813 + endloop + endfacet + facet normal 0.291714 0.093431 0.951931 + outer loop + vertex 1.63197 1.78598 2.52737 + vertex 1.6309 1.78155 2.52813 + vertex 1.63484 1.78166 2.52692 + endloop + endfacet + facet normal 0.292935 0.0942906 0.951472 + outer loop + vertex 1.63593 1.78604 2.52615 + vertex 1.63197 1.78598 2.52737 + vertex 1.63484 1.78166 2.52692 + endloop + endfacet + facet normal 0.294958 0.0936869 0.950906 + outer loop + vertex 1.63593 1.78604 2.52615 + vertex 1.63484 1.78166 2.52692 + vertex 1.63831 1.78404 2.52561 + endloop + endfacet + facet normal 0.290994 0.0885038 0.952622 + outer loop + vertex 1.63831 1.78404 2.52561 + vertex 1.63948 1.78847 2.52484 + vertex 1.63593 1.78604 2.52615 + endloop + endfacet + facet normal 0.288109 0.0894081 0.953415 + outer loop + vertex 1.63831 1.78404 2.52561 + vertex 1.64229 1.78415 2.52439 + vertex 1.63948 1.78847 2.52484 + endloop + endfacet + facet normal 0.291018 0.0997412 0.951504 + outer loop + vertex 1.63911 1.78006 2.52578 + vertex 1.63831 1.78404 2.52561 + vertex 1.63484 1.78166 2.52692 + endloop + endfacet + facet normal 0.286939 0.0988943 0.952831 + outer loop + vertex 1.62349 1.77906 2.53065 + vertex 1.62752 1.77909 2.52944 + vertex 1.62451 1.78351 2.52989 + endloop + endfacet + facet normal 0.288947 0.0906737 0.953041 + outer loop + vertex 1.62451 1.78351 2.52989 + vertex 1.62768 1.78765 2.52853 + vertex 1.62348 1.78889 2.52968 + endloop + endfacet + facet normal 0.289394 0.0941013 0.952573 + outer loop + vertex 1.6309 1.78155 2.52813 + vertex 1.63197 1.78598 2.52737 + vertex 1.62847 1.78355 2.52868 + endloop + endfacet + facet normal 0.289956 0.0889497 0.952897 + outer loop + vertex 1.62768 1.78765 2.52853 + vertex 1.63098 1.79137 2.52718 + vertex 1.62677 1.79259 2.52834 + endloop + endfacet + facet normal 0.287566 0.0978918 0.952745 + outer loop + vertex 1.63849 1.79384 2.52464 + vertex 1.64176 1.79753 2.52328 + vertex 1.6374 1.79919 2.52442 + endloop + endfacet + facet normal 0.29358 0.0990409 0.95079 + outer loop + vertex 1.63849 1.79384 2.52464 + vertex 1.6374 1.79919 2.52442 + vertex 1.63427 1.79508 2.52582 + endloop + endfacet + facet normal 0.29125 0.0895386 0.952448 + outer loop + vertex 1.63518 1.79013 2.526 + vertex 1.63849 1.79384 2.52464 + vertex 1.63427 1.79508 2.52582 + endloop + endfacet + facet normal 0.292514 0.0897574 0.952039 + outer loop + vertex 1.63427 1.79508 2.52582 + vertex 1.63098 1.79137 2.52718 + vertex 1.63518 1.79013 2.526 + endloop + endfacet + facet normal 0.288913 0.0932257 0.952806 + outer loop + vertex 1.62993 1.79673 2.52697 + vertex 1.63098 1.79137 2.52718 + vertex 1.63427 1.79508 2.52582 + endloop + endfacet + facet normal 0.292376 0.100048 0.951056 + outer loop + vertex 1.63342 1.79916 2.52565 + vertex 1.63427 1.79508 2.52582 + vertex 1.6374 1.79919 2.52442 + endloop + endfacet + facet normal 0.291041 0.108503 0.950538 + outer loop + vertex 1.64176 1.79753 2.52328 + vertex 1.64086 1.80157 2.52309 + vertex 1.6374 1.79919 2.52442 + endloop + endfacet + facet normal 0.286112 0.116012 0.951147 + outer loop + vertex 1.6374 1.79919 2.52442 + vertex 1.64086 1.80157 2.52309 + vertex 1.63834 1.80357 2.52361 + endloop + endfacet + facet normal 0.288057 0.115494 0.950623 + outer loop + vertex 1.6343 1.80357 2.52483 + vertex 1.6374 1.79919 2.52442 + vertex 1.63834 1.80357 2.52361 + endloop + endfacet + facet normal 0.292489 0.124828 0.948087 + outer loop + vertex 1.64086 1.80157 2.52309 + vertex 1.64169 1.80597 2.52226 + vertex 1.63834 1.80357 2.52361 + endloop + endfacet + facet normal 0.287707 0.131802 0.948606 + outer loop + vertex 1.63834 1.80357 2.52361 + vertex 1.64169 1.80597 2.52226 + vertex 1.6372 1.80756 2.5234 + endloop + endfacet + facet normal 0.287454 0.131734 0.948692 + outer loop + vertex 1.63834 1.80357 2.52361 + vertex 1.6372 1.80756 2.5234 + vertex 1.6343 1.80357 2.52483 + endloop + endfacet + facet normal 0.289761 0.138748 0.946989 + outer loop + vertex 1.64169 1.80597 2.52226 + vertex 1.64003 1.81156 2.52195 + vertex 1.6372 1.80756 2.5234 + endloop + endfacet + facet normal 0.287397 0.140586 0.947438 + outer loop + vertex 1.6372 1.80756 2.5234 + vertex 1.64003 1.81156 2.52195 + vertex 1.63599 1.81155 2.52317 + endloop + endfacet + facet normal 0.287123 0.140508 0.947533 + outer loop + vertex 1.6372 1.80756 2.5234 + vertex 1.63599 1.81155 2.52317 + vertex 1.63266 1.80915 2.52454 + endloop + endfacet + facet normal 0.284734 0.143941 0.947738 + outer loop + vertex 1.63266 1.80915 2.52454 + vertex 1.63599 1.81155 2.52317 + vertex 1.63334 1.81355 2.52366 + endloop + endfacet + facet normal 0.285846 0.145564 0.947155 + outer loop + vertex 1.63599 1.81155 2.52317 + vertex 1.63666 1.81595 2.5223 + vertex 1.63334 1.81355 2.52366 + endloop + endfacet + facet normal 0.284822 0.147025 0.947238 + outer loop + vertex 1.63334 1.81355 2.52366 + vertex 1.63666 1.81595 2.5223 + vertex 1.63212 1.81753 2.52341 + endloop + endfacet + facet normal 0.285129 0.147112 0.947132 + outer loop + vertex 1.63334 1.81355 2.52366 + vertex 1.63212 1.81753 2.52341 + vertex 1.62928 1.81354 2.52489 + endloop + endfacet + facet normal 0.2843 0.147758 0.947281 + outer loop + vertex 1.62928 1.81354 2.52489 + vertex 1.63212 1.81753 2.52341 + vertex 1.62758 1.81911 2.52453 + endloop + endfacet + facet normal 0.284564 0.147832 0.94719 + outer loop + vertex 1.62928 1.81354 2.52489 + vertex 1.62758 1.81911 2.52453 + vertex 1.62472 1.81512 2.52601 + endloop + endfacet + facet normal 0.284281 0.148054 0.94724 + outer loop + vertex 1.62351 1.8191 2.52575 + vertex 1.62472 1.81512 2.52601 + vertex 1.62758 1.81911 2.52453 + endloop + endfacet + facet normal 0.284304 0.147549 0.947312 + outer loop + vertex 1.62351 1.8191 2.52575 + vertex 1.62758 1.81911 2.52453 + vertex 1.62424 1.82348 2.52485 + endloop + endfacet + facet normal 0.284329 0.147543 0.947306 + outer loop + vertex 1.62351 1.8191 2.52575 + vertex 1.62424 1.82348 2.52485 + vertex 1.62086 1.82111 2.52623 + endloop + endfacet + facet normal 0.284933 0.148417 0.946988 + outer loop + vertex 1.62086 1.82111 2.52623 + vertex 1.62015 1.81669 2.52714 + vertex 1.62351 1.8191 2.52575 + endloop + endfacet + facet normal 0.28516 0.148368 0.946927 + outer loop + vertex 1.62086 1.82111 2.52623 + vertex 1.61668 1.82121 2.52748 + vertex 1.62015 1.81669 2.52714 + endloop + endfacet + facet normal 0.28583 0.148902 0.946641 + outer loop + vertex 1.61668 1.82121 2.52748 + vertex 1.61594 1.8166 2.52843 + vertex 1.62015 1.81669 2.52714 + endloop + endfacet + facet normal 0.285149 0.148887 0.946849 + outer loop + vertex 1.61968 1.82509 2.52596 + vertex 1.61668 1.82121 2.52748 + vertex 1.62086 1.82111 2.52623 + endloop + endfacet + facet normal 0.283105 0.150601 0.947191 + outer loop + vertex 1.61522 1.82674 2.52704 + vertex 1.61668 1.82121 2.52748 + vertex 1.61968 1.82509 2.52596 + endloop + endfacet + facet normal 0.282809 0.149644 0.947431 + outer loop + vertex 1.61968 1.82509 2.52596 + vertex 1.6185 1.82904 2.52569 + vertex 1.61522 1.82674 2.52704 + endloop + endfacet + facet normal 0.281257 0.15192 0.947531 + outer loop + vertex 1.61585 1.83099 2.52617 + vertex 1.61522 1.82674 2.52704 + vertex 1.6185 1.82904 2.52569 + endloop + endfacet + facet normal 0.280295 0.150492 0.948044 + outer loop + vertex 1.6185 1.82904 2.52569 + vertex 1.61921 1.8334 2.52479 + vertex 1.61585 1.83099 2.52617 + endloop + endfacet + facet normal 0.278787 0.152658 0.948142 + outer loop + vertex 1.61585 1.83099 2.52617 + vertex 1.61921 1.8334 2.52479 + vertex 1.61462 1.83493 2.52589 + endloop + endfacet + facet normal 0.280065 0.153028 0.947706 + outer loop + vertex 1.61462 1.83493 2.52589 + vertex 1.61181 1.83092 2.52737 + vertex 1.61585 1.83099 2.52617 + endloop + endfacet + facet normal 0.279036 0.153814 0.947882 + outer loop + vertex 1.61006 1.83644 2.52699 + vertex 1.61181 1.83092 2.52737 + vertex 1.61462 1.83493 2.52589 + endloop + endfacet + facet normal 0.279004 0.153698 0.94791 + outer loop + vertex 1.61462 1.83493 2.52589 + vertex 1.61339 1.83887 2.52562 + vertex 1.61006 1.83644 2.52699 + endloop + endfacet + facet normal 0.278384 0.154575 0.94795 + outer loop + vertex 1.61075 1.84082 2.52607 + vertex 1.61006 1.83644 2.52699 + vertex 1.61339 1.83887 2.52562 + endloop + endfacet + facet normal 0.277885 0.15384 0.948216 + outer loop + vertex 1.61339 1.83887 2.52562 + vertex 1.61401 1.84318 2.52474 + vertex 1.61075 1.84082 2.52607 + endloop + endfacet + facet normal 0.278272 0.153291 0.948191 + outer loop + vertex 1.61075 1.84082 2.52607 + vertex 1.61401 1.84318 2.52474 + vertex 1.60949 1.84485 2.52579 + endloop + endfacet + facet normal 0.284679 0.155151 0.945984 + outer loop + vertex 1.60949 1.84485 2.52579 + vertex 1.60669 1.84085 2.52729 + vertex 1.61075 1.84082 2.52607 + endloop + endfacet + facet normal 0.287691 0.152848 0.945448 + outer loop + vertex 1.60483 1.84657 2.52693 + vertex 1.60669 1.84085 2.52729 + vertex 1.60949 1.84485 2.52579 + endloop + endfacet + facet normal 0.279208 0.156319 0.947421 + outer loop + vertex 1.61401 1.84318 2.52474 + vertex 1.61234 1.84883 2.5243 + vertex 1.60949 1.84485 2.52579 + endloop + endfacet + facet normal 0.279941 0.155748 0.947299 + outer loop + vertex 1.60809 1.84895 2.52553 + vertex 1.60949 1.84485 2.52579 + vertex 1.61234 1.84883 2.5243 + endloop + endfacet + facet normal 0.275965 0.155443 0.948515 + outer loop + vertex 1.61401 1.84318 2.52474 + vertex 1.61648 1.84657 2.52346 + vertex 1.61234 1.84883 2.5243 + endloop + endfacet + facet normal 0.27707 0.157723 0.947816 + outer loop + vertex 1.61648 1.84657 2.52346 + vertex 1.61698 1.85116 2.52255 + vertex 1.61234 1.84883 2.5243 + endloop + endfacet + facet normal 0.276753 0.158346 0.947805 + outer loop + vertex 1.61234 1.84883 2.5243 + vertex 1.61698 1.85116 2.52255 + vertex 1.61285 1.85341 2.52338 + endloop + endfacet + facet normal 0.279493 0.157894 0.947076 + outer loop + vertex 1.6084 1.8537 2.52465 + vertex 1.61234 1.84883 2.5243 + vertex 1.61285 1.85341 2.52338 + endloop + endfacet + facet normal 0.279577 0.163487 0.946102 + outer loop + vertex 1.61285 1.85341 2.52338 + vertex 1.61136 1.85661 2.52327 + vertex 1.6084 1.8537 2.52465 + endloop + endfacet + facet normal 0.280214 0.162805 0.946031 + outer loop + vertex 1.6084 1.8537 2.52465 + vertex 1.61136 1.85661 2.52327 + vertex 1.60863 1.8584 2.52377 + endloop + endfacet + facet normal 0.280853 0.163883 0.945655 + outer loop + vertex 1.61136 1.85661 2.52327 + vertex 1.61177 1.86091 2.5224 + vertex 1.60863 1.8584 2.52377 + endloop + endfacet + facet normal 0.282708 0.161489 0.945514 + outer loop + vertex 1.60863 1.8584 2.52377 + vertex 1.61177 1.86091 2.5224 + vertex 1.60717 1.86249 2.52351 + endloop + endfacet + facet normal 0.284493 0.167828 0.943874 + outer loop + vertex 1.61177 1.86091 2.5224 + vertex 1.6098 1.86652 2.522 + vertex 1.60717 1.86249 2.52351 + endloop + endfacet + facet normal 0.278969 0.16602 0.94584 + outer loop + vertex 1.6098 1.86652 2.522 + vertex 1.61177 1.86091 2.5224 + vertex 1.61446 1.86489 2.52091 + endloop + endfacet + facet normal 0.275577 0.168518 0.946393 + outer loop + vertex 1.61446 1.86489 2.52091 + vertex 1.61177 1.86091 2.5224 + vertex 1.61579 1.86098 2.52122 + endloop + endfacet + facet normal 0.278115 0.169312 0.945508 + outer loop + vertex 1.61579 1.86098 2.52122 + vertex 1.61899 1.86329 2.51986 + vertex 1.61446 1.86489 2.52091 + endloop + endfacet + facet normal 0.278165 0.169482 0.945463 + outer loop + vertex 1.61899 1.86329 2.51986 + vertex 1.61727 1.86885 2.51937 + vertex 1.61446 1.86489 2.52091 + endloop + endfacet + facet normal 0.277783 0.169775 0.945523 + outer loop + vertex 1.61306 1.8689 2.5206 + vertex 1.61446 1.86489 2.52091 + vertex 1.61727 1.86885 2.51937 + endloop + endfacet + facet normal 0.280321 0.170083 0.944718 + outer loop + vertex 1.61899 1.86329 2.51986 + vertex 1.6213 1.86677 2.51855 + vertex 1.61727 1.86885 2.51937 + endloop + endfacet + facet normal 0.28078 0.171094 0.944399 + outer loop + vertex 1.6213 1.86677 2.51855 + vertex 1.6218 1.87125 2.51759 + vertex 1.61727 1.86885 2.51937 + endloop + endfacet + facet normal 0.280852 0.170959 0.944402 + outer loop + vertex 1.61727 1.86885 2.51937 + vertex 1.6218 1.87125 2.51759 + vertex 1.61781 1.87335 2.5184 + endloop + endfacet + facet normal 0.280172 0.171079 0.944582 + outer loop + vertex 1.6134 1.8736 2.51966 + vertex 1.61727 1.86885 2.51937 + vertex 1.61781 1.87335 2.5184 + endloop + endfacet + facet normal 0.280181 0.173827 0.944078 + outer loop + vertex 1.61781 1.87335 2.5184 + vertex 1.61636 1.8765 2.51825 + vertex 1.6134 1.8736 2.51966 + endloop + endfacet + facet normal 0.279878 0.173692 0.944192 + outer loop + vertex 1.61781 1.87335 2.5184 + vertex 1.62022 1.87666 2.51708 + vertex 1.61636 1.8765 2.51825 + endloop + endfacet + facet normal 0.279763 0.174986 0.943988 + outer loop + vertex 1.61675 1.88078 2.51734 + vertex 1.61636 1.8765 2.51825 + vertex 1.62022 1.87666 2.51708 + endloop + endfacet + facet normal 0.279529 0.174782 0.944095 + outer loop + vertex 1.62075 1.88084 2.51614 + vertex 1.61675 1.88078 2.51734 + vertex 1.62022 1.87666 2.51708 + endloop + endfacet + facet normal 0.279643 0.174761 0.944065 + outer loop + vertex 1.62075 1.88084 2.51614 + vertex 1.62022 1.87666 2.51708 + vertex 1.62343 1.87891 2.51571 + endloop + endfacet + facet normal 0.280522 0.176094 0.943556 + outer loop + vertex 1.62343 1.87891 2.51571 + vertex 1.62394 1.88315 2.51477 + vertex 1.62075 1.88084 2.51614 + endloop + endfacet + facet normal 0.279582 0.177414 0.943588 + outer loop + vertex 1.62075 1.88084 2.51614 + vertex 1.62394 1.88315 2.51477 + vertex 1.6194 1.88476 2.51581 + endloop + endfacet + facet normal 0.279513 0.177177 0.943653 + outer loop + vertex 1.62394 1.88315 2.51477 + vertex 1.62217 1.88872 2.51424 + vertex 1.6194 1.88476 2.51581 + endloop + endfacet + facet normal 0.278978 0.177583 0.943735 + outer loop + vertex 1.61796 1.88878 2.51548 + vertex 1.6194 1.88476 2.51581 + vertex 1.62217 1.88872 2.51424 + endloop + endfacet + facet normal 0.28059 0.177483 0.943276 + outer loop + vertex 1.62394 1.88315 2.51477 + vertex 1.62623 1.88661 2.51343 + vertex 1.62217 1.88872 2.51424 + endloop + endfacet + facet normal 0.281003 0.178389 0.942982 + outer loop + vertex 1.62623 1.88661 2.51343 + vertex 1.62668 1.89111 2.51245 + vertex 1.62217 1.88872 2.51424 + endloop + endfacet + facet normal 0.28201 0.176524 0.943032 + outer loop + vertex 1.62217 1.88872 2.51424 + vertex 1.62668 1.89111 2.51245 + vertex 1.62263 1.89327 2.51326 + endloop + endfacet + facet normal 0.280324 0.17679 0.943485 + outer loop + vertex 1.6182 1.89348 2.51453 + vertex 1.62217 1.88872 2.51424 + vertex 1.62263 1.89327 2.51326 + endloop + endfacet + facet normal 0.280333 0.17551 0.943721 + outer loop + vertex 1.62263 1.89327 2.51326 + vertex 1.62102 1.89651 2.51313 + vertex 1.6182 1.89348 2.51453 + endloop + endfacet + facet normal 0.2816 0.174264 0.943575 + outer loop + vertex 1.6182 1.89348 2.51453 + vertex 1.62102 1.89651 2.51313 + vertex 1.61823 1.89811 2.51367 + endloop + endfacet + facet normal 0.281291 0.173659 0.943779 + outer loop + vertex 1.62102 1.89651 2.51313 + vertex 1.62103 1.90115 2.51227 + vertex 1.61823 1.89811 2.51367 + endloop + endfacet + facet normal 0.283413 0.171583 0.943523 + outer loop + vertex 1.61823 1.89811 2.51367 + vertex 1.62103 1.90115 2.51227 + vertex 1.61657 1.90144 2.51356 + endloop + endfacet + facet normal 0.282134 0.173611 0.943536 + outer loop + vertex 1.62103 1.90115 2.51227 + vertex 1.62102 1.89651 2.51313 + vertex 1.62492 1.89664 2.51194 + endloop + endfacet + facet normal 0.283423 0.174766 0.942936 + outer loop + vertex 1.62529 1.90082 2.51105 + vertex 1.62103 1.90115 2.51227 + vertex 1.62492 1.89664 2.51194 + endloop + endfacet + facet normal 0.286451 0.174323 0.942103 + outer loop + vertex 1.62529 1.90082 2.51105 + vertex 1.62492 1.89664 2.51194 + vertex 1.62808 1.89892 2.51056 + endloop + endfacet + facet normal 0.286419 0.174272 0.942122 + outer loop + vertex 1.62808 1.89892 2.51056 + vertex 1.62828 1.90359 2.50963 + vertex 1.62529 1.90082 2.51105 + endloop + endfacet + facet normal 0.286631 0.174032 0.942102 + outer loop + vertex 1.62404 1.9039 2.51086 + vertex 1.62529 1.90082 2.51105 + vertex 1.62828 1.90359 2.50963 + endloop + endfacet + facet normal 0.286605 0.172664 0.942361 + outer loop + vertex 1.62404 1.9039 2.51086 + vertex 1.62828 1.90359 2.50963 + vertex 1.62437 1.90814 2.50999 + endloop + endfacet + facet normal 0.286143 0.172252 0.942577 + outer loop + vertex 1.62437 1.90814 2.50999 + vertex 1.62828 1.90359 2.50963 + vertex 1.62828 1.90825 2.50878 + endloop + endfacet + facet normal 0.286102 0.172783 0.942492 + outer loop + vertex 1.62828 1.90825 2.50878 + vertex 1.62664 1.91155 2.50867 + vertex 1.62437 1.90814 2.50999 + endloop + endfacet + facet normal 0.283585 0.174614 0.942915 + outer loop + vertex 1.62437 1.90814 2.50999 + vertex 1.62664 1.91155 2.50867 + vertex 1.62245 1.91386 2.50951 + endloop + endfacet + facet normal 0.284482 0.176462 0.942301 + outer loop + vertex 1.62664 1.91155 2.50867 + vertex 1.62701 1.91615 2.5077 + vertex 1.62245 1.91386 2.50951 + endloop + endfacet + facet normal 0.283786 0.177811 0.942257 + outer loop + vertex 1.62245 1.91386 2.50951 + vertex 1.62701 1.91615 2.5077 + vertex 1.62283 1.91844 2.50853 + endloop + endfacet + facet normal 0.285429 0.181226 0.94111 + outer loop + vertex 1.62701 1.91615 2.5077 + vertex 1.62508 1.92181 2.5072 + vertex 1.62283 1.91844 2.50853 + endloop + endfacet + facet normal 0.283037 0.182974 0.941494 + outer loop + vertex 1.62283 1.91844 2.50853 + vertex 1.62508 1.92181 2.5072 + vertex 1.62117 1.92169 2.5084 + endloop + endfacet + facet normal 0.282811 0.185657 0.941036 + outer loop + vertex 1.62116 1.92628 2.50749 + vertex 1.62117 1.92169 2.5084 + vertex 1.62508 1.92181 2.5072 + endloop + endfacet + facet normal 0.282529 0.1854 0.941172 + outer loop + vertex 1.62539 1.92598 2.50628 + vertex 1.62116 1.92628 2.50749 + vertex 1.62508 1.92181 2.5072 + endloop + endfacet + facet normal 0.283092 0.185323 0.941017 + outer loop + vertex 1.62539 1.92598 2.50628 + vertex 1.62508 1.92181 2.5072 + vertex 1.62821 1.9241 2.50581 + endloop + endfacet + facet normal 0.284802 0.188157 0.939939 + outer loop + vertex 1.62821 1.9241 2.50581 + vertex 1.62835 1.9287 2.50484 + vertex 1.62539 1.92598 2.50628 + endloop + endfacet + facet normal 0.283238 0.189925 0.940056 + outer loop + vertex 1.62413 1.92899 2.50605 + vertex 1.62539 1.92598 2.50628 + vertex 1.62835 1.9287 2.50484 + endloop + endfacet + facet normal 0.283256 0.191653 0.939699 + outer loop + vertex 1.62413 1.92899 2.50605 + vertex 1.62835 1.9287 2.50484 + vertex 1.62443 1.93314 2.50512 + endloop + endfacet + facet normal 0.282065 0.190567 0.940278 + outer loop + vertex 1.62443 1.93314 2.50512 + vertex 1.62835 1.9287 2.50484 + vertex 1.62832 1.93326 2.50393 + endloop + endfacet + facet normal 0.282585 0.18967 0.940304 + outer loop + vertex 1.62539 1.92598 2.50628 + vertex 1.62413 1.92899 2.50605 + vertex 1.62116 1.92628 2.50749 + endloop + endfacet + facet normal 0.283378 0.172791 0.943313 + outer loop + vertex 1.62529 1.90082 2.51105 + vertex 1.62404 1.9039 2.51086 + vertex 1.62103 1.90115 2.51227 + endloop + endfacet + facet normal 0.281914 0.17627 0.943108 + outer loop + vertex 1.62263 1.89327 2.51326 + vertex 1.62492 1.89664 2.51194 + vertex 1.62102 1.89651 2.51313 + endloop + endfacet + facet normal 0.281897 0.176283 0.943111 + outer loop + vertex 1.62668 1.89111 2.51245 + vertex 1.62492 1.89664 2.51194 + vertex 1.62263 1.89327 2.51326 + endloop + endfacet + facet normal 0.286426 0.177577 0.941502 + outer loop + vertex 1.62492 1.89664 2.51194 + vertex 1.62668 1.89111 2.51245 + vertex 1.6295 1.8949 2.51087 + endloop + endfacet + facet normal 0.285727 0.175349 0.942132 + outer loop + vertex 1.6295 1.8949 2.51087 + vertex 1.62808 1.89892 2.51056 + vertex 1.62492 1.89664 2.51194 + endloop + endfacet + facet normal 0.28902 0.176415 0.940928 + outer loop + vertex 1.62808 1.89892 2.51056 + vertex 1.6295 1.8949 2.51087 + vertex 1.63229 1.89875 2.5093 + endloop + endfacet + facet normal 0.289054 0.174014 0.941364 + outer loop + vertex 1.62808 1.89892 2.51056 + vertex 1.63229 1.89875 2.5093 + vertex 1.62828 1.90359 2.50963 + endloop + endfacet + facet normal 0.289696 0.174568 0.941064 + outer loop + vertex 1.62828 1.90359 2.50963 + vertex 1.63229 1.89875 2.5093 + vertex 1.6327 1.90333 2.50832 + endloop + endfacet + facet normal 0.28969 0.172024 0.941535 + outer loop + vertex 1.6327 1.90333 2.50832 + vertex 1.63105 1.90664 2.50822 + vertex 1.62828 1.90359 2.50963 + endloop + endfacet + facet normal 0.289655 0.172058 0.941539 + outer loop + vertex 1.62828 1.90359 2.50963 + vertex 1.63105 1.90664 2.50822 + vertex 1.62828 1.90825 2.50878 + endloop + endfacet + facet normal 0.289652 0.172052 0.941541 + outer loop + vertex 1.63105 1.90664 2.50822 + vertex 1.63106 1.9113 2.50737 + vertex 1.62828 1.90825 2.50878 + endloop + endfacet + facet normal 0.287968 0.173689 0.941757 + outer loop + vertex 1.62828 1.90825 2.50878 + vertex 1.63106 1.9113 2.50737 + vertex 1.62664 1.91155 2.50867 + endloop + endfacet + facet normal 0.287975 0.175973 0.941331 + outer loop + vertex 1.62701 1.91615 2.5077 + vertex 1.62664 1.91155 2.50867 + vertex 1.63106 1.9113 2.50737 + endloop + endfacet + facet normal 0.286048 0.174304 0.942228 + outer loop + vertex 1.63125 1.91596 2.50645 + vertex 1.62701 1.91615 2.5077 + vertex 1.63106 1.9113 2.50737 + endloop + endfacet + facet normal 0.287616 0.174153 0.941779 + outer loop + vertex 1.63125 1.91596 2.50645 + vertex 1.63106 1.9113 2.50737 + vertex 1.63404 1.91403 2.50595 + endloop + endfacet + facet normal 0.288982 0.172596 0.941647 + outer loop + vertex 1.63527 1.91096 2.50614 + vertex 1.63404 1.91403 2.50595 + vertex 1.63106 1.9113 2.50737 + endloop + endfacet + facet normal 0.288954 0.171466 0.941862 + outer loop + vertex 1.63527 1.91096 2.50614 + vertex 1.63106 1.9113 2.50737 + vertex 1.63494 1.90674 2.50701 + endloop + endfacet + facet normal 0.288935 0.171469 0.941868 + outer loop + vertex 1.63527 1.91096 2.50614 + vertex 1.63494 1.90674 2.50701 + vertex 1.63807 1.90902 2.50563 + endloop + endfacet + facet normal 0.28987 0.17296 0.941308 + outer loop + vertex 1.63807 1.90902 2.50563 + vertex 1.63826 1.91367 2.50472 + vertex 1.63527 1.91096 2.50614 + endloop + endfacet + facet normal 0.289616 0.172054 0.941552 + outer loop + vertex 1.63106 1.9113 2.50737 + vertex 1.63105 1.90664 2.50822 + vertex 1.63494 1.90674 2.50701 + endloop + endfacet + facet normal 0.289621 0.171991 0.941562 + outer loop + vertex 1.6327 1.90333 2.50832 + vertex 1.63494 1.90674 2.50701 + vertex 1.63105 1.90664 2.50822 + endloop + endfacet + facet normal 0.288808 0.172582 0.941703 + outer loop + vertex 1.63685 1.90099 2.50748 + vertex 1.63494 1.90674 2.50701 + vertex 1.6327 1.90333 2.50832 + endloop + endfacet + facet normal 0.288779 0.172573 0.941714 + outer loop + vertex 1.63494 1.90674 2.50701 + vertex 1.63685 1.90099 2.50748 + vertex 1.63958 1.90489 2.50592 + endloop + endfacet + facet normal 0.288579 0.171969 0.941886 + outer loop + vertex 1.63958 1.90489 2.50592 + vertex 1.63807 1.90902 2.50563 + vertex 1.63494 1.90674 2.50701 + endloop + endfacet + facet normal 0.28655 0.171278 0.942631 + outer loop + vertex 1.63807 1.90902 2.50563 + vertex 1.63958 1.90489 2.50592 + vertex 1.64231 1.90879 2.50438 + endloop + endfacet + facet normal 0.286548 0.173282 0.942265 + outer loop + vertex 1.63807 1.90902 2.50563 + vertex 1.64231 1.90879 2.50438 + vertex 1.63826 1.91367 2.50472 + endloop + endfacet + facet normal 0.28736 0.173983 0.941888 + outer loop + vertex 1.63826 1.91367 2.50472 + vertex 1.64231 1.90879 2.50438 + vertex 1.64269 1.91339 2.50342 + endloop + endfacet + facet normal 0.287401 0.178783 0.940977 + outer loop + vertex 1.64269 1.91339 2.50342 + vertex 1.64104 1.91666 2.5033 + vertex 1.63826 1.91367 2.50472 + endloop + endfacet + facet normal 0.287812 0.178378 0.940928 + outer loop + vertex 1.63826 1.91367 2.50472 + vertex 1.64104 1.91666 2.5033 + vertex 1.63827 1.91827 2.50385 + endloop + endfacet + facet normal 0.290259 0.183166 0.939255 + outer loop + vertex 1.64104 1.91666 2.5033 + vertex 1.64104 1.92125 2.50241 + vertex 1.63827 1.91827 2.50385 + endloop + endfacet + facet normal 0.290457 0.18297 0.939232 + outer loop + vertex 1.63827 1.91827 2.50385 + vertex 1.64104 1.92125 2.50241 + vertex 1.63662 1.92155 2.50372 + endloop + endfacet + facet normal 0.290492 0.187074 0.938412 + outer loop + vertex 1.63696 1.9261 2.5027 + vertex 1.63662 1.92155 2.50372 + vertex 1.64104 1.92125 2.50241 + endloop + endfacet + facet normal 0.290839 0.187375 0.938245 + outer loop + vertex 1.6412 1.92587 2.50144 + vertex 1.63696 1.9261 2.5027 + vertex 1.64104 1.92125 2.50241 + endloop + endfacet + facet normal 0.287299 0.187714 0.939267 + outer loop + vertex 1.6412 1.92587 2.50144 + vertex 1.64104 1.92125 2.50241 + vertex 1.64402 1.92394 2.50096 + endloop + endfacet + facet normal 0.287351 0.187799 0.939234 + outer loop + vertex 1.64402 1.92394 2.50096 + vertex 1.64434 1.92812 2.50003 + vertex 1.6412 1.92587 2.50144 + endloop + endfacet + facet normal 0.287219 0.187984 0.939238 + outer loop + vertex 1.6412 1.92587 2.50144 + vertex 1.64434 1.92812 2.50003 + vertex 1.63966 1.92995 2.50109 + endloop + endfacet + facet normal 0.287991 0.19038 0.938518 + outer loop + vertex 1.64434 1.92812 2.50003 + vertex 1.64237 1.93381 2.49948 + vertex 1.63966 1.92995 2.50109 + endloop + endfacet + facet normal 0.288055 0.190331 0.938509 + outer loop + vertex 1.63811 1.93402 2.50074 + vertex 1.63966 1.92995 2.50109 + vertex 1.64237 1.93381 2.49948 + endloop + endfacet + facet normal 0.288023 0.193904 0.937787 + outer loop + vertex 1.63811 1.93402 2.50074 + vertex 1.64237 1.93381 2.49948 + vertex 1.63825 1.93862 2.49975 + endloop + endfacet + facet normal 0.291481 0.191521 0.937208 + outer loop + vertex 1.63966 1.92995 2.50109 + vertex 1.63811 1.93402 2.50074 + vertex 1.635 1.93177 2.50217 + endloop + endfacet + facet normal 0.290762 0.189282 0.937886 + outer loop + vertex 1.635 1.93177 2.50217 + vertex 1.63696 1.9261 2.5027 + vertex 1.63966 1.92995 2.50109 + endloop + endfacet + facet normal 0.285108 0.188107 0.939856 + outer loop + vertex 1.64402 1.92394 2.50096 + vertex 1.64826 1.92362 2.49974 + vertex 1.64434 1.92812 2.50003 + endloop + endfacet + facet normal 0.283063 0.186266 0.94084 + outer loop + vertex 1.64434 1.92812 2.50003 + vertex 1.64826 1.92362 2.49974 + vertex 1.64826 1.92822 2.49883 + endloop + endfacet + facet normal 0.282871 0.188714 0.94041 + outer loop + vertex 1.64826 1.92822 2.49883 + vertex 1.64658 1.93149 2.49867 + vertex 1.64434 1.92812 2.50003 + endloop + endfacet + facet normal 0.282801 0.188766 0.940421 + outer loop + vertex 1.64434 1.92812 2.50003 + vertex 1.64658 1.93149 2.49867 + vertex 1.64237 1.93381 2.49948 + endloop + endfacet + facet normal 0.283386 0.18998 0.94 + outer loop + vertex 1.64658 1.93149 2.49867 + vertex 1.64692 1.93605 2.49765 + vertex 1.64237 1.93381 2.49948 + endloop + endfacet + facet normal 0.281154 0.190279 0.94061 + outer loop + vertex 1.64692 1.93605 2.49765 + vertex 1.64658 1.93149 2.49867 + vertex 1.65103 1.93124 2.49739 + endloop + endfacet + facet normal 0.279188 0.188549 0.941543 + outer loop + vertex 1.65118 1.93587 2.49643 + vertex 1.64692 1.93605 2.49765 + vertex 1.65103 1.93124 2.49739 + endloop + endfacet + facet normal 0.280309 0.188448 0.94123 + outer loop + vertex 1.65118 1.93587 2.49643 + vertex 1.65103 1.93124 2.49739 + vertex 1.65401 1.93397 2.49596 + endloop + endfacet + facet normal 0.283518 0.193722 0.939196 + outer loop + vertex 1.65401 1.93397 2.49596 + vertex 1.65429 1.9381 2.49502 + vertex 1.65118 1.93587 2.49643 + endloop + endfacet + facet normal 0.282086 0.195727 0.939212 + outer loop + vertex 1.65118 1.93587 2.49643 + vertex 1.65429 1.9381 2.49502 + vertex 1.64962 1.93989 2.49605 + endloop + endfacet + facet normal 0.283108 0.198962 0.938224 + outer loop + vertex 1.65429 1.9381 2.49502 + vertex 1.65231 1.9437 2.49443 + vertex 1.64962 1.93989 2.49605 + endloop + endfacet + facet normal 0.282865 0.199148 0.938258 + outer loop + vertex 1.64806 1.94391 2.49567 + vertex 1.64962 1.93989 2.49605 + vertex 1.65231 1.9437 2.49443 + endloop + endfacet + facet normal 0.282835 0.201948 0.937668 + outer loop + vertex 1.64806 1.94391 2.49567 + vertex 1.65231 1.9437 2.49443 + vertex 1.64818 1.94849 2.49465 + endloop + endfacet + facet normal 0.283197 0.201917 0.937566 + outer loop + vertex 1.64806 1.94391 2.49567 + vertex 1.64818 1.94849 2.49465 + vertex 1.64523 1.94581 2.49612 + endloop + endfacet + facet normal 0.281054 0.198384 0.938963 + outer loop + vertex 1.64523 1.94581 2.49612 + vertex 1.64493 1.94168 2.49708 + vertex 1.64806 1.94391 2.49567 + endloop + endfacet + facet normal 0.283518 0.198052 0.938293 + outer loop + vertex 1.64523 1.94581 2.49612 + vertex 1.64099 1.94614 2.49733 + vertex 1.64493 1.94168 2.49708 + endloop + endfacet + facet normal 0.283026 0.197603 0.938536 + outer loop + vertex 1.64099 1.94614 2.49733 + vertex 1.64101 1.9416 2.49828 + vertex 1.64493 1.94168 2.49708 + endloop + endfacet + facet normal 0.283236 0.194898 0.939038 + outer loop + vertex 1.64269 1.93836 2.49844 + vertex 1.64493 1.94168 2.49708 + vertex 1.64101 1.9416 2.49828 + endloop + endfacet + facet normal 0.28645 0.196502 0.937728 + outer loop + vertex 1.64269 1.93836 2.49844 + vertex 1.64101 1.9416 2.49828 + vertex 1.63825 1.93862 2.49975 + endloop + endfacet + facet normal 0.286045 0.196897 0.937769 + outer loop + vertex 1.63825 1.93862 2.49975 + vertex 1.64101 1.9416 2.49828 + vertex 1.63822 1.94317 2.4988 + endloop + endfacet + facet normal 0.282762 0.195246 0.939108 + outer loop + vertex 1.64692 1.93605 2.49765 + vertex 1.64493 1.94168 2.49708 + vertex 1.64269 1.93836 2.49844 + endloop + endfacet + facet normal 0.27965 0.194262 0.940244 + outer loop + vertex 1.64493 1.94168 2.49708 + vertex 1.64692 1.93605 2.49765 + vertex 1.64962 1.93989 2.49605 + endloop + endfacet + facet normal 0.286304 0.197419 0.93758 + outer loop + vertex 1.64101 1.9416 2.49828 + vertex 1.64099 1.94614 2.49733 + vertex 1.63822 1.94317 2.4988 + endloop + endfacet + facet normal 0.285621 0.198089 0.937647 + outer loop + vertex 1.63822 1.94317 2.4988 + vertex 1.64099 1.94614 2.49733 + vertex 1.63656 1.94638 2.49863 + endloop + endfacet + facet normal 0.287374 0.198953 0.936928 + outer loop + vertex 1.63822 1.94317 2.4988 + vertex 1.63656 1.94638 2.49863 + vertex 1.63433 1.94306 2.50002 + endloop + endfacet + facet normal 0.28756 0.196815 0.937322 + outer loop + vertex 1.63433 1.94306 2.50002 + vertex 1.63825 1.93862 2.49975 + vertex 1.63822 1.94317 2.4988 + endloop + endfacet + facet normal 0.29051 0.199516 0.93584 + outer loop + vertex 1.63402 1.93895 2.50099 + vertex 1.63825 1.93862 2.49975 + vertex 1.63433 1.94306 2.50002 + endloop + endfacet + facet normal 0.290448 0.194908 0.93683 + outer loop + vertex 1.63402 1.93895 2.50099 + vertex 1.63529 1.93593 2.50122 + vertex 1.63825 1.93862 2.49975 + endloop + endfacet + facet normal 0.291617 0.193573 0.936744 + outer loop + vertex 1.63811 1.93402 2.50074 + vertex 1.63825 1.93862 2.49975 + vertex 1.63529 1.93593 2.50122 + endloop + endfacet + facet normal 0.290881 0.192362 0.937222 + outer loop + vertex 1.63529 1.93593 2.50122 + vertex 1.635 1.93177 2.50217 + vertex 1.63811 1.93402 2.50074 + endloop + endfacet + facet normal 0.289233 0.192583 0.937687 + outer loop + vertex 1.63529 1.93593 2.50122 + vertex 1.63107 1.93624 2.50246 + vertex 1.635 1.93177 2.50217 + endloop + endfacet + facet normal 0.291359 0.194523 0.936627 + outer loop + vertex 1.63107 1.93624 2.50246 + vertex 1.6311 1.93169 2.5034 + vertex 1.635 1.93177 2.50217 + endloop + endfacet + facet normal 0.291689 0.190305 0.937391 + outer loop + vertex 1.63277 1.92844 2.50354 + vertex 1.635 1.93177 2.50217 + vertex 1.6311 1.93169 2.5034 + endloop + endfacet + facet normal 0.287913 0.188431 0.938935 + outer loop + vertex 1.63277 1.92844 2.50354 + vertex 1.6311 1.93169 2.5034 + vertex 1.62835 1.9287 2.50484 + endloop + endfacet + facet normal 0.287914 0.187322 0.939157 + outer loop + vertex 1.62835 1.9287 2.50484 + vertex 1.63244 1.92389 2.50455 + vertex 1.63277 1.92844 2.50354 + endloop + endfacet + facet normal 0.290985 0.186903 0.938294 + outer loop + vertex 1.63244 1.92389 2.50455 + vertex 1.63696 1.9261 2.5027 + vertex 1.63277 1.92844 2.50354 + endloop + endfacet + facet normal 0.29093 0.187013 0.938289 + outer loop + vertex 1.63662 1.92155 2.50372 + vertex 1.63696 1.9261 2.5027 + vertex 1.63244 1.92389 2.50455 + endloop + endfacet + facet normal 0.289112 0.18331 0.939581 + outer loop + vertex 1.63438 1.91821 2.50506 + vertex 1.63662 1.92155 2.50372 + vertex 1.63244 1.92389 2.50455 + endloop + endfacet + facet normal 0.289923 0.18271 0.939447 + outer loop + vertex 1.63827 1.91827 2.50385 + vertex 1.63662 1.92155 2.50372 + vertex 1.63438 1.91821 2.50506 + endloop + endfacet + facet normal 0.28848 0.18782 0.938884 + outer loop + vertex 1.62821 1.9241 2.50581 + vertex 1.63244 1.92389 2.50455 + vertex 1.62835 1.9287 2.50484 + endloop + endfacet + facet normal 0.288512 0.184186 0.939594 + outer loop + vertex 1.62821 1.9241 2.50581 + vertex 1.62973 1.92004 2.50613 + vertex 1.63244 1.92389 2.50455 + endloop + endfacet + facet normal 0.289499 0.183429 0.939438 + outer loop + vertex 1.63438 1.91821 2.50506 + vertex 1.63244 1.92389 2.50455 + vertex 1.62973 1.92004 2.50613 + endloop + endfacet + facet normal 0.288479 0.180296 0.940358 + outer loop + vertex 1.63125 1.91596 2.50645 + vertex 1.63438 1.91821 2.50506 + vertex 1.62973 1.92004 2.50613 + endloop + endfacet + facet normal 0.290055 0.178066 0.940298 + outer loop + vertex 1.63404 1.91403 2.50595 + vertex 1.63438 1.91821 2.50506 + vertex 1.63125 1.91596 2.50645 + endloop + endfacet + facet normal 0.290036 0.178069 0.940303 + outer loop + vertex 1.63404 1.91403 2.50595 + vertex 1.63826 1.91367 2.50472 + vertex 1.63438 1.91821 2.50506 + endloop + endfacet + facet normal 0.284828 0.18291 0.940966 + outer loop + vertex 1.62973 1.92004 2.50613 + vertex 1.62821 1.9241 2.50581 + vertex 1.62508 1.92181 2.5072 + endloop + endfacet + facet normal 0.284175 0.180838 0.941564 + outer loop + vertex 1.62508 1.92181 2.5072 + vertex 1.62701 1.91615 2.5077 + vertex 1.62973 1.92004 2.50613 + endloop + endfacet + facet normal 0.285916 0.19037 0.939155 + outer loop + vertex 1.62835 1.9287 2.50484 + vertex 1.6311 1.93169 2.5034 + vertex 1.62832 1.93326 2.50393 + endloop + endfacet + facet normal 0.288055 0.194701 0.937612 + outer loop + vertex 1.6311 1.93169 2.5034 + vertex 1.63107 1.93624 2.50246 + vertex 1.62832 1.93326 2.50393 + endloop + endfacet + facet normal 0.292393 0.189789 0.937276 + outer loop + vertex 1.63696 1.9261 2.5027 + vertex 1.635 1.93177 2.50217 + vertex 1.63277 1.92844 2.50354 + endloop + endfacet + facet normal 0.289254 0.194443 0.937296 + outer loop + vertex 1.63529 1.93593 2.50122 + vertex 1.63402 1.93895 2.50099 + vertex 1.63107 1.93624 2.50246 + endloop + endfacet + facet normal 0.283549 0.201761 0.937493 + outer loop + vertex 1.63433 1.94306 2.50002 + vertex 1.63656 1.94638 2.49863 + vertex 1.63236 1.94863 2.49941 + endloop + endfacet + facet normal 0.284822 0.202158 0.937021 + outer loop + vertex 1.63433 1.94306 2.50002 + vertex 1.63236 1.94863 2.49941 + vertex 1.62967 1.94479 2.50106 + endloop + endfacet + facet normal 0.28525 0.203569 0.936585 + outer loop + vertex 1.63121 1.94081 2.50146 + vertex 1.63433 1.94306 2.50002 + vertex 1.62967 1.94479 2.50106 + endloop + endfacet + facet normal 0.282638 0.202659 0.937574 + outer loop + vertex 1.62967 1.94479 2.50106 + vertex 1.62698 1.94097 2.50269 + vertex 1.63121 1.94081 2.50146 + endloop + endfacet + facet normal 0.28274 0.197895 0.938561 + outer loop + vertex 1.63121 1.94081 2.50146 + vertex 1.62698 1.94097 2.50269 + vertex 1.63107 1.93624 2.50246 + endloop + endfacet + facet normal 0.286512 0.19754 0.937491 + outer loop + vertex 1.63121 1.94081 2.50146 + vertex 1.63107 1.93624 2.50246 + vertex 1.63402 1.93895 2.50099 + endloop + endfacet + facet normal 0.280446 0.204329 0.93787 + outer loop + vertex 1.62496 1.94658 2.50208 + vertex 1.62698 1.94097 2.50269 + vertex 1.62967 1.94479 2.50106 + endloop + endfacet + facet normal 0.280865 0.205667 0.937452 + outer loop + vertex 1.62967 1.94479 2.50106 + vertex 1.62809 1.94881 2.50065 + vertex 1.62496 1.94658 2.50208 + endloop + endfacet + facet normal 0.279346 0.207796 0.937436 + outer loop + vertex 1.62516 1.95075 2.50109 + vertex 1.62496 1.94658 2.50208 + vertex 1.62809 1.94881 2.50065 + endloop + endfacet + facet normal 0.278796 0.206887 0.937801 + outer loop + vertex 1.62809 1.94881 2.50065 + vertex 1.62811 1.95348 2.49962 + vertex 1.62516 1.95075 2.50109 + endloop + endfacet + facet normal 0.278433 0.207289 0.93782 + outer loop + vertex 1.62368 1.95392 2.50083 + vertex 1.62516 1.95075 2.50109 + vertex 1.62811 1.95348 2.49962 + endloop + endfacet + facet normal 0.280384 0.206782 0.93735 + outer loop + vertex 1.62809 1.94881 2.50065 + vertex 1.63236 1.94863 2.49941 + vertex 1.62811 1.95348 2.49962 + endloop + endfacet + facet normal 0.277166 0.203889 0.93894 + outer loop + vertex 1.62811 1.95348 2.49962 + vertex 1.63236 1.94863 2.49941 + vertex 1.63269 1.95314 2.49834 + endloop + endfacet + facet normal 0.27719 0.205906 0.938493 + outer loop + vertex 1.63269 1.95314 2.49834 + vertex 1.63093 1.9564 2.49814 + vertex 1.62811 1.95348 2.49962 + endloop + endfacet + facet normal 0.275002 0.208106 0.938651 + outer loop + vertex 1.62811 1.95348 2.49962 + vertex 1.63093 1.9564 2.49814 + vertex 1.62796 1.9581 2.49863 + endloop + endfacet + facet normal 0.279311 0.207976 0.937407 + outer loop + vertex 1.62357 1.9585 2.49985 + vertex 1.62811 1.95348 2.49962 + vertex 1.62796 1.9581 2.49863 + endloop + endfacet + facet normal 0.279454 0.213162 0.936199 + outer loop + vertex 1.62796 1.9581 2.49863 + vertex 1.6263 1.96135 2.49839 + vertex 1.62357 1.9585 2.49985 + endloop + endfacet + facet normal 0.276102 0.211544 0.937559 + outer loop + vertex 1.62796 1.9581 2.49863 + vertex 1.63068 1.96102 2.49717 + vertex 1.6263 1.96135 2.49839 + endloop + endfacet + facet normal 0.276121 0.213315 0.937152 + outer loop + vertex 1.62594 1.96611 2.49741 + vertex 1.6263 1.96135 2.49839 + vertex 1.63068 1.96102 2.49717 + endloop + endfacet + facet normal 0.278938 0.216005 0.935701 + outer loop + vertex 1.63046 1.96562 2.49618 + vertex 1.62594 1.96611 2.49741 + vertex 1.63068 1.96102 2.49717 + endloop + endfacet + facet normal 0.275856 0.216053 0.936603 + outer loop + vertex 1.63046 1.96562 2.49618 + vertex 1.63068 1.96102 2.49717 + vertex 1.63355 1.96378 2.49569 + endloop + endfacet + facet normal 0.278608 0.221193 0.934586 + outer loop + vertex 1.63355 1.96378 2.49569 + vertex 1.63329 1.96843 2.49467 + vertex 1.63046 1.96562 2.49618 + endloop + endfacet + facet normal 0.28288 0.221155 0.933311 + outer loop + vertex 1.63355 1.96378 2.49569 + vertex 1.63803 1.9633 2.49445 + vertex 1.63329 1.96843 2.49467 + endloop + endfacet + facet normal 0.280056 0.218481 0.934791 + outer loop + vertex 1.63329 1.96843 2.49467 + vertex 1.63803 1.9633 2.49445 + vertex 1.63789 1.96809 2.49337 + endloop + endfacet + facet normal 0.284833 0.218299 0.933389 + outer loop + vertex 1.63803 1.9633 2.49445 + vertex 1.64211 1.96599 2.49258 + vertex 1.63789 1.96809 2.49337 + endloop + endfacet + facet normal 0.285514 0.219885 0.932809 + outer loop + vertex 1.64211 1.96599 2.49258 + vertex 1.63988 1.97147 2.49196 + vertex 1.63789 1.96809 2.49337 + endloop + endfacet + facet normal 0.28409 0.21937 0.933365 + outer loop + vertex 1.63988 1.97147 2.49196 + vertex 1.64211 1.96599 2.49258 + vertex 1.64453 1.96974 2.49096 + endloop + endfacet + facet normal 0.286342 0.21778 0.933049 + outer loop + vertex 1.64453 1.96974 2.49096 + vertex 1.64211 1.96599 2.49258 + vertex 1.64618 1.96578 2.49137 + endloop + endfacet + facet normal 0.285616 0.217508 0.933335 + outer loop + vertex 1.64618 1.96578 2.49137 + vertex 1.64918 1.96798 2.48994 + vertex 1.64453 1.96974 2.49096 + endloop + endfacet + facet normal 0.286269 0.219627 0.932638 + outer loop + vertex 1.64918 1.96798 2.48994 + vertex 1.64687 1.97354 2.48934 + vertex 1.64453 1.96974 2.49096 + endloop + endfacet + facet normal 0.284792 0.22063 0.932854 + outer loop + vertex 1.64284 1.9737 2.49054 + vertex 1.64453 1.96974 2.49096 + vertex 1.64687 1.97354 2.48934 + endloop + endfacet + facet normal 0.283811 0.218712 0.933604 + outer loop + vertex 1.64918 1.96798 2.48994 + vertex 1.65115 1.97139 2.48855 + vertex 1.64687 1.97354 2.48934 + endloop + endfacet + facet normal 0.284992 0.221423 0.932605 + outer loop + vertex 1.65115 1.97139 2.48855 + vertex 1.65083 1.97631 2.48748 + vertex 1.64687 1.97354 2.48934 + endloop + endfacet + facet normal 0.284123 0.22265 0.932578 + outer loop + vertex 1.64687 1.97354 2.48934 + vertex 1.65083 1.97631 2.48748 + vertex 1.64671 1.97739 2.48847 + endloop + endfacet + facet normal 0.283074 0.222675 0.932891 + outer loop + vertex 1.64274 1.97824 2.48948 + vertex 1.64687 1.97354 2.48934 + vertex 1.64671 1.97739 2.48847 + endloop + endfacet + facet normal 0.283379 0.224826 0.932282 + outer loop + vertex 1.64671 1.97739 2.48847 + vertex 1.64635 1.98141 2.48761 + vertex 1.64274 1.97824 2.48948 + endloop + endfacet + facet normal 0.283089 0.225161 0.932289 + outer loop + vertex 1.64274 1.97824 2.48948 + vertex 1.64635 1.98141 2.48761 + vertex 1.64238 1.98226 2.48861 + endloop + endfacet + facet normal 0.283026 0.224719 0.932415 + outer loop + vertex 1.64222 1.98605 2.48775 + vertex 1.64238 1.98226 2.48861 + vertex 1.64635 1.98141 2.48761 + endloop + endfacet + facet normal 0.282717 0.22444 0.932576 + outer loop + vertex 1.64626 1.98591 2.48656 + vertex 1.64222 1.98605 2.48775 + vertex 1.64635 1.98141 2.48761 + endloop + endfacet + facet normal 0.283066 0.224423 0.932474 + outer loop + vertex 1.64626 1.98591 2.48656 + vertex 1.64635 1.98141 2.48761 + vertex 1.64917 1.984 2.48613 + endloop + endfacet + facet normal 0.283241 0.22423 0.932467 + outer loop + vertex 1.6507 1.98087 2.48642 + vertex 1.64917 1.984 2.48613 + vertex 1.64635 1.98141 2.48761 + endloop + endfacet + facet normal 0.283211 0.223663 0.932613 + outer loop + vertex 1.6507 1.98087 2.48642 + vertex 1.64635 1.98141 2.48761 + vertex 1.65083 1.97631 2.48748 + endloop + endfacet + facet normal 0.283569 0.223649 0.932507 + outer loop + vertex 1.6507 1.98087 2.48642 + vertex 1.65083 1.97631 2.48748 + vertex 1.65376 1.97897 2.48595 + endloop + endfacet + facet normal 0.283789 0.224043 0.932346 + outer loop + vertex 1.65376 1.97897 2.48595 + vertex 1.65353 1.98352 2.48492 + vertex 1.6507 1.98087 2.48642 + endloop + endfacet + facet normal 0.286272 0.223998 0.931597 + outer loop + vertex 1.65376 1.97897 2.48595 + vertex 1.65827 1.97844 2.48469 + vertex 1.65353 1.98352 2.48492 + endloop + endfacet + facet normal 0.285533 0.22329 0.931994 + outer loop + vertex 1.65353 1.98352 2.48492 + vertex 1.65827 1.97844 2.48469 + vertex 1.65792 1.98311 2.48368 + endloop + endfacet + facet normal 0.286255 0.223636 0.931689 + outer loop + vertex 1.65376 1.97897 2.48595 + vertex 1.65543 1.9757 2.48622 + vertex 1.65827 1.97844 2.48469 + endloop + endfacet + facet normal 0.286614 0.223254 0.931671 + outer loop + vertex 1.65851 1.97379 2.48573 + vertex 1.65827 1.97844 2.48469 + vertex 1.65543 1.9757 2.48622 + endloop + endfacet + facet normal 0.284987 0.220331 0.932865 + outer loop + vertex 1.65543 1.9757 2.48622 + vertex 1.65565 1.97107 2.48725 + vertex 1.65851 1.97379 2.48573 + endloop + endfacet + facet normal 0.284231 0.220346 0.933092 + outer loop + vertex 1.65543 1.9757 2.48622 + vertex 1.65083 1.97631 2.48748 + vertex 1.65565 1.97107 2.48725 + endloop + endfacet + facet normal 0.28438 0.222743 0.932477 + outer loop + vertex 1.65543 1.9757 2.48622 + vertex 1.65376 1.97897 2.48595 + vertex 1.65083 1.97631 2.48748 + endloop + endfacet + facet normal 0.283507 0.224351 0.932357 + outer loop + vertex 1.64917 1.984 2.48613 + vertex 1.6507 1.98087 2.48642 + vertex 1.65353 1.98352 2.48492 + endloop + endfacet + facet normal 0.282723 0.224243 0.932622 + outer loop + vertex 1.64457 1.98982 2.48613 + vertex 1.64222 1.98605 2.48775 + vertex 1.64626 1.98591 2.48656 + endloop + endfacet + facet normal 0.282273 0.224549 0.932684 + outer loop + vertex 1.63994 1.99151 2.48712 + vertex 1.64222 1.98605 2.48775 + vertex 1.64457 1.98982 2.48613 + endloop + endfacet + facet normal 0.283176 0.224886 0.932329 + outer loop + vertex 1.64222 1.98605 2.48775 + vertex 1.63994 1.99151 2.48712 + vertex 1.63799 1.98812 2.48854 + endloop + endfacet + facet normal 0.282834 0.224071 0.932629 + outer loop + vertex 1.63828 1.98327 2.48961 + vertex 1.64222 1.98605 2.48775 + vertex 1.63799 1.98812 2.48854 + endloop + endfacet + facet normal 0.283414 0.224067 0.932454 + outer loop + vertex 1.6335 1.98841 2.48983 + vertex 1.63828 1.98327 2.48961 + vertex 1.63799 1.98812 2.48854 + endloop + endfacet + facet normal 0.28341 0.22527 0.932166 + outer loop + vertex 1.63799 1.98812 2.48854 + vertex 1.63606 1.99139 2.48833 + vertex 1.6335 1.98841 2.48983 + endloop + endfacet + facet normal 0.284504 0.224283 0.93207 + outer loop + vertex 1.6335 1.98841 2.48983 + vertex 1.63606 1.99139 2.48833 + vertex 1.63315 1.99304 2.48882 + endloop + endfacet + facet normal 0.289225 0.224319 0.930607 + outer loop + vertex 1.62925 1.99305 2.49003 + vertex 1.6335 1.98841 2.48983 + vertex 1.63315 1.99304 2.48882 + endloop + endfacet + facet normal 0.285887 0.227057 0.930975 + outer loop + vertex 1.63606 1.99139 2.48833 + vertex 1.63569 1.99604 2.48731 + vertex 1.63315 1.99304 2.48882 + endloop + endfacet + facet normal 0.286972 0.226091 0.930876 + outer loop + vertex 1.63315 1.99304 2.48882 + vertex 1.63569 1.99604 2.48731 + vertex 1.63119 1.99642 2.4886 + endloop + endfacet + facet normal 0.281449 0.222196 0.933496 + outer loop + vertex 1.6337 1.98381 2.49086 + vertex 1.63828 1.98327 2.48961 + vertex 1.6335 1.98841 2.48983 + endloop + endfacet + facet normal 0.285065 0.222108 0.93242 + outer loop + vertex 1.6337 1.98381 2.49086 + vertex 1.6335 1.98841 2.48983 + vertex 1.63062 1.98572 2.49135 + endloop + endfacet + facet normal 0.284916 0.221841 0.932529 + outer loop + vertex 1.63062 1.98572 2.49135 + vertex 1.63086 1.98105 2.49239 + vertex 1.6337 1.98381 2.49086 + endloop + endfacet + facet normal 0.292276 0.221715 0.930278 + outer loop + vertex 1.63062 1.98572 2.49135 + vertex 1.62615 1.98636 2.4926 + vertex 1.63086 1.98105 2.49239 + endloop + endfacet + facet normal 0.287028 0.219957 0.932327 + outer loop + vertex 1.62912 1.9889 2.49106 + vertex 1.63062 1.98572 2.49135 + vertex 1.6335 1.98841 2.48983 + endloop + endfacet + facet normal 0.282965 0.225021 0.932361 + outer loop + vertex 1.63799 1.98812 2.48854 + vertex 1.63994 1.99151 2.48712 + vertex 1.63606 1.99139 2.48833 + endloop + endfacet + facet normal 0.282358 0.224736 0.932613 + outer loop + vertex 1.64238 1.98226 2.48861 + vertex 1.64222 1.98605 2.48775 + vertex 1.63828 1.98327 2.48961 + endloop + endfacet + facet normal 0.284543 0.224852 0.931921 + outer loop + vertex 1.64635 1.98141 2.48761 + vertex 1.64671 1.97739 2.48847 + vertex 1.65083 1.97631 2.48748 + endloop + endfacet + facet normal 0.285371 0.221422 0.932489 + outer loop + vertex 1.65083 1.97631 2.48748 + vertex 1.65115 1.97139 2.48855 + vertex 1.65565 1.97107 2.48725 + endloop + endfacet + facet normal 0.285364 0.217939 0.933311 + outer loop + vertex 1.65309 1.96805 2.48873 + vertex 1.65565 1.97107 2.48725 + vertex 1.65115 1.97139 2.48855 + endloop + endfacet + facet normal 0.285181 0.217838 0.933391 + outer loop + vertex 1.65309 1.96805 2.48873 + vertex 1.65115 1.97139 2.48855 + vertex 1.64918 1.96798 2.48994 + endloop + endfacet + facet normal 0.285497 0.213952 0.934193 + outer loop + vertex 1.64918 1.96798 2.48994 + vertex 1.6534 1.96341 2.4897 + vertex 1.65309 1.96805 2.48873 + endloop + endfacet + facet normal 0.286862 0.215249 0.933476 + outer loop + vertex 1.64905 1.96384 2.49094 + vertex 1.6534 1.96341 2.4897 + vertex 1.64918 1.96798 2.48994 + endloop + endfacet + facet normal 0.286778 0.212626 0.934103 + outer loop + vertex 1.64905 1.96384 2.49094 + vertex 1.65052 1.9607 2.4912 + vertex 1.6534 1.96341 2.4897 + endloop + endfacet + facet normal 0.287352 0.211999 0.934069 + outer loop + vertex 1.6535 1.95884 2.49071 + vertex 1.6534 1.96341 2.4897 + vertex 1.65052 1.9607 2.4912 + endloop + endfacet + facet normal 0.287037 0.211434 0.934294 + outer loop + vertex 1.65052 1.9607 2.4912 + vertex 1.65063 1.95611 2.49221 + vertex 1.6535 1.95884 2.49071 + endloop + endfacet + facet normal 0.287024 0.211448 0.934295 + outer loop + vertex 1.65496 1.95569 2.49097 + vertex 1.6535 1.95884 2.49071 + vertex 1.65063 1.95611 2.49221 + endloop + endfacet + facet normal 0.286968 0.209582 0.934732 + outer loop + vertex 1.65496 1.95569 2.49097 + vertex 1.65063 1.95611 2.49221 + vertex 1.65477 1.95152 2.49196 + endloop + endfacet + facet normal 0.287311 0.209543 0.934636 + outer loop + vertex 1.65496 1.95569 2.49097 + vertex 1.65477 1.95152 2.49196 + vertex 1.65784 1.95374 2.49052 + endloop + endfacet + facet normal 0.287535 0.209907 0.934485 + outer loop + vertex 1.65784 1.95374 2.49052 + vertex 1.65795 1.95833 2.48946 + vertex 1.65496 1.95569 2.49097 + endloop + endfacet + facet normal 0.288183 0.208341 0.934636 + outer loop + vertex 1.65944 1.94971 2.49093 + vertex 1.65784 1.95374 2.49052 + vertex 1.65477 1.95152 2.49196 + endloop + endfacet + facet normal 0.287 0.209611 0.934716 + outer loop + vertex 1.65063 1.95611 2.49221 + vertex 1.65088 1.95146 2.49317 + vertex 1.65477 1.95152 2.49196 + endloop + endfacet + facet normal 0.287158 0.207576 0.935122 + outer loop + vertex 1.65262 1.94819 2.49336 + vertex 1.65477 1.95152 2.49196 + vertex 1.65088 1.95146 2.49317 + endloop + endfacet + facet normal 0.284817 0.206384 0.936101 + outer loop + vertex 1.65262 1.94819 2.49336 + vertex 1.65088 1.95146 2.49317 + vertex 1.64818 1.94849 2.49465 + endloop + endfacet + facet normal 0.285298 0.205923 0.936056 + outer loop + vertex 1.64818 1.94849 2.49465 + vertex 1.65088 1.95146 2.49317 + vertex 1.64803 1.95308 2.49368 + endloop + endfacet + facet normal 0.28621 0.205894 0.935784 + outer loop + vertex 1.64416 1.95298 2.49489 + vertex 1.64818 1.94849 2.49465 + vertex 1.64803 1.95308 2.49368 + endloop + endfacet + facet normal 0.285996 0.208363 0.935303 + outer loop + vertex 1.64803 1.95308 2.49368 + vertex 1.64619 1.9564 2.49351 + vertex 1.64416 1.95298 2.49489 + endloop + endfacet + facet normal 0.286734 0.207876 0.935185 + outer loop + vertex 1.64416 1.95298 2.49489 + vertex 1.64619 1.9564 2.49351 + vertex 1.64201 1.95854 2.49431 + endloop + endfacet + facet normal 0.287149 0.20802 0.935026 + outer loop + vertex 1.64416 1.95298 2.49489 + vertex 1.64201 1.95854 2.49431 + vertex 1.63953 1.95473 2.49592 + endloop + endfacet + facet normal 0.285802 0.203652 0.936399 + outer loop + vertex 1.64112 1.95072 2.49631 + vertex 1.64416 1.95298 2.49489 + vertex 1.63953 1.95473 2.49592 + endloop + endfacet + facet normal 0.284727 0.203267 0.93681 + outer loop + vertex 1.63953 1.95473 2.49592 + vertex 1.6369 1.95089 2.49756 + vertex 1.64112 1.95072 2.49631 + endloop + endfacet + facet normal 0.284791 0.200438 0.9374 + outer loop + vertex 1.64112 1.95072 2.49631 + vertex 1.6369 1.95089 2.49756 + vertex 1.64099 1.94614 2.49733 + endloop + endfacet + facet normal 0.283978 0.200513 0.937631 + outer loop + vertex 1.64112 1.95072 2.49631 + vertex 1.64099 1.94614 2.49733 + vertex 1.64394 1.94883 2.49586 + endloop + endfacet + facet normal 0.28338 0.20427 0.937 + outer loop + vertex 1.63488 1.95648 2.49695 + vertex 1.6369 1.95089 2.49756 + vertex 1.63953 1.95473 2.49592 + endloop + endfacet + facet normal 0.28401 0.206316 0.936361 + outer loop + vertex 1.63953 1.95473 2.49592 + vertex 1.63795 1.95874 2.49552 + vertex 1.63488 1.95648 2.49695 + endloop + endfacet + facet normal 0.282215 0.208761 0.936362 + outer loop + vertex 1.63508 1.96064 2.49596 + vertex 1.63488 1.95648 2.49695 + vertex 1.63795 1.95874 2.49552 + endloop + endfacet + facet normal 0.285486 0.214216 0.934136 + outer loop + vertex 1.63795 1.95874 2.49552 + vertex 1.63803 1.9633 2.49445 + vertex 1.63508 1.96064 2.49596 + endloop + endfacet + facet normal 0.287584 0.21404 0.933532 + outer loop + vertex 1.63795 1.95874 2.49552 + vertex 1.64201 1.95854 2.49431 + vertex 1.63803 1.9633 2.49445 + endloop + endfacet + facet normal 0.285247 0.212048 0.934703 + outer loop + vertex 1.63803 1.9633 2.49445 + vertex 1.64201 1.95854 2.49431 + vertex 1.64206 1.96228 2.49345 + endloop + endfacet + facet normal 0.288089 0.211823 0.933882 + outer loop + vertex 1.64201 1.95854 2.49431 + vertex 1.64609 1.96123 2.49245 + vertex 1.64206 1.96228 2.49345 + endloop + endfacet + facet normal 0.288931 0.216246 0.932608 + outer loop + vertex 1.64211 1.96599 2.49258 + vertex 1.64206 1.96228 2.49345 + vertex 1.64609 1.96123 2.49245 + endloop + endfacet + facet normal 0.276943 0.209348 0.937804 + outer loop + vertex 1.63508 1.96064 2.49596 + vertex 1.63068 1.96102 2.49717 + vertex 1.63488 1.95648 2.49695 + endloop + endfacet + facet normal 0.278783 0.211099 0.936866 + outer loop + vertex 1.63068 1.96102 2.49717 + vertex 1.63093 1.9564 2.49814 + vertex 1.63488 1.95648 2.49695 + endloop + endfacet + facet normal 0.282993 0.204146 0.937144 + outer loop + vertex 1.6369 1.95089 2.49756 + vertex 1.63488 1.95648 2.49695 + vertex 1.63269 1.95314 2.49834 + endloop + endfacet + facet normal 0.285844 0.203595 0.936398 + outer loop + vertex 1.64394 1.94883 2.49586 + vertex 1.64416 1.95298 2.49489 + vertex 1.64112 1.95072 2.49631 + endloop + endfacet + facet normal 0.287694 0.207631 0.934945 + outer loop + vertex 1.63795 1.95874 2.49552 + vertex 1.63953 1.95473 2.49592 + vertex 1.64201 1.95854 2.49431 + endloop + endfacet + facet normal 0.288325 0.211471 0.933889 + outer loop + vertex 1.64619 1.9564 2.49351 + vertex 1.64609 1.96123 2.49245 + vertex 1.64201 1.95854 2.49431 + endloop + endfacet + facet normal 0.287591 0.211502 0.934108 + outer loop + vertex 1.64609 1.96123 2.49245 + vertex 1.64619 1.9564 2.49351 + vertex 1.65063 1.95611 2.49221 + endloop + endfacet + facet normal 0.287591 0.209211 0.934624 + outer loop + vertex 1.64803 1.95308 2.49368 + vertex 1.65063 1.95611 2.49221 + vertex 1.64619 1.9564 2.49351 + endloop + endfacet + facet normal 0.283955 0.203817 0.936925 + outer loop + vertex 1.64394 1.94883 2.49586 + vertex 1.64818 1.94849 2.49465 + vertex 1.64416 1.95298 2.49489 + endloop + endfacet + facet normal 0.287153 0.20961 0.934669 + outer loop + vertex 1.65088 1.95146 2.49317 + vertex 1.65063 1.95611 2.49221 + vertex 1.64803 1.95308 2.49368 + endloop + endfacet + facet normal 0.288305 0.206762 0.934949 + outer loop + vertex 1.65682 1.94589 2.49258 + vertex 1.65477 1.95152 2.49196 + vertex 1.65262 1.94819 2.49336 + endloop + endfacet + facet normal 0.286713 0.20344 0.936167 + outer loop + vertex 1.65231 1.9437 2.49443 + vertex 1.65682 1.94589 2.49258 + vertex 1.65262 1.94819 2.49336 + endloop + endfacet + facet normal 0.286427 0.211191 0.934536 + outer loop + vertex 1.6535 1.95884 2.49071 + vertex 1.65496 1.95569 2.49097 + vertex 1.65795 1.95833 2.48946 + endloop + endfacet + facet normal 0.287496 0.211415 0.934157 + outer loop + vertex 1.65052 1.9607 2.4912 + vertex 1.64609 1.96123 2.49245 + vertex 1.65063 1.95611 2.49221 + endloop + endfacet + facet normal 0.287575 0.212971 0.933779 + outer loop + vertex 1.65052 1.9607 2.4912 + vertex 1.64905 1.96384 2.49094 + vertex 1.64609 1.96123 2.49245 + endloop + endfacet + facet normal 0.286622 0.214076 0.93382 + outer loop + vertex 1.64618 1.96578 2.49137 + vertex 1.64609 1.96123 2.49245 + vertex 1.64905 1.96384 2.49094 + endloop + endfacet + facet normal 0.28731 0.215204 0.933349 + outer loop + vertex 1.64905 1.96384 2.49094 + vertex 1.64918 1.96798 2.48994 + vertex 1.64618 1.96578 2.49137 + endloop + endfacet + facet normal 0.2864 0.214096 0.933883 + outer loop + vertex 1.64618 1.96578 2.49137 + vertex 1.64211 1.96599 2.49258 + vertex 1.64609 1.96123 2.49245 + endloop + endfacet + facet normal 0.286055 0.216477 0.93344 + outer loop + vertex 1.64206 1.96228 2.49345 + vertex 1.64211 1.96599 2.49258 + vertex 1.63803 1.9633 2.49445 + endloop + endfacet + facet normal 0.282738 0.217328 0.934253 + outer loop + vertex 1.63355 1.96378 2.49569 + vertex 1.63508 1.96064 2.49596 + vertex 1.63803 1.9633 2.49445 + endloop + endfacet + facet normal 0.277062 0.214766 0.936543 + outer loop + vertex 1.63508 1.96064 2.49596 + vertex 1.63355 1.96378 2.49569 + vertex 1.63068 1.96102 2.49717 + endloop + endfacet + facet normal 0.28337 0.213402 0.934966 + outer loop + vertex 1.6263 1.96135 2.49839 + vertex 1.62594 1.96611 2.49741 + vertex 1.62327 1.96317 2.49889 + endloop + endfacet + facet normal 0.276541 0.211119 0.937525 + outer loop + vertex 1.63093 1.9564 2.49814 + vertex 1.63068 1.96102 2.49717 + vertex 1.62796 1.9581 2.49863 + endloop + endfacet + facet normal 0.279127 0.206909 0.937697 + outer loop + vertex 1.63269 1.95314 2.49834 + vertex 1.63488 1.95648 2.49695 + vertex 1.63093 1.9564 2.49814 + endloop + endfacet + facet normal 0.282527 0.203154 0.9375 + outer loop + vertex 1.63236 1.94863 2.49941 + vertex 1.6369 1.95089 2.49756 + vertex 1.63269 1.95314 2.49834 + endloop + endfacet + facet normal 0.285196 0.207128 0.935821 + outer loop + vertex 1.62516 1.95075 2.50109 + vertex 1.62079 1.95124 2.50232 + vertex 1.62496 1.94658 2.50208 + endloop + endfacet + facet normal 0.284155 0.206169 0.93635 + outer loop + vertex 1.62079 1.95124 2.50232 + vertex 1.62104 1.94657 2.50327 + vertex 1.62496 1.94658 2.50208 + endloop + endfacet + facet normal 0.284227 0.205025 0.936579 + outer loop + vertex 1.62279 1.94327 2.50346 + vertex 1.62496 1.94658 2.50208 + vertex 1.62104 1.94657 2.50327 + endloop + endfacet + facet normal 0.288641 0.207255 0.934736 + outer loop + vertex 1.62279 1.94327 2.50346 + vertex 1.62104 1.94657 2.50327 + vertex 1.61834 1.94367 2.50475 + endloop + endfacet + facet normal 0.288503 0.201622 0.93601 + outer loop + vertex 1.61834 1.94367 2.50475 + vertex 1.62248 1.93877 2.50453 + vertex 1.62279 1.94327 2.50346 + endloop + endfacet + facet normal 0.286853 0.200196 0.936823 + outer loop + vertex 1.61826 1.93904 2.50576 + vertex 1.62248 1.93877 2.50453 + vertex 1.61834 1.94367 2.50475 + endloop + endfacet + facet normal 0.286844 0.195666 0.937782 + outer loop + vertex 1.61826 1.93904 2.50576 + vertex 1.61979 1.93495 2.50615 + vertex 1.62248 1.93877 2.50453 + endloop + endfacet + facet normal 0.285005 0.197073 0.938048 + outer loop + vertex 1.62443 1.93314 2.50512 + vertex 1.62248 1.93877 2.50453 + vertex 1.61979 1.93495 2.50615 + endloop + endfacet + facet normal 0.283324 0.191854 0.939638 + outer loop + vertex 1.62132 1.93088 2.50652 + vertex 1.62443 1.93314 2.50512 + vertex 1.61979 1.93495 2.50615 + endloop + endfacet + facet normal 0.288389 0.193582 0.937741 + outer loop + vertex 1.61979 1.93495 2.50615 + vertex 1.61707 1.93115 2.50777 + vertex 1.62132 1.93088 2.50652 + endloop + endfacet + facet normal 0.288376 0.189294 0.93862 + outer loop + vertex 1.62132 1.93088 2.50652 + vertex 1.61707 1.93115 2.50777 + vertex 1.62116 1.92628 2.50749 + endloop + endfacet + facet normal 0.282418 0.18986 0.940316 + outer loop + vertex 1.62132 1.93088 2.50652 + vertex 1.62116 1.92628 2.50749 + vertex 1.62413 1.92899 2.50605 + endloop + endfacet + facet normal 0.288114 0.189067 0.938746 + outer loop + vertex 1.61707 1.93115 2.50777 + vertex 1.61673 1.9266 2.50879 + vertex 1.62116 1.92628 2.50749 + endloop + endfacet + facet normal 0.288709 0.193333 0.937694 + outer loop + vertex 1.6151 1.93685 2.5072 + vertex 1.61707 1.93115 2.50777 + vertex 1.61979 1.93495 2.50615 + endloop + endfacet + facet normal 0.283491 0.191621 0.939635 + outer loop + vertex 1.62413 1.92899 2.50605 + vertex 1.62443 1.93314 2.50512 + vertex 1.62132 1.93088 2.50652 + endloop + endfacet + facet normal 0.280985 0.19583 0.93952 + outer loop + vertex 1.62443 1.93314 2.50512 + vertex 1.62665 1.93647 2.50376 + vertex 1.62248 1.93877 2.50453 + endloop + endfacet + facet normal 0.283281 0.200578 0.937827 + outer loop + vertex 1.62665 1.93647 2.50376 + vertex 1.62698 1.94097 2.50269 + vertex 1.62248 1.93877 2.50453 + endloop + endfacet + facet normal 0.28232 0.202448 0.937715 + outer loop + vertex 1.62248 1.93877 2.50453 + vertex 1.62698 1.94097 2.50269 + vertex 1.62279 1.94327 2.50346 + endloop + endfacet + facet normal 0.285431 0.200282 0.937239 + outer loop + vertex 1.62698 1.94097 2.50269 + vertex 1.62665 1.93647 2.50376 + vertex 1.63107 1.93624 2.50246 + endloop + endfacet + facet normal 0.289831 0.19668 0.936651 + outer loop + vertex 1.61979 1.93495 2.50615 + vertex 1.61826 1.93904 2.50576 + vertex 1.6151 1.93685 2.5072 + endloop + endfacet + facet normal 0.283732 0.20538 0.936651 + outer loop + vertex 1.62698 1.94097 2.50269 + vertex 1.62496 1.94658 2.50208 + vertex 1.62279 1.94327 2.50346 + endloop + endfacet + facet normal 0.287907 0.199881 0.936567 + outer loop + vertex 1.63402 1.93895 2.50099 + vertex 1.63433 1.94306 2.50002 + vertex 1.63121 1.94081 2.50146 + endloop + endfacet + facet normal 0.280411 0.205506 0.937623 + outer loop + vertex 1.62809 1.94881 2.50065 + vertex 1.62967 1.94479 2.50106 + vertex 1.63236 1.94863 2.49941 + endloop + endfacet + facet normal 0.283408 0.201462 0.9376 + outer loop + vertex 1.63656 1.94638 2.49863 + vertex 1.6369 1.95089 2.49756 + vertex 1.63236 1.94863 2.49941 + endloop + endfacet + facet normal 0.2856 0.201153 0.937001 + outer loop + vertex 1.6369 1.95089 2.49756 + vertex 1.63656 1.94638 2.49863 + vertex 1.64099 1.94614 2.49733 + endloop + endfacet + facet normal 0.283565 0.20098 0.937656 + outer loop + vertex 1.64523 1.94581 2.49612 + vertex 1.64394 1.94883 2.49586 + vertex 1.64099 1.94614 2.49733 + endloop + endfacet + facet normal 0.283906 0.201113 0.937524 + outer loop + vertex 1.64394 1.94883 2.49586 + vertex 1.64523 1.94581 2.49612 + vertex 1.64818 1.94849 2.49465 + endloop + endfacet + facet normal 0.284808 0.203696 0.936692 + outer loop + vertex 1.64818 1.94849 2.49465 + vertex 1.65231 1.9437 2.49443 + vertex 1.65262 1.94819 2.49336 + endloop + endfacet + facet normal 0.280982 0.198486 0.938964 + outer loop + vertex 1.64962 1.93989 2.49605 + vertex 1.64806 1.94391 2.49567 + vertex 1.64493 1.94168 2.49708 + endloop + endfacet + facet normal 0.287822 0.19315 0.938004 + outer loop + vertex 1.65401 1.93397 2.49596 + vertex 1.65822 1.93362 2.49474 + vertex 1.65429 1.9381 2.49502 + endloop + endfacet + facet normal 0.287705 0.187923 0.939101 + outer loop + vertex 1.65401 1.93397 2.49596 + vertex 1.65526 1.93092 2.49619 + vertex 1.65822 1.93362 2.49474 + endloop + endfacet + facet normal 0.2896 0.185762 0.938948 + outer loop + vertex 1.65806 1.929 2.4957 + vertex 1.65822 1.93362 2.49474 + vertex 1.65526 1.93092 2.49619 + endloop + endfacet + facet normal 0.287518 0.182408 0.940245 + outer loop + vertex 1.65526 1.93092 2.49619 + vertex 1.65494 1.92673 2.4971 + vertex 1.65806 1.929 2.4957 + endloop + endfacet + facet normal 0.289214 0.180031 0.940183 + outer loop + vertex 1.65957 1.9249 2.49603 + vertex 1.65806 1.929 2.4957 + vertex 1.65494 1.92673 2.4971 + endloop + endfacet + facet normal 0.282484 0.183102 0.941635 + outer loop + vertex 1.65526 1.93092 2.49619 + vertex 1.65103 1.93124 2.49739 + vertex 1.65494 1.92673 2.4971 + endloop + endfacet + facet normal 0.285951 0.186211 0.939977 + outer loop + vertex 1.65103 1.93124 2.49739 + vertex 1.65104 1.92663 2.4983 + vertex 1.65494 1.92673 2.4971 + endloop + endfacet + facet normal 0.286124 0.184011 0.940358 + outer loop + vertex 1.65269 1.92336 2.49844 + vertex 1.65494 1.92673 2.4971 + vertex 1.65104 1.92663 2.4983 + endloop + endfacet + facet normal 0.285352 0.183637 0.940666 + outer loop + vertex 1.65269 1.92336 2.49844 + vertex 1.65104 1.92663 2.4983 + vertex 1.64826 1.92362 2.49974 + endloop + endfacet + facet normal 0.285353 0.183766 0.94064 + outer loop + vertex 1.64826 1.92362 2.49974 + vertex 1.65232 1.91879 2.49945 + vertex 1.65269 1.92336 2.49844 + endloop + endfacet + facet normal 0.290607 0.183022 0.939175 + outer loop + vertex 1.65232 1.91879 2.49945 + vertex 1.65685 1.92103 2.49761 + vertex 1.65269 1.92336 2.49844 + endloop + endfacet + facet normal 0.290878 0.18249 0.939195 + outer loop + vertex 1.65648 1.91645 2.49861 + vertex 1.65685 1.92103 2.49761 + vertex 1.65232 1.91879 2.49945 + endloop + endfacet + facet normal 0.291282 0.183312 0.93891 + outer loop + vertex 1.65426 1.91311 2.49995 + vertex 1.65648 1.91645 2.49861 + vertex 1.65232 1.91879 2.49945 + endloop + endfacet + facet normal 0.288513 0.182456 0.939931 + outer loop + vertex 1.65426 1.91311 2.49995 + vertex 1.65232 1.91879 2.49945 + vertex 1.64961 1.91494 2.50103 + endloop + endfacet + facet normal 0.287993 0.180852 0.9404 + outer loop + vertex 1.65114 1.91086 2.50134 + vertex 1.65426 1.91311 2.49995 + vertex 1.64961 1.91494 2.50103 + endloop + endfacet + facet normal 0.283786 0.179393 0.941957 + outer loop + vertex 1.64961 1.91494 2.50103 + vertex 1.64688 1.91106 2.50259 + vertex 1.65114 1.91086 2.50134 + endloop + endfacet + facet normal 0.283819 0.175143 0.942747 + outer loop + vertex 1.65114 1.91086 2.50134 + vertex 1.64688 1.91106 2.50259 + vertex 1.65098 1.90617 2.50226 + endloop + endfacet + facet normal 0.285174 0.175021 0.942361 + outer loop + vertex 1.65114 1.91086 2.50134 + vertex 1.65098 1.90617 2.50226 + vertex 1.65397 1.90892 2.50085 + endloop + endfacet + facet normal 0.284634 0.175634 0.94241 + outer loop + vertex 1.65523 1.90584 2.50104 + vertex 1.65397 1.90892 2.50085 + vertex 1.65098 1.90617 2.50226 + endloop + endfacet + facet normal 0.284614 0.174803 0.94257 + outer loop + vertex 1.65523 1.90584 2.50104 + vertex 1.65098 1.90617 2.50226 + vertex 1.65488 1.90164 2.50193 + endloop + endfacet + facet normal 0.285855 0.174627 0.942227 + outer loop + vertex 1.65523 1.90584 2.50104 + vertex 1.65488 1.90164 2.50193 + vertex 1.65804 1.90391 2.50055 + endloop + endfacet + facet normal 0.288786 0.179347 0.940445 + outer loop + vertex 1.65804 1.90391 2.50055 + vertex 1.65819 1.90855 2.49962 + vertex 1.65523 1.90584 2.50104 + endloop + endfacet + facet normal 0.284383 0.17671 0.942285 + outer loop + vertex 1.65947 1.89988 2.50087 + vertex 1.65804 1.90391 2.50055 + vertex 1.65488 1.90164 2.50193 + endloop + endfacet + facet normal 0.28253 0.172938 0.943541 + outer loop + vertex 1.65098 1.90617 2.50226 + vertex 1.65098 1.90151 2.50312 + vertex 1.65488 1.90164 2.50193 + endloop + endfacet + facet normal 0.28249 0.173426 0.943463 + outer loop + vertex 1.65259 1.89825 2.50324 + vertex 1.65488 1.90164 2.50193 + vertex 1.65098 1.90151 2.50312 + endloop + endfacet + facet normal 0.281848 0.173118 0.943712 + outer loop + vertex 1.65259 1.89825 2.50324 + vertex 1.65098 1.90151 2.50312 + vertex 1.64815 1.89846 2.50452 + endloop + endfacet + facet normal 0.28184 0.174791 0.943406 + outer loop + vertex 1.64815 1.89846 2.50452 + vertex 1.65211 1.8937 2.50422 + vertex 1.65259 1.89825 2.50324 + endloop + endfacet + facet normal 0.282215 0.17473 0.943305 + outer loop + vertex 1.65211 1.8937 2.50422 + vertex 1.65663 1.89608 2.50243 + vertex 1.65259 1.89825 2.50324 + endloop + endfacet + facet normal 0.282659 0.175495 0.94303 + outer loop + vertex 1.64791 1.89377 2.50547 + vertex 1.65211 1.8937 2.50422 + vertex 1.64815 1.89846 2.50452 + endloop + endfacet + facet normal 0.282559 0.175506 0.943058 + outer loop + vertex 1.64791 1.89377 2.50547 + vertex 1.64815 1.89846 2.50452 + vertex 1.64512 1.89568 2.50595 + endloop + endfacet + facet normal 0.284413 0.178495 0.941939 + outer loop + vertex 1.64512 1.89568 2.50595 + vertex 1.64467 1.8914 2.50689 + vertex 1.64791 1.89377 2.50547 + endloop + endfacet + facet normal 0.285845 0.178259 0.94155 + outer loop + vertex 1.64512 1.89568 2.50595 + vertex 1.64084 1.89608 2.50717 + vertex 1.64467 1.8914 2.50689 + endloop + endfacet + facet normal 0.286165 0.178531 0.941401 + outer loop + vertex 1.64084 1.89608 2.50717 + vertex 1.64062 1.8914 2.50813 + vertex 1.64467 1.8914 2.50689 + endloop + endfacet + facet normal 0.28608 0.180102 0.941128 + outer loop + vertex 1.64209 1.88738 2.50845 + vertex 1.64467 1.8914 2.50689 + vertex 1.64062 1.8914 2.50813 + endloop + endfacet + facet normal 0.287908 0.18072 0.940452 + outer loop + vertex 1.64209 1.88738 2.50845 + vertex 1.64062 1.8914 2.50813 + vertex 1.6375 1.88894 2.50955 + endloop + endfacet + facet normal 0.287565 0.179467 0.940797 + outer loop + vertex 1.63952 1.88338 2.51 + vertex 1.64209 1.88738 2.50845 + vertex 1.6375 1.88894 2.50955 + endloop + endfacet + facet normal 0.288317 0.179717 0.940519 + outer loop + vertex 1.63952 1.88338 2.51 + vertex 1.6375 1.88894 2.50955 + vertex 1.63485 1.88506 2.51111 + endloop + endfacet + facet normal 0.289042 0.179174 0.9404 + outer loop + vertex 1.6335 1.88898 2.51077 + vertex 1.63485 1.88506 2.51111 + vertex 1.6375 1.88894 2.50955 + endloop + endfacet + facet normal 0.289025 0.179547 0.940334 + outer loop + vertex 1.6335 1.88898 2.51077 + vertex 1.6375 1.88894 2.50955 + vertex 1.63401 1.89316 2.50982 + endloop + endfacet + facet normal 0.288428 0.179657 0.940496 + outer loop + vertex 1.6335 1.88898 2.51077 + vertex 1.63401 1.89316 2.50982 + vertex 1.63082 1.89097 2.51122 + endloop + endfacet + facet normal 0.287659 0.178519 0.940948 + outer loop + vertex 1.63082 1.89097 2.51122 + vertex 1.63031 1.88675 2.51217 + vertex 1.6335 1.88898 2.51077 + endloop + endfacet + facet normal 0.285927 0.178836 0.941416 + outer loop + vertex 1.63082 1.89097 2.51122 + vertex 1.62668 1.89111 2.51245 + vertex 1.63031 1.88675 2.51217 + endloop + endfacet + facet normal 0.288955 0.17888 0.940482 + outer loop + vertex 1.63082 1.89097 2.51122 + vertex 1.63401 1.89316 2.50982 + vertex 1.6295 1.8949 2.51087 + endloop + endfacet + facet normal 0.287532 0.178703 0.940952 + outer loop + vertex 1.63485 1.88506 2.51111 + vertex 1.6335 1.88898 2.51077 + vertex 1.63031 1.88675 2.51217 + endloop + endfacet + facet normal 0.286928 0.17673 0.941509 + outer loop + vertex 1.63031 1.88675 2.51217 + vertex 1.63207 1.88116 2.51269 + vertex 1.63485 1.88506 2.51111 + endloop + endfacet + facet normal 0.286558 0.177017 0.941568 + outer loop + vertex 1.63485 1.88506 2.51111 + vertex 1.63207 1.88116 2.51269 + vertex 1.63628 1.88103 2.51143 + endloop + endfacet + facet normal 0.286632 0.173644 0.942173 + outer loop + vertex 1.63628 1.88103 2.51143 + vertex 1.63207 1.88116 2.51269 + vertex 1.63598 1.87632 2.51239 + endloop + endfacet + facet normal 0.286087 0.17371 0.942326 + outer loop + vertex 1.63628 1.88103 2.51143 + vertex 1.63598 1.87632 2.51239 + vertex 1.63907 1.87909 2.51094 + endloop + endfacet + facet normal 0.285793 0.174051 0.942352 + outer loop + vertex 1.64026 1.87595 2.51116 + vertex 1.63907 1.87909 2.51094 + vertex 1.63598 1.87632 2.51239 + endloop + endfacet + facet normal 0.285708 0.171419 0.942861 + outer loop + vertex 1.64026 1.87595 2.51116 + vertex 1.63598 1.87632 2.51239 + vertex 1.63981 1.87161 2.51209 + endloop + endfacet + facet normal 0.284813 0.171565 0.943105 + outer loop + vertex 1.64026 1.87595 2.51116 + vertex 1.63981 1.87161 2.51209 + vertex 1.64306 1.87401 2.51067 + endloop + endfacet + facet normal 0.286616 0.174441 0.94203 + outer loop + vertex 1.64306 1.87401 2.51067 + vertex 1.64335 1.8787 2.50971 + vertex 1.64026 1.87595 2.51116 + endloop + endfacet + facet normal 0.285476 0.174577 0.942351 + outer loop + vertex 1.64306 1.87401 2.51067 + vertex 1.6473 1.87387 2.50941 + vertex 1.64335 1.8787 2.50971 + endloop + endfacet + facet normal 0.286017 0.175034 0.942103 + outer loop + vertex 1.64335 1.8787 2.50971 + vertex 1.6473 1.87387 2.50941 + vertex 1.64778 1.87839 2.50842 + endloop + endfacet + facet normal 0.286055 0.177599 0.941611 + outer loop + vertex 1.64778 1.87839 2.50842 + vertex 1.64628 1.88159 2.50827 + vertex 1.64335 1.8787 2.50971 + endloop + endfacet + facet normal 0.285943 0.177719 0.941622 + outer loop + vertex 1.64335 1.8787 2.50971 + vertex 1.64628 1.88159 2.50827 + vertex 1.64357 1.88337 2.50876 + endloop + endfacet + facet normal 0.286662 0.178938 0.941173 + outer loop + vertex 1.64628 1.88159 2.50827 + vertex 1.64667 1.88585 2.50735 + vertex 1.64357 1.88337 2.50876 + endloop + endfacet + facet normal 0.286368 0.179316 0.94119 + outer loop + vertex 1.64357 1.88337 2.50876 + vertex 1.64667 1.88585 2.50735 + vertex 1.64209 1.88738 2.50845 + endloop + endfacet + facet normal 0.285881 0.177521 0.941679 + outer loop + vertex 1.64778 1.87839 2.50842 + vertex 1.65015 1.88167 2.50708 + vertex 1.64628 1.88159 2.50827 + endloop + endfacet + facet normal 0.285766 0.179073 0.941419 + outer loop + vertex 1.64667 1.88585 2.50735 + vertex 1.64628 1.88159 2.50827 + vertex 1.65015 1.88167 2.50708 + endloop + endfacet + facet normal 0.285349 0.178712 0.941615 + outer loop + vertex 1.65064 1.88586 2.50614 + vertex 1.64667 1.88585 2.50735 + vertex 1.65015 1.88167 2.50708 + endloop + endfacet + facet normal 0.284172 0.178922 0.941931 + outer loop + vertex 1.65064 1.88586 2.50614 + vertex 1.65015 1.88167 2.50708 + vertex 1.65331 1.8839 2.50571 + endloop + endfacet + facet normal 0.283707 0.178228 0.942202 + outer loop + vertex 1.65331 1.8839 2.50571 + vertex 1.65383 1.88813 2.50475 + vertex 1.65064 1.88586 2.50614 + endloop + endfacet + facet normal 0.283618 0.178354 0.942205 + outer loop + vertex 1.65064 1.88586 2.50614 + vertex 1.65383 1.88813 2.50475 + vertex 1.64932 1.88976 2.5058 + endloop + endfacet + facet normal 0.283257 0.17714 0.942543 + outer loop + vertex 1.65383 1.88813 2.50475 + vertex 1.65211 1.8937 2.50422 + vertex 1.64932 1.88976 2.5058 + endloop + endfacet + facet normal 0.284164 0.178933 0.941931 + outer loop + vertex 1.65466 1.87997 2.50605 + vertex 1.65331 1.8839 2.50571 + vertex 1.65015 1.88167 2.50708 + endloop + endfacet + facet normal 0.285339 0.178881 0.941585 + outer loop + vertex 1.64932 1.88976 2.5058 + vertex 1.64667 1.88585 2.50735 + vertex 1.65064 1.88586 2.50614 + endloop + endfacet + facet normal 0.284833 0.179256 0.941667 + outer loop + vertex 1.64467 1.8914 2.50689 + vertex 1.64667 1.88585 2.50735 + vertex 1.64932 1.88976 2.5058 + endloop + endfacet + facet normal 0.284558 0.178294 0.941933 + outer loop + vertex 1.64932 1.88976 2.5058 + vertex 1.64791 1.89377 2.50547 + vertex 1.64467 1.8914 2.50689 + endloop + endfacet + facet normal 0.285937 0.177476 0.94167 + outer loop + vertex 1.65189 1.87612 2.5076 + vertex 1.65015 1.88167 2.50708 + vertex 1.64778 1.87839 2.50842 + endloop + endfacet + facet normal 0.284844 0.175228 0.942422 + outer loop + vertex 1.6473 1.87387 2.50941 + vertex 1.65189 1.87612 2.5076 + vertex 1.64778 1.87839 2.50842 + endloop + endfacet + facet normal 0.285411 0.174102 0.942459 + outer loop + vertex 1.65143 1.87159 2.50858 + vertex 1.65189 1.87612 2.5076 + vertex 1.6473 1.87387 2.50941 + endloop + endfacet + facet normal 0.2841 0.171404 0.943349 + outer loop + vertex 1.64902 1.86827 2.50991 + vertex 1.65143 1.87159 2.50858 + vertex 1.6473 1.87387 2.50941 + endloop + endfacet + facet normal 0.28579 0.171869 0.942754 + outer loop + vertex 1.64902 1.86827 2.50991 + vertex 1.6473 1.87387 2.50941 + vertex 1.64449 1.86995 2.51097 + endloop + endfacet + facet normal 0.285195 0.169926 0.943286 + outer loop + vertex 1.64583 1.86601 2.51128 + vertex 1.64902 1.86827 2.50991 + vertex 1.64449 1.86995 2.51097 + endloop + endfacet + facet normal 0.283716 0.169467 0.943815 + outer loop + vertex 1.64449 1.86995 2.51097 + vertex 1.64181 1.86599 2.51249 + vertex 1.64583 1.86601 2.51128 + endloop + endfacet + facet normal 0.283921 0.165622 0.944435 + outer loop + vertex 1.64583 1.86601 2.51128 + vertex 1.64181 1.86599 2.51249 + vertex 1.64528 1.86178 2.51218 + endloop + endfacet + facet normal 0.28563 0.165305 0.943976 + outer loop + vertex 1.64583 1.86601 2.51128 + vertex 1.64528 1.86178 2.51218 + vertex 1.64848 1.86405 2.51082 + endloop + endfacet + facet normal 0.287156 0.163103 0.943896 + outer loop + vertex 1.64979 1.86009 2.51111 + vertex 1.64848 1.86405 2.51082 + vertex 1.64528 1.86178 2.51218 + endloop + endfacet + facet normal 0.285312 0.166817 0.943806 + outer loop + vertex 1.64181 1.86599 2.51249 + vertex 1.64138 1.86168 2.51338 + vertex 1.64528 1.86178 2.51218 + endloop + endfacet + facet normal 0.285515 0.164023 0.944234 + outer loop + vertex 1.64285 1.85846 2.5135 + vertex 1.64528 1.86178 2.51218 + vertex 1.64138 1.86168 2.51338 + endloop + endfacet + facet normal 0.284412 0.163534 0.944651 + outer loop + vertex 1.64285 1.85846 2.5135 + vertex 1.64138 1.86168 2.51338 + vertex 1.6384 1.85877 2.51479 + endloop + endfacet + facet normal 0.284386 0.162086 0.944909 + outer loop + vertex 1.6384 1.85877 2.51479 + vertex 1.64234 1.8539 2.51443 + vertex 1.64285 1.85846 2.5135 + endloop + endfacet + facet normal 0.287268 0.161603 0.94412 + outer loop + vertex 1.64234 1.8539 2.51443 + vertex 1.64696 1.85616 2.51264 + vertex 1.64285 1.85846 2.5135 + endloop + endfacet + facet normal 0.287501 0.161136 0.944129 + outer loop + vertex 1.64646 1.85158 2.51357 + vertex 1.64696 1.85616 2.51264 + vertex 1.64234 1.8539 2.51443 + endloop + endfacet + facet normal 0.287662 0.161462 0.944024 + outer loop + vertex 1.64407 1.84826 2.51487 + vertex 1.64646 1.85158 2.51357 + vertex 1.64234 1.8539 2.51443 + endloop + endfacet + facet normal 0.287362 0.161379 0.944129 + outer loop + vertex 1.64407 1.84826 2.51487 + vertex 1.64234 1.8539 2.51443 + vertex 1.63954 1.85001 2.51595 + endloop + endfacet + facet normal 0.287458 0.161673 0.94405 + outer loop + vertex 1.64087 1.84602 2.51623 + vertex 1.64407 1.84826 2.51487 + vertex 1.63954 1.85001 2.51595 + endloop + endfacet + facet normal 0.287208 0.161596 0.944139 + outer loop + vertex 1.63954 1.85001 2.51595 + vertex 1.63673 1.84617 2.51746 + vertex 1.64087 1.84602 2.51623 + endloop + endfacet + facet normal 0.287221 0.160475 0.944326 + outer loop + vertex 1.64087 1.84602 2.51623 + vertex 1.63673 1.84617 2.51746 + vertex 1.6403 1.84177 2.51712 + endloop + endfacet + facet normal 0.287519 0.160419 0.944245 + outer loop + vertex 1.64087 1.84602 2.51623 + vertex 1.6403 1.84177 2.51712 + vertex 1.64354 1.84402 2.51576 + endloop + endfacet + facet normal 0.287897 0.159862 0.944224 + outer loop + vertex 1.64476 1.84011 2.51604 + vertex 1.64354 1.84402 2.51576 + vertex 1.6403 1.84177 2.51712 + endloop + endfacet + facet normal 0.287087 0.157234 0.944912 + outer loop + vertex 1.6403 1.84177 2.51712 + vertex 1.64186 1.83626 2.51757 + vertex 1.64476 1.84011 2.51604 + endloop + endfacet + facet normal 0.287059 0.157257 0.944917 + outer loop + vertex 1.64476 1.84011 2.51604 + vertex 1.64186 1.83626 2.51757 + vertex 1.64597 1.83618 2.51633 + endloop + endfacet + facet normal 0.287128 0.157277 0.944892 + outer loop + vertex 1.64597 1.83618 2.51633 + vertex 1.6493 1.8385 2.51493 + vertex 1.64476 1.84011 2.51604 + endloop + endfacet + facet normal 0.287929 0.160009 0.94419 + outer loop + vertex 1.6493 1.8385 2.51493 + vertex 1.64752 1.84402 2.51454 + vertex 1.64476 1.84011 2.51604 + endloop + endfacet + facet normal 0.285075 0.159159 0.945199 + outer loop + vertex 1.6493 1.8385 2.51493 + vertex 1.65208 1.84248 2.51343 + vertex 1.64752 1.84402 2.51454 + endloop + endfacet + facet normal 0.285952 0.162345 0.944391 + outer loop + vertex 1.65208 1.84248 2.51343 + vertex 1.65067 1.84651 2.51316 + vertex 1.64752 1.84402 2.51454 + endloop + endfacet + facet normal 0.286634 0.161455 0.944337 + outer loop + vertex 1.64752 1.84402 2.51454 + vertex 1.65067 1.84651 2.51316 + vertex 1.64795 1.84832 2.51367 + endloop + endfacet + facet normal 0.28826 0.161199 0.943886 + outer loop + vertex 1.64407 1.84826 2.51487 + vertex 1.64752 1.84402 2.51454 + vertex 1.64795 1.84832 2.51367 + endloop + endfacet + facet normal 0.288008 0.160985 0.944 + outer loop + vertex 1.64354 1.84402 2.51576 + vertex 1.64752 1.84402 2.51454 + vertex 1.64407 1.84826 2.51487 + endloop + endfacet + facet normal 0.286649 0.161479 0.944329 + outer loop + vertex 1.65067 1.84651 2.51316 + vertex 1.65089 1.85125 2.51228 + vertex 1.64795 1.84832 2.51367 + endloop + endfacet + facet normal 0.287461 0.160618 0.944229 + outer loop + vertex 1.64795 1.84832 2.51367 + vertex 1.65089 1.85125 2.51228 + vertex 1.64646 1.85158 2.51357 + endloop + endfacet + facet normal 0.282297 0.161155 0.945694 + outer loop + vertex 1.65208 1.84248 2.51343 + vertex 1.65472 1.84653 2.51195 + vertex 1.65067 1.84651 2.51316 + endloop + endfacet + facet normal 0.27991 0.162862 0.946111 + outer loop + vertex 1.65666 1.8409 2.51234 + vertex 1.65472 1.84653 2.51195 + vertex 1.65208 1.84248 2.51343 + endloop + endfacet + facet normal 0.278694 0.15858 0.947197 + outer loop + vertex 1.65337 1.83849 2.51371 + vertex 1.65666 1.8409 2.51234 + vertex 1.65208 1.84248 2.51343 + endloop + endfacet + facet normal 0.28382 0.160116 0.945415 + outer loop + vertex 1.65337 1.83849 2.51371 + vertex 1.65208 1.84248 2.51343 + vertex 1.6493 1.8385 2.51493 + endloop + endfacet + facet normal 0.284008 0.15584 0.946072 + outer loop + vertex 1.6493 1.8385 2.51493 + vertex 1.65267 1.83413 2.51464 + vertex 1.65337 1.83849 2.51371 + endloop + endfacet + facet normal 0.284887 0.156542 0.945692 + outer loop + vertex 1.64861 1.83417 2.51586 + vertex 1.65267 1.83413 2.51464 + vertex 1.6493 1.8385 2.51493 + endloop + endfacet + facet normal 0.288101 0.155842 0.944834 + outer loop + vertex 1.64861 1.83417 2.51586 + vertex 1.6493 1.8385 2.51493 + vertex 1.64597 1.83618 2.51633 + endloop + endfacet + facet normal 0.286078 0.152932 0.945923 + outer loop + vertex 1.64597 1.83618 2.51633 + vertex 1.64532 1.8319 2.51722 + vertex 1.64861 1.83417 2.51586 + endloop + endfacet + facet normal 0.287096 0.151417 0.945859 + outer loop + vertex 1.64978 1.83021 2.51614 + vertex 1.64861 1.83417 2.51586 + vertex 1.64532 1.8319 2.51722 + endloop + endfacet + facet normal 0.287188 0.1527 0.945625 + outer loop + vertex 1.64597 1.83618 2.51633 + vertex 1.64186 1.83626 2.51757 + vertex 1.64532 1.8319 2.51722 + endloop + endfacet + facet normal 0.287026 0.152565 0.945696 + outer loop + vertex 1.64186 1.83626 2.51757 + vertex 1.64128 1.83174 2.51847 + vertex 1.64532 1.8319 2.51722 + endloop + endfacet + facet normal 0.287347 0.148679 0.946217 + outer loop + vertex 1.64294 1.82843 2.51849 + vertex 1.64532 1.8319 2.51722 + vertex 1.64128 1.83174 2.51847 + endloop + endfacet + facet normal 0.285286 0.147649 0.947001 + outer loop + vertex 1.64294 1.82843 2.51849 + vertex 1.64128 1.83174 2.51847 + vertex 1.63891 1.82824 2.51973 + endloop + endfacet + facet normal 0.285465 0.145576 0.947269 + outer loop + vertex 1.63891 1.82824 2.51973 + vertex 1.64237 1.82386 2.51936 + vertex 1.64294 1.82843 2.51849 + endloop + endfacet + facet normal 0.28643 0.145406 0.947003 + outer loop + vertex 1.64237 1.82386 2.51936 + vertex 1.64684 1.82634 2.51763 + vertex 1.64294 1.82843 2.51849 + endloop + endfacet + facet normal 0.285026 0.145213 0.947456 + outer loop + vertex 1.63827 1.82391 2.52059 + vertex 1.64237 1.82386 2.51936 + vertex 1.63891 1.82824 2.51973 + endloop + endfacet + facet normal 0.284422 0.145334 0.947619 + outer loop + vertex 1.63827 1.82391 2.52059 + vertex 1.63891 1.82824 2.51973 + vertex 1.63566 1.82591 2.52107 + endloop + endfacet + facet normal 0.284122 0.144904 0.947775 + outer loop + vertex 1.63566 1.82591 2.52107 + vertex 1.63496 1.82153 2.52194 + vertex 1.63827 1.82391 2.52059 + endloop + endfacet + facet normal 0.284192 0.144804 0.94777 + outer loop + vertex 1.63948 1.81993 2.52084 + vertex 1.63827 1.82391 2.52059 + vertex 1.63496 1.82153 2.52194 + endloop + endfacet + facet normal 0.284531 0.145954 0.947491 + outer loop + vertex 1.63496 1.82153 2.52194 + vertex 1.63666 1.81595 2.5223 + vertex 1.63948 1.81993 2.52084 + endloop + endfacet + facet normal 0.285295 0.145362 0.947352 + outer loop + vertex 1.63948 1.81993 2.52084 + vertex 1.63666 1.81595 2.5223 + vertex 1.64068 1.81594 2.52108 + endloop + endfacet + facet normal 0.285488 0.145416 0.947286 + outer loop + vertex 1.64068 1.81594 2.52108 + vertex 1.64393 1.81827 2.51975 + vertex 1.63948 1.81993 2.52084 + endloop + endfacet + facet normal 0.285303 0.144821 0.947433 + outer loop + vertex 1.64393 1.81827 2.51975 + vertex 1.64237 1.82386 2.51936 + vertex 1.63948 1.81993 2.52084 + endloop + endfacet + facet normal 0.285952 0.144747 0.947248 + outer loop + vertex 1.64334 1.81394 2.52059 + vertex 1.64393 1.81827 2.51975 + vertex 1.64068 1.81594 2.52108 + endloop + endfacet + facet normal 0.285313 0.143821 0.947582 + outer loop + vertex 1.64068 1.81594 2.52108 + vertex 1.64003 1.81156 2.52195 + vertex 1.64334 1.81394 2.52059 + endloop + endfacet + facet normal 0.286396 0.142266 0.94749 + outer loop + vertex 1.64456 1.80994 2.52082 + vertex 1.64334 1.81394 2.52059 + vertex 1.64003 1.81156 2.52195 + endloop + endfacet + facet normal 0.285359 0.143812 0.94757 + outer loop + vertex 1.64068 1.81594 2.52108 + vertex 1.63666 1.81595 2.5223 + vertex 1.64003 1.81156 2.52195 + endloop + endfacet + facet normal 0.283418 0.145053 0.947963 + outer loop + vertex 1.63566 1.82591 2.52107 + vertex 1.63164 1.8259 2.52227 + vertex 1.63496 1.82153 2.52194 + endloop + endfacet + facet normal 0.283471 0.145095 0.947941 + outer loop + vertex 1.63164 1.8259 2.52227 + vertex 1.63092 1.82151 2.52316 + vertex 1.63496 1.82153 2.52194 + endloop + endfacet + facet normal 0.283391 0.146818 0.947699 + outer loop + vertex 1.63212 1.81753 2.52341 + vertex 1.63496 1.82153 2.52194 + vertex 1.63092 1.82151 2.52316 + endloop + endfacet + facet normal 0.283227 0.145148 0.948006 + outer loop + vertex 1.63092 1.82151 2.52316 + vertex 1.63164 1.8259 2.52227 + vertex 1.62831 1.82349 2.52363 + endloop + endfacet + facet normal 0.2843 0.146703 0.947445 + outer loop + vertex 1.62758 1.81911 2.52453 + vertex 1.63092 1.82151 2.52316 + vertex 1.62831 1.82349 2.52363 + endloop + endfacet + facet normal 0.282974 0.145509 0.948026 + outer loop + vertex 1.62831 1.82349 2.52363 + vertex 1.63164 1.8259 2.52227 + vertex 1.62713 1.82747 2.52337 + endloop + endfacet + facet normal 0.283524 0.145659 0.947838 + outer loop + vertex 1.62831 1.82349 2.52363 + vertex 1.62713 1.82747 2.52337 + vertex 1.62424 1.82348 2.52485 + endloop + endfacet + facet normal 0.281817 0.147009 0.948139 + outer loop + vertex 1.62424 1.82348 2.52485 + vertex 1.62713 1.82747 2.52337 + vertex 1.62258 1.82904 2.52448 + endloop + endfacet + facet normal 0.283378 0.147439 0.947607 + outer loop + vertex 1.62424 1.82348 2.52485 + vertex 1.62258 1.82904 2.52448 + vertex 1.61968 1.82509 2.52596 + endloop + endfacet + facet normal 0.281479 0.145831 0.948421 + outer loop + vertex 1.62713 1.82747 2.52337 + vertex 1.62596 1.83144 2.52311 + vertex 1.62258 1.82904 2.52448 + endloop + endfacet + facet normal 0.279845 0.148192 0.948539 + outer loop + vertex 1.62258 1.82904 2.52448 + vertex 1.62596 1.83144 2.52311 + vertex 1.62332 1.83342 2.52358 + endloop + endfacet + facet normal 0.278795 0.148424 0.948812 + outer loop + vertex 1.61921 1.8334 2.52479 + vertex 1.62258 1.82904 2.52448 + vertex 1.62332 1.83342 2.52358 + endloop + endfacet + facet normal 0.278669 0.150977 0.948446 + outer loop + vertex 1.62332 1.83342 2.52358 + vertex 1.62206 1.83744 2.52331 + vertex 1.61921 1.8334 2.52479 + endloop + endfacet + facet normal 0.277621 0.151783 0.948625 + outer loop + vertex 1.61921 1.8334 2.52479 + vertex 1.62206 1.83744 2.52331 + vertex 1.61745 1.83895 2.52442 + endloop + endfacet + facet normal 0.277872 0.152712 0.948402 + outer loop + vertex 1.62206 1.83744 2.52331 + vertex 1.62069 1.84151 2.52306 + vertex 1.61745 1.83895 2.52442 + endloop + endfacet + facet normal 0.27742 0.153304 0.948439 + outer loop + vertex 1.61745 1.83895 2.52442 + vertex 1.62069 1.84151 2.52306 + vertex 1.61796 1.84331 2.52356 + endloop + endfacet + facet normal 0.276513 0.153457 0.948679 + outer loop + vertex 1.61401 1.84318 2.52474 + vertex 1.61745 1.83895 2.52442 + vertex 1.61796 1.84331 2.52356 + endloop + endfacet + facet normal 0.27892 0.155811 0.94759 + outer loop + vertex 1.62069 1.84151 2.52306 + vertex 1.62095 1.84628 2.5222 + vertex 1.61796 1.84331 2.52356 + endloop + endfacet + facet normal 0.278639 0.15611 0.947623 + outer loop + vertex 1.61796 1.84331 2.52356 + vertex 1.62095 1.84628 2.5222 + vertex 1.61648 1.84657 2.52346 + endloop + endfacet + facet normal 0.279627 0.155737 0.947394 + outer loop + vertex 1.62095 1.84628 2.5222 + vertex 1.62069 1.84151 2.52306 + vertex 1.62478 1.84153 2.52184 + endloop + endfacet + facet normal 0.281071 0.15695 0.946766 + outer loop + vertex 1.62525 1.8459 2.52098 + vertex 1.62095 1.84628 2.5222 + vertex 1.62478 1.84153 2.52184 + endloop + endfacet + facet normal 0.282015 0.156797 0.94651 + outer loop + vertex 1.62525 1.8459 2.52098 + vertex 1.62478 1.84153 2.52184 + vertex 1.62805 1.84394 2.52047 + endloop + endfacet + facet normal 0.284515 0.160731 0.945102 + outer loop + vertex 1.62805 1.84394 2.52047 + vertex 1.62826 1.84868 2.5196 + vertex 1.62525 1.8459 2.52098 + endloop + endfacet + facet normal 0.285113 0.16005 0.945037 + outer loop + vertex 1.62402 1.84906 2.52082 + vertex 1.62525 1.8459 2.52098 + vertex 1.62826 1.84868 2.5196 + endloop + endfacet + facet normal 0.285168 0.16155 0.944765 + outer loop + vertex 1.62402 1.84906 2.52082 + vertex 1.62826 1.84868 2.5196 + vertex 1.62438 1.85329 2.51999 + endloop + endfacet + facet normal 0.284051 0.161704 0.945075 + outer loop + vertex 1.62402 1.84906 2.52082 + vertex 1.62438 1.85329 2.51999 + vertex 1.62121 1.85101 2.52133 + endloop + endfacet + facet normal 0.281675 0.157943 0.946421 + outer loop + vertex 1.62121 1.85101 2.52133 + vertex 1.62095 1.84628 2.5222 + vertex 1.62402 1.84906 2.52082 + endloop + endfacet + facet normal 0.279502 0.158174 0.947027 + outer loop + vertex 1.62121 1.85101 2.52133 + vertex 1.61698 1.85116 2.52255 + vertex 1.62095 1.84628 2.5222 + endloop + endfacet + facet normal 0.279477 0.160294 0.946678 + outer loop + vertex 1.61979 1.85508 2.52106 + vertex 1.61698 1.85116 2.52255 + vertex 1.62121 1.85101 2.52133 + endloop + endfacet + facet normal 0.27876 0.160854 0.946794 + outer loop + vertex 1.61527 1.85675 2.52211 + vertex 1.61698 1.85116 2.52255 + vertex 1.61979 1.85508 2.52106 + endloop + endfacet + facet normal 0.279039 0.161756 0.946558 + outer loop + vertex 1.61979 1.85508 2.52106 + vertex 1.61847 1.85904 2.52077 + vertex 1.61527 1.85675 2.52211 + endloop + endfacet + facet normal 0.277266 0.164289 0.946643 + outer loop + vertex 1.61579 1.86098 2.52122 + vertex 1.61527 1.85675 2.52211 + vertex 1.61847 1.85904 2.52077 + endloop + endfacet + facet normal 0.284442 0.163419 0.944662 + outer loop + vertex 1.61847 1.85904 2.52077 + vertex 1.61979 1.85508 2.52106 + vertex 1.6226 1.85892 2.51955 + endloop + endfacet + facet normal 0.284378 0.166612 0.944124 + outer loop + vertex 1.61847 1.85904 2.52077 + vertex 1.6226 1.85892 2.51955 + vertex 1.61899 1.86329 2.51986 + endloop + endfacet + facet normal 0.2838 0.166116 0.944385 + outer loop + vertex 1.61899 1.86329 2.51986 + vertex 1.6226 1.85892 2.51955 + vertex 1.62305 1.86346 2.51861 + endloop + endfacet + facet normal 0.287264 0.165575 0.943432 + outer loop + vertex 1.6226 1.85892 2.51955 + vertex 1.6271 1.86126 2.51777 + vertex 1.62305 1.86346 2.51861 + endloop + endfacet + facet normal 0.288017 0.167155 0.942924 + outer loop + vertex 1.6271 1.86126 2.51777 + vertex 1.62537 1.86691 2.51729 + vertex 1.62305 1.86346 2.51861 + endloop + endfacet + facet normal 0.285821 0.168777 0.943303 + outer loop + vertex 1.62305 1.86346 2.51861 + vertex 1.62537 1.86691 2.51729 + vertex 1.6213 1.86677 2.51855 + endloop + endfacet + facet normal 0.2869 0.166846 0.943319 + outer loop + vertex 1.62537 1.86691 2.51729 + vertex 1.6271 1.86126 2.51777 + vertex 1.6299 1.86518 2.51622 + endloop + endfacet + facet normal 0.286998 0.167155 0.943235 + outer loop + vertex 1.6299 1.86518 2.51622 + vertex 1.62859 1.86915 2.51592 + vertex 1.62537 1.86691 2.51729 + endloop + endfacet + facet normal 0.286295 0.168183 0.943266 + outer loop + vertex 1.62592 1.87115 2.51637 + vertex 1.62537 1.86691 2.51729 + vertex 1.62859 1.86915 2.51592 + endloop + endfacet + facet normal 0.286602 0.168632 0.943092 + outer loop + vertex 1.62859 1.86915 2.51592 + vertex 1.62914 1.87335 2.515 + vertex 1.62592 1.87115 2.51637 + endloop + endfacet + facet normal 0.285093 0.170879 0.943145 + outer loop + vertex 1.62592 1.87115 2.51637 + vertex 1.62914 1.87335 2.515 + vertex 1.62468 1.87504 2.51604 + endloop + endfacet + facet normal 0.283763 0.170493 0.943616 + outer loop + vertex 1.62468 1.87504 2.51604 + vertex 1.6218 1.87125 2.51759 + vertex 1.62592 1.87115 2.51637 + endloop + endfacet + facet normal 0.281466 0.172383 0.94396 + outer loop + vertex 1.62022 1.87666 2.51708 + vertex 1.6218 1.87125 2.51759 + vertex 1.62468 1.87504 2.51604 + endloop + endfacet + facet normal 0.28523 0.171317 0.943024 + outer loop + vertex 1.62914 1.87335 2.515 + vertex 1.62755 1.87882 2.51449 + vertex 1.62468 1.87504 2.51604 + endloop + endfacet + facet normal 0.283426 0.172797 0.943298 + outer loop + vertex 1.62343 1.87891 2.51571 + vertex 1.62468 1.87504 2.51604 + vertex 1.62755 1.87882 2.51449 + endloop + endfacet + facet normal 0.284412 0.171105 0.943309 + outer loop + vertex 1.62914 1.87335 2.515 + vertex 1.63156 1.87664 2.51367 + vertex 1.62755 1.87882 2.51449 + endloop + endfacet + facet normal 0.285579 0.173549 0.94251 + outer loop + vertex 1.63156 1.87664 2.51367 + vertex 1.63207 1.88116 2.51269 + vertex 1.62755 1.87882 2.51449 + endloop + endfacet + facet normal 0.285207 0.174254 0.942493 + outer loop + vertex 1.62755 1.87882 2.51449 + vertex 1.63207 1.88116 2.51269 + vertex 1.62801 1.88332 2.51351 + endloop + endfacet + facet normal 0.28234 0.17472 0.94327 + outer loop + vertex 1.62394 1.88315 2.51477 + vertex 1.62755 1.87882 2.51449 + vertex 1.62801 1.88332 2.51351 + endloop + endfacet + facet normal 0.285641 0.170125 0.943115 + outer loop + vertex 1.63302 1.87341 2.51381 + vertex 1.63156 1.87664 2.51367 + vertex 1.62914 1.87335 2.515 + endloop + endfacet + facet normal 0.285766 0.168215 0.94342 + outer loop + vertex 1.62914 1.87335 2.515 + vertex 1.6326 1.8691 2.51471 + vertex 1.63302 1.87341 2.51381 + endloop + endfacet + facet normal 0.285208 0.168301 0.943574 + outer loop + vertex 1.6326 1.8691 2.51471 + vertex 1.63574 1.87159 2.51332 + vertex 1.63302 1.87341 2.51381 + endloop + endfacet + facet normal 0.286416 0.170302 0.942849 + outer loop + vertex 1.63574 1.87159 2.51332 + vertex 1.63598 1.87632 2.51239 + vertex 1.63302 1.87341 2.51381 + endloop + endfacet + facet normal 0.284928 0.168665 0.943593 + outer loop + vertex 1.6372 1.86752 2.5136 + vertex 1.63574 1.87159 2.51332 + vertex 1.6326 1.8691 2.51471 + endloop + endfacet + facet normal 0.284439 0.166915 0.944052 + outer loop + vertex 1.63457 1.86346 2.51511 + vertex 1.6372 1.86752 2.5136 + vertex 1.6326 1.8691 2.51471 + endloop + endfacet + facet normal 0.28585 0.167372 0.943544 + outer loop + vertex 1.63457 1.86346 2.51511 + vertex 1.6326 1.8691 2.51471 + vertex 1.6299 1.86518 2.51622 + endloop + endfacet + facet normal 0.283462 0.167611 0.944222 + outer loop + vertex 1.63866 1.86347 2.51388 + vertex 1.6372 1.86752 2.5136 + vertex 1.63457 1.86346 2.51511 + endloop + endfacet + facet normal 0.283577 0.16529 0.944597 + outer loop + vertex 1.63457 1.86346 2.51511 + vertex 1.6384 1.85877 2.51479 + vertex 1.63866 1.86347 2.51388 + endloop + endfacet + facet normal 0.283309 0.16756 0.944277 + outer loop + vertex 1.63866 1.86347 2.51388 + vertex 1.64181 1.86599 2.51249 + vertex 1.6372 1.86752 2.5136 + endloop + endfacet + facet normal 0.283767 0.169256 0.943837 + outer loop + vertex 1.64181 1.86599 2.51249 + vertex 1.63981 1.87161 2.51209 + vertex 1.6372 1.86752 2.5136 + endloop + endfacet + facet normal 0.284711 0.168592 0.943672 + outer loop + vertex 1.6372 1.86752 2.5136 + vertex 1.63981 1.87161 2.51209 + vertex 1.63574 1.87159 2.51332 + endloop + endfacet + facet normal 0.286309 0.170416 0.94286 + outer loop + vertex 1.63302 1.87341 2.51381 + vertex 1.63598 1.87632 2.51239 + vertex 1.63156 1.87664 2.51367 + endloop + endfacet + facet normal 0.286322 0.168685 0.943168 + outer loop + vertex 1.62859 1.86915 2.51592 + vertex 1.6326 1.8691 2.51471 + vertex 1.62914 1.87335 2.515 + endloop + endfacet + facet normal 0.283813 0.16865 0.943932 + outer loop + vertex 1.62592 1.87115 2.51637 + vertex 1.6218 1.87125 2.51759 + vertex 1.62537 1.86691 2.51729 + endloop + endfacet + facet normal 0.286386 0.166969 0.943454 + outer loop + vertex 1.62859 1.86915 2.51592 + vertex 1.6299 1.86518 2.51622 + vertex 1.6326 1.8691 2.51471 + endloop + endfacet + facet normal 0.287336 0.166505 0.943246 + outer loop + vertex 1.6299 1.86518 2.51622 + vertex 1.6271 1.86126 2.51777 + vertex 1.63131 1.8611 2.51651 + endloop + endfacet + facet normal 0.287349 0.165463 0.943426 + outer loop + vertex 1.63131 1.8611 2.51651 + vertex 1.6271 1.86126 2.51777 + vertex 1.63106 1.85639 2.51742 + endloop + endfacet + facet normal 0.287447 0.165546 0.943382 + outer loop + vertex 1.6271 1.86126 2.51777 + vertex 1.62664 1.85667 2.51871 + vertex 1.63106 1.85639 2.51742 + endloop + endfacet + facet normal 0.287429 0.164164 0.943628 + outer loop + vertex 1.62826 1.85336 2.5188 + vertex 1.63106 1.85639 2.51742 + vertex 1.62664 1.85667 2.51871 + endloop + endfacet + facet normal 0.286635 0.163784 0.943936 + outer loop + vertex 1.62826 1.85336 2.5188 + vertex 1.62664 1.85667 2.51871 + vertex 1.62438 1.85329 2.51999 + endloop + endfacet + facet normal 0.286456 0.163916 0.943967 + outer loop + vertex 1.62438 1.85329 2.51999 + vertex 1.62664 1.85667 2.51871 + vertex 1.6226 1.85892 2.51955 + endloop + endfacet + facet normal 0.287313 0.164278 0.943644 + outer loop + vertex 1.63105 1.85171 2.51823 + vertex 1.63106 1.85639 2.51742 + vertex 1.62826 1.85336 2.5188 + endloop + endfacet + facet normal 0.286589 0.162898 0.944103 + outer loop + vertex 1.62826 1.84868 2.5196 + vertex 1.63105 1.85171 2.51823 + vertex 1.62826 1.85336 2.5188 + endloop + endfacet + facet normal 0.286434 0.16305 0.944124 + outer loop + vertex 1.63268 1.8484 2.51831 + vertex 1.63105 1.85171 2.51823 + vertex 1.62826 1.84868 2.5196 + endloop + endfacet + facet normal 0.286416 0.161433 0.944407 + outer loop + vertex 1.62826 1.84868 2.5196 + vertex 1.63224 1.84381 2.51923 + vertex 1.63268 1.8484 2.51831 + endloop + endfacet + facet normal 0.286574 0.161409 0.944363 + outer loop + vertex 1.63224 1.84381 2.51923 + vertex 1.63673 1.84617 2.51746 + vertex 1.63268 1.8484 2.51831 + endloop + endfacet + facet normal 0.287147 0.162592 0.943987 + outer loop + vertex 1.63673 1.84617 2.51746 + vertex 1.63494 1.8518 2.51704 + vertex 1.63268 1.8484 2.51831 + endloop + endfacet + facet normal 0.286784 0.161015 0.944367 + outer loop + vertex 1.63626 1.84163 2.51838 + vertex 1.63673 1.84617 2.51746 + vertex 1.63224 1.84381 2.51923 + endloop + endfacet + facet normal 0.285345 0.157996 0.945312 + outer loop + vertex 1.63393 1.83815 2.51966 + vertex 1.63626 1.84163 2.51838 + vertex 1.63224 1.84381 2.51923 + endloop + endfacet + facet normal 0.285361 0.158001 0.945307 + outer loop + vertex 1.63393 1.83815 2.51966 + vertex 1.63224 1.84381 2.51923 + vertex 1.62944 1.83985 2.52074 + endloop + endfacet + facet normal 0.284294 0.154614 0.946188 + outer loop + vertex 1.63071 1.83584 2.52101 + vertex 1.63393 1.83815 2.51966 + vertex 1.62944 1.83985 2.52074 + endloop + endfacet + facet normal 0.280841 0.153608 0.947382 + outer loop + vertex 1.62944 1.83985 2.52074 + vertex 1.62665 1.83585 2.52221 + vertex 1.63071 1.83584 2.52101 + endloop + endfacet + facet normal 0.28104 0.148669 0.948111 + outer loop + vertex 1.63071 1.83584 2.52101 + vertex 1.62665 1.83585 2.52221 + vertex 1.63001 1.83147 2.5219 + endloop + endfacet + facet normal 0.282488 0.148359 0.947729 + outer loop + vertex 1.63071 1.83584 2.52101 + vertex 1.63001 1.83147 2.5219 + vertex 1.63332 1.83384 2.52054 + endloop + endfacet + facet normal 0.283569 0.146802 0.947648 + outer loop + vertex 1.63449 1.82988 2.52081 + vertex 1.63332 1.83384 2.52054 + vertex 1.63001 1.83147 2.5219 + endloop + endfacet + facet normal 0.283103 0.14522 0.948032 + outer loop + vertex 1.63001 1.83147 2.5219 + vertex 1.63164 1.8259 2.52227 + vertex 1.63449 1.82988 2.52081 + endloop + endfacet + facet normal 0.286147 0.147504 0.946764 + outer loop + vertex 1.63332 1.83384 2.52054 + vertex 1.63449 1.82988 2.52081 + vertex 1.6374 1.83379 2.51932 + endloop + endfacet + facet normal 0.28598 0.152702 0.94599 + outer loop + vertex 1.63332 1.83384 2.52054 + vertex 1.6374 1.83379 2.51932 + vertex 1.63393 1.83815 2.51966 + endloop + endfacet + facet normal 0.286653 0.15326 0.945696 + outer loop + vertex 1.63393 1.83815 2.51966 + vertex 1.6374 1.83379 2.51932 + vertex 1.63796 1.83832 2.51842 + endloop + endfacet + facet normal 0.286563 0.153276 0.945721 + outer loop + vertex 1.6374 1.83379 2.51932 + vertex 1.64186 1.83626 2.51757 + vertex 1.63796 1.83832 2.51842 + endloop + endfacet + facet normal 0.28537 0.148132 0.946901 + outer loop + vertex 1.63891 1.82824 2.51973 + vertex 1.6374 1.83379 2.51932 + vertex 1.63449 1.82988 2.52081 + endloop + endfacet + facet normal 0.281718 0.149207 0.947825 + outer loop + vertex 1.62665 1.83585 2.52221 + vertex 1.62596 1.83144 2.52311 + vertex 1.63001 1.83147 2.5219 + endloop + endfacet + facet normal 0.281042 0.153455 0.947347 + outer loop + vertex 1.62478 1.84153 2.52184 + vertex 1.62665 1.83585 2.52221 + vertex 1.62944 1.83985 2.52074 + endloop + endfacet + facet normal 0.279987 0.153131 0.947712 + outer loop + vertex 1.62665 1.83585 2.52221 + vertex 1.62478 1.84153 2.52184 + vertex 1.62206 1.83744 2.52331 + endloop + endfacet + facet normal 0.285572 0.152782 0.946101 + outer loop + vertex 1.63332 1.83384 2.52054 + vertex 1.63393 1.83815 2.51966 + vertex 1.63071 1.83584 2.52101 + endloop + endfacet + facet normal 0.285527 0.157873 0.945278 + outer loop + vertex 1.62805 1.84394 2.52047 + vertex 1.62944 1.83985 2.52074 + vertex 1.63224 1.84381 2.51923 + endloop + endfacet + facet normal 0.286317 0.15728 0.945138 + outer loop + vertex 1.63796 1.83832 2.51842 + vertex 1.63626 1.84163 2.51838 + vertex 1.63393 1.83815 2.51966 + endloop + endfacet + facet normal 0.287914 0.158093 0.944517 + outer loop + vertex 1.63796 1.83832 2.51842 + vertex 1.6403 1.84177 2.51712 + vertex 1.63626 1.84163 2.51838 + endloop + endfacet + facet normal 0.286487 0.163075 0.944104 + outer loop + vertex 1.63268 1.8484 2.51831 + vertex 1.63494 1.8518 2.51704 + vertex 1.63105 1.85171 2.51823 + endloop + endfacet + facet normal 0.286399 0.164328 0.943913 + outer loop + vertex 1.63106 1.85639 2.51742 + vertex 1.63105 1.85171 2.51823 + vertex 1.63494 1.8518 2.51704 + endloop + endfacet + facet normal 0.285529 0.16356 0.94431 + outer loop + vertex 1.63531 1.85602 2.51619 + vertex 1.63106 1.85639 2.51742 + vertex 1.63494 1.8518 2.51704 + endloop + endfacet + facet normal 0.285453 0.163571 0.944331 + outer loop + vertex 1.63531 1.85602 2.51619 + vertex 1.63494 1.8518 2.51704 + vertex 1.63811 1.85408 2.51568 + endloop + endfacet + facet normal 0.285497 0.163642 0.944305 + outer loop + vertex 1.63811 1.85408 2.51568 + vertex 1.6384 1.85877 2.51479 + vertex 1.63531 1.85602 2.51619 + endloop + endfacet + facet normal 0.284411 0.164918 0.944411 + outer loop + vertex 1.6341 1.85915 2.51601 + vertex 1.63531 1.85602 2.51619 + vertex 1.6384 1.85877 2.51479 + endloop + endfacet + facet normal 0.28629 0.162377 0.944284 + outer loop + vertex 1.63954 1.85001 2.51595 + vertex 1.63811 1.85408 2.51568 + vertex 1.63494 1.8518 2.51704 + endloop + endfacet + facet normal 0.285588 0.165349 0.943981 + outer loop + vertex 1.63531 1.85602 2.51619 + vertex 1.6341 1.85915 2.51601 + vertex 1.63106 1.85639 2.51742 + endloop + endfacet + facet normal 0.285298 0.165683 0.94401 + outer loop + vertex 1.63131 1.8611 2.51651 + vertex 1.63106 1.85639 2.51742 + vertex 1.6341 1.85915 2.51601 + endloop + endfacet + facet normal 0.287265 0.165574 0.943432 + outer loop + vertex 1.62664 1.85667 2.51871 + vertex 1.6271 1.86126 2.51777 + vertex 1.6226 1.85892 2.51955 + endloop + endfacet + facet normal 0.284519 0.163357 0.94465 + outer loop + vertex 1.62438 1.85329 2.51999 + vertex 1.6226 1.85892 2.51955 + vertex 1.61979 1.85508 2.52106 + endloop + endfacet + facet normal 0.284003 0.161773 0.945078 + outer loop + vertex 1.62121 1.85101 2.52133 + vertex 1.62438 1.85329 2.51999 + vertex 1.61979 1.85508 2.52106 + endloop + endfacet + facet normal 0.286693 0.162892 0.944073 + outer loop + vertex 1.62438 1.85329 2.51999 + vertex 1.62826 1.84868 2.5196 + vertex 1.62826 1.85336 2.5188 + endloop + endfacet + facet normal 0.28548 0.160636 0.944827 + outer loop + vertex 1.62805 1.84394 2.52047 + vertex 1.63224 1.84381 2.51923 + vertex 1.62826 1.84868 2.5196 + endloop + endfacet + facet normal 0.28204 0.156763 0.946509 + outer loop + vertex 1.62944 1.83985 2.52074 + vertex 1.62805 1.84394 2.52047 + vertex 1.62478 1.84153 2.52184 + endloop + endfacet + facet normal 0.281132 0.158572 0.946478 + outer loop + vertex 1.62525 1.8459 2.52098 + vertex 1.62402 1.84906 2.52082 + vertex 1.62095 1.84628 2.5222 + endloop + endfacet + facet normal 0.279749 0.153304 0.947754 + outer loop + vertex 1.62206 1.83744 2.52331 + vertex 1.62478 1.84153 2.52184 + vertex 1.62069 1.84151 2.52306 + endloop + endfacet + facet normal 0.279433 0.151199 0.948186 + outer loop + vertex 1.62332 1.83342 2.52358 + vertex 1.62665 1.83585 2.52221 + vertex 1.62206 1.83744 2.52331 + endloop + endfacet + facet normal 0.28069 0.149424 0.948096 + outer loop + vertex 1.62596 1.83144 2.52311 + vertex 1.62665 1.83585 2.52221 + vertex 1.62332 1.83342 2.52358 + endloop + endfacet + facet normal 0.281875 0.145939 0.948287 + outer loop + vertex 1.62713 1.82747 2.52337 + vertex 1.63001 1.83147 2.5219 + vertex 1.62596 1.83144 2.52311 + endloop + endfacet + facet normal 0.282873 0.145157 0.94811 + outer loop + vertex 1.63164 1.8259 2.52227 + vertex 1.63001 1.83147 2.5219 + vertex 1.62713 1.82747 2.52337 + endloop + endfacet + facet normal 0.283422 0.14497 0.947975 + outer loop + vertex 1.63449 1.82988 2.52081 + vertex 1.63164 1.8259 2.52227 + vertex 1.63566 1.82591 2.52107 + endloop + endfacet + facet normal 0.284477 0.145255 0.947615 + outer loop + vertex 1.63566 1.82591 2.52107 + vertex 1.63891 1.82824 2.51973 + vertex 1.63449 1.82988 2.52081 + endloop + endfacet + facet normal 0.285031 0.145039 0.947481 + outer loop + vertex 1.63827 1.82391 2.52059 + vertex 1.63948 1.81993 2.52084 + vertex 1.64237 1.82386 2.51936 + endloop + endfacet + facet normal 0.284819 0.147996 0.947088 + outer loop + vertex 1.63891 1.82824 2.51973 + vertex 1.64128 1.83174 2.51847 + vertex 1.6374 1.83379 2.51932 + endloop + endfacet + facet normal 0.287806 0.148334 0.946132 + outer loop + vertex 1.64684 1.82634 2.51763 + vertex 1.64532 1.8319 2.51722 + vertex 1.64294 1.82843 2.51849 + endloop + endfacet + facet normal 0.286947 0.15258 0.945717 + outer loop + vertex 1.64128 1.83174 2.51847 + vertex 1.64186 1.83626 2.51757 + vertex 1.6374 1.83379 2.51932 + endloop + endfacet + facet normal 0.288564 0.157609 0.944399 + outer loop + vertex 1.64186 1.83626 2.51757 + vertex 1.6403 1.84177 2.51712 + vertex 1.63796 1.83832 2.51842 + endloop + endfacet + facet normal 0.288059 0.159909 0.944167 + outer loop + vertex 1.64354 1.84402 2.51576 + vertex 1.64476 1.84011 2.51604 + vertex 1.64752 1.84402 2.51454 + endloop + endfacet + facet normal 0.287689 0.160872 0.944116 + outer loop + vertex 1.63673 1.84617 2.51746 + vertex 1.63626 1.84163 2.51838 + vertex 1.6403 1.84177 2.51712 + endloop + endfacet + facet normal 0.286277 0.162339 0.944294 + outer loop + vertex 1.63494 1.8518 2.51704 + vertex 1.63673 1.84617 2.51746 + vertex 1.63954 1.85001 2.51595 + endloop + endfacet + facet normal 0.287918 0.161001 0.944024 + outer loop + vertex 1.64354 1.84402 2.51576 + vertex 1.64407 1.84826 2.51487 + vertex 1.64087 1.84602 2.51623 + endloop + endfacet + facet normal 0.286153 0.162332 0.944333 + outer loop + vertex 1.63811 1.85408 2.51568 + vertex 1.63954 1.85001 2.51595 + vertex 1.64234 1.8539 2.51443 + endloop + endfacet + facet normal 0.288274 0.160982 0.943919 + outer loop + vertex 1.64795 1.84832 2.51367 + vertex 1.64646 1.85158 2.51357 + vertex 1.64407 1.84826 2.51487 + endloop + endfacet + facet normal 0.286143 0.163567 0.944123 + outer loop + vertex 1.63811 1.85408 2.51568 + vertex 1.64234 1.8539 2.51443 + vertex 1.6384 1.85877 2.51479 + endloop + endfacet + facet normal 0.282693 0.165386 0.944845 + outer loop + vertex 1.6384 1.85877 2.51479 + vertex 1.64138 1.86168 2.51338 + vertex 1.63866 1.86347 2.51388 + endloop + endfacet + facet normal 0.287629 0.162337 0.943884 + outer loop + vertex 1.64696 1.85616 2.51264 + vertex 1.64528 1.86178 2.51218 + vertex 1.64285 1.85846 2.5135 + endloop + endfacet + facet normal 0.283688 0.167071 0.94425 + outer loop + vertex 1.64138 1.86168 2.51338 + vertex 1.64181 1.86599 2.51249 + vertex 1.63866 1.86347 2.51388 + endloop + endfacet + facet normal 0.283928 0.169309 0.943779 + outer loop + vertex 1.63981 1.87161 2.51209 + vertex 1.64181 1.86599 2.51249 + vertex 1.64449 1.86995 2.51097 + endloop + endfacet + facet normal 0.286996 0.167339 0.943202 + outer loop + vertex 1.64848 1.86405 2.51082 + vertex 1.64902 1.86827 2.50991 + vertex 1.64583 1.86601 2.51128 + endloop + endfacet + facet normal 0.286938 0.16735 0.943218 + outer loop + vertex 1.64848 1.86405 2.51082 + vertex 1.6525 1.86403 2.5096 + vertex 1.64902 1.86827 2.50991 + endloop + endfacet + facet normal 0.285585 0.166195 0.943833 + outer loop + vertex 1.64902 1.86827 2.50991 + vertex 1.6525 1.86403 2.5096 + vertex 1.65292 1.86835 2.50871 + endloop + endfacet + facet normal 0.285293 0.170461 0.94316 + outer loop + vertex 1.65292 1.86835 2.50871 + vertex 1.65143 1.87159 2.50858 + vertex 1.64902 1.86827 2.50991 + endloop + endfacet + facet normal 0.284153 0.169951 0.943596 + outer loop + vertex 1.65292 1.86835 2.50871 + vertex 1.65588 1.87126 2.5073 + vertex 1.65143 1.87159 2.50858 + endloop + endfacet + facet normal 0.285524 0.172077 0.942797 + outer loop + vertex 1.64306 1.87401 2.51067 + vertex 1.64449 1.86995 2.51097 + vertex 1.6473 1.87387 2.50941 + endloop + endfacet + facet normal 0.284648 0.171792 0.943113 + outer loop + vertex 1.64449 1.86995 2.51097 + vertex 1.64306 1.87401 2.51067 + vertex 1.63981 1.87161 2.51209 + endloop + endfacet + facet normal 0.284608 0.170494 0.943361 + outer loop + vertex 1.63598 1.87632 2.51239 + vertex 1.63574 1.87159 2.51332 + vertex 1.63981 1.87161 2.51209 + endloop + endfacet + facet normal 0.286682 0.174365 0.942025 + outer loop + vertex 1.63907 1.87909 2.51094 + vertex 1.64026 1.87595 2.51116 + vertex 1.64335 1.8787 2.50971 + endloop + endfacet + facet normal 0.286359 0.173415 0.942298 + outer loop + vertex 1.63207 1.88116 2.51269 + vertex 1.63156 1.87664 2.51367 + vertex 1.63598 1.87632 2.51239 + endloop + endfacet + facet normal 0.286273 0.176545 0.941743 + outer loop + vertex 1.63207 1.88116 2.51269 + vertex 1.63031 1.88675 2.51217 + vertex 1.62801 1.88332 2.51351 + endloop + endfacet + facet normal 0.284736 0.17767 0.941997 + outer loop + vertex 1.62801 1.88332 2.51351 + vertex 1.63031 1.88675 2.51217 + vertex 1.62623 1.88661 2.51343 + endloop + endfacet + facet normal 0.287321 0.179639 0.940838 + outer loop + vertex 1.64357 1.88337 2.50876 + vertex 1.64209 1.88738 2.50845 + vertex 1.63952 1.88338 2.51 + endloop + endfacet + facet normal 0.287428 0.177564 0.941199 + outer loop + vertex 1.63952 1.88338 2.51 + vertex 1.64335 1.8787 2.50971 + vertex 1.64357 1.88337 2.50876 + endloop + endfacet + facet normal 0.288253 0.180271 0.940432 + outer loop + vertex 1.6375 1.88894 2.50955 + vertex 1.64062 1.8914 2.50813 + vertex 1.6379 1.8932 2.50862 + endloop + endfacet + facet normal 0.289623 0.18006 0.940051 + outer loop + vertex 1.63401 1.89316 2.50982 + vertex 1.6375 1.88894 2.50955 + vertex 1.6379 1.8932 2.50862 + endloop + endfacet + facet normal 0.289738 0.178243 0.940362 + outer loop + vertex 1.6379 1.8932 2.50862 + vertex 1.63641 1.89643 2.50846 + vertex 1.63401 1.89316 2.50982 + endloop + endfacet + facet normal 0.290584 0.177569 0.940229 + outer loop + vertex 1.63401 1.89316 2.50982 + vertex 1.63641 1.89643 2.50846 + vertex 1.63229 1.89875 2.5093 + endloop + endfacet + facet normal 0.289436 0.175245 0.941019 + outer loop + vertex 1.63641 1.89643 2.50846 + vertex 1.63685 1.90099 2.50748 + vertex 1.63229 1.89875 2.5093 + endloop + endfacet + facet normal 0.287982 0.175473 0.941422 + outer loop + vertex 1.63685 1.90099 2.50748 + vertex 1.63641 1.89643 2.50846 + vertex 1.64084 1.89608 2.50717 + endloop + endfacet + facet normal 0.288513 0.175919 0.941176 + outer loop + vertex 1.64109 1.90076 2.50622 + vertex 1.63685 1.90099 2.50748 + vertex 1.64084 1.89608 2.50717 + endloop + endfacet + facet normal 0.28624 0.176171 0.941823 + outer loop + vertex 1.64109 1.90076 2.50622 + vertex 1.64084 1.89608 2.50717 + vertex 1.6439 1.8988 2.50573 + endloop + endfacet + facet normal 0.284274 0.17306 0.942994 + outer loop + vertex 1.6439 1.8988 2.50573 + vertex 1.64424 1.90304 2.50485 + vertex 1.64109 1.90076 2.50622 + endloop + endfacet + facet normal 0.285253 0.171676 0.942952 + outer loop + vertex 1.64109 1.90076 2.50622 + vertex 1.64424 1.90304 2.50485 + vertex 1.63958 1.90489 2.50592 + endloop + endfacet + facet normal 0.282502 0.173305 0.943482 + outer loop + vertex 1.6439 1.8988 2.50573 + vertex 1.64815 1.89846 2.50452 + vertex 1.64424 1.90304 2.50485 + endloop + endfacet + facet normal 0.282249 0.173081 0.943599 + outer loop + vertex 1.64424 1.90304 2.50485 + vertex 1.64815 1.89846 2.50452 + vertex 1.64818 1.90312 2.50366 + endloop + endfacet + facet normal 0.282298 0.172387 0.943711 + outer loop + vertex 1.64818 1.90312 2.50366 + vertex 1.64651 1.90644 2.50355 + vertex 1.64424 1.90304 2.50485 + endloop + endfacet + facet normal 0.283448 0.171547 0.943519 + outer loop + vertex 1.64424 1.90304 2.50485 + vertex 1.64651 1.90644 2.50355 + vertex 1.64231 1.90879 2.50438 + endloop + endfacet + facet normal 0.284464 0.173603 0.942837 + outer loop + vertex 1.64651 1.90644 2.50355 + vertex 1.64688 1.91106 2.50259 + vertex 1.64231 1.90879 2.50438 + endloop + endfacet + facet normal 0.284035 0.174448 0.942811 + outer loop + vertex 1.64231 1.90879 2.50438 + vertex 1.64688 1.91106 2.50259 + vertex 1.64269 1.91339 2.50342 + endloop + endfacet + facet normal 0.286378 0.179242 0.941201 + outer loop + vertex 1.64688 1.91106 2.50259 + vertex 1.64495 1.91674 2.5021 + vertex 1.64269 1.91339 2.50342 + endloop + endfacet + facet normal 0.282369 0.172422 0.943684 + outer loop + vertex 1.64818 1.90312 2.50366 + vertex 1.65098 1.90617 2.50226 + vertex 1.64651 1.90644 2.50355 + endloop + endfacet + facet normal 0.288029 0.177485 0.94103 + outer loop + vertex 1.6379 1.8932 2.50862 + vertex 1.64084 1.89608 2.50717 + vertex 1.63641 1.89643 2.50846 + endloop + endfacet + facet normal 0.2865 0.179806 0.941057 + outer loop + vertex 1.64667 1.88585 2.50735 + vertex 1.64467 1.8914 2.50689 + vertex 1.64209 1.88738 2.50845 + endloop + endfacet + facet normal 0.287152 0.178427 0.94112 + outer loop + vertex 1.64062 1.8914 2.50813 + vertex 1.64084 1.89608 2.50717 + vertex 1.6379 1.8932 2.50862 + endloop + endfacet + facet normal 0.285791 0.176697 0.941861 + outer loop + vertex 1.64512 1.89568 2.50595 + vertex 1.6439 1.8988 2.50573 + vertex 1.64084 1.89608 2.50717 + endloop + endfacet + facet normal 0.282555 0.175512 0.943058 + outer loop + vertex 1.6439 1.8988 2.50573 + vertex 1.64512 1.89568 2.50595 + vertex 1.64815 1.89846 2.50452 + endloop + endfacet + facet normal 0.282586 0.177659 0.942647 + outer loop + vertex 1.64791 1.89377 2.50547 + vertex 1.64932 1.88976 2.5058 + vertex 1.65211 1.8937 2.50422 + endloop + endfacet + facet normal 0.281862 0.173104 0.94371 + outer loop + vertex 1.64815 1.89846 2.50452 + vertex 1.65098 1.90151 2.50312 + vertex 1.64818 1.90312 2.50366 + endloop + endfacet + facet normal 0.28183 0.173913 0.943571 + outer loop + vertex 1.65663 1.89608 2.50243 + vertex 1.65488 1.90164 2.50193 + vertex 1.65259 1.89825 2.50324 + endloop + endfacet + facet normal 0.281797 0.172977 0.943753 + outer loop + vertex 1.65098 1.90151 2.50312 + vertex 1.65098 1.90617 2.50226 + vertex 1.64818 1.90312 2.50366 + endloop + endfacet + facet normal 0.290171 0.177773 0.940318 + outer loop + vertex 1.65397 1.90892 2.50085 + vertex 1.65523 1.90584 2.50104 + vertex 1.65819 1.90855 2.49962 + endloop + endfacet + facet normal 0.290235 0.180018 0.939871 + outer loop + vertex 1.65397 1.90892 2.50085 + vertex 1.65819 1.90855 2.49962 + vertex 1.65426 1.91311 2.49995 + endloop + endfacet + facet normal 0.293004 0.182499 0.938532 + outer loop + vertex 1.65426 1.91311 2.49995 + vertex 1.65819 1.90855 2.49962 + vertex 1.65814 1.91316 2.49873 + endloop + endfacet + facet normal 0.282378 0.173889 0.943412 + outer loop + vertex 1.64688 1.91106 2.50259 + vertex 1.64651 1.90644 2.50355 + vertex 1.65098 1.90617 2.50226 + endloop + endfacet + facet normal 0.284672 0.178715 0.941819 + outer loop + vertex 1.64495 1.91674 2.5021 + vertex 1.64688 1.91106 2.50259 + vertex 1.64961 1.91494 2.50103 + endloop + endfacet + facet normal 0.285945 0.18269 0.94067 + outer loop + vertex 1.64961 1.91494 2.50103 + vertex 1.64809 1.919 2.5007 + vertex 1.64495 1.91674 2.5021 + endloop + endfacet + facet normal 0.285146 0.183815 0.940693 + outer loop + vertex 1.64527 1.9209 2.50118 + vertex 1.64495 1.91674 2.5021 + vertex 1.64809 1.919 2.5007 + endloop + endfacet + facet normal 0.28632 0.185736 0.939959 + outer loop + vertex 1.64809 1.919 2.5007 + vertex 1.64826 1.92362 2.49974 + vertex 1.64527 1.9209 2.50118 + endloop + endfacet + facet normal 0.287025 0.183554 0.940173 + outer loop + vertex 1.64527 1.9209 2.50118 + vertex 1.64104 1.92125 2.50241 + vertex 1.64495 1.91674 2.5021 + endloop + endfacet + facet normal 0.288416 0.180257 0.940385 + outer loop + vertex 1.65397 1.90892 2.50085 + vertex 1.65426 1.91311 2.49995 + vertex 1.65114 1.91086 2.50134 + endloop + endfacet + facet normal 0.287507 0.183228 0.940089 + outer loop + vertex 1.64809 1.919 2.5007 + vertex 1.64961 1.91494 2.50103 + vertex 1.65232 1.91879 2.49945 + endloop + endfacet + facet normal 0.293035 0.182028 0.938614 + outer loop + vertex 1.65814 1.91316 2.49873 + vertex 1.65648 1.91645 2.49861 + vertex 1.65426 1.91311 2.49995 + endloop + endfacet + facet normal 0.29408 0.182538 0.938188 + outer loop + vertex 1.65814 1.91316 2.49873 + vertex 1.66089 1.91613 2.49729 + vertex 1.65648 1.91645 2.49861 + endloop + endfacet + facet normal 0.294074 0.182038 0.938287 + outer loop + vertex 1.65685 1.92103 2.49761 + vertex 1.65648 1.91645 2.49861 + vertex 1.66089 1.91613 2.49729 + endloop + endfacet + facet normal 0.287485 0.185623 0.939626 + outer loop + vertex 1.64809 1.919 2.5007 + vertex 1.65232 1.91879 2.49945 + vertex 1.64826 1.92362 2.49974 + endloop + endfacet + facet normal 0.289777 0.181334 0.939759 + outer loop + vertex 1.65685 1.92103 2.49761 + vertex 1.65494 1.92673 2.4971 + vertex 1.65269 1.92336 2.49844 + endloop + endfacet + facet normal 0.282685 0.186391 0.940929 + outer loop + vertex 1.65104 1.92663 2.4983 + vertex 1.65103 1.93124 2.49739 + vertex 1.64826 1.92822 2.49883 + endloop + endfacet + facet normal 0.282535 0.185932 0.941065 + outer loop + vertex 1.65526 1.93092 2.49619 + vertex 1.65401 1.93397 2.49596 + vertex 1.65103 1.93124 2.49739 + endloop + endfacet + facet normal 0.279107 0.194676 0.940319 + outer loop + vertex 1.64962 1.93989 2.49605 + vertex 1.64692 1.93605 2.49765 + vertex 1.65118 1.93587 2.49643 + endloop + endfacet + facet normal 0.281158 0.187871 0.941092 + outer loop + vertex 1.64826 1.92822 2.49883 + vertex 1.65103 1.93124 2.49739 + vertex 1.64658 1.93149 2.49867 + endloop + endfacet + facet normal 0.282634 0.18629 0.940964 + outer loop + vertex 1.64826 1.92362 2.49974 + vertex 1.65104 1.92663 2.4983 + vertex 1.64826 1.92822 2.49883 + endloop + endfacet + facet normal 0.285091 0.187136 0.940055 + outer loop + vertex 1.64402 1.92394 2.50096 + vertex 1.64527 1.9209 2.50118 + vertex 1.64826 1.92362 2.49974 + endloop + endfacet + facet normal 0.287123 0.187915 0.939281 + outer loop + vertex 1.64527 1.9209 2.50118 + vertex 1.64402 1.92394 2.50096 + vertex 1.64104 1.92125 2.50241 + endloop + endfacet + facet normal 0.290832 0.189228 0.937875 + outer loop + vertex 1.63966 1.92995 2.50109 + vertex 1.63696 1.9261 2.5027 + vertex 1.6412 1.92587 2.50144 + endloop + endfacet + facet normal 0.286814 0.183364 0.940274 + outer loop + vertex 1.64104 1.92125 2.50241 + vertex 1.64104 1.91666 2.5033 + vertex 1.64495 1.91674 2.5021 + endloop + endfacet + facet normal 0.287158 0.178665 0.941073 + outer loop + vertex 1.64269 1.91339 2.50342 + vertex 1.64495 1.91674 2.5021 + vertex 1.64104 1.91666 2.5033 + endloop + endfacet + facet normal 0.285411 0.17215 0.942818 + outer loop + vertex 1.64424 1.90304 2.50485 + vertex 1.64231 1.90879 2.50438 + vertex 1.63958 1.90489 2.50592 + endloop + endfacet + facet normal 0.288512 0.172778 0.941758 + outer loop + vertex 1.63958 1.90489 2.50592 + vertex 1.63685 1.90099 2.50748 + vertex 1.64109 1.90076 2.50622 + endloop + endfacet + facet normal 0.289889 0.172937 0.941306 + outer loop + vertex 1.63404 1.91403 2.50595 + vertex 1.63527 1.91096 2.50614 + vertex 1.63826 1.91367 2.50472 + endloop + endfacet + facet normal 0.285998 0.179445 0.941278 + outer loop + vertex 1.62973 1.92004 2.50613 + vertex 1.62701 1.91615 2.5077 + vertex 1.63125 1.91596 2.50645 + endloop + endfacet + facet normal 0.289785 0.174555 0.941039 + outer loop + vertex 1.63229 1.89875 2.5093 + vertex 1.63685 1.90099 2.50748 + vertex 1.6327 1.90333 2.50832 + endloop + endfacet + facet normal 0.288341 0.176952 0.941035 + outer loop + vertex 1.63401 1.89316 2.50982 + vertex 1.63229 1.89875 2.5093 + vertex 1.6295 1.8949 2.51087 + endloop + endfacet + facet normal 0.285946 0.177965 0.941575 + outer loop + vertex 1.6295 1.8949 2.51087 + vertex 1.62668 1.89111 2.51245 + vertex 1.63082 1.89097 2.51122 + endloop + endfacet + facet normal 0.284725 0.177799 0.941976 + outer loop + vertex 1.62668 1.89111 2.51245 + vertex 1.62623 1.88661 2.51343 + vertex 1.63031 1.88675 2.51217 + endloop + endfacet + facet normal 0.282195 0.17632 0.943015 + outer loop + vertex 1.62801 1.88332 2.51351 + vertex 1.62623 1.88661 2.51343 + vertex 1.62394 1.88315 2.51477 + endloop + endfacet + facet normal 0.283343 0.175586 0.942808 + outer loop + vertex 1.62343 1.87891 2.51571 + vertex 1.62755 1.87882 2.51449 + vertex 1.62394 1.88315 2.51477 + endloop + endfacet + facet normal 0.281413 0.172207 0.944008 + outer loop + vertex 1.62468 1.87504 2.51604 + vertex 1.62343 1.87891 2.51571 + vertex 1.62022 1.87666 2.51708 + endloop + endfacet + facet normal 0.279361 0.177345 0.943666 + outer loop + vertex 1.6194 1.88476 2.51581 + vertex 1.61675 1.88078 2.51734 + vertex 1.62075 1.88084 2.51614 + endloop + endfacet + facet normal 0.283001 0.174503 0.943111 + outer loop + vertex 1.61636 1.8765 2.51825 + vertex 1.61675 1.88078 2.51734 + vertex 1.61364 1.87827 2.51874 + endloop + endfacet + facet normal 0.281517 0.172396 0.943943 + outer loop + vertex 1.6218 1.87125 2.51759 + vertex 1.62022 1.87666 2.51708 + vertex 1.61781 1.87335 2.5184 + endloop + endfacet + facet normal 0.285699 0.170261 0.943073 + outer loop + vertex 1.6218 1.87125 2.51759 + vertex 1.6213 1.86677 2.51855 + vertex 1.62537 1.86691 2.51729 + endloop + endfacet + facet normal 0.283667 0.167648 0.944154 + outer loop + vertex 1.62305 1.86346 2.51861 + vertex 1.6213 1.86677 2.51855 + vertex 1.61899 1.86329 2.51986 + endloop + endfacet + facet normal 0.279397 0.167506 0.945452 + outer loop + vertex 1.61847 1.85904 2.52077 + vertex 1.61899 1.86329 2.51986 + vertex 1.61579 1.86098 2.52122 + endloop + endfacet + facet normal 0.275828 0.164545 0.947018 + outer loop + vertex 1.61579 1.86098 2.52122 + vertex 1.61177 1.86091 2.5224 + vertex 1.61527 1.85675 2.52211 + endloop + endfacet + facet normal 0.275918 0.164623 0.946979 + outer loop + vertex 1.61177 1.86091 2.5224 + vertex 1.61136 1.85661 2.52327 + vertex 1.61527 1.85675 2.52211 + endloop + endfacet + facet normal 0.276137 0.161931 0.947379 + outer loop + vertex 1.61285 1.85341 2.52338 + vertex 1.61527 1.85675 2.52211 + vertex 1.61136 1.85661 2.52327 + endloop + endfacet + facet normal 0.277839 0.160597 0.947108 + outer loop + vertex 1.61698 1.85116 2.52255 + vertex 1.61527 1.85675 2.52211 + vertex 1.61285 1.85341 2.52338 + endloop + endfacet + facet normal 0.278663 0.157464 0.947392 + outer loop + vertex 1.61698 1.85116 2.52255 + vertex 1.61648 1.84657 2.52346 + vertex 1.62095 1.84628 2.5222 + endloop + endfacet + facet normal 0.276388 0.15511 0.948446 + outer loop + vertex 1.61796 1.84331 2.52356 + vertex 1.61648 1.84657 2.52346 + vertex 1.61401 1.84318 2.52474 + endloop + endfacet + facet normal 0.277139 0.153987 0.94841 + outer loop + vertex 1.61339 1.83887 2.52562 + vertex 1.61745 1.83895 2.52442 + vertex 1.61401 1.84318 2.52474 + endloop + endfacet + facet normal 0.284756 0.153217 0.946276 + outer loop + vertex 1.61075 1.84082 2.52607 + vertex 1.60669 1.84085 2.52729 + vertex 1.61006 1.83644 2.52699 + endloop + endfacet + facet normal 0.284971 0.153388 0.946184 + outer loop + vertex 1.60669 1.84085 2.52729 + vertex 1.60601 1.83644 2.52821 + vertex 1.61006 1.83644 2.52699 + endloop + endfacet + facet normal 0.284942 0.154027 0.946089 + outer loop + vertex 1.60726 1.83245 2.52849 + vertex 1.61006 1.83644 2.52699 + vertex 1.60601 1.83644 2.52821 + endloop + endfacet + facet normal 0.296371 0.157316 0.942028 + outer loop + vertex 1.60726 1.83245 2.52849 + vertex 1.60601 1.83644 2.52821 + vertex 1.60274 1.83417 2.52962 + endloop + endfacet + facet normal 0.296671 0.150906 0.942981 + outer loop + vertex 1.60601 1.83644 2.52821 + vertex 1.60669 1.84085 2.52729 + vertex 1.60341 1.83852 2.5287 + endloop + endfacet + facet normal 0.27719 0.153178 0.948526 + outer loop + vertex 1.61339 1.83887 2.52562 + vertex 1.61462 1.83493 2.52589 + vertex 1.61745 1.83895 2.52442 + endloop + endfacet + facet normal 0.283508 0.155127 0.94634 + outer loop + vertex 1.61181 1.83092 2.52737 + vertex 1.61006 1.83644 2.52699 + vertex 1.60726 1.83245 2.52849 + endloop + endfacet + facet normal 0.282994 0.153254 0.946799 + outer loop + vertex 1.60862 1.82841 2.52873 + vertex 1.61181 1.83092 2.52737 + vertex 1.60726 1.83245 2.52849 + endloop + endfacet + facet normal 0.288003 0.15484 0.945029 + outer loop + vertex 1.60862 1.82841 2.52873 + vertex 1.60726 1.83245 2.52849 + vertex 1.60458 1.82845 2.52996 + endloop + endfacet + facet normal 0.288079 0.152671 0.945358 + outer loop + vertex 1.60458 1.82845 2.52996 + vertex 1.60834 1.8237 2.52958 + vertex 1.60862 1.82841 2.52873 + endloop + endfacet + facet normal 0.281894 0.153362 0.947109 + outer loop + vertex 1.60834 1.8237 2.52958 + vertex 1.61133 1.82662 2.52822 + vertex 1.60862 1.82841 2.52873 + endloop + endfacet + facet normal 0.282487 0.15272 0.947036 + outer loop + vertex 1.61274 1.82342 2.52831 + vertex 1.61133 1.82662 2.52822 + vertex 1.60834 1.8237 2.52958 + endloop + endfacet + facet normal 0.282448 0.150279 0.947438 + outer loop + vertex 1.60834 1.8237 2.52958 + vertex 1.61205 1.81891 2.52923 + vertex 1.61274 1.82342 2.52831 + endloop + endfacet + facet normal 0.284162 0.149924 0.946982 + outer loop + vertex 1.61205 1.81891 2.52923 + vertex 1.61668 1.82121 2.52748 + vertex 1.61274 1.82342 2.52831 + endloop + endfacet + facet normal 0.282206 0.150083 0.947541 + outer loop + vertex 1.60794 1.81897 2.53045 + vertex 1.61205 1.81891 2.52923 + vertex 1.60834 1.8237 2.52958 + endloop + endfacet + facet normal 0.283871 0.149859 0.94708 + outer loop + vertex 1.60794 1.81897 2.53045 + vertex 1.60834 1.8237 2.52958 + vertex 1.60523 1.8209 2.53095 + endloop + endfacet + facet normal 0.282784 0.148177 0.947669 + outer loop + vertex 1.60523 1.8209 2.53095 + vertex 1.60462 1.81661 2.5318 + vertex 1.60794 1.81897 2.53045 + endloop + endfacet + facet normal 0.282885 0.14803 0.947662 + outer loop + vertex 1.6091 1.81493 2.53073 + vertex 1.60794 1.81897 2.53045 + vertex 1.60462 1.81661 2.5318 + endloop + endfacet + facet normal 0.291311 0.146504 0.945343 + outer loop + vertex 1.60523 1.8209 2.53095 + vertex 1.60094 1.82132 2.53221 + vertex 1.60462 1.81661 2.5318 + endloop + endfacet + facet normal 0.289835 0.145295 0.945984 + outer loop + vertex 1.60094 1.82132 2.53221 + vertex 1.60064 1.81656 2.53303 + vertex 1.60462 1.81661 2.5318 + endloop + endfacet + facet normal 0.285008 0.14853 0.946947 + outer loop + vertex 1.60408 1.82408 2.5308 + vertex 1.60523 1.8209 2.53095 + vertex 1.60834 1.8237 2.52958 + endloop + endfacet + facet normal 0.282515 0.152732 0.947026 + outer loop + vertex 1.61274 1.82342 2.52831 + vertex 1.61522 1.82674 2.52704 + vertex 1.61133 1.82662 2.52822 + endloop + endfacet + facet normal 0.282413 0.154099 0.946835 + outer loop + vertex 1.61181 1.83092 2.52737 + vertex 1.61133 1.82662 2.52822 + vertex 1.61522 1.82674 2.52704 + endloop + endfacet + facet normal 0.282341 0.154111 0.946854 + outer loop + vertex 1.61133 1.82662 2.52822 + vertex 1.61181 1.83092 2.52737 + vertex 1.60862 1.82841 2.52873 + endloop + endfacet + facet normal 0.278627 0.152078 0.948282 + outer loop + vertex 1.61921 1.8334 2.52479 + vertex 1.61745 1.83895 2.52442 + vertex 1.61462 1.83493 2.52589 + endloop + endfacet + facet normal 0.281136 0.15031 0.947823 + outer loop + vertex 1.6185 1.82904 2.52569 + vertex 1.62258 1.82904 2.52448 + vertex 1.61921 1.8334 2.52479 + endloop + endfacet + facet normal 0.280118 0.152151 0.947831 + outer loop + vertex 1.61585 1.83099 2.52617 + vertex 1.61181 1.83092 2.52737 + vertex 1.61522 1.82674 2.52704 + endloop + endfacet + facet normal 0.281184 0.149194 0.947986 + outer loop + vertex 1.6185 1.82904 2.52569 + vertex 1.61968 1.82509 2.52596 + vertex 1.62258 1.82904 2.52448 + endloop + endfacet + facet normal 0.284682 0.150977 0.946658 + outer loop + vertex 1.61668 1.82121 2.52748 + vertex 1.61522 1.82674 2.52704 + vertex 1.61274 1.82342 2.52831 + endloop + endfacet + facet normal 0.283686 0.148487 0.947351 + outer loop + vertex 1.62086 1.82111 2.52623 + vertex 1.62424 1.82348 2.52485 + vertex 1.61968 1.82509 2.52596 + endloop + endfacet + facet normal 0.28347 0.146885 0.947665 + outer loop + vertex 1.62424 1.82348 2.52485 + vertex 1.62758 1.81911 2.52453 + vertex 1.62831 1.82349 2.52363 + endloop + endfacet + facet normal 0.285038 0.148266 0.94698 + outer loop + vertex 1.62472 1.81512 2.52601 + vertex 1.62351 1.8191 2.52575 + vertex 1.62015 1.81669 2.52714 + endloop + endfacet + facet normal 0.284319 0.145736 0.947588 + outer loop + vertex 1.62015 1.81669 2.52714 + vertex 1.62187 1.81109 2.52749 + vertex 1.62472 1.81512 2.52601 + endloop + endfacet + facet normal 0.284085 0.147011 0.947462 + outer loop + vertex 1.63212 1.81753 2.52341 + vertex 1.63092 1.82151 2.52316 + vertex 1.62758 1.81911 2.52453 + endloop + endfacet + facet normal 0.28451 0.145948 0.947498 + outer loop + vertex 1.63666 1.81595 2.5223 + vertex 1.63496 1.82153 2.52194 + vertex 1.63212 1.81753 2.52341 + endloop + endfacet + facet normal 0.287196 0.145286 0.946789 + outer loop + vertex 1.63666 1.81595 2.5223 + vertex 1.63599 1.81155 2.52317 + vertex 1.64003 1.81156 2.52195 + endloop + endfacet + facet normal 0.284358 0.0940217 0.954097 + outer loop + vertex 1.64703 1.79103 2.52235 + vertex 1.64599 1.79632 2.52214 + vertex 1.64273 1.79262 2.52347 + endloop + endfacet + facet normal 0.281853 0.086182 0.955579 + outer loop + vertex 1.64348 1.78857 2.52362 + vertex 1.64703 1.79103 2.52235 + vertex 1.64273 1.79262 2.52347 + endloop + endfacet + facet normal 0.288693 0.0873813 0.953426 + outer loop + vertex 1.64348 1.78857 2.52362 + vertex 1.64273 1.79262 2.52347 + vertex 1.63948 1.78847 2.52484 + endloop + endfacet + facet normal 0.288579 0.0897319 0.953242 + outer loop + vertex 1.63948 1.78847 2.52484 + vertex 1.64229 1.78415 2.52439 + vertex 1.64348 1.78857 2.52362 + endloop + endfacet + facet normal 0.281598 0.0865694 0.955619 + outer loop + vertex 1.64585 1.78662 2.52309 + vertex 1.64703 1.79103 2.52235 + vertex 1.64348 1.78857 2.52362 + endloop + endfacet + facet normal 0.288736 0.108025 0.951295 + outer loop + vertex 1.64176 1.79753 2.52328 + vertex 1.64483 1.80161 2.52188 + vertex 1.64086 1.80157 2.52309 + endloop + endfacet + facet normal 0.287968 0.125921 0.949325 + outer loop + vertex 1.64169 1.80597 2.52226 + vertex 1.64086 1.80157 2.52309 + vertex 1.64483 1.80161 2.52188 + endloop + endfacet + facet normal 0.284953 0.137412 0.948641 + outer loop + vertex 1.64003 1.81156 2.52195 + vertex 1.64169 1.80597 2.52226 + vertex 1.64456 1.80994 2.52082 + endloop + endfacet + facet normal 0.285491 0.133363 0.949057 + outer loop + vertex 1.64826 1.80396 2.52056 + vertex 1.64899 1.80829 2.51973 + vertex 1.64571 1.80596 2.52105 + endloop + endfacet + facet normal 0.280778 0.134403 0.950316 + outer loop + vertex 1.64826 1.80396 2.52056 + vertex 1.6523 1.80393 2.51937 + vertex 1.64899 1.80829 2.51973 + endloop + endfacet + facet normal 0.282084 0.135435 0.949782 + outer loop + vertex 1.64899 1.80829 2.51973 + vertex 1.6523 1.80393 2.51937 + vertex 1.65303 1.80848 2.51851 + endloop + endfacet + facet normal 0.280705 0.135728 0.950149 + outer loop + vertex 1.6523 1.80393 2.51937 + vertex 1.65689 1.80636 2.51767 + vertex 1.65303 1.80848 2.51851 + endloop + endfacet + facet normal 0.285891 0.142121 0.947665 + outer loop + vertex 1.64334 1.81394 2.52059 + vertex 1.64456 1.80994 2.52082 + vertex 1.64744 1.81388 2.51936 + endloop + endfacet + facet normal 0.281438 0.143125 0.948845 + outer loop + vertex 1.65303 1.80848 2.51851 + vertex 1.65137 1.81181 2.5185 + vertex 1.64899 1.80829 2.51973 + endloop + endfacet + facet normal 0.282603 0.143705 0.948412 + outer loop + vertex 1.65303 1.80848 2.51851 + vertex 1.65541 1.81197 2.51727 + vertex 1.65137 1.81181 2.5185 + endloop + endfacet + facet normal 0.285811 0.144774 0.947287 + outer loop + vertex 1.64334 1.81394 2.52059 + vertex 1.64744 1.81388 2.51936 + vertex 1.64393 1.81827 2.51975 + endloop + endfacet + facet normal 0.285983 0.144994 0.947201 + outer loop + vertex 1.64393 1.81827 2.51975 + vertex 1.64628 1.82178 2.5185 + vertex 1.64237 1.82386 2.51936 + endloop + endfacet + facet normal 0.284455 0.145894 0.947523 + outer loop + vertex 1.65189 1.81637 2.51764 + vertex 1.65031 1.82194 2.51726 + vertex 1.64796 1.81846 2.5185 + endloop + endfacet + facet normal 0.286292 0.145657 0.947006 + outer loop + vertex 1.64628 1.82178 2.5185 + vertex 1.64684 1.82634 2.51763 + vertex 1.64237 1.82386 2.51936 + endloop + endfacet + facet normal 0.28597 0.147877 0.946759 + outer loop + vertex 1.64532 1.8319 2.51722 + vertex 1.64684 1.82634 2.51763 + vertex 1.64978 1.83021 2.51614 + endloop + endfacet + facet normal 0.28262 0.146042 0.948049 + outer loop + vertex 1.65358 1.82421 2.51593 + vertex 1.65431 1.82857 2.51504 + vertex 1.65095 1.82623 2.5164 + endloop + endfacet + facet normal 0.278111 0.14704 0.949228 + outer loop + vertex 1.65358 1.82421 2.51593 + vertex 1.65764 1.82421 2.51474 + vertex 1.65431 1.82857 2.51504 + endloop + endfacet + facet normal 0.276219 0.145543 0.950011 + outer loop + vertex 1.65431 1.82857 2.51504 + vertex 1.65764 1.82421 2.51474 + vertex 1.65839 1.82859 2.51385 + endloop + endfacet + facet normal 0.285084 0.150872 0.946554 + outer loop + vertex 1.64861 1.83417 2.51586 + vertex 1.64978 1.83021 2.51614 + vertex 1.65267 1.83413 2.51464 + endloop + endfacet + facet normal 0.27594 0.151326 0.949188 + outer loop + vertex 1.65839 1.82859 2.51385 + vertex 1.65722 1.83256 2.51356 + vertex 1.65431 1.82857 2.51504 + endloop + endfacet + facet normal 0.275575 0.151228 0.949309 + outer loop + vertex 1.65839 1.82859 2.51385 + vertex 1.66176 1.83105 2.51248 + vertex 1.65722 1.83256 2.51356 + endloop + endfacet + facet normal 0.278352 0.157069 0.947549 + outer loop + vertex 1.65267 1.83413 2.51464 + vertex 1.65602 1.83652 2.51326 + vertex 1.65337 1.83849 2.51371 + endloop + endfacet + facet normal 0.276375 0.154124 0.948611 + outer loop + vertex 1.66176 1.83105 2.51248 + vertex 1.66009 1.83657 2.51207 + vertex 1.65722 1.83256 2.51356 + endloop + endfacet + facet normal 0.279046 0.158089 0.947175 + outer loop + vertex 1.65602 1.83652 2.51326 + vertex 1.65666 1.8409 2.51234 + vertex 1.65337 1.83849 2.51371 + endloop + endfacet + facet normal 0.275207 0.161354 0.947748 + outer loop + vertex 1.65472 1.84653 2.51195 + vertex 1.65666 1.8409 2.51234 + vertex 1.6594 1.84489 2.51087 + endloop + endfacet + facet normal 0.279103 0.159449 0.946931 + outer loop + vertex 1.66343 1.83896 2.5107 + vertex 1.66395 1.84327 2.50982 + vertex 1.66073 1.84092 2.51116 + endloop + endfacet + facet normal 0.276338 0.165223 0.946752 + outer loop + vertex 1.6594 1.84489 2.51087 + vertex 1.65797 1.84893 2.51058 + vertex 1.65472 1.84653 2.51195 + endloop + endfacet + facet normal 0.282258 0.161918 0.945575 + outer loop + vertex 1.65089 1.85125 2.51228 + vertex 1.65067 1.84651 2.51316 + vertex 1.65472 1.84653 2.51195 + endloop + endfacet + facet normal 0.278254 0.161458 0.94684 + outer loop + vertex 1.65398 1.85403 2.51087 + vertex 1.65517 1.85086 2.51106 + vertex 1.65829 1.85365 2.50967 + endloop + endfacet + facet normal 0.287472 0.16114 0.944136 + outer loop + vertex 1.64696 1.85616 2.51264 + vertex 1.64646 1.85158 2.51357 + vertex 1.65089 1.85125 2.51228 + endloop + endfacet + facet normal 0.286852 0.162128 0.944156 + outer loop + vertex 1.64528 1.86178 2.51218 + vertex 1.64696 1.85616 2.51264 + vertex 1.64979 1.86009 2.51111 + endloop + endfacet + facet normal 0.285117 0.161154 0.944848 + outer loop + vertex 1.65398 1.85403 2.51087 + vertex 1.65447 1.85837 2.50998 + vertex 1.65119 1.856 2.51138 + endloop + endfacet + facet normal 0.287126 0.163094 0.943906 + outer loop + vertex 1.64848 1.86405 2.51082 + vertex 1.64979 1.86009 2.51111 + vertex 1.6525 1.86403 2.5096 + endloop + endfacet + facet normal 0.280819 0.164225 0.945606 + outer loop + vertex 1.65857 1.85836 2.50877 + vertex 1.65712 1.86244 2.50849 + vertex 1.65447 1.85837 2.50998 + endloop + endfacet + facet normal 0.284006 0.166439 0.944266 + outer loop + vertex 1.6525 1.86403 2.5096 + vertex 1.65566 1.86653 2.50821 + vertex 1.65292 1.86835 2.50871 + endloop + endfacet + facet normal 0.27813 0.167004 0.945914 + outer loop + vertex 1.66174 1.86088 2.50741 + vertex 1.65975 1.86652 2.507 + vertex 1.65712 1.86244 2.50849 + endloop + endfacet + facet normal 0.285348 0.168669 0.943466 + outer loop + vertex 1.65566 1.86653 2.50821 + vertex 1.65588 1.87126 2.5073 + vertex 1.65292 1.86835 2.50871 + endloop + endfacet + facet normal 0.279056 0.172519 0.944651 + outer loop + vertex 1.65895 1.874 2.50588 + vertex 1.6602 1.87086 2.50609 + vertex 1.66323 1.87363 2.50469 + endloop + endfacet + facet normal 0.279158 0.175634 0.944046 + outer loop + vertex 1.65895 1.874 2.50588 + vertex 1.66323 1.87363 2.50469 + vertex 1.65927 1.87821 2.505 + endloop + endfacet + facet normal 0.278158 0.174738 0.944508 + outer loop + vertex 1.65927 1.87821 2.505 + vertex 1.66323 1.87363 2.50469 + vertex 1.66319 1.8783 2.50383 + endloop + endfacet + facet normal 0.284241 0.174292 0.942778 + outer loop + vertex 1.65189 1.87612 2.5076 + vertex 1.65143 1.87159 2.50858 + vertex 1.65588 1.87126 2.5073 + endloop + endfacet + facet normal 0.283494 0.17679 0.942537 + outer loop + vertex 1.65015 1.88167 2.50708 + vertex 1.65189 1.87612 2.5076 + vertex 1.65466 1.87997 2.50605 + endloop + endfacet + facet normal 0.280944 0.175395 0.943561 + outer loop + vertex 1.65895 1.874 2.50588 + vertex 1.65927 1.87821 2.505 + vertex 1.65612 1.87594 2.50637 + endloop + endfacet + facet normal 0.281584 0.178128 0.942858 + outer loop + vertex 1.65331 1.8839 2.50571 + vertex 1.65466 1.87997 2.50605 + vertex 1.65744 1.88379 2.50449 + endloop + endfacet + facet normal 0.277927 0.177911 0.943983 + outer loop + vertex 1.66319 1.8783 2.50383 + vertex 1.66152 1.88159 2.50371 + vertex 1.65927 1.87821 2.505 + endloop + endfacet + facet normal 0.278669 0.178277 0.943695 + outer loop + vertex 1.66319 1.8783 2.50383 + vertex 1.66598 1.88133 2.50244 + vertex 1.66152 1.88159 2.50371 + endloop + endfacet + facet normal 0.281572 0.178618 0.942769 + outer loop + vertex 1.65331 1.8839 2.50571 + vertex 1.65744 1.88379 2.50449 + vertex 1.65383 1.88813 2.50475 + endloop + endfacet + facet normal 0.2827 0.176987 0.942739 + outer loop + vertex 1.65383 1.88813 2.50475 + vertex 1.65614 1.89158 2.50341 + vertex 1.65211 1.8937 2.50422 + endloop + endfacet + facet normal 0.277997 0.178197 0.943909 + outer loop + vertex 1.66195 1.88616 2.50272 + vertex 1.66021 1.89174 2.50217 + vertex 1.65789 1.8883 2.50351 + endloop + endfacet + facet normal 0.281918 0.175283 0.943291 + outer loop + vertex 1.65614 1.89158 2.50341 + vertex 1.65663 1.89608 2.50243 + vertex 1.65211 1.8937 2.50422 + endloop + endfacet + facet normal 0.283657 0.17443 0.942928 + outer loop + vertex 1.65488 1.90164 2.50193 + vertex 1.65663 1.89608 2.50243 + vertex 1.65947 1.89988 2.50087 + endloop + endfacet + facet normal 0.278956 0.178107 0.943643 + outer loop + vertex 1.66344 1.89398 2.5008 + vertex 1.66399 1.89815 2.49985 + vertex 1.66077 1.89595 2.50122 + endloop + endfacet + facet normal 0.277766 0.178334 0.943951 + outer loop + vertex 1.66344 1.89398 2.5008 + vertex 1.66746 1.89399 2.49961 + vertex 1.66399 1.89815 2.49985 + endloop + endfacet + facet normal 0.278455 0.178928 0.943635 + outer loop + vertex 1.66399 1.89815 2.49985 + vertex 1.66746 1.89399 2.49961 + vertex 1.6679 1.89824 2.49868 + endloop + endfacet + facet normal 0.286089 0.177266 0.941663 + outer loop + vertex 1.65804 1.90391 2.50055 + vertex 1.65947 1.89988 2.50087 + vertex 1.66225 1.90371 2.49931 + endloop + endfacet + facet normal 0.278202 0.182406 0.943044 + outer loop + vertex 1.6679 1.89824 2.49868 + vertex 1.6664 1.90143 2.49851 + vertex 1.66399 1.89815 2.49985 + endloop + endfacet + facet normal 0.282287 0.184243 0.941471 + outer loop + vertex 1.6679 1.89824 2.49868 + vertex 1.67083 1.90115 2.49723 + vertex 1.6664 1.90143 2.49851 + endloop + endfacet + facet normal 0.286069 0.179593 0.941228 + outer loop + vertex 1.65804 1.90391 2.50055 + vertex 1.66225 1.90371 2.49931 + vertex 1.65819 1.90855 2.49962 + endloop + endfacet + facet normal 0.293527 0.182474 0.938374 + outer loop + vertex 1.65819 1.90855 2.49962 + vertex 1.66092 1.91153 2.49818 + vertex 1.65814 1.91316 2.49873 + endloop + endfacet + facet normal 0.284949 0.187224 0.94008 + outer loop + vertex 1.6668 1.90594 2.49749 + vertex 1.66481 1.91159 2.49697 + vertex 1.6626 1.90825 2.49831 + endloop + endfacet + facet normal 0.293736 0.182877 0.93823 + outer loop + vertex 1.66092 1.91153 2.49818 + vertex 1.66089 1.91613 2.49729 + vertex 1.65814 1.91316 2.49873 + endloop + endfacet + facet normal 0.281696 0.178519 0.94275 + outer loop + vertex 1.66387 1.91883 2.49585 + vertex 1.66511 1.91576 2.49606 + vertex 1.66812 1.9185 2.49465 + endloop + endfacet + facet normal 0.281682 0.177918 0.942868 + outer loop + vertex 1.66387 1.91883 2.49585 + vertex 1.66812 1.9185 2.49465 + vertex 1.66422 1.92305 2.49495 + endloop + endfacet + facet normal 0.281823 0.178043 0.942802 + outer loop + vertex 1.66422 1.92305 2.49495 + vertex 1.66812 1.9185 2.49465 + vertex 1.66816 1.92313 2.49376 + endloop + endfacet + facet normal 0.289626 0.181289 0.939814 + outer loop + vertex 1.65494 1.92673 2.4971 + vertex 1.65685 1.92103 2.49761 + vertex 1.65957 1.9249 2.49603 + endloop + endfacet + facet normal 0.288203 0.17699 0.94107 + outer loop + vertex 1.66387 1.91883 2.49585 + vertex 1.66422 1.92305 2.49495 + vertex 1.66106 1.92079 2.49634 + endloop + endfacet + facet normal 0.289388 0.18009 0.940118 + outer loop + vertex 1.65806 1.929 2.4957 + vertex 1.65957 1.9249 2.49603 + vertex 1.66229 1.92877 2.49445 + endloop + endfacet + facet normal 0.28167 0.180183 0.942442 + outer loop + vertex 1.66816 1.92313 2.49376 + vertex 1.66649 1.92643 2.49363 + vertex 1.66422 1.92305 2.49495 + endloop + endfacet + facet normal 0.280311 0.179518 0.942973 + outer loop + vertex 1.66816 1.92313 2.49376 + vertex 1.67095 1.92616 2.49235 + vertex 1.66649 1.92643 2.49363 + endloop + endfacet + facet normal 0.28937 0.185784 0.939015 + outer loop + vertex 1.65806 1.929 2.4957 + vertex 1.66229 1.92877 2.49445 + vertex 1.65822 1.93362 2.49474 + endloop + endfacet + facet normal 0.289498 0.19156 0.937814 + outer loop + vertex 1.66263 1.93332 2.49344 + vertex 1.66486 1.93663 2.49208 + vertex 1.66097 1.93658 2.49329 + endloop + endfacet + facet normal 0.289019 0.198129 0.936596 + outer loop + vertex 1.66093 1.94111 2.49234 + vertex 1.66097 1.93658 2.49329 + vertex 1.66486 1.93663 2.49208 + endloop + endfacet + facet normal 0.288602 0.19775 0.936805 + outer loop + vertex 1.66517 1.94075 2.49111 + vertex 1.66093 1.94111 2.49234 + vertex 1.66486 1.93663 2.49208 + endloop + endfacet + facet normal 0.283218 0.198498 0.938289 + outer loop + vertex 1.66517 1.94075 2.49111 + vertex 1.66486 1.93663 2.49208 + vertex 1.668 1.93886 2.49066 + endloop + endfacet + facet normal 0.28374 0.199362 0.937948 + outer loop + vertex 1.668 1.93886 2.49066 + vertex 1.66814 1.94344 2.48964 + vertex 1.66517 1.94075 2.49111 + endloop + endfacet + facet normal 0.278351 0.199869 0.939454 + outer loop + vertex 1.668 1.93886 2.49066 + vertex 1.67225 1.93871 2.48943 + vertex 1.66814 1.94344 2.48964 + endloop + endfacet + facet normal 0.283972 0.197435 0.938285 + outer loop + vertex 1.66954 1.93485 2.49104 + vertex 1.668 1.93886 2.49066 + vertex 1.66486 1.93663 2.49208 + endloop + endfacet + facet normal 0.284158 0.199293 0.937836 + outer loop + vertex 1.65429 1.9381 2.49502 + vertex 1.65651 1.9414 2.49365 + vertex 1.65231 1.9437 2.49443 + endloop + endfacet + facet normal 0.29149 0.197993 0.935859 + outer loop + vertex 1.66097 1.93658 2.49329 + vertex 1.66093 1.94111 2.49234 + vertex 1.65818 1.93817 2.49382 + endloop + endfacet + facet normal 0.286421 0.20401 0.936132 + outer loop + vertex 1.65651 1.9414 2.49365 + vertex 1.65682 1.94589 2.49258 + vertex 1.65231 1.9437 2.49443 + endloop + endfacet + facet normal 0.28761 0.206538 0.935213 + outer loop + vertex 1.65477 1.95152 2.49196 + vertex 1.65682 1.94589 2.49258 + vertex 1.65944 1.94971 2.49093 + endloop + endfacet + facet normal 0.28841 0.203517 0.935628 + outer loop + vertex 1.66389 1.94378 2.49086 + vertex 1.66411 1.94793 2.48989 + vertex 1.66105 1.94568 2.49132 + endloop + endfacet + facet normal 0.286738 0.207823 0.935196 + outer loop + vertex 1.65784 1.95374 2.49052 + vertex 1.65944 1.94971 2.49093 + vertex 1.66194 1.95352 2.48931 + endloop + endfacet + facet normal 0.282618 0.205928 0.936868 + outer loop + vertex 1.66803 1.94804 2.48868 + vertex 1.66617 1.95137 2.48851 + vertex 1.66411 1.94793 2.48989 + endloop + endfacet + facet normal 0.286711 0.209983 0.934721 + outer loop + vertex 1.65784 1.95374 2.49052 + vertex 1.66194 1.95352 2.48931 + vertex 1.65795 1.95833 2.48946 + endloop + endfacet + facet normal 0.286468 0.212037 0.934332 + outer loop + vertex 1.6535 1.95884 2.49071 + vertex 1.65795 1.95833 2.48946 + vertex 1.6534 1.96341 2.4897 + endloop + endfacet + facet normal 0.284818 0.213951 0.9344 + outer loop + vertex 1.6534 1.96341 2.4897 + vertex 1.656 1.96641 2.48822 + vertex 1.65309 1.96805 2.48873 + endloop + endfacet + facet normal 0.285926 0.21341 0.934186 + outer loop + vertex 1.66204 1.96102 2.4876 + vertex 1.65987 1.96652 2.48701 + vertex 1.65786 1.96312 2.4884 + endloop + endfacet + facet normal 0.286354 0.217056 0.933214 + outer loop + vertex 1.656 1.96641 2.48822 + vertex 1.65565 1.97107 2.48725 + vertex 1.65309 1.96805 2.48873 + endloop + endfacet + facet normal 0.285473 0.219803 0.932841 + outer loop + vertex 1.66001 1.97063 2.48601 + vertex 1.65851 1.97379 2.48573 + vertex 1.65565 1.97107 2.48725 + endloop + endfacet + facet normal 0.2873 0.220609 0.932089 + outer loop + vertex 1.65851 1.97379 2.48573 + vertex 1.66001 1.97063 2.48601 + vertex 1.66296 1.97327 2.48448 + endloop + endfacet + facet normal 0.28742 0.223241 0.931425 + outer loop + vertex 1.65851 1.97379 2.48573 + vertex 1.66296 1.97327 2.48448 + vertex 1.65827 1.97844 2.48469 + endloop + endfacet + facet normal 0.287889 0.223307 0.931264 + outer loop + vertex 1.65827 1.97844 2.48469 + vertex 1.66093 1.98135 2.48317 + vertex 1.65792 1.98311 2.48368 + endloop + endfacet + facet normal 0.287245 0.224985 0.93106 + outer loop + vertex 1.66704 1.97593 2.48258 + vertex 1.66483 1.98141 2.48195 + vertex 1.66285 1.97804 2.48337 + endloop + endfacet + facet normal 0.287903 0.223335 0.931254 + outer loop + vertex 1.66093 1.98135 2.48317 + vertex 1.66056 1.98598 2.48217 + vertex 1.65792 1.98311 2.48368 + endloop + endfacet + facet normal 0.288596 0.22662 0.930245 + outer loop + vertex 1.67157 1.9873 2.47843 + vertex 1.67123 1.99131 2.47756 + vertex 1.66764 1.98816 2.47944 + endloop + endfacet + facet normal 0.281657 0.227293 0.932205 + outer loop + vertex 1.67404 1.99388 2.47606 + vertex 1.67556 1.99077 2.47636 + vertex 1.67843 1.9934 2.47485 + endloop + endfacet + facet normal 0.272792 0.232002 0.933681 + outer loop + vertex 1.68286 1.99303 2.47363 + vertex 1.68552 1.99591 2.47214 + vertex 1.68111 1.99625 2.47335 + endloop + endfacet + facet normal 0.272794 0.232195 0.933632 + outer loop + vertex 1.68069 2.00094 2.4723 + vertex 1.68111 1.99625 2.47335 + vertex 1.68552 1.99591 2.47214 + endloop + endfacet + facet normal 0.283852 0.233311 0.930051 + outer loop + vertex 1.67806 1.99799 2.47382 + vertex 1.67605 2.00134 2.47359 + vertex 1.67411 1.99797 2.47503 + endloop + endfacet + facet normal 0.281739 0.229432 0.931657 + outer loop + vertex 1.67404 1.99388 2.47606 + vertex 1.67843 1.9934 2.47485 + vertex 1.67411 1.99797 2.47503 + endloop + endfacet + facet normal 0.286821 0.229596 0.930064 + outer loop + vertex 1.67556 1.99077 2.47636 + vertex 1.67404 1.99388 2.47606 + vertex 1.67123 1.99131 2.47756 + endloop + endfacet + facet normal 0.290841 0.230174 0.928672 + outer loop + vertex 1.66946 1.99973 2.47604 + vertex 1.66714 1.99599 2.4777 + vertex 1.67116 1.9958 2.47648 + endloop + endfacet + facet normal 0.289167 0.231318 0.92891 + outer loop + vertex 1.66484 2.00146 2.47705 + vertex 1.66714 1.99599 2.4777 + vertex 1.66946 1.99973 2.47604 + endloop + endfacet + facet normal 0.292737 0.232647 0.927459 + outer loop + vertex 1.66714 1.99599 2.4777 + vertex 1.66484 2.00146 2.47705 + vertex 1.66291 1.99811 2.4785 + endloop + endfacet + facet normal 0.290007 0.224985 0.930203 + outer loop + vertex 1.66764 1.98816 2.47944 + vertex 1.67123 1.99131 2.47756 + vertex 1.66729 1.99218 2.47858 + endloop + endfacet + facet normal 0.290524 0.223176 0.930477 + outer loop + vertex 1.66335 1.98867 2.48066 + vertex 1.66487 1.98553 2.48094 + vertex 1.66764 1.98816 2.47944 + endloop + endfacet + facet normal 0.289876 0.222886 0.930749 + outer loop + vertex 1.66487 1.98553 2.48094 + vertex 1.66335 1.98867 2.48066 + vertex 1.66056 1.98598 2.48217 + endloop + endfacet + facet normal 0.287684 0.223545 0.931271 + outer loop + vertex 1.65792 1.98311 2.48368 + vertex 1.66056 1.98598 2.48217 + vertex 1.65619 1.98637 2.48343 + endloop + endfacet + facet normal 0.285513 0.222465 0.932197 + outer loop + vertex 1.65792 1.98311 2.48368 + vertex 1.65619 1.98637 2.48343 + vertex 1.65353 1.98352 2.48492 + endloop + endfacet + facet normal 0.284158 0.224767 0.932059 + outer loop + vertex 1.65316 1.98814 2.48393 + vertex 1.65581 1.99108 2.48242 + vertex 1.65121 1.99147 2.48372 + endloop + endfacet + facet normal 0.282039 0.225472 0.932532 + outer loop + vertex 1.64293 1.99373 2.48568 + vertex 1.64457 1.98982 2.48613 + vertex 1.64699 1.99358 2.48449 + endloop + endfacet + facet normal 0.282607 0.225685 0.932309 + outer loop + vertex 1.64457 1.98982 2.48613 + vertex 1.64293 1.99373 2.48568 + vertex 1.63994 1.99151 2.48712 + endloop + endfacet + facet normal 0.282773 0.227022 0.931934 + outer loop + vertex 1.63569 1.99604 2.48731 + vertex 1.63606 1.99139 2.48833 + vertex 1.63994 1.99151 2.48712 + endloop + endfacet + facet normal 0.288204 0.231819 0.929085 + outer loop + vertex 1.63547 2.00064 2.48623 + vertex 1.63085 2.00134 2.48749 + vertex 1.63569 1.99604 2.48731 + endloop + endfacet + facet normal 0.288587 0.236867 0.927692 + outer loop + vertex 1.63547 2.00064 2.48623 + vertex 1.63377 2.00393 2.48592 + vertex 1.63085 2.00134 2.48749 + endloop + endfacet + facet normal 0.285013 0.235169 0.929227 + outer loop + vertex 1.63377 2.00393 2.48592 + vertex 1.63547 2.00064 2.48623 + vertex 1.6383 2.00336 2.48467 + endloop + endfacet + facet normal 0.285126 0.237354 0.928637 + outer loop + vertex 1.63377 2.00393 2.48592 + vertex 1.6383 2.00336 2.48467 + vertex 1.63353 2.00847 2.48483 + endloop + endfacet + facet normal 0.287202 0.239331 0.927489 + outer loop + vertex 1.63353 2.00847 2.48483 + vertex 1.6383 2.00336 2.48467 + vertex 1.63793 2.00798 2.4836 + endloop + endfacet + facet normal 0.281911 0.231405 0.931117 + outer loop + vertex 1.63856 1.99873 2.48577 + vertex 1.64006 1.9956 2.48609 + vertex 1.64301 1.99825 2.48454 + endloop + endfacet + facet normal 0.281165 0.239284 0.929349 + outer loop + vertex 1.6383 2.00336 2.48467 + vertex 1.64096 2.00624 2.48313 + vertex 1.63793 2.00798 2.4836 + endloop + endfacet + facet normal 0.281954 0.240833 0.928709 + outer loop + vertex 1.64096 2.00624 2.48313 + vertex 1.64055 2.0108 2.48207 + vertex 1.63793 2.00798 2.4836 + endloop + endfacet + facet normal 0.282398 0.240409 0.928685 + outer loop + vertex 1.63793 2.00798 2.4836 + vertex 1.64055 2.0108 2.48207 + vertex 1.63618 2.01121 2.48329 + endloop + endfacet + facet normal 0.287326 0.242872 0.92653 + outer loop + vertex 1.63793 2.00798 2.4836 + vertex 1.63618 2.01121 2.48329 + vertex 1.63353 2.00847 2.48483 + endloop + endfacet + facet normal 0.280822 0.241953 0.928762 + outer loop + vertex 1.64326 2.01347 2.48056 + vertex 1.64488 2.01039 2.48087 + vertex 1.64755 2.01304 2.47937 + endloop + endfacet + facet normal 0.290218 0.239989 0.92638 + outer loop + vertex 1.63353 2.00847 2.48483 + vertex 1.63618 2.01121 2.48329 + vertex 1.63314 2.01303 2.48377 + endloop + endfacet + facet normal 0.291079 0.233378 0.927797 + outer loop + vertex 1.63068 2.0059 2.48638 + vertex 1.62914 2.00908 2.48607 + vertex 1.62632 2.00647 2.48761 + endloop + endfacet + facet normal 0.287028 0.230722 0.929722 + outer loop + vertex 1.63085 2.00134 2.48749 + vertex 1.63119 1.99642 2.4886 + vertex 1.63569 1.99604 2.48731 + endloop + endfacet + facet normal 0.289038 0.22723 0.929959 + outer loop + vertex 1.63315 1.99304 2.48882 + vertex 1.63119 1.99642 2.4886 + vertex 1.62925 1.99305 2.49003 + endloop + endfacet + facet normal 0.28713 0.222352 0.931727 + outer loop + vertex 1.62912 1.9889 2.49106 + vertex 1.6335 1.98841 2.48983 + vertex 1.62925 1.99305 2.49003 + endloop + endfacet + facet normal 0.292313 0.222243 0.930141 + outer loop + vertex 1.63062 1.98572 2.49135 + vertex 1.62912 1.9889 2.49106 + vertex 1.62615 1.98636 2.4926 + endloop + endfacet + facet normal 0.289316 0.222891 0.930922 + outer loop + vertex 1.62458 1.99494 2.49104 + vertex 1.62217 1.99118 2.49269 + vertex 1.62625 1.99092 2.49149 + endloop + endfacet + facet normal 0.271883 0.235066 0.933179 + outer loop + vertex 1.61992 1.99647 2.49202 + vertex 1.62217 1.99118 2.49269 + vertex 1.62458 1.99494 2.49104 + endloop + endfacet + facet normal 0.287607 0.217477 0.93273 + outer loop + vertex 1.62615 1.98636 2.4926 + vertex 1.62627 1.98152 2.49369 + vertex 1.63086 1.98105 2.49239 + endloop + endfacet + facet normal 0.287559 0.216041 0.933079 + outer loop + vertex 1.62819 1.97812 2.49389 + vertex 1.63086 1.98105 2.49239 + vertex 1.62627 1.98152 2.49369 + endloop + endfacet + facet normal 0.282367 0.22098 0.933508 + outer loop + vertex 1.63121 1.97633 2.4934 + vertex 1.63086 1.98105 2.49239 + vertex 1.62819 1.97812 2.49389 + endloop + endfacet + facet normal 0.282245 0.224662 0.932665 + outer loop + vertex 1.63537 1.98056 2.49114 + vertex 1.6337 1.98381 2.49086 + vertex 1.63086 1.98105 2.49239 + endloop + endfacet + facet normal 0.281551 0.22433 0.932955 + outer loop + vertex 1.6337 1.98381 2.49086 + vertex 1.63537 1.98056 2.49114 + vertex 1.63828 1.98327 2.48961 + endloop + endfacet + facet normal 0.28243 0.225146 0.932493 + outer loop + vertex 1.63828 1.98327 2.48961 + vertex 1.64274 1.97824 2.48948 + vertex 1.64238 1.98226 2.48861 + endloop + endfacet + facet normal 0.284691 0.224122 0.932052 + outer loop + vertex 1.64284 1.9737 2.49054 + vertex 1.64687 1.97354 2.48934 + vertex 1.64274 1.97824 2.48948 + endloop + endfacet + facet normal 0.284425 0.220488 0.932999 + outer loop + vertex 1.64453 1.96974 2.49096 + vertex 1.64284 1.9737 2.49054 + vertex 1.63988 1.97147 2.49196 + endloop + endfacet + facet normal 0.280537 0.224499 0.93322 + outer loop + vertex 1.63995 1.97559 2.49096 + vertex 1.63841 1.97871 2.49067 + vertex 1.6356 1.97599 2.49217 + endloop + endfacet + facet normal 0.282043 0.222148 0.933329 + outer loop + vertex 1.63789 1.96809 2.49337 + vertex 1.63988 1.97147 2.49196 + vertex 1.63596 1.97138 2.49317 + endloop + endfacet + facet normal 0.280074 0.221043 0.934183 + outer loop + vertex 1.63789 1.96809 2.49337 + vertex 1.63596 1.97138 2.49317 + vertex 1.63329 1.96843 2.49467 + endloop + endfacet + facet normal 0.278152 0.221665 0.93461 + outer loop + vertex 1.62877 1.96888 2.49591 + vertex 1.63046 1.96562 2.49618 + vertex 1.63329 1.96843 2.49467 + endloop + endfacet + facet normal 0.279196 0.222173 0.934178 + outer loop + vertex 1.63046 1.96562 2.49618 + vertex 1.62877 1.96888 2.49591 + vertex 1.62594 1.96611 2.49741 + endloop + endfacet + facet normal 0.290092 0.219475 0.931492 + outer loop + vertex 1.62568 1.97081 2.49639 + vertex 1.62415 1.97404 2.4961 + vertex 1.62118 1.97147 2.49763 + endloop + endfacet + facet normal 0.28627 0.210637 0.934709 + outer loop + vertex 1.62327 1.96317 2.49889 + vertex 1.62594 1.96611 2.49741 + vertex 1.62132 1.96662 2.49871 + endloop + endfacet + facet normal 0.281917 0.210703 0.936017 + outer loop + vertex 1.62357 1.9585 2.49985 + vertex 1.6263 1.96135 2.49839 + vertex 1.62327 1.96317 2.49889 + endloop + endfacet + facet normal 0.278428 0.207157 0.937851 + outer loop + vertex 1.62368 1.95392 2.50083 + vertex 1.62811 1.95348 2.49962 + vertex 1.62357 1.9585 2.49985 + endloop + endfacet + facet normal 0.28534 0.210289 0.935072 + outer loop + vertex 1.62516 1.95075 2.50109 + vertex 1.62368 1.95392 2.50083 + vertex 1.62079 1.95124 2.50232 + endloop + endfacet + facet normal 0.28863 0.20498 0.935241 + outer loop + vertex 1.62068 1.95584 2.50133 + vertex 1.61918 1.95907 2.50108 + vertex 1.61619 1.95643 2.50258 + endloop + endfacet + facet normal 0.27388 0.211515 0.938217 + outer loop + vertex 1.61632 1.95164 2.50363 + vertex 1.61619 1.95643 2.50258 + vertex 1.61213 1.95359 2.50441 + endloop + endfacet + facet normal 0.291722 0.206097 0.934035 + outer loop + vertex 1.62104 1.94657 2.50327 + vertex 1.62079 1.95124 2.50232 + vertex 1.61817 1.94829 2.50379 + endloop + endfacet + facet normal 0.291076 0.204878 0.934505 + outer loop + vertex 1.61834 1.94367 2.50475 + vertex 1.62104 1.94657 2.50327 + vertex 1.61817 1.94829 2.50379 + endloop + endfacet + facet normal 0.274426 0.193412 0.941957 + outer loop + vertex 1.61541 1.94103 2.50622 + vertex 1.61409 1.94413 2.50597 + vertex 1.61105 1.94131 2.50744 + endloop + endfacet + facet normal 0.288046 0.183597 0.939852 + outer loop + vertex 1.61838 1.92329 2.50893 + vertex 1.62116 1.92628 2.50749 + vertex 1.61673 1.9266 2.50879 + endloop + endfacet + facet normal 0.286132 0.185475 0.940068 + outer loop + vertex 1.62117 1.92169 2.5084 + vertex 1.62116 1.92628 2.50749 + vertex 1.61838 1.92329 2.50893 + endloop + endfacet + facet normal 0.284637 0.18253 0.941098 + outer loop + vertex 1.61839 1.9187 2.50982 + vertex 1.62117 1.92169 2.5084 + vertex 1.61838 1.92329 2.50893 + endloop + endfacet + facet normal 0.283802 0.183352 0.94119 + outer loop + vertex 1.62283 1.91844 2.50853 + vertex 1.62117 1.92169 2.5084 + vertex 1.61839 1.9187 2.50982 + endloop + endfacet + facet normal 0.283787 0.177811 0.942257 + outer loop + vertex 1.61839 1.9187 2.50982 + vertex 1.62245 1.91386 2.50951 + vertex 1.62283 1.91844 2.50853 + endloop + endfacet + facet normal 0.283156 0.177262 0.94255 + outer loop + vertex 1.6182 1.91405 2.51075 + vertex 1.62245 1.91386 2.50951 + vertex 1.61839 1.9187 2.50982 + endloop + endfacet + facet normal 0.283177 0.175126 0.942943 + outer loop + vertex 1.6182 1.91405 2.51075 + vertex 1.61971 1.90995 2.51106 + vertex 1.62245 1.91386 2.50951 + endloop + endfacet + facet normal 0.283771 0.174671 0.942849 + outer loop + vertex 1.62437 1.90814 2.50999 + vertex 1.62245 1.91386 2.50951 + vertex 1.61971 1.90995 2.51106 + endloop + endfacet + facet normal 0.283446 0.173665 0.943132 + outer loop + vertex 1.62122 1.90584 2.51136 + vertex 1.62437 1.90814 2.50999 + vertex 1.61971 1.90995 2.51106 + endloop + endfacet + facet normal 0.284096 0.173887 0.942896 + outer loop + vertex 1.61971 1.90995 2.51106 + vertex 1.61695 1.90606 2.5126 + vertex 1.62122 1.90584 2.51136 + endloop + endfacet + facet normal 0.284098 0.172496 0.943151 + outer loop + vertex 1.62122 1.90584 2.51136 + vertex 1.61695 1.90606 2.5126 + vertex 1.62103 1.90115 2.51227 + endloop + endfacet + facet normal 0.283595 0.172544 0.943293 + outer loop + vertex 1.62122 1.90584 2.51136 + vertex 1.62103 1.90115 2.51227 + vertex 1.62404 1.9039 2.51086 + endloop + endfacet + facet normal 0.285442 0.172848 0.94268 + outer loop + vertex 1.61503 1.91181 2.51213 + vertex 1.61695 1.90606 2.5126 + vertex 1.61971 1.90995 2.51106 + endloop + endfacet + facet normal 0.283899 0.173033 0.943112 + outer loop + vertex 1.62404 1.9039 2.51086 + vertex 1.62437 1.90814 2.50999 + vertex 1.62122 1.90584 2.51136 + endloop + endfacet + facet normal 0.286581 0.176285 0.941698 + outer loop + vertex 1.61971 1.90995 2.51106 + vertex 1.6182 1.91405 2.51075 + vertex 1.61503 1.91181 2.51213 + endloop + endfacet + facet normal 0.293049 0.176089 0.939742 + outer loop + vertex 1.61539 1.916 2.51124 + vertex 1.61416 1.91911 2.51104 + vertex 1.61116 1.91644 2.51248 + endloop + endfacet + facet normal 0.296663 0.17584 0.938654 + outer loop + vertex 1.61112 1.91183 2.51335 + vertex 1.61116 1.91644 2.51248 + vertex 1.60836 1.91352 2.51391 + endloop + endfacet + facet normal 0.29131 0.174631 0.940554 + outer loop + vertex 1.61695 1.90606 2.5126 + vertex 1.61503 1.91181 2.51213 + vertex 1.61276 1.90849 2.51345 + endloop + endfacet + facet normal 0.283417 0.171909 0.943463 + outer loop + vertex 1.61695 1.90606 2.5126 + vertex 1.61657 1.90144 2.51356 + vertex 1.62103 1.90115 2.51227 + endloop + endfacet + facet normal 0.286964 0.173306 0.942134 + outer loop + vertex 1.61823 1.89811 2.51367 + vertex 1.61657 1.90144 2.51356 + vertex 1.61431 1.89805 2.51487 + endloop + endfacet + facet normal 0.286922 0.173943 0.94203 + outer loop + vertex 1.61431 1.89805 2.51487 + vertex 1.6182 1.89348 2.51453 + vertex 1.61823 1.89811 2.51367 + endloop + endfacet + facet normal 0.279051 0.175691 0.944067 + outer loop + vertex 1.61796 1.88878 2.51548 + vertex 1.62217 1.88872 2.51424 + vertex 1.6182 1.89348 2.51453 + endloop + endfacet + facet normal 0.28211 0.17861 0.942609 + outer loop + vertex 1.6194 1.88476 2.51581 + vertex 1.61796 1.88878 2.51548 + vertex 1.61472 1.88636 2.51691 + endloop + endfacet + facet normal 0.281352 0.175894 0.943346 + outer loop + vertex 1.61472 1.88636 2.51691 + vertex 1.61675 1.88078 2.51734 + vertex 1.6194 1.88476 2.51581 + endloop + endfacet + facet normal 0.292072 0.175812 0.940098 + outer loop + vertex 1.61517 1.89067 2.51596 + vertex 1.61396 1.89379 2.51575 + vertex 1.6109 1.89107 2.51721 + endloop + endfacet + facet normal 0.295957 0.17391 0.939236 + outer loop + vertex 1.61063 1.8864 2.51816 + vertex 1.6109 1.89107 2.51721 + vertex 1.60782 1.88839 2.51868 + endloop + endfacet + facet normal 0.2862 0.177516 0.941583 + outer loop + vertex 1.61675 1.88078 2.51734 + vertex 1.61472 1.88636 2.51691 + vertex 1.61214 1.88233 2.51845 + endloop + endfacet + facet normal 0.284768 0.172257 0.942992 + outer loop + vertex 1.61364 1.87827 2.51874 + vertex 1.61675 1.88078 2.51734 + vertex 1.61214 1.88233 2.51845 + endloop + endfacet + facet normal 0.281671 0.172236 0.943926 + outer loop + vertex 1.6134 1.8736 2.51966 + vertex 1.61636 1.8765 2.51825 + vertex 1.61364 1.87827 2.51874 + endloop + endfacet + facet normal 0.277809 0.169088 0.945638 + outer loop + vertex 1.61306 1.8689 2.5206 + vertex 1.61727 1.86885 2.51937 + vertex 1.6134 1.8736 2.51966 + endloop + endfacet + facet normal 0.280285 0.170579 0.944639 + outer loop + vertex 1.61446 1.86489 2.52091 + vertex 1.61306 1.8689 2.5206 + vertex 1.6098 1.86652 2.522 + endloop + endfacet + facet normal 0.292716 0.166543 0.941584 + outer loop + vertex 1.6103 1.87083 2.52108 + vertex 1.60916 1.87401 2.52088 + vertex 1.60604 1.87132 2.52232 + endloop + endfacet + facet normal 0.290384 0.163597 0.942822 + outer loop + vertex 1.60717 1.86249 2.52351 + vertex 1.6098 1.86652 2.522 + vertex 1.60573 1.86661 2.52324 + endloop + endfacet + facet normal 0.291855 0.164538 0.942204 + outer loop + vertex 1.60863 1.8584 2.52377 + vertex 1.60717 1.86249 2.52351 + vertex 1.60459 1.8585 2.525 + endloop + endfacet + facet normal 0.291932 0.161598 0.942689 + outer loop + vertex 1.60459 1.8585 2.525 + vertex 1.6084 1.8537 2.52465 + vertex 1.60863 1.8584 2.52377 + endloop + endfacet + facet normal 0.279894 0.158232 0.946901 + outer loop + vertex 1.60809 1.84895 2.52553 + vertex 1.61234 1.84883 2.5243 + vertex 1.6084 1.8537 2.52465 + endloop + endfacet + facet normal 0.28951 0.158783 0.943913 + outer loop + vertex 1.60949 1.84485 2.52579 + vertex 1.60809 1.84895 2.52553 + vertex 1.60483 1.84657 2.52693 + endloop + endfacet + facet normal 0.293223 0.157132 0.943043 + outer loop + vertex 1.60531 1.85092 2.52605 + vertex 1.60414 1.85412 2.52588 + vertex 1.60103 1.85136 2.52731 + endloop + endfacet + facet normal 0.283671 0.163723 0.944842 + outer loop + vertex 1.60073 1.84669 2.52821 + vertex 1.60103 1.85136 2.52731 + vertex 1.59789 1.84857 2.52874 + endloop + endfacet + facet normal 0.297951 0.155956 0.941755 + outer loop + vertex 1.60669 1.84085 2.52729 + vertex 1.60483 1.84657 2.52693 + vertex 1.60214 1.84259 2.52844 + endloop + endfacet + facet normal 0.296452 0.151225 0.942999 + outer loop + vertex 1.60341 1.83852 2.5287 + vertex 1.60669 1.84085 2.52729 + vertex 1.60214 1.84259 2.52844 + endloop + endfacet + facet normal 0.298754 0.153775 0.941859 + outer loop + vertex 1.60274 1.83417 2.52962 + vertex 1.60601 1.83644 2.52821 + vertex 1.60341 1.83852 2.5287 + endloop + endfacet + facet normal 0.284443 0.142106 0.948102 + outer loop + vertex 1.59996 1.83028 2.53112 + vertex 1.59875 1.83439 2.53087 + vertex 1.59545 1.83196 2.53223 + endloop + endfacet + facet normal 0.28744 0.15173 0.945704 + outer loop + vertex 1.59545 1.83196 2.53223 + vertex 1.59706 1.82627 2.53265 + vertex 1.59996 1.83028 2.53112 + endloop + endfacet + facet normal 0.264924 0.145892 0.953169 + outer loop + vertex 1.59706 1.82627 2.53265 + vertex 1.59545 1.83196 2.53223 + vertex 1.59294 1.8282 2.5335 + endloop + endfacet + facet normal 0.294148 0.150294 0.943869 + outer loop + vertex 1.60458 1.82845 2.52996 + vertex 1.60726 1.83245 2.52849 + vertex 1.60274 1.83417 2.52962 + endloop + endfacet + facet normal 0.285077 0.150195 0.946664 + outer loop + vertex 1.60408 1.82408 2.5308 + vertex 1.60834 1.8237 2.52958 + vertex 1.60458 1.82845 2.52996 + endloop + endfacet + facet normal 0.291517 0.150769 0.944609 + outer loop + vertex 1.60523 1.8209 2.53095 + vertex 1.60408 1.82408 2.5308 + vertex 1.60094 1.82132 2.53221 + endloop + endfacet + facet normal 0.29524 0.145558 0.94427 + outer loop + vertex 1.59996 1.83028 2.53112 + vertex 1.59706 1.82627 2.53265 + vertex 1.6013 1.8261 2.53135 + endloop + endfacet + facet normal 0.297247 0.147306 0.943369 + outer loop + vertex 1.59796 1.81844 2.5336 + vertex 1.60094 1.82132 2.53221 + vertex 1.5965 1.8217 2.53355 + endloop + endfacet + facet normal 0.300135 0.144109 0.942948 + outer loop + vertex 1.60064 1.81656 2.53303 + vertex 1.60094 1.82132 2.53221 + vertex 1.59796 1.81844 2.5336 + endloop + endfacet + facet normal 0.289926 0.143647 0.946207 + outer loop + vertex 1.60196 1.81256 2.53324 + vertex 1.60462 1.81661 2.5318 + vertex 1.60064 1.81656 2.53303 + endloop + endfacet + facet normal 0.285922 0.140194 0.947942 + outer loop + vertex 1.6034 1.80848 2.53341 + vertex 1.60612 1.81146 2.53214 + vertex 1.60196 1.81256 2.53324 + endloop + endfacet + facet normal 0.287073 0.145715 0.946761 + outer loop + vertex 1.60612 1.81146 2.53214 + vertex 1.60462 1.81661 2.5318 + vertex 1.60196 1.81256 2.53324 + endloop + endfacet + facet normal 0.281701 0.144277 0.948593 + outer loop + vertex 1.60462 1.81661 2.5318 + vertex 1.60612 1.81146 2.53214 + vertex 1.6091 1.81493 2.53073 + endloop + endfacet + facet normal 0.284684 0.141867 0.948066 + outer loop + vertex 1.61459 1.80856 2.53005 + vertex 1.61326 1.81363 2.52969 + vertex 1.61026 1.81018 2.53111 + endloop + endfacet + facet normal 0.282269 0.147867 0.947871 + outer loop + vertex 1.60794 1.81897 2.53045 + vertex 1.6091 1.81493 2.53073 + vertex 1.61205 1.81891 2.52923 + endloop + endfacet + facet normal 0.284534 0.149182 0.946987 + outer loop + vertex 1.61594 1.8166 2.52843 + vertex 1.61668 1.82121 2.52748 + vertex 1.61205 1.81891 2.52923 + endloop + endfacet + facet normal 0.286008 0.146065 0.947029 + outer loop + vertex 1.6174 1.81255 2.52861 + vertex 1.62015 1.81669 2.52714 + vertex 1.61594 1.8166 2.52843 + endloop + endfacet + facet normal 0.285858 0.146175 0.947058 + outer loop + vertex 1.62187 1.81109 2.52749 + vertex 1.62015 1.81669 2.52714 + vertex 1.6174 1.81255 2.52861 + endloop + endfacet + facet normal 0.283616 0.146279 0.947715 + outer loop + vertex 1.62472 1.81512 2.52601 + vertex 1.62187 1.81109 2.52749 + vertex 1.62593 1.81113 2.52627 + endloop + endfacet + facet normal 0.284163 0.146434 0.947528 + outer loop + vertex 1.62593 1.81113 2.52627 + vertex 1.62928 1.81354 2.52489 + vertex 1.62472 1.81512 2.52601 + endloop + endfacet + facet normal 0.285274 0.143828 0.947593 + outer loop + vertex 1.62928 1.81354 2.52489 + vertex 1.63266 1.80915 2.52454 + vertex 1.63334 1.81355 2.52366 + endloop + endfacet + facet normal 0.284557 0.135819 0.948989 + outer loop + vertex 1.62979 1.80514 2.52598 + vertex 1.62859 1.80914 2.52577 + vertex 1.62522 1.80671 2.52713 + endloop + endfacet + facet normal 0.285104 0.133604 0.949139 + outer loop + vertex 1.6343 1.80357 2.52483 + vertex 1.6372 1.80756 2.5234 + vertex 1.63266 1.80915 2.52454 + endloop + endfacet + facet normal 0.291635 0.118164 0.949203 + outer loop + vertex 1.63342 1.79916 2.52565 + vertex 1.6374 1.79919 2.52442 + vertex 1.6343 1.80357 2.52483 + endloop + endfacet + facet normal 0.291063 0.0997916 0.951485 + outer loop + vertex 1.63427 1.79508 2.52582 + vertex 1.63342 1.79916 2.52565 + vertex 1.62993 1.79673 2.52697 + endloop + endfacet + facet normal 0.283992 0.12572 0.950549 + outer loop + vertex 1.62979 1.80514 2.52598 + vertex 1.62685 1.8011 2.5274 + vertex 1.63091 1.80115 2.52617 + endloop + endfacet + facet normal 0.288181 0.111032 0.951117 + outer loop + vertex 1.62595 1.79665 2.52819 + vertex 1.62685 1.8011 2.5274 + vertex 1.62344 1.79864 2.52871 + endloop + endfacet + facet normal 0.291097 0.0936257 0.952101 + outer loop + vertex 1.63098 1.79137 2.52718 + vertex 1.62993 1.79673 2.52697 + vertex 1.62677 1.79259 2.52834 + endloop + endfacet + facet normal 0.288455 0.0886921 0.953377 + outer loop + vertex 1.62768 1.78765 2.52853 + vertex 1.62677 1.79259 2.52834 + vertex 1.62348 1.78889 2.52968 + endloop + endfacet + facet normal 0.284847 0.0899415 0.954344 + outer loop + vertex 1.62451 1.78351 2.52989 + vertex 1.62348 1.78889 2.52968 + vertex 1.62018 1.78519 2.53102 + endloop + endfacet + facet normal 0.284531 0.0932221 0.954124 + outer loop + vertex 1.61597 1.78641 2.53215 + vertex 1.61701 1.78102 2.53237 + vertex 1.62018 1.78519 2.53102 + endloop + endfacet + facet normal 0.279443 0.0923108 0.955715 + outer loop + vertex 1.61701 1.78102 2.53237 + vertex 1.61597 1.78641 2.53215 + vertex 1.61265 1.78269 2.53348 + endloop + endfacet + facet normal 0.279373 0.103701 0.954566 + outer loop + vertex 1.61701 1.78102 2.53237 + vertex 1.616 1.77655 2.53315 + vertex 1.62008 1.77659 2.53195 + endloop + endfacet + facet normal 0.277195 0.116183 0.953763 + outer loop + vertex 1.61712 1.7725 2.53332 + vertex 1.616 1.77655 2.53315 + vertex 1.61257 1.77408 2.53445 + endloop + endfacet + facet normal 0.277809 0.121518 0.95292 + outer loop + vertex 1.60961 1.77 2.53582 + vertex 1.60847 1.77405 2.53564 + vertex 1.60508 1.77158 2.53694 + endloop + endfacet + facet normal 0.278923 0.12202 0.95253 + outer loop + vertex 1.61416 1.76845 2.53471 + vertex 1.61712 1.7725 2.53332 + vertex 1.61257 1.77408 2.53445 + endloop + endfacet + facet normal 0.280062 0.124657 0.951854 + outer loop + vertex 1.61331 1.76405 2.53553 + vertex 1.61732 1.76414 2.53434 + vertex 1.61416 1.76845 2.53471 + endloop + endfacet + facet normal 0.276805 0.12478 0.95279 + outer loop + vertex 1.61076 1.766 2.53602 + vertex 1.60668 1.76595 2.53721 + vertex 1.60984 1.76165 2.53686 + endloop + endfacet + facet normal 0.277412 0.125245 0.952553 + outer loop + vertex 1.60668 1.76595 2.53721 + vertex 1.60584 1.76155 2.53803 + vertex 1.60984 1.76165 2.53686 + endloop + endfacet + facet normal 0.280202 0.122126 0.952141 + outer loop + vertex 1.61331 1.76405 2.53553 + vertex 1.61421 1.76008 2.53578 + vertex 1.61732 1.76414 2.53434 + endloop + endfacet + facet normal 0.281181 0.118182 0.95235 + outer loop + vertex 1.61421 1.76008 2.53578 + vertex 1.61097 1.75645 2.53718 + vertex 1.61521 1.75528 2.53608 + endloop + endfacet + facet normal 0.280564 0.115445 0.952867 + outer loop + vertex 1.61097 1.75645 2.53718 + vertex 1.61209 1.75119 2.53749 + vertex 1.61521 1.75528 2.53608 + endloop + endfacet + facet normal 0.281235 0.11151 0.953138 + outer loop + vertex 1.61112 1.74678 2.53829 + vertex 1.61209 1.75119 2.53749 + vertex 1.6086 1.74879 2.5388 + endloop + endfacet + facet normal 0.281625 0.108629 0.953356 + outer loop + vertex 1.61222 1.74269 2.53843 + vertex 1.6152 1.7468 2.53709 + vertex 1.61112 1.74678 2.53829 + endloop + endfacet + facet normal 0.279621 0.107379 0.954087 + outer loop + vertex 1.61332 1.73861 2.53857 + vertex 1.61222 1.74269 2.53843 + vertex 1.60923 1.73859 2.53977 + endloop + endfacet + facet normal 0.28046 0.106098 0.953984 + outer loop + vertex 1.60833 1.7341 2.54053 + vertex 1.60923 1.73859 2.53977 + vertex 1.6058 1.73611 2.54106 + endloop + endfacet + facet normal 0.28055 0.105772 0.953994 + outer loop + vertex 1.6058 1.73611 2.54106 + vertex 1.60173 1.73607 2.54226 + vertex 1.60485 1.73168 2.54183 + endloop + endfacet + facet normal 0.283625 0.10876 0.952748 + outer loop + vertex 1.60173 1.73607 2.54226 + vertex 1.60018 1.74177 2.54207 + vertex 1.59722 1.73769 2.54341 + endloop + endfacet + facet normal 0.283399 0.10894 0.952794 + outer loop + vertex 1.59722 1.73769 2.54341 + vertex 1.60018 1.74177 2.54207 + vertex 1.59612 1.74173 2.54328 + endloop + endfacet + facet normal 0.293702 0.11164 0.949355 + outer loop + vertex 1.59722 1.73769 2.54341 + vertex 1.59612 1.74173 2.54328 + vertex 1.59279 1.73939 2.54459 + endloop + endfacet + facet normal 0.294999 0.109703 0.949179 + outer loop + vertex 1.59279 1.73939 2.54459 + vertex 1.59612 1.74173 2.54328 + vertex 1.59365 1.74377 2.54381 + endloop + endfacet + facet normal 0.292965 0.10699 0.950118 + outer loop + vertex 1.59612 1.74173 2.54328 + vertex 1.59709 1.74612 2.54249 + vertex 1.59365 1.74377 2.54381 + endloop + endfacet + facet normal 0.293557 0.106077 0.950038 + outer loop + vertex 1.59365 1.74377 2.54381 + vertex 1.59709 1.74612 2.54249 + vertex 1.5928 1.74779 2.54363 + endloop + endfacet + facet normal 0.303762 0.108066 0.946599 + outer loop + vertex 1.59365 1.74377 2.54381 + vertex 1.5928 1.74779 2.54363 + vertex 1.5898 1.74388 2.54504 + endloop + endfacet + facet normal 0.283374 0.109589 0.952727 + outer loop + vertex 1.59709 1.74612 2.54249 + vertex 1.59612 1.74173 2.54328 + vertex 1.60018 1.74177 2.54207 + endloop + endfacet + facet normal 0.27925 0.107886 0.954139 + outer loop + vertex 1.60361 1.74427 2.54078 + vertex 1.6047 1.74019 2.54092 + vertex 1.6077 1.74431 2.53958 + endloop + endfacet + facet normal 0.27916 0.110224 0.953898 + outer loop + vertex 1.60361 1.74427 2.54078 + vertex 1.6077 1.74431 2.53958 + vertex 1.60459 1.74869 2.53998 + endloop + endfacet + facet normal 0.282311 0.108795 0.953134 + outer loop + vertex 1.60108 1.74625 2.54129 + vertex 1.59709 1.74612 2.54249 + vertex 1.60018 1.74177 2.54207 + endloop + endfacet + facet normal 0.295707 0.112559 0.948624 + outer loop + vertex 1.59709 1.74612 2.54249 + vertex 1.59601 1.75137 2.5422 + vertex 1.5928 1.74779 2.54363 + endloop + endfacet + facet normal 0.296493 0.111792 0.948469 + outer loop + vertex 1.5928 1.74779 2.54363 + vertex 1.59601 1.75137 2.5422 + vertex 1.59179 1.75261 2.54337 + endloop + endfacet + facet normal 0.287095 0.114333 0.951054 + outer loop + vertex 1.5949 1.75663 2.5419 + vertex 1.59601 1.75137 2.5422 + vertex 1.59926 1.75503 2.54078 + endloop + endfacet + facet normal 0.278779 0.11439 0.953518 + outer loop + vertex 1.60459 1.74869 2.53998 + vertex 1.60349 1.75392 2.53968 + vertex 1.60023 1.75024 2.54107 + endloop + endfacet + facet normal 0.280918 0.118137 0.952433 + outer loop + vertex 1.5984 1.75904 2.54054 + vertex 1.59926 1.75503 2.54078 + vertex 1.60238 1.75914 2.53935 + endloop + endfacet + facet normal 0.277846 0.117482 0.953415 + outer loop + vertex 1.60772 1.7528 2.53858 + vertex 1.60674 1.75758 2.53828 + vertex 1.60349 1.75392 2.53968 + endloop + endfacet + facet normal 0.277615 0.121861 0.952932 + outer loop + vertex 1.60674 1.75758 2.53828 + vertex 1.60984 1.76165 2.53686 + vertex 1.60584 1.76155 2.53803 + endloop + endfacet + facet normal 0.278037 0.125095 0.95239 + outer loop + vertex 1.60584 1.76155 2.53803 + vertex 1.60668 1.76595 2.53721 + vertex 1.60331 1.76351 2.53852 + endloop + endfacet + facet normal 0.278592 0.124172 0.952348 + outer loop + vertex 1.60508 1.77158 2.53694 + vertex 1.60668 1.76595 2.53721 + vertex 1.60961 1.77 2.53582 + endloop + endfacet + facet normal 0.282092 0.112389 0.952782 + outer loop + vertex 1.60196 1.776 2.53735 + vertex 1.60102 1.77158 2.53815 + vertex 1.60508 1.77158 2.53694 + endloop + endfacet + facet normal 0.30339 0.114739 0.945933 + outer loop + vertex 1.59461 1.77371 2.53991 + vertex 1.59769 1.7692 2.53947 + vertex 1.59852 1.77364 2.53867 + endloop + endfacet + facet normal 0.290796 0.114206 0.949945 + outer loop + vertex 1.59478 1.76514 2.54088 + vertex 1.59368 1.76927 2.54072 + vertex 1.59025 1.76669 2.54208 + endloop + endfacet + facet normal 0.292086 0.118703 0.948997 + outer loop + vertex 1.59025 1.76669 2.54208 + vertex 1.59177 1.76103 2.54232 + vertex 1.59478 1.76514 2.54088 + endloop + endfacet + facet normal 0.277524 0.114999 0.953811 + outer loop + vertex 1.59177 1.76103 2.54232 + vertex 1.59025 1.76669 2.54208 + vertex 1.58723 1.76254 2.54346 + endloop + endfacet + facet normal 0.28805 0.120067 0.950059 + outer loop + vertex 1.59926 1.7635 2.53972 + vertex 1.60216 1.76754 2.53833 + vertex 1.59769 1.7692 2.53947 + endloop + endfacet + facet normal 0.280759 0.120853 0.952139 + outer loop + vertex 1.5984 1.75904 2.54054 + vertex 1.60238 1.75914 2.53935 + vertex 1.59926 1.7635 2.53972 + endloop + endfacet + facet normal 0.288749 0.119682 0.949895 + outer loop + vertex 1.59926 1.75503 2.54078 + vertex 1.5984 1.75904 2.54054 + vertex 1.5949 1.75663 2.5419 + endloop + endfacet + facet normal 0.293301 0.117727 0.948744 + outer loop + vertex 1.59478 1.76514 2.54088 + vertex 1.59177 1.76103 2.54232 + vertex 1.59588 1.76104 2.54105 + endloop + endfacet + facet normal 0.283759 0.123607 0.950895 + outer loop + vertex 1.59085 1.75661 2.54317 + vertex 1.59177 1.76103 2.54232 + vertex 1.58817 1.75868 2.5437 + endloop + endfacet + facet normal 0.29759 0.116341 0.947579 + outer loop + vertex 1.59601 1.75137 2.5422 + vertex 1.5949 1.75663 2.5419 + vertex 1.59179 1.75261 2.54337 + endloop + endfacet + facet normal 0.302979 0.113038 0.94627 + outer loop + vertex 1.5928 1.74779 2.54363 + vertex 1.59179 1.75261 2.54337 + vertex 1.58867 1.74918 2.54478 + endloop + endfacet + facet normal 0.302012 0.109549 0.946989 + outer loop + vertex 1.5898 1.74388 2.54504 + vertex 1.5928 1.74779 2.54363 + vertex 1.58867 1.74918 2.54478 + endloop + endfacet + facet normal 0.303766 0.107541 0.946658 + outer loop + vertex 1.5898 1.74388 2.54504 + vertex 1.59279 1.73939 2.54459 + vertex 1.59365 1.74377 2.54381 + endloop + endfacet + facet normal 0.282029 0.0989307 0.954292 + outer loop + vertex 1.58987 1.73537 2.54595 + vertex 1.58884 1.7395 2.54583 + vertex 1.58537 1.73682 2.54713 + endloop + endfacet + facet normal 0.284657 0.108639 0.952453 + outer loop + vertex 1.58537 1.73682 2.54713 + vertex 1.58683 1.73119 2.54734 + vertex 1.58987 1.73537 2.54595 + endloop + endfacet + facet normal 0.254146 0.101069 0.961871 + outer loop + vertex 1.58683 1.73119 2.54734 + vertex 1.58537 1.73682 2.54713 + vertex 1.58213 1.73218 2.54847 + endloop + endfacet + facet normal 0.291697 0.10549 0.950676 + outer loop + vertex 1.5943 1.73367 2.54476 + vertex 1.59722 1.73769 2.54341 + vertex 1.59279 1.73939 2.54459 + endloop + endfacet + facet normal 0.289029 0.104063 0.951648 + outer loop + vertex 1.59342 1.7292 2.54551 + vertex 1.59739 1.7292 2.54431 + vertex 1.5943 1.73367 2.54476 + endloop + endfacet + facet normal 0.296888 0.101035 0.949552 + outer loop + vertex 1.59427 1.72509 2.54568 + vertex 1.59342 1.7292 2.54551 + vertex 1.58992 1.72682 2.54686 + endloop + endfacet + facet normal 0.292535 0.102357 0.950761 + outer loop + vertex 1.58987 1.73537 2.54595 + vertex 1.58683 1.73119 2.54734 + vertex 1.59093 1.73128 2.54607 + endloop + endfacet + facet normal 0.267244 0.113085 0.95697 + outer loop + vertex 1.58585 1.72673 2.54814 + vertex 1.58683 1.73119 2.54734 + vertex 1.5832 1.72849 2.54867 + endloop + endfacet + facet normal 0.300889 0.0975585 0.948656 + outer loop + vertex 1.59099 1.72141 2.54708 + vertex 1.58992 1.72682 2.54686 + vertex 1.58674 1.72271 2.54829 + endloop + endfacet + facet normal 0.294009 0.0933407 0.951234 + outer loop + vertex 1.59099 1.72141 2.54708 + vertex 1.59198 1.71603 2.5473 + vertex 1.5952 1.72016 2.5459 + endloop + endfacet + facet normal 0.306091 0.0946548 0.947285 + outer loop + vertex 1.59084 1.71163 2.54811 + vertex 1.59198 1.71603 2.5473 + vertex 1.58849 1.71371 2.54866 + endloop + endfacet + facet normal 0.295034 0.100655 0.95017 + outer loop + vertex 1.5917 1.70761 2.54827 + vertex 1.59481 1.71168 2.54687 + vertex 1.59084 1.71163 2.54811 + endloop + endfacet + facet normal 0.310299 0.101518 0.945203 + outer loop + vertex 1.59276 1.70274 2.54844 + vertex 1.5917 1.70761 2.54827 + vertex 1.58861 1.70411 2.54966 + endloop + endfacet + facet normal 0.308347 0.0943678 0.946582 + outer loop + vertex 1.58973 1.69879 2.54982 + vertex 1.59276 1.70274 2.54844 + vertex 1.58861 1.70411 2.54966 + endloop + endfacet + facet normal 0.307022 0.0870629 0.947712 + outer loop + vertex 1.58973 1.69879 2.54982 + vertex 1.59246 1.69441 2.54934 + vertex 1.59361 1.69871 2.54857 + endloop + endfacet + facet normal 0.306771 0.0767023 0.948688 + outer loop + vertex 1.58922 1.69041 2.55072 + vertex 1.58863 1.69448 2.55058 + vertex 1.58508 1.69205 2.55192 + endloop + endfacet + facet normal 0.292412 0.0792009 0.953007 + outer loop + vertex 1.59324 1.68912 2.54954 + vertex 1.5966 1.69272 2.54821 + vertex 1.59246 1.69441 2.54934 + endloop + endfacet + facet normal 0.305293 0.0723824 0.949504 + outer loop + vertex 1.58508 1.69205 2.55192 + vertex 1.58576 1.68676 2.55211 + vertex 1.58922 1.69041 2.55072 + endloop + endfacet + facet normal 0.290101 0.0706001 0.954388 + outer loop + vertex 1.58576 1.68676 2.55211 + vertex 1.58508 1.69205 2.55192 + vertex 1.58167 1.68775 2.55328 + endloop + endfacet + facet normal 0.296498 0.0662161 0.952735 + outer loop + vertex 1.58637 1.68159 2.55228 + vertex 1.58576 1.68676 2.55211 + vertex 1.58211 1.6829 2.55351 + endloop + endfacet + facet normal 0.298743 0.0734117 0.951506 + outer loop + vertex 1.59393 1.68403 2.54972 + vertex 1.59324 1.68912 2.54954 + vertex 1.58985 1.68539 2.55089 + endloop + endfacet + facet normal 0.28579 0.0661563 0.956006 + outer loop + vertex 1.59474 1.67868 2.54985 + vertex 1.59804 1.68286 2.54857 + vertex 1.59393 1.68403 2.54972 + endloop + endfacet + facet normal 0.285912 0.0632575 0.956166 + outer loop + vertex 1.59347 1.67423 2.55052 + vertex 1.59743 1.67438 2.54933 + vertex 1.59474 1.67868 2.54985 + endloop + endfacet + facet normal 0.297599 0.0646516 0.952499 + outer loop + vertex 1.59403 1.6702 2.55062 + vertex 1.59347 1.67423 2.55052 + vertex 1.58984 1.67177 2.55182 + endloop + endfacet + facet normal 0.305825 0.0634705 0.94997 + outer loop + vertex 1.59052 1.68033 2.55103 + vertex 1.58717 1.67614 2.55239 + vertex 1.59115 1.67621 2.55111 + endloop + endfacet + facet normal 0.31386 0.0652021 0.947228 + outer loop + vertex 1.5859 1.67169 2.55312 + vertex 1.58717 1.67614 2.55239 + vertex 1.58358 1.67374 2.55375 + endloop + endfacet + facet normal 0.311936 0.0650945 0.947871 + outer loop + vertex 1.59052 1.66651 2.55196 + vertex 1.58984 1.67177 2.55182 + vertex 1.58649 1.66767 2.55321 + endloop + endfacet + facet normal 0.311979 0.0652759 0.947844 + outer loop + vertex 1.58708 1.6628 2.55334 + vertex 1.59052 1.66651 2.55196 + vertex 1.58649 1.66767 2.55321 + endloop + endfacet + facet normal 0.32196 0.066595 0.944408 + outer loop + vertex 1.58771 1.65795 2.55347 + vertex 1.58708 1.6628 2.55334 + vertex 1.58381 1.65918 2.55471 + endloop + endfacet + facet normal 0.322416 0.0683188 0.94413 + outer loop + vertex 1.58468 1.65388 2.5548 + vertex 1.58771 1.65795 2.55347 + vertex 1.58381 1.65918 2.55471 + endloop + endfacet + facet normal 0.322513 0.0672731 0.944171 + outer loop + vertex 1.58468 1.65388 2.5548 + vertex 1.58746 1.64931 2.55418 + vertex 1.58863 1.65381 2.55346 + endloop + endfacet + facet normal 0.29832 0.0581065 0.952696 + outer loop + vertex 1.58426 1.64552 2.55553 + vertex 1.58362 1.64956 2.55548 + vertex 1.58019 1.64708 2.55671 + endloop + endfacet + facet normal 0.315343 0.061456 0.946986 + outer loop + vertex 1.58801 1.64411 2.55433 + vertex 1.5909 1.6469 2.55319 + vertex 1.58746 1.64931 2.55418 + endloop + endfacet + facet normal 0.299116 0.060498 0.952297 + outer loop + vertex 1.58019 1.64708 2.55671 + vertex 1.58087 1.64179 2.55683 + vertex 1.58426 1.64552 2.55553 + endloop + endfacet + facet normal 0.245033 0.0538135 0.96802 + outer loop + vertex 1.58087 1.64179 2.55683 + vertex 1.58019 1.64708 2.55671 + vertex 1.57671 1.64221 2.55786 + endloop + endfacet + facet normal 0.249382 0.0490507 0.967162 + outer loop + vertex 1.58109 1.63677 2.55703 + vertex 1.58087 1.64179 2.55683 + vertex 1.57691 1.6373 2.55808 + endloop + endfacet + facet normal 0.322888 0.0567939 0.944732 + outer loop + vertex 1.58847 1.63934 2.55446 + vertex 1.58801 1.64411 2.55433 + vertex 1.58474 1.64066 2.55566 + endloop + endfacet + facet normal 0.311196 0.0503485 0.949011 + outer loop + vertex 1.58871 1.63436 2.55465 + vertex 1.59224 1.63803 2.5533 + vertex 1.58847 1.63934 2.55446 + endloop + endfacet + facet normal 0.304605 0.0456711 0.951383 + outer loop + vertex 1.58109 1.63677 2.55703 + vertex 1.58115 1.63174 2.55725 + vertex 1.58494 1.6357 2.55585 + endloop + endfacet + facet normal 0.257407 0.0457419 0.96522 + outer loop + vertex 1.58115 1.63174 2.55725 + vertex 1.58109 1.63677 2.55703 + vertex 1.57693 1.63233 2.55835 + endloop + endfacet + facet normal 0.269276 0.0447179 0.962024 + outer loop + vertex 1.58144 1.62667 2.55741 + vertex 1.58115 1.63174 2.55725 + vertex 1.57716 1.62754 2.55857 + endloop + endfacet + facet normal 0.31579 0.0476719 0.947631 + outer loop + vertex 1.58902 1.62915 2.55481 + vertex 1.58871 1.63436 2.55465 + vertex 1.58511 1.63061 2.55604 + endloop + endfacet + facet normal 0.306493 0.0468292 0.95072 + outer loop + vertex 1.58955 1.62343 2.55492 + vertex 1.59304 1.62783 2.55358 + vertex 1.58902 1.62915 2.55481 + endloop + endfacet + facet normal 0.306965 0.0492072 0.950448 + outer loop + vertex 1.58683 1.61675 2.55614 + vertex 1.59269 1.61957 2.5541 + vertex 1.58955 1.62343 2.55492 + endloop + endfacet + facet normal 0.311978 0.0456991 0.94899 + outer loop + vertex 1.58554 1.6255 2.55614 + vertex 1.58239 1.6213 2.55737 + vertex 1.58606 1.62172 2.55615 + endloop + endfacet + facet normal 0.292608 0.0575687 0.954498 + outer loop + vertex 1.5813 1.61678 2.55798 + vertex 1.58239 1.6213 2.55737 + vertex 1.57826 1.61883 2.55879 + endloop + endfacet + facet normal 0.316916 0.0413552 0.947552 + outer loop + vertex 1.58683 1.61675 2.55614 + vertex 1.58524 1.61079 2.55694 + vertex 1.58909 1.61049 2.55566 + endloop + endfacet + facet normal 0.32839 0.0387462 0.943747 + outer loop + vertex 1.58583 1.60651 2.5569 + vertex 1.58524 1.61079 2.55694 + vertex 1.58205 1.60775 2.55817 + endloop + endfacet + facet normal 0.31428 0.0370999 0.948605 + outer loop + vertex 1.58583 1.60651 2.5569 + vertex 1.58608 1.6017 2.55701 + vertex 1.58976 1.60546 2.55564 + endloop + endfacet + facet normal 0.325912 0.0383718 0.944621 + outer loop + vertex 1.58614 1.59676 2.55719 + vertex 1.58608 1.6017 2.55701 + vertex 1.58238 1.59805 2.55844 + endloop + endfacet + facet normal 0.312044 0.0383353 0.949294 + outer loop + vertex 1.58614 1.59676 2.55719 + vertex 1.58621 1.59177 2.55737 + vertex 1.58994 1.59555 2.55599 + endloop + endfacet + facet normal 0.327534 0.0361642 0.944147 + outer loop + vertex 1.58636 1.58677 2.55751 + vertex 1.58621 1.59177 2.55737 + vertex 1.58258 1.58805 2.55877 + endloop + endfacet + facet normal 0.312787 0.0312496 0.949309 + outer loop + vertex 1.58636 1.58677 2.55751 + vertex 1.58667 1.5817 2.55757 + vertex 1.59026 1.58555 2.55626 + endloop + endfacet + facet normal 0.31141 0.0248924 0.94995 + outer loop + vertex 1.58667 1.5817 2.55757 + vertex 1.58724 1.57623 2.55753 + vertex 1.59072 1.58059 2.55627 + endloop + endfacet + facet normal 0.309365 0.0267011 0.950568 + outer loop + vertex 1.59072 1.58059 2.55627 + vertex 1.58724 1.57623 2.55753 + vertex 1.59128 1.57655 2.5562 + endloop + endfacet + facet normal 0.295931 0.0207517 0.954984 + outer loop + vertex 1.5936 1.57465 2.55552 + vertex 1.59412 1.57058 2.55545 + vertex 1.59761 1.57485 2.55428 + endloop + endfacet + facet normal 0.311781 0.0200436 0.949942 + outer loop + vertex 1.59053 1.56686 2.55665 + vertex 1.58998 1.57209 2.55672 + vertex 1.58664 1.56793 2.55791 + endloop + endfacet + facet normal 0.311728 0.0198211 0.949965 + outer loop + vertex 1.58682 1.56314 2.55794 + vertex 1.59053 1.56686 2.55665 + vertex 1.58664 1.56793 2.55791 + endloop + endfacet + facet normal 0.328068 0.0204106 0.944434 + outer loop + vertex 1.58682 1.56314 2.55794 + vertex 1.58664 1.56793 2.55791 + vertex 1.58257 1.5647 2.55939 + endloop + endfacet + facet normal 0.328086 0.0204675 0.944426 + outer loop + vertex 1.58316 1.55951 2.5593 + vertex 1.58682 1.56314 2.55794 + vertex 1.58257 1.5647 2.55939 + endloop + endfacet + facet normal 0.330771 0.0174327 0.94355 + outer loop + vertex 1.58701 1.55812 2.55797 + vertex 1.58682 1.56314 2.55794 + vertex 1.58316 1.55951 2.5593 + endloop + endfacet + facet normal 0.313744 0.0168165 0.949359 + outer loop + vertex 1.58701 1.55812 2.55797 + vertex 1.59075 1.56183 2.55667 + vertex 1.58682 1.56314 2.55794 + endloop + endfacet + facet normal 0.313918 0.0174027 0.949291 + outer loop + vertex 1.59075 1.56183 2.55667 + vertex 1.59053 1.56686 2.55665 + vertex 1.58682 1.56314 2.55794 + endloop + endfacet + facet normal 0.296462 0.0202745 0.954829 + outer loop + vertex 1.59814 1.56942 2.55423 + vertex 1.59761 1.57485 2.55428 + vertex 1.59412 1.57058 2.55545 + endloop + endfacet + facet normal 0.29729 0.0163053 0.954648 + outer loop + vertex 1.59833 1.56435 2.55425 + vertex 1.60209 1.5681 2.55302 + vertex 1.59814 1.56942 2.55423 + endloop + endfacet + facet normal 0.300194 0.0168162 0.95373 + outer loop + vertex 1.59053 1.56686 2.55665 + vertex 1.59075 1.56183 2.55667 + vertex 1.59447 1.5656 2.55543 + endloop + endfacet + facet normal 0.31518 0.0152151 0.94891 + outer loop + vertex 1.59081 1.5568 2.55673 + vertex 1.59075 1.56183 2.55667 + vertex 1.58701 1.55812 2.55797 + endloop + endfacet + facet normal 0.31551 0.0162909 0.948782 + outer loop + vertex 1.58708 1.5531 2.55804 + vertex 1.59081 1.5568 2.55673 + vertex 1.58701 1.55812 2.55797 + endloop + endfacet + facet normal 0.332415 0.0164271 0.94299 + outer loop + vertex 1.58708 1.5531 2.55804 + vertex 1.58701 1.55812 2.55797 + vertex 1.58336 1.5545 2.55932 + endloop + endfacet + facet normal 0.332569 0.0168943 0.942928 + outer loop + vertex 1.58344 1.54948 2.55938 + vertex 1.58708 1.5531 2.55804 + vertex 1.58336 1.5545 2.55932 + endloop + endfacet + facet normal 0.333206 0.0161728 0.942715 + outer loop + vertex 1.58711 1.54809 2.55811 + vertex 1.58708 1.5531 2.55804 + vertex 1.58344 1.54948 2.55938 + endloop + endfacet + facet normal 0.316534 0.0161624 0.948443 + outer loop + vertex 1.58711 1.54809 2.55811 + vertex 1.59082 1.5518 2.55681 + vertex 1.58708 1.5531 2.55804 + endloop + endfacet + facet normal 0.316301 0.0154059 0.948534 + outer loop + vertex 1.59082 1.5518 2.55681 + vertex 1.59081 1.5568 2.55673 + vertex 1.58708 1.5531 2.55804 + endloop + endfacet + facet normal 0.297881 0.0137314 0.954504 + outer loop + vertex 1.59836 1.55934 2.55432 + vertex 1.59833 1.56435 2.55425 + vertex 1.59458 1.56057 2.55548 + endloop + endfacet + facet normal 0.299546 0.0129883 0.953993 + outer loop + vertex 1.59837 1.55436 2.55438 + vertex 1.60215 1.55812 2.55314 + vertex 1.59836 1.55934 2.55432 + endloop + endfacet + facet normal 0.303058 0.0154508 0.952847 + outer loop + vertex 1.59081 1.5568 2.55673 + vertex 1.59082 1.5518 2.55681 + vertex 1.59458 1.55557 2.55555 + endloop + endfacet + facet normal 0.316744 0.0159286 0.948377 + outer loop + vertex 1.59086 1.54681 2.55688 + vertex 1.59082 1.5518 2.55681 + vertex 1.58711 1.54809 2.55811 + endloop + endfacet + facet normal 0.316685 0.0157349 0.9484 + outer loop + vertex 1.58715 1.5431 2.55818 + vertex 1.59086 1.54681 2.55688 + vertex 1.58711 1.54809 2.55811 + endloop + endfacet + facet normal 0.333333 0.0158159 0.942677 + outer loop + vertex 1.58715 1.5431 2.55818 + vertex 1.58711 1.54809 2.55811 + vertex 1.58348 1.54449 2.55945 + endloop + endfacet + facet normal 0.332474 0.0132266 0.94302 + outer loop + vertex 1.58353 1.5395 2.55951 + vertex 1.58715 1.5431 2.55818 + vertex 1.58348 1.54449 2.55945 + endloop + endfacet + facet normal 0.332427 0.0132806 0.943036 + outer loop + vertex 1.58721 1.53811 2.55823 + vertex 1.58715 1.5431 2.55818 + vertex 1.58353 1.5395 2.55951 + endloop + endfacet + facet normal 0.31631 0.0131438 0.948565 + outer loop + vertex 1.58721 1.53811 2.55823 + vertex 1.59092 1.54182 2.55694 + vertex 1.58715 1.5431 2.55818 + endloop + endfacet + facet normal 0.31699 0.0153968 0.948304 + outer loop + vertex 1.59092 1.54182 2.55694 + vertex 1.59086 1.54681 2.55688 + vertex 1.58715 1.5431 2.55818 + endloop + endfacet + facet normal 0.300227 0.0136616 0.95377 + outer loop + vertex 1.59841 1.54938 2.55444 + vertex 1.59837 1.55436 2.55438 + vertex 1.5946 1.55058 2.55562 + endloop + endfacet + facet normal 0.302958 0.013522 0.952908 + outer loop + vertex 1.59848 1.54439 2.55449 + vertex 1.60223 1.54815 2.55324 + vertex 1.59841 1.54938 2.55444 + endloop + endfacet + facet normal 0.304928 0.0152875 0.952253 + outer loop + vertex 1.59086 1.54681 2.55688 + vertex 1.59092 1.54182 2.55694 + vertex 1.59466 1.5456 2.55568 + endloop + endfacet + facet normal 0.316957 0.0124258 0.948358 + outer loop + vertex 1.59099 1.53683 2.55698 + vertex 1.59092 1.54182 2.55694 + vertex 1.58721 1.53811 2.55823 + endloop + endfacet + facet normal 0.315998 0.00925933 0.948715 + outer loop + vertex 1.58726 1.53312 2.55826 + vertex 1.59099 1.53683 2.55698 + vertex 1.58721 1.53811 2.55823 + endloop + endfacet + facet normal 0.331564 0.0093697 0.943386 + outer loop + vertex 1.58726 1.53312 2.55826 + vertex 1.58721 1.53811 2.55823 + vertex 1.58358 1.53451 2.55954 + endloop + endfacet + facet normal 0.330459 0.00605253 0.943801 + outer loop + vertex 1.58361 1.52952 2.55956 + vertex 1.58726 1.53312 2.55826 + vertex 1.58358 1.53451 2.55954 + endloop + endfacet + facet normal 0.330833 0.0056271 0.943672 + outer loop + vertex 1.58728 1.52813 2.55828 + vertex 1.58726 1.53312 2.55826 + vertex 1.58361 1.52952 2.55956 + endloop + endfacet + facet normal 0.316259 0.00557928 0.948656 + outer loop + vertex 1.58728 1.52813 2.55828 + vertex 1.59103 1.53184 2.55701 + vertex 1.58726 1.53312 2.55826 + endloop + endfacet + facet normal 0.31703 0.00810762 0.948381 + outer loop + vertex 1.59103 1.53184 2.55701 + vertex 1.59099 1.53683 2.55698 + vertex 1.58726 1.53312 2.55826 + endloop + endfacet + facet normal 0.305077 0.0108854 0.952265 + outer loop + vertex 1.59855 1.5394 2.55452 + vertex 1.59848 1.54439 2.55449 + vertex 1.59473 1.54061 2.55573 + endloop + endfacet + facet normal 0.30848 0.00664247 0.951208 + outer loop + vertex 1.59859 1.5344 2.55455 + vertex 1.60233 1.53816 2.5533 + vertex 1.59855 1.5394 2.55452 + endloop + endfacet + facet normal 0.307259 0.00804366 0.951592 + outer loop + vertex 1.59099 1.53683 2.55698 + vertex 1.59103 1.53184 2.55701 + vertex 1.59479 1.53562 2.55576 + endloop + endfacet + facet normal 0.317233 0.00448729 0.948337 + outer loop + vertex 1.59105 1.52685 2.55703 + vertex 1.59103 1.53184 2.55701 + vertex 1.58728 1.52813 2.55828 + endloop + endfacet + facet normal 0.3169 0.0033994 0.948453 + outer loop + vertex 1.5873 1.52314 2.5583 + vertex 1.59105 1.52685 2.55703 + vertex 1.58728 1.52813 2.55828 + endloop + endfacet + facet normal 0.330289 0.0034172 0.943874 + outer loop + vertex 1.5873 1.52314 2.5583 + vertex 1.58728 1.52813 2.55828 + vertex 1.58362 1.52452 2.55958 + endloop + endfacet + facet normal 0.329939 0.00237404 0.943999 + outer loop + vertex 1.58363 1.51953 2.55959 + vertex 1.5873 1.52314 2.5583 + vertex 1.58362 1.52452 2.55958 + endloop + endfacet + facet normal 0.330248 0.00202154 0.943892 + outer loop + vertex 1.5873 1.51815 2.5583 + vertex 1.5873 1.52314 2.5583 + vertex 1.58363 1.51953 2.55959 + endloop + endfacet + facet normal 0.317296 0.00200956 0.948324 + outer loop + vertex 1.5873 1.51815 2.5583 + vertex 1.59106 1.52185 2.55704 + vertex 1.5873 1.52314 2.5583 + endloop + endfacet + facet normal 0.317511 0.00271226 0.948251 + outer loop + vertex 1.59106 1.52185 2.55704 + vertex 1.59105 1.52685 2.55703 + vertex 1.5873 1.52314 2.5583 + endloop + endfacet + facet normal 0.309762 0.00324269 0.950808 + outer loop + vertex 1.59861 1.52941 2.55456 + vertex 1.59859 1.5344 2.55455 + vertex 1.59482 1.53062 2.55578 + endloop + endfacet + facet normal 0.312143 0.00215518 0.950033 + outer loop + vertex 1.59861 1.52442 2.55457 + vertex 1.60236 1.52818 2.55332 + vertex 1.59861 1.52941 2.55456 + endloop + endfacet + facet normal 0.31032 0.00270437 0.950628 + outer loop + vertex 1.59105 1.52685 2.55703 + vertex 1.59106 1.52185 2.55704 + vertex 1.59484 1.52563 2.5558 + endloop + endfacet + facet normal 0.317409 0.00188235 0.948287 + outer loop + vertex 1.59106 1.51686 2.55705 + vertex 1.59106 1.52185 2.55704 + vertex 1.5873 1.51815 2.5583 + endloop + endfacet + facet normal 0.316994 0.000530196 0.948427 + outer loop + vertex 1.58731 1.51315 2.5583 + vertex 1.59106 1.51686 2.55705 + vertex 1.5873 1.51815 2.5583 + endloop + endfacet + facet normal 0.330697 0.00055748 0.943737 + outer loop + vertex 1.58731 1.51315 2.5583 + vertex 1.5873 1.51815 2.5583 + vertex 1.58364 1.51454 2.55959 + endloop + endfacet + facet normal 0.330303 -0.000614466 0.943875 + outer loop + vertex 1.58365 1.50955 2.55959 + vertex 1.58731 1.51315 2.5583 + vertex 1.58364 1.51454 2.55959 + endloop + endfacet + facet normal 0.331102 -0.00152769 0.943594 + outer loop + vertex 1.58732 1.50816 2.55829 + vertex 1.58731 1.51315 2.5583 + vertex 1.58365 1.50955 2.55959 + endloop + endfacet + facet normal 0.31636 -0.00156307 0.948638 + outer loop + vertex 1.58732 1.50816 2.55829 + vertex 1.59108 1.51187 2.55705 + vertex 1.58731 1.51315 2.5583 + endloop + endfacet + facet normal 0.317001 0.000522797 0.948425 + outer loop + vertex 1.59108 1.51187 2.55705 + vertex 1.59106 1.51686 2.55705 + vertex 1.58731 1.51315 2.5583 + endloop + endfacet + facet normal 0.309676 0.00338843 0.950836 + outer loop + vertex 1.59863 1.51943 2.55458 + vertex 1.59861 1.52442 2.55457 + vertex 1.59485 1.52064 2.55581 + endloop + endfacet + facet normal 0.310201 0.00388951 0.950663 + outer loop + vertex 1.59864 1.51444 2.55459 + vertex 1.60239 1.51819 2.55335 + vertex 1.59863 1.51943 2.55458 + endloop + endfacet + facet normal 0.309146 0.00050486 0.951014 + outer loop + vertex 1.59106 1.51686 2.55705 + vertex 1.59108 1.51187 2.55705 + vertex 1.59486 1.51565 2.55582 + endloop + endfacet + facet normal 0.316314 -0.00151054 0.948653 + outer loop + vertex 1.59108 1.50688 2.55704 + vertex 1.59108 1.51187 2.55705 + vertex 1.58732 1.50816 2.55829 + endloop + endfacet + facet normal 0.315797 -0.00318882 0.948821 + outer loop + vertex 1.58732 1.50317 2.55828 + vertex 1.59108 1.50688 2.55704 + vertex 1.58732 1.50816 2.55829 + endloop + endfacet + facet normal 0.331349 -0.00315936 0.943503 + outer loop + vertex 1.58732 1.50317 2.55828 + vertex 1.58732 1.50816 2.55829 + vertex 1.58365 1.50456 2.55957 + endloop + endfacet + facet normal 0.331265 -0.00340642 0.943531 + outer loop + vertex 1.58364 1.49957 2.55955 + vertex 1.58732 1.50317 2.55828 + vertex 1.58365 1.50456 2.55957 + endloop + endfacet + facet normal 0.332235 -0.0045186 0.943186 + outer loop + vertex 1.58732 1.49818 2.55825 + vertex 1.58732 1.50317 2.55828 + vertex 1.58364 1.49957 2.55955 + endloop + endfacet + facet normal 0.315981 -0.00451484 0.948755 + outer loop + vertex 1.58732 1.49818 2.55825 + vertex 1.59108 1.50189 2.55702 + vertex 1.58732 1.50317 2.55828 + endloop + endfacet + facet normal 0.316237 -0.00368503 0.948673 + outer loop + vertex 1.59108 1.50189 2.55702 + vertex 1.59108 1.50688 2.55704 + vertex 1.58732 1.50317 2.55828 + endloop + endfacet + facet normal 0.306374 0.00271117 0.951907 + outer loop + vertex 1.59866 1.50944 2.5546 + vertex 1.59864 1.51444 2.55459 + vertex 1.59487 1.51065 2.55582 + endloop + endfacet + facet normal 0.306635 -0.000110153 0.951827 + outer loop + vertex 1.59866 1.50445 2.5546 + vertex 1.60243 1.50821 2.55339 + vertex 1.59866 1.50944 2.5546 + endloop + endfacet + facet normal 0.30602 -0.00369098 0.952018 + outer loop + vertex 1.59108 1.50688 2.55704 + vertex 1.59108 1.50189 2.55702 + vertex 1.59488 1.50566 2.55581 + endloop + endfacet + facet normal 0.316497 -0.00509775 0.94858 + outer loop + vertex 1.59106 1.49689 2.557 + vertex 1.59108 1.50189 2.55702 + vertex 1.58732 1.49818 2.55825 + endloop + endfacet + facet normal 0.316381 -0.00547224 0.948616 + outer loop + vertex 1.58729 1.49318 2.55823 + vertex 1.59106 1.49689 2.557 + vertex 1.58732 1.49818 2.55825 + endloop + endfacet + facet normal 0.333739 -0.00552325 0.942649 + outer loop + vertex 1.58729 1.49318 2.55823 + vertex 1.58732 1.49818 2.55825 + vertex 1.58363 1.49457 2.55954 + endloop + endfacet + facet normal 0.333734 -0.00553778 0.942651 + outer loop + vertex 1.5836 1.48957 2.55952 + vertex 1.58729 1.49318 2.55823 + vertex 1.58363 1.49457 2.55954 + endloop + endfacet + facet normal 0.334929 -0.00691369 0.942218 + outer loop + vertex 1.58726 1.48819 2.55821 + vertex 1.58729 1.49318 2.55823 + vertex 1.5836 1.48957 2.55952 + endloop + endfacet + facet normal 0.317338 -0.00682107 0.948288 + outer loop + vertex 1.58726 1.48819 2.55821 + vertex 1.59103 1.4919 2.55697 + vertex 1.58729 1.49318 2.55823 + endloop + endfacet + facet normal 0.3174 -0.00662318 0.948269 + outer loop + vertex 1.59103 1.4919 2.55697 + vertex 1.59106 1.49689 2.557 + vertex 1.58729 1.49318 2.55823 + endloop + endfacet + facet normal 0.303357 -0.00303539 0.952872 + outer loop + vertex 1.59864 1.49946 2.55459 + vertex 1.59866 1.50445 2.5546 + vertex 1.59486 1.50067 2.5558 + endloop + endfacet + facet normal 0.304721 -0.0054338 0.952426 + outer loop + vertex 1.59861 1.49447 2.55457 + vertex 1.60242 1.49823 2.55338 + vertex 1.59864 1.49946 2.55459 + endloop + endfacet + facet normal 0.305446 -0.00656667 0.952187 + outer loop + vertex 1.59106 1.49689 2.557 + vertex 1.59103 1.4919 2.55697 + vertex 1.59484 1.49568 2.55578 + endloop + endfacet + facet normal 0.317762 -0.00730088 0.948142 + outer loop + vertex 1.591 1.48691 2.55695 + vertex 1.59103 1.4919 2.55697 + vertex 1.58726 1.48819 2.55821 + endloop + endfacet + facet normal 0.317628 -0.00773096 0.948184 + outer loop + vertex 1.58723 1.48321 2.55818 + vertex 1.591 1.48691 2.55695 + vertex 1.58726 1.48819 2.55821 + endloop + endfacet + facet normal 0.334631 -0.00780611 0.942317 + outer loop + vertex 1.58723 1.48321 2.55818 + vertex 1.58726 1.48819 2.55821 + vertex 1.58356 1.48458 2.55949 + endloop + endfacet + facet normal 0.334028 -0.00960218 0.942514 + outer loop + vertex 1.58353 1.4796 2.55945 + vertex 1.58723 1.48321 2.55818 + vertex 1.58356 1.48458 2.55949 + endloop + endfacet + facet normal 0.333071 -0.00849743 0.942863 + outer loop + vertex 1.58721 1.47824 2.55814 + vertex 1.58723 1.48321 2.55818 + vertex 1.58353 1.4796 2.55945 + endloop + endfacet + facet normal 0.316589 -0.0084886 0.948525 + outer loop + vertex 1.58721 1.47824 2.55814 + vertex 1.59097 1.48193 2.55692 + vertex 1.58723 1.48321 2.55818 + endloop + endfacet + facet normal 0.317033 -0.00705658 0.948388 + outer loop + vertex 1.59097 1.48193 2.55692 + vertex 1.591 1.48691 2.55695 + vertex 1.58723 1.48321 2.55818 + endloop + endfacet + facet normal 0.301807 -0.00618788 0.953349 + outer loop + vertex 1.59858 1.48947 2.55455 + vertex 1.59861 1.49447 2.55457 + vertex 1.5948 1.49068 2.55575 + endloop + endfacet + facet normal 0.303148 -0.00582104 0.952926 + outer loop + vertex 1.59856 1.48447 2.55453 + vertex 1.60237 1.48823 2.55334 + vertex 1.59858 1.48947 2.55455 + endloop + endfacet + facet normal 0.300637 -0.00583891 0.953721 + outer loop + vertex 1.59854 1.47948 2.5545 + vertex 1.59856 1.48447 2.55453 + vertex 1.59476 1.48071 2.5557 + endloop + endfacet + facet normal 0.304657 -0.00702491 0.952436 + outer loop + vertex 1.591 1.48691 2.55695 + vertex 1.59097 1.48193 2.55692 + vertex 1.59477 1.48569 2.55573 + endloop + endfacet + facet normal 0.303157 -0.00644457 0.952919 + outer loop + vertex 1.59476 1.48071 2.5557 + vertex 1.59097 1.47696 2.55688 + vertex 1.59476 1.47574 2.55567 + endloop + endfacet + facet normal 0.313701 -0.00858137 0.949483 + outer loop + vertex 1.59097 1.472 2.55684 + vertex 1.59097 1.47696 2.55688 + vertex 1.5872 1.47326 2.55809 + endloop + endfacet + facet normal 0.302317 -0.012291 0.953128 + outer loop + vertex 1.59097 1.472 2.55684 + vertex 1.59093 1.46699 2.55679 + vertex 1.59475 1.47079 2.55562 + endloop + endfacet + facet normal 0.313229 -0.0164034 0.949536 + outer loop + vertex 1.59086 1.46191 2.55672 + vertex 1.59093 1.46699 2.55679 + vertex 1.58694 1.46298 2.55803 + endloop + endfacet + facet normal 0.312563 -0.0190419 0.949706 + outer loop + vertex 1.58684 1.45772 2.55796 + vertex 1.59086 1.46191 2.55672 + vertex 1.58694 1.46298 2.55803 + endloop + endfacet + facet normal 0.312089 -0.0203816 0.949834 + outer loop + vertex 1.58689 1.45264 2.55784 + vertex 1.59079 1.45686 2.55664 + vertex 1.58684 1.45772 2.55796 + endloop + endfacet + facet normal 0.324905 -0.0198024 0.945539 + outer loop + vertex 1.58697 1.44771 2.5577 + vertex 1.58689 1.45264 2.55784 + vertex 1.58306 1.44842 2.55906 + endloop + endfacet + facet normal 0.311335 -0.0203851 0.950082 + outer loop + vertex 1.59074 1.44745 2.55646 + vertex 1.59072 1.45194 2.55657 + vertex 1.58697 1.44771 2.5577 + endloop + endfacet + facet normal 0.301536 -0.0238163 0.953157 + outer loop + vertex 1.59362 1.44708 2.55554 + vertex 1.59074 1.44745 2.55646 + vertex 1.59134 1.44428 2.55619 + endloop + endfacet + facet normal 0.301843 -0.0240905 0.953053 + outer loop + vertex 1.59362 1.44708 2.55554 + vertex 1.59134 1.44428 2.55619 + vertex 1.59422 1.44387 2.55527 + endloop + endfacet + facet normal 0.298892 -0.0273599 0.953895 + outer loop + vertex 1.5942 1.43932 2.55515 + vertex 1.59796 1.44347 2.55409 + vertex 1.59422 1.44387 2.55527 + endloop + endfacet + facet normal 0.311751 -0.0283016 0.949742 + outer loop + vertex 1.58748 1.44262 2.55741 + vertex 1.58675 1.43698 2.55748 + vertex 1.59069 1.44041 2.55629 + endloop + endfacet + facet normal 0.328374 -0.0343248 0.943924 + outer loop + vertex 1.58647 1.43193 2.5574 + vertex 1.58675 1.43698 2.55748 + vertex 1.58276 1.43326 2.55874 + endloop + endfacet + facet normal 0.327367 -0.0373699 0.944158 + outer loop + vertex 1.58261 1.42829 2.55859 + vertex 1.58647 1.43193 2.5574 + vertex 1.58276 1.43326 2.55874 + endloop + endfacet + facet normal 0.326474 -0.0373506 0.944468 + outer loop + vertex 1.58261 1.42829 2.55859 + vertex 1.58276 1.43326 2.55874 + vertex 1.57891 1.42964 2.55992 + endloop + endfacet + facet normal 0.324799 -0.0423055 0.944837 + outer loop + vertex 1.57876 1.42466 2.55975 + vertex 1.58261 1.42829 2.55859 + vertex 1.57891 1.42964 2.55992 + endloop + endfacet + facet normal 0.322434 -0.0395073 0.945767 + outer loop + vertex 1.58249 1.42335 2.55843 + vertex 1.58261 1.42829 2.55859 + vertex 1.57876 1.42466 2.55975 + endloop + endfacet + facet normal 0.325448 -0.0395414 0.944733 + outer loop + vertex 1.58249 1.42335 2.55843 + vertex 1.58635 1.42702 2.55725 + vertex 1.58261 1.42829 2.55859 + endloop + endfacet + facet normal 0.32647 -0.0363016 0.94451 + outer loop + vertex 1.58635 1.42702 2.55725 + vertex 1.58647 1.43193 2.5574 + vertex 1.58261 1.42829 2.55859 + endloop + endfacet + facet normal 0.301632 -0.0303664 0.952941 + outer loop + vertex 1.59409 1.43444 2.55503 + vertex 1.5942 1.43932 2.55515 + vertex 1.59036 1.43558 2.55624 + endloop + endfacet + facet normal 0.296142 -0.0327127 0.954584 + outer loop + vertex 1.59399 1.4295 2.55489 + vertex 1.59804 1.43346 2.55377 + vertex 1.59409 1.43444 2.55503 + endloop + endfacet + facet normal 0.312382 -0.0360995 0.94927 + outer loop + vertex 1.58647 1.43193 2.5574 + vertex 1.58635 1.42702 2.55725 + vertex 1.59019 1.43068 2.55612 + endloop + endfacet + facet normal 0.323308 -0.0370235 0.945569 + outer loop + vertex 1.58628 1.42211 2.55708 + vertex 1.58635 1.42702 2.55725 + vertex 1.58249 1.42335 2.55843 + endloop + endfacet + facet normal 0.322631 -0.0392461 0.945711 + outer loop + vertex 1.58234 1.41833 2.55827 + vertex 1.58628 1.42211 2.55708 + vertex 1.58249 1.42335 2.55843 + endloop + endfacet + facet normal 0.318143 -0.0391611 0.947234 + outer loop + vertex 1.58234 1.41833 2.55827 + vertex 1.58249 1.42335 2.55843 + vertex 1.57856 1.41962 2.55959 + endloop + endfacet + facet normal 0.317396 -0.041504 0.947384 + outer loop + vertex 1.57823 1.41441 2.55947 + vertex 1.58234 1.41833 2.55827 + vertex 1.57856 1.41962 2.55959 + endloop + endfacet + facet normal 0.319833 -0.0359961 0.94679 + outer loop + vertex 1.58619 1.41715 2.55692 + vertex 1.58628 1.42211 2.55708 + vertex 1.58234 1.41833 2.55827 + endloop + endfacet + facet normal 0.319449 -0.0373322 0.946868 + outer loop + vertex 1.5821 1.41314 2.55815 + vertex 1.58619 1.41715 2.55692 + vertex 1.58234 1.41833 2.55827 + endloop + endfacet + facet normal 0.299127 -0.0344274 0.953592 + outer loop + vertex 1.59388 1.42456 2.55474 + vertex 1.59399 1.4295 2.55489 + vertex 1.59011 1.42578 2.55597 + endloop + endfacet + facet normal 0.294958 -0.0352323 0.95486 + outer loop + vertex 1.59378 1.41963 2.55459 + vertex 1.59766 1.4233 2.55353 + vertex 1.59388 1.42456 2.55474 + endloop + endfacet + facet normal 0.309356 -0.0359208 0.950268 + outer loop + vertex 1.58628 1.42211 2.55708 + vertex 1.58619 1.41715 2.55692 + vertex 1.59004 1.42089 2.55581 + endloop + endfacet + facet normal 0.317338 -0.0349342 0.947669 + outer loop + vertex 1.58607 1.41214 2.55678 + vertex 1.58619 1.41715 2.55692 + vertex 1.5821 1.41314 2.55815 + endloop + endfacet + facet normal 0.299892 -0.0362702 0.953283 + outer loop + vertex 1.59365 1.41466 2.55444 + vertex 1.59378 1.41963 2.55459 + vertex 1.58996 1.41595 2.55565 + endloop + endfacet + facet normal 0.296216 -0.0386127 0.95434 + outer loop + vertex 1.59335 1.40953 2.55433 + vertex 1.59738 1.41333 2.55323 + vertex 1.59365 1.41466 2.55444 + endloop + endfacet + facet normal 0.309837 -0.0365492 0.950087 + outer loop + vertex 1.58607 1.41214 2.55678 + vertex 1.58596 1.40723 2.55663 + vertex 1.58979 1.411 2.55552 + endloop + endfacet + facet normal 0.314162 -0.0366032 0.948663 + outer loop + vertex 1.58596 1.40723 2.55663 + vertex 1.58607 1.41214 2.55678 + vertex 1.58196 1.40793 2.55798 + endloop + endfacet + facet normal 0.312838 -0.0443544 0.94877 + outer loop + vertex 1.58204 1.40291 2.55772 + vertex 1.58596 1.40723 2.55663 + vertex 1.58196 1.40793 2.55798 + endloop + endfacet + facet normal 0.30668 -0.0436628 0.950811 + outer loop + vertex 1.59254 1.40382 2.55433 + vertex 1.59335 1.40953 2.55433 + vertex 1.58943 1.40615 2.55544 + endloop + endfacet + facet normal 0.316967 -0.044489 0.947393 + outer loop + vertex 1.58873 1.40231 2.55549 + vertex 1.58646 1.3996 2.55613 + vertex 1.58925 1.39912 2.55517 + endloop + endfacet + facet normal 0.30063 -0.0454621 0.952657 + outer loop + vertex 1.59693 1.40293 2.5529 + vertex 1.5971 1.40813 2.55309 + vertex 1.59254 1.40382 2.55433 + endloop + endfacet + facet normal 0.295273 -0.0482701 0.954193 + outer loop + vertex 1.59698 1.39796 2.55264 + vertex 1.60084 1.40212 2.55165 + vertex 1.59693 1.40293 2.5529 + endloop + endfacet + facet normal 0.299439 -0.0490402 0.952854 + outer loop + vertex 1.5974 1.39286 2.55224 + vertex 1.59698 1.39796 2.55264 + vertex 1.59299 1.39366 2.55367 + endloop + endfacet + facet normal 0.290962 -0.051764 0.955333 + outer loop + vertex 1.5974 1.39286 2.55224 + vertex 1.59654 1.38715 2.55219 + vertex 1.60059 1.39068 2.55115 + endloop + endfacet + facet normal 0.299709 -0.055368 0.952423 + outer loop + vertex 1.59615 1.382 2.55201 + vertex 1.59654 1.38715 2.55219 + vertex 1.59227 1.3831 2.5533 + endloop + endfacet + facet normal 0.299314 -0.0568012 0.952462 + outer loop + vertex 1.59205 1.37788 2.55306 + vertex 1.59615 1.382 2.55201 + vertex 1.59227 1.3831 2.5533 + endloop + endfacet + facet normal 0.299181 -0.0588036 0.952383 + outer loop + vertex 1.59211 1.3729 2.55273 + vertex 1.59595 1.37707 2.55178 + vertex 1.59205 1.37788 2.55306 + endloop + endfacet + facet normal 0.298445 -0.0618715 0.952419 + outer loop + vertex 1.59591 1.3726 2.55152 + vertex 1.59211 1.3729 2.55273 + vertex 1.59251 1.36778 2.55227 + endloop + endfacet + facet normal 0.309101 -0.0680184 0.948594 + outer loop + vertex 1.59158 1.36206 2.55217 + vertex 1.59251 1.36778 2.55227 + vertex 1.58764 1.36324 2.55354 + endloop + endfacet + facet normal 0.30805 -0.0716348 0.948669 + outer loop + vertex 1.58719 1.35789 2.55328 + vertex 1.59158 1.36206 2.55217 + vertex 1.58764 1.36324 2.55354 + endloop + endfacet + facet normal 0.307191 -0.0699487 0.949074 + outer loop + vertex 1.58713 1.35283 2.55292 + vertex 1.59114 1.35703 2.55194 + vertex 1.58719 1.35789 2.55328 + endloop + endfacet + facet normal 0.307615 -0.066227 0.949203 + outer loop + vertex 1.58754 1.3477 2.55243 + vertex 1.58713 1.35283 2.55292 + vertex 1.58298 1.34837 2.55396 + endloop + endfacet + facet normal 0.306707 -0.0720769 0.949071 + outer loop + vertex 1.58265 1.34309 2.55366 + vertex 1.58754 1.3477 2.55243 + vertex 1.58298 1.34837 2.55396 + endloop + endfacet + facet normal 0.295158 -0.079453 0.952139 + outer loop + vertex 1.58226 1.33782 2.55334 + vertex 1.5867 1.34204 2.55232 + vertex 1.58265 1.34309 2.55366 + endloop + endfacet + facet normal 0.280432 -0.0787347 0.956639 + outer loop + vertex 1.58218 1.33284 2.55296 + vertex 1.58636 1.33707 2.55208 + vertex 1.58226 1.33782 2.55334 + endloop + endfacet + facet normal 0.269679 -0.0784295 0.959751 + outer loop + vertex 1.58215 1.32804 2.55257 + vertex 1.58613 1.33234 2.55181 + vertex 1.58218 1.33284 2.55296 + endloop + endfacet + facet normal 0.263608 -0.0858334 0.960804 + outer loop + vertex 1.58597 1.32802 2.55152 + vertex 1.58215 1.32804 2.55257 + vertex 1.58242 1.32308 2.55206 + endloop + endfacet + facet normal 0.259945 -0.0952932 0.96091 + outer loop + vertex 1.58242 1.32308 2.55206 + vertex 1.58138 1.3175 2.55178 + vertex 1.58548 1.32108 2.55103 + endloop + endfacet + facet normal 0.257129 -0.0918329 0.962004 + outer loop + vertex 1.58548 1.32108 2.55103 + vertex 1.58138 1.3175 2.55178 + vertex 1.58468 1.31635 2.55079 + endloop + endfacet + facet normal 0.255759 -0.0957365 0.961989 + outer loop + vertex 1.58138 1.3175 2.55178 + vertex 1.58098 1.3129 2.55143 + vertex 1.58468 1.31635 2.55079 + endloop + endfacet + facet normal 0.3012 -0.10273 0.948011 + outer loop + vertex 1.58373 1.31243 2.55068 + vertex 1.58397 1.30895 2.55023 + vertex 1.58772 1.31395 2.54958 + endloop + endfacet + facet normal 0.300611 -0.102259 0.948249 + outer loop + vertex 1.58772 1.31395 2.54958 + vertex 1.58397 1.30895 2.55023 + vertex 1.58789 1.3084 2.54893 + endloop + endfacet + facet normal 0.306458 -0.101867 0.946418 + outer loop + vertex 1.58789 1.3084 2.54893 + vertex 1.59231 1.31311 2.548 + vertex 1.58772 1.31395 2.54958 + endloop + endfacet + facet normal 0.30582 -0.101212 0.946694 + outer loop + vertex 1.59261 1.30783 2.54734 + vertex 1.59231 1.31311 2.548 + vertex 1.58789 1.3084 2.54893 + endloop + endfacet + facet normal 0.305465 -0.10374 0.946535 + outer loop + vertex 1.5876 1.30299 2.54843 + vertex 1.59261 1.30783 2.54734 + vertex 1.58789 1.3084 2.54893 + endloop + endfacet + facet normal 0.285959 -0.103283 0.952659 + outer loop + vertex 1.5876 1.30299 2.54843 + vertex 1.58789 1.3084 2.54893 + vertex 1.58286 1.3034 2.5499 + endloop + endfacet + facet normal 0.283737 -0.12332 0.950939 + outer loop + vertex 1.58284 1.29806 2.54921 + vertex 1.5876 1.30299 2.54843 + vertex 1.58286 1.3034 2.5499 + endloop + endfacet + facet normal 0.216653 -0.125281 0.968177 + outer loop + vertex 1.58286 1.3034 2.5499 + vertex 1.57801 1.29811 2.5503 + vertex 1.58284 1.29806 2.54921 + endloop + endfacet + facet normal 0.215529 -0.152912 0.964451 + outer loop + vertex 1.57778 1.29311 2.54956 + vertex 1.58284 1.29806 2.54921 + vertex 1.57801 1.29811 2.5503 + endloop + endfacet + facet normal 0.182613 -0.11845 0.976024 + outer loop + vertex 1.58274 1.29303 2.54862 + vertex 1.58284 1.29806 2.54921 + vertex 1.57778 1.29311 2.54956 + endloop + endfacet + facet normal 0.182294 -0.126508 0.975072 + outer loop + vertex 1.57769 1.28805 2.54891 + vertex 1.58274 1.29303 2.54862 + vertex 1.57778 1.29311 2.54956 + endloop + endfacet + facet normal 0.166822 -0.110536 0.979772 + outer loop + vertex 1.58248 1.28797 2.54809 + vertex 1.58274 1.29303 2.54862 + vertex 1.57769 1.28805 2.54891 + endloop + endfacet + facet normal 0.166362 -0.123437 0.978308 + outer loop + vertex 1.57753 1.28302 2.54831 + vertex 1.58248 1.28797 2.54809 + vertex 1.57769 1.28805 2.54891 + endloop + endfacet + facet normal 0.153928 -0.110833 0.981846 + outer loop + vertex 1.58216 1.28295 2.54757 + vertex 1.58248 1.28797 2.54809 + vertex 1.57753 1.28302 2.54831 + endloop + endfacet + facet normal 0.153494 -0.123658 0.980382 + outer loop + vertex 1.57752 1.27799 2.54767 + vertex 1.58216 1.28295 2.54757 + vertex 1.57753 1.28302 2.54831 + endloop + endfacet + facet normal 0.144011 -0.114739 0.982902 + outer loop + vertex 1.58247 1.27789 2.54694 + vertex 1.58216 1.28295 2.54757 + vertex 1.57752 1.27799 2.54767 + endloop + endfacet + facet normal 0.144099 -0.11231 0.983169 + outer loop + vertex 1.57774 1.273 2.54707 + vertex 1.58247 1.27789 2.54694 + vertex 1.57752 1.27799 2.54767 + endloop + endfacet + facet normal 0.116254 -0.0851818 0.98956 + outer loop + vertex 1.58172 1.27252 2.54656 + vertex 1.58247 1.27789 2.54694 + vertex 1.57774 1.273 2.54707 + endloop + endfacet + facet normal 0.115947 -0.0875421 0.98939 + outer loop + vertex 1.57844 1.26927 2.54666 + vertex 1.58172 1.27252 2.54656 + vertex 1.57774 1.273 2.54707 + endloop + endfacet + facet normal 0.113012 -0.0845661 0.989988 + outer loop + vertex 1.58126 1.26832 2.54626 + vertex 1.58172 1.27252 2.54656 + vertex 1.57844 1.26927 2.54666 + endloop + endfacet + facet normal 0.102218 -0.11568 0.988013 + outer loop + vertex 1.58126 1.26832 2.54626 + vertex 1.57844 1.26927 2.54666 + vertex 1.57779 1.26545 2.54628 + endloop + endfacet + facet normal 0.0964115 -0.108634 0.989395 + outer loop + vertex 1.58099 1.26523 2.54594 + vertex 1.58126 1.26832 2.54626 + vertex 1.57779 1.26545 2.54628 + endloop + endfacet + facet normal 0.0941495 -0.136614 0.98614 + outer loop + vertex 1.58099 1.26523 2.54594 + vertex 1.57779 1.26545 2.54628 + vertex 1.57907 1.26282 2.54579 + endloop + endfacet + facet normal 0.189347 -0.210622 0.959055 + outer loop + vertex 1.58277 1.26331 2.54517 + vertex 1.58099 1.26523 2.54594 + vertex 1.57907 1.26282 2.54579 + endloop + endfacet + facet normal 0.191997 -0.240483 0.951475 + outer loop + vertex 1.57907 1.26282 2.54579 + vertex 1.57692 1.2587 2.54518 + vertex 1.58277 1.26331 2.54517 + endloop + endfacet + facet normal 0.129269 -0.160865 0.978474 + outer loop + vertex 1.58277 1.26331 2.54517 + vertex 1.57692 1.2587 2.54518 + vertex 1.58264 1.2582 2.54435 + endloop + endfacet + facet normal 0.0765859 -0.184619 0.979822 + outer loop + vertex 1.57907 1.26282 2.54579 + vertex 1.57627 1.26219 2.54589 + vertex 1.57692 1.2587 2.54518 + endloop + endfacet + facet normal 0.0687911 -0.148973 0.986445 + outer loop + vertex 1.57907 1.26282 2.54579 + vertex 1.57779 1.26545 2.54628 + vertex 1.57627 1.26219 2.54589 + endloop + endfacet + facet normal 0.221355 -0.108245 0.969167 + outer loop + vertex 1.58609 1.28286 2.54667 + vertex 1.58216 1.28295 2.54757 + vertex 1.58247 1.27789 2.54694 + endloop + endfacet + facet normal 0.232625 -0.114148 0.965845 + outer loop + vertex 1.58216 1.28295 2.54757 + vertex 1.58654 1.28738 2.54704 + vertex 1.58248 1.28797 2.54809 + endloop + endfacet + facet normal 0.251255 -0.11305 0.961296 + outer loop + vertex 1.58248 1.28797 2.54809 + vertex 1.5876 1.29286 2.54733 + vertex 1.58274 1.29303 2.54862 + endloop + endfacet + facet normal 0.251656 -0.106458 0.961944 + outer loop + vertex 1.5876 1.29286 2.54733 + vertex 1.58737 1.29788 2.54794 + vertex 1.58274 1.29303 2.54862 + endloop + endfacet + facet normal 0.297335 -0.10277 0.949226 + outer loop + vertex 1.59122 1.29772 2.54672 + vertex 1.58737 1.29788 2.54794 + vertex 1.5876 1.29286 2.54733 + endloop + endfacet + facet normal 0.262889 -0.117762 0.957612 + outer loop + vertex 1.58274 1.29303 2.54862 + vertex 1.58737 1.29788 2.54794 + vertex 1.58284 1.29806 2.54921 + endloop + endfacet + facet normal 0.278044 -0.183527 0.942873 + outer loop + vertex 1.57893 1.30193 2.55077 + vertex 1.57801 1.29811 2.5503 + vertex 1.58286 1.3034 2.5499 + endloop + endfacet + facet normal 0.257921 -0.120357 0.95864 + outer loop + vertex 1.57893 1.30193 2.55077 + vertex 1.58286 1.3034 2.5499 + vertex 1.58027 1.30579 2.55089 + endloop + endfacet + facet normal 0.169631 -0.0904586 0.981347 + outer loop + vertex 1.58027 1.30579 2.55089 + vertex 1.57675 1.30324 2.55127 + vertex 1.57893 1.30193 2.55077 + endloop + endfacet + facet normal 0.155435 -0.113918 0.981256 + outer loop + vertex 1.57893 1.30193 2.55077 + vertex 1.57675 1.30324 2.55127 + vertex 1.57634 1.30004 2.55096 + endloop + endfacet + facet normal 0.172173 -0.0940896 0.980563 + outer loop + vertex 1.57762 1.30809 2.55158 + vertex 1.57675 1.30324 2.55127 + vertex 1.58027 1.30579 2.55089 + endloop + endfacet + facet normal 0.266281 -0.110864 0.957499 + outer loop + vertex 1.58286 1.3034 2.5499 + vertex 1.58397 1.30895 2.55023 + vertex 1.58027 1.30579 2.55089 + endloop + endfacet + facet normal 0.192091 -0.16571 0.967285 + outer loop + vertex 1.57893 1.30193 2.55077 + vertex 1.57634 1.30004 2.55096 + vertex 1.57801 1.29811 2.5503 + endloop + endfacet + facet normal 0.263893 -0.102869 0.959051 + outer loop + vertex 1.58737 1.29788 2.54794 + vertex 1.5876 1.30299 2.54843 + vertex 1.58284 1.29806 2.54921 + endloop + endfacet + facet normal 0.301636 -0.10356 0.947782 + outer loop + vertex 1.58737 1.29788 2.54794 + vertex 1.59162 1.30225 2.54707 + vertex 1.5876 1.30299 2.54843 + endloop + endfacet + facet normal 0.299787 -0.101784 0.948561 + outer loop + vertex 1.59622 1.31263 2.54672 + vertex 1.59231 1.31311 2.548 + vertex 1.59261 1.30783 2.54734 + endloop + endfacet + facet normal 0.298269 -0.116691 0.947322 + outer loop + vertex 1.58286 1.3034 2.5499 + vertex 1.58789 1.3084 2.54893 + vertex 1.58397 1.30895 2.55023 + endloop + endfacet + facet normal 0.304548 -0.0991739 0.94732 + outer loop + vertex 1.58468 1.31635 2.55079 + vertex 1.58877 1.31968 2.54983 + vertex 1.58548 1.32108 2.55103 + endloop + endfacet + facet normal 0.307252 -0.0978777 0.946581 + outer loop + vertex 1.59231 1.31311 2.548 + vertex 1.59266 1.31842 2.54844 + vertex 1.58772 1.31395 2.54958 + endloop + endfacet + facet normal 0.296182 -0.0974524 0.950147 + outer loop + vertex 1.59231 1.31311 2.548 + vertex 1.59658 1.31723 2.54709 + vertex 1.59266 1.31842 2.54844 + endloop + endfacet + facet normal 0.310077 -0.0920724 0.946243 + outer loop + vertex 1.58877 1.31968 2.54983 + vertex 1.59297 1.32371 2.54884 + vertex 1.58915 1.32437 2.55016 + endloop + endfacet + facet normal 0.297256 -0.0939189 0.950167 + outer loop + vertex 1.59658 1.31723 2.54709 + vertex 1.59754 1.32281 2.54734 + vertex 1.59266 1.31842 2.54844 + endloop + endfacet + facet normal 0.297221 -0.0832363 0.951174 + outer loop + vertex 1.59297 1.32371 2.54884 + vertex 1.59718 1.32807 2.54791 + vertex 1.59262 1.32901 2.54941 + endloop + endfacet + facet normal 0.283853 -0.0770162 0.95577 + outer loop + vertex 1.60108 1.32754 2.54671 + vertex 1.60141 1.33221 2.54699 + vertex 1.59718 1.32807 2.54791 + endloop + endfacet + facet normal 0.279109 -0.081177 0.956822 + outer loop + vertex 1.60394 1.32706 2.54583 + vertex 1.60108 1.32754 2.54671 + vertex 1.60153 1.32434 2.5463 + endloop + endfacet + facet normal 0.283208 -0.0850655 0.955279 + outer loop + vertex 1.60394 1.32706 2.54583 + vertex 1.60153 1.32434 2.5463 + vertex 1.60435 1.32389 2.54543 + endloop + endfacet + facet normal 0.282946 -0.091667 0.954745 + outer loop + vertex 1.59754 1.32281 2.54734 + vertex 1.59658 1.31723 2.54709 + vertex 1.60066 1.32055 2.5462 + endloop + endfacet + facet normal 0.299819 -0.101562 0.948575 + outer loop + vertex 1.59622 1.31263 2.54672 + vertex 1.59658 1.31723 2.54709 + vertex 1.59231 1.31311 2.548 + endloop + endfacet + facet normal 0.287246 -0.103031 0.9523 + outer loop + vertex 1.60296 1.31373 2.54479 + vertex 1.60397 1.31929 2.54509 + vertex 1.59992 1.31591 2.54595 + endloop + endfacet + facet normal 0.285714 -0.106058 0.952428 + outer loop + vertex 1.60296 1.31373 2.54479 + vertex 1.59938 1.30899 2.54534 + vertex 1.60312 1.30855 2.54417 + endloop + endfacet + facet normal 0.28598 -0.104128 0.952561 + outer loop + vertex 1.59893 1.30439 2.54497 + vertex 1.60312 1.30855 2.54417 + vertex 1.59938 1.30899 2.54534 + endloop + endfacet + facet normal 0.292027 -0.106603 0.95045 + outer loop + vertex 1.59903 1.31214 2.5458 + vertex 1.59622 1.31263 2.54672 + vertex 1.59661 1.30948 2.54624 + endloop + endfacet + facet normal 0.303396 -0.104686 0.947096 + outer loop + vertex 1.59661 1.30948 2.54624 + vertex 1.59622 1.31263 2.54672 + vertex 1.59261 1.30783 2.54734 + endloop + endfacet + facet normal 0.302316 -0.10017 0.94793 + outer loop + vertex 1.59162 1.30225 2.54707 + vertex 1.59261 1.30783 2.54734 + vertex 1.5876 1.30299 2.54843 + endloop + endfacet + facet normal 0.297576 -0.0992653 0.949524 + outer loop + vertex 1.59122 1.29772 2.54672 + vertex 1.59162 1.30225 2.54707 + vertex 1.58737 1.29788 2.54794 + endloop + endfacet + facet normal 0.296006 -0.100759 0.949857 + outer loop + vertex 1.59489 1.30105 2.54588 + vertex 1.59893 1.30439 2.54497 + vertex 1.59568 1.30569 2.54612 + endloop + endfacet + facet normal 0.285453 -0.103555 0.952782 + outer loop + vertex 1.60283 1.30339 2.54369 + vertex 1.60312 1.30855 2.54417 + vertex 1.59893 1.30439 2.54497 + endloop + endfacet + facet normal 0.281841 -0.101156 0.954114 + outer loop + vertex 1.60247 1.2981 2.54324 + vertex 1.60747 1.30275 2.54226 + vertex 1.60283 1.30339 2.54369 + endloop + endfacet + facet normal 0.287928 -0.101154 0.952295 + outer loop + vertex 1.6022 1.29298 2.54278 + vertex 1.60247 1.2981 2.54324 + vertex 1.59806 1.29362 2.5441 + endloop + endfacet + facet normal 0.299134 -0.0996611 0.948992 + outer loop + vertex 1.59398 1.29728 2.54577 + vertex 1.59433 1.2941 2.54533 + vertex 1.59789 1.29882 2.5447 + endloop + endfacet + facet normal 0.309321 -0.0981173 0.945882 + outer loop + vertex 1.59398 1.29728 2.54577 + vertex 1.59159 1.29461 2.54627 + vertex 1.59433 1.2941 2.54533 + endloop + endfacet + facet normal 0.295015 -0.100925 0.950148 + outer loop + vertex 1.59159 1.29461 2.54627 + vertex 1.59122 1.29772 2.54672 + vertex 1.5876 1.29286 2.54733 + endloop + endfacet + facet normal 0.23561 -0.095748 0.96712 + outer loop + vertex 1.58654 1.28738 2.54704 + vertex 1.5876 1.29286 2.54733 + vertex 1.58248 1.28797 2.54809 + endloop + endfacet + facet normal 0.221607 -0.102802 0.969702 + outer loop + vertex 1.58609 1.28286 2.54667 + vertex 1.58654 1.28738 2.54704 + vertex 1.58216 1.28295 2.54757 + endloop + endfacet + facet normal 0.307246 -0.105056 0.945813 + outer loop + vertex 1.58983 1.28621 2.54593 + vertex 1.59389 1.28952 2.54498 + vertex 1.59066 1.29083 2.54617 + endloop + endfacet + facet normal 0.300973 -0.102118 0.948149 + outer loop + vertex 1.59778 1.2885 2.54363 + vertex 1.59806 1.29362 2.5441 + vertex 1.59389 1.28952 2.54498 + endloop + endfacet + facet normal 0.288114 -0.103952 0.951937 + outer loop + vertex 1.59743 1.28326 2.54317 + vertex 1.60241 1.28789 2.54217 + vertex 1.59778 1.2885 2.54363 + endloop + endfacet + facet normal 0.300825 -0.104261 0.947963 + outer loop + vertex 1.59718 1.27815 2.54269 + vertex 1.59743 1.28326 2.54317 + vertex 1.59303 1.27874 2.54407 + endloop + endfacet + facet normal 0.306158 -0.106896 0.94596 + outer loop + vertex 1.58888 1.28244 2.54581 + vertex 1.58924 1.2792 2.54533 + vertex 1.59284 1.28397 2.54471 + endloop + endfacet + facet normal 0.285263 -0.11012 0.952102 + outer loop + vertex 1.58888 1.28244 2.54581 + vertex 1.58645 1.2797 2.54623 + vertex 1.58924 1.2792 2.54533 + endloop + endfacet + facet normal 0.223266 -0.109668 0.968569 + outer loop + vertex 1.58645 1.2797 2.54623 + vertex 1.58609 1.28286 2.54667 + vertex 1.58247 1.27789 2.54694 + endloop + endfacet + facet normal 0.278194 -0.100574 0.955245 + outer loop + vertex 1.58478 1.27108 2.54577 + vertex 1.58883 1.27447 2.54495 + vertex 1.58557 1.27582 2.54604 + endloop + endfacet + facet normal 0.302668 -0.101436 0.947683 + outer loop + vertex 1.59278 1.27353 2.54359 + vertex 1.59303 1.27874 2.54407 + vertex 1.58883 1.27447 2.54495 + endloop + endfacet + facet normal 0.303158 -0.105349 0.947099 + outer loop + vertex 1.59251 1.26819 2.54308 + vertex 1.59737 1.27307 2.54207 + vertex 1.59278 1.27353 2.54359 + endloop + endfacet + facet normal 0.280945 -0.112362 0.953124 + outer loop + vertex 1.59269 1.26288 2.5424 + vertex 1.59251 1.26819 2.54308 + vertex 1.58774 1.26318 2.5439 + endloop + endfacet + facet normal 0.296341 -0.179377 0.938086 + outer loop + vertex 1.58356 1.26718 2.54566 + vertex 1.58277 1.26331 2.54517 + vertex 1.58763 1.26864 2.54465 + endloop + endfacet + facet normal 0.279764 -0.125478 0.951834 + outer loop + vertex 1.58754 1.25799 2.54327 + vertex 1.59269 1.26288 2.5424 + vertex 1.58774 1.26318 2.5439 + endloop + endfacet + facet normal 0.260849 -0.126481 0.957058 + outer loop + vertex 1.58723 1.25297 2.54269 + vertex 1.59163 1.25737 2.54208 + vertex 1.58754 1.25799 2.54327 + endloop + endfacet + facet normal 0.251397 -0.125314 0.959738 + outer loop + vertex 1.59115 1.2529 2.54166 + vertex 1.58723 1.25297 2.54269 + vertex 1.58742 1.24799 2.54199 + endloop + endfacet + facet normal 0.243111 -0.118205 0.962769 + outer loop + vertex 1.58742 1.24799 2.54199 + vertex 1.5865 1.24281 2.54159 + vertex 1.59025 1.24597 2.54103 + endloop + endfacet + facet normal 0.227299 -0.104113 0.968244 + outer loop + vertex 1.58911 1.24215 2.54091 + vertex 1.5865 1.24281 2.54159 + vertex 1.58667 1.23954 2.5412 + endloop + endfacet + facet normal 0.233473 -0.228497 0.945135 + outer loop + vertex 1.58377 1.23258 2.54072 + vertex 1.5824 1.22832 2.54002 + vertex 1.5878 1.23358 2.53996 + endloop + endfacet + facet normal 0.173032 -0.166196 0.970793 + outer loop + vertex 1.5878 1.23358 2.53996 + vertex 1.5824 1.22832 2.54002 + vertex 1.58761 1.22821 2.53908 + endloop + endfacet + facet normal 0.172609 -0.174374 0.969433 + outer loop + vertex 1.58252 1.22305 2.53905 + vertex 1.58761 1.22821 2.53908 + vertex 1.5824 1.22832 2.54002 + endloop + endfacet + facet normal 0.157266 -0.159275 0.974628 + outer loop + vertex 1.58749 1.22309 2.53826 + vertex 1.58761 1.22821 2.53908 + vertex 1.58252 1.22305 2.53905 + endloop + endfacet + facet normal 0.15721 -0.162327 0.974133 + outer loop + vertex 1.58262 1.21802 2.5382 + vertex 1.58749 1.22309 2.53826 + vertex 1.58252 1.22305 2.53905 + endloop + endfacet + facet normal 0.142129 -0.14788 0.978739 + outer loop + vertex 1.58741 1.21806 2.53751 + vertex 1.58749 1.22309 2.53826 + vertex 1.58262 1.21802 2.5382 + endloop + endfacet + facet normal 0.142117 -0.148774 0.978606 + outer loop + vertex 1.58314 1.21326 2.5374 + vertex 1.58741 1.21806 2.53751 + vertex 1.58262 1.21802 2.5382 + endloop + endfacet + facet normal 0.248915 -0.1451 0.957595 + outer loop + vertex 1.58919 1.23884 2.54044 + vertex 1.58667 1.23954 2.5412 + vertex 1.58553 1.23606 2.54097 + endloop + endfacet + facet normal 0.289596 -0.125042 0.948946 + outer loop + vertex 1.593 1.24378 2.53992 + vertex 1.58919 1.23884 2.54044 + vertex 1.59298 1.23848 2.53923 + endloop + endfacet + facet normal 0.293694 -0.136468 0.946108 + outer loop + vertex 1.59267 1.23328 2.53858 + vertex 1.59743 1.23828 2.53782 + vertex 1.59298 1.23848 2.53923 + endloop + endfacet + facet normal 0.286183 -0.143195 0.947415 + outer loop + vertex 1.59238 1.22815 2.53789 + vertex 1.59745 1.23313 2.53711 + vertex 1.59267 1.23328 2.53858 + endloop + endfacet + facet normal 0.274976 -0.143773 0.950641 + outer loop + vertex 1.59637 1.22799 2.53671 + vertex 1.59238 1.22815 2.53789 + vertex 1.5924 1.22305 2.53711 + endloop + endfacet + facet normal 0.266591 -0.138239 0.953844 + outer loop + vertex 1.5924 1.22305 2.53711 + vertex 1.59134 1.21789 2.53666 + vertex 1.59521 1.22104 2.53604 + endloop + endfacet + facet normal 0.257238 -0.125402 0.958177 + outer loop + vertex 1.59399 1.21727 2.53587 + vertex 1.59134 1.21789 2.53666 + vertex 1.59144 1.21459 2.5362 + endloop + endfacet + facet normal 0.266727 -0.14279 0.953136 + outer loop + vertex 1.59404 1.2139 2.53537 + vertex 1.59144 1.21459 2.5362 + vertex 1.59023 1.21084 2.53598 + endloop + endfacet + facet normal 0.290193 -0.13509 0.947385 + outer loop + vertex 1.59796 1.21886 2.53488 + vertex 1.59404 1.2139 2.53537 + vertex 1.59791 1.21355 2.53414 + endloop + endfacet + facet normal 0.293964 -0.140338 0.945458 + outer loop + vertex 1.59761 1.20835 2.53346 + vertex 1.60234 1.21336 2.53273 + vertex 1.59791 1.21355 2.53414 + endloop + endfacet + facet normal 0.258744 -0.148428 0.954474 + outer loop + vertex 1.59736 1.20329 2.53274 + vertex 1.59761 1.20835 2.53346 + vertex 1.59267 1.20325 2.534 + endloop + endfacet + facet normal 0.280231 -0.224856 0.933226 + outer loop + vertex 1.58877 1.2071 2.53576 + vertex 1.58779 1.2033 2.53514 + vertex 1.59276 1.20851 2.53491 + endloop + endfacet + facet normal 0.258066 -0.168988 0.951233 + outer loop + vertex 1.59251 1.19821 2.53315 + vertex 1.59736 1.20329 2.53274 + vertex 1.59267 1.20325 2.534 + endloop + endfacet + facet normal 0.245339 -0.15925 0.956268 + outer loop + vertex 1.59228 1.19324 2.53238 + vertex 1.59731 1.19828 2.53193 + vertex 1.59251 1.19821 2.53315 + endloop + endfacet + facet normal 0.227051 -0.140335 0.963719 + outer loop + vertex 1.59611 1.19319 2.53148 + vertex 1.59731 1.19828 2.53193 + vertex 1.59228 1.19324 2.53238 + endloop + endfacet + facet normal 0.227164 -0.137745 0.964066 + outer loop + vertex 1.59611 1.19319 2.53148 + vertex 1.59228 1.19324 2.53238 + vertex 1.59241 1.18851 2.53168 + endloop + endfacet + facet normal 0.216616 -0.112933 0.969703 + outer loop + vertex 1.59595 1.18998 2.53106 + vertex 1.59241 1.18851 2.53168 + vertex 1.59457 1.18707 2.53103 + endloop + endfacet + facet normal 0.225469 -0.136381 0.964658 + outer loop + vertex 1.59595 1.18998 2.53106 + vertex 1.59611 1.19319 2.53148 + vertex 1.59241 1.18851 2.53168 + endloop + endfacet + facet normal 0.280289 -0.151551 0.947877 + outer loop + vertex 1.59731 1.19828 2.53193 + vertex 1.59611 1.19319 2.53148 + vertex 1.6 1.1963 2.53082 + endloop + endfacet + facet normal 0.292457 -0.14139 0.945768 + outer loop + vertex 1.59857 1.19245 2.53066 + vertex 1.59812 1.18848 2.5302 + vertex 1.60265 1.19393 2.52962 + endloop + endfacet + facet normal 0.29771 -0.15461 0.942053 + outer loop + vertex 1.60392 1.19935 2.53008 + vertex 1.60131 1.20005 2.53102 + vertex 1.6 1.1963 2.53082 + endloop + endfacet + facet normal 0.293549 -0.150827 0.94397 + outer loop + vertex 1.60784 1.20409 2.52962 + vertex 1.60392 1.19935 2.53008 + vertex 1.60785 1.19878 2.52877 + endloop + endfacet + facet normal 0.284867 -0.15126 0.946557 + outer loop + vertex 1.60785 1.19878 2.52877 + vertex 1.61257 1.2036 2.52812 + vertex 1.60784 1.20409 2.52962 + endloop + endfacet + facet normal 0.278068 -0.147513 0.949167 + outer loop + vertex 1.61257 1.2036 2.52812 + vertex 1.61706 1.20826 2.52753 + vertex 1.61274 1.20871 2.52886 + endloop + endfacet + facet normal 0.276309 -0.143356 0.950317 + outer loop + vertex 1.62081 1.20804 2.5264 + vertex 1.6214 1.21244 2.5269 + vertex 1.61706 1.20826 2.52753 + endloop + endfacet + facet normal 0.276627 -0.146518 0.949742 + outer loop + vertex 1.62341 1.20741 2.52555 + vertex 1.62081 1.20804 2.5264 + vertex 1.62085 1.20505 2.52593 + endloop + endfacet + facet normal 0.279466 -0.149811 0.948396 + outer loop + vertex 1.62341 1.20741 2.52555 + vertex 1.62085 1.20505 2.52593 + vertex 1.62304 1.20357 2.52505 + endloop + endfacet + facet normal 0.276688 -0.153075 0.948689 + outer loop + vertex 1.62304 1.20357 2.52505 + vertex 1.61928 1.19902 2.52541 + vertex 1.62298 1.19859 2.52427 + endloop + endfacet + facet normal 0.274478 -0.15275 0.949384 + outer loop + vertex 1.61949 1.20227 2.52589 + vertex 1.61723 1.20364 2.52676 + vertex 1.61684 1.19985 2.52626 + endloop + endfacet + facet normal 0.277973 -0.152978 0.94833 + outer loop + vertex 1.61684 1.19985 2.52626 + vertex 1.61723 1.20364 2.52676 + vertex 1.61269 1.1983 2.52723 + endloop + endfacet + facet normal 0.29243 -0.159189 0.942944 + outer loop + vertex 1.6114 1.19294 2.52673 + vertex 1.61269 1.1983 2.52723 + vertex 1.60745 1.19342 2.52803 + endloop + endfacet + facet normal 0.275463 -0.156113 0.948551 + outer loop + vertex 1.61798 1.1938 2.52493 + vertex 1.61928 1.19902 2.52541 + vertex 1.61537 1.19601 2.52606 + endloop + endfacet + facet normal 0.271603 -0.151676 0.950382 + outer loop + vertex 1.61798 1.1938 2.52493 + vertex 1.61401 1.18898 2.5253 + vertex 1.61784 1.18858 2.52414 + endloop + endfacet + facet normal 0.272947 -0.142139 0.951471 + outer loop + vertex 1.61292 1.18388 2.52485 + vertex 1.61784 1.18858 2.52414 + vertex 1.61401 1.18898 2.5253 + endloop + endfacet + facet normal 0.28449 -0.157407 0.945668 + outer loop + vertex 1.61401 1.19225 2.52582 + vertex 1.6114 1.19294 2.52673 + vertex 1.6114 1.18965 2.52618 + endloop + endfacet + facet normal 0.300799 -0.15659 0.940744 + outer loop + vertex 1.6114 1.18965 2.52618 + vertex 1.6114 1.19294 2.52673 + vertex 1.60743 1.18812 2.52719 + endloop + endfacet + facet normal 0.308609 -0.144001 0.940226 + outer loop + vertex 1.60636 1.18298 2.52675 + vertex 1.60743 1.18812 2.52719 + vertex 1.60249 1.18327 2.52807 + endloop + endfacet + facet normal 0.27991 -0.143434 0.949251 + outer loop + vertex 1.61292 1.18388 2.52485 + vertex 1.61401 1.18898 2.5253 + vertex 1.61017 1.186 2.52598 + endloop + endfacet + facet normal 0.274039 -0.143359 0.950974 + outer loop + vertex 1.61756 1.18345 2.52345 + vertex 1.61784 1.18858 2.52414 + vertex 1.61292 1.18388 2.52485 + endloop + endfacet + facet normal 0.296334 -0.115534 0.948071 + outer loop + vertex 1.61245 1.1685 2.52302 + vertex 1.61274 1.17376 2.52357 + vertex 1.60774 1.16924 2.52458 + endloop + endfacet + facet normal 0.296619 -0.113928 0.948176 + outer loop + vertex 1.60787 1.16378 2.52389 + vertex 1.61245 1.1685 2.52302 + vertex 1.60774 1.16924 2.52458 + endloop + endfacet + facet normal 0.286067 -0.116299 0.951126 + outer loop + vertex 1.60878 1.17477 2.52491 + vertex 1.61303 1.17884 2.52413 + vertex 1.60924 1.17927 2.52532 + endloop + endfacet + facet normal 0.300005 -0.124184 0.94582 + outer loop + vertex 1.60901 1.18239 2.5258 + vertex 1.60652 1.17979 2.52625 + vertex 1.60924 1.17927 2.52532 + endloop + endfacet + facet normal 0.305181 -0.121394 0.944525 + outer loop + vertex 1.60251 1.17808 2.52734 + vertex 1.60138 1.1726 2.527 + vertex 1.60552 1.17605 2.52611 + endloop + endfacet + facet normal 0.264193 -0.113813 0.957731 + outer loop + vertex 1.60138 1.1726 2.527 + vertex 1.60251 1.17808 2.52734 + vertex 1.59734 1.17312 2.52818 + endloop + endfacet + facet normal 0.309442 -0.133993 0.941431 + outer loop + vertex 1.60901 1.18239 2.5258 + vertex 1.60636 1.18298 2.52675 + vertex 1.60652 1.17979 2.52625 + endloop + endfacet + facet normal 0.283611 -0.135464 0.949323 + outer loop + vertex 1.59734 1.17312 2.52818 + vertex 1.60251 1.17808 2.52734 + vertex 1.5977 1.17831 2.52881 + endloop + endfacet + facet normal 0.262464 -0.125062 0.956803 + outer loop + vertex 1.59707 1.16813 2.5276 + vertex 1.60138 1.1726 2.527 + vertex 1.59734 1.17312 2.52818 + endloop + endfacet + facet normal 0.248405 -0.110763 0.962303 + outer loop + vertex 1.60097 1.16815 2.52659 + vertex 1.60138 1.1726 2.527 + vertex 1.59707 1.16813 2.5276 + endloop + endfacet + facet normal 0.291784 -0.105806 0.950614 + outer loop + vertex 1.60375 1.16776 2.5257 + vertex 1.60097 1.16815 2.52659 + vertex 1.60131 1.16503 2.52614 + endloop + endfacet + facet normal 0.297456 -0.117266 0.947507 + outer loop + vertex 1.60397 1.16437 2.52522 + vertex 1.60131 1.16503 2.52614 + vertex 1.60023 1.16118 2.52601 + endloop + endfacet + facet normal 0.307655 -0.113225 0.944737 + outer loop + vertex 1.60774 1.16924 2.52458 + vertex 1.60397 1.16437 2.52522 + vertex 1.60787 1.16378 2.52389 + endloop + endfacet + facet normal 0.299072 -0.116503 0.947092 + outer loop + vertex 1.61259 1.16317 2.52232 + vertex 1.61245 1.1685 2.52302 + vertex 1.60787 1.16378 2.52389 + endloop + endfacet + facet normal 0.284007 -0.115239 0.951872 + outer loop + vertex 1.61245 1.1685 2.52302 + vertex 1.61737 1.17314 2.52211 + vertex 1.61274 1.17376 2.52357 + endloop + endfacet + facet normal 0.281946 -0.120742 0.951802 + outer loop + vertex 1.61907 1.16731 2.52088 + vertex 1.61934 1.16419 2.52041 + vertex 1.62297 1.16886 2.51992 + endloop + endfacet + facet normal 0.282936 -0.120601 0.951526 + outer loop + vertex 1.62297 1.16886 2.51992 + vertex 1.6278 1.17365 2.51909 + vertex 1.62398 1.17404 2.52028 + endloop + endfacet + facet normal 0.279967 -0.124069 0.951959 + outer loop + vertex 1.62389 1.17733 2.52073 + vertex 1.62133 1.17468 2.52114 + vertex 1.62398 1.17404 2.52028 + endloop + endfacet + facet normal 0.281848 -0.126011 0.951148 + outer loop + vertex 1.62389 1.17733 2.52073 + vertex 1.62122 1.17795 2.52161 + vertex 1.62133 1.17468 2.52114 + endloop + endfacet + facet normal 0.282689 -0.123534 0.951224 + outer loop + vertex 1.61737 1.17314 2.52211 + vertex 1.61733 1.17833 2.5228 + vertex 1.61274 1.17376 2.52357 + endloop + endfacet + facet normal 0.277453 -0.132983 0.951491 + outer loop + vertex 1.61733 1.17833 2.5228 + vertex 1.62228 1.18313 2.52203 + vertex 1.61756 1.18345 2.52345 + endloop + endfacet + facet normal 0.283139 -0.136463 0.949321 + outer loop + vertex 1.62783 1.17892 2.51978 + vertex 1.63278 1.18374 2.519 + vertex 1.62896 1.18417 2.5202 + endloop + endfacet + facet normal 0.280854 -0.138805 0.94966 + outer loop + vertex 1.62631 1.1848 2.52108 + vertex 1.62228 1.18313 2.52203 + vertex 1.62509 1.18107 2.5209 + endloop + endfacet + facet normal 0.284252 -0.148343 0.947204 + outer loop + vertex 1.62631 1.1848 2.52108 + vertex 1.62623 1.18801 2.52161 + vertex 1.62228 1.18313 2.52203 + endloop + endfacet + facet normal 0.281581 -0.153726 0.947143 + outer loop + vertex 1.62737 1.19313 2.5221 + vertex 1.62623 1.18801 2.52161 + vertex 1.63015 1.1911 2.52094 + endloop + endfacet + facet normal 0.278546 -0.145181 0.949386 + outer loop + vertex 1.62891 1.18744 2.52072 + vertex 1.62896 1.18417 2.5202 + vertex 1.63287 1.18896 2.51979 + endloop + endfacet + facet normal 0.284895 -0.154781 0.94598 + outer loop + vertex 1.63287 1.18896 2.51979 + vertex 1.63784 1.19368 2.51907 + vertex 1.63404 1.19411 2.52028 + endloop + endfacet + facet normal 0.279983 -0.155976 0.947249 + outer loop + vertex 1.63142 1.19476 2.52117 + vertex 1.62737 1.19313 2.5221 + vertex 1.63015 1.1911 2.52094 + endloop + endfacet + facet normal 0.279548 -0.154699 0.947587 + outer loop + vertex 1.63142 1.19476 2.52117 + vertex 1.63135 1.19796 2.52171 + vertex 1.62737 1.19313 2.5221 + endloop + endfacet + facet normal 0.281174 -0.151979 0.947546 + outer loop + vertex 1.63245 1.2031 2.52221 + vertex 1.63135 1.19796 2.52171 + vertex 1.63526 1.20098 2.52104 + endloop + endfacet + facet normal 0.286687 -0.156244 0.945197 + outer loop + vertex 1.63403 1.19734 2.52082 + vertex 1.63404 1.19411 2.52028 + vertex 1.63795 1.19885 2.51988 + endloop + endfacet + facet normal 0.28707 -0.152982 0.945615 + outer loop + vertex 1.63795 1.19885 2.51988 + vertex 1.64288 1.20356 2.51914 + vertex 1.63911 1.20398 2.52035 + endloop + endfacet + facet normal 0.281907 -0.150974 0.947489 + outer loop + vertex 1.6365 1.20464 2.52125 + vertex 1.63245 1.2031 2.52221 + vertex 1.63526 1.20098 2.52104 + endloop + endfacet + facet normal 0.280913 -0.147882 0.948272 + outer loop + vertex 1.6365 1.20464 2.52125 + vertex 1.6364 1.20788 2.52179 + vertex 1.63245 1.2031 2.52221 + endloop + endfacet + facet normal 0.283931 -0.14416 0.947946 + outer loop + vertex 1.63748 1.21305 2.52225 + vertex 1.6364 1.20788 2.52179 + vertex 1.64028 1.21089 2.52108 + endloop + endfacet + facet normal 0.287846 -0.1501 0.945841 + outer loop + vertex 1.63908 1.20722 2.52088 + vertex 1.63911 1.20398 2.52035 + vertex 1.64298 1.20874 2.51993 + endloop + endfacet + facet normal 0.280849 -0.145052 0.948727 + outer loop + vertex 1.64298 1.20874 2.51993 + vertex 1.64792 1.21351 2.5192 + vertex 1.64413 1.21392 2.52039 + endloop + endfacet + facet normal 0.284304 -0.143656 0.947911 + outer loop + vertex 1.64149 1.21457 2.52127 + vertex 1.63748 1.21305 2.52225 + vertex 1.64028 1.21089 2.52108 + endloop + endfacet + facet normal 0.283009 -0.139612 0.948902 + outer loop + vertex 1.64149 1.21457 2.52127 + vertex 1.64139 1.21783 2.52179 + vertex 1.63748 1.21305 2.52225 + endloop + endfacet + facet normal 0.281991 -0.135855 0.94975 + outer loop + vertex 1.64242 1.22302 2.52222 + vertex 1.64139 1.21783 2.52179 + vertex 1.64526 1.22091 2.52108 + endloop + endfacet + facet normal 0.281791 -0.142195 0.948881 + outer loop + vertex 1.64407 1.21719 2.52089 + vertex 1.64413 1.21392 2.52039 + vertex 1.64799 1.21875 2.51996 + endloop + endfacet + facet normal 0.275875 -0.136265 0.951486 + outer loop + vertex 1.64799 1.21875 2.51996 + vertex 1.65286 1.22351 2.51923 + vertex 1.64911 1.22399 2.52039 + endloop + endfacet + facet normal 0.282331 -0.13538 0.949716 + outer loop + vertex 1.64646 1.22463 2.52125 + vertex 1.64242 1.22302 2.52222 + vertex 1.64526 1.22091 2.52108 + endloop + endfacet + facet normal 0.281681 -0.133465 0.95018 + outer loop + vertex 1.64646 1.22463 2.52125 + vertex 1.64632 1.22789 2.52175 + vertex 1.64242 1.22302 2.52222 + endloop + endfacet + facet normal 0.277591 -0.131797 0.951616 + outer loop + vertex 1.64738 1.23307 2.52216 + vertex 1.64632 1.22789 2.52175 + vertex 1.65021 1.23098 2.52104 + endloop + endfacet + facet normal 0.279241 -0.133381 0.950912 + outer loop + vertex 1.64903 1.22728 2.52087 + vertex 1.64911 1.22399 2.52039 + vertex 1.65294 1.22879 2.51993 + endloop + endfacet + facet normal 0.301286 -0.132942 0.944221 + outer loop + vertex 1.65294 1.22879 2.51993 + vertex 1.65783 1.23345 2.51903 + vertex 1.65408 1.23406 2.52031 + endloop + endfacet + facet normal 0.277731 -0.1316 0.951602 + outer loop + vertex 1.65141 1.2347 2.52121 + vertex 1.64738 1.23307 2.52216 + vertex 1.65021 1.23098 2.52104 + endloop + endfacet + facet normal 0.276759 -0.128802 0.952268 + outer loop + vertex 1.65141 1.2347 2.52121 + vertex 1.65128 1.23793 2.52168 + vertex 1.64738 1.23307 2.52216 + endloop + endfacet + facet normal 0.314182 -0.129509 0.940488 + outer loop + vertex 1.654 1.23737 2.5208 + vertex 1.65408 1.23406 2.52031 + vertex 1.65792 1.23891 2.5197 + endloop + endfacet + facet normal 0.376083 -0.131433 0.917217 + outer loop + vertex 1.65792 1.23891 2.5197 + vertex 1.6624 1.24363 2.51854 + vertex 1.65889 1.24425 2.52007 + endloop + endfacet + facet normal 0.380751 -0.107725 0.918381 + outer loop + vertex 1.66232 1.24902 2.5192 + vertex 1.65889 1.24425 2.52007 + vertex 1.6624 1.24363 2.51854 + endloop + endfacet + facet normal 0.397556 -0.121406 0.909511 + outer loop + vertex 1.65873 1.24758 2.52058 + vertex 1.65889 1.24425 2.52007 + vertex 1.66232 1.24902 2.5192 + endloop + endfacet + facet normal 0.396422 -0.11766 0.910498 + outer loop + vertex 1.65873 1.24758 2.52058 + vertex 1.66232 1.24902 2.5192 + vertex 1.65965 1.2514 2.52067 + endloop + endfacet + facet normal 0.325122 -0.101239 0.940238 + outer loop + vertex 1.65965 1.2514 2.52067 + vertex 1.65598 1.24796 2.52157 + vertex 1.65873 1.24758 2.52058 + endloop + endfacet + facet normal 0.323051 -0.114096 0.939479 + outer loop + vertex 1.65873 1.24758 2.52058 + vertex 1.65598 1.24796 2.52157 + vertex 1.65629 1.24484 2.52109 + endloop + endfacet + facet normal 0.334903 -0.112916 0.935462 + outer loop + vertex 1.6564 1.25253 2.52197 + vertex 1.65598 1.24796 2.52157 + vertex 1.65965 1.2514 2.52067 + endloop + endfacet + facet normal 0.337436 -0.105537 0.935414 + outer loop + vertex 1.66043 1.25612 2.52092 + vertex 1.6564 1.25253 2.52197 + vertex 1.65965 1.2514 2.52067 + endloop + endfacet + facet normal 0.418374 -0.116974 0.900711 + outer loop + vertex 1.65965 1.2514 2.52067 + vertex 1.66334 1.25467 2.51939 + vertex 1.66043 1.25612 2.52092 + endloop + endfacet + facet normal 0.42394 -0.104615 0.899628 + outer loop + vertex 1.66334 1.25467 2.51939 + vertex 1.66376 1.25939 2.51973 + vertex 1.66043 1.25612 2.52092 + endloop + endfacet + facet normal 0.43855 -0.122928 0.89026 + outer loop + vertex 1.66376 1.25939 2.51973 + vertex 1.66129 1.26001 2.52104 + vertex 1.66043 1.25612 2.52092 + endloop + endfacet + facet normal 0.346192 -0.103682 0.932417 + outer loop + vertex 1.66129 1.26001 2.52104 + vertex 1.65738 1.25816 2.52228 + vertex 1.66043 1.25612 2.52092 + endloop + endfacet + facet normal 0.339627 -0.087042 0.936524 + outer loop + vertex 1.66129 1.26001 2.52104 + vertex 1.66077 1.26312 2.52152 + vertex 1.65738 1.25816 2.52228 + endloop + endfacet + facet normal 0.34934 -0.0943354 0.932235 + outer loop + vertex 1.66077 1.26312 2.52152 + vertex 1.65704 1.26326 2.52293 + vertex 1.65738 1.25816 2.52228 + endloop + endfacet + facet normal 0.341693 -0.11095 0.933239 + outer loop + vertex 1.65738 1.25816 2.52228 + vertex 1.6564 1.25253 2.52197 + vertex 1.66043 1.25612 2.52092 + endloop + endfacet + facet normal 0.407944 -0.102676 0.907215 + outer loop + vertex 1.66232 1.24902 2.5192 + vertex 1.66334 1.25467 2.51939 + vertex 1.65965 1.2514 2.52067 + endloop + endfacet + facet normal 0.337015 -0.127865 0.932776 + outer loop + vertex 1.65873 1.24758 2.52058 + vertex 1.65629 1.24484 2.52109 + vertex 1.65889 1.24425 2.52007 + endloop + endfacet + facet normal 0.286448 -0.127366 0.949592 + outer loop + vertex 1.65227 1.24307 2.52207 + vertex 1.65128 1.23793 2.52168 + vertex 1.65516 1.2411 2.52094 + endloop + endfacet + facet normal 0.277232 -0.120542 0.953212 + outer loop + vertex 1.65227 1.24307 2.52207 + vertex 1.65208 1.24809 2.52276 + vertex 1.64756 1.24334 2.52348 + endloop + endfacet + facet normal 0.277203 -0.114736 0.953936 + outer loop + vertex 1.65208 1.24809 2.52276 + vertex 1.65237 1.25327 2.5233 + vertex 1.64776 1.24852 2.52407 + endloop + endfacet + facet normal 0.277636 -0.116726 0.953569 + outer loop + vertex 1.64296 1.24378 2.52489 + vertex 1.64776 1.24852 2.52407 + vertex 1.64394 1.24902 2.52524 + endloop + endfacet + facet normal 0.283076 -0.114368 0.952254 + outer loop + vertex 1.64375 1.25234 2.5257 + vertex 1.64125 1.24967 2.52612 + vertex 1.64394 1.24902 2.52524 + endloop + endfacet + facet normal 0.284235 -0.115525 0.951769 + outer loop + vertex 1.64375 1.25234 2.5257 + vertex 1.64096 1.2528 2.52659 + vertex 1.64125 1.24967 2.52612 + endloop + endfacet + facet normal 0.288864 -0.115281 0.950404 + outer loop + vertex 1.64096 1.2528 2.52659 + vertex 1.6414 1.25732 2.527 + vertex 1.63711 1.25304 2.52779 + endloop + endfacet + facet normal 0.283582 -0.114282 0.952114 + outer loop + vertex 1.6425 1.26289 2.52734 + vertex 1.6414 1.25732 2.527 + vertex 1.64558 1.2607 2.52616 + endloop + endfacet + facet normal 0.277736 -0.113242 0.95396 + outer loop + vertex 1.64774 1.25389 2.52472 + vertex 1.64887 1.25946 2.52506 + vertex 1.64473 1.25611 2.52586 + endloop + endfacet + facet normal 0.288083 -0.113038 0.95091 + outer loop + vertex 1.64887 1.25946 2.52506 + vertex 1.65303 1.2637 2.5243 + vertex 1.64936 1.26401 2.52545 + endloop + endfacet + facet normal 0.283069 -0.115036 0.952176 + outer loop + vertex 1.64659 1.26447 2.52632 + vertex 1.6425 1.26289 2.52734 + vertex 1.64558 1.2607 2.52616 + endloop + endfacet + facet normal 0.283683 -0.116894 0.951767 + outer loop + vertex 1.64659 1.26447 2.52632 + vertex 1.64638 1.26776 2.52678 + vertex 1.6425 1.26289 2.52734 + endloop + endfacet + facet normal 0.281099 -0.114713 0.952798 + outer loop + vertex 1.64638 1.26776 2.52678 + vertex 1.64238 1.26828 2.52803 + vertex 1.6425 1.26289 2.52734 + endloop + endfacet + facet normal 0.280701 -0.117281 0.952603 + outer loop + vertex 1.64638 1.26776 2.52678 + vertex 1.64737 1.27299 2.52714 + vertex 1.64238 1.26828 2.52803 + endloop + endfacet + facet normal 0.280787 -0.117295 0.952576 + outer loop + vertex 1.64737 1.27299 2.52714 + vertex 1.64638 1.26776 2.52678 + vertex 1.65025 1.27091 2.52603 + endloop + endfacet + facet normal 0.294385 -0.113803 0.948887 + outer loop + vertex 1.64912 1.26716 2.5259 + vertex 1.64936 1.26401 2.52545 + vertex 1.65293 1.2688 2.52492 + endloop + endfacet + facet normal 0.35372 -0.124425 0.927039 + outer loop + vertex 1.65293 1.2688 2.52492 + vertex 1.65735 1.27347 2.52386 + vertex 1.65397 1.27408 2.52523 + endloop + endfacet + facet normal 0.357049 -0.107899 0.927833 + outer loop + vertex 1.65743 1.27888 2.52445 + vertex 1.65397 1.27408 2.52523 + vertex 1.65735 1.27347 2.52386 + endloop + endfacet + facet normal 0.279831 -0.118677 0.952686 + outer loop + vertex 1.65141 1.27468 2.52616 + vertex 1.64737 1.27299 2.52714 + vertex 1.65025 1.27091 2.52603 + endloop + endfacet + facet normal 0.277648 -0.112662 0.954054 + outer loop + vertex 1.65141 1.27468 2.52616 + vertex 1.6511 1.27782 2.52662 + vertex 1.64737 1.27299 2.52714 + endloop + endfacet + facet normal 0.276637 -0.111838 0.954444 + outer loop + vertex 1.6511 1.27782 2.52662 + vertex 1.64718 1.27807 2.52779 + vertex 1.64737 1.27299 2.52714 + endloop + endfacet + facet normal 0.309876 -0.107694 0.944658 + outer loop + vertex 1.6515 1.28239 2.52701 + vertex 1.6511 1.27782 2.52662 + vertex 1.65478 1.28123 2.5258 + endloop + endfacet + facet normal 0.368884 -0.117389 0.922033 + outer loop + vertex 1.65386 1.27742 2.5257 + vertex 1.65397 1.27408 2.52523 + vertex 1.65743 1.27888 2.52445 + endloop + endfacet + facet normal 0.310645 -0.0791727 0.947223 + outer loop + vertex 1.65645 1.28978 2.52615 + vertex 1.65593 1.29293 2.52658 + vertex 1.65248 1.28801 2.5273 + endloop + endfacet + facet normal 0.320577 -0.0867404 0.943242 + outer loop + vertex 1.65593 1.29293 2.52658 + vertex 1.65212 1.29318 2.5279 + vertex 1.65248 1.28801 2.5273 + endloop + endfacet + facet normal 0.322422 -0.0645906 0.94439 + outer loop + vertex 1.65593 1.29293 2.52658 + vertex 1.65596 1.29745 2.52688 + vertex 1.65212 1.29318 2.5279 + endloop + endfacet + facet normal 0.311971 -0.101722 0.944631 + outer loop + vertex 1.65557 1.28591 2.52605 + vertex 1.6515 1.28239 2.52701 + vertex 1.65478 1.28123 2.5258 + endloop + endfacet + facet normal 0.277184 -0.105724 0.954983 + outer loop + vertex 1.6511 1.27782 2.52662 + vertex 1.6515 1.28239 2.52701 + vertex 1.64718 1.27807 2.52779 + endloop + endfacet + facet normal 0.275526 -0.111919 0.954756 + outer loop + vertex 1.64737 1.27299 2.52714 + vertex 1.64718 1.27807 2.52779 + vertex 1.64267 1.27357 2.52856 + endloop + endfacet + facet normal 0.275594 -0.111454 0.954791 + outer loop + vertex 1.64238 1.26828 2.52803 + vertex 1.64737 1.27299 2.52714 + vertex 1.64267 1.27357 2.52856 + endloop + endfacet + facet normal 0.287461 -0.11433 0.950944 + outer loop + vertex 1.6425 1.26289 2.52734 + vertex 1.64238 1.26828 2.52803 + vertex 1.63777 1.26359 2.52886 + endloop + endfacet + facet normal 0.290692 -0.112574 0.950171 + outer loop + vertex 1.63287 1.25886 2.52979 + vertex 1.63777 1.26359 2.52886 + vertex 1.63388 1.26421 2.53012 + endloop + endfacet + facet normal 0.291156 -0.109861 0.950347 + outer loop + vertex 1.63365 1.26755 2.53058 + vertex 1.63118 1.26486 2.53102 + vertex 1.63388 1.26421 2.53012 + endloop + endfacet + facet normal 0.289946 -0.108667 0.950854 + outer loop + vertex 1.63365 1.26755 2.53058 + vertex 1.63087 1.26797 2.53147 + vertex 1.63118 1.26486 2.53102 + endloop + endfacet + facet normal 0.289487 -0.107704 0.951103 + outer loop + vertex 1.63087 1.26797 2.53147 + vertex 1.63128 1.27248 2.53186 + vertex 1.62704 1.26815 2.53266 + endloop + endfacet + facet normal 0.291908 -0.106983 0.950444 + outer loop + vertex 1.63231 1.278 2.53216 + vertex 1.63128 1.27248 2.53186 + vertex 1.63537 1.27591 2.53099 + endloop + endfacet + facet normal 0.288438 -0.10784 0.951406 + outer loop + vertex 1.63764 1.26903 2.52953 + vertex 1.63868 1.27461 2.52985 + vertex 1.63459 1.27131 2.53071 + endloop + endfacet + facet normal 0.276723 -0.104962 0.9552 + outer loop + vertex 1.63868 1.27461 2.52985 + vertex 1.64292 1.2787 2.52907 + vertex 1.63908 1.27918 2.53023 + endloop + endfacet + facet normal 0.292744 -0.105697 0.950331 + outer loop + vertex 1.63628 1.27968 2.53113 + vertex 1.63231 1.278 2.53216 + vertex 1.63537 1.27591 2.53099 + endloop + endfacet + facet normal 0.293132 -0.106763 0.950092 + outer loop + vertex 1.63628 1.27968 2.53113 + vertex 1.63592 1.28277 2.53159 + vertex 1.63231 1.278 2.53216 + endloop + endfacet + facet normal 0.286408 -0.106123 0.952212 + outer loop + vertex 1.63634 1.28728 2.53196 + vertex 1.63592 1.28277 2.53159 + vertex 1.63966 1.28607 2.53083 + endloop + endfacet + facet normal 0.277013 -0.105938 0.955008 + outer loop + vertex 1.63872 1.28233 2.53069 + vertex 1.63908 1.27918 2.53023 + vertex 1.64273 1.28388 2.5297 + endloop + endfacet + facet normal 0.277424 -0.103986 0.955104 + outer loop + vertex 1.63966 1.28607 2.53083 + vertex 1.6438 1.28945 2.52999 + vertex 1.64049 1.29069 2.53109 + endloop + endfacet + facet normal 0.272355 -0.101653 0.956812 + outer loop + vertex 1.64743 1.28321 2.52829 + vertex 1.64777 1.28852 2.52876 + vertex 1.64273 1.28388 2.5297 + endloop + endfacet + facet normal 0.284981 -0.090495 0.954252 + outer loop + vertex 1.65248 1.28801 2.5273 + vertex 1.65212 1.29318 2.5279 + vertex 1.64777 1.28852 2.52876 + endloop + endfacet + facet normal 0.339803 -0.0820211 0.936913 + outer loop + vertex 1.65212 1.29318 2.5279 + vertex 1.65596 1.29745 2.52688 + vertex 1.65214 1.29826 2.52834 + endloop + endfacet + facet normal 0.279834 -0.10124 0.954696 + outer loop + vertex 1.6438 1.28945 2.52999 + vertex 1.648 1.29371 2.52922 + vertex 1.64425 1.29407 2.53035 + endloop + endfacet + facet normal 0.27893 -0.0996907 0.955123 + outer loop + vertex 1.64391 1.29724 2.53078 + vertex 1.64144 1.2945 2.53122 + vertex 1.64425 1.29407 2.53035 + endloop + endfacet + facet normal 0.279796 -0.100522 0.954782 + outer loop + vertex 1.64391 1.29724 2.53078 + vertex 1.64106 1.29764 2.53166 + vertex 1.64144 1.2945 2.53122 + endloop + endfacet + facet normal 0.283887 -0.0975575 0.953882 + outer loop + vertex 1.64106 1.29764 2.53166 + vertex 1.64145 1.30222 2.53201 + vertex 1.63719 1.29796 2.53285 + endloop + endfacet + facet normal 0.279872 -0.0948782 0.955337 + outer loop + vertex 1.64244 1.30781 2.53228 + vertex 1.64145 1.30222 2.53201 + vertex 1.64559 1.30576 2.53115 + endloop + endfacet + facet normal 0.289194 -0.0939134 0.952653 + outer loop + vertex 1.6478 1.29893 2.52979 + vertex 1.64881 1.30456 2.53004 + vertex 1.64481 1.30107 2.53091 + endloop + endfacet + facet normal 0.297181 -0.0988359 0.949692 + outer loop + vertex 1.64923 1.30918 2.53037 + vertex 1.64649 1.30959 2.53127 + vertex 1.64559 1.30576 2.53115 + endloop + endfacet + facet normal 0.32229 -0.0875963 0.94258 + outer loop + vertex 1.65238 1.30349 2.52872 + vertex 1.6527 1.30864 2.52909 + vertex 1.64881 1.30456 2.53004 + endloop + endfacet + facet normal 0.297344 -0.0978625 0.949742 + outer loop + vertex 1.64888 1.31234 2.5308 + vertex 1.64649 1.30959 2.53127 + vertex 1.64923 1.30918 2.53037 + endloop + endfacet + facet normal 0.290709 -0.0916371 0.952413 + outer loop + vertex 1.64888 1.31234 2.5308 + vertex 1.64606 1.31269 2.5317 + vertex 1.64649 1.30959 2.53127 + endloop + endfacet + facet normal 0.279577 -0.0941479 0.955496 + outer loop + vertex 1.64606 1.31269 2.5317 + vertex 1.64642 1.31725 2.53204 + vertex 1.64218 1.31294 2.53286 + endloop + endfacet + facet normal 0.340689 -0.0937593 0.935489 + outer loop + vertex 1.6526 1.31381 2.52962 + vertex 1.65375 1.31943 2.52976 + vertex 1.64976 1.3161 2.53089 + endloop + endfacet + facet normal 0.42627 -0.109192 0.897982 + outer loop + vertex 1.65375 1.31943 2.52976 + vertex 1.65801 1.32352 2.52824 + vertex 1.65426 1.32418 2.5301 + endloop + endfacet + facet normal 0.427929 -0.100436 0.898215 + outer loop + vertex 1.65739 1.32894 2.52914 + vertex 1.65426 1.32418 2.5301 + vertex 1.65801 1.32352 2.52824 + endloop + endfacet + facet normal 0.416446 -0.0916012 0.904534 + outer loop + vertex 1.65385 1.32742 2.53062 + vertex 1.65426 1.32418 2.5301 + vertex 1.65739 1.32894 2.52914 + endloop + endfacet + facet normal 0.411893 -0.0777438 0.90791 + outer loop + vertex 1.65385 1.32742 2.53062 + vertex 1.65739 1.32894 2.52914 + vertex 1.65454 1.33124 2.53063 + endloop + endfacet + facet normal 0.33077 -0.0630941 0.9416 + outer loop + vertex 1.65454 1.33124 2.53063 + vertex 1.651 1.32777 2.53164 + vertex 1.65385 1.32742 2.53062 + endloop + endfacet + facet normal 0.337139 -0.0703847 0.93882 + outer loop + vertex 1.6511 1.33224 2.53194 + vertex 1.651 1.32777 2.53164 + vertex 1.65454 1.33124 2.53063 + endloop + endfacet + facet normal 0.340289 -0.0590701 0.938464 + outer loop + vertex 1.65495 1.33605 2.53079 + vertex 1.6511 1.33224 2.53194 + vertex 1.65454 1.33124 2.53063 + endloop + endfacet + facet normal 0.409892 -0.0640387 0.909883 + outer loop + vertex 1.65454 1.33124 2.53063 + vertex 1.65814 1.33459 2.52924 + vertex 1.65495 1.33605 2.53079 + endloop + endfacet + facet normal 0.414498 -0.0525578 0.908531 + outer loop + vertex 1.65814 1.33459 2.52924 + vertex 1.65849 1.33968 2.52938 + vertex 1.65495 1.33605 2.53079 + endloop + endfacet + facet normal 0.418356 -0.0571264 0.906485 + outer loop + vertex 1.65495 1.33605 2.53079 + vertex 1.65849 1.33968 2.52938 + vertex 1.65527 1.34098 2.53095 + endloop + endfacet + facet normal 0.349765 -0.0536812 0.935298 + outer loop + vertex 1.65527 1.34098 2.53095 + vertex 1.65134 1.33715 2.5322 + vertex 1.65495 1.33605 2.53079 + endloop + endfacet + facet normal 0.357506 -0.0627483 0.9318 + outer loop + vertex 1.65173 1.34227 2.53239 + vertex 1.65134 1.33715 2.5322 + vertex 1.65527 1.34098 2.53095 + endloop + endfacet + facet normal 0.361517 -0.0508514 0.930978 + outer loop + vertex 1.65568 1.34582 2.53105 + vertex 1.65173 1.34227 2.53239 + vertex 1.65527 1.34098 2.53095 + endloop + endfacet + facet normal 0.435176 -0.0564306 0.898575 + outer loop + vertex 1.65527 1.34098 2.53095 + vertex 1.6587 1.34458 2.52951 + vertex 1.65568 1.34582 2.53105 + endloop + endfacet + facet normal 0.439449 -0.0443233 0.897173 + outer loop + vertex 1.6587 1.34458 2.52951 + vertex 1.65882 1.34911 2.52968 + vertex 1.65568 1.34582 2.53105 + endloop + endfacet + facet normal 0.454863 -0.0627329 0.888349 + outer loop + vertex 1.65882 1.34911 2.52968 + vertex 1.65636 1.3497 2.53098 + vertex 1.65568 1.34582 2.53105 + endloop + endfacet + facet normal 0.374538 -0.0478039 0.925979 + outer loop + vertex 1.65636 1.3497 2.53098 + vertex 1.65254 1.34801 2.53244 + vertex 1.65568 1.34582 2.53105 + endloop + endfacet + facet normal 0.374058 -0.0464965 0.926239 + outer loop + vertex 1.65636 1.3497 2.53098 + vertex 1.65578 1.35287 2.53137 + vertex 1.65254 1.34801 2.53244 + endloop + endfacet + facet normal 0.377093 -0.0488101 0.924888 + outer loop + vertex 1.65578 1.35287 2.53137 + vertex 1.65198 1.35322 2.53294 + vertex 1.65254 1.34801 2.53244 + endloop + endfacet + facet normal 0.377885 -0.0405303 0.924965 + outer loop + vertex 1.65578 1.35287 2.53137 + vertex 1.65575 1.3574 2.53158 + vertex 1.65198 1.35322 2.53294 + endloop + endfacet + facet normal 0.389212 -0.0524789 0.919652 + outer loop + vertex 1.65198 1.35322 2.53294 + vertex 1.65575 1.3574 2.53158 + vertex 1.65202 1.35837 2.53322 + endloop + endfacet + facet normal 0.390473 -0.0471993 0.919404 + outer loop + vertex 1.65575 1.3574 2.53158 + vertex 1.65592 1.36233 2.53177 + vertex 1.65202 1.35837 2.53322 + endloop + endfacet + facet normal 0.397228 -0.0550658 0.916066 + outer loop + vertex 1.65202 1.35837 2.53322 + vertex 1.65592 1.36233 2.53177 + vertex 1.65229 1.3635 2.53341 + endloop + endfacet + facet normal 0.399665 -0.0466847 0.915472 + outer loop + vertex 1.65592 1.36233 2.53177 + vertex 1.65606 1.36729 2.53196 + vertex 1.65229 1.3635 2.53341 + endloop + endfacet + facet normal 0.402741 -0.0503364 0.913929 + outer loop + vertex 1.65229 1.3635 2.53341 + vertex 1.65606 1.36729 2.53196 + vertex 1.65246 1.36848 2.53361 + endloop + endfacet + facet normal 0.367747 -0.0588795 0.92806 + outer loop + vertex 1.65254 1.34801 2.53244 + vertex 1.65173 1.34227 2.53239 + vertex 1.65568 1.34582 2.53105 + endloop + endfacet + facet normal 0.423451 -0.0426733 0.904913 + outer loop + vertex 1.65849 1.33968 2.52938 + vertex 1.6587 1.34458 2.52951 + vertex 1.65527 1.34098 2.53095 + endloop + endfacet + facet normal 0.346264 -0.0658936 0.93582 + outer loop + vertex 1.65134 1.33715 2.5322 + vertex 1.6511 1.33224 2.53194 + vertex 1.65495 1.33605 2.53079 + endloop + endfacet + facet normal 0.415913 -0.0718932 0.906558 + outer loop + vertex 1.65739 1.32894 2.52914 + vertex 1.65814 1.33459 2.52924 + vertex 1.65454 1.33124 2.53063 + endloop + endfacet + facet normal 0.356997 -0.103004 0.928409 + outer loop + vertex 1.65385 1.32742 2.53062 + vertex 1.6515 1.32464 2.53121 + vertex 1.65426 1.32418 2.5301 + endloop + endfacet + facet normal 0.29642 -0.0958599 0.950235 + outer loop + vertex 1.64742 1.32286 2.53229 + vertex 1.64642 1.31725 2.53204 + vertex 1.65057 1.32078 2.5311 + endloop + endfacet + facet normal 0.328973 -0.0765261 0.941234 + outer loop + vertex 1.65385 1.32742 2.53062 + vertex 1.651 1.32777 2.53164 + vertex 1.6515 1.32464 2.53121 + endloop + endfacet + facet normal 0.278838 -0.085376 0.956535 + outer loop + vertex 1.64742 1.32286 2.53229 + vertex 1.64709 1.32799 2.53285 + vertex 1.64273 1.32345 2.53371 + endloop + endfacet + facet normal 0.279679 -0.0769782 0.957003 + outer loop + vertex 1.64709 1.32799 2.53285 + vertex 1.64711 1.33302 2.53325 + vertex 1.64291 1.32865 2.53412 + endloop + endfacet + facet normal 0.279987 -0.083557 0.95636 + outer loop + vertex 1.63879 1.32446 2.53496 + vertex 1.64291 1.32865 2.53412 + vertex 1.63915 1.32915 2.53527 + endloop + endfacet + facet normal 0.287007 -0.0786892 0.954691 + outer loop + vertex 1.63871 1.33237 2.53567 + vertex 1.63635 1.32964 2.53615 + vertex 1.63915 1.32915 2.53527 + endloop + endfacet + facet normal 0.286734 -0.0784343 0.954794 + outer loop + vertex 1.63871 1.33237 2.53567 + vertex 1.63586 1.33277 2.53655 + vertex 1.63635 1.32964 2.53615 + endloop + endfacet + facet normal 0.291672 -0.0727506 0.953748 + outer loop + vertex 1.63586 1.33277 2.53655 + vertex 1.636 1.33723 2.53685 + vertex 1.63204 1.33303 2.53774 + endloop + endfacet + facet normal 0.281637 -0.0670354 0.957176 + outer loop + vertex 1.63641 1.34225 2.53708 + vertex 1.636 1.33723 2.53685 + vertex 1.63998 1.34094 2.53594 + endloop + endfacet + facet normal 0.281313 -0.0737312 0.956779 + outer loop + vertex 1.64261 1.33388 2.53464 + vertex 1.64353 1.33954 2.53481 + vertex 1.63947 1.33616 2.53574 + endloop + endfacet + facet normal 0.277763 -0.0652538 0.958431 + outer loop + vertex 1.63998 1.34094 2.53594 + vertex 1.64397 1.3446 2.53503 + vertex 1.6405 1.34578 2.53612 + endloop + endfacet + facet normal 0.288129 -0.0653458 0.955359 + outer loop + vertex 1.64738 1.33821 2.53356 + vertex 1.64785 1.34352 2.53378 + vertex 1.64353 1.33954 2.53481 + endloop + endfacet + facet normal 0.320351 -0.0523538 0.945851 + outer loop + vertex 1.65173 1.34227 2.53239 + vertex 1.65254 1.34801 2.53244 + vertex 1.64785 1.34352 2.53378 + endloop + endfacet + facet normal 0.294466 -0.0640492 0.953513 + outer loop + vertex 1.64397 1.3446 2.53503 + vertex 1.64799 1.34872 2.53407 + vertex 1.64413 1.34919 2.53529 + endloop + endfacet + facet normal 0.277668 -0.0635741 0.958571 + outer loop + vertex 1.64362 1.35239 2.53565 + vertex 1.64127 1.34966 2.53615 + vertex 1.64413 1.34919 2.53529 + endloop + endfacet + facet normal 0.277862 -0.0637538 0.958503 + outer loop + vertex 1.64362 1.35239 2.53565 + vertex 1.64077 1.35277 2.53651 + vertex 1.64127 1.34966 2.53615 + endloop + endfacet + facet normal 0.280543 -0.0646964 0.957659 + outer loop + vertex 1.64077 1.35277 2.53651 + vertex 1.64089 1.35717 2.53677 + vertex 1.63697 1.35302 2.53763 + endloop + endfacet + facet normal 0.299899 -0.0592189 0.952131 + outer loop + vertex 1.64751 1.35396 2.53456 + vertex 1.64832 1.35963 2.53465 + vertex 1.64436 1.35619 2.53569 + endloop + endfacet + facet normal 0.35135 -0.0599041 0.934326 + outer loop + vertex 1.64832 1.35963 2.53465 + vertex 1.65229 1.3635 2.53341 + vertex 1.64871 1.3647 2.53483 + endloop + endfacet + facet normal 0.354591 -0.0494636 0.933712 + outer loop + vertex 1.65229 1.3635 2.53341 + vertex 1.65246 1.36848 2.53361 + vertex 1.64871 1.3647 2.53483 + endloop + endfacet + facet normal 0.361278 -0.0570713 0.93071 + outer loop + vertex 1.64871 1.3647 2.53483 + vertex 1.65246 1.36848 2.53361 + vertex 1.64895 1.36958 2.53504 + endloop + endfacet + facet normal 0.364334 -0.0465199 0.930106 + outer loop + vertex 1.65246 1.36848 2.53361 + vertex 1.65251 1.37343 2.53383 + vertex 1.64895 1.36958 2.53504 + endloop + endfacet + facet normal 0.281596 -0.0630765 0.957458 + outer loop + vertex 1.64114 1.362 2.53701 + vertex 1.64089 1.35717 2.53677 + vertex 1.64482 1.36096 2.53586 + endloop + endfacet + facet normal 0.278489 -0.0609078 0.958506 + outer loop + vertex 1.64114 1.362 2.53701 + vertex 1.64155 1.3671 2.53722 + vertex 1.63715 1.36289 2.53823 + endloop + endfacet + facet normal 0.284846 -0.0589681 0.956758 + outer loop + vertex 1.64244 1.37283 2.5373 + vertex 1.64155 1.3671 2.53722 + vertex 1.64563 1.37071 2.53622 + endloop + endfacet + facet normal 0.311975 -0.0552919 0.94848 + outer loop + vertex 1.64871 1.3647 2.53483 + vertex 1.64895 1.36958 2.53504 + vertex 1.64518 1.36587 2.53606 + endloop + endfacet + facet normal 0.373541 -0.0563538 0.9259 + outer loop + vertex 1.64895 1.36958 2.53504 + vertex 1.65251 1.37343 2.53383 + vertex 1.64908 1.3741 2.53526 + endloop + endfacet + facet normal 0.375366 -0.0466418 0.925702 + outer loop + vertex 1.65219 1.37868 2.53423 + vertex 1.64908 1.3741 2.53526 + vertex 1.65251 1.37343 2.53383 + endloop + endfacet + facet normal 0.285811 -0.0574198 0.956564 + outer loop + vertex 1.64637 1.37458 2.53623 + vertex 1.64244 1.37283 2.5373 + vertex 1.64563 1.37071 2.53622 + endloop + endfacet + facet normal 0.283699 -0.052091 0.957497 + outer loop + vertex 1.64637 1.37458 2.53623 + vertex 1.64584 1.37772 2.53656 + vertex 1.64244 1.37283 2.5373 + endloop + endfacet + facet normal 0.378399 -0.0490097 0.924344 + outer loop + vertex 1.64862 1.37732 2.53562 + vertex 1.64908 1.3741 2.53526 + vertex 1.65219 1.37868 2.53423 + endloop + endfacet + facet normal 0.324372 -0.0465989 0.944781 + outer loop + vertex 1.64592 1.38219 2.53676 + vertex 1.64584 1.37772 2.53656 + vertex 1.64929 1.38116 2.53555 + endloop + endfacet + facet normal 0.2893 -0.0454155 0.95616 + outer loop + vertex 1.64592 1.38219 2.53676 + vertex 1.64608 1.3871 2.53694 + vertex 1.64205 1.38286 2.53796 + endloop + endfacet + facet normal 0.291586 -0.0477814 0.95535 + outer loop + vertex 1.64205 1.38286 2.53796 + vertex 1.64608 1.3871 2.53694 + vertex 1.64209 1.38792 2.5382 + endloop + endfacet + facet normal 0.292636 -0.0425467 0.955277 + outer loop + vertex 1.64608 1.3871 2.53694 + vertex 1.64623 1.39216 2.53712 + vertex 1.64209 1.38792 2.5382 + endloop + endfacet + facet normal 0.332914 -0.0432514 0.941965 + outer loop + vertex 1.64623 1.39216 2.53712 + vertex 1.64608 1.3871 2.53694 + vertex 1.64993 1.39108 2.53576 + endloop + endfacet + facet normal 0.391449 -0.0381901 0.919407 + outer loop + vertex 1.653 1.38442 2.53415 + vertex 1.65333 1.38962 2.53423 + vertex 1.6497 1.38605 2.53563 + endloop + endfacet + facet normal 0.335654 -0.0331401 0.941402 + outer loop + vertex 1.65005 1.39608 2.5359 + vertex 1.64623 1.39216 2.53712 + vertex 1.64993 1.39108 2.53576 + endloop + endfacet + facet normal 0.293747 -0.0437346 0.954882 + outer loop + vertex 1.64209 1.38792 2.5382 + vertex 1.64623 1.39216 2.53712 + vertex 1.64225 1.39316 2.53839 + endloop + endfacet + facet normal 0.280077 -0.04787 0.958783 + outer loop + vertex 1.64205 1.38286 2.53796 + vertex 1.64209 1.38792 2.5382 + vertex 1.63799 1.38351 2.53918 + endloop + endfacet + facet normal 0.285388 -0.0506431 0.957073 + outer loop + vertex 1.63412 1.3794 2.54011 + vertex 1.63799 1.38351 2.53918 + vertex 1.6342 1.38389 2.54033 + endloop + endfacet + facet normal 0.294835 -0.0473997 0.954372 + outer loop + vertex 1.63367 1.38709 2.54065 + vertex 1.63134 1.38434 2.54123 + vertex 1.6342 1.38389 2.54033 + endloop + endfacet + facet normal 0.295991 -0.0484618 0.95396 + outer loop + vertex 1.63367 1.38709 2.54065 + vertex 1.6308 1.38752 2.54156 + vertex 1.63134 1.38434 2.54123 + endloop + endfacet + facet normal 0.301127 -0.0451002 0.952517 + outer loop + vertex 1.6308 1.38752 2.54156 + vertex 1.63086 1.39206 2.54176 + vertex 1.62702 1.38787 2.54277 + endloop + endfacet + facet normal 0.286765 -0.044134 0.956984 + outer loop + vertex 1.63758 1.38871 2.53956 + vertex 1.63839 1.39447 2.53958 + vertex 1.63437 1.39098 2.54062 + endloop + endfacet + facet normal 0.284031 -0.0397871 0.957989 + outer loop + vertex 1.63839 1.39447 2.53958 + vertex 1.64251 1.39836 2.53852 + vertex 1.63869 1.39962 2.53971 + endloop + endfacet + facet normal 0.29373 -0.0416172 0.954982 + outer loop + vertex 1.63103 1.39705 2.54192 + vertex 1.63086 1.39206 2.54176 + vertex 1.63475 1.39588 2.54073 + endloop + endfacet + facet normal 0.300556 -0.0395963 0.952942 + outer loop + vertex 1.63103 1.39705 2.54192 + vertex 1.63119 1.40212 2.54208 + vertex 1.62713 1.39815 2.5432 + endloop + endfacet + facet normal 0.286811 -0.0374789 0.957254 + outer loop + vertex 1.63869 1.39962 2.53971 + vertex 1.63883 1.40463 2.53986 + vertex 1.63495 1.4009 2.54088 + endloop + endfacet + facet normal 0.291573 -0.0363028 0.955859 + outer loop + vertex 1.63883 1.40463 2.53986 + vertex 1.6428 1.40842 2.5388 + vertex 1.63895 1.40961 2.54001 + endloop + endfacet + facet normal 0.293846 -0.0380484 0.955095 + outer loop + vertex 1.63132 1.40712 2.54224 + vertex 1.63119 1.40212 2.54208 + vertex 1.63507 1.40588 2.54104 + endloop + endfacet + facet normal 0.300953 -0.0367535 0.95293 + outer loop + vertex 1.63132 1.40712 2.54224 + vertex 1.63146 1.41206 2.54239 + vertex 1.62757 1.40838 2.54348 + endloop + endfacet + facet normal 0.294503 -0.033903 0.955049 + outer loop + vertex 1.63173 1.41708 2.54248 + vertex 1.63146 1.41206 2.54239 + vertex 1.63534 1.41571 2.54132 + endloop + endfacet + facet normal 0.289309 -0.0342321 0.956624 + outer loop + vertex 1.63895 1.40961 2.54001 + vertex 1.63905 1.41454 2.54016 + vertex 1.63517 1.41081 2.5412 + endloop + endfacet + facet normal 0.290785 -0.0309668 0.956287 + outer loop + vertex 1.63534 1.41571 2.54132 + vertex 1.63915 1.41936 2.54028 + vertex 1.63568 1.42052 2.54137 + endloop + endfacet + facet normal 0.295284 -0.0309563 0.954908 + outer loop + vertex 1.64297 1.41348 2.53891 + vertex 1.64292 1.41835 2.53909 + vertex 1.63905 1.41454 2.54016 + endloop + endfacet + facet normal 0.319241 -0.0309352 0.947169 + outer loop + vertex 1.64733 1.41775 2.53758 + vertex 1.64615 1.42179 2.53811 + vertex 1.64292 1.41835 2.53909 + endloop + endfacet + facet normal 0.299241 -0.0275074 0.953781 + outer loop + vertex 1.63915 1.41936 2.54028 + vertex 1.64288 1.42313 2.53922 + vertex 1.63919 1.42388 2.5404 + endloop + endfacet + facet normal 0.293676 -0.0284995 0.95548 + outer loop + vertex 1.63863 1.42715 2.54067 + vertex 1.63635 1.4244 2.54129 + vertex 1.63919 1.42388 2.5404 + endloop + endfacet + facet normal 0.295153 -0.0298387 0.954984 + outer loop + vertex 1.63863 1.42715 2.54067 + vertex 1.63577 1.42759 2.54157 + vertex 1.63635 1.4244 2.54129 + endloop + endfacet + facet normal 0.297566 -0.029888 0.954233 + outer loop + vertex 1.63577 1.42759 2.54157 + vertex 1.63576 1.43212 2.54171 + vertex 1.63198 1.42787 2.54276 + endloop + endfacet + facet normal 0.310972 -0.0238659 0.950119 + outer loop + vertex 1.64249 1.42844 2.53947 + vertex 1.64311 1.43425 2.53941 + vertex 1.63925 1.43101 2.54059 + endloop + endfacet + facet normal 0.353675 -0.0246354 0.935044 + outer loop + vertex 1.64311 1.43425 2.53941 + vertex 1.64695 1.43771 2.53805 + vertex 1.64336 1.43942 2.53945 + endloop + endfacet + facet normal 0.357654 -0.0151723 0.933731 + outer loop + vertex 1.64695 1.43771 2.53805 + vertex 1.64719 1.44282 2.53804 + vertex 1.64336 1.43942 2.53945 + endloop + endfacet + facet normal 0.360619 -0.0190084 0.93252 + outer loop + vertex 1.64336 1.43942 2.53945 + vertex 1.64719 1.44282 2.53804 + vertex 1.64358 1.44449 2.53947 + endloop + endfacet + facet normal 0.364363 -0.00980623 0.931205 + outer loop + vertex 1.64719 1.44282 2.53804 + vertex 1.64783 1.44834 2.53785 + vertex 1.64358 1.44449 2.53947 + endloop + endfacet + facet normal 0.297795 -0.0276199 0.95423 + outer loop + vertex 1.63585 1.43707 2.54183 + vertex 1.63576 1.43212 2.54171 + vertex 1.63955 1.4359 2.54064 + endloop + endfacet + facet normal 0.297213 -0.0230562 0.954533 + outer loop + vertex 1.63585 1.43707 2.54183 + vertex 1.63595 1.4421 2.54192 + vertex 1.63196 1.43813 2.54306 + endloop + endfacet + facet normal 0.320297 -0.017263 0.94716 + outer loop + vertex 1.64336 1.43942 2.53945 + vertex 1.64358 1.44449 2.53947 + vertex 1.63971 1.44087 2.54071 + endloop + endfacet + facet normal 0.368923 -0.0156305 0.929328 + outer loop + vertex 1.64358 1.44449 2.53947 + vertex 1.64783 1.44834 2.53785 + vertex 1.64364 1.44953 2.53953 + endloop + endfacet + facet normal 0.368853 -0.0159109 0.929352 + outer loop + vertex 1.64783 1.44834 2.53785 + vertex 1.64731 1.45344 2.53814 + vertex 1.64364 1.44953 2.53953 + endloop + endfacet + facet normal 0.365503 -0.012275 0.930729 + outer loop + vertex 1.64364 1.44953 2.53953 + vertex 1.64731 1.45344 2.53814 + vertex 1.64355 1.45449 2.53963 + endloop + endfacet + facet normal 0.366575 -0.00792766 0.930355 + outer loop + vertex 1.64731 1.45344 2.53814 + vertex 1.6472 1.45835 2.53822 + vertex 1.64355 1.45449 2.53963 + endloop + endfacet + facet normal 0.297648 -0.0165877 0.954532 + outer loop + vertex 1.63601 1.44708 2.54199 + vertex 1.63595 1.4421 2.54192 + vertex 1.63979 1.44583 2.54079 + endloop + endfacet + facet normal 0.295612 -0.0111787 0.955243 + outer loop + vertex 1.63601 1.44708 2.54199 + vertex 1.63602 1.45202 2.54204 + vertex 1.63224 1.44833 2.54317 + endloop + endfacet + facet normal 0.321951 -0.013354 0.946662 + outer loop + vertex 1.64364 1.44953 2.53953 + vertex 1.64355 1.45449 2.53963 + vertex 1.6398 1.45076 2.54085 + endloop + endfacet + facet normal 0.36676 -0.00812979 0.93028 + outer loop + vertex 1.64355 1.45449 2.53963 + vertex 1.6472 1.45835 2.53822 + vertex 1.64355 1.45946 2.53967 + endloop + endfacet + facet normal 0.367877 -0.00389722 0.929866 + outer loop + vertex 1.6472 1.45835 2.53822 + vertex 1.64721 1.46334 2.53824 + vertex 1.64355 1.45946 2.53967 + endloop + endfacet + facet normal 0.370387 -0.0066414 0.928854 + outer loop + vertex 1.64355 1.45946 2.53967 + vertex 1.64721 1.46334 2.53824 + vertex 1.6436 1.46446 2.53969 + endloop + endfacet + facet normal 0.371445 -0.00271224 0.928451 + outer loop + vertex 1.64721 1.46334 2.53824 + vertex 1.64725 1.46835 2.53824 + vertex 1.6436 1.46446 2.53969 + endloop + endfacet + facet normal 0.294748 -0.00785573 0.955543 + outer loop + vertex 1.63603 1.45698 2.54208 + vertex 1.63602 1.45202 2.54204 + vertex 1.63979 1.4557 2.54091 + endloop + endfacet + facet normal 0.295539 -0.0072156 0.955303 + outer loop + vertex 1.63603 1.45698 2.54208 + vertex 1.63606 1.46197 2.54211 + vertex 1.63225 1.45826 2.54326 + endloop + endfacet + facet normal 0.318368 -0.00624341 0.947947 + outer loop + vertex 1.64355 1.45946 2.53967 + vertex 1.6436 1.46446 2.53969 + vertex 1.63983 1.46068 2.54093 + endloop + endfacet + facet normal 0.373619 -0.00508103 0.927568 + outer loop + vertex 1.6436 1.46446 2.53969 + vertex 1.64725 1.46835 2.53824 + vertex 1.64364 1.46947 2.5397 + endloop + endfacet + facet normal 0.374567 -0.0015546 0.927198 + outer loop + vertex 1.64725 1.46835 2.53824 + vertex 1.64727 1.47335 2.53824 + vertex 1.64364 1.46947 2.5397 + endloop + endfacet + facet normal 0.376857 -0.00404427 0.926263 + outer loop + vertex 1.64364 1.46947 2.5397 + vertex 1.64727 1.47335 2.53824 + vertex 1.64368 1.47447 2.53971 + endloop + endfacet + facet normal 0.377105 -0.00311818 0.926165 + outer loop + vertex 1.64727 1.47335 2.53824 + vertex 1.64729 1.47834 2.53825 + vertex 1.64368 1.47447 2.53971 + endloop + endfacet + facet normal 0.29649 -0.00723768 0.955009 + outer loop + vertex 1.63611 1.46697 2.54213 + vertex 1.63606 1.46197 2.54211 + vertex 1.63988 1.46569 2.54095 + endloop + endfacet + facet normal 0.298611 -0.00670191 0.954351 + outer loop + vertex 1.63611 1.46697 2.54213 + vertex 1.63614 1.47197 2.54215 + vertex 1.63232 1.46826 2.54332 + endloop + endfacet + facet normal 0.321123 -0.00370948 0.94703 + outer loop + vertex 1.64364 1.46947 2.5397 + vertex 1.64368 1.47447 2.53971 + vertex 1.63992 1.47069 2.54097 + endloop + endfacet + facet normal 0.378999 -0.00518216 0.925383 + outer loop + vertex 1.64368 1.47447 2.53971 + vertex 1.64729 1.47834 2.53825 + vertex 1.64371 1.47945 2.53972 + endloop + endfacet + facet normal 0.379751 -0.00236139 0.925086 + outer loop + vertex 1.64729 1.47834 2.53825 + vertex 1.6473 1.48331 2.53826 + vertex 1.64371 1.47945 2.53972 + endloop + endfacet + facet normal 0.381856 -0.00465318 0.92421 + outer loop + vertex 1.64371 1.47945 2.53972 + vertex 1.6473 1.48331 2.53826 + vertex 1.64373 1.48442 2.53974 + endloop + endfacet + facet normal 0.382663 -0.00162631 0.923887 + outer loop + vertex 1.6473 1.48331 2.53826 + vertex 1.64731 1.48829 2.53826 + vertex 1.64373 1.48442 2.53974 + endloop + endfacet + facet normal 0.385786 -0.00501713 0.922575 + outer loop + vertex 1.64373 1.48442 2.53974 + vertex 1.64731 1.48829 2.53826 + vertex 1.64376 1.48939 2.53976 + endloop + endfacet + facet normal 0.386752 -0.00138601 0.922183 + outer loop + vertex 1.64731 1.48829 2.53826 + vertex 1.64733 1.49331 2.53826 + vertex 1.64376 1.48939 2.53976 + endloop + endfacet + facet normal 0.389647 -0.00450074 0.920953 + outer loop + vertex 1.64376 1.48939 2.53976 + vertex 1.64733 1.49331 2.53826 + vertex 1.64378 1.49438 2.53977 + endloop + endfacet + facet normal 0.389825 -0.00381002 0.920881 + outer loop + vertex 1.64733 1.49331 2.53826 + vertex 1.64735 1.49836 2.53828 + vertex 1.64378 1.49438 2.53977 + endloop + endfacet + facet normal 0.389277 -0.00322993 0.921115 + outer loop + vertex 1.64378 1.49438 2.53977 + vertex 1.64735 1.49836 2.53828 + vertex 1.64378 1.49938 2.53979 + endloop + endfacet + facet normal 0.388997 -0.00438057 0.921229 + outer loop + vertex 1.64735 1.49836 2.53828 + vertex 1.64732 1.50336 2.53831 + vertex 1.64378 1.49938 2.53979 + endloop + endfacet + facet normal 0.383671 0.00117391 0.923469 + outer loop + vertex 1.64378 1.49938 2.53979 + vertex 1.64732 1.50336 2.53831 + vertex 1.64376 1.50436 2.53979 + endloop + endfacet + facet normal 0.383814 0.00177236 0.923409 + outer loop + vertex 1.64732 1.50336 2.53831 + vertex 1.6473 1.50832 2.53831 + vertex 1.64376 1.50436 2.53979 + endloop + endfacet + facet normal 0.382306 0.0033546 0.92403 + outer loop + vertex 1.64376 1.50436 2.53979 + vertex 1.6473 1.50832 2.53831 + vertex 1.64374 1.50934 2.53978 + endloop + endfacet + facet normal 0.383127 0.00673354 0.923671 + outer loop + vertex 1.6473 1.50832 2.53831 + vertex 1.64731 1.51331 2.53827 + vertex 1.64374 1.50934 2.53978 + endloop + endfacet + facet normal 0.385485 0.0042393 0.922705 + outer loop + vertex 1.64374 1.50934 2.53978 + vertex 1.64731 1.51331 2.53827 + vertex 1.64372 1.51433 2.53977 + endloop + endfacet + facet normal 0.385082 0.00255831 0.922879 + outer loop + vertex 1.64731 1.51331 2.53827 + vertex 1.6473 1.51833 2.53826 + vertex 1.64372 1.51433 2.53977 + endloop + endfacet + facet normal 0.38542 0.00220336 0.922739 + outer loop + vertex 1.64372 1.51433 2.53977 + vertex 1.6473 1.51833 2.53826 + vertex 1.64371 1.5193 2.53976 + endloop + endfacet + facet normal 0.384935 0.000102642 0.922944 + outer loop + vertex 1.6473 1.51833 2.53826 + vertex 1.64728 1.52332 2.53827 + vertex 1.64371 1.5193 2.53976 + endloop + endfacet + facet normal 0.382443 0.0027044 0.923975 + outer loop + vertex 1.64371 1.5193 2.53976 + vertex 1.64728 1.52332 2.53827 + vertex 1.64371 1.52427 2.53974 + endloop + endfacet + facet normal 0.382435 0.00267296 0.923978 + outer loop + vertex 1.64728 1.52332 2.53827 + vertex 1.64729 1.52829 2.53825 + vertex 1.64371 1.52427 2.53974 + endloop + endfacet + facet normal 0.380392 0.00480681 0.924813 + outer loop + vertex 1.64371 1.52427 2.53974 + vertex 1.64729 1.52829 2.53825 + vertex 1.64371 1.52926 2.53972 + endloop + endfacet + facet normal 0.380676 0.00604719 0.924689 + outer loop + vertex 1.64729 1.52829 2.53825 + vertex 1.6473 1.53329 2.53821 + vertex 1.64371 1.52926 2.53972 + endloop + endfacet + facet normal 0.383609 0.00298962 0.923491 + outer loop + vertex 1.64371 1.52926 2.53972 + vertex 1.6473 1.53329 2.53821 + vertex 1.64371 1.53426 2.5397 + endloop + endfacet + facet normal 0.383408 0.00211684 0.923577 + outer loop + vertex 1.6473 1.53329 2.53821 + vertex 1.6473 1.53831 2.5382 + vertex 1.64371 1.53426 2.5397 + endloop + endfacet + facet normal 0.29841 -0.00553727 0.954422 + outer loop + vertex 1.63617 1.47697 2.54217 + vertex 1.63614 1.47197 2.54215 + vertex 1.63995 1.47569 2.54098 + endloop + endfacet + facet normal 0.298875 -0.00528505 0.954278 + outer loop + vertex 1.63617 1.47697 2.54217 + vertex 1.6362 1.48196 2.54219 + vertex 1.63238 1.47825 2.54337 + endloop + endfacet + facet normal 0.323189 -0.00442629 0.946324 + outer loop + vertex 1.64371 1.47945 2.53972 + vertex 1.64373 1.48442 2.53974 + vertex 1.63998 1.48067 2.541 + endloop + endfacet + facet normal 0.298463 -0.00541087 0.954406 + outer loop + vertex 1.63623 1.48694 2.54221 + vertex 1.6362 1.48196 2.54219 + vertex 1.64002 1.48565 2.54102 + endloop + endfacet + facet normal 0.297728 -0.0043683 0.954641 + outer loop + vertex 1.63623 1.48694 2.54221 + vertex 1.63625 1.49193 2.54223 + vertex 1.63242 1.48824 2.54341 + endloop + endfacet + facet normal 0.325778 -0.00430813 0.945437 + outer loop + vertex 1.64376 1.48939 2.53976 + vertex 1.64378 1.49438 2.53977 + vertex 1.64004 1.49062 2.54104 + endloop + endfacet + facet normal 0.296031 -0.00155949 0.955177 + outer loop + vertex 1.63625 1.49692 2.54224 + vertex 1.63625 1.49193 2.54223 + vertex 1.64006 1.4956 2.54105 + endloop + endfacet + facet normal 0.29791 0.00122245 0.954593 + outer loop + vertex 1.63625 1.49692 2.54224 + vertex 1.63624 1.50191 2.54223 + vertex 1.63243 1.49822 2.54343 + endloop + endfacet + facet normal 0.32236 0.000896574 0.946617 + outer loop + vertex 1.64378 1.49938 2.53979 + vertex 1.64376 1.50436 2.53979 + vertex 1.64005 1.50059 2.54106 + endloop + endfacet + facet normal 0.29627 0.00259206 0.955101 + outer loop + vertex 1.63621 1.5069 2.54223 + vertex 1.63624 1.50191 2.54223 + vertex 1.64002 1.50558 2.54105 + endloop + endfacet + facet normal 0.300632 0.00244268 0.953737 + outer loop + vertex 1.63621 1.5069 2.54223 + vertex 1.6362 1.5119 2.54222 + vertex 1.63242 1.50822 2.54342 + endloop + endfacet + facet normal 0.319787 0.00405666 0.947481 + outer loop + vertex 1.64374 1.50934 2.53978 + vertex 1.64372 1.51433 2.53977 + vertex 1.63999 1.51057 2.54104 + endloop + endfacet + facet normal 0.298975 0.00120548 0.95426 + outer loop + vertex 1.63619 1.51689 2.54222 + vertex 1.6362 1.5119 2.54222 + vertex 1.63997 1.51555 2.54103 + endloop + endfacet + facet normal 0.303373 0.00121576 0.952871 + outer loop + vertex 1.63619 1.51689 2.54222 + vertex 1.63618 1.52187 2.54221 + vertex 1.63241 1.51821 2.54342 + endloop + endfacet + facet normal 0.32183 0.00277119 0.946793 + outer loop + vertex 1.64371 1.5193 2.53976 + vertex 1.64371 1.52427 2.53974 + vertex 1.63997 1.52053 2.54103 + endloop + endfacet + facet normal 0.300545 0.00164313 0.953766 + outer loop + vertex 1.63618 1.52686 2.54221 + vertex 1.63618 1.52187 2.54221 + vertex 1.63997 1.52551 2.54101 + endloop + endfacet + facet normal 0.304649 0.00152689 0.952463 + outer loop + vertex 1.63618 1.52686 2.54221 + vertex 1.63617 1.53185 2.5422 + vertex 1.6324 1.52819 2.54341 + endloop + endfacet + facet normal 0.324618 0.00310911 0.94584 + outer loop + vertex 1.64371 1.52926 2.53972 + vertex 1.64371 1.53426 2.5397 + vertex 1.63996 1.5305 2.541 + endloop + endfacet + facet normal 0.385348 0.000100403 0.922771 + outer loop + vertex 1.64371 1.53426 2.5397 + vertex 1.6473 1.53831 2.5382 + vertex 1.64371 1.5393 2.5397 + endloop + endfacet + facet normal 0.384549 -0.00331646 0.923098 + outer loop + vertex 1.6473 1.53831 2.5382 + vertex 1.6473 1.54331 2.53822 + vertex 1.64371 1.5393 2.5397 + endloop + endfacet + facet normal 0.383586 -0.00230818 0.923502 + outer loop + vertex 1.64371 1.5393 2.5397 + vertex 1.6473 1.54331 2.53822 + vertex 1.64372 1.54433 2.53971 + endloop + endfacet + facet normal 0.383432 -0.00293973 0.923564 + outer loop + vertex 1.6473 1.54331 2.53822 + vertex 1.64732 1.54827 2.53822 + vertex 1.64372 1.54433 2.53971 + endloop + endfacet + facet normal 0.38399 -0.00353759 0.923331 + outer loop + vertex 1.64372 1.54433 2.53971 + vertex 1.64732 1.54827 2.53822 + vertex 1.64376 1.54936 2.53971 + endloop + endfacet + facet normal 0.384787 -0.000486755 0.923005 + outer loop + vertex 1.64732 1.54827 2.53822 + vertex 1.64737 1.55324 2.53821 + vertex 1.64376 1.54936 2.53971 + endloop + endfacet + facet normal 0.384967 -0.000683309 0.92293 + outer loop + vertex 1.64376 1.54936 2.53971 + vertex 1.64737 1.55324 2.53821 + vertex 1.64376 1.55439 2.53971 + endloop + endfacet + facet normal 0.384209 -0.00346192 0.92324 + outer loop + vertex 1.64737 1.55324 2.53821 + vertex 1.64729 1.55823 2.53826 + vertex 1.64376 1.55439 2.53971 + endloop + endfacet + facet normal 0.379864 0.00121092 0.925042 + outer loop + vertex 1.64376 1.55439 2.53971 + vertex 1.64729 1.55823 2.53826 + vertex 1.64366 1.55938 2.53975 + endloop + endfacet + facet normal 0.378522 -0.00377602 0.925585 + outer loop + vertex 1.64729 1.55823 2.53826 + vertex 1.64699 1.56311 2.5384 + vertex 1.64366 1.55938 2.53975 + endloop + endfacet + facet normal 0.370957 0.00407255 0.928641 + outer loop + vertex 1.64366 1.55938 2.53975 + vertex 1.64699 1.56311 2.5384 + vertex 1.64346 1.56418 2.53981 + endloop + endfacet + facet normal 0.369132 -0.00292688 0.929372 + outer loop + vertex 1.64699 1.56311 2.5384 + vertex 1.64641 1.56716 2.53864 + vertex 1.64346 1.56418 2.53981 + endloop + endfacet + facet normal 0.354767 0.0134358 0.934858 + outer loop + vertex 1.64346 1.56418 2.53981 + vertex 1.64641 1.56716 2.53864 + vertex 1.64353 1.56897 2.53971 + endloop + endfacet + facet normal 0.362351 0.0274364 0.931638 + outer loop + vertex 1.64641 1.56716 2.53864 + vertex 1.64776 1.57191 2.53798 + vertex 1.64353 1.56897 2.53971 + endloop + endfacet + facet normal 0.3698 0.0151489 0.928988 + outer loop + vertex 1.64353 1.56897 2.53971 + vertex 1.64776 1.57191 2.53798 + vertex 1.64374 1.57412 2.53955 + endloop + endfacet + facet normal 0.364628 0.00419979 0.931144 + outer loop + vertex 1.64776 1.57191 2.53798 + vertex 1.64799 1.57807 2.53786 + vertex 1.64374 1.57412 2.53955 + endloop + endfacet + facet normal 0.303433 0.000445995 0.952853 + outer loop + vertex 1.63616 1.53684 2.5422 + vertex 1.63617 1.53185 2.5422 + vertex 1.63996 1.5355 2.54099 + endloop + endfacet + facet normal 0.303752 -0.000152224 0.952751 + outer loop + vertex 1.63616 1.53684 2.5422 + vertex 1.63617 1.54184 2.5422 + vertex 1.63238 1.53816 2.54341 + endloop + endfacet + facet normal 0.32618 -0.00220527 0.945305 + outer loop + vertex 1.64371 1.5393 2.5397 + vertex 1.64372 1.54433 2.53971 + vertex 1.63996 1.54052 2.541 + endloop + endfacet + facet normal 0.299087 0.00115088 0.954225 + outer loop + vertex 1.63618 1.54684 2.54219 + vertex 1.63617 1.54184 2.5422 + vertex 1.63998 1.54555 2.541 + endloop + endfacet + facet normal 0.322864 -0.000654736 0.946445 + outer loop + vertex 1.64376 1.54936 2.53971 + vertex 1.64376 1.55439 2.53971 + vertex 1.64001 1.55058 2.54099 + endloop + endfacet + facet normal 0.292083 0.00497234 0.95638 + outer loop + vertex 1.63619 1.55689 2.54214 + vertex 1.6362 1.55186 2.54217 + vertex 1.64001 1.55562 2.54098 + endloop + endfacet + facet normal 0.292501 0.00688969 0.956241 + outer loop + vertex 1.63619 1.55689 2.54214 + vertex 1.63614 1.5619 2.54212 + vertex 1.63235 1.55814 2.54331 + endloop + endfacet + facet normal 0.315051 0.00151632 0.949074 + outer loop + vertex 1.64366 1.55938 2.53975 + vertex 1.64346 1.56418 2.53981 + vertex 1.63994 1.56062 2.54098 + endloop + endfacet + facet normal 0.289111 0.00969478 0.957247 + outer loop + vertex 1.63605 1.5669 2.5421 + vertex 1.63614 1.5619 2.54212 + vertex 1.63985 1.56557 2.54097 + endloop + endfacet + facet normal 0.293492 0.0127873 0.955876 + outer loop + vertex 1.63605 1.5669 2.5421 + vertex 1.63597 1.5719 2.54206 + vertex 1.63221 1.56814 2.54326 + endloop + endfacet + facet normal 0.312102 0.0182148 0.949874 + outer loop + vertex 1.64353 1.56897 2.53971 + vertex 1.64374 1.57412 2.53955 + vertex 1.63981 1.57056 2.54091 + endloop + endfacet + facet normal 0.357928 0.0124821 0.933666 + outer loop + vertex 1.64374 1.57412 2.53955 + vertex 1.64799 1.57807 2.53786 + vertex 1.64363 1.57936 2.53952 + endloop + endfacet + facet normal 0.354442 -0.00105223 0.935077 + outer loop + vertex 1.64799 1.57807 2.53786 + vertex 1.64723 1.58328 2.53816 + vertex 1.64363 1.57936 2.53952 + endloop + endfacet + facet normal 0.338441 0.0156509 0.940857 + outer loop + vertex 1.64363 1.57936 2.53952 + vertex 1.64723 1.58328 2.53816 + vertex 1.64338 1.58434 2.53952 + endloop + endfacet + facet normal 0.29225 0.0152582 0.95622 + outer loop + vertex 1.63592 1.5769 2.54199 + vertex 1.63597 1.5719 2.54206 + vertex 1.63977 1.57561 2.54084 + endloop + endfacet + facet normal 0.296318 0.0179349 0.954921 + outer loop + vertex 1.63592 1.5769 2.54199 + vertex 1.63591 1.58188 2.5419 + vertex 1.63215 1.57812 2.54314 + endloop + endfacet + facet normal 0.291689 0.0216473 0.956268 + outer loop + vertex 1.63582 1.58682 2.54182 + vertex 1.63591 1.58188 2.5419 + vertex 1.63959 1.58556 2.54069 + endloop + endfacet + facet normal 0.292805 0.0253729 0.955835 + outer loop + vertex 1.6394 1.59044 2.54062 + vertex 1.63582 1.58682 2.54182 + vertex 1.63959 1.58556 2.54069 + endloop + endfacet + facet normal 0.307452 0.0140419 0.95146 + outer loop + vertex 1.64363 1.57936 2.53952 + vertex 1.64338 1.58434 2.53952 + vertex 1.6397 1.58063 2.54077 + endloop + endfacet + facet normal 0.296085 0.025488 0.954822 + outer loop + vertex 1.63959 1.58556 2.54069 + vertex 1.64312 1.58908 2.53951 + vertex 1.6394 1.59044 2.54062 + endloop + endfacet + facet normal 0.337569 0.0120367 0.941224 + outer loop + vertex 1.64723 1.58328 2.53816 + vertex 1.6468 1.58805 2.53825 + vertex 1.64338 1.58434 2.53952 + endloop + endfacet + facet normal 0.296843 0.0278063 0.954521 + outer loop + vertex 1.64312 1.58908 2.53951 + vertex 1.64303 1.59389 2.5394 + vertex 1.6394 1.59044 2.54062 + endloop + endfacet + facet normal 0.29215 0.0260837 0.956017 + outer loop + vertex 1.6355 1.59177 2.54178 + vertex 1.63582 1.58682 2.54182 + vertex 1.6394 1.59044 2.54062 + endloop + endfacet + facet normal 0.300302 0.0321894 0.953301 + outer loop + vertex 1.6355 1.59177 2.54178 + vertex 1.63484 1.597 2.54181 + vertex 1.63153 1.59291 2.54299 + endloop + endfacet + facet normal 0.290271 0.0326196 0.956388 + outer loop + vertex 1.63847 1.59939 2.54062 + vertex 1.63902 1.59534 2.54059 + vertex 1.64277 1.59949 2.53931 + endloop + endfacet + facet normal 0.299943 0.0364822 0.953259 + outer loop + vertex 1.6322 1.60131 2.54248 + vertex 1.63095 1.59691 2.54304 + vertex 1.63484 1.597 2.54181 + endloop + endfacet + facet normal 0.286557 0.0307392 0.95757 + outer loop + vertex 1.63847 1.59939 2.54062 + vertex 1.63976 1.60384 2.54009 + vertex 1.6361 1.60137 2.54126 + endloop + endfacet + facet normal 0.276293 0.0317601 0.960548 + outer loop + vertex 1.63976 1.60384 2.54009 + vertex 1.64298 1.60808 2.53902 + vertex 1.63902 1.60909 2.54013 + endloop + endfacet + facet normal 0.295397 0.0361274 0.954691 + outer loop + vertex 1.63151 1.60666 2.54249 + vertex 1.6322 1.60131 2.54248 + vertex 1.63552 1.60544 2.54129 + endloop + endfacet + facet normal 0.302421 0.0360615 0.952492 + outer loop + vertex 1.63151 1.60666 2.54249 + vertex 1.63114 1.61178 2.54241 + vertex 1.62756 1.60801 2.54369 + endloop + endfacet + facet normal 0.283083 0.0348019 0.958464 + outer loop + vertex 1.63902 1.60909 2.54013 + vertex 1.63873 1.61416 2.54003 + vertex 1.63503 1.61045 2.54126 + endloop + endfacet + facet normal 0.27573 0.035943 0.960563 + outer loop + vertex 1.63873 1.61416 2.54003 + vertex 1.64267 1.61786 2.53876 + vertex 1.63863 1.61927 2.53987 + endloop + endfacet + facet normal 0.296085 0.0352474 0.954511 + outer loop + vertex 1.63105 1.61682 2.54225 + vertex 1.63114 1.61178 2.54241 + vertex 1.63482 1.61553 2.54113 + endloop + endfacet + facet normal 0.304551 0.0358154 0.951822 + outer loop + vertex 1.63105 1.61682 2.54225 + vertex 1.63108 1.62179 2.54206 + vertex 1.62737 1.61807 2.54338 + endloop + endfacet + facet normal 0.283056 0.0380902 0.958347 + outer loop + vertex 1.63863 1.61927 2.53987 + vertex 1.63859 1.62429 2.53968 + vertex 1.63479 1.62056 2.54095 + endloop + endfacet + facet normal 0.275254 0.0409369 0.9605 + outer loop + vertex 1.63859 1.62429 2.53968 + vertex 1.6424 1.62807 2.53843 + vertex 1.63847 1.62921 2.5395 + endloop + endfacet + facet normal 0.296778 0.0383307 0.954177 + outer loop + vertex 1.631 1.62669 2.54189 + vertex 1.63108 1.62179 2.54206 + vertex 1.63477 1.62549 2.54076 + endloop + endfacet + facet normal 0.303343 0.0426384 0.951927 + outer loop + vertex 1.631 1.62669 2.54189 + vertex 1.63062 1.63158 2.54179 + vertex 1.62705 1.62791 2.54309 + endloop + endfacet + facet normal 0.297156 0.0454525 0.953747 + outer loop + vertex 1.62987 1.63677 2.54177 + vertex 1.63062 1.63158 2.54179 + vertex 1.63405 1.63519 2.54055 + endloop + endfacet + facet normal 0.298131 0.0483907 0.953298 + outer loop + vertex 1.63405 1.63519 2.54055 + vertex 1.63341 1.63919 2.54054 + vertex 1.62987 1.63677 2.54177 + endloop + endfacet + facet normal 0.285317 0.0447717 0.957387 + outer loop + vertex 1.63847 1.62921 2.5395 + vertex 1.6381 1.63412 2.53938 + vertex 1.63457 1.63036 2.54061 + endloop + endfacet + facet normal 0.288365 0.04682 0.956375 + outer loop + vertex 1.63341 1.63919 2.54054 + vertex 1.63405 1.63519 2.54055 + vertex 1.63736 1.63933 2.53935 + endloop + endfacet + facet normal 0.277965 0.0477716 0.959402 + outer loop + vertex 1.64215 1.63297 2.53827 + vertex 1.64162 1.63781 2.53818 + vertex 1.6381 1.63412 2.53938 + endloop + endfacet + facet normal 0.279018 0.0508216 0.95894 + outer loop + vertex 1.63736 1.63933 2.53935 + vertex 1.64099 1.6418 2.53816 + vertex 1.63861 1.64377 2.53875 + endloop + endfacet + facet normal 0.289278 0.047688 0.956056 + outer loop + vertex 1.64569 1.63678 2.537 + vertex 1.64498 1.64198 2.53696 + vertex 1.64162 1.63781 2.53818 + endloop + endfacet + facet normal 0.2792 0.051062 0.958874 + outer loop + vertex 1.64099 1.6418 2.53816 + vertex 1.64226 1.64627 2.53755 + vertex 1.63861 1.64377 2.53875 + endloop + endfacet + facet normal 0.280848 0.0540407 0.95823 + outer loop + vertex 1.64226 1.64627 2.53755 + vertex 1.64153 1.65165 2.53746 + vertex 1.638 1.64789 2.53871 + endloop + endfacet + facet normal 0.329343 0.0427807 0.943241 + outer loop + vertex 1.64967 1.64891 2.53495 + vertex 1.64892 1.65419 2.53497 + vertex 1.64559 1.65048 2.5363 + endloop + endfacet + facet normal 0.283246 0.0575114 0.957321 + outer loop + vertex 1.64112 1.65675 2.53728 + vertex 1.64153 1.65165 2.53746 + vertex 1.64504 1.65546 2.53619 + endloop + endfacet + facet normal 0.281809 0.0606175 0.957554 + outer loop + vertex 1.64112 1.65675 2.53728 + vertex 1.64083 1.66172 2.53705 + vertex 1.63718 1.658 2.53836 + endloop + endfacet + facet normal 0.280887 0.0613887 0.957775 + outer loop + vertex 1.6397 1.67173 2.53673 + vertex 1.64043 1.66661 2.53685 + vertex 1.6439 1.67017 2.5356 + endloop + endfacet + facet normal 0.298312 0.0606356 0.95254 + outer loop + vertex 1.64827 1.66378 2.53465 + vertex 1.64806 1.66878 2.5344 + vertex 1.64442 1.66531 2.53576 + endloop + endfacet + facet normal 0.346261 0.0618177 0.936099 + outer loop + vertex 1.64827 1.66378 2.53465 + vertex 1.6524 1.66669 2.53293 + vertex 1.64806 1.66878 2.5344 + endloop + endfacet + facet normal 0.338109 0.0420629 0.940167 + outer loop + vertex 1.6524 1.66669 2.53293 + vertex 1.65179 1.67222 2.53291 + vertex 1.64806 1.66878 2.5344 + endloop + endfacet + facet normal 0.344057 0.0652895 0.936676 + outer loop + vertex 1.6513 1.66201 2.53366 + vertex 1.6524 1.66669 2.53293 + vertex 1.64827 1.66378 2.53465 + endloop + endfacet + facet normal 0.340976 0.0591613 0.938209 + outer loop + vertex 1.64842 1.65903 2.5349 + vertex 1.6513 1.66201 2.53366 + vertex 1.64827 1.66378 2.53465 + endloop + endfacet + facet normal 0.324269 0.0588011 0.944136 + outer loop + vertex 1.64806 1.66878 2.5344 + vertex 1.65179 1.67222 2.53291 + vertex 1.64738 1.67429 2.53429 + endloop + endfacet + facet normal 0.286237 0.0617478 0.956167 + outer loop + vertex 1.6369 1.67594 2.5373 + vertex 1.63593 1.67141 2.53788 + vertex 1.6397 1.67173 2.53673 + endloop + endfacet + facet normal 0.288138 0.0645649 0.95541 + outer loop + vertex 1.63616 1.68146 2.53715 + vertex 1.6369 1.67594 2.5373 + vertex 1.64026 1.68024 2.536 + endloop + endfacet + facet normal 0.279973 0.0638454 0.957882 + outer loop + vertex 1.64326 1.67419 2.53553 + vertex 1.6445 1.67865 2.53487 + vertex 1.64089 1.67615 2.53609 + endloop + endfacet + facet normal 0.281454 0.0705503 0.956978 + outer loop + vertex 1.64026 1.68024 2.536 + vertex 1.64365 1.68395 2.53473 + vertex 1.63958 1.68523 2.53583 + endloop + endfacet + facet normal 0.278395 0.0759098 0.957462 + outer loop + vertex 1.64771 1.68296 2.53362 + vertex 1.64692 1.68775 2.53347 + vertex 1.64365 1.68395 2.53473 + endloop + endfacet + facet normal 0.286162 0.0618678 0.956182 + outer loop + vertex 1.64326 1.67419 2.53553 + vertex 1.64738 1.67429 2.53429 + vertex 1.6445 1.67865 2.53487 + endloop + endfacet + facet normal 0.317598 0.0425362 0.947271 + outer loop + vertex 1.65179 1.67222 2.53291 + vertex 1.65165 1.6772 2.53273 + vertex 1.64738 1.67429 2.53429 + endloop + endfacet + facet normal 0.299773 0.0711463 0.951354 + outer loop + vertex 1.64856 1.67895 2.53366 + vertex 1.65153 1.68192 2.5325 + vertex 1.64771 1.68296 2.53362 + endloop + endfacet + facet normal 0.299325 0.0691756 0.95164 + outer loop + vertex 1.65153 1.68192 2.5325 + vertex 1.65096 1.68675 2.53233 + vertex 1.64771 1.68296 2.53362 + endloop + endfacet + facet normal 0.290198 0.0777336 0.953804 + outer loop + vertex 1.64771 1.68296 2.53362 + vertex 1.65096 1.68675 2.53233 + vertex 1.64692 1.68775 2.53347 + endloop + endfacet + facet normal 0.340356 0.0734544 0.937423 + outer loop + vertex 1.65096 1.68675 2.53233 + vertex 1.65153 1.68192 2.5325 + vertex 1.65478 1.68547 2.53104 + endloop + endfacet + facet normal 0.289976 0.0766596 0.953959 + outer loop + vertex 1.65096 1.68675 2.53233 + vertex 1.65008 1.69209 2.53217 + vertex 1.64692 1.68775 2.53347 + endloop + endfacet + facet normal 0.284675 0.0808981 0.955205 + outer loop + vertex 1.64692 1.68775 2.53347 + vertex 1.65008 1.69209 2.53217 + vertex 1.64594 1.69191 2.53341 + endloop + endfacet + facet normal 0.284685 0.0807336 0.955215 + outer loop + vertex 1.64723 1.69657 2.53264 + vertex 1.64594 1.69191 2.53341 + vertex 1.65008 1.69209 2.53217 + endloop + endfacet + facet normal 0.406438 0.0816467 0.910023 + outer loop + vertex 1.6535 1.69447 2.53082 + vertex 1.65417 1.69043 2.53089 + vertex 1.65704 1.69446 2.52924 + endloop + endfacet + facet normal 0.406618 0.0755699 0.910467 + outer loop + vertex 1.6535 1.69447 2.53082 + vertex 1.65704 1.69446 2.52924 + vertex 1.6545 1.69857 2.53003 + endloop + endfacet + facet normal 0.288007 0.0829677 0.954027 + outer loop + vertex 1.65123 1.6965 2.53143 + vertex 1.64723 1.69657 2.53264 + vertex 1.65008 1.69209 2.53217 + endloop + endfacet + facet normal 0.277498 0.0858288 0.956885 + outer loop + vertex 1.64723 1.69657 2.53264 + vertex 1.64658 1.70183 2.53235 + vertex 1.64364 1.69882 2.53348 + endloop + endfacet + facet normal 0.335923 0.0852653 0.938022 + outer loop + vertex 1.6545 1.69857 2.53003 + vertex 1.65374 1.70378 2.52983 + vertex 1.65053 1.7005 2.53128 + endloop + endfacet + facet normal 0.420317 0.0963155 0.902251 + outer loop + vertex 1.6545 1.69857 2.53003 + vertex 1.65775 1.70176 2.52818 + vertex 1.65374 1.70378 2.52983 + endloop + endfacet + facet normal 0.410483 0.0710791 0.909094 + outer loop + vertex 1.65775 1.70176 2.52818 + vertex 1.65684 1.70714 2.52817 + vertex 1.65374 1.70378 2.52983 + endloop + endfacet + facet normal 0.412391 0.105882 0.904833 + outer loop + vertex 1.65744 1.69814 2.52874 + vertex 1.65775 1.70176 2.52818 + vertex 1.6545 1.69857 2.53003 + endloop + endfacet + facet normal 0.395106 0.0878952 0.914421 + outer loop + vertex 1.65374 1.70378 2.52983 + vertex 1.65684 1.70714 2.52817 + vertex 1.653 1.70896 2.52965 + endloop + endfacet + facet normal 0.387997 0.0691035 0.919066 + outer loop + vertex 1.65684 1.70714 2.52817 + vertex 1.65634 1.71235 2.52799 + vertex 1.653 1.70896 2.52965 + endloop + endfacet + facet normal 0.373239 0.0859448 0.923746 + outer loop + vertex 1.653 1.70896 2.52965 + vertex 1.65634 1.71235 2.52799 + vertex 1.65229 1.71446 2.52943 + endloop + endfacet + facet normal 0.364713 0.0661755 0.928765 + outer loop + vertex 1.65634 1.71235 2.52799 + vertex 1.65629 1.71737 2.52765 + vertex 1.65229 1.71446 2.52943 + endloop + endfacet + facet normal 0.365975 0.0642167 0.928406 + outer loop + vertex 1.65229 1.71446 2.52943 + vertex 1.65629 1.71737 2.52765 + vertex 1.6534 1.71912 2.52867 + endloop + endfacet + facet normal 0.295456 0.0848132 0.951584 + outer loop + vertex 1.64947 1.71869 2.52993 + vertex 1.65229 1.71446 2.52943 + vertex 1.6534 1.71912 2.52867 + endloop + endfacet + facet normal 0.294906 0.0891884 0.951355 + outer loop + vertex 1.6534 1.71912 2.52867 + vertex 1.65252 1.72299 2.52858 + vertex 1.64947 1.71869 2.52993 + endloop + endfacet + facet normal 0.281281 0.0998191 0.95442 + outer loop + vertex 1.64947 1.71869 2.52993 + vertex 1.65252 1.72299 2.52858 + vertex 1.64842 1.72387 2.52969 + endloop + endfacet + facet normal 0.343201 0.0997077 0.933955 + outer loop + vertex 1.6534 1.71912 2.52867 + vertex 1.65618 1.72203 2.52733 + vertex 1.65252 1.72299 2.52858 + endloop + endfacet + facet normal 0.339952 0.0836815 0.936712 + outer loop + vertex 1.65618 1.72203 2.52733 + vertex 1.65562 1.72669 2.52712 + vertex 1.65252 1.72299 2.52858 + endloop + endfacet + facet normal 0.319906 0.1025 0.941888 + outer loop + vertex 1.65252 1.72299 2.52858 + vertex 1.65562 1.72669 2.52712 + vertex 1.65167 1.72765 2.52836 + endloop + endfacet + facet normal 0.36949 0.071122 0.926509 + outer loop + vertex 1.65629 1.71737 2.52765 + vertex 1.65618 1.72203 2.52733 + vertex 1.6534 1.71912 2.52867 + endloop + endfacet + facet normal 0.283078 0.0895008 0.954912 + outer loop + vertex 1.64573 1.70666 2.53215 + vertex 1.64658 1.70183 2.53235 + vertex 1.64977 1.70538 2.53107 + endloop + endfacet + facet normal 0.274085 0.0919073 0.957304 + outer loop + vertex 1.64573 1.70666 2.53215 + vertex 1.6448 1.71183 2.53192 + vertex 1.6416 1.7077 2.53323 + endloop + endfacet + facet normal 0.297969 0.0910621 0.950222 + outer loop + vertex 1.64833 1.71428 2.53069 + vertex 1.649 1.71028 2.53086 + vertex 1.65229 1.71446 2.52943 + endloop + endfacet + facet normal 0.298264 0.0868083 0.950528 + outer loop + vertex 1.64833 1.71428 2.53069 + vertex 1.65229 1.71446 2.52943 + vertex 1.64947 1.71869 2.52993 + endloop + endfacet + facet normal 0.269784 0.0933743 0.958383 + outer loop + vertex 1.64598 1.71617 2.53117 + vertex 1.642 1.71606 2.5323 + vertex 1.6448 1.71183 2.53192 + endloop + endfacet + facet normal 0.283006 0.0982685 0.954071 + outer loop + vertex 1.642 1.71606 2.5323 + vertex 1.64093 1.72134 2.53207 + vertex 1.63769 1.7177 2.53341 + endloop + endfacet + facet normal 0.276217 0.0986074 0.956024 + outer loop + vertex 1.63977 1.72668 2.53185 + vertex 1.64093 1.72134 2.53207 + vertex 1.64416 1.72498 2.53076 + endloop + endfacet + facet normal 0.26904 0.0975054 0.958181 + outer loop + vertex 1.64947 1.71869 2.52993 + vertex 1.64842 1.72387 2.52969 + vertex 1.64518 1.72015 2.53098 + endloop + endfacet + facet normal 0.266838 0.102074 0.958321 + outer loop + vertex 1.64326 1.72905 2.53058 + vertex 1.64416 1.72498 2.53076 + vertex 1.64733 1.72912 2.52944 + endloop + endfacet + facet normal 0.280609 0.0959518 0.955014 + outer loop + vertex 1.65252 1.72299 2.52858 + vertex 1.65167 1.72765 2.52836 + vertex 1.64842 1.72387 2.52969 + endloop + endfacet + facet normal 0.26742 0.101864 0.958181 + outer loop + vertex 1.64733 1.72912 2.52944 + vertex 1.65091 1.73161 2.52817 + vertex 1.64844 1.73357 2.52866 + endloop + endfacet + facet normal 0.316814 0.0863411 0.94455 + outer loop + vertex 1.65562 1.72669 2.52712 + vertex 1.6548 1.73183 2.52693 + vertex 1.65167 1.72765 2.52836 + endloop + endfacet + facet normal 0.270078 0.105501 0.957041 + outer loop + vertex 1.65091 1.73161 2.52817 + vertex 1.65199 1.73607 2.52738 + vertex 1.64844 1.73357 2.52866 + endloop + endfacet + facet normal 0.376489 0.0995628 0.921055 + outer loop + vertex 1.6581 1.7342 2.52545 + vertex 1.65904 1.73852 2.5246 + vertex 1.65588 1.73622 2.52614 + endloop + endfacet + facet normal 0.422519 0.0978956 0.901052 + outer loop + vertex 1.65904 1.73852 2.5246 + vertex 1.66173 1.74246 2.52291 + vertex 1.65808 1.74382 2.52447 + endloop + endfacet + facet normal 0.417794 0.0808289 0.904939 + outer loop + vertex 1.66173 1.74246 2.52291 + vertex 1.6612 1.74733 2.52272 + vertex 1.65808 1.74382 2.52447 + endloop + endfacet + facet normal 0.395621 0.104364 0.912465 + outer loop + vertex 1.65808 1.74382 2.52447 + vertex 1.6612 1.74733 2.52272 + vertex 1.65717 1.74924 2.52424 + endloop + endfacet + facet normal 0.385264 0.076845 0.919601 + outer loop + vertex 1.6612 1.74733 2.52272 + vertex 1.66106 1.7522 2.52237 + vertex 1.65717 1.74924 2.52424 + endloop + endfacet + facet normal 0.384887 0.0774113 0.919712 + outer loop + vertex 1.65717 1.74924 2.52424 + vertex 1.66106 1.7522 2.52237 + vertex 1.65813 1.75387 2.52346 + endloop + endfacet + facet normal 0.38793 0.0839423 0.917858 + outer loop + vertex 1.66106 1.7522 2.52237 + vertex 1.66078 1.75684 2.52206 + vertex 1.65813 1.75387 2.52346 + endloop + endfacet + facet normal 0.289511 0.109146 0.950931 + outer loop + vertex 1.65089 1.74134 2.52711 + vertex 1.65199 1.73607 2.52738 + vertex 1.65504 1.7402 2.52598 + endloop + endfacet + facet normal 0.266827 0.109606 0.957491 + outer loop + vertex 1.65089 1.74134 2.52711 + vertex 1.64974 1.74654 2.52683 + vertex 1.64675 1.74251 2.52813 + endloop + endfacet + facet normal 0.266674 0.111595 0.957304 + outer loop + vertex 1.65069 1.75094 2.52606 + vertex 1.64653 1.75078 2.52723 + vertex 1.64974 1.74654 2.52683 + endloop + endfacet + facet normal 0.270243 0.116751 0.955687 + outer loop + vertex 1.65069 1.75094 2.52606 + vertex 1.65412 1.75351 2.52477 + vertex 1.64961 1.75497 2.52587 + endloop + endfacet + facet normal 0.308711 0.110604 0.944703 + outer loop + vertex 1.6532 1.74903 2.52557 + vertex 1.65406 1.74503 2.52575 + vertex 1.65717 1.74924 2.52424 + endloop + endfacet + facet normal 0.356937 0.115875 0.926914 + outer loop + vertex 1.65813 1.75387 2.52346 + vertex 1.66078 1.75684 2.52206 + vertex 1.65703 1.75774 2.5234 + endloop + endfacet + facet normal 0.27146 0.116746 0.955343 + outer loop + vertex 1.65261 1.75909 2.52454 + vertex 1.65603 1.76162 2.52326 + vertex 1.65342 1.76356 2.52376 + endloop + endfacet + facet normal 0.353328 0.0952884 0.930634 + outer loop + vertex 1.66078 1.75684 2.52206 + vertex 1.65987 1.76182 2.5219 + vertex 1.65703 1.75774 2.5234 + endloop + endfacet + facet normal 0.278233 0.126724 0.952117 + outer loop + vertex 1.65603 1.76162 2.52326 + vertex 1.65681 1.76612 2.52243 + vertex 1.65342 1.76356 2.52376 + endloop + endfacet + facet normal 0.275776 0.130121 0.952374 + outer loop + vertex 1.65342 1.76356 2.52376 + vertex 1.65681 1.76612 2.52243 + vertex 1.65222 1.76764 2.52355 + endloop + endfacet + facet normal 0.2738 0.123053 0.953882 + outer loop + vertex 1.65681 1.76612 2.52243 + vertex 1.6552 1.77179 2.52216 + vertex 1.65222 1.76764 2.52355 + endloop + endfacet + facet normal 0.307081 0.13197 0.942489 + outer loop + vertex 1.6552 1.77179 2.52216 + vertex 1.65681 1.76612 2.52243 + vertex 1.65966 1.77024 2.52093 + endloop + endfacet + facet normal 0.423923 0.11794 0.897986 + outer loop + vertex 1.66305 1.76414 2.52025 + vertex 1.6638 1.76852 2.51932 + vertex 1.66077 1.7662 2.52106 + endloop + endfacet + facet normal 0.300462 0.108882 0.947559 + outer loop + vertex 1.65966 1.77024 2.52093 + vertex 1.65855 1.77427 2.52082 + vertex 1.6552 1.77179 2.52216 + endloop + endfacet + facet normal 0.294655 0.117162 0.948394 + outer loop + vertex 1.65603 1.77624 2.52136 + vertex 1.6552 1.77179 2.52216 + vertex 1.65855 1.77427 2.52082 + endloop + endfacet + facet normal 0.298524 0.122633 0.946491 + outer loop + vertex 1.65855 1.77427 2.52082 + vertex 1.65928 1.77853 2.52003 + vertex 1.65603 1.77624 2.52136 + endloop + endfacet + facet normal 0.268937 0.123156 0.955252 + outer loop + vertex 1.65603 1.77624 2.52136 + vertex 1.65201 1.77615 2.5225 + vertex 1.6552 1.77179 2.52216 + endloop + endfacet + facet normal 0.266615 0.121389 0.956128 + outer loop + vertex 1.65201 1.77615 2.5225 + vertex 1.65106 1.77171 2.52333 + vertex 1.6552 1.77179 2.52216 + endloop + endfacet + facet normal 0.261203 0.122794 0.957442 + outer loop + vertex 1.65106 1.77171 2.52333 + vertex 1.65201 1.77615 2.5225 + vertex 1.64848 1.77369 2.52378 + endloop + endfacet + facet normal 0.266219 0.128973 0.955245 + outer loop + vertex 1.65222 1.76764 2.52355 + vertex 1.6552 1.77179 2.52216 + vertex 1.65106 1.77171 2.52333 + endloop + endfacet + facet normal 0.260173 0.125786 0.957334 + outer loop + vertex 1.65342 1.76356 2.52376 + vertex 1.65222 1.76764 2.52355 + vertex 1.64924 1.76353 2.5249 + endloop + endfacet + facet normal 0.26823 0.119408 0.955926 + outer loop + vertex 1.64847 1.75904 2.52568 + vertex 1.64924 1.76353 2.5249 + vertex 1.64582 1.76111 2.52617 + endloop + endfacet + facet normal 0.280261 0.118868 0.952536 + outer loop + vertex 1.64582 1.76111 2.52617 + vertex 1.64175 1.76114 2.52736 + vertex 1.64502 1.75661 2.52696 + endloop + endfacet + facet normal 0.289085 0.123981 0.949241 + outer loop + vertex 1.64175 1.76114 2.52736 + vertex 1.64012 1.7668 2.52711 + vertex 1.63733 1.76265 2.52851 + endloop + endfacet + facet normal 0.272684 0.124582 0.954004 + outer loop + vertex 1.64349 1.76922 2.52579 + vertex 1.64463 1.76519 2.52599 + vertex 1.64759 1.76923 2.52461 + endloop + endfacet + facet normal 0.272707 0.12392 0.954083 + outer loop + vertex 1.64349 1.76922 2.52579 + vertex 1.64759 1.76923 2.52461 + vertex 1.64444 1.7736 2.52495 + endloop + endfacet + facet normal 0.289961 0.12427 0.948936 + outer loop + vertex 1.64096 1.77124 2.52628 + vertex 1.63692 1.7713 2.5275 + vertex 1.64012 1.7668 2.52711 + endloop + endfacet + facet normal 0.288952 0.117933 0.950052 + outer loop + vertex 1.63692 1.7713 2.5275 + vertex 1.63599 1.77655 2.52714 + vertex 1.63322 1.77356 2.52835 + endloop + endfacet + facet normal 0.293171 0.106461 0.950114 + outer loop + vertex 1.63484 1.78166 2.52692 + vertex 1.63599 1.77655 2.52714 + vertex 1.63911 1.78006 2.52578 + endloop + endfacet + facet normal 0.282753 0.114475 0.952337 + outer loop + vertex 1.64444 1.7736 2.52495 + vertex 1.64332 1.77888 2.52464 + vertex 1.64008 1.77526 2.52604 + endloop + endfacet + facet normal 0.287598 0.0990995 0.952611 + outer loop + vertex 1.63831 1.78404 2.52561 + vertex 1.63911 1.78006 2.52578 + vertex 1.64229 1.78415 2.52439 + endloop + endfacet + facet normal 0.276611 0.106298 0.955085 + outer loop + vertex 1.64758 1.77774 2.52354 + vertex 1.64661 1.7826 2.52328 + vertex 1.64332 1.77888 2.52464 + endloop + endfacet + facet normal 0.284862 0.0909091 0.954248 + outer loop + vertex 1.64229 1.78415 2.52439 + vertex 1.64585 1.78662 2.52309 + vertex 1.64348 1.78857 2.52362 + endloop + endfacet + facet normal 0.274248 0.0888542 0.957545 + outer loop + vertex 1.64703 1.79103 2.52235 + vertex 1.64585 1.78662 2.52309 + vertex 1.64984 1.78676 2.52194 + endloop + endfacet + facet normal 0.28548 0.0950272 0.953662 + outer loop + vertex 1.6534 1.78918 2.52069 + vertex 1.65417 1.7851 2.52087 + vertex 1.65754 1.78913 2.51946 + endloop + endfacet + facet normal 0.327568 0.105894 0.938875 + outer loop + vertex 1.66159 1.78196 2.51882 + vertex 1.66228 1.78654 2.51806 + vertex 1.65832 1.78361 2.51977 + endloop + endfacet + facet normal 0.285581 0.0890151 0.954212 + outer loop + vertex 1.6534 1.78918 2.52069 + vertex 1.65754 1.78913 2.51946 + vertex 1.65447 1.79357 2.51996 + endloop + endfacet + facet normal 0.304201 0.103851 0.94693 + outer loop + vertex 1.65847 1.79385 2.51874 + vertex 1.66121 1.79684 2.51753 + vertex 1.65732 1.79775 2.51868 + endloop + endfacet + facet normal 0.27649 0.0916412 0.956637 + outer loop + vertex 1.6534 1.78918 2.52069 + vertex 1.65447 1.79357 2.51996 + vertex 1.651 1.79116 2.5212 + endloop + endfacet + facet normal 0.275065 0.089419 0.957258 + outer loop + vertex 1.651 1.79116 2.5212 + vertex 1.64703 1.79103 2.52235 + vertex 1.64984 1.78676 2.52194 + endloop + endfacet + facet normal 0.281199 0.120264 0.952084 + outer loop + vertex 1.64826 1.80396 2.52056 + vertex 1.64919 1.79995 2.52079 + vertex 1.6523 1.80393 2.51937 + endloop + endfacet + facet normal 0.305201 0.109359 0.945988 + outer loop + vertex 1.66121 1.79684 2.51753 + vertex 1.66014 1.80192 2.51729 + vertex 1.65732 1.79775 2.51868 + endloop + endfacet + facet normal 0.281889 0.133472 0.950118 + outer loop + vertex 1.65605 1.80172 2.51857 + vertex 1.65689 1.80636 2.51767 + vertex 1.6523 1.80393 2.51937 + endloop + endfacet + facet normal 0.284054 0.14262 0.948142 + outer loop + vertex 1.65689 1.80636 2.51767 + vertex 1.65541 1.81197 2.51727 + vertex 1.65303 1.80848 2.51851 + endloop + endfacet + facet normal 0.294232 0.145056 0.944662 + outer loop + vertex 1.65869 1.81422 2.51594 + vertex 1.65989 1.81024 2.51618 + vertex 1.66282 1.81407 2.51468 + endloop + endfacet + facet normal 0.294262 0.14145 0.945199 + outer loop + vertex 1.65869 1.81422 2.51594 + vertex 1.66282 1.81407 2.51468 + vertex 1.65936 1.81861 2.51508 + endloop + endfacet + facet normal 0.290553 0.138486 0.946784 + outer loop + vertex 1.65936 1.81861 2.51508 + vertex 1.66282 1.81407 2.51468 + vertex 1.66357 1.81867 2.51378 + endloop + endfacet + facet normal 0.282474 0.145349 0.9482 + outer loop + vertex 1.65189 1.81637 2.51764 + vertex 1.65137 1.81181 2.5185 + vertex 1.65541 1.81197 2.51727 + endloop + endfacet + facet normal 0.282626 0.145419 0.948143 + outer loop + vertex 1.65031 1.82194 2.51726 + vertex 1.65189 1.81637 2.51764 + vertex 1.65477 1.82025 2.51619 + endloop + endfacet + facet normal 0.283027 0.143763 0.948276 + outer loop + vertex 1.65869 1.81422 2.51594 + vertex 1.65936 1.81861 2.51508 + vertex 1.656 1.81628 2.51643 + endloop + endfacet + facet normal 0.278186 0.145184 0.949492 + outer loop + vertex 1.65358 1.82421 2.51593 + vertex 1.65477 1.82025 2.51619 + vertex 1.65764 1.82421 2.51474 + endloop + endfacet + facet normal 0.290709 0.135518 0.947166 + outer loop + vertex 1.66357 1.81867 2.51378 + vertex 1.66213 1.82275 2.51363 + vertex 1.65936 1.81861 2.51508 + endloop + endfacet + facet normal 0.305008 0.140377 0.941947 + outer loop + vertex 1.66357 1.81867 2.51378 + vertex 1.66625 1.82163 2.51247 + vertex 1.66213 1.82275 2.51363 + endloop + endfacet + facet normal 0.318742 0.126808 0.939321 + outer loop + vertex 1.66727 1.81637 2.51283 + vertex 1.66625 1.82163 2.51247 + vertex 1.66357 1.81867 2.51378 + endloop + endfacet + facet normal 0.321351 0.131651 0.937764 + outer loop + vertex 1.66282 1.81407 2.51468 + vertex 1.66727 1.81637 2.51283 + vertex 1.66357 1.81867 2.51378 + endloop + endfacet + facet normal 0.317966 0.138364 0.937951 + outer loop + vertex 1.66656 1.81195 2.51372 + vertex 1.66727 1.81637 2.51283 + vertex 1.66282 1.81407 2.51468 + endloop + endfacet + facet normal 0.318623 0.139714 0.937528 + outer loop + vertex 1.66424 1.80855 2.51502 + vertex 1.66656 1.81195 2.51372 + vertex 1.66282 1.81407 2.51468 + endloop + endfacet + facet normal 0.343142 0.120713 0.931494 + outer loop + vertex 1.66794 1.8088 2.51362 + vertex 1.66656 1.81195 2.51372 + vertex 1.66424 1.80855 2.51502 + endloop + endfacet + facet normal 0.344357 0.108356 0.932565 + outer loop + vertex 1.66424 1.80855 2.51502 + vertex 1.66729 1.80432 2.51438 + vertex 1.66794 1.8088 2.51362 + endloop + endfacet + facet normal 0.361989 0.122339 0.924119 + outer loop + vertex 1.66352 1.80427 2.51587 + vertex 1.66729 1.80432 2.51438 + vertex 1.66424 1.80855 2.51502 + endloop + endfacet + facet normal 0.362634 0.11089 0.925311 + outer loop + vertex 1.66352 1.80427 2.51587 + vertex 1.66431 1.80028 2.51604 + vertex 1.66729 1.80432 2.51438 + endloop + endfacet + facet normal 0.322608 0.103602 0.940846 + outer loop + vertex 1.66431 1.80028 2.51604 + vertex 1.66352 1.80427 2.51587 + vertex 1.66014 1.80192 2.51729 + endloop + endfacet + facet normal 0.32578 0.113385 0.938622 + outer loop + vertex 1.66014 1.80192 2.51729 + vertex 1.66121 1.79684 2.51753 + vertex 1.66431 1.80028 2.51604 + endloop + endfacet + facet normal 0.354538 0.132783 0.925566 + outer loop + vertex 1.66625 1.82163 2.51247 + vertex 1.66727 1.81637 2.51283 + vertex 1.67018 1.82017 2.51117 + endloop + endfacet + facet normal 0.350839 0.120053 0.928708 + outer loop + vertex 1.66916 1.82507 2.51092 + vertex 1.66625 1.82163 2.51247 + vertex 1.67018 1.82017 2.51117 + endloop + endfacet + facet normal 0.40718 0.130546 0.90397 + outer loop + vertex 1.67018 1.82017 2.51117 + vertex 1.67298 1.8236 2.50941 + vertex 1.66916 1.82507 2.51092 + endloop + endfacet + facet normal 0.402523 0.113955 0.908289 + outer loop + vertex 1.67298 1.8236 2.50941 + vertex 1.67187 1.829 2.50923 + vertex 1.66916 1.82507 2.51092 + endloop + endfacet + facet normal 0.380218 0.13236 0.915377 + outer loop + vertex 1.66825 1.82907 2.51072 + vertex 1.66916 1.82507 2.51092 + vertex 1.67187 1.829 2.50923 + endloop + endfacet + facet normal 0.380046 0.137038 0.91476 + outer loop + vertex 1.66825 1.82907 2.51072 + vertex 1.67187 1.829 2.50923 + vertex 1.66904 1.83321 2.50978 + endloop + endfacet + facet normal 0.365268 0.126098 0.922322 + outer loop + vertex 1.66904 1.83321 2.50978 + vertex 1.67187 1.829 2.50923 + vertex 1.67218 1.83273 2.5086 + endloop + endfacet + facet normal 0.325354 0.120968 0.937823 + outer loop + vertex 1.66916 1.82507 2.51092 + vertex 1.66825 1.82907 2.51072 + vertex 1.66496 1.82678 2.51216 + endloop + endfacet + facet normal 0.331241 0.138718 0.933293 + outer loop + vertex 1.66496 1.82678 2.51216 + vertex 1.66625 1.82163 2.51247 + vertex 1.66916 1.82507 2.51092 + endloop + endfacet + facet normal 0.275883 0.145618 0.950097 + outer loop + vertex 1.65764 1.82421 2.51474 + vertex 1.66099 1.82667 2.51339 + vertex 1.65839 1.82859 2.51385 + endloop + endfacet + facet normal 0.303306 0.132276 0.943668 + outer loop + vertex 1.66625 1.82163 2.51247 + vertex 1.66496 1.82678 2.51216 + vertex 1.66213 1.82275 2.51363 + endloop + endfacet + facet normal 0.277677 0.148262 0.949165 + outer loop + vertex 1.66099 1.82667 2.51339 + vertex 1.66176 1.83105 2.51248 + vertex 1.65839 1.82859 2.51385 + endloop + endfacet + facet normal 0.282026 0.155688 0.946691 + outer loop + vertex 1.66009 1.83657 2.51207 + vertex 1.66176 1.83105 2.51248 + vertex 1.66466 1.835 2.51097 + endloop + endfacet + facet normal 0.327036 0.151243 0.932831 + outer loop + vertex 1.66825 1.82907 2.51072 + vertex 1.66904 1.83321 2.50978 + vertex 1.6658 1.83107 2.51126 + endloop + endfacet + facet normal 0.302895 0.158774 0.939705 + outer loop + vertex 1.66343 1.83896 2.5107 + vertex 1.66466 1.835 2.51097 + vertex 1.66757 1.83893 2.50937 + endloop + endfacet + facet normal 0.367541 0.153014 0.917333 + outer loop + vertex 1.67218 1.83273 2.5086 + vertex 1.6724 1.83648 2.50788 + vertex 1.66904 1.83321 2.50978 + endloop + endfacet + facet normal 0.303048 0.1552 0.940253 + outer loop + vertex 1.66343 1.83896 2.5107 + vertex 1.66757 1.83893 2.50937 + vertex 1.66395 1.84327 2.50982 + endloop + endfacet + facet normal 0.277615 0.162086 0.94692 + outer loop + vertex 1.66395 1.84327 2.50982 + vertex 1.66621 1.84681 2.50855 + vertex 1.66221 1.84887 2.50937 + endloop + endfacet + facet normal 0.340965 0.138877 0.929761 + outer loop + vertex 1.67126 1.8419 2.50756 + vertex 1.67007 1.84702 2.50723 + vertex 1.66787 1.84359 2.50855 + endloop + endfacet + facet normal 0.279218 0.165633 0.945834 + outer loop + vertex 1.66621 1.84681 2.50855 + vertex 1.66673 1.85131 2.50761 + vertex 1.66221 1.84887 2.50937 + endloop + endfacet + facet normal 0.280343 0.163878 0.945808 + outer loop + vertex 1.66673 1.85131 2.50761 + vertex 1.66521 1.85672 2.50712 + vertex 1.66276 1.85339 2.50843 + endloop + endfacet + facet normal 0.32412 0.165689 0.931393 + outer loop + vertex 1.66841 1.85902 2.50574 + vertex 1.66962 1.85512 2.50601 + vertex 1.6724 1.85906 2.50435 + endloop + endfacet + facet normal 0.324378 0.161661 0.932011 + outer loop + vertex 1.66841 1.85902 2.50574 + vertex 1.6724 1.85906 2.50435 + vertex 1.66893 1.86325 2.50483 + endloop + endfacet + facet normal 0.314177 0.152643 0.937013 + outer loop + vertex 1.66893 1.86325 2.50483 + vertex 1.6724 1.85906 2.50435 + vertex 1.67275 1.86357 2.50349 + endloop + endfacet + facet normal 0.275954 0.165243 0.94686 + outer loop + vertex 1.66174 1.86088 2.50741 + vertex 1.66131 1.85656 2.50829 + vertex 1.66521 1.85672 2.50712 + endloop + endfacet + facet normal 0.278182 0.167021 0.945896 + outer loop + vertex 1.65975 1.86652 2.507 + vertex 1.66174 1.86088 2.50741 + vertex 1.66445 1.86484 2.50591 + endloop + endfacet + facet normal 0.291483 0.167787 0.941746 + outer loop + vertex 1.66841 1.85902 2.50574 + vertex 1.66893 1.86325 2.50483 + vertex 1.66577 1.86092 2.50622 + endloop + endfacet + facet normal 0.282337 0.169864 0.944157 + outer loop + vertex 1.66302 1.8689 2.50561 + vertex 1.66445 1.86484 2.50591 + vertex 1.66724 1.86879 2.50437 + endloop + endfacet + facet normal 0.313848 0.155248 0.936695 + outer loop + vertex 1.67275 1.86357 2.50349 + vertex 1.67119 1.8667 2.5035 + vertex 1.66893 1.86325 2.50483 + endloop + endfacet + facet normal 0.282299 0.171402 0.94389 + outer loop + vertex 1.66302 1.8689 2.50561 + vertex 1.66724 1.86879 2.50437 + vertex 1.66323 1.87363 2.50469 + endloop + endfacet + facet normal 0.278457 0.174725 0.944422 + outer loop + vertex 1.66323 1.87363 2.50469 + vertex 1.66603 1.87666 2.5033 + vertex 1.66319 1.8783 2.50383 + endloop + endfacet + facet normal 0.297665 0.16834 0.939711 + outer loop + vertex 1.6717 1.87118 2.50253 + vertex 1.66993 1.87676 2.50209 + vertex 1.66769 1.87336 2.5034 + endloop + endfacet + facet normal 0.279745 0.177232 0.943574 + outer loop + vertex 1.66603 1.87666 2.5033 + vertex 1.66598 1.88133 2.50244 + vertex 1.66319 1.8783 2.50383 + endloop + endfacet + facet normal 0.30043 0.181127 0.936448 + outer loop + vertex 1.66901 1.88408 2.50101 + vertex 1.67026 1.88096 2.50122 + vertex 1.67333 1.88362 2.49972 + endloop + endfacet + facet normal 0.300148 0.174977 0.937707 + outer loop + vertex 1.66901 1.88408 2.50101 + vertex 1.67333 1.88362 2.49972 + vertex 1.66946 1.88842 2.50006 + endloop + endfacet + facet normal 0.295435 0.17102 0.939931 + outer loop + vertex 1.66946 1.88842 2.50006 + vertex 1.67333 1.88362 2.49972 + vertex 1.67366 1.88848 2.49873 + endloop + endfacet + facet normal 0.278671 0.178538 0.943645 + outer loop + vertex 1.66195 1.88616 2.50272 + vertex 1.66152 1.88159 2.50371 + vertex 1.66598 1.88133 2.50244 + endloop + endfacet + facet normal 0.277846 0.178155 0.943961 + outer loop + vertex 1.66021 1.89174 2.50217 + vertex 1.66195 1.88616 2.50272 + vertex 1.66475 1.89007 2.50115 + endloop + endfacet + facet normal 0.283328 0.177775 0.942402 + outer loop + vertex 1.66901 1.88408 2.50101 + vertex 1.66946 1.88842 2.50006 + vertex 1.66617 1.88604 2.50149 + endloop + endfacet + facet normal 0.277773 0.178202 0.943974 + outer loop + vertex 1.66344 1.89398 2.5008 + vertex 1.66475 1.89007 2.50115 + vertex 1.66746 1.89399 2.49961 + endloop + endfacet + facet normal 0.295459 0.170651 0.93999 + outer loop + vertex 1.67366 1.88848 2.49873 + vertex 1.672 1.89257 2.49851 + vertex 1.66946 1.88842 2.50006 + endloop + endfacet + facet normal 0.312312 0.177117 0.933322 + outer loop + vertex 1.67366 1.88848 2.49873 + vertex 1.6761 1.89146 2.49734 + vertex 1.672 1.89257 2.49851 + endloop + endfacet + facet normal 0.328357 0.162633 0.930447 + outer loop + vertex 1.67733 1.88634 2.49781 + vertex 1.6761 1.89146 2.49734 + vertex 1.67366 1.88848 2.49873 + endloop + endfacet + facet normal 0.330229 0.16642 0.929114 + outer loop + vertex 1.67333 1.88362 2.49972 + vertex 1.67733 1.88634 2.49781 + vertex 1.67366 1.88848 2.49873 + endloop + endfacet + facet normal 0.326889 0.171518 0.929368 + outer loop + vertex 1.67693 1.88275 2.49861 + vertex 1.67733 1.88634 2.49781 + vertex 1.67333 1.88362 2.49972 + endloop + endfacet + facet normal 0.32447 0.157261 0.932732 + outer loop + vertex 1.67333 1.88362 2.49972 + vertex 1.67687 1.87896 2.49927 + vertex 1.67693 1.88275 2.49861 + endloop + endfacet + facet normal 0.340775 0.170459 0.924563 + outer loop + vertex 1.67301 1.87904 2.50068 + vertex 1.67687 1.87896 2.49927 + vertex 1.67333 1.88362 2.49972 + endloop + endfacet + facet normal 0.340729 0.171576 0.924373 + outer loop + vertex 1.67301 1.87904 2.50068 + vertex 1.67443 1.87501 2.5009 + vertex 1.67687 1.87896 2.49927 + endloop + endfacet + facet normal 0.369759 0.150474 0.916862 + outer loop + vertex 1.67872 1.8732 2.49947 + vertex 1.67687 1.87896 2.49927 + vertex 1.67443 1.87501 2.5009 + endloop + endfacet + facet normal 0.378173 0.176923 0.908671 + outer loop + vertex 1.67571 1.87104 2.50114 + vertex 1.67872 1.8732 2.49947 + vertex 1.67443 1.87501 2.5009 + endloop + endfacet + facet normal 0.327093 0.161702 0.931054 + outer loop + vertex 1.67443 1.87501 2.5009 + vertex 1.6717 1.87118 2.50253 + vertex 1.67571 1.87104 2.50114 + endloop + endfacet + facet normal 0.327231 0.154917 0.932159 + outer loop + vertex 1.67571 1.87104 2.50114 + vertex 1.6717 1.87118 2.50253 + vertex 1.67499 1.8669 2.50208 + endloop + endfacet + facet normal 0.38383 0.140616 0.912634 + outer loop + vertex 1.67571 1.87104 2.50114 + vertex 1.67499 1.8669 2.50208 + vertex 1.6781 1.86892 2.50046 + endloop + endfacet + facet normal 0.336875 0.162831 0.927363 + outer loop + vertex 1.6717 1.87118 2.50253 + vertex 1.67119 1.8667 2.5035 + vertex 1.67499 1.8669 2.50208 + endloop + endfacet + facet normal 0.336498 0.166499 0.926848 + outer loop + vertex 1.67275 1.86357 2.50349 + vertex 1.67499 1.8669 2.50208 + vertex 1.67119 1.8667 2.5035 + endloop + endfacet + facet normal 0.313184 0.172799 0.933839 + outer loop + vertex 1.66993 1.87676 2.50209 + vertex 1.6717 1.87118 2.50253 + vertex 1.67443 1.87501 2.5009 + endloop + endfacet + facet normal 0.393607 0.153706 0.906338 + outer loop + vertex 1.6781 1.86892 2.50046 + vertex 1.67872 1.8732 2.49947 + vertex 1.67571 1.87104 2.50114 + endloop + endfacet + facet normal 0.309586 0.161383 0.937076 + outer loop + vertex 1.67443 1.87501 2.5009 + vertex 1.67301 1.87904 2.50068 + vertex 1.66993 1.87676 2.50209 + endloop + endfacet + facet normal 0.281424 0.178445 0.942846 + outer loop + vertex 1.66746 1.89399 2.49961 + vertex 1.67059 1.89651 2.4982 + vertex 1.6679 1.89824 2.49868 + endloop + endfacet + facet normal 0.310707 0.169147 0.935334 + outer loop + vertex 1.6761 1.89146 2.49734 + vertex 1.6745 1.89659 2.49695 + vertex 1.672 1.89257 2.49851 + endloop + endfacet + facet normal 0.283832 0.182617 0.941324 + outer loop + vertex 1.67059 1.89651 2.4982 + vertex 1.67083 1.90115 2.49723 + vertex 1.6679 1.89824 2.49868 + endloop + endfacet + facet normal 0.326668 0.191945 0.925443 + outer loop + vertex 1.67386 1.90386 2.49576 + vertex 1.67503 1.90079 2.49598 + vertex 1.678 1.90337 2.4944 + endloop + endfacet + facet normal 0.326252 0.183159 0.927369 + outer loop + vertex 1.67386 1.90386 2.49576 + vertex 1.678 1.90337 2.4944 + vertex 1.67411 1.90807 2.49484 + endloop + endfacet + facet normal 0.315145 0.173433 0.933062 + outer loop + vertex 1.67411 1.90807 2.49484 + vertex 1.678 1.90337 2.4944 + vertex 1.67793 1.90829 2.49351 + endloop + endfacet + facet normal 0.282293 0.185481 0.941226 + outer loop + vertex 1.6668 1.90594 2.49749 + vertex 1.6664 1.90143 2.49851 + vertex 1.67083 1.90115 2.49723 + endloop + endfacet + facet normal 0.283062 0.186623 0.94077 + outer loop + vertex 1.66481 1.91159 2.49697 + vertex 1.6668 1.90594 2.49749 + vertex 1.66948 1.90981 2.49592 + endloop + endfacet + facet normal 0.29329 0.187281 0.9375 + outer loop + vertex 1.67386 1.90386 2.49576 + vertex 1.67411 1.90807 2.49484 + vertex 1.67105 1.90577 2.49625 + endloop + endfacet + facet normal 0.28154 0.185551 0.941438 + outer loop + vertex 1.66793 1.91385 2.49559 + vertex 1.66948 1.90981 2.49592 + vertex 1.67214 1.91372 2.49436 + endloop + endfacet + facet normal 0.315219 0.172758 0.933162 + outer loop + vertex 1.67793 1.90829 2.49351 + vertex 1.67615 1.91157 2.4935 + vertex 1.67411 1.90807 2.49484 + endloop + endfacet + facet normal 0.281681 0.179742 0.942523 + outer loop + vertex 1.66793 1.91385 2.49559 + vertex 1.67214 1.91372 2.49436 + vertex 1.66812 1.9185 2.49465 + endloop + endfacet + facet normal 0.278634 0.178242 0.943712 + outer loop + vertex 1.66812 1.9185 2.49465 + vertex 1.67095 1.92153 2.49324 + vertex 1.66816 1.92313 2.49376 + endloop + endfacet + facet normal 0.296952 0.171591 0.939349 + outer loop + vertex 1.67654 1.91607 2.49251 + vertex 1.67483 1.92166 2.49203 + vertex 1.67255 1.91827 2.49337 + endloop + endfacet + facet normal 0.279623 0.180189 0.94305 + outer loop + vertex 1.67095 1.92153 2.49324 + vertex 1.67095 1.92616 2.49235 + vertex 1.66816 1.92313 2.49376 + endloop + endfacet + facet normal 0.297531 0.187222 0.936175 + outer loop + vertex 1.67395 1.92889 2.49093 + vertex 1.6752 1.92583 2.49114 + vertex 1.6782 1.9285 2.48965 + endloop + endfacet + facet normal 0.297528 0.187108 0.936199 + outer loop + vertex 1.67395 1.92889 2.49093 + vertex 1.6782 1.9285 2.48965 + vertex 1.67424 1.93309 2.48999 + endloop + endfacet + facet normal 0.289086 0.179518 0.94032 + outer loop + vertex 1.67424 1.93309 2.48999 + vertex 1.6782 1.9285 2.48965 + vertex 1.67826 1.93327 2.48872 + endloop + endfacet + facet normal 0.317971 0.177355 0.931365 + outer loop + vertex 1.6782 1.9285 2.48965 + vertex 1.68208 1.93139 2.48778 + vertex 1.67826 1.93327 2.48872 + endloop + endfacet + facet normal 0.317229 0.175558 0.931958 + outer loop + vertex 1.68208 1.93139 2.48778 + vertex 1.68039 1.93676 2.48734 + vertex 1.67826 1.93327 2.48872 + endloop + endfacet + facet normal 0.296802 0.189542 0.935939 + outer loop + vertex 1.67826 1.93327 2.48872 + vertex 1.68039 1.93676 2.48734 + vertex 1.67638 1.93658 2.48865 + endloop + endfacet + facet normal 0.319981 0.174549 0.931206 + outer loop + vertex 1.68184 1.92772 2.48855 + vertex 1.68208 1.93139 2.48778 + vertex 1.6782 1.9285 2.48965 + endloop + endfacet + facet normal 0.317429 0.157007 0.935194 + outer loop + vertex 1.6782 1.9285 2.48965 + vertex 1.68183 1.92385 2.4892 + vertex 1.68184 1.92772 2.48855 + endloop + endfacet + facet normal 0.371247 0.153617 0.915739 + outer loop + vertex 1.68183 1.92385 2.4892 + vertex 1.68506 1.92714 2.48734 + vertex 1.68184 1.92772 2.48855 + endloop + endfacet + facet normal 0.383505 0.139972 0.91287 + outer loop + vertex 1.68627 1.92192 2.48763 + vertex 1.68506 1.92714 2.48734 + vertex 1.68183 1.92385 2.4892 + endloop + endfacet + facet normal 0.388888 0.156334 0.907924 + outer loop + vertex 1.68378 1.91787 2.48939 + vertex 1.68627 1.92192 2.48763 + vertex 1.68183 1.92385 2.4892 + endloop + endfacet + facet normal 0.366692 0.149436 0.918262 + outer loop + vertex 1.68378 1.91787 2.48939 + vertex 1.68183 1.92385 2.4892 + vertex 1.67931 1.91986 2.49085 + endloop + endfacet + facet normal 0.375719 0.175827 0.909901 + outer loop + vertex 1.68059 1.9158 2.49111 + vertex 1.68378 1.91787 2.48939 + vertex 1.67931 1.91986 2.49085 + endloop + endfacet + facet normal 0.332077 0.163255 0.929017 + outer loop + vertex 1.67931 1.91986 2.49085 + vertex 1.67654 1.91607 2.49251 + vertex 1.68059 1.9158 2.49111 + endloop + endfacet + facet normal 0.332106 0.169509 0.927886 + outer loop + vertex 1.68059 1.9158 2.49111 + vertex 1.67654 1.91607 2.49251 + vertex 1.67997 1.91164 2.49209 + endloop + endfacet + facet normal 0.385208 0.157194 0.909343 + outer loop + vertex 1.68059 1.9158 2.49111 + vertex 1.67997 1.91164 2.49209 + vertex 1.68316 1.91348 2.49042 + endloop + endfacet + facet normal 0.337739 0.174148 0.924989 + outer loop + vertex 1.67654 1.91607 2.49251 + vertex 1.67615 1.91157 2.4935 + vertex 1.67997 1.91164 2.49209 + endloop + endfacet + facet normal 0.336919 0.1845 0.92328 + outer loop + vertex 1.67793 1.90829 2.49351 + vertex 1.67997 1.91164 2.49209 + vertex 1.67615 1.91157 2.4935 + endloop + endfacet + facet normal 0.365539 0.164025 0.91623 + outer loop + vertex 1.68132 1.90664 2.49245 + vertex 1.67997 1.91164 2.49209 + vertex 1.67793 1.90829 2.49351 + endloop + endfacet + facet normal 0.368131 0.170804 0.913951 + outer loop + vertex 1.678 1.90337 2.4944 + vertex 1.68132 1.90664 2.49245 + vertex 1.67793 1.90829 2.49351 + endloop + endfacet + facet normal 0.382031 0.154992 0.91106 + outer loop + vertex 1.68279 1.90194 2.49263 + vertex 1.68132 1.90664 2.49245 + vertex 1.678 1.90337 2.4944 + endloop + endfacet + facet normal 0.387374 0.181811 0.903818 + outer loop + vertex 1.678 1.90337 2.4944 + vertex 1.68089 1.89825 2.49419 + vertex 1.68279 1.90194 2.49263 + endloop + endfacet + facet normal 0.447786 0.141974 0.882797 + outer loop + vertex 1.68279 1.90194 2.49263 + vertex 1.68089 1.89825 2.49419 + vertex 1.68507 1.89718 2.49224 + endloop + endfacet + facet normal 0.452567 0.144509 0.879943 + outer loop + vertex 1.68595 1.90119 2.49113 + vertex 1.68279 1.90194 2.49263 + vertex 1.68507 1.89718 2.49224 + endloop + endfacet + facet normal 0.525619 0.118196 0.84247 + outer loop + vertex 1.68595 1.90119 2.49113 + vertex 1.68507 1.89718 2.49224 + vertex 1.6879 1.89896 2.49023 + endloop + endfacet + facet normal 0.536971 0.131859 0.833232 + outer loop + vertex 1.6879 1.89896 2.49023 + vertex 1.68848 1.90309 2.4892 + vertex 1.68595 1.90119 2.49113 + endloop + endfacet + facet normal 0.51871 0.162428 0.839379 + outer loop + vertex 1.68595 1.90119 2.49113 + vertex 1.68848 1.90309 2.4892 + vertex 1.685 1.90496 2.49099 + endloop + endfacet + facet normal 0.504326 0.120651 0.855043 + outer loop + vertex 1.68848 1.90309 2.4892 + vertex 1.68709 1.9075 2.4894 + vertex 1.685 1.90496 2.49099 + endloop + endfacet + facet normal 0.469632 0.157685 0.868666 + outer loop + vertex 1.685 1.90496 2.49099 + vertex 1.68709 1.9075 2.4894 + vertex 1.684 1.90947 2.49071 + endloop + endfacet + facet normal 0.422984 0.148921 0.893816 + outer loop + vertex 1.684 1.90947 2.49071 + vertex 1.68132 1.90664 2.49245 + vertex 1.685 1.90496 2.49099 + endloop + endfacet + facet normal 0.40171 0.172516 0.89937 + outer loop + vertex 1.67997 1.91164 2.49209 + vertex 1.68132 1.90664 2.49245 + vertex 1.684 1.90947 2.49071 + endloop + endfacet + facet normal 0.390973 0.146607 0.908651 + outer loop + vertex 1.684 1.90947 2.49071 + vertex 1.68316 1.91348 2.49042 + vertex 1.67997 1.91164 2.49209 + endloop + endfacet + facet normal 0.447814 0.156554 0.880314 + outer loop + vertex 1.68316 1.91348 2.49042 + vertex 1.684 1.90947 2.49071 + vertex 1.68724 1.91255 2.48851 + endloop + endfacet + facet normal 0.446324 0.14407 0.883198 + outer loop + vertex 1.68316 1.91348 2.49042 + vertex 1.68724 1.91255 2.48851 + vertex 1.68378 1.91787 2.48939 + endloop + endfacet + facet normal 0.46124 0.139537 0.876235 + outer loop + vertex 1.68709 1.9075 2.4894 + vertex 1.68724 1.91255 2.48851 + vertex 1.684 1.90947 2.49071 + endloop + endfacet + facet normal 0.452935 0.14741 0.879273 + outer loop + vertex 1.685 1.90496 2.49099 + vertex 1.68279 1.90194 2.49263 + vertex 1.68595 1.90119 2.49113 + endloop + endfacet + facet normal 0.45116 0.166014 0.876866 + outer loop + vertex 1.68255 1.89332 2.49427 + vertex 1.68507 1.89718 2.49224 + vertex 1.68089 1.89825 2.49419 + endloop + endfacet + facet normal 0.407136 0.151594 0.9007 + outer loop + vertex 1.68255 1.89332 2.49427 + vertex 1.68089 1.89825 2.49419 + vertex 1.67871 1.89475 2.49576 + endloop + endfacet + facet normal 0.411206 0.16736 0.896047 + outer loop + vertex 1.67999 1.88998 2.49607 + vertex 1.68255 1.89332 2.49427 + vertex 1.67871 1.89475 2.49576 + endloop + endfacet + facet normal 0.360983 0.155416 0.919531 + outer loop + vertex 1.67871 1.89475 2.49576 + vertex 1.6761 1.89146 2.49734 + vertex 1.67999 1.88998 2.49607 + endloop + endfacet + facet normal 0.36516 0.170087 0.915275 + outer loop + vertex 1.6761 1.89146 2.49734 + vertex 1.67733 1.88634 2.49781 + vertex 1.67999 1.88998 2.49607 + endloop + endfacet + facet normal 0.382413 0.15535 0.910838 + outer loop + vertex 1.67999 1.88998 2.49607 + vertex 1.67733 1.88634 2.49781 + vertex 1.68092 1.88603 2.49635 + endloop + endfacet + facet normal 0.455999 0.169909 0.873611 + outer loop + vertex 1.68092 1.88603 2.49635 + vertex 1.68379 1.88796 2.49448 + vertex 1.67999 1.88998 2.49607 + endloop + endfacet + facet normal 0.46698 0.151261 0.871234 + outer loop + vertex 1.68303 1.88382 2.4956 + vertex 1.68379 1.88796 2.49448 + vertex 1.68092 1.88603 2.49635 + endloop + endfacet + facet normal 0.451444 0.132646 0.882385 + outer loop + vertex 1.68092 1.88603 2.49635 + vertex 1.68006 1.8821 2.49738 + vertex 1.68303 1.88382 2.4956 + endloop + endfacet + facet normal 0.461351 0.113012 0.879991 + outer loop + vertex 1.68372 1.87983 2.49575 + vertex 1.68303 1.88382 2.4956 + vertex 1.68006 1.8821 2.49738 + endloop + endfacet + facet normal 0.479419 0.153528 0.864052 + outer loop + vertex 1.68006 1.8821 2.49738 + vertex 1.68114 1.87702 2.49769 + vertex 1.68372 1.87983 2.49575 + endloop + endfacet + facet normal 0.511015 0.115907 0.851721 + outer loop + vertex 1.68372 1.87983 2.49575 + vertex 1.68114 1.87702 2.49769 + vertex 1.68446 1.87509 2.49595 + endloop + endfacet + facet normal 0.52238 0.145928 0.840133 + outer loop + vertex 1.68114 1.87702 2.49769 + vertex 1.68228 1.87286 2.4977 + vertex 1.68446 1.87509 2.49595 + endloop + endfacet + facet normal 0.560713 0.0948214 0.822563 + outer loop + vertex 1.68446 1.87509 2.49595 + vertex 1.68228 1.87286 2.4977 + vertex 1.68481 1.8704 2.49626 + endloop + endfacet + facet normal 0.643565 0.0968302 0.759242 + outer loop + vertex 1.68481 1.8704 2.49626 + vertex 1.68721 1.87283 2.49391 + vertex 1.68446 1.87509 2.49595 + endloop + endfacet + facet normal 0.636657 0.0816381 0.766814 + outer loop + vertex 1.68721 1.87283 2.49391 + vertex 1.68682 1.87783 2.4937 + vertex 1.68446 1.87509 2.49595 + endloop + endfacet + facet normal 0.603139 0.127495 0.787381 + outer loop + vertex 1.68446 1.87509 2.49595 + vertex 1.68682 1.87783 2.4937 + vertex 1.68372 1.87983 2.49575 + endloop + endfacet + facet normal 0.591193 0.0951654 0.800896 + outer loop + vertex 1.68682 1.87783 2.4937 + vertex 1.68621 1.88329 2.49351 + vertex 1.68372 1.87983 2.49575 + endloop + endfacet + facet normal 0.560906 0.127946 0.817933 + outer loop + vertex 1.68303 1.88382 2.4956 + vertex 1.68372 1.87983 2.49575 + vertex 1.68621 1.88329 2.49351 + endloop + endfacet + facet normal 0.557758 0.0903064 0.825076 + outer loop + vertex 1.68228 1.87286 2.4977 + vertex 1.6816 1.86842 2.49864 + vertex 1.68481 1.8704 2.49626 + endloop + endfacet + facet normal 0.56423 0.0762162 0.822092 + outer loop + vertex 1.68481 1.8704 2.49626 + vertex 1.6816 1.86842 2.49864 + vertex 1.68502 1.86553 2.49656 + endloop + endfacet + facet normal 0.584276 0.113182 0.803624 + outer loop + vertex 1.6816 1.86842 2.49864 + vertex 1.68247 1.86288 2.49879 + vertex 1.68502 1.86553 2.49656 + endloop + endfacet + facet normal 0.560546 0.120058 0.819375 + outer loop + vertex 1.68303 1.88382 2.4956 + vertex 1.68621 1.88329 2.49351 + vertex 1.68379 1.88796 2.49448 + endloop + endfacet + facet normal 0.547365 0.111144 0.829481 + outer loop + vertex 1.68379 1.88796 2.49448 + vertex 1.68621 1.88329 2.49351 + vertex 1.68698 1.88772 2.49241 + endloop + endfacet + facet normal 0.547379 0.109067 0.829747 + outer loop + vertex 1.68698 1.88772 2.49241 + vertex 1.68611 1.89185 2.49243 + vertex 1.68379 1.88796 2.49448 + endloop + endfacet + facet normal 0.500833 0.148939 0.852633 + outer loop + vertex 1.68379 1.88796 2.49448 + vertex 1.68611 1.89185 2.49243 + vertex 1.68255 1.89332 2.49427 + endloop + endfacet + facet normal 0.38241 0.155127 0.910878 + outer loop + vertex 1.68092 1.88603 2.49635 + vertex 1.67733 1.88634 2.49781 + vertex 1.68006 1.8821 2.49738 + endloop + endfacet + facet normal 0.389009 0.159743 0.907278 + outer loop + vertex 1.67733 1.88634 2.49781 + vertex 1.67693 1.88275 2.49861 + vertex 1.68006 1.8821 2.49738 + endloop + endfacet + facet normal 0.388104 0.152118 0.908975 + outer loop + vertex 1.67687 1.87896 2.49927 + vertex 1.68006 1.8821 2.49738 + vertex 1.67693 1.88275 2.49861 + endloop + endfacet + facet normal 0.399316 0.139087 0.906202 + outer loop + vertex 1.68114 1.87702 2.49769 + vertex 1.68006 1.8821 2.49738 + vertex 1.67687 1.87896 2.49927 + endloop + endfacet + facet normal 0.406945 0.161734 0.89902 + outer loop + vertex 1.67872 1.8732 2.49947 + vertex 1.68114 1.87702 2.49769 + vertex 1.67687 1.87896 2.49927 + endloop + endfacet + facet normal 0.451063 0.126513 0.88348 + outer loop + vertex 1.68228 1.87286 2.4977 + vertex 1.68114 1.87702 2.49769 + vertex 1.67872 1.8732 2.49947 + endloop + endfacet + facet normal 0.337299 0.176646 0.924676 + outer loop + vertex 1.6745 1.89659 2.49695 + vertex 1.6761 1.89146 2.49734 + vertex 1.67871 1.89475 2.49576 + endloop + endfacet + facet normal 0.331256 0.159394 0.92998 + outer loop + vertex 1.67871 1.89475 2.49576 + vertex 1.67754 1.89879 2.49549 + vertex 1.6745 1.89659 2.49695 + endloop + endfacet + facet normal 0.443609 0.136975 0.885691 + outer loop + vertex 1.68379 1.88796 2.49448 + vertex 1.68255 1.89332 2.49427 + vertex 1.67999 1.88998 2.49607 + endloop + endfacet + facet normal 0.380109 0.172099 0.90879 + outer loop + vertex 1.67754 1.89879 2.49549 + vertex 1.67871 1.89475 2.49576 + vertex 1.68089 1.89825 2.49419 + endloop + endfacet + facet normal 0.495444 0.127777 0.859191 + outer loop + vertex 1.68611 1.89185 2.49243 + vertex 1.68507 1.89718 2.49224 + vertex 1.68255 1.89332 2.49427 + endloop + endfacet + facet normal 0.380541 0.177799 0.907511 + outer loop + vertex 1.67754 1.89879 2.49549 + vertex 1.68089 1.89825 2.49419 + vertex 1.678 1.90337 2.4944 + endloop + endfacet + facet normal 0.429429 0.168926 0.887161 + outer loop + vertex 1.68132 1.90664 2.49245 + vertex 1.68279 1.90194 2.49263 + vertex 1.685 1.90496 2.49099 + endloop + endfacet + facet normal 0.315617 0.17671 0.932287 + outer loop + vertex 1.67483 1.92166 2.49203 + vertex 1.67654 1.91607 2.49251 + vertex 1.67931 1.91986 2.49085 + endloop + endfacet + facet normal 0.310788 0.161796 0.936607 + outer loop + vertex 1.67931 1.91986 2.49085 + vertex 1.67793 1.92394 2.49061 + vertex 1.67483 1.92166 2.49203 + endloop + endfacet + facet normal 0.386268 0.158574 0.908654 + outer loop + vertex 1.68316 1.91348 2.49042 + vertex 1.68378 1.91787 2.48939 + vertex 1.68059 1.9158 2.49111 + endloop + endfacet + facet normal 0.338242 0.170438 0.925496 + outer loop + vertex 1.67793 1.92394 2.49061 + vertex 1.67931 1.91986 2.49085 + vertex 1.68183 1.92385 2.4892 + endloop + endfacet + facet normal 0.338093 0.174178 0.924854 + outer loop + vertex 1.67793 1.92394 2.49061 + vertex 1.68183 1.92385 2.4892 + vertex 1.6782 1.9285 2.48965 + endloop + endfacet + facet normal 0.422369 0.130945 0.896916 + outer loop + vertex 1.6876 1.91758 2.48764 + vertex 1.68627 1.92192 2.48763 + vertex 1.68378 1.91787 2.48939 + endloop + endfacet + facet normal 0.372608 0.167315 0.912781 + outer loop + vertex 1.68208 1.93139 2.48778 + vertex 1.68184 1.92772 2.48855 + vertex 1.68506 1.92714 2.48734 + endloop + endfacet + facet normal 0.361824 0.159146 0.918562 + outer loop + vertex 1.68581 1.93117 2.48635 + vertex 1.68208 1.93139 2.48778 + vertex 1.68506 1.92714 2.48734 + endloop + endfacet + facet normal 0.418732 0.143208 0.896747 + outer loop + vertex 1.68581 1.93117 2.48635 + vertex 1.68506 1.92714 2.48734 + vertex 1.68811 1.92898 2.48562 + endloop + endfacet + facet normal 0.433975 0.162627 0.886125 + outer loop + vertex 1.68811 1.92898 2.48562 + vertex 1.68874 1.93318 2.48454 + vertex 1.68581 1.93117 2.48635 + endloop + endfacet + facet normal 0.422543 0.181015 0.888082 + outer loop + vertex 1.68581 1.93117 2.48635 + vertex 1.68874 1.93318 2.48454 + vertex 1.68467 1.93508 2.48609 + endloop + endfacet + facet normal 0.412542 0.151195 0.898303 + outer loop + vertex 1.68874 1.93318 2.48454 + vertex 1.68713 1.93886 2.48432 + vertex 1.68467 1.93508 2.48609 + endloop + endfacet + facet normal 0.38201 0.175364 0.907368 + outer loop + vertex 1.68347 1.93896 2.48585 + vertex 1.68467 1.93508 2.48609 + vertex 1.68713 1.93886 2.48432 + endloop + endfacet + facet normal 0.381882 0.178174 0.906874 + outer loop + vertex 1.68347 1.93896 2.48585 + vertex 1.68713 1.93886 2.48432 + vertex 1.68399 1.94304 2.48483 + endloop + endfacet + facet normal 0.361244 0.161294 0.918416 + outer loop + vertex 1.68399 1.94304 2.48483 + vertex 1.68713 1.93886 2.48432 + vertex 1.68718 1.94259 2.48365 + endloop + endfacet + facet normal 0.362917 0.188557 0.912545 + outer loop + vertex 1.68718 1.94259 2.48365 + vertex 1.68709 1.94635 2.48291 + vertex 1.68399 1.94304 2.48483 + endloop + endfacet + facet normal 0.349042 0.20294 0.914869 + outer loop + vertex 1.68399 1.94304 2.48483 + vertex 1.68709 1.94635 2.48291 + vertex 1.68207 1.94869 2.48431 + endloop + endfacet + facet normal 0.339322 0.176601 0.923944 + outer loop + vertex 1.68709 1.94635 2.48291 + vertex 1.68535 1.95197 2.48247 + vertex 1.68207 1.94869 2.48431 + endloop + endfacet + facet normal 0.334527 0.162063 0.928346 + outer loop + vertex 1.68467 1.93508 2.48609 + vertex 1.68347 1.93896 2.48585 + vertex 1.68039 1.93676 2.48734 + endloop + endfacet + facet normal 0.34068 0.182155 0.922365 + outer loop + vertex 1.68039 1.93676 2.48734 + vertex 1.68208 1.93139 2.48778 + vertex 1.68467 1.93508 2.48609 + endloop + endfacet + facet normal 0.36177 0.165155 0.917522 + outer loop + vertex 1.68467 1.93508 2.48609 + vertex 1.68208 1.93139 2.48778 + vertex 1.68581 1.93117 2.48635 + endloop + endfacet + facet normal 0.280331 0.184671 0.941972 + outer loop + vertex 1.66684 1.931 2.49263 + vertex 1.66649 1.92643 2.49363 + vertex 1.67095 1.92616 2.49235 + endloop + endfacet + facet normal 0.281881 0.190795 0.940287 + outer loop + vertex 1.66486 1.93663 2.49208 + vertex 1.66684 1.931 2.49263 + vertex 1.66954 1.93485 2.49104 + endloop + endfacet + facet normal 0.283003 0.189023 0.940308 + outer loop + vertex 1.67395 1.92889 2.49093 + vertex 1.67424 1.93309 2.48999 + vertex 1.6711 1.93081 2.4914 + endloop + endfacet + facet normal 0.278452 0.19551 0.94034 + outer loop + vertex 1.668 1.93886 2.49066 + vertex 1.66954 1.93485 2.49104 + vertex 1.67225 1.93871 2.48943 + endloop + endfacet + facet normal 0.288564 0.184931 0.939432 + outer loop + vertex 1.67826 1.93327 2.48872 + vertex 1.67638 1.93658 2.48865 + vertex 1.67424 1.93309 2.48999 + endloop + endfacet + facet normal 0.296512 0.19238 0.935452 + outer loop + vertex 1.67673 1.94106 2.48762 + vertex 1.67638 1.93658 2.48865 + vertex 1.68039 1.93676 2.48734 + endloop + endfacet + facet normal 0.289234 0.185963 0.939022 + outer loop + vertex 1.68087 1.94093 2.48637 + vertex 1.67673 1.94106 2.48762 + vertex 1.68039 1.93676 2.48734 + endloop + endfacet + facet normal 0.322371 0.179853 0.929371 + outer loop + vertex 1.68087 1.94093 2.48637 + vertex 1.68039 1.93676 2.48734 + vertex 1.68347 1.93896 2.48585 + endloop + endfacet + facet normal 0.274298 0.202429 0.940097 + outer loop + vertex 1.67262 1.94321 2.48838 + vertex 1.67483 1.94655 2.48701 + vertex 1.6709 1.94644 2.48818 + endloop + endfacet + facet normal 0.328821 0.189453 0.925194 + outer loop + vertex 1.68347 1.93896 2.48585 + vertex 1.68399 1.94304 2.48483 + vertex 1.68087 1.94093 2.48637 + endloop + endfacet + facet normal 0.281142 0.198743 0.938861 + outer loop + vertex 1.67948 1.94482 2.48598 + vertex 1.67797 1.94878 2.4856 + vertex 1.67483 1.94655 2.48701 + endloop + endfacet + facet normal 0.27409 0.204876 0.939628 + outer loop + vertex 1.67067 1.9511 2.48723 + vertex 1.6709 1.94644 2.48818 + vertex 1.67483 1.94655 2.48701 + endloop + endfacet + facet normal 0.277509 0.211515 0.93715 + outer loop + vertex 1.67356 1.95385 2.48577 + vertex 1.67507 1.95069 2.48604 + vertex 1.67804 1.95339 2.48455 + endloop + endfacet + facet normal 0.278604 0.207816 0.937652 + outer loop + vertex 1.66605 1.95624 2.48747 + vertex 1.66617 1.95137 2.48851 + vertex 1.67067 1.9511 2.48723 + endloop + endfacet + facet normal 0.278666 0.2114 0.936832 + outer loop + vertex 1.66902 1.95888 2.48598 + vertex 1.67053 1.95572 2.48624 + vertex 1.6734 1.95845 2.48477 + endloop + endfacet + facet normal 0.28385 0.210961 0.935374 + outer loop + vertex 1.66204 1.96102 2.4876 + vertex 1.66199 1.95729 2.48846 + vertex 1.66605 1.95624 2.48747 + endloop + endfacet + facet normal 0.284809 0.213014 0.934617 + outer loop + vertex 1.65987 1.96652 2.48701 + vertex 1.66204 1.96102 2.4876 + vertex 1.66449 1.96478 2.486 + endloop + endfacet + facet normal 0.282549 0.214084 0.935058 + outer loop + vertex 1.66902 1.95888 2.48598 + vertex 1.66914 1.96302 2.48499 + vertex 1.66612 1.96082 2.48641 + endloop + endfacet + facet normal 0.286081 0.216409 0.933448 + outer loop + vertex 1.66287 1.96873 2.48558 + vertex 1.66449 1.96478 2.486 + vertex 1.66693 1.96853 2.48438 + endloop + endfacet + facet normal 0.284384 0.219844 0.933164 + outer loop + vertex 1.67113 1.96641 2.4836 + vertex 1.67103 1.97121 2.4825 + vertex 1.66693 1.96853 2.48438 + endloop + endfacet + facet normal 0.280156 0.217842 0.93491 + outer loop + vertex 1.67305 1.9631 2.4838 + vertex 1.67564 1.96611 2.48232 + vertex 1.67113 1.96641 2.4836 + endloop + endfacet + facet normal 0.278769 0.214441 0.936111 + outer loop + vertex 1.66902 1.95888 2.48598 + vertex 1.6734 1.95845 2.48477 + vertex 1.66914 1.96302 2.48499 + endloop + endfacet + facet normal 0.278941 0.218942 0.935017 + outer loop + vertex 1.67599 1.96146 2.4833 + vertex 1.67564 1.96611 2.48232 + vertex 1.67305 1.9631 2.4838 + endloop + endfacet + facet normal 0.277569 0.213118 0.936769 + outer loop + vertex 1.67356 1.95385 2.48577 + vertex 1.67804 1.95339 2.48455 + vertex 1.6734 1.95845 2.48477 + endloop + endfacet + facet normal 0.285968 0.212619 0.934353 + outer loop + vertex 1.68195 1.95254 2.48354 + vertex 1.682 1.9562 2.4827 + vertex 1.67804 1.95339 2.48455 + endloop + endfacet + facet normal 0.28058 0.219294 0.934444 + outer loop + vertex 1.67791 1.95818 2.4835 + vertex 1.67989 1.96158 2.4821 + vertex 1.67599 1.96146 2.4833 + endloop + endfacet + facet normal 0.367132 0.205549 0.907173 + outer loop + vertex 1.68832 1.95389 2.48093 + vertex 1.68887 1.95797 2.47978 + vertex 1.68588 1.95601 2.48143 + endloop + endfacet + facet normal 0.296603 0.209414 0.931758 + outer loop + vertex 1.68446 1.95988 2.48103 + vertex 1.68289 1.96381 2.48065 + vertex 1.67989 1.96158 2.4821 + endloop + endfacet + facet normal 0.280612 0.21896 0.934512 + outer loop + vertex 1.67564 1.96611 2.48232 + vertex 1.67599 1.96146 2.4833 + vertex 1.67989 1.96158 2.4821 + endloop + endfacet + facet normal 0.287445 0.223138 0.931442 + outer loop + vertex 1.67852 1.96882 2.48082 + vertex 1.68002 1.96569 2.4811 + vertex 1.68294 1.96835 2.47957 + endloop + endfacet + facet normal 0.280158 0.220033 0.934397 + outer loop + vertex 1.67103 1.97121 2.4825 + vertex 1.67113 1.96641 2.4836 + vertex 1.67564 1.96611 2.48232 + endloop + endfacet + facet normal 0.278838 0.222683 0.934163 + outer loop + vertex 1.67402 1.97382 2.48098 + vertex 1.67551 1.97068 2.48128 + vertex 1.6784 1.97338 2.47977 + endloop + endfacet + facet normal 0.284623 0.223719 0.93217 + outer loop + vertex 1.66704 1.97593 2.48258 + vertex 1.66699 1.97224 2.48349 + vertex 1.67103 1.97121 2.4825 + endloop + endfacet + facet normal 0.286611 0.224758 0.93131 + outer loop + vertex 1.66483 1.98141 2.48195 + vertex 1.66704 1.97593 2.48258 + vertex 1.66946 1.97969 2.48094 + endloop + endfacet + facet normal 0.28107 0.225313 0.932863 + outer loop + vertex 1.67402 1.97382 2.48098 + vertex 1.67413 1.97794 2.47995 + vertex 1.67112 1.97574 2.48139 + endloop + endfacet + facet normal 0.285236 0.226162 0.931392 + outer loop + vertex 1.66775 1.98363 2.4805 + vertex 1.66946 1.97969 2.48094 + vertex 1.67177 1.98347 2.47931 + endloop + endfacet + facet normal 0.280608 0.230037 0.931849 + outer loop + vertex 1.67607 1.98134 2.47854 + vertex 1.67571 1.98623 2.47744 + vertex 1.67177 1.98347 2.47931 + endloop + endfacet + facet normal 0.275955 0.230012 0.933243 + outer loop + vertex 1.67571 1.98623 2.47744 + vertex 1.67607 1.98134 2.47854 + vertex 1.68062 1.98103 2.47727 + endloop + endfacet + facet normal 0.275953 0.228555 0.933602 + outer loop + vertex 1.67807 1.97801 2.47877 + vertex 1.68062 1.98103 2.47727 + vertex 1.67607 1.98134 2.47854 + endloop + endfacet + facet normal 0.278928 0.225519 0.933456 + outer loop + vertex 1.67402 1.97382 2.48098 + vertex 1.6784 1.97338 2.47977 + vertex 1.67413 1.97794 2.47995 + endloop + endfacet + facet normal 0.287361 0.220861 0.932011 + outer loop + vertex 1.67852 1.96882 2.48082 + vertex 1.68294 1.96835 2.47957 + vertex 1.6784 1.97338 2.47977 + endloop + endfacet + facet normal 0.303433 0.211172 0.929158 + outer loop + vertex 1.68672 1.96748 2.47853 + vertex 1.68686 1.97108 2.47767 + vertex 1.68294 1.96835 2.47957 + endloop + endfacet + facet normal 0.277496 0.227184 0.933479 + outer loop + vertex 1.68102 1.97637 2.47829 + vertex 1.68062 1.98103 2.47727 + vertex 1.67807 1.97801 2.47877 + endloop + endfacet + facet normal 0.277287 0.231294 0.932532 + outer loop + vertex 1.68035 1.98564 2.47621 + vertex 1.67571 1.98623 2.47744 + vertex 1.68062 1.98103 2.47727 + endloop + endfacet + facet normal 0.274732 0.232573 0.93297 + outer loop + vertex 1.67863 1.98889 2.4759 + vertex 1.68035 1.98564 2.47621 + vertex 1.68323 1.98839 2.47468 + endloop + endfacet + facet normal 0.287822 0.233162 0.928867 + outer loop + vertex 1.68351 1.98374 2.47575 + vertex 1.68508 1.98059 2.47605 + vertex 1.688 1.98328 2.47447 + endloop + endfacet + facet normal 0.273638 0.231155 0.933643 + outer loop + vertex 1.68323 1.98839 2.47468 + vertex 1.68592 1.99131 2.47316 + vertex 1.68286 1.99303 2.47363 + endloop + endfacet + facet normal 0.273653 0.231184 0.933632 + outer loop + vertex 1.68592 1.99131 2.47316 + vertex 1.68552 1.99591 2.47214 + vertex 1.68286 1.99303 2.47363 + endloop + endfacet + facet normal 0.272094 0.23151 0.934006 + outer loop + vertex 1.68526 2.00047 2.47109 + vertex 1.68069 2.00094 2.4723 + vertex 1.68552 1.99591 2.47214 + endloop + endfacet + facet normal 0.272341 0.237011 0.932554 + outer loop + vertex 1.68352 2.00371 2.47077 + vertex 1.68526 2.00047 2.47109 + vertex 1.68811 2.00322 2.46955 + endloop + endfacet + facet normal 0.301384 0.237703 0.923399 + outer loop + vertex 1.68832 1.99864 2.47064 + vertex 1.68986 1.9955 2.47095 + vertex 1.6926 1.99811 2.46938 + endloop + endfacet + facet normal 0.310094 0.228235 0.922903 + outer loop + vertex 1.69263 1.9935 2.47051 + vertex 1.6926 1.99811 2.46938 + vertex 1.68986 1.9955 2.47095 + endloop + endfacet + facet normal 0.337524 0.23195 0.912292 + outer loop + vertex 1.69192 2.00607 2.46768 + vertex 1.69207 2.00235 2.46857 + vertex 1.69549 2.00181 2.46744 + endloop + endfacet + facet normal 0.321719 0.218203 0.921349 + outer loop + vertex 1.69577 2.00584 2.46639 + vertex 1.69192 2.00607 2.46768 + vertex 1.69549 2.00181 2.46744 + endloop + endfacet + facet normal 0.388265 0.207634 0.897852 + outer loop + vertex 1.69577 2.00584 2.46639 + vertex 1.69549 2.00181 2.46744 + vertex 1.69845 2.0036 2.46575 + endloop + endfacet + facet normal 0.398263 0.221784 0.890055 + outer loop + vertex 1.69845 2.0036 2.46575 + vertex 1.69857 2.00783 2.46464 + vertex 1.69577 2.00584 2.46639 + endloop + endfacet + facet normal 0.377599 0.251951 0.891033 + outer loop + vertex 1.69577 2.00584 2.46639 + vertex 1.69857 2.00783 2.46464 + vertex 1.69416 2.00962 2.466 + endloop + endfacet + facet normal 0.368533 0.220445 0.903099 + outer loop + vertex 1.69857 2.00783 2.46464 + vertex 1.69605 2.01299 2.46441 + vertex 1.69416 2.00962 2.466 + endloop + endfacet + facet normal 0.321446 0.230933 0.918337 + outer loop + vertex 1.69416 2.00962 2.466 + vertex 1.69192 2.00607 2.46768 + vertex 1.69577 2.00584 2.46639 + endloop + endfacet + facet normal 0.299121 0.246665 0.921783 + outer loop + vertex 1.68972 2.01135 2.46698 + vertex 1.69192 2.00607 2.46768 + vertex 1.69416 2.00962 2.466 + endloop + endfacet + facet normal 0.272424 0.239339 0.931934 + outer loop + vertex 1.68352 2.00371 2.47077 + vertex 1.68811 2.00322 2.46955 + vertex 1.68318 2.00837 2.46968 + endloop + endfacet + facet normal 0.269536 0.245238 0.93124 + outer loop + vertex 1.68318 2.00837 2.46968 + vertex 1.68584 2.01127 2.46814 + vertex 1.68281 2.01296 2.46857 + endloop + endfacet + facet normal 0.2836 0.241039 0.928155 + outer loop + vertex 1.69192 2.00607 2.46768 + vertex 1.68972 2.01135 2.46698 + vertex 1.6878 2.00804 2.46843 + endloop + endfacet + facet normal 0.271301 0.248764 0.929792 + outer loop + vertex 1.68584 2.01127 2.46814 + vertex 1.68547 2.01577 2.46704 + vertex 1.68281 2.01296 2.46857 + endloop + endfacet + facet normal 0.281257 0.250345 0.926403 + outer loop + vertex 1.68514 2.02024 2.46594 + vertex 1.68065 2.02076 2.46716 + vertex 1.68547 2.01577 2.46704 + endloop + endfacet + facet normal 0.279658 0.248097 0.927491 + outer loop + vertex 1.68333 2.02347 2.46562 + vertex 1.68514 2.02024 2.46594 + vertex 1.68771 2.02295 2.46444 + endloop + endfacet + facet normal 0.285997 0.258732 0.922639 + outer loop + vertex 1.6882 2.01841 2.46552 + vertex 1.68978 2.01535 2.46588 + vertex 1.69242 2.01797 2.46433 + endloop + endfacet + facet normal 0.317127 0.234029 0.919054 + outer loop + vertex 1.69758 2.01686 2.46283 + vertex 1.69515 2.02184 2.4624 + vertex 1.69242 2.01797 2.46433 + endloop + endfacet + facet normal 0.28199 0.249141 0.926504 + outer loop + vertex 1.6916 2.02224 2.46344 + vertex 1.69088 2.02634 2.46256 + vertex 1.68771 2.02295 2.46444 + endloop + endfacet + facet normal 0.28088 0.248356 0.927052 + outer loop + vertex 1.69059 2.03075 2.46147 + vertex 1.68624 2.03125 2.46265 + vertex 1.69088 2.02634 2.46256 + endloop + endfacet + facet normal 0.282182 0.251715 0.92575 + outer loop + vertex 1.689 2.03383 2.46112 + vertex 1.69059 2.03075 2.46147 + vertex 1.69341 2.03338 2.45989 + endloop + endfacet + facet normal 0.301973 0.251165 0.919635 + outer loop + vertex 1.69364 2.02891 2.46103 + vertex 1.69522 2.02583 2.46135 + vertex 1.69807 2.02838 2.45972 + endloop + endfacet + facet normal 0.279912 0.250167 0.926858 + outer loop + vertex 1.69341 2.03338 2.45989 + vertex 1.696 2.03631 2.45832 + vertex 1.69302 2.03793 2.45878 + endloop + endfacet + facet normal 0.28177 0.254058 0.925235 + outer loop + vertex 1.696 2.03631 2.45832 + vertex 1.69555 2.04087 2.45721 + vertex 1.69302 2.03793 2.45878 + endloop + endfacet + facet normal 0.276554 0.259242 0.925371 + outer loop + vertex 1.69519 2.04537 2.45605 + vertex 1.69058 2.04594 2.45727 + vertex 1.69555 2.04087 2.45721 + endloop + endfacet + facet normal 0.279746 0.267505 0.922054 + outer loop + vertex 1.69338 2.04854 2.45568 + vertex 1.69519 2.04537 2.45605 + vertex 1.69779 2.04802 2.45449 + endloop + endfacet + facet normal 0.311662 0.267811 0.911671 + outer loop + vertex 1.69827 2.04353 2.45563 + vertex 1.69988 2.04042 2.45599 + vertex 1.70251 2.04297 2.45435 + endloop + endfacet + facet normal 0.32591 0.252686 0.911006 + outer loop + vertex 1.70265 2.03841 2.45556 + vertex 1.70251 2.04297 2.45435 + vertex 1.69988 2.04042 2.45599 + endloop + endfacet + facet normal 0.340642 0.268278 0.901105 + outer loop + vertex 1.70094 2.05132 2.45255 + vertex 1.70168 2.04726 2.45348 + vertex 1.70521 2.04667 2.45232 + endloop + endfacet + facet normal 0.317562 0.24638 0.91567 + outer loop + vertex 1.70523 2.05067 2.45123 + vertex 1.70094 2.05132 2.45255 + vertex 1.70521 2.04667 2.45232 + endloop + endfacet + facet normal 0.38331 0.239477 0.892034 + outer loop + vertex 1.70523 2.05067 2.45123 + vertex 1.70521 2.04667 2.45232 + vertex 1.70817 2.04844 2.45057 + endloop + endfacet + facet normal 0.386448 0.24441 0.889338 + outer loop + vertex 1.70817 2.04844 2.45057 + vertex 1.70782 2.05312 2.44944 + vertex 1.70523 2.05067 2.45123 + endloop + endfacet + facet normal 0.36139 0.272581 0.891682 + outer loop + vertex 1.70358 2.0538 2.45095 + vertex 1.70523 2.05067 2.45123 + vertex 1.70782 2.05312 2.44944 + endloop + endfacet + facet normal 0.36131 0.270787 0.892261 + outer loop + vertex 1.70358 2.0538 2.45095 + vertex 1.70782 2.05312 2.44944 + vertex 1.70299 2.05823 2.44984 + endloop + endfacet + facet normal 0.311795 0.268924 0.911298 + outer loop + vertex 1.70358 2.0538 2.45095 + vertex 1.70299 2.05823 2.44984 + vertex 1.70051 2.05568 2.45144 + endloop + endfacet + facet normal 0.308188 0.262188 0.914482 + outer loop + vertex 1.70051 2.05568 2.45144 + vertex 1.70094 2.05132 2.45255 + vertex 1.70358 2.0538 2.45095 + endloop + endfacet + facet normal 0.284004 0.261816 0.922385 + outer loop + vertex 1.70051 2.05568 2.45144 + vertex 1.6961 2.05626 2.45264 + vertex 1.70094 2.05132 2.45255 + endloop + endfacet + facet normal 0.284287 0.267421 0.920688 + outer loop + vertex 1.70051 2.05568 2.45144 + vertex 1.69865 2.05882 2.45111 + vertex 1.6961 2.05626 2.45264 + endloop + endfacet + facet normal 0.284922 0.26678 0.920678 + outer loop + vertex 1.69551 2.06069 2.45153 + vertex 1.6961 2.05626 2.45264 + vertex 1.69865 2.05882 2.45111 + endloop + endfacet + facet normal 0.294953 0.285568 0.911841 + outer loop + vertex 1.69865 2.05882 2.45111 + vertex 1.69794 2.06325 2.44995 + vertex 1.69551 2.06069 2.45153 + endloop + endfacet + facet normal 0.295234 0.285297 0.911834 + outer loop + vertex 1.69358 2.06386 2.45117 + vertex 1.69551 2.06069 2.45153 + vertex 1.69794 2.06325 2.44995 + endloop + endfacet + facet normal 0.296957 0.327595 0.896938 + outer loop + vertex 1.69358 2.06386 2.45117 + vertex 1.69794 2.06325 2.44995 + vertex 1.6927 2.06828 2.44984 + endloop + endfacet + facet normal 0.308886 0.328634 0.892518 + outer loop + vertex 1.69358 2.06386 2.45117 + vertex 1.6927 2.06828 2.44984 + vertex 1.69043 2.06572 2.45157 + endloop + endfacet + facet normal 0.282013 0.277682 0.918347 + outer loop + vertex 1.69043 2.06572 2.45157 + vertex 1.69112 2.0613 2.4527 + vertex 1.69358 2.06386 2.45117 + endloop + endfacet + facet normal 0.283187 0.277767 0.91796 + outer loop + vertex 1.69043 2.06572 2.45157 + vertex 1.68612 2.06628 2.45273 + vertex 1.69112 2.0613 2.4527 + endloop + endfacet + facet normal 0.284403 0.307162 0.908167 + outer loop + vertex 1.69043 2.06572 2.45157 + vertex 1.68835 2.06876 2.4512 + vertex 1.68612 2.06628 2.45273 + endloop + endfacet + facet normal 0.282723 0.308685 0.908175 + outer loop + vertex 1.68521 2.07052 2.45158 + vertex 1.68612 2.06628 2.45273 + vertex 1.68835 2.06876 2.4512 + endloop + endfacet + facet normal 0.321462 0.38716 0.864158 + outer loop + vertex 1.68835 2.06876 2.4512 + vertex 1.68697 2.07275 2.44992 + vertex 1.68521 2.07052 2.45158 + endloop + endfacet + facet normal 0.312228 0.385304 0.868363 + outer loop + vertex 1.68835 2.06876 2.4512 + vertex 1.6927 2.06828 2.44984 + vertex 1.68697 2.07275 2.44992 + endloop + endfacet + facet normal 0.284812 0.308931 0.907438 + outer loop + vertex 1.68521 2.07052 2.45158 + vertex 1.6811 2.07108 2.45268 + vertex 1.68612 2.06628 2.45273 + endloop + endfacet + facet normal 0.313092 0.324851 0.892438 + outer loop + vertex 1.68835 2.06876 2.4512 + vertex 1.69043 2.06572 2.45157 + vertex 1.6927 2.06828 2.44984 + endloop + endfacet + facet normal 0.292165 0.32268 0.900287 + outer loop + vertex 1.6927 2.06828 2.44984 + vertex 1.69794 2.06325 2.44995 + vertex 1.69694 2.06724 2.44884 + endloop + endfacet + facet normal 0.312212 0.325529 0.892499 + outer loop + vertex 1.69794 2.06325 2.44995 + vertex 1.70102 2.06636 2.44774 + vertex 1.69694 2.06724 2.44884 + endloop + endfacet + facet normal 0.301655 0.33585 0.892306 + outer loop + vertex 1.70199 2.06236 2.44892 + vertex 1.70102 2.06636 2.44774 + vertex 1.69794 2.06325 2.44995 + endloop + endfacet + facet normal 0.294366 0.276892 0.914702 + outer loop + vertex 1.69794 2.06325 2.44995 + vertex 1.70299 2.05823 2.44984 + vertex 1.70199 2.06236 2.44892 + endloop + endfacet + facet normal 0.323614 0.281419 0.90337 + outer loop + vertex 1.70299 2.05823 2.44984 + vertex 1.70585 2.06142 2.44782 + vertex 1.70199 2.06236 2.44892 + endloop + endfacet + facet normal 0.326793 0.278434 0.903151 + outer loop + vertex 1.70685 2.0574 2.4487 + vertex 1.70585 2.06142 2.44782 + vertex 1.70299 2.05823 2.44984 + endloop + endfacet + facet normal 0.331167 0.33949 0.880383 + outer loop + vertex 1.70102 2.06636 2.44774 + vertex 1.70199 2.06236 2.44892 + vertex 1.70585 2.06142 2.44782 + endloop + endfacet + facet normal 0.281824 0.277865 0.91835 + outer loop + vertex 1.69551 2.06069 2.45153 + vertex 1.69358 2.06386 2.45117 + vertex 1.69112 2.0613 2.4527 + endloop + endfacet + facet normal 0.303447 0.286156 0.908865 + outer loop + vertex 1.69865 2.05882 2.45111 + vertex 1.70299 2.05823 2.44984 + vertex 1.69794 2.06325 2.44995 + endloop + endfacet + facet normal 0.28121 0.266585 0.921875 + outer loop + vertex 1.69551 2.06069 2.45153 + vertex 1.69112 2.0613 2.4527 + vertex 1.6961 2.05626 2.45264 + endloop + endfacet + facet normal 0.303099 0.277589 0.911633 + outer loop + vertex 1.69865 2.05882 2.45111 + vertex 1.70051 2.05568 2.45144 + vertex 1.70299 2.05823 2.44984 + endloop + endfacet + facet normal 0.321048 0.230577 0.918566 + outer loop + vertex 1.70299 2.05823 2.44984 + vertex 1.70782 2.05312 2.44944 + vertex 1.70685 2.0574 2.4487 + endloop + endfacet + facet normal 0.317883 0.251624 0.914131 + outer loop + vertex 1.70523 2.05067 2.45123 + vertex 1.70358 2.0538 2.45095 + vertex 1.70094 2.05132 2.45255 + endloop + endfacet + facet normal 0.2797 0.266245 0.922432 + outer loop + vertex 1.69338 2.04854 2.45568 + vertex 1.69779 2.04802 2.45449 + vertex 1.69287 2.05302 2.45454 + endloop + endfacet + facet normal 0.289744 0.267495 0.918964 + outer loop + vertex 1.6961 2.05626 2.45264 + vertex 1.69695 2.05215 2.45356 + vertex 1.70094 2.05132 2.45255 + endloop + endfacet + facet normal 0.278635 0.2634 0.923571 + outer loop + vertex 1.68843 2.05358 2.45572 + vertex 1.69287 2.05302 2.45454 + vertex 1.68791 2.05807 2.4546 + endloop + endfacet + facet normal 0.278485 0.263873 0.923481 + outer loop + vertex 1.69112 2.0613 2.4527 + vertex 1.69201 2.05716 2.45361 + vertex 1.6961 2.05626 2.45264 + endloop + endfacet + facet normal 0.282619 0.265312 0.921811 + outer loop + vertex 1.68346 2.05865 2.4558 + vertex 1.68791 2.05807 2.4546 + vertex 1.68297 2.06313 2.45466 + endloop + endfacet + facet normal 0.282645 0.277221 0.918292 + outer loop + vertex 1.68612 2.06628 2.45273 + vertex 1.68706 2.06222 2.45367 + vertex 1.69112 2.0613 2.4527 + endloop + endfacet + facet normal 0.288018 0.265667 0.920036 + outer loop + vertex 1.67855 2.06373 2.45587 + vertex 1.68034 2.06054 2.45623 + vertex 1.68297 2.06313 2.45466 + endloop + endfacet + facet normal 0.291434 0.267407 0.918455 + outer loop + vertex 1.68034 2.06054 2.45623 + vertex 1.67855 2.06373 2.45587 + vertex 1.67595 2.06114 2.45745 + endloop + endfacet + facet normal 0.29456 0.262278 0.918937 + outer loop + vertex 1.67109 2.06626 2.45754 + vertex 1.67189 2.06209 2.45848 + vertex 1.67595 2.06114 2.45745 + endloop + endfacet + facet normal 0.300996 0.280773 0.911355 + outer loop + vertex 1.67365 2.06882 2.45592 + vertex 1.67546 2.06564 2.4563 + vertex 1.67804 2.06814 2.45468 + endloop + endfacet + facet normal 0.299788 0.277527 0.912746 + outer loop + vertex 1.67053 2.07071 2.45637 + vertex 1.66617 2.07127 2.45763 + vertex 1.67109 2.06626 2.45754 + endloop + endfacet + facet normal 0.303023 0.317075 0.898688 + outer loop + vertex 1.67365 2.06882 2.45592 + vertex 1.67804 2.06814 2.45468 + vertex 1.67288 2.0732 2.45463 + endloop + endfacet + facet normal 0.296667 0.310626 0.90305 + outer loop + vertex 1.67288 2.0732 2.45463 + vertex 1.67804 2.06814 2.45468 + vertex 1.67717 2.07202 2.45363 + endloop + endfacet + facet normal 0.293846 0.310275 0.904093 + outer loop + vertex 1.67804 2.06814 2.45468 + vertex 1.6811 2.07108 2.45268 + vertex 1.67717 2.07202 2.45363 + endloop + endfacet + facet normal 0.300645 0.303801 0.904056 + outer loop + vertex 1.67053 2.07071 2.45637 + vertex 1.66851 2.07378 2.45601 + vertex 1.66617 2.07127 2.45763 + endloop + endfacet + facet normal 0.288628 0.270358 0.918477 + outer loop + vertex 1.66297 2.06806 2.45959 + vertex 1.66617 2.07127 2.45763 + vertex 1.66214 2.07213 2.45865 + endloop + endfacet + facet normal 0.277279 0.267263 0.922869 + outer loop + vertex 1.65856 2.06858 2.46076 + vertex 1.66032 2.06545 2.46114 + vertex 1.66297 2.06806 2.45959 + endloop + endfacet + facet normal 0.274514 0.265849 0.924103 + outer loop + vertex 1.66032 2.06545 2.46114 + vertex 1.65856 2.06858 2.46076 + vertex 1.65588 2.06599 2.4623 + endloop + endfacet + facet normal 0.2746 0.271306 0.92249 + outer loop + vertex 1.65099 2.07095 2.4623 + vertex 1.65183 2.06684 2.46326 + vertex 1.65588 2.06599 2.4623 + endloop + endfacet + facet normal 0.27128 0.277082 0.921755 + outer loop + vertex 1.65355 2.07351 2.46076 + vertex 1.65544 2.07039 2.46115 + vertex 1.65802 2.07297 2.45961 + endloop + endfacet + facet normal 0.289717 0.276986 0.916157 + outer loop + vertex 1.65034 2.07539 2.46116 + vertex 1.64589 2.07607 2.46236 + vertex 1.65099 2.07095 2.4623 + endloop + endfacet + facet normal 0.280242 0.26749 0.921907 + outer loop + vertex 1.64589 2.07607 2.46236 + vertex 1.64688 2.07189 2.46328 + vertex 1.65099 2.07095 2.4623 + endloop + endfacet + facet normal 0.271903 0.292846 0.916684 + outer loop + vertex 1.65355 2.07351 2.46076 + vertex 1.65802 2.07297 2.45961 + vertex 1.65275 2.07799 2.45957 + endloop + endfacet + facet normal 0.290341 0.286433 0.913049 + outer loop + vertex 1.65034 2.07539 2.46116 + vertex 1.64824 2.07854 2.46084 + vertex 1.64589 2.07607 2.46236 + endloop + endfacet + facet normal 0.291359 0.272667 0.916931 + outer loop + vertex 1.63827 2.07351 2.46553 + vertex 1.64274 2.07288 2.4643 + vertex 1.63773 2.07788 2.4644 + endloop + endfacet + facet normal 0.214354 0.270222 0.938633 + outer loop + vertex 1.63514 2.07517 2.46596 + vertex 1.63319 2.07796 2.4656 + vertex 1.63103 2.07475 2.46702 + endloop + endfacet + facet normal 0.279255 0.260592 0.92418 + outer loop + vertex 1.64012 2.07025 2.46589 + vertex 1.63827 2.07351 2.46553 + vertex 1.63562 2.0707 2.46712 + endloop + endfacet + facet normal 0.291041 0.266722 0.918779 + outer loop + vertex 1.63827 2.07351 2.46553 + vertex 1.64012 2.07025 2.46589 + vertex 1.64274 2.07288 2.4643 + endloop + endfacet + facet normal 0.291371 0.272488 0.916981 + outer loop + vertex 1.64274 2.07288 2.4643 + vertex 1.64774 2.06771 2.46424 + vertex 1.64688 2.07189 2.46328 + endloop + endfacet + facet normal 0.279831 0.272666 0.920515 + outer loop + vertex 1.64819 2.06324 2.46543 + vertex 1.65249 2.06282 2.46425 + vertex 1.64774 2.06771 2.46424 + endloop + endfacet + facet normal 0.291043 0.272543 0.917068 + outer loop + vertex 1.64512 2.06505 2.46584 + vertex 1.6433 2.0683 2.46545 + vertex 1.64062 2.06565 2.46709 + endloop + endfacet + facet normal 0.292057 0.270132 0.917459 + outer loop + vertex 1.64108 2.06106 2.4683 + vertex 1.64062 2.06565 2.46709 + vertex 1.63791 2.06299 2.46874 + endloop + endfacet + facet normal 0.288242 0.25913 0.921829 + outer loop + vertex 1.63876 2.05388 2.47106 + vertex 1.64326 2.05331 2.46981 + vertex 1.63833 2.05843 2.46991 + endloop + endfacet + facet normal 0.287985 0.253631 0.923437 + outer loop + vertex 1.63876 2.05388 2.47106 + vertex 1.64056 2.05065 2.47138 + vertex 1.64326 2.05331 2.46981 + endloop + endfacet + facet normal 0.289534 0.254423 0.922734 + outer loop + vertex 1.64056 2.05065 2.47138 + vertex 1.63876 2.05388 2.47106 + vertex 1.63609 2.05132 2.4726 + endloop + endfacet + facet normal 0.287081 0.265362 0.920417 + outer loop + vertex 1.64586 2.05614 2.46822 + vertex 1.64547 2.06062 2.46705 + vertex 1.64284 2.05785 2.46867 + endloop + endfacet + facet normal 0.282322 0.273201 0.919595 + outer loop + vertex 1.6498 2.06022 2.46583 + vertex 1.64819 2.06324 2.46543 + vertex 1.64547 2.06062 2.46705 + endloop + endfacet + facet normal 0.279821 0.272021 0.920709 + outer loop + vertex 1.64819 2.06324 2.46543 + vertex 1.6498 2.06022 2.46583 + vertex 1.65249 2.06282 2.46425 + endloop + endfacet + facet normal 0.278072 0.264667 0.923378 + outer loop + vertex 1.65249 2.06282 2.46425 + vertex 1.65673 2.0583 2.46427 + vertex 1.65649 2.06202 2.46327 + endloop + endfacet + facet normal 0.283272 0.261098 0.922813 + outer loop + vertex 1.65441 2.05461 2.46602 + vertex 1.6527 2.05842 2.46547 + vertex 1.64976 2.05624 2.46699 + endloop + endfacet + facet normal 0.28238 0.257848 0.924 + outer loop + vertex 1.64976 2.05624 2.46699 + vertex 1.65208 2.05092 2.46777 + vertex 1.65441 2.05461 2.46602 + endloop + endfacet + facet normal 0.282882 0.258707 0.923606 + outer loop + vertex 1.65909 2.05292 2.46505 + vertex 1.66105 2.05622 2.46353 + vertex 1.65673 2.0583 2.46427 + endloop + endfacet + facet normal 0.284883 0.254995 0.924023 + outer loop + vertex 1.65902 2.04892 2.46618 + vertex 1.66342 2.04843 2.46496 + vertex 1.65909 2.05292 2.46505 + endloop + endfacet + facet normal 0.285189 0.255286 0.923849 + outer loop + vertex 1.66061 2.04585 2.46653 + vertex 1.65902 2.04892 2.46618 + vertex 1.65629 2.04635 2.46773 + endloop + endfacet + facet normal 0.284631 0.256308 0.923738 + outer loop + vertex 1.65441 2.05461 2.46602 + vertex 1.65208 2.05092 2.46777 + vertex 1.65611 2.05078 2.46656 + endloop + endfacet + facet normal 0.285451 0.256402 0.923459 + outer loop + vertex 1.65294 2.04316 2.46965 + vertex 1.65629 2.04635 2.46773 + vertex 1.65231 2.04718 2.46873 + endloop + endfacet + facet normal 0.282972 0.256978 0.924061 + outer loop + vertex 1.65031 2.04056 2.47119 + vertex 1.64857 2.04373 2.47084 + vertex 1.64593 2.04112 2.47237 + endloop + endfacet + facet normal 0.282715 0.254867 0.924724 + outer loop + vertex 1.6468 2.03333 2.47426 + vertex 1.65068 2.03604 2.47233 + vertex 1.64656 2.03709 2.4733 + endloop + endfacet + facet normal 0.280724 0.25113 0.926352 + outer loop + vertex 1.64914 2.02793 2.47502 + vertex 1.65112 2.03124 2.47352 + vertex 1.6468 2.03333 2.47426 + endloop + endfacet + facet normal 0.284114 0.245241 0.926896 + outer loop + vertex 1.64907 2.0239 2.47611 + vertex 1.65344 2.02343 2.47489 + vertex 1.64914 2.02793 2.47502 + endloop + endfacet + facet normal 0.277197 0.241567 0.92995 + outer loop + vertex 1.64616 2.02577 2.4765 + vertex 1.64212 2.02587 2.47767 + vertex 1.64632 2.02128 2.47761 + endloop + endfacet + facet normal 0.283979 0.241065 0.928032 + outer loop + vertex 1.64907 2.0239 2.47611 + vertex 1.65063 2.02082 2.47643 + vertex 1.65344 2.02343 2.47489 + endloop + endfacet + facet normal 0.284155 0.238556 0.928626 + outer loop + vertex 1.65344 2.02343 2.47489 + vertex 1.65822 2.01839 2.47472 + vertex 1.65784 2.02302 2.47365 + endloop + endfacet + facet normal 0.285119 0.238228 0.928415 + outer loop + vertex 1.65543 2.01569 2.47627 + vertex 1.6537 2.01895 2.47597 + vertex 1.65096 2.0163 2.47749 + endloop + endfacet + facet normal 0.285672 0.238049 0.928291 + outer loop + vertex 1.65859 2.01374 2.4758 + vertex 1.66318 2.01313 2.47455 + vertex 1.65822 2.01839 2.47472 + endloop + endfacet + facet normal 0.285235 0.24016 0.927882 + outer loop + vertex 1.65543 2.01569 2.47627 + vertex 1.65096 2.0163 2.47749 + vertex 1.6557 2.01111 2.47738 + endloop + endfacet + facet normal 0.285793 0.240227 0.927692 + outer loop + vertex 1.65859 2.01374 2.4758 + vertex 1.66032 2.01047 2.47612 + vertex 1.66318 2.01313 2.47455 + endloop + endfacet + facet normal 0.286964 0.240107 0.927362 + outer loop + vertex 1.66318 2.01313 2.47455 + vertex 1.66764 2.00812 2.47446 + vertex 1.66727 2.01209 2.47355 + endloop + endfacet + facet normal 0.289359 0.239575 0.926755 + outer loop + vertex 1.66775 2.00365 2.47558 + vertex 1.67176 2.00348 2.47438 + vertex 1.66764 2.00812 2.47446 + endloop + endfacet + facet normal 0.29022 0.234838 0.927698 + outer loop + vertex 1.66946 1.99973 2.47604 + vertex 1.66775 2.00365 2.47558 + vertex 1.66484 2.00146 2.47705 + endloop + endfacet + facet normal 0.287092 0.241164 0.927048 + outer loop + vertex 1.66489 2.00552 2.47599 + vertex 1.66337 2.0086 2.47566 + vertex 1.66058 2.00595 2.47722 + endloop + endfacet + facet normal 0.290065 0.234359 0.927868 + outer loop + vertex 1.66291 1.99811 2.4785 + vertex 1.66484 2.00146 2.47705 + vertex 1.66098 2.00139 2.47827 + endloop + endfacet + facet normal 0.290782 0.228097 0.929203 + outer loop + vertex 1.66321 1.99325 2.4796 + vertex 1.66714 1.99599 2.4777 + vertex 1.66291 1.99811 2.4785 + endloop + endfacet + facet normal 0.290454 0.225679 0.929895 + outer loop + vertex 1.65864 1.99385 2.48088 + vertex 1.66031 1.99057 2.48115 + vertex 1.66321 1.99325 2.4796 + endloop + endfacet + facet normal 0.286725 0.223905 0.93148 + outer loop + vertex 1.66031 1.99057 2.48115 + vertex 1.65864 1.99385 2.48088 + vertex 1.65581 1.99108 2.48242 + endloop + endfacet + facet normal 0.28419 0.226784 0.93156 + outer loop + vertex 1.65108 1.99627 2.4826 + vertex 1.65121 1.99147 2.48372 + vertex 1.65581 1.99108 2.48242 + endloop + endfacet + facet normal 0.286846 0.232071 0.929442 + outer loop + vertex 1.65405 1.99889 2.48105 + vertex 1.65556 1.99576 2.48136 + vertex 1.65843 1.99843 2.47981 + endloop + endfacet + facet normal 0.282598 0.233651 0.930347 + outer loop + vertex 1.6471 2.00094 2.48263 + vertex 1.64704 1.99727 2.48357 + vertex 1.65108 1.99627 2.4826 + endloop + endfacet + facet normal 0.280644 0.237966 0.929845 + outer loop + vertex 1.64487 2.00633 2.48193 + vertex 1.6471 2.00094 2.48263 + vertex 1.64952 2.00465 2.48095 + endloop + endfacet + facet normal 0.284222 0.23728 0.928933 + outer loop + vertex 1.65405 1.99889 2.48105 + vertex 1.65417 2.00295 2.47997 + vertex 1.65117 2.00078 2.48144 + endloop + endfacet + facet normal 0.283473 0.240765 0.928265 + outer loop + vertex 1.6478 2.00853 2.48047 + vertex 1.64952 2.00465 2.48095 + vertex 1.65182 2.00839 2.47928 + endloop + endfacet + facet normal 0.285323 0.240684 0.927718 + outer loop + vertex 1.65807 2.003 2.47876 + vertex 1.65611 2.00627 2.47852 + vertex 1.65417 2.00295 2.47997 + endloop + endfacet + facet normal 0.286924 0.242344 0.926792 + outer loop + vertex 1.6557 2.01111 2.47738 + vertex 1.65611 2.00627 2.47852 + vertex 1.66058 2.00595 2.47722 + endloop + endfacet + facet normal 0.283451 0.241346 0.928121 + outer loop + vertex 1.6478 2.00853 2.48047 + vertex 1.65182 2.00839 2.47928 + vertex 1.64755 2.01304 2.47937 + endloop + endfacet + facet normal 0.285432 0.240342 0.927774 + outer loop + vertex 1.65096 2.0163 2.47749 + vertex 1.65155 2.0122 2.47837 + vertex 1.6557 2.01111 2.47738 + endloop + endfacet + facet normal 0.280814 0.241646 0.928844 + outer loop + vertex 1.64326 2.01347 2.48056 + vertex 1.64755 2.01304 2.47937 + vertex 1.64289 2.018 2.47949 + endloop + endfacet + facet normal 0.282982 0.240727 0.928424 + outer loop + vertex 1.64632 2.02128 2.47761 + vertex 1.64692 2.01717 2.4785 + vertex 1.65096 2.0163 2.47749 + endloop + endfacet + facet normal 0.279412 0.241021 0.929429 + outer loop + vertex 1.63847 2.01854 2.48068 + vertex 1.64289 2.018 2.47949 + vertex 1.63821 2.02313 2.47957 + endloop + endfacet + facet normal 0.278861 0.243099 0.929053 + outer loop + vertex 1.64212 2.02587 2.47767 + vertex 1.64233 2.02208 2.4786 + vertex 1.64632 2.02128 2.47761 + endloop + endfacet + facet normal 0.287339 0.243288 0.926416 + outer loop + vertex 1.63362 2.0238 2.48082 + vertex 1.63821 2.02313 2.47957 + vertex 1.63327 2.02842 2.47971 + endloop + endfacet + facet normal 0.284214 0.245319 0.926845 + outer loop + vertex 1.63786 2.02794 2.47842 + vertex 1.63982 2.03125 2.47694 + vertex 1.6359 2.03121 2.47815 + endloop + endfacet + facet normal 0.283991 0.247944 0.926214 + outer loop + vertex 1.63554 2.03576 2.47704 + vertex 1.6359 2.03121 2.47815 + vertex 1.63982 2.03125 2.47694 + endloop + endfacet + facet normal 0.286572 0.250426 0.92475 + outer loop + vertex 1.63988 2.03528 2.47583 + vertex 1.63554 2.03576 2.47704 + vertex 1.63982 2.03125 2.47694 + endloop + endfacet + facet normal 0.267224 0.257516 0.928589 + outer loop + vertex 1.63113 2.03628 2.47828 + vertex 1.63072 2.04086 2.47713 + vertex 1.62794 2.03813 2.47868 + endloop + endfacet + facet normal 0.281785 0.245818 0.927454 + outer loop + vertex 1.63522 2.04025 2.47592 + vertex 1.63342 2.04355 2.47559 + vertex 1.63072 2.04086 2.47713 + endloop + endfacet + facet normal 0.275767 0.251953 0.927617 + outer loop + vertex 1.63026 2.04548 2.47601 + vertex 1.63072 2.04086 2.47713 + vertex 1.63342 2.04355 2.47559 + endloop + endfacet + facet normal 0.278396 0.256704 0.925526 + outer loop + vertex 1.63342 2.04355 2.47559 + vertex 1.63286 2.04811 2.47449 + vertex 1.63026 2.04548 2.47601 + endloop + endfacet + facet normal 0.225103 0.250303 0.941635 + outer loop + vertex 1.63026 2.04548 2.47601 + vertex 1.62571 2.04562 2.47706 + vertex 1.63072 2.04086 2.47713 + endloop + endfacet + facet normal 0.290484 0.250204 0.923589 + outer loop + vertex 1.63342 2.04355 2.47559 + vertex 1.63522 2.04025 2.47592 + vertex 1.63783 2.0429 2.47438 + endloop + endfacet + facet normal 0.283322 0.251764 0.925388 + outer loop + vertex 1.63829 2.03835 2.47548 + vertex 1.63988 2.03528 2.47583 + vertex 1.64257 2.0379 2.47429 + endloop + endfacet + facet normal 0.282453 0.254318 0.924955 + outer loop + vertex 1.64106 2.04615 2.47247 + vertex 1.6419 2.04198 2.47337 + vertex 1.64593 2.04112 2.47237 + endloop + endfacet + facet normal 0.285087 0.256891 0.923435 + outer loop + vertex 1.64549 2.04558 2.47127 + vertex 1.64106 2.04615 2.47247 + vertex 1.64593 2.04112 2.47237 + endloop + endfacet + facet normal 0.283097 0.25685 0.924058 + outer loop + vertex 1.64549 2.04558 2.47127 + vertex 1.64593 2.04112 2.47237 + vertex 1.64857 2.04373 2.47084 + endloop + endfacet + facet normal 0.282838 0.256369 0.924271 + outer loop + vertex 1.64857 2.04373 2.47084 + vertex 1.64823 2.04819 2.4697 + vertex 1.64549 2.04558 2.47127 + endloop + endfacet + facet normal 0.290948 0.257261 0.921502 + outer loop + vertex 1.63342 2.04355 2.47559 + vertex 1.63783 2.0429 2.47438 + vertex 1.63286 2.04811 2.47449 + endloop + endfacet + facet normal 0.289297 0.255574 0.922491 + outer loop + vertex 1.63609 2.05132 2.4726 + vertex 1.63696 2.04712 2.47349 + vertex 1.64106 2.04615 2.47247 + endloop + endfacet + facet normal 0.270065 0.26503 0.925648 + outer loop + vertex 1.62843 2.04865 2.47563 + vertex 1.63026 2.04548 2.47601 + vertex 1.63286 2.04811 2.47449 + endloop + endfacet + facet normal 0.225344 0.241429 0.943892 + outer loop + vertex 1.63026 2.04548 2.47601 + vertex 1.62843 2.04865 2.47563 + vertex 1.62571 2.04562 2.47706 + endloop + endfacet + facet normal 0.252188 0.278527 0.926728 + outer loop + vertex 1.62571 2.04562 2.47706 + vertex 1.6261 2.04124 2.47827 + vertex 1.63072 2.04086 2.47713 + endloop + endfacet + facet normal 0.252145 0.272768 0.928451 + outer loop + vertex 1.62794 2.03813 2.47868 + vertex 1.63072 2.04086 2.47713 + vertex 1.6261 2.04124 2.47827 + endloop + endfacet + facet normal 0.265682 0.254579 0.92984 + outer loop + vertex 1.62834 2.03356 2.47982 + vertex 1.63113 2.03628 2.47828 + vertex 1.62794 2.03813 2.47868 + endloop + endfacet + facet normal 0.29072 0.259643 0.920906 + outer loop + vertex 1.62876 2.02903 2.48096 + vertex 1.63327 2.02842 2.47971 + vertex 1.62834 2.03356 2.47982 + endloop + endfacet + facet normal 0.273044 0.237817 0.932142 + outer loop + vertex 1.6305 2.02576 2.48129 + vertex 1.62876 2.02903 2.48096 + vertex 1.626 2.02618 2.4825 + endloop + endfacet + facet normal 0.19599 0.247943 0.948742 + outer loop + vertex 1.62558 2.03084 2.48136 + vertex 1.62373 2.0339 2.48094 + vertex 1.62094 2.03081 2.48232 + endloop + endfacet + facet normal 0.295787 0.265825 0.917522 + outer loop + vertex 1.626 2.02618 2.4825 + vertex 1.62676 2.02216 2.48342 + vertex 1.63077 2.02119 2.48241 + endloop + endfacet + facet normal 0.292699 0.246253 0.923952 + outer loop + vertex 1.62696 2.01844 2.48435 + vertex 1.63077 2.02119 2.48241 + vertex 1.62676 2.02216 2.48342 + endloop + endfacet + facet normal 0.234131 0.231544 0.94423 + outer loop + vertex 1.62462 2.01468 2.48604 + vertex 1.6229 2.01831 2.48558 + vertex 1.62024 2.01548 2.48693 + endloop + endfacet + facet normal 0.236293 0.248646 0.93933 + outer loop + vertex 1.62024 2.01548 2.48693 + vertex 1.62215 2.01071 2.48771 + vertex 1.62462 2.01468 2.48604 + endloop + endfacet + facet normal 0.262512 0.231329 0.93679 + outer loop + vertex 1.62462 2.01468 2.48604 + vertex 1.62215 2.01071 2.48771 + vertex 1.62623 2.01096 2.48651 + endloop + endfacet + facet normal 0.274951 0.238847 0.931318 + outer loop + vertex 1.62274 2.00321 2.4895 + vertex 1.62632 2.00647 2.48761 + vertex 1.6224 2.00706 2.48862 + endloop + endfacet + facet normal 0.289541 0.24377 0.925604 + outer loop + vertex 1.62285 1.9989 2.4906 + vertex 1.6269 1.99868 2.48939 + vertex 1.62274 2.00321 2.4895 + endloop + endfacet + facet normal 0.268403 0.22177 0.937432 + outer loop + vertex 1.62458 1.99494 2.49104 + vertex 1.62285 1.9989 2.4906 + vertex 1.61992 1.99647 2.49202 + endloop + endfacet + facet normal 0.194344 0.242573 0.950468 + outer loop + vertex 1.61995 2.00051 2.49099 + vertex 1.61827 2.00317 2.49065 + vertex 1.61583 1.99983 2.492 + endloop + endfacet + facet normal 0.128399 0.270356 0.95416 + outer loop + vertex 1.61584 1.99584 2.49313 + vertex 1.61583 1.99983 2.492 + vertex 1.61181 1.99661 2.49345 + endloop + endfacet + facet normal 0.128323 0.269899 0.9543 + outer loop + vertex 1.61356 1.99222 2.49446 + vertex 1.61584 1.99584 2.49313 + vertex 1.61181 1.99661 2.49345 + endloop + endfacet + facet normal 0.260695 0.230858 0.937413 + outer loop + vertex 1.62217 1.99118 2.49269 + vertex 1.61992 1.99647 2.49202 + vertex 1.61795 1.99299 2.49342 + endloop + endfacet + facet normal 0.26247 0.235644 0.935725 + outer loop + vertex 1.6181 1.98836 2.49455 + vertex 1.62217 1.99118 2.49269 + vertex 1.61795 1.99299 2.49342 + endloop + endfacet + facet normal 0.284765 0.236976 0.928844 + outer loop + vertex 1.61803 1.98401 2.49568 + vertex 1.62208 1.98379 2.49449 + vertex 1.6181 1.98836 2.49455 + endloop + endfacet + facet normal 0.248498 0.206334 0.946401 + outer loop + vertex 1.61964 1.98007 2.49611 + vertex 1.61803 1.98401 2.49568 + vertex 1.61496 1.98147 2.49704 + endloop + endfacet + facet normal 0.150964 0.239278 0.959143 + outer loop + vertex 1.61515 1.98557 2.49602 + vertex 1.61347 1.98821 2.49562 + vertex 1.61088 1.98468 2.49691 + endloop + endfacet + facet normal 0.253814 0.228506 0.939874 + outer loop + vertex 1.61496 1.98147 2.49704 + vertex 1.61715 1.97622 2.49772 + vertex 1.61964 1.98007 2.49611 + endloop + endfacet + facet normal 0.277629 0.211905 0.937026 + outer loop + vertex 1.61964 1.98007 2.49611 + vertex 1.61715 1.97622 2.49772 + vertex 1.62126 1.97607 2.49654 + endloop + endfacet + facet normal 0.27746 0.217965 0.935685 + outer loop + vertex 1.62126 1.97607 2.49654 + vertex 1.61715 1.97622 2.49772 + vertex 1.62118 1.97147 2.49763 + endloop + endfacet + facet normal 0.284785 0.224269 0.931988 + outer loop + vertex 1.61715 1.97622 2.49772 + vertex 1.6171 1.97255 2.49862 + vertex 1.62118 1.97147 2.49763 + endloop + endfacet + facet normal 0.283696 0.218624 0.933659 + outer loop + vertex 1.61706 1.96884 2.4995 + vertex 1.62118 1.97147 2.49763 + vertex 1.6171 1.97255 2.49862 + endloop + endfacet + facet normal 0.278136 0.213143 0.936595 + outer loop + vertex 1.6193 1.96326 2.5001 + vertex 1.61706 1.96884 2.4995 + vertex 1.61458 1.96503 2.5011 + endloop + endfacet + facet normal 0.114822 0.243755 0.963016 + outer loop + vertex 1.61014 1.97028 2.50091 + vertex 1.60857 1.97258 2.50051 + vertex 1.60625 1.96941 2.50159 + endloop + endfacet + facet normal 0.219423 0.230829 0.94793 + outer loop + vertex 1.60978 1.96619 2.50193 + vertex 1.61206 1.96091 2.50269 + vertex 1.61458 1.96503 2.5011 + endloop + endfacet + facet normal 0.274615 0.230874 0.933426 + outer loop + vertex 1.61206 1.96091 2.50269 + vertex 1.6122 1.95724 2.50356 + vertex 1.61619 1.95643 2.50258 + endloop + endfacet + facet normal 0.272293 0.213759 0.93817 + outer loop + vertex 1.61213 1.95359 2.50441 + vertex 1.61619 1.95643 2.50258 + vertex 1.6122 1.95724 2.50356 + endloop + endfacet + facet normal 0.171703 0.205894 0.963393 + outer loop + vertex 1.60957 1.94967 2.50596 + vertex 1.60789 1.95323 2.5055 + vertex 1.60506 1.95013 2.50666 + endloop + endfacet + facet normal 0.173152 0.227868 0.958173 + outer loop + vertex 1.60506 1.95013 2.50666 + vertex 1.60674 1.94543 2.50748 + vertex 1.60957 1.94967 2.50596 + endloop + endfacet + facet normal 0.275423 0.215369 0.936888 + outer loop + vertex 1.61428 1.94826 2.505 + vertex 1.61632 1.95164 2.50363 + vertex 1.61213 1.95359 2.50441 + endloop + endfacet + facet normal 0.208014 0.204029 0.95661 + outer loop + vertex 1.60957 1.94967 2.50596 + vertex 1.60674 1.94543 2.50748 + vertex 1.61118 1.94594 2.5064 + endloop + endfacet + facet normal 0.222809 0.233876 0.946392 + outer loop + vertex 1.60813 1.93823 2.50888 + vertex 1.61105 1.94131 2.50744 + vertex 1.60641 1.94108 2.50859 + endloop + endfacet + facet normal 0.247688 0.209914 0.945826 + outer loop + vertex 1.6111 1.93682 2.50842 + vertex 1.61105 1.94131 2.50744 + vertex 1.60813 1.93823 2.50888 + endloop + endfacet + facet normal 0.245569 0.204929 0.94747 + outer loop + vertex 1.60822 1.93376 2.50983 + vertex 1.6111 1.93682 2.50842 + vertex 1.60813 1.93823 2.50888 + endloop + endfacet + facet normal 0.263282 0.187696 0.946284 + outer loop + vertex 1.61283 1.93356 2.50858 + vertex 1.6111 1.93682 2.50842 + vertex 1.60822 1.93376 2.50983 + endloop + endfacet + facet normal 0.263202 0.19563 0.944698 + outer loop + vertex 1.60822 1.93376 2.50983 + vertex 1.61252 1.92904 2.50961 + vertex 1.61283 1.93356 2.50858 + endloop + endfacet + facet normal 0.280914 0.212175 0.935985 + outer loop + vertex 1.60826 1.9293 2.51083 + vertex 1.61252 1.92904 2.50961 + vertex 1.60822 1.93376 2.50983 + endloop + endfacet + facet normal 0.280931 0.193786 0.93996 + outer loop + vertex 1.60826 1.9293 2.51083 + vertex 1.60985 1.92524 2.51119 + vertex 1.61252 1.92904 2.50961 + endloop + endfacet + facet normal 0.290577 0.18643 0.938514 + outer loop + vertex 1.61449 1.92331 2.51013 + vertex 1.61252 1.92904 2.50961 + vertex 1.60985 1.92524 2.51119 + endloop + endfacet + facet normal 0.290053 0.184918 0.938975 + outer loop + vertex 1.61137 1.92111 2.51153 + vertex 1.61449 1.92331 2.51013 + vertex 1.60985 1.92524 2.51119 + endloop + endfacet + facet normal 0.274118 0.179548 0.944787 + outer loop + vertex 1.60985 1.92524 2.51119 + vertex 1.60712 1.92122 2.51275 + vertex 1.61137 1.92111 2.51153 + endloop + endfacet + facet normal 0.274138 0.178815 0.94492 + outer loop + vertex 1.61137 1.92111 2.51153 + vertex 1.60712 1.92122 2.51275 + vertex 1.61116 1.91644 2.51248 + endloop + endfacet + facet normal 0.292313 0.176953 0.939809 + outer loop + vertex 1.61137 1.92111 2.51153 + vertex 1.61116 1.91644 2.51248 + vertex 1.61416 1.91911 2.51104 + endloop + endfacet + facet normal 0.293889 0.179378 0.938857 + outer loop + vertex 1.61416 1.91911 2.51104 + vertex 1.61449 1.92331 2.51013 + vertex 1.61137 1.92111 2.51153 + endloop + endfacet + facet normal 0.240202 0.179066 0.954064 + outer loop + vertex 1.60985 1.92524 2.51119 + vertex 1.60826 1.9293 2.51083 + vertex 1.6051 1.92668 2.51211 + endloop + endfacet + facet normal 0.136807 0.211708 0.967711 + outer loop + vertex 1.6053 1.9309 2.51119 + vertex 1.60358 1.93353 2.51085 + vertex 1.60101 1.92995 2.512 + endloop + endfacet + facet normal 0.245588 0.20041 0.948432 + outer loop + vertex 1.6051 1.92668 2.51211 + vertex 1.60712 1.92122 2.51275 + vertex 1.60985 1.92524 2.51119 + endloop + endfacet + facet normal 0.286085 0.189236 0.939332 + outer loop + vertex 1.60712 1.92122 2.51275 + vertex 1.60674 1.91672 2.51377 + vertex 1.61116 1.91644 2.51248 + endloop + endfacet + facet normal 0.286075 0.186567 0.939869 + outer loop + vertex 1.60836 1.91352 2.51391 + vertex 1.61116 1.91644 2.51248 + vertex 1.60674 1.91672 2.51377 + endloop + endfacet + facet normal 0.296526 0.175588 0.938744 + outer loop + vertex 1.60835 1.90893 2.51477 + vertex 1.61112 1.91183 2.51335 + vertex 1.60836 1.91352 2.51391 + endloop + endfacet + facet normal 0.298638 0.17341 0.93848 + outer loop + vertex 1.60815 1.9042 2.51571 + vertex 1.61239 1.90388 2.51442 + vertex 1.60835 1.90893 2.51477 + endloop + endfacet + facet normal 0.282573 0.163032 0.94529 + outer loop + vertex 1.60967 1.89994 2.51599 + vertex 1.60815 1.9042 2.51571 + vertex 1.6049 1.90168 2.51711 + endloop + endfacet + facet normal 0.220539 0.157549 0.96257 + outer loop + vertex 1.60532 1.9062 2.51619 + vertex 1.60413 1.90933 2.51595 + vertex 1.60084 1.90609 2.51724 + endloop + endfacet + facet normal 0.237914 0.183791 0.953739 + outer loop + vertex 1.60225 1.89746 2.51859 + vertex 1.6049 1.90168 2.51711 + vertex 1.60072 1.90123 2.51824 + endloop + endfacet + facet normal 0.268434 0.184064 0.945549 + outer loop + vertex 1.60361 1.89354 2.51897 + vertex 1.60703 1.89588 2.51754 + vertex 1.60225 1.89746 2.51859 + endloop + endfacet + facet normal 0.273149 0.177163 0.945517 + outer loop + vertex 1.60657 1.89155 2.51848 + vertex 1.60703 1.89588 2.51754 + vertex 1.60361 1.89354 2.51897 + endloop + endfacet + facet normal 0.295517 0.174439 0.939277 + outer loop + vertex 1.60782 1.88839 2.51868 + vertex 1.6109 1.89107 2.51721 + vertex 1.60657 1.89155 2.51848 + endloop + endfacet + facet normal 0.297654 0.176572 0.938203 + outer loop + vertex 1.60746 1.88414 2.51959 + vertex 1.61063 1.8864 2.51816 + vertex 1.60782 1.88839 2.51868 + endloop + endfacet + facet normal 0.29457 0.173242 0.939796 + outer loop + vertex 1.6034 1.88441 2.52082 + vertex 1.60494 1.88024 2.5211 + vertex 1.60746 1.88414 2.51959 + endloop + endfacet + facet normal 0.258904 0.160875 0.952411 + outer loop + vertex 1.60494 1.88024 2.5211 + vertex 1.6034 1.88441 2.52082 + vertex 1.60021 1.88192 2.5221 + endloop + endfacet + facet normal 0.163124 0.170297 0.971797 + outer loop + vertex 1.60048 1.88628 2.52122 + vertex 1.59895 1.88927 2.52096 + vertex 1.59582 1.88593 2.52207 + endloop + endfacet + facet normal 0.239223 0.171587 0.955683 + outer loop + vertex 1.60214 1.87623 2.52264 + vertex 1.60021 1.88192 2.5221 + vertex 1.59783 1.87802 2.5234 + endloop + endfacet + facet normal 0.292988 0.171331 0.94064 + outer loop + vertex 1.60214 1.87623 2.52264 + vertex 1.6016 1.87173 2.52363 + vertex 1.60604 1.87132 2.52232 + endloop + endfacet + facet normal 0.283947 0.166676 0.944242 + outer loop + vertex 1.60304 1.86854 2.52376 + vertex 1.6016 1.87173 2.52363 + vertex 1.59918 1.86852 2.52492 + endloop + endfacet + facet normal 0.288005 0.169561 0.942498 + outer loop + vertex 1.59862 1.86441 2.52583 + vertex 1.60261 1.86426 2.52464 + vertex 1.59918 1.86852 2.52492 + endloop + endfacet + facet normal 0.233735 0.144174 0.961552 + outer loop + vertex 1.59994 1.8603 2.52613 + vertex 1.59862 1.86441 2.52583 + vertex 1.59521 1.86167 2.52707 + endloop + endfacet + facet normal 0.135101 0.169795 0.976175 + outer loop + vertex 1.59477 1.86965 2.52574 + vertex 1.59159 1.86542 2.52691 + vertex 1.59595 1.86623 2.52617 + endloop + endfacet + facet normal 0.240351 0.171205 0.955469 + outer loop + vertex 1.59521 1.86167 2.52707 + vertex 1.59713 1.856 2.52761 + vertex 1.59994 1.8603 2.52613 + endloop + endfacet + facet normal 0.273719 0.169766 0.946709 + outer loop + vertex 1.59713 1.856 2.52761 + vertex 1.59661 1.85161 2.52854 + vertex 1.60103 1.85136 2.52731 + endloop + endfacet + facet normal 0.273753 0.17534 0.945682 + outer loop + vertex 1.59789 1.84857 2.52874 + vertex 1.60103 1.85136 2.52731 + vertex 1.59661 1.85161 2.52854 + endloop + endfacet + facet normal 0.283414 0.163293 0.944993 + outer loop + vertex 1.59746 1.84434 2.5296 + vertex 1.60073 1.84669 2.52821 + vertex 1.59789 1.84857 2.52874 + endloop + endfacet + facet normal 0.274183 0.15576 0.94898 + outer loop + vertex 1.5994 1.83873 2.52996 + vertex 1.59746 1.84434 2.5296 + vertex 1.59481 1.84037 2.53101 + endloop + endfacet + facet normal 0.218599 0.151719 0.963948 + outer loop + vertex 1.59481 1.84037 2.53101 + vertex 1.59179 1.8359 2.5324 + vertex 1.59612 1.83643 2.53134 + endloop + endfacet + facet normal 0.228458 0.169226 0.958733 + outer loop + vertex 1.59179 1.8359 2.5324 + vertex 1.59125 1.83118 2.53336 + vertex 1.59545 1.83196 2.53223 + endloop + endfacet + facet normal 0.227753 0.172438 0.958329 + outer loop + vertex 1.59294 1.8282 2.5335 + vertex 1.59545 1.83196 2.53223 + vertex 1.59125 1.83118 2.53336 + endloop + endfacet + facet normal 0.267751 0.152757 0.951302 + outer loop + vertex 1.59241 1.82368 2.53437 + vertex 1.59706 1.82627 2.53265 + vertex 1.59294 1.8282 2.5335 + endloop + endfacet + facet normal 0.239008 0.155723 0.958449 + outer loop + vertex 1.59412 1.81847 2.53479 + vertex 1.59241 1.82368 2.53437 + vertex 1.58968 1.81979 2.53569 + endloop + endfacet + facet normal 0.298352 0.149397 0.942691 + outer loop + vertex 1.59361 1.81433 2.53561 + vertex 1.59751 1.81416 2.5344 + vertex 1.59412 1.81847 2.53479 + endloop + endfacet + facet normal 0.159584 0.151821 0.97544 + outer loop + vertex 1.59098 1.81625 2.53602 + vertex 1.58671 1.81559 2.53682 + vertex 1.59028 1.81173 2.53683 + endloop + endfacet + facet normal 0.164714 0.156554 0.973838 + outer loop + vertex 1.58671 1.81559 2.53682 + vertex 1.5859 1.81084 2.53772 + vertex 1.59028 1.81173 2.53683 + endloop + endfacet + facet normal 0.163421 0.162238 0.973125 + outer loop + vertex 1.58708 1.80687 2.53818 + vertex 1.59028 1.81173 2.53683 + vertex 1.5859 1.81084 2.53772 + endloop + endfacet + facet normal 0.29839 0.140086 0.944108 + outer loop + vertex 1.59361 1.81433 2.53561 + vertex 1.5948 1.81026 2.53584 + vertex 1.59751 1.81416 2.5344 + endloop + endfacet + facet normal 0.203475 0.134938 0.969737 + outer loop + vertex 1.59184 1.8061 2.53729 + vertex 1.59028 1.81173 2.53683 + vertex 1.58708 1.80687 2.53818 + endloop + endfacet + facet normal 0.208092 0.171545 0.962948 + outer loop + vertex 1.58813 1.80309 2.53863 + vertex 1.59184 1.8061 2.53729 + vertex 1.58708 1.80687 2.53818 + endloop + endfacet + facet normal 0.223881 0.151989 0.962693 + outer loop + vertex 1.59088 1.80162 2.53822 + vertex 1.59184 1.8061 2.53729 + vertex 1.58813 1.80309 2.53863 + endloop + endfacet + facet normal 0.218131 0.14043 0.965763 + outer loop + vertex 1.58723 1.79866 2.53947 + vertex 1.59088 1.80162 2.53822 + vertex 1.58813 1.80309 2.53863 + endloop + endfacet + facet normal 0.241022 0.111451 0.964099 + outer loop + vertex 1.5918 1.79766 2.53845 + vertex 1.59088 1.80162 2.53822 + vertex 1.58723 1.79866 2.53947 + endloop + endfacet + facet normal 0.286393 0.121167 0.95042 + outer loop + vertex 1.5918 1.79766 2.53845 + vertex 1.59494 1.80179 2.53698 + vertex 1.59088 1.80162 2.53822 + endloop + endfacet + facet normal 0.285265 0.136007 0.94875 + outer loop + vertex 1.59184 1.8061 2.53729 + vertex 1.59088 1.80162 2.53822 + vertex 1.59494 1.80179 2.53698 + endloop + endfacet + facet normal 0.298944 0.139661 0.943995 + outer loop + vertex 1.59923 1.80849 2.5347 + vertex 1.59751 1.81416 2.5344 + vertex 1.5948 1.81026 2.53584 + endloop + endfacet + facet normal 0.295122 0.1342 0.945988 + outer loop + vertex 1.59839 1.80407 2.53559 + vertex 1.60243 1.80392 2.53435 + vertex 1.59923 1.80849 2.5347 + endloop + endfacet + facet normal 0.279548 0.131737 0.951051 + outer loop + vertex 1.5959 1.80619 2.53608 + vertex 1.59184 1.8061 2.53729 + vertex 1.59494 1.80179 2.53698 + endloop + endfacet + facet normal 0.298745 0.110863 0.947872 + outer loop + vertex 1.59606 1.79642 2.53725 + vertex 1.59494 1.80179 2.53698 + vertex 1.5918 1.79766 2.53845 + endloop + endfacet + facet normal 0.295172 0.120167 0.947857 + outer loop + vertex 1.59839 1.80407 2.53559 + vertex 1.59927 1.8 2.53583 + vertex 1.60243 1.80392 2.53435 + endloop + endfacet + facet normal 0.289339 0.111907 0.950663 + outer loop + vertex 1.61192 1.79615 2.53243 + vertex 1.61036 1.80179 2.53224 + vertex 1.60752 1.79759 2.5336 + endloop + endfacet + facet normal 0.282991 0.110219 0.952769 + outer loop + vertex 1.61036 1.80179 2.53224 + vertex 1.61192 1.79615 2.53243 + vertex 1.61487 1.80023 2.53108 + endloop + endfacet + facet normal 0.287539 0.127999 0.949177 + outer loop + vertex 1.60617 1.80165 2.53352 + vertex 1.60713 1.80624 2.53261 + vertex 1.60243 1.80392 2.53435 + endloop + endfacet + facet normal 0.281955 0.138135 0.949432 + outer loop + vertex 1.61026 1.81018 2.53111 + vertex 1.60713 1.80624 2.53261 + vertex 1.6112 1.80624 2.5314 + endloop + endfacet + facet normal 0.283628 0.138496 0.948881 + outer loop + vertex 1.6112 1.80624 2.5314 + vertex 1.61459 1.80856 2.53005 + vertex 1.61026 1.81018 2.53111 + endloop + endfacet + facet normal 0.28535 0.132535 0.949215 + outer loop + vertex 1.61459 1.80856 2.53005 + vertex 1.6178 1.80426 2.52969 + vertex 1.61855 1.80865 2.52885 + endloop + endfacet + facet normal 0.286063 0.120734 0.950574 + outer loop + vertex 1.61487 1.80023 2.53108 + vertex 1.61375 1.80425 2.53091 + vertex 1.61036 1.80179 2.53224 + endloop + endfacet + facet normal 0.281509 0.118702 0.952188 + outer loop + vertex 1.61937 1.79863 2.52992 + vertex 1.62233 1.80267 2.52855 + vertex 1.6178 1.80426 2.52969 + endloop + endfacet + facet normal 0.285407 0.103998 0.952747 + outer loop + vertex 1.61846 1.79419 2.53068 + vertex 1.62244 1.79424 2.52948 + vertex 1.61937 1.79863 2.52992 + endloop + endfacet + facet normal 0.285273 0.0915564 0.954063 + outer loop + vertex 1.61928 1.79012 2.53083 + vertex 1.61846 1.79419 2.53068 + vertex 1.61495 1.79178 2.53196 + endloop + endfacet + facet normal 0.284344 0.109148 0.952489 + outer loop + vertex 1.61487 1.80023 2.53108 + vertex 1.61192 1.79615 2.53243 + vertex 1.61596 1.7962 2.53122 + endloop + endfacet + facet normal 0.286362 0.086113 0.954244 + outer loop + vertex 1.61177 1.78763 2.53329 + vertex 1.61495 1.79178 2.53196 + vertex 1.61099 1.79171 2.53316 + endloop + endfacet + facet normal 0.285361 0.0859314 0.95456 + outer loop + vertex 1.61177 1.78763 2.53329 + vertex 1.61099 1.79171 2.53316 + vertex 1.60748 1.78924 2.53443 + endloop + endfacet + facet normal 0.28614 0.10026 0.952928 + outer loop + vertex 1.60855 1.79366 2.53371 + vertex 1.61192 1.79615 2.53243 + vertex 1.60752 1.79759 2.5336 + endloop + endfacet + facet normal 0.285953 0.0871141 0.954276 + outer loop + vertex 1.6035 1.78912 2.53563 + vertex 1.60748 1.78924 2.53443 + vertex 1.60459 1.79351 2.5349 + endloop + endfacet + facet normal 0.290782 0.083659 0.953125 + outer loop + vertex 1.60423 1.78507 2.53577 + vertex 1.6035 1.78912 2.53563 + vertex 1.59994 1.78667 2.53693 + endloop + endfacet + facet normal 0.29687 0.0915178 0.950522 + outer loop + vertex 1.60029 1.79512 2.53606 + vertex 1.59711 1.79105 2.53744 + vertex 1.60112 1.79109 2.53618 + endloop + endfacet + facet normal 0.296931 0.0914659 0.950508 + outer loop + vertex 1.59606 1.79642 2.53725 + vertex 1.59711 1.79105 2.53744 + vertex 1.60029 1.79512 2.53606 + endloop + endfacet + facet normal 0.307066 0.0933324 0.947101 + outer loop + vertex 1.59711 1.79105 2.53744 + vertex 1.59606 1.79642 2.53725 + vertex 1.59281 1.79284 2.53866 + endloop + endfacet + facet normal 0.305141 0.0879341 0.948239 + outer loop + vertex 1.5936 1.78875 2.53878 + vertex 1.59711 1.79105 2.53744 + vertex 1.59281 1.79284 2.53866 + endloop + endfacet + facet normal 0.298041 0.0866416 0.950613 + outer loop + vertex 1.5936 1.78875 2.53878 + vertex 1.59281 1.79284 2.53866 + vertex 1.58973 1.78892 2.53998 + endloop + endfacet + facet normal 0.300764 0.0852895 0.949877 + outer loop + vertex 1.59671 1.78261 2.53832 + vertex 1.59994 1.78667 2.53693 + vertex 1.59595 1.78665 2.5382 + endloop + endfacet + facet normal 0.309835 0.0869008 0.946811 + outer loop + vertex 1.59671 1.78261 2.53832 + vertex 1.59595 1.78665 2.5382 + vertex 1.5925 1.78446 2.53953 + endloop + endfacet + facet normal 0.296108 0.0867802 0.951204 + outer loop + vertex 1.58869 1.78464 2.5407 + vertex 1.58943 1.78047 2.54085 + vertex 1.5925 1.78446 2.53953 + endloop + endfacet + facet normal 0.233416 0.0762489 0.969383 + outer loop + vertex 1.58943 1.78047 2.54085 + vertex 1.58869 1.78464 2.5407 + vertex 1.5852 1.78199 2.54175 + endloop + endfacet + facet normal 0.141976 0.09374 0.985422 + outer loop + vertex 1.58553 1.79041 2.54086 + vertex 1.58219 1.78598 2.54176 + vertex 1.58636 1.78664 2.54109 + endloop + endfacet + facet normal 0.241255 0.100473 0.965247 + outer loop + vertex 1.5852 1.78199 2.54175 + vertex 1.58604 1.77647 2.54211 + vertex 1.58943 1.78047 2.54085 + endloop + endfacet + facet normal 0.258311 0.106742 0.960147 + outer loop + vertex 1.58604 1.77647 2.54211 + vertex 1.58695 1.77088 2.54249 + vertex 1.59031 1.77544 2.54108 + endloop + endfacet + facet normal 0.265429 0.116147 0.957109 + outer loop + vertex 1.58695 1.77088 2.54249 + vertex 1.58609 1.76623 2.54329 + vertex 1.59025 1.76669 2.54208 + endloop + endfacet + facet normal 0.26415 0.12555 0.956275 + outer loop + vertex 1.58723 1.76254 2.54346 + vertex 1.59025 1.76669 2.54208 + vertex 1.58609 1.76623 2.54329 + endloop + endfacet + facet normal 0.281115 0.127808 0.951125 + outer loop + vertex 1.58817 1.75868 2.5437 + vertex 1.59177 1.76103 2.54232 + vertex 1.58723 1.76254 2.54346 + endloop + endfacet + facet normal 0.285262 0.125746 0.950165 + outer loop + vertex 1.5873 1.75444 2.54452 + vertex 1.59085 1.75661 2.54317 + vertex 1.58817 1.75868 2.5437 + endloop + endfacet + facet normal 0.261786 0.129989 0.956332 + outer loop + vertex 1.58324 1.75452 2.54562 + vertex 1.58448 1.75053 2.54583 + vertex 1.5873 1.75444 2.54452 + endloop + endfacet + facet normal 0.191066 0.109039 0.975502 + outer loop + vertex 1.58448 1.75053 2.54583 + vertex 1.58324 1.75452 2.54562 + vertex 1.57997 1.75188 2.54656 + endloop + endfacet + facet normal 0.0935453 0.139945 0.985731 + outer loop + vertex 1.58041 1.75605 2.54593 + vertex 1.57871 1.75863 2.54573 + vertex 1.57617 1.75523 2.54645 + endloop + endfacet + facet normal 0.19603 0.127318 0.972298 + outer loop + vertex 1.57997 1.75188 2.54656 + vertex 1.58125 1.7466 2.54699 + vertex 1.58448 1.75053 2.54583 + endloop + endfacet + facet normal 0.221883 0.114236 0.968359 + outer loop + vertex 1.58125 1.7466 2.54699 + vertex 1.58212 1.74096 2.54746 + vertex 1.58556 1.74561 2.54612 + endloop + endfacet + facet normal 0.233285 0.10675 0.966531 + outer loop + vertex 1.58212 1.74096 2.54746 + vertex 1.58093 1.73595 2.5483 + vertex 1.58537 1.73682 2.54713 + endloop + endfacet + facet normal 0.230796 0.118501 0.965759 + outer loop + vertex 1.58213 1.73218 2.54847 + vertex 1.58537 1.73682 2.54713 + vertex 1.58093 1.73595 2.5483 + endloop + endfacet + facet normal 0.258369 0.12548 0.957862 + outer loop + vertex 1.5832 1.72849 2.54867 + vertex 1.58683 1.73119 2.54734 + vertex 1.58213 1.73218 2.54847 + endloop + endfacet + facet normal 0.264432 0.10844 0.958288 + outer loop + vertex 1.58221 1.72418 2.54943 + vertex 1.58585 1.72673 2.54814 + vertex 1.5832 1.72849 2.54867 + endloop + endfacet + facet normal 0.24291 0.108302 0.963984 + outer loop + vertex 1.58353 1.71916 2.54966 + vertex 1.58221 1.72418 2.54943 + vertex 1.5793 1.72017 2.55062 + endloop + endfacet + facet normal 0.29948 0.107878 0.947984 + outer loop + vertex 1.58466 1.71392 2.5499 + vertex 1.58772 1.7178 2.54849 + vertex 1.58353 1.71916 2.54966 + endloop + endfacet + facet normal 0.312782 0.104445 0.944065 + outer loop + vertex 1.58367 1.70963 2.5507 + vertex 1.58746 1.70943 2.54947 + vertex 1.58466 1.71392 2.5499 + endloop + endfacet + facet normal 0.263208 0.0899005 0.960541 + outer loop + vertex 1.58451 1.70551 2.55086 + vertex 1.58367 1.70963 2.5507 + vertex 1.58026 1.70712 2.55187 + endloop + endfacet + facet normal 0.186294 0.104789 0.97689 + outer loop + vertex 1.58044 1.71565 2.55089 + vertex 1.57719 1.71123 2.55198 + vertex 1.58132 1.7117 2.55114 + endloop + endfacet + facet normal 0.26565 0.0972554 0.959151 + outer loop + vertex 1.58026 1.70712 2.55187 + vertex 1.58123 1.70163 2.55216 + vertex 1.58451 1.70551 2.55086 + endloop + endfacet + facet normal 0.274207 0.0883647 0.957602 + outer loop + vertex 1.58123 1.70163 2.55216 + vertex 1.58213 1.69609 2.55241 + vertex 1.5855 1.70055 2.55104 + endloop + endfacet + facet normal 0.277182 0.0862224 0.956941 + outer loop + vertex 1.58213 1.69609 2.55241 + vertex 1.58105 1.69147 2.55314 + vertex 1.58508 1.69205 2.55192 + endloop + endfacet + facet normal 0.277991 0.0810594 0.957157 + outer loop + vertex 1.58167 1.68775 2.55328 + vertex 1.58508 1.69205 2.55192 + vertex 1.58105 1.69147 2.55314 + endloop + endfacet + facet normal 0.290471 0.0724299 0.954139 + outer loop + vertex 1.58211 1.6829 2.55351 + vertex 1.58576 1.68676 2.55211 + vertex 1.58167 1.68775 2.55328 + endloop + endfacet + facet normal 0.298554 0.0740888 0.951513 + outer loop + vertex 1.58288 1.67788 2.55366 + vertex 1.58637 1.68159 2.55228 + vertex 1.58211 1.6829 2.55351 + endloop + endfacet + facet normal 0.309865 0.071659 0.948076 + outer loop + vertex 1.58358 1.67374 2.55375 + vertex 1.58717 1.67614 2.55239 + vertex 1.58288 1.67788 2.55366 + endloop + endfacet + facet normal 0.316068 0.0679711 0.946299 + outer loop + vertex 1.58239 1.66941 2.55446 + vertex 1.5859 1.67169 2.55312 + vertex 1.58358 1.67374 2.55375 + endloop + endfacet + facet normal 0.294595 0.0659086 0.953347 + outer loop + vertex 1.58316 1.66418 2.55458 + vertex 1.58239 1.66941 2.55446 + vertex 1.57928 1.66551 2.55569 + endloop + endfacet + facet normal 0.227565 0.0616732 0.971808 + outer loop + vertex 1.57928 1.66551 2.55569 + vertex 1.57601 1.66182 2.55669 + vertex 1.57994 1.66061 2.55584 + endloop + endfacet + facet normal 0.229411 0.0683032 0.97093 + outer loop + vertex 1.57601 1.66182 2.55669 + vertex 1.57655 1.65671 2.55692 + vertex 1.57994 1.66061 2.55584 + endloop + endfacet + facet normal 0.239071 0.0699203 0.968481 + outer loop + vertex 1.57655 1.65671 2.55692 + vertex 1.57724 1.65119 2.55715 + vertex 1.58061 1.65566 2.55599 + endloop + endfacet + facet normal 0.232456 0.0639681 0.970501 + outer loop + vertex 1.57724 1.65119 2.55715 + vertex 1.57602 1.64621 2.55777 + vertex 1.58019 1.64708 2.55671 + endloop + endfacet + facet normal 0.232603 0.0632773 0.970511 + outer loop + vertex 1.57671 1.64221 2.55786 + vertex 1.58019 1.64708 2.55671 + vertex 1.57602 1.64621 2.55777 + endloop + endfacet + facet normal 0.244981 0.0531851 0.968068 + outer loop + vertex 1.57691 1.6373 2.55808 + vertex 1.58087 1.64179 2.55683 + vertex 1.57671 1.64221 2.55786 + endloop + endfacet + facet normal 0.249833 0.0533073 0.96682 + outer loop + vertex 1.57693 1.63233 2.55835 + vertex 1.58109 1.63677 2.55703 + vertex 1.57691 1.6373 2.55808 + endloop + endfacet + facet normal 0.258571 0.0556456 0.964388 + outer loop + vertex 1.57716 1.62754 2.55857 + vertex 1.58115 1.63174 2.55725 + vertex 1.57693 1.63233 2.55835 + endloop + endfacet + facet normal 0.271465 0.0570764 0.960755 + outer loop + vertex 1.57758 1.62283 2.55872 + vertex 1.58144 1.62667 2.55741 + vertex 1.57716 1.62754 2.55857 + endloop + endfacet + facet normal 0.288896 0.0641948 0.955206 + outer loop + vertex 1.57826 1.61883 2.55879 + vertex 1.58239 1.6213 2.55737 + vertex 1.57758 1.62283 2.55872 + endloop + endfacet + facet normal 0.292033 0.056627 0.95473 + outer loop + vertex 1.57709 1.61447 2.5594 + vertex 1.5813 1.61678 2.55798 + vertex 1.57826 1.61883 2.55879 + endloop + endfacet + facet normal 0.14785 0.0328906 0.988463 + outer loop + vertex 1.57399 1.61051 2.56046 + vertex 1.57288 1.61431 2.5605 + vertex 1.56976 1.61176 2.56105 + endloop + endfacet + facet normal 0.301887 0.0616769 0.951347 + outer loop + vertex 1.57812 1.60929 2.55941 + vertex 1.58184 1.61262 2.55802 + vertex 1.57709 1.61447 2.5594 + endloop + endfacet + facet normal 0.15413 0.0551979 0.986508 + outer loop + vertex 1.56976 1.61176 2.56105 + vertex 1.57078 1.60683 2.56117 + vertex 1.57399 1.61051 2.56046 + endloop + endfacet + facet normal 0.273152 0.040308 0.961126 + outer loop + vertex 1.57853 1.60437 2.5595 + vertex 1.57812 1.60929 2.55941 + vertex 1.57474 1.60574 2.56052 + endloop + endfacet + facet normal 0.323187 0.0367568 0.945621 + outer loop + vertex 1.57868 1.59944 2.55965 + vertex 1.58229 1.60297 2.55827 + vertex 1.57853 1.60437 2.5595 + endloop + endfacet + facet normal 0.183045 0.0387782 0.982339 + outer loop + vertex 1.57125 1.60192 2.56132 + vertex 1.57136 1.59694 2.56149 + vertex 1.57502 1.60082 2.56066 + endloop + endfacet + facet normal 0.278173 0.0374463 0.959801 + outer loop + vertex 1.57876 1.59444 2.55982 + vertex 1.57868 1.59944 2.55965 + vertex 1.57511 1.59583 2.56082 + endloop + endfacet + facet normal 0.322935 0.0383057 0.945646 + outer loop + vertex 1.57889 1.58943 2.55998 + vertex 1.58245 1.59305 2.55861 + vertex 1.57876 1.59444 2.55982 + endloop + endfacet + facet normal 0.190436 0.0389205 0.980928 + outer loop + vertex 1.57142 1.59194 2.56168 + vertex 1.57153 1.58694 2.56186 + vertex 1.57522 1.59082 2.56099 + endloop + endfacet + facet normal 0.281361 0.0365667 0.958905 + outer loop + vertex 1.57905 1.58444 2.56012 + vertex 1.57889 1.58943 2.55998 + vertex 1.57537 1.58582 2.56115 + endloop + endfacet + facet normal 0.32575 0.0311176 0.944944 + outer loop + vertex 1.5792 1.57946 2.56023 + vertex 1.58277 1.58304 2.55888 + vertex 1.57905 1.58444 2.56012 + endloop + endfacet + facet normal 0.290834 0.0208694 0.956546 + outer loop + vertex 1.57928 1.5744 2.56032 + vertex 1.5792 1.57946 2.56023 + vertex 1.57565 1.57598 2.56139 + endloop + endfacet + facet normal 0.196271 0.0329405 0.979996 + outer loop + vertex 1.57164 1.58194 2.56203 + vertex 1.57176 1.57697 2.56217 + vertex 1.57552 1.58085 2.56129 + endloop + endfacet + facet normal 0.289675 0.0179211 0.956957 + outer loop + vertex 1.57581 1.57159 2.56142 + vertex 1.57928 1.5744 2.56032 + vertex 1.57565 1.57598 2.56139 + endloop + endfacet + facet normal 0.328194 0.0198085 0.944403 + outer loop + vertex 1.58302 1.57295 2.55905 + vertex 1.583 1.57796 2.55895 + vertex 1.57928 1.5744 2.56032 + endloop + endfacet + facet normal 0.327346 0.0176612 0.94474 + outer loop + vertex 1.5835 1.56911 2.55895 + vertex 1.58611 1.57167 2.558 + vertex 1.58302 1.57295 2.55905 + endloop + endfacet + facet normal 0.324894 0.0248745 0.945423 + outer loop + vertex 1.58257 1.5647 2.55939 + vertex 1.58664 1.56793 2.55791 + vertex 1.5835 1.56911 2.55895 + endloop + endfacet + facet normal 0.21602 0.0268361 0.97602 + outer loop + vertex 1.57591 1.55704 2.56174 + vertex 1.57572 1.56242 2.56163 + vertex 1.57179 1.55749 2.56263 + endloop + endfacet + facet normal 0.215546 0.0220018 0.976246 + outer loop + vertex 1.57201 1.55262 2.5627 + vertex 1.57591 1.55704 2.56174 + vertex 1.57179 1.55749 2.56263 + endloop + endfacet + facet normal 0.219505 0.0183416 0.975439 + outer loop + vertex 1.57608 1.55202 2.56179 + vertex 1.57591 1.55704 2.56174 + vertex 1.57201 1.55262 2.5627 + endloop + endfacet + facet normal 0.219455 0.0179693 0.975457 + outer loop + vertex 1.57211 1.54761 2.56277 + vertex 1.57608 1.55202 2.56179 + vertex 1.57201 1.55262 2.5627 + endloop + endfacet + facet normal 0.329338 0.020619 0.943987 + outer loop + vertex 1.58316 1.55951 2.5593 + vertex 1.58257 1.5647 2.55939 + vertex 1.57941 1.56069 2.56058 + endloop + endfacet + facet normal 0.33097 0.0180617 0.943468 + outer loop + vertex 1.58336 1.5545 2.55932 + vertex 1.58701 1.55812 2.55797 + vertex 1.58316 1.55951 2.5593 + endloop + endfacet + facet normal 0.294816 0.020677 0.95533 + outer loop + vertex 1.57591 1.55704 2.56174 + vertex 1.57608 1.55202 2.56179 + vertex 1.57967 1.55587 2.5606 + endloop + endfacet + facet normal 0.22065 0.0168368 0.975208 + outer loop + vertex 1.57617 1.54701 2.56186 + vertex 1.57608 1.55202 2.56179 + vertex 1.57211 1.54761 2.56277 + endloop + endfacet + facet normal 0.220388 0.0149522 0.975298 + outer loop + vertex 1.57213 1.54259 2.56284 + vertex 1.57617 1.54701 2.56186 + vertex 1.57211 1.54761 2.56277 + endloop + endfacet + facet normal 0.22045 0.0148935 0.975285 + outer loop + vertex 1.57621 1.542 2.56192 + vertex 1.57617 1.54701 2.56186 + vertex 1.57213 1.54259 2.56284 + endloop + endfacet + facet normal 0.220319 0.0139138 0.975329 + outer loop + vertex 1.57215 1.5376 2.56291 + vertex 1.57621 1.542 2.56192 + vertex 1.57213 1.54259 2.56284 + endloop + endfacet + facet normal 0.335444 0.0169235 0.941908 + outer loop + vertex 1.58344 1.54948 2.55938 + vertex 1.58336 1.5545 2.55932 + vertex 1.57981 1.55088 2.56065 + endloop + endfacet + facet normal 0.333154 0.0160175 0.942736 + outer loop + vertex 1.58348 1.54449 2.55945 + vertex 1.58711 1.54809 2.55811 + vertex 1.58344 1.54948 2.55938 + endloop + endfacet + facet normal 0.298495 0.0152791 0.954289 + outer loop + vertex 1.57617 1.54701 2.56186 + vertex 1.57621 1.542 2.56192 + vertex 1.57987 1.54588 2.56072 + endloop + endfacet + facet normal 0.223229 0.0110911 0.974703 + outer loop + vertex 1.57624 1.53701 2.56197 + vertex 1.57621 1.542 2.56192 + vertex 1.57215 1.5376 2.56291 + endloop + endfacet + facet normal 0.222992 0.00930796 0.974776 + outer loop + vertex 1.57216 1.53261 2.56295 + vertex 1.57624 1.53701 2.56197 + vertex 1.57215 1.5376 2.56291 + endloop + endfacet + facet normal 0.225748 0.00661724 0.974163 + outer loop + vertex 1.57627 1.53202 2.562 + vertex 1.57624 1.53701 2.56197 + vertex 1.57216 1.53261 2.56295 + endloop + endfacet + facet normal 0.225683 0.0061351 0.974181 + outer loop + vertex 1.57217 1.52762 2.56298 + vertex 1.57627 1.53202 2.562 + vertex 1.57216 1.53261 2.56295 + endloop + endfacet + facet normal 0.335417 0.0132454 0.941977 + outer loop + vertex 1.58353 1.5395 2.55951 + vertex 1.58348 1.54449 2.55945 + vertex 1.57992 1.54088 2.56077 + endloop + endfacet + facet normal 0.33125 0.00972551 0.943493 + outer loop + vertex 1.58358 1.53451 2.55954 + vertex 1.58721 1.53811 2.55823 + vertex 1.58353 1.5395 2.55951 + endloop + endfacet + facet normal 0.299862 0.00687329 0.953958 + outer loop + vertex 1.57624 1.53701 2.56197 + vertex 1.57627 1.53202 2.562 + vertex 1.57996 1.53589 2.56081 + endloop + endfacet + facet normal 0.22725 0.00459802 0.973826 + outer loop + vertex 1.57629 1.52703 2.56202 + vertex 1.57627 1.53202 2.562 + vertex 1.57217 1.52762 2.56298 + endloop + endfacet + facet normal 0.227262 0.00468574 0.973822 + outer loop + vertex 1.57218 1.52263 2.563 + vertex 1.57629 1.52703 2.56202 + vertex 1.57217 1.52762 2.56298 + endloop + endfacet + facet normal 0.228638 0.00333204 0.973506 + outer loop + vertex 1.5763 1.52204 2.56204 + vertex 1.57629 1.52703 2.56202 + vertex 1.57218 1.52263 2.563 + endloop + endfacet + facet normal 0.228497 0.00228559 0.973542 + outer loop + vertex 1.57218 1.51763 2.56301 + vertex 1.5763 1.52204 2.56204 + vertex 1.57218 1.52263 2.563 + endloop + endfacet + facet normal 0.334529 0.0060703 0.942366 + outer loop + vertex 1.58361 1.52952 2.55956 + vertex 1.58358 1.53451 2.55954 + vertex 1.58 1.53091 2.56084 + endloop + endfacet + facet normal 0.330147 0.00357942 0.943923 + outer loop + vertex 1.58362 1.52452 2.55958 + vertex 1.58728 1.52813 2.55828 + vertex 1.58361 1.52952 2.55956 + endloop + endfacet + facet normal 0.300786 0.00344587 0.953685 + outer loop + vertex 1.57629 1.52703 2.56202 + vertex 1.5763 1.52204 2.56204 + vertex 1.58001 1.52591 2.56085 + endloop + endfacet + facet normal 0.228399 0.00238152 0.973565 + outer loop + vertex 1.57631 1.51705 2.56205 + vertex 1.5763 1.52204 2.56204 + vertex 1.57218 1.51763 2.56301 + endloop + endfacet + facet normal 0.228497 0.00311585 0.97354 + outer loop + vertex 1.57219 1.51265 2.56303 + vertex 1.57631 1.51705 2.56205 + vertex 1.57218 1.51763 2.56301 + endloop + endfacet + facet normal 0.230375 0.00126449 0.973101 + outer loop + vertex 1.57631 1.51206 2.56205 + vertex 1.57631 1.51705 2.56205 + vertex 1.57219 1.51265 2.56303 + endloop + endfacet + facet normal 0.230127 -0.000570522 0.97316 + outer loop + vertex 1.57219 1.50765 2.56302 + vertex 1.57631 1.51206 2.56205 + vertex 1.57219 1.51265 2.56303 + endloop + endfacet + facet normal 0.333495 0.00237671 0.942749 + outer loop + vertex 1.58363 1.51953 2.55959 + vertex 1.58362 1.52452 2.55958 + vertex 1.58002 1.52092 2.56086 + endloop + endfacet + facet normal 0.330017 0.00133417 0.943974 + outer loop + vertex 1.58364 1.51454 2.55959 + vertex 1.5873 1.51815 2.5583 + vertex 1.58363 1.51953 2.55959 + endloop + endfacet + facet normal 0.302215 0.0013191 0.953239 + outer loop + vertex 1.57631 1.51705 2.56205 + vertex 1.57631 1.51206 2.56205 + vertex 1.58003 1.51593 2.56087 + endloop + endfacet + facet normal 0.230646 -0.00108138 0.973037 + outer loop + vertex 1.57631 1.50706 2.56205 + vertex 1.57631 1.51206 2.56205 + vertex 1.57219 1.50765 2.56302 + endloop + endfacet + facet normal 0.230541 -0.00185416 0.973061 + outer loop + vertex 1.5722 1.50265 2.56301 + vertex 1.57631 1.50706 2.56205 + vertex 1.57219 1.50765 2.56302 + endloop + endfacet + facet normal 0.230335 -0.00165117 0.97311 + outer loop + vertex 1.57631 1.50207 2.56204 + vertex 1.57631 1.50706 2.56205 + vertex 1.5722 1.50265 2.56301 + endloop + endfacet + facet normal 0.23004 -0.00382261 0.973174 + outer loop + vertex 1.57219 1.49766 2.56299 + vertex 1.57631 1.50207 2.56204 + vertex 1.5722 1.50265 2.56301 + endloop + endfacet + facet normal 0.334819 -0.000605553 0.942282 + outer loop + vertex 1.58365 1.50955 2.55959 + vertex 1.58364 1.51454 2.55959 + vertex 1.58003 1.51094 2.56087 + endloop + endfacet + facet normal 0.330774 -0.00250148 0.943707 + outer loop + vertex 1.58365 1.50456 2.55957 + vertex 1.58732 1.50816 2.55829 + vertex 1.58365 1.50955 2.55959 + endloop + endfacet + facet normal 0.30224 -0.00164121 0.95323 + outer loop + vertex 1.57631 1.50706 2.56205 + vertex 1.57631 1.50207 2.56204 + vertex 1.58004 1.50595 2.56086 + endloop + endfacet + facet normal 0.228005 -0.00182099 0.973658 + outer loop + vertex 1.5763 1.49708 2.56203 + vertex 1.57631 1.50207 2.56204 + vertex 1.57219 1.49766 2.56299 + endloop + endfacet + facet normal 0.227598 -0.00484077 0.973743 + outer loop + vertex 1.57219 1.49266 2.56297 + vertex 1.5763 1.49708 2.56203 + vertex 1.57219 1.49766 2.56299 + endloop + endfacet + facet normal 0.226527 -0.00378963 0.973997 + outer loop + vertex 1.57629 1.49207 2.56201 + vertex 1.5763 1.49708 2.56203 + vertex 1.57219 1.49266 2.56297 + endloop + endfacet + facet normal 0.226219 -0.00604846 0.974058 + outer loop + vertex 1.5722 1.48768 2.56294 + vertex 1.57629 1.49207 2.56201 + vertex 1.57219 1.49266 2.56297 + endloop + endfacet + facet normal 0.225865 -0.00570141 0.974142 + outer loop + vertex 1.57627 1.48708 2.56199 + vertex 1.57629 1.49207 2.56201 + vertex 1.5722 1.48768 2.56294 + endloop + endfacet + facet normal 0.225399 -0.00900024 0.974225 + outer loop + vertex 1.5722 1.4827 2.56289 + vertex 1.57627 1.48708 2.56199 + vertex 1.5722 1.48768 2.56294 + endloop + endfacet + facet normal 0.22591 -0.00950127 0.974102 + outer loop + vertex 1.57624 1.48209 2.56195 + vertex 1.57627 1.48708 2.56199 + vertex 1.5722 1.4827 2.56289 + endloop + endfacet + facet normal 0.225243 -0.0140223 0.974202 + outer loop + vertex 1.57217 1.47772 2.56282 + vertex 1.57624 1.48209 2.56195 + vertex 1.5722 1.4827 2.56289 + endloop + endfacet + facet normal 0.336693 -0.00340414 0.941608 + outer loop + vertex 1.58364 1.49957 2.55955 + vertex 1.58365 1.50456 2.55957 + vertex 1.58003 1.50095 2.56085 + endloop + endfacet + facet normal 0.332411 -0.00399708 0.943126 + outer loop + vertex 1.58363 1.49457 2.55954 + vertex 1.58732 1.49818 2.55825 + vertex 1.58364 1.49957 2.55955 + endloop + endfacet + facet normal 0.30422 -0.00393693 0.952594 + outer loop + vertex 1.5763 1.49708 2.56203 + vertex 1.57629 1.49207 2.56201 + vertex 1.58002 1.49595 2.56084 + endloop + endfacet + facet normal 0.338674 -0.00555901 0.940887 + outer loop + vertex 1.5836 1.48957 2.55952 + vertex 1.58363 1.49457 2.55954 + vertex 1.58 1.49095 2.56082 + endloop + endfacet + facet normal 0.334629 -0.00780298 0.942318 + outer loop + vertex 1.58356 1.48458 2.55949 + vertex 1.58726 1.48819 2.55821 + vertex 1.5836 1.48957 2.55952 + endloop + endfacet + facet normal 0.303345 -0.00984057 0.95283 + outer loop + vertex 1.57627 1.48708 2.56199 + vertex 1.57624 1.48209 2.56195 + vertex 1.57997 1.48596 2.5608 + endloop + endfacet + facet normal 0.223811 -0.0126187 0.974551 + outer loop + vertex 1.5762 1.47709 2.56189 + vertex 1.57624 1.48209 2.56195 + vertex 1.57217 1.47772 2.56282 + endloop + endfacet + facet normal 0.223383 -0.0154398 0.974609 + outer loop + vertex 1.57215 1.47274 2.56275 + vertex 1.5762 1.47709 2.56189 + vertex 1.57217 1.47772 2.56282 + endloop + endfacet + facet normal 0.222355 -0.0144351 0.974859 + outer loop + vertex 1.57616 1.47209 2.56183 + vertex 1.5762 1.47709 2.56189 + vertex 1.57215 1.47274 2.56275 + endloop + endfacet + facet normal 0.221693 -0.0186372 0.974938 + outer loop + vertex 1.57211 1.46774 2.56266 + vertex 1.57616 1.47209 2.56183 + vertex 1.57215 1.47274 2.56275 + endloop + endfacet + facet normal 0.337908 -0.00961748 0.94113 + outer loop + vertex 1.58353 1.4796 2.55945 + vertex 1.58356 1.48458 2.55949 + vertex 1.57992 1.48097 2.56076 + endloop + endfacet + facet normal 0.332356 -0.0106496 0.943094 + outer loop + vertex 1.58351 1.47462 2.5594 + vertex 1.58721 1.47824 2.55814 + vertex 1.58353 1.4796 2.55945 + endloop + endfacet + facet normal 0.300527 -0.01479 0.953659 + outer loop + vertex 1.5762 1.47709 2.56189 + vertex 1.57616 1.47209 2.56183 + vertex 1.57989 1.47598 2.56071 + endloop + endfacet + facet normal 0.219868 -0.016858 0.975384 + outer loop + vertex 1.5761 1.46708 2.56175 + vertex 1.57616 1.47209 2.56183 + vertex 1.57211 1.46774 2.56266 + endloop + endfacet + facet normal 0.219196 -0.02101 0.975455 + outer loop + vertex 1.57209 1.46273 2.56256 + vertex 1.5761 1.46708 2.56175 + vertex 1.57211 1.46774 2.56266 + endloop + endfacet + facet normal 0.216699 -0.0185929 0.976061 + outer loop + vertex 1.57601 1.46212 2.56168 + vertex 1.5761 1.46708 2.56175 + vertex 1.57209 1.46273 2.56256 + endloop + endfacet + facet normal 0.215783 -0.024615 0.976131 + outer loop + vertex 1.57215 1.45776 2.56242 + vertex 1.57601 1.46212 2.56168 + vertex 1.57209 1.46273 2.56256 + endloop + endfacet + facet normal 0.334153 -0.0128813 0.942431 + outer loop + vertex 1.58344 1.46959 2.55936 + vertex 1.58351 1.47462 2.5594 + vertex 1.57984 1.47097 2.56065 + endloop + endfacet + facet normal 0.327749 -0.015879 0.944631 + outer loop + vertex 1.58321 1.4644 2.55935 + vertex 1.58713 1.46822 2.55805 + vertex 1.58344 1.46959 2.55936 + endloop + endfacet + facet normal 0.296213 -0.0195924 0.954921 + outer loop + vertex 1.5761 1.46708 2.56175 + vertex 1.57601 1.46212 2.56168 + vertex 1.57972 1.46593 2.56061 + endloop + endfacet + facet normal 0.209476 -0.0187711 0.977634 + outer loop + vertex 1.57602 1.45756 2.56159 + vertex 1.57601 1.46212 2.56168 + vertex 1.57215 1.45776 2.56242 + endloop + endfacet + facet normal 0.209266 -0.0227149 0.977595 + outer loop + vertex 1.57602 1.45756 2.56159 + vertex 1.57215 1.45776 2.56242 + vertex 1.57269 1.45265 2.56219 + endloop + endfacet + facet normal 0.330796 -0.0189427 0.943512 + outer loop + vertex 1.58251 1.45859 2.55948 + vertex 1.58321 1.4644 2.55935 + vertex 1.57942 1.46098 2.56061 + endloop + endfacet + facet normal 0.330455 -0.0216405 0.943574 + outer loop + vertex 1.58251 1.45859 2.55948 + vertex 1.57936 1.45383 2.56047 + vertex 1.58298 1.45336 2.5592 + endloop + endfacet + facet normal 0.287296 -0.0147012 0.957729 + outer loop + vertex 1.5788 1.45706 2.56075 + vertex 1.57602 1.45756 2.56159 + vertex 1.57661 1.45435 2.56136 + endloop + endfacet + facet normal 0.217655 -0.0286441 0.975605 + outer loop + vertex 1.57661 1.45435 2.56136 + vertex 1.57602 1.45756 2.56159 + vertex 1.57269 1.45265 2.56219 + endloop + endfacet + facet normal 0.288238 -0.0212811 0.957322 + outer loop + vertex 1.5793 1.44452 2.56027 + vertex 1.57937 1.44934 2.56036 + vertex 1.5757 1.44576 2.56139 + endloop + endfacet + facet normal 0.325406 -0.0241483 0.945266 + outer loop + vertex 1.57922 1.4396 2.56018 + vertex 1.58311 1.44346 2.55893 + vertex 1.5793 1.44452 2.56027 + endloop + endfacet + facet normal 0.196186 -0.0309455 0.980078 + outer loop + vertex 1.57177 1.44203 2.5621 + vertex 1.57165 1.43711 2.56197 + vertex 1.57556 1.4409 2.56131 + endloop + endfacet + facet normal 0.284893 -0.0296042 0.958102 + outer loop + vertex 1.57908 1.43463 2.56006 + vertex 1.57922 1.4396 2.56018 + vertex 1.57543 1.43597 2.56119 + endloop + endfacet + facet normal 0.326715 -0.0376377 0.944373 + outer loop + vertex 1.57891 1.42964 2.55992 + vertex 1.58276 1.43326 2.55874 + vertex 1.57908 1.43463 2.56006 + endloop + endfacet + facet normal 0.190254 -0.0369548 0.981039 + outer loop + vertex 1.57152 1.43214 2.56182 + vertex 1.57141 1.42715 2.56166 + vertex 1.57528 1.431 2.56105 + endloop + endfacet + facet normal 0.283329 -0.0414534 0.958126 + outer loop + vertex 1.57876 1.42466 2.55975 + vertex 1.57891 1.42964 2.55992 + vertex 1.57512 1.42601 2.56089 + endloop + endfacet + facet normal 0.321326 -0.0429004 0.945996 + outer loop + vertex 1.57856 1.41962 2.55959 + vertex 1.58249 1.42335 2.55843 + vertex 1.57876 1.42466 2.55975 + endloop + endfacet + facet normal 0.274087 -0.0390443 0.960912 + outer loop + vertex 1.57823 1.41441 2.55947 + vertex 1.57856 1.41962 2.55959 + vertex 1.57467 1.41592 2.56055 + endloop + endfacet + facet normal 0.192694 -0.0487024 0.98005 + outer loop + vertex 1.57139 1.42228 2.56147 + vertex 1.5712 1.41739 2.56126 + vertex 1.57493 1.42101 2.56071 + endloop + endfacet + facet normal 0.275798 -0.0347754 0.960586 + outer loop + vertex 1.57429 1.41088 2.56048 + vertex 1.57823 1.41441 2.55947 + vertex 1.57467 1.41592 2.56055 + endloop + endfacet + facet normal 0.31362 -0.0370996 0.948823 + outer loop + vertex 1.5821 1.41314 2.55815 + vertex 1.58234 1.41833 2.55827 + vertex 1.57823 1.41441 2.55947 + endloop + endfacet + facet normal 0.316374 -0.0389989 0.947833 + outer loop + vertex 1.58196 1.40793 2.55798 + vertex 1.58607 1.41214 2.55678 + vertex 1.5821 1.41314 2.55815 + endloop + endfacet + facet normal 0.294816 -0.0449434 0.954496 + outer loop + vertex 1.58204 1.40291 2.55772 + vertex 1.58196 1.40793 2.55798 + vertex 1.57765 1.40321 2.55909 + endloop + endfacet + facet normal 0.291721 -0.0630977 0.95442 + outer loop + vertex 1.57358 1.40684 2.56055 + vertex 1.57387 1.40354 2.56024 + vertex 1.5774 1.40855 2.55949 + endloop + endfacet + facet normal 0.255418 -0.0399511 0.966005 + outer loop + vertex 1.58175 1.39215 2.55729 + vertex 1.58253 1.39781 2.55731 + vertex 1.57752 1.39285 2.55843 + endloop + endfacet + facet normal 0.29281 -0.0696585 0.95363 + outer loop + vertex 1.57758 1.39805 2.55873 + vertex 1.58204 1.40291 2.55772 + vertex 1.57765 1.40321 2.55909 + endloop + endfacet + facet normal 0.308462 -0.0399757 0.950396 + outer loop + vertex 1.58593 1.40275 2.55645 + vertex 1.58596 1.40723 2.55663 + vertex 1.58204 1.40291 2.55772 + endloop + endfacet + facet normal 0.315239 -0.0428908 0.948043 + outer loop + vertex 1.58873 1.40231 2.55549 + vertex 1.58593 1.40275 2.55645 + vertex 1.58646 1.3996 2.55613 + endloop + endfacet + facet normal 0.310039 -0.0475347 0.949535 + outer loop + vertex 1.58917 1.39461 2.55497 + vertex 1.59295 1.39864 2.55394 + vertex 1.58925 1.39912 2.55517 + endloop + endfacet + facet normal 0.303849 -0.0465449 0.951583 + outer loop + vertex 1.58253 1.39781 2.55731 + vertex 1.58175 1.39215 2.55729 + vertex 1.58577 1.39576 2.55618 + endloop + endfacet + facet normal 0.250313 -0.0468597 0.96703 + outer loop + vertex 1.58142 1.3871 2.55713 + vertex 1.58175 1.39215 2.55729 + vertex 1.57735 1.38775 2.55821 + endloop + endfacet + facet normal 0.322226 -0.0517159 0.945249 + outer loop + vertex 1.58893 1.38968 2.55478 + vertex 1.58917 1.39461 2.55497 + vertex 1.58536 1.39094 2.55607 + endloop + endfacet + facet normal 0.312252 -0.054514 0.948434 + outer loop + vertex 1.58852 1.3845 2.55462 + vertex 1.59274 1.38846 2.55346 + vertex 1.58893 1.38968 2.55478 + endloop + endfacet + facet normal 0.304936 -0.0567324 0.950681 + outer loop + vertex 1.58142 1.3871 2.55713 + vertex 1.5812 1.38221 2.55691 + vertex 1.58503 1.38598 2.5559 + endloop + endfacet + facet normal 0.238509 -0.0579875 0.969408 + outer loop + vertex 1.58111 1.37769 2.55666 + vertex 1.5812 1.38221 2.55691 + vertex 1.57722 1.37788 2.55762 + endloop + endfacet + facet normal 0.322483 -0.0572822 0.94484 + outer loop + vertex 1.58768 1.37873 2.55456 + vertex 1.58852 1.3845 2.55462 + vertex 1.5846 1.38109 2.55575 + endloop + endfacet + facet normal 0.32101 -0.0590231 0.945235 + outer loop + vertex 1.58768 1.37873 2.55456 + vertex 1.58439 1.374 2.55538 + vertex 1.58808 1.37355 2.5541 + endloop + endfacet + facet normal 0.297659 -0.055536 0.953056 + outer loop + vertex 1.58389 1.37721 2.55576 + vertex 1.58111 1.37769 2.55666 + vertex 1.58163 1.3745 2.55631 + endloop + endfacet + facet normal 0.23903 -0.0667337 0.968716 + outer loop + vertex 1.58163 1.3745 2.55631 + vertex 1.58111 1.37769 2.55666 + vertex 1.57765 1.37277 2.55717 + endloop + endfacet + facet normal 0.141094 -0.0582521 0.988281 + outer loop + vertex 1.57674 1.36712 2.55697 + vertex 1.57765 1.37277 2.55717 + vertex 1.57254 1.36788 2.55761 + endloop + endfacet + facet normal 0.137976 -0.0749197 0.987598 + outer loop + vertex 1.57226 1.36279 2.55727 + vertex 1.57674 1.36712 2.55697 + vertex 1.57254 1.36788 2.55761 + endloop + endfacet + facet normal 0.125279 -0.0615864 0.990208 + outer loop + vertex 1.57628 1.36216 2.55672 + vertex 1.57674 1.36712 2.55697 + vertex 1.57226 1.36279 2.55727 + endloop + endfacet + facet normal 0.123819 -0.0704489 0.989801 + outer loop + vertex 1.57225 1.35785 2.55692 + vertex 1.57628 1.36216 2.55672 + vertex 1.57226 1.36279 2.55727 + endloop + endfacet + facet normal 0.2965 -0.0638998 0.952893 + outer loop + vertex 1.58424 1.36949 2.55512 + vertex 1.58439 1.374 2.55538 + vertex 1.58087 1.37066 2.55625 + endloop + endfacet + facet normal 0.316386 -0.0695766 0.946076 + outer loop + vertex 1.58377 1.36448 2.55491 + vertex 1.58806 1.36855 2.55378 + vertex 1.58424 1.36949 2.55512 + endloop + endfacet + facet normal 0.220818 -0.0695956 0.972829 + outer loop + vertex 1.57674 1.36712 2.55697 + vertex 1.57628 1.36216 2.55672 + vertex 1.5803 1.36587 2.55607 + endloop + endfacet + facet normal 0.111282 -0.0586069 0.992059 + outer loop + vertex 1.57608 1.35764 2.55647 + vertex 1.57628 1.36216 2.55672 + vertex 1.57225 1.35785 2.55692 + endloop + endfacet + facet normal 0.111261 -0.0589395 0.992042 + outer loop + vertex 1.57608 1.35764 2.55647 + vertex 1.57225 1.35785 2.55692 + vertex 1.57299 1.35281 2.55653 + endloop + endfacet + facet normal 0.289045 -0.0706631 0.954704 + outer loop + vertex 1.58272 1.35872 2.55481 + vertex 1.58377 1.36448 2.55491 + vertex 1.57966 1.36104 2.5559 + endloop + endfacet + facet normal 0.292577 -0.0732234 0.953434 + outer loop + vertex 1.58272 1.35872 2.55481 + vertex 1.57925 1.35389 2.5555 + vertex 1.58299 1.35344 2.55432 + endloop + endfacet + facet normal 0.206689 -0.0523075 0.977007 + outer loop + vertex 1.5788 1.35715 2.55587 + vertex 1.57608 1.35764 2.55647 + vertex 1.57654 1.35443 2.55621 + endloop + endfacet + facet normal 0.121574 -0.0655577 0.990415 + outer loop + vertex 1.57654 1.35443 2.55621 + vertex 1.57608 1.35764 2.55647 + vertex 1.57299 1.35281 2.55653 + endloop + endfacet + facet normal 0.232543 -0.0695728 0.970094 + outer loop + vertex 1.57914 1.34933 2.5552 + vertex 1.57925 1.35389 2.5555 + vertex 1.576 1.35069 2.55605 + endloop + endfacet + facet normal 0.120066 -0.0751655 0.989916 + outer loop + vertex 1.57313 1.34815 2.55629 + vertex 1.5721 1.34377 2.55608 + vertex 1.57563 1.34612 2.55583 + endloop + endfacet + facet normal 0.253439 -0.103951 0.96175 + outer loop + vertex 1.57752 1.33869 2.55465 + vertex 1.57878 1.34435 2.55493 + vertex 1.57511 1.3416 2.5556 + endloop + endfacet + facet normal 0.0761124 -0.153327 0.98524 + outer loop + vertex 1.57383 1.33809 2.55542 + vertex 1.5726 1.34003 2.55582 + vertex 1.57135 1.33754 2.55552 + endloop + endfacet +endsolid diff --git a/noether_examples/meshes/outputsBackDoor/output_9.stl b/noether_examples/meshes/outputsBackDoor/output_9.stl new file mode 100644 index 00000000..2621572b --- /dev/null +++ b/noether_examples/meshes/outputsBackDoor/output_9.stl @@ -0,0 +1,253724 @@ +solid ascii + facet normal 0.933748 -0.0473794 -0.354781 + outer loop + vertex 0.785 1.47485 2.535 + vertex 0.784445 1.47616 2.53336 + vertex 0.785 1.475 2.53498 + endloop + endfacet + facet normal -0.960492 -0.0714163 0.268987 + outer loop + vertex 0.785 1.47485 2.535 + vertex 0.785 1.475 2.53504 + vertex 0.784445 1.47616 2.53336 + endloop + endfacet + facet normal 0.928102 -0.0186005 -0.37186 + outer loop + vertex 0.785 1.475 2.53498 + vertex 0.784386 1.47901 2.53325 + vertex 0.785 1.48 2.53473 + endloop + endfacet + facet normal 0.947082 0.00632442 -0.320928 + outer loop + vertex 0.784445 1.47616 2.53336 + vertex 0.784386 1.47901 2.53325 + vertex 0.785 1.475 2.53498 + endloop + endfacet + facet normal -0.965497 -0.00919446 0.260251 + outer loop + vertex 0.784445 1.47616 2.53336 + vertex 0.785 1.48 2.53556 + vertex 0.784386 1.47901 2.53325 + endloop + endfacet + facet normal -0.95493 -0.0307045 0.29524 + outer loop + vertex 0.785 1.475 2.53504 + vertex 0.785 1.48 2.53556 + vertex 0.784445 1.47616 2.53336 + endloop + endfacet + facet normal 0.923202 -0.00921511 -0.384204 + outer loop + vertex 0.785 1.48 2.53473 + vertex 0.784453 1.48234 2.53336 + vertex 0.785 1.485 2.53461 + endloop + endfacet + facet normal 0.925279 -0.0058248 -0.379241 + outer loop + vertex 0.784386 1.47901 2.53325 + vertex 0.784453 1.48234 2.53336 + vertex 0.785 1.48 2.53473 + endloop + endfacet + facet normal -0.983612 0.0136843 0.179779 + outer loop + vertex 0.784386 1.47901 2.53325 + vertex 0.785 1.485 2.53615 + vertex 0.784453 1.48234 2.53336 + endloop + endfacet + facet normal -0.962572 -0.0317654 0.269159 + outer loop + vertex 0.785 1.48 2.53556 + vertex 0.785 1.485 2.53615 + vertex 0.784386 1.47901 2.53325 + endloop + endfacet + facet normal 0.836286 0.0829035 -0.541989 + outer loop + vertex 0.785 1.485 2.53461 + vertex 0.784453 1.48234 2.53336 + vertex 0.785 1.48755 2.535 + endloop + endfacet + facet normal -0.988875 0.0611459 0.135597 + outer loop + vertex 0.785 1.48755 2.535 + vertex 0.784453 1.48234 2.53336 + vertex 0.785 1.485 2.53615 + endloop + endfacet + facet normal 0.924422 -0.0118543 -0.381186 + outer loop + vertex 0.785 1.51178 2.535 + vertex 0.784445 1.51548 2.53354 + vertex 0.785 1.515 2.5349 + endloop + endfacet + facet normal -0.969691 -0.0511945 0.238911 + outer loop + vertex 0.785 1.51178 2.535 + vertex 0.785 1.515 2.53569 + vertex 0.784445 1.51548 2.53354 + endloop + endfacet + facet normal 0.927062 0.000750831 -0.374906 + outer loop + vertex 0.785 1.515 2.5349 + vertex 0.784386 1.51886 2.53339 + vertex 0.785 1.52 2.53491 + endloop + endfacet + facet normal 0.925873 -0.000584669 -0.377835 + outer loop + vertex 0.784445 1.51548 2.53354 + vertex 0.784386 1.51886 2.53339 + vertex 0.785 1.515 2.5349 + endloop + endfacet + facet normal -0.964667 -0.00513598 0.263423 + outer loop + vertex 0.784445 1.51548 2.53354 + vertex 0.785 1.52 2.53566 + vertex 0.784386 1.51886 2.53339 + endloop + endfacet + facet normal -0.968196 0.00150317 0.250188 + outer loop + vertex 0.785 1.515 2.53569 + vertex 0.785 1.52 2.53566 + vertex 0.784445 1.51548 2.53354 + endloop + endfacet + facet normal 0.924815 -0.0114048 -0.380247 + outer loop + vertex 0.785 1.52 2.53491 + vertex 0.784453 1.52257 2.5335 + vertex 0.785 1.525 2.53476 + endloop + endfacet + facet normal 0.928659 -0.00545591 -0.370895 + outer loop + vertex 0.784386 1.51886 2.53339 + vertex 0.784453 1.52257 2.5335 + vertex 0.785 1.52 2.53491 + endloop + endfacet + facet normal -0.984726 0.0124671 0.173666 + outer loop + vertex 0.784386 1.51886 2.53339 + vertex 0.785 1.525 2.53643 + vertex 0.784453 1.52257 2.5335 + endloop + endfacet + facet normal -0.958741 -0.0432612 0.28097 + outer loop + vertex 0.785 1.52 2.53566 + vertex 0.785 1.525 2.53643 + vertex 0.784386 1.51886 2.53339 + endloop + endfacet + facet normal 0.896658 0.0267922 -0.441912 + outer loop + vertex 0.785 1.525 2.53476 + vertex 0.784453 1.52257 2.5335 + vertex 0.785 1.52896 2.535 + endloop + endfacet + facet normal -0.988523 0.0513032 0.142091 + outer loop + vertex 0.785 1.52896 2.535 + vertex 0.784453 1.52257 2.5335 + vertex 0.785 1.525 2.53643 + endloop + endfacet + facet normal 0.92969 -0.0635869 -0.362813 + outer loop + vertex 0.785 1.5446 2.535 + vertex 0.784445 1.54536 2.53344 + vertex 0.785 1.545 2.53493 + endloop + endfacet + facet normal -0.951201 -0.172605 0.255781 + outer loop + vertex 0.785 1.5446 2.535 + vertex 0.785 1.545 2.53527 + vertex 0.784445 1.54536 2.53344 + endloop + endfacet + facet normal 0.926924 -0.00899771 -0.37514 + outer loop + vertex 0.785 1.545 2.53493 + vertex 0.78438 1.54869 2.53331 + vertex 0.785 1.55 2.53481 + endloop + endfacet + facet normal 0.936983 0.00403171 -0.349351 + outer loop + vertex 0.784445 1.54536 2.53344 + vertex 0.78438 1.54869 2.53331 + vertex 0.785 1.545 2.53493 + endloop + endfacet + facet normal -0.96196 -0.00758948 0.273083 + outer loop + vertex 0.784445 1.54536 2.53344 + vertex 0.785 1.55 2.53553 + vertex 0.78438 1.54869 2.53331 + endloop + endfacet + facet normal -0.957401 -0.015002 0.288373 + outer loop + vertex 0.785 1.545 2.53527 + vertex 0.785 1.55 2.53553 + vertex 0.784445 1.54536 2.53344 + endloop + endfacet + facet normal 0.893909 -0.0410785 -0.446361 + outer loop + vertex 0.785 1.55 2.53481 + vertex 0.784375 1.55377 2.53321 + vertex 0.785 1.555 2.53435 + endloop + endfacet + facet normal 0.926145 -0.00637772 -0.377114 + outer loop + vertex 0.78438 1.54869 2.53331 + vertex 0.784375 1.55377 2.53321 + vertex 0.785 1.55 2.53481 + endloop + endfacet + facet normal -0.980839 0.00281145 0.1948 + outer loop + vertex 0.78438 1.54869 2.53331 + vertex 0.785 1.555 2.53634 + vertex 0.784375 1.55377 2.53321 + endloop + endfacet + facet normal -0.954381 -0.0477439 0.294749 + outer loop + vertex 0.785 1.55 2.53553 + vertex 0.785 1.555 2.53634 + vertex 0.78438 1.54869 2.53331 + endloop + endfacet + facet normal 0.922294 0.0146775 -0.38621 + outer loop + vertex 0.785 1.555 2.53435 + vertex 0.784387 1.55888 2.53303 + vertex 0.785 1.56 2.53454 + endloop + endfacet + facet normal 0.884659 -0.0183328 -0.465878 + outer loop + vertex 0.784375 1.55377 2.53321 + vertex 0.784387 1.55888 2.53303 + vertex 0.785 1.555 2.53435 + endloop + endfacet + facet normal -0.97693 0.00968955 0.213339 + outer loop + vertex 0.784375 1.55377 2.53321 + vertex 0.785 1.56 2.53579 + vertex 0.784387 1.55888 2.53303 + endloop + endfacet + facet normal -0.981953 0.0206805 0.187993 + outer loop + vertex 0.785 1.555 2.53634 + vertex 0.785 1.56 2.53579 + vertex 0.784375 1.55377 2.53321 + endloop + endfacet + facet normal 0.942833 0.0239334 -0.332405 + outer loop + vertex 0.785 1.56 2.53454 + vertex 0.784445 1.56246 2.53314 + vertex 0.785 1.565 2.5349 + endloop + endfacet + facet normal 0.927176 -0.00356641 -0.37461 + outer loop + vertex 0.784387 1.55888 2.53303 + vertex 0.784445 1.56246 2.53314 + vertex 0.785 1.56 2.53454 + endloop + endfacet + facet normal -0.966317 0.0078311 0.257237 + outer loop + vertex 0.784387 1.55888 2.53303 + vertex 0.785 1.565 2.53515 + vertex 0.784445 1.56246 2.53314 + endloop + endfacet + facet normal -0.978034 0.0264608 0.206757 + outer loop + vertex 0.785 1.56 2.53579 + vertex 0.785 1.565 2.53515 + vertex 0.784387 1.55888 2.53303 + endloop + endfacet + facet normal 0.906118 0.088163 -0.413736 + outer loop + vertex 0.785 1.565 2.5349 + vertex 0.784445 1.56246 2.53314 + vertex 0.785 1.56547 2.535 + endloop + endfacet + facet normal -0.979304 0.0615331 0.192817 + outer loop + vertex 0.785 1.56547 2.535 + vertex 0.784445 1.56246 2.53314 + vertex 0.785 1.565 2.53515 + endloop + endfacet + facet normal 0.917468 -0.113588 -0.381248 + outer loop + vertex 0.79 1.36359 2.535 + vertex 0.789481 1.3649 2.53336 + vertex 0.79 1.365 2.53458 + endloop + endfacet + facet normal 0.970392 0.130279 -0.203386 + outer loop + vertex 0.79 1.36359 2.535 + vertex 0.789884 1.36277 2.53392 + vertex 0.789481 1.3649 2.53336 + endloop + endfacet + facet normal 0.819079 0.0114596 -0.573566 + outer loop + vertex 0.79 1.365 2.53458 + vertex 0.789388 1.36894 2.53378 + vertex 0.79 1.37 2.53468 + endloop + endfacet + facet normal 0.916337 0.0624582 -0.395506 + outer loop + vertex 0.789481 1.3649 2.53336 + vertex 0.789388 1.36894 2.53378 + vertex 0.79 1.365 2.53458 + endloop + endfacet + facet normal -0.967896 -0.0480584 0.246714 + outer loop + vertex 0.789481 1.3649 2.53336 + vertex 0.78973 1.3667 2.53469 + vertex 0.789388 1.36894 2.53378 + endloop + endfacet + facet normal -0.94568 -0.09777 0.310049 + outer loop + vertex 0.789884 1.36277 2.53392 + vertex 0.78973 1.3667 2.53469 + vertex 0.789481 1.3649 2.53336 + endloop + endfacet + facet normal -0.238207 -0.0966326 -0.966395 + outer loop + vertex 0.79 1.37 2.53468 + vertex 0.789388 1.37405 2.53443 + vertex 0.79 1.375 2.53418 + endloop + endfacet + facet normal 0.77741 0.0783813 -0.624092 + outer loop + vertex 0.789388 1.36894 2.53378 + vertex 0.789388 1.37405 2.53443 + vertex 0.79 1.37 2.53468 + endloop + endfacet + facet normal -0.977134 -0.0264958 0.210966 + outer loop + vertex 0.789388 1.36894 2.53378 + vertex 0.79 1.375 2.53738 + vertex 0.789388 1.37405 2.53443 + endloop + endfacet + facet normal -0.968026 -0.0483039 0.246156 + outer loop + vertex 0.78973 1.3667 2.53469 + vertex 0.79 1.375 2.53738 + vertex 0.789388 1.36894 2.53378 + endloop + endfacet + facet normal -0.476617 -0.0175607 -0.878936 + outer loop + vertex 0.79 1.375 2.53418 + vertex 0.78927 1.37874 2.5345 + vertex 0.79 1.38 2.53408 + endloop + endfacet + facet normal -0.380045 0.00524086 -0.924953 + outer loop + vertex 0.789388 1.37405 2.53443 + vertex 0.78927 1.37874 2.5345 + vertex 0.79 1.375 2.53418 + endloop + endfacet + facet normal -0.984896 -0.0275206 0.170949 + outer loop + vertex 0.789388 1.37405 2.53443 + vertex 0.79 1.38 2.53891 + vertex 0.78927 1.37874 2.5345 + endloop + endfacet + facet normal -0.97231 -0.0683776 0.223466 + outer loop + vertex 0.79 1.375 2.53738 + vertex 0.79 1.38 2.53891 + vertex 0.789388 1.37405 2.53443 + endloop + endfacet + facet normal 0.649865 -0.0545841 -0.758087 + outer loop + vertex 0.79 1.38 2.53408 + vertex 0.789095 1.38245 2.53313 + vertex 0.79 1.385 2.53372 + endloop + endfacet + facet normal 0.0535343 -0.344266 -0.937345 + outer loop + vertex 0.78927 1.37874 2.5345 + vertex 0.789095 1.38245 2.53313 + vertex 0.79 1.38 2.53408 + endloop + endfacet + facet normal -0.97545 -0.107454 0.192227 + outer loop + vertex 0.79 1.38195 2.54 + vertex 0.78927 1.37874 2.5345 + vertex 0.79 1.38 2.53891 + endloop + endfacet + facet normal -0.978497 -0.0929162 0.184146 + outer loop + vertex 0.79 1.38195 2.54 + vertex 0.788959 1.38357 2.53529 + vertex 0.78927 1.37874 2.5345 + endloop + endfacet + facet normal -0.997748 -0.0589142 -0.0320753 + outer loop + vertex 0.788959 1.38357 2.53529 + vertex 0.789095 1.38245 2.53313 + vertex 0.78927 1.37874 2.5345 + endloop + endfacet + facet normal 0.966143 -0.0862643 -0.243159 + outer loop + vertex 0.79 1.38195 2.54 + vertex 0.789544 1.38201 2.53816 + vertex 0.788959 1.38357 2.53529 + endloop + endfacet + facet normal 0.300279 -0.0152804 -0.953729 + outer loop + vertex 0.79 1.385 2.53372 + vertex 0.788897 1.38729 2.53334 + vertex 0.79 1.39 2.53364 + endloop + endfacet + facet normal 0.430731 0.0564474 -0.900714 + outer loop + vertex 0.789095 1.38245 2.53313 + vertex 0.788897 1.38729 2.53334 + vertex 0.79 1.385 2.53372 + endloop + endfacet + facet normal -0.998338 -0.0389538 -0.0424636 + outer loop + vertex 0.789095 1.38245 2.53313 + vertex 0.788959 1.38357 2.53529 + vertex 0.788897 1.38729 2.53334 + endloop + endfacet + facet normal -0.996281 -0.0525039 -0.0683137 + outer loop + vertex 0.788897 1.38729 2.53334 + vertex 0.788959 1.38357 2.53529 + vertex 0.788625 1.38967 2.53548 + endloop + endfacet + facet normal -0.986027 -0.0589132 0.155823 + outer loop + vertex 0.788959 1.38357 2.53529 + vertex 0.789284 1.38591 2.53823 + vertex 0.788625 1.38967 2.53548 + endloop + endfacet + facet normal -0.984255 -0.068254 0.163045 + outer loop + vertex 0.789544 1.38201 2.53816 + vertex 0.789284 1.38591 2.53823 + vertex 0.788959 1.38357 2.53529 + endloop + endfacet + facet normal -0.708113 -0.00279455 -0.706094 + outer loop + vertex 0.79 1.39 2.53364 + vertex 0.788624 1.395 2.535 + vertex 0.79 1.395 2.53362 + endloop + endfacet + facet normal -0.22387 0.197992 -0.954296 + outer loop + vertex 0.788897 1.38729 2.53334 + vertex 0.788624 1.395 2.535 + vertex 0.79 1.39 2.53364 + endloop + endfacet + facet normal -0.993337 -0.0104468 -0.114772 + outer loop + vertex 0.788897 1.38729 2.53334 + vertex 0.788625 1.38967 2.53548 + vertex 0.788624 1.395 2.535 + endloop + endfacet + facet normal -0.964104 -0.0238924 -0.264447 + outer loop + vertex 0.788624 1.395 2.535 + vertex 0.788625 1.38967 2.53548 + vertex 0.788371 1.39513 2.53591 + endloop + endfacet + facet normal -0.98648 -0.0580792 0.153246 + outer loop + vertex 0.788625 1.38967 2.53548 + vertex 0.789043 1.39111 2.53872 + vertex 0.788371 1.39513 2.53591 + endloop + endfacet + facet normal -0.986215 -0.0601739 0.154139 + outer loop + vertex 0.789284 1.38591 2.53823 + vertex 0.789043 1.39111 2.53872 + vertex 0.788625 1.38967 2.53548 + endloop + endfacet + facet normal -0.964153 -0.0281479 -0.263848 + outer loop + vertex 0.788624 1.395 2.535 + vertex 0.788371 1.39513 2.53591 + vertex 0.788478 1.4 2.535 + endloop + endfacet + facet normal -0.985162 -0.0103622 -0.171314 + outer loop + vertex 0.788478 1.4 2.535 + vertex 0.788371 1.39513 2.53591 + vertex 0.788262 1.39996 2.53624 + endloop + endfacet + facet normal -0.98962 -0.0318369 0.140141 + outer loop + vertex 0.788371 1.39513 2.53591 + vertex 0.788796 1.39592 2.53909 + vertex 0.788262 1.39996 2.53624 + endloop + endfacet + facet normal -0.987118 -0.06228 0.147376 + outer loop + vertex 0.789043 1.39111 2.53872 + vertex 0.788796 1.39592 2.53909 + vertex 0.788371 1.39513 2.53591 + endloop + endfacet + facet normal -0.974711 0.151471 -0.1643 + outer loop + vertex 0.788478 1.4 2.535 + vertex 0.788262 1.39996 2.53624 + vertex 0.789255 1.405 2.535 + endloop + endfacet + facet normal -0.840129 0.0319572 -0.541444 + outer loop + vertex 0.789255 1.405 2.535 + vertex 0.788262 1.39996 2.53624 + vertex 0.788158 1.4053 2.53672 + endloop + endfacet + facet normal -0.993756 -0.0290937 0.107712 + outer loop + vertex 0.788262 1.39996 2.53624 + vertex 0.788607 1.40065 2.53961 + vertex 0.788158 1.4053 2.53672 + endloop + endfacet + facet normal -0.992326 -0.0518823 0.112233 + outer loop + vertex 0.788796 1.39592 2.53909 + vertex 0.788607 1.40065 2.53961 + vertex 0.788262 1.39996 2.53624 + endloop + endfacet + facet normal -0.845811 -0.0451712 -0.531568 + outer loop + vertex 0.789255 1.405 2.535 + vertex 0.788158 1.4053 2.53672 + vertex 0.788988 1.41 2.535 + endloop + endfacet + facet normal -0.602579 -0.178334 -0.777879 + outer loop + vertex 0.788988 1.41 2.535 + vertex 0.788158 1.4053 2.53672 + vertex 0.78802 1.41031 2.53568 + endloop + endfacet + facet normal -0.995924 -0.0493302 0.0755172 + outer loop + vertex 0.788455 1.40469 2.54024 + vertex 0.788158 1.4053 2.53672 + vertex 0.788607 1.40065 2.53961 + endloop + endfacet + facet normal -0.99579 -0.0528559 0.0748908 + outer loop + vertex 0.788455 1.40469 2.54024 + vertex 0.788121 1.40934 2.53908 + vertex 0.788158 1.4053 2.53672 + endloop + endfacet + facet normal -0.999476 -0.0226808 0.0230999 + outer loop + vertex 0.788121 1.40934 2.53908 + vertex 0.78802 1.41031 2.53568 + vertex 0.788158 1.4053 2.53672 + endloop + endfacet + facet normal -0.978154 -0.0184358 0.207063 + outer loop + vertex 0.788455 1.40469 2.54024 + vertex 0.788899 1.40672 2.54252 + vertex 0.788121 1.40934 2.53908 + endloop + endfacet + facet normal -0.585268 -0.0575877 -0.808792 + outer loop + vertex 0.788988 1.41 2.535 + vertex 0.78802 1.41031 2.53568 + vertex 0.788496 1.415 2.535 + endloop + endfacet + facet normal -0.955529 0.0551349 -0.289696 + outer loop + vertex 0.788496 1.415 2.535 + vertex 0.78802 1.41031 2.53568 + vertex 0.78805 1.41415 2.53631 + endloop + endfacet + facet normal -0.999534 0.00276208 0.030394 + outer loop + vertex 0.78802 1.41031 2.53568 + vertex 0.788121 1.40934 2.53908 + vertex 0.78805 1.41415 2.53631 + endloop + endfacet + facet normal -0.999637 0.00076168 0.0269185 + outer loop + vertex 0.78805 1.41415 2.53631 + vertex 0.788121 1.40934 2.53908 + vertex 0.788145 1.41448 2.53985 + endloop + endfacet + facet normal -0.980107 -0.0250262 0.196885 + outer loop + vertex 0.788121 1.40934 2.53908 + vertex 0.788902 1.41092 2.54317 + vertex 0.788145 1.41448 2.53985 + endloop + endfacet + facet normal -0.979609 -0.0299129 0.198675 + outer loop + vertex 0.788899 1.40672 2.54252 + vertex 0.788902 1.41092 2.54317 + vertex 0.788121 1.40934 2.53908 + endloop + endfacet + facet normal -0.960008 0.101945 -0.260753 + outer loop + vertex 0.788496 1.415 2.535 + vertex 0.78805 1.41415 2.53631 + vertex 0.789027 1.42 2.535 + endloop + endfacet + facet normal -0.937387 0.080697 -0.338813 + outer loop + vertex 0.789027 1.42 2.535 + vertex 0.78805 1.41415 2.53631 + vertex 0.788112 1.41782 2.53701 + endloop + endfacet + facet normal -0.999595 0.0118929 0.0258665 + outer loop + vertex 0.78805 1.41415 2.53631 + vertex 0.788145 1.41448 2.53985 + vertex 0.788112 1.41782 2.53701 + endloop + endfacet + facet normal -0.999669 0.0100435 0.023692 + outer loop + vertex 0.788112 1.41782 2.53701 + vertex 0.788145 1.41448 2.53985 + vertex 0.788199 1.41925 2.54012 + endloop + endfacet + facet normal -0.98286 0.000943201 0.184353 + outer loop + vertex 0.788145 1.41448 2.53985 + vertex 0.788871 1.4159 2.54371 + vertex 0.788199 1.41925 2.54012 + endloop + endfacet + facet normal -0.980546 -0.0274725 0.194355 + outer loop + vertex 0.788902 1.41092 2.54317 + vertex 0.788871 1.4159 2.54371 + vertex 0.788145 1.41448 2.53985 + endloop + endfacet + facet normal -0.827507 0.176488 -0.532995 + outer loop + vertex 0.79 1.42491 2.535 + vertex 0.788499 1.42265 2.53658 + vertex 0.79 1.425 2.53503 + endloop + endfacet + facet normal -0.821341 0.162771 -0.546722 + outer loop + vertex 0.79 1.42491 2.535 + vertex 0.789027 1.42 2.535 + vertex 0.788499 1.42265 2.53658 + endloop + endfacet + facet normal -0.925416 0.0405712 -0.376775 + outer loop + vertex 0.789027 1.42 2.535 + vertex 0.788112 1.41782 2.53701 + vertex 0.788499 1.42265 2.53658 + endloop + endfacet + facet normal -0.996827 0.0791837 -0.00810896 + outer loop + vertex 0.788112 1.41782 2.53701 + vertex 0.788199 1.41925 2.54012 + vertex 0.788499 1.42265 2.53658 + endloop + endfacet + facet normal -0.9969 0.00621125 -0.0784294 + outer loop + vertex 0.788499 1.42265 2.53658 + vertex 0.788199 1.41925 2.54012 + vertex 0.788189 1.42455 2.54067 + endloop + endfacet + facet normal -0.986172 -0.0189243 0.164642 + outer loop + vertex 0.788199 1.41925 2.54012 + vertex 0.788827 1.42084 2.54406 + vertex 0.788189 1.42455 2.54067 + endloop + endfacet + facet normal -0.986054 -0.0203004 0.16518 + outer loop + vertex 0.788871 1.4159 2.54371 + vertex 0.788827 1.42084 2.54406 + vertex 0.788199 1.41925 2.54012 + endloop + endfacet + facet normal -0.890106 0.111372 -0.441936 + outer loop + vertex 0.79 1.425 2.53503 + vertex 0.788158 1.43 2.54 + vertex 0.79 1.43 2.53629 + endloop + endfacet + facet normal -0.837252 0.198153 -0.509651 + outer loop + vertex 0.788499 1.42265 2.53658 + vertex 0.788158 1.43 2.54 + vertex 0.79 1.425 2.53503 + endloop + endfacet + facet normal -0.997515 -0.0141623 -0.0690185 + outer loop + vertex 0.788499 1.42265 2.53658 + vertex 0.788189 1.42455 2.54067 + vertex 0.788158 1.43 2.54 + endloop + endfacet + facet normal -0.996019 -0.0164241 -0.0876121 + outer loop + vertex 0.788158 1.43 2.54 + vertex 0.788189 1.42455 2.54067 + vertex 0.788014 1.43015 2.54161 + endloop + endfacet + facet normal -0.985223 -0.0581462 0.161107 + outer loop + vertex 0.788189 1.42455 2.54067 + vertex 0.788756 1.42569 2.54454 + vertex 0.788014 1.43015 2.54161 + endloop + endfacet + facet normal -0.98776 -0.0297567 0.153116 + outer loop + vertex 0.788827 1.42084 2.54406 + vertex 0.788756 1.42569 2.54454 + vertex 0.788189 1.42455 2.54067 + endloop + endfacet + facet normal -0.995942 -0.023104 -0.0869814 + outer loop + vertex 0.788158 1.43 2.54 + vertex 0.788014 1.43015 2.54161 + vertex 0.788042 1.435 2.54 + endloop + endfacet + facet normal -0.866896 -0.152805 -0.474492 + outer loop + vertex 0.788042 1.435 2.54 + vertex 0.788014 1.43015 2.54161 + vertex 0.787643 1.43496 2.54074 + endloop + endfacet + facet normal -0.983028 -0.0471479 0.177295 + outer loop + vertex 0.788685 1.42959 2.54519 + vertex 0.788014 1.43015 2.54161 + vertex 0.788756 1.42569 2.54454 + endloop + endfacet + facet normal -0.982656 -0.0614096 0.174972 + outer loop + vertex 0.788685 1.42959 2.54519 + vertex 0.788207 1.43399 2.54405 + vertex 0.788014 1.43015 2.54161 + endloop + endfacet + facet normal -0.98689 -0.0479526 0.154106 + outer loop + vertex 0.788207 1.43399 2.54405 + vertex 0.787643 1.43496 2.54074 + vertex 0.788014 1.43015 2.54161 + endloop + endfacet + facet normal -0.957248 -0.0294321 0.287767 + outer loop + vertex 0.788685 1.42959 2.54519 + vertex 0.789282 1.43158 2.54738 + vertex 0.788207 1.43399 2.54405 + endloop + endfacet + facet normal -0.879328 -0.0341195 -0.474992 + outer loop + vertex 0.788042 1.435 2.54 + vertex 0.787643 1.43496 2.54074 + vertex 0.787848 1.44 2.54 + endloop + endfacet + facet normal -0.98183 0.0120163 -0.18938 + outer loop + vertex 0.787848 1.44 2.54 + vertex 0.787643 1.43496 2.54074 + vertex 0.787576 1.4389 2.54134 + endloop + endfacet + facet normal -0.986881 -0.0408982 0.156184 + outer loop + vertex 0.787643 1.43496 2.54074 + vertex 0.788207 1.43399 2.54405 + vertex 0.787576 1.4389 2.54134 + endloop + endfacet + facet normal -0.981953 -0.0228959 0.187735 + outer loop + vertex 0.787576 1.4389 2.54134 + vertex 0.788207 1.43399 2.54405 + vertex 0.788205 1.43934 2.54469 + endloop + endfacet + facet normal -0.954529 -0.0358303 0.295958 + outer loop + vertex 0.788207 1.43399 2.54405 + vertex 0.789346 1.4357 2.54793 + vertex 0.788205 1.43934 2.54469 + endloop + endfacet + facet normal -0.956323 -0.0240997 0.291316 + outer loop + vertex 0.789282 1.43158 2.54738 + vertex 0.789346 1.4357 2.54793 + vertex 0.788207 1.43399 2.54405 + endloop + endfacet + facet normal -0.979099 -0.00567248 -0.203306 + outer loop + vertex 0.787848 1.44 2.54 + vertex 0.787576 1.4389 2.54134 + vertex 0.787819 1.445 2.54 + endloop + endfacet + facet normal -0.98411 0.000195263 -0.177562 + outer loop + vertex 0.787819 1.445 2.54 + vertex 0.787576 1.4389 2.54134 + vertex 0.787533 1.44389 2.54159 + endloop + endfacet + facet normal -0.982186 -0.017614 0.187084 + outer loop + vertex 0.787576 1.4389 2.54134 + vertex 0.788205 1.43934 2.54469 + vertex 0.787533 1.44389 2.54159 + endloop + endfacet + facet normal -0.981694 -0.015673 0.18982 + outer loop + vertex 0.787533 1.44389 2.54159 + vertex 0.788205 1.43934 2.54469 + vertex 0.788167 1.44446 2.54492 + endloop + endfacet + facet normal -0.95313 -0.0204383 0.30187 + outer loop + vertex 0.788205 1.43934 2.54469 + vertex 0.78933 1.44076 2.54834 + vertex 0.788167 1.44446 2.54492 + endloop + endfacet + facet normal -0.952154 -0.0276229 0.304367 + outer loop + vertex 0.789346 1.4357 2.54793 + vertex 0.78933 1.44076 2.54834 + vertex 0.788205 1.43934 2.54469 + endloop + endfacet + facet normal -0.982202 -0.0141442 -0.187294 + outer loop + vertex 0.787819 1.445 2.54 + vertex 0.787533 1.44389 2.54159 + vertex 0.787747 1.45 2.54 + endloop + endfacet + facet normal -0.984591 -0.0107517 -0.174541 + outer loop + vertex 0.787747 1.45 2.54 + vertex 0.787533 1.44389 2.54159 + vertex 0.787471 1.44899 2.54162 + endloop + endfacet + facet normal -0.98182 -0.012964 0.189373 + outer loop + vertex 0.787533 1.44389 2.54159 + vertex 0.788167 1.44446 2.54492 + vertex 0.787471 1.44899 2.54162 + endloop + endfacet + facet normal -0.98295 -0.0177785 0.183011 + outer loop + vertex 0.787471 1.44899 2.54162 + vertex 0.788167 1.44446 2.54492 + vertex 0.788092 1.44952 2.54501 + endloop + endfacet + facet normal -0.955808 -0.0193397 0.293355 + outer loop + vertex 0.788167 1.44446 2.54492 + vertex 0.78925 1.44581 2.54853 + vertex 0.788092 1.44952 2.54501 + endloop + endfacet + facet normal -0.954885 -0.0266154 0.29578 + outer loop + vertex 0.78933 1.44076 2.54834 + vertex 0.78925 1.44581 2.54853 + vertex 0.788167 1.44446 2.54492 + endloop + endfacet + facet normal -0.982021 -0.0302499 -0.18633 + outer loop + vertex 0.787747 1.45 2.54 + vertex 0.787471 1.44899 2.54162 + vertex 0.787593 1.455 2.54 + endloop + endfacet + facet normal -0.987421 -0.0221314 -0.156556 + outer loop + vertex 0.787593 1.455 2.54 + vertex 0.787471 1.44899 2.54162 + vertex 0.787358 1.45403 2.54162 + endloop + endfacet + facet normal -0.982735 -0.0222511 0.183674 + outer loop + vertex 0.787471 1.44899 2.54162 + vertex 0.788092 1.44952 2.54501 + vertex 0.787358 1.45403 2.54162 + endloop + endfacet + facet normal -0.983492 -0.0258065 0.179101 + outer loop + vertex 0.787358 1.45403 2.54162 + vertex 0.788092 1.44952 2.54501 + vertex 0.787977 1.45449 2.54509 + endloop + endfacet + facet normal -0.95949 -0.0269103 0.280456 + outer loop + vertex 0.788092 1.44952 2.54501 + vertex 0.789128 1.45078 2.54867 + vertex 0.787977 1.45449 2.54509 + endloop + endfacet + facet normal -0.95896 -0.0312866 0.281811 + outer loop + vertex 0.78925 1.44581 2.54853 + vertex 0.789128 1.45078 2.54867 + vertex 0.788092 1.44952 2.54501 + endloop + endfacet + facet normal -0.982316 -0.0587497 -0.177772 + outer loop + vertex 0.787593 1.455 2.54 + vertex 0.787358 1.45403 2.54162 + vertex 0.787294 1.46 2.54 + endloop + endfacet + facet normal -0.998086 -0.025902 -0.0561518 + outer loop + vertex 0.787294 1.46 2.54 + vertex 0.787358 1.45403 2.54162 + vertex 0.787225 1.45902 2.54168 + endloop + endfacet + facet normal -0.983378 -0.0280783 0.179384 + outer loop + vertex 0.787358 1.45403 2.54162 + vertex 0.787977 1.45449 2.54509 + vertex 0.787225 1.45902 2.54168 + endloop + endfacet + facet normal -0.983566 -0.0290003 0.178202 + outer loop + vertex 0.787225 1.45902 2.54168 + vertex 0.787977 1.45449 2.54509 + vertex 0.787854 1.45944 2.54521 + endloop + endfacet + facet normal -0.961506 -0.0308494 0.273047 + outer loop + vertex 0.787977 1.45449 2.54509 + vertex 0.788994 1.45573 2.54881 + vertex 0.787854 1.45944 2.54521 + endloop + endfacet + facet normal -0.961162 -0.0337388 0.273915 + outer loop + vertex 0.789128 1.45078 2.54867 + vertex 0.788994 1.45573 2.54881 + vertex 0.787977 1.45449 2.54509 + endloop + endfacet + facet normal -0.998 -0.0273395 -0.0569927 + outer loop + vertex 0.787294 1.46 2.54 + vertex 0.787225 1.45902 2.54168 + vertex 0.787157 1.465 2.54 + endloop + endfacet + facet normal -0.997582 -0.0290555 -0.0631382 + outer loop + vertex 0.787157 1.465 2.54 + vertex 0.787225 1.45902 2.54168 + vertex 0.787078 1.46394 2.54173 + endloop + endfacet + facet normal -0.983441 -0.0314732 0.178477 + outer loop + vertex 0.787225 1.45902 2.54168 + vertex 0.787854 1.45944 2.54521 + vertex 0.787078 1.46394 2.54173 + endloop + endfacet + facet normal -0.982828 -0.0283919 0.182329 + outer loop + vertex 0.787078 1.46394 2.54173 + vertex 0.787854 1.45944 2.54521 + vertex 0.78773 1.46436 2.54531 + endloop + endfacet + facet normal -0.962264 -0.0297 0.270491 + outer loop + vertex 0.787854 1.45944 2.54521 + vertex 0.788862 1.46069 2.54894 + vertex 0.78773 1.46436 2.54531 + endloop + endfacet + facet normal -0.961923 -0.0326041 0.27137 + outer loop + vertex 0.788994 1.45573 2.54881 + vertex 0.788862 1.46069 2.54894 + vertex 0.787854 1.45944 2.54521 + endloop + endfacet + facet normal -0.996328 -0.0450382 -0.0728123 + outer loop + vertex 0.787157 1.465 2.54 + vertex 0.787078 1.46394 2.54173 + vertex 0.786931 1.47 2.54 + endloop + endfacet + facet normal -0.999601 -0.0268115 -0.00886658 + outer loop + vertex 0.786931 1.47 2.54 + vertex 0.787078 1.46394 2.54173 + vertex 0.786945 1.46889 2.54182 + endloop + endfacet + facet normal -0.982769 -0.0295793 0.182457 + outer loop + vertex 0.787078 1.46394 2.54173 + vertex 0.78773 1.46436 2.54531 + vertex 0.786945 1.46889 2.54182 + endloop + endfacet + facet normal -0.981429 -0.0231909 0.190417 + outer loop + vertex 0.786945 1.46889 2.54182 + vertex 0.78773 1.46436 2.54531 + vertex 0.787637 1.46929 2.54543 + endloop + endfacet + facet normal -0.962779 -0.024703 0.269159 + outer loop + vertex 0.78773 1.46436 2.54531 + vertex 0.788741 1.46563 2.54905 + vertex 0.787637 1.46929 2.54543 + endloop + endfacet + facet normal -0.962225 -0.0295334 0.270648 + outer loop + vertex 0.788862 1.46069 2.54894 + vertex 0.788741 1.46563 2.54905 + vertex 0.78773 1.46436 2.54531 + endloop + endfacet + facet normal -0.999492 -0.0299779 -0.0108092 + outer loop + vertex 0.786931 1.47 2.54 + vertex 0.786945 1.46889 2.54182 + vertex 0.786781 1.475 2.54 + endloop + endfacet + facet normal -0.999504 -0.0193896 0.024826 + outer loop + vertex 0.786781 1.475 2.54 + vertex 0.786945 1.46889 2.54182 + vertex 0.786851 1.47383 2.54191 + endloop + endfacet + facet normal -0.981473 -0.0221847 0.190313 + outer loop + vertex 0.786945 1.46889 2.54182 + vertex 0.787637 1.46929 2.54543 + vertex 0.786851 1.47383 2.54191 + endloop + endfacet + facet normal -0.980813 -0.0192108 0.194 + outer loop + vertex 0.786851 1.47383 2.54191 + vertex 0.787637 1.46929 2.54543 + vertex 0.787584 1.47426 2.54566 + endloop + endfacet + facet normal -0.962371 -0.022532 0.270802 + outer loop + vertex 0.787637 1.46929 2.54543 + vertex 0.788671 1.47058 2.54922 + vertex 0.787584 1.47426 2.54566 + endloop + endfacet + facet normal -0.962336 -0.0228501 0.270901 + outer loop + vertex 0.788741 1.46563 2.54905 + vertex 0.788671 1.47058 2.54922 + vertex 0.787637 1.46929 2.54543 + endloop + endfacet + facet normal -0.998738 0.0171802 0.0471993 + outer loop + vertex 0.786781 1.475 2.54 + vertex 0.786851 1.47383 2.54191 + vertex 0.786867 1.48 2.54 + endloop + endfacet + facet normal -0.99668 -0.0217321 -0.0784607 + outer loop + vertex 0.786867 1.48 2.54 + vertex 0.786851 1.47383 2.54191 + vertex 0.786732 1.47882 2.54204 + endloop + endfacet + facet normal -0.980392 -0.0284604 0.19499 + outer loop + vertex 0.786851 1.47383 2.54191 + vertex 0.787584 1.47426 2.54566 + vertex 0.786732 1.47882 2.54204 + endloop + endfacet + facet normal -0.978041 -0.0179809 0.207636 + outer loop + vertex 0.786732 1.47882 2.54204 + vertex 0.787584 1.47426 2.54566 + vertex 0.787591 1.4796 2.54615 + endloop + endfacet + facet normal -0.961447 -0.0241404 0.273928 + outer loop + vertex 0.787584 1.47426 2.54566 + vertex 0.788675 1.47549 2.5496 + vertex 0.787591 1.4796 2.54615 + endloop + endfacet + facet normal -0.961836 -0.0203852 0.272864 + outer loop + vertex 0.788671 1.47058 2.54922 + vertex 0.788675 1.47549 2.5496 + vertex 0.787584 1.47426 2.54566 + endloop + endfacet + facet normal -0.988023 -0.0960391 -0.120777 + outer loop + vertex 0.786867 1.48 2.54 + vertex 0.786732 1.47882 2.54204 + vertex 0.786381 1.485 2.54 + endloop + endfacet + facet normal -0.998283 -0.0439369 0.0387383 + outer loop + vertex 0.786381 1.485 2.54 + vertex 0.786732 1.47882 2.54204 + vertex 0.786512 1.48373 2.54193 + endloop + endfacet + facet normal -0.976626 -0.0391805 0.211345 + outer loop + vertex 0.786732 1.47882 2.54204 + vertex 0.787591 1.4796 2.54615 + vertex 0.786512 1.48373 2.54193 + endloop + endfacet + facet normal -0.975111 -0.0303083 0.219634 + outer loop + vertex 0.786512 1.48373 2.54193 + vertex 0.787591 1.4796 2.54615 + vertex 0.787151 1.48425 2.54484 + endloop + endfacet + facet normal -0.961515 -0.0243738 0.273671 + outer loop + vertex 0.788731 1.47949 2.55015 + vertex 0.787591 1.4796 2.54615 + vertex 0.788675 1.47549 2.5496 + endloop + endfacet + facet normal -0.961561 -0.0211832 0.273775 + outer loop + vertex 0.788731 1.47949 2.55015 + vertex 0.788279 1.48377 2.54889 + vertex 0.787591 1.4796 2.54615 + endloop + endfacet + facet normal -0.963713 -0.0160182 0.266461 + outer loop + vertex 0.788279 1.48377 2.54889 + vertex 0.787151 1.48425 2.54484 + vertex 0.787591 1.4796 2.54615 + endloop + endfacet + facet normal -0.941918 -0.000927706 0.335842 + outer loop + vertex 0.788731 1.47949 2.55015 + vertex 0.789461 1.48186 2.5522 + vertex 0.788279 1.48377 2.54889 + endloop + endfacet + facet normal -0.997293 -0.0704047 0.0212273 + outer loop + vertex 0.786381 1.485 2.54 + vertex 0.786512 1.48373 2.54193 + vertex 0.786028 1.49 2.54 + endloop + endfacet + facet normal -0.989853 -0.0338544 0.138003 + outer loop + vertex 0.786028 1.49 2.54 + vertex 0.786512 1.48373 2.54193 + vertex 0.78634 1.4884 2.54185 + endloop + endfacet + facet normal -0.975006 -0.031835 0.219887 + outer loop + vertex 0.786512 1.48373 2.54193 + vertex 0.787151 1.48425 2.54484 + vertex 0.78634 1.4884 2.54185 + endloop + endfacet + facet normal -0.968992 -0.0112253 0.246837 + outer loop + vertex 0.78634 1.4884 2.54185 + vertex 0.787151 1.48425 2.54484 + vertex 0.787273 1.48814 2.5455 + endloop + endfacet + facet normal -0.963692 -0.0147284 0.266609 + outer loop + vertex 0.787151 1.48425 2.54484 + vertex 0.788279 1.48377 2.54889 + vertex 0.787273 1.48814 2.5455 + endloop + endfacet + facet normal -0.959902 -0.00319726 0.280318 + outer loop + vertex 0.787273 1.48814 2.5455 + vertex 0.788279 1.48377 2.54889 + vertex 0.788418 1.48908 2.54943 + endloop + endfacet + facet normal -0.939581 -0.0099693 0.342182 + outer loop + vertex 0.788279 1.48377 2.54889 + vertex 0.789617 1.48607 2.55263 + vertex 0.788418 1.48908 2.54943 + endloop + endfacet + facet normal -0.941671 0.000424559 0.336534 + outer loop + vertex 0.789461 1.48186 2.5522 + vertex 0.789617 1.48607 2.55263 + vertex 0.788279 1.48377 2.54889 + endloop + endfacet + facet normal -0.9913 -0.0559191 0.119156 + outer loop + vertex 0.786028 1.49 2.54 + vertex 0.78634 1.4884 2.54185 + vertex 0.785746 1.495 2.54 + endloop + endfacet + facet normal -0.964636 -0.0131504 0.263259 + outer loop + vertex 0.785746 1.495 2.54 + vertex 0.78634 1.4884 2.54185 + vertex 0.786315 1.49313 2.54199 + endloop + endfacet + facet normal -0.969 -0.0126695 0.246735 + outer loop + vertex 0.78634 1.4884 2.54185 + vertex 0.787273 1.48814 2.5455 + vertex 0.786315 1.49313 2.54199 + endloop + endfacet + facet normal -0.965744 -0.00310296 0.259477 + outer loop + vertex 0.786315 1.49313 2.54199 + vertex 0.787273 1.48814 2.5455 + vertex 0.787322 1.49297 2.54574 + endloop + endfacet + facet normal -0.959833 -0.00421444 0.280541 + outer loop + vertex 0.787273 1.48814 2.5455 + vertex 0.788418 1.48908 2.54943 + vertex 0.787322 1.49297 2.54574 + endloop + endfacet + facet normal -0.95821 0.00147605 0.286062 + outer loop + vertex 0.787322 1.49297 2.54574 + vertex 0.788418 1.48908 2.54943 + vertex 0.788472 1.49412 2.54958 + endloop + endfacet + facet normal -0.937366 -0.000635014 0.348346 + outer loop + vertex 0.788418 1.48908 2.54943 + vertex 0.789712 1.49114 2.55292 + vertex 0.788472 1.49412 2.54958 + endloop + endfacet + facet normal -0.93714 -0.00179403 0.348949 + outer loop + vertex 0.789617 1.48607 2.55263 + vertex 0.789712 1.49114 2.55292 + vertex 0.788418 1.48908 2.54943 + endloop + endfacet + facet normal -0.952577 0.0323862 0.302569 + outer loop + vertex 0.785746 1.495 2.54 + vertex 0.786315 1.49313 2.54199 + vertex 0.785916 1.5 2.54 + endloop + endfacet + facet normal -0.981468 -0.00147229 0.191622 + outer loop + vertex 0.785916 1.5 2.54 + vertex 0.786315 1.49313 2.54199 + vertex 0.786316 1.49807 2.54203 + endloop + endfacet + facet normal -0.965736 -0.00202027 0.25952 + outer loop + vertex 0.786315 1.49313 2.54199 + vertex 0.787322 1.49297 2.54574 + vertex 0.786316 1.49807 2.54203 + endloop + endfacet + facet normal -0.964236 0.00228017 0.265034 + outer loop + vertex 0.786316 1.49807 2.54203 + vertex 0.787322 1.49297 2.54574 + vertex 0.787335 1.49795 2.54574 + endloop + endfacet + facet normal -0.958272 0.00225102 0.285849 + outer loop + vertex 0.787322 1.49297 2.54574 + vertex 0.788472 1.49412 2.54958 + vertex 0.787335 1.49795 2.54574 + endloop + endfacet + facet normal -0.957871 0.0036994 0.287175 + outer loop + vertex 0.787335 1.49795 2.54574 + vertex 0.788472 1.49412 2.54958 + vertex 0.788479 1.49915 2.54954 + endloop + endfacet + facet normal -0.937661 0.00415373 0.347525 + outer loop + vertex 0.788472 1.49412 2.54958 + vertex 0.789735 1.49617 2.55297 + vertex 0.788479 1.49915 2.54954 + endloop + endfacet + facet normal -0.936981 0.000680444 0.349379 + outer loop + vertex 0.789712 1.49114 2.55292 + vertex 0.789735 1.49617 2.55297 + vertex 0.788472 1.49412 2.54958 + endloop + endfacet + facet normal -0.985538 -0.0281847 0.167094 + outer loop + vertex 0.785916 1.5 2.54 + vertex 0.786316 1.49807 2.54203 + vertex 0.785773 1.505 2.54 + endloop + endfacet + facet normal -0.963161 0.00344225 0.268902 + outer loop + vertex 0.785773 1.505 2.54 + vertex 0.786316 1.49807 2.54203 + vertex 0.786325 1.50307 2.542 + endloop + endfacet + facet normal -0.964224 0.00341964 0.265067 + outer loop + vertex 0.786316 1.49807 2.54203 + vertex 0.787335 1.49795 2.54574 + vertex 0.786325 1.50307 2.542 + endloop + endfacet + facet normal -0.964726 0.00199243 0.26325 + outer loop + vertex 0.786325 1.50307 2.542 + vertex 0.787335 1.49795 2.54574 + vertex 0.787331 1.50297 2.54569 + endloop + endfacet + facet normal -0.95775 0.00224757 0.287595 + outer loop + vertex 0.787335 1.49795 2.54574 + vertex 0.788479 1.49915 2.54954 + vertex 0.787331 1.50297 2.54569 + endloop + endfacet + facet normal -0.958925 -0.00208075 0.283653 + outer loop + vertex 0.787331 1.50297 2.54569 + vertex 0.788479 1.49915 2.54954 + vertex 0.788456 1.50414 2.5495 + endloop + endfacet + facet normal -0.938138 -0.00147393 0.346259 + outer loop + vertex 0.788479 1.49915 2.54954 + vertex 0.789724 1.50117 2.55292 + vertex 0.788456 1.50414 2.5495 + endloop + endfacet + facet normal -0.938595 0.000874008 0.345021 + outer loop + vertex 0.789735 1.49617 2.55297 + vertex 0.789724 1.50117 2.55292 + vertex 0.788479 1.49915 2.54954 + endloop + endfacet + facet normal -0.950433 0.0469517 0.307364 + outer loop + vertex 0.785773 1.505 2.54 + vertex 0.786325 1.50307 2.542 + vertex 0.78602 1.51 2.54 + endloop + endfacet + facet normal -0.989551 -0.00188304 0.144174 + outer loop + vertex 0.78602 1.51 2.54 + vertex 0.786325 1.50307 2.542 + vertex 0.78631 1.50808 2.54197 + endloop + endfacet + facet normal -0.964748 -0.00105377 0.263172 + outer loop + vertex 0.786325 1.50307 2.542 + vertex 0.787331 1.50297 2.54569 + vertex 0.78631 1.50808 2.54197 + endloop + endfacet + facet normal -0.965797 -0.00410558 0.259267 + outer loop + vertex 0.78631 1.50808 2.54197 + vertex 0.787331 1.50297 2.54569 + vertex 0.787303 1.50796 2.54566 + endloop + endfacet + facet normal -0.958764 -0.00393877 0.284176 + outer loop + vertex 0.787331 1.50297 2.54569 + vertex 0.788456 1.50414 2.5495 + vertex 0.787303 1.50796 2.54566 + endloop + endfacet + facet normal -0.960224 -0.00950519 0.279069 + outer loop + vertex 0.787303 1.50796 2.54566 + vertex 0.788456 1.50414 2.5495 + vertex 0.788418 1.50912 2.54954 + endloop + endfacet + facet normal -0.939786 -0.00985294 0.341623 + outer loop + vertex 0.788456 1.50414 2.5495 + vertex 0.789685 1.50615 2.55294 + vertex 0.788418 1.50912 2.54954 + endloop + endfacet + facet normal -0.940058 -0.0084686 0.34091 + outer loop + vertex 0.789724 1.50117 2.55292 + vertex 0.789685 1.50615 2.55294 + vertex 0.788456 1.50414 2.5495 + endloop + endfacet + facet normal -0.994289 -0.0596554 0.0884933 + outer loop + vertex 0.78602 1.51 2.54 + vertex 0.78631 1.50808 2.54197 + vertex 0.78572 1.515 2.54 + endloop + endfacet + facet normal -0.96631 -0.00927419 0.257214 + outer loop + vertex 0.78572 1.515 2.54 + vertex 0.78631 1.50808 2.54197 + vertex 0.786264 1.51307 2.54198 + endloop + endfacet + facet normal -0.965805 -0.00927205 0.259104 + outer loop + vertex 0.78631 1.50808 2.54197 + vertex 0.787303 1.50796 2.54566 + vertex 0.786264 1.51307 2.54198 + endloop + endfacet + facet normal -0.965812 -0.00929316 0.259077 + outer loop + vertex 0.786264 1.51307 2.54198 + vertex 0.787303 1.50796 2.54566 + vertex 0.78727 1.51296 2.54572 + endloop + endfacet + facet normal -0.960226 -0.00947814 0.279062 + outer loop + vertex 0.787303 1.50796 2.54566 + vertex 0.788418 1.50912 2.54954 + vertex 0.78727 1.51296 2.54572 + endloop + endfacet + facet normal -0.960964 -0.0123566 0.276396 + outer loop + vertex 0.78727 1.51296 2.54572 + vertex 0.788418 1.50912 2.54954 + vertex 0.788381 1.51411 2.54963 + endloop + endfacet + facet normal -0.940693 -0.013369 0.338996 + outer loop + vertex 0.788418 1.50912 2.54954 + vertex 0.789647 1.51114 2.55303 + vertex 0.788381 1.51411 2.54963 + endloop + endfacet + facet normal -0.940708 -0.0132924 0.338957 + outer loop + vertex 0.789685 1.50615 2.55294 + vertex 0.789647 1.51114 2.55303 + vertex 0.788418 1.50912 2.54954 + endloop + endfacet + facet normal -0.962391 0.00655086 0.27159 + outer loop + vertex 0.78572 1.515 2.54 + vertex 0.786264 1.51307 2.54198 + vertex 0.785754 1.52 2.54 + endloop + endfacet + facet normal -0.973016 -0.00590015 0.230661 + outer loop + vertex 0.785754 1.52 2.54 + vertex 0.786264 1.51307 2.54198 + vertex 0.786242 1.51806 2.54201 + endloop + endfacet + facet normal -0.965812 -0.00605709 0.259173 + outer loop + vertex 0.786264 1.51307 2.54198 + vertex 0.78727 1.51296 2.54572 + vertex 0.786242 1.51806 2.54201 + endloop + endfacet + facet normal -0.966836 -0.00912557 0.255237 + outer loop + vertex 0.786242 1.51806 2.54201 + vertex 0.78727 1.51296 2.54572 + vertex 0.78724 1.51795 2.54579 + endloop + endfacet + facet normal -0.961229 -0.00936496 0.275592 + outer loop + vertex 0.78727 1.51296 2.54572 + vertex 0.788381 1.51411 2.54963 + vertex 0.78724 1.51795 2.54579 + endloop + endfacet + facet normal -0.960815 -0.00774535 0.277083 + outer loop + vertex 0.78724 1.51795 2.54579 + vertex 0.788381 1.51411 2.54963 + vertex 0.788358 1.51911 2.5497 + endloop + endfacet + facet normal -0.940323 -0.0084224 0.340179 + outer loop + vertex 0.788381 1.51411 2.54963 + vertex 0.789623 1.51615 2.55312 + vertex 0.788358 1.51911 2.5497 + endloop + endfacet + facet normal -0.93992 -0.0104771 0.341235 + outer loop + vertex 0.789647 1.51114 2.55303 + vertex 0.789623 1.51615 2.55312 + vertex 0.788381 1.51411 2.54963 + endloop + endfacet + facet normal -0.973412 -0.00779788 0.228927 + outer loop + vertex 0.785754 1.52 2.54 + vertex 0.786242 1.51806 2.54201 + vertex 0.785714 1.525 2.54 + endloop + endfacet + facet normal -0.968054 -0.00107467 0.25074 + outer loop + vertex 0.785714 1.525 2.54 + vertex 0.786242 1.51806 2.54201 + vertex 0.786243 1.52306 2.54204 + endloop + endfacet + facet normal -0.966815 -0.00110033 0.255477 + outer loop + vertex 0.786242 1.51806 2.54201 + vertex 0.78724 1.51795 2.54579 + vertex 0.786243 1.52306 2.54204 + endloop + endfacet + facet normal -0.967421 -0.00292038 0.253158 + outer loop + vertex 0.786243 1.52306 2.54204 + vertex 0.78724 1.51795 2.54579 + vertex 0.78723 1.52295 2.5458 + endloop + endfacet + facet normal -0.961216 -0.00298713 0.27578 + outer loop + vertex 0.78724 1.51795 2.54579 + vertex 0.788358 1.51911 2.5497 + vertex 0.78723 1.52295 2.5458 + endloop + endfacet + facet normal -0.960342 0.000353191 0.278823 + outer loop + vertex 0.78723 1.52295 2.5458 + vertex 0.788358 1.51911 2.5497 + vertex 0.788352 1.52412 2.54967 + endloop + endfacet + facet normal -0.939314 0.00073755 0.343058 + outer loop + vertex 0.788358 1.51911 2.5497 + vertex 0.789616 1.52115 2.55314 + vertex 0.788352 1.52412 2.54967 + endloop + endfacet + facet normal -0.938698 -0.00247033 0.344733 + outer loop + vertex 0.789623 1.51615 2.55312 + vertex 0.789616 1.52115 2.55314 + vertex 0.788358 1.51911 2.5497 + endloop + endfacet + facet normal -0.9602 0.0293831 0.277765 + outer loop + vertex 0.785714 1.525 2.54 + vertex 0.786243 1.52306 2.54204 + vertex 0.785867 1.53 2.54 + endloop + endfacet + facet normal -0.978345 0.00760587 0.20684 + outer loop + vertex 0.785867 1.53 2.54 + vertex 0.786243 1.52306 2.54204 + vertex 0.786281 1.52807 2.54203 + endloop + endfacet + facet normal -0.967325 0.00755977 0.253429 + outer loop + vertex 0.786243 1.52306 2.54204 + vertex 0.78723 1.52295 2.5458 + vertex 0.786281 1.52807 2.54203 + endloop + endfacet + facet normal -0.968683 0.0035072 0.248274 + outer loop + vertex 0.786281 1.52807 2.54203 + vertex 0.78723 1.52295 2.5458 + vertex 0.787236 1.52797 2.54576 + endloop + endfacet + facet normal -0.960611 0.00377273 0.277871 + outer loop + vertex 0.78723 1.52295 2.5458 + vertex 0.788352 1.52412 2.54967 + vertex 0.787236 1.52797 2.54576 + endloop + endfacet + facet normal -0.959882 0.00647906 0.280331 + outer loop + vertex 0.787236 1.52797 2.54576 + vertex 0.788352 1.52412 2.54967 + vertex 0.788352 1.52912 2.54955 + endloop + endfacet + facet normal -0.936846 0.00806254 0.349649 + outer loop + vertex 0.788352 1.52412 2.54967 + vertex 0.789626 1.52616 2.55303 + vertex 0.788352 1.52912 2.54955 + endloop + endfacet + facet normal -0.937006 0.00890181 0.349201 + outer loop + vertex 0.789616 1.52115 2.55314 + vertex 0.789626 1.52616 2.55303 + vertex 0.788352 1.52412 2.54967 + endloop + endfacet + facet normal -0.973403 0.0299844 0.227128 + outer loop + vertex 0.785867 1.53 2.54 + vertex 0.786281 1.52807 2.54203 + vertex 0.786021 1.535 2.54 + endloop + endfacet + facet normal -0.98755 0.00892165 0.157053 + outer loop + vertex 0.786021 1.535 2.54 + vertex 0.786281 1.52807 2.54203 + vertex 0.786322 1.5331 2.542 + endloop + endfacet + facet normal -0.968612 0.00928733 0.248404 + outer loop + vertex 0.786281 1.52807 2.54203 + vertex 0.787236 1.52797 2.54576 + vertex 0.786322 1.5331 2.542 + endloop + endfacet + facet normal -0.969239 0.00742045 0.246008 + outer loop + vertex 0.786322 1.5331 2.542 + vertex 0.787236 1.52797 2.54576 + vertex 0.787259 1.53299 2.54569 + endloop + endfacet + facet normal -0.95998 0.00779772 0.279961 + outer loop + vertex 0.787236 1.52797 2.54576 + vertex 0.788352 1.52912 2.54955 + vertex 0.787259 1.53299 2.54569 + endloop + endfacet + facet normal -0.960218 0.00693935 0.279167 + outer loop + vertex 0.787259 1.53299 2.54569 + vertex 0.788352 1.52912 2.54955 + vertex 0.788359 1.53404 2.54945 + endloop + endfacet + facet normal -0.934346 0.00845756 0.356266 + outer loop + vertex 0.788352 1.52912 2.54955 + vertex 0.789624 1.53112 2.55284 + vertex 0.788359 1.53404 2.54945 + endloop + endfacet + facet normal -0.935291 0.0134007 0.353626 + outer loop + vertex 0.789626 1.52616 2.55303 + vertex 0.789624 1.53112 2.55284 + vertex 0.788352 1.52912 2.54955 + endloop + endfacet + facet normal -0.989746 -0.00653648 0.142691 + outer loop + vertex 0.786021 1.535 2.54 + vertex 0.786322 1.5331 2.542 + vertex 0.785988 1.54 2.54 + endloop + endfacet + facet normal -0.976663 0.0148607 0.214264 + outer loop + vertex 0.785988 1.54 2.54 + vertex 0.786322 1.5331 2.542 + vertex 0.7864 1.53815 2.54201 + endloop + endfacet + facet normal -0.969112 0.014711 0.246182 + outer loop + vertex 0.786322 1.5331 2.542 + vertex 0.787259 1.53299 2.54569 + vertex 0.7864 1.53815 2.54201 + endloop + endfacet + facet normal -0.970184 0.0116094 0.242093 + outer loop + vertex 0.7864 1.53815 2.54201 + vertex 0.787259 1.53299 2.54569 + vertex 0.787351 1.53805 2.54582 + endloop + endfacet + facet normal -0.960455 0.0105172 0.278237 + outer loop + vertex 0.787259 1.53299 2.54569 + vertex 0.788359 1.53404 2.54945 + vertex 0.787351 1.53805 2.54582 + endloop + endfacet + facet normal -0.962402 0.00402033 0.2716 + outer loop + vertex 0.787351 1.53805 2.54582 + vertex 0.788359 1.53404 2.54945 + vertex 0.788419 1.53858 2.5496 + endloop + endfacet + facet normal -0.934212 0.000898762 0.356716 + outer loop + vertex 0.788359 1.53404 2.54945 + vertex 0.789566 1.53586 2.55261 + vertex 0.788419 1.53858 2.5496 + endloop + endfacet + facet normal -0.935132 0.00578398 0.354252 + outer loop + vertex 0.789624 1.53112 2.55284 + vertex 0.789566 1.53586 2.55261 + vertex 0.788359 1.53404 2.54945 + endloop + endfacet + facet normal -0.973266 0.0301775 0.227688 + outer loop + vertex 0.785988 1.54 2.54 + vertex 0.7864 1.53815 2.54201 + vertex 0.786143 1.545 2.54 + endloop + endfacet + facet normal -0.97417 0.0290445 0.223938 + outer loop + vertex 0.786143 1.545 2.54 + vertex 0.7864 1.53815 2.54201 + vertex 0.78658 1.54329 2.54212 + endloop + endfacet + facet normal -0.969756 0.028472 0.242408 + outer loop + vertex 0.7864 1.53815 2.54201 + vertex 0.787351 1.53805 2.54582 + vertex 0.78658 1.54329 2.54212 + endloop + endfacet + facet normal -0.972938 0.0194162 0.230247 + outer loop + vertex 0.78658 1.54329 2.54212 + vertex 0.787351 1.53805 2.54582 + vertex 0.787663 1.5436 2.54667 + endloop + endfacet + facet normal -0.936725 -0.0107815 0.349901 + outer loop + vertex 0.78869 1.54167 2.55042 + vertex 0.788419 1.53858 2.5496 + vertex 0.789398 1.53954 2.55225 + endloop + endfacet + facet normal -0.962699 0.0125518 0.270284 + outer loop + vertex 0.78869 1.54167 2.55042 + vertex 0.787663 1.5436 2.54667 + vertex 0.788419 1.53858 2.5496 + endloop + endfacet + facet normal -0.962646 0.0126671 0.270468 + outer loop + vertex 0.787663 1.5436 2.54667 + vertex 0.787351 1.53805 2.54582 + vertex 0.788419 1.53858 2.5496 + endloop + endfacet + facet normal -0.937003 -0.00859656 0.349214 + outer loop + vertex 0.789398 1.53954 2.55225 + vertex 0.788419 1.53858 2.5496 + vertex 0.789566 1.53586 2.55261 + endloop + endfacet + facet normal -0.965892 0.0645264 0.250777 + outer loop + vertex 0.786143 1.545 2.54 + vertex 0.78658 1.54329 2.54212 + vertex 0.786477 1.55 2.54 + endloop + endfacet + facet normal -0.987569 0.0334202 0.153594 + outer loop + vertex 0.786477 1.55 2.54 + vertex 0.78658 1.54329 2.54212 + vertex 0.78673 1.54845 2.54196 + endloop + endfacet + facet normal -0.97276 0.0353302 0.229107 + outer loop + vertex 0.78658 1.54329 2.54212 + vertex 0.787663 1.5436 2.54667 + vertex 0.78673 1.54845 2.54196 + endloop + endfacet + facet normal -0.978677 0.0108914 0.205118 + outer loop + vertex 0.78673 1.54845 2.54196 + vertex 0.787663 1.5436 2.54667 + vertex 0.78736 1.54898 2.54494 + endloop + endfacet + facet normal -0.963629 0.00602893 0.267176 + outer loop + vertex 0.788657 1.54442 2.55024 + vertex 0.787663 1.5436 2.54667 + vertex 0.78869 1.54167 2.55042 + endloop + endfacet + facet normal -0.963574 0.0050008 0.267396 + outer loop + vertex 0.788657 1.54442 2.55024 + vertex 0.78829 1.54804 2.54885 + vertex 0.787663 1.5436 2.54667 + endloop + endfacet + facet normal -0.971447 0.0213573 0.236295 + outer loop + vertex 0.78829 1.54804 2.54885 + vertex 0.78736 1.54898 2.54494 + vertex 0.787663 1.5436 2.54667 + endloop + endfacet + facet normal -0.944081 0.0304498 0.328305 + outer loop + vertex 0.788657 1.54442 2.55024 + vertex 0.789274 1.54651 2.55182 + vertex 0.78829 1.54804 2.54885 + endloop + endfacet + facet normal -0.986806 0.0382789 0.157319 + outer loop + vertex 0.786477 1.55 2.54 + vertex 0.78673 1.54845 2.54196 + vertex 0.786671 1.555 2.54 + endloop + endfacet + facet normal -0.989506 0.0332419 0.140616 + outer loop + vertex 0.786671 1.555 2.54 + vertex 0.78673 1.54845 2.54196 + vertex 0.786883 1.55345 2.54186 + endloop + endfacet + facet normal -0.97898 0.0341814 0.201073 + outer loop + vertex 0.78673 1.54845 2.54196 + vertex 0.78736 1.54898 2.54494 + vertex 0.786883 1.55345 2.54186 + endloop + endfacet + facet normal -0.980935 0.0279337 0.192318 + outer loop + vertex 0.786883 1.55345 2.54186 + vertex 0.78736 1.54898 2.54494 + vertex 0.787699 1.55329 2.54604 + endloop + endfacet + facet normal -0.947234 -0.00347699 0.320523 + outer loop + vertex 0.78861 1.5516 2.54983 + vertex 0.78829 1.54804 2.54885 + vertex 0.789241 1.54929 2.55167 + endloop + endfacet + facet normal -0.969998 0.0202725 0.242268 + outer loop + vertex 0.78861 1.5516 2.54983 + vertex 0.787699 1.55329 2.54604 + vertex 0.78829 1.54804 2.54885 + endloop + endfacet + facet normal -0.97182 0.0162713 0.23516 + outer loop + vertex 0.787699 1.55329 2.54604 + vertex 0.78736 1.54898 2.54494 + vertex 0.78829 1.54804 2.54885 + endloop + endfacet + facet normal -0.948431 0.005516 0.316936 + outer loop + vertex 0.789241 1.54929 2.55167 + vertex 0.78829 1.54804 2.54885 + vertex 0.789274 1.54651 2.55182 + endloop + endfacet + facet normal -0.984454 0.0622223 0.164251 + outer loop + vertex 0.786671 1.555 2.54 + vertex 0.786883 1.55345 2.54186 + vertex 0.786987 1.56 2.54 + endloop + endfacet + facet normal -0.997411 0.0338237 0.0634678 + outer loop + vertex 0.786987 1.56 2.54 + vertex 0.786883 1.55345 2.54186 + vertex 0.787064 1.55852 2.54199 + endloop + endfacet + facet normal -0.980865 0.0299181 0.192377 + outer loop + vertex 0.786883 1.55345 2.54186 + vertex 0.787699 1.55329 2.54604 + vertex 0.787064 1.55852 2.54199 + endloop + endfacet + facet normal -0.986442 0.0072269 0.163953 + outer loop + vertex 0.787064 1.55852 2.54199 + vertex 0.787699 1.55329 2.54604 + vertex 0.787678 1.55901 2.54566 + endloop + endfacet + facet normal -0.969678 0.0125832 0.244063 + outer loop + vertex 0.787699 1.55329 2.54604 + vertex 0.788584 1.55557 2.54944 + vertex 0.787678 1.55901 2.54566 + endloop + endfacet + facet normal -0.970358 0.0173517 0.24105 + outer loop + vertex 0.78861 1.5516 2.54983 + vertex 0.788584 1.55557 2.54944 + vertex 0.787699 1.55329 2.54604 + endloop + endfacet + facet normal -0.993845 0.0671859 0.0880826 + outer loop + vertex 0.786987 1.56 2.54 + vertex 0.787064 1.55852 2.54199 + vertex 0.787325 1.565 2.54 + endloop + endfacet + facet normal -0.996264 0.0140205 -0.0852106 + outer loop + vertex 0.787325 1.565 2.54 + vertex 0.787064 1.55852 2.54199 + vertex 0.787137 1.56378 2.542 + endloop + endfacet + facet normal -0.986513 0.0136364 0.163117 + outer loop + vertex 0.787064 1.55852 2.54199 + vertex 0.787678 1.55901 2.54566 + vertex 0.787137 1.56378 2.542 + endloop + endfacet + facet normal -0.989337 -0.000111962 0.145648 + outer loop + vertex 0.787137 1.56378 2.542 + vertex 0.787678 1.55901 2.54566 + vertex 0.787669 1.56426 2.54561 + endloop + endfacet + facet normal -0.969923 0.000945475 0.243412 + outer loop + vertex 0.787678 1.55901 2.54566 + vertex 0.788593 1.5605 2.5493 + vertex 0.787669 1.56426 2.54561 + endloop + endfacet + facet normal -0.970609 0.00844307 0.240514 + outer loop + vertex 0.788584 1.55557 2.54944 + vertex 0.788593 1.5605 2.5493 + vertex 0.787678 1.55901 2.54566 + endloop + endfacet + facet normal -0.996446 0.0193264 -0.0819879 + outer loop + vertex 0.787325 1.565 2.54 + vertex 0.787137 1.56378 2.542 + vertex 0.787422 1.57 2.54 + endloop + endfacet + facet normal -0.992341 0.00584884 -0.123392 + outer loop + vertex 0.787422 1.57 2.54 + vertex 0.787137 1.56378 2.542 + vertex 0.787161 1.56895 2.54205 + endloop + endfacet + facet normal -0.989393 0.00312065 0.145227 + outer loop + vertex 0.787137 1.56378 2.542 + vertex 0.787669 1.56426 2.54561 + vertex 0.787161 1.56895 2.54205 + endloop + endfacet + facet normal -0.990753 -0.00433159 0.135612 + outer loop + vertex 0.787161 1.56895 2.54205 + vertex 0.787669 1.56426 2.54561 + vertex 0.787648 1.56938 2.54562 + endloop + endfacet + facet normal -0.968726 -0.00449863 0.248091 + outer loop + vertex 0.787669 1.56426 2.54561 + vertex 0.788595 1.56555 2.54925 + vertex 0.787648 1.56938 2.54562 + endloop + endfacet + facet normal -0.969381 0.00316865 0.24554 + outer loop + vertex 0.788593 1.5605 2.5493 + vertex 0.788595 1.56555 2.54925 + vertex 0.787669 1.56426 2.54561 + endloop + endfacet + facet normal -0.99339 0.0313935 -0.110407 + outer loop + vertex 0.787422 1.57 2.54 + vertex 0.787161 1.56895 2.54205 + vertex 0.78758 1.575 2.54 + endloop + endfacet + facet normal -0.983395 0.00668955 -0.181355 + outer loop + vertex 0.78758 1.575 2.54 + vertex 0.787161 1.56895 2.54205 + vertex 0.787196 1.57401 2.54205 + endloop + endfacet + facet normal -0.990921 0.00683036 0.134272 + outer loop + vertex 0.787161 1.56895 2.54205 + vertex 0.787648 1.56938 2.54562 + vertex 0.787196 1.57401 2.54205 + endloop + endfacet + facet normal -0.991227 0.00509744 0.132069 + outer loop + vertex 0.787196 1.57401 2.54205 + vertex 0.787648 1.56938 2.54562 + vertex 0.787668 1.57443 2.54557 + endloop + endfacet + facet normal -0.965831 0.00623031 0.259098 + outer loop + vertex 0.787648 1.56938 2.54562 + vertex 0.78862 1.57061 2.54921 + vertex 0.787668 1.57443 2.54557 + endloop + endfacet + facet normal -0.965855 0.00653547 0.259 + outer loop + vertex 0.788595 1.56555 2.54925 + vertex 0.78862 1.57061 2.54921 + vertex 0.787648 1.56938 2.54562 + endloop + endfacet + facet normal -0.9833 0.00550927 -0.181909 + outer loop + vertex 0.78758 1.575 2.54 + vertex 0.787196 1.57401 2.54205 + vertex 0.787608 1.58 2.54 + endloop + endfacet + facet normal -0.985519 0.00998038 -0.169269 + outer loop + vertex 0.787608 1.58 2.54 + vertex 0.787196 1.57401 2.54205 + vertex 0.78727 1.57892 2.54191 + endloop + endfacet + facet normal -0.991278 0.0186598 0.13046 + outer loop + vertex 0.787196 1.57401 2.54205 + vertex 0.787668 1.57443 2.54557 + vertex 0.78727 1.57892 2.54191 + endloop + endfacet + facet normal -0.991524 0.0172579 0.128771 + outer loop + vertex 0.78727 1.57892 2.54191 + vertex 0.787668 1.57443 2.54557 + vertex 0.787735 1.57938 2.54542 + endloop + endfacet + facet normal -0.963724 0.0209908 0.266074 + outer loop + vertex 0.787668 1.57443 2.54557 + vertex 0.788678 1.57565 2.54914 + vertex 0.787735 1.57938 2.54542 + endloop + endfacet + facet normal -0.963319 0.0152644 0.267923 + outer loop + vertex 0.78862 1.57061 2.54921 + vertex 0.788678 1.57565 2.54914 + vertex 0.787668 1.57443 2.54557 + endloop + endfacet + facet normal -0.986342 0.0205062 -0.163426 + outer loop + vertex 0.787608 1.58 2.54 + vertex 0.78727 1.57892 2.54191 + vertex 0.787712 1.585 2.54 + endloop + endfacet + facet normal -0.983409 0.0148526 -0.180792 + outer loop + vertex 0.787712 1.585 2.54 + vertex 0.78727 1.57892 2.54191 + vertex 0.787387 1.58368 2.54166 + endloop + endfacet + facet normal -0.991426 0.0311005 0.126912 + outer loop + vertex 0.78727 1.57892 2.54191 + vertex 0.787735 1.57938 2.54542 + vertex 0.787387 1.58368 2.54166 + endloop + endfacet + facet normal -0.993575 0.0176766 0.111791 + outer loop + vertex 0.787387 1.58368 2.54166 + vertex 0.787735 1.57938 2.54542 + vertex 0.787799 1.58426 2.54522 + endloop + endfacet + facet normal -0.964091 0.0236168 0.264519 + outer loop + vertex 0.787735 1.57938 2.54542 + vertex 0.78875 1.58068 2.54901 + vertex 0.787799 1.58426 2.54522 + endloop + endfacet + facet normal -0.963869 0.0204721 0.26559 + outer loop + vertex 0.788678 1.57565 2.54914 + vertex 0.78875 1.58068 2.54901 + vertex 0.787735 1.57938 2.54542 + endloop + endfacet + facet normal -0.983042 0.012 -0.182987 + outer loop + vertex 0.787712 1.585 2.54 + vertex 0.787387 1.58368 2.54166 + vertex 0.787773 1.59 2.54 + endloop + endfacet + facet normal -0.975197 0.00145987 -0.221332 + outer loop + vertex 0.787773 1.59 2.54 + vertex 0.787387 1.58368 2.54166 + vertex 0.787485 1.58806 2.54125 + endloop + endfacet + facet normal -0.993473 0.0323514 0.109384 + outer loop + vertex 0.787387 1.58368 2.54166 + vertex 0.787799 1.58426 2.54522 + vertex 0.787485 1.58806 2.54125 + endloop + endfacet + facet normal -0.995705 0.013559 0.091586 + outer loop + vertex 0.787485 1.58806 2.54125 + vertex 0.787799 1.58426 2.54522 + vertex 0.787853 1.58919 2.54508 + endloop + endfacet + facet normal -0.9647 0.0179829 0.262736 + outer loop + vertex 0.787799 1.58426 2.54522 + vertex 0.788815 1.58571 2.54885 + vertex 0.787853 1.58919 2.54508 + endloop + endfacet + facet normal -0.964908 0.0205148 0.261785 + outer loop + vertex 0.78875 1.58068 2.54901 + vertex 0.788815 1.58571 2.54885 + vertex 0.787799 1.58426 2.54522 + endloop + endfacet + facet normal -0.784991 0.0012407 -0.619506 + outer loop + vertex 0.79 1.59 2.53506 + vertex 0.788121 1.59137 2.53744 + vertex 0.79 1.595 2.53507 + endloop + endfacet + facet normal -0.804039 -0.471315 -0.362468 + outer loop + vertex 0.787773 1.59 2.54 + vertex 0.788121 1.59137 2.53744 + vertex 0.79 1.59 2.53506 + endloop + endfacet + facet normal 0.992095 -0.0915412 0.0858373 + outer loop + vertex 0.787773 1.59 2.54 + vertex 0.787485 1.58806 2.54125 + vertex 0.788121 1.59137 2.53744 + endloop + endfacet + facet normal -0.987457 0.00801405 -0.157686 + outer loop + vertex 0.788121 1.59137 2.53744 + vertex 0.787485 1.58806 2.54125 + vertex 0.787567 1.59251 2.54097 + endloop + endfacet + facet normal -0.995785 0.0239004 0.0885502 + outer loop + vertex 0.787485 1.58806 2.54125 + vertex 0.787853 1.58919 2.54508 + vertex 0.787567 1.59251 2.54097 + endloop + endfacet + facet normal -0.997074 0.00823542 0.0759996 + outer loop + vertex 0.787567 1.59251 2.54097 + vertex 0.787853 1.58919 2.54508 + vertex 0.787886 1.59418 2.54498 + endloop + endfacet + facet normal -0.963387 0.0121968 0.267836 + outer loop + vertex 0.787853 1.58919 2.54508 + vertex 0.788877 1.59077 2.54869 + vertex 0.787886 1.59418 2.54498 + endloop + endfacet + facet normal -0.964153 0.0201357 0.264582 + outer loop + vertex 0.788815 1.58571 2.54885 + vertex 0.788877 1.59077 2.54869 + vertex 0.787853 1.58919 2.54508 + endloop + endfacet + facet normal -0.766602 0.0167122 -0.641905 + outer loop + vertex 0.79 1.595 2.53507 + vertex 0.788255 1.59579 2.53717 + vertex 0.79 1.6 2.5352 + endloop + endfacet + facet normal -0.772523 -0.0152298 -0.634804 + outer loop + vertex 0.788121 1.59137 2.53744 + vertex 0.788255 1.59579 2.53717 + vertex 0.79 1.595 2.53507 + endloop + endfacet + facet normal -0.986671 0.0201718 -0.161476 + outer loop + vertex 0.788121 1.59137 2.53744 + vertex 0.787567 1.59251 2.54097 + vertex 0.788255 1.59579 2.53717 + endloop + endfacet + facet normal -0.986212 0.0163768 -0.164676 + outer loop + vertex 0.788255 1.59579 2.53717 + vertex 0.787567 1.59251 2.54097 + vertex 0.787658 1.59742 2.54091 + endloop + endfacet + facet normal -0.997261 0.0192257 0.0714168 + outer loop + vertex 0.787567 1.59251 2.54097 + vertex 0.787886 1.59418 2.54498 + vertex 0.787658 1.59742 2.54091 + endloop + endfacet + facet normal -0.997213 0.0198596 0.0719199 + outer loop + vertex 0.787658 1.59742 2.54091 + vertex 0.787886 1.59418 2.54498 + vertex 0.787974 1.59919 2.54482 + endloop + endfacet + facet normal -0.958875 0.0259236 0.282642 + outer loop + vertex 0.787886 1.59418 2.54498 + vertex 0.788969 1.5958 2.5485 + vertex 0.787974 1.59919 2.54482 + endloop + endfacet + facet normal -0.959116 0.0283943 0.281584 + outer loop + vertex 0.788877 1.59077 2.54869 + vertex 0.788969 1.5958 2.5485 + vertex 0.787886 1.59418 2.54498 + endloop + endfacet + facet normal -0.750686 0.129557 -0.647832 + outer loop + vertex 0.79 1.6 2.5352 + vertex 0.788356 1.60069 2.53724 + vertex 0.79 1.605 2.5362 + endloop + endfacet + facet normal -0.774828 0.0249178 -0.631681 + outer loop + vertex 0.788255 1.59579 2.53717 + vertex 0.788356 1.60069 2.53724 + vertex 0.79 1.6 2.5352 + endloop + endfacet + facet normal -0.985646 0.0226028 -0.167303 + outer loop + vertex 0.788255 1.59579 2.53717 + vertex 0.787658 1.59742 2.54091 + vertex 0.788356 1.60069 2.53724 + endloop + endfacet + facet normal -0.984558 0.0143263 -0.174472 + outer loop + vertex 0.788356 1.60069 2.53724 + vertex 0.787658 1.59742 2.54091 + vertex 0.787748 1.60245 2.54082 + endloop + endfacet + facet normal -0.997205 0.0192961 0.0721749 + outer loop + vertex 0.787658 1.59742 2.54091 + vertex 0.787974 1.59919 2.54482 + vertex 0.787748 1.60245 2.54082 + endloop + endfacet + facet normal -0.996323 0.0295091 0.0804349 + outer loop + vertex 0.787748 1.60245 2.54082 + vertex 0.787974 1.59919 2.54482 + vertex 0.788102 1.60409 2.5446 + endloop + endfacet + facet normal -0.953513 0.0381241 0.298929 + outer loop + vertex 0.787974 1.59919 2.54482 + vertex 0.789109 1.60075 2.54824 + vertex 0.788102 1.60409 2.5446 + endloop + endfacet + facet normal -0.953942 0.0428769 0.296913 + outer loop + vertex 0.788969 1.5958 2.5485 + vertex 0.789109 1.60075 2.54824 + vertex 0.787974 1.59919 2.54482 + endloop + endfacet + facet normal -0.532849 0.082525 -0.842177 + outer loop + vertex 0.79 1.605 2.5362 + vertex 0.788395 1.60588 2.5373 + vertex 0.79 1.61 2.53669 + endloop + endfacet + facet normal -0.560868 0.0134094 -0.827797 + outer loop + vertex 0.788356 1.60069 2.53724 + vertex 0.788395 1.60588 2.5373 + vertex 0.79 1.605 2.5362 + endloop + endfacet + facet normal -0.985033 0.00934686 -0.172113 + outer loop + vertex 0.788356 1.60069 2.53724 + vertex 0.787748 1.60245 2.54082 + vertex 0.788395 1.60588 2.5373 + endloop + endfacet + facet normal -0.985174 0.0102577 -0.17125 + outer loop + vertex 0.788395 1.60588 2.5373 + vertex 0.787748 1.60245 2.54082 + vertex 0.787821 1.60768 2.54071 + endloop + endfacet + facet normal -0.996131 0.015567 0.0864921 + outer loop + vertex 0.787748 1.60245 2.54082 + vertex 0.788102 1.60409 2.5446 + vertex 0.787821 1.60768 2.54071 + endloop + endfacet + facet normal -0.994675 0.0290979 0.0988734 + outer loop + vertex 0.787821 1.60768 2.54071 + vertex 0.788102 1.60409 2.5446 + vertex 0.788221 1.60862 2.54446 + endloop + endfacet + facet normal -0.947686 0.0342754 0.317359 + outer loop + vertex 0.788102 1.60409 2.5446 + vertex 0.789252 1.60553 2.54788 + vertex 0.788221 1.60862 2.54446 + endloop + endfacet + facet normal -0.949243 0.0517375 0.310259 + outer loop + vertex 0.789109 1.60075 2.54824 + vertex 0.789252 1.60553 2.54788 + vertex 0.788102 1.60409 2.5446 + endloop + endfacet + facet normal -0.428672 -0.278478 -0.859471 + outer loop + vertex 0.79 1.61 2.53669 + vertex 0.788295 1.61235 2.53678 + vertex 0.79 1.615 2.53507 + endloop + endfacet + facet normal -0.164396 -0.0819182 -0.982987 + outer loop + vertex 0.788395 1.60588 2.5373 + vertex 0.788295 1.61235 2.53678 + vertex 0.79 1.61 2.53669 + endloop + endfacet + facet normal -0.98802 -0.027478 -0.151857 + outer loop + vertex 0.788395 1.60588 2.5373 + vertex 0.787821 1.60768 2.54071 + vertex 0.788295 1.61235 2.53678 + endloop + endfacet + facet normal -0.99434 0.0121671 -0.105544 + outer loop + vertex 0.788295 1.61235 2.53678 + vertex 0.787821 1.60768 2.54071 + vertex 0.787851 1.61328 2.54108 + endloop + endfacet + facet normal -0.944748 0.0345929 0.325968 + outer loop + vertex 0.7885 1.61187 2.54493 + vertex 0.788221 1.60862 2.54446 + vertex 0.789188 1.60931 2.54719 + endloop + endfacet + facet normal -0.980754 0.0575935 0.18656 + outer loop + vertex 0.7885 1.61187 2.54493 + vertex 0.787851 1.61328 2.54108 + vertex 0.788221 1.60862 2.54446 + endloop + endfacet + facet normal -0.994302 -0.00161981 0.106589 + outer loop + vertex 0.787851 1.61328 2.54108 + vertex 0.787821 1.60768 2.54071 + vertex 0.788221 1.60862 2.54446 + endloop + endfacet + facet normal -0.945074 0.0425483 0.324075 + outer loop + vertex 0.789188 1.60931 2.54719 + vertex 0.788221 1.60862 2.54446 + vertex 0.789252 1.60553 2.54788 + endloop + endfacet + facet normal -0.886292 -0.2193 -0.407914 + outer loop + vertex 0.79 1.615 2.53507 + vertex 0.788795 1.62 2.535 + vertex 0.79 1.61513 2.535 + endloop + endfacet + facet normal -0.574304 -0.149655 -0.804846 + outer loop + vertex 0.79 1.615 2.53507 + vertex 0.788295 1.61235 2.53678 + vertex 0.788795 1.62 2.535 + endloop + endfacet + facet normal -0.831221 -0.0738568 -0.551014 + outer loop + vertex 0.788295 1.61235 2.53678 + vertex 0.787686 1.61851 2.53687 + vertex 0.788795 1.62 2.535 + endloop + endfacet + facet normal -0.99195 -0.0968231 -0.081617 + outer loop + vertex 0.788295 1.61235 2.53678 + vertex 0.787851 1.61328 2.54108 + vertex 0.787686 1.61851 2.53687 + endloop + endfacet + facet normal -0.999687 -0.0160481 0.019182 + outer loop + vertex 0.787686 1.61851 2.53687 + vertex 0.787851 1.61328 2.54108 + vertex 0.787741 1.6192 2.54034 + endloop + endfacet + facet normal -0.977821 0.0081384 0.209285 + outer loop + vertex 0.787851 1.61328 2.54108 + vertex 0.788537 1.61576 2.54419 + vertex 0.787741 1.6192 2.54034 + endloop + endfacet + facet normal -0.98235 0.0439075 0.181826 + outer loop + vertex 0.7885 1.61187 2.54493 + vertex 0.788537 1.61576 2.54419 + vertex 0.787851 1.61328 2.54108 + endloop + endfacet + facet normal -0.809573 -0.119816 -0.574662 + outer loop + vertex 0.788795 1.62 2.535 + vertex 0.787686 1.61851 2.53687 + vertex 0.788055 1.625 2.535 + endloop + endfacet + facet normal -0.926037 -0.0550853 -0.373392 + outer loop + vertex 0.788055 1.625 2.535 + vertex 0.787686 1.61851 2.53687 + vertex 0.787465 1.62373 2.53665 + endloop + endfacet + facet normal -0.998853 -0.0413396 0.024169 + outer loop + vertex 0.787686 1.61851 2.53687 + vertex 0.787741 1.6192 2.54034 + vertex 0.787465 1.62373 2.53665 + endloop + endfacet + facet normal -0.99588 0.0122936 0.0898443 + outer loop + vertex 0.787465 1.62373 2.53665 + vertex 0.787741 1.6192 2.54034 + vertex 0.787774 1.62431 2.54 + endloop + endfacet + facet normal -0.969049 0.0223587 0.245855 + outer loop + vertex 0.787741 1.6192 2.54034 + vertex 0.788653 1.62068 2.54379 + vertex 0.787774 1.62431 2.54 + endloop + endfacet + facet normal -0.970401 0.0418221 0.237848 + outer loop + vertex 0.788537 1.61576 2.54419 + vertex 0.788653 1.62068 2.54379 + vertex 0.787741 1.6192 2.54034 + endloop + endfacet + facet normal -0.940405 -0.00507836 -0.340017 + outer loop + vertex 0.788055 1.625 2.535 + vertex 0.787465 1.62373 2.53665 + vertex 0.788028 1.63 2.535 + endloop + endfacet + facet normal -0.933437 -0.0105938 -0.358586 + outer loop + vertex 0.788028 1.63 2.535 + vertex 0.787465 1.62373 2.53665 + vertex 0.787485 1.62858 2.53646 + endloop + endfacet + facet normal -0.995855 0.00783814 0.0906175 + outer loop + vertex 0.787465 1.62373 2.53665 + vertex 0.787774 1.62431 2.54 + vertex 0.787485 1.62858 2.53646 + endloop + endfacet + facet normal -0.992166 0.0329296 0.120509 + outer loop + vertex 0.787485 1.62858 2.53646 + vertex 0.787774 1.62431 2.54 + vertex 0.787913 1.62924 2.5398 + endloop + endfacet + facet normal -0.96143 0.0382822 0.272374 + outer loop + vertex 0.787774 1.62431 2.54 + vertex 0.788839 1.6257 2.54357 + vertex 0.787913 1.62924 2.5398 + endloop + endfacet + facet normal -0.962009 0.0480181 0.268763 + outer loop + vertex 0.788653 1.62068 2.54379 + vertex 0.788839 1.6257 2.54357 + vertex 0.787774 1.62431 2.54 + endloop + endfacet + facet normal -0.926614 -0.0298355 -0.374828 + outer loop + vertex 0.788028 1.63 2.535 + vertex 0.787485 1.62858 2.53646 + vertex 0.787867 1.635 2.535 + endloop + endfacet + facet normal -0.983215 0.0173196 -0.181629 + outer loop + vertex 0.787867 1.635 2.535 + vertex 0.787485 1.62858 2.53646 + vertex 0.787607 1.633 2.53621 + endloop + endfacet + facet normal -0.992156 0.0339981 0.120296 + outer loop + vertex 0.787485 1.62858 2.53646 + vertex 0.787913 1.62924 2.5398 + vertex 0.787607 1.633 2.53621 + endloop + endfacet + facet normal -0.99088 0.0415993 0.128162 + outer loop + vertex 0.787607 1.633 2.53621 + vertex 0.787913 1.62924 2.5398 + vertex 0.788089 1.6341 2.53958 + endloop + endfacet + facet normal -0.957219 0.0474004 0.285455 + outer loop + vertex 0.787913 1.62924 2.5398 + vertex 0.789045 1.63066 2.54336 + vertex 0.788089 1.6341 2.53958 + endloop + endfacet + facet normal -0.957473 0.0515377 0.283884 + outer loop + vertex 0.788839 1.6257 2.54357 + vertex 0.789045 1.63066 2.54336 + vertex 0.787913 1.62924 2.5398 + endloop + endfacet + facet normal -0.302159 0.0228572 -0.952983 + outer loop + vertex 0.79 1.635 2.53287 + vertex 0.788186 1.63629 2.53348 + vertex 0.79 1.64 2.53299 + endloop + endfacet + facet normal -0.590004 -0.550286 -0.59083 + outer loop + vertex 0.787867 1.635 2.535 + vertex 0.788186 1.63629 2.53348 + vertex 0.79 1.635 2.53287 + endloop + endfacet + facet normal 0.97957 -0.0050354 0.201041 + outer loop + vertex 0.787867 1.635 2.535 + vertex 0.787607 1.633 2.53621 + vertex 0.788186 1.63629 2.53348 + endloop + endfacet + facet normal -0.98424 0.0278391 -0.174633 + outer loop + vertex 0.788186 1.63629 2.53348 + vertex 0.787607 1.633 2.53621 + vertex 0.787778 1.63742 2.53596 + endloop + endfacet + facet normal -0.990872 0.045554 0.126876 + outer loop + vertex 0.787607 1.633 2.53621 + vertex 0.788089 1.6341 2.53958 + vertex 0.787778 1.63742 2.53596 + endloop + endfacet + facet normal -0.990281 0.0491359 0.13011 + outer loop + vertex 0.787778 1.63742 2.53596 + vertex 0.788089 1.6341 2.53958 + vertex 0.788285 1.63892 2.53925 + endloop + endfacet + facet normal -0.952152 0.0591836 0.299839 + outer loop + vertex 0.788089 1.6341 2.53958 + vertex 0.789259 1.63557 2.54301 + vertex 0.788285 1.63892 2.53925 + endloop + endfacet + facet normal -0.952389 0.0628984 0.298328 + outer loop + vertex 0.789045 1.63066 2.54336 + vertex 0.789259 1.63557 2.54301 + vertex 0.788089 1.6341 2.53958 + endloop + endfacet + facet normal -0.20718 0.0215001 -0.978067 + outer loop + vertex 0.79 1.64 2.53299 + vertex 0.788375 1.64076 2.53335 + vertex 0.79 1.645 2.5331 + endloop + endfacet + facet normal -0.224649 -0.0178644 -0.974276 + outer loop + vertex 0.788186 1.63629 2.53348 + vertex 0.788375 1.64076 2.53335 + vertex 0.79 1.64 2.53299 + endloop + endfacet + facet normal -0.983262 0.036648 -0.178474 + outer loop + vertex 0.788186 1.63629 2.53348 + vertex 0.787778 1.63742 2.53596 + vertex 0.788375 1.64076 2.53335 + endloop + endfacet + facet normal -0.984131 0.041448 -0.172537 + outer loop + vertex 0.788375 1.64076 2.53335 + vertex 0.787778 1.63742 2.53596 + vertex 0.788011 1.64233 2.53581 + endloop + endfacet + facet normal -0.990297 0.050952 0.129287 + outer loop + vertex 0.787778 1.63742 2.53596 + vertex 0.788285 1.63892 2.53925 + vertex 0.788011 1.64233 2.53581 + endloop + endfacet + facet normal -0.988772 0.059119 0.137244 + outer loop + vertex 0.788011 1.64233 2.53581 + vertex 0.788285 1.63892 2.53925 + vertex 0.788503 1.64347 2.53887 + endloop + endfacet + facet normal -0.947752 0.0719764 0.310783 + outer loop + vertex 0.788285 1.63892 2.53925 + vertex 0.789417 1.64035 2.54238 + vertex 0.788503 1.64347 2.53887 + endloop + endfacet + facet normal -0.947784 0.0724636 0.310572 + outer loop + vertex 0.789259 1.63557 2.54301 + vertex 0.789417 1.64035 2.54238 + vertex 0.788285 1.63892 2.53925 + endloop + endfacet + facet normal -0.138991 0.0218108 -0.990053 + outer loop + vertex 0.79 1.645 2.5331 + vertex 0.788555 1.64579 2.53332 + vertex 0.79 1.65 2.53321 + endloop + endfacet + facet normal -0.151024 -0.000612013 -0.98853 + outer loop + vertex 0.788375 1.64076 2.53335 + vertex 0.788555 1.64579 2.53332 + vertex 0.79 1.645 2.5331 + endloop + endfacet + facet normal -0.985201 0.0340767 -0.167982 + outer loop + vertex 0.788375 1.64076 2.53335 + vertex 0.788011 1.64233 2.53581 + vertex 0.788555 1.64579 2.53332 + endloop + endfacet + facet normal -0.988604 0.054483 -0.140335 + outer loop + vertex 0.788555 1.64579 2.53332 + vertex 0.788011 1.64233 2.53581 + vertex 0.788305 1.64767 2.53581 + endloop + endfacet + facet normal -0.945705 0.0848819 0.313746 + outer loop + vertex 0.788849 1.64682 2.539 + vertex 0.788503 1.64347 2.53887 + vertex 0.789405 1.64421 2.54138 + endloop + endfacet + facet normal -0.977134 0.0931187 0.191148 + outer loop + vertex 0.788849 1.64682 2.539 + vertex 0.788305 1.64767 2.53581 + vertex 0.788503 1.64347 2.53887 + endloop + endfacet + facet normal -0.988795 0.0545434 0.138961 + outer loop + vertex 0.788305 1.64767 2.53581 + vertex 0.788011 1.64233 2.53581 + vertex 0.788503 1.64347 2.53887 + endloop + endfacet + facet normal -0.945637 0.0781197 0.315703 + outer loop + vertex 0.789405 1.64421 2.54138 + vertex 0.788503 1.64347 2.53887 + vertex 0.789417 1.64035 2.54238 + endloop + endfacet + facet normal 0.0707453 0.0358878 -0.996849 + outer loop + vertex 0.79 1.65 2.53321 + vertex 0.788693 1.65105 2.53316 + vertex 0.79 1.655 2.53339 + endloop + endfacet + facet normal 0.0163547 -0.0317648 -0.999362 + outer loop + vertex 0.788555 1.64579 2.53332 + vertex 0.788693 1.65105 2.53316 + vertex 0.79 1.65 2.53321 + endloop + endfacet + facet normal -0.992921 0.022493 -0.116625 + outer loop + vertex 0.788555 1.64579 2.53332 + vertex 0.788305 1.64767 2.53581 + vertex 0.788693 1.65105 2.53316 + endloop + endfacet + facet normal -0.990486 0.00586053 -0.137487 + outer loop + vertex 0.788693 1.65105 2.53316 + vertex 0.788305 1.64767 2.53581 + vertex 0.788469 1.65297 2.53485 + endloop + endfacet + facet normal -0.976306 0.0672212 0.205689 + outer loop + vertex 0.788305 1.64767 2.53581 + vertex 0.788957 1.65056 2.53796 + vertex 0.788469 1.65297 2.53485 + endloop + endfacet + facet normal -0.978808 0.0808237 0.188153 + outer loop + vertex 0.788849 1.64682 2.539 + vertex 0.788957 1.65056 2.53796 + vertex 0.788305 1.64767 2.53581 + endloop + endfacet + facet normal 0.382818 0.0074004 -0.923794 + outer loop + vertex 0.79 1.655 2.53339 + vertex 0.788799 1.65664 2.53291 + vertex 0.79 1.66 2.53343 + endloop + endfacet + facet normal 0.316333 -0.0483408 -0.947416 + outer loop + vertex 0.788693 1.65105 2.53316 + vertex 0.788799 1.65664 2.53291 + vertex 0.79 1.655 2.53339 + endloop + endfacet + facet normal -0.975179 0.0675967 0.210849 + outer loop + vertex 0.788711 1.65644 2.53486 + vertex 0.788469 1.65297 2.53485 + vertex 0.789005 1.65428 2.53691 + endloop + endfacet + facet normal -0.996868 0.069708 -0.0373384 + outer loop + vertex 0.788711 1.65644 2.53486 + vertex 0.788799 1.65664 2.53291 + vertex 0.788469 1.65297 2.53485 + endloop + endfacet + facet normal -0.989434 0.012183 -0.144472 + outer loop + vertex 0.788799 1.65664 2.53291 + vertex 0.788693 1.65105 2.53316 + vertex 0.788469 1.65297 2.53485 + endloop + endfacet + facet normal -0.975403 0.0711793 0.208623 + outer loop + vertex 0.789005 1.65428 2.53691 + vertex 0.788469 1.65297 2.53485 + vertex 0.788957 1.65056 2.53796 + endloop + endfacet + facet normal 0.870468 -0.010841 -0.492106 + outer loop + vertex 0.79 1.66 2.53343 + vertex 0.788976 1.66279 2.53156 + vertex 0.79 1.665 2.53332 + endloop + endfacet + facet normal 0.742296 -0.163843 -0.649733 + outer loop + vertex 0.788799 1.65664 2.53291 + vertex 0.788976 1.66279 2.53156 + vertex 0.79 1.66 2.53343 + endloop + endfacet + facet normal -0.997939 0.0397522 0.050369 + outer loop + vertex 0.788799 1.65664 2.53291 + vertex 0.788993 1.65994 2.53414 + vertex 0.788976 1.66279 2.53156 + endloop + endfacet + facet normal -0.996684 0.0724413 -0.0370513 + outer loop + vertex 0.788711 1.65644 2.53486 + vertex 0.788993 1.65994 2.53414 + vertex 0.788799 1.65664 2.53291 + endloop + endfacet + facet normal 0.829161 -0.360612 -0.427142 + outer loop + vertex 0.79 1.66878 2.53 + vertex 0.789147 1.6675 2.52943 + vertex 0.79 1.67 2.52897 + endloop + endfacet + facet normal 0.83154 -0.366555 -0.417347 + outer loop + vertex 0.79 1.665 2.53332 + vertex 0.789147 1.6675 2.52943 + vertex 0.79 1.66878 2.53 + endloop + endfacet + facet normal 0.931248 -0.177718 -0.31811 + outer loop + vertex 0.79 1.665 2.53332 + vertex 0.788976 1.66279 2.53156 + vertex 0.789147 1.6675 2.52943 + endloop + endfacet + facet normal -0.998263 0.0100621 -0.0580569 + outer loop + vertex 0.788976 1.66279 2.53156 + vertex 0.789086 1.66878 2.5307 + vertex 0.789147 1.6675 2.52943 + endloop + endfacet + facet normal -0.989714 0.0378601 0.13796 + outer loop + vertex 0.788976 1.66279 2.53156 + vertex 0.789341 1.66518 2.53352 + vertex 0.789086 1.66878 2.5307 + endloop + endfacet + facet normal -0.992865 0.0768498 0.091181 + outer loop + vertex 0.788993 1.65994 2.53414 + vertex 0.789341 1.66518 2.53352 + vertex 0.788976 1.66279 2.53156 + endloop + endfacet + facet normal 0.470736 0.00883429 -0.88223 + outer loop + vertex 0.79 1.67 2.52897 + vertex 0.789221 1.67272 2.52858 + vertex 0.79 1.675 2.52902 + endloop + endfacet + facet normal -0.0626063 -0.158875 -0.985312 + outer loop + vertex 0.789147 1.6675 2.52943 + vertex 0.789221 1.67272 2.52858 + vertex 0.79 1.67 2.52897 + endloop + endfacet + facet normal -0.985121 0.113323 0.129207 + outer loop + vertex 0.79 1.675 2.53222 + vertex 0.789086 1.66878 2.5307 + vertex 0.79 1.67183 2.535 + endloop + endfacet + facet normal -0.983777 0.110087 0.141648 + outer loop + vertex 0.79 1.675 2.53222 + vertex 0.789221 1.67272 2.52858 + vertex 0.789086 1.66878 2.5307 + endloop + endfacet + facet normal -0.998557 0.00546139 -0.0534204 + outer loop + vertex 0.789221 1.67272 2.52858 + vertex 0.789147 1.6675 2.52943 + vertex 0.789086 1.66878 2.5307 + endloop + endfacet + facet normal -0.984194 0.0605382 0.166426 + outer loop + vertex 0.79 1.67183 2.535 + vertex 0.789086 1.66878 2.5307 + vertex 0.789341 1.66518 2.53352 + endloop + endfacet + facet normal 0.888285 0.0690055 -0.454079 + outer loop + vertex 0.79 1.675 2.52902 + vertex 0.789392 1.67675 2.5281 + vertex 0.79 1.68 2.52978 + endloop + endfacet + facet normal 0.71769 -0.112968 -0.687139 + outer loop + vertex 0.789221 1.67272 2.52858 + vertex 0.789392 1.67675 2.5281 + vertex 0.79 1.675 2.52902 + endloop + endfacet + facet normal -0.98232 0.0627729 0.17637 + outer loop + vertex 0.789221 1.67272 2.52858 + vertex 0.79 1.68 2.53033 + vertex 0.789392 1.67675 2.5281 + endloop + endfacet + facet normal -0.983299 0.0643492 0.170241 + outer loop + vertex 0.79 1.675 2.53222 + vertex 0.79 1.68 2.53033 + vertex 0.789221 1.67272 2.52858 + endloop + endfacet + facet normal 0.801796 0.149763 -0.578527 + outer loop + vertex 0.79 1.68 2.52978 + vertex 0.789392 1.67675 2.5281 + vertex 0.79 1.68085 2.53 + endloop + endfacet + facet normal -0.982992 0.0664547 0.171202 + outer loop + vertex 0.79 1.68085 2.53 + vertex 0.789392 1.67675 2.5281 + vertex 0.79 1.68 2.53033 + endloop + endfacet + facet normal 0.944873 -0.153346 -0.289308 + outer loop + vertex 0.795 1.294 2.53 + vertex 0.794705 1.29523 2.52839 + vertex 0.795 1.295 2.52947 + endloop + endfacet + facet normal 0.973737 0.227618 -0.00507825 + outer loop + vertex 0.795 1.294 2.53 + vertex 0.795189 1.29317 2.52911 + vertex 0.794705 1.29523 2.52839 + endloop + endfacet + facet normal 0.766981 -0.0409777 -0.64036 + outer loop + vertex 0.795 1.295 2.52947 + vertex 0.794667 1.29905 2.52881 + vertex 0.795 1.3 2.52915 + endloop + endfacet + facet normal 0.966163 0.0380415 -0.25511 + outer loop + vertex 0.794705 1.29523 2.52839 + vertex 0.794667 1.29905 2.52881 + vertex 0.795 1.295 2.52947 + endloop + endfacet + facet normal -0.767731 -0.0785478 0.63594 + outer loop + vertex 0.794705 1.29523 2.52839 + vertex 0.795607 1.29778 2.52979 + vertex 0.794667 1.29905 2.52881 + endloop + endfacet + facet normal -0.836856 -0.00541216 0.547396 + outer loop + vertex 0.795189 1.29317 2.52911 + vertex 0.795607 1.29778 2.52979 + vertex 0.794705 1.29523 2.52839 + endloop + endfacet + facet normal -0.316372 -0.00379967 -0.948628 + outer loop + vertex 0.795 1.3 2.52915 + vertex 0.794398 1.30403 2.52933 + vertex 0.795 1.305 2.52913 + endloop + endfacet + facet normal 0.522765 0.116622 -0.844462 + outer loop + vertex 0.794667 1.29905 2.52881 + vertex 0.794398 1.30403 2.52933 + vertex 0.795 1.3 2.52915 + endloop + endfacet + facet normal -0.988375 -0.0675303 0.136218 + outer loop + vertex 0.794667 1.29905 2.52881 + vertex 0.795 1.305 2.53418 + vertex 0.794398 1.30403 2.52933 + endloop + endfacet + facet normal -0.855225 -0.319833 0.407795 + outer loop + vertex 0.795607 1.29778 2.52979 + vertex 0.795 1.305 2.53418 + vertex 0.794667 1.29905 2.52881 + endloop + endfacet + facet normal 0.474233 -0.0788989 -0.876857 + outer loop + vertex 0.795 1.305 2.52913 + vertex 0.793972 1.3081 2.5283 + vertex 0.795 1.31 2.52868 + endloop + endfacet + facet normal 0.0586946 -0.2416 -0.968599 + outer loop + vertex 0.794398 1.30403 2.52933 + vertex 0.793972 1.3081 2.5283 + vertex 0.795 1.305 2.52913 + endloop + endfacet + facet normal -0.984282 -0.103729 0.142929 + outer loop + vertex 0.795 1.30613 2.535 + vertex 0.794398 1.30403 2.52933 + vertex 0.795 1.305 2.53418 + endloop + endfacet + facet normal -0.975994 -0.149042 0.158815 + outer loop + vertex 0.795 1.30613 2.535 + vertex 0.793817 1.3091 2.53052 + vertex 0.794398 1.30403 2.52933 + endloop + endfacet + facet normal -0.9938 -0.10937 -0.0200146 + outer loop + vertex 0.793817 1.3091 2.53052 + vertex 0.793972 1.3081 2.5283 + vertex 0.794398 1.30403 2.52933 + endloop + endfacet + facet normal 0.975896 0.151228 -0.157342 + outer loop + vertex 0.795 1.30613 2.535 + vertex 0.794545 1.3072 2.5332 + vertex 0.793817 1.3091 2.53052 + endloop + endfacet + facet normal -0.707883 0.00282907 -0.706324 + outer loop + vertex 0.795 1.31 2.52868 + vertex 0.793703 1.315 2.53 + vertex 0.795 1.315 2.5287 + endloop + endfacet + facet normal -0.0751798 0.23623 -0.968785 + outer loop + vertex 0.793972 1.3081 2.5283 + vertex 0.793703 1.315 2.53 + vertex 0.795 1.31 2.52868 + endloop + endfacet + facet normal -0.997975 -0.0243982 -0.0587377 + outer loop + vertex 0.793972 1.3081 2.5283 + vertex 0.793817 1.3091 2.53052 + vertex 0.793703 1.315 2.53 + endloop + endfacet + facet normal -0.911215 -0.0533353 -0.408463 + outer loop + vertex 0.793703 1.315 2.53 + vertex 0.793817 1.3091 2.53052 + vertex 0.793231 1.31504 2.53105 + endloop + endfacet + facet normal -0.991065 -0.105129 0.0820847 + outer loop + vertex 0.793817 1.3091 2.53052 + vertex 0.793888 1.3109 2.53368 + vertex 0.793231 1.31504 2.53105 + endloop + endfacet + facet normal -0.973318 -0.189334 0.129632 + outer loop + vertex 0.794545 1.3072 2.5332 + vertex 0.793888 1.3109 2.53368 + vertex 0.793817 1.3091 2.53052 + endloop + endfacet + facet normal -0.911782 -0.0277167 -0.409738 + outer loop + vertex 0.793703 1.315 2.53 + vertex 0.793231 1.31504 2.53105 + vertex 0.793551 1.32 2.53 + endloop + endfacet + facet normal -0.966867 0.0085299 -0.255137 + outer loop + vertex 0.793551 1.32 2.53 + vertex 0.793231 1.31504 2.53105 + vertex 0.79311 1.32044 2.53169 + endloop + endfacet + facet normal -0.994845 -0.0335824 0.0956892 + outer loop + vertex 0.793231 1.31504 2.53105 + vertex 0.793542 1.31586 2.53457 + vertex 0.79311 1.32044 2.53169 + endloop + endfacet + facet normal -0.990206 -0.0884808 0.108001 + outer loop + vertex 0.793888 1.3109 2.53368 + vertex 0.793542 1.31586 2.53457 + vertex 0.793231 1.31504 2.53105 + endloop + endfacet + facet normal -0.958799 0.0818715 -0.272033 + outer loop + vertex 0.793551 1.32 2.53 + vertex 0.79311 1.32044 2.53169 + vertex 0.793978 1.325 2.53 + endloop + endfacet + facet normal -0.67406 -0.139821 -0.725323 + outer loop + vertex 0.793978 1.325 2.53 + vertex 0.79311 1.32044 2.53169 + vertex 0.793111 1.32508 2.53079 + endloop + endfacet + facet normal -0.995683 -0.0416894 0.0829314 + outer loop + vertex 0.793435 1.31977 2.53526 + vertex 0.79311 1.32044 2.53169 + vertex 0.793542 1.31586 2.53457 + endloop + endfacet + facet normal -0.995805 -0.0364596 0.0839244 + outer loop + vertex 0.793435 1.31977 2.53526 + vertex 0.793188 1.32418 2.53423 + vertex 0.79311 1.32044 2.53169 + endloop + endfacet + facet normal -0.99971 0.00470919 0.023612 + outer loop + vertex 0.793188 1.32418 2.53423 + vertex 0.793111 1.32508 2.53079 + vertex 0.79311 1.32044 2.53169 + endloop + endfacet + facet normal -0.973655 -0.00179375 0.22802 + outer loop + vertex 0.793435 1.31977 2.53526 + vertex 0.793979 1.32172 2.53759 + vertex 0.793188 1.32418 2.53423 + endloop + endfacet + facet normal -0.674889 -0.0225349 -0.737575 + outer loop + vertex 0.793978 1.325 2.53 + vertex 0.793111 1.32508 2.53079 + vertex 0.793811 1.33 2.53 + endloop + endfacet + facet normal -0.960945 0.0949247 -0.25995 + outer loop + vertex 0.793811 1.33 2.53 + vertex 0.793111 1.32508 2.53079 + vertex 0.793041 1.32837 2.53225 + endloop + endfacet + facet normal -0.999496 -0.0279263 0.0150748 + outer loop + vertex 0.793111 1.32508 2.53079 + vertex 0.793188 1.32418 2.53423 + vertex 0.793041 1.32837 2.53225 + endloop + endfacet + facet normal -0.998574 -0.0102647 0.0523868 + outer loop + vertex 0.793041 1.32837 2.53225 + vertex 0.793188 1.32418 2.53423 + vertex 0.793198 1.3297 2.53552 + endloop + endfacet + facet normal -0.975985 -0.0474665 0.212602 + outer loop + vertex 0.793188 1.32418 2.53423 + vertex 0.794017 1.32587 2.53842 + vertex 0.793198 1.3297 2.53552 + endloop + endfacet + facet normal -0.977856 -0.0321765 0.20679 + outer loop + vertex 0.793979 1.32172 2.53759 + vertex 0.794017 1.32587 2.53842 + vertex 0.793188 1.32418 2.53423 + endloop + endfacet + facet normal -0.854721 0.266393 -0.445518 + outer loop + vertex 0.795 1.33301 2.53 + vertex 0.793014 1.335 2.535 + vertex 0.795 1.335 2.53119 + endloop + endfacet + facet normal -0.826637 0.326543 -0.458303 + outer loop + vertex 0.795 1.33301 2.53 + vertex 0.793811 1.33 2.53 + vertex 0.793014 1.335 2.535 + endloop + endfacet + facet normal -0.961527 0.101861 -0.255129 + outer loop + vertex 0.793811 1.33 2.53 + vertex 0.793041 1.32837 2.53225 + vertex 0.793014 1.335 2.535 + endloop + endfacet + facet normal -0.997786 -0.0288437 0.0599282 + outer loop + vertex 0.793041 1.32837 2.53225 + vertex 0.793198 1.3297 2.53552 + vertex 0.793014 1.335 2.535 + endloop + endfacet + facet normal -0.998991 -0.0316106 0.0318883 + outer loop + vertex 0.793014 1.335 2.535 + vertex 0.793198 1.3297 2.53552 + vertex 0.793055 1.33534 2.53662 + endloop + endfacet + facet normal -0.977676 -0.064062 0.200112 + outer loop + vertex 0.793198 1.3297 2.53552 + vertex 0.793915 1.33088 2.53939 + vertex 0.793055 1.33534 2.53662 + endloop + endfacet + facet normal -0.978333 -0.0585885 0.198576 + outer loop + vertex 0.794017 1.32587 2.53842 + vertex 0.793915 1.33088 2.53939 + vertex 0.793198 1.3297 2.53552 + endloop + endfacet + facet normal -0.999247 -0.0241813 0.0303407 + outer loop + vertex 0.793014 1.335 2.535 + vertex 0.793055 1.33534 2.53662 + vertex 0.792893 1.34 2.535 + endloop + endfacet + facet normal -0.955016 -0.126468 -0.268235 + outer loop + vertex 0.792893 1.34 2.535 + vertex 0.793055 1.33534 2.53662 + vertex 0.792648 1.34017 2.53579 + endloop + endfacet + facet normal -0.980781 -0.0778323 0.178915 + outer loop + vertex 0.793754 1.33484 2.54024 + vertex 0.793055 1.33534 2.53662 + vertex 0.793915 1.33088 2.53939 + endloop + endfacet + facet normal -0.980538 -0.0822787 0.178254 + outer loop + vertex 0.793754 1.33484 2.54024 + vertex 0.793193 1.33923 2.53918 + vertex 0.793055 1.33534 2.53662 + endloop + endfacet + facet normal -0.987999 -0.0587607 0.142844 + outer loop + vertex 0.793193 1.33923 2.53918 + vertex 0.792648 1.34017 2.53579 + vertex 0.793055 1.33534 2.53662 + endloop + endfacet + facet normal -0.958913 -0.055489 0.278221 + outer loop + vertex 0.793754 1.33484 2.54024 + vertex 0.794281 1.33689 2.54246 + vertex 0.793193 1.33923 2.53918 + endloop + endfacet + facet normal -0.955673 -0.00401017 -0.294402 + outer loop + vertex 0.792893 1.34 2.535 + vertex 0.792648 1.34017 2.53579 + vertex 0.792872 1.345 2.535 + endloop + endfacet + facet normal -0.964062 0.00109156 -0.265676 + outer loop + vertex 0.792872 1.345 2.535 + vertex 0.792648 1.34017 2.53579 + vertex 0.792468 1.34412 2.53646 + endloop + endfacet + facet normal -0.987751 -0.0688572 0.14002 + outer loop + vertex 0.792648 1.34017 2.53579 + vertex 0.793193 1.33923 2.53918 + vertex 0.792468 1.34412 2.53646 + endloop + endfacet + facet normal -0.985139 -0.0560729 0.162346 + outer loop + vertex 0.792468 1.34412 2.53646 + vertex 0.793193 1.33923 2.53918 + vertex 0.793018 1.34458 2.53996 + endloop + endfacet + facet normal -0.955584 -0.0731686 0.285493 + outer loop + vertex 0.793193 1.33923 2.53918 + vertex 0.794231 1.34094 2.54309 + vertex 0.793018 1.34458 2.53996 + endloop + endfacet + facet normal -0.958861 -0.0551099 0.278475 + outer loop + vertex 0.794281 1.33689 2.54246 + vertex 0.794231 1.34094 2.54309 + vertex 0.793193 1.33923 2.53918 + endloop + endfacet + facet normal -0.956446 -0.0413199 -0.28897 + outer loop + vertex 0.792872 1.345 2.535 + vertex 0.792468 1.34412 2.53646 + vertex 0.792656 1.35 2.535 + endloop + endfacet + facet normal -0.955603 -0.042014 -0.291648 + outer loop + vertex 0.792656 1.35 2.535 + vertex 0.792468 1.34412 2.53646 + vertex 0.792138 1.34905 2.53683 + endloop + endfacet + facet normal -0.983199 -0.0782136 0.164933 + outer loop + vertex 0.792468 1.34412 2.53646 + vertex 0.793018 1.34458 2.53996 + vertex 0.792138 1.34905 2.53683 + endloop + endfacet + facet normal -0.980069 -0.0606308 0.18918 + outer loop + vertex 0.792138 1.34905 2.53683 + vertex 0.793018 1.34458 2.53996 + vertex 0.792806 1.34964 2.54049 + endloop + endfacet + facet normal -0.95219 -0.0706684 0.297222 + outer loop + vertex 0.793018 1.34458 2.53996 + vertex 0.794099 1.34597 2.54376 + vertex 0.792806 1.34964 2.54049 + endloop + endfacet + facet normal -0.9533 -0.0641156 0.295142 + outer loop + vertex 0.794231 1.34094 2.54309 + vertex 0.794099 1.34597 2.54376 + vertex 0.793018 1.34458 2.53996 + endloop + endfacet + facet normal -0.930103 -0.144728 -0.337584 + outer loop + vertex 0.792656 1.35 2.535 + vertex 0.792138 1.34905 2.53683 + vertex 0.791878 1.355 2.535 + endloop + endfacet + facet normal -0.990744 -0.0776075 -0.111373 + outer loop + vertex 0.791878 1.355 2.535 + vertex 0.792138 1.34905 2.53683 + vertex 0.791732 1.35383 2.53712 + endloop + endfacet + facet normal -0.976465 -0.0943521 0.193944 + outer loop + vertex 0.792138 1.34905 2.53683 + vertex 0.792806 1.34964 2.54049 + vertex 0.791732 1.35383 2.53712 + endloop + endfacet + facet normal -0.972012 -0.068441 0.22474 + outer loop + vertex 0.791732 1.35383 2.53712 + vertex 0.792806 1.34964 2.54049 + vertex 0.792602 1.35469 2.54114 + endloop + endfacet + facet normal -0.95122 -0.077204 0.298696 + outer loop + vertex 0.792806 1.34964 2.54049 + vertex 0.793941 1.35088 2.54442 + vertex 0.792602 1.35469 2.54114 + endloop + endfacet + facet normal -0.952242 -0.0708826 0.297002 + outer loop + vertex 0.794099 1.34597 2.54376 + vertex 0.793941 1.35088 2.54442 + vertex 0.792806 1.34964 2.54049 + endloop + endfacet + facet normal -0.971252 -0.173465 -0.163031 + outer loop + vertex 0.791878 1.355 2.535 + vertex 0.791732 1.35383 2.53712 + vertex 0.790985 1.36 2.535 + endloop + endfacet + facet normal -0.992561 -0.0933176 0.0781952 + outer loop + vertex 0.790985 1.36 2.535 + vertex 0.791732 1.35383 2.53712 + vertex 0.79142 1.35744 2.53747 + endloop + endfacet + facet normal -0.967 -0.10601 0.231675 + outer loop + vertex 0.791732 1.35383 2.53712 + vertex 0.792602 1.35469 2.54114 + vertex 0.79142 1.35744 2.53747 + endloop + endfacet + facet normal -0.965877 -0.0911398 0.242438 + outer loop + vertex 0.79142 1.35744 2.53747 + vertex 0.792602 1.35469 2.54114 + vertex 0.791865 1.35894 2.5398 + endloop + endfacet + facet normal -0.951478 -0.0782288 0.297608 + outer loop + vertex 0.793832 1.35476 2.54509 + vertex 0.792602 1.35469 2.54114 + vertex 0.793941 1.35088 2.54442 + endloop + endfacet + facet normal -0.951174 -0.081937 0.297581 + outer loop + vertex 0.793832 1.35476 2.54509 + vertex 0.793105 1.35889 2.54391 + vertex 0.792602 1.35469 2.54114 + endloop + endfacet + facet normal -0.95481 -0.0749431 0.287614 + outer loop + vertex 0.793105 1.35889 2.54391 + vertex 0.791865 1.35894 2.5398 + vertex 0.792602 1.35469 2.54114 + endloop + endfacet + facet normal -0.934127 -0.0635227 0.351244 + outer loop + vertex 0.793832 1.35476 2.54509 + vertex 0.794512 1.357 2.54731 + vertex 0.793105 1.35889 2.54391 + endloop + endfacet + facet normal 0.922414 0.253078 -0.291727 + outer loop + vertex 0.789884 1.36277 2.53392 + vertex 0.79 1.36359 2.535 + vertex 0.790985 1.36 2.535 + endloop + endfacet + facet normal -0.933266 -0.28709 0.215857 + outer loop + vertex 0.789884 1.36277 2.53392 + vertex 0.790985 1.36 2.535 + vertex 0.790705 1.36203 2.53649 + endloop + endfacet + facet normal -0.988508 -0.150018 0.0186291 + outer loop + vertex 0.790705 1.36203 2.53649 + vertex 0.790985 1.36 2.535 + vertex 0.79142 1.35744 2.53747 + endloop + endfacet + facet normal -0.964204 -0.0978802 0.246435 + outer loop + vertex 0.79142 1.35744 2.53747 + vertex 0.791865 1.35894 2.5398 + vertex 0.790705 1.36203 2.53649 + endloop + endfacet + facet normal -0.961272 -0.077499 0.264481 + outer loop + vertex 0.790705 1.36203 2.53649 + vertex 0.791865 1.35894 2.5398 + vertex 0.791719 1.36323 2.54053 + endloop + endfacet + facet normal -0.954364 -0.0811443 0.287411 + outer loop + vertex 0.791865 1.35894 2.5398 + vertex 0.793105 1.35889 2.54391 + vertex 0.791719 1.36323 2.54053 + endloop + endfacet + facet normal -0.952379 -0.0739809 0.295806 + outer loop + vertex 0.791719 1.36323 2.54053 + vertex 0.793105 1.35889 2.54391 + vertex 0.792947 1.36427 2.54474 + endloop + endfacet + facet normal -0.93141 -0.0824788 0.354504 + outer loop + vertex 0.793105 1.35889 2.54391 + vertex 0.794479 1.36113 2.54804 + vertex 0.792947 1.36427 2.54474 + endloop + endfacet + facet normal -0.934796 -0.0691449 0.348391 + outer loop + vertex 0.794512 1.357 2.54731 + vertex 0.794479 1.36113 2.54804 + vertex 0.793105 1.35889 2.54391 + endloop + endfacet + facet normal -0.955979 -0.0920023 0.278639 + outer loop + vertex 0.78973 1.3667 2.53469 + vertex 0.789884 1.36277 2.53392 + vertex 0.790705 1.36203 2.53649 + endloop + endfacet + facet normal -0.951883 -0.0850649 0.294419 + outer loop + vertex 0.790542 1.36836 2.53779 + vertex 0.78973 1.3667 2.53469 + vertex 0.790705 1.36203 2.53649 + endloop + endfacet + facet normal -0.961009 -0.0792231 0.264927 + outer loop + vertex 0.790705 1.36203 2.53649 + vertex 0.791719 1.36323 2.54053 + vertex 0.790542 1.36836 2.53779 + endloop + endfacet + facet normal -0.957831 -0.0713381 0.278335 + outer loop + vertex 0.790542 1.36836 2.53779 + vertex 0.791719 1.36323 2.54053 + vertex 0.791547 1.3688 2.54137 + endloop + endfacet + facet normal -0.952405 -0.0737943 0.295767 + outer loop + vertex 0.791719 1.36323 2.54053 + vertex 0.792947 1.36427 2.54474 + vertex 0.791547 1.3688 2.54137 + endloop + endfacet + facet normal -0.95303 -0.0758876 0.293215 + outer loop + vertex 0.791547 1.3688 2.54137 + vertex 0.792947 1.36427 2.54474 + vertex 0.792748 1.36943 2.54543 + endloop + endfacet + facet normal -0.932611 -0.0828665 0.351241 + outer loop + vertex 0.792947 1.36427 2.54474 + vertex 0.794274 1.36608 2.54869 + vertex 0.792748 1.36943 2.54543 + endloop + endfacet + facet normal -0.932051 -0.0852628 0.352151 + outer loop + vertex 0.794479 1.36113 2.54804 + vertex 0.794274 1.36608 2.54869 + vertex 0.792947 1.36427 2.54474 + endloop + endfacet + facet normal -0.957284 -0.0605127 0.282747 + outer loop + vertex 0.79 1.375 2.53738 + vertex 0.78973 1.3667 2.53469 + vertex 0.790542 1.36836 2.53779 + endloop + endfacet + facet normal -0.933488 -0.0540906 0.354507 + outer loop + vertex 0.790995 1.375 2.54 + vertex 0.79 1.375 2.53738 + vertex 0.790542 1.36836 2.53779 + endloop + endfacet + facet normal -0.961496 -0.0253358 0.273649 + outer loop + vertex 0.790542 1.36836 2.53779 + vertex 0.791547 1.3688 2.54137 + vertex 0.790995 1.375 2.54 + endloop + endfacet + facet normal -0.98834 -0.0569368 0.141218 + outer loop + vertex 0.790995 1.375 2.54 + vertex 0.791547 1.3688 2.54137 + vertex 0.791352 1.37386 2.54204 + endloop + endfacet + facet normal -0.95305 -0.0757178 0.293195 + outer loop + vertex 0.791547 1.3688 2.54137 + vertex 0.792748 1.36943 2.54543 + vertex 0.791352 1.37386 2.54204 + endloop + endfacet + facet normal -0.952563 -0.0740225 0.295202 + outer loop + vertex 0.791352 1.37386 2.54204 + vertex 0.792748 1.36943 2.54543 + vertex 0.792598 1.37471 2.54627 + endloop + endfacet + facet normal -0.93248 -0.0824301 0.351691 + outer loop + vertex 0.792748 1.36943 2.54543 + vertex 0.794096 1.37086 2.54934 + vertex 0.792598 1.37471 2.54627 + endloop + endfacet + facet normal -0.932489 -0.0823859 0.351678 + outer loop + vertex 0.794274 1.36608 2.54869 + vertex 0.794096 1.37086 2.54934 + vertex 0.792748 1.36943 2.54543 + endloop + endfacet + facet normal -0.987002 -0.12219 0.104389 + outer loop + vertex 0.790995 1.375 2.54 + vertex 0.791352 1.37386 2.54204 + vertex 0.790376 1.38 2.54 + endloop + endfacet + facet normal -0.971985 -0.0812803 0.22054 + outer loop + vertex 0.790376 1.38 2.54 + vertex 0.791352 1.37386 2.54204 + vertex 0.791168 1.37749 2.54256 + endloop + endfacet + facet normal -0.950176 -0.0914024 0.298013 + outer loop + vertex 0.791352 1.37386 2.54204 + vertex 0.792598 1.37471 2.54627 + vertex 0.791168 1.37749 2.54256 + endloop + endfacet + facet normal -0.949543 -0.0864142 0.301497 + outer loop + vertex 0.791168 1.37749 2.54256 + vertex 0.792598 1.37471 2.54627 + vertex 0.791788 1.37916 2.545 + endloop + endfacet + facet normal -0.930407 -0.0761889 0.358522 + outer loop + vertex 0.79406 1.37484 2.55009 + vertex 0.792598 1.37471 2.54627 + vertex 0.794096 1.37086 2.54934 + endloop + endfacet + facet normal -0.930544 -0.0745127 0.358519 + outer loop + vertex 0.79406 1.37484 2.55009 + vertex 0.793253 1.37924 2.54891 + vertex 0.792598 1.37471 2.54627 + endloop + endfacet + facet normal -0.933927 -0.069433 0.350655 + outer loop + vertex 0.793253 1.37924 2.54891 + vertex 0.791788 1.37916 2.545 + vertex 0.792598 1.37471 2.54627 + endloop + endfacet + facet normal -0.901612 -0.0500937 0.429635 + outer loop + vertex 0.79406 1.37484 2.55009 + vertex 0.794865 1.37723 2.55206 + vertex 0.793253 1.37924 2.54891 + endloop + endfacet + facet normal 0.955365 0.184205 -0.230967 + outer loop + vertex 0.789544 1.38201 2.53816 + vertex 0.79 1.38195 2.54 + vertex 0.790376 1.38 2.54 + endloop + endfacet + facet normal -0.952772 -0.156341 0.260352 + outer loop + vertex 0.789544 1.38201 2.53816 + vertex 0.790376 1.38 2.54 + vertex 0.790434 1.38191 2.54136 + endloop + endfacet + facet normal -0.974857 -0.108736 0.194502 + outer loop + vertex 0.790434 1.38191 2.54136 + vertex 0.790376 1.38 2.54 + vertex 0.791168 1.37749 2.54256 + endloop + endfacet + facet normal -0.952076 -0.0773532 0.295918 + outer loop + vertex 0.791168 1.37749 2.54256 + vertex 0.791788 1.37916 2.545 + vertex 0.790434 1.38191 2.54136 + endloop + endfacet + facet normal -0.950522 -0.0666778 0.303416 + outer loop + vertex 0.790434 1.38191 2.54136 + vertex 0.791788 1.37916 2.545 + vertex 0.791676 1.38338 2.54557 + endloop + endfacet + facet normal -0.93369 -0.0726736 0.35063 + outer loop + vertex 0.791788 1.37916 2.545 + vertex 0.793253 1.37924 2.54891 + vertex 0.791676 1.38338 2.54557 + endloop + endfacet + facet normal -0.929308 -0.0599079 0.364415 + outer loop + vertex 0.791676 1.38338 2.54557 + vertex 0.793253 1.37924 2.54891 + vertex 0.793094 1.38469 2.5494 + endloop + endfacet + facet normal -0.897105 -0.0655141 0.436932 + outer loop + vertex 0.793253 1.37924 2.54891 + vertex 0.794836 1.38149 2.5525 + vertex 0.793094 1.38469 2.5494 + endloop + endfacet + facet normal -0.901678 -0.0504221 0.429459 + outer loop + vertex 0.794865 1.37723 2.55206 + vertex 0.794836 1.38149 2.5525 + vertex 0.793253 1.37924 2.54891 + endloop + endfacet + facet normal -0.961611 -0.0684121 0.265751 + outer loop + vertex 0.789284 1.38591 2.53823 + vertex 0.789544 1.38201 2.53816 + vertex 0.790434 1.38191 2.54136 + endloop + endfacet + facet normal -0.96299 -0.0739461 0.259196 + outer loop + vertex 0.790217 1.38722 2.54207 + vertex 0.789284 1.38591 2.53823 + vertex 0.790434 1.38191 2.54136 + endloop + endfacet + facet normal -0.948255 -0.0797587 0.307329 + outer loop + vertex 0.790434 1.38191 2.54136 + vertex 0.791676 1.38338 2.54557 + vertex 0.790217 1.38722 2.54207 + endloop + endfacet + facet normal -0.945088 -0.0670961 0.319854 + outer loop + vertex 0.790217 1.38722 2.54207 + vertex 0.791676 1.38338 2.54557 + vertex 0.791461 1.38838 2.54599 + endloop + endfacet + facet normal -0.927454 -0.0702691 0.367275 + outer loop + vertex 0.791676 1.38338 2.54557 + vertex 0.793094 1.38469 2.5494 + vertex 0.791461 1.38838 2.54599 + endloop + endfacet + facet normal -0.923811 -0.0583578 0.378375 + outer loop + vertex 0.791461 1.38838 2.54599 + vertex 0.793094 1.38469 2.5494 + vertex 0.792867 1.38971 2.54962 + endloop + endfacet + facet normal -0.893784 -0.059871 0.444483 + outer loop + vertex 0.793094 1.38469 2.5494 + vertex 0.794666 1.38656 2.55282 + vertex 0.792867 1.38971 2.54962 + endloop + endfacet + facet normal -0.894395 -0.0576483 0.443547 + outer loop + vertex 0.794836 1.38149 2.5525 + vertex 0.794666 1.38656 2.55282 + vertex 0.793094 1.38469 2.5494 + endloop + endfacet + facet normal -0.963776 -0.0688879 0.257663 + outer loop + vertex 0.789043 1.39111 2.53872 + vertex 0.789284 1.38591 2.53823 + vertex 0.790217 1.38722 2.54207 + endloop + endfacet + facet normal -0.9636 -0.0680867 0.258532 + outer loop + vertex 0.789978 1.39217 2.54248 + vertex 0.789043 1.39111 2.53872 + vertex 0.790217 1.38722 2.54207 + endloop + endfacet + facet normal -0.944252 -0.0723991 0.321165 + outer loop + vertex 0.790217 1.38722 2.54207 + vertex 0.791461 1.38838 2.54599 + vertex 0.789978 1.39217 2.54248 + endloop + endfacet + facet normal -0.941734 -0.0628588 0.330432 + outer loop + vertex 0.789978 1.39217 2.54248 + vertex 0.791461 1.38838 2.54599 + vertex 0.791219 1.39323 2.54622 + endloop + endfacet + facet normal -0.922701 -0.0642904 0.380117 + outer loop + vertex 0.791461 1.38838 2.54599 + vertex 0.792867 1.38971 2.54962 + vertex 0.791219 1.39323 2.54622 + endloop + endfacet + facet normal -0.920348 -0.0565493 0.386991 + outer loop + vertex 0.791219 1.39323 2.54622 + vertex 0.792867 1.38971 2.54962 + vertex 0.792631 1.39459 2.54978 + endloop + endfacet + facet normal -0.893281 -0.0570993 0.445857 + outer loop + vertex 0.792867 1.38971 2.54962 + vertex 0.79443 1.39154 2.55299 + vertex 0.792631 1.39459 2.54978 + endloop + endfacet + facet normal -0.893093 -0.057788 0.446145 + outer loop + vertex 0.794666 1.38656 2.55282 + vertex 0.79443 1.39154 2.55299 + vertex 0.792867 1.38971 2.54962 + endloop + endfacet + facet normal -0.963369 -0.0697586 0.258948 + outer loop + vertex 0.788796 1.39592 2.53909 + vertex 0.789043 1.39111 2.53872 + vertex 0.789978 1.39217 2.54248 + endloop + endfacet + facet normal -0.962841 -0.0672196 0.26157 + outer loop + vertex 0.789749 1.39697 2.54287 + vertex 0.788796 1.39592 2.53909 + vertex 0.789978 1.39217 2.54248 + endloop + endfacet + facet normal -0.940346 -0.0719057 0.332535 + outer loop + vertex 0.789978 1.39217 2.54248 + vertex 0.791219 1.39323 2.54622 + vertex 0.789749 1.39697 2.54287 + endloop + endfacet + facet normal -0.938228 -0.0644057 0.339972 + outer loop + vertex 0.789749 1.39697 2.54287 + vertex 0.791219 1.39323 2.54622 + vertex 0.791022 1.39798 2.54658 + endloop + endfacet + facet normal -0.918229 -0.0673653 0.390278 + outer loop + vertex 0.791219 1.39323 2.54622 + vertex 0.792631 1.39459 2.54978 + vertex 0.791022 1.39798 2.54658 + endloop + endfacet + facet normal -0.915627 -0.0591586 0.397654 + outer loop + vertex 0.791022 1.39798 2.54658 + vertex 0.792631 1.39459 2.54978 + vertex 0.79243 1.39934 2.55002 + endloop + endfacet + facet normal -0.890262 -0.0608206 0.451369 + outer loop + vertex 0.792631 1.39459 2.54978 + vertex 0.794206 1.39648 2.55314 + vertex 0.79243 1.39934 2.55002 + endloop + endfacet + facet normal -0.892227 -0.0538292 0.448368 + outer loop + vertex 0.79443 1.39154 2.55299 + vertex 0.794206 1.39648 2.55314 + vertex 0.792631 1.39459 2.54978 + endloop + endfacet + facet normal -0.962846 -0.0671824 0.261561 + outer loop + vertex 0.788607 1.40065 2.53961 + vertex 0.788796 1.39592 2.53909 + vertex 0.789749 1.39697 2.54287 + endloop + endfacet + facet normal -0.962743 -0.0667058 0.262063 + outer loop + vertex 0.789585 1.40219 2.5436 + vertex 0.788607 1.40065 2.53961 + vertex 0.789749 1.39697 2.54287 + endloop + endfacet + facet normal -0.936256 -0.0770947 0.342755 + outer loop + vertex 0.789749 1.39697 2.54287 + vertex 0.791022 1.39798 2.54658 + vertex 0.789585 1.40219 2.5436 + endloop + endfacet + facet normal -0.931594 -0.0649647 0.357649 + outer loop + vertex 0.789585 1.40219 2.5436 + vertex 0.791022 1.39798 2.54658 + vertex 0.79101 1.40203 2.54728 + endloop + endfacet + facet normal -0.912843 -0.072571 0.401811 + outer loop + vertex 0.791022 1.39798 2.54658 + vertex 0.79243 1.39934 2.55002 + vertex 0.79101 1.40203 2.54728 + endloop + endfacet + facet normal -0.909445 -0.0611051 0.411311 + outer loop + vertex 0.79101 1.40203 2.54728 + vertex 0.79243 1.39934 2.55002 + vertex 0.792156 1.40413 2.55013 + endloop + endfacet + facet normal -0.886323 -0.0608498 0.459052 + outer loop + vertex 0.79243 1.39934 2.55002 + vertex 0.794003 1.4014 2.55333 + vertex 0.792156 1.40413 2.55013 + endloop + endfacet + facet normal -0.888289 -0.0545046 0.45604 + outer loop + vertex 0.794206 1.39648 2.55314 + vertex 0.794003 1.4014 2.55333 + vertex 0.79243 1.39934 2.55002 + endloop + endfacet + facet normal -0.960884 -0.077666 0.265839 + outer loop + vertex 0.788607 1.40065 2.53961 + vertex 0.789585 1.40219 2.5436 + vertex 0.788455 1.40469 2.54024 + endloop + endfacet + facet normal -0.96151 -0.0833338 0.26183 + outer loop + vertex 0.788899 1.40672 2.54252 + vertex 0.788455 1.40469 2.54024 + vertex 0.789585 1.40219 2.5436 + endloop + endfacet + facet normal -0.939127 -0.0618601 0.337955 + outer loop + vertex 0.788899 1.40672 2.54252 + vertex 0.789585 1.40219 2.5436 + vertex 0.790257 1.40677 2.5463 + endloop + endfacet + facet normal -0.931121 -0.0743112 0.357059 + outer loop + vertex 0.790257 1.40677 2.5463 + vertex 0.789585 1.40219 2.5436 + vertex 0.79101 1.40203 2.54728 + endloop + endfacet + facet normal -0.909852 -0.0598999 0.410587 + outer loop + vertex 0.79101 1.40203 2.54728 + vertex 0.792156 1.40413 2.55013 + vertex 0.790257 1.40677 2.5463 + endloop + endfacet + facet normal -0.910406 -0.0626809 0.408939 + outer loop + vertex 0.790257 1.40677 2.5463 + vertex 0.792156 1.40413 2.55013 + vertex 0.791878 1.40918 2.55028 + endloop + endfacet + facet normal -0.882362 -0.0629143 0.466347 + outer loop + vertex 0.792156 1.40413 2.55013 + vertex 0.793822 1.40642 2.55359 + vertex 0.791878 1.40918 2.55028 + endloop + endfacet + facet normal -0.884792 -0.0555763 0.462661 + outer loop + vertex 0.794003 1.4014 2.55333 + vertex 0.793822 1.40642 2.55359 + vertex 0.792156 1.40413 2.55013 + endloop + endfacet + facet normal -0.939724 -0.0514639 0.33804 + outer loop + vertex 0.788902 1.41092 2.54317 + vertex 0.788899 1.40672 2.54252 + vertex 0.790257 1.40677 2.5463 + endloop + endfacet + facet normal -0.941878 -0.0574858 0.331001 + outer loop + vertex 0.790162 1.41243 2.54701 + vertex 0.788902 1.41092 2.54317 + vertex 0.790257 1.40677 2.5463 + endloop + endfacet + facet normal -0.909141 -0.0670243 0.411059 + outer loop + vertex 0.790257 1.40677 2.5463 + vertex 0.791878 1.40918 2.55028 + vertex 0.790162 1.41243 2.54701 + endloop + endfacet + facet normal -0.907015 -0.060137 0.416782 + outer loop + vertex 0.790162 1.41243 2.54701 + vertex 0.791878 1.40918 2.55028 + vertex 0.791742 1.41433 2.55073 + endloop + endfacet + facet normal -0.881553 -0.0638796 0.467743 + outer loop + vertex 0.791878 1.40918 2.55028 + vertex 0.793581 1.41136 2.55379 + vertex 0.791742 1.41433 2.55073 + endloop + endfacet + facet normal -0.882125 -0.0620808 0.466906 + outer loop + vertex 0.793822 1.40642 2.55359 + vertex 0.793581 1.41136 2.55379 + vertex 0.791878 1.40918 2.55028 + endloop + endfacet + facet normal -0.944577 -0.0416018 0.325642 + outer loop + vertex 0.788871 1.4159 2.54371 + vertex 0.788902 1.41092 2.54317 + vertex 0.790162 1.41243 2.54701 + endloop + endfacet + facet normal -0.945386 -0.0445124 0.3229 + outer loop + vertex 0.790085 1.41759 2.5475 + vertex 0.788871 1.4159 2.54371 + vertex 0.790162 1.41243 2.54701 + endloop + endfacet + facet normal -0.908906 -0.0525028 0.413682 + outer loop + vertex 0.790162 1.41243 2.54701 + vertex 0.791742 1.41433 2.55073 + vertex 0.790085 1.41759 2.5475 + endloop + endfacet + facet normal -0.907682 -0.0487763 0.416814 + outer loop + vertex 0.790085 1.41759 2.5475 + vertex 0.791742 1.41433 2.55073 + vertex 0.791745 1.41973 2.55137 + endloop + endfacet + facet normal -0.880292 -0.0552172 0.471208 + outer loop + vertex 0.791742 1.41433 2.55073 + vertex 0.793476 1.41606 2.55417 + vertex 0.791745 1.41973 2.55137 + endloop + endfacet + facet normal -0.879558 -0.0580105 0.472242 + outer loop + vertex 0.793581 1.41136 2.55379 + vertex 0.793476 1.41606 2.55417 + vertex 0.791742 1.41433 2.55073 + endloop + endfacet + facet normal -0.947761 -0.0306873 0.317501 + outer loop + vertex 0.788827 1.42084 2.54406 + vertex 0.788871 1.4159 2.54371 + vertex 0.790085 1.41759 2.5475 + endloop + endfacet + facet normal -0.950943 -0.0438124 0.306248 + outer loop + vertex 0.789944 1.42251 2.54777 + vertex 0.788827 1.42084 2.54406 + vertex 0.790085 1.41759 2.5475 + endloop + endfacet + facet normal -0.907736 -0.048566 0.416721 + outer loop + vertex 0.790085 1.41759 2.5475 + vertex 0.791745 1.41973 2.55137 + vertex 0.789944 1.42251 2.54777 + endloop + endfacet + facet normal -0.91144 -0.064412 0.40636 + outer loop + vertex 0.789944 1.42251 2.54777 + vertex 0.791745 1.41973 2.55137 + vertex 0.791088 1.42415 2.55059 + endloop + endfacet + facet normal -0.877361 -0.0491863 0.477303 + outer loop + vertex 0.793584 1.41994 2.55477 + vertex 0.791745 1.41973 2.55137 + vertex 0.793476 1.41606 2.55417 + endloop + endfacet + facet normal -0.877082 -0.0531626 0.477389 + outer loop + vertex 0.793584 1.41994 2.55477 + vertex 0.792815 1.42407 2.55382 + vertex 0.791745 1.41973 2.55137 + endloop + endfacet + facet normal -0.88087 -0.0485417 0.470864 + outer loop + vertex 0.792815 1.42407 2.55382 + vertex 0.791088 1.42415 2.55059 + vertex 0.791745 1.41973 2.55137 + endloop + endfacet + facet normal -0.85298 -0.038747 0.520503 + outer loop + vertex 0.793584 1.41994 2.55477 + vertex 0.794648 1.42222 2.55668 + vertex 0.792815 1.42407 2.55382 + endloop + endfacet + facet normal -0.950821 -0.0445142 0.306527 + outer loop + vertex 0.788756 1.42569 2.54454 + vertex 0.788827 1.42084 2.54406 + vertex 0.789944 1.42251 2.54777 + endloop + endfacet + facet normal -0.950819 -0.0445068 0.306533 + outer loop + vertex 0.789895 1.42743 2.54833 + vertex 0.788756 1.42569 2.54454 + vertex 0.789944 1.42251 2.54777 + endloop + endfacet + facet normal -0.914 -0.0550431 0.401962 + outer loop + vertex 0.789944 1.42251 2.54777 + vertex 0.791088 1.42415 2.55059 + vertex 0.789895 1.42743 2.54833 + endloop + endfacet + facet normal -0.906448 -0.0395639 0.42046 + outer loop + vertex 0.789895 1.42743 2.54833 + vertex 0.791088 1.42415 2.55059 + vertex 0.791421 1.42728 2.55161 + endloop + endfacet + facet normal -0.880498 -0.0585167 0.470424 + outer loop + vertex 0.791088 1.42415 2.55059 + vertex 0.792815 1.42407 2.55382 + vertex 0.791421 1.42728 2.55161 + endloop + endfacet + facet normal -0.873801 -0.0461993 0.484083 + outer loop + vertex 0.791421 1.42728 2.55161 + vertex 0.792815 1.42407 2.55382 + vertex 0.792804 1.42918 2.55428 + endloop + endfacet + facet normal -0.847177 -0.0502386 0.52893 + outer loop + vertex 0.792815 1.42407 2.55382 + vertex 0.794739 1.42642 2.55712 + vertex 0.792804 1.42918 2.55428 + endloop + endfacet + facet normal -0.852297 -0.0360334 0.521816 + outer loop + vertex 0.794648 1.42222 2.55668 + vertex 0.794739 1.42642 2.55712 + vertex 0.792815 1.42407 2.55382 + endloop + endfacet + facet normal -0.946014 -0.0694847 0.316591 + outer loop + vertex 0.788756 1.42569 2.54454 + vertex 0.789895 1.42743 2.54833 + vertex 0.788685 1.42959 2.54519 + endloop + endfacet + facet normal -0.945601 -0.0665393 0.318452 + outer loop + vertex 0.789282 1.43158 2.54738 + vertex 0.788685 1.42959 2.54519 + vertex 0.789895 1.42743 2.54833 + endloop + endfacet + facet normal -0.913205 -0.0418454 0.405347 + outer loop + vertex 0.789282 1.43158 2.54738 + vertex 0.789895 1.42743 2.54833 + vertex 0.790817 1.43179 2.55086 + endloop + endfacet + facet normal -0.906165 -0.0517007 0.419751 + outer loop + vertex 0.790817 1.43179 2.55086 + vertex 0.789895 1.42743 2.54833 + vertex 0.791421 1.42728 2.55161 + endloop + endfacet + facet normal -0.876674 -0.03782 0.479595 + outer loop + vertex 0.791421 1.42728 2.55161 + vertex 0.792804 1.42918 2.55428 + vertex 0.790817 1.43179 2.55086 + endloop + endfacet + facet normal -0.87959 -0.0483753 0.473267 + outer loop + vertex 0.790817 1.43179 2.55086 + vertex 0.792804 1.42918 2.55428 + vertex 0.792634 1.43427 2.55449 + endloop + endfacet + facet normal -0.843539 -0.0496459 0.534769 + outer loop + vertex 0.792804 1.42918 2.55428 + vertex 0.794679 1.43149 2.55746 + vertex 0.792634 1.43427 2.55449 + endloop + endfacet + facet normal -0.845214 -0.0451895 0.532514 + outer loop + vertex 0.794739 1.42642 2.55712 + vertex 0.794679 1.43149 2.55746 + vertex 0.792804 1.42918 2.55428 + endloop + endfacet + facet normal -0.913316 -0.0399515 0.405287 + outer loop + vertex 0.789346 1.4357 2.54793 + vertex 0.789282 1.43158 2.54738 + vertex 0.790817 1.43179 2.55086 + endloop + endfacet + facet normal -0.914367 -0.0423105 0.402669 + outer loop + vertex 0.79082 1.43736 2.55145 + vertex 0.789346 1.4357 2.54793 + vertex 0.790817 1.43179 2.55086 + endloop + endfacet + facet normal -0.879078 -0.0499045 0.474058 + outer loop + vertex 0.790817 1.43179 2.55086 + vertex 0.792634 1.43427 2.55449 + vertex 0.79082 1.43736 2.55145 + endloop + endfacet + facet normal -0.878023 -0.0470833 0.476298 + outer loop + vertex 0.79082 1.43736 2.55145 + vertex 0.792634 1.43427 2.55449 + vertex 0.792503 1.4394 2.55475 + endloop + endfacet + facet normal -0.84116 -0.0493639 0.538529 + outer loop + vertex 0.792634 1.43427 2.55449 + vertex 0.794537 1.43656 2.55767 + vertex 0.792503 1.4394 2.55475 + endloop + endfacet + facet normal -0.842296 -0.0463231 0.537021 + outer loop + vertex 0.794679 1.43149 2.55746 + vertex 0.794537 1.43656 2.55767 + vertex 0.792634 1.43427 2.55449 + endloop + endfacet + facet normal -0.915859 -0.0352405 0.39995 + outer loop + vertex 0.78933 1.44076 2.54834 + vertex 0.789346 1.4357 2.54793 + vertex 0.79082 1.43736 2.55145 + endloop + endfacet + facet normal -0.917428 -0.0396144 0.395925 + outer loop + vertex 0.790726 1.44248 2.55174 + vertex 0.78933 1.44076 2.54834 + vertex 0.79082 1.43736 2.55145 + endloop + endfacet + facet normal -0.879133 -0.0434098 0.474595 + outer loop + vertex 0.79082 1.43736 2.55145 + vertex 0.792503 1.4394 2.55475 + vertex 0.790726 1.44248 2.55174 + endloop + endfacet + facet normal -0.878878 -0.0427411 0.475129 + outer loop + vertex 0.790726 1.44248 2.55174 + vertex 0.792503 1.4394 2.55475 + vertex 0.792357 1.4444 2.55493 + endloop + endfacet + facet normal -0.838628 -0.0440061 0.542924 + outer loop + vertex 0.792503 1.4394 2.55475 + vertex 0.794383 1.44155 2.55783 + vertex 0.792357 1.4444 2.55493 + endloop + endfacet + facet normal -0.838828 -0.0434541 0.54266 + outer loop + vertex 0.794537 1.43656 2.55767 + vertex 0.794383 1.44155 2.55783 + vertex 0.792503 1.4394 2.55475 + endloop + endfacet + facet normal -0.919551 -0.0297931 0.39184 + outer loop + vertex 0.78925 1.44581 2.54853 + vertex 0.78933 1.44076 2.54834 + vertex 0.790726 1.44248 2.55174 + endloop + endfacet + facet normal -0.922152 -0.0375495 0.385002 + outer loop + vertex 0.790594 1.44747 2.55191 + vertex 0.78925 1.44581 2.54853 + vertex 0.790726 1.44248 2.55174 + endloop + endfacet + facet normal -0.879833 -0.0394645 0.473642 + outer loop + vertex 0.790726 1.44248 2.55174 + vertex 0.792357 1.4444 2.55493 + vertex 0.790594 1.44747 2.55191 + endloop + endfacet + facet normal -0.879912 -0.0396735 0.473477 + outer loop + vertex 0.790594 1.44747 2.55191 + vertex 0.792357 1.4444 2.55493 + vertex 0.792212 1.44936 2.55508 + endloop + endfacet + facet normal -0.836129 -0.040547 0.547033 + outer loop + vertex 0.792357 1.4444 2.55493 + vertex 0.794239 1.44651 2.55797 + vertex 0.792212 1.44936 2.55508 + endloop + endfacet + facet normal -0.836642 -0.0391094 0.546352 + outer loop + vertex 0.794383 1.44155 2.55783 + vertex 0.794239 1.44651 2.55797 + vertex 0.792357 1.4444 2.55493 + endloop + endfacet + facet normal -0.923055 -0.0332187 0.383231 + outer loop + vertex 0.789128 1.45078 2.54867 + vertex 0.78925 1.44581 2.54853 + vertex 0.790594 1.44747 2.55191 + endloop + endfacet + facet normal -0.92484 -0.0387675 0.378377 + outer loop + vertex 0.790448 1.45242 2.55206 + vertex 0.789128 1.45078 2.54867 + vertex 0.790594 1.44747 2.55191 + endloop + endfacet + facet normal -0.879714 -0.0403606 0.473787 + outer loop + vertex 0.790594 1.44747 2.55191 + vertex 0.792212 1.44936 2.55508 + vertex 0.790448 1.45242 2.55206 + endloop + endfacet + facet normal -0.879742 -0.0404337 0.473729 + outer loop + vertex 0.790448 1.45242 2.55206 + vertex 0.792212 1.44936 2.55508 + vertex 0.792061 1.45433 2.55522 + endloop + endfacet + facet normal -0.835585 -0.0412438 0.547811 + outer loop + vertex 0.792212 1.44936 2.55508 + vertex 0.794096 1.45147 2.55811 + vertex 0.792061 1.45433 2.55522 + endloop + endfacet + facet normal -0.835972 -0.0401649 0.5473 + outer loop + vertex 0.794239 1.44651 2.55797 + vertex 0.794096 1.45147 2.55811 + vertex 0.792212 1.44936 2.55508 + endloop + endfacet + facet normal -0.925468 -0.035712 0.377139 + outer loop + vertex 0.788994 1.45573 2.54881 + vertex 0.789128 1.45078 2.54867 + vertex 0.790448 1.45242 2.55206 + endloop + endfacet + facet normal -0.926475 -0.03891 0.37434 + outer loop + vertex 0.790296 1.45739 2.55221 + vertex 0.788994 1.45573 2.54881 + vertex 0.790448 1.45242 2.55206 + endloop + endfacet + facet normal -0.879784 -0.0402904 0.473663 + outer loop + vertex 0.790448 1.45242 2.55206 + vertex 0.792061 1.45433 2.55522 + vertex 0.790296 1.45739 2.55221 + endloop + endfacet + facet normal -0.879451 -0.039415 0.474355 + outer loop + vertex 0.790296 1.45739 2.55221 + vertex 0.792061 1.45433 2.55522 + vertex 0.791899 1.45933 2.55534 + endloop + endfacet + facet normal -0.835525 -0.0397049 0.548017 + outer loop + vertex 0.792061 1.45433 2.55522 + vertex 0.793946 1.45647 2.55825 + vertex 0.791899 1.45933 2.55534 + endloop + endfacet + facet normal -0.835257 -0.0404447 0.548371 + outer loop + vertex 0.794096 1.45147 2.55811 + vertex 0.793946 1.45647 2.55825 + vertex 0.792061 1.45433 2.55522 + endloop + endfacet + facet normal -0.927428 -0.03426 0.37243 + outer loop + vertex 0.788862 1.46069 2.54894 + vertex 0.788994 1.45573 2.54881 + vertex 0.790296 1.45739 2.55221 + endloop + endfacet + facet normal -0.927738 -0.0352551 0.371563 + outer loop + vertex 0.790147 1.46237 2.55231 + vertex 0.788862 1.46069 2.54894 + vertex 0.790296 1.45739 2.55221 + endloop + endfacet + facet normal -0.880491 -0.0358838 0.472704 + outer loop + vertex 0.790296 1.45739 2.55221 + vertex 0.791899 1.45933 2.55534 + vertex 0.790147 1.46237 2.55231 + endloop + endfacet + facet normal -0.880372 -0.0355731 0.472947 + outer loop + vertex 0.790147 1.46237 2.55231 + vertex 0.791899 1.45933 2.55534 + vertex 0.79174 1.46434 2.55542 + endloop + endfacet + facet normal -0.836016 -0.0353648 0.547564 + outer loop + vertex 0.791899 1.45933 2.55534 + vertex 0.793783 1.46148 2.55835 + vertex 0.79174 1.46434 2.55542 + endloop + endfacet + facet normal -0.83495 -0.0383031 0.548991 + outer loop + vertex 0.793946 1.45647 2.55825 + vertex 0.793783 1.46148 2.55835 + vertex 0.791899 1.45933 2.55534 + endloop + endfacet + facet normal -0.928629 -0.0308996 0.36972 + outer loop + vertex 0.788741 1.46563 2.54905 + vertex 0.788862 1.46069 2.54894 + vertex 0.790147 1.46237 2.55231 + endloop + endfacet + facet normal -0.928363 -0.0300455 0.370458 + outer loop + vertex 0.790027 1.46736 2.55241 + vertex 0.788741 1.46563 2.54905 + vertex 0.790147 1.46237 2.55231 + endloop + endfacet + facet normal -0.88171 -0.031036 0.470771 + outer loop + vertex 0.790147 1.46237 2.55231 + vertex 0.79174 1.46434 2.55542 + vertex 0.790027 1.46736 2.55241 + endloop + endfacet + facet normal -0.881541 -0.0305997 0.471114 + outer loop + vertex 0.790027 1.46736 2.55241 + vertex 0.79174 1.46434 2.55542 + vertex 0.79163 1.46935 2.55554 + endloop + endfacet + facet normal -0.835181 -0.0314276 0.549076 + outer loop + vertex 0.79174 1.46434 2.55542 + vertex 0.793636 1.4665 2.55843 + vertex 0.79163 1.46935 2.55554 + endloop + endfacet + facet normal -0.834813 -0.0324444 0.549576 + outer loop + vertex 0.793783 1.46148 2.55835 + vertex 0.793636 1.4665 2.55843 + vertex 0.79174 1.46434 2.55542 + endloop + endfacet + facet normal -0.929241 -0.0257454 0.368576 + outer loop + vertex 0.788671 1.47058 2.54922 + vertex 0.788741 1.46563 2.54905 + vertex 0.790027 1.46736 2.55241 + endloop + endfacet + facet normal -0.929524 -0.0266387 0.367798 + outer loop + vertex 0.789982 1.47239 2.55266 + vertex 0.788671 1.47058 2.54922 + vertex 0.790027 1.46736 2.55241 + endloop + endfacet + facet normal -0.881323 -0.031343 0.471474 + outer loop + vertex 0.790027 1.46736 2.55241 + vertex 0.79163 1.46935 2.55554 + vertex 0.789982 1.47239 2.55266 + endloop + endfacet + facet normal -0.880631 -0.0296425 0.472875 + outer loop + vertex 0.789982 1.47239 2.55266 + vertex 0.79163 1.46935 2.55554 + vertex 0.79162 1.4743 2.55583 + endloop + endfacet + facet normal -0.832059 -0.0343086 0.553626 + outer loop + vertex 0.79163 1.46935 2.55554 + vertex 0.793541 1.47151 2.55854 + vertex 0.79162 1.4743 2.55583 + endloop + endfacet + facet normal -0.834063 -0.0287741 0.550919 + outer loop + vertex 0.793636 1.4665 2.55843 + vertex 0.793541 1.47151 2.55854 + vertex 0.79163 1.46935 2.55554 + endloop + endfacet + facet normal -0.929284 -0.0277982 0.368318 + outer loop + vertex 0.788675 1.47549 2.5496 + vertex 0.788671 1.47058 2.54922 + vertex 0.789982 1.47239 2.55266 + endloop + endfacet + facet normal -0.928124 -0.0241787 0.371485 + outer loop + vertex 0.79007 1.47777 2.55323 + vertex 0.788675 1.47549 2.5496 + vertex 0.789982 1.47239 2.55266 + endloop + endfacet + facet normal -0.878828 -0.0360295 0.475777 + outer loop + vertex 0.789982 1.47239 2.55266 + vertex 0.79162 1.4743 2.55583 + vertex 0.79007 1.47777 2.55323 + endloop + endfacet + facet normal -0.874549 -0.0278549 0.484137 + outer loop + vertex 0.79007 1.47777 2.55323 + vertex 0.79162 1.4743 2.55583 + vertex 0.791805 1.4785 2.55641 + endloop + endfacet + facet normal -0.82629 -0.0406032 0.561779 + outer loop + vertex 0.79162 1.4743 2.55583 + vertex 0.793501 1.47638 2.55875 + vertex 0.791805 1.4785 2.55641 + endloop + endfacet + facet normal -0.830171 -0.0300034 0.556701 + outer loop + vertex 0.793541 1.47151 2.55854 + vertex 0.793501 1.47638 2.55875 + vertex 0.79162 1.4743 2.55583 + endloop + endfacet + facet normal -0.924296 -0.0395192 0.379624 + outer loop + vertex 0.788675 1.47549 2.5496 + vertex 0.79007 1.47777 2.55323 + vertex 0.788731 1.47949 2.55015 + endloop + endfacet + facet normal -0.924803 -0.0427649 0.378035 + outer loop + vertex 0.789461 1.48186 2.5522 + vertex 0.788731 1.47949 2.55015 + vertex 0.79007 1.47777 2.55323 + endloop + endfacet + facet normal -0.888855 -0.0173608 0.45786 + outer loop + vertex 0.789461 1.48186 2.5522 + vertex 0.79007 1.47777 2.55323 + vertex 0.791129 1.48286 2.55548 + endloop + endfacet + facet normal -0.873981 -0.0324008 0.484879 + outer loop + vertex 0.791129 1.48286 2.55548 + vertex 0.79007 1.47777 2.55323 + vertex 0.791805 1.4785 2.55641 + endloop + endfacet + facet normal -0.831607 -0.0108325 0.555259 + outer loop + vertex 0.791805 1.4785 2.55641 + vertex 0.793361 1.48116 2.55879 + vertex 0.791129 1.48286 2.55548 + endloop + endfacet + facet normal -0.821791 -0.0289649 0.569052 + outer loop + vertex 0.793501 1.47638 2.55875 + vertex 0.793361 1.48116 2.55879 + vertex 0.791805 1.4785 2.55641 + endloop + endfacet + facet normal -0.889342 -0.0138386 0.457033 + outer loop + vertex 0.789617 1.48607 2.55263 + vertex 0.789461 1.48186 2.5522 + vertex 0.791129 1.48286 2.55548 + endloop + endfacet + facet normal -0.889973 -0.0152658 0.455758 + outer loop + vertex 0.791244 1.48853 2.55589 + vertex 0.789617 1.48607 2.55263 + vertex 0.791129 1.48286 2.55548 + endloop + endfacet + facet normal -0.835669 -0.0231786 0.548744 + outer loop + vertex 0.791129 1.48286 2.55548 + vertex 0.793216 1.48617 2.5588 + vertex 0.791244 1.48853 2.55589 + endloop + endfacet + facet normal -0.834748 -0.0250774 0.550061 + outer loop + vertex 0.793361 1.48116 2.55879 + vertex 0.793216 1.48617 2.5588 + vertex 0.791129 1.48286 2.55548 + endloop + endfacet + facet normal -0.892165 -0.00835806 0.451632 + outer loop + vertex 0.789712 1.49114 2.55292 + vertex 0.789617 1.48607 2.55263 + vertex 0.791244 1.48853 2.55589 + endloop + endfacet + facet normal -0.891319 -0.00591384 0.453339 + outer loop + vertex 0.791281 1.49368 2.55603 + vertex 0.789712 1.49114 2.55292 + vertex 0.791244 1.48853 2.55589 + endloop + endfacet + facet normal -0.837926 -0.0087921 0.545713 + outer loop + vertex 0.791244 1.48853 2.55589 + vertex 0.793193 1.49132 2.55893 + vertex 0.791281 1.49368 2.55603 + endloop + endfacet + facet normal -0.833875 -0.0181036 0.551657 + outer loop + vertex 0.793216 1.48617 2.5588 + vertex 0.793193 1.49132 2.55893 + vertex 0.791244 1.48853 2.55589 + endloop + endfacet + facet normal -0.893099 -0.000541351 0.449859 + outer loop + vertex 0.789735 1.49617 2.55297 + vertex 0.789712 1.49114 2.55292 + vertex 0.791281 1.49368 2.55603 + endloop + endfacet + facet normal -0.893702 -0.00239664 0.448654 + outer loop + vertex 0.791269 1.49868 2.55604 + vertex 0.789735 1.49617 2.55297 + vertex 0.791281 1.49368 2.55603 + endloop + endfacet + facet normal -0.839078 -0.00232037 0.544006 + outer loop + vertex 0.791281 1.49368 2.55603 + vertex 0.793179 1.49634 2.55897 + vertex 0.791269 1.49868 2.55604 + endloop + endfacet + facet normal -0.837201 -0.00680573 0.546854 + outer loop + vertex 0.793193 1.49132 2.55893 + vertex 0.793179 1.49634 2.55897 + vertex 0.791281 1.49368 2.55603 + endloop + endfacet + facet normal -0.895093 0.00185357 0.445875 + outer loop + vertex 0.789724 1.50117 2.55292 + vertex 0.789735 1.49617 2.55297 + vertex 0.791269 1.49868 2.55604 + endloop + endfacet + facet normal -0.897276 -0.00504717 0.441441 + outer loop + vertex 0.79124 1.50366 2.55603 + vertex 0.789724 1.50117 2.55292 + vertex 0.791269 1.49868 2.55604 + endloop + endfacet + facet normal -0.839963 -0.00464417 0.542624 + outer loop + vertex 0.791269 1.49868 2.55604 + vertex 0.793152 1.50131 2.55897 + vertex 0.79124 1.50366 2.55603 + endloop + endfacet + facet normal -0.839938 -0.0047046 0.542662 + outer loop + vertex 0.793179 1.49634 2.55897 + vertex 0.793152 1.50131 2.55897 + vertex 0.791269 1.49868 2.55604 + endloop + endfacet + facet normal -0.89616 -0.00849371 0.443651 + outer loop + vertex 0.789685 1.50615 2.55294 + vertex 0.789724 1.50117 2.55292 + vertex 0.79124 1.50366 2.55603 + endloop + endfacet + facet normal -0.897431 -0.0126067 0.440974 + outer loop + vertex 0.791201 1.50864 2.5561 + vertex 0.789685 1.50615 2.55294 + vertex 0.79124 1.50366 2.55603 + endloop + endfacet + facet normal -0.841439 -0.0134263 0.540186 + outer loop + vertex 0.79124 1.50366 2.55603 + vertex 0.793109 1.50628 2.55901 + vertex 0.791201 1.50864 2.5561 + endloop + endfacet + facet normal -0.842323 -0.0112854 0.538854 + outer loop + vertex 0.793152 1.50131 2.55897 + vertex 0.793109 1.50628 2.55901 + vertex 0.79124 1.50366 2.55603 + endloop + endfacet + facet normal -0.896716 -0.0147949 0.442359 + outer loop + vertex 0.789647 1.51114 2.55303 + vertex 0.789685 1.50615 2.55294 + vertex 0.791201 1.50864 2.5561 + endloop + endfacet + facet normal -0.89641 -0.0138066 0.44301 + outer loop + vertex 0.791169 1.51364 2.55619 + vertex 0.789647 1.51114 2.55303 + vertex 0.791201 1.50864 2.5561 + endloop + endfacet + facet normal -0.840214 -0.0152749 0.54204 + outer loop + vertex 0.791201 1.50864 2.5561 + vertex 0.793072 1.51127 2.55907 + vertex 0.791169 1.51364 2.55619 + endloop + endfacet + facet normal -0.841229 -0.0128358 0.540527 + outer loop + vertex 0.793109 1.50628 2.55901 + vertex 0.793072 1.51127 2.55907 + vertex 0.791201 1.50864 2.5561 + endloop + endfacet + facet normal -0.896976 -0.0120763 0.441913 + outer loop + vertex 0.789623 1.51615 2.55312 + vertex 0.789647 1.51114 2.55303 + vertex 0.791169 1.51364 2.55619 + endloop + endfacet + facet normal -0.894528 -0.00433792 0.446992 + outer loop + vertex 0.791166 1.51865 2.55623 + vertex 0.789623 1.51615 2.55312 + vertex 0.791169 1.51364 2.55619 + endloop + endfacet + facet normal -0.83941 -0.00510897 0.543475 + outer loop + vertex 0.791169 1.51364 2.55619 + vertex 0.793051 1.51626 2.55912 + vertex 0.791166 1.51865 2.55623 + endloop + endfacet + facet normal -0.837866 -0.00882819 0.545804 + outer loop + vertex 0.793072 1.51127 2.55907 + vertex 0.793051 1.51626 2.55912 + vertex 0.791169 1.51364 2.55619 + endloop + endfacet + facet normal -0.89505 -0.00273544 0.445958 + outer loop + vertex 0.789616 1.52115 2.55314 + vertex 0.789623 1.51615 2.55312 + vertex 0.791166 1.51865 2.55623 + endloop + endfacet + facet normal -0.891364 0.00854861 0.453207 + outer loop + vertex 0.791187 1.52367 2.55618 + vertex 0.789616 1.52115 2.55314 + vertex 0.791166 1.51865 2.55623 + endloop + endfacet + facet normal -0.835904 0.00934138 0.548796 + outer loop + vertex 0.791166 1.51865 2.55623 + vertex 0.793081 1.52127 2.5591 + vertex 0.791187 1.52367 2.55618 + endloop + endfacet + facet normal -0.834871 0.00681782 0.550403 + outer loop + vertex 0.793051 1.51626 2.55912 + vertex 0.793081 1.52127 2.5591 + vertex 0.791166 1.51865 2.55623 + endloop + endfacet + facet normal -0.892129 0.0109043 0.45165 + outer loop + vertex 0.789626 1.52616 2.55303 + vertex 0.789616 1.52115 2.55314 + vertex 0.791187 1.52367 2.55618 + endloop + endfacet + facet normal -0.889604 0.0184397 0.456361 + outer loop + vertex 0.791211 1.52867 2.55602 + vertex 0.789626 1.52616 2.55303 + vertex 0.791187 1.52367 2.55618 + endloop + endfacet + facet normal -0.833492 0.0211327 0.552128 + outer loop + vertex 0.791187 1.52367 2.55618 + vertex 0.79313 1.52629 2.55901 + vertex 0.791211 1.52867 2.55602 + endloop + endfacet + facet normal -0.83237 0.0183718 0.553915 + outer loop + vertex 0.793081 1.52127 2.5591 + vertex 0.79313 1.52629 2.55901 + vertex 0.791187 1.52367 2.55618 + endloop + endfacet + facet normal -0.88928 0.0174419 0.45703 + outer loop + vertex 0.789624 1.53112 2.55284 + vertex 0.789626 1.52616 2.55303 + vertex 0.791211 1.52867 2.55602 + endloop + endfacet + facet normal -0.88846 0.0199164 0.458522 + outer loop + vertex 0.791199 1.53369 2.55578 + vertex 0.789624 1.53112 2.55284 + vertex 0.791211 1.52867 2.55602 + endloop + endfacet + facet normal -0.832972 0.0245789 0.55277 + outer loop + vertex 0.791211 1.52867 2.55602 + vertex 0.793173 1.53132 2.55886 + vertex 0.791199 1.53369 2.55578 + endloop + endfacet + facet normal -0.832553 0.0235427 0.553445 + outer loop + vertex 0.79313 1.52629 2.55901 + vertex 0.793173 1.53132 2.55886 + vertex 0.791211 1.52867 2.55602 + endloop + endfacet + facet normal -0.885651 0.0116946 0.464204 + outer loop + vertex 0.789566 1.53586 2.55261 + vertex 0.789624 1.53112 2.55284 + vertex 0.791199 1.53369 2.55578 + endloop + endfacet + facet normal -0.88543 0.0124468 0.464606 + outer loop + vertex 0.791052 1.53902 2.55536 + vertex 0.789566 1.53586 2.55261 + vertex 0.791199 1.53369 2.55578 + endloop + endfacet + facet normal -0.833332 0.0208284 0.55238 + outer loop + vertex 0.791199 1.53369 2.55578 + vertex 0.793203 1.53635 2.5587 + vertex 0.791052 1.53902 2.55536 + endloop + endfacet + facet normal -0.833873 0.0221899 0.551509 + outer loop + vertex 0.793173 1.53132 2.55886 + vertex 0.793203 1.53635 2.5587 + vertex 0.791199 1.53369 2.55578 + endloop + endfacet + facet normal -0.923235 0.02252 0.383574 + outer loop + vertex 0.789822 1.54318 2.55306 + vertex 0.78869 1.54167 2.55042 + vertex 0.789398 1.53954 2.55225 + endloop + endfacet + facet normal -0.882351 0.00581961 0.470555 + outer loop + vertex 0.789398 1.53954 2.55225 + vertex 0.789566 1.53586 2.55261 + vertex 0.791052 1.53902 2.55536 + endloop + endfacet + facet normal -0.882848 -0.00116807 0.469657 + outer loop + vertex 0.789398 1.53954 2.55225 + vertex 0.791052 1.53902 2.55536 + vertex 0.789822 1.54318 2.55306 + endloop + endfacet + facet normal -0.870511 0.0147908 0.491928 + outer loop + vertex 0.789822 1.54318 2.55306 + vertex 0.791052 1.53902 2.55536 + vertex 0.79158 1.54354 2.55616 + endloop + endfacet + facet normal -0.829839 -0.00161131 0.558 + outer loop + vertex 0.791052 1.53902 2.55536 + vertex 0.793309 1.54128 2.55872 + vertex 0.79158 1.54354 2.55616 + endloop + endfacet + facet normal -0.835181 0.0160201 0.549741 + outer loop + vertex 0.793203 1.53635 2.5587 + vertex 0.793309 1.54128 2.55872 + vertex 0.791052 1.53902 2.55536 + endloop + endfacet + facet normal -0.921713 0.0143332 0.387608 + outer loop + vertex 0.78869 1.54167 2.55042 + vertex 0.789822 1.54318 2.55306 + vertex 0.788657 1.54442 2.55024 + endloop + endfacet + facet normal -0.925876 -0.0122324 0.377629 + outer loop + vertex 0.789274 1.54651 2.55182 + vertex 0.788657 1.54442 2.55024 + vertex 0.789822 1.54318 2.55306 + endloop + endfacet + facet normal -0.890225 0.0223267 0.454973 + outer loop + vertex 0.789274 1.54651 2.55182 + vertex 0.789822 1.54318 2.55306 + vertex 0.790842 1.54826 2.5548 + endloop + endfacet + facet normal -0.870123 0.00528661 0.492806 + outer loop + vertex 0.790842 1.54826 2.5548 + vertex 0.789822 1.54318 2.55306 + vertex 0.79158 1.54354 2.55616 + endloop + endfacet + facet normal -0.831773 0.0289454 0.55436 + outer loop + vertex 0.79158 1.54354 2.55616 + vertex 0.793309 1.54611 2.55862 + vertex 0.790842 1.54826 2.5548 + endloop + endfacet + facet normal -0.824065 0.0122745 0.566363 + outer loop + vertex 0.793309 1.54128 2.55872 + vertex 0.793309 1.54611 2.55862 + vertex 0.79158 1.54354 2.55616 + endloop + endfacet + facet normal -0.933982 0.0286064 0.356173 + outer loop + vertex 0.789634 1.55261 2.55244 + vertex 0.78861 1.5516 2.54983 + vertex 0.789241 1.54929 2.55167 + endloop + endfacet + facet normal -0.888309 0.0136894 0.459041 + outer loop + vertex 0.789241 1.54929 2.55167 + vertex 0.789274 1.54651 2.55182 + vertex 0.790842 1.54826 2.5548 + endloop + endfacet + facet normal -0.890153 0.000560619 0.455662 + outer loop + vertex 0.789241 1.54929 2.55167 + vertex 0.790842 1.54826 2.5548 + vertex 0.789634 1.55261 2.55244 + endloop + endfacet + facet normal -0.880555 0.0130854 0.473764 + outer loop + vertex 0.789634 1.55261 2.55244 + vertex 0.790842 1.54826 2.5548 + vertex 0.791308 1.55411 2.55551 + endloop + endfacet + facet normal -0.832278 -0.00050922 0.554358 + outer loop + vertex 0.790842 1.54826 2.5548 + vertex 0.793295 1.55118 2.55849 + vertex 0.791308 1.55411 2.55551 + endloop + endfacet + facet normal -0.836606 0.011562 0.547682 + outer loop + vertex 0.793309 1.54611 2.55862 + vertex 0.793295 1.55118 2.55849 + vertex 0.790842 1.54826 2.5548 + endloop + endfacet + facet normal -0.934017 0.0289521 0.356052 + outer loop + vertex 0.788584 1.55557 2.54944 + vertex 0.78861 1.5516 2.54983 + vertex 0.789634 1.55261 2.55244 + endloop + endfacet + facet normal -0.93687 0.0208611 0.349056 + outer loop + vertex 0.789796 1.55729 2.55259 + vertex 0.788584 1.55557 2.54944 + vertex 0.789634 1.55261 2.55244 + endloop + endfacet + facet normal -0.880885 0.0148217 0.473097 + outer loop + vertex 0.789634 1.55261 2.55244 + vertex 0.791308 1.55411 2.55551 + vertex 0.789796 1.55729 2.55259 + endloop + endfacet + facet normal -0.880401 0.0158451 0.473965 + outer loop + vertex 0.789796 1.55729 2.55259 + vertex 0.791308 1.55411 2.55551 + vertex 0.791459 1.55919 2.55562 + endloop + endfacet + facet normal -0.826753 0.0123388 0.562429 + outer loop + vertex 0.791308 1.55411 2.55551 + vertex 0.793419 1.55634 2.55856 + vertex 0.791459 1.55919 2.55562 + endloop + endfacet + facet normal -0.82659 0.0118413 0.56268 + outer loop + vertex 0.793295 1.55118 2.55849 + vertex 0.793419 1.55634 2.55856 + vertex 0.791308 1.55411 2.55551 + endloop + endfacet + facet normal -0.935338 0.0115624 0.353566 + outer loop + vertex 0.788593 1.5605 2.5493 + vertex 0.788584 1.55557 2.54944 + vertex 0.789796 1.55729 2.55259 + endloop + endfacet + facet normal -0.934277 0.0147085 0.356245 + outer loop + vertex 0.78986 1.56223 2.55256 + vertex 0.788593 1.5605 2.5493 + vertex 0.789796 1.55729 2.55259 + endloop + endfacet + facet normal -0.880156 0.0148553 0.474452 + outer loop + vertex 0.789796 1.55729 2.55259 + vertex 0.791459 1.55919 2.55562 + vertex 0.78986 1.56223 2.55256 + endloop + endfacet + facet normal -0.877249 0.0215274 0.479553 + outer loop + vertex 0.78986 1.56223 2.55256 + vertex 0.791459 1.55919 2.55562 + vertex 0.791541 1.56416 2.55555 + endloop + endfacet + facet normal -0.823767 0.0219052 0.566505 + outer loop + vertex 0.791459 1.55919 2.55562 + vertex 0.793506 1.56134 2.55851 + vertex 0.791541 1.56416 2.55555 + endloop + endfacet + facet normal -0.823149 0.0200119 0.567473 + outer loop + vertex 0.793419 1.55634 2.55856 + vertex 0.793506 1.56134 2.55851 + vertex 0.791459 1.55919 2.55562 + endloop + endfacet + facet normal -0.932533 0.00439766 0.361058 + outer loop + vertex 0.788595 1.56555 2.54925 + vertex 0.788593 1.5605 2.5493 + vertex 0.78986 1.56223 2.55256 + endloop + endfacet + facet normal -0.928594 0.0155721 0.37077 + outer loop + vertex 0.789912 1.56721 2.55248 + vertex 0.788595 1.56555 2.54925 + vertex 0.78986 1.56223 2.55256 + endloop + endfacet + facet normal -0.876035 0.0167404 0.481957 + outer loop + vertex 0.78986 1.56223 2.55256 + vertex 0.791541 1.56416 2.55555 + vertex 0.789912 1.56721 2.55248 + endloop + endfacet + facet normal -0.870019 0.0301358 0.492097 + outer loop + vertex 0.789912 1.56721 2.55248 + vertex 0.791541 1.56416 2.55555 + vertex 0.791644 1.56912 2.55542 + endloop + endfacet + facet normal -0.821145 0.0310356 0.569875 + outer loop + vertex 0.791541 1.56416 2.55555 + vertex 0.793595 1.5663 2.55839 + vertex 0.791644 1.56912 2.55542 + endloop + endfacet + facet normal -0.820459 0.0289145 0.570973 + outer loop + vertex 0.793506 1.56134 2.55851 + vertex 0.793595 1.5663 2.55839 + vertex 0.791541 1.56416 2.55555 + endloop + endfacet + facet normal -0.927193 0.00718187 0.374516 + outer loop + vertex 0.78862 1.57061 2.54921 + vertex 0.788595 1.56555 2.54925 + vertex 0.789912 1.56721 2.55248 + endloop + endfacet + facet normal -0.921047 0.0232207 0.388759 + outer loop + vertex 0.790001 1.57222 2.55239 + vertex 0.78862 1.57061 2.54921 + vertex 0.789912 1.56721 2.55248 + endloop + endfacet + facet normal -0.868519 0.0242009 0.495065 + outer loop + vertex 0.789912 1.56721 2.55248 + vertex 0.791644 1.56912 2.55542 + vertex 0.790001 1.57222 2.55239 + endloop + endfacet + facet normal -0.862505 0.0368251 0.504707 + outer loop + vertex 0.790001 1.57222 2.55239 + vertex 0.791644 1.56912 2.55542 + vertex 0.791781 1.57411 2.55529 + endloop + endfacet + facet normal -0.817943 0.0374315 0.57408 + outer loop + vertex 0.791644 1.56912 2.55542 + vertex 0.79372 1.57126 2.55824 + vertex 0.791781 1.57411 2.55529 + endloop + endfacet + facet normal -0.817984 0.0375576 0.574014 + outer loop + vertex 0.793595 1.5663 2.55839 + vertex 0.79372 1.57126 2.55824 + vertex 0.791644 1.56912 2.55542 + endloop + endfacet + facet normal -0.919966 0.0166248 0.391645 + outer loop + vertex 0.788678 1.57565 2.54914 + vertex 0.78862 1.57061 2.54921 + vertex 0.790001 1.57222 2.55239 + endloop + endfacet + facet normal -0.914863 0.0290934 0.402714 + outer loop + vertex 0.790113 1.57725 2.55228 + vertex 0.788678 1.57565 2.54914 + vertex 0.790001 1.57222 2.55239 + endloop + endfacet + facet normal -0.860826 0.0301709 0.508004 + outer loop + vertex 0.790001 1.57222 2.55239 + vertex 0.791781 1.57411 2.55529 + vertex 0.790113 1.57725 2.55228 + endloop + endfacet + facet normal -0.856056 0.0397481 0.515352 + outer loop + vertex 0.790113 1.57725 2.55228 + vertex 0.791781 1.57411 2.55529 + vertex 0.791931 1.57912 2.55516 + endloop + endfacet + facet normal -0.814517 0.0402146 0.578744 + outer loop + vertex 0.791781 1.57411 2.55529 + vertex 0.793872 1.57624 2.55809 + vertex 0.791931 1.57912 2.55516 + endloop + endfacet + facet normal -0.815314 0.0426993 0.577443 + outer loop + vertex 0.79372 1.57126 2.55824 + vertex 0.793872 1.57624 2.55809 + vertex 0.791781 1.57411 2.55529 + endloop + endfacet + facet normal -0.913919 0.023319 0.405226 + outer loop + vertex 0.78875 1.58068 2.54901 + vertex 0.788678 1.57565 2.54914 + vertex 0.790113 1.57725 2.55228 + endloop + endfacet + facet normal -0.909948 0.0327354 0.413429 + outer loop + vertex 0.790233 1.5823 2.55214 + vertex 0.78875 1.58068 2.54901 + vertex 0.790113 1.57725 2.55228 + endloop + endfacet + facet normal -0.85467 0.0342466 0.518041 + outer loop + vertex 0.790113 1.57725 2.55228 + vertex 0.791931 1.57912 2.55516 + vertex 0.790233 1.5823 2.55214 + endloop + endfacet + facet normal -0.85063 0.0421179 0.524076 + outer loop + vertex 0.790233 1.5823 2.55214 + vertex 0.791931 1.57912 2.55516 + vertex 0.792092 1.58414 2.55501 + endloop + endfacet + facet normal -0.811373 0.0425416 0.582979 + outer loop + vertex 0.791931 1.57912 2.55516 + vertex 0.794037 1.58124 2.55793 + vertex 0.792092 1.58414 2.55501 + endloop + endfacet + facet normal -0.812126 0.0448966 0.581752 + outer loop + vertex 0.793872 1.57624 2.55809 + vertex 0.794037 1.58124 2.55793 + vertex 0.791931 1.57912 2.55516 + endloop + endfacet + facet normal -0.908576 0.0245899 0.416996 + outer loop + vertex 0.788815 1.58571 2.54885 + vertex 0.78875 1.58068 2.54901 + vertex 0.790233 1.5823 2.55214 + endloop + endfacet + facet normal -0.904683 0.0336871 0.424751 + outer loop + vertex 0.790348 1.58735 2.55199 + vertex 0.788815 1.58571 2.54885 + vertex 0.790233 1.5823 2.55214 + endloop + endfacet + facet normal -0.848979 0.0355244 0.527231 + outer loop + vertex 0.790233 1.5823 2.55214 + vertex 0.792092 1.58414 2.55501 + vertex 0.790348 1.58735 2.55199 + endloop + endfacet + facet normal -0.844413 0.0442497 0.533863 + outer loop + vertex 0.790348 1.58735 2.55199 + vertex 0.792092 1.58414 2.55501 + vertex 0.792261 1.58915 2.55487 + endloop + endfacet + facet normal -0.808723 0.0446008 0.586497 + outer loop + vertex 0.792092 1.58414 2.55501 + vertex 0.794216 1.58623 2.55778 + vertex 0.792261 1.58915 2.55487 + endloop + endfacet + facet normal -0.809318 0.0464849 0.585529 + outer loop + vertex 0.794037 1.58124 2.55793 + vertex 0.794216 1.58623 2.55778 + vertex 0.792092 1.58414 2.55501 + endloop + endfacet + facet normal -0.90309 0.0245358 0.428749 + outer loop + vertex 0.788877 1.59077 2.54869 + vertex 0.788815 1.58571 2.54885 + vertex 0.790348 1.58735 2.55199 + endloop + endfacet + facet normal -0.897105 0.038129 0.44017 + outer loop + vertex 0.790477 1.59238 2.55182 + vertex 0.788877 1.59077 2.54869 + vertex 0.790348 1.58735 2.55199 + endloop + endfacet + facet normal -0.843388 0.0400544 0.535809 + outer loop + vertex 0.790348 1.58735 2.55199 + vertex 0.792261 1.58915 2.55487 + vertex 0.790477 1.59238 2.55182 + endloop + endfacet + facet normal -0.839378 0.0476025 0.54146 + outer loop + vertex 0.790477 1.59238 2.55182 + vertex 0.792261 1.58915 2.55487 + vertex 0.792435 1.59411 2.5547 + endloop + endfacet + facet normal -0.807564 0.0480434 0.58782 + outer loop + vertex 0.792261 1.58915 2.55487 + vertex 0.794401 1.5912 2.55764 + vertex 0.792435 1.59411 2.5547 + endloop + endfacet + facet normal -0.807322 0.0472577 0.588215 + outer loop + vertex 0.794216 1.58623 2.55778 + vertex 0.794401 1.5912 2.55764 + vertex 0.792261 1.58915 2.55487 + endloop + endfacet + facet normal -0.896289 0.0333696 0.442213 + outer loop + vertex 0.788969 1.5958 2.5485 + vertex 0.788877 1.59077 2.54869 + vertex 0.790477 1.59238 2.55182 + endloop + endfacet + facet normal -0.890119 0.0468469 0.453314 + outer loop + vertex 0.790628 1.59735 2.5516 + vertex 0.788969 1.5958 2.5485 + vertex 0.790477 1.59238 2.55182 + endloop + endfacet + facet normal -0.839733 0.0491456 0.540772 + outer loop + vertex 0.790477 1.59238 2.55182 + vertex 0.792435 1.59411 2.5547 + vertex 0.790628 1.59735 2.5516 + endloop + endfacet + facet normal -0.838252 0.0519179 0.542806 + outer loop + vertex 0.790628 1.59735 2.5516 + vertex 0.792435 1.59411 2.5547 + vertex 0.792596 1.59897 2.55448 + endloop + endfacet + facet normal -0.809173 0.0528416 0.58519 + outer loop + vertex 0.792435 1.59411 2.5547 + vertex 0.79456 1.59612 2.55746 + vertex 0.792596 1.59897 2.55448 + endloop + endfacet + facet normal -0.807678 0.0478267 0.587681 + outer loop + vertex 0.794401 1.5912 2.55764 + vertex 0.79456 1.59612 2.55746 + vertex 0.792435 1.59411 2.5547 + endloop + endfacet + facet normal -0.890524 0.0494091 0.452245 + outer loop + vertex 0.789109 1.60075 2.54824 + vertex 0.788969 1.5958 2.5485 + vertex 0.790628 1.59735 2.5516 + endloop + endfacet + facet normal -0.885488 0.0600997 0.46076 + outer loop + vertex 0.790815 1.60232 2.55131 + vertex 0.789109 1.60075 2.54824 + vertex 0.790628 1.59735 2.5516 + endloop + endfacet + facet normal -0.840483 0.0629189 0.538173 + outer loop + vertex 0.790628 1.59735 2.5516 + vertex 0.792596 1.59897 2.55448 + vertex 0.790815 1.60232 2.55131 + endloop + endfacet + facet normal -0.84429 0.0559644 0.532957 + outer loop + vertex 0.790815 1.60232 2.55131 + vertex 0.792596 1.59897 2.55448 + vertex 0.792762 1.60352 2.55427 + endloop + endfacet + facet normal -0.814967 0.0569493 0.576702 + outer loop + vertex 0.792596 1.59897 2.55448 + vertex 0.794615 1.60085 2.55715 + vertex 0.792762 1.60352 2.55427 + endloop + endfacet + facet normal -0.812135 0.0470232 0.581571 + outer loop + vertex 0.79456 1.59612 2.55746 + vertex 0.794615 1.60085 2.55715 + vertex 0.792596 1.59897 2.55448 + endloop + endfacet + facet normal -0.885651 0.0611601 0.460306 + outer loop + vertex 0.789252 1.60553 2.54788 + vertex 0.789109 1.60075 2.54824 + vertex 0.790815 1.60232 2.55131 + endloop + endfacet + facet normal -0.881587 0.0700854 0.46679 + outer loop + vertex 0.791094 1.60805 2.55098 + vertex 0.789252 1.60553 2.54788 + vertex 0.790815 1.60232 2.55131 + endloop + endfacet + facet normal -0.824171 0.0560563 0.563559 + outer loop + vertex 0.79325 1.60688 2.55465 + vertex 0.792762 1.60352 2.55427 + vertex 0.794431 1.60453 2.55661 + endloop + endfacet + facet normal -0.851318 0.0648311 0.520629 + outer loop + vertex 0.79325 1.60688 2.55465 + vertex 0.791094 1.60805 2.55098 + vertex 0.792762 1.60352 2.55427 + endloop + endfacet + facet normal -0.846298 0.0719122 0.527833 + outer loop + vertex 0.791094 1.60805 2.55098 + vertex 0.790815 1.60232 2.55131 + vertex 0.792762 1.60352 2.55427 + endloop + endfacet + facet normal -0.822006 0.0425307 0.567889 + outer loop + vertex 0.794431 1.60453 2.55661 + vertex 0.792762 1.60352 2.55427 + vertex 0.794615 1.60085 2.55715 + endloop + endfacet + facet normal -0.922611 0.0849903 0.376251 + outer loop + vertex 0.789638 1.61264 2.54754 + vertex 0.7885 1.61187 2.54493 + vertex 0.789188 1.60931 2.54719 + endloop + endfacet + facet normal -0.881423 0.0694747 0.46719 + outer loop + vertex 0.789188 1.60931 2.54719 + vertex 0.789252 1.60553 2.54788 + vertex 0.791094 1.60805 2.55098 + endloop + endfacet + facet normal -0.881359 0.0697919 0.467263 + outer loop + vertex 0.789188 1.60931 2.54719 + vertex 0.791094 1.60805 2.55098 + vertex 0.789638 1.61264 2.54754 + endloop + endfacet + facet normal -0.881785 0.0691291 0.466558 + outer loop + vertex 0.789638 1.61264 2.54754 + vertex 0.791094 1.60805 2.55098 + vertex 0.79139 1.61388 2.55067 + endloop + endfacet + facet normal -0.853494 0.0702826 0.516341 + outer loop + vertex 0.791094 1.60805 2.55098 + vertex 0.793177 1.61077 2.55405 + vertex 0.79139 1.61388 2.55067 + endloop + endfacet + facet normal -0.851472 0.06406 0.520473 + outer loop + vertex 0.79325 1.60688 2.55465 + vertex 0.793177 1.61077 2.55405 + vertex 0.791094 1.60805 2.55098 + endloop + endfacet + facet normal -0.9225 0.0805798 0.377493 + outer loop + vertex 0.788537 1.61576 2.54419 + vertex 0.7885 1.61187 2.54493 + vertex 0.789638 1.61264 2.54754 + endloop + endfacet + facet normal -0.927067 0.0692319 0.368447 + outer loop + vertex 0.789884 1.61732 2.54729 + vertex 0.788537 1.61576 2.54419 + vertex 0.789638 1.61264 2.54754 + endloop + endfacet + facet normal -0.882092 0.072225 0.465507 + outer loop + vertex 0.789638 1.61264 2.54754 + vertex 0.79139 1.61388 2.55067 + vertex 0.789884 1.61732 2.54729 + endloop + endfacet + facet normal -0.88538 0.0655808 0.46022 + outer loop + vertex 0.789884 1.61732 2.54729 + vertex 0.79139 1.61388 2.55067 + vertex 0.791643 1.61902 2.55043 + endloop + endfacet + facet normal -0.855154 0.0666653 0.51407 + outer loop + vertex 0.79139 1.61388 2.55067 + vertex 0.793429 1.61579 2.55382 + vertex 0.791643 1.61902 2.55043 + endloop + endfacet + facet normal -0.855178 0.0667838 0.514014 + outer loop + vertex 0.793177 1.61077 2.55405 + vertex 0.793429 1.61579 2.55382 + vertex 0.79139 1.61388 2.55067 + endloop + endfacet + facet normal -0.925041 0.0518607 0.376309 + outer loop + vertex 0.788653 1.62068 2.54379 + vertex 0.788537 1.61576 2.54419 + vertex 0.789884 1.61732 2.54729 + endloop + endfacet + facet normal -0.921688 0.0602554 0.383224 + outer loop + vertex 0.790118 1.62229 2.54707 + vertex 0.788653 1.62068 2.54379 + vertex 0.789884 1.61732 2.54729 + endloop + endfacet + facet normal -0.884798 0.0619974 0.461833 + outer loop + vertex 0.789884 1.61732 2.54729 + vertex 0.791643 1.61902 2.55043 + vertex 0.790118 1.62229 2.54707 + endloop + endfacet + facet normal -0.884873 0.0618372 0.461711 + outer loop + vertex 0.790118 1.62229 2.54707 + vertex 0.791643 1.61902 2.55043 + vertex 0.7919 1.6241 2.55024 + endloop + endfacet + facet normal -0.857927 0.062274 0.509983 + outer loop + vertex 0.791643 1.61902 2.55043 + vertex 0.793659 1.62102 2.55357 + vertex 0.7919 1.6241 2.55024 + endloop + endfacet + facet normal -0.857733 0.0614016 0.510415 + outer loop + vertex 0.793429 1.61579 2.55382 + vertex 0.793659 1.62102 2.55357 + vertex 0.791643 1.61902 2.55043 + endloop + endfacet + facet normal -0.920667 0.0518769 0.386887 + outer loop + vertex 0.788839 1.6257 2.54357 + vertex 0.788653 1.62068 2.54379 + vertex 0.790118 1.62229 2.54707 + endloop + endfacet + facet normal -0.917397 0.0598552 0.393447 + outer loop + vertex 0.790373 1.62729 2.5469 + vertex 0.788839 1.6257 2.54357 + vertex 0.790118 1.62229 2.54707 + endloop + endfacet + facet normal -0.884634 0.0604809 0.462347 + outer loop + vertex 0.790118 1.62229 2.54707 + vertex 0.7919 1.6241 2.55024 + vertex 0.790373 1.62729 2.5469 + endloop + endfacet + facet normal -0.883359 0.0632482 0.464411 + outer loop + vertex 0.790373 1.62729 2.5469 + vertex 0.7919 1.6241 2.55024 + vertex 0.792174 1.62909 2.55008 + endloop + endfacet + facet normal -0.86065 0.0632891 0.505249 + outer loop + vertex 0.7919 1.6241 2.55024 + vertex 0.793853 1.62619 2.5533 + vertex 0.792174 1.62909 2.55008 + endloop + endfacet + facet normal -0.859566 0.0587848 0.507633 + outer loop + vertex 0.793659 1.62102 2.55357 + vertex 0.793853 1.62619 2.5533 + vertex 0.7919 1.6241 2.55024 + endloop + endfacet + facet normal -0.916754 0.0544788 0.39572 + outer loop + vertex 0.789045 1.63066 2.54336 + vertex 0.788839 1.6257 2.54357 + vertex 0.790373 1.62729 2.5469 + endloop + endfacet + facet normal -0.911812 0.066379 0.405208 + outer loop + vertex 0.790633 1.63223 2.54667 + vertex 0.789045 1.63066 2.54336 + vertex 0.790373 1.62729 2.5469 + endloop + endfacet + facet normal -0.884092 0.0675289 0.462408 + outer loop + vertex 0.790373 1.62729 2.5469 + vertex 0.792174 1.62909 2.55008 + vertex 0.790633 1.63223 2.54667 + endloop + endfacet + facet normal -0.883297 0.0692799 0.463666 + outer loop + vertex 0.790633 1.63223 2.54667 + vertex 0.792174 1.62909 2.55008 + vertex 0.79245 1.634 2.54987 + endloop + endfacet + facet normal -0.862485 0.0697027 0.50126 + outer loop + vertex 0.792174 1.62909 2.55008 + vertex 0.794113 1.63117 2.55313 + vertex 0.79245 1.634 2.54987 + endloop + endfacet + facet normal -0.860868 0.0628146 0.504936 + outer loop + vertex 0.793853 1.62619 2.5533 + vertex 0.794113 1.63117 2.55313 + vertex 0.792174 1.62909 2.55008 + endloop + endfacet + facet normal -0.912075 0.0687269 0.404222 + outer loop + vertex 0.789259 1.63557 2.54301 + vertex 0.789045 1.63066 2.54336 + vertex 0.790633 1.63223 2.54667 + endloop + endfacet + facet normal -0.908098 0.0782459 0.411382 + outer loop + vertex 0.790854 1.63722 2.54622 + vertex 0.789259 1.63557 2.54301 + vertex 0.790633 1.63223 2.54667 + endloop + endfacet + facet normal -0.885211 0.0815274 0.457989 + outer loop + vertex 0.790633 1.63223 2.54667 + vertex 0.79245 1.634 2.54987 + vertex 0.790854 1.63722 2.54622 + endloop + endfacet + facet normal -0.886611 0.0783725 0.455827 + outer loop + vertex 0.790854 1.63722 2.54622 + vertex 0.79245 1.634 2.54987 + vertex 0.792696 1.63897 2.5495 + endloop + endfacet + facet normal -0.866171 0.0802039 0.493269 + outer loop + vertex 0.79245 1.634 2.54987 + vertex 0.794387 1.63604 2.55294 + vertex 0.792696 1.63897 2.5495 + endloop + endfacet + facet normal -0.863427 0.0676138 0.499923 + outer loop + vertex 0.794113 1.63117 2.55313 + vertex 0.794387 1.63604 2.55294 + vertex 0.79245 1.634 2.54987 + endloop + endfacet + facet normal -0.908788 0.0841535 0.408684 + outer loop + vertex 0.789417 1.64035 2.54238 + vertex 0.789259 1.63557 2.54301 + vertex 0.790854 1.63722 2.54622 + endloop + endfacet + facet normal -0.905191 0.0931496 0.414672 + outer loop + vertex 0.790946 1.64277 2.54517 + vertex 0.789417 1.64035 2.54238 + vertex 0.790854 1.63722 2.54622 + endloop + endfacet + facet normal -0.889354 0.0988658 0.446403 + outer loop + vertex 0.790854 1.63722 2.54622 + vertex 0.792696 1.63897 2.5495 + vertex 0.790946 1.64277 2.54517 + endloop + endfacet + facet normal -0.898102 0.0791436 0.432607 + outer loop + vertex 0.790946 1.64277 2.54517 + vertex 0.792696 1.63897 2.5495 + vertex 0.792982 1.6439 2.54919 + endloop + endfacet + facet normal -0.873493 0.0806721 0.480106 + outer loop + vertex 0.792696 1.63897 2.5495 + vertex 0.794621 1.64088 2.55268 + vertex 0.792982 1.6439 2.54919 + endloop + endfacet + facet normal -0.87128 0.0686475 0.485961 + outer loop + vertex 0.794387 1.63604 2.55294 + vertex 0.794621 1.64088 2.55268 + vertex 0.792696 1.63897 2.5495 + endloop + endfacet + facet normal -0.927787 0.123711 0.352004 + outer loop + vertex 0.789917 1.64755 2.54156 + vertex 0.788849 1.64682 2.539 + vertex 0.789405 1.64421 2.54138 + endloop + endfacet + facet normal -0.907215 0.101947 0.408127 + outer loop + vertex 0.789405 1.64421 2.54138 + vertex 0.789417 1.64035 2.54238 + vertex 0.790946 1.64277 2.54517 + endloop + endfacet + facet normal -0.903536 0.116831 0.412279 + outer loop + vertex 0.789405 1.64421 2.54138 + vertex 0.790946 1.64277 2.54517 + vertex 0.789917 1.64755 2.54156 + endloop + endfacet + facet normal -0.912909 0.101918 0.395234 + outer loop + vertex 0.789917 1.64755 2.54156 + vertex 0.790946 1.64277 2.54517 + vertex 0.791604 1.64797 2.54535 + endloop + endfacet + facet normal -0.89866 0.0990068 0.427326 + outer loop + vertex 0.790946 1.64277 2.54517 + vertex 0.792982 1.6439 2.54919 + vertex 0.791604 1.64797 2.54535 + endloop + endfacet + facet normal -0.912299 0.0716229 0.403212 + outer loop + vertex 0.791604 1.64797 2.54535 + vertex 0.792982 1.6439 2.54919 + vertex 0.793328 1.64838 2.54918 + endloop + endfacet + facet normal -0.88418 0.0696311 0.461928 + outer loop + vertex 0.792982 1.6439 2.54919 + vertex 0.794753 1.64554 2.55233 + vertex 0.793328 1.64838 2.54918 + endloop + endfacet + facet normal -0.882638 0.0597199 0.466244 + outer loop + vertex 0.794621 1.64088 2.55268 + vertex 0.794753 1.64554 2.55233 + vertex 0.792982 1.6439 2.54919 + endloop + endfacet + facet normal -0.927757 0.12504 0.351612 + outer loop + vertex 0.788957 1.65056 2.53796 + vertex 0.788849 1.64682 2.539 + vertex 0.789917 1.64755 2.54156 + endloop + endfacet + facet normal -0.9329 0.112164 0.342224 + outer loop + vertex 0.790247 1.65272 2.54076 + vertex 0.788957 1.65056 2.53796 + vertex 0.789917 1.64755 2.54156 + endloop + endfacet + facet normal -0.911895 0.118612 0.392911 + outer loop + vertex 0.789917 1.64755 2.54156 + vertex 0.791604 1.64797 2.54535 + vertex 0.790247 1.65272 2.54076 + endloop + endfacet + facet normal -0.924401 0.0928698 0.369943 + outer loop + vertex 0.790247 1.65272 2.54076 + vertex 0.791604 1.64797 2.54535 + vertex 0.792313 1.65313 2.54583 + endloop + endfacet + facet normal -0.895011 0.0586131 0.442176 + outer loop + vertex 0.79381 1.65161 2.54972 + vertex 0.793328 1.64838 2.54918 + vertex 0.794662 1.6492 2.55177 + endloop + endfacet + facet normal -0.921257 0.0727228 0.382095 + outer loop + vertex 0.79381 1.65161 2.54972 + vertex 0.792313 1.65313 2.54583 + vertex 0.793328 1.64838 2.54918 + endloop + endfacet + facet normal -0.911742 0.0882306 0.401176 + outer loop + vertex 0.792313 1.65313 2.54583 + vertex 0.791604 1.64797 2.54535 + vertex 0.793328 1.64838 2.54918 + endloop + endfacet + facet normal -0.894065 0.0464255 0.445524 + outer loop + vertex 0.794662 1.6492 2.55177 + vertex 0.793328 1.64838 2.54918 + vertex 0.794753 1.64554 2.55233 + endloop + endfacet + facet normal -0.95321 0.129617 0.273111 + outer loop + vertex 0.789515 1.65724 2.53728 + vertex 0.788711 1.65644 2.53486 + vertex 0.789005 1.65428 2.53691 + endloop + endfacet + facet normal -0.932427 0.108809 0.344589 + outer loop + vertex 0.789005 1.65428 2.53691 + vertex 0.788957 1.65056 2.53796 + vertex 0.790247 1.65272 2.54076 + endloop + endfacet + facet normal -0.930589 0.116395 0.347068 + outer loop + vertex 0.789005 1.65428 2.53691 + vertex 0.790247 1.65272 2.54076 + vertex 0.789515 1.65724 2.53728 + endloop + endfacet + facet normal -0.933537 0.111117 0.340826 + outer loop + vertex 0.789515 1.65724 2.53728 + vertex 0.790247 1.65272 2.54076 + vertex 0.790962 1.65762 2.54113 + endloop + endfacet + facet normal -0.923434 0.107615 0.36836 + outer loop + vertex 0.790247 1.65272 2.54076 + vertex 0.792313 1.65313 2.54583 + vertex 0.790962 1.65762 2.54113 + endloop + endfacet + facet normal -0.9337 0.0834355 0.348198 + outer loop + vertex 0.790962 1.65762 2.54113 + vertex 0.792313 1.65313 2.54583 + vertex 0.792565 1.65875 2.54515 + endloop + endfacet + facet normal -0.920045 0.086878 0.382061 + outer loop + vertex 0.792313 1.65313 2.54583 + vertex 0.793864 1.65554 2.54901 + vertex 0.792565 1.65875 2.54515 + endloop + endfacet + facet normal -0.919206 0.0823734 0.385065 + outer loop + vertex 0.79381 1.65161 2.54972 + vertex 0.793864 1.65554 2.54901 + vertex 0.792313 1.65313 2.54583 + endloop + endfacet + facet normal -0.9531 0.132447 0.272135 + outer loop + vertex 0.788993 1.65994 2.53414 + vertex 0.788711 1.65644 2.53486 + vertex 0.789515 1.65724 2.53728 + endloop + endfacet + facet normal -0.957519 0.120028 0.262203 + outer loop + vertex 0.789986 1.66156 2.53703 + vertex 0.788993 1.65994 2.53414 + vertex 0.789515 1.65724 2.53728 + endloop + endfacet + facet normal -0.932693 0.121874 0.339455 + outer loop + vertex 0.789515 1.65724 2.53728 + vertex 0.790962 1.65762 2.54113 + vertex 0.789986 1.66156 2.53703 + endloop + endfacet + facet normal -0.94294 0.0974393 0.318386 + outer loop + vertex 0.789986 1.66156 2.53703 + vertex 0.790962 1.65762 2.54113 + vertex 0.791403 1.66259 2.54091 + endloop + endfacet + facet normal -0.933789 0.0977329 0.34422 + outer loop + vertex 0.790962 1.65762 2.54113 + vertex 0.792565 1.65875 2.54515 + vertex 0.791403 1.66259 2.54091 + endloop + endfacet + facet normal -0.943056 0.0731438 0.324493 + outer loop + vertex 0.791403 1.66259 2.54091 + vertex 0.792565 1.65875 2.54515 + vertex 0.792872 1.66384 2.5449 + endloop + endfacet + facet normal -0.921339 0.0746538 0.381524 + outer loop + vertex 0.792565 1.65875 2.54515 + vertex 0.794164 1.66054 2.54866 + vertex 0.792872 1.66384 2.5449 + endloop + endfacet + facet normal -0.922072 0.0815631 0.378325 + outer loop + vertex 0.793864 1.65554 2.54901 + vertex 0.794164 1.66054 2.54866 + vertex 0.792565 1.65875 2.54515 + endloop + endfacet + facet normal -0.956552 0.0961834 0.275242 + outer loop + vertex 0.789341 1.66518 2.53352 + vertex 0.788993 1.65994 2.53414 + vertex 0.789986 1.66156 2.53703 + endloop + endfacet + facet normal -0.951391 0.109376 0.28791 + outer loop + vertex 0.790542 1.66763 2.53656 + vertex 0.789341 1.66518 2.53352 + vertex 0.789986 1.66156 2.53703 + endloop + endfacet + facet normal -0.942688 0.11066 0.314792 + outer loop + vertex 0.789986 1.66156 2.53703 + vertex 0.791403 1.66259 2.54091 + vertex 0.790542 1.66763 2.53656 + endloop + endfacet + facet normal -0.954026 0.0850721 0.287396 + outer loop + vertex 0.790542 1.66763 2.53656 + vertex 0.791403 1.66259 2.54091 + vertex 0.791837 1.66761 2.54086 + endloop + endfacet + facet normal -0.943294 0.0844736 0.321029 + outer loop + vertex 0.791403 1.66259 2.54091 + vertex 0.792872 1.66384 2.5449 + vertex 0.791837 1.66761 2.54086 + endloop + endfacet + facet normal -0.952761 0.0575056 0.298226 + outer loop + vertex 0.791837 1.66761 2.54086 + vertex 0.792872 1.66384 2.5449 + vertex 0.793126 1.66886 2.54474 + endloop + endfacet + facet normal -0.923044 0.0585972 0.380204 + outer loop + vertex 0.792872 1.66384 2.5449 + vertex 0.794414 1.66575 2.54835 + vertex 0.793126 1.66886 2.54474 + endloop + endfacet + facet normal -0.924194 0.0671824 0.375968 + outer loop + vertex 0.794164 1.66054 2.54866 + vertex 0.794414 1.66575 2.54835 + vertex 0.792872 1.66384 2.5449 + endloop + endfacet + facet normal -0.933345 0.0128248 0.358751 + outer loop + vertex 0.79 1.67183 2.535 + vertex 0.789341 1.66518 2.53352 + vertex 0.790542 1.66763 2.53656 + endloop + endfacet + facet normal -0.533526 0.233105 0.813027 + outer loop + vertex 0.79 1.67183 2.535 + vertex 0.790542 1.66763 2.53656 + vertex 0.791385 1.675 2.535 + endloop + endfacet + facet normal -0.973995 0.147779 0.171742 + outer loop + vertex 0.791385 1.675 2.535 + vertex 0.790542 1.66763 2.53656 + vertex 0.791398 1.6726 2.53714 + endloop + endfacet + facet normal -0.949296 0.130244 0.286137 + outer loop + vertex 0.790542 1.66763 2.53656 + vertex 0.791837 1.66761 2.54086 + vertex 0.791398 1.6726 2.53714 + endloop + endfacet + facet normal -0.973605 0.07529 0.215465 + outer loop + vertex 0.791398 1.6726 2.53714 + vertex 0.791837 1.66761 2.54086 + vertex 0.79223 1.67256 2.54091 + endloop + endfacet + facet normal -0.953199 0.0728933 0.293424 + outer loop + vertex 0.791837 1.66761 2.54086 + vertex 0.793126 1.66886 2.54474 + vertex 0.79223 1.67256 2.54091 + endloop + endfacet + facet normal -0.961073 0.0487774 0.271957 + outer loop + vertex 0.79223 1.67256 2.54091 + vertex 0.793126 1.66886 2.54474 + vertex 0.793314 1.67382 2.54452 + endloop + endfacet + facet normal -0.924153 0.052201 0.378438 + outer loop + vertex 0.793126 1.66886 2.54474 + vertex 0.794538 1.67085 2.54791 + vertex 0.793314 1.67382 2.54452 + endloop + endfacet + facet normal -0.924535 0.0544812 0.377182 + outer loop + vertex 0.794414 1.66575 2.54835 + vertex 0.794538 1.67085 2.54791 + vertex 0.793126 1.66886 2.54474 + endloop + endfacet + facet normal -0.970173 0.15833 0.183562 + outer loop + vertex 0.791385 1.675 2.535 + vertex 0.791398 1.6726 2.53714 + vertex 0.792201 1.68 2.535 + endloop + endfacet + facet normal -0.993779 0.110885 0.010426 + outer loop + vertex 0.792201 1.68 2.535 + vertex 0.791398 1.6726 2.53714 + vertex 0.791947 1.67752 2.53719 + endloop + endfacet + facet normal -0.970792 0.106135 0.215169 + outer loop + vertex 0.791398 1.6726 2.53714 + vertex 0.79223 1.67256 2.54091 + vertex 0.791947 1.67752 2.53719 + endloop + endfacet + facet normal -0.984688 0.0651829 0.161679 + outer loop + vertex 0.791947 1.67752 2.53719 + vertex 0.79223 1.67256 2.54091 + vertex 0.792554 1.67765 2.54083 + endloop + endfacet + facet normal -0.961658 0.0653498 0.266352 + outer loop + vertex 0.79223 1.67256 2.54091 + vertex 0.793314 1.67382 2.54452 + vertex 0.792554 1.67765 2.54083 + endloop + endfacet + facet normal -0.968509 0.0436039 0.245132 + outer loop + vertex 0.792554 1.67765 2.54083 + vertex 0.793314 1.67382 2.54452 + vertex 0.793473 1.6784 2.54433 + endloop + endfacet + facet normal -0.921649 0.0477183 0.385078 + outer loop + vertex 0.793314 1.67382 2.54452 + vertex 0.794611 1.67563 2.5474 + vertex 0.793473 1.6784 2.54433 + endloop + endfacet + facet normal -0.922981 0.0554209 0.380833 + outer loop + vertex 0.794538 1.67085 2.54791 + vertex 0.794611 1.67563 2.5474 + vertex 0.793314 1.67382 2.54452 + endloop + endfacet + facet normal -0.996771 0.0735643 -0.0321755 + outer loop + vertex 0.792201 1.68 2.535 + vertex 0.791947 1.67752 2.53719 + vertex 0.79257 1.685 2.535 + endloop + endfacet + facet normal -0.996719 0.0804903 -0.00850167 + outer loop + vertex 0.79257 1.685 2.535 + vertex 0.791947 1.67752 2.53719 + vertex 0.792367 1.6827 2.53705 + endloop + endfacet + facet normal -0.983404 0.0840567 0.160785 + outer loop + vertex 0.791947 1.67752 2.53719 + vertex 0.792554 1.67765 2.54083 + vertex 0.792367 1.6827 2.53705 + endloop + endfacet + facet normal -0.989288 0.0622681 0.132028 + outer loop + vertex 0.792367 1.6827 2.53705 + vertex 0.792554 1.67765 2.54083 + vertex 0.792923 1.68306 2.54104 + endloop + endfacet + facet normal -0.922378 0.0508396 0.382928 + outer loop + vertex 0.793805 1.6817 2.54469 + vertex 0.793473 1.6784 2.54433 + vertex 0.794511 1.6793 2.54671 + endloop + endfacet + facet normal -0.963562 0.0685112 0.258562 + outer loop + vertex 0.793805 1.6817 2.54469 + vertex 0.792923 1.68306 2.54104 + vertex 0.793473 1.6784 2.54433 + endloop + endfacet + facet normal -0.96853 0.0565444 0.242388 + outer loop + vertex 0.792923 1.68306 2.54104 + vertex 0.792554 1.67765 2.54083 + vertex 0.793473 1.6784 2.54433 + endloop + endfacet + facet normal -0.922013 0.0467362 0.384328 + outer loop + vertex 0.794511 1.6793 2.54671 + vertex 0.793473 1.6784 2.54433 + vertex 0.794611 1.67563 2.5474 + endloop + endfacet + facet normal -0.997828 0.0480906 -0.0450092 + outer loop + vertex 0.79257 1.685 2.535 + vertex 0.792367 1.6827 2.53705 + vertex 0.792811 1.69 2.535 + endloop + endfacet + facet normal -0.99827 0.0546833 -0.0215974 + outer loop + vertex 0.792811 1.69 2.535 + vertex 0.792367 1.6827 2.53705 + vertex 0.792651 1.6877 2.53656 + endloop + endfacet + facet normal -0.988919 0.0691892 0.131349 + outer loop + vertex 0.792367 1.6827 2.53705 + vertex 0.792923 1.68306 2.54104 + vertex 0.792651 1.6877 2.53656 + endloop + endfacet + facet normal -0.995216 0.0312482 0.0925701 + outer loop + vertex 0.792651 1.6877 2.53656 + vertex 0.792923 1.68306 2.54104 + vertex 0.793016 1.6889 2.54007 + endloop + endfacet + facet normal -0.961361 0.0601434 0.26864 + outer loop + vertex 0.792923 1.68306 2.54104 + vertex 0.793876 1.68562 2.54388 + vertex 0.793016 1.6889 2.54007 + endloop + endfacet + facet normal -0.96315 0.0710523 0.259409 + outer loop + vertex 0.793805 1.6817 2.54469 + vertex 0.793876 1.68562 2.54388 + vertex 0.792923 1.68306 2.54104 + endloop + endfacet + facet normal -0.561933 -0.140213 -0.815212 + outer loop + vertex 0.795 1.69 2.53209 + vertex 0.793298 1.69147 2.53301 + vertex 0.795 1.695 2.53123 + endloop + endfacet + facet normal -0.700261 -0.481844 -0.526745 + outer loop + vertex 0.792811 1.69 2.535 + vertex 0.793298 1.69147 2.53301 + vertex 0.795 1.69 2.53209 + endloop + endfacet + facet normal 0.918458 0.175568 0.354416 + outer loop + vertex 0.792811 1.69 2.535 + vertex 0.792651 1.6877 2.53656 + vertex 0.793298 1.69147 2.53301 + endloop + endfacet + facet normal -0.984118 0.00202207 -0.177503 + outer loop + vertex 0.793298 1.69147 2.53301 + vertex 0.792651 1.6877 2.53656 + vertex 0.792772 1.69256 2.53594 + endloop + endfacet + facet normal -0.995205 0.0360803 0.0909133 + outer loop + vertex 0.792651 1.6877 2.53656 + vertex 0.793016 1.6889 2.54007 + vertex 0.792772 1.69256 2.53594 + endloop + endfacet + facet normal -0.996215 0.0267674 0.0827007 + outer loop + vertex 0.792772 1.69256 2.53594 + vertex 0.793016 1.6889 2.54007 + vertex 0.793112 1.69401 2.53957 + endloop + endfacet + facet normal -0.957613 0.0455713 0.284432 + outer loop + vertex 0.793016 1.6889 2.54007 + vertex 0.794057 1.69054 2.54331 + vertex 0.793112 1.69401 2.53957 + endloop + endfacet + facet normal -0.959361 0.0670296 0.274106 + outer loop + vertex 0.793876 1.68562 2.54388 + vertex 0.794057 1.69054 2.54331 + vertex 0.793016 1.6889 2.54007 + endloop + endfacet + facet normal -0.567029 0.0148443 -0.823564 + outer loop + vertex 0.795 1.695 2.53123 + vertex 0.79336 1.69615 2.53238 + vertex 0.795 1.7 2.53132 + endloop + endfacet + facet normal -0.616079 -0.0972278 -0.781661 + outer loop + vertex 0.793298 1.69147 2.53301 + vertex 0.79336 1.69615 2.53238 + vertex 0.795 1.695 2.53123 + endloop + endfacet + facet normal -0.984866 -0.010349 -0.17301 + outer loop + vertex 0.793298 1.69147 2.53301 + vertex 0.792772 1.69256 2.53594 + vertex 0.79336 1.69615 2.53238 + endloop + endfacet + facet normal -0.985659 -0.00587822 -0.168645 + outer loop + vertex 0.79336 1.69615 2.53238 + vertex 0.792772 1.69256 2.53594 + vertex 0.792799 1.69771 2.5356 + endloop + endfacet + facet normal -0.995977 0.0111788 0.0889054 + outer loop + vertex 0.792772 1.69256 2.53594 + vertex 0.793112 1.69401 2.53957 + vertex 0.792799 1.69771 2.5356 + endloop + endfacet + facet normal -0.99448 0.0252208 0.101849 + outer loop + vertex 0.792799 1.69771 2.5356 + vertex 0.793112 1.69401 2.53957 + vertex 0.793206 1.69863 2.53935 + endloop + endfacet + facet normal -0.948155 0.0345845 0.315922 + outer loop + vertex 0.793112 1.69401 2.53957 + vertex 0.794246 1.69545 2.54282 + vertex 0.793206 1.69863 2.53935 + endloop + endfacet + facet normal -0.950777 0.0669586 0.302554 + outer loop + vertex 0.794057 1.69054 2.54331 + vertex 0.794246 1.69545 2.54282 + vertex 0.793112 1.69401 2.53957 + endloop + endfacet + facet normal -0.424511 -0.226206 -0.876711 + outer loop + vertex 0.795 1.7 2.53132 + vertex 0.793206 1.70226 2.53161 + vertex 0.795 1.705 2.53003 + endloop + endfacet + facet normal -0.310221 -0.127108 -0.942129 + outer loop + vertex 0.79336 1.69615 2.53238 + vertex 0.793206 1.70226 2.53161 + vertex 0.795 1.7 2.53132 + endloop + endfacet + facet normal -0.98762 -0.0439514 -0.15058 + outer loop + vertex 0.79336 1.69615 2.53238 + vertex 0.792799 1.69771 2.5356 + vertex 0.793206 1.70226 2.53161 + endloop + endfacet + facet normal -0.996339 0.0151953 -0.0841284 + outer loop + vertex 0.793206 1.70226 2.53161 + vertex 0.792799 1.69771 2.5356 + vertex 0.792861 1.70317 2.53586 + endloop + endfacet + facet normal -0.942065 0.0467249 0.332161 + outer loop + vertex 0.793523 1.70191 2.53979 + vertex 0.793206 1.69863 2.53935 + vertex 0.79421 1.69933 2.5421 + endloop + endfacet + facet normal -0.979832 0.0695802 0.187319 + outer loop + vertex 0.793523 1.70191 2.53979 + vertex 0.792861 1.70317 2.53586 + vertex 0.793206 1.69863 2.53935 + endloop + endfacet + facet normal -0.994291 0.00624806 0.106517 + outer loop + vertex 0.792861 1.70317 2.53586 + vertex 0.792799 1.69771 2.5356 + vertex 0.793206 1.69863 2.53935 + endloop + endfacet + facet normal -0.942259 0.0526347 0.330723 + outer loop + vertex 0.79421 1.69933 2.5421 + vertex 0.793206 1.69863 2.53935 + vertex 0.794246 1.69545 2.54282 + endloop + endfacet + facet normal -0.864647 -0.355942 -0.35453 + outer loop + vertex 0.795 1.705 2.53003 + vertex 0.792954 1.71 2.53 + vertex 0.795 1.70503 2.53 + endloop + endfacet + facet normal -0.462632 -0.194505 -0.864951 + outer loop + vertex 0.795 1.705 2.53003 + vertex 0.793206 1.70226 2.53161 + vertex 0.792954 1.71 2.53 + endloop + endfacet + facet normal -0.958246 -0.0876523 -0.272178 + outer loop + vertex 0.793206 1.70226 2.53161 + vertex 0.792673 1.70806 2.53161 + vertex 0.792954 1.71 2.53 + endloop + endfacet + facet normal -0.993955 -0.0911275 -0.061225 + outer loop + vertex 0.793206 1.70226 2.53161 + vertex 0.792861 1.70317 2.53586 + vertex 0.792673 1.70806 2.53161 + endloop + endfacet + facet normal -0.997955 0.0156195 0.0619857 + outer loop + vertex 0.792673 1.70806 2.53161 + vertex 0.792861 1.70317 2.53586 + vertex 0.792895 1.70884 2.53499 + endloop + endfacet + facet normal -0.973876 0.0402698 0.223482 + outer loop + vertex 0.792861 1.70317 2.53586 + vertex 0.793671 1.70569 2.53894 + vertex 0.792895 1.70884 2.53499 + endloop + endfacet + facet normal -0.978236 0.0814588 0.190838 + outer loop + vertex 0.793523 1.70191 2.53979 + vertex 0.793671 1.70569 2.53894 + vertex 0.792861 1.70317 2.53586 + endloop + endfacet + facet normal -0.985422 0.00117472 -0.170126 + outer loop + vertex 0.792954 1.71 2.53 + vertex 0.792673 1.70806 2.53161 + vertex 0.79296 1.715 2.53 + endloop + endfacet + facet normal -0.957563 -0.027115 -0.286944 + outer loop + vertex 0.79296 1.715 2.53 + vertex 0.792673 1.70806 2.53161 + vertex 0.792665 1.71272 2.5312 + endloop + endfacet + facet normal -0.997899 0.00395305 0.0646686 + outer loop + vertex 0.792673 1.70806 2.53161 + vertex 0.792895 1.70884 2.53499 + vertex 0.792665 1.71272 2.5312 + endloop + endfacet + facet normal -0.99074 0.0600949 0.121753 + outer loop + vertex 0.792665 1.71272 2.5312 + vertex 0.792895 1.70884 2.53499 + vertex 0.793126 1.71375 2.53444 + endloop + endfacet + facet normal -0.958836 0.0755257 0.273732 + outer loop + vertex 0.792895 1.70884 2.53499 + vertex 0.793963 1.71044 2.53829 + vertex 0.793126 1.71375 2.53444 + endloop + endfacet + facet normal -0.959683 0.0951875 0.264475 + outer loop + vertex 0.793671 1.70569 2.53894 + vertex 0.793963 1.71044 2.53829 + vertex 0.792895 1.70884 2.53499 + endloop + endfacet + facet normal -0.255401 -0.00193629 -0.966833 + outer loop + vertex 0.795 1.715 2.52796 + vertex 0.793253 1.71621 2.52842 + vertex 0.795 1.72 2.52795 + endloop + endfacet + facet normal -0.565444 -0.600424 -0.565477 + outer loop + vertex 0.79296 1.715 2.53 + vertex 0.793253 1.71621 2.52842 + vertex 0.795 1.715 2.52796 + endloop + endfacet + facet normal 0.98831 -0.052596 0.143095 + outer loop + vertex 0.79296 1.715 2.53 + vertex 0.792665 1.71272 2.5312 + vertex 0.793253 1.71621 2.52842 + endloop + endfacet + facet normal -0.986514 0.0398175 -0.158757 + outer loop + vertex 0.793253 1.71621 2.52842 + vertex 0.792665 1.71272 2.5312 + vertex 0.792911 1.71721 2.5308 + endloop + endfacet + facet normal -0.99062 0.065055 0.120164 + outer loop + vertex 0.792665 1.71272 2.5312 + vertex 0.793126 1.71375 2.53444 + vertex 0.792911 1.71721 2.5308 + endloop + endfacet + facet normal -0.985367 0.0907584 0.144273 + outer loop + vertex 0.792911 1.71721 2.5308 + vertex 0.793126 1.71375 2.53444 + vertex 0.793462 1.71826 2.5339 + endloop + endfacet + facet normal -0.945665 0.107442 0.306879 + outer loop + vertex 0.793126 1.71375 2.53444 + vertex 0.794286 1.71522 2.5375 + vertex 0.793462 1.71826 2.5339 + endloop + endfacet + facet normal -0.945882 0.113831 0.303891 + outer loop + vertex 0.793963 1.71044 2.53829 + vertex 0.794286 1.71522 2.5375 + vertex 0.793126 1.71375 2.53444 + endloop + endfacet + facet normal -0.101416 0.0178812 -0.994683 + outer loop + vertex 0.795 1.72 2.52795 + vertex 0.793485 1.72077 2.52812 + vertex 0.795 1.725 2.52804 + endloop + endfacet + facet normal -0.139482 -0.0580787 -0.98852 + outer loop + vertex 0.793253 1.71621 2.52842 + vertex 0.793485 1.72077 2.52812 + vertex 0.795 1.72 2.52795 + endloop + endfacet + facet normal -0.986526 0.0397096 -0.158714 + outer loop + vertex 0.793253 1.71621 2.52842 + vertex 0.792911 1.71721 2.5308 + vertex 0.793485 1.72077 2.52812 + endloop + endfacet + facet normal -0.991388 0.0848583 -0.0997405 + outer loop + vertex 0.793485 1.72077 2.52812 + vertex 0.792911 1.71721 2.5308 + vertex 0.793348 1.72215 2.53066 + endloop + endfacet + facet normal -0.940297 0.130378 0.314394 + outer loop + vertex 0.793873 1.72151 2.53378 + vertex 0.793462 1.71826 2.5339 + vertex 0.794393 1.71917 2.53631 + endloop + endfacet + facet normal -0.972971 0.130033 0.190838 + outer loop + vertex 0.793873 1.72151 2.53378 + vertex 0.793348 1.72215 2.53066 + vertex 0.793462 1.71826 2.5339 + endloop + endfacet + facet normal -0.985359 0.090942 0.14421 + outer loop + vertex 0.793348 1.72215 2.53066 + vertex 0.792911 1.71721 2.5308 + vertex 0.793462 1.71826 2.5339 + endloop + endfacet + facet normal -0.940352 0.121705 0.317688 + outer loop + vertex 0.794393 1.71917 2.53631 + vertex 0.793462 1.71826 2.5339 + vertex 0.794286 1.71522 2.5375 + endloop + endfacet + facet normal 0.162096 0.0315565 -0.98627 + outer loop + vertex 0.795 1.725 2.52804 + vertex 0.79378 1.72613 2.52788 + vertex 0.795 1.73 2.5282 + endloop + endfacet + facet normal 0.0877017 -0.0498852 -0.994897 + outer loop + vertex 0.793485 1.72077 2.52812 + vertex 0.79378 1.72613 2.52788 + vertex 0.795 1.725 2.52804 + endloop + endfacet + facet normal -0.975902 0.117222 0.184048 + outer loop + vertex 0.793709 1.72616 2.53003 + vertex 0.793348 1.72215 2.53066 + vertex 0.793924 1.72426 2.53238 + endloop + endfacet + facet normal -0.995848 0.084395 -0.03412 + outer loop + vertex 0.793709 1.72616 2.53003 + vertex 0.79378 1.72613 2.52788 + vertex 0.793348 1.72215 2.53066 + endloop + endfacet + facet normal -0.995355 0.0510709 -0.081616 + outer loop + vertex 0.79378 1.72613 2.52788 + vertex 0.793485 1.72077 2.52812 + vertex 0.793348 1.72215 2.53066 + endloop + endfacet + facet normal -0.975544 0.113934 0.187969 + outer loop + vertex 0.793924 1.72426 2.53238 + vertex 0.793348 1.72215 2.53066 + vertex 0.793873 1.72151 2.53378 + endloop + endfacet + facet normal 0.623137 -0.188263 -0.759116 + outer loop + vertex 0.795 1.73 2.5282 + vertex 0.794207 1.73102 2.52729 + vertex 0.795 1.735 2.52696 + endloop + endfacet + facet normal 0.656896 -0.145122 -0.739883 + outer loop + vertex 0.79378 1.72613 2.52788 + vertex 0.794207 1.73102 2.52729 + vertex 0.795 1.73 2.5282 + endloop + endfacet + facet normal -0.996117 0.0877212 0.00753652 + outer loop + vertex 0.79378 1.72613 2.52788 + vertex 0.794133 1.73003 2.52908 + vertex 0.794207 1.73102 2.52729 + endloop + endfacet + facet normal -0.994346 0.100515 -0.0342477 + outer loop + vertex 0.793709 1.72616 2.53003 + vertex 0.794133 1.73003 2.52908 + vertex 0.79378 1.72613 2.52788 + endloop + endfacet + facet normal 0.872695 -0.0896739 -0.47996 + outer loop + vertex 0.795 1.73743 2.525 + vertex 0.794554 1.73891 2.52391 + vertex 0.795 1.74 2.52452 + endloop + endfacet + facet normal -0.973697 0.182856 -0.135934 + outer loop + vertex 0.795 1.735 2.52696 + vertex 0.794207 1.73102 2.52729 + vertex 0.795 1.73726 2.53 + endloop + endfacet + facet normal -0.968631 -0.142549 0.203551 + outer loop + vertex 0.795 1.73743 2.525 + vertex 0.795 1.74 2.5268 + vertex 0.794554 1.73891 2.52391 + endloop + endfacet + facet normal -0.992954 0.116155 0.0234542 + outer loop + vertex 0.795 1.73726 2.53 + vertex 0.794207 1.73102 2.52729 + vertex 0.794133 1.73003 2.52908 + endloop + endfacet + facet normal 0.616933 0.174637 -0.767395 + outer loop + vertex 0.795 1.74 2.52452 + vertex 0.794554 1.73891 2.52391 + vertex 0.795 1.74211 2.525 + endloop + endfacet + facet normal -0.988418 0.0984871 0.11546 + outer loop + vertex 0.795 1.74211 2.525 + vertex 0.794554 1.73891 2.52391 + vertex 0.795 1.74 2.5268 + endloop + endfacet + facet normal 0.97955 -0.0385704 -0.197469 + outer loop + vertex 0.8 1.24662 2.525 + vertex 0.799722 1.24991 2.52298 + vertex 0.8 1.25 2.52434 + endloop + endfacet + facet normal 0.0838962 0.527028 0.845697 + outer loop + vertex 0.8 1.24662 2.525 + vertex 0.800829 1.24861 2.52368 + vertex 0.799722 1.24991 2.52298 + endloop + endfacet + facet normal 0.838673 -0.0195949 -0.544283 + outer loop + vertex 0.8 1.25 2.52434 + vertex 0.799429 1.2538 2.52332 + vertex 0.8 1.255 2.52416 + endloop + endfacet + facet normal 0.974423 0.0916153 -0.2052 + outer loop + vertex 0.799722 1.24991 2.52298 + vertex 0.799429 1.2538 2.52332 + vertex 0.8 1.25 2.52434 + endloop + endfacet + facet normal -0.0203703 -0.0897364 0.995757 + outer loop + vertex 0.799722 1.24991 2.52298 + vertex 0.800998 1.25231 2.52322 + vertex 0.799429 1.2538 2.52332 + endloop + endfacet + facet normal -0.415666 0.130161 0.900156 + outer loop + vertex 0.800829 1.24861 2.52368 + vertex 0.800998 1.25231 2.52322 + vertex 0.799722 1.24991 2.52298 + endloop + endfacet + facet normal 0.430571 0.0522884 -0.901041 + outer loop + vertex 0.8 1.255 2.52416 + vertex 0.798962 1.25863 2.52387 + vertex 0.8 1.26 2.52445 + endloop + endfacet + facet normal 0.705587 0.147247 -0.693156 + outer loop + vertex 0.799429 1.2538 2.52332 + vertex 0.798962 1.25863 2.52387 + vertex 0.8 1.255 2.52416 + endloop + endfacet + facet normal -0.284865 -0.360626 0.888145 + outer loop + vertex 0.801411 1.25543 2.52462 + vertex 0.799429 1.2538 2.52332 + vertex 0.800998 1.25231 2.52322 + endloop + endfacet + facet normal -0.191918 -0.457575 0.868212 + outer loop + vertex 0.801411 1.25543 2.52462 + vertex 0.798964 1.25798 2.52542 + vertex 0.799429 1.2538 2.52332 + endloop + endfacet + facet normal -0.995061 -0.0918456 -0.0376608 + outer loop + vertex 0.798964 1.25798 2.52542 + vertex 0.798962 1.25863 2.52387 + vertex 0.799429 1.2538 2.52332 + endloop + endfacet + facet normal -0.736342 -0.658292 -0.156374 + outer loop + vertex 0.801411 1.25543 2.52462 + vertex 0.799651 1.25669 2.5276 + vertex 0.798964 1.25798 2.52542 + endloop + endfacet + facet normal 0.355035 0.120545 -0.927049 + outer loop + vertex 0.8 1.26 2.52445 + vertex 0.798962 1.25863 2.52387 + vertex 0.8 1.26423 2.525 + endloop + endfacet + facet normal -0.605986 0.313339 -0.731163 + outer loop + vertex 0.8 1.26423 2.525 + vertex 0.798651 1.26394 2.52599 + vertex 0.8 1.265 2.52533 + endloop + endfacet + facet normal -0.608139 0.26335 -0.748875 + outer loop + vertex 0.8 1.26423 2.525 + vertex 0.798962 1.25863 2.52387 + vertex 0.798651 1.26394 2.52599 + endloop + endfacet + facet normal -0.998523 -0.0504476 -0.0201639 + outer loop + vertex 0.798962 1.25863 2.52387 + vertex 0.798964 1.25798 2.52542 + vertex 0.798651 1.26394 2.52599 + endloop + endfacet + facet normal -0.998638 -0.0517402 -0.00669796 + outer loop + vertex 0.798964 1.25798 2.52542 + vertex 0.798805 1.26055 2.52911 + vertex 0.798651 1.26394 2.52599 + endloop + endfacet + facet normal -0.953341 -0.265126 0.144392 + outer loop + vertex 0.799651 1.25669 2.5276 + vertex 0.798805 1.26055 2.52911 + vertex 0.798964 1.25798 2.52542 + endloop + endfacet + facet normal -0.945666 -0.0652791 -0.318519 + outer loop + vertex 0.8 1.265 2.52533 + vertex 0.799766 1.27 2.525 + vertex 0.8 1.26661 2.525 + endloop + endfacet + facet normal -0.38862 -0.0787725 -0.918025 + outer loop + vertex 0.8 1.265 2.52533 + vertex 0.798651 1.26394 2.52599 + vertex 0.799766 1.27 2.525 + endloop + endfacet + facet normal -0.645958 -0.00613688 -0.763348 + outer loop + vertex 0.798651 1.26394 2.52599 + vertex 0.798503 1.26833 2.52608 + vertex 0.799766 1.27 2.525 + endloop + endfacet + facet normal -0.996317 -0.0780858 -0.035413 + outer loop + vertex 0.798445 1.26468 2.53016 + vertex 0.798651 1.26394 2.52599 + vertex 0.798805 1.26055 2.52911 + endloop + endfacet + facet normal -0.997789 -0.0531136 -0.0399416 + outer loop + vertex 0.798445 1.26468 2.53016 + vertex 0.798266 1.26874 2.52923 + vertex 0.798651 1.26394 2.52599 + endloop + endfacet + facet normal -0.996954 -0.0320466 -0.0711098 + outer loop + vertex 0.798266 1.26874 2.52923 + vertex 0.798503 1.26833 2.52608 + vertex 0.798651 1.26394 2.52599 + endloop + endfacet + facet normal -0.989639 -0.0109224 0.143165 + outer loop + vertex 0.798445 1.26468 2.53016 + vertex 0.798795 1.26698 2.53276 + vertex 0.798266 1.26874 2.52923 + endloop + endfacet + facet normal -0.4218 0.452537 -0.785682 + outer loop + vertex 0.8 1.27033 2.525 + vertex 0.798621 1.27206 2.52674 + vertex 0.8 1.275 2.52769 + endloop + endfacet + facet normal -0.516177 0.366061 -0.774313 + outer loop + vertex 0.8 1.27033 2.525 + vertex 0.799766 1.27 2.525 + vertex 0.798621 1.27206 2.52674 + endloop + endfacet + facet normal -0.743561 0.138633 -0.654139 + outer loop + vertex 0.799766 1.27 2.525 + vertex 0.798503 1.26833 2.52608 + vertex 0.798621 1.27206 2.52674 + endloop + endfacet + facet normal -0.995654 0.0457154 -0.0811426 + outer loop + vertex 0.798503 1.26833 2.52608 + vertex 0.798266 1.26874 2.52923 + vertex 0.798621 1.27206 2.52674 + endloop + endfacet + facet normal -0.990323 0.00190466 -0.13877 + outer loop + vertex 0.798621 1.27206 2.52674 + vertex 0.798266 1.26874 2.52923 + vertex 0.79808 1.27458 2.53064 + endloop + endfacet + facet normal -0.984923 -0.0695198 0.158409 + outer loop + vertex 0.798266 1.26874 2.52923 + vertex 0.798817 1.27103 2.53366 + vertex 0.79808 1.27458 2.53064 + endloop + endfacet + facet normal -0.990367 -0.0251018 0.136176 + outer loop + vertex 0.798795 1.26698 2.53276 + vertex 0.798817 1.27103 2.53366 + vertex 0.798266 1.26874 2.52923 + endloop + endfacet + facet normal -0.79464 -0.067576 -0.603308 + outer loop + vertex 0.8 1.275 2.52769 + vertex 0.797821 1.28 2.53 + vertex 0.8 1.28 2.52713 + endloop + endfacet + facet normal -0.140466 0.364149 -0.920687 + outer loop + vertex 0.798621 1.27206 2.52674 + vertex 0.797821 1.28 2.53 + vertex 0.8 1.275 2.52769 + endloop + endfacet + facet normal -0.99325 -0.0591214 -0.0998001 + outer loop + vertex 0.798621 1.27206 2.52674 + vertex 0.79808 1.27458 2.53064 + vertex 0.797821 1.28 2.53 + endloop + endfacet + facet normal -0.992098 -0.0602688 -0.11004 + outer loop + vertex 0.797821 1.28 2.53 + vertex 0.79808 1.27458 2.53064 + vertex 0.797578 1.28036 2.53199 + endloop + endfacet + facet normal -0.977563 -0.124734 0.169743 + outer loop + vertex 0.79808 1.27458 2.53064 + vertex 0.798613 1.27594 2.5347 + vertex 0.797578 1.28036 2.53199 + endloop + endfacet + facet normal -0.985372 -0.0736299 0.153689 + outer loop + vertex 0.798817 1.27103 2.53366 + vertex 0.798613 1.27594 2.5347 + vertex 0.79808 1.27458 2.53064 + endloop + endfacet + facet normal -0.991154 -0.0790929 -0.106571 + outer loop + vertex 0.797821 1.28 2.53 + vertex 0.797578 1.28036 2.53199 + vertex 0.797422 1.285 2.53 + endloop + endfacet + facet normal -0.871536 -0.217871 -0.439269 + outer loop + vertex 0.797422 1.285 2.53 + vertex 0.797578 1.28036 2.53199 + vertex 0.796805 1.28488 2.53128 + endloop + endfacet + facet normal -0.977165 -0.122085 0.173908 + outer loop + vertex 0.798309 1.27979 2.5357 + vertex 0.797578 1.28036 2.53199 + vertex 0.798613 1.27594 2.5347 + endloop + endfacet + facet normal -0.972889 -0.15964 0.16734 + outer loop + vertex 0.798309 1.27979 2.5357 + vertex 0.797498 1.28395 2.53496 + vertex 0.797578 1.28036 2.53199 + endloop + endfacet + facet normal -0.978447 -0.143904 0.148095 + outer loop + vertex 0.797498 1.28395 2.53496 + vertex 0.796805 1.28488 2.53128 + vertex 0.797578 1.28036 2.53199 + endloop + endfacet + facet normal -0.949053 -0.133904 0.285251 + outer loop + vertex 0.798309 1.27979 2.5357 + vertex 0.798768 1.28169 2.53812 + vertex 0.797498 1.28395 2.53496 + endloop + endfacet + facet normal -0.889458 -0.125764 -0.439372 + outer loop + vertex 0.797422 1.285 2.53 + vertex 0.796805 1.28488 2.53128 + vertex 0.796715 1.29 2.53 + endloop + endfacet + facet normal -0.991133 -0.0484384 -0.123726 + outer loop + vertex 0.796715 1.29 2.53 + vertex 0.796805 1.28488 2.53128 + vertex 0.796517 1.28765 2.53251 + endloop + endfacet + facet normal -0.976038 -0.164507 0.142433 + outer loop + vertex 0.796805 1.28488 2.53128 + vertex 0.797498 1.28395 2.53496 + vertex 0.796517 1.28765 2.53251 + endloop + endfacet + facet normal -0.970526 -0.118372 0.20992 + outer loop + vertex 0.796517 1.28765 2.53251 + vertex 0.797498 1.28395 2.53496 + vertex 0.797103 1.28941 2.53621 + endloop + endfacet + facet normal -0.946766 -0.135474 0.292029 + outer loop + vertex 0.797498 1.28395 2.53496 + vertex 0.79857 1.28565 2.53922 + vertex 0.797103 1.28941 2.53621 + endloop + endfacet + facet normal -0.948628 -0.127795 0.289437 + outer loop + vertex 0.798768 1.28169 2.53812 + vertex 0.79857 1.28565 2.53922 + vertex 0.797498 1.28395 2.53496 + endloop + endfacet + facet normal 0.905959 0.388424 -0.16842 + outer loop + vertex 0.795189 1.29317 2.52911 + vertex 0.795 1.294 2.53 + vertex 0.796715 1.29 2.53 + endloop + endfacet + facet normal -0.906621 -0.392727 0.154288 + outer loop + vertex 0.795189 1.29317 2.52911 + vertex 0.796715 1.29 2.53 + vertex 0.795948 1.29244 2.53169 + endloop + endfacet + facet normal -0.963939 -0.151989 -0.218452 + outer loop + vertex 0.795948 1.29244 2.53169 + vertex 0.796715 1.29 2.53 + vertex 0.796517 1.28765 2.53251 + endloop + endfacet + facet normal -0.977422 -0.0830754 0.194281 + outer loop + vertex 0.796517 1.28765 2.53251 + vertex 0.797103 1.28941 2.53621 + vertex 0.795948 1.29244 2.53169 + endloop + endfacet + facet normal -0.977188 -0.0783234 0.197407 + outer loop + vertex 0.795948 1.29244 2.53169 + vertex 0.797103 1.28941 2.53621 + vertex 0.796471 1.29424 2.535 + endloop + endfacet + facet normal -0.945592 -0.130035 0.29824 + outer loop + vertex 0.798364 1.28973 2.54035 + vertex 0.797103 1.28941 2.53621 + vertex 0.79857 1.28565 2.53922 + endloop + endfacet + facet normal -0.948538 -0.108622 0.29745 + outer loop + vertex 0.798364 1.28973 2.54035 + vertex 0.797542 1.29409 2.53932 + vertex 0.797103 1.28941 2.53621 + endloop + endfacet + facet normal -0.968983 -0.0671332 0.237834 + outer loop + vertex 0.797542 1.29409 2.53932 + vertex 0.796471 1.29424 2.535 + vertex 0.797103 1.28941 2.53621 + endloop + endfacet + facet normal -0.925491 -0.0874578 0.368534 + outer loop + vertex 0.798364 1.28973 2.54035 + vertex 0.799103 1.29227 2.54281 + vertex 0.797542 1.29409 2.53932 + endloop + endfacet + facet normal -0.955245 0.0431966 0.292645 + outer loop + vertex 0.795607 1.29778 2.52979 + vertex 0.795189 1.29317 2.52911 + vertex 0.795948 1.29244 2.53169 + endloop + endfacet + facet normal -0.96309 0.0336051 0.267075 + outer loop + vertex 0.796316 1.29835 2.53227 + vertex 0.795607 1.29778 2.52979 + vertex 0.795948 1.29244 2.53169 + endloop + endfacet + facet normal -0.990295 0.0487663 0.130148 + outer loop + vertex 0.795948 1.29244 2.53169 + vertex 0.796471 1.29424 2.535 + vertex 0.796316 1.29835 2.53227 + endloop + endfacet + facet normal -0.999396 -0.0182832 0.0295452 + outer loop + vertex 0.796316 1.29835 2.53227 + vertex 0.796471 1.29424 2.535 + vertex 0.796426 1.2986 2.53616 + endloop + endfacet + facet normal -0.968601 -0.0734525 0.237524 + outer loop + vertex 0.796471 1.29424 2.535 + vertex 0.797542 1.29409 2.53932 + vertex 0.796426 1.2986 2.53616 + endloop + endfacet + facet normal -0.969043 -0.0752198 0.235154 + outer loop + vertex 0.796426 1.2986 2.53616 + vertex 0.797542 1.29409 2.53932 + vertex 0.797402 1.29948 2.54047 + endloop + endfacet + facet normal -0.926036 -0.10147 0.363541 + outer loop + vertex 0.797542 1.29409 2.53932 + vertex 0.798936 1.29652 2.54355 + vertex 0.797402 1.29948 2.54047 + endloop + endfacet + facet normal -0.926578 -0.0996332 0.362665 + outer loop + vertex 0.799103 1.29227 2.54281 + vertex 0.798936 1.29652 2.54355 + vertex 0.797542 1.29409 2.53932 + endloop + endfacet + facet normal 0.584158 -0.385173 0.714424 + outer loop + vertex 0.795 1.305 2.53418 + vertex 0.795607 1.29778 2.52979 + vertex 0.8 1.30483 2.53 + endloop + endfacet + facet normal 0.422359 0.772744 0.473792 + outer loop + vertex 0.795 1.305 2.53418 + vertex 0.8 1.30483 2.53 + vertex 0.799689 1.305 2.53 + endloop + endfacet + facet normal -0.844137 0.522399 0.120546 + outer loop + vertex 0.795607 1.29778 2.52979 + vertex 0.796316 1.29835 2.53227 + vertex 0.8 1.30483 2.53 + endloop + endfacet + facet normal -0.674902 0.345636 -0.651953 + outer loop + vertex 0.8 1.305 2.53009 + vertex 0.8 1.30483 2.53 + vertex 0.795257 1.305 2.535 + endloop + endfacet + facet normal -0.712604 0.166126 -0.681614 + outer loop + vertex 0.796316 1.29835 2.53227 + vertex 0.795257 1.305 2.535 + vertex 0.8 1.30483 2.53 + endloop + endfacet + facet normal -0.984183 -0.172772 0.0391585 + outer loop + vertex 0.796316 1.29835 2.53227 + vertex 0.796426 1.2986 2.53616 + vertex 0.795257 1.305 2.535 + endloop + endfacet + facet normal -0.957742 -0.128222 0.257467 + outer loop + vertex 0.795257 1.305 2.535 + vertex 0.796426 1.2986 2.53616 + vertex 0.796243 1.30265 2.5375 + endloop + endfacet + facet normal -0.961972 -0.123796 0.243483 + outer loop + vertex 0.796426 1.2986 2.53616 + vertex 0.797402 1.29948 2.54047 + vertex 0.796243 1.30265 2.5375 + endloop + endfacet + facet normal -0.954877 -0.0817707 0.285522 + outer loop + vertex 0.796243 1.30265 2.5375 + vertex 0.797402 1.29948 2.54047 + vertex 0.797316 1.30488 2.54173 + endloop + endfacet + facet normal -0.922096 -0.101716 0.373354 + outer loop + vertex 0.797402 1.29948 2.54047 + vertex 0.798922 1.3019 2.54488 + vertex 0.797316 1.30488 2.54173 + endloop + endfacet + facet normal -0.924311 -0.0939899 0.369884 + outer loop + vertex 0.798936 1.29652 2.54355 + vertex 0.798922 1.3019 2.54488 + vertex 0.797402 1.29948 2.54047 + endloop + endfacet + facet normal 0.96869 0.220254 -0.114573 + outer loop + vertex 0.794545 1.3072 2.5332 + vertex 0.795 1.30613 2.535 + vertex 0.795257 1.305 2.535 + endloop + endfacet + facet normal -0.965408 -0.126175 0.228182 + outer loop + vertex 0.794545 1.3072 2.5332 + vertex 0.795257 1.305 2.535 + vertex 0.795394 1.30726 2.53683 + endloop + endfacet + facet normal -0.958972 -0.140974 0.245965 + outer loop + vertex 0.795394 1.30726 2.53683 + vertex 0.795257 1.305 2.535 + vertex 0.796243 1.30265 2.5375 + endloop + endfacet + facet normal -0.94278 -0.129079 0.307417 + outer loop + vertex 0.796243 1.30265 2.5375 + vertex 0.797316 1.30488 2.54173 + vertex 0.795394 1.30726 2.53683 + endloop + endfacet + facet normal -0.941463 -0.0950425 0.323443 + outer loop + vertex 0.795394 1.30726 2.53683 + vertex 0.797316 1.30488 2.54173 + vertex 0.796982 1.31023 2.54233 + endloop + endfacet + facet normal -0.925803 -0.0987109 0.36489 + outer loop + vertex 0.797316 1.30488 2.54173 + vertex 0.8 1.31 2.54992 + vertex 0.796982 1.31023 2.54233 + endloop + endfacet + facet normal -0.923226 -0.10682 0.369112 + outer loop + vertex 0.798922 1.3019 2.54488 + vertex 0.8 1.31 2.54992 + vertex 0.797316 1.30488 2.54173 + endloop + endfacet + facet normal -0.953539 -0.198478 0.22665 + outer loop + vertex 0.793888 1.3109 2.53368 + vertex 0.794545 1.3072 2.5332 + vertex 0.795394 1.30726 2.53683 + endloop + endfacet + facet normal -0.948808 -0.154223 0.275643 + outer loop + vertex 0.794827 1.31245 2.53778 + vertex 0.793888 1.3109 2.53368 + vertex 0.795394 1.30726 2.53683 + endloop + endfacet + facet normal -0.919886 -0.165708 0.355459 + outer loop + vertex 0.795394 1.30726 2.53683 + vertex 0.796982 1.31023 2.54233 + vertex 0.794827 1.31245 2.53778 + endloop + endfacet + facet normal -0.917999 -0.113938 0.379863 + outer loop + vertex 0.794827 1.31245 2.53778 + vertex 0.796982 1.31023 2.54233 + vertex 0.795939 1.31417 2.54099 + endloop + endfacet + facet normal -0.917736 0.146373 0.369236 + outer loop + vertex 0.798727 1.311 2.54636 + vertex 0.796982 1.31023 2.54233 + vertex 0.8 1.31 2.54992 + endloop + endfacet + facet normal -0.912016 -0.0594895 0.405817 + outer loop + vertex 0.798727 1.311 2.54636 + vertex 0.797663 1.31428 2.54445 + vertex 0.796982 1.31023 2.54233 + endloop + endfacet + facet normal -0.890994 -0.0842078 0.446137 + outer loop + vertex 0.797663 1.31428 2.54445 + vertex 0.795939 1.31417 2.54099 + vertex 0.796982 1.31023 2.54233 + endloop + endfacet + facet normal -0.879433 -0.00795196 0.475955 + outer loop + vertex 0.798727 1.311 2.54636 + vertex 0.799328 1.31274 2.5475 + vertex 0.797663 1.31428 2.54445 + endloop + endfacet + facet normal -0.958193 -0.113805 0.262516 + outer loop + vertex 0.793542 1.31586 2.53457 + vertex 0.793888 1.3109 2.53368 + vertex 0.794827 1.31245 2.53778 + endloop + endfacet + facet normal -0.953148 -0.0858834 0.290055 + outer loop + vertex 0.794604 1.31747 2.53854 + vertex 0.793542 1.31586 2.53457 + vertex 0.794827 1.31245 2.53778 + endloop + endfacet + facet normal -0.922972 -0.0969 0.372468 + outer loop + vertex 0.794827 1.31245 2.53778 + vertex 0.795939 1.31417 2.54099 + vertex 0.794604 1.31747 2.53854 + endloop + endfacet + facet normal -0.912222 -0.0693645 0.403781 + outer loop + vertex 0.794604 1.31747 2.53854 + vertex 0.795939 1.31417 2.54099 + vertex 0.796169 1.31732 2.54205 + endloop + endfacet + facet normal -0.890909 -0.0851661 0.446125 + outer loop + vertex 0.795939 1.31417 2.54099 + vertex 0.797663 1.31428 2.54445 + vertex 0.796169 1.31732 2.54205 + endloop + endfacet + facet normal -0.890363 -0.0838439 0.447464 + outer loop + vertex 0.796169 1.31732 2.54205 + vertex 0.797663 1.31428 2.54445 + vertex 0.797453 1.31934 2.54498 + endloop + endfacet + facet normal -0.873043 -0.086528 0.479906 + outer loop + vertex 0.797663 1.31428 2.54445 + vertex 0.799292 1.31665 2.54784 + vertex 0.797453 1.31934 2.54498 + endloop + endfacet + facet normal -0.886774 -0.048229 0.45968 + outer loop + vertex 0.799328 1.31274 2.5475 + vertex 0.799292 1.31665 2.54784 + vertex 0.797663 1.31428 2.54445 + endloop + endfacet + facet normal -0.954961 -0.0764726 0.286706 + outer loop + vertex 0.793542 1.31586 2.53457 + vertex 0.794604 1.31747 2.53854 + vertex 0.793435 1.31977 2.53526 + endloop + endfacet + facet normal -0.955007 -0.0768601 0.286452 + outer loop + vertex 0.793979 1.32172 2.53759 + vertex 0.793435 1.31977 2.53526 + vertex 0.794604 1.31747 2.53854 + endloop + endfacet + facet normal -0.930721 -0.0566377 0.361317 + outer loop + vertex 0.793979 1.32172 2.53759 + vertex 0.794604 1.31747 2.53854 + vertex 0.795443 1.32192 2.54139 + endloop + endfacet + facet normal -0.911249 -0.0868596 0.402593 + outer loop + vertex 0.795443 1.32192 2.54139 + vertex 0.794604 1.31747 2.53854 + vertex 0.796169 1.31732 2.54205 + endloop + endfacet + facet normal -0.892461 -0.0779592 0.444338 + outer loop + vertex 0.796169 1.31732 2.54205 + vertex 0.797453 1.31934 2.54498 + vertex 0.795443 1.32192 2.54139 + endloop + endfacet + facet normal -0.896992 -0.100877 0.430382 + outer loop + vertex 0.795443 1.32192 2.54139 + vertex 0.797453 1.31934 2.54498 + vertex 0.797158 1.32445 2.54556 + endloop + endfacet + facet normal -0.872671 -0.104787 0.476933 + outer loop + vertex 0.797453 1.31934 2.54498 + vertex 0.799087 1.32163 2.54847 + vertex 0.797158 1.32445 2.54556 + endloop + endfacet + facet normal -0.87593 -0.0961034 0.472769 + outer loop + vertex 0.799292 1.31665 2.54784 + vertex 0.799087 1.32163 2.54847 + vertex 0.797453 1.31934 2.54498 + endloop + endfacet + facet normal -0.930225 -0.0633661 0.361477 + outer loop + vertex 0.794017 1.32587 2.53842 + vertex 0.793979 1.32172 2.53759 + vertex 0.795443 1.32192 2.54139 + endloop + endfacet + facet normal -0.937427 -0.0836804 0.337977 + outer loop + vertex 0.795334 1.32762 2.54251 + vertex 0.794017 1.32587 2.53842 + vertex 0.795443 1.32192 2.54139 + endloop + endfacet + facet normal -0.896976 -0.100926 0.430405 + outer loop + vertex 0.795443 1.32192 2.54139 + vertex 0.797158 1.32445 2.54556 + vertex 0.795334 1.32762 2.54251 + endloop + endfacet + facet normal -0.89706 -0.101207 0.430164 + outer loop + vertex 0.795334 1.32762 2.54251 + vertex 0.797158 1.32445 2.54556 + vertex 0.797089 1.32978 2.54667 + endloop + endfacet + facet normal -0.871436 -0.110799 0.477831 + outer loop + vertex 0.797158 1.32445 2.54556 + vertex 0.798892 1.32609 2.54911 + vertex 0.797089 1.32978 2.54667 + endloop + endfacet + facet normal -0.872949 -0.105708 0.476221 + outer loop + vertex 0.799087 1.32163 2.54847 + vertex 0.798892 1.32609 2.54911 + vertex 0.797158 1.32445 2.54556 + endloop + endfacet + facet normal -0.937128 -0.0850473 0.338465 + outer loop + vertex 0.793915 1.33088 2.53939 + vertex 0.794017 1.32587 2.53842 + vertex 0.795334 1.32762 2.54251 + endloop + endfacet + facet normal -0.940311 -0.0986166 0.325714 + outer loop + vertex 0.795087 1.33291 2.5434 + vertex 0.793915 1.33088 2.53939 + vertex 0.795334 1.32762 2.54251 + endloop + endfacet + facet normal -0.892852 -0.114836 0.435462 + outer loop + vertex 0.795334 1.32762 2.54251 + vertex 0.797089 1.32978 2.54667 + vertex 0.795087 1.33291 2.5434 + endloop + endfacet + facet normal -0.895218 -0.124177 0.427977 + outer loop + vertex 0.795087 1.33291 2.5434 + vertex 0.797089 1.32978 2.54667 + vertex 0.796384 1.3335 2.54628 + endloop + endfacet + facet normal -0.857874 -0.0850843 0.506766 + outer loop + vertex 0.799419 1.3294 2.55055 + vertex 0.797089 1.32978 2.54667 + vertex 0.798892 1.32609 2.54911 + endloop + endfacet + facet normal -0.856922 -0.10835 0.503929 + outer loop + vertex 0.799419 1.3294 2.55055 + vertex 0.798025 1.33399 2.54917 + vertex 0.797089 1.32978 2.54667 + endloop + endfacet + facet normal -0.85658 -0.108724 0.50443 + outer loop + vertex 0.798025 1.33399 2.54917 + vertex 0.796384 1.3335 2.54628 + vertex 0.797089 1.32978 2.54667 + endloop + endfacet + facet normal -0.830034 -0.0859614 0.551049 + outer loop + vertex 0.799419 1.3294 2.55055 + vertex 0.800636 1.33209 2.55281 + vertex 0.798025 1.33399 2.54917 + endloop + endfacet + facet normal -0.937841 -0.108079 0.329809 + outer loop + vertex 0.793915 1.33088 2.53939 + vertex 0.795087 1.33291 2.5434 + vertex 0.793754 1.33484 2.54024 + endloop + endfacet + facet normal -0.93829 -0.113483 0.326702 + outer loop + vertex 0.794281 1.33689 2.54246 + vertex 0.793754 1.33484 2.54024 + vertex 0.795087 1.33291 2.5434 + endloop + endfacet + facet normal -0.90792 -0.0877191 0.409861 + outer loop + vertex 0.794281 1.33689 2.54246 + vertex 0.795087 1.33291 2.5434 + vertex 0.795783 1.33714 2.54584 + endloop + endfacet + facet normal -0.900027 -0.0976376 0.424756 + outer loop + vertex 0.795783 1.33714 2.54584 + vertex 0.795087 1.33291 2.5434 + vertex 0.796384 1.3335 2.54628 + endloop + endfacet + facet normal -0.860829 -0.0818897 0.502263 + outer loop + vertex 0.796384 1.3335 2.54628 + vertex 0.798025 1.33399 2.54917 + vertex 0.795783 1.33714 2.54584 + endloop + endfacet + facet normal -0.866278 -0.0991278 0.489629 + outer loop + vertex 0.795783 1.33714 2.54584 + vertex 0.798025 1.33399 2.54917 + vertex 0.797595 1.33937 2.5495 + endloop + endfacet + facet normal -0.833272 -0.0997984 0.543781 + outer loop + vertex 0.798025 1.33399 2.54917 + vertex 0.799878 1.33665 2.5525 + vertex 0.797595 1.33937 2.5495 + endloop + endfacet + facet normal -0.83248 -0.101482 0.544683 + outer loop + vertex 0.800636 1.33209 2.55281 + vertex 0.799878 1.33665 2.5525 + vertex 0.798025 1.33399 2.54917 + endloop + endfacet + facet normal -0.909239 -0.07487 0.409486 + outer loop + vertex 0.794231 1.34094 2.54309 + vertex 0.794281 1.33689 2.54246 + vertex 0.795783 1.33714 2.54584 + endloop + endfacet + facet normal -0.912503 -0.0826005 0.400644 + outer loop + vertex 0.795645 1.34256 2.54664 + vertex 0.794231 1.34094 2.54309 + vertex 0.795783 1.33714 2.54584 + endloop + endfacet + facet normal -0.867985 -0.0943302 0.487549 + outer loop + vertex 0.795783 1.33714 2.54584 + vertex 0.797595 1.33937 2.5495 + vertex 0.795645 1.34256 2.54664 + endloop + endfacet + facet normal -0.869618 -0.0987236 0.483754 + outer loop + vertex 0.795645 1.34256 2.54664 + vertex 0.797595 1.33937 2.5495 + vertex 0.797287 1.34454 2.55 + endloop + endfacet + facet normal -0.830367 -0.102581 0.547693 + outer loop + vertex 0.797595 1.33937 2.5495 + vertex 0.799457 1.34163 2.55275 + vertex 0.797287 1.34454 2.55 + endloop + endfacet + facet normal -0.832524 -0.0974424 0.545352 + outer loop + vertex 0.799878 1.33665 2.5525 + vertex 0.799457 1.34163 2.55275 + vertex 0.797595 1.33937 2.5495 + endloop + endfacet + facet normal -0.913921 -0.0767884 0.398562 + outer loop + vertex 0.794099 1.34597 2.54376 + vertex 0.794231 1.34094 2.54309 + vertex 0.795645 1.34256 2.54664 + endloop + endfacet + facet normal -0.916628 -0.0847145 0.390661 + outer loop + vertex 0.795456 1.3477 2.54732 + vertex 0.794099 1.34597 2.54376 + vertex 0.795645 1.34256 2.54664 + endloop + endfacet + facet normal -0.870894 -0.0950188 0.482198 + outer loop + vertex 0.795645 1.34256 2.54664 + vertex 0.797287 1.34454 2.55 + vertex 0.795456 1.3477 2.54732 + endloop + endfacet + facet normal -0.871669 -0.0969932 0.4804 + outer loop + vertex 0.795456 1.3477 2.54732 + vertex 0.797287 1.34454 2.55 + vertex 0.797062 1.34951 2.5506 + endloop + endfacet + facet normal -0.826597 -0.103687 0.55316 + outer loop + vertex 0.797287 1.34454 2.55 + vertex 0.799117 1.34672 2.55314 + vertex 0.797062 1.34951 2.5506 + endloop + endfacet + facet normal -0.8288 -0.0984597 0.550814 + outer loop + vertex 0.799457 1.34163 2.55275 + vertex 0.799117 1.34672 2.55314 + vertex 0.797287 1.34454 2.55 + endloop + endfacet + facet normal -0.917246 -0.0823028 0.389725 + outer loop + vertex 0.793941 1.35088 2.54442 + vertex 0.794099 1.34597 2.54376 + vertex 0.795456 1.3477 2.54732 + endloop + endfacet + facet normal -0.918295 -0.0857425 0.3865 + outer loop + vertex 0.795326 1.353 2.54818 + vertex 0.793941 1.35088 2.54442 + vertex 0.795456 1.3477 2.54732 + endloop + endfacet + facet normal -0.870634 -0.100134 0.481632 + outer loop + vertex 0.795456 1.3477 2.54732 + vertex 0.797062 1.34951 2.5506 + vertex 0.795326 1.353 2.54818 + endloop + endfacet + facet normal -0.867958 -0.0947204 0.487522 + outer loop + vertex 0.795326 1.353 2.54818 + vertex 0.797062 1.34951 2.5506 + vertex 0.79707 1.35366 2.55141 + endloop + endfacet + facet normal -0.820055 -0.10947 0.561717 + outer loop + vertex 0.797062 1.34951 2.5506 + vertex 0.798852 1.3516 2.55361 + vertex 0.79707 1.35366 2.55141 + endloop + endfacet + facet normal -0.824619 -0.0987291 0.557007 + outer loop + vertex 0.799117 1.34672 2.55314 + vertex 0.798852 1.3516 2.55361 + vertex 0.797062 1.34951 2.5506 + endloop + endfacet + facet normal -0.916106 -0.0932692 0.389938 + outer loop + vertex 0.793941 1.35088 2.54442 + vertex 0.795326 1.353 2.54818 + vertex 0.793832 1.35476 2.54509 + endloop + endfacet + facet normal -0.917119 -0.102333 0.385253 + outer loop + vertex 0.794512 1.357 2.54731 + vertex 0.793832 1.35476 2.54509 + vertex 0.795326 1.353 2.54818 + endloop + endfacet + facet normal -0.886637 -0.0807779 0.455356 + outer loop + vertex 0.794512 1.357 2.54731 + vertex 0.795326 1.353 2.54818 + vertex 0.796218 1.35794 2.55079 + endloop + endfacet + facet normal -0.866722 -0.10179 0.488295 + outer loop + vertex 0.796218 1.35794 2.55079 + vertex 0.795326 1.353 2.54818 + vertex 0.79707 1.35366 2.55141 + endloop + endfacet + facet normal -0.823789 -0.0827168 0.56083 + outer loop + vertex 0.79707 1.35366 2.55141 + vertex 0.798574 1.35629 2.55401 + vertex 0.796218 1.35794 2.55079 + endloop + endfacet + facet normal -0.815754 -0.0966 0.570275 + outer loop + vertex 0.798852 1.3516 2.55361 + vertex 0.798574 1.35629 2.55401 + vertex 0.79707 1.35366 2.55141 + endloop + endfacet + facet normal -0.885315 -0.0878656 0.456615 + outer loop + vertex 0.794479 1.36113 2.54804 + vertex 0.794512 1.357 2.54731 + vertex 0.796218 1.35794 2.55079 + endloop + endfacet + facet normal -0.886128 -0.0900377 0.454609 + outer loop + vertex 0.796196 1.36395 2.55194 + vertex 0.794479 1.36113 2.54804 + vertex 0.796218 1.35794 2.55079 + endloop + endfacet + facet normal -0.824119 -0.10917 0.555797 + outer loop + vertex 0.796218 1.35794 2.55079 + vertex 0.798225 1.36108 2.55439 + vertex 0.796196 1.36395 2.55194 + endloop + endfacet + facet normal -0.827019 -0.103599 0.552545 + outer loop + vertex 0.798574 1.35629 2.55401 + vertex 0.798225 1.36108 2.55439 + vertex 0.796218 1.35794 2.55079 + endloop + endfacet + facet normal -0.883257 -0.0973985 0.458662 + outer loop + vertex 0.794274 1.36608 2.54869 + vertex 0.794479 1.36113 2.54804 + vertex 0.796196 1.36395 2.55194 + endloop + endfacet + facet normal -0.886625 -0.117987 0.447186 + outer loop + vertex 0.795436 1.36839 2.55161 + vertex 0.794274 1.36608 2.54869 + vertex 0.796196 1.36395 2.55194 + endloop + endfacet + facet normal -0.823348 -0.107356 0.557291 + outer loop + vertex 0.798095 1.36507 2.55496 + vertex 0.796196 1.36395 2.55194 + vertex 0.798225 1.36108 2.55439 + endloop + endfacet + facet normal -0.823457 -0.106946 0.557208 + outer loop + vertex 0.798095 1.36507 2.55496 + vertex 0.797289 1.36891 2.55451 + vertex 0.796196 1.36395 2.55194 + endloop + endfacet + facet normal -0.830342 -0.100704 0.548079 + outer loop + vertex 0.797289 1.36891 2.55451 + vertex 0.795436 1.36839 2.55161 + vertex 0.796196 1.36395 2.55194 + endloop + endfacet + facet normal -0.780817 -0.0908205 0.618123 + outer loop + vertex 0.798095 1.36507 2.55496 + vertex 0.799206 1.36754 2.55673 + vertex 0.797289 1.36891 2.55451 + endloop + endfacet + facet normal -0.897754 -0.0918043 0.430824 + outer loop + vertex 0.794096 1.37086 2.54934 + vertex 0.794274 1.36608 2.54869 + vertex 0.795436 1.36839 2.55161 + endloop + endfacet + facet normal -0.889741 -0.0686255 0.451278 + outer loop + vertex 0.795669 1.37301 2.55277 + vertex 0.794096 1.37086 2.54934 + vertex 0.795436 1.36839 2.55161 + endloop + endfacet + facet normal -0.831145 -0.0958719 0.547729 + outer loop + vertex 0.795436 1.36839 2.55161 + vertex 0.797289 1.36891 2.55451 + vertex 0.795669 1.37301 2.55277 + endloop + endfacet + facet normal -0.817286 -0.0806951 0.570553 + outer loop + vertex 0.795669 1.37301 2.55277 + vertex 0.797289 1.36891 2.55451 + vertex 0.797614 1.3735 2.55562 + endloop + endfacet + facet normal -0.770221 -0.0984847 0.630127 + outer loop + vertex 0.797289 1.36891 2.55451 + vertex 0.79938 1.3714 2.55745 + vertex 0.797614 1.3735 2.55562 + endloop + endfacet + facet normal -0.778749 -0.0816739 0.621996 + outer loop + vertex 0.799206 1.36754 2.55673 + vertex 0.79938 1.3714 2.55745 + vertex 0.797289 1.36891 2.55451 + endloop + endfacet + facet normal -0.880629 -0.0956505 0.464051 + outer loop + vertex 0.794096 1.37086 2.54934 + vertex 0.795669 1.37301 2.55277 + vertex 0.79406 1.37484 2.55009 + endloop + endfacet + facet normal -0.87935 -0.0891004 0.467765 + outer loop + vertex 0.794865 1.37723 2.55206 + vertex 0.79406 1.37484 2.55009 + vertex 0.795669 1.37301 2.55277 + endloop + endfacet + facet normal -0.834487 -0.0672701 0.546906 + outer loop + vertex 0.794865 1.37723 2.55206 + vertex 0.795669 1.37301 2.55277 + vertex 0.79678 1.37804 2.55508 + endloop + endfacet + facet normal -0.817088 -0.0820237 0.570648 + outer loop + vertex 0.79678 1.37804 2.55508 + vertex 0.795669 1.37301 2.55277 + vertex 0.797614 1.3735 2.55562 + endloop + endfacet + facet normal -0.772978 -0.0667697 0.630909 + outer loop + vertex 0.797614 1.3735 2.55562 + vertex 0.799266 1.37622 2.55794 + vertex 0.79678 1.37804 2.55508 + endloop + endfacet + facet normal -0.762636 -0.0821615 0.641588 + outer loop + vertex 0.79938 1.3714 2.55745 + vertex 0.799266 1.37622 2.55794 + vertex 0.797614 1.3735 2.55562 + endloop + endfacet + facet normal -0.835448 -0.061931 0.546069 + outer loop + vertex 0.794836 1.38149 2.5525 + vertex 0.794865 1.37723 2.55206 + vertex 0.79678 1.37804 2.55508 + endloop + endfacet + facet normal -0.838372 -0.0674488 0.54091 + outer loop + vertex 0.796677 1.38375 2.55564 + vertex 0.794836 1.38149 2.5525 + vertex 0.79678 1.37804 2.55508 + endloop + endfacet + facet normal -0.779539 -0.0742109 0.621941 + outer loop + vertex 0.79678 1.37804 2.55508 + vertex 0.79898 1.38129 2.55823 + vertex 0.796677 1.38375 2.55564 + endloop + endfacet + facet normal -0.776222 -0.0797959 0.625389 + outer loop + vertex 0.799266 1.37622 2.55794 + vertex 0.79898 1.38129 2.55823 + vertex 0.79678 1.37804 2.55508 + endloop + endfacet + facet normal -0.808417 -0.0438108 0.586977 + outer loop + vertex 0.794739 1.42642 2.55712 + vertex 0.794648 1.42222 2.55668 + vertex 0.796836 1.42301 2.55975 + endloop + endfacet + facet normal -0.78605 0.019099 0.617868 + outer loop + vertex 0.79313 1.52629 2.55901 + vertex 0.793081 1.52127 2.5591 + vertex 0.795309 1.52374 2.56186 + endloop + endfacet + facet normal -0.785505 0.0202976 0.618522 + outer loop + vertex 0.795366 1.52882 2.56177 + vertex 0.79313 1.52629 2.55901 + vertex 0.795309 1.52374 2.56186 + endloop + endfacet + facet normal -0.753508 0.0206486 0.657114 + outer loop + vertex 0.795309 1.52374 2.56186 + vertex 0.797753 1.52611 2.56459 + vertex 0.795366 1.52882 2.56177 + endloop + endfacet + facet normal -0.881178 0.0959147 0.462952 + outer loop + vertex 0.793864 1.65554 2.54901 + vertex 0.79381 1.65161 2.54972 + vertex 0.795175 1.65259 2.55212 + endloop + endfacet + facet normal -0.883256 0.0849962 0.461123 + outer loop + vertex 0.794164 1.66054 2.54866 + vertex 0.793864 1.65554 2.54901 + vertex 0.795566 1.65724 2.55196 + endloop + endfacet + facet normal -0.879151 0.0929776 0.467385 + outer loop + vertex 0.796178 1.66258 2.55205 + vertex 0.794164 1.66054 2.54866 + vertex 0.795566 1.65724 2.55196 + endloop + endfacet + facet normal -0.775607 0.0845044 0.625534 + outer loop + vertex 0.798101 1.66195 2.55493 + vertex 0.797499 1.65854 2.55464 + vertex 0.799236 1.65969 2.55664 + endloop + endfacet + facet normal -0.817769 0.0968477 0.567339 + outer loop + vertex 0.798101 1.66195 2.55493 + vertex 0.796178 1.66258 2.55205 + vertex 0.797499 1.65854 2.55464 + endloop + endfacet + facet normal -0.827576 0.0855735 0.554794 + outer loop + vertex 0.796178 1.66258 2.55205 + vertex 0.795566 1.65724 2.55196 + vertex 0.797499 1.65854 2.55464 + endloop + endfacet + facet normal -0.774933 0.0812842 0.626794 + outer loop + vertex 0.799236 1.65969 2.55664 + vertex 0.797499 1.65854 2.55464 + vertex 0.799332 1.65593 2.55725 + endloop + endfacet + facet normal -0.875332 0.071035 0.478277 + outer loop + vertex 0.794414 1.66575 2.54835 + vertex 0.794164 1.66054 2.54866 + vertex 0.796178 1.66258 2.55205 + endloop + endfacet + facet normal -0.874616 0.0726715 0.479338 + outer loop + vertex 0.796179 1.66818 2.5512 + vertex 0.794414 1.66575 2.54835 + vertex 0.796178 1.66258 2.55205 + endloop + endfacet + facet normal -0.813646 0.0871359 0.574793 + outer loop + vertex 0.796178 1.66258 2.55205 + vertex 0.79813 1.66578 2.55433 + vertex 0.796179 1.66818 2.5512 + endloop + endfacet + facet normal -0.818065 0.0952308 0.567187 + outer loop + vertex 0.798101 1.66195 2.55493 + vertex 0.79813 1.66578 2.55433 + vertex 0.796178 1.66258 2.55205 + endloop + endfacet + facet normal -0.871614 0.062475 0.486195 + outer loop + vertex 0.794538 1.67085 2.54791 + vertex 0.794414 1.66575 2.54835 + vertex 0.796179 1.66818 2.5512 + endloop + endfacet + facet normal -0.864856 0.0785299 0.49584 + outer loop + vertex 0.796281 1.67332 2.55056 + vertex 0.794538 1.67085 2.54791 + vertex 0.796179 1.66818 2.5512 + endloop + endfacet + facet normal -0.808469 0.0880586 0.581914 + outer loop + vertex 0.796179 1.66818 2.5512 + vertex 0.798305 1.67078 2.55376 + vertex 0.796281 1.67332 2.55056 + endloop + endfacet + facet normal -0.810651 0.093716 0.577981 + outer loop + vertex 0.79813 1.66578 2.55433 + vertex 0.798305 1.67078 2.55376 + vertex 0.796179 1.66818 2.5512 + endloop + endfacet + facet normal -0.861311 0.067784 0.503537 + outer loop + vertex 0.794611 1.67563 2.5474 + vertex 0.794538 1.67085 2.54791 + vertex 0.796281 1.67332 2.55056 + endloop + endfacet + facet normal -0.853506 0.0873567 0.513709 + outer loop + vertex 0.796304 1.67873 2.54968 + vertex 0.794611 1.67563 2.5474 + vertex 0.796281 1.67332 2.55056 + endloop + endfacet + facet normal -0.804806 0.0987909 0.585258 + outer loop + vertex 0.796281 1.67332 2.55056 + vertex 0.798485 1.67594 2.55315 + vertex 0.796304 1.67873 2.54968 + endloop + endfacet + facet normal -0.804177 0.0971378 0.586398 + outer loop + vertex 0.798305 1.67078 2.55376 + vertex 0.798485 1.67594 2.55315 + vertex 0.796281 1.67332 2.55056 + endloop + endfacet + facet normal -0.894805 0.102345 0.434569 + outer loop + vertex 0.795026 1.68263 2.54699 + vertex 0.793805 1.6817 2.54469 + vertex 0.794511 1.6793 2.54671 + endloop + endfacet + facet normal -0.847364 0.075185 0.525662 + outer loop + vertex 0.794511 1.6793 2.54671 + vertex 0.794611 1.67563 2.5474 + vertex 0.796304 1.67873 2.54968 + endloop + endfacet + facet normal -0.845511 0.0870388 0.526817 + outer loop + vertex 0.794511 1.6793 2.54671 + vertex 0.796304 1.67873 2.54968 + vertex 0.795026 1.68263 2.54699 + endloop + endfacet + facet normal -0.831295 0.104856 0.545852 + outer loop + vertex 0.795026 1.68263 2.54699 + vertex 0.796304 1.67873 2.54968 + vertex 0.79702 1.68392 2.54978 + endloop + endfacet + facet normal -0.799846 0.0997013 0.591866 + outer loop + vertex 0.796304 1.67873 2.54968 + vertex 0.798888 1.68101 2.55279 + vertex 0.79702 1.68392 2.54978 + endloop + endfacet + facet normal -0.801397 0.105753 0.588709 + outer loop + vertex 0.798485 1.67594 2.55315 + vertex 0.798888 1.68101 2.55279 + vertex 0.796304 1.67873 2.54968 + endloop + endfacet + facet normal -0.895009 0.105605 0.433366 + outer loop + vertex 0.793876 1.68562 2.54388 + vertex 0.793805 1.6817 2.54469 + vertex 0.795026 1.68263 2.54699 + endloop + endfacet + facet normal -0.895637 0.104337 0.432375 + outer loop + vertex 0.795422 1.68718 2.54671 + vertex 0.793876 1.68562 2.54388 + vertex 0.795026 1.68263 2.54699 + endloop + endfacet + facet normal -0.831394 0.105674 0.545543 + outer loop + vertex 0.795026 1.68263 2.54699 + vertex 0.79702 1.68392 2.54978 + vertex 0.795422 1.68718 2.54671 + endloop + endfacet + facet normal -0.831676 0.105213 0.545202 + outer loop + vertex 0.795422 1.68718 2.54671 + vertex 0.79702 1.68392 2.54978 + vertex 0.797465 1.68872 2.54953 + endloop + endfacet + facet normal -0.796694 0.104561 0.595269 + outer loop + vertex 0.79702 1.68392 2.54978 + vertex 0.799362 1.68591 2.55256 + vertex 0.797465 1.68872 2.54953 + endloop + endfacet + facet normal -0.796795 0.104971 0.595062 + outer loop + vertex 0.798888 1.68101 2.55279 + vertex 0.799362 1.68591 2.55256 + vertex 0.79702 1.68392 2.54978 + endloop + endfacet + facet normal -0.893018 0.0840848 0.442096 + outer loop + vertex 0.794057 1.69054 2.54331 + vertex 0.793876 1.68562 2.54388 + vertex 0.795422 1.68718 2.54671 + endloop + endfacet + facet normal -0.886001 0.0981153 0.453185 + outer loop + vertex 0.795764 1.69213 2.54631 + vertex 0.794057 1.69054 2.54331 + vertex 0.795422 1.68718 2.54671 + endloop + endfacet + facet normal -0.831146 0.101902 0.546637 + outer loop + vertex 0.795422 1.68718 2.54671 + vertex 0.797465 1.68872 2.54953 + vertex 0.795764 1.69213 2.54631 + endloop + endfacet + facet normal -0.830904 0.102301 0.54693 + outer loop + vertex 0.795764 1.69213 2.54631 + vertex 0.797465 1.68872 2.54953 + vertex 0.79781 1.69328 2.5492 + endloop + endfacet + facet normal -0.799174 0.103138 0.592186 + outer loop + vertex 0.797465 1.68872 2.54953 + vertex 0.799631 1.69057 2.55213 + vertex 0.79781 1.69328 2.5492 + endloop + endfacet + facet normal -0.798659 0.10105 0.59324 + outer loop + vertex 0.799362 1.68591 2.55256 + vertex 0.799631 1.69057 2.55213 + vertex 0.797465 1.68872 2.54953 + endloop + endfacet + facet normal -0.88362 0.0802269 0.46128 + outer loop + vertex 0.794246 1.69545 2.54282 + vertex 0.794057 1.69054 2.54331 + vertex 0.795764 1.69213 2.54631 + endloop + endfacet + facet normal -0.871441 0.10462 0.479213 + outer loop + vertex 0.796214 1.69795 2.54585 + vertex 0.794246 1.69545 2.54282 + vertex 0.795764 1.69213 2.54631 + endloop + endfacet + facet normal -0.805048 0.101207 0.584513 + outer loop + vertex 0.798435 1.69665 2.54948 + vertex 0.79781 1.69328 2.5492 + vertex 0.799573 1.69422 2.55146 + endloop + endfacet + facet normal -0.829623 0.108792 0.547622 + outer loop + vertex 0.798435 1.69665 2.54948 + vertex 0.796214 1.69795 2.54585 + vertex 0.79781 1.69328 2.5492 + endloop + endfacet + facet normal -0.831309 0.10668 0.545477 + outer loop + vertex 0.796214 1.69795 2.54585 + vertex 0.795764 1.69213 2.54631 + vertex 0.79781 1.69328 2.5492 + endloop + endfacet + facet normal -0.804203 0.0939989 0.586875 + outer loop + vertex 0.799573 1.69422 2.55146 + vertex 0.79781 1.69328 2.5492 + vertex 0.799631 1.69057 2.55213 + endloop + endfacet + facet normal -0.906976 0.120171 0.403675 + outer loop + vertex 0.794775 1.70264 2.54238 + vertex 0.793523 1.70191 2.53979 + vertex 0.79421 1.69933 2.5421 + endloop + endfacet + facet normal -0.86598 0.0835495 0.493049 + outer loop + vertex 0.79421 1.69933 2.5421 + vertex 0.794246 1.69545 2.54282 + vertex 0.796214 1.69795 2.54585 + endloop + endfacet + facet normal -0.860923 0.104156 0.497959 + outer loop + vertex 0.79421 1.69933 2.5421 + vertex 0.796214 1.69795 2.54585 + vertex 0.794775 1.70264 2.54238 + endloop + endfacet + facet normal -0.854362 0.113027 0.507238 + outer loop + vertex 0.794775 1.70264 2.54238 + vertex 0.796214 1.69795 2.54585 + vertex 0.796723 1.7038 2.54541 + endloop + endfacet + facet normal -0.829462 0.113884 0.546831 + outer loop + vertex 0.796214 1.69795 2.54585 + vertex 0.798538 1.70065 2.54881 + vertex 0.796723 1.7038 2.54541 + endloop + endfacet + facet normal -0.828825 0.111818 0.54822 + outer loop + vertex 0.798435 1.69665 2.54948 + vertex 0.798538 1.70065 2.54881 + vertex 0.796214 1.69795 2.54585 + endloop + endfacet + facet normal -0.90692 0.126116 0.401984 + outer loop + vertex 0.793671 1.70569 2.53894 + vertex 0.793523 1.70191 2.53979 + vertex 0.794775 1.70264 2.54238 + endloop + endfacet + facet normal -0.907462 0.124947 0.401123 + outer loop + vertex 0.795212 1.70721 2.54195 + vertex 0.793671 1.70569 2.53894 + vertex 0.794775 1.70264 2.54238 + endloop + endfacet + facet normal -0.855364 0.129537 0.50157 + outer loop + vertex 0.794775 1.70264 2.54238 + vertex 0.796723 1.7038 2.54541 + vertex 0.795212 1.70721 2.54195 + endloop + endfacet + facet normal -0.862675 0.116714 0.492107 + outer loop + vertex 0.795212 1.70721 2.54195 + vertex 0.796723 1.7038 2.54541 + vertex 0.797159 1.70886 2.54497 + endloop + endfacet + facet normal -0.834544 0.118246 0.538102 + outer loop + vertex 0.796723 1.7038 2.54541 + vertex 0.798909 1.70577 2.54836 + vertex 0.797159 1.70886 2.54497 + endloop + endfacet + facet normal -0.83254 0.10826 0.543284 + outer loop + vertex 0.798538 1.70065 2.54881 + vertex 0.798909 1.70577 2.54836 + vertex 0.796723 1.7038 2.54541 + endloop + endfacet + facet normal -0.906427 0.111494 0.407381 + outer loop + vertex 0.793963 1.71044 2.53829 + vertex 0.793671 1.70569 2.53894 + vertex 0.795212 1.70721 2.54195 + endloop + endfacet + facet normal -0.899688 0.126071 0.417933 + outer loop + vertex 0.795615 1.71213 2.54133 + vertex 0.793963 1.71044 2.53829 + vertex 0.795212 1.70721 2.54195 + endloop + endfacet + facet normal -0.864469 0.131595 0.485155 + outer loop + vertex 0.795212 1.70721 2.54195 + vertex 0.797159 1.70886 2.54497 + vertex 0.795615 1.71213 2.54133 + endloop + endfacet + facet normal -0.874326 0.112455 0.472132 + outer loop + vertex 0.795615 1.71213 2.54133 + vertex 0.797159 1.70886 2.54497 + vertex 0.797552 1.71389 2.5445 + endloop + endfacet + facet normal -0.849754 0.114514 0.514592 + outer loop + vertex 0.797159 1.70886 2.54497 + vertex 0.799228 1.71089 2.54794 + vertex 0.797552 1.71389 2.5445 + endloop + endfacet + facet normal -0.846037 0.0965689 0.524305 + outer loop + vertex 0.798909 1.70577 2.54836 + vertex 0.799228 1.71089 2.54794 + vertex 0.797159 1.70886 2.54497 + endloop + endfacet + facet normal -0.899977 0.129213 0.416347 + outer loop + vertex 0.794286 1.71522 2.5375 + vertex 0.793963 1.71044 2.53829 + vertex 0.795615 1.71213 2.54133 + endloop + endfacet + facet normal -0.897877 0.13389 0.419392 + outer loop + vertex 0.7959 1.71775 2.54015 + vertex 0.794286 1.71522 2.5375 + vertex 0.795615 1.71213 2.54133 + endloop + endfacet + facet normal -0.877589 0.141038 0.458198 + outer loop + vertex 0.795615 1.71213 2.54133 + vertex 0.797552 1.71389 2.5445 + vertex 0.7959 1.71775 2.54015 + endloop + endfacet + facet normal -0.896765 0.101755 0.43065 + outer loop + vertex 0.7959 1.71775 2.54015 + vertex 0.797552 1.71389 2.5445 + vertex 0.797974 1.71881 2.54422 + endloop + endfacet + facet normal -0.866206 0.102494 0.489063 + outer loop + vertex 0.797552 1.71389 2.5445 + vertex 0.799547 1.71582 2.54763 + vertex 0.797974 1.71881 2.54422 + endloop + endfacet + facet normal -0.863418 0.0867277 0.496978 + outer loop + vertex 0.799228 1.71089 2.54794 + vertex 0.799547 1.71582 2.54763 + vertex 0.797552 1.71389 2.5445 + endloop + endfacet + facet normal -0.922523 0.169273 0.346839 + outer loop + vertex 0.79495 1.723 2.53592 + vertex 0.793873 1.72151 2.53378 + vertex 0.794393 1.71917 2.53631 + endloop + endfacet + facet normal -0.900981 0.147935 0.407859 + outer loop + vertex 0.794393 1.71917 2.53631 + vertex 0.794286 1.71522 2.5375 + vertex 0.7959 1.71775 2.54015 + endloop + endfacet + facet normal -0.893921 0.17193 0.413938 + outer loop + vertex 0.794393 1.71917 2.53631 + vertex 0.7959 1.71775 2.54015 + vertex 0.79495 1.723 2.53592 + endloop + endfacet + facet normal -0.917677 0.135124 0.373644 + outer loop + vertex 0.79495 1.723 2.53592 + vertex 0.7959 1.71775 2.54015 + vertex 0.796759 1.72291 2.54039 + endloop + endfacet + facet normal -0.89666 0.129267 0.423429 + outer loop + vertex 0.7959 1.71775 2.54015 + vertex 0.797974 1.71881 2.54422 + vertex 0.796759 1.72291 2.54039 + endloop + endfacet + facet normal -0.916529 0.0915633 0.389346 + outer loop + vertex 0.796759 1.72291 2.54039 + vertex 0.797974 1.71881 2.54422 + vertex 0.798423 1.72323 2.54423 + endloop + endfacet + facet normal -0.880881 0.0876435 0.465152 + outer loop + vertex 0.797974 1.71881 2.54422 + vertex 0.799771 1.72046 2.54731 + vertex 0.798423 1.72323 2.54423 + endloop + endfacet + facet normal -0.879027 0.0749776 0.47084 + outer loop + vertex 0.799547 1.71582 2.54763 + vertex 0.799771 1.72046 2.54731 + vertex 0.797974 1.71881 2.54422 + endloop + endfacet + facet normal -0.957488 0.175248 0.229138 + outer loop + vertex 0.79448 1.72746 2.53225 + vertex 0.793709 1.72616 2.53003 + vertex 0.793924 1.72426 2.53238 + endloop + endfacet + facet normal -0.923501 0.187766 0.334499 + outer loop + vertex 0.793924 1.72426 2.53238 + vertex 0.793873 1.72151 2.53378 + vertex 0.79495 1.723 2.53592 + endloop + endfacet + facet normal -0.927552 0.173945 0.330742 + outer loop + vertex 0.793924 1.72426 2.53238 + vertex 0.79495 1.723 2.53592 + vertex 0.79448 1.72746 2.53225 + endloop + endfacet + facet normal -0.93422 0.162427 0.317569 + outer loop + vertex 0.79448 1.72746 2.53225 + vertex 0.79495 1.723 2.53592 + vertex 0.79585 1.72777 2.53613 + endloop + endfacet + facet normal -0.914634 0.156325 0.372836 + outer loop + vertex 0.79495 1.723 2.53592 + vertex 0.796759 1.72291 2.54039 + vertex 0.79585 1.72777 2.53613 + endloop + endfacet + facet normal -0.933008 0.122597 0.338328 + outer loop + vertex 0.79585 1.72777 2.53613 + vertex 0.796759 1.72291 2.54039 + vertex 0.797599 1.72797 2.54088 + endloop + endfacet + facet normal -0.890939 0.0889254 0.445331 + outer loop + vertex 0.798975 1.72644 2.5447 + vertex 0.798423 1.72323 2.54423 + vertex 0.799758 1.72407 2.54674 + endloop + endfacet + facet normal -0.921657 0.104572 0.373648 + outer loop + vertex 0.798975 1.72644 2.5447 + vertex 0.797599 1.72797 2.54088 + vertex 0.798423 1.72323 2.54423 + endloop + endfacet + facet normal -0.91499 0.115 0.386741 + outer loop + vertex 0.797599 1.72797 2.54088 + vertex 0.796759 1.72291 2.54039 + vertex 0.798423 1.72323 2.54423 + endloop + endfacet + facet normal -0.889629 0.0682488 0.451556 + outer loop + vertex 0.799758 1.72407 2.54674 + vertex 0.798423 1.72323 2.54423 + vertex 0.799771 1.72046 2.54731 + endloop + endfacet + facet normal -0.957888 0.162453 0.23677 + outer loop + vertex 0.794133 1.73003 2.52908 + vertex 0.793709 1.72616 2.53003 + vertex 0.79448 1.72746 2.53225 + endloop + endfacet + facet normal -0.960022 0.156444 0.232129 + outer loop + vertex 0.795246 1.73311 2.53161 + vertex 0.794133 1.73003 2.52908 + vertex 0.79448 1.72746 2.53225 + endloop + endfacet + facet normal -0.934186 0.162686 0.317536 + outer loop + vertex 0.79448 1.72746 2.53225 + vertex 0.79585 1.72777 2.53613 + vertex 0.795246 1.73311 2.53161 + endloop + endfacet + facet normal -0.946724 0.13859 0.290701 + outer loop + vertex 0.795246 1.73311 2.53161 + vertex 0.79585 1.72777 2.53613 + vertex 0.796556 1.73286 2.536 + endloop + endfacet + facet normal -0.931362 0.137606 0.337089 + outer loop + vertex 0.79585 1.72777 2.53613 + vertex 0.797599 1.72797 2.54088 + vertex 0.796556 1.73286 2.536 + endloop + endfacet + facet normal -0.945556 0.105452 0.307903 + outer loop + vertex 0.796556 1.73286 2.536 + vertex 0.797599 1.72797 2.54088 + vertex 0.797917 1.73362 2.53992 + endloop + endfacet + facet normal -0.91574 0.116726 0.384442 + outer loop + vertex 0.797599 1.72797 2.54088 + vertex 0.799137 1.7304 2.5438 + vertex 0.797917 1.73362 2.53992 + endloop + endfacet + facet normal -0.916923 0.123405 0.379505 + outer loop + vertex 0.798975 1.72644 2.5447 + vertex 0.799137 1.7304 2.5438 + vertex 0.797599 1.72797 2.54088 + endloop + endfacet + facet normal -0.941981 0.0714758 0.327969 + outer loop + vertex 0.795 1.73726 2.53 + vertex 0.794133 1.73003 2.52908 + vertex 0.795246 1.73311 2.53161 + endloop + endfacet + facet normal -0.634015 0.246889 0.732851 + outer loop + vertex 0.795 1.73726 2.53 + vertex 0.795246 1.73311 2.53161 + vertex 0.796067 1.74 2.53 + endloop + endfacet + facet normal -0.952827 0.172082 0.250019 + outer loop + vertex 0.796067 1.74 2.53 + vertex 0.795246 1.73311 2.53161 + vertex 0.796264 1.73817 2.53201 + endloop + endfacet + facet normal -0.942106 0.166656 0.290967 + outer loop + vertex 0.795246 1.73311 2.53161 + vertex 0.796556 1.73286 2.536 + vertex 0.796264 1.73817 2.53201 + endloop + endfacet + facet normal -0.964863 0.121754 0.232841 + outer loop + vertex 0.796264 1.73817 2.53201 + vertex 0.796556 1.73286 2.536 + vertex 0.79716 1.73788 2.53588 + endloop + endfacet + facet normal -0.944754 0.121094 0.304591 + outer loop + vertex 0.796556 1.73286 2.536 + vertex 0.797917 1.73362 2.53992 + vertex 0.79716 1.73788 2.53588 + endloop + endfacet + facet normal -0.956831 0.0916396 0.275821 + outer loop + vertex 0.79716 1.73788 2.53588 + vertex 0.797917 1.73362 2.53992 + vertex 0.798242 1.73834 2.53948 + endloop + endfacet + facet normal -0.914824 0.0995737 0.391385 + outer loop + vertex 0.797917 1.73362 2.53992 + vertex 0.799368 1.73536 2.54287 + vertex 0.798242 1.73834 2.53948 + endloop + endfacet + facet normal -0.916501 0.114906 0.383174 + outer loop + vertex 0.799137 1.7304 2.5438 + vertex 0.799368 1.73536 2.54287 + vertex 0.797917 1.73362 2.53992 + endloop + endfacet + facet normal -0.94175 0.197576 0.272159 + outer loop + vertex 0.796067 1.74 2.53 + vertex 0.796264 1.73817 2.53201 + vertex 0.797116 1.745 2.53 + endloop + endfacet + facet normal -0.982653 0.153277 0.104398 + outer loop + vertex 0.797116 1.745 2.53 + vertex 0.796264 1.73817 2.53201 + vertex 0.797017 1.74295 2.53208 + endloop + endfacet + facet normal -0.960923 0.148049 0.233899 + outer loop + vertex 0.796264 1.73817 2.53201 + vertex 0.79716 1.73788 2.53588 + vertex 0.797017 1.74295 2.53208 + endloop + endfacet + facet normal -0.977589 0.107846 0.180801 + outer loop + vertex 0.797017 1.74295 2.53208 + vertex 0.79716 1.73788 2.53588 + vertex 0.797773 1.74302 2.53613 + endloop + endfacet + facet normal -0.920612 0.0859379 0.380904 + outer loop + vertex 0.798664 1.7417 2.53974 + vertex 0.798242 1.73834 2.53948 + vertex 0.799318 1.73927 2.54187 + endloop + endfacet + facet normal -0.957175 0.0989447 0.272078 + outer loop + vertex 0.798664 1.7417 2.53974 + vertex 0.797773 1.74302 2.53613 + vertex 0.798242 1.73834 2.53948 + endloop + endfacet + facet normal -0.956295 0.100764 0.274494 + outer loop + vertex 0.797773 1.74302 2.53613 + vertex 0.79716 1.73788 2.53588 + vertex 0.798242 1.73834 2.53948 + endloop + endfacet + facet normal -0.920593 0.0856149 0.381023 + outer loop + vertex 0.799318 1.73927 2.54187 + vertex 0.798242 1.73834 2.53948 + vertex 0.799368 1.73536 2.54287 + endloop + endfacet + facet normal -0.995463 0.0870078 0.0385055 + outer loop + vertex 0.797116 1.745 2.53 + vertex 0.797017 1.74295 2.53208 + vertex 0.797553 1.75 2.53 + endloop + endfacet + facet normal -0.97917 0.122231 0.162125 + outer loop + vertex 0.797553 1.75 2.53 + vertex 0.797017 1.74295 2.53208 + vertex 0.797531 1.74753 2.53173 + endloop + endfacet + facet normal -0.975874 0.123234 0.180232 + outer loop + vertex 0.797017 1.74295 2.53208 + vertex 0.797773 1.74302 2.53613 + vertex 0.797531 1.74753 2.53173 + endloop + endfacet + facet normal -0.989994 0.0675935 0.123865 + outer loop + vertex 0.797531 1.74753 2.53173 + vertex 0.797773 1.74302 2.53613 + vertex 0.798037 1.74866 2.53516 + endloop + endfacet + facet normal -0.955505 0.0927123 0.280027 + outer loop + vertex 0.797773 1.74302 2.53613 + vertex 0.798838 1.74558 2.53891 + vertex 0.798037 1.74866 2.53516 + endloop + endfacet + facet normal -0.956751 0.101128 0.272766 + outer loop + vertex 0.798664 1.7417 2.53974 + vertex 0.798838 1.74558 2.53891 + vertex 0.797773 1.74302 2.53613 + endloop + endfacet + facet normal -0.28509 -0.066931 -0.956161 + outer loop + vertex 0.8 1.75 2.52795 + vertex 0.798213 1.75133 2.52839 + vertex 0.8 1.755 2.5276 + endloop + endfacet + facet normal -0.5483 -0.520561 -0.65451 + outer loop + vertex 0.797553 1.75 2.53 + vertex 0.798213 1.75133 2.52839 + vertex 0.8 1.75 2.52795 + endloop + endfacet + facet normal 0.65225 0.431276 0.623354 + outer loop + vertex 0.797553 1.75 2.53 + vertex 0.797531 1.74753 2.53173 + vertex 0.798213 1.75133 2.52839 + endloop + endfacet + facet normal -0.985231 0.0280628 -0.168918 + outer loop + vertex 0.798213 1.75133 2.52839 + vertex 0.797531 1.74753 2.53173 + vertex 0.79779 1.75237 2.53103 + endloop + endfacet + facet normal -0.989903 0.07081 0.122792 + outer loop + vertex 0.797531 1.74753 2.53173 + vertex 0.798037 1.74866 2.53516 + vertex 0.79779 1.75237 2.53103 + endloop + endfacet + facet normal -0.992961 0.0522344 0.106306 + outer loop + vertex 0.79779 1.75237 2.53103 + vertex 0.798037 1.74866 2.53516 + vertex 0.79824 1.75375 2.53456 + endloop + endfacet + facet normal -0.949247 0.0741255 0.305674 + outer loop + vertex 0.798037 1.74866 2.53516 + vertex 0.799204 1.75047 2.53834 + vertex 0.79824 1.75375 2.53456 + endloop + endfacet + facet normal -0.951565 0.10474 0.289057 + outer loop + vertex 0.798838 1.74558 2.53891 + vertex 0.799204 1.75047 2.53834 + vertex 0.798037 1.74866 2.53516 + endloop + endfacet + facet normal -0.0950328 -0.323811 -0.941337 + outer loop + vertex 0.8 1.755 2.5276 + vertex 0.798297 1.75705 2.52707 + vertex 0.8 1.76 2.52588 + endloop + endfacet + facet normal 0.0331048 -0.225657 -0.973644 + outer loop + vertex 0.798213 1.75133 2.52839 + vertex 0.798297 1.75705 2.52707 + vertex 0.8 1.755 2.5276 + endloop + endfacet + facet normal -0.988415 -0.0202301 -0.150421 + outer loop + vertex 0.798213 1.75133 2.52839 + vertex 0.79779 1.75237 2.53103 + vertex 0.798297 1.75705 2.52707 + endloop + endfacet + facet normal -0.991948 0.000260643 -0.126649 + outer loop + vertex 0.798297 1.75705 2.52707 + vertex 0.79779 1.75237 2.53103 + vertex 0.797859 1.75762 2.5305 + endloop + endfacet + facet normal -0.992824 0.0249275 0.11696 + outer loop + vertex 0.79779 1.75237 2.53103 + vertex 0.79824 1.75375 2.53456 + vertex 0.797859 1.75762 2.5305 + endloop + endfacet + facet normal -0.987795 0.0554392 0.14556 + outer loop + vertex 0.797859 1.75762 2.5305 + vertex 0.79824 1.75375 2.53456 + vertex 0.798434 1.75834 2.53412 + endloop + endfacet + facet normal -0.938592 0.0715771 0.337522 + outer loop + vertex 0.79824 1.75375 2.53456 + vertex 0.799471 1.75539 2.53763 + vertex 0.798434 1.75834 2.53412 + endloop + endfacet + facet normal -0.94087 0.0980852 0.324257 + outer loop + vertex 0.799204 1.75047 2.53834 + vertex 0.799471 1.75539 2.53763 + vertex 0.79824 1.75375 2.53456 + endloop + endfacet + facet normal -0.862714 -0.349535 -0.365444 + outer loop + vertex 0.8 1.76 2.52588 + vertex 0.798347 1.765 2.525 + vertex 0.8 1.76092 2.525 + endloop + endfacet + facet normal -0.234604 -0.243208 -0.941175 + outer loop + vertex 0.8 1.76 2.52588 + vertex 0.798297 1.75705 2.52707 + vertex 0.798347 1.765 2.525 + endloop + endfacet + facet normal -0.917675 -0.0945349 -0.385922 + outer loop + vertex 0.798297 1.75705 2.52707 + vertex 0.797885 1.76271 2.52666 + vertex 0.798347 1.765 2.525 + endloop + endfacet + facet normal -0.990345 -0.0801124 -0.113133 + outer loop + vertex 0.798297 1.75705 2.52707 + vertex 0.797859 1.75762 2.5305 + vertex 0.797885 1.76271 2.52666 + endloop + endfacet + facet normal -0.99771 0.0438634 0.0514901 + outer loop + vertex 0.797885 1.76271 2.52666 + vertex 0.797859 1.75762 2.5305 + vertex 0.798092 1.76287 2.53053 + endloop + endfacet + facet normal -0.930934 0.0999717 0.351238 + outer loop + vertex 0.798845 1.76159 2.53428 + vertex 0.798434 1.75834 2.53412 + vertex 0.799469 1.7592 2.53662 + endloop + endfacet + facet normal -0.96656 0.110528 0.231398 + outer loop + vertex 0.798845 1.76159 2.53428 + vertex 0.798092 1.76287 2.53053 + vertex 0.798434 1.75834 2.53412 + endloop + endfacet + facet normal -0.98804 0.0428524 0.148125 + outer loop + vertex 0.798092 1.76287 2.53053 + vertex 0.797859 1.75762 2.5305 + vertex 0.798434 1.75834 2.53412 + endloop + endfacet + facet normal -0.930786 0.0932619 0.353467 + outer loop + vertex 0.799469 1.7592 2.53662 + vertex 0.798434 1.75834 2.53412 + vertex 0.799471 1.75539 2.53763 + endloop + endfacet + facet normal -0.947577 -0.0386549 -0.317182 + outer loop + vertex 0.798347 1.765 2.525 + vertex 0.797885 1.76271 2.52666 + vertex 0.798143 1.77 2.525 + endloop + endfacet + facet normal -0.980471 -0.0100088 -0.196411 + outer loop + vertex 0.798143 1.77 2.525 + vertex 0.797885 1.76271 2.52666 + vertex 0.797918 1.76745 2.52625 + endloop + endfacet + facet normal -0.998536 0.0113756 0.0528776 + outer loop + vertex 0.797885 1.76271 2.52666 + vertex 0.798092 1.76287 2.53053 + vertex 0.797918 1.76745 2.52625 + endloop + endfacet + facet normal -0.991521 0.0665296 0.111622 + outer loop + vertex 0.797918 1.76745 2.52625 + vertex 0.798092 1.76287 2.53053 + vertex 0.798319 1.76807 2.52944 + endloop + endfacet + facet normal -0.959402 0.097145 0.264786 + outer loop + vertex 0.798092 1.76287 2.53053 + vertex 0.799044 1.76528 2.53309 + vertex 0.798319 1.76807 2.52944 + endloop + endfacet + facet normal -0.963025 0.128471 0.236809 + outer loop + vertex 0.798845 1.76159 2.53428 + vertex 0.799044 1.76528 2.53309 + vertex 0.798092 1.76287 2.53053 + endloop + endfacet + facet normal -0.184152 0.0216479 -0.982659 + outer loop + vertex 0.8 1.77 2.52314 + vertex 0.798393 1.77121 2.52347 + vertex 0.8 1.775 2.52325 + endloop + endfacet + facet normal -0.566692 -0.599009 -0.565729 + outer loop + vertex 0.798143 1.77 2.525 + vertex 0.798393 1.77121 2.52347 + vertex 0.8 1.77 2.52314 + endloop + endfacet + facet normal 0.988452 -0.0130157 0.150972 + outer loop + vertex 0.798143 1.77 2.525 + vertex 0.797918 1.76745 2.52625 + vertex 0.798393 1.77121 2.52347 + endloop + endfacet + facet normal -0.9939 0.054479 -0.0958908 + outer loop + vertex 0.798393 1.77121 2.52347 + vertex 0.797918 1.76745 2.52625 + vertex 0.798207 1.77234 2.52604 + endloop + endfacet + facet normal -0.950973 0.114091 0.287462 + outer loop + vertex 0.798735 1.77151 2.52945 + vertex 0.798319 1.76807 2.52944 + vertex 0.799179 1.76902 2.53191 + endloop + endfacet + facet normal -0.976741 0.117584 0.179309 + outer loop + vertex 0.798735 1.77151 2.52945 + vertex 0.798207 1.77234 2.52604 + vertex 0.798319 1.76807 2.52944 + endloop + endfacet + facet normal -0.991644 0.0636518 0.112204 + outer loop + vertex 0.798207 1.77234 2.52604 + vertex 0.797918 1.76745 2.52625 + vertex 0.798319 1.76807 2.52944 + endloop + endfacet + facet normal -0.950888 0.123968 0.283625 + outer loop + vertex 0.799179 1.76902 2.53191 + vertex 0.798319 1.76807 2.52944 + vertex 0.799044 1.76528 2.53309 + endloop + endfacet + facet normal 0.0928756 0.063585 -0.993645 + outer loop + vertex 0.8 1.775 2.52325 + vertex 0.798564 1.77576 2.52316 + vertex 0.8 1.78 2.52357 + endloop + endfacet + facet normal 0.0237783 -0.0673821 -0.997444 + outer loop + vertex 0.798393 1.77121 2.52347 + vertex 0.798564 1.77576 2.52316 + vertex 0.8 1.775 2.52325 + endloop + endfacet + facet normal -0.995793 0.0316584 -0.0859904 + outer loop + vertex 0.798393 1.77121 2.52347 + vertex 0.798207 1.77234 2.52604 + vertex 0.798564 1.77576 2.52316 + endloop + endfacet + facet normal -0.996246 0.0390164 -0.0772824 + outer loop + vertex 0.798564 1.77576 2.52316 + vertex 0.798207 1.77234 2.52604 + vertex 0.798499 1.77748 2.52486 + endloop + endfacet + facet normal -0.975192 0.100452 0.197255 + outer loop + vertex 0.798207 1.77234 2.52604 + vertex 0.798943 1.77524 2.5282 + vertex 0.798499 1.77748 2.52486 + endloop + endfacet + facet normal -0.977185 0.114784 0.178701 + outer loop + vertex 0.798735 1.77151 2.52945 + vertex 0.798943 1.77524 2.5282 + vertex 0.798207 1.77234 2.52604 + endloop + endfacet + facet normal 0.32812 -0.215259 -0.919783 + outer loop + vertex 0.8 1.78 2.52357 + vertex 0.798915 1.78086 2.52298 + vertex 0.8 1.785 2.5224 + endloop + endfacet + facet normal 0.436887 -0.0621534 -0.897367 + outer loop + vertex 0.798564 1.77576 2.52316 + vertex 0.798915 1.78086 2.52298 + vertex 0.8 1.78 2.52357 + endloop + endfacet + facet normal -0.969254 0.128568 0.209801 + outer loop + vertex 0.798988 1.78169 2.52454 + vertex 0.798499 1.77748 2.52486 + vertex 0.799132 1.7792 2.52673 + endloop + endfacet + facet normal -0.993369 0.114044 -0.0145746 + outer loop + vertex 0.798988 1.78169 2.52454 + vertex 0.798915 1.78086 2.52298 + vertex 0.798499 1.77748 2.52486 + endloop + endfacet + facet normal -0.992569 0.0646617 -0.103083 + outer loop + vertex 0.798915 1.78086 2.52298 + vertex 0.798564 1.77576 2.52316 + vertex 0.798499 1.77748 2.52486 + endloop + endfacet + facet normal -0.969024 0.125065 0.212956 + outer loop + vertex 0.799132 1.7792 2.52673 + vertex 0.798499 1.77748 2.52486 + vertex 0.798943 1.77524 2.5282 + endloop + endfacet + facet normal -0.490748 -0.300935 -0.817682 + outer loop + vertex 0.8 1.78693 2.52 + vertex 0.799551 1.78944 2.51935 + vertex 0.8 1.79 2.51887 + endloop + endfacet + facet normal -0.932318 0.202045 -0.299936 + outer loop + vertex 0.8 1.785 2.5224 + vertex 0.798915 1.78086 2.52298 + vertex 0.8 1.78886 2.525 + endloop + endfacet + facet normal -0.983093 -0.147457 0.108561 + outer loop + vertex 0.8 1.78693 2.52 + vertex 0.8 1.79 2.52417 + vertex 0.799551 1.78944 2.51935 + endloop + endfacet + facet normal -0.989474 0.141643 -0.0296238 + outer loop + vertex 0.8 1.78886 2.525 + vertex 0.798915 1.78086 2.52298 + vertex 0.798988 1.78169 2.52454 + endloop + endfacet + facet normal -0.79595 0.137348 -0.589576 + outer loop + vertex 0.8 1.79 2.51887 + vertex 0.799551 1.78944 2.51935 + vertex 0.8 1.79485 2.52 + endloop + endfacet + facet normal -0.993837 0.0722713 0.0840583 + outer loop + vertex 0.8 1.79485 2.52 + vertex 0.799551 1.78944 2.51935 + vertex 0.8 1.79 2.52417 + endloop + endfacet + facet normal -0.572485 -0.152639 -0.805582 + outer loop + vertex 0.805 1.20715 2.52 + vertex 0.804296 1.21064 2.51984 + vertex 0.805 1.21 2.51946 + endloop + endfacet + facet normal -0.959634 -0.18377 0.212909 + outer loop + vertex 0.805 1.20715 2.52 + vertex 0.805 1.21 2.52246 + vertex 0.804296 1.21064 2.51984 + endloop + endfacet + facet normal 0.514239 -0.0701054 -0.854777 + outer loop + vertex 0.805 1.21 2.51946 + vertex 0.803986 1.21271 2.51863 + vertex 0.805 1.215 2.51905 + endloop + endfacet + facet normal -0.700196 -0.435175 -0.565993 + outer loop + vertex 0.804296 1.21064 2.51984 + vertex 0.803986 1.21271 2.51863 + vertex 0.805 1.21 2.51946 + endloop + endfacet + facet normal -0.961376 -0.169493 0.216861 + outer loop + vertex 0.805 1.21325 2.525 + vertex 0.804296 1.21064 2.51984 + vertex 0.805 1.21 2.52246 + endloop + endfacet + facet normal -0.952361 -0.199398 0.230757 + outer loop + vertex 0.805 1.21325 2.525 + vertex 0.803857 1.21414 2.52105 + vertex 0.804296 1.21064 2.51984 + endloop + endfacet + facet normal -0.990781 -0.133025 0.0256426 + outer loop + vertex 0.803857 1.21414 2.52105 + vertex 0.803986 1.21271 2.51863 + vertex 0.804296 1.21064 2.51984 + endloop + endfacet + facet normal 0.958637 0.145102 -0.244869 + outer loop + vertex 0.805 1.21325 2.525 + vertex 0.804664 1.21307 2.52358 + vertex 0.803857 1.21414 2.52105 + endloop + endfacet + facet normal 0.0760542 0.172835 -0.98201 + outer loop + vertex 0.805 1.215 2.51905 + vertex 0.803867 1.21698 2.51931 + vertex 0.805 1.22 2.51993 + endloop + endfacet + facet normal 0.0515437 0.159351 -0.985875 + outer loop + vertex 0.803986 1.21271 2.51863 + vertex 0.803867 1.21698 2.51931 + vertex 0.805 1.215 2.51905 + endloop + endfacet + facet normal -0.99895 -0.021367 -0.0405233 + outer loop + vertex 0.803986 1.21271 2.51863 + vertex 0.803857 1.21414 2.52105 + vertex 0.803867 1.21698 2.51931 + endloop + endfacet + facet normal -0.987719 -0.0791869 -0.134684 + outer loop + vertex 0.803867 1.21698 2.51931 + vertex 0.803857 1.21414 2.52105 + vertex 0.803317 1.21877 2.52229 + endloop + endfacet + facet normal -0.980447 -0.14879 0.12878 + outer loop + vertex 0.803857 1.21414 2.52105 + vertex 0.803974 1.21624 2.52436 + vertex 0.803317 1.21877 2.52229 + endloop + endfacet + facet normal -0.947196 -0.254767 0.194713 + outer loop + vertex 0.804664 1.21307 2.52358 + vertex 0.803974 1.21624 2.52436 + vertex 0.803857 1.21414 2.52105 + endloop + endfacet + facet normal 0.0779863 0.172104 -0.981987 + outer loop + vertex 0.805 1.22 2.51993 + vertex 0.803867 1.21698 2.51931 + vertex 0.805 1.2204 2.52 + endloop + endfacet + facet normal -0.343756 0.24992 -0.905192 + outer loop + vertex 0.805 1.2204 2.52 + vertex 0.803644 1.22181 2.52091 + vertex 0.805 1.225 2.52127 + endloop + endfacet + facet normal -0.308403 0.285258 -0.907477 + outer loop + vertex 0.805 1.2204 2.52 + vertex 0.803867 1.21698 2.51931 + vertex 0.803644 1.22181 2.52091 + endloop + endfacet + facet normal -0.981281 0.0180137 -0.191737 + outer loop + vertex 0.803867 1.21698 2.51931 + vertex 0.803317 1.21877 2.52229 + vertex 0.803644 1.22181 2.52091 + endloop + endfacet + facet normal -0.980205 -0.16682 0.10663 + outer loop + vertex 0.803465 1.21992 2.52545 + vertex 0.803317 1.21877 2.52229 + vertex 0.803974 1.21624 2.52436 + endloop + endfacet + facet normal -0.995722 -0.0614463 0.0690076 + outer loop + vertex 0.803465 1.21992 2.52545 + vertex 0.803184 1.22363 2.52469 + vertex 0.803317 1.21877 2.52229 + endloop + endfacet + facet normal -0.989159 0.0421229 -0.140676 + outer loop + vertex 0.803184 1.22363 2.52469 + vertex 0.803644 1.22181 2.52091 + vertex 0.803317 1.21877 2.52229 + endloop + endfacet + facet normal -0.986277 -0.0420741 0.159647 + outer loop + vertex 0.803465 1.21992 2.52545 + vertex 0.803758 1.2221 2.52783 + vertex 0.803184 1.22363 2.52469 + endloop + endfacet + facet normal -0.420158 0.177954 -0.889831 + outer loop + vertex 0.805 1.225 2.52127 + vertex 0.803533 1.22693 2.52235 + vertex 0.805 1.23 2.52227 + endloop + endfacet + facet normal -0.33994 0.248505 -0.90702 + outer loop + vertex 0.803644 1.22181 2.52091 + vertex 0.803533 1.22693 2.52235 + vertex 0.805 1.225 2.52127 + endloop + endfacet + facet normal -0.99171 0.0143994 -0.127685 + outer loop + vertex 0.803644 1.22181 2.52091 + vertex 0.803184 1.22363 2.52469 + vertex 0.803533 1.22693 2.52235 + endloop + endfacet + facet normal -0.988079 -0.00454373 -0.15388 + outer loop + vertex 0.803533 1.22693 2.52235 + vertex 0.803184 1.22363 2.52469 + vertex 0.802921 1.22959 2.5262 + endloop + endfacet + facet normal -0.984879 -0.0821872 0.152509 + outer loop + vertex 0.803184 1.22363 2.52469 + vertex 0.80366 1.22595 2.52901 + vertex 0.802921 1.22959 2.5262 + endloop + endfacet + facet normal -0.986777 -0.0700078 0.146185 + outer loop + vertex 0.803758 1.2221 2.52783 + vertex 0.80366 1.22595 2.52901 + vertex 0.803184 1.22363 2.52469 + endloop + endfacet + facet normal -0.407057 0.0219016 -0.91314 + outer loop + vertex 0.805 1.23 2.52227 + vertex 0.803195 1.23243 2.52313 + vertex 0.805 1.235 2.52239 + endloop + endfacet + facet normal -0.295861 0.117017 -0.948037 + outer loop + vertex 0.803533 1.22693 2.52235 + vertex 0.803195 1.23243 2.52313 + vertex 0.805 1.23 2.52227 + endloop + endfacet + facet normal -0.990852 -0.0426218 -0.128045 + outer loop + vertex 0.803533 1.22693 2.52235 + vertex 0.802921 1.22959 2.5262 + vertex 0.803195 1.23243 2.52313 + endloop + endfacet + facet normal -0.967449 -0.136717 -0.212959 + outer loop + vertex 0.803195 1.23243 2.52313 + vertex 0.802921 1.22959 2.5262 + vertex 0.802304 1.23478 2.52567 + endloop + endfacet + facet normal -0.986589 -0.101788 0.127598 + outer loop + vertex 0.803417 1.22987 2.53026 + vertex 0.802921 1.22959 2.5262 + vertex 0.80366 1.22595 2.52901 + endloop + endfacet + facet normal -0.981711 -0.13948 0.129569 + outer loop + vertex 0.803417 1.22987 2.53026 + vertex 0.802716 1.23418 2.52959 + vertex 0.802921 1.22959 2.5262 + endloop + endfacet + facet normal -0.990252 -0.108582 0.0872439 + outer loop + vertex 0.802716 1.23418 2.52959 + vertex 0.802304 1.23478 2.52567 + vertex 0.802921 1.22959 2.5262 + endloop + endfacet + facet normal -0.956974 -0.114143 0.26678 + outer loop + vertex 0.803417 1.22987 2.53026 + vertex 0.803875 1.23195 2.5328 + vertex 0.802716 1.23418 2.52959 + endloop + endfacet + facet normal -0.550082 0.115786 -0.827045 + outer loop + vertex 0.805 1.235 2.52239 + vertex 0.802128 1.24 2.525 + vertex 0.805 1.24 2.52309 + endloop + endfacet + facet normal -0.531681 0.131391 -0.836691 + outer loop + vertex 0.803195 1.23243 2.52313 + vertex 0.802128 1.24 2.525 + vertex 0.805 1.235 2.52239 + endloop + endfacet + facet normal -0.959236 -0.0674801 -0.274432 + outer loop + vertex 0.803195 1.23243 2.52313 + vertex 0.802304 1.23478 2.52567 + vertex 0.802128 1.24 2.525 + endloop + endfacet + facet normal -0.958381 -0.0678206 -0.277318 + outer loop + vertex 0.802128 1.24 2.525 + vertex 0.802304 1.23478 2.52567 + vertex 0.801672 1.2389 2.52684 + endloop + endfacet + facet normal -0.982003 -0.1727 0.0764456 + outer loop + vertex 0.802304 1.23478 2.52567 + vertex 0.802716 1.23418 2.52959 + vertex 0.801672 1.2389 2.52684 + endloop + endfacet + facet normal -0.980212 -0.129873 0.149391 + outer loop + vertex 0.801672 1.2389 2.52684 + vertex 0.802716 1.23418 2.52959 + vertex 0.802252 1.23954 2.5312 + endloop + endfacet + facet normal -0.946657 -0.165217 0.276665 + outer loop + vertex 0.802716 1.23418 2.52959 + vertex 0.803711 1.23583 2.53398 + vertex 0.802252 1.23954 2.5312 + endloop + endfacet + facet normal -0.957388 -0.120717 0.262367 + outer loop + vertex 0.803875 1.23195 2.5328 + vertex 0.803711 1.23583 2.53398 + vertex 0.802716 1.23418 2.52959 + endloop + endfacet + facet normal -0.895896 -0.247091 -0.36921 + outer loop + vertex 0.802128 1.24 2.525 + vertex 0.801672 1.2389 2.52684 + vertex 0.800749 1.245 2.525 + endloop + endfacet + facet normal -0.989564 -0.132763 0.0560142 + outer loop + vertex 0.800749 1.245 2.525 + vertex 0.801672 1.2389 2.52684 + vertex 0.801244 1.24243 2.52764 + endloop + endfacet + facet normal -0.976435 -0.152925 0.152279 + outer loop + vertex 0.801672 1.2389 2.52684 + vertex 0.802252 1.23954 2.5312 + vertex 0.801244 1.24243 2.52764 + endloop + endfacet + facet normal -0.976519 -0.120926 0.17829 + outer loop + vertex 0.801244 1.24243 2.52764 + vertex 0.802252 1.23954 2.5312 + vertex 0.801534 1.2439 2.53023 + endloop + endfacet + facet normal -0.942346 -0.144759 0.301709 + outer loop + vertex 0.803496 1.23972 2.53518 + vertex 0.802252 1.23954 2.5312 + vertex 0.803711 1.23583 2.53398 + endloop + endfacet + facet normal -0.94313 -0.139553 0.301712 + outer loop + vertex 0.803496 1.23972 2.53518 + vertex 0.802617 1.2439 2.53436 + vertex 0.802252 1.23954 2.5312 + endloop + endfacet + facet normal -0.962257 -0.102117 0.252256 + outer loop + vertex 0.802617 1.2439 2.53436 + vertex 0.801534 1.2439 2.53023 + vertex 0.802252 1.23954 2.5312 + endloop + endfacet + facet normal -0.910545 -0.114007 0.397379 + outer loop + vertex 0.803496 1.23972 2.53518 + vertex 0.804216 1.24209 2.53751 + vertex 0.802617 1.2439 2.53436 + endloop + endfacet + facet normal 0.581082 0.268649 0.768227 + outer loop + vertex 0.800829 1.24861 2.52368 + vertex 0.8 1.24662 2.525 + vertex 0.800749 1.245 2.525 + endloop + endfacet + facet normal -0.972725 0.0983939 0.210061 + outer loop + vertex 0.800829 1.24861 2.52368 + vertex 0.800749 1.245 2.525 + vertex 0.801343 1.24731 2.52667 + endloop + endfacet + facet normal -0.966234 0.0691067 0.248225 + outer loop + vertex 0.801343 1.24731 2.52667 + vertex 0.800749 1.245 2.525 + vertex 0.801244 1.24243 2.52764 + endloop + endfacet + facet normal -0.995211 0.0381996 0.089978 + outer loop + vertex 0.801244 1.24243 2.52764 + vertex 0.801534 1.2439 2.53023 + vertex 0.801343 1.24731 2.52667 + endloop + endfacet + facet normal -0.99925 -0.025418 0.029227 + outer loop + vertex 0.801343 1.24731 2.52667 + vertex 0.801534 1.2439 2.53023 + vertex 0.801458 1.24802 2.53119 + endloop + endfacet + facet normal -0.964456 -0.0768411 0.252825 + outer loop + vertex 0.801534 1.2439 2.53023 + vertex 0.802617 1.2439 2.53436 + vertex 0.801458 1.24802 2.53119 + endloop + endfacet + facet normal -0.969287 -0.0997832 0.224781 + outer loop + vertex 0.801458 1.24802 2.53119 + vertex 0.802617 1.2439 2.53436 + vertex 0.802338 1.24924 2.53553 + endloop + endfacet + facet normal -0.904641 -0.135498 0.404061 + outer loop + vertex 0.802617 1.2439 2.53436 + vertex 0.804084 1.24632 2.53846 + vertex 0.802338 1.24924 2.53553 + endloop + endfacet + facet normal -0.910887 -0.117387 0.395607 + outer loop + vertex 0.804216 1.24209 2.53751 + vertex 0.804084 1.24632 2.53846 + vertex 0.802617 1.2439 2.53436 + endloop + endfacet + facet normal -0.402856 0.13029 0.905943 + outer loop + vertex 0.800998 1.25231 2.52322 + vertex 0.800829 1.24861 2.52368 + vertex 0.805 1.25231 2.525 + endloop + endfacet + facet normal -0.377522 -0.367568 0.849924 + outer loop + vertex 0.800998 1.25231 2.52322 + vertex 0.805 1.25231 2.525 + vertex 0.802381 1.255 2.525 + endloop + endfacet + facet normal -0.677284 0.624928 0.388267 + outer loop + vertex 0.800829 1.24861 2.52368 + vertex 0.801343 1.24731 2.52667 + vertex 0.805 1.25231 2.525 + endloop + endfacet + facet normal -0.543003 0.330072 -0.77214 + outer loop + vertex 0.805 1.255 2.52615 + vertex 0.805 1.25231 2.525 + vertex 0.801434 1.25292 2.52777 + endloop + endfacet + facet normal -0.587085 0.164437 -0.792649 + outer loop + vertex 0.801343 1.24731 2.52667 + vertex 0.801434 1.25292 2.52777 + vertex 0.805 1.25231 2.525 + endloop + endfacet + facet normal -0.999658 0.0116163 0.0234198 + outer loop + vertex 0.801343 1.24731 2.52667 + vertex 0.801458 1.24802 2.53119 + vertex 0.801434 1.25292 2.52777 + endloop + endfacet + facet normal -0.997127 -0.0465286 -0.0597659 + outer loop + vertex 0.801434 1.25292 2.52777 + vertex 0.801458 1.24802 2.53119 + vertex 0.801176 1.25225 2.53259 + endloop + endfacet + facet normal -0.961542 -0.142045 0.235077 + outer loop + vertex 0.801458 1.24802 2.53119 + vertex 0.802338 1.24924 2.53553 + vertex 0.801176 1.25225 2.53259 + endloop + endfacet + facet normal -0.959322 -0.122353 0.254423 + outer loop + vertex 0.801176 1.25225 2.53259 + vertex 0.802338 1.24924 2.53553 + vertex 0.801882 1.25469 2.53643 + endloop + endfacet + facet normal -0.899241 -0.143624 0.413205 + outer loop + vertex 0.802338 1.24924 2.53553 + vertex 0.803748 1.2513 2.53932 + vertex 0.801882 1.25469 2.53643 + endloop + endfacet + facet normal -0.903573 -0.130986 0.40792 + outer loop + vertex 0.804084 1.24632 2.53846 + vertex 0.803748 1.2513 2.53932 + vertex 0.802338 1.24924 2.53553 + endloop + endfacet + facet normal -0.32014 0.105774 0.941447 + outer loop + vertex 0.802381 1.255 2.525 + vertex 0.804033 1.26 2.525 + vertex 0.801411 1.25543 2.52462 + endloop + endfacet + facet normal -0.461947 -0.311348 0.830462 + outer loop + vertex 0.802381 1.255 2.525 + vertex 0.801411 1.25543 2.52462 + vertex 0.800998 1.25231 2.52322 + endloop + endfacet + facet normal 0.18295 -0.0236123 -0.982839 + outer loop + vertex 0.804033 1.26 2.525 + vertex 0.805 1.26 2.52518 + vertex 0.801411 1.25543 2.52462 + endloop + endfacet + facet normal 0.17004 -0.769118 -0.616072 + outer loop + vertex 0.801434 1.25292 2.52777 + vertex 0.801411 1.25543 2.52462 + vertex 0.805 1.255 2.52615 + endloop + endfacet + facet normal 0.367483 -0.177104 -0.913012 + outer loop + vertex 0.805 1.26 2.52518 + vertex 0.805 1.255 2.52615 + vertex 0.801411 1.25543 2.52462 + endloop + endfacet + facet normal -0.849152 -0.415643 -0.325855 + outer loop + vertex 0.799651 1.25669 2.5276 + vertex 0.801411 1.25543 2.52462 + vertex 0.801434 1.25292 2.52777 + endloop + endfacet + facet normal -0.898276 -0.418391 0.134347 + outer loop + vertex 0.799651 1.25669 2.5276 + vertex 0.801434 1.25292 2.52777 + vertex 0.800139 1.25701 2.53187 + endloop + endfacet + facet normal -0.971085 -0.22386 -0.082947 + outer loop + vertex 0.800139 1.25701 2.53187 + vertex 0.801434 1.25292 2.52777 + vertex 0.801176 1.25225 2.53259 + endloop + endfacet + facet normal -0.946464 -0.163561 0.278306 + outer loop + vertex 0.801176 1.25225 2.53259 + vertex 0.801882 1.25469 2.53643 + vertex 0.800139 1.25701 2.53187 + endloop + endfacet + facet normal -0.945979 -0.179566 0.269962 + outer loop + vertex 0.800139 1.25701 2.53187 + vertex 0.801882 1.25469 2.53643 + vertex 0.800816 1.25924 2.53572 + endloop + endfacet + facet normal -0.896449 -0.134334 0.422295 + outer loop + vertex 0.803474 1.25524 2.53999 + vertex 0.801882 1.25469 2.53643 + vertex 0.803748 1.2513 2.53932 + endloop + endfacet + facet normal -0.895928 -0.137146 0.422498 + outer loop + vertex 0.803474 1.25524 2.53999 + vertex 0.802506 1.25924 2.53923 + vertex 0.801882 1.25469 2.53643 + endloop + endfacet + facet normal -0.891738 -0.142126 0.429656 + outer loop + vertex 0.802506 1.25924 2.53923 + vertex 0.800816 1.25924 2.53572 + vertex 0.801882 1.25469 2.53643 + endloop + endfacet + facet normal -0.862195 -0.115578 0.493215 + outer loop + vertex 0.803474 1.25524 2.53999 + vertex 0.80432 1.25756 2.54201 + vertex 0.802506 1.25924 2.53923 + endloop + endfacet + facet normal -0.956958 -0.259936 0.12909 + outer loop + vertex 0.798805 1.26055 2.52911 + vertex 0.799651 1.25669 2.5276 + vertex 0.800139 1.25701 2.53187 + endloop + endfacet + facet normal -0.955793 -0.177072 0.234744 + outer loop + vertex 0.799478 1.2627 2.53346 + vertex 0.798805 1.26055 2.52911 + vertex 0.800139 1.25701 2.53187 + endloop + endfacet + facet normal -0.943588 -0.186541 0.273578 + outer loop + vertex 0.800139 1.25701 2.53187 + vertex 0.800816 1.25924 2.53572 + vertex 0.799478 1.2627 2.53346 + endloop + endfacet + facet normal -0.923736 -0.119777 0.363821 + outer loop + vertex 0.799478 1.2627 2.53346 + vertex 0.800816 1.25924 2.53572 + vertex 0.800928 1.26255 2.5371 + endloop + endfacet + facet normal -0.890952 -0.148099 0.429267 + outer loop + vertex 0.800816 1.25924 2.53572 + vertex 0.802506 1.25924 2.53923 + vertex 0.800928 1.26255 2.5371 + endloop + endfacet + facet normal -0.877186 -0.118326 0.465343 + outer loop + vertex 0.800928 1.26255 2.5371 + vertex 0.802506 1.25924 2.53923 + vertex 0.802248 1.26434 2.54004 + endloop + endfacet + facet normal -0.857174 -0.122851 0.50016 + outer loop + vertex 0.802506 1.25924 2.53923 + vertex 0.804244 1.26155 2.54278 + vertex 0.802248 1.26434 2.54004 + endloop + endfacet + facet normal -0.861602 -0.11178 0.495123 + outer loop + vertex 0.80432 1.25756 2.54201 + vertex 0.804244 1.26155 2.54278 + vertex 0.802506 1.25924 2.53923 + endloop + endfacet + facet normal -0.965869 -0.139906 0.217998 + outer loop + vertex 0.798805 1.26055 2.52911 + vertex 0.799478 1.2627 2.53346 + vertex 0.798445 1.26468 2.53016 + endloop + endfacet + facet normal -0.965698 -0.115685 0.232473 + outer loop + vertex 0.798795 1.26698 2.53276 + vertex 0.798445 1.26468 2.53016 + vertex 0.799478 1.2627 2.53346 + endloop + endfacet + facet normal -0.934832 -0.0925975 0.342804 + outer loop + vertex 0.798795 1.26698 2.53276 + vertex 0.799478 1.2627 2.53346 + vertex 0.800183 1.26712 2.53658 + endloop + endfacet + facet normal -0.924687 -0.109595 0.364613 + outer loop + vertex 0.800183 1.26712 2.53658 + vertex 0.799478 1.2627 2.53346 + vertex 0.800928 1.26255 2.5371 + endloop + endfacet + facet normal -0.886092 -0.0932261 0.454036 + outer loop + vertex 0.800928 1.26255 2.5371 + vertex 0.802248 1.26434 2.54004 + vertex 0.800183 1.26712 2.53658 + endloop + endfacet + facet normal -0.891841 -0.119666 0.436233 + outer loop + vertex 0.800183 1.26712 2.53658 + vertex 0.802248 1.26434 2.54004 + vertex 0.801889 1.26937 2.54068 + endloop + endfacet + facet normal -0.857202 -0.125304 0.499504 + outer loop + vertex 0.802248 1.26434 2.54004 + vertex 0.804001 1.26653 2.5436 + vertex 0.801889 1.26937 2.54068 + endloop + endfacet + facet normal -0.857616 -0.124244 0.499057 + outer loop + vertex 0.804244 1.26155 2.54278 + vertex 0.804001 1.26653 2.5436 + vertex 0.802248 1.26434 2.54004 + endloop + endfacet + facet normal 0.487139 0.60381 -0.630959 + outer loop + vertex 0.805 1.27477 2.53 + vertex 0.804715 1.275 2.53 + vertex 0.805 1.275 2.53022 + endloop + endfacet + facet normal -0.93674 -0.0712952 0.342688 + outer loop + vertex 0.798817 1.27103 2.53366 + vertex 0.798795 1.26698 2.53276 + vertex 0.800183 1.26712 2.53658 + endloop + endfacet + facet normal -0.943691 -0.092479 0.31764 + outer loop + vertex 0.800035 1.27261 2.53774 + vertex 0.798817 1.27103 2.53366 + vertex 0.800183 1.26712 2.53658 + endloop + endfacet + facet normal -0.893137 -0.115758 0.434633 + outer loop + vertex 0.800183 1.26712 2.53658 + vertex 0.801889 1.26937 2.54068 + vertex 0.800035 1.27261 2.53774 + endloop + endfacet + facet normal -0.898567 -0.134153 0.417828 + outer loop + vertex 0.800035 1.27261 2.53774 + vertex 0.801889 1.26937 2.54068 + vertex 0.801595 1.27467 2.54176 + endloop + endfacet + facet normal -0.85906 -0.146643 0.49042 + outer loop + vertex 0.801889 1.26937 2.54068 + vertex 0.803603 1.27138 2.54429 + vertex 0.801595 1.27467 2.54176 + endloop + endfacet + facet normal -0.861484 -0.140282 0.488022 + outer loop + vertex 0.804001 1.26653 2.5436 + vertex 0.803603 1.27138 2.54429 + vertex 0.801889 1.26937 2.54068 + endloop + endfacet + facet normal -0.940403 -0.107711 0.322554 + outer loop + vertex 0.798613 1.27594 2.5347 + vertex 0.798817 1.27103 2.53366 + vertex 0.800035 1.27261 2.53774 + endloop + endfacet + facet normal -0.944084 -0.125284 0.304974 + outer loop + vertex 0.799688 1.27775 2.53878 + vertex 0.798613 1.27594 2.5347 + vertex 0.800035 1.27261 2.53774 + endloop + endfacet + facet normal -0.894716 -0.14562 0.42223 + outer loop + vertex 0.800035 1.27261 2.53774 + vertex 0.801595 1.27467 2.54176 + vertex 0.799688 1.27775 2.53878 + endloop + endfacet + facet normal -0.899814 -0.167628 0.402786 + outer loop + vertex 0.799688 1.27775 2.53878 + vertex 0.801595 1.27467 2.54176 + vertex 0.800861 1.27825 2.5416 + endloop + endfacet + facet normal -0.862227 -0.154833 0.482277 + outer loop + vertex 0.803286 1.27519 2.54495 + vertex 0.801595 1.27467 2.54176 + vertex 0.803603 1.27138 2.54429 + endloop + endfacet + facet normal -0.861229 -0.159575 0.482515 + outer loop + vertex 0.803286 1.27519 2.54495 + vertex 0.802237 1.279 2.54434 + vertex 0.801595 1.27467 2.54176 + endloop + endfacet + facet normal -0.863789 -0.156971 0.478778 + outer loop + vertex 0.802237 1.279 2.54434 + vertex 0.800861 1.27825 2.5416 + vertex 0.801595 1.27467 2.54176 + endloop + endfacet + facet normal -0.840699 -0.147783 0.520946 + outer loop + vertex 0.803286 1.27519 2.54495 + vertex 0.80413 1.27753 2.54697 + vertex 0.802237 1.279 2.54434 + endloop + endfacet + facet normal -0.935785 -0.155721 0.316318 + outer loop + vertex 0.798613 1.27594 2.5347 + vertex 0.799688 1.27775 2.53878 + vertex 0.798309 1.27979 2.5357 + endloop + endfacet + facet normal -0.936275 -0.167126 0.308963 + outer loop + vertex 0.798768 1.28169 2.53812 + vertex 0.798309 1.27979 2.5357 + vertex 0.799688 1.27775 2.53878 + endloop + endfacet + facet normal -0.907364 -0.146335 0.394052 + outer loop + vertex 0.798768 1.28169 2.53812 + vertex 0.799688 1.27775 2.53878 + vertex 0.800228 1.28201 2.5416 + endloop + endfacet + facet normal -0.903239 -0.151743 0.401414 + outer loop + vertex 0.800228 1.28201 2.5416 + vertex 0.799688 1.27775 2.53878 + vertex 0.800861 1.27825 2.5416 + endloop + endfacet + facet normal -0.86671 -0.145594 0.477091 + outer loop + vertex 0.800861 1.27825 2.5416 + vertex 0.802237 1.279 2.54434 + vertex 0.800228 1.28201 2.5416 + endloop + endfacet + facet normal -0.867703 -0.148806 0.474287 + outer loop + vertex 0.800228 1.28201 2.5416 + vertex 0.802237 1.279 2.54434 + vertex 0.801972 1.28434 2.54552 + endloop + endfacet + facet normal -0.830941 -0.160013 0.532853 + outer loop + vertex 0.802237 1.279 2.54434 + vertex 0.804006 1.28164 2.54789 + vertex 0.801972 1.28434 2.54552 + endloop + endfacet + facet normal -0.839969 -0.141744 0.523794 + outer loop + vertex 0.80413 1.27753 2.54697 + vertex 0.804006 1.28164 2.54789 + vertex 0.802237 1.279 2.54434 + endloop + endfacet + facet normal -0.905913 -0.154682 0.394201 + outer loop + vertex 0.79857 1.28565 2.53922 + vertex 0.798768 1.28169 2.53812 + vertex 0.800228 1.28201 2.5416 + endloop + endfacet + facet normal -0.900512 -0.141003 0.411334 + outer loop + vertex 0.800103 1.288 2.54338 + vertex 0.79857 1.28565 2.53922 + vertex 0.800228 1.28201 2.5416 + endloop + endfacet + facet normal -0.863016 -0.160336 0.479056 + outer loop + vertex 0.800228 1.28201 2.5416 + vertex 0.801972 1.28434 2.54552 + vertex 0.800103 1.288 2.54338 + endloop + endfacet + facet normal -0.893144 -0.161069 0.419942 + outer loop + vertex 0.79857 1.28565 2.53922 + vertex 0.800103 1.288 2.54338 + vertex 0.798364 1.28973 2.54035 + endloop + endfacet + facet normal -0.892438 -0.151663 0.424915 + outer loop + vertex 0.799103 1.29227 2.54281 + vertex 0.798364 1.28973 2.54035 + vertex 0.800103 1.288 2.54338 + endloop + endfacet + facet normal -0.853123 -0.131697 0.504814 + outer loop + vertex 0.799103 1.29227 2.54281 + vertex 0.800103 1.288 2.54338 + vertex 0.801208 1.29353 2.54669 + endloop + endfacet + facet normal -0.85581 -0.121246 0.50288 + outer loop + vertex 0.798936 1.29652 2.54355 + vertex 0.799103 1.29227 2.54281 + vertex 0.801208 1.29353 2.54669 + endloop + endfacet + facet normal -0.85973 -0.135093 0.492559 + outer loop + vertex 0.800299 1.29877 2.54654 + vertex 0.798936 1.29652 2.54355 + vertex 0.801208 1.29353 2.54669 + endloop + endfacet + facet normal -0.802539 -0.122584 0.58387 + outer loop + vertex 0.802543 1.29901 2.54968 + vertex 0.800299 1.29877 2.54654 + vertex 0.801208 1.29353 2.54669 + endloop + endfacet + facet normal -0.865459 -0.122569 0.485754 + outer loop + vertex 0.798922 1.3019 2.54488 + vertex 0.798936 1.29652 2.54355 + vertex 0.800299 1.29877 2.54654 + endloop + endfacet + facet normal -0.864217 -0.120588 0.488454 + outer loop + vertex 0.800529 1.30371 2.54817 + vertex 0.798922 1.3019 2.54488 + vertex 0.800299 1.29877 2.54654 + endloop + endfacet + facet normal -0.797723 -0.154773 0.582823 + outer loop + vertex 0.800299 1.29877 2.54654 + vertex 0.802543 1.29901 2.54968 + vertex 0.800529 1.30371 2.54817 + endloop + endfacet + facet normal -0.785826 -0.143667 0.60153 + outer loop + vertex 0.800529 1.30371 2.54817 + vertex 0.802543 1.29901 2.54968 + vertex 0.80229 1.30481 2.55073 + endloop + endfacet + facet normal -0.826008 -0.214445 0.521271 + outer loop + vertex 0.8 1.31 2.54992 + vertex 0.798922 1.3019 2.54488 + vertex 0.800529 1.30371 2.54817 + endloop + endfacet + facet normal -0.749323 -0.235196 0.61903 + outer loop + vertex 0.800066 1.31 2.55 + vertex 0.8 1.31 2.54992 + vertex 0.800529 1.30371 2.54817 + endloop + endfacet + facet normal -0.751113 -0.234746 0.617028 + outer loop + vertex 0.800529 1.30371 2.54817 + vertex 0.80229 1.30481 2.55073 + vertex 0.800066 1.31 2.55 + endloop + endfacet + facet normal -0.789208 -0.259638 0.556542 + outer loop + vertex 0.800066 1.31 2.55 + vertex 0.80229 1.30481 2.55073 + vertex 0.803592 1.31 2.555 + endloop + endfacet + facet normal -0.482362 0.783182 0.392369 + outer loop + vertex 0.8 1.31 2.54992 + vertex 0.800065 1.31 2.55 + vertex 0.798727 1.311 2.54636 + endloop + endfacet + facet normal -0.927898 0.0822607 0.363645 + outer loop + vertex 0.799328 1.31274 2.5475 + vertex 0.798727 1.311 2.54636 + vertex 0.800065 1.31 2.55 + endloop + endfacet + facet normal -0.860336 0.197495 0.469912 + outer loop + vertex 0.799328 1.31274 2.5475 + vertex 0.800065 1.31 2.55 + vertex 0.801282 1.31351 2.55075 + endloop + endfacet + facet normal -0.844081 -0.107299 0.525371 + outer loop + vertex 0.800713 1.32387 2.55154 + vertex 0.799087 1.32163 2.54847 + vertex 0.801117 1.31902 2.5512 + endloop + endfacet + facet normal -0.842154 -0.111672 0.527547 + outer loop + vertex 0.798892 1.32609 2.54911 + vertex 0.799087 1.32163 2.54847 + vertex 0.800713 1.32387 2.55154 + endloop + endfacet + facet normal -0.842605 -0.113191 0.526503 + outer loop + vertex 0.80022 1.32677 2.55138 + vertex 0.798892 1.32609 2.54911 + vertex 0.800713 1.32387 2.55154 + endloop + endfacet + facet normal -0.795022 -0.100997 0.598113 + outer loop + vertex 0.800713 1.32387 2.55154 + vertex 0.802079 1.32738 2.55395 + vertex 0.80022 1.32677 2.55138 + endloop + endfacet + facet normal -0.846941 -0.0940513 0.523303 + outer loop + vertex 0.798892 1.32609 2.54911 + vertex 0.80022 1.32677 2.55138 + vertex 0.799419 1.3294 2.55055 + endloop + endfacet + facet normal -0.796859 -0.0992617 0.595955 + outer loop + vertex 0.802079 1.32738 2.55395 + vertex 0.802636 1.33109 2.55531 + vertex 0.800636 1.33209 2.55281 + endloop + endfacet + facet normal -0.813392 -0.110353 0.571153 + outer loop + vertex 0.802079 1.32738 2.55395 + vertex 0.800636 1.33209 2.55281 + vertex 0.799419 1.3294 2.55055 + endloop + endfacet + facet normal -0.802633 -0.0585731 0.59359 + outer loop + vertex 0.802079 1.32738 2.55395 + vertex 0.799419 1.3294 2.55055 + vertex 0.80022 1.32677 2.55138 + endloop + endfacet + facet normal -0.703571 -0.000605485 0.710624 + outer loop + vertex 0.802976 1.50985 2.57014 + vertex 0.805306 1.51195 2.57245 + vertex 0.802174 1.51415 2.56935 + endloop + endfacet + facet normal -0.704363 -0.00284453 0.709834 + outer loop + vertex 0.805306 1.51195 2.57245 + vertex 0.804802 1.51719 2.57197 + vertex 0.802174 1.51415 2.56935 + endloop + endfacet + facet normal -0.707485 0.0017894 0.706726 + outer loop + vertex 0.802958 1.52279 2.57013 + vertex 0.802448 1.5193 2.56962 + vertex 0.804407 1.52091 2.57158 + endloop + endfacet + facet normal -0.770888 0.106138 0.628066 + outer loop + vertex 0.798888 1.68101 2.55279 + vertex 0.798485 1.67594 2.55315 + vertex 0.800987 1.67849 2.55579 + endloop + endfacet + facet normal -0.820603 0.0843537 0.565239 + outer loop + vertex 0.801365 1.7133 2.55068 + vertex 0.799228 1.71089 2.54794 + vertex 0.80113 1.70818 2.5511 + endloop + endfacet + facet normal -0.777304 0.0871597 0.623058 + outer loop + vertex 0.80113 1.70818 2.5511 + vertex 0.803406 1.71088 2.55356 + vertex 0.801365 1.7133 2.55068 + endloop + endfacet + facet normal -0.821828 0.0881196 0.56288 + outer loop + vertex 0.799547 1.71582 2.54763 + vertex 0.799228 1.71089 2.54794 + vertex 0.801365 1.7133 2.55068 + endloop + endfacet + facet normal -0.825293 0.0807842 0.558896 + outer loop + vertex 0.801609 1.71828 2.55032 + vertex 0.799547 1.71582 2.54763 + vertex 0.801365 1.7133 2.55068 + endloop + endfacet + facet normal -0.775004 0.0831946 0.626456 + outer loop + vertex 0.801365 1.7133 2.55068 + vertex 0.803678 1.71594 2.55319 + vertex 0.801609 1.71828 2.55032 + endloop + endfacet + facet normal -0.776962 0.0878422 0.623389 + outer loop + vertex 0.803406 1.71088 2.55356 + vertex 0.803678 1.71594 2.55319 + vertex 0.801365 1.7133 2.55068 + endloop + endfacet + facet normal -0.824523 0.0785477 0.560351 + outer loop + vertex 0.799771 1.72046 2.54731 + vertex 0.799547 1.71582 2.54763 + vertex 0.801609 1.71828 2.55032 + endloop + endfacet + facet normal -0.820435 0.088233 0.56489 + outer loop + vertex 0.801657 1.72354 2.54957 + vertex 0.799771 1.72046 2.54731 + vertex 0.801609 1.71828 2.55032 + endloop + endfacet + facet normal -0.77119 0.0969579 0.629179 + outer loop + vertex 0.801609 1.71828 2.55032 + vertex 0.80396 1.72093 2.55279 + vertex 0.801657 1.72354 2.54957 + endloop + endfacet + facet normal -0.769829 0.0937476 0.631328 + outer loop + vertex 0.803678 1.71594 2.55319 + vertex 0.80396 1.72093 2.55279 + vertex 0.801609 1.71828 2.55032 + endloop + endfacet + facet normal -0.866081 0.129436 0.482856 + outer loop + vertex 0.800401 1.72744 2.54699 + vertex 0.798975 1.72644 2.5447 + vertex 0.799758 1.72407 2.54674 + endloop + endfacet + facet normal -0.819596 0.0866482 0.566352 + outer loop + vertex 0.799758 1.72407 2.54674 + vertex 0.799771 1.72046 2.54731 + vertex 0.801657 1.72354 2.54957 + endloop + endfacet + facet normal -0.81503 0.11341 0.568211 + outer loop + vertex 0.799758 1.72407 2.54674 + vertex 0.801657 1.72354 2.54957 + vertex 0.800401 1.72744 2.54699 + endloop + endfacet + facet normal -0.80655 0.122813 0.578268 + outer loop + vertex 0.800401 1.72744 2.54699 + vertex 0.801657 1.72354 2.54957 + vertex 0.802394 1.72837 2.54957 + endloop + endfacet + facet normal -0.768859 0.117051 0.628613 + outer loop + vertex 0.801657 1.72354 2.54957 + vertex 0.804212 1.72576 2.55228 + vertex 0.802394 1.72837 2.54957 + endloop + endfacet + facet normal -0.765981 0.107301 0.633845 + outer loop + vertex 0.80396 1.72093 2.55279 + vertex 0.804212 1.72576 2.55228 + vertex 0.801657 1.72354 2.54957 + endloop + endfacet + facet normal -0.866966 0.143539 0.47725 + outer loop + vertex 0.799137 1.7304 2.5438 + vertex 0.798975 1.72644 2.5447 + vertex 0.800401 1.72744 2.54699 + endloop + endfacet + facet normal -0.860841 0.154364 0.484897 + outer loop + vertex 0.80116 1.73246 2.54674 + vertex 0.799137 1.7304 2.5438 + vertex 0.800401 1.72744 2.54699 + endloop + endfacet + facet normal -0.803 0.156173 0.575153 + outer loop + vertex 0.80317 1.73175 2.54974 + vertex 0.80116 1.73246 2.54674 + vertex 0.802394 1.72837 2.54957 + endloop + endfacet + facet normal -0.80815 0.150625 0.56939 + outer loop + vertex 0.80116 1.73246 2.54674 + vertex 0.800401 1.72744 2.54699 + vertex 0.802394 1.72837 2.54957 + endloop + endfacet + facet normal -0.857374 0.133567 0.497061 + outer loop + vertex 0.799368 1.73536 2.54287 + vertex 0.799137 1.7304 2.5438 + vertex 0.80116 1.73246 2.54674 + endloop + endfacet + facet normal -0.856945 0.134488 0.497552 + outer loop + vertex 0.801117 1.73858 2.54501 + vertex 0.799368 1.73536 2.54287 + vertex 0.80116 1.73246 2.54674 + endloop + endfacet + facet normal -0.79817 0.158529 0.5812 + outer loop + vertex 0.80116 1.73246 2.54674 + vertex 0.803312 1.73566 2.54882 + vertex 0.801117 1.73858 2.54501 + endloop + endfacet + facet normal -0.801031 0.164038 0.575709 + outer loop + vertex 0.80317 1.73175 2.54974 + vertex 0.803312 1.73566 2.54882 + vertex 0.80116 1.73246 2.54674 + endloop + endfacet + facet normal -0.893924 0.134087 0.427693 + outer loop + vertex 0.799903 1.7427 2.54202 + vertex 0.798664 1.7417 2.53974 + vertex 0.799318 1.73927 2.54187 + endloop + endfacet + facet normal -0.849851 0.120293 0.51311 + outer loop + vertex 0.799318 1.73927 2.54187 + vertex 0.799368 1.73536 2.54287 + vertex 0.801117 1.73858 2.54501 + endloop + endfacet + facet normal -0.849355 0.122705 0.513361 + outer loop + vertex 0.799318 1.73927 2.54187 + vertex 0.801117 1.73858 2.54501 + vertex 0.799903 1.7427 2.54202 + endloop + endfacet + facet normal -0.831928 0.144173 0.535826 + outer loop + vertex 0.799903 1.7427 2.54202 + vertex 0.801117 1.73858 2.54501 + vertex 0.801863 1.74392 2.54473 + endloop + endfacet + facet normal -0.795112 0.141849 0.589641 + outer loop + vertex 0.801117 1.73858 2.54501 + vertex 0.803711 1.74079 2.54798 + vertex 0.801863 1.74392 2.54473 + endloop + endfacet + facet normal -0.79859 0.157741 0.580838 + outer loop + vertex 0.803312 1.73566 2.54882 + vertex 0.803711 1.74079 2.54798 + vertex 0.801117 1.73858 2.54501 + endloop + endfacet + facet normal -0.893803 0.131543 0.428734 + outer loop + vertex 0.798838 1.74558 2.53891 + vertex 0.798664 1.7417 2.53974 + vertex 0.799903 1.7427 2.54202 + endloop + endfacet + facet normal -0.890123 0.138684 0.434107 + outer loop + vertex 0.800458 1.74724 2.5417 + vertex 0.798838 1.74558 2.53891 + vertex 0.799903 1.7427 2.54202 + endloop + endfacet + facet normal -0.831478 0.138709 0.537962 + outer loop + vertex 0.799903 1.7427 2.54202 + vertex 0.801863 1.74392 2.54473 + vertex 0.800458 1.74724 2.5417 + endloop + endfacet + facet normal -0.826561 0.145926 0.543601 + outer loop + vertex 0.800458 1.74724 2.5417 + vertex 0.801863 1.74392 2.54473 + vertex 0.802465 1.74842 2.54444 + endloop + endfacet + facet normal -0.789636 0.144421 0.596337 + outer loop + vertex 0.801863 1.74392 2.54473 + vertex 0.804107 1.74575 2.54726 + vertex 0.802465 1.74842 2.54444 + endloop + endfacet + facet normal -0.790616 0.148942 0.593921 + outer loop + vertex 0.803711 1.74079 2.54798 + vertex 0.804107 1.74575 2.54726 + vertex 0.801863 1.74392 2.54473 + endloop + endfacet + facet normal -0.887723 0.118144 0.44496 + outer loop + vertex 0.799204 1.75047 2.53834 + vertex 0.798838 1.74558 2.53891 + vertex 0.800458 1.74724 2.5417 + endloop + endfacet + facet normal -0.87201 0.14703 0.466884 + outer loop + vertex 0.801264 1.75243 2.54157 + vertex 0.799204 1.75047 2.53834 + vertex 0.800458 1.74724 2.5417 + endloop + endfacet + facet normal -0.791253 0.144108 0.594265 + outer loop + vertex 0.803261 1.7517 2.5447 + vertex 0.802465 1.74842 2.54444 + vertex 0.804243 1.74946 2.54655 + endloop + endfacet + facet normal -0.816347 0.153191 0.556876 + outer loop + vertex 0.803261 1.7517 2.5447 + vertex 0.801264 1.75243 2.54157 + vertex 0.802465 1.74842 2.54444 + endloop + endfacet + facet normal -0.82626 0.141846 0.545136 + outer loop + vertex 0.801264 1.75243 2.54157 + vertex 0.800458 1.74724 2.5417 + vertex 0.802465 1.74842 2.54444 + endloop + endfacet + facet normal -0.791031 0.142175 0.595027 + outer loop + vertex 0.804243 1.74946 2.54655 + vertex 0.802465 1.74842 2.54444 + vertex 0.804107 1.74575 2.54726 + endloop + endfacet + facet normal -0.868037 0.117062 0.482503 + outer loop + vertex 0.799471 1.75539 2.53763 + vertex 0.799204 1.75047 2.53834 + vertex 0.801264 1.75243 2.54157 + endloop + endfacet + facet normal -0.857171 0.140845 0.4954 + outer loop + vertex 0.801299 1.75843 2.53993 + vertex 0.799471 1.75539 2.53763 + vertex 0.801264 1.75243 2.54157 + endloop + endfacet + facet normal -0.819023 0.156184 0.552095 + outer loop + vertex 0.801264 1.75243 2.54157 + vertex 0.803426 1.75552 2.54391 + vertex 0.801299 1.75843 2.53993 + endloop + endfacet + facet normal -0.816835 0.151162 0.556714 + outer loop + vertex 0.803261 1.7517 2.5447 + vertex 0.803426 1.75552 2.54391 + vertex 0.801264 1.75243 2.54157 + endloop + endfacet + facet normal -0.890098 0.177445 0.419808 + outer loop + vertex 0.800125 1.76258 2.53658 + vertex 0.798845 1.76159 2.53428 + vertex 0.799469 1.7592 2.53662 + endloop + endfacet + facet normal -0.8539 0.133015 0.503153 + outer loop + vertex 0.799469 1.7592 2.53662 + vertex 0.799471 1.75539 2.53763 + vertex 0.801299 1.75843 2.53993 + endloop + endfacet + facet normal -0.845174 0.169717 0.50683 + outer loop + vertex 0.799469 1.7592 2.53662 + vertex 0.801299 1.75843 2.53993 + vertex 0.800125 1.76258 2.53658 + endloop + endfacet + facet normal -0.846904 0.167493 0.504679 + outer loop + vertex 0.800125 1.76258 2.53658 + vertex 0.801299 1.75843 2.53993 + vertex 0.802117 1.76376 2.53953 + endloop + endfacet + facet normal -0.822171 0.166652 0.544299 + outer loop + vertex 0.801299 1.75843 2.53993 + vertex 0.803858 1.76056 2.54314 + vertex 0.802117 1.76376 2.53953 + endloop + endfacet + facet normal -0.820133 0.153969 0.551068 + outer loop + vertex 0.803426 1.75552 2.54391 + vertex 0.803858 1.76056 2.54314 + vertex 0.801299 1.75843 2.53993 + endloop + endfacet + facet normal -0.890098 0.182859 0.417478 + outer loop + vertex 0.799044 1.76528 2.53309 + vertex 0.798845 1.76159 2.53428 + vertex 0.800125 1.76258 2.53658 + endloop + endfacet + facet normal -0.894749 0.173337 0.411557 + outer loop + vertex 0.800632 1.76771 2.53553 + vertex 0.799044 1.76528 2.53309 + vertex 0.800125 1.76258 2.53658 + endloop + endfacet + facet normal -0.847286 0.186323 0.497383 + outer loop + vertex 0.800125 1.76258 2.53658 + vertex 0.802117 1.76376 2.53953 + vertex 0.800632 1.76771 2.53553 + endloop + endfacet + facet normal -0.864682 0.158662 0.476604 + outer loop + vertex 0.800632 1.76771 2.53553 + vertex 0.802117 1.76376 2.53953 + vertex 0.802778 1.76835 2.5392 + endloop + endfacet + facet normal -0.834499 0.157958 0.527883 + outer loop + vertex 0.802117 1.76376 2.53953 + vertex 0.804261 1.7655 2.5424 + vertex 0.802778 1.76835 2.5392 + endloop + endfacet + facet normal -0.833128 0.147908 0.532937 + outer loop + vertex 0.803858 1.76056 2.54314 + vertex 0.804261 1.7655 2.5424 + vertex 0.802117 1.76376 2.53953 + endloop + endfacet + facet normal -0.923162 0.173769 0.342895 + outer loop + vertex 0.799841 1.77241 2.53197 + vertex 0.798735 1.77151 2.52945 + vertex 0.799179 1.76902 2.53191 + endloop + endfacet + facet normal -0.892924 0.164697 0.419 + outer loop + vertex 0.799179 1.76902 2.53191 + vertex 0.799044 1.76528 2.53309 + vertex 0.800632 1.76771 2.53553 + endloop + endfacet + facet normal -0.892444 0.166299 0.419392 + outer loop + vertex 0.799179 1.76902 2.53191 + vertex 0.800632 1.76771 2.53553 + vertex 0.799841 1.77241 2.53197 + endloop + endfacet + facet normal -0.893907 0.164293 0.417058 + outer loop + vertex 0.799841 1.77241 2.53197 + vertex 0.800632 1.76771 2.53553 + vertex 0.801827 1.77306 2.53598 + endloop + endfacet + facet normal -0.849903 0.129267 0.510838 + outer loop + vertex 0.803557 1.77162 2.53967 + vertex 0.802778 1.76835 2.5392 + vertex 0.804396 1.76922 2.54167 + endloop + endfacet + facet normal -0.87419 0.141707 0.464446 + outer loop + vertex 0.803557 1.77162 2.53967 + vertex 0.801827 1.77306 2.53598 + vertex 0.802778 1.76835 2.5392 + endloop + endfacet + facet normal -0.865054 0.152746 0.47786 + outer loop + vertex 0.801827 1.77306 2.53598 + vertex 0.800632 1.76771 2.53553 + vertex 0.802778 1.76835 2.5392 + endloop + endfacet + facet normal -0.84995 0.130406 0.510469 + outer loop + vertex 0.804396 1.76922 2.54167 + vertex 0.802778 1.76835 2.5392 + vertex 0.804261 1.7655 2.5424 + endloop + endfacet + facet normal 0.585745 -0.324581 -0.742664 + outer loop + vertex 0.805 1.77548 2.525 + vertex 0.805 1.775 2.52521 + vertex 0.804734 1.775 2.525 + endloop + endfacet + facet normal -0.923427 0.167827 0.345133 + outer loop + vertex 0.798943 1.77524 2.5282 + vertex 0.798735 1.77151 2.52945 + vertex 0.799841 1.77241 2.53197 + endloop + endfacet + facet normal -0.926403 0.160709 0.340514 + outer loop + vertex 0.800328 1.77786 2.53073 + vertex 0.798943 1.77524 2.5282 + vertex 0.799841 1.77241 2.53197 + endloop + endfacet + facet normal -0.892939 0.174713 0.414892 + outer loop + vertex 0.799841 1.77241 2.53197 + vertex 0.801827 1.77306 2.53598 + vertex 0.800328 1.77786 2.53073 + endloop + endfacet + facet normal -0.92051 0.119291 0.372063 + outer loop + vertex 0.800328 1.77786 2.53073 + vertex 0.801827 1.77306 2.53598 + vertex 0.802241 1.77884 2.53515 + endloop + endfacet + facet normal -0.885133 0.127571 0.447511 + outer loop + vertex 0.801827 1.77306 2.53598 + vertex 0.803741 1.77557 2.53905 + vertex 0.802241 1.77884 2.53515 + endloop + endfacet + facet normal -0.882131 0.113481 0.457129 + outer loop + vertex 0.803557 1.77162 2.53967 + vertex 0.803741 1.77557 2.53905 + vertex 0.801827 1.77306 2.53598 + endloop + endfacet + facet normal -0.943611 0.186205 0.273724 + outer loop + vertex 0.799974 1.78375 2.52654 + vertex 0.798988 1.78169 2.52454 + vertex 0.799132 1.7792 2.52673 + endloop + endfacet + facet normal -0.927593 0.167875 0.333749 + outer loop + vertex 0.799132 1.7792 2.52673 + vertex 0.798943 1.77524 2.5282 + vertex 0.800328 1.77786 2.53073 + endloop + endfacet + facet normal -0.922776 0.184976 0.338036 + outer loop + vertex 0.799132 1.7792 2.52673 + vertex 0.800328 1.77786 2.53073 + vertex 0.799974 1.78375 2.52654 + endloop + endfacet + facet normal -0.938947 0.160154 0.304514 + outer loop + vertex 0.799974 1.78375 2.52654 + vertex 0.800328 1.77786 2.53073 + vertex 0.801254 1.78309 2.53083 + endloop + endfacet + facet normal -0.91863 0.155396 0.363279 + outer loop + vertex 0.800328 1.77786 2.53073 + vertex 0.802241 1.77884 2.53515 + vertex 0.801254 1.78309 2.53083 + endloop + endfacet + facet normal -0.946144 0.0945957 0.309618 + outer loop + vertex 0.801254 1.78309 2.53083 + vertex 0.802241 1.77884 2.53515 + vertex 0.802685 1.78391 2.53496 + endloop + endfacet + facet normal -0.904396 0.0949624 0.415992 + outer loop + vertex 0.802241 1.77884 2.53515 + vertex 0.804045 1.78063 2.53866 + vertex 0.802685 1.78391 2.53496 + endloop + endfacet + facet normal -0.903448 0.0862681 0.419929 + outer loop + vertex 0.803741 1.77557 2.53905 + vertex 0.804045 1.78063 2.53866 + vertex 0.802241 1.77884 2.53515 + endloop + endfacet + facet normal -0.931637 0.109215 0.346591 + outer loop + vertex 0.8 1.78886 2.525 + vertex 0.798988 1.78169 2.52454 + vertex 0.799974 1.78375 2.52654 + endloop + endfacet + facet normal -0.594962 0.234862 0.768674 + outer loop + vertex 0.8 1.78886 2.525 + vertex 0.799974 1.78375 2.52654 + vertex 0.80045 1.79 2.525 + endloop + endfacet + facet normal -0.860827 0.182633 0.474997 + outer loop + vertex 0.80045 1.79 2.525 + vertex 0.799974 1.78375 2.52654 + vertex 0.801126 1.78807 2.52697 + endloop + endfacet + facet normal -0.926065 0.216275 0.309238 + outer loop + vertex 0.799974 1.78375 2.52654 + vertex 0.801254 1.78309 2.53083 + vertex 0.801126 1.78807 2.52697 + endloop + endfacet + facet normal -0.96769 0.138633 0.210612 + outer loop + vertex 0.801126 1.78807 2.52697 + vertex 0.801254 1.78309 2.53083 + vertex 0.801934 1.78771 2.53092 + endloop + endfacet + facet normal -0.944169 0.1335 0.301201 + outer loop + vertex 0.801254 1.78309 2.53083 + vertex 0.802685 1.78391 2.53496 + vertex 0.801934 1.78771 2.53092 + endloop + endfacet + facet normal -0.966551 0.0709241 0.246473 + outer loop + vertex 0.801934 1.78771 2.53092 + vertex 0.802685 1.78391 2.53496 + vertex 0.803009 1.78882 2.53481 + endloop + endfacet + facet normal -0.921639 0.0718599 0.381338 + outer loop + vertex 0.802685 1.78391 2.53496 + vertex 0.804235 1.78574 2.53836 + vertex 0.803009 1.78882 2.53481 + endloop + endfacet + facet normal -0.919754 0.0573382 0.388283 + outer loop + vertex 0.804045 1.78063 2.53866 + vertex 0.804235 1.78574 2.53836 + vertex 0.802685 1.78391 2.53496 + endloop + endfacet + facet normal -0.792547 0.276436 0.543556 + outer loop + vertex 0.80045 1.79 2.525 + vertex 0.801126 1.78807 2.52697 + vertex 0.802194 1.795 2.525 + endloop + endfacet + facet normal -0.957198 0.205397 0.20392 + outer loop + vertex 0.802194 1.795 2.525 + vertex 0.801126 1.78807 2.52697 + vertex 0.801969 1.79205 2.52691 + endloop + endfacet + facet normal -0.955047 0.205075 0.214079 + outer loop + vertex 0.801126 1.78807 2.52697 + vertex 0.801934 1.78771 2.53092 + vertex 0.801969 1.79205 2.52691 + endloop + endfacet + facet normal -0.991585 0.0919392 0.0911356 + outer loop + vertex 0.801969 1.79205 2.52691 + vertex 0.801934 1.78771 2.53092 + vertex 0.802364 1.79241 2.53085 + endloop + endfacet + facet normal -0.966304 0.0917798 0.240486 + outer loop + vertex 0.801934 1.78771 2.53092 + vertex 0.803009 1.78882 2.53481 + vertex 0.802364 1.79241 2.53085 + endloop + endfacet + facet normal -0.977384 0.0509403 0.205244 + outer loop + vertex 0.802364 1.79241 2.53085 + vertex 0.803009 1.78882 2.53481 + vertex 0.803209 1.79367 2.53456 + endloop + endfacet + facet normal -0.929162 0.0572658 0.365209 + outer loop + vertex 0.803009 1.78882 2.53481 + vertex 0.804392 1.79074 2.53803 + vertex 0.803209 1.79367 2.53456 + endloop + endfacet + facet normal -0.928534 0.0531006 0.36743 + outer loop + vertex 0.804235 1.78574 2.53836 + vertex 0.804392 1.79074 2.53803 + vertex 0.803009 1.78882 2.53481 + endloop + endfacet + facet normal -0.478025 0.12178 -0.869863 + outer loop + vertex 0.805 1.795 2.52224 + vertex 0.802927 1.796 2.52352 + vertex 0.805 1.8 2.52294 + endloop + endfacet + facet normal -0.615909 -0.478129 -0.626137 + outer loop + vertex 0.802194 1.795 2.525 + vertex 0.802927 1.796 2.52352 + vertex 0.805 1.795 2.52224 + endloop + endfacet + facet normal 0.743835 0.322941 0.585165 + outer loop + vertex 0.802194 1.795 2.525 + vertex 0.801969 1.79205 2.52691 + vertex 0.802927 1.796 2.52352 + endloop + endfacet + facet normal -0.977702 0.0658806 -0.199397 + outer loop + vertex 0.802927 1.796 2.52352 + vertex 0.801969 1.79205 2.52691 + vertex 0.802341 1.79653 2.52657 + endloop + endfacet + facet normal -0.99179 0.0894482 0.091385 + outer loop + vertex 0.801969 1.79205 2.52691 + vertex 0.802364 1.79241 2.53085 + vertex 0.802341 1.79653 2.52657 + endloop + endfacet + facet normal -0.997799 0.0450174 0.0486793 + outer loop + vertex 0.802341 1.79653 2.52657 + vertex 0.802364 1.79241 2.53085 + vertex 0.80258 1.79742 2.53066 + endloop + endfacet + facet normal -0.977369 0.0501397 0.205513 + outer loop + vertex 0.802364 1.79241 2.53085 + vertex 0.803209 1.79367 2.53456 + vertex 0.80258 1.79742 2.53066 + endloop + endfacet + facet normal -0.977042 0.0514696 0.206736 + outer loop + vertex 0.80258 1.79742 2.53066 + vertex 0.803209 1.79367 2.53456 + vertex 0.803391 1.79822 2.53429 + endloop + endfacet + facet normal -0.928267 0.059243 0.367165 + outer loop + vertex 0.803209 1.79367 2.53456 + vertex 0.804496 1.79552 2.53752 + vertex 0.803391 1.79822 2.53429 + endloop + endfacet + facet normal -0.92833 0.0596485 0.36694 + outer loop + vertex 0.804392 1.79074 2.53803 + vertex 0.804496 1.79552 2.53752 + vertex 0.803209 1.79367 2.53456 + endloop + endfacet + facet normal 0.0545152 -0.163503 -0.985035 + outer loop + vertex 0.805 1.8 2.52294 + vertex 0.802972 1.80177 2.52253 + vertex 0.805 1.805 2.52211 + endloop + endfacet + facet normal 0.0502696 -0.168224 -0.984466 + outer loop + vertex 0.802927 1.796 2.52352 + vertex 0.802972 1.80177 2.52253 + vertex 0.805 1.8 2.52294 + endloop + endfacet + facet normal -0.982513 -0.0238102 -0.184666 + outer loop + vertex 0.802927 1.796 2.52352 + vertex 0.802341 1.79653 2.52657 + vertex 0.802972 1.80177 2.52253 + endloop + endfacet + facet normal -0.986236 -0.00833063 -0.165132 + outer loop + vertex 0.802972 1.80177 2.52253 + vertex 0.802341 1.79653 2.52657 + vertex 0.802347 1.80203 2.52625 + endloop + endfacet + facet normal -0.998334 0.0044285 0.0575265 + outer loop + vertex 0.802341 1.79653 2.52657 + vertex 0.80258 1.79742 2.53066 + vertex 0.802347 1.80203 2.52625 + endloop + endfacet + facet normal -0.992528 0.0541693 0.109334 + outer loop + vertex 0.802347 1.80203 2.52625 + vertex 0.80258 1.79742 2.53066 + vertex 0.802884 1.80278 2.53076 + endloop + endfacet + facet normal -0.922606 0.0902186 0.375044 + outer loop + vertex 0.803807 1.80153 2.53452 + vertex 0.803391 1.79822 2.53429 + vertex 0.804473 1.79922 2.53671 + endloop + endfacet + facet normal -0.957656 0.101969 0.269252 + outer loop + vertex 0.803807 1.80153 2.53452 + vertex 0.802884 1.80278 2.53076 + vertex 0.803391 1.79822 2.53429 + endloop + endfacet + facet normal -0.977042 0.0514382 0.206743 + outer loop + vertex 0.802884 1.80278 2.53076 + vertex 0.80258 1.79742 2.53066 + vertex 0.803391 1.79822 2.53429 + endloop + endfacet + facet normal -0.921757 0.0772184 0.380001 + outer loop + vertex 0.804473 1.79922 2.53671 + vertex 0.803391 1.79822 2.53429 + vertex 0.804496 1.79552 2.53752 + endloop + endfacet + facet normal -0.704769 -0.524703 -0.47748 + outer loop + vertex 0.805 1.805 2.52211 + vertex 0.802707 1.81 2.52 + vertex 0.805 1.80692 2.52 + endloop + endfacet + facet normal 0.24823 -0.277787 -0.928018 + outer loop + vertex 0.805 1.805 2.52211 + vertex 0.802972 1.80177 2.52253 + vertex 0.802707 1.81 2.52 + endloop + endfacet + facet normal -0.950386 -0.119166 -0.287344 + outer loop + vertex 0.802972 1.80177 2.52253 + vertex 0.802329 1.80781 2.52216 + vertex 0.802707 1.81 2.52 + endloop + endfacet + facet normal -0.980972 -0.114274 -0.156958 + outer loop + vertex 0.802972 1.80177 2.52253 + vertex 0.802347 1.80203 2.52625 + vertex 0.802329 1.80781 2.52216 + endloop + endfacet + facet normal -0.9999 0.00599104 0.0127844 + outer loop + vertex 0.802329 1.80781 2.52216 + vertex 0.802347 1.80203 2.52625 + vertex 0.802377 1.80762 2.52599 + endloop + endfacet + facet normal -0.99312 0.0108944 0.116595 + outer loop + vertex 0.802347 1.80203 2.52625 + vertex 0.802884 1.80278 2.53076 + vertex 0.802377 1.80762 2.52599 + endloop + endfacet + facet normal -0.979211 0.0807973 0.186057 + outer loop + vertex 0.802377 1.80762 2.52599 + vertex 0.802884 1.80278 2.53076 + vertex 0.803121 1.8081 2.5297 + endloop + endfacet + facet normal -0.943886 0.104677 0.313245 + outer loop + vertex 0.802884 1.80278 2.53076 + vertex 0.80404 1.80527 2.53341 + vertex 0.803121 1.8081 2.5297 + endloop + endfacet + facet normal -0.94929 0.142021 0.280497 + outer loop + vertex 0.803807 1.80153 2.53452 + vertex 0.80404 1.80527 2.53341 + vertex 0.802884 1.80278 2.53076 + endloop + endfacet + facet normal -0.990715 0.0443819 -0.128509 + outer loop + vertex 0.802707 1.81 2.52 + vertex 0.802329 1.80781 2.52216 + vertex 0.802931 1.815 2.52 + endloop + endfacet + facet normal -0.957472 -0.0063785 -0.288456 + outer loop + vertex 0.802931 1.815 2.52 + vertex 0.802329 1.80781 2.52216 + vertex 0.802343 1.81311 2.52199 + endloop + endfacet + facet normal -0.999916 0.00293866 0.0126323 + outer loop + vertex 0.802329 1.80781 2.52216 + vertex 0.802377 1.80762 2.52599 + vertex 0.802343 1.81311 2.52199 + endloop + endfacet + facet normal -0.987853 0.0873269 0.128533 + outer loop + vertex 0.802343 1.81311 2.52199 + vertex 0.802377 1.80762 2.52599 + vertex 0.802831 1.81292 2.52587 + endloop + endfacet + facet normal -0.925886 0.147361 0.347878 + outer loop + vertex 0.803647 1.81142 2.52969 + vertex 0.803121 1.8081 2.5297 + vertex 0.804213 1.80897 2.53223 + endloop + endfacet + facet normal -0.952724 0.151422 0.263418 + outer loop + vertex 0.803647 1.81142 2.52969 + vertex 0.802831 1.81292 2.52587 + vertex 0.803121 1.8081 2.5297 + endloop + endfacet + facet normal -0.978796 0.0877705 0.185079 + outer loop + vertex 0.802831 1.81292 2.52587 + vertex 0.802377 1.80762 2.52599 + vertex 0.803121 1.8081 2.5297 + endloop + endfacet + facet normal -0.925715 0.153295 0.345765 + outer loop + vertex 0.804213 1.80897 2.53223 + vertex 0.803121 1.8081 2.5297 + vertex 0.80404 1.80527 2.53341 + endloop + endfacet + facet normal -0.962129 0.0121232 -0.272325 + outer loop + vertex 0.802931 1.815 2.52 + vertex 0.802343 1.81311 2.52199 + vertex 0.802994 1.82 2.52 + endloop + endfacet + facet normal -0.993368 0.0668314 -0.0935639 + outer loop + vertex 0.802994 1.82 2.52 + vertex 0.802343 1.81311 2.52199 + vertex 0.802717 1.81818 2.52164 + endloop + endfacet + facet normal -0.988338 0.0819757 0.128327 + outer loop + vertex 0.802343 1.81311 2.52199 + vertex 0.802831 1.81292 2.52587 + vertex 0.802717 1.81818 2.52164 + endloop + endfacet + facet normal -0.968335 0.143523 0.204278 + outer loop + vertex 0.802717 1.81818 2.52164 + vertex 0.802831 1.81292 2.52587 + vertex 0.803341 1.81822 2.52457 + endloop + endfacet + facet normal -0.944428 0.161449 0.286338 + outer loop + vertex 0.802831 1.81292 2.52587 + vertex 0.803953 1.81514 2.52833 + vertex 0.803341 1.81822 2.52457 + endloop + endfacet + facet normal -0.945682 0.177673 0.272246 + outer loop + vertex 0.803647 1.81142 2.52969 + vertex 0.803953 1.81514 2.52833 + vertex 0.802831 1.81292 2.52587 + endloop + endfacet + facet normal -0.991568 0.0396575 -0.123367 + outer loop + vertex 0.802994 1.82 2.52 + vertex 0.802717 1.81818 2.52164 + vertex 0.803194 1.825 2.52 + endloop + endfacet + facet normal -0.93672 0.142398 0.319809 + outer loop + vertex 0.803194 1.825 2.52 + vertex 0.802717 1.81818 2.52164 + vertex 0.803549 1.82369 2.52162 + endloop + endfacet + facet normal -0.937612 0.16238 0.307436 + outer loop + vertex 0.803996 1.8223 2.52441 + vertex 0.803341 1.81822 2.52457 + vertex 0.804229 1.81909 2.52682 + endloop + endfacet + facet normal -0.958234 0.162966 0.23501 + outer loop + vertex 0.803996 1.8223 2.52441 + vertex 0.803549 1.82369 2.52162 + vertex 0.803341 1.81822 2.52457 + endloop + endfacet + facet normal -0.967888 0.146699 0.20414 + outer loop + vertex 0.803549 1.82369 2.52162 + vertex 0.802717 1.81818 2.52164 + vertex 0.803341 1.81822 2.52457 + endloop + endfacet + facet normal -0.936724 0.179948 0.300277 + outer loop + vertex 0.804229 1.81909 2.52682 + vertex 0.803341 1.81822 2.52457 + vertex 0.803953 1.81514 2.52833 + endloop + endfacet + facet normal -0.626992 -0.454688 -0.632566 + outer loop + vertex 0.805 1.825 2.51771 + vertex 0.804108 1.83 2.515 + vertex 0.805 1.82877 2.515 + endloop + endfacet + facet normal -0.70906 -0.429567 -0.559201 + outer loop + vertex 0.805 1.825 2.51771 + vertex 0.803194 1.825 2.52 + vertex 0.804108 1.83 2.515 + endloop + endfacet + facet normal -0.974222 0.221396 0.0433017 + outer loop + vertex 0.803194 1.825 2.52 + vertex 0.803762 1.82799 2.51748 + vertex 0.804108 1.83 2.515 + endloop + endfacet + facet normal -0.974797 0.150879 0.164335 + outer loop + vertex 0.805 1.83 2.52444 + vertex 0.803549 1.82369 2.52162 + vertex 0.805 1.82939 2.525 + endloop + endfacet + facet normal -0.977631 0.169068 0.125117 + outer loop + vertex 0.805 1.83 2.52444 + vertex 0.803762 1.82799 2.51748 + vertex 0.803549 1.82369 2.52162 + endloop + endfacet + facet normal -0.520221 0.605612 0.602166 + outer loop + vertex 0.803762 1.82799 2.51748 + vertex 0.803194 1.825 2.52 + vertex 0.803549 1.82369 2.52162 + endloop + endfacet + facet normal -0.969289 0.119421 0.214984 + outer loop + vertex 0.805 1.82939 2.525 + vertex 0.803549 1.82369 2.52162 + vertex 0.803996 1.8223 2.52441 + endloop + endfacet + facet normal -0.00071219 -0.0579337 -0.99832 + outer loop + vertex 0.805 1.83 2.51411 + vertex 0.804119 1.83114 2.51404 + vertex 0.805 1.835 2.51382 + endloop + endfacet + facet normal -0.609838 -0.504529 -0.611186 + outer loop + vertex 0.804108 1.83 2.515 + vertex 0.804119 1.83114 2.51404 + vertex 0.805 1.83 2.51411 + endloop + endfacet + facet normal -0.886217 -0.29194 -0.359708 + outer loop + vertex 0.804108 1.83 2.515 + vertex 0.803762 1.82799 2.51748 + vertex 0.804119 1.83114 2.51404 + endloop + endfacet + facet normal -0.994516 0.104317 -0.00753522 + outer loop + vertex 0.804119 1.83114 2.51404 + vertex 0.803762 1.82799 2.51748 + vertex 0.804166 1.83174 2.51605 + endloop + endfacet + facet normal -0.976924 0.1595 0.142052 + outer loop + vertex 0.803762 1.82799 2.51748 + vertex 0.804489 1.83055 2.51961 + vertex 0.804166 1.83174 2.51605 + endloop + endfacet + facet normal -0.976801 0.175152 0.123216 + outer loop + vertex 0.805 1.83 2.52444 + vertex 0.804489 1.83055 2.51961 + vertex 0.803762 1.82799 2.51748 + endloop + endfacet + facet normal -0.873546 0.173182 -0.454891 + outer loop + vertex 0.805 1.835 2.51382 + vertex 0.804119 1.83114 2.51404 + vertex 0.805 1.8381 2.515 + endloop + endfacet + facet normal -0.985795 0.143635 0.0870431 + outer loop + vertex 0.805 1.8381 2.515 + vertex 0.804166 1.83174 2.51605 + vertex 0.805 1.83507 2.52 + endloop + endfacet + facet normal -0.991714 0.127636 -0.0145379 + outer loop + vertex 0.804119 1.83114 2.51404 + vertex 0.804166 1.83174 2.51605 + vertex 0.805 1.8381 2.515 + endloop + endfacet + facet normal -0.98722 0.100911 0.123347 + outer loop + vertex 0.805 1.83507 2.52 + vertex 0.804166 1.83174 2.51605 + vertex 0.804489 1.83055 2.51961 + endloop + endfacet + facet normal -0.342305 -0.134495 -0.929913 + outer loop + vertex 0.81 1.17334 2.515 + vertex 0.809436 1.17599 2.51482 + vertex 0.81 1.175 2.51476 + endloop + endfacet + facet normal -0.937306 -0.179825 0.29853 + outer loop + vertex 0.81 1.17334 2.515 + vertex 0.81 1.175 2.516 + vertex 0.809436 1.17599 2.51482 + endloop + endfacet + facet normal 0.561109 0.0363954 -0.826941 + outer loop + vertex 0.81 1.175 2.51476 + vertex 0.809215 1.17821 2.51437 + vertex 0.81 1.18 2.51498 + endloop + endfacet + facet normal -0.485467 -0.221657 -0.845689 + outer loop + vertex 0.809436 1.17599 2.51482 + vertex 0.809215 1.17821 2.51437 + vertex 0.81 1.175 2.51476 + endloop + endfacet + facet normal -0.938647 -0.23055 0.256495 + outer loop + vertex 0.81 1.17945 2.52 + vertex 0.809436 1.17599 2.51482 + vertex 0.81 1.175 2.516 + endloop + endfacet + facet normal -0.92432 -0.26293 0.276588 + outer loop + vertex 0.81 1.17945 2.52 + vertex 0.809131 1.17878 2.51646 + vertex 0.809436 1.17599 2.51482 + endloop + endfacet + facet normal -0.994772 -0.101364 -0.0123736 + outer loop + vertex 0.809131 1.17878 2.51646 + vertex 0.809215 1.17821 2.51437 + vertex 0.809436 1.17599 2.51482 + endloop + endfacet + facet normal 0.954493 0.143392 -0.261499 + outer loop + vertex 0.81 1.17945 2.52 + vertex 0.809831 1.17799 2.51858 + vertex 0.809131 1.17878 2.51646 + endloop + endfacet + facet normal 0.337275 0.16858 -0.926189 + outer loop + vertex 0.81 1.18 2.51498 + vertex 0.809215 1.17821 2.51437 + vertex 0.81 1.18011 2.515 + endloop + endfacet + facet normal -0.49989 0.294746 -0.814392 + outer loop + vertex 0.81 1.18011 2.515 + vertex 0.808704 1.18294 2.51682 + vertex 0.81 1.185 2.51677 + endloop + endfacet + facet normal -0.305628 0.411903 -0.858445 + outer loop + vertex 0.81 1.18011 2.515 + vertex 0.809215 1.17821 2.51437 + vertex 0.808704 1.18294 2.51682 + endloop + endfacet + facet normal -0.994814 -0.100941 -0.0124909 + outer loop + vertex 0.809215 1.17821 2.51437 + vertex 0.809131 1.17878 2.51646 + vertex 0.808704 1.18294 2.51682 + endloop + endfacet + facet normal -0.991341 -0.108099 0.0745518 + outer loop + vertex 0.809131 1.17878 2.51646 + vertex 0.809134 1.18078 2.5194 + vertex 0.808704 1.18294 2.51682 + endloop + endfacet + facet normal -0.935421 -0.291906 0.199447 + outer loop + vertex 0.809831 1.17799 2.51858 + vertex 0.809134 1.18078 2.5194 + vertex 0.809131 1.17878 2.51646 + endloop + endfacet + facet normal 0.112653 0.211646 -0.970832 + outer loop + vertex 0.81 1.185 2.51677 + vertex 0.808465 1.18819 2.51729 + vertex 0.81 1.19 2.51786 + endloop + endfacet + facet normal -0.165347 0.079789 -0.983003 + outer loop + vertex 0.808704 1.18294 2.51682 + vertex 0.808465 1.18819 2.51729 + vertex 0.81 1.185 2.51677 + endloop + endfacet + facet normal -0.988001 -0.149293 0.0395796 + outer loop + vertex 0.808592 1.18469 2.52062 + vertex 0.808704 1.18294 2.51682 + vertex 0.809134 1.18078 2.5194 + endloop + endfacet + facet normal -0.991746 -0.125049 0.0283232 + outer loop + vertex 0.808592 1.18469 2.52062 + vertex 0.807961 1.18966 2.52043 + vertex 0.808704 1.18294 2.51682 + endloop + endfacet + facet normal -0.989101 -0.0324045 -0.143625 + outer loop + vertex 0.807961 1.18966 2.52043 + vertex 0.808465 1.18819 2.51729 + vertex 0.808704 1.18294 2.51682 + endloop + endfacet + facet normal -0.975155 -0.11667 0.188311 + outer loop + vertex 0.808592 1.18469 2.52062 + vertex 0.808838 1.18701 2.52333 + vertex 0.807961 1.18966 2.52043 + endloop + endfacet + facet normal -0.697814 -0.0328906 -0.715523 + outer loop + vertex 0.81 1.19 2.51786 + vertex 0.80757 1.195 2.52 + vertex 0.81 1.195 2.51763 + endloop + endfacet + facet normal -0.0777919 0.360098 -0.929665 + outer loop + vertex 0.808465 1.18819 2.51729 + vertex 0.80757 1.195 2.52 + vertex 0.81 1.19 2.51786 + endloop + endfacet + facet normal -0.989323 -0.0819546 -0.12051 + outer loop + vertex 0.808465 1.18819 2.51729 + vertex 0.807961 1.18966 2.52043 + vertex 0.80757 1.195 2.52 + endloop + endfacet + facet normal -0.915027 -0.0981209 -0.391276 + outer loop + vertex 0.80757 1.195 2.52 + vertex 0.807961 1.18966 2.52043 + vertex 0.807323 1.19551 2.52045 + endloop + endfacet + facet normal -0.975623 -0.127302 0.178758 + outer loop + vertex 0.808652 1.19014 2.52455 + vertex 0.807961 1.18966 2.52043 + vertex 0.808838 1.18701 2.52333 + endloop + endfacet + facet normal -0.972411 -0.147618 0.180627 + outer loop + vertex 0.808652 1.19014 2.52455 + vertex 0.807901 1.19458 2.52413 + vertex 0.807961 1.18966 2.52043 + endloop + endfacet + facet normal -0.985895 -0.108049 0.127818 + outer loop + vertex 0.807901 1.19458 2.52413 + vertex 0.807323 1.19551 2.52045 + vertex 0.807961 1.18966 2.52043 + endloop + endfacet + facet normal -0.94318 -0.131033 0.305356 + outer loop + vertex 0.808652 1.19014 2.52455 + vertex 0.809277 1.19232 2.52741 + vertex 0.807901 1.19458 2.52413 + endloop + endfacet + facet normal -0.898295 -0.0495804 -0.436587 + outer loop + vertex 0.80757 1.195 2.52 + vertex 0.807323 1.19551 2.52045 + vertex 0.807294 1.2 2.52 + endloop + endfacet + facet normal -0.98376 -0.024156 -0.177856 + outer loop + vertex 0.807294 1.2 2.52 + vertex 0.807323 1.19551 2.52045 + vertex 0.807002 1.19943 2.52169 + endloop + endfacet + facet normal -0.984929 -0.119848 0.124702 + outer loop + vertex 0.807323 1.19551 2.52045 + vertex 0.807901 1.19458 2.52413 + vertex 0.807002 1.19943 2.52169 + endloop + endfacet + facet normal -0.98371 -0.111365 0.141109 + outer loop + vertex 0.807002 1.19943 2.52169 + vertex 0.807901 1.19458 2.52413 + vertex 0.807555 1.20031 2.52624 + endloop + endfacet + facet normal -0.946552 -0.160266 0.279917 + outer loop + vertex 0.807901 1.19458 2.52413 + vertex 0.808994 1.19645 2.52889 + vertex 0.807555 1.20031 2.52624 + endloop + endfacet + facet normal -0.94496 -0.166153 0.281858 + outer loop + vertex 0.809277 1.19232 2.52741 + vertex 0.808994 1.19645 2.52889 + vertex 0.807901 1.19458 2.52413 + endloop + endfacet + facet normal -0.939783 -0.240396 -0.242937 + outer loop + vertex 0.807294 1.2 2.52 + vertex 0.807002 1.19943 2.52169 + vertex 0.806015 1.205 2.52 + endloop + endfacet + facet normal -0.982479 -0.135218 0.128259 + outer loop + vertex 0.806015 1.205 2.52 + vertex 0.807002 1.19943 2.52169 + vertex 0.806606 1.20362 2.52307 + endloop + endfacet + facet normal -0.979168 -0.140847 0.14626 + outer loop + vertex 0.807002 1.19943 2.52169 + vertex 0.807555 1.20031 2.52624 + vertex 0.806606 1.20362 2.52307 + endloop + endfacet + facet normal -0.979185 -0.142509 0.144529 + outer loop + vertex 0.806606 1.20362 2.52307 + vertex 0.807555 1.20031 2.52624 + vertex 0.806796 1.20519 2.52591 + endloop + endfacet + facet normal -0.950154 -0.178055 0.255937 + outer loop + vertex 0.80865 1.20032 2.53031 + vertex 0.807555 1.20031 2.52624 + vertex 0.808994 1.19645 2.52889 + endloop + endfacet + facet normal -0.954141 -0.153587 0.256954 + outer loop + vertex 0.80865 1.20032 2.53031 + vertex 0.807835 1.20453 2.5298 + vertex 0.807555 1.20031 2.52624 + endloop + endfacet + facet normal -0.962921 -0.133849 0.23424 + outer loop + vertex 0.807835 1.20453 2.5298 + vertex 0.806796 1.20519 2.52591 + vertex 0.807555 1.20031 2.52624 + endloop + endfacet + facet normal -0.919578 -0.133225 0.369631 + outer loop + vertex 0.80865 1.20032 2.53031 + vertex 0.809287 1.20242 2.53265 + vertex 0.807835 1.20453 2.5298 + endloop + endfacet + facet normal 0.826993 -0.367353 0.425599 + outer loop + vertex 0.805 1.20715 2.52 + vertex 0.806266 1.21 2.52 + vertex 0.805 1.21 2.52246 + endloop + endfacet + facet normal -0.339657 0.541425 -0.769085 + outer loop + vertex 0.81 1.2075 2.52 + vertex 0.806015 1.205 2.52 + vertex 0.81 1.21 2.52176 + endloop + endfacet + facet normal -0.485199 0.607932 -0.628491 + outer loop + vertex 0.806015 1.205 2.52 + vertex 0.805803 1.21 2.525 + vertex 0.81 1.21 2.52176 + endloop + endfacet + facet normal -0.980317 -0.158834 0.117263 + outer loop + vertex 0.806015 1.205 2.52 + vertex 0.806606 1.20362 2.52307 + vertex 0.805803 1.21 2.525 + endloop + endfacet + facet normal -0.972324 -0.170614 0.159616 + outer loop + vertex 0.806606 1.20362 2.52307 + vertex 0.806796 1.20519 2.52591 + vertex 0.805803 1.21 2.525 + endloop + endfacet + facet normal -0.964638 -0.159523 0.209822 + outer loop + vertex 0.805803 1.21 2.525 + vertex 0.806796 1.20519 2.52591 + vertex 0.806585 1.20848 2.52744 + endloop + endfacet + facet normal -0.959261 -0.16742 0.227571 + outer loop + vertex 0.806796 1.20519 2.52591 + vertex 0.807835 1.20453 2.5298 + vertex 0.806585 1.20848 2.52744 + endloop + endfacet + facet normal -0.95207 -0.137887 0.273039 + outer loop + vertex 0.806585 1.20848 2.52744 + vertex 0.807835 1.20453 2.5298 + vertex 0.807468 1.21001 2.53129 + endloop + endfacet + facet normal -0.911934 -0.163296 0.376444 + outer loop + vertex 0.807835 1.20453 2.5298 + vertex 0.809207 1.20589 2.53372 + vertex 0.807468 1.21001 2.53129 + endloop + endfacet + facet normal -0.919692 -0.134124 0.369023 + outer loop + vertex 0.809287 1.20242 2.53265 + vertex 0.809207 1.20589 2.53372 + vertex 0.807835 1.20453 2.5298 + endloop + endfacet + facet normal 0.939671 0.232169 -0.251228 + outer loop + vertex 0.804664 1.21307 2.52358 + vertex 0.805 1.21325 2.525 + vertex 0.805803 1.21 2.525 + endloop + endfacet + facet normal -0.943084 -0.246262 0.223489 + outer loop + vertex 0.804664 1.21307 2.52358 + vertex 0.805803 1.21 2.525 + vertex 0.805474 1.21297 2.52688 + endloop + endfacet + facet normal -0.960855 -0.2163 0.173122 + outer loop + vertex 0.805474 1.21297 2.52688 + vertex 0.805803 1.21 2.525 + vertex 0.806585 1.20848 2.52744 + endloop + endfacet + facet normal -0.936123 -0.195485 0.292335 + outer loop + vertex 0.806585 1.20848 2.52744 + vertex 0.807468 1.21001 2.53129 + vertex 0.805474 1.21297 2.52688 + endloop + endfacet + facet normal -0.935949 -0.2118 0.281317 + outer loop + vertex 0.805474 1.21297 2.52688 + vertex 0.807468 1.21001 2.53129 + vertex 0.80621 1.2147 2.53063 + endloop + endfacet + facet normal -0.892166 -0.120229 0.435413 + outer loop + vertex 0.809647 1.20935 2.53558 + vertex 0.807468 1.21001 2.53129 + vertex 0.809207 1.20589 2.53372 + endloop + endfacet + facet normal -0.886452 -0.190874 0.421627 + outer loop + vertex 0.809647 1.20935 2.53558 + vertex 0.808077 1.21437 2.53454 + vertex 0.807468 1.21001 2.53129 + endloop + endfacet + facet normal -0.893231 -0.182056 0.411089 + outer loop + vertex 0.808077 1.21437 2.53454 + vertex 0.80621 1.2147 2.53063 + vertex 0.807468 1.21001 2.53129 + endloop + endfacet + facet normal -0.842238 -0.157741 0.515513 + outer loop + vertex 0.809647 1.20935 2.53558 + vertex 0.810686 1.21234 2.53819 + vertex 0.808077 1.21437 2.53454 + endloop + endfacet + facet normal -0.939705 -0.25994 0.222231 + outer loop + vertex 0.803974 1.21624 2.52436 + vertex 0.804664 1.21307 2.52358 + vertex 0.805474 1.21297 2.52688 + endloop + endfacet + facet normal -0.937337 -0.225183 0.265879 + outer loop + vertex 0.804661 1.21813 2.52839 + vertex 0.803974 1.21624 2.52436 + vertex 0.805474 1.21297 2.52688 + endloop + endfacet + facet normal -0.929267 -0.230547 0.288636 + outer loop + vertex 0.805474 1.21297 2.52688 + vertex 0.80621 1.2147 2.53063 + vertex 0.804661 1.21813 2.52839 + endloop + endfacet + facet normal -0.918038 -0.184769 0.350808 + outer loop + vertex 0.804661 1.21813 2.52839 + vertex 0.80621 1.2147 2.53063 + vertex 0.806143 1.21786 2.53213 + endloop + endfacet + facet normal -0.888982 -0.210514 0.406688 + outer loop + vertex 0.80621 1.2147 2.53063 + vertex 0.808077 1.21437 2.53454 + vertex 0.806143 1.21786 2.53213 + endloop + endfacet + facet normal -0.878557 -0.180009 0.442419 + outer loop + vertex 0.806143 1.21786 2.53213 + vertex 0.808077 1.21437 2.53454 + vertex 0.807403 1.21962 2.53534 + endloop + endfacet + facet normal -0.84953 -0.184164 0.49435 + outer loop + vertex 0.808077 1.21437 2.53454 + vertex 0.809659 1.21691 2.53821 + vertex 0.807403 1.21962 2.53534 + endloop + endfacet + facet normal -0.845314 -0.192573 0.498357 + outer loop + vertex 0.810686 1.21234 2.53819 + vertex 0.809659 1.21691 2.53821 + vertex 0.808077 1.21437 2.53454 + endloop + endfacet + facet normal -0.943712 -0.206651 0.258271 + outer loop + vertex 0.803974 1.21624 2.52436 + vertex 0.804661 1.21813 2.52839 + vertex 0.803465 1.21992 2.52545 + endloop + endfacet + facet normal -0.944513 -0.17603 0.277325 + outer loop + vertex 0.803758 1.2221 2.52783 + vertex 0.803465 1.21992 2.52545 + vertex 0.804661 1.21813 2.52839 + endloop + endfacet + facet normal -0.925125 -0.162478 0.34314 + outer loop + vertex 0.803758 1.2221 2.52783 + vertex 0.804661 1.21813 2.52839 + vertex 0.805164 1.2224 2.53176 + endloop + endfacet + facet normal -0.920091 -0.170563 0.352619 + outer loop + vertex 0.805164 1.2224 2.53176 + vertex 0.804661 1.21813 2.52839 + vertex 0.806143 1.21786 2.53213 + endloop + endfacet + facet normal -0.887417 -0.157084 0.433377 + outer loop + vertex 0.806143 1.21786 2.53213 + vertex 0.807403 1.21962 2.53534 + vertex 0.805164 1.2224 2.53176 + endloop + endfacet + facet normal -0.888536 -0.164515 0.428297 + outer loop + vertex 0.805164 1.2224 2.53176 + vertex 0.807403 1.21962 2.53534 + vertex 0.806986 1.22486 2.53649 + endloop + endfacet + facet normal -0.853437 -0.175412 0.490791 + outer loop + vertex 0.807403 1.21962 2.53534 + vertex 0.809097 1.2212 2.53885 + vertex 0.806986 1.22486 2.53649 + endloop + endfacet + facet normal -0.849786 -0.185288 0.49349 + outer loop + vertex 0.809659 1.21691 2.53821 + vertex 0.809097 1.2212 2.53885 + vertex 0.807403 1.21962 2.53534 + endloop + endfacet + facet normal -0.930614 -0.128856 0.34257 + outer loop + vertex 0.80366 1.22595 2.52901 + vertex 0.803758 1.2221 2.52783 + vertex 0.805164 1.2224 2.53176 + endloop + endfacet + facet normal -0.936094 -0.150142 0.318096 + outer loop + vertex 0.804791 1.22799 2.53331 + vertex 0.80366 1.22595 2.52901 + vertex 0.805164 1.2224 2.53176 + endloop + endfacet + facet normal -0.883284 -0.178467 0.433542 + outer loop + vertex 0.805164 1.2224 2.53176 + vertex 0.806986 1.22486 2.53649 + vertex 0.804791 1.22799 2.53331 + endloop + endfacet + facet normal -0.885591 -0.18993 0.423857 + outer loop + vertex 0.804791 1.22799 2.53331 + vertex 0.806986 1.22486 2.53649 + vertex 0.806112 1.22863 2.53635 + endloop + endfacet + facet normal -0.843328 -0.154017 0.514856 + outer loop + vertex 0.809476 1.22453 2.54047 + vertex 0.806986 1.22486 2.53649 + vertex 0.809097 1.2212 2.53885 + endloop + endfacet + facet normal -0.840658 -0.179199 0.511059 + outer loop + vertex 0.809476 1.22453 2.54047 + vertex 0.807806 1.22922 2.53937 + vertex 0.806986 1.22486 2.53649 + endloop + endfacet + facet normal -0.842792 -0.176981 0.50831 + outer loop + vertex 0.807806 1.22922 2.53937 + vertex 0.806112 1.22863 2.53635 + vertex 0.806986 1.22486 2.53649 + endloop + endfacet + facet normal -0.807609 -0.153765 0.569319 + outer loop + vertex 0.809476 1.22453 2.54047 + vertex 0.810782 1.22723 2.54305 + vertex 0.807806 1.22922 2.53937 + endloop + endfacet + facet normal -0.933006 -0.160373 0.322148 + outer loop + vertex 0.80366 1.22595 2.52901 + vertex 0.804791 1.22799 2.53331 + vertex 0.803417 1.22987 2.53026 + endloop + endfacet + facet normal -0.933391 -0.175556 0.312988 + outer loop + vertex 0.803875 1.23195 2.5328 + vertex 0.803417 1.22987 2.53026 + vertex 0.804791 1.22799 2.53331 + endloop + endfacet + facet normal -0.899288 -0.155283 0.408862 + outer loop + vertex 0.803875 1.23195 2.5328 + vertex 0.804791 1.22799 2.53331 + vertex 0.805413 1.23229 2.53631 + endloop + endfacet + facet normal -0.891767 -0.165061 0.421316 + outer loop + vertex 0.805413 1.23229 2.53631 + vertex 0.804791 1.22799 2.53331 + vertex 0.806112 1.22863 2.53635 + endloop + endfacet + facet normal -0.847814 -0.155546 0.506968 + outer loop + vertex 0.806112 1.22863 2.53635 + vertex 0.807806 1.22922 2.53937 + vertex 0.805413 1.23229 2.53631 + endloop + endfacet + facet normal -0.851129 -0.16755 0.497501 + outer loop + vertex 0.805413 1.23229 2.53631 + vertex 0.807806 1.22922 2.53937 + vertex 0.807219 1.23449 2.54014 + endloop + endfacet + facet normal -0.812404 -0.171966 0.55716 + outer loop + vertex 0.807806 1.22922 2.53937 + vertex 0.809614 1.23199 2.54286 + vertex 0.807219 1.23449 2.54014 + endloop + endfacet + facet normal -0.810084 -0.176103 0.559241 + outer loop + vertex 0.810782 1.22723 2.54305 + vertex 0.809614 1.23199 2.54286 + vertex 0.807806 1.22922 2.53937 + endloop + endfacet + facet normal -0.897861 -0.163016 0.408987 + outer loop + vertex 0.803711 1.23583 2.53398 + vertex 0.803875 1.23195 2.5328 + vertex 0.805413 1.23229 2.53631 + endloop + endfacet + facet normal -0.89368 -0.15243 0.422019 + outer loop + vertex 0.805224 1.23798 2.53796 + vertex 0.803711 1.23583 2.53398 + vertex 0.805413 1.23229 2.53631 + endloop + endfacet + facet normal -0.848611 -0.173528 0.499747 + outer loop + vertex 0.805413 1.23229 2.53631 + vertex 0.807219 1.23449 2.54014 + vertex 0.805224 1.23798 2.53796 + endloop + endfacet + facet normal -0.840403 -0.156976 0.51873 + outer loop + vertex 0.805224 1.23798 2.53796 + vertex 0.807219 1.23449 2.54014 + vertex 0.807105 1.23868 2.54122 + endloop + endfacet + facet normal -0.80805 -0.167976 0.564658 + outer loop + vertex 0.807219 1.23449 2.54014 + vertex 0.808989 1.23664 2.54331 + vertex 0.807105 1.23868 2.54122 + endloop + endfacet + facet normal -0.810176 -0.163617 0.562889 + outer loop + vertex 0.809614 1.23199 2.54286 + vertex 0.808989 1.23664 2.54331 + vertex 0.807219 1.23449 2.54014 + endloop + endfacet + facet normal -0.882456 -0.182018 0.433753 + outer loop + vertex 0.803711 1.23583 2.53398 + vertex 0.805224 1.23798 2.53796 + vertex 0.803496 1.23972 2.53518 + endloop + endfacet + facet normal -0.881165 -0.167115 0.442291 + outer loop + vertex 0.804216 1.24209 2.53751 + vertex 0.803496 1.23972 2.53518 + vertex 0.805224 1.23798 2.53796 + endloop + endfacet + facet normal -0.845528 -0.150641 0.512241 + outer loop + vertex 0.804216 1.24209 2.53751 + vertex 0.805224 1.23798 2.53796 + vertex 0.806109 1.24302 2.54091 + endloop + endfacet + facet normal -0.840826 -0.155174 0.518588 + outer loop + vertex 0.806109 1.24302 2.54091 + vertex 0.805224 1.23798 2.53796 + vertex 0.807105 1.23868 2.54122 + endloop + endfacet + facet normal -0.807856 -0.143773 0.571575 + outer loop + vertex 0.807105 1.23868 2.54122 + vertex 0.808558 1.24127 2.54393 + vertex 0.806109 1.24302 2.54091 + endloop + endfacet + facet normal -0.803074 -0.151406 0.576324 + outer loop + vertex 0.808989 1.23664 2.54331 + vertex 0.808558 1.24127 2.54393 + vertex 0.807105 1.23868 2.54122 + endloop + endfacet + facet normal -0.847867 -0.1414 0.511007 + outer loop + vertex 0.804084 1.24632 2.53846 + vertex 0.804216 1.24209 2.53751 + vertex 0.806109 1.24302 2.54091 + endloop + endfacet + facet normal -0.84801 -0.141734 0.510676 + outer loop + vertex 0.806002 1.24907 2.54241 + vertex 0.804084 1.24632 2.53846 + vertex 0.806109 1.24302 2.54091 + endloop + endfacet + facet normal -0.806155 -0.155905 0.570796 + outer loop + vertex 0.806109 1.24302 2.54091 + vertex 0.808139 1.24607 2.54461 + vertex 0.806002 1.24907 2.54241 + endloop + endfacet + facet normal -0.808894 -0.15098 0.568239 + outer loop + vertex 0.808558 1.24127 2.54393 + vertex 0.808139 1.24607 2.54461 + vertex 0.806109 1.24302 2.54091 + endloop + endfacet + facet normal -0.846476 -0.145098 0.512274 + outer loop + vertex 0.803748 1.2513 2.53932 + vertex 0.804084 1.24632 2.53846 + vertex 0.806002 1.24907 2.54241 + endloop + endfacet + facet normal -0.847507 -0.150762 0.508922 + outer loop + vertex 0.805141 1.25402 2.54244 + vertex 0.803748 1.2513 2.53932 + vertex 0.806002 1.24907 2.54241 + endloop + endfacet + facet normal -0.806797 -0.157315 0.569501 + outer loop + vertex 0.807979 1.24994 2.54545 + vertex 0.806002 1.24907 2.54241 + vertex 0.808139 1.24607 2.54461 + endloop + endfacet + facet normal -0.807787 -0.153664 0.569094 + outer loop + vertex 0.807979 1.24994 2.54545 + vertex 0.807172 1.2533 2.54521 + vertex 0.806002 1.24907 2.54241 + endloop + endfacet + facet normal -0.815526 -0.145578 0.560111 + outer loop + vertex 0.807172 1.2533 2.54521 + vertex 0.805141 1.25402 2.54244 + vertex 0.806002 1.24907 2.54241 + endloop + endfacet + facet normal -0.785563 -0.146038 0.601301 + outer loop + vertex 0.807979 1.24994 2.54545 + vertex 0.808959 1.25241 2.54733 + vertex 0.807172 1.2533 2.54521 + endloop + endfacet + facet normal -0.850506 -0.145294 0.5055 + outer loop + vertex 0.803748 1.2513 2.53932 + vertex 0.805141 1.25402 2.54244 + vertex 0.803474 1.25524 2.53999 + endloop + endfacet + facet normal -0.849529 -0.134852 0.510016 + outer loop + vertex 0.80432 1.25756 2.54201 + vertex 0.803474 1.25524 2.53999 + vertex 0.805141 1.25402 2.54244 + endloop + endfacet + facet normal -0.826364 -0.124659 0.549165 + outer loop + vertex 0.80432 1.25756 2.54201 + vertex 0.805141 1.25402 2.54244 + vertex 0.806317 1.25825 2.54517 + endloop + endfacet + facet normal -0.81548 -0.136298 0.562508 + outer loop + vertex 0.806317 1.25825 2.54517 + vertex 0.805141 1.25402 2.54244 + vertex 0.807172 1.2533 2.54521 + endloop + endfacet + facet normal -0.790918 -0.131772 0.597565 + outer loop + vertex 0.807172 1.2533 2.54521 + vertex 0.808826 1.25634 2.54807 + vertex 0.806317 1.25825 2.54517 + endloop + endfacet + facet normal -0.785075 -0.140331 0.603295 + outer loop + vertex 0.808959 1.25241 2.54733 + vertex 0.808826 1.25634 2.54807 + vertex 0.807172 1.2533 2.54521 + endloop + endfacet + facet normal -0.827019 -0.121496 0.548888 + outer loop + vertex 0.804244 1.26155 2.54278 + vertex 0.80432 1.25756 2.54201 + vertex 0.806317 1.25825 2.54517 + endloop + endfacet + facet normal -0.830063 -0.127808 0.542826 + outer loop + vertex 0.80618 1.26386 2.54628 + vertex 0.804244 1.26155 2.54278 + vertex 0.806317 1.25825 2.54517 + endloop + endfacet + facet normal -0.792715 -0.137047 0.593988 + outer loop + vertex 0.806317 1.25825 2.54517 + vertex 0.808545 1.26145 2.54888 + vertex 0.80618 1.26386 2.54628 + endloop + endfacet + facet normal -0.792151 -0.138044 0.594509 + outer loop + vertex 0.808826 1.25634 2.54807 + vertex 0.808545 1.26145 2.54888 + vertex 0.806317 1.25825 2.54517 + endloop + endfacet + facet normal -0.829017 -0.130233 0.543847 + outer loop + vertex 0.804001 1.26653 2.5436 + vertex 0.804244 1.26155 2.54278 + vertex 0.80618 1.26386 2.54628 + endloop + endfacet + facet normal -0.831744 -0.138818 0.537523 + outer loop + vertex 0.805995 1.26928 2.54739 + vertex 0.804001 1.26653 2.5436 + vertex 0.80618 1.26386 2.54628 + endloop + endfacet + facet normal -0.792588 -0.148527 0.591391 + outer loop + vertex 0.80618 1.26386 2.54628 + vertex 0.808224 1.26641 2.54966 + vertex 0.805995 1.26928 2.54739 + endloop + endfacet + facet normal -0.79487 -0.144095 0.589422 + outer loop + vertex 0.808545 1.26145 2.54888 + vertex 0.808224 1.26641 2.54966 + vertex 0.80618 1.26386 2.54628 + endloop + endfacet + facet normal -0.82875 -0.145084 0.540485 + outer loop + vertex 0.803603 1.27138 2.54429 + vertex 0.804001 1.26653 2.5436 + vertex 0.805995 1.26928 2.54739 + endloop + endfacet + facet normal -0.831209 -0.159568 0.532569 + outer loop + vertex 0.805047 1.27404 2.54734 + vertex 0.803603 1.27138 2.54429 + vertex 0.805995 1.26928 2.54739 + endloop + endfacet + facet normal -0.795296 -0.154814 0.58612 + outer loop + vertex 0.808021 1.2701 2.55036 + vertex 0.805995 1.26928 2.54739 + vertex 0.808224 1.26641 2.54966 + endloop + endfacet + facet normal -0.794041 -0.159516 0.58656 + outer loop + vertex 0.808021 1.2701 2.55036 + vertex 0.807173 1.27332 2.55009 + vertex 0.805995 1.26928 2.54739 + endloop + endfacet + facet normal -0.800496 -0.152932 0.579498 + outer loop + vertex 0.807173 1.27332 2.55009 + vertex 0.805047 1.27404 2.54734 + vertex 0.805995 1.26928 2.54739 + endloop + endfacet + facet normal -0.766846 -0.149193 0.624251 + outer loop + vertex 0.808021 1.2701 2.55036 + vertex 0.809039 1.27245 2.55217 + vertex 0.807173 1.27332 2.55009 + endloop + endfacet + facet normal -0.830378 -0.161007 0.533431 + outer loop + vertex 0.803603 1.27138 2.54429 + vertex 0.805047 1.27404 2.54734 + vertex 0.803286 1.27519 2.54495 + endloop + endfacet + facet normal -0.83045 -0.161929 0.53304 + outer loop + vertex 0.80413 1.27753 2.54697 + vertex 0.803286 1.27519 2.54495 + vertex 0.805047 1.27404 2.54734 + endloop + endfacet + facet normal -0.801087 -0.149323 0.579623 + outer loop + vertex 0.80413 1.27753 2.54697 + vertex 0.805047 1.27404 2.54734 + vertex 0.806236 1.27831 2.55008 + endloop + endfacet + facet normal -0.800496 -0.149913 0.580286 + outer loop + vertex 0.806236 1.27831 2.55008 + vertex 0.805047 1.27404 2.54734 + vertex 0.807173 1.27332 2.55009 + endloop + endfacet + facet normal -0.76726 -0.143649 0.625041 + outer loop + vertex 0.807173 1.27332 2.55009 + vertex 0.808891 1.27632 2.55289 + vertex 0.806236 1.27831 2.55008 + endloop + endfacet + facet normal -0.766464 -0.144776 0.625758 + outer loop + vertex 0.809039 1.27245 2.55217 + vertex 0.808891 1.27632 2.55289 + vertex 0.807173 1.27332 2.55009 + endloop + endfacet + facet normal -0.800164 -0.153042 0.579928 + outer loop + vertex 0.804006 1.28164 2.54789 + vertex 0.80413 1.27753 2.54697 + vertex 0.806236 1.27831 2.55008 + endloop + endfacet + facet normal -0.759708 -0.112824 0.640402 + outer loop + vertex 0.804663 1.32943 2.55738 + vertex 0.802079 1.32738 2.55395 + vertex 0.80569 1.32449 2.55773 + endloop + endfacet + facet normal -0.755635 -0.122889 0.643362 + outer loop + vertex 0.802079 1.32738 2.55395 + vertex 0.804663 1.32943 2.55738 + vertex 0.802636 1.33109 2.55531 + endloop + endfacet + facet normal -0.702896 -0.00208293 0.71129 + outer loop + vertex 0.804554 1.50776 2.57169 + vertex 0.805306 1.51195 2.57245 + vertex 0.802976 1.50985 2.57014 + endloop + endfacet + facet normal -0.705038 0.00554713 0.709147 + outer loop + vertex 0.80488 1.52437 2.57202 + vertex 0.802958 1.52279 2.57013 + vertex 0.804407 1.52091 2.57158 + endloop + endfacet + facet normal -0.70681 0.00986157 0.707335 + outer loop + vertex 0.802649 1.52647 2.56977 + vertex 0.802958 1.52279 2.57013 + vertex 0.80488 1.52437 2.57202 + endloop + endfacet + facet normal -0.765034 0.151537 0.625907 + outer loop + vertex 0.804107 1.74575 2.54726 + vertex 0.803711 1.74079 2.54798 + vertex 0.806224 1.74319 2.55046 + endloop + endfacet + facet normal -0.80563 0.151621 0.572687 + outer loop + vertex 0.804261 1.7655 2.5424 + vertex 0.803858 1.76056 2.54314 + vertex 0.806215 1.76297 2.54582 + endloop + endfacet + facet normal -0.814218 0.13435 0.564799 + outer loop + vertex 0.806346 1.76854 2.54468 + vertex 0.804261 1.7655 2.5424 + vertex 0.806215 1.76297 2.54582 + endloop + endfacet + facet normal -0.850089 0.128999 0.510595 + outer loop + vertex 0.805141 1.77258 2.54207 + vertex 0.803557 1.77162 2.53967 + vertex 0.804396 1.76922 2.54167 + endloop + endfacet + facet normal -0.816355 0.138976 0.56058 + outer loop + vertex 0.804396 1.76922 2.54167 + vertex 0.804261 1.7655 2.5424 + vertex 0.806346 1.76854 2.54468 + endloop + endfacet + facet normal -0.821083 0.116954 0.558699 + outer loop + vertex 0.804396 1.76922 2.54167 + vertex 0.806346 1.76854 2.54468 + vertex 0.805141 1.77258 2.54207 + endloop + endfacet + facet normal -0.814131 0.12452 0.567173 + outer loop + vertex 0.805141 1.77258 2.54207 + vertex 0.806346 1.76854 2.54468 + vertex 0.807131 1.77348 2.54473 + endloop + endfacet + facet normal -0.849536 0.120865 0.513498 + outer loop + vertex 0.803741 1.77557 2.53905 + vertex 0.803557 1.77162 2.53967 + vertex 0.805141 1.77258 2.54207 + endloop + endfacet + facet normal -0.855195 0.110935 0.506295 + outer loop + vertex 0.805894 1.77749 2.54226 + vertex 0.803741 1.77557 2.53905 + vertex 0.805141 1.77258 2.54207 + endloop + endfacet + facet normal -0.775199 0.10581 0.622793 + outer loop + vertex 0.807849 1.77685 2.54505 + vertex 0.807131 1.77348 2.54473 + vertex 0.808926 1.7746 2.54677 + endloop + endfacet + facet normal -0.800445 0.114445 0.588379 + outer loop + vertex 0.807849 1.77685 2.54505 + vertex 0.805894 1.77749 2.54226 + vertex 0.807131 1.77348 2.54473 + endloop + endfacet + facet normal -0.812655 0.101725 0.573797 + outer loop + vertex 0.805894 1.77749 2.54226 + vertex 0.805141 1.77258 2.54207 + vertex 0.807131 1.77348 2.54473 + endloop + endfacet + facet normal -0.851678 0.0904841 0.516194 + outer loop + vertex 0.804045 1.78063 2.53866 + vertex 0.803741 1.77557 2.53905 + vertex 0.805894 1.77749 2.54226 + endloop + endfacet + facet normal -0.862402 0.0675004 0.501703 + outer loop + vertex 0.805929 1.78297 2.54158 + vertex 0.804045 1.78063 2.53866 + vertex 0.805894 1.77749 2.54226 + endloop + endfacet + facet normal -0.802308 0.0782603 0.591757 + outer loop + vertex 0.805894 1.77749 2.54226 + vertex 0.807852 1.78054 2.54451 + vertex 0.805929 1.78297 2.54158 + endloop + endfacet + facet normal -0.806087 0.0852193 0.585629 + outer loop + vertex 0.807849 1.77685 2.54505 + vertex 0.807852 1.78054 2.54451 + vertex 0.805894 1.77749 2.54226 + endloop + endfacet + facet normal -0.860867 0.0621316 0.505023 + outer loop + vertex 0.804235 1.78574 2.53836 + vertex 0.804045 1.78063 2.53866 + vertex 0.805929 1.78297 2.54158 + endloop + endfacet + facet normal -0.863423 0.0562634 0.501333 + outer loop + vertex 0.806051 1.7881 2.54122 + vertex 0.804235 1.78574 2.53836 + vertex 0.805929 1.78297 2.54158 + endloop + endfacet + facet normal -0.804076 0.0612397 0.591364 + outer loop + vertex 0.805929 1.78297 2.54158 + vertex 0.808064 1.78538 2.54424 + vertex 0.806051 1.7881 2.54122 + endloop + endfacet + facet normal -0.806823 0.0687061 0.586785 + outer loop + vertex 0.807852 1.78054 2.54451 + vertex 0.808064 1.78538 2.54424 + vertex 0.805929 1.78297 2.54158 + endloop + endfacet + facet normal -0.864439 0.0596423 0.499188 + outer loop + vertex 0.804392 1.79074 2.53803 + vertex 0.804235 1.78574 2.53836 + vertex 0.806051 1.7881 2.54122 + endloop + endfacet + facet normal -0.85925 0.0717419 0.5065 + outer loop + vertex 0.806186 1.79322 2.54072 + vertex 0.804392 1.79074 2.53803 + vertex 0.806051 1.7881 2.54122 + endloop + endfacet + facet normal -0.80405 0.0783337 0.589378 + outer loop + vertex 0.806051 1.7881 2.54122 + vertex 0.808248 1.79057 2.54389 + vertex 0.806186 1.79322 2.54072 + endloop + endfacet + facet normal -0.800439 0.0685098 0.595486 + outer loop + vertex 0.808064 1.78538 2.54424 + vertex 0.808248 1.79057 2.54389 + vertex 0.806051 1.7881 2.54122 + endloop + endfacet + facet normal -0.859704 0.0731219 0.505532 + outer loop + vertex 0.804496 1.79552 2.53752 + vertex 0.804392 1.79074 2.53803 + vertex 0.806186 1.79322 2.54072 + endloop + endfacet + facet normal -0.843762 0.111885 0.524926 + outer loop + vertex 0.806272 1.79863 2.53971 + vertex 0.804496 1.79552 2.53752 + vertex 0.806186 1.79322 2.54072 + endloop + endfacet + facet normal -0.804447 0.121845 0.581394 + outer loop + vertex 0.806186 1.79322 2.54072 + vertex 0.808407 1.7958 2.54326 + vertex 0.806272 1.79863 2.53971 + endloop + endfacet + facet normal -0.795019 0.096664 0.598833 + outer loop + vertex 0.808248 1.79057 2.54389 + vertex 0.808407 1.7958 2.54326 + vertex 0.806186 1.79322 2.54072 + endloop + endfacet + facet normal -0.877245 0.17249 0.447983 + outer loop + vertex 0.805171 1.80263 2.53676 + vertex 0.803807 1.80153 2.53452 + vertex 0.804473 1.79922 2.53671 + endloop + endfacet + facet normal -0.842693 0.109753 0.52709 + outer loop + vertex 0.804473 1.79922 2.53671 + vertex 0.804496 1.79552 2.53752 + vertex 0.806272 1.79863 2.53971 + endloop + endfacet + facet normal -0.831884 0.161919 0.530802 + outer loop + vertex 0.804473 1.79922 2.53671 + vertex 0.806272 1.79863 2.53971 + vertex 0.805171 1.80263 2.53676 + endloop + endfacet + facet normal -0.826948 0.16763 0.536709 + outer loop + vertex 0.805171 1.80263 2.53676 + vertex 0.806272 1.79863 2.53971 + vertex 0.807153 1.80353 2.53954 + endloop + endfacet + facet normal -0.800239 0.164227 0.576755 + outer loop + vertex 0.806272 1.79863 2.53971 + vertex 0.808754 1.80075 2.54255 + vertex 0.807153 1.80353 2.53954 + endloop + endfacet + facet normal -0.795005 0.140023 0.59022 + outer loop + vertex 0.808407 1.7958 2.54326 + vertex 0.808754 1.80075 2.54255 + vertex 0.806272 1.79863 2.53971 + endloop + endfacet + facet normal -0.877677 0.185284 0.441988 + outer loop + vertex 0.80404 1.80527 2.53341 + vertex 0.803807 1.80153 2.53452 + vertex 0.805171 1.80263 2.53676 + endloop + endfacet + facet normal -0.870594 0.198648 0.450117 + outer loop + vertex 0.806019 1.80795 2.53606 + vertex 0.80404 1.80527 2.53341 + vertex 0.805171 1.80263 2.53676 + endloop + endfacet + facet normal -0.802392 0.181683 0.56847 + outer loop + vertex 0.808065 1.80684 2.53976 + vertex 0.807153 1.80353 2.53954 + vertex 0.808983 1.80449 2.54181 + endloop + endfacet + facet normal -0.833425 0.193689 0.517579 + outer loop + vertex 0.808065 1.80684 2.53976 + vertex 0.806019 1.80795 2.53606 + vertex 0.807153 1.80353 2.53954 + endloop + endfacet + facet normal -0.826566 0.20166 0.525473 + outer loop + vertex 0.806019 1.80795 2.53606 + vertex 0.805171 1.80263 2.53676 + vertex 0.807153 1.80353 2.53954 + endloop + endfacet + facet normal -0.801303 0.162531 0.575758 + outer loop + vertex 0.808983 1.80449 2.54181 + vertex 0.807153 1.80353 2.53954 + vertex 0.808754 1.80075 2.54255 + endloop + endfacet + facet normal -0.894755 0.205181 0.396629 + outer loop + vertex 0.804927 1.81238 2.53208 + vertex 0.803647 1.81142 2.52969 + vertex 0.804213 1.80897 2.53223 + endloop + endfacet + facet normal -0.868007 0.186974 0.460006 + outer loop + vertex 0.804213 1.80897 2.53223 + vertex 0.80404 1.80527 2.53341 + vertex 0.806019 1.80795 2.53606 + endloop + endfacet + facet normal -0.863722 0.201603 0.461887 + outer loop + vertex 0.804213 1.80897 2.53223 + vertex 0.806019 1.80795 2.53606 + vertex 0.804927 1.81238 2.53208 + endloop + endfacet + facet normal -0.871561 0.190561 0.45174 + outer loop + vertex 0.804927 1.81238 2.53208 + vertex 0.806019 1.80795 2.53606 + vertex 0.806827 1.81373 2.53518 + endloop + endfacet + facet normal -0.838043 0.194699 0.509682 + outer loop + vertex 0.806019 1.80795 2.53606 + vertex 0.808417 1.81066 2.53896 + vertex 0.806827 1.81373 2.53518 + endloop + endfacet + facet normal -0.835937 0.185501 0.516526 + outer loop + vertex 0.808065 1.80684 2.53976 + vertex 0.808417 1.81066 2.53896 + vertex 0.806019 1.80795 2.53606 + endloop + endfacet + facet normal -0.894179 0.217162 0.391517 + outer loop + vertex 0.803953 1.81514 2.52833 + vertex 0.803647 1.81142 2.52969 + vertex 0.804927 1.81238 2.53208 + endloop + endfacet + facet normal -0.903402 0.19841 0.380128 + outer loop + vertex 0.805491 1.81771 2.53064 + vertex 0.803953 1.81514 2.52833 + vertex 0.804927 1.81238 2.53208 + endloop + endfacet + facet normal -0.871453 0.211879 0.442354 + outer loop + vertex 0.804927 1.81238 2.53208 + vertex 0.806827 1.81373 2.53518 + vertex 0.805491 1.81771 2.53064 + endloop + endfacet + facet normal -0.895914 0.16814 0.411177 + outer loop + vertex 0.805491 1.81771 2.53064 + vertex 0.806827 1.81373 2.53518 + vertex 0.807492 1.81877 2.53456 + endloop + endfacet + facet normal -0.854651 0.172235 0.489803 + outer loop + vertex 0.806827 1.81373 2.53518 + vertex 0.808979 1.81559 2.53828 + vertex 0.807492 1.81877 2.53456 + endloop + endfacet + facet normal -0.853991 0.16597 0.493106 + outer loop + vertex 0.808417 1.81066 2.53896 + vertex 0.808979 1.81559 2.53828 + vertex 0.806827 1.81373 2.53518 + endloop + endfacet + facet normal -0.928741 0.176841 0.325834 + outer loop + vertex 0.80501 1.82363 2.52658 + vertex 0.803996 1.8223 2.52441 + vertex 0.804229 1.81909 2.52682 + endloop + endfacet + facet normal -0.90474 0.205487 0.373123 + outer loop + vertex 0.804229 1.81909 2.52682 + vertex 0.803953 1.81514 2.52833 + vertex 0.805491 1.81771 2.53064 + endloop + endfacet + facet normal -0.913911 0.176343 0.365609 + outer loop + vertex 0.804229 1.81909 2.52682 + vertex 0.805491 1.81771 2.53064 + vertex 0.80501 1.82363 2.52658 + endloop + endfacet + facet normal -0.910393 0.181035 0.372037 + outer loop + vertex 0.80501 1.82363 2.52658 + vertex 0.805491 1.81771 2.53064 + vertex 0.806528 1.82284 2.53068 + endloop + endfacet + facet normal -0.895375 0.177711 0.408317 + outer loop + vertex 0.805491 1.81771 2.53064 + vertex 0.807492 1.81877 2.53456 + vertex 0.806528 1.82284 2.53068 + endloop + endfacet + facet normal -0.914228 0.144742 0.378467 + outer loop + vertex 0.806528 1.82284 2.53068 + vertex 0.807492 1.81877 2.53456 + vertex 0.80813 1.82327 2.53438 + endloop + endfacet + facet normal -0.872177 0.142361 0.468018 + outer loop + vertex 0.807492 1.81877 2.53456 + vertex 0.809357 1.82046 2.53753 + vertex 0.80813 1.82327 2.53438 + endloop + endfacet + facet normal -0.871933 0.140076 0.469161 + outer loop + vertex 0.808979 1.81559 2.53828 + vertex 0.809357 1.82046 2.53753 + vertex 0.807492 1.81877 2.53456 + endloop + endfacet + facet normal -0.923424 0.100084 0.370502 + outer loop + vertex 0.805 1.82939 2.525 + vertex 0.803996 1.8223 2.52441 + vertex 0.80501 1.82363 2.52658 + endloop + endfacet + facet normal -0.604178 0.209992 0.768682 + outer loop + vertex 0.805 1.82939 2.525 + vertex 0.80501 1.82363 2.52658 + vertex 0.805212 1.83 2.525 + endloop + endfacet + facet normal -0.763917 0.178185 0.620226 + outer loop + vertex 0.805212 1.83 2.525 + vertex 0.80501 1.82363 2.52658 + vertex 0.805965 1.82772 2.52658 + endloop + endfacet + facet normal -0.902808 0.210686 0.374898 + outer loop + vertex 0.80501 1.82363 2.52658 + vertex 0.806528 1.82284 2.53068 + vertex 0.805965 1.82772 2.52658 + endloop + endfacet + facet normal -0.931152 0.16544 0.324941 + outer loop + vertex 0.805965 1.82772 2.52658 + vertex 0.806528 1.82284 2.53068 + vertex 0.807554 1.82783 2.53108 + endloop + endfacet + facet normal -0.882533 0.131777 0.45141 + outer loop + vertex 0.808809 1.82651 2.53477 + vertex 0.80813 1.82327 2.53438 + vertex 0.809484 1.82417 2.53677 + endloop + endfacet + facet normal -0.918457 0.149398 0.366219 + outer loop + vertex 0.808809 1.82651 2.53477 + vertex 0.807554 1.82783 2.53108 + vertex 0.80813 1.82327 2.53438 + endloop + endfacet + facet normal -0.912949 0.157511 0.376449 + outer loop + vertex 0.807554 1.82783 2.53108 + vertex 0.806528 1.82284 2.53068 + vertex 0.80813 1.82327 2.53438 + endloop + endfacet + facet normal -0.882194 0.122946 0.454553 + outer loop + vertex 0.809484 1.82417 2.53677 + vertex 0.80813 1.82327 2.53438 + vertex 0.809357 1.82046 2.53753 + endloop + endfacet + facet normal -0.380382 0.91355 0.143999 + outer loop + vertex 0.804489 1.83055 2.51961 + vertex 0.805 1.83 2.52444 + vertex 0.805212 1.83 2.525 + endloop + endfacet + facet normal -0.924744 0.345692 0.159203 + outer loop + vertex 0.80567 1.83267 2.52186 + vertex 0.804489 1.83055 2.51961 + vertex 0.805212 1.83 2.525 + endloop + endfacet + facet normal 0.561147 0.588452 0.582098 + outer loop + vertex 0.805212 1.83 2.525 + vertex 0.805965 1.82772 2.52658 + vertex 0.80567 1.83267 2.52186 + endloop + endfacet + facet normal -0.945173 0.194179 0.262568 + outer loop + vertex 0.80567 1.83267 2.52186 + vertex 0.805965 1.82772 2.52658 + vertex 0.806807 1.83235 2.52619 + endloop + endfacet + facet normal -0.926117 0.195836 0.322422 + outer loop + vertex 0.805965 1.82772 2.52658 + vertex 0.807554 1.82783 2.53108 + vertex 0.806807 1.83235 2.52619 + endloop + endfacet + facet normal -0.952783 0.136219 0.271382 + outer loop + vertex 0.806807 1.83235 2.52619 + vertex 0.807554 1.82783 2.53108 + vertex 0.808063 1.83338 2.53008 + endloop + endfacet + facet normal -0.914039 0.151572 0.376243 + outer loop + vertex 0.807554 1.82783 2.53108 + vertex 0.809125 1.83039 2.53387 + vertex 0.808063 1.83338 2.53008 + endloop + endfacet + facet normal -0.915481 0.160241 0.369076 + outer loop + vertex 0.808809 1.82651 2.53477 + vertex 0.809125 1.83039 2.53387 + vertex 0.807554 1.82783 2.53108 + endloop + endfacet + facet normal -0.907856 0.066746 0.413936 + outer loop + vertex 0.805 1.83507 2.52 + vertex 0.804489 1.83055 2.51961 + vertex 0.80567 1.83267 2.52186 + endloop + endfacet + facet normal -0.683205 0.318045 0.657327 + outer loop + vertex 0.805 1.83507 2.52 + vertex 0.80567 1.83267 2.52186 + vertex 0.807295 1.84 2.52 + endloop + endfacet + facet normal -0.972194 0.228546 0.0510403 + outer loop + vertex 0.807295 1.84 2.52 + vertex 0.80567 1.83267 2.52186 + vertex 0.806814 1.83752 2.52196 + endloop + endfacet + facet normal -0.940214 0.216475 0.262939 + outer loop + vertex 0.80567 1.83267 2.52186 + vertex 0.806807 1.83235 2.52619 + vertex 0.806814 1.83752 2.52196 + endloop + endfacet + facet normal -0.976209 0.138137 0.167134 + outer loop + vertex 0.806814 1.83752 2.52196 + vertex 0.806807 1.83235 2.52619 + vertex 0.807475 1.83741 2.52591 + endloop + endfacet + facet normal -0.9525 0.140646 0.270117 + outer loop + vertex 0.806807 1.83235 2.52619 + vertex 0.808063 1.83338 2.53008 + vertex 0.807475 1.83741 2.52591 + endloop + endfacet + facet normal -0.962636 0.113888 0.245685 + outer loop + vertex 0.807475 1.83741 2.52591 + vertex 0.808063 1.83338 2.53008 + vertex 0.808463 1.8381 2.52946 + endloop + endfacet + facet normal -0.913519 0.128136 0.386088 + outer loop + vertex 0.808063 1.83338 2.53008 + vertex 0.809495 1.83524 2.53285 + vertex 0.808463 1.8381 2.52946 + endloop + endfacet + facet normal -0.915607 0.147987 0.373851 + outer loop + vertex 0.809125 1.83039 2.53387 + vertex 0.809495 1.83524 2.53285 + vertex 0.808063 1.83338 2.53008 + endloop + endfacet + facet normal -0.988631 0.116452 -0.0951192 + outer loop + vertex 0.807295 1.84 2.52 + vertex 0.806814 1.83752 2.52196 + vertex 0.807884 1.845 2.52 + endloop + endfacet + facet normal -0.980041 0.0943117 -0.174998 + outer loop + vertex 0.807884 1.845 2.52 + vertex 0.806814 1.83752 2.52196 + vertex 0.807337 1.84234 2.52163 + endloop + endfacet + facet normal -0.978916 0.117578 0.167032 + outer loop + vertex 0.806814 1.83752 2.52196 + vertex 0.807475 1.83741 2.52591 + vertex 0.807337 1.84234 2.52163 + endloop + endfacet + facet normal -0.981383 0.109489 0.157798 + outer loop + vertex 0.807337 1.84234 2.52163 + vertex 0.807475 1.83741 2.52591 + vertex 0.808055 1.84269 2.52586 + endloop + endfacet + facet normal -0.914634 0.12735 0.383701 + outer loop + vertex 0.808939 1.84147 2.52947 + vertex 0.808463 1.8381 2.52946 + vertex 0.809542 1.83911 2.5317 + endloop + endfacet + facet normal -0.951639 0.13303 0.276923 + outer loop + vertex 0.808939 1.84147 2.52947 + vertex 0.808055 1.84269 2.52586 + vertex 0.808463 1.8381 2.52946 + endloop + endfacet + facet normal -0.962973 0.108391 0.24685 + outer loop + vertex 0.808055 1.84269 2.52586 + vertex 0.807475 1.83741 2.52591 + vertex 0.808463 1.8381 2.52946 + endloop + endfacet + facet normal -0.914567 0.125745 0.38439 + outer loop + vertex 0.809542 1.83911 2.5317 + vertex 0.808463 1.8381 2.52946 + vertex 0.809495 1.83524 2.53285 + endloop + endfacet + facet normal -0.971122 -0.1583 -0.178505 + outer loop + vertex 0.808803 1.845 2.515 + vertex 0.807884 1.845 2.52 + vertex 0.807988 1.85 2.515 + endloop + endfacet + facet normal -0.525146 -0.596262 -0.607201 + outer loop + vertex 0.807988 1.85 2.515 + vertex 0.807884 1.845 2.52 + vertex 0.807462 1.84795 2.51747 + endloop + endfacet + facet normal 0.490266 -0.526114 -0.694869 + outer loop + vertex 0.807884 1.845 2.52 + vertex 0.807337 1.84234 2.52163 + vertex 0.807462 1.84795 2.51747 + endloop + endfacet + facet normal -0.995657 0.0687004 0.0628237 + outer loop + vertex 0.807462 1.84795 2.51747 + vertex 0.807337 1.84234 2.52163 + vertex 0.807651 1.84744 2.52103 + endloop + endfacet + facet normal -0.983797 0.0795061 0.160693 + outer loop + vertex 0.807337 1.84234 2.52163 + vertex 0.808055 1.84269 2.52586 + vertex 0.807651 1.84744 2.52103 + endloop + endfacet + facet normal -0.978782 0.0989557 0.179424 + outer loop + vertex 0.807651 1.84744 2.52103 + vertex 0.808055 1.84269 2.52586 + vertex 0.808372 1.84798 2.52466 + endloop + endfacet + facet normal -0.944097 0.125152 0.30499 + outer loop + vertex 0.808055 1.84269 2.52586 + vertex 0.809185 1.8452 2.52832 + vertex 0.808372 1.84798 2.52466 + endloop + endfacet + facet normal -0.947782 0.149718 0.28159 + outer loop + vertex 0.808939 1.84147 2.52947 + vertex 0.809185 1.8452 2.52832 + vertex 0.808055 1.84269 2.52586 + endloop + endfacet + facet normal -0.976472 -0.00859067 -0.215472 + outer loop + vertex 0.807988 1.85 2.515 + vertex 0.807462 1.84795 2.51747 + vertex 0.807944 1.855 2.515 + endloop + endfacet + facet normal -0.994293 0.0324835 -0.101621 + outer loop + vertex 0.807944 1.855 2.515 + vertex 0.807462 1.84795 2.51747 + vertex 0.80768 1.853 2.51694 + endloop + endfacet + facet normal -0.996965 0.0494429 0.0601368 + outer loop + vertex 0.807462 1.84795 2.51747 + vertex 0.807651 1.84744 2.52103 + vertex 0.80768 1.853 2.51694 + endloop + endfacet + facet normal -0.98448 0.107286 0.138883 + outer loop + vertex 0.80768 1.853 2.51694 + vertex 0.807651 1.84744 2.52103 + vertex 0.808199 1.85275 2.52081 + endloop + endfacet + facet normal -0.934768 0.150493 0.321808 + outer loop + vertex 0.80887 1.8513 2.52456 + vertex 0.808372 1.84798 2.52466 + vertex 0.809359 1.84889 2.5271 + endloop + endfacet + facet normal -0.96117 0.151447 0.230688 + outer loop + vertex 0.80887 1.8513 2.52456 + vertex 0.808199 1.85275 2.52081 + vertex 0.808372 1.84798 2.52466 + endloop + endfacet + facet normal -0.978074 0.108239 0.177918 + outer loop + vertex 0.808199 1.85275 2.52081 + vertex 0.807651 1.84744 2.52103 + vertex 0.808372 1.84798 2.52466 + endloop + endfacet + facet normal -0.934776 0.150202 0.32192 + outer loop + vertex 0.809359 1.84889 2.5271 + vertex 0.808372 1.84798 2.52466 + vertex 0.809185 1.8452 2.52832 + endloop + endfacet + facet normal -0.994751 0.0395951 -0.0943495 + outer loop + vertex 0.807944 1.855 2.515 + vertex 0.80768 1.853 2.51694 + vertex 0.808143 1.86 2.515 + endloop + endfacet + facet normal -0.976604 0.114965 0.181737 + outer loop + vertex 0.808143 1.86 2.515 + vertex 0.80768 1.853 2.51694 + vertex 0.808407 1.8589 2.51711 + endloop + endfacet + facet normal -0.983305 0.11703 0.139339 + outer loop + vertex 0.80768 1.853 2.51694 + vertex 0.808199 1.85275 2.52081 + vertex 0.808407 1.8589 2.51711 + endloop + endfacet + facet normal -0.965067 0.158194 0.208855 + outer loop + vertex 0.808407 1.8589 2.51711 + vertex 0.808199 1.85275 2.52081 + vertex 0.808817 1.85761 2.51998 + endloop + endfacet + facet normal -0.95032 0.165616 0.26356 + outer loop + vertex 0.808199 1.85275 2.52081 + vertex 0.809216 1.85491 2.52312 + vertex 0.808817 1.85761 2.51998 + endloop + endfacet + facet normal -0.951586 0.188057 0.243143 + outer loop + vertex 0.80887 1.8513 2.52456 + vertex 0.809216 1.85491 2.52312 + vertex 0.808199 1.85275 2.52081 + endloop + endfacet + facet normal -0.962121 0.155123 0.224189 + outer loop + vertex 0.81 1.865 2.51973 + vertex 0.808407 1.8589 2.51711 + vertex 0.81 1.86461 2.52 + endloop + endfacet + facet normal -0.946454 0.118386 0.30035 + outer loop + vertex 0.81 1.865 2.51973 + vertex 0.808499 1.865 2.515 + vertex 0.808407 1.8589 2.51711 + endloop + endfacet + facet normal -0.984723 0.0701042 0.159395 + outer loop + vertex 0.808499 1.865 2.515 + vertex 0.808143 1.86 2.515 + vertex 0.808407 1.8589 2.51711 + endloop + endfacet + facet normal -0.926957 0.155911 0.341236 + outer loop + vertex 0.81 1.86461 2.52 + vertex 0.808817 1.85761 2.51998 + vertex 0.809625 1.85908 2.52151 + endloop + endfacet + facet normal -0.963968 0.16249 0.210626 + outer loop + vertex 0.808407 1.8589 2.51711 + vertex 0.808817 1.85761 2.51998 + vertex 0.81 1.86461 2.52 + endloop + endfacet + facet normal -0.932743 0.205868 0.295989 + outer loop + vertex 0.809625 1.85908 2.52151 + vertex 0.808817 1.85761 2.51998 + vertex 0.809216 1.85491 2.52312 + endloop + endfacet + facet normal -0.98772 -0.102921 -0.117543 + outer loop + vertex 0.809094 1.865 2.51 + vertex 0.808499 1.865 2.515 + vertex 0.808573 1.87 2.51 + endloop + endfacet + facet normal 0.100765 0.70277 0.704245 + outer loop + vertex 0.808573 1.87 2.51 + vertex 0.808499 1.865 2.515 + vertex 0.808857 1.86905 2.51091 + endloop + endfacet + facet normal -0.816797 0.444245 0.368089 + outer loop + vertex 0.808499 1.865 2.515 + vertex 0.809255 1.86654 2.51482 + vertex 0.808857 1.86905 2.51091 + endloop + endfacet + facet normal -0.851267 0.449853 0.270143 + outer loop + vertex 0.81 1.865 2.51973 + vertex 0.809255 1.86654 2.51482 + vertex 0.808499 1.865 2.515 + endloop + endfacet + facet normal 0.207396 0.22292 -0.95252 + outer loop + vertex 0.81 1.87 2.50857 + vertex 0.809122 1.87134 2.50869 + vertex 0.81 1.875 2.50974 + endloop + endfacet + facet normal -0.657844 -0.369214 -0.656446 + outer loop + vertex 0.808573 1.87 2.51 + vertex 0.809122 1.87134 2.50869 + vertex 0.81 1.87 2.50857 + endloop + endfacet + facet normal -0.976648 0.180454 0.116594 + outer loop + vertex 0.81 1.875 2.51127 + vertex 0.808857 1.86905 2.51091 + vertex 0.81 1.87259 2.515 + endloop + endfacet + facet normal -0.980238 0.183799 0.0731529 + outer loop + vertex 0.81 1.875 2.51127 + vertex 0.809122 1.87134 2.50869 + vertex 0.808857 1.86905 2.51091 + endloop + endfacet + facet normal 0.0171463 0.693242 0.720501 + outer loop + vertex 0.809122 1.87134 2.50869 + vertex 0.808573 1.87 2.51 + vertex 0.808857 1.86905 2.51091 + endloop + endfacet + facet normal -0.978091 0.115257 0.173362 + outer loop + vertex 0.81 1.87259 2.515 + vertex 0.808857 1.86905 2.51091 + vertex 0.809255 1.86654 2.51482 + endloop + endfacet + facet normal -0.724193 0.344858 -0.597174 + outer loop + vertex 0.81 1.875 2.50974 + vertex 0.809122 1.87134 2.50869 + vertex 0.81 1.87545 2.51 + endloop + endfacet + facet normal -0.979853 0.188252 0.0667028 + outer loop + vertex 0.81 1.87545 2.51 + vertex 0.809122 1.87134 2.50869 + vertex 0.81 1.875 2.51127 + endloop + endfacet + facet normal 0.664839 -0.228575 -0.711156 + outer loop + vertex 0.815 1.13444 2.51 + vertex 0.814506 1.13645 2.50889 + vertex 0.815 1.135 2.50982 + endloop + endfacet + facet normal -0.976616 -0.163923 0.139109 + outer loop + vertex 0.815 1.13444 2.51 + vertex 0.815 1.135 2.51066 + vertex 0.814506 1.13645 2.50889 + endloop + endfacet + facet normal -0.701583 -0.00142711 -0.712586 + outer loop + vertex 0.815 1.135 2.50982 + vertex 0.814807 1.14 2.51 + vertex 0.815 1.14 2.50981 + endloop + endfacet + facet normal 0.91146 0.0498836 -0.408353 + outer loop + vertex 0.814506 1.13645 2.50889 + vertex 0.814807 1.14 2.51 + vertex 0.815 1.135 2.50982 + endloop + endfacet + facet normal -0.981246 0.0235875 0.19131 + outer loop + vertex 0.814506 1.13645 2.50889 + vertex 0.815 1.14 2.51099 + vertex 0.814807 1.14 2.51 + endloop + endfacet + facet normal -0.966393 -0.0169282 0.25651 + outer loop + vertex 0.815 1.135 2.51066 + vertex 0.815 1.14 2.51099 + vertex 0.814506 1.13645 2.50889 + endloop + endfacet + facet normal -0.938632 -0.292371 0.183002 + outer loop + vertex 0.815 1.14251 2.515 + vertex 0.814807 1.14 2.51 + vertex 0.815 1.14 2.51099 + endloop + endfacet + facet normal -0.927187 -0.31921 0.196033 + outer loop + vertex 0.815 1.14251 2.515 + vertex 0.813445 1.14527 2.51213 + vertex 0.814807 1.14 2.51 + endloop + endfacet + facet normal -0.967245 -0.176036 -0.182888 + outer loop + vertex 0.813445 1.14527 2.51213 + vertex 0.813897 1.145 2.51 + vertex 0.814807 1.14 2.51 + endloop + endfacet + facet normal 0.484614 -0.483843 -0.728729 + outer loop + vertex 0.815 1.14251 2.515 + vertex 0.814326 1.14286 2.51432 + vertex 0.813445 1.14527 2.51213 + endloop + endfacet + facet normal -0.974848 -0.112306 -0.192504 + outer loop + vertex 0.813897 1.145 2.51 + vertex 0.813445 1.14527 2.51213 + vertex 0.813321 1.15 2.51 + endloop + endfacet + facet normal -0.996135 -0.0564013 -0.0673407 + outer loop + vertex 0.813321 1.15 2.51 + vertex 0.813445 1.14527 2.51213 + vertex 0.812983 1.15 2.515 + endloop + endfacet + facet normal -0.960788 -0.256891 0.104373 + outer loop + vertex 0.813674 1.1457 2.51531 + vertex 0.813445 1.14527 2.51213 + vertex 0.814326 1.14286 2.51432 + endloop + endfacet + facet normal -0.972474 -0.210963 0.0989395 + outer loop + vertex 0.813674 1.1457 2.51531 + vertex 0.812704 1.15035 2.5157 + vertex 0.813445 1.14527 2.51213 + endloop + endfacet + facet normal -0.879016 0.181294 -0.440979 + outer loop + vertex 0.812704 1.15035 2.5157 + vertex 0.812983 1.15 2.515 + vertex 0.813445 1.14527 2.51213 + endloop + endfacet + facet normal -0.952305 -0.216484 0.215056 + outer loop + vertex 0.813674 1.1457 2.51531 + vertex 0.813923 1.14748 2.51821 + vertex 0.812704 1.15035 2.5157 + endloop + endfacet + facet normal -0.942399 -0.153797 -0.297038 + outer loop + vertex 0.812983 1.15 2.515 + vertex 0.812704 1.15035 2.5157 + vertex 0.812167 1.155 2.515 + endloop + endfacet + facet normal -0.916503 -0.161226 -0.3661 + outer loop + vertex 0.812167 1.155 2.515 + vertex 0.812704 1.15035 2.5157 + vertex 0.811827 1.15547 2.51564 + endloop + endfacet + facet normal -0.952332 -0.217461 0.213948 + outer loop + vertex 0.81357 1.15046 2.51966 + vertex 0.812704 1.15035 2.5157 + vertex 0.813923 1.14748 2.51821 + endloop + endfacet + facet normal -0.956172 -0.19951 0.214316 + outer loop + vertex 0.81357 1.15046 2.51966 + vertex 0.81262 1.15467 2.51934 + vertex 0.812704 1.15035 2.5157 + endloop + endfacet + facet normal -0.97123 -0.164358 0.172335 + outer loop + vertex 0.81262 1.15467 2.51934 + vertex 0.811827 1.15547 2.51564 + vertex 0.812704 1.15035 2.5157 + endloop + endfacet + facet normal -0.9399 -0.190602 0.2833 + outer loop + vertex 0.81357 1.15046 2.51966 + vertex 0.814054 1.15225 2.52247 + vertex 0.81262 1.15467 2.51934 + endloop + endfacet + facet normal -0.91024 -0.113229 -0.398299 + outer loop + vertex 0.812167 1.155 2.515 + vertex 0.811827 1.15547 2.51564 + vertex 0.811545 1.16 2.515 + endloop + endfacet + facet normal -0.997052 -0.0544837 0.0540265 + outer loop + vertex 0.811545 1.16 2.515 + vertex 0.811827 1.15547 2.51564 + vertex 0.811686 1.15924 2.51683 + endloop + endfacet + facet normal -0.977349 -0.0961641 0.188525 + outer loop + vertex 0.811827 1.15547 2.51564 + vertex 0.81262 1.15467 2.51934 + vertex 0.811686 1.15924 2.51683 + endloop + endfacet + facet normal -0.980984 -0.114357 0.156822 + outer loop + vertex 0.811686 1.15924 2.51683 + vertex 0.81262 1.15467 2.51934 + vertex 0.812318 1.16013 2.52144 + endloop + endfacet + facet normal -0.950735 -0.155382 0.268251 + outer loop + vertex 0.81262 1.15467 2.51934 + vertex 0.813706 1.15617 2.52406 + vertex 0.812318 1.16013 2.52144 + endloop + endfacet + facet normal -0.940028 -0.196455 0.278841 + outer loop + vertex 0.814054 1.15225 2.52247 + vertex 0.813706 1.15617 2.52406 + vertex 0.81262 1.15467 2.51934 + endloop + endfacet + facet normal -0.996679 -0.064385 0.0498625 + outer loop + vertex 0.811545 1.16 2.515 + vertex 0.811686 1.15924 2.51683 + vertex 0.811222 1.165 2.515 + endloop + endfacet + facet normal -0.987922 -0.0313623 0.151748 + outer loop + vertex 0.811222 1.165 2.515 + vertex 0.811686 1.15924 2.51683 + vertex 0.811702 1.16295 2.5177 + endloop + endfacet + facet normal -0.989535 -0.028906 0.141365 + outer loop + vertex 0.811686 1.15924 2.51683 + vertex 0.812318 1.16013 2.52144 + vertex 0.811702 1.16295 2.5177 + endloop + endfacet + facet normal -0.991323 -0.0663233 0.113489 + outer loop + vertex 0.811702 1.16295 2.5177 + vertex 0.812318 1.16013 2.52144 + vertex 0.811899 1.1647 2.52044 + endloop + endfacet + facet normal -0.954625 -0.174555 0.241291 + outer loop + vertex 0.813407 1.16005 2.52569 + vertex 0.812318 1.16013 2.52144 + vertex 0.813706 1.15617 2.52406 + endloop + endfacet + facet normal -0.961201 -0.128893 0.243885 + outer loop + vertex 0.813407 1.16005 2.52569 + vertex 0.812698 1.16476 2.52538 + vertex 0.812318 1.16013 2.52144 + endloop + endfacet + facet normal -0.985514 -0.0556113 0.160217 + outer loop + vertex 0.812698 1.16476 2.52538 + vertex 0.811899 1.1647 2.52044 + vertex 0.812318 1.16013 2.52144 + endloop + endfacet + facet normal -0.937377 -0.119963 0.327008 + outer loop + vertex 0.813407 1.16005 2.52569 + vertex 0.814093 1.1616 2.52822 + vertex 0.812698 1.16476 2.52538 + endloop + endfacet + facet normal -0.722191 0.542706 -0.428847 + outer loop + vertex 0.815 1.16985 2.515 + vertex 0.812255 1.16774 2.51695 + vertex 0.815 1.17 2.51519 + endloop + endfacet + facet normal -0.720757 0.561441 -0.406564 + outer loop + vertex 0.815 1.16985 2.515 + vertex 0.811222 1.165 2.515 + vertex 0.812255 1.16774 2.51695 + endloop + endfacet + facet normal -0.946148 0.153633 0.284958 + outer loop + vertex 0.811222 1.165 2.515 + vertex 0.811702 1.16295 2.5177 + vertex 0.812255 1.16774 2.51695 + endloop + endfacet + facet normal -0.993461 0.114158 -0.00169612 + outer loop + vertex 0.811702 1.16295 2.5177 + vertex 0.811899 1.1647 2.52044 + vertex 0.812255 1.16774 2.51695 + endloop + endfacet + facet normal -0.992469 -0.0222685 -0.120454 + outer loop + vertex 0.812255 1.16774 2.51695 + vertex 0.811899 1.1647 2.52044 + vertex 0.811693 1.16905 2.52133 + endloop + endfacet + facet normal -0.983885 -0.0792627 0.160277 + outer loop + vertex 0.811899 1.1647 2.52044 + vertex 0.812698 1.16476 2.52538 + vertex 0.811693 1.16905 2.52133 + endloop + endfacet + facet normal -0.985396 -0.141244 0.0951013 + outer loop + vertex 0.811693 1.16905 2.52133 + vertex 0.812698 1.16476 2.52538 + vertex 0.811921 1.16988 2.52493 + endloop + endfacet + facet normal -0.930324 -0.0917576 0.355074 + outer loop + vertex 0.814589 1.1643 2.53022 + vertex 0.812698 1.16476 2.52538 + vertex 0.814093 1.1616 2.52822 + endloop + endfacet + facet normal -0.924867 -0.15597 0.346834 + outer loop + vertex 0.814589 1.1643 2.53022 + vertex 0.8133 1.16936 2.52906 + vertex 0.812698 1.16476 2.52538 + endloop + endfacet + facet normal -0.946248 -0.116986 0.301545 + outer loop + vertex 0.8133 1.16936 2.52906 + vertex 0.811921 1.16988 2.52493 + vertex 0.812698 1.16476 2.52538 + endloop + endfacet + facet normal -0.888772 -0.125115 0.440944 + outer loop + vertex 0.814589 1.1643 2.53022 + vertex 0.815582 1.16715 2.53303 + vertex 0.8133 1.16936 2.52906 + endloop + endfacet + facet normal -0.648329 0.219002 -0.729183 + outer loop + vertex 0.811279 1.175 2.52 + vertex 0.815 1.17 2.51519 + vertex 0.812255 1.16774 2.51695 + endloop + endfacet + facet normal -0.776511 0.0277053 -0.629494 + outer loop + vertex 0.811279 1.175 2.52 + vertex 0.815 1.175 2.51541 + vertex 0.815 1.17 2.51519 + endloop + endfacet + facet normal 0.328822 -0.487294 0.808962 + outer loop + vertex 0.81246 1.175 2.515 + vertex 0.81 1.175 2.516 + vertex 0.81 1.17334 2.515 + endloop + endfacet + facet normal -0.990827 -0.0912947 -0.0996317 + outer loop + vertex 0.812255 1.16774 2.51695 + vertex 0.811693 1.16905 2.52133 + vertex 0.811279 1.175 2.52 + endloop + endfacet + facet normal -0.991936 -0.0892178 -0.0900136 + outer loop + vertex 0.811279 1.175 2.52 + vertex 0.811693 1.16905 2.52133 + vertex 0.811238 1.17299 2.52245 + endloop + endfacet + facet normal -0.985448 -0.140931 0.0950318 + outer loop + vertex 0.811693 1.16905 2.52133 + vertex 0.811921 1.16988 2.52493 + vertex 0.811238 1.17299 2.52245 + endloop + endfacet + facet normal -0.983779 -0.0948784 0.152237 + outer loop + vertex 0.811238 1.17299 2.52245 + vertex 0.811921 1.16988 2.52493 + vertex 0.811682 1.17378 2.52582 + endloop + endfacet + facet normal -0.945508 -0.126247 0.300128 + outer loop + vertex 0.811921 1.16988 2.52493 + vertex 0.8133 1.16936 2.52906 + vertex 0.811682 1.17378 2.52582 + endloop + endfacet + facet normal -0.936642 -0.0961205 0.336841 + outer loop + vertex 0.811682 1.17378 2.52582 + vertex 0.8133 1.16936 2.52906 + vertex 0.812924 1.17486 2.52958 + endloop + endfacet + facet normal -0.896353 -0.102344 0.431367 + outer loop + vertex 0.8133 1.16936 2.52906 + vertex 0.814805 1.17182 2.53276 + vertex 0.812924 1.17486 2.52958 + endloop + endfacet + facet normal -0.888555 -0.123085 0.441949 + outer loop + vertex 0.815582 1.16715 2.53303 + vertex 0.814805 1.17182 2.53276 + vertex 0.8133 1.16936 2.52906 + endloop + endfacet + facet normal 0.89263 0.256551 -0.370665 + outer loop + vertex 0.809831 1.17799 2.51858 + vertex 0.81 1.17945 2.52 + vertex 0.811279 1.175 2.52 + endloop + endfacet + facet normal -0.912847 -0.396947 0.0956213 + outer loop + vertex 0.809831 1.17799 2.51858 + vertex 0.811279 1.175 2.52 + vertex 0.810429 1.17743 2.52198 + endloop + endfacet + facet normal -0.964985 -0.194444 -0.176057 + outer loop + vertex 0.810429 1.17743 2.52198 + vertex 0.811279 1.175 2.52 + vertex 0.811238 1.17299 2.52245 + endloop + endfacet + facet normal -0.973144 -0.159391 0.166087 + outer loop + vertex 0.811238 1.17299 2.52245 + vertex 0.811682 1.17378 2.52582 + vertex 0.810429 1.17743 2.52198 + endloop + endfacet + facet normal -0.970334 -0.102965 0.218747 + outer loop + vertex 0.810429 1.17743 2.52198 + vertex 0.811682 1.17378 2.52582 + vertex 0.811316 1.17853 2.52643 + endloop + endfacet + facet normal -0.932812 -0.115843 0.341236 + outer loop + vertex 0.811682 1.17378 2.52582 + vertex 0.812924 1.17486 2.52958 + vertex 0.811316 1.17853 2.52643 + endloop + endfacet + facet normal -0.917997 -0.0667591 0.390927 + outer loop + vertex 0.811316 1.17853 2.52643 + vertex 0.812924 1.17486 2.52958 + vertex 0.8127 1.17975 2.52989 + endloop + endfacet + facet normal -0.881915 -0.0698891 0.466199 + outer loop + vertex 0.812924 1.17486 2.52958 + vertex 0.814471 1.17677 2.53279 + vertex 0.8127 1.17975 2.52989 + endloop + endfacet + facet normal -0.884328 -0.0620636 0.462723 + outer loop + vertex 0.814805 1.17182 2.53276 + vertex 0.814471 1.17677 2.53279 + vertex 0.812924 1.17486 2.52958 + endloop + endfacet + facet normal -0.953832 -0.273983 0.123034 + outer loop + vertex 0.809134 1.18078 2.5194 + vertex 0.809831 1.17799 2.51858 + vertex 0.810429 1.17743 2.52198 + endloop + endfacet + facet normal -0.954227 -0.193882 0.227728 + outer loop + vertex 0.809776 1.18276 2.52378 + vertex 0.809134 1.18078 2.5194 + vertex 0.810429 1.17743 2.52198 + endloop + endfacet + facet normal -0.951024 -0.197029 0.238186 + outer loop + vertex 0.810429 1.17743 2.52198 + vertex 0.811316 1.17853 2.52643 + vertex 0.809776 1.18276 2.52378 + endloop + endfacet + facet normal -0.928237 -0.116687 0.353215 + outer loop + vertex 0.809776 1.18276 2.52378 + vertex 0.811316 1.17853 2.52643 + vertex 0.811215 1.18264 2.52752 + endloop + endfacet + facet normal -0.903719 -0.130555 0.407734 + outer loop + vertex 0.811316 1.17853 2.52643 + vertex 0.8127 1.17975 2.52989 + vertex 0.811215 1.18264 2.52752 + endloop + endfacet + facet normal -0.889589 -0.090504 0.447706 + outer loop + vertex 0.811215 1.18264 2.52752 + vertex 0.8127 1.17975 2.52989 + vertex 0.812444 1.18447 2.53033 + endloop + endfacet + facet normal -0.860628 -0.0939157 0.5005 + outer loop + vertex 0.8127 1.17975 2.52989 + vertex 0.814277 1.18172 2.53297 + vertex 0.812444 1.18447 2.53033 + endloop + endfacet + facet normal -0.875231 -0.0516262 0.480943 + outer loop + vertex 0.814471 1.17677 2.53279 + vertex 0.814277 1.18172 2.53297 + vertex 0.8127 1.17975 2.52989 + endloop + endfacet + facet normal -0.951103 -0.204056 0.231872 + outer loop + vertex 0.809134 1.18078 2.5194 + vertex 0.809776 1.18276 2.52378 + vertex 0.808592 1.18469 2.52062 + endloop + endfacet + facet normal -0.952032 -0.184369 0.244221 + outer loop + vertex 0.808838 1.18701 2.52333 + vertex 0.808592 1.18469 2.52062 + vertex 0.809776 1.18276 2.52378 + endloop + endfacet + facet normal -0.917971 -0.164411 0.360968 + outer loop + vertex 0.808838 1.18701 2.52333 + vertex 0.809776 1.18276 2.52378 + vertex 0.810345 1.18766 2.52746 + endloop + endfacet + facet normal -0.923658 -0.155651 0.350184 + outer loop + vertex 0.810345 1.18766 2.52746 + vertex 0.809776 1.18276 2.52378 + vertex 0.811215 1.18264 2.52752 + endloop + endfacet + facet normal -0.868691 -0.144647 0.473766 + outer loop + vertex 0.811215 1.18264 2.52752 + vertex 0.812444 1.18447 2.53033 + vertex 0.810345 1.18766 2.52746 + endloop + endfacet + facet normal -0.868157 -0.142955 0.475255 + outer loop + vertex 0.810345 1.18766 2.52746 + vertex 0.812444 1.18447 2.53033 + vertex 0.812309 1.18867 2.53135 + endloop + endfacet + facet normal -0.83536 -0.154528 0.527536 + outer loop + vertex 0.812444 1.18447 2.53033 + vertex 0.814098 1.1866 2.53358 + vertex 0.812309 1.18867 2.53135 + endloop + endfacet + facet normal -0.860601 -0.0938409 0.500559 + outer loop + vertex 0.814277 1.18172 2.53297 + vertex 0.814098 1.1866 2.53358 + vertex 0.812444 1.18447 2.53033 + endloop + endfacet + facet normal -0.910996 -0.195196 0.363297 + outer loop + vertex 0.808838 1.18701 2.52333 + vertex 0.810345 1.18766 2.52746 + vertex 0.808652 1.19014 2.52455 + endloop + endfacet + facet normal -0.911966 -0.2055 0.355089 + outer loop + vertex 0.809277 1.19232 2.52741 + vertex 0.808652 1.19014 2.52455 + vertex 0.810345 1.18766 2.52746 + endloop + endfacet + facet normal -0.868921 -0.194544 0.455114 + outer loop + vertex 0.809277 1.19232 2.52741 + vertex 0.810345 1.18766 2.52746 + vertex 0.811206 1.1935 2.5316 + endloop + endfacet + facet normal -0.84732 -0.218302 0.484141 + outer loop + vertex 0.811206 1.1935 2.5316 + vertex 0.810345 1.18766 2.52746 + vertex 0.812309 1.18867 2.53135 + endloop + endfacet + facet normal -0.809136 -0.212907 0.547694 + outer loop + vertex 0.812309 1.18867 2.53135 + vertex 0.813631 1.19127 2.53431 + vertex 0.811206 1.1935 2.5316 + endloop + endfacet + facet normal -0.838285 -0.165857 0.519394 + outer loop + vertex 0.814098 1.1866 2.53358 + vertex 0.813631 1.19127 2.53431 + vertex 0.812309 1.18867 2.53135 + endloop + endfacet + facet normal -0.859622 -0.224064 0.45918 + outer loop + vertex 0.808994 1.19645 2.52889 + vertex 0.809277 1.19232 2.52741 + vertex 0.811206 1.1935 2.5316 + endloop + endfacet + facet normal -0.864553 -0.248135 0.43701 + outer loop + vertex 0.810149 1.19889 2.53257 + vertex 0.808994 1.19645 2.52889 + vertex 0.811206 1.1935 2.5316 + endloop + endfacet + facet normal -0.810136 -0.218447 0.544023 + outer loop + vertex 0.813211 1.19503 2.5352 + vertex 0.811206 1.1935 2.5316 + vertex 0.813631 1.19127 2.53431 + endloop + endfacet + facet normal -0.794956 -0.254321 0.550786 + outer loop + vertex 0.813211 1.19503 2.5352 + vertex 0.812175 1.1983 2.53521 + vertex 0.811206 1.1935 2.5316 + endloop + endfacet + facet normal -0.794295 -0.254953 0.551447 + outer loop + vertex 0.812175 1.1983 2.53521 + vertex 0.810149 1.19889 2.53257 + vertex 0.811206 1.1935 2.5316 + endloop + endfacet + facet normal -0.769165 -0.246306 0.589677 + outer loop + vertex 0.813211 1.19503 2.5352 + vertex 0.814037 1.19767 2.53738 + vertex 0.812175 1.1983 2.53521 + endloop + endfacet + facet normal -0.871522 -0.234931 0.430414 + outer loop + vertex 0.808994 1.19645 2.52889 + vertex 0.810149 1.19889 2.53257 + vertex 0.80865 1.20032 2.53031 + endloop + endfacet + facet normal -0.871075 -0.223503 0.43735 + outer loop + vertex 0.809287 1.20242 2.53265 + vertex 0.80865 1.20032 2.53031 + vertex 0.810149 1.19889 2.53257 + endloop + endfacet + facet normal -0.821072 -0.213469 0.529406 + outer loop + vertex 0.809287 1.20242 2.53265 + vertex 0.810149 1.19889 2.53257 + vertex 0.810992 1.20297 2.53552 + endloop + endfacet + facet normal -0.795956 -0.238255 0.556496 + outer loop + vertex 0.810992 1.20297 2.53552 + vertex 0.810149 1.19889 2.53257 + vertex 0.812175 1.1983 2.53521 + endloop + endfacet + facet normal -0.767559 -0.23373 0.596845 + outer loop + vertex 0.812175 1.1983 2.53521 + vertex 0.813604 1.20167 2.53837 + vertex 0.810992 1.20297 2.53552 + endloop + endfacet + facet normal -0.769979 -0.230837 0.59485 + outer loop + vertex 0.814037 1.19767 2.53738 + vertex 0.813604 1.20167 2.53837 + vertex 0.812175 1.1983 2.53521 + endloop + endfacet + facet normal -0.82963 -0.180852 0.528211 + outer loop + vertex 0.809207 1.20589 2.53372 + vertex 0.809287 1.20242 2.53265 + vertex 0.810992 1.20297 2.53552 + endloop + endfacet + facet normal -0.841026 -0.204766 0.500746 + outer loop + vertex 0.810493 1.20638 2.53608 + vertex 0.809207 1.20589 2.53372 + vertex 0.810992 1.20297 2.53552 + endloop + endfacet + facet normal -0.770386 -0.210901 0.601686 + outer loop + vertex 0.810992 1.20297 2.53552 + vertex 0.812338 1.20734 2.53877 + vertex 0.810493 1.20638 2.53608 + endloop + endfacet + facet normal -0.766824 -0.214449 0.604973 + outer loop + vertex 0.813604 1.20167 2.53837 + vertex 0.812338 1.20734 2.53877 + vertex 0.810992 1.20297 2.53552 + endloop + endfacet + facet normal -0.852734 -0.158654 0.497667 + outer loop + vertex 0.809207 1.20589 2.53372 + vertex 0.810493 1.20638 2.53608 + vertex 0.809647 1.20935 2.53558 + endloop + endfacet + facet normal -0.793751 -0.202311 0.573611 + outer loop + vertex 0.812704 1.2115 2.54068 + vertex 0.811902 1.21497 2.5408 + vertex 0.810686 1.21234 2.53819 + endloop + endfacet + facet normal -0.79377 -0.19431 0.576344 + outer loop + vertex 0.812338 1.20734 2.53877 + vertex 0.812704 1.2115 2.54068 + vertex 0.810686 1.21234 2.53819 + endloop + endfacet + facet normal -0.808518 -0.201949 0.552735 + outer loop + vertex 0.812338 1.20734 2.53877 + vertex 0.810686 1.21234 2.53819 + vertex 0.809647 1.20935 2.53558 + endloop + endfacet + facet normal -0.79717 -0.127314 0.590178 + outer loop + vertex 0.812338 1.20734 2.53877 + vertex 0.809647 1.20935 2.53558 + vertex 0.810493 1.20638 2.53608 + endloop + endfacet + facet normal -0.760968 -0.19624 0.618399 + outer loop + vertex 0.812704 1.2115 2.54068 + vertex 0.813815 1.21336 2.54264 + vertex 0.811902 1.21497 2.5408 + endloop + endfacet + facet normal -0.806756 -0.184197 0.561441 + outer loop + vertex 0.809659 1.21691 2.53821 + vertex 0.810686 1.21234 2.53819 + vertex 0.811902 1.21497 2.5408 + endloop + endfacet + facet normal -0.809056 -0.197297 0.553627 + outer loop + vertex 0.811118 1.21905 2.5411 + vertex 0.809659 1.21691 2.53821 + vertex 0.811902 1.21497 2.5408 + endloop + endfacet + facet normal -0.763774 -0.193295 0.615862 + outer loop + vertex 0.811902 1.21497 2.5408 + vertex 0.813457 1.21704 2.54338 + vertex 0.811118 1.21905 2.5411 + endloop + endfacet + facet normal -0.761258 -0.197425 0.617664 + outer loop + vertex 0.813815 1.21336 2.54264 + vertex 0.813457 1.21704 2.54338 + vertex 0.811902 1.21497 2.5408 + endloop + endfacet + facet normal -0.813623 -0.189019 0.549808 + outer loop + vertex 0.809097 1.2212 2.53885 + vertex 0.809659 1.21691 2.53821 + vertex 0.811118 1.21905 2.5411 + endloop + endfacet + facet normal -0.816095 -0.198827 0.542638 + outer loop + vertex 0.810446 1.22183 2.54111 + vertex 0.809097 1.2212 2.53885 + vertex 0.811118 1.21905 2.5411 + endloop + endfacet + facet normal -0.767651 -0.187314 0.612883 + outer loop + vertex 0.811118 1.21905 2.5411 + vertex 0.812336 1.22211 2.54357 + vertex 0.810446 1.22183 2.54111 + endloop + endfacet + facet normal -0.763453 -0.192019 0.616659 + outer loop + vertex 0.813457 1.21704 2.54338 + vertex 0.812336 1.22211 2.54357 + vertex 0.811118 1.21905 2.5411 + endloop + endfacet + facet normal -0.825076 -0.168046 0.539454 + outer loop + vertex 0.809097 1.2212 2.53885 + vertex 0.810446 1.22183 2.54111 + vertex 0.809476 1.22453 2.54047 + endloop + endfacet + facet normal -0.788726 -0.180453 0.587664 + outer loop + vertex 0.812336 1.22211 2.54357 + vertex 0.810782 1.22723 2.54305 + vertex 0.809476 1.22453 2.54047 + endloop + endfacet + facet normal -0.777678 -0.133025 0.614428 + outer loop + vertex 0.812336 1.22211 2.54357 + vertex 0.809476 1.22453 2.54047 + vertex 0.810446 1.22183 2.54111 + endloop + endfacet + facet normal -0.772666 -0.165344 0.612902 + outer loop + vertex 0.808139 1.24607 2.54461 + vertex 0.809808 1.24908 2.54752 + vertex 0.807979 1.24994 2.54545 + endloop + endfacet + facet normal -0.772376 -0.161232 0.614361 + outer loop + vertex 0.808959 1.25241 2.54733 + vertex 0.807979 1.24994 2.54545 + vertex 0.809808 1.24908 2.54752 + endloop + endfacet + facet normal -0.753384 -0.154953 0.639064 + outer loop + vertex 0.808959 1.25241 2.54733 + vertex 0.809808 1.24908 2.54752 + vertex 0.811153 1.25341 2.55016 + endloop + endfacet + facet normal -0.756117 -0.145896 0.637967 + outer loop + vertex 0.808826 1.25634 2.54807 + vertex 0.808959 1.25241 2.54733 + vertex 0.811153 1.25341 2.55016 + endloop + endfacet + facet normal -0.75689 -0.147411 0.636701 + outer loop + vertex 0.811033 1.25905 2.55132 + vertex 0.808826 1.25634 2.54807 + vertex 0.811153 1.25341 2.55016 + endloop + endfacet + facet normal -0.759601 -0.142629 0.634558 + outer loop + vertex 0.808545 1.26145 2.54888 + vertex 0.808826 1.25634 2.54807 + vertex 0.811033 1.25905 2.55132 + endloop + endfacet + facet normal -0.759186 -0.141418 0.635325 + outer loop + vertex 0.811063 1.26449 2.55257 + vertex 0.808545 1.26145 2.54888 + vertex 0.811033 1.25905 2.55132 + endloop + endfacet + facet normal -0.754784 -0.149248 0.638769 + outer loop + vertex 0.808224 1.26641 2.54966 + vertex 0.808545 1.26145 2.54888 + vertex 0.811063 1.26449 2.55257 + endloop + endfacet + facet normal -0.734225 -0.150242 0.662073 + outer loop + vertex 0.808891 1.27632 2.55289 + vertex 0.809039 1.27245 2.55217 + vertex 0.811387 1.27344 2.555 + endloop + endfacet + facet normal -0.732803 -0.147386 0.664287 + outer loop + vertex 0.811121 1.27903 2.55595 + vertex 0.808891 1.27632 2.55289 + vertex 0.811387 1.27344 2.555 + endloop + endfacet + facet normal -0.718942 -0.149194 0.678869 + outer loop + vertex 0.811387 1.27344 2.555 + vertex 0.813806 1.27662 2.55826 + vertex 0.811121 1.27903 2.55595 + endloop + endfacet + facet normal -0.686055 0.00387285 0.727539 + outer loop + vertex 0.809932 1.52377 2.57684 + vertex 0.806982 1.52102 2.57408 + vertex 0.809962 1.51872 2.5769 + endloop + endfacet + facet normal -0.685896 0.00354969 0.727691 + outer loop + vertex 0.807378 1.52635 2.57442 + vertex 0.806982 1.52102 2.57408 + vertex 0.809932 1.52377 2.57684 + endloop + endfacet + facet normal -0.77061 0.111576 0.627464 + outer loop + vertex 0.809649 1.7779 2.54707 + vertex 0.807849 1.77685 2.54505 + vertex 0.808926 1.7746 2.54677 + endloop + endfacet + facet normal -0.767374 0.0922561 0.634528 + outer loop + vertex 0.807852 1.78054 2.54451 + vertex 0.807849 1.77685 2.54505 + vertex 0.809649 1.7779 2.54707 + endloop + endfacet + facet normal -0.766654 0.0698621 0.638248 + outer loop + vertex 0.808064 1.78538 2.54424 + vertex 0.807852 1.78054 2.54451 + vertex 0.8101 1.78231 2.54702 + endloop + endfacet + facet normal -0.767326 0.0687929 0.637557 + outer loop + vertex 0.810728 1.78746 2.54722 + vertex 0.808064 1.78538 2.54424 + vertex 0.8101 1.78231 2.54702 + endloop + endfacet + facet normal -0.754605 0.0622722 0.653218 + outer loop + vertex 0.813054 1.78667 2.54998 + vertex 0.810728 1.78746 2.54722 + vertex 0.812453 1.78338 2.5496 + endloop + endfacet + facet normal -0.750961 0.0660419 0.657036 + outer loop + vertex 0.810728 1.78746 2.54722 + vertex 0.8101 1.78231 2.54702 + vertex 0.812453 1.78338 2.5496 + endloop + endfacet + facet normal -0.767705 0.0701479 0.636952 + outer loop + vertex 0.808248 1.79057 2.54389 + vertex 0.808064 1.78538 2.54424 + vertex 0.810728 1.78746 2.54722 + endloop + endfacet + facet normal -0.763158 0.0785647 0.641419 + outer loop + vertex 0.810643 1.79311 2.54643 + vertex 0.808248 1.79057 2.54389 + vertex 0.810728 1.78746 2.54722 + endloop + endfacet + facet normal -0.758577 0.0793795 0.64673 + outer loop + vertex 0.810728 1.78746 2.54722 + vertex 0.812955 1.79056 2.54945 + vertex 0.810643 1.79311 2.54643 + endloop + endfacet + facet normal -0.753087 0.0700642 0.65418 + outer loop + vertex 0.813054 1.78667 2.54998 + vertex 0.812955 1.79056 2.54945 + vertex 0.810728 1.78746 2.54722 + endloop + endfacet + facet normal -0.771551 0.0995215 0.628335 + outer loop + vertex 0.808407 1.7958 2.54326 + vertex 0.808248 1.79057 2.54389 + vertex 0.810643 1.79311 2.54643 + endloop + endfacet + facet normal -0.762659 0.156256 0.627642 + outer loop + vertex 0.811118 1.80371 2.54468 + vertex 0.808754 1.80075 2.54255 + vertex 0.810858 1.79833 2.54571 + endloop + endfacet + facet normal -0.797 0.188453 0.573826 + outer loop + vertex 0.809927 1.80771 2.54207 + vertex 0.808065 1.80684 2.53976 + vertex 0.808983 1.80449 2.54181 + endloop + endfacet + facet normal -0.768651 0.168677 0.617028 + outer loop + vertex 0.808983 1.80449 2.54181 + vertex 0.808754 1.80075 2.54255 + vertex 0.811118 1.80371 2.54468 + endloop + endfacet + facet normal -0.766607 0.176052 0.617511 + outer loop + vertex 0.808983 1.80449 2.54181 + vertex 0.811118 1.80371 2.54468 + vertex 0.809927 1.80771 2.54207 + endloop + endfacet + facet normal -0.7971 0.193541 0.57199 + outer loop + vertex 0.808417 1.81066 2.53896 + vertex 0.808065 1.80684 2.53976 + vertex 0.809927 1.80771 2.54207 + endloop + endfacet + facet normal -0.806921 0.178954 0.562898 + outer loop + vertex 0.81096 1.8124 2.54205 + vertex 0.808417 1.81066 2.53896 + vertex 0.809927 1.80771 2.54207 + endloop + endfacet + facet normal -0.767586 0.174376 0.616769 + outer loop + vertex 0.81308 1.81152 2.54494 + vertex 0.81096 1.8124 2.54205 + vertex 0.812153 1.80833 2.54469 + endloop + endfacet + facet normal -0.771018 0.171172 0.613376 + outer loop + vertex 0.81096 1.8124 2.54205 + vertex 0.809927 1.80771 2.54207 + vertex 0.812153 1.80833 2.54469 + endloop + endfacet + facet normal -0.806001 0.170773 0.566744 + outer loop + vertex 0.808979 1.81559 2.53828 + vertex 0.808417 1.81066 2.53896 + vertex 0.81096 1.8124 2.54205 + endloop + endfacet + facet normal -0.816146 0.15315 0.557181 + outer loop + vertex 0.811193 1.81792 2.54088 + vertex 0.808979 1.81559 2.53828 + vertex 0.81096 1.8124 2.54205 + endloop + endfacet + facet normal -0.766244 0.164655 0.621095 + outer loop + vertex 0.81096 1.8124 2.54205 + vertex 0.813299 1.81534 2.54416 + vertex 0.811193 1.81792 2.54088 + endloop + endfacet + facet normal -0.768846 0.170106 0.616393 + outer loop + vertex 0.81308 1.81152 2.54494 + vertex 0.813299 1.81534 2.54416 + vertex 0.81096 1.8124 2.54205 + endloop + endfacet + facet normal -0.815185 0.149586 0.559552 + outer loop + vertex 0.809357 1.82046 2.53753 + vertex 0.808979 1.81559 2.53828 + vertex 0.811193 1.81792 2.54088 + endloop + endfacet + facet normal -0.814068 0.151765 0.560589 + outer loop + vertex 0.811371 1.82345 2.53964 + vertex 0.809357 1.82046 2.53753 + vertex 0.811193 1.81792 2.54088 + endloop + endfacet + facet normal -0.761596 0.164883 0.626726 + outer loop + vertex 0.811193 1.81792 2.54088 + vertex 0.813648 1.82038 2.54321 + vertex 0.811371 1.82345 2.53964 + endloop + endfacet + facet normal -0.763314 0.169845 0.623301 + outer loop + vertex 0.813299 1.81534 2.54416 + vertex 0.813648 1.82038 2.54321 + vertex 0.811193 1.81792 2.54088 + endloop + endfacet + facet normal -0.852934 0.174926 0.491839 + outer loop + vertex 0.810271 1.82752 2.53694 + vertex 0.808809 1.82651 2.53477 + vertex 0.809484 1.82417 2.53677 + endloop + endfacet + facet normal -0.81018 0.143702 0.568294 + outer loop + vertex 0.809484 1.82417 2.53677 + vertex 0.809357 1.82046 2.53753 + vertex 0.811371 1.82345 2.53964 + endloop + endfacet + facet normal -0.806152 0.159853 0.569707 + outer loop + vertex 0.809484 1.82417 2.53677 + vertex 0.811371 1.82345 2.53964 + vertex 0.810271 1.82752 2.53694 + endloop + endfacet + facet normal -0.788582 0.177286 0.588819 + outer loop + vertex 0.810271 1.82752 2.53694 + vertex 0.811371 1.82345 2.53964 + vertex 0.812339 1.8283 2.53948 + endloop + endfacet + facet normal -0.754108 0.171925 0.633847 + outer loop + vertex 0.811371 1.82345 2.53964 + vertex 0.81399 1.82531 2.54225 + vertex 0.812339 1.8283 2.53948 + endloop + endfacet + facet normal -0.754889 0.175831 0.631843 + outer loop + vertex 0.813648 1.82038 2.54321 + vertex 0.81399 1.82531 2.54225 + vertex 0.811371 1.82345 2.53964 + endloop + endfacet + facet normal -0.853254 0.182881 0.488376 + outer loop + vertex 0.809125 1.83039 2.53387 + vertex 0.808809 1.82651 2.53477 + vertex 0.810271 1.82752 2.53694 + endloop + endfacet + facet normal -0.844609 0.196609 0.497977 + outer loop + vertex 0.811236 1.83244 2.53663 + vertex 0.809125 1.83039 2.53387 + vertex 0.810271 1.82752 2.53694 + endloop + endfacet + facet normal -0.741793 0.196552 0.641179 + outer loop + vertex 0.813433 1.83166 2.53971 + vertex 0.812339 1.8283 2.53948 + vertex 0.814374 1.82913 2.54158 + endloop + endfacet + facet normal -0.770168 0.208502 0.602801 + outer loop + vertex 0.813433 1.83166 2.53971 + vertex 0.811236 1.83244 2.53663 + vertex 0.812339 1.8283 2.53948 + endloop + endfacet + facet normal -0.788554 0.19107 0.58453 + outer loop + vertex 0.811236 1.83244 2.53663 + vertex 0.810271 1.82752 2.53694 + vertex 0.812339 1.8283 2.53948 + endloop + endfacet + facet normal -0.741418 0.188416 0.644049 + outer loop + vertex 0.814374 1.82913 2.54158 + vertex 0.812339 1.8283 2.53948 + vertex 0.81399 1.82531 2.54225 + endloop + endfacet + facet normal -0.840692 0.171492 0.513641 + outer loop + vertex 0.809495 1.83524 2.53285 + vertex 0.809125 1.83039 2.53387 + vertex 0.811236 1.83244 2.53663 + endloop + endfacet + facet normal -0.838993 0.174797 0.515302 + outer loop + vertex 0.811315 1.83839 2.53475 + vertex 0.809495 1.83524 2.53285 + vertex 0.811236 1.83244 2.53663 + endloop + endfacet + facet normal -0.772399 0.20153 0.602317 + outer loop + vertex 0.811236 1.83244 2.53663 + vertex 0.81357 1.8356 2.53857 + vertex 0.811315 1.83839 2.53475 + endloop + endfacet + facet normal -0.772305 0.201349 0.602498 + outer loop + vertex 0.813433 1.83166 2.53971 + vertex 0.81357 1.8356 2.53857 + vertex 0.811236 1.83244 2.53663 + endloop + endfacet + facet normal -0.878148 0.189078 0.439439 + outer loop + vertex 0.810236 1.84255 2.5316 + vertex 0.808939 1.84147 2.52947 + vertex 0.809542 1.83911 2.5317 + endloop + endfacet + facet normal -0.83477 0.166655 0.524771 + outer loop + vertex 0.809542 1.83911 2.5317 + vertex 0.809495 1.83524 2.53285 + vertex 0.811315 1.83839 2.53475 + endloop + endfacet + facet normal -0.830769 0.181925 0.526047 + outer loop + vertex 0.809542 1.83911 2.5317 + vertex 0.811315 1.83839 2.53475 + vertex 0.810236 1.84255 2.5316 + endloop + endfacet + facet normal -0.816279 0.198189 0.542596 + outer loop + vertex 0.810236 1.84255 2.5316 + vertex 0.811315 1.83839 2.53475 + vertex 0.81224 1.84337 2.53432 + endloop + endfacet + facet normal -0.778429 0.195804 0.596413 + outer loop + vertex 0.811315 1.83839 2.53475 + vertex 0.81383 1.8404 2.53737 + vertex 0.81224 1.84337 2.53432 + endloop + endfacet + facet normal -0.777703 0.192089 0.598565 + outer loop + vertex 0.81357 1.8356 2.53857 + vertex 0.81383 1.8404 2.53737 + vertex 0.811315 1.83839 2.53475 + endloop + endfacet + facet normal -0.878262 0.193358 0.437342 + outer loop + vertex 0.809185 1.8452 2.52832 + vertex 0.808939 1.84147 2.52947 + vertex 0.810236 1.84255 2.5316 + endloop + endfacet + facet normal -0.867696 0.21246 0.449405 + outer loop + vertex 0.811136 1.84788 2.53082 + vertex 0.809185 1.8452 2.52832 + vertex 0.810236 1.84255 2.5316 + endloop + endfacet + facet normal -0.779521 0.205523 0.591699 + outer loop + vertex 0.813359 1.84676 2.53461 + vertex 0.81224 1.84337 2.53432 + vertex 0.814222 1.8442 2.53664 + endloop + endfacet + facet normal -0.811751 0.220627 0.540725 + outer loop + vertex 0.813359 1.84676 2.53461 + vertex 0.811136 1.84788 2.53082 + vertex 0.81224 1.84337 2.53432 + endloop + endfacet + facet normal -0.815629 0.216448 0.536563 + outer loop + vertex 0.811136 1.84788 2.53082 + vertex 0.810236 1.84255 2.5316 + vertex 0.81224 1.84337 2.53432 + endloop + endfacet + facet normal -0.779428 0.194403 0.595567 + outer loop + vertex 0.814222 1.8442 2.53664 + vertex 0.81224 1.84337 2.53432 + vertex 0.81383 1.8404 2.53737 + endloop + endfacet + facet normal -0.898307 0.219841 0.380413 + outer loop + vertex 0.810076 1.85226 2.52685 + vertex 0.80887 1.8513 2.52456 + vertex 0.809359 1.84889 2.5271 + endloop + endfacet + facet normal -0.863418 0.194194 0.465615 + outer loop + vertex 0.809359 1.84889 2.5271 + vertex 0.809185 1.8452 2.52832 + vertex 0.811136 1.84788 2.53082 + endloop + endfacet + facet normal -0.856282 0.217416 0.468521 + outer loop + vertex 0.809359 1.84889 2.5271 + vertex 0.811136 1.84788 2.53082 + vertex 0.810076 1.85226 2.52685 + endloop + endfacet + facet normal -0.859123 0.213595 0.465065 + outer loop + vertex 0.810076 1.85226 2.52685 + vertex 0.811136 1.84788 2.53082 + vertex 0.811998 1.85355 2.52981 + endloop + endfacet + facet normal -0.819141 0.21911 0.530093 + outer loop + vertex 0.811136 1.84788 2.53082 + vertex 0.813688 1.85069 2.5336 + vertex 0.811998 1.85355 2.52981 + endloop + endfacet + facet normal -0.816173 0.207226 0.539369 + outer loop + vertex 0.813359 1.84676 2.53461 + vertex 0.813688 1.85069 2.5336 + vertex 0.811136 1.84788 2.53082 + endloop + endfacet + facet normal -0.897334 0.234852 0.373678 + outer loop + vertex 0.809216 1.85491 2.52312 + vertex 0.80887 1.8513 2.52456 + vertex 0.810076 1.85226 2.52685 + endloop + endfacet + facet normal -0.898776 0.232006 0.371987 + outer loop + vertex 0.810786 1.85744 2.52533 + vertex 0.809216 1.85491 2.52312 + vertex 0.810076 1.85226 2.52685 + endloop + endfacet + facet normal -0.858157 0.249022 0.448948 + outer loop + vertex 0.810076 1.85226 2.52685 + vertex 0.811998 1.85355 2.52981 + vertex 0.810786 1.85744 2.52533 + endloop + endfacet + facet normal -0.884958 0.205153 0.418045 + outer loop + vertex 0.810786 1.85744 2.52533 + vertex 0.811998 1.85355 2.52981 + vertex 0.812788 1.85813 2.52923 + endloop + endfacet + facet normal -0.836187 0.208 0.507472 + outer loop + vertex 0.811998 1.85355 2.52981 + vertex 0.814127 1.85542 2.53255 + vertex 0.812788 1.85813 2.52923 + endloop + endfacet + facet normal -0.834299 0.192336 0.516674 + outer loop + vertex 0.813688 1.85069 2.5336 + vertex 0.814127 1.85542 2.53255 + vertex 0.811998 1.85355 2.52981 + endloop + endfacet + facet normal -0.633291 0.284129 0.719871 + outer loop + vertex 0.810437 1.86294 2.52104 + vertex 0.810175 1.865 2.52 + vertex 0.81 1.86461 2.52 + endloop + endfacet + facet normal -0.710981 0.229402 0.664741 + outer loop + vertex 0.809625 1.85908 2.52151 + vertex 0.810437 1.86294 2.52104 + vertex 0.81 1.86461 2.52 + endloop + endfacet + facet normal -0.898763 0.231928 0.372067 + outer loop + vertex 0.809625 1.85908 2.52151 + vertex 0.809216 1.85491 2.52312 + vertex 0.810786 1.85744 2.52533 + endloop + endfacet + facet normal -0.898046 0.233777 0.372641 + outer loop + vertex 0.809625 1.85908 2.52151 + vertex 0.810786 1.85744 2.52533 + vertex 0.810437 1.86294 2.52104 + endloop + endfacet + facet normal -0.909094 0.218882 0.354456 + outer loop + vertex 0.810437 1.86294 2.52104 + vertex 0.810786 1.85744 2.52533 + vertex 0.812241 1.86274 2.5258 + endloop + endfacet + facet normal -0.854207 0.184761 0.485998 + outer loop + vertex 0.813678 1.86138 2.52956 + vertex 0.812788 1.85813 2.52923 + vertex 0.814358 1.85905 2.53164 + endloop + endfacet + facet normal -0.888706 0.201735 0.411709 + outer loop + vertex 0.813678 1.86138 2.52956 + vertex 0.812241 1.86274 2.5258 + vertex 0.812788 1.85813 2.52923 + endloop + endfacet + facet normal -0.884777 0.206661 0.417686 + outer loop + vertex 0.812241 1.86274 2.5258 + vertex 0.810786 1.85744 2.52533 + vertex 0.812788 1.85813 2.52923 + endloop + endfacet + facet normal -0.854168 0.176646 0.489074 + outer loop + vertex 0.814358 1.85905 2.53164 + vertex 0.812788 1.85813 2.52923 + vertex 0.814127 1.85542 2.53255 + endloop + endfacet + facet normal -0.504293 0.799229 0.326989 + outer loop + vertex 0.809255 1.86654 2.51482 + vertex 0.81 1.865 2.51973 + vertex 0.810175 1.865 2.52 + endloop + endfacet + facet normal -0.932582 0.265522 0.244518 + outer loop + vertex 0.810262 1.86819 2.51687 + vertex 0.809255 1.86654 2.51482 + vertex 0.810175 1.865 2.52 + endloop + endfacet + facet normal 0.916896 0.266704 0.296936 + outer loop + vertex 0.810175 1.865 2.52 + vertex 0.810437 1.86294 2.52104 + vertex 0.810262 1.86819 2.51687 + endloop + endfacet + facet normal -0.924542 0.217881 0.312651 + outer loop + vertex 0.810262 1.86819 2.51687 + vertex 0.810437 1.86294 2.52104 + vertex 0.811486 1.86738 2.52105 + endloop + endfacet + facet normal -0.910097 0.214359 0.354646 + outer loop + vertex 0.810437 1.86294 2.52104 + vertex 0.812241 1.86274 2.5258 + vertex 0.811486 1.86738 2.52105 + endloop + endfacet + facet normal -0.934153 0.16914 0.314246 + outer loop + vertex 0.811486 1.86738 2.52105 + vertex 0.812241 1.86274 2.5258 + vertex 0.812962 1.86824 2.52498 + endloop + endfacet + facet normal -0.89214 0.178613 0.414949 + outer loop + vertex 0.812241 1.86274 2.5258 + vertex 0.814089 1.86523 2.5287 + vertex 0.812962 1.86824 2.52498 + endloop + endfacet + facet normal -0.893423 0.1873 0.408306 + outer loop + vertex 0.813678 1.86138 2.52956 + vertex 0.814089 1.86523 2.5287 + vertex 0.812241 1.86274 2.5258 + endloop + endfacet + facet normal -0.922886 0.102643 0.371141 + outer loop + vertex 0.81 1.87259 2.515 + vertex 0.809255 1.86654 2.51482 + vertex 0.810262 1.86819 2.51687 + endloop + endfacet + facet normal -0.671261 0.255413 0.695825 + outer loop + vertex 0.81 1.87259 2.515 + vertex 0.810262 1.86819 2.51687 + vertex 0.810917 1.875 2.515 + endloop + endfacet + facet normal -0.881773 0.201759 0.426345 + outer loop + vertex 0.810917 1.875 2.515 + vertex 0.810262 1.86819 2.51687 + vertex 0.811407 1.87261 2.51714 + endloop + endfacet + facet normal -0.924012 0.219804 0.312869 + outer loop + vertex 0.810262 1.86819 2.51687 + vertex 0.811486 1.86738 2.52105 + vertex 0.811407 1.87261 2.51714 + endloop + endfacet + facet normal -0.954246 0.169587 0.246284 + outer loop + vertex 0.811407 1.87261 2.51714 + vertex 0.811486 1.86738 2.52105 + vertex 0.81234 1.87229 2.52098 + endloop + endfacet + facet normal -0.934342 0.167126 0.314761 + outer loop + vertex 0.811486 1.86738 2.52105 + vertex 0.812962 1.86824 2.52498 + vertex 0.81234 1.87229 2.52098 + endloop + endfacet + facet normal -0.947005 0.139907 0.289151 + outer loop + vertex 0.81234 1.87229 2.52098 + vertex 0.812962 1.86824 2.52498 + vertex 0.813497 1.87293 2.52446 + endloop + endfacet + facet normal -0.898114 0.148014 0.414106 + outer loop + vertex 0.812962 1.86824 2.52498 + vertex 0.81455 1.87005 2.52778 + vertex 0.813497 1.87293 2.52446 + endloop + endfacet + facet normal -0.899604 0.163472 0.404957 + outer loop + vertex 0.814089 1.86523 2.5287 + vertex 0.81455 1.87005 2.52778 + vertex 0.812962 1.86824 2.52498 + endloop + endfacet + facet normal -0.813718 0.28675 0.505607 + outer loop + vertex 0.810917 1.875 2.515 + vertex 0.811407 1.87261 2.51714 + vertex 0.812679 1.88 2.515 + endloop + endfacet + facet normal -0.983377 0.178665 0.0323942 + outer loop + vertex 0.812679 1.88 2.515 + vertex 0.811407 1.87261 2.51714 + vertex 0.812276 1.87741 2.51705 + endloop + endfacet + facet normal -0.952792 0.177179 0.246564 + outer loop + vertex 0.811407 1.87261 2.51714 + vertex 0.81234 1.87229 2.52098 + vertex 0.812276 1.87741 2.51705 + endloop + endfacet + facet normal -0.969452 0.141514 0.200341 + outer loop + vertex 0.812276 1.87741 2.51705 + vertex 0.81234 1.87229 2.52098 + vertex 0.813089 1.87752 2.52091 + endloop + endfacet + facet normal -0.905476 0.140081 0.400614 + outer loop + vertex 0.814034 1.8763 2.5245 + vertex 0.813497 1.87293 2.52446 + vertex 0.814634 1.87391 2.52669 + endloop + endfacet + facet normal -0.943046 0.147035 0.298404 + outer loop + vertex 0.814034 1.8763 2.5245 + vertex 0.813089 1.87752 2.52091 + vertex 0.813497 1.87293 2.52446 + endloop + endfacet + facet normal -0.947032 0.139578 0.28922 + outer loop + vertex 0.813089 1.87752 2.52091 + vertex 0.81234 1.87229 2.52098 + vertex 0.813497 1.87293 2.52446 + endloop + endfacet + facet normal -0.90522 0.133223 0.40352 + outer loop + vertex 0.814634 1.87391 2.52669 + vertex 0.813497 1.87293 2.52446 + vertex 0.81455 1.87005 2.52778 + endloop + endfacet + facet normal -0.992569 0.102835 -0.0650554 + outer loop + vertex 0.812679 1.88 2.515 + vertex 0.812276 1.87741 2.51705 + vertex 0.813197 1.885 2.515 + endloop + endfacet + facet normal -0.966277 0.0488378 -0.252833 + outer loop + vertex 0.813197 1.885 2.515 + vertex 0.812276 1.87741 2.51705 + vertex 0.812728 1.88248 2.51631 + endloop + endfacet + facet normal -0.972508 0.116338 0.201727 + outer loop + vertex 0.812276 1.87741 2.51705 + vertex 0.813089 1.87752 2.52091 + vertex 0.812728 1.88248 2.51631 + endloop + endfacet + facet normal -0.973395 0.113688 0.198942 + outer loop + vertex 0.812728 1.88248 2.51631 + vertex 0.813089 1.87752 2.52091 + vertex 0.813447 1.88296 2.51955 + endloop + endfacet + facet normal -0.935453 0.142265 0.323555 + outer loop + vertex 0.813089 1.87752 2.52091 + vertex 0.814297 1.88014 2.52325 + vertex 0.813447 1.88296 2.51955 + endloop + endfacet + facet normal -0.939117 0.16262 0.302678 + outer loop + vertex 0.814034 1.8763 2.5245 + vertex 0.814297 1.88014 2.52325 + vertex 0.813089 1.87752 2.52091 + endloop + endfacet + facet normal -0.994275 0.0503147 0.0942622 + outer loop + vertex 0.812723 1.885 2.51 + vertex 0.813197 1.885 2.515 + vertex 0.812976 1.89 2.51 + endloop + endfacet + facet normal -0.4736 -0.633164 -0.612215 + outer loop + vertex 0.812976 1.89 2.51 + vertex 0.813197 1.885 2.515 + vertex 0.812697 1.8881 2.51218 + endloop + endfacet + facet normal 0.673277 -0.435212 -0.597736 + outer loop + vertex 0.813197 1.885 2.515 + vertex 0.812728 1.88248 2.51631 + vertex 0.812697 1.8881 2.51218 + endloop + endfacet + facet normal -0.985835 0.0957903 0.13767 + outer loop + vertex 0.812697 1.8881 2.51218 + vertex 0.812728 1.88248 2.51631 + vertex 0.813139 1.8876 2.51569 + endloop + endfacet + facet normal -0.92998 0.145637 0.337532 + outer loop + vertex 0.813869 1.88651 2.51918 + vertex 0.813447 1.88296 2.51955 + vertex 0.814447 1.88413 2.5218 + endloop + endfacet + facet normal -0.959693 0.13939 0.244048 + outer loop + vertex 0.813869 1.88651 2.51918 + vertex 0.813139 1.8876 2.51569 + vertex 0.813447 1.88296 2.51955 + endloop + endfacet + facet normal -0.974261 0.102443 0.200801 + outer loop + vertex 0.813139 1.8876 2.51569 + vertex 0.812728 1.88248 2.51631 + vertex 0.813447 1.88296 2.51955 + endloop + endfacet + facet normal -0.930206 0.155533 0.332456 + outer loop + vertex 0.814447 1.88413 2.5218 + vertex 0.813447 1.88296 2.51955 + vertex 0.814297 1.88014 2.52325 + endloop + endfacet + facet normal -0.993996 0.0230589 -0.106958 + outer loop + vertex 0.812976 1.89 2.51 + vertex 0.812697 1.8881 2.51218 + vertex 0.813092 1.895 2.51 + endloop + endfacet + facet normal -0.997084 0.067981 0.0346744 + outer loop + vertex 0.813092 1.895 2.51 + vertex 0.812697 1.8881 2.51218 + vertex 0.813007 1.89295 2.51156 + endloop + endfacet + facet normal -0.958375 0.140622 0.248481 + outer loop + vertex 0.813508 1.89158 2.51486 + vertex 0.813139 1.8876 2.51569 + vertex 0.813901 1.8895 2.51755 + endloop + endfacet + facet normal -0.970421 0.132058 0.202098 + outer loop + vertex 0.813508 1.89158 2.51486 + vertex 0.813007 1.89295 2.51156 + vertex 0.813139 1.8876 2.51569 + endloop + endfacet + facet normal -0.987492 0.0803343 0.135671 + outer loop + vertex 0.813007 1.89295 2.51156 + vertex 0.812697 1.8881 2.51218 + vertex 0.813139 1.8876 2.51569 + endloop + endfacet + facet normal -0.958717 0.143918 0.245252 + outer loop + vertex 0.813901 1.8895 2.51755 + vertex 0.813139 1.8876 2.51569 + vertex 0.813869 1.88651 2.51918 + endloop + endfacet + facet normal -0.95951 0.17087 0.223929 + outer loop + vertex 0.813432 1.89668 2.51053 + vertex 0.813007 1.89295 2.51156 + vertex 0.813623 1.89437 2.51312 + endloop + endfacet + facet normal 0.623914 0.139902 0.768868 + outer loop + vertex 0.813432 1.89668 2.51053 + vertex 0.813345 1.9 2.51 + vertex 0.813007 1.89295 2.51156 + endloop + endfacet + facet normal -0.998654 0.0505363 0.0116608 + outer loop + vertex 0.813345 1.9 2.51 + vertex 0.813092 1.895 2.51 + vertex 0.813007 1.89295 2.51156 + endloop + endfacet + facet normal -0.959651 0.176474 0.218922 + outer loop + vertex 0.813623 1.89437 2.51312 + vertex 0.813007 1.89295 2.51156 + vertex 0.813508 1.89158 2.51486 + endloop + endfacet + facet normal -0.99696 0.0725799 0.0283219 + outer loop + vertex 0.813203 1.9 2.505 + vertex 0.813345 1.9 2.51 + vertex 0.813567 1.905 2.505 + endloop + endfacet + facet normal 0.906801 0.277275 0.317538 + outer loop + vertex 0.813567 1.905 2.505 + vertex 0.813345 1.9 2.51 + vertex 0.813808 1.90278 2.50625 + endloop + endfacet + facet normal 0.513737 0.657681 0.550935 + outer loop + vertex 0.813345 1.9 2.51 + vertex 0.813999 1.90033 2.509 + vertex 0.813808 1.90278 2.50625 + endloop + endfacet + facet normal 0.814669 0.112723 0.568865 + outer loop + vertex 0.813432 1.89668 2.51053 + vertex 0.813999 1.90033 2.509 + vertex 0.813345 1.9 2.51 + endloop + endfacet + facet normal -0.666407 0.33159 -0.667795 + outer loop + vertex 0.815 1.905 2.50357 + vertex 0.813567 1.905 2.505 + vertex 0.815 1.90788 2.505 + endloop + endfacet + facet normal -0.962068 0.250986 0.106918 + outer loop + vertex 0.815 1.90788 2.505 + vertex 0.813808 1.90278 2.50625 + vertex 0.815 1.90575 2.51 + endloop + endfacet + facet normal -0.644504 0.320691 0.694098 + outer loop + vertex 0.813567 1.905 2.505 + vertex 0.813808 1.90278 2.50625 + vertex 0.815 1.90788 2.505 + endloop + endfacet + facet normal -0.970307 0.143119 0.194991 + outer loop + vertex 0.815 1.90575 2.51 + vertex 0.813808 1.90278 2.50625 + vertex 0.813999 1.90033 2.509 + endloop + endfacet + facet normal 0.611399 0.527822 -0.589572 + outer loop + vertex 0.819721 1.11303 2.5064 + vertex 0.818256 1.11604 2.50759 + vertex 0.82 1.115 2.50846 + endloop + endfacet + facet normal -0.911171 -0.391012 -0.129913 + outer loop + vertex 0.819721 1.11303 2.5064 + vertex 0.819453 1.113 2.50836 + vertex 0.818256 1.11604 2.50759 + endloop + endfacet + facet normal -0.775053 -0.576677 -0.258336 + outer loop + vertex 0.82 1.115 2.50846 + vertex 0.817433 1.12 2.505 + vertex 0.82 1.11655 2.505 + endloop + endfacet + facet normal 0.10471 -0.528993 -0.842142 + outer loop + vertex 0.82 1.115 2.50846 + vertex 0.818256 1.11604 2.50759 + vertex 0.817433 1.12 2.505 + endloop + endfacet + facet normal -0.975748 -0.217742 -0.0224384 + outer loop + vertex 0.818256 1.11604 2.50759 + vertex 0.817318 1.12 2.51 + vertex 0.817433 1.12 2.505 + endloop + endfacet + facet normal -0.933878 -0.354106 0.0498044 + outer loop + vertex 0.818648 1.11539 2.51026 + vertex 0.818256 1.11604 2.50759 + vertex 0.819453 1.113 2.50836 + endloop + endfacet + facet normal -0.96375 -0.25498 0.0785548 + outer loop + vertex 0.818648 1.11539 2.51026 + vertex 0.817501 1.11995 2.511 + vertex 0.818256 1.11604 2.50759 + endloop + endfacet + facet normal -0.935717 -0.316707 0.15534 + outer loop + vertex 0.817501 1.11995 2.511 + vertex 0.817318 1.12 2.51 + vertex 0.818256 1.11604 2.50759 + endloop + endfacet + facet normal -0.941588 -0.269499 0.201946 + outer loop + vertex 0.818648 1.11539 2.51026 + vertex 0.818825 1.11691 2.51312 + vertex 0.817501 1.11995 2.511 + endloop + endfacet + facet normal -0.970835 -0.169896 0.16916 + outer loop + vertex 0.817318 1.12 2.51 + vertex 0.817501 1.11995 2.511 + vertex 0.816443 1.125 2.51 + endloop + endfacet + facet normal -0.970733 -0.169724 0.169919 + outer loop + vertex 0.816443 1.125 2.51 + vertex 0.817501 1.11995 2.511 + vertex 0.816617 1.12543 2.51142 + endloop + endfacet + facet normal -0.941082 -0.256144 0.220806 + outer loop + vertex 0.818435 1.11995 2.51498 + vertex 0.817501 1.11995 2.511 + vertex 0.818825 1.11691 2.51312 + endloop + endfacet + facet normal -0.954782 -0.195502 0.223988 + outer loop + vertex 0.818435 1.11995 2.51498 + vertex 0.817501 1.12505 2.51545 + vertex 0.817501 1.11995 2.511 + endloop + endfacet + facet normal -0.965643 -0.170891 0.195778 + outer loop + vertex 0.817501 1.12505 2.51545 + vertex 0.816617 1.12543 2.51142 + vertex 0.817501 1.11995 2.511 + endloop + endfacet + facet normal -0.939087 -0.197889 0.280991 + outer loop + vertex 0.818435 1.11995 2.51498 + vertex 0.818936 1.1219 2.51803 + vertex 0.817501 1.12505 2.51545 + endloop + endfacet + facet normal -0.992913 0.00813164 0.118566 + outer loop + vertex 0.816443 1.125 2.51 + vertex 0.816617 1.12543 2.51142 + vertex 0.816484 1.13 2.51 + endloop + endfacet + facet normal -0.996552 -0.00308267 0.0829192 + outer loop + vertex 0.816484 1.13 2.51 + vertex 0.816617 1.12543 2.51142 + vertex 0.8169 1.13 2.515 + endloop + endfacet + facet normal -0.973837 -0.0995371 0.204288 + outer loop + vertex 0.816617 1.12543 2.51142 + vertex 0.817501 1.12505 2.51545 + vertex 0.8169 1.13 2.515 + endloop + endfacet + facet normal -0.982239 -0.131596 -0.13375 + outer loop + vertex 0.8169 1.13 2.515 + vertex 0.817501 1.12505 2.51545 + vertex 0.816676 1.1308 2.51586 + endloop + endfacet + facet normal -0.940236 -0.207203 0.270229 + outer loop + vertex 0.81873 1.1251 2.51977 + vertex 0.817501 1.12505 2.51545 + vertex 0.818936 1.1219 2.51803 + endloop + endfacet + facet normal -0.943636 -0.190011 0.271011 + outer loop + vertex 0.81873 1.1251 2.51977 + vertex 0.817756 1.12971 2.5196 + vertex 0.817501 1.12505 2.51545 + endloop + endfacet + facet normal -0.960504 -0.154047 0.231735 + outer loop + vertex 0.817756 1.12971 2.5196 + vertex 0.816676 1.1308 2.51586 + vertex 0.817501 1.12505 2.51545 + endloop + endfacet + facet normal -0.922217 -0.183027 0.340611 + outer loop + vertex 0.81873 1.1251 2.51977 + vertex 0.819366 1.12733 2.52269 + vertex 0.817756 1.12971 2.5196 + endloop + endfacet + facet normal -0.982134 -0.116682 -0.147642 + outer loop + vertex 0.8169 1.13 2.515 + vertex 0.816676 1.1308 2.51586 + vertex 0.816306 1.135 2.515 + endloop + endfacet + facet normal -0.996131 -0.080768 0.0346305 + outer loop + vertex 0.816306 1.135 2.515 + vertex 0.816676 1.1308 2.51586 + vertex 0.81641 1.13464 2.51714 + endloop + endfacet + facet normal -0.961211 -0.145136 0.23454 + outer loop + vertex 0.816676 1.1308 2.51586 + vertex 0.817756 1.12971 2.5196 + vertex 0.81641 1.13464 2.51714 + endloop + endfacet + facet normal -0.963213 -0.152207 0.221481 + outer loop + vertex 0.81641 1.13464 2.51714 + vertex 0.817756 1.12971 2.5196 + vertex 0.817325 1.13533 2.52159 + endloop + endfacet + facet normal -0.927575 -0.185762 0.324188 + outer loop + vertex 0.817756 1.12971 2.5196 + vertex 0.818996 1.13146 2.52416 + vertex 0.817325 1.13533 2.52159 + endloop + endfacet + facet normal -0.923226 -0.199608 0.328345 + outer loop + vertex 0.819366 1.12733 2.52269 + vertex 0.818996 1.13146 2.52416 + vertex 0.817756 1.12971 2.5196 + endloop + endfacet + facet normal -0.99484 -0.0962985 0.0319454 + outer loop + vertex 0.816306 1.135 2.515 + vertex 0.81641 1.13464 2.51714 + vertex 0.815822 1.14 2.515 + endloop + endfacet + facet normal -0.994365 -0.105685 0.00828904 + outer loop + vertex 0.815822 1.14 2.515 + vertex 0.81641 1.13464 2.51714 + vertex 0.816027 1.13833 2.51833 + endloop + endfacet + facet normal -0.959393 -0.171797 0.223722 + outer loop + vertex 0.81641 1.13464 2.51714 + vertex 0.817325 1.13533 2.52159 + vertex 0.816027 1.13833 2.51833 + endloop + endfacet + facet normal -0.959568 -0.178221 0.21787 + outer loop + vertex 0.816027 1.13833 2.51833 + vertex 0.817325 1.13533 2.52159 + vertex 0.816401 1.13972 2.52112 + endloop + endfacet + facet normal -0.929174 -0.191967 0.315888 + outer loop + vertex 0.818593 1.13533 2.52532 + vertex 0.817325 1.13533 2.52159 + vertex 0.818996 1.13146 2.52416 + endloop + endfacet + facet normal -0.933801 -0.165072 0.317437 + outer loop + vertex 0.818593 1.13533 2.52532 + vertex 0.817707 1.13941 2.52484 + vertex 0.817325 1.13533 2.52159 + endloop + endfacet + facet normal -0.935134 -0.162764 0.314693 + outer loop + vertex 0.817707 1.13941 2.52484 + vertex 0.816401 1.13972 2.52112 + vertex 0.817325 1.13533 2.52159 + endloop + endfacet + facet normal -0.905418 -0.149415 0.397358 + outer loop + vertex 0.818593 1.13533 2.52532 + vertex 0.819202 1.13743 2.5275 + vertex 0.817707 1.13941 2.52484 + endloop + endfacet + facet normal 0.749079 0.245311 -0.615388 + outer loop + vertex 0.814326 1.14286 2.51432 + vertex 0.815 1.14251 2.515 + vertex 0.815822 1.14 2.515 + endloop + endfacet + facet normal -0.88796 -0.419721 0.188048 + outer loop + vertex 0.814326 1.14286 2.51432 + vertex 0.815822 1.14 2.515 + vertex 0.815073 1.14301 2.51819 + endloop + endfacet + facet normal -0.978864 -0.200521 -0.0402062 + outer loop + vertex 0.815073 1.14301 2.51819 + vertex 0.815822 1.14 2.515 + vertex 0.816027 1.13833 2.51833 + endloop + endfacet + facet normal -0.956631 -0.18811 0.222422 + outer loop + vertex 0.816027 1.13833 2.51833 + vertex 0.816401 1.13972 2.52112 + vertex 0.815073 1.14301 2.51819 + endloop + endfacet + facet normal -0.952986 -0.150568 0.262959 + outer loop + vertex 0.815073 1.14301 2.51819 + vertex 0.816401 1.13972 2.52112 + vertex 0.816309 1.14293 2.52263 + endloop + endfacet + facet normal -0.933666 -0.173587 0.313265 + outer loop + vertex 0.816401 1.13972 2.52112 + vertex 0.817707 1.13941 2.52484 + vertex 0.816309 1.14293 2.52263 + endloop + endfacet + facet normal -0.924007 -0.14401 0.354221 + outer loop + vertex 0.816309 1.14293 2.52263 + vertex 0.817707 1.13941 2.52484 + vertex 0.817466 1.14479 2.5264 + endloop + endfacet + facet normal -0.896556 -0.159832 0.413087 + outer loop + vertex 0.817707 1.13941 2.52484 + vertex 0.819137 1.14094 2.52853 + vertex 0.817466 1.14479 2.5264 + endloop + endfacet + facet normal -0.903614 -0.136282 0.406089 + outer loop + vertex 0.819202 1.13743 2.5275 + vertex 0.819137 1.14094 2.52853 + vertex 0.817707 1.13941 2.52484 + endloop + endfacet + facet normal -0.939629 -0.282855 0.192587 + outer loop + vertex 0.814326 1.14286 2.51432 + vertex 0.815073 1.14301 2.51819 + vertex 0.813674 1.1457 2.51531 + endloop + endfacet + facet normal -0.942116 -0.243314 0.230683 + outer loop + vertex 0.813923 1.14748 2.51821 + vertex 0.813674 1.1457 2.51531 + vertex 0.815073 1.14301 2.51819 + endloop + endfacet + facet normal -0.923273 -0.238656 0.301015 + outer loop + vertex 0.813923 1.14748 2.51821 + vertex 0.815073 1.14301 2.51819 + vertex 0.815256 1.14777 2.52252 + endloop + endfacet + facet normal -0.944692 -0.200249 0.259726 + outer loop + vertex 0.815256 1.14777 2.52252 + vertex 0.815073 1.14301 2.51819 + vertex 0.816309 1.14293 2.52263 + endloop + endfacet + facet normal -0.908512 -0.190012 0.372158 + outer loop + vertex 0.816309 1.14293 2.52263 + vertex 0.817466 1.14479 2.5264 + vertex 0.815256 1.14777 2.52252 + endloop + endfacet + facet normal -0.908651 -0.191654 0.370975 + outer loop + vertex 0.815256 1.14777 2.52252 + vertex 0.817466 1.14479 2.5264 + vertex 0.81656 1.14862 2.52616 + endloop + endfacet + facet normal -0.879996 -0.128141 0.457369 + outer loop + vertex 0.8196 1.14445 2.53041 + vertex 0.817466 1.14479 2.5264 + vertex 0.819137 1.14094 2.52853 + endloop + endfacet + facet normal -0.873713 -0.187309 0.448932 + outer loop + vertex 0.8196 1.14445 2.53041 + vertex 0.818059 1.14928 2.52942 + vertex 0.817466 1.14479 2.5264 + endloop + endfacet + facet normal -0.879717 -0.180441 0.439931 + outer loop + vertex 0.818059 1.14928 2.52942 + vertex 0.81656 1.14862 2.52616 + vertex 0.817466 1.14479 2.5264 + endloop + endfacet + facet normal -0.841957 -0.163909 0.514045 + outer loop + vertex 0.8196 1.14445 2.53041 + vertex 0.820625 1.1475 2.53306 + vertex 0.818059 1.14928 2.52942 + endloop + endfacet + facet normal -0.918699 -0.255994 0.300765 + outer loop + vertex 0.813923 1.14748 2.51821 + vertex 0.815256 1.14777 2.52252 + vertex 0.81357 1.15046 2.51966 + endloop + endfacet + facet normal -0.918234 -0.242799 0.312881 + outer loop + vertex 0.814054 1.15225 2.52247 + vertex 0.81357 1.15046 2.51966 + vertex 0.815256 1.14777 2.52252 + endloop + endfacet + facet normal -0.891884 -0.234895 0.38648 + outer loop + vertex 0.814054 1.15225 2.52247 + vertex 0.815256 1.14777 2.52252 + vertex 0.815642 1.15241 2.52624 + endloop + endfacet + facet normal -0.899036 -0.225428 0.375388 + outer loop + vertex 0.815642 1.15241 2.52624 + vertex 0.815256 1.14777 2.52252 + vertex 0.81656 1.14862 2.52616 + endloop + endfacet + facet normal -0.869202 -0.219612 0.443011 + outer loop + vertex 0.81656 1.14862 2.52616 + vertex 0.818059 1.14928 2.52942 + vertex 0.815642 1.15241 2.52624 + endloop + endfacet + facet normal -0.867948 -0.212805 0.448753 + outer loop + vertex 0.815642 1.15241 2.52624 + vertex 0.818059 1.14928 2.52942 + vertex 0.817248 1.15464 2.5304 + endloop + endfacet + facet normal -0.829983 -0.218756 0.513103 + outer loop + vertex 0.818059 1.14928 2.52942 + vertex 0.819605 1.15216 2.53315 + vertex 0.817248 1.15464 2.5304 + endloop + endfacet + facet normal -0.843732 -0.194714 0.500203 + outer loop + vertex 0.820625 1.1475 2.53306 + vertex 0.819605 1.15216 2.53315 + vertex 0.818059 1.14928 2.52942 + endloop + endfacet + facet normal -0.891681 -0.235745 0.386431 + outer loop + vertex 0.813706 1.15617 2.52406 + vertex 0.814054 1.15225 2.52247 + vertex 0.815642 1.15241 2.52624 + endloop + endfacet + facet normal -0.891112 -0.234121 0.388726 + outer loop + vertex 0.81507 1.15785 2.5282 + vertex 0.813706 1.15617 2.52406 + vertex 0.815642 1.15241 2.52624 + endloop + endfacet + facet normal -0.847506 -0.256898 0.464475 + outer loop + vertex 0.815642 1.15241 2.52624 + vertex 0.817248 1.15464 2.5304 + vertex 0.81507 1.15785 2.5282 + endloop + endfacet + facet normal -0.842182 -0.241042 0.482316 + outer loop + vertex 0.81507 1.15785 2.5282 + vertex 0.817248 1.15464 2.5304 + vertex 0.81668 1.15865 2.53141 + endloop + endfacet + facet normal -0.808326 -0.249161 0.533411 + outer loop + vertex 0.817248 1.15464 2.5304 + vertex 0.818772 1.157 2.53381 + vertex 0.81668 1.15865 2.53141 + endloop + endfacet + facet normal -0.828823 -0.212804 0.517462 + outer loop + vertex 0.819605 1.15216 2.53315 + vertex 0.818772 1.157 2.53381 + vertex 0.817248 1.15464 2.5304 + endloop + endfacet + facet normal -0.892225 -0.231212 0.387911 + outer loop + vertex 0.813706 1.15617 2.52406 + vertex 0.81507 1.15785 2.5282 + vertex 0.813407 1.16005 2.52569 + endloop + endfacet + facet normal -0.892553 -0.234772 0.385008 + outer loop + vertex 0.814093 1.1616 2.52822 + vertex 0.813407 1.16005 2.52569 + vertex 0.81507 1.15785 2.5282 + endloop + endfacet + facet normal -0.864824 -0.227847 0.447399 + outer loop + vertex 0.814093 1.1616 2.52822 + vertex 0.81507 1.15785 2.5282 + vertex 0.815437 1.161 2.53051 + endloop + endfacet + facet normal -0.836462 -0.257746 0.48363 + outer loop + vertex 0.815437 1.161 2.53051 + vertex 0.81507 1.15785 2.5282 + vertex 0.81668 1.15865 2.53141 + endloop + endfacet + facet normal -0.812485 -0.224042 0.538213 + outer loop + vertex 0.81668 1.15865 2.53141 + vertex 0.817271 1.16231 2.53383 + vertex 0.815437 1.161 2.53051 + endloop + endfacet + facet normal -0.806292 -0.229612 0.545135 + outer loop + vertex 0.818772 1.157 2.53381 + vertex 0.817271 1.16231 2.53383 + vertex 0.81668 1.15865 2.53141 + endloop + endfacet + facet normal -0.868325 -0.181759 0.461493 + outer loop + vertex 0.814093 1.1616 2.52822 + vertex 0.815437 1.161 2.53051 + vertex 0.814589 1.1643 2.53022 + endloop + endfacet + facet normal -0.830178 -0.153678 0.535898 + outer loop + vertex 0.817444 1.16627 2.53566 + vertex 0.816785 1.16974 2.53563 + vertex 0.815582 1.16715 2.53303 + endloop + endfacet + facet normal -0.830061 -0.203986 0.519026 + outer loop + vertex 0.817271 1.16231 2.53383 + vertex 0.817444 1.16627 2.53566 + vertex 0.815582 1.16715 2.53303 + endloop + endfacet + facet normal -0.836562 -0.20828 0.506739 + outer loop + vertex 0.817271 1.16231 2.53383 + vertex 0.815582 1.16715 2.53303 + vertex 0.814589 1.1643 2.53022 + endloop + endfacet + facet normal -0.833231 -0.166992 0.527106 + outer loop + vertex 0.817271 1.16231 2.53383 + vertex 0.814589 1.1643 2.53022 + vertex 0.815437 1.161 2.53051 + endloop + endfacet + facet normal -0.797515 -0.147081 0.585096 + outer loop + vertex 0.817444 1.16627 2.53566 + vertex 0.818563 1.16813 2.53765 + vertex 0.816785 1.16974 2.53563 + endloop + endfacet + facet normal -0.854245 -0.113691 0.507287 + outer loop + vertex 0.814805 1.17182 2.53276 + vertex 0.815582 1.16715 2.53303 + vertex 0.816785 1.16974 2.53563 + endloop + endfacet + facet normal -0.846143 -0.0786412 0.527123 + outer loop + vertex 0.81641 1.17421 2.5357 + vertex 0.814805 1.17182 2.53276 + vertex 0.816785 1.16974 2.53563 + endloop + endfacet + facet normal -0.807431 -0.0762368 0.585015 + outer loop + vertex 0.816785 1.16974 2.53563 + vertex 0.818564 1.17194 2.53838 + vertex 0.81641 1.17421 2.5357 + endloop + endfacet + facet normal -0.789018 -0.114305 0.603643 + outer loop + vertex 0.818563 1.16813 2.53765 + vertex 0.818564 1.17194 2.53838 + vertex 0.816785 1.16974 2.53563 + endloop + endfacet + facet normal -0.854138 -0.0602938 0.51654 + outer loop + vertex 0.814471 1.17677 2.53279 + vertex 0.814805 1.17182 2.53276 + vertex 0.81641 1.17421 2.5357 + endloop + endfacet + facet normal -0.850273 -0.0487768 0.524077 + outer loop + vertex 0.816182 1.17912 2.53579 + vertex 0.814471 1.17677 2.53279 + vertex 0.81641 1.17421 2.5357 + endloop + endfacet + facet normal -0.82167 -0.0482237 0.567919 + outer loop + vertex 0.81641 1.17421 2.5357 + vertex 0.818267 1.17678 2.5386 + vertex 0.816182 1.17912 2.53579 + endloop + endfacet + facet normal -0.807715 -0.077103 0.584509 + outer loop + vertex 0.818564 1.17194 2.53838 + vertex 0.818267 1.17678 2.5386 + vertex 0.81641 1.17421 2.5357 + endloop + endfacet + facet normal -0.848883 -0.0522329 0.525994 + outer loop + vertex 0.814277 1.18172 2.53297 + vertex 0.814471 1.17677 2.53279 + vertex 0.816182 1.17912 2.53579 + endloop + endfacet + facet normal -0.851122 -0.0585036 0.521699 + outer loop + vertex 0.816078 1.18414 2.53618 + vertex 0.814277 1.18172 2.53297 + vertex 0.816182 1.17912 2.53579 + endloop + endfacet + facet normal -0.818367 -0.0617122 0.571373 + outer loop + vertex 0.816182 1.17912 2.53579 + vertex 0.818161 1.18162 2.53889 + vertex 0.816078 1.18414 2.53618 + endloop + endfacet + facet normal -0.822796 -0.0515476 0.565994 + outer loop + vertex 0.818267 1.17678 2.5386 + vertex 0.818161 1.18162 2.53889 + vertex 0.816182 1.17912 2.53579 + endloop + endfacet + facet normal -0.83452 -0.0980683 0.54218 + outer loop + vertex 0.814098 1.1866 2.53358 + vertex 0.814277 1.18172 2.53297 + vertex 0.816078 1.18414 2.53618 + endloop + endfacet + facet normal -0.839402 -0.113191 0.531594 + outer loop + vertex 0.816001 1.18956 2.53721 + vertex 0.814098 1.1866 2.53358 + vertex 0.816078 1.18414 2.53618 + endloop + endfacet + facet normal -0.801156 -0.122963 0.585687 + outer loop + vertex 0.816078 1.18414 2.53618 + vertex 0.818132 1.18648 2.53948 + vertex 0.816001 1.18956 2.53721 + endloop + endfacet + facet normal -0.822609 -0.0733002 0.563863 + outer loop + vertex 0.818161 1.18162 2.53889 + vertex 0.818132 1.18648 2.53948 + vertex 0.816078 1.18414 2.53618 + endloop + endfacet + facet normal -0.809528 -0.169696 0.56202 + outer loop + vertex 0.813631 1.19127 2.53431 + vertex 0.814098 1.1866 2.53358 + vertex 0.816001 1.18956 2.53721 + endloop + endfacet + facet normal -0.811523 -0.186582 0.553731 + outer loop + vertex 0.815038 1.19437 2.53742 + vertex 0.813631 1.19127 2.53431 + vertex 0.816001 1.18956 2.53721 + endloop + endfacet + facet normal -0.801441 -0.123535 0.585177 + outer loop + vertex 0.818041 1.19039 2.54018 + vertex 0.816001 1.18956 2.53721 + vertex 0.818132 1.18648 2.53948 + endloop + endfacet + facet normal -0.787454 -0.177053 0.590398 + outer loop + vertex 0.818041 1.19039 2.54018 + vertex 0.817186 1.19379 2.54006 + vertex 0.816001 1.18956 2.53721 + endloop + endfacet + facet normal -0.78191 -0.182449 0.596094 + outer loop + vertex 0.817186 1.19379 2.54006 + vertex 0.815038 1.19437 2.53742 + vertex 0.816001 1.18956 2.53721 + endloop + endfacet + facet normal -0.767815 -0.171151 0.617387 + outer loop + vertex 0.818041 1.19039 2.54018 + vertex 0.81907 1.19278 2.54212 + vertex 0.817186 1.19379 2.54006 + endloop + endfacet + facet normal -0.784442 -0.223679 0.578462 + outer loop + vertex 0.813631 1.19127 2.53431 + vertex 0.815038 1.19437 2.53742 + vertex 0.813211 1.19503 2.5352 + endloop + endfacet + facet normal -0.78415 -0.230468 0.576188 + outer loop + vertex 0.814037 1.19767 2.53738 + vertex 0.813211 1.19503 2.5352 + vertex 0.815038 1.19437 2.53742 + endloop + endfacet + facet normal -0.763455 -0.223849 0.605828 + outer loop + vertex 0.814037 1.19767 2.53738 + vertex 0.815038 1.19437 2.53742 + vertex 0.81617 1.19867 2.54044 + endloop + endfacet + facet normal -0.7806 -0.207862 0.589454 + outer loop + vertex 0.81617 1.19867 2.54044 + vertex 0.815038 1.19437 2.53742 + vertex 0.817186 1.19379 2.54006 + endloop + endfacet + facet normal -0.760272 -0.232678 0.606504 + outer loop + vertex 0.813604 1.20167 2.53837 + vertex 0.814037 1.19767 2.53738 + vertex 0.81617 1.19867 2.54044 + endloop + endfacet + facet normal -0.752553 -0.212566 0.623281 + outer loop + vertex 0.812338 1.20734 2.53877 + vertex 0.813604 1.20167 2.53837 + vertex 0.816022 1.20467 2.54231 + endloop + endfacet + facet normal -0.752748 -0.213634 0.62268 + outer loop + vertex 0.814784 1.20988 2.5426 + vertex 0.812338 1.20734 2.53877 + vertex 0.816022 1.20467 2.54231 + endloop + endfacet + facet normal -0.737366 -0.196705 0.646219 + outer loop + vertex 0.819221 1.20455 2.54593 + vertex 0.816022 1.20467 2.54231 + vertex 0.818518 1.20113 2.54408 + endloop + endfacet + facet normal -0.736565 -0.202607 0.645308 + outer loop + vertex 0.819221 1.20455 2.54593 + vertex 0.817705 1.20873 2.54551 + vertex 0.816022 1.20467 2.54231 + endloop + endfacet + facet normal -0.729761 -0.209711 0.650746 + outer loop + vertex 0.817705 1.20873 2.54551 + vertex 0.814784 1.20988 2.5426 + vertex 0.816022 1.20467 2.54231 + endloop + endfacet + facet normal -0.749004 -0.220458 0.624813 + outer loop + vertex 0.812338 1.20734 2.53877 + vertex 0.814784 1.20988 2.5426 + vertex 0.812704 1.2115 2.54068 + endloop + endfacet + facet normal -0.747729 -0.214617 0.628364 + outer loop + vertex 0.813815 1.21336 2.54264 + vertex 0.812704 1.2115 2.54068 + vertex 0.814784 1.20988 2.5426 + endloop + endfacet + facet normal -0.725898 -0.208844 0.65533 + outer loop + vertex 0.813815 1.21336 2.54264 + vertex 0.814784 1.20988 2.5426 + vertex 0.81614 1.21379 2.54535 + endloop + endfacet + facet normal -0.729609 -0.205416 0.652284 + outer loop + vertex 0.81614 1.21379 2.54535 + vertex 0.814784 1.20988 2.5426 + vertex 0.817705 1.20873 2.54551 + endloop + endfacet + facet normal -0.727598 -0.201736 0.65567 + outer loop + vertex 0.813457 1.21704 2.54338 + vertex 0.813815 1.21336 2.54264 + vertex 0.81614 1.21379 2.54535 + endloop + endfacet + facet normal -0.72816 -0.202771 0.654727 + outer loop + vertex 0.815342 1.21905 2.54609 + vertex 0.813457 1.21704 2.54338 + vertex 0.81614 1.21379 2.54535 + endloop + endfacet + facet normal -0.736944 -0.187392 0.64946 + outer loop + vertex 0.812336 1.22211 2.54357 + vertex 0.813457 1.21704 2.54338 + vertex 0.815342 1.21905 2.54609 + endloop + endfacet + facet normal -0.743252 -0.203672 0.637256 + outer loop + vertex 0.814613 1.22222 2.54626 + vertex 0.812336 1.22211 2.54357 + vertex 0.815342 1.21905 2.54609 + endloop + endfacet + facet normal -0.746802 -0.182878 0.639408 + outer loop + vertex 0.812336 1.22211 2.54357 + vertex 0.814613 1.22222 2.54626 + vertex 0.813722 1.22522 2.54607 + endloop + endfacet + facet normal -0.680143 -0.0655931 0.730139 + outer loop + vertex 0.814507 1.4079 2.57659 + vertex 0.812494 1.40702 2.57463 + vertex 0.814985 1.40412 2.5767 + endloop + endfacet + facet normal -0.680553 -0.0641106 0.729889 + outer loop + vertex 0.812494 1.40702 2.57463 + vertex 0.814507 1.4079 2.57659 + vertex 0.812908 1.41024 2.5753 + endloop + endfacet + facet normal -0.692772 0.141514 0.707136 + outer loop + vertex 0.817287 1.7523 2.56048 + vertex 0.819094 1.75403 2.56191 + vertex 0.817228 1.75566 2.55975 + endloop + endfacet + facet normal -0.746991 0.0607607 0.662051 + outer loop + vertex 0.814949 1.7877 2.55204 + vertex 0.816654 1.78366 2.55434 + vertex 0.817275 1.78845 2.5546 + endloop + endfacet + facet normal -0.737888 0.0590179 0.672338 + outer loop + vertex 0.816654 1.78366 2.55434 + vertex 0.819305 1.78552 2.55708 + vertex 0.817275 1.78845 2.5546 + endloop + endfacet + facet normal -0.737881 0.058992 0.672348 + outer loop + vertex 0.819304 1.7808 2.5575 + vertex 0.819305 1.78552 2.55708 + vertex 0.816654 1.78366 2.55434 + endloop + endfacet + facet normal -0.75116 0.07041 0.656355 + outer loop + vertex 0.812955 1.79056 2.54945 + vertex 0.813054 1.78667 2.54998 + vertex 0.814949 1.7877 2.55204 + endloop + endfacet + facet normal -0.74275 0.0835123 0.664341 + outer loop + vertex 0.815651 1.79265 2.5522 + vertex 0.812955 1.79056 2.54945 + vertex 0.814949 1.7877 2.55204 + endloop + endfacet + facet normal -0.735439 0.0859209 0.672121 + outer loop + vertex 0.818121 1.79183 2.55509 + vertex 0.817275 1.78845 2.5546 + vertex 0.819326 1.78927 2.55674 + endloop + endfacet + facet normal -0.744051 0.089539 0.662096 + outer loop + vertex 0.818121 1.79183 2.55509 + vertex 0.815651 1.79265 2.5522 + vertex 0.817275 1.78845 2.5546 + endloop + endfacet + facet normal -0.74913 0.0846621 0.65699 + outer loop + vertex 0.815651 1.79265 2.5522 + vertex 0.814949 1.7877 2.55204 + vertex 0.817275 1.78845 2.5546 + endloop + endfacet + facet normal -0.732879 0.0665117 0.6771 + outer loop + vertex 0.819326 1.78927 2.55674 + vertex 0.817275 1.78845 2.5546 + vertex 0.819305 1.78552 2.55708 + endloop + endfacet + facet normal -0.765769 0.220093 0.604282 + outer loop + vertex 0.815928 1.84766 2.53754 + vertex 0.813359 1.84676 2.53461 + vertex 0.814222 1.8442 2.53664 + endloop + endfacet + facet normal -0.765779 0.219738 0.604398 + outer loop + vertex 0.813688 1.85069 2.5336 + vertex 0.813359 1.84676 2.53461 + vertex 0.815928 1.84766 2.53754 + endloop + endfacet + facet normal -0.783356 0.190298 0.591726 + outer loop + vertex 0.816071 1.85306 2.53599 + vertex 0.813688 1.85069 2.5336 + vertex 0.815928 1.84766 2.53754 + endloop + endfacet + facet normal -0.786842 0.202666 0.582929 + outer loop + vertex 0.814127 1.85542 2.53255 + vertex 0.813688 1.85069 2.5336 + vertex 0.816071 1.85306 2.53599 + endloop + endfacet + facet normal -0.794413 0.188368 0.57743 + outer loop + vertex 0.81631 1.85839 2.53459 + vertex 0.814127 1.85542 2.53255 + vertex 0.816071 1.85306 2.53599 + endloop + endfacet + facet normal -0.838056 0.206472 0.505006 + outer loop + vertex 0.815269 1.86235 2.53181 + vertex 0.813678 1.86138 2.52956 + vertex 0.814358 1.85905 2.53164 + endloop + endfacet + facet normal -0.796902 0.19378 0.572186 + outer loop + vertex 0.814358 1.85905 2.53164 + vertex 0.814127 1.85542 2.53255 + vertex 0.81631 1.85839 2.53459 + endloop + endfacet + facet normal -0.797401 0.191956 0.572106 + outer loop + vertex 0.814358 1.85905 2.53164 + vertex 0.81631 1.85839 2.53459 + vertex 0.815269 1.86235 2.53181 + endloop + endfacet + facet normal -0.790594 0.198719 0.579199 + outer loop + vertex 0.815269 1.86235 2.53181 + vertex 0.81631 1.85839 2.53459 + vertex 0.817361 1.86316 2.53438 + endloop + endfacet + facet normal -0.83802 0.203428 0.5063 + outer loop + vertex 0.814089 1.86523 2.5287 + vertex 0.813678 1.86138 2.52956 + vertex 0.815269 1.86235 2.53181 + endloop + endfacet + facet normal -0.835776 0.206853 0.508617 + outer loop + vertex 0.816308 1.86725 2.53152 + vertex 0.814089 1.86523 2.5287 + vertex 0.815269 1.86235 2.53181 + endloop + endfacet + facet normal -0.754885 0.207111 0.622298 + outer loop + vertex 0.818478 1.86652 2.53462 + vertex 0.817361 1.86316 2.53438 + vertex 0.819355 1.86407 2.5365 + endloop + endfacet + facet normal -0.77525 0.215921 0.593604 + outer loop + vertex 0.818478 1.86652 2.53462 + vertex 0.816308 1.86725 2.53152 + vertex 0.817361 1.86316 2.53438 + endloop + endfacet + facet normal -0.790555 0.201308 0.578358 + outer loop + vertex 0.816308 1.86725 2.53152 + vertex 0.815269 1.86235 2.53181 + vertex 0.817361 1.86316 2.53438 + endloop + endfacet + facet normal -0.754537 0.199933 0.625061 + outer loop + vertex 0.819355 1.86407 2.5365 + vertex 0.817361 1.86316 2.53438 + vertex 0.81893 1.8603 2.53719 + endloop + endfacet + facet normal -0.831952 0.179906 0.524871 + outer loop + vertex 0.81455 1.87005 2.52778 + vertex 0.814089 1.86523 2.5287 + vertex 0.816308 1.86725 2.53152 + endloop + endfacet + facet normal -0.82982 0.1839 0.526858 + outer loop + vertex 0.816439 1.87317 2.52966 + vertex 0.81455 1.87005 2.52778 + vertex 0.816308 1.86725 2.53152 + endloop + endfacet + facet normal -0.774806 0.205044 0.598024 + outer loop + vertex 0.816308 1.86725 2.53152 + vertex 0.818655 1.87043 2.53347 + vertex 0.816439 1.87317 2.52966 + endloop + endfacet + facet normal -0.777127 0.209581 0.593422 + outer loop + vertex 0.818478 1.86652 2.53462 + vertex 0.818655 1.87043 2.53347 + vertex 0.816308 1.86725 2.53152 + endloop + endfacet + facet normal -0.866254 0.201735 0.457063 + outer loop + vertex 0.815368 1.87739 2.52655 + vertex 0.814034 1.8763 2.5245 + vertex 0.814634 1.87391 2.52669 + endloop + endfacet + facet normal -0.822829 0.170437 0.542128 + outer loop + vertex 0.814634 1.87391 2.52669 + vertex 0.81455 1.87005 2.52778 + vertex 0.816439 1.87317 2.52966 + endloop + endfacet + facet normal -0.816101 0.194727 0.544114 + outer loop + vertex 0.814634 1.87391 2.52669 + vertex 0.816439 1.87317 2.52966 + vertex 0.815368 1.87739 2.52655 + endloop + endfacet + facet normal -0.804671 0.206804 0.55654 + outer loop + vertex 0.815368 1.87739 2.52655 + vertex 0.816439 1.87317 2.52966 + vertex 0.817398 1.87816 2.52919 + endloop + endfacet + facet normal -0.773757 0.204872 0.599439 + outer loop + vertex 0.816439 1.87317 2.52966 + vertex 0.818979 1.87517 2.53226 + vertex 0.817398 1.87816 2.52919 + endloop + endfacet + facet normal -0.774044 0.206388 0.598548 + outer loop + vertex 0.818655 1.87043 2.53347 + vertex 0.818979 1.87517 2.53226 + vertex 0.816439 1.87317 2.52966 + endloop + endfacet + facet normal -0.866418 0.20686 0.454455 + outer loop + vertex 0.814297 1.88014 2.52325 + vertex 0.814034 1.8763 2.5245 + vertex 0.815368 1.87739 2.52655 + endloop + endfacet + facet normal -0.860214 0.217413 0.461264 + outer loop + vertex 0.81626 1.88292 2.5256 + vertex 0.814297 1.88014 2.52325 + vertex 0.815368 1.87739 2.52655 + endloop + endfacet + facet normal -0.773171 0.210747 0.598158 + outer loop + vertex 0.818535 1.88155 2.52947 + vertex 0.817398 1.87816 2.52919 + vertex 0.81941 1.87895 2.53152 + endloop + endfacet + facet normal -0.803082 0.224536 0.551945 + outer loop + vertex 0.818535 1.88155 2.52947 + vertex 0.81626 1.88292 2.5256 + vertex 0.817398 1.87816 2.52919 + endloop + endfacet + facet normal -0.803933 0.223664 0.55106 + outer loop + vertex 0.81626 1.88292 2.5256 + vertex 0.815368 1.87739 2.52655 + vertex 0.817398 1.87816 2.52919 + endloop + endfacet + facet normal -0.773188 0.205653 0.599906 + outer loop + vertex 0.81941 1.87895 2.53152 + vertex 0.817398 1.87816 2.52919 + vertex 0.818979 1.87517 2.53226 + endloop + endfacet + facet normal -0.895963 0.211955 0.390289 + outer loop + vertex 0.815066 1.88826 2.52098 + vertex 0.813869 1.88651 2.51918 + vertex 0.814447 1.88413 2.5218 + endloop + endfacet + facet normal -0.856598 0.204157 0.473877 + outer loop + vertex 0.814447 1.88413 2.5218 + vertex 0.814297 1.88014 2.52325 + vertex 0.81626 1.88292 2.5256 + endloop + endfacet + facet normal -0.850472 0.222257 0.476758 + outer loop + vertex 0.814447 1.88413 2.5218 + vertex 0.81626 1.88292 2.5256 + vertex 0.815066 1.88826 2.52098 + endloop + endfacet + facet normal -0.859511 0.210664 0.465685 + outer loop + vertex 0.815066 1.88826 2.52098 + vertex 0.81626 1.88292 2.5256 + vertex 0.817137 1.88869 2.52461 + endloop + endfacet + facet normal -0.811937 0.216581 0.54208 + outer loop + vertex 0.81626 1.88292 2.5256 + vertex 0.818824 1.88548 2.52842 + vertex 0.817137 1.88869 2.52461 + endloop + endfacet + facet normal -0.809696 0.206316 0.549386 + outer loop + vertex 0.818535 1.88155 2.52947 + vertex 0.818824 1.88548 2.52842 + vertex 0.81626 1.88292 2.5256 + endloop + endfacet + facet normal -0.921378 0.230846 0.312686 + outer loop + vertex 0.814533 1.89315 2.51673 + vertex 0.813508 1.89158 2.51486 + vertex 0.813901 1.8895 2.51755 + endloop + endfacet + facet normal -0.89692 0.218879 0.384223 + outer loop + vertex 0.813901 1.8895 2.51755 + vertex 0.813869 1.88651 2.51918 + vertex 0.815066 1.88826 2.52098 + endloop + endfacet + facet normal -0.888287 0.242693 0.389931 + outer loop + vertex 0.813901 1.8895 2.51755 + vertex 0.815066 1.88826 2.52098 + vertex 0.814533 1.89315 2.51673 + endloop + endfacet + facet normal -0.889348 0.241248 0.388405 + outer loop + vertex 0.814533 1.89315 2.51673 + vertex 0.815066 1.88826 2.52098 + vertex 0.816221 1.89293 2.52072 + endloop + endfacet + facet normal -0.855564 0.236891 0.460319 + outer loop + vertex 0.815066 1.88826 2.52098 + vertex 0.817137 1.88869 2.52461 + vertex 0.816221 1.89293 2.52072 + endloop + endfacet + facet normal -0.862552 0.227646 0.451864 + outer loop + vertex 0.816221 1.89293 2.52072 + vertex 0.817137 1.88869 2.52461 + vertex 0.817985 1.89303 2.52404 + endloop + endfacet + facet normal -0.818277 0.228819 0.527318 + outer loop + vertex 0.817137 1.88869 2.52461 + vertex 0.81923 1.89007 2.52726 + vertex 0.817985 1.89303 2.52404 + endloop + endfacet + facet normal -0.817305 0.208102 0.537315 + outer loop + vertex 0.818824 1.88548 2.52842 + vertex 0.81923 1.89007 2.52726 + vertex 0.817137 1.88869 2.52461 + endloop + endfacet + facet normal -0.910941 0.271661 0.310463 + outer loop + vertex 0.814357 1.89735 2.51267 + vertex 0.813432 1.89668 2.51053 + vertex 0.813623 1.89437 2.51312 + endloop + endfacet + facet normal -0.921426 0.232561 0.311272 + outer loop + vertex 0.813623 1.89437 2.51312 + vertex 0.813508 1.89158 2.51486 + vertex 0.814533 1.89315 2.51673 + endloop + endfacet + facet normal -0.907042 0.272324 0.321115 + outer loop + vertex 0.813623 1.89437 2.51312 + vertex 0.814533 1.89315 2.51673 + vertex 0.814357 1.89735 2.51267 + endloop + endfacet + facet normal -0.894361 0.290929 0.339821 + outer loop + vertex 0.814357 1.89735 2.51267 + vertex 0.814533 1.89315 2.51673 + vertex 0.815832 1.89748 2.51643 + endloop + endfacet + facet normal -0.876424 0.288633 0.38545 + outer loop + vertex 0.814533 1.89315 2.51673 + vertex 0.816221 1.89293 2.52072 + vertex 0.815832 1.89748 2.51643 + endloop + endfacet + facet normal -0.877274 0.28752 0.384348 + outer loop + vertex 0.815832 1.89748 2.51643 + vertex 0.816221 1.89293 2.52072 + vertex 0.817604 1.89727 2.52063 + endloop + endfacet + facet normal -0.798177 0.286137 0.53013 + outer loop + vertex 0.819044 1.89609 2.52398 + vertex 0.817985 1.89303 2.52404 + vertex 0.81967 1.89379 2.52617 + endloop + endfacet + facet normal -0.834641 0.297369 0.463623 + outer loop + vertex 0.819044 1.89609 2.52398 + vertex 0.817604 1.89727 2.52063 + vertex 0.817985 1.89303 2.52404 + endloop + endfacet + facet normal -0.850919 0.280336 0.44424 + outer loop + vertex 0.817604 1.89727 2.52063 + vertex 0.816221 1.89293 2.52072 + vertex 0.817985 1.89303 2.52404 + endloop + endfacet + facet normal -0.800207 0.253842 0.543354 + outer loop + vertex 0.81967 1.89379 2.52617 + vertex 0.817985 1.89303 2.52404 + vertex 0.81923 1.89007 2.52726 + endloop + endfacet + facet normal -0.910834 0.272297 0.310219 + outer loop + vertex 0.813999 1.90033 2.509 + vertex 0.813432 1.89668 2.51053 + vertex 0.814357 1.89735 2.51267 + endloop + endfacet + facet normal -0.887105 0.311984 0.340164 + outer loop + vertex 0.815713 1.90247 2.51151 + vertex 0.813999 1.90033 2.509 + vertex 0.814357 1.89735 2.51267 + endloop + endfacet + facet normal -0.888527 0.311596 0.336791 + outer loop + vertex 0.814357 1.89735 2.51267 + vertex 0.815832 1.89748 2.51643 + vertex 0.815713 1.90247 2.51151 + endloop + endfacet + facet normal -0.864176 0.34309 0.368089 + outer loop + vertex 0.815713 1.90247 2.51151 + vertex 0.815832 1.89748 2.51643 + vertex 0.817421 1.90196 2.51599 + endloop + endfacet + facet normal -0.818037 0.342382 0.462159 + outer loop + vertex 0.818581 1.90091 2.51967 + vertex 0.817604 1.89727 2.52063 + vertex 0.819283 1.89894 2.52237 + endloop + endfacet + facet normal -0.868759 0.33103 0.368344 + outer loop + vertex 0.818581 1.90091 2.51967 + vertex 0.817421 1.90196 2.51599 + vertex 0.817604 1.89727 2.52063 + endloop + endfacet + facet normal -0.859412 0.34253 0.379584 + outer loop + vertex 0.817421 1.90196 2.51599 + vertex 0.815832 1.89748 2.51643 + vertex 0.817604 1.89727 2.52063 + endloop + endfacet + facet normal -0.817348 0.334371 0.469188 + outer loop + vertex 0.819283 1.89894 2.52237 + vertex 0.817604 1.89727 2.52063 + vertex 0.819044 1.89609 2.52398 + endloop + endfacet + facet normal -0.846725 0.0586401 0.528789 + outer loop + vertex 0.815 1.90575 2.51 + vertex 0.813999 1.90033 2.509 + vertex 0.815713 1.90247 2.51151 + endloop + endfacet + facet normal -0.495273 0.271184 0.825326 + outer loop + vertex 0.815 1.90575 2.51 + vertex 0.815713 1.90247 2.51151 + vertex 0.817327 1.91 2.51 + endloop + endfacet + facet normal -0.603492 0.278718 0.74707 + outer loop + vertex 0.817327 1.91 2.51 + vertex 0.815713 1.90247 2.51151 + vertex 0.817787 1.9067 2.5116 + endloop + endfacet + facet normal -0.838788 0.41057 0.357584 + outer loop + vertex 0.818629 1.90571 2.51452 + vertex 0.817421 1.90196 2.51599 + vertex 0.818964 1.90378 2.51752 + endloop + endfacet + facet normal -0.826319 0.415451 0.38026 + outer loop + vertex 0.818629 1.90571 2.51452 + vertex 0.817787 1.9067 2.5116 + vertex 0.817421 1.90196 2.51599 + endloop + endfacet + facet normal -0.839225 0.402714 0.365408 + outer loop + vertex 0.817787 1.9067 2.5116 + vertex 0.815713 1.90247 2.51151 + vertex 0.817421 1.90196 2.51599 + endloop + endfacet + facet normal -0.838284 0.394244 0.376632 + outer loop + vertex 0.818964 1.90378 2.51752 + vertex 0.817421 1.90196 2.51599 + vertex 0.818581 1.90091 2.51967 + endloop + endfacet + facet normal -0.77507 0.569151 0.27447 + outer loop + vertex 0.82 1.915 2.50718 + vertex 0.817327 1.91 2.51 + vertex 0.82 1.91364 2.51 + endloop + endfacet + facet normal -0.789231 0.561792 0.248 + outer loop + vertex 0.82 1.915 2.50718 + vertex 0.819315 1.915 2.505 + vertex 0.817327 1.91 2.51 + endloop + endfacet + facet normal -0.859193 0.48974 0.148129 + outer loop + vertex 0.819315 1.915 2.505 + vertex 0.816465 1.91 2.505 + vertex 0.817327 1.91 2.51 + endloop + endfacet + facet normal -0.692058 0.364622 0.622982 + outer loop + vertex 0.82 1.91364 2.51 + vertex 0.817787 1.9067 2.5116 + vertex 0.819353 1.90899 2.512 + endloop + endfacet + facet normal -0.457662 0.336071 0.823166 + outer loop + vertex 0.817327 1.91 2.51 + vertex 0.817787 1.9067 2.5116 + vertex 0.82 1.91364 2.51 + endloop + endfacet + facet normal -0.790257 0.473037 0.389525 + outer loop + vertex 0.819353 1.90899 2.512 + vertex 0.817787 1.9067 2.5116 + vertex 0.818629 1.90571 2.51452 + endloop + endfacet + facet normal -0.871818 0.470196 0.13729 + outer loop + vertex 0.82 1.91773 2.5 + vertex 0.819315 1.915 2.505 + vertex 0.82 1.91627 2.505 + endloop + endfacet + facet normal -0.880318 0.456592 0.128698 + outer loop + vertex 0.818584 1.915 2.5 + vertex 0.819315 1.915 2.505 + vertex 0.82 1.91773 2.5 + endloop + endfacet + facet normal -0.848306 0.457515 0.266563 + outer loop + vertex 0.82 1.91627 2.505 + vertex 0.819315 1.915 2.505 + vertex 0.82 1.915 2.50718 + endloop + endfacet + facet normal -0.604036 -0.333139 -0.723989 + outer loop + vertex 0.825 1.10337 2.5 + vertex 0.824101 1.105 2.5 + vertex 0.825 1.105 2.49925 + endloop + endfacet + facet normal -0.626994 -0.3458 -0.69807 + outer loop + vertex 0.824692 1.10245 2.50073 + vertex 0.824101 1.105 2.5 + vertex 0.825 1.10337 2.5 + endloop + endfacet + facet normal -0.970005 -0.176237 0.167422 + outer loop + vertex 0.824964 1.105 2.505 + vertex 0.824101 1.105 2.5 + vertex 0.824692 1.10245 2.50073 + endloop + endfacet + facet normal -0.943492 0.307345 -0.123945 + outer loop + vertex 0.824692 1.10245 2.50073 + vertex 0.824491 1.1029 2.5034 + vertex 0.824964 1.105 2.505 + endloop + endfacet + facet normal -0.451676 0.603324 -0.657259 + outer loop + vertex 0.823799 1.10493 2.50574 + vertex 0.824964 1.105 2.505 + vertex 0.824491 1.1029 2.5034 + endloop + endfacet + facet normal -0.535732 0.00769433 -0.844353 + outer loop + vertex 0.823799 1.10493 2.50574 + vertex 0.821624 1.10956 2.50716 + vertex 0.824964 1.105 2.505 + endloop + endfacet + facet normal -0.766491 -0.627138 0.138526 + outer loop + vertex 0.821624 1.10956 2.50716 + vertex 0.820873 1.11 2.505 + vertex 0.824964 1.105 2.505 + endloop + endfacet + facet normal -0.862373 -0.466087 0.197678 + outer loop + vertex 0.824392 1.10544 2.50953 + vertex 0.821624 1.10956 2.50716 + vertex 0.823799 1.10493 2.50574 + endloop + endfacet + facet normal -0.862346 -0.466319 0.197244 + outer loop + vertex 0.822671 1.10989 2.51251 + vertex 0.821624 1.10956 2.50716 + vertex 0.824392 1.10544 2.50953 + endloop + endfacet + facet normal -0.787592 -0.523277 0.325392 + outer loop + vertex 0.824392 1.10544 2.50953 + vertex 0.824969 1.10737 2.51403 + vertex 0.822671 1.10989 2.51251 + endloop + endfacet + facet normal -0.895081 0.376087 -0.23956 + outer loop + vertex 0.819721 1.11303 2.5064 + vertex 0.82 1.115 2.50846 + vertex 0.820926 1.115 2.505 + endloop + endfacet + facet normal -0.36031 -0.383847 -0.850199 + outer loop + vertex 0.819721 1.11303 2.5064 + vertex 0.820926 1.115 2.505 + vertex 0.821624 1.10956 2.50716 + endloop + endfacet + facet normal -0.943847 0.0100026 0.330232 + outer loop + vertex 0.821624 1.10956 2.50716 + vertex 0.820926 1.115 2.505 + vertex 0.820873 1.11 2.505 + endloop + endfacet + facet normal -0.858044 -0.498356 -0.124102 + outer loop + vertex 0.819453 1.113 2.50836 + vertex 0.819721 1.11303 2.5064 + vertex 0.821624 1.10956 2.50716 + endloop + endfacet + facet normal -0.778099 -0.57762 0.246815 + outer loop + vertex 0.819453 1.113 2.50836 + vertex 0.821624 1.10956 2.50716 + vertex 0.820303 1.11348 2.51217 + endloop + endfacet + facet normal -0.827454 -0.526912 0.194123 + outer loop + vertex 0.820303 1.11348 2.51217 + vertex 0.821624 1.10956 2.50716 + vertex 0.822671 1.10989 2.51251 + endloop + endfacet + facet normal -0.787188 -0.509685 0.347212 + outer loop + vertex 0.823661 1.11065 2.51587 + vertex 0.822671 1.10989 2.51251 + vertex 0.824969 1.10737 2.51403 + endloop + endfacet + facet normal -0.803986 -0.483461 0.346226 + outer loop + vertex 0.823661 1.11065 2.51587 + vertex 0.822066 1.11395 2.51678 + vertex 0.822671 1.10989 2.51251 + endloop + endfacet + facet normal -0.795768 -0.490972 0.354541 + outer loop + vertex 0.822066 1.11395 2.51678 + vertex 0.820303 1.11348 2.51217 + vertex 0.822671 1.10989 2.51251 + endloop + endfacet + facet normal -0.77327 -0.485544 0.4078 + outer loop + vertex 0.823661 1.11065 2.51587 + vertex 0.823715 1.11266 2.51837 + vertex 0.822066 1.11395 2.51678 + endloop + endfacet + facet normal -0.84105 -0.480477 0.248549 + outer loop + vertex 0.819453 1.113 2.50836 + vertex 0.820303 1.11348 2.51217 + vertex 0.818648 1.11539 2.51026 + endloop + endfacet + facet normal -0.84749 -0.444857 0.289591 + outer loop + vertex 0.818825 1.11691 2.51312 + vertex 0.818648 1.11539 2.51026 + vertex 0.820303 1.11348 2.51217 + endloop + endfacet + facet normal -0.809924 -0.451885 0.373929 + outer loop + vertex 0.818825 1.11691 2.51312 + vertex 0.820303 1.11348 2.51217 + vertex 0.820041 1.11799 2.51706 + endloop + endfacet + facet normal -0.824033 -0.437526 0.359918 + outer loop + vertex 0.820041 1.11799 2.51706 + vertex 0.820303 1.11348 2.51217 + vertex 0.822066 1.11395 2.51678 + endloop + endfacet + facet normal -0.775819 -0.462785 0.428875 + outer loop + vertex 0.823147 1.11521 2.52009 + vertex 0.822066 1.11395 2.51678 + vertex 0.823715 1.11266 2.51837 + endloop + endfacet + facet normal -0.811838 -0.406429 0.419207 + outer loop + vertex 0.823147 1.11521 2.52009 + vertex 0.822178 1.11851 2.52142 + vertex 0.822066 1.11395 2.51678 + endloop + endfacet + facet normal -0.791106 -0.426512 0.43845 + outer loop + vertex 0.822178 1.11851 2.52142 + vertex 0.820041 1.11799 2.51706 + vertex 0.822066 1.11395 2.51678 + endloop + endfacet + facet normal -0.776001 -0.417394 0.472869 + outer loop + vertex 0.823147 1.11521 2.52009 + vertex 0.823794 1.11682 2.52258 + vertex 0.822178 1.11851 2.52142 + endloop + endfacet + facet normal -0.871483 -0.3328 0.360224 + outer loop + vertex 0.818825 1.11691 2.51312 + vertex 0.820041 1.11799 2.51706 + vertex 0.818435 1.11995 2.51498 + endloop + endfacet + facet normal -0.871492 -0.335317 0.357861 + outer loop + vertex 0.818936 1.1219 2.51803 + vertex 0.818435 1.11995 2.51498 + vertex 0.820041 1.11799 2.51706 + endloop + endfacet + facet normal -0.840792 -0.341939 0.419698 + outer loop + vertex 0.818936 1.1219 2.51803 + vertex 0.820041 1.11799 2.51706 + vertex 0.820373 1.12304 2.52184 + endloop + endfacet + facet normal -0.817381 -0.366739 0.444286 + outer loop + vertex 0.820373 1.12304 2.52184 + vertex 0.820041 1.11799 2.51706 + vertex 0.822178 1.11851 2.52142 + endloop + endfacet + facet normal -0.769164 -0.385691 0.509539 + outer loop + vertex 0.824313 1.11931 2.52525 + vertex 0.822178 1.11851 2.52142 + vertex 0.823794 1.11682 2.52258 + endloop + endfacet + facet normal -0.771146 -0.381432 0.509749 + outer loop + vertex 0.824313 1.11931 2.52525 + vertex 0.822726 1.12311 2.52569 + vertex 0.822178 1.11851 2.52142 + endloop + endfacet + facet normal -0.792802 -0.361296 0.490846 + outer loop + vertex 0.822726 1.12311 2.52569 + vertex 0.820373 1.12304 2.52184 + vertex 0.822178 1.11851 2.52142 + endloop + endfacet + facet normal -0.740381 -0.374192 0.558406 + outer loop + vertex 0.824313 1.11931 2.52525 + vertex 0.825452 1.12226 2.52874 + vertex 0.822726 1.12311 2.52569 + endloop + endfacet + facet normal -0.867855 -0.279042 0.411051 + outer loop + vertex 0.818936 1.1219 2.51803 + vertex 0.820373 1.12304 2.52184 + vertex 0.81873 1.1251 2.51977 + endloop + endfacet + facet normal -0.868411 -0.284391 0.406182 + outer loop + vertex 0.819366 1.12733 2.52269 + vertex 0.81873 1.1251 2.51977 + vertex 0.820373 1.12304 2.52184 + endloop + endfacet + facet normal -0.832523 -0.289101 0.472574 + outer loop + vertex 0.819366 1.12733 2.52269 + vertex 0.820373 1.12304 2.52184 + vertex 0.82121 1.12855 2.52668 + endloop + endfacet + facet normal -0.807031 -0.316061 0.498805 + outer loop + vertex 0.82121 1.12855 2.52668 + vertex 0.820373 1.12304 2.52184 + vertex 0.822726 1.12311 2.52569 + endloop + endfacet + facet normal -0.783594 -0.316119 0.534836 + outer loop + vertex 0.822726 1.12311 2.52569 + vertex 0.823867 1.12662 2.52943 + vertex 0.82121 1.12855 2.52668 + endloop + endfacet + facet normal -0.742682 -0.360729 0.56418 + outer loop + vertex 0.825452 1.12226 2.52874 + vertex 0.823867 1.12662 2.52943 + vertex 0.822726 1.12311 2.52569 + endloop + endfacet + facet normal -0.850615 -0.242299 0.466632 + outer loop + vertex 0.818996 1.13146 2.52416 + vertex 0.819366 1.12733 2.52269 + vertex 0.82121 1.12855 2.52668 + endloop + endfacet + facet normal -0.85409 -0.257865 0.451702 + outer loop + vertex 0.820071 1.13391 2.52759 + vertex 0.818996 1.13146 2.52416 + vertex 0.82121 1.12855 2.52668 + endloop + endfacet + facet normal -0.78324 -0.308956 0.539519 + outer loop + vertex 0.823057 1.13025 2.53034 + vertex 0.82121 1.12855 2.52668 + vertex 0.823867 1.12662 2.52943 + endloop + endfacet + facet normal -0.806705 -0.262247 0.529578 + outer loop + vertex 0.823057 1.13025 2.53034 + vertex 0.821988 1.13339 2.53026 + vertex 0.82121 1.12855 2.52668 + endloop + endfacet + facet normal -0.808019 -0.261007 0.528187 + outer loop + vertex 0.821988 1.13339 2.53026 + vertex 0.820071 1.13391 2.52759 + vertex 0.82121 1.12855 2.52668 + endloop + endfacet + facet normal -0.769737 -0.248208 0.588131 + outer loop + vertex 0.823057 1.13025 2.53034 + vertex 0.823816 1.13286 2.53243 + vertex 0.821988 1.13339 2.53026 + endloop + endfacet + facet normal -0.874355 -0.221247 0.431918 + outer loop + vertex 0.818996 1.13146 2.52416 + vertex 0.820071 1.13391 2.52759 + vertex 0.818593 1.13533 2.52532 + endloop + endfacet + facet normal -0.873478 -0.204621 0.441776 + outer loop + vertex 0.819202 1.13743 2.5275 + vertex 0.818593 1.13533 2.52532 + vertex 0.820071 1.13391 2.52759 + endloop + endfacet + facet normal -0.834242 -0.193134 0.516469 + outer loop + vertex 0.819202 1.13743 2.5275 + vertex 0.820071 1.13391 2.52759 + vertex 0.820855 1.13805 2.5304 + endloop + endfacet + facet normal -0.813285 -0.213862 0.541138 + outer loop + vertex 0.820855 1.13805 2.5304 + vertex 0.820071 1.13391 2.52759 + vertex 0.821988 1.13339 2.53026 + endloop + endfacet + facet normal -0.780147 -0.207297 0.590252 + outer loop + vertex 0.821988 1.13339 2.53026 + vertex 0.823405 1.13679 2.53333 + vertex 0.820855 1.13805 2.5304 + endloop + endfacet + facet normal -0.77185 -0.217312 0.597514 + outer loop + vertex 0.823816 1.13286 2.53243 + vertex 0.823405 1.13679 2.53333 + vertex 0.821988 1.13339 2.53026 + endloop + endfacet + facet normal -0.840918 -0.167115 0.514713 + outer loop + vertex 0.819137 1.14094 2.52853 + vertex 0.819202 1.13743 2.5275 + vertex 0.820855 1.13805 2.5304 + endloop + endfacet + facet normal -0.848261 -0.183023 0.496946 + outer loop + vertex 0.820394 1.14151 2.53089 + vertex 0.819137 1.14094 2.52853 + vertex 0.820855 1.13805 2.5304 + endloop + endfacet + facet normal -0.789972 -0.187493 0.583772 + outer loop + vertex 0.820855 1.13805 2.5304 + vertex 0.822208 1.14247 2.53365 + vertex 0.820394 1.14151 2.53089 + endloop + endfacet + facet normal -0.779762 -0.198084 0.593914 + outer loop + vertex 0.823405 1.13679 2.53333 + vertex 0.822208 1.14247 2.53365 + vertex 0.820855 1.13805 2.5304 + endloop + endfacet + facet normal -0.856634 -0.1505 0.493486 + outer loop + vertex 0.819137 1.14094 2.52853 + vertex 0.820394 1.14151 2.53089 + vertex 0.8196 1.14445 2.53041 + endloop + endfacet + facet normal -0.805083 -0.190667 0.561683 + outer loop + vertex 0.822602 1.1466 2.53559 + vertex 0.821891 1.15006 2.53574 + vertex 0.820625 1.1475 2.53306 + endloop + endfacet + facet normal -0.80505 -0.186935 0.562983 + outer loop + vertex 0.822208 1.14247 2.53365 + vertex 0.822602 1.1466 2.53559 + vertex 0.820625 1.1475 2.53306 + endloop + endfacet + facet normal -0.819057 -0.19408 0.539888 + outer loop + vertex 0.822208 1.14247 2.53365 + vertex 0.820625 1.1475 2.53306 + vertex 0.8196 1.14445 2.53041 + endloop + endfacet + facet normal -0.809089 -0.124329 0.574384 + outer loop + vertex 0.822208 1.14247 2.53365 + vertex 0.8196 1.14445 2.53041 + vertex 0.820394 1.14151 2.53089 + endloop + endfacet + facet normal -0.769847 -0.185668 0.610625 + outer loop + vertex 0.822602 1.1466 2.53559 + vertex 0.823755 1.14833 2.53757 + vertex 0.821891 1.15006 2.53574 + endloop + endfacet + facet normal -0.806949 -0.187912 0.559931 + outer loop + vertex 0.819605 1.15216 2.53315 + vertex 0.820625 1.1475 2.53306 + vertex 0.821891 1.15006 2.53574 + endloop + endfacet + facet normal -0.807307 -0.189673 0.558819 + outer loop + vertex 0.821308 1.15438 2.53637 + vertex 0.819605 1.15216 2.53315 + vertex 0.821891 1.15006 2.53574 + endloop + endfacet + facet normal -0.76595 -0.19197 0.61357 + outer loop + vertex 0.821891 1.15006 2.53574 + vertex 0.823629 1.15177 2.53845 + vertex 0.821308 1.15438 2.53637 + endloop + endfacet + facet normal -0.769566 -0.184671 0.611282 + outer loop + vertex 0.823755 1.14833 2.53757 + vertex 0.823629 1.15177 2.53845 + vertex 0.821891 1.15006 2.53574 + endloop + endfacet + facet normal -0.794367 -0.213781 0.568577 + outer loop + vertex 0.818772 1.157 2.53381 + vertex 0.819605 1.15216 2.53315 + vertex 0.821308 1.15438 2.53637 + endloop + endfacet + facet normal -0.742327 -0.215239 0.634526 + outer loop + vertex 0.822414 1.16342 2.54068 + vertex 0.819513 1.16466 2.53771 + vertex 0.82088 1.15952 2.53756 + endloop + endfacet + facet normal -0.770715 -0.239623 0.590406 + outer loop + vertex 0.817271 1.16231 2.53383 + vertex 0.819513 1.16466 2.53771 + vertex 0.817444 1.16627 2.53566 + endloop + endfacet + facet normal -0.763224 -0.199299 0.614629 + outer loop + vertex 0.818563 1.16813 2.53765 + vertex 0.817444 1.16627 2.53566 + vertex 0.819513 1.16466 2.53771 + endloop + endfacet + facet normal -0.738295 -0.192011 0.646569 + outer loop + vertex 0.818563 1.16813 2.53765 + vertex 0.819513 1.16466 2.53771 + vertex 0.821009 1.16864 2.5406 + endloop + endfacet + facet normal -0.741091 -0.189229 0.644187 + outer loop + vertex 0.821009 1.16864 2.5406 + vertex 0.819513 1.16466 2.53771 + vertex 0.822414 1.16342 2.54068 + endloop + endfacet + facet normal -0.78282 -0.0771231 0.61745 + outer loop + vertex 0.818267 1.17678 2.5386 + vertex 0.818564 1.17194 2.53838 + vertex 0.821034 1.17461 2.54184 + endloop + endfacet + facet normal -0.783917 -0.0814196 0.615504 + outer loop + vertex 0.820064 1.17928 2.54122 + vertex 0.818267 1.17678 2.5386 + vertex 0.821034 1.17461 2.54184 + endloop + endfacet + facet normal -0.775911 -0.0783822 0.625954 + outer loop + vertex 0.822668 1.179 2.54442 + vertex 0.820064 1.17928 2.54122 + vertex 0.821034 1.17461 2.54184 + endloop + endfacet + facet normal -0.799162 -0.0529708 0.598777 + outer loop + vertex 0.818161 1.18162 2.53889 + vertex 0.818267 1.17678 2.5386 + vertex 0.820064 1.17928 2.54122 + endloop + endfacet + facet normal -0.795716 -0.0449597 0.603999 + outer loop + vertex 0.820989 1.18389 2.54278 + vertex 0.818161 1.18162 2.53889 + vertex 0.820064 1.17928 2.54122 + endloop + endfacet + facet normal -0.764045 -0.047853 0.643386 + outer loop + vertex 0.823376 1.18202 2.54548 + vertex 0.822668 1.179 2.54442 + vertex 0.824677 1.18001 2.54688 + endloop + endfacet + facet normal -0.764152 -0.0477849 0.643264 + outer loop + vertex 0.823376 1.18202 2.54548 + vertex 0.820989 1.18389 2.54278 + vertex 0.822668 1.179 2.54442 + endloop + endfacet + facet normal -0.776135 -0.0570007 0.627986 + outer loop + vertex 0.820989 1.18389 2.54278 + vertex 0.820064 1.17928 2.54122 + vertex 0.822668 1.179 2.54442 + endloop + endfacet + facet normal -0.75546 -0.0814643 0.650111 + outer loop + vertex 0.824677 1.18001 2.54688 + vertex 0.822668 1.179 2.54442 + vertex 0.825628 1.17704 2.54761 + endloop + endfacet + facet normal -0.784052 -0.0793544 0.615601 + outer loop + vertex 0.818132 1.18648 2.53948 + vertex 0.818161 1.18162 2.53889 + vertex 0.820989 1.18389 2.54278 + endloop + endfacet + facet normal -0.791178 -0.103665 0.602736 + outer loop + vertex 0.81999 1.18927 2.5424 + vertex 0.818132 1.18648 2.53948 + vertex 0.820989 1.18389 2.54278 + endloop + endfacet + facet normal -0.756075 -0.0218737 0.65412 + outer loop + vertex 0.823989 1.1846 2.54628 + vertex 0.820989 1.18389 2.54278 + vertex 0.823376 1.18202 2.54548 + endloop + endfacet + facet normal -0.745716 -0.0935987 0.659657 + outer loop + vertex 0.823989 1.1846 2.54628 + vertex 0.82266 1.18836 2.54531 + vertex 0.820989 1.18389 2.54278 + endloop + endfacet + facet normal -0.747785 -0.0916534 0.657585 + outer loop + vertex 0.82266 1.18836 2.54531 + vertex 0.81999 1.18927 2.5424 + vertex 0.820989 1.18389 2.54278 + endloop + endfacet + facet normal -0.776269 -0.128665 0.617132 + outer loop + vertex 0.818132 1.18648 2.53948 + vertex 0.81999 1.18927 2.5424 + vertex 0.818041 1.19039 2.54018 + endloop + endfacet + facet normal -0.77982 -0.156795 0.606049 + outer loop + vertex 0.81907 1.19278 2.54212 + vertex 0.818041 1.19039 2.54018 + vertex 0.81999 1.18927 2.5424 + endloop + endfacet + facet normal -0.757113 -0.148518 0.636178 + outer loop + vertex 0.81907 1.19278 2.54212 + vertex 0.81999 1.18927 2.5424 + vertex 0.821358 1.19357 2.54503 + endloop + endfacet + facet normal -0.75149 -0.153631 0.641608 + outer loop + vertex 0.821358 1.19357 2.54503 + vertex 0.81999 1.18927 2.5424 + vertex 0.82266 1.18836 2.54531 + endloop + endfacet + facet normal -0.690429 0.146028 0.708508 + outer loop + vertex 0.820636 1.75765 2.56266 + vertex 0.817228 1.75566 2.55975 + vertex 0.819094 1.75403 2.56191 + endloop + endfacet + facet normal -0.688738 0.138556 0.711648 + outer loop + vertex 0.817252 1.76047 2.55884 + vertex 0.817228 1.75566 2.55975 + vertex 0.820636 1.75765 2.56266 + endloop + endfacet + facet normal -0.721125 0.0648196 0.689766 + outer loop + vertex 0.821761 1.78314 2.55984 + vertex 0.819304 1.7808 2.5575 + vertex 0.821757 1.77835 2.56029 + endloop + endfacet + facet normal -0.703322 0.0664819 0.707756 + outer loop + vertex 0.821757 1.77835 2.56029 + vertex 0.824315 1.78087 2.56259 + vertex 0.821761 1.78314 2.55984 + endloop + endfacet + facet normal -0.719344 0.0607099 0.691996 + outer loop + vertex 0.819305 1.78552 2.55708 + vertex 0.819304 1.7808 2.5575 + vertex 0.821761 1.78314 2.55984 + endloop + endfacet + facet normal -0.716227 0.0670004 0.694643 + outer loop + vertex 0.821455 1.78768 2.55909 + vertex 0.819305 1.78552 2.55708 + vertex 0.821761 1.78314 2.55984 + endloop + endfacet + facet normal -0.705122 0.0695776 0.705664 + outer loop + vertex 0.821761 1.78314 2.55984 + vertex 0.824078 1.78551 2.56192 + vertex 0.821455 1.78768 2.55909 + endloop + endfacet + facet normal -0.703452 0.0662103 0.707653 + outer loop + vertex 0.824315 1.78087 2.56259 + vertex 0.824078 1.78551 2.56192 + vertex 0.821761 1.78314 2.55984 + endloop + endfacet + facet normal -0.707232 0.115515 0.69748 + outer loop + vertex 0.820855 1.79272 2.55771 + vertex 0.818121 1.79183 2.55509 + vertex 0.819326 1.78927 2.55674 + endloop + endfacet + facet normal -0.716688 0.0679863 0.694073 + outer loop + vertex 0.819326 1.78927 2.55674 + vertex 0.819305 1.78552 2.55708 + vertex 0.821455 1.78768 2.55909 + endloop + endfacet + facet normal -0.69932 0.109482 0.706375 + outer loop + vertex 0.820855 1.79272 2.55771 + vertex 0.819326 1.78927 2.55674 + vertex 0.821455 1.78768 2.55909 + endloop + endfacet + facet normal -0.731641 0.198466 0.652161 + outer loop + vertex 0.821212 1.86256 2.53906 + vertex 0.81893 1.8603 2.53719 + vertex 0.821104 1.85784 2.54038 + endloop + endfacet + facet normal -0.739727 0.222369 0.635103 + outer loop + vertex 0.821096 1.86754 2.53731 + vertex 0.818478 1.86652 2.53462 + vertex 0.819355 1.86407 2.5365 + endloop + endfacet + facet normal -0.732999 0.201998 0.649546 + outer loop + vertex 0.819355 1.86407 2.5365 + vertex 0.81893 1.8603 2.53719 + vertex 0.821212 1.86256 2.53906 + endloop + endfacet + facet normal -0.727867 0.212455 0.651976 + outer loop + vertex 0.821096 1.86754 2.53731 + vertex 0.819355 1.86407 2.5365 + vertex 0.821212 1.86256 2.53906 + endloop + endfacet + facet normal -0.739699 0.220369 0.635833 + outer loop + vertex 0.818655 1.87043 2.53347 + vertex 0.818478 1.86652 2.53462 + vertex 0.821096 1.86754 2.53731 + endloop + endfacet + facet normal -0.765301 0.219003 0.60527 + outer loop + vertex 0.821118 1.8824 2.53243 + vertex 0.818535 1.88155 2.52947 + vertex 0.81941 1.87895 2.53152 + endloop + endfacet + facet normal -0.749813 0.208469 0.627949 + outer loop + vertex 0.81941 1.87895 2.53152 + vertex 0.818979 1.87517 2.53226 + vertex 0.82124 1.87747 2.53419 + endloop + endfacet + facet normal -0.750935 0.206077 0.627398 + outer loop + vertex 0.821118 1.8824 2.53243 + vertex 0.81941 1.87895 2.53152 + vertex 0.82124 1.87747 2.53419 + endloop + endfacet + facet normal -0.765332 0.21807 0.605568 + outer loop + vertex 0.818824 1.88548 2.52842 + vertex 0.818535 1.88155 2.52947 + vertex 0.821118 1.8824 2.53243 + endloop + endfacet + facet normal -0.748723 0.25941 0.610016 + outer loop + vertex 0.821383 1.8923 2.52895 + vertex 0.81923 1.89007 2.52726 + vertex 0.82117 1.8876 2.53069 + endloop + endfacet + facet normal -0.731673 0.265252 0.627929 + outer loop + vertex 0.82117 1.8876 2.53069 + vertex 0.82359 1.8899 2.53254 + vertex 0.821383 1.8923 2.52895 + endloop + endfacet + facet normal -0.7276 0.253173 0.637575 + outer loop + vertex 0.823334 1.88545 2.53401 + vertex 0.82359 1.8899 2.53254 + vertex 0.82117 1.8876 2.53069 + endloop + endfacet + facet normal -0.715526 0.36866 0.593391 + outer loop + vertex 0.821614 1.8979 2.52596 + vertex 0.819044 1.89609 2.52398 + vertex 0.81967 1.89379 2.52617 + endloop + endfacet + facet normal -0.751025 0.265907 0.604363 + outer loop + vertex 0.81967 1.89379 2.52617 + vertex 0.81923 1.89007 2.52726 + vertex 0.821383 1.8923 2.52895 + endloop + endfacet + facet normal -0.695781 0.360759 0.621082 + outer loop + vertex 0.821614 1.8979 2.52596 + vertex 0.81967 1.89379 2.52617 + vertex 0.821383 1.8923 2.52895 + endloop + endfacet + facet normal -0.710073 0.354543 0.608355 + outer loop + vertex 0.821614 1.8979 2.52596 + vertex 0.821383 1.8923 2.52895 + vertex 0.823885 1.89455 2.53056 + endloop + endfacet + facet normal -0.687883 0.38182 0.617276 + outer loop + vertex 0.821614 1.8979 2.52596 + vertex 0.823885 1.89455 2.53056 + vertex 0.824683 1.89819 2.5292 + endloop + endfacet + facet normal -0.698058 0.317117 0.64199 + outer loop + vertex 0.823885 1.89455 2.53056 + vertex 0.821383 1.8923 2.52895 + vertex 0.82359 1.8899 2.53254 + endloop + endfacet + facet normal -0.735772 0.441692 0.513369 + outer loop + vertex 0.820501 1.90277 2.52082 + vertex 0.818581 1.90091 2.51967 + vertex 0.819283 1.89894 2.52237 + endloop + endfacet + facet normal -0.71759 0.387842 0.578484 + outer loop + vertex 0.819283 1.89894 2.52237 + vertex 0.819044 1.89609 2.52398 + vertex 0.821614 1.8979 2.52596 + endloop + endfacet + facet normal -0.683849 0.449877 0.574422 + outer loop + vertex 0.819283 1.89894 2.52237 + vertex 0.821614 1.8979 2.52596 + vertex 0.820501 1.90277 2.52082 + endloop + endfacet + facet normal -0.712765 0.425503 0.557596 + outer loop + vertex 0.820501 1.90277 2.52082 + vertex 0.821614 1.8979 2.52596 + vertex 0.823024 1.90324 2.52368 + endloop + endfacet + facet normal -0.678662 0.43198 0.593978 + outer loop + vertex 0.821614 1.8979 2.52596 + vertex 0.824746 1.90141 2.52698 + vertex 0.823024 1.90324 2.52368 + endloop + endfacet + facet normal -0.675328 0.426816 0.601465 + outer loop + vertex 0.824683 1.89819 2.5292 + vertex 0.824746 1.90141 2.52698 + vertex 0.821614 1.8979 2.52596 + endloop + endfacet + facet normal -0.774068 0.489716 0.401245 + outer loop + vertex 0.820421 1.90754 2.51574 + vertex 0.818629 1.90571 2.51452 + vertex 0.818964 1.90378 2.51752 + endloop + endfacet + facet normal -0.740633 0.463525 0.486423 + outer loop + vertex 0.818964 1.90378 2.51752 + vertex 0.818581 1.90091 2.51967 + vertex 0.820501 1.90277 2.52082 + endloop + endfacet + facet normal -0.712393 0.505985 0.486287 + outer loop + vertex 0.818964 1.90378 2.51752 + vertex 0.820501 1.90277 2.52082 + vertex 0.820421 1.90754 2.51574 + endloop + endfacet + facet normal -0.743049 0.482014 0.464263 + outer loop + vertex 0.820421 1.90754 2.51574 + vertex 0.820501 1.90277 2.52082 + vertex 0.822739 1.90719 2.51982 + endloop + endfacet + facet normal -0.662571 0.467331 0.585322 + outer loop + vertex 0.824248 1.90603 2.52284 + vertex 0.823024 1.90324 2.52368 + vertex 0.825074 1.90442 2.52506 + endloop + endfacet + facet normal -0.705384 0.469712 0.530853 + outer loop + vertex 0.824248 1.90603 2.52284 + vertex 0.822739 1.90719 2.51982 + vertex 0.823024 1.90324 2.52368 + endloop + endfacet + facet normal -0.697639 0.475355 0.536038 + outer loop + vertex 0.822739 1.90719 2.51982 + vertex 0.820501 1.90277 2.52082 + vertex 0.823024 1.90324 2.52368 + endloop + endfacet + facet normal -0.662147 0.452965 0.596979 + outer loop + vertex 0.825074 1.90442 2.52506 + vertex 0.823024 1.90324 2.52368 + vertex 0.824746 1.90141 2.52698 + endloop + endfacet + facet normal -0.325387 0.276357 0.904295 + outer loop + vertex 0.820984 1.91268 2.51065 + vertex 0.821155 1.915 2.51 + vertex 0.82 1.91364 2.51 + endloop + endfacet + facet normal -0.186472 0.410438 0.892619 + outer loop + vertex 0.819353 1.90899 2.512 + vertex 0.820984 1.91268 2.51065 + vertex 0.82 1.91364 2.51 + endloop + endfacet + facet normal -0.773575 0.484177 0.408844 + outer loop + vertex 0.819353 1.90899 2.512 + vertex 0.818629 1.90571 2.51452 + vertex 0.820421 1.90754 2.51574 + endloop + endfacet + facet normal -0.768897 0.490611 0.409999 + outer loop + vertex 0.819353 1.90899 2.512 + vertex 0.820421 1.90754 2.51574 + vertex 0.820984 1.91268 2.51065 + endloop + endfacet + facet normal -0.775712 0.485092 0.403679 + outer loop + vertex 0.820984 1.91268 2.51065 + vertex 0.820421 1.90754 2.51574 + vertex 0.822809 1.91196 2.51501 + endloop + endfacet + facet normal -0.703555 0.4785 0.525404 + outer loop + vertex 0.824223 1.9105 2.51878 + vertex 0.822739 1.90719 2.51982 + vertex 0.824698 1.90844 2.5213 + endloop + endfacet + facet normal -0.745234 0.478206 0.4647 + outer loop + vertex 0.824223 1.9105 2.51878 + vertex 0.822809 1.91196 2.51501 + vertex 0.822739 1.90719 2.51982 + endloop + endfacet + facet normal -0.744866 0.478495 0.464992 + outer loop + vertex 0.822809 1.91196 2.51501 + vertex 0.820421 1.90754 2.51574 + vertex 0.822739 1.90719 2.51982 + endloop + endfacet + facet normal -0.703687 0.472153 0.530939 + outer loop + vertex 0.824698 1.90844 2.5213 + vertex 0.822739 1.90719 2.51982 + vertex 0.824248 1.90603 2.52284 + endloop + endfacet + facet normal -0.775698 0.545301 0.31771 + outer loop + vertex 0.82 1.91627 2.505 + vertex 0.82 1.915 2.50718 + vertex 0.821155 1.915 2.51 + endloop + endfacet + facet normal -0.811858 0.493007 0.312779 + outer loop + vertex 0.82 1.91627 2.505 + vertex 0.821155 1.915 2.51 + vertex 0.822265 1.92 2.505 + endloop + endfacet + facet normal 0.980248 -0.0209681 0.196655 + outer loop + vertex 0.822265 1.92 2.505 + vertex 0.821155 1.915 2.51 + vertex 0.821953 1.91738 2.50628 + endloop + endfacet + facet normal 0.979784 -0.0165663 0.19937 + outer loop + vertex 0.821155 1.915 2.51 + vertex 0.820984 1.91268 2.51065 + vertex 0.821953 1.91738 2.50628 + endloop + endfacet + facet normal -0.817042 0.473754 0.328632 + outer loop + vertex 0.821953 1.91738 2.50628 + vertex 0.820984 1.91268 2.51065 + vertex 0.823082 1.9167 2.51006 + endloop + endfacet + facet normal -0.768256 0.447774 0.457471 + outer loop + vertex 0.824283 1.91568 2.51385 + vertex 0.822809 1.91196 2.51501 + vertex 0.824781 1.91344 2.51688 + endloop + endfacet + facet normal -0.814383 0.441016 0.377208 + outer loop + vertex 0.824283 1.91568 2.51385 + vertex 0.823082 1.9167 2.51006 + vertex 0.822809 1.91196 2.51501 + endloop + endfacet + facet normal -0.7853 0.468322 0.404944 + outer loop + vertex 0.823082 1.9167 2.51006 + vertex 0.820984 1.91268 2.51065 + vertex 0.822809 1.91196 2.51501 + endloop + endfacet + facet normal -0.768475 0.444438 0.46035 + outer loop + vertex 0.824781 1.91344 2.51688 + vertex 0.822809 1.91196 2.51501 + vertex 0.824223 1.9105 2.51878 + endloop + endfacet + facet normal -0.924758 0.340674 0.1696 + outer loop + vertex 0.821348 1.92 2.5 + vertex 0.822265 1.92 2.505 + vertex 0.82319 1.925 2.5 + endloop + endfacet + facet normal 0.98445 -0.00656356 0.175545 + outer loop + vertex 0.82319 1.925 2.5 + vertex 0.822265 1.92 2.505 + vertex 0.822905 1.92259 2.50151 + endloop + endfacet + facet normal 0.98808 -0.0461826 0.146851 + outer loop + vertex 0.822265 1.92 2.505 + vertex 0.821953 1.91738 2.50628 + vertex 0.822905 1.92259 2.50151 + endloop + endfacet + facet normal -0.855862 0.42562 0.293849 + outer loop + vertex 0.822905 1.92259 2.50151 + vertex 0.821953 1.91738 2.50628 + vertex 0.823415 1.92067 2.50578 + endloop + endfacet + facet normal -0.834141 0.409648 0.36932 + outer loop + vertex 0.824297 1.92032 2.50879 + vertex 0.823082 1.9167 2.51006 + vertex 0.82473 1.91856 2.51173 + endloop + endfacet + facet normal -0.867936 0.396412 0.299242 + outer loop + vertex 0.824297 1.92032 2.50879 + vertex 0.823415 1.92067 2.50578 + vertex 0.823082 1.9167 2.51006 + endloop + endfacet + facet normal -0.843555 0.425337 0.327877 + outer loop + vertex 0.823415 1.92067 2.50578 + vertex 0.821953 1.91738 2.50628 + vertex 0.823082 1.9167 2.51006 + endloop + endfacet + facet normal -0.834118 0.405555 0.37386 + outer loop + vertex 0.82473 1.91856 2.51173 + vertex 0.823082 1.9167 2.51006 + vertex 0.824283 1.91568 2.51385 + endloop + endfacet + facet normal -0.999373 -0.0339772 -0.00999516 + outer loop + vertex 0.82324 1.925 2.495 + vertex 0.82319 1.925 2.5 + vertex 0.82307 1.93 2.495 + endloop + endfacet + facet normal -0.335245 0.662161 0.67019 + outer loop + vertex 0.82307 1.93 2.495 + vertex 0.82319 1.925 2.5 + vertex 0.82354 1.92807 2.49714 + endloop + endfacet + facet normal -0.900551 0.319678 0.294641 + outer loop + vertex 0.823908 1.92706 2.49972 + vertex 0.822905 1.92259 2.50151 + vertex 0.82418 1.92481 2.50299 + endloop + endfacet + facet normal -0.918217 0.306282 0.251135 + outer loop + vertex 0.823908 1.92706 2.49972 + vertex 0.82354 1.92807 2.49714 + vertex 0.822905 1.92259 2.50151 + endloop + endfacet + facet normal 0.991919 -0.126073 -0.0142004 + outer loop + vertex 0.82354 1.92807 2.49714 + vertex 0.82319 1.925 2.5 + vertex 0.822905 1.92259 2.50151 + endloop + endfacet + facet normal -0.883607 0.362293 0.296618 + outer loop + vertex 0.82418 1.92481 2.50299 + vertex 0.823415 1.92067 2.50578 + vertex 0.824677 1.92309 2.50657 + endloop + endfacet + facet normal -0.902275 0.342467 0.261947 + outer loop + vertex 0.822905 1.92259 2.50151 + vertex 0.823415 1.92067 2.50578 + vertex 0.82418 1.92481 2.50299 + endloop + endfacet + facet normal -0.883101 0.361032 0.299647 + outer loop + vertex 0.824677 1.92309 2.50657 + vertex 0.823415 1.92067 2.50578 + vertex 0.824297 1.92032 2.50879 + endloop + endfacet + facet normal -0.581991 0.165634 -0.796148 + outer loop + vertex 0.825 1.93 2.49307 + vertex 0.824038 1.93124 2.49403 + vertex 0.825 1.935 2.49411 + endloop + endfacet + facet normal -0.707107 -3.38815e-05 -0.707107 + outer loop + vertex 0.82307 1.93 2.495 + vertex 0.824038 1.93124 2.49403 + vertex 0.825 1.93 2.49307 + endloop + endfacet + facet normal -0.964332 0.176822 0.196972 + outer loop + vertex 0.825 1.935 2.49807 + vertex 0.82354 1.92807 2.49714 + vertex 0.825 1.93285 2.5 + endloop + endfacet + facet normal -0.978661 0.199982 0.0472131 + outer loop + vertex 0.825 1.935 2.49807 + vertex 0.824038 1.93124 2.49403 + vertex 0.82354 1.92807 2.49714 + endloop + endfacet + facet normal -0.220691 0.700032 0.679154 + outer loop + vertex 0.824038 1.93124 2.49403 + vertex 0.82307 1.93 2.495 + vertex 0.82354 1.92807 2.49714 + endloop + endfacet + facet normal -0.963584 0.171871 0.204856 + outer loop + vertex 0.825 1.93285 2.5 + vertex 0.82354 1.92807 2.49714 + vertex 0.823908 1.92706 2.49972 + endloop + endfacet + facet normal -0.903999 0.238967 -0.354513 + outer loop + vertex 0.825 1.935 2.49411 + vertex 0.824038 1.93124 2.49403 + vertex 0.825 1.93632 2.495 + endloop + endfacet + facet normal -0.982293 0.172115 0.0740012 + outer loop + vertex 0.825 1.93632 2.495 + vertex 0.824038 1.93124 2.49403 + vertex 0.825 1.935 2.49807 + endloop + endfacet + facet normal -0.701628 -0.0728975 -0.708804 + outer loop + vertex 0.83 1.07796 2.495 + vertex 0.829788 1.08 2.495 + vertex 0.83 1.08 2.49479 + endloop + endfacet + facet normal -0.970541 -0.100837 0.218821 + outer loop + vertex 0.83 1.07796 2.495 + vertex 0.83 1.08 2.49594 + vertex 0.829788 1.08 2.495 + endloop + endfacet + facet normal -0.944045 -0.251943 0.212847 + outer loop + vertex 0.83 1.08343 2.5 + vertex 0.829788 1.08 2.495 + vertex 0.83 1.08 2.49594 + endloop + endfacet + facet normal -0.933748 -0.275465 0.228547 + outer loop + vertex 0.83 1.08343 2.5 + vertex 0.82848 1.08549 2.49628 + vertex 0.829788 1.08 2.495 + endloop + endfacet + facet normal -0.965891 -0.188939 -0.17708 + outer loop + vertex 0.82848 1.08549 2.49628 + vertex 0.82881 1.085 2.495 + vertex 0.829788 1.08 2.495 + endloop + endfacet + facet normal 0.919271 -0.0309593 -0.392405 + outer loop + vertex 0.83 1.08343 2.5 + vertex 0.829411 1.08296 2.49866 + vertex 0.82848 1.08549 2.49628 + endloop + endfacet + facet normal -0.969606 -0.150482 -0.192922 + outer loop + vertex 0.82881 1.085 2.495 + vertex 0.82848 1.08549 2.49628 + vertex 0.828034 1.09 2.495 + endloop + endfacet + facet normal -0.91291 -0.192189 -0.36008 + outer loop + vertex 0.828034 1.09 2.495 + vertex 0.82848 1.08549 2.49628 + vertex 0.827494 1.09063 2.49603 + endloop + endfacet + facet normal -0.962651 -0.244398 0.116503 + outer loop + vertex 0.828862 1.0855 2.49945 + vertex 0.82848 1.08549 2.49628 + vertex 0.829411 1.08296 2.49866 + endloop + endfacet + facet normal -0.971037 -0.208085 0.117421 + outer loop + vertex 0.828862 1.0855 2.49945 + vertex 0.827885 1.09005 2.49943 + vertex 0.82848 1.08549 2.49628 + endloop + endfacet + facet normal -0.979602 -0.183929 0.0809268 + outer loop + vertex 0.827885 1.09005 2.49943 + vertex 0.827494 1.09063 2.49603 + vertex 0.82848 1.08549 2.49628 + endloop + endfacet + facet normal -0.954436 -0.204045 0.217757 + outer loop + vertex 0.828862 1.0855 2.49945 + vertex 0.829138 1.08732 2.50237 + vertex 0.827885 1.09005 2.49943 + endloop + endfacet + facet normal -0.88348 0.00865723 -0.468389 + outer loop + vertex 0.828034 1.09 2.495 + vertex 0.827494 1.09063 2.49603 + vertex 0.828083 1.095 2.495 + endloop + endfacet + facet normal -0.96307 0.0684802 -0.260399 + outer loop + vertex 0.828083 1.095 2.495 + vertex 0.827494 1.09063 2.49603 + vertex 0.826731 1.095 2.5 + endloop + endfacet + facet normal -0.969589 -0.234169 0.0711425 + outer loop + vertex 0.827494 1.09063 2.49603 + vertex 0.827885 1.09005 2.49943 + vertex 0.826731 1.095 2.5 + endloop + endfacet + facet normal -0.937078 -0.246795 0.246935 + outer loop + vertex 0.826731 1.095 2.5 + vertex 0.827885 1.09005 2.49943 + vertex 0.827066 1.09579 2.50206 + endloop + endfacet + facet normal -0.941903 -0.241364 0.233586 + outer loop + vertex 0.827885 1.09005 2.49943 + vertex 0.828696 1.09146 2.50416 + vertex 0.827066 1.09579 2.50206 + endloop + endfacet + facet normal -0.954418 -0.198477 0.22292 + outer loop + vertex 0.829138 1.08732 2.50237 + vertex 0.828696 1.09146 2.50416 + vertex 0.827885 1.09005 2.49943 + endloop + endfacet + facet normal -0.985548 -0.0212886 0.168054 + outer loop + vertex 0.826731 1.095 2.5 + vertex 0.827066 1.09579 2.50206 + vertex 0.826623 1.1 2.5 + endloop + endfacet + facet normal -0.906376 -0.25915 -0.333652 + outer loop + vertex 0.826623 1.1 2.5 + vertex 0.827066 1.09579 2.50206 + vertex 0.825603 1.10023 2.50259 + endloop + endfacet + facet normal -0.941975 -0.241703 0.232942 + outer loop + vertex 0.828175 1.09531 2.50605 + vertex 0.827066 1.09579 2.50206 + vertex 0.828696 1.09146 2.50416 + endloop + endfacet + facet normal -0.915177 -0.341992 0.213291 + outer loop + vertex 0.828175 1.09531 2.50605 + vertex 0.826908 1.09891 2.50638 + vertex 0.827066 1.09579 2.50206 + endloop + endfacet + facet normal -0.922505 -0.328234 0.203093 + outer loop + vertex 0.826908 1.09891 2.50638 + vertex 0.825603 1.10023 2.50259 + vertex 0.827066 1.09579 2.50206 + endloop + endfacet + facet normal -0.887915 -0.341227 0.308497 + outer loop + vertex 0.828175 1.09531 2.50605 + vertex 0.828472 1.09707 2.50885 + vertex 0.826908 1.09891 2.50638 + endloop + endfacet + facet normal -0.793962 -0.547818 -0.263667 + outer loop + vertex 0.826623 1.1 2.5 + vertex 0.825603 1.10023 2.50259 + vertex 0.824692 1.10245 2.50073 + endloop + endfacet + facet normal -0.661779 -0.318728 -0.678572 + outer loop + vertex 0.825 1.10337 2.5 + vertex 0.826623 1.1 2.5 + vertex 0.824692 1.10245 2.50073 + endloop + endfacet + facet normal -0.923712 -0.383072 -0.00349827 + outer loop + vertex 0.824491 1.1029 2.5034 + vertex 0.824692 1.10245 2.50073 + vertex 0.825603 1.10023 2.50259 + endloop + endfacet + facet normal -0.901917 -0.413187 0.125787 + outer loop + vertex 0.824491 1.1029 2.5034 + vertex 0.825603 1.10023 2.50259 + vertex 0.82514 1.1023 2.50606 + endloop + endfacet + facet normal -0.88251 -0.446348 0.148155 + outer loop + vertex 0.82514 1.1023 2.50606 + vertex 0.825603 1.10023 2.50259 + vertex 0.826908 1.09891 2.50638 + endloop + endfacet + facet normal -0.884307 -0.370095 0.284658 + outer loop + vertex 0.827688 1.0998 2.50996 + vertex 0.826908 1.09891 2.50638 + vertex 0.828472 1.09707 2.50885 + endloop + endfacet + facet normal -0.841433 -0.4523 0.295661 + outer loop + vertex 0.827688 1.0998 2.50996 + vertex 0.826237 1.10187 2.50901 + vertex 0.826908 1.09891 2.50638 + endloop + endfacet + facet normal -0.865867 -0.426927 0.260782 + outer loop + vertex 0.826237 1.10187 2.50901 + vertex 0.82514 1.1023 2.50606 + vertex 0.826908 1.09891 2.50638 + endloop + endfacet + facet normal -0.838671 -0.436804 0.325319 + outer loop + vertex 0.827688 1.0998 2.50996 + vertex 0.827012 1.10299 2.5125 + vertex 0.826237 1.10187 2.50901 + endloop + endfacet + facet normal -0.890738 -0.439164 0.117134 + outer loop + vertex 0.824491 1.1029 2.5034 + vertex 0.82514 1.1023 2.50606 + vertex 0.823799 1.10493 2.50574 + endloop + endfacet + facet normal -0.84567 -0.473323 0.246592 + outer loop + vertex 0.82514 1.1023 2.50606 + vertex 0.826237 1.10187 2.50901 + vertex 0.824392 1.10544 2.50953 + endloop + endfacet + facet normal -0.883381 -0.425908 0.195552 + outer loop + vertex 0.823799 1.10493 2.50574 + vertex 0.82514 1.1023 2.50606 + vertex 0.824392 1.10544 2.50953 + endloop + endfacet + facet normal -0.759287 -0.503077 0.412791 + outer loop + vertex 0.827131 1.10577 2.51606 + vertex 0.825744 1.10959 2.51815 + vertex 0.824969 1.10737 2.51403 + endloop + endfacet + facet normal -0.759833 -0.499305 0.416351 + outer loop + vertex 0.827012 1.10299 2.5125 + vertex 0.827131 1.10577 2.51606 + vertex 0.824969 1.10737 2.51403 + endloop + endfacet + facet normal -0.813945 -0.488791 0.31397 + outer loop + vertex 0.827012 1.10299 2.5125 + vertex 0.824969 1.10737 2.51403 + vertex 0.824392 1.10544 2.50953 + endloop + endfacet + facet normal -0.817358 -0.471174 0.331544 + outer loop + vertex 0.827012 1.10299 2.5125 + vertex 0.824392 1.10544 2.50953 + vertex 0.826237 1.10187 2.50901 + endloop + endfacet + facet normal -0.735965 -0.511482 0.443556 + outer loop + vertex 0.829328 1.10591 2.51986 + vertex 0.825744 1.10959 2.51815 + vertex 0.827131 1.10577 2.51606 + endloop + endfacet + facet normal -0.731554 -0.495805 0.467981 + outer loop + vertex 0.82785 1.11033 2.52224 + vertex 0.825744 1.10959 2.51815 + vertex 0.829328 1.10591 2.51986 + endloop + endfacet + facet normal -0.712487 -0.501607 0.490665 + outer loop + vertex 0.829328 1.10591 2.51986 + vertex 0.831026 1.10738 2.52383 + vertex 0.82785 1.11033 2.52224 + endloop + endfacet + facet normal -0.734091 -0.531127 0.423101 + outer loop + vertex 0.824969 1.10737 2.51403 + vertex 0.825744 1.10959 2.51815 + vertex 0.823661 1.11065 2.51587 + endloop + endfacet + facet normal -0.737978 -0.517659 0.432918 + outer loop + vertex 0.823715 1.11266 2.51837 + vertex 0.823661 1.11065 2.51587 + vertex 0.825744 1.10959 2.51815 + endloop + endfacet + facet normal -0.71723 -0.507167 0.477873 + outer loop + vertex 0.823715 1.11266 2.51837 + vertex 0.825744 1.10959 2.51815 + vertex 0.825049 1.11372 2.5215 + endloop + endfacet + facet normal -0.728679 -0.50059 0.467373 + outer loop + vertex 0.825049 1.11372 2.5215 + vertex 0.825744 1.10959 2.51815 + vertex 0.82785 1.11033 2.52224 + endloop + endfacet + facet normal -0.706459 -0.4785 0.521492 + outer loop + vertex 0.830183 1.11044 2.5255 + vertex 0.82785 1.11033 2.52224 + vertex 0.831026 1.10738 2.52383 + endloop + endfacet + facet normal -0.704951 -0.481771 0.52052 + outer loop + vertex 0.830183 1.11044 2.5255 + vertex 0.827476 1.11383 2.52497 + vertex 0.82785 1.11033 2.52224 + endloop + endfacet + facet normal -0.712766 -0.477404 0.513858 + outer loop + vertex 0.827476 1.11383 2.52497 + vertex 0.825049 1.11372 2.5215 + vertex 0.82785 1.11033 2.52224 + endloop + endfacet + facet normal -0.679063 -0.452045 0.578385 + outer loop + vertex 0.830183 1.11044 2.5255 + vertex 0.830445 1.11311 2.52789 + vertex 0.827476 1.11383 2.52497 + endloop + endfacet + facet normal -0.732456 -0.485703 0.477075 + outer loop + vertex 0.823715 1.11266 2.51837 + vertex 0.825049 1.11372 2.5215 + vertex 0.823147 1.11521 2.52009 + endloop + endfacet + facet normal -0.732017 -0.468574 0.49456 + outer loop + vertex 0.823794 1.11682 2.52258 + vertex 0.823147 1.11521 2.52009 + vertex 0.825049 1.11372 2.5215 + endloop + endfacet + facet normal -0.71834 -0.469539 0.513342 + outer loop + vertex 0.823794 1.11682 2.52258 + vertex 0.825049 1.11372 2.5215 + vertex 0.825398 1.11648 2.52451 + endloop + endfacet + facet normal -0.715157 -0.472162 0.515376 + outer loop + vertex 0.825398 1.11648 2.52451 + vertex 0.825049 1.11372 2.5215 + vertex 0.827476 1.11383 2.52497 + endloop + endfacet + facet normal -0.689544 -0.442223 0.573557 + outer loop + vertex 0.827476 1.11383 2.52497 + vertex 0.827679 1.11755 2.52808 + vertex 0.825398 1.11648 2.52451 + endloop + endfacet + facet normal -0.679966 -0.448318 0.580221 + outer loop + vertex 0.830445 1.11311 2.52789 + vertex 0.827679 1.11755 2.52808 + vertex 0.827476 1.11383 2.52497 + endloop + endfacet + facet normal -0.733524 -0.419825 0.534499 + outer loop + vertex 0.823794 1.11682 2.52258 + vertex 0.825398 1.11648 2.52451 + vertex 0.824313 1.11931 2.52525 + endloop + endfacet + facet normal -0.680484 -0.395266 0.617015 + outer loop + vertex 0.828736 1.12061 2.5313 + vertex 0.826871 1.12532 2.53226 + vertex 0.825452 1.12226 2.52874 + endloop + endfacet + facet normal -0.680446 -0.406385 0.60979 + outer loop + vertex 0.827679 1.11755 2.52808 + vertex 0.828736 1.12061 2.5313 + vertex 0.825452 1.12226 2.52874 + endloop + endfacet + facet normal -0.703159 -0.412809 0.578927 + outer loop + vertex 0.827679 1.11755 2.52808 + vertex 0.825452 1.12226 2.52874 + vertex 0.824313 1.11931 2.52525 + endloop + endfacet + facet normal -0.702924 -0.418592 0.575047 + outer loop + vertex 0.827679 1.11755 2.52808 + vertex 0.824313 1.11931 2.52525 + vertex 0.825398 1.11648 2.52451 + endloop + endfacet + facet normal -0.664942 -0.392821 0.635252 + outer loop + vertex 0.828736 1.12061 2.5313 + vertex 0.830244 1.12239 2.53398 + vertex 0.826871 1.12532 2.53226 + endloop + endfacet + facet normal -0.717168 -0.356933 0.598555 + outer loop + vertex 0.823867 1.12662 2.52943 + vertex 0.825452 1.12226 2.52874 + vertex 0.826871 1.12532 2.53226 + endloop + endfacet + facet normal -0.718405 -0.331432 0.611594 + outer loop + vertex 0.825042 1.12973 2.5325 + vertex 0.823867 1.12662 2.52943 + vertex 0.826871 1.12532 2.53226 + endloop + endfacet + facet normal -0.670617 -0.409046 0.618832 + outer loop + vertex 0.82902 1.12566 2.53481 + vertex 0.826871 1.12532 2.53226 + vertex 0.830244 1.12239 2.53398 + endloop + endfacet + facet normal -0.699769 -0.331295 0.632903 + outer loop + vertex 0.82902 1.12566 2.53481 + vertex 0.827663 1.12895 2.53504 + vertex 0.826871 1.12532 2.53226 + endloop + endfacet + facet normal -0.705393 -0.326995 0.628884 + outer loop + vertex 0.827663 1.12895 2.53504 + vertex 0.825042 1.12973 2.5325 + vertex 0.826871 1.12532 2.53226 + endloop + endfacet + facet normal -0.665617 -0.320021 0.674196 + outer loop + vertex 0.82902 1.12566 2.53481 + vertex 0.830583 1.127 2.53699 + vertex 0.827663 1.12895 2.53504 + endloop + endfacet + facet normal -0.735889 -0.313546 0.60013 + outer loop + vertex 0.823867 1.12662 2.52943 + vertex 0.825042 1.12973 2.5325 + vertex 0.823057 1.13025 2.53034 + endloop + endfacet + facet normal -0.74012 -0.276747 0.61289 + outer loop + vertex 0.823816 1.13286 2.53243 + vertex 0.823057 1.13025 2.53034 + vertex 0.825042 1.12973 2.5325 + endloop + endfacet + facet normal -0.715725 -0.266447 0.645556 + outer loop + vertex 0.823816 1.13286 2.53243 + vertex 0.825042 1.12973 2.5325 + vertex 0.826172 1.1338 2.53543 + endloop + endfacet + facet normal -0.709546 -0.271538 0.65024 + outer loop + vertex 0.826172 1.1338 2.53543 + vertex 0.825042 1.12973 2.5325 + vertex 0.827663 1.12895 2.53504 + endloop + endfacet + facet normal -0.75536 -0.217307 0.61823 + outer loop + vertex 0.824654 1.14493 2.53751 + vertex 0.822208 1.14247 2.53365 + vertex 0.825888 1.13976 2.5372 + endloop + endfacet + facet normal -0.755193 -0.217621 0.618324 + outer loop + vertex 0.822208 1.14247 2.53365 + vertex 0.824654 1.14493 2.53751 + vertex 0.822602 1.1466 2.53559 + endloop + endfacet + facet normal -0.753533 -0.210419 0.622825 + outer loop + vertex 0.823755 1.14833 2.53757 + vertex 0.822602 1.1466 2.53559 + vertex 0.824654 1.14493 2.53751 + endloop + endfacet + facet normal -0.727765 -0.20421 0.654719 + outer loop + vertex 0.823755 1.14833 2.53757 + vertex 0.824654 1.14493 2.53751 + vertex 0.826095 1.14872 2.54029 + endloop + endfacet + facet normal -0.729969 -0.194469 0.65523 + outer loop + vertex 0.823629 1.15177 2.53845 + vertex 0.823755 1.14833 2.53757 + vertex 0.826095 1.14872 2.54029 + endloop + endfacet + facet normal -0.743357 -0.0168726 0.668682 + outer loop + vertex 0.825544 1.1819 2.54789 + vertex 0.823376 1.18202 2.54548 + vertex 0.824677 1.18001 2.54688 + endloop + endfacet + facet normal -0.737395 -0.0703321 0.67179 + outer loop + vertex 0.824677 1.18001 2.54688 + vertex 0.825628 1.17704 2.54761 + vertex 0.827087 1.179 2.54942 + endloop + endfacet + facet normal -0.730904 -0.0296163 0.681838 + outer loop + vertex 0.825544 1.1819 2.54789 + vertex 0.824677 1.18001 2.54688 + vertex 0.827087 1.179 2.54942 + endloop + endfacet + facet normal -0.731083 -0.0298183 0.681636 + outer loop + vertex 0.825544 1.1819 2.54789 + vertex 0.827087 1.179 2.54942 + vertex 0.828455 1.18119 2.55098 + endloop + endfacet + facet normal -0.729923 -0.0178945 0.683295 + outer loop + vertex 0.825544 1.1819 2.54789 + vertex 0.828455 1.18119 2.55098 + vertex 0.826698 1.18419 2.54918 + endloop + endfacet + facet normal -0.713595 -0.0528442 0.698563 + outer loop + vertex 0.828455 1.18119 2.55098 + vertex 0.827087 1.179 2.54942 + vertex 0.830296 1.17742 2.55258 + endloop + endfacet + facet normal -0.660972 -0.159543 0.733254 + outer loop + vertex 0.828702 1.26997 2.57113 + vertex 0.827336 1.27439 2.57086 + vertex 0.825261 1.27123 2.5683 + endloop + endfacet + facet normal -0.661714 -0.166638 0.731004 + outer loop + vertex 0.828702 1.26997 2.57113 + vertex 0.825261 1.27123 2.5683 + vertex 0.827791 1.26698 2.56962 + endloop + endfacet + facet normal -0.654655 -0.157219 0.739397 + outer loop + vertex 0.828702 1.26997 2.57113 + vertex 0.830431 1.27241 2.57318 + vertex 0.827336 1.27439 2.57086 + endloop + endfacet + facet normal -0.67853 0.0758633 0.730645 + outer loop + vertex 0.826475 1.77348 2.56544 + vertex 0.829332 1.77621 2.56781 + vertex 0.826879 1.77865 2.56528 + endloop + endfacet + facet normal -0.692188 0.0685455 0.718455 + outer loop + vertex 0.826857 1.78355 2.56479 + vertex 0.824315 1.78087 2.56259 + vertex 0.826879 1.77865 2.56528 + endloop + endfacet + facet normal -0.685092 0.069245 0.725158 + outer loop + vertex 0.826879 1.77865 2.56528 + vertex 0.829958 1.78164 2.5679 + vertex 0.826857 1.78355 2.56479 + endloop + endfacet + facet normal -0.683742 0.0665127 0.726686 + outer loop + vertex 0.829332 1.77621 2.56781 + vertex 0.829958 1.78164 2.5679 + vertex 0.826879 1.77865 2.56528 + endloop + endfacet + facet normal -0.692094 0.0683669 0.718563 + outer loop + vertex 0.824078 1.78551 2.56192 + vertex 0.824315 1.78087 2.56259 + vertex 0.826857 1.78355 2.56479 + endloop + endfacet + facet normal -0.68316 0.089967 0.724705 + outer loop + vertex 0.826374 1.7881 2.56377 + vertex 0.824078 1.78551 2.56192 + vertex 0.826857 1.78355 2.56479 + endloop + endfacet + facet normal -0.680285 0.0908521 0.727295 + outer loop + vertex 0.826857 1.78355 2.56479 + vertex 0.82938 1.78659 2.56677 + vertex 0.826374 1.7881 2.56377 + endloop + endfacet + facet normal -0.678224 0.0876338 0.729612 + outer loop + vertex 0.829958 1.78164 2.5679 + vertex 0.82938 1.78659 2.56677 + vertex 0.826857 1.78355 2.56479 + endloop + endfacet + facet normal -0.685504 0.270977 0.675763 + outer loop + vertex 0.828734 1.88612 2.53942 + vertex 0.826105 1.88704 2.53638 + vertex 0.827439 1.88301 2.53935 + endloop + endfacet + facet normal -0.708991 0.258281 0.656219 + outer loop + vertex 0.82359 1.8899 2.53254 + vertex 0.823334 1.88545 2.53401 + vertex 0.826105 1.88704 2.53638 + endloop + endfacet + facet normal -0.674911 0.307678 0.670693 + outer loop + vertex 0.826225 1.89204 2.53421 + vertex 0.82359 1.8899 2.53254 + vertex 0.826105 1.88704 2.53638 + endloop + endfacet + facet normal -0.658698 0.313141 0.684149 + outer loop + vertex 0.826105 1.88704 2.53638 + vertex 0.828809 1.88981 2.53771 + vertex 0.826225 1.89204 2.53421 + endloop + endfacet + facet normal -0.664463 0.323872 0.673495 + outer loop + vertex 0.828734 1.88612 2.53942 + vertex 0.828809 1.88981 2.53771 + vertex 0.826105 1.88704 2.53638 + endloop + endfacet + facet normal -0.646827 0.387601 0.656796 + outer loop + vertex 0.826808 1.89642 2.53234 + vertex 0.824683 1.89819 2.5292 + vertex 0.823885 1.89455 2.53056 + endloop + endfacet + facet normal -0.679691 0.322992 0.658556 + outer loop + vertex 0.823885 1.89455 2.53056 + vertex 0.82359 1.8899 2.53254 + vertex 0.826225 1.89204 2.53421 + endloop + endfacet + facet normal -0.643868 0.371463 0.668916 + outer loop + vertex 0.826808 1.89642 2.53234 + vertex 0.823885 1.89455 2.53056 + vertex 0.826225 1.89204 2.53421 + endloop + endfacet + facet normal -0.623554 0.375843 0.685509 + outer loop + vertex 0.826808 1.89642 2.53234 + vertex 0.826225 1.89204 2.53421 + vertex 0.828841 1.89406 2.53548 + endloop + endfacet + facet normal -0.604307 0.39839 0.689999 + outer loop + vertex 0.826808 1.89642 2.53234 + vertex 0.828841 1.89406 2.53548 + vertex 0.828886 1.89655 2.53408 + endloop + endfacet + facet normal -0.621022 0.368653 0.691683 + outer loop + vertex 0.828841 1.89406 2.53548 + vertex 0.826225 1.89204 2.53421 + vertex 0.828809 1.88981 2.53771 + endloop + endfacet + facet normal -0.594976 0.442928 0.670685 + outer loop + vertex 0.826808 1.89642 2.53234 + vertex 0.828986 1.8985 2.53289 + vertex 0.827227 1.90024 2.53019 + endloop + endfacet + facet normal -0.609526 0.438689 0.660326 + outer loop + vertex 0.826808 1.89642 2.53234 + vertex 0.827227 1.90024 2.53019 + vertex 0.824683 1.89819 2.5292 + endloop + endfacet + facet normal -0.615827 0.454566 0.643527 + outer loop + vertex 0.824683 1.89819 2.5292 + vertex 0.827227 1.90024 2.53019 + vertex 0.824746 1.90141 2.52698 + endloop + endfacet + facet normal -0.593302 0.440323 0.673876 + outer loop + vertex 0.828986 1.8985 2.53289 + vertex 0.826808 1.89642 2.53234 + vertex 0.828886 1.89655 2.53408 + endloop + endfacet + facet normal -0.647553 0.481898 0.590297 + outer loop + vertex 0.826082 1.90725 2.52386 + vertex 0.824248 1.90603 2.52284 + vertex 0.825074 1.90442 2.52506 + endloop + endfacet + facet normal -0.611516 0.484131 0.625832 + outer loop + vertex 0.825074 1.90442 2.52506 + vertex 0.827665 1.9045 2.52754 + vertex 0.826082 1.90725 2.52386 + endloop + endfacet + facet normal -0.616575 0.470063 0.631566 + outer loop + vertex 0.825074 1.90442 2.52506 + vertex 0.824746 1.90141 2.52698 + vertex 0.827665 1.9045 2.52754 + endloop + endfacet + facet normal -0.610798 0.462613 0.642584 + outer loop + vertex 0.824746 1.90141 2.52698 + vertex 0.827227 1.90024 2.53019 + vertex 0.827665 1.9045 2.52754 + endloop + endfacet + facet normal -0.700312 0.481351 0.527128 + outer loop + vertex 0.826487 1.9115 2.52088 + vertex 0.824223 1.9105 2.51878 + vertex 0.824698 1.90844 2.5213 + endloop + endfacet + facet normal -0.648919 0.493063 0.579477 + outer loop + vertex 0.824698 1.90844 2.5213 + vertex 0.824248 1.90603 2.52284 + vertex 0.826082 1.90725 2.52386 + endloop + endfacet + facet normal -0.667404 0.469176 0.578313 + outer loop + vertex 0.826487 1.9115 2.52088 + vertex 0.824698 1.90844 2.5213 + vertex 0.826082 1.90725 2.52386 + endloop + endfacet + facet normal -0.650916 0.476494 0.590983 + outer loop + vertex 0.826487 1.9115 2.52088 + vertex 0.826082 1.90725 2.52386 + vertex 0.828532 1.90901 2.52514 + endloop + endfacet + facet normal -0.698918 0.418384 0.580059 + outer loop + vertex 0.826487 1.9115 2.52088 + vertex 0.828532 1.90901 2.52514 + vertex 0.828698 1.91174 2.52337 + endloop + endfacet + facet normal -0.645681 0.451279 0.61599 + outer loop + vertex 0.828532 1.90901 2.52514 + vertex 0.826082 1.90725 2.52386 + vertex 0.827665 1.9045 2.52754 + endloop + endfacet + facet normal -0.780841 0.434002 0.449366 + outer loop + vertex 0.826583 1.91737 2.51621 + vertex 0.824283 1.91568 2.51385 + vertex 0.824781 1.91344 2.51688 + endloop + endfacet + facet normal -0.701116 0.476847 0.530144 + outer loop + vertex 0.824781 1.91344 2.51688 + vertex 0.824223 1.9105 2.51878 + vertex 0.826487 1.9115 2.52088 + endloop + endfacet + facet normal -0.7385 0.426903 0.521893 + outer loop + vertex 0.826583 1.91737 2.51621 + vertex 0.824781 1.91344 2.51688 + vertex 0.826487 1.9115 2.52088 + endloop + endfacet + facet normal -0.717337 0.440679 0.539657 + outer loop + vertex 0.826583 1.91737 2.51621 + vertex 0.826487 1.9115 2.52088 + vertex 0.828723 1.91453 2.52138 + endloop + endfacet + facet normal -0.773364 0.362739 0.519931 + outer loop + vertex 0.826583 1.91737 2.51621 + vertex 0.828723 1.91453 2.52138 + vertex 0.828737 1.9173 2.51947 + endloop + endfacet + facet normal -0.698426 0.420022 0.579467 + outer loop + vertex 0.828723 1.91453 2.52138 + vertex 0.826487 1.9115 2.52088 + vertex 0.828698 1.91174 2.52337 + endloop + endfacet + facet normal -0.857831 0.374671 0.351779 + outer loop + vertex 0.825843 1.92238 2.51037 + vertex 0.824297 1.92032 2.50879 + vertex 0.82473 1.91856 2.51173 + endloop + endfacet + facet normal -0.779678 0.445789 0.439744 + outer loop + vertex 0.82473 1.91856 2.51173 + vertex 0.824283 1.91568 2.51385 + vertex 0.826583 1.91737 2.51621 + endloop + endfacet + facet normal -0.809595 0.391149 0.437674 + outer loop + vertex 0.82473 1.91856 2.51173 + vertex 0.826583 1.91737 2.51621 + vertex 0.825843 1.92238 2.51037 + endloop + endfacet + facet normal -0.851618 0.339874 0.399039 + outer loop + vertex 0.825843 1.92238 2.51037 + vertex 0.826583 1.91737 2.51621 + vertex 0.827769 1.92275 2.51417 + endloop + endfacet + facet normal -0.772249 0.367629 0.51815 + outer loop + vertex 0.826583 1.91737 2.51621 + vertex 0.829049 1.92009 2.51796 + vertex 0.827769 1.92275 2.51417 + endloop + endfacet + facet normal -0.772002 0.366781 0.519119 + outer loop + vertex 0.828737 1.9173 2.51947 + vertex 0.829049 1.92009 2.51796 + vertex 0.826583 1.91737 2.51621 + endloop + endfacet + facet normal -0.930847 0.260352 0.256399 + outer loop + vertex 0.824917 1.92952 2.50088 + vertex 0.823908 1.92706 2.49972 + vertex 0.82418 1.92481 2.50299 + endloop + endfacet + facet normal -0.91204 0.277715 0.301758 + outer loop + vertex 0.82575 1.92737 2.50538 + vertex 0.824917 1.92952 2.50088 + vertex 0.82418 1.92481 2.50299 + endloop + endfacet + facet normal -0.912459 0.304799 0.272975 + outer loop + vertex 0.824677 1.92309 2.50657 + vertex 0.82575 1.92737 2.50538 + vertex 0.82418 1.92481 2.50299 + endloop + endfacet + facet normal -0.85855 0.38703 0.336301 + outer loop + vertex 0.824677 1.92309 2.50657 + vertex 0.824297 1.92032 2.50879 + vertex 0.825843 1.92238 2.51037 + endloop + endfacet + facet normal -0.888873 0.315435 0.332274 + outer loop + vertex 0.824677 1.92309 2.50657 + vertex 0.825843 1.92238 2.51037 + vertex 0.82575 1.92737 2.50538 + endloop + endfacet + facet normal -0.891643 0.31158 0.328468 + outer loop + vertex 0.82575 1.92737 2.50538 + vertex 0.825843 1.92238 2.51037 + vertex 0.827565 1.92723 2.51044 + endloop + endfacet + facet normal -0.802299 0.313834 0.507764 + outer loop + vertex 0.828948 1.926 2.51402 + vertex 0.827769 1.92275 2.51417 + vertex 0.829537 1.92373 2.51635 + endloop + endfacet + facet normal -0.839591 0.324042 0.435985 + outer loop + vertex 0.828948 1.926 2.51402 + vertex 0.827565 1.92723 2.51044 + vertex 0.827769 1.92275 2.51417 + endloop + endfacet + facet normal -0.862211 0.299933 0.408206 + outer loop + vertex 0.827565 1.92723 2.51044 + vertex 0.825843 1.92238 2.51037 + vertex 0.827769 1.92275 2.51417 + endloop + endfacet + facet normal -0.801196 0.328258 0.500331 + outer loop + vertex 0.829537 1.92373 2.51635 + vertex 0.827769 1.92275 2.51417 + vertex 0.829049 1.92009 2.51796 + endloop + endfacet + facet normal -0.877229 0.143531 0.458115 + outer loop + vertex 0.825 1.93285 2.5 + vertex 0.823908 1.92706 2.49972 + vertex 0.824917 1.92952 2.50088 + endloop + endfacet + facet normal -0.573154 0.223668 0.788332 + outer loop + vertex 0.825 1.93285 2.5 + vertex 0.824917 1.92952 2.50088 + vertex 0.825839 1.935 2.5 + endloop + endfacet + facet normal -0.856361 0.219557 0.467376 + outer loop + vertex 0.825839 1.935 2.5 + vertex 0.824917 1.92952 2.50088 + vertex 0.826048 1.9329 2.50137 + endloop + endfacet + facet normal -0.917587 0.264723 0.296574 + outer loop + vertex 0.824917 1.92952 2.50088 + vertex 0.82575 1.92737 2.50538 + vertex 0.826048 1.9329 2.50137 + endloop + endfacet + facet normal -0.931266 0.245565 0.26915 + outer loop + vertex 0.826048 1.9329 2.50137 + vertex 0.82575 1.92737 2.50538 + vertex 0.82738 1.93275 2.50611 + endloop + endfacet + facet normal -0.866502 0.236508 0.439588 + outer loop + vertex 0.8286 1.93123 2.51033 + vertex 0.827565 1.92723 2.51044 + vertex 0.829215 1.92885 2.51282 + endloop + endfacet + facet normal -0.904576 0.24384 0.349691 + outer loop + vertex 0.8286 1.93123 2.51033 + vertex 0.82738 1.93275 2.50611 + vertex 0.827565 1.92723 2.51044 + endloop + endfacet + facet normal -0.913684 0.231352 0.334152 + outer loop + vertex 0.82738 1.93275 2.50611 + vertex 0.82575 1.92737 2.50538 + vertex 0.827565 1.92723 2.51044 + endloop + endfacet + facet normal -0.867407 0.259584 0.424524 + outer loop + vertex 0.829215 1.92885 2.51282 + vertex 0.827565 1.92723 2.51044 + vertex 0.828948 1.926 2.51402 + endloop + endfacet + facet normal -0.672484 0.679929 0.292337 + outer loop + vertex 0.825 1.93632 2.495 + vertex 0.825 1.935 2.49807 + vertex 0.825839 1.935 2.5 + endloop + endfacet + facet normal -0.804012 0.527617 0.274198 + outer loop + vertex 0.825 1.93632 2.495 + vertex 0.825839 1.935 2.5 + vertex 0.827415 1.94 2.495 + endloop + endfacet + facet normal -0.891188 -0.147937 -0.428834 + outer loop + vertex 0.827415 1.94 2.495 + vertex 0.825839 1.935 2.5 + vertex 0.826539 1.93809 2.49748 + endloop + endfacet + facet normal 0.379429 0.531753 0.757148 + outer loop + vertex 0.825839 1.935 2.5 + vertex 0.826048 1.9329 2.50137 + vertex 0.826539 1.93809 2.49748 + endloop + endfacet + facet normal -0.964919 0.209687 0.157996 + outer loop + vertex 0.826539 1.93809 2.49748 + vertex 0.826048 1.9329 2.50137 + vertex 0.827026 1.93758 2.50113 + endloop + endfacet + facet normal -0.939517 0.210258 0.27037 + outer loop + vertex 0.826048 1.9329 2.50137 + vertex 0.82738 1.93275 2.50611 + vertex 0.827026 1.93758 2.50113 + endloop + endfacet + facet normal -0.962154 0.1584 0.22174 + outer loop + vertex 0.827026 1.93758 2.50113 + vertex 0.82738 1.93275 2.50611 + vertex 0.828073 1.93855 2.50498 + endloop + endfacet + facet normal -0.919199 0.178612 0.350958 + outer loop + vertex 0.82738 1.93275 2.50611 + vertex 0.829026 1.93541 2.50907 + vertex 0.828073 1.93855 2.50498 + endloop + endfacet + facet normal -0.921035 0.195326 0.336961 + outer loop + vertex 0.8286 1.93123 2.51033 + vertex 0.829026 1.93541 2.50907 + vertex 0.82738 1.93275 2.50611 + endloop + endfacet + facet normal -0.949532 0.0301999 -0.312212 + outer loop + vertex 0.827415 1.94 2.495 + vertex 0.826539 1.93809 2.49748 + vertex 0.827574 1.945 2.495 + endloop + endfacet + facet normal -0.988092 0.153181 0.0145185 + outer loop + vertex 0.827574 1.945 2.495 + vertex 0.826539 1.93809 2.49748 + vertex 0.827247 1.9427 2.49704 + endloop + endfacet + facet normal -0.974497 0.164195 0.152954 + outer loop + vertex 0.826539 1.93809 2.49748 + vertex 0.827026 1.93758 2.50113 + vertex 0.827247 1.9427 2.49704 + endloop + endfacet + facet normal -0.98436 0.133894 0.11449 + outer loop + vertex 0.827247 1.9427 2.49704 + vertex 0.827026 1.93758 2.50113 + vertex 0.827658 1.94259 2.50071 + endloop + endfacet + facet normal -0.963772 0.140641 0.226636 + outer loop + vertex 0.827026 1.93758 2.50113 + vertex 0.828073 1.93855 2.50498 + vertex 0.827658 1.94259 2.50071 + endloop + endfacet + facet normal -0.967328 0.130481 0.217374 + outer loop + vertex 0.827658 1.94259 2.50071 + vertex 0.828073 1.93855 2.50498 + vertex 0.828533 1.94314 2.50427 + endloop + endfacet + facet normal -0.921904 0.147667 0.358172 + outer loop + vertex 0.828073 1.93855 2.50498 + vertex 0.829432 1.94019 2.5078 + vertex 0.828533 1.94314 2.50427 + endloop + endfacet + facet normal -0.922849 0.170327 0.345454 + outer loop + vertex 0.829026 1.93541 2.50907 + vertex 0.829432 1.94019 2.5078 + vertex 0.828073 1.93855 2.50498 + endloop + endfacet + facet normal -0.993323 0.109864 -0.0351925 + outer loop + vertex 0.827574 1.945 2.495 + vertex 0.827247 1.9427 2.49704 + vertex 0.828127 1.95 2.495 + endloop + endfacet + facet normal -0.985983 0.0775014 -0.147755 + outer loop + vertex 0.828127 1.95 2.495 + vertex 0.827247 1.9427 2.49704 + vertex 0.827708 1.94733 2.49639 + endloop + endfacet + facet normal -0.98686 0.114315 0.114188 + outer loop + vertex 0.827247 1.9427 2.49704 + vertex 0.827658 1.94259 2.50071 + vertex 0.827708 1.94733 2.49639 + endloop + endfacet + facet normal -0.983834 0.12609 0.127166 + outer loop + vertex 0.827708 1.94733 2.49639 + vertex 0.827658 1.94259 2.50071 + vertex 0.828237 1.94727 2.50054 + endloop + endfacet + facet normal -0.900028 0.198124 0.388195 + outer loop + vertex 0.829188 1.94617 2.50424 + vertex 0.828533 1.94314 2.50427 + vertex 0.829709 1.94391 2.5066 + endloop + endfacet + facet normal -0.931804 0.204073 0.30016 + outer loop + vertex 0.829188 1.94617 2.50424 + vertex 0.828237 1.94727 2.50054 + vertex 0.828533 1.94314 2.50427 + endloop + endfacet + facet normal -0.967618 0.12737 0.217926 + outer loop + vertex 0.828237 1.94727 2.50054 + vertex 0.827658 1.94259 2.50071 + vertex 0.828533 1.94314 2.50427 + endloop + endfacet + facet normal -0.900367 0.192603 0.390183 + outer loop + vertex 0.829709 1.94391 2.5066 + vertex 0.828533 1.94314 2.50427 + vertex 0.829432 1.94019 2.5078 + endloop + endfacet + facet normal -0.716612 -0.492105 -0.494267 + outer loop + vertex 0.83 1.95 2.49228 + vertex 0.828139 1.955 2.49 + vertex 0.83 1.95229 2.49 + endloop + endfacet + facet normal -0.717022 -0.492024 -0.493754 + outer loop + vertex 0.83 1.95 2.49228 + vertex 0.828127 1.95 2.495 + vertex 0.828139 1.955 2.49 + endloop + endfacet + facet normal 0.645807 -0.540643 -0.539109 + outer loop + vertex 0.828127 1.95 2.495 + vertex 0.827961 1.95268 2.49211 + vertex 0.828139 1.955 2.49 + endloop + endfacet + facet normal 0.881707 -0.319425 -0.347218 + outer loop + vertex 0.828127 1.95 2.495 + vertex 0.827708 1.94733 2.49639 + vertex 0.827961 1.95268 2.49211 + endloop + endfacet + facet normal -0.989916 0.113996 0.0840866 + outer loop + vertex 0.827961 1.95268 2.49211 + vertex 0.827708 1.94733 2.49639 + vertex 0.828181 1.95191 2.49574 + endloop + endfacet + facet normal -0.931569 0.189822 0.310074 + outer loop + vertex 0.828671 1.95096 2.49959 + vertex 0.828237 1.94727 2.50054 + vertex 0.829253 1.94894 2.50257 + endloop + endfacet + facet normal -0.974059 0.156839 0.163128 + outer loop + vertex 0.828671 1.95096 2.49959 + vertex 0.828181 1.95191 2.49574 + vertex 0.828237 1.94727 2.50054 + endloop + endfacet + facet normal -0.984648 0.119556 0.127179 + outer loop + vertex 0.828181 1.95191 2.49574 + vertex 0.827708 1.94733 2.49639 + vertex 0.828237 1.94727 2.50054 + endloop + endfacet + facet normal -0.932201 0.202702 0.299854 + outer loop + vertex 0.829253 1.94894 2.50257 + vertex 0.828237 1.94727 2.50054 + vertex 0.829188 1.94617 2.50424 + endloop + endfacet + facet normal -0.998013 0.0233543 -0.0585237 + outer loop + vertex 0.828139 1.955 2.49 + vertex 0.827961 1.95268 2.49211 + vertex 0.828256 1.96 2.49 + endloop + endfacet + facet normal -0.891301 0.158406 0.424841 + outer loop + vertex 0.828256 1.96 2.49 + vertex 0.827961 1.95268 2.49211 + vertex 0.828594 1.95694 2.49185 + endloop + endfacet + facet normal -0.961963 0.204128 0.181546 + outer loop + vertex 0.828863 1.95617 2.49458 + vertex 0.828181 1.95191 2.49574 + vertex 0.828906 1.95384 2.49741 + endloop + endfacet + facet normal -0.968662 0.196921 0.151378 + outer loop + vertex 0.828863 1.95617 2.49458 + vertex 0.828594 1.95694 2.49185 + vertex 0.828181 1.95191 2.49574 + endloop + endfacet + facet normal -0.984103 0.152028 0.0918089 + outer loop + vertex 0.828594 1.95694 2.49185 + vertex 0.827961 1.95268 2.49211 + vertex 0.828181 1.95191 2.49574 + endloop + endfacet + facet normal -0.961958 0.209947 0.17481 + outer loop + vertex 0.828906 1.95384 2.49741 + vertex 0.828181 1.95191 2.49574 + vertex 0.828671 1.95096 2.49959 + endloop + endfacet + facet normal -0.67137 0.310571 -0.672911 + outer loop + vertex 0.83 1.96 2.48826 + vertex 0.828256 1.96 2.49 + vertex 0.83 1.96377 2.49 + endloop + endfacet + facet normal -0.972904 0.219694 0.072065 + outer loop + vertex 0.83 1.96377 2.49 + vertex 0.828594 1.95694 2.49185 + vertex 0.83 1.96213 2.495 + endloop + endfacet + facet normal -0.687939 0.318236 0.652277 + outer loop + vertex 0.828256 1.96 2.49 + vertex 0.828594 1.95694 2.49185 + vertex 0.83 1.96377 2.49 + endloop + endfacet + facet normal -0.973678 0.175233 0.145759 + outer loop + vertex 0.83 1.96213 2.495 + vertex 0.828594 1.95694 2.49185 + vertex 0.828863 1.95617 2.49458 + endloop + endfacet + facet normal 0.953131 -0.127632 -0.27432 + outer loop + vertex 0.83 1.96942 2.485 + vertex 0.829534 1.96882 2.48366 + vertex 0.83 1.97 2.48473 + endloop + endfacet + facet normal -0.807428 -0.380793 0.450618 + outer loop + vertex 0.83 1.96942 2.485 + vertex 0.83 1.97 2.48549 + vertex 0.829534 1.96882 2.48366 + endloop + endfacet + facet normal -0.0417768 0.680779 -0.731296 + outer loop + vertex 0.83 1.97 2.48473 + vertex 0.829534 1.96882 2.48366 + vertex 0.83 1.97029 2.485 + endloop + endfacet + facet normal -0.972525 0.200377 0.118511 + outer loop + vertex 0.83 1.97029 2.485 + vertex 0.829534 1.96882 2.48366 + vertex 0.83 1.97 2.48549 + endloop + endfacet + facet normal 0.920369 -0.0766563 -0.383465 + outer loop + vertex 0.835 1.04375 2.485 + vertex 0.834531 1.04419 2.48379 + vertex 0.835 1.045 2.48475 + endloop + endfacet + facet normal -0.933945 -0.220551 0.281255 + outer loop + vertex 0.835 1.04375 2.485 + vertex 0.835 1.045 2.48598 + vertex 0.834531 1.04419 2.48379 + endloop + endfacet + facet normal 0.553965 0.483729 -0.67759 + outer loop + vertex 0.835 1.045 2.48475 + vertex 0.834531 1.04419 2.48379 + vertex 0.835 1.04535 2.485 + endloop + endfacet + facet normal -0.954597 0.280549 0.100182 + outer loop + vertex 0.835 1.04535 2.485 + vertex 0.834531 1.04419 2.48379 + vertex 0.835 1.045 2.48598 + endloop + endfacet + facet normal 0.134066 -0.291797 -0.947038 + outer loop + vertex 0.835 1.05 2.48992 + vertex 0.835 1.04974 2.49 + vertex 0.834423 1.05136 2.48942 + endloop + endfacet + facet normal 0.565313 -0.0924182 -0.819683 + outer loop + vertex 0.835 1.04974 2.49 + vertex 0.834834 1.04938 2.48993 + vertex 0.834423 1.05136 2.48942 + endloop + endfacet + facet normal -0.635716 -0.0722306 -0.768536 + outer loop + vertex 0.835 1.05 2.48992 + vertex 0.834335 1.055 2.49 + vertex 0.835 1.055 2.48945 + endloop + endfacet + facet normal 0.791253 0.114852 -0.600606 + outer loop + vertex 0.834423 1.05136 2.48942 + vertex 0.834335 1.055 2.49 + vertex 0.835 1.05 2.48992 + endloop + endfacet + facet normal -0.979963 -0.0542472 0.19165 + outer loop + vertex 0.834423 1.05136 2.48942 + vertex 0.835 1.055 2.4934 + vertex 0.834335 1.055 2.49 + endloop + endfacet + facet normal -0.956666 -0.132099 0.259499 + outer loop + vertex 0.834834 1.04938 2.48993 + vertex 0.835 1.055 2.4934 + vertex 0.834423 1.05136 2.48942 + endloop + endfacet + facet normal -0.954739 -0.231541 0.186717 + outer loop + vertex 0.835 1.05629 2.495 + vertex 0.834335 1.055 2.49 + vertex 0.835 1.055 2.4934 + endloop + endfacet + facet normal -0.912562 -0.349909 0.211649 + outer loop + vertex 0.835 1.05629 2.495 + vertex 0.832887 1.06002 2.49205 + vertex 0.834335 1.055 2.49 + endloop + endfacet + facet normal -0.923797 -0.339219 0.177564 + outer loop + vertex 0.832887 1.06002 2.49205 + vertex 0.832499 1.06 2.49 + vertex 0.834335 1.055 2.49 + endloop + endfacet + facet normal 0.140502 -0.564212 -0.813587 + outer loop + vertex 0.835 1.05629 2.495 + vertex 0.833982 1.05728 2.49414 + vertex 0.832887 1.06002 2.49205 + endloop + endfacet + facet normal -0.981337 -0.0484773 0.186085 + outer loop + vertex 0.832499 1.06 2.49 + vertex 0.832887 1.06002 2.49205 + vertex 0.832252 1.065 2.49 + endloop + endfacet + facet normal -0.991321 -0.130976 -0.0113096 + outer loop + vertex 0.832252 1.065 2.49 + vertex 0.832887 1.06002 2.49205 + vertex 0.832195 1.065 2.495 + endloop + endfacet + facet normal -0.951197 -0.2763 0.137412 + outer loop + vertex 0.833349 1.06002 2.49525 + vertex 0.832887 1.06002 2.49205 + vertex 0.833982 1.05728 2.49414 + endloop + endfacet + facet normal -0.964972 -0.222257 0.139393 + outer loop + vertex 0.833349 1.06002 2.49525 + vertex 0.832297 1.06504 2.49597 + vertex 0.832887 1.06002 2.49205 + endloop + endfacet + facet normal -0.97354 -0.2003 0.110002 + outer loop + vertex 0.832297 1.06504 2.49597 + vertex 0.832195 1.065 2.495 + vertex 0.832887 1.06002 2.49205 + endloop + endfacet + facet normal -0.94878 -0.229962 0.216644 + outer loop + vertex 0.833349 1.06002 2.49525 + vertex 0.83367 1.06174 2.49849 + vertex 0.832297 1.06504 2.49597 + endloop + endfacet + facet normal -0.984357 -0.138596 0.108782 + outer loop + vertex 0.832195 1.065 2.495 + vertex 0.832297 1.06504 2.49597 + vertex 0.831491 1.07 2.495 + endloop + endfacet + facet normal -0.957741 -0.196762 -0.2098 + outer loop + vertex 0.831491 1.07 2.495 + vertex 0.832297 1.06504 2.49597 + vertex 0.831182 1.07031 2.49613 + endloop + endfacet + facet normal -0.948273 -0.221637 0.227278 + outer loop + vertex 0.833371 1.06499 2.50041 + vertex 0.832297 1.06504 2.49597 + vertex 0.83367 1.06174 2.49849 + endloop + endfacet + facet normal -0.952152 -0.203073 0.228404 + outer loop + vertex 0.833371 1.06499 2.50041 + vertex 0.832344 1.0699 2.50049 + vertex 0.832297 1.06504 2.49597 + endloop + endfacet + facet normal -0.949829 -0.207949 0.233627 + outer loop + vertex 0.832344 1.0699 2.50049 + vertex 0.831182 1.07031 2.49613 + vertex 0.832297 1.06504 2.49597 + endloop + endfacet + facet normal -0.93104 -0.199913 0.305287 + outer loop + vertex 0.833371 1.06499 2.50041 + vertex 0.834031 1.06688 2.50366 + vertex 0.832344 1.0699 2.50049 + endloop + endfacet + facet normal -0.958452 -0.191494 -0.211424 + outer loop + vertex 0.831491 1.07 2.495 + vertex 0.831182 1.07031 2.49613 + vertex 0.830492 1.075 2.495 + endloop + endfacet + facet normal -0.987376 -0.120299 0.103035 + outer loop + vertex 0.830492 1.075 2.495 + vertex 0.831182 1.07031 2.49613 + vertex 0.830941 1.07365 2.49773 + endloop + endfacet + facet normal -0.954235 -0.182097 0.237226 + outer loop + vertex 0.831182 1.07031 2.49613 + vertex 0.832344 1.0699 2.50049 + vertex 0.830941 1.07365 2.49773 + endloop + endfacet + facet normal -0.953758 -0.178554 0.241793 + outer loop + vertex 0.830941 1.07365 2.49773 + vertex 0.832344 1.0699 2.50049 + vertex 0.831426 1.07506 2.50068 + endloop + endfacet + facet normal -0.925526 -0.154084 0.345918 + outer loop + vertex 0.834037 1.07038 2.50523 + vertex 0.832344 1.0699 2.50049 + vertex 0.834031 1.06688 2.50366 + endloop + endfacet + facet normal -0.921063 -0.177319 0.346701 + outer loop + vertex 0.834037 1.07038 2.50523 + vertex 0.833023 1.07487 2.50483 + vertex 0.832344 1.0699 2.50049 + endloop + endfacet + facet normal -0.921443 -0.176671 0.346019 + outer loop + vertex 0.833023 1.07487 2.50483 + vertex 0.831426 1.07506 2.50068 + vertex 0.832344 1.0699 2.50049 + endloop + endfacet + facet normal -0.815821 -0.134201 0.562517 + outer loop + vertex 0.834037 1.07038 2.50523 + vertex 0.835478 1.07343 2.50805 + vertex 0.833023 1.07487 2.50483 + endloop + endfacet + facet normal -0.929376 -0.15449 0.335252 + outer loop + vertex 0.83 1.08 2.49594 + vertex 0.83 1.07796 2.495 + vertex 0.830492 1.075 2.495 + endloop + endfacet + facet normal -0.956347 -0.142121 0.255345 + outer loop + vertex 0.83 1.08 2.49594 + vertex 0.830492 1.075 2.495 + vertex 0.831084 1.08 2.5 + endloop + endfacet + facet normal -0.988558 -0.0306544 0.147695 + outer loop + vertex 0.831084 1.08 2.5 + vertex 0.830492 1.075 2.495 + vertex 0.830941 1.07365 2.49773 + endloop + endfacet + facet normal -0.982409 -0.042982 0.181727 + outer loop + vertex 0.830941 1.07365 2.49773 + vertex 0.831426 1.07506 2.50068 + vertex 0.831084 1.08 2.5 + endloop + endfacet + facet normal -0.996235 -0.0604201 0.0621722 + outer loop + vertex 0.831084 1.08 2.5 + vertex 0.831426 1.07506 2.50068 + vertex 0.831348 1.07832 2.50259 + endloop + endfacet + facet normal -0.913554 -0.221883 0.340862 + outer loop + vertex 0.831426 1.07506 2.50068 + vertex 0.833023 1.07487 2.50483 + vertex 0.831348 1.07832 2.50259 + endloop + endfacet + facet normal -0.9132 -0.220523 0.342689 + outer loop + vertex 0.831348 1.07832 2.50259 + vertex 0.833023 1.07487 2.50483 + vertex 0.832423 1.0802 2.50667 + endloop + endfacet + facet normal -0.712133 -0.298647 0.635355 + outer loop + vertex 0.833023 1.07487 2.50483 + vertex 0.835206 1.07872 2.50909 + vertex 0.832423 1.0802 2.50667 + endloop + endfacet + facet normal -0.817291 -0.15135 0.555993 + outer loop + vertex 0.835478 1.07343 2.50805 + vertex 0.835206 1.07872 2.50909 + vertex 0.833023 1.07487 2.50483 + endloop + endfacet + facet normal 0.844554 0.266915 -0.464203 + outer loop + vertex 0.829411 1.08296 2.49866 + vertex 0.83 1.08343 2.5 + vertex 0.831084 1.08 2.5 + endloop + endfacet + facet normal -0.8891 -0.417304 0.18804 + outer loop + vertex 0.829411 1.08296 2.49866 + vertex 0.831084 1.08 2.5 + vertex 0.830283 1.08286 2.50256 + endloop + endfacet + facet normal -0.972392 -0.228076 -0.0493441 + outer loop + vertex 0.830283 1.08286 2.50256 + vertex 0.831084 1.08 2.5 + vertex 0.831348 1.07832 2.50259 + endloop + endfacet + facet normal -0.916153 -0.212596 0.339803 + outer loop + vertex 0.831348 1.07832 2.50259 + vertex 0.832423 1.0802 2.50667 + vertex 0.830283 1.08286 2.50256 + endloop + endfacet + facet normal -0.911562 -0.300895 0.280207 + outer loop + vertex 0.830283 1.08286 2.50256 + vertex 0.832423 1.0802 2.50667 + vertex 0.831338 1.08335 2.50651 + endloop + endfacet + facet normal -0.704181 -0.503216 0.500902 + outer loop + vertex 0.834046 1.08147 2.51022 + vertex 0.832423 1.0802 2.50667 + vertex 0.835206 1.07872 2.50909 + endloop + endfacet + facet normal -0.803303 -0.34096 0.488315 + outer loop + vertex 0.834046 1.08147 2.51022 + vertex 0.832686 1.08409 2.50982 + vertex 0.832423 1.0802 2.50667 + endloop + endfacet + facet normal -0.865673 -0.278321 0.416109 + outer loop + vertex 0.832686 1.08409 2.50982 + vertex 0.831338 1.08335 2.50651 + vertex 0.832423 1.0802 2.50667 + endloop + endfacet + facet normal -0.800992 -0.338958 0.493478 + outer loop + vertex 0.834046 1.08147 2.51022 + vertex 0.834274 1.08318 2.51177 + vertex 0.832686 1.08409 2.50982 + endloop + endfacet + facet normal -0.941923 -0.267109 0.20355 + outer loop + vertex 0.829411 1.08296 2.49866 + vertex 0.830283 1.08286 2.50256 + vertex 0.828862 1.0855 2.49945 + endloop + endfacet + facet normal -0.944068 -0.232062 0.234271 + outer loop + vertex 0.829138 1.08732 2.50237 + vertex 0.828862 1.0855 2.49945 + vertex 0.830283 1.08286 2.50256 + endloop + endfacet + facet normal -0.929437 -0.225804 0.291821 + outer loop + vertex 0.829138 1.08732 2.50237 + vertex 0.830283 1.08286 2.50256 + vertex 0.830499 1.08726 2.50665 + endloop + endfacet + facet normal -0.937707 -0.210817 0.276156 + outer loop + vertex 0.830499 1.08726 2.50665 + vertex 0.830283 1.08286 2.50256 + vertex 0.831338 1.08335 2.50651 + endloop + endfacet + facet normal -0.889111 -0.205084 0.409173 + outer loop + vertex 0.831338 1.08335 2.50651 + vertex 0.832686 1.08409 2.50982 + vertex 0.830499 1.08726 2.50665 + endloop + endfacet + facet normal -0.892248 -0.224822 0.391597 + outer loop + vertex 0.830499 1.08726 2.50665 + vertex 0.832686 1.08409 2.50982 + vertex 0.832216 1.08952 2.51186 + endloop + endfacet + facet normal -0.787137 -0.276016 0.55157 + outer loop + vertex 0.832686 1.08409 2.50982 + vertex 0.834617 1.08587 2.51346 + vertex 0.832216 1.08952 2.51186 + endloop + endfacet + facet normal -0.804989 -0.239027 0.543009 + outer loop + vertex 0.834274 1.08318 2.51177 + vertex 0.834617 1.08587 2.51346 + vertex 0.832686 1.08409 2.50982 + endloop + endfacet + facet normal -0.929466 -0.225668 0.291833 + outer loop + vertex 0.828696 1.09146 2.50416 + vertex 0.829138 1.08732 2.50237 + vertex 0.830499 1.08726 2.50665 + endloop + endfacet + facet normal -0.929113 -0.224176 0.294099 + outer loop + vertex 0.829795 1.09317 2.50893 + vertex 0.828696 1.09146 2.50416 + vertex 0.830499 1.08726 2.50665 + endloop + endfacet + facet normal -0.877982 -0.259772 0.402077 + outer loop + vertex 0.830499 1.08726 2.50665 + vertex 0.832216 1.08952 2.51186 + vertex 0.829795 1.09317 2.50893 + endloop + endfacet + facet normal -0.882294 -0.284188 0.375227 + outer loop + vertex 0.829795 1.09317 2.50893 + vertex 0.832216 1.08952 2.51186 + vertex 0.831039 1.09365 2.51222 + endloop + endfacet + facet normal -0.803545 -0.304292 0.511588 + outer loop + vertex 0.834629 1.08967 2.51574 + vertex 0.832216 1.08952 2.51186 + vertex 0.834617 1.08587 2.51346 + endloop + endfacet + facet normal -0.79557 -0.330673 0.507665 + outer loop + vertex 0.834629 1.08967 2.51574 + vertex 0.832677 1.09399 2.5155 + vertex 0.832216 1.08952 2.51186 + endloop + endfacet + facet normal -0.846381 -0.280668 0.452619 + outer loop + vertex 0.832677 1.09399 2.5155 + vertex 0.831039 1.09365 2.51222 + vertex 0.832216 1.08952 2.51186 + endloop + endfacet + facet normal -0.771292 -0.317146 0.55184 + outer loop + vertex 0.834629 1.08967 2.51574 + vertex 0.835428 1.09269 2.5186 + vertex 0.832677 1.09399 2.5155 + endloop + endfacet + facet normal -0.91108 -0.274201 0.30781 + outer loop + vertex 0.828696 1.09146 2.50416 + vertex 0.829795 1.09317 2.50893 + vertex 0.828175 1.09531 2.50605 + endloop + endfacet + facet normal -0.90933 -0.302038 0.286169 + outer loop + vertex 0.828472 1.09707 2.50885 + vertex 0.828175 1.09531 2.50605 + vertex 0.829795 1.09317 2.50893 + endloop + endfacet + facet normal -0.891973 -0.29491 0.342654 + outer loop + vertex 0.828472 1.09707 2.50885 + vertex 0.829795 1.09317 2.50893 + vertex 0.829696 1.09782 2.51268 + endloop + endfacet + facet normal -0.869365 -0.321036 0.375687 + outer loop + vertex 0.829696 1.09782 2.51268 + vertex 0.829795 1.09317 2.50893 + vertex 0.831039 1.09365 2.51222 + endloop + endfacet + facet normal -0.834255 -0.317992 0.450444 + outer loop + vertex 0.831039 1.09365 2.51222 + vertex 0.832677 1.09399 2.5155 + vertex 0.829696 1.09782 2.51268 + endloop + endfacet + facet normal -0.835808 -0.325072 0.44244 + outer loop + vertex 0.829696 1.09782 2.51268 + vertex 0.832677 1.09399 2.5155 + vertex 0.831869 1.09867 2.51741 + endloop + endfacet + facet normal -0.788452 -0.344387 0.509649 + outer loop + vertex 0.832677 1.09399 2.5155 + vertex 0.834312 1.09599 2.51938 + vertex 0.831869 1.09867 2.51741 + endloop + endfacet + facet normal -0.764711 -0.381869 0.519031 + outer loop + vertex 0.835428 1.09269 2.5186 + vertex 0.834312 1.09599 2.51938 + vertex 0.832677 1.09399 2.5155 + endloop + endfacet + facet normal -0.853569 -0.387245 0.348513 + outer loop + vertex 0.828472 1.09707 2.50885 + vertex 0.829696 1.09782 2.51268 + vertex 0.827688 1.0998 2.50996 + endloop + endfacet + facet normal -0.847138 -0.429106 0.31341 + outer loop + vertex 0.827012 1.10299 2.5125 + vertex 0.827688 1.0998 2.50996 + vertex 0.829696 1.09782 2.51268 + endloop + endfacet + facet normal -0.80761 -0.404557 0.429069 + outer loop + vertex 0.827012 1.10299 2.5125 + vertex 0.829696 1.09782 2.51268 + vertex 0.82933 1.10237 2.51628 + endloop + endfacet + facet normal -0.797254 -0.412752 0.440479 + outer loop + vertex 0.82933 1.10237 2.51628 + vertex 0.829696 1.09782 2.51268 + vertex 0.831869 1.09867 2.51741 + endloop + endfacet + facet normal -0.782338 -0.321056 0.533732 + outer loop + vertex 0.834128 1.09899 2.52092 + vertex 0.831869 1.09867 2.51741 + vertex 0.834312 1.09599 2.51938 + endloop + endfacet + facet normal -0.750135 -0.407338 0.520935 + outer loop + vertex 0.834128 1.09899 2.52092 + vertex 0.831604 1.10193 2.51958 + vertex 0.831869 1.09867 2.51741 + endloop + endfacet + facet normal -0.782086 -0.387874 0.487746 + outer loop + vertex 0.831604 1.10193 2.51958 + vertex 0.82933 1.10237 2.51628 + vertex 0.831869 1.09867 2.51741 + endloop + endfacet + facet normal -0.73992 -0.384397 0.552048 + outer loop + vertex 0.834128 1.09899 2.52092 + vertex 0.833999 1.10273 2.52335 + vertex 0.831604 1.10193 2.51958 + endloop + endfacet + facet normal -0.781304 -0.478487 0.400767 + outer loop + vertex 0.827012 1.10299 2.5125 + vertex 0.82933 1.10237 2.51628 + vertex 0.827131 1.10577 2.51606 + endloop + endfacet + facet normal -0.756325 -0.465399 0.459757 + outer loop + vertex 0.82933 1.10237 2.51628 + vertex 0.831604 1.10193 2.51958 + vertex 0.829328 1.10591 2.51986 + endloop + endfacet + facet normal -0.760801 -0.461696 0.45609 + outer loop + vertex 0.827131 1.10577 2.51606 + vertex 0.82933 1.10237 2.51628 + vertex 0.829328 1.10591 2.51986 + endloop + endfacet + facet normal -0.651549 -0.529872 0.54288 + outer loop + vertex 0.834194 1.10575 2.52604 + vertex 0.832092 1.1082 2.52591 + vertex 0.831026 1.10738 2.52383 + endloop + endfacet + facet normal -0.654656 -0.479556 0.584339 + outer loop + vertex 0.833999 1.10273 2.52335 + vertex 0.834194 1.10575 2.52604 + vertex 0.831026 1.10738 2.52383 + endloop + endfacet + facet normal -0.709849 -0.505156 0.490848 + outer loop + vertex 0.833999 1.10273 2.52335 + vertex 0.831026 1.10738 2.52383 + vertex 0.829328 1.10591 2.51986 + endloop + endfacet + facet normal -0.709919 -0.445039 0.545853 + outer loop + vertex 0.833999 1.10273 2.52335 + vertex 0.829328 1.10591 2.51986 + vertex 0.831604 1.10193 2.51958 + endloop + endfacet + facet normal -0.601774 -0.481948 0.636862 + outer loop + vertex 0.834194 1.10575 2.52604 + vertex 0.833953 1.10876 2.52809 + vertex 0.832092 1.1082 2.52591 + endloop + endfacet + facet normal -0.686109 -0.484462 0.542725 + outer loop + vertex 0.831026 1.10738 2.52383 + vertex 0.832092 1.1082 2.52591 + vertex 0.830183 1.11044 2.5255 + endloop + endfacet + facet normal -0.625846 -0.453467 0.634574 + outer loop + vertex 0.833343 1.11186 2.52986 + vertex 0.831565 1.11515 2.53045 + vertex 0.830445 1.11311 2.52789 + endloop + endfacet + facet normal -0.624906 -0.475263 0.619368 + outer loop + vertex 0.833953 1.10876 2.52809 + vertex 0.833343 1.11186 2.52986 + vertex 0.830445 1.11311 2.52789 + endloop + endfacet + facet normal -0.632361 -0.481881 0.606556 + outer loop + vertex 0.833953 1.10876 2.52809 + vertex 0.830445 1.11311 2.52789 + vertex 0.830183 1.11044 2.5255 + endloop + endfacet + facet normal -0.634168 -0.420763 0.648683 + outer loop + vertex 0.833953 1.10876 2.52809 + vertex 0.830183 1.11044 2.5255 + vertex 0.832092 1.1082 2.52591 + endloop + endfacet + facet normal -0.563072 -0.432148 0.704413 + outer loop + vertex 0.833343 1.11186 2.52986 + vertex 0.835571 1.1123 2.5319 + vertex 0.831565 1.11515 2.53045 + endloop + endfacet + facet normal -0.649028 -0.431052 0.626863 + outer loop + vertex 0.827679 1.11755 2.52808 + vertex 0.830445 1.11311 2.52789 + vertex 0.831565 1.11515 2.53045 + endloop + endfacet + facet normal -0.651246 -0.450946 0.61035 + outer loop + vertex 0.830147 1.11783 2.53092 + vertex 0.827679 1.11755 2.52808 + vertex 0.831565 1.11515 2.53045 + endloop + endfacet + facet normal -0.590415 -0.431335 0.682173 + outer loop + vertex 0.831565 1.11515 2.53045 + vertex 0.833603 1.11722 2.53353 + vertex 0.830147 1.11783 2.53092 + endloop + endfacet + facet normal -0.570992 -0.453551 0.684295 + outer loop + vertex 0.835571 1.1123 2.5319 + vertex 0.833603 1.11722 2.53353 + vertex 0.831565 1.11515 2.53045 + endloop + endfacet + facet normal -0.663717 -0.421038 0.618229 + outer loop + vertex 0.827679 1.11755 2.52808 + vertex 0.830147 1.11783 2.53092 + vertex 0.828736 1.12061 2.5313 + endloop + endfacet + facet normal -0.600872 -0.445839 0.663461 + outer loop + vertex 0.833727 1.12073 2.53602 + vertex 0.831275 1.124 2.53599 + vertex 0.830244 1.12239 2.53398 + endloop + endfacet + facet normal -0.601009 -0.448359 0.661636 + outer loop + vertex 0.833603 1.11722 2.53353 + vertex 0.833727 1.12073 2.53602 + vertex 0.830244 1.12239 2.53398 + endloop + endfacet + facet normal -0.612465 -0.454501 0.646773 + outer loop + vertex 0.833603 1.11722 2.53353 + vertex 0.830244 1.12239 2.53398 + vertex 0.828736 1.12061 2.5313 + endloop + endfacet + facet normal -0.596106 -0.397564 0.697568 + outer loop + vertex 0.833603 1.11722 2.53353 + vertex 0.828736 1.12061 2.5313 + vertex 0.830147 1.11783 2.53092 + endloop + endfacet + facet normal -0.581465 -0.431062 0.689989 + outer loop + vertex 0.833727 1.12073 2.53602 + vertex 0.834259 1.12362 2.53827 + vertex 0.831275 1.124 2.53599 + endloop + endfacet + facet normal -0.640253 -0.406126 0.652026 + outer loop + vertex 0.830244 1.12239 2.53398 + vertex 0.831275 1.124 2.53599 + vertex 0.82902 1.12566 2.53481 + endloop + endfacet + facet normal -0.630464 -0.372293 0.681112 + outer loop + vertex 0.831275 1.124 2.53599 + vertex 0.830583 1.127 2.53699 + vertex 0.82902 1.12566 2.53481 + endloop + endfacet + facet normal -0.592324 -0.374291 0.713484 + outer loop + vertex 0.831275 1.124 2.53599 + vertex 0.834259 1.12362 2.53827 + vertex 0.830583 1.127 2.53699 + endloop + endfacet + facet normal -0.609352 -0.404838 0.68176 + outer loop + vertex 0.834259 1.12362 2.53827 + vertex 0.833076 1.12762 2.53959 + vertex 0.830583 1.127 2.53699 + endloop + endfacet + facet normal -0.649242 -0.310213 0.694444 + outer loop + vertex 0.833654 1.13027 2.54137 + vertex 0.831486 1.13442 2.5412 + vertex 0.829931 1.13136 2.53838 + endloop + endfacet + facet normal -0.648696 -0.323093 0.689061 + outer loop + vertex 0.833654 1.13027 2.54137 + vertex 0.829931 1.13136 2.53838 + vertex 0.833076 1.12762 2.53959 + endloop + endfacet + facet normal -0.644807 -0.317879 0.695109 + outer loop + vertex 0.833076 1.12762 2.53959 + vertex 0.829931 1.13136 2.53838 + vertex 0.830583 1.127 2.53699 + endloop + endfacet + facet normal -0.639447 -0.304623 0.705912 + outer loop + vertex 0.833654 1.13027 2.54137 + vertex 0.835089 1.13265 2.5437 + vertex 0.831486 1.13442 2.5412 + endloop + endfacet + facet normal -0.739533 -0.0299992 0.672452 + outer loop + vertex 0.829676 1.18448 2.55247 + vertex 0.826698 1.18419 2.54918 + vertex 0.828455 1.18119 2.55098 + endloop + endfacet + facet normal -0.728867 -0.0676202 0.681308 + outer loop + vertex 0.828455 1.18119 2.55098 + vertex 0.830296 1.17742 2.55258 + vertex 0.832026 1.18031 2.55471 + endloop + endfacet + facet normal -0.726784 -0.0407026 0.685659 + outer loop + vertex 0.828455 1.18119 2.55098 + vertex 0.832026 1.18031 2.55471 + vertex 0.829676 1.18448 2.55247 + endloop + endfacet + facet normal -0.743258 -0.06041 0.666271 + outer loop + vertex 0.829676 1.18448 2.55247 + vertex 0.832026 1.18031 2.55471 + vertex 0.832428 1.18421 2.55551 + endloop + endfacet + facet normal -0.743252 -0.0633521 0.666005 + outer loop + vertex 0.831546 1.18846 2.55493 + vertex 0.829676 1.18448 2.55247 + vertex 0.832428 1.18421 2.55551 + endloop + endfacet + facet normal -0.729335 -0.0583242 0.681666 + outer loop + vertex 0.832428 1.18421 2.55551 + vertex 0.834399 1.18651 2.55782 + vertex 0.831546 1.18846 2.55493 + endloop + endfacet + facet normal -0.729016 -0.0588895 0.681959 + outer loop + vertex 0.834707 1.18205 2.55776 + vertex 0.834399 1.18651 2.55782 + vertex 0.832428 1.18421 2.55551 + endloop + endfacet + facet normal -0.655843 -0.170616 0.735364 + outer loop + vertex 0.827791 1.26698 2.56962 + vertex 0.829704 1.26719 2.57138 + vertex 0.828702 1.26997 2.57113 + endloop + endfacet + facet normal -0.643435 -0.146725 0.751308 + outer loop + vertex 0.832925 1.27095 2.57503 + vertex 0.832482 1.27464 2.57537 + vertex 0.830431 1.27241 2.57318 + endloop + endfacet + facet normal -0.648476 -0.166129 0.742886 + outer loop + vertex 0.831991 1.26747 2.57344 + vertex 0.832925 1.27095 2.57503 + vertex 0.830431 1.27241 2.57318 + endloop + endfacet + facet normal -0.647631 -0.16582 0.743692 + outer loop + vertex 0.831991 1.26747 2.57344 + vertex 0.830431 1.27241 2.57318 + vertex 0.828702 1.26997 2.57113 + endloop + endfacet + facet normal -0.648129 -0.167149 0.742961 + outer loop + vertex 0.831991 1.26747 2.57344 + vertex 0.828702 1.26997 2.57113 + vertex 0.829704 1.26719 2.57138 + endloop + endfacet + facet normal -0.646667 -0.141932 0.749451 + outer loop + vertex 0.829529 1.27692 2.57326 + vertex 0.830431 1.27241 2.57318 + vertex 0.832482 1.27464 2.57537 + endloop + endfacet + facet normal -0.639556 -0.12424 0.758639 + outer loop + vertex 0.831961 1.27928 2.57569 + vertex 0.829529 1.27692 2.57326 + vertex 0.832482 1.27464 2.57537 + endloop + endfacet + facet normal -0.64269 -0.119114 0.75681 + outer loop + vertex 0.82891 1.28173 2.57349 + vertex 0.829529 1.27692 2.57326 + vertex 0.831961 1.27928 2.57569 + endloop + endfacet + facet normal -0.639404 -0.111472 0.760747 + outer loop + vertex 0.831356 1.28427 2.57591 + vertex 0.82891 1.28173 2.57349 + vertex 0.831961 1.27928 2.57569 + endloop + endfacet + facet normal -0.641518 -0.108189 0.75944 + outer loop + vertex 0.828234 1.28681 2.57364 + vertex 0.82891 1.28173 2.57349 + vertex 0.831356 1.28427 2.57591 + endloop + endfacet + facet normal -0.643452 -0.112615 0.757158 + outer loop + vertex 0.830591 1.28938 2.57602 + vertex 0.828234 1.28681 2.57364 + vertex 0.831356 1.28427 2.57591 + endloop + endfacet + facet normal -0.64559 -0.1094 0.755808 + outer loop + vertex 0.827033 1.29245 2.57343 + vertex 0.828234 1.28681 2.57364 + vertex 0.830591 1.28938 2.57602 + endloop + endfacet + facet normal -0.651607 -0.122411 0.748615 + outer loop + vertex 0.829815 1.29344 2.57601 + vertex 0.827033 1.29245 2.57343 + vertex 0.830591 1.28938 2.57602 + endloop + endfacet + facet normal -0.650499 -0.126339 0.748925 + outer loop + vertex 0.827033 1.29245 2.57343 + vertex 0.829815 1.29344 2.57601 + vertex 0.828073 1.296 2.57493 + endloop + endfacet + facet normal -0.649917 -0.125682 0.749541 + outer loop + vertex 0.829815 1.29344 2.57601 + vertex 0.830247 1.29683 2.57696 + vertex 0.828073 1.296 2.57493 + endloop + endfacet + facet normal -0.626887 -0.0431391 0.777915 + outer loop + vertex 0.829469 1.43794 2.5914 + vertex 0.826909 1.4362 2.58924 + vertex 0.829938 1.4338 2.59155 + endloop + endfacet + facet normal -0.627184 -0.0424546 0.777713 + outer loop + vertex 0.826909 1.4362 2.58924 + vertex 0.829469 1.43794 2.5914 + vertex 0.827794 1.44036 2.59018 + endloop + endfacet + facet normal -0.672377 0.0617085 0.737632 + outer loop + vertex 0.832142 1.77848 2.57018 + vertex 0.829332 1.77621 2.56781 + vertex 0.831733 1.77372 2.57021 + endloop + endfacet + facet normal -0.65392 0.0602083 0.754164 + outer loop + vertex 0.831733 1.77372 2.57021 + vertex 0.834103 1.7762 2.57206 + vertex 0.832142 1.77848 2.57018 + endloop + endfacet + facet normal -0.655836 0.0634821 0.75223 + outer loop + vertex 0.834684 1.77172 2.57295 + vertex 0.834103 1.7762 2.57206 + vertex 0.831733 1.77372 2.57021 + endloop + endfacet + facet normal -0.673828 0.0652117 0.736005 + outer loop + vertex 0.829958 1.78164 2.5679 + vertex 0.829332 1.77621 2.56781 + vertex 0.832142 1.77848 2.57018 + endloop + endfacet + facet normal -0.680542 0.056619 0.730518 + outer loop + vertex 0.83278 1.78206 2.5705 + vertex 0.829958 1.78164 2.5679 + vertex 0.832142 1.77848 2.57018 + endloop + endfacet + facet normal -0.662755 0.0520057 0.747028 + outer loop + vertex 0.832142 1.77848 2.57018 + vertex 0.835017 1.78016 2.57261 + vertex 0.83278 1.78206 2.5705 + endloop + endfacet + facet normal -0.661706 0.0485399 0.74819 + outer loop + vertex 0.834103 1.7762 2.57206 + vertex 0.835017 1.78016 2.57261 + vertex 0.832142 1.77848 2.57018 + endloop + endfacet + facet normal -0.681524 0.0866703 0.726645 + outer loop + vertex 0.83278 1.78206 2.5705 + vertex 0.832395 1.78542 2.56973 + vertex 0.829958 1.78164 2.5679 + endloop + endfacet + facet normal -0.681459 0.0865948 0.726715 + outer loop + vertex 0.829958 1.78164 2.5679 + vertex 0.832395 1.78542 2.56973 + vertex 0.82938 1.78659 2.56677 + endloop + endfacet + facet normal -0.629029 0.323138 0.707039 + outer loop + vertex 0.831828 1.88739 2.54154 + vertex 0.831755 1.88257 2.54368 + vertex 0.834517 1.88523 2.54492 + endloop + endfacet + facet normal -0.593821 0.374721 0.712012 + outer loop + vertex 0.831828 1.88739 2.54154 + vertex 0.834517 1.88523 2.54492 + vertex 0.83521 1.8885 2.54377 + endloop + endfacet + facet normal -0.622355 0.310941 0.718325 + outer loop + vertex 0.834517 1.88523 2.54492 + vertex 0.831755 1.88257 2.54368 + vertex 0.834345 1.88113 2.54654 + endloop + endfacet + facet normal -0.622507 0.337949 0.705886 + outer loop + vertex 0.828809 1.88981 2.53771 + vertex 0.828734 1.88612 2.53942 + vertex 0.831828 1.88739 2.54154 + endloop + endfacet + facet normal -0.589811 0.384994 0.709861 + outer loop + vertex 0.831607 1.89241 2.53863 + vertex 0.828809 1.88981 2.53771 + vertex 0.831828 1.88739 2.54154 + endloop + endfacet + facet normal -0.570853 0.3924 0.721214 + outer loop + vertex 0.831828 1.88739 2.54154 + vertex 0.834865 1.89163 2.54163 + vertex 0.831607 1.89241 2.53863 + endloop + endfacet + facet normal -0.592948 0.408882 0.693706 + outer loop + vertex 0.83521 1.8885 2.54377 + vertex 0.834865 1.89163 2.54163 + vertex 0.831828 1.88739 2.54154 + endloop + endfacet + facet normal -0.547706 0.417168 0.725251 + outer loop + vertex 0.831414 1.89692 2.53578 + vertex 0.828886 1.89655 2.53408 + vertex 0.828841 1.89406 2.53548 + endloop + endfacet + facet normal -0.587116 0.380427 0.714542 + outer loop + vertex 0.828841 1.89406 2.53548 + vertex 0.828809 1.88981 2.53771 + vertex 0.831607 1.89241 2.53863 + endloop + endfacet + facet normal -0.556988 0.426841 0.71244 + outer loop + vertex 0.831414 1.89692 2.53578 + vertex 0.828841 1.89406 2.53548 + vertex 0.831607 1.89241 2.53863 + endloop + endfacet + facet normal -0.552313 0.428652 0.714988 + outer loop + vertex 0.831414 1.89692 2.53578 + vertex 0.831607 1.89241 2.53863 + vertex 0.834317 1.89522 2.53904 + endloop + endfacet + facet normal -0.541347 0.444659 0.713598 + outer loop + vertex 0.831414 1.89692 2.53578 + vertex 0.834317 1.89522 2.53904 + vertex 0.83396 1.89734 2.53745 + endloop + endfacet + facet normal -0.553881 0.430502 0.71266 + outer loop + vertex 0.834317 1.89522 2.53904 + vertex 0.831607 1.89241 2.53863 + vertex 0.834865 1.89163 2.54163 + endloop + endfacet + facet normal -0.573757 0.467367 0.672586 + outer loop + vertex 0.831188 1.90207 2.53229 + vertex 0.827227 1.90024 2.53019 + vertex 0.828986 1.8985 2.53289 + endloop + endfacet + facet normal -0.540781 0.457214 0.706054 + outer loop + vertex 0.828986 1.8985 2.53289 + vertex 0.828886 1.89655 2.53408 + vertex 0.831414 1.89692 2.53578 + endloop + endfacet + facet normal -0.543088 0.454102 0.706291 + outer loop + vertex 0.831188 1.90207 2.53229 + vertex 0.828986 1.8985 2.53289 + vertex 0.831414 1.89692 2.53578 + endloop + endfacet + facet normal -0.547086 0.452523 0.704216 + outer loop + vertex 0.831188 1.90207 2.53229 + vertex 0.831414 1.89692 2.53578 + vertex 0.834113 1.89976 2.53605 + endloop + endfacet + facet normal -0.554722 0.442985 0.704307 + outer loop + vertex 0.831188 1.90207 2.53229 + vertex 0.834113 1.89976 2.53605 + vertex 0.834955 1.90312 2.5346 + endloop + endfacet + facet normal -0.541122 0.446034 0.71291 + outer loop + vertex 0.834113 1.89976 2.53605 + vertex 0.831414 1.89692 2.53578 + vertex 0.83396 1.89734 2.53745 + endloop + endfacet + facet normal -0.574173 0.474265 0.667382 + outer loop + vertex 0.827665 1.9045 2.52754 + vertex 0.827227 1.90024 2.53019 + vertex 0.831188 1.90207 2.53229 + endloop + endfacet + facet normal -0.607068 0.429232 0.668751 + outer loop + vertex 0.831133 1.90734 2.52886 + vertex 0.827665 1.9045 2.52754 + vertex 0.831188 1.90207 2.53229 + endloop + endfacet + facet normal -0.568907 0.444662 0.691824 + outer loop + vertex 0.831188 1.90207 2.53229 + vertex 0.834373 1.90644 2.53211 + vertex 0.831133 1.90734 2.52886 + endloop + endfacet + facet normal -0.555235 0.43541 0.708613 + outer loop + vertex 0.834955 1.90312 2.5346 + vertex 0.834373 1.90644 2.53211 + vertex 0.831188 1.90207 2.53229 + endloop + endfacet + facet normal -0.667933 0.432892 0.605367 + outer loop + vertex 0.831151 1.91213 2.5258 + vertex 0.828698 1.91174 2.52337 + vertex 0.828532 1.90901 2.52514 + endloop + endfacet + facet normal -0.618944 0.457921 0.638136 + outer loop + vertex 0.828532 1.90901 2.52514 + vertex 0.827665 1.9045 2.52754 + vertex 0.831133 1.90734 2.52886 + endloop + endfacet + facet normal -0.650273 0.410964 0.638947 + outer loop + vertex 0.831151 1.91213 2.5258 + vertex 0.828532 1.90901 2.52514 + vertex 0.831133 1.90734 2.52886 + endloop + endfacet + facet normal -0.605785 0.430195 0.669296 + outer loop + vertex 0.831151 1.91213 2.5258 + vertex 0.831133 1.90734 2.52886 + vertex 0.833854 1.91024 2.52946 + endloop + endfacet + facet normal -0.648662 0.365659 0.667481 + outer loop + vertex 0.831151 1.91213 2.5258 + vertex 0.833854 1.91024 2.52946 + vertex 0.833578 1.91254 2.52793 + endloop + endfacet + facet normal -0.587462 0.406593 0.699693 + outer loop + vertex 0.833854 1.91024 2.52946 + vertex 0.831133 1.90734 2.52886 + vertex 0.834373 1.90644 2.53211 + endloop + endfacet + facet normal -0.674712 0.421551 0.605853 + outer loop + vertex 0.831269 1.9173 2.52229 + vertex 0.828737 1.9173 2.51947 + vertex 0.828723 1.91453 2.52138 + endloop + endfacet + facet normal -0.666861 0.436966 0.60362 + outer loop + vertex 0.828723 1.91453 2.52138 + vertex 0.828698 1.91174 2.52337 + vertex 0.831151 1.91213 2.5258 + endloop + endfacet + facet normal -0.676391 0.424341 0.602021 + outer loop + vertex 0.831269 1.9173 2.52229 + vertex 0.828723 1.91453 2.52138 + vertex 0.831151 1.91213 2.5258 + endloop + endfacet + facet normal -0.617349 0.451604 0.644154 + outer loop + vertex 0.831269 1.9173 2.52229 + vertex 0.831151 1.91213 2.5258 + vertex 0.833643 1.91485 2.52628 + endloop + endfacet + facet normal -0.553145 0.522033 0.649239 + outer loop + vertex 0.831269 1.9173 2.52229 + vertex 0.833643 1.91485 2.52628 + vertex 0.83392 1.91728 2.52456 + endloop + endfacet + facet normal -0.627665 0.464556 0.62468 + outer loop + vertex 0.833643 1.91485 2.52628 + vertex 0.831151 1.91213 2.5258 + vertex 0.833578 1.91254 2.52793 + endloop + endfacet + facet normal -0.680007 0.40591 0.610597 + outer loop + vertex 0.829049 1.92009 2.51796 + vertex 0.828737 1.9173 2.51947 + vertex 0.831269 1.9173 2.52229 + endloop + endfacet + facet normal -0.66616 0.422809 0.61438 + outer loop + vertex 0.831525 1.92231 2.51912 + vertex 0.829049 1.92009 2.51796 + vertex 0.831269 1.9173 2.52229 + endloop + endfacet + facet normal -0.381509 0.508113 0.772187 + outer loop + vertex 0.831269 1.9173 2.52229 + vertex 0.834593 1.92015 2.52206 + vertex 0.831525 1.92231 2.51912 + endloop + endfacet + facet normal -0.501327 0.633283 0.589596 + outer loop + vertex 0.83392 1.91728 2.52456 + vertex 0.834593 1.92015 2.52206 + vertex 0.831269 1.9173 2.52229 + endloop + endfacet + facet normal -0.753369 0.366136 0.546241 + outer loop + vertex 0.831308 1.92792 2.51599 + vertex 0.828948 1.926 2.51402 + vertex 0.829537 1.92373 2.51635 + endloop + endfacet + facet normal -0.648145 0.37861 0.660729 + outer loop + vertex 0.829537 1.92373 2.51635 + vertex 0.829049 1.92009 2.51796 + vertex 0.831525 1.92231 2.51912 + endloop + endfacet + facet normal -0.671275 0.341123 0.658047 + outer loop + vertex 0.831308 1.92792 2.51599 + vertex 0.829537 1.92373 2.51635 + vertex 0.831525 1.92231 2.51912 + endloop + endfacet + facet normal -0.250919 0.464227 0.849431 + outer loop + vertex 0.831308 1.92792 2.51599 + vertex 0.831525 1.92231 2.51912 + vertex 0.834358 1.92492 2.51853 + endloop + endfacet + facet normal -0.400581 0.319819 0.858633 + outer loop + vertex 0.831308 1.92792 2.51599 + vertex 0.834358 1.92492 2.51853 + vertex 0.833817 1.92879 2.51683 + endloop + endfacet + facet normal -0.345119 0.546891 0.76276 + outer loop + vertex 0.834358 1.92492 2.51853 + vertex 0.831525 1.92231 2.51912 + vertex 0.834593 1.92015 2.52206 + endloop + endfacet + facet normal -0.859456 0.246813 0.447681 + outer loop + vertex 0.830124 1.93238 2.51262 + vertex 0.8286 1.93123 2.51033 + vertex 0.829215 1.92885 2.51282 + endloop + endfacet + facet normal -0.745979 0.316126 0.586157 + outer loop + vertex 0.829215 1.92885 2.51282 + vertex 0.828948 1.926 2.51402 + vertex 0.831308 1.92792 2.51599 + endloop + endfacet + facet normal -0.778165 0.233462 0.583056 + outer loop + vertex 0.829215 1.92885 2.51282 + vertex 0.831308 1.92792 2.51599 + vertex 0.830124 1.93238 2.51262 + endloop + endfacet + facet normal -0.745984 0.263553 0.611595 + outer loop + vertex 0.830124 1.93238 2.51262 + vertex 0.831308 1.92792 2.51599 + vertex 0.83201 1.93348 2.51445 + endloop + endfacet + facet normal -0.529237 0.287767 0.798185 + outer loop + vertex 0.831308 1.92792 2.51599 + vertex 0.833082 1.93123 2.51597 + vertex 0.83201 1.93348 2.51445 + endloop + endfacet + facet normal -0.376107 0.206222 0.903336 + outer loop + vertex 0.833817 1.92879 2.51683 + vertex 0.833082 1.93123 2.51597 + vertex 0.831308 1.92792 2.51599 + endloop + endfacet + facet normal -0.859645 0.225556 0.458404 + outer loop + vertex 0.829026 1.93541 2.50907 + vertex 0.8286 1.93123 2.51033 + vertex 0.830124 1.93238 2.51262 + endloop + endfacet + facet normal -0.84286 0.251766 0.475606 + outer loop + vertex 0.830965 1.93748 2.51141 + vertex 0.829026 1.93541 2.50907 + vertex 0.830124 1.93238 2.51262 + endloop + endfacet + facet normal -0.258831 0.42052 0.86958 + outer loop + vertex 0.83309 1.93728 2.51293 + vertex 0.83201 1.93348 2.51445 + vertex 0.833638 1.9341 2.51463 + endloop + endfacet + facet normal -0.495075 0.43957 0.749452 + outer loop + vertex 0.83309 1.93728 2.51293 + vertex 0.830965 1.93748 2.51141 + vertex 0.83201 1.93348 2.51445 + endloop + endfacet + facet normal -0.746286 0.267628 0.609452 + outer loop + vertex 0.830965 1.93748 2.51141 + vertex 0.830124 1.93238 2.51262 + vertex 0.83201 1.93348 2.51445 + endloop + endfacet + facet normal -0.267868 0.449121 0.852371 + outer loop + vertex 0.833638 1.9341 2.51463 + vertex 0.83201 1.93348 2.51445 + vertex 0.833082 1.93123 2.51597 + endloop + endfacet + facet normal -0.835379 0.206555 0.509388 + outer loop + vertex 0.829432 1.94019 2.5078 + vertex 0.829026 1.93541 2.50907 + vertex 0.830965 1.93748 2.51141 + endloop + endfacet + facet normal -0.810105 0.249203 0.530686 + outer loop + vertex 0.831002 1.94228 2.50922 + vertex 0.829432 1.94019 2.5078 + vertex 0.830965 1.93748 2.51141 + endloop + endfacet + facet normal -0.619277 0.330715 0.712127 + outer loop + vertex 0.830965 1.93748 2.51141 + vertex 0.832397 1.94046 2.51127 + vertex 0.831002 1.94228 2.50922 + endloop + endfacet + facet normal -0.537377 0.294964 0.790078 + outer loop + vertex 0.83309 1.93728 2.51293 + vertex 0.832397 1.94046 2.51127 + vertex 0.830965 1.93748 2.51141 + endloop + endfacet + facet normal -0.777507 0.359559 0.515946 + outer loop + vertex 0.83133 1.94737 2.50663 + vertex 0.829188 1.94617 2.50424 + vertex 0.829709 1.94391 2.5066 + endloop + endfacet + facet normal -0.804668 0.235299 0.545109 + outer loop + vertex 0.829709 1.94391 2.5066 + vertex 0.829432 1.94019 2.5078 + vertex 0.831002 1.94228 2.50922 + endloop + endfacet + facet normal -0.740081 0.34148 0.579372 + outer loop + vertex 0.83133 1.94737 2.50663 + vertex 0.829709 1.94391 2.5066 + vertex 0.831002 1.94228 2.50922 + endloop + endfacet + facet normal -0.529974 0.410453 0.742062 + outer loop + vertex 0.83133 1.94737 2.50663 + vertex 0.831002 1.94228 2.50922 + vertex 0.832769 1.94339 2.50986 + endloop + endfacet + facet normal -0.350897 0.510246 0.785188 + outer loop + vertex 0.83133 1.94737 2.50663 + vertex 0.832769 1.94339 2.50986 + vertex 0.83508 1.94548 2.50954 + endloop + endfacet + facet normal -0.5335 0.420915 0.733627 + outer loop + vertex 0.832769 1.94339 2.50986 + vertex 0.831002 1.94228 2.50922 + vertex 0.832397 1.94046 2.51127 + endloop + endfacet + facet normal -0.876464 0.301853 0.375095 + outer loop + vertex 0.830023 1.95275 2.50131 + vertex 0.828671 1.95096 2.49959 + vertex 0.829253 1.94894 2.50257 + endloop + endfacet + facet normal -0.779109 0.336927 0.528648 + outer loop + vertex 0.829253 1.94894 2.50257 + vertex 0.829188 1.94617 2.50424 + vertex 0.83133 1.94737 2.50663 + endloop + endfacet + facet normal -0.780927 0.333387 0.528211 + outer loop + vertex 0.829253 1.94894 2.50257 + vertex 0.83133 1.94737 2.50663 + vertex 0.830023 1.95275 2.50131 + endloop + endfacet + facet normal -0.867427 0.227485 0.442517 + outer loop + vertex 0.830023 1.95275 2.50131 + vertex 0.83133 1.94737 2.50663 + vertex 0.832201 1.95324 2.50532 + endloop + endfacet + facet normal -0.757886 0.247314 0.603692 + outer loop + vertex 0.83133 1.94737 2.50663 + vertex 0.834154 1.95033 2.50897 + vertex 0.832201 1.95324 2.50532 + endloop + endfacet + facet normal -0.620211 -0.0261465 0.783999 + outer loop + vertex 0.83508 1.94548 2.50954 + vertex 0.834154 1.95033 2.50897 + vertex 0.83133 1.94737 2.50663 + endloop + endfacet + facet normal -0.919748 0.296832 0.256817 + outer loop + vertex 0.830048 1.95812 2.49657 + vertex 0.828863 1.95617 2.49458 + vertex 0.828906 1.95384 2.49741 + endloop + endfacet + facet normal -0.877946 0.331518 0.345409 + outer loop + vertex 0.828906 1.95384 2.49741 + vertex 0.828671 1.95096 2.49959 + vertex 0.830023 1.95275 2.50131 + endloop + endfacet + facet normal -0.889022 0.305329 0.341196 + outer loop + vertex 0.828906 1.95384 2.49741 + vertex 0.830023 1.95275 2.50131 + vertex 0.830048 1.95812 2.49657 + endloop + endfacet + facet normal -0.909336 0.277716 0.309809 + outer loop + vertex 0.830048 1.95812 2.49657 + vertex 0.830023 1.95275 2.50131 + vertex 0.831325 1.95752 2.50085 + endloop + endfacet + facet normal -0.858773 0.275738 0.431832 + outer loop + vertex 0.830023 1.95275 2.50131 + vertex 0.832201 1.95324 2.50532 + vertex 0.831325 1.95752 2.50085 + endloop + endfacet + facet normal -0.903411 0.207437 0.375258 + outer loop + vertex 0.831325 1.95752 2.50085 + vertex 0.832201 1.95324 2.50532 + vertex 0.832989 1.95773 2.50474 + endloop + endfacet + facet normal -0.845914 0.212055 0.489348 + outer loop + vertex 0.832201 1.95324 2.50532 + vertex 0.834254 1.95498 2.50812 + vertex 0.832989 1.95773 2.50474 + endloop + endfacet + facet normal -0.833762 0.116463 0.539701 + outer loop + vertex 0.834154 1.95033 2.50897 + vertex 0.834254 1.95498 2.50812 + vertex 0.832201 1.95324 2.50532 + endloop + endfacet + facet normal -0.906024 0.144405 0.397828 + outer loop + vertex 0.83 1.96213 2.495 + vertex 0.828863 1.95617 2.49458 + vertex 0.830048 1.95812 2.49657 + endloop + endfacet + facet normal -0.436374 0.32264 0.839929 + outer loop + vertex 0.83 1.96213 2.495 + vertex 0.830048 1.95812 2.49657 + vertex 0.832122 1.965 2.495 + endloop + endfacet + facet normal -0.959385 0.277626 -0.0500374 + outer loop + vertex 0.832122 1.965 2.495 + vertex 0.830048 1.95812 2.49657 + vertex 0.83133 1.96252 2.49644 + endloop + endfacet + facet normal -0.910683 0.27348 0.309622 + outer loop + vertex 0.830048 1.95812 2.49657 + vertex 0.831325 1.95752 2.50085 + vertex 0.83133 1.96252 2.49644 + endloop + endfacet + facet normal -0.940496 0.225074 0.254577 + outer loop + vertex 0.83133 1.96252 2.49644 + vertex 0.831325 1.95752 2.50085 + vertex 0.832543 1.96249 2.50095 + endloop + endfacet + facet normal -0.871233 0.197034 0.449589 + outer loop + vertex 0.833797 1.96098 2.50488 + vertex 0.832989 1.95773 2.50474 + vertex 0.834433 1.9586 2.50715 + endloop + endfacet + facet normal -0.905445 0.208876 0.369513 + outer loop + vertex 0.833797 1.96098 2.50488 + vertex 0.832543 1.96249 2.50095 + vertex 0.832989 1.95773 2.50474 + endloop + endfacet + facet normal -0.902388 0.213142 0.374522 + outer loop + vertex 0.832543 1.96249 2.50095 + vertex 0.831325 1.95752 2.50085 + vertex 0.832989 1.95773 2.50474 + endloop + endfacet + facet normal -0.871667 0.165654 0.461253 + outer loop + vertex 0.834433 1.9586 2.50715 + vertex 0.832989 1.95773 2.50474 + vertex 0.834254 1.95498 2.50812 + endloop + endfacet + facet normal -0.980581 0.132967 0.144158 + outer loop + vertex 0.831387 1.965 2.49 + vertex 0.832122 1.965 2.495 + vertex 0.832065 1.97 2.49 + endloop + endfacet + facet normal -0.53298 -0.601328 -0.595262 + outer loop + vertex 0.832065 1.97 2.49 + vertex 0.832122 1.965 2.495 + vertex 0.831792 1.9679 2.49237 + endloop + endfacet + facet normal 0.501074 -0.549945 -0.668196 + outer loop + vertex 0.832122 1.965 2.495 + vertex 0.83133 1.96252 2.49644 + vertex 0.831792 1.9679 2.49237 + endloop + endfacet + facet normal -0.97862 0.17094 0.114379 + outer loop + vertex 0.831792 1.9679 2.49237 + vertex 0.83133 1.96252 2.49644 + vertex 0.832112 1.96732 2.49597 + endloop + endfacet + facet normal -0.949531 0.180269 0.256697 + outer loop + vertex 0.83133 1.96252 2.49644 + vertex 0.832543 1.96249 2.50095 + vertex 0.832112 1.96732 2.49597 + endloop + endfacet + facet normal -0.960903 0.152695 0.230975 + outer loop + vertex 0.832112 1.96732 2.49597 + vertex 0.832543 1.96249 2.50095 + vertex 0.833125 1.96789 2.4998 + endloop + endfacet + facet normal -0.906653 0.179017 0.382012 + outer loop + vertex 0.832543 1.96249 2.50095 + vertex 0.834128 1.96495 2.50356 + vertex 0.833125 1.96789 2.4998 + endloop + endfacet + facet normal -0.909302 0.197406 0.366333 + outer loop + vertex 0.833797 1.96098 2.50488 + vertex 0.834128 1.96495 2.50356 + vertex 0.832543 1.96249 2.50095 + endloop + endfacet + facet normal -0.982769 0.17906 0.045861 + outer loop + vertex 0.832065 1.97 2.49 + vertex 0.831792 1.9679 2.49237 + vertex 0.832976 1.975 2.49 + endloop + endfacet + facet normal -0.980059 0.107628 -0.167037 + outer loop + vertex 0.832976 1.975 2.49 + vertex 0.831792 1.9679 2.49237 + vertex 0.832404 1.97257 2.49179 + endloop + endfacet + facet normal -0.98366 0.142341 0.110235 + outer loop + vertex 0.831792 1.9679 2.49237 + vertex 0.832112 1.96732 2.49597 + vertex 0.832404 1.97257 2.49179 + endloop + endfacet + facet normal -0.98129 0.15027 0.120366 + outer loop + vertex 0.832404 1.97257 2.49179 + vertex 0.832112 1.96732 2.49597 + vertex 0.832902 1.97262 2.49579 + endloop + endfacet + facet normal -0.906357 0.170875 0.386418 + outer loop + vertex 0.833757 1.97138 2.49974 + vertex 0.833125 1.96789 2.4998 + vertex 0.834359 1.96886 2.50227 + endloop + endfacet + facet normal -0.949203 0.176506 0.260499 + outer loop + vertex 0.833757 1.97138 2.49974 + vertex 0.832902 1.97262 2.49579 + vertex 0.833125 1.96789 2.4998 + endloop + endfacet + facet normal -0.961084 0.15112 0.231258 + outer loop + vertex 0.832902 1.97262 2.49579 + vertex 0.832112 1.96732 2.49597 + vertex 0.833125 1.96789 2.4998 + endloop + endfacet + facet normal -0.906151 0.180073 0.382705 + outer loop + vertex 0.834359 1.96886 2.50227 + vertex 0.833125 1.96789 2.4998 + vertex 0.834128 1.96495 2.50356 + endloop + endfacet + facet normal -0.975305 0.0770491 -0.206988 + outer loop + vertex 0.832976 1.975 2.49 + vertex 0.832404 1.97257 2.49179 + vertex 0.833371 1.98 2.49 + endloop + endfacet + facet normal -0.98591 0.0951643 -0.137568 + outer loop + vertex 0.833371 1.98 2.49 + vertex 0.832404 1.97257 2.49179 + vertex 0.832962 1.97729 2.49106 + endloop + endfacet + facet normal -0.983437 0.135098 0.120833 + outer loop + vertex 0.832404 1.97257 2.49179 + vertex 0.832902 1.97262 2.49579 + vertex 0.832962 1.97729 2.49106 + endloop + endfacet + facet normal -0.981812 0.141221 0.126893 + outer loop + vertex 0.832962 1.97729 2.49106 + vertex 0.832902 1.97262 2.49579 + vertex 0.83344 1.97764 2.49437 + endloop + endfacet + facet normal -0.936543 0.184554 0.298039 + outer loop + vertex 0.832902 1.97262 2.49579 + vertex 0.834193 1.97504 2.49834 + vertex 0.83344 1.97764 2.49437 + endloop + endfacet + facet normal -0.938476 0.214945 0.270299 + outer loop + vertex 0.833757 1.97138 2.49974 + vertex 0.834193 1.97504 2.49834 + vertex 0.832902 1.97262 2.49579 + endloop + endfacet + facet normal 0.167373 -0.423092 -0.890494 + outer loop + vertex 0.835 1.98098 2.485 + vertex 0.833915 1.98151 2.48454 + vertex 0.835 1.985 2.48309 + endloop + endfacet + facet normal -0.110524 -0.767243 -0.631761 + outer loop + vertex 0.835 1.98 2.48619 + vertex 0.833915 1.98151 2.48454 + vertex 0.835 1.98098 2.485 + endloop + endfacet + facet normal -0.622362 -0.736109 -0.266101 + outer loop + vertex 0.835 1.98 2.48619 + vertex 0.833371 1.98 2.49 + vertex 0.833915 1.98151 2.48454 + endloop + endfacet + facet normal -0.995405 0.0222771 -0.093125 + outer loop + vertex 0.833371 1.98 2.49 + vertex 0.83368 1.98271 2.48734 + vertex 0.833915 1.98151 2.48454 + endloop + endfacet + facet normal 0.983108 -0.172345 -0.0616076 + outer loop + vertex 0.833371 1.98 2.49 + vertex 0.832962 1.97729 2.49106 + vertex 0.83368 1.98271 2.48734 + endloop + endfacet + facet normal -0.986339 0.159303 0.041925 + outer loop + vertex 0.83368 1.98271 2.48734 + vertex 0.832962 1.97729 2.49106 + vertex 0.833639 1.98153 2.49089 + endloop + endfacet + facet normal -0.918679 0.227717 0.32276 + outer loop + vertex 0.83405 1.98085 2.49384 + vertex 0.83344 1.97764 2.49437 + vertex 0.834535 1.97873 2.49672 + endloop + endfacet + facet normal -0.96004 0.21233 0.182317 + outer loop + vertex 0.83405 1.98085 2.49384 + vertex 0.833639 1.98153 2.49089 + vertex 0.83344 1.97764 2.49437 + endloop + endfacet + facet normal -0.979018 0.161412 0.124381 + outer loop + vertex 0.833639 1.98153 2.49089 + vertex 0.832962 1.97729 2.49106 + vertex 0.83344 1.97764 2.49437 + endloop + endfacet + facet normal -0.918684 0.227647 0.322795 + outer loop + vertex 0.834535 1.97873 2.49672 + vertex 0.83344 1.97764 2.49437 + vertex 0.834193 1.97504 2.49834 + endloop + endfacet + facet normal -0.61055 0.0490373 -0.790458 + outer loop + vertex 0.835 1.985 2.48309 + vertex 0.834115 1.98615 2.48384 + vertex 0.835 1.99 2.4834 + endloop + endfacet + facet normal -0.702626 -0.0762611 -0.70746 + outer loop + vertex 0.833915 1.98151 2.48454 + vertex 0.834115 1.98615 2.48384 + vertex 0.835 1.985 2.48309 + endloop + endfacet + facet normal -0.975923 0.146726 0.16139 + outer loop + vertex 0.835 1.99 2.4887 + vertex 0.83368 1.98271 2.48734 + vertex 0.835 1.98857 2.49 + endloop + endfacet + facet normal -0.984434 0.170015 0.0445375 + outer loop + vertex 0.835 1.99 2.4887 + vertex 0.834115 1.98615 2.48384 + vertex 0.83368 1.98271 2.48734 + endloop + endfacet + facet normal -0.994997 0.0284939 -0.0957567 + outer loop + vertex 0.834115 1.98615 2.48384 + vertex 0.833915 1.98151 2.48454 + vertex 0.83368 1.98271 2.48734 + endloop + endfacet + facet normal -0.945073 0.21377 0.247263 + outer loop + vertex 0.835 1.98857 2.49 + vertex 0.833639 1.98153 2.49089 + vertex 0.834463 1.98403 2.49187 + endloop + endfacet + facet normal -0.979097 0.196015 0.0542929 + outer loop + vertex 0.83368 1.98271 2.48734 + vertex 0.833639 1.98153 2.49089 + vertex 0.835 1.98857 2.49 + endloop + endfacet + facet normal -0.952571 0.239651 0.187553 + outer loop + vertex 0.834463 1.98403 2.49187 + vertex 0.833639 1.98153 2.49089 + vertex 0.83405 1.98085 2.49384 + endloop + endfacet + facet normal 0.66926 -0.0885429 -0.737734 + outer loop + vertex 0.835 1.99 2.4834 + vertex 0.834393 1.99031 2.48281 + vertex 0.835 1.995 2.4828 + endloop + endfacet + facet normal 0.615024 -0.228421 -0.754698 + outer loop + vertex 0.834115 1.98615 2.48384 + vertex 0.834393 1.99031 2.48281 + vertex 0.835 1.99 2.4834 + endloop + endfacet + facet normal -0.985509 0.0998057 0.137149 + outer loop + vertex 0.834115 1.98615 2.48384 + vertex 0.834662 1.98994 2.48502 + vertex 0.834393 1.99031 2.48281 + endloop + endfacet + facet normal -0.989349 0.115363 0.0887699 + outer loop + vertex 0.835 1.99 2.4887 + vertex 0.834662 1.98994 2.48502 + vertex 0.834115 1.98615 2.48384 + endloop + endfacet + facet normal -0.991606 0.128259 -0.016326 + outer loop + vertex 0.835 1.995 2.4828 + vertex 0.834393 1.99031 2.48281 + vertex 0.835 1.99528 2.485 + endloop + endfacet + facet normal -0.989319 0.0629755 0.131461 + outer loop + vertex 0.835 1.99528 2.485 + vertex 0.834393 1.99031 2.48281 + vertex 0.834662 1.98994 2.48502 + endloop + endfacet + facet normal 0.911835 -0.0720131 -0.404191 + outer loop + vertex 0.84 1.01854 2.48 + vertex 0.839529 1.01918 2.47882 + vertex 0.84 1.02 2.47974 + endloop + endfacet + facet normal -0.941903 -0.204454 0.266491 + outer loop + vertex 0.84 1.01854 2.48 + vertex 0.84 1.02 2.48112 + vertex 0.839529 1.01918 2.47882 + endloop + endfacet + facet normal 0.640718 0.377898 -0.668336 + outer loop + vertex 0.84 1.02 2.47974 + vertex 0.839529 1.01918 2.47882 + vertex 0.84 1.02046 2.48 + endloop + endfacet + facet normal -0.96079 0.256488 0.105341 + outer loop + vertex 0.84 1.02046 2.48 + vertex 0.839529 1.01918 2.47882 + vertex 0.84 1.02 2.48112 + endloop + endfacet + facet normal -0.701707 -0.267632 -0.660288 + outer loop + vertex 0.84 1.025 2.48455 + vertex 0.84 1.02389 2.485 + vertex 0.839091 1.0263 2.48499 + endloop + endfacet + facet normal -0.922642 -0.346465 0.169394 + outer loop + vertex 0.84 1.02389 2.485 + vertex 0.84 1.025 2.48727 + vertex 0.839091 1.0263 2.48499 + endloop + endfacet + facet normal -0.641407 -0.11233 -0.758932 + outer loop + vertex 0.84 1.025 2.48455 + vertex 0.838592 1.03 2.485 + vertex 0.84 1.03 2.48381 + endloop + endfacet + facet normal -0.507564 -0.065626 -0.859111 + outer loop + vertex 0.839091 1.0263 2.48499 + vertex 0.838592 1.03 2.485 + vertex 0.84 1.025 2.48455 + endloop + endfacet + facet normal -0.934343 -0.290995 0.205729 + outer loop + vertex 0.84 1.02693 2.49 + vertex 0.839091 1.0263 2.48499 + vertex 0.84 1.025 2.48727 + endloop + endfacet + facet normal -0.940111 -0.272718 0.204491 + outer loop + vertex 0.84 1.02693 2.49 + vertex 0.838255 1.02995 2.486 + vertex 0.839091 1.0263 2.48499 + endloop + endfacet + facet normal -0.937836 -0.125579 -0.323565 + outer loop + vertex 0.838255 1.02995 2.486 + vertex 0.838592 1.03 2.485 + vertex 0.839091 1.0263 2.48499 + endloop + endfacet + facet normal 0.827486 -0.211394 -0.520173 + outer loop + vertex 0.84 1.02693 2.49 + vertex 0.839175 1.02769 2.48838 + vertex 0.838255 1.02995 2.486 + endloop + endfacet + facet normal -0.918053 -0.230427 -0.322618 + outer loop + vertex 0.838592 1.03 2.485 + vertex 0.838255 1.02995 2.486 + vertex 0.837337 1.035 2.485 + endloop + endfacet + facet normal -0.983409 -0.180987 -0.0122711 + outer loop + vertex 0.837337 1.035 2.485 + vertex 0.838255 1.02995 2.486 + vertex 0.837214 1.03551 2.48734 + endloop + endfacet + facet normal -0.962144 -0.218972 0.162265 + outer loop + vertex 0.838255 1.02995 2.486 + vertex 0.838525 1.03115 2.48923 + vertex 0.837214 1.03551 2.48734 + endloop + endfacet + facet normal -0.961775 -0.220257 0.162715 + outer loop + vertex 0.839175 1.02769 2.48838 + vertex 0.838525 1.03115 2.48923 + vertex 0.838255 1.02995 2.486 + endloop + endfacet + facet normal -0.972518 -0.232829 -0.000345299 + outer loop + vertex 0.837337 1.035 2.485 + vertex 0.837214 1.03551 2.48734 + vertex 0.83614 1.04 2.485 + endloop + endfacet + facet normal -0.970815 -0.126002 0.204062 + outer loop + vertex 0.83614 1.04 2.485 + vertex 0.837214 1.03551 2.48734 + vertex 0.837191 1.04 2.49 + endloop + endfacet + facet normal -0.960809 -0.210874 0.179941 + outer loop + vertex 0.837979 1.03506 2.49089 + vertex 0.837214 1.03551 2.48734 + vertex 0.838525 1.03115 2.48923 + endloop + endfacet + facet normal -0.962143 -0.203629 0.181153 + outer loop + vertex 0.837979 1.03506 2.49089 + vertex 0.83703 1.03994 2.49134 + vertex 0.837214 1.03551 2.48734 + endloop + endfacet + facet normal -0.991241 0.0636485 -0.115713 + outer loop + vertex 0.83703 1.03994 2.49134 + vertex 0.837191 1.04 2.49 + vertex 0.837214 1.03551 2.48734 + endloop + endfacet + facet normal -0.949287 -0.206311 0.237256 + outer loop + vertex 0.837979 1.03506 2.49089 + vertex 0.83838 1.03682 2.49402 + vertex 0.83703 1.03994 2.49134 + endloop + endfacet + facet normal -0.974147 -0.188394 -0.124679 + outer loop + vertex 0.837191 1.04 2.49 + vertex 0.83703 1.03994 2.49134 + vertex 0.836224 1.045 2.49 + endloop + endfacet + facet normal -0.975877 -0.185944 -0.114411 + outer loop + vertex 0.836224 1.045 2.49 + vertex 0.83703 1.03994 2.49134 + vertex 0.836165 1.04424 2.49174 + endloop + endfacet + facet normal -0.94889 -0.200757 0.243526 + outer loop + vertex 0.838163 1.03986 2.49569 + vertex 0.83703 1.03994 2.49134 + vertex 0.83838 1.03682 2.49402 + endloop + endfacet + facet normal -0.949677 -0.196656 0.243804 + outer loop + vertex 0.838163 1.03986 2.49569 + vertex 0.837206 1.04465 2.49583 + vertex 0.83703 1.03994 2.49134 + endloop + endfacet + facet normal -0.941131 -0.21399 0.261687 + outer loop + vertex 0.837206 1.04465 2.49583 + vertex 0.836165 1.04424 2.49174 + vertex 0.83703 1.03994 2.49134 + endloop + endfacet + facet normal -0.918558 -0.193225 0.34484 + outer loop + vertex 0.838163 1.03986 2.49569 + vertex 0.838993 1.04147 2.4988 + vertex 0.837206 1.04465 2.49583 + endloop + endfacet + facet normal 0.273344 0.0705874 -0.959323 + outer loop + vertex 0.834834 1.04938 2.48993 + vertex 0.835 1.04974 2.49 + vertex 0.836224 1.045 2.49 + endloop + endfacet + facet normal -0.941666 -0.296257 0.159681 + outer loop + vertex 0.834834 1.04938 2.48993 + vertex 0.836224 1.045 2.49 + vertex 0.835476 1.04862 2.49231 + endloop + endfacet + facet normal -0.985212 -0.142201 -0.0955838 + outer loop + vertex 0.835476 1.04862 2.49231 + vertex 0.836224 1.045 2.49 + vertex 0.836165 1.04424 2.49174 + endloop + endfacet + facet normal -0.948081 -0.182749 0.260278 + outer loop + vertex 0.836165 1.04424 2.49174 + vertex 0.837206 1.04465 2.49583 + vertex 0.835476 1.04862 2.49231 + endloop + endfacet + facet normal -0.950413 -0.216469 0.223285 + outer loop + vertex 0.835476 1.04862 2.49231 + vertex 0.837206 1.04465 2.49583 + vertex 0.836016 1.04987 2.49582 + endloop + endfacet + facet normal -0.896367 -0.0992337 0.432063 + outer loop + vertex 0.839796 1.04536 2.50136 + vertex 0.837206 1.04465 2.49583 + vertex 0.838993 1.04147 2.4988 + endloop + endfacet + facet normal -0.840674 -0.322985 0.434681 + outer loop + vertex 0.839796 1.04536 2.50136 + vertex 0.83756 1.05006 2.50053 + vertex 0.837206 1.04465 2.49583 + endloop + endfacet + facet normal -0.92634 -0.210818 0.312169 + outer loop + vertex 0.83756 1.05006 2.50053 + vertex 0.836016 1.04987 2.49582 + vertex 0.837206 1.04465 2.49583 + endloop + endfacet + facet normal -0.705423 -0.215935 0.675093 + outer loop + vertex 0.839796 1.04536 2.50136 + vertex 0.840148 1.05026 2.5033 + vertex 0.83756 1.05006 2.50053 + endloop + endfacet + facet normal -0.96796 -0.110686 0.225394 + outer loop + vertex 0.835 1.055 2.4934 + vertex 0.834834 1.04938 2.48993 + vertex 0.835476 1.04862 2.49231 + endloop + endfacet + facet normal -0.967599 -0.110904 0.226831 + outer loop + vertex 0.835375 1.055 2.495 + vertex 0.835 1.055 2.4934 + vertex 0.835476 1.04862 2.49231 + endloop + endfacet + facet normal -0.97856 -0.0929546 0.183795 + outer loop + vertex 0.835476 1.04862 2.49231 + vertex 0.836016 1.04987 2.49582 + vertex 0.835375 1.055 2.495 + endloop + endfacet + facet normal -0.991847 -0.115177 0.054529 + outer loop + vertex 0.835375 1.055 2.495 + vertex 0.836016 1.04987 2.49582 + vertex 0.835769 1.05286 2.49765 + endloop + endfacet + facet normal -0.912979 -0.265253 0.310017 + outer loop + vertex 0.836016 1.04987 2.49582 + vertex 0.83756 1.05006 2.50053 + vertex 0.835769 1.05286 2.49765 + endloop + endfacet + facet normal -0.912053 -0.321063 0.255105 + outer loop + vertex 0.835769 1.05286 2.49765 + vertex 0.83756 1.05006 2.50053 + vertex 0.836212 1.05402 2.5007 + endloop + endfacet + facet normal -0.532573 -0.647717 0.54482 + outer loop + vertex 0.838825 1.0521 2.50419 + vertex 0.83756 1.05006 2.50053 + vertex 0.840148 1.05026 2.5033 + endloop + endfacet + facet normal -0.774772 -0.399237 0.490244 + outer loop + vertex 0.838825 1.0521 2.50419 + vertex 0.837558 1.05474 2.50433 + vertex 0.83756 1.05006 2.50053 + endloop + endfacet + facet normal -0.86936 -0.312127 0.383132 + outer loop + vertex 0.837558 1.05474 2.50433 + vertex 0.836212 1.05402 2.5007 + vertex 0.83756 1.05006 2.50053 + endloop + endfacet + facet normal -0.625884 -0.339619 0.702088 + outer loop + vertex 0.838825 1.0521 2.50419 + vertex 0.839156 1.05478 2.50578 + vertex 0.837558 1.05474 2.50433 + endloop + endfacet + facet normal 0.746117 0.216899 -0.629495 + outer loop + vertex 0.833982 1.05728 2.49414 + vertex 0.835 1.05629 2.495 + vertex 0.835375 1.055 2.495 + endloop + endfacet + facet normal -0.868553 -0.46566 0.169639 + outer loop + vertex 0.833982 1.05728 2.49414 + vertex 0.835375 1.055 2.495 + vertex 0.834769 1.05726 2.4981 + endloop + endfacet + facet normal -0.9753 -0.218637 -0.0314296 + outer loop + vertex 0.834769 1.05726 2.4981 + vertex 0.835375 1.055 2.495 + vertex 0.835769 1.05286 2.49765 + endloop + endfacet + facet normal -0.944177 -0.237813 0.227982 + outer loop + vertex 0.835769 1.05286 2.49765 + vertex 0.836212 1.05402 2.5007 + vertex 0.834769 1.05726 2.4981 + endloop + endfacet + facet normal -0.942707 -0.215979 0.254275 + outer loop + vertex 0.834769 1.05726 2.4981 + vertex 0.836212 1.05402 2.5007 + vertex 0.836025 1.0573 2.50279 + endloop + endfacet + facet normal -0.876238 -0.293661 0.382059 + outer loop + vertex 0.836212 1.05402 2.5007 + vertex 0.837558 1.05474 2.50433 + vertex 0.836025 1.0573 2.50279 + endloop + endfacet + facet normal -0.869096 -0.269726 0.414631 + outer loop + vertex 0.836025 1.0573 2.50279 + vertex 0.837558 1.05474 2.50433 + vertex 0.837008 1.06011 2.50668 + endloop + endfacet + facet normal -0.586151 -0.373497 0.718976 + outer loop + vertex 0.837558 1.05474 2.50433 + vertex 0.838786 1.05835 2.50721 + vertex 0.837008 1.06011 2.50668 + endloop + endfacet + facet normal -0.624291 -0.345785 0.700495 + outer loop + vertex 0.839156 1.05478 2.50578 + vertex 0.838786 1.05835 2.50721 + vertex 0.837558 1.05474 2.50433 + endloop + endfacet + facet normal -0.938275 -0.292548 0.184543 + outer loop + vertex 0.833982 1.05728 2.49414 + vertex 0.834769 1.05726 2.4981 + vertex 0.833349 1.06002 2.49525 + endloop + endfacet + facet normal -0.941182 -0.250458 0.226821 + outer loop + vertex 0.83367 1.06174 2.49849 + vertex 0.833349 1.06002 2.49525 + vertex 0.834769 1.05726 2.4981 + endloop + endfacet + facet normal -0.924021 -0.251579 0.287913 + outer loop + vertex 0.83367 1.06174 2.49849 + vertex 0.834769 1.05726 2.4981 + vertex 0.835043 1.06224 2.50332 + endloop + endfacet + facet normal -0.942864 -0.21525 0.254311 + outer loop + vertex 0.835043 1.06224 2.50332 + vertex 0.834769 1.05726 2.4981 + vertex 0.836025 1.0573 2.50279 + endloop + endfacet + facet normal -0.895995 -0.220184 0.385633 + outer loop + vertex 0.836025 1.0573 2.50279 + vertex 0.837008 1.06011 2.50668 + vertex 0.835043 1.06224 2.50332 + endloop + endfacet + facet normal -0.896016 -0.254243 0.364027 + outer loop + vertex 0.835043 1.06224 2.50332 + vertex 0.837008 1.06011 2.50668 + vertex 0.836262 1.06357 2.50725 + endloop + endfacet + facet normal -0.603079 -0.39918 0.690616 + outer loop + vertex 0.838425 1.06206 2.50904 + vertex 0.837008 1.06011 2.50668 + vertex 0.838786 1.05835 2.50721 + endloop + endfacet + facet normal -0.665299 -0.329172 0.670092 + outer loop + vertex 0.838425 1.06206 2.50904 + vertex 0.837469 1.06502 2.50954 + vertex 0.837008 1.06011 2.50668 + endloop + endfacet + facet normal -0.77484 -0.263195 0.574762 + outer loop + vertex 0.837469 1.06502 2.50954 + vertex 0.836262 1.06357 2.50725 + vertex 0.837008 1.06011 2.50668 + endloop + endfacet + facet normal -0.314401 -0.257142 0.9138 + outer loop + vertex 0.838425 1.06206 2.50904 + vertex 0.838936 1.0653 2.51013 + vertex 0.837469 1.06502 2.50954 + endloop + endfacet + facet normal -0.922999 -0.255213 0.287994 + outer loop + vertex 0.83367 1.06174 2.49849 + vertex 0.835043 1.06224 2.50332 + vertex 0.833371 1.06499 2.50041 + endloop + endfacet + facet normal -0.921649 -0.223568 0.317143 + outer loop + vertex 0.834031 1.06688 2.50366 + vertex 0.833371 1.06499 2.50041 + vertex 0.835043 1.06224 2.50332 + endloop + endfacet + facet normal -0.870576 -0.221257 0.43948 + outer loop + vertex 0.834031 1.06688 2.50366 + vertex 0.835043 1.06224 2.50332 + vertex 0.83582 1.06774 2.50764 + endloop + endfacet + facet normal -0.933841 -0.129318 0.333494 + outer loop + vertex 0.83582 1.06774 2.50764 + vertex 0.835043 1.06224 2.50332 + vertex 0.836262 1.06357 2.50725 + endloop + endfacet + facet normal -0.838 -0.137059 0.528177 + outer loop + vertex 0.836262 1.06357 2.50725 + vertex 0.837469 1.06502 2.50954 + vertex 0.83582 1.06774 2.50764 + endloop + endfacet + facet normal -0.832202 -0.125164 0.54016 + outer loop + vertex 0.83582 1.06774 2.50764 + vertex 0.837469 1.06502 2.50954 + vertex 0.837492 1.06901 2.51051 + endloop + endfacet + facet normal -0.318133 -0.220149 0.922131 + outer loop + vertex 0.837469 1.06502 2.50954 + vertex 0.838651 1.06858 2.5108 + vertex 0.837492 1.06901 2.51051 + endloop + endfacet + facet normal -0.324631 -0.217423 0.920512 + outer loop + vertex 0.838936 1.0653 2.51013 + vertex 0.838651 1.06858 2.5108 + vertex 0.837469 1.06502 2.50954 + endloop + endfacet + facet normal -0.877918 -0.195281 0.437178 + outer loop + vertex 0.834031 1.06688 2.50366 + vertex 0.83582 1.06774 2.50764 + vertex 0.834037 1.07038 2.50523 + endloop + endfacet + facet normal -0.84419 -0.089396 0.528538 + outer loop + vertex 0.835478 1.07343 2.50805 + vertex 0.834037 1.07038 2.50523 + vertex 0.83582 1.06774 2.50764 + endloop + endfacet + facet normal -0.747741 -0.0930256 0.657442 + outer loop + vertex 0.835478 1.07343 2.50805 + vertex 0.83582 1.06774 2.50764 + vertex 0.837271 1.07227 2.50993 + endloop + endfacet + facet normal -0.869307 0.0289759 0.493423 + outer loop + vertex 0.837271 1.07227 2.50993 + vertex 0.83582 1.06774 2.50764 + vertex 0.837492 1.06901 2.51051 + endloop + endfacet + facet normal -0.624391 0.0958576 0.775208 + outer loop + vertex 0.837492 1.06901 2.51051 + vertex 0.838352 1.07141 2.5109 + vertex 0.837271 1.07227 2.50993 + endloop + endfacet + facet normal -0.269162 -0.0624166 0.96107 + outer loop + vertex 0.838651 1.06858 2.5108 + vertex 0.838352 1.07141 2.5109 + vertex 0.837492 1.06901 2.51051 + endloop + endfacet + facet normal -0.234801 0.191153 0.953063 + outer loop + vertex 0.837271 1.07227 2.50993 + vertex 0.838635 1.0743 2.50985 + vertex 0.837799 1.07749 2.50901 + endloop + endfacet + facet normal -0.645584 0.194888 0.738404 + outer loop + vertex 0.837271 1.07227 2.50993 + vertex 0.837799 1.07749 2.50901 + vertex 0.835478 1.07343 2.50805 + endloop + endfacet + facet normal -0.0610005 -0.195516 0.978802 + outer loop + vertex 0.835478 1.07343 2.50805 + vertex 0.837799 1.07749 2.50901 + vertex 0.835206 1.07872 2.50909 + endloop + endfacet + facet normal -0.466597 0.341389 0.815929 + outer loop + vertex 0.838635 1.0743 2.50985 + vertex 0.837271 1.07227 2.50993 + vertex 0.838352 1.07141 2.5109 + endloop + endfacet + facet normal -0.856991 -0.462159 0.227984 + outer loop + vertex 0.84 1.08439 2.5 + vertex 0.839671 1.085 2.5 + vertex 0.839919 1.08413 2.49917 + endloop + endfacet + facet normal -0.401235 -0.488357 0.774931 + outer loop + vertex 0.835901 1.08302 2.51216 + vertex 0.834046 1.08147 2.51022 + vertex 0.835206 1.07872 2.50909 + endloop + endfacet + facet normal 0.527671 -0.548347 0.648752 + outer loop + vertex 0.835901 1.08302 2.51216 + vertex 0.835206 1.07872 2.50909 + vertex 0.837919 1.08262 2.51018 + endloop + endfacet + facet normal -0.0730974 -0.220713 0.972596 + outer loop + vertex 0.837919 1.08262 2.51018 + vertex 0.835206 1.07872 2.50909 + vertex 0.837799 1.07749 2.50901 + endloop + endfacet + facet normal -0.240671 -0.632351 0.736349 + outer loop + vertex 0.835901 1.08302 2.51216 + vertex 0.834274 1.08318 2.51177 + vertex 0.834046 1.08147 2.51022 + endloop + endfacet + facet normal 0.874627 0.0570323 -0.48143 + outer loop + vertex 0.839671 1.085 2.5 + vertex 0.839345 1.09 2.5 + vertex 0.84 1.09 2.50119 + endloop + endfacet + facet normal -0.886373 0.161571 -0.433864 + outer loop + vertex 0.839919 1.08413 2.49917 + vertex 0.839671 1.085 2.5 + vertex 0.84 1.09 2.50119 + endloop + endfacet + facet normal 0.513785 -0.572017 0.639391 + outer loop + vertex 0.837919 1.08262 2.51018 + vertex 0.838161 1.0857 2.51274 + vertex 0.835901 1.08302 2.51216 + endloop + endfacet + facet normal -0.24956 -0.493054 0.833437 + outer loop + vertex 0.835901 1.08302 2.51216 + vertex 0.834617 1.08587 2.51346 + vertex 0.834274 1.08318 2.51177 + endloop + endfacet + facet normal -0.337078 -0.512542 0.789734 + outer loop + vertex 0.835901 1.08302 2.51216 + vertex 0.836913 1.08655 2.51488 + vertex 0.834617 1.08587 2.51346 + endloop + endfacet + facet normal 0.564706 -0.599363 0.567337 + outer loop + vertex 0.835901 1.08302 2.51216 + vertex 0.838161 1.0857 2.51274 + vertex 0.836913 1.08655 2.51488 + endloop + endfacet + facet normal -0.183984 -0.73676 0.650641 + outer loop + vertex 0.835841 1.08763 2.5158 + vertex 0.834617 1.08587 2.51346 + vertex 0.836913 1.08655 2.51488 + endloop + endfacet + facet normal 0.0492904 -0.618188 0.784484 + outer loop + vertex 0.836913 1.08655 2.51488 + vertex 0.837161 1.09004 2.51762 + vertex 0.835841 1.08763 2.5158 + endloop + endfacet + facet normal -0.670922 -0.379834 0.636859 + outer loop + vertex 0.834617 1.08587 2.51346 + vertex 0.835841 1.08763 2.5158 + vertex 0.834629 1.08967 2.51574 + endloop + endfacet + facet normal -0.509728 -0.551405 0.660401 + outer loop + vertex 0.837464 1.09284 2.52029 + vertex 0.836439 1.09483 2.52116 + vertex 0.835428 1.09269 2.5186 + endloop + endfacet + facet normal -0.501845 -0.568025 0.652303 + outer loop + vertex 0.837161 1.09004 2.51762 + vertex 0.837464 1.09284 2.52029 + vertex 0.835428 1.09269 2.5186 + endloop + endfacet + facet normal -0.443852 -0.550385 0.707158 + outer loop + vertex 0.837161 1.09004 2.51762 + vertex 0.835428 1.09269 2.5186 + vertex 0.834629 1.08967 2.51574 + endloop + endfacet + facet normal -0.539795 -0.298006 0.787282 + outer loop + vertex 0.837161 1.09004 2.51762 + vertex 0.834629 1.08967 2.51574 + vertex 0.835841 1.08763 2.5158 + endloop + endfacet + facet normal -0.372711 -0.526547 0.76409 + outer loop + vertex 0.837464 1.09284 2.52029 + vertex 0.837991 1.09443 2.52164 + vertex 0.836439 1.09483 2.52116 + endloop + endfacet + facet normal -0.707131 -0.380667 0.595868 + outer loop + vertex 0.834312 1.09599 2.51938 + vertex 0.835428 1.09269 2.5186 + vertex 0.836439 1.09483 2.52116 + endloop + endfacet + facet normal -0.707134 -0.391517 0.588792 + outer loop + vertex 0.835638 1.09676 2.52148 + vertex 0.834312 1.09599 2.51938 + vertex 0.836439 1.09483 2.52116 + endloop + endfacet + facet normal -0.511114 -0.342714 0.788232 + outer loop + vertex 0.836439 1.09483 2.52116 + vertex 0.837708 1.09738 2.52309 + vertex 0.835638 1.09676 2.52148 + endloop + endfacet + facet normal -0.367193 -0.438686 0.820198 + outer loop + vertex 0.837991 1.09443 2.52164 + vertex 0.837708 1.09738 2.52309 + vertex 0.836439 1.09483 2.52116 + endloop + endfacet + facet normal -0.731652 -0.345519 0.587624 + outer loop + vertex 0.834312 1.09599 2.51938 + vertex 0.835638 1.09676 2.52148 + vertex 0.834128 1.09899 2.52092 + endloop + endfacet + facet normal -0.588851 -0.551915 0.590461 + outer loop + vertex 0.838333 1.10082 2.52588 + vertex 0.836281 1.10326 2.52612 + vertex 0.833999 1.10273 2.52335 + endloop + endfacet + facet normal -0.59017 -0.440862 0.676269 + outer loop + vertex 0.837708 1.09738 2.52309 + vertex 0.838333 1.10082 2.52588 + vertex 0.833999 1.10273 2.52335 + endloop + endfacet + facet normal -0.603355 -0.449182 0.658937 + outer loop + vertex 0.837708 1.09738 2.52309 + vertex 0.833999 1.10273 2.52335 + vertex 0.834128 1.09899 2.52092 + endloop + endfacet + facet normal -0.569694 -0.182342 0.801374 + outer loop + vertex 0.837708 1.09738 2.52309 + vertex 0.834128 1.09899 2.52092 + vertex 0.835638 1.09676 2.52148 + endloop + endfacet + facet normal -0.492762 -0.483836 0.723249 + outer loop + vertex 0.838333 1.10082 2.52588 + vertex 0.838566 1.10398 2.52815 + vertex 0.836281 1.10326 2.52612 + endloop + endfacet + facet normal -0.618851 -0.500605 0.605325 + outer loop + vertex 0.833999 1.10273 2.52335 + vertex 0.836281 1.10326 2.52612 + vertex 0.834194 1.10575 2.52604 + endloop + endfacet + facet normal -0.557442 -0.51373 0.652181 + outer loop + vertex 0.837932 1.10693 2.53005 + vertex 0.836061 1.10955 2.53052 + vertex 0.833953 1.10876 2.52809 + endloop + endfacet + facet normal -0.558148 -0.530121 0.638312 + outer loop + vertex 0.838566 1.10398 2.52815 + vertex 0.837932 1.10693 2.53005 + vertex 0.833953 1.10876 2.52809 + endloop + endfacet + facet normal -0.532742 -0.505129 0.678992 + outer loop + vertex 0.838566 1.10398 2.52815 + vertex 0.833953 1.10876 2.52809 + vertex 0.834194 1.10575 2.52604 + endloop + endfacet + facet normal -0.52698 -0.419472 0.739145 + outer loop + vertex 0.838566 1.10398 2.52815 + vertex 0.834194 1.10575 2.52604 + vertex 0.836281 1.10326 2.52612 + endloop + endfacet + facet normal -0.478112 -0.472638 0.740285 + outer loop + vertex 0.837932 1.10693 2.53005 + vertex 0.839913 1.10809 2.53207 + vertex 0.836061 1.10955 2.53052 + endloop + endfacet + facet normal -0.574085 -0.487256 0.658034 + outer loop + vertex 0.833953 1.10876 2.52809 + vertex 0.836061 1.10955 2.53052 + vertex 0.833343 1.11186 2.52986 + endloop + endfacet + facet normal -0.554134 -0.452093 0.698962 + outer loop + vertex 0.836061 1.10955 2.53052 + vertex 0.835571 1.1123 2.5319 + vertex 0.833343 1.11186 2.52986 + endloop + endfacet + facet normal -0.477137 -0.462712 0.747153 + outer loop + vertex 0.836061 1.10955 2.53052 + vertex 0.839913 1.10809 2.53207 + vertex 0.835571 1.1123 2.5319 + endloop + endfacet + facet normal -0.500442 -0.488065 0.715088 + outer loop + vertex 0.839913 1.10809 2.53207 + vertex 0.839647 1.11183 2.53444 + vertex 0.835571 1.1123 2.5319 + endloop + endfacet + facet normal -0.544936 -0.506072 0.668533 + outer loop + vertex 0.838651 1.1153 2.53618 + vertex 0.835934 1.11801 2.53603 + vertex 0.833603 1.11722 2.53353 + endloop + endfacet + facet normal -0.545011 -0.496718 0.675451 + outer loop + vertex 0.838651 1.1153 2.53618 + vertex 0.833603 1.11722 2.53353 + vertex 0.839647 1.11183 2.53444 + endloop + endfacet + facet normal -0.508843 -0.44589 0.736384 + outer loop + vertex 0.839647 1.11183 2.53444 + vertex 0.833603 1.11722 2.53353 + vertex 0.835571 1.1123 2.5319 + endloop + endfacet + facet normal -0.519035 -0.477803 0.708736 + outer loop + vertex 0.838651 1.1153 2.53618 + vertex 0.838327 1.11864 2.5382 + vertex 0.835934 1.11801 2.53603 + endloop + endfacet + facet normal -0.571054 -0.461615 0.678829 + outer loop + vertex 0.833603 1.11722 2.53353 + vertex 0.835934 1.11801 2.53603 + vertex 0.833727 1.12073 2.53602 + endloop + endfacet + facet normal -0.563028 -0.44754 0.694772 + outer loop + vertex 0.837903 1.12179 2.54004 + vertex 0.836367 1.12505 2.5409 + vertex 0.834259 1.12362 2.53827 + endloop + endfacet + facet normal -0.566123 -0.471886 0.675891 + outer loop + vertex 0.838327 1.11864 2.5382 + vertex 0.837903 1.12179 2.54004 + vertex 0.834259 1.12362 2.53827 + endloop + endfacet + facet normal -0.54189 -0.452546 0.708207 + outer loop + vertex 0.838327 1.11864 2.5382 + vertex 0.834259 1.12362 2.53827 + vertex 0.833727 1.12073 2.53602 + endloop + endfacet + facet normal -0.53999 -0.436231 0.719801 + outer loop + vertex 0.838327 1.11864 2.5382 + vertex 0.833727 1.12073 2.53602 + vertex 0.835934 1.11801 2.53603 + endloop + endfacet + facet normal -0.516953 -0.436746 0.736215 + outer loop + vertex 0.837903 1.12179 2.54004 + vertex 0.840371 1.12215 2.54199 + vertex 0.836367 1.12505 2.5409 + endloop + endfacet + facet normal -0.593318 -0.40472 0.695827 + outer loop + vertex 0.833076 1.12762 2.53959 + vertex 0.834259 1.12362 2.53827 + vertex 0.836367 1.12505 2.5409 + endloop + endfacet + facet normal -0.598947 -0.418674 0.682623 + outer loop + vertex 0.835193 1.12761 2.54144 + vertex 0.833076 1.12762 2.53959 + vertex 0.836367 1.12505 2.5409 + endloop + endfacet + facet normal -0.547627 -0.405553 0.731868 + outer loop + vertex 0.836367 1.12505 2.5409 + vertex 0.838576 1.12707 2.54367 + vertex 0.835193 1.12761 2.54144 + endloop + endfacet + facet normal -0.518342 -0.439701 0.733475 + outer loop + vertex 0.840371 1.12215 2.54199 + vertex 0.838576 1.12707 2.54367 + vertex 0.836367 1.12505 2.5409 + endloop + endfacet + facet normal -0.619736 -0.34131 0.706707 + outer loop + vertex 0.833076 1.12762 2.53959 + vertex 0.835193 1.12761 2.54144 + vertex 0.833654 1.13027 2.54137 + endloop + endfacet + facet normal -0.613235 -0.346437 0.709876 + outer loop + vertex 0.838978 1.13073 2.54612 + vertex 0.836381 1.1351 2.54602 + vertex 0.835089 1.13265 2.5437 + endloop + endfacet + facet normal -0.617834 -0.389789 0.682895 + outer loop + vertex 0.838576 1.12707 2.54367 + vertex 0.838978 1.13073 2.54612 + vertex 0.835089 1.13265 2.5437 + endloop + endfacet + facet normal -0.577989 -0.365087 0.729822 + outer loop + vertex 0.838576 1.12707 2.54367 + vertex 0.835089 1.13265 2.5437 + vertex 0.833654 1.13027 2.54137 + endloop + endfacet + facet normal -0.558087 -0.304 0.77209 + outer loop + vertex 0.838576 1.12707 2.54367 + vertex 0.833654 1.13027 2.54137 + vertex 0.835193 1.12761 2.54144 + endloop + endfacet + facet normal -0.615188 -0.347653 0.707588 + outer loop + vertex 0.838978 1.13073 2.54612 + vertex 0.840114 1.13317 2.54831 + vertex 0.836381 1.1351 2.54602 + endloop + endfacet + facet normal -0.661227 -0.300122 0.687536 + outer loop + vertex 0.832585 1.13765 2.54347 + vertex 0.835089 1.13265 2.5437 + vertex 0.836381 1.1351 2.54602 + endloop + endfacet + facet normal -0.662929 -0.307639 0.682556 + outer loop + vertex 0.834928 1.13798 2.5459 + vertex 0.832585 1.13765 2.54347 + vertex 0.836381 1.1351 2.54602 + endloop + endfacet + facet normal -0.636433 -0.292995 0.713517 + outer loop + vertex 0.836381 1.1351 2.54602 + vertex 0.837449 1.13817 2.54823 + vertex 0.834928 1.13798 2.5459 + endloop + endfacet + facet normal -0.609796 -0.312865 0.728193 + outer loop + vertex 0.840114 1.13317 2.54831 + vertex 0.837449 1.13817 2.54823 + vertex 0.836381 1.1351 2.54602 + endloop + endfacet + facet normal -0.716206 -0.0581799 0.69546 + outer loop + vertex 0.834399 1.18651 2.55782 + vertex 0.834707 1.18205 2.55776 + vertex 0.837063 1.18424 2.56037 + endloop + endfacet + facet normal -0.716086 -0.0578716 0.695609 + outer loop + vertex 0.836744 1.18917 2.56046 + vertex 0.834399 1.18651 2.55782 + vertex 0.837063 1.18424 2.56037 + endloop + endfacet + facet normal -0.701817 -0.0571916 0.710058 + outer loop + vertex 0.837063 1.18424 2.56037 + vertex 0.839461 1.18676 2.56295 + vertex 0.836744 1.18917 2.56046 + endloop + endfacet + facet normal -0.691704 -0.0751586 0.71826 + outer loop + vertex 0.840266 1.18133 2.56315 + vertex 0.839461 1.18676 2.56295 + vertex 0.837063 1.18424 2.56037 + endloop + endfacet + facet normal -0.65114 0.0532407 0.757088 + outer loop + vertex 0.837678 1.77989 2.57492 + vertex 0.836987 1.78321 2.57409 + vertex 0.835017 1.78016 2.57261 + endloop + endfacet + facet normal -0.652413 0.0388865 0.756865 + outer loop + vertex 0.837678 1.77989 2.57492 + vertex 0.835017 1.78016 2.57261 + vertex 0.836855 1.77631 2.5744 + endloop + endfacet + facet normal -0.647149 0.0433745 0.761128 + outer loop + vertex 0.836855 1.77631 2.5744 + vertex 0.835017 1.78016 2.57261 + vertex 0.834103 1.7762 2.57206 + endloop + endfacet + facet normal -0.648087 0.054507 0.759614 + outer loop + vertex 0.837678 1.77989 2.57492 + vertex 0.840049 1.78138 2.57684 + vertex 0.836987 1.78321 2.57409 + endloop + endfacet + facet normal -0.633134 0.29724 0.714695 + outer loop + vertex 0.836856 1.8766 2.5506 + vertex 0.838858 1.87836 2.55165 + vertex 0.837072 1.87993 2.54941 + endloop + endfacet + facet normal -0.660974 0.290825 0.691762 + outer loop + vertex 0.836856 1.8766 2.5506 + vertex 0.837072 1.87993 2.54941 + vertex 0.834224 1.87624 2.54824 + endloop + endfacet + facet normal -0.640476 0.265969 0.720452 + outer loop + vertex 0.834224 1.87624 2.54824 + vertex 0.837072 1.87993 2.54941 + vertex 0.834345 1.88113 2.54654 + endloop + endfacet + facet normal -0.624325 0.278226 0.729937 + outer loop + vertex 0.838858 1.87836 2.55165 + vertex 0.836856 1.8766 2.5506 + vertex 0.838641 1.87496 2.55276 + endloop + endfacet + facet normal -0.583837 0.375362 0.719887 + outer loop + vertex 0.836896 1.88752 2.54565 + vertex 0.83521 1.8885 2.54377 + vertex 0.834517 1.88523 2.54492 + endloop + endfacet + facet normal -0.577317 0.365237 0.730279 + outer loop + vertex 0.834517 1.88523 2.54492 + vertex 0.837693 1.88452 2.54778 + vertex 0.836896 1.88752 2.54565 + endloop + endfacet + facet normal -0.595102 0.317677 0.738197 + outer loop + vertex 0.834517 1.88523 2.54492 + vertex 0.834345 1.88113 2.54654 + vertex 0.837693 1.88452 2.54778 + endloop + endfacet + facet normal -0.607725 0.337164 0.719021 + outer loop + vertex 0.834345 1.88113 2.54654 + vertex 0.837072 1.87993 2.54941 + vertex 0.837693 1.88452 2.54778 + endloop + endfacet + facet normal -0.538221 0.43165 0.723876 + outer loop + vertex 0.836896 1.88752 2.54565 + vertex 0.839219 1.88829 2.54692 + vertex 0.838388 1.89116 2.54459 + endloop + endfacet + facet normal -0.54662 0.433002 0.71674 + outer loop + vertex 0.836896 1.88752 2.54565 + vertex 0.838388 1.89116 2.54459 + vertex 0.83521 1.8885 2.54377 + endloop + endfacet + facet normal -0.545577 0.431174 0.718634 + outer loop + vertex 0.83521 1.8885 2.54377 + vertex 0.838388 1.89116 2.54459 + vertex 0.834865 1.89163 2.54163 + endloop + endfacet + facet normal -0.537297 0.388769 0.748445 + outer loop + vertex 0.839219 1.88829 2.54692 + vertex 0.836896 1.88752 2.54565 + vertex 0.837693 1.88452 2.54778 + endloop + endfacet + facet normal -0.541593 0.444535 0.713488 + outer loop + vertex 0.836099 1.89816 2.53856 + vertex 0.83396 1.89734 2.53745 + vertex 0.834317 1.89522 2.53904 + endloop + endfacet + facet normal -0.53644 0.442272 0.718768 + outer loop + vertex 0.834317 1.89522 2.53904 + vertex 0.83815 1.89584 2.54152 + vertex 0.836099 1.89816 2.53856 + endloop + endfacet + facet normal -0.536991 0.438753 0.720512 + outer loop + vertex 0.834317 1.89522 2.53904 + vertex 0.834865 1.89163 2.54163 + vertex 0.83815 1.89584 2.54152 + endloop + endfacet + facet normal -0.541327 0.441989 0.71527 + outer loop + vertex 0.834865 1.89163 2.54163 + vertex 0.838388 1.89116 2.54459 + vertex 0.83815 1.89584 2.54152 + endloop + endfacet + facet normal -0.543671 0.443715 0.712418 + outer loop + vertex 0.837194 1.90175 2.53716 + vertex 0.834955 1.90312 2.5346 + vertex 0.834113 1.89976 2.53605 + endloop + endfacet + facet normal -0.541648 0.445889 0.712601 + outer loop + vertex 0.834113 1.89976 2.53605 + vertex 0.83396 1.89734 2.53745 + vertex 0.836099 1.89816 2.53856 + endloop + endfacet + facet normal -0.543599 0.443494 0.71261 + outer loop + vertex 0.837194 1.90175 2.53716 + vertex 0.834113 1.89976 2.53605 + vertex 0.836099 1.89816 2.53856 + endloop + endfacet + facet normal -0.537561 0.443444 0.717207 + outer loop + vertex 0.837194 1.90175 2.53716 + vertex 0.836099 1.89816 2.53856 + vertex 0.838881 1.9 2.53951 + endloop + endfacet + facet normal -0.543995 0.436466 0.716636 + outer loop + vertex 0.837194 1.90175 2.53716 + vertex 0.838881 1.9 2.53951 + vertex 0.839058 1.90204 2.5384 + endloop + endfacet + facet normal -0.536949 0.441747 0.718711 + outer loop + vertex 0.838881 1.9 2.53951 + vertex 0.836099 1.89816 2.53856 + vertex 0.83815 1.89584 2.54152 + endloop + endfacet + facet normal -0.535168 0.485429 0.691342 + outer loop + vertex 0.837194 1.90175 2.53716 + vertex 0.839355 1.90378 2.53741 + vertex 0.838009 1.90596 2.53484 + endloop + endfacet + facet normal -0.509851 0.489439 0.707461 + outer loop + vertex 0.837194 1.90175 2.53716 + vertex 0.838009 1.90596 2.53484 + vertex 0.834955 1.90312 2.5346 + endloop + endfacet + facet normal -0.491067 0.466874 0.735447 + outer loop + vertex 0.834955 1.90312 2.5346 + vertex 0.838009 1.90596 2.53484 + vertex 0.834373 1.90644 2.53211 + endloop + endfacet + facet normal -0.535006 0.485223 0.691612 + outer loop + vertex 0.839355 1.90378 2.53741 + vertex 0.837194 1.90175 2.53716 + vertex 0.839058 1.90204 2.5384 + endloop + endfacet + facet normal -0.437819 0.460396 0.772237 + outer loop + vertex 0.835704 1.91312 2.52879 + vertex 0.833578 1.91254 2.52793 + vertex 0.833854 1.91024 2.52946 + endloop + endfacet + facet normal -0.448145 0.464977 0.76352 + outer loop + vertex 0.833854 1.91024 2.52946 + vertex 0.837133 1.91005 2.5315 + vertex 0.835704 1.91312 2.52879 + endloop + endfacet + facet normal -0.446858 0.469004 0.761809 + outer loop + vertex 0.833854 1.91024 2.52946 + vertex 0.834373 1.90644 2.53211 + vertex 0.837133 1.91005 2.5315 + endloop + endfacet + facet normal -0.481622 0.489669 0.726818 + outer loop + vertex 0.834373 1.90644 2.53211 + vertex 0.838009 1.90596 2.53484 + vertex 0.837133 1.91005 2.5315 + endloop + endfacet + facet normal -0.305097 0.57276 0.76083 + outer loop + vertex 0.836665 1.91677 2.52604 + vertex 0.83392 1.91728 2.52456 + vertex 0.833643 1.91485 2.52628 + endloop + endfacet + facet normal -0.438155 0.531177 0.72517 + outer loop + vertex 0.833643 1.91485 2.52628 + vertex 0.833578 1.91254 2.52793 + vertex 0.835704 1.91312 2.52879 + endloop + endfacet + facet normal -0.340088 0.620911 0.706264 + outer loop + vertex 0.836665 1.91677 2.52604 + vertex 0.833643 1.91485 2.52628 + vertex 0.835704 1.91312 2.52879 + endloop + endfacet + facet normal -0.200768 0.62219 0.756685 + outer loop + vertex 0.836665 1.91677 2.52604 + vertex 0.835704 1.91312 2.52879 + vertex 0.839547 1.91414 2.52898 + endloop + endfacet + facet normal -0.353187 0.496141 0.793161 + outer loop + vertex 0.836665 1.91677 2.52604 + vertex 0.839547 1.91414 2.52898 + vertex 0.838849 1.91644 2.52723 + endloop + endfacet + facet normal -0.194986 0.596221 0.778782 + outer loop + vertex 0.839547 1.91414 2.52898 + vertex 0.835704 1.91312 2.52879 + vertex 0.837133 1.91005 2.5315 + endloop + endfacet + facet normal 0.436947 0.685448 0.582442 + outer loop + vertex 0.838587 1.9199 2.52138 + vertex 0.838072 1.92232 2.51891 + vertex 0.836569 1.92242 2.51992 + endloop + endfacet + facet normal -0.133623 0.847891 0.513055 + outer loop + vertex 0.836665 1.91677 2.52604 + vertex 0.83917 1.91763 2.52528 + vertex 0.838587 1.9199 2.52138 + endloop + endfacet + facet normal 0.149184 0.791861 0.5922 + outer loop + vertex 0.836665 1.91677 2.52604 + vertex 0.838587 1.9199 2.52138 + vertex 0.834593 1.92015 2.52206 + endloop + endfacet + facet normal -0.253191 0.66975 0.69809 + outer loop + vertex 0.836665 1.91677 2.52604 + vertex 0.834593 1.92015 2.52206 + vertex 0.83392 1.91728 2.52456 + endloop + endfacet + facet normal 0.169641 0.591231 0.788459 + outer loop + vertex 0.834593 1.92015 2.52206 + vertex 0.838587 1.9199 2.52138 + vertex 0.836569 1.92242 2.51992 + endloop + endfacet + facet normal -0.139659 0.854358 0.500567 + outer loop + vertex 0.83917 1.91763 2.52528 + vertex 0.836665 1.91677 2.52604 + vertex 0.838849 1.91644 2.52723 + endloop + endfacet + facet normal 0.766067 0.474707 0.433353 + outer loop + vertex 0.837344 1.92469 2.5168 + vertex 0.837475 1.92756 2.51342 + vertex 0.835735 1.92819 2.5158 + endloop + endfacet + facet normal 0.528207 0.401323 0.74829 + outer loop + vertex 0.835735 1.92819 2.5158 + vertex 0.833817 1.92879 2.51683 + vertex 0.834358 1.92492 2.51853 + endloop + endfacet + facet normal 0.476705 0.435666 0.76351 + outer loop + vertex 0.837344 1.92469 2.5168 + vertex 0.835735 1.92819 2.5158 + vertex 0.834358 1.92492 2.51853 + endloop + endfacet + facet normal 0.401799 0.691537 0.600279 + outer loop + vertex 0.837344 1.92469 2.5168 + vertex 0.834358 1.92492 2.51853 + vertex 0.836569 1.92242 2.51992 + endloop + endfacet + facet normal 0.444332 0.66972 0.595016 + outer loop + vertex 0.837344 1.92469 2.5168 + vertex 0.836569 1.92242 2.51992 + vertex 0.838072 1.92232 2.51891 + endloop + endfacet + facet normal 0.169711 0.591188 0.788477 + outer loop + vertex 0.836569 1.92242 2.51992 + vertex 0.834358 1.92492 2.51853 + vertex 0.834593 1.92015 2.52206 + endloop + endfacet + facet normal -0.706593 0.631852 0.318573 + outer loop + vertex 0.838856 1.92933 2.50678 + vertex 0.84 1.93 2.50799 + vertex 0.838652 1.93 2.505 + endloop + endfacet + facet normal 0.95486 0.297048 0.00231577 + outer loop + vertex 0.838856 1.92933 2.50678 + vertex 0.838652 1.93 2.505 + vertex 0.837916 1.93236 2.50631 + endloop + endfacet + facet normal 0.818358 -0.0621919 0.571334 + outer loop + vertex 0.837916 1.93236 2.50631 + vertex 0.838652 1.93 2.505 + vertex 0.839032 1.935 2.505 + endloop + endfacet + facet normal 0.922458 0.320214 0.215719 + outer loop + vertex 0.838377 1.92878 2.50965 + vertex 0.838856 1.92933 2.50678 + vertex 0.837916 1.93236 2.50631 + endloop + endfacet + facet normal 0.875107 0.385643 0.292347 + outer loop + vertex 0.836596 1.9315 2.5114 + vertex 0.838377 1.92878 2.50965 + vertex 0.837916 1.93236 2.50631 + endloop + endfacet + facet normal 0.872999 0.362547 0.32624 + outer loop + vertex 0.837475 1.92756 2.51342 + vertex 0.838377 1.92878 2.50965 + vertex 0.836596 1.9315 2.5114 + endloop + endfacet + facet normal 0.784211 0.413038 0.463048 + outer loop + vertex 0.837475 1.92756 2.51342 + vertex 0.836596 1.9315 2.5114 + vertex 0.835735 1.92819 2.5158 + endloop + endfacet + facet normal 0.836912 0.346651 0.423569 + outer loop + vertex 0.835735 1.92819 2.5158 + vertex 0.836596 1.9315 2.5114 + vertex 0.834698 1.93172 2.51496 + endloop + endfacet + facet normal 0.52589 0.339749 0.77975 + outer loop + vertex 0.834698 1.93172 2.51496 + vertex 0.833817 1.92879 2.51683 + vertex 0.835735 1.92819 2.5158 + endloop + endfacet + facet normal 0.390062 0.40943 0.824754 + outer loop + vertex 0.833082 1.93123 2.51597 + vertex 0.833817 1.92879 2.51683 + vertex 0.834698 1.93172 2.51496 + endloop + endfacet + facet normal 0.743262 0.0178355 0.668763 + outer loop + vertex 0.839032 1.935 2.505 + vertex 0.838912 1.94 2.505 + vertex 0.837916 1.93236 2.50631 + endloop + endfacet + facet normal 0.710115 0.0281179 0.703524 + outer loop + vertex 0.838912 1.94 2.505 + vertex 0.837075 1.93686 2.50698 + vertex 0.837916 1.93236 2.50631 + endloop + endfacet + facet normal 0.952816 0.137614 0.270562 + outer loop + vertex 0.837916 1.93236 2.50631 + vertex 0.837075 1.93686 2.50698 + vertex 0.836596 1.9315 2.5114 + endloop + endfacet + facet normal 0.890086 0.239609 0.38773 + outer loop + vertex 0.837075 1.93686 2.50698 + vertex 0.835162 1.93627 2.51173 + vertex 0.836596 1.9315 2.5114 + endloop + endfacet + facet normal 0.600787 0.455064 0.657245 + outer loop + vertex 0.833638 1.9341 2.51463 + vertex 0.835162 1.93627 2.51173 + vertex 0.83309 1.93728 2.51293 + endloop + endfacet + facet normal 0.665865 0.385098 0.639002 + outer loop + vertex 0.833638 1.9341 2.51463 + vertex 0.834698 1.93172 2.51496 + vertex 0.835162 1.93627 2.51173 + endloop + endfacet + facet normal 0.865427 0.22807 0.446117 + outer loop + vertex 0.834698 1.93172 2.51496 + vertex 0.836596 1.9315 2.5114 + vertex 0.835162 1.93627 2.51173 + endloop + endfacet + facet normal 0.433287 0.310395 0.846119 + outer loop + vertex 0.834698 1.93172 2.51496 + vertex 0.833638 1.9341 2.51463 + vertex 0.833082 1.93123 2.51597 + endloop + endfacet + facet normal 0.999086 -0.0175911 0.0389568 + outer loop + vertex 0.839107 1.94 2.5 + vertex 0.839195 1.945 2.5 + vertex 0.838912 1.94 2.505 + endloop + endfacet + facet normal 0.15127 0.694684 0.703229 + outer loop + vertex 0.839195 1.945 2.5 + vertex 0.83818 1.94273 2.50246 + vertex 0.838912 1.94 2.505 + endloop + endfacet + facet normal -0.259687 0.619579 0.740732 + outer loop + vertex 0.838912 1.94 2.505 + vertex 0.83818 1.94273 2.50246 + vertex 0.837075 1.93686 2.50698 + endloop + endfacet + facet normal 0.950408 0.0566536 0.305801 + outer loop + vertex 0.83818 1.94273 2.50246 + vertex 0.836579 1.94156 2.50765 + vertex 0.837075 1.93686 2.50698 + endloop + endfacet + facet normal 0.924976 0.0437198 0.377502 + outer loop + vertex 0.837075 1.93686 2.50698 + vertex 0.836579 1.94156 2.50765 + vertex 0.835162 1.93627 2.51173 + endloop + endfacet + facet normal 0.752448 0.264345 0.603278 + outer loop + vertex 0.836579 1.94156 2.50765 + vertex 0.834216 1.94084 2.51092 + vertex 0.835162 1.93627 2.51173 + endloop + endfacet + facet normal 0.574135 0.258493 0.776885 + outer loop + vertex 0.834216 1.94084 2.51092 + vertex 0.83309 1.93728 2.51293 + vertex 0.835162 1.93627 2.51173 + endloop + endfacet + facet normal 0.0740391 0.473929 0.877445 + outer loop + vertex 0.832397 1.94046 2.51127 + vertex 0.83309 1.93728 2.51293 + vertex 0.834216 1.94084 2.51092 + endloop + endfacet + facet normal 0.981802 -0.170297 0.0840396 + outer loop + vertex 0.839038 1.94662 2.50031 + vertex 0.838491 1.94514 2.5037 + vertex 0.83818 1.94273 2.50246 + endloop + endfacet + facet normal -0.978005 0.208101 -0.0141583 + outer loop + vertex 0.839038 1.94662 2.50031 + vertex 0.83818 1.94273 2.50246 + vertex 0.839762 1.95 2.5 + endloop + endfacet + facet normal 0.950024 -0.107725 0.293001 + outer loop + vertex 0.839762 1.95 2.5 + vertex 0.83818 1.94273 2.50246 + vertex 0.839195 1.945 2.5 + endloop + endfacet + facet normal 0.93938 -0.273187 0.207203 + outer loop + vertex 0.838491 1.94514 2.5037 + vertex 0.837729 1.94561 2.50778 + vertex 0.836579 1.94156 2.50765 + endloop + endfacet + facet normal 0.941038 -0.243167 0.235196 + outer loop + vertex 0.83818 1.94273 2.50246 + vertex 0.838491 1.94514 2.5037 + vertex 0.836579 1.94156 2.50765 + endloop + endfacet + facet normal 0.807159 0.0249288 0.589807 + outer loop + vertex 0.834216 1.94084 2.51092 + vertex 0.836579 1.94156 2.50765 + vertex 0.83508 1.94548 2.50954 + endloop + endfacet + facet normal -0.14476 0.306312 0.94086 + outer loop + vertex 0.834216 1.94084 2.51092 + vertex 0.83508 1.94548 2.50954 + vertex 0.832769 1.94339 2.50986 + endloop + endfacet + facet normal 0.549871 -0.182037 0.815172 + outer loop + vertex 0.836579 1.94156 2.50765 + vertex 0.837729 1.94561 2.50778 + vertex 0.83508 1.94548 2.50954 + endloop + endfacet + facet normal -0.032886 -0.340476 0.939678 + outer loop + vertex 0.836433 1.94923 2.51094 + vertex 0.83508 1.94548 2.50954 + vertex 0.837304 1.94713 2.51021 + endloop + endfacet + facet normal 0.39276 -0.748064 0.53492 + outer loop + vertex 0.837729 1.94561 2.50778 + vertex 0.837304 1.94713 2.51021 + vertex 0.83508 1.94548 2.50954 + endloop + endfacet + facet normal 0.0410404 -0.313026 0.948857 + outer loop + vertex 0.837304 1.94713 2.51021 + vertex 0.838013 1.94935 2.51092 + vertex 0.836433 1.94923 2.51094 + endloop + endfacet + facet normal 0.0894439 0.42284 0.901779 + outer loop + vertex 0.834216 1.94084 2.51092 + vertex 0.832769 1.94339 2.50986 + vertex 0.832397 1.94046 2.51127 + endloop + endfacet + facet normal 0.122346 -0.116483 -0.985628 + outer loop + vertex 0.84 1.95025 2.5 + vertex 0.839038 1.94662 2.50031 + vertex 0.839762 1.95 2.5 + endloop + endfacet + facet normal -0.665505 -0.039341 0.745356 + outer loop + vertex 0.834154 1.95033 2.50897 + vertex 0.83508 1.94548 2.50954 + vertex 0.836433 1.94923 2.51094 + endloop + endfacet + facet normal -0.654064 0.00438853 0.756426 + outer loop + vertex 0.83608 1.95335 2.51061 + vertex 0.834154 1.95033 2.50897 + vertex 0.836433 1.94923 2.51094 + endloop + endfacet + facet normal -0.356566 0.0440421 0.933231 + outer loop + vertex 0.836433 1.94923 2.51094 + vertex 0.837859 1.95245 2.51134 + vertex 0.83608 1.95335 2.51061 + endloop + endfacet + facet normal 0.0276483 -0.13315 0.99071 + outer loop + vertex 0.838013 1.94935 2.51092 + vertex 0.837859 1.95245 2.51134 + vertex 0.836433 1.94923 2.51094 + endloop + endfacet + facet normal -0.756561 0.133135 0.640227 + outer loop + vertex 0.834254 1.95498 2.50812 + vertex 0.834154 1.95033 2.50897 + vertex 0.83608 1.95335 2.51061 + endloop + endfacet + facet normal -0.753174 0.140594 0.642621 + outer loop + vertex 0.836115 1.95832 2.50957 + vertex 0.834254 1.95498 2.50812 + vertex 0.83608 1.95335 2.51061 + endloop + endfacet + facet normal -0.556291 0.174953 0.812362 + outer loop + vertex 0.83608 1.95335 2.51061 + vertex 0.837776 1.95677 2.51104 + vertex 0.836115 1.95832 2.50957 + endloop + endfacet + facet normal -0.350341 0.0576725 0.934845 + outer loop + vertex 0.837859 1.95245 2.51134 + vertex 0.837776 1.95677 2.51104 + vertex 0.83608 1.95335 2.51061 + endloop + endfacet + facet normal -0.845632 0.233125 0.480166 + outer loop + vertex 0.835279 1.96218 2.50691 + vertex 0.833797 1.96098 2.50488 + vertex 0.834433 1.9586 2.50715 + endloop + endfacet + facet normal -0.794355 0.19239 0.576182 + outer loop + vertex 0.834433 1.9586 2.50715 + vertex 0.834254 1.95498 2.50812 + vertex 0.836115 1.95832 2.50957 + endloop + endfacet + facet normal -0.786599 0.22575 0.574716 + outer loop + vertex 0.834433 1.9586 2.50715 + vertex 0.836115 1.95832 2.50957 + vertex 0.835279 1.96218 2.50691 + endloop + endfacet + facet normal -0.742287 0.263747 0.615993 + outer loop + vertex 0.835279 1.96218 2.50691 + vertex 0.836115 1.95832 2.50957 + vertex 0.837149 1.96326 2.5087 + endloop + endfacet + facet normal -0.658583 0.261972 0.705436 + outer loop + vertex 0.836115 1.95832 2.50957 + vertex 0.837845 1.96051 2.51037 + vertex 0.837149 1.96326 2.5087 + endloop + endfacet + facet normal -0.569962 0.15511 0.806898 + outer loop + vertex 0.837776 1.95677 2.51104 + vertex 0.837845 1.96051 2.51037 + vertex 0.836115 1.95832 2.50957 + endloop + endfacet + facet normal -0.845507 0.230302 0.481746 + outer loop + vertex 0.834128 1.96495 2.50356 + vertex 0.833797 1.96098 2.50488 + vertex 0.835279 1.96218 2.50691 + endloop + endfacet + facet normal -0.815559 0.275556 0.508854 + outer loop + vertex 0.83625 1.96774 2.50545 + vertex 0.834128 1.96495 2.50356 + vertex 0.835279 1.96218 2.50691 + endloop + endfacet + facet normal -0.374175 0.419827 0.826884 + outer loop + vertex 0.838494 1.96712 2.50735 + vertex 0.837149 1.96326 2.5087 + vertex 0.838672 1.96363 2.5092 + endloop + endfacet + facet normal -0.506722 0.436706 0.743317 + outer loop + vertex 0.838494 1.96712 2.50735 + vertex 0.83625 1.96774 2.50545 + vertex 0.837149 1.96326 2.5087 + endloop + endfacet + facet normal -0.743834 0.287741 0.603254 + outer loop + vertex 0.83625 1.96774 2.50545 + vertex 0.835279 1.96218 2.50691 + vertex 0.837149 1.96326 2.5087 + endloop + endfacet + facet normal -0.373575 0.411071 0.831542 + outer loop + vertex 0.838672 1.96363 2.5092 + vertex 0.837149 1.96326 2.5087 + vertex 0.837845 1.96051 2.51037 + endloop + endfacet + facet normal -0.842963 0.26699 0.467044 + outer loop + vertex 0.835278 1.97223 2.502 + vertex 0.833757 1.97138 2.49974 + vertex 0.834359 1.96886 2.50227 + endloop + endfacet + facet normal -0.798592 0.230974 0.55579 + outer loop + vertex 0.834359 1.96886 2.50227 + vertex 0.834128 1.96495 2.50356 + vertex 0.83625 1.96774 2.50545 + endloop + endfacet + facet normal -0.787531 0.259174 0.559128 + outer loop + vertex 0.834359 1.96886 2.50227 + vertex 0.83625 1.96774 2.50545 + vertex 0.835278 1.97223 2.502 + endloop + endfacet + facet normal -0.701619 0.332424 0.630257 + outer loop + vertex 0.835278 1.97223 2.502 + vertex 0.83625 1.96774 2.50545 + vertex 0.837455 1.97261 2.50422 + endloop + endfacet + facet normal -0.589471 0.331481 0.736643 + outer loop + vertex 0.83625 1.96774 2.50545 + vertex 0.838247 1.97031 2.50589 + vertex 0.837455 1.97261 2.50422 + endloop + endfacet + facet normal -0.56328 0.305805 0.767593 + outer loop + vertex 0.838494 1.96712 2.50735 + vertex 0.838247 1.97031 2.50589 + vertex 0.83625 1.96774 2.50545 + endloop + endfacet + facet normal -0.842131 0.276953 0.462723 + outer loop + vertex 0.834193 1.97504 2.49834 + vertex 0.833757 1.97138 2.49974 + vertex 0.835278 1.97223 2.502 + endloop + endfacet + facet normal -0.802714 0.333417 0.494453 + outer loop + vertex 0.836682 1.9774 2.50079 + vertex 0.834193 1.97504 2.49834 + vertex 0.835278 1.97223 2.502 + endloop + endfacet + facet normal -0.459686 0.470522 0.753192 + outer loop + vertex 0.839669 1.97518 2.50397 + vertex 0.837455 1.97261 2.50422 + vertex 0.838887 1.97239 2.50524 + endloop + endfacet + facet normal -0.456559 0.468158 0.75656 + outer loop + vertex 0.839669 1.97518 2.50397 + vertex 0.836682 1.9774 2.50079 + vertex 0.837455 1.97261 2.50422 + endloop + endfacet + facet normal -0.700813 0.337132 0.628652 + outer loop + vertex 0.836682 1.9774 2.50079 + vertex 0.835278 1.97223 2.502 + vertex 0.837455 1.97261 2.50422 + endloop + endfacet + facet normal -0.488722 0.39576 0.777512 + outer loop + vertex 0.838887 1.97239 2.50524 + vertex 0.837455 1.97261 2.50422 + vertex 0.838247 1.97031 2.50589 + endloop + endfacet + facet normal -0.873709 0.309346 0.375417 + outer loop + vertex 0.835523 1.98267 2.49577 + vertex 0.83405 1.98085 2.49384 + vertex 0.834535 1.97873 2.49672 + endloop + endfacet + facet normal -0.798822 0.303289 0.519518 + outer loop + vertex 0.834535 1.97873 2.49672 + vertex 0.834193 1.97504 2.49834 + vertex 0.836682 1.9774 2.50079 + endloop + endfacet + facet normal -0.789674 0.323547 0.521279 + outer loop + vertex 0.834535 1.97873 2.49672 + vertex 0.836682 1.9774 2.50079 + vertex 0.835523 1.98267 2.49577 + endloop + endfacet + facet normal -0.858554 0.242239 0.45189 + outer loop + vertex 0.835523 1.98267 2.49577 + vertex 0.836682 1.9774 2.50079 + vertex 0.837838 1.98289 2.50005 + endloop + endfacet + facet normal -0.712592 0.239638 0.659383 + outer loop + vertex 0.836682 1.9774 2.50079 + vertex 0.840018 1.98021 2.50338 + vertex 0.837838 1.98289 2.50005 + endloop + endfacet + facet normal -0.674298 0.132241 0.726522 + outer loop + vertex 0.839669 1.97518 2.50397 + vertex 0.840018 1.98021 2.50338 + vertex 0.836682 1.9774 2.50079 + endloop + endfacet + facet normal -0.662905 0.470046 0.582764 + outer loop + vertex 0.835487 1.98794 2.49106 + vertex 0.836014 1.99 2.49 + vertex 0.835 1.98857 2.49 + endloop + endfacet + facet normal -0.777154 0.316201 0.544104 + outer loop + vertex 0.834463 1.98403 2.49187 + vertex 0.835487 1.98794 2.49106 + vertex 0.835 1.98857 2.49 + endloop + endfacet + facet normal -0.874213 0.332525 0.353805 + outer loop + vertex 0.834463 1.98403 2.49187 + vertex 0.83405 1.98085 2.49384 + vertex 0.835523 1.98267 2.49577 + endloop + endfacet + facet normal -0.886967 0.304267 0.347435 + outer loop + vertex 0.834463 1.98403 2.49187 + vertex 0.835523 1.98267 2.49577 + vertex 0.835487 1.98794 2.49106 + endloop + endfacet + facet normal -0.912525 0.268981 0.308135 + outer loop + vertex 0.835487 1.98794 2.49106 + vertex 0.835523 1.98267 2.49577 + vertex 0.837136 1.98781 2.49605 + endloop + endfacet + facet normal -0.832649 0.175041 0.525411 + outer loop + vertex 0.83867 1.98628 2.50024 + vertex 0.837838 1.98289 2.50005 + vertex 0.839634 1.98393 2.50255 + endloop + endfacet + facet normal -0.894868 0.197138 0.400435 + outer loop + vertex 0.83867 1.98628 2.50024 + vertex 0.837136 1.98781 2.49605 + vertex 0.837838 1.98289 2.50005 + endloop + endfacet + facet normal -0.858225 0.243882 0.451631 + outer loop + vertex 0.837136 1.98781 2.49605 + vertex 0.835523 1.98267 2.49577 + vertex 0.837838 1.98289 2.50005 + endloop + endfacet + facet normal -0.819636 0.0430772 0.571263 + outer loop + vertex 0.839634 1.98393 2.50255 + vertex 0.837838 1.98289 2.50005 + vertex 0.840018 1.98021 2.50338 + endloop + endfacet + facet normal 0.0244584 0.999519 -0.019076 + outer loop + vertex 0.834662 1.98994 2.48502 + vertex 0.835 1.99 2.4887 + vertex 0.836014 1.99 2.49 + endloop + endfacet + facet normal -0.947048 0.195739 0.254533 + outer loop + vertex 0.835709 1.99279 2.48672 + vertex 0.834662 1.98994 2.48502 + vertex 0.836014 1.99 2.49 + endloop + endfacet + facet normal 0.790889 -0.42793 -0.437459 + outer loop + vertex 0.836014 1.99 2.49 + vertex 0.835487 1.98794 2.49106 + vertex 0.835709 1.99279 2.48672 + endloop + endfacet + facet normal -0.946147 0.238907 0.218473 + outer loop + vertex 0.835709 1.99279 2.48672 + vertex 0.835487 1.98794 2.49106 + vertex 0.836633 1.99266 2.49086 + endloop + endfacet + facet normal -0.920818 0.23658 0.310039 + outer loop + vertex 0.835487 1.98794 2.49106 + vertex 0.837136 1.98781 2.49605 + vertex 0.836633 1.99266 2.49086 + endloop + endfacet + facet normal -0.941848 0.195263 0.273487 + outer loop + vertex 0.836633 1.99266 2.49086 + vertex 0.837136 1.98781 2.49605 + vertex 0.83792 1.99308 2.49499 + endloop + endfacet + facet normal -0.894255 0.212448 0.39392 + outer loop + vertex 0.837136 1.98781 2.49605 + vertex 0.838936 1.99014 2.49889 + vertex 0.83792 1.99308 2.49499 + endloop + endfacet + facet normal -0.89318 0.202209 0.401672 + outer loop + vertex 0.83867 1.98628 2.50024 + vertex 0.838936 1.99014 2.49889 + vertex 0.837136 1.98781 2.49605 + endloop + endfacet + facet normal -0.890489 0.0578882 0.451307 + outer loop + vertex 0.835 1.99528 2.485 + vertex 0.834662 1.98994 2.48502 + vertex 0.835709 1.99279 2.48672 + endloop + endfacet + facet normal -0.589203 0.338545 0.73364 + outer loop + vertex 0.835 1.99528 2.485 + vertex 0.835709 1.99279 2.48672 + vertex 0.837712 2 2.485 + endloop + endfacet + facet normal -0.964445 0.243608 -0.102477 + outer loop + vertex 0.837712 2 2.485 + vertex 0.835709 1.99279 2.48672 + vertex 0.836991 1.99787 2.48672 + endloop + endfacet + facet normal -0.946166 0.238827 0.218475 + outer loop + vertex 0.835709 1.99279 2.48672 + vertex 0.836633 1.99266 2.49086 + vertex 0.836991 1.99787 2.48672 + endloop + endfacet + facet normal -0.960343 0.211001 0.182264 + outer loop + vertex 0.836991 1.99787 2.48672 + vertex 0.836633 1.99266 2.49086 + vertex 0.837764 1.9978 2.49087 + endloop + endfacet + facet normal -0.89481 0.217766 0.389734 + outer loop + vertex 0.838702 1.99642 2.49492 + vertex 0.83792 1.99308 2.49499 + vertex 0.839231 1.99393 2.49753 + endloop + endfacet + facet normal -0.929972 0.223964 0.291533 + outer loop + vertex 0.838702 1.99642 2.49492 + vertex 0.837764 1.9978 2.49087 + vertex 0.83792 1.99308 2.49499 + endloop + endfacet + facet normal -0.939977 0.206362 0.271767 + outer loop + vertex 0.837764 1.9978 2.49087 + vertex 0.836633 1.99266 2.49086 + vertex 0.83792 1.99308 2.49499 + endloop + endfacet + facet normal -0.895382 0.210237 0.392545 + outer loop + vertex 0.839231 1.99393 2.49753 + vertex 0.83792 1.99308 2.49499 + vertex 0.838936 1.99014 2.49889 + endloop + endfacet + facet normal -0.959047 0.115662 -0.258557 + outer loop + vertex 0.837712 2 2.485 + vertex 0.836991 1.99787 2.48672 + vertex 0.838315 2.005 2.485 + endloop + endfacet + facet normal -0.951477 0.107031 -0.288505 + outer loop + vertex 0.838315 2.005 2.485 + vertex 0.836991 1.99787 2.48672 + vertex 0.837714 2.00247 2.48604 + endloop + endfacet + facet normal -0.966745 0.178746 0.182902 + outer loop + vertex 0.836991 1.99787 2.48672 + vertex 0.837764 1.9978 2.49087 + vertex 0.837714 2.00247 2.48604 + endloop + endfacet + facet normal -0.9683 0.174458 0.178772 + outer loop + vertex 0.837714 2.00247 2.48604 + vertex 0.837764 1.9978 2.49087 + vertex 0.838382 2.00277 2.48937 + endloop + endfacet + facet normal -0.9167 0.215642 0.336392 + outer loop + vertex 0.837764 1.9978 2.49087 + vertex 0.839212 2.00005 2.49338 + vertex 0.838382 2.00277 2.48937 + endloop + endfacet + facet normal -0.918548 0.257203 0.300193 + outer loop + vertex 0.838702 1.99642 2.49492 + vertex 0.839212 2.00005 2.49338 + vertex 0.837764 1.9978 2.49087 + endloop + endfacet + facet normal -0.889602 -0.33953 -0.305496 + outer loop + vertex 0.84 2.005 2.4801 + vertex 0.838126 2.01 2.48 + vertex 0.84 2.00509 2.48 + endloop + endfacet + facet normal -0.889487 -0.339494 -0.305869 + outer loop + vertex 0.84 2.005 2.4801 + vertex 0.838315 2.005 2.485 + vertex 0.838126 2.01 2.48 + endloop + endfacet + facet normal 0.971926 -0.146986 -0.183727 + outer loop + vertex 0.838315 2.005 2.485 + vertex 0.838017 2.00721 2.48166 + vertex 0.838126 2.01 2.48 + endloop + endfacet + facet normal 0.892034 -0.336446 -0.301794 + outer loop + vertex 0.838315 2.005 2.485 + vertex 0.837714 2.00247 2.48604 + vertex 0.838017 2.00721 2.48166 + endloop + endfacet + facet normal -0.988731 0.130746 0.0729184 + outer loop + vertex 0.838017 2.00721 2.48166 + vertex 0.837714 2.00247 2.48604 + vertex 0.838251 2.00692 2.48534 + endloop + endfacet + facet normal -0.90579 0.213784 0.365842 + outer loop + vertex 0.838932 2.00593 2.48888 + vertex 0.838382 2.00277 2.48937 + vertex 0.839541 2.00372 2.49169 + endloop + endfacet + facet normal -0.949759 0.201928 0.239131 + outer loop + vertex 0.838932 2.00593 2.48888 + vertex 0.838251 2.00692 2.48534 + vertex 0.838382 2.00277 2.48937 + endloop + endfacet + facet normal -0.972374 0.145964 0.182165 + outer loop + vertex 0.838251 2.00692 2.48534 + vertex 0.837714 2.00247 2.48604 + vertex 0.838382 2.00277 2.48937 + endloop + endfacet + facet normal -0.903555 0.243465 0.35258 + outer loop + vertex 0.839541 2.00372 2.49169 + vertex 0.838382 2.00277 2.48937 + vertex 0.839212 2.00005 2.49338 + endloop + endfacet + facet normal 0.390373 0.0477858 -0.919416 + outer loop + vertex 0.84 2.01 2.47813 + vertex 0.83859 2.01152 2.47761 + vertex 0.84 2.015 2.47839 + endloop + endfacet + facet normal -0.52642 -0.666754 -0.527561 + outer loop + vertex 0.838126 2.01 2.48 + vertex 0.83859 2.01152 2.47761 + vertex 0.84 2.01 2.47813 + endloop + endfacet + facet normal 0.958098 0.117544 0.261211 + outer loop + vertex 0.838126 2.01 2.48 + vertex 0.838017 2.00721 2.48166 + vertex 0.83859 2.01152 2.47761 + endloop + endfacet + facet normal -0.995157 0.0831667 -0.0523972 + outer loop + vertex 0.83859 2.01152 2.47761 + vertex 0.838017 2.00721 2.48166 + vertex 0.838416 2.01141 2.48075 + endloop + endfacet + facet normal -0.950608 0.194183 0.242152 + outer loop + vertex 0.838741 2.01062 2.4843 + vertex 0.838251 2.00692 2.48534 + vertex 0.839064 2.00871 2.4871 + endloop + endfacet + facet normal -0.978111 0.165232 0.126479 + outer loop + vertex 0.838741 2.01062 2.4843 + vertex 0.838416 2.01141 2.48075 + vertex 0.838251 2.00692 2.48534 + endloop + endfacet + facet normal -0.991424 0.109432 0.0714357 + outer loop + vertex 0.838416 2.01141 2.48075 + vertex 0.838017 2.00721 2.48166 + vertex 0.838251 2.00692 2.48534 + endloop + endfacet + facet normal -0.950783 0.198103 0.238257 + outer loop + vertex 0.839064 2.00871 2.4871 + vertex 0.838251 2.00692 2.48534 + vertex 0.838932 2.00593 2.48888 + endloop + endfacet + facet normal 0.926485 -0.266106 -0.266106 + outer loop + vertex 0.84 2.01953 2.475 + vertex 0.83906 2.01612 2.47514 + vertex 0.84 2.02 2.47453 + endloop + endfacet + facet normal 0.899222 -0.26213 -0.350268 + outer loop + vertex 0.84 2.015 2.47839 + vertex 0.83906 2.01612 2.47514 + vertex 0.84 2.01953 2.475 + endloop + endfacet + facet normal 0.891424 -0.281914 -0.354807 + outer loop + vertex 0.84 2.015 2.47839 + vertex 0.83859 2.01152 2.47761 + vertex 0.83906 2.01612 2.47514 + endloop + endfacet + facet normal -0.995204 0.0605364 -0.0768453 + outer loop + vertex 0.83859 2.01152 2.47761 + vertex 0.838885 2.01568 2.47707 + vertex 0.83906 2.01612 2.47514 + endloop + endfacet + facet normal -0.965848 0.204352 0.159305 + outer loop + vertex 0.839131 2.01572 2.47957 + vertex 0.838416 2.01141 2.48075 + vertex 0.839102 2.01352 2.48221 + endloop + endfacet + facet normal -0.977622 0.188286 0.0938307 + outer loop + vertex 0.839131 2.01572 2.47957 + vertex 0.838885 2.01568 2.47707 + vertex 0.838416 2.01141 2.48075 + endloop + endfacet + facet normal -0.996553 0.0636923 -0.0531577 + outer loop + vertex 0.838885 2.01568 2.47707 + vertex 0.83859 2.01152 2.47761 + vertex 0.838416 2.01141 2.48075 + endloop + endfacet + facet normal -0.965872 0.21951 0.137498 + outer loop + vertex 0.839102 2.01352 2.48221 + vertex 0.838416 2.01141 2.48075 + vertex 0.838741 2.01062 2.4843 + endloop + endfacet + facet normal -0.935111 0.177837 -0.3065 + outer loop + vertex 0.84 2.02 2.47453 + vertex 0.83906 2.01612 2.47514 + vertex 0.84 2.02081 2.475 + endloop + endfacet + facet normal -0.979044 0.201788 -0.027451 + outer loop + vertex 0.84 2.02081 2.475 + vertex 0.838885 2.01568 2.47707 + vertex 0.84 2.02149 2.48 + endloop + endfacet + facet normal -0.979808 0.194743 -0.0452835 + outer loop + vertex 0.83906 2.01612 2.47514 + vertex 0.838885 2.01568 2.47707 + vertex 0.84 2.02081 2.475 + endloop + endfacet + facet normal -0.985389 0.141166 0.0952968 + outer loop + vertex 0.84 2.02149 2.48 + vertex 0.838885 2.01568 2.47707 + vertex 0.839131 2.01572 2.47957 + endloop + endfacet + facet normal -0.726884 -0.518779 -0.450009 + outer loop + vertex 0.845 0.998482 2.48 + vertex 0.843824 1.00112 2.47886 + vertex 0.845 1 2.47825 + endloop + endfacet + facet normal 0.594916 -0.0802185 -0.799775 + outer loop + vertex 0.845 0.998482 2.48 + vertex 0.844389 0.998383 2.47956 + vertex 0.843824 1.00112 2.47886 + endloop + endfacet + facet normal -0.806277 -0.0165509 -0.591307 + outer loop + vertex 0.845 1 2.47825 + vertex 0.843614 1.005 2.48 + vertex 0.845 1.005 2.47811 + endloop + endfacet + facet normal -0.237641 0.261541 -0.93548 + outer loop + vertex 0.843824 1.00112 2.47886 + vertex 0.843614 1.005 2.48 + vertex 0.845 1 2.47825 + endloop + endfacet + facet normal -0.978201 -0.206844 -0.0183726 + outer loop + vertex 0.84383 1.00094 2.48055 + vertex 0.843824 1.00112 2.47886 + vertex 0.844389 0.998383 2.47956 + endloop + endfacet + facet normal -0.980249 -0.197007 -0.0173432 + outer loop + vertex 0.84383 1.00094 2.48055 + vertex 0.842909 1.00549 2.48089 + vertex 0.843824 1.00112 2.47886 + endloop + endfacet + facet normal -0.732184 0.154903 -0.663259 + outer loop + vertex 0.842909 1.00549 2.48089 + vertex 0.843614 1.005 2.48 + vertex 0.843824 1.00112 2.47886 + endloop + endfacet + facet normal -0.963959 -0.207376 0.166669 + outer loop + vertex 0.84383 1.00094 2.48055 + vertex 0.843953 1.00245 2.48315 + vertex 0.842909 1.00549 2.48089 + endloop + endfacet + facet normal -0.822359 -0.277463 -0.496729 + outer loop + vertex 0.843614 1.005 2.48 + vertex 0.842909 1.00549 2.48089 + vertex 0.841927 1.01 2.48 + endloop + endfacet + facet normal -0.977461 -0.198998 0.0705017 + outer loop + vertex 0.841927 1.01 2.48 + vertex 0.842909 1.00549 2.48089 + vertex 0.84187 1.01068 2.48112 + endloop + endfacet + facet normal -0.964011 -0.212803 0.159366 + outer loop + vertex 0.843536 1.00546 2.48465 + vertex 0.842909 1.00549 2.48089 + vertex 0.843953 1.00245 2.48315 + endloop + endfacet + facet normal -0.961978 -0.222105 0.158956 + outer loop + vertex 0.843536 1.00546 2.48465 + vertex 0.842505 1.00993 2.48464 + vertex 0.842909 1.00549 2.48089 + endloop + endfacet + facet normal -0.970767 -0.200315 0.13223 + outer loop + vertex 0.842505 1.00993 2.48464 + vertex 0.84187 1.01068 2.48112 + vertex 0.842909 1.00549 2.48089 + endloop + endfacet + facet normal -0.950199 -0.219365 0.221362 + outer loop + vertex 0.843536 1.00546 2.48465 + vertex 0.843819 1.00728 2.48767 + vertex 0.842505 1.00993 2.48464 + endloop + endfacet + facet normal -0.999016 -0.0293681 -0.0332466 + outer loop + vertex 0.841927 1.01 2.48 + vertex 0.84187 1.01068 2.48112 + vertex 0.84178 1.015 2.48 + endloop + endfacet + facet normal -0.999752 -0.0171436 0.0141947 + outer loop + vertex 0.84178 1.015 2.48 + vertex 0.84187 1.01068 2.48112 + vertex 0.841851 1.015 2.485 + endloop + endfacet + facet normal -0.979619 -0.13658 0.147282 + outer loop + vertex 0.84187 1.01068 2.48112 + vertex 0.842505 1.00993 2.48464 + vertex 0.841851 1.015 2.485 + endloop + endfacet + facet normal -0.99152 -0.128937 0.0162231 + outer loop + vertex 0.841851 1.015 2.485 + vertex 0.842505 1.00993 2.48464 + vertex 0.841813 1.01558 2.48724 + endloop + endfacet + facet normal -0.947322 -0.222199 0.230671 + outer loop + vertex 0.842505 1.00993 2.48464 + vertex 0.843394 1.01123 2.48955 + vertex 0.841813 1.01558 2.48724 + endloop + endfacet + facet normal -0.950339 -0.211429 0.228371 + outer loop + vertex 0.843819 1.00728 2.48767 + vertex 0.843394 1.01123 2.48955 + vertex 0.842505 1.00993 2.48464 + endloop + endfacet + facet normal -0.98835 -0.150622 0.0218417 + outer loop + vertex 0.841851 1.015 2.485 + vertex 0.841813 1.01558 2.48724 + vertex 0.841089 1.02 2.485 + endloop + endfacet + facet normal -0.97782 -0.196594 -0.0722472 + outer loop + vertex 0.841089 1.02 2.485 + vertex 0.841813 1.01558 2.48724 + vertex 0.840952 1.01975 2.48754 + endloop + endfacet + facet normal -0.94639 -0.217567 0.238771 + outer loop + vertex 0.843004 1.01503 2.49147 + vertex 0.841813 1.01558 2.48724 + vertex 0.843394 1.01123 2.48955 + endloop + endfacet + facet normal -0.946556 -0.216662 0.238935 + outer loop + vertex 0.843004 1.01503 2.49147 + vertex 0.841902 1.01983 2.49146 + vertex 0.841813 1.01558 2.48724 + endloop + endfacet + facet normal -0.948657 -0.212251 0.234521 + outer loop + vertex 0.841902 1.01983 2.49146 + vertex 0.840952 1.01975 2.48754 + vertex 0.841813 1.01558 2.48724 + endloop + endfacet + facet normal -0.909486 -0.207931 0.359999 + outer loop + vertex 0.843004 1.01503 2.49147 + vertex 0.843664 1.01679 2.49415 + vertex 0.841902 1.01983 2.49146 + endloop + endfacet + facet normal -0.954718 -0.267278 0.130678 + outer loop + vertex 0.84 1.025 2.48727 + vertex 0.84 1.02389 2.485 + vertex 0.841089 1.02 2.485 + endloop + endfacet + facet normal -0.942878 -0.284248 0.173733 + outer loop + vertex 0.84 1.025 2.48727 + vertex 0.841089 1.02 2.485 + vertex 0.840503 1.025 2.49 + endloop + endfacet + facet normal -0.996582 -0.0574397 -0.059365 + outer loop + vertex 0.840503 1.025 2.49 + vertex 0.841089 1.02 2.485 + vertex 0.840952 1.01975 2.48754 + endloop + endfacet + facet normal -0.952878 -0.19173 0.235083 + outer loop + vertex 0.840952 1.01975 2.48754 + vertex 0.841902 1.01983 2.49146 + vertex 0.840503 1.025 2.49 + endloop + endfacet + facet normal -0.96657 -0.229438 0.114459 + outer loop + vertex 0.840503 1.025 2.49 + vertex 0.841902 1.01983 2.49146 + vertex 0.84095 1.024 2.49177 + endloop + endfacet + facet normal -0.898871 -0.159072 0.408323 + outer loop + vertex 0.843661 1.02006 2.49542 + vertex 0.841902 1.01983 2.49146 + vertex 0.843664 1.01679 2.49415 + endloop + endfacet + facet normal -0.877746 -0.256845 0.404466 + outer loop + vertex 0.843661 1.02006 2.49542 + vertex 0.842325 1.02474 2.49549 + vertex 0.841902 1.01983 2.49146 + endloop + endfacet + facet normal -0.896251 -0.233007 0.377414 + outer loop + vertex 0.842325 1.02474 2.49549 + vertex 0.84095 1.024 2.49177 + vertex 0.841902 1.01983 2.49146 + endloop + endfacet + facet normal -0.630823 -0.191894 0.751824 + outer loop + vertex 0.843661 1.02006 2.49542 + vertex 0.845476 1.02282 2.49764 + vertex 0.842325 1.02474 2.49549 + endloop + endfacet + facet normal 0.906019 0.23613 -0.351242 + outer loop + vertex 0.839175 1.02769 2.48838 + vertex 0.84 1.02693 2.49 + vertex 0.840503 1.025 2.49 + endloop + endfacet + facet normal -0.920417 -0.317346 0.228307 + outer loop + vertex 0.839175 1.02769 2.48838 + vertex 0.840503 1.025 2.49 + vertex 0.840068 1.02753 2.49176 + endloop + endfacet + facet normal -0.964599 -0.240816 0.107505 + outer loop + vertex 0.840068 1.02753 2.49176 + vertex 0.840503 1.025 2.49 + vertex 0.84095 1.024 2.49177 + endloop + endfacet + facet normal -0.89887 -0.224071 0.376597 + outer loop + vertex 0.84095 1.024 2.49177 + vertex 0.842325 1.02474 2.49549 + vertex 0.840068 1.02753 2.49176 + endloop + endfacet + facet normal -0.89835 -0.307031 0.314165 + outer loop + vertex 0.840068 1.02753 2.49176 + vertex 0.842325 1.02474 2.49549 + vertex 0.840926 1.02926 2.49591 + endloop + endfacet + facet normal -0.672277 -0.419749 0.609798 + outer loop + vertex 0.844078 1.02676 2.49881 + vertex 0.842325 1.02474 2.49549 + vertex 0.845476 1.02282 2.49764 + endloop + endfacet + facet normal -0.699752 -0.383885 0.602478 + outer loop + vertex 0.844078 1.02676 2.49881 + vertex 0.842578 1.03003 2.49916 + vertex 0.842325 1.02474 2.49549 + endloop + endfacet + facet normal -0.81996 -0.298945 0.488156 + outer loop + vertex 0.842578 1.03003 2.49916 + vertex 0.840926 1.02926 2.49591 + vertex 0.842325 1.02474 2.49549 + endloop + endfacet + facet normal -0.385949 -0.269355 0.882322 + outer loop + vertex 0.844078 1.02676 2.49881 + vertex 0.844561 1.03005 2.50003 + vertex 0.842578 1.03003 2.49916 + endloop + endfacet + facet normal -0.942413 -0.235101 0.237877 + outer loop + vertex 0.838525 1.03115 2.48923 + vertex 0.839175 1.02769 2.48838 + vertex 0.840068 1.02753 2.49176 + endloop + endfacet + facet normal -0.941825 -0.229484 0.245567 + outer loop + vertex 0.839421 1.03264 2.49406 + vertex 0.838525 1.03115 2.48923 + vertex 0.840068 1.02753 2.49176 + endloop + endfacet + facet normal -0.922407 -0.249237 0.295036 + outer loop + vertex 0.840068 1.02753 2.49176 + vertex 0.840926 1.02926 2.49591 + vertex 0.839421 1.03264 2.49406 + endloop + endfacet + facet normal -0.916525 -0.228346 0.328391 + outer loop + vertex 0.839421 1.03264 2.49406 + vertex 0.840926 1.02926 2.49591 + vertex 0.84086 1.0326 2.49805 + endloop + endfacet + facet normal -0.807747 -0.329091 0.489126 + outer loop + vertex 0.840926 1.02926 2.49591 + vertex 0.842578 1.03003 2.49916 + vertex 0.84086 1.0326 2.49805 + endloop + endfacet + facet normal -0.784864 -0.288153 0.548596 + outer loop + vertex 0.84086 1.0326 2.49805 + vertex 0.842578 1.03003 2.49916 + vertex 0.842044 1.03502 2.50101 + endloop + endfacet + facet normal -0.220063 -0.360791 0.906312 + outer loop + vertex 0.842578 1.03003 2.49916 + vertex 0.844109 1.03408 2.50114 + vertex 0.842044 1.03502 2.50101 + endloop + endfacet + facet normal -0.384006 -0.284963 0.878257 + outer loop + vertex 0.844561 1.03005 2.50003 + vertex 0.844109 1.03408 2.50114 + vertex 0.842578 1.03003 2.49916 + endloop + endfacet + facet normal -0.939615 -0.236539 0.247332 + outer loop + vertex 0.838525 1.03115 2.48923 + vertex 0.839421 1.03264 2.49406 + vertex 0.837979 1.03506 2.49089 + endloop + endfacet + facet normal -0.939794 -0.232302 0.250647 + outer loop + vertex 0.83838 1.03682 2.49402 + vertex 0.837979 1.03506 2.49089 + vertex 0.839421 1.03264 2.49406 + endloop + endfacet + facet normal -0.916173 -0.225774 0.33114 + outer loop + vertex 0.83838 1.03682 2.49402 + vertex 0.839421 1.03264 2.49406 + vertex 0.839911 1.03718 2.49851 + endloop + endfacet + facet normal -0.917599 -0.223352 0.328826 + outer loop + vertex 0.839911 1.03718 2.49851 + vertex 0.839421 1.03264 2.49406 + vertex 0.84086 1.0326 2.49805 + endloop + endfacet + facet normal -0.828542 -0.22351 0.513382 + outer loop + vertex 0.84086 1.0326 2.49805 + vertex 0.842044 1.03502 2.50101 + vertex 0.839911 1.03718 2.49851 + endloop + endfacet + facet normal -0.832074 -0.245376 0.497437 + outer loop + vertex 0.839911 1.03718 2.49851 + vertex 0.842044 1.03502 2.50101 + vertex 0.841827 1.03921 2.50272 + endloop + endfacet + facet normal -0.299777 -0.372588 0.878243 + outer loop + vertex 0.842044 1.03502 2.50101 + vertex 0.843551 1.03844 2.50298 + vertex 0.841827 1.03921 2.50272 + endloop + endfacet + facet normal -0.237879 -0.402972 0.883757 + outer loop + vertex 0.844109 1.03408 2.50114 + vertex 0.843551 1.03844 2.50298 + vertex 0.842044 1.03502 2.50101 + endloop + endfacet + facet normal -0.910992 -0.246001 0.331024 + outer loop + vertex 0.83838 1.03682 2.49402 + vertex 0.839911 1.03718 2.49851 + vertex 0.838163 1.03986 2.49569 + endloop + endfacet + facet normal -0.908719 -0.218859 0.355431 + outer loop + vertex 0.838993 1.04147 2.4988 + vertex 0.838163 1.03986 2.49569 + vertex 0.839911 1.03718 2.49851 + endloop + endfacet + facet normal -0.870064 -0.216528 0.442836 + outer loop + vertex 0.838993 1.04147 2.4988 + vertex 0.839911 1.03718 2.49851 + vertex 0.840456 1.04114 2.50151 + endloop + endfacet + facet normal -0.820509 -0.269797 0.50396 + outer loop + vertex 0.840456 1.04114 2.50151 + vertex 0.839911 1.03718 2.49851 + vertex 0.841827 1.03921 2.50272 + endloop + endfacet + facet normal -0.336921 -0.478419 0.810925 + outer loop + vertex 0.843131 1.04123 2.50445 + vertex 0.841827 1.03921 2.50272 + vertex 0.843551 1.03844 2.50298 + endloop + endfacet + facet normal -0.705374 -0.139874 0.694898 + outer loop + vertex 0.843131 1.04123 2.50445 + vertex 0.842138 1.04323 2.50384 + vertex 0.841827 1.03921 2.50272 + endloop + endfacet + facet normal -0.747609 -0.124672 0.652332 + outer loop + vertex 0.842138 1.04323 2.50384 + vertex 0.840456 1.04114 2.50151 + vertex 0.841827 1.03921 2.50272 + endloop + endfacet + facet normal -0.60971 -0.0636011 0.790069 + outer loop + vertex 0.843131 1.04123 2.50445 + vertex 0.843434 1.043 2.50482 + vertex 0.842138 1.04323 2.50384 + endloop + endfacet + facet normal -0.799096 -0.520286 0.301243 + outer loop + vertex 0.845 1.04994 2.49 + vertex 0.844961 1.05 2.49 + vertex 0.845541 1.04865 2.48921 + endloop + endfacet + facet normal -0.879749 -0.120891 0.459811 + outer loop + vertex 0.838993 1.04147 2.4988 + vertex 0.840456 1.04114 2.50151 + vertex 0.839796 1.04536 2.50136 + endloop + endfacet + facet normal -0.76359 -0.0963699 0.638469 + outer loop + vertex 0.839796 1.04536 2.50136 + vertex 0.840456 1.04114 2.50151 + vertex 0.842138 1.04323 2.50384 + endloop + endfacet + facet normal -0.64053 0.167341 0.749478 + outer loop + vertex 0.839796 1.04536 2.50136 + vertex 0.842138 1.04323 2.50384 + vertex 0.842504 1.04834 2.50301 + endloop + endfacet + facet normal -0.174062 -0.350934 0.92008 + outer loop + vertex 0.839796 1.04536 2.50136 + vertex 0.842504 1.04834 2.50301 + vertex 0.840148 1.05026 2.5033 + endloop + endfacet + facet normal -0.323333 0.174004 0.93015 + outer loop + vertex 0.843602 1.04501 2.50402 + vertex 0.842504 1.04834 2.50301 + vertex 0.842138 1.04323 2.50384 + endloop + endfacet + facet normal -0.525374 0.355087 0.773237 + outer loop + vertex 0.843602 1.04501 2.50402 + vertex 0.842138 1.04323 2.50384 + vertex 0.843434 1.043 2.50482 + endloop + endfacet + facet normal -0.789345 0.0217017 -0.613566 + outer loop + vertex 0.845 1.05142 2.49 + vertex 0.845541 1.04865 2.48921 + vertex 0.844961 1.05 2.49 + endloop + endfacet + facet normal -0.0423996 -0.460348 0.886726 + outer loop + vertex 0.840185 1.05344 2.50495 + vertex 0.838825 1.0521 2.50419 + vertex 0.840148 1.05026 2.5033 + endloop + endfacet + facet normal 0.670072 -0.348494 0.655405 + outer loop + vertex 0.840185 1.05344 2.50495 + vertex 0.840148 1.05026 2.5033 + vertex 0.842188 1.05435 2.50339 + endloop + endfacet + facet normal 0.0732102 -0.0584794 0.995601 + outer loop + vertex 0.842188 1.05435 2.50339 + vertex 0.840148 1.05026 2.5033 + vertex 0.842504 1.04834 2.50301 + endloop + endfacet + facet normal 0.025108 -0.512636 0.858239 + outer loop + vertex 0.840185 1.05344 2.50495 + vertex 0.839156 1.05478 2.50578 + vertex 0.838825 1.0521 2.50419 + endloop + endfacet + facet normal -0.870808 -0.240964 0.42852 + outer loop + vertex 0.845 1.05837 2.495 + vertex 0.844549 1.06 2.495 + vertex 0.844745 1.05741 2.49394 + endloop + endfacet + facet normal 0.821212 -0.0585485 0.567611 + outer loop + vertex 0.842188 1.05435 2.50339 + vertex 0.842834 1.0603 2.50307 + vertex 0.84078 1.05804 2.5058 + endloop + endfacet + facet normal 0.660125 -0.219017 0.718517 + outer loop + vertex 0.840185 1.05344 2.50495 + vertex 0.842188 1.05435 2.50339 + vertex 0.84078 1.05804 2.5058 + endloop + endfacet + facet normal 0.424554 -0.218344 0.87868 + outer loop + vertex 0.84078 1.05804 2.5058 + vertex 0.839156 1.05478 2.50578 + vertex 0.840185 1.05344 2.50495 + endloop + endfacet + facet normal 0.527245 -0.268926 0.806034 + outer loop + vertex 0.838786 1.05835 2.50721 + vertex 0.839156 1.05478 2.50578 + vertex 0.84078 1.05804 2.5058 + endloop + endfacet + facet normal 0.0270203 0.000497322 0.999635 + outer loop + vertex 0.844549 1.06 2.495 + vertex 0.844457 1.065 2.495 + vertex 0.844362 1.06056 2.495 + endloop + endfacet + facet normal -0.809222 -0.273613 0.5199 + outer loop + vertex 0.844745 1.05741 2.49394 + vertex 0.844549 1.06 2.495 + vertex 0.844362 1.06056 2.495 + endloop + endfacet + facet normal 0.915253 0.0431842 0.400558 + outer loop + vertex 0.842834 1.0603 2.50307 + vertex 0.843188 1.06446 2.50181 + vertex 0.841959 1.06396 2.50467 + endloop + endfacet + facet normal 0.819722 -0.0540601 0.570204 + outer loop + vertex 0.84078 1.05804 2.5058 + vertex 0.842834 1.0603 2.50307 + vertex 0.841959 1.06396 2.50467 + endloop + endfacet + facet normal 0.637691 -0.289669 0.713752 + outer loop + vertex 0.838786 1.05835 2.50721 + vertex 0.840082 1.06331 2.50807 + vertex 0.838425 1.06206 2.50904 + endloop + endfacet + facet normal 0.525323 -0.276062 0.804876 + outer loop + vertex 0.838786 1.05835 2.50721 + vertex 0.84078 1.05804 2.5058 + vertex 0.840082 1.06331 2.50807 + endloop + endfacet + facet normal 0.878922 -0.0851397 0.469305 + outer loop + vertex 0.84078 1.05804 2.5058 + vertex 0.841959 1.06396 2.50467 + vertex 0.840082 1.06331 2.50807 + endloop + endfacet + facet normal 0.651251 -0.332187 0.682293 + outer loop + vertex 0.840082 1.06331 2.50807 + vertex 0.838936 1.0653 2.51013 + vertex 0.838425 1.06206 2.50904 + endloop + endfacet + facet normal 0.899442 -0.0187227 0.436638 + outer loop + vertex 0.843926 1.06434 2.49607 + vertex 0.844362 1.06056 2.495 + vertex 0.844457 1.065 2.495 + endloop + endfacet + facet normal 0.856251 0.120944 0.502202 + outer loop + vertex 0.843926 1.06434 2.49607 + vertex 0.844457 1.065 2.495 + vertex 0.843167 1.06897 2.49624 + endloop + endfacet + facet normal 0.667607 -0.016291 0.744336 + outer loop + vertex 0.843167 1.06897 2.49624 + vertex 0.844457 1.065 2.495 + vertex 0.844579 1.07 2.495 + endloop + endfacet + facet normal 0.9863 0.159979 0.0402314 + outer loop + vertex 0.843642 1.0654 2.49882 + vertex 0.843926 1.06434 2.49607 + vertex 0.843167 1.06897 2.49624 + endloop + endfacet + facet normal 0.968219 0.217505 0.123466 + outer loop + vertex 0.842599 1.06881 2.50098 + vertex 0.843642 1.0654 2.49882 + vertex 0.843167 1.06897 2.49624 + endloop + endfacet + facet normal 0.965366 0.168765 0.198962 + outer loop + vertex 0.843188 1.06446 2.50181 + vertex 0.843642 1.0654 2.49882 + vertex 0.842599 1.06881 2.50098 + endloop + endfacet + facet normal 0.887221 0.199591 0.415936 + outer loop + vertex 0.843188 1.06446 2.50181 + vertex 0.842599 1.06881 2.50098 + vertex 0.841959 1.06396 2.50467 + endloop + endfacet + facet normal 0.961533 0.0743718 0.264428 + outer loop + vertex 0.841959 1.06396 2.50467 + vertex 0.842599 1.06881 2.50098 + vertex 0.841319 1.06869 2.50567 + endloop + endfacet + facet normal 0.873895 0.01565 0.485862 + outer loop + vertex 0.841959 1.06396 2.50467 + vertex 0.841319 1.06869 2.50567 + vertex 0.840082 1.06331 2.50807 + endloop + endfacet + facet normal 0.93331 -0.0565537 0.354591 + outer loop + vertex 0.841319 1.06869 2.50567 + vertex 0.839972 1.06852 2.50919 + vertex 0.840082 1.06331 2.50807 + endloop + endfacet + facet normal 0.824203 -0.102364 0.556966 + outer loop + vertex 0.839972 1.06852 2.50919 + vertex 0.838936 1.0653 2.51013 + vertex 0.840082 1.06331 2.50807 + endloop + endfacet + facet normal 0.771259 -0.0631046 0.633385 + outer loop + vertex 0.838651 1.06858 2.5108 + vertex 0.838936 1.0653 2.51013 + vertex 0.839972 1.06852 2.50919 + endloop + endfacet + facet normal 0.488898 0.312597 0.814408 + outer loop + vertex 0.844579 1.07 2.495 + vertex 0.841382 1.075 2.495 + vertex 0.843167 1.06897 2.49624 + endloop + endfacet + facet normal 0.944678 0.231657 -0.232204 + outer loop + vertex 0.841382 1.075 2.495 + vertex 0.842139 1.07416 2.49724 + vertex 0.843167 1.06897 2.49624 + endloop + endfacet + facet normal 0.977768 0.169829 0.122993 + outer loop + vertex 0.843167 1.06897 2.49624 + vertex 0.842139 1.07416 2.49724 + vertex 0.842599 1.06881 2.50098 + endloop + endfacet + facet normal 0.979147 0.165922 0.11722 + outer loop + vertex 0.842139 1.07416 2.49724 + vertex 0.841612 1.07394 2.50196 + vertex 0.842599 1.06881 2.50098 + endloop + endfacet + facet normal 0.955227 0.133129 0.264231 + outer loop + vertex 0.842599 1.06881 2.50098 + vertex 0.841612 1.07394 2.50196 + vertex 0.841319 1.06869 2.50567 + endloop + endfacet + facet normal 0.971892 0.0970705 0.214484 + outer loop + vertex 0.841612 1.07394 2.50196 + vertex 0.840692 1.07321 2.50646 + vertex 0.841319 1.06869 2.50567 + endloop + endfacet + facet normal 0.930864 0.0659543 0.359363 + outer loop + vertex 0.841319 1.06869 2.50567 + vertex 0.840692 1.07321 2.50646 + vertex 0.839972 1.06852 2.50919 + endloop + endfacet + facet normal 0.923971 0.0760066 0.374833 + outer loop + vertex 0.840692 1.07321 2.50646 + vertex 0.83947 1.07234 2.50965 + vertex 0.839972 1.06852 2.50919 + endloop + endfacet + facet normal 0.774167 0.0249858 0.632488 + outer loop + vertex 0.83947 1.07234 2.50965 + vertex 0.838651 1.06858 2.5108 + vertex 0.839972 1.06852 2.50919 + endloop + endfacet + facet normal 0.725204 0.0522059 0.686552 + outer loop + vertex 0.838352 1.07141 2.5109 + vertex 0.838651 1.06858 2.5108 + vertex 0.83947 1.07234 2.50965 + endloop + endfacet + facet normal 0.555466 0.53134 0.639637 + outer loop + vertex 0.845 1.075 2.49409 + vertex 0.844257 1.08012 2.49048 + vertex 0.842477 1.07775 2.494 + endloop + endfacet + facet normal 0.236235 0.248319 0.939431 + outer loop + vertex 0.841382 1.075 2.495 + vertex 0.845 1.075 2.49409 + vertex 0.842477 1.07775 2.494 + endloop + endfacet + facet normal 0.771798 -0.46531 -0.433375 + outer loop + vertex 0.841382 1.075 2.495 + vertex 0.842477 1.07775 2.494 + vertex 0.842139 1.07416 2.49724 + endloop + endfacet + facet normal 0.958491 0.136357 0.250403 + outer loop + vertex 0.842477 1.07775 2.494 + vertex 0.841063 1.07981 2.49829 + vertex 0.842139 1.07416 2.49724 + endloop + endfacet + facet normal 0.979309 0.164985 0.117193 + outer loop + vertex 0.842139 1.07416 2.49724 + vertex 0.841063 1.07981 2.49829 + vertex 0.841612 1.07394 2.50196 + endloop + endfacet + facet normal 0.978435 0.167342 0.121088 + outer loop + vertex 0.841063 1.07981 2.49829 + vertex 0.840846 1.07763 2.50305 + vertex 0.841612 1.07394 2.50196 + endloop + endfacet + facet normal 0.966113 0.135724 0.219557 + outer loop + vertex 0.841612 1.07394 2.50196 + vertex 0.840846 1.07763 2.50305 + vertex 0.840692 1.07321 2.50646 + endloop + endfacet + facet normal 0.949262 0.170712 0.264119 + outer loop + vertex 0.840846 1.07763 2.50305 + vertex 0.839802 1.07751 2.50688 + vertex 0.840692 1.07321 2.50646 + endloop + endfacet + facet normal 0.680866 0.349241 0.64378 + outer loop + vertex 0.838635 1.0743 2.50985 + vertex 0.839802 1.07751 2.50688 + vertex 0.837799 1.07749 2.50901 + endloop + endfacet + facet normal 0.765437 0.265113 0.586363 + outer loop + vertex 0.838635 1.0743 2.50985 + vertex 0.83947 1.07234 2.50965 + vertex 0.839802 1.07751 2.50688 + endloop + endfacet + facet normal 0.908843 0.150153 0.389177 + outer loop + vertex 0.83947 1.07234 2.50965 + vertex 0.840692 1.07321 2.50646 + vertex 0.839802 1.07751 2.50688 + endloop + endfacet + facet normal 0.651219 0.201615 0.731618 + outer loop + vertex 0.83947 1.07234 2.50965 + vertex 0.838635 1.0743 2.50985 + vertex 0.838352 1.07141 2.5109 + endloop + endfacet + facet normal 0.849985 0.0138743 0.526624 + outer loop + vertex 0.844257 1.08012 2.49048 + vertex 0.844358 1.08543 2.49018 + vertex 0.841916 1.08311 2.49418 + endloop + endfacet + facet normal 0.868689 0.0741562 0.489776 + outer loop + vertex 0.842477 1.07775 2.494 + vertex 0.844257 1.08012 2.49048 + vertex 0.841916 1.08311 2.49418 + endloop + endfacet + facet normal 0.821467 0.550387 0.149217 + outer loop + vertex 0.84 1.08439 2.5 + vertex 0.841916 1.08311 2.49418 + vertex 0.84 1.085 2.49775 + endloop + endfacet + facet normal 0.950881 0.112923 0.288224 + outer loop + vertex 0.84 1.08439 2.5 + vertex 0.841063 1.07981 2.49829 + vertex 0.841916 1.08311 2.49418 + endloop + endfacet + facet normal 0.957987 0.0909278 0.272017 + outer loop + vertex 0.841063 1.07981 2.49829 + vertex 0.842477 1.07775 2.494 + vertex 0.841916 1.08311 2.49418 + endloop + endfacet + facet normal -0.94105 -0.28581 0.180936 + outer loop + vertex 0.839919 1.08413 2.49917 + vertex 0.841063 1.07981 2.49829 + vertex 0.84 1.08439 2.5 + endloop + endfacet + facet normal 0.958886 0.270903 -0.0845529 + outer loop + vertex 0.839919 1.08413 2.49917 + vertex 0.840459 1.08317 2.50222 + vertex 0.841063 1.07981 2.49829 + endloop + endfacet + facet normal 0.993214 0.0818223 0.0826461 + outer loop + vertex 0.840459 1.08317 2.50222 + vertex 0.840846 1.07763 2.50305 + vertex 0.841063 1.07981 2.49829 + endloop + endfacet + facet normal 0.958429 0.106771 0.2646 + outer loop + vertex 0.840846 1.07763 2.50305 + vertex 0.840459 1.08317 2.50222 + vertex 0.839802 1.07751 2.50688 + endloop + endfacet + facet normal 0.992554 -0.0156017 0.120798 + outer loop + vertex 0.840459 1.08317 2.50222 + vertex 0.839928 1.08408 2.5067 + vertex 0.839802 1.07751 2.50688 + endloop + endfacet + facet normal 0.72765 0.00504102 0.68593 + outer loop + vertex 0.839928 1.08408 2.5067 + vertex 0.837799 1.07749 2.50901 + vertex 0.839802 1.07751 2.50688 + endloop + endfacet + facet normal 0.8811 -0.124999 0.456112 + outer loop + vertex 0.837919 1.08262 2.51018 + vertex 0.837799 1.07749 2.50901 + vertex 0.839928 1.08408 2.5067 + endloop + endfacet + facet normal 0.996462 -0.0177869 0.082141 + outer loop + vertex 0.844358 1.08543 2.49018 + vertex 0.844398 1.09055 2.4908 + vertex 0.844042 1.09 2.495 + endloop + endfacet + facet normal 0.880688 -0.313814 0.354838 + outer loop + vertex 0.841916 1.08311 2.49418 + vertex 0.844358 1.08543 2.49018 + vertex 0.844042 1.09 2.495 + endloop + endfacet + facet normal 0.76326 -0.303222 0.570518 + outer loop + vertex 0.844042 1.09 2.495 + vertex 0.84 1.085 2.49775 + vertex 0.841916 1.08311 2.49418 + endloop + endfacet + facet normal 0.414654 0.157733 0.896205 + outer loop + vertex 0.84 1.09 2.49687 + vertex 0.84 1.085 2.49775 + vertex 0.844042 1.09 2.495 + endloop + endfacet + facet normal 0.986004 0.0419845 -0.161346 + outer loop + vertex 0.84 1.09 2.50119 + vertex 0.840459 1.08317 2.50222 + vertex 0.839919 1.08413 2.49917 + endloop + endfacet + facet normal 0.833064 -0.0271811 -0.552509 + outer loop + vertex 0.842527 1.09 2.505 + vertex 0.840459 1.08317 2.50222 + vertex 0.84 1.09 2.50119 + endloop + endfacet + facet normal 0.918578 -0.35166 0.180414 + outer loop + vertex 0.840459 1.08317 2.50222 + vertex 0.842527 1.09 2.505 + vertex 0.839928 1.08408 2.5067 + endloop + endfacet + facet normal 0.758389 -0.15083 0.63411 + outer loop + vertex 0.842527 1.09 2.505 + vertex 0.841478 1.09023 2.50631 + vertex 0.839928 1.08408 2.5067 + endloop + endfacet + facet normal 0.880521 -0.342019 0.328184 + outer loop + vertex 0.837919 1.08262 2.51018 + vertex 0.84025 1.08851 2.51007 + vertex 0.838161 1.0857 2.51274 + endloop + endfacet + facet normal 0.869827 -0.337173 0.36016 + outer loop + vertex 0.837919 1.08262 2.51018 + vertex 0.839928 1.08408 2.5067 + vertex 0.84025 1.08851 2.51007 + endloop + endfacet + facet normal 0.951709 -0.226711 0.207007 + outer loop + vertex 0.839928 1.08408 2.5067 + vertex 0.841478 1.09023 2.50631 + vertex 0.84025 1.08851 2.51007 + endloop + endfacet + facet normal 0.875878 -0.412391 0.250543 + outer loop + vertex 0.839513 1.08993 2.51498 + vertex 0.838161 1.0857 2.51274 + vertex 0.84025 1.08851 2.51007 + endloop + endfacet + facet normal 0.64028 -0.508938 0.575346 + outer loop + vertex 0.836913 1.08655 2.51488 + vertex 0.838161 1.0857 2.51274 + vertex 0.839513 1.08993 2.51498 + endloop + endfacet + facet normal 0.634018 -0.504425 0.586155 + outer loop + vertex 0.839513 1.08993 2.51498 + vertex 0.837161 1.09004 2.51762 + vertex 0.836913 1.08655 2.51488 + endloop + endfacet + facet normal 0.15748 -0.624031 0.765366 + outer loop + vertex 0.844398 1.09055 2.4908 + vertex 0.845 1.095 2.4943 + vertex 0.841598 1.095 2.495 + endloop + endfacet + facet normal 0.890494 0.435279 0.132486 + outer loop + vertex 0.844042 1.09 2.495 + vertex 0.844398 1.09055 2.4908 + vertex 0.841598 1.095 2.495 + endloop + endfacet + facet normal 0.761931 -0.133192 0.633815 + outer loop + vertex 0.842527 1.09 2.505 + vertex 0.843401 1.095 2.505 + vertex 0.841478 1.09023 2.50631 + endloop + endfacet + facet normal 0.928898 -0.369915 0.0176513 + outer loop + vertex 0.843401 1.095 2.505 + vertex 0.843306 1.095 2.51 + vertex 0.841478 1.09023 2.50631 + endloop + endfacet + facet normal 0.900574 -0.422984 0.100259 + outer loop + vertex 0.841478 1.09023 2.50631 + vertex 0.843306 1.095 2.51 + vertex 0.84025 1.08851 2.51007 + endloop + endfacet + facet normal 0.848303 -0.395796 0.351751 + outer loop + vertex 0.843306 1.095 2.51 + vertex 0.842133 1.09437 2.51212 + vertex 0.84025 1.08851 2.51007 + endloop + endfacet + facet normal 0.895864 -0.372617 0.242043 + outer loop + vertex 0.84025 1.08851 2.51007 + vertex 0.842133 1.09437 2.51212 + vertex 0.839513 1.08993 2.51498 + endloop + endfacet + facet normal 0.864591 -0.502334 0.0119154 + outer loop + vertex 0.842133 1.09437 2.51212 + vertex 0.841741 1.09379 2.51599 + vertex 0.839513 1.08993 2.51498 + endloop + endfacet + facet normal 0.300023 -0.675356 0.673706 + outer loop + vertex 0.837161 1.09004 2.51762 + vertex 0.840104 1.09385 2.52013 + vertex 0.837464 1.09284 2.52029 + endloop + endfacet + facet normal 0.509318 -0.711901 0.483521 + outer loop + vertex 0.837161 1.09004 2.51762 + vertex 0.839513 1.08993 2.51498 + vertex 0.840104 1.09385 2.52013 + endloop + endfacet + facet normal 0.782829 -0.535111 0.317546 + outer loop + vertex 0.839513 1.08993 2.51498 + vertex 0.841741 1.09379 2.51599 + vertex 0.840104 1.09385 2.52013 + endloop + endfacet + facet normal 0.299519 -0.673746 0.67554 + outer loop + vertex 0.840104 1.09385 2.52013 + vertex 0.837991 1.09443 2.52164 + vertex 0.837464 1.09284 2.52029 + endloop + endfacet + facet normal 0.898043 -0.401687 -0.179349 + outer loop + vertex 0.845 1.1 2.51387 + vertex 0.843816 1.09701 2.51465 + vertex 0.842133 1.09437 2.51212 + endloop + endfacet + facet normal 0.829723 -0.271005 -0.487971 + outer loop + vertex 0.845 1.1 2.51387 + vertex 0.842133 1.09437 2.51212 + vertex 0.842724 1.1 2.51 + endloop + endfacet + facet normal 0.857912 0.0998576 0.504 + outer loop + vertex 0.842724 1.1 2.51 + vertex 0.842133 1.09437 2.51212 + vertex 0.843306 1.095 2.51 + endloop + endfacet + facet normal 0.83219 -0.553101 -0.0392275 + outer loop + vertex 0.843816 1.09701 2.51465 + vertex 0.843457 1.09621 2.51821 + vertex 0.841741 1.09379 2.51599 + endloop + endfacet + facet normal 0.841072 -0.54091 0.0037188 + outer loop + vertex 0.842133 1.09437 2.51212 + vertex 0.843816 1.09701 2.51465 + vertex 0.841741 1.09379 2.51599 + endloop + endfacet + facet normal 0.605682 -0.79136 0.0830593 + outer loop + vertex 0.843457 1.09621 2.51821 + vertex 0.843378 1.09651 2.52166 + vertex 0.840104 1.09385 2.52013 + endloop + endfacet + facet normal 0.652815 -0.708327 0.268525 + outer loop + vertex 0.841741 1.09379 2.51599 + vertex 0.843457 1.09621 2.51821 + vertex 0.840104 1.09385 2.52013 + endloop + endfacet + facet normal 0.481252 -0.349269 0.803995 + outer loop + vertex 0.840104 1.09385 2.52013 + vertex 0.837708 1.09738 2.52309 + vertex 0.837991 1.09443 2.52164 + endloop + endfacet + facet normal -0.190066 -0.703962 0.684334 + outer loop + vertex 0.840104 1.09385 2.52013 + vertex 0.841693 1.09716 2.52398 + vertex 0.837708 1.09738 2.52309 + endloop + endfacet + facet normal 0.392411 -0.770946 0.501653 + outer loop + vertex 0.840104 1.09385 2.52013 + vertex 0.843378 1.09651 2.52166 + vertex 0.841693 1.09716 2.52398 + endloop + endfacet + facet normal -0.174239 -0.786398 0.592638 + outer loop + vertex 0.840257 1.09857 2.52542 + vertex 0.837708 1.09738 2.52309 + vertex 0.841693 1.09716 2.52398 + endloop + endfacet + facet normal 0.0653831 -0.681847 0.728567 + outer loop + vertex 0.841693 1.09716 2.52398 + vertex 0.842339 1.10014 2.52671 + vertex 0.840257 1.09857 2.52542 + endloop + endfacet + facet normal -0.431631 -0.51932 0.737565 + outer loop + vertex 0.837708 1.09738 2.52309 + vertex 0.840257 1.09857 2.52542 + vertex 0.838333 1.10082 2.52588 + endloop + endfacet + facet normal -0.334695 -0.689807 0.641986 + outer loop + vertex 0.84362 1.10269 2.52941 + vertex 0.841026 1.10501 2.53054 + vertex 0.838566 1.10398 2.52815 + endloop + endfacet + facet normal -0.33325 -0.601508 0.726039 + outer loop + vertex 0.842339 1.10014 2.52671 + vertex 0.84362 1.10269 2.52941 + vertex 0.838566 1.10398 2.52815 + endloop + endfacet + facet normal -0.256815 -0.551757 0.79348 + outer loop + vertex 0.842339 1.10014 2.52671 + vertex 0.838566 1.10398 2.52815 + vertex 0.838333 1.10082 2.52588 + endloop + endfacet + facet normal -0.24859 -0.393068 0.885269 + outer loop + vertex 0.842339 1.10014 2.52671 + vertex 0.838333 1.10082 2.52588 + vertex 0.840257 1.09857 2.52542 + endloop + endfacet + facet normal -0.287575 -0.66171 0.692417 + outer loop + vertex 0.84362 1.10269 2.52941 + vertex 0.844228 1.10485 2.53172 + vertex 0.841026 1.10501 2.53054 + endloop + endfacet + facet normal -0.452875 -0.548883 0.702589 + outer loop + vertex 0.838566 1.10398 2.52815 + vertex 0.841026 1.10501 2.53054 + vertex 0.837932 1.10693 2.53005 + endloop + endfacet + facet normal -0.440227 -0.52122 0.731116 + outer loop + vertex 0.841026 1.10501 2.53054 + vertex 0.839913 1.10809 2.53207 + vertex 0.837932 1.10693 2.53005 + endloop + endfacet + facet normal -0.31902 -0.510792 0.798322 + outer loop + vertex 0.841026 1.10501 2.53054 + vertex 0.844228 1.10485 2.53172 + vertex 0.839913 1.10809 2.53207 + endloop + endfacet + facet normal -0.372455 -0.574365 0.728959 + outer loop + vertex 0.844228 1.10485 2.53172 + vertex 0.84457 1.10763 2.53409 + vertex 0.839913 1.10809 2.53207 + endloop + endfacet + facet normal -0.449714 -0.576849 0.681911 + outer loop + vertex 0.844129 1.11039 2.53618 + vertex 0.841441 1.11267 2.53633 + vertex 0.839647 1.11183 2.53444 + endloop + endfacet + facet normal -0.449659 -0.583364 0.676383 + outer loop + vertex 0.844129 1.11039 2.53618 + vertex 0.839647 1.11183 2.53444 + vertex 0.84457 1.10763 2.53409 + endloop + endfacet + facet normal -0.383182 -0.513212 0.767975 + outer loop + vertex 0.84457 1.10763 2.53409 + vertex 0.839647 1.11183 2.53444 + vertex 0.839913 1.10809 2.53207 + endloop + endfacet + facet normal -0.403327 -0.526547 0.748382 + outer loop + vertex 0.844129 1.11039 2.53618 + vertex 0.843502 1.11367 2.53815 + vertex 0.841441 1.11267 2.53633 + endloop + endfacet + facet normal -0.507387 -0.499401 0.702251 + outer loop + vertex 0.839647 1.11183 2.53444 + vertex 0.841441 1.11267 2.53633 + vertex 0.838651 1.1153 2.53618 + endloop + endfacet + facet normal -0.504209 -0.510262 0.696711 + outer loop + vertex 0.842607 1.11678 2.53993 + vertex 0.840742 1.11941 2.54051 + vertex 0.838327 1.11864 2.5382 + endloop + endfacet + facet normal -0.506647 -0.534948 0.676121 + outer loop + vertex 0.843502 1.11367 2.53815 + vertex 0.842607 1.11678 2.53993 + vertex 0.838327 1.11864 2.5382 + endloop + endfacet + facet normal -0.463074 -0.49027 0.738375 + outer loop + vertex 0.843502 1.11367 2.53815 + vertex 0.838327 1.11864 2.5382 + vertex 0.838651 1.1153 2.53618 + endloop + endfacet + facet normal -0.460054 -0.445503 0.768035 + outer loop + vertex 0.843502 1.11367 2.53815 + vertex 0.838651 1.1153 2.53618 + vertex 0.841441 1.11267 2.53633 + endloop + endfacet + facet normal -0.45052 -0.483905 0.750245 + outer loop + vertex 0.842607 1.11678 2.53993 + vertex 0.844716 1.11797 2.54197 + vertex 0.840742 1.11941 2.54051 + endloop + endfacet + facet normal -0.520458 -0.482471 0.704518 + outer loop + vertex 0.838327 1.11864 2.5382 + vertex 0.840742 1.11941 2.54051 + vertex 0.837903 1.12179 2.54004 + endloop + endfacet + facet normal -0.506809 -0.461589 0.728066 + outer loop + vertex 0.840742 1.11941 2.54051 + vertex 0.840371 1.12215 2.54199 + vertex 0.837903 1.12179 2.54004 + endloop + endfacet + facet normal -0.449146 -0.470735 0.759392 + outer loop + vertex 0.840742 1.11941 2.54051 + vertex 0.844716 1.11797 2.54197 + vertex 0.840371 1.12215 2.54199 + endloop + endfacet + facet normal -0.474333 -0.49675 0.726807 + outer loop + vertex 0.844716 1.11797 2.54197 + vertex 0.844512 1.12176 2.54443 + vertex 0.840371 1.12215 2.54199 + endloop + endfacet + facet normal -0.536317 -0.498785 0.680865 + outer loop + vertex 0.843611 1.12519 2.54626 + vertex 0.841041 1.12785 2.54618 + vertex 0.838576 1.12707 2.54367 + endloop + endfacet + facet normal -0.536303 -0.503137 0.677667 + outer loop + vertex 0.843611 1.12519 2.54626 + vertex 0.838576 1.12707 2.54367 + vertex 0.844512 1.12176 2.54443 + endloop + endfacet + facet normal -0.486378 -0.436124 0.757121 + outer loop + vertex 0.844512 1.12176 2.54443 + vertex 0.838576 1.12707 2.54367 + vertex 0.840371 1.12215 2.54199 + endloop + endfacet + facet normal -0.506815 -0.469041 0.723283 + outer loop + vertex 0.843611 1.12519 2.54626 + vertex 0.843537 1.12845 2.54832 + vertex 0.841041 1.12785 2.54618 + endloop + endfacet + facet normal -0.586348 -0.405546 0.701234 + outer loop + vertex 0.838576 1.12707 2.54367 + vertex 0.841041 1.12785 2.54618 + vertex 0.838978 1.13073 2.54612 + endloop + endfacet + facet normal -0.583993 -0.365883 0.724626 + outer loop + vertex 0.84329 1.13156 2.55006 + vertex 0.841707 1.13511 2.55057 + vertex 0.840114 1.13317 2.54831 + endloop + endfacet + facet normal -0.592214 -0.427903 0.682775 + outer loop + vertex 0.843537 1.12845 2.54832 + vertex 0.84329 1.13156 2.55006 + vertex 0.840114 1.13317 2.54831 + endloop + endfacet + facet normal -0.552358 -0.398801 0.732023 + outer loop + vertex 0.843537 1.12845 2.54832 + vertex 0.840114 1.13317 2.54831 + vertex 0.838978 1.13073 2.54612 + endloop + endfacet + facet normal -0.54851 -0.37751 0.746072 + outer loop + vertex 0.843537 1.12845 2.54832 + vertex 0.838978 1.13073 2.54612 + vertex 0.841041 1.12785 2.54618 + endloop + endfacet + facet normal -0.549553 -0.355059 0.756257 + outer loop + vertex 0.84329 1.13156 2.55006 + vertex 0.845611 1.13206 2.55198 + vertex 0.841707 1.13511 2.55057 + endloop + endfacet + facet normal -0.623358 -0.320336 0.713309 + outer loop + vertex 0.837449 1.13817 2.54823 + vertex 0.840114 1.13317 2.54831 + vertex 0.841707 1.13511 2.55057 + endloop + endfacet + facet normal -0.625342 -0.326619 0.708708 + outer loop + vertex 0.84021 1.13873 2.55092 + vertex 0.837449 1.13817 2.54823 + vertex 0.841707 1.13511 2.55057 + endloop + endfacet + facet normal -0.595822 -0.317209 0.737818 + outer loop + vertex 0.841707 1.13511 2.55057 + vertex 0.844276 1.13707 2.55349 + vertex 0.84021 1.13873 2.55092 + endloop + endfacet + facet normal -0.557872 -0.372517 0.741626 + outer loop + vertex 0.845611 1.13206 2.55198 + vertex 0.844276 1.13707 2.55349 + vertex 0.841707 1.13511 2.55057 + endloop + endfacet + facet normal -0.697045 -0.0761496 0.712972 + outer loop + vertex 0.839461 1.18676 2.56295 + vertex 0.840266 1.18133 2.56315 + vertex 0.84237 1.18453 2.56555 + endloop + endfacet + facet normal -0.690892 -0.0593235 0.72052 + outer loop + vertex 0.841814 1.1894 2.56542 + vertex 0.839461 1.18676 2.56295 + vertex 0.84237 1.18453 2.56555 + endloop + endfacet + facet normal -0.688551 -0.0589941 0.722784 + outer loop + vertex 0.84237 1.18453 2.56555 + vertex 0.844576 1.18703 2.56786 + vertex 0.841814 1.1894 2.56542 + endloop + endfacet + facet normal -0.676064 -0.0790258 0.732593 + outer loop + vertex 0.845327 1.18247 2.56806 + vertex 0.844576 1.18703 2.56786 + vertex 0.84237 1.18453 2.56555 + endloop + endfacet + facet normal -0.692898 -0.0639489 0.718194 + outer loop + vertex 0.841541 1.19439 2.5656 + vertex 0.839122 1.19184 2.56304 + vertex 0.841814 1.1894 2.56542 + endloop + endfacet + facet normal -0.677969 -0.0636478 0.73233 + outer loop + vertex 0.841814 1.1894 2.56542 + vertex 0.844258 1.19186 2.5679 + vertex 0.841541 1.19439 2.5656 + endloop + endfacet + facet normal -0.685073 -0.0508996 0.726694 + outer loop + vertex 0.844576 1.18703 2.56786 + vertex 0.844258 1.19186 2.5679 + vertex 0.841814 1.1894 2.56542 + endloop + endfacet + facet normal -0.654957 -0.176495 0.734765 + outer loop + vertex 0.839642 1.22715 2.57144 + vertex 0.837746 1.22697 2.56971 + vertex 0.840281 1.22424 2.57132 + endloop + endfacet + facet normal -0.656308 -0.168578 0.735419 + outer loop + vertex 0.837746 1.22697 2.56971 + vertex 0.839642 1.22715 2.57144 + vertex 0.838681 1.22993 2.57122 + endloop + endfacet + facet normal -0.563309 0.0434754 0.825102 + outer loop + vertex 0.842188 1.60387 2.60005 + vertex 0.844945 1.60661 2.60179 + vertex 0.842715 1.60761 2.60021 + endloop + endfacet + facet normal -0.562734 0.0452264 0.8254 + outer loop + vertex 0.844508 1.60991 2.60131 + vertex 0.842715 1.60761 2.60021 + vertex 0.844945 1.60661 2.60179 + endloop + endfacet + facet normal -0.64922 0.0527079 0.758772 + outer loop + vertex 0.839745 1.77162 2.5772 + vertex 0.842356 1.77084 2.57948 + vertex 0.841817 1.77622 2.57865 + endloop + endfacet + facet normal -0.645308 0.0363435 0.763057 + outer loop + vertex 0.836855 1.77631 2.5744 + vertex 0.839218 1.77783 2.57632 + vertex 0.837678 1.77989 2.57492 + endloop + endfacet + facet normal -0.642902 0.0394155 0.764934 + outer loop + vertex 0.839218 1.77783 2.57632 + vertex 0.840049 1.78138 2.57684 + vertex 0.837678 1.77989 2.57492 + endloop + endfacet + facet normal -0.651835 0.0426309 0.757161 + outer loop + vertex 0.839218 1.77783 2.57632 + vertex 0.841817 1.77622 2.57865 + vertex 0.840049 1.78138 2.57684 + endloop + endfacet + facet normal -0.648248 0.0448929 0.760105 + outer loop + vertex 0.841817 1.77622 2.57865 + vertex 0.843051 1.78096 2.57942 + vertex 0.840049 1.78138 2.57684 + endloop + endfacet + facet normal -0.606155 0.288425 0.741206 + outer loop + vertex 0.841279 1.87767 2.55386 + vertex 0.838641 1.87496 2.55276 + vertex 0.841182 1.87324 2.5555 + endloop + endfacet + facet normal -0.588181 0.292743 0.753886 + outer loop + vertex 0.841182 1.87324 2.5555 + vertex 0.844414 1.8767 2.55668 + vertex 0.841279 1.87767 2.55386 + endloop + endfacet + facet normal -0.600357 0.309735 0.737316 + outer loop + vertex 0.844244 1.87176 2.55862 + vertex 0.844414 1.8767 2.55668 + vertex 0.841182 1.87324 2.5555 + endloop + endfacet + facet normal -0.590263 0.358165 0.7234 + outer loop + vertex 0.841181 1.88232 2.55158 + vertex 0.837072 1.87993 2.54941 + vertex 0.838858 1.87836 2.55165 + endloop + endfacet + facet normal -0.602193 0.28232 0.746766 + outer loop + vertex 0.838858 1.87836 2.55165 + vertex 0.838641 1.87496 2.55276 + vertex 0.841279 1.87767 2.55386 + endloop + endfacet + facet normal -0.575814 0.34996 0.738895 + outer loop + vertex 0.841181 1.88232 2.55158 + vertex 0.838858 1.87836 2.55165 + vertex 0.841279 1.87767 2.55386 + endloop + endfacet + facet normal -0.576572 0.349712 0.738421 + outer loop + vertex 0.841181 1.88232 2.55158 + vertex 0.841279 1.87767 2.55386 + vertex 0.844386 1.88073 2.55483 + endloop + endfacet + facet normal -0.557526 0.383571 0.736232 + outer loop + vertex 0.841181 1.88232 2.55158 + vertex 0.844386 1.88073 2.55483 + vertex 0.845035 1.88389 2.55368 + endloop + endfacet + facet normal -0.569356 0.339035 0.748925 + outer loop + vertex 0.844386 1.88073 2.55483 + vertex 0.841279 1.87767 2.55386 + vertex 0.844414 1.8767 2.55668 + endloop + endfacet + facet normal -0.586087 0.340053 0.735436 + outer loop + vertex 0.837693 1.88452 2.54778 + vertex 0.837072 1.87993 2.54941 + vertex 0.841181 1.88232 2.55158 + endloop + endfacet + facet normal -0.549171 0.397839 0.734939 + outer loop + vertex 0.841487 1.88717 2.54918 + vertex 0.837693 1.88452 2.54778 + vertex 0.841181 1.88232 2.55158 + endloop + endfacet + facet normal -0.541628 0.39964 0.739545 + outer loop + vertex 0.841181 1.88232 2.55158 + vertex 0.844749 1.88685 2.55174 + vertex 0.841487 1.88717 2.54918 + endloop + endfacet + facet normal -0.559849 0.41482 0.717282 + outer loop + vertex 0.845035 1.88389 2.55368 + vertex 0.844749 1.88685 2.55174 + vertex 0.841181 1.88232 2.55158 + endloop + endfacet + facet normal -0.524501 0.4398 0.729023 + outer loop + vertex 0.842113 1.89114 2.54728 + vertex 0.838388 1.89116 2.54459 + vertex 0.839219 1.88829 2.54692 + endloop + endfacet + facet normal -0.546361 0.390694 0.740843 + outer loop + vertex 0.839219 1.88829 2.54692 + vertex 0.837693 1.88452 2.54778 + vertex 0.841487 1.88717 2.54918 + endloop + endfacet + facet normal -0.51978 0.434132 0.73577 + outer loop + vertex 0.842113 1.89114 2.54728 + vertex 0.839219 1.88829 2.54692 + vertex 0.841487 1.88717 2.54918 + endloop + endfacet + facet normal -0.527565 0.433016 0.730871 + outer loop + vertex 0.842113 1.89114 2.54728 + vertex 0.841487 1.88717 2.54918 + vertex 0.844521 1.8902 2.54958 + endloop + endfacet + facet normal -0.519476 0.44715 0.72815 + outer loop + vertex 0.842113 1.89114 2.54728 + vertex 0.844521 1.8902 2.54958 + vertex 0.844348 1.89203 2.54833 + endloop + endfacet + facet normal -0.529347 0.435128 0.728323 + outer loop + vertex 0.844521 1.8902 2.54958 + vertex 0.841487 1.88717 2.54918 + vertex 0.844749 1.88685 2.55174 + endloop + endfacet + facet normal -0.525901 0.451993 0.720508 + outer loop + vertex 0.842113 1.89114 2.54728 + vertex 0.844461 1.89366 2.54742 + vertex 0.84264 1.8955 2.54493 + endloop + endfacet + facet normal -0.520566 0.453068 0.723699 + outer loop + vertex 0.842113 1.89114 2.54728 + vertex 0.84264 1.8955 2.54493 + vertex 0.838388 1.89116 2.54459 + endloop + endfacet + facet normal -0.518384 0.450684 0.726748 + outer loop + vertex 0.838388 1.89116 2.54459 + vertex 0.84264 1.8955 2.54493 + vertex 0.83815 1.89584 2.54152 + endloop + endfacet + facet normal -0.519334 0.445418 0.729311 + outer loop + vertex 0.844461 1.89366 2.54742 + vertex 0.842113 1.89114 2.54728 + vertex 0.844348 1.89203 2.54833 + endloop + endfacet + facet normal -0.463283 0.453686 0.761274 + outer loop + vertex 0.840893 1.90275 2.53909 + vertex 0.839058 1.90204 2.5384 + vertex 0.838881 1.9 2.53951 + endloop + endfacet + facet normal -0.489452 0.468904 0.735231 + outer loop + vertex 0.838881 1.9 2.53951 + vertex 0.841933 1.89981 2.54166 + vertex 0.840893 1.90275 2.53909 + endloop + endfacet + facet normal -0.496888 0.446884 0.743907 + outer loop + vertex 0.838881 1.9 2.53951 + vertex 0.83815 1.89584 2.54152 + vertex 0.841933 1.89981 2.54166 + endloop + endfacet + facet normal -0.513696 0.463663 0.721896 + outer loop + vertex 0.83815 1.89584 2.54152 + vertex 0.84264 1.8955 2.54493 + vertex 0.841933 1.89981 2.54166 + endloop + endfacet + facet normal -0.405505 0.581593 0.705206 + outer loop + vertex 0.841922 1.90626 2.53684 + vertex 0.838009 1.90596 2.53484 + vertex 0.839355 1.90378 2.53741 + endloop + endfacet + facet normal -0.468363 0.496297 0.730975 + outer loop + vertex 0.839355 1.90378 2.53741 + vertex 0.839058 1.90204 2.5384 + vertex 0.840893 1.90275 2.53909 + endloop + endfacet + facet normal -0.397542 0.57554 0.714643 + outer loop + vertex 0.841922 1.90626 2.53684 + vertex 0.839355 1.90378 2.53741 + vertex 0.840893 1.90275 2.53909 + endloop + endfacet + facet normal -0.385742 0.575988 0.720723 + outer loop + vertex 0.841922 1.90626 2.53684 + vertex 0.840893 1.90275 2.53909 + vertex 0.844624 1.90415 2.53997 + endloop + endfacet + facet normal -0.337869 0.619363 0.708685 + outer loop + vertex 0.841922 1.90626 2.53684 + vertex 0.844624 1.90415 2.53997 + vertex 0.844597 1.90689 2.53757 + endloop + endfacet + facet normal -0.377518 0.529772 0.759488 + outer loop + vertex 0.844624 1.90415 2.53997 + vertex 0.840893 1.90275 2.53909 + vertex 0.841933 1.89981 2.54166 + endloop + endfacet + facet normal -0.132574 0.710361 0.691239 + outer loop + vertex 0.841922 1.90626 2.53684 + vertex 0.845575 1.90895 2.53478 + vertex 0.841537 1.91012 2.53279 + endloop + endfacet + facet normal -0.385581 0.648546 0.656289 + outer loop + vertex 0.841922 1.90626 2.53684 + vertex 0.841537 1.91012 2.53279 + vertex 0.838009 1.90596 2.53484 + endloop + endfacet + facet normal -0.238134 0.582734 0.77699 + outer loop + vertex 0.838009 1.90596 2.53484 + vertex 0.841537 1.91012 2.53279 + vertex 0.837133 1.91005 2.5315 + endloop + endfacet + facet normal -0.322665 0.811844 0.486618 + outer loop + vertex 0.845575 1.90895 2.53478 + vertex 0.841922 1.90626 2.53684 + vertex 0.844597 1.90689 2.53757 + endloop + endfacet + facet normal -0.560267 0.798154 0.221475 + outer loop + vertex 0.845 1.91995 2.525 + vertex 0.845 1.92 2.52482 + vertex 0.841844 1.91817 2.52345 + endloop + endfacet + facet normal -0.595517 0.519255 0.612971 + outer loop + vertex 0.842921 1.91594 2.52638 + vertex 0.845 1.91995 2.525 + vertex 0.841844 1.91817 2.52345 + endloop + endfacet + facet normal 0.220489 0.814267 0.536986 + outer loop + vertex 0.84036 1.91652 2.52655 + vertex 0.842921 1.91594 2.52638 + vertex 0.841844 1.91817 2.52345 + endloop + endfacet + facet normal 0.286152 0.633569 0.718823 + outer loop + vertex 0.84036 1.91652 2.52655 + vertex 0.838849 1.91644 2.52723 + vertex 0.839547 1.91414 2.52898 + endloop + endfacet + facet normal 0.199562 0.664493 0.720156 + outer loop + vertex 0.84036 1.91652 2.52655 + vertex 0.839547 1.91414 2.52898 + vertex 0.842921 1.91594 2.52638 + endloop + endfacet + facet normal 0.122081 0.734156 0.667915 + outer loop + vertex 0.842921 1.91594 2.52638 + vertex 0.839547 1.91414 2.52898 + vertex 0.843968 1.91322 2.52918 + endloop + endfacet + facet normal -0.233412 0.607071 0.759594 + outer loop + vertex 0.841537 1.91012 2.53279 + vertex 0.839547 1.91414 2.52898 + vertex 0.837133 1.91005 2.5315 + endloop + endfacet + facet normal 0.116935 0.714414 0.689883 + outer loop + vertex 0.843968 1.91322 2.52918 + vertex 0.839547 1.91414 2.52898 + vertex 0.841537 1.91012 2.53279 + endloop + endfacet + facet normal 0.674478 0.37805 0.634159 + outer loop + vertex 0.842715 1.92005 2.51794 + vertex 0.845 1.9209 2.515 + vertex 0.842702 1.925 2.515 + endloop + endfacet + facet normal 0.0728303 0.509064 0.857642 + outer loop + vertex 0.839736 1.9225 2.51674 + vertex 0.842715 1.92005 2.51794 + vertex 0.842702 1.925 2.515 + endloop + endfacet + facet normal 0.588948 0.63442 0.500651 + outer loop + vertex 0.839736 1.9225 2.51674 + vertex 0.838072 1.92232 2.51891 + vertex 0.838587 1.9199 2.52138 + endloop + endfacet + facet normal 0.406729 0.750686 0.520617 + outer loop + vertex 0.842715 1.92005 2.51794 + vertex 0.839736 1.9225 2.51674 + vertex 0.838587 1.9199 2.52138 + endloop + endfacet + facet normal 0.257722 0.901009 0.348945 + outer loop + vertex 0.842715 1.92005 2.51794 + vertex 0.838587 1.9199 2.52138 + vertex 0.841844 1.91817 2.52345 + endloop + endfacet + facet normal -0.553773 0.810756 0.189762 + outer loop + vertex 0.842715 1.92005 2.51794 + vertex 0.841844 1.91817 2.52345 + vertex 0.845 1.92 2.52482 + endloop + endfacet + facet normal 0.20019 0.822841 0.531842 + outer loop + vertex 0.841844 1.91817 2.52345 + vertex 0.83917 1.91763 2.52528 + vertex 0.84036 1.91652 2.52655 + endloop + endfacet + facet normal 0.155791 0.863902 0.478959 + outer loop + vertex 0.838587 1.9199 2.52138 + vertex 0.83917 1.91763 2.52528 + vertex 0.841844 1.91817 2.52345 + endloop + endfacet + facet normal 0.194971 0.82163 0.535641 + outer loop + vertex 0.84036 1.91652 2.52655 + vertex 0.83917 1.91763 2.52528 + vertex 0.838849 1.91644 2.52723 + endloop + endfacet + facet normal 0.958528 0.284681 -0.0134145 + outer loop + vertex 0.842632 1.925 2.51 + vertex 0.841147 1.93 2.51 + vertex 0.842702 1.925 2.515 + endloop + endfacet + facet normal -0.302589 0.625272 0.719358 + outer loop + vertex 0.841147 1.93 2.51 + vertex 0.839363 1.92571 2.51298 + vertex 0.842702 1.925 2.515 + endloop + endfacet + facet normal 0.662668 0.557687 0.499856 + outer loop + vertex 0.837344 1.92469 2.5168 + vertex 0.839363 1.92571 2.51298 + vertex 0.837475 1.92756 2.51342 + endloop + endfacet + facet normal 0.596666 0.638162 0.486558 + outer loop + vertex 0.837344 1.92469 2.5168 + vertex 0.839736 1.9225 2.51674 + vertex 0.839363 1.92571 2.51298 + endloop + endfacet + facet normal -0.235781 0.726891 0.645009 + outer loop + vertex 0.839736 1.9225 2.51674 + vertex 0.842702 1.925 2.515 + vertex 0.839363 1.92571 2.51298 + endloop + endfacet + facet normal 0.590948 0.631525 0.501952 + outer loop + vertex 0.839736 1.9225 2.51674 + vertex 0.837344 1.92469 2.5168 + vertex 0.838072 1.92232 2.51891 + endloop + endfacet + facet normal 0.994301 -0.0129827 0.105816 + outer loop + vertex 0.840338 1.93237 2.4919 + vertex 0.84 1.93171 2.495 + vertex 0.84 1.93 2.49479 + endloop + endfacet + facet normal 0.605871 0.578664 0.545956 + outer loop + vertex 0.840338 1.93237 2.4919 + vertex 0.84 1.93 2.49479 + vertex 0.842441 1.93295 2.48896 + endloop + endfacet + facet normal 0.456505 0.702455 0.54604 + outer loop + vertex 0.842441 1.93295 2.48896 + vertex 0.84 1.93 2.49479 + vertex 0.845 1.93 2.49061 + endloop + endfacet + facet normal 0.994336 -0.0181455 0.104722 + outer loop + vertex 0.840338 1.93237 2.4919 + vertex 0.84 1.935 2.49557 + vertex 0.84 1.93171 2.495 + endloop + endfacet + facet normal -0.748279 0.507698 0.426992 + outer loop + vertex 0.84 1.93 2.50799 + vertex 0.838856 1.92933 2.50678 + vertex 0.841147 1.93 2.51 + endloop + endfacet + facet normal -0.363776 0.628577 0.687429 + outer loop + vertex 0.841147 1.93 2.51 + vertex 0.838377 1.92878 2.50965 + vertex 0.839363 1.92571 2.51298 + endloop + endfacet + facet normal -0.412796 0.904702 0.105423 + outer loop + vertex 0.838856 1.92933 2.50678 + vertex 0.838377 1.92878 2.50965 + vertex 0.841147 1.93 2.51 + endloop + endfacet + facet normal 0.692991 0.620764 0.366628 + outer loop + vertex 0.839363 1.92571 2.51298 + vertex 0.838377 1.92878 2.50965 + vertex 0.837475 1.92756 2.51342 + endloop + endfacet + facet normal 0.806096 0.0809228 0.586225 + outer loop + vertex 0.842441 1.93295 2.48896 + vertex 0.842462 1.93866 2.48814 + vertex 0.840575 1.93604 2.49109 + endloop + endfacet + facet normal 0.804384 0.0779955 0.588967 + outer loop + vertex 0.840338 1.93237 2.4919 + vertex 0.842441 1.93295 2.48896 + vertex 0.840575 1.93604 2.49109 + endloop + endfacet + facet normal 0.992202 -0.0379265 0.118726 + outer loop + vertex 0.840575 1.93604 2.49109 + vertex 0.84 1.935 2.49557 + vertex 0.840338 1.93237 2.4919 + endloop + endfacet + facet normal 0.991822 0.0005112 0.12763 + outer loop + vertex 0.84 1.94 2.49555 + vertex 0.84 1.935 2.49557 + vertex 0.840575 1.93604 2.49109 + endloop + endfacet + facet normal 0.843231 -0.0397525 0.53608 + outer loop + vertex 0.842462 1.93866 2.48814 + vertex 0.842113 1.94493 2.48915 + vertex 0.840426 1.94137 2.49154 + endloop + endfacet + facet normal 0.850817 -0.0202094 0.525073 + outer loop + vertex 0.840575 1.93604 2.49109 + vertex 0.842462 1.93866 2.48814 + vertex 0.840426 1.94137 2.49154 + endloop + endfacet + facet normal 0.993542 0.0183997 0.111965 + outer loop + vertex 0.840426 1.94137 2.49154 + vertex 0.84 1.94 2.49555 + vertex 0.840575 1.93604 2.49109 + endloop + endfacet + facet normal 0.994182 0.00537601 0.107579 + outer loop + vertex 0.84 1.945 2.4953 + vertex 0.84 1.94 2.49555 + vertex 0.840426 1.94137 2.49154 + endloop + endfacet + facet normal 0.898058 -0.147412 0.414441 + outer loop + vertex 0.84 1.9485 2.495 + vertex 0.840426 1.94137 2.49154 + vertex 0.842113 1.94493 2.48915 + endloop + endfacet + facet normal 0.944821 0.0239392 0.326711 + outer loop + vertex 0.84 1.9485 2.495 + vertex 0.842113 1.94493 2.48915 + vertex 0.84 1.95 2.49489 + endloop + endfacet + facet normal 0.884924 -0.135534 0.445579 + outer loop + vertex 0.84 1.95 2.49489 + vertex 0.842113 1.94493 2.48915 + vertex 0.843212 1.94957 2.48838 + endloop + endfacet + facet normal 0.994518 0.008935 0.104182 + outer loop + vertex 0.840426 1.94137 2.49154 + vertex 0.84 1.9485 2.495 + vertex 0.84 1.945 2.4953 + endloop + endfacet + facet normal 0.93069 -0.365688 -0.00934214 + outer loop + vertex 0.840026 1.94912 2.5009 + vertex 0.838491 1.94514 2.5037 + vertex 0.839038 1.94662 2.50031 + endloop + endfacet + facet normal 0.946168 -0.3161 0.0696149 + outer loop + vertex 0.839476 1.94833 2.50482 + vertex 0.838491 1.94514 2.5037 + vertex 0.840026 1.94912 2.5009 + endloop + endfacet + facet normal 0.910747 -0.35479 0.211339 + outer loop + vertex 0.837729 1.94561 2.50778 + vertex 0.838491 1.94514 2.5037 + vertex 0.839476 1.94833 2.50482 + endloop + endfacet + facet normal 0.903291 -0.393176 0.171689 + outer loop + vertex 0.838806 1.94853 2.50879 + vertex 0.837729 1.94561 2.50778 + vertex 0.839476 1.94833 2.50482 + endloop + endfacet + facet normal 0.798833 -0.437829 0.412519 + outer loop + vertex 0.837304 1.94713 2.51021 + vertex 0.837729 1.94561 2.50778 + vertex 0.838806 1.94853 2.50879 + endloop + endfacet + facet normal 0.798655 -0.397429 0.451886 + outer loop + vertex 0.838806 1.94853 2.50879 + vertex 0.838013 1.94935 2.51092 + vertex 0.837304 1.94713 2.51021 + endloop + endfacet + facet normal 0.791592 -0.44401 0.419806 + outer loop + vertex 0.843212 1.94957 2.48838 + vertex 0.845 1.955 2.49075 + vertex 0.84 1.95 2.49489 + endloop + endfacet + facet normal 0.566716 0.109419 0.816615 + outer loop + vertex 0.84 1.95 2.49489 + vertex 0.845 1.955 2.49075 + vertex 0.84 1.955 2.49422 + endloop + endfacet + facet normal 0.726307 -0.486556 -0.485532 + outer loop + vertex 0.843182 1.955 2.5 + vertex 0.84 1.95025 2.5 + vertex 0.84 1.955 2.49524 + endloop + endfacet + facet normal 0.893117 -0.267421 -0.361702 + outer loop + vertex 0.84 1.95025 2.5 + vertex 0.840026 1.94912 2.5009 + vertex 0.839038 1.94662 2.50031 + endloop + endfacet + facet normal 0.673112 -0.450921 -0.586166 + outer loop + vertex 0.84 1.95025 2.5 + vertex 0.843182 1.955 2.5 + vertex 0.840026 1.94912 2.5009 + endloop + endfacet + facet normal 0.781158 -0.338673 0.524493 + outer loop + vertex 0.843182 1.955 2.5 + vertex 0.841194 1.95293 2.50163 + vertex 0.840026 1.94912 2.5009 + endloop + endfacet + facet normal 0.949777 -0.304423 0.072455 + outer loop + vertex 0.840026 1.94912 2.5009 + vertex 0.841194 1.95293 2.50163 + vertex 0.839476 1.94833 2.50482 + endloop + endfacet + facet normal 0.956007 -0.243379 0.16376 + outer loop + vertex 0.841194 1.95293 2.50163 + vertex 0.840241 1.95201 2.50582 + vertex 0.839476 1.94833 2.50482 + endloop + endfacet + facet normal 0.953838 -0.245456 0.173043 + outer loop + vertex 0.839476 1.94833 2.50482 + vertex 0.840241 1.95201 2.50582 + vertex 0.838806 1.94853 2.50879 + endloop + endfacet + facet normal 0.951168 -0.175548 0.253894 + outer loop + vertex 0.840241 1.95201 2.50582 + vertex 0.839243 1.95208 2.50961 + vertex 0.838806 1.94853 2.50879 + endloop + endfacet + facet normal 0.888891 -0.203888 0.410246 + outer loop + vertex 0.839243 1.95208 2.50961 + vertex 0.838013 1.94935 2.51092 + vertex 0.838806 1.94853 2.50879 + endloop + endfacet + facet normal 0.775206 -0.0471012 0.629949 + outer loop + vertex 0.837859 1.95245 2.51134 + vertex 0.838013 1.94935 2.51092 + vertex 0.839243 1.95208 2.50961 + endloop + endfacet + facet normal 0.678248 -0.0774496 0.730741 + outer loop + vertex 0.843182 1.955 2.5 + vertex 0.843753 1.96 2.5 + vertex 0.841194 1.95293 2.50163 + endloop + endfacet + facet normal 0.82441 -0.174651 0.538373 + outer loop + vertex 0.843753 1.96 2.5 + vertex 0.841757 1.95721 2.50215 + vertex 0.841194 1.95293 2.50163 + endloop + endfacet + facet normal 0.970638 -0.150842 0.187373 + outer loop + vertex 0.841194 1.95293 2.50163 + vertex 0.841757 1.95721 2.50215 + vertex 0.840241 1.95201 2.50582 + endloop + endfacet + facet normal 0.963232 -0.106985 0.246452 + outer loop + vertex 0.841757 1.95721 2.50215 + vertex 0.84057 1.95641 2.50644 + vertex 0.840241 1.95201 2.50582 + endloop + endfacet + facet normal 0.960834 -0.108046 0.255196 + outer loop + vertex 0.840241 1.95201 2.50582 + vertex 0.84057 1.95641 2.50644 + vertex 0.839243 1.95208 2.50961 + endloop + endfacet + facet normal 0.936359 -0.0315506 0.349622 + outer loop + vertex 0.84057 1.95641 2.50644 + vertex 0.839289 1.95643 2.50988 + vertex 0.839243 1.95208 2.50961 + endloop + endfacet + facet normal 0.775194 -0.0471866 0.629958 + outer loop + vertex 0.839289 1.95643 2.50988 + vertex 0.837859 1.95245 2.51134 + vertex 0.839243 1.95208 2.50961 + endloop + endfacet + facet normal 0.617644 0.0660067 0.783683 + outer loop + vertex 0.837776 1.95677 2.51104 + vertex 0.837859 1.95245 2.51134 + vertex 0.839289 1.95643 2.50988 + endloop + endfacet + facet normal 0.735681 -0.00397282 0.677316 + outer loop + vertex 0.843753 1.96 2.5 + vertex 0.84378 1.965 2.5 + vertex 0.841757 1.95721 2.50215 + endloop + endfacet + facet normal 0.782229 -0.0312845 0.622205 + outer loop + vertex 0.84378 1.965 2.5 + vertex 0.841866 1.9617 2.50224 + vertex 0.841757 1.95721 2.50215 + endloop + endfacet + facet normal 0.964783 -0.0286406 0.261485 + outer loop + vertex 0.841757 1.95721 2.50215 + vertex 0.841866 1.9617 2.50224 + vertex 0.84057 1.95641 2.50644 + endloop + endfacet + facet normal 0.960314 -0.0139597 0.278572 + outer loop + vertex 0.841866 1.9617 2.50224 + vertex 0.840581 1.96121 2.50665 + vertex 0.84057 1.95641 2.50644 + endloop + endfacet + facet normal 0.936713 -0.0169093 0.34969 + outer loop + vertex 0.84057 1.95641 2.50644 + vertex 0.840581 1.96121 2.50665 + vertex 0.839289 1.95643 2.50988 + endloop + endfacet + facet normal 0.902128 0.045965 0.429013 + outer loop + vertex 0.840581 1.96121 2.50665 + vertex 0.839162 1.96077 2.50968 + vertex 0.839289 1.95643 2.50988 + endloop + endfacet + facet normal 0.616377 0.053871 0.785607 + outer loop + vertex 0.839162 1.96077 2.50968 + vertex 0.837776 1.95677 2.51104 + vertex 0.839289 1.95643 2.50988 + endloop + endfacet + facet normal 0.436634 0.150677 0.886931 + outer loop + vertex 0.837845 1.96051 2.51037 + vertex 0.837776 1.95677 2.51104 + vertex 0.839162 1.96077 2.50968 + endloop + endfacet + facet normal 0.998509 0.00539213 0.0543247 + outer loop + vertex 0.844052 1.965 2.495 + vertex 0.844025 1.97 2.495 + vertex 0.84378 1.965 2.5 + endloop + endfacet + facet normal 0.16348 0.693585 0.70158 + outer loop + vertex 0.844025 1.97 2.495 + vertex 0.843008 1.96738 2.49783 + vertex 0.84378 1.965 2.5 + endloop + endfacet + facet normal -0.195878 0.625769 0.755013 + outer loop + vertex 0.84378 1.965 2.5 + vertex 0.843008 1.96738 2.49783 + vertex 0.841866 1.9617 2.50224 + endloop + endfacet + facet normal 0.962616 0.0166101 0.270361 + outer loop + vertex 0.843008 1.96738 2.49783 + vertex 0.841811 1.96621 2.50216 + vertex 0.841866 1.9617 2.50224 + endloop + endfacet + facet normal 0.959355 0.0167677 0.281704 + outer loop + vertex 0.841866 1.9617 2.50224 + vertex 0.841811 1.96621 2.50216 + vertex 0.840581 1.96121 2.50665 + endloop + endfacet + facet normal 0.934481 0.081145 0.346641 + outer loop + vertex 0.841811 1.96621 2.50216 + vertex 0.840205 1.96594 2.50655 + vertex 0.840581 1.96121 2.50665 + endloop + endfacet + facet normal 0.598294 0.399085 0.69482 + outer loop + vertex 0.838672 1.96363 2.5092 + vertex 0.840205 1.96594 2.50655 + vertex 0.838494 1.96712 2.50735 + endloop + endfacet + facet normal 0.739848 0.232319 0.63139 + outer loop + vertex 0.838672 1.96363 2.5092 + vertex 0.839162 1.96077 2.50968 + vertex 0.840205 1.96594 2.50655 + endloop + endfacet + facet normal 0.898259 0.0799262 0.432136 + outer loop + vertex 0.839162 1.96077 2.50968 + vertex 0.840581 1.96121 2.50665 + vertex 0.840205 1.96594 2.50655 + endloop + endfacet + facet normal 0.420039 0.219009 0.880683 + outer loop + vertex 0.839162 1.96077 2.50968 + vertex 0.838672 1.96363 2.5092 + vertex 0.837845 1.96051 2.51037 + endloop + endfacet + facet normal 0.962827 -0.105527 0.248651 + outer loop + vertex 0.844025 1.97 2.495 + vertex 0.844573 1.975 2.495 + vertex 0.843008 1.96738 2.49783 + endloop + endfacet + facet normal 0.898849 -0.0222464 0.437693 + outer loop + vertex 0.844573 1.975 2.495 + vertex 0.843156 1.97116 2.49771 + vertex 0.843008 1.96738 2.49783 + endloop + endfacet + facet normal 0.965535 -0.030228 0.258513 + outer loop + vertex 0.843008 1.96738 2.49783 + vertex 0.843156 1.97116 2.49771 + vertex 0.841811 1.96621 2.50216 + endloop + endfacet + facet normal 0.962746 -0.0194105 0.269708 + outer loop + vertex 0.843156 1.97116 2.49771 + vertex 0.841885 1.97059 2.50221 + vertex 0.841811 1.96621 2.50216 + endloop + endfacet + facet normal 0.939434 -0.019847 0.342155 + outer loop + vertex 0.841811 1.96621 2.50216 + vertex 0.841885 1.97059 2.50221 + vertex 0.840205 1.96594 2.50655 + endloop + endfacet + facet normal 0.84935 0.162063 0.502335 + outer loop + vertex 0.841885 1.97059 2.50221 + vertex 0.84002 1.97099 2.50523 + vertex 0.840205 1.96594 2.50655 + endloop + endfacet + facet normal 0.536015 0.231402 0.811875 + outer loop + vertex 0.84002 1.97099 2.50523 + vertex 0.838494 1.96712 2.50735 + vertex 0.840205 1.96594 2.50655 + endloop + endfacet + facet normal 0.169861 0.419318 0.891807 + outer loop + vertex 0.838247 1.97031 2.50589 + vertex 0.838494 1.96712 2.50735 + vertex 0.84002 1.97099 2.50523 + endloop + endfacet + facet normal 0.922608 -0.167664 0.347396 + outer loop + vertex 0.845 1.97568 2.495 + vertex 0.843526 1.97461 2.4984 + vertex 0.843156 1.97116 2.49771 + endloop + endfacet + facet normal 0.808714 -0.507856 -0.296756 + outer loop + vertex 0.844573 1.975 2.495 + vertex 0.845 1.97568 2.495 + vertex 0.843156 1.97116 2.49771 + endloop + endfacet + facet normal 0.940596 -0.0686964 0.332506 + outer loop + vertex 0.843526 1.97461 2.4984 + vertex 0.842054 1.97464 2.50257 + vertex 0.841885 1.97059 2.50221 + endloop + endfacet + facet normal 0.955941 -0.152107 0.251077 + outer loop + vertex 0.843156 1.97116 2.49771 + vertex 0.843526 1.97461 2.4984 + vertex 0.841885 1.97059 2.50221 + endloop + endfacet + facet normal 0.449759 -0.24311 0.859427 + outer loop + vertex 0.842054 1.97464 2.50257 + vertex 0.8422 1.97842 2.50356 + vertex 0.839669 1.97518 2.50397 + endloop + endfacet + facet normal 0.533357 0.284974 0.796442 + outer loop + vertex 0.842054 1.97464 2.50257 + vertex 0.839669 1.97518 2.50397 + vertex 0.84002 1.97099 2.50523 + endloop + endfacet + facet normal 0.843327 -0.0822023 0.531077 + outer loop + vertex 0.842054 1.97464 2.50257 + vertex 0.84002 1.97099 2.50523 + vertex 0.841885 1.97059 2.50221 + endloop + endfacet + facet normal 0.368702 0.296678 0.880932 + outer loop + vertex 0.84002 1.97099 2.50523 + vertex 0.839669 1.97518 2.50397 + vertex 0.838887 1.97239 2.50524 + endloop + endfacet + facet normal 0.266823 0.213667 0.939762 + outer loop + vertex 0.84002 1.97099 2.50523 + vertex 0.838887 1.97239 2.50524 + vertex 0.838247 1.97031 2.50589 + endloop + endfacet + facet normal 0.814263 -0.301357 -0.496145 + outer loop + vertex 0.845 1.98107 2.49 + vertex 0.845 1.98 2.49065 + vertex 0.844604 1.98 2.49 + endloop + endfacet + facet normal -0.476972 -0.0846031 0.874837 + outer loop + vertex 0.842346 1.98129 2.50475 + vertex 0.841581 1.98405 2.5046 + vertex 0.840018 1.98021 2.50338 + endloop + endfacet + facet normal -0.354318 -0.343119 0.869901 + outer loop + vertex 0.842346 1.98129 2.50475 + vertex 0.840018 1.98021 2.50338 + vertex 0.8422 1.97842 2.50356 + endloop + endfacet + facet normal 0.0122248 0.116043 0.993169 + outer loop + vertex 0.8422 1.97842 2.50356 + vertex 0.840018 1.98021 2.50338 + vertex 0.839669 1.97518 2.50397 + endloop + endfacet + facet normal -0.398725 -0.060801 0.915053 + outer loop + vertex 0.842346 1.98129 2.50475 + vertex 0.843192 1.9835 2.50527 + vertex 0.841581 1.98405 2.5046 + endloop + endfacet + facet normal -0.815939 0.199004 0.542808 + outer loop + vertex 0.840291 1.98743 2.50225 + vertex 0.83867 1.98628 2.50024 + vertex 0.839634 1.98393 2.50255 + endloop + endfacet + facet normal -0.726142 0.0776788 0.683143 + outer loop + vertex 0.839634 1.98393 2.50255 + vertex 0.840018 1.98021 2.50338 + vertex 0.841581 1.98405 2.5046 + endloop + endfacet + facet normal -0.718264 0.191274 0.668963 + outer loop + vertex 0.839634 1.98393 2.50255 + vertex 0.841581 1.98405 2.5046 + vertex 0.840291 1.98743 2.50225 + endloop + endfacet + facet normal -0.700705 0.207487 0.682613 + outer loop + vertex 0.840291 1.98743 2.50225 + vertex 0.841581 1.98405 2.5046 + vertex 0.842178 1.9883 2.50393 + endloop + endfacet + facet normal -0.590178 0.207514 0.780146 + outer loop + vertex 0.841581 1.98405 2.5046 + vertex 0.843057 1.98582 2.50525 + vertex 0.842178 1.9883 2.50393 + endloop + endfacet + facet normal -0.386115 -0.015288 0.922324 + outer loop + vertex 0.843192 1.9835 2.50527 + vertex 0.843057 1.98582 2.50525 + vertex 0.841581 1.98405 2.5046 + endloop + endfacet + facet normal -0.818635 0.23921 0.522126 + outer loop + vertex 0.838936 1.99014 2.49889 + vertex 0.83867 1.98628 2.50024 + vertex 0.840291 1.98743 2.50225 + endloop + endfacet + facet normal -0.790935 0.280161 0.543996 + outer loop + vertex 0.841097 1.99278 2.50067 + vertex 0.838936 1.99014 2.49889 + vertex 0.840291 1.98743 2.50225 + endloop + endfacet + facet normal -0.235285 0.41284 0.879889 + outer loop + vertex 0.843333 1.99204 2.50248 + vertex 0.842178 1.9883 2.50393 + vertex 0.843658 1.98851 2.50423 + endloop + endfacet + facet normal -0.472308 0.440941 0.763214 + outer loop + vertex 0.843333 1.99204 2.50248 + vertex 0.841097 1.99278 2.50067 + vertex 0.842178 1.9883 2.50393 + endloop + endfacet + facet normal -0.706454 0.296614 0.642606 + outer loop + vertex 0.841097 1.99278 2.50067 + vertex 0.840291 1.98743 2.50225 + vertex 0.842178 1.9883 2.50393 + endloop + endfacet + facet normal -0.234366 0.391949 0.889634 + outer loop + vertex 0.843658 1.98851 2.50423 + vertex 0.842178 1.9883 2.50393 + vertex 0.843057 1.98582 2.50525 + endloop + endfacet + facet normal -0.832568 0.306169 0.461617 + outer loop + vertex 0.840211 1.99723 2.49711 + vertex 0.838702 1.99642 2.49492 + vertex 0.839231 1.99393 2.49753 + endloop + endfacet + facet normal -0.784297 0.262362 0.562178 + outer loop + vertex 0.839231 1.99393 2.49753 + vertex 0.838936 1.99014 2.49889 + vertex 0.841097 1.99278 2.50067 + endloop + endfacet + facet normal -0.7677 0.300093 0.566199 + outer loop + vertex 0.839231 1.99393 2.49753 + vertex 0.841097 1.99278 2.50067 + vertex 0.840211 1.99723 2.49711 + endloop + endfacet + facet normal -0.699137 0.35656 0.619736 + outer loop + vertex 0.840211 1.99723 2.49711 + vertex 0.841097 1.99278 2.50067 + vertex 0.842291 1.99766 2.49921 + endloop + endfacet + facet normal -0.584857 0.360643 0.726553 + outer loop + vertex 0.841097 1.99278 2.50067 + vertex 0.843012 1.99534 2.50094 + vertex 0.842291 1.99766 2.49921 + endloop + endfacet + facet normal -0.532086 0.315144 0.785855 + outer loop + vertex 0.843333 1.99204 2.50248 + vertex 0.843012 1.99534 2.50094 + vertex 0.841097 1.99278 2.50067 + endloop + endfacet + facet normal -0.831787 0.312567 0.458729 + outer loop + vertex 0.839212 2.00005 2.49338 + vertex 0.838702 1.99642 2.49492 + vertex 0.840211 1.99723 2.49711 + endloop + endfacet + facet normal -0.796572 0.36035 0.485408 + outer loop + vertex 0.84167 2.00235 2.4957 + vertex 0.839212 2.00005 2.49338 + vertex 0.840211 1.99723 2.49711 + endloop + endfacet + facet normal -0.454863 0.495953 0.739682 + outer loop + vertex 0.844573 2.00028 2.49886 + vertex 0.842291 1.99766 2.49921 + vertex 0.843667 1.99749 2.50017 + endloop + endfacet + facet normal -0.453013 0.494611 0.741713 + outer loop + vertex 0.844573 2.00028 2.49886 + vertex 0.84167 2.00235 2.4957 + vertex 0.842291 1.99766 2.49921 + endloop + endfacet + facet normal -0.697128 0.367834 0.615394 + outer loop + vertex 0.84167 2.00235 2.4957 + vertex 0.840211 1.99723 2.49711 + vertex 0.842291 1.99766 2.49921 + endloop + endfacet + facet normal -0.483138 0.422398 0.766915 + outer loop + vertex 0.843667 1.99749 2.50017 + vertex 0.842291 1.99766 2.49921 + vertex 0.843012 1.99534 2.50094 + endloop + endfacet + facet normal -0.856933 0.2972 0.421115 + outer loop + vertex 0.840444 2.00757 2.4908 + vertex 0.838932 2.00593 2.48888 + vertex 0.839541 2.00372 2.49169 + endloop + endfacet + facet normal -0.790715 0.313205 0.525997 + outer loop + vertex 0.839541 2.00372 2.49169 + vertex 0.839212 2.00005 2.49338 + vertex 0.84167 2.00235 2.4957 + endloop + endfacet + facet normal -0.793837 0.306364 0.525323 + outer loop + vertex 0.839541 2.00372 2.49169 + vertex 0.84167 2.00235 2.4957 + vertex 0.840444 2.00757 2.4908 + endloop + endfacet + facet normal -0.8185 0.278928 0.502252 + outer loop + vertex 0.840444 2.00757 2.4908 + vertex 0.84167 2.00235 2.4957 + vertex 0.842959 2.00766 2.49485 + endloop + endfacet + facet normal -0.68399 0.274077 0.676047 + outer loop + vertex 0.84167 2.00235 2.4957 + vertex 0.845087 2.0049 2.49812 + vertex 0.842959 2.00766 2.49485 + endloop + endfacet + facet normal -0.657907 0.188637 0.729091 + outer loop + vertex 0.844573 2.00028 2.49886 + vertex 0.845087 2.0049 2.49812 + vertex 0.84167 2.00235 2.4957 + endloop + endfacet + facet normal -0.895495 0.31277 0.316644 + outer loop + vertex 0.840005 2.01249 2.48603 + vertex 0.838741 2.01062 2.4843 + vertex 0.839064 2.00871 2.4871 + endloop + endfacet + facet normal -0.857356 0.306222 0.413726 + outer loop + vertex 0.839064 2.00871 2.4871 + vertex 0.838932 2.00593 2.48888 + vertex 0.840444 2.00757 2.4908 + endloop + endfacet + facet normal -0.847153 0.329296 0.417008 + outer loop + vertex 0.839064 2.00871 2.4871 + vertex 0.840444 2.00757 2.4908 + vertex 0.840005 2.01249 2.48603 + endloop + endfacet + facet normal -0.874118 0.29595 0.385137 + outer loop + vertex 0.840005 2.01249 2.48603 + vertex 0.840444 2.00757 2.4908 + vertex 0.842172 2.01252 2.49092 + endloop + endfacet + facet normal -0.782584 0.228361 0.57915 + outer loop + vertex 0.844009 2.01095 2.49498 + vertex 0.842959 2.00766 2.49485 + vertex 0.844963 2.00846 2.49725 + endloop + endfacet + facet normal -0.841271 0.25091 0.478861 + outer loop + vertex 0.844009 2.01095 2.49498 + vertex 0.842172 2.01252 2.49092 + vertex 0.842959 2.00766 2.49485 + endloop + endfacet + facet normal -0.819655 0.274001 0.50308 + outer loop + vertex 0.842172 2.01252 2.49092 + vertex 0.840444 2.00757 2.4908 + vertex 0.842959 2.00766 2.49485 + endloop + endfacet + facet normal -0.780767 0.124188 0.612356 + outer loop + vertex 0.844963 2.00846 2.49725 + vertex 0.842959 2.00766 2.49485 + vertex 0.845087 2.0049 2.49812 + endloop + endfacet + facet normal 0.525872 -0.547323 -0.651073 + outer loop + vertex 0.845 2.01525 2.48 + vertex 0.845 2.015 2.48021 + vertex 0.84474 2.015 2.48 + endloop + endfacet + facet normal -0.911388 0.321346 0.257116 + outer loop + vertex 0.839131 2.01572 2.47957 + vertex 0.839102 2.01352 2.48221 + vertex 0.840389 2.01783 2.48139 + endloop + endfacet + facet normal -0.89569 0.327972 0.300291 + outer loop + vertex 0.839102 2.01352 2.48221 + vertex 0.838741 2.01062 2.4843 + vertex 0.840005 2.01249 2.48603 + endloop + endfacet + facet normal -0.89686 0.325191 0.29982 + outer loop + vertex 0.839102 2.01352 2.48221 + vertex 0.840005 2.01249 2.48603 + vertex 0.840389 2.01783 2.48139 + endloop + endfacet + facet normal -0.910174 0.307132 0.277945 + outer loop + vertex 0.840389 2.01783 2.48139 + vertex 0.840005 2.01249 2.48603 + vertex 0.841552 2.01731 2.48577 + endloop + endfacet + facet normal -0.872736 0.300822 0.384498 + outer loop + vertex 0.840005 2.01249 2.48603 + vertex 0.842172 2.01252 2.49092 + vertex 0.841552 2.01731 2.48577 + endloop + endfacet + facet normal -0.915409 0.233984 0.327532 + outer loop + vertex 0.841552 2.01731 2.48577 + vertex 0.842172 2.01252 2.49092 + vertex 0.843072 2.01768 2.48975 + endloop + endfacet + facet normal -0.846436 0.253852 0.468086 + outer loop + vertex 0.842172 2.01252 2.49092 + vertex 0.844225 2.01474 2.49343 + vertex 0.843072 2.01768 2.48975 + endloop + endfacet + facet normal -0.844816 0.242209 0.477096 + outer loop + vertex 0.844009 2.01095 2.49498 + vertex 0.844225 2.01474 2.49343 + vertex 0.842172 2.01252 2.49092 + endloop + endfacet + facet normal -0.866741 0.0936911 0.48988 + outer loop + vertex 0.84 2.02149 2.48 + vertex 0.839131 2.01572 2.47957 + vertex 0.840389 2.01783 2.48139 + endloop + endfacet + facet normal -0.397142 0.288186 0.871336 + outer loop + vertex 0.84 2.02149 2.48 + vertex 0.840389 2.01783 2.48139 + vertex 0.842547 2.025 2.48 + endloop + endfacet + facet normal -0.901415 0.326317 0.284549 + outer loop + vertex 0.842547 2.025 2.48 + vertex 0.840389 2.01783 2.48139 + vertex 0.841921 2.0222 2.48123 + endloop + endfacet + facet normal -0.903187 0.326715 0.278406 + outer loop + vertex 0.840389 2.01783 2.48139 + vertex 0.841552 2.01731 2.48577 + vertex 0.841921 2.0222 2.48123 + endloop + endfacet + facet normal -0.954356 0.238727 0.179485 + outer loop + vertex 0.841921 2.0222 2.48123 + vertex 0.841552 2.01731 2.48577 + vertex 0.842814 2.02238 2.48574 + endloop + endfacet + facet normal -0.855263 0.249122 0.454382 + outer loop + vertex 0.844045 2.02114 2.48969 + vertex 0.843072 2.01768 2.48975 + vertex 0.844564 2.01858 2.49207 + endloop + endfacet + facet normal -0.89608 0.258838 0.360616 + outer loop + vertex 0.844045 2.02114 2.48969 + vertex 0.842814 2.02238 2.48574 + vertex 0.843072 2.01768 2.48975 + endloop + endfacet + facet normal -0.916175 0.230027 0.328193 + outer loop + vertex 0.842814 2.02238 2.48574 + vertex 0.841552 2.01731 2.48577 + vertex 0.843072 2.01768 2.48975 + endloop + endfacet + facet normal -0.855874 0.238592 0.458861 + outer loop + vertex 0.844564 2.01858 2.49207 + vertex 0.843072 2.01768 2.48975 + vertex 0.844225 2.01474 2.49343 + endloop + endfacet + facet normal -0.654179 0.0106024 -0.756265 + outer loop + vertex 0.845 2.025 2.47505 + vertex 0.842993 2.02702 2.47681 + vertex 0.845 2.03 2.47512 + endloop + endfacet + facet normal -0.800313 -0.449674 -0.396601 + outer loop + vertex 0.842547 2.025 2.48 + vertex 0.842993 2.02702 2.47681 + vertex 0.845 2.025 2.47505 + endloop + endfacet + facet normal 0.975764 -0.218818 -0.00183024 + outer loop + vertex 0.842547 2.025 2.48 + vertex 0.841921 2.0222 2.48123 + vertex 0.842993 2.02702 2.47681 + endloop + endfacet + facet normal -0.986033 0.146039 -0.0800676 + outer loop + vertex 0.842993 2.02702 2.47681 + vertex 0.841921 2.0222 2.48123 + vertex 0.84265 2.02683 2.48071 + endloop + endfacet + facet normal -0.96744 0.173079 0.18467 + outer loop + vertex 0.841921 2.0222 2.48123 + vertex 0.842814 2.02238 2.48574 + vertex 0.84265 2.02683 2.48071 + endloop + endfacet + facet normal -0.978215 0.138613 0.154539 + outer loop + vertex 0.84265 2.02683 2.48071 + vertex 0.842814 2.02238 2.48574 + vertex 0.843328 2.02754 2.48437 + endloop + endfacet + facet normal -0.905005 0.191291 0.379967 + outer loop + vertex 0.842814 2.02238 2.48574 + vertex 0.844371 2.02498 2.48814 + vertex 0.843328 2.02754 2.48437 + endloop + endfacet + facet normal -0.909732 0.219396 0.352496 + outer loop + vertex 0.844045 2.02114 2.48969 + vertex 0.844371 2.02498 2.48814 + vertex 0.842814 2.02238 2.48574 + endloop + endfacet + facet normal -0.907423 -0.336175 -0.252131 + outer loop + vertex 0.845 2.03 2.47512 + vertex 0.843181 2.035 2.475 + vertex 0.845 2.03009 2.475 + endloop + endfacet + facet normal -0.4564 -0.186942 -0.869915 + outer loop + vertex 0.845 2.03 2.47512 + vertex 0.842993 2.02702 2.47681 + vertex 0.843181 2.035 2.475 + endloop + endfacet + facet normal -0.963151 -0.0378417 -0.266287 + outer loop + vertex 0.842993 2.02702 2.47681 + vertex 0.842927 2.0318 2.47637 + vertex 0.843181 2.035 2.475 + endloop + endfacet + facet normal -0.995793 -0.0219945 -0.0889488 + outer loop + vertex 0.842993 2.02702 2.47681 + vertex 0.84265 2.02683 2.48071 + vertex 0.842927 2.0318 2.47637 + endloop + endfacet + facet normal -0.993967 0.0981553 0.0489451 + outer loop + vertex 0.842927 2.0318 2.47637 + vertex 0.84265 2.02683 2.48071 + vertex 0.843129 2.03182 2.48044 + endloop + endfacet + facet normal -0.905833 0.180445 0.383283 + outer loop + vertex 0.843809 2.03087 2.48394 + vertex 0.843328 2.02754 2.48437 + vertex 0.844463 2.02876 2.48647 + endloop + endfacet + facet normal -0.958017 0.168297 0.232119 + outer loop + vertex 0.843809 2.03087 2.48394 + vertex 0.843129 2.03182 2.48044 + vertex 0.843328 2.02754 2.48437 + endloop + endfacet + facet normal -0.981407 0.102938 0.162001 + outer loop + vertex 0.843129 2.03182 2.48044 + vertex 0.84265 2.02683 2.48071 + vertex 0.843328 2.02754 2.48437 + endloop + endfacet + facet normal -0.906109 0.188794 0.37858 + outer loop + vertex 0.844463 2.02876 2.48647 + vertex 0.843328 2.02754 2.48437 + vertex 0.844371 2.02498 2.48814 + endloop + endfacet + facet normal 0.416247 0.0689132 -0.906636 + outer loop + vertex 0.845 2.035 2.47318 + vertex 0.843538 2.0366 2.47263 + vertex 0.845 2.04 2.47356 + endloop + endfacet + facet normal -0.527864 -0.665563 -0.527622 + outer loop + vertex 0.843181 2.035 2.475 + vertex 0.843538 2.0366 2.47263 + vertex 0.845 2.035 2.47318 + endloop + endfacet + facet normal 0.990592 -0.0205565 0.135295 + outer loop + vertex 0.843181 2.035 2.475 + vertex 0.842927 2.0318 2.47637 + vertex 0.843538 2.0366 2.47263 + endloop + endfacet + facet normal -0.99488 0.0691887 -0.0736684 + outer loop + vertex 0.843538 2.0366 2.47263 + vertex 0.842927 2.0318 2.47637 + vertex 0.843296 2.03651 2.47582 + endloop + endfacet + facet normal -0.955237 0.17737 0.236774 + outer loop + vertex 0.843604 2.03573 2.47943 + vertex 0.843129 2.03182 2.48044 + vertex 0.843922 2.03374 2.4822 + endloop + endfacet + facet normal -0.981953 0.149335 0.11605 + outer loop + vertex 0.843604 2.03573 2.47943 + vertex 0.843296 2.03651 2.47582 + vertex 0.843129 2.03182 2.48044 + endloop + endfacet + facet normal -0.995274 0.0837788 0.0490945 + outer loop + vertex 0.843296 2.03651 2.47582 + vertex 0.842927 2.0318 2.47637 + vertex 0.843129 2.03182 2.48044 + endloop + endfacet + facet normal -0.955387 0.179398 0.234632 + outer loop + vertex 0.843922 2.03374 2.4822 + vertex 0.843129 2.03182 2.48044 + vertex 0.843809 2.03087 2.48394 + endloop + endfacet + facet normal 0.836551 -0.387417 -0.387417 + outer loop + vertex 0.845 2.0435 2.47 + vertex 0.844039 2.04138 2.47004 + vertex 0.845 2.045 2.4685 + endloop + endfacet + facet normal 0.838743 -0.388302 -0.381748 + outer loop + vertex 0.845 2.04 2.47356 + vertex 0.844039 2.04138 2.47004 + vertex 0.845 2.0435 2.47 + endloop + endfacet + facet normal 0.890161 -0.285295 -0.355274 + outer loop + vertex 0.845 2.04 2.47356 + vertex 0.843538 2.0366 2.47263 + vertex 0.844039 2.04138 2.47004 + endloop + endfacet + facet normal -0.994735 0.0587714 -0.0839585 + outer loop + vertex 0.843538 2.0366 2.47263 + vertex 0.843841 2.04098 2.4721 + vertex 0.844039 2.04138 2.47004 + endloop + endfacet + facet normal -0.96544 0.215908 0.145979 + outer loop + vertex 0.844077 2.04079 2.47465 + vertex 0.843296 2.03651 2.47582 + vertex 0.844009 2.03869 2.47731 + endloop + endfacet + facet normal -0.972898 0.206058 0.104923 + outer loop + vertex 0.844077 2.04079 2.47465 + vertex 0.843841 2.04098 2.4721 + vertex 0.843296 2.03651 2.47582 + endloop + endfacet + facet normal -0.995453 0.0600276 -0.0739566 + outer loop + vertex 0.843841 2.04098 2.4721 + vertex 0.843538 2.0366 2.47263 + vertex 0.843296 2.03651 2.47582 + endloop + endfacet + facet normal -0.965261 0.225921 0.131268 + outer loop + vertex 0.844009 2.03869 2.47731 + vertex 0.843296 2.03651 2.47582 + vertex 0.843604 2.03573 2.47943 + endloop + endfacet + facet normal -0.952731 0.137714 -0.270811 + outer loop + vertex 0.845 2.045 2.4685 + vertex 0.844039 2.04138 2.47004 + vertex 0.845 2.04795 2.47 + endloop + endfacet + facet normal -0.978313 0.18846 0.0859399 + outer loop + vertex 0.845 2.04795 2.47 + vertex 0.843841 2.04098 2.4721 + vertex 0.845 2.04567 2.475 + endloop + endfacet + facet normal -0.987341 0.144063 -0.0663613 + outer loop + vertex 0.844039 2.04138 2.47004 + vertex 0.843841 2.04098 2.4721 + vertex 0.845 2.04795 2.47 + endloop + endfacet + facet normal -0.978627 0.177736 0.103435 + outer loop + vertex 0.845 2.04567 2.475 + vertex 0.843841 2.04098 2.4721 + vertex 0.844077 2.04079 2.47465 + endloop + endfacet + facet normal -0.871851 -0.111315 -0.476953 + outer loop + vertex 0.85 0.967343 2.47 + vertex 0.849328 0.971178 2.47033 + vertex 0.85 0.97 2.46938 + endloop + endfacet + facet normal -0.965987 -0.184976 0.180703 + outer loop + vertex 0.85 0.967343 2.47 + vertex 0.85 0.97 2.47272 + vertex 0.849328 0.971178 2.47033 + endloop + endfacet + facet normal -0.678735 0.0278893 -0.733854 + outer loop + vertex 0.85 0.97 2.46938 + vertex 0.849535 0.975 2.47 + vertex 0.85 0.975 2.46957 + endloop + endfacet + facet normal -0.82054 -0.00542774 -0.571563 + outer loop + vertex 0.849328 0.971178 2.47033 + vertex 0.849535 0.975 2.47 + vertex 0.85 0.97 2.46938 + endloop + endfacet + facet normal -0.96674 -0.176504 0.185096 + outer loop + vertex 0.85 0.972391 2.475 + vertex 0.849328 0.971178 2.47033 + vertex 0.85 0.97 2.47272 + endloop + endfacet + facet normal -0.9455 -0.25503 0.202457 + outer loop + vertex 0.85 0.972391 2.475 + vertex 0.8488 0.974893 2.47255 + vertex 0.849328 0.971178 2.47033 + endloop + endfacet + facet normal -0.960754 0.0279338 -0.275993 + outer loop + vertex 0.8488 0.974893 2.47255 + vertex 0.849535 0.975 2.47 + vertex 0.849328 0.971178 2.47033 + endloop + endfacet + facet normal 0.721066 -0.276686 -0.635223 + outer loop + vertex 0.85 0.972391 2.475 + vertex 0.849417 0.97275 2.47418 + vertex 0.8488 0.974893 2.47255 + endloop + endfacet + facet normal -0.747342 0.401866 -0.529134 + outer loop + vertex 0.85 0.975892 2.47 + vertex 0.848669 0.98 2.475 + vertex 0.85 0.98 2.47312 + endloop + endfacet + facet normal -0.755018 0.393628 -0.524409 + outer loop + vertex 0.85 0.975892 2.47 + vertex 0.849535 0.975 2.47 + vertex 0.848669 0.98 2.475 + endloop + endfacet + facet normal -0.956592 0.105842 -0.27153 + outer loop + vertex 0.849535 0.975 2.47 + vertex 0.8488 0.974893 2.47255 + vertex 0.848669 0.98 2.475 + endloop + endfacet + facet normal -0.972145 -0.221523 0.0765646 + outer loop + vertex 0.848894 0.975401 2.47521 + vertex 0.8488 0.974893 2.47255 + vertex 0.849417 0.97275 2.47418 + endloop + endfacet + facet normal -0.978483 -0.193562 0.0714444 + outer loop + vertex 0.848894 0.975401 2.47521 + vertex 0.847987 0.980221 2.47585 + vertex 0.8488 0.974893 2.47255 + endloop + endfacet + facet normal -0.708539 0.290606 -0.643055 + outer loop + vertex 0.847987 0.980221 2.47585 + vertex 0.848669 0.98 2.475 + vertex 0.8488 0.974893 2.47255 + endloop + endfacet + facet normal -0.958795 -0.20643 0.195187 + outer loop + vertex 0.848894 0.975401 2.47521 + vertex 0.849094 0.977223 2.47811 + vertex 0.847987 0.980221 2.47585 + endloop + endfacet + facet normal -0.7867 -0.244818 -0.566716 + outer loop + vertex 0.848669 0.98 2.475 + vertex 0.847987 0.980221 2.47585 + vertex 0.847113 0.985 2.475 + endloop + endfacet + facet normal -0.97622 -0.195328 -0.0940315 + outer loop + vertex 0.847113 0.985 2.475 + vertex 0.847987 0.980221 2.47585 + vertex 0.846864 0.985614 2.47631 + endloop + endfacet + facet normal -0.959174 -0.217043 0.18132 + outer loop + vertex 0.848685 0.980403 2.47976 + vertex 0.847987 0.980221 2.47585 + vertex 0.849094 0.977223 2.47811 + endloop + endfacet + facet normal -0.954984 -0.234732 0.181399 + outer loop + vertex 0.848685 0.980403 2.47976 + vertex 0.847564 0.984978 2.47978 + vertex 0.847987 0.980221 2.47585 + endloop + endfacet + facet normal -0.964361 -0.214132 0.155419 + outer loop + vertex 0.847564 0.984978 2.47978 + vertex 0.846864 0.985614 2.47631 + vertex 0.847987 0.980221 2.47585 + endloop + endfacet + facet normal -0.93892 -0.23106 0.255029 + outer loop + vertex 0.848685 0.980403 2.47976 + vertex 0.848999 0.982391 2.48272 + vertex 0.847564 0.984978 2.47978 + endloop + endfacet + facet normal -0.984106 -0.120259 -0.130668 + outer loop + vertex 0.847113 0.985 2.475 + vertex 0.846864 0.985614 2.47631 + vertex 0.846502 0.99 2.475 + endloop + endfacet + facet normal -0.995711 -0.0615177 0.0691044 + outer loop + vertex 0.846502 0.99 2.475 + vertex 0.846864 0.985614 2.47631 + vertex 0.846849 0.99 2.48 + endloop + endfacet + facet normal -0.974546 -0.146241 0.169923 + outer loop + vertex 0.846864 0.985614 2.47631 + vertex 0.847564 0.984978 2.47978 + vertex 0.846849 0.99 2.48 + endloop + endfacet + facet normal -0.989932 -0.141258 0.00903325 + outer loop + vertex 0.846849 0.99 2.48 + vertex 0.847564 0.984978 2.47978 + vertex 0.846772 0.99068 2.48224 + endloop + endfacet + facet normal -0.933275 -0.243601 0.263926 + outer loop + vertex 0.847564 0.984978 2.47978 + vertex 0.848501 0.986454 2.48445 + vertex 0.846772 0.99068 2.48224 + endloop + endfacet + facet normal -0.938931 -0.225982 0.2595 + outer loop + vertex 0.848999 0.982391 2.48272 + vertex 0.848501 0.986454 2.48445 + vertex 0.847564 0.984978 2.47978 + endloop + endfacet + facet normal -0.970393 -0.238335 0.0391568 + outer loop + vertex 0.846849 0.99 2.48 + vertex 0.846772 0.99068 2.48224 + vertex 0.845621 0.995 2.48 + endloop + endfacet + facet normal -0.968055 -0.250294 0.0149078 + outer loop + vertex 0.845621 0.995 2.48 + vertex 0.846772 0.99068 2.48224 + vertex 0.84581 0.994408 2.48235 + endloop + endfacet + facet normal -0.931842 -0.237616 0.274244 + outer loop + vertex 0.848048 0.99027 2.48622 + vertex 0.846772 0.99068 2.48224 + vertex 0.848501 0.986454 2.48445 + endloop + endfacet + facet normal -0.929984 -0.246465 0.272736 + outer loop + vertex 0.848048 0.99027 2.48622 + vertex 0.8469 0.994614 2.48623 + vertex 0.846772 0.99068 2.48224 + endloop + endfacet + facet normal -0.929314 -0.247682 0.273914 + outer loop + vertex 0.8469 0.994614 2.48623 + vertex 0.84581 0.994408 2.48235 + vertex 0.846772 0.99068 2.48224 + endloop + endfacet + facet normal -0.894476 -0.237407 0.378881 + outer loop + vertex 0.848048 0.99027 2.48622 + vertex 0.848672 0.991916 2.48872 + vertex 0.8469 0.994614 2.48623 + endloop + endfacet + facet normal 0.574251 0.102409 -0.812249 + outer loop + vertex 0.844389 0.998383 2.47956 + vertex 0.845 0.998482 2.48 + vertex 0.845621 0.995 2.48 + endloop + endfacet + facet normal -0.934851 -0.320216 0.153345 + outer loop + vertex 0.844389 0.998383 2.47956 + vertex 0.845621 0.995 2.48 + vertex 0.845012 0.998201 2.48297 + endloop + endfacet + facet normal -0.977374 -0.209935 0.0258335 + outer loop + vertex 0.845012 0.998201 2.48297 + vertex 0.845621 0.995 2.48 + vertex 0.84581 0.994408 2.48235 + endloop + endfacet + facet normal -0.931029 -0.241011 0.274041 + outer loop + vertex 0.84581 0.994408 2.48235 + vertex 0.8469 0.994614 2.48623 + vertex 0.845012 0.998201 2.48297 + endloop + endfacet + facet normal -0.931599 -0.254581 0.259444 + outer loop + vertex 0.845012 0.998201 2.48297 + vertex 0.8469 0.994614 2.48623 + vertex 0.845999 0.998522 2.48683 + endloop + endfacet + facet normal -0.884938 -0.187224 0.426417 + outer loop + vertex 0.848617 0.994795 2.48987 + vertex 0.8469 0.994614 2.48623 + vertex 0.848672 0.991916 2.48872 + endloop + endfacet + facet normal -0.874278 -0.23663 0.423845 + outer loop + vertex 0.848617 0.994795 2.48987 + vertex 0.847567 0.998989 2.49005 + vertex 0.8469 0.994614 2.48623 + endloop + endfacet + facet normal -0.851008 -0.265638 0.453015 + outer loop + vertex 0.847567 0.998989 2.49005 + vertex 0.845999 0.998522 2.48683 + vertex 0.8469 0.994614 2.48623 + endloop + endfacet + facet normal -0.64946 -0.193471 0.735371 + outer loop + vertex 0.848617 0.994795 2.48987 + vertex 0.850119 0.996753 2.49172 + vertex 0.847567 0.998989 2.49005 + endloop + endfacet + facet normal -0.949755 -0.269753 0.158742 + outer loop + vertex 0.844389 0.998383 2.47956 + vertex 0.845012 0.998201 2.48297 + vertex 0.84383 1.00094 2.48055 + endloop + endfacet + facet normal -0.951224 -0.24475 0.187805 + outer loop + vertex 0.843953 1.00245 2.48315 + vertex 0.84383 1.00094 2.48055 + vertex 0.845012 0.998201 2.48297 + endloop + endfacet + facet normal -0.932474 -0.243318 0.267001 + outer loop + vertex 0.843953 1.00245 2.48315 + vertex 0.845012 0.998201 2.48297 + vertex 0.845145 1.00274 2.48758 + endloop + endfacet + facet normal -0.936751 -0.235238 0.259154 + outer loop + vertex 0.845145 1.00274 2.48758 + vertex 0.845012 0.998201 2.48297 + vertex 0.845999 0.998522 2.48683 + endloop + endfacet + facet normal -0.854845 -0.252963 0.453046 + outer loop + vertex 0.845999 0.998522 2.48683 + vertex 0.847567 0.998989 2.49005 + vertex 0.845145 1.00274 2.48758 + endloop + endfacet + facet normal -0.858807 -0.265229 0.438298 + outer loop + vertex 0.845145 1.00274 2.48758 + vertex 0.847567 0.998989 2.49005 + vertex 0.847166 1.00441 2.49255 + endloop + endfacet + facet normal -0.450031 -0.400566 0.798135 + outer loop + vertex 0.847567 0.998989 2.49005 + vertex 0.849833 1.00231 2.493 + vertex 0.847166 1.00441 2.49255 + endloop + endfacet + facet normal -0.653101 -0.201688 0.729918 + outer loop + vertex 0.850119 0.996753 2.49172 + vertex 0.849833 1.00231 2.493 + vertex 0.847567 0.998989 2.49005 + endloop + endfacet + facet normal -0.927618 -0.261325 0.266898 + outer loop + vertex 0.843953 1.00245 2.48315 + vertex 0.845145 1.00274 2.48758 + vertex 0.843536 1.00546 2.48465 + endloop + endfacet + facet normal -0.927246 -0.27582 0.253257 + outer loop + vertex 0.843819 1.00728 2.48767 + vertex 0.843536 1.00546 2.48465 + vertex 0.845145 1.00274 2.48758 + endloop + endfacet + facet normal -0.897641 -0.269071 0.349059 + outer loop + vertex 0.843819 1.00728 2.48767 + vertex 0.845145 1.00274 2.48758 + vertex 0.845147 1.00783 2.4915 + endloop + endfacet + facet normal -0.821949 -0.34782 0.451023 + outer loop + vertex 0.845147 1.00783 2.4915 + vertex 0.845145 1.00274 2.48758 + vertex 0.847166 1.00441 2.49255 + endloop + endfacet + facet normal -0.47198 -0.435221 0.766692 + outer loop + vertex 0.848794 1.00657 2.49477 + vertex 0.847166 1.00441 2.49255 + vertex 0.849833 1.00231 2.493 + endloop + endfacet + facet normal -0.527099 -0.384457 0.757865 + outer loop + vertex 0.848794 1.00657 2.49477 + vertex 0.847125 1.00971 2.49521 + vertex 0.847166 1.00441 2.49255 + endloop + endfacet + facet normal -0.776616 -0.287405 0.560595 + outer loop + vertex 0.847125 1.00971 2.49521 + vertex 0.845147 1.00783 2.4915 + vertex 0.847166 1.00441 2.49255 + endloop + endfacet + facet normal -0.203748 -0.239488 0.94928 + outer loop + vertex 0.848794 1.00657 2.49477 + vertex 0.849152 1.01007 2.49573 + vertex 0.847125 1.00971 2.49521 + endloop + endfacet + facet normal -0.899391 -0.263415 0.348867 + outer loop + vertex 0.843394 1.01123 2.48955 + vertex 0.843819 1.00728 2.48767 + vertex 0.845147 1.00783 2.4915 + endloop + endfacet + facet normal -0.8934 -0.244087 0.377171 + outer loop + vertex 0.844833 1.01293 2.49406 + vertex 0.843394 1.01123 2.48955 + vertex 0.845147 1.00783 2.4915 + endloop + endfacet + facet normal -0.751613 -0.33198 0.569971 + outer loop + vertex 0.845147 1.00783 2.4915 + vertex 0.847125 1.00971 2.49521 + vertex 0.844833 1.01293 2.49406 + endloop + endfacet + facet normal -0.702095 -0.263963 0.661352 + outer loop + vertex 0.844833 1.01293 2.49406 + vertex 0.847125 1.00971 2.49521 + vertex 0.846639 1.01433 2.49653 + endloop + endfacet + facet normal 0.00811784 -0.275399 0.961296 + outer loop + vertex 0.847125 1.00971 2.49521 + vertex 0.848454 1.01397 2.49642 + vertex 0.846639 1.01433 2.49653 + endloop + endfacet + facet normal -0.211425 -0.205245 0.955601 + outer loop + vertex 0.849152 1.01007 2.49573 + vertex 0.848454 1.01397 2.49642 + vertex 0.847125 1.00971 2.49521 + endloop + endfacet + facet normal -0.876643 -0.285349 0.387393 + outer loop + vertex 0.843394 1.01123 2.48955 + vertex 0.844833 1.01293 2.49406 + vertex 0.843004 1.01503 2.49147 + endloop + endfacet + facet normal -0.876301 -0.274792 0.395709 + outer loop + vertex 0.843664 1.01679 2.49415 + vertex 0.843004 1.01503 2.49147 + vertex 0.844833 1.01293 2.49406 + endloop + endfacet + facet normal -0.755329 -0.243215 0.608543 + outer loop + vertex 0.843664 1.01679 2.49415 + vertex 0.844833 1.01293 2.49406 + vertex 0.845276 1.01739 2.49639 + endloop + endfacet + facet normal -0.694361 -0.278123 0.663709 + outer loop + vertex 0.845276 1.01739 2.49639 + vertex 0.844833 1.01293 2.49406 + vertex 0.846639 1.01433 2.49653 + endloop + endfacet + facet normal -0.250543 -0.0665998 0.965812 + outer loop + vertex 0.846639 1.01433 2.49653 + vertex 0.847462 1.01882 2.49706 + vertex 0.845276 1.01739 2.49639 + endloop + endfacet + facet normal 0.0397996 -0.12273 0.991642 + outer loop + vertex 0.848454 1.01397 2.49642 + vertex 0.847462 1.01882 2.49706 + vertex 0.846639 1.01433 2.49653 + endloop + endfacet + facet normal 0.834715 0.273302 -0.478076 + outer loop + vertex 0.85 1.02416 2.485 + vertex 0.849725 1.025 2.485 + vertex 0.85 1.025 2.48548 + endloop + endfacet + facet normal -0.757609 -0.236455 0.608373 + outer loop + vertex 0.843664 1.01679 2.49415 + vertex 0.845276 1.01739 2.49639 + vertex 0.843661 1.02006 2.49542 + endloop + endfacet + facet normal -0.673326 -0.142718 0.72544 + outer loop + vertex 0.845276 1.01739 2.49639 + vertex 0.845476 1.02282 2.49764 + vertex 0.843661 1.02006 2.49542 + endloop + endfacet + facet normal -0.15135 -0.217076 0.96435 + outer loop + vertex 0.845276 1.01739 2.49639 + vertex 0.847462 1.01882 2.49706 + vertex 0.845476 1.02282 2.49764 + endloop + endfacet + facet normal 0.106373 -0.0929233 0.989975 + outer loop + vertex 0.847462 1.01882 2.49706 + vertex 0.847449 1.02262 2.49741 + vertex 0.845476 1.02282 2.49764 + endloop + endfacet + facet normal 0.865481 -0.0673355 0.496396 + outer loop + vertex 0.847645 1.02619 2.49719 + vertex 0.848436 1.02982 2.4963 + vertex 0.847392 1.02971 2.49811 + endloop + endfacet + facet normal 0.642634 -0.149839 0.751379 + outer loop + vertex 0.847645 1.02619 2.49719 + vertex 0.847392 1.02971 2.49811 + vertex 0.845927 1.02786 2.49899 + endloop + endfacet + facet normal 0.567058 -0.260101 0.781532 + outer loop + vertex 0.847645 1.02619 2.49719 + vertex 0.845927 1.02786 2.49899 + vertex 0.845476 1.02282 2.49764 + endloop + endfacet + facet normal 0.121567 0.0551283 0.991051 + outer loop + vertex 0.847645 1.02619 2.49719 + vertex 0.845476 1.02282 2.49764 + vertex 0.847449 1.02262 2.49741 + endloop + endfacet + facet normal 0.0630383 -0.263457 0.962609 + outer loop + vertex 0.844078 1.02676 2.49881 + vertex 0.845476 1.02282 2.49764 + vertex 0.845927 1.02786 2.49899 + endloop + endfacet + facet normal 0.123907 -0.359828 0.924754 + outer loop + vertex 0.845927 1.02786 2.49899 + vertex 0.844561 1.03005 2.50003 + vertex 0.844078 1.02676 2.49881 + endloop + endfacet + facet normal -0.960008 -0.258208 0.108229 + outer loop + vertex 0.85 1.0312 2.49 + vertex 0.848978 1.035 2.49 + vertex 0.84961 1.03211 2.48871 + endloop + endfacet + facet normal 0.865961 -0.0454376 0.498043 + outer loop + vertex 0.848436 1.02982 2.4963 + vertex 0.848047 1.03209 2.49719 + vertex 0.847392 1.02971 2.49811 + endloop + endfacet + facet normal 0.795161 0.0772756 0.601455 + outer loop + vertex 0.848047 1.03209 2.49719 + vertex 0.848183 1.03471 2.49667 + vertex 0.846498 1.03315 2.4991 + endloop + endfacet + facet normal 0.783385 0.0248734 0.621038 + outer loop + vertex 0.848047 1.03209 2.49719 + vertex 0.846498 1.03315 2.4991 + vertex 0.847392 1.02971 2.49811 + endloop + endfacet + facet normal 0.586629 -0.0794331 0.805951 + outer loop + vertex 0.847392 1.02971 2.49811 + vertex 0.846498 1.03315 2.4991 + vertex 0.845927 1.02786 2.49899 + endloop + endfacet + facet normal 0.525133 -0.0736452 0.847827 + outer loop + vertex 0.846498 1.03315 2.4991 + vertex 0.844561 1.03005 2.50003 + vertex 0.845927 1.02786 2.49899 + endloop + endfacet + facet normal 0.608661 -0.146288 0.779828 + outer loop + vertex 0.844109 1.03408 2.50114 + vertex 0.844561 1.03005 2.50003 + vertex 0.846498 1.03315 2.4991 + endloop + endfacet + facet normal -0.720908 0.0433992 -0.69167 + outer loop + vertex 0.848978 1.035 2.49 + vertex 0.849279 1.04 2.49 + vertex 0.84922 1.03514 2.48976 + endloop + endfacet + facet normal -0.74012 0.132918 -0.659208 + outer loop + vertex 0.84961 1.03211 2.48871 + vertex 0.848978 1.035 2.49 + vertex 0.84922 1.03514 2.48976 + endloop + endfacet + facet normal 0.911487 0.291661 0.290043 + outer loop + vertex 0.848764 1.03625 2.49481 + vertex 0.848606 1.03816 2.49338 + vertex 0.847607 1.03826 2.49643 + endloop + endfacet + facet normal 0.890376 0.173729 0.420771 + outer loop + vertex 0.848183 1.03471 2.49667 + vertex 0.848764 1.03625 2.49481 + vertex 0.847607 1.03826 2.49643 + endloop + endfacet + facet normal 0.756729 0.166631 0.632136 + outer loop + vertex 0.848183 1.03471 2.49667 + vertex 0.847607 1.03826 2.49643 + vertex 0.846498 1.03315 2.4991 + endloop + endfacet + facet normal 0.903854 0.0271784 0.426978 + outer loop + vertex 0.846498 1.03315 2.4991 + vertex 0.847607 1.03826 2.49643 + vertex 0.84563 1.03924 2.50055 + endloop + endfacet + facet normal 0.624393 -0.0955605 0.775243 + outer loop + vertex 0.84563 1.03924 2.50055 + vertex 0.844109 1.03408 2.50114 + vertex 0.846498 1.03315 2.4991 + endloop + endfacet + facet normal 0.77523 -0.158766 0.611402 + outer loop + vertex 0.843551 1.03844 2.50298 + vertex 0.844109 1.03408 2.50114 + vertex 0.84563 1.03924 2.50055 + endloop + endfacet + facet normal 0.938563 -0.0286512 0.343915 + outer loop + vertex 0.848797 1.03796 2.49115 + vertex 0.84922 1.03514 2.48976 + vertex 0.849279 1.04 2.49 + endloop + endfacet + facet normal 0.868057 0.0710202 0.491359 + outer loop + vertex 0.848797 1.03796 2.49115 + vertex 0.849279 1.04 2.49 + vertex 0.847845 1.04144 2.49232 + endloop + endfacet + facet normal 0.859775 0.0333616 0.509582 + outer loop + vertex 0.847845 1.04144 2.49232 + vertex 0.849279 1.04 2.49 + vertex 0.849085 1.045 2.49 + endloop + endfacet + facet normal 0.967817 0.244208 0.0607639 + outer loop + vertex 0.848606 1.03816 2.49338 + vertex 0.848797 1.03796 2.49115 + vertex 0.847845 1.04144 2.49232 + endloop + endfacet + facet normal 0.908005 0.303769 0.288532 + outer loop + vertex 0.848606 1.03816 2.49338 + vertex 0.847845 1.04144 2.49232 + vertex 0.847607 1.03826 2.49643 + endloop + endfacet + facet normal 0.961108 0.188338 0.20199 + outer loop + vertex 0.847607 1.03826 2.49643 + vertex 0.847845 1.04144 2.49232 + vertex 0.846589 1.04345 2.49643 + endloop + endfacet + facet normal 0.903219 0.176855 0.391046 + outer loop + vertex 0.847607 1.03826 2.49643 + vertex 0.846589 1.04345 2.49643 + vertex 0.84563 1.03924 2.50055 + endloop + endfacet + facet normal 0.972217 0.00750877 0.23396 + outer loop + vertex 0.846589 1.04345 2.49643 + vertex 0.845684 1.04444 2.50016 + vertex 0.84563 1.03924 2.50055 + endloop + endfacet + facet normal 0.759717 -0.209685 0.615518 + outer loop + vertex 0.843551 1.03844 2.50298 + vertex 0.844415 1.04274 2.50338 + vertex 0.843131 1.04123 2.50445 + endloop + endfacet + facet normal 0.775718 -0.210988 0.594766 + outer loop + vertex 0.843551 1.03844 2.50298 + vertex 0.84563 1.03924 2.50055 + vertex 0.844415 1.04274 2.50338 + endloop + endfacet + facet normal 0.926672 0.0185726 0.375412 + outer loop + vertex 0.84563 1.03924 2.50055 + vertex 0.845684 1.04444 2.50016 + vertex 0.844415 1.04274 2.50338 + endloop + endfacet + facet normal 0.778262 -0.254955 0.573853 + outer loop + vertex 0.844415 1.04274 2.50338 + vertex 0.843434 1.043 2.50482 + vertex 0.843131 1.04123 2.50445 + endloop + endfacet + facet normal -0.686314 -0.567518 0.454859 + outer loop + vertex 0.845541 1.04865 2.48921 + vertex 0.849085 1.045 2.49 + vertex 0.845 1.04994 2.49 + endloop + endfacet + facet normal 0.718473 0.695486 -0.00978569 + outer loop + vertex 0.845541 1.04865 2.48921 + vertex 0.846201 1.048 2.49145 + vertex 0.849085 1.045 2.49 + endloop + endfacet + facet normal 0.633715 0.256027 0.729969 + outer loop + vertex 0.846201 1.048 2.49145 + vertex 0.847845 1.04144 2.49232 + vertex 0.849085 1.045 2.49 + endloop + endfacet + facet normal 0.951515 0.260346 0.16383 + outer loop + vertex 0.847845 1.04144 2.49232 + vertex 0.846201 1.048 2.49145 + vertex 0.846589 1.04345 2.49643 + endloop + endfacet + facet normal 0.987995 0.144381 0.054948 + outer loop + vertex 0.846201 1.048 2.49145 + vertex 0.845861 1.04833 2.49669 + vertex 0.846589 1.04345 2.49643 + endloop + endfacet + facet normal 0.970637 0.134 0.199768 + outer loop + vertex 0.846589 1.04345 2.49643 + vertex 0.845861 1.04833 2.49669 + vertex 0.845684 1.04444 2.50016 + endloop + endfacet + facet normal 0.947812 0.187109 0.25815 + outer loop + vertex 0.845861 1.04833 2.49669 + vertex 0.84474 1.04777 2.50121 + vertex 0.845684 1.04444 2.50016 + endloop + endfacet + facet normal 0.632907 0.4074 0.658372 + outer loop + vertex 0.843602 1.04501 2.50402 + vertex 0.84474 1.04777 2.50121 + vertex 0.842504 1.04834 2.50301 + endloop + endfacet + facet normal 0.848743 0.161512 0.503537 + outer loop + vertex 0.843602 1.04501 2.50402 + vertex 0.844415 1.04274 2.50338 + vertex 0.84474 1.04777 2.50121 + endloop + endfacet + facet normal 0.899409 0.122235 0.419669 + outer loop + vertex 0.844415 1.04274 2.50338 + vertex 0.845684 1.04444 2.50016 + vertex 0.84474 1.04777 2.50121 + endloop + endfacet + facet normal 0.831418 0.146146 0.536083 + outer loop + vertex 0.844415 1.04274 2.50338 + vertex 0.843602 1.04501 2.50402 + vertex 0.843434 1.043 2.50482 + endloop + endfacet + facet normal 0.812538 -0.0612192 0.579684 + outer loop + vertex 0.845918 1.05221 2.4888 + vertex 0.845 1.05142 2.49 + vertex 0.845 1.05 2.48985 + endloop + endfacet + facet normal 0.854679 -0.113686 0.506556 + outer loop + vertex 0.845918 1.05221 2.4888 + vertex 0.845 1.05 2.48985 + vertex 0.848125 1.05364 2.48539 + endloop + endfacet + facet normal 0.223026 0.672411 0.705778 + outer loop + vertex 0.848125 1.05364 2.48539 + vertex 0.845 1.05 2.48985 + vertex 0.85 1.05 2.48827 + endloop + endfacet + facet normal 0.94718 0.244374 -0.207682 + outer loop + vertex 0.845 1.05142 2.49 + vertex 0.846201 1.048 2.49145 + vertex 0.845541 1.04865 2.48921 + endloop + endfacet + facet normal -0.515866 -0.481791 -0.70835 + outer loop + vertex 0.845 1.05142 2.49 + vertex 0.845918 1.05221 2.4888 + vertex 0.846201 1.048 2.49145 + endloop + endfacet + facet normal 0.992897 0.103573 0.058556 + outer loop + vertex 0.845918 1.05221 2.4888 + vertex 0.845535 1.05353 2.49296 + vertex 0.846201 1.048 2.49145 + endloop + endfacet + facet normal 0.992918 0.103773 0.0578305 + outer loop + vertex 0.846201 1.048 2.49145 + vertex 0.845535 1.05353 2.49296 + vertex 0.845861 1.04833 2.49669 + endloop + endfacet + facet normal 0.984928 0.137303 0.105191 + outer loop + vertex 0.845535 1.05353 2.49296 + vertex 0.845265 1.0519 2.49761 + vertex 0.845861 1.04833 2.49669 + endloop + endfacet + facet normal 0.963232 0.0963487 0.250802 + outer loop + vertex 0.845861 1.04833 2.49669 + vertex 0.845265 1.0519 2.49761 + vertex 0.84474 1.04777 2.50121 + endloop + endfacet + facet normal 0.939429 0.149632 0.308355 + outer loop + vertex 0.845265 1.0519 2.49761 + vertex 0.844133 1.05292 2.50056 + vertex 0.84474 1.04777 2.50121 + endloop + endfacet + facet normal 0.643404 0.169917 0.746431 + outer loop + vertex 0.844133 1.05292 2.50056 + vertex 0.842504 1.04834 2.50301 + vertex 0.84474 1.04777 2.50121 + endloop + endfacet + facet normal 0.825243 0.00800981 0.564722 + outer loop + vertex 0.842188 1.05435 2.50339 + vertex 0.842504 1.04834 2.50301 + vertex 0.844133 1.05292 2.50056 + endloop + endfacet + facet normal 0.86702 0.0149087 0.49805 + outer loop + vertex 0.848125 1.05364 2.48539 + vertex 0.848782 1.05913 2.48409 + vertex 0.846326 1.05661 2.48844 + endloop + endfacet + facet normal 0.845042 -0.0347242 0.533572 + outer loop + vertex 0.845918 1.05221 2.4888 + vertex 0.848125 1.05364 2.48539 + vertex 0.846326 1.05661 2.48844 + endloop + endfacet + facet normal 0.951322 0.285614 0.115806 + outer loop + vertex 0.845 1.05837 2.495 + vertex 0.846326 1.05661 2.48844 + vertex 0.845 1.06 2.49098 + endloop + endfacet + facet normal 0.981233 0.0278592 0.190801 + outer loop + vertex 0.845 1.05837 2.495 + vertex 0.845535 1.05353 2.49296 + vertex 0.846326 1.05661 2.48844 + endloop + endfacet + facet normal 0.989702 -0.0819641 0.117355 + outer loop + vertex 0.845535 1.05353 2.49296 + vertex 0.845918 1.05221 2.4888 + vertex 0.846326 1.05661 2.48844 + endloop + endfacet + facet normal -0.837539 -0.28866 0.4639 + outer loop + vertex 0.844745 1.05741 2.49394 + vertex 0.845535 1.05353 2.49296 + vertex 0.845 1.05837 2.495 + endloop + endfacet + facet normal 0.981059 0.187633 0.0481448 + outer loop + vertex 0.844745 1.05741 2.49394 + vertex 0.844782 1.05653 2.49662 + vertex 0.845535 1.05353 2.49296 + endloop + endfacet + facet normal 0.987061 0.124638 0.100879 + outer loop + vertex 0.844782 1.05653 2.49662 + vertex 0.845265 1.0519 2.49761 + vertex 0.845535 1.05353 2.49296 + endloop + endfacet + facet normal 0.938794 0.162769 0.303599 + outer loop + vertex 0.845265 1.0519 2.49761 + vertex 0.844782 1.05653 2.49662 + vertex 0.844133 1.05292 2.50056 + endloop + endfacet + facet normal 0.977368 0.0490917 0.205773 + outer loop + vertex 0.844782 1.05653 2.49662 + vertex 0.843905 1.05814 2.5004 + vertex 0.844133 1.05292 2.50056 + endloop + endfacet + facet normal 0.83467 0.0533898 0.548157 + outer loop + vertex 0.843905 1.05814 2.5004 + vertex 0.842188 1.05435 2.50339 + vertex 0.844133 1.05292 2.50056 + endloop + endfacet + facet normal 0.90249 -0.0751303 0.424108 + outer loop + vertex 0.842834 1.0603 2.50307 + vertex 0.842188 1.05435 2.50339 + vertex 0.843905 1.05814 2.5004 + endloop + endfacet + facet normal 0.835088 0.0305735 0.549266 + outer loop + vertex 0.848782 1.05913 2.48409 + vertex 0.848893 1.06468 2.48361 + vertex 0.846664 1.06168 2.48716 + endloop + endfacet + facet normal 0.849343 0.0745465 0.522551 + outer loop + vertex 0.846326 1.05661 2.48844 + vertex 0.848782 1.05913 2.48409 + vertex 0.846664 1.06168 2.48716 + endloop + endfacet + facet normal 0.908522 0.0437304 0.415543 + outer loop + vertex 0.846664 1.06168 2.48716 + vertex 0.845 1.06 2.49098 + vertex 0.846326 1.05661 2.48844 + endloop + endfacet + facet normal 0.927594 -0.102728 0.359188 + outer loop + vertex 0.845 1.065 2.49241 + vertex 0.845 1.06 2.49098 + vertex 0.846664 1.06168 2.48716 + endloop + endfacet + facet normal 0.993345 0.112755 0.0234927 + outer loop + vertex 0.844362 1.06056 2.495 + vertex 0.844782 1.05653 2.49662 + vertex 0.844745 1.05741 2.49394 + endloop + endfacet + facet normal 0.994281 0.106518 0.00771014 + outer loop + vertex 0.844249 1.06142 2.49774 + vertex 0.844782 1.05653 2.49662 + vertex 0.844362 1.06056 2.495 + endloop + endfacet + facet normal 0.977718 0.0604059 0.201045 + outer loop + vertex 0.844782 1.05653 2.49662 + vertex 0.844249 1.06142 2.49774 + vertex 0.843905 1.05814 2.5004 + endloop + endfacet + facet normal 0.98791 0.0208727 0.153618 + outer loop + vertex 0.844249 1.06142 2.49774 + vertex 0.843807 1.06228 2.50047 + vertex 0.843905 1.05814 2.5004 + endloop + endfacet + facet normal 0.932103 0.0161227 0.361834 + outer loop + vertex 0.843807 1.06228 2.50047 + vertex 0.842834 1.0603 2.50307 + vertex 0.843905 1.05814 2.5004 + endloop + endfacet + facet normal 0.926976 0.0340364 0.373572 + outer loop + vertex 0.843188 1.06446 2.50181 + vertex 0.842834 1.0603 2.50307 + vertex 0.843807 1.06228 2.50047 + endloop + endfacet + facet normal 0.858271 0.0275103 0.512459 + outer loop + vertex 0.848893 1.06468 2.48361 + vertex 0.848699 1.07022 2.48364 + vertex 0.846623 1.06706 2.48728 + endloop + endfacet + facet normal 0.84921 -0.0051252 0.528031 + outer loop + vertex 0.846664 1.06168 2.48716 + vertex 0.848893 1.06468 2.48361 + vertex 0.846623 1.06706 2.48728 + endloop + endfacet + facet normal 0.953301 0.000638412 0.302022 + outer loop + vertex 0.846623 1.06706 2.48728 + vertex 0.845 1.065 2.49241 + vertex 0.846664 1.06168 2.48716 + endloop + endfacet + facet normal 0.958561 -0.0643915 0.277515 + outer loop + vertex 0.845 1.07 2.49357 + vertex 0.845 1.065 2.49241 + vertex 0.846623 1.06706 2.48728 + endloop + endfacet + facet normal 0.993536 0.113383 0.00553031 + outer loop + vertex 0.844362 1.06056 2.495 + vertex 0.843926 1.06434 2.49607 + vertex 0.844249 1.06142 2.49774 + endloop + endfacet + facet normal 0.985461 0.117445 0.12277 + outer loop + vertex 0.844249 1.06142 2.49774 + vertex 0.843642 1.0654 2.49882 + vertex 0.843807 1.06228 2.50047 + endloop + endfacet + facet normal 0.989229 0.137919 0.049035 + outer loop + vertex 0.843926 1.06434 2.49607 + vertex 0.843642 1.0654 2.49882 + vertex 0.844249 1.06142 2.49774 + endloop + endfacet + facet normal 0.968448 0.155008 0.195143 + outer loop + vertex 0.843807 1.06228 2.50047 + vertex 0.843642 1.0654 2.49882 + vertex 0.843188 1.06446 2.50181 + endloop + endfacet + facet normal 0.878662 0.0104755 0.477329 + outer loop + vertex 0.848699 1.07022 2.48364 + vertex 0.8486 1.07545 2.4837 + vertex 0.846512 1.07236 2.48761 + endloop + endfacet + facet normal 0.873488 -0.0122708 0.486692 + outer loop + vertex 0.846623 1.06706 2.48728 + vertex 0.848699 1.07022 2.48364 + vertex 0.846512 1.07236 2.48761 + endloop + endfacet + facet normal 0.968782 0.0047397 0.247871 + outer loop + vertex 0.846512 1.07236 2.48761 + vertex 0.845 1.07 2.49357 + vertex 0.846623 1.06706 2.48728 + endloop + endfacet + facet normal 0.971228 -0.0246347 0.236876 + outer loop + vertex 0.845 1.075 2.49409 + vertex 0.845 1.07 2.49357 + vertex 0.846512 1.07236 2.48761 + endloop + endfacet + facet normal 0.866631 -0.00390369 0.498935 + outer loop + vertex 0.8486 1.07545 2.4837 + vertex 0.84864 1.08038 2.48367 + vertex 0.846502 1.07751 2.48736 + endloop + endfacet + facet normal 0.873403 0.0253838 0.486335 + outer loop + vertex 0.846512 1.07236 2.48761 + vertex 0.8486 1.07545 2.4837 + vertex 0.846502 1.07751 2.48736 + endloop + endfacet + facet normal 0.974858 0.0127279 0.222462 + outer loop + vertex 0.846502 1.07751 2.48736 + vertex 0.845 1.075 2.49409 + vertex 0.846512 1.07236 2.48761 + endloop + endfacet + facet normal 0.873477 0.358746 0.32915 + outer loop + vertex 0.844257 1.08012 2.49048 + vertex 0.845 1.075 2.49409 + vertex 0.846502 1.07751 2.48736 + endloop + endfacet + facet normal 0.841753 -0.00239559 0.539857 + outer loop + vertex 0.84864 1.08038 2.48367 + vertex 0.848642 1.08517 2.48369 + vertex 0.846567 1.08254 2.48691 + endloop + endfacet + facet normal 0.852534 0.0355646 0.521461 + outer loop + vertex 0.846502 1.07751 2.48736 + vertex 0.84864 1.08038 2.48367 + vertex 0.846567 1.08254 2.48691 + endloop + endfacet + facet normal 0.82623 0.0395172 0.561945 + outer loop + vertex 0.846567 1.08254 2.48691 + vertex 0.844257 1.08012 2.49048 + vertex 0.846502 1.07751 2.48736 + endloop + endfacet + facet normal 0.834387 0.0155629 0.550959 + outer loop + vertex 0.844358 1.08543 2.49018 + vertex 0.844257 1.08012 2.49048 + vertex 0.846567 1.08254 2.48691 + endloop + endfacet + facet normal 0.847273 0.0021438 0.531153 + outer loop + vertex 0.848642 1.08517 2.48369 + vertex 0.848495 1.09004 2.48391 + vertex 0.846559 1.08746 2.487 + endloop + endfacet + facet normal 0.843948 -0.00842189 0.536359 + outer loop + vertex 0.846567 1.08254 2.48691 + vertex 0.848642 1.08517 2.48369 + vertex 0.846559 1.08746 2.487 + endloop + endfacet + facet normal 0.824394 -0.00898908 0.565945 + outer loop + vertex 0.846559 1.08746 2.487 + vertex 0.844358 1.08543 2.49018 + vertex 0.846567 1.08254 2.48691 + endloop + endfacet + facet normal 0.840406 -0.0714867 0.537222 + outer loop + vertex 0.844398 1.09055 2.4908 + vertex 0.844358 1.08543 2.49018 + vertex 0.846559 1.08746 2.487 + endloop + endfacet + facet normal 0.902549 -0.0181092 0.430207 + outer loop + vertex 0.848495 1.09004 2.48391 + vertex 0.848426 1.09512 2.48426 + vertex 0.846666 1.09274 2.48786 + endloop + endfacet + facet normal 0.877532 -0.0935842 0.470297 + outer loop + vertex 0.846559 1.08746 2.487 + vertex 0.848495 1.09004 2.48391 + vertex 0.846666 1.09274 2.48786 + endloop + endfacet + facet normal 0.824071 -0.106418 0.556402 + outer loop + vertex 0.846666 1.09274 2.48786 + vertex 0.844398 1.09055 2.4908 + vertex 0.846559 1.08746 2.487 + endloop + endfacet + facet normal 0.845984 -0.395779 0.35731 + outer loop + vertex 0.845 1.095 2.4943 + vertex 0.844398 1.09055 2.4908 + vertex 0.846666 1.09274 2.48786 + endloop + endfacet + facet normal 0.999365 -0.0174274 0.0310891 + outer loop + vertex 0.848426 1.09512 2.48426 + vertex 0.848522 1.09934 2.48354 + vertex 0.848333 1.1 2.49 + endloop + endfacet + facet normal 0.921284 -0.288659 0.260598 + outer loop + vertex 0.846666 1.09274 2.48786 + vertex 0.848426 1.09512 2.48426 + vertex 0.848333 1.1 2.49 + endloop + endfacet + facet normal 0.891034 -0.304235 0.336897 + outer loop + vertex 0.848333 1.1 2.49 + vertex 0.845 1.095 2.4943 + vertex 0.846666 1.09274 2.48786 + endloop + endfacet + facet normal 0.744507 0.074283 0.663469 + outer loop + vertex 0.845 1.1 2.49374 + vertex 0.845 1.095 2.4943 + vertex 0.848333 1.1 2.49 + endloop + endfacet + facet normal 0.643002 -0.420522 -0.640085 + outer loop + vertex 0.846125 1.1 2.515 + vertex 0.843816 1.09701 2.51465 + vertex 0.845 1.1 2.51387 + endloop + endfacet + facet normal 0.787767 -0.613667 0.0532591 + outer loop + vertex 0.846114 1.10013 2.51665 + vertex 0.843816 1.09701 2.51465 + vertex 0.846125 1.1 2.515 + endloop + endfacet + facet normal 0.818307 -0.573013 -0.0450465 + outer loop + vertex 0.843457 1.09621 2.51821 + vertex 0.843816 1.09701 2.51465 + vertex 0.846114 1.10013 2.51665 + endloop + endfacet + facet normal 0.787708 -0.596157 -0.15528 + outer loop + vertex 0.84579 1.09874 2.52034 + vertex 0.843457 1.09621 2.51821 + vertex 0.846114 1.10013 2.51665 + endloop + endfacet + facet normal 0.699018 -0.710817 0.0781833 + outer loop + vertex 0.843378 1.09651 2.52166 + vertex 0.843457 1.09621 2.51821 + vertex 0.84579 1.09874 2.52034 + endloop + endfacet + facet normal 0.716198 -0.678259 0.164395 + outer loop + vertex 0.844977 1.09878 2.52406 + vertex 0.843378 1.09651 2.52166 + vertex 0.84579 1.09874 2.52034 + endloop + endfacet + facet normal 0.375099 -0.785026 0.492986 + outer loop + vertex 0.841693 1.09716 2.52398 + vertex 0.843378 1.09651 2.52166 + vertex 0.844977 1.09878 2.52406 + endloop + endfacet + facet normal 0.317479 -0.677193 0.66379 + outer loop + vertex 0.844977 1.09878 2.52406 + vertex 0.842339 1.10014 2.52671 + vertex 0.841693 1.09716 2.52398 + endloop + endfacet + facet normal 0.329822 0.189922 0.924742 + outer loop + vertex 0.849758 1.10191 2.46566 + vertex 0.85 1.10471 2.465 + vertex 0.849833 1.105 2.465 + endloop + endfacet + facet normal 0.999538 -0.0271919 -0.0135952 + outer loop + vertex 0.849901 1.105 2.47 + vertex 0.849758 1.10191 2.46566 + vertex 0.849833 1.105 2.465 + endloop + endfacet + facet normal 0.996396 -0.0811036 0.0248546 + outer loop + vertex 0.849623 1.10153 2.46982 + vertex 0.849758 1.10191 2.46566 + vertex 0.849901 1.105 2.47 + endloop + endfacet + facet normal 0.896837 -0.0946264 0.432121 + outer loop + vertex 0.848823 1.10531 2.47231 + vertex 0.849623 1.10153 2.46982 + vertex 0.849901 1.105 2.47 + endloop + endfacet + facet normal 0.983869 0.168234 0.0608196 + outer loop + vertex 0.849352 1.10126 2.47496 + vertex 0.849623 1.10153 2.46982 + vertex 0.848823 1.10531 2.47231 + endloop + endfacet + facet normal 0.993077 0.115465 -0.0215648 + outer loop + vertex 0.849026 1.105 2.48 + vertex 0.849352 1.10126 2.47496 + vertex 0.848823 1.10531 2.47231 + endloop + endfacet + facet normal 0.997431 -0.00879275 0.0710895 + outer loop + vertex 0.848994 1.10071 2.47992 + vertex 0.849352 1.10126 2.47496 + vertex 0.849026 1.105 2.48 + endloop + endfacet + facet normal 0.998697 -0.00843666 0.0503372 + outer loop + vertex 0.848774 1.105 2.485 + vertex 0.848994 1.10071 2.47992 + vertex 0.849026 1.105 2.48 + endloop + endfacet + facet normal 0.992231 -0.0704981 0.102506 + outer loop + vertex 0.848522 1.09934 2.48354 + vertex 0.848994 1.10071 2.47992 + vertex 0.848774 1.105 2.485 + endloop + endfacet + facet normal 0.997975 -0.0532979 0.0347257 + outer loop + vertex 0.848522 1.09934 2.48354 + vertex 0.848774 1.105 2.485 + vertex 0.848333 1.1 2.49 + endloop + endfacet + facet normal 0.950892 0.172878 0.256744 + outer loop + vertex 0.848333 1.1 2.49 + vertex 0.848774 1.105 2.485 + vertex 0.847424 1.105 2.49 + endloop + endfacet + facet normal 0.815138 -0.445254 -0.370539 + outer loop + vertex 0.85 1.105 2.51935 + vertex 0.848419 1.10216 2.51928 + vertex 0.846114 1.10013 2.51665 + endloop + endfacet + facet normal 0.792049 -0.358393 -0.494179 + outer loop + vertex 0.85 1.105 2.51935 + vertex 0.846114 1.10013 2.51665 + vertex 0.847286 1.105 2.515 + endloop + endfacet + facet normal 0.973802 -0.226113 0.0241566 + outer loop + vertex 0.847286 1.105 2.515 + vertex 0.846114 1.10013 2.51665 + vertex 0.846125 1.1 2.515 + endloop + endfacet + facet normal 0.775793 -0.624271 -0.0918195 + outer loop + vertex 0.848419 1.10216 2.51928 + vertex 0.848096 1.10125 2.52275 + vertex 0.84579 1.09874 2.52034 + endloop + endfacet + facet normal 0.754775 -0.63302 -0.17205 + outer loop + vertex 0.846114 1.10013 2.51665 + vertex 0.848419 1.10216 2.51928 + vertex 0.84579 1.09874 2.52034 + endloop + endfacet + facet normal 0.660572 -0.717565 0.220782 + outer loop + vertex 0.848096 1.10125 2.52275 + vertex 0.846935 1.10151 2.52706 + vertex 0.844977 1.09878 2.52406 + endloop + endfacet + facet normal 0.65167 -0.743316 0.151023 + outer loop + vertex 0.84579 1.09874 2.52034 + vertex 0.848096 1.10125 2.52275 + vertex 0.844977 1.09878 2.52406 + endloop + endfacet + facet normal 0.188407 -0.784917 0.590261 + outer loop + vertex 0.842339 1.10014 2.52671 + vertex 0.844977 1.09878 2.52406 + vertex 0.846935 1.10151 2.52706 + endloop + endfacet + facet normal 0.176671 -0.755906 0.630392 + outer loop + vertex 0.842339 1.10014 2.52671 + vertex 0.846935 1.10151 2.52706 + vertex 0.84362 1.10269 2.52941 + endloop + endfacet + facet normal 0.000655518 -0.892474 0.451099 + outer loop + vertex 0.84362 1.10269 2.52941 + vertex 0.846935 1.10151 2.52706 + vertex 0.846846 1.10312 2.53024 + endloop + endfacet + facet normal -0.084389 -0.717729 0.69119 + outer loop + vertex 0.846846 1.10312 2.53024 + vertex 0.844228 1.10485 2.53172 + vertex 0.84362 1.10269 2.52941 + endloop + endfacet + facet normal -0.071979 -0.708346 0.702185 + outer loop + vertex 0.847958 1.10502 2.53228 + vertex 0.844228 1.10485 2.53172 + vertex 0.846846 1.10312 2.53024 + endloop + endfacet + facet normal 0.892261 0.235558 0.385206 + outer loop + vertex 0.849901 1.105 2.47 + vertex 0.848581 1.11 2.47 + vertex 0.848823 1.10531 2.47231 + endloop + endfacet + facet normal 0.997658 0.0636931 0.0249403 + outer loop + vertex 0.848581 1.11 2.47 + vertex 0.848456 1.11 2.475 + vertex 0.848823 1.10531 2.47231 + endloop + endfacet + facet normal 0.995606 0.0908667 -0.0226318 + outer loop + vertex 0.848823 1.10531 2.47231 + vertex 0.848456 1.11 2.475 + vertex 0.849026 1.105 2.48 + endloop + endfacet + facet normal 0.992112 0.124809 0.0117084 + outer loop + vertex 0.848456 1.11 2.475 + vertex 0.848397 1.11 2.48 + vertex 0.849026 1.105 2.48 + endloop + endfacet + facet normal -0.194836 -0.791583 0.579168 + outer loop + vertex 0.848792 1.10706 2.53473 + vertex 0.846658 1.10836 2.53579 + vertex 0.84457 1.10763 2.53409 + endloop + endfacet + facet normal -0.198376 -0.719585 0.665465 + outer loop + vertex 0.848792 1.10706 2.53473 + vertex 0.84457 1.10763 2.53409 + vertex 0.847958 1.10502 2.53228 + endloop + endfacet + facet normal -0.0844063 -0.639662 0.764008 + outer loop + vertex 0.847958 1.10502 2.53228 + vertex 0.84457 1.10763 2.53409 + vertex 0.844228 1.10485 2.53172 + endloop + endfacet + facet normal -0.0723321 -0.698198 0.712241 + outer loop + vertex 0.848792 1.10706 2.53473 + vertex 0.848861 1.10973 2.53736 + vertex 0.846658 1.10836 2.53579 + endloop + endfacet + facet normal -0.37056 -0.597208 0.711356 + outer loop + vertex 0.84457 1.10763 2.53409 + vertex 0.846658 1.10836 2.53579 + vertex 0.844129 1.11039 2.53618 + endloop + endfacet + facet normal -0.37647 -0.612277 0.695261 + outer loop + vertex 0.848243 1.11253 2.53971 + vertex 0.845743 1.11486 2.5404 + vertex 0.843502 1.11367 2.53815 + endloop + endfacet + facet normal -0.37478 -0.643501 0.667418 + outer loop + vertex 0.848861 1.10973 2.53736 + vertex 0.848243 1.11253 2.53971 + vertex 0.843502 1.11367 2.53815 + endloop + endfacet + facet normal -0.274125 -0.533078 0.800427 + outer loop + vertex 0.848861 1.10973 2.53736 + vertex 0.843502 1.11367 2.53815 + vertex 0.844129 1.11039 2.53618 + endloop + endfacet + facet normal -0.27474 -0.49943 0.821637 + outer loop + vertex 0.848861 1.10973 2.53736 + vertex 0.844129 1.11039 2.53618 + vertex 0.846658 1.10836 2.53579 + endloop + endfacet + facet normal -0.34069 -0.585755 0.735406 + outer loop + vertex 0.848243 1.11253 2.53971 + vertex 0.849453 1.11444 2.54179 + vertex 0.845743 1.11486 2.5404 + endloop + endfacet + facet normal -0.438428 -0.539742 0.718651 + outer loop + vertex 0.843502 1.11367 2.53815 + vertex 0.845743 1.11486 2.5404 + vertex 0.842607 1.11678 2.53993 + endloop + endfacet + facet normal -0.42679 -0.51454 0.743706 + outer loop + vertex 0.845743 1.11486 2.5404 + vertex 0.844716 1.11797 2.54197 + vertex 0.842607 1.11678 2.53993 + endloop + endfacet + facet normal -0.35086 -0.510362 0.785129 + outer loop + vertex 0.845743 1.11486 2.5404 + vertex 0.849453 1.11444 2.54179 + vertex 0.844716 1.11797 2.54197 + endloop + endfacet + facet normal -0.399846 -0.572554 0.715755 + outer loop + vertex 0.849453 1.11444 2.54179 + vertex 0.849659 1.1174 2.54427 + vertex 0.844716 1.11797 2.54197 + endloop + endfacet + facet normal -0.45134 -0.562738 0.692545 + outer loop + vertex 0.84901 1.12031 2.54618 + vertex 0.846297 1.12265 2.54631 + vertex 0.844512 1.12176 2.54443 + endloop + endfacet + facet normal -0.451301 -0.557113 0.697103 + outer loop + vertex 0.84901 1.12031 2.54618 + vertex 0.844512 1.12176 2.54443 + vertex 0.849659 1.1174 2.54427 + endloop + endfacet + facet normal -0.410817 -0.511449 0.754751 + outer loop + vertex 0.849659 1.1174 2.54427 + vertex 0.844512 1.12176 2.54443 + vertex 0.844716 1.11797 2.54197 + endloop + endfacet + facet normal -0.426956 -0.536462 0.727954 + outer loop + vertex 0.84901 1.12031 2.54618 + vertex 0.848397 1.12357 2.54823 + vertex 0.846297 1.12265 2.54631 + endloop + endfacet + facet normal -0.493596 -0.507282 0.706419 + outer loop + vertex 0.844512 1.12176 2.54443 + vertex 0.846297 1.12265 2.54631 + vertex 0.843611 1.12519 2.54626 + endloop + endfacet + facet normal -0.513853 -0.495107 0.700588 + outer loop + vertex 0.847582 1.12671 2.55006 + vertex 0.845876 1.12927 2.55061 + vertex 0.843537 1.12845 2.54832 + endloop + endfacet + facet normal -0.516696 -0.528318 0.673725 + outer loop + vertex 0.848397 1.12357 2.54823 + vertex 0.847582 1.12671 2.55006 + vertex 0.843537 1.12845 2.54832 + endloop + endfacet + facet normal -0.46706 -0.480252 0.742438 + outer loop + vertex 0.848397 1.12357 2.54823 + vertex 0.843537 1.12845 2.54832 + vertex 0.843611 1.12519 2.54626 + endloop + endfacet + facet normal -0.466951 -0.47837 0.74372 + outer loop + vertex 0.848397 1.12357 2.54823 + vertex 0.843611 1.12519 2.54626 + vertex 0.846297 1.12265 2.54631 + endloop + endfacet + facet normal -0.474496 -0.477379 0.739569 + outer loop + vertex 0.847582 1.12671 2.55006 + vertex 0.849581 1.12789 2.55211 + vertex 0.845876 1.12927 2.55061 + endloop + endfacet + facet normal -0.544877 -0.441088 0.713127 + outer loop + vertex 0.843537 1.12845 2.54832 + vertex 0.845876 1.12927 2.55061 + vertex 0.84329 1.13156 2.55006 + endloop + endfacet + facet normal -0.526325 -0.412953 0.743271 + outer loop + vertex 0.845876 1.12927 2.55061 + vertex 0.845611 1.13206 2.55198 + vertex 0.84329 1.13156 2.55006 + endloop + endfacet + facet normal -0.468846 -0.423162 0.775318 + outer loop + vertex 0.845876 1.12927 2.55061 + vertex 0.849581 1.12789 2.55211 + vertex 0.845611 1.13206 2.55198 + endloop + endfacet + facet normal -0.513228 -0.467083 0.720021 + outer loop + vertex 0.849581 1.12789 2.55211 + vertex 0.849479 1.13174 2.55453 + vertex 0.845611 1.13206 2.55198 + endloop + endfacet + facet normal -0.581811 -0.37511 0.721656 + outer loop + vertex 0.848888 1.13537 2.55632 + vertex 0.846209 1.1396 2.55636 + vertex 0.844276 1.13707 2.55349 + endloop + endfacet + facet normal -0.582454 -0.435049 0.686644 + outer loop + vertex 0.848888 1.13537 2.55632 + vertex 0.844276 1.13707 2.55349 + vertex 0.849479 1.13174 2.55453 + endloop + endfacet + facet normal -0.532149 -0.371442 0.760821 + outer loop + vertex 0.849479 1.13174 2.55453 + vertex 0.844276 1.13707 2.55349 + vertex 0.845611 1.13206 2.55198 + endloop + endfacet + facet normal -0.582331 -0.375434 0.721068 + outer loop + vertex 0.848888 1.13537 2.55632 + vertex 0.849882 1.13789 2.55844 + vertex 0.846209 1.1396 2.55636 + endloop + endfacet + facet normal -0.627363 -0.32459 0.707854 + outer loop + vertex 0.843028 1.14216 2.55472 + vertex 0.844276 1.13707 2.55349 + vertex 0.846209 1.1396 2.55636 + endloop + endfacet + facet normal -0.631091 -0.334232 0.700009 + outer loop + vertex 0.844857 1.14244 2.5565 + vertex 0.843028 1.14216 2.55472 + vertex 0.846209 1.1396 2.55636 + endloop + endfacet + facet normal -0.59189 -0.31754 0.740834 + outer loop + vertex 0.846209 1.1396 2.55636 + vertex 0.847245 1.14277 2.55855 + vertex 0.844857 1.14244 2.5565 + endloop + endfacet + facet normal -0.575979 -0.328156 0.748707 + outer loop + vertex 0.849882 1.13789 2.55844 + vertex 0.847245 1.14277 2.55855 + vertex 0.846209 1.1396 2.55636 + endloop + endfacet + facet normal -0.681123 -0.0800708 0.727778 + outer loop + vertex 0.844576 1.18703 2.56786 + vertex 0.845327 1.18247 2.56806 + vertex 0.847373 1.18464 2.57021 + endloop + endfacet + facet normal -0.67244 -0.0601629 0.737702 + outer loop + vertex 0.847037 1.18932 2.57029 + vertex 0.844576 1.18703 2.56786 + vertex 0.847373 1.18464 2.57021 + endloop + endfacet + facet normal -0.677546 -0.0504601 0.733748 + outer loop + vertex 0.844258 1.19186 2.5679 + vertex 0.844576 1.18703 2.56786 + vertex 0.847037 1.18932 2.57029 + endloop + endfacet + facet normal -0.677765 -0.0509227 0.733513 + outer loop + vertex 0.846781 1.19431 2.5704 + vertex 0.844258 1.19186 2.5679 + vertex 0.847037 1.18932 2.57029 + endloop + endfacet + facet normal -0.669137 -0.0506535 0.741411 + outer loop + vertex 0.847037 1.18932 2.57029 + vertex 0.849586 1.1918 2.57276 + vertex 0.846781 1.19431 2.5704 + endloop + endfacet + facet normal -0.6673 -0.0539607 0.742831 + outer loop + vertex 0.850176 1.1864 2.5729 + vertex 0.849586 1.1918 2.57276 + vertex 0.847037 1.18932 2.57029 + endloop + endfacet + facet normal -0.646284 0.0533835 0.761228 + outer loop + vertex 0.841817 1.77622 2.57865 + vertex 0.842356 1.77084 2.57948 + vertex 0.844915 1.7736 2.58146 + endloop + endfacet + facet normal -0.651303 0.0435074 0.757569 + outer loop + vertex 0.845256 1.77845 2.58148 + vertex 0.841817 1.77622 2.57865 + vertex 0.844915 1.7736 2.58146 + endloop + endfacet + facet normal -0.648962 0.0433363 0.759586 + outer loop + vertex 0.844915 1.7736 2.58146 + vertex 0.84783 1.77584 2.58383 + vertex 0.845256 1.77845 2.58148 + endloop + endfacet + facet normal -0.650556 0.0470854 0.757997 + outer loop + vertex 0.847242 1.77042 2.58366 + vertex 0.84783 1.77584 2.58383 + vertex 0.844915 1.7736 2.58146 + endloop + endfacet + facet normal -0.652375 0.0465583 0.756465 + outer loop + vertex 0.843051 1.78096 2.57942 + vertex 0.841817 1.77622 2.57865 + vertex 0.845256 1.77845 2.58148 + endloop + endfacet + facet normal -0.637684 0.0682877 0.767265 + outer loop + vertex 0.845543 1.78332 2.58128 + vertex 0.843051 1.78096 2.57942 + vertex 0.845256 1.77845 2.58148 + endloop + endfacet + facet normal -0.645176 0.0684748 0.76096 + outer loop + vertex 0.845256 1.77845 2.58148 + vertex 0.848143 1.78086 2.58371 + vertex 0.845543 1.78332 2.58128 + endloop + endfacet + facet normal -0.640182 0.0578168 0.766045 + outer loop + vertex 0.84783 1.77584 2.58383 + vertex 0.848143 1.78086 2.58371 + vertex 0.845256 1.77845 2.58148 + endloop + endfacet + facet normal -0.594182 0.348431 0.724944 + outer loop + vertex 0.846955 1.8719 2.56085 + vertex 0.849191 1.87332 2.562 + vertex 0.848069 1.87603 2.55977 + endloop + endfacet + facet normal -0.605951 0.348982 0.714867 + outer loop + vertex 0.846955 1.8719 2.56085 + vertex 0.848069 1.87603 2.55977 + vertex 0.844244 1.87176 2.55862 + endloop + endfacet + facet normal -0.579021 0.314793 0.752091 + outer loop + vertex 0.844244 1.87176 2.55862 + vertex 0.848069 1.87603 2.55977 + vertex 0.844414 1.8767 2.55668 + endloop + endfacet + facet normal -0.582691 0.308466 0.751878 + outer loop + vertex 0.849191 1.87332 2.562 + vertex 0.846955 1.8719 2.56085 + vertex 0.848438 1.86986 2.56283 + endloop + endfacet + facet normal -0.547424 0.384138 0.743482 + outer loop + vertex 0.847037 1.88343 2.55539 + vertex 0.845035 1.88389 2.55368 + vertex 0.844386 1.88073 2.55483 + endloop + endfacet + facet normal -0.535324 0.368846 0.759856 + outer loop + vertex 0.844386 1.88073 2.55483 + vertex 0.848324 1.88126 2.55735 + vertex 0.847037 1.88343 2.55539 + endloop + endfacet + facet normal -0.537719 0.347972 0.767967 + outer loop + vertex 0.844386 1.88073 2.55483 + vertex 0.844414 1.8767 2.55668 + vertex 0.848324 1.88126 2.55735 + endloop + endfacet + facet normal -0.559632 0.370714 0.741204 + outer loop + vertex 0.844414 1.8767 2.55668 + vertex 0.848069 1.87603 2.55977 + vertex 0.848324 1.88126 2.55735 + endloop + endfacet + facet normal -0.524023 0.428902 0.735828 + outer loop + vertex 0.847037 1.88343 2.55539 + vertex 0.849606 1.88511 2.55624 + vertex 0.848388 1.88704 2.55425 + endloop + endfacet + facet normal -0.527915 0.429389 0.732756 + outer loop + vertex 0.847037 1.88343 2.55539 + vertex 0.848388 1.88704 2.55425 + vertex 0.845035 1.88389 2.55368 + endloop + endfacet + facet normal -0.527348 0.42863 0.733607 + outer loop + vertex 0.845035 1.88389 2.55368 + vertex 0.848388 1.88704 2.55425 + vertex 0.844749 1.88685 2.55174 + endloop + endfacet + facet normal -0.509181 0.390689 0.766875 + outer loop + vertex 0.849606 1.88511 2.55624 + vertex 0.847037 1.88343 2.55539 + vertex 0.848324 1.88126 2.55735 + endloop + endfacet + facet normal -0.524409 0.445118 0.725855 + outer loop + vertex 0.846284 1.89312 2.54906 + vertex 0.844348 1.89203 2.54833 + vertex 0.844521 1.8902 2.54958 + endloop + endfacet + facet normal -0.510703 0.439192 0.739116 + outer loop + vertex 0.844521 1.8902 2.54958 + vertex 0.84829 1.89127 2.55155 + vertex 0.846284 1.89312 2.54906 + endloop + endfacet + facet normal -0.510636 0.442238 0.737344 + outer loop + vertex 0.844521 1.8902 2.54958 + vertex 0.844749 1.88685 2.55174 + vertex 0.84829 1.89127 2.55155 + endloop + endfacet + facet normal -0.521957 0.450727 0.724159 + outer loop + vertex 0.844749 1.88685 2.55174 + vertex 0.848388 1.88704 2.55425 + vertex 0.84829 1.89127 2.55155 + endloop + endfacet + facet normal -0.519688 0.458597 0.720842 + outer loop + vertex 0.846794 1.89632 2.54741 + vertex 0.84264 1.8955 2.54493 + vertex 0.844461 1.89366 2.54742 + endloop + endfacet + facet normal -0.52417 0.444217 0.726579 + outer loop + vertex 0.844461 1.89366 2.54742 + vertex 0.844348 1.89203 2.54833 + vertex 0.846284 1.89312 2.54906 + endloop + endfacet + facet normal -0.517642 0.456813 0.723443 + outer loop + vertex 0.846794 1.89632 2.54741 + vertex 0.844461 1.89366 2.54742 + vertex 0.846284 1.89312 2.54906 + endloop + endfacet + facet normal -0.50438 0.458853 0.731474 + outer loop + vertex 0.846794 1.89632 2.54741 + vertex 0.846284 1.89312 2.54906 + vertex 0.849032 1.89522 2.54964 + endloop + endfacet + facet normal -0.512914 0.44582 0.733597 + outer loop + vertex 0.846794 1.89632 2.54741 + vertex 0.849032 1.89522 2.54964 + vertex 0.849062 1.89714 2.54849 + endloop + endfacet + facet normal -0.500033 0.450981 0.739312 + outer loop + vertex 0.849032 1.89522 2.54964 + vertex 0.846284 1.89312 2.54906 + vertex 0.84829 1.89127 2.55155 + endloop + endfacet + facet normal -0.510765 0.530651 0.676408 + outer loop + vertex 0.846794 1.89632 2.54741 + vertex 0.849031 1.89866 2.54726 + vertex 0.846626 1.90016 2.54426 + endloop + endfacet + facet normal -0.508345 0.531623 0.677468 + outer loop + vertex 0.846794 1.89632 2.54741 + vertex 0.846626 1.90016 2.54426 + vertex 0.84264 1.8955 2.54493 + endloop + endfacet + facet normal -0.450284 0.491779 0.74525 + outer loop + vertex 0.84264 1.8955 2.54493 + vertex 0.846626 1.90016 2.54426 + vertex 0.841933 1.89981 2.54166 + endloop + endfacet + facet normal -0.514829 0.534167 0.670534 + outer loop + vertex 0.849031 1.89866 2.54726 + vertex 0.846794 1.89632 2.54741 + vertex 0.849062 1.89714 2.54849 + endloop + endfacet + facet normal -0.210255 0.699871 0.682622 + outer loop + vertex 0.844624 1.90415 2.53997 + vertex 0.850287 1.90445 2.54141 + vertex 0.847341 1.90701 2.53787 + endloop + endfacet + facet normal -0.113422 0.655164 0.746924 + outer loop + vertex 0.844597 1.90689 2.53757 + vertex 0.844624 1.90415 2.53997 + vertex 0.847341 1.90701 2.53787 + endloop + endfacet + facet normal -0.436663 0.548456 0.713106 + outer loop + vertex 0.846626 1.90016 2.54426 + vertex 0.844624 1.90415 2.53997 + vertex 0.841933 1.89981 2.54166 + endloop + endfacet + facet normal -0.216894 0.662781 0.716714 + outer loop + vertex 0.850287 1.90445 2.54141 + vertex 0.844624 1.90415 2.53997 + vertex 0.846626 1.90016 2.54426 + endloop + endfacet + facet normal 0.0385392 0.812324 0.581932 + outer loop + vertex 0.849993 1.91119 2.53125 + vertex 0.847885 1.91284 2.52908 + vertex 0.845574 1.91128 2.53142 + endloop + endfacet + facet normal -0.040462 0.821112 0.569331 + outer loop + vertex 0.845574 1.91128 2.53142 + vertex 0.841537 1.91012 2.53279 + vertex 0.845575 1.90895 2.53478 + endloop + endfacet + facet normal 0.0382446 0.821187 0.569376 + outer loop + vertex 0.845574 1.91128 2.53142 + vertex 0.845575 1.90895 2.53478 + vertex 0.849993 1.91119 2.53125 + endloop + endfacet + facet normal 0.0292259 0.826847 0.561668 + outer loop + vertex 0.849993 1.91119 2.53125 + vertex 0.845575 1.90895 2.53478 + vertex 0.849928 1.9087 2.53491 + endloop + endfacet + facet normal -0.100766 0.816775 0.568088 + outer loop + vertex 0.847341 1.90701 2.53787 + vertex 0.845575 1.90895 2.53478 + vertex 0.844597 1.90689 2.53757 + endloop + endfacet + facet normal 0.0322233 0.855677 0.516506 + outer loop + vertex 0.849928 1.9087 2.53491 + vertex 0.845575 1.90895 2.53478 + vertex 0.847341 1.90701 2.53787 + endloop + endfacet + facet normal 0.992494 -0.116327 -0.0377196 + outer loop + vertex 0.847986 1.915 2.47 + vertex 0.848572 1.92 2.47 + vertex 0.848176 1.915 2.475 + endloop + endfacet + facet normal -0.192878 0.701417 0.686157 + outer loop + vertex 0.848572 1.92 2.47 + vertex 0.847694 1.91716 2.47266 + vertex 0.848176 1.915 2.475 + endloop + endfacet + facet normal 0.971125 0.237796 0.0192285 + outer loop + vertex 0.848176 1.915 2.475 + vertex 0.847694 1.91716 2.47266 + vertex 0.848077 1.915 2.48 + endloop + endfacet + facet normal 0.951062 0.306345 0.0404218 + outer loop + vertex 0.847694 1.91716 2.47266 + vertex 0.84742 1.9173 2.47799 + vertex 0.848077 1.915 2.48 + endloop + endfacet + facet normal 0.942125 0.328212 0.0683985 + outer loop + vertex 0.848077 1.915 2.48 + vertex 0.84742 1.9173 2.47799 + vertex 0.847714 1.915 2.485 + endloop + endfacet + facet normal 0.995092 0.0985175 -0.00930281 + outer loop + vertex 0.84742 1.9173 2.47799 + vertex 0.847219 1.92 2.485 + vertex 0.847714 1.915 2.485 + endloop + endfacet + facet normal 0.0762057 0.304816 0.949358 + outer loop + vertex 0.85 1.9187 2.525 + vertex 0.845 1.91995 2.525 + vertex 0.847607 1.91521 2.52631 + endloop + endfacet + facet normal 0.0592044 0.296532 0.953186 + outer loop + vertex 0.847607 1.91521 2.52631 + vertex 0.845 1.91995 2.525 + vertex 0.842921 1.91594 2.52638 + endloop + endfacet + facet normal 0.0904247 0.783933 0.614225 + outer loop + vertex 0.847885 1.91284 2.52908 + vertex 0.843968 1.91322 2.52918 + vertex 0.845574 1.91128 2.53142 + endloop + endfacet + facet normal 0.0889931 0.761648 0.64185 + outer loop + vertex 0.847885 1.91284 2.52908 + vertex 0.847607 1.91521 2.52631 + vertex 0.843968 1.91322 2.52918 + endloop + endfacet + facet normal 0.124042 0.734335 0.667357 + outer loop + vertex 0.847607 1.91521 2.52631 + vertex 0.842921 1.91594 2.52638 + vertex 0.843968 1.91322 2.52918 + endloop + endfacet + facet normal 0.00587684 0.757882 0.652366 + outer loop + vertex 0.845574 1.91128 2.53142 + vertex 0.843968 1.91322 2.52918 + vertex 0.841537 1.91012 2.53279 + endloop + endfacet + facet normal 0.995106 -0.061899 -0.077022 + outer loop + vertex 0.848185 1.92 2.465 + vertex 0.848496 1.925 2.465 + vertex 0.848572 1.92 2.47 + endloop + endfacet + facet normal -0.893078 0.311274 0.32484 + outer loop + vertex 0.848496 1.925 2.465 + vertex 0.848225 1.92155 2.46757 + vertex 0.848572 1.92 2.47 + endloop + endfacet + facet normal -0.589269 0.641479 0.491188 + outer loop + vertex 0.848572 1.92 2.47 + vertex 0.848225 1.92155 2.46757 + vertex 0.847694 1.91716 2.47266 + endloop + endfacet + facet normal 0.996847 -0.0585403 0.0535551 + outer loop + vertex 0.848225 1.92155 2.46757 + vertex 0.847909 1.92057 2.47239 + vertex 0.847694 1.91716 2.47266 + endloop + endfacet + facet normal 0.996885 -0.0586045 0.0527796 + outer loop + vertex 0.847694 1.91716 2.47266 + vertex 0.847909 1.92057 2.47239 + vertex 0.84742 1.9173 2.47799 + endloop + endfacet + facet normal 0.997133 -0.0299551 0.0694808 + outer loop + vertex 0.847909 1.92057 2.47239 + vertex 0.847516 1.9216 2.47847 + vertex 0.84742 1.9173 2.47799 + endloop + endfacet + facet normal 0.998887 -0.0266092 0.0389325 + outer loop + vertex 0.84742 1.9173 2.47799 + vertex 0.847516 1.9216 2.47847 + vertex 0.847219 1.92 2.485 + endloop + endfacet + facet normal 0.916484 0.376952 0.134034 + outer loop + vertex 0.847516 1.9216 2.47847 + vertex 0.846696 1.92152 2.4843 + vertex 0.847219 1.92 2.485 + endloop + endfacet + facet normal 0.930595 0.35707 0.0805818 + outer loop + vertex 0.847219 1.92 2.485 + vertex 0.846696 1.92152 2.4843 + vertex 0.846786 1.92 2.49 + endloop + endfacet + facet normal 0.986508 0.161396 0.0274481 + outer loop + vertex 0.846696 1.92152 2.4843 + vertex 0.845968 1.925 2.49 + vertex 0.846786 1.92 2.49 + endloop + endfacet + facet normal 0.0161684 0.999867 -0.0019986 + outer loop + vertex 0.845463 1.92 2.515 + vertex 0.842715 1.92005 2.51794 + vertex 0.846081 1.92 2.52 + endloop + endfacet + facet normal 0.686209 0.352966 0.636028 + outer loop + vertex 0.845 1.9209 2.515 + vertex 0.842715 1.92005 2.51794 + vertex 0.845463 1.92 2.515 + endloop + endfacet + facet normal 0.0131382 0.999909 0.00294646 + outer loop + vertex 0.846081 1.92 2.52 + vertex 0.842715 1.92005 2.51794 + vertex 0.845 1.92 2.52482 + endloop + endfacet + facet normal 0.966198 -0.209472 0.150275 + outer loop + vertex 0.85 1.92789 2.465 + vertex 0.848834 1.92467 2.468 + vertex 0.848225 1.92155 2.46757 + endloop + endfacet + facet normal 0.784464 -0.408249 -0.466851 + outer loop + vertex 0.848496 1.925 2.465 + vertex 0.85 1.92789 2.465 + vertex 0.848225 1.92155 2.46757 + endloop + endfacet + facet normal 0.984105 -0.171071 0.0476679 + outer loop + vertex 0.848834 1.92467 2.468 + vertex 0.848579 1.92464 2.47315 + vertex 0.847909 1.92057 2.47239 + endloop + endfacet + facet normal 0.980555 -0.194669 0.0248274 + outer loop + vertex 0.848225 1.92155 2.46757 + vertex 0.848834 1.92467 2.468 + vertex 0.847909 1.92057 2.47239 + endloop + endfacet + facet normal 0.983985 -0.128702 0.123327 + outer loop + vertex 0.848579 1.92464 2.47315 + vertex 0.848222 1.92571 2.47712 + vertex 0.847516 1.9216 2.47847 + endloop + endfacet + facet normal 0.979386 -0.178951 0.0936994 + outer loop + vertex 0.847909 1.92057 2.47239 + vertex 0.848579 1.92464 2.47315 + vertex 0.847516 1.9216 2.47847 + endloop + endfacet + facet normal 0.966403 -0.102708 0.23562 + outer loop + vertex 0.848222 1.92571 2.47712 + vertex 0.848356 1.92927 2.47812 + vertex 0.847 1.92534 2.48197 + endloop + endfacet + facet normal 0.967467 -0.0886608 0.236953 + outer loop + vertex 0.848222 1.92571 2.47712 + vertex 0.847 1.92534 2.48197 + vertex 0.847516 1.9216 2.47847 + endloop + endfacet + facet normal 0.990205 0.00584784 0.139496 + outer loop + vertex 0.847516 1.9216 2.47847 + vertex 0.847 1.92534 2.48197 + vertex 0.846696 1.92152 2.4843 + endloop + endfacet + facet normal 0.991842 -0.00160383 0.127465 + outer loop + vertex 0.846696 1.92152 2.4843 + vertex 0.847 1.92534 2.48197 + vertex 0.845968 1.925 2.49 + endloop + endfacet + facet normal 0.904082 0.405984 0.133467 + outer loop + vertex 0.847 1.92534 2.48197 + vertex 0.845547 1.92712 2.48641 + vertex 0.845968 1.925 2.49 + endloop + endfacet + facet normal 0.717825 0.633169 0.289526 + outer loop + vertex 0.845547 1.92712 2.48641 + vertex 0.845 1.925 2.4924 + vertex 0.845968 1.925 2.49 + endloop + endfacet + facet normal 0.99389 0.037203 0.103916 + outer loop + vertex 0.845 1.93 2.49061 + vertex 0.845 1.925 2.4924 + vertex 0.845547 1.92712 2.48641 + endloop + endfacet + facet normal 0.935349 -0.0641564 0.34786 + outer loop + vertex 0.848356 1.92927 2.47812 + vertex 0.848498 1.93381 2.47858 + vertex 0.846986 1.93016 2.48197 + endloop + endfacet + facet normal 0.942301 0.00277815 0.334756 + outer loop + vertex 0.847 1.92534 2.48197 + vertex 0.848356 1.92927 2.47812 + vertex 0.846986 1.93016 2.48197 + endloop + endfacet + facet normal 0.950742 0.00280441 0.309972 + outer loop + vertex 0.847 1.92534 2.48197 + vertex 0.846986 1.93016 2.48197 + vertex 0.845547 1.92712 2.48641 + endloop + endfacet + facet normal 0.90455 0.152964 0.397984 + outer loop + vertex 0.846986 1.93016 2.48197 + vertex 0.845176 1.93153 2.48556 + vertex 0.845547 1.92712 2.48641 + endloop + endfacet + facet normal 0.993374 0.0956776 0.0636645 + outer loop + vertex 0.845176 1.93153 2.48556 + vertex 0.845 1.93 2.49061 + vertex 0.845547 1.92712 2.48641 + endloop + endfacet + facet normal 0.663546 0.709298 0.237913 + outer loop + vertex 0.842441 1.93295 2.48896 + vertex 0.845 1.93 2.49061 + vertex 0.845176 1.93153 2.48556 + endloop + endfacet + facet normal 0.91463 -0.0393416 0.402372 + outer loop + vertex 0.848498 1.93381 2.47858 + vertex 0.848625 1.93869 2.47877 + vertex 0.847025 1.93508 2.48205 + endloop + endfacet + facet normal 0.918709 -0.013606 0.3947 + outer loop + vertex 0.846986 1.93016 2.48197 + vertex 0.848498 1.93381 2.47858 + vertex 0.847025 1.93508 2.48205 + endloop + endfacet + facet normal 0.890593 -0.0143246 0.454576 + outer loop + vertex 0.846986 1.93016 2.48197 + vertex 0.847025 1.93508 2.48205 + vertex 0.845176 1.93153 2.48556 + endloop + endfacet + facet normal 0.847122 0.0785817 0.525556 + outer loop + vertex 0.847025 1.93508 2.48205 + vertex 0.844923 1.9366 2.48521 + vertex 0.845176 1.93153 2.48556 + endloop + endfacet + facet normal 0.792445 0.0813197 0.604498 + outer loop + vertex 0.844923 1.9366 2.48521 + vertex 0.842441 1.93295 2.48896 + vertex 0.845176 1.93153 2.48556 + endloop + endfacet + facet normal 0.79104 0.0838107 0.605997 + outer loop + vertex 0.842462 1.93866 2.48814 + vertex 0.842441 1.93295 2.48896 + vertex 0.844923 1.9366 2.48521 + endloop + endfacet + facet normal 0.900683 -0.0334277 0.43319 + outer loop + vertex 0.848625 1.93869 2.47877 + vertex 0.848772 1.9437 2.47885 + vertex 0.847078 1.94021 2.4821 + endloop + endfacet + facet normal 0.904646 -0.0134899 0.425951 + outer loop + vertex 0.847025 1.93508 2.48205 + vertex 0.848625 1.93869 2.47877 + vertex 0.847078 1.94021 2.4821 + endloop + endfacet + facet normal 0.829371 -0.014015 0.558523 + outer loop + vertex 0.847025 1.93508 2.48205 + vertex 0.847078 1.94021 2.4821 + vertex 0.844923 1.9366 2.48521 + endloop + endfacet + facet normal 0.81907 0.00522069 0.57367 + outer loop + vertex 0.847078 1.94021 2.4821 + vertex 0.844889 1.94209 2.48521 + vertex 0.844923 1.9366 2.48521 + endloop + endfacet + facet normal 0.767141 0.0048897 0.64146 + outer loop + vertex 0.844889 1.94209 2.48521 + vertex 0.842462 1.93866 2.48814 + vertex 0.844923 1.9366 2.48521 + endloop + endfacet + facet normal 0.798299 -0.0526012 0.59996 + outer loop + vertex 0.842113 1.94493 2.48915 + vertex 0.842462 1.93866 2.48814 + vertex 0.844889 1.94209 2.48521 + endloop + endfacet + facet normal 0.885832 -0.0382047 0.46243 + outer loop + vertex 0.848772 1.9437 2.47885 + vertex 0.848948 1.94865 2.47892 + vertex 0.847147 1.94537 2.4821 + endloop + endfacet + facet normal 0.891982 -0.0117591 0.451918 + outer loop + vertex 0.847078 1.94021 2.4821 + vertex 0.848772 1.9437 2.47885 + vertex 0.847147 1.94537 2.4821 + endloop + endfacet + facet normal 0.814473 -0.0107141 0.580103 + outer loop + vertex 0.847078 1.94021 2.4821 + vertex 0.847147 1.94537 2.4821 + vertex 0.844889 1.94209 2.48521 + endloop + endfacet + facet normal 0.817483 -0.016966 0.575703 + outer loop + vertex 0.847147 1.94537 2.4821 + vertex 0.845016 1.94733 2.48518 + vertex 0.844889 1.94209 2.48521 + endloop + endfacet + facet normal 0.811798 -0.0167874 0.583697 + outer loop + vertex 0.845016 1.94733 2.48518 + vertex 0.842113 1.94493 2.48915 + vertex 0.844889 1.94209 2.48521 + endloop + endfacet + facet normal 0.832138 -0.106668 0.544214 + outer loop + vertex 0.843212 1.94957 2.48838 + vertex 0.842113 1.94493 2.48915 + vertex 0.845016 1.94733 2.48518 + endloop + endfacet + facet normal 0.87084 -0.0495487 0.489063 + outer loop + vertex 0.848948 1.94865 2.47892 + vertex 0.849135 1.95338 2.47907 + vertex 0.847269 1.95037 2.48208 + endloop + endfacet + facet normal 0.878599 -0.020004 0.477142 + outer loop + vertex 0.847147 1.94537 2.4821 + vertex 0.848948 1.94865 2.47892 + vertex 0.847269 1.95037 2.48208 + endloop + endfacet + facet normal 0.817093 -0.0181996 0.576218 + outer loop + vertex 0.847147 1.94537 2.4821 + vertex 0.847269 1.95037 2.48208 + vertex 0.845016 1.94733 2.48518 + endloop + endfacet + facet normal 0.842762 -0.0822936 0.531959 + outer loop + vertex 0.847269 1.95037 2.48208 + vertex 0.845407 1.95224 2.48532 + vertex 0.845016 1.94733 2.48518 + endloop + endfacet + facet normal 0.842232 -0.0822752 0.532801 + outer loop + vertex 0.845407 1.95224 2.48532 + vertex 0.843212 1.94957 2.48838 + vertex 0.845016 1.94733 2.48518 + endloop + endfacet + facet normal 0.872257 -0.406211 0.272324 + outer loop + vertex 0.845 1.955 2.49075 + vertex 0.843212 1.94957 2.48838 + vertex 0.845407 1.95224 2.48532 + endloop + endfacet + facet normal 0.856999 -0.0471242 0.513159 + outer loop + vertex 0.849135 1.95338 2.47907 + vertex 0.849353 1.95793 2.47912 + vertex 0.84741 1.95514 2.48211 + endloop + endfacet + facet normal 0.862503 -0.0280924 0.505271 + outer loop + vertex 0.847269 1.95037 2.48208 + vertex 0.849135 1.95338 2.47907 + vertex 0.84741 1.95514 2.48211 + endloop + endfacet + facet normal 0.859509 -0.0280301 0.510352 + outer loop + vertex 0.847269 1.95037 2.48208 + vertex 0.84741 1.95514 2.48211 + vertex 0.845407 1.95224 2.48532 + endloop + endfacet + facet normal 0.876889 -0.0803445 0.473931 + outer loop + vertex 0.84741 1.95514 2.48211 + vertex 0.845684 1.95692 2.48561 + vertex 0.845407 1.95224 2.48532 + endloop + endfacet + facet normal 0.992076 -0.065009 0.107517 + outer loop + vertex 0.845684 1.95692 2.48561 + vertex 0.845 1.955 2.49075 + vertex 0.845407 1.95224 2.48532 + endloop + endfacet + facet normal 0.991213 0.00158939 0.132269 + outer loop + vertex 0.845 1.96 2.49069 + vertex 0.845 1.955 2.49075 + vertex 0.845684 1.95692 2.48561 + endloop + endfacet + facet normal 0.842126 -0.0311006 0.538382 + outer loop + vertex 0.849353 1.95793 2.47912 + vertex 0.849392 1.96277 2.47934 + vertex 0.847389 1.95984 2.4823 + endloop + endfacet + facet normal 0.845919 -0.0182353 0.532999 + outer loop + vertex 0.84741 1.95514 2.48211 + vertex 0.849353 1.95793 2.47912 + vertex 0.847389 1.95984 2.4823 + endloop + endfacet + facet normal 0.893601 -0.0145692 0.448627 + outer loop + vertex 0.84741 1.95514 2.48211 + vertex 0.847389 1.95984 2.4823 + vertex 0.845684 1.95692 2.48561 + endloop + endfacet + facet normal 0.899608 -0.032958 0.435452 + outer loop + vertex 0.847389 1.95984 2.4823 + vertex 0.845595 1.96166 2.48615 + vertex 0.845684 1.95692 2.48561 + endloop + endfacet + facet normal 0.991362 0.00354752 0.131103 + outer loop + vertex 0.845595 1.96166 2.48615 + vertex 0.845 1.96 2.49069 + vertex 0.845684 1.95692 2.48561 + endloop + endfacet + facet normal 0.991033 0.00959598 0.133273 + outer loop + vertex 0.845 1.965 2.49033 + vertex 0.845 1.96 2.49069 + vertex 0.845595 1.96166 2.48615 + endloop + endfacet + facet normal 0.860413 -0.00516374 0.509572 + outer loop + vertex 0.849392 1.96277 2.47934 + vertex 0.849279 1.9678 2.47958 + vertex 0.846866 1.96541 2.48363 + endloop + endfacet + facet normal 0.848216 -0.0461628 0.527636 + outer loop + vertex 0.847389 1.95984 2.4823 + vertex 0.849392 1.96277 2.47934 + vertex 0.846866 1.96541 2.48363 + endloop + endfacet + facet normal 0.961958 0.0387805 0.270432 + outer loop + vertex 0.845 1.96728 2.49 + vertex 0.846866 1.96541 2.48363 + vertex 0.845 1.97 2.48961 + endloop + endfacet + facet normal 0.944209 -0.112354 0.309591 + outer loop + vertex 0.845 1.96728 2.49 + vertex 0.845595 1.96166 2.48615 + vertex 0.846866 1.96541 2.48363 + endloop + endfacet + facet normal 0.902794 -0.0176612 0.42971 + outer loop + vertex 0.845595 1.96166 2.48615 + vertex 0.847389 1.95984 2.4823 + vertex 0.846866 1.96541 2.48363 + endloop + endfacet + facet normal 0.991806 0.0182987 0.126438 + outer loop + vertex 0.845595 1.96166 2.48615 + vertex 0.845 1.96728 2.49 + vertex 0.845 1.965 2.49033 + endloop + endfacet + facet normal 0.850614 -0.0116271 0.525662 + outer loop + vertex 0.849279 1.9678 2.47958 + vertex 0.849287 1.97283 2.47968 + vertex 0.846949 1.97089 2.48342 + endloop + endfacet + facet normal 0.857279 0.00687259 0.514807 + outer loop + vertex 0.846866 1.96541 2.48363 + vertex 0.849279 1.9678 2.47958 + vertex 0.846949 1.97089 2.48342 + endloop + endfacet + facet normal 0.95397 -0.0028461 0.299889 + outer loop + vertex 0.846949 1.97089 2.48342 + vertex 0.845 1.97 2.48961 + vertex 0.846866 1.96541 2.48363 + endloop + endfacet + facet normal 0.951695 0.0365747 0.30486 + outer loop + vertex 0.845 1.975 2.48901 + vertex 0.845 1.97 2.48961 + vertex 0.846949 1.97089 2.48342 + endloop + endfacet + facet normal 0.854306 -0.110723 0.507841 + outer loop + vertex 0.849287 1.97283 2.47968 + vertex 0.849544 1.9784 2.48046 + vertex 0.847221 1.97724 2.48412 + endloop + endfacet + facet normal 0.864967 -0.091252 0.493462 + outer loop + vertex 0.846949 1.97089 2.48342 + vertex 0.849287 1.97283 2.47968 + vertex 0.847221 1.97724 2.48412 + endloop + endfacet + facet normal 0.921089 -0.081286 0.380772 + outer loop + vertex 0.847221 1.97724 2.48412 + vertex 0.845 1.975 2.48901 + vertex 0.846949 1.97089 2.48342 + endloop + endfacet + facet normal 0.896855 0.0664767 0.437301 + outer loop + vertex 0.845 1.98 2.48825 + vertex 0.845 1.975 2.48901 + vertex 0.847221 1.97724 2.48412 + endloop + endfacet + facet normal -0.36592 -0.660333 -0.655791 + outer loop + vertex 0.845352 1.97972 2.49074 + vertex 0.845 1.97568 2.495 + vertex 0.845 1.98 2.49065 + endloop + endfacet + facet normal 0.99448 0.0217346 0.102653 + outer loop + vertex 0.84496 1.9785 2.49479 + vertex 0.845 1.97568 2.495 + vertex 0.845352 1.97972 2.49074 + endloop + endfacet + facet normal 0.911565 0.0436348 0.408834 + outer loop + vertex 0.843526 1.97461 2.4984 + vertex 0.845 1.97568 2.495 + vertex 0.84496 1.9785 2.49479 + endloop + endfacet + facet normal 0.964953 -0.21043 0.156793 + outer loop + vertex 0.844147 1.97875 2.50013 + vertex 0.843526 1.97461 2.4984 + vertex 0.84496 1.9785 2.49479 + endloop + endfacet + facet normal 0.907237 -0.27084 0.321819 + outer loop + vertex 0.842054 1.97464 2.50257 + vertex 0.843526 1.97461 2.4984 + vertex 0.844147 1.97875 2.50013 + endloop + endfacet + facet normal 0.865206 -0.158376 0.475748 + outer loop + vertex 0.844147 1.97875 2.50013 + vertex 0.8422 1.97842 2.50356 + vertex 0.842054 1.97464 2.50257 + endloop + endfacet + facet normal 0.521851 -0.451378 0.72383 + outer loop + vertex 0.849544 1.9784 2.48046 + vertex 0.85 1.985 2.48425 + vertex 0.84896 1.985 2.485 + endloop + endfacet + facet normal 0.851654 -0.243647 0.464028 + outer loop + vertex 0.847221 1.97724 2.48412 + vertex 0.849544 1.9784 2.48046 + vertex 0.84896 1.985 2.485 + endloop + endfacet + facet normal 0.794816 -0.517738 0.316568 + outer loop + vertex 0.845 1.98 2.48825 + vertex 0.84756 1.985 2.49 + vertex 0.845 1.98107 2.49 + endloop + endfacet + facet normal 0.563196 -0.514628 0.646505 + outer loop + vertex 0.845 1.98 2.48825 + vertex 0.847221 1.97724 2.48412 + vertex 0.84756 1.985 2.49 + endloop + endfacet + facet normal 0.93499 -0.239288 0.26179 + outer loop + vertex 0.847221 1.97724 2.48412 + vertex 0.84896 1.985 2.485 + vertex 0.84756 1.985 2.49 + endloop + endfacet + facet normal -0.197247 -0.508938 -0.8379 + outer loop + vertex 0.845 1.98107 2.49 + vertex 0.845352 1.97972 2.49074 + vertex 0.845 1.98 2.49065 + endloop + endfacet + facet normal 0.487614 -0.317629 -0.813231 + outer loop + vertex 0.845 1.98107 2.49 + vertex 0.84756 1.985 2.49 + vertex 0.845352 1.97972 2.49074 + endloop + endfacet + facet normal 0.913428 -0.353553 0.201619 + outer loop + vertex 0.84756 1.985 2.49 + vertex 0.846452 1.98304 2.49159 + vertex 0.845352 1.97972 2.49074 + endloop + endfacet + facet normal 0.949674 -0.31323 -0.00234657 + outer loop + vertex 0.845352 1.97972 2.49074 + vertex 0.846452 1.98304 2.49159 + vertex 0.84496 1.9785 2.49479 + endloop + endfacet + facet normal 0.964706 -0.239341 0.109807 + outer loop + vertex 0.846452 1.98304 2.49159 + vertex 0.845792 1.98243 2.49604 + vertex 0.84496 1.9785 2.49479 + endloop + endfacet + facet normal 0.954763 -0.252396 0.157238 + outer loop + vertex 0.84496 1.9785 2.49479 + vertex 0.845792 1.98243 2.49604 + vertex 0.844147 1.97875 2.50013 + endloop + endfacet + facet normal 0.953524 -0.26281 0.147389 + outer loop + vertex 0.845792 1.98243 2.49604 + vertex 0.845343 1.98302 2.5 + vertex 0.844147 1.97875 2.50013 + endloop + endfacet + facet normal 0.682895 -0.309561 0.661684 + outer loop + vertex 0.8422 1.97842 2.50356 + vertex 0.844038 1.98215 2.50341 + vertex 0.842346 1.98129 2.50475 + endloop + endfacet + facet normal 0.818051 -0.385752 0.426601 + outer loop + vertex 0.8422 1.97842 2.50356 + vertex 0.844147 1.97875 2.50013 + vertex 0.844038 1.98215 2.50341 + endloop + endfacet + facet normal 0.923932 -0.250017 0.289554 + outer loop + vertex 0.844147 1.97875 2.50013 + vertex 0.845343 1.98302 2.5 + vertex 0.844038 1.98215 2.50341 + endloop + endfacet + facet normal 0.68605 -0.403158 0.605639 + outer loop + vertex 0.844038 1.98215 2.50341 + vertex 0.843192 1.9835 2.50527 + vertex 0.842346 1.98129 2.50475 + endloop + endfacet + facet normal 0.909196 -0.235845 0.343132 + outer loop + vertex 0.84756 1.985 2.49 + vertex 0.848857 1.99 2.49 + vertex 0.846452 1.98304 2.49159 + endloop + endfacet + facet normal 0.891815 -0.217576 0.396645 + outer loop + vertex 0.848857 1.99 2.49 + vertex 0.847132 1.98749 2.4925 + vertex 0.846452 1.98304 2.49159 + endloop + endfacet + facet normal 0.977265 -0.174303 0.12071 + outer loop + vertex 0.846452 1.98304 2.49159 + vertex 0.847132 1.98749 2.4925 + vertex 0.845792 1.98243 2.49604 + endloop + endfacet + facet normal 0.976767 -0.155307 0.147665 + outer loop + vertex 0.847132 1.98749 2.4925 + vertex 0.846373 1.98686 2.49687 + vertex 0.845792 1.98243 2.49604 + endloop + endfacet + facet normal 0.9791 -0.153063 0.133923 + outer loop + vertex 0.845792 1.98243 2.49604 + vertex 0.846373 1.98686 2.49687 + vertex 0.845343 1.98302 2.5 + endloop + endfacet + facet normal 0.974142 -0.0931948 0.20582 + outer loop + vertex 0.846373 1.98686 2.49687 + vertex 0.845443 1.98654 2.50112 + vertex 0.845343 1.98302 2.5 + endloop + endfacet + facet normal 0.936726 -0.130088 0.324994 + outer loop + vertex 0.845343 1.98302 2.5 + vertex 0.845443 1.98654 2.50112 + vertex 0.844038 1.98215 2.50341 + endloop + endfacet + facet normal 0.931932 -0.119496 0.34238 + outer loop + vertex 0.845443 1.98654 2.50112 + vertex 0.844228 1.98601 2.50424 + vertex 0.844038 1.98215 2.50341 + endloop + endfacet + facet normal 0.854592 -0.149157 0.497417 + outer loop + vertex 0.844228 1.98601 2.50424 + vertex 0.843192 1.9835 2.50527 + vertex 0.844038 1.98215 2.50341 + endloop + endfacet + facet normal 0.648061 0.043704 0.760333 + outer loop + vertex 0.843057 1.98582 2.50525 + vertex 0.843192 1.9835 2.50527 + vertex 0.844228 1.98601 2.50424 + endloop + endfacet + facet normal 0.817425 0.0119272 0.575912 + outer loop + vertex 0.848857 1.99 2.49 + vertex 0.848784 1.995 2.49 + vertex 0.847132 1.98749 2.4925 + endloop + endfacet + facet normal 0.944189 -0.103562 0.312702 + outer loop + vertex 0.848784 1.995 2.49 + vertex 0.847518 1.99224 2.49291 + vertex 0.847132 1.98749 2.4925 + endloop + endfacet + facet normal 0.983075 -0.0933866 0.157618 + outer loop + vertex 0.847132 1.98749 2.4925 + vertex 0.847518 1.99224 2.49291 + vertex 0.846373 1.98686 2.49687 + endloop + endfacet + facet normal 0.978401 -0.0636586 0.196669 + outer loop + vertex 0.847518 1.99224 2.49291 + vertex 0.846578 1.99138 2.4973 + vertex 0.846373 1.98686 2.49687 + endloop + endfacet + facet normal 0.97591 -0.0646789 0.208368 + outer loop + vertex 0.846373 1.98686 2.49687 + vertex 0.846578 1.99138 2.4973 + vertex 0.845443 1.98654 2.50112 + endloop + endfacet + facet normal 0.940431 0.0451543 0.336973 + outer loop + vertex 0.846578 1.99138 2.4973 + vertex 0.845089 1.99093 2.50152 + vertex 0.845443 1.98654 2.50112 + endloop + endfacet + facet normal 0.619798 0.392551 0.679525 + outer loop + vertex 0.843658 1.98851 2.50423 + vertex 0.845089 1.99093 2.50152 + vertex 0.843333 1.99204 2.50248 + endloop + endfacet + facet normal 0.790687 0.184559 0.58374 + outer loop + vertex 0.843658 1.98851 2.50423 + vertex 0.844228 1.98601 2.50424 + vertex 0.845089 1.99093 2.50152 + endloop + endfacet + facet normal 0.928697 0.0413236 0.36853 + outer loop + vertex 0.844228 1.98601 2.50424 + vertex 0.845443 1.98654 2.50112 + vertex 0.845089 1.99093 2.50152 + endloop + endfacet + facet normal 0.631413 0.149464 0.760906 + outer loop + vertex 0.844228 1.98601 2.50424 + vertex 0.843658 1.98851 2.50423 + vertex 0.843057 1.98582 2.50525 + endloop + endfacet + facet normal 0.941616 -0.0900129 0.324433 + outer loop + vertex 0.848784 1.995 2.49 + vertex 0.849262 2 2.49 + vertex 0.847518 1.99224 2.49291 + endloop + endfacet + facet normal 0.949653 -0.102449 0.296081 + outer loop + vertex 0.849262 2 2.49 + vertex 0.847933 1.99646 2.49304 + vertex 0.847518 1.99224 2.49291 + endloop + endfacet + facet normal 0.97672 -0.101837 0.188807 + outer loop + vertex 0.847518 1.99224 2.49291 + vertex 0.847933 1.99646 2.49304 + vertex 0.846578 1.99138 2.4973 + endloop + endfacet + facet normal 0.96452 -0.0377311 0.261298 + outer loop + vertex 0.847933 1.99646 2.49304 + vertex 0.846739 1.99583 2.49735 + vertex 0.846578 1.99138 2.4973 + endloop + endfacet + facet normal 0.9435 -0.0377278 0.329217 + outer loop + vertex 0.846578 1.99138 2.4973 + vertex 0.846739 1.99583 2.49735 + vertex 0.845089 1.99093 2.50152 + endloop + endfacet + facet normal 0.8289 0.173044 0.531959 + outer loop + vertex 0.846739 1.99583 2.49735 + vertex 0.844839 1.9961 2.50023 + vertex 0.845089 1.99093 2.50152 + endloop + endfacet + facet normal 0.572965 0.224754 0.78816 + outer loop + vertex 0.844839 1.9961 2.50023 + vertex 0.843333 1.99204 2.50248 + vertex 0.845089 1.99093 2.50152 + endloop + endfacet + facet normal 0.166897 0.430318 0.887114 + outer loop + vertex 0.843012 1.99534 2.50094 + vertex 0.843333 1.99204 2.50248 + vertex 0.844839 1.9961 2.50023 + endloop + endfacet + facet normal 0.92793 -0.177271 0.327904 + outer loop + vertex 0.85 2.00166 2.49 + vertex 0.84843 2.00004 2.49357 + vertex 0.847933 1.99646 2.49304 + endloop + endfacet + facet normal 0.911294 -0.405129 -0.0735751 + outer loop + vertex 0.849262 2 2.49 + vertex 0.85 2.00166 2.49 + vertex 0.847933 1.99646 2.49304 + endloop + endfacet + facet normal 0.937576 -0.0702976 0.340603 + outer loop + vertex 0.84843 2.00004 2.49357 + vertex 0.846979 1.99992 2.49754 + vertex 0.846739 1.99583 2.49735 + endloop + endfacet + facet normal 0.956066 -0.168183 0.240108 + outer loop + vertex 0.847933 1.99646 2.49304 + vertex 0.84843 2.00004 2.49357 + vertex 0.846739 1.99583 2.49735 + endloop + endfacet + facet normal 0.440486 -0.236273 0.86611 + outer loop + vertex 0.846979 1.99992 2.49754 + vertex 0.847165 2.00342 2.49839 + vertex 0.844573 2.00028 2.49886 + endloop + endfacet + facet normal 0.492726 0.29952 0.817012 + outer loop + vertex 0.846979 1.99992 2.49754 + vertex 0.844573 2.00028 2.49886 + vertex 0.844839 1.9961 2.50023 + endloop + endfacet + facet normal 0.828872 -0.0734878 0.554591 + outer loop + vertex 0.846979 1.99992 2.49754 + vertex 0.844839 1.9961 2.50023 + vertex 0.846739 1.99583 2.49735 + endloop + endfacet + facet normal 0.326811 0.313425 0.891605 + outer loop + vertex 0.844839 1.9961 2.50023 + vertex 0.844573 2.00028 2.49886 + vertex 0.843667 1.99749 2.50017 + endloop + endfacet + facet normal 0.256454 0.255832 0.932084 + outer loop + vertex 0.844839 1.9961 2.50023 + vertex 0.843667 1.99749 2.50017 + vertex 0.843012 1.99534 2.50094 + endloop + endfacet + facet normal -0.83601 0.131256 -0.532785 + outer loop + vertex 0.849154 2.005 2.485 + vertex 0.849939 2.01 2.485 + vertex 0.849581 2.00602 2.48458 + endloop + endfacet + facet normal 0.780924 -0.489027 -0.3886 + outer loop + vertex 0.85 2.005 2.4867 + vertex 0.849154 2.005 2.485 + vertex 0.849581 2.00602 2.48458 + endloop + endfacet + facet normal -0.51093 0.00933529 0.859572 + outer loop + vertex 0.847307 2.00568 2.49944 + vertex 0.846686 2.0077 2.49904 + vertex 0.845087 2.0049 2.49812 + endloop + endfacet + facet normal -0.373199 -0.368052 0.851622 + outer loop + vertex 0.847307 2.00568 2.49944 + vertex 0.845087 2.0049 2.49812 + vertex 0.847165 2.00342 2.49839 + endloop + endfacet + facet normal -0.0151294 0.158036 0.987317 + outer loop + vertex 0.847165 2.00342 2.49839 + vertex 0.845087 2.0049 2.49812 + vertex 0.844573 2.00028 2.49886 + endloop + endfacet + facet normal -0.421388 0.0459473 0.905716 + outer loop + vertex 0.847307 2.00568 2.49944 + vertex 0.847901 2.00711 2.49964 + vertex 0.846686 2.0077 2.49904 + endloop + endfacet + facet normal -0.112253 0.114035 -0.987115 + outer loop + vertex 0.85 2.01006 2.485 + vertex 0.849581 2.00602 2.48458 + vertex 0.849939 2.01 2.485 + endloop + endfacet + facet normal -0.710085 0.306261 0.634022 + outer loop + vertex 0.84621 2.01204 2.49691 + vertex 0.844009 2.01095 2.49498 + vertex 0.844963 2.00846 2.49725 + endloop + endfacet + facet normal -0.680484 0.153384 0.71653 + outer loop + vertex 0.844963 2.00846 2.49725 + vertex 0.845087 2.0049 2.49812 + vertex 0.846686 2.0077 2.49904 + endloop + endfacet + facet normal -0.628483 0.286062 0.72331 + outer loop + vertex 0.84621 2.01204 2.49691 + vertex 0.844963 2.00846 2.49725 + vertex 0.846686 2.0077 2.49904 + endloop + endfacet + facet normal -0.261323 0.401932 0.877588 + outer loop + vertex 0.84621 2.01204 2.49691 + vertex 0.846686 2.0077 2.49904 + vertex 0.848092 2.00949 2.49864 + endloop + endfacet + facet normal -0.308645 0.366951 0.877545 + outer loop + vertex 0.84621 2.01204 2.49691 + vertex 0.848092 2.00949 2.49864 + vertex 0.848263 2.01298 2.49724 + endloop + endfacet + facet normal -0.245945 0.391888 0.88653 + outer loop + vertex 0.848092 2.00949 2.49864 + vertex 0.846686 2.0077 2.49904 + vertex 0.847901 2.00711 2.49964 + endloop + endfacet + facet normal -0.709839 0.299744 0.637403 + outer loop + vertex 0.844225 2.01474 2.49343 + vertex 0.844009 2.01095 2.49498 + vertex 0.84621 2.01204 2.49691 + endloop + endfacet + facet normal -0.72648 0.27673 0.629004 + outer loop + vertex 0.846029 2.01716 2.49445 + vertex 0.844225 2.01474 2.49343 + vertex 0.84621 2.01204 2.49691 + endloop + endfacet + facet normal -0.487569 0.364299 0.79345 + outer loop + vertex 0.84621 2.01204 2.49691 + vertex 0.847545 2.01564 2.49608 + vertex 0.846029 2.01716 2.49445 + endloop + endfacet + facet normal -0.289548 0.316456 0.903337 + outer loop + vertex 0.848263 2.01298 2.49724 + vertex 0.847545 2.01564 2.49608 + vertex 0.84621 2.01204 2.49691 + endloop + endfacet + facet normal -0.752129 0.360539 0.551646 + outer loop + vertex 0.846218 2.02236 2.49185 + vertex 0.844045 2.02114 2.48969 + vertex 0.844564 2.01858 2.49207 + endloop + endfacet + facet normal -0.731647 0.28467 0.6194 + outer loop + vertex 0.844564 2.01858 2.49207 + vertex 0.844225 2.01474 2.49343 + vertex 0.846029 2.01716 2.49445 + endloop + endfacet + facet normal -0.696589 0.340778 0.631375 + outer loop + vertex 0.846218 2.02236 2.49185 + vertex 0.844564 2.01858 2.49207 + vertex 0.846029 2.01716 2.49445 + endloop + endfacet + facet normal -0.343375 0.429763 0.835103 + outer loop + vertex 0.846218 2.02236 2.49185 + vertex 0.846029 2.01716 2.49445 + vertex 0.848038 2.01945 2.4941 + endloop + endfacet + facet normal -0.390081 0.397128 0.830738 + outer loop + vertex 0.846218 2.02236 2.49185 + vertex 0.848038 2.01945 2.4941 + vertex 0.84887 2.02327 2.49266 + endloop + endfacet + facet normal -0.389891 0.46428 0.795254 + outer loop + vertex 0.848038 2.01945 2.4941 + vertex 0.846029 2.01716 2.49445 + vertex 0.847545 2.01564 2.49608 + endloop + endfacet + facet normal -0.752569 0.300317 0.586045 + outer loop + vertex 0.844371 2.02498 2.48814 + vertex 0.844045 2.02114 2.48969 + vertex 0.846218 2.02236 2.49185 + endloop + endfacet + facet normal -0.781496 0.255843 0.569042 + outer loop + vertex 0.846464 2.0281 2.48961 + vertex 0.844371 2.02498 2.48814 + vertex 0.846218 2.02236 2.49185 + endloop + endfacet + facet normal -0.568618 0.320417 0.757633 + outer loop + vertex 0.846218 2.02236 2.49185 + vertex 0.848434 2.02606 2.49195 + vertex 0.846464 2.0281 2.48961 + endloop + endfacet + facet normal -0.343859 0.181696 0.921275 + outer loop + vertex 0.84887 2.02327 2.49266 + vertex 0.848434 2.02606 2.49195 + vertex 0.846218 2.02236 2.49185 + endloop + endfacet + facet normal -0.843193 0.286292 0.455041 + outer loop + vertex 0.845324 2.03263 2.48564 + vertex 0.843809 2.03087 2.48394 + vertex 0.844463 2.02876 2.48647 + endloop + endfacet + facet normal -0.786719 0.264688 0.557686 + outer loop + vertex 0.844463 2.02876 2.48647 + vertex 0.844371 2.02498 2.48814 + vertex 0.846464 2.0281 2.48961 + endloop + endfacet + facet normal -0.77665 0.293633 0.55731 + outer loop + vertex 0.844463 2.02876 2.48647 + vertex 0.846464 2.0281 2.48961 + vertex 0.845324 2.03263 2.48564 + endloop + endfacet + facet normal -0.805468 0.263245 0.530965 + outer loop + vertex 0.845324 2.03263 2.48564 + vertex 0.846464 2.0281 2.48961 + vertex 0.847806 2.03267 2.48938 + endloop + endfacet + facet normal -0.678908 0.234371 0.695812 + outer loop + vertex 0.846464 2.0281 2.48961 + vertex 0.849658 2.02989 2.49212 + vertex 0.847806 2.03267 2.48938 + endloop + endfacet + facet normal -0.668938 0.181334 0.720861 + outer loop + vertex 0.848434 2.02606 2.49195 + vertex 0.849658 2.02989 2.49212 + vertex 0.846464 2.0281 2.48961 + endloop + endfacet + facet normal -0.877842 0.33589 0.341424 + outer loop + vertex 0.844975 2.03759 2.48112 + vertex 0.843604 2.03573 2.47943 + vertex 0.843922 2.03374 2.4822 + endloop + endfacet + facet normal -0.845119 0.300337 0.442235 + outer loop + vertex 0.843922 2.03374 2.4822 + vertex 0.843809 2.03087 2.48394 + vertex 0.845324 2.03263 2.48564 + endloop + endfacet + facet normal -0.821748 0.350842 0.449044 + outer loop + vertex 0.843922 2.03374 2.4822 + vertex 0.845324 2.03263 2.48564 + vertex 0.844975 2.03759 2.48112 + endloop + endfacet + facet normal -0.846427 0.324615 0.422122 + outer loop + vertex 0.844975 2.03759 2.48112 + vertex 0.845324 2.03263 2.48564 + vertex 0.847195 2.03716 2.4859 + endloop + endfacet + facet normal -0.771135 0.245157 0.587578 + outer loop + vertex 0.848967 2.03573 2.48963 + vertex 0.847806 2.03267 2.48938 + vertex 0.849841 2.03351 2.4917 + endloop + endfacet + facet normal -0.823973 0.272656 0.496716 + outer loop + vertex 0.848967 2.03573 2.48963 + vertex 0.847195 2.03716 2.4859 + vertex 0.847806 2.03267 2.48938 + endloop + endfacet + facet normal -0.797136 0.298221 0.525013 + outer loop + vertex 0.847195 2.03716 2.4859 + vertex 0.845324 2.03263 2.48564 + vertex 0.847806 2.03267 2.48938 + endloop + endfacet + facet normal -0.767021 0.112396 0.631701 + outer loop + vertex 0.849841 2.03351 2.4917 + vertex 0.847806 2.03267 2.48938 + vertex 0.849658 2.02989 2.49212 + endloop + endfacet + facet normal -0.903525 0.347136 0.251276 + outer loop + vertex 0.845408 2.04294 2.47647 + vertex 0.844077 2.04079 2.47465 + vertex 0.844009 2.03869 2.47731 + endloop + endfacet + facet normal -0.878183 0.351889 0.323989 + outer loop + vertex 0.844009 2.03869 2.47731 + vertex 0.843604 2.03573 2.47943 + vertex 0.844975 2.03759 2.48112 + endloop + endfacet + facet normal -0.877646 0.353045 0.324185 + outer loop + vertex 0.844009 2.03869 2.47731 + vertex 0.844975 2.03759 2.48112 + vertex 0.845408 2.04294 2.47647 + endloop + endfacet + facet normal -0.88688 0.341991 0.310623 + outer loop + vertex 0.845408 2.04294 2.47647 + vertex 0.844975 2.03759 2.48112 + vertex 0.846913 2.04265 2.48108 + endloop + endfacet + facet normal -0.824282 0.293075 0.484424 + outer loop + vertex 0.848279 2.04107 2.48538 + vertex 0.847195 2.03716 2.4859 + vertex 0.849067 2.03862 2.4882 + endloop + endfacet + facet normal -0.874489 0.293832 0.385918 + outer loop + vertex 0.848279 2.04107 2.48538 + vertex 0.846913 2.04265 2.48108 + vertex 0.847195 2.03716 2.4859 + endloop + endfacet + facet normal -0.845605 0.326965 0.421954 + outer loop + vertex 0.846913 2.04265 2.48108 + vertex 0.844975 2.03759 2.48112 + vertex 0.847195 2.03716 2.4859 + endloop + endfacet + facet normal -0.823824 0.272997 0.496776 + outer loop + vertex 0.849067 2.03862 2.4882 + vertex 0.847195 2.03716 2.4859 + vertex 0.848967 2.03573 2.48963 + endloop + endfacet + facet normal -0.867043 0.129201 0.48119 + outer loop + vertex 0.845 2.04567 2.475 + vertex 0.844077 2.04079 2.47465 + vertex 0.845408 2.04294 2.47647 + endloop + endfacet + facet normal -0.569217 0.321679 0.756646 + outer loop + vertex 0.845 2.04567 2.475 + vertex 0.845408 2.04294 2.47647 + vertex 0.847447 2.05 2.475 + endloop + endfacet + facet normal -0.891665 0.323381 0.316794 + outer loop + vertex 0.847447 2.05 2.475 + vertex 0.845408 2.04294 2.47647 + vertex 0.846963 2.04762 2.47606 + endloop + endfacet + facet normal -0.893439 0.323523 0.311607 + outer loop + vertex 0.845408 2.04294 2.47647 + vertex 0.846913 2.04265 2.48108 + vertex 0.846963 2.04762 2.47606 + endloop + endfacet + facet normal -0.947688 0.231431 0.219833 + outer loop + vertex 0.846963 2.04762 2.47606 + vertex 0.846913 2.04265 2.48108 + vertex 0.847872 2.04798 2.47961 + endloop + endfacet + facet normal -0.885017 0.26519 0.382649 + outer loop + vertex 0.846913 2.04265 2.48108 + vertex 0.848756 2.04515 2.48361 + vertex 0.847872 2.04798 2.47961 + endloop + endfacet + facet normal -0.885297 0.268163 0.379918 + outer loop + vertex 0.848279 2.04107 2.48538 + vertex 0.848756 2.04515 2.48361 + vertex 0.846913 2.04265 2.48108 + endloop + endfacet + facet normal -0.77969 -0.45083 -0.434551 + outer loop + vertex 0.85 2.05 2.47138 + vertex 0.847878 2.055 2.47 + vertex 0.85 2.05133 2.47 + endloop + endfacet + facet normal -0.729201 -0.45141 -0.51429 + outer loop + vertex 0.85 2.05 2.47138 + vertex 0.847447 2.05 2.475 + vertex 0.847878 2.055 2.47 + endloop + endfacet + facet normal 0.782288 -0.472883 -0.405471 + outer loop + vertex 0.847447 2.05 2.475 + vertex 0.847578 2.05278 2.472 + vertex 0.847878 2.055 2.47 + endloop + endfacet + facet normal 0.927796 -0.292586 -0.231491 + outer loop + vertex 0.847447 2.05 2.475 + vertex 0.846963 2.04762 2.47606 + vertex 0.847578 2.05278 2.472 + endloop + endfacet + facet normal -0.979405 0.1833 0.0846622 + outer loop + vertex 0.847578 2.05278 2.472 + vertex 0.846963 2.04762 2.47606 + vertex 0.847808 2.05231 2.47569 + endloop + endfacet + facet normal -0.903168 0.210009 0.374411 + outer loop + vertex 0.848549 2.05138 2.47933 + vertex 0.847872 2.04798 2.47961 + vertex 0.849117 2.04914 2.48196 + endloop + endfacet + facet normal -0.94662 0.208325 0.245989 + outer loop + vertex 0.848549 2.05138 2.47933 + vertex 0.847808 2.05231 2.47569 + vertex 0.847872 2.04798 2.47961 + endloop + endfacet + facet normal -0.955399 0.190116 0.225983 + outer loop + vertex 0.847808 2.05231 2.47569 + vertex 0.846963 2.04762 2.47606 + vertex 0.847872 2.04798 2.47961 + endloop + endfacet + facet normal -0.902359 0.232148 0.36312 + outer loop + vertex 0.849117 2.04914 2.48196 + vertex 0.847872 2.04798 2.47961 + vertex 0.848756 2.04515 2.48361 + endloop + endfacet + facet normal -0.990012 0.140788 0.00736318 + outer loop + vertex 0.847878 2.055 2.47 + vertex 0.847578 2.05278 2.472 + vertex 0.848589 2.06 2.47 + endloop + endfacet + facet normal -0.982209 0.0921903 -0.163604 + outer loop + vertex 0.848589 2.06 2.47 + vertex 0.847578 2.05278 2.472 + vertex 0.848087 2.05718 2.47142 + endloop + endfacet + facet normal -0.956723 0.17063 0.235726 + outer loop + vertex 0.848358 2.0562 2.47511 + vertex 0.847808 2.05231 2.47569 + vertex 0.848664 2.05415 2.47784 + endloop + endfacet + facet normal -0.981207 0.15589 0.113718 + outer loop + vertex 0.848358 2.0562 2.47511 + vertex 0.848087 2.05718 2.47142 + vertex 0.847808 2.05231 2.47569 + endloop + endfacet + facet normal -0.989124 0.124843 0.0777654 + outer loop + vertex 0.848087 2.05718 2.47142 + vertex 0.847578 2.05278 2.472 + vertex 0.847808 2.05231 2.47569 + endloop + endfacet + facet normal -0.956647 0.168237 0.237747 + outer loop + vertex 0.848664 2.05415 2.47784 + vertex 0.847808 2.05231 2.47569 + vertex 0.848549 2.05138 2.47933 + endloop + endfacet + facet normal -0.163519 -0.55808 -0.813516 + outer loop + vertex 0.85 2.06 2.46859 + vertex 0.848783 2.06104 2.46812 + vertex 0.85 2.065 2.46516 + endloop + endfacet + facet normal -0.465305 -0.752776 -0.465639 + outer loop + vertex 0.848589 2.06 2.47 + vertex 0.848783 2.06104 2.46812 + vertex 0.85 2.06 2.46859 + endloop + endfacet + facet normal 0.985028 -0.172282 0.00623641 + outer loop + vertex 0.848589 2.06 2.47 + vertex 0.848087 2.05718 2.47142 + vertex 0.848783 2.06104 2.46812 + endloop + endfacet + facet normal -0.989994 0.128404 -0.0585149 + outer loop + vertex 0.848783 2.06104 2.46812 + vertex 0.848087 2.05718 2.47142 + vertex 0.84872 2.06147 2.47013 + endloop + endfacet + facet normal -0.969558 0.189792 0.154714 + outer loop + vertex 0.848087 2.05718 2.47142 + vertex 0.848882 2.05967 2.47336 + vertex 0.84872 2.06147 2.47013 + endloop + endfacet + facet normal -0.969179 0.210787 0.127522 + outer loop + vertex 0.848358 2.0562 2.47511 + vertex 0.848882 2.05967 2.47336 + vertex 0.848087 2.05718 2.47142 + endloop + endfacet + facet normal 0.694371 -0.13041 -0.707702 + outer loop + vertex 0.85 2.06517 2.465 + vertex 0.849523 2.06801 2.46401 + vertex 0.85 2.07 2.46411 + endloop + endfacet + facet normal -0.970381 0.212635 -0.11466 + outer loop + vertex 0.85 2.065 2.46516 + vertex 0.848783 2.06104 2.46812 + vertex 0.85 2.06761 2.47 + endloop + endfacet + facet normal -0.976745 -0.0973088 0.191053 + outer loop + vertex 0.85 2.06517 2.465 + vertex 0.85 2.07 2.46746 + vertex 0.849523 2.06801 2.46401 + endloop + endfacet + facet normal -0.935816 0.201232 0.289403 + outer loop + vertex 0.85 2.06761 2.47 + vertex 0.84872 2.06147 2.47013 + vertex 0.849563 2.06352 2.47143 + endloop + endfacet + facet normal -0.976609 0.202028 -0.0736122 + outer loop + vertex 0.848783 2.06104 2.46812 + vertex 0.84872 2.06147 2.47013 + vertex 0.85 2.06761 2.47 + endloop + endfacet + facet normal -0.944459 0.264465 0.195077 + outer loop + vertex 0.849563 2.06352 2.47143 + vertex 0.84872 2.06147 2.47013 + vertex 0.848882 2.05967 2.47336 + endloop + endfacet + facet normal -0.887335 0.232984 -0.397938 + outer loop + vertex 0.85 2.07 2.46411 + vertex 0.849523 2.06801 2.46401 + vertex 0.85 2.07152 2.465 + endloop + endfacet + facet normal -0.990878 0.114637 0.0708397 + outer loop + vertex 0.85 2.07152 2.465 + vertex 0.849523 2.06801 2.46401 + vertex 0.85 2.07 2.46746 + endloop + endfacet + facet normal -0.705198 -0.0987004 -0.702107 + outer loop + vertex 0.855 0.945163 2.465 + vertex 0.854323 0.95 2.465 + vertex 0.855 0.95 2.46432 + endloop + endfacet + facet normal -0.976723 -0.136703 0.1653 + outer loop + vertex 0.855 0.945163 2.465 + vertex 0.855 0.95 2.469 + vertex 0.854323 0.95 2.465 + endloop + endfacet + facet normal -0.964134 0.209333 0.16317 + outer loop + vertex 0.855 0.953118 2.465 + vertex 0.854323 0.95 2.465 + vertex 0.855 0.95 2.469 + endloop + endfacet + facet normal -0.611176 -0.514861 -0.601151 + outer loop + vertex 0.855 0.955 2.46623 + vertex 0.855 0.950598 2.47 + vertex 0.85371 0.954075 2.46833 + endloop + endfacet + facet normal -0.5867 -0.516564 -0.623654 + outer loop + vertex 0.854288 0.951493 2.46993 + vertex 0.85371 0.954075 2.46833 + vertex 0.855 0.950598 2.47 + endloop + endfacet + facet normal -0.961388 -0.263767 -0.0784834 + outer loop + vertex 0.853174 0.955379 2.47052 + vertex 0.85371 0.954075 2.46833 + vertex 0.854288 0.951493 2.46993 + endloop + endfacet + facet normal -0.953924 -0.286958 0.0876562 + outer loop + vertex 0.854288 0.951493 2.46993 + vertex 0.854245 0.952464 2.47264 + vertex 0.853174 0.955379 2.47052 + endloop + endfacet + facet normal -0.671611 0.203735 -0.712342 + outer loop + vertex 0.855 0.955 2.46623 + vertex 0.852518 0.96 2.47 + vertex 0.855 0.96 2.46766 + endloop + endfacet + facet normal -0.848025 -0.0216946 -0.529512 + outer loop + vertex 0.85371 0.954075 2.46833 + vertex 0.852518 0.96 2.47 + vertex 0.855 0.955 2.46623 + endloop + endfacet + facet normal -0.976884 -0.155188 -0.147016 + outer loop + vertex 0.85371 0.954075 2.46833 + vertex 0.853174 0.955379 2.47052 + vertex 0.852518 0.96 2.47 + endloop + endfacet + facet normal -0.966434 -0.159806 -0.201164 + outer loop + vertex 0.852518 0.96 2.47 + vertex 0.853174 0.955379 2.47052 + vertex 0.852018 0.960569 2.47195 + endloop + endfacet + facet normal -0.953606 -0.256001 0.158426 + outer loop + vertex 0.853174 0.955379 2.47052 + vertex 0.8536 0.956118 2.47428 + vertex 0.852018 0.960569 2.47195 + endloop + endfacet + facet normal -0.958432 -0.239121 0.155656 + outer loop + vertex 0.854245 0.952464 2.47264 + vertex 0.8536 0.956118 2.47428 + vertex 0.853174 0.955379 2.47052 + endloop + endfacet + facet normal -0.934851 -0.324021 -0.145132 + outer loop + vertex 0.852518 0.96 2.47 + vertex 0.852018 0.960569 2.47195 + vertex 0.850785 0.965 2.47 + endloop + endfacet + facet normal -0.968837 -0.234614 0.0794404 + outer loop + vertex 0.850785 0.965 2.47 + vertex 0.852018 0.960569 2.47195 + vertex 0.851012 0.964804 2.47219 + endloop + endfacet + facet normal -0.95104 -0.229821 0.206652 + outer loop + vertex 0.853004 0.960029 2.47589 + vertex 0.852018 0.960569 2.47195 + vertex 0.8536 0.956118 2.47428 + endloop + endfacet + facet normal -0.953264 -0.218404 0.208775 + outer loop + vertex 0.853004 0.960029 2.47589 + vertex 0.851901 0.965014 2.47607 + vertex 0.852018 0.960569 2.47195 + endloop + endfacet + facet normal -0.944019 -0.237165 0.229303 + outer loop + vertex 0.851901 0.965014 2.47607 + vertex 0.851012 0.964804 2.47219 + vertex 0.852018 0.960569 2.47195 + endloop + endfacet + facet normal -0.920143 -0.215313 0.327074 + outer loop + vertex 0.853004 0.960029 2.47589 + vertex 0.853578 0.962079 2.47885 + vertex 0.851901 0.965014 2.47607 + endloop + endfacet + facet normal -0.905589 -0.303407 0.296399 + outer loop + vertex 0.85 0.97 2.47272 + vertex 0.85 0.967343 2.47 + vertex 0.850785 0.965 2.47 + endloop + endfacet + facet normal -0.894483 -0.313718 0.31856 + outer loop + vertex 0.85 0.97 2.47272 + vertex 0.850785 0.965 2.47 + vertex 0.850812 0.97 2.475 + endloop + endfacet + facet normal -0.991472 -0.0894309 0.0947884 + outer loop + vertex 0.850812 0.97 2.475 + vertex 0.850785 0.965 2.47 + vertex 0.851012 0.964804 2.47219 + endloop + endfacet + facet normal -0.960099 -0.160741 0.228849 + outer loop + vertex 0.851012 0.964804 2.47219 + vertex 0.851901 0.965014 2.47607 + vertex 0.850812 0.97 2.475 + endloop + endfacet + facet normal -0.977468 -0.210691 0.0128518 + outer loop + vertex 0.850812 0.97 2.475 + vertex 0.851901 0.965014 2.47607 + vertex 0.850999 0.969248 2.47687 + endloop + endfacet + facet normal -0.913013 -0.16948 0.371058 + outer loop + vertex 0.853598 0.965664 2.48054 + vertex 0.851901 0.965014 2.47607 + vertex 0.853578 0.962079 2.47885 + endloop + endfacet + facet normal -0.884747 -0.275728 0.375761 + outer loop + vertex 0.853598 0.965664 2.48054 + vertex 0.852349 0.97004 2.48081 + vertex 0.851901 0.965014 2.47607 + endloop + endfacet + facet normal -0.89652 -0.259142 0.359302 + outer loop + vertex 0.852349 0.97004 2.48081 + vertex 0.850999 0.969248 2.47687 + vertex 0.851901 0.965014 2.47607 + endloop + endfacet + facet normal -0.719631 -0.245549 0.64949 + outer loop + vertex 0.853598 0.965664 2.48054 + vertex 0.855423 0.969214 2.4839 + vertex 0.852349 0.97004 2.48081 + endloop + endfacet + facet normal 0.835442 0.283722 -0.470678 + outer loop + vertex 0.849417 0.97275 2.47418 + vertex 0.85 0.972391 2.475 + vertex 0.850812 0.97 2.475 + endloop + endfacet + facet normal -0.894821 -0.388391 0.220108 + outer loop + vertex 0.849417 0.97275 2.47418 + vertex 0.850812 0.97 2.475 + vertex 0.850173 0.973017 2.47773 + endloop + endfacet + facet normal -0.976276 -0.216274 0.0104871 + outer loop + vertex 0.850173 0.973017 2.47773 + vertex 0.850812 0.97 2.475 + vertex 0.850999 0.969248 2.47687 + endloop + endfacet + facet normal -0.89048 -0.27718 0.360856 + outer loop + vertex 0.850999 0.969248 2.47687 + vertex 0.852349 0.97004 2.48081 + vertex 0.850173 0.973017 2.47773 + endloop + endfacet + facet normal -0.890847 -0.344665 0.295968 + outer loop + vertex 0.850173 0.973017 2.47773 + vertex 0.852349 0.97004 2.48081 + vertex 0.851232 0.973603 2.48159 + endloop + endfacet + facet normal -0.687992 -0.460961 0.56052 + outer loop + vertex 0.854046 0.972173 2.48465 + vertex 0.852349 0.97004 2.48081 + vertex 0.855423 0.969214 2.4839 + endloop + endfacet + facet normal -0.721162 -0.418866 0.551794 + outer loop + vertex 0.854046 0.972173 2.48465 + vertex 0.8526 0.974871 2.48481 + vertex 0.852349 0.97004 2.48081 + endloop + endfacet + facet normal -0.799957 -0.357188 0.482167 + outer loop + vertex 0.8526 0.974871 2.48481 + vertex 0.851232 0.973603 2.48159 + vertex 0.852349 0.97004 2.48081 + endloop + endfacet + facet normal -0.569153 -0.34879 0.744588 + outer loop + vertex 0.854046 0.972173 2.48465 + vertex 0.85451 0.975054 2.48635 + vertex 0.8526 0.974871 2.48481 + endloop + endfacet + facet normal -0.937293 -0.270132 0.220253 + outer loop + vertex 0.849417 0.97275 2.47418 + vertex 0.850173 0.973017 2.47773 + vertex 0.848894 0.975401 2.47521 + endloop + endfacet + facet normal -0.937721 -0.261762 0.228387 + outer loop + vertex 0.849094 0.977223 2.47811 + vertex 0.848894 0.975401 2.47521 + vertex 0.850173 0.973017 2.47773 + endloop + endfacet + facet normal -0.920242 -0.262962 0.289839 + outer loop + vertex 0.849094 0.977223 2.47811 + vertex 0.850173 0.973017 2.47773 + vertex 0.850322 0.977781 2.48252 + endloop + endfacet + facet normal -0.91915 -0.264797 0.291627 + outer loop + vertex 0.850322 0.977781 2.48252 + vertex 0.850173 0.973017 2.47773 + vertex 0.851232 0.973603 2.48159 + endloop + endfacet + facet normal -0.835504 -0.285995 0.46919 + outer loop + vertex 0.851232 0.973603 2.48159 + vertex 0.8526 0.974871 2.48481 + vertex 0.850322 0.977781 2.48252 + endloop + endfacet + facet normal -0.840445 -0.308379 0.445595 + outer loop + vertex 0.850322 0.977781 2.48252 + vertex 0.8526 0.974871 2.48481 + vertex 0.852162 0.979779 2.48738 + endloop + endfacet + facet normal -0.47475 -0.44123 0.761531 + outer loop + vertex 0.8526 0.974871 2.48481 + vertex 0.854089 0.978461 2.48781 + vertex 0.852162 0.979779 2.48738 + endloop + endfacet + facet normal -0.558158 -0.38459 0.735221 + outer loop + vertex 0.85451 0.975054 2.48635 + vertex 0.854089 0.978461 2.48781 + vertex 0.8526 0.974871 2.48481 + endloop + endfacet + facet normal -0.918696 -0.268078 0.290055 + outer loop + vertex 0.849094 0.977223 2.47811 + vertex 0.850322 0.977781 2.48252 + vertex 0.848685 0.980403 2.47976 + endloop + endfacet + facet normal -0.918696 -0.275669 0.282849 + outer loop + vertex 0.848999 0.982391 2.48272 + vertex 0.848685 0.980403 2.47976 + vertex 0.850322 0.977781 2.48252 + endloop + endfacet + facet normal -0.889085 -0.27083 0.369025 + outer loop + vertex 0.848999 0.982391 2.48272 + vertex 0.850322 0.977781 2.48252 + vertex 0.850322 0.983005 2.48636 + endloop + endfacet + facet normal -0.829282 -0.330634 0.450524 + outer loop + vertex 0.850322 0.983005 2.48636 + vertex 0.850322 0.977781 2.48252 + vertex 0.852162 0.979779 2.48738 + endloop + endfacet + facet normal -0.477741 -0.447429 0.756023 + outer loop + vertex 0.853604 0.981978 2.48959 + vertex 0.852162 0.979779 2.48738 + vertex 0.854089 0.978461 2.48781 + endloop + endfacet + facet normal -0.579919 -0.356695 0.732436 + outer loop + vertex 0.853604 0.981978 2.48959 + vertex 0.852205 0.984947 2.48993 + vertex 0.852162 0.979779 2.48738 + endloop + endfacet + facet normal -0.78338 -0.269869 0.559898 + outer loop + vertex 0.852205 0.984947 2.48993 + vertex 0.850322 0.983005 2.48636 + vertex 0.852162 0.979779 2.48738 + endloop + endfacet + facet normal -0.258558 -0.228712 0.93853 + outer loop + vertex 0.853604 0.981978 2.48959 + vertex 0.85403 0.985354 2.49053 + vertex 0.852205 0.984947 2.48993 + endloop + endfacet + facet normal -0.890419 -0.266702 0.368814 + outer loop + vertex 0.848501 0.986454 2.48445 + vertex 0.848999 0.982391 2.48272 + vertex 0.850322 0.983005 2.48636 + endloop + endfacet + facet normal -0.883174 -0.246031 0.399341 + outer loop + vertex 0.849934 0.988161 2.48867 + vertex 0.848501 0.986454 2.48445 + vertex 0.850322 0.983005 2.48636 + endloop + endfacet + facet normal -0.758791 -0.313739 0.570793 + outer loop + vertex 0.850322 0.983005 2.48636 + vertex 0.852205 0.984947 2.48993 + vertex 0.849934 0.988161 2.48867 + endloop + endfacet + facet normal -0.709276 -0.24334 0.661599 + outer loop + vertex 0.849934 0.988161 2.48867 + vertex 0.852205 0.984947 2.48993 + vertex 0.851699 0.989482 2.49105 + endloop + endfacet + facet normal -0.103434 -0.250517 0.962571 + outer loop + vertex 0.852205 0.984947 2.48993 + vertex 0.853431 0.989119 2.49114 + vertex 0.851699 0.989482 2.49105 + endloop + endfacet + facet normal -0.267265 -0.196761 0.943321 + outer loop + vertex 0.85403 0.985354 2.49053 + vertex 0.853431 0.989119 2.49114 + vertex 0.852205 0.984947 2.48993 + endloop + endfacet + facet normal -0.863039 -0.292983 0.411491 + outer loop + vertex 0.848501 0.986454 2.48445 + vertex 0.849934 0.988161 2.48867 + vertex 0.848048 0.99027 2.48622 + endloop + endfacet + facet normal -0.863169 -0.295614 0.40933 + outer loop + vertex 0.848672 0.991916 2.48872 + vertex 0.848048 0.99027 2.48622 + vertex 0.849934 0.988161 2.48867 + endloop + endfacet + facet normal -0.742839 -0.258044 0.61774 + outer loop + vertex 0.848672 0.991916 2.48872 + vertex 0.849934 0.988161 2.48867 + vertex 0.850235 0.992341 2.49078 + endloop + endfacet + facet normal -0.685525 -0.287893 0.66871 + outer loop + vertex 0.850235 0.992341 2.49078 + vertex 0.849934 0.988161 2.48867 + vertex 0.851699 0.989482 2.49105 + endloop + endfacet + facet normal -0.290719 -0.0587124 0.955005 + outer loop + vertex 0.851699 0.989482 2.49105 + vertex 0.852385 0.993919 2.49153 + vertex 0.850235 0.992341 2.49078 + endloop + endfacet + facet normal -0.0728052 -0.0964753 0.992669 + outer loop + vertex 0.853431 0.989119 2.49114 + vertex 0.852385 0.993919 2.49153 + vertex 0.851699 0.989482 2.49105 + endloop + endfacet + facet normal -0.928048 -0.369165 0.0494398 + outer loop + vertex 0.855 0.998562 2.48 + vertex 0.854428 1 2.48 + vertex 0.855306 0.997742 2.47961 + endloop + endfacet + facet normal -0.741946 -0.260842 0.617638 + outer loop + vertex 0.848672 0.991916 2.48872 + vertex 0.850235 0.992341 2.49078 + vertex 0.848617 0.994795 2.48987 + endloop + endfacet + facet normal -0.666518 -0.171169 0.725572 + outer loop + vertex 0.850235 0.992341 2.49078 + vertex 0.850119 0.996753 2.49172 + vertex 0.848617 0.994795 2.48987 + endloop + endfacet + facet normal -0.183007 -0.20816 0.960821 + outer loop + vertex 0.850235 0.992341 2.49078 + vertex 0.852385 0.993919 2.49153 + vertex 0.850119 0.996753 2.49172 + endloop + endfacet + facet normal -0.0188685 -0.0791669 0.996683 + outer loop + vertex 0.852385 0.993919 2.49153 + vertex 0.852102 0.999318 2.49196 + vertex 0.850119 0.996753 2.49172 + endloop + endfacet + facet normal 0.866173 0.390317 -0.312085 + outer loop + vertex 0.854745 1.00025 2.48119 + vertex 0.855306 0.997742 2.47961 + vertex 0.854428 1 2.48 + endloop + endfacet + facet normal 0.939936 0.182573 -0.288422 + outer loop + vertex 0.854745 1.00025 2.48119 + vertex 0.854428 1 2.48 + vertex 0.854991 1.005 2.485 + endloop + endfacet + facet normal 0.995439 -0.0185119 -0.093582 + outer loop + vertex 0.854991 1.005 2.485 + vertex 0.854428 1 2.48 + vertex 0.854521 1.005 2.48 + endloop + endfacet + facet normal 0.905052 -0.293488 0.307809 + outer loop + vertex 0.854745 1.00025 2.48119 + vertex 0.854991 1.005 2.485 + vertex 0.854652 1.00237 2.48349 + endloop + endfacet + facet normal 0.852198 0.0578432 0.520012 + outer loop + vertex 0.853461 1.00185 2.49049 + vertex 0.853619 1.00586 2.48978 + vertex 0.852254 1.00406 2.49222 + endloop + endfacet + facet normal 0.781906 -0.0593814 0.620561 + outer loop + vertex 0.852254 1.00406 2.49222 + vertex 0.852102 0.999318 2.49196 + vertex 0.853461 1.00185 2.49049 + endloop + endfacet + facet normal 0.34601 -0.0629144 0.936119 + outer loop + vertex 0.852254 1.00406 2.49222 + vertex 0.849833 1.00231 2.493 + vertex 0.852102 0.999318 2.49196 + endloop + endfacet + facet normal 0.159335 -0.213893 0.963775 + outer loop + vertex 0.849833 1.00231 2.493 + vertex 0.850119 0.996753 2.49172 + vertex 0.852102 0.999318 2.49196 + endloop + endfacet + facet normal -0.443965 -0.0751215 0.89289 + outer loop + vertex 0.854991 1.005 2.485 + vertex 0.854145 1.01 2.485 + vertex 0.854184 1.00667 2.48474 + endloop + endfacet + facet normal -0.740103 -0.261178 0.619705 + outer loop + vertex 0.854652 1.00237 2.48349 + vertex 0.854991 1.005 2.485 + vertex 0.854184 1.00667 2.48474 + endloop + endfacet + facet normal 0.923342 0.0753682 0.37651 + outer loop + vertex 0.853619 1.00586 2.48978 + vertex 0.853464 1.01024 2.48929 + vertex 0.852685 1.00813 2.49162 + endloop + endfacet + facet normal 0.879282 -0.022867 0.475752 + outer loop + vertex 0.852254 1.00406 2.49222 + vertex 0.853619 1.00586 2.48978 + vertex 0.852685 1.00813 2.49162 + endloop + endfacet + facet normal 0.509658 -0.222138 0.831206 + outer loop + vertex 0.849833 1.00231 2.493 + vertex 0.850851 1.00798 2.49389 + vertex 0.848794 1.00657 2.49477 + endloop + endfacet + facet normal 0.436224 -0.215627 0.873621 + outer loop + vertex 0.849833 1.00231 2.493 + vertex 0.852254 1.00406 2.49222 + vertex 0.850851 1.00798 2.49389 + endloop + endfacet + facet normal 0.777322 0.0105365 0.629015 + outer loop + vertex 0.852254 1.00406 2.49222 + vertex 0.852685 1.00813 2.49162 + vertex 0.850851 1.00798 2.49389 + endloop + endfacet + facet normal 0.532423 -0.27412 0.800865 + outer loop + vertex 0.850851 1.00798 2.49389 + vertex 0.849152 1.01007 2.49573 + vertex 0.848794 1.00657 2.49477 + endloop + endfacet + facet normal 0.653126 0.0266433 0.75678 + outer loop + vertex 0.854145 1.01 2.485 + vertex 0.853941 1.015 2.485 + vertex 0.853799 1.01118 2.48526 + endloop + endfacet + facet normal 0.442753 -0.0649356 0.894289 + outer loop + vertex 0.854184 1.00667 2.48474 + vertex 0.854145 1.01 2.485 + vertex 0.853799 1.01118 2.48526 + endloop + endfacet + facet normal 0.911702 0.195294 0.361469 + outer loop + vertex 0.853464 1.01024 2.48929 + vertex 0.853224 1.0134 2.48818 + vertex 0.852205 1.01268 2.49114 + endloop + endfacet + facet normal 0.894788 0.13891 0.424332 + outer loop + vertex 0.852685 1.00813 2.49162 + vertex 0.853464 1.01024 2.48929 + vertex 0.852205 1.01268 2.49114 + endloop + endfacet + facet normal 0.764609 0.146542 0.627614 + outer loop + vertex 0.852685 1.00813 2.49162 + vertex 0.852205 1.01268 2.49114 + vertex 0.850851 1.00798 2.49389 + endloop + endfacet + facet normal 0.879478 0.0243919 0.475315 + outer loop + vertex 0.852205 1.01268 2.49114 + vertex 0.850354 1.01348 2.49453 + vertex 0.850851 1.00798 2.49389 + endloop + endfacet + facet normal 0.727659 -0.0138105 0.6858 + outer loop + vertex 0.850354 1.01348 2.49453 + vertex 0.849152 1.01007 2.49573 + vertex 0.850851 1.00798 2.49389 + endloop + endfacet + facet normal 0.705451 0.00215904 0.708755 + outer loop + vertex 0.848454 1.01397 2.49642 + vertex 0.849152 1.01007 2.49573 + vertex 0.850354 1.01348 2.49453 + endloop + endfacet + facet normal 0.918228 -0.00743786 0.395982 + outer loop + vertex 0.853425 1.01391 2.48618 + vertex 0.853799 1.01118 2.48526 + vertex 0.853941 1.015 2.485 + endloop + endfacet + facet normal 0.871407 0.104584 0.479283 + outer loop + vertex 0.853425 1.01391 2.48618 + vertex 0.853941 1.015 2.485 + vertex 0.852539 1.01666 2.48719 + endloop + endfacet + facet normal 0.881551 0.15921 0.444432 + outer loop + vertex 0.852539 1.01666 2.48719 + vertex 0.853941 1.015 2.485 + vertex 0.853038 1.02 2.485 + endloop + endfacet + facet normal 0.955197 0.249626 0.159015 + outer loop + vertex 0.853224 1.0134 2.48818 + vertex 0.853425 1.01391 2.48618 + vertex 0.852539 1.01666 2.48719 + endloop + endfacet + facet normal 0.877367 0.299302 0.375027 + outer loop + vertex 0.853224 1.0134 2.48818 + vertex 0.852539 1.01666 2.48719 + vertex 0.852205 1.01268 2.49114 + endloop + endfacet + facet normal 0.940269 0.19708 0.277584 + outer loop + vertex 0.852205 1.01268 2.49114 + vertex 0.852539 1.01666 2.48719 + vertex 0.851072 1.01804 2.49117 + endloop + endfacet + facet normal 0.879946 0.18338 0.438254 + outer loop + vertex 0.852205 1.01268 2.49114 + vertex 0.851072 1.01804 2.49117 + vertex 0.850354 1.01348 2.49453 + endloop + endfacet + facet normal 0.925188 0.119051 0.360352 + outer loop + vertex 0.851072 1.01804 2.49117 + vertex 0.84954 1.01845 2.49497 + vertex 0.850354 1.01348 2.49453 + endloop + endfacet + facet normal 0.711188 0.0537787 0.700942 + outer loop + vertex 0.84954 1.01845 2.49497 + vertex 0.848454 1.01397 2.49642 + vertex 0.850354 1.01348 2.49453 + endloop + endfacet + facet normal 0.712122 0.0532589 0.700032 + outer loop + vertex 0.847462 1.01882 2.49706 + vertex 0.848454 1.01397 2.49642 + vertex 0.84954 1.01845 2.49497 + endloop + endfacet + facet normal 0.727175 0.53104 0.434986 + outer loop + vertex 0.85 1.02416 2.485 + vertex 0.853038 1.02 2.485 + vertex 0.855 1.02 2.48172 + endloop + endfacet + facet normal 0.727194 0.545534 0.416631 + outer loop + vertex 0.85 1.02416 2.485 + vertex 0.855 1.02 2.48172 + vertex 0.85 1.025 2.4839 + endloop + endfacet + facet normal 0.721982 0.525965 0.449559 + outer loop + vertex 0.85 1.025 2.4839 + vertex 0.855 1.02 2.48172 + vertex 0.853567 1.02444 2.47883 + endloop + endfacet + facet normal 0.562085 0.410478 -0.718031 + outer loop + vertex 0.85 1.025 2.48548 + vertex 0.853038 1.02 2.485 + vertex 0.85 1.02416 2.485 + endloop + endfacet + facet normal 0.850144 0.50098 0.162092 + outer loop + vertex 0.85 1.025 2.48548 + vertex 0.850869 1.02322 2.48644 + vertex 0.853038 1.02 2.485 + endloop + endfacet + facet normal 0.772426 0.262922 0.578126 + outer loop + vertex 0.850869 1.02322 2.48644 + vertex 0.852539 1.01666 2.48719 + vertex 0.853038 1.02 2.485 + endloop + endfacet + facet normal 0.930986 0.265737 0.250297 + outer loop + vertex 0.852539 1.01666 2.48719 + vertex 0.850869 1.02322 2.48644 + vertex 0.851072 1.01804 2.49117 + endloop + endfacet + facet normal 0.97654 0.165031 0.138327 + outer loop + vertex 0.850869 1.02322 2.48644 + vertex 0.850119 1.02325 2.49168 + vertex 0.851072 1.01804 2.49117 + endloop + endfacet + facet normal 0.923972 0.133936 0.358242 + outer loop + vertex 0.851072 1.01804 2.49117 + vertex 0.850119 1.02325 2.49168 + vertex 0.84954 1.01845 2.49497 + endloop + endfacet + facet normal 0.93878 0.110313 0.326379 + outer loop + vertex 0.850119 1.02325 2.49168 + vertex 0.848758 1.02294 2.4957 + vertex 0.84954 1.01845 2.49497 + endloop + endfacet + facet normal 0.709176 0.00862083 0.704979 + outer loop + vertex 0.848758 1.02294 2.4957 + vertex 0.847462 1.01882 2.49706 + vertex 0.84954 1.01845 2.49497 + endloop + endfacet + facet normal 0.798046 -0.0537708 0.600193 + outer loop + vertex 0.847449 1.02262 2.49741 + vertex 0.847462 1.01882 2.49706 + vertex 0.848758 1.02294 2.4957 + endloop + endfacet + facet normal 0.805219 -0.127877 0.579024 + outer loop + vertex 0.850662 1.02724 2.48347 + vertex 0.85 1.02998 2.485 + vertex 0.85 1.025 2.4839 + endloop + endfacet + facet normal 0.902635 -0.193852 0.38428 + outer loop + vertex 0.850662 1.02724 2.48347 + vertex 0.85 1.025 2.4839 + vertex 0.852754 1.02867 2.47928 + endloop + endfacet + facet normal 0.819272 0.0965868 0.565211 + outer loop + vertex 0.852754 1.02867 2.47928 + vertex 0.85 1.025 2.4839 + vertex 0.853567 1.02444 2.47883 + endloop + endfacet + facet normal 0.668066 -0.071416 -0.740667 + outer loop + vertex 0.85 1.02998 2.485 + vertex 0.850869 1.02322 2.48644 + vertex 0.85 1.025 2.48548 + endloop + endfacet + facet normal -0.977336 -0.155913 -0.143196 + outer loop + vertex 0.85 1.02998 2.485 + vertex 0.850662 1.02724 2.48347 + vertex 0.850869 1.02322 2.48644 + endloop + endfacet + facet normal 0.991771 0.105048 0.0731782 + outer loop + vertex 0.850662 1.02724 2.48347 + vertex 0.850211 1.02842 2.48788 + vertex 0.850869 1.02322 2.48644 + endloop + endfacet + facet normal 0.98639 0.0857971 0.140263 + outer loop + vertex 0.850869 1.02322 2.48644 + vertex 0.850211 1.02842 2.48788 + vertex 0.850119 1.02325 2.49168 + endloop + endfacet + facet normal 0.980427 0.10517 0.166439 + outer loop + vertex 0.850211 1.02842 2.48788 + vertex 0.849296 1.02802 2.49352 + vertex 0.850119 1.02325 2.49168 + endloop + endfacet + facet normal 0.926227 -0.114046 0.3593 + outer loop + vertex 0.847645 1.02619 2.49719 + vertex 0.849296 1.02802 2.49352 + vertex 0.848436 1.02982 2.4963 + endloop + endfacet + facet normal 0.888272 0.0988443 0.448556 + outer loop + vertex 0.847645 1.02619 2.49719 + vertex 0.848758 1.02294 2.4957 + vertex 0.849296 1.02802 2.49352 + endloop + endfacet + facet normal 0.945533 0.0388814 0.323197 + outer loop + vertex 0.848758 1.02294 2.4957 + vertex 0.850119 1.02325 2.49168 + vertex 0.849296 1.02802 2.49352 + endloop + endfacet + facet normal 0.794867 -0.00584758 0.606755 + outer loop + vertex 0.848758 1.02294 2.4957 + vertex 0.847645 1.02619 2.49719 + vertex 0.847449 1.02262 2.49741 + endloop + endfacet + facet normal 0.912176 -0.023463 0.409127 + outer loop + vertex 0.852754 1.02867 2.47928 + vertex 0.853322 1.03429 2.47834 + vertex 0.851154 1.03127 2.483 + endloop + endfacet + facet normal 0.901124 -0.0593367 0.429482 + outer loop + vertex 0.850662 1.02724 2.48347 + vertex 0.852754 1.02867 2.47928 + vertex 0.851154 1.03127 2.483 + endloop + endfacet + facet normal 0.967632 0.194049 0.16135 + outer loop + vertex 0.85 1.0312 2.49 + vertex 0.851154 1.03127 2.483 + vertex 0.85 1.035 2.48543 + endloop + endfacet + facet normal 0.985585 -0.048979 0.161938 + outer loop + vertex 0.85 1.0312 2.49 + vertex 0.850211 1.02842 2.48788 + vertex 0.851154 1.03127 2.483 + endloop + endfacet + facet normal 0.986022 -0.105123 0.12927 + outer loop + vertex 0.850211 1.02842 2.48788 + vertex 0.850662 1.02724 2.48347 + vertex 0.851154 1.03127 2.483 + endloop + endfacet + facet normal -0.968601 -0.193184 0.156502 + outer loop + vertex 0.84961 1.03211 2.48871 + vertex 0.850211 1.02842 2.48788 + vertex 0.85 1.0312 2.49 + endloop + endfacet + facet normal 0.98735 0.158013 0.0130746 + outer loop + vertex 0.84961 1.03211 2.48871 + vertex 0.849593 1.03204 2.49083 + vertex 0.850211 1.02842 2.48788 + endloop + endfacet + facet normal 0.986067 0.0357561 0.162459 + outer loop + vertex 0.849593 1.03204 2.49083 + vertex 0.849296 1.02802 2.49352 + vertex 0.850211 1.02842 2.48788 + endloop + endfacet + facet normal 0.934858 0.0224706 0.354309 + outer loop + vertex 0.848436 1.02982 2.4963 + vertex 0.849013 1.03286 2.49459 + vertex 0.848047 1.03209 2.49719 + endloop + endfacet + facet normal 0.953484 -0.0110142 0.301241 + outer loop + vertex 0.848436 1.02982 2.4963 + vertex 0.849296 1.02802 2.49352 + vertex 0.849013 1.03286 2.49459 + endloop + endfacet + facet normal 0.988793 0.0252867 0.147134 + outer loop + vertex 0.849296 1.02802 2.49352 + vertex 0.849593 1.03204 2.49083 + vertex 0.849013 1.03286 2.49459 + endloop + endfacet + facet normal 0.935017 0.0211357 0.353972 + outer loop + vertex 0.849013 1.03286 2.49459 + vertex 0.848183 1.03471 2.49667 + vertex 0.848047 1.03209 2.49719 + endloop + endfacet + facet normal 0.877083 0.0188009 0.479971 + outer loop + vertex 0.853322 1.03429 2.47834 + vertex 0.853369 1.0397 2.47804 + vertex 0.851497 1.03645 2.48159 + endloop + endfacet + facet normal 0.887947 0.0650726 0.455319 + outer loop + vertex 0.851154 1.03127 2.483 + vertex 0.853322 1.03429 2.47834 + vertex 0.851497 1.03645 2.48159 + endloop + endfacet + facet normal 0.925635 0.0410432 0.376184 + outer loop + vertex 0.851497 1.03645 2.48159 + vertex 0.85 1.035 2.48543 + vertex 0.851154 1.03127 2.483 + endloop + endfacet + facet normal 0.93858 -0.0786156 0.335987 + outer loop + vertex 0.85 1.04 2.4866 + vertex 0.85 1.035 2.48543 + vertex 0.851497 1.03645 2.48159 + endloop + endfacet + facet normal 0.992261 0.123597 0.0119509 + outer loop + vertex 0.84922 1.03514 2.48976 + vertex 0.849593 1.03204 2.49083 + vertex 0.84961 1.03211 2.48871 + endloop + endfacet + facet normal 0.993252 0.115312 -0.0123773 + outer loop + vertex 0.849199 1.0356 2.4923 + vertex 0.849593 1.03204 2.49083 + vertex 0.84922 1.03514 2.48976 + endloop + endfacet + facet normal 0.976994 0.17338 0.124188 + outer loop + vertex 0.848764 1.03625 2.49481 + vertex 0.849199 1.0356 2.4923 + vertex 0.848606 1.03816 2.49338 + endloop + endfacet + facet normal 0.985956 0.0624993 0.154867 + outer loop + vertex 0.848764 1.03625 2.49481 + vertex 0.849013 1.03286 2.49459 + vertex 0.849199 1.0356 2.4923 + endloop + endfacet + facet normal 0.988623 0.0511087 0.141462 + outer loop + vertex 0.849013 1.03286 2.49459 + vertex 0.849593 1.03204 2.49083 + vertex 0.849199 1.0356 2.4923 + endloop + endfacet + facet normal 0.941783 0.0479738 0.332781 + outer loop + vertex 0.849013 1.03286 2.49459 + vertex 0.848764 1.03625 2.49481 + vertex 0.848183 1.03471 2.49667 + endloop + endfacet + facet normal 0.88262 0.00185694 0.470083 + outer loop + vertex 0.853369 1.0397 2.47804 + vertex 0.853271 1.04502 2.4782 + vertex 0.851421 1.04164 2.48169 + endloop + endfacet + facet normal 0.883026 0.00371564 0.46931 + outer loop + vertex 0.851497 1.03645 2.48159 + vertex 0.853369 1.0397 2.47804 + vertex 0.851421 1.04164 2.48169 + endloop + endfacet + facet normal 0.959774 0.00854143 0.280644 + outer loop + vertex 0.851421 1.04164 2.48169 + vertex 0.85 1.04 2.4866 + vertex 0.851497 1.03645 2.48159 + endloop + endfacet + facet normal 0.964079 -0.0624746 0.258165 + outer loop + vertex 0.85 1.045 2.48781 + vertex 0.85 1.04 2.4866 + vertex 0.851421 1.04164 2.48169 + endloop + endfacet + facet normal 0.987261 0.157842 -0.0200373 + outer loop + vertex 0.84922 1.03514 2.48976 + vertex 0.848797 1.03796 2.49115 + vertex 0.849199 1.0356 2.4923 + endloop + endfacet + facet normal 0.977962 0.198158 0.0657619 + outer loop + vertex 0.849199 1.0356 2.4923 + vertex 0.848797 1.03796 2.49115 + vertex 0.848606 1.03816 2.49338 + endloop + endfacet + facet normal 0.883482 -0.00139279 0.468464 + outer loop + vertex 0.853271 1.04502 2.4782 + vertex 0.853155 1.0502 2.47844 + vertex 0.851208 1.04688 2.4821 + endloop + endfacet + facet normal 0.883629 -0.000647839 0.468187 + outer loop + vertex 0.851421 1.04164 2.48169 + vertex 0.853271 1.04502 2.4782 + vertex 0.851208 1.04688 2.4821 + endloop + endfacet + facet normal 0.976534 0.0230312 0.214129 + outer loop + vertex 0.851208 1.04688 2.4821 + vertex 0.85 1.045 2.48781 + vertex 0.851421 1.04164 2.48169 + endloop + endfacet + facet normal 0.979405 -0.0185031 0.201056 + outer loop + vertex 0.85 1.05 2.48827 + vertex 0.85 1.045 2.48781 + vertex 0.851208 1.04688 2.4821 + endloop + endfacet + facet normal 0.852178 0.00793189 0.523193 + outer loop + vertex 0.853155 1.0502 2.47844 + vertex 0.853098 1.05519 2.47845 + vertex 0.850959 1.05191 2.48199 + endloop + endfacet + facet normal 0.860655 0.0537549 0.506344 + outer loop + vertex 0.851208 1.04688 2.4821 + vertex 0.853155 1.0502 2.47844 + vertex 0.850959 1.05191 2.48199 + endloop + endfacet + facet normal 0.984688 0.0523439 0.16628 + outer loop + vertex 0.850959 1.05191 2.48199 + vertex 0.85 1.05 2.48827 + vertex 0.851208 1.04688 2.4821 + endloop + endfacet + facet normal 0.731875 0.61266 0.298339 + outer loop + vertex 0.848125 1.05364 2.48539 + vertex 0.85 1.05 2.48827 + vertex 0.850959 1.05191 2.48199 + endloop + endfacet + facet normal 0.823292 0.049201 0.565482 + outer loop + vertex 0.853098 1.05519 2.47845 + vertex 0.853077 1.05996 2.47807 + vertex 0.851 1.05696 2.48136 + endloop + endfacet + facet normal 0.82659 0.0634062 0.559222 + outer loop + vertex 0.850959 1.05191 2.48199 + vertex 0.853098 1.05519 2.47845 + vertex 0.851 1.05696 2.48136 + endloop + endfacet + facet normal 0.784192 0.0709136 0.616453 + outer loop + vertex 0.851 1.05696 2.48136 + vertex 0.848125 1.05364 2.48539 + vertex 0.850959 1.05191 2.48199 + endloop + endfacet + facet normal 0.794136 0.0492723 0.60574 + outer loop + vertex 0.848782 1.05913 2.48409 + vertex 0.848125 1.05364 2.48539 + vertex 0.851 1.05696 2.48136 + endloop + endfacet + facet normal 0.845783 0.106395 0.52281 + outer loop + vertex 0.853077 1.05996 2.47807 + vertex 0.853146 1.06378 2.47718 + vertex 0.85134 1.06279 2.4803 + endloop + endfacet + facet normal 0.820618 0.054746 0.568849 + outer loop + vertex 0.851 1.05696 2.48136 + vertex 0.853077 1.05996 2.47807 + vertex 0.85134 1.06279 2.4803 + endloop + endfacet + facet normal 0.798173 0.0615408 0.599276 + outer loop + vertex 0.85134 1.06279 2.4803 + vertex 0.848782 1.05913 2.48409 + vertex 0.851 1.05696 2.48136 + endloop + endfacet + facet normal 0.812414 0.0338545 0.582098 + outer loop + vertex 0.848893 1.06468 2.48361 + vertex 0.848782 1.05913 2.48409 + vertex 0.85134 1.06279 2.4803 + endloop + endfacet + facet normal 0.914709 0.20181 0.350114 + outer loop + vertex 0.853719 1.06617 2.47481 + vertex 0.853643 1.06907 2.47334 + vertex 0.852658 1.06778 2.47666 + endloop + endfacet + facet normal 0.909825 0.161465 0.382291 + outer loop + vertex 0.853146 1.06378 2.47718 + vertex 0.853719 1.06617 2.47481 + vertex 0.852658 1.06778 2.47666 + endloop + endfacet + facet normal 0.82843 0.171361 0.533235 + outer loop + vertex 0.853146 1.06378 2.47718 + vertex 0.852658 1.06778 2.47666 + vertex 0.85134 1.06279 2.4803 + endloop + endfacet + facet normal 0.893098 0.0869796 0.441374 + outer loop + vertex 0.85134 1.06279 2.4803 + vertex 0.852658 1.06778 2.47666 + vertex 0.850808 1.06854 2.48025 + endloop + endfacet + facet normal 0.822785 0.0816707 0.562454 + outer loop + vertex 0.850808 1.06854 2.48025 + vertex 0.848893 1.06468 2.48361 + vertex 0.85134 1.06279 2.4803 + endloop + endfacet + facet normal 0.854736 0.0273584 0.518342 + outer loop + vertex 0.848699 1.07022 2.48364 + vertex 0.848893 1.06468 2.48361 + vertex 0.850808 1.06854 2.48025 + endloop + endfacet + facet normal 0.957317 0.157068 0.242641 + outer loop + vertex 0.85391 1.07163 2.47057 + vertex 0.853691 1.07553 2.46891 + vertex 0.853186 1.07238 2.47294 + endloop + endfacet + facet normal 0.957038 0.160552 0.241456 + outer loop + vertex 0.853643 1.06907 2.47334 + vertex 0.85391 1.07163 2.47057 + vertex 0.853186 1.07238 2.47294 + endloop + endfacet + facet normal 0.925309 0.167829 0.340053 + outer loop + vertex 0.853643 1.06907 2.47334 + vertex 0.853186 1.07238 2.47294 + vertex 0.852658 1.06778 2.47666 + endloop + endfacet + facet normal 0.946555 0.12944 0.295429 + outer loop + vertex 0.852658 1.06778 2.47666 + vertex 0.853186 1.07238 2.47294 + vertex 0.852045 1.07292 2.47636 + endloop + endfacet + facet normal 0.892468 0.130728 0.431754 + outer loop + vertex 0.852658 1.06778 2.47666 + vertex 0.852045 1.07292 2.47636 + vertex 0.850808 1.06854 2.48025 + endloop + endfacet + facet normal 0.928242 0.0629419 0.366612 + outer loop + vertex 0.852045 1.07292 2.47636 + vertex 0.85049 1.07387 2.48014 + vertex 0.850808 1.06854 2.48025 + endloop + endfacet + facet normal 0.860859 0.061763 0.505081 + outer loop + vertex 0.85049 1.07387 2.48014 + vertex 0.848699 1.07022 2.48364 + vertex 0.850808 1.06854 2.48025 + endloop + endfacet + facet normal 0.885495 0.0107699 0.464524 + outer loop + vertex 0.8486 1.07545 2.4837 + vertex 0.848699 1.07022 2.48364 + vertex 0.85049 1.07387 2.48014 + endloop + endfacet + facet normal 0.970157 0.128785 0.205452 + outer loop + vertex 0.853691 1.07553 2.46891 + vertex 0.853546 1.07938 2.46719 + vertex 0.852883 1.07781 2.4713 + endloop + endfacet + facet normal 0.96945 0.119071 0.214452 + outer loop + vertex 0.853186 1.07238 2.47294 + vertex 0.853691 1.07553 2.46891 + vertex 0.852883 1.07781 2.4713 + endloop + endfacet + facet normal 0.945522 0.141581 0.29316 + outer loop + vertex 0.853186 1.07238 2.47294 + vertex 0.852883 1.07781 2.4713 + vertex 0.852045 1.07292 2.47636 + endloop + endfacet + facet normal 0.967902 0.0805964 0.238055 + outer loop + vertex 0.852883 1.07781 2.4713 + vertex 0.851712 1.07815 2.47595 + vertex 0.852045 1.07292 2.47636 + endloop + endfacet + facet normal 0.9286 0.0878528 0.360533 + outer loop + vertex 0.852045 1.07292 2.47636 + vertex 0.851712 1.07815 2.47595 + vertex 0.85049 1.07387 2.48014 + endloop + endfacet + facet normal 0.949887 0.0331227 0.310835 + outer loop + vertex 0.851712 1.07815 2.47595 + vertex 0.850345 1.07893 2.48004 + vertex 0.85049 1.07387 2.48014 + endloop + endfacet + facet normal 0.889273 0.034197 0.456096 + outer loop + vertex 0.850345 1.07893 2.48004 + vertex 0.8486 1.07545 2.4837 + vertex 0.85049 1.07387 2.48014 + endloop + endfacet + facet normal 0.904481 -0.00465303 0.426488 + outer loop + vertex 0.84864 1.08038 2.48367 + vertex 0.8486 1.07545 2.4837 + vertex 0.850345 1.07893 2.48004 + endloop + endfacet + facet normal -0.250194 -0.0445935 0.967168 + outer loop + vertex 0.855 1.08353 2.46 + vertex 0.854738 1.085 2.46 + vertex 0.854275 1.08215 2.45975 + endloop + endfacet + facet normal 0.975163 0.160906 0.152205 + outer loop + vertex 0.853747 1.0813 2.46457 + vertex 0.853641 1.08364 2.46277 + vertex 0.853166 1.08321 2.46627 + endloop + endfacet + facet normal 0.974388 0.138704 0.176999 + outer loop + vertex 0.853546 1.07938 2.46719 + vertex 0.853747 1.0813 2.46457 + vertex 0.853166 1.08321 2.46627 + endloop + endfacet + facet normal 0.966391 0.146159 0.211485 + outer loop + vertex 0.853546 1.07938 2.46719 + vertex 0.853166 1.08321 2.46627 + vertex 0.852883 1.07781 2.4713 + endloop + endfacet + facet normal 0.981192 0.101435 0.164238 + outer loop + vertex 0.852883 1.07781 2.4713 + vertex 0.853166 1.08321 2.46627 + vertex 0.852356 1.08315 2.47115 + endloop + endfacet + facet normal 0.966368 0.10194 0.236097 + outer loop + vertex 0.852883 1.07781 2.4713 + vertex 0.852356 1.08315 2.47115 + vertex 0.851712 1.07815 2.47595 + endloop + endfacet + facet normal 0.979694 0.0578944 0.19196 + outer loop + vertex 0.852356 1.08315 2.47115 + vertex 0.851434 1.08323 2.47583 + vertex 0.851712 1.07815 2.47595 + endloop + endfacet + facet normal 0.950202 0.0588511 0.306028 + outer loop + vertex 0.851712 1.07815 2.47595 + vertex 0.851434 1.08323 2.47583 + vertex 0.850345 1.07893 2.48004 + endloop + endfacet + facet normal 0.962507 0.0209132 0.270449 + outer loop + vertex 0.851434 1.08323 2.47583 + vertex 0.850242 1.0838 2.48003 + vertex 0.850345 1.07893 2.48004 + endloop + endfacet + facet normal 0.908093 0.0200663 0.418287 + outer loop + vertex 0.850242 1.0838 2.48003 + vertex 0.84864 1.08038 2.48367 + vertex 0.850345 1.07893 2.48004 + endloop + endfacet + facet normal 0.915998 -0.00189234 0.401178 + outer loop + vertex 0.848642 1.08517 2.48369 + vertex 0.84864 1.08038 2.48367 + vertex 0.850242 1.0838 2.48003 + endloop + endfacet + facet normal 0.751129 -0.178108 0.635675 + outer loop + vertex 0.853897 1.08398 2.46071 + vertex 0.854275 1.08215 2.45975 + vertex 0.854738 1.085 2.46 + endloop + endfacet + facet normal 0.675463 -0.0463257 0.735937 + outer loop + vertex 0.853897 1.08398 2.46071 + vertex 0.854738 1.085 2.46 + vertex 0.853202 1.08781 2.46159 + endloop + endfacet + facet normal 0.779272 0.0744937 0.622243 + outer loop + vertex 0.853202 1.08781 2.46159 + vertex 0.854738 1.085 2.46 + vertex 0.85426 1.09 2.46 + endloop + endfacet + facet normal 0.978915 0.144196 0.144681 + outer loop + vertex 0.853641 1.08364 2.46277 + vertex 0.853897 1.08398 2.46071 + vertex 0.853202 1.08781 2.46159 + endloop + endfacet + facet normal 0.977772 0.145784 0.150694 + outer loop + vertex 0.853641 1.08364 2.46277 + vertex 0.853202 1.08781 2.46159 + vertex 0.853166 1.08321 2.46627 + endloop + endfacet + facet normal 0.975233 0.154008 0.15875 + outer loop + vertex 0.853166 1.08321 2.46627 + vertex 0.853202 1.08781 2.46159 + vertex 0.852372 1.08828 2.46623 + endloop + endfacet + facet normal 0.974407 0.153921 0.163828 + outer loop + vertex 0.853166 1.08321 2.46627 + vertex 0.852372 1.08828 2.46623 + vertex 0.852356 1.08315 2.47115 + endloop + endfacet + facet normal 0.988501 0.102976 0.110733 + outer loop + vertex 0.852372 1.08828 2.46623 + vertex 0.85182 1.08821 2.47123 + vertex 0.852356 1.08315 2.47115 + endloop + endfacet + facet normal 0.976509 0.100553 0.190575 + outer loop + vertex 0.852356 1.08315 2.47115 + vertex 0.85182 1.08821 2.47123 + vertex 0.851434 1.08323 2.47583 + endloop + endfacet + facet normal 0.986704 0.0623411 0.150096 + outer loop + vertex 0.85182 1.08821 2.47123 + vertex 0.851103 1.08813 2.47598 + vertex 0.851434 1.08323 2.47583 + endloop + endfacet + facet normal 0.962413 0.057328 0.265471 + outer loop + vertex 0.851434 1.08323 2.47583 + vertex 0.851103 1.08813 2.47598 + vertex 0.850242 1.0838 2.48003 + endloop + endfacet + facet normal 0.969935 0.0330466 0.241109 + outer loop + vertex 0.851103 1.08813 2.47598 + vertex 0.850035 1.08858 2.48021 + vertex 0.850242 1.0838 2.48003 + endloop + endfacet + facet normal 0.919392 0.0251406 0.392539 + outer loop + vertex 0.850035 1.08858 2.48021 + vertex 0.848642 1.08517 2.48369 + vertex 0.850242 1.0838 2.48003 + endloop + endfacet + facet normal 0.924563 0.0111086 0.380868 + outer loop + vertex 0.848495 1.09004 2.48391 + vertex 0.848642 1.08517 2.48369 + vertex 0.850035 1.08858 2.48021 + endloop + endfacet + facet normal 0.695304 0.170216 0.698268 + outer loop + vertex 0.85426 1.09 2.46 + vertex 0.853036 1.095 2.46 + vertex 0.853202 1.08781 2.46159 + endloop + endfacet + facet normal 0.821635 0.140928 0.552318 + outer loop + vertex 0.853036 1.095 2.46 + vertex 0.85184 1.09354 2.46215 + vertex 0.853202 1.08781 2.46159 + endloop + endfacet + facet normal 0.964969 0.214718 0.150769 + outer loop + vertex 0.853202 1.08781 2.46159 + vertex 0.85184 1.09354 2.46215 + vertex 0.852372 1.08828 2.46623 + endloop + endfacet + facet normal 0.981107 0.170419 0.0915713 + outer loop + vertex 0.85184 1.09354 2.46215 + vertex 0.851466 1.09323 2.46672 + vertex 0.852372 1.08828 2.46623 + endloop + endfacet + facet normal 0.979513 0.168235 0.110683 + outer loop + vertex 0.852372 1.08828 2.46623 + vertex 0.851466 1.09323 2.46672 + vertex 0.85182 1.08821 2.47123 + endloop + endfacet + facet normal 0.989297 0.129665 0.0669224 + outer loop + vertex 0.851466 1.09323 2.46672 + vertex 0.85116 1.09299 2.47173 + vertex 0.85182 1.08821 2.47123 + endloop + endfacet + facet normal 0.981375 0.119744 0.150215 + outer loop + vertex 0.85182 1.08821 2.47123 + vertex 0.85116 1.09299 2.47173 + vertex 0.851103 1.08813 2.47598 + endloop + endfacet + facet normal 0.987793 0.095751 0.122866 + outer loop + vertex 0.85116 1.09299 2.47173 + vertex 0.850586 1.09279 2.4765 + vertex 0.851103 1.08813 2.47598 + endloop + endfacet + facet normal 0.96845 0.0809593 0.235692 + outer loop + vertex 0.851103 1.08813 2.47598 + vertex 0.850586 1.09279 2.4765 + vertex 0.850035 1.08858 2.48021 + endloop + endfacet + facet normal 0.973925 0.0642832 0.217572 + outer loop + vertex 0.850586 1.09279 2.4765 + vertex 0.849642 1.09319 2.48061 + vertex 0.850035 1.08858 2.48021 + endloop + endfacet + facet normal 0.92854 0.0474021 0.368193 + outer loop + vertex 0.849642 1.09319 2.48061 + vertex 0.848495 1.09004 2.48391 + vertex 0.850035 1.08858 2.48021 + endloop + endfacet + facet normal 0.947313 -0.00977071 0.32016 + outer loop + vertex 0.848426 1.09512 2.48426 + vertex 0.848495 1.09004 2.48391 + vertex 0.849642 1.09319 2.48061 + endloop + endfacet + facet normal 0.746704 0.278374 0.604104 + outer loop + vertex 0.853036 1.095 2.46 + vertex 0.851172 1.1 2.46 + vertex 0.85184 1.09354 2.46215 + endloop + endfacet + facet normal 0.954161 0.178621 0.24015 + outer loop + vertex 0.851172 1.1 2.46 + vertex 0.850618 1.09824 2.46351 + vertex 0.85184 1.09354 2.46215 + endloop + endfacet + facet normal 0.969839 0.224784 0.0942588 + outer loop + vertex 0.85184 1.09354 2.46215 + vertex 0.850618 1.09824 2.46351 + vertex 0.851466 1.09323 2.46672 + endloop + endfacet + facet normal 0.978531 0.199354 0.0523051 + outer loop + vertex 0.850618 1.09824 2.46351 + vertex 0.850509 1.09764 2.46782 + vertex 0.851466 1.09323 2.46672 + endloop + endfacet + facet normal 0.978335 0.195014 0.069497 + outer loop + vertex 0.851466 1.09323 2.46672 + vertex 0.850509 1.09764 2.46782 + vertex 0.85116 1.09299 2.47173 + endloop + endfacet + facet normal 0.982561 0.179126 0.0498726 + outer loop + vertex 0.850509 1.09764 2.46782 + vertex 0.850312 1.09733 2.47284 + vertex 0.85116 1.09299 2.47173 + endloop + endfacet + facet normal 0.979328 0.159499 0.124402 + outer loop + vertex 0.85116 1.09299 2.47173 + vertex 0.850312 1.09733 2.47284 + vertex 0.850586 1.09279 2.4765 + endloop + endfacet + facet normal 0.982932 0.147763 0.109593 + outer loop + vertex 0.850312 1.09733 2.47284 + vertex 0.849837 1.097 2.47754 + vertex 0.850586 1.09279 2.4765 + endloop + endfacet + facet normal 0.97 0.120156 0.211337 + outer loop + vertex 0.850586 1.09279 2.4765 + vertex 0.849837 1.097 2.47754 + vertex 0.849642 1.09319 2.48061 + endloop + endfacet + facet normal 0.97734 0.0999162 0.186609 + outer loop + vertex 0.849837 1.097 2.47754 + vertex 0.849179 1.0969 2.48104 + vertex 0.849642 1.09319 2.48061 + endloop + endfacet + facet normal 0.958211 0.0874903 0.272355 + outer loop + vertex 0.849179 1.0969 2.48104 + vertex 0.848426 1.09512 2.48426 + vertex 0.849642 1.09319 2.48061 + endloop + endfacet + facet normal 0.971284 0.01847 0.237205 + outer loop + vertex 0.848522 1.09934 2.48354 + vertex 0.848426 1.09512 2.48426 + vertex 0.849179 1.0969 2.48104 + endloop + endfacet + facet normal 0.575821 0.344316 -0.741537 + outer loop + vertex 0.85 1.1 2.45909 + vertex 0.85 1.10196 2.46 + vertex 0.851172 1.1 2.46 + endloop + endfacet + facet normal 0.982079 0.0520817 0.181133 + outer loop + vertex 0.851172 1.1 2.46 + vertex 0.85 1.10471 2.465 + vertex 0.850618 1.09824 2.46351 + endloop + endfacet + facet normal 0.82599 0.493906 -0.271659 + outer loop + vertex 0.85 1.10196 2.46 + vertex 0.85 1.10471 2.465 + vertex 0.851172 1.1 2.46 + endloop + endfacet + facet normal 0.978689 0.198603 0.0522049 + outer loop + vertex 0.850618 1.09824 2.46351 + vertex 0.849758 1.10191 2.46566 + vertex 0.850509 1.09764 2.46782 + endloop + endfacet + facet normal 0.931598 0.00524804 0.363453 + outer loop + vertex 0.85 1.10471 2.465 + vertex 0.849758 1.10191 2.46566 + vertex 0.850618 1.09824 2.46351 + endloop + endfacet + facet normal 0.979072 0.197055 0.0508648 + outer loop + vertex 0.850509 1.09764 2.46782 + vertex 0.849623 1.10153 2.46982 + vertex 0.850312 1.09733 2.47284 + endloop + endfacet + facet normal 0.979026 0.197518 0.0499429 + outer loop + vertex 0.849758 1.10191 2.46566 + vertex 0.849623 1.10153 2.46982 + vertex 0.850509 1.09764 2.46782 + endloop + endfacet + facet normal 0.977583 0.178791 0.111203 + outer loop + vertex 0.850312 1.09733 2.47284 + vertex 0.849352 1.10126 2.47496 + vertex 0.849837 1.097 2.47754 + endloop + endfacet + facet normal 0.976776 0.204975 0.0624046 + outer loop + vertex 0.849623 1.10153 2.46982 + vertex 0.849352 1.10126 2.47496 + vertex 0.850312 1.09733 2.47284 + endloop + endfacet + facet normal 0.977086 0.102335 0.18663 + outer loop + vertex 0.849837 1.097 2.47754 + vertex 0.848994 1.10071 2.47992 + vertex 0.849179 1.0969 2.48104 + endloop + endfacet + facet normal 0.982088 0.165968 0.0892043 + outer loop + vertex 0.849352 1.10126 2.47496 + vertex 0.848994 1.10071 2.47992 + vertex 0.849837 1.097 2.47754 + endloop + endfacet + facet normal 0.981722 0.0960096 0.164329 + outer loop + vertex 0.849179 1.0969 2.48104 + vertex 0.848994 1.10071 2.47992 + vertex 0.848522 1.09934 2.48354 + endloop + endfacet + facet normal 0.662138 -0.352748 -0.661167 + outer loop + vertex 0.850649 1.105 2.52 + vertex 0.848419 1.10216 2.51928 + vertex 0.85 1.105 2.51935 + endloop + endfacet + facet normal 0.794413 -0.574969 -0.195754 + outer loop + vertex 0.851082 1.10512 2.52141 + vertex 0.848419 1.10216 2.51928 + vertex 0.850649 1.105 2.52 + endloop + endfacet + facet normal 0.772048 -0.628675 -0.0933241 + outer loop + vertex 0.848096 1.10125 2.52275 + vertex 0.848419 1.10216 2.51928 + vertex 0.851082 1.10512 2.52141 + endloop + endfacet + facet normal 0.764412 -0.632953 -0.122658 + outer loop + vertex 0.8506 1.10379 2.52525 + vertex 0.848096 1.10125 2.52275 + vertex 0.851082 1.10512 2.52141 + endloop + endfacet + facet normal 0.588225 -0.782252 0.205117 + outer loop + vertex 0.846935 1.10151 2.52706 + vertex 0.848096 1.10125 2.52275 + vertex 0.8506 1.10379 2.52525 + endloop + endfacet + facet normal 0.568644 -0.812752 0.126799 + outer loop + vertex 0.84986 1.1039 2.52926 + vertex 0.846935 1.10151 2.52706 + vertex 0.8506 1.10379 2.52525 + endloop + endfacet + facet normal 0.35489 -0.830394 0.429533 + outer loop + vertex 0.846846 1.10312 2.53024 + vertex 0.846935 1.10151 2.52706 + vertex 0.84986 1.1039 2.52926 + endloop + endfacet + facet normal 0.368759 -0.770634 0.519749 + outer loop + vertex 0.84986 1.1039 2.52926 + vertex 0.847958 1.10502 2.53228 + vertex 0.846846 1.10312 2.53024 + endloop + endfacet + facet normal 0.808466 -0.464534 -0.361373 + outer loop + vertex 0.855 1.11 2.5239 + vertex 0.853626 1.10713 2.52452 + vertex 0.851082 1.10512 2.52141 + endloop + endfacet + facet normal 0.777455 -0.361435 -0.514711 + outer loop + vertex 0.855 1.11 2.5239 + vertex 0.851082 1.10512 2.52141 + vertex 0.852418 1.11 2.52 + endloop + endfacet + facet normal 0.912042 -0.322682 -0.253091 + outer loop + vertex 0.852418 1.11 2.52 + vertex 0.851082 1.10512 2.52141 + vertex 0.850649 1.105 2.52 + endloop + endfacet + facet normal 0.731087 -0.678522 -0.0715519 + outer loop + vertex 0.853626 1.10713 2.52452 + vertex 0.853223 1.10632 2.52805 + vertex 0.8506 1.10379 2.52525 + endloop + endfacet + facet normal 0.716796 -0.681925 -0.145539 + outer loop + vertex 0.851082 1.10512 2.52141 + vertex 0.853626 1.10713 2.52452 + vertex 0.8506 1.10379 2.52525 + endloop + endfacet + facet normal 0.618881 -0.760949 0.194788 + outer loop + vertex 0.853223 1.10632 2.52805 + vertex 0.852012 1.10639 2.53214 + vertex 0.84986 1.1039 2.52926 + endloop + endfacet + facet normal 0.610812 -0.780402 0.133718 + outer loop + vertex 0.8506 1.10379 2.52525 + vertex 0.853223 1.10632 2.52805 + vertex 0.84986 1.1039 2.52926 + endloop + endfacet + facet normal 0.292789 -0.820769 0.490522 + outer loop + vertex 0.847958 1.10502 2.53228 + vertex 0.84986 1.1039 2.52926 + vertex 0.852012 1.10639 2.53214 + endloop + endfacet + facet normal 0.282247 -0.782844 0.554519 + outer loop + vertex 0.847958 1.10502 2.53228 + vertex 0.852012 1.10639 2.53214 + vertex 0.848792 1.10706 2.53473 + endloop + endfacet + facet normal 0.137633 -0.903338 0.406248 + outer loop + vertex 0.848792 1.10706 2.53473 + vertex 0.852012 1.10639 2.53214 + vertex 0.851873 1.10782 2.53538 + endloop + endfacet + facet normal 0.022548 -0.701092 0.712714 + outer loop + vertex 0.851873 1.10782 2.53538 + vertex 0.848861 1.10973 2.53736 + vertex 0.848792 1.10706 2.53473 + endloop + endfacet + facet normal -0.0440024 -0.750678 0.659202 + outer loop + vertex 0.853745 1.10938 2.53728 + vertex 0.848861 1.10973 2.53736 + vertex 0.851873 1.10782 2.53538 + endloop + endfacet + facet normal 0.848772 -0.428116 -0.310326 + outer loop + vertex 0.850691 1.115 2.485 + vertex 0.85 1.11363 2.485 + vertex 0.85 1.115 2.48311 + endloop + endfacet + facet normal -0.0488609 -0.802271 0.594957 + outer loop + vertex 0.848861 1.10973 2.53736 + vertex 0.853745 1.10938 2.53728 + vertex 0.853296 1.11155 2.54018 + endloop + endfacet + facet normal -0.194399 -0.655841 0.729439 + outer loop + vertex 0.848243 1.11253 2.53971 + vertex 0.848861 1.10973 2.53736 + vertex 0.853296 1.11155 2.54018 + endloop + endfacet + facet normal -0.195221 -0.663535 0.722226 + outer loop + vertex 0.853296 1.11155 2.54018 + vertex 0.849453 1.11444 2.54179 + vertex 0.848243 1.11253 2.53971 + endloop + endfacet + facet normal -0.286591 -0.728938 0.621703 + outer loop + vertex 0.854654 1.114 2.54367 + vertex 0.849453 1.11444 2.54179 + vertex 0.853296 1.11155 2.54018 + endloop + endfacet + facet normal 0.885159 -0.306198 -0.350338 + outer loop + vertex 0.850851 1.12 2.48 + vertex 0.85 1.11754 2.48 + vertex 0.85 1.12 2.47785 + endloop + endfacet + facet normal -0.372398 -0.618918 0.691563 + outer loop + vertex 0.853633 1.11651 2.54561 + vertex 0.851555 1.11814 2.54596 + vertex 0.849659 1.1174 2.54427 + endloop + endfacet + facet normal -0.369158 -0.65868 0.655639 + outer loop + vertex 0.853633 1.11651 2.54561 + vertex 0.849659 1.1174 2.54427 + vertex 0.854654 1.114 2.54367 + endloop + endfacet + facet normal -0.317057 -0.596463 0.737364 + outer loop + vertex 0.854654 1.114 2.54367 + vertex 0.849659 1.1174 2.54427 + vertex 0.849453 1.11444 2.54179 + endloop + endfacet + facet normal -0.33887 -0.585857 0.736165 + outer loop + vertex 0.853633 1.11651 2.54561 + vertex 0.853845 1.11904 2.54773 + vertex 0.851555 1.11814 2.54596 + endloop + endfacet + facet normal -0.416331 -0.561251 0.715309 + outer loop + vertex 0.849659 1.1174 2.54427 + vertex 0.851555 1.11814 2.54596 + vertex 0.84901 1.12031 2.54618 + endloop + endfacet + facet normal -0.430728 -0.573273 0.697016 + outer loop + vertex 0.852823 1.12226 2.54988 + vertex 0.85052 1.12479 2.55053 + vertex 0.848397 1.12357 2.54823 + endloop + endfacet + facet normal -0.430439 -0.591879 0.68147 + outer loop + vertex 0.853845 1.11904 2.54773 + vertex 0.852823 1.12226 2.54988 + vertex 0.848397 1.12357 2.54823 + endloop + endfacet + facet normal -0.382145 -0.541239 0.749016 + outer loop + vertex 0.853845 1.11904 2.54773 + vertex 0.848397 1.12357 2.54823 + vertex 0.84901 1.12031 2.54618 + endloop + endfacet + facet normal -0.381645 -0.525074 0.760686 + outer loop + vertex 0.853845 1.11904 2.54773 + vertex 0.84901 1.12031 2.54618 + vertex 0.851555 1.11814 2.54596 + endloop + endfacet + facet normal -0.403252 -0.555933 0.726861 + outer loop + vertex 0.852823 1.12226 2.54988 + vertex 0.853978 1.1241 2.55193 + vertex 0.85052 1.12479 2.55053 + endloop + endfacet + facet normal -0.463893 -0.533963 0.706886 + outer loop + vertex 0.848397 1.12357 2.54823 + vertex 0.85052 1.12479 2.55053 + vertex 0.847582 1.12671 2.55006 + endloop + endfacet + facet normal -0.451043 -0.5075 0.734169 + outer loop + vertex 0.85052 1.12479 2.55053 + vertex 0.849581 1.12789 2.55211 + vertex 0.847582 1.12671 2.55006 + endloop + endfacet + facet normal -0.406804 -0.507124 0.759826 + outer loop + vertex 0.85052 1.12479 2.55053 + vertex 0.853978 1.1241 2.55193 + vertex 0.849581 1.12789 2.55211 + endloop + endfacet + facet normal -0.443123 -0.546831 0.710364 + outer loop + vertex 0.853978 1.1241 2.55193 + vertex 0.854211 1.12719 2.55445 + vertex 0.849581 1.12789 2.55211 + endloop + endfacet + facet normal -0.506827 -0.522869 0.685372 + outer loop + vertex 0.853596 1.13025 2.55643 + vertex 0.851159 1.13266 2.55647 + vertex 0.849479 1.13174 2.55453 + endloop + endfacet + facet normal -0.506845 -0.538303 0.673304 + outer loop + vertex 0.853596 1.13025 2.55643 + vertex 0.849479 1.13174 2.55453 + vertex 0.854211 1.12719 2.55445 + endloop + endfacet + facet normal -0.452945 -0.483692 0.748921 + outer loop + vertex 0.854211 1.12719 2.55445 + vertex 0.849479 1.13174 2.55453 + vertex 0.849581 1.12789 2.55211 + endloop + endfacet + facet normal -0.470649 -0.486973 0.735763 + outer loop + vertex 0.853596 1.13025 2.55643 + vertex 0.853364 1.13343 2.55839 + vertex 0.851159 1.13266 2.55647 + endloop + endfacet + facet normal -0.567084 -0.437954 0.697576 + outer loop + vertex 0.849479 1.13174 2.55453 + vertex 0.851159 1.13266 2.55647 + vertex 0.848888 1.13537 2.55632 + endloop + endfacet + facet normal -0.555241 -0.3754 0.742147 + outer loop + vertex 0.852998 1.13652 2.56008 + vertex 0.851486 1.13993 2.56067 + vertex 0.849882 1.13789 2.55844 + endloop + endfacet + facet normal -0.562348 -0.446734 0.69584 + outer loop + vertex 0.853364 1.13343 2.55839 + vertex 0.852998 1.13652 2.56008 + vertex 0.849882 1.13789 2.55844 + endloop + endfacet + facet normal -0.523502 -0.416984 0.743014 + outer loop + vertex 0.853364 1.13343 2.55839 + vertex 0.849882 1.13789 2.55844 + vertex 0.848888 1.13537 2.55632 + endloop + endfacet + facet normal -0.520566 -0.395813 0.756534 + outer loop + vertex 0.853364 1.13343 2.55839 + vertex 0.848888 1.13537 2.55632 + vertex 0.851159 1.13266 2.55647 + endloop + endfacet + facet normal -0.523573 -0.36614 0.769294 + outer loop + vertex 0.852998 1.13652 2.56008 + vertex 0.855321 1.1372 2.56198 + vertex 0.851486 1.13993 2.56067 + endloop + endfacet + facet normal -0.591766 -0.336308 0.732605 + outer loop + vertex 0.847245 1.14277 2.55855 + vertex 0.849882 1.13789 2.55844 + vertex 0.851486 1.13993 2.56067 + endloop + endfacet + facet normal -0.591281 -0.334765 0.733702 + outer loop + vertex 0.850063 1.14348 2.56114 + vertex 0.847245 1.14277 2.55855 + vertex 0.851486 1.13993 2.56067 + endloop + endfacet + facet normal -0.562273 -0.326547 0.759748 + outer loop + vertex 0.851486 1.13993 2.56067 + vertex 0.8542 1.142 2.56357 + vertex 0.850063 1.14348 2.56114 + endloop + endfacet + facet normal -0.527653 -0.375301 0.762057 + outer loop + vertex 0.855321 1.1372 2.56198 + vertex 0.8542 1.142 2.56357 + vertex 0.851486 1.13993 2.56067 + endloop + endfacet + facet normal -0.666558 -0.0652155 0.742595 + outer loop + vertex 0.852882 1.18563 2.57526 + vertex 0.852439 1.18952 2.5752 + vertex 0.850176 1.1864 2.5729 + endloop + endfacet + facet normal -0.671851 -0.119194 0.731033 + outer loop + vertex 0.852882 1.18563 2.57526 + vertex 0.850176 1.1864 2.5729 + vertex 0.852593 1.18233 2.57445 + endloop + endfacet + facet normal -0.655618 -0.0638298 0.75239 + outer loop + vertex 0.852882 1.18563 2.57526 + vertex 0.855003 1.18675 2.5772 + vertex 0.852439 1.18952 2.5752 + endloop + endfacet + facet normal -0.674387 -0.0549012 0.736334 + outer loop + vertex 0.849586 1.1918 2.57276 + vertex 0.850176 1.1864 2.5729 + vertex 0.852439 1.18952 2.5752 + endloop + endfacet + facet normal -0.669274 -0.0426453 0.741791 + outer loop + vertex 0.852115 1.19446 2.57519 + vertex 0.849586 1.1918 2.57276 + vertex 0.852439 1.18952 2.5752 + endloop + endfacet + facet normal -0.667813 -0.0425474 0.743112 + outer loop + vertex 0.852439 1.18952 2.5752 + vertex 0.855447 1.19214 2.57805 + vertex 0.852115 1.19446 2.57519 + endloop + endfacet + facet normal -0.65633 -0.065011 0.751668 + outer loop + vertex 0.855003 1.18675 2.5772 + vertex 0.855447 1.19214 2.57805 + vertex 0.852439 1.18952 2.5752 + endloop + endfacet + facet normal -0.665597 -0.065349 0.743445 + outer loop + vertex 0.85184 1.19941 2.57538 + vertex 0.849312 1.19687 2.5729 + vertex 0.852115 1.19446 2.57519 + endloop + endfacet + facet normal -0.650336 -0.0650077 0.75686 + outer loop + vertex 0.852115 1.19446 2.57519 + vertex 0.854217 1.19699 2.57722 + vertex 0.85184 1.19941 2.57538 + endloop + endfacet + facet normal -0.667127 -0.0406684 0.743833 + outer loop + vertex 0.855447 1.19214 2.57805 + vertex 0.854217 1.19699 2.57722 + vertex 0.852115 1.19446 2.57519 + endloop + endfacet + facet normal -0.550388 -0.0761252 0.831431 + outer loop + vertex 0.84965 1.37311 2.60139 + vertex 0.850597 1.37735 2.60241 + vertex 0.847772 1.37551 2.60037 + endloop + endfacet + facet normal -0.549056 0.0985086 0.82996 + outer loop + vertex 0.852343 1.67799 2.60048 + vertex 0.854287 1.68027 2.60149 + vertex 0.852063 1.68127 2.5999 + endloop + endfacet + facet normal -0.627138 0.0517806 0.777185 + outer loop + vertex 0.853012 1.76599 2.58866 + vertex 0.853302 1.7709 2.58857 + vertex 0.850314 1.76835 2.58633 + endloop + endfacet + facet normal -0.636505 0.0451909 0.769947 + outer loop + vertex 0.84783 1.77584 2.58383 + vertex 0.847242 1.77042 2.58366 + vertex 0.850504 1.77331 2.58618 + endloop + endfacet + facet normal -0.634934 0.0479037 0.771079 + outer loop + vertex 0.850747 1.77836 2.58607 + vertex 0.84783 1.77584 2.58383 + vertex 0.850504 1.77331 2.58618 + endloop + endfacet + facet normal -0.629943 0.0477544 0.775172 + outer loop + vertex 0.850504 1.77331 2.58618 + vertex 0.85345 1.77589 2.58842 + vertex 0.850747 1.77836 2.58607 + endloop + endfacet + facet normal -0.626639 0.0413457 0.778212 + outer loop + vertex 0.853302 1.7709 2.58857 + vertex 0.85345 1.77589 2.58842 + vertex 0.850504 1.77331 2.58618 + endloop + endfacet + facet normal -0.639826 0.0578016 0.766343 + outer loop + vertex 0.848143 1.78086 2.58371 + vertex 0.84783 1.77584 2.58383 + vertex 0.850747 1.77836 2.58607 + endloop + endfacet + facet normal -0.568996 0.303386 0.76433 + outer loop + vertex 0.851394 1.87243 2.56401 + vertex 0.848438 1.86986 2.56283 + vertex 0.851026 1.86802 2.56549 + endloop + endfacet + facet normal -0.554213 0.305487 0.774291 + outer loop + vertex 0.851026 1.86802 2.56549 + vertex 0.854442 1.87181 2.56644 + vertex 0.851394 1.87243 2.56401 + endloop + endfacet + facet normal -0.569581 0.324148 0.755318 + outer loop + vertex 0.854403 1.86699 2.56848 + vertex 0.854442 1.87181 2.56644 + vertex 0.851026 1.86802 2.56549 + endloop + endfacet + facet normal -0.562314 0.372504 0.738271 + outer loop + vertex 0.851791 1.87639 2.56243 + vertex 0.848069 1.87603 2.55977 + vertex 0.849191 1.87332 2.562 + endloop + endfacet + facet normal -0.571583 0.308121 0.760496 + outer loop + vertex 0.849191 1.87332 2.562 + vertex 0.848438 1.86986 2.56283 + vertex 0.851394 1.87243 2.56401 + endloop + endfacet + facet normal -0.547831 0.357757 0.756235 + outer loop + vertex 0.851791 1.87639 2.56243 + vertex 0.849191 1.87332 2.562 + vertex 0.851394 1.87243 2.56401 + endloop + endfacet + facet normal -0.545579 0.358115 0.757692 + outer loop + vertex 0.851791 1.87639 2.56243 + vertex 0.851394 1.87243 2.56401 + vertex 0.854145 1.87548 2.56455 + endloop + endfacet + facet normal -0.544173 0.360958 0.757354 + outer loop + vertex 0.851791 1.87639 2.56243 + vertex 0.854145 1.87548 2.56455 + vertex 0.853867 1.87734 2.56347 + endloop + endfacet + facet normal -0.538609 0.350289 0.766288 + outer loop + vertex 0.854145 1.87548 2.56455 + vertex 0.851394 1.87243 2.56401 + vertex 0.854442 1.87181 2.56644 + endloop + endfacet + facet normal -0.549844 0.409309 0.728106 + outer loop + vertex 0.851791 1.87639 2.56243 + vertex 0.854049 1.87906 2.56263 + vertex 0.852626 1.88106 2.56044 + endloop + endfacet + facet normal -0.555643 0.408626 0.724076 + outer loop + vertex 0.851791 1.87639 2.56243 + vertex 0.852626 1.88106 2.56044 + vertex 0.848069 1.87603 2.55977 + endloop + endfacet + facet normal -0.527455 0.378202 0.760759 + outer loop + vertex 0.848069 1.87603 2.55977 + vertex 0.852626 1.88106 2.56044 + vertex 0.848324 1.88126 2.55735 + endloop + endfacet + facet normal -0.551419 0.410793 0.726076 + outer loop + vertex 0.854049 1.87906 2.56263 + vertex 0.851791 1.87639 2.56243 + vertex 0.853867 1.87734 2.56347 + endloop + endfacet + facet normal -0.509993 0.440751 0.738678 + outer loop + vertex 0.851579 1.888 2.55588 + vertex 0.848388 1.88704 2.55425 + vertex 0.849606 1.88511 2.55624 + endloop + endfacet + facet normal -0.481295 0.424665 0.766822 + outer loop + vertex 0.849606 1.88511 2.55624 + vertex 0.852944 1.88609 2.55779 + vertex 0.851579 1.888 2.55588 + endloop + endfacet + facet normal -0.479845 0.386872 0.787451 + outer loop + vertex 0.849606 1.88511 2.55624 + vertex 0.848324 1.88126 2.55735 + vertex 0.852944 1.88609 2.55779 + endloop + endfacet + facet normal -0.514399 0.423738 0.745547 + outer loop + vertex 0.848324 1.88126 2.55735 + vertex 0.852626 1.88106 2.56044 + vertex 0.852944 1.88609 2.55779 + endloop + endfacet + facet normal -0.483124 0.503189 0.716514 + outer loop + vertex 0.851579 1.888 2.55588 + vertex 0.854169 1.88989 2.5563 + vertex 0.852606 1.89145 2.55415 + endloop + endfacet + facet normal -0.508579 0.502197 0.699389 + outer loop + vertex 0.851579 1.888 2.55588 + vertex 0.852606 1.89145 2.55415 + vertex 0.848388 1.88704 2.55425 + endloop + endfacet + facet normal -0.470906 0.467308 0.748245 + outer loop + vertex 0.848388 1.88704 2.55425 + vertex 0.852606 1.89145 2.55415 + vertex 0.84829 1.89127 2.55155 + endloop + endfacet + facet normal -0.452444 0.448991 0.77052 + outer loop + vertex 0.854169 1.88989 2.5563 + vertex 0.851579 1.888 2.55588 + vertex 0.852944 1.88609 2.55779 + endloop + endfacet + facet normal -0.34336 0.485232 0.804148 + outer loop + vertex 0.851031 1.89784 2.54891 + vertex 0.849062 1.89714 2.54849 + vertex 0.849032 1.89522 2.54964 + endloop + endfacet + facet normal -0.391019 0.510853 0.765593 + outer loop + vertex 0.849032 1.89522 2.54964 + vertex 0.852221 1.89517 2.5513 + vertex 0.851031 1.89784 2.54891 + endloop + endfacet + facet normal -0.405168 0.458203 0.791132 + outer loop + vertex 0.849032 1.89522 2.54964 + vertex 0.84829 1.89127 2.55155 + vertex 0.852221 1.89517 2.5513 + endloop + endfacet + facet normal -0.460007 0.509426 0.72724 + outer loop + vertex 0.84829 1.89127 2.55155 + vertex 0.852606 1.89145 2.55415 + vertex 0.852221 1.89517 2.5513 + endloop + endfacet + facet normal -0.362952 0.682791 0.634084 + outer loop + vertex 0.851419 1.90088 2.54624 + vertex 0.846626 1.90016 2.54426 + vertex 0.849031 1.89866 2.54726 + endloop + endfacet + facet normal -0.361717 0.583332 0.727245 + outer loop + vertex 0.849031 1.89866 2.54726 + vertex 0.849062 1.89714 2.54849 + vertex 0.851031 1.89784 2.54891 + endloop + endfacet + facet normal -0.307177 0.650556 0.694564 + outer loop + vertex 0.851419 1.90088 2.54624 + vertex 0.849031 1.89866 2.54726 + vertex 0.851031 1.89784 2.54891 + endloop + endfacet + facet normal -0.219515 0.660224 0.718274 + outer loop + vertex 0.851419 1.90088 2.54624 + vertex 0.851031 1.89784 2.54891 + vertex 0.855084 1.89903 2.54906 + endloop + endfacet + facet normal -0.260085 0.617061 0.742692 + outer loop + vertex 0.851419 1.90088 2.54624 + vertex 0.855084 1.89903 2.54906 + vertex 0.854096 1.90131 2.54682 + endloop + endfacet + facet normal -0.204067 0.60067 0.773015 + outer loop + vertex 0.855084 1.89903 2.54906 + vertex 0.851031 1.89784 2.54891 + vertex 0.852221 1.89517 2.5513 + endloop + endfacet + facet normal -0.0336574 0.880308 0.473208 + outer loop + vertex 0.854982 1.90666 2.5389 + vertex 0.853681 1.90817 2.536 + vertex 0.850903 1.90714 2.53773 + endloop + endfacet + facet normal -0.00446896 0.807887 0.589321 + outer loop + vertex 0.850903 1.90714 2.53773 + vertex 0.847341 1.90701 2.53787 + vertex 0.850287 1.90445 2.54141 + endloop + endfacet + facet normal -0.0726042 0.811158 0.580303 + outer loop + vertex 0.850903 1.90714 2.53773 + vertex 0.850287 1.90445 2.54141 + vertex 0.854982 1.90666 2.5389 + endloop + endfacet + facet normal -0.0603636 0.801584 0.594827 + outer loop + vertex 0.854982 1.90666 2.5389 + vertex 0.850287 1.90445 2.54141 + vertex 0.854024 1.90474 2.54139 + endloop + endfacet + facet normal -0.356232 0.709392 0.608163 + outer loop + vertex 0.851419 1.90088 2.54624 + vertex 0.850287 1.90445 2.54141 + vertex 0.846626 1.90016 2.54426 + endloop + endfacet + facet normal -0.150267 0.777684 0.610432 + outer loop + vertex 0.851419 1.90088 2.54624 + vertex 0.854245 1.90301 2.54422 + vertex 0.850287 1.90445 2.54141 + endloop + endfacet + facet normal -0.0642463 0.848301 0.525603 + outer loop + vertex 0.854245 1.90301 2.54422 + vertex 0.854024 1.90474 2.54139 + vertex 0.850287 1.90445 2.54141 + endloop + endfacet + facet normal -0.24431 0.817759 0.521135 + outer loop + vertex 0.854245 1.90301 2.54422 + vertex 0.851419 1.90088 2.54624 + vertex 0.854096 1.90131 2.54682 + endloop + endfacet + facet normal 0.765985 0.53141 -0.36176 + outer loop + vertex 0.85 1.91 2.48168 + vertex 0.85 1.91226 2.485 + vertex 0.851568 1.91 2.485 + endloop + endfacet + facet normal -0.329195 0.568934 0.753622 + outer loop + vertex 0.853716 1.915 2.53 + vertex 0.847885 1.91284 2.52908 + vertex 0.849993 1.91119 2.53125 + endloop + endfacet + facet normal 0.0330086 0.28262 0.958664 + outer loop + vertex 0.853716 1.915 2.53 + vertex 0.849993 1.91119 2.53125 + vertex 0.855 1.91485 2.53 + endloop + endfacet + facet normal -0.156271 0.504002 0.849448 + outer loop + vertex 0.855 1.91485 2.53 + vertex 0.849993 1.91119 2.53125 + vertex 0.854096 1.90973 2.53287 + endloop + endfacet + facet normal -0.0193612 0.871109 0.490708 + outer loop + vertex 0.853681 1.90817 2.536 + vertex 0.849928 1.9087 2.53491 + vertex 0.850903 1.90714 2.53773 + endloop + endfacet + facet normal -0.00286607 0.895173 0.445709 + outer loop + vertex 0.853681 1.90817 2.536 + vertex 0.854096 1.90973 2.53287 + vertex 0.849928 1.9087 2.53491 + endloop + endfacet + facet normal 0.0710038 0.824771 0.560991 + outer loop + vertex 0.854096 1.90973 2.53287 + vertex 0.849993 1.91119 2.53125 + vertex 0.849928 1.9087 2.53491 + endloop + endfacet + facet normal -0.0107975 0.872489 0.488514 + outer loop + vertex 0.850903 1.90714 2.53773 + vertex 0.849928 1.9087 2.53491 + vertex 0.847341 1.90701 2.53787 + endloop + endfacet + facet normal 0.783509 0.562369 -0.264302 + outer loop + vertex 0.85 1.915 2.49417 + vertex 0.85 1.91539 2.495 + vertex 0.85028 1.915 2.495 + endloop + endfacet + facet normal 0.0401086 0.999141 -0.0104125 + outer loop + vertex 0.852418 1.915 2.525 + vertex 0.847607 1.91521 2.52631 + vertex 0.853716 1.915 2.53 + endloop + endfacet + facet normal 0.266339 0.174054 0.948034 + outer loop + vertex 0.85 1.9187 2.525 + vertex 0.847607 1.91521 2.52631 + vertex 0.852418 1.915 2.525 + endloop + endfacet + facet normal -0.355226 0.692773 0.627598 + outer loop + vertex 0.853716 1.915 2.53 + vertex 0.847607 1.91521 2.52631 + vertex 0.847885 1.91284 2.52908 + endloop + endfacet + facet normal -0.996298 0.0525646 0.068028 + outer loop + vertex 0.849964 1.93072 2.45824 + vertex 0.85 1.92912 2.46 + vertex 0.85 1.93 2.45932 + endloop + endfacet + facet normal 0.99848 0.0493911 0.0244682 + outer loop + vertex 0.849961 1.92979 2.46025 + vertex 0.85 1.92912 2.46 + vertex 0.849964 1.93072 2.45824 + endloop + endfacet + facet normal 0.998479 0.0535417 0.0131716 + outer loop + vertex 0.85 1.92789 2.465 + vertex 0.85 1.92912 2.46 + vertex 0.849961 1.92979 2.46025 + endloop + endfacet + facet normal 0.795892 0.564222 0.219564 + outer loop + vertex 0.849697 1.9286 2.46428 + vertex 0.85 1.92789 2.465 + vertex 0.849961 1.92979 2.46025 + endloop + endfacet + facet normal -0.073711 0.694292 0.715909 + outer loop + vertex 0.848834 1.92467 2.468 + vertex 0.85 1.92789 2.465 + vertex 0.849697 1.9286 2.46428 + endloop + endfacet + facet normal 0.980236 -0.196888 0.0192832 + outer loop + vertex 0.849499 1.9281 2.46928 + vertex 0.848834 1.92467 2.468 + vertex 0.849697 1.9286 2.46428 + endloop + endfacet + facet normal 0.97728 -0.20665 0.0471083 + outer loop + vertex 0.848579 1.92464 2.47315 + vertex 0.848834 1.92467 2.468 + vertex 0.849499 1.9281 2.46928 + endloop + endfacet + facet normal 0.98274 -0.163026 0.0874384 + outer loop + vertex 0.849161 1.9286 2.474 + vertex 0.848579 1.92464 2.47315 + vertex 0.849499 1.9281 2.46928 + endloop + endfacet + facet normal 0.975894 -0.172029 0.134305 + outer loop + vertex 0.848222 1.92571 2.47712 + vertex 0.848579 1.92464 2.47315 + vertex 0.849161 1.9286 2.474 + endloop + endfacet + facet normal 0.974093 -0.0945053 0.205454 + outer loop + vertex 0.849161 1.9286 2.474 + vertex 0.848356 1.92927 2.47812 + vertex 0.848222 1.92571 2.47712 + endloop + endfacet + facet normal -0.999154 0.0100516 0.0398858 + outer loop + vertex 0.85 1.935 2.45806 + vertex 0.849964 1.93072 2.45824 + vertex 0.85 1.93 2.45932 + endloop + endfacet + facet normal 0.676729 -0.0366558 -0.73532 + outer loop + vertex 0.852108 1.935 2.46 + vertex 0.849964 1.93072 2.45824 + vertex 0.85 1.935 2.45806 + endloop + endfacet + facet normal 0.90734 -0.382628 -0.174156 + outer loop + vertex 0.849964 1.93072 2.45824 + vertex 0.852108 1.935 2.46 + vertex 0.849961 1.92979 2.46025 + endloop + endfacet + facet normal 0.836271 -0.323937 0.442397 + outer loop + vertex 0.852108 1.935 2.46 + vertex 0.850698 1.93309 2.46127 + vertex 0.849961 1.92979 2.46025 + endloop + endfacet + facet normal 0.975954 -0.217974 -0.000855346 + outer loop + vertex 0.849961 1.92979 2.46025 + vertex 0.850698 1.93309 2.46127 + vertex 0.849697 1.9286 2.46428 + endloop + endfacet + facet normal 0.98102 -0.188746 0.044427 + outer loop + vertex 0.850698 1.93309 2.46127 + vertex 0.850322 1.93215 2.4656 + vertex 0.849697 1.9286 2.46428 + endloop + endfacet + facet normal 0.983348 -0.18051 0.0210309 + outer loop + vertex 0.849697 1.9286 2.46428 + vertex 0.850322 1.93215 2.4656 + vertex 0.849499 1.9281 2.46928 + endloop + endfacet + facet normal 0.98741 -0.1467 0.0591581 + outer loop + vertex 0.850322 1.93215 2.4656 + vertex 0.850038 1.9322 2.47044 + vertex 0.849499 1.9281 2.46928 + endloop + endfacet + facet normal 0.984256 -0.154078 0.086609 + outer loop + vertex 0.849499 1.9281 2.46928 + vertex 0.850038 1.9322 2.47044 + vertex 0.849161 1.9286 2.474 + endloop + endfacet + facet normal 0.984755 -0.0974576 0.144079 + outer loop + vertex 0.850038 1.9322 2.47044 + vertex 0.849468 1.93282 2.47476 + vertex 0.849161 1.9286 2.474 + endloop + endfacet + facet normal 0.972308 -0.107921 0.207291 + outer loop + vertex 0.849468 1.93282 2.47476 + vertex 0.848356 1.92927 2.47812 + vertex 0.849161 1.9286 2.474 + endloop + endfacet + facet normal 0.9642 -0.0561766 0.259159 + outer loop + vertex 0.848498 1.93381 2.47858 + vertex 0.848356 1.92927 2.47812 + vertex 0.849468 1.93282 2.47476 + endloop + endfacet + facet normal 0.716807 -0.0682389 0.693924 + outer loop + vertex 0.852108 1.935 2.46 + vertex 0.852584 1.94 2.46 + vertex 0.850698 1.93309 2.46127 + endloop + endfacet + facet normal 0.922469 -0.190147 0.335998 + outer loop + vertex 0.852584 1.94 2.46 + vertex 0.851283 1.9375 2.46215 + vertex 0.850698 1.93309 2.46127 + endloop + endfacet + facet normal 0.988275 -0.142389 0.0551077 + outer loop + vertex 0.850698 1.93309 2.46127 + vertex 0.851283 1.9375 2.46215 + vertex 0.850322 1.93215 2.4656 + endloop + endfacet + facet normal 0.988737 -0.12358 0.0844278 + outer loop + vertex 0.851283 1.9375 2.46215 + vertex 0.850814 1.9367 2.46649 + vertex 0.850322 1.93215 2.4656 + endloop + endfacet + facet normal 0.991146 -0.118884 0.0591312 + outer loop + vertex 0.850322 1.93215 2.4656 + vertex 0.850814 1.9367 2.46649 + vertex 0.850038 1.9322 2.47044 + endloop + endfacet + facet normal 0.991345 -0.078343 0.10534 + outer loop + vertex 0.850814 1.9367 2.46649 + vertex 0.850349 1.93686 2.47098 + vertex 0.850038 1.9322 2.47044 + endloop + endfacet + facet normal 0.986427 -0.0822467 0.142119 + outer loop + vertex 0.850038 1.9322 2.47044 + vertex 0.850349 1.93686 2.47098 + vertex 0.849468 1.93282 2.47476 + endloop + endfacet + facet normal 0.983449 -0.0522497 0.17349 + outer loop + vertex 0.850349 1.93686 2.47098 + vertex 0.849662 1.93754 2.47508 + vertex 0.849468 1.93282 2.47476 + endloop + endfacet + facet normal 0.964068 -0.0572692 0.259409 + outer loop + vertex 0.849662 1.93754 2.47508 + vertex 0.848498 1.93381 2.47858 + vertex 0.849468 1.93282 2.47476 + endloop + endfacet + facet normal 0.959131 -0.035777 0.280693 + outer loop + vertex 0.848625 1.93869 2.47877 + vertex 0.848498 1.93381 2.47858 + vertex 0.849662 1.93754 2.47508 + endloop + endfacet + facet normal 0.871486 -0.0315512 0.489404 + outer loop + vertex 0.852584 1.94 2.46 + vertex 0.852765 1.945 2.46 + vertex 0.851283 1.9375 2.46215 + endloop + endfacet + facet normal 0.957753 -0.113224 0.264365 + outer loop + vertex 0.852765 1.945 2.46 + vertex 0.851747 1.94241 2.46258 + vertex 0.851283 1.9375 2.46215 + endloop + endfacet + facet normal 0.990898 -0.101193 0.0887808 + outer loop + vertex 0.851283 1.9375 2.46215 + vertex 0.851747 1.94241 2.46258 + vertex 0.850814 1.9367 2.46649 + endloop + endfacet + facet normal 0.989559 -0.079385 0.120296 + outer loop + vertex 0.851747 1.94241 2.46258 + vertex 0.85118 1.94168 2.46676 + vertex 0.850814 1.9367 2.46649 + endloop + endfacet + facet normal 0.991317 -0.0786855 0.105349 + outer loop + vertex 0.850814 1.9367 2.46649 + vertex 0.85118 1.94168 2.46676 + vertex 0.850349 1.93686 2.47098 + endloop + endfacet + facet normal 0.990061 -0.0589898 0.127672 + outer loop + vertex 0.85118 1.94168 2.46676 + vertex 0.850624 1.94183 2.47114 + vertex 0.850349 1.93686 2.47098 + endloop + endfacet + facet normal 0.982784 -0.0601317 0.174698 + outer loop + vertex 0.850349 1.93686 2.47098 + vertex 0.850624 1.94183 2.47114 + vertex 0.849662 1.93754 2.47508 + endloop + endfacet + facet normal 0.980636 -0.0450609 0.190587 + outer loop + vertex 0.850624 1.94183 2.47114 + vertex 0.849865 1.94248 2.4752 + vertex 0.849662 1.93754 2.47508 + endloop + endfacet + facet normal 0.957806 -0.0464476 0.283637 + outer loop + vertex 0.849865 1.94248 2.4752 + vertex 0.848625 1.93869 2.47877 + vertex 0.849662 1.93754 2.47508 + endloop + endfacet + facet normal 0.954336 -0.0328274 0.296928 + outer loop + vertex 0.848772 1.9437 2.47885 + vertex 0.848625 1.93869 2.47877 + vertex 0.849865 1.94248 2.4752 + endloop + endfacet + facet normal 0.957176 -0.109301 0.268081 + outer loop + vertex 0.852765 1.945 2.46 + vertex 0.853336 1.95 2.46 + vertex 0.851747 1.94241 2.46258 + endloop + endfacet + facet normal 0.94569 -0.0920605 0.311762 + outer loop + vertex 0.853336 1.95 2.46 + vertex 0.852202 1.94738 2.46267 + vertex 0.851747 1.94241 2.46258 + endloop + endfacet + facet normal 0.988702 -0.0925604 0.117902 + outer loop + vertex 0.851747 1.94241 2.46258 + vertex 0.852202 1.94738 2.46267 + vertex 0.85118 1.94168 2.46676 + endloop + endfacet + facet normal 0.98887 -0.0950766 0.114444 + outer loop + vertex 0.852202 1.94738 2.46267 + vertex 0.851634 1.94666 2.46697 + vertex 0.85118 1.94168 2.46676 + endloop + endfacet + facet normal 0.987101 -0.0955065 0.128493 + outer loop + vertex 0.85118 1.94168 2.46676 + vertex 0.851634 1.94666 2.46697 + vertex 0.850624 1.94183 2.47114 + endloop + endfacet + facet normal 0.986382 -0.0844448 0.14114 + outer loop + vertex 0.851634 1.94666 2.46697 + vertex 0.850986 1.94665 2.4715 + vertex 0.850624 1.94183 2.47114 + endloop + endfacet + facet normal 0.976514 -0.0878304 0.196739 + outer loop + vertex 0.850624 1.94183 2.47114 + vertex 0.850986 1.94665 2.4715 + vertex 0.849865 1.94248 2.4752 + endloop + endfacet + facet normal 0.972946 -0.0645869 0.221822 + outer loop + vertex 0.850986 1.94665 2.4715 + vertex 0.850124 1.94725 2.47546 + vertex 0.849865 1.94248 2.4752 + endloop + endfacet + facet normal 0.949266 -0.0678578 0.307065 + outer loop + vertex 0.850124 1.94725 2.47546 + vertex 0.848772 1.9437 2.47885 + vertex 0.849865 1.94248 2.4752 + endloop + endfacet + facet normal 0.94145 -0.0382773 0.334972 + outer loop + vertex 0.848948 1.94865 2.47892 + vertex 0.848772 1.9437 2.47885 + vertex 0.850124 1.94725 2.47546 + endloop + endfacet + facet normal 0.930171 -0.0301386 0.365888 + outer loop + vertex 0.853336 1.95 2.46 + vertex 0.853498 1.955 2.46 + vertex 0.852202 1.94738 2.46267 + endloop + endfacet + facet normal 0.987329 -0.151756 0.0463868 + outer loop + vertex 0.853498 1.955 2.46 + vertex 0.85287 1.95179 2.46288 + vertex 0.852202 1.94738 2.46267 + endloop + endfacet + facet normal 0.98265 -0.153757 0.103722 + outer loop + vertex 0.852202 1.94738 2.46267 + vertex 0.85287 1.95179 2.46288 + vertex 0.851634 1.94666 2.46697 + endloop + endfacet + facet normal 0.982669 -0.152916 0.104781 + outer loop + vertex 0.85287 1.95179 2.46288 + vertex 0.852283 1.95155 2.46803 + vertex 0.851634 1.94666 2.46697 + endloop + endfacet + facet normal 0.97723 -0.159703 0.1397 + outer loop + vertex 0.851634 1.94666 2.46697 + vertex 0.852283 1.95155 2.46803 + vertex 0.850986 1.94665 2.4715 + endloop + endfacet + facet normal 0.973735 -0.121193 0.192752 + outer loop + vertex 0.852283 1.95155 2.46803 + vertex 0.85126 1.95048 2.47252 + vertex 0.850986 1.94665 2.4715 + endloop + endfacet + facet normal 0.964398 -0.130473 0.230028 + outer loop + vertex 0.850986 1.94665 2.4715 + vertex 0.85126 1.95048 2.47252 + vertex 0.850124 1.94725 2.47546 + endloop + endfacet + facet normal 0.957966 -0.0896245 0.272524 + outer loop + vertex 0.85126 1.95048 2.47252 + vertex 0.850468 1.95182 2.47575 + vertex 0.850124 1.94725 2.47546 + endloop + endfacet + facet normal 0.930866 -0.0927731 0.353385 + outer loop + vertex 0.850468 1.95182 2.47575 + vertex 0.848948 1.94865 2.47892 + vertex 0.850124 1.94725 2.47546 + endloop + endfacet + facet normal 0.918749 -0.0484716 0.391855 + outer loop + vertex 0.849135 1.95338 2.47907 + vertex 0.848948 1.94865 2.47892 + vertex 0.850468 1.95182 2.47575 + endloop + endfacet + facet normal 0.95104 -0.257852 0.170398 + outer loop + vertex 0.855 1.95775 2.46 + vertex 0.853699 1.9553 2.46355 + vertex 0.85287 1.95179 2.46288 + endloop + endfacet + facet normal 0.8302 -0.453464 -0.32425 + outer loop + vertex 0.853498 1.955 2.46 + vertex 0.855 1.95775 2.46 + vertex 0.85287 1.95179 2.46288 + endloop + endfacet + facet normal 0.965124 -0.24007 0.104412 + outer loop + vertex 0.853699 1.9553 2.46355 + vertex 0.853319 1.95557 2.46768 + vertex 0.852283 1.95155 2.46803 + endloop + endfacet + facet normal 0.964012 -0.247044 0.0982312 + outer loop + vertex 0.85287 1.95179 2.46288 + vertex 0.853699 1.9553 2.46355 + vertex 0.852283 1.95155 2.46803 + endloop + endfacet + facet normal 0.938252 -0.256172 0.232505 + outer loop + vertex 0.853319 1.95557 2.46768 + vertex 0.853571 1.958 2.46934 + vertex 0.85212 1.95528 2.4722 + endloop + endfacet + facet normal 0.94554 -0.223635 0.236522 + outer loop + vertex 0.853319 1.95557 2.46768 + vertex 0.85212 1.95528 2.4722 + vertex 0.852283 1.95155 2.46803 + endloop + endfacet + facet normal 0.969862 -0.161731 0.182241 + outer loop + vertex 0.852283 1.95155 2.46803 + vertex 0.85212 1.95528 2.4722 + vertex 0.85126 1.95048 2.47252 + endloop + endfacet + facet normal 0.944032 -0.149562 0.293998 + outer loop + vertex 0.85126 1.95048 2.47252 + vertex 0.85212 1.95528 2.4722 + vertex 0.850468 1.95182 2.47575 + endloop + endfacet + facet normal 0.934147 -0.0927891 0.344614 + outer loop + vertex 0.85212 1.95528 2.4722 + vertex 0.85063 1.95577 2.47637 + vertex 0.850468 1.95182 2.47575 + endloop + endfacet + facet normal 0.90556 -0.102224 0.411717 + outer loop + vertex 0.85063 1.95577 2.47637 + vertex 0.849135 1.95338 2.47907 + vertex 0.850468 1.95182 2.47575 + endloop + endfacet + facet normal 0.890884 -0.0479952 0.451689 + outer loop + vertex 0.849353 1.95793 2.47912 + vertex 0.849135 1.95338 2.47907 + vertex 0.85063 1.95577 2.47637 + endloop + endfacet + facet normal 0.935789 -0.182201 0.301829 + outer loop + vertex 0.853571 1.958 2.46934 + vertex 0.853036 1.9596 2.47197 + vertex 0.85212 1.95528 2.4722 + endloop + endfacet + facet normal 0.903557 -0.10174 0.416213 + outer loop + vertex 0.853036 1.9596 2.47197 + vertex 0.853078 1.96364 2.47287 + vertex 0.851428 1.96005 2.47557 + endloop + endfacet + facet normal 0.892373 -0.166638 0.419408 + outer loop + vertex 0.853036 1.9596 2.47197 + vertex 0.851428 1.96005 2.47557 + vertex 0.85212 1.95528 2.4722 + endloop + endfacet + facet normal 0.931986 -0.108925 0.345741 + outer loop + vertex 0.85212 1.95528 2.4722 + vertex 0.851428 1.96005 2.47557 + vertex 0.85063 1.95577 2.47637 + endloop + endfacet + facet normal 0.880003 -0.0761359 0.468826 + outer loop + vertex 0.851428 1.96005 2.47557 + vertex 0.849353 1.95793 2.47912 + vertex 0.85063 1.95577 2.47637 + endloop + endfacet + facet normal 0.870534 -0.0292024 0.491241 + outer loop + vertex 0.849392 1.96277 2.47934 + vertex 0.849353 1.95793 2.47912 + vertex 0.851428 1.96005 2.47557 + endloop + endfacet + facet normal 0.890325 -0.0505275 0.452514 + outer loop + vertex 0.853078 1.96364 2.47287 + vertex 0.853139 1.96861 2.4733 + vertex 0.851426 1.96548 2.47632 + endloop + endfacet + facet normal 0.886952 -0.063041 0.457538 + outer loop + vertex 0.851428 1.96005 2.47557 + vertex 0.853078 1.96364 2.47287 + vertex 0.851426 1.96548 2.47632 + endloop + endfacet + facet normal 0.85545 -0.0707375 0.513032 + outer loop + vertex 0.851426 1.96548 2.47632 + vertex 0.849392 1.96277 2.47934 + vertex 0.851428 1.96005 2.47557 + endloop + endfacet + facet normal 0.83252 -0.00791001 0.553938 + outer loop + vertex 0.849279 1.9678 2.47958 + vertex 0.849392 1.96277 2.47934 + vertex 0.851426 1.96548 2.47632 + endloop + endfacet + facet normal 0.874384 -0.0285751 0.484393 + outer loop + vertex 0.853139 1.96861 2.4733 + vertex 0.853274 1.97352 2.47335 + vertex 0.851429 1.9704 2.47649 + endloop + endfacet + facet normal 0.877298 -0.0173096 0.479634 + outer loop + vertex 0.851426 1.96548 2.47632 + vertex 0.853139 1.96861 2.4733 + vertex 0.851429 1.9704 2.47649 + endloop + endfacet + facet normal 0.828333 -0.0201084 0.559875 + outer loop + vertex 0.851429 1.9704 2.47649 + vertex 0.849279 1.9678 2.47958 + vertex 0.851426 1.96548 2.47632 + endloop + endfacet + facet normal 0.825416 -0.0123462 0.56439 + outer loop + vertex 0.849287 1.97283 2.47968 + vertex 0.849279 1.9678 2.47958 + vertex 0.851429 1.9704 2.47649 + endloop + endfacet + facet normal 0.865367 -0.0355062 0.499879 + outer loop + vertex 0.853274 1.97352 2.47335 + vertex 0.85345 1.97832 2.47338 + vertex 0.851485 1.97524 2.47657 + endloop + endfacet + facet normal 0.869967 -0.0174789 0.4928 + outer loop + vertex 0.851429 1.9704 2.47649 + vertex 0.853274 1.97352 2.47335 + vertex 0.851485 1.97524 2.47657 + endloop + endfacet + facet normal 0.823301 -0.0180631 0.567318 + outer loop + vertex 0.851485 1.97524 2.47657 + vertex 0.849287 1.97283 2.47968 + vertex 0.851429 1.9704 2.47649 + endloop + endfacet + facet normal 0.850488 -0.11142 0.514059 + outer loop + vertex 0.849544 1.9784 2.48046 + vertex 0.849287 1.97283 2.47968 + vertex 0.851485 1.97524 2.47657 + endloop + endfacet + facet normal 0.881799 -0.0448369 0.469488 + outer loop + vertex 0.85345 1.97832 2.47338 + vertex 0.853602 1.98299 2.47354 + vertex 0.851545 1.98033 2.47715 + endloop + endfacet + facet normal 0.876127 -0.0654556 0.477615 + outer loop + vertex 0.851485 1.97524 2.47657 + vertex 0.85345 1.97832 2.47338 + vertex 0.851545 1.98033 2.47715 + endloop + endfacet + facet normal 0.870469 -0.0665539 0.487703 + outer loop + vertex 0.851545 1.98033 2.47715 + vertex 0.849544 1.9784 2.48046 + vertex 0.851485 1.97524 2.47657 + endloop + endfacet + facet normal 0.885264 -0.275953 0.374376 + outer loop + vertex 0.85 1.985 2.48425 + vertex 0.849544 1.9784 2.48046 + vertex 0.851545 1.98033 2.47715 + endloop + endfacet + facet normal 0.88857 -0.03835 0.457136 + outer loop + vertex 0.853602 1.98299 2.47354 + vertex 0.853793 1.98773 2.47357 + vertex 0.851594 1.98545 2.47765 + endloop + endfacet + facet normal 0.884096 -0.053784 0.464199 + outer loop + vertex 0.851545 1.98033 2.47715 + vertex 0.853602 1.98299 2.47354 + vertex 0.851594 1.98545 2.47765 + endloop + endfacet + facet normal 0.972027 -0.0320765 0.232667 + outer loop + vertex 0.851594 1.98545 2.47765 + vertex 0.85 1.985 2.48425 + vertex 0.851545 1.98033 2.47715 + endloop + endfacet + facet normal 0.972014 0.000940954 0.234919 + outer loop + vertex 0.85 1.99 2.48423 + vertex 0.85 1.985 2.48425 + vertex 0.851594 1.98545 2.47765 + endloop + endfacet + facet normal 0.870197 -0.0279639 0.491909 + outer loop + vertex 0.853793 1.98773 2.47357 + vertex 0.853915 1.99283 2.47364 + vertex 0.851635 1.99053 2.47755 + endloop + endfacet + facet normal 0.879747 0.00284229 0.475433 + outer loop + vertex 0.851594 1.98545 2.47765 + vertex 0.853793 1.98773 2.47357 + vertex 0.851635 1.99053 2.47755 + endloop + endfacet + facet normal 0.971402 -0.00289576 0.237424 + outer loop + vertex 0.851635 1.99053 2.47755 + vertex 0.85 1.99 2.48423 + vertex 0.851594 1.98545 2.47765 + endloop + endfacet + facet normal 0.969703 0.0423439 0.240589 + outer loop + vertex 0.85 1.995 2.48335 + vertex 0.85 1.99 2.48423 + vertex 0.851635 1.99053 2.47755 + endloop + endfacet + facet normal 0.849374 -0.0277712 0.527061 + outer loop + vertex 0.853915 1.99283 2.47364 + vertex 0.853872 1.99813 2.47399 + vertex 0.851635 1.9958 2.47747 + endloop + endfacet + facet normal 0.861654 0.00689993 0.50745 + outer loop + vertex 0.851635 1.99053 2.47755 + vertex 0.853915 1.99283 2.47364 + vertex 0.851635 1.9958 2.47747 + endloop + endfacet + facet normal 0.963264 0.00371436 0.268529 + outer loop + vertex 0.851635 1.9958 2.47747 + vertex 0.85 1.995 2.48335 + vertex 0.851635 1.99053 2.47755 + endloop + endfacet + facet normal 0.962315 0.0233064 0.270937 + outer loop + vertex 0.85 2 2.48292 + vertex 0.85 1.995 2.48335 + vertex 0.851635 1.9958 2.47747 + endloop + endfacet + facet normal 0.821692 -0.104773 0.560218 + outer loop + vertex 0.853872 1.99813 2.47399 + vertex 0.853996 2.00392 2.47489 + vertex 0.851722 2.00148 2.47777 + endloop + endfacet + facet normal 0.85273 -0.0403412 0.520792 + outer loop + vertex 0.851635 1.9958 2.47747 + vertex 0.853872 1.99813 2.47399 + vertex 0.851722 2.00148 2.47777 + endloop + endfacet + facet normal 0.95053 -0.0307779 0.309105 + outer loop + vertex 0.851722 2.00148 2.47777 + vertex 0.85 2 2.48292 + vertex 0.851635 1.9958 2.47747 + endloop + endfacet + facet normal 0.941945 0.0556248 0.331128 + outer loop + vertex 0.85 2.005 2.48208 + vertex 0.85 2 2.48292 + vertex 0.851722 2.00148 2.47777 + endloop + endfacet + facet normal -0.926191 0.265005 0.268221 + outer loop + vertex 0.849658 2.00401 2.48649 + vertex 0.85 2.00166 2.49 + vertex 0.85 2.005 2.4867 + endloop + endfacet + facet normal 0.991085 0.133032 -0.00723796 + outer loop + vertex 0.849723 2.00372 2.48994 + vertex 0.85 2.00166 2.49 + vertex 0.849658 2.00401 2.48649 + endloop + endfacet + facet normal 0.883752 0.13206 0.448935 + outer loop + vertex 0.84843 2.00004 2.49357 + vertex 0.85 2.00166 2.49 + vertex 0.849723 2.00372 2.48994 + endloop + endfacet + facet normal 0.968386 -0.214201 0.127855 + outer loop + vertex 0.849107 2.004 2.49507 + vertex 0.84843 2.00004 2.49357 + vertex 0.849723 2.00372 2.48994 + endloop + endfacet + facet normal 0.904992 -0.277405 0.322546 + outer loop + vertex 0.846979 1.99992 2.49754 + vertex 0.84843 2.00004 2.49357 + vertex 0.849107 2.004 2.49507 + endloop + endfacet + facet normal 0.863924 -0.163044 0.4765 + outer loop + vertex 0.849107 2.004 2.49507 + vertex 0.847165 2.00342 2.49839 + vertex 0.846979 1.99992 2.49754 + endloop + endfacet + facet normal 0.581107 -0.436641 0.686775 + outer loop + vertex 0.853996 2.00392 2.47489 + vertex 0.855 2.01 2.47791 + vertex 0.85253 2.01 2.48 + endloop + endfacet + facet normal 0.845619 -0.208734 0.491282 + outer loop + vertex 0.851722 2.00148 2.47777 + vertex 0.853996 2.00392 2.47489 + vertex 0.85253 2.01 2.48 + endloop + endfacet + facet normal 0.835519 -0.21188 0.506967 + outer loop + vertex 0.85253 2.01 2.48 + vertex 0.85 2.005 2.48208 + vertex 0.851722 2.00148 2.47777 + endloop + endfacet + facet normal 0.847453 -0.229722 0.478592 + outer loop + vertex 0.85 2.01 2.48448 + vertex 0.85 2.005 2.48208 + vertex 0.85253 2.01 2.48 + endloop + endfacet + facet normal -0.918093 0.254825 0.303594 + outer loop + vertex 0.849581 2.00602 2.48458 + vertex 0.849658 2.00401 2.48649 + vertex 0.85 2.005 2.4867 + endloop + endfacet + facet normal 0.925 -0.243315 -0.291844 + outer loop + vertex 0.850574 2.00777 2.48627 + vertex 0.849658 2.00401 2.48649 + vertex 0.849581 2.00602 2.48458 + endloop + endfacet + facet normal 0.970207 -0.239187 -0.0385606 + outer loop + vertex 0.849658 2.00401 2.48649 + vertex 0.850574 2.00777 2.48627 + vertex 0.849723 2.00372 2.48994 + endloop + endfacet + facet normal 0.974222 -0.224564 -0.0215108 + outer loop + vertex 0.850574 2.00777 2.48627 + vertex 0.85065 2.00765 2.49089 + vertex 0.849723 2.00372 2.48994 + endloop + endfacet + facet normal 0.957732 -0.257158 0.128913 + outer loop + vertex 0.849723 2.00372 2.48994 + vertex 0.85065 2.00765 2.49089 + vertex 0.849107 2.004 2.49507 + endloop + endfacet + facet normal 0.959069 -0.247227 0.138074 + outer loop + vertex 0.85065 2.00765 2.49089 + vertex 0.850208 2.00816 2.49487 + vertex 0.849107 2.004 2.49507 + endloop + endfacet + facet normal 0.7474 -0.315515 0.584674 + outer loop + vertex 0.847165 2.00342 2.49839 + vertex 0.848772 2.00679 2.49816 + vertex 0.847307 2.00568 2.49944 + endloop + endfacet + facet normal 0.830001 -0.365915 0.420957 + outer loop + vertex 0.847165 2.00342 2.49839 + vertex 0.849107 2.004 2.49507 + vertex 0.848772 2.00679 2.49816 + endloop + endfacet + facet normal 0.923381 -0.229504 0.307726 + outer loop + vertex 0.849107 2.004 2.49507 + vertex 0.850208 2.00816 2.49487 + vertex 0.848772 2.00679 2.49816 + endloop + endfacet + facet normal 0.754498 -0.3889 0.528667 + outer loop + vertex 0.848772 2.00679 2.49816 + vertex 0.847901 2.00711 2.49964 + vertex 0.847307 2.00568 2.49944 + endloop + endfacet + facet normal 0.879687 -0.042039 -0.473691 + outer loop + vertex 0.85 2.01006 2.485 + vertex 0.850574 2.00777 2.48627 + vertex 0.849581 2.00602 2.48458 + endloop + endfacet + facet normal 0.473796 -0.332709 -0.815367 + outer loop + vertex 0.85 2.01006 2.485 + vertex 0.853469 2.015 2.485 + vertex 0.850574 2.00777 2.48627 + endloop + endfacet + facet normal 0.90124 -0.306898 0.30591 + outer loop + vertex 0.853469 2.015 2.485 + vertex 0.851883 2.01265 2.48731 + vertex 0.850574 2.00777 2.48627 + endloop + endfacet + facet normal 0.966871 -0.254306 -0.0221333 + outer loop + vertex 0.850574 2.00777 2.48627 + vertex 0.851883 2.01265 2.48731 + vertex 0.85065 2.00765 2.49089 + endloop + endfacet + facet normal 0.980279 -0.148333 0.130574 + outer loop + vertex 0.851883 2.01265 2.48731 + vertex 0.851194 2.012 2.49175 + vertex 0.85065 2.00765 2.49089 + endloop + endfacet + facet normal 0.980731 -0.147826 0.127724 + outer loop + vertex 0.85065 2.00765 2.49089 + vertex 0.851194 2.012 2.49175 + vertex 0.850208 2.00816 2.49487 + endloop + endfacet + facet normal 0.948735 0.0130854 0.315801 + outer loop + vertex 0.851194 2.012 2.49175 + vertex 0.849769 2.01162 2.49605 + vertex 0.850208 2.00816 2.49487 + endloop + endfacet + facet normal 0.722516 0.226627 0.653155 + outer loop + vertex 0.848092 2.00949 2.49864 + vertex 0.849769 2.01162 2.49605 + vertex 0.848263 2.01298 2.49724 + endloop + endfacet + facet normal 0.798244 0.0958329 0.594661 + outer loop + vertex 0.848092 2.00949 2.49864 + vertex 0.848772 2.00679 2.49816 + vertex 0.849769 2.01162 2.49605 + endloop + endfacet + facet normal 0.919012 -0.0172097 0.393854 + outer loop + vertex 0.848772 2.00679 2.49816 + vertex 0.850208 2.00816 2.49487 + vertex 0.849769 2.01162 2.49605 + endloop + endfacet + facet normal 0.865936 0.132803 0.482201 + outer loop + vertex 0.848772 2.00679 2.49816 + vertex 0.848092 2.00949 2.49864 + vertex 0.847901 2.00711 2.49964 + endloop + endfacet + facet normal 0.841679 -0.0375366 0.538672 + outer loop + vertex 0.853469 2.015 2.485 + vertex 0.853692 2.02 2.485 + vertex 0.851883 2.01265 2.48731 + endloop + endfacet + facet normal 0.941196 -0.133991 0.310155 + outer loop + vertex 0.853692 2.02 2.485 + vertex 0.852332 2.01725 2.48794 + vertex 0.851883 2.01265 2.48731 + endloop + endfacet + facet normal 0.984046 -0.114613 0.13608 + outer loop + vertex 0.851883 2.01265 2.48731 + vertex 0.852332 2.01725 2.48794 + vertex 0.851194 2.012 2.49175 + endloop + endfacet + facet normal 0.955791 0.00630864 0.293979 + outer loop + vertex 0.852332 2.01725 2.48794 + vertex 0.851031 2.01645 2.49219 + vertex 0.851194 2.012 2.49175 + endloop + endfacet + facet normal 0.94905 0.00399569 0.315101 + outer loop + vertex 0.851194 2.012 2.49175 + vertex 0.851031 2.01645 2.49219 + vertex 0.849769 2.01162 2.49605 + endloop + endfacet + facet normal 0.839193 0.188703 0.510046 + outer loop + vertex 0.851031 2.01645 2.49219 + vertex 0.849277 2.01631 2.49512 + vertex 0.849769 2.01162 2.49605 + endloop + endfacet + facet normal 0.715656 0.206735 0.667156 + outer loop + vertex 0.849277 2.01631 2.49512 + vertex 0.848263 2.01298 2.49724 + vertex 0.849769 2.01162 2.49605 + endloop + endfacet + facet normal 0.293766 0.447922 0.844433 + outer loop + vertex 0.847545 2.01564 2.49608 + vertex 0.848263 2.01298 2.49724 + vertex 0.849277 2.01631 2.49512 + endloop + endfacet + facet normal 0.935972 -0.103139 0.336628 + outer loop + vertex 0.853692 2.02 2.485 + vertex 0.854243 2.025 2.485 + vertex 0.852332 2.01725 2.48794 + endloop + endfacet + facet normal 0.906601 -0.0654856 0.416877 + outer loop + vertex 0.854243 2.025 2.485 + vertex 0.852214 2.02069 2.48873 + vertex 0.852332 2.01725 2.48794 + endloop + endfacet + facet normal 0.957366 -0.0336268 0.286913 + outer loop + vertex 0.852332 2.01725 2.48794 + vertex 0.852214 2.02069 2.48873 + vertex 0.851031 2.01645 2.49219 + endloop + endfacet + facet normal 0.894752 0.10384 0.434323 + outer loop + vertex 0.852214 2.02069 2.48873 + vertex 0.850566 2.02122 2.492 + vertex 0.851031 2.01645 2.49219 + endloop + endfacet + facet normal 0.545317 0.188034 0.816867 + outer loop + vertex 0.848038 2.01945 2.4941 + vertex 0.850566 2.02122 2.492 + vertex 0.84887 2.02327 2.49266 + endloop + endfacet + facet normal 0.386413 0.420291 0.821 + outer loop + vertex 0.848038 2.01945 2.4941 + vertex 0.849277 2.01631 2.49512 + vertex 0.850566 2.02122 2.492 + endloop + endfacet + facet normal 0.851797 0.1027 0.513707 + outer loop + vertex 0.849277 2.01631 2.49512 + vertex 0.851031 2.01645 2.49219 + vertex 0.850566 2.02122 2.492 + endloop + endfacet + facet normal 0.317538 0.404996 0.857408 + outer loop + vertex 0.849277 2.01631 2.49512 + vertex 0.848038 2.01945 2.4941 + vertex 0.847545 2.01564 2.49608 + endloop + endfacet + facet normal 0.458333 0.418295 0.784194 + outer loop + vertex 0.855 2.02815 2.485 + vertex 0.854203 2.0284 2.48533 + vertex 0.852964 2.0252 2.48776 + endloop + endfacet + facet normal 0.881046 -0.211743 0.422992 + outer loop + vertex 0.855 2.02815 2.485 + vertex 0.852964 2.0252 2.48776 + vertex 0.854243 2.025 2.485 + endloop + endfacet + facet normal 0.904313 -0.0593441 0.422726 + outer loop + vertex 0.854243 2.025 2.485 + vertex 0.852964 2.0252 2.48776 + vertex 0.852214 2.02069 2.48873 + endloop + endfacet + facet normal 0.888543 -0.0495388 0.45611 + outer loop + vertex 0.852214 2.02069 2.48873 + vertex 0.852964 2.0252 2.48776 + vertex 0.850566 2.02122 2.492 + endloop + endfacet + facet normal 0.903064 -0.0989267 0.417957 + outer loop + vertex 0.852964 2.0252 2.48776 + vertex 0.851288 2.02683 2.49177 + vertex 0.850566 2.02122 2.492 + endloop + endfacet + facet normal 0.355448 -0.00694046 0.93467 + outer loop + vertex 0.851288 2.02683 2.49177 + vertex 0.84887 2.02327 2.49266 + vertex 0.850566 2.02122 2.492 + endloop + endfacet + facet normal -0.00512026 0.246738 0.969069 + outer loop + vertex 0.848434 2.02606 2.49195 + vertex 0.84887 2.02327 2.49266 + vertex 0.851288 2.02683 2.49177 + endloop + endfacet + facet normal 0.0281491 -0.00358039 -0.999597 + outer loop + vertex 0.854047 2.03 2.48 + vertex 0.854683 2.035 2.48 + vertex 0.854498 2.03142 2.48001 + endloop + endfacet + facet normal 0.922003 -0.292258 -0.253961 + outer loop + vertex 0.855 2.03 2.48346 + vertex 0.854047 2.03 2.48 + vertex 0.854498 2.03142 2.48001 + endloop + endfacet + facet normal 0.955658 -0.236629 0.175286 + outer loop + vertex 0.854203 2.0284 2.48533 + vertex 0.853718 2.02906 2.48886 + vertex 0.852964 2.0252 2.48776 + endloop + endfacet + facet normal 0.806323 -0.526505 0.269509 + outer loop + vertex 0.853718 2.02906 2.48886 + vertex 0.853321 2.03012 2.49213 + vertex 0.851288 2.02683 2.49177 + endloop + endfacet + facet normal 0.832408 -0.296167 0.468382 + outer loop + vertex 0.852964 2.0252 2.48776 + vertex 0.853718 2.02906 2.48886 + vertex 0.851288 2.02683 2.49177 + endloop + endfacet + facet normal 0.0812127 -0.0708521 0.994175 + outer loop + vertex 0.851288 2.02683 2.49177 + vertex 0.849658 2.02989 2.49212 + vertex 0.848434 2.02606 2.49195 + endloop + endfacet + facet normal -0.422838 -0.321753 0.847162 + outer loop + vertex 0.851288 2.02683 2.49177 + vertex 0.85222 2.03048 2.49362 + vertex 0.849658 2.02989 2.49212 + endloop + endfacet + facet normal 0.654983 -0.46817 0.593139 + outer loop + vertex 0.851288 2.02683 2.49177 + vertex 0.853321 2.03012 2.49213 + vertex 0.85222 2.03048 2.49362 + endloop + endfacet + facet normal -0.487517 -0.0927156 0.868177 + outer loop + vertex 0.851581 2.0328 2.49351 + vertex 0.849658 2.02989 2.49212 + vertex 0.85222 2.03048 2.49362 + endloop + endfacet + facet normal -0.587455 -0.123555 0.79977 + outer loop + vertex 0.85222 2.03048 2.49362 + vertex 0.85283 2.0323 2.49435 + vertex 0.851581 2.0328 2.49351 + endloop + endfacet + facet normal 0.00226655 -0.00224586 -0.999995 + outer loop + vertex 0.855 2.03532 2.48 + vertex 0.854498 2.03142 2.48001 + vertex 0.854683 2.035 2.48 + endloop + endfacet + facet normal -0.715273 0.305427 0.628569 + outer loop + vertex 0.851261 2.03758 2.49134 + vertex 0.848967 2.03573 2.48963 + vertex 0.849841 2.03351 2.4917 + endloop + endfacet + facet normal -0.692524 0.117946 0.711688 + outer loop + vertex 0.849841 2.03351 2.4917 + vertex 0.849658 2.02989 2.49212 + vertex 0.851581 2.0328 2.49351 + endloop + endfacet + facet normal -0.632863 0.284809 0.719978 + outer loop + vertex 0.851261 2.03758 2.49134 + vertex 0.849841 2.03351 2.4917 + vertex 0.851581 2.0328 2.49351 + endloop + endfacet + facet normal -0.439847 0.346999 0.828327 + outer loop + vertex 0.851261 2.03758 2.49134 + vertex 0.851581 2.0328 2.49351 + vertex 0.85309 2.0347 2.49352 + endloop + endfacet + facet normal -0.422256 0.360669 0.831636 + outer loop + vertex 0.851261 2.03758 2.49134 + vertex 0.85309 2.0347 2.49352 + vertex 0.85344 2.03802 2.49225 + endloop + endfacet + facet normal -0.42961 0.338856 0.837026 + outer loop + vertex 0.85309 2.0347 2.49352 + vertex 0.851581 2.0328 2.49351 + vertex 0.85283 2.0323 2.49435 + endloop + endfacet + facet normal -0.811363 0.310038 0.495547 + outer loop + vertex 0.850004 2.04222 2.48748 + vertex 0.848279 2.04107 2.48538 + vertex 0.849067 2.03862 2.4882 + endloop + endfacet + facet normal -0.720057 0.326355 0.612381 + outer loop + vertex 0.849067 2.03862 2.4882 + vertex 0.848967 2.03573 2.48963 + vertex 0.851261 2.03758 2.49134 + endloop + endfacet + facet normal -0.726846 0.31138 0.612158 + outer loop + vertex 0.849067 2.03862 2.4882 + vertex 0.851261 2.03758 2.49134 + vertex 0.850004 2.04222 2.48748 + endloop + endfacet + facet normal -0.710953 0.32514 0.623563 + outer loop + vertex 0.850004 2.04222 2.48748 + vertex 0.851261 2.03758 2.49134 + vertex 0.852031 2.04326 2.48926 + endloop + endfacet + facet normal -0.571449 0.349772 0.742365 + outer loop + vertex 0.851261 2.03758 2.49134 + vertex 0.853047 2.04074 2.49123 + vertex 0.852031 2.04326 2.48926 + endloop + endfacet + facet normal -0.41843 0.26774 0.867889 + outer loop + vertex 0.85344 2.03802 2.49225 + vertex 0.853047 2.04074 2.49123 + vertex 0.851261 2.03758 2.49134 + endloop + endfacet + facet normal -0.811373 0.309712 0.495734 + outer loop + vertex 0.848756 2.04515 2.48361 + vertex 0.848279 2.04107 2.48538 + vertex 0.850004 2.04222 2.48748 + endloop + endfacet + facet normal -0.803138 0.321228 0.501778 + outer loop + vertex 0.850988 2.0479 2.48543 + vertex 0.848756 2.04515 2.48361 + vertex 0.850004 2.04222 2.48748 + endloop + endfacet + facet normal -0.306152 0.46497 0.830707 + outer loop + vertex 0.853225 2.04702 2.48759 + vertex 0.852031 2.04326 2.48926 + vertex 0.85365 2.04373 2.48959 + endloop + endfacet + facet normal -0.506301 0.478315 0.717547 + outer loop + vertex 0.853225 2.04702 2.48759 + vertex 0.850988 2.0479 2.48543 + vertex 0.852031 2.04326 2.48926 + endloop + endfacet + facet normal -0.7113 0.345329 0.612209 + outer loop + vertex 0.850988 2.0479 2.48543 + vertex 0.850004 2.04222 2.48748 + vertex 0.852031 2.04326 2.48926 + endloop + endfacet + facet normal -0.31214 0.503607 0.805574 + outer loop + vertex 0.85365 2.04373 2.48959 + vertex 0.852031 2.04326 2.48926 + vertex 0.853047 2.04074 2.49123 + endloop + endfacet + facet normal -0.853036 0.291358 0.432943 + outer loop + vertex 0.850031 2.05294 2.4812 + vertex 0.848549 2.05138 2.47933 + vertex 0.849117 2.04914 2.48196 + endloop + endfacet + facet normal -0.793658 0.292753 0.533294 + outer loop + vertex 0.849117 2.04914 2.48196 + vertex 0.848756 2.04515 2.48361 + vertex 0.850988 2.0479 2.48543 + endloop + endfacet + facet normal -0.791857 0.296765 0.533753 + outer loop + vertex 0.849117 2.04914 2.48196 + vertex 0.850988 2.0479 2.48543 + vertex 0.850031 2.05294 2.4812 + endloop + endfacet + facet normal -0.710088 0.368028 0.600275 + outer loop + vertex 0.850031 2.05294 2.4812 + vertex 0.850988 2.0479 2.48543 + vertex 0.85239 2.05257 2.48422 + endloop + endfacet + facet normal -0.622445 0.365401 0.69213 + outer loop + vertex 0.850988 2.0479 2.48543 + vertex 0.852935 2.05008 2.48602 + vertex 0.85239 2.05257 2.48422 + endloop + endfacet + facet normal -0.589465 0.322815 0.740487 + outer loop + vertex 0.853225 2.04702 2.48759 + vertex 0.852935 2.05008 2.48602 + vertex 0.850988 2.0479 2.48543 + endloop + endfacet + facet normal -0.898448 0.296492 0.323857 + outer loop + vertex 0.849546 2.05724 2.47745 + vertex 0.848358 2.0562 2.47511 + vertex 0.848664 2.05415 2.47784 + endloop + endfacet + facet normal -0.851967 0.275884 0.445018 + outer loop + vertex 0.848664 2.05415 2.47784 + vertex 0.848549 2.05138 2.47933 + vertex 0.850031 2.05294 2.4812 + endloop + endfacet + facet normal -0.843173 0.296147 0.448727 + outer loop + vertex 0.848664 2.05415 2.47784 + vertex 0.850031 2.05294 2.4812 + vertex 0.849546 2.05724 2.47745 + endloop + endfacet + facet normal -0.782322 0.356858 0.510514 + outer loop + vertex 0.849546 2.05724 2.47745 + vertex 0.850031 2.05294 2.4812 + vertex 0.851999 2.05744 2.48107 + endloop + endfacet + facet normal -0.453651 0.51223 0.729261 + outer loop + vertex 0.85511 2.05468 2.48443 + vertex 0.85239 2.05257 2.48422 + vertex 0.853716 2.05196 2.48548 + endloop + endfacet + facet normal -0.422801 0.467711 0.7762 + outer loop + vertex 0.85511 2.05468 2.48443 + vertex 0.851999 2.05744 2.48107 + vertex 0.85239 2.05257 2.48422 + endloop + endfacet + facet normal -0.722475 0.333415 0.605693 + outer loop + vertex 0.851999 2.05744 2.48107 + vertex 0.850031 2.05294 2.4812 + vertex 0.85239 2.05257 2.48422 + endloop + endfacet + facet normal -0.507798 0.429999 0.746487 + outer loop + vertex 0.853716 2.05196 2.48548 + vertex 0.85239 2.05257 2.48422 + vertex 0.852935 2.05008 2.48602 + endloop + endfacet + facet normal -0.898106 0.298862 0.322626 + outer loop + vertex 0.848882 2.05967 2.47336 + vertex 0.848358 2.0562 2.47511 + vertex 0.849546 2.05724 2.47745 + endloop + endfacet + facet normal -0.88504 0.323264 0.334969 + outer loop + vertex 0.850651 2.0622 2.47559 + vertex 0.848882 2.05967 2.47336 + vertex 0.849546 2.05724 2.47745 + endloop + endfacet + facet normal -0.779866 0.365154 0.508401 + outer loop + vertex 0.849546 2.05724 2.47745 + vertex 0.851999 2.05744 2.48107 + vertex 0.850651 2.0622 2.47559 + endloop + endfacet + facet normal -0.873419 0.24067 0.42334 + outer loop + vertex 0.850651 2.0622 2.47559 + vertex 0.851999 2.05744 2.48107 + vertex 0.852755 2.06265 2.47967 + endloop + endfacet + facet normal -0.77699 0.266279 0.570423 + outer loop + vertex 0.851999 2.05744 2.48107 + vertex 0.854466 2.0599 2.48329 + vertex 0.852755 2.06265 2.47967 + endloop + endfacet + facet normal -0.702991 0.0689776 0.707846 + outer loop + vertex 0.85511 2.05468 2.48443 + vertex 0.854466 2.0599 2.48329 + vertex 0.851999 2.05744 2.48107 + endloop + endfacet + facet normal -0.693855 0.379166 0.612208 + outer loop + vertex 0.851086 2.06779 2.47112 + vertex 0.851306 2.07 2.47 + vertex 0.85 2.06761 2.47 + endloop + endfacet + facet normal -0.70855 0.29925 0.639066 + outer loop + vertex 0.849563 2.06352 2.47143 + vertex 0.851086 2.06779 2.47112 + vertex 0.85 2.06761 2.47 + endloop + endfacet + facet normal -0.88506 0.323662 0.334534 + outer loop + vertex 0.849563 2.06352 2.47143 + vertex 0.848882 2.05967 2.47336 + vertex 0.850651 2.0622 2.47559 + endloop + endfacet + facet normal -0.878528 0.338133 0.337424 + outer loop + vertex 0.849563 2.06352 2.47143 + vertex 0.850651 2.0622 2.47559 + vertex 0.851086 2.06779 2.47112 + endloop + endfacet + facet normal -0.906968 0.303822 0.29172 + outer loop + vertex 0.851086 2.06779 2.47112 + vertex 0.850651 2.0622 2.47559 + vertex 0.852349 2.06724 2.47562 + endloop + endfacet + facet normal -0.83753 0.251757 0.484934 + outer loop + vertex 0.853574 2.06598 2.47936 + vertex 0.852755 2.06265 2.47967 + vertex 0.854373 2.06377 2.48188 + endloop + endfacet + facet normal -0.890326 0.254689 0.37743 + outer loop + vertex 0.853574 2.06598 2.47936 + vertex 0.852349 2.06724 2.47562 + vertex 0.852755 2.06265 2.47967 + endloop + endfacet + facet normal -0.863793 0.288521 0.413058 + outer loop + vertex 0.852349 2.06724 2.47562 + vertex 0.850651 2.0622 2.47559 + vertex 0.852755 2.06265 2.47967 + endloop + endfacet + facet normal -0.834565 0.169681 0.524128 + outer loop + vertex 0.854373 2.06377 2.48188 + vertex 0.852755 2.06265 2.47967 + vertex 0.854466 2.0599 2.48329 + endloop + endfacet + facet normal -0.826417 0.31766 0.464894 + outer loop + vertex 0.851306 2.07 2.47 + vertex 0.851086 2.06779 2.47112 + vertex 0.853228 2.075 2.47 + endloop + endfacet + facet normal -0.95313 0.294066 0.0711926 + outer loop + vertex 0.853228 2.075 2.47 + vertex 0.851086 2.06779 2.47112 + vertex 0.852602 2.07267 2.47123 + endloop + endfacet + facet normal -0.889346 0.267254 0.370997 + outer loop + vertex 0.853331 2.0712 2.47512 + vertex 0.852349 2.06724 2.47562 + vertex 0.85375 2.06887 2.4778 + endloop + endfacet + facet normal -0.925045 0.263789 0.273327 + outer loop + vertex 0.853331 2.0712 2.47512 + vertex 0.852602 2.07267 2.47123 + vertex 0.852349 2.06724 2.47562 + endloop + endfacet + facet normal -0.915584 0.277585 0.290951 + outer loop + vertex 0.852602 2.07267 2.47123 + vertex 0.851086 2.06779 2.47112 + vertex 0.852349 2.06724 2.47562 + endloop + endfacet + facet normal -0.8892 0.257662 0.378065 + outer loop + vertex 0.85375 2.06887 2.4778 + vertex 0.852349 2.06724 2.47562 + vertex 0.853574 2.06598 2.47936 + endloop + endfacet + facet normal -0.894747 -0.349765 -0.277654 + outer loop + vertex 0.855 2.075 2.46534 + vertex 0.853151 2.08 2.465 + vertex 0.855 2.07527 2.465 + endloop + endfacet + facet normal -0.876672 -0.346869 -0.33336 + outer loop + vertex 0.855 2.075 2.46534 + vertex 0.853228 2.075 2.47 + vertex 0.853151 2.08 2.465 + endloop + endfacet + facet normal 0.937032 -0.239642 -0.254051 + outer loop + vertex 0.853228 2.075 2.47 + vertex 0.852921 2.0774 2.4666 + vertex 0.853151 2.08 2.465 + endloop + endfacet + facet normal 0.82867 -0.419033 -0.371103 + outer loop + vertex 0.853228 2.075 2.47 + vertex 0.852602 2.07267 2.47123 + vertex 0.852921 2.0774 2.4666 + endloop + endfacet + facet normal -0.987163 0.140641 0.0756944 + outer loop + vertex 0.852921 2.0774 2.4666 + vertex 0.852602 2.07267 2.47123 + vertex 0.853194 2.07768 2.46964 + endloop + endfacet + facet normal -0.929597 0.206635 0.305206 + outer loop + vertex 0.852602 2.07267 2.47123 + vertex 0.853903 2.07505 2.47358 + vertex 0.853194 2.07768 2.46964 + endloop + endfacet + facet normal -0.931831 0.245182 0.267538 + outer loop + vertex 0.853331 2.0712 2.47512 + vertex 0.853903 2.07505 2.47358 + vertex 0.852602 2.07267 2.47123 + endloop + endfacet + facet normal 0.462841 0.0177067 -0.886265 + outer loop + vertex 0.855 2.08 2.46334 + vertex 0.853529 2.08157 2.4626 + vertex 0.855 2.085 2.46344 + endloop + endfacet + facet normal -0.478068 -0.698465 -0.532539 + outer loop + vertex 0.853151 2.08 2.465 + vertex 0.853529 2.08157 2.4626 + vertex 0.855 2.08 2.46334 + endloop + endfacet + facet normal 0.986168 0.0144338 0.165116 + outer loop + vertex 0.853151 2.08 2.465 + vertex 0.852921 2.0774 2.4666 + vertex 0.853529 2.08157 2.4626 + endloop + endfacet + facet normal -0.994443 0.0686099 -0.0798546 + outer loop + vertex 0.853529 2.08157 2.4626 + vertex 0.852921 2.0774 2.4666 + vertex 0.85329 2.08167 2.46567 + endloop + endfacet + facet normal -0.930714 0.186605 0.314563 + outer loop + vertex 0.853708 2.08097 2.46921 + vertex 0.853194 2.07768 2.46964 + vertex 0.854225 2.07886 2.47199 + endloop + endfacet + facet normal -0.973773 0.171797 0.149168 + outer loop + vertex 0.853708 2.08097 2.46921 + vertex 0.85329 2.08167 2.46567 + vertex 0.853194 2.07768 2.46964 + endloop + endfacet + facet normal -0.991498 0.103002 0.0795159 + outer loop + vertex 0.85329 2.08167 2.46567 + vertex 0.852921 2.0774 2.4666 + vertex 0.853194 2.07768 2.46964 + endloop + endfacet + facet normal -0.929977 0.205722 0.304665 + outer loop + vertex 0.854225 2.07886 2.47199 + vertex 0.853194 2.07768 2.46964 + vertex 0.853903 2.07505 2.47358 + endloop + endfacet + facet normal 0.765682 -0.387363 -0.513499 + outer loop + vertex 0.855 2.08825 2.46 + vertex 0.854048 2.08633 2.46003 + vertex 0.855 2.09 2.45868 + endloop + endfacet + facet normal 0.822386 -0.413555 -0.39071 + outer loop + vertex 0.855 2.085 2.46344 + vertex 0.854048 2.08633 2.46003 + vertex 0.855 2.08825 2.46 + endloop + endfacet + facet normal 0.88583 -0.291637 -0.360906 + outer loop + vertex 0.855 2.085 2.46344 + vertex 0.853529 2.08157 2.4626 + vertex 0.854048 2.08633 2.46003 + endloop + endfacet + facet normal -0.993166 0.0516698 -0.104654 + outer loop + vertex 0.853529 2.08157 2.4626 + vertex 0.853821 2.08607 2.46206 + vertex 0.854048 2.08633 2.46003 + endloop + endfacet + facet normal -0.964317 0.208957 0.16257 + outer loop + vertex 0.854027 2.08591 2.4646 + vertex 0.85329 2.08167 2.46567 + vertex 0.854011 2.08377 2.46725 + endloop + endfacet + facet normal -0.976882 0.193214 0.0914927 + outer loop + vertex 0.854027 2.08591 2.4646 + vertex 0.853821 2.08607 2.46206 + vertex 0.85329 2.08167 2.46567 + endloop + endfacet + facet normal -0.995329 0.0548534 -0.0794491 + outer loop + vertex 0.853821 2.08607 2.46206 + vertex 0.853529 2.08157 2.4626 + vertex 0.85329 2.08167 2.46567 + endloop + endfacet + facet normal -0.964317 0.213633 0.156374 + outer loop + vertex 0.854011 2.08377 2.46725 + vertex 0.85329 2.08167 2.46567 + vertex 0.853708 2.08097 2.46921 + endloop + endfacet + facet normal -0.941045 0.129005 -0.312716 + outer loop + vertex 0.855 2.09 2.45868 + vertex 0.854048 2.08633 2.46003 + vertex 0.855 2.0932 2.46 + endloop + endfacet + facet normal -0.981308 0.181065 0.065187 + outer loop + vertex 0.855 2.0932 2.46 + vertex 0.853821 2.08607 2.46206 + vertex 0.855 2.0914 2.465 + endloop + endfacet + facet normal -0.986309 0.136229 -0.0929331 + outer loop + vertex 0.854048 2.08633 2.46003 + vertex 0.853821 2.08607 2.46206 + vertex 0.855 2.0932 2.46 + endloop + endfacet + facet normal -0.981758 0.167339 0.0902718 + outer loop + vertex 0.855 2.0914 2.465 + vertex 0.853821 2.08607 2.46206 + vertex 0.854027 2.08591 2.4646 + endloop + endfacet + facet normal 0.0191058 -0.264013 -0.96433 + outer loop + vertex 0.86 0.922991 2.46 + vertex 0.858923 0.92581 2.45921 + vertex 0.86 0.925 2.45945 + endloop + endfacet + facet normal 0.339057 -0.132529 -0.931384 + outer loop + vertex 0.86 0.922991 2.46 + vertex 0.859465 0.923215 2.45977 + vertex 0.858923 0.92581 2.45921 + endloop + endfacet + facet normal 0.00221398 -0.146415 -0.989221 + outer loop + vertex 0.86 0.925 2.45945 + vertex 0.858763 0.928946 2.45886 + vertex 0.86 0.93 2.45871 + endloop + endfacet + facet normal 0.146717 -0.100342 -0.984076 + outer loop + vertex 0.858923 0.92581 2.45921 + vertex 0.858763 0.928946 2.45886 + vertex 0.86 0.925 2.45945 + endloop + endfacet + facet normal -0.977518 -0.209396 -0.0247513 + outer loop + vertex 0.858888 0.925779 2.46087 + vertex 0.858923 0.92581 2.45921 + vertex 0.859465 0.923215 2.45977 + endloop + endfacet + facet normal -0.988346 -0.15034 -0.0238581 + outer loop + vertex 0.858888 0.925779 2.46087 + vertex 0.858188 0.930265 2.46158 + vertex 0.858923 0.92581 2.45921 + endloop + endfacet + facet normal -0.982257 -0.0692745 -0.174274 + outer loop + vertex 0.858188 0.930265 2.46158 + vertex 0.858763 0.928946 2.45886 + vertex 0.858923 0.92581 2.45921 + endloop + endfacet + facet normal -0.975525 -0.173508 0.135077 + outer loop + vertex 0.858888 0.925779 2.46087 + vertex 0.858944 0.927371 2.46332 + vertex 0.858188 0.930265 2.46158 + endloop + endfacet + facet normal -0.418831 0.102864 -0.902219 + outer loop + vertex 0.86 0.93 2.45871 + vertex 0.858449 0.935 2.46 + vertex 0.86 0.935 2.45928 + endloop + endfacet + facet normal -0.258805 0.165268 -0.951686 + outer loop + vertex 0.858763 0.928946 2.45886 + vertex 0.858449 0.935 2.46 + vertex 0.86 0.93 2.45871 + endloop + endfacet + facet normal -0.979499 -0.0130444 -0.201028 + outer loop + vertex 0.858763 0.928946 2.45886 + vertex 0.858188 0.930265 2.46158 + vertex 0.858449 0.935 2.46 + endloop + endfacet + facet normal -0.990961 0.0100035 -0.133776 + outer loop + vertex 0.858449 0.935 2.46 + vertex 0.858188 0.930265 2.46158 + vertex 0.857774 0.935 2.465 + endloop + endfacet + facet normal -0.975483 -0.201427 0.0886558 + outer loop + vertex 0.858474 0.930405 2.46504 + vertex 0.858188 0.930265 2.46158 + vertex 0.858944 0.927371 2.46332 + endloop + endfacet + facet normal -0.966488 -0.24061 0.0894871 + outer loop + vertex 0.858474 0.930405 2.46504 + vertex 0.857385 0.93511 2.46593 + vertex 0.858188 0.930265 2.46158 + endloop + endfacet + facet normal -0.892273 0.210592 -0.399374 + outer loop + vertex 0.857385 0.93511 2.46593 + vertex 0.857774 0.935 2.465 + vertex 0.858188 0.930265 2.46158 + endloop + endfacet + facet normal -0.942114 -0.258313 0.213763 + outer loop + vertex 0.858474 0.930405 2.46504 + vertex 0.858719 0.932144 2.46822 + vertex 0.857385 0.93511 2.46593 + endloop + endfacet + facet normal -0.898366 -0.272564 -0.344453 + outer loop + vertex 0.857774 0.935 2.465 + vertex 0.857385 0.93511 2.46593 + vertex 0.856257 0.94 2.465 + endloop + endfacet + facet normal -0.95076 -0.253199 -0.178734 + outer loop + vertex 0.856257 0.94 2.465 + vertex 0.857385 0.93511 2.46593 + vertex 0.856031 0.940037 2.46615 + endloop + endfacet + facet normal -0.94217 -0.263944 0.206519 + outer loop + vertex 0.858315 0.935174 2.47025 + vertex 0.857385 0.93511 2.46593 + vertex 0.858719 0.932144 2.46822 + endloop + endfacet + facet normal -0.945341 -0.251936 0.207024 + outer loop + vertex 0.858315 0.935174 2.47025 + vertex 0.85719 0.939691 2.47061 + vertex 0.857385 0.93511 2.46593 + endloop + endfacet + facet normal -0.937453 -0.26759 0.222662 + outer loop + vertex 0.85719 0.939691 2.47061 + vertex 0.856031 0.940037 2.46615 + vertex 0.857385 0.93511 2.46593 + endloop + endfacet + facet normal -0.915986 -0.25293 0.311441 + outer loop + vertex 0.858315 0.935174 2.47025 + vertex 0.858868 0.937163 2.47349 + vertex 0.85719 0.939691 2.47061 + endloop + endfacet + facet normal -0.955821 -0.232079 -0.180402 + outer loop + vertex 0.856257 0.94 2.465 + vertex 0.856031 0.940037 2.46615 + vertex 0.855043 0.945 2.465 + endloop + endfacet + facet normal -0.979003 -0.168271 0.115059 + outer loop + vertex 0.855043 0.945 2.465 + vertex 0.856031 0.940037 2.46615 + vertex 0.855667 0.943307 2.46784 + endloop + endfacet + facet normal -0.947515 -0.223412 0.228695 + outer loop + vertex 0.856031 0.940037 2.46615 + vertex 0.85719 0.939691 2.47061 + vertex 0.855667 0.943307 2.46784 + endloop + endfacet + facet normal -0.947186 -0.219019 0.234241 + outer loop + vertex 0.855667 0.943307 2.46784 + vertex 0.85719 0.939691 2.47061 + vertex 0.856091 0.944831 2.47097 + endloop + endfacet + facet normal -0.913088 -0.202726 0.353796 + outer loop + vertex 0.8588 0.940545 2.47526 + vertex 0.85719 0.939691 2.47061 + vertex 0.858868 0.937163 2.47349 + endloop + endfacet + facet normal -0.910259 -0.213439 0.354784 + outer loop + vertex 0.8588 0.940545 2.47526 + vertex 0.857764 0.944813 2.47517 + vertex 0.85719 0.939691 2.47061 + endloop + endfacet + facet normal -0.906507 -0.219221 0.360815 + outer loop + vertex 0.857764 0.944813 2.47517 + vertex 0.856091 0.944831 2.47097 + vertex 0.85719 0.939691 2.47061 + endloop + endfacet + facet normal -0.768078 -0.173334 0.616451 + outer loop + vertex 0.8588 0.940545 2.47526 + vertex 0.86023 0.943804 2.47795 + vertex 0.857764 0.944813 2.47517 + endloop + endfacet + facet normal -0.924063 -0.243601 0.29456 + outer loop + vertex 0.855 0.95 2.469 + vertex 0.855 0.945163 2.465 + vertex 0.855043 0.945 2.465 + endloop + endfacet + facet normal -0.937342 -0.222533 0.268083 + outer loop + vertex 0.855 0.95 2.469 + vertex 0.855043 0.945 2.465 + vertex 0.855286 0.95 2.47 + endloop + endfacet + facet normal -0.982533 -0.105526 0.153275 + outer loop + vertex 0.855286 0.95 2.47 + vertex 0.855043 0.945 2.465 + vertex 0.855667 0.943307 2.46784 + endloop + endfacet + facet normal -0.975218 -0.116384 0.188164 + outer loop + vertex 0.855667 0.943307 2.46784 + vertex 0.856091 0.944831 2.47097 + vertex 0.855286 0.95 2.47 + endloop + endfacet + facet normal -0.98837 -0.145569 0.0439803 + outer loop + vertex 0.855286 0.95 2.47 + vertex 0.856091 0.944831 2.47097 + vertex 0.855578 0.948922 2.47301 + endloop + endfacet + facet normal -0.890041 -0.287291 0.353964 + outer loop + vertex 0.856091 0.944831 2.47097 + vertex 0.857764 0.944813 2.47517 + vertex 0.855578 0.948922 2.47301 + endloop + endfacet + facet normal -0.884515 -0.270701 0.37994 + outer loop + vertex 0.855578 0.948922 2.47301 + vertex 0.857764 0.944813 2.47517 + vertex 0.857319 0.949807 2.47769 + endloop + endfacet + facet normal -0.476104 -0.430014 0.767081 + outer loop + vertex 0.857764 0.944813 2.47517 + vertex 0.859924 0.949069 2.47889 + vertex 0.857319 0.949807 2.47769 + endloop + endfacet + facet normal -0.767258 -0.155337 0.622242 + outer loop + vertex 0.86023 0.943804 2.47795 + vertex 0.859924 0.949069 2.47889 + vertex 0.857764 0.944813 2.47517 + endloop + endfacet + facet normal -0.822865 -0.555615 -0.119105 + outer loop + vertex 0.855286 0.95 2.47 + vertex 0.855578 0.948922 2.47301 + vertex 0.854288 0.951493 2.46993 + endloop + endfacet + facet normal 0.243524 0.116458 -0.962878 + outer loop + vertex 0.855 0.950598 2.47 + vertex 0.855286 0.95 2.47 + vertex 0.854288 0.951493 2.46993 + endloop + endfacet + facet normal -0.934102 -0.34055 0.107144 + outer loop + vertex 0.854245 0.952464 2.47264 + vertex 0.854288 0.951493 2.46993 + vertex 0.855578 0.948922 2.47301 + endloop + endfacet + facet normal -0.905105 -0.310828 0.290124 + outer loop + vertex 0.854245 0.952464 2.47264 + vertex 0.855578 0.948922 2.47301 + vertex 0.855322 0.95279 2.47635 + endloop + endfacet + facet normal -0.837535 -0.388065 0.384631 + outer loop + vertex 0.855322 0.95279 2.47635 + vertex 0.855578 0.948922 2.47301 + vertex 0.857319 0.949807 2.47769 + endloop + endfacet + facet normal -0.474578 -0.531984 0.701262 + outer loop + vertex 0.858782 0.951904 2.48027 + vertex 0.857319 0.949807 2.47769 + vertex 0.859924 0.949069 2.47889 + endloop + endfacet + facet normal -0.601786 -0.417887 0.680606 + outer loop + vertex 0.858782 0.951904 2.48027 + vertex 0.857222 0.95461 2.48055 + vertex 0.857319 0.949807 2.47769 + endloop + endfacet + facet normal -0.806194 -0.314935 0.500866 + outer loop + vertex 0.857222 0.95461 2.48055 + vertex 0.855322 0.95279 2.47635 + vertex 0.857319 0.949807 2.47769 + endloop + endfacet + facet normal -0.35124 -0.295073 0.888573 + outer loop + vertex 0.858782 0.951904 2.48027 + vertex 0.859273 0.955027 2.4815 + vertex 0.857222 0.95461 2.48055 + endloop + endfacet + facet normal -0.911535 -0.291283 0.290272 + outer loop + vertex 0.8536 0.956118 2.47428 + vertex 0.854245 0.952464 2.47264 + vertex 0.855322 0.95279 2.47635 + endloop + endfacet + facet normal -0.904362 -0.25556 0.341787 + outer loop + vertex 0.854858 0.957981 2.479 + vertex 0.8536 0.956118 2.47428 + vertex 0.855322 0.95279 2.47635 + endloop + endfacet + facet normal -0.798896 -0.328865 0.503601 + outer loop + vertex 0.855322 0.95279 2.47635 + vertex 0.857222 0.95461 2.48055 + vertex 0.854858 0.957981 2.479 + endloop + endfacet + facet normal -0.788596 -0.308692 0.531814 + outer loop + vertex 0.854858 0.957981 2.479 + vertex 0.857222 0.95461 2.48055 + vertex 0.856908 0.959673 2.48303 + endloop + endfacet + facet normal -0.201894 -0.439977 0.875019 + outer loop + vertex 0.857222 0.95461 2.48055 + vertex 0.858803 0.958587 2.48292 + vertex 0.856908 0.959673 2.48303 + endloop + endfacet + facet normal -0.321632 -0.386124 0.864558 + outer loop + vertex 0.859273 0.955027 2.4815 + vertex 0.858803 0.958587 2.48292 + vertex 0.857222 0.95461 2.48055 + endloop + endfacet + facet normal -0.894638 -0.27944 0.348621 + outer loop + vertex 0.8536 0.956118 2.47428 + vertex 0.854858 0.957981 2.479 + vertex 0.853004 0.960029 2.47589 + endloop + endfacet + facet normal -0.895123 -0.266348 0.357509 + outer loop + vertex 0.853578 0.962079 2.47885 + vertex 0.853004 0.960029 2.47589 + vertex 0.854858 0.957981 2.479 + endloop + endfacet + facet normal -0.836031 -0.242868 0.492003 + outer loop + vertex 0.853578 0.962079 2.47885 + vertex 0.854858 0.957981 2.479 + vertex 0.85541 0.963282 2.48256 + endloop + endfacet + facet normal -0.808248 -0.267579 0.524535 + outer loop + vertex 0.85541 0.963282 2.48256 + vertex 0.854858 0.957981 2.479 + vertex 0.856908 0.959673 2.48303 + endloop + endfacet + facet normal -0.23797 -0.498782 0.833419 + outer loop + vertex 0.858337 0.96183 2.48472 + vertex 0.856908 0.959673 2.48303 + vertex 0.858803 0.958587 2.48292 + endloop + endfacet + facet normal -0.397123 -0.390923 0.830345 + outer loop + vertex 0.858337 0.96183 2.48472 + vertex 0.857348 0.963596 2.48508 + vertex 0.856908 0.959673 2.48303 + endloop + endfacet + facet normal -0.75663 -0.235102 0.610113 + outer loop + vertex 0.857348 0.963596 2.48508 + vertex 0.85541 0.963282 2.48256 + vertex 0.856908 0.959673 2.48303 + endloop + endfacet + facet normal -0.0667905 -0.234227 0.969885 + outer loop + vertex 0.858337 0.96183 2.48472 + vertex 0.858668 0.964603 2.48542 + vertex 0.857348 0.963596 2.48508 + endloop + endfacet + facet normal -0.8423 -0.225631 0.489511 + outer loop + vertex 0.853578 0.962079 2.47885 + vertex 0.85541 0.963282 2.48256 + vertex 0.853598 0.965664 2.48054 + endloop + endfacet + facet normal -0.80868 -0.128336 0.574078 + outer loop + vertex 0.855423 0.969214 2.4839 + vertex 0.853598 0.965664 2.48054 + vertex 0.85541 0.963282 2.48256 + endloop + endfacet + facet normal -0.755521 -0.143219 0.639278 + outer loop + vertex 0.855423 0.969214 2.4839 + vertex 0.85541 0.963282 2.48256 + vertex 0.856844 0.966368 2.48495 + endloop + endfacet + facet normal -0.781528 -0.111461 0.613832 + outer loop + vertex 0.856844 0.966368 2.48495 + vertex 0.85541 0.963282 2.48256 + vertex 0.857348 0.963596 2.48508 + endloop + endfacet + facet normal -0.464062 -0.0404057 0.884881 + outer loop + vertex 0.857348 0.963596 2.48508 + vertex 0.858085 0.966418 2.4856 + vertex 0.856844 0.966368 2.48495 + endloop + endfacet + facet normal -0.139221 -0.142631 0.979936 + outer loop + vertex 0.858668 0.964603 2.48542 + vertex 0.858085 0.966418 2.4856 + vertex 0.857348 0.963596 2.48508 + endloop + endfacet + facet normal -0.793625 -0.536754 0.286451 + outer loop + vertex 0.86 0.974447 2.475 + vertex 0.859626 0.975 2.475 + vertex 0.860146 0.973909 2.4744 + endloop + endfacet + facet normal -0.248102 -0.343029 0.905967 + outer loop + vertex 0.855618 0.973568 2.4856 + vertex 0.854046 0.972173 2.48465 + vertex 0.855423 0.969214 2.4839 + endloop + endfacet + facet normal 0.529714 -0.32926 0.781659 + outer loop + vertex 0.855618 0.973568 2.4856 + vertex 0.855423 0.969214 2.4839 + vertex 0.857627 0.974429 2.48461 + endloop + endfacet + facet normal -0.346491 0.165132 0.923404 + outer loop + vertex 0.856844 0.966368 2.48495 + vertex 0.857916 0.96955 2.48478 + vertex 0.855423 0.969214 2.4839 + endloop + endfacet + facet normal -0.332943 0.0137049 0.942847 + outer loop + vertex 0.857916 0.96955 2.48478 + vertex 0.857627 0.974429 2.48461 + vertex 0.855423 0.969214 2.4839 + endloop + endfacet + facet normal -0.462481 0.201055 0.863533 + outer loop + vertex 0.856844 0.966368 2.48495 + vertex 0.858085 0.966418 2.4856 + vertex 0.857916 0.96955 2.48478 + endloop + endfacet + facet normal -0.0854327 -0.49708 0.863488 + outer loop + vertex 0.854046 0.972173 2.48465 + vertex 0.855618 0.973568 2.4856 + vertex 0.85451 0.975054 2.48635 + endloop + endfacet + facet normal 0.878797 0.083662 -0.469805 + outer loop + vertex 0.859626 0.975 2.475 + vertex 0.85915 0.98 2.475 + vertex 0.86 0.98 2.47659 + endloop + endfacet + facet normal -0.373666 0.306366 -0.875508 + outer loop + vertex 0.860146 0.973909 2.4744 + vertex 0.859626 0.975 2.475 + vertex 0.86 0.98 2.47659 + endloop + endfacet + facet normal 0.774945 -0.0381515 0.630876 + outer loop + vertex 0.857627 0.974429 2.48461 + vertex 0.858263 0.97992 2.48416 + vertex 0.856238 0.97819 2.48654 + endloop + endfacet + facet normal 0.511785 -0.235776 0.826127 + outer loop + vertex 0.855618 0.973568 2.4856 + vertex 0.857627 0.974429 2.48461 + vertex 0.856238 0.97819 2.48654 + endloop + endfacet + facet normal 0.313943 -0.228552 0.921523 + outer loop + vertex 0.856238 0.97819 2.48654 + vertex 0.85451 0.975054 2.48635 + vertex 0.855618 0.973568 2.4856 + endloop + endfacet + facet normal 0.457331 -0.302358 0.836318 + outer loop + vertex 0.854089 0.978461 2.48781 + vertex 0.85451 0.975054 2.48635 + vertex 0.856238 0.97819 2.48654 + endloop + endfacet + facet normal -0.217881 -0.0944191 0.971397 + outer loop + vertex 0.86 0.98368 2.48 + vertex 0.859428 0.985 2.48 + vertex 0.859287 0.982532 2.47973 + endloop + endfacet + facet normal 0.900258 0.0906322 0.425819 + outer loop + vertex 0.858263 0.97992 2.48416 + vertex 0.858534 0.983584 2.4828 + vertex 0.857322 0.983607 2.48536 + endloop + endfacet + facet normal 0.766881 -0.0138752 0.641639 + outer loop + vertex 0.856238 0.97819 2.48654 + vertex 0.858263 0.97992 2.48416 + vertex 0.857322 0.983607 2.48536 + endloop + endfacet + facet normal 0.626351 -0.280769 0.727222 + outer loop + vertex 0.854089 0.978461 2.48781 + vertex 0.85537 0.983338 2.48859 + vertex 0.853604 0.981978 2.48959 + endloop + endfacet + facet normal 0.468126 -0.258074 0.845137 + outer loop + vertex 0.854089 0.978461 2.48781 + vertex 0.856238 0.97819 2.48654 + vertex 0.85537 0.983338 2.48859 + endloop + endfacet + facet normal 0.856586 -0.0599372 0.512511 + outer loop + vertex 0.856238 0.97819 2.48654 + vertex 0.857322 0.983607 2.48536 + vertex 0.85537 0.983338 2.48859 + endloop + endfacet + facet normal 0.626576 -0.281373 0.726796 + outer loop + vertex 0.85537 0.983338 2.48859 + vertex 0.85403 0.985354 2.49053 + vertex 0.853604 0.981978 2.48959 + endloop + endfacet + facet normal 0.881348 -0.101126 0.461517 + outer loop + vertex 0.858898 0.984216 2.48084 + vertex 0.859287 0.982532 2.47973 + vertex 0.859428 0.985 2.48 + endloop + endfacet + facet normal 0.826909 0.0419929 0.560765 + outer loop + vertex 0.858898 0.984216 2.48084 + vertex 0.859428 0.985 2.48 + vertex 0.858005 0.987802 2.48189 + endloop + endfacet + facet normal 0.854118 0.0883177 0.512526 + outer loop + vertex 0.858005 0.987802 2.48189 + vertex 0.859428 0.985 2.48 + vertex 0.858911 0.99 2.48 + endloop + endfacet + facet normal 0.957563 0.170511 0.232376 + outer loop + vertex 0.858534 0.983584 2.4828 + vertex 0.858898 0.984216 2.48084 + vertex 0.858005 0.987802 2.48189 + endloop + endfacet + facet normal 0.885787 0.20176 0.41794 + outer loop + vertex 0.858534 0.983584 2.4828 + vertex 0.858005 0.987802 2.48189 + vertex 0.857322 0.983607 2.48536 + endloop + endfacet + facet normal 0.944058 0.105068 0.312593 + outer loop + vertex 0.857322 0.983607 2.48536 + vertex 0.858005 0.987802 2.48189 + vertex 0.85651 0.988242 2.48626 + endloop + endfacet + facet normal 0.853063 0.0491628 0.519487 + outer loop + vertex 0.857322 0.983607 2.48536 + vertex 0.85651 0.988242 2.48626 + vertex 0.85537 0.983338 2.48859 + endloop + endfacet + facet normal 0.914679 -0.0203467 0.403669 + outer loop + vertex 0.85651 0.988242 2.48626 + vertex 0.855072 0.988709 2.48954 + vertex 0.85537 0.983338 2.48859 + endloop + endfacet + facet normal 0.788074 -0.0641206 0.612231 + outer loop + vertex 0.855072 0.988709 2.48954 + vertex 0.85403 0.985354 2.49053 + vertex 0.85537 0.983338 2.48859 + endloop + endfacet + facet normal 0.698513 -0.00584143 0.715574 + outer loop + vertex 0.853431 0.989119 2.49114 + vertex 0.85403 0.985354 2.49053 + vertex 0.855072 0.988709 2.48954 + endloop + endfacet + facet normal 0.787215 0.18184 0.58926 + outer loop + vertex 0.858911 0.99 2.48 + vertex 0.857756 0.995 2.48 + vertex 0.858005 0.987802 2.48189 + endloop + endfacet + facet normal 0.922395 0.127563 0.364575 + outer loop + vertex 0.857756 0.995 2.48 + vertex 0.856807 0.992322 2.48334 + vertex 0.858005 0.987802 2.48189 + endloop + endfacet + facet normal 0.939833 0.150806 0.306547 + outer loop + vertex 0.858005 0.987802 2.48189 + vertex 0.856807 0.992322 2.48334 + vertex 0.85651 0.988242 2.48626 + endloop + endfacet + facet normal 0.956951 0.119504 0.264505 + outer loop + vertex 0.856807 0.992322 2.48334 + vertex 0.855737 0.992998 2.4869 + vertex 0.85651 0.988242 2.48626 + endloop + endfacet + facet normal 0.916648 0.0961347 0.387961 + outer loop + vertex 0.85651 0.988242 2.48626 + vertex 0.855737 0.992998 2.4869 + vertex 0.855072 0.988709 2.48954 + endloop + endfacet + facet normal 0.921374 0.0894363 0.378248 + outer loop + vertex 0.855737 0.992998 2.4869 + vertex 0.854439 0.993329 2.48999 + vertex 0.855072 0.988709 2.48954 + endloop + endfacet + facet normal 0.702477 0.0271287 0.711189 + outer loop + vertex 0.854439 0.993329 2.48999 + vertex 0.853431 0.989119 2.49114 + vertex 0.855072 0.988709 2.48954 + endloop + endfacet + facet normal 0.612653 0.0695316 0.787288 + outer loop + vertex 0.852385 0.993919 2.49153 + vertex 0.853431 0.989119 2.49114 + vertex 0.854439 0.993329 2.48999 + endloop + endfacet + facet normal 0.736617 0.569941 0.364092 + outer loop + vertex 0.855 0.998562 2.48 + vertex 0.857756 0.995 2.48 + vertex 0.86 0.995 2.47546 + endloop + endfacet + facet normal 0.730919 0.590991 0.341302 + outer loop + vertex 0.855 0.998562 2.48 + vertex 0.86 0.995 2.47546 + vertex 0.855 1 2.47751 + endloop + endfacet + facet normal 0.712661 0.519293 0.471646 + outer loop + vertex 0.855 1 2.47751 + vertex 0.86 0.995 2.47546 + vertex 0.858313 0.999812 2.47271 + endloop + endfacet + facet normal -0.657141 -0.508449 0.556458 + outer loop + vertex 0.855306 0.997742 2.47961 + vertex 0.857756 0.995 2.48 + vertex 0.855 0.998562 2.48 + endloop + endfacet + facet normal 0.74587 0.66608 -0.00384997 + outer loop + vertex 0.855306 0.997742 2.47961 + vertex 0.855593 0.99744 2.48312 + vertex 0.857756 0.995 2.48 + endloop + endfacet + facet normal 0.874228 0.225908 0.429756 + outer loop + vertex 0.855593 0.99744 2.48312 + vertex 0.856807 0.992322 2.48334 + vertex 0.857756 0.995 2.48 + endloop + endfacet + facet normal 0.942565 0.233857 0.238501 + outer loop + vertex 0.856807 0.992322 2.48334 + vertex 0.855593 0.99744 2.48312 + vertex 0.855737 0.992998 2.4869 + endloop + endfacet + facet normal 0.977643 0.153864 0.143317 + outer loop + vertex 0.855593 0.99744 2.48312 + vertex 0.855009 0.996965 2.48761 + vertex 0.855737 0.992998 2.4869 + endloop + endfacet + facet normal 0.920733 0.101971 0.376634 + outer loop + vertex 0.855737 0.992998 2.4869 + vertex 0.855009 0.996965 2.48761 + vertex 0.854439 0.993329 2.48999 + endloop + endfacet + facet normal 0.916747 0.107833 0.384639 + outer loop + vertex 0.855009 0.996965 2.48761 + vertex 0.853842 0.997967 2.49011 + vertex 0.854439 0.993329 2.48999 + endloop + endfacet + facet normal 0.610979 0.0578338 0.789531 + outer loop + vertex 0.853842 0.997967 2.49011 + vertex 0.852385 0.993919 2.49153 + vertex 0.854439 0.993329 2.48999 + endloop + endfacet + facet normal 0.721863 -0.0164393 0.691841 + outer loop + vertex 0.852102 0.999318 2.49196 + vertex 0.852385 0.993919 2.49153 + vertex 0.853842 0.997967 2.49011 + endloop + endfacet + facet normal 0.815196 0.160731 0.556436 + outer loop + vertex 0.858313 0.999812 2.47271 + vertex 0.857359 1.00364 2.473 + vertex 0.855 1 2.47751 + endloop + endfacet + facet normal 0.909206 -0.0840009 0.407784 + outer loop + vertex 0.855 1 2.47751 + vertex 0.857359 1.00364 2.473 + vertex 0.855 1.005 2.47854 + endloop + endfacet + facet normal 0.965995 0.252098 -0.0574402 + outer loop + vertex 0.855306 0.997742 2.47961 + vertex 0.854745 1.00025 2.48119 + vertex 0.855593 0.99744 2.48312 + endloop + endfacet + facet normal 0.970389 0.195748 -0.141521 + outer loop + vertex 0.854652 1.00237 2.48349 + vertex 0.855593 0.99744 2.48312 + vertex 0.854745 1.00025 2.48119 + endloop + endfacet + facet normal 0.981257 0.182638 0.0614716 + outer loop + vertex 0.854652 1.00237 2.48349 + vertex 0.854446 1.0023 2.48698 + vertex 0.855593 0.99744 2.48312 + endloop + endfacet + facet normal 0.982765 0.120227 0.140421 + outer loop + vertex 0.854446 1.0023 2.48698 + vertex 0.855009 0.996965 2.48761 + vertex 0.855593 0.99744 2.48312 + endloop + endfacet + facet normal 0.962362 0.00980697 0.271592 + outer loop + vertex 0.853461 1.00185 2.49049 + vertex 0.854446 1.0023 2.48698 + vertex 0.853619 1.00586 2.48978 + endloop + endfacet + facet normal 0.958315 0.0669299 0.277764 + outer loop + vertex 0.853461 1.00185 2.49049 + vertex 0.853842 0.997967 2.49011 + vertex 0.854446 1.0023 2.48698 + endloop + endfacet + facet normal 0.917566 0.140573 0.371903 + outer loop + vertex 0.853842 0.997967 2.49011 + vertex 0.855009 0.996965 2.48761 + vertex 0.854446 1.0023 2.48698 + endloop + endfacet + facet normal 0.72984 0.0051087 0.683599 + outer loop + vertex 0.853842 0.997967 2.49011 + vertex 0.853461 1.00185 2.49049 + vertex 0.852102 0.999318 2.49196 + endloop + endfacet + facet normal 0.921 0.0116507 0.389389 + outer loop + vertex 0.857359 1.00364 2.473 + vertex 0.857145 1.00847 2.47336 + vertex 0.855 1.005 2.47854 + endloop + endfacet + facet normal 0.939864 -0.0890403 0.329739 + outer loop + vertex 0.855 1.005 2.47854 + vertex 0.857145 1.00847 2.47336 + vertex 0.855 1.01 2.47989 + endloop + endfacet + facet normal 0.994038 0.090759 0.0604301 + outer loop + vertex 0.854184 1.00667 2.48474 + vertex 0.854446 1.0023 2.48698 + vertex 0.854652 1.00237 2.48349 + endloop + endfacet + facet normal 0.997027 0.0728314 0.0251599 + outer loop + vertex 0.854009 1.00826 2.48706 + vertex 0.854446 1.0023 2.48698 + vertex 0.854184 1.00667 2.48474 + endloop + endfacet + facet normal 0.977213 0.0691157 0.200694 + outer loop + vertex 0.854009 1.00826 2.48706 + vertex 0.853619 1.00586 2.48978 + vertex 0.854446 1.0023 2.48698 + endloop + endfacet + facet normal 0.980213 0.0562541 0.189785 + outer loop + vertex 0.853464 1.01024 2.48929 + vertex 0.853619 1.00586 2.48978 + vertex 0.854009 1.00826 2.48706 + endloop + endfacet + facet normal 0.997716 -0.0163688 0.0655283 + outer loop + vertex 0.855238 1.01335 2.4771 + vertex 0.855 1.01044 2.48 + vertex 0.855 1.01 2.47989 + endloop + endfacet + facet normal 0.786951 0.361114 0.500304 + outer loop + vertex 0.855238 1.01335 2.4771 + vertex 0.855 1.01 2.47989 + vertex 0.857027 1.01428 2.47361 + endloop + endfacet + facet normal 0.950408 0.00580504 0.310951 + outer loop + vertex 0.857027 1.01428 2.47361 + vertex 0.855 1.01 2.47989 + vertex 0.857145 1.00847 2.47336 + endloop + endfacet + facet normal 0.99762 -0.0144853 0.0674079 + outer loop + vertex 0.855238 1.01335 2.4771 + vertex 0.855 1.015 2.48098 + vertex 0.855 1.01044 2.48 + endloop + endfacet + facet normal 0.996399 0.0827879 0.018289 + outer loop + vertex 0.853799 1.01118 2.48526 + vertex 0.854009 1.00826 2.48706 + vertex 0.854184 1.00667 2.48474 + endloop + endfacet + facet normal 0.996597 0.0809888 0.0153482 + outer loop + vertex 0.853721 1.01179 2.48709 + vertex 0.854009 1.00826 2.48706 + vertex 0.853799 1.01118 2.48526 + endloop + endfacet + facet normal 0.98221 0.0783606 0.170656 + outer loop + vertex 0.853721 1.01179 2.48709 + vertex 0.853464 1.01024 2.48929 + vertex 0.854009 1.00826 2.48706 + endloop + endfacet + facet normal 0.964216 0.149527 0.21893 + outer loop + vertex 0.853224 1.0134 2.48818 + vertex 0.853464 1.01024 2.48929 + vertex 0.853721 1.01179 2.48709 + endloop + endfacet + facet normal 0.893904 -0.0312933 0.447165 + outer loop + vertex 0.857027 1.01428 2.47361 + vertex 0.85757 1.02035 2.47295 + vertex 0.855715 1.01749 2.47646 + endloop + endfacet + facet normal 0.892828 -0.0334954 0.449151 + outer loop + vertex 0.855238 1.01335 2.4771 + vertex 0.857027 1.01428 2.47361 + vertex 0.855715 1.01749 2.47646 + endloop + endfacet + facet normal 0.98987 -0.0981229 0.102613 + outer loop + vertex 0.855715 1.01749 2.47646 + vertex 0.855 1.015 2.48098 + vertex 0.855238 1.01335 2.4771 + endloop + endfacet + facet normal 0.989237 -0.0214233 0.144742 + outer loop + vertex 0.855 1.02 2.48172 + vertex 0.855 1.015 2.48098 + vertex 0.855715 1.01749 2.47646 + endloop + endfacet + facet normal 0.990577 0.136914 -0.00353085 + outer loop + vertex 0.853799 1.01118 2.48526 + vertex 0.853425 1.01391 2.48618 + vertex 0.853721 1.01179 2.48709 + endloop + endfacet + facet normal 0.968783 0.199169 0.147619 + outer loop + vertex 0.853721 1.01179 2.48709 + vertex 0.853425 1.01391 2.48618 + vertex 0.853224 1.0134 2.48818 + endloop + endfacet + facet normal 0.867524 0.00586101 0.49736 + outer loop + vertex 0.85757 1.02035 2.47295 + vertex 0.857638 1.02539 2.47278 + vertex 0.855743 1.02237 2.47612 + endloop + endfacet + facet normal 0.873557 0.0293276 0.485838 + outer loop + vertex 0.855715 1.01749 2.47646 + vertex 0.85757 1.02035 2.47295 + vertex 0.855743 1.02237 2.47612 + endloop + endfacet + facet normal 0.991114 0.00376699 0.13296 + outer loop + vertex 0.855743 1.02237 2.47612 + vertex 0.855 1.02 2.48172 + vertex 0.855715 1.01749 2.47646 + endloop + endfacet + facet normal 0.828405 0.467958 0.307832 + outer loop + vertex 0.853567 1.02444 2.47883 + vertex 0.855 1.02 2.48172 + vertex 0.855743 1.02237 2.47612 + endloop + endfacet + facet normal 0.818234 0.0564832 0.572104 + outer loop + vertex 0.857638 1.02539 2.47278 + vertex 0.857567 1.03003 2.47242 + vertex 0.855523 1.02719 2.47562 + endloop + endfacet + facet normal 0.826875 0.0945381 0.554383 + outer loop + vertex 0.855743 1.02237 2.47612 + vertex 0.857638 1.02539 2.47278 + vertex 0.855523 1.02719 2.47562 + endloop + endfacet + facet normal 0.810547 0.0961857 0.577721 + outer loop + vertex 0.855523 1.02719 2.47562 + vertex 0.853567 1.02444 2.47883 + vertex 0.855743 1.02237 2.47612 + endloop + endfacet + facet normal 0.811701 0.093914 0.576473 + outer loop + vertex 0.852754 1.02867 2.47928 + vertex 0.853567 1.02444 2.47883 + vertex 0.855523 1.02719 2.47562 + endloop + endfacet + facet normal 0.832352 0.0993953 0.545263 + outer loop + vertex 0.857567 1.03003 2.47242 + vertex 0.85765 1.03378 2.47161 + vertex 0.855688 1.03274 2.47479 + endloop + endfacet + facet normal 0.815727 0.0617217 0.575134 + outer loop + vertex 0.855523 1.02719 2.47562 + vertex 0.857567 1.03003 2.47242 + vertex 0.855688 1.03274 2.47479 + endloop + endfacet + facet normal 0.807933 0.0635555 0.585837 + outer loop + vertex 0.855688 1.03274 2.47479 + vertex 0.852754 1.02867 2.47928 + vertex 0.855523 1.02719 2.47562 + endloop + endfacet + facet normal 0.833381 0.00859195 0.552632 + outer loop + vertex 0.853322 1.03429 2.47834 + vertex 0.852754 1.02867 2.47928 + vertex 0.855688 1.03274 2.47479 + endloop + endfacet + facet normal 0.897227 0.187102 0.399971 + outer loop + vertex 0.858372 1.0361 2.46938 + vertex 0.858369 1.03895 2.46806 + vertex 0.857205 1.03776 2.47122 + endloop + endfacet + facet normal 0.888942 0.141585 0.435587 + outer loop + vertex 0.85765 1.03378 2.47161 + vertex 0.858372 1.0361 2.46938 + vertex 0.857205 1.03776 2.47122 + endloop + endfacet + facet normal 0.820447 0.145305 0.55295 + outer loop + vertex 0.85765 1.03378 2.47161 + vertex 0.857205 1.03776 2.47122 + vertex 0.855688 1.03274 2.47479 + endloop + endfacet + facet normal 0.882161 0.0650956 0.466426 + outer loop + vertex 0.855688 1.03274 2.47479 + vertex 0.857205 1.03776 2.47122 + vertex 0.855285 1.0384 2.47476 + endloop + endfacet + facet normal 0.842524 0.062638 0.535004 + outer loop + vertex 0.855285 1.0384 2.47476 + vertex 0.853322 1.03429 2.47834 + vertex 0.855688 1.03274 2.47479 + endloop + endfacet + facet normal 0.866369 0.019939 0.499006 + outer loop + vertex 0.853369 1.0397 2.47804 + vertex 0.853322 1.03429 2.47834 + vertex 0.855285 1.0384 2.47476 + endloop + endfacet + facet normal 0.944696 0.168296 0.28147 + outer loop + vertex 0.85874 1.04135 2.46548 + vertex 0.858532 1.04501 2.46399 + vertex 0.857898 1.04225 2.46777 + endloop + endfacet + facet normal 0.945126 0.159787 0.284964 + outer loop + vertex 0.858369 1.03895 2.46806 + vertex 0.85874 1.04135 2.46548 + vertex 0.857898 1.04225 2.46777 + endloop + endfacet + facet normal 0.904536 0.163546 0.393787 + outer loop + vertex 0.858369 1.03895 2.46806 + vertex 0.857898 1.04225 2.46777 + vertex 0.857205 1.03776 2.47122 + endloop + endfacet + facet normal 0.936383 0.111635 0.332752 + outer loop + vertex 0.857205 1.03776 2.47122 + vertex 0.857898 1.04225 2.46777 + vertex 0.85664 1.04293 2.47108 + endloop + endfacet + facet normal 0.88205 0.109161 0.458335 + outer loop + vertex 0.857205 1.03776 2.47122 + vertex 0.85664 1.04293 2.47108 + vertex 0.855285 1.0384 2.47476 + endloop + endfacet + facet normal 0.923114 0.0354203 0.382892 + outer loop + vertex 0.85664 1.04293 2.47108 + vertex 0.855084 1.04377 2.47475 + vertex 0.855285 1.0384 2.47476 + endloop + endfacet + facet normal 0.86837 0.0336065 0.494777 + outer loop + vertex 0.855084 1.04377 2.47475 + vertex 0.853369 1.0397 2.47804 + vertex 0.855285 1.0384 2.47476 + endloop + endfacet + facet normal 0.885506 0.00207653 0.464624 + outer loop + vertex 0.853271 1.04502 2.4782 + vertex 0.853369 1.0397 2.47804 + vertex 0.855084 1.04377 2.47475 + endloop + endfacet + facet normal 0.964349 0.144664 0.221592 + outer loop + vertex 0.858532 1.04501 2.46399 + vertex 0.85841 1.0487 2.46211 + vertex 0.857625 1.04764 2.46621 + endloop + endfacet + facet normal 0.960992 0.12026 0.249061 + outer loop + vertex 0.857898 1.04225 2.46777 + vertex 0.858532 1.04501 2.46399 + vertex 0.857625 1.04764 2.46621 + endloop + endfacet + facet normal 0.934752 0.141086 0.326088 + outer loop + vertex 0.857898 1.04225 2.46777 + vertex 0.857625 1.04764 2.46621 + vertex 0.85664 1.04293 2.47108 + endloop + endfacet + facet normal 0.965613 0.0593712 0.253115 + outer loop + vertex 0.857625 1.04764 2.46621 + vertex 0.856373 1.04824 2.47085 + vertex 0.85664 1.04293 2.47108 + endloop + endfacet + facet normal 0.924084 0.0626157 0.377026 + outer loop + vertex 0.85664 1.04293 2.47108 + vertex 0.856373 1.04824 2.47085 + vertex 0.855084 1.04377 2.47475 + endloop + endfacet + facet normal 0.944399 0.0143752 0.328488 + outer loop + vertex 0.856373 1.04824 2.47085 + vertex 0.854962 1.04901 2.47487 + vertex 0.855084 1.04377 2.47475 + endloop + endfacet + facet normal 0.886634 0.0099372 0.462366 + outer loop + vertex 0.854962 1.04901 2.47487 + vertex 0.853271 1.04502 2.4782 + vertex 0.855084 1.04377 2.47475 + endloop + endfacet + facet normal 0.89177 -0.000483792 0.45249 + outer loop + vertex 0.853155 1.0502 2.47844 + vertex 0.853271 1.04502 2.4782 + vertex 0.854962 1.04901 2.47487 + endloop + endfacet + facet normal 0.400667 0.101638 0.910569 + outer loop + vertex 0.859179 1.05114 2.45562 + vertex 0.86 1.05349 2.455 + vertex 0.859617 1.055 2.455 + endloop + endfacet + facet normal 0.805303 0.00439804 0.592847 + outer loop + vertex 0.858581 1.0547 2.45641 + vertex 0.859179 1.05114 2.45562 + vertex 0.859617 1.055 2.455 + endloop + endfacet + facet normal 0.977616 0.127255 0.16755 + outer loop + vertex 0.858751 1.05032 2.45874 + vertex 0.859179 1.05114 2.45562 + vertex 0.858581 1.0547 2.45641 + endloop + endfacet + facet normal 0.976116 0.130475 0.173706 + outer loop + vertex 0.857974 1.05318 2.46096 + vertex 0.858751 1.05032 2.45874 + vertex 0.858581 1.0547 2.45641 + endloop + endfacet + facet normal 0.976668 0.13728 0.165147 + outer loop + vertex 0.85841 1.0487 2.46211 + vertex 0.858751 1.05032 2.45874 + vertex 0.857974 1.05318 2.46096 + endloop + endfacet + facet normal 0.963113 0.150728 0.222921 + outer loop + vertex 0.85841 1.0487 2.46211 + vertex 0.857974 1.05318 2.46096 + vertex 0.857625 1.04764 2.46621 + endloop + endfacet + facet normal 0.982915 0.0902284 0.160426 + outer loop + vertex 0.857625 1.04764 2.46621 + vertex 0.857974 1.05318 2.46096 + vertex 0.857127 1.05321 2.46614 + endloop + endfacet + facet normal 0.96437 0.0897988 0.248851 + outer loop + vertex 0.857625 1.04764 2.46621 + vertex 0.857127 1.05321 2.46614 + vertex 0.856373 1.04824 2.47085 + endloop + endfacet + facet normal 0.977882 0.0453626 0.204179 + outer loop + vertex 0.857127 1.05321 2.46614 + vertex 0.85613 1.05346 2.47085 + vertex 0.856373 1.04824 2.47085 + endloop + endfacet + facet normal 0.945328 0.0437778 0.32317 + outer loop + vertex 0.856373 1.04824 2.47085 + vertex 0.85613 1.05346 2.47085 + vertex 0.854962 1.04901 2.47487 + endloop + endfacet + facet normal 0.953372 0.02164 0.30102 + outer loop + vertex 0.85613 1.05346 2.47085 + vertex 0.854816 1.05407 2.47497 + vertex 0.854962 1.04901 2.47487 + endloop + endfacet + facet normal 0.893988 0.0170508 0.447767 + outer loop + vertex 0.854816 1.05407 2.47497 + vertex 0.853155 1.0502 2.47844 + vertex 0.854962 1.04901 2.47487 + endloop + endfacet + facet normal 0.897799 0.00873248 0.440319 + outer loop + vertex 0.853098 1.05519 2.47845 + vertex 0.853155 1.0502 2.47844 + vertex 0.854816 1.05407 2.47497 + endloop + endfacet + facet normal 0.79336 0.0901214 0.602045 + outer loop + vertex 0.859617 1.055 2.455 + vertex 0.859049 1.06 2.455 + vertex 0.858581 1.0547 2.45641 + endloop + endfacet + facet normal 0.809242 0.0832597 0.581545 + outer loop + vertex 0.859049 1.06 2.455 + vertex 0.857798 1.05899 2.45689 + vertex 0.858581 1.0547 2.45641 + endloop + endfacet + facet normal 0.970691 0.157087 0.181889 + outer loop + vertex 0.858581 1.0547 2.45641 + vertex 0.857798 1.05899 2.45689 + vertex 0.857974 1.05318 2.46096 + endloop + endfacet + facet normal 0.981045 0.13037 0.143365 + outer loop + vertex 0.857798 1.05899 2.45689 + vertex 0.85724 1.05846 2.46119 + vertex 0.857974 1.05318 2.46096 + endloop + endfacet + facet normal 0.978684 0.129365 0.159506 + outer loop + vertex 0.857974 1.05318 2.46096 + vertex 0.85724 1.05846 2.46119 + vertex 0.857127 1.05321 2.46614 + endloop + endfacet + facet normal 0.988581 0.0915809 0.119668 + outer loop + vertex 0.85724 1.05846 2.46119 + vertex 0.856648 1.05841 2.46612 + vertex 0.857127 1.05321 2.46614 + endloop + endfacet + facet normal 0.975337 0.090644 0.201248 + outer loop + vertex 0.857127 1.05321 2.46614 + vertex 0.856648 1.05841 2.46612 + vertex 0.85613 1.05346 2.47085 + endloop + endfacet + facet normal 0.980875 0.0709272 0.181255 + outer loop + vertex 0.856648 1.05841 2.46612 + vertex 0.855774 1.05849 2.47081 + vertex 0.85613 1.05346 2.47085 + endloop + endfacet + facet normal 0.95328 0.0699018 0.293889 + outer loop + vertex 0.85613 1.05346 2.47085 + vertex 0.855774 1.05849 2.47081 + vertex 0.854816 1.05407 2.47497 + endloop + endfacet + facet normal 0.958481 0.0554623 0.279711 + outer loop + vertex 0.855774 1.05849 2.47081 + vertex 0.854561 1.05887 2.47489 + vertex 0.854816 1.05407 2.47497 + endloop + endfacet + facet normal 0.902311 0.054883 0.427579 + outer loop + vertex 0.854561 1.05887 2.47489 + vertex 0.853098 1.05519 2.47845 + vertex 0.854816 1.05407 2.47497 + endloop + endfacet + facet normal 0.910149 0.0372782 0.4126 + outer loop + vertex 0.853077 1.05996 2.47807 + vertex 0.853098 1.05519 2.47845 + vertex 0.854561 1.05887 2.47489 + endloop + endfacet + facet normal 0.778088 0.166974 0.605556 + outer loop + vertex 0.859049 1.06 2.455 + vertex 0.857976 1.065 2.455 + vertex 0.857798 1.05899 2.45689 + endloop + endfacet + facet normal 0.834465 0.142322 0.532365 + outer loop + vertex 0.857976 1.065 2.455 + vertex 0.856911 1.06358 2.45705 + vertex 0.857798 1.05899 2.45689 + endloop + endfacet + facet normal 0.971885 0.182595 0.148656 + outer loop + vertex 0.857798 1.05899 2.45689 + vertex 0.856911 1.06358 2.45705 + vertex 0.85724 1.05846 2.46119 + endloop + endfacet + facet normal 0.985501 0.140367 0.0953099 + outer loop + vertex 0.856911 1.06358 2.45705 + vertex 0.856538 1.0633 2.46132 + vertex 0.85724 1.05846 2.46119 + endloop + endfacet + facet normal 0.983005 0.13935 0.119514 + outer loop + vertex 0.85724 1.05846 2.46119 + vertex 0.856538 1.0633 2.46132 + vertex 0.856648 1.05841 2.46612 + endloop + endfacet + facet normal 0.986959 0.123487 0.103257 + outer loop + vertex 0.856538 1.0633 2.46132 + vertex 0.856024 1.06341 2.46609 + vertex 0.856648 1.05841 2.46612 + endloop + endfacet + facet normal 0.976112 0.12256 0.179401 + outer loop + vertex 0.856648 1.05841 2.46612 + vertex 0.856024 1.06341 2.46609 + vertex 0.855774 1.05849 2.47081 + endloop + endfacet + facet normal 0.977407 0.118374 0.17511 + outer loop + vertex 0.856024 1.06341 2.46609 + vertex 0.855201 1.0633 2.47076 + vertex 0.855774 1.05849 2.47081 + endloop + endfacet + facet normal 0.954921 0.116722 0.272951 + outer loop + vertex 0.855774 1.05849 2.47081 + vertex 0.855201 1.0633 2.47076 + vertex 0.854561 1.05887 2.47489 + endloop + endfacet + facet normal 0.962294 0.0978081 0.253818 + outer loop + vertex 0.855201 1.0633 2.47076 + vertex 0.854175 1.06317 2.4747 + vertex 0.854561 1.05887 2.47489 + endloop + endfacet + facet normal 0.914044 0.0997207 0.393166 + outer loop + vertex 0.854175 1.06317 2.4747 + vertex 0.853077 1.05996 2.47807 + vertex 0.854561 1.05887 2.47489 + endloop + endfacet + facet normal 0.927285 0.0688157 0.367978 + outer loop + vertex 0.853146 1.06378 2.47718 + vertex 0.853077 1.05996 2.47807 + vertex 0.854175 1.06317 2.4747 + endloop + endfacet + facet normal 0.803104 0.204955 0.55948 + outer loop + vertex 0.857976 1.065 2.455 + vertex 0.8567 1.07 2.455 + vertex 0.856911 1.06358 2.45705 + endloop + endfacet + facet normal 0.937264 0.133563 0.32202 + outer loop + vertex 0.8567 1.07 2.455 + vertex 0.856111 1.06736 2.45781 + vertex 0.856911 1.06358 2.45705 + endloop + endfacet + facet normal 0.97747 0.187122 0.0976639 + outer loop + vertex 0.856911 1.06358 2.45705 + vertex 0.856111 1.06736 2.45781 + vertex 0.856538 1.0633 2.46132 + endloop + endfacet + facet normal 0.984672 0.161153 0.0667109 + outer loop + vertex 0.856111 1.06736 2.45781 + vertex 0.855728 1.06815 2.46154 + vertex 0.856538 1.0633 2.46132 + endloop + endfacet + facet normal 0.981991 0.159099 0.101887 + outer loop + vertex 0.856538 1.0633 2.46132 + vertex 0.855728 1.06815 2.46154 + vertex 0.856024 1.06341 2.46609 + endloop + endfacet + facet normal 0.983091 0.154984 0.0975298 + outer loop + vertex 0.855728 1.06815 2.46154 + vertex 0.855237 1.06831 2.46623 + vertex 0.856024 1.06341 2.46609 + endloop + endfacet + facet normal 0.972889 0.151114 0.175074 + outer loop + vertex 0.856024 1.06341 2.46609 + vertex 0.855237 1.06831 2.46623 + vertex 0.855201 1.0633 2.47076 + endloop + endfacet + facet normal 0.971493 0.155008 0.17937 + outer loop + vertex 0.855237 1.06831 2.46623 + vertex 0.854422 1.06783 2.47107 + vertex 0.855201 1.0633 2.47076 + endloop + endfacet + facet normal 0.957355 0.150329 0.246725 + outer loop + vertex 0.853719 1.06617 2.47481 + vertex 0.854422 1.06783 2.47107 + vertex 0.853643 1.06907 2.47334 + endloop + endfacet + facet normal 0.960543 0.137635 0.241691 + outer loop + vertex 0.853719 1.06617 2.47481 + vertex 0.854175 1.06317 2.4747 + vertex 0.854422 1.06783 2.47107 + endloop + endfacet + facet normal 0.955962 0.147344 0.253825 + outer loop + vertex 0.854175 1.06317 2.4747 + vertex 0.855201 1.0633 2.47076 + vertex 0.854422 1.06783 2.47107 + endloop + endfacet + facet normal 0.926683 0.128588 0.353162 + outer loop + vertex 0.854175 1.06317 2.4747 + vertex 0.853719 1.06617 2.47481 + vertex 0.853146 1.06378 2.47718 + endloop + endfacet + facet normal 0.596278 0.376832 -0.708838 + outer loop + vertex 0.855 1.07 2.45357 + vertex 0.855 1.07269 2.455 + vertex 0.8567 1.07 2.455 + endloop + endfacet + facet normal 0.796212 0.503186 -0.335931 + outer loop + vertex 0.855 1.075 2.45846 + vertex 0.8567 1.07 2.455 + vertex 0.855 1.07269 2.455 + endloop + endfacet + facet normal 0.90245 0.00876703 0.430706 + outer loop + vertex 0.855 1.075 2.45846 + vertex 0.85521 1.0728 2.45806 + vertex 0.8567 1.07 2.455 + endloop + endfacet + facet normal 0.934718 0.13936 0.326927 + outer loop + vertex 0.85521 1.0728 2.45806 + vertex 0.856111 1.06736 2.45781 + vertex 0.8567 1.07 2.455 + endloop + endfacet + facet normal 0.984867 0.159836 0.0670101 + outer loop + vertex 0.856111 1.06736 2.45781 + vertex 0.85521 1.0728 2.45806 + vertex 0.855728 1.06815 2.46154 + endloop + endfacet + facet normal 0.986454 0.153389 0.0581475 + outer loop + vertex 0.85521 1.0728 2.45806 + vertex 0.854931 1.07307 2.4621 + vertex 0.855728 1.06815 2.46154 + endloop + endfacet + facet normal 0.984066 0.148455 0.0978553 + outer loop + vertex 0.855728 1.06815 2.46154 + vertex 0.854931 1.07307 2.4621 + vertex 0.855237 1.06831 2.46623 + endloop + endfacet + facet normal 0.982005 0.155903 0.106583 + outer loop + vertex 0.854931 1.07307 2.4621 + vertex 0.854419 1.07324 2.46656 + vertex 0.855237 1.06831 2.46623 + endloop + endfacet + facet normal 0.975789 0.12976 0.176065 + outer loop + vertex 0.85391 1.07163 2.47057 + vertex 0.854419 1.07324 2.46656 + vertex 0.853691 1.07553 2.46891 + endloop + endfacet + facet normal 0.970381 0.154836 0.185438 + outer loop + vertex 0.85391 1.07163 2.47057 + vertex 0.854422 1.06783 2.47107 + vertex 0.854419 1.07324 2.46656 + endloop + endfacet + facet normal 0.972436 0.149455 0.178975 + outer loop + vertex 0.854422 1.06783 2.47107 + vertex 0.855237 1.06831 2.46623 + vertex 0.854419 1.07324 2.46656 + endloop + endfacet + facet normal 0.957136 0.160301 0.241233 + outer loop + vertex 0.854422 1.06783 2.47107 + vertex 0.85391 1.07163 2.47057 + vertex 0.853643 1.06907 2.47334 + endloop + endfacet + facet normal -0.809767 0.028114 -0.586077 + outer loop + vertex 0.855 1.08 2.4587 + vertex 0.85521 1.0728 2.45806 + vertex 0.855 1.075 2.45846 + endloop + endfacet + facet normal 0.927882 -0.00582086 0.372828 + outer loop + vertex 0.854555 1.07825 2.45978 + vertex 0.85521 1.0728 2.45806 + vertex 0.855 1.08 2.4587 + endloop + endfacet + facet normal 0.993056 0.0998923 0.0621394 + outer loop + vertex 0.85521 1.0728 2.45806 + vertex 0.854555 1.07825 2.45978 + vertex 0.854931 1.07307 2.4621 + endloop + endfacet + facet normal 0.988651 0.11502 0.0966394 + outer loop + vertex 0.854555 1.07825 2.45978 + vertex 0.854413 1.0769 2.46284 + vertex 0.854931 1.07307 2.4621 + endloop + endfacet + facet normal 0.987662 0.11254 0.108897 + outer loop + vertex 0.854931 1.07307 2.4621 + vertex 0.854413 1.0769 2.46284 + vertex 0.854419 1.07324 2.46656 + endloop + endfacet + facet normal 0.987749 0.112148 0.108511 + outer loop + vertex 0.854413 1.0769 2.46284 + vertex 0.854017 1.07811 2.4652 + vertex 0.854419 1.07324 2.46656 + endloop + endfacet + facet normal 0.975798 0.13 0.175833 + outer loop + vertex 0.854017 1.07811 2.4652 + vertex 0.853691 1.07553 2.46891 + vertex 0.854419 1.07324 2.46656 + endloop + endfacet + facet normal 0.98062 0.10981 0.162252 + outer loop + vertex 0.853546 1.07938 2.46719 + vertex 0.853691 1.07553 2.46891 + vertex 0.854017 1.07811 2.4652 + endloop + endfacet + facet normal 0.964156 -0.0917031 0.248984 + outer loop + vertex 0.855 1.08 2.4587 + vertex 0.855 1.08353 2.46 + vertex 0.854555 1.07825 2.45978 + endloop + endfacet + facet normal -0.30353 -0.0139448 0.95272 + outer loop + vertex 0.854275 1.08215 2.45975 + vertex 0.854555 1.07825 2.45978 + vertex 0.855 1.08353 2.46 + endloop + endfacet + facet normal 0.988827 0.0721468 0.130444 + outer loop + vertex 0.854275 1.08215 2.45975 + vertex 0.854083 1.08079 2.46195 + vertex 0.854555 1.07825 2.45978 + endloop + endfacet + facet normal 0.990179 0.105018 0.0922876 + outer loop + vertex 0.854083 1.08079 2.46195 + vertex 0.854413 1.0769 2.46284 + vertex 0.854555 1.07825 2.45978 + endloop + endfacet + facet normal 0.98703 0.123413 0.10267 + outer loop + vertex 0.853747 1.0813 2.46457 + vertex 0.854083 1.08079 2.46195 + vertex 0.853641 1.08364 2.46277 + endloop + endfacet + facet normal 0.98881 0.104429 0.106533 + outer loop + vertex 0.853747 1.0813 2.46457 + vertex 0.854017 1.07811 2.4652 + vertex 0.854083 1.08079 2.46195 + endloop + endfacet + facet normal 0.987927 0.108888 0.110202 + outer loop + vertex 0.854017 1.07811 2.4652 + vertex 0.854413 1.0769 2.46284 + vertex 0.854083 1.08079 2.46195 + endloop + endfacet + facet normal 0.980581 0.114155 0.159468 + outer loop + vertex 0.854017 1.07811 2.4652 + vertex 0.853747 1.0813 2.46457 + vertex 0.853546 1.07938 2.46719 + endloop + endfacet + facet normal 0.980116 0.119213 0.15862 + outer loop + vertex 0.854275 1.08215 2.45975 + vertex 0.853897 1.08398 2.46071 + vertex 0.854083 1.08079 2.46195 + endloop + endfacet + facet normal 0.983764 0.112178 0.140087 + outer loop + vertex 0.854083 1.08079 2.46195 + vertex 0.853897 1.08398 2.46071 + vertex 0.853641 1.08364 2.46277 + endloop + endfacet + facet normal 0.633879 -0.439905 -0.636145 + outer loop + vertex 0.856104 1.11 2.525 + vertex 0.853626 1.10713 2.52452 + vertex 0.855 1.11 2.5239 + endloop + endfacet + facet normal 0.761433 -0.637494 -0.117568 + outer loop + vertex 0.856876 1.11 2.53 + vertex 0.853626 1.10713 2.52452 + vertex 0.856104 1.11 2.525 + endloop + endfacet + facet normal 0.726668 -0.683089 -0.0730978 + outer loop + vertex 0.853223 1.10632 2.52805 + vertex 0.853626 1.10713 2.52452 + vertex 0.856876 1.11 2.53 + endloop + endfacet + facet normal 0.735571 -0.666586 -0.120826 + outer loop + vertex 0.856025 1.10894 2.53067 + vertex 0.853223 1.10632 2.52805 + vertex 0.856876 1.11 2.53 + endloop + endfacet + facet normal 0.574611 -0.797878 0.182241 + outer loop + vertex 0.852012 1.10639 2.53214 + vertex 0.853223 1.10632 2.52805 + vertex 0.856025 1.10894 2.53067 + endloop + endfacet + facet normal 0.551012 -0.832501 0.0576792 + outer loop + vertex 0.855348 1.10876 2.53448 + vertex 0.852012 1.10639 2.53214 + vertex 0.856025 1.10894 2.53067 + endloop + endfacet + facet normal 0.332085 -0.857007 0.394029 + outer loop + vertex 0.851873 1.10782 2.53538 + vertex 0.852012 1.10639 2.53214 + vertex 0.855348 1.10876 2.53448 + endloop + endfacet + facet normal 0.330499 -0.863319 0.381379 + outer loop + vertex 0.855348 1.10876 2.53448 + vertex 0.853745 1.10938 2.53728 + vertex 0.851873 1.10782 2.53538 + endloop + endfacet + facet normal 0.714065 -0.662763 -0.225513 + outer loop + vertex 0.86 1.11345 2.53 + vertex 0.85942 1.11151 2.53387 + vertex 0.856025 1.10894 2.53067 + endloop + endfacet + facet normal 0.735904 -0.666359 -0.120044 + outer loop + vertex 0.856876 1.11 2.53 + vertex 0.86 1.11345 2.53 + vertex 0.856025 1.10894 2.53067 + endloop + endfacet + facet normal 0.564151 -0.824531 0.0433903 + outer loop + vertex 0.85942 1.11151 2.53387 + vertex 0.858811 1.11133 2.53832 + vertex 0.855348 1.10876 2.53448 + endloop + endfacet + facet normal 0.56544 -0.822551 0.0607233 + outer loop + vertex 0.856025 1.10894 2.53067 + vertex 0.85942 1.11151 2.53387 + vertex 0.855348 1.10876 2.53448 + endloop + endfacet + facet normal 0.271809 -0.894615 0.354662 + outer loop + vertex 0.853745 1.10938 2.53728 + vertex 0.855348 1.10876 2.53448 + vertex 0.858811 1.11133 2.53832 + endloop + endfacet + facet normal 0.173548 -0.774409 0.608418 + outer loop + vertex 0.853745 1.10938 2.53728 + vertex 0.858811 1.11133 2.53832 + vertex 0.853296 1.11155 2.54018 + endloop + endfacet + facet normal 0.0325244 -0.975977 0.215432 + outer loop + vertex 0.853296 1.11155 2.54018 + vertex 0.858811 1.11133 2.53832 + vertex 0.858472 1.11218 2.54224 + endloop + endfacet + facet normal -0.146296 -0.782789 0.604845 + outer loop + vertex 0.858472 1.11218 2.54224 + vertex 0.854654 1.114 2.54367 + vertex 0.853296 1.11155 2.54018 + endloop + endfacet + facet normal -0.251592 -0.866956 0.430218 + outer loop + vertex 0.858942 1.11321 2.54458 + vertex 0.854654 1.114 2.54367 + vertex 0.858472 1.11218 2.54224 + endloop + endfacet + facet normal -0.27031 -0.684002 0.67755 + outer loop + vertex 0.854654 1.114 2.54367 + vertex 0.858942 1.11321 2.54458 + vertex 0.857937 1.1152 2.54619 + endloop + endfacet + facet normal -0.292844 -0.657486 0.69423 + outer loop + vertex 0.853633 1.11651 2.54561 + vertex 0.854654 1.114 2.54367 + vertex 0.857937 1.1152 2.54619 + endloop + endfacet + facet normal -0.282815 -0.60042 0.748005 + outer loop + vertex 0.857937 1.1152 2.54619 + vertex 0.853845 1.11904 2.54773 + vertex 0.853633 1.11651 2.54561 + endloop + endfacet + facet normal -0.291103 -0.606126 0.740183 + outer loop + vertex 0.859617 1.11743 2.54868 + vertex 0.853845 1.11904 2.54773 + vertex 0.857937 1.1152 2.54619 + endloop + endfacet + facet normal -0.297591 -0.657722 0.691983 + outer loop + vertex 0.853845 1.11904 2.54773 + vertex 0.859617 1.11743 2.54868 + vertex 0.856935 1.1206 2.55054 + endloop + endfacet + facet normal -0.355741 -0.594611 0.721032 + outer loop + vertex 0.852823 1.12226 2.54988 + vertex 0.853845 1.11904 2.54773 + vertex 0.856935 1.1206 2.55054 + endloop + endfacet + facet normal -0.353977 -0.587685 0.727548 + outer loop + vertex 0.856935 1.1206 2.55054 + vertex 0.853978 1.1241 2.55193 + vertex 0.852823 1.12226 2.54988 + endloop + endfacet + facet normal -0.33929 -0.58035 0.740322 + outer loop + vertex 0.859526 1.12273 2.5534 + vertex 0.853978 1.1241 2.55193 + vertex 0.856935 1.1206 2.55054 + endloop + endfacet + facet normal -0.408166 -0.629434 0.661221 + outer loop + vertex 0.85804 1.12616 2.55584 + vertex 0.855903 1.12802 2.55629 + vertex 0.854211 1.12719 2.55445 + endloop + endfacet + facet normal -0.407452 -0.639925 0.651521 + outer loop + vertex 0.85804 1.12616 2.55584 + vertex 0.854211 1.12719 2.55445 + vertex 0.859526 1.12273 2.5534 + endloop + endfacet + facet normal -0.339265 -0.579618 0.740906 + outer loop + vertex 0.859526 1.12273 2.5534 + vertex 0.854211 1.12719 2.55445 + vertex 0.853978 1.1241 2.55193 + endloop + endfacet + facet normal -0.352715 -0.582861 0.732028 + outer loop + vertex 0.85804 1.12616 2.55584 + vertex 0.85839 1.12879 2.5581 + vertex 0.855903 1.12802 2.55629 + endloop + endfacet + facet normal -0.480642 -0.542959 0.688606 + outer loop + vertex 0.854211 1.12719 2.55445 + vertex 0.855903 1.12802 2.55629 + vertex 0.853596 1.13025 2.55643 + endloop + endfacet + facet normal -0.471573 -0.522739 0.710185 + outer loop + vertex 0.857657 1.13198 2.56017 + vertex 0.855555 1.13448 2.56062 + vertex 0.853364 1.13343 2.55839 + endloop + endfacet + facet normal -0.471968 -0.554583 0.685335 + outer loop + vertex 0.85839 1.12879 2.5581 + vertex 0.857657 1.13198 2.56017 + vertex 0.853364 1.13343 2.55839 + endloop + endfacet + facet normal -0.415841 -0.498348 0.76074 + outer loop + vertex 0.85839 1.12879 2.5581 + vertex 0.853364 1.13343 2.55839 + vertex 0.853596 1.13025 2.55643 + endloop + endfacet + facet normal -0.414589 -0.480091 0.773064 + outer loop + vertex 0.85839 1.12879 2.5581 + vertex 0.853596 1.13025 2.55643 + vertex 0.855903 1.12802 2.55629 + endloop + endfacet + facet normal -0.443856 -0.504865 0.74034 + outer loop + vertex 0.857657 1.13198 2.56017 + vertex 0.858981 1.13374 2.56217 + vertex 0.855555 1.13448 2.56062 + endloop + endfacet + facet normal -0.517346 -0.456647 0.723759 + outer loop + vertex 0.853364 1.13343 2.55839 + vertex 0.855555 1.13448 2.56062 + vertex 0.852998 1.13652 2.56008 + endloop + endfacet + facet normal -0.497483 -0.422613 0.757568 + outer loop + vertex 0.855555 1.13448 2.56062 + vertex 0.855321 1.1372 2.56198 + vertex 0.852998 1.13652 2.56008 + endloop + endfacet + facet normal -0.447442 -0.431271 0.783454 + outer loop + vertex 0.855555 1.13448 2.56062 + vertex 0.858981 1.13374 2.56217 + vertex 0.855321 1.1372 2.56198 + endloop + endfacet + facet normal -0.481279 -0.469526 0.740213 + outer loop + vertex 0.858981 1.13374 2.56217 + vertex 0.859416 1.13689 2.56445 + vertex 0.855321 1.1372 2.56198 + endloop + endfacet + facet normal -0.550499 -0.380695 0.742982 + outer loop + vertex 0.859043 1.14032 2.5663 + vertex 0.856273 1.14457 2.56642 + vertex 0.8542 1.142 2.56357 + endloop + endfacet + facet normal -0.551624 -0.441356 0.707754 + outer loop + vertex 0.859043 1.14032 2.5663 + vertex 0.8542 1.142 2.56357 + vertex 0.859416 1.13689 2.56445 + endloop + endfacet + facet normal -0.49903 -0.374977 0.781256 + outer loop + vertex 0.859416 1.13689 2.56445 + vertex 0.8542 1.142 2.56357 + vertex 0.855321 1.1372 2.56198 + endloop + endfacet + facet normal -0.558313 -0.385546 0.734603 + outer loop + vertex 0.859043 1.14032 2.5663 + vertex 0.860119 1.14283 2.56844 + vertex 0.856273 1.14457 2.56642 + endloop + endfacet + facet normal -0.550421 -0.331395 0.766299 + outer loop + vertex 0.860119 1.14283 2.56844 + vertex 0.85732 1.14781 2.56858 + vertex 0.856273 1.14457 2.56642 + endloop + endfacet + facet normal -0.6693 -0.0382887 0.742005 + outer loop + vertex 0.858083 1.19084 2.58037 + vertex 0.857888 1.19372 2.58034 + vertex 0.855447 1.19214 2.57805 + endloop + endfacet + facet normal -0.679372 -0.0814289 0.729262 + outer loop + vertex 0.858083 1.19084 2.58037 + vertex 0.855447 1.19214 2.57805 + vertex 0.857606 1.18752 2.57955 + endloop + endfacet + facet normal -0.658 -0.064647 0.750238 + outer loop + vertex 0.857606 1.18752 2.57955 + vertex 0.855447 1.19214 2.57805 + vertex 0.855003 1.18675 2.5772 + endloop + endfacet + facet normal -0.648565 -0.0173374 0.760962 + outer loop + vertex 0.857888 1.19372 2.58034 + vertex 0.859157 1.19589 2.58147 + vertex 0.856877 1.1972 2.57956 + endloop + endfacet + facet normal -0.672687 -0.0292276 0.739349 + outer loop + vertex 0.857888 1.19372 2.58034 + vertex 0.856877 1.1972 2.57956 + vertex 0.855447 1.19214 2.57805 + endloop + endfacet + facet normal -0.658256 -0.0370302 0.751882 + outer loop + vertex 0.855447 1.19214 2.57805 + vertex 0.856877 1.1972 2.57956 + vertex 0.854217 1.19699 2.57722 + endloop + endfacet + facet normal -0.635766 -0.0302137 0.77129 + outer loop + vertex 0.859157 1.19589 2.58147 + vertex 0.857888 1.19372 2.58034 + vertex 0.860304 1.19229 2.58227 + endloop + endfacet + facet normal -0.550397 0.0948138 0.829502 + outer loop + vertex 0.854988 1.68394 2.60154 + vertex 0.852063 1.68127 2.5999 + vertex 0.854287 1.68027 2.60149 + endloop + endfacet + facet normal -0.551213 0.0961328 0.828808 + outer loop + vertex 0.852306 1.68571 2.59955 + vertex 0.852063 1.68127 2.5999 + vertex 0.854988 1.68394 2.60154 + endloop + endfacet + facet normal -0.613747 0.0511955 0.787841 + outer loop + vertex 0.853302 1.7709 2.58857 + vertex 0.853012 1.76599 2.58866 + vertex 0.856058 1.76844 2.59087 + endloop + endfacet + facet normal -0.619863 0.0404249 0.783668 + outer loop + vertex 0.856275 1.77349 2.59078 + vertex 0.853302 1.7709 2.58857 + vertex 0.856058 1.76844 2.59087 + endloop + endfacet + facet normal -0.611811 0.0401896 0.789982 + outer loop + vertex 0.856058 1.76844 2.59087 + vertex 0.859049 1.77106 2.59306 + vertex 0.856275 1.77349 2.59078 + endloop + endfacet + facet normal -0.613877 0.0440578 0.788171 + outer loop + vertex 0.858782 1.76605 2.59313 + vertex 0.859049 1.77106 2.59306 + vertex 0.856058 1.76844 2.59087 + endloop + endfacet + facet normal -0.620323 0.0413051 0.783258 + outer loop + vertex 0.85345 1.77589 2.58842 + vertex 0.853302 1.7709 2.58857 + vertex 0.856275 1.77349 2.59078 + endloop + endfacet + facet normal -0.610344 0.0596196 0.78989 + outer loop + vertex 0.856452 1.77861 2.59053 + vertex 0.85345 1.77589 2.58842 + vertex 0.856275 1.77349 2.59078 + endloop + endfacet + facet normal -0.608268 0.0596264 0.791489 + outer loop + vertex 0.856275 1.77349 2.59078 + vertex 0.859617 1.77659 2.59312 + vertex 0.856452 1.77861 2.59053 + endloop + endfacet + facet normal -0.60451 0.0530635 0.794828 + outer loop + vertex 0.859049 1.77106 2.59306 + vertex 0.859617 1.77659 2.59312 + vertex 0.856275 1.77349 2.59078 + endloop + endfacet + facet normal -0.572091 0.357193 0.738326 + outer loop + vertex 0.857378 1.86783 2.57043 + vertex 0.859648 1.86977 2.57125 + vertex 0.858171 1.87173 2.56916 + endloop + endfacet + facet normal -0.580093 0.356832 0.732232 + outer loop + vertex 0.857378 1.86783 2.57043 + vertex 0.858171 1.87173 2.56916 + vertex 0.854403 1.86699 2.56848 + endloop + endfacet + facet normal -0.551217 0.328863 0.766817 + outer loop + vertex 0.854403 1.86699 2.56848 + vertex 0.858171 1.87173 2.56916 + vertex 0.854442 1.87181 2.56644 + endloop + endfacet + facet normal -0.556859 0.32923 0.762572 + outer loop + vertex 0.859648 1.86977 2.57125 + vertex 0.857378 1.86783 2.57043 + vertex 0.859164 1.86645 2.57233 + endloop + endfacet + facet normal -0.494529 0.381988 0.780722 + outer loop + vertex 0.855828 1.87854 2.56413 + vertex 0.853867 1.87734 2.56347 + vertex 0.854145 1.87548 2.56455 + endloop + endfacet + facet normal -0.510579 0.388884 0.766863 + outer loop + vertex 0.854145 1.87548 2.56455 + vertex 0.857995 1.87661 2.56654 + vertex 0.855828 1.87854 2.56413 + endloop + endfacet + facet normal -0.509654 0.360345 0.781284 + outer loop + vertex 0.854145 1.87548 2.56455 + vertex 0.854442 1.87181 2.56644 + vertex 0.857995 1.87661 2.56654 + endloop + endfacet + facet normal -0.538472 0.382307 0.750926 + outer loop + vertex 0.854442 1.87181 2.56644 + vertex 0.858171 1.87173 2.56916 + vertex 0.857995 1.87661 2.56654 + endloop + endfacet + facet normal -0.514492 0.441976 0.734816 + outer loop + vertex 0.856532 1.88192 2.56265 + vertex 0.852626 1.88106 2.56044 + vertex 0.854049 1.87906 2.56263 + endloop + endfacet + facet normal -0.507672 0.419096 0.752747 + outer loop + vertex 0.854049 1.87906 2.56263 + vertex 0.853867 1.87734 2.56347 + vertex 0.855828 1.87854 2.56413 + endloop + endfacet + facet normal -0.501848 0.430889 0.749989 + outer loop + vertex 0.856532 1.88192 2.56265 + vertex 0.854049 1.87906 2.56263 + vertex 0.855828 1.87854 2.56413 + endloop + endfacet + facet normal -0.502857 0.430821 0.749352 + outer loop + vertex 0.856532 1.88192 2.56265 + vertex 0.855828 1.87854 2.56413 + vertex 0.858673 1.88089 2.56468 + endloop + endfacet + facet normal -0.504802 0.427714 0.749824 + outer loop + vertex 0.856532 1.88192 2.56265 + vertex 0.858673 1.88089 2.56468 + vertex 0.85866 1.88284 2.56356 + endloop + endfacet + facet normal -0.490881 0.412021 0.767642 + outer loop + vertex 0.858673 1.88089 2.56468 + vertex 0.855828 1.87854 2.56413 + vertex 0.857995 1.87661 2.56654 + endloop + endfacet + facet normal -0.517438 0.467812 0.716526 + outer loop + vertex 0.856532 1.88192 2.56265 + vertex 0.858856 1.88449 2.56265 + vertex 0.857264 1.88612 2.56044 + endloop + endfacet + facet normal -0.511956 0.46864 0.719915 + outer loop + vertex 0.856532 1.88192 2.56265 + vertex 0.857264 1.88612 2.56044 + vertex 0.852626 1.88106 2.56044 + endloop + endfacet + facet normal -0.472769 0.432696 0.767635 + outer loop + vertex 0.852626 1.88106 2.56044 + vertex 0.857264 1.88612 2.56044 + vertex 0.852944 1.88609 2.55779 + endloop + endfacet + facet normal -0.509241 0.460398 0.727123 + outer loop + vertex 0.858856 1.88449 2.56265 + vertex 0.856532 1.88192 2.56265 + vertex 0.85866 1.88284 2.56356 + endloop + endfacet + facet normal -0.422816 0.559059 0.713218 + outer loop + vertex 0.856224 1.89241 2.55554 + vertex 0.852606 1.89145 2.55415 + vertex 0.854169 1.88989 2.5563 + endloop + endfacet + facet normal -0.382837 0.537949 0.751031 + outer loop + vertex 0.854169 1.88989 2.5563 + vertex 0.857077 1.89009 2.55764 + vertex 0.856224 1.89241 2.55554 + endloop + endfacet + facet normal -0.399576 0.44426 0.801855 + outer loop + vertex 0.854169 1.88989 2.5563 + vertex 0.852944 1.88609 2.55779 + vertex 0.857077 1.89009 2.55764 + endloop + endfacet + facet normal -0.454871 0.498823 0.737745 + outer loop + vertex 0.852944 1.88609 2.55779 + vertex 0.857264 1.88612 2.56044 + vertex 0.857077 1.89009 2.55764 + endloop + endfacet + facet normal -0.281665 0.65517 0.701012 + outer loop + vertex 0.856224 1.89241 2.55554 + vertex 0.859923 1.89348 2.55602 + vertex 0.856853 1.8954 2.553 + endloop + endfacet + facet normal -0.418327 0.637793 0.646701 + outer loop + vertex 0.856224 1.89241 2.55554 + vertex 0.856853 1.8954 2.553 + vertex 0.852606 1.89145 2.55415 + endloop + endfacet + facet normal -0.310288 0.557646 0.769904 + outer loop + vertex 0.852606 1.89145 2.55415 + vertex 0.856853 1.8954 2.553 + vertex 0.852221 1.89517 2.5513 + endloop + endfacet + facet normal -0.270435 0.588859 0.761649 + outer loop + vertex 0.859923 1.89348 2.55602 + vertex 0.856224 1.89241 2.55554 + vertex 0.857077 1.89009 2.55764 + endloop + endfacet + facet normal 0.136667 0.841863 0.522101 + outer loop + vertex 0.85967 1.90059 2.547 + vertex 0.857551 1.90245 2.54455 + vertex 0.856011 1.90144 2.54659 + endloop + endfacet + facet normal 0.035541 0.708261 0.705055 + outer loop + vertex 0.856011 1.90144 2.54659 + vertex 0.854096 1.90131 2.54682 + vertex 0.855084 1.89903 2.54906 + endloop + endfacet + facet normal 0.0823457 0.69734 0.711994 + outer loop + vertex 0.856011 1.90144 2.54659 + vertex 0.855084 1.89903 2.54906 + vertex 0.85967 1.90059 2.547 + endloop + endfacet + facet normal -0.0227435 0.820283 0.571506 + outer loop + vertex 0.85967 1.90059 2.547 + vertex 0.855084 1.89903 2.54906 + vertex 0.859536 1.89819 2.55045 + endloop + endfacet + facet normal -0.29412 0.633917 0.715292 + outer loop + vertex 0.856853 1.8954 2.553 + vertex 0.855084 1.89903 2.54906 + vertex 0.852221 1.89517 2.5513 + endloop + endfacet + facet normal -0.0809371 0.715107 0.694314 + outer loop + vertex 0.859536 1.89819 2.55045 + vertex 0.855084 1.89903 2.54906 + vertex 0.856853 1.8954 2.553 + endloop + endfacet + facet normal -0.522667 0.827627 0.204579 + outer loop + vertex 0.854982 1.90666 2.5389 + vertex 0.86 1.90956 2.54 + vertex 0.86 1.91 2.53822 + endloop + endfacet + facet normal -0.405339 0.723833 0.55836 + outer loop + vertex 0.853681 1.90817 2.536 + vertex 0.854982 1.90666 2.5389 + vertex 0.86 1.91 2.53822 + endloop + endfacet + facet normal -0.423802 0.433129 0.795482 + outer loop + vertex 0.86 1.90956 2.54 + vertex 0.854982 1.90666 2.5389 + vertex 0.857547 1.90456 2.54142 + endloop + endfacet + facet normal 0.0372385 0.784374 0.61917 + outer loop + vertex 0.857547 1.90456 2.54142 + vertex 0.854982 1.90666 2.5389 + vertex 0.854024 1.90474 2.54139 + endloop + endfacet + facet normal 0.0946812 0.860876 0.499928 + outer loop + vertex 0.857551 1.90245 2.54455 + vertex 0.854245 1.90301 2.54422 + vertex 0.856011 1.90144 2.54659 + endloop + endfacet + facet normal 0.0834917 0.827364 0.555426 + outer loop + vertex 0.857551 1.90245 2.54455 + vertex 0.857547 1.90456 2.54142 + vertex 0.854245 1.90301 2.54422 + endloop + endfacet + facet normal 0.0415862 0.853031 0.520201 + outer loop + vertex 0.857547 1.90456 2.54142 + vertex 0.854024 1.90474 2.54139 + vertex 0.854245 1.90301 2.54422 + endloop + endfacet + facet normal 0.00841469 0.836479 0.547935 + outer loop + vertex 0.856011 1.90144 2.54659 + vertex 0.854245 1.90301 2.54422 + vertex 0.854096 1.90131 2.54682 + endloop + endfacet + facet normal -0.201851 0.973717 0.10551 + outer loop + vertex 0.857768 1.91 2.53 + vertex 0.857541 1.90973 2.5321 + vertex 0.86 1.91 2.53427 + endloop + endfacet + facet normal 0.857757 0.489534 0.156871 + outer loop + vertex 0.857768 1.91 2.53 + vertex 0.855 1.91485 2.53 + vertex 0.857541 1.90973 2.5321 + endloop + endfacet + facet normal 0.195745 0.45313 0.869688 + outer loop + vertex 0.855 1.91485 2.53 + vertex 0.854096 1.90973 2.53287 + vertex 0.857541 1.90973 2.5321 + endloop + endfacet + facet normal -0.376215 0.848171 0.372919 + outer loop + vertex 0.86 1.91 2.53822 + vertex 0.854096 1.90973 2.53287 + vertex 0.853681 1.90817 2.536 + endloop + endfacet + facet normal -0.00707376 0.999095 -0.0419441 + outer loop + vertex 0.857541 1.90973 2.5321 + vertex 0.854096 1.90973 2.53287 + vertex 0.86 1.91 2.53822 + endloop + endfacet + facet normal -0.998267 0.0296419 0.0508318 + outer loop + vertex 0.854879 1.96093 2.45153 + vertex 0.855 1.95904 2.455 + vertex 0.855 1.96 2.45444 + endloop + endfacet + facet normal 0.932951 0.328816 0.146569 + outer loop + vertex 0.854826 1.95959 2.45487 + vertex 0.855 1.95904 2.455 + vertex 0.854879 1.96093 2.45153 + endloop + endfacet + facet normal 0.944953 0.316831 0.0817459 + outer loop + vertex 0.855 1.95775 2.46 + vertex 0.855 1.95904 2.455 + vertex 0.854826 1.95959 2.45487 + endloop + endfacet + facet normal 0.960389 0.27103 0.0647716 + outer loop + vertex 0.854728 1.95877 2.45977 + vertex 0.855 1.95775 2.46 + vertex 0.854826 1.95959 2.45487 + endloop + endfacet + facet normal 0.791589 0.326829 0.516304 + outer loop + vertex 0.853699 1.9553 2.46355 + vertex 0.855 1.95775 2.46 + vertex 0.854728 1.95877 2.45977 + endloop + endfacet + facet normal 0.973466 -0.220019 0.0628977 + outer loop + vertex 0.854403 1.95886 2.46512 + vertex 0.853699 1.9553 2.46355 + vertex 0.854728 1.95877 2.45977 + endloop + endfacet + facet normal 0.965952 -0.236777 0.104273 + outer loop + vertex 0.853319 1.95557 2.46768 + vertex 0.853699 1.9553 2.46355 + vertex 0.854403 1.95886 2.46512 + endloop + endfacet + facet normal 0.967847 -0.202406 0.149343 + outer loop + vertex 0.854403 1.95886 2.46512 + vertex 0.853571 1.958 2.46934 + vertex 0.853319 1.95557 2.46768 + endloop + endfacet + facet normal 0.57767 -0.57719 -0.57719 + outer loop + vertex 0.856219 1.965 2.45 + vertex 0.855 1.96378 2.45 + vertex 0.855 1.965 2.44878 + endloop + endfacet + facet normal -0.994806 0.0775049 0.065983 + outer loop + vertex 0.855 1.96378 2.45 + vertex 0.854879 1.96093 2.45153 + vertex 0.855 1.96 2.45444 + endloop + endfacet + facet normal 0.438918 -0.438553 -0.784233 + outer loop + vertex 0.855 1.96378 2.45 + vertex 0.856219 1.965 2.45 + vertex 0.854879 1.96093 2.45153 + endloop + endfacet + facet normal 0.953471 -0.251807 0.165788 + outer loop + vertex 0.856219 1.965 2.45 + vertex 0.855543 1.96345 2.45153 + vertex 0.854879 1.96093 2.45153 + endloop + endfacet + facet normal 0.963465 -0.253606 -0.0861318 + outer loop + vertex 0.854879 1.96093 2.45153 + vertex 0.855543 1.96345 2.45153 + vertex 0.854826 1.95959 2.45487 + endloop + endfacet + facet normal 0.98043 -0.196212 -0.0160317 + outer loop + vertex 0.855543 1.96345 2.45153 + vertex 0.855411 1.96244 2.45581 + vertex 0.854826 1.95959 2.45487 + endloop + endfacet + facet normal 0.980307 -0.197015 -0.0135466 + outer loop + vertex 0.854826 1.95959 2.45487 + vertex 0.855411 1.96244 2.45581 + vertex 0.854728 1.95877 2.45977 + endloop + endfacet + facet normal 0.984862 -0.17308 0.00944157 + outer loop + vertex 0.855411 1.96244 2.45581 + vertex 0.855331 1.96225 2.46077 + vertex 0.854728 1.95877 2.45977 + endloop + endfacet + facet normal 0.980249 -0.18755 0.0627442 + outer loop + vertex 0.854728 1.95877 2.45977 + vertex 0.855331 1.96225 2.46077 + vertex 0.854403 1.95886 2.46512 + endloop + endfacet + facet normal 0.983588 -0.158599 0.086029 + outer loop + vertex 0.855331 1.96225 2.46077 + vertex 0.855101 1.96292 2.46463 + vertex 0.854403 1.95886 2.46512 + endloop + endfacet + facet normal 0.956517 -0.117772 0.266842 + outer loop + vertex 0.853571 1.958 2.46934 + vertex 0.854238 1.96209 2.46876 + vertex 0.853036 1.9596 2.47197 + endloop + endfacet + facet normal 0.976959 -0.135672 0.164756 + outer loop + vertex 0.853571 1.958 2.46934 + vertex 0.854403 1.95886 2.46512 + vertex 0.854238 1.96209 2.46876 + endloop + endfacet + facet normal 0.973822 -0.146257 0.174011 + outer loop + vertex 0.854403 1.95886 2.46512 + vertex 0.855101 1.96292 2.46463 + vertex 0.854238 1.96209 2.46876 + endloop + endfacet + facet normal 0.951658 -0.075911 0.297631 + outer loop + vertex 0.854238 1.96209 2.46876 + vertex 0.853078 1.96364 2.47287 + vertex 0.853036 1.9596 2.47197 + endloop + endfacet + facet normal 0.954348 -0.239162 0.178944 + outer loop + vertex 0.856219 1.965 2.45 + vertex 0.857472 1.97 2.45 + vertex 0.855543 1.96345 2.45153 + endloop + endfacet + facet normal 0.92511 -0.196347 0.324991 + outer loop + vertex 0.857472 1.97 2.45 + vertex 0.856206 1.96761 2.45216 + vertex 0.855543 1.96345 2.45153 + endloop + endfacet + facet normal 0.987661 -0.156472 -0.00642784 + outer loop + vertex 0.855543 1.96345 2.45153 + vertex 0.856206 1.96761 2.45216 + vertex 0.855411 1.96244 2.45581 + endloop + endfacet + facet normal 0.991038 -0.129623 0.0322609 + outer loop + vertex 0.856206 1.96761 2.45216 + vertex 0.855948 1.96673 2.45656 + vertex 0.855411 1.96244 2.45581 + endloop + endfacet + facet normal 0.991953 -0.126102 0.0113269 + outer loop + vertex 0.855411 1.96244 2.45581 + vertex 0.855948 1.96673 2.45656 + vertex 0.855331 1.96225 2.46077 + endloop + endfacet + facet normal 0.994647 -0.0909015 0.0491284 + outer loop + vertex 0.855948 1.96673 2.45656 + vertex 0.855716 1.9667 2.46118 + vertex 0.855331 1.96225 2.46077 + endloop + endfacet + facet normal 0.992805 -0.0931723 0.0752157 + outer loop + vertex 0.855331 1.96225 2.46077 + vertex 0.855716 1.9667 2.46118 + vertex 0.855101 1.96292 2.46463 + endloop + endfacet + facet normal 0.991445 -0.0525237 0.119492 + outer loop + vertex 0.855716 1.9667 2.46118 + vertex 0.855199 1.96678 2.46551 + vertex 0.855101 1.96292 2.46463 + endloop + endfacet + facet normal 0.97924 -0.0685059 0.190776 + outer loop + vertex 0.855101 1.96292 2.46463 + vertex 0.855199 1.96678 2.46551 + vertex 0.854238 1.96209 2.46876 + endloop + endfacet + facet normal 0.976472 -0.0557691 0.208308 + outer loop + vertex 0.855199 1.96678 2.46551 + vertex 0.854352 1.9673 2.46962 + vertex 0.854238 1.96209 2.46876 + endloop + endfacet + facet normal 0.952768 -0.0696911 0.295593 + outer loop + vertex 0.854352 1.9673 2.46962 + vertex 0.853078 1.96364 2.47287 + vertex 0.854238 1.96209 2.46876 + endloop + endfacet + facet normal 0.944594 -0.0400707 0.325787 + outer loop + vertex 0.853139 1.96861 2.4733 + vertex 0.853078 1.96364 2.47287 + vertex 0.854352 1.9673 2.46962 + endloop + endfacet + facet normal 0.870198 -0.0161828 0.492437 + outer loop + vertex 0.857472 1.97 2.45 + vertex 0.857565 1.975 2.45 + vertex 0.856206 1.96761 2.45216 + endloop + endfacet + facet normal 0.959743 -0.0997806 0.262558 + outer loop + vertex 0.857565 1.975 2.45 + vertex 0.856623 1.9725 2.45249 + vertex 0.856206 1.96761 2.45216 + endloop + endfacet + facet normal 0.995315 -0.0876093 0.0408934 + outer loop + vertex 0.856206 1.96761 2.45216 + vertex 0.856623 1.9725 2.45249 + vertex 0.855948 1.96673 2.45656 + endloop + endfacet + facet normal 0.99545 -0.0752364 0.0584781 + outer loop + vertex 0.856623 1.9725 2.45249 + vertex 0.856316 1.97175 2.45675 + vertex 0.855948 1.96673 2.45656 + endloop + endfacet + facet normal 0.995969 -0.0749257 0.0493111 + outer loop + vertex 0.855948 1.96673 2.45656 + vertex 0.856316 1.97175 2.45675 + vertex 0.855716 1.9667 2.46118 + endloop + endfacet + facet normal 0.995873 -0.0545072 0.0725651 + outer loop + vertex 0.856316 1.97175 2.45675 + vertex 0.855974 1.97162 2.46134 + vertex 0.855716 1.9667 2.46118 + endloop + endfacet + facet normal 0.991262 -0.0557829 0.119531 + outer loop + vertex 0.855716 1.9667 2.46118 + vertex 0.855974 1.97162 2.46134 + vertex 0.855199 1.96678 2.46551 + endloop + endfacet + facet normal 0.990634 -0.0488017 0.127528 + outer loop + vertex 0.855974 1.97162 2.46134 + vertex 0.855407 1.97177 2.46581 + vertex 0.855199 1.96678 2.46551 + endloop + endfacet + facet normal 0.97669 -0.0530253 0.208003 + outer loop + vertex 0.855199 1.96678 2.46551 + vertex 0.855407 1.97177 2.46581 + vertex 0.854352 1.9673 2.46962 + endloop + endfacet + facet normal 0.975506 -0.0468342 0.214928 + outer loop + vertex 0.855407 1.97177 2.46581 + vertex 0.854543 1.97238 2.46986 + vertex 0.854352 1.9673 2.46962 + endloop + endfacet + facet normal 0.942907 -0.051006 0.329128 + outer loop + vertex 0.854543 1.97238 2.46986 + vertex 0.853139 1.96861 2.4733 + vertex 0.854352 1.9673 2.46962 + endloop + endfacet + facet normal 0.93615 -0.0290498 0.350399 + outer loop + vertex 0.853274 1.97352 2.47335 + vertex 0.853139 1.96861 2.4733 + vertex 0.854543 1.97238 2.46986 + endloop + endfacet + facet normal 0.945934 -0.0348103 0.322487 + outer loop + vertex 0.857565 1.975 2.45 + vertex 0.857749 1.98 2.45 + vertex 0.856623 1.9725 2.45249 + endloop + endfacet + facet normal 0.979691 -0.0870513 0.180629 + outer loop + vertex 0.857749 1.98 2.45 + vertex 0.857062 1.9775 2.45252 + vertex 0.856623 1.9725 2.45249 + endloop + endfacet + facet normal 0.994565 -0.0876218 0.0562337 + outer loop + vertex 0.856623 1.9725 2.45249 + vertex 0.857062 1.9775 2.45252 + vertex 0.856316 1.97175 2.45675 + endloop + endfacet + facet normal 0.994501 -0.0915105 0.0509282 + outer loop + vertex 0.857062 1.9775 2.45252 + vertex 0.85677 1.9767 2.45677 + vertex 0.856316 1.97175 2.45675 + endloop + endfacet + facet normal 0.993249 -0.0914878 0.0713171 + outer loop + vertex 0.856316 1.97175 2.45675 + vertex 0.85677 1.9767 2.45677 + vertex 0.855974 1.97162 2.46134 + endloop + endfacet + facet normal 0.993235 -0.0925323 0.0701536 + outer loop + vertex 0.85677 1.9767 2.45677 + vertex 0.856421 1.97661 2.46159 + vertex 0.855974 1.97162 2.46134 + endloop + endfacet + facet normal 0.987141 -0.0948861 0.128647 + outer loop + vertex 0.855974 1.97162 2.46134 + vertex 0.856421 1.97661 2.46159 + vertex 0.855407 1.97177 2.46581 + endloop + endfacet + facet normal 0.98661 -0.0862467 0.138426 + outer loop + vertex 0.856421 1.97661 2.46159 + vertex 0.855783 1.97666 2.46618 + vertex 0.855407 1.97177 2.46581 + endloop + endfacet + facet normal 0.971076 -0.0912866 0.220631 + outer loop + vertex 0.855407 1.97177 2.46581 + vertex 0.855783 1.97666 2.46618 + vertex 0.854543 1.97238 2.46986 + endloop + endfacet + facet normal 0.966656 -0.0672785 0.247083 + outer loop + vertex 0.855783 1.97666 2.46618 + vertex 0.85483 1.97715 2.47004 + vertex 0.854543 1.97238 2.46986 + endloop + endfacet + facet normal 0.929862 -0.0692566 0.361332 + outer loop + vertex 0.85483 1.97715 2.47004 + vertex 0.853274 1.97352 2.47335 + vertex 0.854543 1.97238 2.46986 + endloop + endfacet + facet normal 0.919211 -0.0366721 0.392054 + outer loop + vertex 0.85345 1.97832 2.47338 + vertex 0.853274 1.97352 2.47335 + vertex 0.85483 1.97715 2.47004 + endloop + endfacet + facet normal 0.980433 -0.0962832 0.171697 + outer loop + vertex 0.857749 1.98 2.45 + vertex 0.85824 1.985 2.45 + vertex 0.857062 1.9775 2.45252 + endloop + endfacet + facet normal 0.985753 -0.16533 -0.0309238 + outer loop + vertex 0.85824 1.985 2.45 + vertex 0.857813 1.98197 2.45262 + vertex 0.857062 1.9775 2.45252 + endloop + endfacet + facet normal 0.985343 -0.166721 0.0361005 + outer loop + vertex 0.857062 1.9775 2.45252 + vertex 0.857813 1.98197 2.45262 + vertex 0.85677 1.9767 2.45677 + endloop + endfacet + facet normal 0.985336 -0.166776 0.0360289 + outer loop + vertex 0.857813 1.98197 2.45262 + vertex 0.857496 1.98109 2.45725 + vertex 0.85677 1.9767 2.45677 + endloop + endfacet + facet normal 0.98312 -0.169898 0.0678913 + outer loop + vertex 0.85677 1.9767 2.45677 + vertex 0.857496 1.98109 2.45725 + vertex 0.856421 1.97661 2.46159 + endloop + endfacet + facet normal 0.984375 -0.154914 0.0837065 + outer loop + vertex 0.857496 1.98109 2.45725 + vertex 0.857106 1.98156 2.4627 + vertex 0.856421 1.97661 2.46159 + endloop + endfacet + facet normal 0.976427 -0.165961 0.138015 + outer loop + vertex 0.856421 1.97661 2.46159 + vertex 0.857106 1.98156 2.4627 + vertex 0.855783 1.97666 2.46618 + endloop + endfacet + facet normal 0.97267 -0.12307 0.196895 + outer loop + vertex 0.857106 1.98156 2.4627 + vertex 0.856077 1.98052 2.46713 + vertex 0.855783 1.97666 2.46618 + endloop + endfacet + facet normal 0.957721 -0.135958 0.253549 + outer loop + vertex 0.855783 1.97666 2.46618 + vertex 0.856077 1.98052 2.46713 + vertex 0.85483 1.97715 2.47004 + endloop + endfacet + facet normal 0.94825 -0.0881429 0.305045 + outer loop + vertex 0.856077 1.98052 2.46713 + vertex 0.855191 1.98167 2.47022 + vertex 0.85483 1.97715 2.47004 + endloop + endfacet + facet normal 0.909382 -0.08917 0.406292 + outer loop + vertex 0.855191 1.98167 2.47022 + vertex 0.85345 1.97832 2.47338 + vertex 0.85483 1.97715 2.47004 + endloop + endfacet + facet normal 0.894187 -0.0444097 0.445486 + outer loop + vertex 0.853602 1.98299 2.47354 + vertex 0.85345 1.97832 2.47338 + vertex 0.855191 1.98167 2.47022 + endloop + endfacet + facet normal 0.962712 -0.264912 0.0548336 + outer loop + vertex 0.86 1.98937 2.45 + vertex 0.858685 1.98526 2.45325 + vertex 0.857813 1.98197 2.45262 + endloop + endfacet + facet normal 0.892908 -0.359619 -0.270905 + outer loop + vertex 0.85824 1.985 2.45 + vertex 0.86 1.98937 2.45 + vertex 0.857813 1.98197 2.45262 + endloop + endfacet + facet normal 0.969624 -0.241956 0.0358612 + outer loop + vertex 0.858685 1.98526 2.45325 + vertex 0.858417 1.98493 2.45823 + vertex 0.857496 1.98109 2.45725 + endloop + endfacet + facet normal 0.965826 -0.258606 0.0173952 + outer loop + vertex 0.857813 1.98197 2.45262 + vertex 0.858685 1.98526 2.45325 + vertex 0.857496 1.98109 2.45725 + endloop + endfacet + facet normal 0.966393 -0.233699 0.107099 + outer loop + vertex 0.858417 1.98493 2.45823 + vertex 0.858135 1.98564 2.46232 + vertex 0.857106 1.98156 2.4627 + endloop + endfacet + facet normal 0.962891 -0.254226 0.0906115 + outer loop + vertex 0.857496 1.98109 2.45725 + vertex 0.858417 1.98493 2.45823 + vertex 0.857106 1.98156 2.4627 + endloop + endfacet + facet normal 0.940108 -0.236938 0.245067 + outer loop + vertex 0.858135 1.98564 2.46232 + vertex 0.85836 1.98818 2.46392 + vertex 0.856918 1.98537 2.46673 + endloop + endfacet + facet normal 0.944618 -0.215317 0.247659 + outer loop + vertex 0.858135 1.98564 2.46232 + vertex 0.856918 1.98537 2.46673 + vertex 0.857106 1.98156 2.4627 + endloop + endfacet + facet normal 0.969986 -0.152455 0.189431 + outer loop + vertex 0.857106 1.98156 2.4627 + vertex 0.856918 1.98537 2.46673 + vertex 0.856077 1.98052 2.46713 + endloop + endfacet + facet normal 0.937684 -0.135902 0.319811 + outer loop + vertex 0.856077 1.98052 2.46713 + vertex 0.856918 1.98537 2.46673 + vertex 0.855191 1.98167 2.47022 + endloop + endfacet + facet normal 0.924555 -0.0797907 0.372602 + outer loop + vertex 0.856918 1.98537 2.46673 + vertex 0.855311 1.9856 2.47076 + vertex 0.855191 1.98167 2.47022 + endloop + endfacet + facet normal 0.883924 -0.0904743 0.458796 + outer loop + vertex 0.855311 1.9856 2.47076 + vertex 0.853602 1.98299 2.47354 + vertex 0.855191 1.98167 2.47022 + endloop + endfacet + facet normal 0.866543 -0.0376964 0.497677 + outer loop + vertex 0.853793 1.98773 2.47357 + vertex 0.853602 1.98299 2.47354 + vertex 0.855311 1.9856 2.47076 + endloop + endfacet + facet normal 0.935641 -0.171325 0.308584 + outer loop + vertex 0.85836 1.98818 2.46392 + vertex 0.857808 1.98979 2.46648 + vertex 0.856918 1.98537 2.46673 + endloop + endfacet + facet normal 0.892463 -0.0957729 0.440836 + outer loop + vertex 0.857808 1.98979 2.46648 + vertex 0.857804 1.99379 2.46736 + vertex 0.856117 1.99008 2.46997 + endloop + endfacet + facet normal 0.883986 -0.15355 0.441578 + outer loop + vertex 0.857808 1.98979 2.46648 + vertex 0.856117 1.99008 2.46997 + vertex 0.856918 1.98537 2.46673 + endloop + endfacet + facet normal 0.922475 -0.0998129 0.37293 + outer loop + vertex 0.856918 1.98537 2.46673 + vertex 0.856117 1.99008 2.46997 + vertex 0.855311 1.9856 2.47076 + endloop + endfacet + facet normal 0.856719 -0.0633382 0.51188 + outer loop + vertex 0.856117 1.99008 2.46997 + vertex 0.853793 1.98773 2.47357 + vertex 0.855311 1.9856 2.47076 + endloop + endfacet + facet normal 0.847985 -0.0279701 0.529281 + outer loop + vertex 0.853915 1.99283 2.47364 + vertex 0.853793 1.98773 2.47357 + vertex 0.856117 1.99008 2.46997 + endloop + endfacet + facet normal 0.87525 -0.0593972 0.480009 + outer loop + vertex 0.857804 1.99379 2.46736 + vertex 0.857859 1.99864 2.46786 + vertex 0.856072 1.9956 2.47074 + endloop + endfacet + facet normal 0.875054 -0.060094 0.480281 + outer loop + vertex 0.856117 1.99008 2.46997 + vertex 0.857804 1.99379 2.46736 + vertex 0.856072 1.9956 2.47074 + endloop + endfacet + facet normal 0.831483 -0.0703619 0.551076 + outer loop + vertex 0.856072 1.9956 2.47074 + vertex 0.853915 1.99283 2.47364 + vertex 0.856117 1.99008 2.46997 + endloop + endfacet + facet normal 0.816176 -0.0313148 0.576954 + outer loop + vertex 0.853872 1.99813 2.47399 + vertex 0.853915 1.99283 2.47364 + vertex 0.856072 1.9956 2.47074 + endloop + endfacet + facet normal 0.863719 -0.0333491 0.502869 + outer loop + vertex 0.857859 1.99864 2.46786 + vertex 0.857984 2.00354 2.46797 + vertex 0.856046 2.00069 2.47111 + endloop + endfacet + facet normal 0.864156 -0.0319191 0.50221 + outer loop + vertex 0.856072 1.9956 2.47074 + vertex 0.857859 1.99864 2.46786 + vertex 0.856046 2.00069 2.47111 + endloop + endfacet + facet normal 0.813551 -0.0378246 0.580262 + outer loop + vertex 0.856046 2.00069 2.47111 + vertex 0.853872 1.99813 2.47399 + vertex 0.856072 1.9956 2.47074 + endloop + endfacet + facet normal 0.835518 -0.101915 0.539929 + outer loop + vertex 0.853996 2.00392 2.47489 + vertex 0.853872 1.99813 2.47399 + vertex 0.856046 2.00069 2.47111 + endloop + endfacet + facet normal 0.885191 -0.0348911 0.463917 + outer loop + vertex 0.857984 2.00354 2.46797 + vertex 0.858186 2.00838 2.46795 + vertex 0.856157 2.00587 2.47163 + endloop + endfacet + facet normal 0.87505 -0.0670422 0.479367 + outer loop + vertex 0.856046 2.00069 2.47111 + vertex 0.857984 2.00354 2.46797 + vertex 0.856157 2.00587 2.47163 + endloop + endfacet + facet normal 0.850364 -0.0707506 0.521416 + outer loop + vertex 0.856157 2.00587 2.47163 + vertex 0.853996 2.00392 2.47489 + vertex 0.856046 2.00069 2.47111 + endloop + endfacet + facet normal 0.865819 -0.329639 0.376425 + outer loop + vertex 0.855 2.01 2.47791 + vertex 0.853996 2.00392 2.47489 + vertex 0.856157 2.00587 2.47163 + endloop + endfacet + facet normal 0.899283 -0.030761 0.436283 + outer loop + vertex 0.858186 2.00838 2.46795 + vertex 0.858347 2.01323 2.46796 + vertex 0.856336 2.0109 2.47194 + endloop + endfacet + facet normal 0.890842 -0.0592996 0.450427 + outer loop + vertex 0.856157 2.00587 2.47163 + vertex 0.858186 2.00838 2.46795 + vertex 0.856336 2.0109 2.47194 + endloop + endfacet + facet normal 0.976249 -0.0477072 0.211336 + outer loop + vertex 0.856336 2.0109 2.47194 + vertex 0.855 2.01 2.47791 + vertex 0.856157 2.00587 2.47163 + endloop + endfacet + facet normal 0.97597 -0.00391654 0.217872 + outer loop + vertex 0.855 2.015 2.478 + vertex 0.855 2.01 2.47791 + vertex 0.856336 2.0109 2.47194 + endloop + endfacet + facet normal 0.890229 -0.00753442 0.455452 + outer loop + vertex 0.858347 2.01323 2.46796 + vertex 0.858323 2.01803 2.46809 + vertex 0.856404 2.01575 2.4718 + endloop + endfacet + facet normal 0.892413 0.000616214 0.451219 + outer loop + vertex 0.856336 2.0109 2.47194 + vertex 0.858347 2.01323 2.46796 + vertex 0.856404 2.01575 2.4718 + endloop + endfacet + facet normal 0.975475 -0.00721037 0.219992 + outer loop + vertex 0.856404 2.01575 2.4718 + vertex 0.855 2.015 2.478 + vertex 0.856336 2.0109 2.47194 + endloop + endfacet + facet normal 0.974946 0.0115461 0.22214 + outer loop + vertex 0.855 2.02 2.47774 + vertex 0.855 2.015 2.478 + vertex 0.856404 2.01575 2.4718 + endloop + endfacet + facet normal 0.871009 -0.00572515 0.491234 + outer loop + vertex 0.858323 2.01803 2.46809 + vertex 0.858298 2.02295 2.46819 + vertex 0.856351 2.02074 2.47161 + endloop + endfacet + facet normal 0.881216 0.0268708 0.47195 + outer loop + vertex 0.856404 2.01575 2.4718 + vertex 0.858323 2.01803 2.46809 + vertex 0.856351 2.02074 2.47161 + endloop + endfacet + facet normal 0.97589 0.0183533 0.217492 + outer loop + vertex 0.856351 2.02074 2.47161 + vertex 0.855 2.02 2.47774 + vertex 0.856404 2.01575 2.4718 + endloop + endfacet + facet normal 0.974801 0.0386665 0.2197 + outer loop + vertex 0.855 2.025 2.47686 + vertex 0.855 2.02 2.47774 + vertex 0.856351 2.02074 2.47161 + endloop + endfacet + facet normal 0.825377 -0.0947699 0.556571 + outer loop + vertex 0.858298 2.02295 2.46819 + vertex 0.858411 2.02879 2.46902 + vertex 0.856238 2.02633 2.47182 + endloop + endfacet + facet normal 0.869562 -0.000451685 0.493823 + outer loop + vertex 0.856351 2.02074 2.47161 + vertex 0.858298 2.02295 2.46819 + vertex 0.856238 2.02633 2.47182 + endloop + endfacet + facet normal 0.970416 0.0108143 0.241196 + outer loop + vertex 0.856238 2.02633 2.47182 + vertex 0.855 2.025 2.47686 + vertex 0.856351 2.02074 2.47161 + endloop + endfacet + facet normal 0.966464 0.0527782 0.25132 + outer loop + vertex 0.855 2.03 2.47581 + vertex 0.855 2.025 2.47686 + vertex 0.856238 2.02633 2.47182 + endloop + endfacet + facet normal -0.922073 0.247606 0.297442 + outer loop + vertex 0.854627 2.0299 2.48239 + vertex 0.855 2.02815 2.485 + vertex 0.855 2.03 2.48346 + endloop + endfacet + facet normal 0.435245 0.775536 0.457282 + outer loop + vertex 0.854627 2.0299 2.48239 + vertex 0.854203 2.0284 2.48533 + vertex 0.855 2.02815 2.485 + endloop + endfacet + facet normal 0.539034 -0.452956 0.710121 + outer loop + vertex 0.858411 2.02879 2.46902 + vertex 0.86 2.035 2.47177 + vertex 0.855745 2.035 2.475 + endloop + endfacet + facet normal 0.839449 -0.144535 0.523865 + outer loop + vertex 0.856238 2.02633 2.47182 + vertex 0.858411 2.02879 2.46902 + vertex 0.855745 2.035 2.475 + endloop + endfacet + facet normal 0.928947 -0.0798372 0.361501 + outer loop + vertex 0.855745 2.035 2.475 + vertex 0.855 2.03 2.47581 + vertex 0.856238 2.02633 2.47182 + endloop + endfacet + facet normal 0.890415 -0.0595567 0.451236 + outer loop + vertex 0.855 2.035 2.47647 + vertex 0.855 2.03 2.47581 + vertex 0.855745 2.035 2.475 + endloop + endfacet + facet normal -0.891716 0.358223 0.276622 + outer loop + vertex 0.854498 2.03142 2.48001 + vertex 0.854627 2.0299 2.48239 + vertex 0.855 2.03 2.48346 + endloop + endfacet + facet normal 0.919725 -0.306557 -0.245213 + outer loop + vertex 0.855465 2.03373 2.48074 + vertex 0.854627 2.0299 2.48239 + vertex 0.854498 2.03142 2.48001 + endloop + endfacet + facet normal 0.964996 -0.199934 0.169733 + outer loop + vertex 0.854203 2.0284 2.48533 + vertex 0.855063 2.03225 2.48497 + vertex 0.853718 2.02906 2.48886 + endloop + endfacet + facet normal 0.97603 -0.21544 0.0308358 + outer loop + vertex 0.854203 2.0284 2.48533 + vertex 0.854627 2.0299 2.48239 + vertex 0.855063 2.03225 2.48497 + endloop + endfacet + facet normal 0.978531 -0.205031 0.0209586 + outer loop + vertex 0.854627 2.0299 2.48239 + vertex 0.855465 2.03373 2.48074 + vertex 0.855063 2.03225 2.48497 + endloop + endfacet + facet normal 0.956605 -0.270061 0.109429 + outer loop + vertex 0.854618 2.0327 2.48999 + vertex 0.853718 2.02906 2.48886 + vertex 0.855063 2.03225 2.48497 + endloop + endfacet + facet normal 0.932262 -0.294981 0.209462 + outer loop + vertex 0.853321 2.03012 2.49213 + vertex 0.853718 2.02906 2.48886 + vertex 0.854618 2.0327 2.48999 + endloop + endfacet + facet normal 0.932238 -0.260209 0.251443 + outer loop + vertex 0.853688 2.03254 2.49327 + vertex 0.853321 2.03012 2.49213 + vertex 0.854618 2.0327 2.48999 + endloop + endfacet + facet normal 0.694748 -0.390618 0.603939 + outer loop + vertex 0.85222 2.03048 2.49362 + vertex 0.853321 2.03012 2.49213 + vertex 0.853688 2.03254 2.49327 + endloop + endfacet + facet normal 0.746716 -0.446652 0.492865 + outer loop + vertex 0.853688 2.03254 2.49327 + vertex 0.85283 2.0323 2.49435 + vertex 0.85222 2.03048 2.49362 + endloop + endfacet + facet normal 0.736725 -0.0960367 -0.669338 + outer loop + vertex 0.855 2.03532 2.48 + vertex 0.855465 2.03373 2.48074 + vertex 0.854498 2.03142 2.48001 + endloop + endfacet + facet normal 0.397343 -0.289348 -0.870859 + outer loop + vertex 0.855 2.03532 2.48 + vertex 0.858408 2.04 2.48 + vertex 0.855465 2.03373 2.48074 + endloop + endfacet + facet normal 0.846595 -0.350177 0.400815 + outer loop + vertex 0.858408 2.04 2.48 + vertex 0.856582 2.03768 2.48183 + vertex 0.855465 2.03373 2.48074 + endloop + endfacet + facet normal 0.962509 -0.271223 -0.00379557 + outer loop + vertex 0.855465 2.03373 2.48074 + vertex 0.856582 2.03768 2.48183 + vertex 0.855063 2.03225 2.48497 + endloop + endfacet + facet normal 0.971777 -0.194362 0.133691 + outer loop + vertex 0.856582 2.03768 2.48183 + vertex 0.855794 2.03687 2.48638 + vertex 0.855063 2.03225 2.48497 + endloop + endfacet + facet normal 0.977066 -0.186028 0.103615 + outer loop + vertex 0.855063 2.03225 2.48497 + vertex 0.855794 2.03687 2.48638 + vertex 0.854618 2.0327 2.48999 + endloop + endfacet + facet normal 0.969704 -0.0712789 0.233651 + outer loop + vertex 0.855794 2.03687 2.48638 + vertex 0.854643 2.03661 2.49108 + vertex 0.854618 2.0327 2.48999 + endloop + endfacet + facet normal 0.776201 0.151087 0.612115 + outer loop + vertex 0.85309 2.0347 2.49352 + vertex 0.854643 2.03661 2.49108 + vertex 0.85344 2.03802 2.49225 + endloop + endfacet + facet normal 0.778776 0.146293 0.610005 + outer loop + vertex 0.85309 2.0347 2.49352 + vertex 0.853688 2.03254 2.49327 + vertex 0.854643 2.03661 2.49108 + endloop + endfacet + facet normal 0.959979 -0.0808035 0.268164 + outer loop + vertex 0.853688 2.03254 2.49327 + vertex 0.854618 2.0327 2.48999 + vertex 0.854643 2.03661 2.49108 + endloop + endfacet + facet normal 0.761255 0.138741 0.633436 + outer loop + vertex 0.853688 2.03254 2.49327 + vertex 0.85309 2.0347 2.49352 + vertex 0.85283 2.0323 2.49435 + endloop + endfacet + facet normal 0.746427 -0.0649457 0.662291 + outer loop + vertex 0.858408 2.04 2.48 + vertex 0.858843 2.045 2.48 + vertex 0.856582 2.03768 2.48183 + endloop + endfacet + facet normal 0.869451 -0.150935 0.470398 + outer loop + vertex 0.858843 2.045 2.48 + vertex 0.857091 2.04227 2.48236 + vertex 0.856582 2.03768 2.48183 + endloop + endfacet + facet normal 0.98101 -0.125989 0.147469 + outer loop + vertex 0.856582 2.03768 2.48183 + vertex 0.857091 2.04227 2.48236 + vertex 0.855794 2.03687 2.48638 + endloop + endfacet + facet normal 0.963761 -0.034684 0.264501 + outer loop + vertex 0.857091 2.04227 2.48236 + vertex 0.855832 2.04142 2.48684 + vertex 0.855794 2.03687 2.48638 + endloop + endfacet + facet normal 0.971176 -0.0318882 0.236221 + outer loop + vertex 0.855794 2.03687 2.48638 + vertex 0.855832 2.04142 2.48684 + vertex 0.854643 2.03661 2.49108 + endloop + endfacet + facet normal 0.91913 0.106725 0.379224 + outer loop + vertex 0.855832 2.04142 2.48684 + vertex 0.854446 2.04109 2.49029 + vertex 0.854643 2.03661 2.49108 + endloop + endfacet + facet normal 0.772439 0.142197 0.618965 + outer loop + vertex 0.854446 2.04109 2.49029 + vertex 0.85344 2.03802 2.49225 + vertex 0.854643 2.03661 2.49108 + endloop + endfacet + facet normal 0.44846 0.372284 0.812581 + outer loop + vertex 0.853047 2.04074 2.49123 + vertex 0.85344 2.03802 2.49225 + vertex 0.854446 2.04109 2.49029 + endloop + endfacet + facet normal 0.830967 -0.0543451 0.553661 + outer loop + vertex 0.858843 2.045 2.48 + vertex 0.85917 2.05 2.48 + vertex 0.857091 2.04227 2.48236 + endloop + endfacet + facet normal 0.730382 0.0121553 0.682931 + outer loop + vertex 0.85917 2.05 2.48 + vertex 0.856977 2.0466 2.48241 + vertex 0.857091 2.04227 2.48236 + endloop + endfacet + facet normal 0.961294 0.0225544 0.274599 + outer loop + vertex 0.857091 2.04227 2.48236 + vertex 0.856977 2.0466 2.48241 + vertex 0.855832 2.04142 2.48684 + endloop + endfacet + facet normal 0.90616 0.140989 0.398743 + outer loop + vertex 0.856977 2.0466 2.48241 + vertex 0.855141 2.04592 2.48682 + vertex 0.855832 2.04142 2.48684 + endloop + endfacet + facet normal 0.551788 0.483612 0.679448 + outer loop + vertex 0.85365 2.04373 2.48959 + vertex 0.855141 2.04592 2.48682 + vertex 0.853225 2.04702 2.48759 + endloop + endfacet + facet normal 0.661228 0.372996 0.650885 + outer loop + vertex 0.85365 2.04373 2.48959 + vertex 0.854446 2.04109 2.49029 + vertex 0.855141 2.04592 2.48682 + endloop + endfacet + facet normal 0.913808 0.142083 0.380482 + outer loop + vertex 0.854446 2.04109 2.49029 + vertex 0.855832 2.04142 2.48684 + vertex 0.855141 2.04592 2.48682 + endloop + endfacet + facet normal 0.45551 0.354782 0.816481 + outer loop + vertex 0.854446 2.04109 2.49029 + vertex 0.85365 2.04373 2.48959 + vertex 0.853047 2.04074 2.49123 + endloop + endfacet + facet normal 0.997572 -0.0287185 -0.0634423 + outer loop + vertex 0.858852 2.05 2.475 + vertex 0.858996 2.055 2.475 + vertex 0.85917 2.05 2.48 + endloop + endfacet + facet normal -0.223148 0.685382 0.69315 + outer loop + vertex 0.858996 2.055 2.475 + vertex 0.85819 2.05172 2.47798 + vertex 0.85917 2.05 2.48 + endloop + endfacet + facet normal -0.266106 0.665678 0.69718 + outer loop + vertex 0.85917 2.05 2.48 + vertex 0.85819 2.05172 2.47798 + vertex 0.856977 2.0466 2.48241 + endloop + endfacet + facet normal 0.949781 0.0428074 0.309972 + outer loop + vertex 0.85819 2.05172 2.47798 + vertex 0.85668 2.05102 2.4827 + vertex 0.856977 2.0466 2.48241 + endloop + endfacet + facet normal 0.920792 0.035555 0.38843 + outer loop + vertex 0.856977 2.0466 2.48241 + vertex 0.85668 2.05102 2.4827 + vertex 0.855141 2.04592 2.48682 + endloop + endfacet + facet normal 0.764543 0.248998 0.594536 + outer loop + vertex 0.85668 2.05102 2.4827 + vertex 0.854498 2.0502 2.48585 + vertex 0.855141 2.04592 2.48682 + endloop + endfacet + facet normal 0.485718 0.2612 0.834178 + outer loop + vertex 0.854498 2.0502 2.48585 + vertex 0.853225 2.04702 2.48759 + vertex 0.855141 2.04592 2.48682 + endloop + endfacet + facet normal 0.0629053 0.459047 0.886182 + outer loop + vertex 0.852935 2.05008 2.48602 + vertex 0.853225 2.04702 2.48759 + vertex 0.854498 2.0502 2.48585 + endloop + endfacet + facet normal 0.969081 -0.201503 0.142402 + outer loop + vertex 0.86 2.05832 2.475 + vertex 0.858747 2.05482 2.47857 + vertex 0.85819 2.05172 2.47798 + endloop + endfacet + facet normal 0.955495 -0.288964 -0.0594033 + outer loop + vertex 0.858996 2.055 2.475 + vertex 0.86 2.05832 2.475 + vertex 0.85819 2.05172 2.47798 + endloop + endfacet + facet normal 0.935672 -0.289731 0.20143 + outer loop + vertex 0.858747 2.05482 2.47857 + vertex 0.85793 2.05513 2.48281 + vertex 0.85668 2.05102 2.4827 + endloop + endfacet + facet normal 0.938287 -0.219769 0.267057 + outer loop + vertex 0.85819 2.05172 2.47798 + vertex 0.858747 2.05482 2.47857 + vertex 0.85668 2.05102 2.4827 + endloop + endfacet + facet normal 0.810684 0.0733581 0.58087 + outer loop + vertex 0.854498 2.0502 2.48585 + vertex 0.85668 2.05102 2.4827 + vertex 0.85511 2.05468 2.48443 + endloop + endfacet + facet normal 0.166558 0.277259 0.946248 + outer loop + vertex 0.854498 2.0502 2.48585 + vertex 0.85511 2.05468 2.48443 + vertex 0.853716 2.05196 2.48548 + endloop + endfacet + facet normal 0.512368 -0.17733 0.840258 + outer loop + vertex 0.85668 2.05102 2.4827 + vertex 0.85793 2.05513 2.48281 + vertex 0.85511 2.05468 2.48443 + endloop + endfacet + facet normal -0.12551 -0.220993 0.967166 + outer loop + vertex 0.856669 2.05887 2.4856 + vertex 0.85511 2.05468 2.48443 + vertex 0.857534 2.0567 2.48521 + endloop + endfacet + facet normal 0.42847 -0.722074 0.543159 + outer loop + vertex 0.85793 2.05513 2.48281 + vertex 0.857534 2.0567 2.48521 + vertex 0.85511 2.05468 2.48443 + endloop + endfacet + facet normal -0.210534 -0.250833 0.944859 + outer loop + vertex 0.857534 2.0567 2.48521 + vertex 0.858305 2.059 2.48599 + vertex 0.856669 2.05887 2.4856 + endloop + endfacet + facet normal 0.0871253 0.246008 0.965344 + outer loop + vertex 0.854498 2.0502 2.48585 + vertex 0.853716 2.05196 2.48548 + vertex 0.852935 2.05008 2.48602 + endloop + endfacet + facet normal -0.706863 0.0676784 0.704106 + outer loop + vertex 0.854466 2.0599 2.48329 + vertex 0.85511 2.05468 2.48443 + vertex 0.856669 2.05887 2.4856 + endloop + endfacet + facet normal -0.68988 0.124401 0.713155 + outer loop + vertex 0.856285 2.06345 2.48443 + vertex 0.854466 2.0599 2.48329 + vertex 0.856669 2.05887 2.4856 + endloop + endfacet + facet normal -0.589763 0.153198 0.792912 + outer loop + vertex 0.856669 2.05887 2.4856 + vertex 0.858075 2.06201 2.48604 + vertex 0.856285 2.06345 2.48443 + endloop + endfacet + facet normal -0.233516 -0.0315181 0.971842 + outer loop + vertex 0.858305 2.059 2.48599 + vertex 0.858075 2.06201 2.48604 + vertex 0.856669 2.05887 2.4856 + endloop + endfacet + facet normal -0.808301 0.292275 0.511102 + outer loop + vertex 0.855252 2.06776 2.481 + vertex 0.853574 2.06598 2.47936 + vertex 0.854373 2.06377 2.48188 + endloop + endfacet + facet normal -0.77058 0.200505 0.604984 + outer loop + vertex 0.854373 2.06377 2.48188 + vertex 0.854466 2.0599 2.48329 + vertex 0.856285 2.06345 2.48443 + endloop + endfacet + facet normal -0.744578 0.297515 0.597569 + outer loop + vertex 0.854373 2.06377 2.48188 + vertex 0.856285 2.06345 2.48443 + vertex 0.855252 2.06776 2.481 + endloop + endfacet + facet normal -0.762164 0.281617 0.582922 + outer loop + vertex 0.855252 2.06776 2.481 + vertex 0.856285 2.06345 2.48443 + vertex 0.857317 2.06797 2.48359 + endloop + endfacet + facet normal -0.699591 0.281026 0.65696 + outer loop + vertex 0.856285 2.06345 2.48443 + vertex 0.857967 2.06533 2.48541 + vertex 0.857317 2.06797 2.48359 + endloop + endfacet + facet normal -0.604321 0.127869 0.786413 + outer loop + vertex 0.858075 2.06201 2.48604 + vertex 0.857967 2.06533 2.48541 + vertex 0.856285 2.06345 2.48443 + endloop + endfacet + facet normal -0.848556 0.326691 0.416204 + outer loop + vertex 0.854841 2.07219 2.47742 + vertex 0.853331 2.0712 2.47512 + vertex 0.85375 2.06887 2.4778 + endloop + endfacet + facet normal -0.812275 0.31408 0.49149 + outer loop + vertex 0.85375 2.06887 2.4778 + vertex 0.853574 2.06598 2.47936 + vertex 0.855252 2.06776 2.481 + endloop + endfacet + facet normal -0.808457 0.322199 0.492529 + outer loop + vertex 0.85375 2.06887 2.4778 + vertex 0.855252 2.06776 2.481 + vertex 0.854841 2.07219 2.47742 + endloop + endfacet + facet normal -0.724174 0.390938 0.568102 + outer loop + vertex 0.854841 2.07219 2.47742 + vertex 0.855252 2.06776 2.481 + vertex 0.857165 2.07227 2.48033 + endloop + endfacet + facet normal -0.459402 0.485672 0.743688 + outer loop + vertex 0.858545 2.07048 2.48271 + vertex 0.857317 2.06797 2.48359 + vertex 0.858692 2.06799 2.48443 + endloop + endfacet + facet normal -0.532037 0.500081 0.683268 + outer loop + vertex 0.858545 2.07048 2.48271 + vertex 0.857165 2.07227 2.48033 + vertex 0.857317 2.06797 2.48359 + endloop + endfacet + facet normal -0.735248 0.393249 0.552057 + outer loop + vertex 0.857165 2.07227 2.48033 + vertex 0.855252 2.06776 2.481 + vertex 0.857317 2.06797 2.48359 + endloop + endfacet + facet normal -0.476846 0.416536 0.774025 + outer loop + vertex 0.858692 2.06799 2.48443 + vertex 0.857317 2.06797 2.48359 + vertex 0.857967 2.06533 2.48541 + endloop + endfacet + facet normal -0.851847 0.298326 0.430532 + outer loop + vertex 0.853903 2.07505 2.47358 + vertex 0.853331 2.0712 2.47512 + vertex 0.854841 2.07219 2.47742 + endloop + endfacet + facet normal -0.814834 0.351399 0.461047 + outer loop + vertex 0.856299 2.07755 2.47591 + vertex 0.853903 2.07505 2.47358 + vertex 0.854841 2.07219 2.47742 + endloop + endfacet + facet normal -0.324445 0.500778 0.802469 + outer loop + vertex 0.858828 2.07578 2.47881 + vertex 0.857165 2.07227 2.48033 + vertex 0.859308 2.07301 2.48073 + endloop + endfacet + facet normal -0.454794 0.526273 0.71847 + outer loop + vertex 0.858828 2.07578 2.47881 + vertex 0.856299 2.07755 2.47591 + vertex 0.857165 2.07227 2.48033 + endloop + endfacet + facet normal -0.733061 0.361584 0.576089 + outer loop + vertex 0.856299 2.07755 2.47591 + vertex 0.854841 2.07219 2.47742 + vertex 0.857165 2.07227 2.48033 + endloop + endfacet + facet normal -0.349794 0.640775 0.683411 + outer loop + vertex 0.859308 2.07301 2.48073 + vertex 0.857165 2.07227 2.48033 + vertex 0.858545 2.07048 2.48271 + endloop + endfacet + facet normal -0.857156 0.320945 0.402838 + outer loop + vertex 0.855207 2.08277 2.47096 + vertex 0.853708 2.08097 2.46921 + vertex 0.854225 2.07886 2.47199 + endloop + endfacet + facet normal -0.804321 0.285371 0.521182 + outer loop + vertex 0.854225 2.07886 2.47199 + vertex 0.853903 2.07505 2.47358 + vertex 0.856299 2.07755 2.47591 + endloop + endfacet + facet normal -0.782103 0.33444 0.5258 + outer loop + vertex 0.854225 2.07886 2.47199 + vertex 0.856299 2.07755 2.47591 + vertex 0.855207 2.08277 2.47096 + endloop + endfacet + facet normal -0.82087 0.292769 0.490366 + outer loop + vertex 0.855207 2.08277 2.47096 + vertex 0.856299 2.07755 2.47591 + vertex 0.857548 2.08295 2.47478 + endloop + endfacet + facet normal -0.631536 0.296397 0.716457 + outer loop + vertex 0.856299 2.07755 2.47591 + vertex 0.859689 2.08 2.47788 + vertex 0.857548 2.08295 2.47478 + endloop + endfacet + facet normal -0.628322 0.286446 0.723298 + outer loop + vertex 0.858828 2.07578 2.47881 + vertex 0.859689 2.08 2.47788 + vertex 0.856299 2.07755 2.47591 + endloop + endfacet + facet normal -0.901898 0.338877 0.267849 + outer loop + vertex 0.855352 2.08802 2.46639 + vertex 0.854027 2.08591 2.4646 + vertex 0.854011 2.08377 2.46725 + endloop + endfacet + facet normal -0.858809 0.352804 0.371452 + outer loop + vertex 0.854011 2.08377 2.46725 + vertex 0.853708 2.08097 2.46921 + vertex 0.855207 2.08277 2.47096 + endloop + endfacet + facet normal -0.86149 0.346957 0.370749 + outer loop + vertex 0.854011 2.08377 2.46725 + vertex 0.855207 2.08277 2.47096 + vertex 0.855352 2.08802 2.46639 + endloop + endfacet + facet normal -0.874847 0.331789 0.35293 + outer loop + vertex 0.855352 2.08802 2.46639 + vertex 0.855207 2.08277 2.47096 + vertex 0.856993 2.08766 2.47079 + endloop + endfacet + facet normal -0.790741 0.237435 0.564229 + outer loop + vertex 0.858515 2.08613 2.4748 + vertex 0.857548 2.08295 2.47478 + vertex 0.859456 2.08389 2.47705 + endloop + endfacet + facet normal -0.864802 0.260788 0.429076 + outer loop + vertex 0.858515 2.08613 2.4748 + vertex 0.856993 2.08766 2.47079 + vertex 0.857548 2.08295 2.47478 + endloop + endfacet + facet normal -0.815357 0.314686 0.485969 + outer loop + vertex 0.856993 2.08766 2.47079 + vertex 0.855207 2.08277 2.47096 + vertex 0.857548 2.08295 2.47478 + endloop + endfacet + facet normal -0.780739 0.0853118 0.619006 + outer loop + vertex 0.859456 2.08389 2.47705 + vertex 0.857548 2.08295 2.47478 + vertex 0.859689 2.08 2.47788 + endloop + endfacet + facet normal -0.858896 0.116166 0.498801 + outer loop + vertex 0.855 2.0914 2.465 + vertex 0.854027 2.08591 2.4646 + vertex 0.855352 2.08802 2.46639 + endloop + endfacet + facet normal -0.476394 0.292044 0.829312 + outer loop + vertex 0.855 2.0914 2.465 + vertex 0.855352 2.08802 2.46639 + vertex 0.857207 2.095 2.465 + endloop + endfacet + facet normal -0.781064 0.315106 0.539117 + outer loop + vertex 0.857207 2.095 2.465 + vertex 0.855352 2.08802 2.46639 + vertex 0.856868 2.09253 2.46595 + endloop + endfacet + facet normal -0.87587 0.328917 0.353081 + outer loop + vertex 0.855352 2.08802 2.46639 + vertex 0.856993 2.08766 2.47079 + vertex 0.856868 2.09253 2.46595 + endloop + endfacet + facet normal -0.927761 0.251007 0.276142 + outer loop + vertex 0.856868 2.09253 2.46595 + vertex 0.856993 2.08766 2.47079 + vertex 0.857946 2.09266 2.46945 + endloop + endfacet + facet normal -0.855106 0.280163 0.436236 + outer loop + vertex 0.856993 2.08766 2.47079 + vertex 0.858978 2.08965 2.47341 + vertex 0.857946 2.09266 2.46945 + endloop + endfacet + facet normal -0.855229 0.283179 0.434042 + outer loop + vertex 0.858515 2.08613 2.4748 + vertex 0.858978 2.08965 2.47341 + vertex 0.856993 2.08766 2.47079 + endloop + endfacet + facet normal -0.861229 -0.386759 -0.329701 + outer loop + vertex 0.86 2.095 2.46027 + vertex 0.857858 2.1 2.46 + vertex 0.86 2.09523 2.46 + endloop + endfacet + facet normal -0.800501 -0.368461 -0.472689 + outer loop + vertex 0.86 2.095 2.46027 + vertex 0.857207 2.095 2.465 + vertex 0.857858 2.1 2.46 + endloop + endfacet + facet normal 0.937005 -0.300353 -0.178352 + outer loop + vertex 0.857207 2.095 2.465 + vertex 0.857519 2.09775 2.46201 + vertex 0.857858 2.1 2.46 + endloop + endfacet + facet normal 0.988435 -0.14803 -0.0329066 + outer loop + vertex 0.857207 2.095 2.465 + vertex 0.856868 2.09253 2.46595 + vertex 0.857519 2.09775 2.46201 + endloop + endfacet + facet normal -0.969746 0.212107 0.120848 + outer loop + vertex 0.857519 2.09775 2.46201 + vertex 0.856868 2.09253 2.46595 + vertex 0.85784 2.09716 2.46562 + endloop + endfacet + facet normal -0.860468 0.251632 0.443031 + outer loop + vertex 0.858845 2.096 2.4693 + vertex 0.857946 2.09266 2.46945 + vertex 0.859493 2.09347 2.472 + endloop + endfacet + facet normal -0.907825 0.259316 0.329559 + outer loop + vertex 0.858845 2.096 2.4693 + vertex 0.85784 2.09716 2.46562 + vertex 0.857946 2.09266 2.46945 + endloop + endfacet + facet normal -0.93537 0.216298 0.279818 + outer loop + vertex 0.85784 2.09716 2.46562 + vertex 0.856868 2.09253 2.46595 + vertex 0.857946 2.09266 2.46945 + endloop + endfacet + facet normal -0.857767 0.275928 0.433705 + outer loop + vertex 0.859493 2.09347 2.472 + vertex 0.857946 2.09266 2.46945 + vertex 0.858978 2.08965 2.47341 + endloop + endfacet + facet normal -0.990126 0.139806 -0.0102789 + outer loop + vertex 0.857858 2.1 2.46 + vertex 0.857519 2.09775 2.46201 + vertex 0.858564 2.105 2.46 + endloop + endfacet + facet normal -0.990329 0.127509 -0.0546727 + outer loop + vertex 0.858564 2.105 2.46 + vertex 0.857519 2.09775 2.46201 + vertex 0.858156 2.10242 2.46138 + endloop + endfacet + facet normal -0.929049 0.192218 0.3161 + outer loop + vertex 0.858446 2.10104 2.46504 + vertex 0.85784 2.09716 2.46562 + vertex 0.858932 2.09888 2.46779 + endloop + endfacet + facet normal -0.974517 0.173335 0.142378 + outer loop + vertex 0.858446 2.10104 2.46504 + vertex 0.858156 2.10242 2.46138 + vertex 0.85784 2.09716 2.46562 + endloop + endfacet + facet normal -0.982493 0.149091 0.11171 + outer loop + vertex 0.858156 2.10242 2.46138 + vertex 0.857519 2.09775 2.46201 + vertex 0.85784 2.09716 2.46562 + endloop + endfacet + facet normal -0.929139 0.193918 0.314795 + outer loop + vertex 0.858932 2.09888 2.46779 + vertex 0.85784 2.09716 2.46562 + vertex 0.858845 2.096 2.4693 + endloop + endfacet + facet normal -0.692382 -0.483036 -0.535988 + outer loop + vertex 0.86 2.105 2.45801 + vertex 0.858842 2.11 2.455 + vertex 0.86 2.10834 2.455 + endloop + endfacet + facet normal -0.713514 -0.475208 -0.514855 + outer loop + vertex 0.86 2.105 2.45801 + vertex 0.858564 2.105 2.46 + vertex 0.858842 2.11 2.455 + endloop + endfacet + facet normal -0.925522 0.292272 0.240801 + outer loop + vertex 0.858564 2.105 2.46 + vertex 0.858834 2.10819 2.45717 + vertex 0.858842 2.11 2.455 + endloop + endfacet + facet normal 0.946627 -0.255134 -0.196989 + outer loop + vertex 0.858564 2.105 2.46 + vertex 0.858156 2.10242 2.46138 + vertex 0.858834 2.10819 2.45717 + endloop + endfacet + facet normal -0.97743 0.186866 0.0985478 + outer loop + vertex 0.858834 2.10819 2.45717 + vertex 0.858156 2.10242 2.46138 + vertex 0.858905 2.10698 2.46017 + endloop + endfacet + facet normal -0.959355 0.208291 0.190401 + outer loop + vertex 0.858156 2.10242 2.46138 + vertex 0.859022 2.10455 2.46342 + vertex 0.858905 2.10698 2.46017 + endloop + endfacet + facet normal -0.958462 0.233523 0.16376 + outer loop + vertex 0.858446 2.10104 2.46504 + vertex 0.859022 2.10455 2.46342 + vertex 0.858156 2.10242 2.46138 + endloop + endfacet + facet normal -0.205053 0.0935157 -0.974273 + outer loop + vertex 0.86 2.11 2.45384 + vertex 0.859241 2.11133 2.45413 + vertex 0.86 2.115 2.45432 + endloop + endfacet + facet normal -0.686312 -0.243926 -0.685183 + outer loop + vertex 0.858842 2.11 2.455 + vertex 0.859241 2.11133 2.45413 + vertex 0.86 2.11 2.45384 + endloop + endfacet + facet normal -0.979979 0.157943 0.121228 + outer loop + vertex 0.86 2.115 2.45772 + vertex 0.858834 2.10819 2.45717 + vertex 0.86 2.11325 2.46 + endloop + endfacet + facet normal -0.985432 0.165525 0.0390506 + outer loop + vertex 0.86 2.115 2.45772 + vertex 0.859241 2.11133 2.45413 + vertex 0.858834 2.10819 2.45717 + endloop + endfacet + facet normal -0.758909 0.501033 0.41596 + outer loop + vertex 0.859241 2.11133 2.45413 + vertex 0.858842 2.11 2.455 + vertex 0.858834 2.10819 2.45717 + endloop + endfacet + facet normal -0.901224 0.168017 0.399458 + outer loop + vertex 0.86 2.11325 2.46 + vertex 0.858905 2.10698 2.46017 + vertex 0.859865 2.10844 2.46172 + endloop + endfacet + facet normal -0.980378 0.173654 0.0932944 + outer loop + vertex 0.858834 2.10819 2.45717 + vertex 0.858905 2.10698 2.46017 + vertex 0.86 2.11325 2.46 + endloop + endfacet + facet normal -0.910768 0.31421 0.267908 + outer loop + vertex 0.859865 2.10844 2.46172 + vertex 0.858905 2.10698 2.46017 + vertex 0.859022 2.10455 2.46342 + endloop + endfacet + facet normal -0.917701 0.207511 -0.338769 + outer loop + vertex 0.86 2.115 2.45432 + vertex 0.859241 2.11133 2.45413 + vertex 0.86 2.11611 2.455 + endloop + endfacet + facet normal -0.987506 0.145901 0.0595421 + outer loop + vertex 0.86 2.11611 2.455 + vertex 0.859241 2.11133 2.45413 + vertex 0.86 2.115 2.45772 + endloop + endfacet + facet normal -0.415617 -0.644269 -0.642013 + outer loop + vertex 0.865 0.908575 2.455 + vertex 0.862791 0.91 2.455 + vertex 0.865 0.91 2.45357 + endloop + endfacet + facet normal -0.525033 -0.81388 0.248878 + outer loop + vertex 0.865 0.908575 2.455 + vertex 0.865 0.91 2.45966 + vertex 0.862791 0.91 2.455 + endloop + endfacet + facet normal -0.83832 -0.373238 0.397383 + outer loop + vertex 0.865 0.910362 2.46 + vertex 0.862791 0.91 2.455 + vertex 0.865 0.91 2.45966 + endloop + endfacet + facet normal -0.823314 -0.409176 0.393355 + outer loop + vertex 0.865 0.910362 2.46 + vertex 0.862695 0.915 2.46 + vertex 0.862791 0.91 2.455 + endloop + endfacet + facet normal -0.958611 0.191914 -0.210319 + outer loop + vertex 0.862695 0.915 2.46 + vertex 0.863792 0.915 2.455 + vertex 0.862791 0.91 2.455 + endloop + endfacet + facet normal -0.846184 -0.420542 0.327289 + outer loop + vertex 0.864593 0.91171 2.46068 + vertex 0.862695 0.915 2.46 + vertex 0.865 0.910362 2.46 + endloop + endfacet + facet normal -0.868568 -0.466546 0.167107 + outer loop + vertex 0.862458 0.916169 2.46203 + vertex 0.862695 0.915 2.46 + vertex 0.864593 0.91171 2.46068 + endloop + endfacet + facet normal -0.834927 -0.480909 0.267624 + outer loop + vertex 0.864593 0.91171 2.46068 + vertex 0.86502 0.913028 2.46438 + vertex 0.862458 0.916169 2.46203 + endloop + endfacet + facet normal -0.933582 -0.34673 0.0905693 + outer loop + vertex 0.862695 0.915 2.46 + vertex 0.862458 0.916169 2.46203 + vertex 0.860838 0.92 2.46 + endloop + endfacet + facet normal -0.921182 -0.38913 0.00072739 + outer loop + vertex 0.860838 0.92 2.46 + vertex 0.862458 0.916169 2.46203 + vertex 0.861048 0.919507 2.46213 + endloop + endfacet + facet normal -0.833803 -0.490123 0.25407 + outer loop + vertex 0.863646 0.915975 2.46555 + vertex 0.862458 0.916169 2.46203 + vertex 0.86502 0.913028 2.46438 + endloop + endfacet + facet normal -0.888381 -0.364292 0.279411 + outer loop + vertex 0.863646 0.915975 2.46555 + vertex 0.862125 0.919917 2.46586 + vertex 0.862458 0.916169 2.46203 + endloop + endfacet + facet normal -0.877259 -0.378914 0.294688 + outer loop + vertex 0.862125 0.919917 2.46586 + vertex 0.861048 0.919507 2.46213 + vertex 0.862458 0.916169 2.46203 + endloop + endfacet + facet normal -0.859674 -0.359688 0.362746 + outer loop + vertex 0.863646 0.915975 2.46555 + vertex 0.864105 0.917245 2.4679 + vertex 0.862125 0.919917 2.46586 + endloop + endfacet + facet normal 0.429438 0.120316 -0.895046 + outer loop + vertex 0.859465 0.923215 2.45977 + vertex 0.86 0.922991 2.46 + vertex 0.860838 0.92 2.46 + endloop + endfacet + facet normal -0.910783 -0.377215 0.167879 + outer loop + vertex 0.859465 0.923215 2.45977 + vertex 0.860838 0.92 2.46 + vertex 0.860037 0.923207 2.46286 + endloop + endfacet + facet normal -0.962449 -0.269503 0.0325657 + outer loop + vertex 0.860037 0.923207 2.46286 + vertex 0.860838 0.92 2.46 + vertex 0.861048 0.919507 2.46213 + endloop + endfacet + facet normal -0.905317 -0.305812 0.294754 + outer loop + vertex 0.861048 0.919507 2.46213 + vertex 0.862125 0.919917 2.46586 + vertex 0.860037 0.923207 2.46286 + endloop + endfacet + facet normal -0.9052 -0.327049 0.271388 + outer loop + vertex 0.860037 0.923207 2.46286 + vertex 0.862125 0.919917 2.46586 + vertex 0.86095 0.923819 2.46664 + endloop + endfacet + facet normal -0.854171 -0.318974 0.410667 + outer loop + vertex 0.864312 0.919765 2.47029 + vertex 0.862125 0.919917 2.46586 + vertex 0.864105 0.917245 2.4679 + endloop + endfacet + facet normal -0.844306 -0.351248 0.404689 + outer loop + vertex 0.864312 0.919765 2.47029 + vertex 0.862539 0.924628 2.47081 + vertex 0.862125 0.919917 2.46586 + endloop + endfacet + facet normal -0.856394 -0.336467 0.391636 + outer loop + vertex 0.862539 0.924628 2.47081 + vertex 0.86095 0.923819 2.46664 + vertex 0.862125 0.919917 2.46586 + endloop + endfacet + facet normal -0.810998 -0.346299 0.47155 + outer loop + vertex 0.864312 0.919765 2.47029 + vertex 0.865289 0.922232 2.47378 + vertex 0.862539 0.924628 2.47081 + endloop + endfacet + facet normal -0.942233 -0.286261 0.173929 + outer loop + vertex 0.859465 0.923215 2.45977 + vertex 0.860037 0.923207 2.46286 + vertex 0.858888 0.925779 2.46087 + endloop + endfacet + facet normal -0.942864 -0.269119 0.196425 + outer loop + vertex 0.858944 0.927371 2.46332 + vertex 0.858888 0.925779 2.46087 + vertex 0.860037 0.923207 2.46286 + endloop + endfacet + facet normal -0.929043 -0.271557 0.251268 + outer loop + vertex 0.858944 0.927371 2.46332 + vertex 0.860037 0.923207 2.46286 + vertex 0.859962 0.927814 2.46756 + endloop + endfacet + facet normal -0.918884 -0.289028 0.268542 + outer loop + vertex 0.859962 0.927814 2.46756 + vertex 0.860037 0.923207 2.46286 + vertex 0.86095 0.923819 2.46664 + endloop + endfacet + facet normal -0.868865 -0.304644 0.390213 + outer loop + vertex 0.86095 0.923819 2.46664 + vertex 0.862539 0.924628 2.47081 + vertex 0.859962 0.927814 2.46756 + endloop + endfacet + facet normal -0.870187 -0.349635 0.347175 + outer loop + vertex 0.859962 0.927814 2.46756 + vertex 0.862539 0.924628 2.47081 + vertex 0.861235 0.928682 2.47163 + endloop + endfacet + facet normal -0.808073 -0.296553 0.508994 + outer loop + vertex 0.865183 0.925541 2.47554 + vertex 0.862539 0.924628 2.47081 + vertex 0.865289 0.922232 2.47378 + endloop + endfacet + facet normal -0.784475 -0.356591 0.507387 + outer loop + vertex 0.865183 0.925541 2.47554 + vertex 0.863105 0.929652 2.47522 + vertex 0.862539 0.924628 2.47081 + endloop + endfacet + facet normal -0.78678 -0.354489 0.505286 + outer loop + vertex 0.863105 0.929652 2.47522 + vertex 0.861235 0.928682 2.47163 + vertex 0.862539 0.924628 2.47081 + endloop + endfacet + facet normal -0.717251 -0.313571 0.622274 + outer loop + vertex 0.865183 0.925541 2.47554 + vertex 0.866186 0.928341 2.47811 + vertex 0.863105 0.929652 2.47522 + endloop + endfacet + facet normal -0.924512 -0.286215 0.251711 + outer loop + vertex 0.858944 0.927371 2.46332 + vertex 0.859962 0.927814 2.46756 + vertex 0.858474 0.930405 2.46504 + endloop + endfacet + facet normal -0.923907 -0.301271 0.235863 + outer loop + vertex 0.858719 0.932144 2.46822 + vertex 0.858474 0.930405 2.46504 + vertex 0.859962 0.927814 2.46756 + endloop + endfacet + facet normal -0.887561 -0.307237 0.34328 + outer loop + vertex 0.858719 0.932144 2.46822 + vertex 0.859962 0.927814 2.46756 + vertex 0.860225 0.932914 2.47281 + endloop + endfacet + facet normal -0.88735 -0.307534 0.343559 + outer loop + vertex 0.860225 0.932914 2.47281 + vertex 0.859962 0.927814 2.46756 + vertex 0.861235 0.928682 2.47163 + endloop + endfacet + facet normal -0.797467 -0.330959 0.504493 + outer loop + vertex 0.861235 0.928682 2.47163 + vertex 0.863105 0.929652 2.47522 + vertex 0.860225 0.932914 2.47281 + endloop + endfacet + facet normal -0.796781 -0.328247 0.50734 + outer loop + vertex 0.860225 0.932914 2.47281 + vertex 0.863105 0.929652 2.47522 + vertex 0.862426 0.935014 2.47762 + endloop + endfacet + facet normal -0.405586 -0.416096 0.813857 + outer loop + vertex 0.863105 0.929652 2.47522 + vertex 0.865368 0.93328 2.4782 + vertex 0.862426 0.935014 2.47762 + endloop + endfacet + facet normal -0.707268 -0.13012 0.694867 + outer loop + vertex 0.866186 0.928341 2.47811 + vertex 0.865368 0.93328 2.4782 + vertex 0.863105 0.929652 2.47522 + endloop + endfacet + facet normal -0.872036 -0.347262 0.344908 + outer loop + vertex 0.858719 0.932144 2.46822 + vertex 0.860225 0.932914 2.47281 + vertex 0.858315 0.935174 2.47025 + endloop + endfacet + facet normal -0.872351 -0.336105 0.355019 + outer loop + vertex 0.858868 0.937163 2.47349 + vertex 0.858315 0.935174 2.47025 + vertex 0.860225 0.932914 2.47281 + endloop + endfacet + facet normal -0.790428 -0.335463 0.512532 + outer loop + vertex 0.858868 0.937163 2.47349 + vertex 0.860225 0.932914 2.47281 + vertex 0.860596 0.938654 2.47713 + endloop + endfacet + facet normal -0.794895 -0.331763 0.50801 + outer loop + vertex 0.860596 0.938654 2.47713 + vertex 0.860225 0.932914 2.47281 + vertex 0.862426 0.935014 2.47762 + endloop + endfacet + facet normal -0.415889 -0.439494 0.796167 + outer loop + vertex 0.863775 0.937211 2.47954 + vertex 0.862426 0.935014 2.47762 + vertex 0.865368 0.93328 2.4782 + endloop + endfacet + facet normal -0.471509 -0.397507 0.787189 + outer loop + vertex 0.863775 0.937211 2.47954 + vertex 0.862537 0.939231 2.47982 + vertex 0.862426 0.935014 2.47762 + endloop + endfacet + facet normal -0.743447 -0.293441 0.600982 + outer loop + vertex 0.862537 0.939231 2.47982 + vertex 0.860596 0.938654 2.47713 + vertex 0.862426 0.935014 2.47762 + endloop + endfacet + facet normal -0.161072 -0.230906 0.959551 + outer loop + vertex 0.863775 0.937211 2.47954 + vertex 0.86381 0.940081 2.48024 + vertex 0.862537 0.939231 2.47982 + endloop + endfacet + facet normal -0.818553 -0.278344 0.50249 + outer loop + vertex 0.858868 0.937163 2.47349 + vertex 0.860596 0.938654 2.47713 + vertex 0.8588 0.940545 2.47526 + endloop + endfacet + facet normal -0.786045 -0.151309 0.599365 + outer loop + vertex 0.86023 0.943804 2.47795 + vertex 0.8588 0.940545 2.47526 + vertex 0.860596 0.938654 2.47713 + endloop + endfacet + facet normal -0.711452 -0.159541 0.684385 + outer loop + vertex 0.86023 0.943804 2.47795 + vertex 0.860596 0.938654 2.47713 + vertex 0.862071 0.942766 2.47963 + endloop + endfacet + facet normal -0.800472 -0.0733703 0.594862 + outer loop + vertex 0.862071 0.942766 2.47963 + vertex 0.860596 0.938654 2.47713 + vertex 0.862537 0.939231 2.47982 + endloop + endfacet + facet normal -0.605456 -0.036829 0.795026 + outer loop + vertex 0.862537 0.939231 2.47982 + vertex 0.863249 0.942033 2.48049 + vertex 0.862071 0.942766 2.47963 + endloop + endfacet + facet normal -0.195476 -0.181452 0.963776 + outer loop + vertex 0.86381 0.940081 2.48024 + vertex 0.863249 0.942033 2.48049 + vertex 0.862537 0.939231 2.47982 + endloop + endfacet + facet normal 0.969474 0.118681 -0.214557 + outer loop + vertex 0.865 0.948644 2.465 + vertex 0.864834 0.95 2.465 + vertex 0.865 0.95 2.46575 + endloop + endfacet + facet normal -0.271458 0.175628 0.94629 + outer loop + vertex 0.862071 0.942766 2.47963 + vertex 0.863458 0.944805 2.47965 + vertex 0.862504 0.94788 2.4788 + endloop + endfacet + facet normal -0.605386 0.176511 0.776113 + outer loop + vertex 0.862071 0.942766 2.47963 + vertex 0.862504 0.94788 2.4788 + vertex 0.86023 0.943804 2.47795 + endloop + endfacet + facet normal -0.0473511 -0.177884 0.982912 + outer loop + vertex 0.86023 0.943804 2.47795 + vertex 0.862504 0.94788 2.4788 + vertex 0.859924 0.949069 2.47889 + endloop + endfacet + facet normal -0.440573 0.291628 0.849028 + outer loop + vertex 0.863458 0.944805 2.47965 + vertex 0.862071 0.942766 2.47963 + vertex 0.863249 0.942033 2.48049 + endloop + endfacet + facet normal 0.838672 0.324535 -0.437387 + outer loop + vertex 0.865 0.952992 2.47 + vertex 0.864223 0.955 2.47 + vertex 0.865 0.955 2.47149 + endloop + endfacet + facet normal 0.215289 -0.355258 0.909639 + outer loop + vertex 0.860368 0.953412 2.48048 + vertex 0.858782 0.951904 2.48027 + vertex 0.859924 0.949069 2.47889 + endloop + endfacet + facet normal 0.638104 -0.321469 0.699629 + outer loop + vertex 0.860368 0.953412 2.48048 + vertex 0.859924 0.949069 2.47889 + vertex 0.862337 0.953842 2.47889 + endloop + endfacet + facet normal 0.0290852 -0.0132511 0.999489 + outer loop + vertex 0.862337 0.953842 2.47889 + vertex 0.859924 0.949069 2.47889 + vertex 0.862504 0.94788 2.4788 + endloop + endfacet + facet normal 0.250402 -0.388935 0.886583 + outer loop + vertex 0.860368 0.953412 2.48048 + vertex 0.859273 0.955027 2.4815 + vertex 0.858782 0.951904 2.48027 + endloop + endfacet + facet normal 0.844464 0.0160252 0.535372 + outer loop + vertex 0.862337 0.953842 2.47889 + vertex 0.862946 0.958483 2.47779 + vertex 0.861102 0.958637 2.48069 + endloop + endfacet + facet normal 0.641333 -0.120008 0.757819 + outer loop + vertex 0.860368 0.953412 2.48048 + vertex 0.862337 0.953842 2.47889 + vertex 0.861102 0.958637 2.48069 + endloop + endfacet + facet normal 0.58155 -0.113499 0.805554 + outer loop + vertex 0.861102 0.958637 2.48069 + vertex 0.859273 0.955027 2.4815 + vertex 0.860368 0.953412 2.48048 + endloop + endfacet + facet normal 0.68537 -0.189084 0.703218 + outer loop + vertex 0.858803 0.958587 2.48292 + vertex 0.859273 0.955027 2.4815 + vertex 0.861102 0.958637 2.48069 + endloop + endfacet + facet normal 0.369053 0.0871608 0.925312 + outer loop + vertex 0.863755 0.960002 2.4755 + vertex 0.865 0.960012 2.475 + vertex 0.863822 0.965 2.475 + endloop + endfacet + facet normal 0.824293 0.0451149 0.564364 + outer loop + vertex 0.862519 0.963178 2.47705 + vertex 0.863755 0.960002 2.4755 + vertex 0.863822 0.965 2.475 + endloop + endfacet + facet normal 0.897966 0.146818 0.414852 + outer loop + vertex 0.862946 0.958483 2.47779 + vertex 0.863755 0.960002 2.4755 + vertex 0.862519 0.963178 2.47705 + endloop + endfacet + facet normal 0.837312 0.158296 0.523308 + outer loop + vertex 0.862946 0.958483 2.47779 + vertex 0.862519 0.963178 2.47705 + vertex 0.861102 0.958637 2.48069 + endloop + endfacet + facet normal 0.936756 -0.0118643 0.349781 + outer loop + vertex 0.861102 0.958637 2.48069 + vertex 0.862519 0.963178 2.47705 + vertex 0.86132 0.964149 2.48029 + endloop + endfacet + facet normal 0.747198 -0.238286 0.620415 + outer loop + vertex 0.858803 0.958587 2.48292 + vertex 0.859885 0.96337 2.48345 + vertex 0.858337 0.96183 2.48472 + endloop + endfacet + facet normal 0.679503 -0.231457 0.696207 + outer loop + vertex 0.858803 0.958587 2.48292 + vertex 0.861102 0.958637 2.48069 + vertex 0.859885 0.96337 2.48345 + endloop + endfacet + facet normal 0.910998 -0.00633821 0.412361 + outer loop + vertex 0.861102 0.958637 2.48069 + vertex 0.86132 0.964149 2.48029 + vertex 0.859885 0.96337 2.48345 + endloop + endfacet + facet normal 0.748939 -0.243435 0.616304 + outer loop + vertex 0.859885 0.96337 2.48345 + vertex 0.858668 0.964603 2.48542 + vertex 0.858337 0.96183 2.48472 + endloop + endfacet + facet normal 0.790765 0.111337 0.60191 + outer loop + vertex 0.863822 0.965 2.475 + vertex 0.863118 0.97 2.475 + vertex 0.862519 0.963178 2.47705 + endloop + endfacet + facet normal 0.849051 0.082176 0.52188 + outer loop + vertex 0.863118 0.97 2.475 + vertex 0.861594 0.967431 2.47788 + vertex 0.862519 0.963178 2.47705 + endloop + endfacet + facet normal 0.941391 0.144954 0.304585 + outer loop + vertex 0.862519 0.963178 2.47705 + vertex 0.861594 0.967431 2.47788 + vertex 0.86132 0.964149 2.48029 + endloop + endfacet + facet normal 0.95157 0.12628 0.2803 + outer loop + vertex 0.861594 0.967431 2.47788 + vertex 0.860525 0.968092 2.48121 + vertex 0.86132 0.964149 2.48029 + endloop + endfacet + facet normal 0.899729 0.0811908 0.428831 + outer loop + vertex 0.86132 0.964149 2.48029 + vertex 0.860525 0.968092 2.48121 + vertex 0.859885 0.96337 2.48345 + endloop + endfacet + facet normal 0.926845 0.0505838 0.37202 + outer loop + vertex 0.860525 0.968092 2.48121 + vertex 0.859275 0.967615 2.48439 + vertex 0.859885 0.96337 2.48345 + endloop + endfacet + facet normal 0.852056 0.00625836 0.523414 + outer loop + vertex 0.859275 0.967615 2.48439 + vertex 0.858668 0.964603 2.48542 + vertex 0.859885 0.96337 2.48345 + endloop + endfacet + facet normal 0.638194 0.129402 0.758923 + outer loop + vertex 0.858085 0.966418 2.4856 + vertex 0.858668 0.964603 2.48542 + vertex 0.859275 0.967615 2.48439 + endloop + endfacet + facet normal 0.955916 -0.0803131 0.282443 + outer loop + vertex 0.860732 0.972845 2.46806 + vertex 0.86 0.97095 2.47 + vertex 0.86 0.97 2.46973 + endloop + endfacet + facet normal 0.622291 0.270724 0.734481 + outer loop + vertex 0.860732 0.972845 2.46806 + vertex 0.86 0.97 2.46973 + vertex 0.863264 0.973432 2.4657 + endloop + endfacet + facet normal 0.0210548 0.752682 0.658048 + outer loop + vertex 0.863264 0.973432 2.4657 + vertex 0.86 0.97 2.46973 + vertex 0.865 0.97 2.46957 + endloop + endfacet + facet normal 0.962943 -0.130532 0.236014 + outer loop + vertex 0.86 0.97095 2.47 + vertex 0.860732 0.972845 2.46806 + vertex 0.86 0.975 2.47224 + endloop + endfacet + facet normal 0.725506 0.508685 -0.463552 + outer loop + vertex 0.86 0.97 2.47012 + vertex 0.86 0.974447 2.475 + vertex 0.863118 0.97 2.475 + endloop + endfacet + facet normal -0.781268 -0.547782 0.299259 + outer loop + vertex 0.860146 0.973909 2.4744 + vertex 0.863118 0.97 2.475 + vertex 0.86 0.974447 2.475 + endloop + endfacet + facet normal 0.776104 0.61293 0.148251 + outer loop + vertex 0.860146 0.973909 2.4744 + vertex 0.86048 0.972726 2.47754 + vertex 0.863118 0.97 2.475 + endloop + endfacet + facet normal 0.779685 0.2026 0.59249 + outer loop + vertex 0.86048 0.972726 2.47754 + vertex 0.861594 0.967431 2.47788 + vertex 0.863118 0.97 2.475 + endloop + endfacet + facet normal 0.941535 0.214907 0.259473 + outer loop + vertex 0.861594 0.967431 2.47788 + vertex 0.86048 0.972726 2.47754 + vertex 0.860525 0.968092 2.48121 + endloop + endfacet + facet normal 0.960164 0.179298 0.21433 + outer loop + vertex 0.86048 0.972726 2.47754 + vertex 0.85942 0.972761 2.48226 + vertex 0.860525 0.968092 2.48121 + endloop + endfacet + facet normal 0.81554 0.0686098 0.57462 + outer loop + vertex 0.857916 0.96955 2.48478 + vertex 0.85942 0.972761 2.48226 + vertex 0.857627 0.974429 2.48461 + endloop + endfacet + facet normal 0.616069 0.286672 0.733674 + outer loop + vertex 0.857916 0.96955 2.48478 + vertex 0.859275 0.967615 2.48439 + vertex 0.85942 0.972761 2.48226 + endloop + endfacet + facet normal 0.915665 0.131631 0.379777 + outer loop + vertex 0.859275 0.967615 2.48439 + vertex 0.860525 0.968092 2.48121 + vertex 0.85942 0.972761 2.48226 + endloop + endfacet + facet normal 0.562662 0.237575 0.791814 + outer loop + vertex 0.859275 0.967615 2.48439 + vertex 0.857916 0.96955 2.48478 + vertex 0.858085 0.966418 2.4856 + endloop + endfacet + facet normal 0.74329 0.0427943 0.667599 + outer loop + vertex 0.863264 0.973432 2.4657 + vertex 0.86398 0.97918 2.46453 + vertex 0.861397 0.976672 2.46757 + endloop + endfacet + facet normal 0.685025 -0.02568 0.728067 + outer loop + vertex 0.860732 0.972845 2.46806 + vertex 0.863264 0.973432 2.4657 + vertex 0.861397 0.976672 2.46757 + endloop + endfacet + facet normal 0.961422 -0.136498 0.238823 + outer loop + vertex 0.861397 0.976672 2.46757 + vertex 0.86 0.975 2.47224 + vertex 0.860732 0.972845 2.46806 + endloop + endfacet + facet normal 0.95675 0.0122103 0.290656 + outer loop + vertex 0.86 0.98 2.47203 + vertex 0.86 0.975 2.47224 + vertex 0.861397 0.976672 2.46757 + endloop + endfacet + facet normal 0.99486 0.054532 -0.0853194 + outer loop + vertex 0.86 0.98 2.47659 + vertex 0.86048 0.972726 2.47754 + vertex 0.860146 0.973909 2.4744 + endloop + endfacet + facet normal 0.980806 0.0874755 0.174261 + outer loop + vertex 0.859596 0.978567 2.47959 + vertex 0.86048 0.972726 2.47754 + vertex 0.86 0.98 2.47659 + endloop + endfacet + facet normal 0.973342 0.0709847 0.218098 + outer loop + vertex 0.86048 0.972726 2.47754 + vertex 0.859596 0.978567 2.47959 + vertex 0.85942 0.972761 2.48226 + endloop + endfacet + facet normal 0.979721 0.0585848 0.191609 + outer loop + vertex 0.859596 0.978567 2.47959 + vertex 0.859081 0.977542 2.48253 + vertex 0.85942 0.972761 2.48226 + endloop + endfacet + facet normal 0.802112 0.0230873 0.596728 + outer loop + vertex 0.859081 0.977542 2.48253 + vertex 0.857627 0.974429 2.48461 + vertex 0.85942 0.972761 2.48226 + endloop + endfacet + facet normal 0.855836 -0.0570578 0.51409 + outer loop + vertex 0.858263 0.97992 2.48416 + vertex 0.857627 0.974429 2.48461 + vertex 0.859081 0.977542 2.48253 + endloop + endfacet + facet normal 0.811546 -0.00805499 0.584233 + outer loop + vertex 0.86398 0.97918 2.46453 + vertex 0.864159 0.984941 2.46436 + vertex 0.861732 0.981988 2.46769 + endloop + endfacet + facet normal 0.785609 -0.0639431 0.615411 + outer loop + vertex 0.861397 0.976672 2.46757 + vertex 0.86398 0.97918 2.46453 + vertex 0.861732 0.981988 2.46769 + endloop + endfacet + facet normal 0.936742 -0.067055 0.343538 + outer loop + vertex 0.861732 0.981988 2.46769 + vertex 0.86 0.98 2.47203 + vertex 0.861397 0.976672 2.46757 + endloop + endfacet + facet normal 0.937934 -0.0828466 0.336774 + outer loop + vertex 0.86 0.985 2.47326 + vertex 0.86 0.98 2.47203 + vertex 0.861732 0.981988 2.46769 + endloop + endfacet + facet normal 0.991968 -0.0859735 0.0927778 + outer loop + vertex 0.86 0.98 2.47659 + vertex 0.86 0.98368 2.48 + vertex 0.859596 0.978567 2.47959 + endloop + endfacet + facet normal -0.275313 -0.0559984 0.959722 + outer loop + vertex 0.859287 0.982532 2.47973 + vertex 0.859596 0.978567 2.47959 + vertex 0.86 0.98368 2.48 + endloop + endfacet + facet normal 0.989365 0.0724699 0.126111 + outer loop + vertex 0.859287 0.982532 2.47973 + vertex 0.859152 0.981238 2.48153 + vertex 0.859596 0.978567 2.47959 + endloop + endfacet + facet normal 0.982769 0.030378 0.182327 + outer loop + vertex 0.859152 0.981238 2.48153 + vertex 0.859081 0.977542 2.48253 + vertex 0.859596 0.978567 2.47959 + endloop + endfacet + facet normal 0.931687 0.0779046 0.35481 + outer loop + vertex 0.859152 0.981238 2.48153 + vertex 0.858263 0.97992 2.48416 + vertex 0.859081 0.977542 2.48253 + endloop + endfacet + facet normal 0.936137 0.0587538 0.346693 + outer loop + vertex 0.858534 0.983584 2.4828 + vertex 0.858263 0.97992 2.48416 + vertex 0.859152 0.981238 2.48153 + endloop + endfacet + facet normal 0.854212 0.000607399 0.519925 + outer loop + vertex 0.864159 0.984941 2.46436 + vertex 0.864192 0.990397 2.4643 + vertex 0.86182 0.98816 2.4682 + endloop + endfacet + facet normal 0.830428 -0.0574962 0.554151 + outer loop + vertex 0.861732 0.981988 2.46769 + vertex 0.864159 0.984941 2.46436 + vertex 0.86182 0.98816 2.4682 + endloop + endfacet + facet normal 0.947793 -0.0395814 0.316422 + outer loop + vertex 0.86182 0.98816 2.4682 + vertex 0.86 0.985 2.47326 + vertex 0.861732 0.981988 2.46769 + endloop + endfacet + facet normal 0.948841 -0.0468433 0.312261 + outer loop + vertex 0.86 0.99 2.47401 + vertex 0.86 0.985 2.47326 + vertex 0.86182 0.98816 2.4682 + endloop + endfacet + facet normal 0.979725 0.120672 0.159928 + outer loop + vertex 0.859287 0.982532 2.47973 + vertex 0.858898 0.984216 2.48084 + vertex 0.859152 0.981238 2.48153 + endloop + endfacet + facet normal 0.965767 0.133973 0.222138 + outer loop + vertex 0.859152 0.981238 2.48153 + vertex 0.858898 0.984216 2.48084 + vertex 0.858534 0.983584 2.4828 + endloop + endfacet + facet normal 0.87396 0.0211768 0.485535 + outer loop + vertex 0.864192 0.990397 2.4643 + vertex 0.864121 0.99537 2.46422 + vertex 0.862704 0.992791 2.46688 + endloop + endfacet + facet normal 0.858594 -0.017205 0.512367 + outer loop + vertex 0.86182 0.98816 2.4682 + vertex 0.864192 0.990397 2.4643 + vertex 0.862704 0.992791 2.46688 + endloop + endfacet + facet normal 0.982488 -0.0500203 0.179484 + outer loop + vertex 0.86 0.99 2.47401 + vertex 0.860818 0.99345 2.4705 + vertex 0.86 0.993552 2.475 + endloop + endfacet + facet normal 0.957761 0.0595746 0.281327 + outer loop + vertex 0.86 0.99 2.47401 + vertex 0.86182 0.98816 2.4682 + vertex 0.860818 0.99345 2.4705 + endloop + endfacet + facet normal 0.883544 -0.0349478 0.467043 + outer loop + vertex 0.86182 0.98816 2.4682 + vertex 0.862704 0.992791 2.46688 + vertex 0.860818 0.99345 2.4705 + endloop + endfacet + facet normal 0.982089 -0.0570651 0.17957 + outer loop + vertex 0.860818 0.99345 2.4705 + vertex 0.86 0.995 2.47546 + vertex 0.86 0.993552 2.475 + endloop + endfacet + facet normal 0.884741 0.05368 0.462982 + outer loop + vertex 0.864121 0.99537 2.46422 + vertex 0.863823 1.00026 2.46422 + vertex 0.86239 0.996992 2.46733 + endloop + endfacet + facet normal 0.877281 0.0134211 0.47979 + outer loop + vertex 0.862704 0.992791 2.46688 + vertex 0.864121 0.99537 2.46422 + vertex 0.86239 0.996992 2.46733 + endloop + endfacet + facet normal 0.887809 0.0163701 0.45992 + outer loop + vertex 0.862704 0.992791 2.46688 + vertex 0.86239 0.996992 2.46733 + vertex 0.860818 0.99345 2.4705 + endloop + endfacet + facet normal 0.854763 0.0784607 0.513053 + outer loop + vertex 0.86239 0.996992 2.46733 + vertex 0.860468 0.998349 2.47033 + vertex 0.860818 0.99345 2.4705 + endloop + endfacet + facet normal 0.987412 0.0751642 0.139167 + outer loop + vertex 0.860468 0.998349 2.47033 + vertex 0.86 0.995 2.47546 + vertex 0.860818 0.99345 2.4705 + endloop + endfacet + facet normal 0.773205 0.496461 0.394563 + outer loop + vertex 0.858313 0.999812 2.47271 + vertex 0.86 0.995 2.47546 + vertex 0.860468 0.998349 2.47033 + endloop + endfacet + facet normal 0.885375 0.0806848 0.457822 + outer loop + vertex 0.863823 1.00026 2.46422 + vertex 0.86348 1.00518 2.46401 + vertex 0.862086 1.00175 2.46731 + endloop + endfacet + facet normal 0.88239 0.0584264 0.466876 + outer loop + vertex 0.86239 0.996992 2.46733 + vertex 0.863823 1.00026 2.46422 + vertex 0.862086 1.00175 2.46731 + endloop + endfacet + facet normal 0.851705 0.056708 0.520944 + outer loop + vertex 0.86239 0.996992 2.46733 + vertex 0.862086 1.00175 2.46731 + vertex 0.860468 0.998349 2.47033 + endloop + endfacet + facet normal 0.797397 0.140845 0.586788 + outer loop + vertex 0.862086 1.00175 2.46731 + vertex 0.859955 1.00298 2.46991 + vertex 0.860468 0.998349 2.47033 + endloop + endfacet + facet normal 0.775634 0.140977 0.615237 + outer loop + vertex 0.859955 1.00298 2.46991 + vertex 0.858313 0.999812 2.47271 + vertex 0.860468 0.998349 2.47033 + endloop + endfacet + facet normal 0.772396 0.145351 0.618287 + outer loop + vertex 0.857359 1.00364 2.473 + vertex 0.858313 0.999812 2.47271 + vertex 0.859955 1.00298 2.46991 + endloop + endfacet + facet normal 0.883534 0.104631 0.45653 + outer loop + vertex 0.86348 1.00518 2.46401 + vertex 0.863175 1.00995 2.46351 + vertex 0.861798 1.00665 2.46693 + endloop + endfacet + facet normal 0.881572 0.0879624 0.463782 + outer loop + vertex 0.862086 1.00175 2.46731 + vertex 0.86348 1.00518 2.46401 + vertex 0.861798 1.00665 2.46693 + endloop + endfacet + facet normal 0.791387 0.0935764 0.604111 + outer loop + vertex 0.862086 1.00175 2.46731 + vertex 0.861798 1.00665 2.46693 + vertex 0.859955 1.00298 2.46991 + endloop + endfacet + facet normal 0.801667 0.0790162 0.592525 + outer loop + vertex 0.861798 1.00665 2.46693 + vertex 0.859634 1.00775 2.46971 + vertex 0.859955 1.00298 2.46991 + endloop + endfacet + facet normal 0.771212 0.0786235 0.631704 + outer loop + vertex 0.859634 1.00775 2.46971 + vertex 0.857359 1.00364 2.473 + vertex 0.859955 1.00298 2.46991 + endloop + endfacet + facet normal 0.825607 -0.00566498 0.564217 + outer loop + vertex 0.857145 1.00847 2.47336 + vertex 0.857359 1.00364 2.473 + vertex 0.859634 1.00775 2.46971 + endloop + endfacet + facet normal 0.897388 0.136192 0.419697 + outer loop + vertex 0.863175 1.00995 2.46351 + vertex 0.863084 1.01386 2.46244 + vertex 0.861694 1.01243 2.46587 + endloop + endfacet + facet normal 0.886487 0.0987909 0.452086 + outer loop + vertex 0.861798 1.00665 2.46693 + vertex 0.863175 1.00995 2.46351 + vertex 0.861694 1.01243 2.46587 + endloop + endfacet + facet normal 0.805995 0.120709 0.579484 + outer loop + vertex 0.861798 1.00665 2.46693 + vertex 0.861694 1.01243 2.46587 + vertex 0.859634 1.00775 2.46971 + endloop + endfacet + facet normal 0.861571 0.0362871 0.506339 + outer loop + vertex 0.861694 1.01243 2.46587 + vertex 0.859446 1.01315 2.46965 + vertex 0.859634 1.00775 2.46971 + endloop + endfacet + facet normal 0.828896 0.0357834 0.558258 + outer loop + vertex 0.859446 1.01315 2.46965 + vertex 0.857145 1.00847 2.47336 + vertex 0.859634 1.00775 2.46971 + endloop + endfacet + facet normal 0.853172 -0.00525836 0.521603 + outer loop + vertex 0.857027 1.01428 2.47361 + vertex 0.857145 1.00847 2.47336 + vertex 0.859446 1.01315 2.46965 + endloop + endfacet + facet normal -0.493623 -0.108763 0.862848 + outer loop + vertex 0.865 1.017 2.445 + vertex 0.864339 1.02 2.445 + vertex 0.864401 1.01716 2.44468 + endloop + endfacet + facet normal 0.945015 0.199786 0.258905 + outer loop + vertex 0.863503 1.0161 2.45997 + vertex 0.863477 1.01896 2.45786 + vertex 0.862673 1.018 2.46153 + endloop + endfacet + facet normal 0.939111 0.159998 0.30409 + outer loop + vertex 0.863084 1.01386 2.46244 + vertex 0.863503 1.0161 2.45997 + vertex 0.862673 1.018 2.46153 + endloop + endfacet + facet normal 0.88267 0.182602 0.43307 + outer loop + vertex 0.863084 1.01386 2.46244 + vertex 0.862673 1.018 2.46153 + vertex 0.861694 1.01243 2.46587 + endloop + endfacet + facet normal 0.939476 0.0922393 0.329965 + outer loop + vertex 0.861694 1.01243 2.46587 + vertex 0.862673 1.018 2.46153 + vertex 0.861165 1.0181 2.46579 + endloop + endfacet + facet normal 0.863056 0.0873919 0.497491 + outer loop + vertex 0.861694 1.01243 2.46587 + vertex 0.861165 1.0181 2.46579 + vertex 0.859446 1.01315 2.46965 + endloop + endfacet + facet normal 0.908737 0.00913966 0.417268 + outer loop + vertex 0.861165 1.0181 2.46579 + vertex 0.859395 1.01879 2.46963 + vertex 0.859446 1.01315 2.46965 + endloop + endfacet + facet normal 0.854937 0.00888654 0.518655 + outer loop + vertex 0.859395 1.01879 2.46963 + vertex 0.857027 1.01428 2.47361 + vertex 0.859446 1.01315 2.46965 + endloop + endfacet + facet normal 0.871146 -0.0245597 0.49041 + outer loop + vertex 0.85757 1.02035 2.47295 + vertex 0.857027 1.01428 2.47361 + vertex 0.859395 1.01879 2.46963 + endloop + endfacet + facet normal 0.942719 -0.0172863 0.333138 + outer loop + vertex 0.864001 1.01967 2.44594 + vertex 0.864401 1.01716 2.44468 + vertex 0.864339 1.02 2.445 + endloop + endfacet + facet normal 0.919257 0.121962 0.374289 + outer loop + vertex 0.864001 1.01967 2.44594 + vertex 0.864339 1.02 2.445 + vertex 0.863397 1.02396 2.44602 + endloop + endfacet + facet normal 0.87005 0.0812632 0.486219 + outer loop + vertex 0.863397 1.02396 2.44602 + vertex 0.864339 1.02 2.445 + vertex 0.863872 1.025 2.445 + endloop + endfacet + facet normal 0.990037 0.139818 -0.0166701 + outer loop + vertex 0.863943 1.02048 2.44926 + vertex 0.864001 1.01967 2.44594 + vertex 0.863397 1.02396 2.44602 + endloop + endfacet + facet normal 0.985713 0.167831 0.0142149 + outer loop + vertex 0.863255 1.02443 2.45035 + vertex 0.863943 1.02048 2.44926 + vertex 0.863397 1.02396 2.44602 + endloop + endfacet + facet normal 0.986177 0.160806 0.0399544 + outer loop + vertex 0.863778 1.02033 2.45392 + vertex 0.863943 1.02048 2.44926 + vertex 0.863255 1.02443 2.45035 + endloop + endfacet + facet normal 0.976737 0.197521 0.0834924 + outer loop + vertex 0.86299 1.02331 2.45608 + vertex 0.863778 1.02033 2.45392 + vertex 0.863255 1.02443 2.45035 + endloop + endfacet + facet normal 0.977848 0.162851 0.131505 + outer loop + vertex 0.863477 1.01896 2.45786 + vertex 0.863778 1.02033 2.45392 + vertex 0.86299 1.02331 2.45608 + endloop + endfacet + facet normal 0.941772 0.211649 0.261286 + outer loop + vertex 0.863477 1.01896 2.45786 + vertex 0.86299 1.02331 2.45608 + vertex 0.862673 1.018 2.46153 + endloop + endfacet + facet normal 0.976485 0.123108 0.176978 + outer loop + vertex 0.862673 1.018 2.46153 + vertex 0.86299 1.02331 2.45608 + vertex 0.86207 1.0233 2.46117 + endloop + endfacet + facet normal 0.935918 0.128765 0.327838 + outer loop + vertex 0.862673 1.018 2.46153 + vertex 0.86207 1.0233 2.46117 + vertex 0.861165 1.0181 2.46579 + endloop + endfacet + facet normal 0.963694 0.0630609 0.259455 + outer loop + vertex 0.86207 1.0233 2.46117 + vertex 0.860861 1.02342 2.46563 + vertex 0.861165 1.0181 2.46579 + endloop + endfacet + facet normal 0.910591 0.0646407 0.408223 + outer loop + vertex 0.861165 1.0181 2.46579 + vertex 0.860861 1.02342 2.46563 + vertex 0.859395 1.01879 2.46963 + endloop + endfacet + facet normal 0.934666 0.0113793 0.355346 + outer loop + vertex 0.860861 1.02342 2.46563 + vertex 0.859379 1.02409 2.46951 + vertex 0.859395 1.01879 2.46963 + endloop + endfacet + facet normal 0.879028 0.0140949 0.476561 + outer loop + vertex 0.859379 1.02409 2.46951 + vertex 0.85757 1.02035 2.47295 + vertex 0.859395 1.01879 2.46963 + endloop + endfacet + facet normal 0.883406 0.00462813 0.468586 + outer loop + vertex 0.857638 1.02539 2.47278 + vertex 0.85757 1.02035 2.47295 + vertex 0.859379 1.02409 2.46951 + endloop + endfacet + facet normal 0.8486 0.119653 0.515326 + outer loop + vertex 0.863872 1.025 2.445 + vertex 0.863167 1.03 2.445 + vertex 0.863397 1.02396 2.44602 + endloop + endfacet + facet normal 0.944721 0.089411 0.315448 + outer loop + vertex 0.863167 1.03 2.445 + vertex 0.86265 1.02895 2.44685 + vertex 0.863397 1.02396 2.44602 + endloop + endfacet + facet normal 0.989257 0.14522 0.0167787 + outer loop + vertex 0.863397 1.02396 2.44602 + vertex 0.86265 1.02895 2.44685 + vertex 0.863255 1.02443 2.45035 + endloop + endfacet + facet normal 0.987158 0.156551 0.0317868 + outer loop + vertex 0.86265 1.02895 2.44685 + vertex 0.862553 1.02867 2.45122 + vertex 0.863255 1.02443 2.45035 + endloop + endfacet + facet normal 0.986241 0.14771 0.0742365 + outer loop + vertex 0.863255 1.02443 2.45035 + vertex 0.862553 1.02867 2.45122 + vertex 0.86299 1.02331 2.45608 + endloop + endfacet + facet normal 0.988635 0.136904 0.0621089 + outer loop + vertex 0.862553 1.02867 2.45122 + vertex 0.862264 1.02852 2.45616 + vertex 0.86299 1.02331 2.45608 + endloop + endfacet + facet normal 0.975162 0.133469 0.176761 + outer loop + vertex 0.86299 1.02331 2.45608 + vertex 0.862264 1.02852 2.45616 + vertex 0.86207 1.0233 2.46117 + endloop + endfacet + facet normal 0.98419 0.102268 0.144611 + outer loop + vertex 0.862264 1.02852 2.45616 + vertex 0.861568 1.02841 2.46097 + vertex 0.86207 1.0233 2.46117 + endloop + endfacet + facet normal 0.960647 0.104246 0.257469 + outer loop + vertex 0.86207 1.0233 2.46117 + vertex 0.861568 1.02841 2.46097 + vertex 0.860861 1.02342 2.46563 + endloop + endfacet + facet normal 0.971501 0.0728908 0.225552 + outer loop + vertex 0.861568 1.02841 2.46097 + vertex 0.860521 1.02845 2.46547 + vertex 0.860861 1.02342 2.46563 + endloop + endfacet + facet normal 0.935675 0.0742949 0.344952 + outer loop + vertex 0.860861 1.02342 2.46563 + vertex 0.860521 1.02845 2.46547 + vertex 0.859379 1.02409 2.46951 + endloop + endfacet + facet normal 0.945472 0.0502736 0.3218 + outer loop + vertex 0.860521 1.02845 2.46547 + vertex 0.859173 1.02888 2.46936 + vertex 0.859379 1.02409 2.46951 + endloop + endfacet + facet normal 0.889877 0.0518461 0.453245 + outer loop + vertex 0.859173 1.02888 2.46936 + vertex 0.857638 1.02539 2.47278 + vertex 0.859379 1.02409 2.46951 + endloop + endfacet + facet normal 0.891554 0.0482623 0.450335 + outer loop + vertex 0.857567 1.03003 2.47242 + vertex 0.857638 1.02539 2.47278 + vertex 0.859173 1.02888 2.46936 + endloop + endfacet + facet normal 0.948579 0.0739879 0.307773 + outer loop + vertex 0.863167 1.03 2.445 + vertex 0.862777 1.035 2.445 + vertex 0.86265 1.02895 2.44685 + endloop + endfacet + facet normal 0.942544 0.0792373 0.324551 + outer loop + vertex 0.862777 1.035 2.445 + vertex 0.86193 1.03276 2.44801 + vertex 0.86265 1.02895 2.44685 + endloop + endfacet + facet normal 0.983897 0.175674 0.0329292 + outer loop + vertex 0.86265 1.02895 2.44685 + vertex 0.86193 1.03276 2.44801 + vertex 0.862553 1.02867 2.45122 + endloop + endfacet + facet normal 0.985958 0.165798 0.0199568 + outer loop + vertex 0.86193 1.03276 2.44801 + vertex 0.861764 1.0333 2.45175 + vertex 0.862553 1.02867 2.45122 + endloop + endfacet + facet normal 0.985009 0.160729 0.0626382 + outer loop + vertex 0.862553 1.02867 2.45122 + vertex 0.861764 1.0333 2.45175 + vertex 0.862264 1.02852 2.45616 + endloop + endfacet + facet normal 0.989805 0.137548 0.036955 + outer loop + vertex 0.861764 1.0333 2.45175 + vertex 0.861595 1.0333 2.45629 + vertex 0.862264 1.02852 2.45616 + endloop + endfacet + facet normal 0.980441 0.133293 0.144802 + outer loop + vertex 0.862264 1.02852 2.45616 + vertex 0.861595 1.0333 2.45629 + vertex 0.861568 1.02841 2.46097 + endloop + endfacet + facet normal 0.984038 0.120234 0.131201 + outer loop + vertex 0.861595 1.0333 2.45629 + vertex 0.860978 1.0333 2.46092 + vertex 0.861568 1.02841 2.46097 + endloop + endfacet + facet normal 0.967223 0.119335 0.224142 + outer loop + vertex 0.861568 1.02841 2.46097 + vertex 0.860978 1.0333 2.46092 + vertex 0.860521 1.02845 2.46547 + endloop + endfacet + facet normal 0.970622 0.109653 0.214171 + outer loop + vertex 0.860978 1.0333 2.46092 + vertex 0.859995 1.03316 2.46544 + vertex 0.860521 1.02845 2.46547 + endloop + endfacet + facet normal 0.94312 0.107231 0.314684 + outer loop + vertex 0.860521 1.02845 2.46547 + vertex 0.859995 1.03316 2.46544 + vertex 0.859173 1.02888 2.46936 + endloop + endfacet + facet normal 0.950776 0.0893115 0.296729 + outer loop + vertex 0.859995 1.03316 2.46544 + vertex 0.858821 1.0331 2.46922 + vertex 0.859173 1.02888 2.46936 + endloop + endfacet + facet normal 0.895127 0.0894307 0.436748 + outer loop + vertex 0.858821 1.0331 2.46922 + vertex 0.857567 1.03003 2.47242 + vertex 0.859173 1.02888 2.46936 + endloop + endfacet + facet normal 0.903505 0.0713039 0.422604 + outer loop + vertex 0.85765 1.03378 2.47161 + vertex 0.857567 1.03003 2.47242 + vertex 0.858821 1.0331 2.46922 + endloop + endfacet + facet normal 0.699072 0.588263 -0.406504 + outer loop + vertex 0.86 1.04 2.44746 + vertex 0.862777 1.035 2.445 + vertex 0.86 1.0383 2.445 + endloop + endfacet + facet normal 0.884615 0.462676 0.0582026 + outer loop + vertex 0.86 1.04 2.44746 + vertex 0.860699 1.03846 2.44909 + vertex 0.862777 1.035 2.445 + endloop + endfacet + facet normal 0.924175 0.131829 0.3585 + outer loop + vertex 0.860699 1.03846 2.44909 + vertex 0.86193 1.03276 2.44801 + vertex 0.862777 1.035 2.445 + endloop + endfacet + facet normal 0.977852 0.208867 0.0134529 + outer loop + vertex 0.86193 1.03276 2.44801 + vertex 0.860699 1.03846 2.44909 + vertex 0.861764 1.0333 2.45175 + endloop + endfacet + facet normal 0.98239 0.182733 -0.0389826 + outer loop + vertex 0.860699 1.03846 2.44909 + vertex 0.86107 1.03724 2.45274 + vertex 0.861764 1.0333 2.45175 + endloop + endfacet + facet normal 0.985725 0.164288 0.0368063 + outer loop + vertex 0.861764 1.0333 2.45175 + vertex 0.86107 1.03724 2.45274 + vertex 0.861595 1.0333 2.45629 + endloop + endfacet + facet normal 0.985684 0.164484 0.0370304 + outer loop + vertex 0.86107 1.03724 2.45274 + vertex 0.860801 1.038 2.45653 + vertex 0.861595 1.0333 2.45629 + endloop + endfacet + facet normal 0.978705 0.158448 0.130505 + outer loop + vertex 0.861595 1.0333 2.45629 + vertex 0.860801 1.038 2.45653 + vertex 0.860978 1.0333 2.46092 + endloop + endfacet + facet normal 0.980094 0.153836 0.125502 + outer loop + vertex 0.860801 1.038 2.45653 + vertex 0.860207 1.03803 2.46114 + vertex 0.860978 1.0333 2.46092 + endloop + endfacet + facet normal 0.96562 0.147289 0.214204 + outer loop + vertex 0.860978 1.0333 2.46092 + vertex 0.860207 1.03803 2.46114 + vertex 0.859995 1.03316 2.46544 + endloop + endfacet + facet normal 0.966222 0.145775 0.21252 + outer loop + vertex 0.860207 1.03803 2.46114 + vertex 0.859236 1.03761 2.46584 + vertex 0.859995 1.03316 2.46544 + endloop + endfacet + facet normal 0.947733 0.135519 0.288856 + outer loop + vertex 0.858372 1.0361 2.46938 + vertex 0.859236 1.03761 2.46584 + vertex 0.858369 1.03895 2.46806 + endloop + endfacet + facet normal 0.9499 0.126814 0.285671 + outer loop + vertex 0.858372 1.0361 2.46938 + vertex 0.858821 1.0331 2.46922 + vertex 0.859236 1.03761 2.46584 + endloop + endfacet + facet normal 0.945669 0.134841 0.295851 + outer loop + vertex 0.858821 1.0331 2.46922 + vertex 0.859995 1.03316 2.46544 + vertex 0.859236 1.03761 2.46584 + endloop + endfacet + facet normal 0.904483 0.113327 0.411179 + outer loop + vertex 0.858821 1.0331 2.46922 + vertex 0.858372 1.0361 2.46938 + vertex 0.85765 1.03378 2.47161 + endloop + endfacet + facet normal 0.954183 0.18321 -0.236578 + outer loop + vertex 0.86 1.04 2.44746 + vertex 0.86 1.04328 2.45 + vertex 0.860699 1.03846 2.44909 + endloop + endfacet + facet normal 0.983302 0.159248 -0.088072 + outer loop + vertex 0.86 1.045 2.45311 + vertex 0.860699 1.03846 2.44909 + vertex 0.86 1.04328 2.45 + endloop + endfacet + facet normal 0.995879 0.0752349 0.0506363 + outer loop + vertex 0.86 1.045 2.45311 + vertex 0.860191 1.04256 2.45298 + vertex 0.860699 1.03846 2.44909 + endloop + endfacet + facet normal 0.985262 0.164975 -0.0451924 + outer loop + vertex 0.860191 1.04256 2.45298 + vertex 0.86107 1.03724 2.45274 + vertex 0.860699 1.03846 2.44909 + endloop + endfacet + facet normal 0.986179 0.161342 0.0376942 + outer loop + vertex 0.86107 1.03724 2.45274 + vertex 0.860191 1.04256 2.45298 + vertex 0.860801 1.038 2.45653 + endloop + endfacet + facet normal 0.985005 0.166636 0.0447046 + outer loop + vertex 0.860191 1.04256 2.45298 + vertex 0.859979 1.0427 2.45712 + vertex 0.860801 1.038 2.45653 + endloop + endfacet + facet normal 0.979833 0.155526 0.125458 + outer loop + vertex 0.860801 1.038 2.45653 + vertex 0.859979 1.0427 2.45712 + vertex 0.860207 1.03803 2.46114 + endloop + endfacet + facet normal 0.977908 0.161581 0.13262 + outer loop + vertex 0.859979 1.0427 2.45712 + vertex 0.859357 1.04277 2.46163 + vertex 0.860207 1.03803 2.46114 + endloop + endfacet + facet normal 0.968467 0.139143 0.206667 + outer loop + vertex 0.85874 1.04135 2.46548 + vertex 0.859357 1.04277 2.46163 + vertex 0.858532 1.04501 2.46399 + endloop + endfacet + facet normal 0.966405 0.148494 0.209785 + outer loop + vertex 0.85874 1.04135 2.46548 + vertex 0.859236 1.03761 2.46584 + vertex 0.859357 1.04277 2.46163 + endloop + endfacet + facet normal 0.965361 0.150978 0.212801 + outer loop + vertex 0.859236 1.03761 2.46584 + vertex 0.860207 1.03803 2.46114 + vertex 0.859357 1.04277 2.46163 + endloop + endfacet + facet normal 0.948162 0.15263 0.278733 + outer loop + vertex 0.859236 1.03761 2.46584 + vertex 0.85874 1.04135 2.46548 + vertex 0.858369 1.03895 2.46806 + endloop + endfacet + facet normal -0.539559 0.00168618 -0.841946 + outer loop + vertex 0.86 1.05 2.45312 + vertex 0.860191 1.04256 2.45298 + vertex 0.86 1.045 2.45311 + endloop + endfacet + facet normal 0.965057 0.0199227 0.261281 + outer loop + vertex 0.859645 1.0475 2.45462 + vertex 0.860191 1.04256 2.45298 + vertex 0.86 1.05 2.45312 + endloop + endfacet + facet normal 0.994426 0.0940481 0.0476644 + outer loop + vertex 0.860191 1.04256 2.45298 + vertex 0.859645 1.0475 2.45462 + vertex 0.859979 1.0427 2.45712 + endloop + endfacet + facet normal 0.984019 0.131238 0.120342 + outer loop + vertex 0.859645 1.0475 2.45462 + vertex 0.85933 1.04694 2.45782 + vertex 0.859979 1.0427 2.45712 + endloop + endfacet + facet normal 0.982607 0.12883 0.13374 + outer loop + vertex 0.859979 1.0427 2.45712 + vertex 0.85933 1.04694 2.45782 + vertex 0.859357 1.04277 2.46163 + endloop + endfacet + facet normal 0.981501 0.132716 0.137994 + outer loop + vertex 0.85933 1.04694 2.45782 + vertex 0.858922 1.04688 2.46077 + vertex 0.859357 1.04277 2.46163 + endloop + endfacet + facet normal 0.968748 0.144728 0.201445 + outer loop + vertex 0.858922 1.04688 2.46077 + vertex 0.858532 1.04501 2.46399 + vertex 0.859357 1.04277 2.46163 + endloop + endfacet + facet normal 0.972291 0.130775 0.193771 + outer loop + vertex 0.85841 1.0487 2.46211 + vertex 0.858532 1.04501 2.46399 + vertex 0.858922 1.04688 2.46077 + endloop + endfacet + facet normal 0.990125 -0.0664798 0.12342 + outer loop + vertex 0.86 1.05 2.45312 + vertex 0.86 1.05349 2.455 + vertex 0.859645 1.0475 2.45462 + endloop + endfacet + facet normal 0.988878 0.0950177 0.114421 + outer loop + vertex 0.859645 1.0475 2.45462 + vertex 0.859179 1.05114 2.45562 + vertex 0.85933 1.04694 2.45782 + endloop + endfacet + facet normal 0.746642 -0.0859028 0.659657 + outer loop + vertex 0.86 1.05349 2.455 + vertex 0.859179 1.05114 2.45562 + vertex 0.859645 1.0475 2.45462 + endloop + endfacet + facet normal 0.981872 0.129946 0.137994 + outer loop + vertex 0.85933 1.04694 2.45782 + vertex 0.858751 1.05032 2.45874 + vertex 0.858922 1.04688 2.46077 + endloop + endfacet + facet normal 0.978556 0.121666 0.166211 + outer loop + vertex 0.859179 1.05114 2.45562 + vertex 0.858751 1.05032 2.45874 + vertex 0.85933 1.04694 2.45782 + endloop + endfacet + facet normal 0.974124 0.148568 0.170323 + outer loop + vertex 0.858922 1.04688 2.46077 + vertex 0.858751 1.05032 2.45874 + vertex 0.85841 1.0487 2.46211 + endloop + endfacet + facet normal 0.754374 -0.567492 -0.329958 + outer loop + vertex 0.863353 1.115 2.535 + vertex 0.86 1.11345 2.53 + vertex 0.861166 1.115 2.53 + endloop + endfacet + facet normal 0.682111 -0.689447 -0.243695 + outer loop + vertex 0.85942 1.11151 2.53387 + vertex 0.86 1.11345 2.53 + vertex 0.863353 1.115 2.535 + endloop + endfacet + facet normal 0.681218 -0.711172 -0.173715 + outer loop + vertex 0.864628 1.115 2.54 + vertex 0.85942 1.11151 2.53387 + vertex 0.863353 1.115 2.535 + endloop + endfacet + facet normal 0.525815 -0.849789 0.0371098 + outer loop + vertex 0.858811 1.11133 2.53832 + vertex 0.85942 1.11151 2.53387 + vertex 0.864628 1.115 2.54 + endloop + endfacet + facet normal 0.156862 0.195451 -0.968087 + outer loop + vertex 0.863147 1.11328 2.53941 + vertex 0.858811 1.11133 2.53832 + vertex 0.864628 1.115 2.54 + endloop + endfacet + facet normal 0.428849 -0.898627 -0.0925121 + outer loop + vertex 0.863147 1.11328 2.53941 + vertex 0.862172 1.1126 2.54153 + vertex 0.858811 1.11133 2.53832 + endloop + endfacet + facet normal 0.151499 -0.963003 0.222875 + outer loop + vertex 0.862172 1.1126 2.54153 + vertex 0.858472 1.11218 2.54224 + vertex 0.858811 1.11133 2.53832 + endloop + endfacet + facet normal -0.0174127 -0.903948 0.427288 + outer loop + vertex 0.858942 1.11321 2.54458 + vertex 0.86159 1.11302 2.54429 + vertex 0.860605 1.11366 2.54561 + endloop + endfacet + facet normal -0.0206571 -0.914298 0.404515 + outer loop + vertex 0.858942 1.11321 2.54458 + vertex 0.858472 1.11218 2.54224 + vertex 0.86159 1.11302 2.54429 + endloop + endfacet + facet normal 0.144 -0.973467 0.177839 + outer loop + vertex 0.858472 1.11218 2.54224 + vertex 0.862172 1.1126 2.54153 + vertex 0.86159 1.11302 2.54429 + endloop + endfacet + facet normal 0.229427 -0.796912 0.558833 + outer loop + vertex 0.86159 1.11302 2.54429 + vertex 0.862561 1.1149 2.54657 + vertex 0.860605 1.11366 2.54561 + endloop + endfacet + facet normal -0.257342 0.503786 -0.824606 + outer loop + vertex 0.865 1.11519 2.54 + vertex 0.863147 1.11328 2.53941 + vertex 0.864628 1.115 2.54 + endloop + endfacet + facet normal -0.242272 -0.680873 0.69117 + outer loop + vertex 0.858942 1.11321 2.54458 + vertex 0.860605 1.11366 2.54561 + vertex 0.857937 1.1152 2.54619 + endloop + endfacet + facet normal -0.118658 -0.721676 0.681985 + outer loop + vertex 0.864027 1.11727 2.54927 + vertex 0.861045 1.11928 2.55089 + vertex 0.859617 1.11743 2.54868 + endloop + endfacet + facet normal -0.119497 -0.713487 0.690403 + outer loop + vertex 0.862561 1.1149 2.54657 + vertex 0.864027 1.11727 2.54927 + vertex 0.859617 1.11743 2.54868 + endloop + endfacet + facet normal -0.10376 -0.70471 0.701868 + outer loop + vertex 0.862561 1.1149 2.54657 + vertex 0.859617 1.11743 2.54868 + vertex 0.857937 1.1152 2.54619 + endloop + endfacet + facet normal -0.103394 -0.503054 0.858048 + outer loop + vertex 0.862561 1.1149 2.54657 + vertex 0.857937 1.1152 2.54619 + vertex 0.860605 1.11366 2.54561 + endloop + endfacet + facet normal -0.134162 -0.732736 0.667157 + outer loop + vertex 0.864027 1.11727 2.54927 + vertex 0.864376 1.11956 2.55186 + vertex 0.861045 1.11928 2.55089 + endloop + endfacet + facet normal -0.26782 -0.645943 0.714864 + outer loop + vertex 0.859617 1.11743 2.54868 + vertex 0.861045 1.11928 2.55089 + vertex 0.856935 1.1206 2.55054 + endloop + endfacet + facet normal -0.266648 -0.640954 0.719776 + outer loop + vertex 0.861045 1.11928 2.55089 + vertex 0.859526 1.12273 2.5534 + vertex 0.856935 1.1206 2.55054 + endloop + endfacet + facet normal -0.169743 -0.627461 0.759921 + outer loop + vertex 0.861045 1.11928 2.55089 + vertex 0.864376 1.11956 2.55186 + vertex 0.859526 1.12273 2.5534 + endloop + endfacet + facet normal -0.261537 -0.714045 0.649413 + outer loop + vertex 0.864376 1.11956 2.55186 + vertex 0.864912 1.1216 2.55432 + vertex 0.859526 1.12273 2.5534 + endloop + endfacet + facet normal -0.261112 -0.696381 0.668486 + outer loop + vertex 0.859526 1.12273 2.5534 + vertex 0.864912 1.1216 2.55432 + vertex 0.862781 1.1245 2.55652 + endloop + endfacet + facet normal -0.322962 -0.637452 0.699536 + outer loop + vertex 0.85804 1.12616 2.55584 + vertex 0.859526 1.12273 2.5534 + vertex 0.862781 1.1245 2.55652 + endloop + endfacet + facet normal -0.313881 -0.594887 0.739992 + outer loop + vertex 0.862781 1.1245 2.55652 + vertex 0.85839 1.12879 2.5581 + vertex 0.85804 1.12616 2.55584 + endloop + endfacet + facet normal -0.367482 -0.629332 0.684761 + outer loop + vertex 0.864347 1.12668 2.55935 + vertex 0.85839 1.12879 2.5581 + vertex 0.862781 1.1245 2.55652 + endloop + endfacet + facet normal -0.365802 -0.618027 0.695867 + outer loop + vertex 0.85839 1.12879 2.5581 + vertex 0.864347 1.12668 2.55935 + vertex 0.862505 1.1299 2.56125 + endloop + endfacet + facet normal -0.40128 -0.562667 0.722758 + outer loop + vertex 0.857657 1.13198 2.56017 + vertex 0.85839 1.12879 2.5581 + vertex 0.862505 1.1299 2.56125 + endloop + endfacet + facet normal -0.396368 -0.541598 0.741326 + outer loop + vertex 0.862505 1.1299 2.56125 + vertex 0.858981 1.13374 2.56217 + vertex 0.857657 1.13198 2.56017 + endloop + endfacet + facet normal -0.422275 -0.558749 0.713781 + outer loop + vertex 0.863937 1.13257 2.56419 + vertex 0.858981 1.13374 2.56217 + vertex 0.862505 1.1299 2.56125 + endloop + endfacet + facet normal -0.483753 -0.53188 0.695044 + outer loop + vertex 0.863816 1.13528 2.56628 + vertex 0.861379 1.13762 2.56638 + vertex 0.859416 1.13689 2.56445 + endloop + endfacet + facet normal -0.484255 -0.548619 0.681553 + outer loop + vertex 0.863816 1.13528 2.56628 + vertex 0.859416 1.13689 2.56445 + vertex 0.863937 1.13257 2.56419 + endloop + endfacet + facet normal -0.425231 -0.491569 0.75996 + outer loop + vertex 0.863937 1.13257 2.56419 + vertex 0.859416 1.13689 2.56445 + vertex 0.858981 1.13374 2.56217 + endloop + endfacet + facet normal -0.458535 -0.506999 0.729862 + outer loop + vertex 0.863816 1.13528 2.56628 + vertex 0.863681 1.13835 2.56833 + vertex 0.861379 1.13762 2.56638 + endloop + endfacet + facet normal -0.53739 -0.444593 0.716624 + outer loop + vertex 0.859416 1.13689 2.56445 + vertex 0.861379 1.13762 2.56638 + vertex 0.859043 1.14032 2.5663 + endloop + endfacet + facet normal -0.543591 -0.376905 0.749968 + outer loop + vertex 0.863316 1.14143 2.57005 + vertex 0.86169 1.14494 2.57063 + vertex 0.860119 1.14283 2.56844 + endloop + endfacet + facet normal -0.552136 -0.455418 0.698384 + outer loop + vertex 0.863681 1.13835 2.56833 + vertex 0.863316 1.14143 2.57005 + vertex 0.860119 1.14283 2.56844 + endloop + endfacet + facet normal -0.507734 -0.421478 0.751373 + outer loop + vertex 0.863681 1.13835 2.56833 + vertex 0.860119 1.14283 2.56844 + vertex 0.859043 1.14032 2.5663 + endloop + endfacet + facet normal -0.507157 -0.417399 0.754036 + outer loop + vertex 0.863681 1.13835 2.56833 + vertex 0.859043 1.14032 2.5663 + vertex 0.861379 1.13762 2.56638 + endloop + endfacet + facet normal -0.5332 -0.373606 0.759023 + outer loop + vertex 0.863316 1.14143 2.57005 + vertex 0.865412 1.14221 2.57191 + vertex 0.86169 1.14494 2.57063 + endloop + endfacet + facet normal -0.575284 -0.344695 0.741777 + outer loop + vertex 0.85732 1.14781 2.56858 + vertex 0.860119 1.14283 2.56844 + vertex 0.86169 1.14494 2.57063 + endloop + endfacet + facet normal -0.650492 -0.0233459 0.759155 + outer loop + vertex 0.859067 1.19868 2.58148 + vertex 0.856877 1.1972 2.57956 + vertex 0.859157 1.19589 2.58147 + endloop + endfacet + facet normal -0.635859 -0.0229187 0.771465 + outer loop + vertex 0.859157 1.19589 2.58147 + vertex 0.861819 1.1972 2.5837 + vertex 0.859067 1.19868 2.58148 + endloop + endfacet + facet normal -0.6339 -0.0292674 0.772861 + outer loop + vertex 0.859157 1.19589 2.58147 + vertex 0.860304 1.19229 2.58227 + vertex 0.861819 1.1972 2.5837 + endloop + endfacet + facet normal -0.6161 -0.0387881 0.786713 + outer loop + vertex 0.860304 1.19229 2.58227 + vertex 0.863219 1.1922 2.58455 + vertex 0.861819 1.1972 2.5837 + endloop + endfacet + facet normal -0.638165 -0.0531264 0.768064 + outer loop + vertex 0.856877 1.1972 2.57956 + vertex 0.859067 1.19868 2.58148 + vertex 0.85758 1.20087 2.58039 + endloop + endfacet + facet normal -0.649884 -0.0665441 0.757115 + outer loop + vertex 0.859067 1.19868 2.58148 + vertex 0.859723 1.20182 2.58232 + vertex 0.85758 1.20087 2.58039 + endloop + endfacet + facet normal -0.648711 -0.0670462 0.758076 + outer loop + vertex 0.859067 1.19868 2.58148 + vertex 0.861819 1.1972 2.5837 + vertex 0.859723 1.20182 2.58232 + endloop + endfacet + facet normal -0.628864 -0.0527247 0.775725 + outer loop + vertex 0.861819 1.1972 2.5837 + vertex 0.862448 1.20243 2.58457 + vertex 0.859723 1.20182 2.58232 + endloop + endfacet + facet normal -0.560239 0.132288 0.817699 + outer loop + vertex 0.86042 1.75367 2.59598 + vertex 0.864354 1.75672 2.59818 + vertex 0.861124 1.75879 2.59563 + endloop + endfacet + facet normal -0.597557 0.0433684 0.800653 + outer loop + vertex 0.859049 1.77106 2.59306 + vertex 0.858782 1.76605 2.59313 + vertex 0.861758 1.76884 2.5952 + endloop + endfacet + facet normal -0.598707 0.0412474 0.799905 + outer loop + vertex 0.861998 1.77365 2.59513 + vertex 0.859049 1.77106 2.59306 + vertex 0.861758 1.76884 2.5952 + endloop + endfacet + facet normal -0.57673 0.0403743 0.815937 + outer loop + vertex 0.861758 1.76884 2.5952 + vertex 0.864714 1.77194 2.59713 + vertex 0.861998 1.77365 2.59513 + endloop + endfacet + facet normal -0.579448 0.0442975 0.813805 + outer loop + vertex 0.864583 1.76702 2.59731 + vertex 0.864714 1.77194 2.59713 + vertex 0.861758 1.76884 2.5952 + endloop + endfacet + facet normal -0.605199 0.0531401 0.794299 + outer loop + vertex 0.859617 1.77659 2.59312 + vertex 0.859049 1.77106 2.59306 + vertex 0.861998 1.77365 2.59513 + endloop + endfacet + facet normal -0.552004 0.377773 0.743356 + outer loop + vertex 0.861288 1.87249 2.57108 + vertex 0.858171 1.87173 2.56916 + vertex 0.859648 1.86977 2.57125 + endloop + endfacet + facet normal -0.547408 0.375284 0.748002 + outer loop + vertex 0.859648 1.86977 2.57125 + vertex 0.862511 1.86984 2.57331 + vertex 0.861288 1.87249 2.57108 + endloop + endfacet + facet normal -0.55685 0.32923 0.762578 + outer loop + vertex 0.859648 1.86977 2.57125 + vertex 0.859164 1.86645 2.57233 + vertex 0.862511 1.86984 2.57331 + endloop + endfacet + facet normal -0.561243 0.335254 0.75671 + outer loop + vertex 0.859164 1.86645 2.57233 + vertex 0.86183 1.86525 2.57484 + vertex 0.862511 1.86984 2.57331 + endloop + endfacet + facet normal -0.544746 0.407578 0.732893 + outer loop + vertex 0.861288 1.87249 2.57108 + vertex 0.863767 1.87378 2.57221 + vertex 0.862388 1.87631 2.56978 + endloop + endfacet + facet normal -0.550305 0.407728 0.728644 + outer loop + vertex 0.861288 1.87249 2.57108 + vertex 0.862388 1.87631 2.56978 + vertex 0.858171 1.87173 2.56916 + endloop + endfacet + facet normal -0.529731 0.385161 0.755669 + outer loop + vertex 0.858171 1.87173 2.56916 + vertex 0.862388 1.87631 2.56978 + vertex 0.857995 1.87661 2.56654 + endloop + endfacet + facet normal -0.539258 0.381404 0.750821 + outer loop + vertex 0.863767 1.87378 2.57221 + vertex 0.861288 1.87249 2.57108 + vertex 0.862511 1.86984 2.57331 + endloop + endfacet + facet normal -0.476943 0.435678 0.763354 + outer loop + vertex 0.860578 1.88385 2.56418 + vertex 0.85866 1.88284 2.56356 + vertex 0.858673 1.88089 2.56468 + endloop + endfacet + facet normal -0.492135 0.443071 0.749328 + outer loop + vertex 0.858673 1.88089 2.56468 + vertex 0.86242 1.88137 2.56686 + vertex 0.860578 1.88385 2.56418 + endloop + endfacet + facet normal -0.496694 0.411447 0.764203 + outer loop + vertex 0.858673 1.88089 2.56468 + vertex 0.857995 1.87661 2.56654 + vertex 0.86242 1.88137 2.56686 + endloop + endfacet + facet normal -0.515655 0.430606 0.740728 + outer loop + vertex 0.857995 1.87661 2.56654 + vertex 0.862388 1.87631 2.56978 + vertex 0.86242 1.88137 2.56686 + endloop + endfacet + facet normal -0.477954 0.507252 0.717116 + outer loop + vertex 0.861284 1.88705 2.56246 + vertex 0.857264 1.88612 2.56044 + vertex 0.858856 1.88449 2.56265 + endloop + endfacet + facet normal -0.485015 0.464974 0.740649 + outer loop + vertex 0.858856 1.88449 2.56265 + vertex 0.85866 1.88284 2.56356 + vertex 0.860578 1.88385 2.56418 + endloop + endfacet + facet normal -0.46576 0.496814 0.732286 + outer loop + vertex 0.861284 1.88705 2.56246 + vertex 0.858856 1.88449 2.56265 + vertex 0.860578 1.88385 2.56418 + endloop + endfacet + facet normal -0.482397 0.495232 0.722522 + outer loop + vertex 0.861284 1.88705 2.56246 + vertex 0.860578 1.88385 2.56418 + vertex 0.863469 1.88574 2.56482 + endloop + endfacet + facet normal -0.480098 0.498173 0.722032 + outer loop + vertex 0.861284 1.88705 2.56246 + vertex 0.863469 1.88574 2.56482 + vertex 0.863537 1.88781 2.56344 + endloop + endfacet + facet normal -0.468375 0.463687 0.752077 + outer loop + vertex 0.863469 1.88574 2.56482 + vertex 0.860578 1.88385 2.56418 + vertex 0.86242 1.88137 2.56686 + endloop + endfacet + facet normal -0.470062 0.590433 0.656072 + outer loop + vertex 0.861284 1.88705 2.56246 + vertex 0.863704 1.88919 2.56227 + vertex 0.861606 1.89047 2.55961 + endloop + endfacet + facet normal -0.467377 0.591201 0.657298 + outer loop + vertex 0.861284 1.88705 2.56246 + vertex 0.861606 1.89047 2.55961 + vertex 0.857264 1.88612 2.56044 + endloop + endfacet + facet normal -0.377227 0.521799 0.765131 + outer loop + vertex 0.857264 1.88612 2.56044 + vertex 0.861606 1.89047 2.55961 + vertex 0.857077 1.89009 2.55764 + endloop + endfacet + facet normal -0.479076 0.599334 0.641315 + outer loop + vertex 0.863704 1.88919 2.56227 + vertex 0.861284 1.88705 2.56246 + vertex 0.863537 1.88781 2.56344 + endloop + endfacet + facet normal -0.199212 0.764444 0.61314 + outer loop + vertex 0.859923 1.89348 2.55602 + vertex 0.86546 1.89418 2.55696 + vertex 0.861964 1.89633 2.55314 + endloop + endfacet + facet normal -0.154806 0.755896 0.636126 + outer loop + vertex 0.856853 1.8954 2.553 + vertex 0.859923 1.89348 2.55602 + vertex 0.861964 1.89633 2.55314 + endloop + endfacet + facet normal -0.354716 0.627158 0.693433 + outer loop + vertex 0.861606 1.89047 2.55961 + vertex 0.859923 1.89348 2.55602 + vertex 0.857077 1.89009 2.55764 + endloop + endfacet + facet normal -0.203182 0.700583 0.684033 + outer loop + vertex 0.86546 1.89418 2.55696 + vertex 0.859923 1.89348 2.55602 + vertex 0.861606 1.89047 2.55961 + endloop + endfacet + facet normal -0.0872561 0.867127 0.490385 + outer loop + vertex 0.85967 1.90059 2.547 + vertex 0.86498 1.90185 2.54571 + vertex 0.861145 1.90275 2.54345 + endloop + endfacet + facet normal 0.0995684 0.831585 0.5464 + outer loop + vertex 0.857551 1.90245 2.54455 + vertex 0.85967 1.90059 2.547 + vertex 0.861145 1.90275 2.54345 + endloop + endfacet + facet normal -0.0546702 0.816156 0.57524 + outer loop + vertex 0.86498 1.90185 2.54571 + vertex 0.85967 1.90059 2.547 + vertex 0.8642 1.8991 2.54955 + endloop + endfacet + facet normal -0.0505719 0.819952 0.570194 + outer loop + vertex 0.8642 1.8991 2.54955 + vertex 0.85967 1.90059 2.547 + vertex 0.859536 1.89819 2.55045 + endloop + endfacet + facet normal -0.15306 0.744161 0.650228 + outer loop + vertex 0.861964 1.89633 2.55314 + vertex 0.859536 1.89819 2.55045 + vertex 0.856853 1.8954 2.553 + endloop + endfacet + facet normal -0.0432072 0.804304 0.592645 + outer loop + vertex 0.8642 1.8991 2.54955 + vertex 0.859536 1.89819 2.55045 + vertex 0.861964 1.89633 2.55314 + endloop + endfacet + facet normal 0.0915073 0.171366 0.980949 + outer loop + vertex 0.865 1.90689 2.54 + vertex 0.86 1.90956 2.54 + vertex 0.862303 1.90484 2.54061 + endloop + endfacet + facet normal 0.152521 0.19944 0.967967 + outer loop + vertex 0.862303 1.90484 2.54061 + vertex 0.86 1.90956 2.54 + vertex 0.857547 1.90456 2.54142 + endloop + endfacet + facet normal 0.102498 0.825902 0.554419 + outer loop + vertex 0.861145 1.90275 2.54345 + vertex 0.857547 1.90456 2.54142 + vertex 0.857551 1.90245 2.54455 + endloop + endfacet + facet normal 0.0563635 0.792849 0.606806 + outer loop + vertex 0.862303 1.90484 2.54061 + vertex 0.857547 1.90456 2.54142 + vertex 0.861145 1.90275 2.54345 + endloop + endfacet + facet normal -0.596921 0.521159 0.609982 + outer loop + vertex 0.86 1.91 2.53427 + vertex 0.857541 1.90973 2.5321 + vertex 0.860746 1.91 2.535 + endloop + endfacet + facet normal -0.0705864 0.997372 -0.0163543 + outer loop + vertex 0.860746 1.91 2.535 + vertex 0.857541 1.90973 2.5321 + vertex 0.86 1.91 2.53822 + endloop + endfacet + facet normal -0.998655 -0.0438649 -0.0276313 + outer loop + vertex 0.860057 1.99031 2.44644 + vertex 0.86 1.98937 2.45 + vertex 0.86 1.99 2.449 + endloop + endfacet + facet normal -0.862288 0.492931 0.116094 + outer loop + vertex 0.859692 1.98892 2.44963 + vertex 0.86 1.98937 2.45 + vertex 0.860057 1.99031 2.44644 + endloop + endfacet + facet normal -0.877652 0.436927 0.197031 + outer loop + vertex 0.858685 1.98526 2.45325 + vertex 0.86 1.98937 2.45 + vertex 0.859692 1.98892 2.44963 + endloop + endfacet + facet normal 0.966759 -0.25545 0.0110338 + outer loop + vertex 0.859473 1.9883 2.45448 + vertex 0.858685 1.98526 2.45325 + vertex 0.859692 1.98892 2.44963 + endloop + endfacet + facet normal 0.963908 -0.264048 0.0340564 + outer loop + vertex 0.858417 1.98493 2.45823 + vertex 0.858685 1.98526 2.45325 + vertex 0.859473 1.9883 2.45448 + endloop + endfacet + facet normal 0.972549 -0.219831 0.0763051 + outer loop + vertex 0.859192 1.9889 2.45979 + vertex 0.858417 1.98493 2.45823 + vertex 0.859473 1.9883 2.45448 + endloop + endfacet + facet normal 0.967165 -0.230701 0.10663 + outer loop + vertex 0.858135 1.98564 2.46232 + vertex 0.858417 1.98493 2.45823 + vertex 0.859192 1.9889 2.45979 + endloop + endfacet + facet normal 0.968702 -0.187682 0.162454 + outer loop + vertex 0.859192 1.9889 2.45979 + vertex 0.85836 1.98818 2.46392 + vertex 0.858135 1.98564 2.46232 + endloop + endfacet + facet normal -0.99501 -0.0939543 -0.0335899 + outer loop + vertex 0.86 1.99143 2.445 + vertex 0.860057 1.99031 2.44644 + vertex 0.86 1.99 2.449 + endloop + endfacet + facet normal 0.77151 -0.48668 -0.409773 + outer loop + vertex 0.86 1.99143 2.445 + vertex 0.862252 1.995 2.445 + vertex 0.860057 1.99031 2.44644 + endloop + endfacet + facet normal 0.822806 -0.224752 0.521994 + outer loop + vertex 0.862252 1.995 2.445 + vertex 0.860755 1.99314 2.44656 + vertex 0.860057 1.99031 2.44644 + endloop + endfacet + facet normal 0.97081 -0.239758 0.00666183 + outer loop + vertex 0.860057 1.99031 2.44644 + vertex 0.860755 1.99314 2.44656 + vertex 0.859692 1.98892 2.44963 + endloop + endfacet + facet normal 0.975936 -0.21346 0.0445499 + outer loop + vertex 0.860755 1.99314 2.44656 + vertex 0.860363 1.99219 2.45062 + vertex 0.859692 1.98892 2.44963 + endloop + endfacet + facet normal 0.978411 -0.205892 0.0179012 + outer loop + vertex 0.859692 1.98892 2.44963 + vertex 0.860363 1.99219 2.45062 + vertex 0.859473 1.9883 2.45448 + endloop + endfacet + facet normal 0.982159 -0.183425 0.0414506 + outer loop + vertex 0.860363 1.99219 2.45062 + vertex 0.860165 1.99223 2.45549 + vertex 0.859473 1.9883 2.45448 + endloop + endfacet + facet normal 0.978838 -0.191021 0.073394 + outer loop + vertex 0.859473 1.9883 2.45448 + vertex 0.860165 1.99223 2.45549 + vertex 0.859192 1.9889 2.45979 + endloop + endfacet + facet normal 0.98263 -0.154751 0.102425 + outer loop + vertex 0.860165 1.99223 2.45549 + vertex 0.85989 1.99303 2.45933 + vertex 0.859192 1.9889 2.45979 + endloop + endfacet + facet normal 0.953993 -0.114603 0.277063 + outer loop + vertex 0.85836 1.98818 2.46392 + vertex 0.859006 1.99226 2.46338 + vertex 0.857808 1.98979 2.46648 + endloop + endfacet + facet normal 0.975971 -0.131766 0.173549 + outer loop + vertex 0.85836 1.98818 2.46392 + vertex 0.859192 1.9889 2.45979 + vertex 0.859006 1.99226 2.46338 + endloop + endfacet + facet normal 0.972218 -0.143855 0.184655 + outer loop + vertex 0.859192 1.9889 2.45979 + vertex 0.85989 1.99303 2.45933 + vertex 0.859006 1.99226 2.46338 + endloop + endfacet + facet normal 0.947642 -0.0674442 0.312131 + outer loop + vertex 0.859006 1.99226 2.46338 + vertex 0.857804 1.99379 2.46736 + vertex 0.857808 1.98979 2.46648 + endloop + endfacet + facet normal 0.752961 -0.0569258 0.655598 + outer loop + vertex 0.862252 1.995 2.445 + vertex 0.86263 2 2.445 + vertex 0.860755 1.99314 2.44656 + endloop + endfacet + facet normal 0.908742 -0.160877 0.385105 + outer loop + vertex 0.86263 2 2.445 + vertex 0.861308 1.99751 2.44708 + vertex 0.860755 1.99314 2.44656 + endloop + endfacet + facet normal 0.989064 -0.132594 0.0645852 + outer loop + vertex 0.860755 1.99314 2.44656 + vertex 0.861308 1.99751 2.44708 + vertex 0.860363 1.99219 2.45062 + endloop + endfacet + facet normal 0.989024 -0.13367 0.0629568 + outer loop + vertex 0.861308 1.99751 2.44708 + vertex 0.86093 1.99675 2.4514 + vertex 0.860363 1.99219 2.45062 + endloop + endfacet + facet normal 0.990624 -0.130203 0.0413568 + outer loop + vertex 0.860363 1.99219 2.45062 + vertex 0.86093 1.99675 2.4514 + vertex 0.860165 1.99223 2.45549 + endloop + endfacet + facet normal 0.991987 -0.106868 0.067385 + outer loop + vertex 0.86093 1.99675 2.4514 + vertex 0.860613 1.99676 2.45608 + vertex 0.860165 1.99223 2.45549 + endloop + endfacet + facet normal 0.989501 -0.110047 0.0936834 + outer loop + vertex 0.860165 1.99223 2.45549 + vertex 0.860613 1.99676 2.45608 + vertex 0.85989 1.99303 2.45933 + endloop + endfacet + facet normal 0.988179 -0.0749352 0.133739 + outer loop + vertex 0.860613 1.99676 2.45608 + vertex 0.860033 1.99681 2.46039 + vertex 0.85989 1.99303 2.45933 + endloop + endfacet + facet normal 0.9764 -0.0918611 0.195458 + outer loop + vertex 0.85989 1.99303 2.45933 + vertex 0.860033 1.99681 2.46039 + vertex 0.859006 1.99226 2.46338 + endloop + endfacet + facet normal 0.971122 -0.0690813 0.228363 + outer loop + vertex 0.860033 1.99681 2.46039 + vertex 0.859138 1.9973 2.46435 + vertex 0.859006 1.99226 2.46338 + endloop + endfacet + facet normal 0.944205 -0.0855433 0.318055 + outer loop + vertex 0.859138 1.9973 2.46435 + vertex 0.857804 1.99379 2.46736 + vertex 0.859006 1.99226 2.46338 + endloop + endfacet + facet normal 0.932742 -0.0474202 0.357413 + outer loop + vertex 0.857859 1.99864 2.46786 + vertex 0.857804 1.99379 2.46736 + vertex 0.859138 1.9973 2.46435 + endloop + endfacet + facet normal 0.843882 0.000502981 0.536529 + outer loop + vertex 0.86263 2 2.445 + vertex 0.862627 2.005 2.445 + vertex 0.861308 1.99751 2.44708 + endloop + endfacet + facet normal 0.963696 -0.101129 0.247107 + outer loop + vertex 0.862627 2.005 2.445 + vertex 0.861751 2.00253 2.4474 + vertex 0.861308 1.99751 2.44708 + endloop + endfacet + facet normal 0.993215 -0.0924126 0.0706029 + outer loop + vertex 0.861308 1.99751 2.44708 + vertex 0.861751 2.00253 2.4474 + vertex 0.86093 1.99675 2.4514 + endloop + endfacet + facet normal 0.99313 -0.103577 0.0544403 + outer loop + vertex 0.861751 2.00253 2.4474 + vertex 0.861442 2.0019 2.45184 + vertex 0.86093 1.99675 2.4514 + endloop + endfacet + facet normal 0.992226 -0.104619 0.0673978 + outer loop + vertex 0.86093 1.99675 2.4514 + vertex 0.861442 2.0019 2.45184 + vertex 0.860613 1.99676 2.45608 + endloop + endfacet + facet normal 0.9923 -0.0904328 0.0846265 + outer loop + vertex 0.861442 2.0019 2.45184 + vertex 0.860997 2.00155 2.45669 + vertex 0.860613 1.99676 2.45608 + endloop + endfacet + facet normal 0.986332 -0.0962491 0.133739 + outer loop + vertex 0.860613 1.99676 2.45608 + vertex 0.860997 2.00155 2.45669 + vertex 0.860033 1.99681 2.46039 + endloop + endfacet + facet normal 0.984154 -0.0746232 0.160846 + outer loop + vertex 0.860997 2.00155 2.45669 + vertex 0.860291 2.00143 2.46096 + vertex 0.860033 1.99681 2.46039 + endloop + endfacet + facet normal 0.969783 -0.0822374 0.22969 + outer loop + vertex 0.860033 1.99681 2.46039 + vertex 0.860291 2.00143 2.46096 + vertex 0.859138 1.9973 2.46435 + endloop + endfacet + facet normal 0.964606 -0.0582535 0.257181 + outer loop + vertex 0.860291 2.00143 2.46096 + vertex 0.859361 2.00215 2.46461 + vertex 0.859138 1.9973 2.46435 + endloop + endfacet + facet normal 0.930041 -0.0623351 0.36213 + outer loop + vertex 0.859361 2.00215 2.46461 + vertex 0.857859 1.99864 2.46786 + vertex 0.859138 1.9973 2.46435 + endloop + endfacet + facet normal 0.920245 -0.032263 0.39001 + outer loop + vertex 0.857984 2.00354 2.46797 + vertex 0.857859 1.99864 2.46786 + vertex 0.859361 2.00215 2.46461 + endloop + endfacet + facet normal 0.951777 -0.0416865 0.303945 + outer loop + vertex 0.862627 2.005 2.445 + vertex 0.862846 2.01 2.445 + vertex 0.861751 2.00253 2.4474 + endloop + endfacet + facet normal 0.990115 -0.123958 0.0656184 + outer loop + vertex 0.862846 2.01 2.445 + vertex 0.862377 2.00757 2.44748 + vertex 0.861751 2.00253 2.4474 + endloop + endfacet + facet normal 0.990968 -0.12385 0.0514175 + outer loop + vertex 0.861751 2.00253 2.4474 + vertex 0.862377 2.00757 2.44748 + vertex 0.861442 2.0019 2.45184 + endloop + endfacet + facet normal 0.989113 -0.145333 0.0231084 + outer loop + vertex 0.862377 2.00757 2.44748 + vertex 0.86226 2.00756 2.45246 + vertex 0.861442 2.0019 2.45184 + endloop + endfacet + facet normal 0.985337 -0.150902 0.0796195 + outer loop + vertex 0.861442 2.0019 2.45184 + vertex 0.86226 2.00756 2.45246 + vertex 0.860997 2.00155 2.45669 + endloop + endfacet + facet normal 0.98508 -0.120217 0.123148 + outer loop + vertex 0.86226 2.00756 2.45246 + vertex 0.861333 2.00538 2.45774 + vertex 0.860997 2.00155 2.45669 + endloop + endfacet + facet normal 0.978844 -0.129354 0.15853 + outer loop + vertex 0.860997 2.00155 2.45669 + vertex 0.861333 2.00538 2.45774 + vertex 0.860291 2.00143 2.46096 + endloop + endfacet + facet normal 0.976443 -0.103631 0.189259 + outer loop + vertex 0.861333 2.00538 2.45774 + vertex 0.86073 2.00598 2.46118 + vertex 0.860291 2.00143 2.46096 + endloop + endfacet + facet normal 0.958474 -0.105616 0.2649 + outer loop + vertex 0.860291 2.00143 2.46096 + vertex 0.86073 2.00598 2.46118 + vertex 0.859361 2.00215 2.46461 + endloop + endfacet + facet normal 0.950318 -0.0679125 0.303782 + outer loop + vertex 0.86073 2.00598 2.46118 + vertex 0.859675 2.00681 2.46467 + vertex 0.859361 2.00215 2.46461 + endloop + endfacet + facet normal 0.913472 -0.0666617 0.401404 + outer loop + vertex 0.859675 2.00681 2.46467 + vertex 0.857984 2.00354 2.46797 + vertex 0.859361 2.00215 2.46461 + endloop + endfacet + facet normal 0.903581 -0.0358159 0.426917 + outer loop + vertex 0.858186 2.00838 2.46795 + vertex 0.857984 2.00354 2.46797 + vertex 0.859675 2.00681 2.46467 + endloop + endfacet + facet normal 0.978266 -0.206597 -0.0176792 + outer loop + vertex 0.862846 2.01 2.445 + vertex 0.863902 2.015 2.445 + vertex 0.862377 2.00757 2.44748 + endloop + endfacet + facet normal 0.973598 -0.220025 -0.0607941 + outer loop + vertex 0.863902 2.015 2.445 + vertex 0.863238 2.01151 2.44701 + vertex 0.862377 2.00757 2.44748 + endloop + endfacet + facet normal 0.968703 -0.246624 0.0281309 + outer loop + vertex 0.863356 2.01156 2.44975 + vertex 0.86322 2.01138 2.45289 + vertex 0.86226 2.00756 2.45246 + endloop + endfacet + facet normal 0.957343 -0.286729 -0.0357888 + outer loop + vertex 0.863356 2.01156 2.44975 + vertex 0.86226 2.00756 2.45246 + vertex 0.863238 2.01151 2.44701 + endloop + endfacet + facet normal 0.977265 -0.210797 0.0227608 + outer loop + vertex 0.863238 2.01151 2.44701 + vertex 0.86226 2.00756 2.45246 + vertex 0.862377 2.00757 2.44748 + endloop + endfacet + facet normal 0.950855 -0.278154 0.136035 + outer loop + vertex 0.86322 2.01138 2.45289 + vertex 0.863604 2.01346 2.45445 + vertex 0.862274 2.01032 2.45732 + endloop + endfacet + facet normal 0.956028 -0.256405 0.142362 + outer loop + vertex 0.86322 2.01138 2.45289 + vertex 0.862274 2.01032 2.45732 + vertex 0.86226 2.00756 2.45246 + endloop + endfacet + facet normal 0.979086 -0.178247 0.0980728 + outer loop + vertex 0.86226 2.00756 2.45246 + vertex 0.862274 2.01032 2.45732 + vertex 0.861333 2.00538 2.45774 + endloop + endfacet + facet normal 0.965708 -0.167269 0.198567 + outer loop + vertex 0.861333 2.00538 2.45774 + vertex 0.862274 2.01032 2.45732 + vertex 0.86073 2.00598 2.46118 + endloop + endfacet + facet normal 0.960367 -0.116924 0.253028 + outer loop + vertex 0.862274 2.01032 2.45732 + vertex 0.861051 2.00982 2.46174 + vertex 0.86073 2.00598 2.46118 + endloop + endfacet + facet normal 0.941127 -0.124224 0.314401 + outer loop + vertex 0.86073 2.00598 2.46118 + vertex 0.861051 2.00982 2.46174 + vertex 0.859675 2.00681 2.46467 + endloop + endfacet + facet normal 0.930212 -0.0756273 0.359147 + outer loop + vertex 0.861051 2.00982 2.46174 + vertex 0.860056 2.01145 2.46466 + vertex 0.859675 2.00681 2.46467 + endloop + endfacet + facet normal 0.894834 -0.0725705 0.44046 + outer loop + vertex 0.860056 2.01145 2.46466 + vertex 0.858186 2.00838 2.46795 + vertex 0.859675 2.00681 2.46467 + endloop + endfacet + facet normal 0.881005 -0.0302236 0.472141 + outer loop + vertex 0.858347 2.01323 2.46796 + vertex 0.858186 2.00838 2.46795 + vertex 0.860056 2.01145 2.46466 + endloop + endfacet + facet normal 0.951656 -0.296492 0.0802763 + outer loop + vertex 0.865 2.01662 2.445 + vertex 0.863973 2.01386 2.44696 + vertex 0.863238 2.01151 2.44701 + endloop + endfacet + facet normal 0.677341 -0.459154 -0.574792 + outer loop + vertex 0.863902 2.015 2.445 + vertex 0.865 2.01662 2.445 + vertex 0.863238 2.01151 2.44701 + endloop + endfacet + facet normal 0.953515 -0.299259 -0.0353893 + outer loop + vertex 0.863973 2.01386 2.44696 + vertex 0.863356 2.01156 2.44975 + vertex 0.863238 2.01151 2.44701 + endloop + endfacet + facet normal 0.954426 -0.211972 0.210094 + outer loop + vertex 0.863604 2.01346 2.45445 + vertex 0.863273 2.01466 2.45717 + vertex 0.862274 2.01032 2.45732 + endloop + endfacet + facet normal 0.934225 -0.156083 0.320721 + outer loop + vertex 0.863273 2.01466 2.45717 + vertex 0.863437 2.01845 2.45854 + vertex 0.861907 2.01441 2.46103 + endloop + endfacet + facet normal 0.927238 -0.202056 0.315283 + outer loop + vertex 0.863273 2.01466 2.45717 + vertex 0.861907 2.01441 2.46103 + vertex 0.862274 2.01032 2.45732 + endloop + endfacet + facet normal 0.958116 -0.140076 0.249787 + outer loop + vertex 0.862274 2.01032 2.45732 + vertex 0.861907 2.01441 2.46103 + vertex 0.861051 2.00982 2.46174 + endloop + endfacet + facet normal 0.919434 -0.113353 0.376554 + outer loop + vertex 0.861051 2.00982 2.46174 + vertex 0.861907 2.01441 2.46103 + vertex 0.860056 2.01145 2.46466 + endloop + endfacet + facet normal 0.908993 -0.0635204 0.411943 + outer loop + vertex 0.861907 2.01441 2.46103 + vertex 0.860247 2.01627 2.46498 + vertex 0.860056 2.01145 2.46466 + endloop + endfacet + facet normal 0.870935 -0.0669934 0.486811 + outer loop + vertex 0.860247 2.01627 2.46498 + vertex 0.858347 2.01323 2.46796 + vertex 0.860056 2.01145 2.46466 + endloop + endfacet + facet normal 0.847757 -0.00970321 0.530295 + outer loop + vertex 0.858323 2.01803 2.46809 + vertex 0.858347 2.01323 2.46796 + vertex 0.860247 2.01627 2.46498 + endloop + endfacet + facet normal 0.908676 -0.131951 0.396101 + outer loop + vertex 0.863437 2.01845 2.45854 + vertex 0.863515 2.02235 2.45966 + vertex 0.861936 2.02011 2.46253 + endloop + endfacet + facet normal 0.915276 -0.107169 0.38831 + outer loop + vertex 0.861907 2.01441 2.46103 + vertex 0.863437 2.01845 2.45854 + vertex 0.861936 2.02011 2.46253 + endloop + endfacet + facet normal 0.894287 -0.118466 0.431528 + outer loop + vertex 0.861907 2.01441 2.46103 + vertex 0.861936 2.02011 2.46253 + vertex 0.860247 2.01627 2.46498 + endloop + endfacet + facet normal 0.855275 -0.0474927 0.515993 + outer loop + vertex 0.861936 2.02011 2.46253 + vertex 0.860011 2.02044 2.46575 + vertex 0.860247 2.01627 2.46498 + endloop + endfacet + facet normal 0.834825 -0.0545493 0.547807 + outer loop + vertex 0.860011 2.02044 2.46575 + vertex 0.858323 2.01803 2.46809 + vertex 0.860247 2.01627 2.46498 + endloop + endfacet + facet normal 0.813983 -0.00789933 0.580835 + outer loop + vertex 0.858298 2.02295 2.46819 + vertex 0.858323 2.01803 2.46809 + vertex 0.860011 2.02044 2.46575 + endloop + endfacet + facet normal 0.900987 -0.0905136 0.4243 + outer loop + vertex 0.863515 2.02235 2.45966 + vertex 0.862713 2.02441 2.4618 + vertex 0.861936 2.02011 2.46253 + endloop + endfacet + facet normal 0.84675 -0.0417688 0.530349 + outer loop + vertex 0.862713 2.02441 2.4618 + vertex 0.86264 2.02858 2.46225 + vertex 0.860719 2.02499 2.46503 + endloop + endfacet + facet normal 0.844211 -0.0618958 0.532425 + outer loop + vertex 0.862713 2.02441 2.4618 + vertex 0.860719 2.02499 2.46503 + vertex 0.861936 2.02011 2.46253 + endloop + endfacet + facet normal 0.854974 -0.0509067 0.516166 + outer loop + vertex 0.861936 2.02011 2.46253 + vertex 0.860719 2.02499 2.46503 + vertex 0.860011 2.02044 2.46575 + endloop + endfacet + facet normal 0.80259 -0.0301314 0.59577 + outer loop + vertex 0.860719 2.02499 2.46503 + vertex 0.858298 2.02295 2.46819 + vertex 0.860011 2.02044 2.46575 + endloop + endfacet + facet normal 0.818953 -0.0959502 0.565783 + outer loop + vertex 0.858411 2.02879 2.46902 + vertex 0.858298 2.02295 2.46819 + vertex 0.860719 2.02499 2.46503 + endloop + endfacet + facet normal 0.873389 -0.0466597 0.484782 + outer loop + vertex 0.86264 2.02858 2.46225 + vertex 0.862744 2.03353 2.46254 + vertex 0.860749 2.03085 2.46587 + endloop + endfacet + facet normal 0.863792 -0.0759069 0.498098 + outer loop + vertex 0.860719 2.02499 2.46503 + vertex 0.86264 2.02858 2.46225 + vertex 0.860749 2.03085 2.46587 + endloop + endfacet + facet normal 0.825267 -0.0843608 0.558406 + outer loop + vertex 0.860749 2.03085 2.46587 + vertex 0.858411 2.02879 2.46902 + vertex 0.860719 2.02499 2.46503 + endloop + endfacet + facet normal 0.843768 -0.382814 0.376177 + outer loop + vertex 0.86 2.035 2.47177 + vertex 0.858411 2.02879 2.46902 + vertex 0.860749 2.03085 2.46587 + endloop + endfacet + facet normal 0.894811 -0.0457509 0.444094 + outer loop + vertex 0.862744 2.03353 2.46254 + vertex 0.862949 2.03845 2.46263 + vertex 0.861008 2.03601 2.46629 + endloop + endfacet + facet normal 0.882932 -0.0816829 0.462341 + outer loop + vertex 0.860749 2.03085 2.46587 + vertex 0.862744 2.03353 2.46254 + vertex 0.861008 2.03601 2.46629 + endloop + endfacet + facet normal 0.983568 -0.0629955 0.169191 + outer loop + vertex 0.861008 2.03601 2.46629 + vertex 0.86 2.035 2.47177 + vertex 0.860749 2.03085 2.46587 + endloop + endfacet + facet normal 0.983614 -0.0032405 0.180256 + outer loop + vertex 0.86 2.04 2.47186 + vertex 0.86 2.035 2.47177 + vertex 0.861008 2.03601 2.46629 + endloop + endfacet + facet normal 0.887599 -0.0192688 0.460213 + outer loop + vertex 0.862949 2.03845 2.46263 + vertex 0.863033 2.0434 2.46267 + vertex 0.861153 2.04085 2.46619 + endloop + endfacet + facet normal 0.88811 -0.017525 0.459297 + outer loop + vertex 0.861008 2.03601 2.46629 + vertex 0.862949 2.03845 2.46263 + vertex 0.861153 2.04085 2.46619 + endloop + endfacet + facet normal 0.980353 -0.0255076 0.195595 + outer loop + vertex 0.861153 2.04085 2.46619 + vertex 0.86 2.04 2.47186 + vertex 0.861008 2.03601 2.46629 + endloop + endfacet + facet normal 0.97977 0.00519892 0.200058 + outer loop + vertex 0.86 2.045 2.47173 + vertex 0.86 2.04 2.47186 + vertex 0.861153 2.04085 2.46619 + endloop + endfacet + facet normal 0.86735 -0.000720978 0.497699 + outer loop + vertex 0.863033 2.0434 2.46267 + vertex 0.862864 2.04851 2.46297 + vertex 0.861093 2.04572 2.46606 + endloop + endfacet + facet normal 0.87437 0.0241681 0.484657 + outer loop + vertex 0.861153 2.04085 2.46619 + vertex 0.863033 2.0434 2.46267 + vertex 0.861093 2.04572 2.46606 + endloop + endfacet + facet normal 0.981373 0.0172752 0.191332 + outer loop + vertex 0.861093 2.04572 2.46606 + vertex 0.86 2.045 2.47173 + vertex 0.861153 2.04085 2.46619 + endloop + endfacet + facet normal 0.98064 0.0324417 0.193113 + outer loop + vertex 0.86 2.05 2.47089 + vertex 0.86 2.045 2.47173 + vertex 0.861093 2.04572 2.46606 + endloop + endfacet + facet normal 0.833634 -0.0784796 0.546713 + outer loop + vertex 0.862864 2.04851 2.46297 + vertex 0.862488 2.05424 2.46437 + vertex 0.860794 2.05062 2.46643 + endloop + endfacet + facet normal 0.861651 0.0135457 0.50732 + outer loop + vertex 0.861093 2.04572 2.46606 + vertex 0.862864 2.04851 2.46297 + vertex 0.860794 2.05062 2.46643 + endloop + endfacet + facet normal 0.982328 0.0460901 0.181406 + outer loop + vertex 0.860794 2.05062 2.46643 + vertex 0.86 2.05 2.47089 + vertex 0.861093 2.04572 2.46606 + endloop + endfacet + facet normal 0.983218 0.0319704 0.17961 + outer loop + vertex 0.86 2.055 2.47 + vertex 0.86 2.05 2.47089 + vertex 0.860794 2.05062 2.46643 + endloop + endfacet + facet normal 0.890588 -0.17825 0.418425 + outer loop + vertex 0.86 2.05502 2.47 + vertex 0.860794 2.05062 2.46643 + vertex 0.862488 2.05424 2.46437 + endloop + endfacet + facet normal 0.915964 0.0690552 0.395274 + outer loop + vertex 0.86 2.05502 2.47 + vertex 0.862488 2.05424 2.46437 + vertex 0.86 2.06 2.46913 + endloop + endfacet + facet normal 0.454598 -0.442258 0.773142 + outer loop + vertex 0.86 2.06 2.46913 + vertex 0.862488 2.05424 2.46437 + vertex 0.865 2.06 2.46619 + endloop + endfacet + facet normal 0.976099 0 0.217328 + outer loop + vertex 0.86 2.055 2.47 + vertex 0.860794 2.05062 2.46643 + vertex 0.86 2.05502 2.47 + endloop + endfacet + facet normal 0.81627 -0.525751 -0.239351 + outer loop + vertex 0.86 2.05832 2.475 + vertex 0.86 2.06 2.47131 + vertex 0.861082 2.06 2.475 + endloop + endfacet + facet normal 0.83886 -0.5403 -0.0662494 + outer loop + vertex 0.860501 2.05899 2.47586 + vertex 0.86 2.05832 2.475 + vertex 0.861082 2.06 2.475 + endloop + endfacet + facet normal 0.874139 -0.462823 -0.147225 + outer loop + vertex 0.858747 2.05482 2.47857 + vertex 0.86 2.05832 2.475 + vertex 0.860501 2.05899 2.47586 + endloop + endfacet + facet normal 0.936751 -0.340242 0.0820509 + outer loop + vertex 0.859792 2.05803 2.47996 + vertex 0.858747 2.05482 2.47857 + vertex 0.860501 2.05899 2.47586 + endloop + endfacet + facet normal 0.902345 -0.38092 0.201679 + outer loop + vertex 0.85793 2.05513 2.48281 + vertex 0.858747 2.05482 2.47857 + vertex 0.859792 2.05803 2.47996 + endloop + endfacet + facet normal 0.897592 -0.405057 0.173948 + outer loop + vertex 0.859104 2.05823 2.48399 + vertex 0.85793 2.05513 2.48281 + vertex 0.859792 2.05803 2.47996 + endloop + endfacet + facet normal 0.780072 -0.456807 0.42757 + outer loop + vertex 0.857534 2.0567 2.48521 + vertex 0.85793 2.05513 2.48281 + vertex 0.859104 2.05823 2.48399 + endloop + endfacet + facet normal 0.776702 -0.420069 0.469335 + outer loop + vertex 0.859104 2.05823 2.48399 + vertex 0.858305 2.059 2.48599 + vertex 0.857534 2.0567 2.48521 + endloop + endfacet + facet normal 0.904331 -0.404043 0.137601 + outer loop + vertex 0.861082 2.06 2.475 + vertex 0.863316 2.065 2.475 + vertex 0.860501 2.05899 2.47586 + endloop + endfacet + facet normal 0.868056 -0.357392 0.344601 + outer loop + vertex 0.863316 2.065 2.475 + vertex 0.861565 2.06266 2.47698 + vertex 0.860501 2.05899 2.47586 + endloop + endfacet + facet normal 0.948254 -0.303707 0.092607 + outer loop + vertex 0.860501 2.05899 2.47586 + vertex 0.861565 2.06266 2.47698 + vertex 0.859792 2.05803 2.47996 + endloop + endfacet + facet normal 0.951846 -0.255993 0.168692 + outer loop + vertex 0.861565 2.06266 2.47698 + vertex 0.860559 2.06176 2.4813 + vertex 0.859792 2.05803 2.47996 + endloop + endfacet + facet normal 0.95006 -0.258057 0.175477 + outer loop + vertex 0.859792 2.05803 2.47996 + vertex 0.860559 2.06176 2.4813 + vertex 0.859104 2.05823 2.48399 + endloop + endfacet + facet normal 0.942924 -0.171529 0.285433 + outer loop + vertex 0.860559 2.06176 2.4813 + vertex 0.859483 2.06174 2.48484 + vertex 0.859104 2.05823 2.48399 + endloop + endfacet + facet normal 0.881894 -0.199427 0.427191 + outer loop + vertex 0.859483 2.06174 2.48484 + vertex 0.858305 2.059 2.48599 + vertex 0.859104 2.05823 2.48399 + endloop + endfacet + facet normal 0.6509 0.0390292 0.758159 + outer loop + vertex 0.858075 2.06201 2.48604 + vertex 0.858305 2.059 2.48599 + vertex 0.859483 2.06174 2.48484 + endloop + endfacet + facet normal 0.821924 -0.149924 0.549512 + outer loop + vertex 0.863316 2.065 2.475 + vertex 0.864228 2.07 2.475 + vertex 0.861565 2.06266 2.47698 + endloop + endfacet + facet normal 0.871373 -0.194575 0.450389 + outer loop + vertex 0.864228 2.07 2.475 + vertex 0.862065 2.06683 2.47782 + vertex 0.861565 2.06266 2.47698 + endloop + endfacet + facet normal 0.968811 -0.154807 0.193493 + outer loop + vertex 0.861565 2.06266 2.47698 + vertex 0.862065 2.06683 2.47782 + vertex 0.860559 2.06176 2.4813 + endloop + endfacet + facet normal 0.951493 -0.0780257 0.297614 + outer loop + vertex 0.862065 2.06683 2.47782 + vertex 0.86064 2.0658 2.4821 + vertex 0.860559 2.06176 2.4813 + endloop + endfacet + facet normal 0.954102 -0.0764859 0.28955 + outer loop + vertex 0.860559 2.06176 2.4813 + vertex 0.86064 2.0658 2.4821 + vertex 0.859483 2.06174 2.48484 + endloop + endfacet + facet normal 0.895114 0.0443179 0.44363 + outer loop + vertex 0.86064 2.0658 2.4821 + vertex 0.859262 2.06544 2.48492 + vertex 0.859483 2.06174 2.48484 + endloop + endfacet + facet normal 0.649436 0.023125 0.760064 + outer loop + vertex 0.859262 2.06544 2.48492 + vertex 0.858075 2.06201 2.48604 + vertex 0.859483 2.06174 2.48484 + endloop + endfacet + facet normal 0.337676 0.184188 0.923065 + outer loop + vertex 0.857967 2.06533 2.48541 + vertex 0.858075 2.06201 2.48604 + vertex 0.859262 2.06544 2.48492 + endloop + endfacet + facet normal 0.811897 -0.0363712 0.582667 + outer loop + vertex 0.864228 2.07 2.475 + vertex 0.864452 2.075 2.475 + vertex 0.862065 2.06683 2.47782 + endloop + endfacet + facet normal 0.859771 -0.0772057 0.50481 + outer loop + vertex 0.864452 2.075 2.475 + vertex 0.861752 2.07019 2.47886 + vertex 0.862065 2.06683 2.47782 + endloop + endfacet + facet normal 0.949527 -0.0092793 0.313548 + outer loop + vertex 0.862065 2.06683 2.47782 + vertex 0.861752 2.07019 2.47886 + vertex 0.86064 2.0658 2.4821 + endloop + endfacet + facet normal 0.877538 0.119903 0.464273 + outer loop + vertex 0.861752 2.07019 2.47886 + vertex 0.86007 2.06989 2.48212 + vertex 0.86064 2.0658 2.4821 + endloop + endfacet + facet normal 0.475601 0.518063 0.710925 + outer loop + vertex 0.858692 2.06799 2.48443 + vertex 0.86007 2.06989 2.48212 + vertex 0.858545 2.07048 2.48271 + endloop + endfacet + facet normal 0.702895 0.282419 0.652823 + outer loop + vertex 0.858692 2.06799 2.48443 + vertex 0.859262 2.06544 2.48492 + vertex 0.86007 2.06989 2.48212 + endloop + endfacet + facet normal 0.885457 0.121087 0.44867 + outer loop + vertex 0.859262 2.06544 2.48492 + vertex 0.86064 2.0658 2.4821 + vertex 0.86007 2.06989 2.48212 + endloop + endfacet + facet normal 0.32788 0.248385 0.911482 + outer loop + vertex 0.859262 2.06544 2.48492 + vertex 0.858692 2.06799 2.48443 + vertex 0.857967 2.06533 2.48541 + endloop + endfacet + facet normal 0.613655 0.708693 0.348112 + outer loop + vertex 0.864218 2.07729 2.47076 + vertex 0.863699 2.07644 2.4734 + vertex 0.864452 2.075 2.475 + endloop + endfacet + facet normal -0.947021 0.258058 0.191201 + outer loop + vertex 0.864218 2.07729 2.47076 + vertex 0.864452 2.075 2.475 + vertex 0.864805 2.08 2.47 + endloop + endfacet + facet normal 0.965066 -0.216175 -0.148043 + outer loop + vertex 0.864805 2.08 2.47 + vertex 0.864452 2.075 2.475 + vertex 0.863685 2.075 2.47 + endloop + endfacet + facet normal 0.870673 -0.392771 0.296072 + outer loop + vertex 0.863699 2.07644 2.4734 + vertex 0.863966 2.07832 2.47511 + vertex 0.861792 2.07563 2.47794 + endloop + endfacet + facet normal 0.583733 0.721045 0.373297 + outer loop + vertex 0.863699 2.07644 2.4734 + vertex 0.861792 2.07563 2.47794 + vertex 0.864452 2.075 2.475 + endloop + endfacet + facet normal 0.748653 0.105551 0.654506 + outer loop + vertex 0.864452 2.075 2.475 + vertex 0.861792 2.07563 2.47794 + vertex 0.861752 2.07019 2.47886 + endloop + endfacet + facet normal 0.255707 0.580758 0.772874 + outer loop + vertex 0.859308 2.07301 2.48073 + vertex 0.861792 2.07563 2.47794 + vertex 0.858828 2.07578 2.47881 + endloop + endfacet + facet normal 0.411288 0.452814 0.791076 + outer loop + vertex 0.859308 2.07301 2.48073 + vertex 0.86007 2.06989 2.48212 + vertex 0.861792 2.07563 2.47794 + endloop + endfacet + facet normal 0.883474 0.0720403 0.462907 + outer loop + vertex 0.86007 2.06989 2.48212 + vertex 0.861752 2.07019 2.47886 + vertex 0.861792 2.07563 2.47794 + endloop + endfacet + facet normal 0.468699 0.45243 0.758701 + outer loop + vertex 0.86007 2.06989 2.48212 + vertex 0.859308 2.07301 2.48073 + vertex 0.858545 2.07048 2.48271 + endloop + endfacet + facet normal 0.418935 -0.326681 -0.847215 + outer loop + vertex 0.865 2.08025 2.47 + vertex 0.864218 2.07729 2.47076 + vertex 0.864805 2.08 2.47 + endloop + endfacet + facet normal 0.86959 -0.402525 0.285984 + outer loop + vertex 0.863966 2.07832 2.47511 + vertex 0.863752 2.07961 2.47758 + vertex 0.861792 2.07563 2.47794 + endloop + endfacet + facet normal 0.284957 0.149169 0.946862 + outer loop + vertex 0.861792 2.07563 2.47794 + vertex 0.859689 2.08 2.47788 + vertex 0.858828 2.07578 2.47881 + endloop + endfacet + facet normal -0.36386 -0.163342 0.91702 + outer loop + vertex 0.861792 2.07563 2.47794 + vertex 0.862539 2.08072 2.47914 + vertex 0.859689 2.08 2.47788 + endloop + endfacet + facet normal 0.661896 -0.26294 0.701966 + outer loop + vertex 0.861792 2.07563 2.47794 + vertex 0.863752 2.07961 2.47758 + vertex 0.862539 2.08072 2.47914 + endloop + endfacet + facet normal -0.373075 -0.129818 0.918674 + outer loop + vertex 0.86161 2.08389 2.47921 + vertex 0.859689 2.08 2.47788 + vertex 0.862539 2.08072 2.47914 + endloop + endfacet + facet normal -0.470839 -0.157403 0.868064 + outer loop + vertex 0.862539 2.08072 2.47914 + vertex 0.863433 2.08362 2.48015 + vertex 0.86161 2.08389 2.47921 + endloop + endfacet + facet normal -0.775107 0.2571 0.577155 + outer loop + vertex 0.860345 2.08697 2.47688 + vertex 0.858515 2.08613 2.4748 + vertex 0.859456 2.08389 2.47705 + endloop + endfacet + facet normal -0.703628 0.107715 0.702357 + outer loop + vertex 0.859456 2.08389 2.47705 + vertex 0.859689 2.08 2.47788 + vertex 0.86161 2.08389 2.47921 + endloop + endfacet + facet normal -0.687203 0.237831 0.686431 + outer loop + vertex 0.859456 2.08389 2.47705 + vertex 0.86161 2.08389 2.47921 + vertex 0.860345 2.08697 2.47688 + endloop + endfacet + facet normal -0.722663 0.203624 0.660526 + outer loop + vertex 0.860345 2.08697 2.47688 + vertex 0.86161 2.08389 2.47921 + vertex 0.862494 2.08738 2.4791 + endloop + endfacet + facet normal -0.678299 0.193907 0.708739 + outer loop + vertex 0.86161 2.08389 2.47921 + vertex 0.863281 2.0855 2.48037 + vertex 0.862494 2.08738 2.4791 + endloop + endfacet + facet normal -0.469973 -0.139315 0.871617 + outer loop + vertex 0.863433 2.08362 2.48015 + vertex 0.863281 2.0855 2.48037 + vertex 0.86161 2.08389 2.47921 + endloop + endfacet + facet normal -0.772215 0.317981 0.550065 + outer loop + vertex 0.858978 2.08965 2.47341 + vertex 0.858515 2.08613 2.4748 + vertex 0.860345 2.08697 2.47688 + endloop + endfacet + facet normal -0.762437 0.330795 0.556115 + outer loop + vertex 0.861483 2.09141 2.4758 + vertex 0.858978 2.08965 2.47341 + vertex 0.860345 2.08697 2.47688 + endloop + endfacet + facet normal -0.521537 0.45726 0.720355 + outer loop + vertex 0.864409 2.08999 2.47883 + vertex 0.862494 2.08738 2.4791 + vertex 0.863805 2.08713 2.48021 + endloop + endfacet + facet normal -0.523098 0.458222 0.71861 + outer loop + vertex 0.864409 2.08999 2.47883 + vertex 0.861483 2.09141 2.4758 + vertex 0.862494 2.08738 2.4791 + endloop + endfacet + facet normal -0.708144 0.333102 0.622555 + outer loop + vertex 0.861483 2.09141 2.4758 + vertex 0.860345 2.08697 2.47688 + vertex 0.862494 2.08738 2.4791 + endloop + endfacet + facet normal -0.59186 0.265398 0.761095 + outer loop + vertex 0.863805 2.08713 2.48021 + vertex 0.862494 2.08738 2.4791 + vertex 0.863281 2.0855 2.48037 + endloop + endfacet + facet normal -0.807419 0.320732 0.495183 + outer loop + vertex 0.86107 2.09764 2.47187 + vertex 0.858845 2.096 2.4693 + vertex 0.859493 2.09347 2.472 + endloop + endfacet + facet normal -0.761175 0.31261 0.568233 + outer loop + vertex 0.859493 2.09347 2.472 + vertex 0.858978 2.08965 2.47341 + vertex 0.861483 2.09141 2.4758 + endloop + endfacet + facet normal -0.764576 0.306764 0.566851 + outer loop + vertex 0.86107 2.09764 2.47187 + vertex 0.859493 2.09347 2.472 + vertex 0.861483 2.09141 2.4758 + endloop + endfacet + facet normal -0.694483 0.35028 0.628487 + outer loop + vertex 0.86107 2.09764 2.47187 + vertex 0.861483 2.09141 2.4758 + vertex 0.864132 2.09517 2.47663 + endloop + endfacet + facet normal -0.773046 0.200989 0.601667 + outer loop + vertex 0.86107 2.09764 2.47187 + vertex 0.864132 2.09517 2.47663 + vertex 0.863245 2.09796 2.47456 + endloop + endfacet + facet normal -0.623472 0.277633 0.730891 + outer loop + vertex 0.864132 2.09517 2.47663 + vertex 0.861483 2.09141 2.4758 + vertex 0.864409 2.08999 2.47883 + endloop + endfacet + facet normal -0.875001 0.292496 0.385771 + outer loop + vertex 0.85976 2.10205 2.46726 + vertex 0.858446 2.10104 2.46504 + vertex 0.858932 2.09888 2.46779 + endloop + endfacet + facet normal -0.807113 0.294163 0.511896 + outer loop + vertex 0.858932 2.09888 2.46779 + vertex 0.858845 2.096 2.4693 + vertex 0.86107 2.09764 2.47187 + endloop + endfacet + facet normal -0.806508 0.295609 0.512017 + outer loop + vertex 0.858932 2.09888 2.46779 + vertex 0.86107 2.09764 2.47187 + vertex 0.85976 2.10205 2.46726 + endloop + endfacet + facet normal -0.800112 0.303276 0.517537 + outer loop + vertex 0.85976 2.10205 2.46726 + vertex 0.86107 2.09764 2.47187 + vertex 0.861738 2.10292 2.46981 + endloop + endfacet + facet normal -0.760584 0.317356 0.566389 + outer loop + vertex 0.86107 2.09764 2.47187 + vertex 0.863358 2.10056 2.4733 + vertex 0.861738 2.10292 2.46981 + endloop + endfacet + facet normal -0.756812 0.309946 0.575474 + outer loop + vertex 0.863245 2.09796 2.47456 + vertex 0.863358 2.10056 2.4733 + vertex 0.86107 2.09764 2.47187 + endloop + endfacet + facet normal -0.872118 0.31645 0.373189 + outer loop + vertex 0.859022 2.10455 2.46342 + vertex 0.858446 2.10104 2.46504 + vertex 0.85976 2.10205 2.46726 + endloop + endfacet + facet normal -0.843674 0.361441 0.396956 + outer loop + vertex 0.860874 2.10655 2.46553 + vertex 0.859022 2.10455 2.46342 + vertex 0.85976 2.10205 2.46726 + endloop + endfacet + facet normal -0.747836 0.366021 0.553868 + outer loop + vertex 0.862707 2.1062 2.46895 + vertex 0.861738 2.10292 2.46981 + vertex 0.863699 2.10396 2.47177 + endloop + endfacet + facet normal -0.806046 0.36099 0.469016 + outer loop + vertex 0.862707 2.1062 2.46895 + vertex 0.860874 2.10655 2.46553 + vertex 0.861738 2.10292 2.46981 + endloop + endfacet + facet normal -0.78894 0.38073 0.482306 + outer loop + vertex 0.860874 2.10655 2.46553 + vertex 0.85976 2.10205 2.46726 + vertex 0.861738 2.10292 2.46981 + endloop + endfacet + facet normal -0.74916 0.333743 0.572166 + outer loop + vertex 0.863699 2.10396 2.47177 + vertex 0.861738 2.10292 2.46981 + vertex 0.863358 2.10056 2.4733 + endloop + endfacet + facet normal -0.479247 0.263716 0.837124 + outer loop + vertex 0.861788 2.11187 2.46146 + vertex 0.860963 2.115 2.46 + vertex 0.86 2.11325 2.46 + endloop + endfacet + facet normal -0.443897 0.312443 0.839842 + outer loop + vertex 0.859865 2.10844 2.46172 + vertex 0.861788 2.11187 2.46146 + vertex 0.86 2.11325 2.46 + endloop + endfacet + facet normal -0.84361 0.357579 0.400575 + outer loop + vertex 0.859865 2.10844 2.46172 + vertex 0.859022 2.10455 2.46342 + vertex 0.860874 2.10655 2.46553 + endloop + endfacet + facet normal -0.771359 0.46496 0.434532 + outer loop + vertex 0.861788 2.11187 2.46146 + vertex 0.859865 2.10844 2.46172 + vertex 0.860874 2.10655 2.46553 + endloop + endfacet + facet normal -0.79599 0.448093 0.406955 + outer loop + vertex 0.861788 2.11187 2.46146 + vertex 0.860874 2.10655 2.46553 + vertex 0.862958 2.10948 2.46638 + endloop + endfacet + facet normal -0.81411 0.42223 0.398681 + outer loop + vertex 0.861788 2.11187 2.46146 + vertex 0.862958 2.10948 2.46638 + vertex 0.863207 2.11185 2.46438 + endloop + endfacet + facet normal -0.780721 0.421196 0.461593 + outer loop + vertex 0.862958 2.10948 2.46638 + vertex 0.860874 2.10655 2.46553 + vertex 0.862707 2.1062 2.46895 + endloop + endfacet + facet normal 0.439598 0.83161 0.339379 + outer loop + vertex 0.86 2.115 2.45772 + vertex 0.8621 2.115 2.455 + vertex 0.86 2.11611 2.455 + endloop + endfacet + facet normal -0.601813 -0.424095 -0.67673 + outer loop + vertex 0.865 2.115 2.45641 + vertex 0.860963 2.115 2.46 + vertex 0.865 2.11725 2.455 + endloop + endfacet + facet normal -0.632704 -0.372963 -0.678663 + outer loop + vertex 0.860963 2.115 2.46 + vertex 0.863379 2.12 2.455 + vertex 0.865 2.11725 2.455 + endloop + endfacet + facet normal 0.631239 0.374299 0.679291 + outer loop + vertex 0.860963 2.115 2.46 + vertex 0.863034 2.11639 2.45731 + vertex 0.863379 2.12 2.455 + endloop + endfacet + facet normal -0.736386 0.554511 0.387626 + outer loop + vertex 0.863645 2.11528 2.46011 + vertex 0.861788 2.11187 2.46146 + vertex 0.863727 2.11343 2.46291 + endloop + endfacet + facet normal -0.740137 0.553996 0.381164 + outer loop + vertex 0.863645 2.11528 2.46011 + vertex 0.863034 2.11639 2.45731 + vertex 0.861788 2.11187 2.46146 + endloop + endfacet + facet normal 0.568316 0.465873 0.678218 + outer loop + vertex 0.863034 2.11639 2.45731 + vertex 0.860963 2.115 2.46 + vertex 0.861788 2.11187 2.46146 + endloop + endfacet + facet normal -0.733544 0.575875 0.360946 + outer loop + vertex 0.863727 2.11343 2.46291 + vertex 0.861788 2.11187 2.46146 + vertex 0.863207 2.11185 2.46438 + endloop + endfacet + facet normal -0.484422 0.747863 -0.453912 + outer loop + vertex 0.865 2.12 2.45327 + vertex 0.863379 2.12 2.455 + vertex 0.865 2.12105 2.455 + endloop + endfacet + facet normal -0.913766 0.404458 0.038012 + outer loop + vertex 0.865 2.12105 2.455 + vertex 0.863034 2.11639 2.45731 + vertex 0.865 2.12058 2.46 + endloop + endfacet + facet normal -0.342855 0.529307 0.77607 + outer loop + vertex 0.863379 2.12 2.455 + vertex 0.863034 2.11639 2.45731 + vertex 0.865 2.12105 2.455 + endloop + endfacet + facet normal -0.923476 0.242272 0.297484 + outer loop + vertex 0.865 2.12058 2.46 + vertex 0.863034 2.11639 2.45731 + vertex 0.863645 2.11528 2.46011 + endloop + endfacet + facet normal -0.33952 -0.829113 -0.444181 + outer loop + vertex 0.87 0.91 2.45636 + vertex 0.87 0.90805 2.46 + vertex 0.865238 0.91 2.46 + endloop + endfacet + facet normal 0.389748 -0.880667 0.2693 + outer loop + vertex 0.86822 0.91 2.455 + vertex 0.865 0.91 2.45966 + vertex 0.865 0.908575 2.455 + endloop + endfacet + facet normal -0.378862 -0.925188 0.022171 + outer loop + vertex 0.869471 0.908306 2.46163 + vertex 0.865238 0.91 2.46 + vertex 0.87 0.90805 2.46 + endloop + endfacet + facet normal -0.478393 -0.740104 0.472639 + outer loop + vertex 0.866509 0.909662 2.46076 + vertex 0.865238 0.91 2.46 + vertex 0.869471 0.908306 2.46163 + endloop + endfacet + facet normal -0.465048 -0.844641 0.265165 + outer loop + vertex 0.869471 0.908306 2.46163 + vertex 0.867879 0.909874 2.46384 + vertex 0.866509 0.909662 2.46076 + endloop + endfacet + facet normal -0.539826 -0.478867 0.692296 + outer loop + vertex 0.865238 0.91 2.46 + vertex 0.866509 0.909662 2.46076 + vertex 0.864593 0.91171 2.46068 + endloop + endfacet + facet normal -0.719934 -0.473357 0.50757 + outer loop + vertex 0.865 0.910362 2.46 + vertex 0.865238 0.91 2.46 + vertex 0.864593 0.91171 2.46068 + endloop + endfacet + facet normal -0.744362 -0.556127 0.369659 + outer loop + vertex 0.867487 0.91141 2.46691 + vertex 0.865899 0.914243 2.46798 + vertex 0.86502 0.913028 2.46438 + endloop + endfacet + facet normal -0.696173 -0.673835 0.247567 + outer loop + vertex 0.867879 0.909874 2.46384 + vertex 0.867487 0.91141 2.46691 + vertex 0.86502 0.913028 2.46438 + endloop + endfacet + facet normal -0.675341 -0.666646 0.315432 + outer loop + vertex 0.867879 0.909874 2.46384 + vertex 0.86502 0.913028 2.46438 + vertex 0.864593 0.91171 2.46068 + endloop + endfacet + facet normal -0.690371 -0.632702 0.350822 + outer loop + vertex 0.867879 0.909874 2.46384 + vertex 0.864593 0.91171 2.46068 + vertex 0.866509 0.909662 2.46076 + endloop + endfacet + facet normal -0.691222 -0.559321 0.457571 + outer loop + vertex 0.869402 0.911639 2.47009 + vertex 0.865899 0.914243 2.46798 + vertex 0.867487 0.91141 2.46691 + endloop + endfacet + facet normal -0.690926 -0.542581 0.477731 + outer loop + vertex 0.867584 0.91472 2.47096 + vertex 0.865899 0.914243 2.46798 + vertex 0.869402 0.911639 2.47009 + endloop + endfacet + facet normal -0.656224 -0.536921 0.530176 + outer loop + vertex 0.869402 0.911639 2.47009 + vertex 0.87047 0.913565 2.47336 + vertex 0.867584 0.91472 2.47096 + endloop + endfacet + facet normal -0.780866 -0.508713 0.362573 + outer loop + vertex 0.86502 0.913028 2.46438 + vertex 0.865899 0.914243 2.46798 + vertex 0.863646 0.915975 2.46555 + endloop + endfacet + facet normal -0.789545 -0.461755 0.404228 + outer loop + vertex 0.864105 0.917245 2.4679 + vertex 0.863646 0.915975 2.46555 + vertex 0.865899 0.914243 2.46798 + endloop + endfacet + facet normal -0.772097 -0.450245 0.448493 + outer loop + vertex 0.864105 0.917245 2.4679 + vertex 0.865899 0.914243 2.46798 + vertex 0.865666 0.916734 2.47008 + endloop + endfacet + facet normal -0.72829 -0.480209 0.488869 + outer loop + vertex 0.865666 0.916734 2.47008 + vertex 0.865899 0.914243 2.46798 + vertex 0.867584 0.91472 2.47096 + endloop + endfacet + facet normal -0.711722 -0.438143 0.549075 + outer loop + vertex 0.867584 0.91472 2.47096 + vertex 0.867545 0.918103 2.47361 + vertex 0.865666 0.916734 2.47008 + endloop + endfacet + facet normal -0.669164 -0.462898 0.581331 + outer loop + vertex 0.87047 0.913565 2.47336 + vertex 0.867545 0.918103 2.47361 + vertex 0.867584 0.91472 2.47096 + endloop + endfacet + facet normal -0.789872 -0.386377 0.476251 + outer loop + vertex 0.864105 0.917245 2.4679 + vertex 0.865666 0.916734 2.47008 + vertex 0.864312 0.919765 2.47029 + endloop + endfacet + facet normal -0.703653 -0.380301 0.600203 + outer loop + vertex 0.86731 0.921895 2.47594 + vertex 0.866425 0.923669 2.47602 + vertex 0.865289 0.922232 2.47378 + endloop + endfacet + facet normal -0.697425 -0.40639 0.590292 + outer loop + vertex 0.867545 0.918103 2.47361 + vertex 0.86731 0.921895 2.47594 + vertex 0.865289 0.922232 2.47378 + endloop + endfacet + facet normal -0.74473 -0.428856 0.511332 + outer loop + vertex 0.867545 0.918103 2.47361 + vertex 0.865289 0.922232 2.47378 + vertex 0.864312 0.919765 2.47029 + endloop + endfacet + facet normal -0.750701 -0.373663 0.544815 + outer loop + vertex 0.867545 0.918103 2.47361 + vertex 0.864312 0.919765 2.47029 + vertex 0.865666 0.916734 2.47008 + endloop + endfacet + facet normal -0.480123 -0.280015 0.831308 + outer loop + vertex 0.86731 0.921895 2.47594 + vertex 0.868839 0.925109 2.4779 + vertex 0.866425 0.923669 2.47602 + endloop + endfacet + facet normal -0.735471 -0.336357 0.588173 + outer loop + vertex 0.865289 0.922232 2.47378 + vertex 0.866425 0.923669 2.47602 + vertex 0.865183 0.925541 2.47554 + endloop + endfacet + facet normal -0.679793 -0.0522177 0.731543 + outer loop + vertex 0.867871 0.927685 2.47963 + vertex 0.867433 0.929635 2.47936 + vertex 0.866186 0.928341 2.47811 + endloop + endfacet + facet normal -0.660454 -0.573013 0.48524 + outer loop + vertex 0.868839 0.925109 2.4779 + vertex 0.867871 0.927685 2.47963 + vertex 0.866186 0.928341 2.47811 + endloop + endfacet + facet normal -0.517424 -0.470116 0.715026 + outer loop + vertex 0.868839 0.925109 2.4779 + vertex 0.866186 0.928341 2.47811 + vertex 0.865183 0.925541 2.47554 + endloop + endfacet + facet normal -0.548923 -0.152423 0.821858 + outer loop + vertex 0.868839 0.925109 2.4779 + vertex 0.865183 0.925541 2.47554 + vertex 0.866425 0.923669 2.47602 + endloop + endfacet + facet normal -0.739348 -0.0741835 0.669225 + outer loop + vertex 0.867871 0.927685 2.47963 + vertex 0.868229 0.928386 2.4801 + vertex 0.867433 0.929635 2.47936 + endloop + endfacet + facet normal -0.0951777 -0.135808 0.986153 + outer loop + vertex 0.87 0.934241 2.465 + vertex 0.868917 0.935 2.465 + vertex 0.870101 0.933014 2.46484 + endloop + endfacet + facet normal 0.876165 0.319898 0.360556 + outer loop + vertex 0.868197 0.932023 2.47711 + vertex 0.868439 0.935132 2.47376 + vertex 0.866987 0.936511 2.47607 + endloop + endfacet + facet normal 0.344426 0.583469 0.735483 + outer loop + vertex 0.867433 0.929635 2.47936 + vertex 0.868608 0.92919 2.47916 + vertex 0.868197 0.932023 2.47711 + endloop + endfacet + facet normal 0.497284 0.505737 0.704939 + outer loop + vertex 0.867433 0.929635 2.47936 + vertex 0.868197 0.932023 2.47711 + vertex 0.865368 0.93328 2.4782 + endloop + endfacet + facet normal -0.6384 -0.119943 0.760302 + outer loop + vertex 0.867433 0.929635 2.47936 + vertex 0.865368 0.93328 2.4782 + vertex 0.866186 0.928341 2.47811 + endloop + endfacet + facet normal 0.461199 0.316735 0.828839 + outer loop + vertex 0.865368 0.93328 2.4782 + vertex 0.868197 0.932023 2.47711 + vertex 0.866987 0.936511 2.47607 + endloop + endfacet + facet normal 0.355438 0.634428 0.686415 + outer loop + vertex 0.868608 0.92919 2.47916 + vertex 0.867433 0.929635 2.47936 + vertex 0.868229 0.928386 2.4801 + endloop + endfacet + facet normal 0.843376 0.51504 -0.153137 + outer loop + vertex 0.86915 0.934979 2.46621 + vertex 0.870101 0.933014 2.46484 + vertex 0.868917 0.935 2.465 + endloop + endfacet + facet normal 0.93789 0.299541 -0.175037 + outer loop + vertex 0.86915 0.934979 2.46621 + vertex 0.868917 0.935 2.465 + vertex 0.867953 0.938951 2.46659 + endloop + endfacet + facet normal 0.918001 0.0662735 0.391001 + outer loop + vertex 0.867953 0.938951 2.46659 + vertex 0.868917 0.935 2.465 + vertex 0.868556 0.94 2.465 + endloop + endfacet + facet normal 0.9576 0.288019 0.00690778 + outer loop + vertex 0.868967 0.935503 2.46976 + vertex 0.86915 0.934979 2.46621 + vertex 0.867953 0.938951 2.46659 + endloop + endfacet + facet normal 0.939182 0.336988 0.0661529 + outer loop + vertex 0.867522 0.939159 2.47165 + vertex 0.868967 0.935503 2.46976 + vertex 0.867953 0.938951 2.46659 + endloop + endfacet + facet normal 0.943537 0.294442 0.151798 + outer loop + vertex 0.868439 0.935132 2.47376 + vertex 0.868967 0.935503 2.46976 + vertex 0.867522 0.939159 2.47165 + endloop + endfacet + facet normal 0.869843 0.369485 0.326887 + outer loop + vertex 0.868439 0.935132 2.47376 + vertex 0.867522 0.939159 2.47165 + vertex 0.866987 0.936511 2.47607 + endloop + endfacet + facet normal 0.961436 0.168431 0.217419 + outer loop + vertex 0.866987 0.936511 2.47607 + vertex 0.867522 0.939159 2.47165 + vertex 0.866501 0.940521 2.47511 + endloop + endfacet + facet normal 0.631947 -0.00780575 0.774972 + outer loop + vertex 0.865368 0.93328 2.4782 + vertex 0.865264 0.939138 2.47835 + vertex 0.863775 0.937211 2.47954 + endloop + endfacet + facet normal 0.797344 -0.000662776 0.603525 + outer loop + vertex 0.865368 0.93328 2.4782 + vertex 0.866987 0.936511 2.47607 + vertex 0.865264 0.939138 2.47835 + endloop + endfacet + facet normal 0.880607 0.208416 0.425551 + outer loop + vertex 0.866987 0.936511 2.47607 + vertex 0.866501 0.940521 2.47511 + vertex 0.865264 0.939138 2.47835 + endloop + endfacet + facet normal 0.739622 -0.167226 0.651916 + outer loop + vertex 0.865264 0.939138 2.47835 + vertex 0.86381 0.940081 2.48024 + vertex 0.863775 0.937211 2.47954 + endloop + endfacet + facet normal 0.82976 0.267348 0.489922 + outer loop + vertex 0.868556 0.94 2.465 + vertex 0.866945 0.945 2.465 + vertex 0.867953 0.938951 2.46659 + endloop + endfacet + facet normal 0.965873 0.203224 0.160593 + outer loop + vertex 0.866945 0.945 2.465 + vertex 0.866827 0.942961 2.46829 + vertex 0.867953 0.938951 2.46659 + endloop + endfacet + facet normal 0.967809 0.241001 0.0725519 + outer loop + vertex 0.867953 0.938951 2.46659 + vertex 0.866827 0.942961 2.46829 + vertex 0.867522 0.939159 2.47165 + endloop + endfacet + facet normal 0.970194 0.233763 0.0638686 + outer loop + vertex 0.866827 0.942961 2.46829 + vertex 0.866374 0.943787 2.47214 + vertex 0.867522 0.939159 2.47165 + endloop + endfacet + facet normal 0.956261 0.216133 0.197105 + outer loop + vertex 0.867522 0.939159 2.47165 + vertex 0.866374 0.943787 2.47214 + vertex 0.866501 0.940521 2.47511 + endloop + endfacet + facet normal 0.960656 0.206242 0.186022 + outer loop + vertex 0.866374 0.943787 2.47214 + vertex 0.865619 0.94369 2.47615 + vertex 0.866501 0.940521 2.47511 + endloop + endfacet + facet normal 0.908742 0.121634 0.39924 + outer loop + vertex 0.866501 0.940521 2.47511 + vertex 0.865619 0.94369 2.47615 + vertex 0.865264 0.939138 2.47835 + endloop + endfacet + facet normal 0.918036 0.111824 0.380402 + outer loop + vertex 0.865619 0.94369 2.47615 + vertex 0.864421 0.942987 2.47925 + vertex 0.865264 0.939138 2.47835 + endloop + endfacet + facet normal 0.800788 0.0352165 0.597911 + outer loop + vertex 0.864421 0.942987 2.47925 + vertex 0.86381 0.940081 2.48024 + vertex 0.865264 0.939138 2.47835 + endloop + endfacet + facet normal 0.682901 0.102701 0.723256 + outer loop + vertex 0.863249 0.942033 2.48049 + vertex 0.86381 0.940081 2.48024 + vertex 0.864421 0.942987 2.47925 + endloop + endfacet + facet normal 0.619682 0.330762 0.711751 + outer loop + vertex 0.865 0.948644 2.465 + vertex 0.866945 0.945 2.465 + vertex 0.87 0.945 2.46234 + endloop + endfacet + facet normal 0.633247 0.374523 0.677297 + outer loop + vertex 0.865 0.948644 2.465 + vertex 0.87 0.945 2.46234 + vertex 0.865 0.95 2.46425 + endloop + endfacet + facet normal 0.714924 0.550016 0.431702 + outer loop + vertex 0.865 0.95 2.46425 + vertex 0.87 0.945 2.46234 + vertex 0.868693 0.949352 2.45896 + endloop + endfacet + facet normal 0.671754 0.358556 -0.648216 + outer loop + vertex 0.865 0.95 2.46575 + vertex 0.866945 0.945 2.465 + vertex 0.865 0.948644 2.465 + endloop + endfacet + facet normal 0.932538 0.360844 0.0127783 + outer loop + vertex 0.865 0.95 2.46575 + vertex 0.865547 0.948467 2.46911 + vertex 0.866945 0.945 2.465 + endloop + endfacet + facet normal 0.966606 0.200858 0.159153 + outer loop + vertex 0.865547 0.948467 2.46911 + vertex 0.866827 0.942961 2.46829 + vertex 0.866945 0.945 2.465 + endloop + endfacet + facet normal 0.97397 0.216211 0.0680765 + outer loop + vertex 0.866827 0.942961 2.46829 + vertex 0.865547 0.948467 2.46911 + vertex 0.866374 0.943787 2.47214 + endloop + endfacet + facet normal 0.976421 0.208587 0.0556182 + outer loop + vertex 0.865547 0.948467 2.46911 + vertex 0.865544 0.947337 2.47341 + vertex 0.866374 0.943787 2.47214 + endloop + endfacet + facet normal 0.969331 0.159998 0.186544 + outer loop + vertex 0.866374 0.943787 2.47214 + vertex 0.865544 0.947337 2.47341 + vertex 0.865619 0.94369 2.47615 + endloop + endfacet + facet normal 0.948044 0.203232 0.244764 + outer loop + vertex 0.865544 0.947337 2.47341 + vertex 0.864553 0.94761 2.47702 + vertex 0.865619 0.94369 2.47615 + endloop + endfacet + facet normal 0.634193 0.38129 0.67262 + outer loop + vertex 0.863458 0.944805 2.47965 + vertex 0.864553 0.94761 2.47702 + vertex 0.862504 0.94788 2.4788 + endloop + endfacet + facet normal 0.753497 0.267376 0.600626 + outer loop + vertex 0.863458 0.944805 2.47965 + vertex 0.864421 0.942987 2.47925 + vertex 0.864553 0.94761 2.47702 + endloop + endfacet + facet normal 0.907795 0.160475 0.387499 + outer loop + vertex 0.864421 0.942987 2.47925 + vertex 0.865619 0.94369 2.47615 + vertex 0.864553 0.94761 2.47702 + endloop + endfacet + facet normal 0.643945 0.177808 0.744124 + outer loop + vertex 0.864421 0.942987 2.47925 + vertex 0.863458 0.944805 2.47965 + vertex 0.863249 0.942033 2.48049 + endloop + endfacet + facet normal 0.97482 -0.0584229 0.215203 + outer loop + vertex 0.865664 0.95331 2.46214 + vertex 0.865 0.952762 2.465 + vertex 0.865 0.95 2.46425 + endloop + endfacet + facet normal 0.750919 0.241047 0.614831 + outer loop + vertex 0.865664 0.95331 2.46214 + vertex 0.865 0.95 2.46425 + vertex 0.867932 0.95406 2.45908 + endloop + endfacet + facet normal 0.820964 0.118709 0.558504 + outer loop + vertex 0.867932 0.95406 2.45908 + vertex 0.865 0.95 2.46425 + vertex 0.868693 0.949352 2.45896 + endloop + endfacet + facet normal 0.974114 -0.082724 0.210379 + outer loop + vertex 0.865 0.952762 2.465 + vertex 0.865664 0.95331 2.46214 + vertex 0.865 0.955 2.46588 + endloop + endfacet + facet normal 0.985616 0.138191 -0.0972861 + outer loop + vertex 0.865 0.95 2.46575 + vertex 0.865 0.952992 2.47 + vertex 0.865547 0.948467 2.46911 + endloop + endfacet + facet normal 0.964072 0.158289 -0.213331 + outer loop + vertex 0.865 0.955 2.47149 + vertex 0.865547 0.948467 2.46911 + vertex 0.865 0.952992 2.47 + endloop + endfacet + facet normal 0.992937 0.0429344 0.110605 + outer loop + vertex 0.865 0.955 2.47149 + vertex 0.86489 0.952535 2.47343 + vertex 0.865547 0.948467 2.46911 + endloop + endfacet + facet normal 0.991649 0.124528 0.0335333 + outer loop + vertex 0.86489 0.952535 2.47343 + vertex 0.865544 0.947337 2.47341 + vertex 0.865547 0.948467 2.46911 + endloop + endfacet + facet normal 0.959692 0.119722 0.254278 + outer loop + vertex 0.865544 0.947337 2.47341 + vertex 0.86489 0.952535 2.47343 + vertex 0.864553 0.94761 2.47702 + endloop + endfacet + facet normal 0.956983 0.12531 0.26169 + outer loop + vertex 0.86489 0.952535 2.47343 + vertex 0.863993 0.952709 2.47663 + vertex 0.864553 0.94761 2.47702 + endloop + endfacet + facet normal 0.659715 0.129341 0.740302 + outer loop + vertex 0.863993 0.952709 2.47663 + vertex 0.862504 0.94788 2.4788 + vertex 0.864553 0.94761 2.47702 + endloop + endfacet + facet normal 0.809245 0.0145164 0.587292 + outer loop + vertex 0.862337 0.953842 2.47889 + vertex 0.862504 0.94788 2.4788 + vertex 0.863993 0.952709 2.47663 + endloop + endfacet + facet normal 0.832331 -0.0486477 0.55214 + outer loop + vertex 0.867932 0.95406 2.45908 + vertex 0.868517 0.959966 2.45872 + vertex 0.866372 0.957103 2.4617 + endloop + endfacet + facet normal 0.810621 -0.0834166 0.579599 + outer loop + vertex 0.865664 0.95331 2.46214 + vertex 0.867932 0.95406 2.45908 + vertex 0.866372 0.957103 2.4617 + endloop + endfacet + facet normal 0.959273 -0.151118 0.238659 + outer loop + vertex 0.866372 0.957103 2.4617 + vertex 0.865 0.955 2.46588 + vertex 0.865664 0.95331 2.46214 + endloop + endfacet + facet normal 0.953715 -0.0263679 0.299553 + outer loop + vertex 0.865 0.96 2.46632 + vertex 0.865 0.955 2.46588 + vertex 0.866372 0.957103 2.4617 + endloop + endfacet + facet normal 0.999332 -0.0209184 0.0299673 + outer loop + vertex 0.865 0.96 2.47498 + vertex 0.86489 0.952535 2.47343 + vertex 0.865 0.955 2.47149 + endloop + endfacet + facet normal 0.621359 -0.167793 0.765348 + outer loop + vertex 0.864425 0.956928 2.47477 + vertex 0.86489 0.952535 2.47343 + vertex 0.865 0.96 2.47498 + endloop + endfacet + facet normal 0.962911 0.0198793 0.269087 + outer loop + vertex 0.86489 0.952535 2.47343 + vertex 0.864425 0.956928 2.47477 + vertex 0.863993 0.952709 2.47663 + endloop + endfacet + facet normal 0.939301 0.0530777 0.338964 + outer loop + vertex 0.864425 0.956928 2.47477 + vertex 0.863771 0.956532 2.47665 + vertex 0.863993 0.952709 2.47663 + endloop + endfacet + facet normal 0.815685 0.0449124 0.576751 + outer loop + vertex 0.863771 0.956532 2.47665 + vertex 0.862337 0.953842 2.47889 + vertex 0.863993 0.952709 2.47663 + endloop + endfacet + facet normal 0.828405 0.0238837 0.55962 + outer loop + vertex 0.862946 0.958483 2.47779 + vertex 0.862337 0.953842 2.47889 + vertex 0.863771 0.956532 2.47665 + endloop + endfacet + facet normal 0.865872 -0.0317072 0.49926 + outer loop + vertex 0.868517 0.959966 2.45872 + vertex 0.868588 0.965241 2.45893 + vertex 0.86657 0.962088 2.46223 + endloop + endfacet + facet normal 0.847183 -0.0893587 0.523733 + outer loop + vertex 0.866372 0.957103 2.4617 + vertex 0.868517 0.959966 2.45872 + vertex 0.86657 0.962088 2.46223 + endloop + endfacet + facet normal 0.942973 -0.0720338 0.324983 + outer loop + vertex 0.86657 0.962088 2.46223 + vertex 0.865 0.96 2.46632 + vertex 0.866372 0.957103 2.4617 + endloop + endfacet + facet normal 0.945389 -0.108223 0.307452 + outer loop + vertex 0.865 0.965 2.46808 + vertex 0.865 0.96 2.46632 + vertex 0.86657 0.962088 2.46223 + endloop + endfacet + facet normal 0.974865 -0.190333 0.115805 + outer loop + vertex 0.865 0.96 2.47498 + vertex 0.865 0.960012 2.475 + vertex 0.864425 0.956928 2.47477 + endloop + endfacet + facet normal 0.929162 0.120177 0.349593 + outer loop + vertex 0.864425 0.956928 2.47477 + vertex 0.863755 0.960002 2.4755 + vertex 0.863771 0.956532 2.47665 + endloop + endfacet + facet normal 0.368592 -0.136215 0.919557 + outer loop + vertex 0.865 0.960012 2.475 + vertex 0.863755 0.960002 2.4755 + vertex 0.864425 0.956928 2.47477 + endloop + endfacet + facet normal 0.90045 0.140607 0.411606 + outer loop + vertex 0.863771 0.956532 2.47665 + vertex 0.863755 0.960002 2.4755 + vertex 0.862946 0.958483 2.47779 + endloop + endfacet + facet normal 0.884852 0.00813029 0.465802 + outer loop + vertex 0.868588 0.965241 2.45893 + vertex 0.868476 0.970278 2.45905 + vertex 0.866472 0.966979 2.46292 + endloop + endfacet + facet normal 0.872919 -0.0509277 0.4852 + outer loop + vertex 0.86657 0.962088 2.46223 + vertex 0.868588 0.965241 2.45893 + vertex 0.866472 0.966979 2.46292 + endloop + endfacet + facet normal 0.963359 -0.0184126 0.267582 + outer loop + vertex 0.866472 0.966979 2.46292 + vertex 0.865 0.965 2.46808 + vertex 0.86657 0.962088 2.46223 + endloop + endfacet + facet normal 0.966159 -0.0736611 0.247208 + outer loop + vertex 0.865 0.97 2.46957 + vertex 0.865 0.965 2.46808 + vertex 0.866472 0.966979 2.46292 + endloop + endfacet + facet normal 0.864576 0.0416734 0.500771 + outer loop + vertex 0.868476 0.970278 2.45905 + vertex 0.86834 0.975215 2.45888 + vertex 0.866267 0.971764 2.46274 + endloop + endfacet + facet normal 0.866345 0.0551893 0.496388 + outer loop + vertex 0.866472 0.966979 2.46292 + vertex 0.868476 0.970278 2.45905 + vertex 0.866267 0.971764 2.46274 + endloop + endfacet + facet normal 0.979682 0.0490653 0.194462 + outer loop + vertex 0.866267 0.971764 2.46274 + vertex 0.865 0.97 2.46957 + vertex 0.866472 0.966979 2.46292 + endloop + endfacet + facet normal 0.671561 0.677648 0.299664 + outer loop + vertex 0.863264 0.973432 2.4657 + vertex 0.865 0.97 2.46957 + vertex 0.866267 0.971764 2.46274 + endloop + endfacet + facet normal 0.845916 0.0842264 0.526624 + outer loop + vertex 0.86834 0.975215 2.45888 + vertex 0.868198 0.980006 2.45834 + vertex 0.866286 0.976865 2.46191 + endloop + endfacet + facet normal 0.845662 0.0827239 0.527269 + outer loop + vertex 0.866267 0.971764 2.46274 + vertex 0.86834 0.975215 2.45888 + vertex 0.866286 0.976865 2.46191 + endloop + endfacet + facet normal 0.727242 0.107736 0.677873 + outer loop + vertex 0.866286 0.976865 2.46191 + vertex 0.863264 0.973432 2.4657 + vertex 0.866267 0.971764 2.46274 + endloop + endfacet + facet normal 0.765538 0.0349164 0.642443 + outer loop + vertex 0.86398 0.97918 2.46453 + vertex 0.863264 0.973432 2.4657 + vertex 0.866286 0.976865 2.46191 + endloop + endfacet + facet normal 0.884301 0.132788 0.447637 + outer loop + vertex 0.868198 0.980006 2.45834 + vertex 0.868153 0.983847 2.45729 + vertex 0.866544 0.982837 2.46077 + endloop + endfacet + facet normal 0.856674 0.0612777 0.512205 + outer loop + vertex 0.866286 0.976865 2.46191 + vertex 0.868198 0.980006 2.45834 + vertex 0.866544 0.982837 2.46077 + endloop + endfacet + facet normal 0.783914 0.0841401 0.615141 + outer loop + vertex 0.866544 0.982837 2.46077 + vertex 0.86398 0.97918 2.46453 + vertex 0.866286 0.976865 2.46191 + endloop + endfacet + facet normal 0.830952 -0.00947657 0.556264 + outer loop + vertex 0.864159 0.984941 2.46436 + vertex 0.86398 0.97918 2.46453 + vertex 0.866544 0.982837 2.46077 + endloop + endfacet + facet normal 0.93584 0.20721 0.285074 + outer loop + vertex 0.868571 0.986221 2.45473 + vertex 0.868453 0.989192 2.45296 + vertex 0.867628 0.987966 2.45656 + endloop + endfacet + facet normal 0.932981 0.174656 0.314709 + outer loop + vertex 0.868153 0.983847 2.45729 + vertex 0.868571 0.986221 2.45473 + vertex 0.867628 0.987966 2.45656 + endloop + endfacet + facet normal 0.868373 0.191702 0.457361 + outer loop + vertex 0.868153 0.983847 2.45729 + vertex 0.867628 0.987966 2.45656 + vertex 0.866544 0.982837 2.46077 + endloop + endfacet + facet normal 0.931855 0.0911499 0.351196 + outer loop + vertex 0.866544 0.982837 2.46077 + vertex 0.867628 0.987966 2.45656 + vertex 0.865996 0.988606 2.46072 + endloop + endfacet + facet normal 0.85268 0.0848978 0.51549 + outer loop + vertex 0.865996 0.988606 2.46072 + vertex 0.864159 0.984941 2.46436 + vertex 0.866544 0.982837 2.46077 + endloop + endfacet + facet normal 0.893019 -0.000390733 0.450018 + outer loop + vertex 0.864192 0.990397 2.4643 + vertex 0.864159 0.984941 2.46436 + vertex 0.865996 0.988606 2.46072 + endloop + endfacet + facet normal -0.542224 -0.0973048 0.834581 + outer loop + vertex 0.87 0.993239 2.44 + vertex 0.869684 0.995 2.44 + vertex 0.869401 0.992388 2.43951 + endloop + endfacet + facet normal 0.960288 0.212242 0.18111 + outer loop + vertex 0.868693 0.991208 2.45013 + vertex 0.868533 0.994016 2.44768 + vertex 0.867978 0.99319 2.4516 + endloop + endfacet + facet normal 0.958676 0.186932 0.214467 + outer loop + vertex 0.868453 0.989192 2.45296 + vertex 0.868693 0.991208 2.45013 + vertex 0.867978 0.99319 2.4516 + endloop + endfacet + facet normal 0.935502 0.208319 0.285374 + outer loop + vertex 0.868453 0.989192 2.45296 + vertex 0.867978 0.99319 2.4516 + vertex 0.867628 0.987966 2.45656 + endloop + endfacet + facet normal 0.965085 0.143475 0.219147 + outer loop + vertex 0.867628 0.987966 2.45656 + vertex 0.867978 0.99319 2.4516 + vertex 0.866913 0.993214 2.45627 + endloop + endfacet + facet normal 0.928559 0.145204 0.341606 + outer loop + vertex 0.867628 0.987966 2.45656 + vertex 0.866913 0.993214 2.45627 + vertex 0.865996 0.988606 2.46072 + endloop + endfacet + facet normal 0.957392 0.0780474 0.278044 + outer loop + vertex 0.866913 0.993214 2.45627 + vertex 0.865607 0.993889 2.46058 + vertex 0.865996 0.988606 2.46072 + endloop + endfacet + facet normal 0.905505 0.0779907 0.417108 + outer loop + vertex 0.865607 0.993889 2.46058 + vertex 0.864192 0.990397 2.4643 + vertex 0.865996 0.988606 2.46072 + endloop + endfacet + facet normal 0.928293 0.0198968 0.371317 + outer loop + vertex 0.864121 0.99537 2.46422 + vertex 0.864192 0.990397 2.4643 + vertex 0.865607 0.993889 2.46058 + endloop + endfacet + facet normal 0.736888 -0.200373 0.645637 + outer loop + vertex 0.868943 0.994576 2.44071 + vertex 0.869401 0.992388 2.43951 + vertex 0.869684 0.995 2.44 + endloop + endfacet + facet normal 0.675743 0.0568819 0.734939 + outer loop + vertex 0.868943 0.994576 2.44071 + vertex 0.869684 0.995 2.44 + vertex 0.8683 0.998719 2.44098 + endloop + endfacet + facet normal 0.725876 0.0895685 0.681969 + outer loop + vertex 0.8683 0.998719 2.44098 + vertex 0.869684 0.995 2.44 + vertex 0.869067 1 2.44 + endloop + endfacet + facet normal 0.987151 0.149462 0.0565221 + outer loop + vertex 0.868709 0.994918 2.44389 + vertex 0.868943 0.994576 2.44071 + vertex 0.8683 0.998719 2.44098 + endloop + endfacet + facet normal 0.977344 0.1845 0.103723 + outer loop + vertex 0.86787 0.998201 2.44595 + vertex 0.868709 0.994918 2.44389 + vertex 0.8683 0.998719 2.44098 + endloop + endfacet + facet normal 0.977084 0.192438 0.0909672 + outer loop + vertex 0.868533 0.994016 2.44768 + vertex 0.868709 0.994918 2.44389 + vertex 0.86787 0.998201 2.44595 + endloop + endfacet + facet normal 0.95627 0.227545 0.183769 + outer loop + vertex 0.868533 0.994016 2.44768 + vertex 0.86787 0.998201 2.44595 + vertex 0.867978 0.99319 2.4516 + endloop + endfacet + facet normal 0.980383 0.156294 0.120085 + outer loop + vertex 0.867978 0.99319 2.4516 + vertex 0.86787 0.998201 2.44595 + vertex 0.867208 0.998382 2.45112 + endloop + endfacet + facet normal 0.962218 0.162603 0.218396 + outer loop + vertex 0.867978 0.99319 2.4516 + vertex 0.867208 0.998382 2.45112 + vertex 0.866913 0.993214 2.45627 + endloop + endfacet + facet normal 0.978575 0.114557 0.171078 + outer loop + vertex 0.867208 0.998382 2.45112 + vertex 0.86635 0.998459 2.45598 + vertex 0.866913 0.993214 2.45627 + endloop + endfacet + facet normal 0.955313 0.117541 0.271222 + outer loop + vertex 0.866913 0.993214 2.45627 + vertex 0.86635 0.998459 2.45598 + vertex 0.865607 0.993889 2.46058 + endloop + endfacet + facet normal 0.968882 0.0786119 0.234708 + outer loop + vertex 0.86635 0.998459 2.45598 + vertex 0.865226 0.999048 2.46042 + vertex 0.865607 0.993889 2.46058 + endloop + endfacet + facet normal 0.933654 0.0794903 0.349244 + outer loop + vertex 0.865226 0.999048 2.46042 + vertex 0.864121 0.99537 2.46422 + vertex 0.865607 0.993889 2.46058 + endloop + endfacet + facet normal 0.942203 0.0572061 0.330123 + outer loop + vertex 0.863823 1.00026 2.46422 + vertex 0.864121 0.99537 2.46422 + vertex 0.865226 0.999048 2.46042 + endloop + endfacet + facet normal 0.714575 0.103899 0.6918 + outer loop + vertex 0.869067 1 2.44 + vertex 0.86834 1.005 2.44 + vertex 0.8683 0.998719 2.44098 + endloop + endfacet + facet normal 0.843412 0.0779484 0.531583 + outer loop + vertex 0.86834 1.005 2.44 + vertex 0.867236 1.00368 2.44194 + vertex 0.8683 0.998719 2.44098 + endloop + endfacet + facet normal 0.976401 0.189205 0.104132 + outer loop + vertex 0.8683 0.998719 2.44098 + vertex 0.867236 1.00368 2.44194 + vertex 0.86787 0.998201 2.44595 + endloop + endfacet + facet normal 0.982529 0.169674 0.0764666 + outer loop + vertex 0.867236 1.00368 2.44194 + vertex 0.86694 1.00345 2.44625 + vertex 0.86787 0.998201 2.44595 + endloop + endfacet + facet normal 0.978767 0.166525 0.119519 + outer loop + vertex 0.86787 0.998201 2.44595 + vertex 0.86694 1.00345 2.44625 + vertex 0.867208 0.998382 2.45112 + endloop + endfacet + facet normal 0.987431 0.13348 0.0846302 + outer loop + vertex 0.86694 1.00345 2.44625 + vertex 0.866514 1.00356 2.45105 + vertex 0.867208 0.998382 2.45112 + endloop + endfacet + facet normal 0.976339 0.133151 0.170388 + outer loop + vertex 0.867208 0.998382 2.45112 + vertex 0.866514 1.00356 2.45105 + vertex 0.86635 0.998459 2.45598 + endloop + endfacet + facet normal 0.984264 0.105331 0.141877 + outer loop + vertex 0.866514 1.00356 2.45105 + vertex 0.865811 1.00365 2.45587 + vertex 0.86635 0.998459 2.45598 + endloop + endfacet + facet normal 0.967278 0.105528 0.230732 + outer loop + vertex 0.86635 0.998459 2.45598 + vertex 0.865811 1.00365 2.45587 + vertex 0.865226 0.999048 2.46042 + endloop + endfacet + facet normal 0.973127 0.0872951 0.213079 + outer loop + vertex 0.865811 1.00365 2.45587 + vertex 0.864797 1.00413 2.4603 + vertex 0.865226 0.999048 2.46042 + endloop + endfacet + facet normal 0.943103 0.087362 0.320819 + outer loop + vertex 0.864797 1.00413 2.4603 + vertex 0.863823 1.00026 2.46422 + vertex 0.865226 0.999048 2.46042 + endloop + endfacet + facet normal 0.946358 0.0789622 0.313323 + outer loop + vertex 0.86348 1.00518 2.46401 + vertex 0.863823 1.00026 2.46422 + vertex 0.864797 1.00413 2.4603 + endloop + endfacet + facet normal 0.759316 0.249974 0.600793 + outer loop + vertex 0.86834 1.005 2.44 + vertex 0.866694 1.01 2.44 + vertex 0.867236 1.00368 2.44194 + endloop + endfacet + facet normal 0.961598 0.152675 0.228079 + outer loop + vertex 0.866694 1.01 2.44 + vertex 0.866347 1.00761 2.44306 + vertex 0.867236 1.00368 2.44194 + endloop + endfacet + facet normal 0.976929 0.19896 0.077614 + outer loop + vertex 0.867236 1.00368 2.44194 + vertex 0.866347 1.00761 2.44306 + vertex 0.86694 1.00345 2.44625 + endloop + endfacet + facet normal 0.985596 0.165881 0.0329287 + outer loop + vertex 0.866347 1.00761 2.44306 + vertex 0.866115 1.00825 2.4468 + vertex 0.86694 1.00345 2.44625 + endloop + endfacet + facet normal 0.983599 0.159768 0.083715 + outer loop + vertex 0.86694 1.00345 2.44625 + vertex 0.866115 1.00825 2.4468 + vertex 0.866514 1.00356 2.45105 + endloop + endfacet + facet normal 0.989618 0.133228 0.0539028 + outer loop + vertex 0.866115 1.00825 2.4468 + vertex 0.865846 1.0084 2.45137 + vertex 0.866514 1.00356 2.45105 + endloop + endfacet + facet normal 0.981869 0.126538 0.141142 + outer loop + vertex 0.866514 1.00356 2.45105 + vertex 0.865846 1.0084 2.45137 + vertex 0.865811 1.00365 2.45587 + endloop + endfacet + facet normal 0.985489 0.112883 0.126765 + outer loop + vertex 0.865846 1.0084 2.45137 + vertex 0.865233 1.00857 2.45598 + vertex 0.865811 1.00365 2.45587 + endloop + endfacet + facet normal 0.971505 0.109372 0.210277 + outer loop + vertex 0.865811 1.00365 2.45587 + vertex 0.865233 1.00857 2.45598 + vertex 0.864797 1.00413 2.4603 + endloop + endfacet + facet normal 0.974739 0.0991573 0.200127 + outer loop + vertex 0.865233 1.00857 2.45598 + vertex 0.86433 1.00893 2.4602 + vertex 0.864797 1.00413 2.4603 + endloop + endfacet + facet normal 0.94634 0.0986796 0.307737 + outer loop + vertex 0.86433 1.00893 2.4602 + vertex 0.86348 1.00518 2.46401 + vertex 0.864797 1.00413 2.4603 + endloop + endfacet + facet normal 0.948743 0.0925084 0.302207 + outer loop + vertex 0.863175 1.00995 2.46351 + vertex 0.86348 1.00518 2.46401 + vertex 0.86433 1.00893 2.4602 + endloop + endfacet + facet normal 0.762702 0.545143 -0.348002 + outer loop + vertex 0.865 1.015 2.44412 + vertex 0.866694 1.01 2.44 + vertex 0.865 1.01237 2.44 + endloop + endfacet + facet normal 0.958469 0.106839 0.26443 + outer loop + vertex 0.865 1.015 2.44412 + vertex 0.865264 1.01286 2.44403 + vertex 0.866694 1.01 2.44 + endloop + endfacet + facet normal 0.960541 0.155806 0.230404 + outer loop + vertex 0.865264 1.01286 2.44403 + vertex 0.866347 1.00761 2.44306 + vertex 0.866694 1.01 2.44 + endloop + endfacet + facet normal 0.980003 0.197109 0.0272502 + outer loop + vertex 0.866347 1.00761 2.44306 + vertex 0.865264 1.01286 2.44403 + vertex 0.866115 1.00825 2.4468 + endloop + endfacet + facet normal 0.984684 0.173878 -0.0128364 + outer loop + vertex 0.865264 1.01286 2.44403 + vertex 0.865457 1.01205 2.44793 + vertex 0.866115 1.00825 2.4468 + endloop + endfacet + facet normal 0.986541 0.154682 0.0530221 + outer loop + vertex 0.866115 1.00825 2.4468 + vertex 0.865457 1.01205 2.44793 + vertex 0.865846 1.0084 2.45137 + endloop + endfacet + facet normal 0.987451 0.150353 0.0483126 + outer loop + vertex 0.865457 1.01205 2.44793 + vertex 0.865148 1.01283 2.45184 + vertex 0.865846 1.0084 2.45137 + endloop + endfacet + facet normal 0.982016 0.141264 0.125257 + outer loop + vertex 0.865846 1.0084 2.45137 + vertex 0.865148 1.01283 2.45184 + vertex 0.865233 1.00857 2.45598 + endloop + endfacet + facet normal 0.985376 0.128439 0.111973 + outer loop + vertex 0.865148 1.01283 2.45184 + vertex 0.864622 1.01296 2.45632 + vertex 0.865233 1.00857 2.45598 + endloop + endfacet + facet normal 0.972854 0.119952 0.197906 + outer loop + vertex 0.865233 1.00857 2.45598 + vertex 0.864622 1.01296 2.45632 + vertex 0.86433 1.00893 2.4602 + endloop + endfacet + facet normal 0.97591 0.110373 0.188195 + outer loop + vertex 0.864622 1.01296 2.45632 + vertex 0.863886 1.01306 2.46007 + vertex 0.86433 1.00893 2.4602 + endloop + endfacet + facet normal 0.948579 0.110663 0.296567 + outer loop + vertex 0.863886 1.01306 2.46007 + vertex 0.863175 1.00995 2.46351 + vertex 0.86433 1.00893 2.4602 + endloop + endfacet + facet normal 0.951925 0.10155 0.28901 + outer loop + vertex 0.863084 1.01386 2.46244 + vertex 0.863175 1.00995 2.46351 + vertex 0.863886 1.01306 2.46007 + endloop + endfacet + facet normal 0.94675 0.129671 -0.294703 + outer loop + vertex 0.865 1.015 2.44412 + vertex 0.865 1.017 2.445 + vertex 0.865264 1.01286 2.44403 + endloop + endfacet + facet normal -0.508362 -0.227578 0.830528 + outer loop + vertex 0.864401 1.01716 2.44468 + vertex 0.865264 1.01286 2.44403 + vertex 0.865 1.017 2.445 + endloop + endfacet + facet normal 0.979533 0.199992 -0.0227641 + outer loop + vertex 0.864401 1.01716 2.44468 + vertex 0.864656 1.01626 2.4477 + vertex 0.865264 1.01286 2.44403 + endloop + endfacet + facet normal 0.982355 0.186755 -0.010065 + outer loop + vertex 0.864656 1.01626 2.4477 + vertex 0.865457 1.01205 2.44793 + vertex 0.865264 1.01286 2.44403 + endloop + endfacet + facet normal 0.98112 0.189196 0.0401139 + outer loop + vertex 0.865457 1.01205 2.44793 + vertex 0.864656 1.01626 2.4477 + vertex 0.865148 1.01283 2.45184 + endloop + endfacet + facet normal 0.985588 0.16775 0.0218143 + outer loop + vertex 0.864656 1.01626 2.4477 + vertex 0.864444 1.01686 2.45264 + vertex 0.865148 1.01283 2.45184 + endloop + endfacet + facet normal 0.982496 0.149574 0.111039 + outer loop + vertex 0.865148 1.01283 2.45184 + vertex 0.864444 1.01686 2.45264 + vertex 0.864622 1.01296 2.45632 + endloop + endfacet + facet normal 0.983599 0.14547 0.106636 + outer loop + vertex 0.864444 1.01686 2.45264 + vertex 0.86403 1.01652 2.45692 + vertex 0.864622 1.01296 2.45632 + endloop + endfacet + facet normal 0.970837 0.148089 0.188532 + outer loop + vertex 0.863503 1.0161 2.45997 + vertex 0.86403 1.01652 2.45692 + vertex 0.863477 1.01896 2.45786 + endloop + endfacet + facet normal 0.973863 0.129655 0.186494 + outer loop + vertex 0.863503 1.0161 2.45997 + vertex 0.863886 1.01306 2.46007 + vertex 0.86403 1.01652 2.45692 + endloop + endfacet + facet normal 0.973644 0.130296 0.187188 + outer loop + vertex 0.863886 1.01306 2.46007 + vertex 0.864622 1.01296 2.45632 + vertex 0.86403 1.01652 2.45692 + endloop + endfacet + facet normal 0.951389 0.130163 0.279137 + outer loop + vertex 0.863886 1.01306 2.46007 + vertex 0.863503 1.0161 2.45997 + vertex 0.863084 1.01386 2.46244 + endloop + endfacet + facet normal 0.984452 0.172843 -0.031304 + outer loop + vertex 0.864401 1.01716 2.44468 + vertex 0.864001 1.01967 2.44594 + vertex 0.864656 1.01626 2.4477 + endloop + endfacet + facet normal 0.987112 0.158366 0.0230336 + outer loop + vertex 0.864656 1.01626 2.4477 + vertex 0.863943 1.02048 2.44926 + vertex 0.864444 1.01686 2.45264 + endloop + endfacet + facet normal 0.984102 0.175755 -0.0255503 + outer loop + vertex 0.864001 1.01967 2.44594 + vertex 0.863943 1.02048 2.44926 + vertex 0.864656 1.01626 2.4477 + endloop + endfacet + facet normal 0.982993 0.149333 0.106884 + outer loop + vertex 0.864444 1.01686 2.45264 + vertex 0.863778 1.02033 2.45392 + vertex 0.86403 1.01652 2.45692 + endloop + endfacet + facet normal 0.983911 0.174058 0.0402908 + outer loop + vertex 0.863943 1.02048 2.44926 + vertex 0.863778 1.02033 2.45392 + vertex 0.864444 1.01686 2.45264 + endloop + endfacet + facet normal 0.976248 0.17027 0.133968 + outer loop + vertex 0.86403 1.01652 2.45692 + vertex 0.863778 1.02033 2.45392 + vertex 0.863477 1.01896 2.45786 + endloop + endfacet + facet normal 0.444623 -0.891858 -0.0830617 + outer loop + vertex 0.864975 1.11404 2.54111 + vertex 0.862172 1.1126 2.54153 + vertex 0.863147 1.11328 2.53941 + endloop + endfacet + facet normal 0.463307 -0.883416 0.0701674 + outer loop + vertex 0.864819 1.11418 2.5439 + vertex 0.862172 1.1126 2.54153 + vertex 0.864975 1.11404 2.54111 + endloop + endfacet + facet normal 0.352581 -0.911348 0.212442 + outer loop + vertex 0.86159 1.11302 2.54429 + vertex 0.862172 1.1126 2.54153 + vertex 0.864819 1.11418 2.5439 + endloop + endfacet + facet normal 0.34476 -0.791212 0.505099 + outer loop + vertex 0.864819 1.11418 2.5439 + vertex 0.862561 1.1149 2.54657 + vertex 0.86159 1.11302 2.54429 + endloop + endfacet + facet normal 0.688406 -0.510568 -0.515188 + outer loop + vertex 0.864975 1.11404 2.54111 + vertex 0.863147 1.11328 2.53941 + vertex 0.865 1.11519 2.54 + endloop + endfacet + facet normal 0.630895 -0.544994 -0.552225 + outer loop + vertex 0.864975 1.11404 2.54111 + vertex 0.865 1.11519 2.54 + vertex 0.869147 1.11663 2.54332 + endloop + endfacet + facet normal 0.551246 -0.75102 -0.363452 + outer loop + vertex 0.869147 1.11663 2.54332 + vertex 0.865 1.11519 2.54 + vertex 0.87 1.11886 2.54 + endloop + endfacet + facet normal 0.502362 -0.851812 0.148491 + outer loop + vertex 0.869147 1.11663 2.54332 + vertex 0.867213 1.1161 2.54684 + vertex 0.864819 1.11418 2.5439 + endloop + endfacet + facet normal 0.498764 -0.863811 0.0711714 + outer loop + vertex 0.864975 1.11404 2.54111 + vertex 0.869147 1.11663 2.54332 + vertex 0.864819 1.11418 2.5439 + endloop + endfacet + facet normal 0.205611 -0.88703 0.413404 + outer loop + vertex 0.862561 1.1149 2.54657 + vertex 0.864819 1.11418 2.5439 + vertex 0.867213 1.1161 2.54684 + endloop + endfacet + facet normal 0.168816 -0.784778 0.596343 + outer loop + vertex 0.862561 1.1149 2.54657 + vertex 0.867213 1.1161 2.54684 + vertex 0.864027 1.11727 2.54927 + endloop + endfacet + facet normal 0.0448786 -0.876953 0.478476 + outer loop + vertex 0.864027 1.11727 2.54927 + vertex 0.867213 1.1161 2.54684 + vertex 0.868194 1.11789 2.55003 + endloop + endfacet + facet normal -0.00823355 -0.747988 0.663662 + outer loop + vertex 0.868194 1.11789 2.55003 + vertex 0.864376 1.11956 2.55186 + vertex 0.864027 1.11727 2.54927 + endloop + endfacet + facet normal -0.112961 -0.840971 0.529157 + outer loop + vertex 0.868239 1.11954 2.55265 + vertex 0.864376 1.11956 2.55186 + vertex 0.868194 1.11789 2.55003 + endloop + endfacet + facet normal -0.234083 -0.751903 0.616317 + outer loop + vertex 0.868882 1.12104 2.55514 + vertex 0.866223 1.12261 2.55605 + vertex 0.864912 1.1216 2.55432 + endloop + endfacet + facet normal -0.227244 -0.807048 0.545008 + outer loop + vertex 0.868882 1.12104 2.55514 + vertex 0.864912 1.1216 2.55432 + vertex 0.868239 1.11954 2.55265 + endloop + endfacet + facet normal -0.137487 -0.747325 0.650079 + outer loop + vertex 0.868239 1.11954 2.55265 + vertex 0.864912 1.1216 2.55432 + vertex 0.864376 1.11956 2.55186 + endloop + endfacet + facet normal -0.251628 -0.766701 0.590638 + outer loop + vertex 0.868882 1.12104 2.55514 + vertex 0.868834 1.12334 2.55811 + vertex 0.866223 1.12261 2.55605 + endloop + endfacet + facet normal -0.302074 -0.705658 0.640935 + outer loop + vertex 0.864912 1.1216 2.55432 + vertex 0.866223 1.12261 2.55605 + vertex 0.862781 1.1245 2.55652 + endloop + endfacet + facet normal -0.34299 -0.659305 0.669085 + outer loop + vertex 0.868072 1.12608 2.56067 + vertex 0.865889 1.12771 2.56116 + vertex 0.864347 1.12668 2.55935 + endloop + endfacet + facet normal -0.337506 -0.691246 0.638959 + outer loop + vertex 0.868834 1.12334 2.55811 + vertex 0.868072 1.12608 2.56067 + vertex 0.864347 1.12668 2.55935 + endloop + endfacet + facet normal -0.307459 -0.665965 0.679677 + outer loop + vertex 0.868834 1.12334 2.55811 + vertex 0.864347 1.12668 2.55935 + vertex 0.862781 1.1245 2.55652 + endloop + endfacet + facet normal -0.304276 -0.708604 0.636629 + outer loop + vertex 0.868834 1.12334 2.55811 + vertex 0.862781 1.1245 2.55652 + vertex 0.866223 1.12261 2.55605 + endloop + endfacet + facet normal -0.338695 -0.655371 0.675111 + outer loop + vertex 0.868072 1.12608 2.56067 + vertex 0.868578 1.1284 2.56318 + vertex 0.865889 1.12771 2.56116 + endloop + endfacet + facet normal -0.384611 -0.621127 0.682844 + outer loop + vertex 0.864347 1.12668 2.55935 + vertex 0.865889 1.12771 2.56116 + vertex 0.862505 1.1299 2.56125 + endloop + endfacet + facet normal -0.41636 -0.615542 0.669143 + outer loop + vertex 0.868056 1.13136 2.56564 + vertex 0.866141 1.13314 2.56607 + vertex 0.863937 1.13257 2.56419 + endloop + endfacet + facet normal -0.416169 -0.622684 0.662623 + outer loop + vertex 0.868578 1.1284 2.56318 + vertex 0.868056 1.13136 2.56564 + vertex 0.863937 1.13257 2.56419 + endloop + endfacet + facet normal -0.37354 -0.588475 0.717053 + outer loop + vertex 0.868578 1.1284 2.56318 + vertex 0.863937 1.13257 2.56419 + vertex 0.862505 1.1299 2.56125 + endloop + endfacet + facet normal -0.373275 -0.604475 0.703758 + outer loop + vertex 0.868578 1.1284 2.56318 + vertex 0.862505 1.1299 2.56125 + vertex 0.865889 1.12771 2.56116 + endloop + endfacet + facet normal -0.403413 -0.605689 0.685857 + outer loop + vertex 0.868056 1.13136 2.56564 + vertex 0.868477 1.13382 2.56806 + vertex 0.866141 1.13314 2.56607 + endloop + endfacet + facet normal -0.45337 -0.557797 0.695211 + outer loop + vertex 0.863937 1.13257 2.56419 + vertex 0.866141 1.13314 2.56607 + vertex 0.863816 1.13528 2.56628 + endloop + endfacet + facet normal -0.493173 -0.510843 0.704145 + outer loop + vertex 0.867643 1.137 2.57012 + vertex 0.865783 1.13941 2.57057 + vertex 0.863681 1.13835 2.56833 + endloop + endfacet + facet normal -0.49254 -0.561745 0.664716 + outer loop + vertex 0.868477 1.13382 2.56806 + vertex 0.867643 1.137 2.57012 + vertex 0.863681 1.13835 2.56833 + endloop + endfacet + facet normal -0.440986 -0.511374 0.737582 + outer loop + vertex 0.868477 1.13382 2.56806 + vertex 0.863681 1.13835 2.56833 + vertex 0.863816 1.13528 2.56628 + endloop + endfacet + facet normal -0.441995 -0.54701 0.710929 + outer loop + vertex 0.868477 1.13382 2.56806 + vertex 0.863816 1.13528 2.56628 + vertex 0.866141 1.13314 2.56607 + endloop + endfacet + facet normal -0.48686 -0.50726 0.711094 + outer loop + vertex 0.867643 1.137 2.57012 + vertex 0.868584 1.13884 2.57208 + vertex 0.865783 1.13941 2.57057 + endloop + endfacet + facet normal -0.528189 -0.460848 0.713187 + outer loop + vertex 0.863681 1.13835 2.56833 + vertex 0.865783 1.13941 2.57057 + vertex 0.863316 1.14143 2.57005 + endloop + endfacet + facet normal -0.506491 -0.424585 0.750463 + outer loop + vertex 0.865783 1.13941 2.57057 + vertex 0.865412 1.14221 2.57191 + vertex 0.863316 1.14143 2.57005 + endloop + endfacet + facet normal -0.495015 -0.426246 0.757149 + outer loop + vertex 0.865783 1.13941 2.57057 + vertex 0.868584 1.13884 2.57208 + vertex 0.865412 1.14221 2.57191 + endloop + endfacet + facet normal -0.514823 -0.446146 0.732059 + outer loop + vertex 0.868584 1.13884 2.57208 + vertex 0.86886 1.14214 2.57429 + vertex 0.865412 1.14221 2.57191 + endloop + endfacet + facet normal -0.60872 -0.0357272 0.79258 + outer loop + vertex 0.861819 1.1972 2.5837 + vertex 0.863219 1.1922 2.58455 + vertex 0.865483 1.19454 2.5864 + endloop + endfacet + facet normal -0.610877 -0.0406128 0.790683 + outer loop + vertex 0.865106 1.19953 2.58636 + vertex 0.861819 1.1972 2.5837 + vertex 0.865483 1.19454 2.5864 + endloop + endfacet + facet normal -0.591407 -0.0390381 0.805427 + outer loop + vertex 0.865483 1.19454 2.5864 + vertex 0.868242 1.19709 2.58855 + vertex 0.865106 1.19953 2.58636 + endloop + endfacet + facet normal -0.58365 -0.0515813 0.810365 + outer loop + vertex 0.868713 1.19192 2.58856 + vertex 0.868242 1.19709 2.58855 + vertex 0.865483 1.19454 2.5864 + endloop + endfacet + facet normal -0.60209 -0.059335 0.796221 + outer loop + vertex 0.862448 1.20243 2.58457 + vertex 0.861819 1.1972 2.5837 + vertex 0.865106 1.19953 2.58636 + endloop + endfacet + facet normal -0.603916 -0.0619925 0.794633 + outer loop + vertex 0.864732 1.20343 2.58638 + vertex 0.862448 1.20243 2.58457 + vertex 0.865106 1.19953 2.58636 + endloop + endfacet + facet normal -0.58983 -0.0606963 0.805243 + outer loop + vertex 0.865106 1.19953 2.58636 + vertex 0.867634 1.20265 2.58845 + vertex 0.864732 1.20343 2.58638 + endloop + endfacet + facet normal -0.597379 -0.0512814 0.800317 + outer loop + vertex 0.868242 1.19709 2.58855 + vertex 0.867634 1.20265 2.58845 + vertex 0.865106 1.19953 2.58636 + endloop + endfacet + facet normal -0.599333 -0.113771 0.792374 + outer loop + vertex 0.864732 1.20343 2.58638 + vertex 0.865107 1.20683 2.58715 + vertex 0.862928 1.20583 2.58536 + endloop + endfacet + facet normal -0.539102 -0.144546 0.829744 + outer loop + vertex 0.870122 1.26204 2.60149 + vertex 0.867043 1.26573 2.60013 + vertex 0.865332 1.26188 2.59835 + endloop + endfacet + facet normal -0.526234 -0.129931 0.840354 + outer loop + vertex 0.870122 1.26204 2.60149 + vertex 0.869588 1.26793 2.60206 + vertex 0.867043 1.26573 2.60013 + endloop + endfacet + facet normal -0.475711 -0.0348339 0.878912 + outer loop + vertex 0.867767 1.41583 2.61526 + vertex 0.870824 1.41745 2.61698 + vertex 0.8673 1.41983 2.61517 + endloop + endfacet + facet normal -0.475939 -0.0352811 0.87877 + outer loop + vertex 0.870824 1.41745 2.61698 + vertex 0.870256 1.42275 2.61689 + vertex 0.8673 1.41983 2.61517 + endloop + endfacet + facet normal -0.562403 0.0480431 0.825466 + outer loop + vertex 0.867474 1.76537 2.59937 + vertex 0.867646 1.77033 2.5992 + vertex 0.864583 1.76702 2.59731 + endloop + endfacet + facet normal -0.559609 0.0442555 0.827574 + outer loop + vertex 0.864583 1.76702 2.59731 + vertex 0.867646 1.77033 2.5992 + vertex 0.864714 1.77194 2.59713 + endloop + endfacet + facet normal -0.579381 0.333599 0.743659 + outer loop + vertex 0.862511 1.86984 2.57331 + vertex 0.86183 1.86525 2.57484 + vertex 0.8659 1.86744 2.57702 + endloop + endfacet + facet normal -0.553116 0.372866 0.745006 + outer loop + vertex 0.866042 1.87234 2.57468 + vertex 0.862511 1.86984 2.57331 + vertex 0.8659 1.86744 2.57702 + endloop + endfacet + facet normal -0.582457 0.364813 0.726399 + outer loop + vertex 0.8659 1.86744 2.57702 + vertex 0.868628 1.87074 2.57755 + vertex 0.866042 1.87234 2.57468 + endloop + endfacet + facet normal -0.586731 0.36927 0.720685 + outer loop + vertex 0.86866 1.86818 2.5789 + vertex 0.868628 1.87074 2.57755 + vertex 0.8659 1.86744 2.57702 + endloop + endfacet + facet normal -0.53795 0.413123 0.734805 + outer loop + vertex 0.866487 1.87645 2.5727 + vertex 0.862388 1.87631 2.56978 + vertex 0.863767 1.87378 2.57221 + endloop + endfacet + facet normal -0.5572 0.38317 0.736688 + outer loop + vertex 0.863767 1.87378 2.57221 + vertex 0.862511 1.86984 2.57331 + vertex 0.866042 1.87234 2.57468 + endloop + endfacet + facet normal -0.537436 0.412459 0.735554 + outer loop + vertex 0.866487 1.87645 2.5727 + vertex 0.863767 1.87378 2.57221 + vertex 0.866042 1.87234 2.57468 + endloop + endfacet + facet normal -0.561373 0.407652 0.720195 + outer loop + vertex 0.866487 1.87645 2.5727 + vertex 0.866042 1.87234 2.57468 + vertex 0.868804 1.8746 2.57555 + endloop + endfacet + facet normal -0.548707 0.42403 0.7205 + outer loop + vertex 0.866487 1.87645 2.5727 + vertex 0.868804 1.8746 2.57555 + vertex 0.868881 1.87703 2.57418 + endloop + endfacet + facet normal -0.558486 0.402044 0.725572 + outer loop + vertex 0.868804 1.8746 2.57555 + vertex 0.866042 1.87234 2.57468 + vertex 0.868628 1.87074 2.57755 + endloop + endfacet + facet normal -0.545473 0.433213 0.717485 + outer loop + vertex 0.866487 1.87645 2.5727 + vertex 0.868806 1.87886 2.57301 + vertex 0.866393 1.88024 2.57034 + endloop + endfacet + facet normal -0.531666 0.438128 0.724828 + outer loop + vertex 0.866487 1.87645 2.5727 + vertex 0.866393 1.88024 2.57034 + vertex 0.862388 1.87631 2.56978 + endloop + endfacet + facet normal -0.523611 0.428226 0.736515 + outer loop + vertex 0.862388 1.87631 2.56978 + vertex 0.866393 1.88024 2.57034 + vertex 0.86242 1.88137 2.56686 + endloop + endfacet + facet normal -0.547702 0.435767 0.714234 + outer loop + vertex 0.868806 1.87886 2.57301 + vertex 0.866487 1.87645 2.5727 + vertex 0.868881 1.87703 2.57418 + endloop + endfacet + facet normal -0.399359 0.518338 0.7562 + outer loop + vertex 0.8657 1.88822 2.5643 + vertex 0.863537 1.88781 2.56344 + vertex 0.863469 1.88574 2.56482 + endloop + endfacet + facet normal -0.442764 0.547595 0.71 + outer loop + vertex 0.863469 1.88574 2.56482 + vertex 0.867144 1.88491 2.56775 + vertex 0.8657 1.88822 2.5643 + endloop + endfacet + facet normal -0.486541 0.462866 0.740968 + outer loop + vertex 0.863469 1.88574 2.56482 + vertex 0.86242 1.88137 2.56686 + vertex 0.867144 1.88491 2.56775 + endloop + endfacet + facet normal -0.496498 0.480771 0.722737 + outer loop + vertex 0.86242 1.88137 2.56686 + vertex 0.866393 1.88024 2.57034 + vertex 0.867144 1.88491 2.56775 + endloop + endfacet + facet normal -0.360178 0.696527 0.620582 + outer loop + vertex 0.866405 1.89104 2.56176 + vertex 0.861606 1.89047 2.55961 + vertex 0.863704 1.88919 2.56227 + endloop + endfacet + facet normal -0.388819 0.621333 0.680268 + outer loop + vertex 0.863704 1.88919 2.56227 + vertex 0.863537 1.88781 2.56344 + vertex 0.8657 1.88822 2.5643 + endloop + endfacet + facet normal -0.338435 0.674584 0.656047 + outer loop + vertex 0.866405 1.89104 2.56176 + vertex 0.863704 1.88919 2.56227 + vertex 0.8657 1.88822 2.5643 + endloop + endfacet + facet normal -0.41518 0.663509 0.6224 + outer loop + vertex 0.866405 1.89104 2.56176 + vertex 0.8657 1.88822 2.5643 + vertex 0.869798 1.88931 2.56586 + endloop + endfacet + facet normal -0.36588 0.710307 0.601329 + outer loop + vertex 0.866405 1.89104 2.56176 + vertex 0.869798 1.88931 2.56586 + vertex 0.869246 1.89149 2.56295 + endloop + endfacet + facet normal -0.422199 0.55974 0.713049 + outer loop + vertex 0.869798 1.88931 2.56586 + vertex 0.8657 1.88822 2.5643 + vertex 0.867144 1.88491 2.56775 + endloop + endfacet + facet normal -0.138596 0.819719 0.555744 + outer loop + vertex 0.86902 1.89648 2.55411 + vertex 0.867862 1.89846 2.55091 + vertex 0.86571 1.89682 2.55278 + endloop + endfacet + facet normal -0.0603771 0.844948 0.53143 + outer loop + vertex 0.86571 1.89682 2.55278 + vertex 0.861964 1.89633 2.55314 + vertex 0.86546 1.89418 2.55696 + endloop + endfacet + facet normal -0.124231 0.841661 0.525522 + outer loop + vertex 0.86571 1.89682 2.55278 + vertex 0.86546 1.89418 2.55696 + vertex 0.86902 1.89648 2.55411 + endloop + endfacet + facet normal -0.226886 0.876178 0.425247 + outer loop + vertex 0.86902 1.89648 2.55411 + vertex 0.86546 1.89418 2.55696 + vertex 0.869626 1.89484 2.55782 + endloop + endfacet + facet normal -0.340292 0.754855 0.56071 + outer loop + vertex 0.866405 1.89104 2.56176 + vertex 0.86546 1.89418 2.55696 + vertex 0.861606 1.89047 2.55961 + endloop + endfacet + facet normal -0.332287 0.758039 0.561216 + outer loop + vertex 0.866405 1.89104 2.56176 + vertex 0.869105 1.89307 2.56061 + vertex 0.86546 1.89418 2.55696 + endloop + endfacet + facet normal -0.234321 0.840587 0.488372 + outer loop + vertex 0.869105 1.89307 2.56061 + vertex 0.869626 1.89484 2.55782 + vertex 0.86546 1.89418 2.55696 + endloop + endfacet + facet normal -0.348657 0.767011 0.538639 + outer loop + vertex 0.869105 1.89307 2.56061 + vertex 0.866405 1.89104 2.56176 + vertex 0.869246 1.89149 2.56295 + endloop + endfacet + facet normal -0.413981 0.352306 0.839345 + outer loop + vertex 0.866213 1.905 2.545 + vertex 0.861145 1.90275 2.54345 + vertex 0.86498 1.90185 2.54571 + endloop + endfacet + facet normal 0.0164482 0.214851 0.976508 + outer loop + vertex 0.866213 1.905 2.545 + vertex 0.86498 1.90185 2.54571 + vertex 0.87 1.90471 2.545 + endloop + endfacet + facet normal -0.450431 0.855156 0.256555 + outer loop + vertex 0.87 1.90471 2.545 + vertex 0.86498 1.90185 2.54571 + vertex 0.87 1.90321 2.55 + endloop + endfacet + facet normal -0.0833225 0.796446 0.598941 + outer loop + vertex 0.867862 1.89846 2.55091 + vertex 0.8642 1.8991 2.54955 + vertex 0.86571 1.89682 2.55278 + endloop + endfacet + facet normal -0.284877 0.302085 0.90972 + outer loop + vertex 0.867862 1.89846 2.55091 + vertex 0.87 1.90321 2.55 + vertex 0.8642 1.8991 2.54955 + endloop + endfacet + facet normal -0.548335 0.728022 0.411476 + outer loop + vertex 0.87 1.90321 2.55 + vertex 0.86498 1.90185 2.54571 + vertex 0.8642 1.8991 2.54955 + endloop + endfacet + facet normal -0.0496576 0.805951 0.589895 + outer loop + vertex 0.86571 1.89682 2.55278 + vertex 0.8642 1.8991 2.54955 + vertex 0.861964 1.89633 2.55314 + endloop + endfacet + facet normal -0.0403303 0.999185 -0.00136296 + outer loop + vertex 0.866382 1.905 2.54 + vertex 0.862303 1.90484 2.54061 + vertex 0.866213 1.905 2.545 + endloop + endfacet + facet normal 0.143076 0.104615 0.984167 + outer loop + vertex 0.865 1.90689 2.54 + vertex 0.862303 1.90484 2.54061 + vertex 0.866382 1.905 2.54 + endloop + endfacet + facet normal -0.471054 0.791201 0.390012 + outer loop + vertex 0.866213 1.905 2.545 + vertex 0.862303 1.90484 2.54061 + vertex 0.861145 1.90275 2.54345 + endloop + endfacet + facet normal 0.964012 -0.264492 0.0269051 + outer loop + vertex 0.864133 2.01446 2.45043 + vertex 0.86322 2.01138 2.45289 + vertex 0.863356 2.01156 2.44975 + endloop + endfacet + facet normal 0.970194 -0.232034 0.0698787 + outer loop + vertex 0.864133 2.01446 2.45043 + vertex 0.863604 2.01346 2.45445 + vertex 0.86322 2.01138 2.45289 + endloop + endfacet + facet normal 0.6222 -0.434832 -0.65099 + outer loop + vertex 0.86681 2.02 2.44 + vertex 0.865 2.01741 2.44 + vertex 0.865 2.02 2.43827 + endloop + endfacet + facet normal 0.704314 -0.492219 0.511529 + outer loop + vertex 0.865441 2.01895 2.44087 + vertex 0.865 2.01741 2.44 + vertex 0.86681 2.02 2.44 + endloop + endfacet + facet normal 0.966286 -0.254316 -0.040189 + outer loop + vertex 0.865 2.01662 2.445 + vertex 0.865 2.01741 2.44 + vertex 0.865441 2.01895 2.44087 + endloop + endfacet + facet normal 0.987069 0.0691427 0.14462 + outer loop + vertex 0.864889 2.01746 2.44535 + vertex 0.865 2.01662 2.445 + vertex 0.865441 2.01895 2.44087 + endloop + endfacet + facet normal 0.912315 -0.0503129 0.406387 + outer loop + vertex 0.863973 2.01386 2.44696 + vertex 0.865 2.01662 2.445 + vertex 0.864889 2.01746 2.44535 + endloop + endfacet + facet normal 0.965919 -0.258845 0.000587832 + outer loop + vertex 0.863973 2.01386 2.44696 + vertex 0.864133 2.01446 2.45043 + vertex 0.863356 2.01156 2.44975 + endloop + endfacet + facet normal 0.969025 -0.246956 -0.00162728 + outer loop + vertex 0.863973 2.01386 2.44696 + vertex 0.864889 2.01746 2.44535 + vertex 0.864133 2.01446 2.45043 + endloop + endfacet + facet normal 0.977117 -0.211722 0.0203839 + outer loop + vertex 0.864889 2.01746 2.44535 + vertex 0.864973 2.01825 2.44951 + vertex 0.864133 2.01446 2.45043 + endloop + endfacet + facet normal 0.9684 -0.161953 0.189662 + outer loop + vertex 0.863604 2.01346 2.45445 + vertex 0.864356 2.01744 2.45401 + vertex 0.863273 2.01466 2.45717 + endloop + endfacet + facet normal 0.980707 -0.17591 0.0852607 + outer loop + vertex 0.863604 2.01346 2.45445 + vertex 0.864133 2.01446 2.45043 + vertex 0.864356 2.01744 2.45401 + endloop + endfacet + facet normal 0.976313 -0.192301 0.0991679 + outer loop + vertex 0.864133 2.01446 2.45043 + vertex 0.864973 2.01825 2.44951 + vertex 0.864356 2.01744 2.45401 + endloop + endfacet + facet normal 0.966927 -0.122565 0.223675 + outer loop + vertex 0.864356 2.01744 2.45401 + vertex 0.863437 2.01845 2.45854 + vertex 0.863273 2.01466 2.45717 + endloop + endfacet + facet normal 0.583474 -0.089036 0.807236 + outer loop + vertex 0.86681 2.02 2.44 + vertex 0.867573 2.025 2.44 + vertex 0.865441 2.01895 2.44087 + endloop + endfacet + facet normal 0.869871 -0.244612 0.428356 + outer loop + vertex 0.867573 2.025 2.44 + vertex 0.866048 2.02266 2.44176 + vertex 0.865441 2.01895 2.44087 + endloop + endfacet + facet normal 0.982491 -0.175404 0.0628137 + outer loop + vertex 0.865441 2.01895 2.44087 + vertex 0.866048 2.02266 2.44176 + vertex 0.864889 2.01746 2.44535 + endloop + endfacet + facet normal 0.982023 -0.180471 0.0553192 + outer loop + vertex 0.866048 2.02266 2.44176 + vertex 0.865669 2.02193 2.44608 + vertex 0.864889 2.01746 2.44535 + endloop + endfacet + facet normal 0.984653 -0.174028 0.0131241 + outer loop + vertex 0.864889 2.01746 2.44535 + vertex 0.865669 2.02193 2.44608 + vertex 0.864973 2.01825 2.44951 + endloop + endfacet + facet normal 0.989884 -0.125308 0.0665414 + outer loop + vertex 0.865669 2.02193 2.44608 + vertex 0.865367 2.02205 2.45079 + vertex 0.864973 2.01825 2.44951 + endloop + endfacet + facet normal 0.984142 -0.13933 0.109777 + outer loop + vertex 0.864973 2.01825 2.44951 + vertex 0.865367 2.02205 2.45079 + vertex 0.864356 2.01744 2.45401 + endloop + endfacet + facet normal 0.981531 -0.102811 0.16133 + outer loop + vertex 0.865367 2.02205 2.45079 + vertex 0.864665 2.0229 2.45561 + vertex 0.864356 2.01744 2.45401 + endloop + endfacet + facet normal 0.967338 -0.120134 0.223213 + outer loop + vertex 0.864665 2.0229 2.45561 + vertex 0.863437 2.01845 2.45854 + vertex 0.864356 2.01744 2.45401 + endloop + endfacet + facet normal 0.960953 -0.0939638 0.26027 + outer loop + vertex 0.863515 2.02235 2.45966 + vertex 0.863437 2.01845 2.45854 + vertex 0.864665 2.0229 2.45561 + endloop + endfacet + facet normal 0.767171 -0.0170291 0.641216 + outer loop + vertex 0.867573 2.025 2.44 + vertex 0.867684 2.03 2.44 + vertex 0.866048 2.02266 2.44176 + endloop + endfacet + facet normal 0.950576 -0.146193 0.273923 + outer loop + vertex 0.867684 2.03 2.44 + vertex 0.866613 2.02749 2.44238 + vertex 0.866048 2.02266 2.44176 + endloop + endfacet + facet normal 0.990067 -0.12436 0.0655814 + outer loop + vertex 0.866048 2.02266 2.44176 + vertex 0.866613 2.02749 2.44238 + vertex 0.865669 2.02193 2.44608 + endloop + endfacet + facet normal 0.990159 -0.119024 0.0736059 + outer loop + vertex 0.866613 2.02749 2.44238 + vertex 0.866208 2.0268 2.44671 + vertex 0.865669 2.02193 2.44608 + endloop + endfacet + facet normal 0.99077 -0.11817 0.0664174 + outer loop + vertex 0.865669 2.02193 2.44608 + vertex 0.866208 2.0268 2.44671 + vertex 0.865367 2.02205 2.45079 + endloop + endfacet + facet normal 0.99105 -0.0929741 0.0957899 + outer loop + vertex 0.866208 2.0268 2.44671 + vertex 0.86579 2.027 2.45123 + vertex 0.865367 2.02205 2.45079 + endloop + endfacet + facet normal 0.982152 -0.0979629 0.160565 + outer loop + vertex 0.865367 2.02205 2.45079 + vertex 0.86579 2.027 2.45123 + vertex 0.864665 2.0229 2.45561 + endloop + endfacet + facet normal 0.982005 -0.0952417 0.16308 + outer loop + vertex 0.86579 2.027 2.45123 + vertex 0.865303 2.02785 2.45466 + vertex 0.864665 2.0229 2.45561 + endloop + endfacet + facet normal 0.922107 -0.0410563 0.384751 + outer loop + vertex 0.863515 2.02235 2.45966 + vertex 0.864171 2.02692 2.45857 + vertex 0.862713 2.02441 2.4618 + endloop + endfacet + facet normal 0.96183 -0.0757353 0.262958 + outer loop + vertex 0.863515 2.02235 2.45966 + vertex 0.864665 2.0229 2.45561 + vertex 0.864171 2.02692 2.45857 + endloop + endfacet + facet normal 0.962536 -0.0740842 0.260837 + outer loop + vertex 0.864665 2.0229 2.45561 + vertex 0.865303 2.02785 2.45466 + vertex 0.864171 2.02692 2.45857 + endloop + endfacet + facet normal 0.918422 -0.0260431 0.394744 + outer loop + vertex 0.864171 2.02692 2.45857 + vertex 0.86264 2.02858 2.46225 + vertex 0.862713 2.02441 2.4618 + endloop + endfacet + facet normal 0.926415 -0.0411259 0.374252 + outer loop + vertex 0.867684 2.03 2.44 + vertex 0.867906 2.035 2.44 + vertex 0.866613 2.02749 2.44238 + endloop + endfacet + facet normal 0.979205 -0.115878 0.166523 + outer loop + vertex 0.867906 2.035 2.44 + vertex 0.867163 2.03246 2.4426 + vertex 0.866613 2.02749 2.44238 + endloop + endfacet + facet normal 0.990787 -0.113022 0.0746129 + outer loop + vertex 0.866613 2.02749 2.44238 + vertex 0.867163 2.03246 2.4426 + vertex 0.866208 2.0268 2.44671 + endloop + endfacet + facet normal 0.990793 -0.112424 0.0754378 + outer loop + vertex 0.867163 2.03246 2.4426 + vertex 0.866745 2.03176 2.44705 + vertex 0.866208 2.0268 2.44671 + endloop + endfacet + facet normal 0.988823 -0.113654 0.0965 + outer loop + vertex 0.866208 2.0268 2.44671 + vertex 0.866745 2.03176 2.44705 + vertex 0.86579 2.027 2.45123 + endloop + endfacet + facet normal 0.988696 -0.101195 0.110638 + outer loop + vertex 0.866745 2.03176 2.44705 + vertex 0.866224 2.03162 2.45158 + vertex 0.86579 2.027 2.45123 + endloop + endfacet + facet normal 0.980707 -0.104513 0.1652 + outer loop + vertex 0.86579 2.027 2.45123 + vertex 0.866224 2.03162 2.45158 + vertex 0.865303 2.02785 2.45466 + endloop + endfacet + facet normal 0.977858 -0.0811679 0.192888 + outer loop + vertex 0.866224 2.03162 2.45158 + vertex 0.865438 2.03154 2.45553 + vertex 0.865303 2.02785 2.45466 + endloop + endfacet + facet normal 0.962068 -0.095353 0.255602 + outer loop + vertex 0.865303 2.02785 2.45466 + vertex 0.865438 2.03154 2.45553 + vertex 0.864171 2.02692 2.45857 + endloop + endfacet + facet normal 0.950956 -0.0608915 0.303273 + outer loop + vertex 0.865438 2.03154 2.45553 + vertex 0.864316 2.03209 2.45916 + vertex 0.864171 2.02692 2.45857 + endloop + endfacet + facet normal 0.908587 -0.0718813 0.411464 + outer loop + vertex 0.864316 2.03209 2.45916 + vertex 0.86264 2.02858 2.46225 + vertex 0.864171 2.02692 2.45857 + endloop + endfacet + facet normal 0.898333 -0.0443904 0.437068 + outer loop + vertex 0.862744 2.03353 2.46254 + vertex 0.86264 2.02858 2.46225 + vertex 0.864316 2.03209 2.45916 + endloop + endfacet + facet normal 0.979754 -0.142074 0.14106 + outer loop + vertex 0.867906 2.035 2.44 + vertex 0.868631 2.04 2.44 + vertex 0.867163 2.03246 2.4426 + endloop + endfacet + facet normal 0.983471 -0.169132 0.0646513 + outer loop + vertex 0.868631 2.04 2.44 + vertex 0.867906 2.03686 2.44283 + vertex 0.867163 2.03246 2.4426 + endloop + endfacet + facet normal 0.983383 -0.16918 0.0658524 + outer loop + vertex 0.867163 2.03246 2.4426 + vertex 0.867906 2.03686 2.44283 + vertex 0.866745 2.03176 2.44705 + endloop + endfacet + facet normal 0.984123 -0.159611 0.0776249 + outer loop + vertex 0.867906 2.03686 2.44283 + vertex 0.867439 2.03655 2.4481 + vertex 0.866745 2.03176 2.44705 + endloop + endfacet + facet normal 0.980278 -0.165679 0.107726 + outer loop + vertex 0.866745 2.03176 2.44705 + vertex 0.867439 2.03655 2.4481 + vertex 0.866224 2.03162 2.45158 + endloop + endfacet + facet normal 0.979084 -0.132395 0.154487 + outer loop + vertex 0.867439 2.03655 2.4481 + vertex 0.866518 2.03514 2.45273 + vertex 0.866224 2.03162 2.45158 + endloop + endfacet + facet normal 0.971218 -0.143443 0.190157 + outer loop + vertex 0.866224 2.03162 2.45158 + vertex 0.866518 2.03514 2.45273 + vertex 0.865438 2.03154 2.45553 + endloop + endfacet + facet normal 0.966721 -0.110659 0.230661 + outer loop + vertex 0.866518 2.03514 2.45273 + vertex 0.865808 2.03588 2.45606 + vertex 0.865438 2.03154 2.45553 + endloop + endfacet + facet normal 0.943441 -0.118364 0.309693 + outer loop + vertex 0.865438 2.03154 2.45553 + vertex 0.865808 2.03588 2.45606 + vertex 0.864316 2.03209 2.45916 + endloop + endfacet + facet normal 0.931572 -0.076353 0.355449 + outer loop + vertex 0.865808 2.03588 2.45606 + vertex 0.864573 2.03681 2.4595 + vertex 0.864316 2.03209 2.45916 + endloop + endfacet + facet normal 0.889972 -0.0808384 0.448792 + outer loop + vertex 0.864573 2.03681 2.4595 + vertex 0.862744 2.03353 2.46254 + vertex 0.864316 2.03209 2.45916 + endloop + endfacet + facet normal 0.876772 -0.0456517 0.478735 + outer loop + vertex 0.862949 2.03845 2.46263 + vertex 0.862744 2.03353 2.46254 + vertex 0.864573 2.03681 2.4595 + endloop + endfacet + facet normal 0.953048 -0.254898 0.163486 + outer loop + vertex 0.87 2.04288 2.44 + vertex 0.868735 2.04032 2.44339 + vertex 0.867906 2.03686 2.44283 + endloop + endfacet + facet normal 0.8773 -0.417008 -0.237589 + outer loop + vertex 0.868631 2.04 2.44 + vertex 0.87 2.04288 2.44 + vertex 0.867906 2.03686 2.44283 + endloop + endfacet + facet normal 0.967016 -0.244924 0.0699412 + outer loop + vertex 0.868735 2.04032 2.44339 + vertex 0.868486 2.04056 2.44767 + vertex 0.867439 2.03655 2.4481 + endloop + endfacet + facet normal 0.967297 -0.243447 0.071199 + outer loop + vertex 0.867906 2.03686 2.44283 + vertex 0.868735 2.04032 2.44339 + vertex 0.867439 2.03655 2.4481 + endloop + endfacet + facet normal 0.946775 -0.272015 0.172119 + outer loop + vertex 0.868486 2.04056 2.44767 + vertex 0.868848 2.04294 2.44944 + vertex 0.867429 2.03991 2.45246 + endloop + endfacet + facet normal 0.956353 -0.230288 0.17988 + outer loop + vertex 0.868486 2.04056 2.44767 + vertex 0.867429 2.03991 2.45246 + vertex 0.867439 2.03655 2.4481 + endloop + endfacet + facet normal 0.974084 -0.177975 0.13959 + outer loop + vertex 0.867439 2.03655 2.4481 + vertex 0.867429 2.03991 2.45246 + vertex 0.866518 2.03514 2.45273 + endloop + endfacet + facet normal 0.955705 -0.168708 0.241174 + outer loop + vertex 0.866518 2.03514 2.45273 + vertex 0.867429 2.03991 2.45246 + vertex 0.865808 2.03588 2.45606 + endloop + endfacet + facet normal 0.948424 -0.118692 0.293946 + outer loop + vertex 0.867429 2.03991 2.45246 + vertex 0.866057 2.03972 2.45681 + vertex 0.865808 2.03588 2.45606 + endloop + endfacet + facet normal 0.92115 -0.131037 0.366486 + outer loop + vertex 0.865808 2.03588 2.45606 + vertex 0.866057 2.03972 2.45681 + vertex 0.864573 2.03681 2.4595 + endloop + endfacet + facet normal 0.904941 -0.074469 0.41897 + outer loop + vertex 0.866057 2.03972 2.45681 + vertex 0.864899 2.04154 2.45963 + vertex 0.864573 2.03681 2.4595 + endloop + endfacet + facet normal 0.868859 -0.0740335 0.489494 + outer loop + vertex 0.864899 2.04154 2.45963 + vertex 0.862949 2.03845 2.46263 + vertex 0.864573 2.03681 2.4595 + endloop + endfacet + facet normal 0.846687 -0.0192155 0.531744 + outer loop + vertex 0.863033 2.0434 2.46267 + vertex 0.862949 2.03845 2.46263 + vertex 0.864899 2.04154 2.45963 + endloop + endfacet + facet normal 0.948894 -0.208427 0.236979 + outer loop + vertex 0.868848 2.04294 2.44944 + vertex 0.86845 2.04436 2.45229 + vertex 0.867429 2.03991 2.45246 + endloop + endfacet + facet normal 0.920505 -0.140023 0.364779 + outer loop + vertex 0.86845 2.04436 2.45229 + vertex 0.868643 2.04838 2.45334 + vertex 0.866946 2.04433 2.45607 + endloop + endfacet + facet normal 0.911953 -0.195074 0.360953 + outer loop + vertex 0.86845 2.04436 2.45229 + vertex 0.866946 2.04433 2.45607 + vertex 0.867429 2.03991 2.45246 + endloop + endfacet + facet normal 0.946573 -0.135522 0.292632 + outer loop + vertex 0.867429 2.03991 2.45246 + vertex 0.866946 2.04433 2.45607 + vertex 0.866057 2.03972 2.45681 + endloop + endfacet + facet normal 0.895306 -0.102994 0.433381 + outer loop + vertex 0.866057 2.03972 2.45681 + vertex 0.866946 2.04433 2.45607 + vertex 0.864899 2.04154 2.45963 + endloop + endfacet + facet normal 0.88322 -0.052424 0.466019 + outer loop + vertex 0.866946 2.04433 2.45607 + vertex 0.865086 2.04659 2.45985 + vertex 0.864899 2.04154 2.45963 + endloop + endfacet + facet normal 0.835806 -0.0540631 0.546356 + outer loop + vertex 0.865086 2.04659 2.45985 + vertex 0.863033 2.0434 2.46267 + vertex 0.864899 2.04154 2.45963 + endloop + endfacet + facet normal 0.812925 -0.00751308 0.58232 + outer loop + vertex 0.862864 2.04851 2.46297 + vertex 0.863033 2.0434 2.46267 + vertex 0.865086 2.04659 2.45985 + endloop + endfacet + facet normal 0.904016 -0.0935046 0.417147 + outer loop + vertex 0.868643 2.04838 2.45334 + vertex 0.868871 2.05341 2.45397 + vertex 0.867108 2.04989 2.45701 + endloop + endfacet + facet normal 0.903193 -0.0968348 0.41817 + outer loop + vertex 0.866946 2.04433 2.45607 + vertex 0.868643 2.04838 2.45334 + vertex 0.867108 2.04989 2.45701 + endloop + endfacet + facet normal 0.864941 -0.107867 0.490145 + outer loop + vertex 0.866946 2.04433 2.45607 + vertex 0.867108 2.04989 2.45701 + vertex 0.865086 2.04659 2.45985 + endloop + endfacet + facet normal 0.837085 -0.0432544 0.54536 + outer loop + vertex 0.867108 2.04989 2.45701 + vertex 0.865044 2.05179 2.46033 + vertex 0.865086 2.04659 2.45985 + endloop + endfacet + facet normal 0.799933 -0.0484064 0.598134 + outer loop + vertex 0.865044 2.05179 2.46033 + vertex 0.862864 2.04851 2.46297 + vertex 0.865086 2.04659 2.45985 + endloop + endfacet + facet normal 0.818465 -0.0847284 0.568274 + outer loop + vertex 0.862488 2.05424 2.46437 + vertex 0.862864 2.04851 2.46297 + vertex 0.865044 2.05179 2.46033 + endloop + endfacet + facet normal 0.88915 -0.0672726 0.452644 + outer loop + vertex 0.868871 2.05341 2.45397 + vertex 0.869102 2.05836 2.45426 + vertex 0.867254 2.05498 2.45738 + endloop + endfacet + facet normal 0.891198 -0.0589378 0.449769 + outer loop + vertex 0.867108 2.04989 2.45701 + vertex 0.868871 2.05341 2.45397 + vertex 0.867254 2.05498 2.45738 + endloop + endfacet + facet normal 0.830303 -0.0648451 0.553527 + outer loop + vertex 0.867108 2.04989 2.45701 + vertex 0.867254 2.05498 2.45738 + vertex 0.865044 2.05179 2.46033 + endloop + endfacet + facet normal 0.841569 -0.0923713 0.532193 + outer loop + vertex 0.867254 2.05498 2.45738 + vertex 0.865305 2.05691 2.4608 + vertex 0.865044 2.05179 2.46033 + endloop + endfacet + facet normal 0.814788 -0.0946942 0.571973 + outer loop + vertex 0.865305 2.05691 2.4608 + vertex 0.862488 2.05424 2.46437 + vertex 0.865044 2.05179 2.46033 + endloop + endfacet + facet normal 0.831383 -0.460581 0.310915 + outer loop + vertex 0.865 2.06 2.46619 + vertex 0.862488 2.05424 2.46437 + vertex 0.865305 2.05691 2.4608 + endloop + endfacet + facet normal 0.874411 -0.0579414 0.481714 + outer loop + vertex 0.869102 2.05836 2.45426 + vertex 0.869202 2.06301 2.45463 + vertex 0.867405 2.05984 2.45751 + endloop + endfacet + facet normal 0.878617 -0.0400919 0.475841 + outer loop + vertex 0.867254 2.05498 2.45738 + vertex 0.869102 2.05836 2.45426 + vertex 0.867405 2.05984 2.45751 + endloop + endfacet + facet normal 0.857935 -0.0404361 0.512164 + outer loop + vertex 0.867254 2.05498 2.45738 + vertex 0.867405 2.05984 2.45751 + vertex 0.865305 2.05691 2.4608 + endloop + endfacet + facet normal 0.871738 -0.0833158 0.482837 + outer loop + vertex 0.867405 2.05984 2.45751 + vertex 0.865658 2.06188 2.46102 + vertex 0.865305 2.05691 2.4608 + endloop + endfacet + facet normal 0.992256 -0.0749128 0.0990749 + outer loop + vertex 0.865658 2.06188 2.46102 + vertex 0.865 2.06 2.46619 + vertex 0.865305 2.05691 2.4608 + endloop + endfacet + facet normal 0.991538 0.00906475 0.1295 + outer loop + vertex 0.865 2.065 2.46584 + vertex 0.865 2.06 2.46619 + vertex 0.865658 2.06188 2.46102 + endloop + endfacet + facet normal 0.848901 -0.0461174 0.526536 + outer loop + vertex 0.869202 2.06301 2.45463 + vertex 0.869034 2.0669 2.45525 + vertex 0.867403 2.06457 2.45767 + endloop + endfacet + facet normal 0.856468 -0.0167111 0.51593 + outer loop + vertex 0.867405 2.05984 2.45751 + vertex 0.869202 2.06301 2.45463 + vertex 0.867403 2.06457 2.45767 + endloop + endfacet + facet normal 0.891548 -0.0146063 0.45269 + outer loop + vertex 0.867405 2.05984 2.45751 + vertex 0.867403 2.06457 2.45767 + vertex 0.865658 2.06188 2.46102 + endloop + endfacet + facet normal 0.892598 -0.0180231 0.450494 + outer loop + vertex 0.867403 2.06457 2.45767 + vertex 0.865496 2.06761 2.46157 + vertex 0.865658 2.06188 2.46102 + endloop + endfacet + facet normal 0.992023 0.0160653 0.125032 + outer loop + vertex 0.865496 2.06761 2.46157 + vertex 0.865 2.065 2.46584 + vertex 0.865658 2.06188 2.46102 + endloop + endfacet + facet normal 0.99357 -0.00362083 0.113163 + outer loop + vertex 0.865 2.07 2.466 + vertex 0.865 2.065 2.46584 + vertex 0.865496 2.06761 2.46157 + endloop + endfacet + facet normal 0.841728 -0.0279816 0.539177 + outer loop + vertex 0.869034 2.0669 2.45525 + vertex 0.867394 2.06956 2.45794 + vertex 0.867403 2.06457 2.45767 + endloop + endfacet + facet normal 0.920702 -0.0417751 0.388024 + outer loop + vertex 0.867394 2.06956 2.45794 + vertex 0.867782 2.0738 2.45748 + vertex 0.865 2.075 2.46421 + endloop + endfacet + facet normal 0.90155 -0.0906056 0.423082 + outer loop + vertex 0.867394 2.06956 2.45794 + vertex 0.865 2.075 2.46421 + vertex 0.865496 2.06761 2.46157 + endloop + endfacet + facet normal 0.890852 -0.0232231 0.453699 + outer loop + vertex 0.867394 2.06956 2.45794 + vertex 0.865496 2.06761 2.46157 + vertex 0.867403 2.06457 2.45767 + endloop + endfacet + facet normal 0.995151 0.0337794 0.0923759 + outer loop + vertex 0.865496 2.06761 2.46157 + vertex 0.865 2.075 2.46421 + vertex 0.865 2.07284 2.465 + endloop + endfacet + facet normal 0.995063 0.0329647 0.0936055 + outer loop + vertex 0.865496 2.06761 2.46157 + vertex 0.865 2.07284 2.465 + vertex 0.865 2.07 2.466 + endloop + endfacet + facet normal 0.920959 -0.0392494 0.387678 + outer loop + vertex 0.867782 2.0738 2.45748 + vertex 0.867523 2.07819 2.45854 + vertex 0.865 2.075 2.46421 + endloop + endfacet + facet normal 0.892146 0.0834756 0.443968 + outer loop + vertex 0.865 2.075 2.46421 + vertex 0.867523 2.07819 2.45854 + vertex 0.865 2.08 2.46327 + endloop + endfacet + facet normal 0.94465 -0.317317 0.0833387 + outer loop + vertex 0.865025 2.07987 2.47146 + vertex 0.863699 2.07644 2.4734 + vertex 0.864218 2.07729 2.47076 + endloop + endfacet + facet normal 0.947998 -0.277023 0.156713 + outer loop + vertex 0.865025 2.07987 2.47146 + vertex 0.863966 2.07832 2.47511 + vertex 0.863699 2.07644 2.4734 + endloop + endfacet + facet normal 0.73112 -0.408891 0.546143 + outer loop + vertex 0.867523 2.07819 2.45854 + vertex 0.87 2.085 2.46032 + vertex 0.865 2.08 2.46327 + endloop + endfacet + facet normal 0.421326 0.109804 0.900238 + outer loop + vertex 0.865 2.08 2.46327 + vertex 0.87 2.085 2.46032 + vertex 0.865 2.085 2.46266 + endloop + endfacet + facet normal 0.758341 -0.431213 -0.48885 + outer loop + vertex 0.867701 2.085 2.47 + vertex 0.865 2.08025 2.47 + vertex 0.865 2.085 2.46581 + endloop + endfacet + facet normal 0.957427 -0.274984 -0.0878502 + outer loop + vertex 0.865 2.08025 2.47 + vertex 0.865025 2.07987 2.47146 + vertex 0.864218 2.07729 2.47076 + endloop + endfacet + facet normal 0.860467 -0.489284 -0.142119 + outer loop + vertex 0.865 2.08025 2.47 + vertex 0.867701 2.085 2.47 + vertex 0.865025 2.07987 2.47146 + endloop + endfacet + facet normal 0.739029 -0.203433 0.642224 + outer loop + vertex 0.867701 2.085 2.47 + vertex 0.866589 2.08402 2.47097 + vertex 0.865025 2.07987 2.47146 + endloop + endfacet + facet normal 0.907498 -0.334745 0.253759 + outer loop + vertex 0.863966 2.07832 2.47511 + vertex 0.865403 2.08199 2.47482 + vertex 0.863752 2.07961 2.47758 + endloop + endfacet + facet normal 0.92799 -0.353253 0.118516 + outer loop + vertex 0.863966 2.07832 2.47511 + vertex 0.865025 2.07987 2.47146 + vertex 0.865403 2.08199 2.47482 + endloop + endfacet + facet normal 0.934216 -0.339583 0.109201 + outer loop + vertex 0.865025 2.07987 2.47146 + vertex 0.866589 2.08402 2.47097 + vertex 0.865403 2.08199 2.47482 + endloop + endfacet + facet normal 0.909292 -0.315261 0.271658 + outer loop + vertex 0.864506 2.08272 2.47867 + vertex 0.863752 2.07961 2.47758 + vertex 0.865403 2.08199 2.47482 + endloop + endfacet + facet normal 0.570494 -0.391091 0.722208 + outer loop + vertex 0.862539 2.08072 2.47914 + vertex 0.863752 2.07961 2.47758 + vertex 0.864506 2.08272 2.47867 + endloop + endfacet + facet normal 0.593522 -0.422495 0.685003 + outer loop + vertex 0.864506 2.08272 2.47867 + vertex 0.863433 2.08362 2.48015 + vertex 0.862539 2.08072 2.47914 + endloop + endfacet + facet normal 0.718488 -0.142123 0.680864 + outer loop + vertex 0.867701 2.085 2.47 + vertex 0.86869 2.09 2.47 + vertex 0.866589 2.08402 2.47097 + endloop + endfacet + facet normal 0.943523 -0.31456 0.104003 + outer loop + vertex 0.86869 2.09 2.47 + vertex 0.867348 2.0867 2.47221 + vertex 0.866589 2.08402 2.47097 + endloop + endfacet + facet normal 0.939374 -0.321015 0.120526 + outer loop + vertex 0.866589 2.08402 2.47097 + vertex 0.867348 2.0867 2.47221 + vertex 0.865403 2.08199 2.47482 + endloop + endfacet + facet normal 0.940517 -0.291659 0.174252 + outer loop + vertex 0.867348 2.0867 2.47221 + vertex 0.866273 2.08583 2.47655 + vertex 0.865403 2.08199 2.47482 + endloop + endfacet + facet normal 0.904466 -0.327811 0.272911 + outer loop + vertex 0.865403 2.08199 2.47482 + vertex 0.866273 2.08583 2.47655 + vertex 0.864506 2.08272 2.47867 + endloop + endfacet + facet normal 0.874654 -0.193638 0.444393 + outer loop + vertex 0.866273 2.08583 2.47655 + vertex 0.864761 2.08616 2.47967 + vertex 0.864506 2.08272 2.47867 + endloop + endfacet + facet normal 0.70918 -0.24416 0.6614 + outer loop + vertex 0.864761 2.08616 2.47967 + vertex 0.863433 2.08362 2.48015 + vertex 0.864506 2.08272 2.47867 + endloop + endfacet + facet normal 0.45229 -0.0668984 0.889358 + outer loop + vertex 0.863281 2.0855 2.48037 + vertex 0.863433 2.08362 2.48015 + vertex 0.864761 2.08616 2.47967 + endloop + endfacet + facet normal 0.928977 -0.329719 0.168186 + outer loop + vertex 0.87 2.09305 2.47 + vertex 0.868238 2.0899 2.47357 + vertex 0.867348 2.0867 2.47221 + endloop + endfacet + facet normal 0.918414 -0.394452 -0.0304025 + outer loop + vertex 0.86869 2.09 2.47 + vertex 0.87 2.09305 2.47 + vertex 0.867348 2.0867 2.47221 + endloop + endfacet + facet normal 0.924225 -0.214508 0.315901 + outer loop + vertex 0.868238 2.0899 2.47357 + vertex 0.866774 2.08965 2.47768 + vertex 0.866273 2.08583 2.47655 + endloop + endfacet + facet normal 0.930144 -0.328391 0.164292 + outer loop + vertex 0.867348 2.0867 2.47221 + vertex 0.868238 2.0899 2.47357 + vertex 0.866273 2.08583 2.47655 + endloop + endfacet + facet normal 0.402898 -0.213867 0.889907 + outer loop + vertex 0.866774 2.08965 2.47768 + vertex 0.867019 2.0938 2.47857 + vertex 0.864409 2.08999 2.47883 + endloop + endfacet + facet normal 0.452583 0.230167 0.861505 + outer loop + vertex 0.866774 2.08965 2.47768 + vertex 0.864409 2.08999 2.47883 + vertex 0.864761 2.08616 2.47967 + endloop + endfacet + facet normal 0.862238 -0.244199 0.443747 + outer loop + vertex 0.866774 2.08965 2.47768 + vertex 0.864761 2.08616 2.47967 + vertex 0.866273 2.08583 2.47655 + endloop + endfacet + facet normal 0.639109 0.22008 0.736956 + outer loop + vertex 0.864761 2.08616 2.47967 + vertex 0.864409 2.08999 2.47883 + vertex 0.863805 2.08713 2.48021 + endloop + endfacet + facet normal 0.448316 -0.0550839 0.892176 + outer loop + vertex 0.864761 2.08616 2.47967 + vertex 0.863805 2.08713 2.48021 + vertex 0.863281 2.0855 2.48037 + endloop + endfacet + facet normal 0.579645 -0.754028 -0.308956 + outer loop + vertex 0.87 2.09634 2.465 + vertex 0.87 2.095 2.46827 + vertex 0.868257 2.095 2.465 + endloop + endfacet + facet normal -0.70814 0.261809 0.655739 + outer loop + vertex 0.864762 2.09858 2.47595 + vertex 0.863245 2.09796 2.47456 + vertex 0.864132 2.09517 2.47663 + endloop + endfacet + facet normal -0.408161 0.338823 0.847705 + outer loop + vertex 0.864132 2.09517 2.47663 + vertex 0.864409 2.08999 2.47883 + vertex 0.867019 2.0938 2.47857 + endloop + endfacet + facet normal -0.555359 0.00608889 0.831589 + outer loop + vertex 0.864132 2.09517 2.47663 + vertex 0.867019 2.0938 2.47857 + vertex 0.867138 2.09723 2.47862 + endloop + endfacet + facet normal -0.651426 0.262554 0.711835 + outer loop + vertex 0.864132 2.09517 2.47663 + vertex 0.867138 2.09723 2.47862 + vertex 0.864762 2.09858 2.47595 + endloop + endfacet + facet normal -0.796062 0.01804 0.604946 + outer loop + vertex 0.867138 2.09723 2.47862 + vertex 0.867019 2.0938 2.47857 + vertex 0.867902 2.09578 2.47967 + endloop + endfacet + facet normal -0.738141 0.0940558 0.668058 + outer loop + vertex 0.867902 2.09578 2.47967 + vertex 0.868215 2.09644 2.47992 + vertex 0.867138 2.09723 2.47862 + endloop + endfacet + facet normal -0.707663 0.331232 0.624098 + outer loop + vertex 0.863358 2.10056 2.4733 + vertex 0.863245 2.09796 2.47456 + vertex 0.864762 2.09858 2.47595 + endloop + endfacet + facet normal -0.683283 0.361935 0.634135 + outer loop + vertex 0.866255 2.10223 2.47547 + vertex 0.863358 2.10056 2.4733 + vertex 0.864762 2.09858 2.47595 + endloop + endfacet + facet normal -0.484126 0.548715 0.681567 + outer loop + vertex 0.87023 2.0994 2.47907 + vertex 0.867138 2.09723 2.47862 + vertex 0.868645 2.09714 2.47976 + endloop + endfacet + facet normal -0.417869 0.429844 0.800387 + outer loop + vertex 0.87023 2.0994 2.47907 + vertex 0.866255 2.10223 2.47547 + vertex 0.867138 2.09723 2.47862 + endloop + endfacet + facet normal -0.609546 0.34232 0.715032 + outer loop + vertex 0.866255 2.10223 2.47547 + vertex 0.864762 2.09858 2.47595 + vertex 0.867138 2.09723 2.47862 + endloop + endfacet + facet normal -0.513072 0.476226 0.714119 + outer loop + vertex 0.868645 2.09714 2.47976 + vertex 0.867138 2.09723 2.47862 + vertex 0.868215 2.09644 2.47992 + endloop + endfacet + facet normal -0.713728 0.40404 0.57214 + outer loop + vertex 0.865032 2.10744 2.47097 + vertex 0.862707 2.1062 2.46895 + vertex 0.863699 2.10396 2.47177 + endloop + endfacet + facet normal -0.682828 0.356639 0.637616 + outer loop + vertex 0.863699 2.10396 2.47177 + vertex 0.863358 2.10056 2.4733 + vertex 0.866255 2.10223 2.47547 + endloop + endfacet + facet normal -0.657725 0.39799 0.639532 + outer loop + vertex 0.863699 2.10396 2.47177 + vertex 0.866255 2.10223 2.47547 + vertex 0.865032 2.10744 2.47097 + endloop + endfacet + facet normal -0.757576 0.315633 0.571362 + outer loop + vertex 0.865032 2.10744 2.47097 + vertex 0.866255 2.10223 2.47547 + vertex 0.867394 2.10652 2.47461 + endloop + endfacet + facet normal -0.69822 0.314233 0.643232 + outer loop + vertex 0.866255 2.10223 2.47547 + vertex 0.869264 2.10418 2.47779 + vertex 0.867394 2.10652 2.47461 + endloop + endfacet + facet normal -0.638684 0.0760415 0.765702 + outer loop + vertex 0.87023 2.0994 2.47907 + vertex 0.869264 2.10418 2.47779 + vertex 0.866255 2.10223 2.47547 + endloop + endfacet + facet normal -0.701042 0.501612 0.506878 + outer loop + vertex 0.865302 2.11221 2.46692 + vertex 0.863207 2.11185 2.46438 + vertex 0.862958 2.10948 2.46638 + endloop + endfacet + facet normal -0.708918 0.467672 0.527937 + outer loop + vertex 0.862958 2.10948 2.46638 + vertex 0.862707 2.1062 2.46895 + vertex 0.865032 2.10744 2.47097 + endloop + endfacet + facet normal -0.692307 0.489548 0.530145 + outer loop + vertex 0.865302 2.11221 2.46692 + vertex 0.862958 2.10948 2.46638 + vertex 0.865032 2.10744 2.47097 + endloop + endfacet + facet normal -0.712928 0.477001 0.514008 + outer loop + vertex 0.865302 2.11221 2.46692 + vertex 0.865032 2.10744 2.47097 + vertex 0.867797 2.11039 2.47207 + endloop + endfacet + facet normal -0.697623 0.49881 0.514305 + outer loop + vertex 0.865302 2.11221 2.46692 + vertex 0.867797 2.11039 2.47207 + vertex 0.86744 2.11296 2.46909 + endloop + endfacet + facet normal -0.7057 0.439013 0.556107 + outer loop + vertex 0.867797 2.11039 2.47207 + vertex 0.867394 2.10652 2.47461 + vertex 0.869303 2.1078 2.47603 + endloop + endfacet + facet normal -0.696737 0.443258 0.563986 + outer loop + vertex 0.865032 2.10744 2.47097 + vertex 0.867394 2.10652 2.47461 + vertex 0.867797 2.11039 2.47207 + endloop + endfacet + facet normal -0.693213 0.32102 0.645292 + outer loop + vertex 0.869303 2.1078 2.47603 + vertex 0.867394 2.10652 2.47461 + vertex 0.869264 2.10418 2.47779 + endloop + endfacet + facet normal -0.699757 0.586603 0.407722 + outer loop + vertex 0.866041 2.1161 2.46305 + vertex 0.863645 2.11528 2.46011 + vertex 0.863727 2.11343 2.46291 + endloop + endfacet + facet normal -0.644761 0.622918 0.443009 + outer loop + vertex 0.863727 2.11343 2.46291 + vertex 0.863207 2.11185 2.46438 + vertex 0.865302 2.11221 2.46692 + endloop + endfacet + facet normal -0.687447 0.574019 0.444882 + outer loop + vertex 0.866041 2.1161 2.46305 + vertex 0.863727 2.11343 2.46291 + vertex 0.865302 2.11221 2.46692 + endloop + endfacet + facet normal -0.611751 0.613683 0.499152 + outer loop + vertex 0.866041 2.1161 2.46305 + vertex 0.865302 2.11221 2.46692 + vertex 0.867715 2.11477 2.46673 + endloop + endfacet + facet normal -0.577928 0.647968 0.496121 + outer loop + vertex 0.866041 2.1161 2.46305 + vertex 0.867715 2.11477 2.46673 + vertex 0.868416 2.11689 2.46478 + endloop + endfacet + facet normal -0.646486 0.640234 0.414918 + outer loop + vertex 0.867715 2.11477 2.46673 + vertex 0.865302 2.11221 2.46692 + vertex 0.86744 2.11296 2.46909 + endloop + endfacet + facet normal -0.785489 0.212759 0.581154 + outer loop + vertex 0.866041 2.1161 2.46305 + vertex 0.865 2.12058 2.46 + vertex 0.863645 2.11528 2.46011 + endloop + endfacet + facet normal -0.697103 0.285348 0.657742 + outer loop + vertex 0.866041 2.1161 2.46305 + vertex 0.87 2.12127 2.465 + vertex 0.865 2.12058 2.46 + endloop + endfacet + facet normal -0.225082 0.97006 0.0912193 + outer loop + vertex 0.87 2.12127 2.465 + vertex 0.87 2.12174 2.46 + vertex 0.865 2.12058 2.46 + endloop + endfacet + facet normal -0.618186 0.184903 0.763974 + outer loop + vertex 0.87 2.12127 2.465 + vertex 0.866041 2.1161 2.46305 + vertex 0.868416 2.11689 2.46478 + endloop + endfacet + facet normal -0.232808 -0.970835 0.0572774 + outer loop + vertex 0.875 0.906851 2.46 + vertex 0.875 0.907146 2.465 + vertex 0.87 0.90805 2.46 + endloop + endfacet + facet normal -0.246395 -0.966518 0.0716451 + outer loop + vertex 0.875 0.907146 2.465 + vertex 0.869471 0.908306 2.46163 + vertex 0.87 0.90805 2.46 + endloop + endfacet + facet normal -0.451691 -0.872823 0.184809 + outer loop + vertex 0.867879 0.909874 2.46384 + vertex 0.873553 0.90748 2.4664 + vertex 0.870518 0.90939 2.468 + endloop + endfacet + facet normal -0.472264 -0.842682 0.258561 + outer loop + vertex 0.867879 0.909874 2.46384 + vertex 0.869471 0.908306 2.46163 + vertex 0.873553 0.90748 2.4664 + endloop + endfacet + facet normal -0.212961 -0.976972 0.0131669 + outer loop + vertex 0.869471 0.908306 2.46163 + vertex 0.875 0.907146 2.465 + vertex 0.873553 0.90748 2.4664 + endloop + endfacet + facet normal -0.438806 -0.873647 0.210214 + outer loop + vertex 0.874252 0.908101 2.47044 + vertex 0.870518 0.90939 2.468 + vertex 0.873553 0.90748 2.4664 + endloop + endfacet + facet normal -0.475765 -0.830521 0.289625 + outer loop + vertex 0.871733 0.909534 2.47041 + vertex 0.870518 0.90939 2.468 + vertex 0.874252 0.908101 2.47044 + endloop + endfacet + facet normal -0.444165 -0.77157 0.455409 + outer loop + vertex 0.874252 0.908101 2.47044 + vertex 0.873318 0.910095 2.4729 + vertex 0.871733 0.909534 2.47041 + endloop + endfacet + facet normal -0.600726 -0.743285 0.294373 + outer loop + vertex 0.867879 0.909874 2.46384 + vertex 0.870518 0.90939 2.468 + vertex 0.867487 0.91141 2.46691 + endloop + endfacet + facet normal -0.650572 -0.664366 0.367932 + outer loop + vertex 0.870518 0.90939 2.468 + vertex 0.871733 0.909534 2.47041 + vertex 0.869402 0.911639 2.47009 + endloop + endfacet + facet normal -0.60279 -0.682625 0.413119 + outer loop + vertex 0.867487 0.91141 2.46691 + vertex 0.870518 0.90939 2.468 + vertex 0.869402 0.911639 2.47009 + endloop + endfacet + facet normal -0.637693 -0.508831 0.578307 + outer loop + vertex 0.874112 0.911867 2.47588 + vertex 0.871959 0.915884 2.47704 + vertex 0.87047 0.913565 2.47336 + endloop + endfacet + facet normal -0.62838 -0.583279 0.514707 + outer loop + vertex 0.873318 0.910095 2.4729 + vertex 0.874112 0.911867 2.47588 + vertex 0.87047 0.913565 2.47336 + endloop + endfacet + facet normal -0.614855 -0.575399 0.539323 + outer loop + vertex 0.873318 0.910095 2.4729 + vertex 0.87047 0.913565 2.47336 + vertex 0.869402 0.911639 2.47009 + endloop + endfacet + facet normal -0.610259 -0.596413 0.521417 + outer loop + vertex 0.873318 0.910095 2.4729 + vertex 0.869402 0.911639 2.47009 + vertex 0.871733 0.909534 2.47041 + endloop + endfacet + facet normal -0.660875 -0.512553 0.548209 + outer loop + vertex 0.874112 0.911867 2.47588 + vertex 0.875683 0.91294 2.47878 + vertex 0.871959 0.915884 2.47704 + endloop + endfacet + facet normal -0.677249 -0.467397 0.56822 + outer loop + vertex 0.867545 0.918103 2.47361 + vertex 0.87047 0.913565 2.47336 + vertex 0.871959 0.915884 2.47704 + endloop + endfacet + facet normal -0.679665 -0.394684 0.618288 + outer loop + vertex 0.869722 0.920391 2.47746 + vertex 0.867545 0.918103 2.47361 + vertex 0.871959 0.915884 2.47704 + endloop + endfacet + facet normal -0.656075 -0.492572 0.571785 + outer loop + vertex 0.87514 0.915512 2.48037 + vertex 0.871959 0.915884 2.47704 + vertex 0.875683 0.91294 2.47878 + endloop + endfacet + facet normal -0.691933 -0.370402 0.619702 + outer loop + vertex 0.87514 0.915512 2.48037 + vertex 0.872828 0.918961 2.47985 + vertex 0.871959 0.915884 2.47704 + endloop + endfacet + facet normal -0.667738 -0.390213 0.633924 + outer loop + vertex 0.872828 0.918961 2.47985 + vertex 0.869722 0.920391 2.47746 + vertex 0.871959 0.915884 2.47704 + endloop + endfacet + facet normal -0.665289 -0.346266 0.66143 + outer loop + vertex 0.87514 0.915512 2.48037 + vertex 0.876158 0.917729 2.48256 + vertex 0.872828 0.918961 2.47985 + endloop + endfacet + facet normal -0.657234 -0.424069 0.623064 + outer loop + vertex 0.867545 0.918103 2.47361 + vertex 0.869722 0.920391 2.47746 + vertex 0.86731 0.921895 2.47594 + endloop + endfacet + facet normal -0.604435 -0.1862 0.774589 + outer loop + vertex 0.868839 0.925109 2.4779 + vertex 0.86731 0.921895 2.47594 + vertex 0.869722 0.920391 2.47746 + endloop + endfacet + facet normal -0.637849 -0.189792 0.74641 + outer loop + vertex 0.868839 0.925109 2.4779 + vertex 0.869722 0.920391 2.47746 + vertex 0.87152 0.922082 2.47943 + endloop + endfacet + facet normal -0.649354 -0.171214 0.740962 + outer loop + vertex 0.87152 0.922082 2.47943 + vertex 0.869722 0.920391 2.47746 + vertex 0.872828 0.918961 2.47985 + endloop + endfacet + facet normal -0.549974 -0.117847 0.826826 + outer loop + vertex 0.872828 0.918961 2.47985 + vertex 0.874713 0.92128 2.48143 + vertex 0.87152 0.922082 2.47943 + endloop + endfacet + facet normal -0.633421 -0.0136962 0.773686 + outer loop + vertex 0.876158 0.917729 2.48256 + vertex 0.874713 0.92128 2.48143 + vertex 0.872828 0.918961 2.47985 + endloop + endfacet + facet normal 0.62366 0.362261 0.692687 + outer loop + vertex 0.874482 0.926507 2.46577 + vertex 0.875 0.927094 2.465 + vertex 0.873312 0.93 2.465 + endloop + endfacet + facet normal 0.808325 0.371806 0.456476 + outer loop + vertex 0.872689 0.928524 2.4673 + vertex 0.874482 0.926507 2.46577 + vertex 0.873312 0.93 2.465 + endloop + endfacet + facet normal 0.769177 0.635953 0.0626874 + outer loop + vertex 0.874193 0.926442 2.46999 + vertex 0.874482 0.926507 2.46577 + vertex 0.872689 0.928524 2.4673 + endloop + endfacet + facet normal 0.75043 0.655062 0.0880239 + outer loop + vertex 0.871756 0.929007 2.47167 + vertex 0.874193 0.926442 2.46999 + vertex 0.872689 0.928524 2.4673 + endloop + endfacet + facet normal 0.776835 0.58449 0.234307 + outer loop + vertex 0.872841 0.926067 2.4754 + vertex 0.874193 0.926442 2.46999 + vertex 0.871756 0.929007 2.47167 + endloop + endfacet + facet normal 0.715569 0.634745 0.291649 + outer loop + vertex 0.869927 0.928776 2.47666 + vertex 0.872841 0.926067 2.4754 + vertex 0.871756 0.929007 2.47167 + endloop + endfacet + facet normal 0.116015 0.851503 0.511355 + outer loop + vertex 0.872979 0.923821 2.47911 + vertex 0.872841 0.926067 2.4754 + vertex 0.868839 0.925109 2.4779 + endloop + endfacet + facet normal -0.17391 0.314771 0.933099 + outer loop + vertex 0.872979 0.923821 2.47911 + vertex 0.868839 0.925109 2.4779 + vertex 0.87152 0.922082 2.47943 + endloop + endfacet + facet normal 0.500109 0.14209 0.854226 + outer loop + vertex 0.872841 0.926067 2.4754 + vertex 0.869927 0.928776 2.47666 + vertex 0.868839 0.925109 2.4779 + endloop + endfacet + facet normal 0.304246 -0.448242 0.840544 + outer loop + vertex 0.867871 0.927685 2.47963 + vertex 0.868839 0.925109 2.4779 + vertex 0.868749 0.927734 2.47934 + endloop + endfacet + facet normal 0.925147 -0.156986 0.345627 + outer loop + vertex 0.869927 0.928776 2.47666 + vertex 0.868749 0.927734 2.47934 + vertex 0.868839 0.925109 2.4779 + endloop + endfacet + facet normal -0.384266 0.466471 0.796709 + outer loop + vertex 0.87152 0.922082 2.47943 + vertex 0.874713 0.92128 2.48143 + vertex 0.872979 0.923821 2.47911 + endloop + endfacet + facet normal 0.275947 -0.631024 0.725025 + outer loop + vertex 0.867871 0.927685 2.47963 + vertex 0.868749 0.927734 2.47934 + vertex 0.868229 0.928386 2.4801 + endloop + endfacet + facet normal -0.180802 -0.141197 0.973332 + outer loop + vertex 0.870101 0.933014 2.46484 + vertex 0.873312 0.93 2.465 + vertex 0.87 0.934241 2.465 + endloop + endfacet + facet normal 0.673441 0.725115 0.143822 + outer loop + vertex 0.870101 0.933014 2.46484 + vertex 0.870724 0.931839 2.46785 + vertex 0.873312 0.93 2.465 + endloop + endfacet + facet normal 0.792365 0.39358 0.466103 + outer loop + vertex 0.870724 0.931839 2.46785 + vertex 0.872689 0.928524 2.4673 + vertex 0.873312 0.93 2.465 + endloop + endfacet + facet normal 0.862069 0.489777 0.130212 + outer loop + vertex 0.872689 0.928524 2.4673 + vertex 0.870724 0.931839 2.46785 + vertex 0.871756 0.929007 2.47167 + endloop + endfacet + facet normal 0.863412 0.487876 0.12844 + outer loop + vertex 0.870724 0.931839 2.46785 + vertex 0.869799 0.93212 2.473 + vertex 0.871756 0.929007 2.47167 + endloop + endfacet + facet normal 0.883364 0.309803 0.351697 + outer loop + vertex 0.868197 0.932023 2.47711 + vertex 0.869799 0.93212 2.473 + vertex 0.868439 0.935132 2.47376 + endloop + endfacet + facet normal 0.848628 0.40492 0.340396 + outer loop + vertex 0.868197 0.932023 2.47711 + vertex 0.869927 0.928776 2.47666 + vertex 0.869799 0.93212 2.473 + endloop + endfacet + facet normal 0.856074 0.396078 0.332055 + outer loop + vertex 0.869927 0.928776 2.47666 + vertex 0.871756 0.929007 2.47167 + vertex 0.869799 0.93212 2.473 + endloop + endfacet + facet normal 0.885597 0.138731 0.443251 + outer loop + vertex 0.869927 0.928776 2.47666 + vertex 0.868608 0.92919 2.47916 + vertex 0.868749 0.927734 2.47934 + endloop + endfacet + facet normal 0.838402 0.394531 0.376067 + outer loop + vertex 0.868197 0.932023 2.47711 + vertex 0.868608 0.92919 2.47916 + vertex 0.869927 0.928776 2.47666 + endloop + endfacet + facet normal 0.870496 0.140662 0.471647 + outer loop + vertex 0.868749 0.927734 2.47934 + vertex 0.868608 0.92919 2.47916 + vertex 0.868229 0.928386 2.4801 + endloop + endfacet + facet normal 0.992164 -0.0375906 0.119152 + outer loop + vertex 0.870387 0.938867 2.45723 + vertex 0.87 0.937441 2.46 + vertex 0.87 0.935 2.45923 + endloop + endfacet + facet normal 0.793559 0.215431 0.569081 + outer loop + vertex 0.870387 0.938867 2.45723 + vertex 0.87 0.935 2.45923 + vertex 0.872421 0.939539 2.45414 + endloop + endfacet + facet normal 0.419827 0.569389 0.706783 + outer loop + vertex 0.872421 0.939539 2.45414 + vertex 0.87 0.935 2.45923 + vertex 0.875 0.935 2.45626 + endloop + endfacet + facet normal 0.992263 -0.0424104 0.116688 + outer loop + vertex 0.870387 0.938867 2.45723 + vertex 0.87 0.94 2.46093 + vertex 0.87 0.937441 2.46 + endloop + endfacet + facet normal 0.896535 0.442787 -0.0128284 + outer loop + vertex 0.870101 0.933014 2.46484 + vertex 0.86915 0.934979 2.46621 + vertex 0.870724 0.931839 2.46785 + endloop + endfacet + facet normal 0.919528 0.365213 0.145214 + outer loop + vertex 0.870724 0.931839 2.46785 + vertex 0.868967 0.935503 2.46976 + vertex 0.869799 0.93212 2.473 + endloop + endfacet + facet normal 0.897655 0.440303 -0.0186852 + outer loop + vertex 0.86915 0.934979 2.46621 + vertex 0.868967 0.935503 2.46976 + vertex 0.870724 0.931839 2.46785 + endloop + endfacet + facet normal 0.914483 0.373633 0.155305 + outer loop + vertex 0.869799 0.93212 2.473 + vertex 0.868967 0.935503 2.46976 + vertex 0.868439 0.935132 2.47376 + endloop + endfacet + facet normal 0.860158 0.0280965 0.509253 + outer loop + vertex 0.872421 0.939539 2.45414 + vertex 0.872723 0.945274 2.45331 + vertex 0.870749 0.942461 2.4568 + endloop + endfacet + facet normal 0.837089 -0.0192588 0.546728 + outer loop + vertex 0.870387 0.938867 2.45723 + vertex 0.872421 0.939539 2.45414 + vertex 0.870749 0.942461 2.4568 + endloop + endfacet + facet normal 0.98807 -0.0841079 0.129007 + outer loop + vertex 0.870749 0.942461 2.4568 + vertex 0.87 0.94 2.46093 + vertex 0.870387 0.938867 2.45723 + endloop + endfacet + facet normal 0.987246 -0.0432093 0.153223 + outer loop + vertex 0.87 0.945 2.46234 + vertex 0.87 0.94 2.46093 + vertex 0.870749 0.942461 2.4568 + endloop + endfacet + facet normal 0.858581 0.00322343 0.512668 + outer loop + vertex 0.872723 0.945274 2.45331 + vertex 0.872895 0.950238 2.45299 + vertex 0.870868 0.947226 2.4564 + endloop + endfacet + facet normal 0.863105 0.020278 0.504618 + outer loop + vertex 0.870749 0.942461 2.4568 + vertex 0.872723 0.945274 2.45331 + vertex 0.870868 0.947226 2.4564 + endloop + endfacet + facet normal 0.990083 -0.0132034 0.139859 + outer loop + vertex 0.870868 0.947226 2.4564 + vertex 0.87 0.945 2.46234 + vertex 0.870749 0.942461 2.4568 + endloop + endfacet + facet normal 0.823562 0.480923 0.300763 + outer loop + vertex 0.868693 0.949352 2.45896 + vertex 0.87 0.945 2.46234 + vertex 0.870868 0.947226 2.4564 + endloop + endfacet + facet normal 0.820025 0.0833983 0.566219 + outer loop + vertex 0.872895 0.950238 2.45299 + vertex 0.873052 0.954156 2.45219 + vertex 0.87102 0.952877 2.45532 + endloop + endfacet + facet normal 0.821317 0.0863622 0.563898 + outer loop + vertex 0.870868 0.947226 2.4564 + vertex 0.872895 0.950238 2.45299 + vertex 0.87102 0.952877 2.45532 + endloop + endfacet + facet normal 0.795341 0.0937791 0.598865 + outer loop + vertex 0.87102 0.952877 2.45532 + vertex 0.868693 0.949352 2.45896 + vertex 0.870868 0.947226 2.4564 + endloop + endfacet + facet normal 0.784925 0.111598 0.609457 + outer loop + vertex 0.867932 0.95406 2.45908 + vertex 0.868693 0.949352 2.45896 + vertex 0.87102 0.952877 2.45532 + endloop + endfacet + facet normal 0.891773 0.248116 0.378391 + outer loop + vertex 0.873701 0.956568 2.44989 + vertex 0.87359 0.959454 2.44826 + vertex 0.872528 0.9582 2.45159 + endloop + endfacet + facet normal 0.881127 0.178854 0.437752 + outer loop + vertex 0.873052 0.954156 2.45219 + vertex 0.873701 0.956568 2.44989 + vertex 0.872528 0.9582 2.45159 + endloop + endfacet + facet normal 0.786747 0.188826 0.587685 + outer loop + vertex 0.873052 0.954156 2.45219 + vertex 0.872528 0.9582 2.45159 + vertex 0.87102 0.952877 2.45532 + endloop + endfacet + facet normal 0.884399 0.0724353 0.461076 + outer loop + vertex 0.87102 0.952877 2.45532 + vertex 0.872528 0.9582 2.45159 + vertex 0.870515 0.95853 2.4554 + endloop + endfacet + facet normal 0.780699 0.0608869 0.621935 + outer loop + vertex 0.870515 0.95853 2.4554 + vertex 0.867932 0.95406 2.45908 + vertex 0.87102 0.952877 2.45532 + endloop + endfacet + facet normal 0.845621 -0.0512408 0.531318 + outer loop + vertex 0.868517 0.959966 2.45872 + vertex 0.867932 0.95406 2.45908 + vertex 0.870515 0.95853 2.4554 + endloop + endfacet + facet normal 0.949266 0.234951 0.209026 + outer loop + vertex 0.873846 0.961384 2.4455 + vertex 0.873689 0.964161 2.4431 + vertex 0.873055 0.963327 2.44691 + endloop + endfacet + facet normal 0.947613 0.213712 0.237396 + outer loop + vertex 0.87359 0.959454 2.44826 + vertex 0.873846 0.961384 2.4455 + vertex 0.873055 0.963327 2.44691 + endloop + endfacet + facet normal 0.88887 0.255549 0.38027 + outer loop + vertex 0.87359 0.959454 2.44826 + vertex 0.873055 0.963327 2.44691 + vertex 0.872528 0.9582 2.45159 + endloop + endfacet + facet normal 0.953398 0.143917 0.265179 + outer loop + vertex 0.872528 0.9582 2.45159 + vertex 0.873055 0.963327 2.44691 + vertex 0.871829 0.96335 2.4513 + endloop + endfacet + facet normal 0.880005 0.144255 0.452527 + outer loop + vertex 0.872528 0.9582 2.45159 + vertex 0.871829 0.96335 2.4513 + vertex 0.870515 0.95853 2.4554 + endloop + endfacet + facet normal 0.939834 0.0324653 0.340085 + outer loop + vertex 0.871829 0.96335 2.4513 + vertex 0.870358 0.96397 2.45531 + vertex 0.870515 0.95853 2.4554 + endloop + endfacet + facet normal 0.862455 0.0328538 0.505067 + outer loop + vertex 0.870358 0.96397 2.45531 + vertex 0.868517 0.959966 2.45872 + vertex 0.870515 0.95853 2.4554 + endloop + endfacet + facet normal 0.893559 -0.0300144 0.447941 + outer loop + vertex 0.868588 0.965241 2.45893 + vertex 0.868517 0.959966 2.45872 + vertex 0.870358 0.96397 2.45531 + endloop + endfacet + facet normal 0.559021 0.0912623 0.824116 + outer loop + vertex 0.874345 0.965996 2.43563 + vertex 0.875 0.967648 2.435 + vertex 0.874616 0.97 2.435 + endloop + endfacet + facet normal 0.861041 0.0213611 0.508086 + outer loop + vertex 0.873709 0.969726 2.43655 + vertex 0.874345 0.965996 2.43563 + vertex 0.874616 0.97 2.435 + endloop + endfacet + facet normal 0.983158 0.138231 0.11955 + outer loop + vertex 0.873978 0.965424 2.43931 + vertex 0.874345 0.965996 2.43563 + vertex 0.873709 0.969726 2.43655 + endloop + endfacet + facet normal 0.972918 0.164835 0.16205 + outer loop + vertex 0.873143 0.968419 2.44128 + vertex 0.873978 0.965424 2.43931 + vertex 0.873709 0.969726 2.43655 + endloop + endfacet + facet normal 0.973815 0.182675 0.135327 + outer loop + vertex 0.873689 0.964161 2.4431 + vertex 0.873978 0.965424 2.43931 + vertex 0.873143 0.968419 2.44128 + endloop + endfacet + facet normal 0.956023 0.210041 0.2047 + outer loop + vertex 0.873689 0.964161 2.4431 + vertex 0.873143 0.968419 2.44128 + vertex 0.873055 0.963327 2.44691 + endloop + endfacet + facet normal 0.975487 0.155504 0.155706 + outer loop + vertex 0.873055 0.963327 2.44691 + vertex 0.873143 0.968419 2.44128 + vertex 0.872341 0.968418 2.4463 + endloop + endfacet + facet normal 0.950253 0.164988 0.264192 + outer loop + vertex 0.873055 0.963327 2.44691 + vertex 0.872341 0.968418 2.4463 + vertex 0.871829 0.96335 2.4513 + endloop + endfacet + facet normal 0.97699 0.0915883 0.192622 + outer loop + vertex 0.872341 0.968418 2.4463 + vertex 0.871407 0.968552 2.45097 + vertex 0.871829 0.96335 2.4513 + endloop + endfacet + facet normal 0.939043 0.0972121 0.329769 + outer loop + vertex 0.871829 0.96335 2.4513 + vertex 0.871407 0.968552 2.45097 + vertex 0.870358 0.96397 2.45531 + endloop + endfacet + facet normal 0.96157 0.0373789 0.272005 + outer loop + vertex 0.871407 0.968552 2.45097 + vertex 0.870178 0.969185 2.45523 + vertex 0.870358 0.96397 2.45531 + endloop + endfacet + facet normal 0.902692 0.0376886 0.428633 + outer loop + vertex 0.870178 0.969185 2.45523 + vertex 0.868588 0.965241 2.45893 + vertex 0.870358 0.96397 2.45531 + endloop + endfacet + facet normal 0.914487 0.0103139 0.404483 + outer loop + vertex 0.868476 0.970278 2.45905 + vertex 0.868588 0.965241 2.45893 + vertex 0.870178 0.969185 2.45523 + endloop + endfacet + facet normal 0.858625 0.044136 0.510701 + outer loop + vertex 0.874616 0.97 2.435 + vertex 0.874359 0.975 2.435 + vertex 0.873709 0.969726 2.43655 + endloop + endfacet + facet normal 0.788113 0.0820057 0.610043 + outer loop + vertex 0.874359 0.975 2.435 + vertex 0.872943 0.974112 2.43695 + vertex 0.873709 0.969726 2.43655 + endloop + endfacet + facet normal 0.974797 0.155719 0.159755 + outer loop + vertex 0.873709 0.969726 2.43655 + vertex 0.872943 0.974112 2.43695 + vertex 0.873143 0.968419 2.44128 + endloop + endfacet + facet normal 0.974654 0.156097 0.160259 + outer loop + vertex 0.872943 0.974112 2.43695 + vertex 0.87233 0.973646 2.44113 + vertex 0.873143 0.968419 2.44128 + endloop + endfacet + facet normal 0.975397 0.156083 0.155692 + outer loop + vertex 0.873143 0.968419 2.44128 + vertex 0.87233 0.973646 2.44113 + vertex 0.872341 0.968418 2.4463 + endloop + endfacet + facet normal 0.986199 0.117492 0.116646 + outer loop + vertex 0.87233 0.973646 2.44113 + vertex 0.871766 0.973576 2.44597 + vertex 0.872341 0.968418 2.4463 + endloop + endfacet + facet normal 0.97408 0.120874 0.191199 + outer loop + vertex 0.872341 0.968418 2.4463 + vertex 0.871766 0.973576 2.44597 + vertex 0.871407 0.968552 2.45097 + endloop + endfacet + facet normal 0.984516 0.0833135 0.154231 + outer loop + vertex 0.871766 0.973576 2.44597 + vertex 0.871005 0.973727 2.45075 + vertex 0.871407 0.968552 2.45097 + endloop + endfacet + facet normal 0.960537 0.0862822 0.264431 + outer loop + vertex 0.871407 0.968552 2.45097 + vertex 0.871005 0.973727 2.45075 + vertex 0.870178 0.969185 2.45523 + endloop + endfacet + facet normal 0.969665 0.0579847 0.237461 + outer loop + vertex 0.871005 0.973727 2.45075 + vertex 0.869902 0.974236 2.45512 + vertex 0.870178 0.969185 2.45523 + endloop + endfacet + facet normal 0.91799 0.0584759 0.392269 + outer loop + vertex 0.869902 0.974236 2.45512 + vertex 0.868476 0.970278 2.45905 + vertex 0.870178 0.969185 2.45523 + endloop + endfacet + facet normal 0.926039 0.0388536 0.375423 + outer loop + vertex 0.86834 0.975215 2.45888 + vertex 0.868476 0.970278 2.45905 + vertex 0.869902 0.974236 2.45512 + endloop + endfacet + facet normal 0.758923 0.169542 0.628722 + outer loop + vertex 0.874359 0.975 2.435 + vertex 0.873242 0.98 2.435 + vertex 0.872943 0.974112 2.43695 + endloop + endfacet + facet normal 0.829509 0.13705 0.541416 + outer loop + vertex 0.873242 0.98 2.435 + vertex 0.872073 0.978824 2.43709 + vertex 0.872943 0.974112 2.43695 + endloop + endfacet + facet normal 0.971285 0.174424 0.161809 + outer loop + vertex 0.872943 0.974112 2.43695 + vertex 0.872073 0.978824 2.43709 + vertex 0.87233 0.973646 2.44113 + endloop + endfacet + facet normal 0.98274 0.141615 0.119027 + outer loop + vertex 0.872073 0.978824 2.43709 + vertex 0.871612 0.978544 2.44123 + vertex 0.87233 0.973646 2.44113 + endloop + endfacet + facet normal 0.983015 0.141705 0.116625 + outer loop + vertex 0.87233 0.973646 2.44113 + vertex 0.871612 0.978544 2.44123 + vertex 0.871766 0.973576 2.44597 + endloop + endfacet + facet normal 0.98928 0.115664 0.0891415 + outer loop + vertex 0.871612 0.978544 2.44123 + vertex 0.871175 0.97864 2.44596 + vertex 0.871766 0.973576 2.44597 + endloop + endfacet + facet normal 0.981558 0.114934 0.152758 + outer loop + vertex 0.871766 0.973576 2.44597 + vertex 0.871175 0.97864 2.44596 + vertex 0.871005 0.973727 2.45075 + endloop + endfacet + facet normal 0.985319 0.100455 0.138041 + outer loop + vertex 0.871175 0.97864 2.44596 + vertex 0.870503 0.978713 2.4507 + vertex 0.871005 0.973727 2.45075 + endloop + endfacet + facet normal 0.967581 0.0995702 0.232104 + outer loop + vertex 0.871005 0.973727 2.45075 + vertex 0.870503 0.978713 2.4507 + vertex 0.869902 0.974236 2.45512 + endloop + endfacet + facet normal 0.971795 0.0864565 0.219408 + outer loop + vertex 0.870503 0.978713 2.4507 + vertex 0.869514 0.979018 2.45496 + vertex 0.869902 0.974236 2.45512 + endloop + endfacet + facet normal 0.927541 0.0878875 0.363241 + outer loop + vertex 0.869514 0.979018 2.45496 + vertex 0.86834 0.975215 2.45888 + vertex 0.869902 0.974236 2.45512 + endloop + endfacet + facet normal 0.93619 0.0665627 0.345134 + outer loop + vertex 0.868198 0.980006 2.45834 + vertex 0.86834 0.975215 2.45888 + vertex 0.869514 0.979018 2.45496 + endloop + endfacet + facet normal 0.817611 0.166308 0.55123 + outer loop + vertex 0.873242 0.98 2.435 + vertex 0.872225 0.985 2.435 + vertex 0.872073 0.978824 2.43709 + endloop + endfacet + facet normal 0.921914 0.103569 0.373294 + outer loop + vertex 0.872225 0.985 2.435 + vertex 0.871251 0.982685 2.43805 + vertex 0.872073 0.978824 2.43709 + endloop + endfacet + facet normal 0.976606 0.1779 0.120799 + outer loop + vertex 0.872073 0.978824 2.43709 + vertex 0.871251 0.982685 2.43805 + vertex 0.871612 0.978544 2.44123 + endloop + endfacet + facet normal 0.985304 0.149424 0.082758 + outer loop + vertex 0.871251 0.982685 2.43805 + vertex 0.870853 0.983257 2.44175 + vertex 0.871612 0.978544 2.44123 + endloop + endfacet + facet normal 0.984942 0.148774 0.0880684 + outer loop + vertex 0.871612 0.978544 2.44123 + vertex 0.870853 0.983257 2.44175 + vertex 0.871175 0.97864 2.44596 + endloop + endfacet + facet normal 0.988071 0.135476 0.0732224 + outer loop + vertex 0.870853 0.983257 2.44175 + vertex 0.870507 0.983318 2.44631 + vertex 0.871175 0.97864 2.44596 + endloop + endfacet + facet normal 0.982007 0.129849 0.13712 + outer loop + vertex 0.871175 0.97864 2.44596 + vertex 0.870507 0.983318 2.44631 + vertex 0.870503 0.978713 2.4507 + endloop + endfacet + facet normal 0.981179 0.132788 0.140199 + outer loop + vertex 0.870507 0.983318 2.44631 + vertex 0.869868 0.983307 2.45079 + vertex 0.870503 0.978713 2.4507 + endloop + endfacet + facet normal 0.967898 0.12949 0.215418 + outer loop + vertex 0.870503 0.978713 2.4507 + vertex 0.869868 0.983307 2.45079 + vertex 0.869514 0.979018 2.45496 + endloop + endfacet + facet normal 0.971255 0.119776 0.205711 + outer loop + vertex 0.869868 0.983307 2.45079 + vertex 0.869044 0.983222 2.45473 + vertex 0.869514 0.979018 2.45496 + endloop + endfacet + facet normal 0.936394 0.122576 0.328848 + outer loop + vertex 0.869044 0.983222 2.45473 + vertex 0.868198 0.980006 2.45834 + vertex 0.869514 0.979018 2.45496 + endloop + endfacet + facet normal 0.947048 0.094954 0.30673 + outer loop + vertex 0.868153 0.983847 2.45729 + vertex 0.868198 0.980006 2.45834 + vertex 0.869044 0.983222 2.45473 + endloop + endfacet + facet normal 0.775062 0.557914 -0.296667 + outer loop + vertex 0.87 0.99 2.43859 + vertex 0.872225 0.985 2.435 + vertex 0.87 0.988091 2.435 + endloop + endfacet + facet normal 0.920991 0.152401 0.358537 + outer loop + vertex 0.87 0.99 2.43859 + vertex 0.870212 0.988025 2.43888 + vertex 0.872225 0.985 2.435 + endloop + endfacet + facet normal 0.916283 0.118276 0.382671 + outer loop + vertex 0.870212 0.988025 2.43888 + vertex 0.871251 0.982685 2.43805 + vertex 0.872225 0.985 2.435 + endloop + endfacet + facet normal 0.980832 0.17867 0.0777571 + outer loop + vertex 0.871251 0.982685 2.43805 + vertex 0.870212 0.988025 2.43888 + vertex 0.870853 0.983257 2.44175 + endloop + endfacet + facet normal 0.985893 0.16071 0.0467791 + outer loop + vertex 0.870212 0.988025 2.43888 + vertex 0.870195 0.98697 2.44287 + vertex 0.870853 0.983257 2.44175 + endloop + endfacet + facet normal 0.98557 0.152815 0.0728027 + outer loop + vertex 0.870853 0.983257 2.44175 + vertex 0.870195 0.98697 2.44287 + vertex 0.870507 0.983318 2.44631 + endloop + endfacet + facet normal 0.983553 0.16106 0.0817527 + outer loop + vertex 0.870195 0.98697 2.44287 + vertex 0.869784 0.987559 2.44665 + vertex 0.870507 0.983318 2.44631 + endloop + endfacet + facet normal 0.977914 0.155381 0.139789 + outer loop + vertex 0.870507 0.983318 2.44631 + vertex 0.869784 0.987559 2.44665 + vertex 0.869868 0.983307 2.45079 + endloop + endfacet + facet normal 0.976875 0.158728 0.143249 + outer loop + vertex 0.869784 0.987559 2.44665 + vertex 0.869139 0.987532 2.45108 + vertex 0.869868 0.983307 2.45079 + endloop + endfacet + facet normal 0.964394 0.162706 0.208495 + outer loop + vertex 0.868571 0.986221 2.45473 + vertex 0.869139 0.987532 2.45108 + vertex 0.868453 0.989192 2.45296 + endloop + endfacet + facet normal 0.966773 0.152466 0.20519 + outer loop + vertex 0.868571 0.986221 2.45473 + vertex 0.869044 0.983222 2.45473 + vertex 0.869139 0.987532 2.45108 + endloop + endfacet + facet normal 0.96668 0.152697 0.205459 + outer loop + vertex 0.869044 0.983222 2.45473 + vertex 0.869868 0.983307 2.45079 + vertex 0.869139 0.987532 2.45108 + endloop + endfacet + facet normal 0.944543 0.148909 0.292687 + outer loop + vertex 0.869044 0.983222 2.45473 + vertex 0.868571 0.986221 2.45473 + vertex 0.868153 0.983847 2.45729 + endloop + endfacet + facet normal 0.980513 0.0784145 -0.180129 + outer loop + vertex 0.87 0.99 2.43859 + vertex 0.87 0.993239 2.44 + vertex 0.870212 0.988025 2.43888 + endloop + endfacet + facet normal -0.425939 -0.205792 0.881037 + outer loop + vertex 0.869401 0.992388 2.43951 + vertex 0.870212 0.988025 2.43888 + vertex 0.87 0.993239 2.44 + endloop + endfacet + facet normal 0.982995 0.174327 0.0577066 + outer loop + vertex 0.869401 0.992388 2.43951 + vertex 0.869458 0.991095 2.44245 + vertex 0.870212 0.988025 2.43888 + endloop + endfacet + facet normal 0.982162 0.180686 0.052052 + outer loop + vertex 0.869458 0.991095 2.44245 + vertex 0.870195 0.98697 2.44287 + vertex 0.870212 0.988025 2.43888 + endloop + endfacet + facet normal 0.980025 0.18296 0.0779557 + outer loop + vertex 0.870195 0.98697 2.44287 + vertex 0.869458 0.991095 2.44245 + vertex 0.869784 0.987559 2.44665 + endloop + endfacet + facet normal 0.982993 0.170795 0.0674876 + outer loop + vertex 0.869458 0.991095 2.44245 + vertex 0.869106 0.991348 2.44695 + vertex 0.869784 0.987559 2.44665 + endloop + endfacet + facet normal 0.975865 0.172262 0.134213 + outer loop + vertex 0.868693 0.991208 2.45013 + vertex 0.869106 0.991348 2.44695 + vertex 0.868533 0.994016 2.44768 + endloop + endfacet + facet normal 0.979045 0.153518 0.133803 + outer loop + vertex 0.868693 0.991208 2.45013 + vertex 0.869139 0.987532 2.45108 + vertex 0.869106 0.991348 2.44695 + endloop + endfacet + facet normal 0.97608 0.163624 0.143163 + outer loop + vertex 0.869139 0.987532 2.45108 + vertex 0.869784 0.987559 2.44665 + vertex 0.869106 0.991348 2.44695 + endloop + endfacet + facet normal 0.964495 0.169494 0.202538 + outer loop + vertex 0.869139 0.987532 2.45108 + vertex 0.868693 0.991208 2.45013 + vertex 0.868453 0.989192 2.45296 + endloop + endfacet + facet normal 0.982967 0.174465 0.0577679 + outer loop + vertex 0.869401 0.992388 2.43951 + vertex 0.868943 0.994576 2.44071 + vertex 0.869458 0.991095 2.44245 + endloop + endfacet + facet normal 0.983578 0.167295 0.06773 + outer loop + vertex 0.869458 0.991095 2.44245 + vertex 0.868709 0.994918 2.44389 + vertex 0.869106 0.991348 2.44695 + endloop + endfacet + facet normal 0.983531 0.172556 0.0537694 + outer loop + vertex 0.868943 0.994576 2.44071 + vertex 0.868709 0.994918 2.44389 + vertex 0.869458 0.991095 2.44245 + endloop + endfacet + facet normal 0.978627 0.185233 0.089325 + outer loop + vertex 0.869106 0.991348 2.44695 + vertex 0.868709 0.994918 2.44389 + vertex 0.868533 0.994016 2.44768 + endloop + endfacet + facet normal 0.607122 -0.511797 -0.607838 + outer loop + vertex 0.870961 1.12 2.54 + vertex 0.87 1.11886 2.54 + vertex 0.87 1.12 2.53904 + endloop + endfacet + facet normal 0.716127 -0.603687 -0.350321 + outer loop + vertex 0.873407 1.12 2.545 + vertex 0.87 1.11886 2.54 + vertex 0.870961 1.12 2.54 + endloop + endfacet + facet normal 0.661878 -0.689656 -0.293755 + outer loop + vertex 0.869147 1.11663 2.54332 + vertex 0.87 1.11886 2.54 + vertex 0.873407 1.12 2.545 + endloop + endfacet + facet normal 0.662148 -0.685336 -0.303107 + outer loop + vertex 0.875 1.12 2.54848 + vertex 0.869147 1.11663 2.54332 + vertex 0.873407 1.12 2.545 + endloop + endfacet + facet normal 0.721976 -0.45417 -0.521996 + outer loop + vertex 0.875 1.12 2.54848 + vertex 0.873761 1.11771 2.54876 + vertex 0.869147 1.11663 2.54332 + endloop + endfacet + facet normal 0.242085 -0.970177 -0.0123269 + outer loop + vertex 0.873761 1.11771 2.54876 + vertex 0.867213 1.1161 2.54684 + vertex 0.869147 1.11663 2.54332 + endloop + endfacet + facet normal -0.127121 -0.983606 0.127905 + outer loop + vertex 0.871302 1.11834 2.55112 + vertex 0.873761 1.11771 2.54876 + vertex 0.874561 1.11801 2.55187 + endloop + endfacet + facet normal 0.0344601 -0.956765 0.288814 + outer loop + vertex 0.871302 1.11834 2.55112 + vertex 0.868194 1.11789 2.55003 + vertex 0.873761 1.11771 2.54876 + endloop + endfacet + facet normal 0.0783958 -0.879412 0.469562 + outer loop + vertex 0.868194 1.11789 2.55003 + vertex 0.867213 1.1161 2.54684 + vertex 0.873761 1.11771 2.54876 + endloop + endfacet + facet normal -0.0663619 -0.844888 0.530811 + outer loop + vertex 0.871302 1.11834 2.55112 + vertex 0.868239 1.11954 2.55265 + vertex 0.868194 1.11789 2.55003 + endloop + endfacet + facet normal 0.577188 -0.772687 -0.264215 + outer loop + vertex 0.875 1.12119 2.545 + vertex 0.875 1.12 2.54848 + vertex 0.873407 1.12 2.545 + endloop + endfacet + facet normal -0.176483 -0.909601 0.376138 + outer loop + vertex 0.874561 1.11801 2.55187 + vertex 0.872054 1.11913 2.55339 + vertex 0.871302 1.11834 2.55112 + endloop + endfacet + facet normal -0.170459 -0.911324 0.374742 + outer loop + vertex 0.868239 1.11954 2.55265 + vertex 0.871302 1.11834 2.55112 + vertex 0.872054 1.11913 2.55339 + endloop + endfacet + facet normal -0.192857 -0.817621 0.542496 + outer loop + vertex 0.868239 1.11954 2.55265 + vertex 0.872054 1.11913 2.55339 + vertex 0.868882 1.12104 2.55514 + endloop + endfacet + facet normal -0.304988 -0.867334 0.393336 + outer loop + vertex 0.868882 1.12104 2.55514 + vertex 0.872054 1.11913 2.55339 + vertex 0.873647 1.11989 2.5563 + endloop + endfacet + facet normal -0.321533 -0.750715 0.577099 + outer loop + vertex 0.873647 1.11989 2.5563 + vertex 0.868834 1.12334 2.55811 + vertex 0.868882 1.12104 2.55514 + endloop + endfacet + facet normal -0.370909 -0.780626 0.503041 + outer loop + vertex 0.874477 1.1215 2.55941 + vertex 0.868834 1.12334 2.55811 + vertex 0.873647 1.11989 2.5563 + endloop + endfacet + facet normal -0.36824 -0.682704 0.631121 + outer loop + vertex 0.868834 1.12334 2.55811 + vertex 0.874477 1.1215 2.55941 + vertex 0.87251 1.12443 2.56144 + endloop + endfacet + facet normal -0.363663 -0.688152 0.62785 + outer loop + vertex 0.868072 1.12608 2.56067 + vertex 0.868834 1.12334 2.55811 + vertex 0.87251 1.12443 2.56144 + endloop + endfacet + facet normal -0.356748 -0.648527 0.672417 + outer loop + vertex 0.87251 1.12443 2.56144 + vertex 0.868578 1.1284 2.56318 + vertex 0.868072 1.12608 2.56067 + endloop + endfacet + facet normal -0.393137 -0.667209 0.632673 + outer loop + vertex 0.874093 1.12631 2.56441 + vertex 0.868578 1.1284 2.56318 + vertex 0.87251 1.12443 2.56144 + endloop + endfacet + facet normal -0.391125 -0.651862 0.64969 + outer loop + vertex 0.868578 1.1284 2.56318 + vertex 0.874093 1.12631 2.56441 + vertex 0.872435 1.12944 2.56655 + endloop + endfacet + facet normal -0.411771 -0.623527 0.664574 + outer loop + vertex 0.868056 1.13136 2.56564 + vertex 0.868578 1.1284 2.56318 + vertex 0.872435 1.12944 2.56655 + endloop + endfacet + facet normal -0.40745 -0.604061 0.684905 + outer loop + vertex 0.872435 1.12944 2.56655 + vertex 0.868477 1.13382 2.56806 + vertex 0.868056 1.13136 2.56564 + endloop + endfacet + facet normal -0.467574 -0.634425 0.615532 + outer loop + vertex 0.873756 1.13171 2.56988 + vertex 0.868477 1.13382 2.56806 + vertex 0.872435 1.12944 2.56655 + endloop + endfacet + facet normal -0.464819 -0.585841 0.663878 + outer loop + vertex 0.868477 1.13382 2.56806 + vertex 0.873756 1.13171 2.56988 + vertex 0.871134 1.13537 2.57128 + endloop + endfacet + facet normal -0.484921 -0.562799 0.669409 + outer loop + vertex 0.867643 1.137 2.57012 + vertex 0.868477 1.13382 2.56806 + vertex 0.871134 1.13537 2.57128 + endloop + endfacet + facet normal -0.476673 -0.514381 0.712878 + outer loop + vertex 0.871134 1.13537 2.57128 + vertex 0.868584 1.13884 2.57208 + vertex 0.867643 1.137 2.57012 + endloop + endfacet + facet normal -0.512191 -0.53167 0.674527 + outer loop + vertex 0.872086 1.13774 2.57387 + vertex 0.868584 1.13884 2.57208 + vertex 0.871134 1.13537 2.57128 + endloop + endfacet + facet normal -0.548667 -0.41195 0.727504 + outer loop + vertex 0.873066 1.14005 2.57628 + vertex 0.87076 1.14355 2.57652 + vertex 0.86886 1.14214 2.57429 + endloop + endfacet + facet normal -0.557532 -0.472805 0.682359 + outer loop + vertex 0.873066 1.14005 2.57628 + vertex 0.86886 1.14214 2.57429 + vertex 0.872086 1.13774 2.57387 + endloop + endfacet + facet normal -0.514752 -0.446174 0.732092 + outer loop + vertex 0.872086 1.13774 2.57387 + vertex 0.86886 1.14214 2.57429 + vertex 0.868584 1.13884 2.57208 + endloop + endfacet + facet normal -0.551523 -0.413619 0.724391 + outer loop + vertex 0.873066 1.14005 2.57628 + vertex 0.874104 1.14292 2.5787 + vertex 0.87076 1.14355 2.57652 + endloop + endfacet + facet normal -0.563268 -0.254467 0.786114 + outer loop + vertex 0.87502 1.15265 2.58341 + vertex 0.872982 1.15772 2.58359 + vertex 0.871262 1.15469 2.58138 + endloop + endfacet + facet normal -0.581359 -0.0513693 0.812024 + outer loop + vertex 0.868242 1.19709 2.58855 + vertex 0.868713 1.19192 2.58856 + vertex 0.871432 1.19455 2.59067 + endloop + endfacet + facet normal -0.574595 -0.0382538 0.817543 + outer loop + vertex 0.87111 1.19968 2.59068 + vertex 0.868242 1.19709 2.58855 + vertex 0.871432 1.19455 2.59067 + endloop + endfacet + facet normal -0.567673 -0.0378319 0.822384 + outer loop + vertex 0.871432 1.19455 2.59067 + vertex 0.874928 1.19712 2.5932 + vertex 0.87111 1.19968 2.59068 + endloop + endfacet + facet normal -0.560285 -0.0521039 0.826659 + outer loop + vertex 0.874063 1.19209 2.5923 + vertex 0.874928 1.19712 2.5932 + vertex 0.871432 1.19455 2.59067 + endloop + endfacet + facet normal -0.568691 -0.0477765 0.821163 + outer loop + vertex 0.867634 1.20265 2.58845 + vertex 0.868242 1.19709 2.58855 + vertex 0.87111 1.19968 2.59068 + endloop + endfacet + facet normal -0.573252 -0.0558923 0.817471 + outer loop + vertex 0.870804 1.20469 2.59081 + vertex 0.867634 1.20265 2.58845 + vertex 0.87111 1.19968 2.59068 + endloop + endfacet + facet normal -0.552752 -0.0550014 0.831528 + outer loop + vertex 0.87111 1.19968 2.59068 + vertex 0.873514 1.20225 2.59245 + vertex 0.870804 1.20469 2.59081 + endloop + endfacet + facet normal -0.566855 -0.0359745 0.823032 + outer loop + vertex 0.874928 1.19712 2.5932 + vertex 0.873514 1.20225 2.59245 + vertex 0.87111 1.19968 2.59068 + endloop + endfacet + facet normal -0.491477 -0.103879 0.864673 + outer loop + vertex 0.872914 1.27601 2.60511 + vertex 0.875896 1.27774 2.60701 + vertex 0.87224 1.28021 2.60523 + endloop + endfacet + facet normal -0.496516 -0.114351 0.860462 + outer loop + vertex 0.875896 1.27774 2.60701 + vertex 0.875071 1.28309 2.60725 + vertex 0.87224 1.28021 2.60523 + endloop + endfacet + facet normal -0.475927 -0.0343245 0.878815 + outer loop + vertex 0.869629 1.41349 2.61618 + vertex 0.870824 1.41745 2.61698 + vertex 0.867767 1.41583 2.61526 + endloop + endfacet + facet normal -0.544421 0.0523602 0.837176 + outer loop + vertex 0.870207 1.76354 2.60131 + vertex 0.873507 1.7662 2.60329 + vertex 0.870651 1.76851 2.60129 + endloop + endfacet + facet normal -0.552491 0.0671337 0.830811 + outer loop + vertex 0.872645 1.76058 2.60317 + vertex 0.873507 1.7662 2.60329 + vertex 0.870207 1.76354 2.60131 + endloop + endfacet + facet normal -0.549405 0.0478922 0.834182 + outer loop + vertex 0.867646 1.77033 2.5992 + vertex 0.867474 1.76537 2.59937 + vertex 0.870651 1.76851 2.60129 + endloop + endfacet + facet normal -0.544554 0.058723 0.836667 + outer loop + vertex 0.870901 1.77372 2.60108 + vertex 0.867646 1.77033 2.5992 + vertex 0.870651 1.76851 2.60129 + endloop + endfacet + facet normal -0.541853 0.0586615 0.838424 + outer loop + vertex 0.870651 1.76851 2.60129 + vertex 0.874322 1.77188 2.60342 + vertex 0.870901 1.77372 2.60108 + endloop + endfacet + facet normal -0.54126 0.0577311 0.838871 + outer loop + vertex 0.873507 1.7662 2.60329 + vertex 0.874322 1.77188 2.60342 + vertex 0.870651 1.76851 2.60129 + endloop + endfacet + facet normal -0.52501 0.152686 0.837288 + outer loop + vertex 0.871885 1.78273 2.6006 + vertex 0.874078 1.78512 2.60154 + vertex 0.871725 1.78608 2.59989 + endloop + endfacet + facet normal -0.571196 0.374532 0.730384 + outer loop + vertex 0.868628 1.87074 2.57755 + vertex 0.86866 1.86818 2.5789 + vertex 0.870867 1.86903 2.58019 + endloop + endfacet + facet normal -0.568361 0.378491 0.730555 + outer loop + vertex 0.871291 1.87295 2.57848 + vertex 0.868628 1.87074 2.57755 + vertex 0.870867 1.86903 2.58019 + endloop + endfacet + facet normal -0.589295 0.374404 0.715928 + outer loop + vertex 0.870867 1.86903 2.58019 + vertex 0.873993 1.87128 2.58158 + vertex 0.871291 1.87295 2.57848 + endloop + endfacet + facet normal -0.569992 0.323401 0.755328 + outer loop + vertex 0.87324 1.8661 2.58323 + vertex 0.873993 1.87128 2.58158 + vertex 0.870867 1.86903 2.58019 + endloop + endfacet + facet normal -0.565984 0.418741 0.710154 + outer loop + vertex 0.871242 1.87736 2.57587 + vertex 0.868881 1.87703 2.57418 + vertex 0.868804 1.8746 2.57555 + endloop + endfacet + facet normal -0.577499 0.396665 0.713549 + outer loop + vertex 0.868804 1.8746 2.57555 + vertex 0.868628 1.87074 2.57755 + vertex 0.871291 1.87295 2.57848 + endloop + endfacet + facet normal -0.563855 0.416505 0.713156 + outer loop + vertex 0.871242 1.87736 2.57587 + vertex 0.868804 1.8746 2.57555 + vertex 0.871291 1.87295 2.57848 + endloop + endfacet + facet normal -0.595131 0.404903 0.69417 + outer loop + vertex 0.871242 1.87736 2.57587 + vertex 0.871291 1.87295 2.57848 + vertex 0.873887 1.87528 2.57935 + endloop + endfacet + facet normal -0.589723 0.412266 0.694452 + outer loop + vertex 0.871242 1.87736 2.57587 + vertex 0.873887 1.87528 2.57935 + vertex 0.873603 1.87765 2.5777 + endloop + endfacet + facet normal -0.583381 0.383773 0.715811 + outer loop + vertex 0.873887 1.87528 2.57935 + vertex 0.871291 1.87295 2.57848 + vertex 0.873993 1.87128 2.58158 + endloop + endfacet + facet normal -0.53755 0.444878 0.716327 + outer loop + vertex 0.870732 1.882 2.5725 + vertex 0.866393 1.88024 2.57034 + vertex 0.868806 1.87886 2.57301 + endloop + endfacet + facet normal -0.564002 0.4294 0.705349 + outer loop + vertex 0.868806 1.87886 2.57301 + vertex 0.868881 1.87703 2.57418 + vertex 0.871242 1.87736 2.57587 + endloop + endfacet + facet normal -0.549435 0.450186 0.703885 + outer loop + vertex 0.870732 1.882 2.5725 + vertex 0.868806 1.87886 2.57301 + vertex 0.871242 1.87736 2.57587 + endloop + endfacet + facet normal -0.58732 0.431928 0.684466 + outer loop + vertex 0.870732 1.882 2.5725 + vertex 0.871242 1.87736 2.57587 + vertex 0.873516 1.88002 2.57614 + endloop + endfacet + facet normal -0.57337 0.450873 0.684077 + outer loop + vertex 0.870732 1.882 2.5725 + vertex 0.873516 1.88002 2.57614 + vertex 0.873552 1.88239 2.57461 + endloop + endfacet + facet normal -0.585881 0.430484 0.686605 + outer loop + vertex 0.873516 1.88002 2.57614 + vertex 0.871242 1.87736 2.57587 + vertex 0.873603 1.87765 2.5777 + endloop + endfacet + facet normal -0.539231 0.473174 0.696661 + outer loop + vertex 0.867144 1.88491 2.56775 + vertex 0.866393 1.88024 2.57034 + vertex 0.870732 1.882 2.5725 + endloop + endfacet + facet normal -0.508311 0.508546 0.694983 + outer loop + vertex 0.871052 1.88604 2.56978 + vertex 0.867144 1.88491 2.56775 + vertex 0.870732 1.882 2.5725 + endloop + endfacet + facet normal -0.567587 0.490502 0.661251 + outer loop + vertex 0.870732 1.882 2.5725 + vertex 0.873635 1.8848 2.57292 + vertex 0.871052 1.88604 2.56978 + endloop + endfacet + facet normal -0.564932 0.487041 0.666065 + outer loop + vertex 0.873552 1.88239 2.57461 + vertex 0.873635 1.8848 2.57292 + vertex 0.870732 1.882 2.5725 + endloop + endfacet + facet normal -0.505889 0.685521 0.52358 + outer loop + vertex 0.869798 1.88931 2.56586 + vertex 0.873301 1.89117 2.56681 + vertex 0.871413 1.89224 2.56359 + endloop + endfacet + facet normal -0.413019 0.689655 0.594804 + outer loop + vertex 0.869246 1.89149 2.56295 + vertex 0.869798 1.88931 2.56586 + vertex 0.871413 1.89224 2.56359 + endloop + endfacet + facet normal -0.501821 0.577973 0.643524 + outer loop + vertex 0.871052 1.88604 2.56978 + vertex 0.869798 1.88931 2.56586 + vertex 0.867144 1.88491 2.56775 + endloop + endfacet + facet normal -0.545998 0.548625 0.633164 + outer loop + vertex 0.871052 1.88604 2.56978 + vertex 0.873579 1.88843 2.56989 + vertex 0.869798 1.88931 2.56586 + endloop + endfacet + facet normal -0.495455 0.625656 0.602561 + outer loop + vertex 0.873579 1.88843 2.56989 + vertex 0.873301 1.89117 2.56681 + vertex 0.869798 1.88931 2.56586 + endloop + endfacet + facet normal -0.535172 0.536233 0.652721 + outer loop + vertex 0.873579 1.88843 2.56989 + vertex 0.871052 1.88604 2.56978 + vertex 0.873635 1.8848 2.57292 + endloop + endfacet + facet normal -0.141104 0.818983 0.556198 + outer loop + vertex 0.870291 1.89868 2.5512 + vertex 0.867862 1.89846 2.55091 + vertex 0.86902 1.89648 2.55411 + endloop + endfacet + facet normal -0.222912 0.822592 0.523118 + outer loop + vertex 0.871704 1.8977 2.55334 + vertex 0.870291 1.89868 2.5512 + vertex 0.86902 1.89648 2.55411 + endloop + endfacet + facet normal -0.296543 0.883587 0.362405 + outer loop + vertex 0.871704 1.8977 2.55334 + vertex 0.86902 1.89648 2.55411 + vertex 0.872037 1.8964 2.55678 + endloop + endfacet + facet normal -0.354818 0.831969 0.426534 + outer loop + vertex 0.872037 1.8964 2.55678 + vertex 0.86902 1.89648 2.55411 + vertex 0.869626 1.89484 2.55782 + endloop + endfacet + facet normal -0.363638 0.835663 0.411625 + outer loop + vertex 0.872037 1.8964 2.55678 + vertex 0.869626 1.89484 2.55782 + vertex 0.872049 1.89453 2.56059 + endloop + endfacet + facet normal -0.396342 0.807369 0.437113 + outer loop + vertex 0.872049 1.89453 2.56059 + vertex 0.869626 1.89484 2.55782 + vertex 0.869105 1.89307 2.56061 + endloop + endfacet + facet normal -0.411622 0.743736 0.52671 + outer loop + vertex 0.871413 1.89224 2.56359 + vertex 0.869105 1.89307 2.56061 + vertex 0.869246 1.89149 2.56295 + endloop + endfacet + facet normal -0.37869 0.772777 0.509323 + outer loop + vertex 0.872049 1.89453 2.56059 + vertex 0.869105 1.89307 2.56061 + vertex 0.871413 1.89224 2.56359 + endloop + endfacet + facet normal -0.138218 0.24561 0.959464 + outer loop + vertex 0.870291 1.89868 2.5512 + vertex 0.87 1.90321 2.55 + vertex 0.867862 1.89846 2.55091 + endloop + endfacet + facet normal -0.0871955 0.250163 0.964269 + outer loop + vertex 0.870291 1.89868 2.5512 + vertex 0.872734 1.90027 2.55101 + vertex 0.87 1.90321 2.55 + endloop + endfacet + facet normal -0.0682836 0.266743 0.961346 + outer loop + vertex 0.872734 1.90027 2.55101 + vertex 0.875 1.90449 2.55 + vertex 0.87 1.90321 2.55 + endloop + endfacet + facet normal -0.408702 0.697428 0.588691 + outer loop + vertex 0.872734 1.90027 2.55101 + vertex 0.870291 1.89868 2.5512 + vertex 0.871704 1.8977 2.55334 + endloop + endfacet + facet normal 0.577467 -0.531246 -0.619928 + outer loop + vertex 0.870322 2.045 2.435 + vertex 0.87 2.04465 2.435 + vertex 0.87 2.045 2.4347 + endloop + endfacet + facet normal 0.734736 -0.675927 -0.0573232 + outer loop + vertex 0.870083 2.04468 2.43568 + vertex 0.87 2.04465 2.435 + vertex 0.870322 2.045 2.435 + endloop + endfacet + facet normal 0.95211 -0.288229 -0.102032 + outer loop + vertex 0.87 2.04288 2.44 + vertex 0.87 2.04465 2.435 + vertex 0.870083 2.04468 2.43568 + endloop + endfacet + facet normal 0.921254 0.352364 0.164712 + outer loop + vertex 0.869744 2.04375 2.43958 + vertex 0.87 2.04288 2.44 + vertex 0.870083 2.04468 2.43568 + endloop + endfacet + facet normal 0.63834 0.48043 0.601423 + outer loop + vertex 0.868735 2.04032 2.44339 + vertex 0.87 2.04288 2.44 + vertex 0.869744 2.04375 2.43958 + endloop + endfacet + facet normal 0.969711 -0.240937 0.0401179 + outer loop + vertex 0.869557 2.04389 2.44498 + vertex 0.868735 2.04032 2.44339 + vertex 0.869744 2.04375 2.43958 + endloop + endfacet + facet normal 0.964835 -0.253286 0.0702805 + outer loop + vertex 0.868486 2.04056 2.44767 + vertex 0.868735 2.04032 2.44339 + vertex 0.869557 2.04389 2.44498 + endloop + endfacet + facet normal 0.968413 -0.225839 0.105705 + outer loop + vertex 0.869557 2.04389 2.44498 + vertex 0.868848 2.04294 2.44944 + vertex 0.868486 2.04056 2.44767 + endloop + endfacet + facet normal 0.921699 -0.354125 0.158323 + outer loop + vertex 0.870322 2.045 2.435 + vertex 0.872243 2.05 2.435 + vertex 0.870083 2.04468 2.43568 + endloop + endfacet + facet normal 0.85592 -0.293088 0.426029 + outer loop + vertex 0.872243 2.05 2.435 + vertex 0.870818 2.04793 2.43644 + vertex 0.870083 2.04468 2.43568 + endloop + endfacet + facet normal 0.97338 -0.2272 0.0301877 + outer loop + vertex 0.870083 2.04468 2.43568 + vertex 0.870818 2.04793 2.43644 + vertex 0.869744 2.04375 2.43958 + endloop + endfacet + facet normal 0.974694 -0.21986 0.0404221 + outer loop + vertex 0.870818 2.04793 2.43644 + vertex 0.870516 2.04737 2.44066 + vertex 0.869744 2.04375 2.43958 + endloop + endfacet + facet normal 0.974767 -0.219664 0.0397144 + outer loop + vertex 0.869744 2.04375 2.43958 + vertex 0.870516 2.04737 2.44066 + vertex 0.869557 2.04389 2.44498 + endloop + endfacet + facet normal 0.977746 -0.202716 0.054023 + outer loop + vertex 0.870516 2.04737 2.44066 + vertex 0.870423 2.04798 2.44464 + vertex 0.869557 2.04389 2.44498 + endloop + endfacet + facet normal 0.963021 -0.161597 0.215587 + outer loop + vertex 0.868848 2.04294 2.44944 + vertex 0.869649 2.04706 2.44895 + vertex 0.86845 2.04436 2.45229 + endloop + endfacet + facet normal 0.97731 -0.176096 0.117706 + outer loop + vertex 0.868848 2.04294 2.44944 + vertex 0.869557 2.04389 2.44498 + vertex 0.869649 2.04706 2.44895 + endloop + endfacet + facet normal 0.971807 -0.194838 0.132778 + outer loop + vertex 0.869557 2.04389 2.44498 + vertex 0.870423 2.04798 2.44464 + vertex 0.869649 2.04706 2.44895 + endloop + endfacet + facet normal 0.960567 -0.112901 0.254095 + outer loop + vertex 0.869649 2.04706 2.44895 + vertex 0.868643 2.04838 2.45334 + vertex 0.86845 2.04436 2.45229 + endloop + endfacet + facet normal 0.751274 -0.0599493 0.657263 + outer loop + vertex 0.872243 2.05 2.435 + vertex 0.872642 2.055 2.435 + vertex 0.870818 2.04793 2.43644 + endloop + endfacet + facet normal 0.945722 -0.190409 0.263353 + outer loop + vertex 0.872642 2.055 2.435 + vertex 0.871503 2.05246 2.43726 + vertex 0.870818 2.04793 2.43644 + endloop + endfacet + facet normal 0.986196 -0.158018 0.0494734 + outer loop + vertex 0.870818 2.04793 2.43644 + vertex 0.871503 2.05246 2.43726 + vertex 0.870516 2.04737 2.44066 + endloop + endfacet + facet normal 0.986345 -0.156178 0.0522669 + outer loop + vertex 0.871503 2.05246 2.43726 + vertex 0.871185 2.05185 2.44142 + vertex 0.870516 2.04737 2.44066 + endloop + endfacet + facet normal 0.986747 -0.155331 0.0469301 + outer loop + vertex 0.870516 2.04737 2.44066 + vertex 0.871185 2.05185 2.44142 + vertex 0.870423 2.04798 2.44464 + endloop + endfacet + facet normal 0.988709 -0.118225 0.0920743 + outer loop + vertex 0.871185 2.05185 2.44142 + vertex 0.870765 2.05177 2.44583 + vertex 0.870423 2.04798 2.44464 + endloop + endfacet + facet normal 0.979905 -0.13475 0.147065 + outer loop + vertex 0.870423 2.04798 2.44464 + vertex 0.870765 2.05177 2.44583 + vertex 0.869649 2.04706 2.44895 + endloop + endfacet + facet normal 0.976564 -0.108111 0.186106 + outer loop + vertex 0.870765 2.05177 2.44583 + vertex 0.870003 2.05221 2.45009 + vertex 0.869649 2.04706 2.44895 + endloop + endfacet + facet normal 0.95875 -0.122404 0.256546 + outer loop + vertex 0.870003 2.05221 2.45009 + vertex 0.868643 2.04838 2.45334 + vertex 0.869649 2.04706 2.44895 + endloop + endfacet + facet normal 0.950014 -0.081049 0.301504 + outer loop + vertex 0.868871 2.05341 2.45397 + vertex 0.868643 2.04838 2.45334 + vertex 0.870003 2.05221 2.45009 + endloop + endfacet + facet normal 0.903997 -0.026403 0.426724 + outer loop + vertex 0.872642 2.055 2.435 + vertex 0.872788 2.06 2.435 + vertex 0.871503 2.05246 2.43726 + endloop + endfacet + facet normal 0.984757 -0.135136 0.109509 + outer loop + vertex 0.872788 2.06 2.435 + vertex 0.872134 2.05741 2.43768 + vertex 0.871503 2.05246 2.43726 + endloop + endfacet + facet normal 0.989766 -0.131162 0.056211 + outer loop + vertex 0.871503 2.05246 2.43726 + vertex 0.872134 2.05741 2.43768 + vertex 0.871185 2.05185 2.44142 + endloop + endfacet + facet normal 0.990115 -0.116492 0.0781107 + outer loop + vertex 0.872134 2.05741 2.43768 + vertex 0.871711 2.05663 2.44189 + vertex 0.871185 2.05185 2.44142 + endloop + endfacet + facet normal 0.988771 -0.117693 0.0920893 + outer loop + vertex 0.871185 2.05185 2.44142 + vertex 0.871711 2.05663 2.44189 + vertex 0.870765 2.05177 2.44583 + endloop + endfacet + facet normal 0.988269 -0.0957793 0.118959 + outer loop + vertex 0.871711 2.05663 2.44189 + vertex 0.871177 2.05664 2.44633 + vertex 0.870765 2.05177 2.44583 + endloop + endfacet + facet normal 0.977358 -0.101641 0.185582 + outer loop + vertex 0.870765 2.05177 2.44583 + vertex 0.871177 2.05664 2.44633 + vertex 0.870003 2.05221 2.45009 + endloop + endfacet + facet normal 0.974872 -0.0830286 0.206715 + outer loop + vertex 0.871177 2.05664 2.44633 + vertex 0.870339 2.05725 2.45052 + vertex 0.870003 2.05221 2.45009 + endloop + endfacet + facet normal 0.94853 -0.0896821 0.303725 + outer loop + vertex 0.870339 2.05725 2.45052 + vertex 0.868871 2.05341 2.45397 + vertex 0.870003 2.05221 2.45009 + endloop + endfacet + facet normal 0.941634 -0.0627665 0.330735 + outer loop + vertex 0.869102 2.05836 2.45426 + vertex 0.868871 2.05341 2.45397 + vertex 0.870339 2.05725 2.45052 + endloop + endfacet + facet normal 0.980855 -0.185173 0.0602811 + outer loop + vertex 0.872788 2.06 2.435 + vertex 0.873732 2.065 2.435 + vertex 0.872134 2.05741 2.43768 + endloop + endfacet + facet normal 0.971671 -0.136264 0.193099 + outer loop + vertex 0.873732 2.065 2.435 + vertex 0.872794 2.06222 2.43776 + vertex 0.872134 2.05741 2.43768 + endloop + endfacet + facet normal 0.987838 -0.136666 0.0741472 + outer loop + vertex 0.872134 2.05741 2.43768 + vertex 0.872794 2.06222 2.43776 + vertex 0.871711 2.05663 2.44189 + endloop + endfacet + facet normal 0.988064 -0.122171 0.0938233 + outer loop + vertex 0.872794 2.06222 2.43776 + vertex 0.872267 2.06126 2.44206 + vertex 0.871711 2.05663 2.44189 + endloop + endfacet + facet normal 0.985319 -0.122762 0.118641 + outer loop + vertex 0.871711 2.05663 2.44189 + vertex 0.872267 2.06126 2.44206 + vertex 0.871177 2.05664 2.44633 + endloop + endfacet + facet normal 0.985139 -0.112182 0.130062 + outer loop + vertex 0.872267 2.06126 2.44206 + vertex 0.87167 2.06141 2.44671 + vertex 0.871177 2.05664 2.44633 + endloop + endfacet + facet normal 0.970488 -0.11715 0.210783 + outer loop + vertex 0.871177 2.05664 2.44633 + vertex 0.87167 2.06141 2.44671 + vertex 0.870339 2.05725 2.45052 + endloop + endfacet + facet normal 0.966319 -0.0871132 0.242155 + outer loop + vertex 0.87167 2.06141 2.44671 + vertex 0.870651 2.06208 2.45101 + vertex 0.870339 2.05725 2.45052 + endloop + endfacet + facet normal 0.936135 -0.0949924 0.338566 + outer loop + vertex 0.870651 2.06208 2.45101 + vertex 0.869102 2.05836 2.45426 + vertex 0.870339 2.05725 2.45052 + endloop + endfacet + facet normal 0.922539 -0.0509102 0.382532 + outer loop + vertex 0.869202 2.06301 2.45463 + vertex 0.869102 2.05836 2.45426 + vertex 0.870651 2.06208 2.45101 + endloop + endfacet + facet normal 0.972488 -0.168056 0.161318 + outer loop + vertex 0.873732 2.065 2.435 + vertex 0.874596 2.07 2.435 + vertex 0.872794 2.06222 2.43776 + endloop + endfacet + facet normal 0.971227 -0.163597 0.173072 + outer loop + vertex 0.874596 2.07 2.435 + vertex 0.873427 2.06602 2.43779 + vertex 0.872794 2.06222 2.43776 + endloop + endfacet + facet normal 0.982786 -0.164684 0.0837364 + outer loop + vertex 0.872794 2.06222 2.43776 + vertex 0.873427 2.06602 2.43779 + vertex 0.872267 2.06126 2.44206 + endloop + endfacet + facet normal 0.982723 -0.165551 0.0827529 + outer loop + vertex 0.873427 2.06602 2.43779 + vertex 0.872927 2.06541 2.44252 + vertex 0.872267 2.06126 2.44206 + endloop + endfacet + facet normal 0.976718 -0.170009 0.130836 + outer loop + vertex 0.872267 2.06126 2.44206 + vertex 0.872927 2.06541 2.44252 + vertex 0.87167 2.06141 2.44671 + endloop + endfacet + facet normal 0.9772 -0.140268 0.159391 + outer loop + vertex 0.872927 2.06541 2.44252 + vertex 0.87223 2.06629 2.44757 + vertex 0.87167 2.06141 2.44671 + endloop + endfacet + facet normal 0.955953 -0.153859 0.249962 + outer loop + vertex 0.87167 2.06141 2.44671 + vertex 0.87223 2.06629 2.44757 + vertex 0.870651 2.06208 2.45101 + endloop + endfacet + facet normal 0.940277 -0.08236 0.330297 + outer loop + vertex 0.87223 2.06629 2.44757 + vertex 0.870638 2.06653 2.45216 + vertex 0.870651 2.06208 2.45101 + endloop + endfacet + facet normal 0.914843 -0.0982654 0.39167 + outer loop + vertex 0.870638 2.06653 2.45216 + vertex 0.869202 2.06301 2.45463 + vertex 0.870651 2.06208 2.45101 + endloop + endfacet + facet normal 0.884768 -0.0348533 0.464726 + outer loop + vertex 0.869034 2.0669 2.45525 + vertex 0.869202 2.06301 2.45463 + vertex 0.870638 2.06653 2.45216 + endloop + endfacet + facet normal 0.961487 -0.23223 0.147013 + outer loop + vertex 0.875 2.07076 2.435 + vertex 0.874096 2.06916 2.43838 + vertex 0.873427 2.06602 2.43779 + endloop + endfacet + facet normal 0.845846 -0.449588 -0.287082 + outer loop + vertex 0.874596 2.07 2.435 + vertex 0.875 2.07076 2.435 + vertex 0.873427 2.06602 2.43779 + endloop + endfacet + facet normal 0.973822 -0.211345 0.0836893 + outer loop + vertex 0.874096 2.06916 2.43838 + vertex 0.873691 2.06921 2.44323 + vertex 0.872927 2.06541 2.44252 + endloop + endfacet + facet normal 0.972419 -0.221005 0.0745531 + outer loop + vertex 0.873427 2.06602 2.43779 + vertex 0.874096 2.06916 2.43838 + vertex 0.872927 2.06541 2.44252 + endloop + endfacet + facet normal 0.960555 -0.210897 0.181264 + outer loop + vertex 0.873691 2.06921 2.44323 + vertex 0.873243 2.0702 2.44675 + vertex 0.87223 2.06629 2.44757 + endloop + endfacet + facet normal 0.959218 -0.224628 0.171591 + outer loop + vertex 0.872927 2.06541 2.44252 + vertex 0.873691 2.06921 2.44323 + vertex 0.87223 2.06629 2.44757 + endloop + endfacet + facet normal 0.927486 -0.146461 0.343975 + outer loop + vertex 0.873243 2.0702 2.44675 + vertex 0.873383 2.07368 2.44786 + vertex 0.871997 2.07025 2.45013 + endloop + endfacet + facet normal 0.924222 -0.167714 0.343053 + outer loop + vertex 0.873243 2.0702 2.44675 + vertex 0.871997 2.07025 2.45013 + vertex 0.87223 2.06629 2.44757 + endloop + endfacet + facet normal 0.930093 -0.159501 0.330888 + outer loop + vertex 0.87223 2.06629 2.44757 + vertex 0.871997 2.07025 2.45013 + vertex 0.870638 2.06653 2.45216 + endloop + endfacet + facet normal 0.842099 -0.0272047 0.538637 + outer loop + vertex 0.869034 2.0669 2.45525 + vertex 0.869865 2.07108 2.45416 + vertex 0.867394 2.06956 2.45794 + endloop + endfacet + facet normal 0.883041 -0.054272 0.466147 + outer loop + vertex 0.869034 2.0669 2.45525 + vertex 0.870638 2.06653 2.45216 + vertex 0.869865 2.07108 2.45416 + endloop + endfacet + facet normal 0.876832 -0.0600989 0.477027 + outer loop + vertex 0.870638 2.06653 2.45216 + vertex 0.871997 2.07025 2.45013 + vertex 0.869865 2.07108 2.45416 + endloop + endfacet + facet normal 0.840545 -0.017626 0.541455 + outer loop + vertex 0.869865 2.07108 2.45416 + vertex 0.867782 2.0738 2.45748 + vertex 0.867394 2.06956 2.45794 + endloop + endfacet + facet normal 0.905058 -0.0838584 0.416939 + outer loop + vertex 0.873383 2.07368 2.44786 + vertex 0.873482 2.07826 2.44857 + vertex 0.871835 2.07474 2.45143 + endloop + endfacet + facet normal 0.904234 -0.088116 0.417848 + outer loop + vertex 0.871997 2.07025 2.45013 + vertex 0.873383 2.07368 2.44786 + vertex 0.871835 2.07474 2.45143 + endloop + endfacet + facet normal 0.869032 -0.108167 0.482787 + outer loop + vertex 0.871997 2.07025 2.45013 + vertex 0.871835 2.07474 2.45143 + vertex 0.869865 2.07108 2.45416 + endloop + endfacet + facet normal 0.835702 -0.042128 0.547565 + outer loop + vertex 0.871835 2.07474 2.45143 + vertex 0.869744 2.07638 2.45475 + vertex 0.869865 2.07108 2.45416 + endloop + endfacet + facet normal 0.830156 -0.0431823 0.555856 + outer loop + vertex 0.869744 2.07638 2.45475 + vertex 0.867782 2.0738 2.45748 + vertex 0.869865 2.07108 2.45416 + endloop + endfacet + facet normal 0.843221 -0.0785643 0.531796 + outer loop + vertex 0.867523 2.07819 2.45854 + vertex 0.867782 2.0738 2.45748 + vertex 0.869744 2.07638 2.45475 + endloop + endfacet + facet normal 0.886164 -0.0516347 0.460487 + outer loop + vertex 0.873482 2.07826 2.44857 + vertex 0.873572 2.08337 2.44896 + vertex 0.871778 2.07979 2.45202 + endloop + endfacet + facet normal 0.888147 -0.0428074 0.457562 + outer loop + vertex 0.871835 2.07474 2.45143 + vertex 0.873482 2.07826 2.44857 + vertex 0.871778 2.07979 2.45202 + endloop + endfacet + facet normal 0.832415 -0.0542877 0.551488 + outer loop + vertex 0.871835 2.07474 2.45143 + vertex 0.871778 2.07979 2.45202 + vertex 0.869744 2.07638 2.45475 + endloop + endfacet + facet normal 0.848539 -0.0877283 0.521809 + outer loop + vertex 0.871778 2.07979 2.45202 + vertex 0.869898 2.08164 2.45538 + vertex 0.869744 2.07638 2.45475 + endloop + endfacet + facet normal 0.840131 -0.0890759 0.53502 + outer loop + vertex 0.869898 2.08164 2.45538 + vertex 0.867523 2.07819 2.45854 + vertex 0.869744 2.07638 2.45475 + endloop + endfacet + facet normal 0.888686 -0.387498 0.245117 + outer loop + vertex 0.87 2.085 2.46032 + vertex 0.867523 2.07819 2.45854 + vertex 0.869898 2.08164 2.45538 + endloop + endfacet + facet normal 0.880629 -0.129834 0.45567 + outer loop + vertex 0.873572 2.08337 2.44896 + vertex 0.873939 2.08927 2.44994 + vertex 0.872004 2.08557 2.45262 + endloop + endfacet + facet normal 0.897648 -0.0805089 0.433297 + outer loop + vertex 0.871778 2.07979 2.45202 + vertex 0.873572 2.08337 2.44896 + vertex 0.872004 2.08557 2.45262 + endloop + endfacet + facet normal 0.848489 -0.0878825 0.521866 + outer loop + vertex 0.871778 2.07979 2.45202 + vertex 0.872004 2.08557 2.45262 + vertex 0.869898 2.08164 2.45538 + endloop + endfacet + facet normal 0.880836 -0.158488 0.446106 + outer loop + vertex 0.872004 2.08557 2.45262 + vertex 0.8704 2.08711 2.45634 + vertex 0.869898 2.08164 2.45538 + endloop + endfacet + facet normal 0.993931 -0.0994283 0.0470578 + outer loop + vertex 0.8704 2.08711 2.45634 + vertex 0.87 2.085 2.46032 + vertex 0.869898 2.08164 2.45538 + endloop + endfacet + facet normal 0.994631 0.00660889 0.103275 + outer loop + vertex 0.87 2.09 2.46 + vertex 0.87 2.085 2.46032 + vertex 0.8704 2.08711 2.45634 + endloop + endfacet + facet normal 0.732472 -0.459904 0.501969 + outer loop + vertex 0.873939 2.08927 2.44994 + vertex 0.875 2.095 2.45364 + vertex 0.874068 2.095 2.455 + endloop + endfacet + facet normal 0.918491 -0.273211 0.285884 + outer loop + vertex 0.872004 2.08557 2.45262 + vertex 0.873939 2.08927 2.44994 + vertex 0.874068 2.095 2.455 + endloop + endfacet + facet normal 0.633299 0.225526 0.740317 + outer loop + vertex 0.87 2.09001 2.46 + vertex 0.874068 2.095 2.455 + vertex 0.87 2.095 2.45848 + endloop + endfacet + facet normal 0.866469 -0.341107 0.364523 + outer loop + vertex 0.87 2.09001 2.46 + vertex 0.8704 2.08711 2.45634 + vertex 0.874068 2.095 2.455 + endloop + endfacet + facet normal 0.82352 -0.301495 0.480536 + outer loop + vertex 0.8704 2.08711 2.45634 + vertex 0.872004 2.08557 2.45262 + vertex 0.874068 2.095 2.455 + endloop + endfacet + facet normal 0.994104 0 0.108431 + outer loop + vertex 0.8704 2.08711 2.45634 + vertex 0.87 2.09001 2.46 + vertex 0.87 2.09 2.46 + endloop + endfacet + facet normal -0.872767 -0.323946 -0.365153 + outer loop + vertex 0.870575 2.09525 2.46667 + vertex 0.87 2.09305 2.47 + vertex 0.87 2.095 2.46827 + endloop + endfacet + facet normal 0.949335 -0.311472 -0.0418189 + outer loop + vertex 0.870335 2.09402 2.47036 + vertex 0.87 2.09305 2.47 + vertex 0.870575 2.09525 2.46667 + endloop + endfacet + facet normal 0.921126 -0.366135 0.132185 + outer loop + vertex 0.868238 2.0899 2.47357 + vertex 0.87 2.09305 2.47 + vertex 0.870335 2.09402 2.47036 + endloop + endfacet + facet normal 0.923699 -0.351241 0.153005 + outer loop + vertex 0.869313 2.09358 2.47552 + vertex 0.868238 2.0899 2.47357 + vertex 0.870335 2.09402 2.47036 + endloop + endfacet + facet normal 0.868865 -0.405073 0.284586 + outer loop + vertex 0.866774 2.08965 2.47768 + vertex 0.868238 2.0899 2.47357 + vertex 0.869313 2.09358 2.47552 + endloop + endfacet + facet normal 0.780559 -0.174324 0.600282 + outer loop + vertex 0.869313 2.09358 2.47552 + vertex 0.867019 2.0938 2.47857 + vertex 0.866774 2.08965 2.47768 + endloop + endfacet + facet normal -0.544833 -0.775935 -0.317932 + outer loop + vertex 0.87 2.09634 2.465 + vertex 0.870575 2.09525 2.46667 + vertex 0.87 2.095 2.46827 + endloop + endfacet + facet normal 0.629489 -0.534036 -0.564402 + outer loop + vertex 0.87 2.09634 2.465 + vertex 0.873105 2.1 2.465 + vertex 0.870575 2.09525 2.46667 + endloop + endfacet + facet normal 0.869324 -0.488793 -0.0731932 + outer loop + vertex 0.873105 2.1 2.465 + vertex 0.873526 2.1 2.47 + vertex 0.870575 2.09525 2.46667 + endloop + endfacet + facet normal 0.875155 -0.473294 -0.100484 + outer loop + vertex 0.870575 2.09525 2.46667 + vertex 0.873526 2.1 2.47 + vertex 0.870335 2.09402 2.47036 + endloop + endfacet + facet normal 0.864969 -0.472062 -0.170252 + outer loop + vertex 0.873526 2.1 2.47 + vertex 0.872248 2.09695 2.47196 + vertex 0.870335 2.09402 2.47036 + endloop + endfacet + facet normal 0.803704 -0.584931 0.109155 + outer loop + vertex 0.870335 2.09402 2.47036 + vertex 0.872248 2.09695 2.47196 + vertex 0.869313 2.09358 2.47552 + endloop + endfacet + facet normal 0.808492 -0.575768 0.121787 + outer loop + vertex 0.872248 2.09695 2.47196 + vertex 0.871619 2.09701 2.47642 + vertex 0.869313 2.09358 2.47552 + endloop + endfacet + facet normal 0.517898 -0.582306 0.626659 + outer loop + vertex 0.867019 2.0938 2.47857 + vertex 0.869015 2.09601 2.47897 + vertex 0.867902 2.09578 2.47967 + endloop + endfacet + facet normal 0.597685 -0.630171 0.495638 + outer loop + vertex 0.867019 2.0938 2.47857 + vertex 0.869313 2.09358 2.47552 + vertex 0.869015 2.09601 2.47897 + endloop + endfacet + facet normal 0.674228 -0.575055 0.463388 + outer loop + vertex 0.869313 2.09358 2.47552 + vertex 0.871619 2.09701 2.47642 + vertex 0.869015 2.09601 2.47897 + endloop + endfacet + facet normal 0.533017 -0.508593 0.676185 + outer loop + vertex 0.869015 2.09601 2.47897 + vertex 0.868215 2.09644 2.47992 + vertex 0.867902 2.09578 2.47967 + endloop + endfacet + facet normal 0.720436 -0.596352 -0.354029 + outer loop + vertex 0.875 2.10144 2.47 + vertex 0.874771 2.09888 2.47384 + vertex 0.872248 2.09695 2.47196 + endloop + endfacet + facet normal 0.584164 -0.597946 -0.548829 + outer loop + vertex 0.873526 2.1 2.47 + vertex 0.875 2.10144 2.47 + vertex 0.872248 2.09695 2.47196 + endloop + endfacet + facet normal 0.548623 -0.833556 0.0647878 + outer loop + vertex 0.874771 2.09888 2.47384 + vertex 0.874501 2.09906 2.47837 + vertex 0.871619 2.09701 2.47642 + endloop + endfacet + facet normal 0.562535 -0.821825 0.0903264 + outer loop + vertex 0.872248 2.09695 2.47196 + vertex 0.874771 2.09888 2.47384 + vertex 0.871619 2.09701 2.47642 + endloop + endfacet + facet normal 0.724687 -0.277979 0.63052 + outer loop + vertex 0.869015 2.09601 2.47897 + vertex 0.871619 2.09701 2.47642 + vertex 0.87023 2.0994 2.47907 + endloop + endfacet + facet normal 0.675138 -0.261859 0.689651 + outer loop + vertex 0.869015 2.09601 2.47897 + vertex 0.87023 2.0994 2.47907 + vertex 0.868645 2.09714 2.47976 + endloop + endfacet + facet normal 0.0532243 -0.727368 0.684181 + outer loop + vertex 0.871619 2.09701 2.47642 + vertex 0.874501 2.09906 2.47837 + vertex 0.87023 2.0994 2.47907 + endloop + endfacet + facet normal -0.504873 -0.201138 0.839433 + outer loop + vertex 0.872134 2.10282 2.48103 + vertex 0.87023 2.0994 2.47907 + vertex 0.874555 2.10061 2.48196 + endloop + endfacet + facet normal -0.00885639 -0.917898 0.396718 + outer loop + vertex 0.874501 2.09906 2.47837 + vertex 0.874555 2.10061 2.48196 + vertex 0.87023 2.0994 2.47907 + endloop + endfacet + facet normal -0.652045 -0.462564 0.600726 + outer loop + vertex 0.874555 2.10061 2.48196 + vertex 0.87494 2.10247 2.48381 + vertex 0.872134 2.10282 2.48103 + endloop + endfacet + facet normal 0.678181 -0.25941 0.687587 + outer loop + vertex 0.869015 2.09601 2.47897 + vertex 0.868645 2.09714 2.47976 + vertex 0.868215 2.09644 2.47992 + endloop + endfacet + facet normal -0.742596 0.0291467 0.669106 + outer loop + vertex 0.869264 2.10418 2.47779 + vertex 0.87023 2.0994 2.47907 + vertex 0.872134 2.10282 2.48103 + endloop + endfacet + facet normal -0.679832 0.228042 0.697012 + outer loop + vertex 0.871439 2.10652 2.47914 + vertex 0.869264 2.10418 2.47779 + vertex 0.872134 2.10282 2.48103 + endloop + endfacet + facet normal -0.752098 0.182056 0.633407 + outer loop + vertex 0.872134 2.10282 2.48103 + vertex 0.874047 2.10508 2.48265 + vertex 0.871439 2.10652 2.47914 + endloop + endfacet + facet normal -0.696963 0.0786279 0.712783 + outer loop + vertex 0.87494 2.10247 2.48381 + vertex 0.874047 2.10508 2.48265 + vertex 0.872134 2.10282 2.48103 + endloop + endfacet + facet normal -0.558859 0.593336 0.579335 + outer loop + vertex 0.869532 2.11355 2.47051 + vertex 0.86744 2.11296 2.46909 + vertex 0.867797 2.11039 2.47207 + endloop + endfacet + facet normal -0.604455 0.594287 0.530525 + outer loop + vertex 0.871472 2.11082 2.47577 + vertex 0.869532 2.11355 2.47051 + vertex 0.867797 2.11039 2.47207 + endloop + endfacet + facet normal -0.640326 0.507801 0.576299 + outer loop + vertex 0.869303 2.1078 2.47603 + vertex 0.871472 2.11082 2.47577 + vertex 0.867797 2.11039 2.47207 + endloop + endfacet + facet normal -0.720213 0.309457 0.62091 + outer loop + vertex 0.869303 2.1078 2.47603 + vertex 0.869264 2.10418 2.47779 + vertex 0.871439 2.10652 2.47914 + endloop + endfacet + facet normal -0.611536 0.490932 0.620492 + outer loop + vertex 0.871472 2.11082 2.47577 + vertex 0.869303 2.1078 2.47603 + vertex 0.871439 2.10652 2.47914 + endloop + endfacet + facet normal -0.687281 0.451305 0.569183 + outer loop + vertex 0.871472 2.11082 2.47577 + vertex 0.871439 2.10652 2.47914 + vertex 0.873798 2.10867 2.48028 + endloop + endfacet + facet normal -0.671036 0.472848 0.571074 + outer loop + vertex 0.871472 2.11082 2.47577 + vertex 0.873798 2.10867 2.48028 + vertex 0.873879 2.11101 2.47845 + endloop + endfacet + facet normal -0.660644 0.380706 0.647003 + outer loop + vertex 0.873798 2.10867 2.48028 + vertex 0.871439 2.10652 2.47914 + vertex 0.874047 2.10508 2.48265 + endloop + endfacet + facet normal -0.515876 0.666374 0.538347 + outer loop + vertex 0.87073 2.11652 2.46746 + vertex 0.868416 2.11689 2.46478 + vertex 0.867715 2.11477 2.46673 + endloop + endfacet + facet normal -0.522193 0.705385 0.479318 + outer loop + vertex 0.867715 2.11477 2.46673 + vertex 0.86744 2.11296 2.46909 + vertex 0.869532 2.11355 2.47051 + endloop + endfacet + facet normal -0.523617 0.704138 0.479599 + outer loop + vertex 0.87073 2.11652 2.46746 + vertex 0.867715 2.11477 2.46673 + vertex 0.869532 2.11355 2.47051 + endloop + endfacet + facet normal -0.50342 0.709663 0.492897 + outer loop + vertex 0.87073 2.11652 2.46746 + vertex 0.869532 2.11355 2.47051 + vertex 0.872932 2.11475 2.47226 + endloop + endfacet + facet normal -0.36312 0.807602 0.464674 + outer loop + vertex 0.87073 2.11652 2.46746 + vertex 0.872932 2.11475 2.47226 + vertex 0.873195 2.11663 2.46918 + endloop + endfacet + facet normal -0.599321 0.64633 0.472305 + outer loop + vertex 0.872932 2.11475 2.47226 + vertex 0.871472 2.11082 2.47577 + vertex 0.874263 2.11278 2.47664 + endloop + endfacet + facet normal -0.512024 0.671076 0.53618 + outer loop + vertex 0.869532 2.11355 2.47051 + vertex 0.871472 2.11082 2.47577 + vertex 0.872932 2.11475 2.47226 + endloop + endfacet + facet normal -0.596633 0.633381 0.492805 + outer loop + vertex 0.874263 2.11278 2.47664 + vertex 0.871472 2.11082 2.47577 + vertex 0.873879 2.11101 2.47845 + endloop + endfacet + facet normal -0.721004 0.227632 0.654474 + outer loop + vertex 0.87073 2.11652 2.46746 + vertex 0.87 2.12127 2.465 + vertex 0.868416 2.11689 2.46478 + endloop + endfacet + facet normal -0.267738 0.40975 0.872021 + outer loop + vertex 0.87073 2.11652 2.46746 + vertex 0.874642 2.11866 2.46765 + vertex 0.87 2.12127 2.465 + endloop + endfacet + facet normal -0.120047 0.594327 0.795213 + outer loop + vertex 0.874642 2.11866 2.46765 + vertex 0.875 2.12228 2.465 + vertex 0.87 2.12127 2.465 + endloop + endfacet + facet normal -0.421012 0.718586 0.553519 + outer loop + vertex 0.874642 2.11866 2.46765 + vertex 0.87073 2.11652 2.46746 + vertex 0.873195 2.11663 2.46918 + endloop + endfacet + facet normal -0.321047 -0.922561 0.214034 + outer loop + vertex 0.88 0.905406 2.465 + vertex 0.88 0.906566 2.47 + vertex 0.875 0.907146 2.465 + endloop + endfacet + facet normal -0.171623 -0.98348 0.0575475 + outer loop + vertex 0.88 0.906566 2.47 + vertex 0.873553 0.90748 2.4664 + vertex 0.875 0.907146 2.465 + endloop + endfacet + facet normal 0.125987 -0.884215 -0.449767 + outer loop + vertex 0.88 0.906566 2.47 + vertex 0.879133 0.906063 2.47075 + vertex 0.873553 0.90748 2.4664 + endloop + endfacet + facet normal -0.388233 -0.898411 0.205263 + outer loop + vertex 0.879133 0.906063 2.47075 + vertex 0.874252 0.908101 2.47044 + vertex 0.873553 0.90748 2.4664 + endloop + endfacet + facet normal -0.507482 -0.76394 0.39857 + outer loop + vertex 0.873318 0.910095 2.4729 + vertex 0.878032 0.907902 2.4747 + vertex 0.875842 0.909716 2.47539 + endloop + endfacet + facet normal -0.50924 -0.753364 0.416074 + outer loop + vertex 0.873318 0.910095 2.4729 + vertex 0.874252 0.908101 2.47044 + vertex 0.878032 0.907902 2.4747 + endloop + endfacet + facet normal -0.383835 -0.873521 0.299386 + outer loop + vertex 0.874252 0.908101 2.47044 + vertex 0.879133 0.906063 2.47075 + vertex 0.878032 0.907902 2.4747 + endloop + endfacet + facet normal -0.474767 -0.74875 0.462569 + outer loop + vertex 0.878032 0.907902 2.4747 + vertex 0.877992 0.909972 2.47801 + vertex 0.875842 0.909716 2.47539 + endloop + endfacet + facet normal -0.603571 -0.604024 0.52044 + outer loop + vertex 0.873318 0.910095 2.4729 + vertex 0.875842 0.909716 2.47539 + vertex 0.874112 0.911867 2.47588 + endloop + endfacet + facet normal -0.606812 -0.581459 0.541928 + outer loop + vertex 0.878825 0.911496 2.48075 + vertex 0.876996 0.91341 2.48075 + vertex 0.875683 0.91294 2.47878 + endloop + endfacet + facet normal -0.603661 -0.603982 0.520384 + outer loop + vertex 0.877992 0.909972 2.47801 + vertex 0.878825 0.911496 2.48075 + vertex 0.875683 0.91294 2.47878 + endloop + endfacet + facet normal -0.589927 -0.598797 0.54169 + outer loop + vertex 0.877992 0.909972 2.47801 + vertex 0.875683 0.91294 2.47878 + vertex 0.874112 0.911867 2.47588 + endloop + endfacet + facet normal -0.589979 -0.598085 0.542419 + outer loop + vertex 0.877992 0.909972 2.47801 + vertex 0.874112 0.911867 2.47588 + vertex 0.875842 0.909716 2.47539 + endloop + endfacet + facet normal -0.57796 -0.554009 0.599197 + outer loop + vertex 0.878825 0.911496 2.48075 + vertex 0.879087 0.913785 2.48312 + vertex 0.876996 0.91341 2.48075 + endloop + endfacet + facet normal -0.668518 -0.488418 0.560832 + outer loop + vertex 0.875683 0.91294 2.47878 + vertex 0.876996 0.91341 2.48075 + vertex 0.87514 0.915512 2.48037 + endloop + endfacet + facet normal -0.66342 -0.115686 0.73925 + outer loop + vertex 0.879527 0.91626 2.48535 + vertex 0.878051 0.919409 2.48452 + vertex 0.876158 0.917729 2.48256 + endloop + endfacet + facet normal -0.680761 -0.420226 0.599978 + outer loop + vertex 0.879087 0.913785 2.48312 + vertex 0.879527 0.91626 2.48535 + vertex 0.876158 0.917729 2.48256 + endloop + endfacet + facet normal -0.634317 -0.374918 0.676076 + outer loop + vertex 0.879087 0.913785 2.48312 + vertex 0.876158 0.917729 2.48256 + vertex 0.87514 0.915512 2.48037 + endloop + endfacet + facet normal -0.634361 -0.445389 0.631834 + outer loop + vertex 0.879087 0.913785 2.48312 + vertex 0.87514 0.915512 2.48037 + vertex 0.876996 0.91341 2.48075 + endloop + endfacet + facet normal -0.753362 -0.186574 0.630584 + outer loop + vertex 0.879527 0.91626 2.48535 + vertex 0.880924 0.917609 2.48742 + vertex 0.878051 0.919409 2.48452 + endloop + endfacet + facet normal 0.668529 0.720555 -0.184038 + outer loop + vertex 0.88 0.92399 2.475 + vertex 0.88 0.922713 2.47 + vertex 0.877535 0.925 2.47 + endloop + endfacet + facet normal 0.116407 0.983113 0.141203 + outer loop + vertex 0.876572 0.924585 2.47368 + vertex 0.88 0.92399 2.475 + vertex 0.877535 0.925 2.47 + endloop + endfacet + facet normal 0.0267073 0.935258 0.352957 + outer loop + vertex 0.879627 0.922995 2.47766 + vertex 0.88 0.92399 2.475 + vertex 0.876572 0.924585 2.47368 + endloop + endfacet + facet normal 0.268046 0.94778 0.172816 + outer loop + vertex 0.875851 0.923963 2.47821 + vertex 0.879627 0.922995 2.47766 + vertex 0.876572 0.924585 2.47368 + endloop + endfacet + facet normal 0.274757 0.926658 0.25654 + outer loop + vertex 0.878685 0.92196 2.48241 + vertex 0.879627 0.922995 2.47766 + vertex 0.875851 0.923963 2.47821 + endloop + endfacet + facet normal 0.0979737 0.922339 0.373754 + outer loop + vertex 0.875295 0.923072 2.48056 + vertex 0.878685 0.92196 2.48241 + vertex 0.875851 0.923963 2.47821 + endloop + endfacet + facet normal -0.553975 0.607394 0.569372 + outer loop + vertex 0.878051 0.919409 2.48452 + vertex 0.880988 0.919843 2.48691 + vertex 0.878685 0.92196 2.48241 + endloop + endfacet + facet normal -0.284638 0.651102 0.703596 + outer loop + vertex 0.878051 0.919409 2.48452 + vertex 0.878685 0.92196 2.48241 + vertex 0.874713 0.92128 2.48143 + endloop + endfacet + facet normal -0.694054 -0.0560406 0.717739 + outer loop + vertex 0.878051 0.919409 2.48452 + vertex 0.874713 0.92128 2.48143 + vertex 0.876158 0.917729 2.48256 + endloop + endfacet + facet normal -0.286623 0.494786 0.820387 + outer loop + vertex 0.874713 0.92128 2.48143 + vertex 0.878685 0.92196 2.48241 + vertex 0.875295 0.923072 2.48056 + endloop + endfacet + facet normal -0.63716 0.18751 0.747574 + outer loop + vertex 0.880988 0.919843 2.48691 + vertex 0.878051 0.919409 2.48452 + vertex 0.880924 0.917609 2.48742 + endloop + endfacet + facet normal 0.825686 0.332902 0.455432 + outer loop + vertex 0.877816 0.927294 2.44735 + vertex 0.878173 0.93081 2.44414 + vertex 0.877232 0.929745 2.44662 + endloop + endfacet + facet normal 0.854315 0.324856 0.405728 + outer loop + vertex 0.877816 0.927294 2.44735 + vertex 0.877232 0.929745 2.44662 + vertex 0.875932 0.929171 2.44982 + endloop + endfacet + facet normal 0.833615 0.132878 0.536125 + outer loop + vertex 0.877816 0.927294 2.44735 + vertex 0.875932 0.929171 2.44982 + vertex 0.875 0.925 2.4523 + endloop + endfacet + facet normal 0.178488 0.849906 0.495784 + outer loop + vertex 0.877816 0.927294 2.44735 + vertex 0.875 0.925 2.4523 + vertex 0.88 0.925 2.4505 + endloop + endfacet + facet normal 0.978584 -0.118478 0.168334 + outer loop + vertex 0.875 0.928836 2.455 + vertex 0.875 0.925 2.4523 + vertex 0.875932 0.929171 2.44982 + endloop + endfacet + facet normal 0.970663 -0.176615 0.163156 + outer loop + vertex 0.875932 0.929171 2.44982 + vertex 0.875 0.93 2.45626 + vertex 0.875 0.928836 2.455 + endloop + endfacet + facet normal 0.663071 0.563019 -0.493301 + outer loop + vertex 0.875 0.925 2.46261 + vertex 0.875 0.927094 2.465 + vertex 0.876778 0.925 2.465 + endloop + endfacet + facet normal 0.528008 0.845469 -0.0799363 + outer loop + vertex 0.876778 0.925 2.465 + vertex 0.874482 0.926507 2.46577 + vertex 0.877535 0.925 2.47 + endloop + endfacet + facet normal 0.538526 0.457266 0.707741 + outer loop + vertex 0.875 0.927094 2.465 + vertex 0.874482 0.926507 2.46577 + vertex 0.876778 0.925 2.465 + endloop + endfacet + facet normal 0.387203 0.899466 0.202572 + outer loop + vertex 0.877535 0.925 2.47 + vertex 0.874193 0.926442 2.46999 + vertex 0.876572 0.924585 2.47368 + endloop + endfacet + facet normal 0.395568 0.917502 0.0414157 + outer loop + vertex 0.874482 0.926507 2.46577 + vertex 0.874193 0.926442 2.46999 + vertex 0.877535 0.925 2.47 + endloop + endfacet + facet normal 0.436894 0.879152 0.190305 + outer loop + vertex 0.876572 0.924585 2.47368 + vertex 0.872841 0.926067 2.4754 + vertex 0.875851 0.923963 2.47821 + endloop + endfacet + facet normal 0.430018 0.886921 0.168689 + outer loop + vertex 0.874193 0.926442 2.46999 + vertex 0.872841 0.926067 2.4754 + vertex 0.876572 0.924585 2.47368 + endloop + endfacet + facet normal 0.0695514 0.926915 0.368769 + outer loop + vertex 0.875851 0.923963 2.47821 + vertex 0.872979 0.923821 2.47911 + vertex 0.875295 0.923072 2.48056 + endloop + endfacet + facet normal 0.117909 0.851343 0.511188 + outer loop + vertex 0.872841 0.926067 2.4754 + vertex 0.872979 0.923821 2.47911 + vertex 0.875851 0.923963 2.47821 + endloop + endfacet + facet normal -0.336651 0.500039 0.797889 + outer loop + vertex 0.875295 0.923072 2.48056 + vertex 0.872979 0.923821 2.47911 + vertex 0.874713 0.92128 2.48143 + endloop + endfacet + facet normal 0.906281 0.166531 0.388488 + outer loop + vertex 0.878173 0.93081 2.44414 + vertex 0.878211 0.934191 2.4426 + vertex 0.877025 0.933088 2.44584 + endloop + endfacet + facet normal 0.901303 0.150901 0.406056 + outer loop + vertex 0.877232 0.929745 2.44662 + vertex 0.878173 0.93081 2.44414 + vertex 0.877025 0.933088 2.44584 + endloop + endfacet + facet normal 0.906441 0.148693 0.395291 + outer loop + vertex 0.877232 0.929745 2.44662 + vertex 0.877025 0.933088 2.44584 + vertex 0.875932 0.929171 2.44982 + endloop + endfacet + facet normal 0.933227 0.0923616 0.347213 + outer loop + vertex 0.877025 0.933088 2.44584 + vertex 0.875365 0.933414 2.45021 + vertex 0.875932 0.929171 2.44982 + endloop + endfacet + facet normal 0.984651 0.119689 0.127035 + outer loop + vertex 0.875365 0.933414 2.45021 + vertex 0.875 0.93 2.45626 + vertex 0.875932 0.929171 2.44982 + endloop + endfacet + facet normal 0.998181 -0 0.0602887 + outer loop + vertex 0.875 0.935 2.45626 + vertex 0.875 0.93 2.45626 + vertex 0.875365 0.933414 2.45021 + endloop + endfacet + facet normal 0.902427 0.402706 -0.153144 + outer loop + vertex 0.88 0.93946 2.425 + vertex 0.879759 0.94 2.425 + vertex 0.88 0.94 2.42642 + endloop + endfacet + facet normal 0.942156 0.212712 0.259027 + outer loop + vertex 0.878645 0.936205 2.44012 + vertex 0.878609 0.938944 2.43801 + vertex 0.877808 0.938153 2.44157 + endloop + endfacet + facet normal 0.935716 0.174756 0.306424 + outer loop + vertex 0.878211 0.934191 2.4426 + vertex 0.878645 0.936205 2.44012 + vertex 0.877808 0.938153 2.44157 + endloop + endfacet + facet normal 0.898082 0.193865 0.394797 + outer loop + vertex 0.878211 0.934191 2.4426 + vertex 0.877808 0.938153 2.44157 + vertex 0.877025 0.933088 2.44584 + endloop + endfacet + facet normal 0.941024 0.120873 0.316012 + outer loop + vertex 0.877025 0.933088 2.44584 + vertex 0.877808 0.938153 2.44157 + vertex 0.876374 0.938127 2.44585 + endloop + endfacet + facet normal 0.93118 0.119526 0.344409 + outer loop + vertex 0.877025 0.933088 2.44584 + vertex 0.876374 0.938127 2.44585 + vertex 0.875365 0.933414 2.45021 + endloop + endfacet + facet normal 0.933879 0.113905 0.338961 + outer loop + vertex 0.876374 0.938127 2.44585 + vertex 0.874771 0.938482 2.45015 + vertex 0.875365 0.933414 2.45021 + endloop + endfacet + facet normal 0.992725 0.116769 0.0293469 + outer loop + vertex 0.874771 0.938482 2.45015 + vertex 0.875 0.935 2.45626 + vertex 0.875365 0.933414 2.45021 + endloop + endfacet + facet normal 0.763422 0.573156 0.297791 + outer loop + vertex 0.872421 0.939539 2.45414 + vertex 0.875 0.935 2.45626 + vertex 0.874771 0.938482 2.45015 + endloop + endfacet + facet normal 0.599941 0.163698 0.783118 + outer loop + vertex 0.879407 0.940889 2.43075 + vertex 0.88 0.942288 2.43 + vertex 0.87926 0.945 2.43 + endloop + endfacet + facet normal 0.939719 0.0934162 0.32894 + outer loop + vertex 0.878753 0.944534 2.43158 + vertex 0.879407 0.940889 2.43075 + vertex 0.87926 0.945 2.43 + endloop + endfacet + facet normal 0.980316 0.145418 0.133546 + outer loop + vertex 0.879011 0.940205 2.4344 + vertex 0.879407 0.940889 2.43075 + vertex 0.878753 0.944534 2.43158 + endloop + endfacet + facet normal 0.970293 0.169989 0.172147 + outer loop + vertex 0.87813 0.943308 2.43631 + vertex 0.879011 0.940205 2.4344 + vertex 0.878753 0.944534 2.43158 + endloop + endfacet + facet normal 0.970525 0.172261 0.168546 + outer loop + vertex 0.878609 0.938944 2.43801 + vertex 0.879011 0.940205 2.4344 + vertex 0.87813 0.943308 2.43631 + endloop + endfacet + facet normal 0.944436 0.204121 0.257634 + outer loop + vertex 0.878609 0.938944 2.43801 + vertex 0.87813 0.943308 2.43631 + vertex 0.877808 0.938153 2.44157 + endloop + endfacet + facet normal 0.974307 0.128235 0.185154 + outer loop + vertex 0.877808 0.938153 2.44157 + vertex 0.87813 0.943308 2.43631 + vertex 0.877172 0.943483 2.44122 + endloop + endfacet + facet normal 0.939584 0.132578 0.315602 + outer loop + vertex 0.877808 0.938153 2.44157 + vertex 0.877172 0.943483 2.44122 + vertex 0.876374 0.938127 2.44585 + endloop + endfacet + facet normal 0.96542 0.0724386 0.250433 + outer loop + vertex 0.877172 0.943483 2.44122 + vertex 0.875994 0.94352 2.44575 + vertex 0.876374 0.938127 2.44585 + endloop + endfacet + facet normal 0.936432 0.0720797 0.343366 + outer loop + vertex 0.876374 0.938127 2.44585 + vertex 0.875994 0.94352 2.44575 + vertex 0.874771 0.938482 2.45015 + endloop + endfacet + facet normal 0.938243 0.0680283 0.339224 + outer loop + vertex 0.875994 0.94352 2.44575 + vertex 0.874477 0.943968 2.44986 + vertex 0.874771 0.938482 2.45015 + endloop + endfacet + facet normal 0.867658 0.0721792 0.491895 + outer loop + vertex 0.874477 0.943968 2.44986 + vertex 0.872421 0.939539 2.45414 + vertex 0.874771 0.938482 2.45015 + endloop + endfacet + facet normal 0.893934 0.0174824 0.447857 + outer loop + vertex 0.872723 0.945274 2.45331 + vertex 0.872421 0.939539 2.45414 + vertex 0.874477 0.943968 2.44986 + endloop + endfacet + facet normal 0.955585 -0.0632568 0.287848 + outer loop + vertex 0.87926 0.945 2.43 + vertex 0.879591 0.95 2.43 + vertex 0.878753 0.944534 2.43158 + endloop + endfacet + facet normal 0.750913 0.0746382 0.65617 + outer loop + vertex 0.879591 0.95 2.43 + vertex 0.878037 0.948895 2.4319 + vertex 0.878753 0.944534 2.43158 + endloop + endfacet + facet normal 0.974837 0.147702 0.166965 + outer loop + vertex 0.878753 0.944534 2.43158 + vertex 0.878037 0.948895 2.4319 + vertex 0.87813 0.943308 2.43631 + endloop + endfacet + facet normal 0.975563 0.145725 0.164439 + outer loop + vertex 0.878037 0.948895 2.4319 + vertex 0.877325 0.948715 2.43629 + vertex 0.87813 0.943308 2.43631 + endloop + endfacet + facet normal 0.972109 0.145271 0.18412 + outer loop + vertex 0.87813 0.943308 2.43631 + vertex 0.877325 0.948715 2.43629 + vertex 0.877172 0.943483 2.44122 + endloop + endfacet + facet normal 0.985006 0.102275 0.138936 + outer loop + vertex 0.877325 0.948715 2.43629 + vertex 0.876636 0.948797 2.44111 + vertex 0.877172 0.943483 2.44122 + endloop + endfacet + facet normal 0.962942 0.102326 0.249545 + outer loop + vertex 0.877172 0.943483 2.44122 + vertex 0.876636 0.948797 2.44111 + vertex 0.875994 0.94352 2.44575 + endloop + endfacet + facet normal 0.977153 0.0603714 0.203784 + outer loop + vertex 0.876636 0.948797 2.44111 + vertex 0.875677 0.948827 2.4457 + vertex 0.875994 0.94352 2.44575 + endloop + endfacet + facet normal 0.93846 0.0593575 0.340249 + outer loop + vertex 0.875994 0.94352 2.44575 + vertex 0.875677 0.948827 2.4457 + vertex 0.874477 0.943968 2.44986 + endloop + endfacet + facet normal 0.955969 0.0146811 0.293101 + outer loop + vertex 0.875677 0.948827 2.4457 + vertex 0.874425 0.94917 2.44977 + vertex 0.874477 0.943968 2.44986 + endloop + endfacet + facet normal 0.893837 0.0167659 0.448078 + outer loop + vertex 0.874425 0.94917 2.44977 + vertex 0.872723 0.945274 2.45331 + vertex 0.874477 0.943968 2.44986 + endloop + endfacet + facet normal 0.902849 -0.00365134 0.429942 + outer loop + vertex 0.872895 0.950238 2.45299 + vertex 0.872723 0.945274 2.45331 + vertex 0.874425 0.94917 2.44977 + endloop + endfacet + facet normal 0.71772 0.1589 0.677959 + outer loop + vertex 0.879591 0.95 2.43 + vertex 0.878484 0.955 2.43 + vertex 0.878037 0.948895 2.4319 + endloop + endfacet + facet normal 0.735183 0.152194 0.660563 + outer loop + vertex 0.878484 0.955 2.43 + vertex 0.876911 0.953482 2.4321 + vertex 0.878037 0.948895 2.4319 + endloop + endfacet + facet normal 0.959446 0.228392 0.165226 + outer loop + vertex 0.878037 0.948895 2.4319 + vertex 0.876911 0.953482 2.4321 + vertex 0.877325 0.948715 2.43629 + endloop + endfacet + facet normal 0.984542 0.155769 0.0800775 + outer loop + vertex 0.876911 0.953482 2.4321 + vertex 0.876535 0.953565 2.43657 + vertex 0.877325 0.948715 2.43629 + endloop + endfacet + facet normal 0.978879 0.151545 0.137224 + outer loop + vertex 0.877325 0.948715 2.43629 + vertex 0.876535 0.953565 2.43657 + vertex 0.876636 0.948797 2.44111 + endloop + endfacet + facet normal 0.985451 0.127743 0.112108 + outer loop + vertex 0.876535 0.953565 2.43657 + vertex 0.875982 0.953693 2.44128 + vertex 0.876636 0.948797 2.44111 + endloop + endfacet + facet normal 0.971605 0.122864 0.20221 + outer loop + vertex 0.876636 0.948797 2.44111 + vertex 0.875982 0.953693 2.44128 + vertex 0.875677 0.948827 2.4457 + endloop + endfacet + facet normal 0.979178 0.0994525 0.176975 + outer loop + vertex 0.875982 0.953693 2.44128 + vertex 0.875165 0.953597 2.44586 + vertex 0.875677 0.948827 2.4457 + endloop + endfacet + facet normal 0.953745 0.0932182 0.285798 + outer loop + vertex 0.875677 0.948827 2.4457 + vertex 0.875165 0.953597 2.44586 + vertex 0.874425 0.94917 2.44977 + endloop + endfacet + facet normal 0.965575 0.0619282 0.252647 + outer loop + vertex 0.875165 0.953597 2.44586 + vertex 0.874151 0.953535 2.44974 + vertex 0.874425 0.94917 2.44977 + endloop + endfacet + facet normal 0.909214 0.0593219 0.41208 + outer loop + vertex 0.874151 0.953535 2.44974 + vertex 0.872895 0.950238 2.45299 + vertex 0.874425 0.94917 2.44977 + endloop + endfacet + facet normal 0.915177 0.0456143 0.400462 + outer loop + vertex 0.873052 0.954156 2.45219 + vertex 0.872895 0.950238 2.45299 + vertex 0.874151 0.953535 2.44974 + endloop + endfacet + facet normal 0.626682 0.666098 -0.404454 + outer loop + vertex 0.875 0.96 2.42915 + vertex 0.877636 0.955 2.425 + vertex 0.875 0.95748 2.425 + endloop + endfacet + facet normal 0.903379 0.424236 0.0626824 + outer loop + vertex 0.875 0.96 2.42915 + vertex 0.875761 0.958296 2.42971 + vertex 0.877636 0.955 2.425 + endloop + endfacet + facet normal 0.770077 0.62444 -0.130601 + outer loop + vertex 0.875761 0.958296 2.42971 + vertex 0.878484 0.955 2.43 + vertex 0.877636 0.955 2.425 + endloop + endfacet + facet normal 0.501392 0.478224 0.721047 + outer loop + vertex 0.878484 0.955 2.43 + vertex 0.875761 0.958296 2.42971 + vertex 0.876911 0.953482 2.4321 + endloop + endfacet + facet normal 0.968698 0.246392 0.0302559 + outer loop + vertex 0.875761 0.958296 2.42971 + vertex 0.875945 0.957141 2.43325 + vertex 0.876911 0.953482 2.4321 + endloop + endfacet + facet normal 0.969664 0.231858 0.0774224 + outer loop + vertex 0.876911 0.953482 2.4321 + vertex 0.875945 0.957141 2.43325 + vertex 0.876535 0.953565 2.43657 + endloop + endfacet + facet normal 0.980805 0.192217 0.0327652 + outer loop + vertex 0.875945 0.957141 2.43325 + vertex 0.875651 0.957977 2.43714 + vertex 0.876535 0.953565 2.43657 + endloop + endfacet + facet normal 0.977246 0.181555 0.109675 + outer loop + vertex 0.876535 0.953565 2.43657 + vertex 0.875651 0.957977 2.43714 + vertex 0.875982 0.953693 2.44128 + endloop + endfacet + facet normal 0.979151 0.175149 0.102893 + outer loop + vertex 0.875651 0.957977 2.43714 + vertex 0.875157 0.958021 2.44177 + vertex 0.875982 0.953693 2.44128 + endloop + endfacet + facet normal 0.970305 0.165097 0.176778 + outer loop + vertex 0.875982 0.953693 2.44128 + vertex 0.875157 0.958021 2.44177 + vertex 0.875165 0.953597 2.44586 + endloop + endfacet + facet normal 0.972208 0.159831 0.171073 + outer loop + vertex 0.875157 0.958021 2.44177 + vertex 0.874387 0.957829 2.44632 + vertex 0.875165 0.953597 2.44586 + endloop + endfacet + facet normal 0.953583 0.175107 0.244983 + outer loop + vertex 0.873701 0.956568 2.44989 + vertex 0.874387 0.957829 2.44632 + vertex 0.87359 0.959454 2.44826 + endloop + endfacet + facet normal 0.963844 0.131712 0.231637 + outer loop + vertex 0.873701 0.956568 2.44989 + vertex 0.874151 0.953535 2.44974 + vertex 0.874387 0.957829 2.44632 + endloop + endfacet + facet normal 0.956432 0.148052 0.25163 + outer loop + vertex 0.874151 0.953535 2.44974 + vertex 0.875165 0.953597 2.44586 + vertex 0.874387 0.957829 2.44632 + endloop + endfacet + facet normal 0.916372 0.117162 0.382799 + outer loop + vertex 0.874151 0.953535 2.44974 + vertex 0.873701 0.956568 2.44989 + vertex 0.873052 0.954156 2.45219 + endloop + endfacet + facet normal 0.842125 0.214646 -0.494725 + outer loop + vertex 0.875 0.96 2.42915 + vertex 0.875 0.961959 2.43 + vertex 0.875761 0.958296 2.42971 + endloop + endfacet + facet normal 0.963222 0.213315 -0.163401 + outer loop + vertex 0.875 0.965 2.43397 + vertex 0.875761 0.958296 2.42971 + vertex 0.875 0.961959 2.43 + endloop + endfacet + facet normal 0.985322 0.00338695 0.170673 + outer loop + vertex 0.875 0.965 2.43397 + vertex 0.875031 0.961857 2.43385 + vertex 0.875761 0.958296 2.42971 + endloop + endfacet + facet normal 0.981957 0.188795 0.0107697 + outer loop + vertex 0.875031 0.961857 2.43385 + vertex 0.875945 0.957141 2.43325 + vertex 0.875761 0.958296 2.42971 + endloop + endfacet + facet normal 0.981991 0.185799 0.0342343 + outer loop + vertex 0.875945 0.957141 2.43325 + vertex 0.875031 0.961857 2.43385 + vertex 0.875651 0.957977 2.43714 + endloop + endfacet + facet normal 0.977175 0.204567 0.0572834 + outer loop + vertex 0.875031 0.961857 2.43385 + vertex 0.874757 0.961984 2.43807 + vertex 0.875651 0.957977 2.43714 + endloop + endfacet + facet normal 0.975702 0.19373 0.102348 + outer loop + vertex 0.875651 0.957977 2.43714 + vertex 0.874757 0.961984 2.43807 + vertex 0.875157 0.958021 2.44177 + endloop + endfacet + facet normal 0.973336 0.201044 0.110449 + outer loop + vertex 0.874757 0.961984 2.43807 + vertex 0.87434 0.961662 2.44233 + vertex 0.875157 0.958021 2.44177 + endloop + endfacet + facet normal 0.96517 0.200444 0.168132 + outer loop + vertex 0.873846 0.961384 2.4455 + vertex 0.87434 0.961662 2.44233 + vertex 0.873689 0.964161 2.4431 + endloop + endfacet + facet normal 0.968229 0.185835 0.167328 + outer loop + vertex 0.873846 0.961384 2.4455 + vertex 0.874387 0.957829 2.44632 + vertex 0.87434 0.961662 2.44233 + endloop + endfacet + facet normal 0.966691 0.190067 0.171415 + outer loop + vertex 0.874387 0.957829 2.44632 + vertex 0.875157 0.958021 2.44177 + vertex 0.87434 0.961662 2.44233 + endloop + endfacet + facet normal 0.953817 0.197301 0.226508 + outer loop + vertex 0.874387 0.957829 2.44632 + vertex 0.873846 0.961384 2.4455 + vertex 0.87359 0.959454 2.44826 + endloop + endfacet + facet normal 0.999534 0.0110662 -0.0284513 + outer loop + vertex 0.875 0.965 2.43397 + vertex 0.875 0.967648 2.435 + vertex 0.875031 0.961857 2.43385 + endloop + endfacet + facet normal 0.988596 0.138111 0.0600315 + outer loop + vertex 0.875031 0.961857 2.43385 + vertex 0.874345 0.965996 2.43563 + vertex 0.874757 0.961984 2.43807 + endloop + endfacet + facet normal 0.816353 -0.10813 0.56734 + outer loop + vertex 0.875 0.967648 2.435 + vertex 0.874345 0.965996 2.43563 + vertex 0.875031 0.961857 2.43385 + endloop + endfacet + facet normal 0.977183 0.182065 0.109388 + outer loop + vertex 0.874757 0.961984 2.43807 + vertex 0.873978 0.965424 2.43931 + vertex 0.87434 0.961662 2.44233 + endloop + endfacet + facet normal 0.976382 0.176363 0.124794 + outer loop + vertex 0.874345 0.965996 2.43563 + vertex 0.873978 0.965424 2.43931 + vertex 0.874757 0.961984 2.43807 + endloop + endfacet + facet normal 0.967432 0.208552 0.143463 + outer loop + vertex 0.87434 0.961662 2.44233 + vertex 0.873978 0.965424 2.43931 + vertex 0.873689 0.964161 2.4431 + endloop + endfacet + facet normal 0.164257 -0.513358 -0.842308 + outer loop + vertex 0.873761 1.11771 2.54876 + vertex 0.88 1.12 2.54858 + vertex 0.88 1.11767 2.55 + endloop + endfacet + facet normal 0.0198022 -0.131443 -0.991126 + outer loop + vertex 0.875 1.12 2.54848 + vertex 0.88 1.12 2.54858 + vertex 0.873761 1.11771 2.54876 + endloop + endfacet + facet normal -0.0141226 -0.999835 0.0114363 + outer loop + vertex 0.874561 1.11801 2.55187 + vertex 0.88 1.11797 2.555 + vertex 0.87609 1.11801 2.55407 + endloop + endfacet + facet normal -0.0735661 -0.99066 0.11481 + outer loop + vertex 0.874561 1.11801 2.55187 + vertex 0.873761 1.11771 2.54876 + vertex 0.88 1.11797 2.555 + endloop + endfacet + facet normal -0.0182966 -0.998039 0.0598671 + outer loop + vertex 0.873761 1.11771 2.54876 + vertex 0.88 1.11767 2.55 + vertex 0.88 1.11797 2.555 + endloop + endfacet + facet normal 0.229263 -0.0980327 -0.968415 + outer loop + vertex 0.879629 1.11593 2.55512 + vertex 0.87609 1.11801 2.55407 + vertex 0.88 1.11797 2.555 + endloop + endfacet + facet normal -0.544698 -0.805794 0.232378 + outer loop + vertex 0.876937 1.11795 2.55583 + vertex 0.87609 1.11801 2.55407 + vertex 0.879629 1.11593 2.55512 + endloop + endfacet + facet normal -0.530543 -0.801841 0.27491 + outer loop + vertex 0.879629 1.11593 2.55512 + vertex 0.87832 1.118 2.55866 + vertex 0.876937 1.11795 2.55583 + endloop + endfacet + facet normal -0.291967 -0.93434 0.204364 + outer loop + vertex 0.874561 1.11801 2.55187 + vertex 0.87609 1.11801 2.55407 + vertex 0.872054 1.11913 2.55339 + endloop + endfacet + facet normal -0.476176 -0.856894 0.197456 + outer loop + vertex 0.87609 1.11801 2.55407 + vertex 0.876937 1.11795 2.55583 + vertex 0.873647 1.11989 2.5563 + endloop + endfacet + facet normal -0.305154 -0.867245 0.393404 + outer loop + vertex 0.872054 1.11913 2.55339 + vertex 0.87609 1.11801 2.55407 + vertex 0.873647 1.11989 2.5563 + endloop + endfacet + facet normal -0.50205 -0.615073 0.607973 + outer loop + vertex 0.877256 1.12089 2.5611 + vertex 0.875502 1.12246 2.56123 + vertex 0.874477 1.1215 2.55941 + endloop + endfacet + facet normal -0.488706 -0.660785 0.569675 + outer loop + vertex 0.87832 1.118 2.55866 + vertex 0.877256 1.12089 2.5611 + vertex 0.874477 1.1215 2.55941 + endloop + endfacet + facet normal -0.528007 -0.68844 0.497251 + outer loop + vertex 0.87832 1.118 2.55866 + vertex 0.874477 1.1215 2.55941 + vertex 0.873647 1.11989 2.5563 + endloop + endfacet + facet normal -0.465722 -0.850575 0.244183 + outer loop + vertex 0.87832 1.118 2.55866 + vertex 0.873647 1.11989 2.5563 + vertex 0.876937 1.11795 2.55583 + endloop + endfacet + facet normal -0.532017 -0.643482 0.550353 + outer loop + vertex 0.877256 1.12089 2.5611 + vertex 0.876814 1.12323 2.56341 + vertex 0.875502 1.12246 2.56123 + endloop + endfacet + facet normal -0.412499 -0.688434 0.596576 + outer loop + vertex 0.874477 1.1215 2.55941 + vertex 0.875502 1.12246 2.56123 + vertex 0.87251 1.12443 2.56144 + endloop + endfacet + facet normal -0.486892 -0.595768 0.638747 + outer loop + vertex 0.876835 1.12564 2.56586 + vertex 0.875397 1.12724 2.56626 + vertex 0.874093 1.12631 2.56441 + endloop + endfacet + facet normal -0.481266 -0.625112 0.614506 + outer loop + vertex 0.876814 1.12323 2.56341 + vertex 0.876835 1.12564 2.56586 + vertex 0.874093 1.12631 2.56441 + endloop + endfacet + facet normal -0.462683 -0.616139 0.637414 + outer loop + vertex 0.876814 1.12323 2.56341 + vertex 0.874093 1.12631 2.56441 + vertex 0.87251 1.12443 2.56144 + endloop + endfacet + facet normal -0.442491 -0.726501 0.525735 + outer loop + vertex 0.876814 1.12323 2.56341 + vertex 0.87251 1.12443 2.56144 + vertex 0.875502 1.12246 2.56123 + endloop + endfacet + facet normal -0.558079 -0.633958 0.535392 + outer loop + vertex 0.876835 1.12564 2.56586 + vertex 0.876655 1.12789 2.56835 + vertex 0.875397 1.12724 2.56626 + endloop + endfacet + facet normal -0.426403 -0.653759 0.625124 + outer loop + vertex 0.874093 1.12631 2.56441 + vertex 0.875397 1.12724 2.56626 + vertex 0.872435 1.12944 2.56655 + endloop + endfacet + facet normal -0.539972 -0.589136 0.601122 + outer loop + vertex 0.87713 1.1303 2.57154 + vertex 0.875299 1.13382 2.57334 + vertex 0.873756 1.13171 2.56988 + endloop + endfacet + facet normal -0.536925 -0.632765 0.557961 + outer loop + vertex 0.876655 1.12789 2.56835 + vertex 0.87713 1.1303 2.57154 + vertex 0.873756 1.13171 2.56988 + endloop + endfacet + facet normal -0.489524 -0.619252 0.613916 + outer loop + vertex 0.876655 1.12789 2.56835 + vertex 0.873756 1.13171 2.56988 + vertex 0.872435 1.12944 2.56655 + endloop + endfacet + facet normal -0.480187 -0.711638 0.512827 + outer loop + vertex 0.876655 1.12789 2.56835 + vertex 0.872435 1.12944 2.56655 + vertex 0.875397 1.12724 2.56626 + endloop + endfacet + facet normal -0.617776 -0.588767 0.521255 + outer loop + vertex 0.879486 1.13065 2.57472 + vertex 0.875299 1.13382 2.57334 + vertex 0.87713 1.1303 2.57154 + endloop + endfacet + facet normal -0.596999 -0.523728 0.607702 + outer loop + vertex 0.877634 1.13437 2.57611 + vertex 0.875299 1.13382 2.57334 + vertex 0.879486 1.13065 2.57472 + endloop + endfacet + facet normal -0.630312 -0.526446 0.570579 + outer loop + vertex 0.879486 1.13065 2.57472 + vertex 0.880752 1.13289 2.57819 + vertex 0.877634 1.13437 2.57611 + endloop + endfacet + facet normal -0.522512 -0.603623 0.60218 + outer loop + vertex 0.873756 1.13171 2.56988 + vertex 0.875299 1.13382 2.57334 + vertex 0.871134 1.13537 2.57128 + endloop + endfacet + facet normal -0.526283 -0.522212 0.671059 + outer loop + vertex 0.872086 1.13774 2.57387 + vertex 0.871134 1.13537 2.57128 + vertex 0.875299 1.13382 2.57334 + endloop + endfacet + facet normal -0.553895 -0.539836 0.633859 + outer loop + vertex 0.872086 1.13774 2.57387 + vertex 0.875299 1.13382 2.57334 + vertex 0.875142 1.13668 2.57564 + endloop + endfacet + facet normal -0.598171 -0.521706 0.608288 + outer loop + vertex 0.875142 1.13668 2.57564 + vertex 0.875299 1.13382 2.57334 + vertex 0.877634 1.13437 2.57611 + endloop + endfacet + facet normal -0.578625 -0.492164 0.650359 + outer loop + vertex 0.877634 1.13437 2.57611 + vertex 0.877559 1.13755 2.57845 + vertex 0.875142 1.13668 2.57564 + endloop + endfacet + facet normal -0.633194 -0.468341 0.616216 + outer loop + vertex 0.880752 1.13289 2.57819 + vertex 0.877559 1.13755 2.57845 + vertex 0.877634 1.13437 2.57611 + endloop + endfacet + facet normal -0.558526 -0.472069 0.682055 + outer loop + vertex 0.872086 1.13774 2.57387 + vertex 0.875142 1.13668 2.57564 + vertex 0.873066 1.14005 2.57628 + endloop + endfacet + facet normal -0.570149 -0.400752 0.717166 + outer loop + vertex 0.877559 1.13755 2.57845 + vertex 0.874104 1.14292 2.5787 + vertex 0.873066 1.14005 2.57628 + endloop + endfacet + facet normal -0.58445 -0.482483 0.652402 + outer loop + vertex 0.877559 1.13755 2.57845 + vertex 0.873066 1.14005 2.57628 + vertex 0.875142 1.13668 2.57564 + endloop + endfacet + facet normal -0.570885 -0.257299 0.779671 + outer loop + vertex 0.872982 1.15772 2.58359 + vertex 0.87502 1.15265 2.58341 + vertex 0.876995 1.15491 2.5856 + endloop + endfacet + facet normal -0.566646 -0.0263965 0.823539 + outer loop + vertex 0.878 1.19562 2.59527 + vertex 0.877853 1.19868 2.59526 + vertex 0.874928 1.19712 2.5932 + endloop + endfacet + facet normal -0.580093 -0.0703596 0.811506 + outer loop + vertex 0.878 1.19562 2.59527 + vertex 0.874928 1.19712 2.5932 + vertex 0.877227 1.19174 2.59438 + endloop + endfacet + facet normal -0.552729 -0.0542907 0.831591 + outer loop + vertex 0.877227 1.19174 2.59438 + vertex 0.874928 1.19712 2.5932 + vertex 0.874063 1.19209 2.5923 + endloop + endfacet + facet normal -0.546436 -0.012611 0.837406 + outer loop + vertex 0.877853 1.19868 2.59526 + vertex 0.87935 1.20094 2.59627 + vertex 0.876643 1.20241 2.59453 + endloop + endfacet + facet normal -0.568083 -0.0225293 0.822663 + outer loop + vertex 0.877853 1.19868 2.59526 + vertex 0.876643 1.20241 2.59453 + vertex 0.874928 1.19712 2.5932 + endloop + endfacet + facet normal -0.552037 -0.0303972 0.833265 + outer loop + vertex 0.874928 1.19712 2.5932 + vertex 0.876643 1.20241 2.59453 + vertex 0.873514 1.20225 2.59245 + endloop + endfacet + facet normal -0.541997 -0.0168011 0.840213 + outer loop + vertex 0.87935 1.20094 2.59627 + vertex 0.877853 1.19868 2.59526 + vertex 0.880619 1.19719 2.59702 + endloop + endfacet + facet normal -0.492076 -0.102632 0.864481 + outer loop + vertex 0.87487 1.27366 2.60594 + vertex 0.875896 1.27774 2.60701 + vertex 0.872914 1.27601 2.60511 + endloop + endfacet + facet normal -0.530632 0.0634701 0.845222 + outer loop + vertex 0.873507 1.7662 2.60329 + vertex 0.872645 1.76058 2.60317 + vertex 0.876397 1.76389 2.60528 + endloop + endfacet + facet normal -0.535729 0.0548167 0.842609 + outer loop + vertex 0.876851 1.76884 2.60524 + vertex 0.873507 1.7662 2.60329 + vertex 0.876397 1.76389 2.60528 + endloop + endfacet + facet normal -0.516164 0.0531006 0.854842 + outer loop + vertex 0.876397 1.76389 2.60528 + vertex 0.879717 1.76699 2.60709 + vertex 0.876851 1.76884 2.60524 + endloop + endfacet + facet normal -0.518944 0.0572236 0.85289 + outer loop + vertex 0.879501 1.76209 2.60729 + vertex 0.879717 1.76699 2.60709 + vertex 0.876397 1.76389 2.60528 + endloop + endfacet + facet normal -0.536953 0.0570472 0.841681 + outer loop + vertex 0.874322 1.77188 2.60342 + vertex 0.873507 1.7662 2.60329 + vertex 0.876851 1.76884 2.60524 + endloop + endfacet + facet normal -0.533489 0.0610872 0.843598 + outer loop + vertex 0.877476 1.77266 2.60536 + vertex 0.874322 1.77188 2.60342 + vertex 0.876851 1.76884 2.60524 + endloop + endfacet + facet normal -0.508284 0.0564629 0.859336 + outer loop + vertex 0.876851 1.76884 2.60524 + vertex 0.87992 1.77164 2.60687 + vertex 0.877476 1.77266 2.60536 + endloop + endfacet + facet normal -0.511832 0.0618099 0.856859 + outer loop + vertex 0.879717 1.76699 2.60709 + vertex 0.87992 1.77164 2.60687 + vertex 0.876851 1.76884 2.60524 + endloop + endfacet + facet normal -0.521883 0.161002 0.837685 + outer loop + vertex 0.875057 1.78889 2.60142 + vertex 0.871725 1.78608 2.59989 + vertex 0.874078 1.78512 2.60154 + endloop + endfacet + facet normal -0.520519 0.158673 0.838977 + outer loop + vertex 0.872218 1.79065 2.59933 + vertex 0.871725 1.78608 2.59989 + vertex 0.875057 1.78889 2.60142 + endloop + endfacet + facet normal -0.58217 0.296563 0.757052 + outer loop + vertex 0.87702 1.86721 2.58571 + vertex 0.879457 1.86975 2.58659 + vertex 0.876975 1.87038 2.58443 + endloop + endfacet + facet normal -0.58318 0.29628 0.756385 + outer loop + vertex 0.87702 1.86721 2.58571 + vertex 0.876975 1.87038 2.58443 + vertex 0.87324 1.8661 2.58323 + endloop + endfacet + facet normal -0.60255 0.320367 0.730957 + outer loop + vertex 0.87324 1.8661 2.58323 + vertex 0.876975 1.87038 2.58443 + vertex 0.873993 1.87128 2.58158 + endloop + endfacet + facet normal -0.547915 0.249504 0.798459 + outer loop + vertex 0.879457 1.86975 2.58659 + vertex 0.87702 1.86721 2.58571 + vertex 0.879363 1.86647 2.58755 + endloop + endfacet + facet normal -0.600589 0.406735 0.688374 + outer loop + vertex 0.875524 1.87823 2.57904 + vertex 0.873603 1.87765 2.5777 + vertex 0.873887 1.87528 2.57935 + endloop + endfacet + facet normal -0.597436 0.405361 0.69192 + outer loop + vertex 0.873887 1.87528 2.57935 + vertex 0.877247 1.87503 2.5824 + vertex 0.875524 1.87823 2.57904 + endloop + endfacet + facet normal -0.607494 0.374575 0.700461 + outer loop + vertex 0.873887 1.87528 2.57935 + vertex 0.873993 1.87128 2.58158 + vertex 0.877247 1.87503 2.5824 + endloop + endfacet + facet normal -0.589037 0.352709 0.72707 + outer loop + vertex 0.873993 1.87128 2.58158 + vertex 0.876975 1.87038 2.58443 + vertex 0.877247 1.87503 2.5824 + endloop + endfacet + facet normal -0.597037 0.441849 0.669565 + outer loop + vertex 0.876122 1.88239 2.5769 + vertex 0.873552 1.88239 2.57461 + vertex 0.873516 1.88002 2.57614 + endloop + endfacet + facet normal -0.599254 0.424729 0.678601 + outer loop + vertex 0.873516 1.88002 2.57614 + vertex 0.873603 1.87765 2.5777 + vertex 0.875524 1.87823 2.57904 + endloop + endfacet + facet normal -0.592263 0.433506 0.679188 + outer loop + vertex 0.876122 1.88239 2.5769 + vertex 0.873516 1.88002 2.57614 + vertex 0.875524 1.87823 2.57904 + endloop + endfacet + facet normal -0.620539 0.426672 0.657937 + outer loop + vertex 0.876122 1.88239 2.5769 + vertex 0.875524 1.87823 2.57904 + vertex 0.878374 1.87961 2.58082 + endloop + endfacet + facet normal -0.636763 0.408172 0.654163 + outer loop + vertex 0.876122 1.88239 2.5769 + vertex 0.878374 1.87961 2.58082 + vertex 0.87871 1.88228 2.57949 + endloop + endfacet + facet normal -0.617862 0.386696 0.684626 + outer loop + vertex 0.878374 1.87961 2.58082 + vertex 0.875524 1.87823 2.57904 + vertex 0.877247 1.87503 2.5824 + endloop + endfacet + facet normal -0.583928 0.479811 0.654836 + outer loop + vertex 0.873635 1.8848 2.57292 + vertex 0.873552 1.88239 2.57461 + vertex 0.876122 1.88239 2.5769 + endloop + endfacet + facet normal -0.57844 0.485991 0.655149 + outer loop + vertex 0.876399 1.88692 2.57378 + vertex 0.873635 1.8848 2.57292 + vertex 0.876122 1.88239 2.5769 + endloop + endfacet + facet normal -0.630464 0.465688 0.621007 + outer loop + vertex 0.876122 1.88239 2.5769 + vertex 0.878865 1.88495 2.57777 + vertex 0.876399 1.88692 2.57378 + endloop + endfacet + facet normal -0.62192 0.449732 0.641059 + outer loop + vertex 0.87871 1.88228 2.57949 + vertex 0.878865 1.88495 2.57777 + vertex 0.876122 1.88239 2.5769 + endloop + endfacet + facet normal -0.526092 0.665931 0.528926 + outer loop + vertex 0.874415 1.89395 2.56443 + vertex 0.871413 1.89224 2.56359 + vertex 0.873301 1.89117 2.56681 + endloop + endfacet + facet normal -0.569062 0.655407 0.496599 + outer loop + vertex 0.876877 1.8919 2.56995 + vertex 0.874415 1.89395 2.56443 + vertex 0.873301 1.89117 2.56681 + endloop + endfacet + facet normal -0.605748 0.565916 0.559293 + outer loop + vertex 0.873579 1.88843 2.56989 + vertex 0.876877 1.8919 2.56995 + vertex 0.873301 1.89117 2.56681 + endloop + endfacet + facet normal -0.589133 0.512227 0.624936 + outer loop + vertex 0.873579 1.88843 2.56989 + vertex 0.873635 1.8848 2.57292 + vertex 0.876399 1.88692 2.57378 + endloop + endfacet + facet normal -0.573109 0.533873 0.621712 + outer loop + vertex 0.876877 1.8919 2.56995 + vertex 0.873579 1.88843 2.56989 + vertex 0.876399 1.88692 2.57378 + endloop + endfacet + facet normal -0.638293 0.507254 0.57903 + outer loop + vertex 0.876877 1.8919 2.56995 + vertex 0.876399 1.88692 2.57378 + vertex 0.879056 1.88896 2.57493 + endloop + endfacet + facet normal -0.690866 0.448321 0.567197 + outer loop + vertex 0.876877 1.8919 2.56995 + vertex 0.879056 1.88896 2.57493 + vertex 0.879229 1.89152 2.57311 + endloop + endfacet + facet normal -0.62752 0.469535 0.621092 + outer loop + vertex 0.879056 1.88896 2.57493 + vertex 0.876399 1.88692 2.57378 + vertex 0.878865 1.88495 2.57777 + endloop + endfacet + facet normal -0.572232 0.747355 0.337656 + outer loop + vertex 0.874111 1.89895 2.55465 + vertex 0.871704 1.8977 2.55334 + vertex 0.872037 1.8964 2.55678 + endloop + endfacet + facet normal -0.582038 0.745172 0.325501 + outer loop + vertex 0.875038 1.89738 2.55991 + vertex 0.874111 1.89895 2.55465 + vertex 0.872037 1.8964 2.55678 + endloop + endfacet + facet normal -0.601845 0.716062 0.353608 + outer loop + vertex 0.872049 1.89453 2.56059 + vertex 0.875038 1.89738 2.55991 + vertex 0.872037 1.8964 2.55678 + endloop + endfacet + facet normal -0.533398 0.723203 0.438708 + outer loop + vertex 0.872049 1.89453 2.56059 + vertex 0.871413 1.89224 2.56359 + vertex 0.874415 1.89395 2.56443 + endloop + endfacet + facet normal -0.559917 0.695189 0.450783 + outer loop + vertex 0.872049 1.89453 2.56059 + vertex 0.874415 1.89395 2.56443 + vertex 0.875038 1.89738 2.55991 + endloop + endfacet + facet normal -0.713712 0.601717 0.358541 + outer loop + vertex 0.875038 1.89738 2.55991 + vertex 0.874415 1.89395 2.56443 + vertex 0.877287 1.89691 2.56517 + endloop + endfacet + facet normal -0.695477 0.475875 0.538382 + outer loop + vertex 0.878825 1.89574 2.56907 + vertex 0.876877 1.8919 2.56995 + vertex 0.879524 1.89367 2.5718 + endloop + endfacet + facet normal -0.754634 0.484075 0.442944 + outer loop + vertex 0.878825 1.89574 2.56907 + vertex 0.877287 1.89691 2.56517 + vertex 0.876877 1.8919 2.56995 + endloop + endfacet + facet normal -0.680825 0.533849 0.501481 + outer loop + vertex 0.877287 1.89691 2.56517 + vertex 0.874415 1.89395 2.56443 + vertex 0.876877 1.8919 2.56995 + endloop + endfacet + facet normal -0.693893 0.441743 0.568661 + outer loop + vertex 0.879524 1.89367 2.5718 + vertex 0.876877 1.8919 2.56995 + vertex 0.879229 1.89152 2.57311 + endloop + endfacet + facet normal -0.555978 0.441547 0.704219 + outer loop + vertex 0.876032 1.90313 2.55167 + vertex 0.875405 1.905 2.55 + vertex 0.875 1.90449 2.55 + endloop + endfacet + facet normal -0.53841 0.458379 0.707109 + outer loop + vertex 0.872734 1.90027 2.55101 + vertex 0.876032 1.90313 2.55167 + vertex 0.875 1.90449 2.55 + endloop + endfacet + facet normal -0.594012 0.657811 0.46307 + outer loop + vertex 0.872734 1.90027 2.55101 + vertex 0.871704 1.8977 2.55334 + vertex 0.874111 1.89895 2.55465 + endloop + endfacet + facet normal -0.631103 0.621632 0.463985 + outer loop + vertex 0.872734 1.90027 2.55101 + vertex 0.874111 1.89895 2.55465 + vertex 0.876032 1.90313 2.55167 + endloop + endfacet + facet normal -0.757277 0.57264 0.314031 + outer loop + vertex 0.876032 1.90313 2.55167 + vertex 0.874111 1.89895 2.55465 + vertex 0.876977 1.90181 2.55634 + endloop + endfacet + facet normal -0.757104 0.577129 0.30613 + outer loop + vertex 0.874111 1.89895 2.55465 + vertex 0.875038 1.89738 2.55991 + vertex 0.876977 1.90181 2.55634 + endloop + endfacet + facet normal -0.777936 0.563536 0.277926 + outer loop + vertex 0.876977 1.90181 2.55634 + vertex 0.875038 1.89738 2.55991 + vertex 0.877757 1.90061 2.56096 + endloop + endfacet + facet normal -0.795191 0.446961 0.409754 + outer loop + vertex 0.878765 1.9004 2.56424 + vertex 0.877287 1.89691 2.56517 + vertex 0.87927 1.89867 2.5671 + endloop + endfacet + facet normal -0.85054 0.438405 0.290486 + outer loop + vertex 0.878765 1.9004 2.56424 + vertex 0.877757 1.90061 2.56096 + vertex 0.877287 1.89691 2.56517 + endloop + endfacet + facet normal -0.766212 0.522602 0.373906 + outer loop + vertex 0.877757 1.90061 2.56096 + vertex 0.875038 1.89738 2.55991 + vertex 0.877287 1.89691 2.56517 + endloop + endfacet + facet normal -0.796277 0.416147 0.43905 + outer loop + vertex 0.87927 1.89867 2.5671 + vertex 0.877287 1.89691 2.56517 + vertex 0.878825 1.89574 2.56907 + endloop + endfacet + facet normal -0.824156 0.566036 0.0192439 + outer loop + vertex 0.88 1.90896 2.55 + vertex 0.876032 1.90313 2.55167 + vertex 0.88 1.90879 2.555 + endloop + endfacet + facet normal -0.44021 0.510795 0.738447 + outer loop + vertex 0.875405 1.905 2.55 + vertex 0.876032 1.90313 2.55167 + vertex 0.88 1.90896 2.55 + endloop + endfacet + facet normal -0.837399 0.428192 0.339727 + outer loop + vertex 0.88 1.90879 2.555 + vertex 0.876977 1.90181 2.55634 + vertex 0.879165 1.9048 2.55797 + endloop + endfacet + facet normal -0.855459 0.427034 0.292971 + outer loop + vertex 0.876032 1.90313 2.55167 + vertex 0.876977 1.90181 2.55634 + vertex 0.88 1.90879 2.555 + endloop + endfacet + facet normal -0.861519 0.453172 0.228956 + outer loop + vertex 0.879165 1.9048 2.55797 + vertex 0.877757 1.90061 2.56096 + vertex 0.879318 1.90311 2.56189 + endloop + endfacet + facet normal -0.841006 0.471818 0.264759 + outer loop + vertex 0.876977 1.90181 2.55634 + vertex 0.877757 1.90061 2.56096 + vertex 0.879165 1.9048 2.55797 + endloop + endfacet + facet normal -0.856184 0.42663 0.291439 + outer loop + vertex 0.879318 1.90311 2.56189 + vertex 0.877757 1.90061 2.56096 + vertex 0.878765 1.9004 2.56424 + endloop + endfacet + facet normal 0.601765 -0.525872 -0.601113 + outer loop + vertex 0.875769 2.075 2.425 + vertex 0.875 2.07412 2.425 + vertex 0.875 2.075 2.42423 + endloop + endfacet + facet normal 0.733348 -0.64086 -0.226937 + outer loop + vertex 0.875382 2.07432 2.42568 + vertex 0.875 2.07412 2.425 + vertex 0.875769 2.075 2.425 + endloop + endfacet + facet normal 0.818527 -0.4746 -0.32368 + outer loop + vertex 0.875 2.07071 2.43 + vertex 0.875 2.07412 2.425 + vertex 0.875382 2.07432 2.42568 + endloop + endfacet + facet normal 0.997359 -0.063666 0.0349631 + outer loop + vertex 0.875188 2.0734 2.42954 + vertex 0.875 2.07071 2.43 + vertex 0.875382 2.07432 2.42568 + endloop + endfacet + facet normal 0.99758 -0.0695281 0.000696242 + outer loop + vertex 0.875 2.07076 2.435 + vertex 0.875 2.07071 2.43 + vertex 0.875188 2.0734 2.42954 + endloop + endfacet + facet normal 0.99931 -0.0319538 0.018944 + outer loop + vertex 0.87508 2.07295 2.43445 + vertex 0.875 2.07076 2.435 + vertex 0.875188 2.0734 2.42954 + endloop + endfacet + facet normal 0.961564 0.0330032 0.272591 + outer loop + vertex 0.874096 2.06916 2.43838 + vertex 0.875 2.07076 2.435 + vertex 0.87508 2.07295 2.43445 + endloop + endfacet + facet normal 0.977065 -0.208378 0.0438487 + outer loop + vertex 0.874804 2.07272 2.43951 + vertex 0.874096 2.06916 2.43838 + vertex 0.87508 2.07295 2.43445 + endloop + endfacet + facet normal 0.971918 -0.219963 0.0836185 + outer loop + vertex 0.873691 2.06921 2.44323 + vertex 0.874096 2.06916 2.43838 + vertex 0.874804 2.07272 2.43951 + endloop + endfacet + facet normal 0.975911 -0.181407 0.1212 + outer loop + vertex 0.874301 2.07301 2.44401 + vertex 0.873691 2.06921 2.44323 + vertex 0.874804 2.07272 2.43951 + endloop + endfacet + facet normal 0.965612 -0.19107 0.176314 + outer loop + vertex 0.873243 2.0702 2.44675 + vertex 0.873691 2.06921 2.44323 + vertex 0.874301 2.07301 2.44401 + endloop + endfacet + facet normal 0.961188 -0.11778 0.249491 + outer loop + vertex 0.874301 2.07301 2.44401 + vertex 0.873383 2.07368 2.44786 + vertex 0.873243 2.0702 2.44675 + endloop + endfacet + facet normal 0.919437 -0.355832 0.167388 + outer loop + vertex 0.875769 2.075 2.425 + vertex 0.877704 2.08 2.425 + vertex 0.875382 2.07432 2.42568 + endloop + endfacet + facet normal 0.829648 -0.281715 0.481997 + outer loop + vertex 0.877704 2.08 2.425 + vertex 0.876251 2.07808 2.42638 + vertex 0.875382 2.07432 2.42568 + endloop + endfacet + facet normal 0.974557 -0.224101 -0.00416659 + outer loop + vertex 0.875382 2.07432 2.42568 + vertex 0.876251 2.07808 2.42638 + vertex 0.875188 2.0734 2.42954 + endloop + endfacet + facet normal 0.977208 -0.21175 0.0150216 + outer loop + vertex 0.876251 2.07808 2.42638 + vertex 0.876014 2.0773 2.4307 + vertex 0.875188 2.0734 2.42954 + endloop + endfacet + facet normal 0.978107 -0.208094 0.00210487 + outer loop + vertex 0.875188 2.0734 2.42954 + vertex 0.876014 2.0773 2.4307 + vertex 0.87508 2.07295 2.43445 + endloop + endfacet + facet normal 0.981076 -0.192488 0.0209475 + outer loop + vertex 0.876014 2.0773 2.4307 + vertex 0.875829 2.0769 2.43573 + vertex 0.87508 2.07295 2.43445 + endloop + endfacet + facet normal 0.978872 -0.19961 0.0443459 + outer loop + vertex 0.87508 2.07295 2.43445 + vertex 0.875829 2.0769 2.43573 + vertex 0.874804 2.07272 2.43951 + endloop + endfacet + facet normal 0.982975 -0.161543 0.0875397 + outer loop + vertex 0.875829 2.0769 2.43573 + vertex 0.875398 2.07684 2.44045 + vertex 0.874804 2.07272 2.43951 + endloop + endfacet + facet normal 0.978302 -0.168457 0.120615 + outer loop + vertex 0.874804 2.07272 2.43951 + vertex 0.875398 2.07684 2.44045 + vertex 0.874301 2.07301 2.44401 + endloop + endfacet + facet normal 0.977052 -0.111715 0.181354 + outer loop + vertex 0.875398 2.07684 2.44045 + vertex 0.874658 2.07727 2.44471 + vertex 0.874301 2.07301 2.44401 + endloop + endfacet + facet normal 0.960567 -0.121667 0.250017 + outer loop + vertex 0.874658 2.07727 2.44471 + vertex 0.873383 2.07368 2.44786 + vertex 0.874301 2.07301 2.44401 + endloop + endfacet + facet normal 0.949331 -0.0678508 0.306866 + outer loop + vertex 0.873482 2.07826 2.44857 + vertex 0.873383 2.07368 2.44786 + vertex 0.874658 2.07727 2.44471 + endloop + endfacet + facet normal 0.703519 -0.0215279 0.71035 + outer loop + vertex 0.877704 2.08 2.425 + vertex 0.877857 2.085 2.425 + vertex 0.876251 2.07808 2.42638 + endloop + endfacet + facet normal 0.971715 -0.200852 0.124208 + outer loop + vertex 0.877857 2.085 2.425 + vertex 0.877112 2.08283 2.42731 + vertex 0.876251 2.07808 2.42638 + endloop + endfacet + facet normal 0.982975 -0.182578 0.0206428 + outer loop + vertex 0.876251 2.07808 2.42638 + vertex 0.877112 2.08283 2.42731 + vertex 0.876014 2.0773 2.4307 + endloop + endfacet + facet normal 0.981834 -0.18953 0.00893671 + outer loop + vertex 0.877112 2.08283 2.42731 + vertex 0.876863 2.08175 2.43185 + vertex 0.876014 2.0773 2.4307 + endloop + endfacet + facet normal 0.981078 -0.192475 0.0209486 + outer loop + vertex 0.876014 2.0773 2.4307 + vertex 0.876863 2.08175 2.43185 + vertex 0.875829 2.0769 2.43573 + endloop + endfacet + facet normal 0.985029 -0.161182 0.0611421 + outer loop + vertex 0.876863 2.08175 2.43185 + vertex 0.876479 2.08118 2.43652 + vertex 0.875829 2.0769 2.43573 + endloop + endfacet + facet normal 0.982299 -0.165667 0.0874254 + outer loop + vertex 0.875829 2.0769 2.43573 + vertex 0.876479 2.08118 2.43652 + vertex 0.875398 2.07684 2.44045 + endloop + endfacet + facet normal 0.98321 -0.122876 0.134906 + outer loop + vertex 0.876479 2.08118 2.43652 + vertex 0.8759 2.08133 2.44089 + vertex 0.875398 2.07684 2.44045 + endloop + endfacet + facet normal 0.975025 -0.126542 0.18252 + outer loop + vertex 0.875398 2.07684 2.44045 + vertex 0.8759 2.08133 2.44089 + vertex 0.874658 2.07727 2.44471 + endloop + endfacet + facet normal 0.969629 -0.0787058 0.231571 + outer loop + vertex 0.8759 2.08133 2.44089 + vertex 0.874954 2.082 2.44508 + vertex 0.874658 2.07727 2.44471 + endloop + endfacet + facet normal 0.947028 -0.0833943 0.310134 + outer loop + vertex 0.874954 2.082 2.44508 + vertex 0.873482 2.07826 2.44857 + vertex 0.874658 2.07727 2.44471 + endloop + endfacet + facet normal 0.936403 -0.0437649 0.348186 + outer loop + vertex 0.873572 2.08337 2.44896 + vertex 0.873482 2.07826 2.44857 + vertex 0.874954 2.082 2.44508 + endloop + endfacet + facet normal 0.968228 -0.0797815 0.236999 + outer loop + vertex 0.877857 2.085 2.425 + vertex 0.878269 2.09 2.425 + vertex 0.877112 2.08283 2.42731 + endloop + endfacet + facet normal 0.975391 -0.192134 -0.108154 + outer loop + vertex 0.878269 2.09 2.425 + vertex 0.87823 2.08808 2.42805 + vertex 0.877112 2.08283 2.42731 + endloop + endfacet + facet normal 0.978002 -0.208553 0.00422093 + outer loop + vertex 0.877112 2.08283 2.42731 + vertex 0.87823 2.08808 2.42805 + vertex 0.876863 2.08175 2.43185 + endloop + endfacet + facet normal 0.981007 -0.190797 0.0349573 + outer loop + vertex 0.87823 2.08808 2.42805 + vertex 0.87749 2.08518 2.43297 + vertex 0.876863 2.08175 2.43185 + endloop + endfacet + facet normal 0.978727 -0.197321 0.0561941 + outer loop + vertex 0.876863 2.08175 2.43185 + vertex 0.87749 2.08518 2.43297 + vertex 0.876479 2.08118 2.43652 + endloop + endfacet + facet normal 0.981512 -0.17028 0.0874032 + outer loop + vertex 0.87749 2.08518 2.43297 + vertex 0.877215 2.08556 2.43679 + vertex 0.876479 2.08118 2.43652 + endloop + endfacet + facet normal 0.975668 -0.172233 0.135672 + outer loop + vertex 0.876479 2.08118 2.43652 + vertex 0.877215 2.08556 2.43679 + vertex 0.8759 2.08133 2.44089 + endloop + endfacet + facet normal 0.974894 -0.12454 0.184584 + outer loop + vertex 0.877215 2.08556 2.43679 + vertex 0.876419 2.08592 2.44124 + vertex 0.8759 2.08133 2.44089 + endloop + endfacet + facet normal 0.962925 -0.127336 0.237824 + outer loop + vertex 0.8759 2.08133 2.44089 + vertex 0.876419 2.08592 2.44124 + vertex 0.874954 2.082 2.44508 + endloop + endfacet + facet normal 0.954095 -0.0724262 0.290616 + outer loop + vertex 0.876419 2.08592 2.44124 + vertex 0.875206 2.08689 2.44547 + vertex 0.874954 2.082 2.44508 + endloop + endfacet + facet normal 0.930684 -0.0765938 0.357715 + outer loop + vertex 0.875206 2.08689 2.44547 + vertex 0.873572 2.08337 2.44896 + vertex 0.874954 2.082 2.44508 + endloop + endfacet + facet normal 0.938777 -0.11206 0.325791 + outer loop + vertex 0.873939 2.08927 2.44994 + vertex 0.873572 2.08337 2.44896 + vertex 0.875206 2.08689 2.44547 + endloop + endfacet + facet normal 0.957944 -0.27657 -0.0764982 + outer loop + vertex 0.879245 2.09226 2.42568 + vertex 0.879166 2.09136 2.42792 + vertex 0.87823 2.08808 2.42805 + endloop + endfacet + facet normal -0.959393 0.27324 0.0700348 + outer loop + vertex 0.879245 2.09226 2.42568 + vertex 0.87823 2.08808 2.42805 + vertex 0.879977 2.095 2.425 + endloop + endfacet + facet normal 0.929553 -0.317523 -0.18738 + outer loop + vertex 0.879977 2.095 2.425 + vertex 0.87823 2.08808 2.42805 + vertex 0.878269 2.09 2.425 + endloop + endfacet + facet normal 0.959539 -0.28143 0.00907121 + outer loop + vertex 0.879166 2.09136 2.42792 + vertex 0.87966 2.09309 2.42942 + vertex 0.878588 2.08952 2.4321 + endloop + endfacet + facet normal 0.961631 -0.274057 0.0126086 + outer loop + vertex 0.879166 2.09136 2.42792 + vertex 0.878588 2.08952 2.4321 + vertex 0.87823 2.08808 2.42805 + endloop + endfacet + facet normal 0.969621 -0.244609 0.00141407 + outer loop + vertex 0.87823 2.08808 2.42805 + vertex 0.878588 2.08952 2.4321 + vertex 0.87749 2.08518 2.43297 + endloop + endfacet + facet normal 0.969659 -0.226444 0.0921131 + outer loop + vertex 0.87749 2.08518 2.43297 + vertex 0.878588 2.08952 2.4321 + vertex 0.877215 2.08556 2.43679 + endloop + endfacet + facet normal 0.974241 -0.185809 0.127791 + outer loop + vertex 0.878588 2.08952 2.4321 + vertex 0.878058 2.09046 2.43749 + vertex 0.877215 2.08556 2.43679 + endloop + endfacet + facet normal 0.963105 -0.192521 0.188056 + outer loop + vertex 0.877215 2.08556 2.43679 + vertex 0.878058 2.09046 2.43749 + vertex 0.876419 2.08592 2.44124 + endloop + endfacet + facet normal 0.955466 -0.123609 0.267966 + outer loop + vertex 0.878058 2.09046 2.43749 + vertex 0.876678 2.08992 2.44216 + vertex 0.876419 2.08592 2.44124 + endloop + endfacet + facet normal 0.944584 -0.130529 0.301204 + outer loop + vertex 0.876419 2.08592 2.44124 + vertex 0.876678 2.08992 2.44216 + vertex 0.875206 2.08689 2.44547 + endloop + endfacet + facet normal 0.942945 -0.119127 0.310908 + outer loop + vertex 0.876678 2.08992 2.44216 + vertex 0.875616 2.09206 2.4462 + vertex 0.875206 2.08689 2.44547 + endloop + endfacet + facet normal 0.93617 -0.121293 0.329961 + outer loop + vertex 0.875616 2.09206 2.4462 + vertex 0.873939 2.08927 2.44994 + vertex 0.875206 2.08689 2.44547 + endloop + endfacet + facet normal 0.93385 -0.299322 0.195781 + outer loop + vertex 0.875 2.095 2.45364 + vertex 0.873939 2.08927 2.44994 + vertex 0.875616 2.09206 2.4462 + endloop + endfacet + facet normal 0.419697 -0.321435 -0.848843 + outer loop + vertex 0.88 2.09503 2.425 + vertex 0.879245 2.09226 2.42568 + vertex 0.879977 2.095 2.425 + endloop + endfacet + facet normal 0.969235 -0.234081 0.0760924 + outer loop + vertex 0.87966 2.09309 2.42942 + vertex 0.879479 2.09354 2.43308 + vertex 0.878588 2.08952 2.4321 + endloop + endfacet + facet normal 0.965309 -0.191498 0.177501 + outer loop + vertex 0.879479 2.09354 2.43308 + vertex 0.87904 2.09483 2.43687 + vertex 0.878058 2.09046 2.43749 + endloop + endfacet + facet normal 0.959331 -0.246868 0.136893 + outer loop + vertex 0.878588 2.08952 2.4321 + vertex 0.879479 2.09354 2.43308 + vertex 0.878058 2.09046 2.43749 + endloop + endfacet + facet normal 0.946466 -0.162958 0.278653 + outer loop + vertex 0.87904 2.09483 2.43687 + vertex 0.879095 2.09931 2.4393 + vertex 0.877724 2.09521 2.44156 + endloop + endfacet + facet normal 0.944716 -0.172368 0.278927 + outer loop + vertex 0.87904 2.09483 2.43687 + vertex 0.877724 2.09521 2.44156 + vertex 0.878058 2.09046 2.43749 + endloop + endfacet + facet normal 0.951779 -0.15814 0.262886 + outer loop + vertex 0.878058 2.09046 2.43749 + vertex 0.877724 2.09521 2.44156 + vertex 0.876678 2.08992 2.44216 + endloop + endfacet + facet normal 0.934491 -0.147779 0.323863 + outer loop + vertex 0.876678 2.08992 2.44216 + vertex 0.877724 2.09521 2.44156 + vertex 0.875616 2.09206 2.4462 + endloop + endfacet + facet normal 0.935312 -0.162148 0.314484 + outer loop + vertex 0.877724 2.09521 2.44156 + vertex 0.87624 2.09802 2.44742 + vertex 0.875616 2.09206 2.4462 + endloop + endfacet + facet normal 0.982591 -0.129907 0.132811 + outer loop + vertex 0.87624 2.09802 2.44742 + vertex 0.875 2.095 2.45364 + vertex 0.875616 2.09206 2.4462 + endloop + endfacet + facet normal 0.982492 -0.0225663 0.184931 + outer loop + vertex 0.875 2.1 2.45425 + vertex 0.875 2.095 2.45364 + vertex 0.87624 2.09802 2.44742 + endloop + endfacet + facet normal 0.780733 -0.479905 0.400184 + outer loop + vertex 0.879095 2.09931 2.4393 + vertex 0.88 2.105 2.44436 + vertex 0.879672 2.105 2.445 + endloop + endfacet + facet normal 0.959639 -0.241559 0.144022 + outer loop + vertex 0.877724 2.09521 2.44156 + vertex 0.879095 2.09931 2.4393 + vertex 0.879672 2.105 2.445 + endloop + endfacet + facet normal 0.878558 -0.304225 0.368216 + outer loop + vertex 0.877724 2.09521 2.44156 + vertex 0.879672 2.105 2.445 + vertex 0.87624 2.09802 2.44742 + endloop + endfacet + facet normal 0.822089 -0.222335 0.524154 + outer loop + vertex 0.879672 2.105 2.445 + vertex 0.876484 2.105 2.45 + vertex 0.87624 2.09802 2.44742 + endloop + endfacet + facet normal 0.97167 -0.111052 0.208624 + outer loop + vertex 0.876484 2.105 2.45 + vertex 0.875 2.1 2.45425 + vertex 0.87624 2.09802 2.44742 + endloop + endfacet + facet normal 0.511938 0.463057 0.723531 + outer loop + vertex 0.875 2.105 2.45105 + vertex 0.875 2.1 2.45425 + vertex 0.876484 2.105 2.45 + endloop + endfacet + facet normal 0.719142 -0.537526 -0.440341 + outer loop + vertex 0.88 2.105 2.47382 + vertex 0.875 2.10144 2.47 + vertex 0.877661 2.105 2.47 + endloop + endfacet + facet normal 0.677593 -0.189052 -0.710723 + outer loop + vertex 0.88 2.105 2.47382 + vertex 0.878152 2.10161 2.47296 + vertex 0.875 2.10144 2.47 + endloop + endfacet + facet normal 0.47827 -0.743943 -0.466698 + outer loop + vertex 0.878152 2.10161 2.47296 + vertex 0.874771 2.09888 2.47384 + vertex 0.875 2.10144 2.47 + endloop + endfacet + facet normal 0.562259 -0.783208 -0.265425 + outer loop + vertex 0.878152 2.10161 2.47296 + vertex 0.878002 2.10028 2.47656 + vertex 0.874771 2.09888 2.47384 + endloop + endfacet + facet normal 0.355064 -0.933097 0.0570871 + outer loop + vertex 0.878002 2.10028 2.47656 + vertex 0.874501 2.09906 2.47837 + vertex 0.874771 2.09888 2.47384 + endloop + endfacet + facet normal 0.329652 -0.944102 0.000432467 + outer loop + vertex 0.878002 2.10028 2.47656 + vertex 0.87855 2.10047 2.48186 + vertex 0.874501 2.09906 2.47837 + endloop + endfacet + facet normal -0.0208321 -0.917669 0.3968 + outer loop + vertex 0.87855 2.10047 2.48186 + vertex 0.874555 2.10061 2.48196 + vertex 0.874501 2.09906 2.47837 + endloop + endfacet + facet normal -0.557209 -0.22399 0.799591 + outer loop + vertex 0.87494 2.10247 2.48381 + vertex 0.878229 2.10163 2.48587 + vertex 0.877143 2.104 2.48578 + endloop + endfacet + facet normal -0.542917 -0.532995 0.648966 + outer loop + vertex 0.87494 2.10247 2.48381 + vertex 0.874555 2.10061 2.48196 + vertex 0.878229 2.10163 2.48587 + endloop + endfacet + facet normal -0.0253724 -0.96136 0.274123 + outer loop + vertex 0.874555 2.10061 2.48196 + vertex 0.87855 2.10047 2.48186 + vertex 0.878229 2.10163 2.48587 + endloop + endfacet + facet normal -0.670945 -0.28024 0.686512 + outer loop + vertex 0.878229 2.10163 2.48587 + vertex 0.880472 2.10317 2.48869 + vertex 0.877143 2.104 2.48578 + endloop + endfacet + facet normal 0.890948 -0.196003 0.409628 + outer loop + vertex 0.878332 2.10712 2.43377 + vertex 0.88 2.11 2.43152 + vertex 0.8784 2.11 2.435 + endloop + endfacet + facet normal 0.577914 0.668686 0.467841 + outer loop + vertex 0.8784 2.11 2.435 + vertex 0.875 2.11 2.4392 + vertex 0.875 2.10944 2.44 + endloop + endfacet + facet normal 0.814402 -0.24412 0.526454 + outer loop + vertex 0.8784 2.11 2.435 + vertex 0.875 2.10944 2.44 + vertex 0.878332 2.10712 2.43377 + endloop + endfacet + facet normal 0.469683 0.879539 -0.0762143 + outer loop + vertex 0.878332 2.10712 2.43377 + vertex 0.875 2.10944 2.44 + vertex 0.88 2.10677 2.44 + endloop + endfacet + facet normal 0.645475 -0.653569 -0.395234 + outer loop + vertex 0.88 2.10731 2.47 + vertex 0.88 2.105 2.47382 + vertex 0.877661 2.105 2.47 + endloop + endfacet + facet normal -0.693858 0.0809229 0.71555 + outer loop + vertex 0.874047 2.10508 2.48265 + vertex 0.87494 2.10247 2.48381 + vertex 0.877143 2.104 2.48578 + endloop + endfacet + facet normal -0.622157 0.303874 0.721513 + outer loop + vertex 0.876545 2.10735 2.48385 + vertex 0.874047 2.10508 2.48265 + vertex 0.877143 2.104 2.48578 + endloop + endfacet + facet normal -0.61465 0.307921 0.726216 + outer loop + vertex 0.877143 2.104 2.48578 + vertex 0.879853 2.10615 2.48716 + vertex 0.876545 2.10735 2.48385 + endloop + endfacet + facet normal -0.596543 0.264752 0.757656 + outer loop + vertex 0.880472 2.10317 2.48869 + vertex 0.879853 2.10615 2.48716 + vertex 0.877143 2.104 2.48578 + endloop + endfacet + facet normal -0.57819 0.516964 0.631224 + outer loop + vertex 0.87644 2.11137 2.4805 + vertex 0.873879 2.11101 2.47845 + vertex 0.873798 2.10867 2.48028 + endloop + endfacet + facet normal -0.658244 0.381986 0.648692 + outer loop + vertex 0.873798 2.10867 2.48028 + vertex 0.874047 2.10508 2.48265 + vertex 0.876545 2.10735 2.48385 + endloop + endfacet + facet normal -0.576265 0.514798 0.634746 + outer loop + vertex 0.87644 2.11137 2.4805 + vertex 0.873798 2.10867 2.48028 + vertex 0.876545 2.10735 2.48385 + endloop + endfacet + facet normal -0.629332 0.488261 0.604601 + outer loop + vertex 0.87644 2.11137 2.4805 + vertex 0.876545 2.10735 2.48385 + vertex 0.879046 2.10973 2.48454 + endloop + endfacet + facet normal -0.64245 0.469695 0.605512 + outer loop + vertex 0.87644 2.11137 2.4805 + vertex 0.879046 2.10973 2.48454 + vertex 0.878705 2.1119 2.48249 + endloop + endfacet + facet normal -0.573217 0.396577 0.717042 + outer loop + vertex 0.879046 2.10973 2.48454 + vertex 0.876545 2.10735 2.48385 + vertex 0.879853 2.10615 2.48716 + endloop + endfacet + facet normal -0.429319 0.785619 0.445521 + outer loop + vertex 0.875333 2.1167 2.47112 + vertex 0.873195 2.11663 2.46918 + vertex 0.872932 2.11475 2.47226 + endloop + endfacet + facet normal -0.449066 0.791632 0.414317 + outer loop + vertex 0.877149 2.11515 2.47606 + vertex 0.875333 2.1167 2.47112 + vertex 0.872932 2.11475 2.47226 + endloop + endfacet + facet normal -0.498861 0.72385 0.476633 + outer loop + vertex 0.874263 2.11278 2.47664 + vertex 0.877149 2.11515 2.47606 + vertex 0.872932 2.11475 2.47226 + endloop + endfacet + facet normal -0.522764 0.662266 0.53677 + outer loop + vertex 0.874263 2.11278 2.47664 + vertex 0.873879 2.11101 2.47845 + vertex 0.87644 2.11137 2.4805 + endloop + endfacet + facet normal -0.474523 0.706131 0.525554 + outer loop + vertex 0.877149 2.11515 2.47606 + vertex 0.874263 2.11278 2.47664 + vertex 0.87644 2.11137 2.4805 + endloop + endfacet + facet normal -0.616417 0.645378 0.451128 + outer loop + vertex 0.877149 2.11515 2.47606 + vertex 0.87644 2.11137 2.4805 + vertex 0.878929 2.11374 2.48051 + endloop + endfacet + facet normal -0.5748 0.685331 0.447132 + outer loop + vertex 0.877149 2.11515 2.47606 + vertex 0.878929 2.11374 2.48051 + vertex 0.879584 2.11543 2.47876 + endloop + endfacet + facet normal -0.594241 0.621751 0.510199 + outer loop + vertex 0.878929 2.11374 2.48051 + vertex 0.87644 2.11137 2.4805 + vertex 0.878705 2.1119 2.48249 + endloop + endfacet + facet normal -0.0418323 0.995785 0.081621 + outer loop + vertex 0.88 2.12249 2.465 + vertex 0.875 2.12228 2.465 + vertex 0.88 2.12208 2.47 + endloop + endfacet + facet normal -0.597316 0.51148 0.617739 + outer loop + vertex 0.88 2.12208 2.47 + vertex 0.875 2.12228 2.465 + vertex 0.874642 2.11866 2.46765 + endloop + endfacet + facet normal -0.478276 0.7206 0.501984 + outer loop + vertex 0.875333 2.1167 2.47112 + vertex 0.874642 2.11866 2.46765 + vertex 0.873195 2.11663 2.46918 + endloop + endfacet + facet normal -0.468779 0.726011 0.503145 + outer loop + vertex 0.875333 2.1167 2.47112 + vertex 0.879659 2.11841 2.47269 + vertex 0.874642 2.11866 2.46765 + endloop + endfacet + facet normal -0.596884 0.509263 0.619984 + outer loop + vertex 0.879659 2.11841 2.47269 + vertex 0.88 2.12208 2.47 + vertex 0.874642 2.11866 2.46765 + endloop + endfacet + facet normal -0.474014 0.782426 0.403881 + outer loop + vertex 0.879659 2.11841 2.47269 + vertex 0.877149 2.11515 2.47606 + vertex 0.881215 2.1168 2.47763 + endloop + endfacet + facet normal -0.460106 0.784337 0.416073 + outer loop + vertex 0.875333 2.1167 2.47112 + vertex 0.877149 2.11515 2.47606 + vertex 0.879659 2.11841 2.47269 + endloop + endfacet + facet normal -0.46221 0.822734 0.330863 + outer loop + vertex 0.881215 2.1168 2.47763 + vertex 0.877149 2.11515 2.47606 + vertex 0.879584 2.11543 2.47876 + endloop + endfacet + facet normal -0.402281 -0.914775 -0.036816 + outer loop + vertex 0.88577 0.903758 2.47195 + vertex 0.883124 0.905 2.47 + vertex 0.885 0.904175 2.47 + endloop + endfacet + facet normal -0.290894 -0.935451 -0.200781 + outer loop + vertex 0.883082 0.90459 2.47197 + vertex 0.883124 0.905 2.47 + vertex 0.88577 0.903758 2.47195 + endloop + endfacet + facet normal -0.293677 -0.951006 0.0966482 + outer loop + vertex 0.88577 0.903758 2.47195 + vertex 0.885497 0.904071 2.47421 + vertex 0.883082 0.90459 2.47197 + endloop + endfacet + facet normal -0.287022 -0.936612 -0.20094 + outer loop + vertex 0.883124 0.905 2.47 + vertex 0.883082 0.90459 2.47197 + vertex 0.879133 0.906063 2.47075 + endloop + endfacet + facet normal -0.298119 -0.594694 -0.746635 + outer loop + vertex 0.88 0.906566 2.47 + vertex 0.883124 0.905 2.47 + vertex 0.879133 0.906063 2.47075 + endloop + endfacet + facet normal -0.405153 -0.884131 0.23273 + outer loop + vertex 0.883082 0.90459 2.47197 + vertex 0.885497 0.904071 2.47421 + vertex 0.883229 0.90547 2.47557 + endloop + endfacet + facet normal -0.402506 -0.885293 0.232905 + outer loop + vertex 0.883082 0.90459 2.47197 + vertex 0.883229 0.90547 2.47557 + vertex 0.879133 0.906063 2.47075 + endloop + endfacet + facet normal -0.444884 -0.853015 0.272844 + outer loop + vertex 0.879133 0.906063 2.47075 + vertex 0.883229 0.90547 2.47557 + vertex 0.878032 0.907902 2.4747 + endloop + endfacet + facet normal -0.515097 -0.738006 0.435915 + outer loop + vertex 0.877992 0.909972 2.47801 + vertex 0.882696 0.90773 2.47977 + vertex 0.880659 0.909586 2.48051 + endloop + endfacet + facet normal -0.515998 -0.729026 0.449742 + outer loop + vertex 0.877992 0.909972 2.47801 + vertex 0.878032 0.907902 2.4747 + vertex 0.882696 0.90773 2.47977 + endloop + endfacet + facet normal -0.443489 -0.811622 0.380246 + outer loop + vertex 0.878032 0.907902 2.4747 + vertex 0.883229 0.90547 2.47557 + vertex 0.882696 0.90773 2.47977 + endloop + endfacet + facet normal -0.475268 -0.721198 0.503978 + outer loop + vertex 0.882696 0.90773 2.47977 + vertex 0.882709 0.910025 2.48307 + vertex 0.880659 0.909586 2.48051 + endloop + endfacet + facet normal -0.580895 -0.622891 0.523993 + outer loop + vertex 0.877992 0.909972 2.47801 + vertex 0.880659 0.909586 2.48051 + vertex 0.878825 0.911496 2.48075 + endloop + endfacet + facet normal -0.603624 -0.568124 0.559351 + outer loop + vertex 0.883431 0.911794 2.48578 + vertex 0.881275 0.914007 2.4857 + vertex 0.879087 0.913785 2.48312 + endloop + endfacet + facet normal -0.601644 -0.586056 0.542737 + outer loop + vertex 0.882709 0.910025 2.48307 + vertex 0.883431 0.911794 2.48578 + vertex 0.879087 0.913785 2.48312 + endloop + endfacet + facet normal -0.571437 -0.557691 0.602031 + outer loop + vertex 0.882709 0.910025 2.48307 + vertex 0.879087 0.913785 2.48312 + vertex 0.878825 0.911496 2.48075 + endloop + endfacet + facet normal -0.563945 -0.61061 0.555987 + outer loop + vertex 0.882709 0.910025 2.48307 + vertex 0.878825 0.911496 2.48075 + vertex 0.880659 0.909586 2.48051 + endloop + endfacet + facet normal -0.580305 -0.543717 0.606315 + outer loop + vertex 0.883431 0.911794 2.48578 + vertex 0.883712 0.914075 2.4881 + vertex 0.881275 0.914007 2.4857 + endloop + endfacet + facet normal 0.59242 -0.805625 0.00272595 + outer loop + vertex 0.883238 0.92 2.43 + vertex 0.88 0.917602 2.425 + vertex 0.883261 0.92 2.425 + endloop + endfacet + facet normal 0.566976 -0.823269 0.0276654 + outer loop + vertex 0.88 0.91777 2.43 + vertex 0.88 0.917602 2.425 + vertex 0.883238 0.92 2.43 + endloop + endfacet + facet normal -0.672213 -0.426454 0.6052 + outer loop + vertex 0.879087 0.913785 2.48312 + vertex 0.881275 0.914007 2.4857 + vertex 0.879527 0.91626 2.48535 + endloop + endfacet + facet normal -0.698557 -0.188491 0.690282 + outer loop + vertex 0.883309 0.916424 2.48951 + vertex 0.882527 0.918224 2.48921 + vertex 0.880924 0.917609 2.48742 + endloop + endfacet + facet normal -0.704447 -0.4503 0.548621 + outer loop + vertex 0.883712 0.914075 2.4881 + vertex 0.883309 0.916424 2.48951 + vertex 0.880924 0.917609 2.48742 + endloop + endfacet + facet normal -0.637428 -0.373317 0.674033 + outer loop + vertex 0.883712 0.914075 2.4881 + vertex 0.880924 0.917609 2.48742 + vertex 0.879527 0.91626 2.48535 + endloop + endfacet + facet normal -0.639089 -0.391845 0.661833 + outer loop + vertex 0.883712 0.914075 2.4881 + vertex 0.879527 0.91626 2.48535 + vertex 0.881275 0.914007 2.4857 + endloop + endfacet + facet normal -0.627327 -0.145027 0.765133 + outer loop + vertex 0.883309 0.916424 2.48951 + vertex 0.885313 0.916757 2.49121 + vertex 0.882527 0.918224 2.48921 + endloop + endfacet + facet normal 0.96753 -0.252718 0.00445196 + outer loop + vertex 0.883261 0.92 2.425 + vertex 0.884567 0.925 2.425 + vertex 0.883238 0.92 2.43 + endloop + endfacet + facet normal 0.793734 0.311492 0.522455 + outer loop + vertex 0.884567 0.925 2.425 + vertex 0.882805 0.924519 2.42796 + vertex 0.883238 0.92 2.43 + endloop + endfacet + facet normal 0.993945 -0.0841665 0.0706307 + outer loop + vertex 0.88339 0.923051 2.43085 + vertex 0.883289 0.922988 2.4322 + vertex 0.882837 0.92 2.435 + endloop + endfacet + facet normal 0.490381 -0.732261 -0.472568 + outer loop + vertex 0.88339 0.923051 2.43085 + vertex 0.882837 0.92 2.435 + vertex 0.882805 0.924519 2.42796 + endloop + endfacet + facet normal 0.988279 0.130464 0.0792659 + outer loop + vertex 0.882805 0.924519 2.42796 + vertex 0.882837 0.92 2.435 + vertex 0.883238 0.92 2.43 + endloop + endfacet + facet normal 0.879758 0.0518932 0.47258 + outer loop + vertex 0.883289 0.922988 2.4322 + vertex 0.883522 0.924737 2.43158 + vertex 0.882046 0.923845 2.43442 + endloop + endfacet + facet normal 0.883422 0.242047 0.401222 + outer loop + vertex 0.883289 0.922988 2.4322 + vertex 0.882046 0.923845 2.43442 + vertex 0.882837 0.92 2.435 + endloop + endfacet + facet normal 0.884232 0.241954 0.39949 + outer loop + vertex 0.882837 0.92 2.435 + vertex 0.882046 0.923845 2.43442 + vertex 0.880578 0.92 2.44 + endloop + endfacet + facet normal 0.995204 -0.0754392 0.0622756 + outer loop + vertex 0.88 0.92 2.44088 + vertex 0.880336 0.923949 2.4403 + vertex 0.88 0.923401 2.445 + endloop + endfacet + facet normal 0.835797 0.0097202 0.548952 + outer loop + vertex 0.88 0.92 2.44088 + vertex 0.880578 0.92 2.44 + vertex 0.880336 0.923949 2.4403 + endloop + endfacet + facet normal 0.959659 0.0377878 0.278615 + outer loop + vertex 0.880578 0.92 2.44 + vertex 0.882046 0.923845 2.43442 + vertex 0.880336 0.923949 2.4403 + endloop + endfacet + facet normal 0.965041 -0.259226 0.0387014 + outer loop + vertex 0.880229 0.925 2.45 + vertex 0.88 0.923401 2.445 + vertex 0.880336 0.923949 2.4403 + endloop + endfacet + facet normal 0.537591 -0.80997 0.234403 + outer loop + vertex 0.88 0.924848 2.45 + vertex 0.88 0.923401 2.445 + vertex 0.880229 0.925 2.45 + endloop + endfacet + facet normal 0.226365 0.852282 0.471566 + outer loop + vertex 0.885 0.922662 2.475 + vertex 0.88 0.92399 2.475 + vertex 0.883818 0.921766 2.47719 + endloop + endfacet + facet normal 0.300027 0.879129 0.370292 + outer loop + vertex 0.883818 0.921766 2.47719 + vertex 0.88 0.92399 2.475 + vertex 0.879627 0.922995 2.47766 + endloop + endfacet + facet normal 0.284951 0.957924 0.0344041 + outer loop + vertex 0.883818 0.921766 2.47719 + vertex 0.879627 0.922995 2.47766 + vertex 0.883539 0.921682 2.48184 + endloop + endfacet + facet normal 0.0825346 0.970174 0.227925 + outer loop + vertex 0.883539 0.921682 2.48184 + vertex 0.879627 0.922995 2.47766 + vertex 0.878685 0.92196 2.48241 + endloop + endfacet + facet normal 0.0765155 0.982272 0.171134 + outer loop + vertex 0.883539 0.921682 2.48184 + vertex 0.878685 0.92196 2.48241 + vertex 0.883836 0.920814 2.48669 + endloop + endfacet + facet normal -0.240878 0.824859 0.511454 + outer loop + vertex 0.883836 0.920814 2.48669 + vertex 0.878685 0.92196 2.48241 + vertex 0.880988 0.919843 2.48691 + endloop + endfacet + facet normal -0.762231 0.163564 0.626299 + outer loop + vertex 0.882527 0.918224 2.48921 + vertex 0.880988 0.919843 2.48691 + vertex 0.880924 0.917609 2.48742 + endloop + endfacet + facet normal -0.489794 0.523292 0.697329 + outer loop + vertex 0.882527 0.918224 2.48921 + vertex 0.884548 0.919046 2.49001 + vertex 0.880988 0.919843 2.48691 + endloop + endfacet + facet normal -0.244967 0.833214 0.495727 + outer loop + vertex 0.884548 0.919046 2.49001 + vertex 0.883836 0.920814 2.48669 + vertex 0.880988 0.919843 2.48691 + endloop + endfacet + facet normal -0.453147 0.291518 0.842422 + outer loop + vertex 0.884548 0.919046 2.49001 + vertex 0.882527 0.918224 2.48921 + vertex 0.885313 0.916757 2.49121 + endloop + endfacet + facet normal 0.960965 0.139541 -0.238901 + outer loop + vertex 0.883324 0.925 2.42 + vertex 0.882598 0.93 2.42 + vertex 0.884567 0.925 2.425 + endloop + endfacet + facet normal 0.70835 0.618709 0.339764 + outer loop + vertex 0.882598 0.93 2.42 + vertex 0.88197 0.929267 2.42264 + vertex 0.884567 0.925 2.425 + endloop + endfacet + facet normal 0.615583 0.633488 0.468776 + outer loop + vertex 0.884567 0.925 2.425 + vertex 0.88197 0.929267 2.42264 + vertex 0.882805 0.924519 2.42796 + endloop + endfacet + facet normal 0.987817 0.154698 -0.0169054 + outer loop + vertex 0.88197 0.929267 2.42264 + vertex 0.88198 0.929573 2.42602 + vertex 0.882805 0.924519 2.42796 + endloop + endfacet + facet normal 0.925639 -0.226262 -0.303311 + outer loop + vertex 0.883622 0.924809 2.43024 + vertex 0.88339 0.923051 2.43085 + vertex 0.882805 0.924519 2.42796 + endloop + endfacet + facet normal 0.858658 0.369508 -0.355205 + outer loop + vertex 0.883622 0.924809 2.43024 + vertex 0.882805 0.924519 2.42796 + vertex 0.882486 0.9277 2.4305 + endloop + endfacet + facet normal 0.988599 0.141081 -0.0526072 + outer loop + vertex 0.882486 0.9277 2.4305 + vertex 0.882805 0.924519 2.42796 + vertex 0.88198 0.929573 2.42602 + endloop + endfacet + facet normal 0.929807 0.357237 0.0885515 + outer loop + vertex 0.883522 0.924737 2.43158 + vertex 0.883622 0.924809 2.43024 + vertex 0.882486 0.9277 2.4305 + endloop + endfacet + facet normal 0.731079 0.443643 0.518367 + outer loop + vertex 0.883522 0.924737 2.43158 + vertex 0.882486 0.9277 2.4305 + vertex 0.882046 0.923845 2.43442 + endloop + endfacet + facet normal 0.959848 0.138518 0.243936 + outer loop + vertex 0.882046 0.923845 2.43442 + vertex 0.882486 0.9277 2.4305 + vertex 0.881073 0.928325 2.43571 + endloop + endfacet + facet normal 0.952862 0.128092 0.275038 + outer loop + vertex 0.882046 0.923845 2.43442 + vertex 0.881073 0.928325 2.43571 + vertex 0.880336 0.923949 2.4403 + endloop + endfacet + facet normal 0.963927 0.0974958 0.247668 + outer loop + vertex 0.881073 0.928325 2.43571 + vertex 0.87948 0.928612 2.44179 + vertex 0.880336 0.923949 2.4403 + endloop + endfacet + facet normal 0.92372 0.203255 0.324699 + outer loop + vertex 0.877816 0.927294 2.44735 + vertex 0.87948 0.928612 2.44179 + vertex 0.878173 0.93081 2.44414 + endloop + endfacet + facet normal 0.435668 0.837828 0.328995 + outer loop + vertex 0.877816 0.927294 2.44735 + vertex 0.880229 0.925 2.45 + vertex 0.87948 0.928612 2.44179 + endloop + endfacet + facet normal 0.983026 0.183241 -0.00904321 + outer loop + vertex 0.880229 0.925 2.45 + vertex 0.880336 0.923949 2.4403 + vertex 0.87948 0.928612 2.44179 + endloop + endfacet + facet normal 0.519362 0.820776 0.237886 + outer loop + vertex 0.880229 0.925 2.45 + vertex 0.877816 0.927294 2.44735 + vertex 0.88 0.925 2.4505 + endloop + endfacet + facet normal 0.893653 0.330291 0.303794 + outer loop + vertex 0.882598 0.93 2.42 + vertex 0.88075 0.935 2.42 + vertex 0.88197 0.929267 2.42264 + endloop + endfacet + facet normal 0.974983 0.220488 0.028153 + outer loop + vertex 0.88075 0.935 2.42 + vertex 0.880763 0.934393 2.42429 + vertex 0.88197 0.929267 2.42264 + endloop + endfacet + facet normal 0.971333 0.23648 -0.024263 + outer loop + vertex 0.88197 0.929267 2.42264 + vertex 0.880763 0.934393 2.42429 + vertex 0.88198 0.929573 2.42602 + endloop + endfacet + facet normal 0.972843 0.221566 -0.0669749 + outer loop + vertex 0.880763 0.934393 2.42429 + vertex 0.881474 0.932362 2.4279 + vertex 0.88198 0.929573 2.42602 + endloop + endfacet + facet normal 0.980034 0.196797 -0.0283738 + outer loop + vertex 0.88198 0.929573 2.42602 + vertex 0.881474 0.932362 2.4279 + vertex 0.882486 0.9277 2.4305 + endloop + endfacet + facet normal 0.964521 0.252402 0.0774052 + outer loop + vertex 0.881474 0.932362 2.4279 + vertex 0.881068 0.932662 2.43199 + vertex 0.882486 0.9277 2.4305 + endloop + endfacet + facet normal 0.951108 0.201601 0.23399 + outer loop + vertex 0.882486 0.9277 2.4305 + vertex 0.881068 0.932662 2.43199 + vertex 0.881073 0.928325 2.43571 + endloop + endfacet + facet normal 0.966279 0.168201 0.194969 + outer loop + vertex 0.881068 0.932662 2.43199 + vertex 0.880093 0.932785 2.43672 + vertex 0.881073 0.928325 2.43571 + endloop + endfacet + facet normal 0.957448 0.155324 0.243244 + outer loop + vertex 0.881073 0.928325 2.43571 + vertex 0.880093 0.932785 2.43672 + vertex 0.87948 0.928612 2.44179 + endloop + endfacet + facet normal 0.955696 0.160134 0.246986 + outer loop + vertex 0.880093 0.932785 2.43672 + vertex 0.879048 0.933169 2.44051 + vertex 0.87948 0.928612 2.44179 + endloop + endfacet + facet normal 0.921603 0.183594 0.341968 + outer loop + vertex 0.879048 0.933169 2.44051 + vertex 0.878173 0.93081 2.44414 + vertex 0.87948 0.928612 2.44179 + endloop + endfacet + facet normal 0.940637 0.131744 0.312802 + outer loop + vertex 0.878211 0.934191 2.4426 + vertex 0.878173 0.93081 2.44414 + vertex 0.879048 0.933169 2.44051 + endloop + endfacet + facet normal 0.989049 0.146527 0.0176576 + outer loop + vertex 0.88075 0.935 2.42 + vertex 0.88 0.93946 2.425 + vertex 0.880763 0.934393 2.42429 + endloop + endfacet + facet normal 0.692934 0.586558 -0.419277 + outer loop + vertex 0.88 0.935886 2.42 + vertex 0.88 0.93946 2.425 + vertex 0.88075 0.935 2.42 + endloop + endfacet + facet normal 0.985821 0.156841 -0.0596448 + outer loop + vertex 0.88 0.94 2.42642 + vertex 0.880763 0.934393 2.42429 + vertex 0.88 0.93946 2.425 + endloop + endfacet + facet normal 0.991961 0.121065 0.0368198 + outer loop + vertex 0.88 0.94 2.42642 + vertex 0.880279 0.937021 2.42868 + vertex 0.880763 0.934393 2.42429 + endloop + endfacet + facet normal 0.965693 0.255493 -0.0464839 + outer loop + vertex 0.880279 0.937021 2.42868 + vertex 0.881474 0.932362 2.4279 + vertex 0.880763 0.934393 2.42429 + endloop + endfacet + facet normal 0.968726 0.235193 0.0790856 + outer loop + vertex 0.881474 0.932362 2.4279 + vertex 0.880279 0.937021 2.42868 + vertex 0.881068 0.932662 2.43199 + endloop + endfacet + facet normal 0.964555 0.246297 0.094722 + outer loop + vertex 0.880279 0.937021 2.42868 + vertex 0.879902 0.936773 2.43318 + vertex 0.881068 0.932662 2.43199 + endloop + endfacet + facet normal 0.957304 0.216233 0.191866 + outer loop + vertex 0.881068 0.932662 2.43199 + vertex 0.879902 0.936773 2.43318 + vertex 0.880093 0.932785 2.43672 + endloop + endfacet + facet normal 0.966729 0.194182 0.166516 + outer loop + vertex 0.879902 0.936773 2.43318 + vertex 0.879271 0.936453 2.43721 + vertex 0.880093 0.932785 2.43672 + endloop + endfacet + facet normal 0.957659 0.183911 0.221507 + outer loop + vertex 0.878645 0.936205 2.44012 + vertex 0.879271 0.936453 2.43721 + vertex 0.878609 0.938944 2.43801 + endloop + endfacet + facet normal 0.962907 0.155882 0.220252 + outer loop + vertex 0.878645 0.936205 2.44012 + vertex 0.879048 0.933169 2.44051 + vertex 0.879271 0.936453 2.43721 + endloop + endfacet + facet normal 0.952788 0.180558 0.24412 + outer loop + vertex 0.879048 0.933169 2.44051 + vertex 0.880093 0.932785 2.43672 + vertex 0.879271 0.936453 2.43721 + endloop + endfacet + facet normal 0.940702 0.162837 0.297598 + outer loop + vertex 0.879048 0.933169 2.44051 + vertex 0.878645 0.936205 2.44012 + vertex 0.878211 0.934191 2.4426 + endloop + endfacet + facet normal 0.997204 0.0629646 -0.0402397 + outer loop + vertex 0.88 0.94 2.42642 + vertex 0.88 0.942288 2.43 + vertex 0.880279 0.937021 2.42868 + endloop + endfacet + facet normal 0.980772 0.172116 0.0919911 + outer loop + vertex 0.880279 0.937021 2.42868 + vertex 0.879407 0.940889 2.43075 + vertex 0.879902 0.936773 2.43318 + endloop + endfacet + facet normal 0.851245 -0.0841655 0.517975 + outer loop + vertex 0.88 0.942288 2.43 + vertex 0.879407 0.940889 2.43075 + vertex 0.880279 0.937021 2.42868 + endloop + endfacet + facet normal 0.967256 0.191643 0.166397 + outer loop + vertex 0.879902 0.936773 2.43318 + vertex 0.879011 0.940205 2.4344 + vertex 0.879271 0.936453 2.43721 + endloop + endfacet + facet normal 0.969221 0.20064 0.142666 + outer loop + vertex 0.879407 0.940889 2.43075 + vertex 0.879011 0.940205 2.4344 + vertex 0.879902 0.936773 2.43318 + endloop + endfacet + facet normal 0.963695 0.199597 0.177352 + outer loop + vertex 0.879271 0.936453 2.43721 + vertex 0.879011 0.940205 2.4344 + vertex 0.878609 0.938944 2.43801 + endloop + endfacet + facet normal -0.744629 -0.251069 -0.618459 + outer loop + vertex 0.885 1.10468 2.55 + vertex 0.884261 1.10686 2.55 + vertex 0.885 1.105 2.54987 + endloop + endfacet + facet normal -0.939692 -0.318619 0.124345 + outer loop + vertex 0.885 1.10468 2.55 + vertex 0.885 1.105 2.55082 + vertex 0.884261 1.10686 2.55 + endloop + endfacet + facet normal -0.692697 0.00433317 -0.721215 + outer loop + vertex 0.885 1.105 2.54987 + vertex 0.884896 1.11 2.55 + vertex 0.885 1.11 2.5499 + endloop + endfacet + facet normal -0.121658 0.0232568 -0.9923 + outer loop + vertex 0.884261 1.10686 2.55 + vertex 0.884896 1.11 2.55 + vertex 0.885 1.105 2.54987 + endloop + endfacet + facet normal -0.92896 -0.248654 0.274233 + outer loop + vertex 0.885 1.10961 2.555 + vertex 0.884261 1.10686 2.55 + vertex 0.885 1.105 2.55082 + endloop + endfacet + facet normal -0.820789 -0.440441 0.363753 + outer loop + vertex 0.885 1.10961 2.555 + vertex 0.883176 1.11042 2.55186 + vertex 0.884261 1.10686 2.55 + endloop + endfacet + facet normal -0.711019 0.14291 -0.688497 + outer loop + vertex 0.883176 1.11042 2.55186 + vertex 0.884896 1.11 2.55 + vertex 0.884261 1.10686 2.55 + endloop + endfacet + facet normal 0.845196 -0.117468 -0.521388 + outer loop + vertex 0.885 1.10961 2.555 + vertex 0.884115 1.1081 2.55391 + vertex 0.883176 1.11042 2.55186 + endloop + endfacet + facet normal -0.715585 -0.403012 -0.570543 + outer loop + vertex 0.884896 1.11 2.55 + vertex 0.883176 1.11042 2.55186 + vertex 0.88208 1.115 2.55 + endloop + endfacet + facet normal -0.97628 -0.203405 0.0741916 + outer loop + vertex 0.88208 1.115 2.55 + vertex 0.883176 1.11042 2.55186 + vertex 0.88246 1.115 2.555 + endloop + endfacet + facet normal -0.907697 -0.41598 -0.0552005 + outer loop + vertex 0.883126 1.11016 2.55466 + vertex 0.883176 1.11042 2.55186 + vertex 0.884115 1.1081 2.55391 + endloop + endfacet + facet normal -0.906256 -0.419075 -0.0554625 + outer loop + vertex 0.883126 1.11016 2.55466 + vertex 0.881968 1.11272 2.55424 + vertex 0.883176 1.11042 2.55186 + endloop + endfacet + facet normal -0.639859 0.363524 -0.677075 + outer loop + vertex 0.881968 1.11272 2.55424 + vertex 0.88246 1.115 2.555 + vertex 0.883176 1.11042 2.55186 + endloop + endfacet + facet normal -0.913093 -0.404543 0.0510468 + outer loop + vertex 0.883126 1.11016 2.55466 + vertex 0.882017 1.11303 2.55763 + vertex 0.881968 1.11272 2.55424 + endloop + endfacet + facet normal 0.0592932 0.303978 -0.950832 + outer loop + vertex 0.88246 1.115 2.555 + vertex 0.881968 1.11272 2.55424 + vertex 0.879629 1.11593 2.55512 + endloop + endfacet + facet normal -0.0575769 -0.0476903 -0.997201 + outer loop + vertex 0.88 1.11797 2.555 + vertex 0.88246 1.115 2.555 + vertex 0.879629 1.11593 2.55512 + endloop + endfacet + facet normal -0.730423 -0.521716 0.440789 + outer loop + vertex 0.881645 1.11565 2.56138 + vertex 0.879978 1.11963 2.56333 + vertex 0.87832 1.118 2.55866 + endloop + endfacet + facet normal -0.715279 -0.604261 0.351061 + outer loop + vertex 0.882017 1.11303 2.55763 + vertex 0.881645 1.11565 2.56138 + vertex 0.87832 1.118 2.55866 + endloop + endfacet + facet normal -0.794938 -0.603658 0.0605876 + outer loop + vertex 0.882017 1.11303 2.55763 + vertex 0.87832 1.118 2.55866 + vertex 0.879629 1.11593 2.55512 + endloop + endfacet + facet normal -0.797405 -0.599653 0.0675402 + outer loop + vertex 0.882017 1.11303 2.55763 + vertex 0.879629 1.11593 2.55512 + vertex 0.881968 1.11272 2.55424 + endloop + endfacet + facet normal -0.771127 -0.509772 0.381439 + outer loop + vertex 0.882885 1.11646 2.56497 + vertex 0.879978 1.11963 2.56333 + vertex 0.881645 1.11565 2.56138 + endloop + endfacet + facet normal -0.76222 -0.466818 0.448443 + outer loop + vertex 0.882011 1.12021 2.56739 + vertex 0.879978 1.11963 2.56333 + vertex 0.882885 1.11646 2.56497 + endloop + endfacet + facet normal -0.800365 -0.445317 0.401383 + outer loop + vertex 0.882885 1.11646 2.56497 + vertex 0.883711 1.11789 2.56821 + vertex 0.882011 1.12021 2.56739 + endloop + endfacet + facet normal -0.650758 -0.61522 0.444994 + outer loop + vertex 0.87832 1.118 2.55866 + vertex 0.879978 1.11963 2.56333 + vertex 0.877256 1.12089 2.5611 + endloop + endfacet + facet normal -0.658448 -0.587927 0.46988 + outer loop + vertex 0.876814 1.12323 2.56341 + vertex 0.877256 1.12089 2.5611 + vertex 0.879978 1.11963 2.56333 + endloop + endfacet + facet normal -0.633 -0.566872 0.527226 + outer loop + vertex 0.876814 1.12323 2.56341 + vertex 0.879978 1.11963 2.56333 + vertex 0.879373 1.12389 2.56718 + endloop + endfacet + facet normal -0.740099 -0.505935 0.443038 + outer loop + vertex 0.879373 1.12389 2.56718 + vertex 0.879978 1.11963 2.56333 + vertex 0.882011 1.12021 2.56739 + endloop + endfacet + facet normal -0.795573 -0.434473 0.422252 + outer loop + vertex 0.883373 1.12038 2.57012 + vertex 0.882011 1.12021 2.56739 + vertex 0.883711 1.11789 2.56821 + endloop + endfacet + facet normal -0.790496 -0.445425 0.420372 + outer loop + vertex 0.883373 1.12038 2.57012 + vertex 0.882067 1.12363 2.57112 + vertex 0.882011 1.12021 2.56739 + endloop + endfacet + facet normal -0.730611 -0.497703 0.467439 + outer loop + vertex 0.882067 1.12363 2.57112 + vertex 0.879373 1.12389 2.56718 + vertex 0.882011 1.12021 2.56739 + endloop + endfacet + facet normal -0.776587 -0.447036 0.443928 + outer loop + vertex 0.883373 1.12038 2.57012 + vertex 0.883989 1.12172 2.57255 + vertex 0.882067 1.12363 2.57112 + endloop + endfacet + facet normal -0.649534 -0.541248 0.534 + outer loop + vertex 0.876814 1.12323 2.56341 + vertex 0.879373 1.12389 2.56718 + vertex 0.876835 1.12564 2.56586 + endloop + endfacet + facet normal -0.652493 -0.583872 0.483059 + outer loop + vertex 0.876655 1.12789 2.56835 + vertex 0.876835 1.12564 2.56586 + vertex 0.879373 1.12389 2.56718 + endloop + endfacet + facet normal -0.629553 -0.578653 0.518482 + outer loop + vertex 0.876655 1.12789 2.56835 + vertex 0.879373 1.12389 2.56718 + vertex 0.87955 1.12731 2.57121 + endloop + endfacet + facet normal -0.725651 -0.508676 0.463336 + outer loop + vertex 0.87955 1.12731 2.57121 + vertex 0.879373 1.12389 2.56718 + vertex 0.882067 1.12363 2.57112 + endloop + endfacet + facet normal -0.772668 -0.417435 0.47826 + outer loop + vertex 0.884127 1.12421 2.57495 + vertex 0.882067 1.12363 2.57112 + vertex 0.883989 1.12172 2.57255 + endloop + endfacet + facet normal -0.742749 -0.475983 0.470918 + outer loop + vertex 0.884127 1.12421 2.57495 + vertex 0.881837 1.12695 2.57411 + vertex 0.882067 1.12363 2.57112 + endloop + endfacet + facet normal -0.709394 -0.49841 0.498345 + outer loop + vertex 0.881837 1.12695 2.57411 + vertex 0.87955 1.12731 2.57121 + vertex 0.882067 1.12363 2.57112 + endloop + endfacet + facet normal -0.725941 -0.446055 0.523493 + outer loop + vertex 0.884127 1.12421 2.57495 + vertex 0.884037 1.12795 2.57801 + vertex 0.881837 1.12695 2.57411 + endloop + endfacet + facet normal -0.633366 -0.569188 0.524283 + outer loop + vertex 0.876655 1.12789 2.56835 + vertex 0.87955 1.12731 2.57121 + vertex 0.87713 1.1303 2.57154 + endloop + endfacet + facet normal -0.698507 -0.524709 0.486589 + outer loop + vertex 0.87955 1.12731 2.57121 + vertex 0.881837 1.12695 2.57411 + vertex 0.879486 1.13065 2.57472 + endloop + endfacet + facet normal -0.630952 -0.567733 0.528752 + outer loop + vertex 0.87713 1.1303 2.57154 + vertex 0.87955 1.12731 2.57121 + vertex 0.879486 1.13065 2.57472 + endloop + endfacet + facet normal -0.653549 -0.430625 0.622443 + outer loop + vertex 0.884424 1.13108 2.58079 + vertex 0.881738 1.1351 2.58076 + vertex 0.880752 1.13289 2.57819 + endloop + endfacet + facet normal -0.653269 -0.455921 0.604463 + outer loop + vertex 0.884037 1.12795 2.57801 + vertex 0.884424 1.13108 2.58079 + vertex 0.880752 1.13289 2.57819 + endloop + endfacet + facet normal -0.682959 -0.473939 0.555832 + outer loop + vertex 0.884037 1.12795 2.57801 + vertex 0.880752 1.13289 2.57819 + vertex 0.879486 1.13065 2.57472 + endloop + endfacet + facet normal -0.681155 -0.518617 0.516783 + outer loop + vertex 0.884037 1.12795 2.57801 + vertex 0.879486 1.13065 2.57472 + vertex 0.881837 1.12695 2.57411 + endloop + endfacet + facet normal -0.631707 -0.41574 0.654299 + outer loop + vertex 0.884424 1.13108 2.58079 + vertex 0.885424 1.13319 2.5831 + vertex 0.881738 1.1351 2.58076 + endloop + endfacet + facet normal -0.620074 -0.46039 0.635255 + outer loop + vertex 0.877559 1.13755 2.57845 + vertex 0.880752 1.13289 2.57819 + vertex 0.881738 1.1351 2.58076 + endloop + endfacet + facet normal -0.612628 -0.408618 0.676549 + outer loop + vertex 0.880024 1.13778 2.58082 + vertex 0.877559 1.13755 2.57845 + vertex 0.881738 1.1351 2.58076 + endloop + endfacet + facet normal -0.596402 -0.39872 0.696654 + outer loop + vertex 0.881738 1.1351 2.58076 + vertex 0.882568 1.13801 2.58313 + vertex 0.880024 1.13778 2.58082 + endloop + endfacet + facet normal -0.628274 -0.376628 0.680752 + outer loop + vertex 0.885424 1.13319 2.5831 + vertex 0.882568 1.13801 2.58313 + vertex 0.881738 1.1351 2.58076 + endloop + endfacet + facet normal -0.548686 -0.0186325 0.835821 + outer loop + vertex 0.879268 1.20398 2.59629 + vertex 0.876643 1.20241 2.59453 + vertex 0.87935 1.20094 2.59627 + endloop + endfacet + facet normal -0.554616 -0.018773 0.831895 + outer loop + vertex 0.87935 1.20094 2.59627 + vertex 0.882394 1.20235 2.59834 + vertex 0.879268 1.20398 2.59629 + endloop + endfacet + facet normal -0.553479 -0.0222017 0.832567 + outer loop + vertex 0.87935 1.20094 2.59627 + vertex 0.880619 1.19719 2.59702 + vertex 0.882394 1.20235 2.59834 + endloop + endfacet + facet normal -0.539617 -0.0292193 0.841403 + outer loop + vertex 0.880619 1.19719 2.59702 + vertex 0.883824 1.19725 2.59907 + vertex 0.882394 1.20235 2.59834 + endloop + endfacet + facet normal -0.441196 0.0946668 0.892404 + outer loop + vertex 0.881505 1.7039 2.61511 + vertex 0.884711 1.70806 2.61625 + vertex 0.881649 1.70713 2.61484 + endloop + endfacet + facet normal -0.442872 0.102758 0.890677 + outer loop + vertex 0.881649 1.70713 2.61484 + vertex 0.884711 1.70806 2.61625 + vertex 0.881942 1.71044 2.6146 + endloop + endfacet + facet normal -0.496372 0.0584329 0.866141 + outer loop + vertex 0.882637 1.76048 2.60919 + vertex 0.882822 1.76537 2.60897 + vertex 0.879501 1.76209 2.60729 + endloop + endfacet + facet normal -0.495119 0.0567372 0.866971 + outer loop + vertex 0.879501 1.76209 2.60729 + vertex 0.882822 1.76537 2.60897 + vertex 0.879717 1.76699 2.60709 + endloop + endfacet + facet normal -0.492948 0.0614903 0.867883 + outer loop + vertex 0.879717 1.76699 2.60709 + vertex 0.883005 1.77037 2.60872 + vertex 0.87992 1.77164 2.60687 + endloop + endfacet + facet normal -0.471193 0.147691 0.869577 + outer loop + vertex 0.881525 1.78873 2.60522 + vertex 0.884957 1.79179 2.60656 + vertex 0.882506 1.7925 2.60511 + endloop + endfacet + facet normal -0.476144 0.155394 0.865528 + outer loop + vertex 0.882506 1.7925 2.60511 + vertex 0.884762 1.79499 2.60591 + vertex 0.88246 1.79595 2.60447 + endloop + endfacet + facet normal -0.470743 0.149208 0.869562 + outer loop + vertex 0.884762 1.79499 2.60591 + vertex 0.882506 1.7925 2.60511 + vertex 0.884957 1.79179 2.60656 + endloop + endfacet + facet normal -0.578191 0.307633 0.755683 + outer loop + vertex 0.880377 1.87344 2.58579 + vertex 0.876975 1.87038 2.58443 + vertex 0.879457 1.86975 2.58659 + endloop + endfacet + facet normal -0.55075 0.305343 0.776814 + outer loop + vertex 0.879457 1.86975 2.58659 + vertex 0.883164 1.87123 2.58863 + vertex 0.880377 1.87344 2.58579 + endloop + endfacet + facet normal -0.542686 0.250324 0.801767 + outer loop + vertex 0.879457 1.86975 2.58659 + vertex 0.879363 1.86647 2.58755 + vertex 0.883164 1.87123 2.58863 + endloop + endfacet + facet normal -0.601174 0.349687 0.718547 + outer loop + vertex 0.877247 1.87503 2.5824 + vertex 0.876975 1.87038 2.58443 + vertex 0.880377 1.87344 2.58579 + endloop + endfacet + facet normal -0.606456 0.339868 0.718819 + outer loop + vertex 0.88094 1.87786 2.58418 + vertex 0.877247 1.87503 2.5824 + vertex 0.880377 1.87344 2.58579 + endloop + endfacet + facet normal -0.607476 0.339711 0.718032 + outer loop + vertex 0.880377 1.87344 2.58579 + vertex 0.883858 1.87654 2.58727 + vertex 0.88094 1.87786 2.58418 + endloop + endfacet + facet normal -0.572054 0.273797 0.773169 + outer loop + vertex 0.883164 1.87123 2.58863 + vertex 0.883858 1.87654 2.58727 + vertex 0.880377 1.87344 2.58579 + endloop + endfacet + facet normal -0.636208 0.408325 0.654607 + outer loop + vertex 0.881277 1.88243 2.58189 + vertex 0.87871 1.88228 2.57949 + vertex 0.878374 1.87961 2.58082 + endloop + endfacet + facet normal -0.623324 0.386393 0.679829 + outer loop + vertex 0.878374 1.87961 2.58082 + vertex 0.877247 1.87503 2.5824 + vertex 0.88094 1.87786 2.58418 + endloop + endfacet + facet normal -0.623653 0.385887 0.679815 + outer loop + vertex 0.881277 1.88243 2.58189 + vertex 0.878374 1.87961 2.58082 + vertex 0.88094 1.87786 2.58418 + endloop + endfacet + facet normal -0.640846 0.380588 0.666686 + outer loop + vertex 0.881277 1.88243 2.58189 + vertex 0.88094 1.87786 2.58418 + vertex 0.883887 1.88051 2.5855 + endloop + endfacet + facet normal -0.663276 0.345194 0.664007 + outer loop + vertex 0.881277 1.88243 2.58189 + vertex 0.883887 1.88051 2.5855 + vertex 0.883724 1.88278 2.58415 + endloop + endfacet + facet normal -0.614554 0.325406 0.718634 + outer loop + vertex 0.883887 1.88051 2.5855 + vertex 0.88094 1.87786 2.58418 + vertex 0.883858 1.87654 2.58727 + endloop + endfacet + facet normal -0.624351 0.448778 0.639362 + outer loop + vertex 0.878865 1.88495 2.57777 + vertex 0.87871 1.88228 2.57949 + vertex 0.881277 1.88243 2.58189 + endloop + endfacet + facet normal -0.639605 0.430275 0.636999 + outer loop + vertex 0.881395 1.88696 2.57895 + vertex 0.878865 1.88495 2.57777 + vertex 0.881277 1.88243 2.58189 + endloop + endfacet + facet normal -0.660966 0.420703 0.621396 + outer loop + vertex 0.881277 1.88243 2.58189 + vertex 0.883732 1.88518 2.58264 + vertex 0.881395 1.88696 2.57895 + endloop + endfacet + facet normal -0.650959 0.40631 0.641221 + outer loop + vertex 0.883724 1.88278 2.58415 + vertex 0.883732 1.88518 2.58264 + vertex 0.881277 1.88243 2.58189 + endloop + endfacet + facet normal -0.679317 0.454113 0.576464 + outer loop + vertex 0.881458 1.8917 2.5756 + vertex 0.879229 1.89152 2.57311 + vertex 0.879056 1.88896 2.57493 + endloop + endfacet + facet normal -0.648891 0.459956 0.606119 + outer loop + vertex 0.879056 1.88896 2.57493 + vertex 0.878865 1.88495 2.57777 + vertex 0.881395 1.88696 2.57895 + endloop + endfacet + facet normal -0.666572 0.436096 0.604568 + outer loop + vertex 0.881458 1.8917 2.5756 + vertex 0.879056 1.88896 2.57493 + vertex 0.881395 1.88696 2.57895 + endloop + endfacet + facet normal -0.667226 0.435764 0.604086 + outer loop + vertex 0.881458 1.8917 2.5756 + vertex 0.881395 1.88696 2.57895 + vertex 0.883793 1.889 2.58013 + endloop + endfacet + facet normal -0.68589 0.412253 0.599669 + outer loop + vertex 0.881458 1.8917 2.5756 + vertex 0.883793 1.889 2.58013 + vertex 0.88375 1.89171 2.57821 + endloop + endfacet + facet normal -0.661863 0.41939 0.621328 + outer loop + vertex 0.883793 1.889 2.58013 + vertex 0.881395 1.88696 2.57895 + vertex 0.883732 1.88518 2.58264 + endloop + endfacet + facet normal -0.743656 0.427481 0.514038 + outer loop + vertex 0.881375 1.89756 2.57125 + vertex 0.878825 1.89574 2.56907 + vertex 0.879524 1.89367 2.5718 + endloop + endfacet + facet normal -0.681892 0.446575 0.579305 + outer loop + vertex 0.879524 1.89367 2.5718 + vertex 0.879229 1.89152 2.57311 + vertex 0.881458 1.8917 2.5756 + endloop + endfacet + facet normal -0.703706 0.417146 0.575141 + outer loop + vertex 0.881375 1.89756 2.57125 + vertex 0.879524 1.89367 2.5718 + vertex 0.881458 1.8917 2.5756 + endloop + endfacet + facet normal -0.6995 0.419654 0.578438 + outer loop + vertex 0.881375 1.89756 2.57125 + vertex 0.881458 1.8917 2.5756 + vertex 0.883657 1.89457 2.57618 + endloop + endfacet + facet normal -0.740276 0.365346 0.56437 + outer loop + vertex 0.881375 1.89756 2.57125 + vertex 0.883657 1.89457 2.57618 + vertex 0.883609 1.89745 2.57425 + endloop + endfacet + facet normal -0.687942 0.406129 0.601494 + outer loop + vertex 0.883657 1.89457 2.57618 + vertex 0.881458 1.8917 2.5756 + vertex 0.88375 1.89171 2.57821 + endloop + endfacet + facet normal -0.825799 0.406602 0.390807 + outer loop + vertex 0.880504 1.90257 2.56565 + vertex 0.878765 1.9004 2.56424 + vertex 0.87927 1.89867 2.5671 + endloop + endfacet + facet normal -0.743415 0.447268 0.497277 + outer loop + vertex 0.87927 1.89867 2.5671 + vertex 0.878825 1.89574 2.56907 + vertex 0.881375 1.89756 2.57125 + endloop + endfacet + facet normal -0.756434 0.424343 0.497735 + outer loop + vertex 0.87927 1.89867 2.5671 + vertex 0.881375 1.89756 2.57125 + vertex 0.880504 1.90257 2.56565 + endloop + endfacet + facet normal -0.837285 0.336091 0.431274 + outer loop + vertex 0.880504 1.90257 2.56565 + vertex 0.881375 1.89756 2.57125 + vertex 0.882507 1.90307 2.56915 + endloop + endfacet + facet normal -0.752145 0.363608 0.549607 + outer loop + vertex 0.881375 1.89756 2.57125 + vertex 0.883822 1.90029 2.57279 + vertex 0.882507 1.90307 2.56915 + endloop + endfacet + facet normal -0.745982 0.34773 0.567974 + outer loop + vertex 0.883609 1.89745 2.57425 + vertex 0.883822 1.90029 2.57279 + vertex 0.881375 1.89756 2.57125 + endloop + endfacet + facet normal -0.651135 0.517155 0.555494 + outer loop + vertex 0.88077 1.90912 2.55559 + vertex 0.880961 1.91 2.555 + vertex 0.88 1.90879 2.555 + endloop + endfacet + facet normal -0.647813 0.537532 0.539813 + outer loop + vertex 0.879165 1.9048 2.55797 + vertex 0.88077 1.90912 2.55559 + vertex 0.88 1.90879 2.555 + endloop + endfacet + facet normal -0.889026 0.424507 0.171542 + outer loop + vertex 0.880799 1.90727 2.56033 + vertex 0.88077 1.90912 2.55559 + vertex 0.879165 1.9048 2.55797 + endloop + endfacet + facet normal -0.894963 0.395935 0.205612 + outer loop + vertex 0.879318 1.90311 2.56189 + vertex 0.880799 1.90727 2.56033 + vertex 0.879165 1.9048 2.55797 + endloop + endfacet + facet normal -0.830138 0.451832 0.326679 + outer loop + vertex 0.879318 1.90311 2.56189 + vertex 0.878765 1.9004 2.56424 + vertex 0.880504 1.90257 2.56565 + endloop + endfacet + facet normal -0.844702 0.423587 0.327188 + outer loop + vertex 0.879318 1.90311 2.56189 + vertex 0.880504 1.90257 2.56565 + vertex 0.880799 1.90727 2.56033 + endloop + endfacet + facet normal -0.893174 0.360518 0.268826 + outer loop + vertex 0.880799 1.90727 2.56033 + vertex 0.880504 1.90257 2.56565 + vertex 0.882364 1.90743 2.56531 + endloop + endfacet + facet normal -0.777835 0.338651 0.529423 + outer loop + vertex 0.883645 1.90618 2.56883 + vertex 0.882507 1.90307 2.56915 + vertex 0.884219 1.90384 2.57117 + endloop + endfacet + facet normal -0.834214 0.348774 0.427134 + outer loop + vertex 0.883645 1.90618 2.56883 + vertex 0.882364 1.90743 2.56531 + vertex 0.882507 1.90307 2.56915 + endloop + endfacet + facet normal -0.833901 0.349094 0.427484 + outer loop + vertex 0.882364 1.90743 2.56531 + vertex 0.880504 1.90257 2.56565 + vertex 0.882507 1.90307 2.56915 + endloop + endfacet + facet normal -0.778767 0.329963 0.533523 + outer loop + vertex 0.884219 1.90384 2.57117 + vertex 0.882507 1.90307 2.56915 + vertex 0.883822 1.90029 2.57279 + endloop + endfacet + facet normal -0.862437 0.398442 0.312164 + outer loop + vertex 0.880961 1.91 2.555 + vertex 0.88077 1.90912 2.55559 + vertex 0.883271 1.915 2.555 + endloop + endfacet + facet normal -0.904212 0.361711 -0.227082 + outer loop + vertex 0.883271 1.915 2.555 + vertex 0.88077 1.90912 2.55559 + vertex 0.882011 1.91252 2.55607 + endloop + endfacet + facet normal -0.936913 0.323547 0.132331 + outer loop + vertex 0.88077 1.90912 2.55559 + vertex 0.880799 1.90727 2.56033 + vertex 0.882011 1.91252 2.55607 + endloop + endfacet + facet normal -0.92985 0.336072 0.149782 + outer loop + vertex 0.882011 1.91252 2.55607 + vertex 0.880799 1.90727 2.56033 + vertex 0.882605 1.91211 2.56068 + endloop + endfacet + facet normal -0.837978 0.346987 0.42118 + outer loop + vertex 0.883594 1.91118 2.56467 + vertex 0.882364 1.90743 2.56531 + vertex 0.884081 1.90904 2.5674 + endloop + endfacet + facet normal -0.88985 0.34336 0.300452 + outer loop + vertex 0.883594 1.91118 2.56467 + vertex 0.882605 1.91211 2.56068 + vertex 0.882364 1.90743 2.56531 + endloop + endfacet + facet normal -0.907214 0.318663 0.274621 + outer loop + vertex 0.882605 1.91211 2.56068 + vertex 0.880799 1.90727 2.56033 + vertex 0.882364 1.90743 2.56531 + endloop + endfacet + facet normal -0.838076 0.341069 0.425794 + outer loop + vertex 0.884081 1.90904 2.5674 + vertex 0.882364 1.90743 2.56531 + vertex 0.883645 1.90618 2.56883 + endloop + endfacet + facet normal -0.995288 0.0451929 0.0857921 + outer loop + vertex 0.88284 1.915 2.55 + vertex 0.883271 1.915 2.555 + vertex 0.883067 1.92 2.55 + endloop + endfacet + facet normal -0.965711 0.162825 0.202215 + outer loop + vertex 0.883067 1.92 2.55 + vertex 0.883271 1.915 2.555 + vertex 0.883251 1.91817 2.55235 + endloop + endfacet + facet normal 0.517725 -0.546769 -0.65803 + outer loop + vertex 0.883271 1.915 2.555 + vertex 0.882011 1.91252 2.55607 + vertex 0.883251 1.91817 2.55235 + endloop + endfacet + facet normal -0.957492 0.272426 0.0948362 + outer loop + vertex 0.883251 1.91817 2.55235 + vertex 0.882011 1.91252 2.55607 + vertex 0.883195 1.91661 2.55628 + endloop + endfacet + facet normal -0.896051 0.332633 0.29402 + outer loop + vertex 0.883631 1.91592 2.55949 + vertex 0.882605 1.91211 2.56068 + vertex 0.883968 1.91405 2.56263 + endloop + endfacet + facet normal -0.930757 0.310622 0.192887 + outer loop + vertex 0.883631 1.91592 2.55949 + vertex 0.883195 1.91661 2.55628 + vertex 0.882605 1.91211 2.56068 + endloop + endfacet + facet normal -0.952157 0.268168 0.146571 + outer loop + vertex 0.883195 1.91661 2.55628 + vertex 0.882011 1.91252 2.55607 + vertex 0.882605 1.91211 2.56068 + endloop + endfacet + facet normal -0.896197 0.328212 0.298508 + outer loop + vertex 0.883968 1.91405 2.56263 + vertex 0.882605 1.91211 2.56068 + vertex 0.883594 1.91118 2.56467 + endloop + endfacet + facet normal -0.594348 0.189155 -0.781646 + outer loop + vertex 0.885 1.92 2.54807 + vertex 0.88397 1.92121 2.54915 + vertex 0.885 1.925 2.54928 + endloop + endfacet + facet normal -0.706277 0.0283741 -0.707367 + outer loop + vertex 0.883067 1.92 2.55 + vertex 0.88397 1.92121 2.54915 + vertex 0.885 1.92 2.54807 + endloop + endfacet + facet normal -0.963181 0.234641 0.13125 + outer loop + vertex 0.885 1.925 2.55298 + vertex 0.883251 1.91817 2.55235 + vertex 0.885 1.92387 2.555 + endloop + endfacet + facet normal -0.968945 0.246702 0.0168298 + outer loop + vertex 0.885 1.925 2.55298 + vertex 0.88397 1.92121 2.54915 + vertex 0.883251 1.91817 2.55235 + endloop + endfacet + facet normal -0.402104 0.707003 0.581773 + outer loop + vertex 0.88397 1.92121 2.54915 + vertex 0.883067 1.92 2.55 + vertex 0.883251 1.91817 2.55235 + endloop + endfacet + facet normal -0.921596 0.277037 0.271868 + outer loop + vertex 0.885 1.92387 2.555 + vertex 0.883195 1.91661 2.55628 + vertex 0.884213 1.91919 2.5571 + endloop + endfacet + facet normal -0.962997 0.254828 0.0877515 + outer loop + vertex 0.883251 1.91817 2.55235 + vertex 0.883195 1.91661 2.55628 + vertex 0.885 1.92387 2.555 + endloop + endfacet + facet normal -0.932252 0.306527 0.192216 + outer loop + vertex 0.884213 1.91919 2.5571 + vertex 0.883195 1.91661 2.55628 + vertex 0.883631 1.91592 2.55949 + endloop + endfacet + facet normal -0.916633 0.260133 -0.303503 + outer loop + vertex 0.885 1.925 2.54928 + vertex 0.88397 1.92121 2.54915 + vertex 0.885 1.92584 2.55 + endloop + endfacet + facet normal -0.976643 0.206807 0.0582993 + outer loop + vertex 0.885 1.92584 2.55 + vertex 0.88397 1.92121 2.54915 + vertex 0.885 1.925 2.55298 + endloop + endfacet + facet normal 0.595517 -0.525029 -0.608033 + outer loop + vertex 0.880194 2.095 2.42 + vertex 0.88 2.09478 2.42 + vertex 0.88 2.095 2.41981 + endloop + endfacet + facet normal 0.749713 -0.660974 0.0323238 + outer loop + vertex 0.880194 2.095 2.42 + vertex 0.88 2.095 2.4245 + vertex 0.88 2.09478 2.42 + endloop + endfacet + facet normal 0.960726 -0.267755 -0.0728909 + outer loop + vertex 0.879921 2.09469 2.42566 + vertex 0.879166 2.09136 2.42792 + vertex 0.879245 2.09226 2.42568 + endloop + endfacet + facet normal 0.968898 -0.244766 -0.0364216 + outer loop + vertex 0.879921 2.09469 2.42566 + vertex 0.87966 2.09309 2.42942 + vertex 0.879166 2.09136 2.42792 + endloop + endfacet + facet normal 0.967405 -0.252778 0.0151884 + outer loop + vertex 0.88 2.095 2.4245 + vertex 0.88075 2.09771 2.42181 + vertex 0.88 2.09503 2.425 + endloop + endfacet + facet normal 0.972827 -0.227704 0.0419433 + outer loop + vertex 0.88 2.095 2.4245 + vertex 0.880194 2.095 2.42 + vertex 0.88075 2.09771 2.42181 + endloop + endfacet + facet normal 0.894048 -0.360842 0.265464 + outer loop + vertex 0.880194 2.095 2.42 + vertex 0.882212 2.1 2.42 + vertex 0.88075 2.09771 2.42181 + endloop + endfacet + facet normal 0.963108 -0.268034 -0.0240888 + outer loop + vertex 0.88 2.09503 2.425 + vertex 0.879921 2.09469 2.42566 + vertex 0.879245 2.09226 2.42568 + endloop + endfacet + facet normal 0.938472 -0.339322 -0.064272 + outer loop + vertex 0.88 2.09503 2.425 + vertex 0.88075 2.09771 2.42181 + vertex 0.879921 2.09469 2.42566 + endloop + endfacet + facet normal 0.98065 -0.184035 0.0667595 + outer loop + vertex 0.88075 2.09771 2.42181 + vertex 0.88081 2.0991 2.42475 + vertex 0.879921 2.09469 2.42566 + endloop + endfacet + facet normal 0.992534 -0.105233 0.0616697 + outer loop + vertex 0.87966 2.09309 2.42942 + vertex 0.880125 2.09731 2.42912 + vertex 0.879479 2.09354 2.43308 + endloop + endfacet + facet normal 0.99387 -0.108087 0.0232209 + outer loop + vertex 0.87966 2.09309 2.42942 + vertex 0.879921 2.09469 2.42566 + vertex 0.880125 2.09731 2.42912 + endloop + endfacet + facet normal 0.980206 -0.181326 0.0794788 + outer loop + vertex 0.879921 2.09469 2.42566 + vertex 0.88081 2.0991 2.42475 + vertex 0.880125 2.09731 2.42912 + endloop + endfacet + facet normal 0.992767 -0.0622192 0.102674 + outer loop + vertex 0.879608 2.09768 2.43435 + vertex 0.879479 2.09354 2.43308 + vertex 0.880125 2.09731 2.42912 + endloop + endfacet + facet normal 0.987469 -0.0733756 0.139717 + outer loop + vertex 0.87904 2.09483 2.43687 + vertex 0.879479 2.09354 2.43308 + vertex 0.879608 2.09768 2.43435 + endloop + endfacet + facet normal 0.988138 -0.0824593 0.129556 + outer loop + vertex 0.879608 2.09768 2.43435 + vertex 0.879095 2.09931 2.4393 + vertex 0.87904 2.09483 2.43687 + endloop + endfacet + facet normal 0.83535 -0.107257 0.539153 + outer loop + vertex 0.882212 2.1 2.42 + vertex 0.882854 2.105 2.42 + vertex 0.88075 2.09771 2.42181 + endloop + endfacet + facet normal 0.957681 -0.285474 -0.0367733 + outer loop + vertex 0.882854 2.105 2.42 + vertex 0.883046 2.105 2.425 + vertex 0.88075 2.09771 2.42181 + endloop + endfacet + facet normal 0.922656 -0.355704 0.14893 + outer loop + vertex 0.88075 2.09771 2.42181 + vertex 0.883046 2.105 2.425 + vertex 0.88081 2.0991 2.42475 + endloop + endfacet + facet normal 0.721003 -0.299502 0.624863 + outer loop + vertex 0.883046 2.105 2.425 + vertex 0.880857 2.10335 2.42673 + vertex 0.88081 2.0991 2.42475 + endloop + endfacet + facet normal 0.989506 -0.0699635 0.126428 + outer loop + vertex 0.88081 2.0991 2.42475 + vertex 0.880857 2.10335 2.42673 + vertex 0.880125 2.09731 2.42912 + endloop + endfacet + facet normal 0.975453 -0.0320872 0.217858 + outer loop + vertex 0.880857 2.10335 2.42673 + vertex 0.87957 2.10271 2.4324 + vertex 0.880125 2.09731 2.42912 + endloop + endfacet + facet normal 0.994463 0.0443964 0.0952444 + outer loop + vertex 0.880125 2.09731 2.42912 + vertex 0.87957 2.10271 2.4324 + vertex 0.879608 2.09768 2.43435 + endloop + endfacet + facet normal 0.998092 0.0286913 0.054682 + outer loop + vertex 0.87957 2.10271 2.4324 + vertex 0.879329 2.10161 2.43737 + vertex 0.879608 2.09768 2.43435 + endloop + endfacet + facet normal 0.99419 -0.0118536 0.106989 + outer loop + vertex 0.879329 2.10161 2.43737 + vertex 0.879095 2.09931 2.4393 + vertex 0.879608 2.09768 2.43435 + endloop + endfacet + facet normal 0.991153 -0.128649 -0.0326391 + outer loop + vertex 0.88 2.105 2.44436 + vertex 0.879095 2.09931 2.4393 + vertex 0.879329 2.10161 2.43737 + endloop + endfacet + facet normal 0.692806 -0.202026 -0.692246 + outer loop + vertex 0.881179 2.105 2.475 + vertex 0.878152 2.10161 2.47296 + vertex 0.88 2.105 2.47382 + endloop + endfacet + facet normal 0.658112 -0.142779 -0.739258 + outer loop + vertex 0.881224 2.10297 2.47543 + vertex 0.878152 2.10161 2.47296 + vertex 0.881179 2.105 2.475 + endloop + endfacet + facet normal 0.561307 -0.783803 -0.265684 + outer loop + vertex 0.878002 2.10028 2.47656 + vertex 0.878152 2.10161 2.47296 + vertex 0.881224 2.10297 2.47543 + endloop + endfacet + facet normal 0.563519 -0.784094 -0.260084 + outer loop + vertex 0.881594 2.10188 2.47951 + vertex 0.878002 2.10028 2.47656 + vertex 0.881224 2.10297 2.47543 + endloop + endfacet + facet normal 0.414319 -0.910081 -0.00958056 + outer loop + vertex 0.87855 2.10047 2.48186 + vertex 0.878002 2.10028 2.47656 + vertex 0.881594 2.10188 2.47951 + endloop + endfacet + facet normal 0.32205 -0.935627 -0.144523 + outer loop + vertex 0.882154 2.10145 2.48357 + vertex 0.87855 2.10047 2.48186 + vertex 0.881594 2.10188 2.47951 + endloop + endfacet + facet normal 0.240811 -0.969482 0.0459857 + outer loop + vertex 0.882154 2.10145 2.48357 + vertex 0.881286 2.10138 2.4866 + vertex 0.87855 2.10047 2.48186 + endloop + endfacet + facet normal -0.140229 -0.954565 0.262948 + outer loop + vertex 0.881286 2.10138 2.4866 + vertex 0.878229 2.10163 2.48587 + vertex 0.87855 2.10047 2.48186 + endloop + endfacet + facet normal -0.712975 -0.192599 0.67422 + outer loop + vertex 0.880472 2.10317 2.48869 + vertex 0.881436 2.10194 2.48936 + vertex 0.882461 2.10265 2.49064 + endloop + endfacet + facet normal -0.713664 -0.193709 0.673172 + outer loop + vertex 0.880472 2.10317 2.48869 + vertex 0.878229 2.10163 2.48587 + vertex 0.881436 2.10194 2.48936 + endloop + endfacet + facet normal -0.127334 -0.970695 0.203806 + outer loop + vertex 0.878229 2.10163 2.48587 + vertex 0.881286 2.10138 2.4866 + vertex 0.881436 2.10194 2.48936 + endloop + endfacet + facet normal -0.773391 -0.0312879 0.633157 + outer loop + vertex 0.881436 2.10194 2.48936 + vertex 0.882678 2.10218 2.49089 + vertex 0.882461 2.10265 2.49064 + endloop + endfacet + facet normal 0.590179 0.0626736 0.804836 + outer loop + vertex 0.883046 2.105 2.425 + vertex 0.882515 2.11 2.425 + vertex 0.880857 2.10335 2.42673 + endloop + endfacet + facet normal 0.935033 -0.149189 0.321646 + outer loop + vertex 0.882515 2.11 2.425 + vertex 0.880795 2.11 2.43 + vertex 0.880857 2.10335 2.42673 + endloop + endfacet + facet normal 0.876157 -0.149418 0.458282 + outer loop + vertex 0.878332 2.10712 2.43377 + vertex 0.880795 2.11 2.43 + vertex 0.88 2.11 2.43152 + endloop + endfacet + facet normal 0.81753 0.0516684 0.573564 + outer loop + vertex 0.878332 2.10712 2.43377 + vertex 0.87957 2.10271 2.4324 + vertex 0.880795 2.11 2.43 + endloop + endfacet + facet normal 0.973092 -0.0941545 0.210304 + outer loop + vertex 0.87957 2.10271 2.4324 + vertex 0.880857 2.10335 2.42673 + vertex 0.880795 2.11 2.43 + endloop + endfacet + facet normal 0.990346 -0.137512 0.0174926 + outer loop + vertex 0.87957 2.10271 2.4324 + vertex 0.88 2.10677 2.44 + vertex 0.879329 2.10161 2.43737 + endloop + endfacet + facet normal 0.91716 0.3275 -0.22707 + outer loop + vertex 0.878332 2.10712 2.43377 + vertex 0.88 2.10677 2.44 + vertex 0.87957 2.10271 2.4324 + endloop + endfacet + facet normal 0.99332 -0.106914 -0.043404 + outer loop + vertex 0.879329 2.10161 2.43737 + vertex 0.88 2.10677 2.44 + vertex 0.88 2.105 2.44436 + endloop + endfacet + facet normal 0.747522 -0.654405 -0.113863 + outer loop + vertex 0.885 2.10736 2.475 + vertex 0.885 2.10649 2.48 + vertex 0.881224 2.10297 2.47543 + endloop + endfacet + facet normal 0.125898 -0.203849 -0.970873 + outer loop + vertex 0.881179 2.105 2.475 + vertex 0.885 2.10736 2.475 + vertex 0.881224 2.10297 2.47543 + endloop + endfacet + facet normal 0.716514 -0.475655 -0.510255 + outer loop + vertex 0.885 2.10649 2.48 + vertex 0.885184 2.10335 2.48318 + vertex 0.881594 2.10188 2.47951 + endloop + endfacet + facet normal 0.795013 -0.564307 -0.222513 + outer loop + vertex 0.881224 2.10297 2.47543 + vertex 0.885 2.10649 2.48 + vertex 0.881594 2.10188 2.47951 + endloop + endfacet + facet normal 0.509785 -0.845153 -0.160737 + outer loop + vertex 0.885184 2.10335 2.48318 + vertex 0.882154 2.10145 2.48357 + vertex 0.881594 2.10188 2.47951 + endloop + endfacet + facet normal -0.355077 0.63981 0.681589 + outer loop + vertex 0.882461 2.10265 2.49064 + vertex 0.883168 2.10268 2.49098 + vertex 0.883944 2.10444 2.48973 + endloop + endfacet + facet normal -0.428178 0.664855 0.612072 + outer loop + vertex 0.882461 2.10265 2.49064 + vertex 0.883944 2.10444 2.48973 + vertex 0.880472 2.10317 2.48869 + endloop + endfacet + facet normal -0.38645 0.356116 0.850787 + outer loop + vertex 0.880472 2.10317 2.48869 + vertex 0.883944 2.10444 2.48973 + vertex 0.879853 2.10615 2.48716 + endloop + endfacet + facet normal -0.427982 0.250879 0.868269 + outer loop + vertex 0.883168 2.10268 2.49098 + vertex 0.882461 2.10265 2.49064 + vertex 0.882678 2.10218 2.49089 + endloop + endfacet + facet normal 0.370548 0.920025 0.127467 + outer loop + vertex 0.882515 2.11 2.425 + vertex 0.88 2.11032 2.43 + vertex 0.880795 2.11 2.43 + endloop + endfacet + facet normal 0.520253 0.828131 0.208652 + outer loop + vertex 0.88 2.11158 2.425 + vertex 0.88 2.11032 2.43 + vertex 0.882515 2.11 2.425 + endloop + endfacet + facet normal -0.553953 0.523226 0.647589 + outer loop + vertex 0.880634 2.11231 2.4838 + vertex 0.878705 2.1119 2.48249 + vertex 0.879046 2.10973 2.48454 + endloop + endfacet + facet normal -0.525785 0.51441 0.677445 + outer loop + vertex 0.879046 2.10973 2.48454 + vertex 0.882611 2.10933 2.4876 + vertex 0.880634 2.11231 2.4838 + endloop + endfacet + facet normal -0.572863 0.396782 0.717212 + outer loop + vertex 0.879046 2.10973 2.48454 + vertex 0.879853 2.10615 2.48716 + vertex 0.882611 2.10933 2.4876 + endloop + endfacet + facet normal -0.435093 0.257468 0.862788 + outer loop + vertex 0.879853 2.10615 2.48716 + vertex 0.883944 2.10444 2.48973 + vertex 0.882611 2.10933 2.4876 + endloop + endfacet + facet normal -0.520101 0.703202 0.48477 + outer loop + vertex 0.881689 2.11506 2.48155 + vertex 0.879584 2.11543 2.47876 + vertex 0.878929 2.11374 2.48051 + endloop + endfacet + facet normal -0.516499 0.655767 0.550635 + outer loop + vertex 0.878929 2.11374 2.48051 + vertex 0.878705 2.1119 2.48249 + vertex 0.880634 2.11231 2.4838 + endloop + endfacet + facet normal -0.520485 0.652176 0.551147 + outer loop + vertex 0.881689 2.11506 2.48155 + vertex 0.878929 2.11374 2.48051 + vertex 0.880634 2.11231 2.4838 + endloop + endfacet + facet normal -0.544387 0.647091 0.533775 + outer loop + vertex 0.881689 2.11506 2.48155 + vertex 0.880634 2.11231 2.4838 + vertex 0.883371 2.11326 2.48545 + endloop + endfacet + facet normal -0.56916 0.625021 0.534233 + outer loop + vertex 0.881689 2.11506 2.48155 + vertex 0.883371 2.11326 2.48545 + vertex 0.883984 2.11528 2.48374 + endloop + endfacet + facet normal -0.568211 0.477238 0.670358 + outer loop + vertex 0.883371 2.11326 2.48545 + vertex 0.880634 2.11231 2.4838 + vertex 0.882611 2.10933 2.4876 + endloop + endfacet + facet normal -0.356608 0.869807 0.34098 + outer loop + vertex 0.885 2.12413 2.47 + vertex 0.88 2.12208 2.47 + vertex 0.885 2.12217 2.475 + endloop + endfacet + facet normal -0.616174 0.501672 0.60717 + outer loop + vertex 0.885 2.12217 2.475 + vertex 0.88 2.12208 2.47 + vertex 0.879659 2.11841 2.47269 + endloop + endfacet + facet normal -0.607119 0.46674 0.643086 + outer loop + vertex 0.885 2.12217 2.475 + vertex 0.879659 2.11841 2.47269 + vertex 0.884997 2.1191 2.47723 + endloop + endfacet + facet normal -0.444022 0.801455 0.400642 + outer loop + vertex 0.884997 2.1191 2.47723 + vertex 0.879659 2.11841 2.47269 + vertex 0.881215 2.1168 2.47763 + endloop + endfacet + facet normal -0.402657 0.817769 0.411243 + outer loop + vertex 0.881689 2.11506 2.48155 + vertex 0.881215 2.1168 2.47763 + vertex 0.879584 2.11543 2.47876 + endloop + endfacet + facet normal -0.446304 0.796842 0.407254 + outer loop + vertex 0.881689 2.11506 2.48155 + vertex 0.88526 2.1169 2.48187 + vertex 0.881215 2.1168 2.47763 + endloop + endfacet + facet normal -0.442985 0.80034 0.404005 + outer loop + vertex 0.88526 2.1169 2.48187 + vertex 0.884997 2.1191 2.47723 + vertex 0.881215 2.1168 2.47763 + endloop + endfacet + facet normal -0.448527 0.80423 0.389919 + outer loop + vertex 0.88526 2.1169 2.48187 + vertex 0.881689 2.11506 2.48155 + vertex 0.883984 2.11528 2.48374 + endloop + endfacet + facet normal -0.0609549 -0.992867 -0.102466 + outer loop + vertex 0.89 0.903868 2.47 + vertex 0.89 0.903352 2.475 + vertex 0.885 0.904175 2.47 + endloop + endfacet + facet normal 0.0780437 -0.968267 -0.237419 + outer loop + vertex 0.89 0.903352 2.475 + vertex 0.88577 0.903758 2.47195 + vertex 0.885 0.904175 2.47 + endloop + endfacet + facet normal -0.259533 -0.947073 0.188934 + outer loop + vertex 0.885497 0.904071 2.47421 + vertex 0.889461 0.903369 2.47613 + vertex 0.887061 0.904213 2.47706 + endloop + endfacet + facet normal -0.22378 -0.968684 0.107582 + outer loop + vertex 0.885497 0.904071 2.47421 + vertex 0.88577 0.903758 2.47195 + vertex 0.889461 0.903369 2.47613 + endloop + endfacet + facet normal -0.0794259 -0.996587 -0.0224934 + outer loop + vertex 0.88577 0.903758 2.47195 + vertex 0.89 0.903352 2.475 + vertex 0.889461 0.903369 2.47613 + endloop + endfacet + facet normal -0.266576 -0.948357 0.171921 + outer loop + vertex 0.889461 0.903369 2.47613 + vertex 0.889946 0.903783 2.47917 + vertex 0.887061 0.904213 2.47706 + endloop + endfacet + facet normal -0.390255 -0.884018 0.25732 + outer loop + vertex 0.885497 0.904071 2.47421 + vertex 0.887061 0.904213 2.47706 + vertex 0.883229 0.90547 2.47557 + endloop + endfacet + facet normal -0.365683 -0.872842 0.323145 + outer loop + vertex 0.887061 0.904213 2.47706 + vertex 0.889946 0.903783 2.47917 + vertex 0.887895 0.905208 2.4807 + endloop + endfacet + facet normal -0.407191 -0.852732 0.327175 + outer loop + vertex 0.887061 0.904213 2.47706 + vertex 0.887895 0.905208 2.4807 + vertex 0.883229 0.90547 2.47557 + endloop + endfacet + facet normal -0.457589 -0.806013 0.375441 + outer loop + vertex 0.883229 0.90547 2.47557 + vertex 0.887895 0.905208 2.4807 + vertex 0.882696 0.90773 2.47977 + endloop + endfacet + facet normal -0.520201 -0.711426 0.472508 + outer loop + vertex 0.882709 0.910025 2.48307 + vertex 0.88769 0.907591 2.48489 + vertex 0.885649 0.9096 2.48567 + endloop + endfacet + facet normal -0.5206 -0.699749 0.489212 + outer loop + vertex 0.882709 0.910025 2.48307 + vertex 0.882696 0.90773 2.47977 + vertex 0.88769 0.907591 2.48489 + endloop + endfacet + facet normal -0.455129 -0.783519 0.423032 + outer loop + vertex 0.882696 0.90773 2.47977 + vertex 0.887895 0.905208 2.4807 + vertex 0.88769 0.907591 2.48489 + endloop + endfacet + facet normal -0.486333 -0.697733 0.525975 + outer loop + vertex 0.88769 0.907591 2.48489 + vertex 0.887754 0.910018 2.48817 + vertex 0.885649 0.9096 2.48567 + endloop + endfacet + facet normal -0.573222 -0.607908 0.549422 + outer loop + vertex 0.882709 0.910025 2.48307 + vertex 0.885649 0.9096 2.48567 + vertex 0.883431 0.911794 2.48578 + endloop + endfacet + facet normal -0.594562 -0.539824 0.595891 + outer loop + vertex 0.888566 0.91182 2.4909 + vertex 0.885906 0.914619 2.49078 + vertex 0.883712 0.914075 2.4881 + endloop + endfacet + facet normal -0.592184 -0.579954 0.559438 + outer loop + vertex 0.887754 0.910018 2.48817 + vertex 0.888566 0.91182 2.4909 + vertex 0.883712 0.914075 2.4881 + endloop + endfacet + facet normal -0.565263 -0.552185 0.612838 + outer loop + vertex 0.887754 0.910018 2.48817 + vertex 0.883712 0.914075 2.4881 + vertex 0.883431 0.911794 2.48578 + endloop + endfacet + facet normal -0.56158 -0.597342 0.572548 + outer loop + vertex 0.887754 0.910018 2.48817 + vertex 0.883431 0.911794 2.48578 + vertex 0.885649 0.9096 2.48567 + endloop + endfacet + facet normal -0.564815 -0.5093 0.649306 + outer loop + vertex 0.888566 0.91182 2.4909 + vertex 0.889473 0.913884 2.4933 + vertex 0.885906 0.914619 2.49078 + endloop + endfacet + facet normal 0.592545 0.608514 -0.527827 + outer loop + vertex 0.89 0.917441 2.475 + vertex 0.887372 0.92 2.475 + vertex 0.89 0.92 2.47795 + endloop + endfacet + facet normal -0.63083 -0.476135 0.612658 + outer loop + vertex 0.883712 0.914075 2.4881 + vertex 0.885906 0.914619 2.49078 + vertex 0.883309 0.916424 2.48951 + endloop + endfacet + facet normal -0.584572 -0.314362 0.747965 + outer loop + vertex 0.885906 0.914619 2.49078 + vertex 0.885313 0.916757 2.49121 + vertex 0.883309 0.916424 2.48951 + endloop + endfacet + facet normal -0.590935 -0.315049 0.742657 + outer loop + vertex 0.885906 0.914619 2.49078 + vertex 0.889473 0.913884 2.4933 + vertex 0.885313 0.916757 2.49121 + endloop + endfacet + facet normal -0.534908 -0.172398 0.827135 + outer loop + vertex 0.889473 0.913884 2.4933 + vertex 0.888212 0.917256 2.49319 + vertex 0.885313 0.916757 2.49121 + endloop + endfacet + facet normal 0.857073 -0.513608 0.0404115 + outer loop + vertex 0.883906 0.923935 2.43114 + vertex 0.883289 0.922988 2.4322 + vertex 0.88339 0.923051 2.43085 + endloop + endfacet + facet normal 0.824347 0.0901391 0.558862 + outer loop + vertex 0.883906 0.923935 2.43114 + vertex 0.883522 0.924737 2.43158 + vertex 0.883289 0.922988 2.4322 + endloop + endfacet + facet normal 0.134853 0.983557 -0.120125 + outer loop + vertex 0.887372 0.92 2.475 + vertex 0.887976 0.920171 2.47708 + vertex 0.89 0.92 2.47795 + endloop + endfacet + facet normal 0.720481 0.641998 -0.262193 + outer loop + vertex 0.887372 0.92 2.475 + vertex 0.885 0.922662 2.475 + vertex 0.887976 0.920171 2.47708 + endloop + endfacet + facet normal 0.321101 0.802766 0.502454 + outer loop + vertex 0.885 0.922662 2.475 + vertex 0.883818 0.921766 2.47719 + vertex 0.887976 0.920171 2.47708 + endloop + endfacet + facet normal 0.354448 0.930524 -0.0921502 + outer loop + vertex 0.887976 0.920171 2.47708 + vertex 0.883818 0.921766 2.47719 + vertex 0.887848 0.920601 2.48093 + endloop + endfacet + facet normal 0.249566 0.967814 0.0324564 + outer loop + vertex 0.887848 0.920601 2.48093 + vertex 0.883818 0.921766 2.47719 + vertex 0.883539 0.921682 2.48184 + endloop + endfacet + facet normal 0.238208 0.970895 -0.0249113 + outer loop + vertex 0.887848 0.920601 2.48093 + vertex 0.883539 0.921682 2.48184 + vertex 0.888195 0.920649 2.48611 + endloop + endfacet + facet normal 0.0601405 0.983206 0.172305 + outer loop + vertex 0.888195 0.920649 2.48611 + vertex 0.883539 0.921682 2.48184 + vertex 0.883836 0.920814 2.48669 + endloop + endfacet + facet normal 0.0644946 0.976194 0.207091 + outer loop + vertex 0.888195 0.920649 2.48611 + vertex 0.883836 0.920814 2.48669 + vertex 0.888777 0.919491 2.49138 + endloop + endfacet + facet normal -0.248557 0.832058 0.495881 + outer loop + vertex 0.888777 0.919491 2.49138 + vertex 0.883836 0.920814 2.48669 + vertex 0.884548 0.919046 2.49001 + endloop + endfacet + facet normal -0.575468 0.221637 0.787219 + outer loop + vertex 0.888212 0.917256 2.49319 + vertex 0.884548 0.919046 2.49001 + vertex 0.885313 0.916757 2.49121 + endloop + endfacet + facet normal -0.296496 0.645103 0.704225 + outer loop + vertex 0.888777 0.919491 2.49138 + vertex 0.884548 0.919046 2.49001 + vertex 0.888212 0.917256 2.49319 + endloop + endfacet + facet normal 0.795894 -0.288248 -0.532415 + outer loop + vertex 0.88339 0.923051 2.43085 + vertex 0.883622 0.924809 2.43024 + vertex 0.883906 0.923935 2.43114 + endloop + endfacet + facet normal 0.916435 0.390089 0.0893178 + outer loop + vertex 0.883906 0.923935 2.43114 + vertex 0.883622 0.924809 2.43024 + vertex 0.883522 0.924737 2.43158 + endloop + endfacet + facet normal 0.171745 -0.232482 -0.957317 + outer loop + vertex 0.89 1.0886 2.55 + vertex 0.888693 1.09092 2.5492 + vertex 0.89 1.09 2.54966 + endloop + endfacet + facet normal 0.551531 0.0237939 -0.833815 + outer loop + vertex 0.89 1.0886 2.55 + vertex 0.889445 1.08811 2.54962 + vertex 0.888693 1.09092 2.5492 + endloop + endfacet + facet normal -0.66463 -0.149341 -0.732095 + outer loop + vertex 0.89 1.09 2.54966 + vertex 0.888502 1.095 2.55 + vertex 0.89 1.095 2.54864 + endloop + endfacet + facet normal 0.442465 0.192124 -0.875964 + outer loop + vertex 0.888693 1.09092 2.5492 + vertex 0.888502 1.095 2.55 + vertex 0.89 1.09 2.54966 + endloop + endfacet + facet normal -0.9624 -0.265385 -0.0579424 + outer loop + vertex 0.888692 1.09058 2.55077 + vertex 0.888693 1.09092 2.5492 + vertex 0.889445 1.08811 2.54962 + endloop + endfacet + facet normal -0.973297 -0.224231 -0.0491215 + outer loop + vertex 0.888692 1.09058 2.55077 + vertex 0.8876 1.0952 2.55133 + vertex 0.888693 1.09092 2.5492 + endloop + endfacet + facet normal -0.820892 0.0722911 -0.566489 + outer loop + vertex 0.8876 1.0952 2.55133 + vertex 0.888502 1.095 2.55 + vertex 0.888693 1.09092 2.5492 + endloop + endfacet + facet normal -0.958612 -0.244503 0.145881 + outer loop + vertex 0.888692 1.09058 2.55077 + vertex 0.888723 1.09202 2.55338 + vertex 0.8876 1.0952 2.55133 + endloop + endfacet + facet normal -0.814029 -0.279213 -0.50931 + outer loop + vertex 0.888502 1.095 2.55 + vertex 0.8876 1.0952 2.55133 + vertex 0.886787 1.1 2.55 + endloop + endfacet + facet normal -0.955064 -0.217626 -0.201227 + outer loop + vertex 0.886787 1.1 2.55 + vertex 0.8876 1.0952 2.55133 + vertex 0.886437 1.09973 2.55195 + endloop + endfacet + facet normal -0.95854 -0.247738 0.140807 + outer loop + vertex 0.88821 1.09502 2.55516 + vertex 0.8876 1.0952 2.55133 + vertex 0.888723 1.09202 2.55338 + endloop + endfacet + facet normal -0.953664 -0.266771 0.139131 + outer loop + vertex 0.88821 1.09502 2.55516 + vertex 0.886995 1.09962 2.55566 + vertex 0.8876 1.0952 2.55133 + endloop + endfacet + facet normal -0.955052 -0.263571 0.135668 + outer loop + vertex 0.886995 1.09962 2.55566 + vertex 0.886437 1.09973 2.55195 + vertex 0.8876 1.0952 2.55133 + endloop + endfacet + facet normal -0.936645 -0.271249 0.221632 + outer loop + vertex 0.88821 1.09502 2.55516 + vertex 0.888522 1.09645 2.55823 + vertex 0.886995 1.09962 2.55566 + endloop + endfacet + facet normal -0.925286 -0.353317 0.137886 + outer loop + vertex 0.885 1.105 2.55082 + vertex 0.885 1.10468 2.55 + vertex 0.886787 1.1 2.55 + endloop + endfacet + facet normal -0.916119 -0.357261 0.18191 + outer loop + vertex 0.885 1.105 2.55082 + vertex 0.886787 1.1 2.55 + vertex 0.88583 1.105 2.555 + endloop + endfacet + facet normal -0.983988 -0.0104049 -0.177929 + outer loop + vertex 0.88583 1.105 2.555 + vertex 0.886787 1.1 2.55 + vertex 0.886437 1.09973 2.55195 + endloop + endfacet + facet normal -0.971117 -0.193084 0.140181 + outer loop + vertex 0.886437 1.09973 2.55195 + vertex 0.886995 1.09962 2.55566 + vertex 0.88583 1.105 2.555 + endloop + endfacet + facet normal -0.963455 -0.226299 -0.143332 + outer loop + vertex 0.88583 1.105 2.555 + vertex 0.886995 1.09962 2.55566 + vertex 0.885883 1.10378 2.55656 + endloop + endfacet + facet normal -0.936636 -0.269513 0.223776 + outer loop + vertex 0.888145 1.0993 2.56009 + vertex 0.886995 1.09962 2.55566 + vertex 0.888522 1.09645 2.55823 + endloop + endfacet + facet normal -0.927608 -0.30262 0.219007 + outer loop + vertex 0.888145 1.0993 2.56009 + vertex 0.886856 1.10329 2.56015 + vertex 0.886995 1.09962 2.55566 + endloop + endfacet + facet normal -0.931535 -0.294999 0.212646 + outer loop + vertex 0.886856 1.10329 2.56015 + vertex 0.885883 1.10378 2.55656 + vertex 0.886995 1.09962 2.55566 + endloop + endfacet + facet normal -0.907643 -0.297339 0.296267 + outer loop + vertex 0.888748 1.10108 2.56373 + vertex 0.886856 1.10329 2.56015 + vertex 0.888145 1.0993 2.56009 + endloop + endfacet + facet normal -0.9061 -0.310553 0.287298 + outer loop + vertex 0.887769 1.10514 2.56502 + vertex 0.886856 1.10329 2.56015 + vertex 0.888748 1.10108 2.56373 + endloop + endfacet + facet normal -0.86867 -0.328183 0.371092 + outer loop + vertex 0.888748 1.10108 2.56373 + vertex 0.889419 1.10327 2.56723 + vertex 0.887769 1.10514 2.56502 + endloop + endfacet + facet normal 0.681952 0.122782 -0.721017 + outer loop + vertex 0.884115 1.1081 2.55391 + vertex 0.885 1.10961 2.555 + vertex 0.88583 1.105 2.555 + endloop + endfacet + facet normal -0.884102 -0.459586 0.0845169 + outer loop + vertex 0.884115 1.1081 2.55391 + vertex 0.88583 1.105 2.555 + vertex 0.884687 1.10767 2.55756 + endloop + endfacet + facet normal -0.953969 -0.251552 -0.163294 + outer loop + vertex 0.884687 1.10767 2.55756 + vertex 0.88583 1.105 2.555 + vertex 0.885883 1.10378 2.55656 + endloop + endfacet + facet normal -0.91974 -0.335404 0.203916 + outer loop + vertex 0.885883 1.10378 2.55656 + vertex 0.886856 1.10329 2.56015 + vertex 0.884687 1.10767 2.55756 + endloop + endfacet + facet normal -0.918653 -0.312755 0.241372 + outer loop + vertex 0.884687 1.10767 2.55756 + vertex 0.886856 1.10329 2.56015 + vertex 0.886071 1.10741 2.56249 + endloop + endfacet + facet normal -0.89326 -0.338729 0.295547 + outer loop + vertex 0.886856 1.10329 2.56015 + vertex 0.887769 1.10514 2.56502 + vertex 0.886071 1.10741 2.56249 + endloop + endfacet + facet normal -0.894271 -0.318507 0.314377 + outer loop + vertex 0.886071 1.10741 2.56249 + vertex 0.887769 1.10514 2.56502 + vertex 0.886768 1.10989 2.56698 + endloop + endfacet + facet normal -0.857075 -0.340549 0.386586 + outer loop + vertex 0.887769 1.10514 2.56502 + vertex 0.888862 1.10683 2.56894 + vertex 0.886768 1.10989 2.56698 + endloop + endfacet + facet normal -0.868721 -0.317741 0.379953 + outer loop + vertex 0.889419 1.10327 2.56723 + vertex 0.888862 1.10683 2.56894 + vertex 0.887769 1.10514 2.56502 + endloop + endfacet + facet normal -0.885432 -0.456923 0.0850371 + outer loop + vertex 0.884115 1.1081 2.55391 + vertex 0.884687 1.10767 2.55756 + vertex 0.883126 1.11016 2.55466 + endloop + endfacet + facet normal -0.890345 -0.44455 0.0982882 + outer loop + vertex 0.882017 1.11303 2.55763 + vertex 0.883126 1.11016 2.55466 + vertex 0.884687 1.10767 2.55756 + endloop + endfacet + facet normal -0.856772 -0.430233 0.284327 + outer loop + vertex 0.882017 1.11303 2.55763 + vertex 0.884687 1.10767 2.55756 + vertex 0.884228 1.11192 2.56261 + endloop + endfacet + facet normal -0.898238 -0.373036 0.232407 + outer loop + vertex 0.884228 1.11192 2.56261 + vertex 0.884687 1.10767 2.55756 + vertex 0.886071 1.10741 2.56249 + endloop + endfacet + facet normal -0.868909 -0.363925 0.335492 + outer loop + vertex 0.886071 1.10741 2.56249 + vertex 0.886768 1.10989 2.56698 + vertex 0.884228 1.11192 2.56261 + endloop + endfacet + facet normal -0.86889 -0.364025 0.335435 + outer loop + vertex 0.884228 1.11192 2.56261 + vertex 0.886768 1.10989 2.56698 + vertex 0.88501 1.11461 2.56756 + endloop + endfacet + facet normal -0.8556 -0.333695 0.395723 + outer loop + vertex 0.8883 1.11024 2.5706 + vertex 0.886768 1.10989 2.56698 + vertex 0.888862 1.10683 2.56894 + endloop + endfacet + facet normal -0.85511 -0.335036 0.395647 + outer loop + vertex 0.8883 1.11024 2.5706 + vertex 0.887263 1.11394 2.57148 + vertex 0.886768 1.10989 2.56698 + endloop + endfacet + facet normal -0.834203 -0.361088 0.416798 + outer loop + vertex 0.887263 1.11394 2.57148 + vertex 0.88501 1.11461 2.56756 + vertex 0.886768 1.10989 2.56698 + endloop + endfacet + facet normal -0.813159 -0.341429 0.471379 + outer loop + vertex 0.8883 1.11024 2.5706 + vertex 0.889039 1.1118 2.573 + vertex 0.887263 1.11394 2.57148 + endloop + endfacet + facet normal -0.831923 -0.490272 0.25988 + outer loop + vertex 0.882017 1.11303 2.55763 + vertex 0.884228 1.11192 2.56261 + vertex 0.881645 1.11565 2.56138 + endloop + endfacet + facet normal -0.823278 -0.43374 0.366173 + outer loop + vertex 0.884228 1.11192 2.56261 + vertex 0.88501 1.11461 2.56756 + vertex 0.882885 1.11646 2.56497 + endloop + endfacet + facet normal -0.814351 -0.438425 0.380285 + outer loop + vertex 0.881645 1.11565 2.56138 + vertex 0.884228 1.11192 2.56261 + vertex 0.882885 1.11646 2.56497 + endloop + endfacet + facet normal -0.827132 -0.404517 0.390151 + outer loop + vertex 0.883711 1.11789 2.56821 + vertex 0.882885 1.11646 2.56497 + vertex 0.88501 1.11461 2.56756 + endloop + endfacet + facet normal -0.813252 -0.404562 0.418271 + outer loop + vertex 0.883711 1.11789 2.56821 + vertex 0.88501 1.11461 2.56756 + vertex 0.885149 1.11832 2.57142 + endloop + endfacet + facet normal -0.825406 -0.391806 0.406439 + outer loop + vertex 0.885149 1.11832 2.57142 + vertex 0.88501 1.11461 2.56756 + vertex 0.887263 1.11394 2.57148 + endloop + endfacet + facet normal -0.806351 -0.314903 0.500634 + outer loop + vertex 0.889487 1.11435 2.57533 + vertex 0.887263 1.11394 2.57148 + vertex 0.889039 1.1118 2.573 + endloop + endfacet + facet normal -0.782561 -0.379172 0.493787 + outer loop + vertex 0.889487 1.11435 2.57533 + vertex 0.887512 1.1181 2.57508 + vertex 0.887263 1.11394 2.57148 + endloop + endfacet + facet normal -0.789356 -0.373277 0.487422 + outer loop + vertex 0.887512 1.1181 2.57508 + vertex 0.885149 1.11832 2.57142 + vertex 0.887263 1.11394 2.57148 + endloop + endfacet + facet normal -0.752115 -0.359268 0.552494 + outer loop + vertex 0.889487 1.11435 2.57533 + vertex 0.890202 1.11752 2.57836 + vertex 0.887512 1.1181 2.57508 + endloop + endfacet + facet normal -0.800876 -0.430537 0.416215 + outer loop + vertex 0.883711 1.11789 2.56821 + vertex 0.885149 1.11832 2.57142 + vertex 0.883373 1.12038 2.57012 + endloop + endfacet + facet normal -0.798573 -0.417724 0.433346 + outer loop + vertex 0.883989 1.12172 2.57255 + vertex 0.883373 1.12038 2.57012 + vertex 0.885149 1.11832 2.57142 + endloop + endfacet + facet normal -0.766481 -0.423318 0.483022 + outer loop + vertex 0.883989 1.12172 2.57255 + vertex 0.885149 1.11832 2.57142 + vertex 0.885602 1.12116 2.57462 + endloop + endfacet + facet normal -0.775751 -0.414093 0.47617 + outer loop + vertex 0.885602 1.12116 2.57462 + vertex 0.885149 1.11832 2.57142 + vertex 0.887512 1.1181 2.57508 + endloop + endfacet + facet normal -0.749462 -0.388757 0.535888 + outer loop + vertex 0.887512 1.1181 2.57508 + vertex 0.887591 1.12236 2.57827 + vertex 0.885602 1.12116 2.57462 + endloop + endfacet + facet normal -0.744423 -0.392219 0.540369 + outer loop + vertex 0.890202 1.11752 2.57836 + vertex 0.887591 1.12236 2.57827 + vertex 0.887512 1.1181 2.57508 + endloop + endfacet + facet normal -0.766651 -0.422651 0.483334 + outer loop + vertex 0.883989 1.12172 2.57255 + vertex 0.885602 1.12116 2.57462 + vertex 0.884127 1.12421 2.57495 + endloop + endfacet + facet normal -0.692481 -0.414372 0.590564 + outer loop + vertex 0.888112 1.12553 2.58109 + vertex 0.886284 1.12837 2.58094 + vertex 0.884037 1.12795 2.57801 + endloop + endfacet + facet normal -0.692411 -0.412429 0.592004 + outer loop + vertex 0.887591 1.12236 2.57827 + vertex 0.888112 1.12553 2.58109 + vertex 0.884037 1.12795 2.57801 + endloop + endfacet + facet normal -0.732795 -0.441522 0.517754 + outer loop + vertex 0.887591 1.12236 2.57827 + vertex 0.884037 1.12795 2.57801 + vertex 0.884127 1.12421 2.57495 + endloop + endfacet + facet normal -0.735746 -0.413356 0.536483 + outer loop + vertex 0.887591 1.12236 2.57827 + vertex 0.884127 1.12421 2.57495 + vertex 0.885602 1.12116 2.57462 + endloop + endfacet + facet normal -0.682783 -0.436073 0.586215 + outer loop + vertex 0.884037 1.12795 2.57801 + vertex 0.886284 1.12837 2.58094 + vertex 0.884424 1.13108 2.58079 + endloop + endfacet + facet normal -0.659055 -0.390307 0.64289 + outer loop + vertex 0.888616 1.12836 2.58344 + vertex 0.885424 1.13319 2.5831 + vertex 0.884424 1.13108 2.58079 + endloop + endfacet + facet normal -0.663548 -0.421119 0.618354 + outer loop + vertex 0.888616 1.12836 2.58344 + vertex 0.884424 1.13108 2.58079 + vertex 0.886284 1.12837 2.58094 + endloop + endfacet + facet normal -0.529742 -0.209353 0.821915 + outer loop + vertex 0.889937 1.14702 2.59229 + vertex 0.889196 1.15256 2.59322 + vertex 0.886482 1.14992 2.5908 + endloop + endfacet + facet normal -0.548869 -0.0326994 0.835269 + outer loop + vertex 0.882394 1.20235 2.59834 + vertex 0.883824 1.19725 2.59907 + vertex 0.886264 1.19974 2.60078 + endloop + endfacet + facet normal -0.548332 -0.0315348 0.835666 + outer loop + vertex 0.886093 1.2047 2.60085 + vertex 0.882394 1.20235 2.59834 + vertex 0.886264 1.19974 2.60078 + endloop + endfacet + facet normal -0.543866 -0.0314243 0.838584 + outer loop + vertex 0.886264 1.19974 2.60078 + vertex 0.889923 1.20218 2.60324 + vertex 0.886093 1.2047 2.60085 + endloop + endfacet + facet normal -0.534745 -0.050072 0.843529 + outer loop + vertex 0.88899 1.19719 2.60235 + vertex 0.889923 1.20218 2.60324 + vertex 0.886264 1.19974 2.60078 + endloop + endfacet + facet normal -0.547511 -0.039561 0.835863 + outer loop + vertex 0.889923 1.20218 2.60324 + vertex 0.888517 1.20724 2.60256 + vertex 0.886093 1.2047 2.60085 + endloop + endfacet + facet normal -0.461502 0.103739 0.881053 + outer loop + vertex 0.885288 1.7541 2.61116 + vertex 0.881922 1.75108 2.60976 + vertex 0.884489 1.7503 2.61119 + endloop + endfacet + facet normal -0.463446 0.0775284 0.882727 + outer loop + vertex 0.882637 1.76048 2.60919 + vertex 0.882319 1.75566 2.60945 + vertex 0.885782 1.75888 2.61098 + endloop + endfacet + facet normal -0.471312 0.0590111 0.87999 + outer loop + vertex 0.886037 1.76379 2.61079 + vertex 0.882637 1.76048 2.60919 + vertex 0.885782 1.75888 2.61098 + endloop + endfacet + facet normal -0.445092 0.0581809 0.893593 + outer loop + vertex 0.885782 1.75888 2.61098 + vertex 0.889315 1.76218 2.61253 + vertex 0.886037 1.76379 2.61079 + endloop + endfacet + facet normal -0.44831 0.0625084 0.89169 + outer loop + vertex 0.888925 1.7571 2.61269 + vertex 0.889315 1.76218 2.61253 + vertex 0.885782 1.75888 2.61098 + endloop + endfacet + facet normal -0.470635 0.0581132 0.880412 + outer loop + vertex 0.882822 1.76537 2.60897 + vertex 0.882637 1.76048 2.60919 + vertex 0.886037 1.76379 2.61079 + endloop + endfacet + facet normal -0.471768 0.0553172 0.879986 + outer loop + vertex 0.886201 1.76874 2.61057 + vertex 0.882822 1.76537 2.60897 + vertex 0.886037 1.76379 2.61079 + endloop + endfacet + facet normal -0.447556 0.0550861 0.892558 + outer loop + vertex 0.886037 1.76379 2.61079 + vertex 0.88959 1.7673 2.61236 + vertex 0.886201 1.76874 2.61057 + endloop + endfacet + facet normal -0.446782 0.0541019 0.893006 + outer loop + vertex 0.889315 1.76218 2.61253 + vertex 0.88959 1.7673 2.61236 + vertex 0.886037 1.76379 2.61079 + endloop + endfacet + facet normal -0.456701 0.151509 0.876624 + outer loop + vertex 0.884762 1.79499 2.60591 + vertex 0.884957 1.79179 2.60656 + vertex 0.888326 1.79647 2.60751 + endloop + endfacet + facet normal -0.474529 0.18033 0.86157 + outer loop + vertex 0.886788 1.82769 2.60081 + vertex 0.889176 1.83023 2.6016 + vertex 0.886611 1.83095 2.60004 + endloop + endfacet + facet normal -0.579666 0.273364 0.767632 + outer loop + vertex 0.883164 1.87123 2.58863 + vertex 0.886887 1.87583 2.58981 + vertex 0.883858 1.87654 2.58727 + endloop + endfacet + facet normal -0.631394 0.360733 0.68645 + outer loop + vertex 0.885627 1.88341 2.58557 + vertex 0.883724 1.88278 2.58415 + vertex 0.883887 1.88051 2.5855 + endloop + endfacet + facet normal -0.607133 0.345412 0.715597 + outer loop + vertex 0.883887 1.88051 2.5855 + vertex 0.887255 1.88043 2.58839 + vertex 0.885627 1.88341 2.58557 + endloop + endfacet + facet normal -0.611824 0.326253 0.720576 + outer loop + vertex 0.883887 1.88051 2.5855 + vertex 0.883858 1.87654 2.58727 + vertex 0.887255 1.88043 2.58839 + endloop + endfacet + facet normal -0.576713 0.282273 0.766632 + outer loop + vertex 0.883858 1.87654 2.58727 + vertex 0.886887 1.87583 2.58981 + vertex 0.887255 1.88043 2.58839 + endloop + endfacet + facet normal -0.627964 0.416456 0.657439 + outer loop + vertex 0.883732 1.88518 2.58264 + vertex 0.883724 1.88278 2.58415 + vertex 0.885627 1.88341 2.58557 + endloop + endfacet + facet normal -0.647754 0.390175 0.654353 + outer loop + vertex 0.886131 1.88715 2.58384 + vertex 0.883732 1.88518 2.58264 + vertex 0.885627 1.88341 2.58557 + endloop + endfacet + facet normal -0.635899 0.393117 0.664147 + outer loop + vertex 0.885627 1.88341 2.58557 + vertex 0.88844 1.88506 2.58729 + vertex 0.886131 1.88715 2.58384 + endloop + endfacet + facet normal -0.624794 0.328746 0.708208 + outer loop + vertex 0.887255 1.88043 2.58839 + vertex 0.88844 1.88506 2.58729 + vertex 0.885627 1.88341 2.58557 + endloop + endfacet + facet normal -0.686917 0.411683 0.598884 + outer loop + vertex 0.886104 1.89185 2.58082 + vertex 0.88375 1.89171 2.57821 + vertex 0.883793 1.889 2.58013 + endloop + endfacet + facet normal -0.658151 0.421142 0.624081 + outer loop + vertex 0.883793 1.889 2.58013 + vertex 0.883732 1.88518 2.58264 + vertex 0.886131 1.88715 2.58384 + endloop + endfacet + facet normal -0.67498 0.396328 0.622355 + outer loop + vertex 0.886104 1.89185 2.58082 + vertex 0.883793 1.889 2.58013 + vertex 0.886131 1.88715 2.58384 + endloop + endfacet + facet normal -0.673379 0.397125 0.623581 + outer loop + vertex 0.886104 1.89185 2.58082 + vertex 0.886131 1.88715 2.58384 + vertex 0.888683 1.88925 2.58526 + endloop + endfacet + facet normal -0.702123 0.356391 0.616448 + outer loop + vertex 0.886104 1.89185 2.58082 + vertex 0.888683 1.88925 2.58526 + vertex 0.888571 1.89198 2.58355 + endloop + endfacet + facet normal -0.661048 0.357753 0.659567 + outer loop + vertex 0.888683 1.88925 2.58526 + vertex 0.886131 1.88715 2.58384 + vertex 0.88844 1.88506 2.58729 + endloop + endfacet + facet normal -0.718611 0.378451 0.583415 + outer loop + vertex 0.885881 1.89732 2.57713 + vertex 0.883609 1.89745 2.57425 + vertex 0.883657 1.89457 2.57618 + endloop + endfacet + facet normal -0.688768 0.405656 0.600868 + outer loop + vertex 0.883657 1.89457 2.57618 + vertex 0.88375 1.89171 2.57821 + vertex 0.886104 1.89185 2.58082 + endloop + endfacet + facet normal -0.713926 0.371033 0.593838 + outer loop + vertex 0.885881 1.89732 2.57713 + vertex 0.883657 1.89457 2.57618 + vertex 0.886104 1.89185 2.58082 + endloop + endfacet + facet normal -0.703655 0.377097 0.602219 + outer loop + vertex 0.885881 1.89732 2.57713 + vertex 0.886104 1.89185 2.58082 + vertex 0.888239 1.8947 2.58153 + endloop + endfacet + facet normal -0.718258 0.356281 0.597636 + outer loop + vertex 0.885881 1.89732 2.57713 + vertex 0.888239 1.8947 2.58153 + vertex 0.887963 1.89738 2.5796 + endloop + endfacet + facet normal -0.698359 0.370608 0.612326 + outer loop + vertex 0.888239 1.8947 2.58153 + vertex 0.886104 1.89185 2.58082 + vertex 0.888571 1.89198 2.58355 + endloop + endfacet + facet normal -0.725886 0.35659 0.58816 + outer loop + vertex 0.883822 1.90029 2.57279 + vertex 0.883609 1.89745 2.57425 + vertex 0.885881 1.89732 2.57713 + endloop + endfacet + facet normal -0.731825 0.34866 0.58555 + outer loop + vertex 0.885897 1.90226 2.57421 + vertex 0.883822 1.90029 2.57279 + vertex 0.885881 1.89732 2.57713 + endloop + endfacet + facet normal -0.72557 0.352033 0.591288 + outer loop + vertex 0.885881 1.89732 2.57713 + vertex 0.888039 1.90028 2.57802 + vertex 0.885897 1.90226 2.57421 + endloop + endfacet + facet normal -0.721057 0.346076 0.600256 + outer loop + vertex 0.887963 1.89738 2.5796 + vertex 0.888039 1.90028 2.57802 + vertex 0.885881 1.89732 2.57713 + endloop + endfacet + facet normal -0.740777 0.375389 0.557075 + outer loop + vertex 0.885786 1.90711 2.57106 + vertex 0.883645 1.90618 2.56883 + vertex 0.884219 1.90384 2.57117 + endloop + endfacet + facet normal -0.731769 0.34847 0.585732 + outer loop + vertex 0.884219 1.90384 2.57117 + vertex 0.883822 1.90029 2.57279 + vertex 0.885897 1.90226 2.57421 + endloop + endfacet + facet normal -0.72027 0.366702 0.588847 + outer loop + vertex 0.885786 1.90711 2.57106 + vertex 0.884219 1.90384 2.57117 + vertex 0.885897 1.90226 2.57421 + endloop + endfacet + facet normal -0.731883 0.359819 0.578686 + outer loop + vertex 0.885786 1.90711 2.57106 + vertex 0.885897 1.90226 2.57421 + vertex 0.887971 1.9047 2.57532 + endloop + endfacet + facet normal -0.734568 0.355781 0.57778 + outer loop + vertex 0.885786 1.90711 2.57106 + vertex 0.887971 1.9047 2.57532 + vertex 0.887723 1.90756 2.57324 + endloop + endfacet + facet normal -0.726858 0.349962 0.590935 + outer loop + vertex 0.887971 1.9047 2.57532 + vertex 0.885897 1.90226 2.57421 + vertex 0.888039 1.90028 2.57802 + endloop + endfacet + facet normal -0.792683 0.403249 0.457214 + outer loop + vertex 0.885767 1.91296 2.56687 + vertex 0.883594 1.91118 2.56467 + vertex 0.884081 1.90904 2.5674 + endloop + endfacet + facet normal -0.739249 0.388267 0.550236 + outer loop + vertex 0.884081 1.90904 2.5674 + vertex 0.883645 1.90618 2.56883 + vertex 0.885786 1.90711 2.57106 + endloop + endfacet + facet normal -0.736721 0.391958 0.55101 + outer loop + vertex 0.885767 1.91296 2.56687 + vertex 0.884081 1.90904 2.5674 + vertex 0.885786 1.90711 2.57106 + endloop + endfacet + facet normal -0.75031 0.383136 0.53874 + outer loop + vertex 0.885767 1.91296 2.56687 + vertex 0.885786 1.90711 2.57106 + vertex 0.887588 1.91023 2.57135 + endloop + endfacet + facet normal -0.782472 0.336943 0.523648 + outer loop + vertex 0.885767 1.91296 2.56687 + vertex 0.887588 1.91023 2.57135 + vertex 0.887634 1.91285 2.56973 + endloop + endfacet + facet normal -0.731929 0.369367 0.57258 + outer loop + vertex 0.887588 1.91023 2.57135 + vertex 0.885786 1.90711 2.57106 + vertex 0.887723 1.90756 2.57324 + endloop + endfacet + facet normal -0.871556 0.374576 0.316359 + outer loop + vertex 0.885058 1.91798 2.56099 + vertex 0.883631 1.91592 2.55949 + vertex 0.883968 1.91405 2.56263 + endloop + endfacet + facet normal -0.792115 0.41817 0.44462 + outer loop + vertex 0.883968 1.91405 2.56263 + vertex 0.883594 1.91118 2.56467 + vertex 0.885767 1.91296 2.56687 + endloop + endfacet + facet normal -0.797731 0.407703 0.444302 + outer loop + vertex 0.883968 1.91405 2.56263 + vertex 0.885767 1.91296 2.56687 + vertex 0.885058 1.91798 2.56099 + endloop + endfacet + facet normal -0.862361 0.328962 0.38486 + outer loop + vertex 0.885058 1.91798 2.56099 + vertex 0.885767 1.91296 2.56687 + vertex 0.887011 1.91865 2.56479 + endloop + endfacet + facet normal -0.789715 0.355216 0.500172 + outer loop + vertex 0.885767 1.91296 2.56687 + vertex 0.888162 1.91566 2.56873 + vertex 0.887011 1.91865 2.56479 + endloop + endfacet + facet normal -0.783657 0.333194 0.524274 + outer loop + vertex 0.887634 1.91285 2.56973 + vertex 0.888162 1.91566 2.56873 + vertex 0.885767 1.91296 2.56687 + endloop + endfacet + facet normal -0.671193 0.426479 0.606313 + outer loop + vertex 0.885361 1.92302 2.556 + vertex 0.885718 1.925 2.555 + vertex 0.885 1.92387 2.555 + endloop + endfacet + facet normal -0.71491 0.382903 0.585055 + outer loop + vertex 0.884213 1.91919 2.5571 + vertex 0.885361 1.92302 2.556 + vertex 0.885 1.92387 2.555 + endloop + endfacet + facet normal -0.871832 0.380689 0.308198 + outer loop + vertex 0.884213 1.91919 2.5571 + vertex 0.883631 1.91592 2.55949 + vertex 0.885058 1.91798 2.56099 + endloop + endfacet + facet normal -0.885605 0.352487 0.302418 + outer loop + vertex 0.884213 1.91919 2.5571 + vertex 0.885058 1.91798 2.56099 + vertex 0.885361 1.92302 2.556 + endloop + endfacet + facet normal -0.908183 0.320724 0.268962 + outer loop + vertex 0.885361 1.92302 2.556 + vertex 0.885058 1.91798 2.56099 + vertex 0.886543 1.92276 2.5603 + endloop + endfacet + facet normal -0.863625 0.323764 0.386431 + outer loop + vertex 0.885058 1.91798 2.56099 + vertex 0.887011 1.91865 2.56479 + vertex 0.886543 1.92276 2.5603 + endloop + endfacet + facet normal -0.888355 0.288767 0.356985 + outer loop + vertex 0.886543 1.92276 2.5603 + vertex 0.887011 1.91865 2.56479 + vertex 0.888079 1.92299 2.56394 + endloop + endfacet + facet normal -0.827025 0.29725 0.47715 + outer loop + vertex 0.887011 1.91865 2.56479 + vertex 0.889021 1.91997 2.56745 + vertex 0.888079 1.92299 2.56394 + endloop + endfacet + facet normal -0.826589 0.305143 0.472905 + outer loop + vertex 0.888162 1.91566 2.56873 + vertex 0.889021 1.91997 2.56745 + vertex 0.887011 1.91865 2.56479 + endloop + endfacet + facet normal -0.606791 0.765043 0.215668 + outer loop + vertex 0.885 1.92584 2.55 + vertex 0.885 1.925 2.55298 + vertex 0.885718 1.925 2.555 + endloop + endfacet + facet normal -0.829116 0.519599 0.206356 + outer loop + vertex 0.885 1.92584 2.55 + vertex 0.885718 1.925 2.555 + vertex 0.887607 1.93 2.55 + endloop + endfacet + facet normal -0.318917 -0.607237 -0.727706 + outer loop + vertex 0.887607 1.93 2.55 + vertex 0.885718 1.925 2.555 + vertex 0.886361 1.92811 2.55213 + endloop + endfacet + facet normal 0.987198 -0.146932 0.0620654 + outer loop + vertex 0.885718 1.925 2.555 + vertex 0.885361 1.92302 2.556 + vertex 0.886361 1.92811 2.55213 + endloop + endfacet + facet normal -0.944241 0.295799 0.144613 + outer loop + vertex 0.886361 1.92811 2.55213 + vertex 0.885361 1.92302 2.556 + vertex 0.886676 1.92733 2.55577 + endloop + endfacet + facet normal -0.916924 0.294097 0.269735 + outer loop + vertex 0.885361 1.92302 2.556 + vertex 0.886543 1.92276 2.5603 + vertex 0.886676 1.92733 2.55577 + endloop + endfacet + facet normal -0.926749 0.27775 0.252966 + outer loop + vertex 0.886676 1.92733 2.55577 + vertex 0.886543 1.92276 2.5603 + vertex 0.887883 1.92725 2.56027 + endloop + endfacet + facet normal -0.841555 0.275209 0.464806 + outer loop + vertex 0.889055 1.92605 2.56389 + vertex 0.888079 1.92299 2.56394 + vertex 0.889569 1.92369 2.56622 + endloop + endfacet + facet normal -0.879544 0.286104 0.380194 + outer loop + vertex 0.889055 1.92605 2.56389 + vertex 0.887883 1.92725 2.56027 + vertex 0.888079 1.92299 2.56394 + endloop + endfacet + facet normal -0.893347 0.268444 0.360372 + outer loop + vertex 0.887883 1.92725 2.56027 + vertex 0.886543 1.92276 2.5603 + vertex 0.888079 1.92299 2.56394 + endloop + endfacet + facet normal -0.841298 0.277419 0.463958 + outer loop + vertex 0.889569 1.92369 2.56622 + vertex 0.888079 1.92299 2.56394 + vertex 0.889021 1.91997 2.56745 + endloop + endfacet + facet normal -0.89366 0.0958048 -0.438399 + outer loop + vertex 0.887607 1.93 2.55 + vertex 0.886361 1.92811 2.55213 + vertex 0.888143 1.935 2.55 + endloop + endfacet + facet normal -0.967556 0.204244 -0.148728 + outer loop + vertex 0.888143 1.935 2.55 + vertex 0.886361 1.92811 2.55213 + vertex 0.887329 1.93248 2.55183 + endloop + endfacet + facet normal -0.966055 0.22271 0.130915 + outer loop + vertex 0.886361 1.92811 2.55213 + vertex 0.886676 1.92733 2.55577 + vertex 0.887329 1.93248 2.55183 + endloop + endfacet + facet normal -0.951896 0.252991 0.172886 + outer loop + vertex 0.887329 1.93248 2.55183 + vertex 0.886676 1.92733 2.55577 + vertex 0.887884 1.93192 2.55571 + endloop + endfacet + facet normal -0.890117 0.26269 0.372405 + outer loop + vertex 0.888626 1.93101 2.5594 + vertex 0.887883 1.92725 2.56027 + vertex 0.889214 1.92896 2.56225 + endloop + endfacet + facet normal -0.937724 0.243174 0.248074 + outer loop + vertex 0.888626 1.93101 2.5594 + vertex 0.887884 1.93192 2.55571 + vertex 0.887883 1.92725 2.56027 + endloop + endfacet + facet normal -0.934336 0.249478 0.254513 + outer loop + vertex 0.887884 1.93192 2.55571 + vertex 0.886676 1.92733 2.55577 + vertex 0.887883 1.92725 2.56027 + endloop + endfacet + facet normal -0.889961 0.259772 0.374816 + outer loop + vertex 0.889214 1.92896 2.56225 + vertex 0.887883 1.92725 2.56027 + vertex 0.889055 1.92605 2.56389 + endloop + endfacet + facet normal -0.942987 0.0675136 -0.32591 + outer loop + vertex 0.888143 1.935 2.55 + vertex 0.887329 1.93248 2.55183 + vertex 0.888501 1.94 2.55 + endloop + endfacet + facet normal -0.866582 0.241403 0.436762 + outer loop + vertex 0.888501 1.94 2.55 + vertex 0.887329 1.93248 2.55183 + vertex 0.888376 1.93644 2.55172 + endloop + endfacet + facet normal -0.933231 0.27692 0.2289 + outer loop + vertex 0.888689 1.93569 2.55443 + vertex 0.887884 1.93192 2.55571 + vertex 0.88887 1.9339 2.55733 + endloop + endfacet + facet normal -0.94689 0.26431 0.183139 + outer loop + vertex 0.888689 1.93569 2.55443 + vertex 0.888376 1.93644 2.55172 + vertex 0.887884 1.93192 2.55571 + endloop + endfacet + facet normal -0.951034 0.256 0.173199 + outer loop + vertex 0.888376 1.93644 2.55172 + vertex 0.887329 1.93248 2.55183 + vertex 0.887884 1.93192 2.55571 + endloop + endfacet + facet normal -0.93283 0.258625 0.250881 + outer loop + vertex 0.88887 1.9339 2.55733 + vertex 0.887884 1.93192 2.55571 + vertex 0.888626 1.93101 2.5594 + endloop + endfacet + facet normal -0.779418 0.417268 -0.467327 + outer loop + vertex 0.89 1.94 2.5475 + vertex 0.888501 1.94 2.55 + vertex 0.89 1.9428 2.55 + endloop + endfacet + facet normal -0.900288 0.312059 0.303482 + outer loop + vertex 0.89 1.9428 2.55 + vertex 0.888376 1.93644 2.55172 + vertex 0.889323 1.93876 2.55215 + endloop + endfacet + facet normal -0.650961 0.348497 0.674388 + outer loop + vertex 0.888501 1.94 2.55 + vertex 0.888376 1.93644 2.55172 + vertex 0.89 1.9428 2.55 + endloop + endfacet + facet normal -0.919203 0.33883 0.200652 + outer loop + vertex 0.889323 1.93876 2.55215 + vertex 0.888376 1.93644 2.55172 + vertex 0.888689 1.93569 2.55443 + endloop + endfacet + facet normal 0.369566 -0.925415 0.0838367 + outer loop + vertex 0.884068 2.10252 2.48694 + vertex 0.881286 2.10138 2.4866 + vertex 0.882154 2.10145 2.48357 + endloop + endfacet + facet normal 0.37066 -0.925673 0.0757589 + outer loop + vertex 0.882909 2.10228 2.48969 + vertex 0.881286 2.10138 2.4866 + vertex 0.884068 2.10252 2.48694 + endloop + endfacet + facet normal 0.183319 -0.965333 0.185811 + outer loop + vertex 0.881436 2.10194 2.48936 + vertex 0.881286 2.10138 2.4866 + vertex 0.882909 2.10228 2.48969 + endloop + endfacet + facet normal 0.234293 -0.97153 -0.0351675 + outer loop + vertex 0.882909 2.10228 2.48969 + vertex 0.882678 2.10218 2.49089 + vertex 0.881436 2.10194 2.48936 + endloop + endfacet + facet normal 0.220058 -0.973618 -0.0603549 + outer loop + vertex 0.89 2.10762 2.48 + vertex 0.89 2.10731 2.485 + vertex 0.885 2.10649 2.48 + endloop + endfacet + facet normal 0.642708 -0.526718 -0.556323 + outer loop + vertex 0.89 2.10731 2.485 + vertex 0.885184 2.10335 2.48318 + vertex 0.885 2.10649 2.48 + endloop + endfacet + facet normal 0.528342 -0.848477 -0.0306947 + outer loop + vertex 0.884068 2.10252 2.48694 + vertex 0.882154 2.10145 2.48357 + vertex 0.885184 2.10335 2.48318 + endloop + endfacet + facet normal 0.415929 -0.906146 -0.0768244 + outer loop + vertex 0.884068 2.10252 2.48694 + vertex 0.885184 2.10335 2.48318 + vertex 0.888637 2.10453 2.48799 + endloop + endfacet + facet normal 0.670718 -0.670075 -0.318021 + outer loop + vertex 0.888637 2.10453 2.48799 + vertex 0.885184 2.10335 2.48318 + vertex 0.89 2.10731 2.485 + endloop + endfacet + facet normal 0.850981 -0.413934 0.323248 + outer loop + vertex 0.882909 2.10228 2.48969 + vertex 0.884068 2.10252 2.48694 + vertex 0.883944 2.10444 2.48973 + endloop + endfacet + facet normal 0.901356 -0.430387 -0.0482103 + outer loop + vertex 0.882909 2.10228 2.48969 + vertex 0.883944 2.10444 2.48973 + vertex 0.883168 2.10268 2.49098 + endloop + endfacet + facet normal 0.222923 -0.797967 0.559958 + outer loop + vertex 0.884068 2.10252 2.48694 + vertex 0.888637 2.10453 2.48799 + vertex 0.883944 2.10444 2.48973 + endloop + endfacet + facet normal -0.375868 -0.112184 0.919858 + outer loop + vertex 0.886398 2.108 2.49117 + vertex 0.883944 2.10444 2.48973 + vertex 0.889031 2.10563 2.49196 + endloop + endfacet + facet normal 0.112181 -0.96053 0.254555 + outer loop + vertex 0.888637 2.10453 2.48799 + vertex 0.889031 2.10563 2.49196 + vertex 0.883944 2.10444 2.48973 + endloop + endfacet + facet normal -0.598019 -0.44221 0.668448 + outer loop + vertex 0.889031 2.10563 2.49196 + vertex 0.889538 2.10765 2.49374 + vertex 0.886398 2.108 2.49117 + endloop + endfacet + facet normal 0.702923 -0.707121 0.0766691 + outer loop + vertex 0.882909 2.10228 2.48969 + vertex 0.883168 2.10268 2.49098 + vertex 0.882678 2.10218 2.49089 + endloop + endfacet + facet normal -0.650154 0.147626 0.745323 + outer loop + vertex 0.882611 2.10933 2.4876 + vertex 0.883944 2.10444 2.48973 + vertex 0.886398 2.108 2.49117 + endloop + endfacet + facet normal -0.58725 0.320517 0.743241 + outer loop + vertex 0.885832 2.11156 2.48919 + vertex 0.882611 2.10933 2.4876 + vertex 0.886398 2.108 2.49117 + endloop + endfacet + facet normal -0.688264 0.266344 0.674799 + outer loop + vertex 0.886398 2.108 2.49117 + vertex 0.88868 2.11026 2.4926 + vertex 0.885832 2.11156 2.48919 + endloop + endfacet + facet normal -0.619303 0.134056 0.773624 + outer loop + vertex 0.889538 2.10765 2.49374 + vertex 0.88868 2.11026 2.4926 + vertex 0.886398 2.108 2.49117 + endloop + endfacet + facet normal -0.539716 0.63335 0.554593 + outer loop + vertex 0.886413 2.11484 2.4866 + vertex 0.883984 2.11528 2.48374 + vertex 0.883371 2.11326 2.48545 + endloop + endfacet + facet normal -0.627989 0.463897 0.624843 + outer loop + vertex 0.883371 2.11326 2.48545 + vertex 0.882611 2.10933 2.4876 + vertex 0.885832 2.11156 2.48919 + endloop + endfacet + facet normal -0.534478 0.579114 0.615598 + outer loop + vertex 0.886413 2.11484 2.4866 + vertex 0.883371 2.11326 2.48545 + vertex 0.885832 2.11156 2.48919 + endloop + endfacet + facet normal -0.613787 0.552493 0.56393 + outer loop + vertex 0.886413 2.11484 2.4866 + vertex 0.885832 2.11156 2.48919 + vertex 0.888656 2.11332 2.49053 + endloop + endfacet + facet normal -0.567817 0.605104 0.558062 + outer loop + vertex 0.886413 2.11484 2.4866 + vertex 0.888656 2.11332 2.49053 + vertex 0.889044 2.11524 2.48885 + endloop + endfacet + facet normal -0.596652 0.446428 0.666865 + outer loop + vertex 0.888656 2.11332 2.49053 + vertex 0.885832 2.11156 2.48919 + vertex 0.88868 2.11026 2.4926 + endloop + endfacet + facet normal -0.443186 0.791407 0.421024 + outer loop + vertex 0.89 2.12497 2.475 + vertex 0.885 2.12217 2.475 + vertex 0.89 2.12231 2.48 + endloop + endfacet + facet normal -0.636723 0.452958 0.624029 + outer loop + vertex 0.89 2.12231 2.48 + vertex 0.885 2.12217 2.475 + vertex 0.884997 2.1191 2.47723 + endloop + endfacet + facet normal -0.637944 0.461142 0.616746 + outer loop + vertex 0.89 2.12231 2.48 + vertex 0.884997 2.1191 2.47723 + vertex 0.889797 2.1193 2.48204 + endloop + endfacet + facet normal -0.439707 0.801873 0.404546 + outer loop + vertex 0.889797 2.1193 2.48204 + vertex 0.884997 2.1191 2.47723 + vertex 0.88526 2.1169 2.48187 + endloop + endfacet + facet normal -0.377985 0.811952 0.444816 + outer loop + vertex 0.886413 2.11484 2.4866 + vertex 0.88526 2.1169 2.48187 + vertex 0.883984 2.11528 2.48374 + endloop + endfacet + facet normal -0.459468 0.768264 0.445712 + outer loop + vertex 0.886413 2.11484 2.4866 + vertex 0.890068 2.11693 2.48678 + vertex 0.88526 2.1169 2.48187 + endloop + endfacet + facet normal -0.436339 0.794215 0.422883 + outer loop + vertex 0.890068 2.11693 2.48678 + vertex 0.889797 2.1193 2.48204 + vertex 0.88526 2.1169 2.48187 + endloop + endfacet + facet normal -0.466911 0.784463 0.408182 + outer loop + vertex 0.890068 2.11693 2.48678 + vertex 0.886413 2.11484 2.4866 + vertex 0.889044 2.11524 2.48885 + endloop + endfacet + facet normal -0.137813 -0.978712 0.15209 + outer loop + vertex 0.895 0.902648 2.475 + vertex 0.895 0.903425 2.48 + vertex 0.89 0.903352 2.475 + endloop + endfacet + facet normal -0.000476107 -0.999886 0.0150653 + outer loop + vertex 0.895 0.903425 2.48 + vertex 0.889461 0.903369 2.47613 + vertex 0.89 0.903352 2.475 + endloop + endfacet + facet normal -0.238483 -0.946652 0.216741 + outer loop + vertex 0.889946 0.903783 2.47917 + vertex 0.894153 0.903155 2.48105 + vertex 0.891843 0.903967 2.48206 + endloop + endfacet + facet normal -0.218014 -0.961727 0.165983 + outer loop + vertex 0.889946 0.903783 2.47917 + vertex 0.889461 0.903369 2.47613 + vertex 0.894153 0.903155 2.48105 + endloop + endfacet + facet normal 0.118804 -0.980569 -0.156107 + outer loop + vertex 0.889461 0.903369 2.47613 + vertex 0.895 0.903425 2.48 + vertex 0.894153 0.903155 2.48105 + endloop + endfacet + facet normal -0.250779 -0.949105 0.190552 + outer loop + vertex 0.894153 0.903155 2.48105 + vertex 0.894806 0.903607 2.48417 + vertex 0.891843 0.903967 2.48206 + endloop + endfacet + facet normal -0.379777 -0.873431 0.304775 + outer loop + vertex 0.889946 0.903783 2.47917 + vertex 0.891843 0.903967 2.48206 + vertex 0.887895 0.905208 2.4807 + endloop + endfacet + facet normal -0.350591 -0.870938 0.344315 + outer loop + vertex 0.891843 0.903967 2.48206 + vertex 0.894806 0.903607 2.48417 + vertex 0.892834 0.905017 2.48572 + endloop + endfacet + facet normal -0.388626 -0.852598 0.349351 + outer loop + vertex 0.891843 0.903967 2.48206 + vertex 0.892834 0.905017 2.48572 + vertex 0.887895 0.905208 2.4807 + endloop + endfacet + facet normal -0.459559 -0.781627 0.42174 + outer loop + vertex 0.887895 0.905208 2.4807 + vertex 0.892834 0.905017 2.48572 + vertex 0.88769 0.907591 2.48489 + endloop + endfacet + facet normal -0.525924 -0.698135 0.485811 + outer loop + vertex 0.887754 0.910018 2.48817 + vertex 0.892744 0.907467 2.4899 + vertex 0.890827 0.909483 2.49073 + endloop + endfacet + facet normal -0.525481 -0.678901 0.512799 + outer loop + vertex 0.887754 0.910018 2.48817 + vertex 0.88769 0.907591 2.48489 + vertex 0.892744 0.907467 2.4899 + endloop + endfacet + facet normal -0.457721 -0.771313 0.442231 + outer loop + vertex 0.88769 0.907591 2.48489 + vertex 0.892834 0.905017 2.48572 + vertex 0.892744 0.907467 2.4899 + endloop + endfacet + facet normal -0.492694 -0.686519 0.534737 + outer loop + vertex 0.892744 0.907467 2.4899 + vertex 0.892953 0.909914 2.49324 + vertex 0.890827 0.909483 2.49073 + endloop + endfacet + facet normal -0.572827 -0.595093 0.563678 + outer loop + vertex 0.887754 0.910018 2.48817 + vertex 0.890827 0.909483 2.49073 + vertex 0.888566 0.91182 2.4909 + endloop + endfacet + facet normal -0.605808 -0.377591 0.700301 + outer loop + vertex 0.894028 0.911795 2.49612 + vertex 0.891906 0.915206 2.49612 + vertex 0.889473 0.913884 2.4933 + endloop + endfacet + facet normal -0.607398 -0.541969 0.580807 + outer loop + vertex 0.892953 0.909914 2.49324 + vertex 0.894028 0.911795 2.49612 + vertex 0.889473 0.913884 2.4933 + endloop + endfacet + facet normal -0.566964 -0.507664 0.648713 + outer loop + vertex 0.892953 0.909914 2.49324 + vertex 0.889473 0.913884 2.4933 + vertex 0.888566 0.91182 2.4909 + endloop + endfacet + facet normal -0.56468 -0.588302 0.578823 + outer loop + vertex 0.892953 0.909914 2.49324 + vertex 0.888566 0.91182 2.4909 + vertex 0.890827 0.909483 2.49073 + endloop + endfacet + facet normal -0.641983 -0.40004 0.654084 + outer loop + vertex 0.894028 0.911795 2.49612 + vertex 0.89566 0.913376 2.49869 + vertex 0.891906 0.915206 2.49612 + endloop + endfacet + facet normal 0.586361 0.660408 -0.469085 + outer loop + vertex 0.895 0.917379 2.48 + vertex 0.892048 0.92 2.48 + vertex 0.895 0.92 2.48369 + endloop + endfacet + facet normal -0.680101 -0.231122 0.695733 + outer loop + vertex 0.888212 0.917256 2.49319 + vertex 0.889473 0.913884 2.4933 + vertex 0.891906 0.915206 2.49612 + endloop + endfacet + facet normal -0.598193 0.0638701 0.798802 + outer loop + vertex 0.891093 0.917738 2.49531 + vertex 0.888212 0.917256 2.49319 + vertex 0.891906 0.915206 2.49612 + endloop + endfacet + facet normal -0.677172 0.018235 0.735599 + outer loop + vertex 0.891906 0.915206 2.49612 + vertex 0.894095 0.916497 2.49811 + vertex 0.891093 0.917738 2.49531 + endloop + endfacet + facet normal -0.609028 -0.160503 0.776739 + outer loop + vertex 0.89566 0.913376 2.49869 + vertex 0.894095 0.916497 2.49811 + vertex 0.891906 0.915206 2.49612 + endloop + endfacet + facet normal 0.145183 0.978715 -0.145048 + outer loop + vertex 0.89 0.92 2.47795 + vertex 0.887976 0.920171 2.47708 + vertex 0.892048 0.92 2.48 + endloop + endfacet + facet normal -0.32861 0.907142 0.262886 + outer loop + vertex 0.892048 0.92 2.48 + vertex 0.891764 0.919649 2.48085 + vertex 0.895 0.92 2.48369 + endloop + endfacet + facet normal -0.189325 0.928926 0.318203 + outer loop + vertex 0.892048 0.92 2.48 + vertex 0.887976 0.920171 2.47708 + vertex 0.891764 0.919649 2.48085 + endloop + endfacet + facet normal 0.233181 0.967249 -0.100283 + outer loop + vertex 0.887976 0.920171 2.47708 + vertex 0.887848 0.920601 2.48093 + vertex 0.891764 0.919649 2.48085 + endloop + endfacet + facet normal 0.233345 0.967616 -0.0962785 + outer loop + vertex 0.891764 0.919649 2.48085 + vertex 0.887848 0.920601 2.48093 + vertex 0.892316 0.919905 2.48476 + endloop + endfacet + facet normal 0.171037 0.98505 -0.020544 + outer loop + vertex 0.892316 0.919905 2.48476 + vertex 0.887848 0.920601 2.48093 + vertex 0.888195 0.920649 2.48611 + endloop + endfacet + facet normal 0.175607 0.984441 -0.0061927 + outer loop + vertex 0.892316 0.919905 2.48476 + vertex 0.888195 0.920649 2.48611 + vertex 0.893387 0.91975 2.49048 + endloop + endfacet + facet normal -0.0125974 0.976391 0.215643 + outer loop + vertex 0.893387 0.91975 2.49048 + vertex 0.888195 0.920649 2.48611 + vertex 0.888777 0.919491 2.49138 + endloop + endfacet + facet normal -0.533311 0.60963 0.586456 + outer loop + vertex 0.891093 0.917738 2.49531 + vertex 0.888777 0.919491 2.49138 + vertex 0.888212 0.917256 2.49319 + endloop + endfacet + facet normal -0.380556 0.740008 0.554586 + outer loop + vertex 0.891093 0.917738 2.49531 + vertex 0.893817 0.918722 2.49587 + vertex 0.888777 0.919491 2.49138 + endloop + endfacet + facet normal -0.018141 0.981835 0.188867 + outer loop + vertex 0.893817 0.918722 2.49587 + vertex 0.893387 0.91975 2.49048 + vertex 0.888777 0.919491 2.49138 + endloop + endfacet + facet normal -0.368283 0.636094 0.67805 + outer loop + vertex 0.893817 0.918722 2.49587 + vertex 0.891093 0.917738 2.49531 + vertex 0.894095 0.916497 2.49811 + endloop + endfacet + facet normal -0.487732 -0.489946 -0.722545 + outer loop + vertex 0.895 1.07326 2.55 + vertex 0.893385 1.07587 2.54932 + vertex 0.895 1.075 2.54882 + endloop + endfacet + facet normal 0.145455 -0.163784 -0.975714 + outer loop + vertex 0.895 1.07326 2.55 + vertex 0.89423 1.07313 2.54991 + vertex 0.893385 1.07587 2.54932 + endloop + endfacet + facet normal -0.546268 -0.089942 -0.832767 + outer loop + vertex 0.895 1.075 2.54882 + vertex 0.892378 1.08 2.55 + vertex 0.895 1.08 2.54828 + endloop + endfacet + facet normal -0.246557 0.0982289 -0.964137 + outer loop + vertex 0.893385 1.07587 2.54932 + vertex 0.892378 1.08 2.55 + vertex 0.895 1.075 2.54882 + endloop + endfacet + facet normal -0.951605 -0.303454 -0.0486238 + outer loop + vertex 0.893399 1.07554 2.55109 + vertex 0.893385 1.07587 2.54932 + vertex 0.89423 1.07313 2.54991 + endloop + endfacet + facet normal -0.962302 -0.268697 -0.0421424 + outer loop + vertex 0.893399 1.07554 2.55109 + vertex 0.892189 1.07982 2.55141 + vertex 0.893385 1.07587 2.54932 + endloop + endfacet + facet normal -0.965346 -0.209831 -0.155174 + outer loop + vertex 0.892189 1.07982 2.55141 + vertex 0.892378 1.08 2.55 + vertex 0.893385 1.07587 2.54932 + endloop + endfacet + facet normal -0.949335 -0.279169 0.144318 + outer loop + vertex 0.893399 1.07554 2.55109 + vertex 0.893396 1.07679 2.55349 + vertex 0.892189 1.07982 2.55141 + endloop + endfacet + facet normal -0.950365 -0.266668 -0.160293 + outer loop + vertex 0.892378 1.08 2.55 + vertex 0.892189 1.07982 2.55141 + vertex 0.890975 1.085 2.55 + endloop + endfacet + facet normal -0.94904 -0.267908 -0.165975 + outer loop + vertex 0.890975 1.085 2.55 + vertex 0.892189 1.07982 2.55141 + vertex 0.891037 1.08371 2.55173 + endloop + endfacet + facet normal -0.949805 -0.270148 0.157769 + outer loop + vertex 0.892898 1.07952 2.55516 + vertex 0.892189 1.07982 2.55141 + vertex 0.893396 1.07679 2.55349 + endloop + endfacet + facet normal -0.946172 -0.283588 0.156003 + outer loop + vertex 0.892898 1.07952 2.55516 + vertex 0.891713 1.08349 2.55519 + vertex 0.892189 1.07982 2.55141 + endloop + endfacet + facet normal -0.941889 -0.292499 0.165195 + outer loop + vertex 0.891713 1.08349 2.55519 + vertex 0.891037 1.08371 2.55173 + vertex 0.892189 1.07982 2.55141 + endloop + endfacet + facet normal -0.92584 -0.27825 0.255728 + outer loop + vertex 0.893403 1.08123 2.55885 + vertex 0.891713 1.08349 2.55519 + vertex 0.892898 1.07952 2.55516 + endloop + endfacet + facet normal -0.925462 -0.281469 0.253564 + outer loop + vertex 0.892434 1.08575 2.56033 + vertex 0.891713 1.08349 2.55519 + vertex 0.893403 1.08123 2.55885 + endloop + endfacet + facet normal -0.898315 -0.298248 0.322611 + outer loop + vertex 0.893403 1.08123 2.55885 + vertex 0.894032 1.08323 2.56245 + vertex 0.892434 1.08575 2.56033 + endloop + endfacet + facet normal 0.480142 0.13004 -0.867499 + outer loop + vertex 0.889445 1.08811 2.54962 + vertex 0.89 1.0886 2.55 + vertex 0.890975 1.085 2.55 + endloop + endfacet + facet normal -0.897607 -0.430864 0.0930472 + outer loop + vertex 0.889445 1.08811 2.54962 + vertex 0.890975 1.085 2.55 + vertex 0.890009 1.08762 2.5528 + endloop + endfacet + facet normal -0.967201 -0.21896 -0.128762 + outer loop + vertex 0.890009 1.08762 2.5528 + vertex 0.890975 1.085 2.55 + vertex 0.891037 1.08371 2.55173 + endloop + endfacet + facet normal -0.941688 -0.29319 0.165113 + outer loop + vertex 0.891037 1.08371 2.55173 + vertex 0.891713 1.08349 2.55519 + vertex 0.890009 1.08762 2.5528 + endloop + endfacet + facet normal -0.941214 -0.274905 0.196325 + outer loop + vertex 0.890009 1.08762 2.5528 + vertex 0.891713 1.08349 2.55519 + vertex 0.890945 1.08758 2.55724 + endloop + endfacet + facet normal -0.916334 -0.303013 0.261752 + outer loop + vertex 0.891713 1.08349 2.55519 + vertex 0.892434 1.08575 2.56033 + vertex 0.890945 1.08758 2.55724 + endloop + endfacet + facet normal -0.918646 -0.285159 0.273447 + outer loop + vertex 0.890945 1.08758 2.55724 + vertex 0.892434 1.08575 2.56033 + vertex 0.891293 1.08945 2.56036 + endloop + endfacet + facet normal -0.896522 -0.279157 0.343975 + outer loop + vertex 0.893718 1.08615 2.564 + vertex 0.892434 1.08575 2.56033 + vertex 0.894032 1.08323 2.56245 + endloop + endfacet + facet normal -0.89801 -0.27434 0.343972 + outer loop + vertex 0.893718 1.08615 2.564 + vertex 0.892629 1.08978 2.56405 + vertex 0.892434 1.08575 2.56033 + endloop + endfacet + facet normal -0.895148 -0.278361 0.348175 + outer loop + vertex 0.892629 1.08978 2.56405 + vertex 0.891293 1.08945 2.56036 + vertex 0.892434 1.08575 2.56033 + endloop + endfacet + facet normal -0.86683 -0.26604 0.421698 + outer loop + vertex 0.893718 1.08615 2.564 + vertex 0.894414 1.0882 2.56673 + vertex 0.892629 1.08978 2.56405 + endloop + endfacet + facet normal -0.93462 -0.336864 0.114052 + outer loop + vertex 0.889445 1.08811 2.54962 + vertex 0.890009 1.08762 2.5528 + vertex 0.888692 1.09058 2.55077 + endloop + endfacet + facet normal -0.938715 -0.297177 0.174641 + outer loop + vertex 0.888723 1.09202 2.55338 + vertex 0.888692 1.09058 2.55077 + vertex 0.890009 1.08762 2.5528 + endloop + endfacet + facet normal -0.927544 -0.30016 0.222633 + outer loop + vertex 0.888723 1.09202 2.55338 + vertex 0.890009 1.08762 2.5528 + vertex 0.889747 1.09207 2.55772 + endloop + endfacet + facet normal -0.941967 -0.272183 0.196503 + outer loop + vertex 0.889747 1.09207 2.55772 + vertex 0.890009 1.08762 2.5528 + vertex 0.890945 1.08758 2.55724 + endloop + endfacet + facet normal -0.923465 -0.274788 0.267775 + outer loop + vertex 0.890945 1.08758 2.55724 + vertex 0.891293 1.08945 2.56036 + vertex 0.889747 1.09207 2.55772 + endloop + endfacet + facet normal -0.923167 -0.251868 0.290387 + outer loop + vertex 0.889747 1.09207 2.55772 + vertex 0.891293 1.08945 2.56036 + vertex 0.891045 1.09248 2.56219 + endloop + endfacet + facet normal -0.893291 -0.28442 0.348047 + outer loop + vertex 0.891293 1.08945 2.56036 + vertex 0.892629 1.08978 2.56405 + vertex 0.891045 1.09248 2.56219 + endloop + endfacet + facet normal -0.889313 -0.265127 0.372599 + outer loop + vertex 0.891045 1.09248 2.56219 + vertex 0.892629 1.08978 2.56405 + vertex 0.891991 1.09498 2.56623 + endloop + endfacet + facet normal -0.852481 -0.287427 0.436648 + outer loop + vertex 0.892629 1.08978 2.56405 + vertex 0.894026 1.09206 2.56828 + vertex 0.891991 1.09498 2.56623 + endloop + endfacet + facet normal -0.866907 -0.258818 0.426012 + outer loop + vertex 0.894414 1.0882 2.56673 + vertex 0.894026 1.09206 2.56828 + vertex 0.892629 1.08978 2.56405 + endloop + endfacet + facet normal -0.930068 -0.29187 0.223127 + outer loop + vertex 0.888723 1.09202 2.55338 + vertex 0.889747 1.09207 2.55772 + vertex 0.88821 1.09502 2.55516 + endloop + endfacet + facet normal -0.930193 -0.287314 0.228455 + outer loop + vertex 0.888522 1.09645 2.55823 + vertex 0.88821 1.09502 2.55516 + vertex 0.889747 1.09207 2.55772 + endloop + endfacet + facet normal -0.911283 -0.289506 0.29283 + outer loop + vertex 0.888522 1.09645 2.55823 + vertex 0.889747 1.09207 2.55772 + vertex 0.8898 1.0965 2.56226 + endloop + endfacet + facet normal -0.912756 -0.287152 0.290551 + outer loop + vertex 0.8898 1.0965 2.56226 + vertex 0.889747 1.09207 2.55772 + vertex 0.891045 1.09248 2.56219 + endloop + endfacet + facet normal -0.882049 -0.279129 0.379575 + outer loop + vertex 0.891045 1.09248 2.56219 + vertex 0.891991 1.09498 2.56623 + vertex 0.8898 1.0965 2.56226 + endloop + endfacet + facet normal -0.878733 -0.303522 0.368378 + outer loop + vertex 0.8898 1.0965 2.56226 + vertex 0.891991 1.09498 2.56623 + vertex 0.890602 1.09974 2.56684 + endloop + endfacet + facet normal -0.849083 -0.274939 0.451073 + outer loop + vertex 0.893594 1.09577 2.56973 + vertex 0.891991 1.09498 2.56623 + vertex 0.894026 1.09206 2.56828 + endloop + endfacet + facet normal -0.840713 -0.29763 0.452347 + outer loop + vertex 0.893594 1.09577 2.56973 + vertex 0.892554 1.09906 2.56996 + vertex 0.891991 1.09498 2.56623 + endloop + endfacet + facet normal -0.836366 -0.302576 0.457099 + outer loop + vertex 0.892554 1.09906 2.56996 + vertex 0.890602 1.09974 2.56684 + vertex 0.891991 1.09498 2.56623 + endloop + endfacet + facet normal -0.811893 -0.292245 0.505394 + outer loop + vertex 0.893594 1.09577 2.56973 + vertex 0.89431 1.09814 2.57225 + vertex 0.892554 1.09906 2.56996 + endloop + endfacet + facet normal -0.905262 -0.309356 0.291205 + outer loop + vertex 0.888522 1.09645 2.55823 + vertex 0.8898 1.0965 2.56226 + vertex 0.888145 1.0993 2.56009 + endloop + endfacet + facet normal -0.868345 -0.320461 0.378525 + outer loop + vertex 0.8898 1.0965 2.56226 + vertex 0.890602 1.09974 2.56684 + vertex 0.888748 1.10108 2.56373 + endloop + endfacet + facet normal -0.904868 -0.30328 0.298722 + outer loop + vertex 0.888145 1.0993 2.56009 + vertex 0.8898 1.0965 2.56226 + vertex 0.888748 1.10108 2.56373 + endloop + endfacet + facet normal -0.866687 -0.331497 0.372779 + outer loop + vertex 0.889419 1.10327 2.56723 + vertex 0.888748 1.10108 2.56373 + vertex 0.890602 1.09974 2.56684 + endloop + endfacet + facet normal -0.824249 -0.327033 0.462236 + outer loop + vertex 0.889419 1.10327 2.56723 + vertex 0.890602 1.09974 2.56684 + vertex 0.891248 1.10416 2.57112 + endloop + endfacet + facet normal -0.833812 -0.316216 0.452509 + outer loop + vertex 0.891248 1.10416 2.57112 + vertex 0.890602 1.09974 2.56684 + vertex 0.892554 1.09906 2.56996 + endloop + endfacet + facet normal -0.811715 -0.294583 0.504321 + outer loop + vertex 0.89431 1.09814 2.57225 + vertex 0.893794 1.10184 2.57358 + vertex 0.892554 1.09906 2.56996 + endloop + endfacet + facet normal -0.814845 -0.349005 0.462842 + outer loop + vertex 0.888862 1.10683 2.56894 + vertex 0.889419 1.10327 2.56723 + vertex 0.891248 1.10416 2.57112 + endloop + endfacet + facet normal -0.814792 -0.348682 0.46318 + outer loop + vertex 0.889926 1.10882 2.57231 + vertex 0.888862 1.10683 2.56894 + vertex 0.891248 1.10416 2.57112 + endloop + endfacet + facet normal -0.777194 -0.345366 0.526015 + outer loop + vertex 0.893162 1.10553 2.57485 + vertex 0.891858 1.1085 2.57487 + vertex 0.891248 1.10416 2.57112 + endloop + endfacet + facet normal -0.768125 -0.353454 0.533905 + outer loop + vertex 0.891858 1.1085 2.57487 + vertex 0.889926 1.10882 2.57231 + vertex 0.891248 1.10416 2.57112 + endloop + endfacet + facet normal -0.758707 -0.337494 0.55719 + outer loop + vertex 0.893162 1.10553 2.57485 + vertex 0.893775 1.10826 2.57734 + vertex 0.891858 1.1085 2.57487 + endloop + endfacet + facet normal -0.806831 -0.36079 0.467818 + outer loop + vertex 0.888862 1.10683 2.56894 + vertex 0.889926 1.10882 2.57231 + vertex 0.8883 1.11024 2.5706 + endloop + endfacet + facet normal -0.806558 -0.351077 0.475615 + outer loop + vertex 0.889039 1.1118 2.573 + vertex 0.8883 1.11024 2.5706 + vertex 0.889926 1.10882 2.57231 + endloop + endfacet + facet normal -0.772333 -0.353133 0.528015 + outer loop + vertex 0.889039 1.1118 2.573 + vertex 0.889926 1.10882 2.57231 + vertex 0.890539 1.11132 2.57487 + endloop + endfacet + facet normal -0.766792 -0.358831 0.532231 + outer loop + vertex 0.890539 1.11132 2.57487 + vertex 0.889926 1.10882 2.57231 + vertex 0.891858 1.1085 2.57487 + endloop + endfacet + facet normal -0.746366 -0.349227 0.566549 + outer loop + vertex 0.891858 1.1085 2.57487 + vertex 0.89248 1.11271 2.57829 + vertex 0.890539 1.11132 2.57487 + endloop + endfacet + facet normal -0.758247 -0.339432 0.556639 + outer loop + vertex 0.893775 1.10826 2.57734 + vertex 0.89248 1.11271 2.57829 + vertex 0.891858 1.1085 2.57487 + endloop + endfacet + facet normal -0.773298 -0.347694 0.530207 + outer loop + vertex 0.889039 1.1118 2.573 + vertex 0.890539 1.11132 2.57487 + vertex 0.889487 1.11435 2.57533 + endloop + endfacet + facet normal -0.748277 -0.362864 0.555347 + outer loop + vertex 0.89248 1.11271 2.57829 + vertex 0.890202 1.11752 2.57836 + vertex 0.889487 1.11435 2.57533 + endloop + endfacet + facet normal -0.748871 -0.344591 0.566083 + outer loop + vertex 0.89248 1.11271 2.57829 + vertex 0.889487 1.11435 2.57533 + vertex 0.890539 1.11132 2.57487 + endloop + endfacet + facet normal -0.55061 -0.235173 0.800951 + outer loop + vertex 0.894817 1.13673 2.59251 + vertex 0.893786 1.14228 2.59344 + vertex 0.891312 1.13967 2.59097 + endloop + endfacet + facet normal -0.538453 -0.0311281 0.84208 + outer loop + vertex 0.893016 1.20071 2.60516 + vertex 0.892867 1.20375 2.60518 + vertex 0.889923 1.20218 2.60324 + endloop + endfacet + facet normal -0.550955 -0.0713037 0.831483 + outer loop + vertex 0.893016 1.20071 2.60516 + vertex 0.889923 1.20218 2.60324 + vertex 0.892248 1.19683 2.60432 + endloop + endfacet + facet normal -0.520959 -0.0541334 0.851863 + outer loop + vertex 0.892248 1.19683 2.60432 + vertex 0.889923 1.20218 2.60324 + vertex 0.88899 1.19719 2.60235 + endloop + endfacet + facet normal -0.505283 -0.0143983 0.862833 + outer loop + vertex 0.892867 1.20375 2.60518 + vertex 0.894323 1.20602 2.60607 + vertex 0.891643 1.20744 2.60453 + endloop + endfacet + facet normal -0.539141 -0.0293706 0.841703 + outer loop + vertex 0.892867 1.20375 2.60518 + vertex 0.891643 1.20744 2.60453 + vertex 0.889923 1.20218 2.60324 + endloop + endfacet + facet normal -0.530694 -0.0334007 0.846905 + outer loop + vertex 0.889923 1.20218 2.60324 + vertex 0.891643 1.20744 2.60453 + vertex 0.888517 1.20724 2.60256 + endloop + endfacet + facet normal -0.492956 -0.0250047 0.869695 + outer loop + vertex 0.894323 1.20602 2.60607 + vertex 0.892867 1.20375 2.60518 + vertex 0.895645 1.20239 2.60672 + endloop + endfacet + facet normal -0.428006 0.0612645 0.901697 + outer loop + vertex 0.888925 1.7571 2.61269 + vertex 0.892602 1.76053 2.6142 + vertex 0.889315 1.76218 2.61253 + endloop + endfacet + facet normal -0.430945 0.0544522 0.900734 + outer loop + vertex 0.892602 1.76053 2.6142 + vertex 0.892943 1.76567 2.61405 + vertex 0.889315 1.76218 2.61253 + endloop + endfacet + facet normal -0.43019 0.0534848 0.901153 + outer loop + vertex 0.889315 1.76218 2.61253 + vertex 0.892943 1.76567 2.61405 + vertex 0.88959 1.7673 2.61236 + endloop + endfacet + facet normal -0.474696 0.179786 0.861592 + outer loop + vertex 0.890194 1.83407 2.60136 + vertex 0.886611 1.83095 2.60004 + vertex 0.889176 1.83023 2.6016 + endloop + endfacet + facet normal -0.473833 0.17848 0.862338 + outer loop + vertex 0.887241 1.83561 2.59942 + vertex 0.886611 1.83095 2.60004 + vertex 0.890194 1.83407 2.60136 + endloop + endfacet + facet normal -0.605791 0.327869 0.724927 + outer loop + vertex 0.88844 1.88506 2.58729 + vertex 0.887255 1.88043 2.58839 + vertex 0.891074 1.88332 2.59028 + endloop + endfacet + facet normal -0.619043 0.305466 0.723517 + outer loop + vertex 0.891387 1.88774 2.58868 + vertex 0.88844 1.88506 2.58729 + vertex 0.891074 1.88332 2.59028 + endloop + endfacet + facet normal -0.593874 0.310461 0.742245 + outer loop + vertex 0.891074 1.88332 2.59028 + vertex 0.894548 1.88667 2.59165 + vertex 0.891387 1.88774 2.58868 + endloop + endfacet + facet normal -0.694455 0.360588 0.622663 + outer loop + vertex 0.891187 1.89286 2.58596 + vertex 0.888571 1.89198 2.58355 + vertex 0.888683 1.88925 2.58526 + endloop + endfacet + facet normal -0.646401 0.3626 0.671333 + outer loop + vertex 0.888683 1.88925 2.58526 + vertex 0.88844 1.88506 2.58729 + vertex 0.891387 1.88774 2.58868 + endloop + endfacet + facet normal -0.664025 0.330026 0.670934 + outer loop + vertex 0.891187 1.89286 2.58596 + vertex 0.888683 1.88925 2.58526 + vertex 0.891387 1.88774 2.58868 + endloop + endfacet + facet normal -0.651686 0.335465 0.680271 + outer loop + vertex 0.891187 1.89286 2.58596 + vertex 0.891387 1.88774 2.58868 + vertex 0.894159 1.89058 2.58993 + endloop + endfacet + facet normal -0.711743 0.228831 0.664123 + outer loop + vertex 0.891187 1.89286 2.58596 + vertex 0.894159 1.89058 2.58993 + vertex 0.893775 1.89282 2.58875 + endloop + endfacet + facet normal -0.611199 0.267254 0.744991 + outer loop + vertex 0.894159 1.89058 2.58993 + vertex 0.891387 1.88774 2.58868 + vertex 0.894548 1.88667 2.59165 + endloop + endfacet + facet normal -0.728628 0.349162 0.589226 + outer loop + vertex 0.889744 1.89752 2.58172 + vertex 0.887963 1.89738 2.5796 + vertex 0.888239 1.8947 2.58153 + endloop + endfacet + facet normal -0.693024 0.374161 0.616216 + outer loop + vertex 0.888239 1.8947 2.58153 + vertex 0.888571 1.89198 2.58355 + vertex 0.891187 1.89286 2.58596 + endloop + endfacet + facet normal -0.712442 0.338871 0.614486 + outer loop + vertex 0.888239 1.8947 2.58153 + vertex 0.891187 1.89286 2.58596 + vertex 0.889744 1.89752 2.58172 + endloop + endfacet + facet normal -0.735244 0.317551 0.598814 + outer loop + vertex 0.889744 1.89752 2.58172 + vertex 0.891187 1.89286 2.58596 + vertex 0.892242 1.89783 2.58462 + endloop + endfacet + facet normal -0.703146 0.320439 0.634747 + outer loop + vertex 0.891187 1.89286 2.58596 + vertex 0.89396 1.89528 2.58781 + vertex 0.892242 1.89783 2.58462 + endloop + endfacet + facet normal -0.696784 0.300619 0.651246 + outer loop + vertex 0.893775 1.89282 2.58875 + vertex 0.89396 1.89528 2.58781 + vertex 0.891187 1.89286 2.58596 + endloop + endfacet + facet normal -0.730547 0.341471 0.591353 + outer loop + vertex 0.888039 1.90028 2.57802 + vertex 0.887963 1.89738 2.5796 + vertex 0.889744 1.89752 2.58172 + endloop + endfacet + facet normal -0.738368 0.331332 0.587394 + outer loop + vertex 0.890883 1.90278 2.58018 + vertex 0.888039 1.90028 2.57802 + vertex 0.889744 1.89752 2.58172 + endloop + endfacet + facet normal -0.714658 0.319155 0.622418 + outer loop + vertex 0.893494 1.90108 2.58439 + vertex 0.892242 1.89783 2.58462 + vertex 0.894434 1.89852 2.58678 + endloop + endfacet + facet normal -0.738691 0.326092 0.589915 + outer loop + vertex 0.893494 1.90108 2.58439 + vertex 0.890883 1.90278 2.58018 + vertex 0.892242 1.89783 2.58462 + endloop + endfacet + facet normal -0.73219 0.332111 0.594643 + outer loop + vertex 0.890883 1.90278 2.58018 + vertex 0.889744 1.89752 2.58172 + vertex 0.892242 1.89783 2.58462 + endloop + endfacet + facet normal -0.715886 0.304062 0.628533 + outer loop + vertex 0.894434 1.89852 2.58678 + vertex 0.892242 1.89783 2.58462 + vertex 0.89396 1.89528 2.58781 + endloop + endfacet + facet normal -0.744165 0.348998 0.569578 + outer loop + vertex 0.889614 1.90837 2.57521 + vertex 0.887723 1.90756 2.57324 + vertex 0.887971 1.9047 2.57532 + endloop + endfacet + facet normal -0.740756 0.341976 0.578215 + outer loop + vertex 0.887971 1.9047 2.57532 + vertex 0.888039 1.90028 2.57802 + vertex 0.890883 1.90278 2.58018 + endloop + endfacet + facet normal -0.738305 0.346632 0.578577 + outer loop + vertex 0.887971 1.9047 2.57532 + vertex 0.890883 1.90278 2.58018 + vertex 0.889614 1.90837 2.57521 + endloop + endfacet + facet normal -0.763282 0.323669 0.559142 + outer loop + vertex 0.889614 1.90837 2.57521 + vertex 0.890883 1.90278 2.58018 + vertex 0.892288 1.90814 2.579 + endloop + endfacet + facet normal -0.745827 0.324136 0.58196 + outer loop + vertex 0.890883 1.90278 2.58018 + vertex 0.893856 1.90493 2.5828 + vertex 0.892288 1.90814 2.579 + endloop + endfacet + facet normal -0.744695 0.31418 0.58883 + outer loop + vertex 0.893494 1.90108 2.58439 + vertex 0.893856 1.90493 2.5828 + vertex 0.890883 1.90278 2.58018 + endloop + endfacet + facet normal -0.761835 0.349869 0.545159 + outer loop + vertex 0.889205 1.91276 2.57198 + vertex 0.887634 1.91285 2.56973 + vertex 0.887588 1.91023 2.57135 + endloop + endfacet + facet normal -0.742893 0.362053 0.563052 + outer loop + vertex 0.887588 1.91023 2.57135 + vertex 0.887723 1.90756 2.57324 + vertex 0.889614 1.90837 2.57521 + endloop + endfacet + facet normal -0.754934 0.341857 0.55965 + outer loop + vertex 0.887588 1.91023 2.57135 + vertex 0.889614 1.90837 2.57521 + vertex 0.889205 1.91276 2.57198 + endloop + endfacet + facet normal -0.768311 0.331637 0.547462 + outer loop + vertex 0.889205 1.91276 2.57198 + vertex 0.889614 1.90837 2.57521 + vertex 0.891663 1.91262 2.57551 + endloop + endfacet + facet normal -0.763571 0.313279 0.564637 + outer loop + vertex 0.89354 1.91133 2.57892 + vertex 0.892288 1.90814 2.579 + vertex 0.894304 1.90884 2.58134 + endloop + endfacet + facet normal -0.774632 0.317211 0.547104 + outer loop + vertex 0.89354 1.91133 2.57892 + vertex 0.891663 1.91262 2.57551 + vertex 0.892288 1.90814 2.579 + endloop + endfacet + facet normal -0.761996 0.327817 0.558479 + outer loop + vertex 0.891663 1.91262 2.57551 + vertex 0.889614 1.90837 2.57521 + vertex 0.892288 1.90814 2.579 + endloop + endfacet + facet normal -0.765012 0.300311 0.569711 + outer loop + vertex 0.894304 1.90884 2.58134 + vertex 0.892288 1.90814 2.579 + vertex 0.893856 1.90493 2.5828 + endloop + endfacet + facet normal -0.765617 0.337984 0.547355 + outer loop + vertex 0.888162 1.91566 2.56873 + vertex 0.887634 1.91285 2.56973 + vertex 0.889205 1.91276 2.57198 + endloop + endfacet + facet normal -0.780955 0.320101 0.536325 + outer loop + vertex 0.890656 1.91708 2.57151 + vertex 0.888162 1.91566 2.56873 + vertex 0.889205 1.91276 2.57198 + endloop + endfacet + facet normal -0.776281 0.31395 0.546647 + outer loop + vertex 0.892699 1.91634 2.57485 + vertex 0.891663 1.91262 2.57551 + vertex 0.893665 1.91415 2.57748 + endloop + endfacet + facet normal -0.77695 0.313964 0.545687 + outer loop + vertex 0.892699 1.91634 2.57485 + vertex 0.890656 1.91708 2.57151 + vertex 0.891663 1.91262 2.57551 + endloop + endfacet + facet normal -0.772236 0.318606 0.549674 + outer loop + vertex 0.890656 1.91708 2.57151 + vertex 0.889205 1.91276 2.57198 + vertex 0.891663 1.91262 2.57551 + endloop + endfacet + facet normal -0.776272 0.313834 0.546727 + outer loop + vertex 0.893665 1.91415 2.57748 + vertex 0.891663 1.91262 2.57551 + vertex 0.89354 1.91133 2.57892 + endloop + endfacet + facet normal -0.781106 0.315669 0.538727 + outer loop + vertex 0.889021 1.91997 2.56745 + vertex 0.888162 1.91566 2.56873 + vertex 0.890656 1.91708 2.57151 + endloop + endfacet + facet normal -0.794492 0.296112 0.530189 + outer loop + vertex 0.891015 1.92216 2.56921 + vertex 0.889021 1.91997 2.56745 + vertex 0.890656 1.91708 2.57151 + endloop + endfacet + facet normal -0.782553 0.301772 0.544559 + outer loop + vertex 0.890656 1.91708 2.57151 + vertex 0.892929 1.92012 2.5731 + vertex 0.891015 1.92216 2.56921 + endloop + endfacet + facet normal -0.782046 0.30071 0.545874 + outer loop + vertex 0.892699 1.91634 2.57485 + vertex 0.892929 1.92012 2.5731 + vertex 0.890656 1.91708 2.57151 + endloop + endfacet + facet normal -0.809944 0.312914 0.496061 + outer loop + vertex 0.891084 1.92767 2.56618 + vertex 0.889055 1.92605 2.56389 + vertex 0.889569 1.92369 2.56622 + endloop + endfacet + facet normal -0.793736 0.29322 0.532921 + outer loop + vertex 0.889569 1.92369 2.56622 + vertex 0.889021 1.91997 2.56745 + vertex 0.891015 1.92216 2.56921 + endloop + endfacet + facet normal -0.787467 0.304717 0.535764 + outer loop + vertex 0.891084 1.92767 2.56618 + vertex 0.889569 1.92369 2.56622 + vertex 0.891015 1.92216 2.56921 + endloop + endfacet + facet normal -0.786215 0.305474 0.537169 + outer loop + vertex 0.891084 1.92767 2.56618 + vertex 0.891015 1.92216 2.56921 + vertex 0.893038 1.92466 2.57076 + endloop + endfacet + facet normal -0.793213 0.294552 0.532965 + outer loop + vertex 0.891084 1.92767 2.56618 + vertex 0.893038 1.92466 2.57076 + vertex 0.893019 1.92755 2.56913 + endloop + endfacet + facet normal -0.78388 0.299393 0.543963 + outer loop + vertex 0.893038 1.92466 2.57076 + vertex 0.891015 1.92216 2.56921 + vertex 0.892929 1.92012 2.5731 + endloop + endfacet + facet normal -0.859102 0.314811 0.403532 + outer loop + vertex 0.890065 1.93291 2.56098 + vertex 0.888626 1.93101 2.5594 + vertex 0.889214 1.92896 2.56225 + endloop + endfacet + facet normal -0.810146 0.320772 0.490681 + outer loop + vertex 0.889214 1.92896 2.56225 + vertex 0.889055 1.92605 2.56389 + vertex 0.891084 1.92767 2.56618 + endloop + endfacet + facet normal -0.805088 0.331585 0.491818 + outer loop + vertex 0.889214 1.92896 2.56225 + vertex 0.891084 1.92767 2.56618 + vertex 0.890065 1.93291 2.56098 + endloop + endfacet + facet normal -0.84295 0.287455 0.454757 + outer loop + vertex 0.890065 1.93291 2.56098 + vertex 0.891084 1.92767 2.56618 + vertex 0.892091 1.93317 2.56457 + endloop + endfacet + facet normal -0.796021 0.299688 0.525869 + outer loop + vertex 0.891084 1.92767 2.56618 + vertex 0.893389 1.93039 2.56812 + vertex 0.892091 1.93317 2.56457 + endloop + endfacet + facet normal -0.793775 0.292517 0.53325 + outer loop + vertex 0.893019 1.92755 2.56913 + vertex 0.893389 1.93039 2.56812 + vertex 0.891084 1.92767 2.56618 + endloop + endfacet + facet normal -0.900363 0.343056 0.26769 + outer loop + vertex 0.88992 1.93771 2.55598 + vertex 0.888689 1.93569 2.55443 + vertex 0.88887 1.9339 2.55733 + endloop + endfacet + facet normal -0.862148 0.341237 0.37451 + outer loop + vertex 0.88887 1.9339 2.55733 + vertex 0.888626 1.93101 2.5594 + vertex 0.890065 1.93291 2.56098 + endloop + endfacet + facet normal -0.849603 0.368179 0.37765 + outer loop + vertex 0.88887 1.9339 2.55733 + vertex 0.890065 1.93291 2.56098 + vertex 0.88992 1.93771 2.55598 + endloop + endfacet + facet normal -0.896104 0.307104 0.320445 + outer loop + vertex 0.88992 1.93771 2.55598 + vertex 0.890065 1.93291 2.56098 + vertex 0.891686 1.93798 2.56066 + endloop + endfacet + facet normal -0.808713 0.279338 0.517643 + outer loop + vertex 0.893111 1.93647 2.56438 + vertex 0.892091 1.93317 2.56457 + vertex 0.893812 1.93394 2.56685 + endloop + endfacet + facet normal -0.849943 0.287718 0.441379 + outer loop + vertex 0.893111 1.93647 2.56438 + vertex 0.891686 1.93798 2.56066 + vertex 0.892091 1.93317 2.56457 + endloop + endfacet + facet normal -0.840523 0.297693 0.452659 + outer loop + vertex 0.891686 1.93798 2.56066 + vertex 0.890065 1.93291 2.56098 + vertex 0.892091 1.93317 2.56457 + endloop + endfacet + facet normal -0.808478 0.282002 0.516564 + outer loop + vertex 0.893812 1.93394 2.56685 + vertex 0.892091 1.93317 2.56457 + vertex 0.893389 1.93039 2.56812 + endloop + endfacet + facet normal -0.749105 0.51518 0.416451 + outer loop + vertex 0.890789 1.94283 2.55138 + vertex 0.891513 1.945 2.55 + vertex 0.89 1.9428 2.55 + endloop + endfacet + facet normal -0.808257 0.376099 0.453068 + outer loop + vertex 0.889323 1.93876 2.55215 + vertex 0.890789 1.94283 2.55138 + vertex 0.89 1.9428 2.55 + endloop + endfacet + facet normal -0.899924 0.364061 0.239991 + outer loop + vertex 0.889323 1.93876 2.55215 + vertex 0.888689 1.93569 2.55443 + vertex 0.88992 1.93771 2.55598 + endloop + endfacet + facet normal -0.897806 0.36865 0.240918 + outer loop + vertex 0.889323 1.93876 2.55215 + vertex 0.88992 1.93771 2.55598 + vertex 0.890789 1.94283 2.55138 + endloop + endfacet + facet normal -0.937179 0.307301 0.165113 + outer loop + vertex 0.890789 1.94283 2.55138 + vertex 0.88992 1.93771 2.55598 + vertex 0.891444 1.9425 2.55571 + endloop + endfacet + facet normal -0.897222 0.303137 0.321093 + outer loop + vertex 0.88992 1.93771 2.55598 + vertex 0.891686 1.93798 2.56066 + vertex 0.891444 1.9425 2.55571 + endloop + endfacet + facet normal -0.934082 0.23955 0.264775 + outer loop + vertex 0.891444 1.9425 2.55571 + vertex 0.891686 1.93798 2.56066 + vertex 0.892662 1.94301 2.55955 + endloop + endfacet + facet normal -0.863354 0.262456 0.430972 + outer loop + vertex 0.891686 1.93798 2.56066 + vertex 0.893597 1.94022 2.56312 + vertex 0.892662 1.94301 2.55955 + endloop + endfacet + facet normal -0.862884 0.258269 0.434429 + outer loop + vertex 0.893111 1.93647 2.56438 + vertex 0.893597 1.94022 2.56312 + vertex 0.891686 1.93798 2.56066 + endloop + endfacet + facet normal -0.954214 0.297335 -0.032675 + outer loop + vertex 0.891513 1.945 2.55 + vertex 0.890789 1.94283 2.55138 + vertex 0.893071 1.95 2.55 + endloop + endfacet + facet normal -0.954483 0.291886 -0.061357 + outer loop + vertex 0.893071 1.95 2.55 + vertex 0.890789 1.94283 2.55138 + vertex 0.892171 1.94736 2.55144 + endloop + endfacet + facet normal -0.944 0.286001 0.164521 + outer loop + vertex 0.890789 1.94283 2.55138 + vertex 0.891444 1.9425 2.55571 + vertex 0.892171 1.94736 2.55144 + endloop + endfacet + facet normal -0.955644 0.261763 0.135 + outer loop + vertex 0.892171 1.94736 2.55144 + vertex 0.891444 1.9425 2.55571 + vertex 0.892766 1.94721 2.55595 + endloop + endfacet + facet normal -0.877397 0.239975 0.415436 + outer loop + vertex 0.89355 1.94621 2.55958 + vertex 0.892662 1.94301 2.55955 + vertex 0.894029 1.94391 2.56192 + endloop + endfacet + facet normal -0.928168 0.255422 0.270674 + outer loop + vertex 0.89355 1.94621 2.55958 + vertex 0.892766 1.94721 2.55595 + vertex 0.892662 1.94301 2.55955 + endloop + endfacet + facet normal -0.932165 0.248869 0.26293 + outer loop + vertex 0.892766 1.94721 2.55595 + vertex 0.891444 1.9425 2.55571 + vertex 0.892662 1.94301 2.55955 + endloop + endfacet + facet normal -0.877499 0.238564 0.416031 + outer loop + vertex 0.894029 1.94391 2.56192 + vertex 0.892662 1.94301 2.55955 + vertex 0.893597 1.94022 2.56312 + endloop + endfacet + facet normal -0.815972 -0.421719 -0.395401 + outer loop + vertex 0.895 1.95 2.54628 + vertex 0.893036 1.955 2.545 + vertex 0.895 1.9512 2.545 + endloop + endfacet + facet normal -0.804503 -0.422785 -0.417166 + outer loop + vertex 0.895 1.95 2.54628 + vertex 0.893071 1.95 2.55 + vertex 0.893036 1.955 2.545 + endloop + endfacet + facet normal -0.934908 0.247651 0.254199 + outer loop + vertex 0.893071 1.95 2.55 + vertex 0.893391 1.95377 2.54751 + vertex 0.893036 1.955 2.545 + endloop + endfacet + facet normal 0.352163 -0.537112 -0.766481 + outer loop + vertex 0.893071 1.95 2.55 + vertex 0.892171 1.94736 2.55144 + vertex 0.893391 1.95377 2.54751 + endloop + endfacet + facet normal -0.966487 0.239977 0.0911765 + outer loop + vertex 0.893391 1.95377 2.54751 + vertex 0.892171 1.94736 2.55144 + vertex 0.893296 1.95178 2.55173 + endloop + endfacet + facet normal -0.962328 0.236004 0.135009 + outer loop + vertex 0.892171 1.94736 2.55144 + vertex 0.892766 1.94721 2.55595 + vertex 0.893296 1.95178 2.55173 + endloop + endfacet + facet normal -0.957673 0.247109 0.14765 + outer loop + vertex 0.893296 1.95178 2.55173 + vertex 0.892766 1.94721 2.55595 + vertex 0.893644 1.95107 2.55518 + endloop + endfacet + facet normal -0.922187 0.265613 0.281108 + outer loop + vertex 0.892766 1.94721 2.55595 + vertex 0.894165 1.94951 2.55836 + vertex 0.893644 1.95107 2.55518 + endloop + endfacet + facet normal -0.922156 0.272866 0.274176 + outer loop + vertex 0.89355 1.94621 2.55958 + vertex 0.894165 1.94951 2.55836 + vertex 0.892766 1.94721 2.55595 + endloop + endfacet + facet normal -0.967457 0.238577 0.0843059 + outer loop + vertex 0.895 1.96 2.54833 + vertex 0.893391 1.95377 2.54751 + vertex 0.895 1.95941 2.55 + endloop + endfacet + facet normal -0.962031 0.228636 0.149071 + outer loop + vertex 0.895 1.96 2.54833 + vertex 0.894484 1.96 2.545 + vertex 0.893391 1.95377 2.54751 + endloop + endfacet + facet normal -0.926661 0.268357 0.26322 + outer loop + vertex 0.894484 1.96 2.545 + vertex 0.893036 1.955 2.545 + vertex 0.893391 1.95377 2.54751 + endloop + endfacet + facet normal -0.939922 0.260063 0.221165 + outer loop + vertex 0.895 1.95941 2.55 + vertex 0.893296 1.95178 2.55173 + vertex 0.894419 1.95481 2.55294 + endloop + endfacet + facet normal -0.967546 0.236336 0.0894406 + outer loop + vertex 0.893391 1.95377 2.54751 + vertex 0.893296 1.95178 2.55173 + vertex 0.895 1.95941 2.55 + endloop + endfacet + facet normal -0.905257 0.339916 0.254887 + outer loop + vertex 0.894419 1.95481 2.55294 + vertex 0.893644 1.95107 2.55518 + vertex 0.894714 1.9529 2.55654 + endloop + endfacet + facet normal -0.944891 0.288426 0.154894 + outer loop + vertex 0.893296 1.95178 2.55173 + vertex 0.893644 1.95107 2.55518 + vertex 0.894419 1.95481 2.55294 + endloop + endfacet + facet normal -0.903845 0.306764 0.298261 + outer loop + vertex 0.894714 1.9529 2.55654 + vertex 0.893644 1.95107 2.55518 + vertex 0.894165 1.94951 2.55836 + endloop + endfacet + facet normal -0.630835 0.458457 -0.62599 + outer loop + vertex 0.895 1.96 2.54448 + vertex 0.894484 1.96 2.545 + vertex 0.895 1.96071 2.545 + endloop + endfacet + facet normal -0.802657 0.583328 0.124375 + outer loop + vertex 0.895 1.96071 2.545 + vertex 0.894484 1.96 2.545 + vertex 0.895 1.96 2.54833 + endloop + endfacet + facet normal 0.0578529 -0.997749 0.0339212 + outer loop + vertex 0.895 2.1076 2.485 + vertex 0.895 2.10777 2.49 + vertex 0.89 2.10731 2.485 + endloop + endfacet + facet normal 0.514328 -0.731888 -0.446997 + outer loop + vertex 0.895 2.10777 2.49 + vertex 0.888637 2.10453 2.48799 + vertex 0.89 2.10731 2.485 + endloop + endfacet + facet normal 0.511559 -0.669532 -0.538549 + outer loop + vertex 0.895 2.10777 2.49 + vertex 0.893698 2.10511 2.49207 + vertex 0.888637 2.10453 2.48799 + endloop + endfacet + facet normal -0.111655 -0.954881 0.275202 + outer loop + vertex 0.893698 2.10511 2.49207 + vertex 0.889031 2.10563 2.49196 + vertex 0.888637 2.10453 2.48799 + endloop + endfacet + facet normal -0.504589 -0.19956 0.83998 + outer loop + vertex 0.889538 2.10765 2.49374 + vertex 0.893368 2.10637 2.49574 + vertex 0.891786 2.10925 2.49547 + endloop + endfacet + facet normal -0.525812 -0.486385 0.697819 + outer loop + vertex 0.889538 2.10765 2.49374 + vertex 0.889031 2.10563 2.49196 + vertex 0.893368 2.10637 2.49574 + endloop + endfacet + facet normal -0.11127 -0.94326 0.312858 + outer loop + vertex 0.889031 2.10563 2.49196 + vertex 0.893698 2.10511 2.49207 + vertex 0.893368 2.10637 2.49574 + endloop + endfacet + facet normal -0.660935 -0.299668 0.688015 + outer loop + vertex 0.893368 2.10637 2.49574 + vertex 0.895225 2.10852 2.49846 + vertex 0.891786 2.10925 2.49547 + endloop + endfacet + facet normal -0.654842 0.111025 0.747566 + outer loop + vertex 0.88868 2.11026 2.4926 + vertex 0.889538 2.10765 2.49374 + vertex 0.891786 2.10925 2.49547 + endloop + endfacet + facet normal -0.579174 0.333087 0.74405 + outer loop + vertex 0.891338 2.1123 2.49376 + vertex 0.88868 2.11026 2.4926 + vertex 0.891786 2.10925 2.49547 + endloop + endfacet + facet normal -0.627388 0.309455 0.714579 + outer loop + vertex 0.891786 2.10925 2.49547 + vertex 0.894302 2.11155 2.49669 + vertex 0.891338 2.1123 2.49376 + endloop + endfacet + facet normal -0.601695 0.259924 0.75525 + outer loop + vertex 0.895225 2.10852 2.49846 + vertex 0.894302 2.11155 2.49669 + vertex 0.891786 2.10925 2.49547 + endloop + endfacet + facet normal -0.533992 0.616406 0.578703 + outer loop + vertex 0.891624 2.11513 2.49134 + vertex 0.889044 2.11524 2.48885 + vertex 0.888656 2.11332 2.49053 + endloop + endfacet + facet normal -0.619036 0.436708 0.652748 + outer loop + vertex 0.888656 2.11332 2.49053 + vertex 0.88868 2.11026 2.4926 + vertex 0.891338 2.1123 2.49376 + endloop + endfacet + facet normal -0.52478 0.582674 0.620562 + outer loop + vertex 0.891624 2.11513 2.49134 + vertex 0.888656 2.11332 2.49053 + vertex 0.891338 2.1123 2.49376 + endloop + endfacet + facet normal -0.581255 0.561444 0.589003 + outer loop + vertex 0.891624 2.11513 2.49134 + vertex 0.891338 2.1123 2.49376 + vertex 0.893935 2.11425 2.49447 + endloop + endfacet + facet normal -0.549719 0.603455 0.577625 + outer loop + vertex 0.891624 2.11513 2.49134 + vertex 0.893935 2.11425 2.49447 + vertex 0.894022 2.11577 2.49296 + endloop + endfacet + facet normal -0.549099 0.485192 0.680499 + outer loop + vertex 0.893935 2.11425 2.49447 + vertex 0.891338 2.1123 2.49376 + vertex 0.894302 2.11155 2.49669 + endloop + endfacet + facet normal -0.522698 0.723209 0.451392 + outer loop + vertex 0.895 2.125 2.48148 + vertex 0.893722 2.125 2.48 + vertex 0.89 2.12231 2.48 + endloop + endfacet + facet normal -0.520521 0.69333 0.498349 + outer loop + vertex 0.895 2.125 2.48148 + vertex 0.89 2.12231 2.48 + vertex 0.895 2.12247 2.485 + endloop + endfacet + facet normal -0.63421 0.462704 0.619421 + outer loop + vertex 0.895 2.12247 2.485 + vertex 0.89 2.12231 2.48 + vertex 0.889797 2.1193 2.48204 + endloop + endfacet + facet normal -0.631291 0.439881 0.638731 + outer loop + vertex 0.895 2.12247 2.485 + vertex 0.889797 2.1193 2.48204 + vertex 0.894504 2.11915 2.48679 + endloop + endfacet + facet normal -0.406644 0.807274 0.427726 + outer loop + vertex 0.894504 2.11915 2.48679 + vertex 0.889797 2.1193 2.48204 + vertex 0.890068 2.11693 2.48678 + endloop + endfacet + facet normal -0.402536 0.797016 0.450256 + outer loop + vertex 0.891624 2.11513 2.49134 + vertex 0.890068 2.11693 2.48678 + vertex 0.889044 2.11524 2.48885 + endloop + endfacet + facet normal -0.457507 0.763485 0.455826 + outer loop + vertex 0.891624 2.11513 2.49134 + vertex 0.894734 2.11705 2.49125 + vertex 0.890068 2.11693 2.48678 + endloop + endfacet + facet normal -0.411053 0.816247 0.405927 + outer loop + vertex 0.894734 2.11705 2.49125 + vertex 0.894504 2.11915 2.48679 + vertex 0.890068 2.11693 2.48678 + endloop + endfacet + facet normal -0.473997 0.787354 0.394208 + outer loop + vertex 0.894734 2.11705 2.49125 + vertex 0.891624 2.11513 2.49134 + vertex 0.894022 2.11577 2.49296 + endloop + endfacet + facet normal -0.662168 0.748816 0.0284216 + outer loop + vertex 0.895 2.12632 2.475 + vertex 0.893722 2.125 2.48 + vertex 0.895 2.12613 2.48 + endloop + endfacet + facet normal -0.254172 0.949185 0.185593 + outer loop + vertex 0.890071 2.125 2.475 + vertex 0.893722 2.125 2.48 + vertex 0.895 2.12632 2.475 + endloop + endfacet + facet normal -0.574997 0.650238 0.496557 + outer loop + vertex 0.895 2.12613 2.48 + vertex 0.893722 2.125 2.48 + vertex 0.895 2.125 2.48148 + endloop + endfacet + facet normal -0.157342 -0.983445 0.0898869 + outer loop + vertex 0.9 0.902625 2.48 + vertex 0.9 0.903082 2.485 + vertex 0.895 0.903425 2.48 + endloop + endfacet + facet normal 0.102166 -0.980236 -0.169407 + outer loop + vertex 0.9 0.903082 2.485 + vertex 0.894153 0.903155 2.48105 + vertex 0.895 0.903425 2.48 + endloop + endfacet + facet normal -0.229992 -0.944961 0.232706 + outer loop + vertex 0.894806 0.903607 2.48417 + vertex 0.899054 0.903055 2.48612 + vertex 0.896742 0.903854 2.48708 + endloop + endfacet + facet normal -0.209365 -0.960463 0.183515 + outer loop + vertex 0.894806 0.903607 2.48417 + vertex 0.894153 0.903155 2.48105 + vertex 0.899054 0.903055 2.48612 + endloop + endfacet + facet normal 0.00237431 -0.999757 -0.0219362 + outer loop + vertex 0.894153 0.903155 2.48105 + vertex 0.9 0.903082 2.485 + vertex 0.899054 0.903055 2.48612 + endloop + endfacet + facet normal -0.244236 -0.948578 0.201366 + outer loop + vertex 0.899054 0.903055 2.48612 + vertex 0.899734 0.903546 2.48926 + vertex 0.896742 0.903854 2.48708 + endloop + endfacet + facet normal -0.370554 -0.871961 0.319958 + outer loop + vertex 0.894806 0.903607 2.48417 + vertex 0.896742 0.903854 2.48708 + vertex 0.892834 0.905017 2.48572 + endloop + endfacet + facet normal -0.348834 -0.866725 0.356514 + outer loop + vertex 0.896742 0.903854 2.48708 + vertex 0.899734 0.903546 2.48926 + vertex 0.897732 0.90496 2.49074 + endloop + endfacet + facet normal -0.378755 -0.852483 0.3603 + outer loop + vertex 0.896742 0.903854 2.48708 + vertex 0.897732 0.90496 2.49074 + vertex 0.892834 0.905017 2.48572 + endloop + endfacet + facet normal -0.46082 -0.769959 0.44137 + outer loop + vertex 0.892834 0.905017 2.48572 + vertex 0.897732 0.90496 2.49074 + vertex 0.892744 0.907467 2.4899 + endloop + endfacet + facet normal -0.532463 -0.692379 0.486924 + outer loop + vertex 0.892953 0.909914 2.49324 + vertex 0.897546 0.907466 2.49478 + vertex 0.895847 0.909457 2.49575 + endloop + endfacet + facet normal -0.530943 -0.66694 0.522772 + outer loop + vertex 0.892953 0.909914 2.49324 + vertex 0.892744 0.907467 2.4899 + vertex 0.897546 0.907466 2.49478 + endloop + endfacet + facet normal -0.459737 -0.764055 0.452616 + outer loop + vertex 0.892744 0.907467 2.4899 + vertex 0.897732 0.90496 2.49074 + vertex 0.897546 0.907466 2.49478 + endloop + endfacet + facet normal -0.48507 -0.681647 0.547781 + outer loop + vertex 0.897546 0.907466 2.49478 + vertex 0.897936 0.909905 2.49816 + vertex 0.895847 0.909457 2.49575 + endloop + endfacet + facet normal -0.594375 -0.553454 0.583444 + outer loop + vertex 0.892953 0.909914 2.49324 + vertex 0.895847 0.909457 2.49575 + vertex 0.894028 0.911795 2.49612 + endloop + endfacet + facet normal -0.595172 -0.304233 0.743783 + outer loop + vertex 0.899274 0.911728 2.5009 + vertex 0.89733 0.915003 2.50069 + vertex 0.89566 0.913376 2.49869 + endloop + endfacet + facet normal -0.607244 -0.492624 0.623359 + outer loop + vertex 0.897936 0.909905 2.49816 + vertex 0.899274 0.911728 2.5009 + vertex 0.89566 0.913376 2.49869 + endloop + endfacet + facet normal -0.577292 -0.478757 0.661457 + outer loop + vertex 0.897936 0.909905 2.49816 + vertex 0.89566 0.913376 2.49869 + vertex 0.894028 0.911795 2.49612 + endloop + endfacet + facet normal -0.580036 -0.545644 0.60484 + outer loop + vertex 0.897936 0.909905 2.49816 + vertex 0.894028 0.911795 2.49612 + vertex 0.895847 0.909457 2.49575 + endloop + endfacet + facet normal -0.609814 -0.313985 0.727695 + outer loop + vertex 0.899274 0.911728 2.5009 + vertex 0.900746 0.913364 2.50284 + vertex 0.89733 0.915003 2.50069 + endloop + endfacet + facet normal 0.536027 0.780165 -0.322517 + outer loop + vertex 0.9 0.919663 2.49 + vertex 0.9 0.917596 2.485 + vertex 0.896501 0.92 2.485 + endloop + endfacet + facet normal -0.193603 0.960434 0.200212 + outer loop + vertex 0.896602 0.919341 2.48826 + vertex 0.9 0.919663 2.49 + vertex 0.896501 0.92 2.485 + endloop + endfacet + facet normal -0.306866 0.842355 0.443024 + outer loop + vertex 0.900336 0.918737 2.49199 + vertex 0.9 0.919663 2.49 + vertex 0.896602 0.919341 2.48826 + endloop + endfacet + facet normal 0.186845 0.981989 -0.0280379 + outer loop + vertex 0.8974 0.919292 2.49186 + vertex 0.900336 0.918737 2.49199 + vertex 0.896602 0.919341 2.48826 + endloop + endfacet + facet normal 0.185818 0.982578 -0.00339113 + outer loop + vertex 0.900336 0.918737 2.49199 + vertex 0.8974 0.919292 2.49186 + vertex 0.899664 0.918873 2.49465 + endloop + endfacet + facet normal -0.666237 -0.200064 0.718403 + outer loop + vertex 0.894095 0.916497 2.49811 + vertex 0.89566 0.913376 2.49869 + vertex 0.89733 0.915003 2.50069 + endloop + endfacet + facet normal -0.578888 0.13666 0.803873 + outer loop + vertex 0.89618 0.917379 2.49946 + vertex 0.894095 0.916497 2.49811 + vertex 0.89733 0.915003 2.50069 + endloop + endfacet + facet normal -0.514536 0.185092 0.837254 + outer loop + vertex 0.89733 0.915003 2.50069 + vertex 0.899364 0.916486 2.50161 + vertex 0.89618 0.917379 2.49946 + endloop + endfacet + facet normal -0.485002 0.127217 0.865211 + outer loop + vertex 0.900746 0.913364 2.50284 + vertex 0.899364 0.916486 2.50161 + vertex 0.89733 0.915003 2.50069 + endloop + endfacet + facet normal -0.657302 -0.0246804 0.753223 + outer loop + vertex 0.895 0.92 2.48369 + vertex 0.891764 0.919649 2.48085 + vertex 0.896501 0.92 2.485 + endloop + endfacet + facet normal -0.0334173 0.979411 0.199091 + outer loop + vertex 0.896501 0.92 2.485 + vertex 0.892316 0.919905 2.48476 + vertex 0.896602 0.919341 2.48826 + endloop + endfacet + facet normal -0.0190612 0.997856 -0.0626062 + outer loop + vertex 0.891764 0.919649 2.48085 + vertex 0.892316 0.919905 2.48476 + vertex 0.896501 0.92 2.485 + endloop + endfacet + facet normal 0.117655 0.992975 -0.0125491 + outer loop + vertex 0.896602 0.919341 2.48826 + vertex 0.893387 0.91975 2.49048 + vertex 0.8974 0.919292 2.49186 + endloop + endfacet + facet normal 0.128176 0.991747 0.00289767 + outer loop + vertex 0.892316 0.919905 2.48476 + vertex 0.893387 0.91975 2.49048 + vertex 0.896602 0.919341 2.48826 + endloop + endfacet + facet normal 0.13528 0.99005 0.0387245 + outer loop + vertex 0.8974 0.919292 2.49186 + vertex 0.896927 0.919229 2.49512 + vertex 0.899664 0.918873 2.49465 + endloop + endfacet + facet normal 0.101833 0.994222 0.0339647 + outer loop + vertex 0.8974 0.919292 2.49186 + vertex 0.893387 0.91975 2.49048 + vertex 0.896927 0.919229 2.49512 + endloop + endfacet + facet normal -0.112137 0.974384 0.194941 + outer loop + vertex 0.893387 0.91975 2.49048 + vertex 0.893817 0.918722 2.49587 + vertex 0.896927 0.919229 2.49512 + endloop + endfacet + facet normal -0.608146 0.523908 0.596388 + outer loop + vertex 0.89618 0.917379 2.49946 + vertex 0.893817 0.918722 2.49587 + vertex 0.894095 0.916497 2.49811 + endloop + endfacet + facet normal -0.344026 0.782368 0.519179 + outer loop + vertex 0.89618 0.917379 2.49946 + vertex 0.897514 0.918403 2.4988 + vertex 0.893817 0.918722 2.49587 + endloop + endfacet + facet normal -0.101689 0.967031 0.233475 + outer loop + vertex 0.897514 0.918403 2.4988 + vertex 0.896927 0.919229 2.49512 + vertex 0.893817 0.918722 2.49587 + endloop + endfacet + facet normal -0.235558 0.724089 0.648234 + outer loop + vertex 0.897514 0.918403 2.4988 + vertex 0.89618 0.917379 2.49946 + vertex 0.899364 0.916486 2.50161 + endloop + endfacet + facet normal -0.701849 -0.141442 -0.698142 + outer loop + vertex 0.9 1.0561 2.545 + vertex 0.899214 1.06 2.545 + vertex 0.9 1.06 2.54421 + endloop + endfacet + facet normal -0.960941 -0.193657 0.197712 + outer loop + vertex 0.9 1.0561 2.545 + vertex 0.9 1.06 2.54882 + vertex 0.899214 1.06 2.545 + endloop + endfacet + facet normal -0.92605 -0.325773 0.190533 + outer loop + vertex 0.9 1.06069 2.55 + vertex 0.899214 1.06 2.545 + vertex 0.9 1.06 2.54882 + endloop + endfacet + facet normal -0.865087 -0.460239 0.19951 + outer loop + vertex 0.9 1.06069 2.55 + vertex 0.897707 1.065 2.55 + vertex 0.899214 1.06 2.545 + endloop + endfacet + facet normal -0.936502 -0.345004 0.0627431 + outer loop + vertex 0.897707 1.065 2.55 + vertex 0.897372 1.065 2.545 + vertex 0.899214 1.06 2.545 + endloop + endfacet + facet normal -0.595652 -0.316896 -0.738089 + outer loop + vertex 0.898443 1.06188 2.55075 + vertex 0.897707 1.065 2.55 + vertex 0.9 1.06069 2.55 + endloop + endfacet + facet normal -0.939997 -0.271186 -0.207037 + outer loop + vertex 0.896931 1.06606 2.55214 + vertex 0.897707 1.065 2.55 + vertex 0.898443 1.06188 2.55075 + endloop + endfacet + facet normal -0.931162 -0.358695 0.0653892 + outer loop + vertex 0.898443 1.06188 2.55075 + vertex 0.898291 1.06287 2.554 + vertex 0.896931 1.06606 2.55214 + endloop + endfacet + facet normal -0.923893 -0.345532 -0.164405 + outer loop + vertex 0.897707 1.065 2.55 + vertex 0.896931 1.06606 2.55214 + vertex 0.895837 1.07 2.55 + endloop + endfacet + facet normal -0.94271 -0.317376 -0.102813 + outer loop + vertex 0.895837 1.07 2.55 + vertex 0.896931 1.06606 2.55214 + vertex 0.895808 1.06932 2.55236 + endloop + endfacet + facet normal -0.938456 -0.296887 0.176518 + outer loop + vertex 0.897826 1.06548 2.55592 + vertex 0.896931 1.06606 2.55214 + vertex 0.898291 1.06287 2.554 + endloop + endfacet + facet normal -0.937377 -0.300771 0.175672 + outer loop + vertex 0.897826 1.06548 2.55592 + vertex 0.896604 1.06947 2.55623 + vertex 0.896931 1.06606 2.55214 + endloop + endfacet + facet normal -0.921935 -0.330639 0.201776 + outer loop + vertex 0.896604 1.06947 2.55623 + vertex 0.895808 1.06932 2.55236 + vertex 0.896931 1.06606 2.55214 + endloop + endfacet + facet normal -0.910527 -0.301001 0.283443 + outer loop + vertex 0.897826 1.06548 2.55592 + vertex 0.898309 1.06662 2.55869 + vertex 0.896604 1.06947 2.55623 + endloop + endfacet + facet normal 0.113865 0.0292366 -0.993066 + outer loop + vertex 0.89423 1.07313 2.54991 + vertex 0.895 1.07326 2.55 + vertex 0.895837 1.07 2.55 + endloop + endfacet + facet normal -0.886099 -0.452722 0.0993563 + outer loop + vertex 0.89423 1.07313 2.54991 + vertex 0.895837 1.07 2.55 + vertex 0.894743 1.07283 2.55312 + endloop + endfacet + facet normal -0.958142 -0.271803 -0.0899237 + outer loop + vertex 0.894743 1.07283 2.55312 + vertex 0.895837 1.07 2.55 + vertex 0.895808 1.06932 2.55236 + endloop + endfacet + facet normal -0.923918 -0.324938 0.201968 + outer loop + vertex 0.895808 1.06932 2.55236 + vertex 0.896604 1.06947 2.55623 + vertex 0.894743 1.07283 2.55312 + endloop + endfacet + facet normal -0.924847 -0.31482 0.213419 + outer loop + vertex 0.894743 1.07283 2.55312 + vertex 0.896604 1.06947 2.55623 + vertex 0.895516 1.07306 2.55682 + endloop + endfacet + facet normal -0.909145 -0.274766 0.312983 + outer loop + vertex 0.898099 1.06926 2.5604 + vertex 0.896604 1.06947 2.55623 + vertex 0.898309 1.06662 2.55869 + endloop + endfacet + facet normal -0.90099 -0.304969 0.308563 + outer loop + vertex 0.898099 1.06926 2.5604 + vertex 0.89673 1.07338 2.56047 + vertex 0.896604 1.06947 2.55623 + endloop + endfacet + facet normal -0.889497 -0.322132 0.324077 + outer loop + vertex 0.89673 1.07338 2.56047 + vertex 0.895516 1.07306 2.55682 + vertex 0.896604 1.06947 2.55623 + endloop + endfacet + facet normal -0.866717 -0.295174 0.402086 + outer loop + vertex 0.899443 1.07036 2.5641 + vertex 0.89673 1.07338 2.56047 + vertex 0.898099 1.06926 2.5604 + endloop + endfacet + facet normal -0.867018 -0.307361 0.392184 + outer loop + vertex 0.898146 1.07541 2.56519 + vertex 0.89673 1.07338 2.56047 + vertex 0.899443 1.07036 2.5641 + endloop + endfacet + facet normal -0.837115 -0.311994 0.44933 + outer loop + vertex 0.899443 1.07036 2.5641 + vertex 0.900509 1.07284 2.56781 + vertex 0.898146 1.07541 2.56519 + endloop + endfacet + facet normal -0.92145 -0.371839 0.112542 + outer loop + vertex 0.89423 1.07313 2.54991 + vertex 0.894743 1.07283 2.55312 + vertex 0.893399 1.07554 2.55109 + endloop + endfacet + facet normal -0.927907 -0.331094 0.171362 + outer loop + vertex 0.893396 1.07679 2.55349 + vertex 0.893399 1.07554 2.55109 + vertex 0.894743 1.07283 2.55312 + endloop + endfacet + facet normal -0.911514 -0.332174 0.242492 + outer loop + vertex 0.893396 1.07679 2.55349 + vertex 0.894743 1.07283 2.55312 + vertex 0.894482 1.07655 2.55724 + endloop + endfacet + facet normal -0.92932 -0.301308 0.213488 + outer loop + vertex 0.894482 1.07655 2.55724 + vertex 0.894743 1.07283 2.55312 + vertex 0.895516 1.07306 2.55682 + endloop + endfacet + facet normal -0.895425 -0.30477 0.324545 + outer loop + vertex 0.895516 1.07306 2.55682 + vertex 0.89673 1.07338 2.56047 + vertex 0.894482 1.07655 2.55724 + endloop + endfacet + facet normal -0.895313 -0.298733 0.330414 + outer loop + vertex 0.894482 1.07655 2.55724 + vertex 0.89673 1.07338 2.56047 + vertex 0.895592 1.07913 2.56258 + endloop + endfacet + facet normal -0.862847 -0.315887 0.394601 + outer loop + vertex 0.89673 1.07338 2.56047 + vertex 0.898146 1.07541 2.56519 + vertex 0.895592 1.07913 2.56258 + endloop + endfacet + facet normal -0.858026 -0.293902 0.421204 + outer loop + vertex 0.895592 1.07913 2.56258 + vertex 0.898146 1.07541 2.56519 + vertex 0.897651 1.07979 2.56723 + endloop + endfacet + facet normal -0.836557 -0.306777 0.453938 + outer loop + vertex 0.898146 1.07541 2.56519 + vertex 0.899581 1.07663 2.56866 + vertex 0.897651 1.07979 2.56723 + endloop + endfacet + facet normal -0.836556 -0.30678 0.453939 + outer loop + vertex 0.900509 1.07284 2.56781 + vertex 0.899581 1.07663 2.56866 + vertex 0.898146 1.07541 2.56519 + endloop + endfacet + facet normal -0.91616 -0.317393 0.244772 + outer loop + vertex 0.893396 1.07679 2.55349 + vertex 0.894482 1.07655 2.55724 + vertex 0.892898 1.07952 2.55516 + endloop + endfacet + facet normal -0.884611 -0.320536 0.338703 + outer loop + vertex 0.894482 1.07655 2.55724 + vertex 0.895592 1.07913 2.56258 + vertex 0.893403 1.08123 2.55885 + endloop + endfacet + facet normal -0.915432 -0.302464 0.265518 + outer loop + vertex 0.892898 1.07952 2.55516 + vertex 0.894482 1.07655 2.55724 + vertex 0.893403 1.08123 2.55885 + endloop + endfacet + facet normal -0.883973 -0.325745 0.335384 + outer loop + vertex 0.894032 1.08323 2.56245 + vertex 0.893403 1.08123 2.55885 + vertex 0.895592 1.07913 2.56258 + endloop + endfacet + facet normal -0.851521 -0.310754 0.422308 + outer loop + vertex 0.894032 1.08323 2.56245 + vertex 0.895592 1.07913 2.56258 + vertex 0.895608 1.08416 2.56631 + endloop + endfacet + facet normal -0.852509 -0.309794 0.421018 + outer loop + vertex 0.895608 1.08416 2.56631 + vertex 0.895592 1.07913 2.56258 + vertex 0.897651 1.07979 2.56723 + endloop + endfacet + facet normal -0.824134 -0.28246 0.490937 + outer loop + vertex 0.899677 1.07957 2.57051 + vertex 0.897651 1.07979 2.56723 + vertex 0.899581 1.07663 2.56866 + endloop + endfacet + facet normal -0.822063 -0.291638 0.489039 + outer loop + vertex 0.899677 1.07957 2.57051 + vertex 0.898102 1.08355 2.57023 + vertex 0.897651 1.07979 2.56723 + endloop + endfacet + facet normal -0.828148 -0.285547 0.482321 + outer loop + vertex 0.898102 1.08355 2.57023 + vertex 0.895608 1.08416 2.56631 + vertex 0.897651 1.07979 2.56723 + endloop + endfacet + facet normal -0.80205 -0.281131 0.526955 + outer loop + vertex 0.899677 1.07957 2.57051 + vertex 0.900432 1.08227 2.5731 + vertex 0.898102 1.08355 2.57023 + endloop + endfacet + facet normal -0.849418 -0.315937 0.422698 + outer loop + vertex 0.894032 1.08323 2.56245 + vertex 0.895608 1.08416 2.56631 + vertex 0.893718 1.08615 2.564 + endloop + endfacet + facet normal -0.848308 -0.295661 0.439269 + outer loop + vertex 0.894414 1.0882 2.56673 + vertex 0.893718 1.08615 2.564 + vertex 0.895608 1.08416 2.56631 + endloop + endfacet + facet normal -0.818568 -0.292514 0.49435 + outer loop + vertex 0.894414 1.0882 2.56673 + vertex 0.895608 1.08416 2.56631 + vertex 0.896659 1.08905 2.57095 + endloop + endfacet + facet normal -0.829122 -0.280215 0.483773 + outer loop + vertex 0.896659 1.08905 2.57095 + vertex 0.895608 1.08416 2.56631 + vertex 0.898102 1.08355 2.57023 + endloop + endfacet + facet normal -0.801867 -0.285642 0.524802 + outer loop + vertex 0.900432 1.08227 2.5731 + vertex 0.899332 1.08612 2.57351 + vertex 0.898102 1.08355 2.57023 + endloop + endfacet + facet normal -0.815952 -0.287159 0.501759 + outer loop + vertex 0.89431 1.09814 2.57225 + vertex 0.893594 1.09577 2.56973 + vertex 0.895401 1.0947 2.57206 + endloop + endfacet + facet normal -0.595637 -0.285679 0.750735 + outer loop + vertex 0.895035 1.13333 2.59156 + vertex 0.892884 1.13267 2.5896 + vertex 0.896314 1.12971 2.59119 + endloop + endfacet + facet normal -0.548994 -0.273187 0.78992 + outer loop + vertex 0.896314 1.12971 2.59119 + vertex 0.898708 1.1321 2.59369 + vertex 0.895035 1.13333 2.59156 + endloop + endfacet + facet normal -0.564438 -0.253328 0.785643 + outer loop + vertex 0.899774 1.12666 2.5927 + vertex 0.898708 1.1321 2.59369 + vertex 0.896314 1.12971 2.59119 + endloop + endfacet + facet normal -0.59309 -0.292337 0.750189 + outer loop + vertex 0.892884 1.13267 2.5896 + vertex 0.895035 1.13333 2.59156 + vertex 0.892584 1.13587 2.59061 + endloop + endfacet + facet normal -0.567821 -0.255882 0.78237 + outer loop + vertex 0.895035 1.13333 2.59156 + vertex 0.894817 1.13673 2.59251 + vertex 0.892584 1.13587 2.59061 + endloop + endfacet + facet normal -0.54751 -0.258375 0.795911 + outer loop + vertex 0.895035 1.13333 2.59156 + vertex 0.898708 1.1321 2.59369 + vertex 0.894817 1.13673 2.59251 + endloop + endfacet + facet normal -0.507951 -0.0212726 0.861123 + outer loop + vertex 0.89429 1.20903 2.60613 + vertex 0.891643 1.20744 2.60453 + vertex 0.894323 1.20602 2.60607 + endloop + endfacet + facet normal -0.476033 -0.0212487 0.879171 + outer loop + vertex 0.894323 1.20602 2.60607 + vertex 0.897258 1.20742 2.60769 + vertex 0.89429 1.20903 2.60613 + endloop + endfacet + facet normal -0.477354 -0.0177524 0.878532 + outer loop + vertex 0.894323 1.20602 2.60607 + vertex 0.895645 1.20239 2.60672 + vertex 0.897258 1.20742 2.60769 + endloop + endfacet + facet normal -0.452058 -0.0283802 0.891537 + outer loop + vertex 0.895645 1.20239 2.60672 + vertex 0.899942 1.20243 2.6089 + vertex 0.897258 1.20742 2.60769 + endloop + endfacet + facet normal -0.5552 -0.0659995 0.829094 + outer loop + vertex 0.894815 1.38284 2.62715 + vertex 0.89756 1.38612 2.62925 + vertex 0.894448 1.38793 2.62731 + endloop + endfacet + facet normal -0.554778 -0.0648738 0.829465 + outer loop + vertex 0.89756 1.38612 2.62925 + vertex 0.897346 1.39135 2.62951 + vertex 0.894448 1.38793 2.62731 + endloop + endfacet + facet normal -0.557431 -0.0616343 0.827932 + outer loop + vertex 0.894448 1.38793 2.62731 + vertex 0.897346 1.39135 2.62951 + vertex 0.894127 1.39286 2.62746 + endloop + endfacet + facet normal -0.553658 -0.0490792 0.831297 + outer loop + vertex 0.897346 1.39135 2.62951 + vertex 0.896878 1.3969 2.62953 + vertex 0.894127 1.39286 2.62746 + endloop + endfacet + facet normal -0.544361 -0.0582463 0.836826 + outer loop + vertex 0.894127 1.39286 2.62746 + vertex 0.896878 1.3969 2.62953 + vertex 0.893554 1.39691 2.62737 + endloop + endfacet + facet normal -0.54839 -0.0449939 0.835011 + outer loop + vertex 0.897625 1.40116 2.63024 + vertex 0.897004 1.40471 2.63002 + vertex 0.894469 1.40133 2.62817 + endloop + endfacet + facet normal -0.548357 -0.0428518 0.835145 + outer loop + vertex 0.897625 1.40116 2.63024 + vertex 0.894469 1.40133 2.62817 + vertex 0.896878 1.3969 2.62953 + endloop + endfacet + facet normal -0.544833 -0.0401913 0.837581 + outer loop + vertex 0.896878 1.3969 2.62953 + vertex 0.894469 1.40133 2.62817 + vertex 0.893554 1.39691 2.62737 + endloop + endfacet + facet normal -0.626221 -0.0620836 0.777169 + outer loop + vertex 0.897625 1.40116 2.63024 + vertex 0.899266 1.40313 2.63172 + vertex 0.897004 1.40471 2.63002 + endloop + endfacet + facet normal -0.539696 -0.0542939 0.840107 + outer loop + vertex 0.893779 1.40675 2.62808 + vertex 0.894469 1.40133 2.62817 + vertex 0.897004 1.40471 2.63002 + endloop + endfacet + facet normal -0.542813 -0.0616299 0.837589 + outer loop + vertex 0.896627 1.40935 2.63012 + vertex 0.893779 1.40675 2.62808 + vertex 0.897004 1.40471 2.63002 + endloop + endfacet + facet normal -0.639598 -0.0680131 0.765695 + outer loop + vertex 0.897004 1.40471 2.63002 + vertex 0.899427 1.40675 2.63223 + vertex 0.896627 1.40935 2.63012 + endloop + endfacet + facet normal -0.633251 -0.0799934 0.769801 + outer loop + vertex 0.899266 1.40313 2.63172 + vertex 0.899427 1.40675 2.63223 + vertex 0.897004 1.40471 2.63002 + endloop + endfacet + facet normal -0.548322 -0.0532382 0.834571 + outer loop + vertex 0.8931 1.41237 2.62799 + vertex 0.893779 1.40675 2.62808 + vertex 0.896627 1.40935 2.63012 + endloop + endfacet + facet normal -0.546458 -0.0500544 0.83599 + outer loop + vertex 0.896503 1.41425 2.63033 + vertex 0.8931 1.41237 2.62799 + vertex 0.896627 1.40935 2.63012 + endloop + endfacet + facet normal -0.647033 -0.0493472 0.760863 + outer loop + vertex 0.896627 1.40935 2.63012 + vertex 0.899308 1.4115 2.63254 + vertex 0.896503 1.41425 2.63033 + endloop + endfacet + facet normal -0.638677 -0.066275 0.766615 + outer loop + vertex 0.899427 1.40675 2.63223 + vertex 0.899308 1.4115 2.63254 + vertex 0.896627 1.40935 2.63012 + endloop + endfacet + facet normal -0.559082 -0.0184065 0.828908 + outer loop + vertex 0.894036 1.41682 2.62872 + vertex 0.8931 1.41237 2.62799 + vertex 0.896503 1.41425 2.63033 + endloop + endfacet + facet normal -0.575852 -0.0422209 0.816463 + outer loop + vertex 0.896401 1.41903 2.6305 + vertex 0.894036 1.41682 2.62872 + vertex 0.896503 1.41425 2.63033 + endloop + endfacet + facet normal -0.653364 -0.0416595 0.755897 + outer loop + vertex 0.896503 1.41425 2.63033 + vertex 0.899134 1.41645 2.63272 + vertex 0.896401 1.41903 2.6305 + endloop + endfacet + facet normal -0.648333 -0.0516886 0.7596 + outer loop + vertex 0.899308 1.4115 2.63254 + vertex 0.899134 1.41645 2.63272 + vertex 0.896503 1.41425 2.63033 + endloop + endfacet + facet normal -0.570096 -0.0512301 0.819979 + outer loop + vertex 0.893398 1.42104 2.62854 + vertex 0.894036 1.41682 2.62872 + vertex 0.896401 1.41903 2.6305 + endloop + endfacet + facet normal -0.566457 -0.0428693 0.822976 + outer loop + vertex 0.896132 1.42391 2.63057 + vertex 0.893398 1.42104 2.62854 + vertex 0.896401 1.41903 2.6305 + endloop + endfacet + facet normal -0.655266 -0.0467573 0.75395 + outer loop + vertex 0.896401 1.41903 2.6305 + vertex 0.898939 1.42144 2.63286 + vertex 0.896132 1.42391 2.63057 + endloop + endfacet + facet normal -0.655667 -0.0460372 0.753646 + outer loop + vertex 0.899134 1.41645 2.63272 + vertex 0.898939 1.42144 2.63286 + vertex 0.896401 1.41903 2.6305 + endloop + endfacet + facet normal -0.566897 -0.0422583 0.822704 + outer loop + vertex 0.893065 1.42602 2.62857 + vertex 0.893398 1.42104 2.62854 + vertex 0.896132 1.42391 2.63057 + endloop + endfacet + facet normal -0.564864 -0.0377538 0.82432 + outer loop + vertex 0.895963 1.42894 2.63069 + vertex 0.893065 1.42602 2.62857 + vertex 0.896132 1.42391 2.63057 + endloop + endfacet + facet normal -0.654606 -0.0391913 0.754954 + outer loop + vertex 0.896132 1.42391 2.63057 + vertex 0.898763 1.42645 2.63299 + vertex 0.895963 1.42894 2.63069 + endloop + endfacet + facet normal -0.652975 -0.0420728 0.75621 + outer loop + vertex 0.898939 1.42144 2.63286 + vertex 0.898763 1.42645 2.63299 + vertex 0.896132 1.42391 2.63057 + endloop + endfacet + facet normal -0.56636 -0.0355942 0.823389 + outer loop + vertex 0.892931 1.43105 2.62869 + vertex 0.893065 1.42602 2.62857 + vertex 0.895963 1.42894 2.63069 + endloop + endfacet + facet normal -0.566637 -0.0361954 0.823172 + outer loop + vertex 0.895865 1.43395 2.63084 + vertex 0.892931 1.43105 2.62869 + vertex 0.895963 1.42894 2.63069 + endloop + endfacet + facet normal -0.656734 -0.0358396 0.75327 + outer loop + vertex 0.895963 1.42894 2.63069 + vertex 0.898627 1.43147 2.63313 + vertex 0.895865 1.43395 2.63084 + endloop + endfacet + facet normal -0.654734 -0.0394509 0.754829 + outer loop + vertex 0.898763 1.42645 2.63299 + vertex 0.898627 1.43147 2.63313 + vertex 0.895963 1.42894 2.63069 + endloop + endfacet + facet normal -0.569828 -0.0314777 0.821161 + outer loop + vertex 0.892872 1.43606 2.62884 + vertex 0.892931 1.43105 2.62869 + vertex 0.895865 1.43395 2.63084 + endloop + endfacet + facet normal -0.570919 -0.0338385 0.820309 + outer loop + vertex 0.895773 1.43894 2.63098 + vertex 0.892872 1.43606 2.62884 + vertex 0.895865 1.43395 2.63084 + endloop + endfacet + facet normal -0.660106 -0.0334986 0.750425 + outer loop + vertex 0.895865 1.43395 2.63084 + vertex 0.898503 1.43646 2.63327 + vertex 0.895773 1.43894 2.63098 + endloop + endfacet + facet normal -0.657726 -0.0378294 0.752307 + outer loop + vertex 0.898627 1.43147 2.63313 + vertex 0.898503 1.43646 2.63327 + vertex 0.895865 1.43395 2.63084 + endloop + endfacet + facet normal -0.575102 -0.0276277 0.817615 + outer loop + vertex 0.892807 1.44104 2.62897 + vertex 0.892872 1.43606 2.62884 + vertex 0.895773 1.43894 2.63098 + endloop + endfacet + facet normal -0.576896 -0.0314969 0.81621 + outer loop + vertex 0.895666 1.44392 2.6311 + vertex 0.892807 1.44104 2.62897 + vertex 0.895773 1.43894 2.63098 + endloop + endfacet + facet normal -0.665202 -0.0317557 0.745987 + outer loop + vertex 0.895773 1.43894 2.63098 + vertex 0.898369 1.44144 2.6334 + vertex 0.895666 1.44392 2.6311 + endloop + endfacet + facet normal -0.662073 -0.0374431 0.748503 + outer loop + vertex 0.898503 1.43646 2.63327 + vertex 0.898369 1.44144 2.6334 + vertex 0.895773 1.43894 2.63098 + endloop + endfacet + facet normal -0.579908 -0.0270297 0.814233 + outer loop + vertex 0.892715 1.44603 2.62907 + vertex 0.892807 1.44104 2.62897 + vertex 0.895666 1.44392 2.6311 + endloop + endfacet + facet normal -0.580836 -0.0290304 0.813503 + outer loop + vertex 0.895557 1.4489 2.6312 + vertex 0.892715 1.44603 2.62907 + vertex 0.895666 1.44392 2.6311 + endloop + endfacet + facet normal -0.669867 -0.029535 0.741893 + outer loop + vertex 0.895666 1.44392 2.6311 + vertex 0.898234 1.44642 2.63352 + vertex 0.895557 1.4489 2.6312 + endloop + endfacet + facet normal -0.666841 -0.0350419 0.744376 + outer loop + vertex 0.898369 1.44144 2.6334 + vertex 0.898234 1.44642 2.63352 + vertex 0.895666 1.44392 2.6311 + endloop + endfacet + facet normal -0.583336 -0.0253206 0.811836 + outer loop + vertex 0.892622 1.45101 2.62916 + vertex 0.892715 1.44603 2.62907 + vertex 0.895557 1.4489 2.6312 + endloop + endfacet + facet normal -0.584105 -0.0269748 0.81123 + outer loop + vertex 0.89546 1.45388 2.63129 + vertex 0.892622 1.45101 2.62916 + vertex 0.895557 1.4489 2.6312 + endloop + endfacet + facet normal -0.673731 -0.0273315 0.738471 + outer loop + vertex 0.895557 1.4489 2.6312 + vertex 0.898111 1.4514 2.63362 + vertex 0.89546 1.45388 2.63129 + endloop + endfacet + facet normal -0.671138 -0.0320784 0.740638 + outer loop + vertex 0.898234 1.44642 2.63352 + vertex 0.898111 1.4514 2.63362 + vertex 0.895557 1.4489 2.6312 + endloop + endfacet + facet normal -0.587512 -0.0218876 0.80892 + outer loop + vertex 0.892547 1.45601 2.62924 + vertex 0.892622 1.45101 2.62916 + vertex 0.89546 1.45388 2.63129 + endloop + endfacet + facet normal -0.588236 -0.0234324 0.808349 + outer loop + vertex 0.895378 1.45887 2.63138 + vertex 0.892547 1.45601 2.62924 + vertex 0.89546 1.45388 2.63129 + endloop + endfacet + facet normal -0.675807 -0.0236454 0.736699 + outer loop + vertex 0.89546 1.45388 2.63129 + vertex 0.898009 1.45639 2.63371 + vertex 0.895378 1.45887 2.63138 + endloop + endfacet + facet normal -0.673767 -0.0274032 0.738436 + outer loop + vertex 0.898111 1.4514 2.63362 + vertex 0.898009 1.45639 2.63371 + vertex 0.89546 1.45388 2.63129 + endloop + endfacet + facet normal -0.589985 -0.0208032 0.807146 + outer loop + vertex 0.892478 1.461 2.62932 + vertex 0.892547 1.45601 2.62924 + vertex 0.895378 1.45887 2.63138 + endloop + endfacet + facet normal -0.589545 -0.0198711 0.807491 + outer loop + vertex 0.895309 1.46386 2.63145 + vertex 0.892478 1.461 2.62932 + vertex 0.895378 1.45887 2.63138 + endloop + endfacet + facet normal -0.67885 -0.0200468 0.734003 + outer loop + vertex 0.895378 1.45887 2.63138 + vertex 0.897919 1.46137 2.6338 + vertex 0.895309 1.46386 2.63145 + endloop + endfacet + facet normal -0.676341 -0.0247026 0.736175 + outer loop + vertex 0.898009 1.45639 2.63371 + vertex 0.897919 1.46137 2.6338 + vertex 0.895378 1.45887 2.63138 + endloop + endfacet + facet normal -0.590856 -0.0178947 0.806579 + outer loop + vertex 0.892418 1.46599 2.62938 + vertex 0.892478 1.461 2.62932 + vertex 0.895309 1.46386 2.63145 + endloop + endfacet + facet normal -0.59053 -0.0172058 0.806832 + outer loop + vertex 0.895251 1.46885 2.63152 + vertex 0.892418 1.46599 2.62938 + vertex 0.895309 1.46386 2.63145 + endloop + endfacet + facet normal -0.680667 -0.0172823 0.732389 + outer loop + vertex 0.895309 1.46386 2.63145 + vertex 0.897848 1.46636 2.63387 + vertex 0.895251 1.46885 2.63152 + endloop + endfacet + facet normal -0.679014 -0.0203691 0.733843 + outer loop + vertex 0.897919 1.46137 2.6338 + vertex 0.897848 1.46636 2.63387 + vertex 0.895309 1.46386 2.63145 + endloop + endfacet + facet normal -0.590653 -0.0170201 0.806746 + outer loop + vertex 0.892364 1.47098 2.62945 + vertex 0.892418 1.46599 2.62938 + vertex 0.895251 1.46885 2.63152 + endloop + endfacet + facet normal -0.590896 -0.0175358 0.806557 + outer loop + vertex 0.895204 1.47384 2.63159 + vertex 0.892364 1.47098 2.62945 + vertex 0.895251 1.46885 2.63152 + endloop + endfacet + facet normal -0.682667 -0.0172743 0.730525 + outer loop + vertex 0.895251 1.46885 2.63152 + vertex 0.897788 1.47135 2.63395 + vertex 0.895204 1.47384 2.63159 + endloop + endfacet + facet normal -0.68164 -0.0191992 0.731435 + outer loop + vertex 0.897848 1.46636 2.63387 + vertex 0.897788 1.47135 2.63395 + vertex 0.895251 1.46885 2.63152 + endloop + endfacet + facet normal -0.592045 -0.0157907 0.80575 + outer loop + vertex 0.892322 1.47596 2.62951 + vertex 0.892364 1.47098 2.62945 + vertex 0.895204 1.47384 2.63159 + endloop + endfacet + facet normal -0.593592 -0.0190701 0.80454 + outer loop + vertex 0.895165 1.47882 2.63168 + vertex 0.892322 1.47596 2.62951 + vertex 0.895204 1.47384 2.63159 + endloop + endfacet + facet normal -0.68751 -0.0183948 0.725942 + outer loop + vertex 0.895204 1.47384 2.63159 + vertex 0.897737 1.47635 2.63405 + vertex 0.895165 1.47882 2.63168 + endloop + endfacet + facet normal -0.685316 -0.0225284 0.727897 + outer loop + vertex 0.897788 1.47135 2.63395 + vertex 0.897737 1.47635 2.63405 + vertex 0.895204 1.47384 2.63159 + endloop + endfacet + facet normal -0.597148 -0.0136204 0.802015 + outer loop + vertex 0.892293 1.48096 2.62958 + vertex 0.892322 1.47596 2.62951 + vertex 0.895165 1.47882 2.63168 + endloop + endfacet + facet normal -0.597863 -0.01513 0.801456 + outer loop + vertex 0.895123 1.4838 2.63174 + vertex 0.892293 1.48096 2.62958 + vertex 0.895165 1.47882 2.63168 + endloop + endfacet + facet normal -0.693667 -0.0149325 0.720141 + outer loop + vertex 0.895165 1.47882 2.63168 + vertex 0.897708 1.48139 2.63418 + vertex 0.895123 1.4838 2.63174 + endloop + endfacet + facet normal -0.689597 -0.0225761 0.723841 + outer loop + vertex 0.897737 1.47635 2.63405 + vertex 0.897708 1.48139 2.63418 + vertex 0.895165 1.47882 2.63168 + endloop + endfacet + facet normal -0.599682 -0.0123169 0.800144 + outer loop + vertex 0.892267 1.48596 2.62963 + vertex 0.892293 1.48096 2.62958 + vertex 0.895123 1.4838 2.63174 + endloop + endfacet + facet normal -0.598812 -0.0105053 0.800821 + outer loop + vertex 0.895075 1.48873 2.63177 + vertex 0.892267 1.48596 2.62963 + vertex 0.895123 1.4838 2.63174 + endloop + endfacet + facet normal -0.691831 -0.0109481 0.721977 + outer loop + vertex 0.895123 1.4838 2.63174 + vertex 0.897574 1.4863 2.63413 + vertex 0.895075 1.48873 2.63177 + endloop + endfacet + facet normal -0.691789 -0.011026 0.722015 + outer loop + vertex 0.897708 1.48139 2.63418 + vertex 0.897574 1.4863 2.63413 + vertex 0.895123 1.4838 2.63174 + endloop + endfacet + facet normal -0.59913 -0.0100044 0.800589 + outer loop + vertex 0.892245 1.49096 2.62968 + vertex 0.892267 1.48596 2.62963 + vertex 0.895075 1.48873 2.63177 + endloop + endfacet + facet normal -0.59922 -0.0101836 0.80052 + outer loop + vertex 0.895049 1.49365 2.63181 + vertex 0.892245 1.49096 2.62968 + vertex 0.895075 1.48873 2.63177 + endloop + endfacet + facet normal -0.690954 -0.00997501 0.72283 + outer loop + vertex 0.895075 1.48873 2.63177 + vertex 0.897466 1.49099 2.63409 + vertex 0.895049 1.49365 2.63181 + endloop + endfacet + facet normal -0.691146 -0.00958752 0.722651 + outer loop + vertex 0.897574 1.4863 2.63413 + vertex 0.897466 1.49099 2.63409 + vertex 0.895075 1.48873 2.63177 + endloop + endfacet + facet normal -0.601998 -0.00566103 0.798477 + outer loop + vertex 0.892233 1.49598 2.62971 + vertex 0.892245 1.49096 2.62968 + vertex 0.895049 1.49365 2.63181 + endloop + endfacet + facet normal -0.604206 -0.00985776 0.796767 + outer loop + vertex 0.895031 1.49861 2.63186 + vertex 0.892233 1.49598 2.62971 + vertex 0.895049 1.49365 2.63181 + endloop + endfacet + facet normal -0.695968 -0.00943625 0.718011 + outer loop + vertex 0.895049 1.49365 2.63181 + vertex 0.897498 1.49574 2.63422 + vertex 0.895031 1.49861 2.63186 + endloop + endfacet + facet normal -0.693626 -0.0146619 0.720186 + outer loop + vertex 0.897466 1.49099 2.63409 + vertex 0.897498 1.49574 2.63422 + vertex 0.895049 1.49365 2.63181 + endloop + endfacet + facet normal -0.607289 -0.00468473 0.794467 + outer loop + vertex 0.892213 1.50101 2.62972 + vertex 0.892233 1.49598 2.62971 + vertex 0.895031 1.49861 2.63186 + endloop + endfacet + facet normal -0.607566 -0.00520097 0.794252 + outer loop + vertex 0.895005 1.50362 2.63187 + vertex 0.892213 1.50101 2.62972 + vertex 0.895031 1.49861 2.63186 + endloop + endfacet + facet normal -0.699692 -0.00546549 0.714423 + outer loop + vertex 0.895031 1.49861 2.63186 + vertex 0.89749 1.50068 2.63429 + vertex 0.895005 1.50362 2.63187 + endloop + endfacet + facet normal -0.697123 -0.0113737 0.716861 + outer loop + vertex 0.897498 1.49574 2.63422 + vertex 0.89749 1.50068 2.63429 + vertex 0.895031 1.49861 2.63186 + endloop + endfacet + facet normal -0.608944 -0.00286543 0.793208 + outer loop + vertex 0.89219 1.50602 2.62972 + vertex 0.892213 1.50101 2.62972 + vertex 0.895005 1.50362 2.63187 + endloop + endfacet + facet normal -0.608657 -0.00232941 0.79343 + outer loop + vertex 0.894981 1.50863 2.63187 + vertex 0.89219 1.50602 2.62972 + vertex 0.895005 1.50362 2.63187 + endloop + endfacet + facet normal -0.700892 -0.00282542 0.713262 + outer loop + vertex 0.895005 1.50362 2.63187 + vertex 0.897465 1.50568 2.6343 + vertex 0.894981 1.50863 2.63187 + endloop + endfacet + facet normal -0.699734 -0.00553426 0.714382 + outer loop + vertex 0.89749 1.50068 2.63429 + vertex 0.897465 1.50568 2.6343 + vertex 0.895005 1.50362 2.63187 + endloop + endfacet + facet normal -0.609834 -0.000328277 0.792529 + outer loop + vertex 0.892182 1.51103 2.62972 + vertex 0.89219 1.50602 2.62972 + vertex 0.894981 1.50863 2.63187 + endloop + endfacet + facet normal -0.610098 -0.000818747 0.792326 + outer loop + vertex 0.894971 1.51364 2.63187 + vertex 0.892182 1.51103 2.62972 + vertex 0.894981 1.50863 2.63187 + endloop + endfacet + facet normal -0.701241 -0.00105414 0.712924 + outer loop + vertex 0.894981 1.50863 2.63187 + vertex 0.897443 1.51068 2.6343 + vertex 0.894971 1.51364 2.63187 + endloop + endfacet + facet normal -0.700656 -0.00243475 0.713495 + outer loop + vertex 0.897465 1.50568 2.6343 + vertex 0.897443 1.51068 2.6343 + vertex 0.894981 1.50863 2.63187 + endloop + endfacet + facet normal -0.610663 0.00014568 0.791891 + outer loop + vertex 0.892183 1.51603 2.62972 + vertex 0.892182 1.51103 2.62972 + vertex 0.894971 1.51364 2.63187 + endloop + endfacet + facet normal -0.610822 -0.000151112 0.791768 + outer loop + vertex 0.894971 1.51863 2.63187 + vertex 0.892183 1.51603 2.62972 + vertex 0.894971 1.51364 2.63187 + endloop + endfacet + facet normal -0.702427 -0.000135841 0.711756 + outer loop + vertex 0.894971 1.51364 2.63187 + vertex 0.897429 1.51567 2.63429 + vertex 0.894971 1.51863 2.63187 + endloop + endfacet + facet normal -0.701714 -0.0018326 0.712457 + outer loop + vertex 0.897443 1.51068 2.6343 + vertex 0.897429 1.51567 2.63429 + vertex 0.894971 1.51364 2.63187 + endloop + endfacet + facet normal -0.610569 -0.000584251 0.791963 + outer loop + vertex 0.892183 1.52101 2.62972 + vertex 0.892183 1.51603 2.62972 + vertex 0.894971 1.51863 2.63187 + endloop + endfacet + facet normal -0.609706 0.00102613 0.792627 + outer loop + vertex 0.894973 1.52363 2.63186 + vertex 0.892183 1.52101 2.62972 + vertex 0.894971 1.51863 2.63187 + endloop + endfacet + facet normal -0.702864 0.000989638 0.711323 + outer loop + vertex 0.894971 1.51863 2.63187 + vertex 0.897425 1.52066 2.63429 + vertex 0.894973 1.52363 2.63186 + endloop + endfacet + facet normal -0.702407 -0.000102803 0.711775 + outer loop + vertex 0.897429 1.51567 2.63429 + vertex 0.897425 1.52066 2.63429 + vertex 0.894971 1.51863 2.63187 + endloop + endfacet + facet normal -0.610848 0.00297132 0.791742 + outer loop + vertex 0.892191 1.52601 2.62971 + vertex 0.892183 1.52101 2.62972 + vertex 0.894973 1.52363 2.63186 + endloop + endfacet + facet normal -0.609788 0.00493755 0.792549 + outer loop + vertex 0.894982 1.52863 2.63184 + vertex 0.892191 1.52601 2.62971 + vertex 0.894973 1.52363 2.63186 + endloop + endfacet + facet normal -0.701932 0.00470132 0.712229 + outer loop + vertex 0.894973 1.52363 2.63186 + vertex 0.897433 1.52566 2.63428 + vertex 0.894982 1.52863 2.63184 + endloop + endfacet + facet normal -0.701387 0.00339868 0.712773 + outer loop + vertex 0.897425 1.52066 2.63429 + vertex 0.897433 1.52566 2.63428 + vertex 0.894973 1.52363 2.63186 + endloop + endfacet + facet normal -0.608964 0.00353595 0.79319 + outer loop + vertex 0.892191 1.531 2.62969 + vertex 0.892191 1.52601 2.62971 + vertex 0.894982 1.52863 2.63184 + endloop + endfacet + facet normal -0.606942 0.00730324 0.794712 + outer loop + vertex 0.894997 1.53363 2.63181 + vertex 0.892191 1.531 2.62969 + vertex 0.894982 1.52863 2.63184 + endloop + endfacet + facet normal -0.699353 0.00702573 0.714742 + outer loop + vertex 0.894982 1.52863 2.63184 + vertex 0.897457 1.53067 2.63424 + vertex 0.894997 1.53363 2.63181 + endloop + endfacet + facet normal -0.699814 0.00813383 0.714279 + outer loop + vertex 0.897433 1.52566 2.63428 + vertex 0.897457 1.53067 2.63424 + vertex 0.894982 1.52863 2.63184 + endloop + endfacet + facet normal -0.606831 0.00711461 0.794799 + outer loop + vertex 0.892201 1.53599 2.62965 + vertex 0.892191 1.531 2.62969 + vertex 0.894997 1.53363 2.63181 + endloop + endfacet + facet normal -0.606124 0.00843419 0.795326 + outer loop + vertex 0.895029 1.53865 2.63178 + vertex 0.892201 1.53599 2.62965 + vertex 0.894997 1.53363 2.63181 + endloop + endfacet + facet normal -0.697844 0.00858272 0.716198 + outer loop + vertex 0.894997 1.53363 2.63181 + vertex 0.897507 1.53568 2.63423 + vertex 0.895029 1.53865 2.63178 + endloop + endfacet + facet normal -0.698063 0.00911157 0.715978 + outer loop + vertex 0.897457 1.53067 2.63424 + vertex 0.897507 1.53568 2.63423 + vertex 0.894997 1.53363 2.63181 + endloop + endfacet + facet normal -0.605492 0.00736999 0.795817 + outer loop + vertex 0.892215 1.54097 2.62961 + vertex 0.892201 1.53599 2.62965 + vertex 0.895029 1.53865 2.63178 + endloop + endfacet + facet normal -0.604308 0.00962194 0.796693 + outer loop + vertex 0.895068 1.5437 2.63175 + vertex 0.892215 1.54097 2.62961 + vertex 0.895029 1.53865 2.63178 + endloop + endfacet + facet normal -0.698644 0.00983391 0.715402 + outer loop + vertex 0.895029 1.53865 2.63178 + vertex 0.897613 1.54078 2.63427 + vertex 0.895068 1.5437 2.63175 + endloop + endfacet + facet normal -0.698008 0.0083177 0.716042 + outer loop + vertex 0.897507 1.53568 2.63423 + vertex 0.897613 1.54078 2.63427 + vertex 0.895029 1.53865 2.63178 + endloop + endfacet + facet normal -0.603921 0.00898325 0.796994 + outer loop + vertex 0.892239 1.54595 2.62958 + vertex 0.892215 1.54097 2.62961 + vertex 0.895068 1.5437 2.63175 + endloop + endfacet + facet normal -0.601994 0.0127678 0.798399 + outer loop + vertex 0.8951 1.54877 2.63169 + vertex 0.892239 1.54595 2.62958 + vertex 0.895068 1.5437 2.63175 + endloop + endfacet + facet normal -0.69644 0.0124432 0.717507 + outer loop + vertex 0.895068 1.5437 2.63175 + vertex 0.897662 1.54603 2.63422 + vertex 0.8951 1.54877 2.63169 + endloop + endfacet + facet normal -0.696728 0.0130734 0.717216 + outer loop + vertex 0.897613 1.54078 2.63427 + vertex 0.897662 1.54603 2.63422 + vertex 0.895068 1.5437 2.63175 + endloop + endfacet + facet normal -0.600668 0.0106531 0.799428 + outer loop + vertex 0.892271 1.55092 2.62953 + vertex 0.892239 1.54595 2.62958 + vertex 0.8951 1.54877 2.63169 + endloop + endfacet + facet normal -0.598828 0.014396 0.800748 + outer loop + vertex 0.895139 1.55379 2.63163 + vertex 0.892271 1.55092 2.62953 + vertex 0.8951 1.54877 2.63169 + endloop + endfacet + facet normal -0.690597 0.0141862 0.723101 + outer loop + vertex 0.8951 1.54877 2.63169 + vertex 0.897654 1.55124 2.63408 + vertex 0.895139 1.55379 2.63163 + endloop + endfacet + facet normal -0.692897 0.0187954 0.720792 + outer loop + vertex 0.897662 1.54603 2.63422 + vertex 0.897654 1.55124 2.63408 + vertex 0.8951 1.54877 2.63169 + endloop + endfacet + facet normal -0.598914 0.0145301 0.800681 + outer loop + vertex 0.892318 1.55589 2.62948 + vertex 0.892271 1.55092 2.62953 + vertex 0.895139 1.55379 2.63163 + endloop + endfacet + facet normal -0.596977 0.0185355 0.802044 + outer loop + vertex 0.895207 1.55878 2.63156 + vertex 0.892318 1.55589 2.62948 + vertex 0.895139 1.55379 2.63163 + endloop + endfacet + facet normal -0.688435 0.0187863 0.725054 + outer loop + vertex 0.895139 1.55379 2.63163 + vertex 0.897705 1.5563 2.634 + vertex 0.895207 1.55878 2.63156 + endloop + endfacet + facet normal -0.688284 0.0184892 0.725205 + outer loop + vertex 0.897654 1.55124 2.63408 + vertex 0.897705 1.5563 2.634 + vertex 0.895139 1.55379 2.63163 + endloop + endfacet + facet normal -0.595957 0.0169457 0.802837 + outer loop + vertex 0.892369 1.56085 2.62941 + vertex 0.892318 1.55589 2.62948 + vertex 0.895207 1.55878 2.63156 + endloop + endfacet + facet normal -0.594135 0.0207514 0.804098 + outer loop + vertex 0.895279 1.56375 2.63149 + vertex 0.892369 1.56085 2.62941 + vertex 0.895207 1.55878 2.63156 + endloop + endfacet + facet normal -0.686858 0.0209126 0.726491 + outer loop + vertex 0.895207 1.55878 2.63156 + vertex 0.897791 1.56129 2.63393 + vertex 0.895279 1.56375 2.63149 + endloop + endfacet + facet normal -0.687078 0.0213472 0.72627 + outer loop + vertex 0.897705 1.5563 2.634 + vertex 0.897791 1.56129 2.63393 + vertex 0.895207 1.55878 2.63156 + endloop + endfacet + facet normal -0.595296 0.022565 0.80319 + outer loop + vertex 0.892432 1.56584 2.62932 + vertex 0.892369 1.56085 2.62941 + vertex 0.895279 1.56375 2.63149 + endloop + endfacet + facet normal -0.594038 0.0251686 0.804043 + outer loop + vertex 0.895355 1.56874 2.63139 + vertex 0.892432 1.56584 2.62932 + vertex 0.895279 1.56375 2.63149 + endloop + endfacet + facet normal -0.683443 0.0250415 0.729574 + outer loop + vertex 0.895279 1.56375 2.63149 + vertex 0.897891 1.56627 2.63385 + vertex 0.895355 1.56874 2.63139 + endloop + endfacet + facet normal -0.684048 0.0262376 0.728965 + outer loop + vertex 0.897791 1.56129 2.63393 + vertex 0.897891 1.56627 2.63385 + vertex 0.895279 1.56375 2.63149 + endloop + endfacet + facet normal -0.592839 0.0232904 0.804984 + outer loop + vertex 0.892495 1.57083 2.62922 + vertex 0.892432 1.56584 2.62932 + vertex 0.895355 1.56874 2.63139 + endloop + endfacet + facet normal -0.591753 0.0255379 0.805715 + outer loop + vertex 0.895427 1.57373 2.63128 + vertex 0.892495 1.57083 2.62922 + vertex 0.895355 1.56874 2.63139 + endloop + endfacet + facet normal -0.678516 0.0252776 0.73415 + outer loop + vertex 0.895355 1.56874 2.63139 + vertex 0.897992 1.57127 2.63374 + vertex 0.895427 1.57373 2.63128 + endloop + endfacet + facet normal -0.680864 0.0299103 0.731799 + outer loop + vertex 0.897891 1.56627 2.63385 + vertex 0.897992 1.57127 2.63374 + vertex 0.895355 1.56874 2.63139 + endloop + endfacet + facet normal -0.590698 0.0238888 0.806539 + outer loop + vertex 0.892563 1.57582 2.62912 + vertex 0.892495 1.57083 2.62922 + vertex 0.895427 1.57373 2.63128 + endloop + endfacet + facet normal -0.589838 0.0256642 0.807114 + outer loop + vertex 0.895501 1.57873 2.63118 + vertex 0.892563 1.57582 2.62912 + vertex 0.895427 1.57373 2.63128 + endloop + endfacet + facet normal -0.674572 0.0254586 0.73777 + outer loop + vertex 0.895427 1.57373 2.63128 + vertex 0.898086 1.57627 2.63363 + vertex 0.895501 1.57873 2.63118 + endloop + endfacet + facet normal -0.67646 0.029167 0.735902 + outer loop + vertex 0.897992 1.57127 2.63374 + vertex 0.898086 1.57627 2.63363 + vertex 0.895427 1.57373 2.63128 + endloop + endfacet + facet normal -0.588873 0.0241574 0.807865 + outer loop + vertex 0.892634 1.58082 2.62902 + vertex 0.892563 1.57582 2.62912 + vertex 0.895501 1.57873 2.63118 + endloop + endfacet + facet normal -0.588095 0.0257565 0.808381 + outer loop + vertex 0.89558 1.58372 2.63108 + vertex 0.892634 1.58082 2.62902 + vertex 0.895501 1.57873 2.63118 + endloop + endfacet + facet normal -0.671691 0.0256996 0.740385 + outer loop + vertex 0.895501 1.57873 2.63118 + vertex 0.89818 1.58126 2.63352 + vertex 0.89558 1.58372 2.63108 + endloop + endfacet + facet normal -0.673042 0.0283512 0.73906 + outer loop + vertex 0.898086 1.57627 2.63363 + vertex 0.89818 1.58126 2.63352 + vertex 0.895501 1.57873 2.63118 + endloop + endfacet + facet normal -0.586643 0.023492 0.809505 + outer loop + vertex 0.892703 1.58581 2.62893 + vertex 0.892634 1.58082 2.62902 + vertex 0.89558 1.58372 2.63108 + endloop + endfacet + facet normal -0.584537 0.0278183 0.81089 + outer loop + vertex 0.895671 1.58872 2.63097 + vertex 0.892703 1.58581 2.62893 + vertex 0.89558 1.58372 2.63108 + endloop + endfacet + facet normal -0.6693 0.027897 0.742469 + outer loop + vertex 0.89558 1.58372 2.63108 + vertex 0.898282 1.58626 2.63342 + vertex 0.895671 1.58872 2.63097 + endloop + endfacet + facet normal -0.6699 0.0290782 0.741882 + outer loop + vertex 0.89818 1.58126 2.63352 + vertex 0.898282 1.58626 2.63342 + vertex 0.89558 1.58372 2.63108 + endloop + endfacet + facet normal -0.584801 0.0282309 0.810685 + outer loop + vertex 0.892788 1.59082 2.62882 + vertex 0.892703 1.58581 2.62893 + vertex 0.895671 1.58872 2.63097 + endloop + endfacet + facet normal -0.583075 0.0317534 0.811797 + outer loop + vertex 0.895775 1.59371 2.63085 + vertex 0.892788 1.59082 2.62882 + vertex 0.895671 1.58872 2.63097 + endloop + endfacet + facet normal -0.666312 0.0318967 0.744991 + outer loop + vertex 0.895671 1.58872 2.63097 + vertex 0.8984 1.59126 2.6333 + vertex 0.895775 1.59371 2.63085 + endloop + endfacet + facet normal -0.666728 0.0327209 0.744582 + outer loop + vertex 0.898282 1.58626 2.63342 + vertex 0.8984 1.59126 2.6333 + vertex 0.895671 1.58872 2.63097 + endloop + endfacet + facet normal -0.583289 0.0320901 0.811631 + outer loop + vertex 0.892885 1.5958 2.62869 + vertex 0.892788 1.59082 2.62882 + vertex 0.895775 1.59371 2.63085 + endloop + endfacet + facet normal -0.580459 0.0378492 0.813409 + outer loop + vertex 0.895893 1.59868 2.6307 + vertex 0.892885 1.5958 2.62869 + vertex 0.895775 1.59371 2.63085 + endloop + endfacet + facet normal -0.664931 0.0378439 0.745945 + outer loop + vertex 0.895775 1.59371 2.63085 + vertex 0.898524 1.59623 2.63317 + vertex 0.895893 1.59868 2.6307 + endloop + endfacet + facet normal -0.664065 0.0361049 0.746803 + outer loop + vertex 0.8984 1.59126 2.6333 + vertex 0.898524 1.59623 2.63317 + vertex 0.895775 1.59371 2.63085 + endloop + endfacet + facet normal -0.579274 0.0359609 0.814339 + outer loop + vertex 0.892983 1.60074 2.62854 + vertex 0.892885 1.5958 2.62869 + vertex 0.895893 1.59868 2.6307 + endloop + endfacet + facet normal -0.57739 0.0398309 0.815496 + outer loop + vertex 0.895989 1.60361 2.63053 + vertex 0.892983 1.60074 2.62854 + vertex 0.895893 1.59868 2.6307 + endloop + endfacet + facet normal -0.662303 0.0391271 0.748213 + outer loop + vertex 0.895893 1.59868 2.6307 + vertex 0.898651 1.60117 2.63301 + vertex 0.895989 1.60361 2.63053 + endloop + endfacet + facet normal -0.663235 0.0410164 0.747287 + outer loop + vertex 0.898524 1.59623 2.63317 + vertex 0.898651 1.60117 2.63301 + vertex 0.895893 1.59868 2.6307 + endloop + endfacet + facet normal -0.576769 0.0388438 0.815983 + outer loop + vertex 0.893017 1.60566 2.62833 + vertex 0.892983 1.60074 2.62854 + vertex 0.895989 1.60361 2.63053 + endloop + endfacet + facet normal -0.574337 0.0439349 0.817439 + outer loop + vertex 0.89606 1.60862 2.63031 + vertex 0.893017 1.60566 2.62833 + vertex 0.895989 1.60361 2.63053 + endloop + endfacet + facet normal -0.657893 0.0422635 0.751925 + outer loop + vertex 0.895989 1.60361 2.63053 + vertex 0.898786 1.60613 2.63284 + vertex 0.89606 1.60862 2.63031 + endloop + endfacet + facet normal -0.659216 0.0449377 0.750609 + outer loop + vertex 0.898651 1.60117 2.63301 + vertex 0.898786 1.60613 2.63284 + vertex 0.895989 1.60361 2.63053 + endloop + endfacet + facet normal -0.568825 0.0354121 0.821696 + outer loop + vertex 0.892723 1.61091 2.6279 + vertex 0.893017 1.60566 2.62833 + vertex 0.89606 1.60862 2.63031 + endloop + endfacet + facet normal -0.561081 0.0513972 0.826164 + outer loop + vertex 0.896321 1.61372 2.63017 + vertex 0.892723 1.61091 2.6279 + vertex 0.89606 1.60862 2.63031 + endloop + endfacet + facet normal -0.654503 0.0541804 0.754116 + outer loop + vertex 0.89606 1.60862 2.63031 + vertex 0.898986 1.61116 2.63267 + vertex 0.896321 1.61372 2.63017 + endloop + endfacet + facet normal -0.653084 0.0512147 0.755551 + outer loop + vertex 0.898786 1.60613 2.63284 + vertex 0.898986 1.61116 2.63267 + vertex 0.89606 1.60862 2.63031 + endloop + endfacet + facet normal -0.565963 0.0608427 0.822183 + outer loop + vertex 0.893576 1.61646 2.62808 + vertex 0.892723 1.61091 2.6279 + vertex 0.896321 1.61372 2.63017 + endloop + endfacet + facet normal -0.564652 0.0627362 0.822942 + outer loop + vertex 0.896828 1.61866 2.63014 + vertex 0.893576 1.61646 2.62808 + vertex 0.896321 1.61372 2.63017 + endloop + endfacet + facet normal -0.654262 0.0715485 0.752876 + outer loop + vertex 0.896321 1.61372 2.63017 + vertex 0.899257 1.61617 2.63249 + vertex 0.896828 1.61866 2.63014 + endloop + endfacet + facet normal -0.649971 0.0621002 0.757418 + outer loop + vertex 0.898986 1.61116 2.63267 + vertex 0.899257 1.61617 2.63249 + vertex 0.896321 1.61372 2.63017 + endloop + endfacet + facet normal -0.565015 0.0635696 0.822628 + outer loop + vertex 0.894439 1.62205 2.62824 + vertex 0.893576 1.61646 2.62808 + vertex 0.896828 1.61866 2.63014 + endloop + endfacet + facet normal -0.564247 0.0643708 0.823093 + outer loop + vertex 0.897463 1.62239 2.63029 + vertex 0.894439 1.62205 2.62824 + vertex 0.896828 1.61866 2.63014 + endloop + endfacet + facet normal -0.657925 0.0831848 0.748475 + outer loop + vertex 0.896828 1.61866 2.63014 + vertex 0.899441 1.62081 2.6322 + vertex 0.897463 1.62239 2.63029 + endloop + endfacet + facet normal -0.65342 0.0729364 0.753474 + outer loop + vertex 0.899257 1.61617 2.63249 + vertex 0.899441 1.62081 2.6322 + vertex 0.896828 1.61866 2.63014 + endloop + endfacet + facet normal -0.642738 0.0380639 0.76514 + outer loop + vertex 0.897463 1.62239 2.63029 + vertex 0.899135 1.62428 2.6316 + vertex 0.897086 1.62582 2.6298 + endloop + endfacet + facet normal -0.563853 0.0550952 0.824035 + outer loop + vertex 0.897463 1.62239 2.63029 + vertex 0.897086 1.62582 2.6298 + vertex 0.894439 1.62205 2.62824 + endloop + endfacet + facet normal -0.558673 0.0498593 0.827888 + outer loop + vertex 0.894439 1.62205 2.62824 + vertex 0.897086 1.62582 2.6298 + vertex 0.894182 1.62742 2.62774 + endloop + endfacet + facet normal -0.663829 0.0709838 0.744508 + outer loop + vertex 0.899135 1.62428 2.6316 + vertex 0.897463 1.62239 2.63029 + vertex 0.899441 1.62081 2.6322 + endloop + endfacet + facet normal -0.563542 0.0376196 0.82523 + outer loop + vertex 0.897086 1.62582 2.6298 + vertex 0.897203 1.63041 2.62967 + vertex 0.894182 1.62742 2.62774 + endloop + endfacet + facet normal -0.571167 0.0491139 0.819363 + outer loop + vertex 0.894182 1.62742 2.62774 + vertex 0.897203 1.63041 2.62967 + vertex 0.894229 1.63245 2.62747 + endloop + endfacet + facet normal -0.570113 0.0513002 0.819963 + outer loop + vertex 0.897203 1.63041 2.62967 + vertex 0.897344 1.63547 2.62945 + vertex 0.894229 1.63245 2.62747 + endloop + endfacet + facet normal -0.573138 0.0559976 0.817543 + outer loop + vertex 0.894229 1.63245 2.62747 + vertex 0.897344 1.63547 2.62945 + vertex 0.894367 1.6375 2.62722 + endloop + endfacet + facet normal -0.569699 0.0631263 0.819426 + outer loop + vertex 0.897344 1.63547 2.62945 + vertex 0.897428 1.6406 2.62911 + vertex 0.894367 1.6375 2.62722 + endloop + endfacet + facet normal -0.446977 0.0569942 0.892728 + outer loop + vertex 0.89586 1.75891 2.61585 + vertex 0.899337 1.7623 2.61738 + vertex 0.896154 1.76395 2.61568 + endloop + endfacet + facet normal -0.448846 0.0594021 0.891633 + outer loop + vertex 0.899013 1.75715 2.61756 + vertex 0.899337 1.7623 2.61738 + vertex 0.89586 1.75891 2.61585 + endloop + endfacet + facet normal -0.427333 0.0542633 0.902464 + outer loop + vertex 0.892943 1.76567 2.61405 + vertex 0.892602 1.76053 2.6142 + vertex 0.896154 1.76395 2.61568 + endloop + endfacet + facet normal -0.423191 0.0632812 0.903828 + outer loop + vertex 0.896518 1.76887 2.6155 + vertex 0.892943 1.76567 2.61405 + vertex 0.896154 1.76395 2.61568 + endloop + endfacet + facet normal -0.438443 0.0641491 0.896467 + outer loop + vertex 0.896154 1.76395 2.61568 + vertex 0.899582 1.76731 2.61711 + vertex 0.896518 1.76887 2.6155 + endloop + endfacet + facet normal -0.441897 0.0685438 0.894443 + outer loop + vertex 0.899337 1.7623 2.61738 + vertex 0.899582 1.76731 2.61711 + vertex 0.896154 1.76395 2.61568 + endloop + endfacet + facet normal -0.623428 0.279004 0.730406 + outer loop + vertex 0.895935 1.89371 2.59025 + vertex 0.893775 1.89282 2.58875 + vertex 0.894159 1.89058 2.58993 + endloop + endfacet + facet normal -0.570411 0.243416 0.784462 + outer loop + vertex 0.894159 1.89058 2.58993 + vertex 0.898153 1.89128 2.59262 + vertex 0.895935 1.89371 2.59025 + endloop + endfacet + facet normal -0.569037 0.283324 0.771961 + outer loop + vertex 0.894159 1.89058 2.58993 + vertex 0.894548 1.88667 2.59165 + vertex 0.898153 1.89128 2.59262 + endloop + endfacet + facet normal -0.626545 0.318324 0.711415 + outer loop + vertex 0.89396 1.89528 2.58781 + vertex 0.893775 1.89282 2.58875 + vertex 0.895935 1.89371 2.59025 + endloop + endfacet + facet normal -0.642206 0.293498 0.708118 + outer loop + vertex 0.896461 1.89749 2.58916 + vertex 0.89396 1.89528 2.58781 + vertex 0.895935 1.89371 2.59025 + endloop + endfacet + facet normal -0.575899 0.299406 0.760721 + outer loop + vertex 0.895935 1.89371 2.59025 + vertex 0.899278 1.89645 2.5917 + vertex 0.896461 1.89749 2.58916 + endloop + endfacet + facet normal -0.5564 0.260624 0.788983 + outer loop + vertex 0.898153 1.89128 2.59262 + vertex 0.899278 1.89645 2.5917 + vertex 0.895935 1.89371 2.59025 + endloop + endfacet + facet normal -0.695622 0.33726 0.634324 + outer loop + vertex 0.896288 1.902 2.58696 + vertex 0.893494 1.90108 2.58439 + vertex 0.894434 1.89852 2.58678 + endloop + endfacet + facet normal -0.651177 0.314354 0.69076 + outer loop + vertex 0.894434 1.89852 2.58678 + vertex 0.89396 1.89528 2.58781 + vertex 0.896461 1.89749 2.58916 + endloop + endfacet + facet normal -0.65266 0.31136 0.690716 + outer loop + vertex 0.896288 1.902 2.58696 + vertex 0.894434 1.89852 2.58678 + vertex 0.896461 1.89749 2.58916 + endloop + endfacet + facet normal -0.62238 0.323284 0.712832 + outer loop + vertex 0.896288 1.902 2.58696 + vertex 0.896461 1.89749 2.58916 + vertex 0.89907 1.90036 2.59014 + endloop + endfacet + facet normal -0.661862 0.246725 0.707859 + outer loop + vertex 0.896288 1.902 2.58696 + vertex 0.89907 1.90036 2.59014 + vertex 0.898641 1.90263 2.58895 + endloop + endfacet + facet normal -0.586512 0.274049 0.762169 + outer loop + vertex 0.89907 1.90036 2.59014 + vertex 0.896461 1.89749 2.58916 + vertex 0.899278 1.89645 2.5917 + endloop + endfacet + facet normal -0.696192 0.329841 0.63759 + outer loop + vertex 0.893856 1.90493 2.5828 + vertex 0.893494 1.90108 2.58439 + vertex 0.896288 1.902 2.58696 + endloop + endfacet + facet normal -0.722382 0.292417 0.626624 + outer loop + vertex 0.896154 1.90711 2.58443 + vertex 0.893856 1.90493 2.5828 + vertex 0.896288 1.902 2.58696 + endloop + endfacet + facet normal -0.678024 0.312754 0.665183 + outer loop + vertex 0.896288 1.902 2.58696 + vertex 0.898507 1.90526 2.58769 + vertex 0.896154 1.90711 2.58443 + endloop + endfacet + facet normal -0.660245 0.294939 0.690716 + outer loop + vertex 0.898641 1.90263 2.58895 + vertex 0.898507 1.90526 2.58769 + vertex 0.896288 1.902 2.58696 + endloop + endfacet + facet normal -0.761014 0.315959 0.566593 + outer loop + vertex 0.895956 1.9127 2.5814 + vertex 0.89354 1.91133 2.57892 + vertex 0.894304 1.90884 2.58134 + endloop + endfacet + facet normal -0.728585 0.311225 0.610167 + outer loop + vertex 0.894304 1.90884 2.58134 + vertex 0.893856 1.90493 2.5828 + vertex 0.896154 1.90711 2.58443 + endloop + endfacet + facet normal -0.733228 0.303367 0.608559 + outer loop + vertex 0.895956 1.9127 2.5814 + vertex 0.894304 1.90884 2.58134 + vertex 0.896154 1.90711 2.58443 + endloop + endfacet + facet normal -0.706249 0.317443 0.632805 + outer loop + vertex 0.895956 1.9127 2.5814 + vertex 0.896154 1.90711 2.58443 + vertex 0.898414 1.90949 2.58575 + endloop + endfacet + facet normal -0.746468 0.259404 0.612777 + outer loop + vertex 0.895956 1.9127 2.5814 + vertex 0.898414 1.90949 2.58575 + vertex 0.89836 1.91245 2.58443 + endloop + endfacet + facet normal -0.692304 0.288181 0.661564 + outer loop + vertex 0.898414 1.90949 2.58575 + vertex 0.896154 1.90711 2.58443 + vertex 0.898507 1.90526 2.58769 + endloop + endfacet + facet normal -0.786855 0.300288 0.539153 + outer loop + vertex 0.89458 1.91745 2.57698 + vertex 0.892699 1.91634 2.57485 + vertex 0.893665 1.91415 2.57748 + endloop + endfacet + facet normal -0.760982 0.321676 0.563411 + outer loop + vertex 0.893665 1.91415 2.57748 + vertex 0.89354 1.91133 2.57892 + vertex 0.895956 1.9127 2.5814 + endloop + endfacet + facet normal -0.771537 0.299405 0.561327 + outer loop + vertex 0.893665 1.91415 2.57748 + vertex 0.895956 1.9127 2.5814 + vertex 0.89458 1.91745 2.57698 + endloop + endfacet + facet normal -0.788006 0.281703 0.547439 + outer loop + vertex 0.89458 1.91745 2.57698 + vertex 0.895956 1.9127 2.5814 + vertex 0.896782 1.91819 2.57977 + endloop + endfacet + facet normal -0.749263 0.290139 0.595335 + outer loop + vertex 0.895956 1.9127 2.5814 + vertex 0.898537 1.91548 2.58329 + vertex 0.896782 1.91819 2.57977 + endloop + endfacet + facet normal -0.742837 0.273543 0.611037 + outer loop + vertex 0.89836 1.91245 2.58443 + vertex 0.898537 1.91548 2.58329 + vertex 0.895956 1.9127 2.5814 + endloop + endfacet + facet normal -0.786884 0.298365 0.540178 + outer loop + vertex 0.892929 1.92012 2.5731 + vertex 0.892699 1.91634 2.57485 + vertex 0.89458 1.91745 2.57698 + endloop + endfacet + facet normal -0.789413 0.294511 0.5386 + outer loop + vertex 0.895602 1.92289 2.5755 + vertex 0.892929 1.92012 2.5731 + vertex 0.89458 1.91745 2.57698 + endloop + endfacet + facet normal -0.768206 0.283599 0.573961 + outer loop + vertex 0.897766 1.92155 2.57942 + vertex 0.896782 1.91819 2.57977 + vertex 0.898701 1.91915 2.58186 + endloop + endfacet + facet normal -0.793813 0.287217 0.536066 + outer loop + vertex 0.897766 1.92155 2.57942 + vertex 0.895602 1.92289 2.5755 + vertex 0.896782 1.91819 2.57977 + endloop + endfacet + facet normal -0.786429 0.295051 0.542654 + outer loop + vertex 0.895602 1.92289 2.5755 + vertex 0.89458 1.91745 2.57698 + vertex 0.896782 1.91819 2.57977 + endloop + endfacet + facet normal -0.768341 0.262576 0.5837 + outer loop + vertex 0.898701 1.91915 2.58186 + vertex 0.896782 1.91819 2.57977 + vertex 0.898537 1.91548 2.58329 + endloop + endfacet + facet normal -0.786574 0.298775 0.540402 + outer loop + vertex 0.89464 1.92769 2.57141 + vertex 0.893019 1.92755 2.56913 + vertex 0.893038 1.92466 2.57076 + endloop + endfacet + facet normal -0.789773 0.296057 0.537224 + outer loop + vertex 0.893038 1.92466 2.57076 + vertex 0.892929 1.92012 2.5731 + vertex 0.895602 1.92289 2.5755 + endloop + endfacet + facet normal -0.787918 0.300069 0.537721 + outer loop + vertex 0.893038 1.92466 2.57076 + vertex 0.895602 1.92289 2.5755 + vertex 0.89464 1.92769 2.57141 + endloop + endfacet + facet normal -0.789543 0.298469 0.536225 + outer loop + vertex 0.89464 1.92769 2.57141 + vertex 0.895602 1.92289 2.5755 + vertex 0.896879 1.92812 2.57447 + endloop + endfacet + facet normal -0.789222 0.298482 0.536691 + outer loop + vertex 0.895602 1.92289 2.5755 + vertex 0.898274 1.92523 2.57813 + vertex 0.896879 1.92812 2.57447 + endloop + endfacet + facet normal -0.789143 0.2979 0.537131 + outer loop + vertex 0.897766 1.92155 2.57942 + vertex 0.898274 1.92523 2.57813 + vertex 0.895602 1.92289 2.5755 + endloop + endfacet + facet normal -0.78752 0.29457 0.541332 + outer loop + vertex 0.893389 1.93039 2.56812 + vertex 0.893019 1.92755 2.56913 + vertex 0.89464 1.92769 2.57141 + endloop + endfacet + facet normal -0.789278 0.2922 0.540055 + outer loop + vertex 0.895875 1.9327 2.5705 + vertex 0.893389 1.93039 2.56812 + vertex 0.89464 1.92769 2.57141 + endloop + endfacet + facet normal -0.791274 0.294596 0.535816 + outer loop + vertex 0.897987 1.93139 2.57431 + vertex 0.896879 1.92812 2.57447 + vertex 0.898793 1.92889 2.57687 + endloop + endfacet + facet normal -0.788919 0.293986 0.53961 + outer loop + vertex 0.897987 1.93139 2.57431 + vertex 0.895875 1.9327 2.5705 + vertex 0.896879 1.92812 2.57447 + endloop + endfacet + facet normal -0.79071 0.292175 0.53797 + outer loop + vertex 0.895875 1.9327 2.5705 + vertex 0.89464 1.92769 2.57141 + vertex 0.896879 1.92812 2.57447 + endloop + endfacet + facet normal -0.79115 0.295821 0.535323 + outer loop + vertex 0.898793 1.92889 2.57687 + vertex 0.896879 1.92812 2.57447 + vertex 0.898274 1.92523 2.57813 + endloop + endfacet + facet normal -0.804135 0.284688 0.521842 + outer loop + vertex 0.894844 1.9373 2.5666 + vertex 0.893111 1.93647 2.56438 + vertex 0.893812 1.93394 2.56685 + endloop + endfacet + facet normal -0.788719 0.288997 0.542589 + outer loop + vertex 0.893812 1.93394 2.56685 + vertex 0.893389 1.93039 2.56812 + vertex 0.895875 1.9327 2.5705 + endloop + endfacet + facet normal -0.791588 0.282291 0.541941 + outer loop + vertex 0.893812 1.93394 2.56685 + vertex 0.895875 1.9327 2.5705 + vertex 0.894844 1.9373 2.5666 + endloop + endfacet + facet normal -0.786565 0.28735 0.546577 + outer loop + vertex 0.894844 1.9373 2.5666 + vertex 0.895875 1.9327 2.5705 + vertex 0.897004 1.93799 2.56935 + endloop + endfacet + facet normal -0.790035 0.287028 0.541719 + outer loop + vertex 0.895875 1.9327 2.5705 + vertex 0.89844 1.9351 2.57298 + vertex 0.897004 1.93799 2.56935 + endloop + endfacet + facet normal -0.790585 0.290195 0.539225 + outer loop + vertex 0.897987 1.93139 2.57431 + vertex 0.89844 1.9351 2.57298 + vertex 0.895875 1.9327 2.5705 + endloop + endfacet + facet normal -0.804419 0.280767 0.523526 + outer loop + vertex 0.893597 1.94022 2.56312 + vertex 0.893111 1.93647 2.56438 + vertex 0.894844 1.9373 2.5666 + endloop + endfacet + facet normal -0.806286 0.278186 0.522029 + outer loop + vertex 0.895971 1.94268 2.56548 + vertex 0.893597 1.94022 2.56312 + vertex 0.894844 1.9373 2.5666 + endloop + endfacet + facet normal -0.78801 0.286167 0.545114 + outer loop + vertex 0.898064 1.9414 2.56909 + vertex 0.897004 1.93799 2.56935 + vertex 0.898893 1.93885 2.57163 + endloop + endfacet + facet normal -0.78224 0.285031 0.553948 + outer loop + vertex 0.898064 1.9414 2.56909 + vertex 0.895971 1.94268 2.56548 + vertex 0.897004 1.93799 2.56935 + endloop + endfacet + facet normal -0.787448 0.279921 0.549154 + outer loop + vertex 0.895971 1.94268 2.56548 + vertex 0.894844 1.9373 2.5666 + vertex 0.897004 1.93799 2.56935 + endloop + endfacet + facet normal -0.787733 0.29023 0.543363 + outer loop + vertex 0.898893 1.93885 2.57163 + vertex 0.897004 1.93799 2.56935 + vertex 0.89844 1.9351 2.57298 + endloop + endfacet + facet normal -0.837937 0.293584 0.460077 + outer loop + vertex 0.89507 1.94719 2.56172 + vertex 0.89355 1.94621 2.55958 + vertex 0.894029 1.94391 2.56192 + endloop + endfacet + facet normal -0.804071 0.26744 0.530986 + outer loop + vertex 0.894029 1.94391 2.56192 + vertex 0.893597 1.94022 2.56312 + vertex 0.895971 1.94268 2.56548 + endloop + endfacet + facet normal -0.796741 0.284826 0.53299 + outer loop + vertex 0.894029 1.94391 2.56192 + vertex 0.895971 1.94268 2.56548 + vertex 0.89507 1.94719 2.56172 + endloop + endfacet + facet normal -0.795253 0.28631 0.534415 + outer loop + vertex 0.89507 1.94719 2.56172 + vertex 0.895971 1.94268 2.56548 + vertex 0.897137 1.94802 2.56435 + endloop + endfacet + facet normal -0.783741 0.287226 0.550682 + outer loop + vertex 0.895971 1.94268 2.56548 + vertex 0.898535 1.94516 2.56783 + vertex 0.897137 1.94802 2.56435 + endloop + endfacet + facet normal -0.782928 0.28345 0.553787 + outer loop + vertex 0.898064 1.9414 2.56909 + vertex 0.898535 1.94516 2.56783 + vertex 0.895971 1.94268 2.56548 + endloop + endfacet + facet normal -0.835647 0.320251 0.446244 + outer loop + vertex 0.894165 1.94951 2.55836 + vertex 0.89355 1.94621 2.55958 + vertex 0.89507 1.94719 2.56172 + endloop + endfacet + facet normal -0.837513 0.317402 0.444779 + outer loop + vertex 0.896341 1.95241 2.56039 + vertex 0.894165 1.94951 2.55836 + vertex 0.89507 1.94719 2.56172 + endloop + endfacet + facet normal -0.785227 0.290089 0.547053 + outer loop + vertex 0.898217 1.95137 2.56412 + vertex 0.897137 1.94802 2.56435 + vertex 0.899009 1.9489 2.56657 + endloop + endfacet + facet normal -0.817771 0.296919 0.493041 + outer loop + vertex 0.898217 1.95137 2.56412 + vertex 0.896341 1.95241 2.56039 + vertex 0.897137 1.94802 2.56435 + endloop + endfacet + facet normal -0.790809 0.324946 0.518683 + outer loop + vertex 0.896341 1.95241 2.56039 + vertex 0.89507 1.94719 2.56172 + vertex 0.897137 1.94802 2.56435 + endloop + endfacet + facet normal -0.785521 0.284799 0.549406 + outer loop + vertex 0.899009 1.9489 2.56657 + vertex 0.897137 1.94802 2.56435 + vertex 0.898535 1.94516 2.56783 + endloop + endfacet + facet normal -0.627516 0.397744 0.669345 + outer loop + vertex 0.895491 1.95902 2.55069 + vertex 0.895374 1.96 2.55 + vertex 0.895 1.95941 2.55 + endloop + endfacet + facet normal -0.549511 0.498313 0.670613 + outer loop + vertex 0.894419 1.95481 2.55294 + vertex 0.895491 1.95902 2.55069 + vertex 0.895 1.95941 2.55 + endloop + endfacet + facet normal -0.903017 0.357245 0.238615 + outer loop + vertex 0.895925 1.95715 2.55514 + vertex 0.895491 1.95902 2.55069 + vertex 0.894419 1.95481 2.55294 + endloop + endfacet + facet normal -0.904248 0.341876 0.255846 + outer loop + vertex 0.894714 1.9529 2.55654 + vertex 0.895925 1.95715 2.55514 + vertex 0.894419 1.95481 2.55294 + endloop + endfacet + facet normal -0.844962 0.35293 0.401845 + outer loop + vertex 0.894714 1.9529 2.55654 + vertex 0.894165 1.94951 2.55836 + vertex 0.896341 1.95241 2.56039 + endloop + endfacet + facet normal -0.837687 0.370762 0.401018 + outer loop + vertex 0.894714 1.9529 2.55654 + vertex 0.896341 1.95241 2.56039 + vertex 0.895925 1.95715 2.55514 + endloop + endfacet + facet normal -0.895656 0.292531 0.335002 + outer loop + vertex 0.895925 1.95715 2.55514 + vertex 0.896341 1.95241 2.56039 + vertex 0.897679 1.95786 2.5592 + endloop + endfacet + facet normal -0.824269 0.305788 0.476523 + outer loop + vertex 0.896341 1.95241 2.56039 + vertex 0.89873 1.95498 2.56287 + vertex 0.897679 1.95786 2.5592 + endloop + endfacet + facet normal -0.821417 0.287865 0.492349 + outer loop + vertex 0.898217 1.95137 2.56412 + vertex 0.89873 1.95498 2.56287 + vertex 0.896341 1.95241 2.56039 + endloop + endfacet + facet normal -0.716346 0.343417 0.607382 + outer loop + vertex 0.895374 1.96 2.55 + vertex 0.895491 1.95902 2.55069 + vertex 0.897771 1.965 2.55 + endloop + endfacet + facet normal -0.929379 0.337013 -0.150587 + outer loop + vertex 0.897771 1.965 2.55 + vertex 0.895491 1.95902 2.55069 + vertex 0.896642 1.96233 2.55099 + endloop + endfacet + facet normal -0.927536 0.303338 0.218319 + outer loop + vertex 0.895491 1.95902 2.55069 + vertex 0.895925 1.95715 2.55514 + vertex 0.896642 1.96233 2.55099 + endloop + endfacet + facet normal -0.932356 0.295725 0.207988 + outer loop + vertex 0.896642 1.96233 2.55099 + vertex 0.895925 1.95715 2.55514 + vertex 0.897582 1.96222 2.55535 + endloop + endfacet + facet normal -0.839546 0.284711 0.462712 + outer loop + vertex 0.898787 1.96128 2.55911 + vertex 0.897679 1.95786 2.5592 + vertex 0.89935 1.95884 2.56163 + endloop + endfacet + facet normal -0.885239 0.296741 0.358185 + outer loop + vertex 0.898787 1.96128 2.55911 + vertex 0.897582 1.96222 2.55535 + vertex 0.897679 1.95786 2.5592 + endloop + endfacet + facet normal -0.898561 0.279163 0.33861 + outer loop + vertex 0.897582 1.96222 2.55535 + vertex 0.895925 1.95715 2.55514 + vertex 0.897679 1.95786 2.5592 + endloop + endfacet + facet normal -0.839658 0.283376 0.463327 + outer loop + vertex 0.89935 1.95884 2.56163 + vertex 0.897679 1.95786 2.5592 + vertex 0.89873 1.95498 2.56287 + endloop + endfacet + facet normal -0.991725 0.111472 0.0636764 + outer loop + vertex 0.89745 1.965 2.545 + vertex 0.897771 1.965 2.55 + vertex 0.898012 1.97 2.545 + endloop + endfacet + facet normal 0.580084 -0.589781 -0.561837 + outer loop + vertex 0.898012 1.97 2.545 + vertex 0.897771 1.965 2.55 + vertex 0.897414 1.96742 2.54709 + endloop + endfacet + facet normal 0.720713 -0.486858 -0.493499 + outer loop + vertex 0.897771 1.965 2.55 + vertex 0.896642 1.96233 2.55099 + vertex 0.897414 1.96742 2.54709 + endloop + endfacet + facet normal -0.959856 0.247113 0.132706 + outer loop + vertex 0.897414 1.96742 2.54709 + vertex 0.896642 1.96233 2.55099 + vertex 0.897748 1.96677 2.55071 + endloop + endfacet + facet normal -0.895342 0.276706 0.348992 + outer loop + vertex 0.898454 1.96613 2.55449 + vertex 0.897582 1.96222 2.55535 + vertex 0.898995 1.96421 2.5574 + endloop + endfacet + facet normal -0.940823 0.258172 0.219541 + outer loop + vertex 0.898454 1.96613 2.55449 + vertex 0.897748 1.96677 2.55071 + vertex 0.897582 1.96222 2.55535 + endloop + endfacet + facet normal -0.945697 0.248339 0.209724 + outer loop + vertex 0.897748 1.96677 2.55071 + vertex 0.896642 1.96233 2.55099 + vertex 0.897582 1.96222 2.55535 + endloop + endfacet + facet normal -0.894971 0.270535 0.354735 + outer loop + vertex 0.898995 1.96421 2.5574 + vertex 0.897582 1.96222 2.55535 + vertex 0.898787 1.96128 2.55911 + endloop + endfacet + facet normal -0.982364 0.0988266 -0.158727 + outer loop + vertex 0.898012 1.97 2.545 + vertex 0.897414 1.96742 2.54709 + vertex 0.898515 1.975 2.545 + endloop + endfacet + facet normal -0.831579 0.256725 0.492513 + outer loop + vertex 0.898515 1.975 2.545 + vertex 0.897414 1.96742 2.54709 + vertex 0.898341 1.9712 2.54669 + endloop + endfacet + facet normal -0.937184 0.284589 0.201729 + outer loop + vertex 0.898639 1.97057 2.54949 + vertex 0.897748 1.96677 2.55071 + vertex 0.898774 1.96893 2.55243 + endloop + endfacet + facet normal -0.947925 0.274275 0.161901 + outer loop + vertex 0.898639 1.97057 2.54949 + vertex 0.898341 1.9712 2.54669 + vertex 0.897748 1.96677 2.55071 + endloop + endfacet + facet normal -0.959172 0.249557 0.133079 + outer loop + vertex 0.898341 1.9712 2.54669 + vertex 0.897414 1.96742 2.54709 + vertex 0.897748 1.96677 2.55071 + endloop + endfacet + facet normal -0.937348 0.269486 0.220806 + outer loop + vertex 0.898774 1.96893 2.55243 + vertex 0.897748 1.96677 2.55071 + vertex 0.898454 1.96613 2.55449 + endloop + endfacet + facet normal -0.639382 0.423884 -0.641493 + outer loop + vertex 0.9 1.975 2.54352 + vertex 0.898515 1.975 2.545 + vertex 0.9 1.97724 2.545 + endloop + endfacet + facet normal -0.910972 0.322068 0.257688 + outer loop + vertex 0.9 1.97724 2.545 + vertex 0.898341 1.9712 2.54669 + vertex 0.899347 1.97359 2.54726 + endloop + endfacet + facet normal -0.544565 0.361024 0.757041 + outer loop + vertex 0.898515 1.975 2.545 + vertex 0.898341 1.9712 2.54669 + vertex 0.9 1.97724 2.545 + endloop + endfacet + facet normal -0.921707 0.346115 0.175104 + outer loop + vertex 0.899347 1.97359 2.54726 + vertex 0.898341 1.9712 2.54669 + vertex 0.898639 1.97057 2.54949 + endloop + endfacet + facet normal -0.00952209 -0.681544 -0.731715 + outer loop + vertex 0.9 2.1077 2.49 + vertex 0.899033 2.10533 2.49222 + vertex 0.895 2.10777 2.49 + endloop + endfacet + facet normal 0.0478619 -0.627744 -0.776947 + outer loop + vertex 0.899033 2.10533 2.49222 + vertex 0.893698 2.10511 2.49207 + vertex 0.895 2.10777 2.49 + endloop + endfacet + facet normal 0.043748 -0.993869 -0.101543 + outer loop + vertex 0.899033 2.10533 2.49222 + vertex 0.898259 2.10487 2.4964 + vertex 0.893698 2.10511 2.49207 + endloop + endfacet + facet normal -0.315943 -0.905994 0.281699 + outer loop + vertex 0.898259 2.10487 2.4964 + vertex 0.893368 2.10637 2.49574 + vertex 0.893698 2.10511 2.49207 + endloop + endfacet + facet normal -0.680923 -0.408627 0.607756 + outer loop + vertex 0.895225 2.10852 2.49846 + vertex 0.898317 2.10618 2.50035 + vertex 0.897741 2.10818 2.50105 + endloop + endfacet + facet normal -0.654866 -0.307733 0.690254 + outer loop + vertex 0.895225 2.10852 2.49846 + vertex 0.893368 2.10637 2.49574 + vertex 0.898317 2.10618 2.50035 + endloop + endfacet + facet normal -0.31662 -0.898932 0.302774 + outer loop + vertex 0.893368 2.10637 2.49574 + vertex 0.898259 2.10487 2.4964 + vertex 0.898317 2.10618 2.50035 + endloop + endfacet + facet normal -0.719534 -0.404616 0.564408 + outer loop + vertex 0.898317 2.10618 2.50035 + vertex 0.89972 2.10725 2.50291 + vertex 0.897741 2.10818 2.50105 + endloop + endfacet + facet normal -0.713689 0.265198 0.648319 + outer loop + vertex 0.897741 2.10818 2.50105 + vertex 0.899346 2.10903 2.50247 + vertex 0.897714 2.11099 2.49987 + endloop + endfacet + facet normal -0.668327 0.282388 0.688183 + outer loop + vertex 0.897741 2.10818 2.50105 + vertex 0.897714 2.11099 2.49987 + vertex 0.895225 2.10852 2.49846 + endloop + endfacet + facet normal -0.64268 0.232585 0.729977 + outer loop + vertex 0.895225 2.10852 2.49846 + vertex 0.897714 2.11099 2.49987 + vertex 0.894302 2.11155 2.49669 + endloop + endfacet + facet normal -0.673809 0.0418791 0.737718 + outer loop + vertex 0.899346 2.10903 2.50247 + vertex 0.897741 2.10818 2.50105 + vertex 0.89972 2.10725 2.50291 + endloop + endfacet + facet normal -0.483617 0.629697 0.607944 + outer loop + vertex 0.895623 2.11578 2.49422 + vertex 0.894022 2.11577 2.49296 + vertex 0.893935 2.11425 2.49447 + endloop + endfacet + facet normal -0.475224 0.622626 0.62169 + outer loop + vertex 0.893935 2.11425 2.49447 + vertex 0.896766 2.1141 2.49678 + vertex 0.895623 2.11578 2.49422 + endloop + endfacet + facet normal -0.534831 0.492275 0.686747 + outer loop + vertex 0.893935 2.11425 2.49447 + vertex 0.894302 2.11155 2.49669 + vertex 0.896766 2.1141 2.49678 + endloop + endfacet + facet normal -0.544329 0.501935 0.672137 + outer loop + vertex 0.894302 2.11155 2.49669 + vertex 0.897714 2.11099 2.49987 + vertex 0.896766 2.1141 2.49678 + endloop + endfacet + facet normal 0.217234 -0.340693 0.914734 + outer loop + vertex 0.898383 2.12259 2.48424 + vertex 0.898968 2.125 2.485 + vertex 0.895 2.12247 2.485 + endloop + endfacet + facet normal 0.0811648 0.860369 0.503167 + outer loop + vertex 0.898383 2.12259 2.48424 + vertex 0.895 2.12247 2.485 + vertex 0.899003 2.12088 2.48708 + endloop + endfacet + facet normal -0.24048 0.489435 0.838226 + outer loop + vertex 0.899003 2.12088 2.48708 + vertex 0.895 2.12247 2.485 + vertex 0.894504 2.11915 2.48679 + endloop + endfacet + facet normal -0.350582 0.850053 0.393067 + outer loop + vertex 0.899003 2.12088 2.48708 + vertex 0.894504 2.11915 2.48679 + vertex 0.898902 2.11879 2.49149 + endloop + endfacet + facet normal -0.371651 0.832225 0.411432 + outer loop + vertex 0.898902 2.11879 2.49149 + vertex 0.894504 2.11915 2.48679 + vertex 0.894734 2.11705 2.49125 + endloop + endfacet + facet normal -0.365851 0.810853 0.456805 + outer loop + vertex 0.895623 2.11578 2.49422 + vertex 0.894734 2.11705 2.49125 + vertex 0.894022 2.11577 2.49296 + endloop + endfacet + facet normal -0.384716 0.801213 0.458314 + outer loop + vertex 0.895623 2.11578 2.49422 + vertex 0.898387 2.11659 2.49512 + vertex 0.894734 2.11705 2.49125 + endloop + endfacet + facet normal -0.367319 0.817383 0.443804 + outer loop + vertex 0.898387 2.11659 2.49512 + vertex 0.898902 2.11879 2.49149 + vertex 0.894734 2.11705 2.49125 + endloop + endfacet + facet normal -0.399909 0.673713 0.621437 + outer loop + vertex 0.898387 2.11659 2.49512 + vertex 0.895623 2.11578 2.49422 + vertex 0.896766 2.1141 2.49678 + endloop + endfacet + facet normal -0.474058 0.699782 0.534391 + outer loop + vertex 0.898968 2.125 2.485 + vertex 0.895 2.12613 2.48 + vertex 0.895 2.125 2.48148 + endloop + endfacet + facet normal -0.500113 0.670198 0.548382 + outer loop + vertex 0.898968 2.125 2.485 + vertex 0.9 2.12577 2.485 + vertex 0.895 2.12613 2.48 + endloop + endfacet + facet normal -0.0337898 0.993861 0.105353 + outer loop + vertex 0.9 2.12577 2.485 + vertex 0.9 2.1263 2.48 + vertex 0.895 2.12613 2.48 + endloop + endfacet + facet normal 0.258675 -0.346649 0.901622 + outer loop + vertex 0.9 2.12577 2.485 + vertex 0.898968 2.125 2.485 + vertex 0.898383 2.12259 2.48424 + endloop + endfacet + facet normal -0.134819 -0.979764 0.147943 + outer loop + vertex 0.905 0.902394 2.485 + vertex 0.905 0.903149 2.49 + vertex 0.9 0.903082 2.485 + endloop + endfacet + facet normal 0.0202578 -0.999771 -0.00686154 + outer loop + vertex 0.905 0.903149 2.49 + vertex 0.899054 0.903055 2.48612 + vertex 0.9 0.903082 2.485 + endloop + endfacet + facet normal -0.231798 -0.941362 0.245166 + outer loop + vertex 0.899734 0.903546 2.48926 + vertex 0.904068 0.902999 2.49126 + vertex 0.901668 0.903839 2.49221 + endloop + endfacet + facet normal -0.211012 -0.957715 0.195593 + outer loop + vertex 0.899734 0.903546 2.48926 + vertex 0.899054 0.903055 2.48612 + vertex 0.904068 0.902999 2.49126 + endloop + endfacet + facet normal 0.0628026 -0.99541 -0.0722141 + outer loop + vertex 0.899054 0.903055 2.48612 + vertex 0.905 0.903149 2.49 + vertex 0.904068 0.902999 2.49126 + endloop + endfacet + facet normal -0.247265 -0.94586 0.210258 + outer loop + vertex 0.904068 0.902999 2.49126 + vertex 0.904675 0.903546 2.49443 + vertex 0.901668 0.903839 2.49221 + endloop + endfacet + facet normal -0.370622 -0.868612 0.328866 + outer loop + vertex 0.899734 0.903546 2.48926 + vertex 0.901668 0.903839 2.49221 + vertex 0.897732 0.90496 2.49074 + endloop + endfacet + facet normal -0.363416 -0.850414 0.380427 + outer loop + vertex 0.901668 0.903839 2.49221 + vertex 0.904675 0.903546 2.49443 + vertex 0.902469 0.905061 2.49571 + endloop + endfacet + facet normal -0.382623 -0.841382 0.381675 + outer loop + vertex 0.901668 0.903839 2.49221 + vertex 0.902469 0.905061 2.49571 + vertex 0.897732 0.90496 2.49074 + endloop + endfacet + facet normal -0.458933 -0.764393 0.452862 + outer loop + vertex 0.897732 0.90496 2.49074 + vertex 0.902469 0.905061 2.49571 + vertex 0.897546 0.907466 2.49478 + endloop + endfacet + facet normal -0.523395 -0.671564 0.52446 + outer loop + vertex 0.897936 0.909905 2.49816 + vertex 0.901691 0.907582 2.49893 + vertex 0.900705 0.909498 2.5004 + endloop + endfacet + facet normal -0.520733 -0.66269 0.538219 + outer loop + vertex 0.897936 0.909905 2.49816 + vertex 0.897546 0.907466 2.49478 + vertex 0.901691 0.907582 2.49893 + endloop + endfacet + facet normal -0.456867 -0.750871 0.476932 + outer loop + vertex 0.897546 0.907466 2.49478 + vertex 0.902469 0.905061 2.49571 + vertex 0.901691 0.907582 2.49893 + endloop + endfacet + facet normal -0.445253 -0.677823 0.585069 + outer loop + vertex 0.901691 0.907582 2.49893 + vertex 0.903699 0.909508 2.50269 + vertex 0.900705 0.909498 2.5004 + endloop + endfacet + facet normal -0.583631 -0.515739 0.627206 + outer loop + vertex 0.897936 0.909905 2.49816 + vertex 0.900705 0.909498 2.5004 + vertex 0.899274 0.911728 2.5009 + endloop + endfacet + facet normal -0.557448 -0.0800067 0.826348 + outer loop + vertex 0.903711 0.912122 2.50472 + vertex 0.902584 0.914565 2.5042 + vertex 0.900746 0.913364 2.50284 + endloop + endfacet + facet normal -0.604005 -0.487253 0.630684 + outer loop + vertex 0.903699 0.909508 2.50269 + vertex 0.903711 0.912122 2.50472 + vertex 0.900746 0.913364 2.50284 + endloop + endfacet + facet normal -0.513801 -0.422705 0.746545 + outer loop + vertex 0.903699 0.909508 2.50269 + vertex 0.900746 0.913364 2.50284 + vertex 0.899274 0.911728 2.5009 + endloop + endfacet + facet normal -0.527243 -0.493988 0.691369 + outer loop + vertex 0.903699 0.909508 2.50269 + vertex 0.899274 0.911728 2.5009 + vertex 0.900705 0.909498 2.5004 + endloop + endfacet + facet normal -0.624521 -0.122764 0.771299 + outer loop + vertex 0.903711 0.912122 2.50472 + vertex 0.905281 0.912818 2.50611 + vertex 0.902584 0.914565 2.5042 + endloop + endfacet + facet normal 0.350055 0.927033 -0.134429 + outer loop + vertex 0.905 0.917775 2.49 + vertex 0.9 0.919663 2.49 + vertex 0.905 0.9185 2.495 + endloop + endfacet + facet normal -0.241008 0.864035 0.441994 + outer loop + vertex 0.905 0.9185 2.495 + vertex 0.9 0.919663 2.49 + vertex 0.900336 0.918737 2.49199 + endloop + endfacet + facet normal 0.152076 0.983202 0.100926 + outer loop + vertex 0.899664 0.918873 2.49465 + vertex 0.900028 0.918457 2.49816 + vertex 0.90372 0.917992 2.49712 + endloop + endfacet + facet normal 0.210503 0.977588 0.00311213 + outer loop + vertex 0.899664 0.918873 2.49465 + vertex 0.90372 0.917992 2.49712 + vertex 0.900336 0.918737 2.49199 + endloop + endfacet + facet normal -0.0728934 0.979016 0.190303 + outer loop + vertex 0.900336 0.918737 2.49199 + vertex 0.90372 0.917992 2.49712 + vertex 0.905 0.9185 2.495 + endloop + endfacet + facet normal 0.191133 0.947514 0.256291 + outer loop + vertex 0.903256 0.916725 2.50215 + vertex 0.90372 0.917992 2.49712 + vertex 0.900028 0.918457 2.49816 + endloop + endfacet + facet normal 0.192046 0.947527 0.255559 + outer loop + vertex 0.899818 0.91787 2.50049 + vertex 0.903256 0.916725 2.50215 + vertex 0.900028 0.918457 2.49816 + endloop + endfacet + facet normal -0.339367 0.700397 0.627913 + outer loop + vertex 0.902584 0.914565 2.5042 + vertex 0.905374 0.914525 2.50575 + vertex 0.903256 0.916725 2.50215 + endloop + endfacet + facet normal -0.140359 0.703567 0.696629 + outer loop + vertex 0.902584 0.914565 2.5042 + vertex 0.903256 0.916725 2.50215 + vertex 0.899364 0.916486 2.50161 + endloop + endfacet + facet normal -0.610826 0.0420495 0.790647 + outer loop + vertex 0.902584 0.914565 2.5042 + vertex 0.899364 0.916486 2.50161 + vertex 0.900746 0.913364 2.50284 + endloop + endfacet + facet normal -0.143953 0.650787 0.745489 + outer loop + vertex 0.899364 0.916486 2.50161 + vertex 0.903256 0.916725 2.50215 + vertex 0.899818 0.91787 2.50049 + endloop + endfacet + facet normal -0.47378 0.20339 0.856834 + outer loop + vertex 0.905374 0.914525 2.50575 + vertex 0.902584 0.914565 2.5042 + vertex 0.905281 0.912818 2.50611 + endloop + endfacet + facet normal 0.145396 0.98413 0.101729 + outer loop + vertex 0.899664 0.918873 2.49465 + vertex 0.896927 0.919229 2.49512 + vertex 0.900028 0.918457 2.49816 + endloop + endfacet + facet normal 0.0422329 0.968024 0.247277 + outer loop + vertex 0.900028 0.918457 2.49816 + vertex 0.897514 0.918403 2.4988 + vertex 0.899818 0.91787 2.50049 + endloop + endfacet + facet normal 0.0335553 0.976267 0.213956 + outer loop + vertex 0.896927 0.919229 2.49512 + vertex 0.897514 0.918403 2.4988 + vertex 0.900028 0.918457 2.49816 + endloop + endfacet + facet normal -0.342059 0.656563 0.672251 + outer loop + vertex 0.899818 0.91787 2.50049 + vertex 0.897514 0.918403 2.4988 + vertex 0.899364 0.916486 2.50161 + endloop + endfacet + facet normal 0.0376331 -0.3717 -0.92759 + outer loop + vertex 0.905 1.0398 2.545 + vertex 0.90371 1.04112 2.54442 + vertex 0.905 1.04 2.54492 + endloop + endfacet + facet normal 0.355895 -0.0637312 -0.93235 + outer loop + vertex 0.905 1.0398 2.545 + vertex 0.904577 1.03833 2.54494 + vertex 0.90371 1.04112 2.54442 + endloop + endfacet + facet normal -0.660596 -0.140114 -0.737551 + outer loop + vertex 0.905 1.04 2.54492 + vertex 0.90385 1.045 2.545 + vertex 0.905 1.045 2.54397 + endloop + endfacet + facet normal 0.447613 0.11715 -0.88652 + outer loop + vertex 0.90371 1.04112 2.54442 + vertex 0.90385 1.045 2.545 + vertex 0.905 1.04 2.54492 + endloop + endfacet + facet normal -0.939801 -0.315836 -0.130463 + outer loop + vertex 0.903643 1.04064 2.54609 + vertex 0.90371 1.04112 2.54442 + vertex 0.904577 1.03833 2.54494 + endloop + endfacet + facet normal -0.964554 -0.240179 -0.109315 + outer loop + vertex 0.903643 1.04064 2.54609 + vertex 0.902412 1.04542 2.54643 + vertex 0.90371 1.04112 2.54442 + endloop + endfacet + facet normal -0.679581 0.132913 -0.72146 + outer loop + vertex 0.902412 1.04542 2.54643 + vertex 0.90385 1.045 2.545 + vertex 0.90371 1.04112 2.54442 + endloop + endfacet + facet normal -0.957415 -0.255899 0.133686 + outer loop + vertex 0.903643 1.04064 2.54609 + vertex 0.903614 1.04208 2.54864 + vertex 0.902412 1.04542 2.54643 + endloop + endfacet + facet normal -0.7086 -0.363228 -0.604939 + outer loop + vertex 0.90385 1.045 2.545 + vertex 0.902412 1.04542 2.54643 + vertex 0.901287 1.05 2.545 + endloop + endfacet + facet normal -0.965797 -0.253845 -0.0529007 + outer loop + vertex 0.901287 1.05 2.545 + vertex 0.902412 1.04542 2.54643 + vertex 0.900984 1.05084 2.54651 + endloop + endfacet + facet normal -0.957477 -0.254647 0.135617 + outer loop + vertex 0.903021 1.0452 2.55031 + vertex 0.902412 1.04542 2.54643 + vertex 0.903614 1.04208 2.54864 + endloop + endfacet + facet normal -0.95774 -0.253602 0.135718 + outer loop + vertex 0.903021 1.0452 2.55031 + vertex 0.901761 1.05018 2.55073 + vertex 0.902412 1.04542 2.54643 + endloop + endfacet + facet normal -0.957412 -0.254363 0.136609 + outer loop + vertex 0.901761 1.05018 2.55073 + vertex 0.900984 1.05084 2.54651 + vertex 0.902412 1.04542 2.54643 + endloop + endfacet + facet normal -0.937008 -0.256889 0.236696 + outer loop + vertex 0.903021 1.0452 2.55031 + vertex 0.903391 1.04662 2.55332 + vertex 0.901761 1.05018 2.55073 + endloop + endfacet + facet normal -0.977178 -0.192894 -0.0889644 + outer loop + vertex 0.901287 1.05 2.545 + vertex 0.900984 1.05084 2.54651 + vertex 0.9003 1.055 2.545 + endloop + endfacet + facet normal -0.984409 -0.112919 0.134863 + outer loop + vertex 0.9003 1.055 2.545 + vertex 0.900984 1.05084 2.54651 + vertex 0.900985 1.055 2.55 + endloop + endfacet + facet normal -0.978178 -0.133396 0.159287 + outer loop + vertex 0.900984 1.05084 2.54651 + vertex 0.901761 1.05018 2.55073 + vertex 0.900985 1.055 2.55 + endloop + endfacet + facet normal -0.94824 -0.191153 -0.253579 + outer loop + vertex 0.900985 1.055 2.55 + vertex 0.901761 1.05018 2.55073 + vertex 0.900535 1.05546 2.55134 + endloop + endfacet + facet normal -0.936353 -0.248034 0.248438 + outer loop + vertex 0.903162 1.04948 2.55531 + vertex 0.901761 1.05018 2.55073 + vertex 0.903391 1.04662 2.55332 + endloop + endfacet + facet normal -0.926612 -0.290275 0.23902 + outer loop + vertex 0.903162 1.04948 2.55531 + vertex 0.901823 1.05395 2.55555 + vertex 0.901761 1.05018 2.55073 + endloop + endfacet + facet normal -0.948367 -0.243775 0.202913 + outer loop + vertex 0.901823 1.05395 2.55555 + vertex 0.900535 1.05546 2.55134 + vertex 0.901761 1.05018 2.55073 + endloop + endfacet + facet normal -0.887824 -0.28516 0.361182 + outer loop + vertex 0.904485 1.05048 2.55936 + vertex 0.901823 1.05395 2.55555 + vertex 0.903162 1.04948 2.55531 + endloop + endfacet + facet normal -0.888229 -0.318102 0.331452 + outer loop + vertex 0.903113 1.05538 2.56038 + vertex 0.901823 1.05395 2.55555 + vertex 0.904485 1.05048 2.55936 + endloop + endfacet + facet normal -0.840117 -0.326036 0.433479 + outer loop + vertex 0.904485 1.05048 2.55936 + vertex 0.905522 1.05304 2.56329 + vertex 0.903113 1.05538 2.56038 + endloop + endfacet + facet normal -0.95268 -0.119849 -0.279351 + outer loop + vertex 0.900985 1.055 2.55 + vertex 0.900535 1.05546 2.55134 + vertex 0.900356 1.06 2.55 + endloop + endfacet + facet normal -0.979297 -0.0917582 -0.18044 + outer loop + vertex 0.900356 1.06 2.55 + vertex 0.900535 1.05546 2.55134 + vertex 0.899762 1.05905 2.55371 + endloop + endfacet + facet normal -0.933286 -0.314762 0.172922 + outer loop + vertex 0.900535 1.05546 2.55134 + vertex 0.901823 1.05395 2.55555 + vertex 0.899762 1.05905 2.55371 + endloop + endfacet + facet normal -0.927813 -0.29044 0.234112 + outer loop + vertex 0.899762 1.05905 2.55371 + vertex 0.901823 1.05395 2.55555 + vertex 0.901137 1.0581 2.55798 + endloop + endfacet + facet normal -0.877846 -0.341637 0.335664 + outer loop + vertex 0.901823 1.05395 2.55555 + vertex 0.903113 1.05538 2.56038 + vertex 0.901137 1.0581 2.55798 + endloop + endfacet + facet normal -0.876448 -0.316886 0.362521 + outer loop + vertex 0.901137 1.0581 2.55798 + vertex 0.903113 1.05538 2.56038 + vertex 0.901943 1.06008 2.56166 + endloop + endfacet + facet normal -0.839905 -0.326951 0.433201 + outer loop + vertex 0.903113 1.05538 2.56038 + vertex 0.904254 1.05731 2.56405 + vertex 0.901943 1.06008 2.56166 + endloop + endfacet + facet normal -0.840127 -0.326561 0.433065 + outer loop + vertex 0.905522 1.05304 2.56329 + vertex 0.904254 1.05731 2.56405 + vertex 0.903113 1.05538 2.56038 + endloop + endfacet + facet normal -0.726214 -0.628961 -0.277527 + outer loop + vertex 0.900356 1.06 2.55 + vertex 0.899762 1.05905 2.55371 + vertex 0.898443 1.06188 2.55075 + endloop + endfacet + facet normal -0.590694 -0.304735 -0.747139 + outer loop + vertex 0.9 1.06069 2.55 + vertex 0.900356 1.06 2.55 + vertex 0.898443 1.06188 2.55075 + endloop + endfacet + facet normal -0.929316 -0.363186 0.0668381 + outer loop + vertex 0.898291 1.06287 2.554 + vertex 0.898443 1.06188 2.55075 + vertex 0.899762 1.05905 2.55371 + endloop + endfacet + facet normal -0.89406 -0.36444 0.260462 + outer loop + vertex 0.898291 1.06287 2.554 + vertex 0.899762 1.05905 2.55371 + vertex 0.899632 1.06263 2.55827 + endloop + endfacet + facet normal -0.920207 -0.320263 0.225057 + outer loop + vertex 0.899632 1.06263 2.55827 + vertex 0.899762 1.05905 2.55371 + vertex 0.901137 1.0581 2.55798 + endloop + endfacet + facet normal -0.877502 -0.314913 0.361692 + outer loop + vertex 0.901137 1.0581 2.55798 + vertex 0.901943 1.06008 2.56166 + vertex 0.899632 1.06263 2.55827 + endloop + endfacet + facet normal -0.876799 -0.329644 0.350083 + outer loop + vertex 0.899632 1.06263 2.55827 + vertex 0.901943 1.06008 2.56166 + vertex 0.900747 1.06317 2.56158 + endloop + endfacet + facet normal -0.839079 -0.321161 0.439092 + outer loop + vertex 0.903338 1.06079 2.56485 + vertex 0.901943 1.06008 2.56166 + vertex 0.904254 1.05731 2.56405 + endloop + endfacet + facet normal -0.840084 -0.318684 0.438975 + outer loop + vertex 0.903338 1.06079 2.56485 + vertex 0.901791 1.06403 2.56423 + vertex 0.901943 1.06008 2.56166 + endloop + endfacet + facet normal -0.844559 -0.314976 0.433024 + outer loop + vertex 0.901791 1.06403 2.56423 + vertex 0.900747 1.06317 2.56158 + vertex 0.901943 1.06008 2.56166 + endloop + endfacet + facet normal -0.823153 -0.302695 0.480411 + outer loop + vertex 0.903338 1.06079 2.56485 + vertex 0.903716 1.06332 2.56708 + vertex 0.901791 1.06403 2.56423 + endloop + endfacet + facet normal -0.898143 -0.352841 0.262378 + outer loop + vertex 0.898291 1.06287 2.554 + vertex 0.899632 1.06263 2.55827 + vertex 0.897826 1.06548 2.55592 + endloop + endfacet + facet normal -0.898247 -0.328057 0.292457 + outer loop + vertex 0.898309 1.06662 2.55869 + vertex 0.897826 1.06548 2.55592 + vertex 0.899632 1.06263 2.55827 + endloop + endfacet + facet normal -0.870551 -0.32665 0.368024 + outer loop + vertex 0.898309 1.06662 2.55869 + vertex 0.899632 1.06263 2.55827 + vertex 0.899791 1.06619 2.56181 + endloop + endfacet + facet normal -0.885174 -0.307366 0.349275 + outer loop + vertex 0.899791 1.06619 2.56181 + vertex 0.899632 1.06263 2.55827 + vertex 0.900747 1.06317 2.56158 + endloop + endfacet + facet normal -0.850018 -0.302574 0.431183 + outer loop + vertex 0.900747 1.06317 2.56158 + vertex 0.901791 1.06403 2.56423 + vertex 0.899791 1.06619 2.56181 + endloop + endfacet + facet normal -0.850447 -0.309319 0.425513 + outer loop + vertex 0.899791 1.06619 2.56181 + vertex 0.901791 1.06403 2.56423 + vertex 0.900826 1.06715 2.56457 + endloop + endfacet + facet normal -0.822711 -0.306518 0.478742 + outer loop + vertex 0.901791 1.06403 2.56423 + vertex 0.902382 1.06795 2.56776 + vertex 0.900826 1.06715 2.56457 + endloop + endfacet + facet normal -0.8225 -0.306745 0.478959 + outer loop + vertex 0.903716 1.06332 2.56708 + vertex 0.902382 1.06795 2.56776 + vertex 0.901791 1.06403 2.56423 + endloop + endfacet + facet normal -0.874704 -0.310374 0.372238 + outer loop + vertex 0.898309 1.06662 2.55869 + vertex 0.899791 1.06619 2.56181 + vertex 0.898099 1.06926 2.5604 + endloop + endfacet + facet normal -0.852738 -0.304217 0.424606 + outer loop + vertex 0.899791 1.06619 2.56181 + vertex 0.900826 1.06715 2.56457 + vertex 0.899443 1.07036 2.5641 + endloop + endfacet + facet normal -0.867638 -0.292917 0.401752 + outer loop + vertex 0.898099 1.06926 2.5604 + vertex 0.899791 1.06619 2.56181 + vertex 0.899443 1.07036 2.5641 + endloop + endfacet + facet normal -0.811838 -0.309041 0.495392 + outer loop + vertex 0.9024 1.07182 2.57027 + vertex 0.901399 1.07494 2.57057 + vertex 0.900509 1.07284 2.56781 + endloop + endfacet + facet normal -0.811283 -0.315248 0.492381 + outer loop + vertex 0.902382 1.06795 2.56776 + vertex 0.9024 1.07182 2.57027 + vertex 0.900509 1.07284 2.56781 + endloop + endfacet + facet normal -0.830513 -0.322269 0.454303 + outer loop + vertex 0.902382 1.06795 2.56776 + vertex 0.900509 1.07284 2.56781 + vertex 0.899443 1.07036 2.5641 + endloop + endfacet + facet normal -0.830458 -0.286852 0.477552 + outer loop + vertex 0.902382 1.06795 2.56776 + vertex 0.899443 1.07036 2.5641 + vertex 0.900826 1.06715 2.56457 + endloop + endfacet + facet normal -0.78803 -0.305289 0.53461 + outer loop + vertex 0.9024 1.07182 2.57027 + vertex 0.903265 1.07371 2.57262 + vertex 0.901399 1.07494 2.57057 + endloop + endfacet + facet normal -0.811165 -0.309994 0.495898 + outer loop + vertex 0.899581 1.07663 2.56866 + vertex 0.900509 1.07284 2.56781 + vertex 0.901399 1.07494 2.57057 + endloop + endfacet + facet normal -0.810354 -0.302225 0.501982 + outer loop + vertex 0.90065 1.07722 2.57073 + vertex 0.899581 1.07663 2.56866 + vertex 0.901399 1.07494 2.57057 + endloop + endfacet + facet normal -0.783144 -0.296397 0.546658 + outer loop + vertex 0.901399 1.07494 2.57057 + vertex 0.902223 1.0779 2.57336 + vertex 0.90065 1.07722 2.57073 + endloop + endfacet + facet normal -0.787745 -0.291406 0.542716 + outer loop + vertex 0.903265 1.07371 2.57262 + vertex 0.902223 1.0779 2.57336 + vertex 0.901399 1.07494 2.57057 + endloop + endfacet + facet normal -0.815706 -0.289101 0.501043 + outer loop + vertex 0.899581 1.07663 2.56866 + vertex 0.90065 1.07722 2.57073 + vertex 0.899677 1.07957 2.57051 + endloop + endfacet + facet normal -0.783127 -0.288915 0.550673 + outer loop + vertex 0.902323 1.08169 2.57549 + vertex 0.901321 1.08482 2.5757 + vertex 0.900432 1.08227 2.5731 + endloop + endfacet + facet normal -0.783224 -0.288144 0.550938 + outer loop + vertex 0.902223 1.0779 2.57336 + vertex 0.902323 1.08169 2.57549 + vertex 0.900432 1.08227 2.5731 + endloop + endfacet + facet normal -0.791925 -0.292584 0.535957 + outer loop + vertex 0.902223 1.0779 2.57336 + vertex 0.900432 1.08227 2.5731 + vertex 0.899677 1.07957 2.57051 + endloop + endfacet + facet normal -0.791462 -0.274704 0.546009 + outer loop + vertex 0.902223 1.0779 2.57336 + vertex 0.899677 1.07957 2.57051 + vertex 0.90065 1.07722 2.57073 + endloop + endfacet + facet normal -0.771203 -0.286332 0.568559 + outer loop + vertex 0.902323 1.08169 2.57549 + vertex 0.90323 1.08375 2.57775 + vertex 0.901321 1.08482 2.5757 + endloop + endfacet + facet normal -0.787375 -0.2839 0.547213 + outer loop + vertex 0.899332 1.08612 2.57351 + vertex 0.900432 1.08227 2.5731 + vertex 0.901321 1.08482 2.5757 + endloop + endfacet + facet normal -0.787505 -0.288292 0.544723 + outer loop + vertex 0.90053 1.08715 2.57579 + vertex 0.899332 1.08612 2.57351 + vertex 0.901321 1.08482 2.5757 + endloop + endfacet + facet normal -0.77328 -0.284322 0.566744 + outer loop + vertex 0.901321 1.08482 2.5757 + vertex 0.902191 1.08799 2.57848 + vertex 0.90053 1.08715 2.57579 + endloop + endfacet + facet normal -0.771204 -0.286435 0.568506 + outer loop + vertex 0.90323 1.08375 2.57775 + vertex 0.902191 1.08799 2.57848 + vertex 0.901321 1.08482 2.5757 + endloop + endfacet + facet normal -0.719358 -0.284195 0.633844 + outer loop + vertex 0.903619 1.10062 2.58595 + vertex 0.901938 1.105 2.58601 + vertex 0.900606 1.10234 2.58331 + endloop + endfacet + facet normal -0.71793 -0.269395 0.641874 + outer loop + vertex 0.902361 1.09751 2.58324 + vertex 0.903619 1.10062 2.58595 + vertex 0.900606 1.10234 2.58331 + endloop + endfacet + facet normal -0.670499 -0.266237 0.692495 + outer loop + vertex 0.903619 1.10062 2.58595 + vertex 0.905101 1.10313 2.58835 + vertex 0.901938 1.105 2.58601 + endloop + endfacet + facet normal -0.721448 -0.281812 0.632531 + outer loop + vertex 0.899168 1.10668 2.5836 + vertex 0.900606 1.10234 2.58331 + vertex 0.901938 1.105 2.58601 + endloop + endfacet + facet normal -0.722487 -0.291732 0.626821 + outer loop + vertex 0.900558 1.10842 2.58601 + vertex 0.899168 1.10668 2.5836 + vertex 0.901938 1.105 2.58601 + endloop + endfacet + facet normal -0.672226 -0.271422 0.688797 + outer loop + vertex 0.901938 1.105 2.58601 + vertex 0.903247 1.10806 2.58849 + vertex 0.900558 1.10842 2.58601 + endloop + endfacet + facet normal -0.671521 -0.272073 0.689228 + outer loop + vertex 0.905101 1.10313 2.58835 + vertex 0.903247 1.10806 2.58849 + vertex 0.901938 1.105 2.58601 + endloop + endfacet + facet normal -0.722006 -0.292433 0.627049 + outer loop + vertex 0.899168 1.10668 2.5836 + vertex 0.900558 1.10842 2.58601 + vertex 0.898688 1.11006 2.58462 + endloop + endfacet + facet normal -0.716418 -0.273612 0.64178 + outer loop + vertex 0.900558 1.10842 2.58601 + vertex 0.900345 1.11157 2.58711 + vertex 0.898688 1.11006 2.58462 + endloop + endfacet + facet normal -0.670438 -0.285601 0.684796 + outer loop + vertex 0.900558 1.10842 2.58601 + vertex 0.903247 1.10806 2.58849 + vertex 0.900345 1.11157 2.58711 + endloop + endfacet + facet normal -0.661895 -0.273381 0.697967 + outer loop + vertex 0.903247 1.10806 2.58849 + vertex 0.902711 1.1125 2.58972 + vertex 0.900345 1.11157 2.58711 + endloop + endfacet + facet normal -0.642659 -0.2843 0.711451 + outer loop + vertex 0.902644 1.11564 2.59086 + vertex 0.901302 1.11933 2.59113 + vertex 0.899658 1.11623 2.5884 + endloop + endfacet + facet normal -0.643441 -0.273523 0.714961 + outer loop + vertex 0.902644 1.11564 2.59086 + vertex 0.899658 1.11623 2.5884 + vertex 0.902711 1.1125 2.58972 + endloop + endfacet + facet normal -0.655322 -0.289381 0.697719 + outer loop + vertex 0.902711 1.1125 2.58972 + vertex 0.899658 1.11623 2.5884 + vertex 0.900345 1.11157 2.58711 + endloop + endfacet + facet normal -0.576782 -0.264637 0.772846 + outer loop + vertex 0.902644 1.11564 2.59086 + vertex 0.904735 1.11667 2.59278 + vertex 0.901302 1.11933 2.59113 + endloop + endfacet + facet normal -0.627117 -0.299292 0.71913 + outer loop + vertex 0.89705 1.12229 2.58865 + vertex 0.899658 1.11623 2.5884 + vertex 0.901302 1.11933 2.59113 + endloop + endfacet + facet normal -0.627694 -0.301207 0.717827 + outer loop + vertex 0.899885 1.12319 2.59151 + vertex 0.89705 1.12229 2.58865 + vertex 0.901302 1.11933 2.59113 + endloop + endfacet + facet normal -0.55709 -0.281584 0.781256 + outer loop + vertex 0.901302 1.11933 2.59113 + vertex 0.903678 1.12206 2.5938 + vertex 0.899885 1.12319 2.59151 + endloop + endfacet + facet normal -0.574932 -0.260538 0.775611 + outer loop + vertex 0.904735 1.11667 2.59278 + vertex 0.903678 1.12206 2.5938 + vertex 0.901302 1.11933 2.59113 + endloop + endfacet + facet normal -0.618514 -0.323974 0.715878 + outer loop + vertex 0.89705 1.12229 2.58865 + vertex 0.899885 1.12319 2.59151 + vertex 0.897448 1.12591 2.59063 + endloop + endfacet + facet normal -0.585568 -0.280008 0.760728 + outer loop + vertex 0.899885 1.12319 2.59151 + vertex 0.899774 1.12666 2.5927 + vertex 0.897448 1.12591 2.59063 + endloop + endfacet + facet normal -0.557307 -0.285592 0.779645 + outer loop + vertex 0.899885 1.12319 2.59151 + vertex 0.903678 1.12206 2.5938 + vertex 0.899774 1.12666 2.5927 + endloop + endfacet + facet normal -0.41511 -0.00640072 0.909748 + outer loop + vertex 0.90291 1.20397 2.61039 + vertex 0.904488 1.20636 2.61113 + vertex 0.901577 1.20752 2.60981 + endloop + endfacet + facet normal -0.441644 -0.0184397 0.897001 + outer loop + vertex 0.90291 1.20397 2.61039 + vertex 0.901577 1.20752 2.60981 + vertex 0.899942 1.20243 2.6089 + endloop + endfacet + facet normal -0.438782 -0.0196047 0.89838 + outer loop + vertex 0.899942 1.20243 2.6089 + vertex 0.901577 1.20752 2.60981 + vertex 0.897258 1.20742 2.60769 + endloop + endfacet + facet normal -0.401397 -0.0172959 0.915741 + outer loop + vertex 0.904488 1.20636 2.61113 + vertex 0.90291 1.20397 2.61039 + vertex 0.905843 1.20273 2.61165 + endloop + endfacet + facet normal -0.651085 -0.0274258 0.758509 + outer loop + vertex 0.899266 1.40313 2.63172 + vertex 0.897625 1.40116 2.63024 + vertex 0.899842 1.39968 2.63209 + endloop + endfacet + facet normal -0.556511 0.108587 0.823714 + outer loop + vertex 0.898484 1.70643 2.62305 + vertex 0.901969 1.71059 2.62486 + vertex 0.898959 1.71228 2.6226 + endloop + endfacet + facet normal -0.559522 0.101701 0.822552 + outer loop + vertex 0.901969 1.71059 2.62486 + vertex 0.902292 1.7153 2.62449 + vertex 0.898959 1.71228 2.6226 + endloop + endfacet + facet normal -0.565628 0.111925 0.81703 + outer loop + vertex 0.898959 1.71228 2.6226 + vertex 0.902292 1.7153 2.62449 + vertex 0.899352 1.71726 2.62219 + endloop + endfacet + facet normal -0.563048 0.117037 0.818095 + outer loop + vertex 0.902292 1.7153 2.62449 + vertex 0.902426 1.7203 2.62387 + vertex 0.899352 1.71726 2.62219 + endloop + endfacet + facet normal -0.565077 0.120107 0.816249 + outer loop + vertex 0.899352 1.71726 2.62219 + vertex 0.902426 1.7203 2.62387 + vertex 0.899643 1.72183 2.62172 + endloop + endfacet + facet normal -0.56729 0.109733 0.816174 + outer loop + vertex 0.901859 1.74373 2.6202 + vertex 0.904833 1.74662 2.62188 + vertex 0.902568 1.74751 2.62019 + endloop + endfacet + facet normal -0.57637 0.0808209 0.813182 + outer loop + vertex 0.904468 1.74988 2.6213 + vertex 0.902568 1.74751 2.62019 + vertex 0.904833 1.74662 2.62188 + endloop + endfacet + facet normal -0.496786 0.0556083 0.86609 + outer loop + vertex 0.902113 1.7554 2.61945 + vertex 0.902389 1.76047 2.61928 + vertex 0.899013 1.75715 2.61756 + endloop + endfacet + facet normal -0.501242 0.0616989 0.863105 + outer loop + vertex 0.899013 1.75715 2.61756 + vertex 0.902389 1.76047 2.61928 + vertex 0.899337 1.7623 2.61738 + endloop + endfacet + facet normal -0.496028 0.072618 0.865265 + outer loop + vertex 0.902389 1.76047 2.61928 + vertex 0.902634 1.76554 2.61899 + vertex 0.899337 1.7623 2.61738 + endloop + endfacet + facet normal -0.493829 0.0696254 0.866767 + outer loop + vertex 0.899337 1.7623 2.61738 + vertex 0.902634 1.76554 2.61899 + vertex 0.899582 1.76731 2.61711 + endloop + endfacet + facet normal -0.589814 0.285377 0.755433 + outer loop + vertex 0.90073 1.90371 2.59017 + vertex 0.898641 1.90263 2.58895 + vertex 0.89907 1.90036 2.59014 + endloop + endfacet + facet normal -0.546705 0.263672 0.794727 + outer loop + vertex 0.89907 1.90036 2.59014 + vertex 0.903018 1.90118 2.59258 + vertex 0.90073 1.90371 2.59017 + endloop + endfacet + facet normal -0.546581 0.286116 0.787011 + outer loop + vertex 0.89907 1.90036 2.59014 + vertex 0.899278 1.89645 2.5917 + vertex 0.903018 1.90118 2.59258 + endloop + endfacet + facet normal -0.596448 0.319821 0.736183 + outer loop + vertex 0.898507 1.90526 2.58769 + vertex 0.898641 1.90263 2.58895 + vertex 0.90073 1.90371 2.59017 + endloop + endfacet + facet normal -0.617782 0.284325 0.733147 + outer loop + vertex 0.901055 1.90776 2.58887 + vertex 0.898507 1.90526 2.58769 + vertex 0.90073 1.90371 2.59017 + endloop + endfacet + facet normal -0.559354 0.293172 0.775354 + outer loop + vertex 0.90073 1.90371 2.59017 + vertex 0.904105 1.90645 2.59157 + vertex 0.901055 1.90776 2.58887 + endloop + endfacet + facet normal -0.545162 0.265496 0.795179 + outer loop + vertex 0.903018 1.90118 2.59258 + vertex 0.904105 1.90645 2.59157 + vertex 0.90073 1.90371 2.59017 + endloop + endfacet + facet normal -0.670843 0.291562 0.681881 + outer loop + vertex 0.901043 1.91268 2.58698 + vertex 0.89836 1.91245 2.58443 + vertex 0.898414 1.90949 2.58575 + endloop + endfacet + facet normal -0.632967 0.311192 0.708881 + outer loop + vertex 0.898414 1.90949 2.58575 + vertex 0.898507 1.90526 2.58769 + vertex 0.901055 1.90776 2.58887 + endloop + endfacet + facet normal -0.655564 0.270036 0.705207 + outer loop + vertex 0.901043 1.91268 2.58698 + vertex 0.898414 1.90949 2.58575 + vertex 0.901055 1.90776 2.58887 + endloop + endfacet + facet normal -0.5945 0.287748 0.750847 + outer loop + vertex 0.901043 1.91268 2.58698 + vertex 0.901055 1.90776 2.58887 + vertex 0.903898 1.91049 2.59008 + endloop + endfacet + facet normal -0.629927 0.229168 0.742074 + outer loop + vertex 0.901043 1.91268 2.58698 + vertex 0.903898 1.91049 2.59008 + vertex 0.903679 1.913 2.58912 + endloop + endfacet + facet normal -0.575728 0.256975 0.77621 + outer loop + vertex 0.903898 1.91049 2.59008 + vertex 0.901055 1.90776 2.58887 + vertex 0.904105 1.90645 2.59157 + endloop + endfacet + facet normal -0.670174 0.295573 0.68081 + outer loop + vertex 0.898537 1.91548 2.58329 + vertex 0.89836 1.91245 2.58443 + vertex 0.901043 1.91268 2.58698 + endloop + endfacet + facet normal -0.694096 0.261088 0.670867 + outer loop + vertex 0.901188 1.91849 2.58487 + vertex 0.898537 1.91548 2.58329 + vertex 0.901043 1.91268 2.58698 + endloop + endfacet + facet normal -0.635313 0.277703 0.720596 + outer loop + vertex 0.901043 1.91268 2.58698 + vertex 0.90429 1.91634 2.58843 + vertex 0.901188 1.91849 2.58487 + endloop + endfacet + facet normal -0.626658 0.265162 0.732795 + outer loop + vertex 0.903679 1.913 2.58912 + vertex 0.90429 1.91634 2.58843 + vertex 0.901043 1.91268 2.58698 + endloop + endfacet + facet normal -0.759661 0.293418 0.580363 + outer loop + vertex 0.899781 1.92247 2.5816 + vertex 0.897766 1.92155 2.57942 + vertex 0.898701 1.91915 2.58186 + endloop + endfacet + facet normal -0.706964 0.284724 0.647406 + outer loop + vertex 0.898701 1.91915 2.58186 + vertex 0.898537 1.91548 2.58329 + vertex 0.901188 1.91849 2.58487 + endloop + endfacet + facet normal -0.707909 0.281959 0.647584 + outer loop + vertex 0.898701 1.91915 2.58186 + vertex 0.901188 1.91849 2.58487 + vertex 0.899781 1.92247 2.5816 + endloop + endfacet + facet normal -0.725716 0.265181 0.634835 + outer loop + vertex 0.899781 1.92247 2.5816 + vertex 0.901188 1.91849 2.58487 + vertex 0.902334 1.9234 2.58413 + endloop + endfacet + facet normal -0.658641 0.260237 0.706024 + outer loop + vertex 0.901188 1.91849 2.58487 + vertex 0.904558 1.92128 2.58698 + vertex 0.902334 1.9234 2.58413 + endloop + endfacet + facet normal -0.652974 0.245442 0.716507 + outer loop + vertex 0.90429 1.91634 2.58843 + vertex 0.904558 1.92128 2.58698 + vertex 0.901188 1.91849 2.58487 + endloop + endfacet + facet normal -0.759078 0.306793 0.574177 + outer loop + vertex 0.898274 1.92523 2.57813 + vertex 0.897766 1.92155 2.57942 + vertex 0.899781 1.92247 2.5816 + endloop + endfacet + facet normal -0.771306 0.290335 0.566385 + outer loop + vertex 0.90096 1.92764 2.58055 + vertex 0.898274 1.92523 2.57813 + vertex 0.899781 1.92247 2.5816 + endloop + endfacet + facet normal -0.676459 0.254367 0.691159 + outer loop + vertex 0.903386 1.92671 2.58394 + vertex 0.902334 1.9234 2.58413 + vertex 0.904741 1.92488 2.58594 + endloop + endfacet + facet normal -0.745494 0.271634 0.608649 + outer loop + vertex 0.903386 1.92671 2.58394 + vertex 0.90096 1.92764 2.58055 + vertex 0.902334 1.9234 2.58413 + endloop + endfacet + facet normal -0.724819 0.29147 0.624245 + outer loop + vertex 0.90096 1.92764 2.58055 + vertex 0.899781 1.92247 2.5816 + vertex 0.902334 1.9234 2.58413 + endloop + endfacet + facet normal -0.67306 0.237535 0.700405 + outer loop + vertex 0.904741 1.92488 2.58594 + vertex 0.902334 1.9234 2.58413 + vertex 0.904558 1.92128 2.58698 + endloop + endfacet + facet normal -0.794072 0.291291 0.533479 + outer loop + vertex 0.899862 1.9322 2.57665 + vertex 0.897987 1.93139 2.57431 + vertex 0.898793 1.92889 2.57687 + endloop + endfacet + facet normal -0.773346 0.301057 0.557944 + outer loop + vertex 0.898793 1.92889 2.57687 + vertex 0.898274 1.92523 2.57813 + vertex 0.90096 1.92764 2.58055 + endloop + endfacet + facet normal -0.779076 0.287976 0.556876 + outer loop + vertex 0.898793 1.92889 2.57687 + vertex 0.90096 1.92764 2.58055 + vertex 0.899862 1.9322 2.57665 + endloop + endfacet + facet normal -0.78685 0.280141 0.549898 + outer loop + vertex 0.899862 1.9322 2.57665 + vertex 0.90096 1.92764 2.58055 + vertex 0.902074 1.93283 2.5795 + endloop + endfacet + facet normal -0.748548 0.282046 0.600104 + outer loop + vertex 0.90096 1.92764 2.58055 + vertex 0.903634 1.93015 2.5827 + vertex 0.902074 1.93283 2.5795 + endloop + endfacet + facet normal -0.745542 0.271506 0.608647 + outer loop + vertex 0.903386 1.92671 2.58394 + vertex 0.903634 1.93015 2.5827 + vertex 0.90096 1.92764 2.58055 + endloop + endfacet + facet normal -0.794275 0.288935 0.534456 + outer loop + vertex 0.89844 1.9351 2.57298 + vertex 0.897987 1.93139 2.57431 + vertex 0.899862 1.9322 2.57665 + endloop + endfacet + facet normal -0.794361 0.288814 0.534394 + outer loop + vertex 0.901016 1.93752 2.5755 + vertex 0.89844 1.9351 2.57298 + vertex 0.899862 1.9322 2.57665 + endloop + endfacet + facet normal -0.753691 0.288613 0.590467 + outer loop + vertex 0.903309 1.93622 2.57942 + vertex 0.902074 1.93283 2.5795 + vertex 0.904126 1.9337 2.58169 + endloop + endfacet + facet normal -0.778364 0.296732 0.553262 + outer loop + vertex 0.903309 1.93622 2.57942 + vertex 0.901016 1.93752 2.5755 + vertex 0.902074 1.93283 2.5795 + endloop + endfacet + facet normal -0.785566 0.289611 0.54682 + outer loop + vertex 0.901016 1.93752 2.5755 + vertex 0.899862 1.9322 2.57665 + vertex 0.902074 1.93283 2.5795 + endloop + endfacet + facet normal -0.754184 0.27449 0.596542 + outer loop + vertex 0.904126 1.9337 2.58169 + vertex 0.902074 1.93283 2.5795 + vertex 0.903634 1.93015 2.5827 + endloop + endfacet + facet normal -0.789837 0.284044 0.543577 + outer loop + vertex 0.89996 1.94223 2.57141 + vertex 0.898064 1.9414 2.56909 + vertex 0.898893 1.93885 2.57163 + endloop + endfacet + facet normal -0.794226 0.288017 0.535024 + outer loop + vertex 0.898893 1.93885 2.57163 + vertex 0.89844 1.9351 2.57298 + vertex 0.901016 1.93752 2.5755 + endloop + endfacet + facet normal -0.795426 0.285241 0.534729 + outer loop + vertex 0.898893 1.93885 2.57163 + vertex 0.901016 1.93752 2.5755 + vertex 0.89996 1.94223 2.57141 + endloop + endfacet + facet normal -0.792097 0.288669 0.537822 + outer loop + vertex 0.89996 1.94223 2.57141 + vertex 0.901016 1.93752 2.5755 + vertex 0.902158 1.94285 2.57431 + endloop + endfacet + facet normal -0.778812 0.289908 0.556242 + outer loop + vertex 0.901016 1.93752 2.5755 + vertex 0.903746 1.94008 2.57798 + vertex 0.902158 1.94285 2.57431 + endloop + endfacet + facet normal -0.779609 0.29387 0.553038 + outer loop + vertex 0.903309 1.93622 2.57942 + vertex 0.903746 1.94008 2.57798 + vertex 0.901016 1.93752 2.5755 + endloop + endfacet + facet normal -0.790032 0.2813 0.544719 + outer loop + vertex 0.898535 1.94516 2.56783 + vertex 0.898064 1.9414 2.56909 + vertex 0.89996 1.94223 2.57141 + endloop + endfacet + facet normal -0.784691 0.288626 0.548594 + outer loop + vertex 0.901123 1.9475 2.5703 + vertex 0.898535 1.94516 2.56783 + vertex 0.89996 1.94223 2.57141 + endloop + endfacet + facet normal -0.78284 0.29193 0.549489 + outer loop + vertex 0.903216 1.94612 2.57409 + vertex 0.902158 1.94285 2.57431 + vertex 0.904059 1.94377 2.57654 + endloop + endfacet + facet normal -0.787395 0.292914 0.542413 + outer loop + vertex 0.903216 1.94612 2.57409 + vertex 0.901123 1.9475 2.5703 + vertex 0.902158 1.94285 2.57431 + endloop + endfacet + facet normal -0.792185 0.288055 0.538021 + outer loop + vertex 0.901123 1.9475 2.5703 + vertex 0.89996 1.94223 2.57141 + vertex 0.902158 1.94285 2.57431 + endloop + endfacet + facet normal -0.783248 0.28349 0.553314 + outer loop + vertex 0.904059 1.94377 2.57654 + vertex 0.902158 1.94285 2.57431 + vertex 0.903746 1.94008 2.57798 + endloop + endfacet + facet normal -0.783137 0.292469 0.548778 + outer loop + vertex 0.900062 1.95211 2.56636 + vertex 0.898217 1.95137 2.56412 + vertex 0.899009 1.9489 2.56657 + endloop + endfacet + facet normal -0.784109 0.285223 0.551199 + outer loop + vertex 0.899009 1.9489 2.56657 + vertex 0.898535 1.94516 2.56783 + vertex 0.901123 1.9475 2.5703 + endloop + endfacet + facet normal -0.781044 0.291992 0.552006 + outer loop + vertex 0.899009 1.9489 2.56657 + vertex 0.901123 1.9475 2.5703 + vertex 0.900062 1.95211 2.56636 + endloop + endfacet + facet normal -0.775669 0.297276 0.556744 + outer loop + vertex 0.900062 1.95211 2.56636 + vertex 0.901123 1.9475 2.5703 + vertex 0.902261 1.95265 2.56914 + endloop + endfacet + facet normal -0.782568 0.296672 0.547333 + outer loop + vertex 0.901123 1.9475 2.5703 + vertex 0.903688 1.94968 2.57279 + vertex 0.902261 1.95265 2.56914 + endloop + endfacet + facet normal -0.783268 0.301961 0.543425 + outer loop + vertex 0.903216 1.94612 2.57409 + vertex 0.903688 1.94968 2.57279 + vertex 0.901123 1.9475 2.5703 + endloop + endfacet + facet normal -0.782361 0.300763 0.545392 + outer loop + vertex 0.89873 1.95498 2.56287 + vertex 0.898217 1.95137 2.56412 + vertex 0.900062 1.95211 2.56636 + endloop + endfacet + facet normal -0.783516 0.299233 0.544576 + outer loop + vertex 0.901055 1.95682 2.5652 + vertex 0.89873 1.95498 2.56287 + vertex 0.900062 1.95211 2.56636 + endloop + endfacet + facet normal -0.7769 0.302048 0.552443 + outer loop + vertex 0.903274 1.95608 2.56869 + vertex 0.902261 1.95265 2.56914 + vertex 0.904239 1.95348 2.57147 + endloop + endfacet + facet normal -0.77381 0.301725 0.556938 + outer loop + vertex 0.903274 1.95608 2.56869 + vertex 0.901055 1.95682 2.5652 + vertex 0.902261 1.95265 2.56914 + endloop + endfacet + facet normal -0.775203 0.300247 0.555799 + outer loop + vertex 0.901055 1.95682 2.5652 + vertex 0.900062 1.95211 2.56636 + vertex 0.902261 1.95265 2.56914 + endloop + endfacet + facet normal -0.776688 0.304493 0.551398 + outer loop + vertex 0.904239 1.95348 2.57147 + vertex 0.902261 1.95265 2.56914 + vertex 0.903688 1.94968 2.57279 + endloop + endfacet + facet normal -0.802859 0.328883 0.497245 + outer loop + vertex 0.900899 1.9629 2.56145 + vertex 0.898787 1.96128 2.55911 + vertex 0.89935 1.95884 2.56163 + endloop + endfacet + facet normal -0.78361 0.30021 0.543901 + outer loop + vertex 0.89935 1.95884 2.56163 + vertex 0.89873 1.95498 2.56287 + vertex 0.901055 1.95682 2.5652 + endloop + endfacet + facet normal -0.772126 0.319477 0.549323 + outer loop + vertex 0.900899 1.9629 2.56145 + vertex 0.89935 1.95884 2.56163 + vertex 0.901055 1.95682 2.5652 + endloop + endfacet + facet normal -0.77743 0.315961 0.543848 + outer loop + vertex 0.900899 1.9629 2.56145 + vertex 0.901055 1.95682 2.5652 + vertex 0.903011 1.95981 2.56627 + endloop + endfacet + facet normal -0.789651 0.296884 0.536946 + outer loop + vertex 0.900899 1.9629 2.56145 + vertex 0.903011 1.95981 2.56627 + vertex 0.902813 1.96274 2.56435 + endloop + endfacet + facet normal -0.771625 0.307544 0.556787 + outer loop + vertex 0.903011 1.95981 2.56627 + vertex 0.901055 1.95682 2.5652 + vertex 0.903274 1.95608 2.56869 + endloop + endfacet + facet normal -0.863094 0.332719 0.379956 + outer loop + vertex 0.899935 1.96812 2.55612 + vertex 0.898454 1.96613 2.55449 + vertex 0.898995 1.96421 2.5574 + endloop + endfacet + facet normal -0.80292 0.341902 0.488285 + outer loop + vertex 0.898995 1.96421 2.5574 + vertex 0.898787 1.96128 2.55911 + vertex 0.900899 1.9629 2.56145 + endloop + endfacet + facet normal -0.797519 0.352903 0.489308 + outer loop + vertex 0.898995 1.96421 2.5574 + vertex 0.900899 1.9629 2.56145 + vertex 0.899935 1.96812 2.55612 + endloop + endfacet + facet normal -0.842452 0.301094 0.446785 + outer loop + vertex 0.899935 1.96812 2.55612 + vertex 0.900899 1.9629 2.56145 + vertex 0.901913 1.96841 2.55965 + endloop + endfacet + facet normal -0.789565 0.31706 0.525414 + outer loop + vertex 0.900899 1.9629 2.56145 + vertex 0.903154 1.9656 2.56321 + vertex 0.901913 1.96841 2.55965 + endloop + endfacet + facet normal -0.786443 0.307937 0.535428 + outer loop + vertex 0.902813 1.96274 2.56435 + vertex 0.903154 1.9656 2.56321 + vertex 0.900899 1.9629 2.56145 + endloop + endfacet + facet normal -0.90269 0.356841 0.240447 + outer loop + vertex 0.899929 1.97272 2.55115 + vertex 0.898639 1.97057 2.54949 + vertex 0.898774 1.96893 2.55243 + endloop + endfacet + facet normal -0.865155 0.357464 0.351748 + outer loop + vertex 0.898774 1.96893 2.55243 + vertex 0.898454 1.96613 2.55449 + vertex 0.899935 1.96812 2.55612 + endloop + endfacet + facet normal -0.854595 0.3804 0.353502 + outer loop + vertex 0.898774 1.96893 2.55243 + vertex 0.899935 1.96812 2.55612 + vertex 0.899929 1.97272 2.55115 + endloop + endfacet + facet normal -0.894295 0.3277 0.304712 + outer loop + vertex 0.899929 1.97272 2.55115 + vertex 0.899935 1.96812 2.55612 + vertex 0.901665 1.9731 2.55583 + endloop + endfacet + facet normal -0.803033 0.297124 0.516581 + outer loop + vertex 0.903007 1.97164 2.55949 + vertex 0.901913 1.96841 2.55965 + vertex 0.903619 1.96914 2.56188 + endloop + endfacet + facet normal -0.846973 0.307805 0.433466 + outer loop + vertex 0.903007 1.97164 2.55949 + vertex 0.901665 1.9731 2.55583 + vertex 0.901913 1.96841 2.55965 + endloop + endfacet + facet normal -0.838651 0.316324 0.4434 + outer loop + vertex 0.901665 1.9731 2.55583 + vertex 0.899935 1.96812 2.55612 + vertex 0.901913 1.96841 2.55965 + endloop + endfacet + facet normal -0.802831 0.299008 0.515807 + outer loop + vertex 0.903619 1.96914 2.56188 + vertex 0.901913 1.96841 2.55965 + vertex 0.903154 1.9656 2.56321 + endloop + endfacet + facet normal -0.755405 0.599939 0.263508 + outer loop + vertex 0.90094 1.97774 2.54657 + vertex 0.902192 1.98 2.545 + vertex 0.9 1.97724 2.545 + endloop + endfacet + facet normal -0.839849 0.385963 0.38169 + outer loop + vertex 0.899347 1.97359 2.54726 + vertex 0.90094 1.97774 2.54657 + vertex 0.9 1.97724 2.545 + endloop + endfacet + facet normal -0.901631 0.373377 0.218293 + outer loop + vertex 0.899347 1.97359 2.54726 + vertex 0.898639 1.97057 2.54949 + vertex 0.899929 1.97272 2.55115 + endloop + endfacet + facet normal -0.897946 0.381432 0.219549 + outer loop + vertex 0.899347 1.97359 2.54726 + vertex 0.899929 1.97272 2.55115 + vertex 0.90094 1.97774 2.54657 + endloop + endfacet + facet normal -0.933647 0.325226 0.150106 + outer loop + vertex 0.90094 1.97774 2.54657 + vertex 0.899929 1.97272 2.55115 + vertex 0.901537 1.97744 2.55093 + endloop + endfacet + facet normal -0.896588 0.319954 0.306202 + outer loop + vertex 0.899929 1.97272 2.55115 + vertex 0.901665 1.9731 2.55583 + vertex 0.901537 1.97744 2.55093 + endloop + endfacet + facet normal -0.928099 0.266635 0.259882 + outer loop + vertex 0.901537 1.97744 2.55093 + vertex 0.901665 1.9731 2.55583 + vertex 0.902816 1.97814 2.55478 + endloop + endfacet + facet normal -0.856516 0.285857 0.429727 + outer loop + vertex 0.901665 1.9731 2.55583 + vertex 0.903686 1.9753 2.5584 + vertex 0.902816 1.97814 2.55478 + endloop + endfacet + facet normal -0.8566 0.287085 0.428741 + outer loop + vertex 0.903007 1.97164 2.55949 + vertex 0.903686 1.9753 2.5584 + vertex 0.901665 1.9731 2.55583 + endloop + endfacet + facet normal -0.880646 0.18441 -0.436411 + outer loop + vertex 0.902192 1.98 2.545 + vertex 0.90094 1.97774 2.54657 + vertex 0.903239 1.985 2.545 + endloop + endfacet + facet normal -0.952439 0.304402 0.0141293 + outer loop + vertex 0.903239 1.985 2.545 + vertex 0.90094 1.97774 2.54657 + vertex 0.90229 1.98196 2.5466 + endloop + endfacet + facet normal -0.942161 0.299953 0.149538 + outer loop + vertex 0.90094 1.97774 2.54657 + vertex 0.901537 1.97744 2.55093 + vertex 0.90229 1.98196 2.5466 + endloop + endfacet + facet normal -0.95143 0.280287 0.127359 + outer loop + vertex 0.90229 1.98196 2.5466 + vertex 0.901537 1.97744 2.55093 + vertex 0.902906 1.98206 2.55098 + endloop + endfacet + facet normal -0.927033 0.271503 0.258641 + outer loop + vertex 0.901537 1.97744 2.55093 + vertex 0.902816 1.97814 2.55478 + vertex 0.902906 1.98206 2.55098 + endloop + endfacet + facet normal -0.92931 0.267579 0.254529 + outer loop + vertex 0.902906 1.98206 2.55098 + vertex 0.902816 1.97814 2.55478 + vertex 0.903722 1.98146 2.55459 + endloop + endfacet + facet normal -0.864265 0.259737 0.430793 + outer loop + vertex 0.902816 1.97814 2.55478 + vertex 0.904502 1.97948 2.55735 + vertex 0.903722 1.98146 2.55459 + endloop + endfacet + facet normal -0.863701 0.274594 0.422633 + outer loop + vertex 0.903686 1.9753 2.5584 + vertex 0.904502 1.97948 2.55735 + vertex 0.902816 1.97814 2.55478 + endloop + endfacet + facet normal -0.563983 -0.563588 -0.603566 + outer loop + vertex 0.905 1.985 2.54324 + vertex 0.903471 1.99 2.54 + vertex 0.905 1.98847 2.54 + endloop + endfacet + facet normal -0.586057 -0.559198 -0.586375 + outer loop + vertex 0.905 1.985 2.54324 + vertex 0.903239 1.985 2.545 + vertex 0.903471 1.99 2.54 + endloop + endfacet + facet normal -0.197299 0.697777 0.688607 + outer loop + vertex 0.903239 1.985 2.545 + vertex 0.903432 1.98727 2.54275 + vertex 0.903471 1.99 2.54 + endloop + endfacet + facet normal 0.798839 -0.455995 -0.392334 + outer loop + vertex 0.903239 1.985 2.545 + vertex 0.90229 1.98196 2.5466 + vertex 0.903432 1.98727 2.54275 + endloop + endfacet + facet normal -0.960353 0.266261 0.0826261 + outer loop + vertex 0.903432 1.98727 2.54275 + vertex 0.90229 1.98196 2.5466 + vertex 0.903383 1.98591 2.54656 + endloop + endfacet + facet normal -0.915927 0.304378 0.261595 + outer loop + vertex 0.903801 1.98581 2.54976 + vertex 0.902906 1.98206 2.55098 + vertex 0.904362 1.9846 2.55313 + endloop + endfacet + facet normal -0.953152 0.271366 0.133647 + outer loop + vertex 0.903801 1.98581 2.54976 + vertex 0.903383 1.98591 2.54656 + vertex 0.902906 1.98206 2.55098 + endloop + endfacet + facet normal -0.955541 0.265493 0.128278 + outer loop + vertex 0.903383 1.98591 2.54656 + vertex 0.90229 1.98196 2.5466 + vertex 0.902906 1.98206 2.55098 + endloop + endfacet + facet normal -0.847337 0.356536 0.393576 + outer loop + vertex 0.904362 1.9846 2.55313 + vertex 0.903722 1.98146 2.55459 + vertex 0.905009 1.98292 2.55604 + endloop + endfacet + facet normal -0.915932 0.307337 0.258094 + outer loop + vertex 0.902906 1.98206 2.55098 + vertex 0.903722 1.98146 2.55459 + vertex 0.904362 1.9846 2.55313 + endloop + endfacet + facet normal -0.842495 0.295606 0.450355 + outer loop + vertex 0.905009 1.98292 2.55604 + vertex 0.903722 1.98146 2.55459 + vertex 0.904502 1.97948 2.55735 + endloop + endfacet + facet normal -0.688709 0.227929 -0.688279 + outer loop + vertex 0.905 1.99 2.53847 + vertex 0.903471 1.99 2.54 + vertex 0.905 1.99462 2.54 + endloop + endfacet + facet normal -0.959919 0.251289 0.124135 + outer loop + vertex 0.905 1.99462 2.54 + vertex 0.903432 1.98727 2.54275 + vertex 0.905 1.99215 2.545 + endloop + endfacet + facet normal -0.909823 0.301107 0.285583 + outer loop + vertex 0.903471 1.99 2.54 + vertex 0.903432 1.98727 2.54275 + vertex 0.905 1.99462 2.54 + endloop + endfacet + facet normal -0.936895 0.291183 0.193493 + outer loop + vertex 0.905 1.99215 2.545 + vertex 0.903383 1.98591 2.54656 + vertex 0.904392 1.98873 2.5472 + endloop + endfacet + facet normal -0.959304 0.269639 0.0838475 + outer loop + vertex 0.903432 1.98727 2.54275 + vertex 0.903383 1.98591 2.54656 + vertex 0.905 1.99215 2.545 + endloop + endfacet + facet normal -0.942368 0.306826 0.133415 + outer loop + vertex 0.904392 1.98873 2.5472 + vertex 0.903383 1.98591 2.54656 + vertex 0.903801 1.98581 2.54976 + endloop + endfacet + facet normal 0.0713282 -0.870192 -0.487523 + outer loop + vertex 0.905 2.10811 2.49 + vertex 0.904857 2.10655 2.49277 + vertex 0.9 2.1077 2.49 + endloop + endfacet + facet normal 0.211835 -0.712834 -0.668576 + outer loop + vertex 0.904857 2.10655 2.49277 + vertex 0.899033 2.10533 2.49222 + vertex 0.9 2.1077 2.49 + endloop + endfacet + facet normal 0.222816 -0.910216 -0.349085 + outer loop + vertex 0.904857 2.10655 2.49277 + vertex 0.903699 2.10476 2.4967 + vertex 0.899033 2.10533 2.49222 + endloop + endfacet + facet normal -0.0146613 -0.993564 -0.112316 + outer loop + vertex 0.903699 2.10476 2.4967 + vertex 0.898259 2.10487 2.4964 + vertex 0.899033 2.10533 2.49222 + endloop + endfacet + facet normal -0.0203724 -0.999753 -0.00892479 + outer loop + vertex 0.903699 2.10476 2.4967 + vertex 0.903112 2.10473 2.50121 + vertex 0.898259 2.10487 2.4964 + endloop + endfacet + facet normal -0.325644 -0.895988 0.301931 + outer loop + vertex 0.903112 2.10473 2.50121 + vertex 0.898317 2.10618 2.50035 + vertex 0.898259 2.10487 2.4964 + endloop + endfacet + facet normal -0.540357 -0.266525 0.79811 + outer loop + vertex 0.89972 2.10725 2.50291 + vertex 0.90302 2.10601 2.50473 + vertex 0.901671 2.10824 2.50456 + endloop + endfacet + facet normal -0.544312 -0.624274 0.560363 + outer loop + vertex 0.89972 2.10725 2.50291 + vertex 0.898317 2.10618 2.50035 + vertex 0.90302 2.10601 2.50473 + endloop + endfacet + facet normal -0.326581 -0.890865 0.315759 + outer loop + vertex 0.898317 2.10618 2.50035 + vertex 0.903112 2.10473 2.50121 + vertex 0.90302 2.10601 2.50473 + endloop + endfacet + facet normal -0.664521 -0.351779 0.65929 + outer loop + vertex 0.90302 2.10601 2.50473 + vertex 0.904343 2.10745 2.50683 + vertex 0.901671 2.10824 2.50456 + endloop + endfacet + facet normal -0.615974 0.39273 0.682891 + outer loop + vertex 0.901224 2.11108 2.50298 + vertex 0.897714 2.11099 2.49987 + vertex 0.899346 2.10903 2.50247 + endloop + endfacet + facet normal -0.659498 0.04798 0.750174 + outer loop + vertex 0.899346 2.10903 2.50247 + vertex 0.89972 2.10725 2.50291 + vertex 0.901671 2.10824 2.50456 + endloop + endfacet + facet normal -0.567444 0.330487 0.754178 + outer loop + vertex 0.901224 2.11108 2.50298 + vertex 0.899346 2.10903 2.50247 + vertex 0.901671 2.10824 2.50456 + endloop + endfacet + facet normal -0.652228 0.287703 0.701303 + outer loop + vertex 0.901224 2.11108 2.50298 + vertex 0.901671 2.10824 2.50456 + vertex 0.903699 2.10974 2.50583 + endloop + endfacet + facet normal -0.621032 0.347705 0.702439 + outer loop + vertex 0.901224 2.11108 2.50298 + vertex 0.903699 2.10974 2.50583 + vertex 0.903355 2.11158 2.50462 + endloop + endfacet + facet normal -0.609326 0.16703 0.775128 + outer loop + vertex 0.903699 2.10974 2.50583 + vertex 0.901671 2.10824 2.50456 + vertex 0.904343 2.10745 2.50683 + endloop + endfacet + facet normal -0.594312 0.530209 0.604708 + outer loop + vertex 0.901224 2.11108 2.50298 + vertex 0.903222 2.11309 2.50318 + vertex 0.900808 2.11441 2.49966 + endloop + endfacet + facet normal -0.563234 0.547908 0.618517 + outer loop + vertex 0.901224 2.11108 2.50298 + vertex 0.900808 2.11441 2.49966 + vertex 0.897714 2.11099 2.49987 + endloop + endfacet + facet normal -0.52297 0.515234 0.678997 + outer loop + vertex 0.897714 2.11099 2.49987 + vertex 0.900808 2.11441 2.49966 + vertex 0.896766 2.1141 2.49678 + endloop + endfacet + facet normal -0.591798 0.527188 0.609793 + outer loop + vertex 0.903222 2.11309 2.50318 + vertex 0.901224 2.11108 2.50298 + vertex 0.903355 2.11158 2.50462 + endloop + endfacet + facet normal -0.428006 0.728585 0.534766 + outer loop + vertex 0.900848 2.12283 2.48589 + vertex 0.898383 2.12259 2.48424 + vertex 0.899003 2.12088 2.48708 + endloop + endfacet + facet normal -0.458582 0.735519 0.498713 + outer loop + vertex 0.902722 2.1222 2.48855 + vertex 0.900848 2.12283 2.48589 + vertex 0.899003 2.12088 2.48708 + endloop + endfacet + facet normal -0.451018 0.773421 0.445425 + outer loop + vertex 0.902722 2.1222 2.48855 + vertex 0.899003 2.12088 2.48708 + vertex 0.903573 2.12067 2.49207 + endloop + endfacet + facet normal -0.384043 0.838389 0.386799 + outer loop + vertex 0.903573 2.12067 2.49207 + vertex 0.899003 2.12088 2.48708 + vertex 0.898902 2.11879 2.49149 + endloop + endfacet + facet normal -0.381977 0.822745 0.420932 + outer loop + vertex 0.903573 2.12067 2.49207 + vertex 0.898902 2.11879 2.49149 + vertex 0.903443 2.11799 2.49718 + endloop + endfacet + facet normal -0.400071 0.807624 0.433228 + outer loop + vertex 0.903443 2.11799 2.49718 + vertex 0.898902 2.11879 2.49149 + vertex 0.898387 2.11659 2.49512 + endloop + endfacet + facet normal -0.459138 0.679526 0.57222 + outer loop + vertex 0.900808 2.11441 2.49966 + vertex 0.898387 2.11659 2.49512 + vertex 0.896766 2.1141 2.49678 + endloop + endfacet + facet normal -0.426306 0.704888 0.566919 + outer loop + vertex 0.903443 2.11799 2.49718 + vertex 0.898387 2.11659 2.49512 + vertex 0.900808 2.11441 2.49966 + endloop + endfacet + facet normal -0.559327 0.0883231 0.824228 + outer loop + vertex 0.900848 2.12283 2.48589 + vertex 0.9 2.12577 2.485 + vertex 0.898383 2.12259 2.48424 + endloop + endfacet + facet normal -0.707487 0.009913 0.706657 + outer loop + vertex 0.900848 2.12283 2.48589 + vertex 0.905 2.12618 2.49 + vertex 0.9 2.12577 2.485 + endloop + endfacet + facet normal -0.266522 0.945107 0.189048 + outer loop + vertex 0.905 2.12618 2.49 + vertex 0.905 2.12718 2.485 + vertex 0.9 2.12577 2.485 + endloop + endfacet + facet normal -0.770736 0.223355 0.596723 + outer loop + vertex 0.905 2.12618 2.49 + vertex 0.900848 2.12283 2.48589 + vertex 0.902722 2.1222 2.48855 + endloop + endfacet + facet normal -0.182786 -0.96406 0.192814 + outer loop + vertex 0.91 0.902201 2.49 + vertex 0.91 0.903201 2.495 + vertex 0.905 0.903149 2.49 + endloop + endfacet + facet normal 0.0741361 -0.995206 -0.0637933 + outer loop + vertex 0.91 0.903201 2.495 + vertex 0.904068 0.902999 2.49126 + vertex 0.905 0.903149 2.49 + endloop + endfacet + facet normal -0.280246 -0.911673 0.300523 + outer loop + vertex 0.904675 0.903546 2.49443 + vertex 0.908908 0.902787 2.49608 + vertex 0.906522 0.903934 2.49733 + endloop + endfacet + facet normal -0.25127 -0.944679 0.21082 + outer loop + vertex 0.904675 0.903546 2.49443 + vertex 0.904068 0.902999 2.49126 + vertex 0.908908 0.902787 2.49608 + endloop + endfacet + facet normal 0.16275 -0.964947 -0.205889 + outer loop + vertex 0.904068 0.902999 2.49126 + vertex 0.91 0.903201 2.495 + vertex 0.908908 0.902787 2.49608 + endloop + endfacet + facet normal -0.296631 -0.915253 0.272622 + outer loop + vertex 0.908908 0.902787 2.49608 + vertex 0.909384 0.903598 2.49932 + vertex 0.906522 0.903934 2.49733 + endloop + endfacet + facet normal -0.379796 -0.853757 0.356166 + outer loop + vertex 0.904675 0.903546 2.49443 + vertex 0.906522 0.903934 2.49733 + vertex 0.902469 0.905061 2.49571 + endloop + endfacet + facet normal -0.399455 -0.804624 0.439336 + outer loop + vertex 0.906522 0.903934 2.49733 + vertex 0.909384 0.903598 2.49932 + vertex 0.907111 0.905473 2.50069 + endloop + endfacet + facet normal -0.399403 -0.804648 0.439339 + outer loop + vertex 0.906522 0.903934 2.49733 + vertex 0.907111 0.905473 2.50069 + vertex 0.902469 0.905061 2.49571 + endloop + endfacet + facet normal -0.448513 -0.75337 0.480904 + outer loop + vertex 0.902469 0.905061 2.49571 + vertex 0.907111 0.905473 2.50069 + vertex 0.901691 0.907582 2.49893 + endloop + endfacet + facet normal -0.451231 -0.67316 0.585872 + outer loop + vertex 0.907111 0.905473 2.50069 + vertex 0.903699 0.909508 2.50269 + vertex 0.901691 0.907582 2.49893 + endloop + endfacet + facet normal -0.503365 -0.686688 0.524484 + outer loop + vertex 0.909224 0.907022 2.50474 + vertex 0.903699 0.909508 2.50269 + vertex 0.907111 0.905473 2.50069 + endloop + endfacet + facet normal -0.501135 -0.600464 0.623142 + outer loop + vertex 0.903699 0.909508 2.50269 + vertex 0.909224 0.907022 2.50474 + vertex 0.907659 0.909924 2.50628 + endloop + endfacet + facet normal -0.546184 -0.512372 0.66269 + outer loop + vertex 0.903711 0.912122 2.50472 + vertex 0.903699 0.909508 2.50269 + vertex 0.907659 0.909924 2.50628 + endloop + endfacet + facet normal -0.513008 -0.375662 0.771816 + outer loop + vertex 0.907659 0.909924 2.50628 + vertex 0.905281 0.912818 2.50611 + vertex 0.903711 0.912122 2.50472 + endloop + endfacet + facet normal -0.492645 -0.357661 0.793334 + outer loop + vertex 0.909045 0.912164 2.50815 + vertex 0.905281 0.912818 2.50611 + vertex 0.907659 0.909924 2.50628 + endloop + endfacet + facet normal 0.166416 0.98124 -0.097331 + outer loop + vertex 0.91 0.917652 2.495 + vertex 0.905 0.9185 2.495 + vertex 0.91 0.918148 2.5 + endloop + endfacet + facet normal -0.103201 0.979646 0.17217 + outer loop + vertex 0.91 0.918148 2.5 + vertex 0.905 0.9185 2.495 + vertex 0.90372 0.917992 2.49712 + endloop + endfacet + facet normal -0.211232 0.885914 0.412962 + outer loop + vertex 0.91 0.918148 2.5 + vertex 0.90372 0.917992 2.49712 + vertex 0.908576 0.916833 2.50209 + endloop + endfacet + facet normal -0.0168958 0.969941 0.242754 + outer loop + vertex 0.908576 0.916833 2.50209 + vertex 0.90372 0.917992 2.49712 + vertex 0.903256 0.916725 2.50215 + endloop + endfacet + facet normal -0.0150235 0.937297 0.348207 + outer loop + vertex 0.908576 0.916833 2.50209 + vertex 0.903256 0.916725 2.50215 + vertex 0.908939 0.91509 2.5068 + endloop + endfacet + facet normal -0.296933 0.726952 0.61917 + outer loop + vertex 0.908939 0.91509 2.5068 + vertex 0.903256 0.916725 2.50215 + vertex 0.905374 0.914525 2.50575 + endloop + endfacet + facet normal -0.439005 0.205227 0.874732 + outer loop + vertex 0.909045 0.912164 2.50815 + vertex 0.905374 0.914525 2.50575 + vertex 0.905281 0.912818 2.50611 + endloop + endfacet + facet normal -0.315598 0.388132 0.865882 + outer loop + vertex 0.908939 0.91509 2.5068 + vertex 0.905374 0.914525 2.50575 + vertex 0.909045 0.912164 2.50815 + endloop + endfacet + facet normal -0.688577 -0.197856 -0.697649 + outer loop + vertex 0.91 1.02366 2.54 + vertex 0.909615 1.025 2.54 + vertex 0.91 1.025 2.53962 + endloop + endfacet + facet normal -0.956723 -0.274906 0.0954359 + outer loop + vertex 0.91 1.02366 2.54 + vertex 0.91 1.025 2.54386 + vertex 0.909615 1.025 2.54 + endloop + endfacet + facet normal -0.944131 -0.315826 0.0941799 + outer loop + vertex 0.91 1.02534 2.545 + vertex 0.909615 1.025 2.54 + vertex 0.91 1.025 2.54386 + endloop + endfacet + facet normal -0.921943 -0.375112 0.0965023 + outer loop + vertex 0.91 1.02534 2.545 + vertex 0.908104 1.03 2.545 + vertex 0.909615 1.025 2.54 + endloop + endfacet + facet normal -0.95952 -0.00844152 -0.281515 + outer loop + vertex 0.908104 1.03 2.545 + vertex 0.909571 1.03 2.54 + vertex 0.909615 1.025 2.54 + endloop + endfacet + facet normal -0.647319 -0.263375 -0.71527 + outer loop + vertex 0.908714 1.02679 2.54563 + vertex 0.908104 1.03 2.545 + vertex 0.91 1.02534 2.545 + endloop + endfacet + facet normal -0.948031 -0.224438 -0.225534 + outer loop + vertex 0.907398 1.03093 2.54704 + vertex 0.908104 1.03 2.545 + vertex 0.908714 1.02679 2.54563 + endloop + endfacet + facet normal -0.939437 -0.33009 0.092191 + outer loop + vertex 0.908714 1.02679 2.54563 + vertex 0.908677 1.02778 2.54878 + vertex 0.907398 1.03093 2.54704 + endloop + endfacet + facet normal -0.942394 -0.263869 -0.20559 + outer loop + vertex 0.908104 1.03 2.545 + vertex 0.907398 1.03093 2.54704 + vertex 0.906704 1.035 2.545 + endloop + endfacet + facet normal -0.924725 -0.28456 -0.252803 + outer loop + vertex 0.906704 1.035 2.545 + vertex 0.907398 1.03093 2.54704 + vertex 0.906298 1.03423 2.54735 + endloop + endfacet + facet normal -0.942359 -0.295006 0.157895 + outer loop + vertex 0.908171 1.03041 2.55068 + vertex 0.907398 1.03093 2.54704 + vertex 0.908677 1.02778 2.54878 + endloop + endfacet + facet normal -0.939936 -0.303544 0.156146 + outer loop + vertex 0.908171 1.03041 2.55068 + vertex 0.906903 1.03458 2.55116 + vertex 0.907398 1.03093 2.54704 + endloop + endfacet + facet normal -0.928521 -0.326098 0.177509 + outer loop + vertex 0.906903 1.03458 2.55116 + vertex 0.906298 1.03423 2.54735 + vertex 0.907398 1.03093 2.54704 + endloop + endfacet + facet normal -0.903951 -0.308753 0.295879 + outer loop + vertex 0.908171 1.03041 2.55068 + vertex 0.908511 1.03211 2.5535 + vertex 0.906903 1.03458 2.55116 + endloop + endfacet + facet normal 0.064187 0.0227865 -0.997678 + outer loop + vertex 0.904577 1.03833 2.54494 + vertex 0.905 1.0398 2.545 + vertex 0.906704 1.035 2.545 + endloop + endfacet + facet normal -0.84164 -0.536587 0.0609591 + outer loop + vertex 0.904577 1.03833 2.54494 + vertex 0.906704 1.035 2.545 + vertex 0.905102 1.03788 2.54822 + endloop + endfacet + facet normal -0.937306 -0.249365 -0.243464 + outer loop + vertex 0.905102 1.03788 2.54822 + vertex 0.906704 1.035 2.545 + vertex 0.906298 1.03423 2.54735 + endloop + endfacet + facet normal -0.92172 -0.344531 0.178131 + outer loop + vertex 0.906298 1.03423 2.54735 + vertex 0.906903 1.03458 2.55116 + vertex 0.905102 1.03788 2.54822 + endloop + endfacet + facet normal -0.924577 -0.318627 0.208888 + outer loop + vertex 0.905102 1.03788 2.54822 + vertex 0.906903 1.03458 2.55116 + vertex 0.905796 1.03836 2.55203 + endloop + endfacet + facet normal -0.903627 -0.292032 0.313329 + outer loop + vertex 0.908071 1.03525 2.55515 + vertex 0.906903 1.03458 2.55116 + vertex 0.908511 1.03211 2.5535 + endloop + endfacet + facet normal -0.897211 -0.310036 0.314469 + outer loop + vertex 0.908071 1.03525 2.55515 + vertex 0.90682 1.03939 2.55566 + vertex 0.906903 1.03458 2.55116 + endloop + endfacet + facet normal -0.877775 -0.335481 0.341999 + outer loop + vertex 0.90682 1.03939 2.55566 + vertex 0.905796 1.03836 2.55203 + vertex 0.906903 1.03458 2.55116 + endloop + endfacet + facet normal -0.855188 -0.309757 0.415576 + outer loop + vertex 0.908071 1.03525 2.55515 + vertex 0.908583 1.03749 2.55788 + vertex 0.90682 1.03939 2.55566 + endloop + endfacet + facet normal -0.907074 -0.411533 0.0886456 + outer loop + vertex 0.904577 1.03833 2.54494 + vertex 0.905102 1.03788 2.54822 + vertex 0.903643 1.04064 2.54609 + endloop + endfacet + facet normal -0.920463 -0.344647 0.184299 + outer loop + vertex 0.903614 1.04208 2.54864 + vertex 0.903643 1.04064 2.54609 + vertex 0.905102 1.03788 2.54822 + endloop + endfacet + facet normal -0.903366 -0.345541 0.254029 + outer loop + vertex 0.903614 1.04208 2.54864 + vertex 0.905102 1.03788 2.54822 + vertex 0.904719 1.04225 2.5528 + endloop + endfacet + facet normal -0.931267 -0.299369 0.207652 + outer loop + vertex 0.904719 1.04225 2.5528 + vertex 0.905102 1.03788 2.54822 + vertex 0.905796 1.03836 2.55203 + endloop + endfacet + facet normal -0.887387 -0.313114 0.338386 + outer loop + vertex 0.905796 1.03836 2.55203 + vertex 0.90682 1.03939 2.55566 + vertex 0.904719 1.04225 2.5528 + endloop + endfacet + facet normal -0.887508 -0.322087 0.329529 + outer loop + vertex 0.904719 1.04225 2.5528 + vertex 0.90682 1.03939 2.55566 + vertex 0.905783 1.04298 2.55638 + endloop + endfacet + facet normal -0.854982 -0.304892 0.419579 + outer loop + vertex 0.908204 1.04067 2.55942 + vertex 0.90682 1.03939 2.55566 + vertex 0.908583 1.03749 2.55788 + endloop + endfacet + facet normal -0.843437 -0.330027 0.423907 + outer loop + vertex 0.908204 1.04067 2.55942 + vertex 0.906804 1.04405 2.55926 + vertex 0.90682 1.03939 2.55566 + endloop + endfacet + facet normal -0.845261 -0.328274 0.421628 + outer loop + vertex 0.906804 1.04405 2.55926 + vertex 0.905783 1.04298 2.55638 + vertex 0.90682 1.03939 2.55566 + endloop + endfacet + facet normal -0.817971 -0.316904 0.480099 + outer loop + vertex 0.908204 1.04067 2.55942 + vertex 0.90872 1.04331 2.56204 + vertex 0.906804 1.04405 2.55926 + endloop + endfacet + facet normal -0.915318 -0.311053 0.25581 + outer loop + vertex 0.903614 1.04208 2.54864 + vertex 0.904719 1.04225 2.5528 + vertex 0.903021 1.0452 2.55031 + endloop + endfacet + facet normal -0.915328 -0.308743 0.258558 + outer loop + vertex 0.903391 1.04662 2.55332 + vertex 0.903021 1.0452 2.55031 + vertex 0.904719 1.04225 2.5528 + endloop + endfacet + facet normal -0.890972 -0.310086 0.331686 + outer loop + vertex 0.903391 1.04662 2.55332 + vertex 0.904719 1.04225 2.5528 + vertex 0.904858 1.04619 2.55686 + endloop + endfacet + facet normal -0.893605 -0.306301 0.3281 + outer loop + vertex 0.904858 1.04619 2.55686 + vertex 0.904719 1.04225 2.5528 + vertex 0.905783 1.04298 2.55638 + endloop + endfacet + facet normal -0.854715 -0.308363 0.417581 + outer loop + vertex 0.905783 1.04298 2.55638 + vertex 0.906804 1.04405 2.55926 + vertex 0.904858 1.04619 2.55686 + endloop + endfacet + facet normal -0.855344 -0.323649 0.404521 + outer loop + vertex 0.904858 1.04619 2.55686 + vertex 0.906804 1.04405 2.55926 + vertex 0.905875 1.04727 2.55987 + endloop + endfacet + facet normal -0.815227 -0.326134 0.478583 + outer loop + vertex 0.906804 1.04405 2.55926 + vertex 0.907398 1.04808 2.56302 + vertex 0.905875 1.04727 2.55987 + endloop + endfacet + facet normal -0.816681 -0.324587 0.477154 + outer loop + vertex 0.90872 1.04331 2.56204 + vertex 0.907398 1.04808 2.56302 + vertex 0.906804 1.04405 2.55926 + endloop + endfacet + facet normal -0.892647 -0.303599 0.333181 + outer loop + vertex 0.903391 1.04662 2.55332 + vertex 0.904858 1.04619 2.55686 + vertex 0.903162 1.04948 2.55531 + endloop + endfacet + facet normal -0.862329 -0.308569 0.401464 + outer loop + vertex 0.904858 1.04619 2.55686 + vertex 0.905875 1.04727 2.55987 + vertex 0.904485 1.05048 2.55936 + endloop + endfacet + facet normal -0.886978 -0.287423 0.361466 + outer loop + vertex 0.903162 1.04948 2.55531 + vertex 0.904858 1.04619 2.55686 + vertex 0.904485 1.05048 2.55936 + endloop + endfacet + facet normal -0.808525 -0.323874 0.491317 + outer loop + vertex 0.907477 1.05185 2.56572 + vertex 0.906781 1.05548 2.56697 + vertex 0.905522 1.05304 2.56329 + endloop + endfacet + facet normal -0.807924 -0.332153 0.486759 + outer loop + vertex 0.907398 1.04808 2.56302 + vertex 0.907477 1.05185 2.56572 + vertex 0.905522 1.05304 2.56329 + endloop + endfacet + facet normal -0.831972 -0.338603 0.439512 + outer loop + vertex 0.907398 1.04808 2.56302 + vertex 0.905522 1.05304 2.56329 + vertex 0.904485 1.05048 2.55936 + endloop + endfacet + facet normal -0.832435 -0.28365 0.476019 + outer loop + vertex 0.907398 1.04808 2.56302 + vertex 0.904485 1.05048 2.55936 + vertex 0.905875 1.04727 2.55987 + endloop + endfacet + facet normal -0.786718 -0.330129 0.521623 + outer loop + vertex 0.907477 1.05185 2.56572 + vertex 0.908584 1.0528 2.56799 + vertex 0.906781 1.05548 2.56697 + endloop + endfacet + facet normal -0.806341 -0.327146 0.492738 + outer loop + vertex 0.904254 1.05731 2.56405 + vertex 0.905522 1.05304 2.56329 + vertex 0.906781 1.05548 2.56697 + endloop + endfacet + facet normal -0.806349 -0.326617 0.493075 + outer loop + vertex 0.905234 1.05992 2.56738 + vertex 0.904254 1.05731 2.56405 + vertex 0.906781 1.05548 2.56697 + endloop + endfacet + facet normal -0.779275 -0.318179 0.5399 + outer loop + vertex 0.909328 1.05485 2.57028 + vertex 0.906781 1.05548 2.56697 + vertex 0.908584 1.0528 2.56799 + endloop + endfacet + facet normal -0.776728 -0.331863 0.535314 + outer loop + vertex 0.909328 1.05485 2.57028 + vertex 0.907725 1.05887 2.57044 + vertex 0.906781 1.05548 2.56697 + endloop + endfacet + facet normal -0.785278 -0.322516 0.52851 + outer loop + vertex 0.907725 1.05887 2.57044 + vertex 0.905234 1.05992 2.56738 + vertex 0.906781 1.05548 2.56697 + endloop + endfacet + facet normal -0.760651 -0.326525 0.561062 + outer loop + vertex 0.909328 1.05485 2.57028 + vertex 0.910537 1.05724 2.5733 + vertex 0.907725 1.05887 2.57044 + endloop + endfacet + facet normal -0.807558 -0.325 0.492165 + outer loop + vertex 0.904254 1.05731 2.56405 + vertex 0.905234 1.05992 2.56738 + vertex 0.903338 1.06079 2.56485 + endloop + endfacet + facet normal -0.80845 -0.318044 0.495234 + outer loop + vertex 0.903716 1.06332 2.56708 + vertex 0.903338 1.06079 2.56485 + vertex 0.905234 1.05992 2.56738 + endloop + endfacet + facet normal -0.793506 -0.308818 0.524385 + outer loop + vertex 0.903716 1.06332 2.56708 + vertex 0.905234 1.05992 2.56738 + vertex 0.906064 1.06433 2.57123 + endloop + endfacet + facet normal -0.785994 -0.316224 0.53124 + outer loop + vertex 0.906064 1.06433 2.57123 + vertex 0.905234 1.05992 2.56738 + vertex 0.907725 1.05887 2.57044 + endloop + endfacet + facet normal -0.772431 -0.315024 0.551461 + outer loop + vertex 0.907725 1.05887 2.57044 + vertex 0.909113 1.06127 2.57376 + vertex 0.906064 1.06433 2.57123 + endloop + endfacet + facet normal -0.760616 -0.331309 0.558299 + outer loop + vertex 0.910537 1.05724 2.5733 + vertex 0.909113 1.06127 2.57376 + vertex 0.907725 1.05887 2.57044 + endloop + endfacet + facet normal -0.794858 -0.305429 0.524322 + outer loop + vertex 0.902382 1.06795 2.56776 + vertex 0.903716 1.06332 2.56708 + vertex 0.906064 1.06433 2.57123 + endloop + endfacet + facet normal -0.796263 -0.313515 0.517371 + outer loop + vertex 0.904526 1.07007 2.57235 + vertex 0.902382 1.06795 2.56776 + vertex 0.906064 1.06433 2.57123 + endloop + endfacet + facet normal -0.769496 -0.303416 0.561974 + outer loop + vertex 0.909132 1.06458 2.57557 + vertex 0.906064 1.06433 2.57123 + vertex 0.909113 1.06127 2.57376 + endloop + endfacet + facet normal -0.76547 -0.317062 0.559935 + outer loop + vertex 0.909132 1.06458 2.57557 + vertex 0.907384 1.06869 2.57551 + vertex 0.906064 1.06433 2.57123 + endloop + endfacet + facet normal -0.768471 -0.313879 0.557614 + outer loop + vertex 0.907384 1.06869 2.57551 + vertex 0.904526 1.07007 2.57235 + vertex 0.906064 1.06433 2.57123 + endloop + endfacet + facet normal -0.737627 -0.304507 0.602646 + outer loop + vertex 0.909132 1.06458 2.57557 + vertex 0.910243 1.06735 2.57833 + vertex 0.907384 1.06869 2.57551 + endloop + endfacet + facet normal -0.78488 -0.334371 0.521689 + outer loop + vertex 0.902382 1.06795 2.56776 + vertex 0.904526 1.07007 2.57235 + vertex 0.9024 1.07182 2.57027 + endloop + endfacet + facet normal -0.782854 -0.312166 0.538231 + outer loop + vertex 0.903265 1.07371 2.57262 + vertex 0.9024 1.07182 2.57027 + vertex 0.904526 1.07007 2.57235 + endloop + endfacet + facet normal -0.761365 -0.307178 0.570934 + outer loop + vertex 0.903265 1.07371 2.57262 + vertex 0.904526 1.07007 2.57235 + vertex 0.905893 1.07433 2.57646 + endloop + endfacet + facet normal -0.769181 -0.298805 0.564868 + outer loop + vertex 0.905893 1.07433 2.57646 + vertex 0.904526 1.07007 2.57235 + vertex 0.907384 1.06869 2.57551 + endloop + endfacet + facet normal -0.747102 -0.297921 0.594207 + outer loop + vertex 0.907384 1.06869 2.57551 + vertex 0.909053 1.07118 2.57886 + vertex 0.905893 1.07433 2.57646 + endloop + endfacet + facet normal -0.737511 -0.311225 0.599347 + outer loop + vertex 0.910243 1.06735 2.57833 + vertex 0.909053 1.07118 2.57886 + vertex 0.907384 1.06869 2.57551 + endloop + endfacet + facet normal -0.76673 -0.291334 0.572057 + outer loop + vertex 0.902223 1.0779 2.57336 + vertex 0.903265 1.07371 2.57262 + vertex 0.905893 1.07433 2.57646 + endloop + endfacet + facet normal -0.767996 -0.296362 0.567761 + outer loop + vertex 0.904463 1.08008 2.57752 + vertex 0.902223 1.0779 2.57336 + vertex 0.905893 1.07433 2.57646 + endloop + endfacet + facet normal -0.739862 -0.275822 0.613618 + outer loop + vertex 0.909321 1.07445 2.58065 + vertex 0.905893 1.07433 2.57646 + vertex 0.909053 1.07118 2.57886 + endloop + endfacet + facet normal -0.731698 -0.308391 0.607876 + outer loop + vertex 0.909321 1.07445 2.58065 + vertex 0.907417 1.07876 2.58054 + vertex 0.905893 1.07433 2.57646 + endloop + endfacet + facet normal -0.743845 -0.296178 0.599144 + outer loop + vertex 0.907417 1.07876 2.58054 + vertex 0.904463 1.08008 2.57752 + vertex 0.905893 1.07433 2.57646 + endloop + endfacet + facet normal -0.695987 -0.291469 0.656238 + outer loop + vertex 0.909321 1.07445 2.58065 + vertex 0.910506 1.07745 2.58324 + vertex 0.907417 1.07876 2.58054 + endloop + endfacet + facet normal -0.766953 -0.298245 0.568184 + outer loop + vertex 0.902223 1.0779 2.57336 + vertex 0.904463 1.08008 2.57752 + vertex 0.902323 1.08169 2.57549 + endloop + endfacet + facet normal -0.766282 -0.292411 0.572108 + outer loop + vertex 0.90323 1.08375 2.57775 + vertex 0.902323 1.08169 2.57549 + vertex 0.904463 1.08008 2.57752 + endloop + endfacet + facet normal -0.747678 -0.287806 0.598452 + outer loop + vertex 0.90323 1.08375 2.57775 + vertex 0.904463 1.08008 2.57752 + vertex 0.905827 1.08449 2.58135 + endloop + endfacet + facet normal -0.74396 -0.291441 0.601319 + outer loop + vertex 0.905827 1.08449 2.58135 + vertex 0.904463 1.08008 2.57752 + vertex 0.907417 1.07876 2.58054 + endloop + endfacet + facet normal -0.715789 -0.288513 0.635929 + outer loop + vertex 0.907417 1.07876 2.58054 + vertex 0.908987 1.08167 2.58363 + vertex 0.905827 1.08449 2.58135 + endloop + endfacet + facet normal -0.69619 -0.310878 0.647051 + outer loop + vertex 0.910506 1.07745 2.58324 + vertex 0.908987 1.08167 2.58363 + vertex 0.907417 1.07876 2.58054 + endloop + endfacet + facet normal -0.748315 -0.285971 0.598536 + outer loop + vertex 0.902191 1.08799 2.57848 + vertex 0.90323 1.08375 2.57775 + vertex 0.905827 1.08449 2.58135 + endloop + endfacet + facet normal -0.749731 -0.290822 0.594412 + outer loop + vertex 0.904487 1.09003 2.58237 + vertex 0.902191 1.08799 2.57848 + vertex 0.905827 1.08449 2.58135 + endloop + endfacet + facet normal -0.714814 -0.285392 0.63843 + outer loop + vertex 0.908562 1.08508 2.58468 + vertex 0.905827 1.08449 2.58135 + vertex 0.908987 1.08167 2.58363 + endloop + endfacet + facet normal -0.719532 -0.27041 0.639651 + outer loop + vertex 0.908562 1.08508 2.58468 + vertex 0.907468 1.08864 2.58495 + vertex 0.905827 1.08449 2.58135 + endloop + endfacet + facet normal -0.700016 -0.289543 0.652796 + outer loop + vertex 0.907468 1.08864 2.58495 + vertex 0.904487 1.09003 2.58237 + vertex 0.905827 1.08449 2.58135 + endloop + endfacet + facet normal -0.641197 -0.25283 0.72453 + outer loop + vertex 0.908562 1.08508 2.58468 + vertex 0.910456 1.08665 2.5869 + vertex 0.907468 1.08864 2.58495 + endloop + endfacet + facet normal -0.741136 -0.306265 0.597427 + outer loop + vertex 0.902191 1.08799 2.57848 + vertex 0.904487 1.09003 2.58237 + vertex 0.902348 1.09179 2.58062 + endloop + endfacet + facet normal -0.73848 -0.293399 0.607095 + outer loop + vertex 0.90326 1.09361 2.58261 + vertex 0.902348 1.09179 2.58062 + vertex 0.904487 1.09003 2.58237 + endloop + endfacet + facet normal -0.698356 -0.282968 0.657441 + outer loop + vertex 0.90326 1.09361 2.58261 + vertex 0.904487 1.09003 2.58237 + vertex 0.905656 1.09382 2.58524 + endloop + endfacet + facet normal -0.699659 -0.281872 0.656526 + outer loop + vertex 0.905656 1.09382 2.58524 + vertex 0.904487 1.09003 2.58237 + vertex 0.907468 1.08864 2.58495 + endloop + endfacet + facet normal -0.633625 -0.262801 0.727637 + outer loop + vertex 0.907468 1.08864 2.58495 + vertex 0.9099 1.09158 2.58813 + vertex 0.905656 1.09382 2.58524 + endloop + endfacet + facet normal -0.641251 -0.253024 0.724414 + outer loop + vertex 0.910456 1.08665 2.5869 + vertex 0.9099 1.09158 2.58813 + vertex 0.907468 1.08864 2.58495 + endloop + endfacet + facet normal -0.702035 -0.26842 0.659619 + outer loop + vertex 0.902361 1.09751 2.58324 + vertex 0.90326 1.09361 2.58261 + vertex 0.905656 1.09382 2.58524 + endloop + endfacet + facet normal -0.710711 -0.285148 0.643103 + outer loop + vertex 0.904727 1.09747 2.58584 + vertex 0.902361 1.09751 2.58324 + vertex 0.905656 1.09382 2.58524 + endloop + endfacet + facet normal -0.641226 -0.279118 0.714788 + outer loop + vertex 0.905656 1.09382 2.58524 + vertex 0.907316 1.09782 2.5883 + vertex 0.904727 1.09747 2.58584 + endloop + endfacet + facet normal -0.636982 -0.282692 0.717174 + outer loop + vertex 0.9099 1.09158 2.58813 + vertex 0.907316 1.09782 2.5883 + vertex 0.905656 1.09382 2.58524 + endloop + endfacet + facet normal -0.712954 -0.274391 0.645295 + outer loop + vertex 0.902361 1.09751 2.58324 + vertex 0.904727 1.09747 2.58584 + vertex 0.903619 1.10062 2.58595 + endloop + endfacet + facet normal -0.613841 -0.253582 0.747593 + outer loop + vertex 0.90796 1.10164 2.59019 + vertex 0.906855 1.10545 2.59058 + vertex 0.905101 1.10313 2.58835 + endloop + endfacet + facet normal -0.616036 -0.264775 0.741886 + outer loop + vertex 0.907316 1.09782 2.5883 + vertex 0.90796 1.10164 2.59019 + vertex 0.905101 1.10313 2.58835 + endloop + endfacet + facet normal -0.65669 -0.281283 0.699742 + outer loop + vertex 0.907316 1.09782 2.5883 + vertex 0.905101 1.10313 2.58835 + vertex 0.903619 1.10062 2.58595 + endloop + endfacet + facet normal -0.647842 -0.254113 0.718142 + outer loop + vertex 0.907316 1.09782 2.5883 + vertex 0.903619 1.10062 2.58595 + vertex 0.904727 1.09747 2.58584 + endloop + endfacet + facet normal -0.546922 -0.23975 0.80212 + outer loop + vertex 0.90796 1.10164 2.59019 + vertex 0.910504 1.10284 2.59229 + vertex 0.906855 1.10545 2.59058 + endloop + endfacet + facet normal -0.614897 -0.252351 0.747142 + outer loop + vertex 0.903247 1.10806 2.58849 + vertex 0.905101 1.10313 2.58835 + vertex 0.906855 1.10545 2.59058 + endloop + endfacet + facet normal -0.617067 -0.258484 0.743246 + outer loop + vertex 0.905767 1.10982 2.59119 + vertex 0.903247 1.10806 2.58849 + vertex 0.906855 1.10545 2.59058 + endloop + endfacet + facet normal -0.556276 -0.250237 0.792426 + outer loop + vertex 0.906855 1.10545 2.59058 + vertex 0.908739 1.10737 2.59251 + vertex 0.905767 1.10982 2.59119 + endloop + endfacet + facet normal -0.553171 -0.254209 0.793334 + outer loop + vertex 0.910504 1.10284 2.59229 + vertex 0.908739 1.10737 2.59251 + vertex 0.906855 1.10545 2.59058 + endloop + endfacet + facet normal -0.604803 -0.279729 0.745631 + outer loop + vertex 0.902711 1.1125 2.58972 + vertex 0.903247 1.10806 2.58849 + vertex 0.905767 1.10982 2.59119 + endloop + endfacet + facet normal -0.601509 -0.273205 0.750697 + outer loop + vertex 0.904834 1.11337 2.59174 + vertex 0.902711 1.1125 2.58972 + vertex 0.905767 1.10982 2.59119 + endloop + endfacet + facet normal -0.533327 -0.26343 0.803845 + outer loop + vertex 0.905767 1.10982 2.59119 + vertex 0.908408 1.11215 2.59371 + vertex 0.904834 1.11337 2.59174 + endloop + endfacet + facet normal -0.550595 -0.239443 0.799695 + outer loop + vertex 0.908739 1.10737 2.59251 + vertex 0.908408 1.11215 2.59371 + vertex 0.905767 1.10982 2.59119 + endloop + endfacet + facet normal -0.596239 -0.285387 0.750369 + outer loop + vertex 0.902711 1.1125 2.58972 + vertex 0.904834 1.11337 2.59174 + vertex 0.902644 1.11564 2.59086 + endloop + endfacet + facet normal -0.578921 -0.260132 0.772775 + outer loop + vertex 0.904834 1.11337 2.59174 + vertex 0.904735 1.11667 2.59278 + vertex 0.902644 1.11564 2.59086 + endloop + endfacet + facet normal -0.533846 -0.267965 0.801999 + outer loop + vertex 0.904834 1.11337 2.59174 + vertex 0.908408 1.11215 2.59371 + vertex 0.904735 1.11667 2.59278 + endloop + endfacet + facet normal -0.417528 -0.0138069 0.908559 + outer loop + vertex 0.904429 1.20932 2.61114 + vertex 0.901577 1.20752 2.60981 + vertex 0.904488 1.20636 2.61113 + endloop + endfacet + facet normal -0.435325 -0.0141112 0.900163 + outer loop + vertex 0.904488 1.20636 2.61113 + vertex 0.907831 1.20815 2.61277 + vertex 0.904429 1.20932 2.61114 + endloop + endfacet + facet normal -0.428603 -0.0292993 0.903018 + outer loop + vertex 0.904488 1.20636 2.61113 + vertex 0.905843 1.20273 2.61165 + vertex 0.907831 1.20815 2.61277 + endloop + endfacet + facet normal -0.433859 -0.026868 0.90058 + outer loop + vertex 0.905843 1.20273 2.61165 + vertex 0.910219 1.2026 2.61376 + vertex 0.907831 1.20815 2.61277 + endloop + endfacet + facet normal -0.407929 -0.0318834 0.912457 + outer loop + vertex 0.901577 1.20752 2.60981 + vertex 0.904429 1.20932 2.61114 + vertex 0.902642 1.21138 2.61042 + endloop + endfacet + facet normal -0.430134 -0.0551573 0.901079 + outer loop + vertex 0.904429 1.20932 2.61114 + vertex 0.905611 1.213 2.61193 + vertex 0.902642 1.21138 2.61042 + endloop + endfacet + facet normal -0.506959 -0.158313 0.847307 + outer loop + vertex 0.907953 1.24638 2.6192 + vertex 0.906852 1.25143 2.61949 + vertex 0.904345 1.24814 2.61737 + endloop + endfacet + facet normal -0.503835 -0.161507 0.848567 + outer loop + vertex 0.904345 1.24814 2.61737 + vertex 0.906852 1.25143 2.61949 + vertex 0.90285 1.2529 2.61739 + endloop + endfacet + facet normal -0.549172 -0.128968 0.825698 + outer loop + vertex 0.908373 1.25487 2.62121 + vertex 0.907017 1.25938 2.62101 + vertex 0.904865 1.2563 2.6191 + endloop + endfacet + facet normal -0.556153 -0.161558 0.815226 + outer loop + vertex 0.908373 1.25487 2.62121 + vertex 0.904865 1.2563 2.6191 + vertex 0.906852 1.25143 2.61949 + endloop + endfacet + facet normal -0.498136 -0.134575 0.856592 + outer loop + vertex 0.906852 1.25143 2.61949 + vertex 0.904865 1.2563 2.6191 + vertex 0.90285 1.2529 2.61739 + endloop + endfacet + facet normal -0.612939 -0.150299 0.775704 + outer loop + vertex 0.908373 1.25487 2.62121 + vertex 0.910262 1.25744 2.6232 + vertex 0.907017 1.25938 2.62101 + endloop + endfacet + facet normal -0.541377 -0.136811 0.829575 + outer loop + vertex 0.903467 1.26122 2.619 + vertex 0.904865 1.2563 2.6191 + vertex 0.907017 1.25938 2.62101 + endloop + endfacet + facet normal -0.533188 -0.110919 0.838694 + outer loop + vertex 0.906 1.26427 2.62101 + vertex 0.903467 1.26122 2.619 + vertex 0.907017 1.25938 2.62101 + endloop + endfacet + facet normal -0.608838 -0.126665 0.783117 + outer loop + vertex 0.907017 1.25938 2.62101 + vertex 0.909239 1.26201 2.62316 + vertex 0.906 1.26427 2.62101 + endloop + endfacet + facet normal -0.606489 -0.129734 0.784436 + outer loop + vertex 0.910262 1.25744 2.6232 + vertex 0.909239 1.26201 2.62316 + vertex 0.907017 1.25938 2.62101 + endloop + endfacet + facet normal -0.529037 -0.115668 0.840679 + outer loop + vertex 0.902526 1.2664 2.61912 + vertex 0.903467 1.26122 2.619 + vertex 0.906 1.26427 2.62101 + endloop + endfacet + facet normal -0.522253 -0.098997 0.847025 + outer loop + vertex 0.905249 1.26942 2.62115 + vertex 0.902526 1.2664 2.61912 + vertex 0.906 1.26427 2.62101 + endloop + endfacet + facet normal -0.605302 -0.109529 0.788424 + outer loop + vertex 0.906 1.26427 2.62101 + vertex 0.908495 1.26698 2.6233 + vertex 0.905249 1.26942 2.62115 + endloop + endfacet + facet normal -0.603222 -0.112443 0.789608 + outer loop + vertex 0.909239 1.26201 2.62316 + vertex 0.908495 1.26698 2.6233 + vertex 0.906 1.26427 2.62101 + endloop + endfacet + facet normal -0.518095 -0.104063 0.848969 + outer loop + vertex 0.901726 1.27204 2.61932 + vertex 0.902526 1.2664 2.61912 + vertex 0.905249 1.26942 2.62115 + endloop + endfacet + facet normal -0.508218 -0.0852079 0.857003 + outer loop + vertex 0.904681 1.27373 2.62124 + vertex 0.901726 1.27204 2.61932 + vertex 0.905249 1.26942 2.62115 + endloop + endfacet + facet normal -0.606809 -0.0967577 0.788937 + outer loop + vertex 0.905249 1.26942 2.62115 + vertex 0.907767 1.27268 2.62349 + vertex 0.904681 1.27373 2.62124 + endloop + endfacet + facet normal -0.602164 -0.102375 0.791782 + outer loop + vertex 0.908495 1.26698 2.6233 + vertex 0.907767 1.27268 2.62349 + vertex 0.905249 1.26942 2.62115 + endloop + endfacet + facet normal -0.510757 -0.07964 0.856029 + outer loop + vertex 0.901726 1.27204 2.61932 + vertex 0.904681 1.27373 2.62124 + vertex 0.902833 1.27619 2.62037 + endloop + endfacet + facet normal -0.550633 -0.12017 0.826053 + outer loop + vertex 0.904681 1.27373 2.62124 + vertex 0.905404 1.2777 2.6223 + vertex 0.902833 1.27619 2.62037 + endloop + endfacet + facet normal -0.607284 -0.0997607 0.788197 + outer loop + vertex 0.904681 1.27373 2.62124 + vertex 0.907767 1.27268 2.62349 + vertex 0.905404 1.2777 2.6223 + endloop + endfacet + facet normal -0.649941 -0.0546657 0.758016 + outer loop + vertex 0.907542 1.40519 2.64 + vertex 0.904719 1.40562 2.63761 + vertex 0.906902 1.40104 2.63915 + endloop + endfacet + facet normal -0.613676 0.112958 0.781436 + outer loop + vertex 0.904634 1.73701 2.623 + vertex 0.907337 1.74102 2.62454 + vertex 0.904672 1.74218 2.62228 + endloop + endfacet + facet normal -0.624718 0.0786721 0.776877 + outer loop + vertex 0.907337 1.74102 2.62454 + vertex 0.907475 1.74542 2.62421 + vertex 0.904672 1.74218 2.62228 + endloop + endfacet + facet normal -0.633976 0.0920348 0.767857 + outer loop + vertex 0.904672 1.74218 2.62228 + vertex 0.907475 1.74542 2.62421 + vertex 0.904833 1.74662 2.62188 + endloop + endfacet + facet normal -0.551918 0.0225339 0.833594 + outer loop + vertex 0.904935 1.75357 2.62151 + vertex 0.902036 1.75075 2.61967 + vertex 0.904468 1.74988 2.6213 + endloop + endfacet + facet normal -0.659817 0.0409415 0.75031 + outer loop + vertex 0.904468 1.74988 2.6213 + vertex 0.907264 1.75053 2.62372 + vertex 0.904935 1.75357 2.62151 + endloop + endfacet + facet normal -0.661631 0.0595149 0.747464 + outer loop + vertex 0.904468 1.74988 2.6213 + vertex 0.904833 1.74662 2.62188 + vertex 0.907264 1.75053 2.62372 + endloop + endfacet + facet normal -0.648295 0.045295 0.760041 + outer loop + vertex 0.904833 1.74662 2.62188 + vertex 0.907475 1.74542 2.62421 + vertex 0.907264 1.75053 2.62372 + endloop + endfacet + facet normal -0.568903 0.0482463 0.820988 + outer loop + vertex 0.902113 1.7554 2.61945 + vertex 0.902036 1.75075 2.61967 + vertex 0.904935 1.75357 2.62151 + endloop + endfacet + facet normal -0.573266 0.0386449 0.818458 + outer loop + vertex 0.905184 1.75836 2.62146 + vertex 0.902113 1.7554 2.61945 + vertex 0.904935 1.75357 2.62151 + endloop + endfacet + facet normal -0.675691 0.0430773 0.735925 + outer loop + vertex 0.904935 1.75357 2.62151 + vertex 0.90768 1.75591 2.62389 + vertex 0.905184 1.75836 2.62146 + endloop + endfacet + facet normal -0.669025 0.0283471 0.742699 + outer loop + vertex 0.907264 1.75053 2.62372 + vertex 0.90768 1.75591 2.62389 + vertex 0.904935 1.75357 2.62151 + endloop + endfacet + facet normal -0.585819 0.0585456 0.808324 + outer loop + vertex 0.902389 1.76047 2.61928 + vertex 0.902113 1.7554 2.61945 + vertex 0.905184 1.75836 2.62146 + endloop + endfacet + facet normal -0.580555 0.0686149 0.811325 + outer loop + vertex 0.905437 1.76335 2.62122 + vertex 0.902389 1.76047 2.61928 + vertex 0.905184 1.75836 2.62146 + endloop + endfacet + facet normal -0.678815 0.069724 0.730992 + outer loop + vertex 0.905184 1.75836 2.62146 + vertex 0.907913 1.76081 2.62376 + vertex 0.905437 1.76335 2.62122 + endloop + endfacet + facet normal -0.670641 0.0522173 0.739942 + outer loop + vertex 0.90768 1.75591 2.62389 + vertex 0.907913 1.76081 2.62376 + vertex 0.905184 1.75836 2.62146 + endloop + endfacet + facet normal -0.583651 0.0736819 0.808655 + outer loop + vertex 0.902634 1.76554 2.61899 + vertex 0.902389 1.76047 2.61928 + vertex 0.905437 1.76335 2.62122 + endloop + endfacet + facet normal -0.564507 0.108079 0.818322 + outer loop + vertex 0.905784 1.76836 2.62079 + vertex 0.902634 1.76554 2.61899 + vertex 0.905437 1.76335 2.62122 + endloop + endfacet + facet normal -0.659863 0.108386 0.743528 + outer loop + vertex 0.905437 1.76335 2.62122 + vertex 0.908336 1.76583 2.62343 + vertex 0.905784 1.76836 2.62079 + endloop + endfacet + facet normal -0.658123 0.104483 0.745625 + outer loop + vertex 0.907913 1.76081 2.62376 + vertex 0.908336 1.76583 2.62343 + vertex 0.905437 1.76335 2.62122 + endloop + endfacet + facet normal -0.56083 0.101854 0.821642 + outer loop + vertex 0.90296 1.77061 2.61859 + vertex 0.902634 1.76554 2.61899 + vertex 0.905784 1.76836 2.62079 + endloop + endfacet + facet normal -0.538018 0.139889 0.831245 + outer loop + vertex 0.90628 1.77314 2.62031 + vertex 0.90296 1.77061 2.61859 + vertex 0.905784 1.76836 2.62079 + endloop + endfacet + facet normal -0.623419 0.142422 0.768807 + outer loop + vertex 0.905784 1.76836 2.62079 + vertex 0.908769 1.77078 2.62277 + vertex 0.90628 1.77314 2.62031 + endloop + endfacet + facet normal -0.629766 0.156791 0.760797 + outer loop + vertex 0.908336 1.76583 2.62343 + vertex 0.908769 1.77078 2.62277 + vertex 0.905784 1.76836 2.62079 + endloop + endfacet + facet normal -0.530316 0.124812 0.838562 + outer loop + vertex 0.903455 1.77633 2.61805 + vertex 0.90296 1.77061 2.61859 + vertex 0.90628 1.77314 2.62031 + endloop + endfacet + facet normal -0.510524 0.148288 0.84698 + outer loop + vertex 0.907146 1.77678 2.6202 + vertex 0.903455 1.77633 2.61805 + vertex 0.90628 1.77314 2.62031 + endloop + endfacet + facet normal -0.596258 0.166784 0.785277 + outer loop + vertex 0.90628 1.77314 2.62031 + vertex 0.909181 1.77507 2.6221 + vertex 0.907146 1.77678 2.6202 + endloop + endfacet + facet normal -0.600313 0.178047 0.779695 + outer loop + vertex 0.908769 1.77078 2.62277 + vertex 0.909181 1.77507 2.6221 + vertex 0.90628 1.77314 2.62031 + endloop + endfacet + facet normal -0.584592 0.131527 0.800595 + outer loop + vertex 0.907146 1.77678 2.6202 + vertex 0.909263 1.77844 2.62147 + vertex 0.907139 1.78027 2.61962 + endloop + endfacet + facet normal -0.510388 0.139615 0.848535 + outer loop + vertex 0.907146 1.77678 2.6202 + vertex 0.907139 1.78027 2.61962 + vertex 0.903455 1.77633 2.61805 + endloop + endfacet + facet normal -0.598918 0.162371 0.784176 + outer loop + vertex 0.909263 1.77844 2.62147 + vertex 0.907146 1.77678 2.6202 + vertex 0.909181 1.77507 2.6221 + endloop + endfacet + facet normal -0.581523 0.257726 0.771627 + outer loop + vertex 0.90429 1.91634 2.58843 + vertex 0.907329 1.92029 2.5894 + vertex 0.904558 1.92128 2.58698 + endloop + endfacet + facet normal -0.659964 0.275235 0.699066 + outer loop + vertex 0.905728 1.92835 2.5855 + vertex 0.903386 1.92671 2.58394 + vertex 0.904741 1.92488 2.58594 + endloop + endfacet + facet normal -0.585574 0.262566 0.766917 + outer loop + vertex 0.904741 1.92488 2.58594 + vertex 0.908181 1.92568 2.58829 + vertex 0.905728 1.92835 2.5855 + endloop + endfacet + facet normal -0.58555 0.253308 0.770043 + outer loop + vertex 0.904741 1.92488 2.58594 + vertex 0.904558 1.92128 2.58698 + vertex 0.908181 1.92568 2.58829 + endloop + endfacet + facet normal -0.583964 0.251466 0.771849 + outer loop + vertex 0.904558 1.92128 2.58698 + vertex 0.907329 1.92029 2.5894 + vertex 0.908181 1.92568 2.58829 + endloop + endfacet + facet normal -0.664798 0.293728 0.686853 + outer loop + vertex 0.903634 1.93015 2.5827 + vertex 0.903386 1.92671 2.58394 + vertex 0.905728 1.92835 2.5855 + endloop + endfacet + facet normal -0.678061 0.27204 0.682809 + outer loop + vertex 0.906096 1.93255 2.58419 + vertex 0.903634 1.93015 2.5827 + vertex 0.905728 1.92835 2.5855 + endloop + endfacet + facet normal -0.604038 0.28474 0.744353 + outer loop + vertex 0.905728 1.92835 2.5855 + vertex 0.908902 1.93127 2.58696 + vertex 0.906096 1.93255 2.58419 + endloop + endfacet + facet normal -0.58921 0.257952 0.765698 + outer loop + vertex 0.908181 1.92568 2.58829 + vertex 0.908902 1.93127 2.58696 + vertex 0.905728 1.92835 2.5855 + endloop + endfacet + facet normal -0.723859 0.31801 0.612289 + outer loop + vertex 0.906123 1.93742 2.58212 + vertex 0.903309 1.93622 2.57942 + vertex 0.904126 1.9337 2.58169 + endloop + endfacet + facet normal -0.684318 0.285918 0.67079 + outer loop + vertex 0.904126 1.9337 2.58169 + vertex 0.903634 1.93015 2.5827 + vertex 0.906096 1.93255 2.58419 + endloop + endfacet + facet normal -0.682704 0.289208 0.671025 + outer loop + vertex 0.906123 1.93742 2.58212 + vertex 0.904126 1.9337 2.58169 + vertex 0.906096 1.93255 2.58419 + endloop + endfacet + facet normal -0.642005 0.303115 0.704238 + outer loop + vertex 0.906123 1.93742 2.58212 + vertex 0.906096 1.93255 2.58419 + vertex 0.908795 1.93553 2.58537 + endloop + endfacet + facet normal -0.683511 0.226713 0.69384 + outer loop + vertex 0.906123 1.93742 2.58212 + vertex 0.908795 1.93553 2.58537 + vertex 0.908557 1.9381 2.5843 + endloop + endfacet + facet normal -0.614313 0.262092 0.744263 + outer loop + vertex 0.908795 1.93553 2.58537 + vertex 0.906096 1.93255 2.58419 + vertex 0.908902 1.93127 2.58696 + endloop + endfacet + facet normal -0.724068 0.31088 0.615695 + outer loop + vertex 0.903746 1.94008 2.57798 + vertex 0.903309 1.93622 2.57942 + vertex 0.906123 1.93742 2.58212 + endloop + endfacet + facet normal -0.742801 0.281398 0.607504 + outer loop + vertex 0.906357 1.94323 2.57972 + vertex 0.903746 1.94008 2.57798 + vertex 0.906123 1.93742 2.58212 + endloop + endfacet + facet normal -0.692438 0.299582 0.656339 + outer loop + vertex 0.906123 1.93742 2.58212 + vertex 0.909189 1.94142 2.58353 + vertex 0.906357 1.94323 2.57972 + endloop + endfacet + facet normal -0.681737 0.285229 0.673706 + outer loop + vertex 0.908557 1.9381 2.5843 + vertex 0.909189 1.94142 2.58353 + vertex 0.906123 1.93742 2.58212 + endloop + endfacet + facet normal -0.77617 0.299759 0.554711 + outer loop + vertex 0.905108 1.94694 2.57629 + vertex 0.903216 1.94612 2.57409 + vertex 0.904059 1.94377 2.57654 + endloop + endfacet + facet normal -0.749787 0.295789 0.591885 + outer loop + vertex 0.904059 1.94377 2.57654 + vertex 0.903746 1.94008 2.57798 + vertex 0.906357 1.94323 2.57972 + endloop + endfacet + facet normal -0.750364 0.294071 0.59201 + outer loop + vertex 0.904059 1.94377 2.57654 + vertex 0.906357 1.94323 2.57972 + vertex 0.905108 1.94694 2.57629 + endloop + endfacet + facet normal -0.757683 0.28643 0.586409 + outer loop + vertex 0.905108 1.94694 2.57629 + vertex 0.906357 1.94323 2.57972 + vertex 0.907477 1.94796 2.57886 + endloop + endfacet + facet normal -0.708664 0.285524 0.645191 + outer loop + vertex 0.906357 1.94323 2.57972 + vertex 0.909578 1.94622 2.58193 + vertex 0.907477 1.94796 2.57886 + endloop + endfacet + facet normal -0.704857 0.274996 0.653877 + outer loop + vertex 0.909189 1.94142 2.58353 + vertex 0.909578 1.94622 2.58193 + vertex 0.906357 1.94323 2.57972 + endloop + endfacet + facet normal -0.77581 0.304355 0.552709 + outer loop + vertex 0.903688 1.94968 2.57279 + vertex 0.903216 1.94612 2.57409 + vertex 0.905108 1.94694 2.57629 + endloop + endfacet + facet normal -0.776753 0.303073 0.552088 + outer loop + vertex 0.906092 1.95153 2.57516 + vertex 0.903688 1.94968 2.57279 + vertex 0.905108 1.94694 2.57629 + endloop + endfacet + facet normal -0.718857 0.29393 0.629961 + outer loop + vertex 0.908383 1.95133 2.57831 + vertex 0.907477 1.94796 2.57886 + vertex 0.909801 1.9498 2.58065 + endloop + endfacet + facet normal -0.764063 0.29689 0.572769 + outer loop + vertex 0.908383 1.95133 2.57831 + vertex 0.906092 1.95153 2.57516 + vertex 0.907477 1.94796 2.57886 + endloop + endfacet + facet normal -0.756755 0.305217 0.578071 + outer loop + vertex 0.906092 1.95153 2.57516 + vertex 0.905108 1.94694 2.57629 + vertex 0.907477 1.94796 2.57886 + endloop + endfacet + facet normal -0.714363 0.275329 0.643335 + outer loop + vertex 0.909801 1.9498 2.58065 + vertex 0.907477 1.94796 2.57886 + vertex 0.909578 1.94622 2.58193 + endloop + endfacet + facet normal -0.775435 0.303777 0.553552 + outer loop + vertex 0.90578 1.95758 2.57138 + vertex 0.903274 1.95608 2.56869 + vertex 0.904239 1.95348 2.57147 + endloop + endfacet + facet normal -0.776882 0.304436 0.551155 + outer loop + vertex 0.904239 1.95348 2.57147 + vertex 0.903688 1.94968 2.57279 + vertex 0.906092 1.95153 2.57516 + endloop + endfacet + facet normal -0.776963 0.304294 0.551121 + outer loop + vertex 0.90578 1.95758 2.57138 + vertex 0.904239 1.95348 2.57147 + vertex 0.906092 1.95153 2.57516 + endloop + endfacet + facet normal -0.76963 0.30932 0.558561 + outer loop + vertex 0.90578 1.95758 2.57138 + vertex 0.906092 1.95153 2.57516 + vertex 0.908063 1.95469 2.57612 + endloop + endfacet + facet normal -0.781979 0.289109 0.552199 + outer loop + vertex 0.90578 1.95758 2.57138 + vertex 0.908063 1.95469 2.57612 + vertex 0.907912 1.95736 2.57451 + endloop + endfacet + facet normal -0.762904 0.300984 0.572177 + outer loop + vertex 0.908063 1.95469 2.57612 + vertex 0.906092 1.95153 2.57516 + vertex 0.908383 1.95133 2.57831 + endloop + endfacet + facet normal -0.772245 0.30966 0.554751 + outer loop + vertex 0.904495 1.96274 2.56669 + vertex 0.902813 1.96274 2.56435 + vertex 0.903011 1.95981 2.56627 + endloop + endfacet + facet normal -0.775439 0.304802 0.552983 + outer loop + vertex 0.903011 1.95981 2.56627 + vertex 0.903274 1.95608 2.56869 + vertex 0.90578 1.95758 2.57138 + endloop + endfacet + facet normal -0.772757 0.310055 0.553816 + outer loop + vertex 0.903011 1.95981 2.56627 + vertex 0.90578 1.95758 2.57138 + vertex 0.904495 1.96274 2.56669 + endloop + endfacet + facet normal -0.774955 0.307839 0.551978 + outer loop + vertex 0.904495 1.96274 2.56669 + vertex 0.90578 1.95758 2.57138 + vertex 0.906769 1.96306 2.56971 + endloop + endfacet + facet normal -0.777873 0.307219 0.548207 + outer loop + vertex 0.90578 1.95758 2.57138 + vertex 0.908247 1.96023 2.57339 + vertex 0.906769 1.96306 2.56971 + endloop + endfacet + facet normal -0.777297 0.305208 0.550143 + outer loop + vertex 0.907912 1.95736 2.57451 + vertex 0.908247 1.96023 2.57339 + vertex 0.90578 1.95758 2.57138 + endloop + endfacet + facet normal -0.771201 0.313561 0.554012 + outer loop + vertex 0.903154 1.9656 2.56321 + vertex 0.902813 1.96274 2.56435 + vertex 0.904495 1.96274 2.56669 + endloop + endfacet + facet normal -0.775595 0.307894 0.551048 + outer loop + vertex 0.905717 1.96782 2.56558 + vertex 0.903154 1.9656 2.56321 + vertex 0.904495 1.96274 2.56669 + endloop + endfacet + facet normal -0.780173 0.306094 0.54556 + outer loop + vertex 0.907845 1.96642 2.56936 + vertex 0.906769 1.96306 2.56971 + vertex 0.908672 1.96384 2.57199 + endloop + endfacet + facet normal -0.777306 0.305626 0.549899 + outer loop + vertex 0.907845 1.96642 2.56936 + vertex 0.905717 1.96782 2.56558 + vertex 0.906769 1.96306 2.56971 + endloop + endfacet + facet normal -0.774935 0.307934 0.551953 + outer loop + vertex 0.905717 1.96782 2.56558 + vertex 0.904495 1.96274 2.56669 + vertex 0.906769 1.96306 2.56971 + endloop + endfacet + facet normal -0.780398 0.303747 0.54655 + outer loop + vertex 0.908672 1.96384 2.57199 + vertex 0.906769 1.96306 2.56971 + vertex 0.908247 1.96023 2.57339 + endloop + endfacet + facet normal -0.793807 0.307269 0.524839 + outer loop + vertex 0.904787 1.97233 2.56178 + vertex 0.903007 1.97164 2.55949 + vertex 0.903619 1.96914 2.56188 + endloop + endfacet + facet normal -0.775684 0.30848 0.550595 + outer loop + vertex 0.903619 1.96914 2.56188 + vertex 0.903154 1.9656 2.56321 + vertex 0.905717 1.96782 2.56558 + endloop + endfacet + facet normal -0.778458 0.302463 0.550018 + outer loop + vertex 0.903619 1.96914 2.56188 + vertex 0.905717 1.96782 2.56558 + vertex 0.904787 1.97233 2.56178 + endloop + endfacet + facet normal -0.773369 0.307289 0.554504 + outer loop + vertex 0.904787 1.97233 2.56178 + vertex 0.905717 1.96782 2.56558 + vertex 0.907004 1.97298 2.56451 + endloop + endfacet + facet normal -0.775498 0.307211 0.551565 + outer loop + vertex 0.905717 1.96782 2.56558 + vertex 0.908385 1.97018 2.56801 + vertex 0.907004 1.97298 2.56451 + endloop + endfacet + facet normal -0.775773 0.308887 0.550241 + outer loop + vertex 0.907845 1.96642 2.56936 + vertex 0.908385 1.97018 2.56801 + vertex 0.905717 1.96782 2.56558 + endloop + endfacet + facet normal -0.794152 0.304475 0.525945 + outer loop + vertex 0.903686 1.9753 2.5584 + vertex 0.903007 1.97164 2.55949 + vertex 0.904787 1.97233 2.56178 + endloop + endfacet + facet normal -0.793704 0.305038 0.526294 + outer loop + vertex 0.906096 1.97693 2.56109 + vertex 0.903686 1.9753 2.5584 + vertex 0.904787 1.97233 2.56178 + endloop + endfacet + facet normal -0.769138 0.314331 0.556437 + outer loop + vertex 0.908112 1.97623 2.56421 + vertex 0.907004 1.97298 2.56451 + vertex 0.908935 1.97387 2.56668 + endloop + endfacet + facet normal -0.764012 0.313286 0.564037 + outer loop + vertex 0.908112 1.97623 2.56421 + vertex 0.906096 1.97693 2.56109 + vertex 0.907004 1.97298 2.56451 + endloop + endfacet + facet normal -0.773858 0.30382 0.555732 + outer loop + vertex 0.906096 1.97693 2.56109 + vertex 0.904787 1.97233 2.56178 + vertex 0.907004 1.97298 2.56451 + endloop + endfacet + facet normal -0.769046 0.315675 0.555803 + outer loop + vertex 0.908935 1.97387 2.56668 + vertex 0.907004 1.97298 2.56451 + vertex 0.908385 1.97018 2.56801 + endloop + endfacet + facet normal -0.793397 0.289276 0.535574 + outer loop + vertex 0.904502 1.97948 2.55735 + vertex 0.903686 1.9753 2.5584 + vertex 0.906096 1.97693 2.56109 + endloop + endfacet + facet normal -0.778808 0.311441 0.544484 + outer loop + vertex 0.906499 1.9818 2.55888 + vertex 0.904502 1.97948 2.55735 + vertex 0.906096 1.97693 2.56109 + endloop + endfacet + facet normal -0.759821 0.319677 0.566109 + outer loop + vertex 0.906096 1.97693 2.56109 + vertex 0.908402 1.97975 2.56259 + vertex 0.906499 1.9818 2.55888 + endloop + endfacet + facet normal -0.760714 0.321651 0.563787 + outer loop + vertex 0.908112 1.97623 2.56421 + vertex 0.908402 1.97975 2.56259 + vertex 0.906096 1.97693 2.56109 + endloop + endfacet + facet normal -0.888046 0.365512 0.278882 + outer loop + vertex 0.905143 1.98846 2.55055 + vertex 0.903801 1.98581 2.54976 + vertex 0.904362 1.9846 2.55313 + endloop + endfacet + facet normal -0.823403 0.420507 0.381026 + outer loop + vertex 0.906779 1.98694 2.55576 + vertex 0.905143 1.98846 2.55055 + vertex 0.904362 1.9846 2.55313 + endloop + endfacet + facet normal -0.824773 0.391037 0.40846 + outer loop + vertex 0.905009 1.98292 2.55604 + vertex 0.906779 1.98694 2.55576 + vertex 0.904362 1.9846 2.55313 + endloop + endfacet + facet normal -0.781412 0.319189 0.536203 + outer loop + vertex 0.905009 1.98292 2.55604 + vertex 0.904502 1.97948 2.55735 + vertex 0.906499 1.9818 2.55888 + endloop + endfacet + facet normal -0.754755 0.369469 0.542068 + outer loop + vertex 0.906779 1.98694 2.55576 + vertex 0.905009 1.98292 2.55604 + vertex 0.906499 1.9818 2.55888 + endloop + endfacet + facet normal -0.7597 0.366684 0.537027 + outer loop + vertex 0.906779 1.98694 2.55576 + vertex 0.906499 1.9818 2.55888 + vertex 0.908683 1.98423 2.56031 + endloop + endfacet + facet normal -0.796406 0.310552 0.518937 + outer loop + vertex 0.906779 1.98694 2.55576 + vertex 0.908683 1.98423 2.56031 + vertex 0.908721 1.98706 2.55867 + endloop + endfacet + facet normal -0.748906 0.337446 0.570324 + outer loop + vertex 0.908683 1.98423 2.56031 + vertex 0.906499 1.9818 2.55888 + vertex 0.908402 1.97975 2.56259 + endloop + endfacet + facet normal -0.769037 0.604168 0.208716 + outer loop + vertex 0.90595 1.99289 2.54637 + vertex 0.907239 1.995 2.545 + vertex 0.905 1.99215 2.545 + endloop + endfacet + facet normal -0.841095 0.390437 0.374324 + outer loop + vertex 0.904392 1.98873 2.5472 + vertex 0.90595 1.99289 2.54637 + vertex 0.905 1.99215 2.545 + endloop + endfacet + facet normal -0.894312 0.382888 0.231523 + outer loop + vertex 0.904392 1.98873 2.5472 + vertex 0.903801 1.98581 2.54976 + vertex 0.905143 1.98846 2.55055 + endloop + endfacet + facet normal -0.89472 0.381925 0.231536 + outer loop + vertex 0.904392 1.98873 2.5472 + vertex 0.905143 1.98846 2.55055 + vertex 0.90595 1.99289 2.54637 + endloop + endfacet + facet normal -0.906961 0.364624 0.210881 + outer loop + vertex 0.90595 1.99289 2.54637 + vertex 0.905143 1.98846 2.55055 + vertex 0.906938 1.99265 2.55103 + endloop + endfacet + facet normal -0.801205 0.326896 0.501208 + outer loop + vertex 0.908076 1.99129 2.555 + vertex 0.906779 1.98694 2.55576 + vertex 0.908768 1.98913 2.55751 + endloop + endfacet + facet normal -0.874095 0.324247 0.361693 + outer loop + vertex 0.908076 1.99129 2.555 + vertex 0.906938 1.99265 2.55103 + vertex 0.906779 1.98694 2.55576 + endloop + endfacet + facet normal -0.868872 0.33009 0.368921 + outer loop + vertex 0.906938 1.99265 2.55103 + vertex 0.905143 1.98846 2.55055 + vertex 0.906779 1.98694 2.55576 + endloop + endfacet + facet normal -0.796924 0.308498 0.519366 + outer loop + vertex 0.908768 1.98913 2.55751 + vertex 0.906779 1.98694 2.55576 + vertex 0.908721 1.98706 2.55867 + endloop + endfacet + facet normal -0.836653 0.175028 -0.519016 + outer loop + vertex 0.907239 1.995 2.545 + vertex 0.90595 1.99289 2.54637 + vertex 0.908285 2 2.545 + endloop + endfacet + facet normal -0.951749 0.300581 -0.0618446 + outer loop + vertex 0.908285 2 2.545 + vertex 0.90595 1.99289 2.54637 + vertex 0.90727 1.99707 2.54637 + endloop + endfacet + facet normal -0.931899 0.293953 0.212497 + outer loop + vertex 0.90595 1.99289 2.54637 + vertex 0.906938 1.99265 2.55103 + vertex 0.90727 1.99707 2.54637 + endloop + endfacet + facet normal -0.946155 0.265792 0.184785 + outer loop + vertex 0.90727 1.99707 2.54637 + vertex 0.906938 1.99265 2.55103 + vertex 0.908043 1.99746 2.54976 + endloop + endfacet + facet normal -0.884353 0.29774 0.359542 + outer loop + vertex 0.906938 1.99265 2.55103 + vertex 0.90873 1.9951 2.55341 + vertex 0.908043 1.99746 2.54976 + endloop + endfacet + facet normal -0.884536 0.300695 0.356621 + outer loop + vertex 0.908076 1.99129 2.555 + vertex 0.90873 1.9951 2.55341 + vertex 0.906938 1.99265 2.55103 + endloop + endfacet + facet normal -0.998485 0.0247693 0.0491339 + outer loop + vertex 0.908039 2 2.54 + vertex 0.908285 2 2.545 + vertex 0.908163 2.005 2.54 + endloop + endfacet + facet normal 0.954707 -0.198428 -0.221724 + outer loop + vertex 0.908163 2.005 2.54 + vertex 0.908285 2 2.545 + vertex 0.908137 2.00196 2.54261 + endloop + endfacet + facet normal 0.770882 -0.468552 -0.431509 + outer loop + vertex 0.908285 2 2.545 + vertex 0.90727 1.99707 2.54637 + vertex 0.908137 2.00196 2.54261 + endloop + endfacet + facet normal -0.956155 0.265128 0.124398 + outer loop + vertex 0.908137 2.00196 2.54261 + vertex 0.90727 1.99707 2.54637 + vertex 0.908243 2.00063 2.54625 + endloop + endfacet + facet normal -0.88677 0.302755 0.349254 + outer loop + vertex 0.908885 2.00058 2.54919 + vertex 0.908043 1.99746 2.54976 + vertex 0.909281 1.99878 2.55177 + endloop + endfacet + facet normal -0.934122 0.289774 0.208441 + outer loop + vertex 0.908885 2.00058 2.54919 + vertex 0.908243 2.00063 2.54625 + vertex 0.908043 1.99746 2.54976 + endloop + endfacet + facet normal -0.946454 0.26458 0.184993 + outer loop + vertex 0.908243 2.00063 2.54625 + vertex 0.90727 1.99707 2.54637 + vertex 0.908043 1.99746 2.54976 + endloop + endfacet + facet normal -0.887394 0.292233 0.356554 + outer loop + vertex 0.909281 1.99878 2.55177 + vertex 0.908043 1.99746 2.54976 + vertex 0.90873 1.9951 2.55341 + endloop + endfacet + facet normal -0.684175 0.255467 -0.683111 + outer loop + vertex 0.91 2.005 2.53816 + vertex 0.908163 2.005 2.54 + vertex 0.91 2.00992 2.54 + endloop + endfacet + facet normal -0.93844 0.284061 0.196569 + outer loop + vertex 0.91 2.00992 2.54 + vertex 0.908137 2.00196 2.54261 + vertex 0.909145 2.00488 2.5432 + endloop + endfacet + facet normal -0.870283 0.324959 0.370147 + outer loop + vertex 0.908163 2.005 2.54 + vertex 0.908137 2.00196 2.54261 + vertex 0.91 2.00992 2.54 + endloop + endfacet + facet normal -0.926718 0.32822 0.182934 + outer loop + vertex 0.909145 2.00488 2.5432 + vertex 0.908243 2.00063 2.54625 + vertex 0.909277 2.00316 2.54696 + endloop + endfacet + facet normal -0.944626 0.298539 0.136224 + outer loop + vertex 0.908137 2.00196 2.54261 + vertex 0.908243 2.00063 2.54625 + vertex 0.909145 2.00488 2.5432 + endloop + endfacet + facet normal -0.924388 0.32051 0.206835 + outer loop + vertex 0.909277 2.00316 2.54696 + vertex 0.908243 2.00063 2.54625 + vertex 0.908885 2.00058 2.54919 + endloop + endfacet + facet normal 0.577132 -0.577459 -0.577459 + outer loop + vertex 0.906891 2.11 2.49 + vertex 0.905 2.10811 2.49 + vertex 0.905 2.11 2.48811 + endloop + endfacet + facet normal 0.669791 -0.670172 -0.319765 + outer loop + vertex 0.909278 2.11 2.495 + vertex 0.905 2.10811 2.49 + vertex 0.906891 2.11 2.49 + endloop + endfacet + facet normal 0.679097 -0.65368 -0.333961 + outer loop + vertex 0.904857 2.10655 2.49277 + vertex 0.905 2.10811 2.49 + vertex 0.909278 2.11 2.495 + endloop + endfacet + facet normal 0.656256 -0.447628 -0.607418 + outer loop + vertex 0.91 2.11 2.49578 + vertex 0.904857 2.10655 2.49277 + vertex 0.909278 2.11 2.495 + endloop + endfacet + facet normal 0.63479 -0.3404 -0.693664 + outer loop + vertex 0.91 2.11 2.49578 + vertex 0.909736 2.10623 2.49739 + vertex 0.904857 2.10655 2.49277 + endloop + endfacet + facet normal 0.25884 -0.905483 -0.336308 + outer loop + vertex 0.909736 2.10623 2.49739 + vertex 0.903699 2.10476 2.4967 + vertex 0.904857 2.10655 2.49277 + endloop + endfacet + facet normal 0.256629 -0.928414 -0.268681 + outer loop + vertex 0.909736 2.10623 2.49739 + vertex 0.908548 2.10464 2.50173 + vertex 0.903699 2.10476 2.4967 + endloop + endfacet + facet normal -0.015694 -0.999842 -0.0083171 + outer loop + vertex 0.908548 2.10464 2.50173 + vertex 0.903112 2.10473 2.50121 + vertex 0.903699 2.10476 2.4967 + endloop + endfacet + facet normal -0.0203939 -0.998949 0.0410377 + outer loop + vertex 0.908548 2.10464 2.50173 + vertex 0.907966 2.10483 2.50608 + vertex 0.903112 2.10473 2.50121 + endloop + endfacet + facet normal -0.301365 -0.898496 0.319192 + outer loop + vertex 0.907966 2.10483 2.50608 + vertex 0.90302 2.10601 2.50473 + vertex 0.903112 2.10473 2.50121 + endloop + endfacet + facet normal -0.526439 -0.134346 0.839531 + outer loop + vertex 0.904343 2.10745 2.50683 + vertex 0.907425 2.10621 2.50857 + vertex 0.906645 2.10859 2.50846 + endloop + endfacet + facet normal -0.568992 -0.465916 0.677621 + outer loop + vertex 0.904343 2.10745 2.50683 + vertex 0.90302 2.10601 2.50473 + vertex 0.907425 2.10621 2.50857 + endloop + endfacet + facet normal -0.315655 -0.856891 0.407553 + outer loop + vertex 0.90302 2.10601 2.50473 + vertex 0.907966 2.10483 2.50608 + vertex 0.907425 2.10621 2.50857 + endloop + endfacet + facet normal -0.620402 -0.168549 0.765959 + outer loop + vertex 0.907425 2.10621 2.50857 + vertex 0.910335 2.10755 2.51122 + vertex 0.906645 2.10859 2.50846 + endloop + endfacet + facet normal 0.57568 -0.620223 -0.532838 + outer loop + vertex 0.91 2.11067 2.495 + vertex 0.91 2.11 2.49578 + vertex 0.909278 2.11 2.495 + endloop + endfacet + facet normal -0.531008 0.395567 0.749371 + outer loop + vertex 0.905819 2.11193 2.50618 + vertex 0.903355 2.11158 2.50462 + vertex 0.903699 2.10974 2.50583 + endloop + endfacet + facet normal -0.620722 0.160466 0.767434 + outer loop + vertex 0.903699 2.10974 2.50583 + vertex 0.904343 2.10745 2.50683 + vertex 0.906645 2.10859 2.50846 + endloop + endfacet + facet normal -0.523912 0.387225 0.758666 + outer loop + vertex 0.905819 2.11193 2.50618 + vertex 0.903699 2.10974 2.50583 + vertex 0.906645 2.10859 2.50846 + endloop + endfacet + facet normal -0.615783 0.333894 0.713671 + outer loop + vertex 0.905819 2.11193 2.50618 + vertex 0.906645 2.10859 2.50846 + vertex 0.908881 2.11029 2.50959 + endloop + endfacet + facet normal -0.590518 0.378775 0.712614 + outer loop + vertex 0.905819 2.11193 2.50618 + vertex 0.908881 2.11029 2.50959 + vertex 0.908137 2.11223 2.50794 + endloop + endfacet + facet normal -0.55413 0.188245 0.810866 + outer loop + vertex 0.908881 2.11029 2.50959 + vertex 0.906645 2.10859 2.50846 + vertex 0.910335 2.10755 2.51122 + endloop + endfacet + facet normal -0.506886 0.634307 0.583713 + outer loop + vertex 0.905442 2.11536 2.50265 + vertex 0.900808 2.11441 2.49966 + vertex 0.903222 2.11309 2.50318 + endloop + endfacet + facet normal -0.494555 0.575318 0.651479 + outer loop + vertex 0.903222 2.11309 2.50318 + vertex 0.903355 2.11158 2.50462 + vertex 0.905819 2.11193 2.50618 + endloop + endfacet + facet normal -0.46722 0.609113 0.640848 + outer loop + vertex 0.905442 2.11536 2.50265 + vertex 0.903222 2.11309 2.50318 + vertex 0.905819 2.11193 2.50618 + endloop + endfacet + facet normal -0.560936 0.563441 0.606535 + outer loop + vertex 0.905442 2.11536 2.50265 + vertex 0.905819 2.11193 2.50618 + vertex 0.908042 2.11414 2.50619 + endloop + endfacet + facet normal -0.519723 0.614181 0.59386 + outer loop + vertex 0.905442 2.11536 2.50265 + vertex 0.908042 2.11414 2.50619 + vertex 0.908286 2.11606 2.50441 + endloop + endfacet + facet normal -0.548798 0.551096 0.62858 + outer loop + vertex 0.908042 2.11414 2.50619 + vertex 0.905819 2.11193 2.50618 + vertex 0.908137 2.11223 2.50794 + endloop + endfacet + facet normal -0.547452 0.710878 0.441531 + outer loop + vertex 0.9057 2.12297 2.491 + vertex 0.902722 2.1222 2.48855 + vertex 0.903573 2.12067 2.49207 + endloop + endfacet + facet normal -0.49113 0.696712 0.522861 + outer loop + vertex 0.907515 2.12229 2.49361 + vertex 0.9057 2.12297 2.491 + vertex 0.903573 2.12067 2.49207 + endloop + endfacet + facet normal -0.485866 0.742179 0.461632 + outer loop + vertex 0.907515 2.12229 2.49361 + vertex 0.903573 2.12067 2.49207 + vertex 0.908366 2.12058 2.49726 + endloop + endfacet + facet normal -0.429111 0.804692 0.410285 + outer loop + vertex 0.908366 2.12058 2.49726 + vertex 0.903573 2.12067 2.49207 + vertex 0.903443 2.11799 2.49718 + endloop + endfacet + facet normal -0.479262 0.709308 0.516904 + outer loop + vertex 0.905442 2.11536 2.50265 + vertex 0.903443 2.11799 2.49718 + vertex 0.900808 2.11441 2.49966 + endloop + endfacet + facet normal -0.482671 0.706921 0.517003 + outer loop + vertex 0.905442 2.11536 2.50265 + vertex 0.909094 2.11799 2.50247 + vertex 0.903443 2.11799 2.49718 + endloop + endfacet + facet normal -0.420614 0.787396 0.450656 + outer loop + vertex 0.909094 2.11799 2.50247 + vertex 0.908366 2.12058 2.49726 + vertex 0.903443 2.11799 2.49718 + endloop + endfacet + facet normal -0.48777 0.713101 0.503554 + outer loop + vertex 0.909094 2.11799 2.50247 + vertex 0.905442 2.11536 2.50265 + vertex 0.908286 2.11606 2.50441 + endloop + endfacet + facet normal -0.646794 0.0939811 0.756852 + outer loop + vertex 0.9057 2.12297 2.491 + vertex 0.905 2.12618 2.49 + vertex 0.902722 2.1222 2.48855 + endloop + endfacet + facet normal -0.706319 0.0648711 0.704915 + outer loop + vertex 0.9057 2.12297 2.491 + vertex 0.91 2.12629 2.495 + vertex 0.905 2.12618 2.49 + endloop + endfacet + facet normal -0.202123 0.962503 0.180925 + outer loop + vertex 0.91 2.12629 2.495 + vertex 0.91 2.12723 2.49 + vertex 0.905 2.12618 2.49 + endloop + endfacet + facet normal -0.758505 0.264298 0.595665 + outer loop + vertex 0.91 2.12629 2.495 + vertex 0.9057 2.12297 2.491 + vertex 0.907515 2.12229 2.49361 + endloop + endfacet + facet normal -0.315125 -0.940131 -0.129806 + outer loop + vertex 0.915 0.901525 2.495 + vertex 0.914261 0.901481 2.49711 + vertex 0.91 0.903201 2.495 + endloop + endfacet + facet normal -0.12442 -0.87729 -0.463554 + outer loop + vertex 0.914261 0.901481 2.49711 + vertex 0.908908 0.902787 2.49608 + vertex 0.91 0.903201 2.495 + endloop + endfacet + facet normal -0.324207 -0.880819 0.345034 + outer loop + vertex 0.909384 0.903598 2.49932 + vertex 0.913343 0.902633 2.50057 + vertex 0.91073 0.903884 2.50131 + endloop + endfacet + facet normal -0.308833 -0.910991 0.273346 + outer loop + vertex 0.909384 0.903598 2.49932 + vertex 0.908908 0.902787 2.49608 + vertex 0.913343 0.902633 2.50057 + endloop + endfacet + facet normal -0.273268 -0.932147 0.237545 + outer loop + vertex 0.908908 0.902787 2.49608 + vertex 0.914261 0.901481 2.49711 + vertex 0.913343 0.902633 2.50057 + endloop + endfacet + facet normal -0.303275 -0.866897 0.395619 + outer loop + vertex 0.913343 0.902633 2.50057 + vertex 0.912638 0.904383 2.50387 + vertex 0.91073 0.903884 2.50131 + endloop + endfacet + facet normal -0.425562 -0.81005 0.40338 + outer loop + vertex 0.909384 0.903598 2.49932 + vertex 0.91073 0.903884 2.50131 + vertex 0.907111 0.905473 2.50069 + endloop + endfacet + facet normal -0.471305 -0.68889 0.550729 + outer loop + vertex 0.913326 0.905866 2.50681 + vertex 0.910823 0.907651 2.5069 + vertex 0.909224 0.907022 2.50474 + endloop + endfacet + facet normal -0.454351 -0.747874 0.483994 + outer loop + vertex 0.912638 0.904383 2.50387 + vertex 0.913326 0.905866 2.50681 + vertex 0.909224 0.907022 2.50474 + endloop + endfacet + facet normal -0.439998 -0.738301 0.511188 + outer loop + vertex 0.912638 0.904383 2.50387 + vertex 0.909224 0.907022 2.50474 + vertex 0.907111 0.905473 2.50069 + endloop + endfacet + facet normal -0.422075 -0.777169 0.466756 + outer loop + vertex 0.912638 0.904383 2.50387 + vertex 0.907111 0.905473 2.50069 + vertex 0.91073 0.903884 2.50131 + endloop + endfacet + facet normal -0.439785 -0.648242 0.621588 + outer loop + vertex 0.913326 0.905866 2.50681 + vertex 0.91322 0.908119 2.50908 + vertex 0.910823 0.907651 2.5069 + endloop + endfacet + facet normal -0.546458 -0.602803 0.581388 + outer loop + vertex 0.909224 0.907022 2.50474 + vertex 0.910823 0.907651 2.5069 + vertex 0.907659 0.909924 2.50628 + endloop + endfacet + facet normal -0.586626 -0.153604 0.795158 + outer loop + vertex 0.913623 0.910492 2.5112 + vertex 0.911756 0.913089 2.51033 + vertex 0.909045 0.912164 2.50815 + endloop + endfacet + facet normal -0.601941 -0.473303 0.643157 + outer loop + vertex 0.91322 0.908119 2.50908 + vertex 0.913623 0.910492 2.5112 + vertex 0.909045 0.912164 2.50815 + endloop + endfacet + facet normal -0.509101 -0.343878 0.789027 + outer loop + vertex 0.91322 0.908119 2.50908 + vertex 0.909045 0.912164 2.50815 + vertex 0.907659 0.909924 2.50628 + endloop + endfacet + facet normal -0.512405 -0.529738 0.675883 + outer loop + vertex 0.91322 0.908119 2.50908 + vertex 0.907659 0.909924 2.50628 + vertex 0.910823 0.907651 2.5069 + endloop + endfacet + facet normal -0.650322 -0.2226 0.726313 + outer loop + vertex 0.913623 0.910492 2.5112 + vertex 0.915114 0.911996 2.513 + vertex 0.911756 0.913089 2.51033 + endloop + endfacet + facet normal 0.10216 0.899342 0.425145 + outer loop + vertex 0.915 0.91758 2.5 + vertex 0.91 0.918148 2.5 + vertex 0.913704 0.916682 2.50221 + endloop + endfacet + facet normal 0.0123875 0.842822 0.538049 + outer loop + vertex 0.913704 0.916682 2.50221 + vertex 0.91 0.918148 2.5 + vertex 0.908576 0.916833 2.50209 + endloop + endfacet + facet normal 0.0254545 0.987697 0.154296 + outer loop + vertex 0.913704 0.916682 2.50221 + vertex 0.908576 0.916833 2.50209 + vertex 0.91328 0.915989 2.50671 + endloop + endfacet + facet normal -0.183121 0.917232 0.353769 + outer loop + vertex 0.91328 0.915989 2.50671 + vertex 0.908576 0.916833 2.50209 + vertex 0.908939 0.91509 2.5068 + endloop + endfacet + facet normal -0.657732 0.295853 0.692719 + outer loop + vertex 0.911756 0.913089 2.51033 + vertex 0.908939 0.91509 2.5068 + vertex 0.909045 0.912164 2.50815 + endloop + endfacet + facet normal -0.53317 0.479154 0.697239 + outer loop + vertex 0.911756 0.913089 2.51033 + vertex 0.914273 0.914383 2.51136 + vertex 0.908939 0.91509 2.5068 + endloop + endfacet + facet normal -0.182934 0.91651 0.355732 + outer loop + vertex 0.914273 0.914383 2.51136 + vertex 0.91328 0.915989 2.50671 + vertex 0.908939 0.91509 2.5068 + endloop + endfacet + facet normal -0.50688 0.358774 0.783807 + outer loop + vertex 0.914273 0.914383 2.51136 + vertex 0.911756 0.913089 2.51033 + vertex 0.915114 0.911996 2.513 + endloop + endfacet + facet normal -0.699124 -0.158464 -0.697219 + outer loop + vertex 0.915 1.00846 2.54 + vertex 0.914651 1.01 2.54 + vertex 0.915 1.01 2.53965 + endloop + endfacet + facet normal -0.3025 -0.0685647 -0.95068 + outer loop + vertex 0.914324 1.00744 2.54029 + vertex 0.914651 1.01 2.54 + vertex 0.915 1.00846 2.54 + endloop + endfacet + facet normal -0.644486 -0.00387603 -0.764607 + outer loop + vertex 0.912886 1.01149 2.54148 + vertex 0.914651 1.01 2.54 + vertex 0.914324 1.00744 2.54029 + endloop + endfacet + facet normal -0.942638 -0.333782 -0.00488525 + outer loop + vertex 0.914324 1.00744 2.54029 + vertex 0.914081 1.00809 2.54308 + vertex 0.912886 1.01149 2.54148 + endloop + endfacet + facet normal -0.759425 -0.366341 -0.537651 + outer loop + vertex 0.914651 1.01 2.54 + vertex 0.912886 1.01149 2.54148 + vertex 0.912239 1.015 2.54 + endloop + endfacet + facet normal -0.940657 -0.26335 -0.214037 + outer loop + vertex 0.912239 1.015 2.54 + vertex 0.912886 1.01149 2.54148 + vertex 0.911617 1.01602 2.54148 + endloop + endfacet + facet normal -0.95244 -0.287886 0.0999037 + outer loop + vertex 0.913478 1.01074 2.54496 + vertex 0.912886 1.01149 2.54148 + vertex 0.914081 1.00809 2.54308 + endloop + endfacet + facet normal -0.956549 -0.272417 0.103942 + outer loop + vertex 0.913478 1.01074 2.54496 + vertex 0.912173 1.01553 2.54551 + vertex 0.912886 1.01149 2.54148 + endloop + endfacet + facet normal -0.958214 -0.268215 0.0994336 + outer loop + vertex 0.912173 1.01553 2.54551 + vertex 0.911617 1.01602 2.54148 + vertex 0.912886 1.01149 2.54148 + endloop + endfacet + facet normal -0.93403 -0.27977 0.222072 + outer loop + vertex 0.913478 1.01074 2.54496 + vertex 0.913722 1.01231 2.54797 + vertex 0.912173 1.01553 2.54551 + endloop + endfacet + facet normal -0.944886 -0.195598 -0.262547 + outer loop + vertex 0.912239 1.015 2.54 + vertex 0.911617 1.01602 2.54148 + vertex 0.911204 1.02 2.54 + endloop + endfacet + facet normal -0.995083 -0.0832041 0.053735 + outer loop + vertex 0.911204 1.02 2.54 + vertex 0.911617 1.01602 2.54148 + vertex 0.911474 1.02 2.545 + endloop + endfacet + facet normal -0.983003 -0.140147 0.11859 + outer loop + vertex 0.911617 1.01602 2.54148 + vertex 0.912173 1.01553 2.54551 + vertex 0.911474 1.02 2.545 + endloop + endfacet + facet normal -0.908338 -0.184538 -0.375324 + outer loop + vertex 0.911474 1.02 2.545 + vertex 0.912173 1.01553 2.54551 + vertex 0.910845 1.02062 2.54622 + endloop + endfacet + facet normal -0.934014 -0.278299 0.223983 + outer loop + vertex 0.913236 1.01542 2.54981 + vertex 0.912173 1.01553 2.54551 + vertex 0.913722 1.01231 2.54797 + endloop + endfacet + facet normal -0.930597 -0.290403 0.222833 + outer loop + vertex 0.913236 1.01542 2.54981 + vertex 0.911984 1.01996 2.5505 + vertex 0.912173 1.01553 2.54551 + endloop + endfacet + facet normal -0.939176 -0.273605 0.207576 + outer loop + vertex 0.911984 1.01996 2.5505 + vertex 0.910845 1.02062 2.54622 + vertex 0.912173 1.01553 2.54551 + endloop + endfacet + facet normal -0.891666 -0.297691 0.341044 + outer loop + vertex 0.913236 1.01542 2.54981 + vertex 0.913721 1.01734 2.55275 + vertex 0.911984 1.01996 2.5505 + endloop + endfacet + facet normal -0.907086 -0.237471 -0.347567 + outer loop + vertex 0.911474 1.02 2.545 + vertex 0.910845 1.02062 2.54622 + vertex 0.910165 1.025 2.545 + endloop + endfacet + facet normal -0.980373 -0.176612 -0.0876221 + outer loop + vertex 0.910165 1.025 2.545 + vertex 0.910845 1.02062 2.54622 + vertex 0.909998 1.02423 2.54843 + endloop + endfacet + facet normal -0.922064 -0.335184 0.193521 + outer loop + vertex 0.910845 1.02062 2.54622 + vertex 0.911984 1.01996 2.5505 + vertex 0.909998 1.02423 2.54843 + endloop + endfacet + facet normal -0.920027 -0.315023 0.233047 + outer loop + vertex 0.909998 1.02423 2.54843 + vertex 0.911984 1.01996 2.5505 + vertex 0.910973 1.02387 2.55179 + endloop + endfacet + facet normal -0.890512 -0.285837 0.353957 + outer loop + vertex 0.913414 1.02042 2.55447 + vertex 0.911984 1.01996 2.5505 + vertex 0.913721 1.01734 2.55275 + endloop + endfacet + facet normal -0.880449 -0.315694 0.353762 + outer loop + vertex 0.913414 1.02042 2.55447 + vertex 0.91221 1.02428 2.55492 + vertex 0.911984 1.01996 2.5505 + endloop + endfacet + facet normal -0.854956 -0.348312 0.384356 + outer loop + vertex 0.91221 1.02428 2.55492 + vertex 0.910973 1.02387 2.55179 + vertex 0.911984 1.01996 2.5505 + endloop + endfacet + facet normal -0.832237 -0.312833 0.457731 + outer loop + vertex 0.913414 1.02042 2.55447 + vertex 0.914075 1.02272 2.55724 + vertex 0.91221 1.02428 2.55492 + endloop + endfacet + facet normal -0.794049 -0.583527 -0.170244 + outer loop + vertex 0.910165 1.025 2.545 + vertex 0.909998 1.02423 2.54843 + vertex 0.908714 1.02679 2.54563 + endloop + endfacet + facet normal -0.691739 -0.335683 -0.639386 + outer loop + vertex 0.91 1.02534 2.545 + vertex 0.910165 1.025 2.545 + vertex 0.908714 1.02679 2.54563 + endloop + endfacet + facet normal -0.929096 -0.355947 0.100409 + outer loop + vertex 0.908677 1.02778 2.54878 + vertex 0.908714 1.02679 2.54563 + vertex 0.909998 1.02423 2.54843 + endloop + endfacet + facet normal -0.887987 -0.359439 0.286848 + outer loop + vertex 0.908677 1.02778 2.54878 + vertex 0.909998 1.02423 2.54843 + vertex 0.909942 1.02798 2.55295 + endloop + endfacet + facet normal -0.924667 -0.298743 0.2361 + outer loop + vertex 0.909942 1.02798 2.55295 + vertex 0.909998 1.02423 2.54843 + vertex 0.910973 1.02387 2.55179 + endloop + endfacet + facet normal -0.86373 -0.32539 0.384827 + outer loop + vertex 0.910973 1.02387 2.55179 + vertex 0.91221 1.02428 2.55492 + vertex 0.909942 1.02798 2.55295 + endloop + endfacet + facet normal -0.856247 -0.302933 0.418418 + outer loop + vertex 0.909942 1.02798 2.55295 + vertex 0.91221 1.02428 2.55492 + vertex 0.911774 1.02943 2.55775 + endloop + endfacet + facet normal -0.815627 -0.330559 0.47485 + outer loop + vertex 0.91221 1.02428 2.55492 + vertex 0.913626 1.02667 2.55901 + vertex 0.911774 1.02943 2.55775 + endloop + endfacet + facet normal -0.832223 -0.30282 0.46444 + outer loop + vertex 0.914075 1.02272 2.55724 + vertex 0.913626 1.02667 2.55901 + vertex 0.91221 1.02428 2.55492 + endloop + endfacet + facet normal -0.881688 -0.375496 0.285709 + outer loop + vertex 0.908677 1.02778 2.54878 + vertex 0.909942 1.02798 2.55295 + vertex 0.908171 1.03041 2.55068 + endloop + endfacet + facet normal -0.882694 -0.347272 0.316627 + outer loop + vertex 0.908511 1.03211 2.5535 + vertex 0.908171 1.03041 2.55068 + vertex 0.909942 1.02798 2.55295 + endloop + endfacet + facet normal -0.835715 -0.345547 0.426822 + outer loop + vertex 0.908511 1.03211 2.5535 + vertex 0.909942 1.02798 2.55295 + vertex 0.90984 1.0335 2.55722 + endloop + endfacet + facet normal -0.838259 -0.343195 0.42372 + outer loop + vertex 0.90984 1.0335 2.55722 + vertex 0.909942 1.02798 2.55295 + vertex 0.911774 1.02943 2.55775 + endloop + endfacet + facet normal -0.809173 -0.317272 0.494548 + outer loop + vertex 0.913194 1.03036 2.56067 + vertex 0.911774 1.02943 2.55775 + vertex 0.913626 1.02667 2.55901 + endloop + endfacet + facet normal -0.807113 -0.321798 0.494991 + outer loop + vertex 0.913194 1.03036 2.56067 + vertex 0.912253 1.03403 2.56152 + vertex 0.911774 1.02943 2.55775 + endloop + endfacet + facet normal -0.8088 -0.320207 0.493265 + outer loop + vertex 0.912253 1.03403 2.56152 + vertex 0.90984 1.0335 2.55722 + vertex 0.911774 1.02943 2.55775 + endloop + endfacet + facet normal -0.78568 -0.323777 0.527139 + outer loop + vertex 0.913194 1.03036 2.56067 + vertex 0.913943 1.03211 2.56286 + vertex 0.912253 1.03403 2.56152 + endloop + endfacet + facet normal -0.837361 -0.342313 0.426202 + outer loop + vertex 0.908511 1.03211 2.5535 + vertex 0.90984 1.0335 2.55722 + vertex 0.908071 1.03525 2.55515 + endloop + endfacet + facet normal -0.837203 -0.334578 0.432607 + outer loop + vertex 0.908583 1.03749 2.55788 + vertex 0.908071 1.03525 2.55515 + vertex 0.90984 1.0335 2.55722 + endloop + endfacet + facet normal -0.8046 -0.333902 0.491048 + outer loop + vertex 0.908583 1.03749 2.55788 + vertex 0.90984 1.0335 2.55722 + vertex 0.910183 1.03891 2.56147 + endloop + endfacet + facet normal -0.803565 -0.33481 0.492123 + outer loop + vertex 0.910183 1.03891 2.56147 + vertex 0.90984 1.0335 2.55722 + vertex 0.912253 1.03403 2.56152 + endloop + endfacet + facet normal -0.784598 -0.320192 0.530927 + outer loop + vertex 0.914482 1.03463 2.56518 + vertex 0.912253 1.03403 2.56152 + vertex 0.913943 1.03211 2.56286 + endloop + endfacet + facet normal -0.780338 -0.331607 0.530198 + outer loop + vertex 0.914482 1.03463 2.56518 + vertex 0.912895 1.03861 2.56533 + vertex 0.912253 1.03403 2.56152 + endloop + endfacet + facet normal -0.785643 -0.326808 0.52532 + outer loop + vertex 0.912895 1.03861 2.56533 + vertex 0.910183 1.03891 2.56147 + vertex 0.912253 1.03403 2.56152 + endloop + endfacet + facet normal -0.772576 -0.329012 0.543026 + outer loop + vertex 0.914482 1.03463 2.56518 + vertex 0.915428 1.03753 2.56828 + vertex 0.912895 1.03861 2.56533 + endloop + endfacet + facet normal -0.804839 -0.333438 0.490971 + outer loop + vertex 0.908583 1.03749 2.55788 + vertex 0.910183 1.03891 2.56147 + vertex 0.908204 1.04067 2.55942 + endloop + endfacet + facet normal -0.804717 -0.33168 0.492361 + outer loop + vertex 0.90872 1.04331 2.56204 + vertex 0.908204 1.04067 2.55942 + vertex 0.910183 1.03891 2.56147 + endloop + endfacet + facet normal -0.78534 -0.329364 0.524176 + outer loop + vertex 0.90872 1.04331 2.56204 + vertex 0.910183 1.03891 2.56147 + vertex 0.911103 1.04429 2.56622 + endloop + endfacet + facet normal -0.784902 -0.329786 0.524567 + outer loop + vertex 0.911103 1.04429 2.56622 + vertex 0.910183 1.03891 2.56147 + vertex 0.912895 1.03861 2.56533 + endloop + endfacet + facet normal -0.772449 -0.328791 0.54334 + outer loop + vertex 0.912895 1.03861 2.56533 + vertex 0.914229 1.04136 2.56889 + vertex 0.911103 1.04429 2.56622 + endloop + endfacet + facet normal -0.772623 -0.328565 0.54323 + outer loop + vertex 0.915428 1.03753 2.56828 + vertex 0.914229 1.04136 2.56889 + vertex 0.912895 1.03861 2.56533 + endloop + endfacet + facet normal -0.786761 -0.325941 0.524185 + outer loop + vertex 0.907398 1.04808 2.56302 + vertex 0.90872 1.04331 2.56204 + vertex 0.911103 1.04429 2.56622 + endloop + endfacet + facet normal -0.789425 -0.339159 0.511645 + outer loop + vertex 0.909437 1.04968 2.56722 + vertex 0.907398 1.04808 2.56302 + vertex 0.911103 1.04429 2.56622 + endloop + endfacet + facet normal -0.770758 -0.320091 0.550884 + outer loop + vertex 0.914206 1.04456 2.57072 + vertex 0.911103 1.04429 2.56622 + vertex 0.914229 1.04136 2.56889 + endloop + endfacet + facet normal -0.765193 -0.337693 0.548126 + outer loop + vertex 0.914206 1.04456 2.57072 + vertex 0.912094 1.04852 2.57021 + vertex 0.911103 1.04429 2.56622 + endloop + endfacet + facet normal -0.764532 -0.338342 0.54865 + outer loop + vertex 0.912094 1.04852 2.57021 + vertex 0.909437 1.04968 2.56722 + vertex 0.911103 1.04429 2.56622 + endloop + endfacet + facet normal -0.748269 -0.32477 0.578462 + outer loop + vertex 0.914206 1.04456 2.57072 + vertex 0.915146 1.04737 2.57351 + vertex 0.912094 1.04852 2.57021 + endloop + endfacet + facet normal -0.782878 -0.351688 0.513243 + outer loop + vertex 0.907398 1.04808 2.56302 + vertex 0.909437 1.04968 2.56722 + vertex 0.907477 1.05185 2.56572 + endloop + endfacet + facet normal -0.780261 -0.342196 0.523541 + outer loop + vertex 0.908584 1.0528 2.56799 + vertex 0.907477 1.05185 2.56572 + vertex 0.909437 1.04968 2.56722 + endloop + endfacet + facet normal -0.764848 -0.343303 0.545115 + outer loop + vertex 0.908584 1.0528 2.56799 + vertex 0.909437 1.04968 2.56722 + vertex 0.91034 1.05179 2.56982 + endloop + endfacet + facet normal -0.763895 -0.344459 0.545722 + outer loop + vertex 0.91034 1.05179 2.56982 + vertex 0.909437 1.04968 2.56722 + vertex 0.912094 1.04852 2.57021 + endloop + endfacet + facet normal -0.74942 -0.333513 0.57196 + outer loop + vertex 0.912094 1.04852 2.57021 + vertex 0.91269 1.0524 2.57326 + vertex 0.91034 1.05179 2.56982 + endloop + endfacet + facet normal -0.747213 -0.335298 0.573801 + outer loop + vertex 0.915146 1.04737 2.57351 + vertex 0.91269 1.0524 2.57326 + vertex 0.912094 1.04852 2.57021 + endloop + endfacet + facet normal -0.765084 -0.334703 0.55011 + outer loop + vertex 0.908584 1.0528 2.56799 + vertex 0.91034 1.05179 2.56982 + vertex 0.909328 1.05485 2.57028 + endloop + endfacet + facet normal -0.73008 -0.335238 0.595481 + outer loop + vertex 0.91352 1.05563 2.57605 + vertex 0.911648 1.05968 2.57604 + vertex 0.910537 1.05724 2.5733 + endloop + endfacet + facet normal -0.730027 -0.330858 0.597992 + outer loop + vertex 0.91269 1.0524 2.57326 + vertex 0.91352 1.05563 2.57605 + vertex 0.910537 1.05724 2.5733 + endloop + endfacet + facet normal -0.750302 -0.339566 0.567223 + outer loop + vertex 0.91269 1.0524 2.57326 + vertex 0.910537 1.05724 2.5733 + vertex 0.909328 1.05485 2.57028 + endloop + endfacet + facet normal -0.749665 -0.33287 0.572013 + outer loop + vertex 0.91269 1.0524 2.57326 + vertex 0.909328 1.05485 2.57028 + vertex 0.91034 1.05179 2.56982 + endloop + endfacet + facet normal -0.697052 -0.319844 0.641731 + outer loop + vertex 0.91352 1.05563 2.57605 + vertex 0.914717 1.05798 2.57853 + vertex 0.911648 1.05968 2.57604 + endloop + endfacet + facet normal -0.737511 -0.326816 0.590989 + outer loop + vertex 0.909113 1.06127 2.57376 + vertex 0.910537 1.05724 2.5733 + vertex 0.911648 1.05968 2.57604 + endloop + endfacet + facet normal -0.73803 -0.336093 0.58511 + outer loop + vertex 0.910426 1.06226 2.57598 + vertex 0.909113 1.06127 2.57376 + vertex 0.911648 1.05968 2.57604 + endloop + endfacet + facet normal -0.701176 -0.317266 0.63851 + outer loop + vertex 0.911648 1.05968 2.57604 + vertex 0.912389 1.06289 2.57845 + vertex 0.910426 1.06226 2.57598 + endloop + endfacet + facet normal -0.697095 -0.320386 0.641413 + outer loop + vertex 0.914717 1.05798 2.57853 + vertex 0.912389 1.06289 2.57845 + vertex 0.911648 1.05968 2.57604 + endloop + endfacet + facet normal -0.749483 -0.314732 0.582425 + outer loop + vertex 0.909113 1.06127 2.57376 + vertex 0.910426 1.06226 2.57598 + vertex 0.909132 1.06458 2.57557 + endloop + endfacet + facet normal -0.689936 -0.311285 0.653522 + outer loop + vertex 0.912649 1.06632 2.58038 + vertex 0.911613 1.06956 2.58083 + vertex 0.910243 1.06735 2.57833 + endloop + endfacet + facet normal -0.689971 -0.314389 0.651997 + outer loop + vertex 0.912389 1.06289 2.57845 + vertex 0.912649 1.06632 2.58038 + vertex 0.910243 1.06735 2.57833 + endloop + endfacet + facet normal -0.715541 -0.327657 0.616962 + outer loop + vertex 0.912389 1.06289 2.57845 + vertex 0.910243 1.06735 2.57833 + vertex 0.909132 1.06458 2.57557 + endloop + endfacet + facet normal -0.713633 -0.284767 0.640028 + outer loop + vertex 0.912389 1.06289 2.57845 + vertex 0.909132 1.06458 2.57557 + vertex 0.910426 1.06226 2.57598 + endloop + endfacet + facet normal -0.631701 -0.30114 0.714331 + outer loop + vertex 0.912649 1.06632 2.58038 + vertex 0.914657 1.06715 2.5825 + vertex 0.911613 1.06956 2.58083 + endloop + endfacet + facet normal -0.695106 -0.305149 0.650931 + outer loop + vertex 0.909053 1.07118 2.57886 + vertex 0.910243 1.06735 2.57833 + vertex 0.911613 1.06956 2.58083 + endloop + endfacet + facet normal -0.696728 -0.316337 0.643818 + outer loop + vertex 0.91065 1.07204 2.581 + vertex 0.909053 1.07118 2.57886 + vertex 0.911613 1.06956 2.58083 + endloop + endfacet + facet normal -0.635421 -0.297428 0.712585 + outer loop + vertex 0.911613 1.06956 2.58083 + vertex 0.913181 1.07237 2.5834 + vertex 0.91065 1.07204 2.581 + endloop + endfacet + facet normal -0.631692 -0.301118 0.714348 + outer loop + vertex 0.914657 1.06715 2.5825 + vertex 0.913181 1.07237 2.5834 + vertex 0.911613 1.06956 2.58083 + endloop + endfacet + facet normal -0.707077 -0.294569 0.642862 + outer loop + vertex 0.909053 1.07118 2.57886 + vertex 0.91065 1.07204 2.581 + vertex 0.909321 1.07445 2.58065 + endloop + endfacet + facet normal -0.622878 -0.309066 0.71868 + outer loop + vertex 0.913169 1.07657 2.58517 + vertex 0.911811 1.0802 2.58555 + vertex 0.910506 1.07745 2.58324 + endloop + endfacet + facet normal -0.622825 -0.30488 0.720512 + outer loop + vertex 0.913181 1.07237 2.5834 + vertex 0.913169 1.07657 2.58517 + vertex 0.910506 1.07745 2.58324 + endloop + endfacet + facet normal -0.658847 -0.325184 0.678363 + outer loop + vertex 0.913181 1.07237 2.5834 + vertex 0.910506 1.07745 2.58324 + vertex 0.909321 1.07445 2.58065 + endloop + endfacet + facet normal -0.647957 -0.250572 0.719281 + outer loop + vertex 0.913181 1.07237 2.5834 + vertex 0.909321 1.07445 2.58065 + vertex 0.91065 1.07204 2.581 + endloop + endfacet + facet normal -0.544951 -0.287154 0.787763 + outer loop + vertex 0.913169 1.07657 2.58517 + vertex 0.915524 1.07806 2.58734 + vertex 0.911811 1.0802 2.58555 + endloop + endfacet + facet normal -0.637674 -0.295794 0.711251 + outer loop + vertex 0.908987 1.08167 2.58363 + vertex 0.910506 1.07745 2.58324 + vertex 0.911811 1.0802 2.58555 + endloop + endfacet + facet normal -0.64024 -0.313955 0.701088 + outer loop + vertex 0.910459 1.08349 2.58579 + vertex 0.908987 1.08167 2.58363 + vertex 0.911811 1.0802 2.58555 + endloop + endfacet + facet normal -0.561961 -0.287148 0.775723 + outer loop + vertex 0.911811 1.0802 2.58555 + vertex 0.913068 1.08311 2.58754 + vertex 0.910459 1.08349 2.58579 + endloop + endfacet + facet normal -0.547985 -0.297377 0.781844 + outer loop + vertex 0.915524 1.07806 2.58734 + vertex 0.913068 1.08311 2.58754 + vertex 0.911811 1.0802 2.58555 + endloop + endfacet + facet normal -0.654898 -0.295475 0.695559 + outer loop + vertex 0.908987 1.08167 2.58363 + vertex 0.910459 1.08349 2.58579 + vertex 0.908562 1.08508 2.58468 + endloop + endfacet + facet normal -0.639189 -0.256132 0.725144 + outer loop + vertex 0.910459 1.08349 2.58579 + vertex 0.910456 1.08665 2.5869 + vertex 0.908562 1.08508 2.58468 + endloop + endfacet + facet normal -0.56274 -0.275199 0.77948 + outer loop + vertex 0.910459 1.08349 2.58579 + vertex 0.913068 1.08311 2.58754 + vertex 0.910456 1.08665 2.5869 + endloop + endfacet + facet normal -0.548152 -0.261753 0.794364 + outer loop + vertex 0.913068 1.08311 2.58754 + vertex 0.913723 1.08726 2.58936 + vertex 0.910456 1.08665 2.5869 + endloop + endfacet + facet normal -0.555869 -0.274531 0.784629 + outer loop + vertex 0.913287 1.09131 2.59044 + vertex 0.911571 1.09517 2.59057 + vertex 0.9099 1.09158 2.58813 + endloop + endfacet + facet normal -0.556403 -0.269404 0.786026 + outer loop + vertex 0.913287 1.09131 2.59044 + vertex 0.9099 1.09158 2.58813 + vertex 0.913723 1.08726 2.58936 + endloop + endfacet + facet normal -0.548628 -0.260095 0.794581 + outer loop + vertex 0.913723 1.08726 2.58936 + vertex 0.9099 1.09158 2.58813 + vertex 0.910456 1.08665 2.5869 + endloop + endfacet + facet normal -0.482754 -0.244106 0.841047 + outer loop + vertex 0.913287 1.09131 2.59044 + vertex 0.915725 1.093 2.59232 + vertex 0.911571 1.09517 2.59057 + endloop + endfacet + facet normal -0.575905 -0.258957 0.775419 + outer loop + vertex 0.907316 1.09782 2.5883 + vertex 0.9099 1.09158 2.58813 + vertex 0.911571 1.09517 2.59057 + endloop + endfacet + facet normal -0.582689 -0.28083 0.762632 + outer loop + vertex 0.910109 1.09909 2.5909 + vertex 0.907316 1.09782 2.5883 + vertex 0.911571 1.09517 2.59057 + endloop + endfacet + facet normal -0.508245 -0.257939 0.821678 + outer loop + vertex 0.911571 1.09517 2.59057 + vertex 0.913264 1.09814 2.59255 + vertex 0.910109 1.09909 2.5909 + endloop + endfacet + facet normal -0.49141 -0.271461 0.827541 + outer loop + vertex 0.915725 1.093 2.59232 + vertex 0.913264 1.09814 2.59255 + vertex 0.911571 1.09517 2.59057 + endloop + endfacet + facet normal -0.582739 -0.280724 0.762633 + outer loop + vertex 0.907316 1.09782 2.5883 + vertex 0.910109 1.09909 2.5909 + vertex 0.90796 1.10164 2.59019 + endloop + endfacet + facet normal -0.546986 -0.239611 0.802117 + outer loop + vertex 0.910109 1.09909 2.5909 + vertex 0.910504 1.10284 2.59229 + vertex 0.90796 1.10164 2.59019 + endloop + endfacet + facet normal -0.507605 -0.251845 0.823961 + outer loop + vertex 0.910109 1.09909 2.5909 + vertex 0.913264 1.09814 2.59255 + vertex 0.910504 1.10284 2.59229 + endloop + endfacet + facet normal -0.481224 -0.235204 0.844454 + outer loop + vertex 0.913264 1.09814 2.59255 + vertex 0.914493 1.10177 2.59426 + vertex 0.910504 1.10284 2.59229 + endloop + endfacet + facet normal -0.482021 -0.243247 0.841717 + outer loop + vertex 0.914493 1.10177 2.59426 + vertex 0.912214 1.10688 2.59443 + vertex 0.910504 1.10284 2.59229 + endloop + endfacet + facet normal -0.49632 -0.234132 0.835972 + outer loop + vertex 0.910504 1.10284 2.59229 + vertex 0.912214 1.10688 2.59443 + vertex 0.908739 1.10737 2.59251 + endloop + endfacet + facet normal -0.496191 -0.244102 0.833192 + outer loop + vertex 0.912214 1.10688 2.59443 + vertex 0.908408 1.11215 2.59371 + vertex 0.908739 1.10737 2.59251 + endloop + endfacet + facet normal -0.515662 -0.0816829 0.852889 + outer loop + vertex 0.912982 1.20078 2.61525 + vertex 0.913038 1.2036 2.61556 + vertex 0.910219 1.2026 2.61376 + endloop + endfacet + facet normal -0.525242 -0.102984 0.844698 + outer loop + vertex 0.912982 1.20078 2.61525 + vertex 0.910219 1.2026 2.61376 + vertex 0.911962 1.19714 2.61417 + endloop + endfacet + facet normal -0.601813 -0.0737498 0.795225 + outer loop + vertex 0.912982 1.20078 2.61525 + vertex 0.915113 1.20161 2.61694 + vertex 0.913038 1.2036 2.61556 + endloop + endfacet + facet normal -0.596018 -0.0729099 0.799654 + outer loop + vertex 0.913038 1.2036 2.61556 + vertex 0.914852 1.20549 2.61708 + vertex 0.911947 1.20681 2.61504 + endloop + endfacet + facet normal -0.527167 -0.0416057 0.848742 + outer loop + vertex 0.913038 1.2036 2.61556 + vertex 0.911947 1.20681 2.61504 + vertex 0.910219 1.2026 2.61376 + endloop + endfacet + facet normal -0.496001 -0.0597297 0.866265 + outer loop + vertex 0.910219 1.2026 2.61376 + vertex 0.911947 1.20681 2.61504 + vertex 0.907831 1.20815 2.61277 + endloop + endfacet + facet normal -0.598846 -0.0687825 0.797905 + outer loop + vertex 0.914852 1.20549 2.61708 + vertex 0.913038 1.2036 2.61556 + vertex 0.915113 1.20161 2.61694 + endloop + endfacet + facet normal -0.491352 -0.0389275 0.870091 + outer loop + vertex 0.911947 1.20681 2.61504 + vertex 0.911392 1.21135 2.61492 + vertex 0.907831 1.20815 2.61277 + endloop + endfacet + facet normal -0.502164 -0.0231302 0.864463 + outer loop + vertex 0.907831 1.20815 2.61277 + vertex 0.911392 1.21135 2.61492 + vertex 0.908516 1.21224 2.61328 + endloop + endfacet + facet normal -0.518469 -0.105421 0.848573 + outer loop + vertex 0.911392 1.21135 2.61492 + vertex 0.90895 1.21601 2.61401 + vertex 0.908516 1.21224 2.61328 + endloop + endfacet + facet normal -0.551417 -0.178012 0.815016 + outer loop + vertex 0.913582 1.22303 2.6181 + vertex 0.9137 1.22732 2.61912 + vertex 0.910492 1.22784 2.61706 + endloop + endfacet + facet normal -0.551361 -0.17416 0.815886 + outer loop + vertex 0.9137 1.22732 2.61912 + vertex 0.912116 1.23192 2.61903 + vertex 0.910492 1.22784 2.61706 + endloop + endfacet + facet normal -0.538969 -0.182214 0.822381 + outer loop + vertex 0.910492 1.22784 2.61706 + vertex 0.912116 1.23192 2.61903 + vertex 0.908859 1.23242 2.61701 + endloop + endfacet + facet normal -0.554751 -0.17526 0.813348 + outer loop + vertex 0.912475 1.2358 2.62015 + vertex 0.911916 1.23967 2.6206 + vertex 0.908924 1.23734 2.61806 + endloop + endfacet + facet normal -0.556134 -0.181624 0.811004 + outer loop + vertex 0.912475 1.2358 2.62015 + vertex 0.908924 1.23734 2.61806 + vertex 0.912116 1.23192 2.61903 + endloop + endfacet + facet normal -0.538791 -0.168814 0.825352 + outer loop + vertex 0.912116 1.23192 2.61903 + vertex 0.908924 1.23734 2.61806 + vertex 0.908859 1.23242 2.61701 + endloop + endfacet + facet normal -0.603338 -0.178056 0.777354 + outer loop + vertex 0.912475 1.2358 2.62015 + vertex 0.914812 1.23668 2.62216 + vertex 0.911916 1.23967 2.6206 + endloop + endfacet + facet normal -0.568505 -0.152284 0.808463 + outer loop + vertex 0.909189 1.24218 2.61916 + vertex 0.908924 1.23734 2.61806 + vertex 0.911916 1.23967 2.6206 + endloop + endfacet + facet normal -0.580689 -0.172976 0.795537 + outer loop + vertex 0.911261 1.24431 2.62113 + vertex 0.909189 1.24218 2.61916 + vertex 0.911916 1.23967 2.6206 + endloop + endfacet + facet normal -0.60955 -0.174512 0.773301 + outer loop + vertex 0.911916 1.23967 2.6206 + vertex 0.914818 1.24155 2.62331 + vertex 0.911261 1.24431 2.62113 + endloop + endfacet + facet normal -0.605841 -0.181971 0.774495 + outer loop + vertex 0.914812 1.23668 2.62216 + vertex 0.914818 1.24155 2.62331 + vertex 0.911916 1.23967 2.6206 + endloop + endfacet + facet normal -0.576521 -0.17867 0.797308 + outer loop + vertex 0.907953 1.24638 2.6192 + vertex 0.909189 1.24218 2.61916 + vertex 0.911261 1.24431 2.62113 + endloop + endfacet + facet normal -0.573091 -0.168906 0.801896 + outer loop + vertex 0.910152 1.24896 2.62132 + vertex 0.907953 1.24638 2.6192 + vertex 0.911261 1.24431 2.62113 + endloop + endfacet + facet normal -0.611277 -0.176795 0.771417 + outer loop + vertex 0.911261 1.24431 2.62113 + vertex 0.913471 1.24698 2.62349 + vertex 0.910152 1.24896 2.62132 + endloop + endfacet + facet normal -0.610794 -0.17741 0.771659 + outer loop + vertex 0.914818 1.24155 2.62331 + vertex 0.913471 1.24698 2.62349 + vertex 0.911261 1.24431 2.62113 + endloop + endfacet + facet normal -0.572191 -0.170009 0.802306 + outer loop + vertex 0.906852 1.25143 2.61949 + vertex 0.907953 1.24638 2.6192 + vertex 0.910152 1.24896 2.62132 + endloop + endfacet + facet normal -0.566001 -0.156477 0.809418 + outer loop + vertex 0.909339 1.25197 2.62133 + vertex 0.906852 1.25143 2.61949 + vertex 0.910152 1.24896 2.62132 + endloop + endfacet + facet normal -0.617856 -0.170272 0.767634 + outer loop + vertex 0.910152 1.24896 2.62132 + vertex 0.911882 1.25246 2.62349 + vertex 0.909339 1.25197 2.62133 + endloop + endfacet + facet normal -0.611084 -0.176138 0.77172 + outer loop + vertex 0.913471 1.24698 2.62349 + vertex 0.911882 1.25246 2.62349 + vertex 0.910152 1.24896 2.62132 + endloop + endfacet + facet normal -0.481546 -0.110909 0.869375 + outer loop + vertex 0.913436 1.36057 2.63932 + vertex 0.912062 1.36635 2.6393 + vertex 0.909575 1.36255 2.63744 + endloop + endfacet + facet normal -0.512432 -0.0834454 0.854664 + outer loop + vertex 0.909575 1.36255 2.63744 + vertex 0.912062 1.36635 2.6393 + vertex 0.908769 1.36666 2.63735 + endloop + endfacet + facet normal -0.491218 -0.081758 0.867191 + outer loop + vertex 0.912771 1.37064 2.6401 + vertex 0.912119 1.37467 2.64011 + vertex 0.909519 1.37105 2.6383 + endloop + endfacet + facet normal -0.491217 -0.081735 0.867194 + outer loop + vertex 0.912771 1.37064 2.6401 + vertex 0.909519 1.37105 2.6383 + vertex 0.912062 1.36635 2.6393 + endloop + endfacet + facet normal -0.512748 -0.0963506 0.853115 + outer loop + vertex 0.912062 1.36635 2.6393 + vertex 0.909519 1.37105 2.6383 + vertex 0.908769 1.36666 2.63735 + endloop + endfacet + facet normal -0.306536 -0.052062 0.950434 + outer loop + vertex 0.912771 1.37064 2.6401 + vertex 0.915928 1.37305 2.64125 + vertex 0.912119 1.37467 2.64011 + endloop + endfacet + facet normal -0.494531 -0.0785754 0.865601 + outer loop + vertex 0.908848 1.37647 2.63841 + vertex 0.909519 1.37105 2.6383 + vertex 0.912119 1.37467 2.64011 + endloop + endfacet + facet normal -0.495723 -0.0816565 0.864634 + outer loop + vertex 0.911564 1.37951 2.64025 + vertex 0.908848 1.37647 2.63841 + vertex 0.912119 1.37467 2.64011 + endloop + endfacet + facet normal -0.326881 -0.0645327 0.942859 + outer loop + vertex 0.912119 1.37467 2.64011 + vertex 0.915144 1.37822 2.64141 + vertex 0.911564 1.37951 2.64025 + endloop + endfacet + facet normal -0.315183 -0.0756242 0.946013 + outer loop + vertex 0.915928 1.37305 2.64125 + vertex 0.915144 1.37822 2.64141 + vertex 0.912119 1.37467 2.64011 + endloop + endfacet + facet normal -0.505675 -0.0698823 0.859889 + outer loop + vertex 0.908406 1.38149 2.63856 + vertex 0.908848 1.37647 2.63841 + vertex 0.911564 1.37951 2.64025 + endloop + endfacet + facet normal -0.504668 -0.0676152 0.860661 + outer loop + vertex 0.911207 1.38447 2.64043 + vertex 0.908406 1.38149 2.63856 + vertex 0.911564 1.37951 2.64025 + endloop + endfacet + facet normal -0.334231 -0.0582856 0.940687 + outer loop + vertex 0.911564 1.37951 2.64025 + vertex 0.91478 1.38313 2.64162 + vertex 0.911207 1.38447 2.64043 + endloop + endfacet + facet normal -0.327129 -0.0653521 0.942717 + outer loop + vertex 0.915144 1.37822 2.64141 + vertex 0.91478 1.38313 2.64162 + vertex 0.911564 1.37951 2.64025 + endloop + endfacet + facet normal -0.509195 -0.061947 0.858419 + outer loop + vertex 0.908019 1.38661 2.6387 + vertex 0.908406 1.38149 2.63856 + vertex 0.911207 1.38447 2.64043 + endloop + endfacet + facet normal -0.508075 -0.0596163 0.859247 + outer loop + vertex 0.910903 1.38961 2.64061 + vertex 0.908019 1.38661 2.6387 + vertex 0.911207 1.38447 2.64043 + endloop + endfacet + facet normal -0.339349 -0.0523557 0.939202 + outer loop + vertex 0.911207 1.38447 2.64043 + vertex 0.914585 1.3881 2.64186 + vertex 0.910903 1.38961 2.64061 + endloop + endfacet + facet normal -0.334093 -0.0578503 0.940763 + outer loop + vertex 0.91478 1.38313 2.64162 + vertex 0.914585 1.3881 2.64186 + vertex 0.911207 1.38447 2.64043 + endloop + endfacet + facet normal -0.510263 -0.0568 0.858141 + outer loop + vertex 0.907434 1.39222 2.63872 + vertex 0.908019 1.38661 2.6387 + vertex 0.910903 1.38961 2.64061 + endloop + endfacet + facet normal -0.51692 -0.0691696 0.853234 + outer loop + vertex 0.910664 1.39464 2.64087 + vertex 0.907434 1.39222 2.63872 + vertex 0.910903 1.38961 2.64061 + endloop + endfacet + facet normal -0.328438 -0.0648715 0.942295 + outer loop + vertex 0.910903 1.38961 2.64061 + vertex 0.914404 1.39316 2.64207 + vertex 0.910664 1.39464 2.64087 + endloop + endfacet + facet normal -0.339469 -0.0527001 0.93914 + outer loop + vertex 0.914585 1.3881 2.64186 + vertex 0.914404 1.39316 2.64207 + vertex 0.910903 1.38961 2.64061 + endloop + endfacet + facet normal -0.494203 -0.107936 0.86262 + outer loop + vertex 0.907946 1.39668 2.63957 + vertex 0.907434 1.39222 2.63872 + vertex 0.910664 1.39464 2.64087 + endloop + endfacet + facet normal -0.473631 -0.0709374 0.877862 + outer loop + vertex 0.910222 1.39936 2.64102 + vertex 0.907946 1.39668 2.63957 + vertex 0.910664 1.39464 2.64087 + endloop + endfacet + facet normal -0.319928 -0.0586341 0.945626 + outer loop + vertex 0.910664 1.39464 2.64087 + vertex 0.914084 1.39825 2.64225 + vertex 0.910222 1.39936 2.64102 + endloop + endfacet + facet normal -0.324655 -0.0536538 0.944309 + outer loop + vertex 0.914404 1.39316 2.64207 + vertex 0.914084 1.39825 2.64225 + vertex 0.910664 1.39464 2.64087 + endloop + endfacet + facet normal -0.503505 -0.0375842 0.863174 + outer loop + vertex 0.906902 1.40104 2.63915 + vertex 0.907946 1.39668 2.63957 + vertex 0.910222 1.39936 2.64102 + endloop + endfacet + facet normal -0.52267 -0.0929447 0.847453 + outer loop + vertex 0.909495 1.40317 2.64099 + vertex 0.906902 1.40104 2.63915 + vertex 0.910222 1.39936 2.64102 + endloop + endfacet + facet normal -0.321699 -0.053844 0.94531 + outer loop + vertex 0.910222 1.39936 2.64102 + vertex 0.913455 1.40369 2.64236 + vertex 0.909495 1.40317 2.64099 + endloop + endfacet + facet normal -0.319262 -0.0558833 0.946017 + outer loop + vertex 0.914084 1.39825 2.64225 + vertex 0.913455 1.40369 2.64236 + vertex 0.910222 1.39936 2.64102 + endloop + endfacet + facet normal -0.522971 -0.092465 0.84732 + outer loop + vertex 0.906902 1.40104 2.63915 + vertex 0.909495 1.40317 2.64099 + vertex 0.907542 1.40519 2.64 + endloop + endfacet + facet normal -0.464628 -0.0174793 0.885334 + outer loop + vertex 0.909495 1.40317 2.64099 + vertex 0.91063 1.40771 2.64167 + vertex 0.907542 1.40519 2.64 + endloop + endfacet + facet normal -0.320521 -0.0625192 0.945176 + outer loop + vertex 0.909495 1.40317 2.64099 + vertex 0.913455 1.40369 2.64236 + vertex 0.91063 1.40771 2.64167 + endloop + endfacet + facet normal -0.289463 -0.0387861 0.956403 + outer loop + vertex 0.913455 1.40369 2.64236 + vertex 0.91474 1.40867 2.64295 + vertex 0.91063 1.40771 2.64167 + endloop + endfacet + facet normal -0.286839 -0.0504655 0.956649 + outer loop + vertex 0.91474 1.40867 2.64295 + vertex 0.914053 1.41263 2.64296 + vertex 0.91063 1.40771 2.64167 + endloop + endfacet + facet normal -0.302217 -0.0386564 0.952455 + outer loop + vertex 0.91063 1.40771 2.64167 + vertex 0.914053 1.41263 2.64296 + vertex 0.910042 1.41301 2.6417 + endloop + endfacet + facet normal -0.302908 -0.0481621 0.951802 + outer loop + vertex 0.914053 1.41263 2.64296 + vertex 0.913749 1.4175 2.64311 + vertex 0.910042 1.41301 2.6417 + endloop + endfacet + facet normal -0.310988 -0.0407787 0.949539 + outer loop + vertex 0.910042 1.41301 2.6417 + vertex 0.913749 1.4175 2.64311 + vertex 0.909806 1.41804 2.64184 + endloop + endfacet + facet normal -0.311158 -0.042283 0.949417 + outer loop + vertex 0.913749 1.4175 2.64311 + vertex 0.913689 1.42252 2.64331 + vertex 0.909806 1.41804 2.64184 + endloop + endfacet + facet normal -0.310642 -0.0427778 0.949564 + outer loop + vertex 0.909806 1.41804 2.64184 + vertex 0.913689 1.42252 2.64331 + vertex 0.909721 1.42305 2.64204 + endloop + endfacet + facet normal -0.310071 -0.0374337 0.949976 + outer loop + vertex 0.913689 1.42252 2.64331 + vertex 0.913738 1.42759 2.64353 + vertex 0.909721 1.42305 2.64204 + endloop + endfacet + facet normal -0.312343 -0.0352094 0.949317 + outer loop + vertex 0.909721 1.42305 2.64204 + vertex 0.913738 1.42759 2.64353 + vertex 0.909721 1.42809 2.64222 + endloop + endfacet + facet normal -0.311812 -0.0300634 0.949668 + outer loop + vertex 0.913738 1.42759 2.64353 + vertex 0.913807 1.43266 2.64371 + vertex 0.909721 1.42809 2.64222 + endloop + endfacet + facet normal -0.311668 -0.030206 0.949711 + outer loop + vertex 0.909721 1.42809 2.64222 + vertex 0.913807 1.43266 2.64371 + vertex 0.909719 1.43317 2.64238 + endloop + endfacet + facet normal -0.311833 -0.0318388 0.949603 + outer loop + vertex 0.913807 1.43266 2.64371 + vertex 0.913764 1.43764 2.64386 + vertex 0.909719 1.43317 2.64238 + endloop + endfacet + facet normal -0.3148 -0.0288625 0.948719 + outer loop + vertex 0.909719 1.43317 2.64238 + vertex 0.913764 1.43764 2.64386 + vertex 0.909671 1.4382 2.64252 + endloop + endfacet + facet normal -0.315208 -0.0324441 0.948468 + outer loop + vertex 0.913764 1.43764 2.64386 + vertex 0.913586 1.44236 2.64396 + vertex 0.909671 1.4382 2.64252 + endloop + endfacet + facet normal -0.318893 -0.0285901 0.947359 + outer loop + vertex 0.909671 1.4382 2.64252 + vertex 0.913586 1.44236 2.64396 + vertex 0.909616 1.44315 2.64265 + endloop + endfacet + facet normal -0.317964 -0.0231832 0.947819 + outer loop + vertex 0.913586 1.44236 2.64396 + vertex 0.913625 1.44701 2.64409 + vertex 0.909616 1.44315 2.64265 + endloop + endfacet + facet normal -0.316262 -0.0251447 0.948339 + outer loop + vertex 0.909616 1.44315 2.64265 + vertex 0.913625 1.44701 2.64409 + vertex 0.909585 1.4481 2.64277 + endloop + endfacet + facet normal -0.316004 -0.0240529 0.948453 + outer loop + vertex 0.913625 1.44701 2.64409 + vertex 0.913632 1.4519 2.64422 + vertex 0.909585 1.4481 2.64277 + endloop + endfacet + facet normal -0.3146 -0.0257112 0.948876 + outer loop + vertex 0.909585 1.4481 2.64277 + vertex 0.913632 1.4519 2.64422 + vertex 0.909509 1.45309 2.64288 + endloop + endfacet + facet normal -0.316568 -0.0335008 0.947978 + outer loop + vertex 0.913632 1.4519 2.64422 + vertex 0.913382 1.4569 2.64431 + vertex 0.909509 1.45309 2.64288 + endloop + endfacet + facet normal -0.323986 -0.0251201 0.945728 + outer loop + vertex 0.909509 1.45309 2.64288 + vertex 0.913382 1.4569 2.64431 + vertex 0.909433 1.4581 2.64299 + endloop + endfacet + facet normal -0.324334 -0.0264415 0.945573 + outer loop + vertex 0.913382 1.4569 2.64431 + vertex 0.913279 1.46192 2.64442 + vertex 0.909433 1.4581 2.64299 + endloop + endfacet + facet normal -0.328141 -0.022159 0.944369 + outer loop + vertex 0.909433 1.4581 2.64299 + vertex 0.913279 1.46192 2.64442 + vertex 0.909423 1.46312 2.6431 + endloop + endfacet + facet normal -0.327056 -0.0181599 0.94483 + outer loop + vertex 0.913279 1.46192 2.64442 + vertex 0.913276 1.46695 2.64451 + vertex 0.909423 1.46312 2.6431 + endloop + endfacet + facet normal -0.327502 -0.017658 0.944686 + outer loop + vertex 0.909423 1.46312 2.6431 + vertex 0.913276 1.46695 2.64451 + vertex 0.909417 1.46815 2.6432 + endloop + endfacet + facet normal -0.327601 -0.0180231 0.944644 + outer loop + vertex 0.913276 1.46695 2.64451 + vertex 0.913178 1.47196 2.64457 + vertex 0.909417 1.46815 2.6432 + endloop + endfacet + facet normal -0.325466 -0.0203778 0.945334 + outer loop + vertex 0.909417 1.46815 2.6432 + vertex 0.913178 1.47196 2.64457 + vertex 0.909262 1.47315 2.64325 + endloop + endfacet + facet normal -0.326765 -0.0253153 0.944766 + outer loop + vertex 0.913178 1.47196 2.64457 + vertex 0.912786 1.47688 2.64457 + vertex 0.909262 1.47315 2.64325 + endloop + endfacet + facet normal -0.330516 -0.0213474 0.943559 + outer loop + vertex 0.909262 1.47315 2.64325 + vertex 0.912786 1.47688 2.64457 + vertex 0.908877 1.47801 2.64323 + endloop + endfacet + facet normal -0.332926 -0.0310354 0.942442 + outer loop + vertex 0.912786 1.47688 2.64457 + vertex 0.911965 1.48102 2.64442 + vertex 0.908877 1.47801 2.64323 + endloop + endfacet + facet normal -0.347512 -0.0141578 0.937569 + outer loop + vertex 0.908877 1.47801 2.64323 + vertex 0.911965 1.48102 2.64442 + vertex 0.908507 1.48321 2.64317 + endloop + endfacet + facet normal -0.333734 0.010462 0.942609 + outer loop + vertex 0.911965 1.48102 2.64442 + vertex 0.913366 1.48561 2.64486 + vertex 0.908507 1.48321 2.64317 + endloop + endfacet + facet normal -0.307561 -0.0480496 0.950314 + outer loop + vertex 0.908507 1.48321 2.64317 + vertex 0.913366 1.48561 2.64486 + vertex 0.90989 1.48788 2.64385 + endloop + endfacet + facet normal -0.293254 -0.0237862 0.955739 + outer loop + vertex 0.913366 1.48561 2.64486 + vertex 0.912972 1.49086 2.64487 + vertex 0.90989 1.48788 2.64385 + endloop + endfacet + facet normal -0.476974 0.0556343 0.877155 + outer loop + vertex 0.907981 1.63615 2.63873 + vertex 0.90709 1.63074 2.63859 + vertex 0.910809 1.63399 2.6404 + endloop + endfacet + facet normal -0.467839 0.0706173 0.880988 + outer loop + vertex 0.911363 1.63881 2.64031 + vertex 0.907981 1.63615 2.63873 + vertex 0.910809 1.63399 2.6404 + endloop + endfacet + facet normal -0.301147 0.0527747 0.952116 + outer loop + vertex 0.910809 1.63399 2.6404 + vertex 0.914586 1.63764 2.6414 + vertex 0.911363 1.63881 2.64031 + endloop + endfacet + facet normal -0.471179 0.0761902 0.878741 + outer loop + vertex 0.908973 1.64173 2.63878 + vertex 0.907981 1.63615 2.63873 + vertex 0.911363 1.63881 2.64031 + endloop + endfacet + facet normal -0.464361 0.0833418 0.881716 + outer loop + vertex 0.912147 1.64256 2.64037 + vertex 0.908973 1.64173 2.63878 + vertex 0.911363 1.63881 2.64031 + endloop + endfacet + facet normal -0.28201 0.044113 0.958397 + outer loop + vertex 0.911363 1.63881 2.64031 + vertex 0.914774 1.64205 2.64117 + vertex 0.912147 1.64256 2.64037 + endloop + endfacet + facet normal -0.297829 0.0623228 0.952583 + outer loop + vertex 0.914586 1.63764 2.6414 + vertex 0.914774 1.64205 2.64117 + vertex 0.911363 1.63881 2.64031 + endloop + endfacet + facet normal -0.328388 0.111958 0.937884 + outer loop + vertex 0.912147 1.64256 2.64037 + vertex 0.91445 1.64518 2.64086 + vertex 0.912081 1.64602 2.63993 + endloop + endfacet + facet normal -0.46743 0.101787 0.878151 + outer loop + vertex 0.912147 1.64256 2.64037 + vertex 0.912081 1.64602 2.63993 + vertex 0.908973 1.64173 2.63878 + endloop + endfacet + facet normal -0.462954 0.097787 0.880972 + outer loop + vertex 0.908973 1.64173 2.63878 + vertex 0.912081 1.64602 2.63993 + vertex 0.909086 1.64724 2.63822 + endloop + endfacet + facet normal -0.278121 0.0638955 0.958419 + outer loop + vertex 0.91445 1.64518 2.64086 + vertex 0.912147 1.64256 2.64037 + vertex 0.914774 1.64205 2.64117 + endloop + endfacet + facet normal -0.454081 0.121865 0.882587 + outer loop + vertex 0.912081 1.64602 2.63993 + vertex 0.913146 1.65137 2.63974 + vertex 0.909086 1.64724 2.63822 + endloop + endfacet + facet normal -0.422568 0.0836249 0.902465 + outer loop + vertex 0.909086 1.64724 2.63822 + vertex 0.913146 1.65137 2.63974 + vertex 0.90941 1.65248 2.63789 + endloop + endfacet + facet normal -0.422616 0.0834502 0.902459 + outer loop + vertex 0.913146 1.65137 2.63974 + vertex 0.913283 1.65676 2.63931 + vertex 0.90941 1.65248 2.63789 + endloop + endfacet + facet normal -0.409177 0.06885 0.909854 + outer loop + vertex 0.90941 1.65248 2.63789 + vertex 0.913283 1.65676 2.63931 + vertex 0.909637 1.65763 2.6376 + endloop + endfacet + facet normal -0.407414 0.0766376 0.910022 + outer loop + vertex 0.913283 1.65676 2.63931 + vertex 0.913634 1.66202 2.63902 + vertex 0.909637 1.65763 2.6376 + endloop + endfacet + facet normal -0.397541 0.0659792 0.915209 + outer loop + vertex 0.909637 1.65763 2.6376 + vertex 0.913634 1.66202 2.63902 + vertex 0.90983 1.6627 2.63732 + endloop + endfacet + facet normal -0.396533 0.071641 0.915221 + outer loop + vertex 0.913634 1.66202 2.63902 + vertex 0.913788 1.66713 2.63869 + vertex 0.90983 1.6627 2.63732 + endloop + endfacet + facet normal -0.403289 0.07878 0.911675 + outer loop + vertex 0.90983 1.6627 2.63732 + vertex 0.913788 1.66713 2.63869 + vertex 0.909882 1.66766 2.63692 + endloop + endfacet + facet normal -0.403092 0.0801184 0.911645 + outer loop + vertex 0.913788 1.66713 2.63869 + vertex 0.913713 1.67209 2.63822 + vertex 0.909882 1.66766 2.63692 + endloop + endfacet + facet normal -0.419671 0.097151 0.902462 + outer loop + vertex 0.909882 1.66766 2.63692 + vertex 0.913713 1.67209 2.63822 + vertex 0.909587 1.67236 2.63627 + endloop + endfacet + facet normal -0.526712 0.0689043 0.847246 + outer loop + vertex 0.910149 1.67971 2.63599 + vertex 0.907838 1.67851 2.63465 + vertex 0.908607 1.67624 2.63532 + endloop + endfacet + facet normal -0.434935 0.0176832 0.900288 + outer loop + vertex 0.908607 1.67624 2.63532 + vertex 0.913119 1.67725 2.63748 + vertex 0.910149 1.67971 2.63599 + endloop + endfacet + facet normal -0.448455 0.105573 0.887549 + outer loop + vertex 0.908607 1.67624 2.63532 + vertex 0.909587 1.67236 2.63627 + vertex 0.913119 1.67725 2.63748 + endloop + endfacet + facet normal -0.421057 0.0819133 0.903328 + outer loop + vertex 0.909587 1.67236 2.63627 + vertex 0.913713 1.67209 2.63822 + vertex 0.913119 1.67725 2.63748 + endloop + endfacet + facet normal -0.545096 0.124547 0.829071 + outer loop + vertex 0.907721 1.68127 2.63416 + vertex 0.907838 1.67851 2.63465 + vertex 0.910149 1.67971 2.63599 + endloop + endfacet + facet normal -0.555739 0.103149 0.824933 + outer loop + vertex 0.910653 1.68402 2.63579 + vertex 0.907721 1.68127 2.63416 + vertex 0.910149 1.67971 2.63599 + endloop + endfacet + facet normal -0.394211 0.0884645 0.914752 + outer loop + vertex 0.910149 1.67971 2.63599 + vertex 0.914028 1.6827 2.63737 + vertex 0.910653 1.68402 2.63579 + endloop + endfacet + facet normal -0.390088 0.0820395 0.917116 + outer loop + vertex 0.913119 1.67725 2.63748 + vertex 0.914028 1.6827 2.63737 + vertex 0.910149 1.67971 2.63599 + endloop + endfacet + facet normal -0.561399 0.112148 0.819911 + outer loop + vertex 0.907941 1.6859 2.63368 + vertex 0.907721 1.68127 2.63416 + vertex 0.910653 1.68402 2.63579 + endloop + endfacet + facet normal -0.567983 0.0993824 0.817018 + outer loop + vertex 0.911008 1.68888 2.63545 + vertex 0.907941 1.6859 2.63368 + vertex 0.910653 1.68402 2.63579 + endloop + endfacet + facet normal -0.396763 0.093643 0.913132 + outer loop + vertex 0.910653 1.68402 2.63579 + vertex 0.91436 1.68764 2.63703 + vertex 0.911008 1.68888 2.63545 + endloop + endfacet + facet normal -0.393688 0.0899056 0.914837 + outer loop + vertex 0.914028 1.6827 2.63737 + vertex 0.91436 1.68764 2.63703 + vertex 0.910653 1.68402 2.63579 + endloop + endfacet + facet normal -0.568124 0.0996017 0.816893 + outer loop + vertex 0.908413 1.69104 2.63338 + vertex 0.907941 1.6859 2.63368 + vertex 0.911008 1.68888 2.63545 + endloop + endfacet + facet normal -0.573029 0.0913775 0.814425 + outer loop + vertex 0.911483 1.69382 2.63523 + vertex 0.908413 1.69104 2.63338 + vertex 0.911008 1.68888 2.63545 + endloop + endfacet + facet normal -0.396631 0.0789194 0.914579 + outer loop + vertex 0.911008 1.68888 2.63545 + vertex 0.914552 1.69256 2.63667 + vertex 0.911483 1.69382 2.63523 + endloop + endfacet + facet normal -0.400364 0.0831734 0.912574 + outer loop + vertex 0.91436 1.68764 2.63703 + vertex 0.914552 1.69256 2.63667 + vertex 0.911008 1.68888 2.63545 + endloop + endfacet + facet normal -0.575272 0.0952081 0.812402 + outer loop + vertex 0.909321 1.69681 2.63335 + vertex 0.908413 1.69104 2.63338 + vertex 0.911483 1.69382 2.63523 + endloop + endfacet + facet normal -0.580157 0.0898755 0.809531 + outer loop + vertex 0.912185 1.69772 2.6353 + vertex 0.909321 1.69681 2.63335 + vertex 0.911483 1.69382 2.63523 + endloop + endfacet + facet normal -0.378267 0.051472 0.924264 + outer loop + vertex 0.911483 1.69382 2.63523 + vertex 0.914677 1.69715 2.63635 + vertex 0.912185 1.69772 2.6353 + endloop + endfacet + facet normal -0.398397 0.0741877 0.914208 + outer loop + vertex 0.914552 1.69256 2.63667 + vertex 0.914677 1.69715 2.63635 + vertex 0.911483 1.69382 2.63523 + endloop + endfacet + facet normal -0.447636 0.136636 0.883715 + outer loop + vertex 0.912185 1.69772 2.6353 + vertex 0.914325 1.70037 2.63597 + vertex 0.912137 1.70119 2.63474 + endloop + endfacet + facet normal -0.584969 0.121517 0.801901 + outer loop + vertex 0.912185 1.69772 2.6353 + vertex 0.912137 1.70119 2.63474 + vertex 0.909321 1.69681 2.63335 + endloop + endfacet + facet normal -0.591295 0.127349 0.796337 + outer loop + vertex 0.909321 1.69681 2.63335 + vertex 0.912137 1.70119 2.63474 + vertex 0.909434 1.70231 2.63255 + endloop + endfacet + facet normal -0.374768 0.0674677 0.924661 + outer loop + vertex 0.914325 1.70037 2.63597 + vertex 0.912185 1.69772 2.6353 + vertex 0.914677 1.69715 2.63635 + endloop + endfacet + facet normal -0.58026 0.158763 0.798807 + outer loop + vertex 0.912137 1.70119 2.63474 + vertex 0.913034 1.70642 2.63435 + vertex 0.909434 1.70231 2.63255 + endloop + endfacet + facet normal -0.658293 0.0775819 0.748753 + outer loop + vertex 0.907475 1.74542 2.62421 + vertex 0.907337 1.74102 2.62454 + vertex 0.909905 1.74355 2.62654 + endloop + endfacet + facet normal -0.678738 0.0323869 0.733666 + outer loop + vertex 0.910186 1.74823 2.62659 + vertex 0.907475 1.74542 2.62421 + vertex 0.909905 1.74355 2.62654 + endloop + endfacet + facet normal -0.641022 0.029755 0.766946 + outer loop + vertex 0.909905 1.74355 2.62654 + vertex 0.912717 1.74588 2.6288 + vertex 0.910186 1.74823 2.62659 + endloop + endfacet + facet normal -0.654467 0.0586586 0.753812 + outer loop + vertex 0.912012 1.74068 2.62859 + vertex 0.912717 1.74588 2.6288 + vertex 0.909905 1.74355 2.62654 + endloop + endfacet + facet normal -0.683381 0.0408927 0.728916 + outer loop + vertex 0.907264 1.75053 2.62372 + vertex 0.907475 1.74542 2.62421 + vertex 0.910186 1.74823 2.62659 + endloop + endfacet + facet normal -0.701577 -0.00269275 0.712589 + outer loop + vertex 0.910492 1.7536 2.62691 + vertex 0.907264 1.75053 2.62372 + vertex 0.910186 1.74823 2.62659 + endloop + endfacet + facet normal -0.673845 -0.00584902 0.73885 + outer loop + vertex 0.910186 1.74823 2.62659 + vertex 0.912872 1.7504 2.62906 + vertex 0.910492 1.7536 2.62691 + endloop + endfacet + facet normal -0.66752 -0.0199334 0.744325 + outer loop + vertex 0.912717 1.74588 2.6288 + vertex 0.912872 1.7504 2.62906 + vertex 0.910186 1.74823 2.62659 + endloop + endfacet + facet normal -0.718529 0.0336806 0.694681 + outer loop + vertex 0.90768 1.75591 2.62389 + vertex 0.907264 1.75053 2.62372 + vertex 0.910492 1.7536 2.62691 + endloop + endfacet + facet normal -0.721879 0.0254844 0.69155 + outer loop + vertex 0.909839 1.75823 2.62606 + vertex 0.90768 1.75591 2.62389 + vertex 0.910492 1.7536 2.62691 + endloop + endfacet + facet normal -0.693361 -0.033072 0.719831 + outer loop + vertex 0.913234 1.75408 2.62958 + vertex 0.910492 1.7536 2.62691 + vertex 0.912872 1.7504 2.62906 + endloop + endfacet + facet normal -0.696798 0.000914201 0.717267 + outer loop + vertex 0.913234 1.75408 2.62958 + vertex 0.912456 1.75813 2.62882 + vertex 0.910492 1.7536 2.62691 + endloop + endfacet + facet normal -0.724294 0.0246819 0.689049 + outer loop + vertex 0.912456 1.75813 2.62882 + vertex 0.909839 1.75823 2.62606 + vertex 0.910492 1.7536 2.62691 + endloop + endfacet + facet normal -0.559953 0.0478502 0.827141 + outer loop + vertex 0.913234 1.75408 2.62958 + vertex 0.915882 1.75665 2.63122 + vertex 0.912456 1.75813 2.62882 + endloop + endfacet + facet normal -0.735643 0.0535416 0.67525 + outer loop + vertex 0.907913 1.76081 2.62376 + vertex 0.90768 1.75591 2.62389 + vertex 0.909839 1.75823 2.62606 + endloop + endfacet + facet normal -0.718433 0.0803787 0.690936 + outer loop + vertex 0.910885 1.76284 2.62661 + vertex 0.907913 1.76081 2.62376 + vertex 0.909839 1.75823 2.62606 + endloop + endfacet + facet normal -0.634911 0.0389962 0.7716 + outer loop + vertex 0.913315 1.76224 2.62931 + vertex 0.912456 1.75813 2.62882 + vertex 0.914883 1.76038 2.6307 + endloop + endfacet + facet normal -0.733748 0.0713806 0.675662 + outer loop + vertex 0.913315 1.76224 2.62931 + vertex 0.910885 1.76284 2.62661 + vertex 0.912456 1.75813 2.62882 + endloop + endfacet + facet normal -0.721153 0.0813471 0.687983 + outer loop + vertex 0.910885 1.76284 2.62661 + vertex 0.909839 1.75823 2.62606 + vertex 0.912456 1.75813 2.62882 + endloop + endfacet + facet normal -0.586757 -0.0439918 0.808567 + outer loop + vertex 0.914883 1.76038 2.6307 + vertex 0.912456 1.75813 2.62882 + vertex 0.915882 1.75665 2.63122 + endloop + endfacet + facet normal -0.725454 0.105831 0.680085 + outer loop + vertex 0.908336 1.76583 2.62343 + vertex 0.907913 1.76081 2.62376 + vertex 0.910885 1.76284 2.62661 + endloop + endfacet + facet normal -0.689187 0.164127 0.70575 + outer loop + vertex 0.911244 1.76851 2.62564 + vertex 0.908336 1.76583 2.62343 + vertex 0.910885 1.76284 2.62661 + endloop + endfacet + facet normal -0.693813 0.163663 0.701311 + outer loop + vertex 0.910885 1.76284 2.62661 + vertex 0.913944 1.7667 2.62874 + vertex 0.911244 1.76851 2.62564 + endloop + endfacet + facet normal -0.709105 0.187753 0.679646 + outer loop + vertex 0.913315 1.76224 2.62931 + vertex 0.913944 1.7667 2.62874 + vertex 0.910885 1.76284 2.62661 + endloop + endfacet + facet normal -0.685287 0.155077 0.711571 + outer loop + vertex 0.908769 1.77078 2.62277 + vertex 0.908336 1.76583 2.62343 + vertex 0.911244 1.76851 2.62564 + endloop + endfacet + facet normal -0.66277 0.194409 0.723146 + outer loop + vertex 0.911618 1.77337 2.62468 + vertex 0.908769 1.77078 2.62277 + vertex 0.911244 1.76851 2.62564 + endloop + endfacet + facet normal -0.650368 0.195606 0.734002 + outer loop + vertex 0.911244 1.76851 2.62564 + vertex 0.914343 1.77192 2.62748 + vertex 0.911618 1.77337 2.62468 + endloop + endfacet + facet normal -0.666402 0.222239 0.711701 + outer loop + vertex 0.913944 1.7667 2.62874 + vertex 0.914343 1.77192 2.62748 + vertex 0.911244 1.76851 2.62564 + endloop + endfacet + facet normal -0.654491 0.176384 0.735207 + outer loop + vertex 0.909181 1.77507 2.6221 + vertex 0.908769 1.77078 2.62277 + vertex 0.911618 1.77337 2.62468 + endloop + endfacet + facet normal -0.654771 0.175814 0.735094 + outer loop + vertex 0.911614 1.77766 2.62365 + vertex 0.909181 1.77507 2.6221 + vertex 0.911618 1.77337 2.62468 + endloop + endfacet + facet normal -0.630159 0.180655 0.755158 + outer loop + vertex 0.911618 1.77337 2.62468 + vertex 0.914628 1.77673 2.62639 + vertex 0.911614 1.77766 2.62365 + endloop + endfacet + facet normal -0.646251 0.205272 0.734999 + outer loop + vertex 0.914343 1.77192 2.62748 + vertex 0.914628 1.77673 2.62639 + vertex 0.911618 1.77337 2.62468 + endloop + endfacet + facet normal -0.60006 0.105864 0.792919 + outer loop + vertex 0.910894 1.78229 2.62219 + vertex 0.907139 1.78027 2.61962 + vertex 0.909263 1.77844 2.62147 + endloop + endfacet + facet normal -0.643555 0.156854 0.749156 + outer loop + vertex 0.909263 1.77844 2.62147 + vertex 0.909181 1.77507 2.6221 + vertex 0.911614 1.77766 2.62365 + endloop + endfacet + facet normal -0.64969 0.135236 0.748074 + outer loop + vertex 0.910894 1.78229 2.62219 + vertex 0.909263 1.77844 2.62147 + vertex 0.911614 1.77766 2.62365 + endloop + endfacet + facet normal -0.636382 0.140584 0.758455 + outer loop + vertex 0.910894 1.78229 2.62219 + vertex 0.911614 1.77766 2.62365 + vertex 0.914001 1.7807 2.62509 + endloop + endfacet + facet normal -0.649077 0.106215 0.753271 + outer loop + vertex 0.910894 1.78229 2.62219 + vertex 0.914001 1.7807 2.62509 + vertex 0.913404 1.78304 2.62425 + endloop + endfacet + facet normal -0.640199 0.145544 0.754295 + outer loop + vertex 0.914001 1.7807 2.62509 + vertex 0.911614 1.77766 2.62365 + vertex 0.914628 1.77673 2.62639 + endloop + endfacet + facet normal -0.610903 0.144492 0.778408 + outer loop + vertex 0.907575 1.7851 2.61906 + vertex 0.907139 1.78027 2.61962 + vertex 0.910894 1.78229 2.62219 + endloop + endfacet + facet normal -0.604824 0.154762 0.781176 + outer loop + vertex 0.910756 1.78794 2.62096 + vertex 0.907575 1.7851 2.61906 + vertex 0.910894 1.78229 2.62219 + endloop + endfacet + facet normal -0.651548 0.145658 0.744493 + outer loop + vertex 0.910894 1.78229 2.62219 + vertex 0.913366 1.78594 2.62364 + vertex 0.910756 1.78794 2.62096 + endloop + endfacet + facet normal -0.652894 0.147153 0.743017 + outer loop + vertex 0.913404 1.78304 2.62425 + vertex 0.913366 1.78594 2.62364 + vertex 0.910894 1.78229 2.62219 + endloop + endfacet + facet normal -0.604395 0.153952 0.781669 + outer loop + vertex 0.907684 1.79066 2.61805 + vertex 0.907575 1.7851 2.61906 + vertex 0.910756 1.78794 2.62096 + endloop + endfacet + facet normal -0.596338 0.166814 0.78521 + outer loop + vertex 0.911319 1.79302 2.62031 + vertex 0.907684 1.79066 2.61805 + vertex 0.910756 1.78794 2.62096 + endloop + endfacet + facet normal -0.648979 0.16714 0.74222 + outer loop + vertex 0.910756 1.78794 2.62096 + vertex 0.913658 1.79058 2.62291 + vertex 0.911319 1.79302 2.62031 + endloop + endfacet + facet normal -0.644871 0.15863 0.747648 + outer loop + vertex 0.913366 1.78594 2.62364 + vertex 0.913658 1.79058 2.62291 + vertex 0.910756 1.78794 2.62096 + endloop + endfacet + facet normal -0.599592 0.17619 0.78067 + outer loop + vertex 0.909343 1.7966 2.61799 + vertex 0.907684 1.79066 2.61805 + vertex 0.911319 1.79302 2.62031 + endloop + endfacet + facet normal -0.606033 0.170251 0.777006 + outer loop + vertex 0.91227 1.79677 2.62023 + vertex 0.909343 1.7966 2.61799 + vertex 0.911319 1.79302 2.62031 + endloop + endfacet + facet normal -0.65203 0.181066 0.736256 + outer loop + vertex 0.911319 1.79302 2.62031 + vertex 0.914035 1.79496 2.62224 + vertex 0.91227 1.79677 2.62023 + endloop + endfacet + facet normal -0.647898 0.168785 0.742792 + outer loop + vertex 0.913658 1.79058 2.62291 + vertex 0.914035 1.79496 2.62224 + vertex 0.911319 1.79302 2.62031 + endloop + endfacet + facet normal -0.655406 0.162616 0.737563 + outer loop + vertex 0.91227 1.79677 2.62023 + vertex 0.914156 1.79839 2.62155 + vertex 0.912301 1.80023 2.61949 + endloop + endfacet + facet normal -0.606012 0.170567 0.776954 + outer loop + vertex 0.91227 1.79677 2.62023 + vertex 0.912301 1.80023 2.61949 + vertex 0.909343 1.7966 2.61799 + endloop + endfacet + facet normal -0.60829 0.173422 0.774537 + outer loop + vertex 0.909343 1.7966 2.61799 + vertex 0.912301 1.80023 2.61949 + vertex 0.909581 1.80156 2.61706 + endloop + endfacet + facet normal -0.658817 0.170514 0.732724 + outer loop + vertex 0.914156 1.79839 2.62155 + vertex 0.91227 1.79677 2.62023 + vertex 0.914035 1.79496 2.62224 + endloop + endfacet + facet normal -0.495607 0.139158 0.857326 + outer loop + vertex 0.910167 1.80863 2.61606 + vertex 0.906887 1.80599 2.61459 + vertex 0.909351 1.80496 2.61619 + endloop + endfacet + facet normal -0.60201 0.160251 0.782243 + outer loop + vertex 0.909351 1.80496 2.61619 + vertex 0.91241 1.80527 2.61848 + vertex 0.910167 1.80863 2.61606 + endloop + endfacet + facet normal -0.601982 0.16111 0.782087 + outer loop + vertex 0.909351 1.80496 2.61619 + vertex 0.909581 1.80156 2.61706 + vertex 0.91241 1.80527 2.61848 + endloop + endfacet + facet normal -0.609678 0.169976 0.77421 + outer loop + vertex 0.909581 1.80156 2.61706 + vertex 0.912301 1.80023 2.61949 + vertex 0.91241 1.80527 2.61848 + endloop + endfacet + facet normal -0.502088 0.150366 0.851644 + outer loop + vertex 0.907406 1.81069 2.61407 + vertex 0.906887 1.80599 2.61459 + vertex 0.910167 1.80863 2.61606 + endloop + endfacet + facet normal -0.49618 0.159942 0.85336 + outer loop + vertex 0.911006 1.81325 2.61568 + vertex 0.907406 1.81069 2.61407 + vertex 0.910167 1.80863 2.61606 + endloop + endfacet + facet normal -0.591447 0.171855 0.787818 + outer loop + vertex 0.910167 1.80863 2.61606 + vertex 0.913373 1.81071 2.61801 + vertex 0.911006 1.81325 2.61568 + endloop + endfacet + facet normal -0.591328 0.171518 0.78798 + outer loop + vertex 0.91241 1.80527 2.61848 + vertex 0.913373 1.81071 2.61801 + vertex 0.910167 1.80863 2.61606 + endloop + endfacet + facet normal -0.498003 0.163603 0.851603 + outer loop + vertex 0.908574 1.81618 2.6137 + vertex 0.907406 1.81069 2.61407 + vertex 0.911006 1.81325 2.61568 + endloop + endfacet + facet normal -0.498347 0.16323 0.851473 + outer loop + vertex 0.911973 1.81692 2.61554 + vertex 0.908574 1.81618 2.6137 + vertex 0.911006 1.81325 2.61568 + endloop + endfacet + facet normal -0.583474 0.18342 0.791148 + outer loop + vertex 0.911006 1.81325 2.61568 + vertex 0.913934 1.81523 2.61738 + vertex 0.911973 1.81692 2.61554 + endloop + endfacet + facet normal -0.583245 0.182816 0.791457 + outer loop + vertex 0.913373 1.81071 2.61801 + vertex 0.913934 1.81523 2.61738 + vertex 0.911006 1.81325 2.61568 + endloop + endfacet + facet normal -0.572105 0.138534 0.808396 + outer loop + vertex 0.911973 1.81692 2.61554 + vertex 0.914021 1.81866 2.6167 + vertex 0.911837 1.82028 2.61487 + endloop + endfacet + facet normal -0.49724 0.150763 0.854414 + outer loop + vertex 0.911973 1.81692 2.61554 + vertex 0.911837 1.82028 2.61487 + vertex 0.908574 1.81618 2.6137 + endloop + endfacet + facet normal -0.500842 0.154428 0.851651 + outer loop + vertex 0.908574 1.81618 2.6137 + vertex 0.911837 1.82028 2.61487 + vertex 0.90818 1.82152 2.6125 + endloop + endfacet + facet normal -0.590103 0.172948 0.788585 + outer loop + vertex 0.914021 1.81866 2.6167 + vertex 0.911973 1.81692 2.61554 + vertex 0.913934 1.81523 2.61738 + endloop + endfacet + facet normal -0.498707 0.160862 0.851713 + outer loop + vertex 0.911837 1.82028 2.61487 + vertex 0.912219 1.82508 2.61419 + vertex 0.90818 1.82152 2.6125 + endloop + endfacet + facet normal -0.512366 0.182312 0.839192 + outer loop + vertex 0.90818 1.82152 2.6125 + vertex 0.912219 1.82508 2.61419 + vertex 0.909162 1.82671 2.61197 + endloop + endfacet + facet normal -0.512577 0.181872 0.839159 + outer loop + vertex 0.909162 1.82671 2.61197 + vertex 0.912219 1.82508 2.61419 + vertex 0.912517 1.8307 2.61315 + endloop + endfacet + facet normal -0.443447 0.242413 0.862896 + outer loop + vertex 0.90802 1.90585 2.59413 + vertex 0.906799 1.90073 2.59494 + vertex 0.910588 1.90394 2.59598 + endloop + endfacet + facet normal -0.450582 0.231994 0.862064 + outer loop + vertex 0.911822 1.90759 2.59565 + vertex 0.90802 1.90585 2.59413 + vertex 0.910588 1.90394 2.59598 + endloop + endfacet + facet normal -0.394285 0.215851 0.893279 + outer loop + vertex 0.910588 1.90394 2.59598 + vertex 0.914384 1.90719 2.59688 + vertex 0.911822 1.90759 2.59565 + endloop + endfacet + facet normal -0.417585 0.242508 0.875678 + outer loop + vertex 0.911822 1.90759 2.59565 + vertex 0.914385 1.91034 2.59611 + vertex 0.911853 1.91076 2.59478 + endloop + endfacet + facet normal -0.452434 0.238409 0.859339 + outer loop + vertex 0.911822 1.90759 2.59565 + vertex 0.911853 1.91076 2.59478 + vertex 0.90802 1.90585 2.59413 + endloop + endfacet + facet normal -0.393919 0.217461 0.89305 + outer loop + vertex 0.914385 1.91034 2.59611 + vertex 0.911822 1.90759 2.59565 + vertex 0.914384 1.90719 2.59688 + endloop + endfacet + facet normal -0.599749 0.260698 0.75653 + outer loop + vertex 0.910812 1.93893 2.5858 + vertex 0.908557 1.9381 2.5843 + vertex 0.908795 1.93553 2.58537 + endloop + endfacet + facet normal -0.555757 0.229229 0.799117 + outer loop + vertex 0.908795 1.93553 2.58537 + vertex 0.913127 1.93613 2.58821 + vertex 0.910812 1.93893 2.5858 + endloop + endfacet + facet normal -0.553302 0.278785 0.784943 + outer loop + vertex 0.908795 1.93553 2.58537 + vertex 0.908902 1.93127 2.58696 + vertex 0.913127 1.93613 2.58821 + endloop + endfacet + facet normal -0.601849 0.286544 0.745433 + outer loop + vertex 0.909189 1.94142 2.58353 + vertex 0.908557 1.9381 2.5843 + vertex 0.910812 1.93893 2.5858 + endloop + endfacet + facet normal -0.61983 0.267746 0.737647 + outer loop + vertex 0.91195 1.94218 2.58558 + vertex 0.909189 1.94142 2.58353 + vertex 0.910812 1.93893 2.5858 + endloop + endfacet + facet normal -0.532625 0.242257 0.810939 + outer loop + vertex 0.910812 1.93893 2.5858 + vertex 0.914194 1.94145 2.58727 + vertex 0.91195 1.94218 2.58558 + endloop + endfacet + facet normal -0.536654 0.250701 0.805699 + outer loop + vertex 0.913127 1.93613 2.58821 + vertex 0.914194 1.94145 2.58727 + vertex 0.910812 1.93893 2.5858 + endloop + endfacet + facet normal -0.556034 0.283844 0.781191 + outer loop + vertex 0.91195 1.94218 2.58558 + vertex 0.914222 1.94462 2.58631 + vertex 0.912151 1.94544 2.58453 + endloop + endfacet + facet normal -0.619842 0.273212 0.73563 + outer loop + vertex 0.91195 1.94218 2.58558 + vertex 0.912151 1.94544 2.58453 + vertex 0.909189 1.94142 2.58353 + endloop + endfacet + facet normal -0.635701 0.289922 0.715422 + outer loop + vertex 0.909189 1.94142 2.58353 + vertex 0.912151 1.94544 2.58453 + vertex 0.909578 1.94622 2.58193 + endloop + endfacet + facet normal -0.529565 0.250523 0.810431 + outer loop + vertex 0.914222 1.94462 2.58631 + vertex 0.91195 1.94218 2.58558 + vertex 0.914194 1.94145 2.58727 + endloop + endfacet + facet normal -0.711296 0.305568 0.632998 + outer loop + vertex 0.910748 1.95395 2.57971 + vertex 0.908383 1.95133 2.57831 + vertex 0.909801 1.9498 2.58065 + endloop + endfacet + facet normal -0.635317 0.305433 0.709283 + outer loop + vertex 0.909801 1.9498 2.58065 + vertex 0.913289 1.95093 2.58329 + vertex 0.910748 1.95395 2.57971 + endloop + endfacet + facet normal -0.635301 0.295568 0.713465 + outer loop + vertex 0.909801 1.9498 2.58065 + vertex 0.909578 1.94622 2.58193 + vertex 0.913289 1.95093 2.58329 + endloop + endfacet + facet normal -0.634104 0.294149 0.715114 + outer loop + vertex 0.909578 1.94622 2.58193 + vertex 0.912151 1.94544 2.58453 + vertex 0.913289 1.95093 2.58329 + endloop + endfacet + facet normal -0.76201 0.302538 0.572549 + outer loop + vertex 0.909627 1.95767 2.57663 + vertex 0.907912 1.95736 2.57451 + vertex 0.908063 1.95469 2.57612 + endloop + endfacet + facet normal -0.72231 0.328586 0.608522 + outer loop + vertex 0.908063 1.95469 2.57612 + vertex 0.908383 1.95133 2.57831 + vertex 0.910748 1.95395 2.57971 + endloop + endfacet + facet normal -0.738684 0.283624 0.611477 + outer loop + vertex 0.908063 1.95469 2.57612 + vertex 0.910748 1.95395 2.57971 + vertex 0.909627 1.95767 2.57663 + endloop + endfacet + facet normal -0.733148 0.288794 0.615704 + outer loop + vertex 0.909627 1.95767 2.57663 + vertex 0.910748 1.95395 2.57971 + vertex 0.91218 1.95851 2.57927 + endloop + endfacet + facet normal -0.654168 0.272567 0.705529 + outer loop + vertex 0.910748 1.95395 2.57971 + vertex 0.914365 1.95661 2.58204 + vertex 0.91218 1.95851 2.57927 + endloop + endfacet + facet normal -0.656018 0.27869 0.701408 + outer loop + vertex 0.913289 1.95093 2.58329 + vertex 0.914365 1.95661 2.58204 + vertex 0.910748 1.95395 2.57971 + endloop + endfacet + facet normal -0.760457 0.311004 0.570072 + outer loop + vertex 0.908247 1.96023 2.57339 + vertex 0.907912 1.95736 2.57451 + vertex 0.909627 1.95767 2.57663 + endloop + endfacet + facet normal -0.76868 0.30003 0.564901 + outer loop + vertex 0.910866 1.96261 2.57569 + vertex 0.908247 1.96023 2.57339 + vertex 0.909627 1.95767 2.57663 + endloop + endfacet + facet normal -0.670584 0.269362 0.691203 + outer loop + vertex 0.913294 1.96174 2.5791 + vertex 0.91218 1.95851 2.57927 + vertex 0.914615 1.96009 2.58102 + endloop + endfacet + facet normal -0.742925 0.289482 0.603541 + outer loop + vertex 0.913294 1.96174 2.5791 + vertex 0.910866 1.96261 2.57569 + vertex 0.91218 1.95851 2.57927 + endloop + endfacet + facet normal -0.732335 0.299766 0.611413 + outer loop + vertex 0.910866 1.96261 2.57569 + vertex 0.909627 1.95767 2.57663 + vertex 0.91218 1.95851 2.57927 + endloop + endfacet + facet normal -0.666724 0.252119 0.701367 + outer loop + vertex 0.914615 1.96009 2.58102 + vertex 0.91218 1.95851 2.57927 + vertex 0.914365 1.95661 2.58204 + endloop + endfacet + facet normal -0.781541 0.304544 0.544469 + outer loop + vertex 0.909777 1.96719 2.5717 + vertex 0.907845 1.96642 2.56936 + vertex 0.908672 1.96384 2.57199 + endloop + endfacet + facet normal -0.770126 0.30735 0.558965 + outer loop + vertex 0.908672 1.96384 2.57199 + vertex 0.908247 1.96023 2.57339 + vertex 0.910866 1.96261 2.57569 + endloop + endfacet + facet normal -0.772203 0.302685 0.558645 + outer loop + vertex 0.908672 1.96384 2.57199 + vertex 0.910866 1.96261 2.57569 + vertex 0.909777 1.96719 2.5717 + endloop + endfacet + facet normal -0.776372 0.298579 0.555065 + outer loop + vertex 0.909777 1.96719 2.5717 + vertex 0.910866 1.96261 2.57569 + vertex 0.912051 1.96779 2.57456 + endloop + endfacet + facet normal -0.743931 0.300269 0.596997 + outer loop + vertex 0.910866 1.96261 2.57569 + vertex 0.913592 1.96516 2.57781 + vertex 0.912051 1.96779 2.57456 + endloop + endfacet + facet normal -0.741758 0.292558 0.603494 + outer loop + vertex 0.913294 1.96174 2.5791 + vertex 0.913592 1.96516 2.57781 + vertex 0.910866 1.96261 2.57569 + endloop + endfacet + facet normal -0.781266 0.307208 0.543366 + outer loop + vertex 0.908385 1.97018 2.56801 + vertex 0.907845 1.96642 2.56936 + vertex 0.909777 1.96719 2.5717 + endloop + endfacet + facet normal -0.774174 0.316466 0.548182 + outer loop + vertex 0.911059 1.97245 2.57048 + vertex 0.908385 1.97018 2.56801 + vertex 0.909777 1.96719 2.5717 + endloop + endfacet + facet normal -0.741461 0.320796 0.589344 + outer loop + vertex 0.913381 1.97114 2.57441 + vertex 0.912051 1.96779 2.57456 + vertex 0.91416 1.96868 2.57673 + endloop + endfacet + facet normal -0.761904 0.327502 0.558789 + outer loop + vertex 0.913381 1.97114 2.57441 + vertex 0.911059 1.97245 2.57048 + vertex 0.912051 1.96779 2.57456 + endloop + endfacet + facet normal -0.773524 0.316515 0.549071 + outer loop + vertex 0.911059 1.97245 2.57048 + vertex 0.909777 1.96719 2.5717 + vertex 0.912051 1.96779 2.57456 + endloop + endfacet + facet normal -0.742369 0.302311 0.59791 + outer loop + vertex 0.91416 1.96868 2.57673 + vertex 0.912051 1.96779 2.57456 + vertex 0.913592 1.96516 2.57781 + endloop + endfacet + facet normal -0.761255 0.323133 0.562206 + outer loop + vertex 0.909992 1.977 2.56631 + vertex 0.908112 1.97623 2.56421 + vertex 0.908935 1.97387 2.56668 + endloop + endfacet + facet normal -0.773865 0.314253 0.549889 + outer loop + vertex 0.908935 1.97387 2.56668 + vertex 0.908385 1.97018 2.56801 + vertex 0.911059 1.97245 2.57048 + endloop + endfacet + facet normal -0.768924 0.3244 0.550928 + outer loop + vertex 0.908935 1.97387 2.56668 + vertex 0.911059 1.97245 2.57048 + vertex 0.909992 1.977 2.56631 + endloop + endfacet + facet normal -0.758265 0.334714 0.559464 + outer loop + vertex 0.909992 1.977 2.56631 + vertex 0.911059 1.97245 2.57048 + vertex 0.912272 1.97754 2.56908 + endloop + endfacet + facet normal -0.754246 0.335167 0.564602 + outer loop + vertex 0.911059 1.97245 2.57048 + vertex 0.913875 1.97481 2.57284 + vertex 0.912272 1.97754 2.56908 + endloop + endfacet + facet normal -0.75523 0.341449 0.5595 + outer loop + vertex 0.913381 1.97114 2.57441 + vertex 0.913875 1.97481 2.57284 + vertex 0.911059 1.97245 2.57048 + endloop + endfacet + facet normal -0.761417 0.321351 0.563007 + outer loop + vertex 0.908402 1.97975 2.56259 + vertex 0.908112 1.97623 2.56421 + vertex 0.909992 1.977 2.56631 + endloop + endfacet + facet normal -0.748667 0.338356 0.570098 + outer loop + vertex 0.910996 1.98169 2.56484 + vertex 0.908402 1.97975 2.56259 + vertex 0.909992 1.977 2.56631 + endloop + endfacet + facet normal -0.749719 0.347687 0.563059 + outer loop + vertex 0.913383 1.98089 2.56849 + vertex 0.912272 1.97754 2.56908 + vertex 0.914348 1.97851 2.57124 + endloop + endfacet + facet normal -0.747495 0.347493 0.566128 + outer loop + vertex 0.913383 1.98089 2.56849 + vertex 0.910996 1.98169 2.56484 + vertex 0.912272 1.97754 2.56908 + endloop + endfacet + facet normal -0.757879 0.336778 0.558748 + outer loop + vertex 0.910996 1.98169 2.56484 + vertex 0.909992 1.977 2.56631 + vertex 0.912272 1.97754 2.56908 + endloop + endfacet + facet normal -0.750216 0.340518 0.566765 + outer loop + vertex 0.914348 1.97851 2.57124 + vertex 0.912272 1.97754 2.56908 + vertex 0.913875 1.97481 2.57284 + endloop + endfacet + facet normal -0.746652 0.340302 0.571582 + outer loop + vertex 0.910928 1.98775 2.56115 + vertex 0.908721 1.98706 2.55867 + vertex 0.908683 1.98423 2.56031 + endloop + endfacet + facet normal -0.748583 0.337596 0.570659 + outer loop + vertex 0.908683 1.98423 2.56031 + vertex 0.908402 1.97975 2.56259 + vertex 0.910996 1.98169 2.56484 + endloop + endfacet + facet normal -0.746779 0.340443 0.571331 + outer loop + vertex 0.910928 1.98775 2.56115 + vertex 0.908683 1.98423 2.56031 + vertex 0.910996 1.98169 2.56484 + endloop + endfacet + facet normal -0.74154 0.343527 0.576288 + outer loop + vertex 0.910928 1.98775 2.56115 + vertex 0.910996 1.98169 2.56484 + vertex 0.913206 1.98453 2.566 + endloop + endfacet + facet normal -0.731447 0.357381 0.580745 + outer loop + vertex 0.910928 1.98775 2.56115 + vertex 0.913206 1.98453 2.566 + vertex 0.91307 1.98737 2.56407 + endloop + endfacet + facet normal -0.745928 0.351187 0.565914 + outer loop + vertex 0.913206 1.98453 2.566 + vertex 0.910996 1.98169 2.56484 + vertex 0.913383 1.98089 2.56849 + endloop + endfacet + facet normal -0.78822 0.342661 0.511168 + outer loop + vertex 0.90983 1.99238 2.55697 + vertex 0.908076 1.99129 2.555 + vertex 0.908768 1.98913 2.55751 + endloop + endfacet + facet normal -0.747081 0.337292 0.572803 + outer loop + vertex 0.908768 1.98913 2.55751 + vertex 0.908721 1.98706 2.55867 + vertex 0.910928 1.98775 2.56115 + endloop + endfacet + facet normal -0.746121 0.339168 0.572947 + outer loop + vertex 0.908768 1.98913 2.55751 + vertex 0.910928 1.98775 2.56115 + vertex 0.90983 1.99238 2.55697 + endloop + endfacet + facet normal -0.747721 0.337694 0.57173 + outer loop + vertex 0.90983 1.99238 2.55697 + vertex 0.910928 1.98775 2.56115 + vertex 0.912019 1.99301 2.55946 + endloop + endfacet + facet normal -0.740131 0.339008 0.580758 + outer loop + vertex 0.910928 1.98775 2.56115 + vertex 0.913415 1.99009 2.56295 + vertex 0.912019 1.99301 2.55946 + endloop + endfacet + facet normal -0.73926 0.335813 0.583716 + outer loop + vertex 0.91307 1.98737 2.56407 + vertex 0.913415 1.99009 2.56295 + vertex 0.910928 1.98775 2.56115 + endloop + endfacet + facet normal -0.787976 0.347535 0.508245 + outer loop + vertex 0.90873 1.9951 2.55341 + vertex 0.908076 1.99129 2.555 + vertex 0.90983 1.99238 2.55697 + endloop + endfacet + facet normal -0.789705 0.345308 0.507079 + outer loop + vertex 0.91111 1.99769 2.55535 + vertex 0.90873 1.9951 2.55341 + vertex 0.90983 1.99238 2.55697 + endloop + endfacet + facet normal -0.744624 0.337211 0.576041 + outer loop + vertex 0.913263 1.9963 2.55915 + vertex 0.912019 1.99301 2.55946 + vertex 0.914022 1.99362 2.5617 + endloop + endfacet + facet normal -0.758821 0.340568 0.55516 + outer loop + vertex 0.913263 1.9963 2.55915 + vertex 0.91111 1.99769 2.55535 + vertex 0.912019 1.99301 2.55946 + endloop + endfacet + facet normal -0.745329 0.352578 0.565839 + outer loop + vertex 0.91111 1.99769 2.55535 + vertex 0.90983 1.99238 2.55697 + vertex 0.912019 1.99301 2.55946 + endloop + endfacet + facet normal -0.745227 0.332962 0.577731 + outer loop + vertex 0.914022 1.99362 2.5617 + vertex 0.912019 1.99301 2.55946 + vertex 0.913415 1.99009 2.56295 + endloop + endfacet + facet normal -0.834044 0.382769 0.397313 + outer loop + vertex 0.910425 2.00259 2.55049 + vertex 0.908885 2.00058 2.54919 + vertex 0.909281 1.99878 2.55177 + endloop + endfacet + facet normal -0.789615 0.344924 0.50748 + outer loop + vertex 0.909281 1.99878 2.55177 + vertex 0.90873 1.9951 2.55341 + vertex 0.91111 1.99769 2.55535 + endloop + endfacet + facet normal -0.762211 0.398863 0.509846 + outer loop + vertex 0.909281 1.99878 2.55177 + vertex 0.91111 1.99769 2.55535 + vertex 0.910425 2.00259 2.55049 + endloop + endfacet + facet normal -0.812019 0.349707 0.467259 + outer loop + vertex 0.910425 2.00259 2.55049 + vertex 0.91111 1.99769 2.55535 + vertex 0.912527 2.00292 2.5539 + endloop + endfacet + facet normal -0.759708 0.356747 0.543669 + outer loop + vertex 0.91111 1.99769 2.55535 + vertex 0.913772 1.99998 2.55757 + vertex 0.912527 2.00292 2.5539 + endloop + endfacet + facet normal -0.757584 0.343006 0.55535 + outer loop + vertex 0.913263 1.9963 2.55915 + vertex 0.913772 1.99998 2.55757 + vertex 0.91111 1.99769 2.55535 + endloop + endfacet + facet normal -0.636359 0.452648 0.624626 + outer loop + vertex 0.910358 2.00934 2.54079 + vertex 0.910057 2.01 2.54 + vertex 0.91 2.00992 2.54 + endloop + endfacet + facet normal -0.582033 0.504208 0.637975 + outer loop + vertex 0.909145 2.00488 2.5432 + vertex 0.910358 2.00934 2.54079 + vertex 0.91 2.00992 2.54 + endloop + endfacet + facet normal -0.909362 0.360183 0.208156 + outer loop + vertex 0.910624 2.00733 2.54543 + vertex 0.910358 2.00934 2.54079 + vertex 0.909145 2.00488 2.5432 + endloop + endfacet + facet normal -0.908456 0.366993 0.200059 + outer loop + vertex 0.909277 2.00316 2.54696 + vertex 0.910624 2.00733 2.54543 + vertex 0.909145 2.00488 2.5432 + endloop + endfacet + facet normal -0.839396 0.423577 0.340583 + outer loop + vertex 0.909277 2.00316 2.54696 + vertex 0.908885 2.00058 2.54919 + vertex 0.910425 2.00259 2.55049 + endloop + endfacet + facet normal -0.850897 0.399998 0.340554 + outer loop + vertex 0.909277 2.00316 2.54696 + vertex 0.910425 2.00259 2.55049 + vertex 0.910624 2.00733 2.54543 + endloop + endfacet + facet normal -0.870733 0.375811 0.31716 + outer loop + vertex 0.910624 2.00733 2.54543 + vertex 0.910425 2.00259 2.55049 + vertex 0.912365 2.00733 2.55021 + endloop + endfacet + facet normal -0.767121 0.353341 0.535421 + outer loop + vertex 0.913807 2.00606 2.55366 + vertex 0.912527 2.00292 2.5539 + vertex 0.91438 2.00372 2.55603 + endloop + endfacet + facet normal -0.804587 0.363648 0.469467 + outer loop + vertex 0.913807 2.00606 2.55366 + vertex 0.912365 2.00733 2.55021 + vertex 0.912527 2.00292 2.5539 + endloop + endfacet + facet normal -0.809278 0.359426 0.464631 + outer loop + vertex 0.912365 2.00733 2.55021 + vertex 0.910425 2.00259 2.55049 + vertex 0.912527 2.00292 2.5539 + endloop + endfacet + facet normal -0.767906 0.346853 0.538529 + outer loop + vertex 0.91438 2.00372 2.55603 + vertex 0.912527 2.00292 2.5539 + vertex 0.913772 1.99998 2.55757 + endloop + endfacet + facet normal -0.721994 0.367771 0.586062 + outer loop + vertex 0.910057 2.01 2.54 + vertex 0.910358 2.00934 2.54079 + vertex 0.912604 2.015 2.54 + endloop + endfacet + facet normal -0.92955 0.368695 -0.000234826 + outer loop + vertex 0.912604 2.015 2.54 + vertex 0.910358 2.00934 2.54079 + vertex 0.911779 2.01292 2.54152 + endloop + endfacet + facet normal -0.924807 0.326889 0.194616 + outer loop + vertex 0.910358 2.00934 2.54079 + vertex 0.910624 2.00733 2.54543 + vertex 0.911779 2.01292 2.54152 + endloop + endfacet + facet normal -0.918844 0.335192 0.20826 + outer loop + vertex 0.911779 2.01292 2.54152 + vertex 0.910624 2.00733 2.54543 + vertex 0.912545 2.01232 2.54587 + endloop + endfacet + facet normal -0.823913 0.325487 0.463924 + outer loop + vertex 0.913521 2.01103 2.54967 + vertex 0.912365 2.00733 2.55021 + vertex 0.914087 2.0088 2.55223 + endloop + endfacet + facet normal -0.883146 0.325453 0.337835 + outer loop + vertex 0.913521 2.01103 2.54967 + vertex 0.912545 2.01232 2.54587 + vertex 0.912365 2.00733 2.55021 + endloop + endfacet + facet normal -0.891932 0.314507 0.324875 + outer loop + vertex 0.912545 2.01232 2.54587 + vertex 0.910624 2.00733 2.54543 + vertex 0.912365 2.00733 2.55021 + endloop + endfacet + facet normal -0.823916 0.325851 0.463662 + outer loop + vertex 0.914087 2.0088 2.55223 + vertex 0.912365 2.00733 2.55021 + vertex 0.913807 2.00606 2.55366 + endloop + endfacet + facet normal -0.941772 0.155776 -0.297994 + outer loop + vertex 0.912604 2.015 2.54 + vertex 0.911779 2.01292 2.54152 + vertex 0.913431 2.02 2.54 + endloop + endfacet + facet normal -0.877338 0.287285 0.384377 + outer loop + vertex 0.913431 2.02 2.54 + vertex 0.911779 2.01292 2.54152 + vertex 0.913103 2.01722 2.54133 + endloop + endfacet + facet normal -0.932705 0.29648 0.205334 + outer loop + vertex 0.911779 2.01292 2.54152 + vertex 0.912545 2.01232 2.54587 + vertex 0.913103 2.01722 2.54133 + endloop + endfacet + facet normal -0.939318 0.284534 0.191628 + outer loop + vertex 0.913103 2.01722 2.54133 + vertex 0.912545 2.01232 2.54587 + vertex 0.913606 2.01635 2.54508 + endloop + endfacet + facet normal -0.892981 0.300403 0.335177 + outer loop + vertex 0.912545 2.01232 2.54587 + vertex 0.91415 2.01444 2.54825 + vertex 0.913606 2.01635 2.54508 + endloop + endfacet + facet normal -0.892971 0.303102 0.332764 + outer loop + vertex 0.913521 2.01103 2.54967 + vertex 0.91415 2.01444 2.54825 + vertex 0.912545 2.01232 2.54587 + endloop + endfacet + facet normal 0.354083 -0.416859 -0.83717 + outer loop + vertex 0.915 2.02263 2.535 + vertex 0.914056 2.02146 2.53518 + vertex 0.915 2.025 2.53382 + endloop + endfacet + facet normal 0.535878 -0.534343 -0.653691 + outer loop + vertex 0.915 2.02 2.53715 + vertex 0.914056 2.02146 2.53518 + vertex 0.915 2.02263 2.535 + endloop + endfacet + facet normal -0.556036 -0.772734 -0.306113 + outer loop + vertex 0.915 2.02 2.53715 + vertex 0.913431 2.02 2.54 + vertex 0.914056 2.02146 2.53518 + endloop + endfacet + facet normal -0.992305 0.0464585 -0.114771 + outer loop + vertex 0.913431 2.02 2.54 + vertex 0.913787 2.02115 2.53738 + vertex 0.914056 2.02146 2.53518 + endloop + endfacet + facet normal -0.924547 0.317821 0.210246 + outer loop + vertex 0.914062 2.02108 2.53971 + vertex 0.913103 2.01722 2.54133 + vertex 0.914365 2.01969 2.54314 + endloop + endfacet + facet normal -0.950491 0.286479 0.120405 + outer loop + vertex 0.914062 2.02108 2.53971 + vertex 0.913787 2.02115 2.53738 + vertex 0.913103 2.01722 2.54133 + endloop + endfacet + facet normal 0.992152 -0.0660462 0.106167 + outer loop + vertex 0.913787 2.02115 2.53738 + vertex 0.913431 2.02 2.54 + vertex 0.913103 2.01722 2.54133 + endloop + endfacet + facet normal -0.877714 0.373805 0.299813 + outer loop + vertex 0.914365 2.01969 2.54314 + vertex 0.913606 2.01635 2.54508 + vertex 0.914805 2.01792 2.54663 + endloop + endfacet + facet normal -0.924243 0.325753 0.199149 + outer loop + vertex 0.913103 2.01722 2.54133 + vertex 0.913606 2.01635 2.54508 + vertex 0.914365 2.01969 2.54314 + endloop + endfacet + facet normal -0.87856 0.326597 0.34852 + outer loop + vertex 0.914805 2.01792 2.54663 + vertex 0.913606 2.01635 2.54508 + vertex 0.91415 2.01444 2.54825 + endloop + endfacet + facet normal -0.955913 0.159776 -0.246378 + outer loop + vertex 0.915 2.025 2.53382 + vertex 0.914056 2.02146 2.53518 + vertex 0.915 2.02682 2.535 + endloop + endfacet + facet normal -0.969952 0.234528 0.0647299 + outer loop + vertex 0.915 2.02682 2.535 + vertex 0.913787 2.02115 2.53738 + vertex 0.915 2.02544 2.54 + endloop + endfacet + facet normal -0.980873 0.169345 -0.0959735 + outer loop + vertex 0.914056 2.02146 2.53518 + vertex 0.913787 2.02115 2.53738 + vertex 0.915 2.02682 2.535 + endloop + endfacet + facet normal -0.972119 0.20115 0.120515 + outer loop + vertex 0.915 2.02544 2.54 + vertex 0.913787 2.02115 2.53738 + vertex 0.914062 2.02108 2.53971 + endloop + endfacet + facet normal 0.348768 -0.156021 -0.924131 + outer loop + vertex 0.909736 2.10623 2.49739 + vertex 0.915 2.11 2.49874 + vertex 0.913919 2.10723 2.4988 + endloop + endfacet + facet normal 0.472526 -0.37364 -0.798193 + outer loop + vertex 0.91 2.11 2.49578 + vertex 0.915 2.11 2.49874 + vertex 0.909736 2.10623 2.49739 + endloop + endfacet + facet normal 0.341447 -0.846401 -0.408679 + outer loop + vertex 0.913919 2.10723 2.4988 + vertex 0.913993 2.10575 2.50193 + vertex 0.909736 2.10623 2.49739 + endloop + endfacet + facet normal 0.201302 -0.936601 -0.286803 + outer loop + vertex 0.913993 2.10575 2.50193 + vertex 0.908548 2.10464 2.50173 + vertex 0.909736 2.10623 2.49739 + endloop + endfacet + facet normal 0.202595 -0.968824 -0.1426 + outer loop + vertex 0.913993 2.10575 2.50193 + vertex 0.913344 2.10488 2.50692 + vertex 0.908548 2.10464 2.50173 + endloop + endfacet + facet normal 0.00242307 -0.999025 0.0440908 + outer loop + vertex 0.913344 2.10488 2.50692 + vertex 0.907966 2.10483 2.50608 + vertex 0.908548 2.10464 2.50173 + endloop + endfacet + facet normal -0.0153912 -0.987267 0.158325 + outer loop + vertex 0.913344 2.10488 2.50692 + vertex 0.912761 2.10557 2.51116 + vertex 0.907966 2.10483 2.50608 + endloop + endfacet + facet normal -0.303385 -0.85938 0.411611 + outer loop + vertex 0.912761 2.10557 2.51116 + vertex 0.907425 2.10621 2.50857 + vertex 0.907966 2.10483 2.50608 + endloop + endfacet + facet normal -0.420449 -0.535529 0.732415 + outer loop + vertex 0.912761 2.10557 2.51116 + vertex 0.910335 2.10755 2.51122 + vertex 0.907425 2.10621 2.50857 + endloop + endfacet + facet normal -0.493074 -0.620722 0.609575 + outer loop + vertex 0.914056 2.10723 2.5139 + vertex 0.910335 2.10755 2.51122 + vertex 0.912761 2.10557 2.51116 + endloop + endfacet + facet normal -0.506646 0.436912 0.743248 + outer loop + vertex 0.910236 2.11263 2.50914 + vertex 0.908137 2.11223 2.50794 + vertex 0.908881 2.11029 2.50959 + endloop + endfacet + facet normal -0.522424 0.443198 0.728456 + outer loop + vertex 0.908881 2.11029 2.50959 + vertex 0.912709 2.11006 2.51247 + vertex 0.910236 2.11263 2.50914 + endloop + endfacet + facet normal -0.587717 0.159829 0.793122 + outer loop + vertex 0.908881 2.11029 2.50959 + vertex 0.910335 2.10755 2.51122 + vertex 0.912709 2.11006 2.51247 + endloop + endfacet + facet normal -0.571229 0.136106 0.809427 + outer loop + vertex 0.910335 2.10755 2.51122 + vertex 0.914056 2.10723 2.5139 + vertex 0.912709 2.11006 2.51247 + endloop + endfacet + facet normal -0.49031 0.62396 0.608498 + outer loop + vertex 0.910941 2.11565 2.50697 + vertex 0.908286 2.11606 2.50441 + vertex 0.908042 2.11414 2.50619 + endloop + endfacet + facet normal -0.483722 0.579506 0.655886 + outer loop + vertex 0.908042 2.11414 2.50619 + vertex 0.908137 2.11223 2.50794 + vertex 0.910236 2.11263 2.50914 + endloop + endfacet + facet normal -0.481212 0.582164 0.655378 + outer loop + vertex 0.910941 2.11565 2.50697 + vertex 0.908042 2.11414 2.50619 + vertex 0.910236 2.11263 2.50914 + endloop + endfacet + facet normal -0.510546 0.576519 0.637941 + outer loop + vertex 0.910941 2.11565 2.50697 + vertex 0.910236 2.11263 2.50914 + vertex 0.913319 2.11367 2.51067 + endloop + endfacet + facet normal -0.524041 0.562783 0.639263 + outer loop + vertex 0.910941 2.11565 2.50697 + vertex 0.913319 2.11367 2.51067 + vertex 0.913762 2.11587 2.50909 + endloop + endfacet + facet normal -0.513781 0.452277 0.729023 + outer loop + vertex 0.913319 2.11367 2.51067 + vertex 0.910236 2.11263 2.50914 + vertex 0.912709 2.11006 2.51247 + endloop + endfacet + facet normal -0.423784 0.777938 0.463917 + outer loop + vertex 0.910343 2.1226 2.49568 + vertex 0.907515 2.12229 2.49361 + vertex 0.908366 2.12058 2.49726 + endloop + endfacet + facet normal -0.397196 0.774324 0.492604 + outer loop + vertex 0.912121 2.12179 2.49838 + vertex 0.910343 2.1226 2.49568 + vertex 0.908366 2.12058 2.49726 + endloop + endfacet + facet normal -0.38802 0.828367 0.404041 + outer loop + vertex 0.912121 2.12179 2.49838 + vertex 0.908366 2.12058 2.49726 + vertex 0.913412 2.12047 2.50232 + endloop + endfacet + facet normal -0.434366 0.780706 0.449249 + outer loop + vertex 0.913412 2.12047 2.50232 + vertex 0.908366 2.12058 2.49726 + vertex 0.909094 2.11799 2.50247 + endloop + endfacet + facet normal -0.41528 0.726748 0.547157 + outer loop + vertex 0.910941 2.11565 2.50697 + vertex 0.909094 2.11799 2.50247 + vertex 0.908286 2.11606 2.50441 + endloop + endfacet + facet normal -0.482056 0.681259 0.550916 + outer loop + vertex 0.910941 2.11565 2.50697 + vertex 0.914491 2.11794 2.50725 + vertex 0.909094 2.11799 2.50247 + endloop + endfacet + facet normal -0.42372 0.76439 0.485972 + outer loop + vertex 0.914491 2.11794 2.50725 + vertex 0.913412 2.12047 2.50232 + vertex 0.909094 2.11799 2.50247 + endloop + endfacet + facet normal -0.477377 0.672192 0.565924 + outer loop + vertex 0.914491 2.11794 2.50725 + vertex 0.910941 2.11565 2.50697 + vertex 0.913762 2.11587 2.50909 + endloop + endfacet + facet normal -0.594399 0.0918101 0.798912 + outer loop + vertex 0.910343 2.1226 2.49568 + vertex 0.91 2.12629 2.495 + vertex 0.907515 2.12229 2.49361 + endloop + endfacet + facet normal -0.386007 0.132151 0.912981 + outer loop + vertex 0.910343 2.1226 2.49568 + vertex 0.914357 2.12373 2.49721 + vertex 0.91 2.12629 2.495 + endloop + endfacet + facet normal -0.0960312 0.55191 0.828356 + outer loop + vertex 0.914357 2.12373 2.49721 + vertex 0.915 2.12716 2.495 + vertex 0.91 2.12629 2.495 + endloop + endfacet + facet normal -0.405715 0.767588 0.496189 + outer loop + vertex 0.914357 2.12373 2.49721 + vertex 0.910343 2.1226 2.49568 + vertex 0.912121 2.12179 2.49838 + endloop + endfacet + facet normal -0.256684 -0.966437 -0.0106335 + outer loop + vertex 0.92 0.900197 2.495 + vertex 0.92 0.900142 2.5 + vertex 0.915 0.901525 2.495 + endloop + endfacet + facet normal -0.185557 -0.978932 -0.0852147 + outer loop + vertex 0.92 0.900142 2.5 + vertex 0.914261 0.901481 2.49711 + vertex 0.915 0.901525 2.495 + endloop + endfacet + facet normal -0.336486 -0.908676 0.247155 + outer loop + vertex 0.92 0.900142 2.5 + vertex 0.918935 0.900962 2.50157 + vertex 0.914261 0.901481 2.49711 + endloop + endfacet + facet normal -0.315184 -0.92241 0.223203 + outer loop + vertex 0.918935 0.900962 2.50157 + vertex 0.913343 0.902633 2.50057 + vertex 0.914261 0.901481 2.49711 + endloop + endfacet + facet normal -0.375707 -0.838207 0.395289 + outer loop + vertex 0.912638 0.904383 2.50387 + vertex 0.918031 0.90264 2.5053 + vertex 0.91565 0.904211 2.50637 + endloop + endfacet + facet normal -0.373263 -0.850016 0.371682 + outer loop + vertex 0.912638 0.904383 2.50387 + vertex 0.913343 0.902633 2.50057 + vertex 0.918031 0.90264 2.5053 + endloop + endfacet + facet normal -0.322997 -0.889986 0.321868 + outer loop + vertex 0.913343 0.902633 2.50057 + vertex 0.918935 0.900962 2.50157 + vertex 0.918031 0.90264 2.5053 + endloop + endfacet + facet normal -0.343446 -0.825296 0.448253 + outer loop + vertex 0.918031 0.90264 2.5053 + vertex 0.917707 0.904665 2.50878 + vertex 0.91565 0.904211 2.50637 + endloop + endfacet + facet normal -0.444842 -0.753254 0.484483 + outer loop + vertex 0.912638 0.904383 2.50387 + vertex 0.91565 0.904211 2.50637 + vertex 0.913326 0.905866 2.50681 + endloop + endfacet + facet normal -0.506445 -0.635422 0.582883 + outer loop + vertex 0.918283 0.90631 2.51151 + vertex 0.915828 0.908333 2.51158 + vertex 0.91322 0.908119 2.50908 + endloop + endfacet + facet normal -0.497789 -0.692323 0.522394 + outer loop + vertex 0.917707 0.904665 2.50878 + vertex 0.918283 0.90631 2.51151 + vertex 0.91322 0.908119 2.50908 + endloop + endfacet + facet normal -0.453909 -0.643553 0.616285 + outer loop + vertex 0.917707 0.904665 2.50878 + vertex 0.91322 0.908119 2.50908 + vertex 0.913326 0.905866 2.50681 + endloop + endfacet + facet normal -0.433199 -0.743531 0.509412 + outer loop + vertex 0.917707 0.904665 2.50878 + vertex 0.913326 0.905866 2.50681 + vertex 0.91565 0.904211 2.50637 + endloop + endfacet + facet normal -0.480223 -0.605487 0.634643 + outer loop + vertex 0.918283 0.90631 2.51151 + vertex 0.91842 0.908626 2.51382 + vertex 0.915828 0.908333 2.51158 + endloop + endfacet + facet normal -0.584607 -0.483626 0.651414 + outer loop + vertex 0.91322 0.908119 2.50908 + vertex 0.915828 0.908333 2.51158 + vertex 0.913623 0.910492 2.5112 + endloop + endfacet + facet normal -0.635372 -0.122092 0.762493 + outer loop + vertex 0.917923 0.911102 2.5152 + vertex 0.916823 0.912904 2.51457 + vertex 0.915114 0.911996 2.513 + endloop + endfacet + facet normal -0.631879 -0.469708 0.616525 + outer loop + vertex 0.91842 0.908626 2.51382 + vertex 0.917923 0.911102 2.5152 + vertex 0.915114 0.911996 2.513 + endloop + endfacet + facet normal -0.550439 -0.356105 0.75512 + outer loop + vertex 0.91842 0.908626 2.51382 + vertex 0.915114 0.911996 2.513 + vertex 0.913623 0.910492 2.5112 + endloop + endfacet + facet normal -0.556063 -0.445731 0.701511 + outer loop + vertex 0.91842 0.908626 2.51382 + vertex 0.913623 0.910492 2.5112 + vertex 0.915828 0.908333 2.51158 + endloop + endfacet + facet normal -0.58293 -0.0738288 0.809161 + outer loop + vertex 0.917923 0.911102 2.5152 + vertex 0.919922 0.911627 2.51669 + vertex 0.916823 0.912904 2.51457 + endloop + endfacet + facet normal 0.0306678 0.851853 0.522883 + outer loop + vertex 0.92 0.9174 2.5 + vertex 0.915 0.91758 2.5 + vertex 0.918658 0.916136 2.50214 + endloop + endfacet + facet normal 0.105305 0.898305 0.426567 + outer loop + vertex 0.918658 0.916136 2.50214 + vertex 0.915 0.91758 2.5 + vertex 0.913704 0.916682 2.50221 + endloop + endfacet + facet normal 0.109921 0.993626 0.0249935 + outer loop + vertex 0.918658 0.916136 2.50214 + vertex 0.913704 0.916682 2.50221 + vertex 0.918149 0.916081 2.50657 + endloop + endfacet + facet normal -0.0140103 0.98848 0.150703 + outer loop + vertex 0.918149 0.916081 2.50657 + vertex 0.913704 0.916682 2.50221 + vertex 0.91328 0.915989 2.50671 + endloop + endfacet + facet normal -0.0147229 0.991555 0.128845 + outer loop + vertex 0.918149 0.916081 2.50657 + vertex 0.91328 0.915989 2.50671 + vertex 0.918149 0.915444 2.51147 + endloop + endfacet + facet normal -0.255203 0.895756 0.363994 + outer loop + vertex 0.918149 0.915444 2.51147 + vertex 0.91328 0.915989 2.50671 + vertex 0.914273 0.914383 2.51136 + endloop + endfacet + facet normal -0.71863 0.202744 0.665181 + outer loop + vertex 0.916823 0.912904 2.51457 + vertex 0.914273 0.914383 2.51136 + vertex 0.915114 0.911996 2.513 + endloop + endfacet + facet normal -0.466874 0.601074 0.648644 + outer loop + vertex 0.916823 0.912904 2.51457 + vertex 0.918846 0.913864 2.51514 + vertex 0.914273 0.914383 2.51136 + endloop + endfacet + facet normal -0.250069 0.870932 0.423016 + outer loop + vertex 0.918846 0.913864 2.51514 + vertex 0.918149 0.915444 2.51147 + vertex 0.914273 0.914383 2.51136 + endloop + endfacet + facet normal -0.411317 0.376774 0.829976 + outer loop + vertex 0.918846 0.913864 2.51514 + vertex 0.916823 0.912904 2.51457 + vertex 0.919922 0.911627 2.51669 + endloop + endfacet + facet normal -0.726117 -0.281781 -0.627179 + outer loop + vertex 0.92 0.989688 2.535 + vertex 0.919215 0.991691 2.53501 + vertex 0.92 0.99 2.53486 + endloop + endfacet + facet normal -0.91449 -0.35895 0.186716 + outer loop + vertex 0.92 0.989688 2.535 + vertex 0.92 0.99 2.5356 + vertex 0.919215 0.991691 2.53501 + endloop + endfacet + facet normal -0.70143 -0.126236 -0.70147 + outer loop + vertex 0.92 0.99 2.53486 + vertex 0.91896 0.995 2.535 + vertex 0.92 0.995 2.53396 + endloop + endfacet + facet normal -0.227418 -0.0200072 -0.973592 + outer loop + vertex 0.919215 0.991691 2.53501 + vertex 0.91896 0.995 2.535 + vertex 0.92 0.99 2.53486 + endloop + endfacet + facet normal -0.907022 -0.328776 0.263092 + outer loop + vertex 0.92 0.993521 2.54 + vertex 0.919215 0.991691 2.53501 + vertex 0.92 0.99 2.5356 + endloop + endfacet + facet normal -0.845724 -0.444167 0.295749 + outer loop + vertex 0.92 0.993521 2.54 + vertex 0.918357 0.995128 2.53772 + vertex 0.919215 0.991691 2.53501 + endloop + endfacet + facet normal -0.974207 -0.0757236 -0.21257 + outer loop + vertex 0.918357 0.995128 2.53772 + vertex 0.91896 0.995 2.535 + vertex 0.919215 0.991691 2.53501 + endloop + endfacet + facet normal 0.725029 -0.196729 -0.660023 + outer loop + vertex 0.92 0.993521 2.54 + vertex 0.919253 0.99305 2.53932 + vertex 0.918357 0.995128 2.53772 + endloop + endfacet + facet normal -0.71992 0.420611 -0.552089 + outer loop + vertex 0.92 0.997795 2.535 + vertex 0.917454 1 2.54 + vertex 0.92 1 2.53668 + endloop + endfacet + facet normal -0.792596 0.294933 -0.533672 + outer loop + vertex 0.92 0.997795 2.535 + vertex 0.91896 0.995 2.535 + vertex 0.917454 1 2.54 + endloop + endfacet + facet normal -0.973848 -0.0810854 -0.212237 + outer loop + vertex 0.91896 0.995 2.535 + vertex 0.918357 0.995128 2.53772 + vertex 0.917454 1 2.54 + endloop + endfacet + facet normal -0.931477 -0.359784 0.0539031 + outer loop + vertex 0.918426 0.995396 2.54069 + vertex 0.918357 0.995128 2.53772 + vertex 0.919253 0.99305 2.53932 + endloop + endfacet + facet normal -0.958664 -0.280561 0.0474223 + outer loop + vertex 0.918426 0.995396 2.54069 + vertex 0.917216 0.999698 2.54167 + vertex 0.918357 0.995128 2.53772 + endloop + endfacet + facet normal -0.981388 -0.107324 -0.159244 + outer loop + vertex 0.917216 0.999698 2.54167 + vertex 0.917454 1 2.54 + vertex 0.918357 0.995128 2.53772 + endloop + endfacet + facet normal -0.937459 -0.302832 0.171651 + outer loop + vertex 0.918426 0.995396 2.54069 + vertex 0.918551 0.996731 2.54373 + vertex 0.917216 0.999698 2.54167 + endloop + endfacet + facet normal -0.939237 -0.288536 -0.185959 + outer loop + vertex 0.917454 1 2.54 + vertex 0.917216 0.999698 2.54167 + vertex 0.915918 1.005 2.54 + endloop + endfacet + facet normal -0.937652 -0.28995 -0.19167 + outer loop + vertex 0.915918 1.005 2.54 + vertex 0.917216 0.999698 2.54167 + vertex 0.915434 1.00476 2.54272 + endloop + endfacet + facet normal -0.937761 -0.29564 0.182213 + outer loop + vertex 0.918213 0.999127 2.54588 + vertex 0.917216 0.999698 2.54167 + vertex 0.918551 0.996731 2.54373 + endloop + endfacet + facet normal -0.925834 -0.335507 0.173973 + outer loop + vertex 0.918213 0.999127 2.54588 + vertex 0.91703 1.00266 2.54639 + vertex 0.917216 0.999698 2.54167 + endloop + endfacet + facet normal -0.913157 -0.360528 0.190168 + outer loop + vertex 0.91703 1.00266 2.54639 + vertex 0.915434 1.00476 2.54272 + vertex 0.917216 0.999698 2.54167 + endloop + endfacet + facet normal -0.880752 -0.342492 0.32707 + outer loop + vertex 0.919296 1.00008 2.5498 + vertex 0.91703 1.00266 2.54639 + vertex 0.918213 0.999127 2.54588 + endloop + endfacet + facet normal -0.880333 -0.347132 0.323286 + outer loop + vertex 0.917781 1.00487 2.55081 + vertex 0.91703 1.00266 2.54639 + vertex 0.919296 1.00008 2.5498 + endloop + endfacet + facet normal -0.83117 -0.35387 0.428874 + outer loop + vertex 0.919296 1.00008 2.5498 + vertex 0.920194 1.00265 2.55365 + vertex 0.917781 1.00487 2.55081 + endloop + endfacet + facet normal -0.831976 -0.520222 -0.192836 + outer loop + vertex 0.915918 1.005 2.54 + vertex 0.915434 1.00476 2.54272 + vertex 0.914324 1.00744 2.54029 + endloop + endfacet + facet normal -0.290829 -0.0771585 -0.953659 + outer loop + vertex 0.915 1.00846 2.54 + vertex 0.915918 1.005 2.54 + vertex 0.914324 1.00744 2.54029 + endloop + endfacet + facet normal -0.925892 -0.377728 0.00671238 + outer loop + vertex 0.914081 1.00809 2.54308 + vertex 0.914324 1.00744 2.54029 + vertex 0.915434 1.00476 2.54272 + endloop + endfacet + facet normal -0.89197 -0.388171 0.231761 + outer loop + vertex 0.914081 1.00809 2.54308 + vertex 0.915434 1.00476 2.54272 + vertex 0.915274 1.00802 2.54756 + endloop + endfacet + facet normal -0.917085 -0.344144 0.201298 + outer loop + vertex 0.915274 1.00802 2.54756 + vertex 0.915434 1.00476 2.54272 + vertex 0.91703 1.00266 2.54639 + endloop + endfacet + facet normal -0.874401 -0.357866 0.327649 + outer loop + vertex 0.91703 1.00266 2.54639 + vertex 0.917781 1.00487 2.55081 + vertex 0.915274 1.00802 2.54756 + endloop + endfacet + facet normal -0.874647 -0.327118 0.357752 + outer loop + vertex 0.915274 1.00802 2.54756 + vertex 0.917781 1.00487 2.55081 + vertex 0.916894 1.00945 2.55283 + endloop + endfacet + facet normal -0.828856 -0.352194 0.434692 + outer loop + vertex 0.917781 1.00487 2.55081 + vertex 0.918896 1.00686 2.55455 + vertex 0.916894 1.00945 2.55283 + endloop + endfacet + facet normal -0.831237 -0.348264 0.433311 + outer loop + vertex 0.920194 1.00265 2.55365 + vertex 0.918896 1.00686 2.55455 + vertex 0.917781 1.00487 2.55081 + endloop + endfacet + facet normal -0.898827 -0.370717 0.233834 + outer loop + vertex 0.914081 1.00809 2.54308 + vertex 0.915274 1.00802 2.54756 + vertex 0.913478 1.01074 2.54496 + endloop + endfacet + facet normal -0.900824 -0.350442 0.256334 + outer loop + vertex 0.913722 1.01231 2.54797 + vertex 0.913478 1.01074 2.54496 + vertex 0.915274 1.00802 2.54756 + endloop + endfacet + facet normal -0.868061 -0.347846 0.354223 + outer loop + vertex 0.913722 1.01231 2.54797 + vertex 0.915274 1.00802 2.54756 + vertex 0.914948 1.01337 2.55202 + endloop + endfacet + facet normal -0.86291 -0.353386 0.361255 + outer loop + vertex 0.914948 1.01337 2.55202 + vertex 0.915274 1.00802 2.54756 + vertex 0.916894 1.00945 2.55283 + endloop + endfacet + facet normal -0.82539 -0.337805 0.452348 + outer loop + vertex 0.91818 1.01024 2.55576 + vertex 0.916894 1.00945 2.55283 + vertex 0.918896 1.00686 2.55455 + endloop + endfacet + facet normal -0.833972 -0.318166 0.450844 + outer loop + vertex 0.91818 1.01024 2.55576 + vertex 0.917196 1.01379 2.55645 + vertex 0.916894 1.00945 2.55283 + endloop + endfacet + facet normal -0.832608 -0.319547 0.452386 + outer loop + vertex 0.917196 1.01379 2.55645 + vertex 0.914948 1.01337 2.55202 + vertex 0.916894 1.00945 2.55283 + endloop + endfacet + facet normal -0.802412 -0.319672 0.503928 + outer loop + vertex 0.91818 1.01024 2.55576 + vertex 0.918846 1.01187 2.55786 + vertex 0.917196 1.01379 2.55645 + endloop + endfacet + facet normal -0.869387 -0.3449 0.353851 + outer loop + vertex 0.913722 1.01231 2.54797 + vertex 0.914948 1.01337 2.55202 + vertex 0.913236 1.01542 2.54981 + endloop + endfacet + facet normal -0.86946 -0.335849 0.362277 + outer loop + vertex 0.913721 1.01734 2.55275 + vertex 0.913236 1.01542 2.54981 + vertex 0.914948 1.01337 2.55202 + endloop + endfacet + facet normal -0.822158 -0.338818 0.457449 + outer loop + vertex 0.913721 1.01734 2.55275 + vertex 0.914948 1.01337 2.55202 + vertex 0.915254 1.01853 2.55639 + endloop + endfacet + facet normal -0.827847 -0.333229 0.451251 + outer loop + vertex 0.915254 1.01853 2.55639 + vertex 0.914948 1.01337 2.55202 + vertex 0.917196 1.01379 2.55645 + endloop + endfacet + facet normal -0.798586 -0.305666 0.518487 + outer loop + vertex 0.91935 1.01441 2.56013 + vertex 0.917196 1.01379 2.55645 + vertex 0.918846 1.01187 2.55786 + endloop + endfacet + facet normal -0.7917 -0.32445 0.517633 + outer loop + vertex 0.91935 1.01441 2.56013 + vertex 0.917782 1.01844 2.56027 + vertex 0.917196 1.01379 2.55645 + endloop + endfacet + facet normal -0.79687 -0.3197 0.51263 + outer loop + vertex 0.917782 1.01844 2.56027 + vertex 0.915254 1.01853 2.55639 + vertex 0.917196 1.01379 2.55645 + endloop + endfacet + facet normal -0.778318 -0.319984 0.540213 + outer loop + vertex 0.91935 1.01441 2.56013 + vertex 0.920338 1.01758 2.56343 + vertex 0.917782 1.01844 2.56027 + endloop + endfacet + facet normal -0.823235 -0.336572 0.457169 + outer loop + vertex 0.913721 1.01734 2.55275 + vertex 0.915254 1.01853 2.55639 + vertex 0.913414 1.02042 2.55447 + endloop + endfacet + facet normal -0.822219 -0.326184 0.466434 + outer loop + vertex 0.914075 1.02272 2.55724 + vertex 0.913414 1.02042 2.55447 + vertex 0.915254 1.01853 2.55639 + endloop + endfacet + facet normal -0.788771 -0.327726 0.520035 + outer loop + vertex 0.914075 1.02272 2.55724 + vertex 0.915254 1.01853 2.55639 + vertex 0.916098 1.02402 2.56113 + endloop + endfacet + facet normal -0.796777 -0.320042 0.512562 + outer loop + vertex 0.916098 1.02402 2.56113 + vertex 0.915254 1.01853 2.55639 + vertex 0.917782 1.01844 2.56027 + endloop + endfacet + facet normal -0.780472 -0.318994 0.537686 + outer loop + vertex 0.917782 1.01844 2.56027 + vertex 0.91896 1.02197 2.56407 + vertex 0.916098 1.02402 2.56113 + endloop + endfacet + facet normal -0.778063 -0.321774 0.539517 + outer loop + vertex 0.920338 1.01758 2.56343 + vertex 0.91896 1.02197 2.56407 + vertex 0.917782 1.01844 2.56027 + endloop + endfacet + facet normal -0.791061 -0.322851 0.519606 + outer loop + vertex 0.913626 1.02667 2.55901 + vertex 0.914075 1.02272 2.55724 + vertex 0.916098 1.02402 2.56113 + endloop + endfacet + facet normal -0.790638 -0.321055 0.521359 + outer loop + vertex 0.914763 1.02904 2.5622 + vertex 0.913626 1.02667 2.55901 + vertex 0.916098 1.02402 2.56113 + endloop + endfacet + facet normal -0.780502 -0.319698 0.537224 + outer loop + vertex 0.918055 1.0257 2.56497 + vertex 0.916098 1.02402 2.56113 + vertex 0.91896 1.02197 2.56407 + endloop + endfacet + facet normal -0.779723 -0.321174 0.537475 + outer loop + vertex 0.918055 1.0257 2.56497 + vertex 0.916671 1.02872 2.56477 + vertex 0.916098 1.02402 2.56113 + endloop + endfacet + facet normal -0.779276 -0.321555 0.537896 + outer loop + vertex 0.916671 1.02872 2.56477 + vertex 0.914763 1.02904 2.5622 + vertex 0.916098 1.02402 2.56113 + endloop + endfacet + facet normal -0.773045 -0.317311 0.549286 + outer loop + vertex 0.918055 1.0257 2.56497 + vertex 0.918598 1.02847 2.56734 + vertex 0.916671 1.02872 2.56477 + endloop + endfacet + facet normal -0.78547 -0.328104 0.524771 + outer loop + vertex 0.913626 1.02667 2.55901 + vertex 0.914763 1.02904 2.5622 + vertex 0.913194 1.03036 2.56067 + endloop + endfacet + facet normal -0.785119 -0.324505 0.527527 + outer loop + vertex 0.913943 1.03211 2.56286 + vertex 0.913194 1.03036 2.56067 + vertex 0.914763 1.02904 2.5622 + endloop + endfacet + facet normal -0.777374 -0.324856 0.538664 + outer loop + vertex 0.913943 1.03211 2.56286 + vertex 0.914763 1.02904 2.5622 + vertex 0.915389 1.03163 2.56466 + endloop + endfacet + facet normal -0.778903 -0.323283 0.5374 + outer loop + vertex 0.915389 1.03163 2.56466 + vertex 0.914763 1.02904 2.5622 + vertex 0.916671 1.02872 2.56477 + endloop + endfacet + facet normal -0.773144 -0.320391 0.547355 + outer loop + vertex 0.916671 1.02872 2.56477 + vertex 0.917296 1.03293 2.56811 + vertex 0.915389 1.03163 2.56466 + endloop + endfacet + facet normal -0.772154 -0.321248 0.548249 + outer loop + vertex 0.918598 1.02847 2.56734 + vertex 0.917296 1.03293 2.56811 + vertex 0.916671 1.02872 2.56477 + endloop + endfacet + facet normal -0.776916 -0.327871 0.537497 + outer loop + vertex 0.913943 1.03211 2.56286 + vertex 0.915389 1.03163 2.56466 + vertex 0.914482 1.03463 2.56518 + endloop + endfacet + facet normal -0.761853 -0.327485 0.558868 + outer loop + vertex 0.9174 1.03693 2.57062 + vertex 0.916372 1.03999 2.57101 + vertex 0.915428 1.03753 2.56828 + endloop + endfacet + facet normal -0.761542 -0.329557 0.558073 + outer loop + vertex 0.917296 1.03293 2.56811 + vertex 0.9174 1.03693 2.57062 + vertex 0.915428 1.03753 2.56828 + endloop + endfacet + facet normal -0.769591 -0.332344 0.545231 + outer loop + vertex 0.917296 1.03293 2.56811 + vertex 0.915428 1.03753 2.56828 + vertex 0.914482 1.03463 2.56518 + endloop + endfacet + facet normal -0.769639 -0.3275 0.548087 + outer loop + vertex 0.917296 1.03293 2.56811 + vertex 0.914482 1.03463 2.56518 + vertex 0.915389 1.03163 2.56466 + endloop + endfacet + facet normal -0.742742 -0.324506 0.585688 + outer loop + vertex 0.9174 1.03693 2.57062 + vertex 0.918276 1.03874 2.57273 + vertex 0.916372 1.03999 2.57101 + endloop + endfacet + facet normal -0.761706 -0.327654 0.55897 + outer loop + vertex 0.914229 1.04136 2.56889 + vertex 0.915428 1.03753 2.56828 + vertex 0.916372 1.03999 2.57101 + endloop + endfacet + facet normal -0.761679 -0.3266 0.559623 + outer loop + vertex 0.915522 1.04225 2.57118 + vertex 0.914229 1.04136 2.56889 + vertex 0.916372 1.03999 2.57101 + endloop + endfacet + facet normal -0.738853 -0.320421 0.592812 + outer loop + vertex 0.916372 1.03999 2.57101 + vertex 0.917299 1.04254 2.57354 + vertex 0.915522 1.04225 2.57118 + endloop + endfacet + facet normal -0.742156 -0.316962 0.590542 + outer loop + vertex 0.918276 1.03874 2.57273 + vertex 0.917299 1.04254 2.57354 + vertex 0.916372 1.03999 2.57101 + endloop + endfacet + facet normal -0.762524 -0.324925 0.559447 + outer loop + vertex 0.914229 1.04136 2.56889 + vertex 0.915522 1.04225 2.57118 + vertex 0.914206 1.04456 2.57072 + endloop + endfacet + facet normal -0.716877 -0.330372 0.613956 + outer loop + vertex 0.918409 1.04548 2.57631 + vertex 0.91632 1.04989 2.57624 + vertex 0.915146 1.04737 2.57351 + endloop + endfacet + facet normal -0.715881 -0.315227 0.623015 + outer loop + vertex 0.917299 1.04254 2.57354 + vertex 0.918409 1.04548 2.57631 + vertex 0.915146 1.04737 2.57351 + endloop + endfacet + facet normal -0.744792 -0.328372 0.580911 + outer loop + vertex 0.917299 1.04254 2.57354 + vertex 0.915146 1.04737 2.57351 + vertex 0.914206 1.04456 2.57072 + endloop + endfacet + facet normal -0.743198 -0.307045 0.594457 + outer loop + vertex 0.917299 1.04254 2.57354 + vertex 0.914206 1.04456 2.57072 + vertex 0.915522 1.04225 2.57118 + endloop + endfacet + facet normal -0.679414 -0.311842 0.664192 + outer loop + vertex 0.918409 1.04548 2.57631 + vertex 0.919723 1.04781 2.57875 + vertex 0.91632 1.04989 2.57624 + endloop + endfacet + facet normal -0.724248 -0.322242 0.609611 + outer loop + vertex 0.91269 1.0524 2.57326 + vertex 0.915146 1.04737 2.57351 + vertex 0.91632 1.04989 2.57624 + endloop + endfacet + facet normal -0.726215 -0.338436 0.598392 + outer loop + vertex 0.914881 1.05282 2.57615 + vertex 0.91269 1.0524 2.57326 + vertex 0.91632 1.04989 2.57624 + endloop + endfacet + facet normal -0.684475 -0.316108 0.65694 + outer loop + vertex 0.91632 1.04989 2.57624 + vertex 0.917243 1.05299 2.57869 + vertex 0.914881 1.05282 2.57615 + endloop + endfacet + facet normal -0.68052 -0.319311 0.659495 + outer loop + vertex 0.919723 1.04781 2.57875 + vertex 0.917243 1.05299 2.57869 + vertex 0.91632 1.04989 2.57624 + endloop + endfacet + facet normal -0.728411 -0.332291 0.599166 + outer loop + vertex 0.91269 1.0524 2.57326 + vertex 0.914881 1.05282 2.57615 + vertex 0.91352 1.05563 2.57605 + endloop + endfacet + facet normal -0.655663 -0.297505 0.693972 + outer loop + vertex 0.917613 1.05627 2.58053 + vertex 0.916328 1.06007 2.58094 + vertex 0.914717 1.05798 2.57853 + endloop + endfacet + facet normal -0.657796 -0.309936 0.686472 + outer loop + vertex 0.917243 1.05299 2.57869 + vertex 0.917613 1.05627 2.58053 + vertex 0.914717 1.05798 2.57853 + endloop + endfacet + facet normal -0.68988 -0.327547 0.645584 + outer loop + vertex 0.917243 1.05299 2.57869 + vertex 0.914717 1.05798 2.57853 + vertex 0.91352 1.05563 2.57605 + endloop + endfacet + facet normal -0.686201 -0.309833 0.658128 + outer loop + vertex 0.917243 1.05299 2.57869 + vertex 0.91352 1.05563 2.57605 + vertex 0.914881 1.05282 2.57615 + endloop + endfacet + facet normal -0.598771 -0.284215 0.748796 + outer loop + vertex 0.917613 1.05627 2.58053 + vertex 0.919878 1.05697 2.58261 + vertex 0.916328 1.06007 2.58094 + endloop + endfacet + facet normal -0.654243 -0.299272 0.694552 + outer loop + vertex 0.912389 1.06289 2.57845 + vertex 0.914717 1.05798 2.57853 + vertex 0.916328 1.06007 2.58094 + endloop + endfacet + facet normal -0.658549 -0.31517 0.68336 + outer loop + vertex 0.914884 1.06385 2.5813 + vertex 0.912389 1.06289 2.57845 + vertex 0.916328 1.06007 2.58094 + endloop + endfacet + facet normal -0.590932 -0.295599 0.750613 + outer loop + vertex 0.916328 1.06007 2.58094 + vertex 0.918689 1.0624 2.58372 + vertex 0.914884 1.06385 2.5813 + endloop + endfacet + facet normal -0.599033 -0.284733 0.748389 + outer loop + vertex 0.919878 1.05697 2.58261 + vertex 0.918689 1.0624 2.58372 + vertex 0.916328 1.06007 2.58094 + endloop + endfacet + facet normal -0.650001 -0.334498 0.682356 + outer loop + vertex 0.912389 1.06289 2.57845 + vertex 0.914884 1.06385 2.5813 + vertex 0.912649 1.06632 2.58038 + endloop + endfacet + facet normal -0.630143 -0.304639 0.714223 + outer loop + vertex 0.914884 1.06385 2.5813 + vertex 0.914657 1.06715 2.5825 + vertex 0.912649 1.06632 2.58038 + endloop + endfacet + facet normal -0.592291 -0.312441 0.742679 + outer loop + vertex 0.914884 1.06385 2.5813 + vertex 0.918689 1.0624 2.58372 + vertex 0.914657 1.06715 2.5825 + endloop + endfacet + facet normal -0.578817 -0.296657 0.759582 + outer loop + vertex 0.918689 1.0624 2.58372 + vertex 0.917344 1.06779 2.5848 + vertex 0.914657 1.06715 2.5825 + endloop + endfacet + facet normal -0.57974 -0.311312 0.752985 + outer loop + vertex 0.916893 1.07118 2.58577 + vertex 0.915477 1.07423 2.58594 + vertex 0.913181 1.07237 2.5834 + endloop + endfacet + facet normal -0.578938 -0.293313 0.760788 + outer loop + vertex 0.916893 1.07118 2.58577 + vertex 0.913181 1.07237 2.5834 + vertex 0.917344 1.06779 2.5848 + endloop + endfacet + facet normal -0.579655 -0.294241 0.759883 + outer loop + vertex 0.917344 1.06779 2.5848 + vertex 0.913181 1.07237 2.5834 + vertex 0.914657 1.06715 2.5825 + endloop + endfacet + facet normal -0.510815 -0.282628 0.811905 + outer loop + vertex 0.916893 1.07118 2.58577 + vertex 0.919073 1.07273 2.58768 + vertex 0.915477 1.07423 2.58594 + endloop + endfacet + facet normal -0.574611 -0.318756 0.753802 + outer loop + vertex 0.913181 1.07237 2.5834 + vertex 0.915477 1.07423 2.58594 + vertex 0.913169 1.07657 2.58517 + endloop + endfacet + facet normal -0.548186 -0.281657 0.787503 + outer loop + vertex 0.915477 1.07423 2.58594 + vertex 0.915524 1.07806 2.58734 + vertex 0.913169 1.07657 2.58517 + endloop + endfacet + facet normal -0.512165 -0.289803 0.808518 + outer loop + vertex 0.915477 1.07423 2.58594 + vertex 0.919073 1.07273 2.58768 + vertex 0.915524 1.07806 2.58734 + endloop + endfacet + facet normal -0.483142 -0.268907 0.833224 + outer loop + vertex 0.919073 1.07273 2.58768 + vertex 0.919687 1.07696 2.5894 + vertex 0.915524 1.07806 2.58734 + endloop + endfacet + facet normal -0.484056 -0.280542 0.828846 + outer loop + vertex 0.919687 1.07696 2.5894 + vertex 0.917024 1.08223 2.58963 + vertex 0.915524 1.07806 2.58734 + endloop + endfacet + facet normal -0.495926 -0.27367 0.824113 + outer loop + vertex 0.915524 1.07806 2.58734 + vertex 0.917024 1.08223 2.58963 + vertex 0.913068 1.08311 2.58754 + endloop + endfacet + facet normal -0.485431 -0.281169 0.827829 + outer loop + vertex 0.916963 1.08612 2.59087 + vertex 0.915724 1.08917 2.59118 + vertex 0.913723 1.08726 2.58936 + endloop + endfacet + facet normal -0.48423 -0.273346 0.831145 + outer loop + vertex 0.916963 1.08612 2.59087 + vertex 0.913723 1.08726 2.58936 + vertex 0.917024 1.08223 2.58963 + endloop + endfacet + facet normal -0.496194 -0.281722 0.821234 + outer loop + vertex 0.917024 1.08223 2.58963 + vertex 0.913723 1.08726 2.58936 + vertex 0.913068 1.08311 2.58754 + endloop + endfacet + facet normal -0.42933 -0.262049 0.864295 + outer loop + vertex 0.916963 1.08612 2.59087 + vertex 0.91911 1.08784 2.59246 + vertex 0.915724 1.08917 2.59118 + endloop + endfacet + facet normal -0.491885 -0.273287 0.826658 + outer loop + vertex 0.913723 1.08726 2.58936 + vertex 0.915724 1.08917 2.59118 + vertex 0.913287 1.09131 2.59044 + endloop + endfacet + facet normal -0.477747 -0.25194 0.841596 + outer loop + vertex 0.915724 1.08917 2.59118 + vertex 0.915725 1.093 2.59232 + vertex 0.913287 1.09131 2.59044 + endloop + endfacet + facet normal -0.428644 -0.259117 0.865519 + outer loop + vertex 0.915724 1.08917 2.59118 + vertex 0.91911 1.08784 2.59246 + vertex 0.915725 1.093 2.59232 + endloop + endfacet + facet normal -0.421016 -0.253965 0.870774 + outer loop + vertex 0.91911 1.08784 2.59246 + vertex 0.920029 1.09202 2.59412 + vertex 0.915725 1.093 2.59232 + endloop + endfacet + facet normal -0.42175 -0.262581 0.867859 + outer loop + vertex 0.920029 1.09202 2.59412 + vertex 0.917424 1.09716 2.59441 + vertex 0.915725 1.093 2.59232 + endloop + endfacet + facet normal -0.44359 -0.250043 0.860643 + outer loop + vertex 0.915725 1.093 2.59232 + vertex 0.917424 1.09716 2.59441 + vertex 0.913264 1.09814 2.59255 + endloop + endfacet + facet normal -0.443988 -0.254693 0.859073 + outer loop + vertex 0.917424 1.09716 2.59441 + vertex 0.914493 1.10177 2.59426 + vertex 0.913264 1.09814 2.59255 + endloop + endfacet + facet normal -0.529202 -0.196299 0.825477 + outer loop + vertex 0.915384 1.17785 2.61225 + vertex 0.917227 1.18165 2.61434 + vertex 0.913302 1.18313 2.61218 + endloop + endfacet + facet normal -0.563552 -0.184064 0.805313 + outer loop + vertex 0.918431 1.18508 2.61604 + vertex 0.916849 1.18965 2.61598 + vertex 0.914952 1.18657 2.61395 + endloop + endfacet + facet normal -0.566479 -0.198644 0.799776 + outer loop + vertex 0.918431 1.18508 2.61604 + vertex 0.914952 1.18657 2.61395 + vertex 0.917227 1.18165 2.61434 + endloop + endfacet + facet normal -0.525623 -0.177174 0.832064 + outer loop + vertex 0.917227 1.18165 2.61434 + vertex 0.914952 1.18657 2.61395 + vertex 0.913302 1.18313 2.61218 + endloop + endfacet + facet normal -0.604494 -0.198687 0.771434 + outer loop + vertex 0.918431 1.18508 2.61604 + vertex 0.920216 1.1877 2.61812 + vertex 0.916849 1.18965 2.61598 + endloop + endfacet + facet normal -0.554625 -0.192357 0.809561 + outer loop + vertex 0.913224 1.19159 2.61396 + vertex 0.914952 1.18657 2.61395 + vertex 0.916849 1.18965 2.61598 + endloop + endfacet + facet normal -0.547817 -0.169497 0.819248 + outer loop + vertex 0.9155 1.19452 2.61609 + vertex 0.913224 1.19159 2.61396 + vertex 0.916849 1.18965 2.61598 + endloop + endfacet + facet normal -0.60864 -0.185314 0.771503 + outer loop + vertex 0.916849 1.18965 2.61598 + vertex 0.918901 1.19239 2.61826 + vertex 0.9155 1.19452 2.61609 + endloop + endfacet + facet normal -0.602687 -0.192247 0.774474 + outer loop + vertex 0.920216 1.1877 2.61812 + vertex 0.918901 1.19239 2.61826 + vertex 0.916849 1.18965 2.61598 + endloop + endfacet + facet normal -0.557986 -0.158248 0.814622 + outer loop + vertex 0.911962 1.19714 2.61417 + vertex 0.913224 1.19159 2.61396 + vertex 0.9155 1.19452 2.61609 + endloop + endfacet + facet normal -0.545616 -0.132156 0.82755 + outer loop + vertex 0.91461 1.19843 2.61612 + vertex 0.911962 1.19714 2.61417 + vertex 0.9155 1.19452 2.61609 + endloop + endfacet + facet normal -0.621526 -0.1489 0.769113 + outer loop + vertex 0.9155 1.19452 2.61609 + vertex 0.917603 1.19777 2.61842 + vertex 0.91461 1.19843 2.61612 + endloop + endfacet + facet normal -0.603184 -0.168301 0.779643 + outer loop + vertex 0.918901 1.19239 2.61826 + vertex 0.917603 1.19777 2.61842 + vertex 0.9155 1.19452 2.61609 + endloop + endfacet + facet normal -0.56381 -0.0853125 0.821487 + outer loop + vertex 0.911962 1.19714 2.61417 + vertex 0.91461 1.19843 2.61612 + vertex 0.912982 1.20078 2.61525 + endloop + endfacet + facet normal -0.590357 -0.111811 0.79936 + outer loop + vertex 0.91461 1.19843 2.61612 + vertex 0.915113 1.20161 2.61694 + vertex 0.912982 1.20078 2.61525 + endloop + endfacet + facet normal -0.618806 -0.102059 0.778886 + outer loop + vertex 0.91461 1.19843 2.61612 + vertex 0.917603 1.19777 2.61842 + vertex 0.915113 1.20161 2.61694 + endloop + endfacet + facet normal -0.641899 -0.125687 0.756418 + outer loop + vertex 0.917603 1.19777 2.61842 + vertex 0.917672 1.20313 2.61937 + vertex 0.915113 1.20161 2.61694 + endloop + endfacet + facet normal -0.582024 -0.0217921 0.81288 + outer loop + vertex 0.91406 1.20881 2.6166 + vertex 0.911947 1.20681 2.61504 + vertex 0.914852 1.20549 2.61708 + endloop + endfacet + facet normal -0.663344 -0.0712439 0.744915 + outer loop + vertex 0.914852 1.20549 2.61708 + vertex 0.915113 1.20161 2.61694 + vertex 0.917672 1.20313 2.61937 + endloop + endfacet + facet normal -0.647799 -0.0371334 0.760906 + outer loop + vertex 0.914852 1.20549 2.61708 + vertex 0.917672 1.20313 2.61937 + vertex 0.917102 1.20831 2.61913 + endloop + endfacet + facet normal -0.643247 -0.0433345 0.764432 + outer loop + vertex 0.914852 1.20549 2.61708 + vertex 0.917102 1.20831 2.61913 + vertex 0.91406 1.20881 2.6166 + endloop + endfacet + facet normal -0.710228 -0.046644 0.702425 + outer loop + vertex 0.917102 1.20831 2.61913 + vertex 0.917672 1.20313 2.61937 + vertex 0.918783 1.20552 2.62065 + endloop + endfacet + facet normal -0.643038 0.0280255 0.765321 + outer loop + vertex 0.918783 1.20552 2.62065 + vertex 0.920518 1.20723 2.62204 + vertex 0.917102 1.20831 2.61913 + endloop + endfacet + facet normal -0.564491 -0.0490007 0.823983 + outer loop + vertex 0.911392 1.21135 2.61492 + vertex 0.911947 1.20681 2.61504 + vertex 0.91406 1.20881 2.6166 + endloop + endfacet + facet normal -0.566573 -0.0522647 0.822352 + outer loop + vertex 0.91461 1.21149 2.61715 + vertex 0.911392 1.21135 2.61492 + vertex 0.91406 1.20881 2.6166 + endloop + endfacet + facet normal -0.634775 -0.0224523 0.772371 + outer loop + vertex 0.916744 1.21352 2.61899 + vertex 0.917102 1.20831 2.61913 + vertex 0.919181 1.21104 2.62092 + endloop + endfacet + facet normal -0.640043 -0.0229332 0.767996 + outer loop + vertex 0.916744 1.21352 2.61899 + vertex 0.91461 1.21149 2.61715 + vertex 0.917102 1.20831 2.61913 + endloop + endfacet + facet normal -0.641883 -0.0253746 0.766383 + outer loop + vertex 0.91461 1.21149 2.61715 + vertex 0.91406 1.20881 2.6166 + vertex 0.917102 1.20831 2.61913 + endloop + endfacet + facet normal -0.649105 -0.00388511 0.760689 + outer loop + vertex 0.919181 1.21104 2.62092 + vertex 0.917102 1.20831 2.61913 + vertex 0.920518 1.20723 2.62204 + endloop + endfacet + facet normal -0.565672 -0.0664145 0.821952 + outer loop + vertex 0.911392 1.21135 2.61492 + vertex 0.91461 1.21149 2.61715 + vertex 0.913169 1.21506 2.61645 + endloop + endfacet + facet normal -0.604074 -0.130742 0.78613 + outer loop + vertex 0.917861 1.21659 2.62011 + vertex 0.917174 1.22019 2.62018 + vertex 0.915116 1.21799 2.61824 + endloop + endfacet + facet normal -0.589835 -0.0794252 0.803608 + outer loop + vertex 0.916744 1.21352 2.61899 + vertex 0.917861 1.21659 2.62011 + vertex 0.915116 1.21799 2.61824 + endloop + endfacet + facet normal -0.601666 -0.0853104 0.794179 + outer loop + vertex 0.916744 1.21352 2.61899 + vertex 0.915116 1.21799 2.61824 + vertex 0.913169 1.21506 2.61645 + endloop + endfacet + facet normal -0.60196 -0.0865849 0.793818 + outer loop + vertex 0.916744 1.21352 2.61899 + vertex 0.913169 1.21506 2.61645 + vertex 0.91461 1.21149 2.61715 + endloop + endfacet + facet normal -0.610668 -0.131899 0.780825 + outer loop + vertex 0.917861 1.21659 2.62011 + vertex 0.920313 1.21744 2.62217 + vertex 0.917174 1.22019 2.62018 + endloop + endfacet + facet normal -0.585014 -0.157084 0.795666 + outer loop + vertex 0.913582 1.22303 2.6181 + vertex 0.915116 1.21799 2.61824 + vertex 0.917174 1.22019 2.62018 + endloop + endfacet + facet normal -0.589144 -0.165833 0.790828 + outer loop + vertex 0.91648 1.22461 2.62059 + vertex 0.913582 1.22303 2.6181 + vertex 0.917174 1.22019 2.62018 + endloop + endfacet + facet normal -0.59473 -0.166311 0.786535 + outer loop + vertex 0.917174 1.22019 2.62018 + vertex 0.919179 1.22191 2.62206 + vertex 0.91648 1.22461 2.62059 + endloop + endfacet + facet normal -0.612872 -0.136201 0.778356 + outer loop + vertex 0.920313 1.21744 2.62217 + vertex 0.919179 1.22191 2.62206 + vertex 0.917174 1.22019 2.62018 + endloop + endfacet + facet normal -0.58664 -0.171469 0.791487 + outer loop + vertex 0.9137 1.22732 2.61912 + vertex 0.913582 1.22303 2.6181 + vertex 0.91648 1.22461 2.62059 + endloop + endfacet + facet normal -0.593408 -0.182513 0.783937 + outer loop + vertex 0.915657 1.22929 2.62106 + vertex 0.9137 1.22732 2.61912 + vertex 0.91648 1.22461 2.62059 + endloop + endfacet + facet normal -0.584965 -0.181675 0.790449 + outer loop + vertex 0.91648 1.22461 2.62059 + vertex 0.919386 1.22642 2.62316 + vertex 0.915657 1.22929 2.62106 + endloop + endfacet + facet normal -0.593488 -0.164339 0.787887 + outer loop + vertex 0.919179 1.22191 2.62206 + vertex 0.919386 1.22642 2.62316 + vertex 0.91648 1.22461 2.62059 + endloop + endfacet + facet normal -0.589589 -0.187907 0.785541 + outer loop + vertex 0.912116 1.23192 2.61903 + vertex 0.9137 1.22732 2.61912 + vertex 0.915657 1.22929 2.62106 + endloop + endfacet + facet normal -0.585965 -0.179443 0.790219 + outer loop + vertex 0.914551 1.23322 2.62113 + vertex 0.912116 1.23192 2.61903 + vertex 0.915657 1.22929 2.62106 + endloop + endfacet + facet normal -0.593699 -0.181499 0.783952 + outer loop + vertex 0.915657 1.22929 2.62106 + vertex 0.917722 1.23254 2.62338 + vertex 0.914551 1.23322 2.62113 + endloop + endfacet + facet normal -0.58762 -0.187593 0.787091 + outer loop + vertex 0.919386 1.22642 2.62316 + vertex 0.917722 1.23254 2.62338 + vertex 0.915657 1.22929 2.62106 + endloop + endfacet + facet normal -0.589091 -0.172377 0.789467 + outer loop + vertex 0.912116 1.23192 2.61903 + vertex 0.914551 1.23322 2.62113 + vertex 0.912475 1.2358 2.62015 + endloop + endfacet + facet normal -0.600529 -0.186147 0.777634 + outer loop + vertex 0.914551 1.23322 2.62113 + vertex 0.914812 1.23668 2.62216 + vertex 0.912475 1.2358 2.62015 + endloop + endfacet + facet normal -0.593908 -0.188024 0.782253 + outer loop + vertex 0.914551 1.23322 2.62113 + vertex 0.917722 1.23254 2.62338 + vertex 0.914812 1.23668 2.62216 + endloop + endfacet + facet normal -0.595849 -0.189958 0.780308 + outer loop + vertex 0.917722 1.23254 2.62338 + vertex 0.917592 1.23755 2.6245 + vertex 0.914812 1.23668 2.62216 + endloop + endfacet + facet normal -0.589741 -0.174561 0.788501 + outer loop + vertex 0.917953 1.24106 2.62555 + vertex 0.916991 1.24495 2.62569 + vertex 0.914818 1.24155 2.62331 + endloop + endfacet + facet normal -0.589739 -0.175286 0.788342 + outer loop + vertex 0.917953 1.24106 2.62555 + vertex 0.914818 1.24155 2.62331 + vertex 0.917592 1.23755 2.6245 + endloop + endfacet + facet normal -0.59792 -0.18335 0.780304 + outer loop + vertex 0.917592 1.23755 2.6245 + vertex 0.914818 1.24155 2.62331 + vertex 0.914812 1.23668 2.62216 + endloop + endfacet + facet normal -0.499192 -0.154452 0.852615 + outer loop + vertex 0.917953 1.24106 2.62555 + vertex 0.920761 1.24276 2.6275 + vertex 0.916991 1.24495 2.62569 + endloop + endfacet + facet normal -0.591204 -0.173088 0.78773 + outer loop + vertex 0.913471 1.24698 2.62349 + vertex 0.914818 1.24155 2.62331 + vertex 0.916991 1.24495 2.62569 + endloop + endfacet + facet normal -0.59639 -0.190829 0.779682 + outer loop + vertex 0.915701 1.24974 2.62588 + vertex 0.913471 1.24698 2.62349 + vertex 0.916991 1.24495 2.62569 + endloop + endfacet + facet normal -0.52444 -0.173564 0.833569 + outer loop + vertex 0.916991 1.24495 2.62569 + vertex 0.91944 1.24791 2.62785 + vertex 0.915701 1.24974 2.62588 + endloop + endfacet + facet normal -0.51167 -0.187673 0.838435 + outer loop + vertex 0.920761 1.24276 2.6275 + vertex 0.91944 1.24791 2.62785 + vertex 0.916991 1.24495 2.62569 + endloop + endfacet + facet normal -0.608894 -0.175502 0.773594 + outer loop + vertex 0.911882 1.25246 2.62349 + vertex 0.913471 1.24698 2.62349 + vertex 0.915701 1.24974 2.62588 + endloop + endfacet + facet normal -0.617779 -0.1993 0.760676 + outer loop + vertex 0.914709 1.25363 2.62609 + vertex 0.911882 1.25246 2.62349 + vertex 0.915701 1.24974 2.62588 + endloop + endfacet + facet normal -0.555821 -0.186182 0.810185 + outer loop + vertex 0.915701 1.24974 2.62588 + vertex 0.917664 1.25268 2.6279 + vertex 0.914709 1.25363 2.62609 + endloop + endfacet + facet normal -0.53377 -0.207488 0.819779 + outer loop + vertex 0.91944 1.24791 2.62785 + vertex 0.917664 1.25268 2.6279 + vertex 0.915701 1.24974 2.62588 + endloop + endfacet + facet normal -0.625703 -0.177585 0.759579 + outer loop + vertex 0.911882 1.25246 2.62349 + vertex 0.914709 1.25363 2.62609 + vertex 0.912883 1.25609 2.62516 + endloop + endfacet + facet normal -0.611356 -0.161254 0.774752 + outer loop + vertex 0.914709 1.25363 2.62609 + vertex 0.915348 1.25725 2.62735 + vertex 0.912883 1.25609 2.62516 + endloop + endfacet + facet normal -0.555505 -0.183677 0.810973 + outer loop + vertex 0.914709 1.25363 2.62609 + vertex 0.917664 1.25268 2.6279 + vertex 0.915348 1.25725 2.62735 + endloop + endfacet + facet normal -0.517773 -0.160986 0.840235 + outer loop + vertex 0.917664 1.25268 2.6279 + vertex 0.919084 1.2562 2.62945 + vertex 0.915348 1.25725 2.62735 + endloop + endfacet + facet normal -0.519912 -0.178318 0.835401 + outer loop + vertex 0.919084 1.2562 2.62945 + vertex 0.917131 1.26117 2.62929 + vertex 0.915348 1.25725 2.62735 + endloop + endfacet + facet normal -0.56232 -0.148159 0.813539 + outer loop + vertex 0.915348 1.25725 2.62735 + vertex 0.917131 1.26117 2.62929 + vertex 0.914046 1.26159 2.62724 + endloop + endfacet + facet normal -0.545785 -0.10927 0.83077 + outer loop + vertex 0.917517 1.26539 2.6302 + vertex 0.916865 1.26962 2.63032 + vertex 0.914406 1.26596 2.62823 + endloop + endfacet + facet normal -0.54697 -0.127202 0.827432 + outer loop + vertex 0.917517 1.26539 2.6302 + vertex 0.914406 1.26596 2.62823 + vertex 0.917131 1.26117 2.62929 + endloop + endfacet + facet normal -0.562197 -0.13854 0.815317 + outer loop + vertex 0.917131 1.26117 2.62929 + vertex 0.914406 1.26596 2.62823 + vertex 0.914046 1.26159 2.62724 + endloop + endfacet + facet normal -0.35848 -0.0833407 0.92981 + outer loop + vertex 0.917517 1.26539 2.6302 + vertex 0.920725 1.26801 2.63167 + vertex 0.916865 1.26962 2.63032 + endloop + endfacet + facet normal -0.546204 -0.108862 0.830548 + outer loop + vertex 0.9136 1.2716 2.62844 + vertex 0.914406 1.26596 2.62823 + vertex 0.916865 1.26962 2.63032 + endloop + endfacet + facet normal -0.547526 -0.1123 0.829219 + outer loop + vertex 0.916245 1.27475 2.63061 + vertex 0.9136 1.2716 2.62844 + vertex 0.916865 1.26962 2.63032 + endloop + endfacet + facet normal -0.384848 -0.0975835 0.917807 + outer loop + vertex 0.916865 1.26962 2.63032 + vertex 0.919998 1.27341 2.63204 + vertex 0.916245 1.27475 2.63061 + endloop + endfacet + facet normal -0.368523 -0.113275 0.922691 + outer loop + vertex 0.920725 1.26801 2.63167 + vertex 0.919998 1.27341 2.63204 + vertex 0.916865 1.26962 2.63032 + endloop + endfacet + facet normal -0.551929 -0.10706 0.82699 + outer loop + vertex 0.912906 1.27677 2.62864 + vertex 0.9136 1.2716 2.62844 + vertex 0.916245 1.27475 2.63061 + endloop + endfacet + facet normal -0.555057 -0.115372 0.823773 + outer loop + vertex 0.915529 1.27984 2.63084 + vertex 0.912906 1.27677 2.62864 + vertex 0.916245 1.27475 2.63061 + endloop + endfacet + facet normal -0.402622 -0.0978542 0.910121 + outer loop + vertex 0.916245 1.27475 2.63061 + vertex 0.919463 1.27856 2.63244 + vertex 0.915529 1.27984 2.63084 + endloop + endfacet + facet normal -0.388669 -0.111787 0.914571 + outer loop + vertex 0.919998 1.27341 2.63204 + vertex 0.919463 1.27856 2.63244 + vertex 0.916245 1.27475 2.63061 + endloop + endfacet + facet normal -0.560997 -0.108124 0.820726 + outer loop + vertex 0.911669 1.28223 2.62852 + vertex 0.912906 1.27677 2.62864 + vertex 0.915529 1.27984 2.63084 + endloop + endfacet + facet normal -0.574317 -0.144165 0.805839 + outer loop + vertex 0.914811 1.28389 2.63105 + vertex 0.911669 1.28223 2.62852 + vertex 0.915529 1.27984 2.63084 + endloop + endfacet + facet normal -0.410389 -0.120246 0.903948 + outer loop + vertex 0.915529 1.27984 2.63084 + vertex 0.918721 1.28391 2.63283 + vertex 0.914811 1.28389 2.63105 + endloop + endfacet + facet normal -0.408327 -0.122192 0.90462 + outer loop + vertex 0.919463 1.27856 2.63244 + vertex 0.918721 1.28391 2.63283 + vertex 0.915529 1.27984 2.63084 + endloop + endfacet + facet normal -0.565331 -0.164786 0.808236 + outer loop + vertex 0.911669 1.28223 2.62852 + vertex 0.914811 1.28389 2.63105 + vertex 0.912822 1.28613 2.63012 + endloop + endfacet + facet normal -0.511087 -0.0974461 0.853987 + outer loop + vertex 0.914811 1.28389 2.63105 + vertex 0.915928 1.28816 2.63221 + vertex 0.912822 1.28613 2.63012 + endloop + endfacet + facet normal -0.409416 -0.137085 0.90199 + outer loop + vertex 0.914811 1.28389 2.63105 + vertex 0.918721 1.28391 2.63283 + vertex 0.915928 1.28816 2.63221 + endloop + endfacet + facet normal -0.368031 -0.106681 0.923673 + outer loop + vertex 0.918721 1.28391 2.63283 + vertex 0.919921 1.28835 2.63382 + vertex 0.915928 1.28816 2.63221 + endloop + endfacet + facet normal -0.365923 -0.130883 0.921396 + outer loop + vertex 0.919921 1.28835 2.63382 + vertex 0.918891 1.29221 2.63396 + vertex 0.915928 1.28816 2.63221 + endloop + endfacet + facet normal -0.387446 -0.112382 0.915017 + outer loop + vertex 0.915928 1.28816 2.63221 + vertex 0.918891 1.29221 2.63396 + vertex 0.914891 1.29312 2.63238 + endloop + endfacet + facet normal -0.39274 -0.148669 0.907553 + outer loop + vertex 0.918891 1.29221 2.63396 + vertex 0.917542 1.29717 2.63419 + vertex 0.914891 1.29312 2.63238 + endloop + endfacet + facet normal -0.433589 -0.11571 0.893651 + outer loop + vertex 0.914891 1.29312 2.63238 + vertex 0.917542 1.29717 2.63419 + vertex 0.913885 1.297 2.63239 + endloop + endfacet + facet normal -0.427148 -0.144691 0.89253 + outer loop + vertex 0.918126 1.30137 2.6351 + vertex 0.917097 1.3051 2.63521 + vertex 0.914583 1.30141 2.63341 + endloop + endfacet + facet normal -0.427675 -0.134634 0.89385 + outer loop + vertex 0.918126 1.30137 2.6351 + vertex 0.914583 1.30141 2.63341 + vertex 0.917542 1.29717 2.63419 + endloop + endfacet + facet normal -0.431531 -0.137751 0.891519 + outer loop + vertex 0.917542 1.29717 2.63419 + vertex 0.914583 1.30141 2.63341 + vertex 0.913885 1.297 2.63239 + endloop + endfacet + facet normal -0.268679 -0.102791 0.957729 + outer loop + vertex 0.918126 1.30137 2.6351 + vertex 0.920818 1.30404 2.63614 + vertex 0.917097 1.3051 2.63521 + endloop + endfacet + facet normal -0.458047 -0.118017 0.881059 + outer loop + vertex 0.913551 1.30676 2.63359 + vertex 0.914583 1.30141 2.63341 + vertex 0.917097 1.3051 2.63521 + endloop + endfacet + facet normal -0.461768 -0.129377 0.877515 + outer loop + vertex 0.91617 1.30978 2.63542 + vertex 0.913551 1.30676 2.63359 + vertex 0.917097 1.3051 2.63521 + endloop + endfacet + facet normal -0.293112 -0.0992186 0.950916 + outer loop + vertex 0.917097 1.3051 2.63521 + vertex 0.920042 1.30851 2.63648 + vertex 0.91617 1.30978 2.63542 + endloop + endfacet + facet normal -0.27243 -0.118525 0.954848 + outer loop + vertex 0.920818 1.30404 2.63614 + vertex 0.920042 1.30851 2.63648 + vertex 0.917097 1.3051 2.63521 + endloop + endfacet + facet normal -0.480745 -0.108453 0.870128 + outer loop + vertex 0.912366 1.31213 2.63361 + vertex 0.913551 1.30676 2.63359 + vertex 0.91617 1.30978 2.63542 + endloop + endfacet + facet normal -0.491901 -0.134064 0.860267 + outer loop + vertex 0.915377 1.31456 2.63571 + vertex 0.912366 1.31213 2.63361 + vertex 0.91617 1.30978 2.63542 + endloop + endfacet + facet normal -0.293975 -0.10664 0.949845 + outer loop + vertex 0.91617 1.30978 2.63542 + vertex 0.919329 1.31336 2.6368 + vertex 0.915377 1.31456 2.63571 + endloop + endfacet + facet normal -0.294912 -0.10574 0.949656 + outer loop + vertex 0.920042 1.30851 2.63648 + vertex 0.919329 1.31336 2.6368 + vertex 0.91617 1.30978 2.63542 + endloop + endfacet + facet normal -0.480036 -0.152028 0.863975 + outer loop + vertex 0.912294 1.31685 2.6344 + vertex 0.912366 1.31213 2.63361 + vertex 0.915377 1.31456 2.63571 + endloop + endfacet + facet normal -0.475061 -0.142871 0.868277 + outer loop + vertex 0.914653 1.31837 2.63594 + vertex 0.912294 1.31685 2.6344 + vertex 0.915377 1.31456 2.63571 + endloop + endfacet + facet normal -0.282557 -0.111515 0.952746 + outer loop + vertex 0.915377 1.31456 2.63571 + vertex 0.918529 1.31879 2.63714 + vertex 0.914653 1.31837 2.63594 + endloop + endfacet + facet normal -0.293052 -0.102959 0.950537 + outer loop + vertex 0.919329 1.31336 2.6368 + vertex 0.918529 1.31879 2.63714 + vertex 0.915377 1.31456 2.63571 + endloop + endfacet + facet normal -0.479464 -0.134908 0.86713 + outer loop + vertex 0.912294 1.31685 2.6344 + vertex 0.914653 1.31837 2.63594 + vertex 0.912631 1.32039 2.63514 + endloop + endfacet + facet normal -0.419002 -0.0588295 0.906077 + outer loop + vertex 0.914653 1.31837 2.63594 + vertex 0.915672 1.32287 2.6367 + vertex 0.912631 1.32039 2.63514 + endloop + endfacet + facet normal -0.284388 -0.0974183 0.953747 + outer loop + vertex 0.914653 1.31837 2.63594 + vertex 0.918529 1.31879 2.63714 + vertex 0.915672 1.32287 2.6367 + endloop + endfacet + facet normal -0.257221 -0.0773826 0.963249 + outer loop + vertex 0.918529 1.31879 2.63714 + vertex 0.919808 1.32388 2.63789 + vertex 0.915672 1.32287 2.6367 + endloop + endfacet + facet normal -0.254754 -0.0872925 0.963058 + outer loop + vertex 0.919808 1.32388 2.63789 + vertex 0.919189 1.32793 2.63809 + vertex 0.915672 1.32287 2.6367 + endloop + endfacet + facet normal -0.2741 -0.0727239 0.958948 + outer loop + vertex 0.915672 1.32287 2.6367 + vertex 0.919189 1.32793 2.63809 + vertex 0.915093 1.32828 2.63695 + endloop + endfacet + facet normal -0.274865 -0.0862929 0.957603 + outer loop + vertex 0.919189 1.32793 2.63809 + vertex 0.918951 1.33283 2.63846 + vertex 0.915093 1.32828 2.63695 + endloop + endfacet + facet normal -0.276436 -0.0848529 0.957279 + outer loop + vertex 0.915093 1.32828 2.63695 + vertex 0.918951 1.33283 2.63846 + vertex 0.914868 1.33337 2.63733 + endloop + endfacet + facet normal -0.277669 -0.0973697 0.95573 + outer loop + vertex 0.918951 1.33283 2.63846 + vertex 0.918672 1.33755 2.63886 + vertex 0.914868 1.33337 2.63733 + endloop + endfacet + facet normal -0.288528 -0.0866957 0.953538 + outer loop + vertex 0.914868 1.33337 2.63733 + vertex 0.918672 1.33755 2.63886 + vertex 0.91468 1.33834 2.63773 + endloop + endfacet + facet normal -0.289545 -0.0931714 0.952619 + outer loop + vertex 0.918672 1.33755 2.63886 + vertex 0.918344 1.34212 2.63921 + vertex 0.91468 1.33834 2.63773 + endloop + endfacet + facet normal -0.304997 -0.0768646 0.949246 + outer loop + vertex 0.91468 1.33834 2.63773 + vertex 0.918344 1.34212 2.63921 + vertex 0.91424 1.34322 2.63798 + endloop + endfacet + facet normal -0.30886 -0.0944893 0.946402 + outer loop + vertex 0.918344 1.34212 2.63921 + vertex 0.91747 1.34615 2.63933 + vertex 0.91424 1.34322 2.63798 + endloop + endfacet + facet normal -0.325052 -0.074956 0.942721 + outer loop + vertex 0.91424 1.34322 2.63798 + vertex 0.91747 1.34615 2.63933 + vertex 0.913599 1.34847 2.63818 + endloop + endfacet + facet normal -0.319266 -0.0639373 0.945506 + outer loop + vertex 0.91747 1.34615 2.63933 + vertex 0.918382 1.35071 2.63995 + vertex 0.913599 1.34847 2.63818 + endloop + endfacet + facet normal -0.290643 -0.127303 0.948325 + outer loop + vertex 0.913599 1.34847 2.63818 + vertex 0.918382 1.35071 2.63995 + vertex 0.914436 1.35289 2.63903 + endloop + endfacet + facet normal -0.282622 -0.110879 0.952801 + outer loop + vertex 0.918382 1.35071 2.63995 + vertex 0.916686 1.35624 2.64008 + vertex 0.914436 1.35289 2.63903 + endloop + endfacet + facet normal -0.332416 -0.073427 0.94027 + outer loop + vertex 0.914436 1.35289 2.63903 + vertex 0.916686 1.35624 2.64008 + vertex 0.913005 1.35608 2.63877 + endloop + endfacet + facet normal -0.327037 -0.0888383 0.940827 + outer loop + vertex 0.917153 1.3605 2.64061 + vertex 0.916047 1.36456 2.64061 + vertex 0.913436 1.36057 2.63932 + endloop + endfacet + facet normal -0.327144 -0.0792986 0.941641 + outer loop + vertex 0.917153 1.3605 2.64061 + vertex 0.913436 1.36057 2.63932 + vertex 0.916686 1.35624 2.64008 + endloop + endfacet + facet normal -0.331792 -0.0831309 0.939683 + outer loop + vertex 0.916686 1.35624 2.64008 + vertex 0.913436 1.36057 2.63932 + vertex 0.913005 1.35608 2.63877 + endloop + endfacet + facet normal -0.181539 -0.0492603 0.982149 + outer loop + vertex 0.917153 1.3605 2.64061 + vertex 0.920462 1.36309 2.64135 + vertex 0.916047 1.36456 2.64061 + endloop + endfacet + facet normal -0.342201 -0.0775133 0.936424 + outer loop + vertex 0.912062 1.36635 2.6393 + vertex 0.913436 1.36057 2.63932 + vertex 0.916047 1.36456 2.64061 + endloop + endfacet + facet normal -0.355498 -0.113629 0.927744 + outer loop + vertex 0.915001 1.36859 2.6407 + vertex 0.912062 1.36635 2.6393 + vertex 0.916047 1.36456 2.64061 + endloop + endfacet + facet normal -0.193384 -0.0726433 0.97843 + outer loop + vertex 0.916047 1.36456 2.64061 + vertex 0.919042 1.36895 2.64152 + vertex 0.915001 1.36859 2.6407 + endloop + endfacet + facet normal -0.189683 -0.0752819 0.978955 + outer loop + vertex 0.920462 1.36309 2.64135 + vertex 0.919042 1.36895 2.64152 + vertex 0.916047 1.36456 2.64061 + endloop + endfacet + facet normal -0.353992 -0.115794 0.928052 + outer loop + vertex 0.912062 1.36635 2.6393 + vertex 0.915001 1.36859 2.6407 + vertex 0.912771 1.37064 2.6401 + endloop + endfacet + facet normal -0.304344 -0.0551812 0.950963 + outer loop + vertex 0.915001 1.36859 2.6407 + vertex 0.915928 1.37305 2.64125 + vertex 0.912771 1.37064 2.6401 + endloop + endfacet + facet normal -0.192465 -0.0817602 0.977892 + outer loop + vertex 0.915001 1.36859 2.6407 + vertex 0.919042 1.36895 2.64152 + vertex 0.915928 1.37305 2.64125 + endloop + endfacet + facet normal -0.302763 0.0941122 0.948408 + outer loop + vertex 0.913146 1.65137 2.63974 + vertex 0.912081 1.64602 2.63993 + vertex 0.915597 1.64902 2.64076 + endloop + endfacet + facet normal -0.29619 0.101513 0.949719 + outer loop + vertex 0.916752 1.65284 2.64071 + vertex 0.913146 1.65137 2.63974 + vertex 0.915597 1.64902 2.64076 + endloop + endfacet + facet normal -0.157113 0.0599514 0.985759 + outer loop + vertex 0.915597 1.64902 2.64076 + vertex 0.919457 1.65236 2.64117 + vertex 0.916752 1.65284 2.64071 + endloop + endfacet + facet normal -0.185978 0.0874398 0.978655 + outer loop + vertex 0.916752 1.65284 2.64071 + vertex 0.919304 1.65565 2.64094 + vertex 0.91674 1.65623 2.6404 + endloop + endfacet + facet normal -0.290318 0.0847658 0.953168 + outer loop + vertex 0.916752 1.65284 2.64071 + vertex 0.91674 1.65623 2.6404 + vertex 0.913146 1.65137 2.63974 + endloop + endfacet + facet normal -0.289546 0.0841551 0.953457 + outer loop + vertex 0.913146 1.65137 2.63974 + vertex 0.91674 1.65623 2.6404 + vertex 0.913283 1.65676 2.63931 + endloop + endfacet + facet normal -0.156997 0.0605888 0.985739 + outer loop + vertex 0.919304 1.65565 2.64094 + vertex 0.916752 1.65284 2.64071 + vertex 0.919457 1.65236 2.64117 + endloop + endfacet + facet normal -0.43404 0.17923 0.882885 + outer loop + vertex 0.916479 1.71111 2.63523 + vertex 0.917975 1.71648 2.63488 + vertex 0.912689 1.7119 2.63321 + endloop + endfacet + facet normal -0.374333 0.0959506 0.922317 + outer loop + vertex 0.912689 1.7119 2.63321 + vertex 0.917975 1.71648 2.63488 + vertex 0.913875 1.7175 2.63311 + endloop + endfacet + facet normal -0.367305 0.123447 0.921872 + outer loop + vertex 0.917975 1.71648 2.63488 + vertex 0.918322 1.72187 2.63429 + vertex 0.913875 1.7175 2.63311 + endloop + endfacet + facet normal -0.355014 0.109165 0.928465 + outer loop + vertex 0.913875 1.7175 2.63311 + vertex 0.918322 1.72187 2.63429 + vertex 0.914347 1.72257 2.63269 + endloop + endfacet + facet normal -0.352548 0.121785 0.927835 + outer loop + vertex 0.918322 1.72187 2.63429 + vertex 0.918585 1.72699 2.63372 + vertex 0.914347 1.72257 2.63269 + endloop + endfacet + facet normal -0.346379 0.115134 0.931003 + outer loop + vertex 0.914347 1.72257 2.63269 + vertex 0.918585 1.72699 2.63372 + vertex 0.914634 1.72753 2.63218 + endloop + endfacet + facet normal -0.34457 0.126144 0.930247 + outer loop + vertex 0.918585 1.72699 2.63372 + vertex 0.918675 1.732 2.63308 + vertex 0.914634 1.72753 2.63218 + endloop + endfacet + facet normal -0.336559 0.1181 0.934227 + outer loop + vertex 0.914634 1.72753 2.63218 + vertex 0.918675 1.732 2.63308 + vertex 0.914763 1.73207 2.63166 + endloop + endfacet + facet normal -0.531369 0.15749 0.832373 + outer loop + vertex 0.915132 1.73917 2.63076 + vertex 0.912005 1.73591 2.62938 + vertex 0.914329 1.73525 2.63099 + endloop + endfacet + facet normal -0.357233 0.127355 0.925292 + outer loop + vertex 0.914329 1.73525 2.63099 + vertex 0.918286 1.73709 2.63227 + vertex 0.915132 1.73917 2.63076 + endloop + endfacet + facet normal -0.363073 0.143029 0.920718 + outer loop + vertex 0.914329 1.73525 2.63099 + vertex 0.914763 1.73207 2.63166 + vertex 0.918286 1.73709 2.63227 + endloop + endfacet + facet normal -0.3363 0.122681 0.93373 + outer loop + vertex 0.914763 1.73207 2.63166 + vertex 0.918675 1.732 2.63308 + vertex 0.918286 1.73709 2.63227 + endloop + endfacet + facet normal -0.518881 0.140993 0.843139 + outer loop + vertex 0.912012 1.74068 2.62859 + vertex 0.912005 1.73591 2.62938 + vertex 0.915132 1.73917 2.63076 + endloop + endfacet + facet normal -0.543477 0.0791918 0.83568 + outer loop + vertex 0.915606 1.74406 2.63061 + vertex 0.912012 1.74068 2.62859 + vertex 0.915132 1.73917 2.63076 + endloop + endfacet + facet normal -0.348131 0.0633611 0.935302 + outer loop + vertex 0.915132 1.73917 2.63076 + vertex 0.919151 1.74278 2.63201 + vertex 0.915606 1.74406 2.63061 + endloop + endfacet + facet normal -0.374978 0.097958 0.921844 + outer loop + vertex 0.918286 1.73709 2.63227 + vertex 0.919151 1.74278 2.63201 + vertex 0.915132 1.73917 2.63076 + endloop + endfacet + facet normal -0.514353 0.0356008 0.856839 + outer loop + vertex 0.912717 1.74588 2.6288 + vertex 0.912012 1.74068 2.62859 + vertex 0.915606 1.74406 2.63061 + endloop + endfacet + facet normal -0.539043 -0.0181199 0.842084 + outer loop + vertex 0.91566 1.74878 2.63074 + vertex 0.912717 1.74588 2.6288 + vertex 0.915606 1.74406 2.63061 + endloop + endfacet + facet normal -0.335917 -0.023316 0.941603 + outer loop + vertex 0.915606 1.74406 2.63061 + vertex 0.919295 1.74784 2.63202 + vertex 0.91566 1.74878 2.63074 + endloop + endfacet + facet normal -0.365654 0.00969672 0.9307 + outer loop + vertex 0.919151 1.74278 2.63201 + vertex 0.919295 1.74784 2.63202 + vertex 0.915606 1.74406 2.63061 + endloop + endfacet + facet normal -0.530219 -0.0305728 0.847309 + outer loop + vertex 0.912872 1.7504 2.62906 + vertex 0.912717 1.74588 2.6288 + vertex 0.91566 1.74878 2.63074 + endloop + endfacet + facet normal -0.551633 -0.0859287 0.829649 + outer loop + vertex 0.915148 1.75241 2.63078 + vertex 0.912872 1.7504 2.62906 + vertex 0.91566 1.74878 2.63074 + endloop + endfacet + facet normal -0.339658 -0.0570685 0.938816 + outer loop + vertex 0.91566 1.74878 2.63074 + vertex 0.918798 1.75309 2.63214 + vertex 0.915148 1.75241 2.63078 + endloop + endfacet + facet normal -0.342682 -0.0545589 0.937866 + outer loop + vertex 0.919295 1.74784 2.63202 + vertex 0.918798 1.75309 2.63214 + vertex 0.91566 1.74878 2.63074 + endloop + endfacet + facet normal -0.568192 -0.0595937 0.820735 + outer loop + vertex 0.912872 1.7504 2.62906 + vertex 0.915148 1.75241 2.63078 + vertex 0.913234 1.75408 2.62958 + endloop + endfacet + facet normal -0.5301 0.00369916 0.847927 + outer loop + vertex 0.915148 1.75241 2.63078 + vertex 0.915882 1.75665 2.63122 + vertex 0.913234 1.75408 2.62958 + endloop + endfacet + facet normal -0.34307 -0.0381931 0.938533 + outer loop + vertex 0.915148 1.75241 2.63078 + vertex 0.918798 1.75309 2.63214 + vertex 0.915882 1.75665 2.63122 + endloop + endfacet + facet normal -0.329432 -0.0256269 0.943831 + outer loop + vertex 0.918798 1.75309 2.63214 + vertex 0.919771 1.75797 2.63261 + vertex 0.915882 1.75665 2.63122 + endloop + endfacet + facet normal -0.568878 0.12552 0.812787 + outer loop + vertex 0.915773 1.76409 2.63075 + vertex 0.913315 1.76224 2.62931 + vertex 0.914883 1.76038 2.6307 + endloop + endfacet + facet normal -0.374683 0.0774008 0.923917 + outer loop + vertex 0.914883 1.76038 2.6307 + vertex 0.918587 1.76195 2.63207 + vertex 0.915773 1.76409 2.63075 + endloop + endfacet + facet normal -0.359523 0.0341334 0.932512 + outer loop + vertex 0.914883 1.76038 2.6307 + vertex 0.915882 1.75665 2.63122 + vertex 0.918587 1.76195 2.63207 + endloop + endfacet + facet normal -0.344917 0.0257634 0.93828 + outer loop + vertex 0.915882 1.75665 2.63122 + vertex 0.919771 1.75797 2.63261 + vertex 0.918587 1.76195 2.63207 + endloop + endfacet + facet normal -0.595557 0.18495 0.781733 + outer loop + vertex 0.913944 1.7667 2.62874 + vertex 0.913315 1.76224 2.62931 + vertex 0.915773 1.76409 2.63075 + endloop + endfacet + facet normal -0.590482 0.190454 0.784256 + outer loop + vertex 0.916695 1.76758 2.63059 + vertex 0.913944 1.7667 2.62874 + vertex 0.915773 1.76409 2.63075 + endloop + endfacet + facet normal -0.374785 0.13941 0.91657 + outer loop + vertex 0.915773 1.76409 2.63075 + vertex 0.919155 1.76697 2.63169 + vertex 0.916695 1.76758 2.63059 + endloop + endfacet + facet normal -0.352837 0.10944 0.929263 + outer loop + vertex 0.918587 1.76195 2.63207 + vertex 0.919155 1.76697 2.63169 + vertex 0.915773 1.76409 2.63075 + endloop + endfacet + facet normal -0.444178 0.248365 0.860826 + outer loop + vertex 0.916695 1.76758 2.63059 + vertex 0.919075 1.77015 2.63108 + vertex 0.916959 1.77092 2.62977 + endloop + endfacet + facet normal -0.59466 0.237312 0.768155 + outer loop + vertex 0.916695 1.76758 2.63059 + vertex 0.916959 1.77092 2.62977 + vertex 0.913944 1.7667 2.62874 + endloop + endfacet + facet normal -0.588614 0.231429 0.77458 + outer loop + vertex 0.913944 1.7667 2.62874 + vertex 0.916959 1.77092 2.62977 + vertex 0.914343 1.77192 2.62748 + endloop + endfacet + facet normal -0.367227 0.16687 0.91504 + outer loop + vertex 0.919075 1.77015 2.63108 + vertex 0.916695 1.76758 2.63059 + vertex 0.919155 1.76697 2.63169 + endloop + endfacet + facet normal -0.578614 0.256739 0.774139 + outer loop + vertex 0.916959 1.77092 2.62977 + vertex 0.918402 1.77623 2.62909 + vertex 0.914343 1.77192 2.62748 + endloop + endfacet + facet normal -0.548576 0.216007 0.807716 + outer loop + vertex 0.914343 1.77192 2.62748 + vertex 0.918402 1.77623 2.62909 + vertex 0.914628 1.77673 2.62639 + endloop + endfacet + facet normal -0.60503 0.12918 0.785653 + outer loop + vertex 0.915644 1.78428 2.62577 + vertex 0.913404 1.78304 2.62425 + vertex 0.914001 1.7807 2.62509 + endloop + endfacet + facet normal -0.550376 0.0958184 0.829401 + outer loop + vertex 0.914001 1.7807 2.62509 + vertex 0.918194 1.78172 2.62775 + vertex 0.915644 1.78428 2.62577 + endloop + endfacet + facet normal -0.558161 0.176891 0.810658 + outer loop + vertex 0.914001 1.7807 2.62509 + vertex 0.914628 1.77673 2.62639 + vertex 0.918194 1.78172 2.62775 + endloop + endfacet + facet normal -0.55686 0.175643 0.811823 + outer loop + vertex 0.914628 1.77673 2.62639 + vertex 0.918402 1.77623 2.62909 + vertex 0.918194 1.78172 2.62775 + endloop + endfacet + facet normal -0.612173 0.154506 0.775482 + outer loop + vertex 0.913366 1.78594 2.62364 + vertex 0.913404 1.78304 2.62425 + vertex 0.915644 1.78428 2.62577 + endloop + endfacet + facet normal -0.616349 0.14653 0.77372 + outer loop + vertex 0.916251 1.78872 2.62541 + vertex 0.913366 1.78594 2.62364 + vertex 0.915644 1.78428 2.62577 + endloop + endfacet + facet normal -0.519586 0.138846 0.843061 + outer loop + vertex 0.915644 1.78428 2.62577 + vertex 0.919308 1.78732 2.62752 + vertex 0.916251 1.78872 2.62541 + endloop + endfacet + facet normal -0.519085 0.137982 0.843512 + outer loop + vertex 0.918194 1.78172 2.62775 + vertex 0.919308 1.78732 2.62752 + vertex 0.915644 1.78428 2.62577 + endloop + endfacet + facet normal -0.623921 0.16003 0.764927 + outer loop + vertex 0.913658 1.79058 2.62291 + vertex 0.913366 1.78594 2.62364 + vertex 0.916251 1.78872 2.62541 + endloop + endfacet + facet normal -0.626043 0.155892 0.764047 + outer loop + vertex 0.916517 1.79334 2.62469 + vertex 0.913658 1.79058 2.62291 + vertex 0.916251 1.78872 2.62541 + endloop + endfacet + facet normal -0.53372 0.160941 0.830206 + outer loop + vertex 0.916251 1.78872 2.62541 + vertex 0.919701 1.79222 2.62695 + vertex 0.916517 1.79334 2.62469 + endloop + endfacet + facet normal -0.518878 0.140615 0.843204 + outer loop + vertex 0.919308 1.78732 2.62752 + vertex 0.919701 1.79222 2.62695 + vertex 0.916251 1.78872 2.62541 + endloop + endfacet + facet normal -0.633447 0.169402 0.755015 + outer loop + vertex 0.914035 1.79496 2.62224 + vertex 0.913658 1.79058 2.62291 + vertex 0.916517 1.79334 2.62469 + endloop + endfacet + facet normal -0.638864 0.157977 0.752925 + outer loop + vertex 0.916414 1.79761 2.6237 + vertex 0.914035 1.79496 2.62224 + vertex 0.916517 1.79334 2.62469 + endloop + endfacet + facet normal -0.555677 0.173814 0.813026 + outer loop + vertex 0.916517 1.79334 2.62469 + vertex 0.919615 1.79684 2.62606 + vertex 0.916414 1.79761 2.6237 + endloop + endfacet + facet normal -0.537098 0.150755 0.829939 + outer loop + vertex 0.919701 1.79222 2.62695 + vertex 0.919615 1.79684 2.62606 + vertex 0.916517 1.79334 2.62469 + endloop + endfacet + facet normal -0.656259 0.161248 0.737104 + outer loop + vertex 0.915784 1.80226 2.62215 + vertex 0.912301 1.80023 2.61949 + vertex 0.914156 1.79839 2.62155 + endloop + endfacet + facet normal -0.647856 0.172009 0.742089 + outer loop + vertex 0.914156 1.79839 2.62155 + vertex 0.914035 1.79496 2.62224 + vertex 0.916414 1.79761 2.6237 + endloop + endfacet + facet normal -0.651881 0.158717 0.741525 + outer loop + vertex 0.915784 1.80226 2.62215 + vertex 0.914156 1.79839 2.62155 + vertex 0.916414 1.79761 2.6237 + endloop + endfacet + facet normal -0.60283 0.177486 0.777878 + outer loop + vertex 0.915784 1.80226 2.62215 + vertex 0.916414 1.79761 2.6237 + vertex 0.918859 1.80069 2.62489 + endloop + endfacet + facet normal -0.641487 0.0765155 0.763308 + outer loop + vertex 0.915784 1.80226 2.62215 + vertex 0.918859 1.80069 2.62489 + vertex 0.918264 1.80295 2.62417 + endloop + endfacet + facet normal -0.56575 0.134111 0.813598 + outer loop + vertex 0.918859 1.80069 2.62489 + vertex 0.916414 1.79761 2.6237 + vertex 0.919615 1.79684 2.62606 + endloop + endfacet + facet normal -0.656766 0.16331 0.736198 + outer loop + vertex 0.91241 1.80527 2.61848 + vertex 0.912301 1.80023 2.61949 + vertex 0.915784 1.80226 2.62215 + endloop + endfacet + facet normal -0.648326 0.177791 0.740314 + outer loop + vertex 0.915952 1.80804 2.62091 + vertex 0.91241 1.80527 2.61848 + vertex 0.915784 1.80226 2.62215 + endloop + endfacet + facet normal -0.645305 0.178246 0.742839 + outer loop + vertex 0.915784 1.80226 2.62215 + vertex 0.918471 1.80595 2.6236 + vertex 0.915952 1.80804 2.62091 + endloop + endfacet + facet normal -0.650302 0.184165 0.737015 + outer loop + vertex 0.918264 1.80295 2.62417 + vertex 0.918471 1.80595 2.6236 + vertex 0.915784 1.80226 2.62215 + endloop + endfacet + facet normal -0.648238 0.177564 0.740445 + outer loop + vertex 0.913373 1.81071 2.61801 + vertex 0.91241 1.80527 2.61848 + vertex 0.915952 1.80804 2.62091 + endloop + endfacet + facet normal -0.640902 0.188617 0.744089 + outer loop + vertex 0.916421 1.81327 2.61999 + vertex 0.913373 1.81071 2.61801 + vertex 0.915952 1.80804 2.62091 + endloop + endfacet + facet normal -0.626026 0.189456 0.756437 + outer loop + vertex 0.915952 1.80804 2.62091 + vertex 0.919564 1.8114 2.62306 + vertex 0.916421 1.81327 2.61999 + endloop + endfacet + facet normal -0.632099 0.201196 0.748312 + outer loop + vertex 0.918471 1.80595 2.6236 + vertex 0.919564 1.8114 2.62306 + vertex 0.915952 1.80804 2.62091 + endloop + endfacet + facet normal -0.638681 0.183513 0.747268 + outer loop + vertex 0.913934 1.81523 2.61738 + vertex 0.913373 1.81071 2.61801 + vertex 0.916421 1.81327 2.61999 + endloop + endfacet + facet normal -0.639951 0.181208 0.746744 + outer loop + vertex 0.91638 1.81782 2.61885 + vertex 0.913934 1.81523 2.61738 + vertex 0.916421 1.81327 2.61999 + endloop + endfacet + facet normal -0.617063 0.185903 0.764639 + outer loop + vertex 0.916421 1.81327 2.61999 + vertex 0.919487 1.81674 2.62162 + vertex 0.91638 1.81782 2.61885 + endloop + endfacet + facet normal -0.623427 0.195027 0.757168 + outer loop + vertex 0.919564 1.8114 2.62306 + vertex 0.919487 1.81674 2.62162 + vertex 0.916421 1.81327 2.61999 + endloop + endfacet + facet normal -0.579799 0.124568 0.805181 + outer loop + vertex 0.915676 1.82248 2.6173 + vertex 0.911837 1.82028 2.61487 + vertex 0.914021 1.81866 2.6167 + endloop + endfacet + facet normal -0.631689 0.167664 0.756874 + outer loop + vertex 0.914021 1.81866 2.6167 + vertex 0.913934 1.81523 2.61738 + vertex 0.91638 1.81782 2.61885 + endloop + endfacet + facet normal -0.635239 0.156271 0.756341 + outer loop + vertex 0.915676 1.82248 2.6173 + vertex 0.914021 1.81866 2.6167 + vertex 0.91638 1.81782 2.61885 + endloop + endfacet + facet normal -0.619869 0.162387 0.767719 + outer loop + vertex 0.915676 1.82248 2.6173 + vertex 0.91638 1.81782 2.61885 + vertex 0.918796 1.82084 2.62016 + endloop + endfacet + facet normal -0.628582 0.140776 0.764896 + outer loop + vertex 0.915676 1.82248 2.6173 + vertex 0.918796 1.82084 2.62016 + vertex 0.918235 1.82322 2.61926 + endloop + endfacet + facet normal -0.623241 0.166669 0.764063 + outer loop + vertex 0.918796 1.82084 2.62016 + vertex 0.91638 1.81782 2.61885 + vertex 0.919487 1.81674 2.62162 + endloop + endfacet + facet normal -0.590787 0.159528 0.790899 + outer loop + vertex 0.912219 1.82508 2.61419 + vertex 0.911837 1.82028 2.61487 + vertex 0.915676 1.82248 2.6173 + endloop + endfacet + facet normal -0.581803 0.175411 0.794189 + outer loop + vertex 0.915715 1.82818 2.61607 + vertex 0.912219 1.82508 2.61419 + vertex 0.915676 1.82248 2.6173 + endloop + endfacet + facet normal -0.629165 0.168105 0.758876 + outer loop + vertex 0.915676 1.82248 2.6173 + vertex 0.918351 1.82618 2.6187 + vertex 0.915715 1.82818 2.61607 + endloop + endfacet + facet normal -0.631017 0.170201 0.756868 + outer loop + vertex 0.918235 1.82322 2.61926 + vertex 0.918351 1.82618 2.6187 + vertex 0.915676 1.82248 2.6173 + endloop + endfacet + facet normal -0.582742 0.177113 0.793122 + outer loop + vertex 0.912517 1.8307 2.61315 + vertex 0.912219 1.82508 2.61419 + vertex 0.915715 1.82818 2.61607 + endloop + endfacet + facet normal -0.575524 0.18914 0.795612 + outer loop + vertex 0.916427 1.83343 2.61533 + vertex 0.912517 1.8307 2.61315 + vertex 0.915715 1.82818 2.61607 + endloop + endfacet + facet normal -0.630952 0.190581 0.752049 + outer loop + vertex 0.915715 1.82818 2.61607 + vertex 0.919238 1.83139 2.61821 + vertex 0.916427 1.83343 2.61533 + endloop + endfacet + facet normal -0.624203 0.177279 0.760883 + outer loop + vertex 0.918351 1.82618 2.6187 + vertex 0.919238 1.83139 2.61821 + vertex 0.915715 1.82818 2.61607 + endloop + endfacet + facet normal -0.58021 0.2009 0.789301 + outer loop + vertex 0.914322 1.83669 2.61296 + vertex 0.912517 1.8307 2.61315 + vertex 0.916427 1.83343 2.61533 + endloop + endfacet + facet normal -0.580785 0.200327 0.789024 + outer loop + vertex 0.917388 1.83735 2.61505 + vertex 0.914322 1.83669 2.61296 + vertex 0.916427 1.83343 2.61533 + endloop + endfacet + facet normal -0.631645 0.209664 0.746368 + outer loop + vertex 0.916427 1.83343 2.61533 + vertex 0.919406 1.83626 2.61706 + vertex 0.917388 1.83735 2.61505 + endloop + endfacet + facet normal -0.626213 0.199455 0.753707 + outer loop + vertex 0.919238 1.83139 2.61821 + vertex 0.919406 1.83626 2.61706 + vertex 0.916427 1.83343 2.61533 + endloop + endfacet + facet normal -0.623938 0.197578 0.756085 + outer loop + vertex 0.917388 1.83735 2.61505 + vertex 0.919355 1.83962 2.61607 + vertex 0.917314 1.84071 2.61411 + endloop + endfacet + facet normal -0.580962 0.207194 0.787118 + outer loop + vertex 0.917388 1.83735 2.61505 + vertex 0.917314 1.84071 2.61411 + vertex 0.914322 1.83669 2.61296 + endloop + endfacet + facet normal -0.575378 0.201449 0.792691 + outer loop + vertex 0.914322 1.83669 2.61296 + vertex 0.917314 1.84071 2.61411 + vertex 0.914634 1.84157 2.61194 + endloop + endfacet + facet normal -0.631964 0.208947 0.746299 + outer loop + vertex 0.919355 1.83962 2.61607 + vertex 0.917388 1.83735 2.61505 + vertex 0.919406 1.83626 2.61706 + endloop + endfacet + facet normal -0.574777 0.203264 0.792663 + outer loop + vertex 0.914634 1.84157 2.61194 + vertex 0.917314 1.84071 2.61411 + vertex 0.917522 1.84544 2.61304 + endloop + endfacet + facet normal -0.416649 0.239963 0.876825 + outer loop + vertex 0.913319 1.91606 2.59402 + vertex 0.917823 1.92162 2.59464 + vertex 0.913345 1.9213 2.5926 + endloop + endfacet + facet normal -0.416834 0.23581 0.877863 + outer loop + vertex 0.917823 1.92162 2.59464 + vertex 0.918157 1.92641 2.59351 + vertex 0.913345 1.9213 2.5926 + endloop + endfacet + facet normal -0.404217 0.222232 0.887255 + outer loop + vertex 0.913345 1.9213 2.5926 + vertex 0.918157 1.92641 2.59351 + vertex 0.914541 1.92653 2.59183 + endloop + endfacet + facet normal -0.477498 0.256391 0.840392 + outer loop + vertex 0.915845 1.93362 2.59055 + vertex 0.912055 1.93048 2.58935 + vertex 0.914572 1.9298 2.59099 + endloop + endfacet + facet normal -0.408582 0.23812 0.881112 + outer loop + vertex 0.914572 1.9298 2.59099 + vertex 0.918476 1.9315 2.59234 + vertex 0.915845 1.93362 2.59055 + endloop + endfacet + facet normal -0.406689 0.231749 0.883683 + outer loop + vertex 0.914572 1.9298 2.59099 + vertex 0.914541 1.92653 2.59183 + vertex 0.918476 1.9315 2.59234 + endloop + endfacet + facet normal -0.403375 0.228894 0.885944 + outer loop + vertex 0.914541 1.92653 2.59183 + vertex 0.918157 1.92641 2.59351 + vertex 0.918476 1.9315 2.59234 + endloop + endfacet + facet normal -0.479881 0.260232 0.837851 + outer loop + vertex 0.913127 1.93613 2.58821 + vertex 0.912055 1.93048 2.58935 + vertex 0.915845 1.93362 2.59055 + endloop + endfacet + facet normal -0.484935 0.253864 0.836894 + outer loop + vertex 0.917258 1.93747 2.5902 + vertex 0.913127 1.93613 2.58821 + vertex 0.915845 1.93362 2.59055 + endloop + endfacet + facet normal -0.413817 0.231748 0.880368 + outer loop + vertex 0.915845 1.93362 2.59055 + vertex 0.919731 1.93665 2.59158 + vertex 0.917258 1.93747 2.5902 + endloop + endfacet + facet normal -0.413601 0.231407 0.88056 + outer loop + vertex 0.918476 1.9315 2.59234 + vertex 0.919731 1.93665 2.59158 + vertex 0.915845 1.93362 2.59055 + endloop + endfacet + facet normal -0.434766 0.256422 0.863265 + outer loop + vertex 0.917258 1.93747 2.5902 + vertex 0.919927 1.93986 2.59083 + vertex 0.917863 1.94136 2.58935 + endloop + endfacet + facet normal -0.485539 0.258191 0.835218 + outer loop + vertex 0.917258 1.93747 2.5902 + vertex 0.917863 1.94136 2.58935 + vertex 0.913127 1.93613 2.58821 + endloop + endfacet + facet normal -0.473764 0.245228 0.84582 + outer loop + vertex 0.913127 1.93613 2.58821 + vertex 0.917863 1.94136 2.58935 + vertex 0.914194 1.94145 2.58727 + endloop + endfacet + facet normal -0.41471 0.229397 0.880564 + outer loop + vertex 0.919927 1.93986 2.59083 + vertex 0.917258 1.93747 2.5902 + vertex 0.919731 1.93665 2.59158 + endloop + endfacet + facet normal -0.55367 0.289209 0.780902 + outer loop + vertex 0.915575 1.94843 2.58586 + vertex 0.912151 1.94544 2.58453 + vertex 0.914222 1.94462 2.58631 + endloop + endfacet + facet normal -0.47203 0.267195 0.840116 + outer loop + vertex 0.914222 1.94462 2.58631 + vertex 0.917945 1.94631 2.58786 + vertex 0.915575 1.94843 2.58586 + endloop + endfacet + facet normal -0.470149 0.260001 0.843421 + outer loop + vertex 0.914222 1.94462 2.58631 + vertex 0.914194 1.94145 2.58727 + vertex 0.917945 1.94631 2.58786 + endloop + endfacet + facet normal -0.471406 0.261099 0.84238 + outer loop + vertex 0.914194 1.94145 2.58727 + vertex 0.917863 1.94136 2.58935 + vertex 0.917945 1.94631 2.58786 + endloop + endfacet + facet normal -0.555409 0.292251 0.778531 + outer loop + vertex 0.913289 1.95093 2.58329 + vertex 0.912151 1.94544 2.58453 + vertex 0.915575 1.94843 2.58586 + endloop + endfacet + facet normal -0.559232 0.287693 0.777491 + outer loop + vertex 0.917095 1.95233 2.5855 + vertex 0.913289 1.95093 2.58329 + vertex 0.915575 1.94843 2.58586 + endloop + endfacet + facet normal -0.464823 0.257236 0.847213 + outer loop + vertex 0.915575 1.94843 2.58586 + vertex 0.919434 1.95155 2.58703 + vertex 0.917095 1.95233 2.5855 + endloop + endfacet + facet normal -0.471402 0.267993 0.840214 + outer loop + vertex 0.917945 1.94631 2.58786 + vertex 0.919434 1.95155 2.58703 + vertex 0.915575 1.94843 2.58586 + endloop + endfacet + facet normal -0.480872 0.283233 0.829784 + outer loop + vertex 0.917095 1.95233 2.5855 + vertex 0.919753 1.95483 2.58619 + vertex 0.917844 1.95627 2.58459 + endloop + endfacet + facet normal -0.559066 0.286165 0.778174 + outer loop + vertex 0.917095 1.95233 2.5855 + vertex 0.917844 1.95627 2.58459 + vertex 0.913289 1.95093 2.58329 + endloop + endfacet + facet normal -0.551491 0.277641 0.786622 + outer loop + vertex 0.913289 1.95093 2.58329 + vertex 0.917844 1.95627 2.58459 + vertex 0.914365 1.95661 2.58204 + endloop + endfacet + facet normal -0.463677 0.260143 0.846953 + outer loop + vertex 0.919753 1.95483 2.58619 + vertex 0.917095 1.95233 2.5855 + vertex 0.919434 1.95155 2.58703 + endloop + endfacet + facet normal -0.645149 0.302073 0.701808 + outer loop + vertex 0.91568 1.96354 2.58052 + vertex 0.913294 1.96174 2.5791 + vertex 0.914615 1.96009 2.58102 + endloop + endfacet + facet normal -0.550618 0.285022 0.784591 + outer loop + vertex 0.914615 1.96009 2.58102 + vertex 0.917951 1.96126 2.58294 + vertex 0.91568 1.96354 2.58052 + endloop + endfacet + facet normal -0.548994 0.269784 0.791089 + outer loop + vertex 0.914615 1.96009 2.58102 + vertex 0.914365 1.95661 2.58204 + vertex 0.917951 1.96126 2.58294 + endloop + endfacet + facet normal -0.552524 0.273212 0.787447 + outer loop + vertex 0.914365 1.95661 2.58204 + vertex 0.917844 1.95627 2.58459 + vertex 0.917951 1.96126 2.58294 + endloop + endfacet + facet normal -0.649964 0.317416 0.690503 + outer loop + vertex 0.913592 1.96516 2.57781 + vertex 0.913294 1.96174 2.5791 + vertex 0.91568 1.96354 2.58052 + endloop + endfacet + facet normal -0.6582 0.303926 0.688769 + outer loop + vertex 0.916175 1.96765 2.57918 + vertex 0.913592 1.96516 2.57781 + vertex 0.91568 1.96354 2.58052 + endloop + endfacet + facet normal -0.56405 0.316676 0.762603 + outer loop + vertex 0.91568 1.96354 2.58052 + vertex 0.919038 1.96653 2.58176 + vertex 0.916175 1.96765 2.57918 + endloop + endfacet + facet normal -0.54759 0.28882 0.785321 + outer loop + vertex 0.917951 1.96126 2.58294 + vertex 0.919038 1.96653 2.58176 + vertex 0.91568 1.96354 2.58052 + endloop + endfacet + facet normal -0.697864 0.361797 0.618134 + outer loop + vertex 0.916294 1.97239 2.57697 + vertex 0.913381 1.97114 2.57441 + vertex 0.91416 1.96868 2.57673 + endloop + endfacet + facet normal -0.663203 0.314391 0.679206 + outer loop + vertex 0.91416 1.96868 2.57673 + vertex 0.913592 1.96516 2.57781 + vertex 0.916175 1.96765 2.57918 + endloop + endfacet + facet normal -0.654034 0.332649 0.6794 + outer loop + vertex 0.916294 1.97239 2.57697 + vertex 0.91416 1.96868 2.57673 + vertex 0.916175 1.96765 2.57918 + endloop + endfacet + facet normal -0.613461 0.345853 0.709965 + outer loop + vertex 0.916294 1.97239 2.57697 + vertex 0.916175 1.96765 2.57918 + vertex 0.919057 1.97057 2.58024 + endloop + endfacet + facet normal -0.645746 0.290191 0.706259 + outer loop + vertex 0.916294 1.97239 2.57697 + vertex 0.919057 1.97057 2.58024 + vertex 0.919371 1.97359 2.57929 + endloop + endfacet + facet normal -0.576224 0.289421 0.764331 + outer loop + vertex 0.919057 1.97057 2.58024 + vertex 0.916175 1.96765 2.57918 + vertex 0.919038 1.96653 2.58176 + endloop + endfacet + facet normal -0.69796 0.359405 0.619418 + outer loop + vertex 0.913875 1.97481 2.57284 + vertex 0.913381 1.97114 2.57441 + vertex 0.916294 1.97239 2.57697 + endloop + endfacet + facet normal -0.715294 0.333234 0.614255 + outer loop + vertex 0.916328 1.97737 2.57431 + vertex 0.913875 1.97481 2.57284 + vertex 0.916294 1.97239 2.57697 + endloop + endfacet + facet normal -0.670401 0.353354 0.652459 + outer loop + vertex 0.916294 1.97239 2.57697 + vertex 0.919118 1.97662 2.57758 + vertex 0.916328 1.97737 2.57431 + endloop + endfacet + facet normal -0.647039 0.332879 0.685953 + outer loop + vertex 0.919371 1.97359 2.57929 + vertex 0.919118 1.97662 2.57758 + vertex 0.916294 1.97239 2.57697 + endloop + endfacet + facet normal -0.743001 0.355246 0.56723 + outer loop + vertex 0.916087 1.98255 2.57099 + vertex 0.913383 1.98089 2.56849 + vertex 0.914348 1.97851 2.57124 + endloop + endfacet + facet normal -0.722141 0.349868 0.596745 + outer loop + vertex 0.914348 1.97851 2.57124 + vertex 0.913875 1.97481 2.57284 + vertex 0.916328 1.97737 2.57431 + endloop + endfacet + facet normal -0.72289 0.348418 0.596687 + outer loop + vertex 0.916087 1.98255 2.57099 + vertex 0.914348 1.97851 2.57124 + vertex 0.916328 1.97737 2.57431 + endloop + endfacet + facet normal -0.700341 0.361511 0.615493 + outer loop + vertex 0.916087 1.98255 2.57099 + vertex 0.916328 1.97737 2.57431 + vertex 0.918807 1.9804 2.57535 + endloop + endfacet + facet normal -0.746736 0.27901 0.60377 + outer loop + vertex 0.916087 1.98255 2.57099 + vertex 0.918807 1.9804 2.57535 + vertex 0.918474 1.9827 2.57387 + endloop + endfacet + facet normal -0.679377 0.330854 0.654968 + outer loop + vertex 0.918807 1.9804 2.57535 + vertex 0.916328 1.97737 2.57431 + vertex 0.919118 1.97662 2.57758 + endloop + endfacet + facet normal -0.751813 0.344075 0.562485 + outer loop + vertex 0.914775 1.98721 2.56645 + vertex 0.91307 1.98737 2.56407 + vertex 0.913206 1.98453 2.566 + endloop + endfacet + facet normal -0.742968 0.353154 0.568578 + outer loop + vertex 0.913206 1.98453 2.566 + vertex 0.913383 1.98089 2.56849 + vertex 0.916087 1.98255 2.57099 + endloop + endfacet + facet normal -0.749106 0.341638 0.567559 + outer loop + vertex 0.913206 1.98453 2.566 + vertex 0.916087 1.98255 2.57099 + vertex 0.914775 1.98721 2.56645 + endloop + endfacet + facet normal -0.759816 0.330905 0.559627 + outer loop + vertex 0.914775 1.98721 2.56645 + vertex 0.916087 1.98255 2.57099 + vertex 0.917089 1.98755 2.56939 + endloop + endfacet + facet normal -0.738808 0.334763 0.58489 + outer loop + vertex 0.916087 1.98255 2.57099 + vertex 0.918694 1.98523 2.57275 + vertex 0.917089 1.98755 2.56939 + endloop + endfacet + facet normal -0.736122 0.327138 0.592541 + outer loop + vertex 0.918474 1.9827 2.57387 + vertex 0.918694 1.98523 2.57275 + vertex 0.916087 1.98255 2.57099 + endloop + endfacet + facet normal -0.756336 0.330122 0.564779 + outer loop + vertex 0.913415 1.99009 2.56295 + vertex 0.91307 1.98737 2.56407 + vertex 0.914775 1.98721 2.56645 + endloop + endfacet + facet normal -0.755551 0.331085 0.565265 + outer loop + vertex 0.915862 1.99154 2.56537 + vertex 0.913415 1.99009 2.56295 + vertex 0.914775 1.98721 2.56645 + endloop + endfacet + facet normal -0.746904 0.331643 0.576322 + outer loop + vertex 0.918157 1.99091 2.56885 + vertex 0.917089 1.98755 2.56939 + vertex 0.91914 1.98864 2.57143 + endloop + endfacet + facet normal -0.758016 0.332686 0.561009 + outer loop + vertex 0.918157 1.99091 2.56885 + vertex 0.915862 1.99154 2.56537 + vertex 0.917089 1.98755 2.56939 + endloop + endfacet + facet normal -0.759846 0.330767 0.559667 + outer loop + vertex 0.915862 1.99154 2.56537 + vertex 0.914775 1.98721 2.56645 + vertex 0.917089 1.98755 2.56939 + endloop + endfacet + facet normal -0.747023 0.323302 0.580889 + outer loop + vertex 0.91914 1.98864 2.57143 + vertex 0.917089 1.98755 2.56939 + vertex 0.918694 1.98523 2.57275 + endloop + endfacet + facet normal -0.748693 0.333236 0.573072 + outer loop + vertex 0.915802 1.99698 2.56207 + vertex 0.913263 1.9963 2.55915 + vertex 0.914022 1.99362 2.5617 + endloop + endfacet + facet normal -0.755549 0.330458 0.565636 + outer loop + vertex 0.914022 1.99362 2.5617 + vertex 0.913415 1.99009 2.56295 + vertex 0.915862 1.99154 2.56537 + endloop + endfacet + facet normal -0.752206 0.33576 0.566967 + outer loop + vertex 0.915802 1.99698 2.56207 + vertex 0.914022 1.99362 2.5617 + vertex 0.915862 1.99154 2.56537 + endloop + endfacet + facet normal -0.758054 0.332218 0.561235 + outer loop + vertex 0.915802 1.99698 2.56207 + vertex 0.915862 1.99154 2.56537 + vertex 0.917978 1.99449 2.56648 + endloop + endfacet + facet normal -0.757891 0.332477 0.561302 + outer loop + vertex 0.915802 1.99698 2.56207 + vertex 0.917978 1.99449 2.56648 + vertex 0.917808 1.99734 2.56457 + endloop + endfacet + facet normal -0.758143 0.332357 0.561033 + outer loop + vertex 0.917978 1.99449 2.56648 + vertex 0.915862 1.99154 2.56537 + vertex 0.918157 1.99091 2.56885 + endloop + endfacet + facet normal -0.746427 0.346857 0.567923 + outer loop + vertex 0.913772 1.99998 2.55757 + vertex 0.913263 1.9963 2.55915 + vertex 0.915802 1.99698 2.56207 + endloop + endfacet + facet normal -0.745345 0.348351 0.56843 + outer loop + vertex 0.916012 2.00216 2.55917 + vertex 0.913772 1.99998 2.55757 + vertex 0.915802 1.99698 2.56207 + endloop + endfacet + facet normal -0.756482 0.342496 0.557164 + outer loop + vertex 0.915802 1.99698 2.56207 + vertex 0.918003 2.00021 2.56307 + vertex 0.916012 2.00216 2.55917 + endloop + endfacet + facet normal -0.755913 0.341721 0.558411 + outer loop + vertex 0.917808 1.99734 2.56457 + vertex 0.918003 2.00021 2.56307 + vertex 0.915802 1.99698 2.56207 + endloop + endfacet + facet normal -0.760221 0.360276 0.540615 + outer loop + vertex 0.916133 2.00746 2.556 + vertex 0.913807 2.00606 2.55366 + vertex 0.91438 2.00372 2.55603 + endloop + endfacet + facet normal -0.746764 0.353614 0.563294 + outer loop + vertex 0.91438 2.00372 2.55603 + vertex 0.913772 1.99998 2.55757 + vertex 0.916012 2.00216 2.55917 + endloop + endfacet + facet normal -0.746508 0.354036 0.56337 + outer loop + vertex 0.916133 2.00746 2.556 + vertex 0.91438 2.00372 2.55603 + vertex 0.916012 2.00216 2.55917 + endloop + endfacet + facet normal -0.752882 0.350435 0.557103 + outer loop + vertex 0.916133 2.00746 2.556 + vertex 0.916012 2.00216 2.55917 + vertex 0.91816 2.00451 2.56059 + endloop + endfacet + facet normal -0.750877 0.353254 0.558028 + outer loop + vertex 0.916133 2.00746 2.556 + vertex 0.91816 2.00451 2.56059 + vertex 0.918188 2.00732 2.55886 + endloop + endfacet + facet normal -0.752445 0.349224 0.558453 + outer loop + vertex 0.91816 2.00451 2.56059 + vertex 0.916012 2.00216 2.55917 + vertex 0.918003 2.00021 2.56307 + endloop + endfacet + facet normal -0.807552 0.345694 0.477866 + outer loop + vertex 0.915119 2.01188 2.55175 + vertex 0.913521 2.01103 2.54967 + vertex 0.914087 2.0088 2.55223 + endloop + endfacet + facet normal -0.760239 0.359644 0.541012 + outer loop + vertex 0.914087 2.0088 2.55223 + vertex 0.913807 2.00606 2.55366 + vertex 0.916133 2.00746 2.556 + endloop + endfacet + facet normal -0.769042 0.342477 0.539708 + outer loop + vertex 0.914087 2.0088 2.55223 + vertex 0.916133 2.00746 2.556 + vertex 0.915119 2.01188 2.55175 + endloop + endfacet + facet normal -0.773121 0.338399 0.536442 + outer loop + vertex 0.915119 2.01188 2.55175 + vertex 0.916133 2.00746 2.556 + vertex 0.917194 2.01262 2.55427 + endloop + endfacet + facet normal -0.758414 0.341609 0.555078 + outer loop + vertex 0.916133 2.00746 2.556 + vertex 0.918579 2.01001 2.55777 + vertex 0.917194 2.01262 2.55427 + endloop + endfacet + facet normal -0.756584 0.335567 0.561227 + outer loop + vertex 0.918188 2.00732 2.55886 + vertex 0.918579 2.01001 2.55777 + vertex 0.916133 2.00746 2.556 + endloop + endfacet + facet normal -0.807346 0.347285 0.47706 + outer loop + vertex 0.91415 2.01444 2.54825 + vertex 0.913521 2.01103 2.54967 + vertex 0.915119 2.01188 2.55175 + endloop + endfacet + facet normal -0.808535 0.345676 0.476213 + outer loop + vertex 0.916211 2.01646 2.55028 + vertex 0.91415 2.01444 2.54825 + vertex 0.915119 2.01188 2.55175 + endloop + endfacet + facet normal -0.76673 0.334275 0.548075 + outer loop + vertex 0.918257 2.01602 2.55369 + vertex 0.917194 2.01262 2.55427 + vertex 0.919149 2.01361 2.5564 + endloop + endfacet + facet normal -0.787953 0.335436 0.516345 + outer loop + vertex 0.918257 2.01602 2.55369 + vertex 0.916211 2.01646 2.55028 + vertex 0.917194 2.01262 2.55427 + endloop + endfacet + facet normal -0.770699 0.353921 0.529871 + outer loop + vertex 0.916211 2.01646 2.55028 + vertex 0.915119 2.01188 2.55175 + vertex 0.917194 2.01262 2.55427 + endloop + endfacet + facet normal -0.766963 0.330399 0.550096 + outer loop + vertex 0.919149 2.01361 2.5564 + vertex 0.917194 2.01262 2.55427 + vertex 0.918579 2.01001 2.55777 + endloop + endfacet + facet normal -0.909531 0.351141 0.222382 + outer loop + vertex 0.915396 2.02388 2.54075 + vertex 0.914062 2.02108 2.53971 + vertex 0.914365 2.01969 2.54314 + endloop + endfacet + facet normal -0.866216 0.39107 0.311022 + outer loop + vertex 0.916529 2.02219 2.54603 + vertex 0.915396 2.02388 2.54075 + vertex 0.914365 2.01969 2.54314 + endloop + endfacet + facet normal -0.865906 0.393787 0.308446 + outer loop + vertex 0.914805 2.01792 2.54663 + vertex 0.916529 2.02219 2.54603 + vertex 0.914365 2.01969 2.54314 + endloop + endfacet + facet normal -0.810196 0.364902 0.458725 + outer loop + vertex 0.914805 2.01792 2.54663 + vertex 0.91415 2.01444 2.54825 + vertex 0.916211 2.01646 2.55028 + endloop + endfacet + facet normal -0.797086 0.387826 0.462865 + outer loop + vertex 0.916529 2.02219 2.54603 + vertex 0.914805 2.01792 2.54663 + vertex 0.916211 2.01646 2.55028 + endloop + endfacet + facet normal -0.809516 0.378238 0.449021 + outer loop + vertex 0.916529 2.02219 2.54603 + vertex 0.916211 2.01646 2.55028 + vertex 0.918193 2.01954 2.55126 + endloop + endfacet + facet normal -0.868185 0.272961 0.414423 + outer loop + vertex 0.916529 2.02219 2.54603 + vertex 0.918193 2.01954 2.55126 + vertex 0.918158 2.02231 2.54936 + endloop + endfacet + facet normal -0.785659 0.341648 0.515769 + outer loop + vertex 0.918193 2.01954 2.55126 + vertex 0.916211 2.01646 2.55028 + vertex 0.918257 2.01602 2.55369 + endloop + endfacet + facet normal -0.753307 0.118739 0.646861 + outer loop + vertex 0.915 2.02544 2.54 + vertex 0.914062 2.02108 2.53971 + vertex 0.915396 2.02388 2.54075 + endloop + endfacet + facet normal -0.473708 0.279653 0.835102 + outer loop + vertex 0.915 2.02544 2.54 + vertex 0.915396 2.02388 2.54075 + vertex 0.917692 2.03 2.54 + endloop + endfacet + facet normal -0.912421 0.364817 0.185465 + outer loop + vertex 0.917692 2.03 2.54 + vertex 0.915396 2.02388 2.54075 + vertex 0.91681 2.0274 2.54077 + endloop + endfacet + facet normal -0.885154 0.353158 0.302954 + outer loop + vertex 0.915396 2.02388 2.54075 + vertex 0.916529 2.02219 2.54603 + vertex 0.91681 2.0274 2.54077 + endloop + endfacet + facet normal -0.914531 0.310589 0.259167 + outer loop + vertex 0.91681 2.0274 2.54077 + vertex 0.916529 2.02219 2.54603 + vertex 0.917875 2.0276 2.5443 + endloop + endfacet + facet normal -0.852128 0.339557 0.398219 + outer loop + vertex 0.916529 2.02219 2.54603 + vertex 0.918633 2.02499 2.54814 + vertex 0.917875 2.0276 2.5443 + endloop + endfacet + facet normal -0.851381 0.334725 0.403868 + outer loop + vertex 0.918158 2.02231 2.54936 + vertex 0.918633 2.02499 2.54814 + vertex 0.916529 2.02219 2.54603 + endloop + endfacet + facet normal -0.989589 0.14111 0.0283013 + outer loop + vertex 0.917549 2.03 2.535 + vertex 0.917692 2.03 2.54 + vertex 0.918262 2.035 2.535 + endloop + endfacet + facet normal 0.932563 -0.302826 -0.196525 + outer loop + vertex 0.918262 2.035 2.535 + vertex 0.917692 2.03 2.54 + vertex 0.91756 2.03166 2.53682 + endloop + endfacet + facet normal 0.898046 -0.373729 -0.232035 + outer loop + vertex 0.917692 2.03 2.54 + vertex 0.91681 2.0274 2.54077 + vertex 0.91756 2.03166 2.53682 + endloop + endfacet + facet normal -0.94376 0.298446 0.142294 + outer loop + vertex 0.91756 2.03166 2.53682 + vertex 0.91681 2.0274 2.54077 + vertex 0.918051 2.03156 2.54029 + endloop + endfacet + facet normal -0.854995 0.330236 0.39991 + outer loop + vertex 0.918968 2.03083 2.54396 + vertex 0.917875 2.0276 2.5443 + vertex 0.919361 2.02856 2.54668 + endloop + endfacet + facet normal -0.897244 0.333155 0.289761 + outer loop + vertex 0.918968 2.03083 2.54396 + vertex 0.918051 2.03156 2.54029 + vertex 0.917875 2.0276 2.5443 + endloop + endfacet + facet normal -0.916469 0.30401 0.260119 + outer loop + vertex 0.918051 2.03156 2.54029 + vertex 0.91681 2.0274 2.54077 + vertex 0.917875 2.0276 2.5443 + endloop + endfacet + facet normal -0.853979 0.336723 0.396659 + outer loop + vertex 0.919361 2.02856 2.54668 + vertex 0.917875 2.0276 2.5443 + vertex 0.918633 2.02499 2.54814 + endloop + endfacet + facet normal -0.448329 0.0942253 -0.888889 + outer loop + vertex 0.92 2.035 2.53326 + vertex 0.918641 2.03553 2.534 + vertex 0.92 2.04 2.53379 + endloop + endfacet + facet normal -0.544552 -0.638432 -0.543937 + outer loop + vertex 0.918262 2.035 2.535 + vertex 0.918641 2.03553 2.534 + vertex 0.92 2.035 2.53326 + endloop + endfacet + facet normal 0.935885 -0.00524037 0.352266 + outer loop + vertex 0.918262 2.035 2.535 + vertex 0.91756 2.03166 2.53682 + vertex 0.918641 2.03553 2.534 + endloop + endfacet + facet normal -0.964782 0.262888 -0.00920607 + outer loop + vertex 0.918641 2.03553 2.534 + vertex 0.91756 2.03166 2.53682 + vertex 0.918555 2.0353 2.53641 + endloop + endfacet + facet normal -0.903344 0.325712 0.279071 + outer loop + vertex 0.919013 2.03522 2.53913 + vertex 0.918051 2.03156 2.54029 + vertex 0.919339 2.03359 2.54209 + endloop + endfacet + facet normal -0.93929 0.299777 0.166938 + outer loop + vertex 0.919013 2.03522 2.53913 + vertex 0.918555 2.0353 2.53641 + vertex 0.918051 2.03156 2.54029 + endloop + endfacet + facet normal -0.950506 0.276044 0.14261 + outer loop + vertex 0.918555 2.0353 2.53641 + vertex 0.91756 2.03166 2.53682 + vertex 0.918051 2.03156 2.54029 + endloop + endfacet + facet normal -0.903361 0.317618 0.288199 + outer loop + vertex 0.919339 2.03359 2.54209 + vertex 0.918051 2.03156 2.54029 + vertex 0.918968 2.03083 2.54396 + endloop + endfacet + facet normal -0.874227 0.245902 -0.41864 + outer loop + vertex 0.92 2.04 2.53379 + vertex 0.918641 2.03553 2.534 + vertex 0.92 2.04206 2.535 + endloop + endfacet + facet normal -0.895284 0.265701 0.357587 + outer loop + vertex 0.92 2.04206 2.535 + vertex 0.918555 2.0353 2.53641 + vertex 0.919674 2.03825 2.53701 + endloop + endfacet + facet normal -0.978453 0.205913 -0.0151479 + outer loop + vertex 0.918641 2.03553 2.534 + vertex 0.918555 2.0353 2.53641 + vertex 0.92 2.04206 2.535 + endloop + endfacet + facet normal -0.93302 0.319005 0.166459 + outer loop + vertex 0.919674 2.03825 2.53701 + vertex 0.918555 2.0353 2.53641 + vertex 0.919013 2.03522 2.53913 + endloop + endfacet + facet normal 0.679394 -0.279955 -0.678269 + outer loop + vertex 0.916258 2.11 2.5 + vertex 0.913919 2.10723 2.4988 + vertex 0.915 2.11 2.49874 + endloop + endfacet + facet normal 0.573875 -0.13454 -0.807816 + outer loop + vertex 0.916685 2.10829 2.50059 + vertex 0.913919 2.10723 2.4988 + vertex 0.916258 2.11 2.5 + endloop + endfacet + facet normal 0.531984 -0.760422 -0.372493 + outer loop + vertex 0.913993 2.10575 2.50193 + vertex 0.913919 2.10723 2.4988 + vertex 0.916685 2.10829 2.50059 + endloop + endfacet + facet normal 0.484242 -0.750628 -0.44952 + outer loop + vertex 0.917976 2.10744 2.50341 + vertex 0.913993 2.10575 2.50193 + vertex 0.916685 2.10829 2.50059 + endloop + endfacet + facet normal 0.475449 -0.796701 -0.373116 + outer loop + vertex 0.917976 2.10744 2.50341 + vertex 0.918535 2.10604 2.5071 + vertex 0.913993 2.10575 2.50193 + endloop + endfacet + facet normal 0.220565 -0.965323 -0.139651 + outer loop + vertex 0.918535 2.10604 2.5071 + vertex 0.913344 2.10488 2.50692 + vertex 0.913993 2.10575 2.50193 + endloop + endfacet + facet normal 0.220378 -0.969056 -0.111192 + outer loop + vertex 0.918535 2.10604 2.5071 + vertex 0.918164 2.1054 2.51192 + vertex 0.913344 2.10488 2.50692 + endloop + endfacet + facet normal -0.0523157 -0.986813 0.153175 + outer loop + vertex 0.918164 2.1054 2.51192 + vertex 0.912761 2.10557 2.51116 + vertex 0.913344 2.10488 2.50692 + endloop + endfacet + facet normal -0.464268 -0.255448 0.848057 + outer loop + vertex 0.914056 2.10723 2.5139 + vertex 0.918302 2.10643 2.51598 + vertex 0.916684 2.10895 2.51586 + endloop + endfacet + facet normal -0.424597 -0.671097 0.607739 + outer loop + vertex 0.914056 2.10723 2.5139 + vertex 0.912761 2.10557 2.51116 + vertex 0.918302 2.10643 2.51598 + endloop + endfacet + facet normal -0.0649798 -0.966753 0.247319 + outer loop + vertex 0.912761 2.10557 2.51116 + vertex 0.918164 2.1054 2.51192 + vertex 0.918302 2.10643 2.51598 + endloop + endfacet + facet normal -0.627156 -0.367994 0.68648 + outer loop + vertex 0.918302 2.10643 2.51598 + vertex 0.920322 2.10843 2.5189 + vertex 0.916684 2.10895 2.51586 + endloop + endfacet + facet normal 0.786573 -0.61467 -0.0590284 + outer loop + vertex 0.92 2.11259 2.5 + vertex 0.92 2.11211 2.505 + vertex 0.916685 2.10829 2.50059 + endloop + endfacet + facet normal 0.191271 -0.27633 -0.941837 + outer loop + vertex 0.916258 2.11 2.5 + vertex 0.92 2.11259 2.5 + vertex 0.916685 2.10829 2.50059 + endloop + endfacet + facet normal 0.861248 -0.216361 -0.459827 + outer loop + vertex 0.92 2.11211 2.505 + vertex 0.917976 2.10744 2.50341 + vertex 0.916685 2.10829 2.50059 + endloop + endfacet + facet normal -0.631389 0.087889 0.77047 + outer loop + vertex 0.912709 2.11006 2.51247 + vertex 0.914056 2.10723 2.5139 + vertex 0.916684 2.10895 2.51586 + endloop + endfacet + facet normal -0.548287 0.350663 0.759221 + outer loop + vertex 0.916203 2.11224 2.51399 + vertex 0.912709 2.11006 2.51247 + vertex 0.916684 2.10895 2.51586 + endloop + endfacet + facet normal -0.619596 0.316893 0.718108 + outer loop + vertex 0.916684 2.10895 2.51586 + vertex 0.919365 2.11141 2.51709 + vertex 0.916203 2.11224 2.51399 + endloop + endfacet + facet normal -0.594743 0.270153 0.757164 + outer loop + vertex 0.920322 2.10843 2.5189 + vertex 0.919365 2.11141 2.51709 + vertex 0.916684 2.10895 2.51586 + endloop + endfacet + facet normal -0.520088 0.563709 0.64167 + outer loop + vertex 0.916497 2.11562 2.51153 + vertex 0.913762 2.11587 2.50909 + vertex 0.913319 2.11367 2.51067 + endloop + endfacet + facet normal -0.574721 0.442309 0.688519 + outer loop + vertex 0.913319 2.11367 2.51067 + vertex 0.912709 2.11006 2.51247 + vertex 0.916203 2.11224 2.51399 + endloop + endfacet + facet normal -0.510906 0.535023 0.672849 + outer loop + vertex 0.916497 2.11562 2.51153 + vertex 0.913319 2.11367 2.51067 + vertex 0.916203 2.11224 2.51399 + endloop + endfacet + facet normal -0.563685 0.518081 0.643313 + outer loop + vertex 0.916497 2.11562 2.51153 + vertex 0.916203 2.11224 2.51399 + vertex 0.918993 2.11445 2.51466 + endloop + endfacet + facet normal -0.533128 0.55963 0.634498 + outer loop + vertex 0.916497 2.11562 2.51153 + vertex 0.918993 2.11445 2.51466 + vertex 0.919035 2.11629 2.51307 + endloop + endfacet + facet normal -0.545035 0.481354 0.686465 + outer loop + vertex 0.918993 2.11445 2.51466 + vertex 0.916203 2.11224 2.51399 + vertex 0.919365 2.11141 2.51709 + endloop + endfacet + facet normal -0.350532 0.847686 0.39819 + outer loop + vertex 0.915087 2.12205 2.50043 + vertex 0.912121 2.12179 2.49838 + vertex 0.913412 2.12047 2.50232 + endloop + endfacet + facet normal -0.368517 0.847484 0.382055 + outer loop + vertex 0.917172 2.12163 2.50337 + vertex 0.915087 2.12205 2.50043 + vertex 0.913412 2.12047 2.50232 + endloop + endfacet + facet normal -0.371925 0.832275 0.411083 + outer loop + vertex 0.917172 2.12163 2.50337 + vertex 0.913412 2.12047 2.50232 + vertex 0.918558 2.12039 2.50714 + endloop + endfacet + facet normal -0.442418 0.754398 0.484923 + outer loop + vertex 0.918558 2.12039 2.50714 + vertex 0.913412 2.12047 2.50232 + vertex 0.914491 2.11794 2.50725 + endloop + endfacet + facet normal -0.454675 0.676317 0.57954 + outer loop + vertex 0.916497 2.11562 2.51153 + vertex 0.914491 2.11794 2.50725 + vertex 0.913762 2.11587 2.50909 + endloop + endfacet + facet normal -0.496974 0.643852 0.581784 + outer loop + vertex 0.916497 2.11562 2.51153 + vertex 0.919469 2.11794 2.5115 + vertex 0.914491 2.11794 2.50725 + endloop + endfacet + facet normal -0.434877 0.742937 0.508848 + outer loop + vertex 0.919469 2.11794 2.5115 + vertex 0.918558 2.12039 2.50714 + vertex 0.914491 2.11794 2.50725 + endloop + endfacet + facet normal -0.509622 0.659635 0.55242 + outer loop + vertex 0.919469 2.11794 2.5115 + vertex 0.916497 2.11562 2.51153 + vertex 0.919035 2.11629 2.51307 + endloop + endfacet + facet normal -0.0398981 0.997287 0.0618668 + outer loop + vertex 0.92 2.12736 2.495 + vertex 0.915 2.12716 2.495 + vertex 0.92 2.12705 2.5 + endloop + endfacet + facet normal -0.603085 0.508869 0.614281 + outer loop + vertex 0.92 2.12705 2.5 + vertex 0.915 2.12716 2.495 + vertex 0.914357 2.12373 2.49721 + endloop + endfacet + facet normal -0.40854 0.768544 0.492378 + outer loop + vertex 0.915087 2.12205 2.50043 + vertex 0.914357 2.12373 2.49721 + vertex 0.912121 2.12179 2.49838 + endloop + endfacet + facet normal -0.406116 0.76977 0.492466 + outer loop + vertex 0.915087 2.12205 2.50043 + vertex 0.919347 2.12334 2.50192 + vertex 0.914357 2.12373 2.49721 + endloop + endfacet + facet normal -0.594377 0.450694 0.666026 + outer loop + vertex 0.919347 2.12334 2.50192 + vertex 0.92 2.12705 2.5 + vertex 0.914357 2.12373 2.49721 + endloop + endfacet + facet normal -0.390827 0.831128 0.395576 + outer loop + vertex 0.919347 2.12334 2.50192 + vertex 0.915087 2.12205 2.50043 + vertex 0.917172 2.12163 2.50337 + endloop + endfacet + facet normal -0.329872 -0.94232 0.056727 + outer loop + vertex 0.925 0.898676 2.5 + vertex 0.920358 0.9 2.495 + vertex 0.925 0.898375 2.495 + endloop + endfacet + facet normal -0.271147 -0.962533 -0.00314498 + outer loop + vertex 0.9203 0.9 2.5 + vertex 0.920358 0.9 2.495 + vertex 0.925 0.898676 2.5 + endloop + endfacet + facet normal -0.260714 -0.925498 0.274738 + outer loop + vertex 0.925 0.898676 2.5 + vertex 0.925 0.9 2.50446 + vertex 0.9203 0.9 2.5 + endloop + endfacet + facet normal -0.400309 -0.813513 0.421841 + outer loop + vertex 0.9203 0.9 2.5 + vertex 0.925 0.9 2.50446 + vertex 0.925 0.90028 2.505 + endloop + endfacet + facet normal -0.389822 -0.82332 0.412533 + outer loop + vertex 0.9203 0.9 2.5 + vertex 0.925 0.90028 2.505 + vertex 0.92 0.900142 2.5 + endloop + endfacet + facet normal -0.270599 -0.916098 0.295873 + outer loop + vertex 0.92 0.900142 2.5 + vertex 0.925 0.90028 2.505 + vertex 0.918935 0.900962 2.50157 + endloop + endfacet + facet normal -0.161993 -0.982598 0.0908815 + outer loop + vertex 0.925 0.90028 2.505 + vertex 0.923674 0.900573 2.5058 + vertex 0.918935 0.900962 2.50157 + endloop + endfacet + facet normal -0.351206 -0.882846 0.311829 + outer loop + vertex 0.923674 0.900573 2.5058 + vertex 0.918031 0.90264 2.5053 + vertex 0.918935 0.900962 2.50157 + endloop + endfacet + facet normal -0.41702 -0.801625 0.42836 + outer loop + vertex 0.917707 0.904665 2.50878 + vertex 0.923028 0.902583 2.51006 + vertex 0.920775 0.904337 2.51115 + endloop + endfacet + facet normal -0.417005 -0.801933 0.427797 + outer loop + vertex 0.917707 0.904665 2.50878 + vertex 0.918031 0.90264 2.5053 + vertex 0.923028 0.902583 2.51006 + endloop + endfacet + facet normal -0.349243 -0.866801 0.35593 + outer loop + vertex 0.918031 0.90264 2.5053 + vertex 0.923674 0.900573 2.5058 + vertex 0.923028 0.902583 2.51006 + endloop + endfacet + facet normal -0.378334 -0.787778 0.486075 + outer loop + vertex 0.923028 0.902583 2.51006 + vertex 0.922804 0.904849 2.51356 + vertex 0.920775 0.904337 2.51115 + endloop + endfacet + facet normal -0.480987 -0.702274 0.524846 + outer loop + vertex 0.917707 0.904665 2.50878 + vertex 0.920775 0.904337 2.51115 + vertex 0.918283 0.90631 2.51151 + endloop + endfacet + facet normal -0.527165 -0.559152 0.639879 + outer loop + vertex 0.923406 0.906755 2.51629 + vertex 0.920675 0.909437 2.51639 + vertex 0.91842 0.908626 2.51382 + endloop + endfacet + facet normal -0.520154 -0.64253 0.562668 + outer loop + vertex 0.922804 0.904849 2.51356 + vertex 0.923406 0.906755 2.51629 + vertex 0.91842 0.908626 2.51382 + endloop + endfacet + facet normal -0.483003 -0.604322 0.633642 + outer loop + vertex 0.922804 0.904849 2.51356 + vertex 0.91842 0.908626 2.51382 + vertex 0.918283 0.90631 2.51151 + endloop + endfacet + facet normal -0.471432 -0.693749 0.544486 + outer loop + vertex 0.922804 0.904849 2.51356 + vertex 0.918283 0.90631 2.51151 + vertex 0.920775 0.904337 2.51115 + endloop + endfacet + facet normal -0.49435 -0.527497 0.690916 + outer loop + vertex 0.923406 0.906755 2.51629 + vertex 0.924106 0.90894 2.51846 + vertex 0.920675 0.909437 2.51639 + endloop + endfacet + facet normal 0.584983 0.593197 -0.553094 + outer loop + vertex 0.925 0.912436 2.5 + vertex 0.9224 0.915 2.5 + vertex 0.925 0.915 2.50275 + endloop + endfacet + facet normal -0.576778 -0.482415 0.659244 + outer loop + vertex 0.91842 0.908626 2.51382 + vertex 0.920675 0.909437 2.51639 + vertex 0.917923 0.911102 2.5152 + endloop + endfacet + facet normal -0.521679 -0.288926 0.802728 + outer loop + vertex 0.920675 0.909437 2.51639 + vertex 0.919922 0.911627 2.51669 + vertex 0.917923 0.911102 2.5152 + endloop + endfacet + facet normal -0.525781 -0.289922 0.799687 + outer loop + vertex 0.920675 0.909437 2.51639 + vertex 0.924106 0.90894 2.51846 + vertex 0.919922 0.911627 2.51669 + endloop + endfacet + facet normal -0.469835 -0.157162 0.868652 + outer loop + vertex 0.924106 0.90894 2.51846 + vertex 0.922855 0.912202 2.51838 + vertex 0.919922 0.911627 2.51669 + endloop + endfacet + facet normal 0.235644 0.945956 -0.222798 + outer loop + vertex 0.9224 0.915 2.5 + vertex 0.923594 0.915301 2.50254 + vertex 0.925 0.915 2.50275 + endloop + endfacet + facet normal 0.652873 0.652873 -0.384075 + outer loop + vertex 0.9224 0.915 2.5 + vertex 0.92 0.9174 2.5 + vertex 0.923594 0.915301 2.50254 + endloop + endfacet + facet normal 0.0954368 0.829494 0.550301 + outer loop + vertex 0.92 0.9174 2.5 + vertex 0.918658 0.916136 2.50214 + vertex 0.923594 0.915301 2.50254 + endloop + endfacet + facet normal 0.17598 0.97493 -0.136169 + outer loop + vertex 0.923594 0.915301 2.50254 + vertex 0.918658 0.916136 2.50214 + vertex 0.923559 0.915895 2.50675 + endloop + endfacet + facet normal 0.0337677 0.999297 0.0163061 + outer loop + vertex 0.923559 0.915895 2.50675 + vertex 0.918658 0.916136 2.50214 + vertex 0.918149 0.916081 2.50657 + endloop + endfacet + facet normal 0.0338691 0.999338 0.0132815 + outer loop + vertex 0.923559 0.915895 2.50675 + vertex 0.918149 0.916081 2.50657 + vertex 0.923147 0.915846 2.51151 + endloop + endfacet + facet normal -0.0804487 0.988448 0.128445 + outer loop + vertex 0.923147 0.915846 2.51151 + vertex 0.918149 0.916081 2.50657 + vertex 0.918149 0.915444 2.51147 + endloop + endfacet + facet normal -0.0796565 0.969359 0.232373 + outer loop + vertex 0.923147 0.915846 2.51151 + vertex 0.918149 0.915444 2.51147 + vertex 0.923392 0.914633 2.51665 + endloop + endfacet + facet normal -0.286754 0.85871 0.424723 + outer loop + vertex 0.923392 0.914633 2.51665 + vertex 0.918149 0.915444 2.51147 + vertex 0.918846 0.913864 2.51514 + endloop + endfacet + facet normal -0.519862 0.302948 0.798728 + outer loop + vertex 0.922855 0.912202 2.51838 + vertex 0.918846 0.913864 2.51514 + vertex 0.919922 0.911627 2.51669 + endloop + endfacet + facet normal -0.343 0.592908 0.728568 + outer loop + vertex 0.923392 0.914633 2.51665 + vertex 0.918846 0.913864 2.51514 + vertex 0.922855 0.912202 2.51838 + endloop + endfacet + facet normal -0.70113 -0.151747 -0.696699 + outer loop + vertex 0.925 0.976969 2.535 + vertex 0.924344 0.98 2.535 + vertex 0.925 0.98 2.53434 + endloop + endfacet + facet normal -0.595397 -0.128863 -0.79303 + outer loop + vertex 0.924307 0.97709 2.5355 + vertex 0.924344 0.98 2.535 + vertex 0.925 0.976969 2.535 + endloop + endfacet + facet normal -0.762932 -0.100192 -0.638668 + outer loop + vertex 0.922809 0.981235 2.53664 + vertex 0.924344 0.98 2.535 + vertex 0.924307 0.97709 2.5355 + endloop + endfacet + facet normal -0.934152 -0.352651 0.0547369 + outer loop + vertex 0.924307 0.97709 2.5355 + vertex 0.924172 0.977876 2.53825 + vertex 0.922809 0.981235 2.53664 + endloop + endfacet + facet normal -0.800283 -0.391498 -0.454176 + outer loop + vertex 0.924344 0.98 2.535 + vertex 0.922809 0.981235 2.53664 + vertex 0.921898 0.985 2.535 + endloop + endfacet + facet normal -0.952249 -0.281732 -0.117677 + outer loop + vertex 0.921898 0.985 2.535 + vertex 0.922809 0.981235 2.53664 + vertex 0.921627 0.985063 2.53705 + endloop + endfacet + facet normal -0.939153 -0.307695 0.152694 + outer loop + vertex 0.923559 0.980633 2.54003 + vertex 0.922809 0.981235 2.53664 + vertex 0.924172 0.977876 2.53825 + endloop + endfacet + facet normal -0.943311 -0.292832 0.15625 + outer loop + vertex 0.923559 0.980633 2.54003 + vertex 0.92224 0.985242 2.54071 + vertex 0.922809 0.981235 2.53664 + endloop + endfacet + facet normal -0.936005 -0.307353 0.17155 + outer loop + vertex 0.92224 0.985242 2.54071 + vertex 0.921627 0.985063 2.53705 + vertex 0.922809 0.981235 2.53664 + endloop + endfacet + facet normal -0.918446 -0.300596 0.257096 + outer loop + vertex 0.923559 0.980633 2.54003 + vertex 0.923838 0.982317 2.543 + vertex 0.92224 0.985242 2.54071 + endloop + endfacet + facet normal -0.909743 -0.368322 0.191591 + outer loop + vertex 0.92 0.99 2.5356 + vertex 0.92 0.989688 2.535 + vertex 0.921898 0.985 2.535 + endloop + endfacet + facet normal -0.890249 -0.369833 0.265857 + outer loop + vertex 0.92 0.99 2.5356 + vertex 0.921898 0.985 2.535 + vertex 0.921314 0.99 2.54 + endloop + endfacet + facet normal -0.991105 0.0163118 -0.132077 + outer loop + vertex 0.921314 0.99 2.54 + vertex 0.921898 0.985 2.535 + vertex 0.921627 0.985063 2.53705 + endloop + endfacet + facet normal -0.971687 -0.163564 0.170502 + outer loop + vertex 0.921627 0.985063 2.53705 + vertex 0.92224 0.985242 2.54071 + vertex 0.921314 0.99 2.54 + endloop + endfacet + facet normal -0.956237 -0.215851 -0.197535 + outer loop + vertex 0.921314 0.99 2.54 + vertex 0.92224 0.985242 2.54071 + vertex 0.921085 0.989365 2.5418 + endloop + endfacet + facet normal -0.918479 -0.301965 0.255368 + outer loop + vertex 0.923335 0.985457 2.54491 + vertex 0.92224 0.985242 2.54071 + vertex 0.923838 0.982317 2.543 + endloop + endfacet + facet normal -0.908347 -0.332047 0.254263 + outer loop + vertex 0.923335 0.985457 2.54491 + vertex 0.921964 0.989733 2.54559 + vertex 0.92224 0.985242 2.54071 + endloop + endfacet + facet normal -0.915303 -0.320808 0.243522 + outer loop + vertex 0.921964 0.989733 2.54559 + vertex 0.921085 0.989365 2.5418 + vertex 0.92224 0.985242 2.54071 + endloop + endfacet + facet normal -0.876462 -0.336312 0.344542 + outer loop + vertex 0.923335 0.985457 2.54491 + vertex 0.92374 0.987493 2.54792 + vertex 0.921964 0.989733 2.54559 + endloop + endfacet + facet normal 0.579253 0.216171 -0.785962 + outer loop + vertex 0.919253 0.99305 2.53932 + vertex 0.92 0.993521 2.54 + vertex 0.921314 0.99 2.54 + endloop + endfacet + facet normal -0.834517 -0.532025 0.143287 + outer loop + vertex 0.919253 0.99305 2.53932 + vertex 0.921314 0.99 2.54 + vertex 0.91993 0.992951 2.5429 + endloop + endfacet + facet normal -0.948058 -0.242484 -0.205883 + outer loop + vertex 0.91993 0.992951 2.5429 + vertex 0.921314 0.99 2.54 + vertex 0.921085 0.989365 2.5418 + endloop + endfacet + facet normal -0.898947 -0.363868 0.243913 + outer loop + vertex 0.921085 0.989365 2.5418 + vertex 0.921964 0.989733 2.54559 + vertex 0.91993 0.992951 2.5429 + endloop + endfacet + facet normal -0.89902 -0.362764 0.245286 + outer loop + vertex 0.91993 0.992951 2.5429 + vertex 0.921964 0.989733 2.54559 + vertex 0.920788 0.99329 2.54654 + endloop + endfacet + facet normal -0.876468 -0.333446 0.347301 + outer loop + vertex 0.923242 0.990582 2.54963 + vertex 0.921964 0.989733 2.54559 + vertex 0.92374 0.987493 2.54792 + endloop + endfacet + facet normal -0.860221 -0.370818 0.35002 + outer loop + vertex 0.923242 0.990582 2.54963 + vertex 0.921731 0.994018 2.54956 + vertex 0.921964 0.989733 2.54559 + endloop + endfacet + facet normal -0.853743 -0.377975 0.358131 + outer loop + vertex 0.921731 0.994018 2.54956 + vertex 0.920788 0.99329 2.54654 + vertex 0.921964 0.989733 2.54559 + endloop + endfacet + facet normal -0.825249 -0.353476 0.440476 + outer loop + vertex 0.923242 0.990582 2.54963 + vertex 0.923601 0.993094 2.55232 + vertex 0.921731 0.994018 2.54956 + endloop + endfacet + facet normal -0.898359 -0.409566 0.158764 + outer loop + vertex 0.919253 0.99305 2.53932 + vertex 0.91993 0.992951 2.5429 + vertex 0.918426 0.995396 2.54069 + endloop + endfacet + facet normal -0.904889 -0.374699 0.201932 + outer loop + vertex 0.918551 0.996731 2.54373 + vertex 0.918426 0.995396 2.54069 + vertex 0.91993 0.992951 2.5429 + endloop + endfacet + facet normal -0.885441 -0.381583 0.265309 + outer loop + vertex 0.918551 0.996731 2.54373 + vertex 0.91993 0.992951 2.5429 + vertex 0.919785 0.99627 2.54719 + endloop + endfacet + facet normal -0.901553 -0.356419 0.245292 + outer loop + vertex 0.919785 0.99627 2.54719 + vertex 0.91993 0.992951 2.5429 + vertex 0.920788 0.99329 2.54654 + endloop + endfacet + facet normal -0.859264 -0.366314 0.357044 + outer loop + vertex 0.920788 0.99329 2.54654 + vertex 0.921731 0.994018 2.54956 + vertex 0.919785 0.99627 2.54719 + endloop + endfacet + facet normal -0.859185 -0.369314 0.35413 + outer loop + vertex 0.919785 0.99627 2.54719 + vertex 0.921731 0.994018 2.54956 + vertex 0.920685 0.997106 2.55024 + endloop + endfacet + facet normal -0.802252 -0.374461 0.464942 + outer loop + vertex 0.921731 0.994018 2.54956 + vertex 0.922181 0.997819 2.5534 + vertex 0.920685 0.997106 2.55024 + endloop + endfacet + facet normal -0.826058 -0.349005 0.442519 + outer loop + vertex 0.923601 0.993094 2.55232 + vertex 0.922181 0.997819 2.5534 + vertex 0.921731 0.994018 2.54956 + endloop + endfacet + facet normal -0.890501 -0.366888 0.269076 + outer loop + vertex 0.918551 0.996731 2.54373 + vertex 0.919785 0.99627 2.54719 + vertex 0.918213 0.999127 2.54588 + endloop + endfacet + facet normal -0.867331 -0.352082 0.351816 + outer loop + vertex 0.919785 0.99627 2.54719 + vertex 0.920685 0.997106 2.55024 + vertex 0.919296 1.00008 2.5498 + endloop + endfacet + facet normal -0.883256 -0.336687 0.326346 + outer loop + vertex 0.918213 0.999127 2.54588 + vertex 0.919785 0.99627 2.54719 + vertex 0.919296 1.00008 2.5498 + endloop + endfacet + facet normal -0.797348 -0.34182 0.497388 + outer loop + vertex 0.922202 1.00158 2.55614 + vertex 0.921255 1.00523 2.55713 + vertex 0.920194 1.00265 2.55365 + endloop + endfacet + facet normal -0.795996 -0.353616 0.491269 + outer loop + vertex 0.922181 0.997819 2.5534 + vertex 0.922202 1.00158 2.55614 + vertex 0.920194 1.00265 2.55365 + endloop + endfacet + facet normal -0.825143 -0.362547 0.433242 + outer loop + vertex 0.922181 0.997819 2.5534 + vertex 0.920194 1.00265 2.55365 + vertex 0.919296 1.00008 2.5498 + endloop + endfacet + facet normal -0.82737 -0.31676 0.463812 + outer loop + vertex 0.922181 0.997819 2.5534 + vertex 0.919296 1.00008 2.5498 + vertex 0.920685 0.997106 2.55024 + endloop + endfacet + facet normal -0.77587 -0.344656 0.528429 + outer loop + vertex 0.922202 1.00158 2.55614 + vertex 0.923151 1.00314 2.55855 + vertex 0.921255 1.00523 2.55713 + endloop + endfacet + facet normal -0.790865 -0.35037 0.501771 + outer loop + vertex 0.918896 1.00686 2.55455 + vertex 0.920194 1.00265 2.55365 + vertex 0.921255 1.00523 2.55713 + endloop + endfacet + facet normal -0.790946 -0.347234 0.503817 + outer loop + vertex 0.919775 1.00905 2.55744 + vertex 0.918896 1.00686 2.55455 + vertex 0.921255 1.00523 2.55713 + endloop + endfacet + facet normal -0.774151 -0.338916 0.534628 + outer loop + vertex 0.922958 1.0057 2.55989 + vertex 0.921255 1.00523 2.55713 + vertex 0.923151 1.00314 2.55855 + endloop + endfacet + facet normal -0.773383 -0.340883 0.534487 + outer loop + vertex 0.922958 1.0057 2.55989 + vertex 0.921673 1.00865 2.55992 + vertex 0.921255 1.00523 2.55713 + endloop + endfacet + facet normal -0.771644 -0.342369 0.536049 + outer loop + vertex 0.921673 1.00865 2.55992 + vertex 0.919775 1.00905 2.55744 + vertex 0.921255 1.00523 2.55713 + endloop + endfacet + facet normal -0.764549 -0.337163 0.549351 + outer loop + vertex 0.922958 1.0057 2.55989 + vertex 0.923546 1.00809 2.56218 + vertex 0.921673 1.00865 2.55992 + endloop + endfacet + facet normal -0.789505 -0.349095 0.504791 + outer loop + vertex 0.918896 1.00686 2.55455 + vertex 0.919775 1.00905 2.55744 + vertex 0.91818 1.01024 2.55576 + endloop + endfacet + facet normal -0.789348 -0.33693 0.513233 + outer loop + vertex 0.918846 1.01187 2.55786 + vertex 0.91818 1.01024 2.55576 + vertex 0.919775 1.00905 2.55744 + endloop + endfacet + facet normal -0.776043 -0.335642 0.533949 + outer loop + vertex 0.918846 1.01187 2.55786 + vertex 0.919775 1.00905 2.55744 + vertex 0.920304 1.01141 2.55969 + endloop + endfacet + facet normal -0.772281 -0.33941 0.537013 + outer loop + vertex 0.920304 1.01141 2.55969 + vertex 0.919775 1.00905 2.55744 + vertex 0.921673 1.00865 2.55992 + endloop + endfacet + facet normal -0.764894 -0.334655 0.550403 + outer loop + vertex 0.921673 1.00865 2.55992 + vertex 0.9222 1.0127 2.56311 + vertex 0.920304 1.01141 2.55969 + endloop + endfacet + facet normal -0.764968 -0.334594 0.550337 + outer loop + vertex 0.923546 1.00809 2.56218 + vertex 0.9222 1.0127 2.56311 + vertex 0.921673 1.00865 2.55992 + endloop + endfacet + facet normal -0.777505 -0.326731 0.537339 + outer loop + vertex 0.918846 1.01187 2.55786 + vertex 0.920304 1.01141 2.55969 + vertex 0.91935 1.01441 2.56013 + endloop + endfacet + facet normal -0.768876 -0.318933 0.554176 + outer loop + vertex 0.922403 1.01679 2.56585 + vertex 0.921734 1.02062 2.56712 + vertex 0.920338 1.01758 2.56343 + endloop + endfacet + facet normal -0.76763 -0.329578 0.549657 + outer loop + vertex 0.9222 1.0127 2.56311 + vertex 0.922403 1.01679 2.56585 + vertex 0.920338 1.01758 2.56343 + endloop + endfacet + facet normal -0.769237 -0.330025 0.547136 + outer loop + vertex 0.9222 1.0127 2.56311 + vertex 0.920338 1.01758 2.56343 + vertex 0.91935 1.01441 2.56013 + endloop + endfacet + facet normal -0.76928 -0.325913 0.549535 + outer loop + vertex 0.9222 1.0127 2.56311 + vertex 0.91935 1.01441 2.56013 + vertex 0.920304 1.01141 2.55969 + endloop + endfacet + facet normal -0.756939 -0.321713 0.568809 + outer loop + vertex 0.922403 1.01679 2.56585 + vertex 0.923631 1.01792 2.56812 + vertex 0.921734 1.02062 2.56712 + endloop + endfacet + facet normal -0.767477 -0.320695 0.555098 + outer loop + vertex 0.91896 1.02197 2.56407 + vertex 0.920338 1.01758 2.56343 + vertex 0.921734 1.02062 2.56712 + endloop + endfacet + facet normal -0.7674 -0.321991 0.554454 + outer loop + vertex 0.920121 1.02516 2.56752 + vertex 0.91896 1.02197 2.56407 + vertex 0.921734 1.02062 2.56712 + endloop + endfacet + facet normal -0.74447 -0.303313 0.594782 + outer loop + vertex 0.924495 1.02009 2.57031 + vertex 0.921734 1.02062 2.56712 + vertex 0.923631 1.01792 2.56812 + endloop + endfacet + facet normal -0.739944 -0.329196 0.586612 + outer loop + vertex 0.924495 1.02009 2.57031 + vertex 0.922741 1.02429 2.57045 + vertex 0.921734 1.02062 2.56712 + endloop + endfacet + facet normal -0.751297 -0.31837 0.578095 + outer loop + vertex 0.922741 1.02429 2.57045 + vertex 0.920121 1.02516 2.56752 + vertex 0.921734 1.02062 2.56712 + endloop + endfacet + facet normal -0.71332 -0.319386 0.623833 + outer loop + vertex 0.924495 1.02009 2.57031 + vertex 0.925672 1.02273 2.573 + vertex 0.922741 1.02429 2.57045 + endloop + endfacet + facet normal -0.768466 -0.320769 0.553685 + outer loop + vertex 0.91896 1.02197 2.56407 + vertex 0.920121 1.02516 2.56752 + vertex 0.918055 1.0257 2.56497 + endloop + endfacet + facet normal -0.768308 -0.321714 0.553356 + outer loop + vertex 0.918598 1.02847 2.56734 + vertex 0.918055 1.0257 2.56497 + vertex 0.920121 1.02516 2.56752 + endloop + endfacet + facet normal -0.755147 -0.31446 0.575212 + outer loop + vertex 0.918598 1.02847 2.56734 + vertex 0.920121 1.02516 2.56752 + vertex 0.920994 1.02969 2.57115 + endloop + endfacet + facet normal -0.751375 -0.317703 0.578361 + outer loop + vertex 0.920994 1.02969 2.57115 + vertex 0.920121 1.02516 2.56752 + vertex 0.922741 1.02429 2.57045 + endloop + endfacet + facet normal -0.725274 -0.313689 0.612844 + outer loop + vertex 0.922741 1.02429 2.57045 + vertex 0.924145 1.02693 2.57346 + vertex 0.920994 1.02969 2.57115 + endloop + endfacet + facet normal -0.713639 -0.327324 0.619337 + outer loop + vertex 0.925672 1.02273 2.573 + vertex 0.924145 1.02693 2.57346 + vertex 0.922741 1.02429 2.57045 + endloop + endfacet + facet normal -0.75255 -0.320239 0.575427 + outer loop + vertex 0.917296 1.03293 2.56811 + vertex 0.918598 1.02847 2.56734 + vertex 0.920994 1.02969 2.57115 + endloop + endfacet + facet normal -0.752944 -0.322207 0.57381 + outer loop + vertex 0.919514 1.03519 2.57229 + vertex 0.917296 1.03293 2.56811 + vertex 0.920994 1.02969 2.57115 + endloop + endfacet + facet normal -0.724105 -0.309379 0.616406 + outer loop + vertex 0.923644 1.03027 2.57455 + vertex 0.920994 1.02969 2.57115 + vertex 0.924145 1.02693 2.57346 + endloop + endfacet + facet normal -0.724675 -0.307713 0.61657 + outer loop + vertex 0.923644 1.03027 2.57455 + vertex 0.922449 1.0338 2.57491 + vertex 0.920994 1.02969 2.57115 + endloop + endfacet + facet normal -0.710248 -0.321627 0.626183 + outer loop + vertex 0.922449 1.0338 2.57491 + vertex 0.919514 1.03519 2.57229 + vertex 0.920994 1.02969 2.57115 + endloop + endfacet + facet normal -0.659825 -0.293384 0.691778 + outer loop + vertex 0.923644 1.03027 2.57455 + vertex 0.925521 1.03177 2.57698 + vertex 0.922449 1.0338 2.57491 + endloop + endfacet + facet normal -0.74038 -0.342737 0.578246 + outer loop + vertex 0.917296 1.03293 2.56811 + vertex 0.919514 1.03519 2.57229 + vertex 0.9174 1.03693 2.57062 + endloop + endfacet + facet normal -0.738052 -0.330072 0.5885 + outer loop + vertex 0.918276 1.03874 2.57273 + vertex 0.9174 1.03693 2.57062 + vertex 0.919514 1.03519 2.57229 + endloop + endfacet + facet normal -0.704618 -0.323721 0.631442 + outer loop + vertex 0.918276 1.03874 2.57273 + vertex 0.919514 1.03519 2.57229 + vertex 0.92061 1.03887 2.5754 + endloop + endfacet + facet normal -0.710221 -0.318836 0.627638 + outer loop + vertex 0.92061 1.03887 2.5754 + vertex 0.919514 1.03519 2.57229 + vertex 0.922449 1.0338 2.57491 + endloop + endfacet + facet normal -0.65292 -0.304472 0.693536 + outer loop + vertex 0.922449 1.0338 2.57491 + vertex 0.924692 1.03663 2.57826 + vertex 0.92061 1.03887 2.5754 + endloop + endfacet + facet normal -0.660238 -0.295196 0.690612 + outer loop + vertex 0.925521 1.03177 2.57698 + vertex 0.924692 1.03663 2.57826 + vertex 0.922449 1.0338 2.57491 + endloop + endfacet + facet normal -0.706538 -0.316827 0.632791 + outer loop + vertex 0.917299 1.04254 2.57354 + vertex 0.918276 1.03874 2.57273 + vertex 0.92061 1.03887 2.5754 + endloop + endfacet + facet normal -0.710546 -0.324773 0.624216 + outer loop + vertex 0.919668 1.0424 2.57617 + vertex 0.917299 1.04254 2.57354 + vertex 0.92061 1.03887 2.5754 + endloop + endfacet + facet normal -0.650872 -0.322528 0.687271 + outer loop + vertex 0.92061 1.03887 2.5754 + vertex 0.92219 1.04258 2.57864 + vertex 0.919668 1.0424 2.57617 + endloop + endfacet + facet normal -0.654934 -0.318906 0.685099 + outer loop + vertex 0.924692 1.03663 2.57826 + vertex 0.92219 1.04258 2.57864 + vertex 0.92061 1.03887 2.5754 + endloop + endfacet + facet normal -0.711796 -0.319239 0.625646 + outer loop + vertex 0.917299 1.04254 2.57354 + vertex 0.919668 1.0424 2.57617 + vertex 0.918409 1.04548 2.57631 + endloop + endfacet + facet normal -0.625991 -0.295529 0.721663 + outer loop + vertex 0.922698 1.0461 2.58062 + vertex 0.921423 1.04988 2.58107 + vertex 0.919723 1.04781 2.57875 + endloop + endfacet + facet normal -0.629072 -0.310978 0.712433 + outer loop + vertex 0.92219 1.04258 2.57864 + vertex 0.922698 1.0461 2.58062 + vertex 0.919723 1.04781 2.57875 + endloop + endfacet + facet normal -0.665183 -0.327186 0.671179 + outer loop + vertex 0.92219 1.04258 2.57864 + vertex 0.919723 1.04781 2.57875 + vertex 0.918409 1.04548 2.57631 + endloop + endfacet + facet normal -0.656917 -0.299883 0.691758 + outer loop + vertex 0.92219 1.04258 2.57864 + vertex 0.918409 1.04548 2.57631 + vertex 0.919668 1.0424 2.57617 + endloop + endfacet + facet normal -0.556479 -0.279236 0.782533 + outer loop + vertex 0.922698 1.0461 2.58062 + vertex 0.924989 1.04695 2.58256 + vertex 0.921423 1.04988 2.58107 + endloop + endfacet + facet normal -0.627724 -0.293391 0.72103 + outer loop + vertex 0.917243 1.05299 2.57869 + vertex 0.919723 1.04781 2.57875 + vertex 0.921423 1.04988 2.58107 + endloop + endfacet + facet normal -0.632273 -0.306883 0.711375 + outer loop + vertex 0.920004 1.05359 2.58141 + vertex 0.917243 1.05299 2.57869 + vertex 0.921423 1.04988 2.58107 + endloop + endfacet + facet normal -0.553907 -0.283491 0.782828 + outer loop + vertex 0.921423 1.04988 2.58107 + vertex 0.92385 1.05232 2.58367 + vertex 0.920004 1.05359 2.58141 + endloop + endfacet + facet normal -0.556792 -0.279839 0.782095 + outer loop + vertex 0.924989 1.04695 2.58256 + vertex 0.92385 1.05232 2.58367 + vertex 0.921423 1.04988 2.58107 + endloop + endfacet + facet normal -0.625535 -0.326056 0.708798 + outer loop + vertex 0.917243 1.05299 2.57869 + vertex 0.920004 1.05359 2.58141 + vertex 0.917613 1.05627 2.58053 + endloop + endfacet + facet normal -0.597363 -0.28793 0.748501 + outer loop + vertex 0.920004 1.05359 2.58141 + vertex 0.919878 1.05697 2.58261 + vertex 0.917613 1.05627 2.58053 + endloop + endfacet + facet normal -0.554944 -0.296544 0.777238 + outer loop + vertex 0.920004 1.05359 2.58141 + vertex 0.92385 1.05232 2.58367 + vertex 0.919878 1.05697 2.58261 + endloop + endfacet + facet normal -0.542015 -0.282215 0.791565 + outer loop + vertex 0.92385 1.05232 2.58367 + vertex 0.922708 1.05766 2.58479 + vertex 0.919878 1.05697 2.58261 + endloop + endfacet + facet normal -0.535849 -0.280874 0.796226 + outer loop + vertex 0.9225 1.06104 2.5858 + vertex 0.921157 1.06484 2.58624 + vertex 0.918689 1.0624 2.58372 + endloop + endfacet + facet normal -0.534898 -0.273119 0.799556 + outer loop + vertex 0.9225 1.06104 2.5858 + vertex 0.918689 1.0624 2.58372 + vertex 0.922708 1.05766 2.58479 + endloop + endfacet + facet normal -0.542353 -0.281221 0.791686 + outer loop + vertex 0.922708 1.05766 2.58479 + vertex 0.918689 1.0624 2.58372 + vertex 0.919878 1.05697 2.58261 + endloop + endfacet + facet normal -0.4793 -0.265522 0.836522 + outer loop + vertex 0.9225 1.06104 2.5858 + vertex 0.924804 1.06197 2.58742 + vertex 0.921157 1.06484 2.58624 + endloop + endfacet + facet normal -0.527266 -0.291525 0.798125 + outer loop + vertex 0.917344 1.06779 2.5848 + vertex 0.918689 1.0624 2.58372 + vertex 0.921157 1.06484 2.58624 + endloop + endfacet + facet normal -0.527962 -0.292891 0.797165 + outer loop + vertex 0.919643 1.06875 2.58668 + vertex 0.917344 1.06779 2.5848 + vertex 0.921157 1.06484 2.58624 + endloop + endfacet + facet normal -0.470177 -0.275107 0.8386 + outer loop + vertex 0.921157 1.06484 2.58624 + vertex 0.923782 1.06743 2.58856 + vertex 0.919643 1.06875 2.58668 + endloop + endfacet + facet normal -0.478896 -0.264821 0.836976 + outer loop + vertex 0.924804 1.06197 2.58742 + vertex 0.923782 1.06743 2.58856 + vertex 0.921157 1.06484 2.58624 + endloop + endfacet + facet normal -0.526245 -0.296574 0.796938 + outer loop + vertex 0.917344 1.06779 2.5848 + vertex 0.919643 1.06875 2.58668 + vertex 0.916893 1.07118 2.58577 + endloop + endfacet + facet normal -0.514173 -0.277487 0.811559 + outer loop + vertex 0.919643 1.06875 2.58668 + vertex 0.919073 1.07273 2.58768 + vertex 0.916893 1.07118 2.58577 + endloop + endfacet + facet normal -0.470534 -0.277785 0.837516 + outer loop + vertex 0.919643 1.06875 2.58668 + vertex 0.923782 1.06743 2.58856 + vertex 0.919073 1.07273 2.58768 + endloop + endfacet + facet normal -0.462241 -0.269192 0.844908 + outer loop + vertex 0.923782 1.06743 2.58856 + vertex 0.922773 1.07284 2.58974 + vertex 0.919073 1.07273 2.58768 + endloop + endfacet + facet normal -0.441027 -0.262117 0.858364 + outer loop + vertex 0.922762 1.07625 2.59076 + vertex 0.921108 1.08001 2.59106 + vertex 0.919687 1.07696 2.5894 + endloop + endfacet + facet normal -0.440836 -0.25969 0.8592 + outer loop + vertex 0.922762 1.07625 2.59076 + vertex 0.919687 1.07696 2.5894 + vertex 0.922773 1.07284 2.58974 + endloop + endfacet + facet normal -0.461124 -0.276187 0.843259 + outer loop + vertex 0.922773 1.07284 2.58974 + vertex 0.919687 1.07696 2.5894 + vertex 0.919073 1.07273 2.58768 + endloop + endfacet + facet normal -0.412167 -0.250823 0.875903 + outer loop + vertex 0.922762 1.07625 2.59076 + vertex 0.925188 1.07792 2.59238 + vertex 0.921108 1.08001 2.59106 + endloop + endfacet + facet normal -0.442841 -0.260956 0.857784 + outer loop + vertex 0.917024 1.08223 2.58963 + vertex 0.919687 1.07696 2.5894 + vertex 0.921108 1.08001 2.59106 + endloop + endfacet + facet normal -0.447425 -0.273474 0.851483 + outer loop + vertex 0.919358 1.08387 2.59138 + vertex 0.917024 1.08223 2.58963 + vertex 0.921108 1.08001 2.59106 + endloop + endfacet + facet normal -0.411161 -0.2589 0.874024 + outer loop + vertex 0.921108 1.08001 2.59106 + vertex 0.922574 1.08319 2.59269 + vertex 0.919358 1.08387 2.59138 + endloop + endfacet + facet normal -0.414384 -0.256929 0.873083 + outer loop + vertex 0.925188 1.07792 2.59238 + vertex 0.922574 1.08319 2.59269 + vertex 0.921108 1.08001 2.59106 + endloop + endfacet + facet normal -0.443487 -0.279266 0.851663 + outer loop + vertex 0.917024 1.08223 2.58963 + vertex 0.919358 1.08387 2.59138 + vertex 0.916963 1.08612 2.59087 + endloop + endfacet + facet normal -0.429614 -0.261669 0.864269 + outer loop + vertex 0.919358 1.08387 2.59138 + vertex 0.91911 1.08784 2.59246 + vertex 0.916963 1.08612 2.59087 + endloop + endfacet + facet normal -0.411458 -0.262832 0.872709 + outer loop + vertex 0.919358 1.08387 2.59138 + vertex 0.922574 1.08319 2.59269 + vertex 0.91911 1.08784 2.59246 + endloop + endfacet + facet normal -0.400101 -0.253993 0.880572 + outer loop + vertex 0.922574 1.08319 2.59269 + vertex 0.923535 1.08745 2.59436 + vertex 0.91911 1.08784 2.59246 + endloop + endfacet + facet normal -0.391461 -0.254373 0.884338 + outer loop + vertex 0.923248 1.09144 2.59538 + vertex 0.921496 1.0952 2.59569 + vertex 0.920029 1.09202 2.59412 + endloop + endfacet + facet normal -0.391494 -0.254946 0.884158 + outer loop + vertex 0.923248 1.09144 2.59538 + vertex 0.920029 1.09202 2.59412 + vertex 0.923535 1.08745 2.59436 + endloop + endfacet + facet normal -0.399863 -0.261665 0.878431 + outer loop + vertex 0.923535 1.08745 2.59436 + vertex 0.920029 1.09202 2.59412 + vertex 0.91911 1.08784 2.59246 + endloop + endfacet + facet normal -0.392356 -0.254748 0.883833 + outer loop + vertex 0.923248 1.09144 2.59538 + vertex 0.925729 1.09318 2.59698 + vertex 0.921496 1.0952 2.59569 + endloop + endfacet + facet normal -0.397182 -0.250959 0.88276 + outer loop + vertex 0.917424 1.09716 2.59441 + vertex 0.920029 1.09202 2.59412 + vertex 0.921496 1.0952 2.59569 + endloop + endfacet + facet normal -0.396893 -0.250114 0.88313 + outer loop + vertex 0.919901 1.09897 2.59604 + vertex 0.917424 1.09716 2.59441 + vertex 0.921496 1.0952 2.59569 + endloop + endfacet + facet normal -0.375574 -0.24215 0.894599 + outer loop + vertex 0.921496 1.0952 2.59569 + vertex 0.923186 1.09836 2.59725 + vertex 0.919901 1.09897 2.59604 + endloop + endfacet + facet normal -0.385664 -0.235499 0.892078 + outer loop + vertex 0.925729 1.09318 2.59698 + vertex 0.923186 1.09836 2.59725 + vertex 0.921496 1.0952 2.59569 + endloop + endfacet + facet normal -0.39804 -0.248492 0.883072 + outer loop + vertex 0.917424 1.09716 2.59441 + vertex 0.919901 1.09897 2.59604 + vertex 0.91759 1.10112 2.5956 + endloop + endfacet + facet normal -0.379172 -0.225314 0.897475 + outer loop + vertex 0.919901 1.09897 2.59604 + vertex 0.920256 1.10299 2.5972 + vertex 0.91759 1.10112 2.5956 + endloop + endfacet + facet normal -0.374353 -0.226253 0.89926 + outer loop + vertex 0.919901 1.09897 2.59604 + vertex 0.923186 1.09836 2.59725 + vertex 0.920256 1.10299 2.5972 + endloop + endfacet + facet normal -0.437202 -0.208827 0.874783 + outer loop + vertex 0.922749 1.13107 2.60535 + vertex 0.921571 1.13499 2.6057 + vertex 0.919568 1.13201 2.60399 + endloop + endfacet + facet normal -0.437699 -0.211937 0.873786 + outer loop + vertex 0.922749 1.13107 2.60535 + vertex 0.919568 1.13201 2.60399 + vertex 0.922408 1.12712 2.60423 + endloop + endfacet + facet normal -0.501723 -0.224696 0.835336 + outer loop + vertex 0.922749 1.13107 2.60535 + vertex 0.925081 1.13221 2.60706 + vertex 0.921571 1.13499 2.6057 + endloop + endfacet + facet normal -0.436168 -0.2097 0.875091 + outer loop + vertex 0.917457 1.13729 2.6042 + vertex 0.919568 1.13201 2.60399 + vertex 0.921571 1.13499 2.6057 + endloop + endfacet + facet normal -0.430663 -0.196047 0.880963 + outer loop + vertex 0.92034 1.13901 2.60599 + vertex 0.917457 1.13729 2.6042 + vertex 0.921571 1.13499 2.6057 + endloop + endfacet + facet normal -0.502143 -0.21477 0.837691 + outer loop + vertex 0.921571 1.13499 2.6057 + vertex 0.924262 1.13777 2.60803 + vertex 0.92034 1.13901 2.60599 + endloop + endfacet + facet normal -0.498576 -0.219068 0.838708 + outer loop + vertex 0.925081 1.13221 2.60706 + vertex 0.924262 1.13777 2.60803 + vertex 0.921571 1.13499 2.6057 + endloop + endfacet + facet normal -0.434781 -0.188701 0.880544 + outer loop + vertex 0.917457 1.13729 2.6042 + vertex 0.92034 1.13901 2.60599 + vertex 0.917891 1.14142 2.6053 + endloop + endfacet + facet normal -0.454229 -0.21291 0.86507 + outer loop + vertex 0.92034 1.13901 2.60599 + vertex 0.920514 1.14315 2.6071 + vertex 0.917891 1.14142 2.6053 + endloop + endfacet + facet normal -0.500687 -0.20454 0.841116 + outer loop + vertex 0.92034 1.13901 2.60599 + vertex 0.924262 1.13777 2.60803 + vertex 0.920514 1.14315 2.6071 + endloop + endfacet + facet normal -0.512049 -0.21405 0.831858 + outer loop + vertex 0.924262 1.13777 2.60803 + vertex 0.923951 1.14263 2.60909 + vertex 0.920514 1.14315 2.6071 + endloop + endfacet + facet normal -0.512022 -0.207771 0.833466 + outer loop + vertex 0.923951 1.14263 2.60909 + vertex 0.922252 1.14715 2.60917 + vertex 0.920514 1.14315 2.6071 + endloop + endfacet + facet normal -0.496064 -0.218284 0.8404 + outer loop + vertex 0.920514 1.14315 2.6071 + vertex 0.922252 1.14715 2.60917 + vertex 0.918335 1.14831 2.60716 + endloop + endfacet + facet normal -0.52278 -0.214797 0.824963 + outer loop + vertex 0.922663 1.15077 2.61038 + vertex 0.921779 1.15457 2.61081 + vertex 0.919809 1.15181 2.60884 + endloop + endfacet + facet normal -0.522992 -0.216053 0.8245 + outer loop + vertex 0.922663 1.15077 2.61038 + vertex 0.919809 1.15181 2.60884 + vertex 0.922252 1.14715 2.60917 + endloop + endfacet + facet normal -0.493544 -0.199089 0.846627 + outer loop + vertex 0.922252 1.14715 2.60917 + vertex 0.919809 1.15181 2.60884 + vertex 0.918335 1.14831 2.60716 + endloop + endfacet + facet normal -0.573189 -0.222414 0.788661 + outer loop + vertex 0.922663 1.15077 2.61038 + vertex 0.924844 1.15181 2.61226 + vertex 0.921779 1.15457 2.61081 + endloop + endfacet + facet normal -0.520953 -0.216594 0.825648 + outer loop + vertex 0.918096 1.1567 2.60904 + vertex 0.919809 1.15181 2.60884 + vertex 0.921779 1.15457 2.61081 + endloop + endfacet + facet normal -0.513785 -0.19634 0.83515 + outer loop + vertex 0.920611 1.15942 2.61123 + vertex 0.918096 1.1567 2.60904 + vertex 0.921779 1.15457 2.61081 + endloop + endfacet + facet normal -0.572582 -0.206864 0.793321 + outer loop + vertex 0.921779 1.15457 2.61081 + vertex 0.924609 1.15675 2.61342 + vertex 0.920611 1.15942 2.61123 + endloop + endfacet + facet normal -0.568293 -0.213893 0.79454 + outer loop + vertex 0.924844 1.15181 2.61226 + vertex 0.924609 1.15675 2.61342 + vertex 0.921779 1.15457 2.61081 + endloop + endfacet + facet normal -0.515804 -0.193925 0.83447 + outer loop + vertex 0.916746 1.16198 2.60943 + vertex 0.918096 1.1567 2.60904 + vertex 0.920611 1.15942 2.61123 + endloop + endfacet + facet normal -0.507401 -0.174696 0.843816 + outer loop + vertex 0.919459 1.16345 2.61137 + vertex 0.916746 1.16198 2.60943 + vertex 0.920611 1.15942 2.61123 + endloop + endfacet + facet normal -0.573955 -0.192027 0.796054 + outer loop + vertex 0.920611 1.15942 2.61123 + vertex 0.922769 1.16266 2.61357 + vertex 0.919459 1.16345 2.61137 + endloop + endfacet + facet normal -0.568883 -0.197121 0.798446 + outer loop + vertex 0.924609 1.15675 2.61342 + vertex 0.922769 1.16266 2.61357 + vertex 0.920611 1.15942 2.61123 + endloop + endfacet + facet normal -0.507587 -0.174312 0.843784 + outer loop + vertex 0.916746 1.16198 2.60943 + vertex 0.919459 1.16345 2.61137 + vertex 0.917246 1.16576 2.61052 + endloop + endfacet + facet normal -0.53312 -0.207497 0.8202 + outer loop + vertex 0.919459 1.16345 2.61137 + vertex 0.919628 1.16694 2.61236 + vertex 0.917246 1.16576 2.61052 + endloop + endfacet + facet normal -0.574264 -0.19814 0.794331 + outer loop + vertex 0.919459 1.16345 2.61137 + vertex 0.922769 1.16266 2.61357 + vertex 0.919628 1.16694 2.61236 + endloop + endfacet + facet normal -0.5881 -0.212201 0.780454 + outer loop + vertex 0.922769 1.16266 2.61357 + vertex 0.922587 1.16733 2.6147 + vertex 0.919628 1.16694 2.61236 + endloop + endfacet + facet normal -0.59537 -0.206919 0.77635 + outer loop + vertex 0.923509 1.17015 2.61624 + vertex 0.921737 1.17475 2.61611 + vertex 0.919138 1.17226 2.61345 + endloop + endfacet + facet normal -0.598899 -0.224318 0.768766 + outer loop + vertex 0.923509 1.17015 2.61624 + vertex 0.919138 1.17226 2.61345 + vertex 0.922587 1.16733 2.6147 + endloop + endfacet + facet normal -0.58779 -0.21363 0.780298 + outer loop + vertex 0.922587 1.16733 2.6147 + vertex 0.919138 1.17226 2.61345 + vertex 0.919628 1.16694 2.61236 + endloop + endfacet + facet normal -0.607529 -0.211922 0.765505 + outer loop + vertex 0.923509 1.17015 2.61624 + vertex 0.925225 1.1725 2.61825 + vertex 0.921737 1.17475 2.61611 + endloop + endfacet + facet normal -0.605565 -0.191974 0.772293 + outer loop + vertex 0.918764 1.17719 2.61438 + vertex 0.919138 1.17226 2.61345 + vertex 0.921737 1.17475 2.61611 + endloop + endfacet + facet normal -0.603819 -0.188231 0.774579 + outer loop + vertex 0.920439 1.17927 2.6162 + vertex 0.918764 1.17719 2.61438 + vertex 0.921737 1.17475 2.61611 + endloop + endfacet + facet normal -0.60867 -0.189543 0.770451 + outer loop + vertex 0.921737 1.17475 2.61611 + vertex 0.923679 1.17735 2.61828 + vertex 0.920439 1.17927 2.6162 + endloop + endfacet + facet normal -0.602567 -0.196631 0.773466 + outer loop + vertex 0.925225 1.1725 2.61825 + vertex 0.923679 1.17735 2.61828 + vertex 0.921737 1.17475 2.61611 + endloop + endfacet + facet normal -0.595917 -0.197829 0.778297 + outer loop + vertex 0.917227 1.18165 2.61434 + vertex 0.918764 1.17719 2.61438 + vertex 0.920439 1.17927 2.6162 + endloop + endfacet + facet normal -0.586238 -0.174821 0.791051 + outer loop + vertex 0.919494 1.18217 2.61613 + vertex 0.917227 1.18165 2.61434 + vertex 0.920439 1.17927 2.6162 + endloop + endfacet + facet normal -0.610781 -0.183286 0.770294 + outer loop + vertex 0.920439 1.17927 2.6162 + vertex 0.922009 1.18272 2.61826 + vertex 0.919494 1.18217 2.61613 + endloop + endfacet + facet normal -0.607603 -0.185868 0.772186 + outer loop + vertex 0.923679 1.17735 2.61828 + vertex 0.922009 1.18272 2.61826 + vertex 0.920439 1.17927 2.6162 + endloop + endfacet + facet normal -0.582769 -0.188302 0.790521 + outer loop + vertex 0.917227 1.18165 2.61434 + vertex 0.919494 1.18217 2.61613 + vertex 0.918431 1.18508 2.61604 + endloop + endfacet + facet normal -0.598806 -0.202433 0.774888 + outer loop + vertex 0.923048 1.18645 2.61998 + vertex 0.922226 1.19015 2.62031 + vertex 0.920216 1.1877 2.61812 + endloop + endfacet + facet normal -0.597054 -0.192759 0.778698 + outer loop + vertex 0.922009 1.18272 2.61826 + vertex 0.923048 1.18645 2.61998 + vertex 0.920216 1.1877 2.61812 + endloop + endfacet + facet normal -0.606581 -0.196428 0.770374 + outer loop + vertex 0.922009 1.18272 2.61826 + vertex 0.920216 1.1877 2.61812 + vertex 0.918431 1.18508 2.61604 + endloop + endfacet + facet normal -0.607046 -0.197813 0.769653 + outer loop + vertex 0.922009 1.18272 2.61826 + vertex 0.918431 1.18508 2.61604 + vertex 0.919494 1.18217 2.61613 + endloop + endfacet + facet normal -0.532913 -0.192194 0.824054 + outer loop + vertex 0.923048 1.18645 2.61998 + vertex 0.925811 1.18788 2.6221 + vertex 0.922226 1.19015 2.62031 + endloop + endfacet + facet normal -0.606316 -0.193172 0.771405 + outer loop + vertex 0.918901 1.19239 2.61826 + vertex 0.920216 1.1877 2.61812 + vertex 0.922226 1.19015 2.62031 + endloop + endfacet + facet normal -0.609229 -0.201596 0.766941 + outer loop + vertex 0.921264 1.19472 2.62075 + vertex 0.918901 1.19239 2.61826 + vertex 0.922226 1.19015 2.62031 + endloop + endfacet + facet normal -0.563195 -0.19533 0.802906 + outer loop + vertex 0.922226 1.19015 2.62031 + vertex 0.924363 1.1921 2.62228 + vertex 0.921264 1.19472 2.62075 + endloop + endfacet + facet normal -0.544337 -0.222151 0.808917 + outer loop + vertex 0.925811 1.18788 2.6221 + vertex 0.924363 1.1921 2.62228 + vertex 0.922226 1.19015 2.62031 + endloop + endfacet + facet normal -0.627972 -0.173661 0.758612 + outer loop + vertex 0.917603 1.19777 2.61842 + vertex 0.918901 1.19239 2.61826 + vertex 0.921264 1.19472 2.62075 + endloop + endfacet + facet normal -0.628659 -0.175185 0.757693 + outer loop + vertex 0.920557 1.19967 2.62131 + vertex 0.917603 1.19777 2.61842 + vertex 0.921264 1.19472 2.62075 + endloop + endfacet + facet normal -0.565221 -0.171686 0.806876 + outer loop + vertex 0.921264 1.19472 2.62075 + vertex 0.924492 1.19658 2.62341 + vertex 0.920557 1.19967 2.62131 + endloop + endfacet + facet normal -0.558222 -0.186148 0.80854 + outer loop + vertex 0.924363 1.1921 2.62228 + vertex 0.924492 1.19658 2.62341 + vertex 0.921264 1.19472 2.62075 + endloop + endfacet + facet normal -0.652033 -0.124062 0.747972 + outer loop + vertex 0.917672 1.20313 2.61937 + vertex 0.917603 1.19777 2.61842 + vertex 0.920557 1.19967 2.62131 + endloop + endfacet + facet normal -0.660426 -0.136448 0.73839 + outer loop + vertex 0.920015 1.20358 2.62154 + vertex 0.917672 1.20313 2.61937 + vertex 0.920557 1.19967 2.62131 + endloop + endfacet + facet normal -0.574971 -0.128777 0.807975 + outer loop + vertex 0.920557 1.19967 2.62131 + vertex 0.923069 1.20273 2.62358 + vertex 0.920015 1.20358 2.62154 + endloop + endfacet + facet normal -0.555435 -0.15196 0.817558 + outer loop + vertex 0.924492 1.19658 2.62341 + vertex 0.923069 1.20273 2.62358 + vertex 0.920557 1.19967 2.62131 + endloop + endfacet + facet normal -0.669763 -0.0844305 0.737759 + outer loop + vertex 0.917672 1.20313 2.61937 + vertex 0.920015 1.20358 2.62154 + vertex 0.918783 1.20552 2.62065 + endloop + endfacet + facet normal -0.612166 -0.0235719 0.790378 + outer loop + vertex 0.920015 1.20358 2.62154 + vertex 0.920518 1.20723 2.62204 + vertex 0.918783 1.20552 2.62065 + endloop + endfacet + facet normal -0.561592 -0.0354915 0.826653 + outer loop + vertex 0.920015 1.20358 2.62154 + vertex 0.923069 1.20273 2.62358 + vertex 0.920518 1.20723 2.62204 + endloop + endfacet + facet normal -0.567402 -0.0402172 0.822458 + outer loop + vertex 0.923069 1.20273 2.62358 + vertex 0.923919 1.20783 2.62442 + vertex 0.920518 1.20723 2.62204 + endloop + endfacet + facet normal -0.630057 -0.0146761 0.77641 + outer loop + vertex 0.919306 1.2141 2.62108 + vertex 0.916744 1.21352 2.61899 + vertex 0.919181 1.21104 2.62092 + endloop + endfacet + facet normal -0.60858 -0.0164265 0.793322 + outer loop + vertex 0.919181 1.21104 2.62092 + vertex 0.921868 1.2122 2.62301 + vertex 0.919306 1.2141 2.62108 + endloop + endfacet + facet normal -0.617079 0.015072 0.786757 + outer loop + vertex 0.919181 1.21104 2.62092 + vertex 0.920518 1.20723 2.62204 + vertex 0.921868 1.2122 2.62301 + endloop + endfacet + facet normal -0.572151 -0.00363924 0.82014 + outer loop + vertex 0.920518 1.20723 2.62204 + vertex 0.923919 1.20783 2.62442 + vertex 0.921868 1.2122 2.62301 + endloop + endfacet + facet normal -0.622965 -0.0587879 0.780037 + outer loop + vertex 0.916744 1.21352 2.61899 + vertex 0.919306 1.2141 2.62108 + vertex 0.917861 1.21659 2.62011 + endloop + endfacet + facet normal -0.628911 -0.0642535 0.774818 + outer loop + vertex 0.919306 1.2141 2.62108 + vertex 0.920313 1.21744 2.62217 + vertex 0.917861 1.21659 2.62011 + endloop + endfacet + facet normal -0.629569 -0.0638897 0.774313 + outer loop + vertex 0.919306 1.2141 2.62108 + vertex 0.921868 1.2122 2.62301 + vertex 0.920313 1.21744 2.62217 + endloop + endfacet + facet normal -0.535619 -0.0249312 0.844092 + outer loop + vertex 0.921868 1.2122 2.62301 + vertex 0.923924 1.21634 2.62443 + vertex 0.920313 1.21744 2.62217 + endloop + endfacet + facet normal -0.551993 -0.116671 0.825646 + outer loop + vertex 0.923924 1.21634 2.62443 + vertex 0.922412 1.22149 2.62415 + vertex 0.920313 1.21744 2.62217 + endloop + endfacet + facet normal -0.54923 -0.118848 0.827177 + outer loop + vertex 0.920313 1.21744 2.62217 + vertex 0.922412 1.22149 2.62415 + vertex 0.919179 1.22191 2.62206 + endloop + endfacet + facet normal -0.52088 -0.176494 0.835185 + outer loop + vertex 0.922843 1.22587 2.6252 + vertex 0.921764 1.23016 2.62543 + vertex 0.919386 1.22642 2.62316 + endloop + endfacet + facet normal -0.520017 -0.150448 0.840802 + outer loop + vertex 0.922843 1.22587 2.6252 + vertex 0.919386 1.22642 2.62316 + vertex 0.922412 1.22149 2.62415 + endloop + endfacet + facet normal -0.549767 -0.17345 0.817111 + outer loop + vertex 0.922412 1.22149 2.62415 + vertex 0.919386 1.22642 2.62316 + vertex 0.919179 1.22191 2.62206 + endloop + endfacet + facet normal -0.40155 -0.15018 0.90344 + outer loop + vertex 0.922843 1.22587 2.6252 + vertex 0.925959 1.22828 2.62699 + vertex 0.921764 1.23016 2.62543 + endloop + endfacet + facet normal -0.52551 -0.172314 0.833155 + outer loop + vertex 0.917722 1.23254 2.62338 + vertex 0.919386 1.22642 2.62316 + vertex 0.921764 1.23016 2.62543 + endloop + endfacet + facet normal -0.532043 -0.190432 0.825025 + outer loop + vertex 0.920764 1.23512 2.62593 + vertex 0.917722 1.23254 2.62338 + vertex 0.921764 1.23016 2.62543 + endloop + endfacet + facet normal -0.4212 -0.174635 0.889996 + outer loop + vertex 0.921764 1.23016 2.62543 + vertex 0.924601 1.23345 2.62742 + vertex 0.920764 1.23512 2.62593 + endloop + endfacet + facet normal -0.41238 -0.183628 0.892313 + outer loop + vertex 0.925959 1.22828 2.62699 + vertex 0.924601 1.23345 2.62742 + vertex 0.921764 1.23016 2.62543 + endloop + endfacet + facet normal -0.526544 -0.198523 0.826644 + outer loop + vertex 0.917592 1.23755 2.6245 + vertex 0.917722 1.23254 2.62338 + vertex 0.920764 1.23512 2.62593 + endloop + endfacet + facet normal -0.526764 -0.198955 0.8264 + outer loop + vertex 0.920019 1.23894 2.62638 + vertex 0.917592 1.23755 2.6245 + vertex 0.920764 1.23512 2.62593 + endloop + endfacet + facet normal -0.417267 -0.185012 0.889752 + outer loop + vertex 0.920764 1.23512 2.62593 + vertex 0.923522 1.23857 2.62795 + vertex 0.920019 1.23894 2.62638 + endloop + endfacet + facet normal -0.422744 -0.179763 0.888241 + outer loop + vertex 0.924601 1.23345 2.62742 + vertex 0.923522 1.23857 2.62795 + vertex 0.920764 1.23512 2.62593 + endloop + endfacet + facet normal -0.529955 -0.192653 0.825853 + outer loop + vertex 0.917592 1.23755 2.6245 + vertex 0.920019 1.23894 2.62638 + vertex 0.917953 1.24106 2.62555 + endloop + endfacet + facet normal -0.499927 -0.153034 0.85244 + outer loop + vertex 0.920019 1.23894 2.62638 + vertex 0.920761 1.24276 2.6275 + vertex 0.917953 1.24106 2.62555 + endloop + endfacet + facet normal -0.417217 -0.180344 0.890734 + outer loop + vertex 0.920019 1.23894 2.62638 + vertex 0.923522 1.23857 2.62795 + vertex 0.920761 1.24276 2.6275 + endloop + endfacet + facet normal -0.402141 -0.169441 0.899762 + outer loop + vertex 0.923522 1.23857 2.62795 + vertex 0.923925 1.24214 2.6288 + vertex 0.920761 1.24276 2.6275 + endloop + endfacet + facet normal -0.400653 -0.154955 0.903032 + outer loop + vertex 0.923925 1.24214 2.6288 + vertex 0.923882 1.24588 2.62942 + vertex 0.920761 1.24276 2.6275 + endloop + endfacet + facet normal -0.394448 -0.162077 0.904512 + outer loop + vertex 0.920761 1.24276 2.6275 + vertex 0.923882 1.24588 2.62942 + vertex 0.91944 1.24791 2.62785 + endloop + endfacet + facet normal -0.406102 -0.196966 0.892348 + outer loop + vertex 0.923882 1.24588 2.62942 + vertex 0.921799 1.2516 2.62973 + vertex 0.91944 1.24791 2.62785 + endloop + endfacet + facet normal -0.437153 -0.172201 0.882748 + outer loop + vertex 0.91944 1.24791 2.62785 + vertex 0.921799 1.2516 2.62973 + vertex 0.917664 1.25268 2.6279 + endloop + endfacet + facet normal -0.375711 -0.145526 0.915239 + outer loop + vertex 0.92221 1.25566 2.63064 + vertex 0.920983 1.25952 2.63076 + vertex 0.919084 1.2562 2.62945 + endloop + endfacet + facet normal -0.377632 -0.165921 0.910969 + outer loop + vertex 0.92221 1.25566 2.63064 + vertex 0.919084 1.2562 2.62945 + vertex 0.921799 1.2516 2.62973 + endloop + endfacet + facet normal -0.44177 -0.206135 0.873125 + outer loop + vertex 0.921799 1.2516 2.62973 + vertex 0.919084 1.2562 2.62945 + vertex 0.917664 1.25268 2.6279 + endloop + endfacet + facet normal -0.22614 -0.0996049 0.968989 + outer loop + vertex 0.92221 1.25566 2.63064 + vertex 0.925311 1.25814 2.63162 + vertex 0.920983 1.25952 2.63076 + endloop + endfacet + facet normal -0.399688 -0.128791 0.907558 + outer loop + vertex 0.917131 1.26117 2.62929 + vertex 0.919084 1.2562 2.62945 + vertex 0.920983 1.25952 2.63076 + endloop + endfacet + facet normal -0.409467 -0.160047 0.898177 + outer loop + vertex 0.919747 1.26336 2.63088 + vertex 0.917131 1.26117 2.62929 + vertex 0.920983 1.25952 2.63076 + endloop + endfacet + facet normal -0.236604 -0.106451 0.965757 + outer loop + vertex 0.920983 1.25952 2.63076 + vertex 0.923847 1.26392 2.63194 + vertex 0.919747 1.26336 2.63088 + endloop + endfacet + facet normal -0.229482 -0.111399 0.966917 + outer loop + vertex 0.925311 1.25814 2.63162 + vertex 0.923847 1.26392 2.63194 + vertex 0.920983 1.25952 2.63076 + endloop + endfacet + facet normal -0.413684 -0.154335 0.897244 + outer loop + vertex 0.917131 1.26117 2.62929 + vertex 0.919747 1.26336 2.63088 + vertex 0.917517 1.26539 2.6302 + endloop + endfacet + facet normal -0.358628 -0.0831373 0.929771 + outer loop + vertex 0.919747 1.26336 2.63088 + vertex 0.920725 1.26801 2.63167 + vertex 0.917517 1.26539 2.6302 + endloop + endfacet + facet normal -0.235234 -0.115137 0.965095 + outer loop + vertex 0.919747 1.26336 2.63088 + vertex 0.923847 1.26392 2.63194 + vertex 0.920725 1.26801 2.63167 + endloop + endfacet + facet normal -0.211561 -0.0965276 0.972587 + outer loop + vertex 0.923847 1.26392 2.63194 + vertex 0.924961 1.26902 2.63269 + vertex 0.920725 1.26801 2.63167 + endloop + endfacet + facet normal -0.207254 -0.113601 0.971669 + outer loop + vertex 0.924961 1.26902 2.63269 + vertex 0.924209 1.27299 2.63299 + vertex 0.920725 1.26801 2.63167 + endloop + endfacet + facet normal -0.228875 -0.0976659 0.968544 + outer loop + vertex 0.920725 1.26801 2.63167 + vertex 0.924209 1.27299 2.63299 + vertex 0.919998 1.27341 2.63204 + endloop + endfacet + facet normal -0.230212 -0.116365 0.966158 + outer loop + vertex 0.924209 1.27299 2.63299 + vertex 0.923663 1.2777 2.63343 + vertex 0.919998 1.27341 2.63204 + endloop + endfacet + facet normal -0.247321 -0.100911 0.963665 + outer loop + vertex 0.919998 1.27341 2.63204 + vertex 0.923663 1.2777 2.63343 + vertex 0.919463 1.27856 2.63244 + endloop + endfacet + facet normal -0.249884 -0.116116 0.961288 + outer loop + vertex 0.923663 1.2777 2.63343 + vertex 0.923238 1.28244 2.63389 + vertex 0.919463 1.27856 2.63244 + endloop + endfacet + facet normal -0.260072 -0.105657 0.959791 + outer loop + vertex 0.919463 1.27856 2.63244 + vertex 0.923238 1.28244 2.63389 + vertex 0.918721 1.28391 2.63283 + endloop + endfacet + facet normal -0.266268 -0.127899 0.955376 + outer loop + vertex 0.923238 1.28244 2.63389 + vertex 0.922661 1.28646 2.63427 + vertex 0.918721 1.28391 2.63283 + endloop + endfacet + facet normal -0.255968 -0.144126 0.955881 + outer loop + vertex 0.918721 1.28391 2.63283 + vertex 0.922661 1.28646 2.63427 + vertex 0.919921 1.28835 2.63382 + endloop + endfacet + facet normal -0.230135 -0.10404 0.967581 + outer loop + vertex 0.922661 1.28646 2.63427 + vertex 0.923608 1.29073 2.63495 + vertex 0.919921 1.28835 2.63382 + endloop + endfacet + facet normal -0.234319 -0.0973894 0.967269 + outer loop + vertex 0.919921 1.28835 2.63382 + vertex 0.923608 1.29073 2.63495 + vertex 0.918891 1.29221 2.63396 + endloop + endfacet + facet normal -0.246872 -0.143256 0.958401 + outer loop + vertex 0.923608 1.29073 2.63495 + vertex 0.921925 1.29549 2.63523 + vertex 0.918891 1.29221 2.63396 + endloop + endfacet + facet normal -0.272559 -0.118161 0.954856 + outer loop + vertex 0.918891 1.29221 2.63396 + vertex 0.921925 1.29549 2.63523 + vertex 0.917542 1.29717 2.63419 + endloop + endfacet + facet normal -0.280584 -0.142725 0.949159 + outer loop + vertex 0.917542 1.29717 2.63419 + vertex 0.921925 1.29549 2.63523 + vertex 0.921224 1.29978 2.63567 + endloop + endfacet + facet normal -0.160472 -0.0927189 0.982676 + outer loop + vertex 0.918951 1.33283 2.63846 + vertex 0.923185 1.3374 2.63959 + vertex 0.918672 1.33755 2.63886 + endloop + endfacet + facet normal -0.160766 -0.109775 0.980869 + outer loop + vertex 0.923185 1.3374 2.63959 + vertex 0.922101 1.34116 2.63983 + vertex 0.918672 1.33755 2.63886 + endloop + endfacet + facet normal -0.294341 0.167639 0.940883 + outer loop + vertex 0.920425 1.71419 2.63592 + vertex 0.916479 1.71111 2.63523 + vertex 0.919024 1.7105 2.63614 + endloop + endfacet + facet normal -0.137476 0.110633 0.984307 + outer loop + vertex 0.919024 1.7105 2.63614 + vertex 0.923259 1.71229 2.63653 + vertex 0.920425 1.71419 2.63592 + endloop + endfacet + facet normal -0.132943 0.099531 0.986113 + outer loop + vertex 0.919024 1.7105 2.63614 + vertex 0.919152 1.70733 2.63647 + vertex 0.923259 1.71229 2.63653 + endloop + endfacet + facet normal -0.273982 0.139142 0.951616 + outer loop + vertex 0.917975 1.71648 2.63488 + vertex 0.916479 1.71111 2.63523 + vertex 0.920425 1.71419 2.63592 + endloop + endfacet + facet normal -0.264062 0.150259 0.95273 + outer loop + vertex 0.922019 1.71795 2.63577 + vertex 0.917975 1.71648 2.63488 + vertex 0.920425 1.71419 2.63592 + endloop + endfacet + facet normal -0.132693 0.0959467 0.986502 + outer loop + vertex 0.920425 1.71419 2.63592 + vertex 0.924516 1.71724 2.63617 + vertex 0.922019 1.71795 2.63577 + endloop + endfacet + facet normal -0.140343 0.106368 0.984373 + outer loop + vertex 0.923259 1.71229 2.63653 + vertex 0.924516 1.71724 2.63617 + vertex 0.920425 1.71419 2.63592 + endloop + endfacet + facet normal -0.155169 0.129626 0.979347 + outer loop + vertex 0.922019 1.71795 2.63577 + vertex 0.924837 1.72034 2.6359 + vertex 0.922884 1.72189 2.63538 + endloop + endfacet + facet normal -0.26429 0.150996 0.95255 + outer loop + vertex 0.922019 1.71795 2.63577 + vertex 0.922884 1.72189 2.63538 + vertex 0.917975 1.71648 2.63488 + endloop + endfacet + facet normal -0.230836 0.119409 0.965638 + outer loop + vertex 0.917975 1.71648 2.63488 + vertex 0.922884 1.72189 2.63538 + vertex 0.918322 1.72187 2.63429 + endloop + endfacet + facet normal -0.131213 0.101008 0.986195 + outer loop + vertex 0.924837 1.72034 2.6359 + vertex 0.922019 1.71795 2.63577 + vertex 0.924516 1.71724 2.63617 + endloop + endfacet + facet normal -0.230669 0.125898 0.964853 + outer loop + vertex 0.922884 1.72189 2.63538 + vertex 0.923122 1.72689 2.63479 + vertex 0.918322 1.72187 2.63429 + endloop + endfacet + facet normal -0.224315 0.119597 0.96715 + outer loop + vertex 0.918322 1.72187 2.63429 + vertex 0.923122 1.72689 2.63479 + vertex 0.918585 1.72699 2.63372 + endloop + endfacet + facet normal -0.223972 0.12661 0.966337 + outer loop + vertex 0.923122 1.72689 2.63479 + vertex 0.923315 1.73196 2.63417 + vertex 0.918585 1.72699 2.63372 + endloop + endfacet + facet normal -0.225968 0.128574 0.965612 + outer loop + vertex 0.918585 1.72699 2.63372 + vertex 0.923315 1.73196 2.63417 + vertex 0.918675 1.732 2.63308 + endloop + endfacet + facet normal -0.226041 0.126607 0.965855 + outer loop + vertex 0.923315 1.73196 2.63417 + vertex 0.923356 1.73702 2.63351 + vertex 0.918675 1.732 2.63308 + endloop + endfacet + facet normal -0.234771 0.135032 0.962626 + outer loop + vertex 0.918675 1.732 2.63308 + vertex 0.923356 1.73702 2.63351 + vertex 0.918286 1.73709 2.63227 + endloop + endfacet + facet normal -0.236272 0.0991425 0.966616 + outer loop + vertex 0.923356 1.73702 2.63351 + vertex 0.923486 1.74213 2.63302 + vertex 0.918286 1.73709 2.63227 + endloop + endfacet + facet normal -0.214758 0.0758775 0.973715 + outer loop + vertex 0.918286 1.73709 2.63227 + vertex 0.923486 1.74213 2.63302 + vertex 0.919151 1.74278 2.63201 + endloop + endfacet + facet normal -0.220686 0.0375252 0.974623 + outer loop + vertex 0.923486 1.74213 2.63302 + vertex 0.923639 1.74721 2.63286 + vertex 0.919151 1.74278 2.63201 + endloop + endfacet + facet normal -0.189567 0.00465111 0.981857 + outer loop + vertex 0.919151 1.74278 2.63201 + vertex 0.923639 1.74721 2.63286 + vertex 0.919295 1.74784 2.63202 + endloop + endfacet + facet normal -0.19362 -0.0246493 0.980767 + outer loop + vertex 0.923639 1.74721 2.63286 + vertex 0.923528 1.75222 2.63296 + vertex 0.919295 1.74784 2.63202 + endloop + endfacet + facet normal -0.178217 -0.0400725 0.983175 + outer loop + vertex 0.919295 1.74784 2.63202 + vertex 0.923528 1.75222 2.63296 + vertex 0.918798 1.75309 2.63214 + endloop + endfacet + facet normal -0.177826 -0.0378068 0.983335 + outer loop + vertex 0.923528 1.75222 2.63296 + vertex 0.923506 1.75721 2.63315 + vertex 0.918798 1.75309 2.63214 + endloop + endfacet + facet normal -0.154995 -0.064512 0.985807 + outer loop + vertex 0.918798 1.75309 2.63214 + vertex 0.923506 1.75721 2.63315 + vertex 0.919771 1.75797 2.63261 + endloop + endfacet + facet normal -0.202573 0.0958152 0.974568 + outer loop + vertex 0.918587 1.76195 2.63207 + vertex 0.923315 1.76695 2.63256 + vertex 0.919155 1.76697 2.63169 + endloop + endfacet + facet normal -0.441955 0.253751 0.860399 + outer loop + vertex 0.920549 1.77394 2.63072 + vertex 0.916959 1.77092 2.62977 + vertex 0.919075 1.77015 2.63108 + endloop + endfacet + facet normal -0.24584 0.186043 0.951289 + outer loop + vertex 0.919075 1.77015 2.63108 + vertex 0.923207 1.77202 2.63178 + vertex 0.920549 1.77394 2.63072 + endloop + endfacet + facet normal -0.242393 0.177456 0.953811 + outer loop + vertex 0.919075 1.77015 2.63108 + vertex 0.919155 1.76697 2.63169 + vertex 0.923207 1.77202 2.63178 + endloop + endfacet + facet normal -0.201225 0.144167 0.968878 + outer loop + vertex 0.919155 1.76697 2.63169 + vertex 0.923315 1.76695 2.63256 + vertex 0.923207 1.77202 2.63178 + endloop + endfacet + facet normal -0.424493 0.227972 0.876262 + outer loop + vertex 0.918402 1.77623 2.62909 + vertex 0.916959 1.77092 2.62977 + vertex 0.920549 1.77394 2.63072 + endloop + endfacet + facet normal -0.426892 0.225369 0.875769 + outer loop + vertex 0.922138 1.77779 2.63051 + vertex 0.918402 1.77623 2.62909 + vertex 0.920549 1.77394 2.63072 + endloop + endfacet + facet normal -0.24929 0.156528 0.955695 + outer loop + vertex 0.920549 1.77394 2.63072 + vertex 0.924533 1.77711 2.63124 + vertex 0.922138 1.77779 2.63051 + endloop + endfacet + facet normal -0.258372 0.168679 0.951205 + outer loop + vertex 0.923207 1.77202 2.63178 + vertex 0.924533 1.77711 2.63124 + vertex 0.920549 1.77394 2.63072 + endloop + endfacet + facet normal -0.288474 0.192587 0.93792 + outer loop + vertex 0.922138 1.77779 2.63051 + vertex 0.924872 1.78026 2.63084 + vertex 0.922943 1.78173 2.62994 + endloop + endfacet + facet normal -0.423249 0.211984 0.880865 + outer loop + vertex 0.922138 1.77779 2.63051 + vertex 0.922943 1.78173 2.62994 + vertex 0.918402 1.77623 2.62909 + endloop + endfacet + facet normal -0.41044 0.200031 0.889678 + outer loop + vertex 0.918402 1.77623 2.62909 + vertex 0.922943 1.78173 2.62994 + vertex 0.918194 1.78172 2.62775 + endloop + endfacet + facet normal -0.251523 0.149251 0.956274 + outer loop + vertex 0.924872 1.78026 2.63084 + vertex 0.922138 1.77779 2.63051 + vertex 0.924533 1.77711 2.63124 + endloop + endfacet + facet normal -0.413615 0.15771 0.896689 + outer loop + vertex 0.922943 1.78173 2.62994 + vertex 0.923233 1.78672 2.6292 + vertex 0.918194 1.78172 2.62775 + endloop + endfacet + facet normal -0.375557 0.112589 0.919935 + outer loop + vertex 0.918194 1.78172 2.62775 + vertex 0.923233 1.78672 2.6292 + vertex 0.919308 1.78732 2.62752 + endloop + endfacet + facet normal -0.372156 0.131492 0.918809 + outer loop + vertex 0.923233 1.78672 2.6292 + vertex 0.923625 1.79175 2.62864 + vertex 0.919308 1.78732 2.62752 + endloop + endfacet + facet normal -0.377784 0.137792 0.915583 + outer loop + vertex 0.919308 1.78732 2.62752 + vertex 0.923625 1.79175 2.62864 + vertex 0.919701 1.79222 2.62695 + endloop + endfacet + facet normal -0.376425 0.146375 0.914811 + outer loop + vertex 0.923625 1.79175 2.62864 + vertex 0.923716 1.79669 2.62789 + vertex 0.919701 1.79222 2.62695 + endloop + endfacet + facet normal -0.396959 0.167404 0.902441 + outer loop + vertex 0.919701 1.79222 2.62695 + vertex 0.923716 1.79669 2.62789 + vertex 0.919615 1.79684 2.62606 + endloop + endfacet + facet normal -0.511998 0.137606 0.847893 + outer loop + vertex 0.92063 1.8042 2.62539 + vertex 0.918264 1.80295 2.62417 + vertex 0.918859 1.80069 2.62489 + endloop + endfacet + facet normal -0.422417 0.0847597 0.90243 + outer loop + vertex 0.918859 1.80069 2.62489 + vertex 0.923319 1.80183 2.62688 + vertex 0.92063 1.8042 2.62539 + endloop + endfacet + facet normal -0.437268 0.179722 0.881191 + outer loop + vertex 0.918859 1.80069 2.62489 + vertex 0.919615 1.79684 2.62606 + vertex 0.923319 1.80183 2.62688 + endloop + endfacet + facet normal -0.398855 0.147287 0.905108 + outer loop + vertex 0.919615 1.79684 2.62606 + vertex 0.923716 1.79669 2.62789 + vertex 0.923319 1.80183 2.62688 + endloop + endfacet + facet normal -0.529738 0.192683 0.825985 + outer loop + vertex 0.918471 1.80595 2.6236 + vertex 0.918264 1.80295 2.62417 + vertex 0.92063 1.8042 2.62539 + endloop + endfacet + facet normal -0.542373 0.173094 0.822113 + outer loop + vertex 0.921603 1.80852 2.62513 + vertex 0.918471 1.80595 2.6236 + vertex 0.92063 1.8042 2.62539 + endloop + endfacet + facet normal -0.37702 0.14158 0.91532 + outer loop + vertex 0.92063 1.8042 2.62539 + vertex 0.924487 1.80728 2.62651 + vertex 0.921603 1.80852 2.62513 + endloop + endfacet + facet normal -0.37787 0.142844 0.914773 + outer loop + vertex 0.923319 1.80183 2.62688 + vertex 0.924487 1.80728 2.62651 + vertex 0.92063 1.8042 2.62539 + endloop + endfacet + facet normal -0.552193 0.191411 0.811446 + outer loop + vertex 0.919564 1.8114 2.62306 + vertex 0.918471 1.80595 2.6236 + vertex 0.921603 1.80852 2.62513 + endloop + endfacet + facet normal -0.557882 0.185559 0.80891 + outer loop + vertex 0.922715 1.81233 2.62502 + vertex 0.919564 1.8114 2.62306 + vertex 0.921603 1.80852 2.62513 + endloop + endfacet + facet normal -0.382095 0.137185 0.913884 + outer loop + vertex 0.921603 1.80852 2.62513 + vertex 0.925024 1.81165 2.62609 + vertex 0.922715 1.81233 2.62502 + endloop + endfacet + facet normal -0.37999 0.134491 0.915161 + outer loop + vertex 0.924487 1.80728 2.62651 + vertex 0.925024 1.81165 2.62609 + vertex 0.921603 1.80852 2.62513 + endloop + endfacet + facet normal -0.448664 0.226802 0.864443 + outer loop + vertex 0.922715 1.81233 2.62502 + vertex 0.925095 1.81474 2.62562 + vertex 0.923332 1.81644 2.62426 + endloop + endfacet + facet normal -0.562105 0.230867 0.79419 + outer loop + vertex 0.922715 1.81233 2.62502 + vertex 0.923332 1.81644 2.62426 + vertex 0.919564 1.8114 2.62306 + endloop + endfacet + facet normal -0.542044 0.211333 0.813343 + outer loop + vertex 0.919564 1.8114 2.62306 + vertex 0.923332 1.81644 2.62426 + vertex 0.919487 1.81674 2.62162 + endloop + endfacet + facet normal -0.379352 0.146129 0.91364 + outer loop + vertex 0.925095 1.81474 2.62562 + vertex 0.922715 1.81233 2.62502 + vertex 0.925024 1.81165 2.62609 + endloop + endfacet + facet normal -0.588861 0.160434 0.792151 + outer loop + vertex 0.920526 1.82438 2.62073 + vertex 0.918235 1.82322 2.61926 + vertex 0.918796 1.82084 2.62016 + endloop + endfacet + facet normal -0.536485 0.128017 0.834144 + outer loop + vertex 0.918796 1.82084 2.62016 + vertex 0.923051 1.82176 2.62276 + vertex 0.920526 1.82438 2.62073 + endloop + endfacet + facet normal -0.541356 0.199223 0.81685 + outer loop + vertex 0.918796 1.82084 2.62016 + vertex 0.919487 1.81674 2.62162 + vertex 0.923051 1.82176 2.62276 + endloop + endfacet + facet normal -0.543753 0.201405 0.81472 + outer loop + vertex 0.919487 1.81674 2.62162 + vertex 0.923332 1.81644 2.62426 + vertex 0.923051 1.82176 2.62276 + endloop + endfacet + facet normal -0.592328 0.17439 0.786598 + outer loop + vertex 0.918351 1.82618 2.6187 + vertex 0.918235 1.82322 2.61926 + vertex 0.920526 1.82438 2.62073 + endloop + endfacet + facet normal -0.599735 0.162074 0.783613 + outer loop + vertex 0.921347 1.82864 2.62048 + vertex 0.918351 1.82618 2.6187 + vertex 0.920526 1.82438 2.62073 + endloop + endfacet + facet normal -0.494995 0.14625 0.856499 + outer loop + vertex 0.920526 1.82438 2.62073 + vertex 0.924207 1.82726 2.62237 + vertex 0.921347 1.82864 2.62048 + endloop + endfacet + facet normal -0.506265 0.166528 0.846147 + outer loop + vertex 0.923051 1.82176 2.62276 + vertex 0.924207 1.82726 2.62237 + vertex 0.920526 1.82438 2.62073 + endloop + endfacet + facet normal -0.606161 0.175594 0.775716 + outer loop + vertex 0.919238 1.83139 2.61821 + vertex 0.918351 1.82618 2.6187 + vertex 0.921347 1.82864 2.62048 + endloop + endfacet + facet normal -0.614682 0.165358 0.771247 + outer loop + vertex 0.922131 1.83231 2.62032 + vertex 0.919238 1.83139 2.61821 + vertex 0.921347 1.82864 2.62048 + endloop + endfacet + facet normal -0.487385 0.142173 0.861535 + outer loop + vertex 0.921347 1.82864 2.62048 + vertex 0.924622 1.8318 2.62181 + vertex 0.922131 1.83231 2.62032 + endloop + endfacet + facet normal -0.493253 0.150265 0.856809 + outer loop + vertex 0.924207 1.82726 2.62237 + vertex 0.924622 1.8318 2.62181 + vertex 0.921347 1.82864 2.62048 + endloop + endfacet + facet normal -0.539145 0.210115 0.815582 + outer loop + vertex 0.922131 1.83231 2.62032 + vertex 0.92429 1.83498 2.62106 + vertex 0.921985 1.83561 2.61937 + endloop + endfacet + facet normal -0.61716 0.191601 0.763153 + outer loop + vertex 0.922131 1.83231 2.62032 + vertex 0.921985 1.83561 2.61937 + vertex 0.919238 1.83139 2.61821 + endloop + endfacet + facet normal -0.625591 0.19955 0.754199 + outer loop + vertex 0.919238 1.83139 2.61821 + vertex 0.921985 1.83561 2.61937 + vertex 0.919406 1.83626 2.61706 + endloop + endfacet + facet normal -0.484779 0.153402 0.861079 + outer loop + vertex 0.92429 1.83498 2.62106 + vertex 0.922131 1.83231 2.62032 + vertex 0.924622 1.8318 2.62181 + endloop + endfacet + facet normal -0.62194 0.202126 0.756529 + outer loop + vertex 0.920322 1.84348 2.61584 + vertex 0.917314 1.84071 2.61411 + vertex 0.919355 1.83962 2.61607 + endloop + endfacet + facet normal -0.621555 0.20205 0.756865 + outer loop + vertex 0.919355 1.83962 2.61607 + vertex 0.922335 1.84049 2.61829 + vertex 0.920322 1.84348 2.61584 + endloop + endfacet + facet normal -0.622055 0.211326 0.753916 + outer loop + vertex 0.919355 1.83962 2.61607 + vertex 0.919406 1.83626 2.61706 + vertex 0.922335 1.84049 2.61829 + endloop + endfacet + facet normal -0.622207 0.21148 0.753747 + outer loop + vertex 0.919406 1.83626 2.61706 + vertex 0.921985 1.83561 2.61937 + vertex 0.922335 1.84049 2.61829 + endloop + endfacet + facet normal -0.619688 0.197801 0.759514 + outer loop + vertex 0.917522 1.84544 2.61304 + vertex 0.917314 1.84071 2.61411 + vertex 0.920322 1.84348 2.61584 + endloop + endfacet + facet normal -0.614067 0.208331 0.761262 + outer loop + vertex 0.921089 1.84834 2.61513 + vertex 0.917522 1.84544 2.61304 + vertex 0.920322 1.84348 2.61584 + endloop + endfacet + facet normal -0.604268 0.207946 0.769168 + outer loop + vertex 0.920322 1.84348 2.61584 + vertex 0.924255 1.8465 2.61811 + vertex 0.921089 1.84834 2.61513 + endloop + endfacet + facet normal -0.607988 0.216842 0.76376 + outer loop + vertex 0.922335 1.84049 2.61829 + vertex 0.924255 1.8465 2.61811 + vertex 0.920322 1.84348 2.61584 + endloop + endfacet + facet normal -0.614504 0.209313 0.76064 + outer loop + vertex 0.918594 1.85022 2.61259 + vertex 0.917522 1.84544 2.61304 + vertex 0.921089 1.84834 2.61513 + endloop + endfacet + facet normal -0.617205 0.204536 0.759752 + outer loop + vertex 0.921276 1.85289 2.61405 + vertex 0.918594 1.85022 2.61259 + vertex 0.921089 1.84834 2.61513 + endloop + endfacet + facet normal -0.595521 0.207491 0.776081 + outer loop + vertex 0.921089 1.84834 2.61513 + vertex 0.92443 1.85179 2.61677 + vertex 0.921276 1.85289 2.61405 + endloop + endfacet + facet normal -0.600661 0.215405 0.76994 + outer loop + vertex 0.924255 1.8465 2.61811 + vertex 0.92443 1.85179 2.61677 + vertex 0.921089 1.84834 2.61513 + endloop + endfacet + facet normal -0.563317 0.154037 0.811755 + outer loop + vertex 0.920681 1.85757 2.61244 + vertex 0.916689 1.85543 2.61008 + vertex 0.918873 1.85373 2.61191 + endloop + endfacet + facet normal -0.612673 0.196873 0.765423 + outer loop + vertex 0.918873 1.85373 2.61191 + vertex 0.918594 1.85022 2.61259 + vertex 0.921276 1.85289 2.61405 + endloop + endfacet + facet normal -0.616484 0.185444 0.765217 + outer loop + vertex 0.920681 1.85757 2.61244 + vertex 0.918873 1.85373 2.61191 + vertex 0.921276 1.85289 2.61405 + endloop + endfacet + facet normal -0.602219 0.190705 0.775219 + outer loop + vertex 0.920681 1.85757 2.61244 + vertex 0.921276 1.85289 2.61405 + vertex 0.923844 1.85592 2.6153 + endloop + endfacet + facet normal -0.612196 0.167423 0.772778 + outer loop + vertex 0.920681 1.85757 2.61244 + vertex 0.923844 1.85592 2.6153 + vertex 0.92329 1.85829 2.61435 + endloop + endfacet + facet normal -0.601567 0.189856 0.775933 + outer loop + vertex 0.923844 1.85592 2.6153 + vertex 0.921276 1.85289 2.61405 + vertex 0.92443 1.85179 2.61677 + endloop + endfacet + facet normal -0.573997 0.190898 0.796294 + outer loop + vertex 0.917287 1.86034 2.60933 + vertex 0.916689 1.85543 2.61008 + vertex 0.920681 1.85757 2.61244 + endloop + endfacet + facet normal -0.563926 0.206856 0.799499 + outer loop + vertex 0.920756 1.86293 2.61111 + vertex 0.917287 1.86034 2.60933 + vertex 0.920681 1.85757 2.61244 + endloop + endfacet + facet normal -0.60997 0.199391 0.766928 + outer loop + vertex 0.920681 1.85757 2.61244 + vertex 0.923278 1.86101 2.61361 + vertex 0.920756 1.86293 2.61111 + endloop + endfacet + facet normal -0.614489 0.2045 0.76196 + outer loop + vertex 0.92329 1.85829 2.61435 + vertex 0.923278 1.86101 2.61361 + vertex 0.920681 1.85757 2.61244 + endloop + endfacet + facet normal -0.564676 0.208522 0.798536 + outer loop + vertex 0.918092 1.86633 2.60834 + vertex 0.917287 1.86034 2.60933 + vertex 0.920756 1.86293 2.61111 + endloop + endfacet + facet normal -0.563577 0.209753 0.79899 + outer loop + vertex 0.921558 1.86677 2.61067 + vertex 0.918092 1.86633 2.60834 + vertex 0.920756 1.86293 2.61111 + endloop + endfacet + facet normal -0.608213 0.215053 0.764087 + outer loop + vertex 0.920756 1.86293 2.61111 + vertex 0.923534 1.86505 2.61272 + vertex 0.921558 1.86677 2.61067 + endloop + endfacet + facet normal -0.605186 0.207738 0.768502 + outer loop + vertex 0.923278 1.86101 2.61361 + vertex 0.923534 1.86505 2.61272 + vertex 0.920756 1.86293 2.61111 + endloop + endfacet + facet normal -0.609235 0.208078 0.765203 + outer loop + vertex 0.921558 1.86677 2.61067 + vertex 0.923663 1.86854 2.61186 + vertex 0.921686 1.8704 2.60978 + endloop + endfacet + facet normal -0.563414 0.214434 0.797861 + outer loop + vertex 0.921558 1.86677 2.61067 + vertex 0.921686 1.8704 2.60978 + vertex 0.918092 1.86633 2.60834 + endloop + endfacet + facet normal -0.569928 0.222625 0.790961 + outer loop + vertex 0.918092 1.86633 2.60834 + vertex 0.921686 1.8704 2.60978 + vertex 0.918927 1.87181 2.60739 + endloop + endfacet + facet normal -0.610685 0.211155 0.763202 + outer loop + vertex 0.923663 1.86854 2.61186 + vertex 0.921558 1.86677 2.61067 + vertex 0.923534 1.86505 2.61272 + endloop + endfacet + facet normal -0.474682 0.182254 0.861081 + outer loop + vertex 0.920075 1.87888 2.60635 + vertex 0.916592 1.87604 2.60503 + vertex 0.918976 1.87523 2.60651 + endloop + endfacet + facet normal -0.56976 0.207829 0.795098 + outer loop + vertex 0.918976 1.87523 2.60651 + vertex 0.922198 1.87564 2.60871 + vertex 0.920075 1.87888 2.60635 + endloop + endfacet + facet normal -0.569593 0.212585 0.793959 + outer loop + vertex 0.918976 1.87523 2.60651 + vertex 0.918927 1.87181 2.60739 + vertex 0.922198 1.87564 2.60871 + endloop + endfacet + facet normal -0.572779 0.216457 0.790614 + outer loop + vertex 0.918927 1.87181 2.60739 + vertex 0.921686 1.8704 2.60978 + vertex 0.922198 1.87564 2.60871 + endloop + endfacet + facet normal -0.481596 0.193668 0.854727 + outer loop + vertex 0.91721 1.88053 2.60436 + vertex 0.916592 1.87604 2.60503 + vertex 0.920075 1.87888 2.60635 + endloop + endfacet + facet normal -0.47389 0.208178 0.855623 + outer loop + vertex 0.92112 1.88355 2.60579 + vertex 0.91721 1.88053 2.60436 + vertex 0.920075 1.87888 2.60635 + endloop + endfacet + facet normal -0.564677 0.221259 0.7951 + outer loop + vertex 0.920075 1.87888 2.60635 + vertex 0.923953 1.8816 2.60834 + vertex 0.92112 1.88355 2.60579 + endloop + endfacet + facet normal -0.562214 0.215255 0.798487 + outer loop + vertex 0.922198 1.87564 2.60871 + vertex 0.923953 1.8816 2.60834 + vertex 0.920075 1.87888 2.60635 + endloop + endfacet + facet normal -0.473048 0.206703 0.856446 + outer loop + vertex 0.918473 1.88603 2.60373 + vertex 0.91721 1.88053 2.60436 + vertex 0.92112 1.88355 2.60579 + endloop + endfacet + facet normal -0.464283 0.217784 0.858494 + outer loop + vertex 0.922148 1.88732 2.60539 + vertex 0.918473 1.88603 2.60373 + vertex 0.92112 1.88355 2.60579 + endloop + endfacet + facet normal -0.553961 0.235913 0.798419 + outer loop + vertex 0.92112 1.88355 2.60579 + vertex 0.924345 1.88643 2.60718 + vertex 0.922148 1.88732 2.60539 + endloop + endfacet + facet normal -0.555065 0.237795 0.797092 + outer loop + vertex 0.923953 1.8816 2.60834 + vertex 0.924345 1.88643 2.60718 + vertex 0.92112 1.88355 2.60579 + endloop + endfacet + facet normal -0.526083 0.194449 0.827905 + outer loop + vertex 0.922148 1.88732 2.60539 + vertex 0.924304 1.88967 2.60621 + vertex 0.921927 1.89053 2.6045 + endloop + endfacet + facet normal -0.462457 0.208293 0.861828 + outer loop + vertex 0.922148 1.88732 2.60539 + vertex 0.921927 1.89053 2.6045 + vertex 0.918473 1.88603 2.60373 + endloop + endfacet + facet normal -0.555641 0.231831 0.798447 + outer loop + vertex 0.924304 1.88967 2.60621 + vertex 0.922148 1.88732 2.60539 + vertex 0.924345 1.88643 2.60718 + endloop + endfacet + facet normal -0.373667 0.229942 0.89861 + outer loop + vertex 0.918157 1.92641 2.59351 + vertex 0.923054 1.93115 2.59434 + vertex 0.918476 1.9315 2.59234 + endloop + endfacet + facet normal -0.373621 0.230232 0.898555 + outer loop + vertex 0.923054 1.93115 2.59434 + vertex 0.923363 1.93624 2.59316 + vertex 0.918476 1.9315 2.59234 + endloop + endfacet + facet normal -0.36778 0.223497 0.902656 + outer loop + vertex 0.918476 1.9315 2.59234 + vertex 0.923363 1.93624 2.59316 + vertex 0.919731 1.93665 2.59158 + endloop + endfacet + facet normal -0.428188 0.265905 0.863683 + outer loop + vertex 0.92138 1.94268 2.59069 + vertex 0.917863 1.94136 2.58935 + vertex 0.919927 1.93986 2.59083 + endloop + endfacet + facet normal -0.372796 0.239147 0.896566 + outer loop + vertex 0.919927 1.93986 2.59083 + vertex 0.923539 1.94114 2.59199 + vertex 0.92138 1.94268 2.59069 + endloop + endfacet + facet normal -0.370867 0.231104 0.899471 + outer loop + vertex 0.919927 1.93986 2.59083 + vertex 0.919731 1.93665 2.59158 + vertex 0.923539 1.94114 2.59199 + endloop + endfacet + facet normal -0.367009 0.227611 0.901941 + outer loop + vertex 0.919731 1.93665 2.59158 + vertex 0.923363 1.93624 2.59316 + vertex 0.923539 1.94114 2.59199 + endloop + endfacet + facet normal -0.389837 0.267605 0.881144 + outer loop + vertex 0.92138 1.94268 2.59069 + vertex 0.924055 1.94503 2.59116 + vertex 0.921657 1.94591 2.58983 + endloop + endfacet + facet normal -0.428258 0.266221 0.863552 + outer loop + vertex 0.92138 1.94268 2.59069 + vertex 0.921657 1.94591 2.58983 + vertex 0.917863 1.94136 2.58935 + endloop + endfacet + facet normal -0.428717 0.266641 0.863194 + outer loop + vertex 0.917863 1.94136 2.58935 + vertex 0.921657 1.94591 2.58983 + vertex 0.917945 1.94631 2.58786 + endloop + endfacet + facet normal -0.37048 0.242455 0.896638 + outer loop + vertex 0.924055 1.94503 2.59116 + vertex 0.92138 1.94268 2.59069 + vertex 0.923539 1.94114 2.59199 + endloop + endfacet + facet normal -0.426239 0.278072 0.860811 + outer loop + vertex 0.921657 1.94591 2.58983 + vertex 0.923288 1.95116 2.58894 + vertex 0.917945 1.94631 2.58786 + endloop + endfacet + facet normal -0.409201 0.255989 0.875799 + outer loop + vertex 0.917945 1.94631 2.58786 + vertex 0.923288 1.95116 2.58894 + vertex 0.919434 1.95155 2.58703 + endloop + endfacet + facet normal -0.472773 0.294662 0.830458 + outer loop + vertex 0.921274 1.95769 2.58604 + vertex 0.917844 1.95627 2.58459 + vertex 0.919753 1.95483 2.58619 + endloop + endfacet + facet normal -0.405123 0.261126 0.876179 + outer loop + vertex 0.919753 1.95483 2.58619 + vertex 0.923346 1.95624 2.58743 + vertex 0.921274 1.95769 2.58604 + endloop + endfacet + facet normal -0.405297 0.261818 0.875892 + outer loop + vertex 0.919753 1.95483 2.58619 + vertex 0.919434 1.95155 2.58703 + vertex 0.923346 1.95624 2.58743 + endloop + endfacet + facet normal -0.407614 0.263896 0.874191 + outer loop + vertex 0.919434 1.95155 2.58703 + vertex 0.923288 1.95116 2.58894 + vertex 0.923346 1.95624 2.58743 + endloop + endfacet + facet normal -0.415027 0.284344 0.864234 + outer loop + vertex 0.921274 1.95769 2.58604 + vertex 0.923934 1.9601 2.58653 + vertex 0.921565 1.96085 2.58514 + endloop + endfacet + facet normal -0.469941 0.281535 0.836596 + outer loop + vertex 0.921274 1.95769 2.58604 + vertex 0.921565 1.96085 2.58514 + vertex 0.917844 1.95627 2.58459 + endloop + endfacet + facet normal -0.475171 0.286342 0.831998 + outer loop + vertex 0.917844 1.95627 2.58459 + vertex 0.921565 1.96085 2.58514 + vertex 0.917951 1.96126 2.58294 + endloop + endfacet + facet normal -0.401271 0.26672 0.876266 + outer loop + vertex 0.923934 1.9601 2.58653 + vertex 0.921274 1.95769 2.58604 + vertex 0.923346 1.95624 2.58743 + endloop + endfacet + facet normal -0.474839 0.287719 0.831712 + outer loop + vertex 0.921565 1.96085 2.58514 + vertex 0.92294 1.96593 2.58417 + vertex 0.917951 1.96126 2.58294 + endloop + endfacet + facet normal -0.472255 0.284261 0.834369 + outer loop + vertex 0.917951 1.96126 2.58294 + vertex 0.92294 1.96593 2.58417 + vertex 0.919038 1.96653 2.58176 + endloop + endfacet + facet normal -0.564632 0.301358 0.768358 + outer loop + vertex 0.921282 1.97311 2.58088 + vertex 0.919371 1.97359 2.57929 + vertex 0.919057 1.97057 2.58024 + endloop + endfacet + facet normal -0.509565 0.238356 0.826759 + outer loop + vertex 0.919057 1.97057 2.58024 + vertex 0.922933 1.97105 2.58249 + vertex 0.921282 1.97311 2.58088 + endloop + endfacet + facet normal -0.506075 0.305007 0.806758 + outer loop + vertex 0.919057 1.97057 2.58024 + vertex 0.919038 1.96653 2.58176 + vertex 0.922933 1.97105 2.58249 + endloop + endfacet + facet normal -0.47512 0.273495 0.836338 + outer loop + vertex 0.919038 1.96653 2.58176 + vertex 0.92294 1.96593 2.58417 + vertex 0.922933 1.97105 2.58249 + endloop + endfacet + facet normal -0.492829 0.321383 0.808599 + outer loop + vertex 0.921282 1.97311 2.58088 + vertex 0.9238 1.97489 2.58171 + vertex 0.921838 1.97613 2.58002 + endloop + endfacet + facet normal -0.557439 0.320996 0.765653 + outer loop + vertex 0.921282 1.97311 2.58088 + vertex 0.921838 1.97613 2.58002 + vertex 0.919371 1.97359 2.57929 + endloop + endfacet + facet normal -0.586175 0.360365 0.725628 + outer loop + vertex 0.919371 1.97359 2.57929 + vertex 0.921838 1.97613 2.58002 + vertex 0.919118 1.97662 2.57758 + endloop + endfacet + facet normal -0.471121 0.277342 0.837333 + outer loop + vertex 0.9238 1.97489 2.58171 + vertex 0.921282 1.97311 2.58088 + vertex 0.922933 1.97105 2.58249 + endloop + endfacet + facet normal -0.675785 0.326036 0.661072 + outer loop + vertex 0.920546 1.98362 2.57554 + vertex 0.918474 1.9827 2.57387 + vertex 0.918807 1.9804 2.57535 + endloop + endfacet + facet normal -0.625949 0.295545 0.721693 + outer loop + vertex 0.918807 1.9804 2.57535 + vertex 0.922797 1.98098 2.57857 + vertex 0.920546 1.98362 2.57554 + endloop + endfacet + facet normal -0.617093 0.361843 0.698761 + outer loop + vertex 0.918807 1.9804 2.57535 + vertex 0.919118 1.97662 2.57758 + vertex 0.922797 1.98098 2.57857 + endloop + endfacet + facet normal -0.594788 0.33586 0.73036 + outer loop + vertex 0.919118 1.97662 2.57758 + vertex 0.921838 1.97613 2.58002 + vertex 0.922797 1.98098 2.57857 + endloop + endfacet + facet normal -0.676181 0.347366 0.649705 + outer loop + vertex 0.918694 1.98523 2.57275 + vertex 0.918474 1.9827 2.57387 + vertex 0.920546 1.98362 2.57554 + endloop + endfacet + facet normal -0.691874 0.322714 0.645883 + outer loop + vertex 0.921083 1.98761 2.57412 + vertex 0.918694 1.98523 2.57275 + vertex 0.920546 1.98362 2.57554 + endloop + endfacet + facet normal -0.622071 0.335236 0.707562 + outer loop + vertex 0.920546 1.98362 2.57554 + vertex 0.923803 1.98633 2.57712 + vertex 0.921083 1.98761 2.57412 + endloop + endfacet + facet normal -0.612266 0.312495 0.726276 + outer loop + vertex 0.922797 1.98098 2.57857 + vertex 0.923803 1.98633 2.57712 + vertex 0.920546 1.98362 2.57554 + endloop + endfacet + facet normal -0.735899 0.344132 0.583117 + outer loop + vertex 0.920896 1.99274 2.57122 + vertex 0.918157 1.99091 2.56885 + vertex 0.91914 1.98864 2.57143 + endloop + endfacet + facet normal -0.697923 0.33672 0.632079 + outer loop + vertex 0.91914 1.98864 2.57143 + vertex 0.918694 1.98523 2.57275 + vertex 0.921083 1.98761 2.57412 + endloop + endfacet + facet normal -0.700525 0.331487 0.631966 + outer loop + vertex 0.920896 1.99274 2.57122 + vertex 0.91914 1.98864 2.57143 + vertex 0.921083 1.98761 2.57412 + endloop + endfacet + facet normal -0.664891 0.348885 0.660454 + outer loop + vertex 0.920896 1.99274 2.57122 + vertex 0.921083 1.98761 2.57412 + vertex 0.923748 1.9905 2.57527 + endloop + endfacet + facet normal -0.727839 0.237737 0.64322 + outer loop + vertex 0.920896 1.99274 2.57122 + vertex 0.923748 1.9905 2.57527 + vertex 0.923381 1.99289 2.57398 + endloop + endfacet + facet normal -0.637246 0.304295 0.70804 + outer loop + vertex 0.923748 1.9905 2.57527 + vertex 0.921083 1.98761 2.57412 + vertex 0.923803 1.98633 2.57712 + endloop + endfacet + facet normal -0.758427 0.332106 0.560798 + outer loop + vertex 0.919538 1.99754 2.56679 + vertex 0.917808 1.99734 2.56457 + vertex 0.917978 1.99449 2.56648 + endloop + endfacet + facet normal -0.736099 0.346817 0.581271 + outer loop + vertex 0.917978 1.99449 2.56648 + vertex 0.918157 1.99091 2.56885 + vertex 0.920896 1.99274 2.57122 + endloop + endfacet + facet normal -0.747284 0.324466 0.579904 + outer loop + vertex 0.917978 1.99449 2.56648 + vertex 0.920896 1.99274 2.57122 + vertex 0.919538 1.99754 2.56679 + endloop + endfacet + facet normal -0.756438 0.315457 0.572964 + outer loop + vertex 0.919538 1.99754 2.56679 + vertex 0.920896 1.99274 2.57122 + vertex 0.921961 1.99793 2.56977 + endloop + endfacet + facet normal -0.719958 0.319939 0.615873 + outer loop + vertex 0.920896 1.99274 2.57122 + vertex 0.923597 1.99541 2.57299 + vertex 0.921961 1.99793 2.56977 + endloop + endfacet + facet normal -0.715069 0.306891 0.628088 + outer loop + vertex 0.923381 1.99289 2.57398 + vertex 0.923597 1.99541 2.57299 + vertex 0.920896 1.99274 2.57122 + endloop + endfacet + facet normal -0.756152 0.341605 0.558158 + outer loop + vertex 0.918003 2.00021 2.56307 + vertex 0.917808 1.99734 2.56457 + vertex 0.919538 1.99754 2.56679 + endloop + endfacet + facet normal -0.760123 0.336302 0.55598 + outer loop + vertex 0.920789 2.00262 2.56542 + vertex 0.918003 2.00021 2.56307 + vertex 0.919538 1.99754 2.56679 + endloop + endfacet + facet normal -0.723238 0.331232 0.60598 + outer loop + vertex 0.923248 2.00112 2.56956 + vertex 0.921961 1.99793 2.56977 + vertex 0.924109 1.99866 2.57193 + endloop + endfacet + facet normal -0.749576 0.33937 0.568299 + outer loop + vertex 0.923248 2.00112 2.56956 + vertex 0.920789 2.00262 2.56542 + vertex 0.921961 1.99793 2.56977 + endloop + endfacet + facet normal -0.751948 0.337116 0.566504 + outer loop + vertex 0.920789 2.00262 2.56542 + vertex 0.919538 1.99754 2.56679 + vertex 0.921961 1.99793 2.56977 + endloop + endfacet + facet normal -0.724754 0.31371 0.613447 + outer loop + vertex 0.924109 1.99866 2.57193 + vertex 0.921961 1.99793 2.56977 + vertex 0.923597 1.99541 2.57299 + endloop + endfacet + facet normal -0.766392 0.343848 0.542598 + outer loop + vertex 0.919811 2.00731 2.56115 + vertex 0.918188 2.00732 2.55886 + vertex 0.91816 2.00451 2.56059 + endloop + endfacet + facet normal -0.761399 0.344281 0.549311 + outer loop + vertex 0.91816 2.00451 2.56059 + vertex 0.918003 2.00021 2.56307 + vertex 0.920789 2.00262 2.56542 + endloop + endfacet + facet normal -0.763267 0.340723 0.548936 + outer loop + vertex 0.91816 2.00451 2.56059 + vertex 0.920789 2.00262 2.56542 + vertex 0.919811 2.00731 2.56115 + endloop + endfacet + facet normal -0.770938 0.33341 0.542671 + outer loop + vertex 0.919811 2.00731 2.56115 + vertex 0.920789 2.00262 2.56542 + vertex 0.922082 2.00767 2.56416 + endloop + endfacet + facet normal -0.75111 0.3349 0.568925 + outer loop + vertex 0.920789 2.00262 2.56542 + vertex 0.923668 2.00477 2.56796 + vertex 0.922082 2.00767 2.56416 + endloop + endfacet + facet normal -0.751232 0.336059 0.56808 + outer loop + vertex 0.923248 2.00112 2.56956 + vertex 0.923668 2.00477 2.56796 + vertex 0.920789 2.00262 2.56542 + endloop + endfacet + facet normal -0.770156 0.331093 0.545195 + outer loop + vertex 0.918579 2.01001 2.55777 + vertex 0.918188 2.00732 2.55886 + vertex 0.919811 2.00731 2.56115 + endloop + endfacet + facet normal -0.770486 0.330676 0.544982 + outer loop + vertex 0.920957 2.0117 2.56011 + vertex 0.918579 2.01001 2.55777 + vertex 0.919811 2.00731 2.56115 + endloop + endfacet + facet normal -0.757241 0.333724 0.561439 + outer loop + vertex 0.923188 2.011 2.56367 + vertex 0.922082 2.00767 2.56416 + vertex 0.924116 2.00855 2.56638 + endloop + endfacet + facet normal -0.767452 0.334937 0.546658 + outer loop + vertex 0.923188 2.011 2.56367 + vertex 0.920957 2.0117 2.56011 + vertex 0.922082 2.00767 2.56416 + endloop + endfacet + facet normal -0.771572 0.330604 0.543487 + outer loop + vertex 0.920957 2.0117 2.56011 + vertex 0.919811 2.00731 2.56115 + vertex 0.922082 2.00767 2.56416 + endloop + endfacet + facet normal -0.75788 0.326097 0.565048 + outer loop + vertex 0.924116 2.00855 2.56638 + vertex 0.922082 2.00767 2.56416 + vertex 0.923668 2.00477 2.56796 + endloop + endfacet + facet normal -0.7666 0.334424 0.548165 + outer loop + vertex 0.920805 2.01761 2.55628 + vertex 0.918257 2.01602 2.55369 + vertex 0.919149 2.01361 2.5564 + endloop + endfacet + facet normal -0.77042 0.329342 0.545881 + outer loop + vertex 0.919149 2.01361 2.5564 + vertex 0.918579 2.01001 2.55777 + vertex 0.920957 2.0117 2.56011 + endloop + endfacet + facet normal -0.767263 0.334666 0.547089 + outer loop + vertex 0.920805 2.01761 2.55628 + vertex 0.919149 2.01361 2.5564 + vertex 0.920957 2.0117 2.56011 + endloop + endfacet + facet normal -0.768516 0.333826 0.545842 + outer loop + vertex 0.920805 2.01761 2.55628 + vertex 0.920957 2.0117 2.56011 + vertex 0.923041 2.01463 2.56125 + endloop + endfacet + facet normal -0.770277 0.331116 0.545009 + outer loop + vertex 0.920805 2.01761 2.55628 + vertex 0.923041 2.01463 2.56125 + vertex 0.922938 2.0175 2.55936 + endloop + endfacet + facet normal -0.768141 0.333203 0.54675 + outer loop + vertex 0.923041 2.01463 2.56125 + vertex 0.920957 2.0117 2.56011 + vertex 0.923188 2.011 2.56367 + endloop + endfacet + facet normal -0.787154 0.341803 0.51338 + outer loop + vertex 0.919695 2.02233 2.5517 + vertex 0.918158 2.02231 2.54936 + vertex 0.918193 2.01954 2.55126 + endloop + endfacet + facet normal -0.766379 0.355367 0.535143 + outer loop + vertex 0.918193 2.01954 2.55126 + vertex 0.918257 2.01602 2.55369 + vertex 0.920805 2.01761 2.55628 + endloop + endfacet + facet normal -0.77774 0.333685 0.532706 + outer loop + vertex 0.918193 2.01954 2.55126 + vertex 0.920805 2.01761 2.55628 + vertex 0.919695 2.02233 2.5517 + endloop + endfacet + facet normal -0.761276 0.350183 0.545738 + outer loop + vertex 0.919695 2.02233 2.5517 + vertex 0.920805 2.01761 2.55628 + vertex 0.921869 2.02277 2.55446 + endloop + endfacet + facet normal -0.76468 0.349378 0.541478 + outer loop + vertex 0.920805 2.01761 2.55628 + vertex 0.923323 2.02027 2.55812 + vertex 0.921869 2.02277 2.55446 + endloop + endfacet + facet normal -0.764613 0.349144 0.541725 + outer loop + vertex 0.922938 2.0175 2.55936 + vertex 0.923323 2.02027 2.55812 + vertex 0.920805 2.01761 2.55628 + endloop + endfacet + facet normal -0.778635 0.36895 0.507547 + outer loop + vertex 0.918633 2.02499 2.54814 + vertex 0.918158 2.02231 2.54936 + vertex 0.919695 2.02233 2.5517 + endloop + endfacet + facet normal -0.781848 0.364929 0.50551 + outer loop + vertex 0.920843 2.02667 2.55035 + vertex 0.918633 2.02499 2.54814 + vertex 0.919695 2.02233 2.5517 + endloop + endfacet + facet normal -0.756036 0.367422 0.541674 + outer loop + vertex 0.922835 2.02605 2.55358 + vertex 0.921869 2.02277 2.55446 + vertex 0.923777 2.02382 2.5564 + endloop + endfacet + facet normal -0.758573 0.367249 0.538234 + outer loop + vertex 0.922835 2.02605 2.55358 + vertex 0.920843 2.02667 2.55035 + vertex 0.921869 2.02277 2.55446 + endloop + endfacet + facet normal -0.756945 0.3689 0.539395 + outer loop + vertex 0.920843 2.02667 2.55035 + vertex 0.919695 2.02233 2.5517 + vertex 0.921869 2.02277 2.55446 + endloop + endfacet + facet normal -0.756405 0.360523 0.545779 + outer loop + vertex 0.923777 2.02382 2.5564 + vertex 0.921869 2.02277 2.55446 + vertex 0.923323 2.02027 2.55812 + endloop + endfacet + facet normal -0.809881 0.386988 0.440832 + outer loop + vertex 0.921057 2.03247 2.54636 + vertex 0.918968 2.03083 2.54396 + vertex 0.919361 2.02856 2.54668 + endloop + endfacet + facet normal -0.781868 0.36626 0.504516 + outer loop + vertex 0.919361 2.02856 2.54668 + vertex 0.918633 2.02499 2.54814 + vertex 0.920843 2.02667 2.55035 + endloop + endfacet + facet normal -0.774836 0.37718 0.50731 + outer loop + vertex 0.921057 2.03247 2.54636 + vertex 0.919361 2.02856 2.54668 + vertex 0.920843 2.02667 2.55035 + endloop + endfacet + facet normal -0.764908 0.383726 0.517369 + outer loop + vertex 0.921057 2.03247 2.54636 + vertex 0.920843 2.02667 2.55035 + vertex 0.922806 2.02954 2.55112 + endloop + endfacet + facet normal -0.790495 0.347398 0.504413 + outer loop + vertex 0.921057 2.03247 2.54636 + vertex 0.922806 2.02954 2.55112 + vertex 0.922886 2.03233 2.54932 + endloop + endfacet + facet normal -0.756346 0.372379 0.537842 + outer loop + vertex 0.922806 2.02954 2.55112 + vertex 0.920843 2.02667 2.55035 + vertex 0.922835 2.02605 2.55358 + endloop + endfacet + facet normal -0.877444 0.372634 0.302053 + outer loop + vertex 0.92053 2.03746 2.54077 + vertex 0.919013 2.03522 2.53913 + vertex 0.919339 2.03359 2.54209 + endloop + endfacet + facet normal -0.808723 0.401275 0.430052 + outer loop + vertex 0.919339 2.03359 2.54209 + vertex 0.918968 2.03083 2.54396 + vertex 0.921057 2.03247 2.54636 + endloop + endfacet + facet normal -0.811628 0.39569 0.429756 + outer loop + vertex 0.919339 2.03359 2.54209 + vertex 0.921057 2.03247 2.54636 + vertex 0.92053 2.03746 2.54077 + endloop + endfacet + facet normal -0.870884 0.323009 0.37044 + outer loop + vertex 0.92053 2.03746 2.54077 + vertex 0.921057 2.03247 2.54636 + vertex 0.922293 2.03792 2.54451 + endloop + endfacet + facet normal -0.794941 0.348534 0.496581 + outer loop + vertex 0.921057 2.03247 2.54636 + vertex 0.923369 2.03519 2.54815 + vertex 0.922293 2.03792 2.54451 + endloop + endfacet + facet normal -0.792695 0.340803 0.505458 + outer loop + vertex 0.922886 2.03233 2.54932 + vertex 0.923369 2.03519 2.54815 + vertex 0.921057 2.03247 2.54636 + endloop + endfacet + facet normal -0.709681 0.536087 0.457125 + outer loop + vertex 0.92132 2.04264 2.53637 + vertex 0.922221 2.045 2.535 + vertex 0.92 2.04206 2.535 + endloop + endfacet + facet normal -0.743213 0.361301 0.563112 + outer loop + vertex 0.919674 2.03825 2.53701 + vertex 0.92132 2.04264 2.53637 + vertex 0.92 2.04206 2.535 + endloop + endfacet + facet normal -0.87768 0.387544 0.281935 + outer loop + vertex 0.919674 2.03825 2.53701 + vertex 0.919013 2.03522 2.53913 + vertex 0.92053 2.03746 2.54077 + endloop + endfacet + facet normal -0.884408 0.373093 0.280401 + outer loop + vertex 0.919674 2.03825 2.53701 + vertex 0.92053 2.03746 2.54077 + vertex 0.92132 2.04264 2.53637 + endloop + endfacet + facet normal -0.913793 0.334769 0.230027 + outer loop + vertex 0.92132 2.04264 2.53637 + vertex 0.92053 2.03746 2.54077 + vertex 0.922276 2.04229 2.54068 + endloop + endfacet + facet normal -0.817932 0.310359 0.484423 + outer loop + vertex 0.923311 2.04121 2.54413 + vertex 0.922293 2.03792 2.54451 + vertex 0.923911 2.0389 2.54662 + endloop + endfacet + facet normal -0.877558 0.314429 0.361975 + outer loop + vertex 0.923311 2.04121 2.54413 + vertex 0.922276 2.04229 2.54068 + vertex 0.922293 2.03792 2.54451 + endloop + endfacet + facet normal -0.871127 0.32209 0.370669 + outer loop + vertex 0.922276 2.04229 2.54068 + vertex 0.92053 2.03746 2.54077 + vertex 0.922293 2.03792 2.54451 + endloop + endfacet + facet normal -0.817331 0.318123 0.480383 + outer loop + vertex 0.923911 2.0389 2.54662 + vertex 0.922293 2.03792 2.54451 + vertex 0.923369 2.03519 2.54815 + endloop + endfacet + facet normal -0.94951 0.280866 -0.139801 + outer loop + vertex 0.922221 2.045 2.535 + vertex 0.92132 2.04264 2.53637 + vertex 0.9237 2.05 2.535 + endloop + endfacet + facet normal -0.941399 0.322624 0.0983902 + outer loop + vertex 0.9237 2.05 2.535 + vertex 0.92132 2.04264 2.53637 + vertex 0.92284 2.04708 2.53633 + endloop + endfacet + facet normal -0.889875 0.306423 0.337977 + outer loop + vertex 0.92327 2.046 2.53993 + vertex 0.922276 2.04229 2.54068 + vertex 0.923596 2.04406 2.54255 + endloop + endfacet + facet normal -0.935835 0.290694 0.199273 + outer loop + vertex 0.92327 2.046 2.53993 + vertex 0.92284 2.04708 2.53633 + vertex 0.922276 2.04229 2.54068 + endloop + endfacet + facet normal -0.920219 0.316715 0.229975 + outer loop + vertex 0.92284 2.04708 2.53633 + vertex 0.92132 2.04264 2.53637 + vertex 0.922276 2.04229 2.54068 + endloop + endfacet + facet normal -0.889285 0.286269 0.356683 + outer loop + vertex 0.923596 2.04406 2.54255 + vertex 0.922276 2.04229 2.54068 + vertex 0.923311 2.04121 2.54413 + endloop + endfacet + facet normal -0.680093 -0.506632 -0.529904 + outer loop + vertex 0.925 2.05 2.53327 + vertex 0.923823 2.055 2.53 + vertex 0.925 2.05342 2.53 + endloop + endfacet + facet normal -0.691257 -0.502387 -0.519395 + outer loop + vertex 0.925 2.05 2.53327 + vertex 0.9237 2.05 2.535 + vertex 0.923823 2.055 2.53 + endloop + endfacet + facet normal 0.991392 -0.103969 -0.0795766 + outer loop + vertex 0.9237 2.05 2.535 + vertex 0.923687 2.05186 2.5324 + vertex 0.923823 2.055 2.53 + endloop + endfacet + facet normal -0.928472 0.307047 0.208955 + outer loop + vertex 0.923813 2.05096 2.53496 + vertex 0.92284 2.04708 2.53633 + vertex 0.923753 2.04883 2.53782 + endloop + endfacet + facet normal -0.945333 0.290077 0.149002 + outer loop + vertex 0.923813 2.05096 2.53496 + vertex 0.923687 2.05186 2.5324 + vertex 0.92284 2.04708 2.53633 + endloop + endfacet + facet normal 0.877671 -0.387431 -0.282118 + outer loop + vertex 0.923687 2.05186 2.5324 + vertex 0.9237 2.05 2.535 + vertex 0.92284 2.04708 2.53633 + endloop + endfacet + facet normal -0.928234 0.310802 0.204409 + outer loop + vertex 0.923753 2.04883 2.53782 + vertex 0.92284 2.04708 2.53633 + vertex 0.92327 2.046 2.53993 + endloop + endfacet + facet normal -0.671385 0.317355 -0.669723 + outer loop + vertex 0.925 2.055 2.52882 + vertex 0.923823 2.055 2.53 + vertex 0.925 2.05749 2.53 + endloop + endfacet + facet normal -0.965147 0.253287 0.065858 + outer loop + vertex 0.925 2.05749 2.53 + vertex 0.923687 2.05186 2.5324 + vertex 0.925 2.05619 2.535 + endloop + endfacet + facet normal -0.806386 0.381169 0.452163 + outer loop + vertex 0.923823 2.055 2.53 + vertex 0.923687 2.05186 2.5324 + vertex 0.925 2.05749 2.53 + endloop + endfacet + facet normal -0.967773 0.218651 0.124928 + outer loop + vertex 0.925 2.05619 2.535 + vertex 0.923687 2.05186 2.5324 + vertex 0.923813 2.05096 2.53496 + endloop + endfacet + facet normal 0.56266 -0.741514 -0.365473 + outer loop + vertex 0.92087 2.10839 2.50592 + vertex 0.918535 2.10604 2.5071 + vertex 0.917976 2.10744 2.50341 + endloop + endfacet + facet normal 0.472561 -0.722086 -0.505249 + outer loop + vertex 0.922512 2.1076 2.50859 + vertex 0.918535 2.10604 2.5071 + vertex 0.92087 2.10839 2.50592 + endloop + endfacet + facet normal 0.456073 -0.809278 -0.370225 + outer loop + vertex 0.922512 2.1076 2.50859 + vertex 0.922423 2.10618 2.51158 + vertex 0.918535 2.10604 2.5071 + endloop + endfacet + facet normal 0.169637 -0.978613 -0.116361 + outer loop + vertex 0.922423 2.10618 2.51158 + vertex 0.918164 2.1054 2.51192 + vertex 0.918535 2.10604 2.5071 + endloop + endfacet + facet normal 0.168642 -0.977543 -0.126374 + outer loop + vertex 0.922423 2.10618 2.51158 + vertex 0.923527 2.10577 2.51621 + vertex 0.918164 2.1054 2.51192 + endloop + endfacet + facet normal -0.131689 -0.959816 0.247814 + outer loop + vertex 0.923527 2.10577 2.51621 + vertex 0.918302 2.10643 2.51598 + vertex 0.918164 2.1054 2.51192 + endloop + endfacet + facet normal -0.586272 -0.633667 0.504728 + outer loop + vertex 0.920322 2.10843 2.5189 + vertex 0.923486 2.10656 2.52023 + vertex 0.922749 2.10817 2.52139 + endloop + endfacet + facet normal -0.558519 -0.451259 0.696004 + outer loop + vertex 0.920322 2.10843 2.5189 + vertex 0.918302 2.10643 2.51598 + vertex 0.923486 2.10656 2.52023 + endloop + endfacet + facet normal -0.130825 -0.973174 0.189253 + outer loop + vertex 0.918302 2.10643 2.51598 + vertex 0.923527 2.10577 2.51621 + vertex 0.923486 2.10656 2.52023 + endloop + endfacet + facet normal -0.609105 -0.628709 0.483442 + outer loop + vertex 0.923486 2.10656 2.52023 + vertex 0.924632 2.10742 2.52279 + vertex 0.922749 2.10817 2.52139 + endloop + endfacet + facet normal 0.661686 -0.0314471 -0.749121 + outer loop + vertex 0.92087 2.10839 2.50592 + vertex 0.917976 2.10744 2.50341 + vertex 0.92 2.11211 2.505 + endloop + endfacet + facet normal 0.707143 -0.0103448 -0.706994 + outer loop + vertex 0.92087 2.10839 2.50592 + vertex 0.92 2.11211 2.505 + vertex 0.925 2.11219 2.51 + endloop + endfacet + facet normal 0.0991976 -0.991574 -0.0833128 + outer loop + vertex 0.925 2.11219 2.51 + vertex 0.92 2.11211 2.505 + vertex 0.925 2.11261 2.505 + endloop + endfacet + facet normal 0.787859 -0.255333 -0.560431 + outer loop + vertex 0.925 2.11219 2.51 + vertex 0.922512 2.1076 2.50859 + vertex 0.92087 2.10839 2.50592 + endloop + endfacet + facet normal -0.698433 0.275136 0.660675 + outer loop + vertex 0.922749 2.10817 2.52139 + vertex 0.924297 2.10897 2.52269 + vertex 0.922738 2.11088 2.52025 + endloop + endfacet + facet normal -0.671109 0.285193 0.684308 + outer loop + vertex 0.922749 2.10817 2.52139 + vertex 0.922738 2.11088 2.52025 + vertex 0.920322 2.10843 2.5189 + endloop + endfacet + facet normal -0.644837 0.235696 0.727071 + outer loop + vertex 0.920322 2.10843 2.5189 + vertex 0.922738 2.11088 2.52025 + vertex 0.919365 2.11141 2.51709 + endloop + endfacet + facet normal -0.616273 -0.0809196 0.783364 + outer loop + vertex 0.924297 2.10897 2.52269 + vertex 0.922749 2.10817 2.52139 + vertex 0.924632 2.10742 2.52279 + endloop + endfacet + facet normal -0.509955 0.568583 0.645491 + outer loop + vertex 0.920631 2.11627 2.51435 + vertex 0.919035 2.11629 2.51307 + vertex 0.918993 2.11445 2.51466 + endloop + endfacet + facet normal -0.506214 0.56608 0.650616 + outer loop + vertex 0.918993 2.11445 2.51466 + vertex 0.9218 2.11426 2.517 + vertex 0.920631 2.11627 2.51435 + endloop + endfacet + facet normal -0.542652 0.482506 0.687544 + outer loop + vertex 0.918993 2.11445 2.51466 + vertex 0.919365 2.11141 2.51709 + vertex 0.9218 2.11426 2.517 + endloop + endfacet + facet normal -0.553586 0.491396 0.672363 + outer loop + vertex 0.919365 2.11141 2.51709 + vertex 0.922738 2.11088 2.52025 + vertex 0.9218 2.11426 2.517 + endloop + endfacet + facet normal -0.354254 0.841609 0.407674 + outer loop + vertex 0.920224 2.12196 2.50535 + vertex 0.917172 2.12163 2.50337 + vertex 0.918558 2.12039 2.50714 + endloop + endfacet + facet normal -0.372032 0.841734 0.391249 + outer loop + vertex 0.922263 2.12152 2.50823 + vertex 0.920224 2.12196 2.50535 + vertex 0.918558 2.12039 2.50714 + endloop + endfacet + facet normal -0.379583 0.805416 0.455217 + outer loop + vertex 0.922263 2.12152 2.50823 + vertex 0.918558 2.12039 2.50714 + vertex 0.923262 2.11998 2.5118 + endloop + endfacet + facet normal -0.437983 0.741297 0.508576 + outer loop + vertex 0.923262 2.11998 2.5118 + vertex 0.918558 2.12039 2.50714 + vertex 0.919469 2.11794 2.5115 + endloop + endfacet + facet normal -0.456912 0.673311 0.581278 + outer loop + vertex 0.920631 2.11627 2.51435 + vertex 0.919469 2.11794 2.5115 + vertex 0.919035 2.11629 2.51307 + endloop + endfacet + facet normal -0.45383 0.675412 0.581255 + outer loop + vertex 0.920631 2.11627 2.51435 + vertex 0.923072 2.1172 2.51518 + vertex 0.919469 2.11794 2.5115 + endloop + endfacet + facet normal -0.425528 0.710374 0.56062 + outer loop + vertex 0.923072 2.1172 2.51518 + vertex 0.923262 2.11998 2.5118 + vertex 0.919469 2.11794 2.5115 + endloop + endfacet + facet normal -0.452009 0.604598 0.655857 + outer loop + vertex 0.923072 2.1172 2.51518 + vertex 0.920631 2.11627 2.51435 + vertex 0.9218 2.11426 2.517 + endloop + endfacet + facet normal -0.0653687 0.99052 0.120816 + outer loop + vertex 0.925 2.12738 2.5 + vertex 0.92 2.12705 2.5 + vertex 0.925 2.12677 2.505 + endloop + endfacet + facet normal -0.620758 0.444757 0.64564 + outer loop + vertex 0.925 2.12677 2.505 + vertex 0.92 2.12705 2.5 + vertex 0.919347 2.12334 2.50192 + endloop + endfacet + facet normal -0.365761 0.826532 0.427859 + outer loop + vertex 0.920224 2.12196 2.50535 + vertex 0.919347 2.12334 2.50192 + vertex 0.917172 2.12163 2.50337 + endloop + endfacet + facet normal -0.352907 0.832543 0.426999 + outer loop + vertex 0.920224 2.12196 2.50535 + vertex 0.924354 2.12306 2.50662 + vertex 0.919347 2.12334 2.50192 + endloop + endfacet + facet normal -0.613597 0.402887 0.679103 + outer loop + vertex 0.924354 2.12306 2.50662 + vertex 0.925 2.12677 2.505 + vertex 0.919347 2.12334 2.50192 + endloop + endfacet + facet normal -0.344391 0.860882 0.374535 + outer loop + vertex 0.924354 2.12306 2.50662 + vertex 0.920224 2.12196 2.50535 + vertex 0.922263 2.12152 2.50823 + endloop + endfacet + facet normal -0.312151 -0.915192 0.254924 + outer loop + vertex 0.925 0.9 2.50446 + vertex 0.93 0.898445 2.505 + vertex 0.925441 0.9 2.505 + endloop + endfacet + facet normal -0.31241 -0.910669 0.270336 + outer loop + vertex 0.925 0.9 2.50446 + vertex 0.925 0.898676 2.5 + vertex 0.93 0.898445 2.505 + endloop + endfacet + facet normal -0.134223 -0.98698 0.0886291 + outer loop + vertex 0.925 0.898676 2.5 + vertex 0.93 0.897996 2.5 + vertex 0.93 0.898445 2.505 + endloop + endfacet + facet normal -0.303312 -0.889276 -0.34233 + outer loop + vertex 0.929232 0.898561 2.50538 + vertex 0.925441 0.9 2.505 + vertex 0.93 0.898445 2.505 + endloop + endfacet + facet normal -0.360185 -0.930272 0.0697166 + outer loop + vertex 0.927338 0.899377 2.50649 + vertex 0.925441 0.9 2.505 + vertex 0.929232 0.898561 2.50538 + endloop + endfacet + facet normal -0.28135 -0.93649 0.209354 + outer loop + vertex 0.929232 0.898561 2.50538 + vertex 0.93071 0.89876 2.50826 + vertex 0.927338 0.899377 2.50649 + endloop + endfacet + facet normal -0.309634 -0.95085 -0.00343956 + outer loop + vertex 0.925441 0.9 2.505 + vertex 0.927338 0.899377 2.50649 + vertex 0.923674 0.900573 2.5058 + endloop + endfacet + facet normal -0.463612 -0.730154 -0.501936 + outer loop + vertex 0.925 0.90028 2.505 + vertex 0.925441 0.9 2.505 + vertex 0.923674 0.900573 2.5058 + endloop + endfacet + facet normal -0.321219 -0.898784 0.298338 + outer loop + vertex 0.927338 0.899377 2.50649 + vertex 0.93071 0.89876 2.50826 + vertex 0.928368 0.900289 2.51034 + endloop + endfacet + facet normal -0.346429 -0.88796 0.302512 + outer loop + vertex 0.927338 0.899377 2.50649 + vertex 0.928368 0.900289 2.51034 + vertex 0.923674 0.900573 2.5058 + endloop + endfacet + facet normal -0.385727 -0.855628 0.34513 + outer loop + vertex 0.923674 0.900573 2.5058 + vertex 0.928368 0.900289 2.51034 + vertex 0.923028 0.902583 2.51006 + endloop + endfacet + facet normal -0.441676 -0.771377 0.458148 + outer loop + vertex 0.922804 0.904849 2.51356 + vertex 0.927824 0.902678 2.51474 + vertex 0.925778 0.904545 2.51591 + endloop + endfacet + facet normal -0.44149 -0.76571 0.467733 + outer loop + vertex 0.922804 0.904849 2.51356 + vertex 0.923028 0.902583 2.51006 + vertex 0.927824 0.902678 2.51474 + endloop + endfacet + facet normal -0.378817 -0.832196 0.404904 + outer loop + vertex 0.923028 0.902583 2.51006 + vertex 0.928368 0.900289 2.51034 + vertex 0.927824 0.902678 2.51474 + endloop + endfacet + facet normal -0.368928 -0.749231 0.550041 + outer loop + vertex 0.927824 0.902678 2.51474 + vertex 0.92761 0.905241 2.51809 + vertex 0.925778 0.904545 2.51591 + endloop + endfacet + facet normal -0.512959 -0.646973 0.56418 + outer loop + vertex 0.922804 0.904849 2.51356 + vertex 0.925778 0.904545 2.51591 + vertex 0.923406 0.906755 2.51629 + endloop + endfacet + facet normal -0.531835 -0.387636 0.752921 + outer loop + vertex 0.927932 0.907305 2.52032 + vertex 0.92671 0.910029 2.52086 + vertex 0.924106 0.90894 2.51846 + endloop + endfacet + facet normal -0.543218 -0.575715 0.611119 + outer loop + vertex 0.92761 0.905241 2.51809 + vertex 0.927932 0.907305 2.52032 + vertex 0.924106 0.90894 2.51846 + endloop + endfacet + facet normal -0.487765 -0.531333 0.692655 + outer loop + vertex 0.92761 0.905241 2.51809 + vertex 0.924106 0.90894 2.51846 + vertex 0.923406 0.906755 2.51629 + endloop + endfacet + facet normal -0.48631 -0.626133 0.609475 + outer loop + vertex 0.92761 0.905241 2.51809 + vertex 0.923406 0.906755 2.51629 + vertex 0.925778 0.904545 2.51591 + endloop + endfacet + facet normal -0.527142 -0.386317 0.756889 + outer loop + vertex 0.927932 0.907305 2.52032 + vertex 0.930533 0.907512 2.52224 + vertex 0.92671 0.910029 2.52086 + endloop + endfacet + facet normal 0.556197 0.595217 -0.579967 + outer loop + vertex 0.93 0.912876 2.505 + vertex 0.927727 0.915 2.505 + vertex 0.93 0.915 2.50718 + endloop + endfacet + facet normal -0.611925 -0.21451 0.761271 + outer loop + vertex 0.922855 0.912202 2.51838 + vertex 0.924106 0.90894 2.51846 + vertex 0.92671 0.910029 2.52086 + endloop + endfacet + facet normal -0.551427 -0.0241434 0.833874 + outer loop + vertex 0.926035 0.912683 2.52049 + vertex 0.922855 0.912202 2.51838 + vertex 0.92671 0.910029 2.52086 + endloop + endfacet + facet normal -0.595954 -0.039905 0.802027 + outer loop + vertex 0.92671 0.910029 2.52086 + vertex 0.930061 0.910862 2.52339 + vertex 0.926035 0.912683 2.52049 + endloop + endfacet + facet normal -0.510276 -0.343419 0.788468 + outer loop + vertex 0.930533 0.907512 2.52224 + vertex 0.930061 0.910862 2.52339 + vertex 0.92671 0.910029 2.52086 + endloop + endfacet + facet normal 0.241608 0.925145 -0.292801 + outer loop + vertex 0.925 0.915 2.50275 + vertex 0.923594 0.915301 2.50254 + vertex 0.927727 0.915 2.505 + endloop + endfacet + facet normal 0.521573 0.6574 -0.543864 + outer loop + vertex 0.927727 0.915 2.505 + vertex 0.93 0.917333 2.51 + vertex 0.93 0.915 2.50718 + endloop + endfacet + facet normal 0.368475 0.766945 -0.525378 + outer loop + vertex 0.927727 0.915 2.505 + vertex 0.923594 0.915301 2.50254 + vertex 0.93 0.917333 2.51 + endloop + endfacet + facet normal -0.148188 0.979081 -0.139428 + outer loop + vertex 0.923594 0.915301 2.50254 + vertex 0.923559 0.915895 2.50675 + vertex 0.93 0.917333 2.51 + endloop + endfacet + facet normal -0.3305 0.909426 0.252415 + outer loop + vertex 0.93 0.917333 2.51 + vertex 0.923559 0.915895 2.50675 + vertex 0.92882 0.916385 2.51187 + endloop + endfacet + facet normal -0.0947388 0.9955 0.00210568 + outer loop + vertex 0.92882 0.916385 2.51187 + vertex 0.923559 0.915895 2.50675 + vertex 0.923147 0.915846 2.51151 + endloop + endfacet + facet normal -0.0987591 0.992719 0.0689592 + outer loop + vertex 0.92882 0.916385 2.51187 + vertex 0.923147 0.915846 2.51151 + vertex 0.928199 0.916011 2.51637 + endloop + endfacet + facet normal -0.255124 0.938307 0.233435 + outer loop + vertex 0.928199 0.916011 2.51637 + vertex 0.923147 0.915846 2.51151 + vertex 0.923392 0.914633 2.51665 + endloop + endfacet + facet normal -0.513404 0.56926 0.642153 + outer loop + vertex 0.926035 0.912683 2.52049 + vertex 0.923392 0.914633 2.51665 + vertex 0.922855 0.912202 2.51838 + endloop + endfacet + facet normal -0.535201 0.545417 0.645043 + outer loop + vertex 0.926035 0.912683 2.52049 + vertex 0.929001 0.914389 2.52151 + vertex 0.923392 0.914633 2.51665 + endloop + endfacet + facet normal -0.242596 0.913765 0.325855 + outer loop + vertex 0.929001 0.914389 2.52151 + vertex 0.928199 0.916011 2.51637 + vertex 0.923392 0.914633 2.51665 + endloop + endfacet + facet normal -0.461694 0.305738 0.832684 + outer loop + vertex 0.929001 0.914389 2.52151 + vertex 0.926035 0.912683 2.52049 + vertex 0.930061 0.910862 2.52339 + endloop + endfacet + facet normal -0.639219 -0.278009 -0.717015 + outer loop + vertex 0.93 0.959794 2.53 + vertex 0.929229 0.961656 2.52997 + vertex 0.93 0.96 2.52992 + endloop + endfacet + facet normal -0.911985 -0.374386 0.167688 + outer loop + vertex 0.93 0.959794 2.53 + vertex 0.93 0.96 2.53046 + vertex 0.929229 0.961656 2.52997 + endloop + endfacet + facet normal -0.702128 -0.122062 -0.701511 + outer loop + vertex 0.93 0.96 2.52992 + vertex 0.929051 0.965 2.53 + vertex 0.93 0.965 2.52905 + endloop + endfacet + facet normal -0.0407112 0.00823308 -0.999137 + outer loop + vertex 0.929229 0.961656 2.52997 + vertex 0.929051 0.965 2.53 + vertex 0.93 0.96 2.52992 + endloop + endfacet + facet normal -0.904161 -0.34599 0.250567 + outer loop + vertex 0.93 0.963288 2.535 + vertex 0.929229 0.961656 2.52997 + vertex 0.93 0.96 2.53046 + endloop + endfacet + facet normal -0.868403 -0.417107 0.268139 + outer loop + vertex 0.93 0.963288 2.535 + vertex 0.928445 0.964908 2.53248 + vertex 0.929229 0.961656 2.52997 + endloop + endfacet + facet normal -0.969949 -0.0491835 -0.238286 + outer loop + vertex 0.928445 0.964908 2.53248 + vertex 0.929051 0.965 2.53 + vertex 0.929229 0.961656 2.52997 + endloop + endfacet + facet normal 0.817258 -0.0975999 -0.567947 + outer loop + vertex 0.93 0.963288 2.535 + vertex 0.929269 0.96277 2.53404 + vertex 0.928445 0.964908 2.53248 + endloop + endfacet + facet normal -0.813889 0.349601 -0.464073 + outer loop + vertex 0.93 0.968354 2.53 + vertex 0.927856 0.97 2.535 + vertex 0.93 0.97 2.53124 + endloop + endfacet + facet normal -0.859874 0.243303 -0.448798 + outer loop + vertex 0.93 0.968354 2.53 + vertex 0.929051 0.965 2.53 + vertex 0.927856 0.97 2.535 + endloop + endfacet + facet normal -0.971575 0.00449792 -0.23669 + outer loop + vertex 0.929051 0.965 2.53 + vertex 0.928445 0.964908 2.53248 + vertex 0.927856 0.97 2.535 + endloop + endfacet + facet normal -0.941884 -0.333446 0.0408546 + outer loop + vertex 0.928532 0.965018 2.53537 + vertex 0.928445 0.964908 2.53248 + vertex 0.929269 0.96277 2.53404 + endloop + endfacet + facet normal -0.958194 -0.28339 0.039439 + outer loop + vertex 0.928532 0.965018 2.53537 + vertex 0.927312 0.969226 2.53597 + vertex 0.928445 0.964908 2.53248 + endloop + endfacet + facet normal -0.900635 0.104199 -0.421899 + outer loop + vertex 0.927312 0.969226 2.53597 + vertex 0.927856 0.97 2.535 + vertex 0.928445 0.964908 2.53248 + endloop + endfacet + facet normal -0.937756 -0.297393 0.179363 + outer loop + vertex 0.928727 0.96658 2.53898 + vertex 0.927312 0.969226 2.53597 + vertex 0.928532 0.965018 2.53537 + endloop + endfacet + facet normal -0.935049 -0.315028 0.162603 + outer loop + vertex 0.927663 0.970787 2.54101 + vertex 0.927312 0.969226 2.53597 + vertex 0.928727 0.96658 2.53898 + endloop + endfacet + facet normal -0.892414 -0.358172 0.274426 + outer loop + vertex 0.928727 0.96658 2.53898 + vertex 0.929325 0.967771 2.54248 + vertex 0.927663 0.970787 2.54101 + endloop + endfacet + facet normal -0.700871 -0.311894 -0.641485 + outer loop + vertex 0.927856 0.97 2.535 + vertex 0.927312 0.969226 2.53597 + vertex 0.925631 0.975 2.535 + endloop + endfacet + facet normal -0.95612 -0.287652 -0.0556009 + outer loop + vertex 0.925631 0.975 2.535 + vertex 0.927312 0.969226 2.53597 + vertex 0.925682 0.974219 2.53816 + endloop + endfacet + facet normal -0.909284 -0.375467 0.179518 + outer loop + vertex 0.927312 0.969226 2.53597 + vertex 0.927663 0.970787 2.54101 + vertex 0.925682 0.974219 2.53816 + endloop + endfacet + facet normal -0.910921 -0.363674 0.194844 + outer loop + vertex 0.925682 0.974219 2.53816 + vertex 0.927663 0.970787 2.54101 + vertex 0.926437 0.974175 2.54161 + endloop + endfacet + facet normal -0.876786 -0.300137 0.375719 + outer loop + vertex 0.929629 0.970123 2.54507 + vertex 0.927663 0.970787 2.54101 + vertex 0.929325 0.967771 2.54248 + endloop + endfacet + facet normal -0.859215 -0.36722 0.356229 + outer loop + vertex 0.929629 0.970123 2.54507 + vertex 0.927723 0.974532 2.54502 + vertex 0.927663 0.970787 2.54101 + endloop + endfacet + facet normal -0.854799 -0.372619 0.36121 + outer loop + vertex 0.927723 0.974532 2.54502 + vertex 0.926437 0.974175 2.54161 + vertex 0.927663 0.970787 2.54101 + endloop + endfacet + facet normal -0.811826 -0.345391 0.47079 + outer loop + vertex 0.929629 0.970123 2.54507 + vertex 0.930373 0.972856 2.54836 + vertex 0.927723 0.974532 2.54502 + endloop + endfacet + facet normal -0.851436 -0.512191 -0.112773 + outer loop + vertex 0.925631 0.975 2.535 + vertex 0.925682 0.974219 2.53816 + vertex 0.924307 0.97709 2.5355 + endloop + endfacet + facet normal -0.596538 -0.191165 -0.779486 + outer loop + vertex 0.925 0.976969 2.535 + vertex 0.925631 0.975 2.535 + vertex 0.924307 0.97709 2.5355 + endloop + endfacet + facet normal -0.921829 -0.382308 0.0638128 + outer loop + vertex 0.924172 0.977876 2.53825 + vertex 0.924307 0.97709 2.5355 + vertex 0.925682 0.974219 2.53816 + endloop + endfacet + facet normal -0.891295 -0.374438 0.255714 + outer loop + vertex 0.924172 0.977876 2.53825 + vertex 0.925682 0.974219 2.53816 + vertex 0.925306 0.978086 2.54251 + endloop + endfacet + facet normal -0.928131 -0.314447 0.199238 + outer loop + vertex 0.925306 0.978086 2.54251 + vertex 0.925682 0.974219 2.53816 + vertex 0.926437 0.974175 2.54161 + endloop + endfacet + facet normal -0.869445 -0.3353 0.362823 + outer loop + vertex 0.926437 0.974175 2.54161 + vertex 0.927723 0.974532 2.54502 + vertex 0.925306 0.978086 2.54251 + endloop + endfacet + facet normal -0.869301 -0.334326 0.364063 + outer loop + vertex 0.925306 0.978086 2.54251 + vertex 0.927723 0.974532 2.54502 + vertex 0.926887 0.979477 2.54756 + endloop + endfacet + facet normal -0.813767 -0.368773 0.449209 + outer loop + vertex 0.927723 0.974532 2.54502 + vertex 0.928913 0.977006 2.54921 + vertex 0.926887 0.979477 2.54756 + endloop + endfacet + facet normal -0.808387 -0.376682 0.452351 + outer loop + vertex 0.930373 0.972856 2.54836 + vertex 0.928913 0.977006 2.54921 + vertex 0.927723 0.974532 2.54502 + endloop + endfacet + facet normal -0.895085 -0.364907 0.256255 + outer loop + vertex 0.924172 0.977876 2.53825 + vertex 0.925306 0.978086 2.54251 + vertex 0.923559 0.980633 2.54003 + endloop + endfacet + facet normal -0.896643 -0.343474 0.279385 + outer loop + vertex 0.923838 0.982317 2.543 + vertex 0.923559 0.980633 2.54003 + vertex 0.925306 0.978086 2.54251 + endloop + endfacet + facet normal -0.871137 -0.342956 0.351428 + outer loop + vertex 0.923838 0.982317 2.543 + vertex 0.925306 0.978086 2.54251 + vertex 0.925001 0.983486 2.54703 + endloop + endfacet + facet normal -0.859807 -0.355192 0.366838 + outer loop + vertex 0.925001 0.983486 2.54703 + vertex 0.925306 0.978086 2.54251 + vertex 0.926887 0.979477 2.54756 + endloop + endfacet + facet normal -0.813862 -0.369196 0.44869 + outer loop + vertex 0.928134 0.980373 2.55056 + vertex 0.926887 0.979477 2.54756 + vertex 0.928913 0.977006 2.54921 + endloop + endfacet + facet normal -0.827237 -0.341672 0.446027 + outer loop + vertex 0.928134 0.980373 2.55056 + vertex 0.927139 0.98388 2.5514 + vertex 0.926887 0.979477 2.54756 + endloop + endfacet + facet normal -0.834839 -0.33393 0.437647 + outer loop + vertex 0.927139 0.98388 2.5514 + vertex 0.925001 0.983486 2.54703 + vertex 0.926887 0.979477 2.54756 + endloop + endfacet + facet normal -0.797155 -0.345 0.495498 + outer loop + vertex 0.928134 0.980373 2.55056 + vertex 0.928782 0.982024 2.55276 + vertex 0.927139 0.98388 2.5514 + endloop + endfacet + facet normal -0.866559 -0.352825 0.352972 + outer loop + vertex 0.923838 0.982317 2.543 + vertex 0.925001 0.983486 2.54703 + vertex 0.923335 0.985457 2.54491 + endloop + endfacet + facet normal -0.866577 -0.35197 0.353781 + outer loop + vertex 0.92374 0.987493 2.54792 + vertex 0.923335 0.985457 2.54491 + vertex 0.925001 0.983486 2.54703 + endloop + endfacet + facet normal -0.825361 -0.357608 0.436916 + outer loop + vertex 0.92374 0.987493 2.54792 + vertex 0.925001 0.983486 2.54703 + vertex 0.925128 0.988739 2.55156 + endloop + endfacet + facet normal -0.82654 -0.356462 0.435622 + outer loop + vertex 0.925128 0.988739 2.55156 + vertex 0.925001 0.983486 2.54703 + vertex 0.927139 0.98388 2.5514 + endloop + endfacet + facet normal -0.792432 -0.326447 0.515251 + outer loop + vertex 0.929307 0.984525 2.55515 + vertex 0.927139 0.98388 2.5514 + vertex 0.928782 0.982024 2.55276 + endloop + endfacet + facet normal -0.780867 -0.355646 0.513578 + outer loop + vertex 0.929307 0.984525 2.55515 + vertex 0.927628 0.988553 2.55538 + vertex 0.927139 0.98388 2.5514 + endloop + endfacet + facet normal -0.792981 -0.344775 0.502306 + outer loop + vertex 0.927628 0.988553 2.55538 + vertex 0.925128 0.988739 2.55156 + vertex 0.927139 0.98388 2.5514 + endloop + endfacet + facet normal -0.763254 -0.35004 0.543061 + outer loop + vertex 0.929307 0.984525 2.55515 + vertex 0.930222 0.987683 2.55847 + vertex 0.927628 0.988553 2.55538 + endloop + endfacet + facet normal -0.816408 -0.374745 0.439368 + outer loop + vertex 0.92374 0.987493 2.54792 + vertex 0.925128 0.988739 2.55156 + vertex 0.923242 0.990582 2.54963 + endloop + endfacet + facet normal -0.815941 -0.364052 0.449117 + outer loop + vertex 0.923601 0.993094 2.55232 + vertex 0.923242 0.990582 2.54963 + vertex 0.925128 0.988739 2.55156 + endloop + endfacet + facet normal -0.778051 -0.361936 0.513458 + outer loop + vertex 0.923601 0.993094 2.55232 + vertex 0.925128 0.988739 2.55156 + vertex 0.925764 0.994388 2.55651 + endloop + endfacet + facet normal -0.791581 -0.349638 0.501153 + outer loop + vertex 0.925764 0.994388 2.55651 + vertex 0.925128 0.988739 2.55156 + vertex 0.927628 0.988553 2.55538 + endloop + endfacet + facet normal -0.765395 -0.348919 0.540764 + outer loop + vertex 0.927628 0.988553 2.55538 + vertex 0.928745 0.991977 2.55918 + vertex 0.925764 0.994388 2.55651 + endloop + endfacet + facet normal -0.76301 -0.351544 0.542432 + outer loop + vertex 0.930222 0.987683 2.55847 + vertex 0.928745 0.991977 2.55918 + vertex 0.927628 0.988553 2.55538 + endloop + endfacet + facet normal -0.782916 -0.35207 0.512922 + outer loop + vertex 0.922181 0.997819 2.5534 + vertex 0.923601 0.993094 2.55232 + vertex 0.925764 0.994388 2.55651 + endloop + endfacet + facet normal -0.782957 -0.352332 0.51268 + outer loop + vertex 0.924205 0.999967 2.55796 + vertex 0.922181 0.997819 2.5534 + vertex 0.925764 0.994388 2.55651 + endloop + endfacet + facet normal -0.765176 -0.346808 0.542429 + outer loop + vertex 0.927993 0.99563 2.56045 + vertex 0.925764 0.994388 2.55651 + vertex 0.928745 0.991977 2.55918 + endloop + endfacet + facet normal -0.765298 -0.346556 0.542419 + outer loop + vertex 0.927993 0.99563 2.56045 + vertex 0.926978 0.99938 2.56141 + vertex 0.925764 0.994388 2.55651 + endloop + endfacet + facet normal -0.757283 -0.354486 0.548509 + outer loop + vertex 0.926978 0.99938 2.56141 + vertex 0.924205 0.999967 2.55796 + vertex 0.925764 0.994388 2.55651 + endloop + endfacet + facet normal -0.747378 -0.347786 0.566101 + outer loop + vertex 0.927993 0.99563 2.56045 + vertex 0.928957 0.997398 2.56281 + vertex 0.926978 0.99938 2.56141 + endloop + endfacet + facet normal -0.770931 -0.372329 0.516756 + outer loop + vertex 0.922181 0.997819 2.5534 + vertex 0.924205 0.999967 2.55796 + vertex 0.922202 1.00158 2.55614 + endloop + endfacet + facet normal -0.769515 -0.353688 0.531743 + outer loop + vertex 0.923151 1.00314 2.55855 + vertex 0.922202 1.00158 2.55614 + vertex 0.924205 0.999967 2.55796 + endloop + endfacet + facet normal -0.755957 -0.352794 0.551422 + outer loop + vertex 0.923151 1.00314 2.55855 + vertex 0.924205 0.999967 2.55796 + vertex 0.924934 1.00416 2.56165 + endloop + endfacet + facet normal -0.758048 -0.350944 0.549728 + outer loop + vertex 0.924934 1.00416 2.56165 + vertex 0.924205 0.999967 2.55796 + vertex 0.926978 0.99938 2.56141 + endloop + endfacet + facet normal -0.743304 -0.334351 0.579403 + outer loop + vertex 0.929662 0.999804 2.5651 + vertex 0.926978 0.99938 2.56141 + vertex 0.928957 0.997398 2.56281 + endloop + endfacet + facet normal -0.734996 -0.357706 0.576044 + outer loop + vertex 0.929662 0.999804 2.5651 + vertex 0.927785 1.00389 2.56524 + vertex 0.926978 0.99938 2.56141 + endloop + endfacet + facet normal -0.747451 -0.347237 0.566343 + outer loop + vertex 0.927785 1.00389 2.56524 + vertex 0.924934 1.00416 2.56165 + vertex 0.926978 0.99938 2.56141 + endloop + endfacet + facet normal -0.719289 -0.351285 0.599352 + outer loop + vertex 0.929662 0.999804 2.5651 + vertex 0.930735 1.00273 2.56811 + vertex 0.927785 1.00389 2.56524 + endloop + endfacet + facet normal -0.759106 -0.34644 0.551123 + outer loop + vertex 0.923151 1.00314 2.55855 + vertex 0.924934 1.00416 2.56165 + vertex 0.922958 1.0057 2.55989 + endloop + endfacet + facet normal -0.75875 -0.342877 0.553835 + outer loop + vertex 0.923546 1.00809 2.56218 + vertex 0.922958 1.0057 2.55989 + vertex 0.924934 1.00416 2.56165 + endloop + endfacet + facet normal -0.750333 -0.341541 0.565995 + outer loop + vertex 0.923546 1.00809 2.56218 + vertex 0.924934 1.00416 2.56165 + vertex 0.925866 1.00942 2.56606 + endloop + endfacet + facet normal -0.748487 -0.343117 0.567483 + outer loop + vertex 0.925866 1.00942 2.56606 + vertex 0.924934 1.00416 2.56165 + vertex 0.927785 1.00389 2.56524 + endloop + endfacet + facet normal -0.733623 -0.340963 0.587827 + outer loop + vertex 0.927785 1.00389 2.56524 + vertex 0.92909 1.00695 2.56865 + vertex 0.925866 1.00942 2.56606 + endloop + endfacet + facet normal -0.718805 -0.356991 0.596555 + outer loop + vertex 0.930735 1.00273 2.56811 + vertex 0.92909 1.00695 2.56865 + vertex 0.927785 1.00389 2.56524 + endloop + endfacet + facet normal -0.753803 -0.334429 0.56563 + outer loop + vertex 0.9222 1.0127 2.56311 + vertex 0.923546 1.00809 2.56218 + vertex 0.925866 1.00942 2.56606 + endloop + endfacet + facet normal -0.754477 -0.337783 0.562732 + outer loop + vertex 0.924381 1.01468 2.56722 + vertex 0.9222 1.0127 2.56311 + vertex 0.925866 1.00942 2.56606 + endloop + endfacet + facet normal -0.732924 -0.336383 0.591328 + outer loop + vertex 0.928399 1.01034 2.56972 + vertex 0.925866 1.00942 2.56606 + vertex 0.92909 1.00695 2.56865 + endloop + endfacet + facet normal -0.735936 -0.329233 0.591611 + outer loop + vertex 0.928399 1.01034 2.56972 + vertex 0.927001 1.01362 2.56981 + vertex 0.925866 1.00942 2.56606 + endloop + endfacet + facet normal -0.72654 -0.337793 0.598361 + outer loop + vertex 0.927001 1.01362 2.56981 + vertex 0.924381 1.01468 2.56722 + vertex 0.925866 1.00942 2.56606 + endloop + endfacet + facet normal -0.680923 -0.307705 0.664576 + outer loop + vertex 0.928399 1.01034 2.56972 + vertex 0.930023 1.01198 2.57214 + vertex 0.927001 1.01362 2.56981 + endloop + endfacet + facet normal -0.753668 -0.33918 0.562975 + outer loop + vertex 0.9222 1.0127 2.56311 + vertex 0.924381 1.01468 2.56722 + vertex 0.922403 1.01679 2.56585 + endloop + endfacet + facet normal -0.751152 -0.331801 0.570682 + outer loop + vertex 0.923631 1.01792 2.56812 + vertex 0.922403 1.01679 2.56585 + vertex 0.924381 1.01468 2.56722 + endloop + endfacet + facet normal -0.728182 -0.334151 0.598409 + outer loop + vertex 0.923631 1.01792 2.56812 + vertex 0.924381 1.01468 2.56722 + vertex 0.925487 1.01689 2.5698 + endloop + endfacet + facet normal -0.726669 -0.335909 0.599264 + outer loop + vertex 0.925487 1.01689 2.5698 + vertex 0.924381 1.01468 2.56722 + vertex 0.927001 1.01362 2.56981 + endloop + endfacet + facet normal -0.685799 -0.316853 0.655197 + outer loop + vertex 0.927001 1.01362 2.56981 + vertex 0.928313 1.01743 2.57302 + vertex 0.925487 1.01689 2.5698 + endloop + endfacet + facet normal -0.682149 -0.320026 0.657462 + outer loop + vertex 0.930023 1.01198 2.57214 + vertex 0.928313 1.01743 2.57302 + vertex 0.927001 1.01362 2.56981 + endloop + endfacet + facet normal -0.727796 -0.321181 0.605934 + outer loop + vertex 0.923631 1.01792 2.56812 + vertex 0.925487 1.01689 2.5698 + vertex 0.924495 1.02009 2.57031 + endloop + endfacet + facet normal -0.659584 -0.315806 0.682067 + outer loop + vertex 0.928229 1.02156 2.57493 + vertex 0.927059 1.02515 2.57547 + vertex 0.925672 1.02273 2.573 + endloop + endfacet + facet normal -0.660238 -0.326842 0.67621 + outer loop + vertex 0.928313 1.01743 2.57302 + vertex 0.928229 1.02156 2.57493 + vertex 0.925672 1.02273 2.573 + endloop + endfacet + facet normal -0.691092 -0.342308 0.636567 + outer loop + vertex 0.928313 1.01743 2.57302 + vertex 0.925672 1.02273 2.573 + vertex 0.924495 1.02009 2.57031 + endloop + endfacet + facet normal -0.686069 -0.316054 0.6553 + outer loop + vertex 0.928313 1.01743 2.57302 + vertex 0.924495 1.02009 2.57031 + vertex 0.925487 1.01689 2.5698 + endloop + endfacet + facet normal -0.588592 -0.302715 0.749615 + outer loop + vertex 0.928229 1.02156 2.57493 + vertex 0.930336 1.02248 2.57696 + vertex 0.927059 1.02515 2.57547 + endloop + endfacet + facet normal -0.660546 -0.314787 0.681607 + outer loop + vertex 0.924145 1.02693 2.57346 + vertex 0.925672 1.02273 2.573 + vertex 0.927059 1.02515 2.57547 + endloop + endfacet + facet normal -0.662247 -0.324789 0.675234 + outer loop + vertex 0.925754 1.02852 2.57581 + vertex 0.924145 1.02693 2.57346 + vertex 0.927059 1.02515 2.57547 + endloop + endfacet + facet normal -0.583402 -0.302271 0.75384 + outer loop + vertex 0.927059 1.02515 2.57547 + vertex 0.929263 1.0277 2.57819 + vertex 0.925754 1.02852 2.57581 + endloop + endfacet + facet normal -0.586607 -0.298461 0.75287 + outer loop + vertex 0.930336 1.02248 2.57696 + vertex 0.929263 1.0277 2.57819 + vertex 0.927059 1.02515 2.57547 + endloop + endfacet + facet normal -0.66595 -0.319454 0.674136 + outer loop + vertex 0.924145 1.02693 2.57346 + vertex 0.925754 1.02852 2.57581 + vertex 0.923644 1.03027 2.57455 + endloop + endfacet + facet normal -0.657896 -0.296569 0.692257 + outer loop + vertex 0.925754 1.02852 2.57581 + vertex 0.925521 1.03177 2.57698 + vertex 0.923644 1.03027 2.57455 + endloop + endfacet + facet normal -0.583131 -0.312017 0.750069 + outer loop + vertex 0.925754 1.02852 2.57581 + vertex 0.929263 1.0277 2.57819 + vertex 0.925521 1.03177 2.57698 + endloop + endfacet + facet normal -0.582942 -0.311768 0.750319 + outer loop + vertex 0.929263 1.0277 2.57819 + vertex 0.928031 1.03293 2.57941 + vertex 0.925521 1.03177 2.57698 + endloop + endfacet + facet normal -0.587219 -0.294641 0.753897 + outer loop + vertex 0.927779 1.03622 2.58051 + vertex 0.926448 1.0398 2.58087 + vertex 0.924692 1.03663 2.57826 + endloop + endfacet + facet normal -0.58707 -0.296133 0.753428 + outer loop + vertex 0.927779 1.03622 2.58051 + vertex 0.924692 1.03663 2.57826 + vertex 0.928031 1.03293 2.57941 + endloop + endfacet + facet normal -0.589214 -0.29894 0.750641 + outer loop + vertex 0.928031 1.03293 2.57941 + vertex 0.924692 1.03663 2.57826 + vertex 0.925521 1.03177 2.57698 + endloop + endfacet + facet normal -0.506776 -0.271237 0.818296 + outer loop + vertex 0.927779 1.03622 2.58051 + vertex 0.929927 1.03729 2.58219 + vertex 0.926448 1.0398 2.58087 + endloop + endfacet + facet normal -0.587058 -0.294786 0.753965 + outer loop + vertex 0.92219 1.04258 2.57864 + vertex 0.924692 1.03663 2.57826 + vertex 0.926448 1.0398 2.58087 + endloop + endfacet + facet normal -0.592689 -0.312874 0.742179 + outer loop + vertex 0.925083 1.04354 2.58136 + vertex 0.92219 1.04258 2.57864 + vertex 0.926448 1.0398 2.58087 + endloop + endfacet + facet normal -0.503464 -0.289624 0.814028 + outer loop + vertex 0.926448 1.0398 2.58087 + vertex 0.929033 1.04247 2.58342 + vertex 0.925083 1.04354 2.58136 + endloop + endfacet + facet normal -0.51122 -0.280523 0.81238 + outer loop + vertex 0.929927 1.03729 2.58219 + vertex 0.929033 1.04247 2.58342 + vertex 0.926448 1.0398 2.58087 + endloop + endfacet + facet normal -0.584087 -0.333132 0.740179 + outer loop + vertex 0.92219 1.04258 2.57864 + vertex 0.925083 1.04354 2.58136 + vertex 0.922698 1.0461 2.58062 + endloop + endfacet + facet normal -0.551549 -0.290837 0.781798 + outer loop + vertex 0.925083 1.04354 2.58136 + vertex 0.924989 1.04695 2.58256 + vertex 0.922698 1.0461 2.58062 + endloop + endfacet + facet normal -0.504081 -0.299501 0.810063 + outer loop + vertex 0.925083 1.04354 2.58136 + vertex 0.929033 1.04247 2.58342 + vertex 0.924989 1.04695 2.58256 + endloop + endfacet + facet normal -0.494394 -0.288882 0.81983 + outer loop + vertex 0.929033 1.04247 2.58342 + vertex 0.927828 1.04787 2.58459 + vertex 0.924989 1.04695 2.58256 + endloop + endfacet + facet normal -0.495475 -0.276703 0.823371 + outer loop + vertex 0.927638 1.0514 2.58564 + vertex 0.926217 1.05508 2.58602 + vertex 0.92385 1.05232 2.58367 + endloop + endfacet + facet normal -0.495167 -0.270952 0.825466 + outer loop + vertex 0.927638 1.0514 2.58564 + vertex 0.92385 1.05232 2.58367 + vertex 0.927828 1.04787 2.58459 + endloop + endfacet + facet normal -0.499596 -0.275798 0.821182 + outer loop + vertex 0.927828 1.04787 2.58459 + vertex 0.92385 1.05232 2.58367 + vertex 0.924989 1.04695 2.58256 + endloop + endfacet + facet normal -0.441525 -0.259589 0.858877 + outer loop + vertex 0.927638 1.0514 2.58564 + vertex 0.930221 1.05298 2.58744 + vertex 0.926217 1.05508 2.58602 + endloop + endfacet + facet normal -0.493647 -0.278647 0.823814 + outer loop + vertex 0.922708 1.05766 2.58479 + vertex 0.92385 1.05232 2.58367 + vertex 0.926217 1.05508 2.58602 + endloop + endfacet + facet normal -0.494687 -0.280692 0.822494 + outer loop + vertex 0.924864 1.05867 2.58643 + vertex 0.922708 1.05766 2.58479 + vertex 0.926217 1.05508 2.58602 + endloop + endfacet + facet normal -0.449143 -0.266962 0.852644 + outer loop + vertex 0.926217 1.05508 2.58602 + vertex 0.927803 1.05797 2.58776 + vertex 0.924864 1.05867 2.58643 + endloop + endfacet + facet normal -0.445139 -0.269875 0.853826 + outer loop + vertex 0.930221 1.05298 2.58744 + vertex 0.927803 1.05797 2.58776 + vertex 0.926217 1.05508 2.58602 + endloop + endfacet + facet normal -0.496196 -0.277661 0.822614 + outer loop + vertex 0.922708 1.05766 2.58479 + vertex 0.924864 1.05867 2.58643 + vertex 0.9225 1.06104 2.5858 + endloop + endfacet + facet normal -0.481926 -0.25963 0.836863 + outer loop + vertex 0.924864 1.05867 2.58643 + vertex 0.924804 1.06197 2.58742 + vertex 0.9225 1.06104 2.5858 + endloop + endfacet + facet normal -0.448914 -0.264067 0.853665 + outer loop + vertex 0.924864 1.05867 2.58643 + vertex 0.927803 1.05797 2.58776 + vertex 0.924804 1.06197 2.58742 + endloop + endfacet + facet normal -0.440863 -0.257509 0.859842 + outer loop + vertex 0.927803 1.05797 2.58776 + vertex 0.928445 1.06226 2.58938 + vertex 0.924804 1.06197 2.58742 + endloop + endfacet + facet normal -0.437824 -0.26153 0.860182 + outer loop + vertex 0.927957 1.06638 2.59037 + vertex 0.926374 1.07025 2.59074 + vertex 0.923782 1.06743 2.58856 + endloop + endfacet + facet normal -0.437644 -0.259706 0.860825 + outer loop + vertex 0.927957 1.06638 2.59037 + vertex 0.923782 1.06743 2.58856 + vertex 0.928445 1.06226 2.58938 + endloop + endfacet + facet normal -0.439987 -0.262122 0.858897 + outer loop + vertex 0.928445 1.06226 2.58938 + vertex 0.923782 1.06743 2.58856 + vertex 0.924804 1.06197 2.58742 + endloop + endfacet + facet normal -0.424828 -0.256965 0.868038 + outer loop + vertex 0.927957 1.06638 2.59037 + vertex 0.930629 1.06803 2.59216 + vertex 0.926374 1.07025 2.59074 + endloop + endfacet + facet normal -0.4325 -0.267164 0.861143 + outer loop + vertex 0.922773 1.07284 2.58974 + vertex 0.923782 1.06743 2.58856 + vertex 0.926374 1.07025 2.59074 + endloop + endfacet + facet normal -0.427329 -0.25789 0.866535 + outer loop + vertex 0.925048 1.074 2.5912 + vertex 0.922773 1.07284 2.58974 + vertex 0.926374 1.07025 2.59074 + endloop + endfacet + facet normal -0.412978 -0.253825 0.874655 + outer loop + vertex 0.926374 1.07025 2.59074 + vertex 0.928186 1.0732 2.59245 + vertex 0.925048 1.074 2.5912 + endloop + endfacet + facet normal -0.421344 -0.247439 0.872492 + outer loop + vertex 0.930629 1.06803 2.59216 + vertex 0.928186 1.0732 2.59245 + vertex 0.926374 1.07025 2.59074 + endloop + endfacet + facet normal -0.425236 -0.261799 0.866392 + outer loop + vertex 0.922773 1.07284 2.58974 + vertex 0.925048 1.074 2.5912 + vertex 0.922762 1.07625 2.59076 + endloop + endfacet + facet normal -0.413834 -0.248329 0.875828 + outer loop + vertex 0.925048 1.074 2.5912 + vertex 0.925188 1.07792 2.59238 + vertex 0.922762 1.07625 2.59076 + endloop + endfacet + facet normal -0.412353 -0.248571 0.876457 + outer loop + vertex 0.925048 1.074 2.5912 + vertex 0.928186 1.0732 2.59245 + vertex 0.925188 1.07792 2.59238 + endloop + endfacet + facet normal -0.411758 -0.248188 0.876845 + outer loop + vertex 0.928186 1.0732 2.59245 + vertex 0.929497 1.07693 2.59412 + vertex 0.925188 1.07792 2.59238 + endloop + endfacet + facet normal -0.411652 -0.247083 0.877207 + outer loop + vertex 0.929497 1.07693 2.59412 + vertex 0.927025 1.0822 2.59445 + vertex 0.925188 1.07792 2.59238 + endloop + endfacet + facet normal -0.403356 -0.251845 0.879704 + outer loop + vertex 0.925188 1.07792 2.59238 + vertex 0.927025 1.0822 2.59445 + vertex 0.922574 1.08319 2.59269 + endloop + endfacet + facet normal -0.397684 -0.249491 0.882951 + outer loop + vertex 0.927083 1.08618 2.59559 + vertex 0.925749 1.08928 2.59587 + vertex 0.923535 1.08745 2.59436 + endloop + endfacet + facet normal -0.397522 -0.248777 0.883225 + outer loop + vertex 0.927083 1.08618 2.59559 + vertex 0.923535 1.08745 2.59436 + vertex 0.927025 1.0822 2.59445 + endloop + endfacet + facet normal -0.403441 -0.252781 0.879396 + outer loop + vertex 0.927025 1.0822 2.59445 + vertex 0.923535 1.08745 2.59436 + vertex 0.922574 1.08319 2.59269 + endloop + endfacet + facet normal -0.430601 -0.261952 0.863692 + outer loop + vertex 0.927083 1.08618 2.59559 + vertex 0.929287 1.08799 2.59724 + vertex 0.925749 1.08928 2.59587 + endloop + endfacet + facet normal -0.393491 -0.254868 0.883293 + outer loop + vertex 0.923535 1.08745 2.59436 + vertex 0.925749 1.08928 2.59587 + vertex 0.923248 1.09144 2.59538 + endloop + endfacet + facet normal -0.392858 -0.254019 0.88382 + outer loop + vertex 0.925749 1.08928 2.59587 + vertex 0.925729 1.09318 2.59698 + vertex 0.923248 1.09144 2.59538 + endloop + endfacet + facet normal -0.428061 -0.249838 0.86853 + outer loop + vertex 0.925749 1.08928 2.59587 + vertex 0.929287 1.08799 2.59724 + vertex 0.925729 1.09318 2.59698 + endloop + endfacet + facet normal -0.431907 -0.252609 0.86582 + outer loop + vertex 0.929287 1.08799 2.59724 + vertex 0.92997 1.09224 2.59882 + vertex 0.925729 1.09318 2.59698 + endloop + endfacet + facet normal -0.430135 -0.231066 0.872692 + outer loop + vertex 0.92997 1.09224 2.59882 + vertex 0.927547 1.09738 2.59899 + vertex 0.925729 1.09318 2.59698 + endloop + endfacet + facet normal -0.406294 -0.245005 0.880283 + outer loop + vertex 0.925729 1.09318 2.59698 + vertex 0.927547 1.09738 2.59899 + vertex 0.923186 1.09836 2.59725 + endloop + endfacet + facet normal -0.421756 -0.231851 0.876565 + outer loop + vertex 0.927821 1.10128 2.60014 + vertex 0.926645 1.1051 2.60059 + vertex 0.924629 1.10215 2.59884 + endloop + endfacet + facet normal -0.421409 -0.229332 0.877395 + outer loop + vertex 0.927821 1.10128 2.60014 + vertex 0.924629 1.10215 2.59884 + vertex 0.927547 1.09738 2.59899 + endloop + endfacet + facet normal -0.403557 -0.218045 0.888594 + outer loop + vertex 0.927547 1.09738 2.59899 + vertex 0.924629 1.10215 2.59884 + vertex 0.923186 1.09836 2.59725 + endloop + endfacet + facet normal -0.493206 -0.248823 0.833568 + outer loop + vertex 0.927821 1.10128 2.60014 + vertex 0.930156 1.10241 2.60186 + vertex 0.926645 1.1051 2.60059 + endloop + endfacet + facet normal -0.419823 -0.233466 0.877064 + outer loop + vertex 0.922509 1.10731 2.5992 + vertex 0.924629 1.10215 2.59884 + vertex 0.926645 1.1051 2.60059 + endloop + endfacet + facet normal -0.413923 -0.218195 0.883775 + outer loop + vertex 0.925409 1.10905 2.60098 + vertex 0.922509 1.10731 2.5992 + vertex 0.926645 1.1051 2.60059 + endloop + endfacet + facet normal -0.493143 -0.238267 0.836683 + outer loop + vertex 0.926645 1.1051 2.60059 + vertex 0.929339 1.10785 2.60296 + vertex 0.925409 1.10905 2.60098 + endloop + endfacet + facet normal -0.489698 -0.242376 0.837526 + outer loop + vertex 0.930156 1.10241 2.60186 + vertex 0.929339 1.10785 2.60296 + vertex 0.926645 1.1051 2.60059 + endloop + endfacet + facet normal -0.417075 -0.212777 0.883615 + outer loop + vertex 0.922509 1.10731 2.5992 + vertex 0.925409 1.10905 2.60098 + vertex 0.92293 1.11141 2.60038 + endloop + endfacet + facet normal -0.43655 -0.237311 0.867818 + outer loop + vertex 0.925409 1.10905 2.60098 + vertex 0.925544 1.11316 2.60217 + vertex 0.92293 1.11141 2.60038 + endloop + endfacet + facet normal -0.491764 -0.227566 0.840465 + outer loop + vertex 0.925409 1.10905 2.60098 + vertex 0.929339 1.10785 2.60296 + vertex 0.925544 1.11316 2.60217 + endloop + endfacet + facet normal -0.499367 -0.233923 0.834214 + outer loop + vertex 0.929339 1.10785 2.60296 + vertex 0.929019 1.11264 2.60411 + vertex 0.925544 1.11316 2.60217 + endloop + endfacet + facet normal -0.4994 -0.226307 0.836292 + outer loop + vertex 0.929019 1.11264 2.60411 + vertex 0.927238 1.11717 2.60427 + vertex 0.925544 1.11316 2.60217 + endloop + endfacet + facet normal -0.475192 -0.241629 0.846054 + outer loop + vertex 0.925544 1.11316 2.60217 + vertex 0.927238 1.11717 2.60427 + vertex 0.923226 1.11829 2.60234 + endloop + endfacet + facet normal -0.49672 -0.232534 0.83618 + outer loop + vertex 0.927538 1.12083 2.60548 + vertex 0.926386 1.12465 2.60585 + vertex 0.924554 1.12189 2.604 + endloop + endfacet + facet normal -0.497004 -0.234218 0.835541 + outer loop + vertex 0.927538 1.12083 2.60548 + vertex 0.924554 1.12189 2.604 + vertex 0.927238 1.11717 2.60427 + endloop + endfacet + facet normal -0.472564 -0.219303 0.853574 + outer loop + vertex 0.927238 1.11717 2.60427 + vertex 0.924554 1.12189 2.604 + vertex 0.923226 1.11829 2.60234 + endloop + endfacet + facet normal -0.552944 -0.245507 0.796228 + outer loop + vertex 0.927538 1.12083 2.60548 + vertex 0.929658 1.12195 2.60729 + vertex 0.926386 1.12465 2.60585 + endloop + endfacet + facet normal -0.490742 -0.237864 0.838208 + outer loop + vertex 0.922408 1.12712 2.60423 + vertex 0.924554 1.12189 2.604 + vertex 0.926386 1.12465 2.60585 + endloop + endfacet + facet normal -0.480455 -0.213025 0.850755 + outer loop + vertex 0.925111 1.12855 2.60611 + vertex 0.922408 1.12712 2.60423 + vertex 0.926386 1.12465 2.60585 + endloop + endfacet + facet normal -0.544825 -0.231129 0.806068 + outer loop + vertex 0.926386 1.12465 2.60585 + vertex 0.928844 1.12745 2.60832 + vertex 0.925111 1.12855 2.60611 + endloop + endfacet + facet normal -0.545093 -0.230813 0.805977 + outer loop + vertex 0.929658 1.12195 2.60729 + vertex 0.928844 1.12745 2.60832 + vertex 0.926386 1.12465 2.60585 + endloop + endfacet + facet normal -0.486474 -0.200998 0.85026 + outer loop + vertex 0.922408 1.12712 2.60423 + vertex 0.925111 1.12855 2.60611 + vertex 0.922749 1.13107 2.60535 + endloop + endfacet + facet normal -0.503315 -0.221354 0.83527 + outer loop + vertex 0.925111 1.12855 2.60611 + vertex 0.925081 1.13221 2.60706 + vertex 0.922749 1.13107 2.60535 + endloop + endfacet + facet normal -0.54333 -0.215478 0.811395 + outer loop + vertex 0.925111 1.12855 2.60611 + vertex 0.928844 1.12745 2.60832 + vertex 0.925081 1.13221 2.60706 + endloop + endfacet + facet normal -0.547185 -0.219491 0.80772 + outer loop + vertex 0.928844 1.12745 2.60832 + vertex 0.927895 1.13303 2.60919 + vertex 0.925081 1.13221 2.60706 + endloop + endfacet + facet normal -0.551681 -0.223893 0.803443 + outer loop + vertex 0.927825 1.13642 2.6101 + vertex 0.926923 1.14009 2.6105 + vertex 0.924262 1.13777 2.60803 + endloop + endfacet + facet normal -0.552011 -0.226035 0.802615 + outer loop + vertex 0.927825 1.13642 2.6101 + vertex 0.924262 1.13777 2.60803 + vertex 0.927895 1.13303 2.60919 + endloop + endfacet + facet normal -0.546763 -0.220774 0.807657 + outer loop + vertex 0.927895 1.13303 2.60919 + vertex 0.924262 1.13777 2.60803 + vertex 0.925081 1.13221 2.60706 + endloop + endfacet + facet normal -0.573066 -0.22739 0.787331 + outer loop + vertex 0.927825 1.13642 2.6101 + vertex 0.930114 1.13699 2.61193 + vertex 0.926923 1.14009 2.6105 + endloop + endfacet + facet normal -0.560901 -0.210387 0.800704 + outer loop + vertex 0.923951 1.14263 2.60909 + vertex 0.924262 1.13777 2.60803 + vertex 0.926923 1.14009 2.6105 + endloop + endfacet + facet normal -0.56691 -0.221475 0.79345 + outer loop + vertex 0.925854 1.14465 2.61101 + vertex 0.923951 1.14263 2.60909 + vertex 0.926923 1.14009 2.6105 + endloop + endfacet + facet normal -0.576024 -0.222827 0.786476 + outer loop + vertex 0.926923 1.14009 2.6105 + vertex 0.929782 1.1418 2.61308 + vertex 0.925854 1.14465 2.61101 + endloop + endfacet + facet normal -0.573395 -0.227908 0.786941 + outer loop + vertex 0.930114 1.13699 2.61193 + vertex 0.929782 1.1418 2.61308 + vertex 0.926923 1.14009 2.6105 + endloop + endfacet + facet normal -0.563145 -0.226266 0.794777 + outer loop + vertex 0.922252 1.14715 2.60917 + vertex 0.923951 1.14263 2.60909 + vertex 0.925854 1.14465 2.61101 + endloop + endfacet + facet normal -0.557131 -0.211464 0.803049 + outer loop + vertex 0.92466 1.14842 2.61117 + vertex 0.922252 1.14715 2.60917 + vertex 0.925854 1.14465 2.61101 + endloop + endfacet + facet normal -0.579187 -0.217698 0.785589 + outer loop + vertex 0.925854 1.14465 2.61101 + vertex 0.92785 1.14779 2.61335 + vertex 0.92466 1.14842 2.61117 + endloop + endfacet + facet normal -0.575424 -0.221384 0.787322 + outer loop + vertex 0.929782 1.1418 2.61308 + vertex 0.92785 1.14779 2.61335 + vertex 0.925854 1.14465 2.61101 + endloop + endfacet + facet normal -0.56043 -0.204472 0.802564 + outer loop + vertex 0.922252 1.14715 2.60917 + vertex 0.92466 1.14842 2.61117 + vertex 0.922663 1.15077 2.61038 + endloop + endfacet + facet normal -0.573932 -0.220734 0.788593 + outer loop + vertex 0.92466 1.14842 2.61117 + vertex 0.924844 1.15181 2.61226 + vertex 0.922663 1.15077 2.61038 + endloop + endfacet + facet normal -0.579196 -0.21934 0.785125 + outer loop + vertex 0.92466 1.14842 2.61117 + vertex 0.92785 1.14779 2.61335 + vertex 0.924844 1.15181 2.61226 + endloop + endfacet + facet normal -0.578493 -0.218617 0.785845 + outer loop + vertex 0.92785 1.14779 2.61335 + vertex 0.92765 1.15271 2.61457 + vertex 0.924844 1.15181 2.61226 + endloop + endfacet + facet normal -0.577205 -0.206498 0.790059 + outer loop + vertex 0.927889 1.15615 2.61566 + vertex 0.926665 1.15992 2.61575 + vertex 0.924609 1.15675 2.61342 + endloop + endfacet + facet normal -0.577209 -0.208934 0.789415 + outer loop + vertex 0.927889 1.15615 2.61566 + vertex 0.924609 1.15675 2.61342 + vertex 0.92765 1.15271 2.61457 + endloop + endfacet + facet normal -0.580591 -0.212465 0.785985 + outer loop + vertex 0.92765 1.15271 2.61457 + vertex 0.924609 1.15675 2.61342 + vertex 0.924844 1.15181 2.61226 + endloop + endfacet + facet normal -0.519897 -0.188972 0.833065 + outer loop + vertex 0.927889 1.15615 2.61566 + vertex 0.930439 1.15762 2.61758 + vertex 0.926665 1.15992 2.61575 + endloop + endfacet + facet normal -0.582604 -0.201113 0.787481 + outer loop + vertex 0.922769 1.16266 2.61357 + vertex 0.924609 1.15675 2.61342 + vertex 0.926665 1.15992 2.61575 + endloop + endfacet + facet normal -0.589316 -0.218366 0.777832 + outer loop + vertex 0.925542 1.16436 2.61615 + vertex 0.922769 1.16266 2.61357 + vertex 0.926665 1.15992 2.61575 + endloop + endfacet + facet normal -0.548652 -0.210846 0.809027 + outer loop + vertex 0.926665 1.15992 2.61575 + vertex 0.928618 1.16196 2.61761 + vertex 0.925542 1.16436 2.61615 + endloop + endfacet + facet normal -0.534593 -0.228508 0.81363 + outer loop + vertex 0.930439 1.15762 2.61758 + vertex 0.928618 1.16196 2.61761 + vertex 0.926665 1.15992 2.61575 + endloop + endfacet + facet normal -0.592783 -0.211565 0.777077 + outer loop + vertex 0.922587 1.16733 2.6147 + vertex 0.922769 1.16266 2.61357 + vertex 0.925542 1.16436 2.61615 + endloop + endfacet + facet normal -0.601474 -0.225426 0.766428 + outer loop + vertex 0.92483 1.16721 2.61642 + vertex 0.922587 1.16733 2.6147 + vertex 0.925542 1.16436 2.61615 + endloop + endfacet + facet normal -0.559546 -0.218186 0.799564 + outer loop + vertex 0.925542 1.16436 2.61615 + vertex 0.927808 1.16693 2.61843 + vertex 0.92483 1.16721 2.61642 + endloop + endfacet + facet normal -0.554973 -0.223699 0.801227 + outer loop + vertex 0.928618 1.16196 2.61761 + vertex 0.927808 1.16693 2.61843 + vertex 0.925542 1.16436 2.61615 + endloop + endfacet + facet normal -0.601795 -0.222436 0.76705 + outer loop + vertex 0.922587 1.16733 2.6147 + vertex 0.92483 1.16721 2.61642 + vertex 0.923509 1.17015 2.61624 + endloop + endfacet + facet normal -0.540109 -0.189605 0.819958 + outer loop + vertex 0.928201 1.17123 2.61992 + vertex 0.9272 1.17536 2.62021 + vertex 0.925225 1.1725 2.61825 + endloop + endfacet + facet normal -0.548101 -0.228322 0.804646 + outer loop + vertex 0.927808 1.16693 2.61843 + vertex 0.928201 1.17123 2.61992 + vertex 0.925225 1.1725 2.61825 + endloop + endfacet + facet normal -0.579039 -0.243504 0.778087 + outer loop + vertex 0.927808 1.16693 2.61843 + vertex 0.925225 1.1725 2.61825 + vertex 0.923509 1.17015 2.61624 + endloop + endfacet + facet normal -0.56048 -0.201678 0.803236 + outer loop + vertex 0.927808 1.16693 2.61843 + vertex 0.923509 1.17015 2.61624 + vertex 0.92483 1.16721 2.61642 + endloop + endfacet + facet normal -0.403634 -0.162241 0.900421 + outer loop + vertex 0.928201 1.17123 2.61992 + vertex 0.93122 1.17335 2.62166 + vertex 0.9272 1.17536 2.62021 + endloop + endfacet + facet normal -0.549736 -0.180019 0.81571 + outer loop + vertex 0.923679 1.17735 2.61828 + vertex 0.925225 1.1725 2.61825 + vertex 0.9272 1.17536 2.62021 + endloop + endfacet + facet normal -0.549695 -0.179891 0.815767 + outer loop + vertex 0.926015 1.1802 2.62048 + vertex 0.923679 1.17735 2.61828 + vertex 0.9272 1.17536 2.62021 + endloop + endfacet + facet normal -0.441766 -0.157186 0.883252 + outer loop + vertex 0.9272 1.17536 2.62021 + vertex 0.929831 1.17862 2.62211 + vertex 0.926015 1.1802 2.62048 + endloop + endfacet + facet normal -0.412336 -0.185876 0.891868 + outer loop + vertex 0.93122 1.17335 2.62166 + vertex 0.929831 1.17862 2.62211 + vertex 0.9272 1.17536 2.62021 + endloop + endfacet + facet normal -0.558014 -0.170287 0.812171 + outer loop + vertex 0.922009 1.18272 2.61826 + vertex 0.923679 1.17735 2.61828 + vertex 0.926015 1.1802 2.62048 + endloop + endfacet + facet normal -0.567545 -0.196539 0.79954 + outer loop + vertex 0.925094 1.18413 2.6208 + vertex 0.922009 1.18272 2.61826 + vertex 0.926015 1.1802 2.62048 + endloop + endfacet + facet normal -0.457626 -0.176533 0.871444 + outer loop + vertex 0.926015 1.1802 2.62048 + vertex 0.928697 1.18379 2.62262 + vertex 0.925094 1.18413 2.6208 + endloop + endfacet + facet normal -0.449153 -0.184493 0.874199 + outer loop + vertex 0.929831 1.17862 2.62211 + vertex 0.928697 1.18379 2.62262 + vertex 0.926015 1.1802 2.62048 + endloop + endfacet + facet normal -0.560682 -0.212809 0.800218 + outer loop + vertex 0.922009 1.18272 2.61826 + vertex 0.925094 1.18413 2.6208 + vertex 0.923048 1.18645 2.61998 + endloop + endfacet + facet normal -0.536848 -0.183685 0.82344 + outer loop + vertex 0.925094 1.18413 2.6208 + vertex 0.925811 1.18788 2.6221 + vertex 0.923048 1.18645 2.61998 + endloop + endfacet + facet normal -0.457035 -0.212862 0.863602 + outer loop + vertex 0.925094 1.18413 2.6208 + vertex 0.928697 1.18379 2.62262 + vertex 0.925811 1.18788 2.6221 + endloop + endfacet + facet normal -0.432588 -0.193451 0.880593 + outer loop + vertex 0.928697 1.18379 2.62262 + vertex 0.928931 1.18746 2.62354 + vertex 0.925811 1.18788 2.6221 + endloop + endfacet + facet normal -0.43272 -0.19834 0.87944 + outer loop + vertex 0.928931 1.18746 2.62354 + vertex 0.928411 1.19144 2.62418 + vertex 0.925811 1.18788 2.6221 + endloop + endfacet + facet normal -0.442003 -0.189937 0.876674 + outer loop + vertex 0.925811 1.18788 2.6221 + vertex 0.928411 1.19144 2.62418 + vertex 0.924363 1.1921 2.62228 + endloop + endfacet + facet normal -0.457922 -0.170939 0.872403 + outer loop + vertex 0.928123 1.19597 2.62519 + vertex 0.926879 1.20017 2.62536 + vertex 0.924492 1.19658 2.62341 + endloop + endfacet + facet normal -0.460175 -0.220786 0.859937 + outer loop + vertex 0.928123 1.19597 2.62519 + vertex 0.924492 1.19658 2.62341 + vertex 0.928411 1.19144 2.62418 + endloop + endfacet + facet normal -0.442712 -0.205543 0.872788 + outer loop + vertex 0.928411 1.19144 2.62418 + vertex 0.924492 1.19658 2.62341 + vertex 0.924363 1.1921 2.62228 + endloop + endfacet + facet normal -0.288869 -0.123942 0.949312 + outer loop + vertex 0.928123 1.19597 2.62519 + vertex 0.931156 1.19835 2.62643 + vertex 0.926879 1.20017 2.62536 + endloop + endfacet + facet normal -0.494272 -0.138965 0.858128 + outer loop + vertex 0.923069 1.20273 2.62358 + vertex 0.924492 1.19658 2.62341 + vertex 0.926879 1.20017 2.62536 + endloop + endfacet + facet normal -0.478893 -0.106872 0.871344 + outer loop + vertex 0.926357 1.20495 2.62566 + vertex 0.923069 1.20273 2.62358 + vertex 0.926879 1.20017 2.62536 + endloop + endfacet + facet normal -0.324084 -0.0943661 0.94131 + outer loop + vertex 0.926879 1.20017 2.62536 + vertex 0.929857 1.20352 2.62672 + vertex 0.926357 1.20495 2.62566 + endloop + endfacet + facet normal -0.290148 -0.127444 0.948458 + outer loop + vertex 0.931156 1.19835 2.62643 + vertex 0.929857 1.20352 2.62672 + vertex 0.926879 1.20017 2.62536 + endloop + endfacet + facet normal -0.506026 -0.0567213 0.860651 + outer loop + vertex 0.923919 1.20783 2.62442 + vertex 0.923069 1.20273 2.62358 + vertex 0.926357 1.20495 2.62566 + endloop + endfacet + facet normal -0.477796 -0.025206 0.878109 + outer loop + vertex 0.926599 1.2086 2.6259 + vertex 0.923919 1.20783 2.62442 + vertex 0.926357 1.20495 2.62566 + endloop + endfacet + facet normal -0.325872 -0.0395987 0.944584 + outer loop + vertex 0.926357 1.20495 2.62566 + vertex 0.9293 1.20804 2.62681 + vertex 0.926599 1.2086 2.6259 + endloop + endfacet + facet normal -0.310589 -0.0557596 0.948908 + outer loop + vertex 0.929857 1.20352 2.62672 + vertex 0.9293 1.20804 2.62681 + vertex 0.926357 1.20495 2.62566 + endloop + endfacet + facet normal -0.378259 0.0568617 0.923952 + outer loop + vertex 0.926599 1.2086 2.6259 + vertex 0.928458 1.21105 2.62651 + vertex 0.925725 1.2121 2.62533 + endloop + endfacet + facet normal -0.488049 0.0210122 0.872563 + outer loop + vertex 0.926599 1.2086 2.6259 + vertex 0.925725 1.2121 2.62533 + vertex 0.923919 1.20783 2.62442 + endloop + endfacet + facet normal -0.514249 0.0354155 0.856909 + outer loop + vertex 0.923919 1.20783 2.62442 + vertex 0.925725 1.2121 2.62533 + vertex 0.921868 1.2122 2.62301 + endloop + endfacet + facet normal -0.317864 0.00506997 0.948123 + outer loop + vertex 0.928458 1.21105 2.62651 + vertex 0.926599 1.2086 2.6259 + vertex 0.9293 1.20804 2.62681 + endloop + endfacet + facet normal -0.432397 -0.0670563 0.899186 + outer loop + vertex 0.926951 1.21594 2.62586 + vertex 0.926286 1.21983 2.62583 + vertex 0.923924 1.21634 2.62443 + endloop + endfacet + facet normal -0.425106 0.00980232 0.905091 + outer loop + vertex 0.926951 1.21594 2.62586 + vertex 0.923924 1.21634 2.62443 + vertex 0.925725 1.2121 2.62533 + endloop + endfacet + facet normal -0.515582 -0.0389518 0.855954 + outer loop + vertex 0.925725 1.2121 2.62533 + vertex 0.923924 1.21634 2.62443 + vertex 0.921868 1.2122 2.62301 + endloop + endfacet + facet normal -0.313532 -0.0463513 0.948446 + outer loop + vertex 0.926951 1.21594 2.62586 + vertex 0.930322 1.21839 2.62709 + vertex 0.926286 1.21983 2.62583 + endloop + endfacet + facet normal -0.423342 -0.0746621 0.902888 + outer loop + vertex 0.922412 1.22149 2.62415 + vertex 0.923924 1.21634 2.62443 + vertex 0.926286 1.21983 2.62583 + endloop + endfacet + facet normal -0.445368 -0.145901 0.88338 + outer loop + vertex 0.925247 1.22376 2.62596 + vertex 0.922412 1.22149 2.62415 + vertex 0.926286 1.21983 2.62583 + endloop + endfacet + facet normal -0.319461 -0.114447 0.940663 + outer loop + vertex 0.926286 1.21983 2.62583 + vertex 0.929285 1.2242 2.62738 + vertex 0.925247 1.22376 2.62596 + endloop + endfacet + facet normal -0.331226 -0.105299 0.937657 + outer loop + vertex 0.930322 1.21839 2.62709 + vertex 0.929285 1.2242 2.62738 + vertex 0.926286 1.21983 2.62583 + endloop + endfacet + facet normal -0.428071 -0.170719 0.887474 + outer loop + vertex 0.922412 1.22149 2.62415 + vertex 0.925247 1.22376 2.62596 + vertex 0.922843 1.22587 2.6252 + endloop + endfacet + facet normal -0.407362 -0.141765 0.902197 + outer loop + vertex 0.925247 1.22376 2.62596 + vertex 0.925959 1.22828 2.62699 + vertex 0.922843 1.22587 2.6252 + endloop + endfacet + facet normal -0.312324 -0.164378 0.935646 + outer loop + vertex 0.925247 1.22376 2.62596 + vertex 0.929285 1.2242 2.62738 + vertex 0.925959 1.22828 2.62699 + endloop + endfacet + facet normal -0.291312 -0.146334 0.94537 + outer loop + vertex 0.929285 1.2242 2.62738 + vertex 0.929962 1.22883 2.6283 + vertex 0.925959 1.22828 2.62699 + endloop + endfacet + facet normal -0.287106 -0.170511 0.942601 + outer loop + vertex 0.929962 1.22883 2.6283 + vertex 0.928752 1.23245 2.62859 + vertex 0.925959 1.22828 2.62699 + endloop + endfacet + facet normal -0.302854 -0.158844 0.939706 + outer loop + vertex 0.925959 1.22828 2.62699 + vertex 0.928752 1.23245 2.62859 + vertex 0.924601 1.23345 2.62742 + endloop + endfacet + facet normal -0.30558 -0.174403 0.936058 + outer loop + vertex 0.928752 1.23245 2.62859 + vertex 0.927366 1.23641 2.62888 + vertex 0.924601 1.23345 2.62742 + endloop + endfacet + facet normal -0.317575 -0.162306 0.934239 + outer loop + vertex 0.924601 1.23345 2.62742 + vertex 0.927366 1.23641 2.62888 + vertex 0.923522 1.23857 2.62795 + endloop + endfacet + facet normal -0.311872 -0.150482 0.938131 + outer loop + vertex 0.927366 1.23641 2.62888 + vertex 0.927686 1.24123 2.62976 + vertex 0.923522 1.23857 2.62795 + endloop + endfacet + facet normal -0.28574 -0.191932 0.93889 + outer loop + vertex 0.923522 1.23857 2.62795 + vertex 0.927686 1.24123 2.62976 + vertex 0.923925 1.24214 2.6288 + endloop + endfacet + facet normal -0.276079 -0.156289 0.948343 + outer loop + vertex 0.927761 1.24577 2.63053 + vertex 0.926187 1.24977 2.63073 + vertex 0.923882 1.24588 2.62942 + endloop + endfacet + facet normal -0.276062 -0.157344 0.948174 + outer loop + vertex 0.927761 1.24577 2.63053 + vertex 0.923882 1.24588 2.62942 + vertex 0.927686 1.24123 2.62976 + endloop + endfacet + facet normal -0.280128 -0.160802 0.946399 + outer loop + vertex 0.927686 1.24123 2.62976 + vertex 0.923882 1.24588 2.62942 + vertex 0.923925 1.24214 2.6288 + endloop + endfacet + facet normal -0.168768 -0.115575 0.978856 + outer loop + vertex 0.927761 1.24577 2.63053 + vertex 0.930911 1.24831 2.63137 + vertex 0.926187 1.24977 2.63073 + endloop + endfacet + facet normal -0.279633 -0.153959 0.947682 + outer loop + vertex 0.921799 1.2516 2.62973 + vertex 0.923882 1.24588 2.62942 + vertex 0.926187 1.24977 2.63073 + endloop + endfacet + facet normal -0.285841 -0.171458 0.942813 + outer loop + vertex 0.924707 1.25367 2.63099 + vertex 0.921799 1.2516 2.62973 + vertex 0.926187 1.24977 2.63073 + endloop + endfacet + facet normal -0.156114 -0.124702 0.979836 + outer loop + vertex 0.926187 1.24977 2.63073 + vertex 0.928921 1.25405 2.63171 + vertex 0.924707 1.25367 2.63099 + endloop + endfacet + facet normal -0.168961 -0.116251 0.978743 + outer loop + vertex 0.930911 1.24831 2.63137 + vertex 0.928921 1.25405 2.63171 + vertex 0.926187 1.24977 2.63073 + endloop + endfacet + facet normal -0.277556 -0.183269 0.943067 + outer loop + vertex 0.921799 1.2516 2.62973 + vertex 0.924707 1.25367 2.63099 + vertex 0.92221 1.25566 2.63064 + endloop + endfacet + facet normal -0.22042 -0.106945 0.969525 + outer loop + vertex 0.924707 1.25367 2.63099 + vertex 0.925311 1.25814 2.63162 + vertex 0.92221 1.25566 2.63064 + endloop + endfacet + facet normal -0.156942 -0.117084 0.980643 + outer loop + vertex 0.924707 1.25367 2.63099 + vertex 0.928921 1.25405 2.63171 + vertex 0.925311 1.25814 2.63162 + endloop + endfacet + facet normal -0.133085 -0.0959314 0.986451 + outer loop + vertex 0.928921 1.25405 2.63171 + vertex 0.929701 1.25898 2.6323 + vertex 0.925311 1.25814 2.63162 + endloop + endfacet + facet normal -0.133037 -0.0961716 0.986434 + outer loop + vertex 0.929701 1.25898 2.6323 + vertex 0.928768 1.26308 2.63257 + vertex 0.925311 1.25814 2.63162 + endloop + endfacet + facet normal -0.141478 -0.0901423 0.985829 + outer loop + vertex 0.925311 1.25814 2.63162 + vertex 0.928768 1.26308 2.63257 + vertex 0.923847 1.26392 2.63194 + endloop + endfacet + facet normal -0.142803 -0.0986084 0.984827 + outer loop + vertex 0.928768 1.26308 2.63257 + vertex 0.928635 1.26813 2.63306 + vertex 0.923847 1.26392 2.63194 + endloop + endfacet + facet normal -0.12681 -0.11688 0.985017 + outer loop + vertex 0.923847 1.26392 2.63194 + vertex 0.928635 1.26813 2.63306 + vertex 0.924961 1.26902 2.63269 + endloop + endfacet + facet normal -0.124673 -0.107529 0.986354 + outer loop + vertex 0.928635 1.26813 2.63306 + vertex 0.928707 1.27298 2.6336 + vertex 0.924961 1.26902 2.63269 + endloop + endfacet + facet normal -0.132072 -0.100486 0.986134 + outer loop + vertex 0.924961 1.26902 2.63269 + vertex 0.928707 1.27298 2.6336 + vertex 0.924209 1.27299 2.63299 + endloop + endfacet + facet normal -0.131864 -0.117436 0.984287 + outer loop + vertex 0.928707 1.27298 2.6336 + vertex 0.928222 1.27757 2.63408 + vertex 0.924209 1.27299 2.63299 + endloop + endfacet + facet normal -0.142696 -0.107842 0.983874 + outer loop + vertex 0.924209 1.27299 2.63299 + vertex 0.928222 1.27757 2.63408 + vertex 0.923663 1.2777 2.63343 + endloop + endfacet + facet normal -0.142892 -0.126807 0.981581 + outer loop + vertex 0.928222 1.27757 2.63408 + vertex 0.927087 1.2814 2.63441 + vertex 0.923663 1.2777 2.63343 + endloop + endfacet + facet normal -0.160808 -0.110054 0.980831 + outer loop + vertex 0.923663 1.2777 2.63343 + vertex 0.927087 1.2814 2.63441 + vertex 0.923238 1.28244 2.63389 + endloop + endfacet + facet normal -0.160258 -0.107856 0.981165 + outer loop + vertex 0.927087 1.2814 2.63441 + vertex 0.92764 1.2864 2.63505 + vertex 0.923238 1.28244 2.63389 + endloop + endfacet + facet normal -0.154544 -0.114263 0.981356 + outer loop + vertex 0.923238 1.28244 2.63389 + vertex 0.92764 1.2864 2.63505 + vertex 0.922661 1.28646 2.63427 + endloop + endfacet + facet normal -0.147381 -0.119941 0.98178 + outer loop + vertex 0.927916 1.29094 2.63563 + vertex 0.926252 1.29463 2.63583 + vertex 0.923608 1.29073 2.63495 + endloop + endfacet + facet normal -0.147618 -0.116435 0.982167 + outer loop + vertex 0.927916 1.29094 2.63563 + vertex 0.923608 1.29073 2.63495 + vertex 0.92764 1.2864 2.63505 + endloop + endfacet + facet normal -0.154475 -0.122872 0.980326 + outer loop + vertex 0.92764 1.2864 2.63505 + vertex 0.923608 1.29073 2.63495 + vertex 0.922661 1.28646 2.63427 + endloop + endfacet + facet normal -0.0908337 -0.0949708 0.991327 + outer loop + vertex 0.927916 1.29094 2.63563 + vertex 0.931094 1.29359 2.63617 + vertex 0.926252 1.29463 2.63583 + endloop + endfacet + facet normal -0.157399 -0.113002 0.981048 + outer loop + vertex 0.921925 1.29549 2.63523 + vertex 0.923608 1.29073 2.63495 + vertex 0.926252 1.29463 2.63583 + endloop + endfacet + facet normal -0.160968 -0.133144 0.977938 + outer loop + vertex 0.92456 1.29827 2.63605 + vertex 0.921925 1.29549 2.63523 + vertex 0.926252 1.29463 2.63583 + endloop + endfacet + facet normal -0.0935245 -0.102546 0.990322 + outer loop + vertex 0.926252 1.29463 2.63583 + vertex 0.928978 1.29902 2.63654 + vertex 0.92456 1.29827 2.63605 + endloop + endfacet + facet normal -0.0925335 -0.103167 0.990351 + outer loop + vertex 0.931094 1.29359 2.63617 + vertex 0.928978 1.29902 2.63654 + vertex 0.926252 1.29463 2.63583 + endloop + endfacet + facet normal -0.16723 -0.127138 0.977686 + outer loop + vertex 0.921925 1.29549 2.63523 + vertex 0.92456 1.29827 2.63605 + vertex 0.921224 1.29978 2.63567 + endloop + endfacet + facet normal -0.154877 -0.0985181 0.983009 + outer loop + vertex 0.92456 1.29827 2.63605 + vertex 0.925263 1.30279 2.63661 + vertex 0.921224 1.29978 2.63567 + endloop + endfacet + facet normal -0.0923586 -0.109077 0.989733 + outer loop + vertex 0.92456 1.29827 2.63605 + vertex 0.928978 1.29902 2.63654 + vertex 0.925263 1.30279 2.63661 + endloop + endfacet + facet normal -0.0783917 -0.0953805 0.992349 + outer loop + vertex 0.928978 1.29902 2.63654 + vertex 0.929755 1.30393 2.63707 + vertex 0.925263 1.30279 2.63661 + endloop + endfacet + facet normal -0.077058 -0.100472 0.991951 + outer loop + vertex 0.929755 1.30393 2.63707 + vertex 0.928851 1.30779 2.63739 + vertex 0.925263 1.30279 2.63661 + endloop + endfacet + facet normal -0.116271 0.0349694 0.992602 + outer loop + vertex 0.923486 1.74213 2.63302 + vertex 0.928442 1.74706 2.63343 + vertex 0.923639 1.74721 2.63286 + endloop + endfacet + facet normal -0.117105 0.00971434 0.993072 + outer loop + vertex 0.928442 1.74706 2.63343 + vertex 0.928382 1.752 2.63337 + vertex 0.923639 1.74721 2.63286 + endloop + endfacet + facet normal -0.0848767 -0.0225606 0.996136 + outer loop + vertex 0.923639 1.74721 2.63286 + vertex 0.928382 1.752 2.63337 + vertex 0.923528 1.75222 2.63296 + endloop + endfacet + facet normal -0.0846406 -0.0171396 0.996264 + outer loop + vertex 0.928382 1.752 2.63337 + vertex 0.928313 1.75697 2.63345 + vertex 0.923528 1.75222 2.63296 + endloop + endfacet + facet normal -0.0641853 -0.0378401 0.99722 + outer loop + vertex 0.923528 1.75222 2.63296 + vertex 0.928313 1.75697 2.63345 + vertex 0.923506 1.75721 2.63315 + endloop + endfacet + facet normal -0.12535 0.147656 0.981063 + outer loop + vertex 0.923315 1.76695 2.63256 + vertex 0.928378 1.77218 2.63242 + vertex 0.923207 1.77202 2.63178 + endloop + endfacet + facet normal -0.125233 0.139189 0.982315 + outer loop + vertex 0.928378 1.77218 2.63242 + vertex 0.928521 1.77707 2.63175 + vertex 0.923207 1.77202 2.63178 + endloop + endfacet + facet normal -0.122949 0.136792 0.98294 + outer loop + vertex 0.923207 1.77202 2.63178 + vertex 0.928521 1.77707 2.63175 + vertex 0.924533 1.77711 2.63124 + endloop + endfacet + facet normal -0.278692 0.205562 0.938123 + outer loop + vertex 0.926652 1.78311 2.63074 + vertex 0.922943 1.78173 2.62994 + vertex 0.924872 1.78026 2.63084 + endloop + endfacet + facet normal -0.132304 0.115786 0.984423 + outer loop + vertex 0.924872 1.78026 2.63084 + vertex 0.928497 1.78147 2.63118 + vertex 0.926652 1.78311 2.63074 + endloop + endfacet + facet normal -0.140103 0.140316 0.980144 + outer loop + vertex 0.924872 1.78026 2.63084 + vertex 0.924533 1.77711 2.63124 + vertex 0.928497 1.78147 2.63118 + endloop + endfacet + facet normal -0.123261 0.125071 0.984461 + outer loop + vertex 0.924533 1.77711 2.63124 + vertex 0.928521 1.77707 2.63175 + vertex 0.928497 1.78147 2.63118 + endloop + endfacet + facet normal -0.147961 0.156437 0.976542 + outer loop + vertex 0.926652 1.78311 2.63074 + vertex 0.929413 1.78499 2.63086 + vertex 0.92784 1.78684 2.63033 + endloop + endfacet + facet normal -0.274835 0.193039 0.941914 + outer loop + vertex 0.926652 1.78311 2.63074 + vertex 0.92784 1.78684 2.63033 + vertex 0.922943 1.78173 2.62994 + endloop + endfacet + facet normal -0.238234 0.156707 0.958482 + outer loop + vertex 0.922943 1.78173 2.62994 + vertex 0.92784 1.78684 2.63033 + vertex 0.923233 1.78672 2.6292 + endloop + endfacet + facet normal -0.125685 0.123218 0.984388 + outer loop + vertex 0.929413 1.78499 2.63086 + vertex 0.926652 1.78311 2.63074 + vertex 0.928497 1.78147 2.63118 + endloop + endfacet + facet normal -0.238419 0.140145 0.960997 + outer loop + vertex 0.92784 1.78684 2.63033 + vertex 0.928173 1.79173 2.62969 + vertex 0.923233 1.78672 2.6292 + endloop + endfacet + facet normal -0.223874 0.125277 0.966533 + outer loop + vertex 0.923233 1.78672 2.6292 + vertex 0.928173 1.79173 2.62969 + vertex 0.923625 1.79175 2.62864 + endloop + endfacet + facet normal -0.223559 0.134753 0.965331 + outer loop + vertex 0.928173 1.79173 2.62969 + vertex 0.928356 1.79674 2.62904 + vertex 0.923625 1.79175 2.62864 + endloop + endfacet + facet normal -0.239742 0.150615 0.959082 + outer loop + vertex 0.923625 1.79175 2.62864 + vertex 0.928356 1.79674 2.62904 + vertex 0.923716 1.79669 2.62789 + endloop + endfacet + facet normal -0.239726 0.15116 0.959001 + outer loop + vertex 0.928356 1.79674 2.62904 + vertex 0.928429 1.8018 2.62826 + vertex 0.923716 1.79669 2.62789 + endloop + endfacet + facet normal -0.256828 0.167458 0.951839 + outer loop + vertex 0.923716 1.79669 2.62789 + vertex 0.928429 1.8018 2.62826 + vertex 0.923319 1.80183 2.62688 + endloop + endfacet + facet normal -0.257744 0.147693 0.954859 + outer loop + vertex 0.928429 1.8018 2.62826 + vertex 0.928604 1.80693 2.62751 + vertex 0.923319 1.80183 2.62688 + endloop + endfacet + facet normal -0.226735 0.114008 0.967261 + outer loop + vertex 0.923319 1.80183 2.62688 + vertex 0.928604 1.80693 2.62751 + vertex 0.924487 1.80728 2.62651 + endloop + endfacet + facet normal -0.224853 0.131039 0.965541 + outer loop + vertex 0.928604 1.80693 2.62751 + vertex 0.928777 1.81177 2.6269 + vertex 0.924487 1.80728 2.62651 + endloop + endfacet + facet normal -0.212869 0.119208 0.969782 + outer loop + vertex 0.924487 1.80728 2.62651 + vertex 0.928777 1.81177 2.6269 + vertex 0.925024 1.81165 2.62609 + endloop + endfacet + facet normal -0.429855 0.249009 0.867882 + outer loop + vertex 0.926701 1.81769 2.62557 + vertex 0.923332 1.81644 2.62426 + vertex 0.925095 1.81474 2.62562 + endloop + endfacet + facet normal -0.242865 0.149 0.958549 + outer loop + vertex 0.925095 1.81474 2.62562 + vertex 0.928543 1.81609 2.62629 + vertex 0.926701 1.81769 2.62557 + endloop + endfacet + facet normal -0.243113 0.149717 0.958374 + outer loop + vertex 0.925095 1.81474 2.62562 + vertex 0.925024 1.81165 2.62609 + vertex 0.928543 1.81609 2.62629 + endloop + endfacet + facet normal -0.212893 0.125307 0.969007 + outer loop + vertex 0.925024 1.81165 2.62609 + vertex 0.928777 1.81177 2.6269 + vertex 0.928543 1.81609 2.62629 + endloop + endfacet + facet normal -0.291081 0.234083 0.927619 + outer loop + vertex 0.926701 1.81769 2.62557 + vertex 0.929348 1.8197 2.62589 + vertex 0.927818 1.82159 2.62494 + endloop + endfacet + facet normal -0.433092 0.2641 0.86179 + outer loop + vertex 0.926701 1.81769 2.62557 + vertex 0.927818 1.82159 2.62494 + vertex 0.923332 1.81644 2.62426 + endloop + endfacet + facet normal -0.397794 0.229877 0.88821 + outer loop + vertex 0.923332 1.81644 2.62426 + vertex 0.927818 1.82159 2.62494 + vertex 0.923051 1.82176 2.62276 + endloop + endfacet + facet normal -0.236227 0.156811 0.958962 + outer loop + vertex 0.929348 1.8197 2.62589 + vertex 0.926701 1.81769 2.62557 + vertex 0.928543 1.81609 2.62629 + endloop + endfacet + facet normal -0.401794 0.196774 0.894338 + outer loop + vertex 0.927818 1.82159 2.62494 + vertex 0.928212 1.82666 2.624 + vertex 0.923051 1.82176 2.62276 + endloop + endfacet + facet normal -0.355344 0.140291 0.924148 + outer loop + vertex 0.923051 1.82176 2.62276 + vertex 0.928212 1.82666 2.624 + vertex 0.924207 1.82726 2.62237 + endloop + endfacet + facet normal -0.352093 0.157843 0.92256 + outer loop + vertex 0.928212 1.82666 2.624 + vertex 0.928514 1.83175 2.62324 + vertex 0.924207 1.82726 2.62237 + endloop + endfacet + facet normal -0.340187 0.145163 0.929086 + outer loop + vertex 0.924207 1.82726 2.62237 + vertex 0.928514 1.83175 2.62324 + vertex 0.924622 1.8318 2.62181 + endloop + endfacet + facet normal -0.53572 0.220951 0.814975 + outer loop + vertex 0.925277 1.83892 2.62064 + vertex 0.921985 1.83561 2.61937 + vertex 0.92429 1.83498 2.62106 + endloop + endfacet + facet normal -0.36446 0.188353 0.911971 + outer loop + vertex 0.92429 1.83498 2.62106 + vertex 0.928283 1.83691 2.62225 + vertex 0.925277 1.83892 2.62064 + endloop + endfacet + facet normal -0.360983 0.179148 0.915203 + outer loop + vertex 0.92429 1.83498 2.62106 + vertex 0.924622 1.8318 2.62181 + vertex 0.928283 1.83691 2.62225 + endloop + endfacet + facet normal -0.339082 0.162463 0.926622 + outer loop + vertex 0.924622 1.8318 2.62181 + vertex 0.928514 1.83175 2.62324 + vertex 0.928283 1.83691 2.62225 + endloop + endfacet + facet normal -0.534338 0.219028 0.8164 + outer loop + vertex 0.922335 1.84049 2.61829 + vertex 0.921985 1.83561 2.61937 + vertex 0.925277 1.83892 2.62064 + endloop + endfacet + facet normal -0.544969 0.197025 0.814979 + outer loop + vertex 0.926286 1.84361 2.62018 + vertex 0.922335 1.84049 2.61829 + vertex 0.925277 1.83892 2.62064 + endloop + endfacet + facet normal -0.372394 0.169497 0.912466 + outer loop + vertex 0.925277 1.83892 2.62064 + vertex 0.92932 1.84243 2.62163 + vertex 0.926286 1.84361 2.62018 + endloop + endfacet + facet normal -0.374585 0.172428 0.911018 + outer loop + vertex 0.928283 1.83691 2.62225 + vertex 0.92932 1.84243 2.62163 + vertex 0.925277 1.83892 2.62064 + endloop + endfacet + facet normal -0.545705 0.198463 0.814137 + outer loop + vertex 0.924255 1.8465 2.61811 + vertex 0.922335 1.84049 2.61829 + vertex 0.926286 1.84361 2.62018 + endloop + endfacet + facet normal -0.541248 0.202936 0.816007 + outer loop + vertex 0.927566 1.84736 2.6201 + vertex 0.924255 1.8465 2.61811 + vertex 0.926286 1.84361 2.62018 + endloop + endfacet + facet normal -0.376392 0.148726 0.914445 + outer loop + vertex 0.926286 1.84361 2.62018 + vertex 0.929779 1.84656 2.62114 + vertex 0.927566 1.84736 2.6201 + endloop + endfacet + facet normal -0.379114 0.152527 0.912693 + outer loop + vertex 0.92932 1.84243 2.62163 + vertex 0.929779 1.84656 2.62114 + vertex 0.926286 1.84361 2.62018 + endloop + endfacet + facet normal -0.437616 0.251422 0.863295 + outer loop + vertex 0.927566 1.84736 2.6201 + vertex 0.929908 1.84941 2.62069 + vertex 0.928337 1.85132 2.61933 + endloop + endfacet + facet normal -0.544739 0.259561 0.797426 + outer loop + vertex 0.927566 1.84736 2.6201 + vertex 0.928337 1.85132 2.61933 + vertex 0.924255 1.8465 2.61811 + endloop + endfacet + facet normal -0.514959 0.226946 0.826628 + outer loop + vertex 0.924255 1.8465 2.61811 + vertex 0.928337 1.85132 2.61933 + vertex 0.92443 1.85179 2.61677 + endloop + endfacet + facet normal -0.371702 0.161385 0.914217 + outer loop + vertex 0.929908 1.84941 2.62069 + vertex 0.927566 1.84736 2.6201 + vertex 0.929779 1.84656 2.62114 + endloop + endfacet + facet normal -0.569005 0.188595 0.800416 + outer loop + vertex 0.925556 1.85935 2.61571 + vertex 0.92329 1.85829 2.61435 + vertex 0.923844 1.85592 2.6153 + endloop + endfacet + facet normal -0.511639 0.15471 0.845157 + outer loop + vertex 0.923844 1.85592 2.6153 + vertex 0.928165 1.85671 2.61777 + vertex 0.925556 1.85935 2.61571 + endloop + endfacet + facet normal -0.514383 0.220929 0.828614 + outer loop + vertex 0.923844 1.85592 2.6153 + vertex 0.92443 1.85179 2.61677 + vertex 0.928165 1.85671 2.61777 + endloop + endfacet + facet normal -0.515924 0.222371 0.827269 + outer loop + vertex 0.92443 1.85179 2.61677 + vertex 0.928337 1.85132 2.61933 + vertex 0.928165 1.85671 2.61777 + endloop + endfacet + facet normal -0.5743 0.212463 0.790594 + outer loop + vertex 0.923278 1.86101 2.61361 + vertex 0.92329 1.85829 2.61435 + vertex 0.925556 1.85935 2.61571 + endloop + endfacet + facet normal -0.580838 0.201151 0.788774 + outer loop + vertex 0.926085 1.8635 2.61504 + vertex 0.923278 1.86101 2.61361 + vertex 0.925556 1.85935 2.61571 + endloop + endfacet + facet normal -0.483768 0.198986 0.852275 + outer loop + vertex 0.925556 1.85935 2.61571 + vertex 0.929241 1.86219 2.61714 + vertex 0.926085 1.8635 2.61504 + endloop + endfacet + facet normal -0.480613 0.19333 0.855357 + outer loop + vertex 0.928165 1.85671 2.61777 + vertex 0.929241 1.86219 2.61714 + vertex 0.925556 1.85935 2.61571 + endloop + endfacet + facet normal -0.585514 0.209704 0.78307 + outer loop + vertex 0.923534 1.86505 2.61272 + vertex 0.923278 1.86101 2.61361 + vertex 0.926085 1.8635 2.61504 + endloop + endfacet + facet normal -0.590091 0.200602 0.782018 + outer loop + vertex 0.926085 1.86776 2.61395 + vertex 0.923534 1.86505 2.61272 + vertex 0.926085 1.8635 2.61504 + endloop + endfacet + facet normal -0.503137 0.214726 0.837106 + outer loop + vertex 0.926085 1.8635 2.61504 + vertex 0.929397 1.86689 2.61617 + vertex 0.926085 1.86776 2.61395 + endloop + endfacet + facet normal -0.486181 0.19313 0.852249 + outer loop + vertex 0.929241 1.86219 2.61714 + vertex 0.929397 1.86689 2.61617 + vertex 0.926085 1.8635 2.61504 + endloop + endfacet + facet normal -0.605918 0.213017 0.766477 + outer loop + vertex 0.925663 1.87263 2.6123 + vertex 0.921686 1.8704 2.60978 + vertex 0.923663 1.86854 2.61186 + endloop + endfacet + facet normal -0.598531 0.212944 0.77228 + outer loop + vertex 0.923663 1.86854 2.61186 + vertex 0.923534 1.86505 2.61272 + vertex 0.926085 1.86776 2.61395 + endloop + endfacet + facet normal -0.599724 0.209359 0.772334 + outer loop + vertex 0.925663 1.87263 2.6123 + vertex 0.923663 1.86854 2.61186 + vertex 0.926085 1.86776 2.61395 + endloop + endfacet + facet normal -0.553145 0.223615 0.802513 + outer loop + vertex 0.925663 1.87263 2.6123 + vertex 0.926085 1.86776 2.61395 + vertex 0.9288 1.87088 2.61495 + endloop + endfacet + facet normal -0.587951 0.149945 0.794878 + outer loop + vertex 0.925663 1.87263 2.6123 + vertex 0.9288 1.87088 2.61495 + vertex 0.928441 1.8734 2.61421 + endloop + endfacet + facet normal -0.514201 0.177848 0.839028 + outer loop + vertex 0.9288 1.87088 2.61495 + vertex 0.926085 1.86776 2.61395 + vertex 0.929397 1.86689 2.61617 + endloop + endfacet + facet normal -0.60634 0.214669 0.765682 + outer loop + vertex 0.922198 1.87564 2.60871 + vertex 0.921686 1.8704 2.60978 + vertex 0.925663 1.87263 2.6123 + endloop + endfacet + facet normal -0.600972 0.223037 0.76752 + outer loop + vertex 0.92612 1.87838 2.61099 + vertex 0.922198 1.87564 2.60871 + vertex 0.925663 1.87263 2.6123 + endloop + endfacet + facet normal -0.571333 0.225602 0.789102 + outer loop + vertex 0.925663 1.87263 2.6123 + vertex 0.929223 1.87681 2.61369 + vertex 0.92612 1.87838 2.61099 + endloop + endfacet + facet normal -0.594513 0.254014 0.76291 + outer loop + vertex 0.928441 1.8734 2.61421 + vertex 0.929223 1.87681 2.61369 + vertex 0.925663 1.87263 2.6123 + endloop + endfacet + facet normal -0.601641 0.224884 0.766457 + outer loop + vertex 0.923953 1.8816 2.60834 + vertex 0.922198 1.87564 2.60871 + vertex 0.92612 1.87838 2.61099 + endloop + endfacet + facet normal -0.600914 0.225655 0.7668 + outer loop + vertex 0.926989 1.88238 2.6105 + vertex 0.923953 1.8816 2.60834 + vertex 0.92612 1.87838 2.61099 + endloop + endfacet + facet normal -0.553591 0.219896 0.803233 + outer loop + vertex 0.92612 1.87838 2.61099 + vertex 0.929436 1.88162 2.61239 + vertex 0.926989 1.88238 2.6105 + endloop + endfacet + facet normal -0.565563 0.237964 0.789627 + outer loop + vertex 0.929223 1.87681 2.61369 + vertex 0.929436 1.88162 2.61239 + vertex 0.92612 1.87838 2.61099 + endloop + endfacet + facet normal -0.57018 0.243537 0.784592 + outer loop + vertex 0.926989 1.88238 2.6105 + vertex 0.929157 1.88493 2.61128 + vertex 0.926926 1.88573 2.60941 + endloop + endfacet + facet normal -0.6012 0.236085 0.763428 + outer loop + vertex 0.926989 1.88238 2.6105 + vertex 0.926926 1.88573 2.60941 + vertex 0.923953 1.8816 2.60834 + endloop + endfacet + facet normal -0.598936 0.233818 0.765901 + outer loop + vertex 0.923953 1.8816 2.60834 + vertex 0.926926 1.88573 2.60941 + vertex 0.924345 1.88643 2.60718 + endloop + endfacet + facet normal -0.552566 0.222908 0.803108 + outer loop + vertex 0.929157 1.88493 2.61128 + vertex 0.926989 1.88238 2.6105 + vertex 0.929436 1.88162 2.61239 + endloop + endfacet + facet normal -0.527671 0.190062 0.827913 + outer loop + vertex 0.92527 1.89338 2.60597 + vertex 0.921927 1.89053 2.6045 + vertex 0.924304 1.88967 2.60621 + endloop + endfacet + facet normal -0.593463 0.204 0.778579 + outer loop + vertex 0.924304 1.88967 2.60621 + vertex 0.927343 1.89051 2.6083 + vertex 0.92527 1.89338 2.60597 + endloop + endfacet + facet normal -0.594575 0.223541 0.772341 + outer loop + vertex 0.924304 1.88967 2.60621 + vertex 0.924345 1.88643 2.60718 + vertex 0.927343 1.89051 2.6083 + endloop + endfacet + facet normal -0.600315 0.229466 0.766138 + outer loop + vertex 0.924345 1.88643 2.60718 + vertex 0.926926 1.88573 2.60941 + vertex 0.927343 1.89051 2.6083 + endloop + endfacet + facet normal -0.536026 0.204393 0.819085 + outer loop + vertex 0.922388 1.89502 2.60368 + vertex 0.921927 1.89053 2.6045 + vertex 0.92527 1.89338 2.60597 + endloop + endfacet + facet normal -0.52952 0.217162 0.82003 + outer loop + vertex 0.925953 1.89818 2.60514 + vertex 0.922388 1.89502 2.60368 + vertex 0.92527 1.89338 2.60597 + endloop + endfacet + facet normal -0.57943 0.218264 0.785253 + outer loop + vertex 0.92527 1.89338 2.60597 + vertex 0.92925 1.89645 2.60805 + vertex 0.925953 1.89818 2.60514 + endloop + endfacet + facet normal -0.579747 0.218968 0.784823 + outer loop + vertex 0.927343 1.89051 2.6083 + vertex 0.92925 1.89645 2.60805 + vertex 0.92527 1.89338 2.60597 + endloop + endfacet + facet normal -0.534326 0.225021 0.814777 + outer loop + vertex 0.922779 1.89989 2.60259 + vertex 0.922388 1.89502 2.60368 + vertex 0.925953 1.89818 2.60514 + endloop + endfacet + facet normal -0.524398 0.244648 0.81557 + outer loop + vertex 0.926198 1.90279 2.60391 + vertex 0.922779 1.89989 2.60259 + vertex 0.925953 1.89818 2.60514 + endloop + endfacet + facet normal -0.563797 0.240008 0.790272 + outer loop + vertex 0.925953 1.89818 2.60514 + vertex 0.929444 1.9017 2.60656 + vertex 0.926198 1.90279 2.60391 + endloop + endfacet + facet normal -0.566903 0.244546 0.78665 + outer loop + vertex 0.92925 1.89645 2.60805 + vertex 0.929444 1.9017 2.60656 + vertex 0.925953 1.89818 2.60514 + endloop + endfacet + facet normal -0.468421 0.211329 0.857859 + outer loop + vertex 0.925938 1.90743 2.60234 + vertex 0.921673 1.90571 2.60043 + vertex 0.923656 1.90379 2.60199 + endloop + endfacet + facet normal -0.523826 0.243675 0.816228 + outer loop + vertex 0.923656 1.90379 2.60199 + vertex 0.922779 1.89989 2.60259 + vertex 0.926198 1.90279 2.60391 + endloop + endfacet + facet normal -0.521702 0.248767 0.816052 + outer loop + vertex 0.925938 1.90743 2.60234 + vertex 0.923656 1.90379 2.60199 + vertex 0.926198 1.90279 2.60391 + endloop + endfacet + facet normal -0.544405 0.242997 0.802855 + outer loop + vertex 0.925938 1.90743 2.60234 + vertex 0.926198 1.90279 2.60391 + vertex 0.929003 1.90578 2.60491 + endloop + endfacet + facet normal -0.524682 0.280885 0.803625 + outer loop + vertex 0.925938 1.90743 2.60234 + vertex 0.929003 1.90578 2.60491 + vertex 0.928573 1.90802 2.60385 + endloop + endfacet + facet normal -0.556642 0.259033 0.789336 + outer loop + vertex 0.929003 1.90578 2.60491 + vertex 0.926198 1.90279 2.60391 + vertex 0.929444 1.9017 2.60656 + endloop + endfacet + facet normal -0.473448 0.233308 0.849361 + outer loop + vertex 0.922876 1.9109 2.59968 + vertex 0.921673 1.90571 2.60043 + vertex 0.925938 1.90743 2.60234 + endloop + endfacet + facet normal -0.447942 0.260377 0.855308 + outer loop + vertex 0.926535 1.91158 2.60139 + vertex 0.922876 1.9109 2.59968 + vertex 0.925938 1.90743 2.60234 + endloop + endfacet + facet normal -0.518526 0.261132 0.814212 + outer loop + vertex 0.925938 1.90743 2.60234 + vertex 0.928583 1.91033 2.60309 + vertex 0.926535 1.91158 2.60139 + endloop + endfacet + facet normal -0.524398 0.268032 0.808187 + outer loop + vertex 0.928573 1.90802 2.60385 + vertex 0.928583 1.91033 2.60309 + vertex 0.925938 1.90743 2.60234 + endloop + endfacet + facet normal -0.506825 0.222878 0.832739 + outer loop + vertex 0.926535 1.91158 2.60139 + vertex 0.928651 1.91349 2.60216 + vertex 0.92646 1.91511 2.60039 + endloop + endfacet + facet normal -0.446793 0.232877 0.863796 + outer loop + vertex 0.926535 1.91158 2.60139 + vertex 0.92646 1.91511 2.60039 + vertex 0.922876 1.9109 2.59968 + endloop + endfacet + facet normal -0.524626 0.250362 0.813687 + outer loop + vertex 0.928651 1.91349 2.60216 + vertex 0.926535 1.91158 2.60139 + vertex 0.928583 1.91033 2.60309 + endloop + endfacet + facet normal -0.385386 0.249995 0.888246 + outer loop + vertex 0.926909 1.93255 2.59561 + vertex 0.923054 1.93115 2.59434 + vertex 0.925512 1.9289 2.59604 + endloop + endfacet + facet normal -0.451566 0.270871 0.850128 + outer loop + vertex 0.925512 1.9289 2.59604 + vertex 0.929214 1.93162 2.59714 + vertex 0.926909 1.93255 2.59561 + endloop + endfacet + facet normal -0.431144 0.236002 0.870872 + outer loop + vertex 0.926909 1.93255 2.59561 + vertex 0.929463 1.93497 2.59622 + vertex 0.927009 1.93579 2.59479 + endloop + endfacet + facet normal -0.38298 0.239935 0.892052 + outer loop + vertex 0.926909 1.93255 2.59561 + vertex 0.927009 1.93579 2.59479 + vertex 0.923054 1.93115 2.59434 + endloop + endfacet + facet normal -0.372433 0.230271 0.899037 + outer loop + vertex 0.923054 1.93115 2.59434 + vertex 0.927009 1.93579 2.59479 + vertex 0.923363 1.93624 2.59316 + endloop + endfacet + facet normal -0.454056 0.265389 0.85053 + outer loop + vertex 0.929463 1.93497 2.59622 + vertex 0.926909 1.93255 2.59561 + vertex 0.929214 1.93162 2.59714 + endloop + endfacet + facet normal -0.372881 0.228038 0.899421 + outer loop + vertex 0.927009 1.93579 2.59479 + vertex 0.928164 1.94091 2.59397 + vertex 0.923363 1.93624 2.59316 + endloop + endfacet + facet normal -0.372244 0.227306 0.89987 + outer loop + vertex 0.923363 1.93624 2.59316 + vertex 0.928164 1.94091 2.59397 + vertex 0.923539 1.94114 2.59199 + endloop + endfacet + facet normal -0.389562 0.268244 0.881071 + outer loop + vertex 0.925661 1.94883 2.59071 + vertex 0.921657 1.94591 2.58983 + vertex 0.924055 1.94503 2.59116 + endloop + endfacet + facet normal -0.379298 0.264557 0.886647 + outer loop + vertex 0.924055 1.94503 2.59116 + vertex 0.928079 1.94635 2.59248 + vertex 0.925661 1.94883 2.59071 + endloop + endfacet + facet normal -0.374815 0.242632 0.894787 + outer loop + vertex 0.924055 1.94503 2.59116 + vertex 0.923539 1.94114 2.59199 + vertex 0.928079 1.94635 2.59248 + endloop + endfacet + facet normal -0.370678 0.238762 0.897547 + outer loop + vertex 0.923539 1.94114 2.59199 + vertex 0.928164 1.94091 2.59397 + vertex 0.928079 1.94635 2.59248 + endloop + endfacet + facet normal -0.39079 0.270287 0.879902 + outer loop + vertex 0.923288 1.95116 2.58894 + vertex 0.921657 1.94591 2.58983 + vertex 0.925661 1.94883 2.59071 + endloop + endfacet + facet normal -0.388241 0.27308 0.880168 + outer loop + vertex 0.927292 1.95263 2.59025 + vertex 0.923288 1.95116 2.58894 + vertex 0.925661 1.94883 2.59071 + endloop + endfacet + facet normal -0.398797 0.276895 0.874237 + outer loop + vertex 0.925661 1.94883 2.59071 + vertex 0.929631 1.95162 2.59164 + vertex 0.927292 1.95263 2.59025 + endloop + endfacet + facet normal -0.387034 0.256351 0.885714 + outer loop + vertex 0.928079 1.94635 2.59248 + vertex 0.929631 1.95162 2.59164 + vertex 0.925661 1.94883 2.59071 + endloop + endfacet + facet normal -0.393353 0.271027 0.878531 + outer loop + vertex 0.927292 1.95263 2.59025 + vertex 0.92996 1.95488 2.59075 + vertex 0.927883 1.95646 2.58933 + endloop + endfacet + facet normal -0.387708 0.270774 0.881115 + outer loop + vertex 0.927292 1.95263 2.59025 + vertex 0.927883 1.95646 2.58933 + vertex 0.923288 1.95116 2.58894 + endloop + endfacet + facet normal -0.383208 0.266629 0.884342 + outer loop + vertex 0.923288 1.95116 2.58894 + vertex 0.927883 1.95646 2.58933 + vertex 0.923346 1.95624 2.58743 + endloop + endfacet + facet normal -0.398314 0.277886 0.874143 + outer loop + vertex 0.92996 1.95488 2.59075 + vertex 0.927292 1.95263 2.59025 + vertex 0.929631 1.95162 2.59164 + endloop + endfacet + facet normal -0.416214 0.281351 0.864643 + outer loop + vertex 0.925475 1.96383 2.58605 + vertex 0.921565 1.96085 2.58514 + vertex 0.923934 1.9601 2.58653 + endloop + endfacet + facet normal -0.385234 0.270801 0.882191 + outer loop + vertex 0.923934 1.9601 2.58653 + vertex 0.927905 1.96154 2.58782 + vertex 0.925475 1.96383 2.58605 + endloop + endfacet + facet normal -0.384117 0.265953 0.884151 + outer loop + vertex 0.923934 1.9601 2.58653 + vertex 0.923346 1.95624 2.58743 + vertex 0.927905 1.96154 2.58782 + endloop + endfacet + facet normal -0.383302 0.265209 0.884728 + outer loop + vertex 0.923346 1.95624 2.58743 + vertex 0.927883 1.95646 2.58933 + vertex 0.927905 1.96154 2.58782 + endloop + endfacet + facet normal -0.414151 0.278021 0.866708 + outer loop + vertex 0.92294 1.96593 2.58417 + vertex 0.921565 1.96085 2.58514 + vertex 0.925475 1.96383 2.58605 + endloop + endfacet + facet normal -0.417114 0.274246 0.86649 + outer loop + vertex 0.926868 1.9675 2.58556 + vertex 0.92294 1.96593 2.58417 + vertex 0.925475 1.96383 2.58605 + endloop + endfacet + facet normal -0.391546 0.266443 0.880738 + outer loop + vertex 0.925475 1.96383 2.58605 + vertex 0.929429 1.96677 2.58692 + vertex 0.926868 1.9675 2.58556 + endloop + endfacet + facet normal -0.390536 0.264805 0.88168 + outer loop + vertex 0.927905 1.96154 2.58782 + vertex 0.929429 1.96677 2.58692 + vertex 0.925475 1.96383 2.58605 + endloop + endfacet + facet normal -0.399078 0.271169 0.875902 + outer loop + vertex 0.926868 1.9675 2.58556 + vertex 0.929488 1.97004 2.58597 + vertex 0.926843 1.97072 2.58456 + endloop + endfacet + facet normal -0.415779 0.268825 0.868827 + outer loop + vertex 0.926868 1.9675 2.58556 + vertex 0.926843 1.97072 2.58456 + vertex 0.92294 1.96593 2.58417 + endloop + endfacet + facet normal -0.429414 0.28078 0.858351 + outer loop + vertex 0.92294 1.96593 2.58417 + vertex 0.926843 1.97072 2.58456 + vertex 0.922933 1.97105 2.58249 + endloop + endfacet + facet normal -0.392564 0.263616 0.881136 + outer loop + vertex 0.929488 1.97004 2.58597 + vertex 0.926868 1.9675 2.58556 + vertex 0.929429 1.96677 2.58692 + endloop + endfacet + facet normal -0.495425 0.317311 0.808621 + outer loop + vertex 0.925336 1.97854 2.58122 + vertex 0.921838 1.97613 2.58002 + vertex 0.9238 1.97489 2.58171 + endloop + endfacet + facet normal -0.427743 0.294991 0.85441 + outer loop + vertex 0.9238 1.97489 2.58171 + vertex 0.928016 1.97611 2.5834 + vertex 0.925336 1.97854 2.58122 + endloop + endfacet + facet normal -0.424773 0.272214 0.863405 + outer loop + vertex 0.9238 1.97489 2.58171 + vertex 0.922933 1.97105 2.58249 + vertex 0.928016 1.97611 2.5834 + endloop + endfacet + facet normal -0.429934 0.278197 0.858931 + outer loop + vertex 0.922933 1.97105 2.58249 + vertex 0.926843 1.97072 2.58456 + vertex 0.928016 1.97611 2.5834 + endloop + endfacet + facet normal -0.50443 0.337243 0.79487 + outer loop + vertex 0.922797 1.98098 2.57857 + vertex 0.921838 1.97613 2.58002 + vertex 0.925336 1.97854 2.58122 + endloop + endfacet + facet normal -0.528385 0.308221 0.791081 + outer loop + vertex 0.926674 1.98217 2.5807 + vertex 0.922797 1.98098 2.57857 + vertex 0.925336 1.97854 2.58122 + endloop + endfacet + facet normal -0.444599 0.285575 0.848987 + outer loop + vertex 0.925336 1.97854 2.58122 + vertex 0.929243 1.98149 2.58227 + vertex 0.926674 1.98217 2.5807 + endloop + endfacet + facet normal -0.440902 0.279235 0.853014 + outer loop + vertex 0.928016 1.97611 2.5834 + vertex 0.929243 1.98149 2.58227 + vertex 0.925336 1.97854 2.58122 + endloop + endfacet + facet normal -0.468866 0.302798 0.829746 + outer loop + vertex 0.926674 1.98217 2.5807 + vertex 0.929323 1.98473 2.58126 + vertex 0.926866 1.98549 2.57959 + endloop + endfacet + facet normal -0.527461 0.295181 0.796651 + outer loop + vertex 0.926674 1.98217 2.5807 + vertex 0.926866 1.98549 2.57959 + vertex 0.922797 1.98098 2.57857 + endloop + endfacet + facet normal -0.54351 0.313757 0.778559 + outer loop + vertex 0.922797 1.98098 2.57857 + vertex 0.926866 1.98549 2.57959 + vertex 0.923803 1.98633 2.57712 + endloop + endfacet + facet normal -0.447776 0.276569 0.850298 + outer loop + vertex 0.929323 1.98473 2.58126 + vertex 0.926674 1.98217 2.5807 + vertex 0.929243 1.98149 2.58227 + endloop + endfacet + facet normal -0.62156 0.29818 0.724398 + outer loop + vertex 0.925603 1.99376 2.57553 + vertex 0.923381 1.99289 2.57398 + vertex 0.923748 1.9905 2.57527 + endloop + endfacet + facet normal -0.567788 0.263297 0.77993 + outer loop + vertex 0.923748 1.9905 2.57527 + vertex 0.928098 1.99101 2.57827 + vertex 0.925603 1.99376 2.57553 + endloop + endfacet + facet normal -0.561491 0.328095 0.759659 + outer loop + vertex 0.923748 1.9905 2.57527 + vertex 0.923803 1.98633 2.57712 + vertex 0.928098 1.99101 2.57827 + endloop + endfacet + facet normal -0.545466 0.308611 0.779248 + outer loop + vertex 0.923803 1.98633 2.57712 + vertex 0.926866 1.98549 2.57959 + vertex 0.928098 1.99101 2.57827 + endloop + endfacet + facet normal -0.623294 0.330552 0.708689 + outer loop + vertex 0.923597 1.99541 2.57299 + vertex 0.923381 1.99289 2.57398 + vertex 0.925603 1.99376 2.57553 + endloop + endfacet + facet normal -0.637384 0.309092 0.705836 + outer loop + vertex 0.926139 1.99758 2.57434 + vertex 0.923597 1.99541 2.57299 + vertex 0.925603 1.99376 2.57553 + endloop + endfacet + facet normal -0.554917 0.317225 0.769048 + outer loop + vertex 0.925603 1.99376 2.57553 + vertex 0.92907 1.99646 2.57691 + vertex 0.926139 1.99758 2.57434 + endloop + endfacet + facet normal -0.543062 0.292807 0.786986 + outer loop + vertex 0.928098 1.99101 2.57827 + vertex 0.92907 1.99646 2.57691 + vertex 0.925603 1.99376 2.57553 + endloop + endfacet + facet normal -0.68834 0.36409 0.627396 + outer loop + vertex 0.92603 2.00198 2.57211 + vertex 0.923248 2.00112 2.56956 + vertex 0.924109 1.99866 2.57193 + endloop + endfacet + facet normal -0.644513 0.326428 0.69141 + outer loop + vertex 0.924109 1.99866 2.57193 + vertex 0.923597 1.99541 2.57299 + vertex 0.926139 1.99758 2.57434 + endloop + endfacet + facet normal -0.640974 0.3332 0.691469 + outer loop + vertex 0.92603 2.00198 2.57211 + vertex 0.924109 1.99866 2.57193 + vertex 0.926139 1.99758 2.57434 + endloop + endfacet + facet normal -0.600164 0.348571 0.719932 + outer loop + vertex 0.92603 2.00198 2.57211 + vertex 0.926139 1.99758 2.57434 + vertex 0.92884 2.00034 2.57525 + endloop + endfacet + facet normal -0.647656 0.259993 0.716202 + outer loop + vertex 0.92603 2.00198 2.57211 + vertex 0.92884 2.00034 2.57525 + vertex 0.928413 2.00255 2.57406 + endloop + endfacet + facet normal -0.564122 0.296612 0.770577 + outer loop + vertex 0.92884 2.00034 2.57525 + vertex 0.926139 1.99758 2.57434 + vertex 0.92907 1.99646 2.57691 + endloop + endfacet + facet normal -0.689154 0.356521 0.63084 + outer loop + vertex 0.923668 2.00477 2.56796 + vertex 0.923248 2.00112 2.56956 + vertex 0.92603 2.00198 2.57211 + endloop + endfacet + facet normal -0.712042 0.324754 0.62252 + outer loop + vertex 0.925996 2.00692 2.5695 + vertex 0.923668 2.00477 2.56796 + vertex 0.92603 2.00198 2.57211 + endloop + endfacet + facet normal -0.658245 0.348752 0.667147 + outer loop + vertex 0.92603 2.00198 2.57211 + vertex 0.928355 2.00511 2.57277 + vertex 0.925996 2.00692 2.5695 + endloop + endfacet + facet normal -0.643145 0.33277 0.689659 + outer loop + vertex 0.928413 2.00255 2.57406 + vertex 0.928355 2.00511 2.57277 + vertex 0.92603 2.00198 2.57211 + endloop + endfacet + facet normal -0.741816 0.350737 0.571571 + outer loop + vertex 0.925848 2.01246 2.56623 + vertex 0.923188 2.011 2.56367 + vertex 0.924116 2.00855 2.56638 + endloop + endfacet + facet normal -0.716774 0.339592 0.609026 + outer loop + vertex 0.924116 2.00855 2.56638 + vertex 0.923668 2.00477 2.56796 + vertex 0.925996 2.00692 2.5695 + endloop + endfacet + facet normal -0.71605 0.340784 0.609211 + outer loop + vertex 0.925848 2.01246 2.56623 + vertex 0.924116 2.00855 2.56638 + vertex 0.925996 2.00692 2.5695 + endloop + endfacet + facet normal -0.680045 0.35938 0.63905 + outer loop + vertex 0.925848 2.01246 2.56623 + vertex 0.925996 2.00692 2.5695 + vertex 0.92838 2.00925 2.57072 + endloop + endfacet + facet normal -0.720212 0.305163 0.623033 + outer loop + vertex 0.925848 2.01246 2.56623 + vertex 0.92838 2.00925 2.57072 + vertex 0.92839 2.01212 2.56933 + endloop + endfacet + facet normal -0.667943 0.333125 0.665493 + outer loop + vertex 0.92838 2.00925 2.57072 + vertex 0.925996 2.00692 2.5695 + vertex 0.928355 2.00511 2.57277 + endloop + endfacet + facet normal -0.760011 0.338094 0.555046 + outer loop + vertex 0.924642 2.01751 2.56169 + vertex 0.922938 2.0175 2.55936 + vertex 0.923041 2.01463 2.56125 + endloop + endfacet + facet normal -0.741815 0.35079 0.571539 + outer loop + vertex 0.923041 2.01463 2.56125 + vertex 0.923188 2.011 2.56367 + vertex 0.925848 2.01246 2.56623 + endloop + endfacet + facet normal -0.752349 0.331705 0.569159 + outer loop + vertex 0.923041 2.01463 2.56125 + vertex 0.925848 2.01246 2.56623 + vertex 0.924642 2.01751 2.56169 + endloop + endfacet + facet normal -0.756735 0.327576 0.565726 + outer loop + vertex 0.924642 2.01751 2.56169 + vertex 0.925848 2.01246 2.56623 + vertex 0.926976 2.01778 2.56465 + endloop + endfacet + facet normal -0.719206 0.332709 0.609957 + outer loop + vertex 0.925848 2.01246 2.56623 + vertex 0.928643 2.01497 2.56815 + vertex 0.926976 2.01778 2.56465 + endloop + endfacet + facet normal -0.715529 0.320255 0.62085 + outer loop + vertex 0.92839 2.01212 2.56933 + vertex 0.928643 2.01497 2.56815 + vertex 0.925848 2.01246 2.56623 + endloop + endfacet + facet normal -0.755777 0.352467 0.551876 + outer loop + vertex 0.923323 2.02027 2.55812 + vertex 0.922938 2.0175 2.55936 + vertex 0.924642 2.01751 2.56169 + endloop + endfacet + facet normal -0.757934 0.349803 0.550612 + outer loop + vertex 0.925969 2.02255 2.56031 + vertex 0.923323 2.02027 2.55812 + vertex 0.924642 2.01751 2.56169 + endloop + endfacet + facet normal -0.734089 0.335687 0.590278 + outer loop + vertex 0.928247 2.02104 2.56438 + vertex 0.926976 2.01778 2.56465 + vertex 0.929061 2.01849 2.56684 + endloop + endfacet + facet normal -0.759738 0.342573 0.552668 + outer loop + vertex 0.928247 2.02104 2.56438 + vertex 0.925969 2.02255 2.56031 + vertex 0.926976 2.01778 2.56465 + endloop + endfacet + facet normal -0.75125 0.350417 0.559313 + outer loop + vertex 0.925969 2.02255 2.56031 + vertex 0.924642 2.01751 2.56169 + vertex 0.926976 2.01778 2.56465 + endloop + endfacet + facet normal -0.736549 0.310914 0.600689 + outer loop + vertex 0.929061 2.01849 2.56684 + vertex 0.926976 2.01778 2.56465 + vertex 0.928643 2.01497 2.56815 + endloop + endfacet + facet normal -0.757702 0.365452 0.540677 + outer loop + vertex 0.924878 2.0277 2.55532 + vertex 0.922835 2.02605 2.55358 + vertex 0.923777 2.02382 2.5564 + endloop + endfacet + facet normal -0.759353 0.359305 0.542478 + outer loop + vertex 0.923777 2.02382 2.5564 + vertex 0.923323 2.02027 2.55812 + vertex 0.925969 2.02255 2.56031 + endloop + endfacet + facet normal -0.756161 0.365589 0.542738 + outer loop + vertex 0.923777 2.02382 2.5564 + vertex 0.925969 2.02255 2.56031 + vertex 0.924878 2.0277 2.55532 + endloop + endfacet + facet normal -0.766545 0.355633 0.534727 + outer loop + vertex 0.924878 2.0277 2.55532 + vertex 0.925969 2.02255 2.56031 + vertex 0.927405 2.02773 2.55892 + endloop + endfacet + facet normal -0.757058 0.356446 0.547549 + outer loop + vertex 0.925969 2.02255 2.56031 + vertex 0.928759 2.02472 2.56276 + vertex 0.927405 2.02773 2.55892 + endloop + endfacet + facet normal -0.756343 0.349155 0.553206 + outer loop + vertex 0.928247 2.02104 2.56438 + vertex 0.928759 2.02472 2.56276 + vertex 0.925969 2.02255 2.56031 + endloop + endfacet + facet normal -0.767394 0.362487 0.528875 + outer loop + vertex 0.92445 2.03234 2.55158 + vertex 0.922886 2.03233 2.54932 + vertex 0.922806 2.02954 2.55112 + endloop + endfacet + facet normal -0.75828 0.371077 0.536016 + outer loop + vertex 0.922806 2.02954 2.55112 + vertex 0.922835 2.02605 2.55358 + vertex 0.924878 2.0277 2.55532 + endloop + endfacet + facet normal -0.76474 0.360028 0.534371 + outer loop + vertex 0.922806 2.02954 2.55112 + vertex 0.924878 2.0277 2.55532 + vertex 0.92445 2.03234 2.55158 + endloop + endfacet + facet normal -0.764483 0.360235 0.534599 + outer loop + vertex 0.92445 2.03234 2.55158 + vertex 0.924878 2.0277 2.55532 + vertex 0.926896 2.03221 2.55517 + endloop + endfacet + facet normal -0.763354 0.357754 0.537869 + outer loop + vertex 0.928703 2.03083 2.55871 + vertex 0.927405 2.02773 2.55892 + vertex 0.929348 2.02844 2.56121 + endloop + endfacet + facet normal -0.76695 0.358857 0.531987 + outer loop + vertex 0.928703 2.03083 2.55871 + vertex 0.926896 2.03221 2.55517 + vertex 0.927405 2.02773 2.55892 + endloop + endfacet + facet normal -0.765051 0.360456 0.533637 + outer loop + vertex 0.926896 2.03221 2.55517 + vertex 0.924878 2.0277 2.55532 + vertex 0.927405 2.02773 2.55892 + endloop + endfacet + facet normal -0.765044 0.346685 0.542695 + outer loop + vertex 0.929348 2.02844 2.56121 + vertex 0.927405 2.02773 2.55892 + vertex 0.928759 2.02472 2.56276 + endloop + endfacet + facet normal -0.771814 0.348193 0.532039 + outer loop + vertex 0.923369 2.03519 2.54815 + vertex 0.922886 2.03233 2.54932 + vertex 0.92445 2.03234 2.55158 + endloop + endfacet + facet normal -0.771599 0.348448 0.532183 + outer loop + vertex 0.925922 2.03745 2.55037 + vertex 0.923369 2.03519 2.54815 + vertex 0.92445 2.03234 2.55158 + endloop + endfacet + facet normal -0.764714 0.35878 0.535247 + outer loop + vertex 0.928037 2.03593 2.55431 + vertex 0.926896 2.03221 2.55517 + vertex 0.928913 2.03357 2.55714 + endloop + endfacet + facet normal -0.757172 0.358906 0.545782 + outer loop + vertex 0.928037 2.03593 2.55431 + vertex 0.925922 2.03745 2.55037 + vertex 0.926896 2.03221 2.55517 + endloop + endfacet + facet normal -0.768333 0.348597 0.53679 + outer loop + vertex 0.925922 2.03745 2.55037 + vertex 0.92445 2.03234 2.55158 + vertex 0.926896 2.03221 2.55517 + endloop + endfacet + facet normal -0.764743 0.362879 0.532435 + outer loop + vertex 0.928913 2.03357 2.55714 + vertex 0.926896 2.03221 2.55517 + vertex 0.928703 2.03083 2.55871 + endloop + endfacet + facet normal -0.788365 0.344971 0.509388 + outer loop + vertex 0.925026 2.0428 2.5457 + vertex 0.923311 2.04121 2.54413 + vertex 0.923911 2.0389 2.54662 + endloop + endfacet + facet normal -0.769883 0.336677 0.542152 + outer loop + vertex 0.923911 2.0389 2.54662 + vertex 0.923369 2.03519 2.54815 + vertex 0.925922 2.03745 2.55037 + endloop + endfacet + facet normal -0.76491 0.346239 0.543168 + outer loop + vertex 0.923911 2.0389 2.54662 + vertex 0.925922 2.03745 2.55037 + vertex 0.925026 2.0428 2.5457 + endloop + endfacet + facet normal -0.761396 0.349376 0.546088 + outer loop + vertex 0.925026 2.0428 2.5457 + vertex 0.925922 2.03745 2.55037 + vertex 0.927356 2.04279 2.54896 + endloop + endfacet + facet normal -0.758941 0.349585 0.549362 + outer loop + vertex 0.925922 2.03745 2.55037 + vertex 0.928579 2.03964 2.55265 + vertex 0.927356 2.04279 2.54896 + endloop + endfacet + facet normal -0.759551 0.354499 0.545356 + outer loop + vertex 0.928037 2.03593 2.55431 + vertex 0.928579 2.03964 2.55265 + vertex 0.925922 2.03745 2.55037 + endloop + endfacet + facet normal -0.837174 0.384312 0.389158 + outer loop + vertex 0.924758 2.04779 2.54136 + vertex 0.92327 2.046 2.53993 + vertex 0.923596 2.04406 2.54255 + endloop + endfacet + facet normal -0.789643 0.35553 0.500063 + outer loop + vertex 0.923596 2.04406 2.54255 + vertex 0.923311 2.04121 2.54413 + vertex 0.925026 2.0428 2.5457 + endloop + endfacet + facet normal -0.764681 0.398987 0.506036 + outer loop + vertex 0.923596 2.04406 2.54255 + vertex 0.925026 2.0428 2.5457 + vertex 0.924758 2.04779 2.54136 + endloop + endfacet + facet normal -0.799492 0.369138 0.473867 + outer loop + vertex 0.924758 2.04779 2.54136 + vertex 0.925026 2.0428 2.5457 + vertex 0.926958 2.04742 2.54536 + endloop + endfacet + facet normal -0.755541 0.351229 0.552988 + outer loop + vertex 0.928652 2.04597 2.54871 + vertex 0.927356 2.04279 2.54896 + vertex 0.929308 2.04345 2.5512 + endloop + endfacet + facet normal -0.763738 0.353562 0.54009 + outer loop + vertex 0.928652 2.04597 2.54871 + vertex 0.926958 2.04742 2.54536 + vertex 0.927356 2.04279 2.54896 + endloop + endfacet + facet normal -0.758949 0.357295 0.544368 + outer loop + vertex 0.926958 2.04742 2.54536 + vertex 0.925026 2.0428 2.5457 + vertex 0.927356 2.04279 2.54896 + endloop + endfacet + facet normal -0.755123 0.35395 0.551823 + outer loop + vertex 0.929308 2.04345 2.5512 + vertex 0.927356 2.04279 2.54896 + vertex 0.928579 2.03964 2.55265 + endloop + endfacet + facet normal -0.889078 0.375992 0.261094 + outer loop + vertex 0.925173 2.05299 2.53667 + vertex 0.923813 2.05096 2.53496 + vertex 0.923753 2.04883 2.53782 + endloop + endfacet + facet normal -0.838679 0.410293 0.358157 + outer loop + vertex 0.923753 2.04883 2.53782 + vertex 0.92327 2.046 2.53993 + vertex 0.924758 2.04779 2.54136 + endloop + endfacet + facet normal -0.850178 0.388714 0.355104 + outer loop + vertex 0.923753 2.04883 2.53782 + vertex 0.924758 2.04779 2.54136 + vertex 0.925173 2.05299 2.53667 + endloop + endfacet + facet normal -0.859637 0.378592 0.343062 + outer loop + vertex 0.925173 2.05299 2.53667 + vertex 0.924758 2.04779 2.54136 + vertex 0.926696 2.05263 2.54088 + endloop + endfacet + facet normal -0.772691 0.346557 0.531834 + outer loop + vertex 0.928093 2.05111 2.5446 + vertex 0.926958 2.04742 2.54536 + vertex 0.92885 2.04877 2.54723 + endloop + endfacet + facet normal -0.82382 0.34535 0.449504 + outer loop + vertex 0.928093 2.05111 2.5446 + vertex 0.926696 2.05263 2.54088 + vertex 0.926958 2.04742 2.54536 + endloop + endfacet + facet normal -0.800066 0.367665 0.474044 + outer loop + vertex 0.926696 2.05263 2.54088 + vertex 0.924758 2.04779 2.54136 + vertex 0.926958 2.04742 2.54536 + endloop + endfacet + facet normal -0.772392 0.337999 0.537742 + outer loop + vertex 0.92885 2.04877 2.54723 + vertex 0.926958 2.04742 2.54536 + vertex 0.928652 2.04597 2.54871 + endloop + endfacet + facet normal -0.866531 0.192838 0.460367 + outer loop + vertex 0.925 2.05619 2.535 + vertex 0.923813 2.05096 2.53496 + vertex 0.925173 2.05299 2.53667 + endloop + endfacet + facet normal -0.51847 0.372735 0.769583 + outer loop + vertex 0.925 2.05619 2.535 + vertex 0.925173 2.05299 2.53667 + vertex 0.927739 2.06 2.535 + endloop + endfacet + facet normal -0.928384 0.360876 0.0887258 + outer loop + vertex 0.927739 2.06 2.535 + vertex 0.925173 2.05299 2.53667 + vertex 0.92681 2.05732 2.5362 + endloop + endfacet + facet normal -0.865279 0.364719 0.343906 + outer loop + vertex 0.925173 2.05299 2.53667 + vertex 0.926696 2.05263 2.54088 + vertex 0.92681 2.05732 2.5362 + endloop + endfacet + facet normal -0.912076 0.300728 0.278712 + outer loop + vertex 0.92681 2.05732 2.5362 + vertex 0.926696 2.05263 2.54088 + vertex 0.927838 2.05745 2.53942 + endloop + endfacet + facet normal -0.83342 0.33169 0.442032 + outer loop + vertex 0.926696 2.05263 2.54088 + vertex 0.928661 2.05474 2.543 + vertex 0.927838 2.05745 2.53942 + endloop + endfacet + facet normal -0.833055 0.3276 0.445756 + outer loop + vertex 0.928093 2.05111 2.5446 + vertex 0.928661 2.05474 2.543 + vertex 0.926696 2.05263 2.54088 + endloop + endfacet + facet normal -0.941358 0.304049 0.146285 + outer loop + vertex 0.926962 2.06 2.53 + vertex 0.927739 2.06 2.535 + vertex 0.928577 2.065 2.53 + endloop + endfacet + facet normal 0.781365 -0.501878 -0.370927 + outer loop + vertex 0.928577 2.065 2.53 + vertex 0.927739 2.06 2.535 + vertex 0.927755 2.06215 2.53212 + endloop + endfacet + facet normal 0.84211 -0.434136 -0.319962 + outer loop + vertex 0.927739 2.06 2.535 + vertex 0.92681 2.05732 2.5362 + vertex 0.927755 2.06215 2.53212 + endloop + endfacet + facet normal -0.941034 0.305788 0.144738 + outer loop + vertex 0.927755 2.06215 2.53212 + vertex 0.92681 2.05732 2.5362 + vertex 0.927951 2.06088 2.53609 + endloop + endfacet + facet normal -0.83486 0.33019 0.440434 + outer loop + vertex 0.928887 2.0606 2.53904 + vertex 0.927838 2.05745 2.53942 + vertex 0.929336 2.05844 2.54151 + endloop + endfacet + facet normal -0.889236 0.333228 0.313397 + outer loop + vertex 0.928887 2.0606 2.53904 + vertex 0.927951 2.06088 2.53609 + vertex 0.927838 2.05745 2.53942 + endloop + endfacet + facet normal -0.912169 0.300405 0.278756 + outer loop + vertex 0.927951 2.06088 2.53609 + vertex 0.92681 2.05732 2.5362 + vertex 0.927838 2.05745 2.53942 + endloop + endfacet + facet normal -0.834926 0.32957 0.440774 + outer loop + vertex 0.929336 2.05844 2.54151 + vertex 0.927838 2.05745 2.53942 + vertex 0.928661 2.05474 2.543 + endloop + endfacet + facet normal -0.284442 0.0802673 -0.955327 + outer loop + vertex 0.93 2.065 2.52858 + vertex 0.928765 2.06566 2.529 + vertex 0.93 2.07 2.529 + endloop + endfacet + facet normal -0.533115 -0.656035 -0.534234 + outer loop + vertex 0.928577 2.065 2.53 + vertex 0.928765 2.06566 2.529 + vertex 0.93 2.065 2.52858 + endloop + endfacet + facet normal -0.93687 0.318188 0.14502 + outer loop + vertex 0.928814 2.06606 2.53039 + vertex 0.927755 2.06215 2.53212 + vertex 0.928817 2.06468 2.53345 + endloop + endfacet + facet normal -0.968489 0.246357 -0.0365651 + outer loop + vertex 0.928814 2.06606 2.53039 + vertex 0.928765 2.06566 2.529 + vertex 0.927755 2.06215 2.53212 + endloop + endfacet + facet normal 0.959764 -0.280765 -0.00496087 + outer loop + vertex 0.928765 2.06566 2.529 + vertex 0.928577 2.065 2.53 + vertex 0.927755 2.06215 2.53212 + endloop + endfacet + facet normal -0.888317 0.381021 0.256351 + outer loop + vertex 0.928817 2.06468 2.53345 + vertex 0.927951 2.06088 2.53609 + vertex 0.929251 2.06328 2.53702 + endloop + endfacet + facet normal -0.936926 0.316639 0.148016 + outer loop + vertex 0.927755 2.06215 2.53212 + vertex 0.927951 2.06088 2.53609 + vertex 0.928817 2.06468 2.53345 + endloop + endfacet + facet normal -0.880884 0.355238 0.312809 + outer loop + vertex 0.929251 2.06328 2.53702 + vertex 0.927951 2.06088 2.53609 + vertex 0.928887 2.0606 2.53904 + endloop + endfacet + facet normal -0.907066 0.257904 -0.332742 + outer loop + vertex 0.93 2.07 2.529 + vertex 0.928765 2.06566 2.529 + vertex 0.93 2.07129 2.53 + endloop + endfacet + facet normal -0.97531 0.219003 -0.02843 + outer loop + vertex 0.93 2.07129 2.53 + vertex 0.928765 2.06566 2.529 + vertex 0.928814 2.06606 2.53039 + endloop + endfacet + facet normal 0.35827 -0.847653 -0.391315 + outer loop + vertex 0.925169 2.10774 2.51071 + vertex 0.922423 2.10618 2.51158 + vertex 0.922512 2.1076 2.50859 + endloop + endfacet + facet normal 0.332915 -0.832156 -0.44349 + outer loop + vertex 0.926198 2.10652 2.51379 + vertex 0.922423 2.10618 2.51158 + vertex 0.925169 2.10774 2.51071 + endloop + endfacet + facet normal 0.159869 -0.979264 -0.124432 + outer loop + vertex 0.923527 2.10577 2.51621 + vertex 0.922423 2.10618 2.51158 + vertex 0.926198 2.10652 2.51379 + endloop + endfacet + facet normal 0.0551689 -0.969958 -0.236936 + outer loop + vertex 0.927546 2.10589 2.51668 + vertex 0.923527 2.10577 2.51621 + vertex 0.926198 2.10652 2.51379 + endloop + endfacet + facet normal 0.0524708 -0.975807 -0.212245 + outer loop + vertex 0.927546 2.10589 2.51668 + vertex 0.928919 2.10531 2.51967 + vertex 0.923527 2.10577 2.51621 + endloop + endfacet + facet normal -0.202268 -0.961462 0.186222 + outer loop + vertex 0.928919 2.10531 2.51967 + vertex 0.923486 2.10656 2.52023 + vertex 0.923527 2.10577 2.51621 + endloop + endfacet + facet normal -0.278985 -0.475895 0.834081 + outer loop + vertex 0.924632 2.10742 2.52279 + vertex 0.927705 2.10641 2.52324 + vertex 0.926839 2.10849 2.52414 + endloop + endfacet + facet normal -0.338556 -0.83572 0.432379 + outer loop + vertex 0.924632 2.10742 2.52279 + vertex 0.923486 2.10656 2.52023 + vertex 0.927705 2.10641 2.52324 + endloop + endfacet + facet normal -0.19627 -0.953731 0.227761 + outer loop + vertex 0.923486 2.10656 2.52023 + vertex 0.928919 2.10531 2.51967 + vertex 0.927705 2.10641 2.52324 + endloop + endfacet + facet normal -0.378388 -0.495013 0.782167 + outer loop + vertex 0.927705 2.10641 2.52324 + vertex 0.930773 2.10785 2.52564 + vertex 0.926839 2.10849 2.52414 + endloop + endfacet + facet normal 0.623477 -0.100461 -0.775361 + outer loop + vertex 0.925169 2.10774 2.51071 + vertex 0.922512 2.1076 2.50859 + vertex 0.925 2.11219 2.51 + endloop + endfacet + facet normal 0.214363 -0.146537 -0.965699 + outer loop + vertex 0.925169 2.10774 2.51071 + vertex 0.925 2.11219 2.51 + vertex 0.929451 2.10871 2.51152 + endloop + endfacet + facet normal 0.0360095 -0.360121 -0.93221 + outer loop + vertex 0.929451 2.10871 2.51152 + vertex 0.925 2.11219 2.51 + vertex 0.93 2.11269 2.51 + endloop + endfacet + facet normal 0.194082 -0.829531 -0.523652 + outer loop + vertex 0.929451 2.10871 2.51152 + vertex 0.929028 2.10659 2.51471 + vertex 0.926198 2.10652 2.51379 + endloop + endfacet + facet normal 0.275304 -0.857631 -0.43437 + outer loop + vertex 0.925169 2.10774 2.51071 + vertex 0.929451 2.10871 2.51152 + vertex 0.926198 2.10652 2.51379 + endloop + endfacet + facet normal 0.111145 -0.959012 -0.260657 + outer loop + vertex 0.929028 2.10659 2.51471 + vertex 0.927546 2.10589 2.51668 + vertex 0.926198 2.10652 2.51379 + endloop + endfacet + facet normal -0.562865 0.437822 0.701067 + outer loop + vertex 0.922738 2.11088 2.52025 + vertex 0.924297 2.10897 2.52269 + vertex 0.926307 2.11116 2.52294 + endloop + endfacet + facet normal -0.501724 -0.0508363 0.863533 + outer loop + vertex 0.924297 2.10897 2.52269 + vertex 0.924632 2.10742 2.52279 + vertex 0.926839 2.10849 2.52414 + endloop + endfacet + facet normal -0.428961 0.29775 0.852841 + outer loop + vertex 0.926307 2.11116 2.52294 + vertex 0.924297 2.10897 2.52269 + vertex 0.926839 2.10849 2.52414 + endloop + endfacet + facet normal -0.525301 0.259518 0.810376 + outer loop + vertex 0.926307 2.11116 2.52294 + vertex 0.926839 2.10849 2.52414 + vertex 0.929205 2.11052 2.52502 + endloop + endfacet + facet normal -0.529321 0.24629 0.811887 + outer loop + vertex 0.926307 2.11116 2.52294 + vertex 0.929205 2.11052 2.52502 + vertex 0.928449 2.11197 2.52409 + endloop + endfacet + facet normal -0.354754 0.00685492 0.934934 + outer loop + vertex 0.929205 2.11052 2.52502 + vertex 0.926839 2.10849 2.52414 + vertex 0.930773 2.10785 2.52564 + endloop + endfacet + facet normal -0.552839 0.519203 0.651765 + outer loop + vertex 0.926307 2.11116 2.52294 + vertex 0.928232 2.1135 2.52271 + vertex 0.925648 2.11468 2.51957 + endloop + endfacet + facet normal -0.537383 0.527812 0.657749 + outer loop + vertex 0.926307 2.11116 2.52294 + vertex 0.925648 2.11468 2.51957 + vertex 0.922738 2.11088 2.52025 + endloop + endfacet + facet normal -0.514273 0.515104 0.685704 + outer loop + vertex 0.922738 2.11088 2.52025 + vertex 0.925648 2.11468 2.51957 + vertex 0.9218 2.11426 2.517 + endloop + endfacet + facet normal -0.548634 0.516312 0.657589 + outer loop + vertex 0.928232 2.1135 2.52271 + vertex 0.926307 2.11116 2.52294 + vertex 0.928449 2.11197 2.52409 + endloop + endfacet + facet normal -0.368666 0.810861 0.454522 + outer loop + vertex 0.925216 2.12169 2.51032 + vertex 0.922263 2.12152 2.50823 + vertex 0.923262 2.11998 2.5118 + endloop + endfacet + facet normal -0.37407 0.811771 0.448441 + outer loop + vertex 0.927097 2.1208 2.5135 + vertex 0.925216 2.12169 2.51032 + vertex 0.923262 2.11998 2.5118 + endloop + endfacet + facet normal -0.39871 0.743232 0.537249 + outer loop + vertex 0.927097 2.1208 2.5135 + vertex 0.923262 2.11998 2.5118 + vertex 0.926805 2.11849 2.51649 + endloop + endfacet + facet normal -0.439287 0.705648 0.555956 + outer loop + vertex 0.926805 2.11849 2.51649 + vertex 0.923262 2.11998 2.5118 + vertex 0.923072 2.1172 2.51518 + endloop + endfacet + facet normal -0.48726 0.604115 0.630573 + outer loop + vertex 0.925648 2.11468 2.51957 + vertex 0.923072 2.1172 2.51518 + vertex 0.9218 2.11426 2.517 + endloop + endfacet + facet normal -0.442059 0.64243 0.625993 + outer loop + vertex 0.926805 2.11849 2.51649 + vertex 0.923072 2.1172 2.51518 + vertex 0.925648 2.11468 2.51957 + endloop + endfacet + facet normal -0.103141 0.661275 0.743019 + outer loop + vertex 0.93 2.12755 2.505 + vertex 0.925 2.12677 2.505 + vertex 0.929568 2.12494 2.50726 + endloop + endfacet + facet normal -0.260293 0.423546 0.867673 + outer loop + vertex 0.929568 2.12494 2.50726 + vertex 0.925 2.12677 2.505 + vertex 0.924354 2.12306 2.50662 + endloop + endfacet + facet normal -0.328214 0.858734 0.393512 + outer loop + vertex 0.925216 2.12169 2.51032 + vertex 0.924354 2.12306 2.50662 + vertex 0.922263 2.12152 2.50823 + endloop + endfacet + facet normal -0.299051 0.870437 0.391035 + outer loop + vertex 0.925216 2.12169 2.51032 + vertex 0.929343 2.12251 2.51166 + vertex 0.924354 2.12306 2.50662 + endloop + endfacet + facet normal -0.352202 0.826665 0.438838 + outer loop + vertex 0.929343 2.12251 2.51166 + vertex 0.929568 2.12494 2.50726 + vertex 0.924354 2.12306 2.50662 + endloop + endfacet + facet normal -0.305312 0.854713 0.419821 + outer loop + vertex 0.929343 2.12251 2.51166 + vertex 0.925216 2.12169 2.51032 + vertex 0.927097 2.1208 2.5135 + endloop + endfacet + facet normal -0.100766 -0.991769 -0.0790024 + outer loop + vertex 0.935 0.897937 2.505 + vertex 0.933709 0.897908 2.50702 + vertex 0.93 0.898445 2.505 + endloop + endfacet + facet normal -0.146291 -0.989226 0.00546274 + outer loop + vertex 0.933709 0.897908 2.50702 + vertex 0.929232 0.898561 2.50538 + vertex 0.93 0.898445 2.505 + endloop + endfacet + facet normal -0.203124 -0.964088 0.171102 + outer loop + vertex 0.933709 0.897908 2.50702 + vertex 0.93071 0.89876 2.50826 + vertex 0.929232 0.898561 2.50538 + endloop + endfacet + facet normal -0.21526 -0.966011 0.143126 + outer loop + vertex 0.933962 0.898324 2.51021 + vertex 0.93071 0.89876 2.50826 + vertex 0.933709 0.897908 2.50702 + endloop + endfacet + facet normal -0.26957 -0.932242 0.241367 + outer loop + vertex 0.93071 0.89876 2.50826 + vertex 0.933962 0.898324 2.51021 + vertex 0.932264 0.899169 2.51157 + endloop + endfacet + facet normal -0.344294 -0.898527 0.272234 + outer loop + vertex 0.928368 0.900289 2.51034 + vertex 0.93071 0.89876 2.50826 + vertex 0.932264 0.899169 2.51157 + endloop + endfacet + facet normal -0.361525 -0.858899 0.362757 + outer loop + vertex 0.932264 0.899169 2.51157 + vertex 0.933025 0.900398 2.51524 + vertex 0.928368 0.900289 2.51034 + endloop + endfacet + facet normal -0.399984 -0.825326 0.39856 + outer loop + vertex 0.933025 0.900398 2.51524 + vertex 0.927824 0.902678 2.51474 + vertex 0.928368 0.900289 2.51034 + endloop + endfacet + facet normal -0.442614 -0.700395 0.559946 + outer loop + vertex 0.92761 0.905241 2.51809 + vertex 0.931988 0.902944 2.51868 + vertex 0.930552 0.9053 2.52049 + endloop + endfacet + facet normal -0.449669 -0.722845 0.524684 + outer loop + vertex 0.92761 0.905241 2.51809 + vertex 0.927824 0.902678 2.51474 + vertex 0.931988 0.902944 2.51868 + endloop + endfacet + facet normal -0.391996 -0.79185 0.468309 + outer loop + vertex 0.927824 0.902678 2.51474 + vertex 0.933025 0.900398 2.51524 + vertex 0.931988 0.902944 2.51868 + endloop + endfacet + facet normal -0.418293 -0.700043 0.578766 + outer loop + vertex 0.931988 0.902944 2.51868 + vertex 0.933955 0.904511 2.522 + vertex 0.930552 0.9053 2.52049 + endloop + endfacet + facet normal -0.498798 -0.599082 0.626339 + outer loop + vertex 0.92761 0.905241 2.51809 + vertex 0.930552 0.9053 2.52049 + vertex 0.927932 0.907305 2.52032 + endloop + endfacet + facet normal -0.466273 -0.551088 0.69202 + outer loop + vertex 0.930552 0.9053 2.52049 + vertex 0.930533 0.907512 2.52224 + vertex 0.927932 0.907305 2.52032 + endloop + endfacet + facet normal -0.440334 -0.559137 0.702476 + outer loop + vertex 0.930552 0.9053 2.52049 + vertex 0.933955 0.904511 2.522 + vertex 0.930533 0.907512 2.52224 + endloop + endfacet + facet normal -0.470718 -0.590013 0.655979 + outer loop + vertex 0.933955 0.904511 2.522 + vertex 0.93437 0.907268 2.52477 + vertex 0.930533 0.907512 2.52224 + endloop + endfacet + facet normal -0.614436 -0.150527 0.774474 + outer loop + vertex 0.93405 0.910121 2.52641 + vertex 0.931923 0.912796 2.52525 + vertex 0.930061 0.910862 2.52339 + endloop + endfacet + facet normal -0.590538 -0.451027 0.669208 + outer loop + vertex 0.93405 0.910121 2.52641 + vertex 0.930061 0.910862 2.52339 + vertex 0.93437 0.907268 2.52477 + endloop + endfacet + facet normal -0.532954 -0.341667 0.774095 + outer loop + vertex 0.93437 0.907268 2.52477 + vertex 0.930061 0.910862 2.52339 + vertex 0.930533 0.907512 2.52224 + endloop + endfacet + facet normal -0.622823 -0.161064 0.765604 + outer loop + vertex 0.93405 0.910121 2.52641 + vertex 0.935134 0.912329 2.52776 + vertex 0.931923 0.912796 2.52525 + endloop + endfacet + facet normal -0.0203876 0.99955 0.0219837 + outer loop + vertex 0.935 0.917435 2.51 + vertex 0.93 0.917333 2.51 + vertex 0.935 0.917325 2.515 + endloop + endfacet + facet normal -0.283635 0.915573 0.285091 + outer loop + vertex 0.935 0.917325 2.515 + vertex 0.93 0.917333 2.51 + vertex 0.92882 0.916385 2.51187 + endloop + endfacet + facet normal -0.0842833 0.987875 -0.130384 + outer loop + vertex 0.935 0.917325 2.515 + vertex 0.92882 0.916385 2.51187 + vertex 0.93371 0.917342 2.51596 + endloop + endfacet + facet normal -0.231017 0.971718 0.0489331 + outer loop + vertex 0.93371 0.917342 2.51596 + vertex 0.92882 0.916385 2.51187 + vertex 0.928199 0.916011 2.51637 + endloop + endfacet + facet normal -0.23223 0.972079 0.0336482 + outer loop + vertex 0.93371 0.917342 2.51596 + vertex 0.928199 0.916011 2.51637 + vertex 0.932586 0.916902 2.52091 + endloop + endfacet + facet normal -0.503924 0.79816 0.330152 + outer loop + vertex 0.932586 0.916902 2.52091 + vertex 0.928199 0.916011 2.51637 + vertex 0.929001 0.914389 2.52151 + endloop + endfacet + facet normal -0.758128 0.114836 0.641914 + outer loop + vertex 0.931923 0.912796 2.52525 + vertex 0.929001 0.914389 2.52151 + vertex 0.930061 0.910862 2.52339 + endloop + endfacet + facet normal -0.647212 0.372611 0.665039 + outer loop + vertex 0.931923 0.912796 2.52525 + vertex 0.933382 0.91516 2.52534 + vertex 0.929001 0.914389 2.52151 + endloop + endfacet + facet normal -0.482242 0.782506 0.393861 + outer loop + vertex 0.933382 0.91516 2.52534 + vertex 0.932586 0.916902 2.52091 + vertex 0.929001 0.914389 2.52151 + endloop + endfacet + facet normal -0.556915 0.312731 0.769445 + outer loop + vertex 0.933382 0.91516 2.52534 + vertex 0.931923 0.912796 2.52525 + vertex 0.935134 0.912329 2.52776 + endloop + endfacet + facet normal -0.69543 -0.194479 -0.691777 + outer loop + vertex 0.935 0.947901 2.53 + vertex 0.934413 0.95 2.53 + vertex 0.935 0.95 2.52941 + endloop + endfacet + facet normal 0.476901 0.133367 -0.86878 + outer loop + vertex 0.935 0.947901 2.53 + vertex 0.934582 0.947594 2.52972 + vertex 0.934413 0.95 2.53 + endloop + endfacet + facet normal -0.841002 0.00310304 -0.541022 + outer loop + vertex 0.933661 0.949618 2.53117 + vertex 0.934413 0.95 2.53 + vertex 0.934582 0.947594 2.52972 + endloop + endfacet + facet normal -0.811274 -0.138207 -0.568096 + outer loop + vertex 0.933661 0.949618 2.53117 + vertex 0.932415 0.953419 2.53202 + vertex 0.934413 0.95 2.53 + endloop + endfacet + facet normal -0.89315 -0.39746 -0.210497 + outer loop + vertex 0.932415 0.953419 2.53202 + vertex 0.932188 0.955 2.53 + vertex 0.934413 0.95 2.53 + endloop + endfacet + facet normal -0.926305 -0.34011 0.162124 + outer loop + vertex 0.933616 0.95131 2.53446 + vertex 0.932415 0.953419 2.53202 + vertex 0.933661 0.949618 2.53117 + endloop + endfacet + facet normal -0.930042 -0.319154 0.182108 + outer loop + vertex 0.932353 0.956099 2.5364 + vertex 0.932415 0.953419 2.53202 + vertex 0.933616 0.95131 2.53446 + endloop + endfacet + facet normal -0.896555 -0.347718 0.274375 + outer loop + vertex 0.933616 0.95131 2.53446 + vertex 0.933959 0.953295 2.5381 + vertex 0.932353 0.956099 2.5364 + endloop + endfacet + facet normal -0.894397 -0.4082 0.182833 + outer loop + vertex 0.93 0.96 2.53046 + vertex 0.93 0.959794 2.53 + vertex 0.932188 0.955 2.53 + endloop + endfacet + facet normal -0.883101 -0.407784 0.232044 + outer loop + vertex 0.93 0.96 2.53046 + vertex 0.932188 0.955 2.53 + vertex 0.931193 0.96 2.535 + endloop + endfacet + facet normal -0.984802 -0.17202 -0.023951 + outer loop + vertex 0.931193 0.96 2.535 + vertex 0.932188 0.955 2.53 + vertex 0.932415 0.953419 2.53202 + endloop + endfacet + facet normal -0.962081 -0.238527 0.132304 + outer loop + vertex 0.932415 0.953419 2.53202 + vertex 0.932353 0.956099 2.5364 + vertex 0.931193 0.96 2.535 + endloop + endfacet + facet normal -0.942772 -0.31715 -0.102939 + outer loop + vertex 0.931193 0.96 2.535 + vertex 0.932353 0.956099 2.5364 + vertex 0.931138 0.959577 2.53681 + endloop + endfacet + facet normal -0.89446 -0.329899 0.30184 + outer loop + vertex 0.933574 0.956082 2.54 + vertex 0.932353 0.956099 2.5364 + vertex 0.933959 0.953295 2.5381 + endloop + endfacet + facet normal -0.889026 -0.345947 0.299922 + outer loop + vertex 0.933574 0.956082 2.54 + vertex 0.932272 0.960009 2.54067 + vertex 0.932353 0.956099 2.5364 + endloop + endfacet + facet normal -0.888951 -0.346054 0.300022 + outer loop + vertex 0.932272 0.960009 2.54067 + vertex 0.931138 0.959577 2.53681 + vertex 0.932353 0.956099 2.5364 + endloop + endfacet + facet normal -0.847441 -0.349193 0.399885 + outer loop + vertex 0.933574 0.956082 2.54 + vertex 0.93427 0.957376 2.54261 + vertex 0.932272 0.960009 2.54067 + endloop + endfacet + facet normal 0.699745 0.253887 -0.667756 + outer loop + vertex 0.929269 0.96277 2.53404 + vertex 0.93 0.963288 2.535 + vertex 0.931193 0.96 2.535 + endloop + endfacet + facet normal -0.83577 -0.528095 0.150346 + outer loop + vertex 0.929269 0.96277 2.53404 + vertex 0.931193 0.96 2.535 + vertex 0.929973 0.962554 2.53719 + endloop + endfacet + facet normal -0.930325 -0.349793 -0.110186 + outer loop + vertex 0.929973 0.962554 2.53719 + vertex 0.931193 0.96 2.535 + vertex 0.931138 0.959577 2.53681 + endloop + endfacet + facet normal -0.874888 -0.380434 0.299737 + outer loop + vertex 0.931138 0.959577 2.53681 + vertex 0.932272 0.960009 2.54067 + vertex 0.929973 0.962554 2.53719 + endloop + endfacet + facet normal -0.872093 -0.397485 0.28541 + outer loop + vertex 0.929973 0.962554 2.53719 + vertex 0.932272 0.960009 2.54067 + vertex 0.930505 0.964609 2.54168 + endloop + endfacet + facet normal -0.841113 -0.315253 0.439481 + outer loop + vertex 0.934598 0.959966 2.54509 + vertex 0.932272 0.960009 2.54067 + vertex 0.93427 0.957376 2.54261 + endloop + endfacet + facet normal -0.811423 -0.403306 0.423009 + outer loop + vertex 0.934598 0.959966 2.54509 + vertex 0.932617 0.96383 2.54498 + vertex 0.932272 0.960009 2.54067 + endloop + endfacet + facet normal -0.810598 -0.404201 0.423737 + outer loop + vertex 0.932617 0.96383 2.54498 + vertex 0.930505 0.964609 2.54168 + vertex 0.932272 0.960009 2.54067 + endloop + endfacet + facet normal -0.768986 -0.378815 0.514936 + outer loop + vertex 0.934598 0.959966 2.54509 + vertex 0.935205 0.963107 2.54831 + vertex 0.932617 0.96383 2.54498 + endloop + endfacet + facet normal -0.900487 -0.398706 0.173659 + outer loop + vertex 0.929269 0.96277 2.53404 + vertex 0.929973 0.962554 2.53719 + vertex 0.928532 0.965018 2.53537 + endloop + endfacet + facet normal -0.872339 -0.397063 0.285246 + outer loop + vertex 0.929973 0.962554 2.53719 + vertex 0.930505 0.964609 2.54168 + vertex 0.928727 0.96658 2.53898 + endloop + endfacet + facet normal -0.903516 -0.373365 0.210374 + outer loop + vertex 0.928532 0.965018 2.53537 + vertex 0.929973 0.962554 2.53719 + vertex 0.928727 0.96658 2.53898 + endloop + endfacet + facet normal -0.872183 -0.397941 0.284501 + outer loop + vertex 0.929325 0.967771 2.54248 + vertex 0.928727 0.96658 2.53898 + vertex 0.930505 0.964609 2.54168 + endloop + endfacet + facet normal -0.81829 -0.408434 0.404455 + outer loop + vertex 0.929325 0.967771 2.54248 + vertex 0.930505 0.964609 2.54168 + vertex 0.93085 0.966903 2.54469 + endloop + endfacet + facet normal -0.804646 -0.424515 0.415129 + outer loop + vertex 0.93085 0.966903 2.54469 + vertex 0.930505 0.964609 2.54168 + vertex 0.932617 0.96383 2.54498 + endloop + endfacet + facet normal -0.761651 -0.39038 0.517195 + outer loop + vertex 0.932617 0.96383 2.54498 + vertex 0.932711 0.968106 2.54834 + vertex 0.93085 0.966903 2.54469 + endloop + endfacet + facet normal -0.767277 -0.386174 0.512011 + outer loop + vertex 0.935205 0.963107 2.54831 + vertex 0.932711 0.968106 2.54834 + vertex 0.932617 0.96383 2.54498 + endloop + endfacet + facet normal -0.827187 -0.364079 0.428028 + outer loop + vertex 0.929325 0.967771 2.54248 + vertex 0.93085 0.966903 2.54469 + vertex 0.929629 0.970123 2.54507 + endloop + endfacet + facet normal -0.757263 -0.381112 0.530382 + outer loop + vertex 0.932516 0.971917 2.55074 + vertex 0.931553 0.975469 2.55192 + vertex 0.930373 0.972856 2.54836 + endloop + endfacet + facet normal -0.75807 -0.375212 0.533428 + outer loop + vertex 0.932711 0.968106 2.54834 + vertex 0.932516 0.971917 2.55074 + vertex 0.930373 0.972856 2.54836 + endloop + endfacet + facet normal -0.77824 -0.385001 0.496102 + outer loop + vertex 0.932711 0.968106 2.54834 + vertex 0.930373 0.972856 2.54836 + vertex 0.929629 0.970123 2.54507 + endloop + endfacet + facet normal -0.779587 -0.356256 0.515097 + outer loop + vertex 0.932711 0.968106 2.54834 + vertex 0.929629 0.970123 2.54507 + vertex 0.93085 0.966903 2.54469 + endloop + endfacet + facet normal -0.733919 -0.384564 0.559887 + outer loop + vertex 0.932516 0.971917 2.55074 + vertex 0.933652 0.972948 2.55294 + vertex 0.931553 0.975469 2.55192 + endloop + endfacet + facet normal -0.761711 -0.375689 0.527877 + outer loop + vertex 0.928913 0.977006 2.54921 + vertex 0.930373 0.972856 2.54836 + vertex 0.931553 0.975469 2.55192 + endloop + endfacet + facet normal -0.760332 -0.395118 0.515536 + outer loop + vertex 0.929817 0.979302 2.5523 + vertex 0.928913 0.977006 2.54921 + vertex 0.931553 0.975469 2.55192 + endloop + endfacet + facet normal -0.734571 -0.385796 0.558183 + outer loop + vertex 0.934265 0.975021 2.55518 + vertex 0.931553 0.975469 2.55192 + vertex 0.933652 0.972948 2.55294 + endloop + endfacet + facet normal -0.731859 -0.396109 0.554509 + outer loop + vertex 0.934265 0.975021 2.55518 + vertex 0.932167 0.978793 2.55511 + vertex 0.931553 0.975469 2.55192 + endloop + endfacet + facet normal -0.739894 -0.389121 0.548764 + outer loop + vertex 0.932167 0.978793 2.55511 + vertex 0.929817 0.979302 2.5523 + vertex 0.931553 0.975469 2.55192 + endloop + endfacet + facet normal -0.725088 -0.392111 0.566124 + outer loop + vertex 0.934265 0.975021 2.55518 + vertex 0.935266 0.977756 2.55836 + vertex 0.932167 0.978793 2.55511 + endloop + endfacet + facet normal -0.769967 -0.383671 0.50985 + outer loop + vertex 0.928913 0.977006 2.54921 + vertex 0.929817 0.979302 2.5523 + vertex 0.928134 0.980373 2.55056 + endloop + endfacet + facet normal -0.770216 -0.378868 0.513056 + outer loop + vertex 0.928782 0.982024 2.55276 + vertex 0.928134 0.980373 2.55056 + vertex 0.929817 0.979302 2.5523 + endloop + endfacet + facet normal -0.754141 -0.376904 0.537787 + outer loop + vertex 0.928782 0.982024 2.55276 + vertex 0.929817 0.979302 2.5523 + vertex 0.93036 0.98163 2.55469 + endloop + endfacet + facet normal -0.73946 -0.39091 0.548077 + outer loop + vertex 0.93036 0.98163 2.55469 + vertex 0.929817 0.979302 2.5523 + vertex 0.932167 0.978793 2.55511 + endloop + endfacet + facet normal -0.731005 -0.383092 0.564688 + outer loop + vertex 0.932167 0.978793 2.55511 + vertex 0.932499 0.982994 2.55839 + vertex 0.93036 0.98163 2.55469 + endloop + endfacet + facet normal -0.725987 -0.386643 0.568726 + outer loop + vertex 0.935266 0.977756 2.55836 + vertex 0.932499 0.982994 2.55839 + vertex 0.932167 0.978793 2.55511 + endloop + endfacet + facet normal -0.757562 -0.36109 0.543795 + outer loop + vertex 0.928782 0.982024 2.55276 + vertex 0.93036 0.98163 2.55469 + vertex 0.929307 0.984525 2.55515 + endloop + endfacet + facet normal -0.747038 -0.349989 0.565192 + outer loop + vertex 0.932328 0.987047 2.56086 + vertex 0.931412 0.990671 2.56189 + vertex 0.930222 0.987683 2.55847 + endloop + endfacet + facet normal -0.743483 -0.370839 0.556518 + outer loop + vertex 0.932499 0.982994 2.55839 + vertex 0.932328 0.987047 2.56086 + vertex 0.930222 0.987683 2.55847 + endloop + endfacet + facet normal -0.743107 -0.370667 0.557134 + outer loop + vertex 0.932499 0.982994 2.55839 + vertex 0.930222 0.987683 2.55847 + vertex 0.929307 0.984525 2.55515 + endloop + endfacet + facet normal -0.74399 -0.359245 0.563402 + outer loop + vertex 0.932499 0.982994 2.55839 + vertex 0.929307 0.984525 2.55515 + vertex 0.93036 0.98163 2.55469 + endloop + endfacet + facet normal -0.731517 -0.351491 0.584241 + outer loop + vertex 0.932328 0.987047 2.56086 + vertex 0.933387 0.988386 2.56299 + vertex 0.931412 0.990671 2.56189 + endloop + endfacet + facet normal -0.747179 -0.349832 0.565103 + outer loop + vertex 0.928745 0.991977 2.55918 + vertex 0.930222 0.987683 2.55847 + vertex 0.931412 0.990671 2.56189 + endloop + endfacet + facet normal -0.747229 -0.348983 0.565561 + outer loop + vertex 0.929928 0.994539 2.56232 + vertex 0.928745 0.991977 2.55918 + vertex 0.931412 0.990671 2.56189 + endloop + endfacet + facet normal -0.724114 -0.336559 0.601986 + outer loop + vertex 0.933498 0.990648 2.56439 + vertex 0.931412 0.990671 2.56189 + vertex 0.933387 0.988386 2.56299 + endloop + endfacet + facet normal -0.721855 -0.344823 0.600019 + outer loop + vertex 0.933498 0.990648 2.56439 + vertex 0.932292 0.993827 2.56476 + vertex 0.931412 0.990671 2.56189 + endloop + endfacet + facet normal -0.72332 -0.343498 0.599013 + outer loop + vertex 0.932292 0.993827 2.56476 + vertex 0.929928 0.994539 2.56232 + vertex 0.931412 0.990671 2.56189 + endloop + endfacet + facet normal -0.676207 -0.334198 0.656548 + outer loop + vertex 0.933498 0.990648 2.56439 + vertex 0.935208 0.991867 2.56677 + vertex 0.932292 0.993827 2.56476 + endloop + endfacet + facet normal -0.745368 -0.351184 0.566654 + outer loop + vertex 0.928745 0.991977 2.55918 + vertex 0.929928 0.994539 2.56232 + vertex 0.927993 0.99563 2.56045 + endloop + endfacet + facet normal -0.745381 -0.350311 0.567177 + outer loop + vertex 0.928957 0.997398 2.56281 + vertex 0.927993 0.99563 2.56045 + vertex 0.929928 0.994539 2.56232 + endloop + endfacet + facet normal -0.726836 -0.348258 0.591968 + outer loop + vertex 0.928957 0.997398 2.56281 + vertex 0.929928 0.994539 2.56232 + vertex 0.930747 0.996818 2.56466 + endloop + endfacet + facet normal -0.722034 -0.353082 0.594979 + outer loop + vertex 0.930747 0.996818 2.56466 + vertex 0.929928 0.994539 2.56232 + vertex 0.932292 0.993827 2.56476 + endloop + endfacet + facet normal -0.696652 -0.338707 0.632419 + outer loop + vertex 0.932292 0.993827 2.56476 + vertex 0.93345 0.997476 2.56799 + vertex 0.930747 0.996818 2.56466 + endloop + endfacet + facet normal -0.67964 -0.353328 0.642844 + outer loop + vertex 0.935208 0.991867 2.56677 + vertex 0.93345 0.997476 2.56799 + vertex 0.932292 0.993827 2.56476 + endloop + endfacet + facet normal -0.72657 -0.350357 0.591055 + outer loop + vertex 0.928957 0.997398 2.56281 + vertex 0.930747 0.996818 2.56466 + vertex 0.929662 0.999804 2.5651 + endloop + endfacet + facet normal -0.675378 -0.347278 0.650587 + outer loop + vertex 0.933262 1.00167 2.57016 + vertex 0.932018 1.00524 2.57078 + vertex 0.930735 1.00273 2.56811 + endloop + endfacet + facet normal -0.67519 -0.362248 0.642569 + outer loop + vertex 0.93345 0.997476 2.56799 + vertex 0.933262 1.00167 2.57016 + vertex 0.930735 1.00273 2.56811 + endloop + endfacet + facet normal -0.697026 -0.372885 0.612464 + outer loop + vertex 0.93345 0.997476 2.56799 + vertex 0.930735 1.00273 2.56811 + vertex 0.929662 0.999804 2.5651 + endloop + endfacet + facet normal -0.69437 -0.344616 0.631735 + outer loop + vertex 0.93345 0.997476 2.56799 + vertex 0.929662 0.999804 2.5651 + vertex 0.930747 0.996818 2.56466 + endloop + endfacet + facet normal -0.599401 -0.334164 0.72736 + outer loop + vertex 0.933262 1.00167 2.57016 + vertex 0.935297 1.00252 2.57223 + vertex 0.932018 1.00524 2.57078 + endloop + endfacet + facet normal -0.675592 -0.347058 0.650482 + outer loop + vertex 0.92909 1.00695 2.56865 + vertex 0.930735 1.00273 2.56811 + vertex 0.932018 1.00524 2.57078 + endloop + endfacet + facet normal -0.676058 -0.351363 0.64768 + outer loop + vertex 0.930575 1.00866 2.57112 + vertex 0.92909 1.00695 2.56865 + vertex 0.932018 1.00524 2.57078 + endloop + endfacet + facet normal -0.596451 -0.326385 0.733293 + outer loop + vertex 0.932018 1.00524 2.57078 + vertex 0.934059 1.00767 2.57352 + vertex 0.930575 1.00866 2.57112 + endloop + endfacet + facet normal -0.596027 -0.326881 0.733417 + outer loop + vertex 0.935297 1.00252 2.57223 + vertex 0.934059 1.00767 2.57352 + vertex 0.932018 1.00524 2.57078 + endloop + endfacet + facet normal -0.682106 -0.343234 0.645695 + outer loop + vertex 0.92909 1.00695 2.56865 + vertex 0.930575 1.00866 2.57112 + vertex 0.928399 1.01034 2.56972 + endloop + endfacet + facet normal -0.674908 -0.316592 0.666535 + outer loop + vertex 0.930575 1.00866 2.57112 + vertex 0.930023 1.01198 2.57214 + vertex 0.928399 1.01034 2.56972 + endloop + endfacet + facet normal -0.59648 -0.324287 0.7342 + outer loop + vertex 0.930575 1.00866 2.57112 + vertex 0.934059 1.00767 2.57352 + vertex 0.930023 1.01198 2.57214 + endloop + endfacet + facet normal -0.60226 -0.332391 0.72581 + outer loop + vertex 0.934059 1.00767 2.57352 + vertex 0.932453 1.01306 2.57465 + vertex 0.930023 1.01198 2.57214 + endloop + endfacet + facet normal -0.618596 -0.33724 0.709654 + outer loop + vertex 0.931887 1.01643 2.57566 + vertex 0.930444 1.01927 2.57575 + vertex 0.928313 1.01743 2.57302 + endloop + endfacet + facet normal -0.619273 -0.318611 0.717627 + outer loop + vertex 0.931887 1.01643 2.57566 + vertex 0.928313 1.01743 2.57302 + vertex 0.932453 1.01306 2.57465 + endloop + endfacet + facet normal -0.613302 -0.309572 0.726653 + outer loop + vertex 0.932453 1.01306 2.57465 + vertex 0.928313 1.01743 2.57302 + vertex 0.930023 1.01198 2.57214 + endloop + endfacet + facet normal -0.530545 -0.295187 0.794599 + outer loop + vertex 0.931887 1.01643 2.57566 + vertex 0.933885 1.01798 2.57757 + vertex 0.930444 1.01927 2.57575 + endloop + endfacet + facet normal -0.615476 -0.34171 0.710228 + outer loop + vertex 0.928313 1.01743 2.57302 + vertex 0.930444 1.01927 2.57575 + vertex 0.928229 1.02156 2.57493 + endloop + endfacet + facet normal -0.588926 -0.302006 0.749639 + outer loop + vertex 0.930444 1.01927 2.57575 + vertex 0.930336 1.02248 2.57696 + vertex 0.928229 1.02156 2.57493 + endloop + endfacet + facet normal -0.532857 -0.313769 0.785883 + outer loop + vertex 0.930444 1.01927 2.57575 + vertex 0.933885 1.01798 2.57757 + vertex 0.930336 1.02248 2.57696 + endloop + endfacet + facet normal -0.515068 -0.297278 0.803947 + outer loop + vertex 0.933885 1.01798 2.57757 + vertex 0.933829 1.02266 2.57927 + vertex 0.930336 1.02248 2.57696 + endloop + endfacet + facet normal -0.516581 -0.307824 0.798992 + outer loop + vertex 0.933131 1.02671 2.58032 + vertex 0.93142 1.03058 2.5807 + vertex 0.929263 1.0277 2.57819 + endloop + endfacet + facet normal -0.516193 -0.296923 0.803357 + outer loop + vertex 0.933131 1.02671 2.58032 + vertex 0.929263 1.0277 2.57819 + vertex 0.933829 1.02266 2.57927 + endloop + endfacet + facet normal -0.515342 -0.29596 0.804258 + outer loop + vertex 0.933829 1.02266 2.57927 + vertex 0.929263 1.0277 2.57819 + vertex 0.930336 1.02248 2.57696 + endloop + endfacet + facet normal -0.452779 -0.284174 0.845125 + outer loop + vertex 0.933131 1.02671 2.58032 + vertex 0.935666 1.02823 2.58218 + vertex 0.93142 1.03058 2.5807 + endloop + endfacet + facet normal -0.516903 -0.307509 0.798905 + outer loop + vertex 0.928031 1.03293 2.57941 + vertex 0.929263 1.0277 2.57819 + vertex 0.93142 1.03058 2.5807 + endloop + endfacet + facet normal -0.519481 -0.313401 0.794934 + outer loop + vertex 0.929967 1.03415 2.58116 + vertex 0.928031 1.03293 2.57941 + vertex 0.93142 1.03058 2.5807 + endloop + endfacet + facet normal -0.457817 -0.293951 0.839045 + outer loop + vertex 0.93142 1.03058 2.5807 + vertex 0.932921 1.03341 2.58251 + vertex 0.929967 1.03415 2.58116 + endloop + endfacet + facet normal -0.456647 -0.294792 0.839387 + outer loop + vertex 0.935666 1.02823 2.58218 + vertex 0.932921 1.03341 2.58251 + vertex 0.93142 1.03058 2.5807 + endloop + endfacet + facet normal -0.524561 -0.305145 0.794809 + outer loop + vertex 0.928031 1.03293 2.57941 + vertex 0.929967 1.03415 2.58116 + vertex 0.927779 1.03622 2.58051 + endloop + endfacet + facet normal -0.504172 -0.276319 0.818204 + outer loop + vertex 0.929967 1.03415 2.58116 + vertex 0.929927 1.03729 2.58219 + vertex 0.927779 1.03622 2.58051 + endloop + endfacet + facet normal -0.45705 -0.283881 0.842922 + outer loop + vertex 0.929967 1.03415 2.58116 + vertex 0.932921 1.03341 2.58251 + vertex 0.929927 1.03729 2.58219 + endloop + endfacet + facet normal -0.446765 -0.275295 0.851243 + outer loop + vertex 0.932921 1.03341 2.58251 + vertex 0.93355 1.03755 2.58418 + vertex 0.929927 1.03729 2.58219 + endloop + endfacet + facet normal -0.448104 -0.286167 0.846942 + outer loop + vertex 0.933078 1.04159 2.58526 + vertex 0.931469 1.0454 2.5857 + vertex 0.929033 1.04247 2.58342 + endloop + endfacet + facet normal -0.447776 -0.279994 0.849176 + outer loop + vertex 0.933078 1.04159 2.58526 + vertex 0.929033 1.04247 2.58342 + vertex 0.93355 1.03755 2.58418 + endloop + endfacet + facet normal -0.44618 -0.278312 0.850568 + outer loop + vertex 0.93355 1.03755 2.58418 + vertex 0.929033 1.04247 2.58342 + vertex 0.929927 1.03729 2.58219 + endloop + endfacet + facet normal -0.423345 -0.277513 0.862418 + outer loop + vertex 0.933078 1.04159 2.58526 + vertex 0.935733 1.04321 2.58709 + vertex 0.931469 1.0454 2.5857 + endloop + endfacet + facet normal -0.449572 -0.284723 0.846651 + outer loop + vertex 0.927828 1.04787 2.58459 + vertex 0.929033 1.04247 2.58342 + vertex 0.931469 1.0454 2.5857 + endloop + endfacet + facet normal -0.448882 -0.283329 0.847484 + outer loop + vertex 0.930063 1.04914 2.5862 + vertex 0.927828 1.04787 2.58459 + vertex 0.931469 1.0454 2.5857 + endloop + endfacet + facet normal -0.418958 -0.274519 0.865514 + outer loop + vertex 0.931469 1.0454 2.5857 + vertex 0.933237 1.04834 2.58749 + vertex 0.930063 1.04914 2.5862 + endloop + endfacet + facet normal -0.421588 -0.27254 0.864861 + outer loop + vertex 0.935733 1.04321 2.58709 + vertex 0.933237 1.04834 2.58749 + vertex 0.931469 1.0454 2.5857 + endloop + endfacet + facet normal -0.453596 -0.275273 0.84763 + outer loop + vertex 0.927828 1.04787 2.58459 + vertex 0.930063 1.04914 2.5862 + vertex 0.927638 1.0514 2.58564 + endloop + endfacet + facet normal -0.441571 -0.259514 0.858876 + outer loop + vertex 0.930063 1.04914 2.5862 + vertex 0.930221 1.05298 2.58744 + vertex 0.927638 1.0514 2.58564 + endloop + endfacet + facet normal -0.417827 -0.263886 0.869359 + outer loop + vertex 0.930063 1.04914 2.5862 + vertex 0.933237 1.04834 2.58749 + vertex 0.930221 1.05298 2.58744 + endloop + endfacet + facet normal -0.421222 -0.266117 0.867038 + outer loop + vertex 0.933237 1.04834 2.58749 + vertex 0.934501 1.05199 2.58922 + vertex 0.930221 1.05298 2.58744 + endloop + endfacet + facet normal -0.421137 -0.265118 0.867385 + outer loop + vertex 0.934501 1.05199 2.58922 + vertex 0.93201 1.05714 2.58958 + vertex 0.930221 1.05298 2.58744 + endloop + endfacet + facet normal -0.426837 -0.261757 0.865617 + outer loop + vertex 0.930221 1.05298 2.58744 + vertex 0.93201 1.05714 2.58958 + vertex 0.927803 1.05797 2.58776 + endloop + endfacet + facet normal -0.428042 -0.260288 0.865465 + outer loop + vertex 0.931993 1.06104 2.59076 + vertex 0.930629 1.06412 2.59101 + vertex 0.928445 1.06226 2.58938 + endloop + endfacet + facet normal -0.428557 -0.263021 0.864383 + outer loop + vertex 0.931993 1.06104 2.59076 + vertex 0.928445 1.06226 2.58938 + vertex 0.93201 1.05714 2.58958 + endloop + endfacet + facet normal -0.426838 -0.261775 0.865611 + outer loop + vertex 0.93201 1.05714 2.58958 + vertex 0.928445 1.06226 2.58938 + vertex 0.927803 1.05797 2.58776 + endloop + endfacet + facet normal -0.442601 -0.266009 0.856355 + outer loop + vertex 0.931993 1.06104 2.59076 + vertex 0.934166 1.06286 2.59245 + vertex 0.930629 1.06412 2.59101 + endloop + endfacet + facet normal -0.428481 -0.259729 0.865416 + outer loop + vertex 0.928445 1.06226 2.58938 + vertex 0.930629 1.06412 2.59101 + vertex 0.927957 1.06638 2.59037 + endloop + endfacet + facet normal -0.425642 -0.255637 0.868031 + outer loop + vertex 0.930629 1.06412 2.59101 + vertex 0.930629 1.06803 2.59216 + vertex 0.927957 1.06638 2.59037 + endloop + endfacet + facet normal -0.440217 -0.253661 0.861316 + outer loop + vertex 0.930629 1.06412 2.59101 + vertex 0.934166 1.06286 2.59245 + vertex 0.930629 1.06803 2.59216 + endloop + endfacet + facet normal -0.448422 -0.259606 0.855291 + outer loop + vertex 0.934166 1.06286 2.59245 + vertex 0.934834 1.06708 2.59408 + vertex 0.930629 1.06803 2.59216 + endloop + endfacet + facet normal -0.447235 -0.243307 0.860688 + outer loop + vertex 0.934834 1.06708 2.59408 + vertex 0.932456 1.07217 2.59429 + vertex 0.930629 1.06803 2.59216 + endloop + endfacet + facet normal -0.432494 -0.252319 0.865612 + outer loop + vertex 0.930629 1.06803 2.59216 + vertex 0.932456 1.07217 2.59429 + vertex 0.928186 1.0732 2.59245 + endloop + endfacet + facet normal -0.440555 -0.251389 0.861809 + outer loop + vertex 0.932678 1.07604 2.59549 + vertex 0.931327 1.07988 2.59592 + vertex 0.929497 1.07693 2.59412 + endloop + endfacet + facet normal -0.439587 -0.243874 0.864459 + outer loop + vertex 0.932678 1.07604 2.59549 + vertex 0.929497 1.07693 2.59412 + vertex 0.932456 1.07217 2.59429 + endloop + endfacet + facet normal -0.431125 -0.238417 0.870223 + outer loop + vertex 0.932456 1.07217 2.59429 + vertex 0.929497 1.07693 2.59412 + vertex 0.928186 1.0732 2.59245 + endloop + endfacet + facet normal -0.49203 -0.265854 0.828992 + outer loop + vertex 0.932678 1.07604 2.59549 + vertex 0.934949 1.0772 2.59721 + vertex 0.931327 1.07988 2.59592 + endloop + endfacet + facet normal -0.433869 -0.256663 0.863645 + outer loop + vertex 0.927025 1.0822 2.59445 + vertex 0.929497 1.07693 2.59412 + vertex 0.931327 1.07988 2.59592 + endloop + endfacet + facet normal -0.428962 -0.243673 0.869836 + outer loop + vertex 0.929743 1.08384 2.59625 + vertex 0.927025 1.0822 2.59445 + vertex 0.931327 1.07988 2.59592 + endloop + endfacet + facet normal -0.483283 -0.26253 0.835174 + outer loop + vertex 0.931327 1.07988 2.59592 + vertex 0.9338 1.08273 2.59825 + vertex 0.929743 1.08384 2.59625 + endloop + endfacet + facet normal -0.487798 -0.2577 0.834053 + outer loop + vertex 0.934949 1.0772 2.59721 + vertex 0.9338 1.08273 2.59825 + vertex 0.931327 1.07988 2.59592 + endloop + endfacet + facet normal -0.428489 -0.244471 0.869846 + outer loop + vertex 0.927025 1.0822 2.59445 + vertex 0.929743 1.08384 2.59625 + vertex 0.927083 1.08618 2.59559 + endloop + endfacet + facet normal -0.435977 -0.254876 0.863112 + outer loop + vertex 0.929743 1.08384 2.59625 + vertex 0.929287 1.08799 2.59724 + vertex 0.927083 1.08618 2.59559 + endloop + endfacet + facet normal -0.482487 -0.25404 0.838254 + outer loop + vertex 0.929743 1.08384 2.59625 + vertex 0.9338 1.08273 2.59825 + vertex 0.929287 1.08799 2.59724 + endloop + endfacet + facet normal -0.475695 -0.247065 0.8442 + outer loop + vertex 0.9338 1.08273 2.59825 + vertex 0.932936 1.08809 2.59933 + vertex 0.929287 1.08799 2.59724 + endloop + endfacet + facet normal -0.492773 -0.247806 0.834127 + outer loop + vertex 0.932926 1.09133 2.6003 + vertex 0.931581 1.09501 2.6006 + vertex 0.92997 1.09224 2.59882 + endloop + endfacet + facet normal -0.493185 -0.251187 0.832871 + outer loop + vertex 0.932926 1.09133 2.6003 + vertex 0.92997 1.09224 2.59882 + vertex 0.932936 1.08809 2.59933 + endloop + endfacet + facet normal -0.477022 -0.238014 0.846049 + outer loop + vertex 0.932936 1.08809 2.59933 + vertex 0.92997 1.09224 2.59882 + vertex 0.929287 1.08799 2.59724 + endloop + endfacet + facet normal -0.543871 -0.26345 0.796743 + outer loop + vertex 0.932926 1.09133 2.6003 + vertex 0.935049 1.09221 2.60204 + vertex 0.931581 1.09501 2.6006 + endloop + endfacet + facet normal -0.483634 -0.255125 0.837263 + outer loop + vertex 0.927547 1.09738 2.59899 + vertex 0.92997 1.09224 2.59882 + vertex 0.931581 1.09501 2.6006 + endloop + endfacet + facet normal -0.472801 -0.227073 0.851409 + outer loop + vertex 0.930198 1.09884 2.60085 + vertex 0.927547 1.09738 2.59899 + vertex 0.931581 1.09501 2.6006 + endloop + endfacet + facet normal -0.539555 -0.248105 0.804565 + outer loop + vertex 0.931581 1.09501 2.6006 + vertex 0.93397 1.09771 2.60303 + vertex 0.930198 1.09884 2.60085 + endloop + endfacet + facet normal -0.537215 -0.250829 0.805285 + outer loop + vertex 0.935049 1.09221 2.60204 + vertex 0.93397 1.09771 2.60303 + vertex 0.931581 1.09501 2.6006 + endloop + endfacet + facet normal -0.477775 -0.217624 0.8511 + outer loop + vertex 0.927547 1.09738 2.59899 + vertex 0.930198 1.09884 2.60085 + vertex 0.927821 1.10128 2.60014 + endloop + endfacet + facet normal -0.49687 -0.241299 0.833604 + outer loop + vertex 0.930198 1.09884 2.60085 + vertex 0.930156 1.10241 2.60186 + vertex 0.927821 1.10128 2.60014 + endloop + endfacet + facet normal -0.538355 -0.234924 0.809311 + outer loop + vertex 0.930198 1.09884 2.60085 + vertex 0.93397 1.09771 2.60303 + vertex 0.930156 1.10241 2.60186 + endloop + endfacet + facet normal -0.54457 -0.241491 0.803197 + outer loop + vertex 0.93397 1.09771 2.60303 + vertex 0.932972 1.10319 2.604 + vertex 0.930156 1.10241 2.60186 + endloop + endfacet + facet normal -0.546546 -0.23966 0.802403 + outer loop + vertex 0.932914 1.1065 2.60499 + vertex 0.932021 1.11012 2.60546 + vertex 0.929339 1.10785 2.60296 + endloop + endfacet + facet normal -0.547682 -0.247393 0.799275 + outer loop + vertex 0.932914 1.1065 2.60499 + vertex 0.929339 1.10785 2.60296 + vertex 0.932972 1.10319 2.604 + endloop + endfacet + facet normal -0.543874 -0.243576 0.803039 + outer loop + vertex 0.932972 1.10319 2.604 + vertex 0.929339 1.10785 2.60296 + vertex 0.930156 1.10241 2.60186 + endloop + endfacet + facet normal -0.560454 -0.241739 0.792119 + outer loop + vertex 0.932914 1.1065 2.60499 + vertex 0.935243 1.10707 2.60681 + vertex 0.932021 1.11012 2.60546 + endloop + endfacet + facet normal -0.553519 -0.229454 0.800604 + outer loop + vertex 0.929019 1.11264 2.60411 + vertex 0.929339 1.10785 2.60296 + vertex 0.932021 1.11012 2.60546 + endloop + endfacet + facet normal -0.557069 -0.236039 0.796216 + outer loop + vertex 0.930933 1.11466 2.60605 + vertex 0.929019 1.11264 2.60411 + vertex 0.932021 1.11012 2.60546 + endloop + endfacet + facet normal -0.563999 -0.237031 0.791025 + outer loop + vertex 0.932021 1.11012 2.60546 + vertex 0.934919 1.11184 2.60804 + vertex 0.930933 1.11466 2.60605 + endloop + endfacet + facet normal -0.561029 -0.24265 0.791434 + outer loop + vertex 0.935243 1.10707 2.60681 + vertex 0.934919 1.11184 2.60804 + vertex 0.932021 1.11012 2.60546 + endloop + endfacet + facet normal -0.550004 -0.244879 0.798455 + outer loop + vertex 0.927238 1.11717 2.60427 + vertex 0.929019 1.11264 2.60411 + vertex 0.930933 1.11466 2.60605 + endloop + endfacet + facet normal -0.541944 -0.224974 0.809743 + outer loop + vertex 0.929663 1.11846 2.60625 + vertex 0.927238 1.11717 2.60427 + vertex 0.930933 1.11466 2.60605 + endloop + endfacet + facet normal -0.56696 -0.232309 0.790309 + outer loop + vertex 0.930933 1.11466 2.60605 + vertex 0.932896 1.11781 2.60838 + vertex 0.929663 1.11846 2.60625 + endloop + endfacet + facet normal -0.563429 -0.235646 0.791845 + outer loop + vertex 0.934919 1.11184 2.60804 + vertex 0.932896 1.11781 2.60838 + vertex 0.930933 1.11466 2.60605 + endloop + endfacet + facet normal -0.543463 -0.221869 0.809582 + outer loop + vertex 0.927238 1.11717 2.60427 + vertex 0.929663 1.11846 2.60625 + vertex 0.927538 1.12083 2.60548 + endloop + endfacet + facet normal -0.556603 -0.238095 0.795929 + outer loop + vertex 0.929663 1.11846 2.60625 + vertex 0.929658 1.12195 2.60729 + vertex 0.927538 1.12083 2.60548 + endloop + endfacet + facet normal -0.566968 -0.236098 0.78918 + outer loop + vertex 0.929663 1.11846 2.60625 + vertex 0.932896 1.11781 2.60838 + vertex 0.929658 1.12195 2.60729 + endloop + endfacet + facet normal -0.564481 -0.233477 0.791739 + outer loop + vertex 0.932896 1.11781 2.60838 + vertex 0.932493 1.12284 2.60958 + vertex 0.929658 1.12195 2.60729 + endloop + endfacet + facet normal -0.559142 -0.220375 0.799247 + outer loop + vertex 0.93261 1.12634 2.61065 + vertex 0.931283 1.13018 2.61078 + vertex 0.928844 1.12745 2.60832 + endloop + endfacet + facet normal -0.559534 -0.225016 0.797677 + outer loop + vertex 0.93261 1.12634 2.61065 + vertex 0.928844 1.12745 2.60832 + vertex 0.932493 1.12284 2.60958 + endloop + endfacet + facet normal -0.565286 -0.231173 0.79184 + outer loop + vertex 0.932493 1.12284 2.60958 + vertex 0.928844 1.12745 2.60832 + vertex 0.929658 1.12195 2.60729 + endloop + endfacet + facet normal -0.507339 -0.203785 0.837304 + outer loop + vertex 0.93261 1.12634 2.61065 + vertex 0.935238 1.12777 2.61259 + vertex 0.931283 1.13018 2.61078 + endloop + endfacet + facet normal -0.559279 -0.220208 0.799197 + outer loop + vertex 0.927895 1.13303 2.60919 + vertex 0.928844 1.12745 2.60832 + vertex 0.931283 1.13018 2.61078 + endloop + endfacet + facet normal -0.564553 -0.23011 0.792672 + outer loop + vertex 0.930006 1.1339 2.61095 + vertex 0.927895 1.13303 2.60919 + vertex 0.931283 1.13018 2.61078 + endloop + endfacet + facet normal -0.539268 -0.22234 0.812253 + outer loop + vertex 0.931283 1.13018 2.61078 + vertex 0.932947 1.13278 2.61259 + vertex 0.930006 1.1339 2.61095 + endloop + endfacet + facet normal -0.520771 -0.239248 0.819486 + outer loop + vertex 0.935238 1.12777 2.61259 + vertex 0.932947 1.13278 2.61259 + vertex 0.931283 1.13018 2.61078 + endloop + endfacet + facet normal -0.567184 -0.223679 0.792635 + outer loop + vertex 0.927895 1.13303 2.60919 + vertex 0.930006 1.1339 2.61095 + vertex 0.927825 1.13642 2.6101 + endloop + endfacet + facet normal -0.572289 -0.229955 0.787151 + outer loop + vertex 0.930006 1.1339 2.61095 + vertex 0.930114 1.13699 2.61193 + vertex 0.927825 1.13642 2.6101 + endloop + endfacet + facet normal -0.541681 -0.237149 0.806438 + outer loop + vertex 0.930006 1.1339 2.61095 + vertex 0.932947 1.13278 2.61259 + vertex 0.930114 1.13699 2.61193 + endloop + endfacet + facet normal -0.534111 -0.23097 0.813252 + outer loop + vertex 0.932947 1.13278 2.61259 + vertex 0.933607 1.13687 2.61419 + vertex 0.930114 1.13699 2.61193 + endloop + endfacet + facet normal -0.53377 -0.205816 0.820201 + outer loop + vertex 0.933163 1.14118 2.61512 + vertex 0.931896 1.14539 2.61536 + vertex 0.929782 1.1418 2.61308 + endloop + endfacet + facet normal -0.534191 -0.231611 0.813017 + outer loop + vertex 0.933163 1.14118 2.61512 + vertex 0.929782 1.1418 2.61308 + vertex 0.933607 1.13687 2.61419 + endloop + endfacet + facet normal -0.534057 -0.231479 0.813143 + outer loop + vertex 0.933607 1.13687 2.61419 + vertex 0.929782 1.1418 2.61308 + vertex 0.930114 1.13699 2.61193 + endloop + endfacet + facet normal -0.397593 -0.169337 0.901801 + outer loop + vertex 0.933163 1.14118 2.61512 + vertex 0.936115 1.14343 2.61685 + vertex 0.931896 1.14539 2.61536 + endloop + endfacet + facet normal -0.530675 -0.208486 0.821533 + outer loop + vertex 0.92785 1.14779 2.61335 + vertex 0.929782 1.1418 2.61308 + vertex 0.931896 1.14539 2.61536 + endloop + endfacet + facet normal -0.533764 -0.217267 0.817246 + outer loop + vertex 0.930858 1.15023 2.61596 + vertex 0.92785 1.14779 2.61335 + vertex 0.931896 1.14539 2.61536 + endloop + endfacet + facet normal -0.421759 -0.201612 0.884009 + outer loop + vertex 0.931896 1.14539 2.61536 + vertex 0.934649 1.14857 2.6174 + vertex 0.930858 1.15023 2.61596 + endloop + endfacet + facet normal -0.411785 -0.211727 0.886343 + outer loop + vertex 0.936115 1.14343 2.61685 + vertex 0.934649 1.14857 2.6174 + vertex 0.931896 1.14539 2.61536 + endloop + endfacet + facet normal -0.5288 -0.224704 0.818461 + outer loop + vertex 0.92765 1.15271 2.61457 + vertex 0.92785 1.14779 2.61335 + vertex 0.930858 1.15023 2.61596 + endloop + endfacet + facet normal -0.530364 -0.227765 0.816601 + outer loop + vertex 0.930054 1.15397 2.61649 + vertex 0.92765 1.15271 2.61457 + vertex 0.930858 1.15023 2.61596 + endloop + endfacet + facet normal -0.428207 -0.214393 0.877881 + outer loop + vertex 0.930858 1.15023 2.61596 + vertex 0.933468 1.15354 2.61805 + vertex 0.930054 1.15397 2.61649 + endloop + endfacet + facet normal -0.426089 -0.2164 0.878419 + outer loop + vertex 0.934649 1.14857 2.6174 + vertex 0.933468 1.15354 2.61805 + vertex 0.930858 1.15023 2.61596 + endloop + endfacet + facet normal -0.533964 -0.220408 0.816274 + outer loop + vertex 0.92765 1.15271 2.61457 + vertex 0.930054 1.15397 2.61649 + vertex 0.927889 1.15615 2.61566 + endloop + endfacet + facet normal -0.516226 -0.196151 0.833688 + outer loop + vertex 0.930054 1.15397 2.61649 + vertex 0.930439 1.15762 2.61758 + vertex 0.927889 1.15615 2.61566 + endloop + endfacet + facet normal -0.428252 -0.218415 0.876867 + outer loop + vertex 0.930054 1.15397 2.61649 + vertex 0.933468 1.15354 2.61805 + vertex 0.930439 1.15762 2.61758 + endloop + endfacet + facet normal -0.424504 -0.21534 0.879446 + outer loop + vertex 0.933468 1.15354 2.61805 + vertex 0.933532 1.15706 2.61894 + vertex 0.930439 1.15762 2.61758 + endloop + endfacet + facet normal -0.424036 -0.207898 0.88146 + outer loop + vertex 0.933532 1.15706 2.61894 + vertex 0.932688 1.1611 2.61949 + vertex 0.930439 1.15762 2.61758 + endloop + endfacet + facet normal -0.444659 -0.19109 0.875079 + outer loop + vertex 0.930439 1.15762 2.61758 + vertex 0.932688 1.1611 2.61949 + vertex 0.928618 1.16196 2.61761 + endloop + endfacet + facet normal -0.46152 -0.247985 0.851765 + outer loop + vertex 0.932062 1.1657 2.62038 + vertex 0.930623 1.16898 2.62055 + vertex 0.927808 1.16693 2.61843 + endloop + endfacet + facet normal -0.45909 -0.229144 0.858329 + outer loop + vertex 0.932062 1.1657 2.62038 + vertex 0.927808 1.16693 2.61843 + vertex 0.932688 1.1611 2.61949 + endloop + endfacet + facet normal -0.446825 -0.217143 0.867869 + outer loop + vertex 0.932688 1.1611 2.61949 + vertex 0.927808 1.16693 2.61843 + vertex 0.928618 1.16196 2.61761 + endloop + endfacet + facet normal -0.28293 -0.174382 0.943155 + outer loop + vertex 0.932062 1.1657 2.62038 + vertex 0.935094 1.16876 2.62186 + vertex 0.930623 1.16898 2.62055 + endloop + endfacet + facet normal -0.458135 -0.252998 0.852117 + outer loop + vertex 0.927808 1.16693 2.61843 + vertex 0.930623 1.16898 2.62055 + vertex 0.928201 1.17123 2.61992 + endloop + endfacet + facet normal -0.3967 -0.172978 0.901503 + outer loop + vertex 0.930623 1.16898 2.62055 + vertex 0.93122 1.17335 2.62166 + vertex 0.928201 1.17123 2.61992 + endloop + endfacet + facet normal -0.282731 -0.19788 0.938566 + outer loop + vertex 0.930623 1.16898 2.62055 + vertex 0.935094 1.16876 2.62186 + vertex 0.93122 1.17335 2.62166 + endloop + endfacet + facet normal -0.25419 -0.173235 0.951513 + outer loop + vertex 0.935094 1.16876 2.62186 + vertex 0.935306 1.1741 2.62288 + vertex 0.93122 1.17335 2.62166 + endloop + endfacet + facet normal -0.253427 -0.176705 0.951078 + outer loop + vertex 0.935306 1.1741 2.62288 + vertex 0.93396 1.17802 2.62325 + vertex 0.93122 1.17335 2.62166 + endloop + endfacet + facet normal -0.284297 -0.156785 0.94583 + outer loop + vertex 0.93122 1.17335 2.62166 + vertex 0.93396 1.17802 2.62325 + vertex 0.929831 1.17862 2.62211 + endloop + endfacet + facet normal -0.286955 -0.186939 0.939527 + outer loop + vertex 0.93396 1.17802 2.62325 + vertex 0.932466 1.18195 2.62358 + vertex 0.929831 1.17862 2.62211 + endloop + endfacet + facet normal -0.316583 -0.161372 0.934737 + outer loop + vertex 0.929831 1.17862 2.62211 + vertex 0.932466 1.18195 2.62358 + vertex 0.928697 1.18379 2.62262 + endloop + endfacet + facet normal -0.31854 -0.16617 0.933231 + outer loop + vertex 0.932466 1.18195 2.62358 + vertex 0.93269 1.18688 2.62453 + vertex 0.928697 1.18379 2.62262 + endloop + endfacet + facet normal -0.280229 -0.216839 0.935122 + outer loop + vertex 0.928697 1.18379 2.62262 + vertex 0.93269 1.18688 2.62453 + vertex 0.928931 1.18746 2.62354 + endloop + endfacet + facet normal -0.297975 -0.238007 0.924426 + outer loop + vertex 0.932521 1.19115 2.62543 + vertex 0.930923 1.19407 2.62567 + vertex 0.928411 1.19144 2.62418 + endloop + endfacet + facet normal -0.298017 -0.208116 0.931597 + outer loop + vertex 0.932521 1.19115 2.62543 + vertex 0.928411 1.19144 2.62418 + vertex 0.93269 1.18688 2.62453 + endloop + endfacet + facet normal -0.277678 -0.188219 0.942056 + outer loop + vertex 0.93269 1.18688 2.62453 + vertex 0.928411 1.19144 2.62418 + vertex 0.928931 1.18746 2.62354 + endloop + endfacet + facet normal -0.153782 -0.163267 0.974523 + outer loop + vertex 0.932521 1.19115 2.62543 + vertex 0.935346 1.19424 2.6264 + vertex 0.930923 1.19407 2.62567 + endloop + endfacet + facet normal -0.310564 -0.225427 0.923435 + outer loop + vertex 0.928411 1.19144 2.62418 + vertex 0.930923 1.19407 2.62567 + vertex 0.928123 1.19597 2.62519 + endloop + endfacet + facet normal -0.266514 -0.153606 0.951512 + outer loop + vertex 0.930923 1.19407 2.62567 + vertex 0.931156 1.19835 2.62643 + vertex 0.928123 1.19597 2.62519 + endloop + endfacet + facet normal -0.153748 -0.163799 0.974439 + outer loop + vertex 0.930923 1.19407 2.62567 + vertex 0.935346 1.19424 2.6264 + vertex 0.931156 1.19835 2.62643 + endloop + endfacet + facet normal -0.145984 -0.155907 0.976925 + outer loop + vertex 0.935346 1.19424 2.6264 + vertex 0.935257 1.19908 2.62716 + vertex 0.931156 1.19835 2.62643 + endloop + endfacet + facet normal -0.153185 -0.119469 0.980949 + outer loop + vertex 0.935257 1.19908 2.62716 + vertex 0.934029 1.20302 2.62744 + vertex 0.931156 1.19835 2.62643 + endloop + endfacet + facet normal -0.181019 -0.101733 0.978204 + outer loop + vertex 0.931156 1.19835 2.62643 + vertex 0.934029 1.20302 2.62744 + vertex 0.929857 1.20352 2.62672 + endloop + endfacet + facet normal -0.176686 -0.0597554 0.982452 + outer loop + vertex 0.934029 1.20302 2.62744 + vertex 0.933392 1.20794 2.62763 + vertex 0.929857 1.20352 2.62672 + endloop + endfacet + facet normal -0.197574 -0.0424055 0.97937 + outer loop + vertex 0.929857 1.20352 2.62672 + vertex 0.933392 1.20794 2.62763 + vertex 0.9293 1.20804 2.62681 + endloop + endfacet + facet normal -0.385726 0.0351063 0.921945 + outer loop + vertex 0.92872 1.21399 2.62651 + vertex 0.925725 1.2121 2.62533 + vertex 0.928458 1.21105 2.62651 + endloop + endfacet + facet normal -0.252939 0.0233147 0.967201 + outer loop + vertex 0.928458 1.21105 2.62651 + vertex 0.932558 1.21354 2.62752 + vertex 0.92872 1.21399 2.62651 + endloop + endfacet + facet normal -0.25382 0.0248743 0.966932 + outer loop + vertex 0.928458 1.21105 2.62651 + vertex 0.9293 1.20804 2.62681 + vertex 0.932558 1.21354 2.62752 + endloop + endfacet + facet normal -0.196956 -0.0105547 0.980356 + outer loop + vertex 0.9293 1.20804 2.62681 + vertex 0.933392 1.20794 2.62763 + vertex 0.932558 1.21354 2.62752 + endloop + endfacet + facet normal -0.358279 -0.0154504 0.933487 + outer loop + vertex 0.925725 1.2121 2.62533 + vertex 0.92872 1.21399 2.62651 + vertex 0.926951 1.21594 2.62586 + endloop + endfacet + facet normal -0.343581 -0.000259578 0.939123 + outer loop + vertex 0.92872 1.21399 2.62651 + vertex 0.930322 1.21839 2.62709 + vertex 0.926951 1.21594 2.62586 + endloop + endfacet + facet normal -0.259185 -0.0344972 0.965212 + outer loop + vertex 0.92872 1.21399 2.62651 + vertex 0.932558 1.21354 2.62752 + vertex 0.930322 1.21839 2.62709 + endloop + endfacet + facet normal -0.220488 -0.0157588 0.975262 + outer loop + vertex 0.932558 1.21354 2.62752 + vertex 0.934835 1.2192 2.62813 + vertex 0.930322 1.21839 2.62709 + endloop + endfacet + facet normal -0.208691 -0.0807879 0.974639 + outer loop + vertex 0.934835 1.2192 2.62813 + vertex 0.93421 1.22332 2.62833 + vertex 0.930322 1.21839 2.62709 + endloop + endfacet + facet normal -0.20421 -0.0844823 0.975275 + outer loop + vertex 0.930322 1.21839 2.62709 + vertex 0.93421 1.22332 2.62833 + vertex 0.929285 1.2242 2.62738 + endloop + endfacet + facet normal -0.212092 -0.137003 0.967599 + outer loop + vertex 0.93421 1.22332 2.62833 + vertex 0.93359 1.22794 2.62885 + vertex 0.929285 1.2242 2.62738 + endloop + endfacet + facet normal -0.187004 -0.166131 0.96821 + outer loop + vertex 0.929285 1.2242 2.62738 + vertex 0.93359 1.22794 2.62885 + vertex 0.929962 1.22883 2.6283 + endloop + endfacet + facet normal -0.187356 -0.167779 0.967857 + outer loop + vertex 0.93359 1.22794 2.62885 + vertex 0.93239 1.23156 2.62925 + vertex 0.929962 1.22883 2.6283 + endloop + endfacet + facet normal -0.21043 -0.146813 0.966522 + outer loop + vertex 0.929962 1.22883 2.6283 + vertex 0.93239 1.23156 2.62925 + vertex 0.928752 1.23245 2.62859 + endloop + endfacet + facet normal -0.21051 -0.147195 0.966447 + outer loop + vertex 0.93239 1.23156 2.62925 + vertex 0.932329 1.23631 2.62996 + vertex 0.928752 1.23245 2.62859 + endloop + endfacet + facet normal -0.213473 -0.144365 0.966223 + outer loop + vertex 0.928752 1.23245 2.62859 + vertex 0.932329 1.23631 2.62996 + vertex 0.927366 1.23641 2.62888 + endloop + endfacet + facet normal -0.207523 -0.15617 0.965684 + outer loop + vertex 0.932226 1.24084 2.63067 + vertex 0.930659 1.24392 2.63083 + vertex 0.927686 1.24123 2.62976 + endloop + endfacet + facet normal -0.207523 -0.156168 0.965684 + outer loop + vertex 0.932226 1.24084 2.63067 + vertex 0.927686 1.24123 2.62976 + vertex 0.932329 1.23631 2.62996 + endloop + endfacet + facet normal -0.213265 -0.161665 0.963526 + outer loop + vertex 0.932329 1.23631 2.62996 + vertex 0.927686 1.24123 2.62976 + vertex 0.927366 1.23641 2.62888 + endloop + endfacet + facet normal -0.11985 -0.112632 0.986382 + outer loop + vertex 0.932226 1.24084 2.63067 + vertex 0.935228 1.24398 2.63139 + vertex 0.930659 1.24392 2.63083 + endloop + endfacet + facet normal -0.202692 -0.16157 0.965821 + outer loop + vertex 0.927686 1.24123 2.62976 + vertex 0.930659 1.24392 2.63083 + vertex 0.927761 1.24577 2.63053 + endloop + endfacet + facet normal -0.172083 -0.111443 0.978758 + outer loop + vertex 0.930659 1.24392 2.63083 + vertex 0.930911 1.24831 2.63137 + vertex 0.927761 1.24577 2.63053 + endloop + endfacet + facet normal -0.119778 -0.115349 0.986077 + outer loop + vertex 0.930659 1.24392 2.63083 + vertex 0.935228 1.24398 2.63139 + vertex 0.930911 1.24831 2.63137 + endloop + endfacet + facet normal -0.102242 -0.0978743 0.989933 + outer loop + vertex 0.935228 1.24398 2.63139 + vertex 0.935224 1.24901 2.63189 + vertex 0.930911 1.24831 2.63137 + endloop + endfacet + facet normal -0.103213 -0.0921476 0.990382 + outer loop + vertex 0.935224 1.24901 2.63189 + vertex 0.933933 1.25309 2.63213 + vertex 0.930911 1.24831 2.63137 + endloop + endfacet + facet normal -0.101209 -0.0934285 0.990469 + outer loop + vertex 0.930911 1.24831 2.63137 + vertex 0.933933 1.25309 2.63213 + vertex 0.928921 1.25405 2.63171 + endloop + endfacet + facet normal -0.10067 -0.0904553 0.990799 + outer loop + vertex 0.933933 1.25309 2.63213 + vertex 0.933471 1.25802 2.63254 + vertex 0.928921 1.25405 2.63171 + endloop + endfacet + facet normal -0.0893789 -0.103346 0.990622 + outer loop + vertex 0.928921 1.25405 2.63171 + vertex 0.933471 1.25802 2.63254 + vertex 0.929701 1.25898 2.6323 + endloop + endfacet + facet normal -0.0862815 -0.0907318 0.992131 + outer loop + vertex 0.933471 1.25802 2.63254 + vertex 0.933432 1.26291 2.63298 + vertex 0.929701 1.25898 2.6323 + endloop + endfacet + facet normal -0.0903795 -0.0868434 0.992114 + outer loop + vertex 0.929701 1.25898 2.6323 + vertex 0.933432 1.26291 2.63298 + vertex 0.928768 1.26308 2.63257 + endloop + endfacet + facet normal -0.0905994 -0.0948858 0.991357 + outer loop + vertex 0.933432 1.26291 2.63298 + vertex 0.933388 1.26786 2.63345 + vertex 0.928768 1.26308 2.63257 + endloop + endfacet + facet normal -0.0876013 -0.0977832 0.991345 + outer loop + vertex 0.928768 1.26308 2.63257 + vertex 0.933388 1.26786 2.63345 + vertex 0.928635 1.26813 2.63306 + endloop + endfacet + facet normal -0.0878749 -0.103475 0.990743 + outer loop + vertex 0.933388 1.26786 2.63345 + vertex 0.933488 1.27286 2.63398 + vertex 0.928635 1.26813 2.63306 + endloop + endfacet + facet normal -0.082834 -0.10862 0.990626 + outer loop + vertex 0.928635 1.26813 2.63306 + vertex 0.933488 1.27286 2.63398 + vertex 0.928707 1.27298 2.6336 + endloop + endfacet + facet normal -0.0829288 -0.114461 0.98996 + outer loop + vertex 0.933488 1.27286 2.63398 + vertex 0.933257 1.27764 2.63452 + vertex 0.928707 1.27298 2.6336 + endloop + endfacet + facet normal -0.0844068 -0.113027 0.99 + outer loop + vertex 0.928707 1.27298 2.6336 + vertex 0.933257 1.27764 2.63452 + vertex 0.928222 1.27757 2.63408 + endloop + endfacet + facet normal -0.0841924 -0.121663 0.988994 + outer loop + vertex 0.933257 1.27764 2.63452 + vertex 0.932094 1.28256 2.63502 + vertex 0.928222 1.27757 2.63408 + endloop + endfacet + facet normal -0.095016 -0.113264 0.989011 + outer loop + vertex 0.928222 1.27757 2.63408 + vertex 0.932094 1.28256 2.63502 + vertex 0.927087 1.2814 2.63441 + endloop + endfacet + facet normal -0.0955798 -0.125629 0.987462 + outer loop + vertex 0.932634 1.28681 2.63558 + vertex 0.930919 1.28946 2.63575 + vertex 0.92764 1.2864 2.63505 + endloop + endfacet + facet normal -0.0962549 -0.118345 0.988296 + outer loop + vertex 0.932634 1.28681 2.63558 + vertex 0.92764 1.2864 2.63505 + vertex 0.932094 1.28256 2.63502 + endloop + endfacet + facet normal -0.0943255 -0.116114 0.988747 + outer loop + vertex 0.932094 1.28256 2.63502 + vertex 0.92764 1.2864 2.63505 + vertex 0.927087 1.2814 2.63441 + endloop + endfacet + facet normal -0.0572148 -0.101205 0.993219 + outer loop + vertex 0.932634 1.28681 2.63558 + vertex 0.935116 1.29011 2.63606 + vertex 0.930919 1.28946 2.63575 + endloop + endfacet + facet normal -0.100886 -0.119977 0.987637 + outer loop + vertex 0.92764 1.2864 2.63505 + vertex 0.930919 1.28946 2.63575 + vertex 0.927916 1.29094 2.63563 + endloop + endfacet + facet normal -0.0894873 -0.0965803 0.991294 + outer loop + vertex 0.930919 1.28946 2.63575 + vertex 0.931094 1.29359 2.63617 + vertex 0.927916 1.29094 2.63563 + endloop + endfacet + facet normal -0.057708 -0.0981537 0.993497 + outer loop + vertex 0.930919 1.28946 2.63575 + vertex 0.935116 1.29011 2.63606 + vertex 0.931094 1.29359 2.63617 + endloop + endfacet + facet normal -0.05427 -0.0941982 0.994073 + outer loop + vertex 0.935116 1.29011 2.63606 + vertex 0.935356 1.29423 2.63647 + vertex 0.931094 1.29359 2.63617 + endloop + endfacet + facet normal -0.0547971 -0.0908137 0.994359 + outer loop + vertex 0.935356 1.29423 2.63647 + vertex 0.934021 1.29811 2.63675 + vertex 0.931094 1.29359 2.63617 + endloop + endfacet + facet normal -0.0568048 -0.0895135 0.994364 + outer loop + vertex 0.931094 1.29359 2.63617 + vertex 0.934021 1.29811 2.63675 + vertex 0.928978 1.29902 2.63654 + endloop + endfacet + facet normal -0.0569562 -0.0903698 0.994278 + outer loop + vertex 0.934021 1.29811 2.63675 + vertex 0.93353 1.30304 2.63717 + vertex 0.928978 1.29902 2.63654 + endloop + endfacet + facet normal -0.0480929 -0.100326 0.993792 + outer loop + vertex 0.928978 1.29902 2.63654 + vertex 0.93353 1.30304 2.63717 + vertex 0.929755 1.30393 2.63707 + endloop + endfacet + facet normal -0.0463657 -0.0929448 0.994591 + outer loop + vertex 0.93353 1.30304 2.63717 + vertex 0.933466 1.30789 2.63762 + vertex 0.929755 1.30393 2.63707 + endloop + endfacet + facet normal -0.0458903 -0.0933885 0.994572 + outer loop + vertex 0.929755 1.30393 2.63707 + vertex 0.933466 1.30789 2.63762 + vertex 0.928851 1.30779 2.63739 + endloop + endfacet + facet normal -0.0458903 -0.0933873 0.994572 + outer loop + vertex 0.933466 1.30789 2.63762 + vertex 0.933309 1.31269 2.63806 + vertex 0.928851 1.30779 2.63739 + endloop + endfacet + facet normal -0.0443484 -0.0947836 0.99451 + outer loop + vertex 0.928851 1.30779 2.63739 + vertex 0.933309 1.31269 2.63806 + vertex 0.928422 1.31255 2.63783 + endloop + endfacet + facet normal -0.0444308 -0.0921603 0.994752 + outer loop + vertex 0.933309 1.31269 2.63806 + vertex 0.933248 1.31767 2.63852 + vertex 0.928422 1.31255 2.63783 + endloop + endfacet + facet normal -0.0549427 0.0130905 0.998404 + outer loop + vertex 0.933404 1.75205 2.63365 + vertex 0.933365 1.757 2.63358 + vertex 0.928382 1.752 2.63337 + endloop + endfacet + facet normal -0.0254315 -0.0163638 0.999543 + outer loop + vertex 0.928382 1.752 2.63337 + vertex 0.933365 1.757 2.63358 + vertex 0.928313 1.75697 2.63345 + endloop + endfacet + facet normal -0.118417 0.132552 0.984077 + outer loop + vertex 0.928777 1.81177 2.6269 + vertex 0.933008 1.81651 2.62677 + vertex 0.928543 1.81609 2.62629 + endloop + endfacet + facet normal -0.117734 0.123791 0.985299 + outer loop + vertex 0.928543 1.81609 2.62629 + vertex 0.933008 1.81651 2.62677 + vertex 0.932452 1.82014 2.62624 + endloop + endfacet + facet normal -0.217201 0.193971 0.95666 + outer loop + vertex 0.927818 1.82159 2.62494 + vertex 0.933289 1.82667 2.62515 + vertex 0.928212 1.82666 2.624 + endloop + endfacet + facet normal -0.218394 0.163653 0.96204 + outer loop + vertex 0.933289 1.82667 2.62515 + vertex 0.933272 1.83179 2.62427 + vertex 0.928212 1.82666 2.624 + endloop + endfacet + facet normal -0.210565 0.155756 0.965092 + outer loop + vertex 0.928212 1.82666 2.624 + vertex 0.933272 1.83179 2.62427 + vertex 0.928514 1.83175 2.62324 + endloop + endfacet + facet normal -0.210386 0.162358 0.964042 + outer loop + vertex 0.933272 1.83179 2.62427 + vertex 0.933373 1.83693 2.62343 + vertex 0.928514 1.83175 2.62324 + endloop + endfacet + facet normal -0.222553 0.17394 0.959278 + outer loop + vertex 0.928514 1.83175 2.62324 + vertex 0.933373 1.83693 2.62343 + vertex 0.928283 1.83691 2.62225 + endloop + endfacet + facet normal -0.222889 0.163926 0.960962 + outer loop + vertex 0.933373 1.83693 2.62343 + vertex 0.933533 1.84209 2.62259 + vertex 0.928283 1.83691 2.62225 + endloop + endfacet + facet normal -0.206814 0.147254 0.967235 + outer loop + vertex 0.928283 1.83691 2.62225 + vertex 0.933533 1.84209 2.62259 + vertex 0.92932 1.84243 2.62163 + endloop + endfacet + facet normal -0.206524 0.149907 0.96689 + outer loop + vertex 0.933533 1.84209 2.62259 + vertex 0.933533 1.84672 2.62187 + vertex 0.92932 1.84243 2.62163 + endloop + endfacet + facet normal -0.195788 0.139154 0.970723 + outer loop + vertex 0.92932 1.84243 2.62163 + vertex 0.933533 1.84672 2.62187 + vertex 0.929779 1.84656 2.62114 + endloop + endfacet + facet normal -0.391027 0.295515 0.871647 + outer loop + vertex 0.931785 1.85218 2.62059 + vertex 0.928337 1.85132 2.61933 + vertex 0.929908 1.84941 2.62069 + endloop + endfacet + facet normal -0.22592 0.186662 0.956095 + outer loop + vertex 0.929908 1.84941 2.62069 + vertex 0.932894 1.8501 2.62126 + vertex 0.931785 1.85218 2.62059 + endloop + endfacet + facet normal -0.221264 0.162048 0.961656 + outer loop + vertex 0.929908 1.84941 2.62069 + vertex 0.929779 1.84656 2.62114 + vertex 0.932894 1.8501 2.62126 + endloop + endfacet + facet normal -0.195791 0.139347 0.970695 + outer loop + vertex 0.929779 1.84656 2.62114 + vertex 0.933533 1.84672 2.62187 + vertex 0.932894 1.8501 2.62126 + endloop + endfacet + facet normal -0.204511 0.233866 0.950517 + outer loop + vertex 0.931785 1.85218 2.62059 + vertex 0.935349 1.85402 2.6209 + vertex 0.933218 1.85642 2.61985 + endloop + endfacet + facet normal -0.389714 0.283497 0.876215 + outer loop + vertex 0.931785 1.85218 2.62059 + vertex 0.933218 1.85642 2.61985 + vertex 0.928337 1.85132 2.61933 + endloop + endfacet + facet normal -0.355985 0.248708 0.900788 + outer loop + vertex 0.928337 1.85132 2.61933 + vertex 0.933218 1.85642 2.61985 + vertex 0.928165 1.85671 2.61777 + endloop + endfacet + facet normal -0.191123 0.206375 0.959626 + outer loop + vertex 0.935349 1.85402 2.6209 + vertex 0.931785 1.85218 2.62059 + vertex 0.932894 1.8501 2.62126 + endloop + endfacet + facet normal -0.3628 0.19896 0.91038 + outer loop + vertex 0.933218 1.85642 2.61985 + vertex 0.93337 1.8616 2.61878 + vertex 0.928165 1.85671 2.61777 + endloop + endfacet + facet normal -0.341816 0.173925 0.923532 + outer loop + vertex 0.928165 1.85671 2.61777 + vertex 0.93337 1.8616 2.61878 + vertex 0.929241 1.86219 2.61714 + endloop + endfacet + facet normal -0.339142 0.187905 0.921778 + outer loop + vertex 0.93337 1.8616 2.61878 + vertex 0.933619 1.86667 2.61784 + vertex 0.929241 1.86219 2.61714 + endloop + endfacet + facet normal -0.35183 0.201506 0.914117 + outer loop + vertex 0.929241 1.86219 2.61714 + vertex 0.933619 1.86667 2.61784 + vertex 0.929397 1.86689 2.61617 + endloop + endfacet + facet normal -0.466506 0.187662 0.864381 + outer loop + vertex 0.930887 1.87421 2.61536 + vertex 0.928441 1.8734 2.61421 + vertex 0.9288 1.87088 2.61495 + endloop + endfacet + facet normal -0.37898 0.126617 0.916702 + outer loop + vertex 0.9288 1.87088 2.61495 + vertex 0.933318 1.87174 2.6167 + vertex 0.930887 1.87421 2.61536 + endloop + endfacet + facet normal -0.387974 0.214195 0.896436 + outer loop + vertex 0.9288 1.87088 2.61495 + vertex 0.929397 1.86689 2.61617 + vertex 0.933318 1.87174 2.6167 + endloop + endfacet + facet normal -0.353845 0.184385 0.916949 + outer loop + vertex 0.929397 1.86689 2.61617 + vertex 0.933619 1.86667 2.61784 + vertex 0.933318 1.87174 2.6167 + endloop + endfacet + facet normal -0.475519 0.239708 0.846417 + outer loop + vertex 0.929223 1.87681 2.61369 + vertex 0.928441 1.8734 2.61421 + vertex 0.930887 1.87421 2.61536 + endloop + endfacet + facet normal -0.482314 0.233925 0.844188 + outer loop + vertex 0.932285 1.87745 2.61526 + vertex 0.929223 1.87681 2.61369 + vertex 0.930887 1.87421 2.61536 + endloop + endfacet + facet normal -0.336007 0.17326 0.925786 + outer loop + vertex 0.930887 1.87421 2.61536 + vertex 0.934432 1.87643 2.61623 + vertex 0.932285 1.87745 2.61526 + endloop + endfacet + facet normal -0.336201 0.173625 0.925648 + outer loop + vertex 0.933318 1.87174 2.6167 + vertex 0.934432 1.87643 2.61623 + vertex 0.930887 1.87421 2.61536 + endloop + endfacet + facet normal -0.376584 0.26213 0.888523 + outer loop + vertex 0.932285 1.87745 2.61526 + vertex 0.934727 1.8794 2.61572 + vertex 0.933175 1.88139 2.61447 + endloop + endfacet + facet normal -0.483972 0.274884 0.830789 + outer loop + vertex 0.932285 1.87745 2.61526 + vertex 0.933175 1.88139 2.61447 + vertex 0.929223 1.87681 2.61369 + endloop + endfacet + facet normal -0.459565 0.250136 0.852192 + outer loop + vertex 0.929223 1.87681 2.61369 + vertex 0.933175 1.88139 2.61447 + vertex 0.929436 1.88162 2.61239 + endloop + endfacet + facet normal -0.327101 0.191551 0.925372 + outer loop + vertex 0.934727 1.8794 2.61572 + vertex 0.932285 1.87745 2.61526 + vertex 0.934432 1.87643 2.61623 + endloop + endfacet + facet normal -0.569904 0.244256 0.784569 + outer loop + vertex 0.930191 1.88883 2.61082 + vertex 0.926926 1.88573 2.60941 + vertex 0.929157 1.88493 2.61128 + endloop + endfacet + facet normal -0.458608 0.223625 0.860041 + outer loop + vertex 0.929157 1.88493 2.61128 + vertex 0.933058 1.88666 2.61291 + vertex 0.930191 1.88883 2.61082 + endloop + endfacet + facet normal -0.464652 0.24625 0.850564 + outer loop + vertex 0.929157 1.88493 2.61128 + vertex 0.929436 1.88162 2.61239 + vertex 0.933058 1.88666 2.61291 + endloop + endfacet + facet normal -0.460767 0.243143 0.853566 + outer loop + vertex 0.929436 1.88162 2.61239 + vertex 0.933175 1.88139 2.61447 + vertex 0.933058 1.88666 2.61291 + endloop + endfacet + facet normal -0.562546 0.232469 0.79341 + outer loop + vertex 0.927343 1.89051 2.6083 + vertex 0.926926 1.88573 2.60941 + vertex 0.930191 1.88883 2.61082 + endloop + endfacet + facet normal -0.570135 0.217776 0.792161 + outer loop + vertex 0.931261 1.89354 2.61029 + vertex 0.927343 1.89051 2.6083 + vertex 0.930191 1.88883 2.61082 + endloop + endfacet + facet normal -0.451396 0.199488 0.869739 + outer loop + vertex 0.930191 1.88883 2.61082 + vertex 0.934215 1.89227 2.61211 + vertex 0.931261 1.89354 2.61029 + endloop + endfacet + facet normal -0.463077 0.217034 0.859335 + outer loop + vertex 0.933058 1.88666 2.61291 + vertex 0.934215 1.89227 2.61211 + vertex 0.930191 1.88883 2.61082 + endloop + endfacet + facet normal -0.569295 0.21597 0.793259 + outer loop + vertex 0.92925 1.89645 2.60805 + vertex 0.927343 1.89051 2.6083 + vertex 0.931261 1.89354 2.61029 + endloop + endfacet + facet normal -0.568523 0.216762 0.793597 + outer loop + vertex 0.93255 1.89739 2.61016 + vertex 0.92925 1.89645 2.60805 + vertex 0.931261 1.89354 2.61029 + endloop + endfacet + facet normal -0.446112 0.178574 0.876981 + outer loop + vertex 0.931261 1.89354 2.61029 + vertex 0.934852 1.89672 2.61147 + vertex 0.93255 1.89739 2.61016 + endloop + endfacet + facet normal -0.454948 0.191222 0.869745 + outer loop + vertex 0.934215 1.89227 2.61211 + vertex 0.934852 1.89672 2.61147 + vertex 0.931261 1.89354 2.61029 + endloop + endfacet + facet normal -0.500076 0.262803 0.825141 + outer loop + vertex 0.93255 1.89739 2.61016 + vertex 0.934964 1.89977 2.61087 + vertex 0.933235 1.90142 2.60929 + endloop + endfacet + facet normal -0.5714 0.26451 0.776876 + outer loop + vertex 0.93255 1.89739 2.61016 + vertex 0.933235 1.90142 2.60929 + vertex 0.92925 1.89645 2.60805 + endloop + endfacet + facet normal -0.554461 0.246425 0.794888 + outer loop + vertex 0.92925 1.89645 2.60805 + vertex 0.933235 1.90142 2.60929 + vertex 0.929444 1.9017 2.60656 + endloop + endfacet + facet normal -0.442643 0.189474 0.876451 + outer loop + vertex 0.934964 1.89977 2.61087 + vertex 0.93255 1.89739 2.61016 + vertex 0.934852 1.89672 2.61147 + endloop + endfacet + facet normal -0.560104 0.265179 0.784833 + outer loop + vertex 0.930706 1.909 2.60504 + vertex 0.928573 1.90802 2.60385 + vertex 0.929003 1.90578 2.60491 + endloop + endfacet + facet normal -0.542845 0.255463 0.800037 + outer loop + vertex 0.929003 1.90578 2.60491 + vertex 0.933102 1.90658 2.60744 + vertex 0.930706 1.909 2.60504 + endloop + endfacet + facet normal -0.542821 0.263772 0.797351 + outer loop + vertex 0.929003 1.90578 2.60491 + vertex 0.929444 1.9017 2.60656 + vertex 0.933102 1.90658 2.60744 + endloop + endfacet + facet normal -0.549595 0.270068 0.790575 + outer loop + vertex 0.929444 1.9017 2.60656 + vertex 0.933235 1.90142 2.60929 + vertex 0.933102 1.90658 2.60744 + endloop + endfacet + facet normal -0.559315 0.261121 0.786754 + outer loop + vertex 0.928583 1.91033 2.60309 + vertex 0.928573 1.90802 2.60385 + vertex 0.930706 1.909 2.60504 + endloop + endfacet + facet normal -0.564732 0.251445 0.786037 + outer loop + vertex 0.931037 1.9128 2.60406 + vertex 0.928583 1.91033 2.60309 + vertex 0.930706 1.909 2.60504 + endloop + endfacet + facet normal -0.539226 0.253611 0.803067 + outer loop + vertex 0.930706 1.909 2.60504 + vertex 0.93408 1.91177 2.60643 + vertex 0.931037 1.9128 2.60406 + endloop + endfacet + facet normal -0.541285 0.257431 0.800462 + outer loop + vertex 0.933102 1.90658 2.60744 + vertex 0.93408 1.91177 2.60643 + vertex 0.930706 1.909 2.60504 + endloop + endfacet + facet normal -0.519818 0.202338 0.829969 + outer loop + vertex 0.930639 1.91748 2.60243 + vertex 0.92646 1.91511 2.60039 + vertex 0.928651 1.91349 2.60216 + endloop + endfacet + facet normal -0.560039 0.244622 0.791528 + outer loop + vertex 0.928651 1.91349 2.60216 + vertex 0.928583 1.91033 2.60309 + vertex 0.931037 1.9128 2.60406 + endloop + endfacet + facet normal -0.565692 0.227686 0.79256 + outer loop + vertex 0.930639 1.91748 2.60243 + vertex 0.928651 1.91349 2.60216 + vertex 0.931037 1.9128 2.60406 + endloop + endfacet + facet normal -0.552743 0.231562 0.800534 + outer loop + vertex 0.930639 1.91748 2.60243 + vertex 0.931037 1.9128 2.60406 + vertex 0.9338 1.91579 2.60511 + endloop + endfacet + facet normal -0.566069 0.203904 0.798742 + outer loop + vertex 0.930639 1.91748 2.60243 + vertex 0.9338 1.91579 2.60511 + vertex 0.933492 1.91831 2.60424 + endloop + endfacet + facet normal -0.549217 0.226989 0.804261 + outer loop + vertex 0.9338 1.91579 2.60511 + vertex 0.931037 1.9128 2.60406 + vertex 0.93408 1.91177 2.60643 + endloop + endfacet + facet normal -0.527574 0.225368 0.81907 + outer loop + vertex 0.927038 1.92003 2.59941 + vertex 0.92646 1.91511 2.60039 + vertex 0.930639 1.91748 2.60243 + endloop + endfacet + facet normal -0.516102 0.243944 0.821055 + outer loop + vertex 0.93095 1.92316 2.60094 + vertex 0.927038 1.92003 2.59941 + vertex 0.930639 1.91748 2.60243 + endloop + endfacet + facet normal -0.568982 0.237939 0.787175 + outer loop + vertex 0.930639 1.91748 2.60243 + vertex 0.93408 1.92165 2.60366 + vertex 0.93095 1.92316 2.60094 + endloop + endfacet + facet normal -0.568685 0.2376 0.787492 + outer loop + vertex 0.933492 1.91831 2.60424 + vertex 0.93408 1.92165 2.60366 + vertex 0.930639 1.91748 2.60243 + endloop + endfacet + facet normal -0.517524 0.246542 0.819381 + outer loop + vertex 0.927994 1.92612 2.59819 + vertex 0.927038 1.92003 2.59941 + vertex 0.93095 1.92316 2.60094 + endloop + endfacet + facet normal -0.510647 0.255007 0.821103 + outer loop + vertex 0.931886 1.92724 2.60026 + vertex 0.927994 1.92612 2.59819 + vertex 0.93095 1.92316 2.60094 + endloop + endfacet + facet normal -0.560822 0.260568 0.785865 + outer loop + vertex 0.93095 1.92316 2.60094 + vertex 0.934327 1.92637 2.60229 + vertex 0.931886 1.92724 2.60026 + endloop + endfacet + facet normal -0.559459 0.258435 0.787539 + outer loop + vertex 0.93408 1.92165 2.60366 + vertex 0.934327 1.92637 2.60229 + vertex 0.93095 1.92316 2.60094 + endloop + endfacet + facet normal -0.552425 0.259384 0.792178 + outer loop + vertex 0.931886 1.92724 2.60026 + vertex 0.93433 1.92976 2.60114 + vertex 0.932012 1.93074 2.5992 + endloop + endfacet + facet normal -0.511592 0.265462 0.817193 + outer loop + vertex 0.931886 1.92724 2.60026 + vertex 0.932012 1.93074 2.5992 + vertex 0.927994 1.92612 2.59819 + endloop + endfacet + facet normal -0.515442 0.269637 0.813398 + outer loop + vertex 0.927994 1.92612 2.59819 + vertex 0.932012 1.93074 2.5992 + vertex 0.929214 1.93162 2.59714 + endloop + endfacet + facet normal -0.558144 0.267255 0.785525 + outer loop + vertex 0.93433 1.92976 2.60114 + vertex 0.931886 1.92724 2.60026 + vertex 0.934327 1.92637 2.60229 + endloop + endfacet + facet normal -0.431361 0.235436 0.870918 + outer loop + vertex 0.93074 1.93859 2.59588 + vertex 0.927009 1.93579 2.59479 + vertex 0.929463 1.93497 2.59622 + endloop + endfacet + facet normal -0.520603 0.261293 0.812834 + outer loop + vertex 0.929463 1.93497 2.59622 + vertex 0.933145 1.93609 2.59822 + vertex 0.93074 1.93859 2.59588 + endloop + endfacet + facet normal -0.520494 0.260173 0.813263 + outer loop + vertex 0.929463 1.93497 2.59622 + vertex 0.929214 1.93162 2.59714 + vertex 0.933145 1.93609 2.59822 + endloop + endfacet + facet normal -0.51944 0.258991 0.814313 + outer loop + vertex 0.929214 1.93162 2.59714 + vertex 0.932012 1.93074 2.5992 + vertex 0.933145 1.93609 2.59822 + endloop + endfacet + facet normal -0.432117 0.236723 0.870194 + outer loop + vertex 0.928164 1.94091 2.59397 + vertex 0.927009 1.93579 2.59479 + vertex 0.93074 1.93859 2.59588 + endloop + endfacet + facet normal -0.424716 0.245859 0.871303 + outer loop + vertex 0.932006 1.94229 2.59545 + vertex 0.928164 1.94091 2.59397 + vertex 0.93074 1.93859 2.59588 + endloop + endfacet + facet normal -0.517216 0.270688 0.811921 + outer loop + vertex 0.93074 1.93859 2.59588 + vertex 0.934282 1.94141 2.59719 + vertex 0.932006 1.94229 2.59545 + endloop + endfacet + facet normal -0.515455 0.267439 0.814115 + outer loop + vertex 0.933145 1.93609 2.59822 + vertex 0.934282 1.94141 2.59719 + vertex 0.93074 1.93859 2.59588 + endloop + endfacet + facet normal -0.491582 0.230409 0.839797 + outer loop + vertex 0.932006 1.94229 2.59545 + vertex 0.934475 1.9448 2.59621 + vertex 0.932011 1.94566 2.59453 + endloop + endfacet + facet normal -0.423383 0.239576 0.873699 + outer loop + vertex 0.932006 1.94229 2.59545 + vertex 0.932011 1.94566 2.59453 + vertex 0.928164 1.94091 2.59397 + endloop + endfacet + facet normal -0.416025 0.232994 0.878998 + outer loop + vertex 0.928164 1.94091 2.59397 + vertex 0.932011 1.94566 2.59453 + vertex 0.928079 1.94635 2.59248 + endloop + endfacet + facet normal -0.519244 0.265992 0.812179 + outer loop + vertex 0.934475 1.9448 2.59621 + vertex 0.932006 1.94229 2.59545 + vertex 0.934282 1.94141 2.59719 + endloop + endfacet + facet normal -0.41583 0.233772 0.878883 + outer loop + vertex 0.932011 1.94566 2.59453 + vertex 0.933271 1.95089 2.59373 + vertex 0.928079 1.94635 2.59248 + endloop + endfacet + facet normal -0.440019 0.267376 0.85726 + outer loop + vertex 0.928079 1.94635 2.59248 + vertex 0.933271 1.95089 2.59373 + vertex 0.929631 1.95162 2.59164 + endloop + endfacet + facet normal -0.39695 0.266183 0.878395 + outer loop + vertex 0.931458 1.95761 2.5906 + vertex 0.927883 1.95646 2.58933 + vertex 0.92996 1.95488 2.59075 + endloop + endfacet + facet normal -0.447459 0.292028 0.845281 + outer loop + vertex 0.92996 1.95488 2.59075 + vertex 0.933361 1.95593 2.59219 + vertex 0.931458 1.95761 2.5906 + endloop + endfacet + facet normal -0.445324 0.276502 0.851606 + outer loop + vertex 0.92996 1.95488 2.59075 + vertex 0.929631 1.95162 2.59164 + vertex 0.933361 1.95593 2.59219 + endloop + endfacet + facet normal -0.439109 0.270466 0.856756 + outer loop + vertex 0.929631 1.95162 2.59164 + vertex 0.933271 1.95089 2.59373 + vertex 0.933361 1.95593 2.59219 + endloop + endfacet + facet normal -0.446552 0.263443 0.855096 + outer loop + vertex 0.931458 1.95761 2.5906 + vertex 0.934069 1.9598 2.59129 + vertex 0.931745 1.96087 2.58975 + endloop + endfacet + facet normal -0.396778 0.265252 0.878754 + outer loop + vertex 0.931458 1.95761 2.5906 + vertex 0.931745 1.96087 2.58975 + vertex 0.927883 1.95646 2.58933 + endloop + endfacet + facet normal -0.395256 0.263814 0.879872 + outer loop + vertex 0.927883 1.95646 2.58933 + vertex 0.931745 1.96087 2.58975 + vertex 0.927905 1.96154 2.58782 + endloop + endfacet + facet normal -0.457352 0.279745 0.84414 + outer loop + vertex 0.934069 1.9598 2.59129 + vertex 0.931458 1.95761 2.5906 + vertex 0.933361 1.95593 2.59219 + endloop + endfacet + facet normal -0.397128 0.256695 0.881134 + outer loop + vertex 0.931745 1.96087 2.58975 + vertex 0.933196 1.96602 2.5889 + vertex 0.927905 1.96154 2.58782 + endloop + endfacet + facet normal -0.405094 0.267758 0.874188 + outer loop + vertex 0.927905 1.96154 2.58782 + vertex 0.933196 1.96602 2.5889 + vertex 0.929429 1.96677 2.58692 + endloop + endfacet + facet normal -0.400372 0.267346 0.876486 + outer loop + vertex 0.930802 1.97369 2.58546 + vertex 0.926843 1.97072 2.58456 + vertex 0.929488 1.97004 2.58597 + endloop + endfacet + facet normal -0.407949 0.269493 0.872325 + outer loop + vertex 0.929488 1.97004 2.58597 + vertex 0.933324 1.97134 2.58737 + vertex 0.930802 1.97369 2.58546 + endloop + endfacet + facet normal -0.406529 0.262145 0.875222 + outer loop + vertex 0.929488 1.97004 2.58597 + vertex 0.929429 1.96677 2.58692 + vertex 0.933324 1.97134 2.58737 + endloop + endfacet + facet normal -0.406671 0.262277 0.875117 + outer loop + vertex 0.929429 1.96677 2.58692 + vertex 0.933196 1.96602 2.5889 + vertex 0.933324 1.97134 2.58737 + endloop + endfacet + facet normal -0.405424 0.27558 0.8716 + outer loop + vertex 0.928016 1.97611 2.5834 + vertex 0.926843 1.97072 2.58456 + vertex 0.930802 1.97369 2.58546 + endloop + endfacet + facet normal -0.406875 0.27381 0.871482 + outer loop + vertex 0.932325 1.97742 2.585 + vertex 0.928016 1.97611 2.5834 + vertex 0.930802 1.97369 2.58546 + endloop + endfacet + facet normal -0.418361 0.277669 0.864797 + outer loop + vertex 0.930802 1.97369 2.58546 + vertex 0.934722 1.9764 2.58648 + vertex 0.932325 1.97742 2.585 + endloop + endfacet + facet normal -0.411607 0.265236 0.871911 + outer loop + vertex 0.933324 1.97134 2.58737 + vertex 0.934722 1.9764 2.58648 + vertex 0.930802 1.97369 2.58546 + endloop + endfacet + facet normal -0.413811 0.274361 0.868036 + outer loop + vertex 0.932325 1.97742 2.585 + vertex 0.93502 1.97962 2.58559 + vertex 0.933032 1.98127 2.58412 + endloop + endfacet + facet normal -0.406885 0.27387 0.871458 + outer loop + vertex 0.932325 1.97742 2.585 + vertex 0.933032 1.98127 2.58412 + vertex 0.928016 1.97611 2.5834 + endloop + endfacet + facet normal -0.408319 0.275427 0.870297 + outer loop + vertex 0.928016 1.97611 2.5834 + vertex 0.933032 1.98127 2.58412 + vertex 0.929243 1.98149 2.58227 + endloop + endfacet + facet normal -0.417396 0.279674 0.864617 + outer loop + vertex 0.93502 1.97962 2.58559 + vertex 0.932325 1.97742 2.585 + vertex 0.934722 1.9764 2.58648 + endloop + endfacet + facet normal -0.470349 0.299098 0.830249 + outer loop + vertex 0.930728 1.98847 2.58071 + vertex 0.926866 1.98549 2.57959 + vertex 0.929323 1.98473 2.58126 + endloop + endfacet + facet normal -0.418451 0.284326 0.862588 + outer loop + vertex 0.929323 1.98473 2.58126 + vertex 0.933196 1.98626 2.58263 + vertex 0.930728 1.98847 2.58071 + endloop + endfacet + facet normal -0.417475 0.280225 0.864401 + outer loop + vertex 0.929323 1.98473 2.58126 + vertex 0.929243 1.98149 2.58227 + vertex 0.933196 1.98626 2.58263 + endloop + endfacet + facet normal -0.408813 0.272557 0.870967 + outer loop + vertex 0.929243 1.98149 2.58227 + vertex 0.933032 1.98127 2.58412 + vertex 0.933196 1.98626 2.58263 + endloop + endfacet + facet normal -0.473093 0.3039 0.826939 + outer loop + vertex 0.928098 1.99101 2.57827 + vertex 0.926866 1.98549 2.57959 + vertex 0.930728 1.98847 2.58071 + endloop + endfacet + facet normal -0.479601 0.296242 0.825968 + outer loop + vertex 0.932288 1.99226 2.58026 + vertex 0.928098 1.99101 2.57827 + vertex 0.930728 1.98847 2.58071 + endloop + endfacet + facet normal -0.425466 0.278149 0.861169 + outer loop + vertex 0.930728 1.98847 2.58071 + vertex 0.934706 1.9914 2.58173 + vertex 0.932288 1.99226 2.58026 + endloop + endfacet + facet normal -0.42469 0.276815 0.861982 + outer loop + vertex 0.933196 1.98626 2.58263 + vertex 0.934706 1.9914 2.58173 + vertex 0.930728 1.98847 2.58071 + endloop + endfacet + facet normal -0.436594 0.29109 0.851265 + outer loop + vertex 0.932288 1.99226 2.58026 + vertex 0.935007 1.9946 2.58085 + vertex 0.93297 1.99611 2.57929 + endloop + endfacet + facet normal -0.479242 0.292663 0.827451 + outer loop + vertex 0.932288 1.99226 2.58026 + vertex 0.93297 1.99611 2.57929 + vertex 0.928098 1.99101 2.57827 + endloop + endfacet + facet normal -0.478273 0.291544 0.828406 + outer loop + vertex 0.928098 1.99101 2.57827 + vertex 0.93297 1.99611 2.57929 + vertex 0.92907 1.99646 2.57691 + endloop + endfacet + facet normal -0.426173 0.276474 0.861359 + outer loop + vertex 0.935007 1.9946 2.58085 + vertex 0.932288 1.99226 2.58026 + vertex 0.934706 1.9914 2.58173 + endloop + endfacet + facet normal -0.544456 0.313317 0.778074 + outer loop + vertex 0.930625 2.0036 2.57519 + vertex 0.928413 2.00255 2.57406 + vertex 0.92884 2.00034 2.57525 + endloop + endfacet + facet normal -0.500515 0.289915 0.815742 + outer loop + vertex 0.92884 2.00034 2.57525 + vertex 0.932999 2.00113 2.57752 + vertex 0.930625 2.0036 2.57519 + endloop + endfacet + facet normal -0.500213 0.315706 0.806298 + outer loop + vertex 0.92884 2.00034 2.57525 + vertex 0.92907 1.99646 2.57691 + vertex 0.932999 2.00113 2.57752 + endloop + endfacet + facet normal -0.477726 0.293957 0.827869 + outer loop + vertex 0.92907 1.99646 2.57691 + vertex 0.93297 1.99611 2.57929 + vertex 0.932999 2.00113 2.57752 + endloop + endfacet + facet normal -0.553791 0.364473 0.748649 + outer loop + vertex 0.928355 2.00511 2.57277 + vertex 0.928413 2.00255 2.57406 + vertex 0.930625 2.0036 2.57519 + endloop + endfacet + facet normal -0.576568 0.329045 0.747862 + outer loop + vertex 0.931115 2.00758 2.57381 + vertex 0.928355 2.00511 2.57277 + vertex 0.930625 2.0036 2.57519 + endloop + endfacet + facet normal -0.50477 0.336473 0.79498 + outer loop + vertex 0.930625 2.0036 2.57519 + vertex 0.934282 2.00629 2.57637 + vertex 0.931115 2.00758 2.57381 + endloop + endfacet + facet normal -0.488235 0.303931 0.818079 + outer loop + vertex 0.932999 2.00113 2.57752 + vertex 0.934282 2.00629 2.57637 + vertex 0.930625 2.0036 2.57519 + endloop + endfacet + facet normal -0.633041 0.340037 0.695438 + outer loop + vertex 0.931243 2.01247 2.57176 + vertex 0.92839 2.01212 2.56933 + vertex 0.92838 2.00925 2.57072 + endloop + endfacet + facet normal -0.593487 0.359652 0.720017 + outer loop + vertex 0.92838 2.00925 2.57072 + vertex 0.928355 2.00511 2.57277 + vertex 0.931115 2.00758 2.57381 + endloop + endfacet + facet normal -0.617538 0.31863 0.719112 + outer loop + vertex 0.931243 2.01247 2.57176 + vertex 0.92838 2.00925 2.57072 + vertex 0.931115 2.00758 2.57381 + endloop + endfacet + facet normal -0.54406 0.337372 0.768231 + outer loop + vertex 0.931243 2.01247 2.57176 + vertex 0.931115 2.00758 2.57381 + vertex 0.934353 2.01033 2.5749 + endloop + endfacet + facet normal -0.571046 0.294982 0.766089 + outer loop + vertex 0.931243 2.01247 2.57176 + vertex 0.934353 2.01033 2.5749 + vertex 0.934782 2.01351 2.57399 + endloop + endfacet + facet normal -0.522315 0.299875 0.798287 + outer loop + vertex 0.934353 2.01033 2.5749 + vertex 0.931115 2.00758 2.57381 + vertex 0.934282 2.00629 2.57637 + endloop + endfacet + facet normal -0.632502 0.343279 0.694335 + outer loop + vertex 0.928643 2.01497 2.56815 + vertex 0.92839 2.01212 2.56933 + vertex 0.931243 2.01247 2.57176 + endloop + endfacet + facet normal -0.660926 0.302689 0.6867 + outer loop + vertex 0.931161 2.01729 2.56955 + vertex 0.928643 2.01497 2.56815 + vertex 0.931243 2.01247 2.57176 + endloop + endfacet + facet normal -0.594605 0.325899 0.735007 + outer loop + vertex 0.931243 2.01247 2.57176 + vertex 0.934276 2.01667 2.57235 + vertex 0.931161 2.01729 2.56955 + endloop + endfacet + facet normal -0.571372 0.305374 0.761762 + outer loop + vertex 0.934782 2.01351 2.57399 + vertex 0.934276 2.01667 2.57235 + vertex 0.931243 2.01247 2.57176 + endloop + endfacet + facet normal -0.71164 0.357103 0.605018 + outer loop + vertex 0.930932 2.02192 2.56702 + vertex 0.928247 2.02104 2.56438 + vertex 0.929061 2.01849 2.56684 + endloop + endfacet + facet normal -0.671423 0.327135 0.664962 + outer loop + vertex 0.929061 2.01849 2.56684 + vertex 0.928643 2.01497 2.56815 + vertex 0.931161 2.01729 2.56955 + endloop + endfacet + facet normal -0.669438 0.330905 0.665098 + outer loop + vertex 0.930932 2.02192 2.56702 + vertex 0.929061 2.01849 2.56684 + vertex 0.931161 2.01729 2.56955 + endloop + endfacet + facet normal -0.642241 0.34331 0.685321 + outer loop + vertex 0.930932 2.02192 2.56702 + vertex 0.931161 2.01729 2.56955 + vertex 0.933661 2.02035 2.57036 + endloop + endfacet + facet normal -0.687018 0.255118 0.680383 + outer loop + vertex 0.930932 2.02192 2.56702 + vertex 0.933661 2.02035 2.57036 + vertex 0.933188 2.02256 2.56906 + endloop + endfacet + facet normal -0.604033 0.297717 0.739262 + outer loop + vertex 0.933661 2.02035 2.57036 + vertex 0.931161 2.01729 2.56955 + vertex 0.934276 2.01667 2.57235 + endloop + endfacet + facet normal -0.710785 0.364229 0.601765 + outer loop + vertex 0.928759 2.02472 2.56276 + vertex 0.928247 2.02104 2.56438 + vertex 0.930932 2.02192 2.56702 + endloop + endfacet + facet normal -0.731952 0.334948 0.593343 + outer loop + vertex 0.931029 2.02682 2.56437 + vertex 0.928759 2.02472 2.56276 + vertex 0.930932 2.02192 2.56702 + endloop + endfacet + facet normal -0.697001 0.351394 0.625069 + outer loop + vertex 0.930932 2.02192 2.56702 + vertex 0.93319 2.02509 2.56776 + vertex 0.931029 2.02682 2.56437 + endloop + endfacet + facet normal -0.682218 0.335108 0.649832 + outer loop + vertex 0.933188 2.02256 2.56906 + vertex 0.93319 2.02509 2.56776 + vertex 0.930932 2.02192 2.56702 + endloop + endfacet + facet normal -0.755499 0.365798 0.54352 + outer loop + vertex 0.931105 2.03212 2.56117 + vertex 0.928703 2.03083 2.55871 + vertex 0.929348 2.02844 2.56121 + endloop + endfacet + facet normal -0.737454 0.355444 0.574301 + outer loop + vertex 0.929348 2.02844 2.56121 + vertex 0.928759 2.02472 2.56276 + vertex 0.931029 2.02682 2.56437 + endloop + endfacet + facet normal -0.736442 0.357069 0.574592 + outer loop + vertex 0.931105 2.03212 2.56117 + vertex 0.929348 2.02844 2.56121 + vertex 0.931029 2.02682 2.56437 + endloop + endfacet + facet normal -0.710723 0.370734 0.597853 + outer loop + vertex 0.931105 2.03212 2.56117 + vertex 0.931029 2.02682 2.56437 + vertex 0.933364 2.02915 2.5657 + endloop + endfacet + facet normal -0.743356 0.325407 0.584407 + outer loop + vertex 0.931105 2.03212 2.56117 + vertex 0.933364 2.02915 2.5657 + vertex 0.933474 2.03195 2.56429 + endloop + endfacet + facet normal -0.70061 0.345469 0.624338 + outer loop + vertex 0.933364 2.02915 2.5657 + vertex 0.931029 2.02682 2.56437 + vertex 0.93319 2.02509 2.56776 + endloop + endfacet + facet normal -0.767966 0.354999 0.533108 + outer loop + vertex 0.929938 2.03669 2.55654 + vertex 0.928037 2.03593 2.55431 + vertex 0.928913 2.03357 2.55714 + endloop + endfacet + facet normal -0.755372 0.367823 0.542328 + outer loop + vertex 0.928913 2.03357 2.55714 + vertex 0.928703 2.03083 2.55871 + vertex 0.931105 2.03212 2.56117 + endloop + endfacet + facet normal -0.76229 0.354718 0.541377 + outer loop + vertex 0.928913 2.03357 2.55714 + vertex 0.931105 2.03212 2.56117 + vertex 0.929938 2.03669 2.55654 + endloop + endfacet + facet normal -0.768398 0.348483 0.536772 + outer loop + vertex 0.929938 2.03669 2.55654 + vertex 0.931105 2.03212 2.56117 + vertex 0.932143 2.03732 2.55928 + endloop + endfacet + facet normal -0.740069 0.355274 0.571033 + outer loop + vertex 0.931105 2.03212 2.56117 + vertex 0.933761 2.03476 2.56298 + vertex 0.932143 2.03732 2.55928 + endloop + endfacet + facet normal -0.737077 0.345582 0.580767 + outer loop + vertex 0.933474 2.03195 2.56429 + vertex 0.933761 2.03476 2.56298 + vertex 0.931105 2.03212 2.56117 + endloop + endfacet + facet normal -0.768504 0.351132 0.53489 + outer loop + vertex 0.928579 2.03964 2.55265 + vertex 0.928037 2.03593 2.55431 + vertex 0.929938 2.03669 2.55654 + endloop + endfacet + facet normal -0.766144 0.354101 0.536316 + outer loop + vertex 0.931042 2.0414 2.55501 + vertex 0.928579 2.03964 2.55265 + vertex 0.929938 2.03669 2.55654 + endloop + endfacet + facet normal -0.748162 0.359057 0.557971 + outer loop + vertex 0.933261 2.04073 2.55859 + vertex 0.932143 2.03732 2.55928 + vertex 0.934184 2.03838 2.56135 + endloop + endfacet + facet normal -0.761843 0.359621 0.538765 + outer loop + vertex 0.933261 2.04073 2.55859 + vertex 0.931042 2.0414 2.55501 + vertex 0.932143 2.03732 2.55928 + endloop + endfacet + facet normal -0.767375 0.353868 0.534708 + outer loop + vertex 0.931042 2.0414 2.55501 + vertex 0.929938 2.03669 2.55654 + vertex 0.932143 2.03732 2.55928 + endloop + endfacet + facet normal -0.748928 0.34345 0.566701 + outer loop + vertex 0.934184 2.03838 2.56135 + vertex 0.932143 2.03732 2.55928 + vertex 0.933761 2.03476 2.56298 + endloop + endfacet + facet normal -0.758078 0.348707 0.551109 + outer loop + vertex 0.931055 2.04733 2.55115 + vertex 0.928652 2.04597 2.54871 + vertex 0.929308 2.04345 2.5512 + endloop + endfacet + facet normal -0.766032 0.350983 0.538522 + outer loop + vertex 0.929308 2.04345 2.5512 + vertex 0.928579 2.03964 2.55265 + vertex 0.931042 2.0414 2.55501 + endloop + endfacet + facet normal -0.76547 0.351868 0.538744 + outer loop + vertex 0.931055 2.04733 2.55115 + vertex 0.929308 2.04345 2.5512 + vertex 0.931042 2.0414 2.55501 + endloop + endfacet + facet normal -0.758844 0.356111 0.54529 + outer loop + vertex 0.931055 2.04733 2.55115 + vertex 0.931042 2.0414 2.55501 + vertex 0.933201 2.04436 2.55608 + endloop + endfacet + facet normal -0.755988 0.360245 0.54654 + outer loop + vertex 0.931055 2.04733 2.55115 + vertex 0.933201 2.04436 2.55608 + vertex 0.933151 2.04721 2.55413 + endloop + endfacet + facet normal -0.761508 0.360419 0.538705 + outer loop + vertex 0.933201 2.04436 2.55608 + vertex 0.931042 2.0414 2.55501 + vertex 0.933261 2.04073 2.55859 + endloop + endfacet + facet normal -0.766447 0.353538 0.536256 + outer loop + vertex 0.929879 2.0519 2.54664 + vertex 0.928093 2.05111 2.5446 + vertex 0.92885 2.04877 2.54723 + endloop + endfacet + facet normal -0.758186 0.345148 0.553197 + outer loop + vertex 0.92885 2.04877 2.54723 + vertex 0.928652 2.04597 2.54871 + vertex 0.931055 2.04733 2.55115 + endloop + endfacet + facet normal -0.754214 0.352827 0.553783 + outer loop + vertex 0.92885 2.04877 2.54723 + vertex 0.931055 2.04733 2.55115 + vertex 0.929879 2.0519 2.54664 + endloop + endfacet + facet normal -0.749928 0.357017 0.556909 + outer loop + vertex 0.929879 2.0519 2.54664 + vertex 0.931055 2.04733 2.55115 + vertex 0.932101 2.0526 2.54918 + endloop + endfacet + facet normal -0.755969 0.35551 0.549657 + outer loop + vertex 0.931055 2.04733 2.55115 + vertex 0.933533 2.04991 2.5529 + vertex 0.932101 2.0526 2.54918 + endloop + endfacet + facet normal -0.756718 0.358058 0.546966 + outer loop + vertex 0.933151 2.04721 2.55413 + vertex 0.933533 2.04991 2.5529 + vertex 0.931055 2.04733 2.55115 + endloop + endfacet + facet normal -0.766101 0.356433 0.534832 + outer loop + vertex 0.928661 2.05474 2.543 + vertex 0.928093 2.05111 2.5446 + vertex 0.929879 2.0519 2.54664 + endloop + endfacet + facet normal -0.764885 0.357916 0.535581 + outer loop + vertex 0.930968 2.05658 2.54507 + vertex 0.928661 2.05474 2.543 + vertex 0.929879 2.0519 2.54664 + endloop + endfacet + facet normal -0.752516 0.359854 0.551566 + outer loop + vertex 0.933205 2.05598 2.54848 + vertex 0.932101 2.0526 2.54918 + vertex 0.934126 2.05351 2.55135 + endloop + endfacet + facet normal -0.750401 0.359771 0.554494 + outer loop + vertex 0.933205 2.05598 2.54848 + vertex 0.930968 2.05658 2.54507 + vertex 0.932101 2.0526 2.54918 + endloop + endfacet + facet normal -0.74928 0.360899 0.555276 + outer loop + vertex 0.930968 2.05658 2.54507 + vertex 0.929879 2.0519 2.54664 + vertex 0.932101 2.0526 2.54918 + endloop + endfacet + facet normal -0.752508 0.359928 0.551528 + outer loop + vertex 0.934126 2.05351 2.55135 + vertex 0.932101 2.0526 2.54918 + vertex 0.933533 2.04991 2.5529 + endloop + endfacet + facet normal -0.776141 0.397987 0.489092 + outer loop + vertex 0.931097 2.0624 2.54109 + vertex 0.928887 2.0606 2.53904 + vertex 0.929336 2.05844 2.54151 + endloop + endfacet + facet normal -0.76468 0.355658 0.537375 + outer loop + vertex 0.929336 2.05844 2.54151 + vertex 0.928661 2.05474 2.543 + vertex 0.930968 2.05658 2.54507 + endloop + endfacet + facet normal -0.742804 0.389127 0.544815 + outer loop + vertex 0.931097 2.0624 2.54109 + vertex 0.929336 2.05844 2.54151 + vertex 0.930968 2.05658 2.54507 + endloop + endfacet + facet normal -0.756005 0.380885 0.532337 + outer loop + vertex 0.931097 2.0624 2.54109 + vertex 0.930968 2.05658 2.54507 + vertex 0.933096 2.05955 2.54596 + endloop + endfacet + facet normal -0.775317 0.352779 0.523862 + outer loop + vertex 0.931097 2.0624 2.54109 + vertex 0.933096 2.05955 2.54596 + vertex 0.93304 2.06236 2.54399 + endloop + endfacet + facet normal -0.746993 0.367991 0.553701 + outer loop + vertex 0.933096 2.05955 2.54596 + vertex 0.930968 2.05658 2.54507 + vertex 0.933205 2.05598 2.54848 + endloop + endfacet + facet normal -0.910742 0.375862 0.171103 + outer loop + vertex 0.930162 2.06902 2.53106 + vertex 0.928814 2.06606 2.53039 + vertex 0.928817 2.06468 2.53345 + endloop + endfacet + facet normal -0.876365 0.410066 0.252645 + outer loop + vertex 0.930625 2.06733 2.53541 + vertex 0.930162 2.06902 2.53106 + vertex 0.928817 2.06468 2.53345 + endloop + endfacet + facet normal -0.87675 0.402463 0.263312 + outer loop + vertex 0.929251 2.06328 2.53702 + vertex 0.930625 2.06733 2.53541 + vertex 0.928817 2.06468 2.53345 + endloop + endfacet + facet normal -0.775818 0.443526 0.448766 + outer loop + vertex 0.929251 2.06328 2.53702 + vertex 0.928887 2.0606 2.53904 + vertex 0.931097 2.0624 2.54109 + endloop + endfacet + facet normal -0.776448 0.442385 0.448804 + outer loop + vertex 0.929251 2.06328 2.53702 + vertex 0.931097 2.0624 2.54109 + vertex 0.930625 2.06733 2.53541 + endloop + endfacet + facet normal -0.854836 0.354482 0.378944 + outer loop + vertex 0.930625 2.06733 2.53541 + vertex 0.931097 2.0624 2.54109 + vertex 0.932441 2.06766 2.5392 + endloop + endfacet + facet normal -0.772833 0.380031 0.508238 + outer loop + vertex 0.931097 2.0624 2.54109 + vertex 0.933495 2.06498 2.54281 + vertex 0.932441 2.06766 2.5392 + endloop + endfacet + facet normal -0.76993 0.3692 0.52048 + outer loop + vertex 0.93304 2.06236 2.54399 + vertex 0.933495 2.06498 2.54281 + vertex 0.931097 2.0624 2.54109 + endloop + endfacet + facet normal -0.775991 0.220181 0.591066 + outer loop + vertex 0.93 2.07129 2.53 + vertex 0.928814 2.06606 2.53039 + vertex 0.930162 2.06902 2.53106 + endloop + endfacet + facet normal -0.483676 0.34131 0.805956 + outer loop + vertex 0.93 2.07129 2.53 + vertex 0.930162 2.06902 2.53106 + vertex 0.932618 2.075 2.53 + endloop + endfacet + facet normal -0.914428 0.39291 0.0971752 + outer loop + vertex 0.932618 2.075 2.53 + vertex 0.930162 2.06902 2.53106 + vertex 0.931718 2.07259 2.53126 + endloop + endfacet + facet normal -0.894662 0.375946 0.24134 + outer loop + vertex 0.930162 2.06902 2.53106 + vertex 0.930625 2.06733 2.53541 + vertex 0.931718 2.07259 2.53126 + endloop + endfacet + facet normal -0.897653 0.372264 0.235877 + outer loop + vertex 0.931718 2.07259 2.53126 + vertex 0.930625 2.06733 2.53541 + vertex 0.932545 2.07191 2.53549 + endloop + endfacet + facet normal -0.786666 0.359166 0.502152 + outer loop + vertex 0.933679 2.07064 2.53901 + vertex 0.932441 2.06766 2.5392 + vertex 0.934188 2.06834 2.54145 + endloop + endfacet + facet normal -0.835191 0.373065 0.404078 + outer loop + vertex 0.933679 2.07064 2.53901 + vertex 0.932545 2.07191 2.53549 + vertex 0.932441 2.06766 2.5392 + endloop + endfacet + facet normal -0.855569 0.352112 0.379499 + outer loop + vertex 0.932545 2.07191 2.53549 + vertex 0.930625 2.06733 2.53541 + vertex 0.932441 2.06766 2.5392 + endloop + endfacet + facet normal -0.785815 0.363919 0.500057 + outer loop + vertex 0.934188 2.06834 2.54145 + vertex 0.932441 2.06766 2.5392 + vertex 0.933495 2.06498 2.54281 + endloop + endfacet + facet normal -0.52442 -0.527546 -0.66834 + outer loop + vertex 0.935 2.075 2.52841 + vertex 0.934316 2.08 2.525 + vertex 0.935 2.07932 2.525 + endloop + endfacet + facet normal -0.466945 -0.54095 -0.699525 + outer loop + vertex 0.935 2.075 2.52841 + vertex 0.932618 2.075 2.53 + vertex 0.934316 2.08 2.525 + endloop + endfacet + facet normal -0.887253 -0.138644 -0.439955 + outer loop + vertex 0.932618 2.075 2.53 + vertex 0.933277 2.07845 2.52758 + vertex 0.934316 2.08 2.525 + endloop + endfacet + facet normal 0.583678 -0.537635 -0.608497 + outer loop + vertex 0.932618 2.075 2.53 + vertex 0.931718 2.07259 2.53126 + vertex 0.933277 2.07845 2.52758 + endloop + endfacet + facet normal -0.941658 0.318675 0.108289 + outer loop + vertex 0.933277 2.07845 2.52758 + vertex 0.931718 2.07259 2.53126 + vertex 0.933116 2.07664 2.5315 + endloop + endfacet + facet normal -0.841392 0.36405 0.399408 + outer loop + vertex 0.933771 2.07557 2.53474 + vertex 0.932545 2.07191 2.53549 + vertex 0.934163 2.07343 2.53751 + endloop + endfacet + facet normal -0.8849 0.35792 0.298068 + outer loop + vertex 0.933771 2.07557 2.53474 + vertex 0.933116 2.07664 2.5315 + vertex 0.932545 2.07191 2.53549 + endloop + endfacet + facet normal -0.923931 0.305495 0.23027 + outer loop + vertex 0.933116 2.07664 2.5315 + vertex 0.931718 2.07259 2.53126 + vertex 0.932545 2.07191 2.53549 + endloop + endfacet + facet normal -0.841555 0.361052 0.40178 + outer loop + vertex 0.934163 2.07343 2.53751 + vertex 0.932545 2.07191 2.53549 + vertex 0.933679 2.07064 2.53901 + endloop + endfacet + facet normal -0.302861 -0.0721831 -0.950297 + outer loop + vertex 0.935 2.08 2.52432 + vertex 0.934126 2.08147 2.52449 + vertex 0.935 2.085 2.52394 + endloop + endfacet + facet normal -0.667746 -0.321271 -0.671491 + outer loop + vertex 0.934316 2.08 2.525 + vertex 0.934126 2.08147 2.52449 + vertex 0.935 2.08 2.52432 + endloop + endfacet + facet normal -0.96018 0.193637 0.201393 + outer loop + vertex 0.935 2.085 2.5295 + vertex 0.933277 2.07845 2.52758 + vertex 0.935 2.08448 2.53 + endloop + endfacet + facet normal -0.966039 0.258049 -0.0133658 + outer loop + vertex 0.935 2.085 2.5295 + vertex 0.934126 2.08147 2.52449 + vertex 0.933277 2.07845 2.52758 + endloop + endfacet + facet normal -0.82049 -0.280463 -0.498133 + outer loop + vertex 0.934126 2.08147 2.52449 + vertex 0.934316 2.08 2.525 + vertex 0.933277 2.07845 2.52758 + endloop + endfacet + facet normal -0.86439 0.286822 0.412993 + outer loop + vertex 0.935 2.08448 2.53 + vertex 0.933116 2.07664 2.5315 + vertex 0.934395 2.07907 2.53249 + endloop + endfacet + facet normal -0.96632 0.24649 0.0739437 + outer loop + vertex 0.933277 2.07845 2.52758 + vertex 0.933116 2.07664 2.5315 + vertex 0.935 2.08448 2.53 + endloop + endfacet + facet normal -0.889685 0.347885 0.295698 + outer loop + vertex 0.934395 2.07907 2.53249 + vertex 0.933116 2.07664 2.5315 + vertex 0.933771 2.07557 2.53474 + endloop + endfacet + facet normal -0.928874 0.179739 -0.323862 + outer loop + vertex 0.935 2.085 2.52394 + vertex 0.934126 2.08147 2.52449 + vertex 0.935 2.08691 2.525 + endloop + endfacet + facet normal -0.986214 0.152323 0.0646528 + outer loop + vertex 0.935 2.08691 2.525 + vertex 0.934126 2.08147 2.52449 + vertex 0.935 2.085 2.5295 + endloop + endfacet + facet normal 0.461243 -0.606598 -0.647529 + outer loop + vertex 0.935 2.10874 2.515 + vertex 0.931893 2.10715 2.51428 + vertex 0.935 2.11 2.51382 + endloop + endfacet + facet normal 0.471152 -0.648218 -0.598188 + outer loop + vertex 0.932799 2.1053 2.517 + vertex 0.931893 2.10715 2.51428 + vertex 0.935 2.10874 2.515 + endloop + endfacet + facet normal -0.11865 -0.838759 -0.531418 + outer loop + vertex 0.930065 2.1059 2.51666 + vertex 0.931893 2.10715 2.51428 + vertex 0.932799 2.1053 2.517 + endloop + endfacet + facet normal 0.00226362 -0.981707 -0.190382 + outer loop + vertex 0.930065 2.1059 2.51666 + vertex 0.928919 2.10531 2.51967 + vertex 0.927546 2.10589 2.51668 + endloop + endfacet + facet normal -0.177636 -0.951055 -0.252862 + outer loop + vertex 0.930065 2.1059 2.51666 + vertex 0.932799 2.1053 2.517 + vertex 0.928919 2.10531 2.51967 + endloop + endfacet + facet normal -0.280629 -0.871289 -0.40262 + outer loop + vertex 0.932799 2.1053 2.517 + vertex 0.933557 2.10356 2.52022 + vertex 0.928919 2.10531 2.51967 + endloop + endfacet + facet normal -0.361409 -0.926649 0.103461 + outer loop + vertex 0.933557 2.10356 2.52022 + vertex 0.933173 2.10416 2.52424 + vertex 0.928919 2.10531 2.51967 + endloop + endfacet + facet normal -0.399097 -0.905544 0.143914 + outer loop + vertex 0.933173 2.10416 2.52424 + vertex 0.927705 2.10641 2.52324 + vertex 0.928919 2.10531 2.51967 + endloop + endfacet + facet normal -0.356587 -0.525484 0.772472 + outer loop + vertex 0.933173 2.10416 2.52424 + vertex 0.930773 2.10785 2.52564 + vertex 0.927705 2.10641 2.52324 + endloop + endfacet + facet normal -0.458814 -0.560513 0.689431 + outer loop + vertex 0.935501 2.10696 2.52807 + vertex 0.930773 2.10785 2.52564 + vertex 0.933173 2.10416 2.52424 + endloop + endfacet + facet normal 0.42415 -0.574652 -0.699908 + outer loop + vertex 0.935 2.11 2.51382 + vertex 0.931893 2.10715 2.51428 + vertex 0.929451 2.10871 2.51152 + endloop + endfacet + facet normal 0.391121 -0.762664 -0.515139 + outer loop + vertex 0.935 2.11 2.51382 + vertex 0.929451 2.10871 2.51152 + vertex 0.935 2.11258 2.51 + endloop + endfacet + facet normal -0.00780523 -0.35507 -0.934807 + outer loop + vertex 0.935 2.11258 2.51 + vertex 0.929451 2.10871 2.51152 + vertex 0.93 2.11269 2.51 + endloop + endfacet + facet normal 0.117625 -0.91354 -0.38937 + outer loop + vertex 0.931893 2.10715 2.51428 + vertex 0.930065 2.1059 2.51666 + vertex 0.929028 2.10659 2.51471 + endloop + endfacet + facet normal 0.0792621 -0.83593 -0.543082 + outer loop + vertex 0.929451 2.10871 2.51152 + vertex 0.931893 2.10715 2.51428 + vertex 0.929028 2.10659 2.51471 + endloop + endfacet + facet normal 0.0012917 -0.941379 -0.337348 + outer loop + vertex 0.930065 2.1059 2.51666 + vertex 0.927546 2.10589 2.51668 + vertex 0.929028 2.10659 2.51471 + endloop + endfacet + facet normal -0.345023 0.373636 0.86102 + outer loop + vertex 0.930495 2.11316 2.52439 + vertex 0.928449 2.11197 2.52409 + vertex 0.929205 2.11052 2.52502 + endloop + endfacet + facet normal -0.41006 0.395957 0.821626 + outer loop + vertex 0.929205 2.11052 2.52502 + vertex 0.933374 2.11141 2.52667 + vertex 0.930495 2.11316 2.52439 + endloop + endfacet + facet normal -0.368091 -0.00215165 0.929787 + outer loop + vertex 0.929205 2.11052 2.52502 + vertex 0.930773 2.10785 2.52564 + vertex 0.933374 2.11141 2.52667 + endloop + endfacet + facet normal -0.446283 0.0658284 0.892468 + outer loop + vertex 0.930773 2.10785 2.52564 + vertex 0.935501 2.10696 2.52807 + vertex 0.933374 2.11141 2.52667 + endloop + endfacet + facet normal -0.47725 0.616536 0.626191 + outer loop + vertex 0.930373 2.11657 2.52131 + vertex 0.925648 2.11468 2.51957 + vertex 0.928232 2.1135 2.52271 + endloop + endfacet + facet normal -0.434733 0.569039 0.697999 + outer loop + vertex 0.928232 2.1135 2.52271 + vertex 0.928449 2.11197 2.52409 + vertex 0.930495 2.11316 2.52439 + endloop + endfacet + facet normal -0.41798 0.600431 0.681744 + outer loop + vertex 0.930373 2.11657 2.52131 + vertex 0.928232 2.1135 2.52271 + vertex 0.930495 2.11316 2.52439 + endloop + endfacet + facet normal -0.479173 0.578616 0.659997 + outer loop + vertex 0.930373 2.11657 2.52131 + vertex 0.930495 2.11316 2.52439 + vertex 0.933408 2.11527 2.52466 + endloop + endfacet + facet normal -0.503959 0.545569 0.669612 + outer loop + vertex 0.930373 2.11657 2.52131 + vertex 0.933408 2.11527 2.52466 + vertex 0.933351 2.11728 2.52298 + endloop + endfacet + facet normal -0.385747 0.429325 0.816627 + outer loop + vertex 0.933408 2.11527 2.52466 + vertex 0.930495 2.11316 2.52439 + vertex 0.933374 2.11141 2.52667 + endloop + endfacet + facet normal -0.41114 0.739441 0.533095 + outer loop + vertex 0.930813 2.12022 2.51718 + vertex 0.927097 2.1208 2.5135 + vertex 0.926805 2.11849 2.51649 + endloop + endfacet + facet normal -0.477638 0.636604 0.605473 + outer loop + vertex 0.926805 2.11849 2.51649 + vertex 0.925648 2.11468 2.51957 + vertex 0.930373 2.11657 2.52131 + endloop + endfacet + facet normal -0.405145 0.706909 0.579773 + outer loop + vertex 0.930813 2.12022 2.51718 + vertex 0.926805 2.11849 2.51649 + vertex 0.930373 2.11657 2.52131 + endloop + endfacet + facet normal -0.495613 0.677142 0.543918 + outer loop + vertex 0.930813 2.12022 2.51718 + vertex 0.930373 2.11657 2.52131 + vertex 0.933485 2.119 2.52113 + endloop + endfacet + facet normal -0.444629 0.726046 0.524559 + outer loop + vertex 0.930813 2.12022 2.51718 + vertex 0.933485 2.119 2.52113 + vertex 0.933836 2.12063 2.51917 + endloop + endfacet + facet normal -0.480043 0.659724 0.578206 + outer loop + vertex 0.933485 2.119 2.52113 + vertex 0.930373 2.11657 2.52131 + vertex 0.933351 2.11728 2.52298 + endloop + endfacet + facet normal -0.520911 0.672655 0.525535 + outer loop + vertex 0.935 2.13 2.50682 + vertex 0.933164 2.13 2.505 + vertex 0.93 2.12755 2.505 + endloop + endfacet + facet normal -0.520706 0.663986 0.536645 + outer loop + vertex 0.935 2.13 2.50682 + vertex 0.93 2.12755 2.505 + vertex 0.935 2.12743 2.51 + endloop + endfacet + facet normal -0.562253 0.592904 0.576487 + outer loop + vertex 0.935 2.12743 2.51 + vertex 0.93 2.12755 2.505 + vertex 0.929568 2.12494 2.50726 + endloop + endfacet + facet normal -0.562916 0.565635 0.602647 + outer loop + vertex 0.935 2.12743 2.51 + vertex 0.929568 2.12494 2.50726 + vertex 0.934441 2.12471 2.51203 + endloop + endfacet + facet normal -0.383626 0.816437 0.431581 + outer loop + vertex 0.934441 2.12471 2.51203 + vertex 0.929568 2.12494 2.50726 + vertex 0.929343 2.12251 2.51166 + endloop + endfacet + facet normal -0.293483 0.852621 0.432326 + outer loop + vertex 0.930813 2.12022 2.51718 + vertex 0.929343 2.12251 2.51166 + vertex 0.927097 2.1208 2.5135 + endloop + endfacet + facet normal -0.381093 0.813451 0.439392 + outer loop + vertex 0.930813 2.12022 2.51718 + vertex 0.93461 2.1222 2.51679 + vertex 0.929343 2.12251 2.51166 + endloop + endfacet + facet normal -0.382432 0.812121 0.440688 + outer loop + vertex 0.93461 2.1222 2.51679 + vertex 0.934441 2.12471 2.51203 + vertex 0.929343 2.12251 2.51166 + endloop + endfacet + facet normal -0.38761 0.821713 0.417786 + outer loop + vertex 0.93461 2.1222 2.51679 + vertex 0.930813 2.12022 2.51718 + vertex 0.933836 2.12063 2.51917 + endloop + endfacet + facet normal -0.552885 0.619021 0.557792 + outer loop + vertex 0.935 2.13164 2.505 + vertex 0.933164 2.13 2.505 + vertex 0.935 2.13 2.50682 + endloop + endfacet + facet normal -0.083572 -0.994965 0.0553206 + outer loop + vertex 0.94 0.897517 2.505 + vertex 0.94 0.897795 2.51 + vertex 0.935 0.897937 2.505 + endloop + endfacet + facet normal -0.0084195 -0.999765 -0.01997 + outer loop + vertex 0.94 0.897795 2.51 + vertex 0.933709 0.897908 2.50702 + vertex 0.935 0.897937 2.505 + endloop + endfacet + facet normal -0.189228 -0.958593 0.212819 + outer loop + vertex 0.933962 0.898324 2.51021 + vertex 0.938438 0.897799 2.51182 + vertex 0.935446 0.898742 2.51341 + endloop + endfacet + facet normal -0.165189 -0.976205 0.140483 + outer loop + vertex 0.933962 0.898324 2.51021 + vertex 0.933709 0.897908 2.50702 + vertex 0.938438 0.897799 2.51182 + endloop + endfacet + facet normal -0.0134601 -0.999866 -0.00934899 + outer loop + vertex 0.933709 0.897908 2.50702 + vertex 0.94 0.897795 2.51 + vertex 0.938438 0.897799 2.51182 + endloop + endfacet + facet normal -0.218097 -0.962603 0.160714 + outer loop + vertex 0.938721 0.898301 2.51521 + vertex 0.935446 0.898742 2.51341 + vertex 0.938438 0.897799 2.51182 + endloop + endfacet + facet normal -0.290083 -0.907078 0.305059 + outer loop + vertex 0.936975 0.899328 2.51661 + vertex 0.935446 0.898742 2.51341 + vertex 0.938721 0.898301 2.51521 + endloop + endfacet + facet normal -0.285972 -0.906729 0.309941 + outer loop + vertex 0.938721 0.898301 2.51521 + vertex 0.940481 0.898873 2.51851 + vertex 0.936975 0.899328 2.51661 + endloop + endfacet + facet normal -0.266455 -0.932144 0.24517 + outer loop + vertex 0.933962 0.898324 2.51021 + vertex 0.935446 0.898742 2.51341 + vertex 0.932264 0.899169 2.51157 + endloop + endfacet + facet normal -0.350855 -0.876893 0.328573 + outer loop + vertex 0.935446 0.898742 2.51341 + vertex 0.936975 0.899328 2.51661 + vertex 0.933025 0.900398 2.51524 + endloop + endfacet + facet normal -0.325006 -0.874362 0.360364 + outer loop + vertex 0.932264 0.899169 2.51157 + vertex 0.935446 0.898742 2.51341 + vertex 0.933025 0.900398 2.51524 + endloop + endfacet + facet normal -0.354155 -0.81575 0.457302 + outer loop + vertex 0.936975 0.899328 2.51661 + vertex 0.940481 0.898873 2.51851 + vertex 0.937588 0.901217 2.52045 + endloop + endfacet + facet normal -0.375856 -0.806577 0.456252 + outer loop + vertex 0.936975 0.899328 2.51661 + vertex 0.937588 0.901217 2.52045 + vertex 0.933025 0.900398 2.51524 + endloop + endfacet + facet normal -0.392168 -0.791812 0.468229 + outer loop + vertex 0.933025 0.900398 2.51524 + vertex 0.937588 0.901217 2.52045 + vertex 0.931988 0.902944 2.51868 + endloop + endfacet + facet normal -0.401549 -0.712904 0.574914 + outer loop + vertex 0.937588 0.901217 2.52045 + vertex 0.933955 0.904511 2.522 + vertex 0.931988 0.902944 2.51868 + endloop + endfacet + facet normal -0.419346 -0.721372 0.551154 + outer loop + vertex 0.938013 0.903955 2.52436 + vertex 0.933955 0.904511 2.522 + vertex 0.937588 0.901217 2.52045 + endloop + endfacet + facet normal -0.497885 -0.585023 0.640202 + outer loop + vertex 0.938325 0.906002 2.52669 + vertex 0.936155 0.908032 2.52686 + vertex 0.93437 0.907268 2.52477 + endloop + endfacet + facet normal -0.494128 -0.620189 0.609265 + outer loop + vertex 0.938325 0.906002 2.52669 + vertex 0.93437 0.907268 2.52477 + vertex 0.938013 0.903955 2.52436 + endloop + endfacet + facet normal -0.463899 -0.593114 0.658037 + outer loop + vertex 0.938013 0.903955 2.52436 + vertex 0.93437 0.907268 2.52477 + vertex 0.933955 0.904511 2.522 + endloop + endfacet + facet normal -0.44142 -0.531489 0.722958 + outer loop + vertex 0.938325 0.906002 2.52669 + vertex 0.938287 0.908697 2.52865 + vertex 0.936155 0.908032 2.52686 + endloop + endfacet + facet normal -0.589691 -0.451268 0.669793 + outer loop + vertex 0.93437 0.907268 2.52477 + vertex 0.936155 0.908032 2.52686 + vertex 0.93405 0.910121 2.52641 + endloop + endfacet + facet normal -0.562291 0.0637787 0.824476 + outer loop + vertex 0.938178 0.911677 2.52989 + vertex 0.936952 0.914736 2.52881 + vertex 0.935134 0.912329 2.52776 + endloop + endfacet + facet normal -0.5872 -0.32837 0.739845 + outer loop + vertex 0.938287 0.908697 2.52865 + vertex 0.938178 0.911677 2.52989 + vertex 0.935134 0.912329 2.52776 + endloop + endfacet + facet normal -0.515971 -0.246828 0.820275 + outer loop + vertex 0.938287 0.908697 2.52865 + vertex 0.935134 0.912329 2.52776 + vertex 0.93405 0.910121 2.52641 + endloop + endfacet + facet normal -0.527813 -0.368523 0.765248 + outer loop + vertex 0.938287 0.908697 2.52865 + vertex 0.93405 0.910121 2.52641 + vertex 0.936155 0.908032 2.52686 + endloop + endfacet + facet normal -0.575608 0.0554162 0.815846 + outer loop + vertex 0.938178 0.911677 2.52989 + vertex 0.940866 0.91287 2.5317 + vertex 0.936952 0.914736 2.52881 + endloop + endfacet + facet normal 0.0403128 0.80226 -0.595612 + outer loop + vertex 0.937229 0.918889 2.51681 + vertex 0.94 0.92 2.51849 + vertex 0.94 0.917409 2.515 + endloop + endfacet + facet normal -0.11879 0.67089 -0.73198 + outer loop + vertex 0.937229 0.918889 2.51681 + vertex 0.94 0.917409 2.515 + vertex 0.93371 0.917342 2.51596 + endloop + endfacet + facet normal -0.0167809 0.999068 -0.0397749 + outer loop + vertex 0.93371 0.917342 2.51596 + vertex 0.94 0.917409 2.515 + vertex 0.935 0.917325 2.515 + endloop + endfacet + facet normal -0.343391 0.909343 -0.234899 + outer loop + vertex 0.935934 0.919162 2.51976 + vertex 0.937229 0.918889 2.51681 + vertex 0.93371 0.917342 2.51596 + endloop + endfacet + facet normal -0.572087 0.818193 -0.0572418 + outer loop + vertex 0.932586 0.916902 2.52091 + vertex 0.935934 0.919162 2.51976 + vertex 0.93371 0.917342 2.51596 + endloop + endfacet + facet normal -0.528982 0.84108 0.112975 + outer loop + vertex 0.9367 0.918848 2.52569 + vertex 0.935934 0.919162 2.51976 + vertex 0.932586 0.916902 2.52091 + endloop + endfacet + facet normal -0.708818 0.603971 0.364412 + outer loop + vertex 0.933382 0.91516 2.52534 + vertex 0.9367 0.918848 2.52569 + vertex 0.932586 0.916902 2.52091 + endloop + endfacet + facet normal -0.671913 0.194681 0.714585 + outer loop + vertex 0.933382 0.91516 2.52534 + vertex 0.935134 0.912329 2.52776 + vertex 0.936952 0.914736 2.52881 + endloop + endfacet + facet normal -0.587389 0.467009 0.660967 + outer loop + vertex 0.9367 0.918848 2.52569 + vertex 0.933382 0.91516 2.52534 + vertex 0.936952 0.914736 2.52881 + endloop + endfacet + facet normal -0.768303 0.35718 0.531163 + outer loop + vertex 0.9367 0.918848 2.52569 + vertex 0.936952 0.914736 2.52881 + vertex 0.939139 0.917194 2.53032 + endloop + endfacet + facet normal -0.878611 0.0395116 0.475901 + outer loop + vertex 0.9367 0.918848 2.52569 + vertex 0.939139 0.917194 2.53032 + vertex 0.938593 0.919496 2.52913 + endloop + endfacet + facet normal -0.586182 0.0239106 0.809826 + outer loop + vertex 0.939139 0.917194 2.53032 + vertex 0.936952 0.914736 2.52881 + vertex 0.940866 0.91287 2.5317 + endloop + endfacet + facet normal 0.0469108 0.186429 -0.981348 + outer loop + vertex 0.94 0.92 2.51849 + vertex 0.938306 0.921417 2.51868 + vertex 0.94 0.925 2.51944 + endloop + endfacet + facet normal 0.308233 0.477885 -0.822568 + outer loop + vertex 0.937229 0.918889 2.51681 + vertex 0.938306 0.921417 2.51868 + vertex 0.94 0.92 2.51849 + endloop + endfacet + facet normal -0.722735 0.582898 -0.371327 + outer loop + vertex 0.937229 0.918889 2.51681 + vertex 0.935934 0.919162 2.51976 + vertex 0.938306 0.921417 2.51868 + endloop + endfacet + facet normal -0.724606 0.639107 -0.257855 + outer loop + vertex 0.938306 0.921417 2.51868 + vertex 0.935934 0.919162 2.51976 + vertex 0.93805 0.92243 2.52191 + endloop + endfacet + facet normal -0.870349 0.47283 0.137566 + outer loop + vertex 0.935934 0.919162 2.51976 + vertex 0.9367 0.918848 2.52569 + vertex 0.93805 0.92243 2.52191 + endloop + endfacet + facet normal -0.924638 0.37968 0.0297932 + outer loop + vertex 0.93805 0.92243 2.52191 + vertex 0.9367 0.918848 2.52569 + vertex 0.93841 0.923053 2.52515 + endloop + endfacet + facet normal -0.874034 0.391977 0.287086 + outer loop + vertex 0.9367 0.918848 2.52569 + vertex 0.938847 0.921821 2.52816 + vertex 0.93841 0.923053 2.52515 + endloop + endfacet + facet normal -0.864153 0.270361 0.424434 + outer loop + vertex 0.938593 0.919496 2.52913 + vertex 0.938847 0.921821 2.52816 + vertex 0.9367 0.918848 2.52569 + endloop + endfacet + facet normal -0.762757 0.457714 -0.456837 + outer loop + vertex 0.94 0.925 2.51944 + vertex 0.938306 0.921417 2.51868 + vertex 0.94 0.925559 2.52 + endloop + endfacet + facet normal -0.882822 0.403093 -0.241127 + outer loop + vertex 0.94 0.925559 2.52 + vertex 0.93805 0.92243 2.52191 + vertex 0.94 0.92855 2.525 + endloop + endfacet + facet normal -0.881808 0.425518 -0.203348 + outer loop + vertex 0.938306 0.921417 2.51868 + vertex 0.93805 0.92243 2.52191 + vertex 0.94 0.925559 2.52 + endloop + endfacet + facet normal -0.940388 0.277347 0.19685 + outer loop + vertex 0.94 0.92855 2.525 + vertex 0.93841 0.923053 2.52515 + vertex 0.939334 0.925049 2.52675 + endloop + endfacet + facet normal -0.958881 0.278816 0.0529949 + outer loop + vertex 0.93805 0.92243 2.52191 + vertex 0.93841 0.923053 2.52515 + vertex 0.94 0.92855 2.525 + endloop + endfacet + facet normal -0.940118 0.245237 0.23672 + outer loop + vertex 0.939334 0.925049 2.52675 + vertex 0.93841 0.923053 2.52515 + vertex 0.938847 0.921821 2.52816 + endloop + endfacet + facet normal -0.816789 -0.148051 -0.557617 + outer loop + vertex 0.94 0.931233 2.525 + vertex 0.938896 0.935483 2.52549 + vertex 0.94 0.935 2.524 + endloop + endfacet + facet normal -0.940639 -0.268259 0.207933 + outer loop + vertex 0.94 0.931233 2.525 + vertex 0.94 0.935 2.52986 + vertex 0.938896 0.935483 2.52549 + endloop + endfacet + facet normal -0.541858 -0.0935553 -0.835247 + outer loop + vertex 0.94 0.935 2.524 + vertex 0.937595 0.94 2.525 + vertex 0.94 0.94 2.52344 + endloop + endfacet + facet normal -0.8115 -0.288702 -0.508054 + outer loop + vertex 0.938896 0.935483 2.52549 + vertex 0.937595 0.94 2.525 + vertex 0.94 0.935 2.524 + endloop + endfacet + facet normal -0.95342 -0.208758 0.217738 + outer loop + vertex 0.94 0.935146 2.53 + vertex 0.938896 0.935483 2.52549 + vertex 0.94 0.935 2.52986 + endloop + endfacet + facet normal -0.894928 -0.404297 0.188807 + outer loop + vertex 0.94 0.935146 2.53 + vertex 0.937954 0.938492 2.52747 + vertex 0.938896 0.935483 2.52549 + endloop + endfacet + facet normal -0.959563 -0.279753 -0.0312472 + outer loop + vertex 0.937954 0.938492 2.52747 + vertex 0.937595 0.94 2.525 + vertex 0.938896 0.935483 2.52549 + endloop + endfacet + facet normal -0.764336 -0.614669 -0.194865 + outer loop + vertex 0.938711 0.93672 2.53009 + vertex 0.937954 0.938492 2.52747 + vertex 0.94 0.935146 2.53 + endloop + endfacet + facet normal -0.946641 -0.316847 0.0589822 + outer loop + vertex 0.937436 0.940789 2.53148 + vertex 0.937954 0.938492 2.52747 + vertex 0.938711 0.93672 2.53009 + endloop + endfacet + facet normal -0.934462 -0.334555 0.121879 + outer loop + vertex 0.938711 0.93672 2.53009 + vertex 0.938604 0.938131 2.53314 + vertex 0.937436 0.940789 2.53148 + endloop + endfacet + facet normal -0.596312 0.516576 -0.61446 + outer loop + vertex 0.94 0.94343 2.525 + vertex 0.936208 0.945 2.53 + vertex 0.94 0.945 2.52632 + endloop + endfacet + facet normal -0.638974 0.448023 -0.62529 + outer loop + vertex 0.94 0.94343 2.525 + vertex 0.937595 0.94 2.525 + vertex 0.936208 0.945 2.53 + endloop + endfacet + facet normal -0.967121 -0.253912 -0.0143676 + outer loop + vertex 0.937595 0.94 2.525 + vertex 0.937954 0.938492 2.52747 + vertex 0.936208 0.945 2.53 + endloop + endfacet + facet normal -0.962401 -0.269957 0.0301372 + outer loop + vertex 0.937954 0.938492 2.52747 + vertex 0.937436 0.940789 2.53148 + vertex 0.936208 0.945 2.53 + endloop + endfacet + facet normal -0.950677 -0.302049 -0.0705697 + outer loop + vertex 0.936208 0.945 2.53 + vertex 0.937436 0.940789 2.53148 + vertex 0.93634 0.944123 2.53198 + endloop + endfacet + facet normal -0.936862 -0.305828 0.169588 + outer loop + vertex 0.938126 0.940747 2.53522 + vertex 0.937436 0.940789 2.53148 + vertex 0.938604 0.938131 2.53314 + endloop + endfacet + facet normal -0.934784 -0.312368 0.16913 + outer loop + vertex 0.938126 0.940747 2.53522 + vertex 0.93693 0.944793 2.53608 + vertex 0.937436 0.940789 2.53148 + endloop + endfacet + facet normal -0.92461 -0.331775 0.187143 + outer loop + vertex 0.93693 0.944793 2.53608 + vertex 0.93634 0.944123 2.53198 + vertex 0.937436 0.940789 2.53148 + endloop + endfacet + facet normal -0.892538 -0.329403 0.308009 + outer loop + vertex 0.938126 0.940747 2.53522 + vertex 0.938468 0.942567 2.53816 + vertex 0.93693 0.944793 2.53608 + endloop + endfacet + facet normal 0.444188 0.184963 -0.876633 + outer loop + vertex 0.934582 0.947594 2.52972 + vertex 0.935 0.947901 2.53 + vertex 0.936208 0.945 2.53 + endloop + endfacet + facet normal -0.848428 -0.523434 0.0786549 + outer loop + vertex 0.934582 0.947594 2.52972 + vertex 0.936208 0.945 2.53 + vertex 0.93511 0.947166 2.53258 + endloop + endfacet + facet normal -0.929312 -0.356562 -0.0961342 + outer loop + vertex 0.93511 0.947166 2.53258 + vertex 0.936208 0.945 2.53 + vertex 0.93634 0.944123 2.53198 + endloop + endfacet + facet normal -0.895802 -0.399828 0.194105 + outer loop + vertex 0.93634 0.944123 2.53198 + vertex 0.93693 0.944793 2.53608 + vertex 0.93511 0.947166 2.53258 + endloop + endfacet + facet normal -0.905223 -0.359819 0.226058 + outer loop + vertex 0.93511 0.947166 2.53258 + vertex 0.93693 0.944793 2.53608 + vertex 0.935291 0.949793 2.53748 + endloop + endfacet + facet normal -0.892216 -0.311338 0.327138 + outer loop + vertex 0.938178 0.945489 2.54015 + vertex 0.93693 0.944793 2.53608 + vertex 0.938468 0.942567 2.53816 + endloop + endfacet + facet normal -0.888703 -0.320694 0.327662 + outer loop + vertex 0.938178 0.945489 2.54015 + vertex 0.93725 0.949302 2.54137 + vertex 0.93693 0.944793 2.53608 + endloop + endfacet + facet normal -0.843786 -0.381831 0.377133 + outer loop + vertex 0.93725 0.949302 2.54137 + vertex 0.935291 0.949793 2.53748 + vertex 0.93693 0.944793 2.53608 + endloop + endfacet + facet normal -0.817433 -0.345798 0.460681 + outer loop + vertex 0.938178 0.945489 2.54015 + vertex 0.93892 0.94717 2.54273 + vertex 0.93725 0.949302 2.54137 + endloop + endfacet + facet normal -0.879611 -0.46652 0.092968 + outer loop + vertex 0.934582 0.947594 2.52972 + vertex 0.93511 0.947166 2.53258 + vertex 0.933661 0.949618 2.53117 + endloop + endfacet + facet normal -0.863502 -0.430662 0.262478 + outer loop + vertex 0.93511 0.947166 2.53258 + vertex 0.935291 0.949793 2.53748 + vertex 0.933616 0.95131 2.53446 + endloop + endfacet + facet normal -0.889467 -0.411292 0.199217 + outer loop + vertex 0.933661 0.949618 2.53117 + vertex 0.93511 0.947166 2.53258 + vertex 0.933616 0.95131 2.53446 + endloop + endfacet + facet normal -0.875626 -0.384405 0.292424 + outer loop + vertex 0.933959 0.953295 2.5381 + vertex 0.933616 0.95131 2.53446 + vertex 0.935291 0.949793 2.53748 + endloop + endfacet + facet normal -0.836944 -0.386431 0.387551 + outer loop + vertex 0.933959 0.953295 2.5381 + vertex 0.935291 0.949793 2.53748 + vertex 0.935323 0.953784 2.54153 + endloop + endfacet + facet normal -0.845285 -0.377155 0.378479 + outer loop + vertex 0.935323 0.953784 2.54153 + vertex 0.935291 0.949793 2.53748 + vertex 0.93725 0.949302 2.54137 + endloop + endfacet + facet normal -0.806961 -0.311235 0.501943 + outer loop + vertex 0.9394 0.949876 2.54518 + vertex 0.93725 0.949302 2.54137 + vertex 0.93892 0.94717 2.54273 + endloop + endfacet + facet normal -0.783629 -0.371554 0.497869 + outer loop + vertex 0.9394 0.949876 2.54518 + vertex 0.937527 0.953666 2.54506 + vertex 0.93725 0.949302 2.54137 + endloop + endfacet + facet normal -0.796698 -0.360137 0.485358 + outer loop + vertex 0.937527 0.953666 2.54506 + vertex 0.935323 0.953784 2.54153 + vertex 0.93725 0.949302 2.54137 + endloop + endfacet + facet normal -0.752279 -0.354271 0.555489 + outer loop + vertex 0.9394 0.949876 2.54518 + vertex 0.940324 0.952974 2.54841 + vertex 0.937527 0.953666 2.54506 + endloop + endfacet + facet normal -0.839357 -0.380975 0.387734 + outer loop + vertex 0.933959 0.953295 2.5381 + vertex 0.935323 0.953784 2.54153 + vertex 0.933574 0.956082 2.54 + endloop + endfacet + facet normal -0.836957 -0.367033 0.405944 + outer loop + vertex 0.93427 0.957376 2.54261 + vertex 0.933574 0.956082 2.54 + vertex 0.935323 0.953784 2.54153 + endloop + endfacet + facet normal -0.796046 -0.375613 0.474579 + outer loop + vertex 0.93427 0.957376 2.54261 + vertex 0.935323 0.953784 2.54153 + vertex 0.935821 0.956731 2.5447 + endloop + endfacet + facet normal -0.789398 -0.382621 0.480055 + outer loop + vertex 0.935821 0.956731 2.5447 + vertex 0.935323 0.953784 2.54153 + vertex 0.937527 0.953666 2.54506 + endloop + endfacet + facet normal -0.762805 -0.361128 0.53639 + outer loop + vertex 0.937527 0.953666 2.54506 + vertex 0.937716 0.958223 2.54839 + vertex 0.935821 0.956731 2.5447 + endloop + endfacet + facet normal -0.748843 -0.371042 0.549146 + outer loop + vertex 0.940324 0.952974 2.54841 + vertex 0.937716 0.958223 2.54839 + vertex 0.937527 0.953666 2.54506 + endloop + endfacet + facet normal -0.798896 -0.360725 0.481292 + outer loop + vertex 0.93427 0.957376 2.54261 + vertex 0.935821 0.956731 2.5447 + vertex 0.934598 0.959966 2.54509 + endloop + endfacet + facet normal -0.744714 -0.371591 0.554365 + outer loop + vertex 0.937476 0.962196 2.55075 + vertex 0.936443 0.965877 2.55183 + vertex 0.935205 0.963107 2.54831 + endloop + endfacet + facet normal -0.744547 -0.372865 0.553733 + outer loop + vertex 0.937716 0.958223 2.54839 + vertex 0.937476 0.962196 2.55075 + vertex 0.935205 0.963107 2.54831 + endloop + endfacet + facet normal -0.764131 -0.383553 0.518644 + outer loop + vertex 0.937716 0.958223 2.54839 + vertex 0.935205 0.963107 2.54831 + vertex 0.934598 0.959966 2.54509 + endloop + endfacet + facet normal -0.766192 -0.355002 0.535653 + outer loop + vertex 0.937716 0.958223 2.54839 + vertex 0.934598 0.959966 2.54509 + vertex 0.935821 0.956731 2.5447 + endloop + endfacet + facet normal -0.734954 -0.372464 0.566668 + outer loop + vertex 0.937476 0.962196 2.55075 + vertex 0.938631 0.963195 2.5529 + vertex 0.936443 0.965877 2.55183 + endloop + endfacet + facet normal -0.742533 -0.374121 0.555588 + outer loop + vertex 0.932711 0.968106 2.54834 + vertex 0.935205 0.963107 2.54831 + vertex 0.936443 0.965877 2.55183 + endloop + endfacet + facet normal -0.742474 -0.377764 0.553198 + outer loop + vertex 0.934664 0.970021 2.55227 + vertex 0.932711 0.968106 2.54834 + vertex 0.936443 0.965877 2.55183 + endloop + endfacet + facet normal -0.731598 -0.366433 0.574884 + outer loop + vertex 0.93934 0.965194 2.55508 + vertex 0.936443 0.965877 2.55183 + vertex 0.938631 0.963195 2.5529 + endloop + endfacet + facet normal -0.729509 -0.376758 0.570851 + outer loop + vertex 0.93934 0.965194 2.55508 + vertex 0.937351 0.968975 2.55503 + vertex 0.936443 0.965877 2.55183 + endloop + endfacet + facet normal -0.731539 -0.374804 0.569537 + outer loop + vertex 0.937351 0.968975 2.55503 + vertex 0.934664 0.970021 2.55227 + vertex 0.936443 0.965877 2.55183 + endloop + endfacet + facet normal -0.71947 -0.37128 0.586953 + outer loop + vertex 0.93934 0.965194 2.55508 + vertex 0.940457 0.967708 2.55804 + vertex 0.937351 0.968975 2.55503 + endloop + endfacet + facet normal -0.736151 -0.387591 0.554846 + outer loop + vertex 0.932711 0.968106 2.54834 + vertex 0.934664 0.970021 2.55227 + vertex 0.932516 0.971917 2.55074 + endloop + endfacet + facet normal -0.735144 -0.382622 0.55961 + outer loop + vertex 0.933652 0.972948 2.55294 + vertex 0.932516 0.971917 2.55074 + vertex 0.934664 0.970021 2.55227 + endloop + endfacet + facet normal -0.729849 -0.382409 0.566642 + outer loop + vertex 0.933652 0.972948 2.55294 + vertex 0.934664 0.970021 2.55227 + vertex 0.935526 0.971995 2.55471 + endloop + endfacet + facet normal -0.73069 -0.381477 0.566186 + outer loop + vertex 0.935526 0.971995 2.55471 + vertex 0.934664 0.970021 2.55227 + vertex 0.937351 0.968975 2.55503 + endloop + endfacet + facet normal -0.727121 -0.378633 0.572653 + outer loop + vertex 0.937351 0.968975 2.55503 + vertex 0.937856 0.972649 2.5581 + vertex 0.935526 0.971995 2.55471 + endloop + endfacet + facet normal -0.718037 -0.385561 0.579453 + outer loop + vertex 0.940457 0.967708 2.55804 + vertex 0.937856 0.972649 2.5581 + vertex 0.937351 0.968975 2.55503 + endloop + endfacet + facet normal -0.729316 -0.390926 0.561494 + outer loop + vertex 0.933652 0.972948 2.55294 + vertex 0.935526 0.971995 2.55471 + vertex 0.934265 0.975021 2.55518 + endloop + endfacet + facet normal -0.708554 -0.389583 0.588368 + outer loop + vertex 0.93864 0.975917 2.5612 + vertex 0.936703 0.980696 2.56204 + vertex 0.935266 0.977756 2.55836 + endloop + endfacet + facet normal -0.70856 -0.388684 0.588955 + outer loop + vertex 0.937856 0.972649 2.5581 + vertex 0.93864 0.975917 2.5612 + vertex 0.935266 0.977756 2.55836 + endloop + endfacet + facet normal -0.722548 -0.394711 0.567563 + outer loop + vertex 0.937856 0.972649 2.5581 + vertex 0.935266 0.977756 2.55836 + vertex 0.934265 0.975021 2.55518 + endloop + endfacet + facet normal -0.722293 -0.389545 0.571443 + outer loop + vertex 0.937856 0.972649 2.5581 + vertex 0.934265 0.975021 2.55518 + vertex 0.935526 0.971995 2.55471 + endloop + endfacet + facet normal -0.685183 -0.385284 0.618127 + outer loop + vertex 0.93864 0.975917 2.5612 + vertex 0.939989 0.977727 2.56383 + vertex 0.936703 0.980696 2.56204 + endloop + endfacet + facet normal -0.715953 -0.381431 0.58474 + outer loop + vertex 0.932499 0.982994 2.55839 + vertex 0.935266 0.977756 2.55836 + vertex 0.936703 0.980696 2.56204 + endloop + endfacet + facet normal -0.715907 -0.385447 0.582158 + outer loop + vertex 0.934569 0.985254 2.56243 + vertex 0.932499 0.982994 2.55839 + vertex 0.936703 0.980696 2.56204 + endloop + endfacet + facet normal -0.682065 -0.376535 0.626905 + outer loop + vertex 0.93914 0.980755 2.56472 + vertex 0.936703 0.980696 2.56204 + vertex 0.939989 0.977727 2.56383 + endloop + endfacet + facet normal -0.685737 -0.364553 0.629973 + outer loop + vertex 0.93914 0.980755 2.56472 + vertex 0.937563 0.984088 2.56493 + vertex 0.936703 0.980696 2.56204 + endloop + endfacet + facet normal -0.676637 -0.371687 0.635619 + outer loop + vertex 0.937563 0.984088 2.56493 + vertex 0.934569 0.985254 2.56243 + vertex 0.936703 0.980696 2.56204 + endloop + endfacet + facet normal -0.612753 -0.335459 0.715542 + outer loop + vertex 0.93914 0.980755 2.56472 + vertex 0.940807 0.982006 2.56674 + vertex 0.937563 0.984088 2.56493 + endloop + endfacet + facet normal -0.716009 -0.385301 0.582129 + outer loop + vertex 0.932499 0.982994 2.55839 + vertex 0.934569 0.985254 2.56243 + vertex 0.932328 0.987047 2.56086 + endloop + endfacet + facet normal -0.714182 -0.375507 0.590711 + outer loop + vertex 0.933387 0.988386 2.56299 + vertex 0.932328 0.987047 2.56086 + vertex 0.934569 0.985254 2.56243 + endloop + endfacet + facet normal -0.677399 -0.369741 0.635942 + outer loop + vertex 0.933387 0.988386 2.56299 + vertex 0.934569 0.985254 2.56243 + vertex 0.935512 0.988016 2.56504 + endloop + endfacet + facet normal -0.676707 -0.370343 0.636329 + outer loop + vertex 0.935512 0.988016 2.56504 + vertex 0.934569 0.985254 2.56243 + vertex 0.937563 0.984088 2.56493 + endloop + endfacet + facet normal -0.616151 -0.340679 0.710138 + outer loop + vertex 0.937563 0.984088 2.56493 + vertex 0.939331 0.987421 2.56807 + vertex 0.935512 0.988016 2.56504 + endloop + endfacet + facet normal -0.614483 -0.342223 0.71084 + outer loop + vertex 0.940807 0.982006 2.56674 + vertex 0.939331 0.987421 2.56807 + vertex 0.937563 0.984088 2.56493 + endloop + endfacet + facet normal -0.678917 -0.361628 0.638981 + outer loop + vertex 0.933387 0.988386 2.56299 + vertex 0.935512 0.988016 2.56504 + vertex 0.933498 0.990648 2.56439 + endloop + endfacet + facet normal -0.667763 -0.348449 0.657781 + outer loop + vertex 0.935512 0.988016 2.56504 + vertex 0.935208 0.991867 2.56677 + vertex 0.933498 0.990648 2.56439 + endloop + endfacet + facet normal -0.612876 -0.363764 0.70147 + outer loop + vertex 0.935512 0.988016 2.56504 + vertex 0.939331 0.987421 2.56807 + vertex 0.935208 0.991867 2.56677 + endloop + endfacet + facet normal -0.615342 -0.367208 0.697504 + outer loop + vertex 0.939331 0.987421 2.56807 + vertex 0.937564 0.993115 2.56951 + vertex 0.935208 0.991867 2.56677 + endloop + endfacet + facet normal -0.631459 -0.373762 0.679383 + outer loop + vertex 0.936911 0.99654 2.5707 + vertex 0.93547 0.999361 2.57091 + vertex 0.93345 0.997476 2.56799 + endloop + endfacet + facet normal -0.632721 -0.359143 0.686061 + outer loop + vertex 0.936911 0.99654 2.5707 + vertex 0.93345 0.997476 2.56799 + vertex 0.937564 0.993115 2.56951 + endloop + endfacet + facet normal -0.62573 -0.348445 0.697888 + outer loop + vertex 0.937564 0.993115 2.56951 + vertex 0.93345 0.997476 2.56799 + vertex 0.935208 0.991867 2.56677 + endloop + endfacet + facet normal -0.540877 -0.334414 0.771764 + outer loop + vertex 0.936911 0.99654 2.5707 + vertex 0.938763 0.998054 2.57265 + vertex 0.93547 0.999361 2.57091 + endloop + endfacet + facet normal -0.627201 -0.379502 0.680144 + outer loop + vertex 0.93345 0.997476 2.56799 + vertex 0.93547 0.999361 2.57091 + vertex 0.933262 1.00167 2.57016 + endloop + endfacet + facet normal -0.59828 -0.336483 0.727214 + outer loop + vertex 0.93547 0.999361 2.57091 + vertex 0.935297 1.00252 2.57223 + vertex 0.933262 1.00167 2.57016 + endloop + endfacet + facet normal -0.542576 -0.348868 0.764135 + outer loop + vertex 0.93547 0.999361 2.57091 + vertex 0.938763 0.998054 2.57265 + vertex 0.935297 1.00252 2.57223 + endloop + endfacet + facet normal -0.515292 -0.324964 0.793015 + outer loop + vertex 0.938763 0.998054 2.57265 + vertex 0.938798 1.00247 2.57448 + vertex 0.935297 1.00252 2.57223 + endloop + endfacet + facet normal -0.526611 -0.326975 0.784709 + outer loop + vertex 0.937923 1.00634 2.57555 + vertex 0.936294 1.01022 2.57608 + vertex 0.934059 1.00767 2.57352 + endloop + endfacet + facet normal -0.527409 -0.335794 0.780437 + outer loop + vertex 0.937923 1.00634 2.57555 + vertex 0.934059 1.00767 2.57352 + vertex 0.938798 1.00247 2.57448 + endloop + endfacet + facet normal -0.515693 -0.322671 0.79369 + outer loop + vertex 0.938798 1.00247 2.57448 + vertex 0.934059 1.00767 2.57352 + vertex 0.935297 1.00252 2.57223 + endloop + endfacet + facet normal -0.449334 -0.30218 0.840706 + outer loop + vertex 0.937923 1.00634 2.57555 + vertex 0.940268 1.00726 2.57714 + vertex 0.936294 1.01022 2.57608 + endloop + endfacet + facet normal -0.530122 -0.323126 0.783939 + outer loop + vertex 0.932453 1.01306 2.57465 + vertex 0.934059 1.00767 2.57352 + vertex 0.936294 1.01022 2.57608 + endloop + endfacet + facet normal -0.533711 -0.330842 0.778265 + outer loop + vertex 0.934635 1.0141 2.57659 + vertex 0.932453 1.01306 2.57465 + vertex 0.936294 1.01022 2.57608 + endloop + endfacet + facet normal -0.454711 -0.304804 0.836859 + outer loop + vertex 0.936294 1.01022 2.57608 + vertex 0.938863 1.01278 2.57841 + vertex 0.934635 1.0141 2.57659 + endloop + endfacet + facet normal -0.452332 -0.307475 0.837171 + outer loop + vertex 0.940268 1.00726 2.57714 + vertex 0.938863 1.01278 2.57841 + vertex 0.936294 1.01022 2.57608 + endloop + endfacet + facet normal -0.53777 -0.323166 0.778696 + outer loop + vertex 0.932453 1.01306 2.57465 + vertex 0.934635 1.0141 2.57659 + vertex 0.931887 1.01643 2.57566 + endloop + endfacet + facet normal -0.525662 -0.302202 0.795207 + outer loop + vertex 0.934635 1.0141 2.57659 + vertex 0.933885 1.01798 2.57757 + vertex 0.931887 1.01643 2.57566 + endloop + endfacet + facet normal -0.454028 -0.299448 0.83916 + outer loop + vertex 0.934635 1.0141 2.57659 + vertex 0.938863 1.01278 2.57841 + vertex 0.933885 1.01798 2.57757 + endloop + endfacet + facet normal -0.467453 -0.314391 0.826224 + outer loop + vertex 0.938863 1.01278 2.57841 + vertex 0.937469 1.01818 2.57968 + vertex 0.933885 1.01798 2.57757 + endloop + endfacet + facet normal -0.466448 -0.300653 0.831886 + outer loop + vertex 0.937223 1.02139 2.58071 + vertex 0.935807 1.02435 2.58098 + vertex 0.933829 1.02266 2.57927 + endloop + endfacet + facet normal -0.466962 -0.303547 0.830546 + outer loop + vertex 0.937223 1.02139 2.58071 + vertex 0.933829 1.02266 2.57927 + vertex 0.937469 1.01818 2.57968 + endloop + endfacet + facet normal -0.469271 -0.305613 0.828484 + outer loop + vertex 0.937469 1.01818 2.57968 + vertex 0.933829 1.02266 2.57927 + vertex 0.933885 1.01798 2.57757 + endloop + endfacet + facet normal -0.426297 -0.283936 0.858866 + outer loop + vertex 0.937223 1.02139 2.58071 + vertex 0.939283 1.023 2.58226 + vertex 0.935807 1.02435 2.58098 + endloop + endfacet + facet normal -0.469891 -0.296249 0.831528 + outer loop + vertex 0.933829 1.02266 2.57927 + vertex 0.935807 1.02435 2.58098 + vertex 0.933131 1.02671 2.58032 + endloop + endfacet + facet normal -0.456776 -0.277565 0.845171 + outer loop + vertex 0.935807 1.02435 2.58098 + vertex 0.935666 1.02823 2.58218 + vertex 0.933131 1.02671 2.58032 + endloop + endfacet + facet normal -0.42565 -0.281058 0.860133 + outer loop + vertex 0.935807 1.02435 2.58098 + vertex 0.939283 1.023 2.58226 + vertex 0.935666 1.02823 2.58218 + endloop + endfacet + facet normal -0.427259 -0.282189 0.858964 + outer loop + vertex 0.939283 1.023 2.58226 + vertex 0.940094 1.02713 2.58402 + vertex 0.935666 1.02823 2.58218 + endloop + endfacet + facet normal -0.427305 -0.282672 0.858782 + outer loop + vertex 0.940094 1.02713 2.58402 + vertex 0.937225 1.03241 2.58434 + vertex 0.935666 1.02823 2.58218 + endloop + endfacet + facet normal -0.429439 -0.281522 0.858095 + outer loop + vertex 0.935666 1.02823 2.58218 + vertex 0.937225 1.03241 2.58434 + vertex 0.932921 1.03341 2.58251 + endloop + endfacet + facet normal -0.426637 -0.279805 0.860052 + outer loop + vertex 0.937101 1.0363 2.58553 + vertex 0.935728 1.03935 2.58585 + vertex 0.93355 1.03755 2.58418 + endloop + endfacet + facet normal -0.426406 -0.278608 0.860555 + outer loop + vertex 0.937101 1.0363 2.58553 + vertex 0.93355 1.03755 2.58418 + vertex 0.937225 1.03241 2.58434 + endloop + endfacet + facet normal -0.429384 -0.280803 0.858358 + outer loop + vertex 0.937225 1.03241 2.58434 + vertex 0.93355 1.03755 2.58418 + vertex 0.932921 1.03341 2.58251 + endloop + endfacet + facet normal -0.435576 -0.283247 0.854426 + outer loop + vertex 0.937101 1.0363 2.58553 + vertex 0.939301 1.03808 2.58724 + vertex 0.935728 1.03935 2.58585 + endloop + endfacet + facet normal -0.426185 -0.280386 0.860087 + outer loop + vertex 0.93355 1.03755 2.58418 + vertex 0.935728 1.03935 2.58585 + vertex 0.933078 1.04159 2.58526 + endloop + endfacet + facet normal -0.423745 -0.276873 0.862428 + outer loop + vertex 0.935728 1.03935 2.58585 + vertex 0.935733 1.04321 2.58709 + vertex 0.933078 1.04159 2.58526 + endloop + endfacet + facet normal -0.434066 -0.275361 0.857767 + outer loop + vertex 0.935728 1.03935 2.58585 + vertex 0.939301 1.03808 2.58724 + vertex 0.935733 1.04321 2.58709 + endloop + endfacet + facet normal -0.436567 -0.277155 0.855917 + outer loop + vertex 0.939301 1.03808 2.58724 + vertex 0.939961 1.04231 2.58895 + vertex 0.935733 1.04321 2.58709 + endloop + endfacet + facet normal -0.436101 -0.26945 0.858611 + outer loop + vertex 0.939961 1.04231 2.58895 + vertex 0.937532 1.04731 2.58929 + vertex 0.935733 1.04321 2.58709 + endloop + endfacet + facet normal -0.427054 -0.274931 0.861416 + outer loop + vertex 0.935733 1.04321 2.58709 + vertex 0.937532 1.04731 2.58929 + vertex 0.933237 1.04834 2.58749 + endloop + endfacet + facet normal -0.438289 -0.274789 0.8558 + outer loop + vertex 0.937684 1.05111 2.59057 + vertex 0.936272 1.05487 2.59105 + vertex 0.934501 1.05199 2.58922 + endloop + endfacet + facet normal -0.437895 -0.271478 0.857057 + outer loop + vertex 0.937684 1.05111 2.59057 + vertex 0.934501 1.05199 2.58922 + vertex 0.937532 1.04731 2.58929 + endloop + endfacet + facet normal -0.426033 -0.263687 0.865428 + outer loop + vertex 0.937532 1.04731 2.58929 + vertex 0.934501 1.05199 2.58922 + vertex 0.933237 1.04834 2.58749 + endloop + endfacet + facet normal -0.481464 -0.287378 0.828013 + outer loop + vertex 0.937684 1.05111 2.59057 + vertex 0.93994 1.05224 2.59227 + vertex 0.936272 1.05487 2.59105 + endloop + endfacet + facet normal -0.440033 -0.273425 0.855342 + outer loop + vertex 0.93201 1.05714 2.58958 + vertex 0.934501 1.05199 2.58922 + vertex 0.936272 1.05487 2.59105 + endloop + endfacet + facet normal -0.437447 -0.266218 0.858934 + outer loop + vertex 0.93465 1.05876 2.59143 + vertex 0.93201 1.05714 2.58958 + vertex 0.936272 1.05487 2.59105 + endloop + endfacet + facet normal -0.478563 -0.280769 0.831953 + outer loop + vertex 0.936272 1.05487 2.59105 + vertex 0.938695 1.05767 2.59339 + vertex 0.93465 1.05876 2.59143 + endloop + endfacet + facet normal -0.478265 -0.281082 0.832019 + outer loop + vertex 0.93994 1.05224 2.59227 + vertex 0.938695 1.05767 2.59339 + vertex 0.936272 1.05487 2.59105 + endloop + endfacet + facet normal -0.440378 -0.261419 0.858911 + outer loop + vertex 0.93201 1.05714 2.58958 + vertex 0.93465 1.05876 2.59143 + vertex 0.931993 1.06104 2.59076 + endloop + endfacet + facet normal -0.443105 -0.265352 0.856298 + outer loop + vertex 0.93465 1.05876 2.59143 + vertex 0.934166 1.06286 2.59245 + vertex 0.931993 1.06104 2.59076 + endloop + endfacet + facet normal -0.477193 -0.264814 0.83795 + outer loop + vertex 0.93465 1.05876 2.59143 + vertex 0.938695 1.05767 2.59339 + vertex 0.934166 1.06286 2.59245 + endloop + endfacet + facet normal -0.476866 -0.264476 0.838243 + outer loop + vertex 0.938695 1.05767 2.59339 + vertex 0.937786 1.06297 2.59455 + vertex 0.934166 1.06286 2.59245 + endloop + endfacet + facet normal -0.493569 -0.256118 0.83114 + outer loop + vertex 0.937762 1.06619 2.59555 + vertex 0.936438 1.06985 2.59589 + vertex 0.934834 1.06708 2.59408 + endloop + endfacet + facet normal -0.494187 -0.261539 0.829082 + outer loop + vertex 0.937762 1.06619 2.59555 + vertex 0.934834 1.06708 2.59408 + vertex 0.937786 1.06297 2.59455 + endloop + endfacet + facet normal -0.479238 -0.249413 0.841501 + outer loop + vertex 0.937786 1.06297 2.59455 + vertex 0.934834 1.06708 2.59408 + vertex 0.934166 1.06286 2.59245 + endloop + endfacet + facet normal -0.532046 -0.267487 0.803354 + outer loop + vertex 0.937762 1.06619 2.59555 + vertex 0.939907 1.06707 2.59726 + vertex 0.936438 1.06985 2.59589 + endloop + endfacet + facet normal -0.487472 -0.261014 0.833212 + outer loop + vertex 0.932456 1.07217 2.59429 + vertex 0.934834 1.06708 2.59408 + vertex 0.936438 1.06985 2.59589 + endloop + endfacet + facet normal -0.479401 -0.239617 0.84425 + outer loop + vertex 0.935066 1.07363 2.59618 + vertex 0.932456 1.07217 2.59429 + vertex 0.936438 1.06985 2.59589 + endloop + endfacet + facet normal -0.529335 -0.254963 0.809196 + outer loop + vertex 0.936438 1.06985 2.59589 + vertex 0.938846 1.07254 2.59831 + vertex 0.935066 1.07363 2.59618 + endloop + endfacet + facet normal -0.526888 -0.257786 0.809899 + outer loop + vertex 0.939907 1.06707 2.59726 + vertex 0.938846 1.07254 2.59831 + vertex 0.936438 1.06985 2.59589 + endloop + endfacet + facet normal -0.481833 -0.235117 0.844131 + outer loop + vertex 0.932456 1.07217 2.59429 + vertex 0.935066 1.07363 2.59618 + vertex 0.932678 1.07604 2.59549 + endloop + endfacet + facet normal -0.497582 -0.255067 0.829068 + outer loop + vertex 0.935066 1.07363 2.59618 + vertex 0.934949 1.0772 2.59721 + vertex 0.932678 1.07604 2.59549 + endloop + endfacet + facet normal -0.528986 -0.250817 0.810719 + outer loop + vertex 0.935066 1.07363 2.59618 + vertex 0.938846 1.07254 2.59831 + vertex 0.934949 1.0772 2.59721 + endloop + endfacet + facet normal -0.529487 -0.251353 0.810225 + outer loop + vertex 0.938846 1.07254 2.59831 + vertex 0.937792 1.07801 2.59932 + vertex 0.934949 1.0772 2.59721 + endloop + endfacet + facet normal -0.524365 -0.256168 0.812047 + outer loop + vertex 0.937629 1.08137 2.60029 + vertex 0.936425 1.08509 2.60069 + vertex 0.9338 1.08273 2.59825 + endloop + endfacet + facet normal -0.524855 -0.25969 0.81061 + outer loop + vertex 0.937629 1.08137 2.60029 + vertex 0.9338 1.08273 2.59825 + vertex 0.937792 1.07801 2.59932 + endloop + endfacet + facet normal -0.5261 -0.261023 0.809374 + outer loop + vertex 0.937792 1.07801 2.59932 + vertex 0.9338 1.08273 2.59825 + vertex 0.934949 1.0772 2.59721 + endloop + endfacet + facet normal -0.537417 -0.259366 0.802442 + outer loop + vertex 0.937629 1.08137 2.60029 + vertex 0.939937 1.08205 2.60206 + vertex 0.936425 1.08509 2.60069 + endloop + endfacet + facet normal -0.529655 -0.24902 0.810836 + outer loop + vertex 0.932936 1.08809 2.59933 + vertex 0.9338 1.08273 2.59825 + vertex 0.936425 1.08509 2.60069 + endloop + endfacet + facet normal -0.530642 -0.25069 0.809675 + outer loop + vertex 0.935236 1.08884 2.60107 + vertex 0.932936 1.08809 2.59933 + vertex 0.936425 1.08509 2.60069 + endloop + endfacet + facet normal -0.547007 -0.254636 0.797461 + outer loop + vertex 0.936425 1.08509 2.60069 + vertex 0.939004 1.0874 2.60319 + vertex 0.935236 1.08884 2.60107 + endloop + endfacet + facet normal -0.540149 -0.264049 0.799073 + outer loop + vertex 0.939937 1.08205 2.60206 + vertex 0.939004 1.0874 2.60319 + vertex 0.936425 1.08509 2.60069 + endloop + endfacet + facet normal -0.532947 -0.244476 0.810061 + outer loop + vertex 0.932936 1.08809 2.59933 + vertex 0.935236 1.08884 2.60107 + vertex 0.932926 1.09133 2.6003 + endloop + endfacet + facet normal -0.545359 -0.260048 0.796843 + outer loop + vertex 0.935236 1.08884 2.60107 + vertex 0.935049 1.09221 2.60204 + vertex 0.932926 1.09133 2.6003 + endloop + endfacet + facet normal -0.547744 -0.259738 0.795306 + outer loop + vertex 0.935236 1.08884 2.60107 + vertex 0.939004 1.0874 2.60319 + vertex 0.935049 1.09221 2.60204 + endloop + endfacet + facet normal -0.551569 -0.263841 0.791302 + outer loop + vertex 0.939004 1.0874 2.60319 + vertex 0.937857 1.093 2.60426 + vertex 0.935049 1.09221 2.60204 + endloop + endfacet + facet normal -0.551089 -0.242568 0.798412 + outer loop + vertex 0.937732 1.09659 2.60529 + vertex 0.936364 1.10039 2.6055 + vertex 0.93397 1.09771 2.60303 + endloop + endfacet + facet normal -0.551481 -0.24754 0.796613 + outer loop + vertex 0.937732 1.09659 2.60529 + vertex 0.93397 1.09771 2.60303 + vertex 0.937857 1.093 2.60426 + endloop + endfacet + facet normal -0.555639 -0.252096 0.792283 + outer loop + vertex 0.937857 1.093 2.60426 + vertex 0.93397 1.09771 2.60303 + vertex 0.935049 1.09221 2.60204 + endloop + endfacet + facet normal -0.490603 -0.223225 0.842306 + outer loop + vertex 0.937732 1.09659 2.60529 + vertex 0.940375 1.0981 2.60723 + vertex 0.936364 1.10039 2.6055 + endloop + endfacet + facet normal -0.551649 -0.2419 0.798228 + outer loop + vertex 0.932972 1.10319 2.604 + vertex 0.93397 1.09771 2.60303 + vertex 0.936364 1.10039 2.6055 + endloop + endfacet + facet normal -0.557024 -0.252142 0.791295 + outer loop + vertex 0.935096 1.10403 2.60577 + vertex 0.932972 1.10319 2.604 + vertex 0.936364 1.10039 2.6055 + endloop + endfacet + facet normal -0.523079 -0.242211 0.817143 + outer loop + vertex 0.936364 1.10039 2.6055 + vertex 0.938078 1.10298 2.60737 + vertex 0.935096 1.10403 2.60577 + endloop + endfacet + facet normal -0.503653 -0.259935 0.823874 + outer loop + vertex 0.940375 1.0981 2.60723 + vertex 0.938078 1.10298 2.60737 + vertex 0.936364 1.10039 2.6055 + endloop + endfacet + facet normal -0.559877 -0.245276 0.79144 + outer loop + vertex 0.932972 1.10319 2.604 + vertex 0.935096 1.10403 2.60577 + vertex 0.932914 1.1065 2.60499 + endloop + endfacet + facet normal -0.559494 -0.244806 0.791856 + outer loop + vertex 0.935096 1.10403 2.60577 + vertex 0.935243 1.10707 2.60681 + vertex 0.932914 1.1065 2.60499 + endloop + endfacet + facet normal -0.524694 -0.253621 0.812634 + outer loop + vertex 0.935096 1.10403 2.60577 + vertex 0.938078 1.10298 2.60737 + vertex 0.935243 1.10707 2.60681 + endloop + endfacet + facet normal -0.513728 -0.244708 0.822315 + outer loop + vertex 0.938078 1.10298 2.60737 + vertex 0.938817 1.10704 2.60903 + vertex 0.935243 1.10707 2.60681 + endloop + endfacet + facet normal -0.513986 -0.225342 0.827671 + outer loop + vertex 0.938372 1.11126 2.61003 + vertex 0.93703 1.11541 2.61033 + vertex 0.934919 1.11184 2.60804 + endloop + endfacet + facet normal -0.514019 -0.247872 0.821184 + outer loop + vertex 0.938372 1.11126 2.61003 + vertex 0.934919 1.11184 2.60804 + vertex 0.938817 1.10704 2.60903 + endloop + endfacet + facet normal -0.513405 -0.247256 0.821754 + outer loop + vertex 0.938817 1.10704 2.60903 + vertex 0.934919 1.11184 2.60804 + vertex 0.935243 1.10707 2.60681 + endloop + endfacet + facet normal -0.377202 -0.186656 0.907126 + outer loop + vertex 0.938372 1.11126 2.61003 + vertex 0.941296 1.11353 2.61171 + vertex 0.93703 1.11541 2.61033 + endloop + endfacet + facet normal -0.517792 -0.222127 0.826167 + outer loop + vertex 0.932896 1.11781 2.60838 + vertex 0.934919 1.11184 2.60804 + vertex 0.93703 1.11541 2.61033 + endloop + endfacet + facet normal -0.521152 -0.231749 0.821397 + outer loop + vertex 0.935899 1.12022 2.61097 + vertex 0.932896 1.11781 2.60838 + vertex 0.93703 1.11541 2.61033 + endloop + endfacet + facet normal -0.407736 -0.213942 0.887682 + outer loop + vertex 0.93703 1.11541 2.61033 + vertex 0.939738 1.11859 2.61234 + vertex 0.935899 1.12022 2.61097 + endloop + endfacet + facet normal -0.391111 -0.230215 0.891085 + outer loop + vertex 0.941296 1.11353 2.61171 + vertex 0.939738 1.11859 2.61234 + vertex 0.93703 1.11541 2.61033 + endloop + endfacet + facet normal -0.517626 -0.236953 0.822142 + outer loop + vertex 0.932493 1.12284 2.60958 + vertex 0.932896 1.11781 2.60838 + vertex 0.935899 1.12022 2.61097 + endloop + endfacet + facet normal -0.520052 -0.241643 0.81924 + outer loop + vertex 0.934975 1.124 2.61149 + vertex 0.932493 1.12284 2.60958 + vertex 0.935899 1.12022 2.61097 + endloop + endfacet + facet normal -0.416445 -0.224909 0.880903 + outer loop + vertex 0.935899 1.12022 2.61097 + vertex 0.938461 1.12355 2.61303 + vertex 0.934975 1.124 2.61149 + endloop + endfacet + facet normal -0.412036 -0.22894 0.881937 + outer loop + vertex 0.939738 1.11859 2.61234 + vertex 0.938461 1.12355 2.61303 + vertex 0.935899 1.12022 2.61097 + endloop + endfacet + facet normal -0.524151 -0.23277 0.819197 + outer loop + vertex 0.932493 1.12284 2.60958 + vertex 0.934975 1.124 2.61149 + vertex 0.93261 1.12634 2.61065 + endloop + endfacet + facet normal -0.505548 -0.207348 0.837513 + outer loop + vertex 0.934975 1.124 2.61149 + vertex 0.935238 1.12777 2.61259 + vertex 0.93261 1.12634 2.61065 + endloop + endfacet + facet normal -0.416459 -0.226014 0.880613 + outer loop + vertex 0.934975 1.124 2.61149 + vertex 0.938461 1.12355 2.61303 + vertex 0.935238 1.12777 2.61259 + endloop + endfacet + facet normal -0.417472 -0.226859 0.879916 + outer loop + vertex 0.938461 1.12355 2.61303 + vertex 0.938466 1.12711 2.61395 + vertex 0.935238 1.12777 2.61259 + endloop + endfacet + facet normal -0.417021 -0.221407 0.881517 + outer loop + vertex 0.938466 1.12711 2.61395 + vertex 0.93764 1.13125 2.6146 + vertex 0.935238 1.12777 2.61259 + endloop + endfacet + facet normal -0.439557 -0.202156 0.87517 + outer loop + vertex 0.935238 1.12777 2.61259 + vertex 0.93764 1.13125 2.6146 + vertex 0.932947 1.13278 2.61259 + endloop + endfacet + facet normal -0.430305 -0.240204 0.870137 + outer loop + vertex 0.937153 1.13578 2.61564 + vertex 0.935718 1.13906 2.61584 + vertex 0.933607 1.13687 2.61419 + endloop + endfacet + facet normal -0.4313 -0.246388 0.867913 + outer loop + vertex 0.937153 1.13578 2.61564 + vertex 0.933607 1.13687 2.61419 + vertex 0.93764 1.13125 2.6146 + endloop + endfacet + facet normal -0.449709 -0.26058 0.854319 + outer loop + vertex 0.93764 1.13125 2.6146 + vertex 0.933607 1.13687 2.61419 + vertex 0.932947 1.13278 2.61259 + endloop + endfacet + facet normal -0.264308 -0.172246 0.948932 + outer loop + vertex 0.937153 1.13578 2.61564 + vertex 0.940081 1.1389 2.61702 + vertex 0.935718 1.13906 2.61584 + endloop + endfacet + facet normal -0.436182 -0.233667 0.868991 + outer loop + vertex 0.933607 1.13687 2.61419 + vertex 0.935718 1.13906 2.61584 + vertex 0.933163 1.14118 2.61512 + endloop + endfacet + facet normal -0.395051 -0.172994 0.902224 + outer loop + vertex 0.935718 1.13906 2.61584 + vertex 0.936115 1.14343 2.61685 + vertex 0.933163 1.14118 2.61512 + endloop + endfacet + facet normal -0.263972 -0.194732 0.944668 + outer loop + vertex 0.935718 1.13906 2.61584 + vertex 0.940081 1.1389 2.61702 + vertex 0.936115 1.14343 2.61685 + endloop + endfacet + facet normal -0.251837 -0.183909 0.950135 + outer loop + vertex 0.940081 1.1389 2.61702 + vertex 0.940297 1.14414 2.61809 + vertex 0.936115 1.14343 2.61685 + endloop + endfacet + facet normal -0.248535 -0.199412 0.947874 + outer loop + vertex 0.940297 1.14414 2.61809 + vertex 0.938877 1.14789 2.61851 + vertex 0.936115 1.14343 2.61685 + endloop + endfacet + facet normal -0.277906 -0.179654 0.943659 + outer loop + vertex 0.936115 1.14343 2.61685 + vertex 0.938877 1.14789 2.61851 + vertex 0.934649 1.14857 2.6174 + endloop + endfacet + facet normal -0.281715 -0.218658 0.934251 + outer loop + vertex 0.938877 1.14789 2.61851 + vertex 0.937283 1.15164 2.61891 + vertex 0.934649 1.14857 2.6174 + endloop + endfacet + facet normal -0.307451 -0.195118 0.931345 + outer loop + vertex 0.934649 1.14857 2.6174 + vertex 0.937283 1.15164 2.61891 + vertex 0.933468 1.15354 2.61805 + endloop + endfacet + facet normal -0.307323 -0.194814 0.93145 + outer loop + vertex 0.937283 1.15164 2.61891 + vertex 0.937336 1.15632 2.6199 + vertex 0.933468 1.15354 2.61805 + endloop + endfacet + facet normal -0.281205 -0.231109 0.931404 + outer loop + vertex 0.933468 1.15354 2.61805 + vertex 0.937336 1.15632 2.6199 + vertex 0.933532 1.15706 2.61894 + endloop + endfacet + facet normal -0.311438 -0.235125 0.920719 + outer loop + vertex 0.93695 1.16056 2.62079 + vertex 0.935127 1.16373 2.62098 + vertex 0.932688 1.1611 2.61949 + endloop + endfacet + facet normal -0.310806 -0.221389 0.92433 + outer loop + vertex 0.93695 1.16056 2.62079 + vertex 0.932688 1.1611 2.61949 + vertex 0.937336 1.15632 2.6199 + endloop + endfacet + facet normal -0.275334 -0.185254 0.94333 + outer loop + vertex 0.937336 1.15632 2.6199 + vertex 0.932688 1.1611 2.61949 + vertex 0.933532 1.15706 2.61894 + endloop + endfacet + facet normal -0.166338 -0.154946 0.973819 + outer loop + vertex 0.93695 1.16056 2.62079 + vertex 0.93983 1.16386 2.62181 + vertex 0.935127 1.16373 2.62098 + endloop + endfacet + facet normal -0.324119 -0.222644 0.919444 + outer loop + vertex 0.932688 1.1611 2.61949 + vertex 0.935127 1.16373 2.62098 + vertex 0.932062 1.1657 2.62038 + endloop + endfacet + facet normal -0.291704 -0.1652 0.942135 + outer loop + vertex 0.935127 1.16373 2.62098 + vertex 0.935094 1.16876 2.62186 + vertex 0.932062 1.1657 2.62038 + endloop + endfacet + facet normal -0.165553 -0.169452 0.971534 + outer loop + vertex 0.935127 1.16373 2.62098 + vertex 0.93983 1.16386 2.62181 + vertex 0.935094 1.16876 2.62186 + endloop + endfacet + facet normal -0.151766 -0.156183 0.975999 + outer loop + vertex 0.93983 1.16386 2.62181 + vertex 0.939921 1.16918 2.62267 + vertex 0.935094 1.16876 2.62186 + endloop + endfacet + facet normal -0.150884 -0.164182 0.974822 + outer loop + vertex 0.939921 1.16918 2.62267 + vertex 0.939011 1.17335 2.62323 + vertex 0.935094 1.16876 2.62186 + endloop + endfacet + facet normal -0.129184 -0.182662 0.974652 + outer loop + vertex 0.935094 1.16876 2.62186 + vertex 0.939011 1.17335 2.62323 + vertex 0.935306 1.1741 2.62288 + endloop + endfacet + facet normal -0.125293 -0.161421 0.9789 + outer loop + vertex 0.939011 1.17335 2.62323 + vertex 0.938443 1.17804 2.62393 + vertex 0.935306 1.1741 2.62288 + endloop + endfacet + facet normal -0.148118 -0.143156 0.978554 + outer loop + vertex 0.935306 1.1741 2.62288 + vertex 0.938443 1.17804 2.62393 + vertex 0.93396 1.17802 2.62325 + endloop + endfacet + facet normal -0.147439 -0.167794 0.974734 + outer loop + vertex 0.938443 1.17804 2.62393 + vertex 0.937063 1.18291 2.62457 + vertex 0.93396 1.17802 2.62325 + endloop + endfacet + facet normal -0.177608 -0.148169 0.972883 + outer loop + vertex 0.93396 1.17802 2.62325 + vertex 0.937063 1.18291 2.62457 + vertex 0.932466 1.18195 2.62358 + endloop + endfacet + facet normal -0.15955 -0.217969 0.962826 + outer loop + vertex 0.93741 1.18719 2.62539 + vertex 0.935566 1.18983 2.62568 + vertex 0.93269 1.18688 2.62453 + endloop + endfacet + facet normal -0.163996 -0.173018 0.97117 + outer loop + vertex 0.93741 1.18719 2.62539 + vertex 0.93269 1.18688 2.62453 + vertex 0.937063 1.18291 2.62457 + endloop + endfacet + facet normal -0.170131 -0.179799 0.96888 + outer loop + vertex 0.937063 1.18291 2.62457 + vertex 0.93269 1.18688 2.62453 + vertex 0.932466 1.18195 2.62358 + endloop + endfacet + facet normal -0.0725208 -0.159589 0.984516 + outer loop + vertex 0.93741 1.18719 2.62539 + vertex 0.939833 1.1906 2.62612 + vertex 0.935566 1.18983 2.62568 + endloop + endfacet + facet normal -0.168246 -0.209636 0.963196 + outer loop + vertex 0.93269 1.18688 2.62453 + vertex 0.935566 1.18983 2.62568 + vertex 0.932521 1.19115 2.62543 + endloop + endfacet + facet normal -0.150459 -0.166304 0.974528 + outer loop + vertex 0.935566 1.18983 2.62568 + vertex 0.935346 1.19424 2.6264 + vertex 0.932521 1.19115 2.62543 + endloop + endfacet + facet normal -0.0716794 -0.163893 0.983871 + outer loop + vertex 0.935566 1.18983 2.62568 + vertex 0.939833 1.1906 2.62612 + vertex 0.935346 1.19424 2.6264 + endloop + endfacet + facet normal -0.0614045 -0.151422 0.98656 + outer loop + vertex 0.939833 1.1906 2.62612 + vertex 0.940161 1.19465 2.62676 + vertex 0.935346 1.19424 2.6264 + endloop + endfacet + facet normal -0.0613925 -0.151547 0.986542 + outer loop + vertex 0.940161 1.19465 2.62676 + vertex 0.939032 1.19831 2.62725 + vertex 0.935346 1.19424 2.6264 + endloop + endfacet + facet normal -0.0566999 -0.155723 0.986172 + outer loop + vertex 0.935346 1.19424 2.6264 + vertex 0.939032 1.19831 2.62725 + vertex 0.935257 1.19908 2.62716 + endloop + endfacet + facet normal -0.0502036 -0.123486 0.991076 + outer loop + vertex 0.939032 1.19831 2.62725 + vertex 0.938483 1.20289 2.62779 + vertex 0.935257 1.19908 2.62716 + endloop + endfacet + facet normal -0.0807918 -0.0976975 0.991931 + outer loop + vertex 0.935257 1.19908 2.62716 + vertex 0.938483 1.20289 2.62779 + vertex 0.934029 1.20302 2.62744 + endloop + endfacet + facet normal -0.0804073 -0.0805442 0.993503 + outer loop + vertex 0.938483 1.20289 2.62779 + vertex 0.938137 1.20776 2.62816 + vertex 0.934029 1.20302 2.62744 + endloop + endfacet + facet normal -0.113252 -0.0518982 0.99221 + outer loop + vertex 0.934029 1.20302 2.62744 + vertex 0.938137 1.20776 2.62816 + vertex 0.933392 1.20794 2.62763 + endloop + endfacet + facet normal -0.151113 -0.00358417 0.98851 + outer loop + vertex 0.933392 1.20794 2.62763 + vertex 0.938063 1.21297 2.62836 + vertex 0.932558 1.21354 2.62752 + endloop + endfacet + facet normal -0.153893 -0.0318013 0.987576 + outer loop + vertex 0.938063 1.21297 2.62836 + vertex 0.938527 1.21826 2.6286 + vertex 0.932558 1.21354 2.62752 + endloop + endfacet + facet normal -0.140088 -0.0495796 0.988897 + outer loop + vertex 0.932558 1.21354 2.62752 + vertex 0.938527 1.21826 2.6286 + vertex 0.934835 1.2192 2.62813 + endloop + endfacet + facet normal -0.143296 -0.0627821 0.987686 + outer loop + vertex 0.938527 1.21826 2.6286 + vertex 0.938906 1.22313 2.62897 + vertex 0.934835 1.2192 2.62813 + endloop + endfacet + facet normal -0.135985 -0.0704553 0.988203 + outer loop + vertex 0.934835 1.2192 2.62813 + vertex 0.938906 1.22313 2.62897 + vertex 0.93421 1.22332 2.62833 + endloop + endfacet + facet normal -0.137118 -0.113494 0.984031 + outer loop + vertex 0.938906 1.22313 2.62897 + vertex 0.938443 1.22764 2.62942 + vertex 0.93421 1.22332 2.62833 + endloop + endfacet + facet normal -0.123407 -0.126955 0.984202 + outer loop + vertex 0.93421 1.22332 2.62833 + vertex 0.938443 1.22764 2.62942 + vertex 0.93359 1.22794 2.62885 + endloop + endfacet + facet normal -0.124545 -0.153542 0.980262 + outer loop + vertex 0.938443 1.22764 2.62942 + vertex 0.937048 1.23241 2.62999 + vertex 0.93359 1.22794 2.62885 + endloop + endfacet + facet normal -0.129253 -0.149893 0.980217 + outer loop + vertex 0.93359 1.22794 2.62885 + vertex 0.937048 1.23241 2.62999 + vertex 0.93239 1.23156 2.62925 + endloop + endfacet + facet normal -0.134525 -0.163918 0.977258 + outer loop + vertex 0.937312 1.23657 2.63069 + vertex 0.935374 1.23935 2.63089 + vertex 0.932329 1.23631 2.62996 + endloop + endfacet + facet normal -0.135191 -0.155052 0.978612 + outer loop + vertex 0.937312 1.23657 2.63069 + vertex 0.932329 1.23631 2.62996 + vertex 0.937048 1.23241 2.62999 + endloop + endfacet + facet normal -0.129586 -0.148246 0.980424 + outer loop + vertex 0.937048 1.23241 2.62999 + vertex 0.932329 1.23631 2.62996 + vertex 0.93239 1.23156 2.62925 + endloop + endfacet + facet normal -0.0721193 -0.121331 0.989989 + outer loop + vertex 0.937312 1.23657 2.63069 + vertex 0.939768 1.24001 2.63129 + vertex 0.935374 1.23935 2.63089 + endloop + endfacet + facet normal -0.14197 -0.156517 0.977418 + outer loop + vertex 0.932329 1.23631 2.62996 + vertex 0.935374 1.23935 2.63089 + vertex 0.932226 1.24084 2.63067 + endloop + endfacet + facet normal -0.121172 -0.111362 0.986365 + outer loop + vertex 0.935374 1.23935 2.63089 + vertex 0.935228 1.24398 2.63139 + vertex 0.932226 1.24084 2.63067 + endloop + endfacet + facet normal -0.0738679 -0.110391 0.991139 + outer loop + vertex 0.935374 1.23935 2.63089 + vertex 0.939768 1.24001 2.63129 + vertex 0.935228 1.24398 2.63139 + endloop + endfacet + facet normal -0.0649147 -0.100195 0.992848 + outer loop + vertex 0.939768 1.24001 2.63129 + vertex 0.940083 1.24431 2.63174 + vertex 0.935228 1.24398 2.63139 + endloop + endfacet + facet normal -0.0655463 -0.0917307 0.993624 + outer loop + vertex 0.940083 1.24431 2.63174 + vertex 0.939005 1.24815 2.63203 + vertex 0.935228 1.24398 2.63139 + endloop + endfacet + facet normal -0.0430128 0.0411514 0.998227 + outer loop + vertex 0.93346 1.74714 2.63385 + vertex 0.938449 1.75213 2.63386 + vertex 0.933404 1.75205 2.63365 + endloop + endfacet + facet normal -0.042981 0.0389016 0.998318 + outer loop + vertex 0.938449 1.75213 2.63386 + vertex 0.938441 1.75709 2.63367 + vertex 0.933404 1.75205 2.63365 + endloop + endfacet + facet normal -0.0175142 0.013408 0.999757 + outer loop + vertex 0.933404 1.75205 2.63365 + vertex 0.938441 1.75709 2.63367 + vertex 0.933365 1.757 2.63358 + endloop + endfacet + facet normal -0.3214 0.262895 0.909719 + outer loop + vertex 0.933175 1.88139 2.61447 + vertex 0.938188 1.88656 2.61475 + vertex 0.933058 1.88666 2.61291 + endloop + endfacet + facet normal -0.326189 0.214478 0.920652 + outer loop + vertex 0.938188 1.88656 2.61475 + vertex 0.938309 1.89183 2.61357 + vertex 0.933058 1.88666 2.61291 + endloop + endfacet + facet normal -0.308659 0.195368 0.930892 + outer loop + vertex 0.933058 1.88666 2.61291 + vertex 0.938309 1.89183 2.61357 + vertex 0.934215 1.89227 2.61211 + endloop + endfacet + facet normal -0.309317 0.19135 0.931509 + outer loop + vertex 0.938309 1.89183 2.61357 + vertex 0.938623 1.89679 2.61265 + vertex 0.934215 1.89227 2.61211 + endloop + endfacet + facet normal -0.296958 0.178508 0.938057 + outer loop + vertex 0.934215 1.89227 2.61211 + vertex 0.938623 1.89679 2.61265 + vertex 0.934852 1.89672 2.61147 + endloop + endfacet + facet normal -0.482534 0.28436 0.828433 + outer loop + vertex 0.936574 1.90275 2.61078 + vertex 0.933235 1.90142 2.60929 + vertex 0.934964 1.89977 2.61087 + endloop + endfacet + facet normal -0.310531 0.194031 0.930549 + outer loop + vertex 0.934964 1.89977 2.61087 + vertex 0.938529 1.90131 2.61174 + vertex 0.936574 1.90275 2.61078 + endloop + endfacet + facet normal -0.310953 0.195231 0.930157 + outer loop + vertex 0.934964 1.89977 2.61087 + vertex 0.934852 1.89672 2.61147 + vertex 0.938529 1.90131 2.61174 + endloop + endfacet + facet normal -0.296764 0.183456 0.937163 + outer loop + vertex 0.934852 1.89672 2.61147 + vertex 0.938623 1.89679 2.61265 + vertex 0.938529 1.90131 2.61174 + endloop + endfacet + facet normal -0.363693 0.283787 0.887239 + outer loop + vertex 0.936574 1.90275 2.61078 + vertex 0.939297 1.90504 2.61117 + vertex 0.937636 1.90663 2.60998 + endloop + endfacet + facet normal -0.486093 0.303281 0.819594 + outer loop + vertex 0.936574 1.90275 2.61078 + vertex 0.937636 1.90663 2.60998 + vertex 0.933235 1.90142 2.60929 + endloop + endfacet + facet normal -0.470135 0.287841 0.834338 + outer loop + vertex 0.933235 1.90142 2.60929 + vertex 0.937636 1.90663 2.60998 + vertex 0.933102 1.90658 2.60744 + endloop + endfacet + facet normal -0.303024 0.204433 0.930797 + outer loop + vertex 0.939297 1.90504 2.61117 + vertex 0.936574 1.90275 2.61078 + vertex 0.938529 1.90131 2.61174 + endloop + endfacet + facet normal -0.472161 0.272901 0.838206 + outer loop + vertex 0.937636 1.90663 2.60998 + vertex 0.938061 1.91147 2.60864 + vertex 0.933102 1.90658 2.60744 + endloop + endfacet + facet normal -0.455046 0.251591 0.854187 + outer loop + vertex 0.933102 1.90658 2.60744 + vertex 0.938061 1.91147 2.60864 + vertex 0.93408 1.91177 2.60643 + endloop + endfacet + facet normal -0.532713 0.214763 0.818593 + outer loop + vertex 0.935869 1.91917 2.60557 + vertex 0.933492 1.91831 2.60424 + vertex 0.9338 1.91579 2.60511 + endloop + endfacet + facet normal -0.468251 0.168782 0.867326 + outer loop + vertex 0.9338 1.91579 2.60511 + vertex 0.938173 1.91665 2.6073 + vertex 0.935869 1.91917 2.60557 + endloop + endfacet + facet normal -0.47284 0.246123 0.846077 + outer loop + vertex 0.9338 1.91579 2.60511 + vertex 0.93408 1.91177 2.60643 + vertex 0.938173 1.91665 2.6073 + endloop + endfacet + facet normal -0.458552 0.232048 0.857837 + outer loop + vertex 0.93408 1.91177 2.60643 + vertex 0.938061 1.91147 2.60864 + vertex 0.938173 1.91665 2.6073 + endloop + endfacet + facet normal -0.535967 0.235878 0.810618 + outer loop + vertex 0.93408 1.92165 2.60366 + vertex 0.933492 1.91831 2.60424 + vertex 0.935869 1.91917 2.60557 + endloop + endfacet + facet normal -0.549411 0.222216 0.805461 + outer loop + vertex 0.937004 1.92243 2.60544 + vertex 0.93408 1.92165 2.60366 + vertex 0.935869 1.91917 2.60557 + endloop + endfacet + facet normal -0.434485 0.185077 0.881458 + outer loop + vertex 0.935869 1.91917 2.60557 + vertex 0.939372 1.9217 2.60676 + vertex 0.937004 1.92243 2.60544 + endloop + endfacet + facet normal -0.441743 0.198221 0.87497 + outer loop + vertex 0.938173 1.91665 2.6073 + vertex 0.939372 1.9217 2.60676 + vertex 0.935869 1.91917 2.60557 + endloop + endfacet + facet normal -0.482125 0.259368 0.836829 + outer loop + vertex 0.937004 1.92243 2.60544 + vertex 0.939282 1.92484 2.60601 + vertex 0.937088 1.92568 2.60448 + endloop + endfacet + facet normal -0.551059 0.249227 0.796379 + outer loop + vertex 0.937004 1.92243 2.60544 + vertex 0.937088 1.92568 2.60448 + vertex 0.93408 1.92165 2.60366 + endloop + endfacet + facet normal -0.560575 0.258277 0.786796 + outer loop + vertex 0.93408 1.92165 2.60366 + vertex 0.937088 1.92568 2.60448 + vertex 0.934327 1.92637 2.60229 + endloop + endfacet + facet normal -0.429658 0.199361 0.88071 + outer loop + vertex 0.939282 1.92484 2.60601 + vertex 0.937004 1.92243 2.60544 + vertex 0.939372 1.9217 2.60676 + endloop + endfacet + facet normal -0.552575 0.259043 0.792185 + outer loop + vertex 0.935569 1.93354 2.60076 + vertex 0.932012 1.93074 2.5992 + vertex 0.93433 1.92976 2.60114 + endloop + endfacet + facet normal -0.539472 0.255735 0.802228 + outer loop + vertex 0.93433 1.92976 2.60114 + vertex 0.938199 1.93105 2.60333 + vertex 0.935569 1.93354 2.60076 + endloop + endfacet + facet normal -0.541069 0.270852 0.796168 + outer loop + vertex 0.93433 1.92976 2.60114 + vertex 0.934327 1.92637 2.60229 + vertex 0.938199 1.93105 2.60333 + endloop + endfacet + facet normal -0.552365 0.282861 0.784145 + outer loop + vertex 0.934327 1.92637 2.60229 + vertex 0.937088 1.92568 2.60448 + vertex 0.938199 1.93105 2.60333 + endloop + endfacet + facet normal -0.55398 0.261909 0.790259 + outer loop + vertex 0.933145 1.93609 2.59822 + vertex 0.932012 1.93074 2.5992 + vertex 0.935569 1.93354 2.60076 + endloop + endfacet + facet normal -0.558394 0.256411 0.788955 + outer loop + vertex 0.936799 1.93729 2.60042 + vertex 0.933145 1.93609 2.59822 + vertex 0.935569 1.93354 2.60076 + endloop + endfacet + facet normal -0.52082 0.246697 0.817244 + outer loop + vertex 0.935569 1.93354 2.60076 + vertex 0.939304 1.93657 2.60223 + vertex 0.936799 1.93729 2.60042 + endloop + endfacet + facet normal -0.531493 0.266153 0.804163 + outer loop + vertex 0.938199 1.93105 2.60333 + vertex 0.939304 1.93657 2.60223 + vertex 0.935569 1.93354 2.60076 + endloop + endfacet + facet normal -0.540003 0.268951 0.797535 + outer loop + vertex 0.936799 1.93729 2.60042 + vertex 0.93929 1.93991 2.60122 + vertex 0.936997 1.94069 2.59941 + endloop + endfacet + facet normal -0.55929 0.266344 0.78502 + outer loop + vertex 0.936799 1.93729 2.60042 + vertex 0.936997 1.94069 2.59941 + vertex 0.933145 1.93609 2.59822 + endloop + endfacet + facet normal -0.563618 0.271203 0.780246 + outer loop + vertex 0.933145 1.93609 2.59822 + vertex 0.936997 1.94069 2.59941 + vertex 0.934282 1.94141 2.59719 + endloop + endfacet + facet normal -0.521368 0.245104 0.817373 + outer loop + vertex 0.93929 1.93991 2.60122 + vertex 0.936799 1.93729 2.60042 + vertex 0.939304 1.93657 2.60223 + endloop + endfacet + facet normal -0.490905 0.232166 0.839709 + outer loop + vertex 0.935695 1.94854 2.59589 + vertex 0.932011 1.94566 2.59453 + vertex 0.934475 1.9448 2.59621 + endloop + endfacet + facet normal -0.559413 0.250282 0.7902 + outer loop + vertex 0.934475 1.9448 2.59621 + vertex 0.9381 1.94607 2.59837 + vertex 0.935695 1.94854 2.59589 + endloop + endfacet + facet normal -0.560559 0.26072 0.786001 + outer loop + vertex 0.934475 1.9448 2.59621 + vertex 0.934282 1.94141 2.59719 + vertex 0.9381 1.94607 2.59837 + endloop + endfacet + facet normal -0.565399 0.26601 0.780744 + outer loop + vertex 0.934282 1.94141 2.59719 + vertex 0.936997 1.94069 2.59941 + vertex 0.9381 1.94607 2.59837 + endloop + endfacet + facet normal -0.49884 0.246501 0.830901 + outer loop + vertex 0.933271 1.95089 2.59373 + vertex 0.932011 1.94566 2.59453 + vertex 0.935695 1.94854 2.59589 + endloop + endfacet + facet normal -0.498087 0.247436 0.831074 + outer loop + vertex 0.936901 1.95228 2.5955 + vertex 0.933271 1.95089 2.59373 + vertex 0.935695 1.94854 2.59589 + endloop + endfacet + facet normal -0.546598 0.259444 0.796191 + outer loop + vertex 0.935695 1.94854 2.59589 + vertex 0.939184 1.95143 2.59734 + vertex 0.936901 1.95228 2.5955 + endloop + endfacet + facet normal -0.548849 0.263637 0.793259 + outer loop + vertex 0.9381 1.94607 2.59837 + vertex 0.939184 1.95143 2.59734 + vertex 0.935695 1.94854 2.59589 + endloop + endfacet + facet normal -0.536342 0.254685 0.804657 + outer loop + vertex 0.936901 1.95228 2.5955 + vertex 0.939331 1.9548 2.59632 + vertex 0.936902 1.95559 2.59445 + endloop + endfacet + facet normal -0.500574 0.26122 0.825342 + outer loop + vertex 0.936901 1.95228 2.5955 + vertex 0.936902 1.95559 2.59445 + vertex 0.933271 1.95089 2.59373 + endloop + endfacet + facet normal -0.501174 0.261766 0.824805 + outer loop + vertex 0.933271 1.95089 2.59373 + vertex 0.936902 1.95559 2.59445 + vertex 0.933361 1.95593 2.59219 + endloop + endfacet + facet normal -0.544259 0.265133 0.795919 + outer loop + vertex 0.939331 1.9548 2.59632 + vertex 0.936901 1.95228 2.5955 + vertex 0.939184 1.95143 2.59734 + endloop + endfacet + facet normal -0.447539 0.261433 0.855197 + outer loop + vertex 0.935565 1.96356 2.59092 + vertex 0.931745 1.96087 2.58975 + vertex 0.934069 1.9598 2.59129 + endloop + endfacet + facet normal -0.514968 0.283786 0.808872 + outer loop + vertex 0.934069 1.9598 2.59129 + vertex 0.937911 1.96096 2.59333 + vertex 0.935565 1.96356 2.59092 + endloop + endfacet + facet normal -0.51483 0.282207 0.809512 + outer loop + vertex 0.934069 1.9598 2.59129 + vertex 0.933361 1.95593 2.59219 + vertex 0.937911 1.96096 2.59333 + endloop + endfacet + facet normal -0.500305 0.265781 0.824048 + outer loop + vertex 0.933361 1.95593 2.59219 + vertex 0.936902 1.95559 2.59445 + vertex 0.937911 1.96096 2.59333 + endloop + endfacet + facet normal -0.45041 0.266908 0.851992 + outer loop + vertex 0.933196 1.96602 2.5889 + vertex 0.931745 1.96087 2.58975 + vertex 0.935565 1.96356 2.59092 + endloop + endfacet + facet normal -0.448336 0.269207 0.852363 + outer loop + vertex 0.936931 1.96725 2.59048 + vertex 0.933196 1.96602 2.5889 + vertex 0.935565 1.96356 2.59092 + endloop + endfacet + facet normal -0.518689 0.289442 0.804478 + outer loop + vertex 0.935565 1.96356 2.59092 + vertex 0.93917 1.96636 2.59224 + vertex 0.936931 1.96725 2.59048 + endloop + endfacet + facet normal -0.515445 0.283248 0.808756 + outer loop + vertex 0.937911 1.96096 2.59333 + vertex 0.93917 1.96636 2.59224 + vertex 0.935565 1.96356 2.59092 + endloop + endfacet + facet normal -0.500418 0.256578 0.826891 + outer loop + vertex 0.936931 1.96725 2.59048 + vertex 0.939422 1.96971 2.59122 + vertex 0.937021 1.97056 2.5895 + endloop + endfacet + facet normal -0.447381 0.263301 0.854706 + outer loop + vertex 0.936931 1.96725 2.59048 + vertex 0.937021 1.97056 2.5895 + vertex 0.933196 1.96602 2.5889 + endloop + endfacet + facet normal -0.442259 0.258437 0.858846 + outer loop + vertex 0.933196 1.96602 2.5889 + vertex 0.937021 1.97056 2.5895 + vertex 0.933324 1.97134 2.58737 + endloop + endfacet + facet normal -0.521069 0.284159 0.804823 + outer loop + vertex 0.939422 1.96971 2.59122 + vertex 0.936931 1.96725 2.59048 + vertex 0.93917 1.96636 2.59224 + endloop + endfacet + facet normal -0.443255 0.255049 0.859346 + outer loop + vertex 0.937021 1.97056 2.5895 + vertex 0.938312 1.97566 2.58865 + vertex 0.933324 1.97134 2.58737 + endloop + endfacet + facet normal -0.45578 0.27311 0.847157 + outer loop + vertex 0.933324 1.97134 2.58737 + vertex 0.938312 1.97566 2.58865 + vertex 0.934722 1.9764 2.58648 + endloop + endfacet + facet normal -0.415771 0.271861 0.867886 + outer loop + vertex 0.936521 1.98234 2.58545 + vertex 0.933032 1.98127 2.58412 + vertex 0.93502 1.97962 2.58559 + endloop + endfacet + facet normal -0.456211 0.292802 0.840321 + outer loop + vertex 0.93502 1.97962 2.58559 + vertex 0.938429 1.98068 2.58707 + vertex 0.936521 1.98234 2.58545 + endloop + endfacet + facet normal -0.454263 0.278004 0.84638 + outer loop + vertex 0.93502 1.97962 2.58559 + vertex 0.934722 1.9764 2.58648 + vertex 0.938429 1.98068 2.58707 + endloop + endfacet + facet normal -0.454285 0.278026 0.846361 + outer loop + vertex 0.934722 1.9764 2.58648 + vertex 0.938312 1.97566 2.58865 + vertex 0.938429 1.98068 2.58707 + endloop + endfacet + facet normal -0.453027 0.272389 0.848865 + outer loop + vertex 0.936521 1.98234 2.58545 + vertex 0.939175 1.98458 2.58615 + vertex 0.936876 1.98563 2.58459 + endloop + endfacet + facet normal -0.415991 0.273243 0.867347 + outer loop + vertex 0.936521 1.98234 2.58545 + vertex 0.936876 1.98563 2.58459 + vertex 0.933032 1.98127 2.58412 + endloop + endfacet + facet normal -0.414682 0.271978 0.86837 + outer loop + vertex 0.933032 1.98127 2.58412 + vertex 0.936876 1.98563 2.58459 + vertex 0.933196 1.98626 2.58263 + endloop + endfacet + facet normal -0.461843 0.285733 0.839678 + outer loop + vertex 0.939175 1.98458 2.58615 + vertex 0.936521 1.98234 2.58545 + vertex 0.938429 1.98068 2.58707 + endloop + endfacet + facet normal -0.41561 0.268538 0.868997 + outer loop + vertex 0.936876 1.98563 2.58459 + vertex 0.938482 1.99091 2.58372 + vertex 0.933196 1.98626 2.58263 + endloop + endfacet + facet normal -0.421231 0.276136 0.863894 + outer loop + vertex 0.933196 1.98626 2.58263 + vertex 0.938482 1.99091 2.58372 + vertex 0.934706 1.9914 2.58173 + endloop + endfacet + facet normal -0.43502 0.29328 0.851319 + outer loop + vertex 0.936521 1.99739 2.58066 + vertex 0.93297 1.99611 2.57929 + vertex 0.935007 1.9946 2.58085 + endloop + endfacet + facet normal -0.422793 0.287171 0.859523 + outer loop + vertex 0.935007 1.9946 2.58085 + vertex 0.938545 1.99597 2.58213 + vertex 0.936521 1.99739 2.58066 + endloop + endfacet + facet normal -0.420424 0.276689 0.86411 + outer loop + vertex 0.935007 1.9946 2.58085 + vertex 0.934706 1.9914 2.58173 + vertex 0.938545 1.99597 2.58213 + endloop + endfacet + facet normal -0.420978 0.277194 0.863679 + outer loop + vertex 0.934706 1.9914 2.58173 + vertex 0.938482 1.99091 2.58372 + vertex 0.938545 1.99597 2.58213 + endloop + endfacet + facet normal -0.428144 0.291127 0.855534 + outer loop + vertex 0.936521 1.99739 2.58066 + vertex 0.939163 1.99976 2.58118 + vertex 0.936835 2.00055 2.57974 + endloop + endfacet + facet normal -0.434557 0.290849 0.852389 + outer loop + vertex 0.936521 1.99739 2.58066 + vertex 0.936835 2.00055 2.57974 + vertex 0.93297 1.99611 2.57929 + endloop + endfacet + facet normal -0.443749 0.299638 0.844573 + outer loop + vertex 0.93297 1.99611 2.57929 + vertex 0.936835 2.00055 2.57974 + vertex 0.932999 2.00113 2.57752 + endloop + endfacet + facet normal -0.423914 0.285557 0.859508 + outer loop + vertex 0.939163 1.99976 2.58118 + vertex 0.936521 1.99739 2.58066 + vertex 0.938545 1.99597 2.58213 + endloop + endfacet + facet normal -0.444254 0.29778 0.844964 + outer loop + vertex 0.936835 2.00055 2.57974 + vertex 0.93841 2.0057 2.57875 + vertex 0.932999 2.00113 2.57752 + endloop + endfacet + facet normal -0.445101 0.29902 0.84408 + outer loop + vertex 0.932999 2.00113 2.57752 + vertex 0.93841 2.0057 2.57875 + vertex 0.934282 2.00629 2.57637 + endloop + endfacet + facet normal -0.502106 0.298629 0.811609 + outer loop + vertex 0.936859 2.01292 2.5755 + vertex 0.934782 2.01351 2.57399 + vertex 0.934353 2.01033 2.5749 + endloop + endfacet + facet normal -0.47091 0.261222 0.842619 + outer loop + vertex 0.934353 2.01033 2.5749 + vertex 0.938413 2.01079 2.57703 + vertex 0.936859 2.01292 2.5755 + endloop + endfacet + facet normal -0.468414 0.309564 0.827501 + outer loop + vertex 0.934353 2.01033 2.5749 + vertex 0.934282 2.00629 2.57637 + vertex 0.938413 2.01079 2.57703 + endloop + endfacet + facet normal -0.447998 0.288021 0.84637 + outer loop + vertex 0.934282 2.00629 2.57637 + vertex 0.93841 2.0057 2.57875 + vertex 0.938413 2.01079 2.57703 + endloop + endfacet + facet normal -0.4552 0.309473 0.834877 + outer loop + vertex 0.936859 2.01292 2.5755 + vertex 0.939356 2.01455 2.57625 + vertex 0.937844 2.01654 2.57469 + endloop + endfacet + facet normal -0.495822 0.314828 0.809348 + outer loop + vertex 0.936859 2.01292 2.5755 + vertex 0.937844 2.01654 2.57469 + vertex 0.934782 2.01351 2.57399 + endloop + endfacet + facet normal -0.509372 0.332054 0.793902 + outer loop + vertex 0.934782 2.01351 2.57399 + vertex 0.937844 2.01654 2.57469 + vertex 0.934276 2.01667 2.57235 + endloop + endfacet + facet normal -0.443969 0.285671 0.849284 + outer loop + vertex 0.939356 2.01455 2.57625 + vertex 0.936859 2.01292 2.5755 + vertex 0.938413 2.01079 2.57703 + endloop + endfacet + facet normal -0.584812 0.316274 0.746971 + outer loop + vertex 0.935349 2.02364 2.57029 + vertex 0.933188 2.02256 2.56906 + vertex 0.933661 2.02035 2.57036 + endloop + endfacet + facet normal -0.53478 0.291638 0.793068 + outer loop + vertex 0.933661 2.02035 2.57036 + vertex 0.937736 2.02127 2.57278 + vertex 0.935349 2.02364 2.57029 + endloop + endfacet + facet normal -0.534527 0.330211 0.777972 + outer loop + vertex 0.933661 2.02035 2.57036 + vertex 0.934276 2.01667 2.57235 + vertex 0.937736 2.02127 2.57278 + endloop + endfacet + facet normal -0.513533 0.312423 0.799172 + outer loop + vertex 0.934276 2.01667 2.57235 + vertex 0.937844 2.01654 2.57469 + vertex 0.937736 2.02127 2.57278 + endloop + endfacet + facet normal -0.593111 0.368903 0.715633 + outer loop + vertex 0.93319 2.02509 2.56776 + vertex 0.933188 2.02256 2.56906 + vertex 0.935349 2.02364 2.57029 + endloop + endfacet + facet normal -0.612625 0.337883 0.714511 + outer loop + vertex 0.935917 2.02758 2.56892 + vertex 0.93319 2.02509 2.56776 + vertex 0.935349 2.02364 2.57029 + endloop + endfacet + facet normal -0.529204 0.346769 0.774399 + outer loop + vertex 0.935349 2.02364 2.57029 + vertex 0.939003 2.02639 2.57156 + vertex 0.935917 2.02758 2.56892 + endloop + endfacet + facet normal -0.514243 0.3165 0.797109 + outer loop + vertex 0.937736 2.02127 2.57278 + vertex 0.939003 2.02639 2.57156 + vertex 0.935349 2.02364 2.57029 + endloop + endfacet + facet normal -0.662456 0.359231 0.657347 + outer loop + vertex 0.936208 2.0324 2.56679 + vertex 0.933474 2.03195 2.56429 + vertex 0.933364 2.02915 2.5657 + endloop + endfacet + facet normal -0.629696 0.371654 0.682171 + outer loop + vertex 0.933364 2.02915 2.5657 + vertex 0.93319 2.02509 2.56776 + vertex 0.935917 2.02758 2.56892 + endloop + endfacet + facet normal -0.648694 0.339113 0.681321 + outer loop + vertex 0.936208 2.0324 2.56679 + vertex 0.933364 2.02915 2.5657 + vertex 0.935917 2.02758 2.56892 + endloop + endfacet + facet normal -0.572572 0.359056 0.737049 + outer loop + vertex 0.936208 2.0324 2.56679 + vertex 0.935917 2.02758 2.56892 + vertex 0.939174 2.03039 2.57008 + endloop + endfacet + facet normal -0.597288 0.319955 0.735443 + outer loop + vertex 0.936208 2.0324 2.56679 + vertex 0.939174 2.03039 2.57008 + vertex 0.939731 2.0336 2.56914 + endloop + endfacet + facet normal -0.54587 0.311227 0.777923 + outer loop + vertex 0.939174 2.03039 2.57008 + vertex 0.935917 2.02758 2.56892 + vertex 0.939003 2.02639 2.57156 + endloop + endfacet + facet normal -0.660299 0.371235 0.652833 + outer loop + vertex 0.933761 2.03476 2.56298 + vertex 0.933474 2.03195 2.56429 + vertex 0.936208 2.0324 2.56679 + endloop + endfacet + facet normal -0.68416 0.33684 0.646888 + outer loop + vertex 0.936245 2.03726 2.5643 + vertex 0.933761 2.03476 2.56298 + vertex 0.936208 2.0324 2.56679 + endloop + endfacet + facet normal -0.619972 0.361673 0.696296 + outer loop + vertex 0.936208 2.0324 2.56679 + vertex 0.93934 2.03671 2.56734 + vertex 0.936245 2.03726 2.5643 + endloop + endfacet + facet normal -0.597829 0.341903 0.725054 + outer loop + vertex 0.939731 2.0336 2.56914 + vertex 0.93934 2.03671 2.56734 + vertex 0.936208 2.0324 2.56679 + endloop + endfacet + facet normal -0.733205 0.375433 0.566974 + outer loop + vertex 0.936006 2.04237 2.56105 + vertex 0.933261 2.04073 2.55859 + vertex 0.934184 2.03838 2.56135 + endloop + endfacet + facet normal -0.695385 0.361701 0.620977 + outer loop + vertex 0.934184 2.03838 2.56135 + vertex 0.933761 2.03476 2.56298 + vertex 0.936245 2.03726 2.5643 + endloop + endfacet + facet normal -0.695204 0.362044 0.62098 + outer loop + vertex 0.936006 2.04237 2.56105 + vertex 0.934184 2.03838 2.56135 + vertex 0.936245 2.03726 2.5643 + endloop + endfacet + facet normal -0.665971 0.377621 0.643339 + outer loop + vertex 0.936006 2.04237 2.56105 + vertex 0.936245 2.03726 2.5643 + vertex 0.938808 2.04034 2.56515 + endloop + endfacet + facet normal -0.728366 0.266888 0.631073 + outer loop + vertex 0.936006 2.04237 2.56105 + vertex 0.938808 2.04034 2.56515 + vertex 0.938432 2.04249 2.5638 + endloop + endfacet + facet normal -0.630445 0.332108 0.7016 + outer loop + vertex 0.938808 2.04034 2.56515 + vertex 0.936245 2.03726 2.5643 + vertex 0.93934 2.03671 2.56734 + endloop + endfacet + facet normal -0.757858 0.359001 0.544766 + outer loop + vertex 0.934809 2.04707 2.55653 + vertex 0.933151 2.04721 2.55413 + vertex 0.933201 2.04436 2.55608 + endloop + endfacet + facet normal -0.733202 0.378873 0.564686 + outer loop + vertex 0.933201 2.04436 2.55608 + vertex 0.933261 2.04073 2.55859 + vertex 0.936006 2.04237 2.56105 + endloop + endfacet + facet normal -0.74889 0.350723 0.562278 + outer loop + vertex 0.933201 2.04436 2.55608 + vertex 0.936006 2.04237 2.56105 + vertex 0.934809 2.04707 2.55653 + endloop + endfacet + facet normal -0.751488 0.348219 0.560366 + outer loop + vertex 0.934809 2.04707 2.55653 + vertex 0.936006 2.04237 2.56105 + vertex 0.937101 2.04726 2.55948 + endloop + endfacet + facet normal -0.713458 0.353949 0.60473 + outer loop + vertex 0.936006 2.04237 2.56105 + vertex 0.938686 2.0449 2.56274 + vertex 0.937101 2.04726 2.55948 + endloop + endfacet + facet normal -0.710884 0.346296 0.612146 + outer loop + vertex 0.938432 2.04249 2.5638 + vertex 0.938686 2.0449 2.56274 + vertex 0.936006 2.04237 2.56105 + endloop + endfacet + facet normal -0.758405 0.357418 0.545046 + outer loop + vertex 0.933533 2.04991 2.5529 + vertex 0.933151 2.04721 2.55413 + vertex 0.934809 2.04707 2.55653 + endloop + endfacet + facet normal -0.756988 0.359132 0.545887 + outer loop + vertex 0.935955 2.05139 2.55528 + vertex 0.933533 2.04991 2.5529 + vertex 0.934809 2.04707 2.55653 + endloop + endfacet + facet normal -0.708708 0.369133 0.601227 + outer loop + vertex 0.93828 2.05055 2.55885 + vertex 0.937101 2.04726 2.55948 + vertex 0.939241 2.04824 2.56141 + endloop + endfacet + facet normal -0.736038 0.372072 0.565518 + outer loop + vertex 0.93828 2.05055 2.55885 + vertex 0.935955 2.05139 2.55528 + vertex 0.937101 2.04726 2.55948 + endloop + endfacet + facet normal -0.74831 0.360087 0.557108 + outer loop + vertex 0.935955 2.05139 2.55528 + vertex 0.934809 2.04707 2.55653 + vertex 0.937101 2.04726 2.55948 + endloop + endfacet + facet normal -0.709112 0.359441 0.606598 + outer loop + vertex 0.939241 2.04824 2.56141 + vertex 0.937101 2.04726 2.55948 + vertex 0.938686 2.0449 2.56274 + endloop + endfacet + facet normal -0.751244 0.361266 0.552376 + outer loop + vertex 0.935847 2.05738 2.55116 + vertex 0.933205 2.05598 2.54848 + vertex 0.934126 2.05351 2.55135 + endloop + endfacet + facet normal -0.756999 0.358441 0.546327 + outer loop + vertex 0.934126 2.05351 2.55135 + vertex 0.933533 2.04991 2.5529 + vertex 0.935955 2.05139 2.55528 + endloop + endfacet + facet normal -0.754415 0.362422 0.547273 + outer loop + vertex 0.935847 2.05738 2.55116 + vertex 0.934126 2.05351 2.55135 + vertex 0.935955 2.05139 2.55528 + endloop + endfacet + facet normal -0.743488 0.369553 0.557366 + outer loop + vertex 0.935847 2.05738 2.55116 + vertex 0.935955 2.05139 2.55528 + vertex 0.938137 2.0542 2.55632 + endloop + endfacet + facet normal -0.763389 0.340984 0.548605 + outer loop + vertex 0.935847 2.05738 2.55116 + vertex 0.938137 2.0542 2.55632 + vertex 0.938004 2.05703 2.55438 + endloop + endfacet + facet normal -0.73989 0.363544 0.566037 + outer loop + vertex 0.938137 2.0542 2.55632 + vertex 0.935955 2.05139 2.55528 + vertex 0.93828 2.05055 2.55885 + endloop + endfacet + facet normal -0.745798 0.373085 0.551899 + outer loop + vertex 0.934723 2.06226 2.54633 + vertex 0.93304 2.06236 2.54399 + vertex 0.933096 2.05955 2.54596 + endloop + endfacet + facet normal -0.751005 0.365291 0.550049 + outer loop + vertex 0.933096 2.05955 2.54596 + vertex 0.933205 2.05598 2.54848 + vertex 0.935847 2.05738 2.55116 + endloop + endfacet + facet normal -0.746274 0.373496 0.550977 + outer loop + vertex 0.933096 2.05955 2.54596 + vertex 0.935847 2.05738 2.55116 + vertex 0.934723 2.06226 2.54633 + endloop + endfacet + facet normal -0.744402 0.37525 0.552316 + outer loop + vertex 0.934723 2.06226 2.54633 + vertex 0.935847 2.05738 2.55116 + vertex 0.937053 2.06254 2.54928 + endloop + endfacet + facet normal -0.751614 0.373729 0.54351 + outer loop + vertex 0.935847 2.05738 2.55116 + vertex 0.938421 2.05973 2.55311 + vertex 0.937053 2.06254 2.54928 + endloop + endfacet + facet normal -0.751484 0.373053 0.544154 + outer loop + vertex 0.938004 2.05703 2.55438 + vertex 0.938421 2.05973 2.55311 + vertex 0.935847 2.05738 2.55116 + endloop + endfacet + facet normal -0.743954 0.378386 0.550778 + outer loop + vertex 0.933495 2.06498 2.54281 + vertex 0.93304 2.06236 2.54399 + vertex 0.934723 2.06226 2.54633 + endloop + endfacet + facet normal -0.743704 0.378677 0.550915 + outer loop + vertex 0.935926 2.06648 2.54505 + vertex 0.933495 2.06498 2.54281 + vertex 0.934723 2.06226 2.54633 + endloop + endfacet + facet normal -0.742154 0.385356 0.548368 + outer loop + vertex 0.938232 2.06584 2.54856 + vertex 0.937053 2.06254 2.54928 + vertex 0.939107 2.06333 2.55151 + endloop + endfacet + facet normal -0.737002 0.385073 0.55547 + outer loop + vertex 0.938232 2.06584 2.54856 + vertex 0.935926 2.06648 2.54505 + vertex 0.937053 2.06254 2.54928 + endloop + endfacet + facet normal -0.743447 0.378703 0.551245 + outer loop + vertex 0.935926 2.06648 2.54505 + vertex 0.934723 2.06226 2.54633 + vertex 0.937053 2.06254 2.54928 + endloop + endfacet + facet normal -0.742193 0.385103 0.548494 + outer loop + vertex 0.939107 2.06333 2.55151 + vertex 0.937053 2.06254 2.54928 + vertex 0.938421 2.05973 2.55311 + endloop + endfacet + facet normal -0.751465 0.394955 0.528499 + outer loop + vertex 0.935835 2.07165 2.54132 + vertex 0.933679 2.07064 2.53901 + vertex 0.934188 2.06834 2.54145 + endloop + endfacet + facet normal -0.743718 0.376395 0.552459 + outer loop + vertex 0.934188 2.06834 2.54145 + vertex 0.933495 2.06498 2.54281 + vertex 0.935926 2.06648 2.54505 + endloop + endfacet + facet normal -0.735865 0.388242 0.554771 + outer loop + vertex 0.935835 2.07165 2.54132 + vertex 0.934188 2.06834 2.54145 + vertex 0.935926 2.06648 2.54505 + endloop + endfacet + facet normal -0.736913 0.387561 0.553855 + outer loop + vertex 0.935835 2.07165 2.54132 + vertex 0.935926 2.06648 2.54505 + vertex 0.938061 2.06945 2.54582 + endloop + endfacet + facet normal -0.741044 0.381175 0.552774 + outer loop + vertex 0.935835 2.07165 2.54132 + vertex 0.938061 2.06945 2.54582 + vertex 0.937775 2.07227 2.54349 + endloop + endfacet + facet normal -0.73627 0.386725 0.555292 + outer loop + vertex 0.938061 2.06945 2.54582 + vertex 0.935926 2.06648 2.54505 + vertex 0.938232 2.06584 2.54856 + endloop + endfacet + facet normal -0.788536 0.428234 0.441392 + outer loop + vertex 0.935912 2.07744 2.53675 + vertex 0.933771 2.07557 2.53474 + vertex 0.934163 2.07343 2.53751 + endloop + endfacet + facet normal -0.749555 0.408716 0.52069 + outer loop + vertex 0.934163 2.07343 2.53751 + vertex 0.933679 2.07064 2.53901 + vertex 0.935835 2.07165 2.54132 + endloop + endfacet + facet normal -0.74009 0.422691 0.523067 + outer loop + vertex 0.935912 2.07744 2.53675 + vertex 0.934163 2.07343 2.53751 + vertex 0.935835 2.07165 2.54132 + endloop + endfacet + facet normal -0.761853 0.407529 0.503488 + outer loop + vertex 0.935912 2.07744 2.53675 + vertex 0.935835 2.07165 2.54132 + vertex 0.93761 2.07487 2.54139 + endloop + endfacet + facet normal -0.795648 0.358118 0.488565 + outer loop + vertex 0.935912 2.07744 2.53675 + vertex 0.93761 2.07487 2.54139 + vertex 0.937636 2.07743 2.53956 + endloop + endfacet + facet normal -0.738698 0.393732 0.547083 + outer loop + vertex 0.93761 2.07487 2.54139 + vertex 0.935835 2.07165 2.54132 + vertex 0.937775 2.07227 2.54349 + endloop + endfacet + facet normal -0.607292 0.329333 0.723005 + outer loop + vertex 0.935909 2.08313 2.53138 + vertex 0.935282 2.085 2.53 + vertex 0.935 2.08448 2.53 + endloop + endfacet + facet normal -0.532313 0.402338 0.744827 + outer loop + vertex 0.934395 2.07907 2.53249 + vertex 0.935909 2.08313 2.53138 + vertex 0.935 2.08448 2.53 + endloop + endfacet + facet normal -0.788571 0.425223 0.444232 + outer loop + vertex 0.934395 2.07907 2.53249 + vertex 0.933771 2.07557 2.53474 + vertex 0.935912 2.07744 2.53675 + endloop + endfacet + facet normal -0.793587 0.417174 0.442927 + outer loop + vertex 0.934395 2.07907 2.53249 + vertex 0.935912 2.07744 2.53675 + vertex 0.935909 2.08313 2.53138 + endloop + endfacet + facet normal -0.793412 0.417331 0.443094 + outer loop + vertex 0.935909 2.08313 2.53138 + vertex 0.935912 2.07744 2.53675 + vertex 0.937396 2.08272 2.53443 + endloop + endfacet + facet normal -0.776583 0.423039 0.466858 + outer loop + vertex 0.935912 2.07744 2.53675 + vertex 0.93821 2.08001 2.53824 + vertex 0.937396 2.08272 2.53443 + endloop + endfacet + facet normal -0.774793 0.416176 0.475913 + outer loop + vertex 0.937636 2.07743 2.53956 + vertex 0.93821 2.08001 2.53824 + vertex 0.935912 2.07744 2.53675 + endloop + endfacet + facet normal -0.573277 0.352916 0.739462 + outer loop + vertex 0.935282 2.085 2.53 + vertex 0.935909 2.08313 2.53138 + vertex 0.93836 2.09 2.53 + endloop + endfacet + facet normal -0.358839 0.304985 0.882167 + outer loop + vertex 0.93836 2.09 2.53 + vertex 0.935909 2.08313 2.53138 + vertex 0.937764 2.08733 2.53068 + endloop + endfacet + facet normal -0.779359 0.420041 0.464936 + outer loop + vertex 0.938761 2.08588 2.53386 + vertex 0.937396 2.08272 2.53443 + vertex 0.939101 2.08352 2.53656 + endloop + endfacet + facet normal -0.792793 0.421423 0.44032 + outer loop + vertex 0.938761 2.08588 2.53386 + vertex 0.937764 2.08733 2.53068 + vertex 0.937396 2.08272 2.53443 + endloop + endfacet + facet normal -0.790684 0.423059 0.442538 + outer loop + vertex 0.937764 2.08733 2.53068 + vertex 0.935909 2.08313 2.53138 + vertex 0.937396 2.08272 2.53443 + endloop + endfacet + facet normal -0.779425 0.419728 0.465107 + outer loop + vertex 0.939101 2.08352 2.53656 + vertex 0.937396 2.08272 2.53443 + vertex 0.93821 2.08001 2.53824 + endloop + endfacet + facet normal -0.940274 0.266845 0.211372 + outer loop + vertex 0.937236 2.09 2.525 + vertex 0.93836 2.09 2.53 + vertex 0.938655 2.095 2.525 + endloop + endfacet + facet normal 0.54039 -0.610686 -0.578827 + outer loop + vertex 0.938655 2.095 2.525 + vertex 0.93836 2.09 2.53 + vertex 0.937946 2.09281 2.52665 + endloop + endfacet + facet normal -0.818712 0.33045 0.46959 + outer loop + vertex 0.938692 2.09113 2.52962 + vertex 0.937764 2.08733 2.53068 + vertex 0.939183 2.08872 2.53218 + endloop + endfacet + facet normal -0.860409 0.320245 0.396409 + outer loop + vertex 0.938692 2.09113 2.52962 + vertex 0.937946 2.09281 2.52665 + vertex 0.937764 2.08733 2.53068 + endloop + endfacet + facet normal 0.890591 -0.28836 -0.351705 + outer loop + vertex 0.937946 2.09281 2.52665 + vertex 0.93836 2.09 2.53 + vertex 0.937764 2.08733 2.53068 + endloop + endfacet + facet normal -0.82108 0.37672 0.428847 + outer loop + vertex 0.939183 2.08872 2.53218 + vertex 0.937764 2.08733 2.53068 + vertex 0.938761 2.08588 2.53386 + endloop + endfacet + facet normal 0.71766 -0.492425 -0.492425 + outer loop + vertex 0.94 2.09973 2.52 + vertex 0.93852 2.09738 2.5202 + vertex 0.94 2.1 2.51973 + endloop + endfacet + facet normal 0.655516 -0.462147 -0.59726 + outer loop + vertex 0.94 2.095 2.52366 + vertex 0.93852 2.09738 2.5202 + vertex 0.94 2.09973 2.52 + endloop + endfacet + facet normal -0.396522 -0.827288 -0.397951 + outer loop + vertex 0.94 2.095 2.52366 + vertex 0.938655 2.095 2.525 + vertex 0.93852 2.09738 2.5202 + endloop + endfacet + facet normal -0.529694 -0.766134 -0.363954 + outer loop + vertex 0.938655 2.095 2.525 + vertex 0.937445 2.09719 2.52216 + vertex 0.93852 2.09738 2.5202 + endloop + endfacet + facet normal 0.411222 -0.629434 -0.659325 + outer loop + vertex 0.938655 2.095 2.525 + vertex 0.937946 2.09281 2.52665 + vertex 0.937445 2.09719 2.52216 + endloop + endfacet + facet normal -0.992016 -0.12558 -0.0115665 + outer loop + vertex 0.937445 2.09719 2.52216 + vertex 0.937946 2.09281 2.52665 + vertex 0.937302 2.09804 2.52516 + endloop + endfacet + facet normal -0.921844 -0.00375063 0.387542 + outer loop + vertex 0.937946 2.09281 2.52665 + vertex 0.938713 2.09541 2.5285 + vertex 0.937302 2.09804 2.52516 + endloop + endfacet + facet normal -0.955399 0.0795092 0.284414 + outer loop + vertex 0.938692 2.09113 2.52962 + vertex 0.938713 2.09541 2.5285 + vertex 0.937946 2.09281 2.52665 + endloop + endfacet + facet normal 0.330174 -0.208092 -0.920697 + outer loop + vertex 0.94 2.1 2.51973 + vertex 0.936938 2.10259 2.51805 + vertex 0.94 2.105 2.5186 + endloop + endfacet + facet normal 0.248541 -0.303917 -0.919708 + outer loop + vertex 0.93852 2.09738 2.5202 + vertex 0.936938 2.10259 2.51805 + vertex 0.94 2.1 2.51973 + endloop + endfacet + facet normal -0.774895 -0.427131 -0.465937 + outer loop + vertex 0.93852 2.09738 2.5202 + vertex 0.937445 2.09719 2.52216 + vertex 0.936938 2.10259 2.51805 + endloop + endfacet + facet normal -0.863076 -0.354575 -0.359689 + outer loop + vertex 0.936938 2.10259 2.51805 + vertex 0.937445 2.09719 2.52216 + vertex 0.935811 2.10102 2.5223 + endloop + endfacet + facet normal -0.916904 -0.393288 0.067905 + outer loop + vertex 0.937445 2.09719 2.52216 + vertex 0.937302 2.09804 2.52516 + vertex 0.935811 2.10102 2.5223 + endloop + endfacet + facet normal -0.924011 -0.370223 0.0955896 + outer loop + vertex 0.935811 2.10102 2.5223 + vertex 0.937302 2.09804 2.52516 + vertex 0.936021 2.10118 2.52492 + endloop + endfacet + facet normal -0.851505 -0.315734 0.418631 + outer loop + vertex 0.937302 2.09804 2.52516 + vertex 0.937442 2.10132 2.52792 + vertex 0.936021 2.10118 2.52492 + endloop + endfacet + facet normal -0.948687 -0.178841 0.260785 + outer loop + vertex 0.938713 2.09541 2.5285 + vertex 0.937442 2.10132 2.52792 + vertex 0.937302 2.09804 2.52516 + endloop + endfacet + facet normal 0.512658 -0.489529 -0.705367 + outer loop + vertex 0.936938 2.10259 2.51805 + vertex 0.94 2.11 2.51513 + vertex 0.94 2.105 2.5186 + endloop + endfacet + facet normal 0.126324 -0.408108 -0.904151 + outer loop + vertex 0.936938 2.10259 2.51805 + vertex 0.935 2.10874 2.515 + vertex 0.94 2.11 2.51513 + endloop + endfacet + facet normal -0.0785075 -0.462304 -0.883239 + outer loop + vertex 0.936938 2.10259 2.51805 + vertex 0.932799 2.1053 2.517 + vertex 0.935 2.10874 2.515 + endloop + endfacet + facet normal 0.235863 -0.897733 -0.37208 + outer loop + vertex 0.939795 2.11 2.515 + vertex 0.94 2.11 2.51513 + vertex 0.935 2.10874 2.515 + endloop + endfacet + facet normal -0.486933 -0.769482 -0.413272 + outer loop + vertex 0.936938 2.10259 2.51805 + vertex 0.935811 2.10102 2.5223 + vertex 0.933557 2.10356 2.52022 + endloop + endfacet + facet normal -0.453761 -0.824948 -0.33699 + outer loop + vertex 0.932799 2.1053 2.517 + vertex 0.936938 2.10259 2.51805 + vertex 0.933557 2.10356 2.52022 + endloop + endfacet + facet normal -0.731221 -0.67504 0.0981705 + outer loop + vertex 0.935811 2.10102 2.5223 + vertex 0.936021 2.10118 2.52492 + vertex 0.933173 2.10416 2.52424 + endloop + endfacet + facet normal -0.757801 -0.652017 0.0247014 + outer loop + vertex 0.933557 2.10356 2.52022 + vertex 0.935811 2.10102 2.5223 + vertex 0.933173 2.10416 2.52424 + endloop + endfacet + facet normal -0.630234 -0.108771 0.768748 + outer loop + vertex 0.938245 2.10491 2.53003 + vertex 0.938313 2.10782 2.53049 + vertex 0.935501 2.10696 2.52807 + endloop + endfacet + facet normal -0.6799 -0.251417 0.688858 + outer loop + vertex 0.937442 2.10132 2.52792 + vertex 0.938245 2.10491 2.53003 + vertex 0.935501 2.10696 2.52807 + endloop + endfacet + facet normal -0.725128 -0.265567 0.635346 + outer loop + vertex 0.937442 2.10132 2.52792 + vertex 0.935501 2.10696 2.52807 + vertex 0.933173 2.10416 2.52424 + endloop + endfacet + facet normal -0.713831 -0.596723 0.36656 + outer loop + vertex 0.937442 2.10132 2.52792 + vertex 0.933173 2.10416 2.52424 + vertex 0.936021 2.10118 2.52492 + endloop + endfacet + facet normal -0.617122 -0.110726 0.779038 + outer loop + vertex 0.938245 2.10491 2.53003 + vertex 0.94065 2.10599 2.53208 + vertex 0.938313 2.10782 2.53049 + endloop + endfacet + facet normal 0.288193 -0.842767 -0.45463 + outer loop + vertex 0.94 2.11007 2.515 + vertex 0.94 2.11 2.51513 + vertex 0.939795 2.11 2.515 + endloop + endfacet + facet normal -0.628099 0.135362 0.76627 + outer loop + vertex 0.938313 2.10782 2.53049 + vertex 0.939995 2.10954 2.53157 + vertex 0.937897 2.11129 2.52954 + endloop + endfacet + facet normal -0.66932 0.121273 0.73301 + outer loop + vertex 0.938313 2.10782 2.53049 + vertex 0.937897 2.11129 2.52954 + vertex 0.935501 2.10696 2.52807 + endloop + endfacet + facet normal -0.534749 0.00861561 0.844967 + outer loop + vertex 0.935501 2.10696 2.52807 + vertex 0.937897 2.11129 2.52954 + vertex 0.933374 2.11141 2.52667 + endloop + endfacet + facet normal -0.552208 0.0194715 0.833479 + outer loop + vertex 0.939995 2.10954 2.53157 + vertex 0.938313 2.10782 2.53049 + vertex 0.94065 2.10599 2.53208 + endloop + endfacet + facet normal -0.434371 0.570469 0.697056 + outer loop + vertex 0.935527 2.11776 2.52394 + vertex 0.933351 2.11728 2.52298 + vertex 0.933408 2.11527 2.52466 + endloop + endfacet + facet normal -0.432973 0.56971 0.698545 + outer loop + vertex 0.933408 2.11527 2.52466 + vertex 0.936751 2.11507 2.52689 + vertex 0.935527 2.11776 2.52394 + endloop + endfacet + facet normal -0.490728 0.406316 0.770774 + outer loop + vertex 0.933408 2.11527 2.52466 + vertex 0.933374 2.11141 2.52667 + vertex 0.936751 2.11507 2.52689 + endloop + endfacet + facet normal -0.482985 0.398663 0.779611 + outer loop + vertex 0.933374 2.11141 2.52667 + vertex 0.937897 2.11129 2.52954 + vertex 0.936751 2.11507 2.52689 + endloop + endfacet + facet normal -0.405909 0.736933 0.540525 + outer loop + vertex 0.936387 2.12036 2.52145 + vertex 0.933836 2.12063 2.51917 + vertex 0.933485 2.119 2.52113 + endloop + endfacet + facet normal -0.416806 0.680769 0.60235 + outer loop + vertex 0.933485 2.119 2.52113 + vertex 0.933351 2.11728 2.52298 + vertex 0.935527 2.11776 2.52394 + endloop + endfacet + facet normal -0.394674 0.700281 0.594843 + outer loop + vertex 0.936387 2.12036 2.52145 + vertex 0.933485 2.119 2.52113 + vertex 0.935527 2.11776 2.52394 + endloop + endfacet + facet normal -0.410473 0.697899 0.586898 + outer loop + vertex 0.936387 2.12036 2.52145 + vertex 0.935527 2.11776 2.52394 + vertex 0.939024 2.11864 2.52535 + endloop + endfacet + facet normal -0.432864 0.678523 0.593495 + outer loop + vertex 0.936387 2.12036 2.52145 + vertex 0.939024 2.11864 2.52535 + vertex 0.938998 2.12074 2.52292 + endloop + endfacet + facet normal -0.424798 0.574571 0.699582 + outer loop + vertex 0.939024 2.11864 2.52535 + vertex 0.935527 2.11776 2.52394 + vertex 0.936751 2.11507 2.52689 + endloop + endfacet + facet normal -0.574859 0.740557 0.348013 + outer loop + vertex 0.94 2.13 2.51279 + vertex 0.938311 2.13 2.51 + vertex 0.935 2.12743 2.51 + endloop + endfacet + facet normal -0.597375 0.645409 0.476015 + outer loop + vertex 0.94 2.13 2.51279 + vertex 0.935 2.12743 2.51 + vertex 0.94 2.12837 2.515 + endloop + endfacet + facet normal -0.644462 0.538062 0.543285 + outer loop + vertex 0.94 2.12837 2.515 + vertex 0.935 2.12743 2.51 + vertex 0.934441 2.12471 2.51203 + endloop + endfacet + facet normal -0.626066 0.41597 0.659553 + outer loop + vertex 0.94 2.12837 2.515 + vertex 0.934441 2.12471 2.51203 + vertex 0.939082 2.12427 2.51671 + endloop + endfacet + facet normal -0.369621 0.816915 0.442753 + outer loop + vertex 0.939082 2.12427 2.51671 + vertex 0.934441 2.12471 2.51203 + vertex 0.93461 2.1222 2.51679 + endloop + endfacet + facet normal -0.314745 0.835397 0.450608 + outer loop + vertex 0.936387 2.12036 2.52145 + vertex 0.93461 2.1222 2.51679 + vertex 0.933836 2.12063 2.51917 + endloop + endfacet + facet normal -0.381275 0.800617 0.462214 + outer loop + vertex 0.936387 2.12036 2.52145 + vertex 0.938988 2.1221 2.52058 + vertex 0.93461 2.1222 2.51679 + endloop + endfacet + facet normal -0.368488 0.814654 0.447834 + outer loop + vertex 0.938988 2.1221 2.52058 + vertex 0.939082 2.12427 2.51671 + vertex 0.93461 2.1222 2.51679 + endloop + endfacet + facet normal -0.378911 0.799236 0.466527 + outer loop + vertex 0.938988 2.1221 2.52058 + vertex 0.936387 2.12036 2.52145 + vertex 0.938998 2.12074 2.52292 + endloop + endfacet + facet normal -0.61806 0.691377 0.374166 + outer loop + vertex 0.94 2.13151 2.51 + vertex 0.938311 2.13 2.51 + vertex 0.94 2.13 2.51279 + endloop + endfacet + facet normal -0.162231 -0.96909 0.185863 + outer loop + vertex 0.945 0.896958 2.51 + vertex 0.945 0.897917 2.515 + vertex 0.94 0.897795 2.51 + endloop + endfacet + facet normal 0.0119489 -0.999851 0.0124374 + outer loop + vertex 0.945 0.897917 2.515 + vertex 0.938438 0.897799 2.51182 + vertex 0.94 0.897795 2.51 + endloop + endfacet + facet normal 0.0717051 -0.991203 -0.111243 + outer loop + vertex 0.945 0.897917 2.515 + vertex 0.943217 0.897618 2.51652 + vertex 0.938438 0.897799 2.51182 + endloop + endfacet + facet normal -0.193297 -0.968096 0.159456 + outer loop + vertex 0.943217 0.897618 2.51652 + vertex 0.938721 0.898301 2.51521 + vertex 0.938438 0.897799 2.51182 + endloop + endfacet + facet normal -0.223362 -0.933304 0.281163 + outer loop + vertex 0.943217 0.897618 2.51652 + vertex 0.940481 0.898873 2.51851 + vertex 0.938721 0.898301 2.51521 + endloop + endfacet + facet normal -0.265751 -0.9373 0.225487 + outer loop + vertex 0.94406 0.898271 2.52022 + vertex 0.940481 0.898873 2.51851 + vertex 0.943217 0.897618 2.51652 + endloop + endfacet + facet normal -0.330029 -0.861335 0.386242 + outer loop + vertex 0.940481 0.898873 2.51851 + vertex 0.94406 0.898271 2.52022 + vertex 0.943044 0.899587 2.52229 + endloop + endfacet + facet normal -0.386524 -0.822517 0.41721 + outer loop + vertex 0.937588 0.901217 2.52045 + vertex 0.940481 0.898873 2.51851 + vertex 0.943044 0.899587 2.52229 + endloop + endfacet + facet normal -0.432606 -0.704068 0.563152 + outer loop + vertex 0.938013 0.903955 2.52436 + vertex 0.942383 0.902021 2.5253 + vertex 0.940455 0.903968 2.52625 + endloop + endfacet + facet normal -0.434155 -0.714841 0.548189 + outer loop + vertex 0.938013 0.903955 2.52436 + vertex 0.937588 0.901217 2.52045 + vertex 0.942383 0.902021 2.5253 + endloop + endfacet + facet normal -0.401021 -0.752977 0.521735 + outer loop + vertex 0.937588 0.901217 2.52045 + vertex 0.943044 0.899587 2.52229 + vertex 0.942383 0.902021 2.5253 + endloop + endfacet + facet normal -0.381425 -0.68278 0.623158 + outer loop + vertex 0.942383 0.902021 2.5253 + vertex 0.942112 0.90486 2.52824 + vertex 0.940455 0.903968 2.52625 + endloop + endfacet + facet normal -0.473458 -0.630249 0.615324 + outer loop + vertex 0.938013 0.903955 2.52436 + vertex 0.940455 0.903968 2.52625 + vertex 0.938325 0.906002 2.52669 + endloop + endfacet + facet normal -0.492481 -0.450626 0.74458 + outer loop + vertex 0.942239 0.907156 2.53033 + vertex 0.940739 0.909649 2.53085 + vertex 0.938287 0.908697 2.52865 + endloop + endfacet + facet normal -0.499683 -0.568168 0.653836 + outer loop + vertex 0.942112 0.90486 2.52824 + vertex 0.942239 0.907156 2.53033 + vertex 0.938287 0.908697 2.52865 + endloop + endfacet + facet normal -0.452739 -0.528267 0.718304 + outer loop + vertex 0.942112 0.90486 2.52824 + vertex 0.938287 0.908697 2.52865 + vertex 0.938325 0.906002 2.52669 + endloop + endfacet + facet normal -0.450111 -0.613184 0.649158 + outer loop + vertex 0.942112 0.90486 2.52824 + vertex 0.938325 0.906002 2.52669 + vertex 0.940455 0.903968 2.52625 + endloop + endfacet + facet normal -0.445909 -0.430871 0.784548 + outer loop + vertex 0.942239 0.907156 2.53033 + vertex 0.944564 0.908197 2.53222 + vertex 0.940739 0.909649 2.53085 + endloop + endfacet + facet normal -0.552769 -0.33646 0.762392 + outer loop + vertex 0.938287 0.908697 2.52865 + vertex 0.940739 0.909649 2.53085 + vertex 0.938178 0.911677 2.52989 + endloop + endfacet + facet normal -0.483062 -0.206439 0.850902 + outer loop + vertex 0.940739 0.909649 2.53085 + vertex 0.940866 0.91287 2.5317 + vertex 0.938178 0.911677 2.52989 + endloop + endfacet + facet normal -0.403046 -0.219552 0.888454 + outer loop + vertex 0.940739 0.909649 2.53085 + vertex 0.944564 0.908197 2.53222 + vertex 0.940866 0.91287 2.5317 + endloop + endfacet + facet normal -0.530673 -0.33269 0.779554 + outer loop + vertex 0.944564 0.908197 2.53222 + vertex 0.945241 0.911836 2.53424 + vertex 0.940866 0.91287 2.5317 + endloop + endfacet + facet normal -0.790712 0.124572 0.59938 + outer loop + vertex 0.940279 0.920367 2.53117 + vertex 0.938593 0.919496 2.52913 + vertex 0.939139 0.917194 2.53032 + endloop + endfacet + facet normal -0.678568 0.0487024 0.732921 + outer loop + vertex 0.939139 0.917194 2.53032 + vertex 0.942682 0.917019 2.53362 + vertex 0.940279 0.920367 2.53117 + endloop + endfacet + facet normal -0.681179 -0.0391459 0.73107 + outer loop + vertex 0.939139 0.917194 2.53032 + vertex 0.940866 0.91287 2.5317 + vertex 0.942682 0.917019 2.53362 + endloop + endfacet + facet normal -0.522962 -0.15758 0.837663 + outer loop + vertex 0.940866 0.91287 2.5317 + vertex 0.945241 0.911836 2.53424 + vertex 0.942682 0.917019 2.53362 + endloop + endfacet + facet normal 0.269187 0.747301 -0.607519 + outer loop + vertex 0.945 0.92387 2.52 + vertex 0.941863 0.925 2.52 + vertex 0.945 0.925 2.52139 + endloop + endfacet + facet normal -0.794308 0.304653 0.525606 + outer loop + vertex 0.938847 0.921821 2.52816 + vertex 0.938593 0.919496 2.52913 + vertex 0.940279 0.920367 2.53117 + endloop + endfacet + facet normal -0.873905 0.115696 0.472129 + outer loop + vertex 0.940526 0.924914 2.53051 + vertex 0.938847 0.921821 2.52816 + vertex 0.940279 0.920367 2.53117 + endloop + endfacet + facet normal -0.79433 0.128933 0.593646 + outer loop + vertex 0.940279 0.920367 2.53117 + vertex 0.94274 0.922241 2.53406 + vertex 0.940526 0.924914 2.53051 + endloop + endfacet + facet normal -0.744544 -0.0476832 0.665868 + outer loop + vertex 0.942682 0.917019 2.53362 + vertex 0.94274 0.922241 2.53406 + vertex 0.940279 0.920367 2.53117 + endloop + endfacet + facet normal -0.92906 0.366514 -0.0501515 + outer loop + vertex 0.939896 0.928611 2.52737 + vertex 0.940572 0.93 2.525 + vertex 0.94 0.92855 2.525 + endloop + endfacet + facet normal -0.985354 0.163789 -0.0474459 + outer loop + vertex 0.939334 0.925049 2.52675 + vertex 0.939896 0.928611 2.52737 + vertex 0.94 0.92855 2.525 + endloop + endfacet + facet normal -0.915297 0.269076 0.299715 + outer loop + vertex 0.939334 0.925049 2.52675 + vertex 0.938847 0.921821 2.52816 + vertex 0.940526 0.924914 2.53051 + endloop + endfacet + facet normal -0.947796 0.0968135 0.303824 + outer loop + vertex 0.939334 0.925049 2.52675 + vertex 0.940526 0.924914 2.53051 + vertex 0.939896 0.928611 2.52737 + endloop + endfacet + facet normal -0.980625 -0.000559284 0.195891 + outer loop + vertex 0.939896 0.928611 2.52737 + vertex 0.940526 0.924914 2.53051 + vertex 0.940857 0.930589 2.53219 + endloop + endfacet + facet normal -0.856811 -0.0992321 0.505993 + outer loop + vertex 0.940526 0.924914 2.53051 + vertex 0.942687 0.926962 2.53457 + vertex 0.940857 0.930589 2.53219 + endloop + endfacet + facet normal -0.867261 -0.0638957 0.493736 + outer loop + vertex 0.94274 0.922241 2.53406 + vertex 0.942687 0.926962 2.53457 + vertex 0.940526 0.924914 2.53051 + endloop + endfacet + facet normal -0.862404 -0.400101 0.310126 + outer loop + vertex 0.94 0.935 2.52986 + vertex 0.94 0.931233 2.525 + vertex 0.940572 0.93 2.525 + endloop + endfacet + facet normal -0.799307 -0.463358 0.382632 + outer loop + vertex 0.94 0.935 2.52986 + vertex 0.940572 0.93 2.525 + vertex 0.940067 0.935 2.53 + endloop + endfacet + facet normal -0.970972 0.112832 -0.210911 + outer loop + vertex 0.940067 0.935 2.53 + vertex 0.940572 0.93 2.525 + vertex 0.939896 0.928611 2.52737 + endloop + endfacet + facet normal -0.973153 -0.0648817 0.220824 + outer loop + vertex 0.939896 0.928611 2.52737 + vertex 0.940857 0.930589 2.53219 + vertex 0.940067 0.935 2.53 + endloop + endfacet + facet normal -0.972763 -0.215977 -0.0841735 + outer loop + vertex 0.940067 0.935 2.53 + vertex 0.940857 0.930589 2.53219 + vertex 0.939754 0.935307 2.53283 + endloop + endfacet + facet normal -0.887781 -0.165126 0.429626 + outer loop + vertex 0.942593 0.930572 2.53577 + vertex 0.940857 0.930589 2.53219 + vertex 0.942687 0.926962 2.53457 + endloop + endfacet + facet normal -0.861908 -0.28922 0.416494 + outer loop + vertex 0.942593 0.930572 2.53577 + vertex 0.9418 0.934378 2.53677 + vertex 0.940857 0.930589 2.53219 + endloop + endfacet + facet normal -0.880346 -0.260401 0.396463 + outer loop + vertex 0.9418 0.934378 2.53677 + vertex 0.939754 0.935307 2.53283 + vertex 0.940857 0.930589 2.53219 + endloop + endfacet + facet normal -0.785551 -0.305394 0.538186 + outer loop + vertex 0.942593 0.930572 2.53577 + vertex 0.943599 0.932073 2.53809 + vertex 0.9418 0.934378 2.53677 + endloop + endfacet + facet normal -0.785594 -0.618424 -0.0198537 + outer loop + vertex 0.940067 0.935 2.53 + vertex 0.939754 0.935307 2.53283 + vertex 0.938711 0.93672 2.53009 + endloop + endfacet + facet normal -0.160244 -0.0735461 -0.984334 + outer loop + vertex 0.94 0.935146 2.53 + vertex 0.940067 0.935 2.53 + vertex 0.938711 0.93672 2.53009 + endloop + endfacet + facet normal -0.910385 -0.38681 0.146894 + outer loop + vertex 0.938604 0.938131 2.53314 + vertex 0.938711 0.93672 2.53009 + vertex 0.939754 0.935307 2.53283 + endloop + endfacet + facet normal -0.858596 -0.386544 0.336746 + outer loop + vertex 0.938604 0.938131 2.53314 + vertex 0.939754 0.935307 2.53283 + vertex 0.939767 0.938948 2.53705 + endloop + endfacet + facet normal -0.848711 -0.39882 0.347323 + outer loop + vertex 0.939767 0.938948 2.53705 + vertex 0.939754 0.935307 2.53283 + vertex 0.9418 0.934378 2.53677 + endloop + endfacet + facet normal -0.789141 -0.314134 0.527802 + outer loop + vertex 0.944244 0.934607 2.54056 + vertex 0.9418 0.934378 2.53677 + vertex 0.943599 0.932073 2.53809 + endloop + endfacet + facet normal -0.760394 -0.39667 0.514251 + outer loop + vertex 0.944244 0.934607 2.54056 + vertex 0.942519 0.939052 2.54144 + vertex 0.9418 0.934378 2.53677 + endloop + endfacet + facet normal -0.780452 -0.377637 0.498282 + outer loop + vertex 0.942519 0.939052 2.54144 + vertex 0.939767 0.938948 2.53705 + vertex 0.9418 0.934378 2.53677 + endloop + endfacet + facet normal -0.727266 -0.393329 0.562474 + outer loop + vertex 0.944244 0.934607 2.54056 + vertex 0.945273 0.937174 2.54368 + vertex 0.942519 0.939052 2.54144 + endloop + endfacet + facet normal -0.840409 -0.422893 0.338932 + outer loop + vertex 0.938604 0.938131 2.53314 + vertex 0.939767 0.938948 2.53705 + vertex 0.938126 0.940747 2.53522 + endloop + endfacet + facet normal -0.84124 -0.410238 0.352165 + outer loop + vertex 0.938468 0.942567 2.53816 + vertex 0.938126 0.940747 2.53522 + vertex 0.939767 0.938948 2.53705 + endloop + endfacet + facet normal -0.771947 -0.422992 0.474527 + outer loop + vertex 0.938468 0.942567 2.53816 + vertex 0.939767 0.938948 2.53705 + vertex 0.939983 0.943488 2.54145 + endloop + endfacet + facet normal -0.758388 -0.434562 0.485801 + outer loop + vertex 0.939983 0.943488 2.54145 + vertex 0.939767 0.938948 2.53705 + vertex 0.942519 0.939052 2.54144 + endloop + endfacet + facet normal -0.727781 -0.404073 0.55413 + outer loop + vertex 0.944738 0.940312 2.54527 + vertex 0.942519 0.939052 2.54144 + vertex 0.945273 0.937174 2.54368 + endloop + endfacet + facet normal -0.719105 -0.41933 0.554121 + outer loop + vertex 0.944738 0.940312 2.54527 + vertex 0.942508 0.943667 2.54492 + vertex 0.942519 0.939052 2.54144 + endloop + endfacet + facet normal -0.725023 -0.415621 0.549182 + outer loop + vertex 0.942508 0.943667 2.54492 + vertex 0.939983 0.943488 2.54145 + vertex 0.942519 0.939052 2.54144 + endloop + endfacet + facet normal -0.714325 -0.415177 0.563354 + outer loop + vertex 0.944738 0.940312 2.54527 + vertex 0.945277 0.943106 2.54801 + vertex 0.942508 0.943667 2.54492 + endloop + endfacet + facet normal -0.784203 -0.400563 0.473893 + outer loop + vertex 0.938468 0.942567 2.53816 + vertex 0.939983 0.943488 2.54145 + vertex 0.938178 0.945489 2.54015 + endloop + endfacet + facet normal -0.782634 -0.393887 0.482013 + outer loop + vertex 0.93892 0.94717 2.54273 + vertex 0.938178 0.945489 2.54015 + vertex 0.939983 0.943488 2.54145 + endloop + endfacet + facet normal -0.740845 -0.40149 0.538473 + outer loop + vertex 0.93892 0.94717 2.54273 + vertex 0.939983 0.943488 2.54145 + vertex 0.940546 0.946702 2.54462 + endloop + endfacet + facet normal -0.725293 -0.414937 0.549343 + outer loop + vertex 0.940546 0.946702 2.54462 + vertex 0.939983 0.943488 2.54145 + vertex 0.942508 0.943667 2.54492 + endloop + endfacet + facet normal -0.710365 -0.402531 0.577366 + outer loop + vertex 0.942508 0.943667 2.54492 + vertex 0.94273 0.947874 2.54812 + vertex 0.940546 0.946702 2.54462 + endloop + endfacet + facet normal -0.718835 -0.396988 0.570681 + outer loop + vertex 0.945277 0.943106 2.54801 + vertex 0.94273 0.947874 2.54812 + vertex 0.942508 0.943667 2.54492 + endloop + endfacet + facet normal -0.747775 -0.367751 0.552803 + outer loop + vertex 0.93892 0.94717 2.54273 + vertex 0.940546 0.946702 2.54462 + vertex 0.9394 0.949876 2.54518 + endloop + endfacet + facet normal -0.726844 -0.374376 0.575795 + outer loop + vertex 0.943599 0.95103 2.55128 + vertex 0.941847 0.955768 2.55215 + vertex 0.940324 0.952974 2.54841 + endloop + endfacet + facet normal -0.726851 -0.374979 0.575394 + outer loop + vertex 0.94273 0.947874 2.54812 + vertex 0.943599 0.95103 2.55128 + vertex 0.940324 0.952974 2.54841 + endloop + endfacet + facet normal -0.730203 -0.376276 0.570281 + outer loop + vertex 0.94273 0.947874 2.54812 + vertex 0.940324 0.952974 2.54841 + vertex 0.9394 0.949876 2.54518 + endloop + endfacet + facet normal -0.730054 -0.365684 0.577318 + outer loop + vertex 0.94273 0.947874 2.54812 + vertex 0.9394 0.949876 2.54518 + vertex 0.940546 0.946702 2.54462 + endloop + endfacet + facet normal -0.716406 -0.373042 0.589578 + outer loop + vertex 0.943599 0.95103 2.55128 + vertex 0.945288 0.952331 2.55415 + vertex 0.941847 0.955768 2.55215 + endloop + endfacet + facet normal -0.735235 -0.364232 0.571634 + outer loop + vertex 0.937716 0.958223 2.54839 + vertex 0.940324 0.952974 2.54841 + vertex 0.941847 0.955768 2.55215 + endloop + endfacet + facet normal -0.735239 -0.377611 0.562879 + outer loop + vertex 0.939673 0.960224 2.55229 + vertex 0.937716 0.958223 2.54839 + vertex 0.941847 0.955768 2.55215 + endloop + endfacet + facet normal -0.715781 -0.371351 0.591402 + outer loop + vertex 0.944894 0.955382 2.55559 + vertex 0.941847 0.955768 2.55215 + vertex 0.945288 0.952331 2.55415 + endloop + endfacet + facet normal -0.713281 -0.381307 0.588077 + outer loop + vertex 0.944894 0.955382 2.55559 + vertex 0.942436 0.959187 2.55508 + vertex 0.941847 0.955768 2.55215 + endloop + endfacet + facet normal -0.724106 -0.37276 0.580277 + outer loop + vertex 0.942436 0.959187 2.55508 + vertex 0.939673 0.960224 2.55229 + vertex 0.941847 0.955768 2.55215 + endloop + endfacet + facet normal -0.699964 -0.369585 0.611112 + outer loop + vertex 0.944894 0.955382 2.55559 + vertex 0.945507 0.958086 2.55793 + vertex 0.942436 0.959187 2.55508 + endloop + endfacet + facet normal -0.735161 -0.377731 0.562901 + outer loop + vertex 0.937716 0.958223 2.54839 + vertex 0.939673 0.960224 2.55229 + vertex 0.937476 0.962196 2.55075 + endloop + endfacet + facet normal -0.734241 -0.373629 0.566826 + outer loop + vertex 0.938631 0.963195 2.5529 + vertex 0.937476 0.962196 2.55075 + vertex 0.939673 0.960224 2.55229 + endloop + endfacet + facet normal -0.727802 -0.37313 0.575394 + outer loop + vertex 0.938631 0.963195 2.5529 + vertex 0.939673 0.960224 2.55229 + vertex 0.940516 0.962203 2.55464 + endloop + endfacet + facet normal -0.723486 -0.377803 0.577782 + outer loop + vertex 0.940516 0.962203 2.55464 + vertex 0.939673 0.960224 2.55229 + vertex 0.942436 0.959187 2.55508 + endloop + endfacet + facet normal -0.710589 -0.366314 0.60073 + outer loop + vertex 0.942436 0.959187 2.55508 + vertex 0.942953 0.962807 2.55789 + vertex 0.940516 0.962203 2.55464 + endloop + endfacet + facet normal -0.699499 -0.374206 0.608828 + outer loop + vertex 0.945507 0.958086 2.55793 + vertex 0.942953 0.962807 2.55789 + vertex 0.942436 0.959187 2.55508 + endloop + endfacet + facet normal -0.727895 -0.370218 0.577155 + outer loop + vertex 0.938631 0.963195 2.5529 + vertex 0.940516 0.962203 2.55464 + vertex 0.93934 0.965194 2.55508 + endloop + endfacet + facet normal -0.682754 -0.389223 0.618347 + outer loop + vertex 0.943953 0.965919 2.56077 + vertex 0.941602 0.970221 2.56089 + vertex 0.940457 0.967708 2.55804 + endloop + endfacet + facet normal -0.682261 -0.366035 0.632881 + outer loop + vertex 0.942953 0.962807 2.55789 + vertex 0.943953 0.965919 2.56077 + vertex 0.940457 0.967708 2.55804 + endloop + endfacet + facet normal -0.711565 -0.379742 0.591161 + outer loop + vertex 0.942953 0.962807 2.55789 + vertex 0.940457 0.967708 2.55804 + vertex 0.93934 0.965194 2.55508 + endloop + endfacet + facet normal -0.710405 -0.366763 0.600675 + outer loop + vertex 0.942953 0.962807 2.55789 + vertex 0.93934 0.965194 2.55508 + vertex 0.940516 0.962203 2.55464 + endloop + endfacet + facet normal -0.640975 -0.367833 0.673684 + outer loop + vertex 0.943953 0.965919 2.56077 + vertex 0.945168 0.968366 2.56326 + vertex 0.941602 0.970221 2.56089 + endloop + endfacet + facet normal -0.696918 -0.374868 0.611375 + outer loop + vertex 0.937856 0.972649 2.5581 + vertex 0.940457 0.967708 2.55804 + vertex 0.941602 0.970221 2.56089 + endloop + endfacet + facet normal -0.699167 -0.399374 0.593014 + outer loop + vertex 0.940075 0.97307 2.561 + vertex 0.937856 0.972649 2.5581 + vertex 0.941602 0.970221 2.56089 + endloop + endfacet + facet normal -0.659686 -0.380512 0.648093 + outer loop + vertex 0.941602 0.970221 2.56089 + vertex 0.942338 0.973363 2.56348 + vertex 0.940075 0.97307 2.561 + endloop + endfacet + facet normal -0.643054 -0.392328 0.657693 + outer loop + vertex 0.945168 0.968366 2.56326 + vertex 0.942338 0.973363 2.56348 + vertex 0.941602 0.970221 2.56089 + endloop + endfacet + facet normal -0.700969 -0.395072 0.593768 + outer loop + vertex 0.937856 0.972649 2.5581 + vertex 0.940075 0.97307 2.561 + vertex 0.93864 0.975917 2.5612 + endloop + endfacet + facet normal -0.623559 -0.385235 0.680271 + outer loop + vertex 0.942401 0.976476 2.56533 + vertex 0.941203 0.979006 2.56566 + vertex 0.939989 0.977727 2.56383 + endloop + endfacet + facet normal -0.624047 -0.389938 0.677137 + outer loop + vertex 0.942338 0.973363 2.56348 + vertex 0.942401 0.976476 2.56533 + vertex 0.939989 0.977727 2.56383 + endloop + endfacet + facet normal -0.666072 -0.408326 0.624195 + outer loop + vertex 0.942338 0.973363 2.56348 + vertex 0.939989 0.977727 2.56383 + vertex 0.93864 0.975917 2.5612 + endloop + endfacet + facet normal -0.660425 -0.378482 0.648529 + outer loop + vertex 0.942338 0.973363 2.56348 + vertex 0.93864 0.975917 2.5612 + vertex 0.940075 0.97307 2.561 + endloop + endfacet + facet normal -0.540924 -0.356872 0.761606 + outer loop + vertex 0.942401 0.976476 2.56533 + vertex 0.944101 0.977937 2.56722 + vertex 0.941203 0.979006 2.56566 + endloop + endfacet + facet normal -0.629874 -0.377281 0.678909 + outer loop + vertex 0.939989 0.977727 2.56383 + vertex 0.941203 0.979006 2.56566 + vertex 0.93914 0.980755 2.56472 + endloop + endfacet + facet normal -0.612069 -0.336515 0.715632 + outer loop + vertex 0.941203 0.979006 2.56566 + vertex 0.940807 0.982006 2.56674 + vertex 0.93914 0.980755 2.56472 + endloop + endfacet + facet normal -0.539921 -0.345517 0.767531 + outer loop + vertex 0.941203 0.979006 2.56566 + vertex 0.944101 0.977937 2.56722 + vertex 0.940807 0.982006 2.56674 + endloop + endfacet + facet normal -0.527173 -0.333519 0.781571 + outer loop + vertex 0.944101 0.977937 2.56722 + vertex 0.944096 0.982528 2.56918 + vertex 0.940807 0.982006 2.56674 + endloop + endfacet + facet normal -0.53403 -0.367404 0.761463 + outer loop + vertex 0.943197 0.986675 2.57042 + vertex 0.94126 0.990578 2.57094 + vertex 0.939331 0.987421 2.56807 + endloop + endfacet + facet normal -0.535353 -0.346593 0.77024 + outer loop + vertex 0.943197 0.986675 2.57042 + vertex 0.939331 0.987421 2.56807 + vertex 0.944096 0.982528 2.56918 + endloop + endfacet + facet normal -0.526534 -0.335531 0.781141 + outer loop + vertex 0.944096 0.982528 2.56918 + vertex 0.939331 0.987421 2.56807 + vertex 0.940807 0.982006 2.56674 + endloop + endfacet + facet normal -0.457377 -0.337587 0.822704 + outer loop + vertex 0.943197 0.986675 2.57042 + vertex 0.945626 0.988255 2.57242 + vertex 0.94126 0.990578 2.57094 + endloop + endfacet + facet normal -0.542353 -0.360122 0.759055 + outer loop + vertex 0.937564 0.993115 2.56951 + vertex 0.939331 0.987421 2.56807 + vertex 0.94126 0.990578 2.57094 + endloop + endfacet + facet normal -0.549475 -0.378548 0.744835 + outer loop + vertex 0.939416 0.994367 2.57151 + vertex 0.937564 0.993115 2.56951 + vertex 0.94126 0.990578 2.57094 + endloop + endfacet + facet normal -0.467453 -0.34871 0.812335 + outer loop + vertex 0.94126 0.990578 2.57094 + vertex 0.942533 0.993504 2.57293 + vertex 0.939416 0.994367 2.57151 + endloop + endfacet + facet normal -0.462132 -0.3521 0.813916 + outer loop + vertex 0.945626 0.988255 2.57242 + vertex 0.942533 0.993504 2.57293 + vertex 0.94126 0.990578 2.57094 + endloop + endfacet + facet normal -0.558345 -0.365383 0.744813 + outer loop + vertex 0.937564 0.993115 2.56951 + vertex 0.939416 0.994367 2.57151 + vertex 0.936911 0.99654 2.5707 + endloop + endfacet + facet normal -0.540576 -0.334824 0.771797 + outer loop + vertex 0.939416 0.994367 2.57151 + vertex 0.938763 0.998054 2.57265 + vertex 0.936911 0.99654 2.5707 + endloop + endfacet + facet normal -0.4666 -0.336068 0.818134 + outer loop + vertex 0.939416 0.994367 2.57151 + vertex 0.942533 0.993504 2.57293 + vertex 0.938763 0.998054 2.57265 + endloop + endfacet + facet normal -0.454382 -0.325255 0.829304 + outer loop + vertex 0.942533 0.993504 2.57293 + vertex 0.943021 0.997506 2.57477 + vertex 0.938763 0.998054 2.57265 + endloop + endfacet + facet normal -0.45532 -0.344957 0.820785 + outer loop + vertex 0.942299 1.00113 2.57586 + vertex 0.94063 1.00398 2.57613 + vertex 0.938798 1.00247 2.57448 + endloop + endfacet + facet normal -0.454264 -0.339037 0.823831 + outer loop + vertex 0.942299 1.00113 2.57586 + vertex 0.938798 1.00247 2.57448 + vertex 0.943021 0.997506 2.57477 + endloop + endfacet + facet normal -0.453646 -0.338479 0.824401 + outer loop + vertex 0.943021 0.997506 2.57477 + vertex 0.938798 1.00247 2.57448 + vertex 0.938763 0.998054 2.57265 + endloop + endfacet + facet normal -0.41236 -0.32274 0.851938 + outer loop + vertex 0.942299 1.00113 2.57586 + vertex 0.944192 1.00275 2.57739 + vertex 0.94063 1.00398 2.57613 + endloop + endfacet + facet normal -0.465032 -0.332746 0.820381 + outer loop + vertex 0.938798 1.00247 2.57448 + vertex 0.94063 1.00398 2.57613 + vertex 0.937923 1.00634 2.57555 + endloop + endfacet + facet normal -0.446992 -0.307149 0.840153 + outer loop + vertex 0.94063 1.00398 2.57613 + vertex 0.940268 1.00726 2.57714 + vertex 0.937923 1.00634 2.57555 + endloop + endfacet + facet normal -0.40978 -0.308638 0.858384 + outer loop + vertex 0.94063 1.00398 2.57613 + vertex 0.944192 1.00275 2.57739 + vertex 0.940268 1.00726 2.57714 + endloop + endfacet + facet normal -0.411937 -0.310611 0.856638 + outer loop + vertex 0.944192 1.00275 2.57739 + vertex 0.944082 1.00755 2.57908 + vertex 0.940268 1.00726 2.57714 + endloop + endfacet + facet normal -0.422763 -0.317088 0.848956 + outer loop + vertex 0.943172 1.01169 2.58015 + vertex 0.941298 1.01553 2.58065 + vertex 0.938863 1.01278 2.57841 + endloop + endfacet + facet normal -0.422343 -0.312283 0.850944 + outer loop + vertex 0.943172 1.01169 2.58015 + vertex 0.938863 1.01278 2.57841 + vertex 0.944082 1.00755 2.57908 + endloop + endfacet + facet normal -0.413587 -0.302567 0.858719 + outer loop + vertex 0.944082 1.00755 2.57908 + vertex 0.938863 1.01278 2.57841 + vertex 0.940268 1.00726 2.57714 + endloop + endfacet + facet normal -0.432096 -0.320838 0.842826 + outer loop + vertex 0.943172 1.01169 2.58015 + vertex 0.945701 1.01324 2.58203 + vertex 0.941298 1.01553 2.58065 + endloop + endfacet + facet normal -0.430047 -0.309833 0.847976 + outer loop + vertex 0.937469 1.01818 2.57968 + vertex 0.938863 1.01278 2.57841 + vertex 0.941298 1.01553 2.58065 + endloop + endfacet + facet normal -0.430626 -0.310923 0.847283 + outer loop + vertex 0.939654 1.01922 2.58117 + vertex 0.937469 1.01818 2.57968 + vertex 0.941298 1.01553 2.58065 + endloop + endfacet + facet normal -0.421394 -0.30763 0.853107 + outer loop + vertex 0.941298 1.01553 2.58065 + vertex 0.942816 1.01844 2.58245 + vertex 0.939654 1.01922 2.58117 + endloop + endfacet + facet normal -0.426307 -0.304297 0.85186 + outer loop + vertex 0.945701 1.01324 2.58203 + vertex 0.942816 1.01844 2.58245 + vertex 0.941298 1.01553 2.58065 + endloop + endfacet + facet normal -0.433026 -0.306458 0.847686 + outer loop + vertex 0.937469 1.01818 2.57968 + vertex 0.939654 1.01922 2.58117 + vertex 0.937223 1.02139 2.58071 + endloop + endfacet + facet normal -0.421171 -0.29073 0.859122 + outer loop + vertex 0.939654 1.01922 2.58117 + vertex 0.939283 1.023 2.58226 + vertex 0.937223 1.02139 2.58071 + endloop + endfacet + facet normal -0.419902 -0.29078 0.859726 + outer loop + vertex 0.939654 1.01922 2.58117 + vertex 0.942816 1.01844 2.58245 + vertex 0.939283 1.023 2.58226 + endloop + endfacet + facet normal -0.428668 -0.29784 0.852956 + outer loop + vertex 0.942816 1.01844 2.58245 + vertex 0.943617 1.02251 2.58427 + vertex 0.939283 1.023 2.58226 + endloop + endfacet + facet normal -0.438432 -0.289006 0.851031 + outer loop + vertex 0.943245 1.02629 2.58536 + vertex 0.9416 1.03005 2.58579 + vertex 0.940094 1.02713 2.58402 + endloop + endfacet + facet normal -0.438417 -0.288854 0.85109 + outer loop + vertex 0.943245 1.02629 2.58536 + vertex 0.940094 1.02713 2.58402 + vertex 0.943617 1.02251 2.58427 + endloop + endfacet + facet normal -0.429253 -0.281473 0.858205 + outer loop + vertex 0.943617 1.02251 2.58427 + vertex 0.940094 1.02713 2.58402 + vertex 0.939283 1.023 2.58226 + endloop + endfacet + facet normal -0.472372 -0.301227 0.828328 + outer loop + vertex 0.943245 1.02629 2.58536 + vertex 0.945358 1.0273 2.58693 + vertex 0.9416 1.03005 2.58579 + endloop + endfacet + facet normal -0.439051 -0.288581 0.850856 + outer loop + vertex 0.937225 1.03241 2.58434 + vertex 0.940094 1.02713 2.58402 + vertex 0.9416 1.03005 2.58579 + endloop + endfacet + facet normal -0.435705 -0.279435 0.855615 + outer loop + vertex 0.939822 1.03398 2.58617 + vertex 0.937225 1.03241 2.58434 + vertex 0.9416 1.03005 2.58579 + endloop + endfacet + facet normal -0.466384 -0.291378 0.835216 + outer loop + vertex 0.9416 1.03005 2.58579 + vertex 0.944021 1.03284 2.58812 + vertex 0.939822 1.03398 2.58617 + endloop + endfacet + facet normal -0.466853 -0.290893 0.835123 + outer loop + vertex 0.945358 1.0273 2.58693 + vertex 0.944021 1.03284 2.58812 + vertex 0.9416 1.03005 2.58579 + endloop + endfacet + facet normal -0.436932 -0.277432 0.855641 + outer loop + vertex 0.937225 1.03241 2.58434 + vertex 0.939822 1.03398 2.58617 + vertex 0.937101 1.0363 2.58553 + endloop + endfacet + facet normal -0.438397 -0.279544 0.854204 + outer loop + vertex 0.939822 1.03398 2.58617 + vertex 0.939301 1.03808 2.58724 + vertex 0.937101 1.0363 2.58553 + endloop + endfacet + facet normal -0.465289 -0.27923 0.839962 + outer loop + vertex 0.939822 1.03398 2.58617 + vertex 0.944021 1.03284 2.58812 + vertex 0.939301 1.03808 2.58724 + endloop + endfacet + facet normal -0.459843 -0.273511 0.844829 + outer loop + vertex 0.944021 1.03284 2.58812 + vertex 0.942909 1.03831 2.58928 + vertex 0.939301 1.03808 2.58724 + endloop + endfacet + facet normal -0.470942 -0.283376 0.835411 + outer loop + vertex 0.94286 1.04152 2.59032 + vertex 0.94156 1.04504 2.59078 + vertex 0.939961 1.04231 2.58895 + endloop + endfacet + facet normal -0.470386 -0.277146 0.837811 + outer loop + vertex 0.94286 1.04152 2.59032 + vertex 0.939961 1.04231 2.58895 + vertex 0.942909 1.03831 2.58928 + endloop + endfacet + facet normal -0.460636 -0.269294 0.845751 + outer loop + vertex 0.942909 1.03831 2.58928 + vertex 0.939961 1.04231 2.58895 + vertex 0.939301 1.03808 2.58724 + endloop + endfacet + facet normal -0.503441 -0.292437 0.813036 + outer loop + vertex 0.94286 1.04152 2.59032 + vertex 0.94498 1.04237 2.59194 + vertex 0.94156 1.04504 2.59078 + endloop + endfacet + facet normal -0.4698 -0.284269 0.83575 + outer loop + vertex 0.937532 1.04731 2.58929 + vertex 0.939961 1.04231 2.58895 + vertex 0.94156 1.04504 2.59078 + endloop + endfacet + facet normal -0.46543 -0.272285 0.842162 + outer loop + vertex 0.940138 1.04874 2.59119 + vertex 0.937532 1.04731 2.58929 + vertex 0.94156 1.04504 2.59078 + endloop + endfacet + facet normal -0.507249 -0.285187 0.813245 + outer loop + vertex 0.94156 1.04504 2.59078 + vertex 0.944017 1.04762 2.59322 + vertex 0.940138 1.04874 2.59119 + endloop + endfacet + facet normal -0.502483 -0.290683 0.814257 + outer loop + vertex 0.94498 1.04237 2.59194 + vertex 0.944017 1.04762 2.59322 + vertex 0.94156 1.04504 2.59078 + endloop + endfacet + facet normal -0.469353 -0.265224 0.842237 + outer loop + vertex 0.937532 1.04731 2.58929 + vertex 0.940138 1.04874 2.59119 + vertex 0.937684 1.05111 2.59057 + endloop + endfacet + facet normal -0.483486 -0.283557 0.828153 + outer loop + vertex 0.940138 1.04874 2.59119 + vertex 0.93994 1.05224 2.59227 + vertex 0.937684 1.05111 2.59057 + endloop + endfacet + facet normal -0.506901 -0.280808 0.814983 + outer loop + vertex 0.940138 1.04874 2.59119 + vertex 0.944017 1.04762 2.59322 + vertex 0.93994 1.05224 2.59227 + endloop + endfacet + facet normal -0.512623 -0.28705 0.80921 + outer loop + vertex 0.944017 1.04762 2.59322 + vertex 0.942758 1.05305 2.59434 + vertex 0.93994 1.05224 2.59227 + endloop + endfacet + facet normal -0.513672 -0.273997 0.81306 + outer loop + vertex 0.942526 1.05634 2.59536 + vertex 0.941299 1.06001 2.59582 + vertex 0.938695 1.05767 2.59339 + endloop + endfacet + facet normal -0.515263 -0.286362 0.807775 + outer loop + vertex 0.942526 1.05634 2.59536 + vertex 0.938695 1.05767 2.59339 + vertex 0.942758 1.05305 2.59434 + endloop + endfacet + facet normal -0.513569 -0.284518 0.809504 + outer loop + vertex 0.942758 1.05305 2.59434 + vertex 0.938695 1.05767 2.59339 + vertex 0.93994 1.05224 2.59227 + endloop + endfacet + facet normal -0.516246 -0.274625 0.811216 + outer loop + vertex 0.942526 1.05634 2.59536 + vertex 0.944835 1.05711 2.59709 + vertex 0.941299 1.06001 2.59582 + endloop + endfacet + facet normal -0.519668 -0.266076 0.811879 + outer loop + vertex 0.937786 1.06297 2.59455 + vertex 0.938695 1.05767 2.59339 + vertex 0.941299 1.06001 2.59582 + endloop + endfacet + facet normal -0.519398 -0.265617 0.812203 + outer loop + vertex 0.940086 1.06372 2.59626 + vertex 0.937786 1.06297 2.59455 + vertex 0.941299 1.06001 2.59582 + endloop + endfacet + facet normal -0.524891 -0.266939 0.808228 + outer loop + vertex 0.941299 1.06001 2.59582 + vertex 0.943911 1.06236 2.5983 + vertex 0.940086 1.06372 2.59626 + endloop + endfacet + facet normal -0.517454 -0.276754 0.809721 + outer loop + vertex 0.944835 1.05711 2.59709 + vertex 0.943911 1.06236 2.5983 + vertex 0.941299 1.06001 2.59582 + endloop + endfacet + facet normal -0.522806 -0.256715 0.812879 + outer loop + vertex 0.937786 1.06297 2.59455 + vertex 0.940086 1.06372 2.59626 + vertex 0.937762 1.06619 2.59555 + endloop + endfacet + facet normal -0.531837 -0.26796 0.803335 + outer loop + vertex 0.940086 1.06372 2.59626 + vertex 0.939907 1.06707 2.59726 + vertex 0.937762 1.06619 2.59555 + endloop + endfacet + facet normal -0.525143 -0.268826 0.807439 + outer loop + vertex 0.940086 1.06372 2.59626 + vertex 0.943911 1.06236 2.5983 + vertex 0.939907 1.06707 2.59726 + endloop + endfacet + facet normal -0.530599 -0.274683 0.801882 + outer loop + vertex 0.943911 1.06236 2.5983 + vertex 0.942765 1.06787 2.59943 + vertex 0.939907 1.06707 2.59726 + endloop + endfacet + facet normal -0.531264 -0.249174 0.809735 + outer loop + vertex 0.942661 1.07145 2.60048 + vertex 0.941294 1.07524 2.60075 + vertex 0.938846 1.07254 2.59831 + endloop + endfacet + facet normal -0.53158 -0.253241 0.808265 + outer loop + vertex 0.942661 1.07145 2.60048 + vertex 0.938846 1.07254 2.59831 + vertex 0.942765 1.06787 2.59943 + endloop + endfacet + facet normal -0.536346 -0.25839 0.803472 + outer loop + vertex 0.942765 1.06787 2.59943 + vertex 0.938846 1.07254 2.59831 + vertex 0.939907 1.06707 2.59726 + endloop + endfacet + facet normal -0.465278 -0.228509 0.855161 + outer loop + vertex 0.942661 1.07145 2.60048 + vertex 0.945346 1.07302 2.60236 + vertex 0.941294 1.07524 2.60075 + endloop + endfacet + facet normal -0.529408 -0.251347 0.810279 + outer loop + vertex 0.937792 1.07801 2.59932 + vertex 0.938846 1.07254 2.59831 + vertex 0.941294 1.07524 2.60075 + endloop + endfacet + facet normal -0.534269 -0.260647 0.804127 + outer loop + vertex 0.939974 1.07888 2.60105 + vertex 0.937792 1.07801 2.59932 + vertex 0.941294 1.07524 2.60075 + endloop + endfacet + facet normal -0.499561 -0.250198 0.829361 + outer loop + vertex 0.941294 1.07524 2.60075 + vertex 0.942999 1.07788 2.60257 + vertex 0.939974 1.07888 2.60105 + endloop + endfacet + facet normal -0.479119 -0.267872 0.835877 + outer loop + vertex 0.945346 1.07302 2.60236 + vertex 0.942999 1.07788 2.60257 + vertex 0.941294 1.07524 2.60075 + endloop + endfacet + facet normal -0.535257 -0.258347 0.804212 + outer loop + vertex 0.937792 1.07801 2.59932 + vertex 0.939974 1.07888 2.60105 + vertex 0.937629 1.08137 2.60029 + endloop + endfacet + facet normal -0.536988 -0.260555 0.802344 + outer loop + vertex 0.939974 1.07888 2.60105 + vertex 0.939937 1.08205 2.60206 + vertex 0.937629 1.08137 2.60029 + endloop + endfacet + facet normal -0.501757 -0.266653 0.822883 + outer loop + vertex 0.939974 1.07888 2.60105 + vertex 0.942999 1.07788 2.60257 + vertex 0.939937 1.08205 2.60206 + endloop + endfacet + facet normal -0.493093 -0.259366 0.830415 + outer loop + vertex 0.942999 1.07788 2.60257 + vertex 0.943606 1.08204 2.60423 + vertex 0.939937 1.08205 2.60206 + endloop + endfacet + facet normal -0.498641 -0.260064 0.826876 + outer loop + vertex 0.943033 1.0863 2.60528 + vertex 0.941548 1.0904 2.60567 + vertex 0.939004 1.0874 2.60319 + endloop + endfacet + facet normal -0.499377 -0.269225 0.823493 + outer loop + vertex 0.943033 1.0863 2.60528 + vertex 0.939004 1.0874 2.60319 + vertex 0.943606 1.08204 2.60423 + endloop + endfacet + facet normal -0.4927 -0.262278 0.829733 + outer loop + vertex 0.943606 1.08204 2.60423 + vertex 0.939004 1.0874 2.60319 + vertex 0.939937 1.08205 2.60206 + endloop + endfacet + facet normal -0.362074 -0.218153 0.906263 + outer loop + vertex 0.943033 1.0863 2.60528 + vertex 0.94606 1.0885 2.60702 + vertex 0.941548 1.0904 2.60567 + endloop + endfacet + facet normal -0.498878 -0.259811 0.826812 + outer loop + vertex 0.937857 1.093 2.60426 + vertex 0.939004 1.0874 2.60319 + vertex 0.941548 1.0904 2.60567 + endloop + endfacet + facet normal -0.5021 -0.266632 0.82268 + outer loop + vertex 0.940226 1.09427 2.60612 + vertex 0.937857 1.093 2.60426 + vertex 0.941548 1.0904 2.60567 + endloop + endfacet + facet normal -0.390688 -0.236291 0.88968 + outer loop + vertex 0.941548 1.0904 2.60567 + vertex 0.943924 1.09402 2.60768 + vertex 0.940226 1.09427 2.60612 + endloop + endfacet + facet normal -0.372049 -0.250744 0.893704 + outer loop + vertex 0.94606 1.0885 2.60702 + vertex 0.943924 1.09402 2.60768 + vertex 0.941548 1.0904 2.60567 + endloop + endfacet + facet normal -0.509042 -0.253506 0.822564 + outer loop + vertex 0.937857 1.093 2.60426 + vertex 0.940226 1.09427 2.60612 + vertex 0.937732 1.09659 2.60529 + endloop + endfacet + facet normal -0.489412 -0.225448 0.842407 + outer loop + vertex 0.940226 1.09427 2.60612 + vertex 0.940375 1.0981 2.60723 + vertex 0.937732 1.09659 2.60529 + endloop + endfacet + facet normal -0.39044 -0.242551 0.888102 + outer loop + vertex 0.940226 1.09427 2.60612 + vertex 0.943924 1.09402 2.60768 + vertex 0.940375 1.0981 2.60723 + endloop + endfacet + facet normal -0.402586 -0.254061 0.879419 + outer loop + vertex 0.943924 1.09402 2.60768 + vertex 0.943587 1.09767 2.60858 + vertex 0.940375 1.0981 2.60723 + endloop + endfacet + facet normal -0.402321 -0.234623 0.884924 + outer loop + vertex 0.943587 1.09767 2.60858 + vertex 0.942829 1.10173 2.60931 + vertex 0.940375 1.0981 2.60723 + endloop + endfacet + facet normal -0.418417 -0.221404 0.880856 + outer loop + vertex 0.940375 1.0981 2.60723 + vertex 0.942829 1.10173 2.60931 + vertex 0.938078 1.10298 2.60737 + endloop + endfacet + facet normal -0.40505 -0.259574 0.876673 + outer loop + vertex 0.942434 1.10607 2.61042 + vertex 0.940971 1.10922 2.61068 + vertex 0.938817 1.10704 2.60903 + endloop + endfacet + facet normal -0.405257 -0.261176 0.876101 + outer loop + vertex 0.942434 1.10607 2.61042 + vertex 0.938817 1.10704 2.60903 + vertex 0.942829 1.10173 2.60931 + endloop + endfacet + facet normal -0.42524 -0.277019 0.861645 + outer loop + vertex 0.942829 1.10173 2.60931 + vertex 0.938817 1.10704 2.60903 + vertex 0.938078 1.10298 2.60737 + endloop + endfacet + facet normal -0.24636 -0.19178 0.950014 + outer loop + vertex 0.942434 1.10607 2.61042 + vertex 0.945267 1.10919 2.61178 + vertex 0.940971 1.10922 2.61068 + endloop + endfacet + facet normal -0.413691 -0.250099 0.875392 + outer loop + vertex 0.938817 1.10704 2.60903 + vertex 0.940971 1.10922 2.61068 + vertex 0.938372 1.11126 2.61003 + endloop + endfacet + facet normal -0.374603 -0.190248 0.907457 + outer loop + vertex 0.940971 1.10922 2.61068 + vertex 0.941296 1.11353 2.61171 + vertex 0.938372 1.11126 2.61003 + endloop + endfacet + facet normal -0.245581 -0.209389 0.946492 + outer loop + vertex 0.940971 1.10922 2.61068 + vertex 0.945267 1.10919 2.61178 + vertex 0.941296 1.11353 2.61171 + endloop + endfacet + facet normal -0.233774 -0.198507 0.951811 + outer loop + vertex 0.945267 1.10919 2.61178 + vertex 0.945403 1.11426 2.61287 + vertex 0.941296 1.11353 2.61171 + endloop + endfacet + facet normal -0.230151 -0.214767 0.949161 + outer loop + vertex 0.945403 1.11426 2.61287 + vertex 0.943943 1.11798 2.61336 + vertex 0.941296 1.11353 2.61171 + endloop + endfacet + facet normal -0.259071 -0.196281 0.945704 + outer loop + vertex 0.941296 1.11353 2.61171 + vertex 0.943943 1.11798 2.61336 + vertex 0.939738 1.11859 2.61234 + endloop + endfacet + facet normal -0.262045 -0.231553 0.936865 + outer loop + vertex 0.943943 1.11798 2.61336 + vertex 0.942309 1.1217 2.61383 + vertex 0.939738 1.11859 2.61234 + endloop + endfacet + facet normal -0.292159 -0.205322 0.934069 + outer loop + vertex 0.939738 1.11859 2.61234 + vertex 0.942309 1.1217 2.61383 + vertex 0.938461 1.12355 2.61303 + endloop + endfacet + facet normal -0.293369 -0.208291 0.933032 + outer loop + vertex 0.942309 1.1217 2.61383 + vertex 0.942298 1.12641 2.61487 + vertex 0.938461 1.12355 2.61303 + endloop + endfacet + facet normal -0.269008 -0.240676 0.932582 + outer loop + vertex 0.938461 1.12355 2.61303 + vertex 0.942298 1.12641 2.61487 + vertex 0.938466 1.12711 2.61395 + endloop + endfacet + facet normal -0.296401 -0.249631 0.921862 + outer loop + vertex 0.941885 1.13069 2.61581 + vertex 0.940076 1.13386 2.61609 + vertex 0.93764 1.13125 2.6146 + endloop + endfacet + facet normal -0.295471 -0.231584 0.926858 + outer loop + vertex 0.941885 1.13069 2.61581 + vertex 0.93764 1.13125 2.6146 + vertex 0.942298 1.12641 2.61487 + endloop + endfacet + facet normal -0.264341 -0.200666 0.943322 + outer loop + vertex 0.942298 1.12641 2.61487 + vertex 0.93764 1.13125 2.6146 + vertex 0.938466 1.12711 2.61395 + endloop + endfacet + facet normal -0.152944 -0.172048 0.973143 + outer loop + vertex 0.941885 1.13069 2.61581 + vertex 0.94481 1.13404 2.61686 + vertex 0.940076 1.13386 2.61609 + endloop + endfacet + facet normal -0.301387 -0.244793 0.921544 + outer loop + vertex 0.93764 1.13125 2.6146 + vertex 0.940076 1.13386 2.61609 + vertex 0.937153 1.13578 2.61564 + endloop + endfacet + facet normal -0.260423 -0.176057 0.949307 + outer loop + vertex 0.940076 1.13386 2.61609 + vertex 0.940081 1.1389 2.61702 + vertex 0.937153 1.13578 2.61564 + endloop + endfacet + facet normal -0.152383 -0.180336 0.97173 + outer loop + vertex 0.940076 1.13386 2.61609 + vertex 0.94481 1.13404 2.61686 + vertex 0.940081 1.1389 2.61702 + endloop + endfacet + facet normal -0.143229 -0.171515 0.974714 + outer loop + vertex 0.94481 1.13404 2.61686 + vertex 0.944994 1.13934 2.61782 + vertex 0.940081 1.1389 2.61702 + endloop + endfacet + facet normal -0.141933 -0.182669 0.972876 + outer loop + vertex 0.944994 1.13934 2.61782 + vertex 0.944089 1.14337 2.61845 + vertex 0.940081 1.1389 2.61702 + endloop + endfacet + facet normal -0.12973 -0.193494 0.972487 + outer loop + vertex 0.940081 1.1389 2.61702 + vertex 0.944089 1.14337 2.61845 + vertex 0.940297 1.14414 2.61809 + endloop + endfacet + facet normal -0.128128 -0.184803 0.974388 + outer loop + vertex 0.944089 1.14337 2.61845 + vertex 0.943483 1.14779 2.61921 + vertex 0.940297 1.14414 2.61809 + endloop + endfacet + facet normal -0.150542 -0.165312 0.974684 + outer loop + vertex 0.940297 1.14414 2.61809 + vertex 0.943483 1.14779 2.61921 + vertex 0.938877 1.14789 2.61851 + endloop + endfacet + facet normal -0.150368 -0.197278 0.968747 + outer loop + vertex 0.943483 1.14779 2.61921 + vertex 0.941977 1.15237 2.6199 + vertex 0.938877 1.14789 2.61851 + endloop + endfacet + facet normal -0.177807 -0.178013 0.967831 + outer loop + vertex 0.938877 1.14789 2.61851 + vertex 0.941977 1.15237 2.6199 + vertex 0.937283 1.15164 2.61891 + endloop + endfacet + facet normal -0.167519 -0.233323 0.957861 + outer loop + vertex 0.942184 1.15643 2.62078 + vertex 0.940155 1.15911 2.62108 + vertex 0.937336 1.15632 2.6199 + endloop + endfacet + facet normal -0.169589 -0.199199 0.965173 + outer loop + vertex 0.942184 1.15643 2.62078 + vertex 0.937336 1.15632 2.6199 + vertex 0.941977 1.15237 2.6199 + endloop + endfacet + facet normal -0.173002 -0.203212 0.96373 + outer loop + vertex 0.941977 1.15237 2.6199 + vertex 0.937336 1.15632 2.6199 + vertex 0.937283 1.15164 2.61891 + endloop + endfacet + facet normal -0.0730311 -0.164856 0.98361 + outer loop + vertex 0.942184 1.15643 2.62078 + vertex 0.944592 1.1599 2.62154 + vertex 0.940155 1.15911 2.62108 + endloop + endfacet + facet normal -0.18401 -0.21702 0.958667 + outer loop + vertex 0.937336 1.15632 2.6199 + vertex 0.940155 1.15911 2.62108 + vertex 0.93695 1.16056 2.62079 + endloop + endfacet + facet normal -0.15988 -0.160638 0.973978 + outer loop + vertex 0.940155 1.15911 2.62108 + vertex 0.93983 1.16386 2.62181 + vertex 0.93695 1.16056 2.62079 + endloop + endfacet + facet normal -0.0746477 -0.156461 0.984859 + outer loop + vertex 0.940155 1.15911 2.62108 + vertex 0.944592 1.1599 2.62154 + vertex 0.93983 1.16386 2.62181 + endloop + endfacet + facet normal -0.0632403 -0.183105 0.981057 + outer loop + vertex 0.93741 1.18719 2.62539 + vertex 0.937063 1.18291 2.62457 + vertex 0.941458 1.18645 2.62551 + endloop + endfacet + facet normal -0.0605677 -0.167957 0.983932 + outer loop + vertex 0.941458 1.18645 2.62551 + vertex 0.939833 1.1906 2.62612 + vertex 0.93741 1.18719 2.62539 + endloop + endfacet + facet normal -0.0713778 -0.0510036 0.996144 + outer loop + vertex 0.943173 1.21292 2.62872 + vertex 0.943428 1.21809 2.62901 + vertex 0.938063 1.21297 2.62836 + endloop + endfacet + facet normal -0.0833883 -0.0383642 0.995778 + outer loop + vertex 0.938063 1.21297 2.62836 + vertex 0.943428 1.21809 2.62901 + vertex 0.938527 1.21826 2.6286 + endloop + endfacet + facet normal -0.355828 0.292331 0.887654 + outer loop + vertex 0.941269 1.90803 2.61097 + vertex 0.937636 1.90663 2.60998 + vertex 0.939297 1.90504 2.61117 + endloop + endfacet + facet normal -0.188712 0.186932 0.964077 + outer loop + vertex 0.939297 1.90504 2.61117 + vertex 0.94304 1.90631 2.61165 + vertex 0.941269 1.90803 2.61097 + endloop + endfacet + facet normal -0.188404 0.185922 0.964332 + outer loop + vertex 0.939297 1.90504 2.61117 + vertex 0.938529 1.90131 2.61174 + vertex 0.94304 1.90631 2.61165 + endloop + endfacet + facet normal -0.225649 0.267052 0.936891 + outer loop + vertex 0.941269 1.90803 2.61097 + vertex 0.944116 1.90996 2.61111 + vertex 0.942675 1.91174 2.61025 + endloop + endfacet + facet normal -0.359671 0.306921 0.881156 + outer loop + vertex 0.941269 1.90803 2.61097 + vertex 0.942675 1.91174 2.61025 + vertex 0.937636 1.90663 2.60998 + endloop + endfacet + facet normal -0.331476 0.278067 0.901555 + outer loop + vertex 0.937636 1.90663 2.60998 + vertex 0.942675 1.91174 2.61025 + vertex 0.938061 1.91147 2.60864 + endloop + endfacet + facet normal -0.1791 0.196776 0.963952 + outer loop + vertex 0.944116 1.90996 2.61111 + vertex 0.941269 1.90803 2.61097 + vertex 0.94304 1.90631 2.61165 + endloop + endfacet + facet normal -0.332416 0.253296 0.908483 + outer loop + vertex 0.942675 1.91174 2.61025 + vertex 0.94315 1.9166 2.60907 + vertex 0.938061 1.91147 2.60864 + endloop + endfacet + facet normal -0.323277 0.243745 0.914374 + outer loop + vertex 0.938061 1.91147 2.60864 + vertex 0.94315 1.9166 2.60907 + vertex 0.938173 1.91665 2.6073 + endloop + endfacet + facet normal -0.326459 0.206653 0.922344 + outer loop + vertex 0.94315 1.9166 2.60907 + vertex 0.943379 1.92162 2.60803 + vertex 0.938173 1.91665 2.6073 + endloop + endfacet + facet normal -0.294182 0.170182 0.940476 + outer loop + vertex 0.938173 1.91665 2.6073 + vertex 0.943379 1.92162 2.60803 + vertex 0.939372 1.9217 2.60676 + endloop + endfacet + facet normal -0.477545 0.269933 0.836114 + outer loop + vertex 0.940455 1.92841 2.60552 + vertex 0.937088 1.92568 2.60448 + vertex 0.939282 1.92484 2.60601 + endloop + endfacet + facet normal -0.322065 0.230065 0.918338 + outer loop + vertex 0.939282 1.92484 2.60601 + vertex 0.943094 1.92649 2.60693 + vertex 0.940455 1.92841 2.60552 + endloop + endfacet + facet normal -0.316195 0.213128 0.924444 + outer loop + vertex 0.939282 1.92484 2.60601 + vertex 0.939372 1.9217 2.60676 + vertex 0.943094 1.92649 2.60693 + endloop + endfacet + facet normal -0.292398 0.194221 0.936366 + outer loop + vertex 0.939372 1.9217 2.60676 + vertex 0.943379 1.92162 2.60803 + vertex 0.943094 1.92649 2.60693 + endloop + endfacet + facet normal -0.482624 0.27838 0.830409 + outer loop + vertex 0.938199 1.93105 2.60333 + vertex 0.937088 1.92568 2.60448 + vertex 0.940455 1.92841 2.60552 + endloop + endfacet + facet normal -0.473762 0.28759 0.832371 + outer loop + vertex 0.942114 1.93208 2.6052 + vertex 0.938199 1.93105 2.60333 + vertex 0.940455 1.92841 2.60552 + endloop + endfacet + facet normal -0.357052 0.24107 0.902441 + outer loop + vertex 0.940455 1.92841 2.60552 + vertex 0.943681 1.93055 2.60623 + vertex 0.942114 1.93208 2.6052 + endloop + endfacet + facet normal -0.338211 0.207573 0.917893 + outer loop + vertex 0.943094 1.92649 2.60693 + vertex 0.943681 1.93055 2.60623 + vertex 0.940455 1.92841 2.60552 + endloop + endfacet + facet normal -0.328073 0.288161 0.899629 + outer loop + vertex 0.942114 1.93208 2.6052 + vertex 0.945548 1.93404 2.60582 + vertex 0.943407 1.93643 2.60428 + endloop + endfacet + facet normal -0.475723 0.315447 0.821085 + outer loop + vertex 0.942114 1.93208 2.6052 + vertex 0.943407 1.93643 2.60428 + vertex 0.938199 1.93105 2.60333 + endloop + endfacet + facet normal -0.42438 0.257438 0.868117 + outer loop + vertex 0.938199 1.93105 2.60333 + vertex 0.943407 1.93643 2.60428 + vertex 0.939304 1.93657 2.60223 + endloop + endfacet + facet normal -0.322962 0.277515 0.90481 + outer loop + vertex 0.945548 1.93404 2.60582 + vertex 0.942114 1.93208 2.6052 + vertex 0.943681 1.93055 2.60623 + endloop + endfacet + facet normal -0.54045 0.267819 0.797613 + outer loop + vertex 0.940544 1.94371 2.60079 + vertex 0.936997 1.94069 2.59941 + vertex 0.93929 1.93991 2.60122 + endloop + endfacet + facet normal -0.430784 0.239759 0.870023 + outer loop + vertex 0.93929 1.93991 2.60122 + vertex 0.943237 1.94168 2.60269 + vertex 0.940544 1.94371 2.60079 + endloop + endfacet + facet normal -0.436308 0.258881 0.861752 + outer loop + vertex 0.93929 1.93991 2.60122 + vertex 0.939304 1.93657 2.60223 + vertex 0.943237 1.94168 2.60269 + endloop + endfacet + facet normal -0.425486 0.249822 0.869799 + outer loop + vertex 0.939304 1.93657 2.60223 + vertex 0.943407 1.93643 2.60428 + vertex 0.943237 1.94168 2.60269 + endloop + endfacet + facet normal -0.538395 0.264216 0.8002 + outer loop + vertex 0.9381 1.94607 2.59837 + vertex 0.936997 1.94069 2.59941 + vertex 0.940544 1.94371 2.60079 + endloop + endfacet + facet normal -0.547996 0.251717 0.797708 + outer loop + vertex 0.94176 1.94744 2.60045 + vertex 0.9381 1.94607 2.59837 + vertex 0.940544 1.94371 2.60079 + endloop + endfacet + facet normal -0.428738 0.220033 0.876224 + outer loop + vertex 0.940544 1.94371 2.60079 + vertex 0.944302 1.94684 2.60185 + vertex 0.94176 1.94744 2.60045 + endloop + endfacet + facet normal -0.436477 0.23161 0.869393 + outer loop + vertex 0.943237 1.94168 2.60269 + vertex 0.944302 1.94684 2.60185 + vertex 0.940544 1.94371 2.60079 + endloop + endfacet + facet normal -0.474439 0.273982 0.836565 + outer loop + vertex 0.94176 1.94744 2.60045 + vertex 0.944252 1.95001 2.60102 + vertex 0.941939 1.95074 2.59947 + endloop + endfacet + facet normal -0.549786 0.264905 0.792187 + outer loop + vertex 0.94176 1.94744 2.60045 + vertex 0.941939 1.95074 2.59947 + vertex 0.9381 1.94607 2.59837 + endloop + endfacet + facet normal -0.548583 0.26362 0.793449 + outer loop + vertex 0.9381 1.94607 2.59837 + vertex 0.941939 1.95074 2.59947 + vertex 0.939184 1.95143 2.59734 + endloop + endfacet + facet normal -0.42853 0.220743 0.876148 + outer loop + vertex 0.944252 1.95001 2.60102 + vertex 0.94176 1.94744 2.60045 + vertex 0.944302 1.94684 2.60185 + endloop + endfacet + facet normal -0.534007 0.260877 0.804226 + outer loop + vertex 0.940522 1.95855 2.59589 + vertex 0.936902 1.95559 2.59445 + vertex 0.939331 1.9548 2.59632 + endloop + endfacet + facet normal -0.517501 0.256983 0.816181 + outer loop + vertex 0.939331 1.9548 2.59632 + vertex 0.943232 1.95612 2.59837 + vertex 0.940522 1.95855 2.59589 + endloop + endfacet + facet normal -0.518969 0.268741 0.811449 + outer loop + vertex 0.939331 1.9548 2.59632 + vertex 0.939184 1.95143 2.59734 + vertex 0.943232 1.95612 2.59837 + endloop + endfacet + facet normal -0.539305 0.290962 0.790247 + outer loop + vertex 0.939184 1.95143 2.59734 + vertex 0.941939 1.95074 2.59947 + vertex 0.943232 1.95612 2.59837 + endloop + endfacet + facet normal -0.537698 0.267687 0.799515 + outer loop + vertex 0.937911 1.96096 2.59333 + vertex 0.936902 1.95559 2.59445 + vertex 0.940522 1.95855 2.59589 + endloop + endfacet + facet normal -0.540796 0.263569 0.798793 + outer loop + vertex 0.941711 1.9623 2.59546 + vertex 0.937911 1.96096 2.59333 + vertex 0.940522 1.95855 2.59589 + endloop + endfacet + facet normal -0.493673 0.252463 0.832195 + outer loop + vertex 0.940522 1.95855 2.59589 + vertex 0.944311 1.96161 2.59721 + vertex 0.941711 1.9623 2.59546 + endloop + endfacet + facet normal -0.505423 0.2729 0.81858 + outer loop + vertex 0.943232 1.95612 2.59837 + vertex 0.944311 1.96161 2.59721 + vertex 0.940522 1.95855 2.59589 + endloop + endfacet + facet normal -0.51722 0.283396 0.807571 + outer loop + vertex 0.941711 1.9623 2.59546 + vertex 0.944246 1.96492 2.59616 + vertex 0.941913 1.96567 2.5944 + endloop + endfacet + facet normal -0.542694 0.280014 0.791881 + outer loop + vertex 0.941711 1.9623 2.59546 + vertex 0.941913 1.96567 2.5944 + vertex 0.937911 1.96096 2.59333 + endloop + endfacet + facet normal -0.548406 0.286287 0.785678 + outer loop + vertex 0.937911 1.96096 2.59333 + vertex 0.941913 1.96567 2.5944 + vertex 0.93917 1.96636 2.59224 + endloop + endfacet + facet normal -0.493278 0.253638 0.832072 + outer loop + vertex 0.944246 1.96492 2.59616 + vertex 0.941711 1.9623 2.59546 + vertex 0.944311 1.96161 2.59721 + endloop + endfacet + facet normal -0.499291 0.259371 0.826701 + outer loop + vertex 0.940694 1.97339 2.59083 + vertex 0.937021 1.97056 2.5895 + vertex 0.939422 1.96971 2.59122 + endloop + endfacet + facet normal -0.540008 0.270353 0.797057 + outer loop + vertex 0.939422 1.96971 2.59122 + vertex 0.943213 1.97111 2.59331 + vertex 0.940694 1.97339 2.59083 + endloop + endfacet + facet normal -0.541492 0.281812 0.792066 + outer loop + vertex 0.939422 1.96971 2.59122 + vertex 0.93917 1.96636 2.59224 + vertex 0.943213 1.97111 2.59331 + endloop + endfacet + facet normal -0.547628 0.288529 0.785401 + outer loop + vertex 0.93917 1.96636 2.59224 + vertex 0.941913 1.96567 2.5944 + vertex 0.943213 1.97111 2.59331 + endloop + endfacet + facet normal -0.501737 0.263933 0.823772 + outer loop + vertex 0.938312 1.97566 2.58865 + vertex 0.937021 1.97056 2.5895 + vertex 0.940694 1.97339 2.59083 + endloop + endfacet + facet normal -0.498196 0.268336 0.824498 + outer loop + vertex 0.941916 1.97706 2.59038 + vertex 0.938312 1.97566 2.58865 + vertex 0.940694 1.97339 2.59083 + endloop + endfacet + facet normal -0.523169 0.274443 0.80683 + outer loop + vertex 0.940694 1.97339 2.59083 + vertex 0.94434 1.97649 2.59214 + vertex 0.941916 1.97706 2.59038 + endloop + endfacet + facet normal -0.529206 0.284743 0.799289 + outer loop + vertex 0.943213 1.97111 2.59331 + vertex 0.94434 1.97649 2.59214 + vertex 0.940694 1.97339 2.59083 + endloop + endfacet + facet normal -0.515995 0.272721 0.812018 + outer loop + vertex 0.941916 1.97706 2.59038 + vertex 0.944378 1.97972 2.59105 + vertex 0.941973 1.98037 2.5893 + endloop + endfacet + facet normal -0.499469 0.275472 0.821368 + outer loop + vertex 0.941916 1.97706 2.59038 + vertex 0.941973 1.98037 2.5893 + vertex 0.938312 1.97566 2.58865 + endloop + endfacet + facet normal -0.495788 0.27215 0.8247 + outer loop + vertex 0.938312 1.97566 2.58865 + vertex 0.941973 1.98037 2.5893 + vertex 0.938429 1.98068 2.58707 + endloop + endfacet + facet normal -0.521545 0.27934 0.806201 + outer loop + vertex 0.944378 1.97972 2.59105 + vertex 0.941916 1.97706 2.59038 + vertex 0.94434 1.97649 2.59214 + endloop + endfacet + facet normal -0.452638 0.273175 0.84882 + outer loop + vertex 0.940778 1.98845 2.58576 + vertex 0.936876 1.98563 2.58459 + vertex 0.939175 1.98458 2.58615 + endloop + endfacet + facet normal -0.504816 0.291106 0.812661 + outer loop + vertex 0.939175 1.98458 2.58615 + vertex 0.943204 1.98593 2.58817 + vertex 0.940778 1.98845 2.58576 + endloop + endfacet + facet normal -0.504428 0.287852 0.81406 + outer loop + vertex 0.939175 1.98458 2.58615 + vertex 0.938429 1.98068 2.58707 + vertex 0.943204 1.98593 2.58817 + endloop + endfacet + facet normal -0.494741 0.277016 0.823707 + outer loop + vertex 0.938429 1.98068 2.58707 + vertex 0.941973 1.98037 2.5893 + vertex 0.943204 1.98593 2.58817 + endloop + endfacet + facet normal -0.454553 0.276721 0.846645 + outer loop + vertex 0.938482 1.99091 2.58372 + vertex 0.936876 1.98563 2.58459 + vertex 0.940778 1.98845 2.58576 + endloop + endfacet + facet normal -0.451642 0.279874 0.847166 + outer loop + vertex 0.942316 1.99236 2.58529 + vertex 0.938482 1.99091 2.58372 + vertex 0.940778 1.98845 2.58576 + endloop + endfacet + facet normal -0.505083 0.296495 0.810544 + outer loop + vertex 0.940778 1.98845 2.58576 + vertex 0.94453 1.99145 2.587 + vertex 0.942316 1.99236 2.58529 + endloop + endfacet + facet normal -0.503137 0.293047 0.813005 + outer loop + vertex 0.943204 1.98593 2.58817 + vertex 0.94453 1.99145 2.587 + vertex 0.940778 1.98845 2.58576 + endloop + endfacet + facet normal -0.488812 0.273331 0.828464 + outer loop + vertex 0.942316 1.99236 2.58529 + vertex 0.944825 1.99475 2.58598 + vertex 0.942863 1.99627 2.58432 + endloop + endfacet + facet normal -0.450309 0.27328 0.850023 + outer loop + vertex 0.942316 1.99236 2.58529 + vertex 0.942863 1.99627 2.58432 + vertex 0.938482 1.99091 2.58372 + endloop + endfacet + facet normal -0.450293 0.273265 0.850037 + outer loop + vertex 0.938482 1.99091 2.58372 + vertex 0.942863 1.99627 2.58432 + vertex 0.938545 1.99597 2.58213 + endloop + endfacet + facet normal -0.505368 0.295886 0.810589 + outer loop + vertex 0.944825 1.99475 2.58598 + vertex 0.942316 1.99236 2.58529 + vertex 0.94453 1.99145 2.587 + endloop + endfacet + facet normal -0.428689 0.28983 0.855701 + outer loop + vertex 0.940784 2.00351 2.58072 + vertex 0.936835 2.00055 2.57974 + vertex 0.939163 1.99976 2.58118 + endloop + endfacet + facet normal -0.455274 0.299221 0.838565 + outer loop + vertex 0.939163 1.99976 2.58118 + vertex 0.94296 2.00129 2.58269 + vertex 0.940784 2.00351 2.58072 + endloop + endfacet + facet normal -0.452498 0.286431 0.844513 + outer loop + vertex 0.939163 1.99976 2.58118 + vertex 0.938545 1.99597 2.58213 + vertex 0.94296 2.00129 2.58269 + endloop + endfacet + facet normal -0.449504 0.283681 0.847037 + outer loop + vertex 0.938545 1.99597 2.58213 + vertex 0.942863 1.99627 2.58432 + vertex 0.94296 2.00129 2.58269 + endloop + endfacet + facet normal -0.431983 0.295403 0.852131 + outer loop + vertex 0.93841 2.0057 2.57875 + vertex 0.936835 2.00055 2.57974 + vertex 0.940784 2.00351 2.58072 + endloop + endfacet + facet normal -0.430256 0.297426 0.852301 + outer loop + vertex 0.942417 2.00726 2.58023 + vertex 0.93841 2.0057 2.57875 + vertex 0.940784 2.00351 2.58072 + endloop + endfacet + facet normal -0.462892 0.308866 0.830862 + outer loop + vertex 0.940784 2.00351 2.58072 + vertex 0.944628 2.00645 2.58177 + vertex 0.942417 2.00726 2.58023 + endloop + endfacet + facet normal -0.456517 0.297841 0.838381 + outer loop + vertex 0.94296 2.00129 2.58269 + vertex 0.944628 2.00645 2.58177 + vertex 0.940784 2.00351 2.58072 + endloop + endfacet + facet normal -0.447588 0.289539 0.846069 + outer loop + vertex 0.942417 2.00726 2.58023 + vertex 0.945004 2.00961 2.5808 + vertex 0.942934 2.011 2.57923 + endloop + endfacet + facet normal -0.428512 0.289536 0.855889 + outer loop + vertex 0.942417 2.00726 2.58023 + vertex 0.942934 2.011 2.57923 + vertex 0.93841 2.0057 2.57875 + endloop + endfacet + facet normal -0.429928 0.29085 0.854733 + outer loop + vertex 0.93841 2.0057 2.57875 + vertex 0.942934 2.011 2.57923 + vertex 0.938413 2.01079 2.57703 + endloop + endfacet + facet normal -0.46254 0.309646 0.830768 + outer loop + vertex 0.945004 2.00961 2.5808 + vertex 0.942417 2.00726 2.58023 + vertex 0.944628 2.00645 2.58177 + endloop + endfacet + facet normal -0.452383 0.312056 0.835447 + outer loop + vertex 0.941032 2.0174 2.5761 + vertex 0.937844 2.01654 2.57469 + vertex 0.939356 2.01455 2.57625 + endloop + endfacet + facet normal -0.428484 0.298947 0.852662 + outer loop + vertex 0.939356 2.01455 2.57625 + vertex 0.942881 2.01572 2.57761 + vertex 0.941032 2.0174 2.5761 + endloop + endfacet + facet normal -0.42582 0.283197 0.859347 + outer loop + vertex 0.939356 2.01455 2.57625 + vertex 0.938413 2.01079 2.57703 + vertex 0.942881 2.01572 2.57761 + endloop + endfacet + facet normal -0.430234 0.287625 0.85567 + outer loop + vertex 0.938413 2.01079 2.57703 + vertex 0.942934 2.011 2.57923 + vertex 0.942881 2.01572 2.57761 + endloop + endfacet + facet normal -0.438021 0.313449 0.842548 + outer loop + vertex 0.941032 2.0174 2.5761 + vertex 0.943769 2.01972 2.57666 + vertex 0.94147 2.02068 2.57511 + endloop + endfacet + facet normal -0.45247 0.313099 0.835009 + outer loop + vertex 0.941032 2.0174 2.5761 + vertex 0.94147 2.02068 2.57511 + vertex 0.937844 2.01654 2.57469 + endloop + endfacet + facet normal -0.463628 0.323922 0.824696 + outer loop + vertex 0.937844 2.01654 2.57469 + vertex 0.94147 2.02068 2.57511 + vertex 0.937736 2.02127 2.57278 + endloop + endfacet + facet normal -0.428143 0.299349 0.852692 + outer loop + vertex 0.943769 2.01972 2.57666 + vertex 0.941032 2.0174 2.5761 + vertex 0.942881 2.01572 2.57761 + endloop + endfacet + facet normal -0.463623 0.323936 0.824693 + outer loop + vertex 0.94147 2.02068 2.57511 + vertex 0.943126 2.02585 2.57401 + vertex 0.937736 2.02127 2.57278 + endloop + endfacet + facet normal -0.454669 0.310719 0.834703 + outer loop + vertex 0.937736 2.02127 2.57278 + vertex 0.943126 2.02585 2.57401 + vertex 0.939003 2.02639 2.57156 + endloop + endfacet + facet normal -0.513976 0.322895 0.794712 + outer loop + vertex 0.941785 2.03311 2.57066 + vertex 0.939731 2.0336 2.56914 + vertex 0.939174 2.03039 2.57008 + endloop + endfacet + facet normal -0.472436 0.273796 0.837759 + outer loop + vertex 0.939174 2.03039 2.57008 + vertex 0.94325 2.03095 2.57219 + vertex 0.941785 2.03311 2.57066 + endloop + endfacet + facet normal -0.470522 0.323867 0.820804 + outer loop + vertex 0.939174 2.03039 2.57008 + vertex 0.939003 2.02639 2.57156 + vertex 0.94325 2.03095 2.57219 + endloop + endfacet + facet normal -0.45545 0.307786 0.835364 + outer loop + vertex 0.939003 2.02639 2.57156 + vertex 0.943126 2.02585 2.57401 + vertex 0.94325 2.03095 2.57219 + endloop + endfacet + facet normal -0.448318 0.34691 0.823811 + outer loop + vertex 0.941785 2.03311 2.57066 + vertex 0.944384 2.03485 2.57134 + vertex 0.943019 2.03686 2.56975 + endloop + endfacet + facet normal -0.501577 0.355886 0.788521 + outer loop + vertex 0.941785 2.03311 2.57066 + vertex 0.943019 2.03686 2.56975 + vertex 0.939731 2.0336 2.56914 + endloop + endfacet + facet normal -0.518238 0.376556 0.767877 + outer loop + vertex 0.939731 2.0336 2.56914 + vertex 0.943019 2.03686 2.56975 + vertex 0.93934 2.03671 2.56734 + endloop + endfacet + facet normal -0.429955 0.309896 0.848 + outer loop + vertex 0.944384 2.03485 2.57134 + vertex 0.941785 2.03311 2.57066 + vertex 0.94325 2.03095 2.57219 + endloop + endfacet + facet normal -0.610476 0.340059 0.715318 + outer loop + vertex 0.940614 2.04347 2.5652 + vertex 0.938432 2.04249 2.5638 + vertex 0.938808 2.04034 2.56515 + endloop + endfacet + facet normal -0.551601 0.305076 0.776315 + outer loop + vertex 0.938808 2.04034 2.56515 + vertex 0.942935 2.0414 2.56766 + vertex 0.940614 2.04347 2.5652 + endloop + endfacet + facet normal -0.551001 0.371392 0.747306 + outer loop + vertex 0.938808 2.04034 2.56515 + vertex 0.93934 2.03671 2.56734 + vertex 0.942935 2.0414 2.56766 + endloop + endfacet + facet normal -0.523453 0.34824 0.777641 + outer loop + vertex 0.93934 2.03671 2.56734 + vertex 0.943019 2.03686 2.56975 + vertex 0.942935 2.0414 2.56766 + endloop + endfacet + facet normal -0.613134 0.37328 0.696225 + outer loop + vertex 0.938686 2.0449 2.56274 + vertex 0.938432 2.04249 2.5638 + vertex 0.940614 2.04347 2.5652 + endloop + endfacet + facet normal -0.618441 0.365319 0.695753 + outer loop + vertex 0.941303 2.04728 2.56381 + vertex 0.938686 2.0449 2.56274 + vertex 0.940614 2.04347 2.5652 + endloop + endfacet + facet normal -0.528455 0.373322 0.762473 + outer loop + vertex 0.940614 2.04347 2.5652 + vertex 0.944189 2.04627 2.56631 + vertex 0.941303 2.04728 2.56381 + endloop + endfacet + facet normal -0.516418 0.350509 0.781316 + outer loop + vertex 0.942935 2.0414 2.56766 + vertex 0.944189 2.04627 2.56631 + vertex 0.940614 2.04347 2.5652 + endloop + endfacet + facet normal -0.674957 0.402271 0.618555 + outer loop + vertex 0.941351 2.05249 2.56095 + vertex 0.93828 2.05055 2.55885 + vertex 0.939241 2.04824 2.56141 + endloop + endfacet + facet normal -0.623989 0.376396 0.684809 + outer loop + vertex 0.939241 2.04824 2.56141 + vertex 0.938686 2.0449 2.56274 + vertex 0.941303 2.04728 2.56381 + endloop + endfacet + facet normal -0.620695 0.382498 0.684421 + outer loop + vertex 0.941351 2.05249 2.56095 + vertex 0.939241 2.04824 2.56141 + vertex 0.941303 2.04728 2.56381 + endloop + endfacet + facet normal -0.563609 0.402348 0.721429 + outer loop + vertex 0.941351 2.05249 2.56095 + vertex 0.941303 2.04728 2.56381 + vertex 0.944465 2.05019 2.56466 + endloop + endfacet + facet normal -0.597515 0.353566 0.719699 + outer loop + vertex 0.941351 2.05249 2.56095 + vertex 0.944465 2.05019 2.56466 + vertex 0.945089 2.05337 2.56362 + endloop + endfacet + facet normal -0.535255 0.359056 0.764579 + outer loop + vertex 0.944465 2.05019 2.56466 + vertex 0.941303 2.04728 2.56381 + vertex 0.944189 2.04627 2.56631 + endloop + endfacet + facet normal -0.731186 0.362589 0.577838 + outer loop + vertex 0.939767 2.05694 2.55667 + vertex 0.938004 2.05703 2.55438 + vertex 0.938137 2.0542 2.55632 + endloop + endfacet + facet normal -0.674974 0.402431 0.618433 + outer loop + vertex 0.938137 2.0542 2.55632 + vertex 0.93828 2.05055 2.55885 + vertex 0.941351 2.05249 2.56095 + endloop + endfacet + facet normal -0.706853 0.343042 0.618612 + outer loop + vertex 0.938137 2.0542 2.55632 + vertex 0.941351 2.05249 2.56095 + vertex 0.939767 2.05694 2.55667 + endloop + endfacet + facet normal -0.704362 0.345398 0.620141 + outer loop + vertex 0.939767 2.05694 2.55667 + vertex 0.941351 2.05249 2.56095 + vertex 0.942297 2.05768 2.55913 + endloop + endfacet + facet normal -0.611388 0.358326 0.705554 + outer loop + vertex 0.941351 2.05249 2.56095 + vertex 0.94484 2.05645 2.56196 + vertex 0.942297 2.05768 2.55913 + endloop + endfacet + facet normal -0.598314 0.341938 0.724637 + outer loop + vertex 0.945089 2.05337 2.56362 + vertex 0.94484 2.05645 2.56196 + vertex 0.941351 2.05249 2.56095 + endloop + endfacet + facet normal -0.724453 0.382659 0.573358 + outer loop + vertex 0.938421 2.05973 2.55311 + vertex 0.938004 2.05703 2.55438 + vertex 0.939767 2.05694 2.55667 + endloop + endfacet + facet normal -0.730836 0.37537 0.570067 + outer loop + vertex 0.940914 2.06132 2.55525 + vertex 0.938421 2.05973 2.55311 + vertex 0.939767 2.05694 2.55667 + endloop + endfacet + facet normal -0.636938 0.368436 0.677174 + outer loop + vertex 0.943193 2.06089 2.55822 + vertex 0.942297 2.05768 2.55913 + vertex 0.944655 2.05949 2.56036 + endloop + endfacet + facet normal -0.711608 0.367213 0.598972 + outer loop + vertex 0.943193 2.06089 2.55822 + vertex 0.940914 2.06132 2.55525 + vertex 0.942297 2.05768 2.55913 + endloop + endfacet + facet normal -0.699886 0.378713 0.605587 + outer loop + vertex 0.940914 2.06132 2.55525 + vertex 0.939767 2.05694 2.55667 + vertex 0.942297 2.05768 2.55913 + endloop + endfacet + facet normal -0.624745 0.332665 0.706419 + outer loop + vertex 0.944655 2.05949 2.56036 + vertex 0.942297 2.05768 2.55913 + vertex 0.94484 2.05645 2.56196 + endloop + endfacet + facet normal -0.727915 0.400185 0.556768 + outer loop + vertex 0.940968 2.06732 2.55107 + vertex 0.938232 2.06584 2.54856 + vertex 0.939107 2.06333 2.55151 + endloop + endfacet + facet normal -0.731187 0.388461 0.56077 + outer loop + vertex 0.939107 2.06333 2.55151 + vertex 0.938421 2.05973 2.55311 + vertex 0.940914 2.06132 2.55525 + endloop + endfacet + facet normal -0.723872 0.398969 0.56288 + outer loop + vertex 0.940968 2.06732 2.55107 + vertex 0.939107 2.06333 2.55151 + vertex 0.940914 2.06132 2.55525 + endloop + endfacet + facet normal -0.703351 0.410804 0.580119 + outer loop + vertex 0.940968 2.06732 2.55107 + vertex 0.940914 2.06132 2.55525 + vertex 0.943282 2.0643 2.55601 + endloop + endfacet + facet normal -0.708295 0.404457 0.57856 + outer loop + vertex 0.940968 2.06732 2.55107 + vertex 0.943282 2.0643 2.55601 + vertex 0.943505 2.06706 2.55436 + endloop + endfacet + facet normal -0.697243 0.402665 0.593054 + outer loop + vertex 0.943282 2.0643 2.55601 + vertex 0.940914 2.06132 2.55525 + vertex 0.943193 2.06089 2.55822 + endloop + endfacet + facet normal -0.721335 0.395938 0.568251 + outer loop + vertex 0.939668 2.07297 2.54541 + vertex 0.937775 2.07227 2.54349 + vertex 0.938061 2.06945 2.54582 + endloop + endfacet + facet normal -0.728315 0.39215 0.561938 + outer loop + vertex 0.938061 2.06945 2.54582 + vertex 0.938232 2.06584 2.54856 + vertex 0.940968 2.06732 2.55107 + endloop + endfacet + facet normal -0.725361 0.397078 0.562299 + outer loop + vertex 0.938061 2.06945 2.54582 + vertex 0.940968 2.06732 2.55107 + vertex 0.939668 2.07297 2.54541 + endloop + endfacet + facet normal -0.71131 0.409388 0.571348 + outer loop + vertex 0.939668 2.07297 2.54541 + vertex 0.940968 2.06732 2.55107 + vertex 0.942397 2.07252 2.54912 + endloop + endfacet + facet normal -0.703344 0.410552 0.580305 + outer loop + vertex 0.940968 2.06732 2.55107 + vertex 0.943921 2.06977 2.55292 + vertex 0.942397 2.07252 2.54912 + endloop + endfacet + facet normal -0.704244 0.4147 0.57625 + outer loop + vertex 0.943505 2.06706 2.55436 + vertex 0.943921 2.06977 2.55292 + vertex 0.940968 2.06732 2.55107 + endloop + endfacet + facet normal -0.726081 0.40533 0.555441 + outer loop + vertex 0.939215 2.07733 2.5417 + vertex 0.937636 2.07743 2.53956 + vertex 0.93761 2.07487 2.54139 + endloop + endfacet + facet normal -0.719589 0.407289 0.562412 + outer loop + vertex 0.93761 2.07487 2.54139 + vertex 0.937775 2.07227 2.54349 + vertex 0.939668 2.07297 2.54541 + endloop + endfacet + facet normal -0.722832 0.402417 0.56176 + outer loop + vertex 0.93761 2.07487 2.54139 + vertex 0.939668 2.07297 2.54541 + vertex 0.939215 2.07733 2.5417 + endloop + endfacet + facet normal -0.710538 0.411418 0.570851 + outer loop + vertex 0.939215 2.07733 2.5417 + vertex 0.939668 2.07297 2.54541 + vertex 0.94181 2.07698 2.54518 + endloop + endfacet + facet normal -0.70536 0.410383 0.577972 + outer loop + vertex 0.943766 2.07543 2.54873 + vertex 0.942397 2.07252 2.54912 + vertex 0.944488 2.07313 2.55124 + endloop + endfacet + facet normal -0.710068 0.411683 0.571244 + outer loop + vertex 0.943766 2.07543 2.54873 + vertex 0.94181 2.07698 2.54518 + vertex 0.942397 2.07252 2.54912 + endloop + endfacet + facet normal -0.710464 0.411385 0.570967 + outer loop + vertex 0.94181 2.07698 2.54518 + vertex 0.939668 2.07297 2.54541 + vertex 0.942397 2.07252 2.54912 + endloop + endfacet + facet normal -0.705874 0.407694 0.579248 + outer loop + vertex 0.944488 2.07313 2.55124 + vertex 0.942397 2.07252 2.54912 + vertex 0.943921 2.06977 2.55292 + endloop + endfacet + facet normal -0.712732 0.438838 0.547205 + outer loop + vertex 0.93821 2.08001 2.53824 + vertex 0.937636 2.07743 2.53956 + vertex 0.939215 2.07733 2.5417 + endloop + endfacet + facet normal -0.723237 0.428078 0.541919 + outer loop + vertex 0.940708 2.08152 2.54038 + vertex 0.93821 2.08001 2.53824 + vertex 0.939215 2.07733 2.5417 + endloop + endfacet + facet normal -0.713176 0.414248 0.56549 + outer loop + vertex 0.943062 2.08076 2.54399 + vertex 0.94181 2.07698 2.54518 + vertex 0.944108 2.07839 2.54705 + endloop + endfacet + facet normal -0.720233 0.413834 0.556781 + outer loop + vertex 0.943062 2.08076 2.54399 + vertex 0.940708 2.08152 2.54038 + vertex 0.94181 2.07698 2.54518 + endloop + endfacet + facet normal -0.703164 0.428885 0.567113 + outer loop + vertex 0.940708 2.08152 2.54038 + vertex 0.939215 2.07733 2.5417 + vertex 0.94181 2.07698 2.54518 + endloop + endfacet + facet normal -0.713074 0.406995 0.570859 + outer loop + vertex 0.944108 2.07839 2.54705 + vertex 0.94181 2.07698 2.54518 + vertex 0.943766 2.07543 2.54873 + endloop + endfacet + facet normal -0.77321 0.42622 0.469555 + outer loop + vertex 0.940999 2.08739 2.53618 + vertex 0.938761 2.08588 2.53386 + vertex 0.939101 2.08352 2.53656 + endloop + endfacet + facet normal -0.722851 0.43837 0.534152 + outer loop + vertex 0.939101 2.08352 2.53656 + vertex 0.93821 2.08001 2.53824 + vertex 0.940708 2.08152 2.54038 + endloop + endfacet + facet normal -0.739604 0.415689 0.529328 + outer loop + vertex 0.940999 2.08739 2.53618 + vertex 0.939101 2.08352 2.53656 + vertex 0.940708 2.08152 2.54038 + endloop + endfacet + facet normal -0.718531 0.428104 0.548125 + outer loop + vertex 0.940999 2.08739 2.53618 + vertex 0.940708 2.08152 2.54038 + vertex 0.943013 2.08446 2.54111 + endloop + endfacet + facet normal -0.725205 0.419683 0.545842 + outer loop + vertex 0.940999 2.08739 2.53618 + vertex 0.943013 2.08446 2.54111 + vertex 0.943008 2.08727 2.53894 + endloop + endfacet + facet normal -0.715334 0.423708 0.555669 + outer loop + vertex 0.943013 2.08446 2.54111 + vertex 0.940708 2.08152 2.54038 + vertex 0.943062 2.08076 2.54399 + endloop + endfacet + facet normal -0.868357 0.266216 0.418432 + outer loop + vertex 0.940062 2.09215 2.53182 + vertex 0.938692 2.09113 2.52962 + vertex 0.939183 2.08872 2.53218 + endloop + endfacet + facet normal -0.7751 0.403772 0.485992 + outer loop + vertex 0.939183 2.08872 2.53218 + vertex 0.938761 2.08588 2.53386 + vertex 0.940999 2.08739 2.53618 + endloop + endfacet + facet normal -0.841884 0.264904 0.470167 + outer loop + vertex 0.939183 2.08872 2.53218 + vertex 0.940999 2.08739 2.53618 + vertex 0.940062 2.09215 2.53182 + endloop + endfacet + facet normal -0.794933 0.317183 0.517181 + outer loop + vertex 0.940062 2.09215 2.53182 + vertex 0.940999 2.08739 2.53618 + vertex 0.942042 2.09281 2.53446 + endloop + endfacet + facet normal -0.73158 0.330146 0.596485 + outer loop + vertex 0.940999 2.08739 2.53618 + vertex 0.943428 2.08996 2.53774 + vertex 0.942042 2.09281 2.53446 + endloop + endfacet + facet normal -0.744822 0.366168 0.557817 + outer loop + vertex 0.943008 2.08727 2.53894 + vertex 0.943428 2.08996 2.53774 + vertex 0.940999 2.08739 2.53618 + endloop + endfacet + facet normal -0.867104 0.130718 0.480671 + outer loop + vertex 0.938713 2.09541 2.5285 + vertex 0.938692 2.09113 2.52962 + vertex 0.940062 2.09215 2.53182 + endloop + endfacet + facet normal -0.875662 0.115252 0.46897 + outer loop + vertex 0.94057 2.09738 2.53148 + vertex 0.938713 2.09541 2.5285 + vertex 0.940062 2.09215 2.53182 + endloop + endfacet + facet normal -0.753721 0.200466 0.625873 + outer loop + vertex 0.943004 2.09642 2.53446 + vertex 0.942042 2.09281 2.53446 + vertex 0.944007 2.09357 2.53658 + endloop + endfacet + facet normal -0.72832 0.193713 0.657287 + outer loop + vertex 0.943004 2.09642 2.53446 + vertex 0.94057 2.09738 2.53148 + vertex 0.942042 2.09281 2.53446 + endloop + endfacet + facet normal -0.808465 0.115652 0.577069 + outer loop + vertex 0.94057 2.09738 2.53148 + vertex 0.940062 2.09215 2.53182 + vertex 0.942042 2.09281 2.53446 + endloop + endfacet + facet normal -0.750687 0.3074 0.584786 + outer loop + vertex 0.944007 2.09357 2.53658 + vertex 0.942042 2.09281 2.53446 + vertex 0.943428 2.08996 2.53774 + endloop + endfacet + facet normal -0.806675 -0.117163 0.579265 + outer loop + vertex 0.937442 2.10132 2.52792 + vertex 0.938713 2.09541 2.5285 + vertex 0.94057 2.09738 2.53148 + endloop + endfacet + facet normal -0.776938 -0.0498245 0.627602 + outer loop + vertex 0.93986 2.1022 2.53098 + vertex 0.937442 2.10132 2.52792 + vertex 0.94057 2.09738 2.53148 + endloop + endfacet + facet normal -0.698764 -0.0293802 0.714748 + outer loop + vertex 0.94057 2.09738 2.53148 + vertex 0.942667 2.10121 2.53369 + vertex 0.93986 2.1022 2.53098 + endloop + endfacet + facet normal -0.765533 0.0494454 0.641494 + outer loop + vertex 0.943004 2.09642 2.53446 + vertex 0.942667 2.10121 2.53369 + vertex 0.94057 2.09738 2.53148 + endloop + endfacet + facet normal -0.736444 -0.21165 0.642537 + outer loop + vertex 0.937442 2.10132 2.52792 + vertex 0.93986 2.1022 2.53098 + vertex 0.938245 2.10491 2.53003 + endloop + endfacet + facet normal -0.622114 -0.0957744 0.777047 + outer loop + vertex 0.93986 2.1022 2.53098 + vertex 0.94065 2.10599 2.53208 + vertex 0.938245 2.10491 2.53003 + endloop + endfacet + facet normal -0.703252 -0.0589583 0.708492 + outer loop + vertex 0.93986 2.1022 2.53098 + vertex 0.942667 2.10121 2.53369 + vertex 0.94065 2.10599 2.53208 + endloop + endfacet + facet normal -0.581846 0.0272927 0.812841 + outer loop + vertex 0.942667 2.10121 2.53369 + vertex 0.943501 2.10578 2.53413 + vertex 0.94065 2.10599 2.53208 + endloop + endfacet + facet normal -0.560367 0.245585 0.790997 + outer loop + vertex 0.940912 2.11211 2.53142 + vertex 0.937897 2.11129 2.52954 + vertex 0.939995 2.10954 2.53157 + endloop + endfacet + facet normal -0.492014 0.224051 0.841263 + outer loop + vertex 0.939995 2.10954 2.53157 + vertex 0.942819 2.10985 2.53314 + vertex 0.940912 2.11211 2.53142 + endloop + endfacet + facet normal -0.488721 0.0367087 0.871667 + outer loop + vertex 0.939995 2.10954 2.53157 + vertex 0.94065 2.10599 2.53208 + vertex 0.942819 2.10985 2.53314 + endloop + endfacet + facet normal -0.575486 0.101911 0.811437 + outer loop + vertex 0.94065 2.10599 2.53208 + vertex 0.943501 2.10578 2.53413 + vertex 0.942819 2.10985 2.53314 + endloop + endfacet + facet normal -0.493926 0.456156 0.740243 + outer loop + vertex 0.940912 2.11211 2.53142 + vertex 0.943224 2.11355 2.53207 + vertex 0.940885 2.11537 2.52939 + endloop + endfacet + facet normal -0.559031 0.434445 0.706216 + outer loop + vertex 0.940912 2.11211 2.53142 + vertex 0.940885 2.11537 2.52939 + vertex 0.937897 2.11129 2.52954 + endloop + endfacet + facet normal -0.496663 0.391163 0.774802 + outer loop + vertex 0.937897 2.11129 2.52954 + vertex 0.940885 2.11537 2.52939 + vertex 0.936751 2.11507 2.52689 + endloop + endfacet + facet normal -0.424652 0.292568 0.856782 + outer loop + vertex 0.943224 2.11355 2.53207 + vertex 0.940912 2.11211 2.53142 + vertex 0.942819 2.10985 2.53314 + endloop + endfacet + facet normal -0.39344 0.705066 0.589989 + outer loop + vertex 0.939024 2.11864 2.52535 + vertex 0.94257 2.1187 2.52764 + vertex 0.941495 2.12089 2.5243 + endloop + endfacet + facet normal -0.378202 0.697146 0.609057 + outer loop + vertex 0.938998 2.12074 2.52292 + vertex 0.939024 2.11864 2.52535 + vertex 0.941495 2.12089 2.5243 + endloop + endfacet + facet normal -0.450949 0.581511 0.677118 + outer loop + vertex 0.940885 2.11537 2.52939 + vertex 0.939024 2.11864 2.52535 + vertex 0.936751 2.11507 2.52689 + endloop + endfacet + facet normal -0.44803 0.583477 0.677365 + outer loop + vertex 0.94257 2.1187 2.52764 + vertex 0.939024 2.11864 2.52535 + vertex 0.940885 2.11537 2.52939 + endloop + endfacet + facet normal 0.203838 -0.30162 0.931384 + outer loop + vertex 0.942999 2.12786 2.51418 + vertex 0.942412 2.13 2.515 + vertex 0.94 2.12837 2.515 + endloop + endfacet + facet normal 0.277986 0.813074 0.511502 + outer loop + vertex 0.942999 2.12786 2.51418 + vertex 0.94 2.12837 2.515 + vertex 0.943725 2.12584 2.51699 + endloop + endfacet + facet normal -0.194138 0.415146 0.888799 + outer loop + vertex 0.943725 2.12584 2.51699 + vertex 0.94 2.12837 2.515 + vertex 0.939082 2.12427 2.51671 + endloop + endfacet + facet normal -0.310783 0.83837 0.447828 + outer loop + vertex 0.943725 2.12584 2.51699 + vertex 0.939082 2.12427 2.51671 + vertex 0.943722 2.12316 2.52201 + endloop + endfacet + facet normal -0.32336 0.828709 0.456815 + outer loop + vertex 0.943722 2.12316 2.52201 + vertex 0.939082 2.12427 2.51671 + vertex 0.938988 2.1221 2.52058 + endloop + endfacet + facet normal -0.313265 0.820304 0.478505 + outer loop + vertex 0.941495 2.12089 2.5243 + vertex 0.938988 2.1221 2.52058 + vertex 0.938998 2.12074 2.52292 + endloop + endfacet + facet normal -0.327882 0.810604 0.485195 + outer loop + vertex 0.943722 2.12316 2.52201 + vertex 0.938988 2.1221 2.52058 + vertex 0.941495 2.12089 2.5243 + endloop + endfacet + facet normal -0.399758 0.806138 0.436274 + outer loop + vertex 0.942412 2.13 2.515 + vertex 0.94 2.13151 2.51 + vertex 0.94 2.13 2.51279 + endloop + endfacet + facet normal -0.412882 0.79746 0.439984 + outer loop + vertex 0.942412 2.13 2.515 + vertex 0.945 2.13134 2.515 + vertex 0.94 2.13151 2.51 + endloop + endfacet + facet normal -0.132882 0.977115 0.166098 + outer loop + vertex 0.945 2.13134 2.515 + vertex 0.945 2.13219 2.51 + vertex 0.94 2.13151 2.51 + endloop + endfacet + facet normal 0.162765 -0.314373 0.935242 + outer loop + vertex 0.945 2.13134 2.515 + vertex 0.942412 2.13 2.515 + vertex 0.942999 2.12786 2.51418 + endloop + endfacet + facet normal -0.267165 -0.952825 -0.144036 + outer loop + vertex 0.95 0.896515 2.515 + vertex 0.948888 0.89651 2.5171 + vertex 0.945 0.897917 2.515 + endloop + endfacet + facet normal -0.144578 -0.924565 -0.35253 + outer loop + vertex 0.948888 0.89651 2.5171 + vertex 0.943217 0.897618 2.51652 + vertex 0.945 0.897917 2.515 + endloop + endfacet + facet normal -0.255195 -0.918229 0.302872 + outer loop + vertex 0.94406 0.898271 2.52022 + vertex 0.948075 0.897431 2.52106 + vertex 0.946277 0.89855 2.52294 + endloop + endfacet + facet normal -0.243717 -0.944169 0.221691 + outer loop + vertex 0.94406 0.898271 2.52022 + vertex 0.943217 0.897618 2.51652 + vertex 0.948075 0.897431 2.52106 + endloop + endfacet + facet normal -0.20637 -0.961576 0.181062 + outer loop + vertex 0.943217 0.897618 2.51652 + vertex 0.948888 0.89651 2.5171 + vertex 0.948075 0.897431 2.52106 + endloop + endfacet + facet normal -0.25941 -0.918348 0.298903 + outer loop + vertex 0.948075 0.897431 2.52106 + vertex 0.94918 0.898316 2.52474 + vertex 0.946277 0.89855 2.52294 + endloop + endfacet + facet normal -0.350299 -0.858521 0.374476 + outer loop + vertex 0.94406 0.898271 2.52022 + vertex 0.946277 0.89855 2.52294 + vertex 0.943044 0.899587 2.52229 + endloop + endfacet + facet normal -0.349772 -0.817514 0.457527 + outer loop + vertex 0.946277 0.89855 2.52294 + vertex 0.94918 0.898316 2.52474 + vertex 0.947388 0.899835 2.52608 + endloop + endfacet + facet normal -0.35328 -0.81572 0.458033 + outer loop + vertex 0.946277 0.89855 2.52294 + vertex 0.947388 0.899835 2.52608 + vertex 0.943044 0.899587 2.52229 + endloop + endfacet + facet normal -0.409491 -0.750877 0.518171 + outer loop + vertex 0.943044 0.899587 2.52229 + vertex 0.947388 0.899835 2.52608 + vertex 0.942383 0.902021 2.5253 + endloop + endfacet + facet normal -0.426743 -0.637282 0.641687 + outer loop + vertex 0.942112 0.90486 2.52824 + vertex 0.946535 0.902528 2.52887 + vertex 0.945033 0.905178 2.5305 + endloop + endfacet + facet normal -0.437095 -0.667261 0.603084 + outer loop + vertex 0.942112 0.90486 2.52824 + vertex 0.942383 0.902021 2.5253 + vertex 0.946535 0.902528 2.52887 + endloop + endfacet + facet normal -0.402561 -0.716366 0.569882 + outer loop + vertex 0.942383 0.902021 2.5253 + vertex 0.947388 0.899835 2.52608 + vertex 0.946535 0.902528 2.52887 + endloop + endfacet + facet normal -0.419758 -0.636579 0.64697 + outer loop + vertex 0.946535 0.902528 2.52887 + vertex 0.94869 0.904244 2.53195 + vertex 0.945033 0.905178 2.5305 + endloop + endfacet + facet normal -0.454737 -0.586 0.670685 + outer loop + vertex 0.942112 0.90486 2.52824 + vertex 0.945033 0.905178 2.5305 + vertex 0.942239 0.907156 2.53033 + endloop + endfacet + facet normal -0.400346 -0.501132 0.767196 + outer loop + vertex 0.945033 0.905178 2.5305 + vertex 0.944564 0.908197 2.53222 + vertex 0.942239 0.907156 2.53033 + endloop + endfacet + facet normal -0.427175 -0.4981 0.754598 + outer loop + vertex 0.945033 0.905178 2.5305 + vertex 0.94869 0.904244 2.53195 + vertex 0.944564 0.908197 2.53222 + endloop + endfacet + facet normal -0.463788 -0.533068 0.70763 + outer loop + vertex 0.94869 0.904244 2.53195 + vertex 0.949278 0.907281 2.53463 + vertex 0.944564 0.908197 2.53222 + endloop + endfacet + facet normal -0.54012 -0.28132 0.793177 + outer loop + vertex 0.948939 0.910695 2.53635 + vertex 0.946534 0.915048 2.53626 + vertex 0.945241 0.911836 2.53424 + endloop + endfacet + facet normal -0.544485 -0.421127 0.725388 + outer loop + vertex 0.948939 0.910695 2.53635 + vertex 0.945241 0.911836 2.53424 + vertex 0.949278 0.907281 2.53463 + endloop + endfacet + facet normal -0.477967 -0.355577 0.803189 + outer loop + vertex 0.949278 0.907281 2.53463 + vertex 0.945241 0.911836 2.53424 + vertex 0.944564 0.908197 2.53222 + endloop + endfacet + facet normal -0.58728 -0.308352 0.748346 + outer loop + vertex 0.948939 0.910695 2.53635 + vertex 0.950022 0.913247 2.53825 + vertex 0.946534 0.915048 2.53626 + endloop + endfacet + facet normal -0.625653 -0.218945 0.748747 + outer loop + vertex 0.942682 0.917019 2.53362 + vertex 0.945241 0.911836 2.53424 + vertex 0.946534 0.915048 2.53626 + endloop + endfacet + facet normal -0.618437 -0.184624 0.763839 + outer loop + vertex 0.945491 0.919711 2.53654 + vertex 0.942682 0.917019 2.53362 + vertex 0.946534 0.915048 2.53626 + endloop + endfacet + facet normal -0.638598 -0.188065 0.746207 + outer loop + vertex 0.946534 0.915048 2.53626 + vertex 0.948509 0.917488 2.53856 + vertex 0.945491 0.919711 2.53654 + endloop + endfacet + facet normal -0.577678 -0.262573 0.77288 + outer loop + vertex 0.950022 0.913247 2.53825 + vertex 0.948509 0.917488 2.53856 + vertex 0.946534 0.915048 2.53626 + endloop + endfacet + facet normal -0.6957 -0.0524718 0.716413 + outer loop + vertex 0.94274 0.922241 2.53406 + vertex 0.942682 0.917019 2.53362 + vertex 0.945491 0.919711 2.53654 + endloop + endfacet + facet normal -0.732276 -0.141661 0.666111 + outer loop + vertex 0.945475 0.924721 2.53759 + vertex 0.94274 0.922241 2.53406 + vertex 0.945491 0.919711 2.53654 + endloop + endfacet + facet normal -0.670601 -0.153929 0.725673 + outer loop + vertex 0.945491 0.919711 2.53654 + vertex 0.94799 0.921492 2.53923 + vertex 0.945475 0.924721 2.53759 + endloop + endfacet + facet normal -0.64485 -0.205765 0.73609 + outer loop + vertex 0.948509 0.917488 2.53856 + vertex 0.94799 0.921492 2.53923 + vertex 0.945491 0.919711 2.53654 + endloop + endfacet + facet normal -0.760682 -0.0792317 0.644271 + outer loop + vertex 0.942687 0.926962 2.53457 + vertex 0.94274 0.922241 2.53406 + vertex 0.945475 0.924721 2.53759 + endloop + endfacet + facet normal -0.791035 -0.211548 0.574031 + outer loop + vertex 0.944369 0.929102 2.53768 + vertex 0.942687 0.926962 2.53457 + vertex 0.945475 0.924721 2.53759 + endloop + endfacet + facet normal -0.712153 -0.215488 0.668134 + outer loop + vertex 0.9486 0.924714 2.54092 + vertex 0.945475 0.924721 2.53759 + vertex 0.94799 0.921492 2.53923 + endloop + endfacet + facet normal -0.70442 -0.25916 0.660779 + outer loop + vertex 0.9486 0.924714 2.54092 + vertex 0.946791 0.928538 2.54049 + vertex 0.945475 0.924721 2.53759 + endloop + endfacet + facet normal -0.761307 -0.204895 0.615167 + outer loop + vertex 0.946791 0.928538 2.54049 + vertex 0.944369 0.929102 2.53768 + vertex 0.945475 0.924721 2.53759 + endloop + endfacet + facet normal -0.737443 -0.279967 0.614651 + outer loop + vertex 0.9486 0.924714 2.54092 + vertex 0.949683 0.92782 2.54363 + vertex 0.946791 0.928538 2.54049 + endloop + endfacet + facet normal -0.79183 -0.210102 0.573465 + outer loop + vertex 0.942687 0.926962 2.53457 + vertex 0.944369 0.929102 2.53768 + vertex 0.942593 0.930572 2.53577 + endloop + endfacet + facet normal -0.801349 -0.280007 0.528617 + outer loop + vertex 0.943599 0.932073 2.53809 + vertex 0.942593 0.930572 2.53577 + vertex 0.944369 0.929102 2.53768 + endloop + endfacet + facet normal -0.766333 -0.277865 0.579245 + outer loop + vertex 0.943599 0.932073 2.53809 + vertex 0.944369 0.929102 2.53768 + vertex 0.945251 0.931526 2.54001 + endloop + endfacet + facet normal -0.752464 -0.293081 0.589831 + outer loop + vertex 0.945251 0.931526 2.54001 + vertex 0.944369 0.929102 2.53768 + vertex 0.946791 0.928538 2.54049 + endloop + endfacet + facet normal -0.766383 -0.304115 0.565837 + outer loop + vertex 0.946791 0.928538 2.54049 + vertex 0.947327 0.932879 2.54355 + vertex 0.945251 0.931526 2.54001 + endloop + endfacet + facet normal -0.730911 -0.330533 0.597091 + outer loop + vertex 0.949683 0.92782 2.54363 + vertex 0.947327 0.932879 2.54355 + vertex 0.946791 0.928538 2.54049 + endloop + endfacet + facet normal -0.758068 -0.346291 0.552644 + outer loop + vertex 0.943599 0.932073 2.53809 + vertex 0.945251 0.931526 2.54001 + vertex 0.944244 0.934607 2.54056 + endloop + endfacet + facet normal -0.729234 -0.387753 0.563795 + outer loop + vertex 0.947 0.936712 2.5456 + vertex 0.946034 0.938501 2.54558 + vertex 0.945273 0.937174 2.54368 + endloop + endfacet + facet normal -0.732953 -0.368603 0.571762 + outer loop + vertex 0.947327 0.932879 2.54355 + vertex 0.947 0.936712 2.5456 + vertex 0.945273 0.937174 2.54368 + endloop + endfacet + facet normal -0.745124 -0.373808 0.552321 + outer loop + vertex 0.947327 0.932879 2.54355 + vertex 0.945273 0.937174 2.54368 + vertex 0.944244 0.934607 2.54056 + endloop + endfacet + facet normal -0.745882 -0.345336 0.569564 + outer loop + vertex 0.947327 0.932879 2.54355 + vertex 0.944244 0.934607 2.54056 + vertex 0.945251 0.931526 2.54001 + endloop + endfacet + facet normal -0.738448 -0.392893 0.548023 + outer loop + vertex 0.947 0.936712 2.5456 + vertex 0.947225 0.939063 2.54759 + vertex 0.946034 0.938501 2.54558 + endloop + endfacet + facet normal -0.710455 -0.410096 0.571904 + outer loop + vertex 0.945273 0.937174 2.54368 + vertex 0.946034 0.938501 2.54558 + vertex 0.944738 0.940312 2.54527 + endloop + endfacet + facet normal -0.716679 -0.397109 0.573302 + outer loop + vertex 0.948555 0.941079 2.55071 + vertex 0.946385 0.945358 2.55096 + vertex 0.945277 0.943106 2.54801 + endloop + endfacet + facet normal -0.716836 -0.404836 0.567674 + outer loop + vertex 0.947225 0.939063 2.54759 + vertex 0.948555 0.941079 2.55071 + vertex 0.945277 0.943106 2.54801 + endloop + endfacet + facet normal -0.723875 -0.407111 0.557015 + outer loop + vertex 0.947225 0.939063 2.54759 + vertex 0.945277 0.943106 2.54801 + vertex 0.944738 0.940312 2.54527 + endloop + endfacet + facet normal -0.722451 -0.422972 0.546954 + outer loop + vertex 0.947225 0.939063 2.54759 + vertex 0.944738 0.940312 2.54527 + vertex 0.946034 0.938501 2.54558 + endloop + endfacet + facet normal -0.698093 -0.389319 0.600913 + outer loop + vertex 0.948555 0.941079 2.55071 + vertex 0.949991 0.943039 2.55364 + vertex 0.946385 0.945358 2.55096 + endloop + endfacet + facet normal -0.717419 -0.396283 0.572948 + outer loop + vertex 0.94273 0.947874 2.54812 + vertex 0.945277 0.943106 2.54801 + vertex 0.946385 0.945358 2.55096 + endloop + endfacet + facet normal -0.717128 -0.392591 0.575847 + outer loop + vertex 0.944901 0.948224 2.55106 + vertex 0.94273 0.947874 2.54812 + vertex 0.946385 0.945358 2.55096 + endloop + endfacet + facet normal -0.701946 -0.385579 0.598832 + outer loop + vertex 0.946385 0.945358 2.55096 + vertex 0.947349 0.947965 2.55377 + vertex 0.944901 0.948224 2.55106 + endloop + endfacet + facet normal -0.69809 -0.38928 0.600943 + outer loop + vertex 0.949991 0.943039 2.55364 + vertex 0.947349 0.947965 2.55377 + vertex 0.946385 0.945358 2.55096 + endloop + endfacet + facet normal -0.722527 -0.378984 0.57821 + outer loop + vertex 0.94273 0.947874 2.54812 + vertex 0.944901 0.948224 2.55106 + vertex 0.943599 0.95103 2.55128 + endloop + endfacet + facet normal -0.689597 -0.39757 0.605305 + outer loop + vertex 0.948176 0.950447 2.5562 + vertex 0.9466 0.952942 2.55605 + vertex 0.945288 0.952331 2.55415 + endloop + endfacet + facet normal -0.687532 -0.37916 0.619304 + outer loop + vertex 0.947349 0.947965 2.55377 + vertex 0.948176 0.950447 2.5562 + vertex 0.945288 0.952331 2.55415 + endloop + endfacet + facet normal -0.708234 -0.386422 0.590833 + outer loop + vertex 0.947349 0.947965 2.55377 + vertex 0.945288 0.952331 2.55415 + vertex 0.943599 0.95103 2.55128 + endloop + endfacet + facet normal -0.705228 -0.372838 0.60303 + outer loop + vertex 0.947349 0.947965 2.55377 + vertex 0.943599 0.95103 2.55128 + vertex 0.944901 0.948224 2.55106 + endloop + endfacet + facet normal -0.661362 -0.377029 0.648421 + outer loop + vertex 0.948176 0.950447 2.5562 + vertex 0.948441 0.953497 2.55825 + vertex 0.9466 0.952942 2.55605 + endloop + endfacet + facet normal -0.700683 -0.376353 0.606136 + outer loop + vertex 0.945288 0.952331 2.55415 + vertex 0.9466 0.952942 2.55605 + vertex 0.944894 0.955382 2.55559 + endloop + endfacet + facet normal -0.65911 -0.36646 0.65672 + outer loop + vertex 0.948247 0.956823 2.55997 + vertex 0.946734 0.960291 2.56039 + vertex 0.945507 0.958086 2.55793 + endloop + endfacet + facet normal -0.659316 -0.37613 0.651022 + outer loop + vertex 0.948441 0.953497 2.55825 + vertex 0.948247 0.956823 2.55997 + vertex 0.945507 0.958086 2.55793 + endloop + endfacet + facet normal -0.675776 -0.388363 0.6265 + outer loop + vertex 0.948441 0.953497 2.55825 + vertex 0.945507 0.958086 2.55793 + vertex 0.944894 0.955382 2.55559 + endloop + endfacet + facet normal -0.673584 -0.348915 0.651569 + outer loop + vertex 0.948441 0.953497 2.55825 + vertex 0.944894 0.955382 2.55559 + vertex 0.9466 0.952942 2.55605 + endloop + endfacet + facet normal -0.590826 -0.345375 0.729137 + outer loop + vertex 0.948247 0.956823 2.55997 + vertex 0.950274 0.957531 2.56195 + vertex 0.946734 0.960291 2.56039 + endloop + endfacet + facet normal -0.668198 -0.356969 0.652751 + outer loop + vertex 0.942953 0.962807 2.55789 + vertex 0.945507 0.958086 2.55793 + vertex 0.946734 0.960291 2.56039 + endloop + endfacet + facet normal -0.67156 -0.376446 0.638198 + outer loop + vertex 0.945447 0.963074 2.56068 + vertex 0.942953 0.962807 2.55789 + vertex 0.946734 0.960291 2.56039 + endloop + endfacet + facet normal -0.598733 -0.351206 0.719843 + outer loop + vertex 0.946734 0.960291 2.56039 + vertex 0.94852 0.962901 2.56315 + vertex 0.945447 0.963074 2.56068 + endloop + endfacet + facet normal -0.594897 -0.355148 0.721088 + outer loop + vertex 0.950274 0.957531 2.56195 + vertex 0.94852 0.962901 2.56315 + vertex 0.946734 0.960291 2.56039 + endloop + endfacet + facet normal -0.672222 -0.374558 0.63861 + outer loop + vertex 0.942953 0.962807 2.55789 + vertex 0.945447 0.963074 2.56068 + vertex 0.943953 0.965919 2.56077 + endloop + endfacet + facet normal -0.57237 -0.369329 0.732113 + outer loop + vertex 0.948331 0.966976 2.56504 + vertex 0.946472 0.970789 2.56551 + vertex 0.945168 0.968366 2.56326 + endloop + endfacet + facet normal -0.572059 -0.366512 0.733769 + outer loop + vertex 0.94852 0.962901 2.56315 + vertex 0.948331 0.966976 2.56504 + vertex 0.945168 0.968366 2.56326 + endloop + endfacet + facet normal -0.614886 -0.39174 0.684438 + outer loop + vertex 0.94852 0.962901 2.56315 + vertex 0.945168 0.968366 2.56326 + vertex 0.943953 0.965919 2.56077 + endloop + endfacet + facet normal -0.60094 -0.340002 0.723374 + outer loop + vertex 0.94852 0.962901 2.56315 + vertex 0.943953 0.965919 2.56077 + vertex 0.945447 0.963074 2.56068 + endloop + endfacet + facet normal -0.496363 -0.340473 0.798562 + outer loop + vertex 0.948331 0.966976 2.56504 + vertex 0.950744 0.968349 2.56712 + vertex 0.946472 0.970789 2.56551 + endloop + endfacet + facet normal -0.582123 -0.360863 0.728636 + outer loop + vertex 0.942338 0.973363 2.56348 + vertex 0.945168 0.968366 2.56326 + vertex 0.946472 0.970789 2.56551 + endloop + endfacet + facet normal -0.589871 -0.390523 0.706784 + outer loop + vertex 0.944595 0.974386 2.56593 + vertex 0.942338 0.973363 2.56348 + vertex 0.946472 0.970789 2.56551 + endloop + endfacet + facet normal -0.506148 -0.356023 0.785533 + outer loop + vertex 0.946472 0.970789 2.56551 + vertex 0.947701 0.973547 2.56755 + vertex 0.944595 0.974386 2.56593 + endloop + endfacet + facet normal -0.502308 -0.358667 0.786794 + outer loop + vertex 0.950744 0.968349 2.56712 + vertex 0.947701 0.973547 2.56755 + vertex 0.946472 0.970789 2.56551 + endloop + endfacet + facet normal -0.580367 -0.407455 0.705092 + outer loop + vertex 0.942338 0.973363 2.56348 + vertex 0.944595 0.974386 2.56593 + vertex 0.942401 0.976476 2.56533 + endloop + endfacet + facet normal -0.543854 -0.353061 0.761296 + outer loop + vertex 0.944595 0.974386 2.56593 + vertex 0.944101 0.977937 2.56722 + vertex 0.942401 0.976476 2.56533 + endloop + endfacet + facet normal -0.506162 -0.356568 0.785277 + outer loop + vertex 0.944595 0.974386 2.56593 + vertex 0.947701 0.973547 2.56755 + vertex 0.944101 0.977937 2.56722 + endloop + endfacet + facet normal -0.480393 -0.333515 0.811166 + outer loop + vertex 0.947701 0.973547 2.56755 + vertex 0.94819 0.977612 2.56951 + vertex 0.944101 0.977937 2.56722 + endloop + endfacet + facet normal -0.471564 -0.346806 0.810773 + outer loop + vertex 0.947537 0.981389 2.57069 + vertex 0.945942 0.984407 2.57105 + vertex 0.944096 0.982528 2.56918 + endloop + endfacet + facet normal -0.470372 -0.336582 0.815759 + outer loop + vertex 0.947537 0.981389 2.57069 + vertex 0.944096 0.982528 2.56918 + vertex 0.94819 0.977612 2.56951 + endloop + endfacet + facet normal -0.479121 -0.344439 0.807344 + outer loop + vertex 0.94819 0.977612 2.56951 + vertex 0.944096 0.982528 2.56918 + vertex 0.944101 0.977937 2.56722 + endloop + endfacet + facet normal -0.438717 -0.332352 0.834907 + outer loop + vertex 0.947537 0.981389 2.57069 + vertex 0.949505 0.983017 2.57237 + vertex 0.945942 0.984407 2.57105 + endloop + endfacet + facet normal -0.473051 -0.345176 0.810602 + outer loop + vertex 0.944096 0.982528 2.56918 + vertex 0.945942 0.984407 2.57105 + vertex 0.943197 0.986675 2.57042 + endloop + endfacet + facet normal -0.462884 -0.329414 0.822937 + outer loop + vertex 0.945942 0.984407 2.57105 + vertex 0.945626 0.988255 2.57242 + vertex 0.943197 0.986675 2.57042 + endloop + endfacet + facet normal -0.438599 -0.331769 0.835201 + outer loop + vertex 0.945942 0.984407 2.57105 + vertex 0.949505 0.983017 2.57237 + vertex 0.945626 0.988255 2.57242 + endloop + endfacet + facet normal -0.426927 -0.323203 0.844555 + outer loop + vertex 0.949505 0.983017 2.57237 + vertex 0.950071 0.987101 2.57422 + vertex 0.945626 0.988255 2.57242 + endloop + endfacet + facet normal -0.427461 -0.329492 0.84185 + outer loop + vertex 0.950071 0.987101 2.57422 + vertex 0.947005 0.992337 2.57471 + vertex 0.945626 0.988255 2.57242 + endloop + endfacet + facet normal -0.42286 -0.331835 0.843253 + outer loop + vertex 0.945626 0.988255 2.57242 + vertex 0.947005 0.992337 2.57471 + vertex 0.942533 0.993504 2.57293 + endloop + endfacet + facet normal -0.417773 -0.336519 0.843932 + outer loop + vertex 0.946665 0.996113 2.57602 + vertex 0.944975 0.999057 2.57635 + vertex 0.943021 0.997506 2.57477 + endloop + endfacet + facet normal -0.416326 -0.329676 0.847341 + outer loop + vertex 0.946665 0.996113 2.57602 + vertex 0.943021 0.997506 2.57477 + vertex 0.947005 0.992337 2.57471 + endloop + endfacet + facet normal -0.42312 -0.334856 0.841927 + outer loop + vertex 0.947005 0.992337 2.57471 + vertex 0.943021 0.997506 2.57477 + vertex 0.942533 0.993504 2.57293 + endloop + endfacet + facet normal -0.429587 -0.342348 0.835615 + outer loop + vertex 0.946665 0.996113 2.57602 + vertex 0.948634 0.997793 2.57772 + vertex 0.944975 0.999057 2.57635 + endloop + endfacet + facet normal -0.416862 -0.337661 0.843926 + outer loop + vertex 0.943021 0.997506 2.57477 + vertex 0.944975 0.999057 2.57635 + vertex 0.942299 1.00113 2.57586 + endloop + endfacet + facet normal -0.40946 -0.326202 0.852018 + outer loop + vertex 0.944975 0.999057 2.57635 + vertex 0.944192 1.00275 2.57739 + vertex 0.942299 1.00113 2.57586 + endloop + endfacet + facet normal -0.42711 -0.32737 0.842856 + outer loop + vertex 0.944975 0.999057 2.57635 + vertex 0.948634 0.997793 2.57772 + vertex 0.944192 1.00275 2.57739 + endloop + endfacet + facet normal -0.425362 -0.325704 0.844384 + outer loop + vertex 0.948634 0.997793 2.57772 + vertex 0.948677 1.00245 2.57954 + vertex 0.944192 1.00275 2.57739 + endloop + endfacet + facet normal -0.424937 -0.309242 0.850763 + outer loop + vertex 0.947728 1.0064 2.58048 + vertex 0.946005 1.00942 2.58072 + vertex 0.944082 1.00755 2.57908 + endloop + endfacet + facet normal -0.424497 -0.306269 0.852057 + outer loop + vertex 0.947728 1.0064 2.58048 + vertex 0.944082 1.00755 2.57908 + vertex 0.948677 1.00245 2.57954 + endloop + endfacet + facet normal -0.4269 -0.30862 0.850006 + outer loop + vertex 0.948677 1.00245 2.57954 + vertex 0.944082 1.00755 2.57908 + vertex 0.944192 1.00275 2.57739 + endloop + endfacet + facet normal -0.464384 -0.329432 0.822084 + outer loop + vertex 0.947728 1.0064 2.58048 + vertex 0.949542 1.0082 2.58223 + vertex 0.946005 1.00942 2.58072 + endloop + endfacet + facet normal -0.4222 -0.312271 0.851019 + outer loop + vertex 0.944082 1.00755 2.57908 + vertex 0.946005 1.00942 2.58072 + vertex 0.943172 1.01169 2.58015 + endloop + endfacet + facet normal -0.429974 -0.324105 0.842661 + outer loop + vertex 0.946005 1.00942 2.58072 + vertex 0.945701 1.01324 2.58203 + vertex 0.943172 1.01169 2.58015 + endloop + endfacet + facet normal -0.463185 -0.321053 0.826066 + outer loop + vertex 0.946005 1.00942 2.58072 + vertex 0.949542 1.0082 2.58223 + vertex 0.945701 1.01324 2.58203 + endloop + endfacet + facet normal -0.467286 -0.324322 0.822472 + outer loop + vertex 0.949542 1.0082 2.58223 + vertex 0.949937 1.01216 2.58402 + vertex 0.945701 1.01324 2.58203 + endloop + endfacet + facet normal -0.46623 -0.306347 0.829928 + outer loop + vertex 0.949937 1.01216 2.58402 + vertex 0.947173 1.01729 2.58436 + vertex 0.945701 1.01324 2.58203 + endloop + endfacet + facet normal -0.449339 -0.315773 0.835692 + outer loop + vertex 0.945701 1.01324 2.58203 + vertex 0.947173 1.01729 2.58436 + vertex 0.942816 1.01844 2.58245 + endloop + endfacet + facet normal -0.460039 -0.290291 0.839104 + outer loop + vertex 0.94701 1.0211 2.58564 + vertex 0.945628 1.02405 2.58591 + vertex 0.943617 1.02251 2.58427 + endloop + endfacet + facet normal -0.462565 -0.301609 0.833706 + outer loop + vertex 0.94701 1.0211 2.58564 + vertex 0.943617 1.02251 2.58427 + vertex 0.947173 1.01729 2.58436 + endloop + endfacet + facet normal -0.447232 -0.290966 0.845767 + outer loop + vertex 0.947173 1.01729 2.58436 + vertex 0.943617 1.02251 2.58427 + vertex 0.942816 1.01844 2.58245 + endloop + endfacet + facet normal -0.489982 -0.3024 0.817601 + outer loop + vertex 0.94701 1.0211 2.58564 + vertex 0.948949 1.02276 2.58742 + vertex 0.945628 1.02405 2.58591 + endloop + endfacet + facet normal -0.461929 -0.287675 0.838967 + outer loop + vertex 0.943617 1.02251 2.58427 + vertex 0.945628 1.02405 2.58591 + vertex 0.943245 1.02629 2.58536 + endloop + endfacet + facet normal -0.47231 -0.301345 0.82832 + outer loop + vertex 0.945628 1.02405 2.58591 + vertex 0.945358 1.0273 2.58693 + vertex 0.943245 1.02629 2.58536 + endloop + endfacet + facet normal -0.489524 -0.299779 0.81884 + outer loop + vertex 0.945628 1.02405 2.58591 + vertex 0.948949 1.02276 2.58742 + vertex 0.945358 1.0273 2.58693 + endloop + endfacet + facet normal -0.492182 -0.302146 0.816373 + outer loop + vertex 0.948949 1.02276 2.58742 + vertex 0.948862 1.02756 2.58914 + vertex 0.945358 1.0273 2.58693 + endloop + endfacet + facet normal -0.488272 -0.277564 0.827375 + outer loop + vertex 0.948152 1.03165 2.59015 + vertex 0.946438 1.03557 2.59046 + vertex 0.944021 1.03284 2.58812 + endloop + endfacet + facet normal -0.489294 -0.288619 0.822977 + outer loop + vertex 0.948152 1.03165 2.59015 + vertex 0.944021 1.03284 2.58812 + vertex 0.948862 1.02756 2.58914 + endloop + endfacet + facet normal -0.494009 -0.293848 0.818296 + outer loop + vertex 0.948862 1.02756 2.58914 + vertex 0.944021 1.03284 2.58812 + vertex 0.945358 1.0273 2.58693 + endloop + endfacet + facet normal -0.473756 -0.272018 0.837592 + outer loop + vertex 0.948152 1.03165 2.59015 + vertex 0.950707 1.0331 2.59207 + vertex 0.946438 1.03557 2.59046 + endloop + endfacet + facet normal -0.489884 -0.27582 0.827005 + outer loop + vertex 0.942909 1.03831 2.58928 + vertex 0.944021 1.03284 2.58812 + vertex 0.946438 1.03557 2.59046 + endloop + endfacet + facet normal -0.490521 -0.276967 0.826243 + outer loop + vertex 0.945016 1.03924 2.59085 + vertex 0.942909 1.03831 2.58928 + vertex 0.946438 1.03557 2.59046 + endloop + endfacet + facet normal -0.495814 -0.278628 0.822518 + outer loop + vertex 0.946438 1.03557 2.59046 + vertex 0.948059 1.0382 2.59233 + vertex 0.945016 1.03924 2.59085 + endloop + endfacet + facet normal -0.480826 -0.291105 0.827082 + outer loop + vertex 0.950707 1.0331 2.59207 + vertex 0.948059 1.0382 2.59233 + vertex 0.946438 1.03557 2.59046 + endloop + endfacet + facet normal -0.492035 -0.2738 0.826399 + outer loop + vertex 0.942909 1.03831 2.58928 + vertex 0.945016 1.03924 2.59085 + vertex 0.94286 1.04152 2.59032 + endloop + endfacet + facet normal -0.504981 -0.289069 0.813286 + outer loop + vertex 0.945016 1.03924 2.59085 + vertex 0.94498 1.04237 2.59194 + vertex 0.94286 1.04152 2.59032 + endloop + endfacet + facet normal -0.497385 -0.29044 0.817467 + outer loop + vertex 0.945016 1.03924 2.59085 + vertex 0.948059 1.0382 2.59233 + vertex 0.94498 1.04237 2.59194 + endloop + endfacet + facet normal -0.496705 -0.289881 0.818079 + outer loop + vertex 0.948059 1.0382 2.59233 + vertex 0.948654 1.04238 2.59417 + vertex 0.94498 1.04237 2.59194 + endloop + endfacet + facet normal -0.500999 -0.292043 0.814685 + outer loop + vertex 0.948027 1.04659 2.59531 + vertex 0.946361 1.05043 2.59566 + vertex 0.944017 1.04762 2.59322 + endloop + endfacet + facet normal -0.501169 -0.295355 0.813385 + outer loop + vertex 0.948027 1.04659 2.59531 + vertex 0.944017 1.04762 2.59322 + vertex 0.948654 1.04238 2.59417 + endloop + endfacet + facet normal -0.496607 -0.290499 0.817919 + outer loop + vertex 0.948654 1.04238 2.59417 + vertex 0.944017 1.04762 2.59322 + vertex 0.94498 1.04237 2.59194 + endloop + endfacet + facet normal -0.426231 -0.264127 0.865196 + outer loop + vertex 0.948027 1.04659 2.59531 + vertex 0.950703 1.04841 2.59719 + vertex 0.946361 1.05043 2.59566 + endloop + endfacet + facet normal -0.506321 -0.286452 0.813379 + outer loop + vertex 0.942758 1.05305 2.59434 + vertex 0.944017 1.04762 2.59322 + vertex 0.946361 1.05043 2.59566 + endloop + endfacet + facet normal -0.511738 -0.29764 0.805937 + outer loop + vertex 0.944899 1.05397 2.59604 + vertex 0.942758 1.05305 2.59434 + vertex 0.946361 1.05043 2.59566 + endloop + endfacet + facet normal -0.468258 -0.283055 0.837027 + outer loop + vertex 0.946361 1.05043 2.59566 + vertex 0.947941 1.05321 2.59749 + vertex 0.944899 1.05397 2.59604 + endloop + endfacet + facet normal -0.438427 -0.305387 0.845293 + outer loop + vertex 0.950703 1.04841 2.59719 + vertex 0.947941 1.05321 2.59749 + vertex 0.946361 1.05043 2.59566 + endloop + endfacet + facet normal -0.517224 -0.286137 0.806601 + outer loop + vertex 0.942758 1.05305 2.59434 + vertex 0.944899 1.05397 2.59604 + vertex 0.942526 1.05634 2.59536 + endloop + endfacet + facet normal -0.513571 -0.281314 0.810621 + outer loop + vertex 0.944899 1.05397 2.59604 + vertex 0.944835 1.05711 2.59709 + vertex 0.942526 1.05634 2.59536 + endloop + endfacet + facet normal -0.468637 -0.288515 0.834948 + outer loop + vertex 0.944899 1.05397 2.59604 + vertex 0.947941 1.05321 2.59749 + vertex 0.944835 1.05711 2.59709 + endloop + endfacet + facet normal -0.460105 -0.280973 0.842233 + outer loop + vertex 0.947941 1.05321 2.59749 + vertex 0.948525 1.05737 2.59919 + vertex 0.944835 1.05711 2.59709 + endloop + endfacet + facet normal -0.47193 -0.270891 0.838988 + outer loop + vertex 0.947995 1.06143 2.60029 + vertex 0.946511 1.06538 2.60073 + vertex 0.943911 1.06236 2.5983 + endloop + endfacet + facet normal -0.472765 -0.287115 0.833101 + outer loop + vertex 0.947995 1.06143 2.60029 + vertex 0.943911 1.06236 2.5983 + vertex 0.948525 1.05737 2.59919 + endloop + endfacet + facet normal -0.461347 -0.274673 0.843631 + outer loop + vertex 0.948525 1.05737 2.59919 + vertex 0.943911 1.06236 2.5983 + vertex 0.944835 1.05711 2.59709 + endloop + endfacet + facet normal -0.335076 -0.227887 0.914216 + outer loop + vertex 0.947995 1.06143 2.60029 + vertex 0.951011 1.06371 2.60197 + vertex 0.946511 1.06538 2.60073 + endloop + endfacet + facet normal -0.472608 -0.270183 0.838834 + outer loop + vertex 0.942765 1.06787 2.59943 + vertex 0.943911 1.06236 2.5983 + vertex 0.946511 1.06538 2.60073 + endloop + endfacet + facet normal -0.474651 -0.274619 0.836236 + outer loop + vertex 0.945181 1.06918 2.60123 + vertex 0.942765 1.06787 2.59943 + vertex 0.946511 1.06538 2.60073 + endloop + endfacet + facet normal -0.361801 -0.243385 0.899924 + outer loop + vertex 0.946511 1.06538 2.60073 + vertex 0.948911 1.06905 2.60269 + vertex 0.945181 1.06918 2.60123 + endloop + endfacet + facet normal -0.343036 -0.257465 0.903348 + outer loop + vertex 0.951011 1.06371 2.60197 + vertex 0.948911 1.06905 2.60269 + vertex 0.946511 1.06538 2.60073 + endloop + endfacet + facet normal -0.482596 -0.260089 0.836334 + outer loop + vertex 0.942765 1.06787 2.59943 + vertex 0.945181 1.06918 2.60123 + vertex 0.942661 1.07145 2.60048 + endloop + endfacet + facet normal -0.463144 -0.232323 0.855292 + outer loop + vertex 0.945181 1.06918 2.60123 + vertex 0.945346 1.07302 2.60236 + vertex 0.942661 1.07145 2.60048 + endloop + endfacet + facet normal -0.361416 -0.249406 0.898429 + outer loop + vertex 0.945181 1.06918 2.60123 + vertex 0.948911 1.06905 2.60269 + vertex 0.945346 1.07302 2.60236 + endloop + endfacet + facet normal -0.371184 -0.258744 0.891781 + outer loop + vertex 0.948911 1.06905 2.60269 + vertex 0.948582 1.07271 2.60361 + vertex 0.945346 1.07302 2.60236 + endloop + endfacet + facet normal -0.371307 -0.247354 0.894956 + outer loop + vertex 0.948582 1.07271 2.60361 + vertex 0.947804 1.07674 2.60441 + vertex 0.945346 1.07302 2.60236 + endloop + endfacet + facet normal -0.394378 -0.229307 0.889879 + outer loop + vertex 0.945346 1.07302 2.60236 + vertex 0.947804 1.07674 2.60441 + vertex 0.942999 1.07788 2.60257 + endloop + endfacet + facet normal -0.387642 -0.28525 0.876565 + outer loop + vertex 0.947396 1.08106 2.60559 + vertex 0.94584 1.08416 2.60591 + vertex 0.943606 1.08204 2.60423 + endloop + endfacet + facet normal -0.386609 -0.27701 0.879658 + outer loop + vertex 0.947396 1.08106 2.60559 + vertex 0.943606 1.08204 2.60423 + vertex 0.947804 1.07674 2.60441 + endloop + endfacet + facet normal -0.400686 -0.288491 0.869611 + outer loop + vertex 0.947804 1.07674 2.60441 + vertex 0.943606 1.08204 2.60423 + vertex 0.942999 1.07788 2.60257 + endloop + endfacet + facet normal -0.231781 -0.214577 0.948807 + outer loop + vertex 0.947396 1.08106 2.60559 + vertex 0.95025 1.08419 2.60699 + vertex 0.94584 1.08416 2.60591 + endloop + endfacet + facet normal -0.402171 -0.26885 0.875202 + outer loop + vertex 0.943606 1.08204 2.60423 + vertex 0.94584 1.08416 2.60591 + vertex 0.943033 1.0863 2.60528 + endloop + endfacet + facet normal -0.366047 -0.212478 0.906015 + outer loop + vertex 0.94584 1.08416 2.60591 + vertex 0.94606 1.0885 2.60702 + vertex 0.943033 1.0863 2.60528 + endloop + endfacet + facet normal -0.230859 -0.229421 0.945553 + outer loop + vertex 0.94584 1.08416 2.60591 + vertex 0.95025 1.08419 2.60699 + vertex 0.94606 1.0885 2.60702 + endloop + endfacet + facet normal -0.222684 -0.22148 0.949399 + outer loop + vertex 0.95025 1.08419 2.60699 + vertex 0.950393 1.08912 2.60818 + vertex 0.94606 1.0885 2.60702 + endloop + endfacet + facet normal -0.221511 -0.227512 0.948246 + outer loop + vertex 0.950393 1.08912 2.60818 + vertex 0.948888 1.09289 2.60873 + vertex 0.94606 1.0885 2.60702 + endloop + endfacet + facet normal -0.248518 -0.209166 0.945774 + outer loop + vertex 0.94606 1.0885 2.60702 + vertex 0.948888 1.09289 2.60873 + vertex 0.943924 1.09402 2.60768 + endloop + endfacet + facet normal -0.254541 -0.245397 0.935409 + outer loop + vertex 0.948888 1.09289 2.60873 + vertex 0.947213 1.09763 2.60952 + vertex 0.943924 1.09402 2.60768 + endloop + endfacet + facet normal -0.0255891 -0.0533734 0.998247 + outer loop + vertex 0.943173 1.21292 2.62872 + vertex 0.948498 1.21815 2.62914 + vertex 0.943428 1.21809 2.62901 + endloop + endfacet + facet normal -0.294354 0.268454 0.917218 + outer loop + vertex 0.943407 1.93643 2.60428 + vertex 0.948205 1.94194 2.6042 + vertex 0.943237 1.94168 2.60269 + endloop + endfacet + facet normal -0.295417 0.228141 0.927729 + outer loop + vertex 0.948205 1.94194 2.6042 + vertex 0.948345 1.9468 2.60305 + vertex 0.943237 1.94168 2.60269 + endloop + endfacet + facet normal -0.277869 0.209946 0.937396 + outer loop + vertex 0.943237 1.94168 2.60269 + vertex 0.948345 1.9468 2.60305 + vertex 0.944302 1.94684 2.60185 + endloop + endfacet + facet normal -0.470208 0.284767 0.835352 + outer loop + vertex 0.945503 1.95351 2.60054 + vertex 0.941939 1.95074 2.59947 + vertex 0.944252 1.95001 2.60102 + endloop + endfacet + facet normal -0.309102 0.238996 0.920509 + outer loop + vertex 0.944252 1.95001 2.60102 + vertex 0.948129 1.95159 2.60192 + vertex 0.945503 1.95351 2.60054 + endloop + endfacet + facet normal -0.307675 0.234574 0.922123 + outer loop + vertex 0.944252 1.95001 2.60102 + vertex 0.944302 1.94684 2.60185 + vertex 0.948129 1.95159 2.60192 + endloop + endfacet + facet normal -0.277844 0.210302 0.937324 + outer loop + vertex 0.944302 1.94684 2.60185 + vertex 0.948345 1.9468 2.60305 + vertex 0.948129 1.95159 2.60192 + endloop + endfacet + facet normal -0.469514 0.283566 0.83615 + outer loop + vertex 0.943232 1.95612 2.59837 + vertex 0.941939 1.95074 2.59947 + vertex 0.945503 1.95351 2.60054 + endloop + endfacet + facet normal -0.450699 0.302882 0.839722 + outer loop + vertex 0.947234 1.95708 2.60017 + vertex 0.943232 1.95612 2.59837 + vertex 0.945503 1.95351 2.60054 + endloop + endfacet + facet normal -0.336277 0.254275 0.906787 + outer loop + vertex 0.945503 1.95351 2.60054 + vertex 0.948802 1.95553 2.60119 + vertex 0.947234 1.95708 2.60017 + endloop + endfacet + facet normal -0.320266 0.223745 0.920526 + outer loop + vertex 0.948129 1.95159 2.60192 + vertex 0.948802 1.95553 2.60119 + vertex 0.945503 1.95351 2.60054 + endloop + endfacet + facet normal -0.304455 0.2997 0.90415 + outer loop + vertex 0.947234 1.95708 2.60017 + vertex 0.950734 1.95894 2.60074 + vertex 0.948526 1.96141 2.59918 + endloop + endfacet + facet normal -0.452058 0.326667 0.83002 + outer loop + vertex 0.947234 1.95708 2.60017 + vertex 0.948526 1.96141 2.59918 + vertex 0.943232 1.95612 2.59837 + endloop + endfacet + facet normal -0.397247 0.264388 0.878803 + outer loop + vertex 0.943232 1.95612 2.59837 + vertex 0.948526 1.96141 2.59918 + vertex 0.944311 1.96161 2.59721 + endloop + endfacet + facet normal -0.30062 0.291223 0.908194 + outer loop + vertex 0.950734 1.95894 2.60074 + vertex 0.947234 1.95708 2.60017 + vertex 0.948802 1.95553 2.60119 + endloop + endfacet + facet normal -0.516127 0.286142 0.807301 + outer loop + vertex 0.945575 1.9687 2.59567 + vertex 0.941913 1.96567 2.5944 + vertex 0.944246 1.96492 2.59616 + endloop + endfacet + facet normal -0.403974 0.255954 0.878233 + outer loop + vertex 0.944246 1.96492 2.59616 + vertex 0.948269 1.96665 2.59751 + vertex 0.945575 1.9687 2.59567 + endloop + endfacet + facet normal -0.407501 0.26825 0.872917 + outer loop + vertex 0.944246 1.96492 2.59616 + vertex 0.944311 1.96161 2.59721 + vertex 0.948269 1.96665 2.59751 + endloop + endfacet + facet normal -0.397878 0.260297 0.879738 + outer loop + vertex 0.944311 1.96161 2.59721 + vertex 0.948526 1.96141 2.59918 + vertex 0.948269 1.96665 2.59751 + endloop + endfacet + facet normal -0.515702 0.285405 0.807834 + outer loop + vertex 0.943213 1.97111 2.59331 + vertex 0.941913 1.96567 2.5944 + vertex 0.945575 1.9687 2.59567 + endloop + endfacet + facet normal -0.520742 0.27937 0.80671 + outer loop + vertex 0.947069 1.97254 2.59531 + vertex 0.943213 1.97111 2.59331 + vertex 0.945575 1.9687 2.59567 + endloop + endfacet + facet normal -0.410121 0.243241 0.878996 + outer loop + vertex 0.945575 1.9687 2.59567 + vertex 0.949422 1.97174 2.59663 + vertex 0.947069 1.97254 2.59531 + endloop + endfacet + facet normal -0.41157 0.245484 0.877694 + outer loop + vertex 0.948269 1.96665 2.59751 + vertex 0.949422 1.97174 2.59663 + vertex 0.945575 1.9687 2.59567 + endloop + endfacet + facet normal -0.453532 0.300422 0.83908 + outer loop + vertex 0.947069 1.97254 2.59531 + vertex 0.949731 1.97493 2.59589 + vertex 0.948006 1.97653 2.59438 + endloop + endfacet + facet normal -0.524446 0.306733 0.794274 + outer loop + vertex 0.947069 1.97254 2.59531 + vertex 0.948006 1.97653 2.59438 + vertex 0.943213 1.97111 2.59331 + endloop + endfacet + facet normal -0.502664 0.282987 0.816852 + outer loop + vertex 0.943213 1.97111 2.59331 + vertex 0.948006 1.97653 2.59438 + vertex 0.94434 1.97649 2.59214 + endloop + endfacet + facet normal -0.410381 0.242579 0.879058 + outer loop + vertex 0.949731 1.97493 2.59589 + vertex 0.947069 1.97254 2.59531 + vertex 0.949422 1.97174 2.59663 + endloop + endfacet + facet normal -0.515184 0.275017 0.811758 + outer loop + vertex 0.9457 1.98353 2.5906 + vertex 0.941973 1.98037 2.5893 + vertex 0.944378 1.97972 2.59105 + endloop + endfacet + facet normal -0.484673 0.266941 0.832967 + outer loop + vertex 0.944378 1.97972 2.59105 + vertex 0.948211 1.98153 2.5927 + vertex 0.9457 1.98353 2.5906 + endloop + endfacet + facet normal -0.489421 0.285045 0.824146 + outer loop + vertex 0.944378 1.97972 2.59105 + vertex 0.94434 1.97649 2.59214 + vertex 0.948211 1.98153 2.5927 + endloop + endfacet + facet normal -0.500882 0.294992 0.813694 + outer loop + vertex 0.94434 1.97649 2.59214 + vertex 0.948006 1.97653 2.59438 + vertex 0.948211 1.98153 2.5927 + endloop + endfacet + facet normal -0.51759 0.279055 0.808844 + outer loop + vertex 0.943204 1.98593 2.58817 + vertex 0.941973 1.98037 2.5893 + vertex 0.9457 1.98353 2.5906 + endloop + endfacet + facet normal -0.522412 0.272999 0.80781 + outer loop + vertex 0.947194 1.9874 2.59025 + vertex 0.943204 1.98593 2.58817 + vertex 0.9457 1.98353 2.5906 + endloop + endfacet + facet normal -0.474556 0.257555 0.841702 + outer loop + vertex 0.9457 1.98353 2.5906 + vertex 0.949534 1.98665 2.5918 + vertex 0.947194 1.9874 2.59025 + endloop + endfacet + facet normal -0.482269 0.270291 0.833282 + outer loop + vertex 0.948211 1.98153 2.5927 + vertex 0.949534 1.98665 2.5918 + vertex 0.9457 1.98353 2.5906 + endloop + endfacet + facet normal -0.501939 0.288064 0.815522 + outer loop + vertex 0.947194 1.9874 2.59025 + vertex 0.949805 1.98985 2.591 + vertex 0.947917 1.9913 2.58932 + endloop + endfacet + facet normal -0.524615 0.288763 0.800871 + outer loop + vertex 0.947194 1.9874 2.59025 + vertex 0.947917 1.9913 2.58932 + vertex 0.943204 1.98593 2.58817 + endloop + endfacet + facet normal -0.530906 0.295713 0.794161 + outer loop + vertex 0.943204 1.98593 2.58817 + vertex 0.947917 1.9913 2.58932 + vertex 0.94453 1.99145 2.587 + endloop + endfacet + facet normal -0.47641 0.25269 0.842129 + outer loop + vertex 0.949805 1.98985 2.591 + vertex 0.947194 1.9874 2.59025 + vertex 0.949534 1.98665 2.5918 + endloop + endfacet + facet normal -0.491873 0.268961 0.828083 + outer loop + vertex 0.946231 1.99759 2.58589 + vertex 0.942863 1.99627 2.58432 + vertex 0.944825 1.99475 2.58598 + endloop + endfacet + facet normal -0.520664 0.2825 0.805669 + outer loop + vertex 0.944825 1.99475 2.58598 + vertex 0.948091 1.99603 2.58764 + vertex 0.946231 1.99759 2.58589 + endloop + endfacet + facet normal -0.522507 0.294224 0.800262 + outer loop + vertex 0.944825 1.99475 2.58598 + vertex 0.94453 1.99145 2.587 + vertex 0.948091 1.99603 2.58764 + endloop + endfacet + facet normal -0.529821 0.300947 0.792919 + outer loop + vertex 0.94453 1.99145 2.587 + vertex 0.947917 1.9913 2.58932 + vertex 0.948091 1.99603 2.58764 + endloop + endfacet + facet normal -0.508328 0.279612 0.814506 + outer loop + vertex 0.946231 1.99759 2.58589 + vertex 0.948795 1.99992 2.58669 + vertex 0.94653 2.00084 2.58497 + endloop + endfacet + facet normal -0.494058 0.280684 0.822875 + outer loop + vertex 0.946231 1.99759 2.58589 + vertex 0.94653 2.00084 2.58497 + vertex 0.942863 1.99627 2.58432 + endloop + endfacet + facet normal -0.490763 0.277613 0.825883 + outer loop + vertex 0.942863 1.99627 2.58432 + vertex 0.94653 2.00084 2.58497 + vertex 0.94296 2.00129 2.58269 + endloop + endfacet + facet normal -0.515218 0.289941 0.806526 + outer loop + vertex 0.948795 1.99992 2.58669 + vertex 0.946231 1.99759 2.58589 + vertex 0.948091 1.99603 2.58764 + endloop + endfacet + facet normal -0.488016 0.28857 0.823752 + outer loop + vertex 0.94653 2.00084 2.58497 + vertex 0.948009 2.00594 2.58406 + vertex 0.94296 2.00129 2.58269 + endloop + endfacet + facet normal -0.501028 0.306981 0.809156 + outer loop + vertex 0.94296 2.00129 2.58269 + vertex 0.948009 2.00594 2.58406 + vertex 0.944628 2.00645 2.58177 + endloop + endfacet + facet normal -0.449592 0.286504 0.846039 + outer loop + vertex 0.946434 2.01238 2.58062 + vertex 0.942934 2.011 2.57923 + vertex 0.945004 2.00961 2.5808 + endloop + endfacet + facet normal -0.495069 0.307865 0.812481 + outer loop + vertex 0.945004 2.00961 2.5808 + vertex 0.948294 2.01085 2.58233 + vertex 0.946434 2.01238 2.58062 + endloop + endfacet + facet normal -0.495075 0.307906 0.812462 + outer loop + vertex 0.945004 2.00961 2.5808 + vertex 0.944628 2.00645 2.58177 + vertex 0.948294 2.01085 2.58233 + endloop + endfacet + facet normal -0.499527 0.312169 0.808099 + outer loop + vertex 0.944628 2.00645 2.58177 + vertex 0.948009 2.00594 2.58406 + vertex 0.948294 2.01085 2.58233 + endloop + endfacet + facet normal -0.481709 0.287744 0.827744 + outer loop + vertex 0.946434 2.01238 2.58062 + vertex 0.949015 2.01471 2.58131 + vertex 0.946658 2.0156 2.57963 + endloop + endfacet + facet normal -0.450474 0.290618 0.844165 + outer loop + vertex 0.946434 2.01238 2.58062 + vertex 0.946658 2.0156 2.57963 + vertex 0.942934 2.011 2.57923 + endloop + endfacet + facet normal -0.444383 0.285256 0.849207 + outer loop + vertex 0.942934 2.011 2.57923 + vertex 0.946658 2.0156 2.57963 + vertex 0.942881 2.01572 2.57761 + endloop + endfacet + facet normal -0.495384 0.307444 0.812449 + outer loop + vertex 0.949015 2.01471 2.58131 + vertex 0.946434 2.01238 2.58062 + vertex 0.948294 2.01085 2.58233 + endloop + endfacet + facet normal -0.436432 0.316659 0.842172 + outer loop + vertex 0.945515 2.02358 2.57611 + vertex 0.94147 2.02068 2.57511 + vertex 0.943769 2.01972 2.57666 + endloop + endfacet + facet normal -0.450019 0.321532 0.833127 + outer loop + vertex 0.943769 2.01972 2.57666 + vertex 0.947981 2.02109 2.5784 + vertex 0.945515 2.02358 2.57611 + endloop + endfacet + facet normal -0.447139 0.301077 0.842271 + outer loop + vertex 0.943769 2.01972 2.57666 + vertex 0.942881 2.01572 2.57761 + vertex 0.947981 2.02109 2.5784 + endloop + endfacet + facet normal -0.44256 0.296116 0.846437 + outer loop + vertex 0.942881 2.01572 2.57761 + vertex 0.946658 2.0156 2.57963 + vertex 0.947981 2.02109 2.5784 + endloop + endfacet + facet normal -0.437742 0.319032 0.840596 + outer loop + vertex 0.943126 2.02585 2.57401 + vertex 0.94147 2.02068 2.57511 + vertex 0.945515 2.02358 2.57611 + endloop + endfacet + facet normal -0.430396 0.327323 0.841201 + outer loop + vertex 0.947213 2.0274 2.57549 + vertex 0.943126 2.02585 2.57401 + vertex 0.945515 2.02358 2.57611 + endloop + endfacet + facet normal -0.451597 0.334473 0.827157 + outer loop + vertex 0.945515 2.02358 2.57611 + vertex 0.949502 2.02655 2.57709 + vertex 0.947213 2.0274 2.57549 + endloop + endfacet + facet normal -0.44644 0.325456 0.833528 + outer loop + vertex 0.947981 2.02109 2.5784 + vertex 0.949502 2.02655 2.57709 + vertex 0.945515 2.02358 2.57611 + endloop + endfacet + facet normal -0.43593 0.324592 0.839407 + outer loop + vertex 0.947213 2.0274 2.57549 + vertex 0.949922 2.02974 2.576 + vertex 0.947817 2.03113 2.57436 + endloop + endfacet + facet normal -0.42984 0.324559 0.842555 + outer loop + vertex 0.947213 2.0274 2.57549 + vertex 0.947817 2.03113 2.57436 + vertex 0.943126 2.02585 2.57401 + endloop + endfacet + facet normal -0.417735 0.313101 0.852916 + outer loop + vertex 0.943126 2.02585 2.57401 + vertex 0.947817 2.03113 2.57436 + vertex 0.94325 2.03095 2.57219 + endloop + endfacet + facet normal -0.448178 0.34165 0.826082 + outer loop + vertex 0.949922 2.02974 2.576 + vertex 0.947213 2.0274 2.57549 + vertex 0.949502 2.02655 2.57709 + endloop + endfacet + facet normal -0.441132 0.352848 0.825167 + outer loop + vertex 0.946305 2.03782 2.5711 + vertex 0.943019 2.03686 2.56975 + vertex 0.944384 2.03485 2.57134 + endloop + endfacet + facet normal -0.404025 0.331116 0.852717 + outer loop + vertex 0.944384 2.03485 2.57134 + vertex 0.947816 2.0358 2.5726 + vertex 0.946305 2.03782 2.5711 + endloop + endfacet + facet normal -0.400824 0.304892 0.863934 + outer loop + vertex 0.944384 2.03485 2.57134 + vertex 0.94325 2.03095 2.57219 + vertex 0.947816 2.0358 2.5726 + endloop + endfacet + facet normal -0.416839 0.321101 0.850376 + outer loop + vertex 0.94325 2.03095 2.57219 + vertex 0.947817 2.03113 2.57436 + vertex 0.947816 2.0358 2.5726 + endloop + endfacet + facet normal -0.410556 0.348727 0.842516 + outer loop + vertex 0.946305 2.03782 2.5711 + vertex 0.948934 2.0397 2.5716 + vertex 0.947341 2.04147 2.57009 + endloop + endfacet + facet normal -0.441112 0.352642 0.825266 + outer loop + vertex 0.946305 2.03782 2.5711 + vertex 0.947341 2.04147 2.57009 + vertex 0.943019 2.03686 2.56975 + endloop + endfacet + facet normal -0.453929 0.365608 0.812576 + outer loop + vertex 0.943019 2.03686 2.56975 + vertex 0.947341 2.04147 2.57009 + vertex 0.942935 2.0414 2.56766 + endloop + endfacet + facet normal -0.401515 0.333257 0.853068 + outer loop + vertex 0.948934 2.0397 2.5716 + vertex 0.946305 2.03782 2.5711 + vertex 0.947816 2.0358 2.5726 + endloop + endfacet + facet normal -0.457289 0.346143 0.81919 + outer loop + vertex 0.947341 2.04147 2.57009 + vertex 0.947887 2.04595 2.56851 + vertex 0.942935 2.0414 2.56766 + endloop + endfacet + facet normal -0.457048 0.34583 0.819456 + outer loop + vertex 0.942935 2.0414 2.56766 + vertex 0.947887 2.04595 2.56851 + vertex 0.944189 2.04627 2.56631 + endloop + endfacet + facet normal -0.50548 0.35708 0.785483 + outer loop + vertex 0.947138 2.0528 2.56519 + vertex 0.945089 2.05337 2.56362 + vertex 0.944465 2.05019 2.56466 + endloop + endfacet + facet normal -0.477225 0.321481 0.817867 + outer loop + vertex 0.944465 2.05019 2.56466 + vertex 0.948474 2.05069 2.5668 + vertex 0.947138 2.0528 2.56519 + endloop + endfacet + facet normal -0.473379 0.369431 0.799645 + outer loop + vertex 0.944465 2.05019 2.56466 + vertex 0.944189 2.04627 2.56631 + vertex 0.948474 2.05069 2.5668 + endloop + endfacet + facet normal -0.455887 0.350369 0.818174 + outer loop + vertex 0.944189 2.04627 2.56631 + vertex 0.947887 2.04595 2.56851 + vertex 0.948474 2.05069 2.5668 + endloop + endfacet + facet normal -0.444545 0.364228 0.818363 + outer loop + vertex 0.947138 2.0528 2.56519 + vertex 0.949757 2.05447 2.56587 + vertex 0.94841 2.05647 2.56425 + endloop + endfacet + facet normal -0.498423 0.373663 0.782273 + outer loop + vertex 0.947138 2.0528 2.56519 + vertex 0.94841 2.05647 2.56425 + vertex 0.945089 2.05337 2.56362 + endloop + endfacet + facet normal -0.501915 0.378325 0.777786 + outer loop + vertex 0.945089 2.05337 2.56362 + vertex 0.94841 2.05647 2.56425 + vertex 0.94484 2.05645 2.56196 + endloop + endfacet + facet normal -0.439033 0.352225 0.826552 + outer loop + vertex 0.949757 2.05447 2.56587 + vertex 0.947138 2.0528 2.56519 + vertex 0.948474 2.05069 2.5668 + endloop + endfacet + facet normal -0.609781 0.40398 0.681885 + outer loop + vertex 0.945594 2.06285 2.55921 + vertex 0.943193 2.06089 2.55822 + vertex 0.944655 2.05949 2.56036 + endloop + endfacet + facet normal -0.526933 0.403522 0.748005 + outer loop + vertex 0.944655 2.05949 2.56036 + vertex 0.948177 2.0609 2.56208 + vertex 0.945594 2.06285 2.55921 + endloop + endfacet + facet normal -0.523208 0.370797 0.767309 + outer loop + vertex 0.944655 2.05949 2.56036 + vertex 0.94484 2.05645 2.56196 + vertex 0.948177 2.0609 2.56208 + endloop + endfacet + facet normal -0.506279 0.357635 0.784716 + outer loop + vertex 0.94484 2.05645 2.56196 + vertex 0.94841 2.05647 2.56425 + vertex 0.948177 2.0609 2.56208 + endloop + endfacet + facet normal -0.653244 0.427736 0.624751 + outer loop + vertex 0.946179 2.06745 2.55689 + vertex 0.943505 2.06706 2.55436 + vertex 0.943282 2.0643 2.55601 + endloop + endfacet + facet normal -0.623086 0.436852 0.648787 + outer loop + vertex 0.943282 2.0643 2.55601 + vertex 0.943193 2.06089 2.55822 + vertex 0.945594 2.06285 2.55921 + endloop + endfacet + facet normal -0.640859 0.409556 0.649279 + outer loop + vertex 0.946179 2.06745 2.55689 + vertex 0.943282 2.0643 2.55601 + vertex 0.945594 2.06285 2.55921 + endloop + endfacet + facet normal -0.575927 0.425837 0.697833 + outer loop + vertex 0.946179 2.06745 2.55689 + vertex 0.945594 2.06285 2.55921 + vertex 0.948874 2.06541 2.56035 + endloop + endfacet + facet normal -0.614502 0.371617 0.695908 + outer loop + vertex 0.946179 2.06745 2.55689 + vertex 0.948874 2.06541 2.56035 + vertex 0.949439 2.06842 2.55925 + endloop + endfacet + facet normal -0.550757 0.371283 0.74754 + outer loop + vertex 0.948874 2.06541 2.56035 + vertex 0.945594 2.06285 2.55921 + vertex 0.948177 2.0609 2.56208 + endloop + endfacet + facet normal -0.65226 0.431627 0.623101 + outer loop + vertex 0.943921 2.06977 2.55292 + vertex 0.943505 2.06706 2.55436 + vertex 0.946179 2.06745 2.55689 + endloop + endfacet + facet normal -0.676551 0.399847 0.618386 + outer loop + vertex 0.946376 2.072 2.55416 + vertex 0.943921 2.06977 2.55292 + vertex 0.946179 2.06745 2.55689 + endloop + endfacet + facet normal -0.638651 0.415684 0.647558 + outer loop + vertex 0.946179 2.06745 2.55689 + vertex 0.94905 2.07124 2.55729 + vertex 0.946376 2.072 2.55416 + endloop + endfacet + facet normal -0.6132 0.392304 0.685626 + outer loop + vertex 0.949439 2.06842 2.55925 + vertex 0.94905 2.07124 2.55729 + vertex 0.946179 2.06745 2.55689 + endloop + endfacet + facet normal -0.706848 0.409002 0.577134 + outer loop + vertex 0.946195 2.07653 2.55092 + vertex 0.943766 2.07543 2.54873 + vertex 0.944488 2.07313 2.55124 + endloop + endfacet + facet normal -0.682107 0.415048 0.602051 + outer loop + vertex 0.944488 2.07313 2.55124 + vertex 0.943921 2.06977 2.55292 + vertex 0.946376 2.072 2.55416 + endloop + endfacet + facet normal -0.689492 0.402666 0.602047 + outer loop + vertex 0.946195 2.07653 2.55092 + vertex 0.944488 2.07313 2.55124 + vertex 0.946376 2.072 2.55416 + endloop + endfacet + facet normal -0.673691 0.411652 0.613745 + outer loop + vertex 0.946195 2.07653 2.55092 + vertex 0.946376 2.072 2.55416 + vertex 0.948646 2.0748 2.55477 + endloop + endfacet + facet normal -0.710965 0.350157 0.609851 + outer loop + vertex 0.946195 2.07653 2.55092 + vertex 0.948646 2.0748 2.55477 + vertex 0.948276 2.07713 2.55301 + endloop + endfacet + facet normal -0.652433 0.386092 0.652123 + outer loop + vertex 0.948646 2.0748 2.55477 + vertex 0.946376 2.072 2.55416 + vertex 0.94905 2.07124 2.55729 + endloop + endfacet + facet normal -0.724101 0.40247 0.560086 + outer loop + vertex 0.945855 2.08243 2.5464 + vertex 0.943062 2.08076 2.54399 + vertex 0.944108 2.07839 2.54705 + endloop + endfacet + facet normal -0.706793 0.409623 0.57676 + outer loop + vertex 0.944108 2.07839 2.54705 + vertex 0.943766 2.07543 2.54873 + vertex 0.946195 2.07653 2.55092 + endloop + endfacet + facet normal -0.713095 0.400179 0.575632 + outer loop + vertex 0.945855 2.08243 2.5464 + vertex 0.944108 2.07839 2.54705 + vertex 0.946195 2.07653 2.55092 + endloop + endfacet + facet normal -0.719232 0.396112 0.570789 + outer loop + vertex 0.945855 2.08243 2.5464 + vertex 0.946195 2.07653 2.55092 + vertex 0.948179 2.07968 2.55124 + endloop + endfacet + facet normal -0.738968 0.368029 0.564341 + outer loop + vertex 0.945855 2.08243 2.5464 + vertex 0.948179 2.07968 2.55124 + vertex 0.948234 2.0823 2.5496 + endloop + endfacet + facet normal -0.705734 0.385238 0.594584 + outer loop + vertex 0.948179 2.07968 2.55124 + vertex 0.946195 2.07653 2.55092 + vertex 0.948276 2.07713 2.55301 + endloop + endfacet + facet normal -0.744356 0.406986 0.529431 + outer loop + vertex 0.944666 2.08721 2.54131 + vertex 0.943008 2.08727 2.53894 + vertex 0.943013 2.08446 2.54111 + endloop + endfacet + facet normal -0.723763 0.418269 0.548834 + outer loop + vertex 0.943013 2.08446 2.54111 + vertex 0.943062 2.08076 2.54399 + vertex 0.945855 2.08243 2.5464 + endloop + endfacet + facet normal -0.734864 0.399923 0.547756 + outer loop + vertex 0.943013 2.08446 2.54111 + vertex 0.945855 2.08243 2.5464 + vertex 0.944666 2.08721 2.54131 + endloop + endfacet + facet normal -0.753443 0.381952 0.535198 + outer loop + vertex 0.944666 2.08721 2.54131 + vertex 0.945855 2.08243 2.5464 + vertex 0.946938 2.08759 2.54424 + endloop + endfacet + facet normal -0.737652 0.386389 0.55369 + outer loop + vertex 0.945855 2.08243 2.5464 + vertex 0.94848 2.08498 2.54812 + vertex 0.946938 2.08759 2.54424 + endloop + endfacet + facet normal -0.735409 0.378417 0.562115 + outer loop + vertex 0.948234 2.0823 2.5496 + vertex 0.94848 2.08498 2.54812 + vertex 0.945855 2.08243 2.5464 + endloop + endfacet + facet normal -0.760732 0.360561 0.539706 + outer loop + vertex 0.943428 2.08996 2.53774 + vertex 0.943008 2.08727 2.53894 + vertex 0.944666 2.08721 2.54131 + endloop + endfacet + facet normal -0.771017 0.347782 0.533462 + outer loop + vertex 0.945795 2.09154 2.54012 + vertex 0.943428 2.08996 2.53774 + vertex 0.944666 2.08721 2.54131 + endloop + endfacet + facet normal -0.753582 0.362841 0.548143 + outer loop + vertex 0.947989 2.09087 2.54352 + vertex 0.946938 2.08759 2.54424 + vertex 0.948886 2.08853 2.5463 + endloop + endfacet + facet normal -0.748173 0.362746 0.555564 + outer loop + vertex 0.947989 2.09087 2.54352 + vertex 0.945795 2.09154 2.54012 + vertex 0.946938 2.08759 2.54424 + endloop + endfacet + facet normal -0.761751 0.3488 0.545961 + outer loop + vertex 0.945795 2.09154 2.54012 + vertex 0.944666 2.08721 2.54131 + vertex 0.946938 2.08759 2.54424 + endloop + endfacet + facet normal -0.75327 0.366234 0.546312 + outer loop + vertex 0.948886 2.08853 2.5463 + vertex 0.946938 2.08759 2.54424 + vertex 0.94848 2.08498 2.54812 + endloop + endfacet + facet normal -0.763315 0.190686 0.617243 + outer loop + vertex 0.94561 2.09728 2.53742 + vertex 0.943004 2.09642 2.53446 + vertex 0.944007 2.09357 2.53658 + endloop + endfacet + facet normal -0.769737 0.303109 0.56181 + outer loop + vertex 0.944007 2.09357 2.53658 + vertex 0.943428 2.08996 2.53774 + vertex 0.945795 2.09154 2.54012 + endloop + endfacet + facet normal -0.810355 0.228433 0.539577 + outer loop + vertex 0.94561 2.09728 2.53742 + vertex 0.944007 2.09357 2.53658 + vertex 0.945795 2.09154 2.54012 + endloop + endfacet + facet normal -0.736413 0.269101 0.62071 + outer loop + vertex 0.94561 2.09728 2.53742 + vertex 0.945795 2.09154 2.54012 + vertex 0.947837 2.09444 2.54129 + endloop + endfacet + facet normal -0.703481 0.316393 0.636404 + outer loop + vertex 0.94561 2.09728 2.53742 + vertex 0.947837 2.09444 2.54129 + vertex 0.947718 2.09741 2.53968 + endloop + endfacet + facet normal -0.767116 0.315599 0.558507 + outer loop + vertex 0.947837 2.09444 2.54129 + vertex 0.945795 2.09154 2.54012 + vertex 0.947989 2.09087 2.54352 + endloop + endfacet + facet normal -0.756761 0.0517 0.651644 + outer loop + vertex 0.942667 2.10121 2.53369 + vertex 0.943004 2.09642 2.53446 + vertex 0.94561 2.09728 2.53742 + endloop + endfacet + facet normal -0.686799 0.158849 0.709277 + outer loop + vertex 0.945779 2.10322 2.53625 + vertex 0.942667 2.10121 2.53369 + vertex 0.94561 2.09728 2.53742 + endloop + endfacet + facet normal -0.68557 0.159039 0.710423 + outer loop + vertex 0.94561 2.09728 2.53742 + vertex 0.948052 2.10056 2.53904 + vertex 0.945779 2.10322 2.53625 + endloop + endfacet + facet normal -0.721674 0.211243 0.659213 + outer loop + vertex 0.947718 2.09741 2.53968 + vertex 0.948052 2.10056 2.53904 + vertex 0.94561 2.09728 2.53742 + endloop + endfacet + facet normal -0.652357 0.045591 0.75654 + outer loop + vertex 0.943501 2.10578 2.53413 + vertex 0.942667 2.10121 2.53369 + vertex 0.945779 2.10322 2.53625 + endloop + endfacet + facet normal -0.579504 0.147561 0.801499 + outer loop + vertex 0.945997 2.10823 2.53549 + vertex 0.943501 2.10578 2.53413 + vertex 0.945779 2.10322 2.53625 + endloop + endfacet + facet normal -0.626774 0.144166 0.765748 + outer loop + vertex 0.945779 2.10322 2.53625 + vertex 0.949071 2.10597 2.53843 + vertex 0.945997 2.10823 2.53549 + endloop + endfacet + facet normal -0.653411 0.205534 0.728567 + outer loop + vertex 0.948052 2.10056 2.53904 + vertex 0.949071 2.10597 2.53843 + vertex 0.945779 2.10322 2.53625 + endloop + endfacet + facet normal -0.554388 0.108801 0.825116 + outer loop + vertex 0.942819 2.10985 2.53314 + vertex 0.943501 2.10578 2.53413 + vertex 0.945997 2.10823 2.53549 + endloop + endfacet + facet normal -0.479418 0.270107 0.834985 + outer loop + vertex 0.945912 2.11263 2.53401 + vertex 0.942819 2.10985 2.53314 + vertex 0.945997 2.10823 2.53549 + endloop + endfacet + facet normal -0.546807 0.256138 0.797117 + outer loop + vertex 0.945997 2.10823 2.53549 + vertex 0.949038 2.11121 2.53661 + vertex 0.945912 2.11263 2.53401 + endloop + endfacet + facet normal -0.555454 0.268842 0.786889 + outer loop + vertex 0.949071 2.10597 2.53843 + vertex 0.949038 2.11121 2.53661 + vertex 0.945997 2.10823 2.53549 + endloop + endfacet + facet normal -0.44869 0.507617 0.735528 + outer loop + vertex 0.945502 2.11677 2.53124 + vertex 0.940885 2.11537 2.52939 + vertex 0.943224 2.11355 2.53207 + endloop + endfacet + facet normal -0.492886 0.289611 0.820481 + outer loop + vertex 0.943224 2.11355 2.53207 + vertex 0.942819 2.10985 2.53314 + vertex 0.945912 2.11263 2.53401 + endloop + endfacet + facet normal -0.397611 0.482909 0.780195 + outer loop + vertex 0.945502 2.11677 2.53124 + vertex 0.943224 2.11355 2.53207 + vertex 0.945912 2.11263 2.53401 + endloop + endfacet + facet normal -0.520724 0.438684 0.732395 + outer loop + vertex 0.945502 2.11677 2.53124 + vertex 0.945912 2.11263 2.53401 + vertex 0.948662 2.11519 2.53443 + endloop + endfacet + facet normal -0.492591 0.480875 0.725337 + outer loop + vertex 0.945502 2.11677 2.53124 + vertex 0.948662 2.11519 2.53443 + vertex 0.9483 2.11736 2.53275 + endloop + endfacet + facet normal -0.479958 0.385714 0.78795 + outer loop + vertex 0.948662 2.11519 2.53443 + vertex 0.945912 2.11263 2.53401 + vertex 0.949038 2.11121 2.53661 + endloop + endfacet + facet normal -0.395827 0.703788 0.589918 + outer loop + vertex 0.945625 2.12053 2.5275 + vertex 0.941495 2.12089 2.5243 + vertex 0.94257 2.1187 2.52764 + endloop + endfacet + facet normal -0.448327 0.583509 0.677141 + outer loop + vertex 0.94257 2.1187 2.52764 + vertex 0.940885 2.11537 2.52939 + vertex 0.945502 2.11677 2.53124 + endloop + endfacet + facet normal -0.367562 0.661839 0.653351 + outer loop + vertex 0.945625 2.12053 2.5275 + vertex 0.94257 2.1187 2.52764 + vertex 0.945502 2.11677 2.53124 + endloop + endfacet + facet normal -0.488297 0.623374 0.610714 + outer loop + vertex 0.945625 2.12053 2.5275 + vertex 0.945502 2.11677 2.53124 + vertex 0.948284 2.11913 2.53105 + endloop + endfacet + facet normal -0.446178 0.667186 0.59648 + outer loop + vertex 0.945625 2.12053 2.5275 + vertex 0.948284 2.11913 2.53105 + vertex 0.948554 2.1209 2.52928 + endloop + endfacet + facet normal -0.47262 0.607205 0.638696 + outer loop + vertex 0.948284 2.11913 2.53105 + vertex 0.945502 2.11677 2.53124 + vertex 0.9483 2.11736 2.53275 + endloop + endfacet + facet normal -0.153264 0.783823 0.601773 + outer loop + vertex 0.945579 2.1275 2.5153 + vertex 0.942999 2.12786 2.51418 + vertex 0.943725 2.12584 2.51699 + endloop + endfacet + facet normal -0.261459 0.81625 0.515146 + outer loop + vertex 0.947419 2.12648 2.51786 + vertex 0.945579 2.1275 2.5153 + vertex 0.943725 2.12584 2.51699 + endloop + endfacet + facet normal -0.240325 0.899828 0.364079 + outer loop + vertex 0.947419 2.12648 2.51786 + vertex 0.943725 2.12584 2.51699 + vertex 0.948516 2.12512 2.52195 + endloop + endfacet + facet normal -0.33352 0.831552 0.444168 + outer loop + vertex 0.948516 2.12512 2.52195 + vertex 0.943725 2.12584 2.51699 + vertex 0.943722 2.12316 2.52201 + endloop + endfacet + facet normal -0.314628 0.809012 0.496497 + outer loop + vertex 0.945625 2.12053 2.5275 + vertex 0.943722 2.12316 2.52201 + vertex 0.941495 2.12089 2.5243 + endloop + endfacet + facet normal -0.408799 0.759764 0.505611 + outer loop + vertex 0.945625 2.12053 2.5275 + vertex 0.94931 2.12267 2.52727 + vertex 0.943722 2.12316 2.52201 + endloop + endfacet + facet normal -0.335396 0.835839 0.434606 + outer loop + vertex 0.94931 2.12267 2.52727 + vertex 0.948516 2.12512 2.52195 + vertex 0.943722 2.12316 2.52201 + endloop + endfacet + facet normal -0.406294 0.756223 0.512885 + outer loop + vertex 0.94931 2.12267 2.52727 + vertex 0.945625 2.12053 2.5275 + vertex 0.948554 2.1209 2.52928 + endloop + endfacet + facet normal -0.39762 0.0121557 0.917469 + outer loop + vertex 0.945579 2.1275 2.5153 + vertex 0.945 2.13134 2.515 + vertex 0.942999 2.12786 2.51418 + endloop + endfacet + facet normal -0.374561 0.0163914 0.927058 + outer loop + vertex 0.945579 2.1275 2.5153 + vertex 0.949546 2.1285 2.51689 + vertex 0.945 2.13134 2.515 + endloop + endfacet + facet normal -0.0698836 0.472153 0.878742 + outer loop + vertex 0.949546 2.1285 2.51689 + vertex 0.95 2.13208 2.515 + vertex 0.945 2.13134 2.515 + endloop + endfacet + facet normal -0.408433 0.707279 0.577008 + outer loop + vertex 0.949546 2.1285 2.51689 + vertex 0.945579 2.1275 2.5153 + vertex 0.947419 2.12648 2.51786 + endloop + endfacet + facet normal -0.4273 -0.862053 0.272542 + outer loop + vertex 0.955 0.894197 2.515 + vertex 0.955 0.895 2.51754 + vertex 0.95338 0.895 2.515 + endloop + endfacet + facet normal -0.484887 -0.818068 0.309273 + outer loop + vertex 0.95338 0.895 2.515 + vertex 0.955 0.895 2.51754 + vertex 0.955 0.89593 2.52 + endloop + endfacet + facet normal -0.391529 -0.873493 0.289334 + outer loop + vertex 0.95338 0.895 2.515 + vertex 0.955 0.89593 2.52 + vertex 0.95 0.896515 2.515 + endloop + endfacet + facet normal -0.0746346 -0.996329 -0.0419409 + outer loop + vertex 0.95 0.896515 2.515 + vertex 0.955 0.89593 2.52 + vertex 0.948888 0.89651 2.5171 + endloop + endfacet + facet normal -0.111497 -0.993103 0.0362722 + outer loop + vertex 0.955 0.89593 2.52 + vertex 0.95315 0.896181 2.52119 + vertex 0.948888 0.89651 2.5171 + endloop + endfacet + facet normal -0.239609 -0.955367 0.172806 + outer loop + vertex 0.95315 0.896181 2.52119 + vertex 0.948075 0.897431 2.52106 + vertex 0.948888 0.89651 2.5171 + endloop + endfacet + facet normal -0.286401 -0.874763 0.39085 + outer loop + vertex 0.94918 0.898316 2.52474 + vertex 0.953049 0.897476 2.52569 + vertex 0.951265 0.898806 2.52736 + endloop + endfacet + facet normal -0.272867 -0.913495 0.301778 + outer loop + vertex 0.94918 0.898316 2.52474 + vertex 0.948075 0.897431 2.52106 + vertex 0.953049 0.897476 2.52569 + endloop + endfacet + facet normal -0.236863 -0.935178 0.263321 + outer loop + vertex 0.948075 0.897431 2.52106 + vertex 0.95315 0.896181 2.52119 + vertex 0.953049 0.897476 2.52569 + endloop + endfacet + facet normal -0.307853 -0.876745 0.369519 + outer loop + vertex 0.953049 0.897476 2.52569 + vertex 0.954112 0.898548 2.52912 + vertex 0.951265 0.898806 2.52736 + endloop + endfacet + facet normal -0.363569 -0.820037 0.441992 + outer loop + vertex 0.94918 0.898316 2.52474 + vertex 0.951265 0.898806 2.52736 + vertex 0.947388 0.899835 2.52608 + endloop + endfacet + facet normal -0.391458 -0.757751 0.522086 + outer loop + vertex 0.951265 0.898806 2.52736 + vertex 0.954112 0.898548 2.52912 + vertex 0.95208 0.900481 2.53041 + endloop + endfacet + facet normal -0.375586 -0.765668 0.522195 + outer loop + vertex 0.951265 0.898806 2.52736 + vertex 0.95208 0.900481 2.53041 + vertex 0.947388 0.899835 2.52608 + endloop + endfacet + facet normal -0.419229 -0.713232 0.561737 + outer loop + vertex 0.947388 0.899835 2.52608 + vertex 0.95208 0.900481 2.53041 + vertex 0.946535 0.902528 2.52887 + endloop + endfacet + facet normal -0.415679 -0.640131 0.646098 + outer loop + vertex 0.95208 0.900481 2.53041 + vertex 0.94869 0.904244 2.53195 + vertex 0.946535 0.902528 2.52887 + endloop + endfacet + facet normal -0.452511 -0.656033 0.604032 + outer loop + vertex 0.953779 0.902895 2.5343 + vertex 0.94869 0.904244 2.53195 + vertex 0.95208 0.900481 2.53041 + endloop + endfacet + facet normal -0.50987 -0.503764 0.69732 + outer loop + vertex 0.953591 0.905475 2.53647 + vertex 0.951042 0.908007 2.53644 + vertex 0.949278 0.907281 2.53463 + endloop + endfacet + facet normal -0.513724 -0.574518 0.637194 + outer loop + vertex 0.953591 0.905475 2.53647 + vertex 0.949278 0.907281 2.53463 + vertex 0.953779 0.902895 2.5343 + endloop + endfacet + facet normal -0.466902 -0.53162 0.70667 + outer loop + vertex 0.953779 0.902895 2.5343 + vertex 0.949278 0.907281 2.53463 + vertex 0.94869 0.904244 2.53195 + endloop + endfacet + facet normal -0.492991 -0.48645 0.721336 + outer loop + vertex 0.953591 0.905475 2.53647 + vertex 0.953423 0.908547 2.53843 + vertex 0.951042 0.908007 2.53644 + endloop + endfacet + facet normal -0.562568 -0.417078 0.713837 + outer loop + vertex 0.949278 0.907281 2.53463 + vertex 0.951042 0.908007 2.53644 + vertex 0.948939 0.910695 2.53635 + endloop + endfacet + facet normal -0.58525 -0.324778 0.742968 + outer loop + vertex 0.952898 0.911902 2.53993 + vertex 0.9517 0.915378 2.54051 + vertex 0.950022 0.913247 2.53825 + endloop + endfacet + facet normal -0.594463 -0.404043 0.695243 + outer loop + vertex 0.953423 0.908547 2.53843 + vertex 0.952898 0.911902 2.53993 + vertex 0.950022 0.913247 2.53825 + endloop + endfacet + facet normal -0.527179 -0.352413 0.773232 + outer loop + vertex 0.953423 0.908547 2.53843 + vertex 0.950022 0.913247 2.53825 + vertex 0.948939 0.910695 2.53635 + endloop + endfacet + facet normal -0.535189 -0.394596 0.746905 + outer loop + vertex 0.953423 0.908547 2.53843 + vertex 0.948939 0.910695 2.53635 + vertex 0.951042 0.908007 2.53644 + endloop + endfacet + facet normal -0.611189 -0.329828 0.719487 + outer loop + vertex 0.952898 0.911902 2.53993 + vertex 0.955095 0.912596 2.54212 + vertex 0.9517 0.915378 2.54051 + endloop + endfacet + facet normal -0.626695 -0.276807 0.728445 + outer loop + vertex 0.948509 0.917488 2.53856 + vertex 0.950022 0.913247 2.53825 + vertex 0.9517 0.915378 2.54051 + endloop + endfacet + facet normal -0.623853 -0.266872 0.734566 + outer loop + vertex 0.950605 0.919534 2.54109 + vertex 0.948509 0.917488 2.53856 + vertex 0.9517 0.915378 2.54051 + endloop + endfacet + facet normal -0.658109 -0.271394 0.702309 + outer loop + vertex 0.9517 0.915378 2.54051 + vertex 0.954407 0.917105 2.54371 + vertex 0.950605 0.919534 2.54109 + endloop + endfacet + facet normal -0.617371 -0.344444 0.707257 + outer loop + vertex 0.955095 0.912596 2.54212 + vertex 0.954407 0.917105 2.54371 + vertex 0.9517 0.915378 2.54051 + endloop + endfacet + facet normal -0.664522 -0.205396 0.718486 + outer loop + vertex 0.94799 0.921492 2.53923 + vertex 0.948509 0.917488 2.53856 + vertex 0.950605 0.919534 2.54109 + endloop + endfacet + facet normal -0.674284 -0.236335 0.699634 + outer loop + vertex 0.949747 0.922269 2.54118 + vertex 0.94799 0.921492 2.53923 + vertex 0.950605 0.919534 2.54109 + endloop + endfacet + facet normal -0.719871 -0.248785 0.64799 + outer loop + vertex 0.950605 0.919534 2.54109 + vertex 0.951933 0.922997 2.54389 + vertex 0.949747 0.922269 2.54118 + endloop + endfacet + facet normal -0.664208 -0.299916 0.684747 + outer loop + vertex 0.954407 0.917105 2.54371 + vertex 0.951933 0.922997 2.54389 + vertex 0.950605 0.919534 2.54109 + endloop + endfacet + facet normal -0.673032 -0.239496 0.699764 + outer loop + vertex 0.94799 0.921492 2.53923 + vertex 0.949747 0.922269 2.54118 + vertex 0.9486 0.924714 2.54092 + endloop + endfacet + facet normal -0.733361 -0.340203 0.588595 + outer loop + vertex 0.952124 0.926834 2.5461 + vertex 0.95118 0.93067 2.54714 + vertex 0.949683 0.92782 2.54363 + endloop + endfacet + facet normal -0.735331 -0.31052 0.602383 + outer loop + vertex 0.951933 0.922997 2.54389 + vertex 0.952124 0.926834 2.5461 + vertex 0.949683 0.92782 2.54363 + endloop + endfacet + facet normal -0.716552 -0.300291 0.629586 + outer loop + vertex 0.951933 0.922997 2.54389 + vertex 0.949683 0.92782 2.54363 + vertex 0.9486 0.924714 2.54092 + endloop + endfacet + facet normal -0.714392 -0.264557 0.647806 + outer loop + vertex 0.951933 0.922997 2.54389 + vertex 0.9486 0.924714 2.54092 + vertex 0.949747 0.922269 2.54118 + endloop + endfacet + facet normal -0.725479 -0.3408 0.597943 + outer loop + vertex 0.952124 0.926834 2.5461 + vertex 0.953465 0.927827 2.5483 + vertex 0.95118 0.93067 2.54714 + endloop + endfacet + facet normal -0.738335 -0.334173 0.585824 + outer loop + vertex 0.947327 0.932879 2.54355 + vertex 0.949683 0.92782 2.54363 + vertex 0.95118 0.93067 2.54714 + endloop + endfacet + facet normal -0.738416 -0.366622 0.565977 + outer loop + vertex 0.949145 0.935211 2.54743 + vertex 0.947327 0.932879 2.54355 + vertex 0.95118 0.93067 2.54714 + endloop + endfacet + facet normal -0.718582 -0.329357 0.612506 + outer loop + vertex 0.954305 0.929965 2.55043 + vertex 0.95118 0.93067 2.54714 + vertex 0.953465 0.927827 2.5483 + endloop + endfacet + facet normal -0.710176 -0.377669 0.594152 + outer loop + vertex 0.954305 0.929965 2.55043 + vertex 0.952095 0.934019 2.55037 + vertex 0.95118 0.93067 2.54714 + endloop + endfacet + facet normal -0.726927 -0.362559 0.583205 + outer loop + vertex 0.952095 0.934019 2.55037 + vertex 0.949145 0.935211 2.54743 + vertex 0.95118 0.93067 2.54714 + endloop + endfacet + facet normal -0.684229 -0.362927 0.632546 + outer loop + vertex 0.954305 0.929965 2.55043 + vertex 0.955339 0.932765 2.55316 + vertex 0.952095 0.934019 2.55037 + endloop + endfacet + facet normal -0.738913 -0.365915 0.565785 + outer loop + vertex 0.947327 0.932879 2.54355 + vertex 0.949145 0.935211 2.54743 + vertex 0.947 0.936712 2.5456 + endloop + endfacet + facet normal -0.740333 -0.391439 0.546519 + outer loop + vertex 0.947225 0.939063 2.54759 + vertex 0.947 0.936712 2.5456 + vertex 0.949145 0.935211 2.54743 + endloop + endfacet + facet normal -0.726478 -0.385456 0.568905 + outer loop + vertex 0.947225 0.939063 2.54759 + vertex 0.949145 0.935211 2.54743 + vertex 0.949944 0.9375 2.55 + endloop + endfacet + facet normal -0.724202 -0.387754 0.570243 + outer loop + vertex 0.949944 0.9375 2.55 + vertex 0.949145 0.935211 2.54743 + vertex 0.952095 0.934019 2.55037 + endloop + endfacet + facet normal -0.701566 -0.369674 0.609218 + outer loop + vertex 0.952095 0.934019 2.55037 + vertex 0.952692 0.937828 2.55337 + vertex 0.949944 0.9375 2.55 + endloop + endfacet + facet normal -0.682954 -0.382767 0.622144 + outer loop + vertex 0.955339 0.932765 2.55316 + vertex 0.952692 0.937828 2.55337 + vertex 0.952095 0.934019 2.55037 + endloop + endfacet + facet normal -0.726358 -0.392846 0.563983 + outer loop + vertex 0.947225 0.939063 2.54759 + vertex 0.949944 0.9375 2.55 + vertex 0.948555 0.941079 2.55071 + endloop + endfacet + facet normal -0.652164 -0.39366 0.647853 + outer loop + vertex 0.953815 0.940812 2.55614 + vertex 0.951326 0.945108 2.55625 + vertex 0.949991 0.943039 2.55364 + endloop + endfacet + facet normal -0.649535 -0.372105 0.663055 + outer loop + vertex 0.952692 0.937828 2.55337 + vertex 0.953815 0.940812 2.55614 + vertex 0.949991 0.943039 2.55364 + endloop + endfacet + facet normal -0.695449 -0.392626 0.601827 + outer loop + vertex 0.952692 0.937828 2.55337 + vertex 0.949991 0.943039 2.55364 + vertex 0.948555 0.941079 2.55071 + endloop + endfacet + facet normal -0.694604 -0.388646 0.605376 + outer loop + vertex 0.952692 0.937828 2.55337 + vertex 0.948555 0.941079 2.55071 + vertex 0.949944 0.9375 2.55 + endloop + endfacet + facet normal -0.602158 -0.366187 0.709445 + outer loop + vertex 0.953815 0.940812 2.55614 + vertex 0.955092 0.9432 2.55846 + vertex 0.951326 0.945108 2.55625 + endloop + endfacet + facet normal -0.669223 -0.374803 0.641609 + outer loop + vertex 0.947349 0.947965 2.55377 + vertex 0.949991 0.943039 2.55364 + vertex 0.951326 0.945108 2.55625 + endloop + endfacet + facet normal -0.674641 -0.401762 0.619231 + outer loop + vertex 0.9497 0.947864 2.55626 + vertex 0.947349 0.947965 2.55377 + vertex 0.951326 0.945108 2.55625 + endloop + endfacet + facet normal -0.624206 -0.372397 0.686795 + outer loop + vertex 0.951326 0.945108 2.55625 + vertex 0.951986 0.948233 2.55854 + vertex 0.9497 0.947864 2.55626 + endloop + endfacet + facet normal -0.604516 -0.384516 0.697644 + outer loop + vertex 0.955092 0.9432 2.55846 + vertex 0.951986 0.948233 2.55854 + vertex 0.951326 0.945108 2.55625 + endloop + endfacet + facet normal -0.679072 -0.386604 0.624018 + outer loop + vertex 0.947349 0.947965 2.55377 + vertex 0.9497 0.947864 2.55626 + vertex 0.948176 0.950447 2.5562 + endloop + endfacet + facet normal -0.616707 -0.389435 0.684115 + outer loop + vertex 0.951932 0.951617 2.56033 + vertex 0.95057 0.954474 2.56072 + vertex 0.948441 0.953497 2.55825 + endloop + endfacet + facet normal -0.614824 -0.375558 0.693504 + outer loop + vertex 0.951986 0.948233 2.55854 + vertex 0.951932 0.951617 2.56033 + vertex 0.948441 0.953497 2.55825 + endloop + endfacet + facet normal -0.635437 -0.390971 0.665854 + outer loop + vertex 0.951986 0.948233 2.55854 + vertex 0.948441 0.953497 2.55825 + vertex 0.948176 0.950447 2.5562 + endloop + endfacet + facet normal -0.630055 -0.356197 0.69004 + outer loop + vertex 0.951986 0.948233 2.55854 + vertex 0.948176 0.950447 2.5562 + vertex 0.9497 0.947864 2.55626 + endloop + endfacet + facet normal -0.533031 -0.360859 0.765283 + outer loop + vertex 0.951932 0.951617 2.56033 + vertex 0.953939 0.952997 2.56237 + vertex 0.95057 0.954474 2.56072 + endloop + endfacet + facet normal -0.616007 -0.390711 0.684017 + outer loop + vertex 0.948441 0.953497 2.55825 + vertex 0.95057 0.954474 2.56072 + vertex 0.948247 0.956823 2.55997 + endloop + endfacet + facet normal -0.588899 -0.349611 0.728677 + outer loop + vertex 0.95057 0.954474 2.56072 + vertex 0.950274 0.957531 2.56195 + vertex 0.948247 0.956823 2.55997 + endloop + endfacet + facet normal -0.532779 -0.359239 0.766221 + outer loop + vertex 0.95057 0.954474 2.56072 + vertex 0.953939 0.952997 2.56237 + vertex 0.950274 0.957531 2.56195 + endloop + endfacet + facet normal -0.513126 -0.341364 0.78751 + outer loop + vertex 0.953939 0.952997 2.56237 + vertex 0.953799 0.95757 2.56426 + vertex 0.950274 0.957531 2.56195 + endloop + endfacet + facet normal -0.525908 -0.373768 0.764014 + outer loop + vertex 0.952624 0.961504 2.56529 + vertex 0.950924 0.964566 2.56562 + vertex 0.94852 0.962901 2.56315 + endloop + endfacet + facet normal -0.524847 -0.358084 0.772212 + outer loop + vertex 0.952624 0.961504 2.56529 + vertex 0.94852 0.962901 2.56315 + vertex 0.953799 0.95757 2.56426 + endloop + endfacet + facet normal -0.512779 -0.343038 0.787009 + outer loop + vertex 0.953799 0.95757 2.56426 + vertex 0.94852 0.962901 2.56315 + vertex 0.950274 0.957531 2.56195 + endloop + endfacet + facet normal -0.467104 -0.346413 0.813518 + outer loop + vertex 0.952624 0.961504 2.56529 + vertex 0.954661 0.963128 2.56715 + vertex 0.950924 0.964566 2.56562 + endloop + endfacet + facet normal -0.522783 -0.378215 0.763971 + outer loop + vertex 0.94852 0.962901 2.56315 + vertex 0.950924 0.964566 2.56562 + vertex 0.948331 0.966976 2.56504 + endloop + endfacet + facet normal -0.496002 -0.341065 0.798534 + outer loop + vertex 0.950924 0.964566 2.56562 + vertex 0.950744 0.968349 2.56712 + vertex 0.948331 0.966976 2.56504 + endloop + endfacet + facet normal -0.466996 -0.345774 0.813852 + outer loop + vertex 0.950924 0.964566 2.56562 + vertex 0.954661 0.963128 2.56715 + vertex 0.950744 0.968349 2.56712 + endloop + endfacet + facet normal -0.456781 -0.33806 0.82284 + outer loop + vertex 0.954661 0.963128 2.56715 + vertex 0.95516 0.967177 2.56909 + vertex 0.950744 0.968349 2.56712 + endloop + endfacet + facet normal -0.456901 -0.339892 0.822019 + outer loop + vertex 0.95516 0.967177 2.56909 + vertex 0.952082 0.972397 2.56954 + vertex 0.950744 0.968349 2.56712 + endloop + endfacet + facet normal -0.461408 -0.337489 0.82049 + outer loop + vertex 0.950744 0.968349 2.56712 + vertex 0.952082 0.972397 2.56954 + vertex 0.947701 0.973547 2.56755 + endloop + endfacet + facet normal -0.451421 -0.331772 0.828339 + outer loop + vertex 0.951735 0.976222 2.57088 + vertex 0.950124 0.979251 2.57122 + vertex 0.94819 0.977612 2.56951 + endloop + endfacet + facet normal -0.451515 -0.332253 0.828095 + outer loop + vertex 0.951735 0.976222 2.57088 + vertex 0.94819 0.977612 2.56951 + vertex 0.952082 0.972397 2.56954 + endloop + endfacet + facet normal -0.461545 -0.339788 0.819463 + outer loop + vertex 0.952082 0.972397 2.56954 + vertex 0.94819 0.977612 2.56951 + vertex 0.947701 0.973547 2.56755 + endloop + endfacet + facet normal -0.459147 -0.335251 0.822673 + outer loop + vertex 0.951735 0.976222 2.57088 + vertex 0.953653 0.977951 2.57266 + vertex 0.950124 0.979251 2.57122 + endloop + endfacet + facet normal -0.44748 -0.336616 0.828524 + outer loop + vertex 0.94819 0.977612 2.56951 + vertex 0.950124 0.979251 2.57122 + vertex 0.947537 0.981389 2.57069 + endloop + endfacet + facet normal -0.441934 -0.328349 0.834794 + outer loop + vertex 0.950124 0.979251 2.57122 + vertex 0.949505 0.983017 2.57237 + vertex 0.947537 0.981389 2.57069 + endloop + endfacet + facet normal -0.457994 -0.328328 0.826101 + outer loop + vertex 0.950124 0.979251 2.57122 + vertex 0.953653 0.977951 2.57266 + vertex 0.949505 0.983017 2.57237 + endloop + endfacet + facet normal -0.448803 -0.320344 0.83424 + outer loop + vertex 0.953653 0.977951 2.57266 + vertex 0.953726 0.982543 2.57446 + vertex 0.949505 0.983017 2.57237 + endloop + endfacet + facet normal -0.445203 -0.328526 0.832985 + outer loop + vertex 0.953183 0.986212 2.57553 + vertex 0.951458 0.989912 2.57607 + vertex 0.950071 0.987101 2.57422 + endloop + endfacet + facet normal -0.44346 -0.311396 0.840462 + outer loop + vertex 0.953183 0.986212 2.57553 + vertex 0.950071 0.987101 2.57422 + vertex 0.953726 0.982543 2.57446 + endloop + endfacet + facet normal -0.449056 -0.316133 0.835708 + outer loop + vertex 0.953726 0.982543 2.57446 + vertex 0.950071 0.987101 2.57422 + vertex 0.949505 0.983017 2.57237 + endloop + endfacet + facet normal -0.487835 -0.34394 0.802323 + outer loop + vertex 0.953183 0.986212 2.57553 + vertex 0.955218 0.987143 2.57717 + vertex 0.951458 0.989912 2.57607 + endloop + endfacet + facet normal -0.436634 -0.334243 0.835244 + outer loop + vertex 0.947005 0.992337 2.57471 + vertex 0.950071 0.987101 2.57422 + vertex 0.951458 0.989912 2.57607 + endloop + endfacet + facet normal -0.433247 -0.325001 0.840638 + outer loop + vertex 0.949527 0.993781 2.57657 + vertex 0.947005 0.992337 2.57471 + vertex 0.951458 0.989912 2.57607 + endloop + endfacet + facet normal -0.475032 -0.342 0.81079 + outer loop + vertex 0.951458 0.989912 2.57607 + vertex 0.953767 0.99248 2.57851 + vertex 0.949527 0.993781 2.57657 + endloop + endfacet + facet normal -0.482662 -0.334023 0.809608 + outer loop + vertex 0.955218 0.987143 2.57717 + vertex 0.953767 0.99248 2.57851 + vertex 0.951458 0.989912 2.57607 + endloop + endfacet + facet normal -0.431004 -0.3286 0.840391 + outer loop + vertex 0.947005 0.992337 2.57471 + vertex 0.949527 0.993781 2.57657 + vertex 0.946665 0.996113 2.57602 + endloop + endfacet + facet normal -0.435476 -0.335266 0.835439 + outer loop + vertex 0.949527 0.993781 2.57657 + vertex 0.948634 0.997793 2.57772 + vertex 0.946665 0.996113 2.57602 + endloop + endfacet + facet normal -0.474626 -0.337546 0.812892 + outer loop + vertex 0.949527 0.993781 2.57657 + vertex 0.953767 0.99248 2.57851 + vertex 0.948634 0.997793 2.57772 + endloop + endfacet + facet normal -0.461905 -0.32332 0.825899 + outer loop + vertex 0.953767 0.99248 2.57851 + vertex 0.95257 0.997655 2.57986 + vertex 0.948634 0.997793 2.57772 + endloop + endfacet + facet normal -0.46816 -0.306334 0.828846 + outer loop + vertex 0.953147 1.00057 2.58137 + vertex 0.950595 1.00427 2.58129 + vertex 0.948677 1.00245 2.57954 + endloop + endfacet + facet normal -0.47267 -0.327574 0.818094 + outer loop + vertex 0.953147 1.00057 2.58137 + vertex 0.948677 1.00245 2.57954 + vertex 0.95257 0.997655 2.57986 + endloop + endfacet + facet normal -0.462529 -0.318708 0.82734 + outer loop + vertex 0.95257 0.997655 2.57986 + vertex 0.948677 1.00245 2.57954 + vertex 0.948634 0.997793 2.57772 + endloop + endfacet + facet normal -0.49266 -0.32371 0.807773 + outer loop + vertex 0.953147 1.00057 2.58137 + vertex 0.95411 1.00376 2.58323 + vertex 0.950595 1.00427 2.58129 + endloop + endfacet + facet normal -0.46465 -0.310466 0.829283 + outer loop + vertex 0.948677 1.00245 2.57954 + vertex 0.950595 1.00427 2.58129 + vertex 0.947728 1.0064 2.58048 + endloop + endfacet + facet normal -0.470974 -0.322018 0.821272 + outer loop + vertex 0.950595 1.00427 2.58129 + vertex 0.949542 1.0082 2.58223 + vertex 0.947728 1.0064 2.58048 + endloop + endfacet + facet normal -0.492613 -0.324524 0.807475 + outer loop + vertex 0.950595 1.00427 2.58129 + vertex 0.95411 1.00376 2.58323 + vertex 0.949542 1.0082 2.58223 + endloop + endfacet + facet normal -0.489447 -0.320469 0.811013 + outer loop + vertex 0.95411 1.00376 2.58323 + vertex 0.953019 1.00831 2.58437 + vertex 0.949542 1.0082 2.58223 + endloop + endfacet + facet normal -0.4892 -0.310765 0.814928 + outer loop + vertex 0.952896 1.0113 2.58546 + vertex 0.951396 1.01487 2.58592 + vertex 0.949937 1.01216 2.58402 + endloop + endfacet + facet normal -0.489699 -0.316928 0.812251 + outer loop + vertex 0.952896 1.0113 2.58546 + vertex 0.949937 1.01216 2.58402 + vertex 0.953019 1.00831 2.58437 + endloop + endfacet + facet normal -0.490085 -0.31727 0.811885 + outer loop + vertex 0.953019 1.00831 2.58437 + vertex 0.949937 1.01216 2.58402 + vertex 0.949542 1.0082 2.58223 + endloop + endfacet + facet normal -0.47147 -0.304933 0.827485 + outer loop + vertex 0.952896 1.0113 2.58546 + vertex 0.955024 1.0124 2.58708 + vertex 0.951396 1.01487 2.58592 + endloop + endfacet + facet normal -0.483736 -0.314894 0.816603 + outer loop + vertex 0.947173 1.01729 2.58436 + vertex 0.949937 1.01216 2.58402 + vertex 0.951396 1.01487 2.58592 + endloop + endfacet + facet normal -0.479995 -0.304424 0.822758 + outer loop + vertex 0.949654 1.01872 2.58633 + vertex 0.947173 1.01729 2.58436 + vertex 0.951396 1.01487 2.58592 + endloop + endfacet + facet normal -0.475359 -0.302682 0.826085 + outer loop + vertex 0.951396 1.01487 2.58592 + vertex 0.95375 1.01774 2.58833 + vertex 0.949654 1.01872 2.58633 + endloop + endfacet + facet normal -0.47199 -0.306029 0.826784 + outer loop + vertex 0.955024 1.0124 2.58708 + vertex 0.95375 1.01774 2.58833 + vertex 0.951396 1.01487 2.58592 + endloop + endfacet + facet normal -0.483295 -0.298836 0.822875 + outer loop + vertex 0.947173 1.01729 2.58436 + vertex 0.949654 1.01872 2.58633 + vertex 0.94701 1.0211 2.58564 + endloop + endfacet + facet normal -0.487777 -0.305258 0.817858 + outer loop + vertex 0.949654 1.01872 2.58633 + vertex 0.948949 1.02276 2.58742 + vertex 0.94701 1.0211 2.58564 + endloop + endfacet + facet normal -0.475471 -0.305069 0.825143 + outer loop + vertex 0.949654 1.01872 2.58633 + vertex 0.95375 1.01774 2.58833 + vertex 0.948949 1.02276 2.58742 + endloop + endfacet + facet normal -0.482405 -0.312978 0.818126 + outer loop + vertex 0.95375 1.01774 2.58833 + vertex 0.952507 1.02309 2.58965 + vertex 0.948949 1.02276 2.58742 + endloop + endfacet + facet normal -0.476894 -0.292551 0.828846 + outer loop + vertex 0.952362 1.02641 2.59075 + vertex 0.950928 1.02933 2.59096 + vertex 0.948862 1.02756 2.58914 + endloop + endfacet + facet normal -0.477437 -0.296746 0.82704 + outer loop + vertex 0.952362 1.02641 2.59075 + vertex 0.948862 1.02756 2.58914 + vertex 0.952507 1.02309 2.58965 + endloop + endfacet + facet normal -0.484706 -0.303441 0.820356 + outer loop + vertex 0.952507 1.02309 2.58965 + vertex 0.948862 1.02756 2.58914 + vertex 0.948949 1.02276 2.58742 + endloop + endfacet + facet normal -0.411755 -0.263672 0.872316 + outer loop + vertex 0.952362 1.02641 2.59075 + vertex 0.954714 1.02851 2.5925 + vertex 0.950928 1.02933 2.59096 + endloop + endfacet + facet normal -0.480125 -0.288381 0.828442 + outer loop + vertex 0.948862 1.02756 2.58914 + vertex 0.950928 1.02933 2.59096 + vertex 0.948152 1.03165 2.59015 + endloop + endfacet + facet normal -0.471873 -0.275309 0.83758 + outer loop + vertex 0.950928 1.02933 2.59096 + vertex 0.950707 1.0331 2.59207 + vertex 0.948152 1.03165 2.59015 + endloop + endfacet + facet normal -0.413031 -0.280399 0.866477 + outer loop + vertex 0.950928 1.02933 2.59096 + vertex 0.954714 1.02851 2.5925 + vertex 0.950707 1.0331 2.59207 + endloop + endfacet + facet normal -0.424847 -0.291577 0.857023 + outer loop + vertex 0.954714 1.02851 2.5925 + vertex 0.953996 1.03235 2.59345 + vertex 0.950707 1.0331 2.59207 + endloop + endfacet + facet normal -0.424208 -0.282976 0.860216 + outer loop + vertex 0.953996 1.03235 2.59345 + vertex 0.952932 1.03664 2.59433 + vertex 0.950707 1.0331 2.59207 + endloop + endfacet + facet normal -0.439349 -0.27105 0.856449 + outer loop + vertex 0.950707 1.0331 2.59207 + vertex 0.952932 1.03664 2.59433 + vertex 0.948059 1.0382 2.59233 + endloop + endfacet + facet normal -0.43661 -0.305486 0.846197 + outer loop + vertex 0.952427 1.04117 2.59568 + vertex 0.950838 1.04438 2.59602 + vertex 0.948654 1.04238 2.59417 + endloop + endfacet + facet normal -0.435897 -0.300672 0.848286 + outer loop + vertex 0.952427 1.04117 2.59568 + vertex 0.948654 1.04238 2.59417 + vertex 0.952932 1.03664 2.59433 + endloop + endfacet + facet normal -0.444746 -0.307472 0.841226 + outer loop + vertex 0.952932 1.03664 2.59433 + vertex 0.948654 1.04238 2.59417 + vertex 0.948059 1.0382 2.59233 + endloop + endfacet + facet normal -0.31509 -0.252794 0.914775 + outer loop + vertex 0.952427 1.04117 2.59568 + vertex 0.955082 1.04384 2.59733 + vertex 0.950838 1.04438 2.59602 + endloop + endfacet + facet normal -0.4449 -0.29568 0.845362 + outer loop + vertex 0.948654 1.04238 2.59417 + vertex 0.950838 1.04438 2.59602 + vertex 0.948027 1.04659 2.59531 + endloop + endfacet + facet normal -0.425697 -0.264931 0.865213 + outer loop + vertex 0.950838 1.04438 2.59602 + vertex 0.950703 1.04841 2.59719 + vertex 0.948027 1.04659 2.59531 + endloop + endfacet + facet normal -0.315825 -0.273758 0.908466 + outer loop + vertex 0.950838 1.04438 2.59602 + vertex 0.955082 1.04384 2.59733 + vertex 0.950703 1.04841 2.59719 + endloop + endfacet + facet normal -0.316059 -0.273987 0.908316 + outer loop + vertex 0.955082 1.04384 2.59733 + vertex 0.954748 1.04842 2.5986 + vertex 0.950703 1.04841 2.59719 + endloop + endfacet + facet normal -0.314527 -0.28954 0.904013 + outer loop + vertex 0.954748 1.04842 2.5986 + vertex 0.952554 1.0527 2.59921 + vertex 0.950703 1.04841 2.59719 + endloop + endfacet + facet normal -0.361855 -0.264416 0.893949 + outer loop + vertex 0.950703 1.04841 2.59719 + vertex 0.952554 1.0527 2.59921 + vertex 0.947941 1.05321 2.59749 + endloop + endfacet + facet normal -0.348172 -0.317562 0.882004 + outer loop + vertex 0.952423 1.0567 2.60049 + vertex 0.950766 1.05954 2.60086 + vertex 0.948525 1.05737 2.59919 + endloop + endfacet + facet normal -0.347187 -0.297748 0.889273 + outer loop + vertex 0.952423 1.0567 2.60049 + vertex 0.948525 1.05737 2.59919 + vertex 0.952554 1.0527 2.59921 + endloop + endfacet + facet normal -0.361423 -0.310073 0.879334 + outer loop + vertex 0.952554 1.0527 2.59921 + vertex 0.948525 1.05737 2.59919 + vertex 0.947941 1.05321 2.59749 + endloop + endfacet + facet normal -0.207277 -0.243823 0.94741 + outer loop + vertex 0.952423 1.0567 2.60049 + vertex 0.954843 1.05994 2.60186 + vertex 0.950766 1.05954 2.60086 + endloop + endfacet + facet normal -0.376419 -0.287428 0.880735 + outer loop + vertex 0.948525 1.05737 2.59919 + vertex 0.950766 1.05954 2.60086 + vertex 0.947995 1.06143 2.60029 + endloop + endfacet + facet normal -0.339029 -0.222568 0.914069 + outer loop + vertex 0.950766 1.05954 2.60086 + vertex 0.951011 1.06371 2.60197 + vertex 0.947995 1.06143 2.60029 + endloop + endfacet + facet normal -0.207962 -0.23936 0.948398 + outer loop + vertex 0.950766 1.05954 2.60086 + vertex 0.954843 1.05994 2.60186 + vertex 0.951011 1.06371 2.60197 + endloop + endfacet + facet normal -0.195101 -0.226463 0.95428 + outer loop + vertex 0.954843 1.05994 2.60186 + vertex 0.955349 1.06439 2.60302 + vertex 0.951011 1.06371 2.60197 + endloop + endfacet + facet normal -0.193505 -0.234261 0.952721 + outer loop + vertex 0.955349 1.06439 2.60302 + vertex 0.953881 1.06808 2.60362 + vertex 0.951011 1.06371 2.60197 + endloop + endfacet + facet normal -0.22066 -0.215822 0.951173 + outer loop + vertex 0.951011 1.06371 2.60197 + vertex 0.953881 1.06808 2.60362 + vertex 0.948911 1.06905 2.60269 + endloop + endfacet + facet normal -0.225619 -0.250477 0.941466 + outer loop + vertex 0.953881 1.06808 2.60362 + vertex 0.952208 1.07279 2.60448 + vertex 0.948911 1.06905 2.60269 + endloop + endfacet + facet normal -0.217687 -0.25746 0.941449 + outer loop + vertex 0.948911 1.06905 2.60269 + vertex 0.952208 1.07279 2.60448 + vertex 0.948582 1.07271 2.60361 + endloop + endfacet + facet normal -0.220032 -0.228667 0.948313 + outer loop + vertex 0.952208 1.07279 2.60448 + vertex 0.947804 1.07674 2.60441 + vertex 0.948582 1.07271 2.60361 + endloop + endfacet + facet normal -0.275117 0.2791 0.920007 + outer loop + vertex 0.948526 1.96141 2.59918 + vertex 0.953292 1.96688 2.59894 + vertex 0.948269 1.96665 2.59751 + endloop + endfacet + facet normal -0.276537 0.234114 0.93205 + outer loop + vertex 0.953292 1.96688 2.59894 + vertex 0.953297 1.97164 2.59775 + vertex 0.948269 1.96665 2.59751 + endloop + endfacet + facet normal -0.265674 0.222881 0.937946 + outer loop + vertex 0.948269 1.96665 2.59751 + vertex 0.953297 1.97164 2.59775 + vertex 0.949422 1.97174 2.59663 + endloop + endfacet + facet normal -0.438358 0.318202 0.840589 + outer loop + vertex 0.951475 1.9778 2.59571 + vertex 0.948006 1.97653 2.59438 + vertex 0.949731 1.97493 2.59589 + endloop + endfacet + facet normal -0.293587 0.235613 0.926441 + outer loop + vertex 0.949731 1.97493 2.59589 + vertex 0.953234 1.9761 2.5967 + vertex 0.951475 1.9778 2.59571 + endloop + endfacet + facet normal -0.295189 0.241885 0.924313 + outer loop + vertex 0.949731 1.97493 2.59589 + vertex 0.949422 1.97174 2.59663 + vertex 0.953234 1.9761 2.5967 + endloop + endfacet + facet normal -0.266243 0.216317 0.93932 + outer loop + vertex 0.949422 1.97174 2.59663 + vertex 0.953297 1.97164 2.59775 + vertex 0.953234 1.9761 2.5967 + endloop + endfacet + facet normal -0.32874 0.31845 0.889112 + outer loop + vertex 0.951475 1.9778 2.59571 + vertex 0.954176 1.9797 2.59603 + vertex 0.952766 1.98163 2.59482 + endloop + endfacet + facet normal -0.442768 0.342779 0.828528 + outer loop + vertex 0.951475 1.9778 2.59571 + vertex 0.952766 1.98163 2.59482 + vertex 0.948006 1.97653 2.59438 + endloop + endfacet + facet normal -0.407178 0.30686 0.860257 + outer loop + vertex 0.948006 1.97653 2.59438 + vertex 0.952766 1.98163 2.59482 + vertex 0.948211 1.98153 2.5927 + endloop + endfacet + facet normal -0.282944 0.246838 0.92683 + outer loop + vertex 0.954176 1.9797 2.59603 + vertex 0.951475 1.9778 2.59571 + vertex 0.953234 1.9761 2.5967 + endloop + endfacet + facet normal -0.408853 0.292142 0.864576 + outer loop + vertex 0.952766 1.98163 2.59482 + vertex 0.953318 1.98656 2.59341 + vertex 0.948211 1.98153 2.5927 + endloop + endfacet + facet normal -0.373775 0.252573 0.892468 + outer loop + vertex 0.948211 1.98153 2.5927 + vertex 0.953318 1.98656 2.59341 + vertex 0.949534 1.98665 2.5918 + endloop + endfacet + facet normal -0.499054 0.29216 0.815836 + outer loop + vertex 0.951235 1.99268 2.59086 + vertex 0.947917 1.9913 2.58932 + vertex 0.949805 1.98985 2.591 + endloop + endfacet + facet normal -0.384743 0.238184 0.891763 + outer loop + vertex 0.949805 1.98985 2.591 + vertex 0.95332 1.99126 2.59214 + vertex 0.951235 1.99268 2.59086 + endloop + endfacet + facet normal -0.389661 0.256067 0.884644 + outer loop + vertex 0.949805 1.98985 2.591 + vertex 0.949534 1.98665 2.5918 + vertex 0.95332 1.99126 2.59214 + endloop + endfacet + facet normal -0.374891 0.243251 0.894587 + outer loop + vertex 0.949534 1.98665 2.5918 + vertex 0.953318 1.98656 2.59341 + vertex 0.95332 1.99126 2.59214 + endloop + endfacet + facet normal -0.42472 0.306572 0.851837 + outer loop + vertex 0.951235 1.99268 2.59086 + vertex 0.95376 1.99499 2.59129 + vertex 0.95149 1.99583 2.58985 + endloop + endfacet + facet normal -0.500548 0.299982 0.812073 + outer loop + vertex 0.951235 1.99268 2.59086 + vertex 0.95149 1.99583 2.58985 + vertex 0.947917 1.9913 2.58932 + endloop + endfacet + facet normal -0.506101 0.304983 0.806751 + outer loop + vertex 0.947917 1.9913 2.58932 + vertex 0.95149 1.99583 2.58985 + vertex 0.948091 1.99603 2.58764 + endloop + endfacet + facet normal -0.378041 0.2482 0.891898 + outer loop + vertex 0.95376 1.99499 2.59129 + vertex 0.951235 1.99268 2.59086 + vertex 0.95332 1.99126 2.59214 + endloop + endfacet + facet normal -0.503875 0.289422 0.813846 + outer loop + vertex 0.950307 2.00373 2.58628 + vertex 0.94653 2.00084 2.58497 + vertex 0.948795 1.99992 2.58669 + endloop + endfacet + facet normal -0.471566 0.279057 0.836512 + outer loop + vertex 0.948795 1.99992 2.58669 + vertex 0.952908 2.0012 2.58858 + vertex 0.950307 2.00373 2.58628 + endloop + endfacet + facet normal -0.472741 0.288623 0.832594 + outer loop + vertex 0.948795 1.99992 2.58669 + vertex 0.948091 1.99603 2.58764 + vertex 0.952908 2.0012 2.58858 + endloop + endfacet + facet normal -0.502402 0.32171 0.802555 + outer loop + vertex 0.948091 1.99603 2.58764 + vertex 0.95149 1.99583 2.58985 + vertex 0.952908 2.0012 2.58858 + endloop + endfacet + facet normal -0.504951 0.29146 0.81245 + outer loop + vertex 0.948009 2.00594 2.58406 + vertex 0.94653 2.00084 2.58497 + vertex 0.950307 2.00373 2.58628 + endloop + endfacet + facet normal -0.504584 0.291908 0.812517 + outer loop + vertex 0.951636 2.00745 2.58576 + vertex 0.948009 2.00594 2.58406 + vertex 0.950307 2.00373 2.58628 + endloop + endfacet + facet normal -0.443023 0.275535 0.853118 + outer loop + vertex 0.950307 2.00373 2.58628 + vertex 0.954224 2.00676 2.58733 + vertex 0.951636 2.00745 2.58576 + endloop + endfacet + facet normal -0.456016 0.297245 0.838865 + outer loop + vertex 0.952908 2.0012 2.58858 + vertex 0.954224 2.00676 2.58733 + vertex 0.950307 2.00373 2.58628 + endloop + endfacet + facet normal -0.468989 0.315606 0.824889 + outer loop + vertex 0.951636 2.00745 2.58576 + vertex 0.9542 2.01003 2.58623 + vertex 0.951748 2.01067 2.5846 + endloop + endfacet + facet normal -0.507851 0.309376 0.803974 + outer loop + vertex 0.951636 2.00745 2.58576 + vertex 0.951748 2.01067 2.5846 + vertex 0.948009 2.00594 2.58406 + endloop + endfacet + facet normal -0.509391 0.310765 0.802462 + outer loop + vertex 0.948009 2.00594 2.58406 + vertex 0.951748 2.01067 2.5846 + vertex 0.948294 2.01085 2.58233 + endloop + endfacet + facet normal -0.440582 0.282446 0.852122 + outer loop + vertex 0.9542 2.01003 2.58623 + vertex 0.951636 2.00745 2.58576 + vertex 0.954224 2.00676 2.58733 + endloop + endfacet + facet normal -0.478834 0.294196 0.827144 + outer loop + vertex 0.950522 2.01858 2.58081 + vertex 0.946658 2.0156 2.57963 + vertex 0.949015 2.01471 2.58131 + endloop + endfacet + facet normal -0.495441 0.299158 0.815501 + outer loop + vertex 0.949015 2.01471 2.58131 + vertex 0.953062 2.01605 2.58328 + vertex 0.950522 2.01858 2.58081 + endloop + endfacet + facet normal -0.496398 0.307468 0.811821 + outer loop + vertex 0.949015 2.01471 2.58131 + vertex 0.948294 2.01085 2.58233 + vertex 0.953062 2.01605 2.58328 + endloop + endfacet + facet normal -0.507425 0.31972 0.800187 + outer loop + vertex 0.948294 2.01085 2.58233 + vertex 0.951748 2.01067 2.5846 + vertex 0.953062 2.01605 2.58328 + endloop + endfacet + facet normal -0.482314 0.300418 0.822874 + outer loop + vertex 0.947981 2.02109 2.5784 + vertex 0.946658 2.0156 2.57963 + vertex 0.950522 2.01858 2.58081 + endloop + endfacet + facet normal -0.479138 0.304103 0.823376 + outer loop + vertex 0.952076 2.02244 2.58029 + vertex 0.947981 2.02109 2.5784 + vertex 0.950522 2.01858 2.58081 + endloop + endfacet + facet normal -0.480347 0.304475 0.822534 + outer loop + vertex 0.950522 2.01858 2.58081 + vertex 0.954422 2.02149 2.58201 + vertex 0.952076 2.02244 2.58029 + endloop + endfacet + facet normal -0.484394 0.312027 0.817314 + outer loop + vertex 0.953062 2.01605 2.58328 + vertex 0.954422 2.02149 2.58201 + vertex 0.950522 2.01858 2.58081 + endloop + endfacet + facet normal -0.488605 0.325901 0.809354 + outer loop + vertex 0.952076 2.02244 2.58029 + vertex 0.954737 2.02474 2.58097 + vertex 0.952912 2.02628 2.57925 + endloop + endfacet + facet normal -0.481691 0.325556 0.813626 + outer loop + vertex 0.952076 2.02244 2.58029 + vertex 0.952912 2.02628 2.57925 + vertex 0.947981 2.02109 2.5784 + endloop + endfacet + facet normal -0.486194 0.330606 0.808897 + outer loop + vertex 0.947981 2.02109 2.5784 + vertex 0.952912 2.02628 2.57925 + vertex 0.949502 2.02655 2.57709 + endloop + endfacet + facet normal -0.477864 0.309708 0.822026 + outer loop + vertex 0.954737 2.02474 2.58097 + vertex 0.952076 2.02244 2.58029 + vertex 0.954422 2.02149 2.58201 + endloop + endfacet + facet normal -0.434539 0.326618 0.839343 + outer loop + vertex 0.951428 2.03246 2.57572 + vertex 0.947817 2.03113 2.57436 + vertex 0.949922 2.02974 2.576 + endloop + endfacet + facet normal -0.478403 0.347502 0.806457 + outer loop + vertex 0.949922 2.02974 2.576 + vertex 0.953282 2.03093 2.57747 + vertex 0.951428 2.03246 2.57572 + endloop + endfacet + facet normal -0.477401 0.340076 0.810208 + outer loop + vertex 0.949922 2.02974 2.576 + vertex 0.949502 2.02655 2.57709 + vertex 0.953282 2.03093 2.57747 + endloop + endfacet + facet normal -0.482616 0.345025 0.805009 + outer loop + vertex 0.949502 2.02655 2.57709 + vertex 0.952912 2.02628 2.57925 + vertex 0.953282 2.03093 2.57747 + endloop + endfacet + facet normal -0.466551 0.325646 0.822365 + outer loop + vertex 0.951428 2.03246 2.57572 + vertex 0.954036 2.03472 2.5763 + vertex 0.951532 2.03553 2.57456 + endloop + endfacet + facet normal -0.435222 0.330304 0.837545 + outer loop + vertex 0.951428 2.03246 2.57572 + vertex 0.951532 2.03553 2.57456 + vertex 0.947817 2.03113 2.57436 + endloop + endfacet + facet normal -0.423541 0.320002 0.847474 + outer loop + vertex 0.947817 2.03113 2.57436 + vertex 0.951532 2.03553 2.57456 + vertex 0.947816 2.0358 2.5726 + endloop + endfacet + facet normal -0.480097 0.345347 0.806376 + outer loop + vertex 0.954036 2.03472 2.5763 + vertex 0.951428 2.03246 2.57572 + vertex 0.953282 2.03093 2.57747 + endloop + endfacet + facet normal -0.416678 0.342749 0.841964 + outer loop + vertex 0.950728 2.04234 2.57142 + vertex 0.947341 2.04147 2.57009 + vertex 0.948934 2.0397 2.5716 + endloop + endfacet + facet normal -0.424243 0.347484 0.836225 + outer loop + vertex 0.948934 2.0397 2.5716 + vertex 0.952057 2.03999 2.57307 + vertex 0.950728 2.04234 2.57142 + endloop + endfacet + facet normal -0.425085 0.33673 0.840188 + outer loop + vertex 0.948934 2.0397 2.5716 + vertex 0.947816 2.0358 2.5726 + vertex 0.952057 2.03999 2.57307 + endloop + endfacet + facet normal -0.4209 0.332053 0.844147 + outer loop + vertex 0.947816 2.0358 2.5726 + vertex 0.951532 2.03553 2.57456 + vertex 0.952057 2.03999 2.57307 + endloop + endfacet + facet normal -0.437847 0.332971 0.835117 + outer loop + vertex 0.950728 2.04234 2.57142 + vertex 0.953351 2.04385 2.57219 + vertex 0.951462 2.04544 2.57056 + endloop + endfacet + facet normal -0.415685 0.331027 0.847129 + outer loop + vertex 0.950728 2.04234 2.57142 + vertex 0.951462 2.04544 2.57056 + vertex 0.947341 2.04147 2.57009 + endloop + endfacet + facet normal -0.430212 0.347758 0.833056 + outer loop + vertex 0.947341 2.04147 2.57009 + vertex 0.951462 2.04544 2.57056 + vertex 0.947887 2.04595 2.56851 + endloop + endfacet + facet normal -0.439292 0.336619 0.832893 + outer loop + vertex 0.953351 2.04385 2.57219 + vertex 0.950728 2.04234 2.57142 + vertex 0.952057 2.03999 2.57307 + endloop + endfacet + facet normal -0.431667 0.342783 0.834364 + outer loop + vertex 0.951462 2.04544 2.57056 + vertex 0.953002 2.05041 2.56932 + vertex 0.947887 2.04595 2.56851 + endloop + endfacet + facet normal -0.438122 0.351468 0.827357 + outer loop + vertex 0.947887 2.04595 2.56851 + vertex 0.953002 2.05041 2.56932 + vertex 0.948474 2.05069 2.5668 + endloop + endfacet + facet normal -0.440069 0.36788 0.819148 + outer loop + vertex 0.951702 2.05737 2.56562 + vertex 0.94841 2.05647 2.56425 + vertex 0.949757 2.05447 2.56587 + endloop + endfacet + facet normal -0.430622 0.3622 0.826666 + outer loop + vertex 0.949757 2.05447 2.56587 + vertex 0.953113 2.05538 2.56722 + vertex 0.951702 2.05737 2.56562 + endloop + endfacet + facet normal -0.429647 0.350434 0.832226 + outer loop + vertex 0.949757 2.05447 2.56587 + vertex 0.948474 2.05069 2.5668 + vertex 0.953113 2.05538 2.56722 + endloop + endfacet + facet normal -0.436621 0.357934 0.825376 + outer loop + vertex 0.948474 2.05069 2.5668 + vertex 0.953002 2.05041 2.56932 + vertex 0.953113 2.05538 2.56722 + endloop + endfacet + facet normal -0.428345 0.348208 0.83383 + outer loop + vertex 0.951702 2.05737 2.56562 + vertex 0.954282 2.05922 2.56617 + vertex 0.952635 2.06101 2.56457 + endloop + endfacet + facet normal -0.438658 0.349188 0.828038 + outer loop + vertex 0.951702 2.05737 2.56562 + vertex 0.952635 2.06101 2.56457 + vertex 0.94841 2.05647 2.56425 + endloop + endfacet + facet normal -0.460272 0.370792 0.806637 + outer loop + vertex 0.94841 2.05647 2.56425 + vertex 0.952635 2.06101 2.56457 + vertex 0.948177 2.0609 2.56208 + endloop + endfacet + facet normal -0.43446 0.35898 0.826061 + outer loop + vertex 0.954282 2.05922 2.56617 + vertex 0.951702 2.05737 2.56562 + vertex 0.953113 2.05538 2.56722 + endloop + endfacet + facet normal -0.544367 0.37793 0.748888 + outer loop + vertex 0.951372 2.06792 2.56091 + vertex 0.949439 2.06842 2.55925 + vertex 0.948874 2.06541 2.56035 + endloop + endfacet + facet normal -0.503712 0.326069 0.799971 + outer loop + vertex 0.948874 2.06541 2.56035 + vertex 0.952813 2.06577 2.56269 + vertex 0.951372 2.06792 2.56091 + endloop + endfacet + facet normal -0.49741 0.376121 0.781739 + outer loop + vertex 0.948874 2.06541 2.56035 + vertex 0.948177 2.0609 2.56208 + vertex 0.952813 2.06577 2.56269 + endloop + endfacet + facet normal -0.465258 0.341056 0.816833 + outer loop + vertex 0.948177 2.0609 2.56208 + vertex 0.952635 2.06101 2.56457 + vertex 0.952813 2.06577 2.56269 + endloop + endfacet + facet normal -0.495145 0.387199 0.777759 + outer loop + vertex 0.951372 2.06792 2.56091 + vertex 0.95386 2.0696 2.56165 + vertex 0.951814 2.07077 2.55977 + endloop + endfacet + facet normal -0.542349 0.382623 0.747969 + outer loop + vertex 0.951372 2.06792 2.56091 + vertex 0.951814 2.07077 2.55977 + vertex 0.949439 2.06842 2.55925 + endloop + endfacet + facet normal -0.567235 0.416106 0.710704 + outer loop + vertex 0.949439 2.06842 2.55925 + vertex 0.951814 2.07077 2.55977 + vertex 0.94905 2.07124 2.55729 + endloop + endfacet + facet normal -0.477668 0.348807 0.80633 + outer loop + vertex 0.95386 2.0696 2.56165 + vertex 0.951372 2.06792 2.56091 + vertex 0.952813 2.06577 2.56269 + endloop + endfacet + facet normal -0.661097 0.384317 0.6444 + outer loop + vertex 0.950057 2.07789 2.55438 + vertex 0.948276 2.07713 2.55301 + vertex 0.948646 2.0748 2.55477 + endloop + endfacet + facet normal -0.616876 0.370472 0.694417 + outer loop + vertex 0.948646 2.0748 2.55477 + vertex 0.9519 2.07486 2.55763 + vertex 0.950057 2.07789 2.55438 + endloop + endfacet + facet normal -0.605673 0.41171 0.680922 + outer loop + vertex 0.948646 2.0748 2.55477 + vertex 0.94905 2.07124 2.55729 + vertex 0.9519 2.07486 2.55763 + endloop + endfacet + facet normal -0.578668 0.386935 0.717931 + outer loop + vertex 0.94905 2.07124 2.55729 + vertex 0.951814 2.07077 2.55977 + vertex 0.9519 2.07486 2.55763 + endloop + endfacet + facet normal -0.693623 0.392036 0.604313 + outer loop + vertex 0.950512 2.08218 2.5523 + vertex 0.948234 2.0823 2.5496 + vertex 0.948179 2.07968 2.55124 + endloop + endfacet + facet normal -0.660301 0.410671 0.62877 + outer loop + vertex 0.948179 2.07968 2.55124 + vertex 0.948276 2.07713 2.55301 + vertex 0.950057 2.07789 2.55438 + endloop + endfacet + facet normal -0.685238 0.375881 0.623829 + outer loop + vertex 0.950512 2.08218 2.5523 + vertex 0.948179 2.07968 2.55124 + vertex 0.950057 2.07789 2.55438 + endloop + endfacet + facet normal -0.620467 0.395053 0.677461 + outer loop + vertex 0.950512 2.08218 2.5523 + vertex 0.950057 2.07789 2.55438 + vertex 0.952829 2.07938 2.55605 + endloop + endfacet + facet normal -0.660021 0.3472 0.666201 + outer loop + vertex 0.950512 2.08218 2.5523 + vertex 0.952829 2.07938 2.55605 + vertex 0.953015 2.08209 2.55482 + endloop + endfacet + facet normal -0.617235 0.370116 0.694288 + outer loop + vertex 0.952829 2.07938 2.55605 + vertex 0.950057 2.07789 2.55438 + vertex 0.9519 2.07486 2.55763 + endloop + endfacet + facet normal -0.691861 0.397069 0.603046 + outer loop + vertex 0.94848 2.08498 2.54812 + vertex 0.948234 2.0823 2.5496 + vertex 0.950512 2.08218 2.5523 + endloop + endfacet + facet normal -0.719163 0.362225 0.592957 + outer loop + vertex 0.950664 2.08694 2.54957 + vertex 0.94848 2.08498 2.54812 + vertex 0.950512 2.08218 2.5523 + endloop + endfacet + facet normal -0.664069 0.387167 0.63962 + outer loop + vertex 0.950512 2.08218 2.5523 + vertex 0.953056 2.08491 2.55328 + vertex 0.950664 2.08694 2.54957 + endloop + endfacet + facet normal -0.653476 0.36978 0.660479 + outer loop + vertex 0.953015 2.08209 2.55482 + vertex 0.953056 2.08491 2.55328 + vertex 0.950512 2.08218 2.5523 + endloop + endfacet + facet normal -0.757288 0.358636 0.545798 + outer loop + vertex 0.95057 2.09237 2.54611 + vertex 0.947989 2.09087 2.54352 + vertex 0.948886 2.08853 2.5463 + endloop + endfacet + facet normal -0.723485 0.378664 0.57722 + outer loop + vertex 0.948886 2.08853 2.5463 + vertex 0.94848 2.08498 2.54812 + vertex 0.950664 2.08694 2.54957 + endloop + endfacet + facet normal -0.739757 0.352296 0.573278 + outer loop + vertex 0.95057 2.09237 2.54611 + vertex 0.948886 2.08853 2.5463 + vertex 0.950664 2.08694 2.54957 + endloop + endfacet + facet normal -0.691299 0.379608 0.61482 + outer loop + vertex 0.95057 2.09237 2.54611 + vertex 0.950664 2.08694 2.54957 + vertex 0.953029 2.08922 2.55082 + endloop + endfacet + facet normal -0.72282 0.337396 0.603071 + outer loop + vertex 0.95057 2.09237 2.54611 + vertex 0.953029 2.08922 2.55082 + vertex 0.953047 2.09209 2.54924 + endloop + endfacet + facet normal -0.682816 0.359011 0.636296 + outer loop + vertex 0.953029 2.08922 2.55082 + vertex 0.950664 2.08694 2.54957 + vertex 0.953056 2.08491 2.55328 + endloop + endfacet + facet normal -0.76106 0.285025 0.582708 + outer loop + vertex 0.949417 2.09738 2.54191 + vertex 0.947718 2.09741 2.53968 + vertex 0.947837 2.09444 2.54129 + endloop + endfacet + facet normal -0.757837 0.321682 0.56763 + outer loop + vertex 0.947837 2.09444 2.54129 + vertex 0.947989 2.09087 2.54352 + vertex 0.95057 2.09237 2.54611 + endloop + endfacet + facet normal -0.771553 0.294708 0.563784 + outer loop + vertex 0.947837 2.09444 2.54129 + vertex 0.95057 2.09237 2.54611 + vertex 0.949417 2.09738 2.54191 + endloop + endfacet + facet normal -0.74363 0.320412 0.586814 + outer loop + vertex 0.949417 2.09738 2.54191 + vertex 0.95057 2.09237 2.54611 + vertex 0.95174 2.09763 2.54472 + endloop + endfacet + facet normal -0.716157 0.322755 0.618828 + outer loop + vertex 0.95057 2.09237 2.54611 + vertex 0.953367 2.09495 2.548 + vertex 0.95174 2.09763 2.54472 + endloop + endfacet + facet normal -0.72173 0.340734 0.602501 + outer loop + vertex 0.953047 2.09209 2.54924 + vertex 0.953367 2.09495 2.548 + vertex 0.95057 2.09237 2.54611 + endloop + endfacet + facet normal -0.777793 0.203949 0.594511 + outer loop + vertex 0.948052 2.10056 2.53904 + vertex 0.947718 2.09741 2.53968 + vertex 0.949417 2.09738 2.54191 + endloop + endfacet + facet normal -0.723334 0.265949 0.637228 + outer loop + vertex 0.950892 2.10193 2.54169 + vertex 0.948052 2.10056 2.53904 + vertex 0.949417 2.09738 2.54191 + endloop + endfacet + facet normal -0.709482 0.318416 0.628687 + outer loop + vertex 0.953101 2.10096 2.54457 + vertex 0.95174 2.09763 2.54472 + vertex 0.953893 2.09854 2.54669 + endloop + endfacet + facet normal -0.699164 0.314794 0.64193 + outer loop + vertex 0.953101 2.10096 2.54457 + vertex 0.950892 2.10193 2.54169 + vertex 0.95174 2.09763 2.54472 + endloop + endfacet + facet normal -0.75287 0.273639 0.598589 + outer loop + vertex 0.950892 2.10193 2.54169 + vertex 0.949417 2.09738 2.54191 + vertex 0.95174 2.09763 2.54472 + endloop + endfacet + facet normal -0.709137 0.331343 0.622363 + outer loop + vertex 0.953893 2.09854 2.54669 + vertex 0.95174 2.09763 2.54472 + vertex 0.953367 2.09495 2.548 + endloop + endfacet + facet normal -0.71954 0.210424 0.661804 + outer loop + vertex 0.949071 2.10597 2.53843 + vertex 0.948052 2.10056 2.53904 + vertex 0.950892 2.10193 2.54169 + endloop + endfacet + facet normal -0.647785 0.280391 0.708347 + outer loop + vertex 0.951846 2.10617 2.54089 + vertex 0.949071 2.10597 2.53843 + vertex 0.950892 2.10193 2.54169 + endloop + endfacet + facet normal -0.681658 0.281728 0.675257 + outer loop + vertex 0.950892 2.10193 2.54169 + vertex 0.953576 2.10451 2.54332 + vertex 0.951846 2.10617 2.54089 + endloop + endfacet + facet normal -0.697243 0.319081 0.641904 + outer loop + vertex 0.953101 2.10096 2.54457 + vertex 0.953576 2.10451 2.54332 + vertex 0.950892 2.10193 2.54169 + endloop + endfacet + facet normal -0.644376 0.304006 0.701683 + outer loop + vertex 0.951846 2.10617 2.54089 + vertex 0.953892 2.10809 2.54193 + vertex 0.952037 2.10982 2.53948 + endloop + endfacet + facet normal -0.643902 0.304129 0.702065 + outer loop + vertex 0.951846 2.10617 2.54089 + vertex 0.952037 2.10982 2.53948 + vertex 0.949071 2.10597 2.53843 + endloop + endfacet + facet normal -0.602532 0.257642 0.755365 + outer loop + vertex 0.949071 2.10597 2.53843 + vertex 0.952037 2.10982 2.53948 + vertex 0.949038 2.11121 2.53661 + endloop + endfacet + facet normal -0.653797 0.323589 0.683988 + outer loop + vertex 0.953892 2.10809 2.54193 + vertex 0.951846 2.10617 2.54089 + vertex 0.953576 2.10451 2.54332 + endloop + endfacet + facet normal -0.449205 0.499897 0.740484 + outer loop + vertex 0.950398 2.1177 2.53379 + vertex 0.9483 2.11736 2.53275 + vertex 0.948662 2.11519 2.53443 + endloop + endfacet + facet normal -0.473502 0.51087 0.717501 + outer loop + vertex 0.948662 2.11519 2.53443 + vertex 0.952283 2.11464 2.53722 + vertex 0.950398 2.1177 2.53379 + endloop + endfacet + facet normal -0.530969 0.367545 0.763533 + outer loop + vertex 0.948662 2.11519 2.53443 + vertex 0.949038 2.11121 2.53661 + vertex 0.952283 2.11464 2.53722 + endloop + endfacet + facet normal -0.541257 0.379607 0.750293 + outer loop + vertex 0.949038 2.11121 2.53661 + vertex 0.952037 2.10982 2.53948 + vertex 0.952283 2.11464 2.53722 + endloop + endfacet + facet normal -0.443096 0.66805 0.597809 + outer loop + vertex 0.95116 2.12047 2.53169 + vertex 0.948554 2.1209 2.52928 + vertex 0.948284 2.11913 2.53105 + endloop + endfacet + facet normal -0.426841 0.623365 0.655151 + outer loop + vertex 0.948284 2.11913 2.53105 + vertex 0.9483 2.11736 2.53275 + vertex 0.950398 2.1177 2.53379 + endloop + endfacet + facet normal -0.432818 0.617562 0.656724 + outer loop + vertex 0.95116 2.12047 2.53169 + vertex 0.948284 2.11913 2.53105 + vertex 0.950398 2.1177 2.53379 + endloop + endfacet + facet normal -0.485586 0.60938 0.626787 + outer loop + vertex 0.95116 2.12047 2.53169 + vertex 0.950398 2.1177 2.53379 + vertex 0.953379 2.11861 2.53522 + endloop + endfacet + facet normal -0.512953 0.582966 0.630103 + outer loop + vertex 0.95116 2.12047 2.53169 + vertex 0.953379 2.11861 2.53522 + vertex 0.953855 2.12066 2.53371 + endloop + endfacet + facet normal -0.492927 0.495972 0.714867 + outer loop + vertex 0.953379 2.11861 2.53522 + vertex 0.950398 2.1177 2.53379 + vertex 0.952283 2.11464 2.53722 + endloop + endfacet + facet normal -0.315838 0.871584 0.374949 + outer loop + vertex 0.950343 2.1266 2.52003 + vertex 0.947419 2.12648 2.51786 + vertex 0.948516 2.12512 2.52195 + endloop + endfacet + facet normal -0.332819 0.871952 0.35907 + outer loop + vertex 0.952324 2.1261 2.52309 + vertex 0.950343 2.1266 2.52003 + vertex 0.948516 2.12512 2.52195 + endloop + endfacet + facet normal -0.333029 0.871378 0.360266 + outer loop + vertex 0.952324 2.1261 2.52309 + vertex 0.948516 2.12512 2.52195 + vertex 0.953606 2.12492 2.52713 + endloop + endfacet + facet normal -0.407742 0.804887 0.431166 + outer loop + vertex 0.953606 2.12492 2.52713 + vertex 0.948516 2.12512 2.52195 + vertex 0.94931 2.12267 2.52727 + endloop + endfacet + facet normal -0.367395 0.762301 0.53284 + outer loop + vertex 0.95116 2.12047 2.53169 + vertex 0.94931 2.12267 2.52727 + vertex 0.948554 2.1209 2.52928 + endloop + endfacet + facet normal -0.474757 0.692609 0.543045 + outer loop + vertex 0.95116 2.12047 2.53169 + vertex 0.954607 2.12255 2.53205 + vertex 0.94931 2.12267 2.52727 + endloop + endfacet + facet normal -0.399741 0.791491 0.46233 + outer loop + vertex 0.954607 2.12255 2.53205 + vertex 0.953606 2.12492 2.52713 + vertex 0.94931 2.12267 2.52727 + endloop + endfacet + facet normal -0.469456 0.680537 0.562566 + outer loop + vertex 0.954607 2.12255 2.53205 + vertex 0.95116 2.12047 2.53169 + vertex 0.953855 2.12066 2.53371 + endloop + endfacet + facet normal -0.0772302 0.990601 0.112896 + outer loop + vertex 0.955 2.13247 2.515 + vertex 0.95 2.13208 2.515 + vertex 0.955 2.1319 2.52 + endloop + endfacet + facet normal -0.633312 0.422285 0.64853 + outer loop + vertex 0.955 2.1319 2.52 + vertex 0.95 2.13208 2.515 + vertex 0.949546 2.1285 2.51689 + endloop + endfacet + facet normal -0.434245 0.718287 0.543594 + outer loop + vertex 0.950343 2.1266 2.52003 + vertex 0.949546 2.1285 2.51689 + vertex 0.947419 2.12648 2.51786 + endloop + endfacet + facet normal -0.401486 0.735541 0.5457 + outer loop + vertex 0.950343 2.1266 2.52003 + vertex 0.954396 2.12774 2.52148 + vertex 0.949546 2.1285 2.51689 + endloop + endfacet + facet normal -0.617367 0.341684 0.708597 + outer loop + vertex 0.954396 2.12774 2.52148 + vertex 0.955 2.1319 2.52 + vertex 0.949546 2.1285 2.51689 + endloop + endfacet + facet normal -0.37365 0.845637 0.381162 + outer loop + vertex 0.954396 2.12774 2.52148 + vertex 0.950343 2.1266 2.52003 + vertex 0.952324 2.1261 2.52309 + endloop + endfacet + facet normal -0.231877 -0.7933 -0.562946 + outer loop + vertex 0.96 0.895 2.51907 + vertex 0.96 0.89434 2.52 + vertex 0.957742 0.895 2.52 + endloop + endfacet + facet normal 0.567087 -0.785343 0.24829 + outer loop + vertex 0.956112 0.895 2.515 + vertex 0.955 0.895 2.51754 + vertex 0.955 0.894197 2.515 + endloop + endfacet + facet normal -0.267885 -0.916491 -0.297122 + outer loop + vertex 0.96 0.89434 2.52 + vertex 0.959841 0.894172 2.52066 + vertex 0.957742 0.895 2.52 + endloop + endfacet + facet normal -0.309006 -0.932573 -0.18661 + outer loop + vertex 0.957742 0.895 2.52 + vertex 0.959841 0.894172 2.52066 + vertex 0.957136 0.895019 2.52091 + endloop + endfacet + facet normal -0.315297 -0.929603 -0.190856 + outer loop + vertex 0.957742 0.895 2.52 + vertex 0.957136 0.895019 2.52091 + vertex 0.955 0.89593 2.52 + endloop + endfacet + facet normal -0.286933 -0.924201 -0.252034 + outer loop + vertex 0.955 0.89593 2.52 + vertex 0.957136 0.895019 2.52091 + vertex 0.95315 0.896181 2.52119 + endloop + endfacet + facet normal -0.259077 -0.940529 0.219735 + outer loop + vertex 0.957136 0.895019 2.52091 + vertex 0.958102 0.895812 2.52544 + vertex 0.95315 0.896181 2.52119 + endloop + endfacet + facet normal -0.290662 -0.921347 0.258137 + outer loop + vertex 0.958102 0.895812 2.52544 + vertex 0.953049 0.897476 2.52569 + vertex 0.95315 0.896181 2.52119 + endloop + endfacet + facet normal -0.347487 -0.828998 0.438195 + outer loop + vertex 0.954112 0.898548 2.52912 + vertex 0.95784 0.897567 2.53022 + vertex 0.955605 0.898906 2.53098 + endloop + endfacet + facet normal -0.33779 -0.863447 0.374642 + outer loop + vertex 0.954112 0.898548 2.52912 + vertex 0.953049 0.897476 2.52569 + vertex 0.95784 0.897567 2.53022 + endloop + endfacet + facet normal -0.282496 -0.905367 0.317028 + outer loop + vertex 0.953049 0.897476 2.52569 + vertex 0.958102 0.895812 2.52544 + vertex 0.95784 0.897567 2.53022 + endloop + endfacet + facet normal -0.331335 -0.81911 0.468269 + outer loop + vertex 0.95784 0.897567 2.53022 + vertex 0.957519 0.899535 2.53344 + vertex 0.955605 0.898906 2.53098 + endloop + endfacet + facet normal -0.421875 -0.76559 0.485689 + outer loop + vertex 0.954112 0.898548 2.52912 + vertex 0.955605 0.898906 2.53098 + vertex 0.95208 0.900481 2.53041 + endloop + endfacet + facet normal -0.493125 -0.626624 0.603465 + outer loop + vertex 0.958434 0.901118 2.53626 + vertex 0.956147 0.903095 2.53644 + vertex 0.953779 0.902895 2.5343 + endloop + endfacet + facet normal -0.489 -0.683236 0.54228 + outer loop + vertex 0.957519 0.899535 2.53344 + vertex 0.958434 0.901118 2.53626 + vertex 0.953779 0.902895 2.5343 + endloop + endfacet + facet normal -0.451171 -0.656963 0.604024 + outer loop + vertex 0.957519 0.899535 2.53344 + vertex 0.953779 0.902895 2.5343 + vertex 0.95208 0.900481 2.53041 + endloop + endfacet + facet normal -0.418493 -0.746323 0.517557 + outer loop + vertex 0.957519 0.899535 2.53344 + vertex 0.95208 0.900481 2.53041 + vertex 0.955605 0.898906 2.53098 + endloop + endfacet + facet normal -0.486302 -0.61989 0.61583 + outer loop + vertex 0.958434 0.901118 2.53626 + vertex 0.958509 0.903431 2.53865 + vertex 0.956147 0.903095 2.53644 + endloop + endfacet + facet normal -0.523779 -0.571001 0.63215 + outer loop + vertex 0.953779 0.902895 2.5343 + vertex 0.956147 0.903095 2.53644 + vertex 0.953591 0.905475 2.53647 + endloop + endfacet + facet normal -0.559234 -0.4585 0.690678 + outer loop + vertex 0.95852 0.906136 2.54096 + vertex 0.955626 0.909559 2.54089 + vertex 0.953423 0.908547 2.53843 + endloop + endfacet + facet normal -0.564599 -0.534909 0.62857 + outer loop + vertex 0.958509 0.903431 2.53865 + vertex 0.95852 0.906136 2.54096 + vertex 0.953423 0.908547 2.53843 + endloop + endfacet + facet normal -0.513607 -0.480781 0.710674 + outer loop + vertex 0.958509 0.903431 2.53865 + vertex 0.953423 0.908547 2.53843 + vertex 0.953591 0.905475 2.53647 + endloop + endfacet + facet normal -0.518288 -0.565229 0.64179 + outer loop + vertex 0.958509 0.903431 2.53865 + vertex 0.953591 0.905475 2.53647 + vertex 0.956147 0.903095 2.53644 + endloop + endfacet + facet normal -0.572767 -0.470341 0.671355 + outer loop + vertex 0.95852 0.906136 2.54096 + vertex 0.95919 0.90875 2.54336 + vertex 0.955626 0.909559 2.54089 + endloop + endfacet + facet normal -0.591531 -0.404565 0.697437 + outer loop + vertex 0.953423 0.908547 2.53843 + vertex 0.955626 0.909559 2.54089 + vertex 0.952898 0.911902 2.53993 + endloop + endfacet + facet normal -0.584235 -0.390317 0.711563 + outer loop + vertex 0.955626 0.909559 2.54089 + vertex 0.955095 0.912596 2.54212 + vertex 0.952898 0.911902 2.53993 + endloop + endfacet + facet normal -0.583135 -0.390458 0.712388 + outer loop + vertex 0.955626 0.909559 2.54089 + vertex 0.95919 0.90875 2.54336 + vertex 0.955095 0.912596 2.54212 + endloop + endfacet + facet normal -0.600641 -0.419342 0.680722 + outer loop + vertex 0.95919 0.90875 2.54336 + vertex 0.957918 0.912826 2.54475 + vertex 0.955095 0.912596 2.54212 + endloop + endfacet + facet normal -0.642731 -0.366428 0.672776 + outer loop + vertex 0.958405 0.915614 2.54672 + vertex 0.956266 0.920467 2.54732 + vertex 0.954407 0.917105 2.54371 + endloop + endfacet + facet normal -0.64278 -0.364013 0.674039 + outer loop + vertex 0.958405 0.915614 2.54672 + vertex 0.954407 0.917105 2.54371 + vertex 0.957918 0.912826 2.54475 + endloop + endfacet + facet normal -0.62545 -0.343344 0.700662 + outer loop + vertex 0.957918 0.912826 2.54475 + vertex 0.954407 0.917105 2.54371 + vertex 0.955095 0.912596 2.54212 + endloop + endfacet + facet normal -0.636838 -0.364639 0.67932 + outer loop + vertex 0.958405 0.915614 2.54672 + vertex 0.959789 0.917621 2.54909 + vertex 0.956266 0.920467 2.54732 + endloop + endfacet + facet normal -0.694623 -0.311578 0.648396 + outer loop + vertex 0.951933 0.922997 2.54389 + vertex 0.954407 0.917105 2.54371 + vertex 0.956266 0.920467 2.54732 + endloop + endfacet + facet normal -0.698315 -0.351769 0.62339 + outer loop + vertex 0.954344 0.924828 2.54763 + vertex 0.951933 0.922997 2.54389 + vertex 0.956266 0.920467 2.54732 + endloop + endfacet + facet normal -0.646857 -0.393175 0.653444 + outer loop + vertex 0.958727 0.920782 2.54994 + vertex 0.956266 0.920467 2.54732 + vertex 0.959789 0.917621 2.54909 + endloop + endfacet + facet normal -0.658451 -0.36092 0.660439 + outer loop + vertex 0.958727 0.920782 2.54994 + vertex 0.957153 0.92385 2.55005 + vertex 0.956266 0.920467 2.54732 + endloop + endfacet + facet normal -0.679308 -0.34511 0.647641 + outer loop + vertex 0.957153 0.92385 2.55005 + vertex 0.954344 0.924828 2.54763 + vertex 0.956266 0.920467 2.54732 + endloop + endfacet + facet normal -0.587982 -0.327557 0.739583 + outer loop + vertex 0.958727 0.920782 2.54994 + vertex 0.960381 0.922158 2.55187 + vertex 0.957153 0.92385 2.55005 + endloop + endfacet + facet normal -0.715795 -0.321568 0.619864 + outer loop + vertex 0.951933 0.922997 2.54389 + vertex 0.954344 0.924828 2.54763 + vertex 0.952124 0.926834 2.5461 + endloop + endfacet + facet normal -0.722793 -0.345569 0.598459 + outer loop + vertex 0.953465 0.927827 2.5483 + vertex 0.952124 0.926834 2.5461 + vertex 0.954344 0.924828 2.54763 + endloop + endfacet + facet normal -0.694345 -0.344658 0.631741 + outer loop + vertex 0.953465 0.927827 2.5483 + vertex 0.954344 0.924828 2.54763 + vertex 0.955481 0.926832 2.54997 + endloop + endfacet + facet normal -0.678151 -0.362611 0.639237 + outer loop + vertex 0.955481 0.926832 2.54997 + vertex 0.954344 0.924828 2.54763 + vertex 0.957153 0.92385 2.55005 + endloop + endfacet + facet normal -0.633229 -0.335829 0.697309 + outer loop + vertex 0.957153 0.92385 2.55005 + vertex 0.958511 0.927469 2.55303 + vertex 0.955481 0.926832 2.54997 + endloop + endfacet + facet normal -0.594673 -0.365666 0.715998 + outer loop + vertex 0.960381 0.922158 2.55187 + vertex 0.958511 0.927469 2.55303 + vertex 0.957153 0.92385 2.55005 + endloop + endfacet + facet normal -0.694493 -0.353159 0.626864 + outer loop + vertex 0.953465 0.927827 2.5483 + vertex 0.955481 0.926832 2.54997 + vertex 0.954305 0.929965 2.55043 + endloop + endfacet + facet normal -0.61845 -0.375336 0.690393 + outer loop + vertex 0.958173 0.93166 2.55509 + vertex 0.956649 0.935218 2.55566 + vertex 0.955339 0.932765 2.55316 + endloop + endfacet + facet normal -0.618527 -0.387088 0.683804 + outer loop + vertex 0.958511 0.927469 2.55303 + vertex 0.958173 0.93166 2.55509 + vertex 0.955339 0.932765 2.55316 + endloop + endfacet + facet normal -0.64147 -0.400116 0.654541 + outer loop + vertex 0.958511 0.927469 2.55303 + vertex 0.955339 0.932765 2.55316 + vertex 0.954305 0.929965 2.55043 + endloop + endfacet + facet normal -0.631746 -0.339893 0.696685 + outer loop + vertex 0.958511 0.927469 2.55303 + vertex 0.954305 0.929965 2.55043 + vertex 0.955481 0.926832 2.54997 + endloop + endfacet + facet normal -0.529987 -0.350518 0.772173 + outer loop + vertex 0.958173 0.93166 2.55509 + vertex 0.960259 0.93271 2.557 + vertex 0.956649 0.935218 2.55566 + endloop + endfacet + facet normal -0.634594 -0.360032 0.683862 + outer loop + vertex 0.952692 0.937828 2.55337 + vertex 0.955339 0.932765 2.55316 + vertex 0.956649 0.935218 2.55566 + endloop + endfacet + facet normal -0.640116 -0.385287 0.664685 + outer loop + vertex 0.955372 0.937964 2.55603 + vertex 0.952692 0.937828 2.55337 + vertex 0.956649 0.935218 2.55566 + endloop + endfacet + facet normal -0.547341 -0.354458 0.75814 + outer loop + vertex 0.956649 0.935218 2.55566 + vertex 0.958498 0.93795 2.55828 + vertex 0.955372 0.937964 2.55603 + endloop + endfacet + facet normal -0.536012 -0.365052 0.761202 + outer loop + vertex 0.960259 0.93271 2.557 + vertex 0.958498 0.93795 2.55828 + vertex 0.956649 0.935218 2.55566 + endloop + endfacet + facet normal -0.642394 -0.378099 0.666612 + outer loop + vertex 0.952692 0.937828 2.55337 + vertex 0.955372 0.937964 2.55603 + vertex 0.953815 0.940812 2.55614 + endloop + endfacet + facet normal -0.532461 -0.372262 0.760202 + outer loop + vertex 0.958349 0.941951 2.56013 + vertex 0.956464 0.94566 2.56062 + vertex 0.955092 0.9432 2.55846 + endloop + endfacet + facet normal -0.5324 -0.371639 0.760549 + outer loop + vertex 0.958498 0.93795 2.55828 + vertex 0.958349 0.941951 2.56013 + vertex 0.955092 0.9432 2.55846 + endloop + endfacet + facet normal -0.569821 -0.394549 0.720857 + outer loop + vertex 0.958498 0.93795 2.55828 + vertex 0.955092 0.9432 2.55846 + vertex 0.953815 0.940812 2.55614 + endloop + endfacet + facet normal -0.551944 -0.332622 0.764671 + outer loop + vertex 0.958498 0.93795 2.55828 + vertex 0.953815 0.940812 2.55614 + vertex 0.955372 0.937964 2.55603 + endloop + endfacet + facet normal -0.473061 -0.348607 0.809127 + outer loop + vertex 0.958349 0.941951 2.56013 + vertex 0.960785 0.943382 2.56217 + vertex 0.956464 0.94566 2.56062 + endloop + endfacet + facet normal -0.553998 -0.354252 0.753387 + outer loop + vertex 0.951986 0.948233 2.55854 + vertex 0.955092 0.9432 2.55846 + vertex 0.956464 0.94566 2.56062 + endloop + endfacet + facet normal -0.563403 -0.391588 0.727486 + outer loop + vertex 0.954498 0.949282 2.56105 + vertex 0.951986 0.948233 2.55854 + vertex 0.956464 0.94566 2.56062 + endloop + endfacet + facet normal -0.489288 -0.359286 0.794677 + outer loop + vertex 0.956464 0.94566 2.56062 + vertex 0.957788 0.948429 2.56269 + vertex 0.954498 0.949282 2.56105 + endloop + endfacet + facet normal -0.478566 -0.366741 0.797795 + outer loop + vertex 0.960785 0.943382 2.56217 + vertex 0.957788 0.948429 2.56269 + vertex 0.956464 0.94566 2.56062 + endloop + endfacet + facet normal -0.562855 -0.392604 0.727362 + outer loop + vertex 0.951986 0.948233 2.55854 + vertex 0.954498 0.949282 2.56105 + vertex 0.951932 0.951617 2.56033 + endloop + endfacet + facet normal -0.537996 -0.353548 0.765222 + outer loop + vertex 0.954498 0.949282 2.56105 + vertex 0.953939 0.952997 2.56237 + vertex 0.951932 0.951617 2.56033 + endloop + endfacet + facet normal -0.489229 -0.357078 0.795707 + outer loop + vertex 0.954498 0.949282 2.56105 + vertex 0.957788 0.948429 2.56269 + vertex 0.953939 0.952997 2.56237 + endloop + endfacet + facet normal -0.473667 -0.342893 0.811211 + outer loop + vertex 0.957788 0.948429 2.56269 + vertex 0.958416 0.95242 2.56474 + vertex 0.953939 0.952997 2.56237 + endloop + endfacet + facet normal -0.471314 -0.354397 0.80763 + outer loop + vertex 0.957433 0.956334 2.56584 + vertex 0.955485 0.959344 2.56603 + vertex 0.953799 0.95757 2.56426 + endloop + endfacet + facet normal -0.470306 -0.346095 0.811807 + outer loop + vertex 0.957433 0.956334 2.56584 + vertex 0.953799 0.95757 2.56426 + vertex 0.958416 0.95242 2.56474 + endloop + endfacet + facet normal -0.473216 -0.348976 0.808877 + outer loop + vertex 0.958416 0.95242 2.56474 + vertex 0.953799 0.95757 2.56426 + vertex 0.953939 0.952997 2.56237 + endloop + endfacet + facet normal -0.461102 -0.348306 0.81613 + outer loop + vertex 0.957433 0.956334 2.56584 + vertex 0.959045 0.958243 2.56757 + vertex 0.955485 0.959344 2.56603 + endloop + endfacet + facet normal -0.473608 -0.351949 0.807359 + outer loop + vertex 0.953799 0.95757 2.56426 + vertex 0.955485 0.959344 2.56603 + vertex 0.952624 0.961504 2.56529 + endloop + endfacet + facet normal -0.469079 -0.34387 0.813461 + outer loop + vertex 0.955485 0.959344 2.56603 + vertex 0.954661 0.963128 2.56715 + vertex 0.952624 0.961504 2.56529 + endloop + endfacet + facet normal -0.460616 -0.343505 0.818436 + outer loop + vertex 0.955485 0.959344 2.56603 + vertex 0.959045 0.958243 2.56757 + vertex 0.954661 0.963128 2.56715 + endloop + endfacet + facet normal -0.45883 -0.341755 0.82017 + outer loop + vertex 0.959045 0.958243 2.56757 + vertex 0.958892 0.962721 2.56935 + vertex 0.954661 0.963128 2.56715 + endloop + endfacet + facet normal -0.462828 -0.345857 0.816194 + outer loop + vertex 0.958245 0.966315 2.57048 + vertex 0.95647 0.969976 2.57102 + vertex 0.95516 0.967177 2.56909 + endloop + endfacet + facet normal -0.462407 -0.340076 0.818858 + outer loop + vertex 0.958245 0.966315 2.57048 + vertex 0.95516 0.967177 2.56909 + vertex 0.958892 0.962721 2.56935 + endloop + endfacet + facet normal -0.459243 -0.337258 0.821799 + outer loop + vertex 0.958892 0.962721 2.56935 + vertex 0.95516 0.967177 2.56909 + vertex 0.954661 0.963128 2.56715 + endloop + endfacet + facet normal -0.493889 -0.357422 0.792668 + outer loop + vertex 0.958245 0.966315 2.57048 + vertex 0.960229 0.967235 2.57213 + vertex 0.95647 0.969976 2.57102 + endloop + endfacet + facet normal -0.465241 -0.344251 0.815501 + outer loop + vertex 0.952082 0.972397 2.56954 + vertex 0.95516 0.967177 2.56909 + vertex 0.95647 0.969976 2.57102 + endloop + endfacet + facet normal -0.461878 -0.334524 0.82144 + outer loop + vertex 0.954531 0.973851 2.57151 + vertex 0.952082 0.972397 2.56954 + vertex 0.95647 0.969976 2.57102 + endloop + endfacet + facet normal -0.490901 -0.34627 0.799446 + outer loop + vertex 0.95647 0.969976 2.57102 + vertex 0.95868 0.972598 2.57351 + vertex 0.954531 0.973851 2.57151 + endloop + endfacet + facet normal -0.489139 -0.348048 0.799754 + outer loop + vertex 0.960229 0.967235 2.57213 + vertex 0.95868 0.972598 2.57351 + vertex 0.95647 0.969976 2.57102 + endloop + endfacet + facet normal -0.464038 -0.331109 0.821605 + outer loop + vertex 0.952082 0.972397 2.56954 + vertex 0.954531 0.973851 2.57151 + vertex 0.951735 0.976222 2.57088 + endloop + endfacet + facet normal -0.46341 -0.330176 0.822335 + outer loop + vertex 0.954531 0.973851 2.57151 + vertex 0.953653 0.977951 2.57266 + vertex 0.951735 0.976222 2.57088 + endloop + endfacet + facet normal -0.489769 -0.331356 0.80643 + outer loop + vertex 0.954531 0.973851 2.57151 + vertex 0.95868 0.972598 2.57351 + vertex 0.953653 0.977951 2.57266 + endloop + endfacet + facet normal -0.483136 -0.324017 0.813384 + outer loop + vertex 0.95868 0.972598 2.57351 + vertex 0.95726 0.978041 2.57484 + vertex 0.953653 0.977951 2.57266 + endloop + endfacet + facet normal -0.484881 -0.305259 0.819578 + outer loop + vertex 0.956959 0.981228 2.57589 + vertex 0.955557 0.983997 2.57609 + vertex 0.953726 0.982543 2.57446 + endloop + endfacet + facet normal -0.486516 -0.31385 0.815353 + outer loop + vertex 0.956959 0.981228 2.57589 + vertex 0.953726 0.982543 2.57446 + vertex 0.95726 0.978041 2.57484 + endloop + endfacet + facet normal -0.485291 -0.312794 0.816488 + outer loop + vertex 0.95726 0.978041 2.57484 + vertex 0.953726 0.982543 2.57446 + vertex 0.953653 0.977951 2.57266 + endloop + endfacet + facet normal -0.507006 -0.315206 0.802241 + outer loop + vertex 0.956959 0.981228 2.57589 + vertex 0.958821 0.982719 2.57765 + vertex 0.955557 0.983997 2.57609 + endloop + endfacet + facet normal -0.480698 -0.310905 0.819919 + outer loop + vertex 0.953726 0.982543 2.57446 + vertex 0.955557 0.983997 2.57609 + vertex 0.953183 0.986212 2.57553 + endloop + endfacet + facet normal -0.495066 -0.330374 0.803594 + outer loop + vertex 0.955557 0.983997 2.57609 + vertex 0.955218 0.987143 2.57717 + vertex 0.953183 0.986212 2.57553 + endloop + endfacet + facet normal -0.509113 -0.329033 0.795325 + outer loop + vertex 0.955557 0.983997 2.57609 + vertex 0.958821 0.982719 2.57765 + vertex 0.955218 0.987143 2.57717 + endloop + endfacet + facet normal -0.507987 -0.327992 0.796474 + outer loop + vertex 0.958821 0.982719 2.57765 + vertex 0.958667 0.987324 2.57945 + vertex 0.955218 0.987143 2.57717 + endloop + endfacet + facet normal -0.495303 -0.320129 0.807584 + outer loop + vertex 0.95786 0.991139 2.58049 + vertex 0.956219 0.994817 2.58094 + vertex 0.953767 0.99248 2.57851 + endloop + endfacet + facet normal -0.495778 -0.324721 0.805456 + outer loop + vertex 0.95786 0.991139 2.58049 + vertex 0.953767 0.99248 2.57851 + vertex 0.958667 0.987324 2.57945 + endloop + endfacet + facet normal -0.50602 -0.336509 0.79417 + outer loop + vertex 0.958667 0.987324 2.57945 + vertex 0.953767 0.99248 2.57851 + vertex 0.955218 0.987143 2.57717 + endloop + endfacet + facet normal -0.469467 -0.310913 0.826398 + outer loop + vertex 0.95786 0.991139 2.58049 + vertex 0.960074 0.992309 2.58219 + vertex 0.956219 0.994817 2.58094 + endloop + endfacet + facet normal -0.490893 -0.325376 0.80818 + outer loop + vertex 0.95257 0.997655 2.57986 + vertex 0.953767 0.99248 2.57851 + vertex 0.956219 0.994817 2.58094 + endloop + endfacet + facet normal -0.487583 -0.319475 0.812526 + outer loop + vertex 0.954998 0.997684 2.58133 + vertex 0.95257 0.997655 2.57986 + vertex 0.956219 0.994817 2.58094 + endloop + endfacet + facet normal -0.480658 -0.317214 0.817522 + outer loop + vertex 0.956219 0.994817 2.58094 + vertex 0.958106 0.997827 2.58322 + vertex 0.954998 0.997684 2.58133 + endloop + endfacet + facet normal -0.474514 -0.322281 0.819128 + outer loop + vertex 0.960074 0.992309 2.58219 + vertex 0.958106 0.997827 2.58322 + vertex 0.956219 0.994817 2.58094 + endloop + endfacet + facet normal -0.487204 -0.321537 0.81194 + outer loop + vertex 0.95257 0.997655 2.57986 + vertex 0.954998 0.997684 2.58133 + vertex 0.953147 1.00057 2.58137 + endloop + endfacet + facet normal -0.47841 -0.316813 0.818996 + outer loop + vertex 0.958065 1.00203 2.58487 + vertex 0.956635 1.00579 2.58549 + vertex 0.95411 1.00376 2.58323 + endloop + endfacet + facet normal -0.480346 -0.325589 0.814408 + outer loop + vertex 0.958106 0.997827 2.58322 + vertex 0.958065 1.00203 2.58487 + vertex 0.95411 1.00376 2.58323 + endloop + endfacet + facet normal -0.484216 -0.328189 0.811065 + outer loop + vertex 0.958106 0.997827 2.58322 + vertex 0.95411 1.00376 2.58323 + vertex 0.953147 1.00057 2.58137 + endloop + endfacet + facet normal -0.480622 -0.317388 0.817476 + outer loop + vertex 0.958106 0.997827 2.58322 + vertex 0.953147 1.00057 2.58137 + vertex 0.954998 0.997684 2.58133 + endloop + endfacet + facet normal -0.400237 -0.295093 0.867601 + outer loop + vertex 0.958065 1.00203 2.58487 + vertex 0.960938 1.00374 2.58678 + vertex 0.956635 1.00579 2.58549 + endloop + endfacet + facet normal -0.47646 -0.319388 0.819132 + outer loop + vertex 0.953019 1.00831 2.58437 + vertex 0.95411 1.00376 2.58323 + vertex 0.956635 1.00579 2.58549 + endloop + endfacet + facet normal -0.478089 -0.322735 0.816868 + outer loop + vertex 0.955232 1.00917 2.58601 + vertex 0.953019 1.00831 2.58437 + vertex 0.956635 1.00579 2.58549 + endloop + endfacet + facet normal -0.417589 -0.303637 0.856402 + outer loop + vertex 0.956635 1.00579 2.58549 + vertex 0.958789 1.00872 2.58758 + vertex 0.955232 1.00917 2.58601 + endloop + endfacet + facet normal -0.406203 -0.313413 0.858354 + outer loop + vertex 0.960938 1.00374 2.58678 + vertex 0.958789 1.00872 2.58758 + vertex 0.956635 1.00579 2.58549 + endloop + endfacet + facet normal -0.480142 -0.318404 0.817363 + outer loop + vertex 0.953019 1.00831 2.58437 + vertex 0.955232 1.00917 2.58601 + vertex 0.952896 1.0113 2.58546 + endloop + endfacet + facet normal -0.471 -0.305775 0.827443 + outer loop + vertex 0.955232 1.00917 2.58601 + vertex 0.955024 1.0124 2.58708 + vertex 0.952896 1.0113 2.58546 + endloop + endfacet + facet normal -0.417396 -0.311112 0.853809 + outer loop + vertex 0.955232 1.00917 2.58601 + vertex 0.958789 1.00872 2.58758 + vertex 0.955024 1.0124 2.58708 + endloop + endfacet + facet normal -0.412164 -0.305136 0.858495 + outer loop + vertex 0.958789 1.00872 2.58758 + vertex 0.958295 1.01346 2.58903 + vertex 0.955024 1.0124 2.58708 + endloop + endfacet + facet normal -0.418837 -0.310634 0.853277 + outer loop + vertex 0.958061 1.01709 2.59021 + vertex 0.956384 1.02076 2.59072 + vertex 0.95375 1.01774 2.58833 + endloop + endfacet + facet normal -0.418869 -0.305345 0.855169 + outer loop + vertex 0.958061 1.01709 2.59021 + vertex 0.95375 1.01774 2.58833 + vertex 0.958295 1.01346 2.58903 + endloop + endfacet + facet normal -0.414352 -0.299867 0.859297 + outer loop + vertex 0.958295 1.01346 2.58903 + vertex 0.95375 1.01774 2.58833 + vertex 0.955024 1.0124 2.58708 + endloop + endfacet + facet normal -0.30694 -0.26786 0.913257 + outer loop + vertex 0.958061 1.01709 2.59021 + vertex 0.960623 1.01951 2.59178 + vertex 0.956384 1.02076 2.59072 + endloop + endfacet + facet normal -0.422032 -0.307502 0.852837 + outer loop + vertex 0.952507 1.02309 2.58965 + vertex 0.95375 1.01774 2.58833 + vertex 0.956384 1.02076 2.59072 + endloop + endfacet + facet normal -0.422865 -0.309393 0.85174 + outer loop + vertex 0.954919 1.02439 2.59131 + vertex 0.952507 1.02309 2.58965 + vertex 0.956384 1.02076 2.59072 + endloop + endfacet + facet normal -0.3202 -0.276783 0.906015 + outer loop + vertex 0.956384 1.02076 2.59072 + vertex 0.958716 1.02431 2.59263 + vertex 0.954919 1.02439 2.59131 + endloop + endfacet + facet normal -0.31022 -0.284008 0.90725 + outer loop + vertex 0.960623 1.01951 2.59178 + vertex 0.958716 1.02431 2.59263 + vertex 0.956384 1.02076 2.59072 + endloop + endfacet + facet normal -0.426658 -0.302901 0.852182 + outer loop + vertex 0.952507 1.02309 2.58965 + vertex 0.954919 1.02439 2.59131 + vertex 0.952362 1.02641 2.59075 + endloop + endfacet + facet normal -0.405855 -0.270778 0.872904 + outer loop + vertex 0.954919 1.02439 2.59131 + vertex 0.954714 1.02851 2.5925 + vertex 0.952362 1.02641 2.59075 + endloop + endfacet + facet normal -0.320253 -0.276079 0.906211 + outer loop + vertex 0.954919 1.02439 2.59131 + vertex 0.958716 1.02431 2.59263 + vertex 0.954714 1.02851 2.5925 + endloop + endfacet + facet normal -0.327415 -0.283059 0.901486 + outer loop + vertex 0.958716 1.02431 2.59263 + vertex 0.958364 1.02788 2.59362 + vertex 0.954714 1.02851 2.5925 + endloop + endfacet + facet normal -0.326572 -0.271032 0.905479 + outer loop + vertex 0.958364 1.02788 2.59362 + vertex 0.957734 1.03172 2.59455 + vertex 0.954714 1.02851 2.5925 + endloop + endfacet + facet normal -0.314234 -0.283067 0.906162 + outer loop + vertex 0.954714 1.02851 2.5925 + vertex 0.957734 1.03172 2.59455 + vertex 0.953996 1.03235 2.59345 + endloop + endfacet + facet normal -0.330828 -0.30471 0.893143 + outer loop + vertex 0.95719 1.03605 2.59571 + vertex 0.955389 1.03921 2.59612 + vertex 0.952932 1.03664 2.59433 + endloop + endfacet + facet normal -0.330206 -0.283333 0.900381 + outer loop + vertex 0.95719 1.03605 2.59571 + vertex 0.952932 1.03664 2.59433 + vertex 0.957734 1.03172 2.59455 + endloop + endfacet + facet normal -0.313018 -0.266072 0.911716 + outer loop + vertex 0.957734 1.03172 2.59455 + vertex 0.952932 1.03664 2.59433 + vertex 0.953996 1.03235 2.59345 + endloop + endfacet + facet normal -0.204815 -0.240074 0.948902 + outer loop + vertex 0.95719 1.03605 2.59571 + vertex 0.960038 1.03928 2.59714 + vertex 0.955389 1.03921 2.59612 + endloop + endfacet + facet normal -0.333091 -0.302485 0.893058 + outer loop + vertex 0.952932 1.03664 2.59433 + vertex 0.955389 1.03921 2.59612 + vertex 0.952427 1.04117 2.59568 + endloop + endfacet + facet normal -0.308216 -0.259845 0.915141 + outer loop + vertex 0.955389 1.03921 2.59612 + vertex 0.955082 1.04384 2.59733 + vertex 0.952427 1.04117 2.59568 + endloop + endfacet + facet normal -0.203397 -0.260399 0.943834 + outer loop + vertex 0.955389 1.03921 2.59612 + vertex 0.960038 1.03928 2.59714 + vertex 0.955082 1.04384 2.59733 + endloop + endfacet + facet normal -0.196818 -0.25339 0.94713 + outer loop + vertex 0.960038 1.03928 2.59714 + vertex 0.959693 1.0441 2.59836 + vertex 0.955082 1.04384 2.59733 + endloop + endfacet + facet normal -0.192668 -0.289235 0.937669 + outer loop + vertex 0.959693 1.0441 2.59836 + vertex 0.957854 1.04689 2.59884 + vertex 0.955082 1.04384 2.59733 + endloop + endfacet + facet normal -0.209289 -0.274537 0.938524 + outer loop + vertex 0.955082 1.04384 2.59733 + vertex 0.957854 1.04689 2.59884 + vertex 0.954748 1.04842 2.5986 + endloop + endfacet + facet normal -0.161299 0.222958 0.961391 + outer loop + vertex 0.953297 1.97164 2.59775 + vertex 0.957725 1.97631 2.59741 + vertex 0.953234 1.9761 2.5967 + endloop + endfacet + facet normal -0.161157 0.209471 0.964443 + outer loop + vertex 0.953234 1.9761 2.5967 + vertex 0.957725 1.97631 2.59741 + vertex 0.957276 1.98001 2.59653 + endloop + endfacet + facet normal -0.25882 0.253401 0.932095 + outer loop + vertex 0.953318 1.98656 2.59341 + vertex 0.958129 1.99164 2.59337 + vertex 0.95332 1.99126 2.59214 + endloop + endfacet + facet normal -0.422033 0.312441 0.85104 + outer loop + vertex 0.955192 1.99852 2.5907 + vertex 0.95149 1.99583 2.58985 + vertex 0.95376 1.99499 2.59129 + endloop + endfacet + facet normal -0.279952 0.266608 0.922251 + outer loop + vertex 0.95376 1.99499 2.59129 + vertex 0.957669 1.99634 2.59208 + vertex 0.955192 1.99852 2.5907 + endloop + endfacet + facet normal -0.273936 0.244628 0.930116 + outer loop + vertex 0.95376 1.99499 2.59129 + vertex 0.95332 1.99126 2.59214 + vertex 0.957669 1.99634 2.59208 + endloop + endfacet + facet normal -0.258597 0.231575 0.937817 + outer loop + vertex 0.95332 1.99126 2.59214 + vertex 0.958129 1.99164 2.59337 + vertex 0.957669 1.99634 2.59208 + endloop + endfacet + facet normal -0.421723 0.311904 0.85139 + outer loop + vertex 0.952908 2.0012 2.58858 + vertex 0.95149 1.99583 2.58985 + vertex 0.955192 1.99852 2.5907 + endloop + endfacet + facet normal -0.401929 0.330697 0.853869 + outer loop + vertex 0.957106 2.00207 2.59023 + vertex 0.952908 2.0012 2.58858 + vertex 0.955192 1.99852 2.5907 + endloop + endfacet + facet normal -0.306807 0.286581 0.907601 + outer loop + vertex 0.955192 1.99852 2.5907 + vertex 0.958507 2.0003 2.59126 + vertex 0.957106 2.00207 2.59023 + endloop + endfacet + facet normal -0.291526 0.253505 0.92236 + outer loop + vertex 0.957669 1.99634 2.59208 + vertex 0.958507 2.0003 2.59126 + vertex 0.955192 1.99852 2.5907 + endloop + endfacet + facet normal -0.260122 0.316778 0.912134 + outer loop + vertex 0.957106 2.00207 2.59023 + vertex 0.960814 2.00369 2.59072 + vertex 0.958555 2.00645 2.58912 + endloop + endfacet + facet normal -0.402636 0.347442 0.846858 + outer loop + vertex 0.957106 2.00207 2.59023 + vertex 0.958555 2.00645 2.58912 + vertex 0.952908 2.0012 2.58858 + endloop + endfacet + facet normal -0.348157 0.284016 0.893376 + outer loop + vertex 0.952908 2.0012 2.58858 + vertex 0.958555 2.00645 2.58912 + vertex 0.954224 2.00676 2.58733 + endloop + endfacet + facet normal -0.262387 0.322822 0.909362 + outer loop + vertex 0.960814 2.00369 2.59072 + vertex 0.957106 2.00207 2.59023 + vertex 0.958507 2.0003 2.59126 + endloop + endfacet + facet normal -0.467805 0.318764 0.824347 + outer loop + vertex 0.955544 2.01365 2.5856 + vertex 0.951748 2.01067 2.5846 + vertex 0.9542 2.01003 2.58623 + endloop + endfacet + facet normal -0.364112 0.290835 0.884781 + outer loop + vertex 0.9542 2.01003 2.58623 + vertex 0.95823 2.0116 2.58738 + vertex 0.955544 2.01365 2.5856 + endloop + endfacet + facet normal -0.364833 0.293562 0.883582 + outer loop + vertex 0.9542 2.01003 2.58623 + vertex 0.954224 2.00676 2.58733 + vertex 0.95823 2.0116 2.58738 + endloop + endfacet + facet normal -0.348825 0.28021 0.894317 + outer loop + vertex 0.954224 2.00676 2.58733 + vertex 0.958555 2.00645 2.58912 + vertex 0.95823 2.0116 2.58738 + endloop + endfacet + facet normal -0.466184 0.316035 0.826314 + outer loop + vertex 0.953062 2.01605 2.58328 + vertex 0.951748 2.01067 2.5846 + vertex 0.955544 2.01365 2.5856 + endloop + endfacet + facet normal -0.4689 0.312894 0.825972 + outer loop + vertex 0.957098 2.01729 2.5851 + vertex 0.953062 2.01605 2.58328 + vertex 0.955544 2.01365 2.5856 + endloop + endfacet + facet normal -0.375614 0.280821 0.883206 + outer loop + vertex 0.955544 2.01365 2.5856 + vertex 0.959328 2.01629 2.58637 + vertex 0.957098 2.01729 2.5851 + endloop + endfacet + facet normal -0.373945 0.277961 0.884818 + outer loop + vertex 0.95823 2.0116 2.58738 + vertex 0.959328 2.01629 2.58637 + vertex 0.955544 2.01365 2.5856 + endloop + endfacet + facet normal -0.409101 0.335103 0.84873 + outer loop + vertex 0.957098 2.01729 2.5851 + vertex 0.959751 2.01931 2.58558 + vertex 0.958189 2.02121 2.58408 + endloop + endfacet + facet normal -0.471919 0.343035 0.81217 + outer loop + vertex 0.957098 2.01729 2.5851 + vertex 0.958189 2.02121 2.58408 + vertex 0.953062 2.01605 2.58328 + endloop + endfacet + facet normal -0.440732 0.307222 0.843428 + outer loop + vertex 0.953062 2.01605 2.58328 + vertex 0.958189 2.02121 2.58408 + vertex 0.954422 2.02149 2.58201 + endloop + endfacet + facet normal -0.37494 0.282153 0.883068 + outer loop + vertex 0.959751 2.01931 2.58558 + vertex 0.957098 2.01729 2.5851 + vertex 0.959328 2.01629 2.58637 + endloop + endfacet + facet normal -0.487825 0.326898 0.809422 + outer loop + vertex 0.956255 2.0275 2.58077 + vertex 0.952912 2.02628 2.57925 + vertex 0.954737 2.02474 2.58097 + endloop + endfacet + facet normal -0.431856 0.299146 0.850889 + outer loop + vertex 0.954737 2.02474 2.58097 + vertex 0.958346 2.02606 2.58233 + vertex 0.956255 2.0275 2.58077 + endloop + endfacet + facet normal -0.434486 0.312738 0.84464 + outer loop + vertex 0.954737 2.02474 2.58097 + vertex 0.954422 2.02149 2.58201 + vertex 0.958346 2.02606 2.58233 + endloop + endfacet + facet normal -0.438697 0.316613 0.841012 + outer loop + vertex 0.954422 2.02149 2.58201 + vertex 0.958189 2.02121 2.58408 + vertex 0.958346 2.02606 2.58233 + endloop + endfacet + facet normal -0.454535 0.339799 0.823368 + outer loop + vertex 0.956255 2.0275 2.58077 + vertex 0.95892 2.02984 2.58127 + vertex 0.956659 2.03067 2.57968 + endloop + endfacet + facet normal -0.489306 0.33762 0.80411 + outer loop + vertex 0.956255 2.0275 2.58077 + vertex 0.956659 2.03067 2.57968 + vertex 0.952912 2.02628 2.57925 + endloop + endfacet + facet normal -0.495312 0.343355 0.797981 + outer loop + vertex 0.952912 2.02628 2.57925 + vertex 0.956659 2.03067 2.57968 + vertex 0.953282 2.03093 2.57747 + endloop + endfacet + facet normal -0.428441 0.30409 0.850863 + outer loop + vertex 0.95892 2.02984 2.58127 + vertex 0.956255 2.0275 2.58077 + vertex 0.958346 2.02606 2.58233 + endloop + endfacet + facet normal -0.465592 0.327883 0.82202 + outer loop + vertex 0.955243 2.03851 2.57547 + vertex 0.951532 2.03553 2.57456 + vertex 0.954036 2.03472 2.5763 + endloop + endfacet + facet normal -0.492609 0.332603 0.804184 + outer loop + vertex 0.954036 2.03472 2.5763 + vertex 0.958089 2.03601 2.57825 + vertex 0.955243 2.03851 2.57547 + endloop + endfacet + facet normal -0.493744 0.345481 0.798035 + outer loop + vertex 0.954036 2.03472 2.5763 + vertex 0.953282 2.03093 2.57747 + vertex 0.958089 2.03601 2.57825 + endloop + endfacet + facet normal -0.494539 0.346369 0.797157 + outer loop + vertex 0.953282 2.03093 2.57747 + vertex 0.956659 2.03067 2.57968 + vertex 0.958089 2.03601 2.57825 + endloop + endfacet + facet normal -0.466651 0.329597 0.820733 + outer loop + vertex 0.952057 2.03999 2.57307 + vertex 0.951532 2.03553 2.57456 + vertex 0.955243 2.03851 2.57547 + endloop + endfacet + facet normal -0.464924 0.3328 0.82042 + outer loop + vertex 0.955921 2.04292 2.57407 + vertex 0.952057 2.03999 2.57307 + vertex 0.955243 2.03851 2.57547 + endloop + endfacet + facet normal -0.487629 0.332146 0.807401 + outer loop + vertex 0.955243 2.03851 2.57547 + vertex 0.959169 2.04162 2.57656 + vertex 0.955921 2.04292 2.57407 + endloop + endfacet + facet normal -0.48987 0.336008 0.804441 + outer loop + vertex 0.958089 2.03601 2.57825 + vertex 0.959169 2.04162 2.57656 + vertex 0.955243 2.03851 2.57547 + endloop + endfacet + facet normal -0.453709 0.313311 0.834257 + outer loop + vertex 0.956124 2.04759 2.57229 + vertex 0.951462 2.04544 2.57056 + vertex 0.953351 2.04385 2.57219 + endloop + endfacet + facet normal -0.470478 0.34261 0.813184 + outer loop + vertex 0.953351 2.04385 2.57219 + vertex 0.952057 2.03999 2.57307 + vertex 0.955921 2.04292 2.57407 + endloop + endfacet + facet normal -0.476136 0.330449 0.814922 + outer loop + vertex 0.956124 2.04759 2.57229 + vertex 0.953351 2.04385 2.57219 + vertex 0.955921 2.04292 2.57407 + endloop + endfacet + facet normal -0.497707 0.326982 0.803349 + outer loop + vertex 0.956124 2.04759 2.57229 + vertex 0.955921 2.04292 2.57407 + vertex 0.959194 2.04566 2.57498 + endloop + endfacet + facet normal -0.505143 0.315227 0.803407 + outer loop + vertex 0.956124 2.04759 2.57229 + vertex 0.959194 2.04566 2.57498 + vertex 0.959559 2.0486 2.57406 + endloop + endfacet + facet normal -0.493449 0.320114 0.808724 + outer loop + vertex 0.959194 2.04566 2.57498 + vertex 0.955921 2.04292 2.57407 + vertex 0.959169 2.04162 2.57656 + endloop + endfacet + facet normal -0.462617 0.347672 0.815543 + outer loop + vertex 0.953002 2.05041 2.56932 + vertex 0.951462 2.04544 2.57056 + vertex 0.956124 2.04759 2.57229 + endloop + endfacet + facet normal -0.462068 0.348318 0.815578 + outer loop + vertex 0.956951 2.05194 2.5709 + vertex 0.953002 2.05041 2.56932 + vertex 0.956124 2.04759 2.57229 + endloop + endfacet + facet normal -0.507527 0.348203 0.788144 + outer loop + vertex 0.956124 2.04759 2.57229 + vertex 0.959478 2.05155 2.5727 + vertex 0.956951 2.05194 2.5709 + endloop + endfacet + facet normal -0.50709 0.347785 0.78861 + outer loop + vertex 0.959559 2.0486 2.57406 + vertex 0.959478 2.05155 2.5727 + vertex 0.956124 2.04759 2.57229 + endloop + endfacet + facet normal -0.496818 0.346887 0.795513 + outer loop + vertex 0.956951 2.05194 2.5709 + vertex 0.959339 2.05461 2.57123 + vertex 0.956734 2.05517 2.56936 + endloop + endfacet + facet normal -0.463525 0.356611 0.811155 + outer loop + vertex 0.956951 2.05194 2.5709 + vertex 0.956734 2.05517 2.56936 + vertex 0.953002 2.05041 2.56932 + endloop + endfacet + facet normal -0.459996 0.353817 0.814381 + outer loop + vertex 0.953002 2.05041 2.56932 + vertex 0.956734 2.05517 2.56936 + vertex 0.953113 2.05538 2.56722 + endloop + endfacet + facet normal -0.505164 0.355488 0.786408 + outer loop + vertex 0.959339 2.05461 2.57123 + vertex 0.956951 2.05194 2.5709 + vertex 0.959478 2.05155 2.5727 + endloop + endfacet + facet normal -0.439186 0.337222 0.832704 + outer loop + vertex 0.956004 2.06186 2.56601 + vertex 0.952635 2.06101 2.56457 + vertex 0.954282 2.05922 2.56617 + endloop + endfacet + facet normal -0.468119 0.35476 0.809327 + outer loop + vertex 0.954282 2.05922 2.56617 + vertex 0.957258 2.05959 2.56773 + vertex 0.956004 2.06186 2.56601 + endloop + endfacet + facet normal -0.467373 0.36345 0.805895 + outer loop + vertex 0.954282 2.05922 2.56617 + vertex 0.953113 2.05538 2.56722 + vertex 0.957258 2.05959 2.56773 + endloop + endfacet + facet normal -0.459731 0.354932 0.814046 + outer loop + vertex 0.953113 2.05538 2.56722 + vertex 0.956734 2.05517 2.56936 + vertex 0.957258 2.05959 2.56773 + endloop + endfacet + facet normal -0.473984 0.324818 0.818433 + outer loop + vertex 0.956004 2.06186 2.56601 + vertex 0.958518 2.06341 2.56685 + vertex 0.956614 2.06508 2.56508 + endloop + endfacet + facet normal -0.438288 0.323825 0.838475 + outer loop + vertex 0.956004 2.06186 2.56601 + vertex 0.956614 2.06508 2.56508 + vertex 0.952635 2.06101 2.56457 + endloop + endfacet + facet normal -0.455364 0.342629 0.821735 + outer loop + vertex 0.952635 2.06101 2.56457 + vertex 0.956614 2.06508 2.56508 + vertex 0.952813 2.06577 2.56269 + endloop + endfacet + facet normal -0.481869 0.344427 0.805712 + outer loop + vertex 0.958518 2.06341 2.56685 + vertex 0.956004 2.06186 2.56601 + vertex 0.957258 2.05959 2.56773 + endloop + endfacet + facet normal -0.501064 0.377996 0.778495 + outer loop + vertex 0.955093 2.0732 2.5607 + vertex 0.951814 2.07077 2.55977 + vertex 0.95386 2.0696 2.56165 + endloop + endfacet + facet normal -0.463896 0.372029 0.803987 + outer loop + vertex 0.95386 2.0696 2.56165 + vertex 0.958016 2.0706 2.56359 + vertex 0.955093 2.0732 2.5607 + endloop + endfacet + facet normal -0.46327 0.347309 0.815327 + outer loop + vertex 0.95386 2.0696 2.56165 + vertex 0.952813 2.06577 2.56269 + vertex 0.958016 2.0706 2.56359 + endloop + endfacet + facet normal -0.456623 0.338786 0.82263 + outer loop + vertex 0.952813 2.06577 2.56269 + vertex 0.956614 2.06508 2.56508 + vertex 0.958016 2.0706 2.56359 + endloop + endfacet + facet normal -0.514782 0.405222 0.75551 + outer loop + vertex 0.9519 2.07486 2.55763 + vertex 0.951814 2.07077 2.55977 + vertex 0.955093 2.0732 2.5607 + endloop + endfacet + facet normal -0.53878 0.365448 0.759055 + outer loop + vertex 0.95569 2.07764 2.55898 + vertex 0.9519 2.07486 2.55763 + vertex 0.955093 2.0732 2.5607 + endloop + endfacet + facet normal -0.484761 0.370945 0.79209 + outer loop + vertex 0.955093 2.0732 2.5607 + vertex 0.959054 2.07631 2.56167 + vertex 0.95569 2.07764 2.55898 + endloop + endfacet + facet normal -0.476613 0.357051 0.803339 + outer loop + vertex 0.958016 2.0706 2.56359 + vertex 0.959054 2.07631 2.56167 + vertex 0.955093 2.0732 2.5607 + endloop + endfacet + facet normal -0.561319 0.373266 0.738643 + outer loop + vertex 0.956021 2.08259 2.55685 + vertex 0.953015 2.08209 2.55482 + vertex 0.952829 2.07938 2.55605 + endloop + endfacet + facet normal -0.542984 0.374869 0.751426 + outer loop + vertex 0.952829 2.07938 2.55605 + vertex 0.9519 2.07486 2.55763 + vertex 0.95569 2.07764 2.55898 + endloop + endfacet + facet normal -0.55197 0.360713 0.751808 + outer loop + vertex 0.956021 2.08259 2.55685 + vertex 0.952829 2.07938 2.55605 + vertex 0.95569 2.07764 2.55898 + endloop + endfacet + facet normal -0.49926 0.370691 0.783152 + outer loop + vertex 0.956021 2.08259 2.55685 + vertex 0.95569 2.07764 2.55898 + vertex 0.959278 2.08048 2.55993 + endloop + endfacet + facet normal -0.510644 0.353831 0.783611 + outer loop + vertex 0.956021 2.08259 2.55685 + vertex 0.959278 2.08048 2.55993 + vertex 0.959864 2.08366 2.55887 + endloop + endfacet + facet normal -0.491657 0.357447 0.794044 + outer loop + vertex 0.959278 2.08048 2.55993 + vertex 0.95569 2.07764 2.55898 + vertex 0.959054 2.07631 2.56167 + endloop + endfacet + facet normal -0.557483 0.403771 0.725384 + outer loop + vertex 0.953056 2.08491 2.55328 + vertex 0.953015 2.08209 2.55482 + vertex 0.956021 2.08259 2.55685 + endloop + endfacet + facet normal -0.594495 0.35237 0.72278 + outer loop + vertex 0.955891 2.08755 2.55432 + vertex 0.953056 2.08491 2.55328 + vertex 0.956021 2.08259 2.55685 + endloop + endfacet + facet normal -0.537974 0.37119 0.756837 + outer loop + vertex 0.956021 2.08259 2.55685 + vertex 0.959327 2.08676 2.55716 + vertex 0.955891 2.08755 2.55432 + endloop + endfacet + facet normal -0.510428 0.347094 0.786758 + outer loop + vertex 0.959864 2.08366 2.55887 + vertex 0.959327 2.08676 2.55716 + vertex 0.956021 2.08259 2.55685 + endloop + endfacet + facet normal -0.648271 0.371032 0.664891 + outer loop + vertex 0.955936 2.09261 2.55177 + vertex 0.953047 2.09209 2.54924 + vertex 0.953029 2.08922 2.55082 + endloop + endfacet + facet normal -0.614663 0.388196 0.686654 + outer loop + vertex 0.953029 2.08922 2.55082 + vertex 0.953056 2.08491 2.55328 + vertex 0.955891 2.08755 2.55432 + endloop + endfacet + facet normal -0.635031 0.353548 0.686833 + outer loop + vertex 0.955936 2.09261 2.55177 + vertex 0.953029 2.08922 2.55082 + vertex 0.955891 2.08755 2.55432 + endloop + endfacet + facet normal -0.571309 0.374887 0.730113 + outer loop + vertex 0.955936 2.09261 2.55177 + vertex 0.955891 2.08755 2.55432 + vertex 0.959009 2.09063 2.55519 + endloop + endfacet + facet normal -0.58718 0.349892 0.729929 + outer loop + vertex 0.955936 2.09261 2.55177 + vertex 0.959009 2.09063 2.55519 + vertex 0.959482 2.09385 2.55402 + endloop + endfacet + facet normal -0.548899 0.343182 0.762192 + outer loop + vertex 0.959009 2.09063 2.55519 + vertex 0.955891 2.08755 2.55432 + vertex 0.959327 2.08676 2.55716 + endloop + endfacet + facet normal -0.649864 0.361275 0.668698 + outer loop + vertex 0.953367 2.09495 2.548 + vertex 0.953047 2.09209 2.54924 + vertex 0.955936 2.09261 2.55177 + endloop + endfacet + facet normal -0.663932 0.340858 0.665589 + outer loop + vertex 0.956046 2.09744 2.5494 + vertex 0.953367 2.09495 2.548 + vertex 0.955936 2.09261 2.55177 + endloop + endfacet + facet normal -0.595415 0.364068 0.716195 + outer loop + vertex 0.955936 2.09261 2.55177 + vertex 0.959134 2.09684 2.55227 + vertex 0.956046 2.09744 2.5494 + endloop + endfacet + facet normal -0.587366 0.356777 0.726437 + outer loop + vertex 0.959482 2.09385 2.55402 + vertex 0.959134 2.09684 2.55227 + vertex 0.955936 2.09261 2.55177 + endloop + endfacet + facet normal -0.670725 0.352177 0.652763 + outer loop + vertex 0.956103 2.10231 2.54693 + vertex 0.953101 2.10096 2.54457 + vertex 0.953893 2.09854 2.54669 + endloop + endfacet + facet normal -0.663808 0.340574 0.665859 + outer loop + vertex 0.953893 2.09854 2.54669 + vertex 0.953367 2.09495 2.548 + vertex 0.956046 2.09744 2.5494 + endloop + endfacet + facet normal -0.661147 0.345761 0.665833 + outer loop + vertex 0.956103 2.10231 2.54693 + vertex 0.953893 2.09854 2.54669 + vertex 0.956046 2.09744 2.5494 + endloop + endfacet + facet normal -0.613888 0.36304 0.700959 + outer loop + vertex 0.956103 2.10231 2.54693 + vertex 0.956046 2.09744 2.5494 + vertex 0.958928 2.10051 2.55033 + endloop + endfacet + facet normal -0.625343 0.344042 0.700416 + outer loop + vertex 0.956103 2.10231 2.54693 + vertex 0.958928 2.10051 2.55033 + vertex 0.959247 2.10348 2.54916 + endloop + endfacet + facet normal -0.601999 0.346205 0.719541 + outer loop + vertex 0.958928 2.10051 2.55033 + vertex 0.956046 2.09744 2.5494 + vertex 0.959134 2.09684 2.55227 + endloop + endfacet + facet normal -0.669965 0.324515 0.66771 + outer loop + vertex 0.953576 2.10451 2.54332 + vertex 0.953101 2.10096 2.54457 + vertex 0.956103 2.10231 2.54693 + endloop + endfacet + facet normal -0.656978 0.34434 0.670678 + outer loop + vertex 0.956188 2.10733 2.54444 + vertex 0.953576 2.10451 2.54332 + vertex 0.956103 2.10231 2.54693 + endloop + endfacet + facet normal -0.620171 0.357439 0.698302 + outer loop + vertex 0.956103 2.10231 2.54693 + vertex 0.958974 2.10646 2.54736 + vertex 0.956188 2.10733 2.54444 + endloop + endfacet + facet normal -0.625481 0.361847 0.69126 + outer loop + vertex 0.959247 2.10348 2.54916 + vertex 0.958974 2.10646 2.54736 + vertex 0.956103 2.10231 2.54693 + endloop + endfacet + facet normal -0.605985 0.357795 0.710468 + outer loop + vertex 0.956026 2.11218 2.54169 + vertex 0.952037 2.10982 2.53948 + vertex 0.953892 2.10809 2.54193 + endloop + endfacet + facet normal -0.645384 0.325573 0.691 + outer loop + vertex 0.953892 2.10809 2.54193 + vertex 0.953576 2.10451 2.54332 + vertex 0.956188 2.10733 2.54444 + endloop + endfacet + facet normal -0.626976 0.367404 0.686961 + outer loop + vertex 0.956026 2.11218 2.54169 + vertex 0.953892 2.10809 2.54193 + vertex 0.956188 2.10733 2.54444 + endloop + endfacet + facet normal -0.618183 0.371075 0.692931 + outer loop + vertex 0.956026 2.11218 2.54169 + vertex 0.956188 2.10733 2.54444 + vertex 0.958981 2.1103 2.54534 + endloop + endfacet + facet normal -0.607979 0.38736 0.693046 + outer loop + vertex 0.956026 2.11218 2.54169 + vertex 0.958981 2.1103 2.54534 + vertex 0.959497 2.11337 2.54407 + endloop + endfacet + facet normal -0.615699 0.367501 0.697035 + outer loop + vertex 0.958981 2.1103 2.54534 + vertex 0.956188 2.10733 2.54444 + vertex 0.958974 2.10646 2.54736 + endloop + endfacet + facet normal -0.607011 0.362688 0.707103 + outer loop + vertex 0.952283 2.11464 2.53722 + vertex 0.952037 2.10982 2.53948 + vertex 0.956026 2.11218 2.54169 + endloop + endfacet + facet normal -0.55109 0.445264 0.705719 + outer loop + vertex 0.956084 2.11701 2.53869 + vertex 0.952283 2.11464 2.53722 + vertex 0.956026 2.11218 2.54169 + endloop + endfacet + facet normal -0.601631 0.426876 0.675142 + outer loop + vertex 0.956026 2.11218 2.54169 + vertex 0.95922 2.11616 2.54202 + vertex 0.956084 2.11701 2.53869 + endloop + endfacet + facet normal -0.606133 0.431046 0.668432 + outer loop + vertex 0.959497 2.11337 2.54407 + vertex 0.95922 2.11616 2.54202 + vertex 0.956026 2.11218 2.54169 + endloop + endfacet + facet normal -0.53852 0.577064 0.613998 + outer loop + vertex 0.956488 2.12044 2.53622 + vertex 0.953855 2.12066 2.53371 + vertex 0.953379 2.11861 2.53522 + endloop + endfacet + facet normal -0.563417 0.490279 0.664972 + outer loop + vertex 0.953379 2.11861 2.53522 + vertex 0.952283 2.11464 2.53722 + vertex 0.956084 2.11701 2.53869 + endloop + endfacet + facet normal -0.528552 0.535516 0.658677 + outer loop + vertex 0.956488 2.12044 2.53622 + vertex 0.953379 2.11861 2.53522 + vertex 0.956084 2.11701 2.53869 + endloop + endfacet + facet normal -0.588394 0.516357 0.622228 + outer loop + vertex 0.956488 2.12044 2.53622 + vertex 0.956084 2.11701 2.53869 + vertex 0.959046 2.11931 2.53958 + endloop + endfacet + facet normal -0.575295 0.535159 0.618579 + outer loop + vertex 0.956488 2.12044 2.53622 + vertex 0.959046 2.11931 2.53958 + vertex 0.959008 2.1211 2.538 + endloop + endfacet + facet normal -0.57353 0.481545 0.662705 + outer loop + vertex 0.959046 2.11931 2.53958 + vertex 0.956084 2.11701 2.53869 + vertex 0.95922 2.11616 2.54202 + endloop + endfacet + facet normal -0.358445 0.859319 0.364812 + outer loop + vertex 0.95525 2.12641 2.52523 + vertex 0.952324 2.1261 2.52309 + vertex 0.953606 2.12492 2.52713 + endloop + endfacet + facet normal -0.38582 0.857684 0.339884 + outer loop + vertex 0.957273 2.1261 2.52832 + vertex 0.95525 2.12641 2.52523 + vertex 0.953606 2.12492 2.52713 + endloop + endfacet + facet normal -0.392033 0.838757 0.377886 + outer loop + vertex 0.957273 2.1261 2.52832 + vertex 0.953606 2.12492 2.52713 + vertex 0.958677 2.125 2.53221 + endloop + endfacet + facet normal -0.471534 0.753254 0.458546 + outer loop + vertex 0.958677 2.125 2.53221 + vertex 0.953606 2.12492 2.52713 + vertex 0.954607 2.12255 2.53205 + endloop + endfacet + facet normal -0.476496 0.679365 0.558045 + outer loop + vertex 0.956488 2.12044 2.53622 + vertex 0.954607 2.12255 2.53205 + vertex 0.953855 2.12066 2.53371 + endloop + endfacet + facet normal -0.530562 0.635947 0.560424 + outer loop + vertex 0.956488 2.12044 2.53622 + vertex 0.95966 2.12271 2.53665 + vertex 0.954607 2.12255 2.53205 + endloop + endfacet + facet normal -0.465074 0.74072 0.484809 + outer loop + vertex 0.95966 2.12271 2.53665 + vertex 0.958677 2.125 2.53221 + vertex 0.954607 2.12255 2.53205 + endloop + endfacet + facet normal -0.540976 0.657055 0.524999 + outer loop + vertex 0.95966 2.12271 2.53665 + vertex 0.956488 2.12044 2.53622 + vertex 0.959008 2.1211 2.538 + endloop + endfacet + facet normal -0.0475908 0.660961 0.74891 + outer loop + vertex 0.96 2.13226 2.52 + vertex 0.955 2.1319 2.52 + vertex 0.959539 2.12967 2.52226 + endloop + endfacet + facet normal -0.26921 0.357226 0.89438 + outer loop + vertex 0.959539 2.12967 2.52226 + vertex 0.955 2.1319 2.52 + vertex 0.954396 2.12774 2.52148 + endloop + endfacet + facet normal -0.371092 0.84539 0.384196 + outer loop + vertex 0.95525 2.12641 2.52523 + vertex 0.954396 2.12774 2.52148 + vertex 0.952324 2.1261 2.52309 + endloop + endfacet + facet normal -0.367184 0.847206 0.38395 + outer loop + vertex 0.95525 2.12641 2.52523 + vertex 0.959105 2.12756 2.52639 + vertex 0.954396 2.12774 2.52148 + endloop + endfacet + facet normal -0.374343 0.841022 0.390575 + outer loop + vertex 0.959105 2.12756 2.52639 + vertex 0.959539 2.12967 2.52226 + vertex 0.954396 2.12774 2.52148 + endloop + endfacet + facet normal -0.357417 0.876243 0.32319 + outer loop + vertex 0.959105 2.12756 2.52639 + vertex 0.95525 2.12641 2.52523 + vertex 0.957273 2.1261 2.52832 + endloop + endfacet + facet normal -0.193476 -0.970999 0.140457 + outer loop + vertex 0.959841 0.894172 2.52066 + vertex 0.965 0.893772 2.525 + vertex 0.960996 0.894335 2.52338 + endloop + endfacet + facet normal 0.109717 -0.96935 -0.219825 + outer loop + vertex 0.959841 0.894172 2.52066 + vertex 0.96 0.89434 2.52 + vertex 0.965 0.893772 2.525 + endloop + endfacet + facet normal -0.226473 -0.96701 0.116623 + outer loop + vertex 0.96 0.89434 2.52 + vertex 0.965 0.893169 2.52 + vertex 0.965 0.893772 2.525 + endloop + endfacet + facet normal -0.0586751 -0.979106 -0.194703 + outer loop + vertex 0.9648 0.893614 2.52585 + vertex 0.960996 0.894335 2.52338 + vertex 0.965 0.893772 2.525 + endloop + endfacet + facet normal -0.312367 -0.926413 0.210203 + outer loop + vertex 0.962499 0.894557 2.52659 + vertex 0.960996 0.894335 2.52338 + vertex 0.9648 0.893614 2.52585 + endloop + endfacet + facet normal -0.329581 -0.930276 0.161129 + outer loop + vertex 0.9648 0.893614 2.52585 + vertex 0.966274 0.893602 2.5288 + vertex 0.962499 0.894557 2.52659 + endloop + endfacet + facet normal -0.279236 -0.944081 0.175323 + outer loop + vertex 0.959841 0.894172 2.52066 + vertex 0.960996 0.894335 2.52338 + vertex 0.957136 0.895019 2.52091 + endloop + endfacet + facet normal -0.319005 -0.923483 0.213107 + outer loop + vertex 0.960996 0.894335 2.52338 + vertex 0.962499 0.894557 2.52659 + vertex 0.958102 0.895812 2.52544 + endloop + endfacet + facet normal -0.308849 -0.923535 0.227366 + outer loop + vertex 0.957136 0.895019 2.52091 + vertex 0.960996 0.894335 2.52338 + vertex 0.958102 0.895812 2.52544 + endloop + endfacet + facet normal -0.37805 -0.887861 0.262262 + outer loop + vertex 0.962499 0.894557 2.52659 + vertex 0.966274 0.893602 2.5288 + vertex 0.96322 0.895427 2.53057 + endloop + endfacet + facet normal -0.326561 -0.909384 0.257642 + outer loop + vertex 0.962499 0.894557 2.52659 + vertex 0.96322 0.895427 2.53057 + vertex 0.958102 0.895812 2.52544 + endloop + endfacet + facet normal -0.369212 -0.878741 0.302484 + outer loop + vertex 0.958102 0.895812 2.52544 + vertex 0.96322 0.895427 2.53057 + vertex 0.95784 0.897567 2.53022 + endloop + endfacet + facet normal -0.435427 -0.76995 0.466455 + outer loop + vertex 0.957519 0.899535 2.53344 + vertex 0.962681 0.897573 2.53502 + vertex 0.960626 0.899266 2.53589 + endloop + endfacet + facet normal -0.433472 -0.787247 0.438571 + outer loop + vertex 0.957519 0.899535 2.53344 + vertex 0.95784 0.897567 2.53022 + vertex 0.962681 0.897573 2.53502 + endloop + endfacet + facet normal -0.364177 -0.855253 0.368669 + outer loop + vertex 0.95784 0.897567 2.53022 + vertex 0.96322 0.895427 2.53057 + vertex 0.962681 0.897573 2.53502 + endloop + endfacet + facet normal -0.422955 -0.764875 0.485876 + outer loop + vertex 0.962681 0.897573 2.53502 + vertex 0.962698 0.899665 2.53833 + vertex 0.960626 0.899266 2.53589 + endloop + endfacet + facet normal -0.487946 -0.683945 0.542336 + outer loop + vertex 0.957519 0.899535 2.53344 + vertex 0.960626 0.899266 2.53589 + vertex 0.958434 0.901118 2.53626 + endloop + endfacet + facet normal -0.542353 -0.596072 0.592074 + outer loop + vertex 0.963424 0.901293 2.541 + vertex 0.961119 0.903451 2.54106 + vertex 0.958509 0.903431 2.53865 + endloop + endfacet + facet normal -0.539314 -0.645696 0.540571 + outer loop + vertex 0.962698 0.899665 2.53833 + vertex 0.963424 0.901293 2.541 + vertex 0.958509 0.903431 2.53865 + endloop + endfacet + facet normal -0.504087 -0.612325 0.60906 + outer loop + vertex 0.962698 0.899665 2.53833 + vertex 0.958509 0.903431 2.53865 + vertex 0.958434 0.901118 2.53626 + endloop + endfacet + facet normal -0.492864 -0.687897 0.532807 + outer loop + vertex 0.962698 0.899665 2.53833 + vertex 0.958434 0.901118 2.53626 + vertex 0.960626 0.899266 2.53589 + endloop + endfacet + facet normal -0.526101 -0.579569 0.622348 + outer loop + vertex 0.963424 0.901293 2.541 + vertex 0.963419 0.903849 2.54337 + vertex 0.961119 0.903451 2.54106 + endloop + endfacet + facet normal -0.572662 -0.531268 0.62435 + outer loop + vertex 0.958509 0.903431 2.53865 + vertex 0.961119 0.903451 2.54106 + vertex 0.95852 0.906136 2.54096 + endloop + endfacet + facet normal -0.580686 -0.445941 0.681132 + outer loop + vertex 0.963029 0.906741 2.54532 + vertex 0.961303 0.910125 2.54606 + vertex 0.95919 0.90875 2.54336 + endloop + endfacet + facet normal -0.58697 -0.505046 0.632768 + outer loop + vertex 0.963419 0.903849 2.54337 + vertex 0.963029 0.906741 2.54532 + vertex 0.95919 0.90875 2.54336 + endloop + endfacet + facet normal -0.557725 -0.479713 0.677361 + outer loop + vertex 0.963419 0.903849 2.54337 + vertex 0.95919 0.90875 2.54336 + vertex 0.95852 0.906136 2.54096 + endloop + endfacet + facet normal -0.560331 -0.51854 0.645868 + outer loop + vertex 0.963419 0.903849 2.54337 + vertex 0.95852 0.906136 2.54096 + vertex 0.961119 0.903451 2.54106 + endloop + endfacet + facet normal -0.540556 -0.434165 0.720624 + outer loop + vertex 0.963029 0.906741 2.54532 + vertex 0.965237 0.907283 2.5473 + vertex 0.961303 0.910125 2.54606 + endloop + endfacet + facet normal -0.599157 -0.419327 0.682038 + outer loop + vertex 0.957918 0.912826 2.54475 + vertex 0.95919 0.90875 2.54336 + vertex 0.961303 0.910125 2.54606 + endloop + endfacet + facet normal -0.601683 -0.425422 0.676013 + outer loop + vertex 0.960009 0.912799 2.54659 + vertex 0.957918 0.912826 2.54475 + vertex 0.961303 0.910125 2.54606 + endloop + endfacet + facet normal -0.545537 -0.409232 0.731381 + outer loop + vertex 0.961303 0.910125 2.54606 + vertex 0.96298 0.912606 2.5487 + vertex 0.960009 0.912799 2.54659 + endloop + endfacet + facet normal -0.53419 -0.419574 0.733893 + outer loop + vertex 0.965237 0.907283 2.5473 + vertex 0.96298 0.912606 2.5487 + vertex 0.961303 0.910125 2.54606 + endloop + endfacet + facet normal -0.614326 -0.380965 0.690991 + outer loop + vertex 0.957918 0.912826 2.54475 + vertex 0.960009 0.912799 2.54659 + vertex 0.958405 0.915614 2.54672 + endloop + endfacet + facet normal -0.564496 -0.409476 0.71671 + outer loop + vertex 0.962403 0.916503 2.55051 + vertex 0.960915 0.919175 2.55087 + vertex 0.959789 0.917621 2.54909 + endloop + endfacet + facet normal -0.564962 -0.41531 0.712976 + outer loop + vertex 0.96298 0.912606 2.5487 + vertex 0.962403 0.916503 2.55051 + vertex 0.959789 0.917621 2.54909 + endloop + endfacet + facet normal -0.579944 -0.423514 0.695918 + outer loop + vertex 0.96298 0.912606 2.5487 + vertex 0.959789 0.917621 2.54909 + vertex 0.958405 0.915614 2.54672 + endloop + endfacet + facet normal -0.556917 -0.351015 0.75275 + outer loop + vertex 0.96298 0.912606 2.5487 + vertex 0.958405 0.915614 2.54672 + vertex 0.960009 0.912799 2.54659 + endloop + endfacet + facet normal -0.483521 -0.374299 0.791269 + outer loop + vertex 0.962403 0.916503 2.55051 + vertex 0.964137 0.918087 2.55232 + vertex 0.960915 0.919175 2.55087 + endloop + endfacet + facet normal -0.585649 -0.388241 0.711537 + outer loop + vertex 0.959789 0.917621 2.54909 + vertex 0.960915 0.919175 2.55087 + vertex 0.958727 0.920782 2.54994 + endloop + endfacet + facet normal -0.571198 -0.351045 0.741957 + outer loop + vertex 0.960915 0.919175 2.55087 + vertex 0.960381 0.922158 2.55187 + vertex 0.958727 0.920782 2.54994 + endloop + endfacet + facet normal -0.481522 -0.354888 0.801368 + outer loop + vertex 0.960915 0.919175 2.55087 + vertex 0.964137 0.918087 2.55232 + vertex 0.960381 0.922158 2.55187 + endloop + endfacet + facet normal -0.49547 -0.369454 0.786138 + outer loop + vertex 0.964137 0.918087 2.55232 + vertex 0.963726 0.922736 2.55425 + vertex 0.960381 0.922158 2.55187 + endloop + endfacet + facet normal -0.535113 -0.418327 0.733932 + outer loop + vertex 0.962397 0.926672 2.55541 + vertex 0.960613 0.92952 2.55573 + vertex 0.958511 0.927469 2.55303 + endloop + endfacet + facet normal -0.536824 -0.399913 0.742892 + outer loop + vertex 0.962397 0.926672 2.55541 + vertex 0.958511 0.927469 2.55303 + vertex 0.963726 0.922736 2.55425 + endloop + endfacet + facet normal -0.50231 -0.349501 0.790907 + outer loop + vertex 0.963726 0.922736 2.55425 + vertex 0.958511 0.927469 2.55303 + vertex 0.960381 0.922158 2.55187 + endloop + endfacet + facet normal -0.462025 -0.380173 0.80125 + outer loop + vertex 0.962397 0.926672 2.55541 + vertex 0.964271 0.928324 2.55727 + vertex 0.960613 0.92952 2.55573 + endloop + endfacet + facet normal -0.546319 -0.405472 0.73289 + outer loop + vertex 0.958511 0.927469 2.55303 + vertex 0.960613 0.92952 2.55573 + vertex 0.958173 0.93166 2.55509 + endloop + endfacet + facet normal -0.521322 -0.365674 0.771042 + outer loop + vertex 0.960613 0.92952 2.55573 + vertex 0.960259 0.93271 2.557 + vertex 0.958173 0.93166 2.55509 + endloop + endfacet + facet normal -0.461242 -0.372647 0.805227 + outer loop + vertex 0.960613 0.92952 2.55573 + vertex 0.964271 0.928324 2.55727 + vertex 0.960259 0.93271 2.557 + endloop + endfacet + facet normal -0.455122 -0.36667 0.811429 + outer loop + vertex 0.964271 0.928324 2.55727 + vertex 0.963852 0.932947 2.55913 + vertex 0.960259 0.93271 2.557 + endloop + endfacet + facet normal -0.478913 -0.386392 0.788253 + outer loop + vertex 0.962604 0.93682 2.56022 + vertex 0.960925 0.939732 2.56062 + vertex 0.958498 0.93795 2.55828 + endloop + endfacet + facet normal -0.478594 -0.377589 0.792701 + outer loop + vertex 0.962604 0.93682 2.56022 + vertex 0.958498 0.93795 2.55828 + vertex 0.963852 0.932947 2.55913 + endloop + endfacet + facet normal -0.458645 -0.352318 0.815792 + outer loop + vertex 0.963852 0.932947 2.55913 + vertex 0.958498 0.93795 2.55828 + vertex 0.960259 0.93271 2.557 + endloop + endfacet + facet normal -0.446422 -0.371273 0.814165 + outer loop + vertex 0.962604 0.93682 2.56022 + vertex 0.96464 0.93838 2.56204 + vertex 0.960925 0.939732 2.56062 + endloop + endfacet + facet normal -0.481783 -0.382612 0.788349 + outer loop + vertex 0.958498 0.93795 2.55828 + vertex 0.960925 0.939732 2.56062 + vertex 0.958349 0.941951 2.56013 + endloop + endfacet + facet normal -0.46593 -0.359711 0.808404 + outer loop + vertex 0.960925 0.939732 2.56062 + vertex 0.960785 0.943382 2.56217 + vertex 0.958349 0.941951 2.56013 + endloop + endfacet + facet normal -0.445138 -0.363187 0.818503 + outer loop + vertex 0.960925 0.939732 2.56062 + vertex 0.96464 0.93838 2.56204 + vertex 0.960785 0.943382 2.56217 + endloop + endfacet + facet normal -0.449136 -0.366182 0.814977 + outer loop + vertex 0.96464 0.93838 2.56204 + vertex 0.965118 0.942273 2.56406 + vertex 0.960785 0.943382 2.56217 + endloop + endfacet + facet normal -0.448801 -0.359505 0.818128 + outer loop + vertex 0.965118 0.942273 2.56406 + vertex 0.962336 0.947094 2.56465 + vertex 0.960785 0.943382 2.56217 + endloop + endfacet + facet normal -0.455901 -0.355175 0.816091 + outer loop + vertex 0.960785 0.943382 2.56217 + vertex 0.962336 0.947094 2.56465 + vertex 0.957788 0.948429 2.56269 + endloop + endfacet + facet normal -0.462769 -0.346041 0.81615 + outer loop + vertex 0.963036 0.950435 2.56652 + vertex 0.960396 0.954197 2.56662 + vertex 0.958416 0.95242 2.56474 + endloop + endfacet + facet normal -0.465045 -0.356578 0.810299 + outer loop + vertex 0.963036 0.950435 2.56652 + vertex 0.958416 0.95242 2.56474 + vertex 0.962336 0.947094 2.56465 + endloop + endfacet + facet normal -0.45542 -0.349642 0.818745 + outer loop + vertex 0.962336 0.947094 2.56465 + vertex 0.958416 0.95242 2.56474 + vertex 0.957788 0.948429 2.56269 + endloop + endfacet + facet normal -0.476714 -0.355506 0.803965 + outer loop + vertex 0.963036 0.950435 2.56652 + vertex 0.963939 0.953711 2.56851 + vertex 0.960396 0.954197 2.56662 + endloop + endfacet + facet normal -0.463207 -0.345522 0.816121 + outer loop + vertex 0.958416 0.95242 2.56474 + vertex 0.960396 0.954197 2.56662 + vertex 0.957433 0.956334 2.56584 + endloop + endfacet + facet normal -0.463459 -0.345996 0.815777 + outer loop + vertex 0.960396 0.954197 2.56662 + vertex 0.959045 0.958243 2.56757 + vertex 0.957433 0.956334 2.56584 + endloop + endfacet + facet normal -0.477223 -0.348473 0.806737 + outer loop + vertex 0.960396 0.954197 2.56662 + vertex 0.963939 0.953711 2.56851 + vertex 0.959045 0.958243 2.56757 + endloop + endfacet + facet normal -0.475774 -0.346561 0.808415 + outer loop + vertex 0.963939 0.953711 2.56851 + vertex 0.96249 0.958453 2.56969 + vertex 0.959045 0.958243 2.56757 + endloop + endfacet + facet normal -0.48314 -0.339883 0.80688 + outer loop + vertex 0.962091 0.96146 2.57073 + vertex 0.960641 0.964146 2.571 + vertex 0.958892 0.962721 2.56935 + endloop + endfacet + facet normal -0.483889 -0.344373 0.804524 + outer loop + vertex 0.962091 0.96146 2.57073 + vertex 0.958892 0.962721 2.56935 + vertex 0.96249 0.958453 2.56969 + endloop + endfacet + facet normal -0.477646 -0.338623 0.810672 + outer loop + vertex 0.96249 0.958453 2.56969 + vertex 0.958892 0.962721 2.56935 + vertex 0.959045 0.958243 2.56757 + endloop + endfacet + facet normal -0.497988 -0.346723 0.794853 + outer loop + vertex 0.962091 0.96146 2.57073 + vertex 0.963866 0.962812 2.57243 + vertex 0.960641 0.964146 2.571 + endloop + endfacet + facet normal -0.483027 -0.34003 0.806886 + outer loop + vertex 0.958892 0.962721 2.56935 + vertex 0.960641 0.964146 2.571 + vertex 0.958245 0.966315 2.57048 + endloop + endfacet + facet normal -0.49458 -0.356171 0.792801 + outer loop + vertex 0.960641 0.964146 2.571 + vertex 0.960229 0.967235 2.57213 + vertex 0.958245 0.966315 2.57048 + endloop + endfacet + facet normal -0.49951 -0.355763 0.789887 + outer loop + vertex 0.960641 0.964146 2.571 + vertex 0.963866 0.962812 2.57243 + vertex 0.960229 0.967235 2.57213 + endloop + endfacet + facet normal -0.501449 -0.357498 0.787873 + outer loop + vertex 0.963866 0.962812 2.57243 + vertex 0.963741 0.967311 2.5744 + vertex 0.960229 0.967235 2.57213 + endloop + endfacet + facet normal -0.50321 -0.325485 0.800524 + outer loop + vertex 0.962759 0.971248 2.57553 + vertex 0.961109 0.975101 2.57606 + vertex 0.95868 0.972598 2.57351 + endloop + endfacet + facet normal -0.505675 -0.352521 0.787414 + outer loop + vertex 0.962759 0.971248 2.57553 + vertex 0.95868 0.972598 2.57351 + vertex 0.963741 0.967311 2.5744 + endloop + endfacet + facet normal -0.50318 -0.349653 0.790287 + outer loop + vertex 0.963741 0.967311 2.5744 + vertex 0.95868 0.972598 2.57351 + vertex 0.960229 0.967235 2.57213 + endloop + endfacet + facet normal -0.452936 -0.308873 0.836329 + outer loop + vertex 0.962759 0.971248 2.57553 + vertex 0.96512 0.972421 2.57724 + vertex 0.961109 0.975101 2.57606 + endloop + endfacet + facet normal -0.502737 -0.326023 0.800602 + outer loop + vertex 0.95726 0.978041 2.57484 + vertex 0.95868 0.972598 2.57351 + vertex 0.961109 0.975101 2.57606 + endloop + endfacet + facet normal -0.498372 -0.317811 0.806612 + outer loop + vertex 0.959532 0.978911 2.57658 + vertex 0.95726 0.978041 2.57484 + vertex 0.961109 0.975101 2.57606 + endloop + endfacet + facet normal -0.467211 -0.307975 0.828774 + outer loop + vertex 0.961109 0.975101 2.57606 + vertex 0.963668 0.97782 2.57851 + vertex 0.959532 0.978911 2.57658 + endloop + endfacet + facet normal -0.457517 -0.318416 0.830235 + outer loop + vertex 0.96512 0.972421 2.57724 + vertex 0.963668 0.97782 2.57851 + vertex 0.961109 0.975101 2.57606 + endloop + endfacet + facet normal -0.500827 -0.312506 0.807163 + outer loop + vertex 0.95726 0.978041 2.57484 + vertex 0.959532 0.978911 2.57658 + vertex 0.956959 0.981228 2.57589 + endloop + endfacet + facet normal -0.504745 -0.318279 0.802453 + outer loop + vertex 0.959532 0.978911 2.57658 + vertex 0.958821 0.982719 2.57765 + vertex 0.956959 0.981228 2.57589 + endloop + endfacet + facet normal -0.467879 -0.317611 0.82475 + outer loop + vertex 0.959532 0.978911 2.57658 + vertex 0.963668 0.97782 2.57851 + vertex 0.958821 0.982719 2.57765 + endloop + endfacet + facet normal -0.48296 -0.335328 0.808891 + outer loop + vertex 0.963668 0.97782 2.57851 + vertex 0.962369 0.983044 2.5799 + vertex 0.958821 0.982719 2.57765 + endloop + endfacet + facet normal -0.476568 -0.325321 0.816731 + outer loop + vertex 0.962166 0.986237 2.58105 + vertex 0.960635 0.988962 2.58125 + vertex 0.958667 0.987324 2.57945 + endloop + endfacet + facet normal -0.476576 -0.325407 0.816692 + outer loop + vertex 0.962166 0.986237 2.58105 + vertex 0.958667 0.987324 2.57945 + vertex 0.962369 0.983044 2.5799 + endloop + endfacet + facet normal -0.483728 -0.332337 0.809666 + outer loop + vertex 0.962369 0.983044 2.5799 + vertex 0.958667 0.987324 2.57945 + vertex 0.958821 0.982719 2.57765 + endloop + endfacet + facet normal -0.393228 -0.282623 0.874926 + outer loop + vertex 0.962166 0.986237 2.58105 + vertex 0.964492 0.988357 2.58278 + vertex 0.960635 0.988962 2.58125 + endloop + endfacet + facet normal -0.477646 -0.323937 0.816651 + outer loop + vertex 0.958667 0.987324 2.57945 + vertex 0.960635 0.988962 2.58125 + vertex 0.95786 0.991139 2.58049 + endloop + endfacet + facet normal -0.469733 -0.310446 0.826423 + outer loop + vertex 0.960635 0.988962 2.58125 + vertex 0.960074 0.992309 2.58219 + vertex 0.95786 0.991139 2.58049 + endloop + endfacet + facet normal -0.393702 -0.308754 0.865835 + outer loop + vertex 0.960635 0.988962 2.58125 + vertex 0.964492 0.988357 2.58278 + vertex 0.960074 0.992309 2.58219 + endloop + endfacet + facet normal -0.398499 -0.31478 0.861459 + outer loop + vertex 0.964492 0.988357 2.58278 + vertex 0.963271 0.99348 2.58409 + vertex 0.960074 0.992309 2.58219 + endloop + endfacet + facet normal -0.416953 -0.349836 0.838907 + outer loop + vertex 0.962646 0.997133 2.58518 + vertex 0.960852 0.999936 2.58546 + vertex 0.958106 0.997827 2.58322 + endloop + endfacet + facet normal -0.417368 -0.324935 0.848659 + outer loop + vertex 0.962646 0.997133 2.58518 + vertex 0.958106 0.997827 2.58322 + vertex 0.963271 0.99348 2.58409 + endloop + endfacet + facet normal -0.402967 -0.304953 0.862914 + outer loop + vertex 0.963271 0.99348 2.58409 + vertex 0.958106 0.997827 2.58322 + vertex 0.960074 0.992309 2.58219 + endloop + endfacet + facet normal -0.302008 -0.283301 0.910237 + outer loop + vertex 0.962646 0.997133 2.58518 + vertex 0.964935 1.00009 2.58686 + vertex 0.960852 0.999936 2.58546 + endloop + endfacet + facet normal -0.428665 -0.334824 0.83913 + outer loop + vertex 0.958106 0.997827 2.58322 + vertex 0.960852 0.999936 2.58546 + vertex 0.958065 1.00203 2.58487 + endloop + endfacet + facet normal -0.402347 -0.29173 0.867762 + outer loop + vertex 0.960852 0.999936 2.58546 + vertex 0.960938 1.00374 2.58678 + vertex 0.958065 1.00203 2.58487 + endloop + endfacet + facet normal -0.298902 -0.306539 0.90371 + outer loop + vertex 0.960852 0.999936 2.58546 + vertex 0.964935 1.00009 2.58686 + vertex 0.960938 1.00374 2.58678 + endloop + endfacet + facet normal -0.288608 -0.295107 0.910833 + outer loop + vertex 0.964935 1.00009 2.58686 + vertex 0.964891 1.00413 2.58816 + vertex 0.960938 1.00374 2.58678 + endloop + endfacet + facet normal -0.284753 -0.315001 0.905367 + outer loop + vertex 0.964891 1.00413 2.58816 + vertex 0.96288 1.00684 2.58847 + vertex 0.960938 1.00374 2.58678 + endloop + endfacet + facet normal -0.326987 -0.286021 0.900706 + outer loop + vertex 0.960938 1.00374 2.58678 + vertex 0.96288 1.00684 2.58847 + vertex 0.958789 1.00872 2.58758 + endloop + endfacet + facet normal -0.32454 -0.279262 0.903707 + outer loop + vertex 0.96288 1.00684 2.58847 + vertex 0.962926 1.01086 2.58973 + vertex 0.958789 1.00872 2.58758 + endloop + endfacet + facet normal -0.30837 -0.307114 0.900327 + outer loop + vertex 0.958789 1.00872 2.58758 + vertex 0.962926 1.01086 2.58973 + vertex 0.958295 1.01346 2.58903 + endloop + endfacet + facet normal -0.309882 -0.310227 0.898739 + outer loop + vertex 0.958295 1.01346 2.58903 + vertex 0.962926 1.01086 2.58973 + vertex 0.961659 1.01526 2.59081 + endloop + endfacet + facet normal -0.308598 -0.312342 0.898448 + outer loop + vertex 0.958061 1.01709 2.59021 + vertex 0.958295 1.01346 2.58903 + vertex 0.961659 1.01526 2.59081 + endloop + endfacet + facet normal -0.29496 -0.280634 0.913369 + outer loop + vertex 0.961659 1.01526 2.59081 + vertex 0.960623 1.01951 2.59178 + vertex 0.958061 1.01709 2.59021 + endloop + endfacet + facet normal -0.180057 -0.260624 0.948501 + outer loop + vertex 0.96557 1.01822 2.59237 + vertex 0.960623 1.01951 2.59178 + vertex 0.961659 1.01526 2.59081 + endloop + endfacet + facet normal -0.181107 -0.265355 0.946988 + outer loop + vertex 0.96557 1.01822 2.59237 + vertex 0.963873 1.02303 2.59339 + vertex 0.960623 1.01951 2.59178 + endloop + endfacet + facet normal -0.20068 -0.247689 0.947828 + outer loop + vertex 0.960623 1.01951 2.59178 + vertex 0.963873 1.02303 2.59339 + vertex 0.958716 1.02431 2.59263 + endloop + endfacet + facet normal -0.206425 -0.276369 0.938621 + outer loop + vertex 0.963873 1.02303 2.59339 + vertex 0.962159 1.02782 2.59442 + vertex 0.958716 1.02431 2.59263 + endloop + endfacet + facet normal -0.201653 -0.280893 0.938315 + outer loop + vertex 0.958716 1.02431 2.59263 + vertex 0.962159 1.02782 2.59442 + vertex 0.958364 1.02788 2.59362 + endloop + endfacet + facet normal -0.206838 -0.29532 0.93274 + outer loop + vertex 0.962257 1.03177 2.59557 + vertex 0.960322 1.03453 2.59601 + vertex 0.957734 1.03172 2.59455 + endloop + endfacet + facet normal -0.208954 -0.267141 0.94073 + outer loop + vertex 0.962257 1.03177 2.59557 + vertex 0.957734 1.03172 2.59455 + vertex 0.962159 1.02782 2.59442 + endloop + endfacet + facet normal -0.202563 -0.259996 0.944124 + outer loop + vertex 0.962159 1.02782 2.59442 + vertex 0.957734 1.03172 2.59455 + vertex 0.958364 1.02788 2.59362 + endloop + endfacet + facet normal -0.111555 -0.233946 0.965829 + outer loop + vertex 0.962257 1.03177 2.59557 + vertex 0.9647 1.03533 2.59671 + vertex 0.960322 1.03453 2.59601 + endloop + endfacet + facet normal -0.225007 -0.27903 0.933549 + outer loop + vertex 0.957734 1.03172 2.59455 + vertex 0.960322 1.03453 2.59601 + vertex 0.95719 1.03605 2.59571 + endloop + endfacet + facet normal -0.206775 -0.238348 0.948912 + outer loop + vertex 0.960322 1.03453 2.59601 + vertex 0.960038 1.03928 2.59714 + vertex 0.95719 1.03605 2.59571 + endloop + endfacet + facet normal -0.111 -0.236495 0.965272 + outer loop + vertex 0.960322 1.03453 2.59601 + vertex 0.9647 1.03533 2.59671 + vertex 0.960038 1.03928 2.59714 + endloop + endfacet + facet normal -0.102261 -0.226527 0.968622 + outer loop + vertex 0.9647 1.03533 2.59671 + vertex 0.965155 1.03976 2.59779 + vertex 0.960038 1.03928 2.59714 + endloop + endfacet + facet normal -0.100252 -0.242788 0.964885 + outer loop + vertex 0.965155 1.03976 2.59779 + vertex 0.96379 1.04344 2.59858 + vertex 0.960038 1.03928 2.59714 + endloop + endfacet + facet normal -0.0179503 0.206887 0.9782 + outer loop + vertex 0.962633 1.95611 2.60229 + vertex 0.961908 1.96008 2.60143 + vertex 0.957808 1.95625 2.60217 + endloop + endfacet + facet normal -0.15963 0.24622 0.955978 + outer loop + vertex 0.958129 1.99164 2.59337 + vertex 0.962823 1.99661 2.59287 + vertex 0.957669 1.99634 2.59208 + endloop + endfacet + facet normal -0.25166 0.259545 0.932364 + outer loop + vertex 0.95823 2.0116 2.58738 + vertex 0.963015 2.01613 2.58741 + vertex 0.959328 2.01629 2.58637 + endloop + endfacet + facet normal -0.373934 0.366529 0.851957 + outer loop + vertex 0.961843 2.02204 2.58532 + vertex 0.958189 2.02121 2.58408 + vertex 0.959751 2.01931 2.58558 + endloop + endfacet + facet normal -0.275499 0.297137 0.914227 + outer loop + vertex 0.959751 2.01931 2.58558 + vertex 0.962699 2.01969 2.58635 + vertex 0.961843 2.02204 2.58532 + endloop + endfacet + facet normal -0.27467 0.277854 0.920518 + outer loop + vertex 0.959751 2.01931 2.58558 + vertex 0.959328 2.01629 2.58637 + vertex 0.962699 2.01969 2.58635 + endloop + endfacet + facet normal -0.252114 0.255534 0.933349 + outer loop + vertex 0.959328 2.01629 2.58637 + vertex 0.963015 2.01613 2.58741 + vertex 0.962699 2.01969 2.58635 + endloop + endfacet + facet normal -0.236905 0.326684 0.914961 + outer loop + vertex 0.961843 2.02204 2.58532 + vertex 0.965623 2.02357 2.58576 + vertex 0.963389 2.02632 2.5842 + endloop + endfacet + facet normal -0.373478 0.360251 0.854829 + outer loop + vertex 0.961843 2.02204 2.58532 + vertex 0.963389 2.02632 2.5842 + vertex 0.958189 2.02121 2.58408 + endloop + endfacet + facet normal -0.342122 0.327743 0.880646 + outer loop + vertex 0.958189 2.02121 2.58408 + vertex 0.963389 2.02632 2.5842 + vertex 0.958346 2.02606 2.58233 + endloop + endfacet + facet normal -0.232819 0.315149 0.920041 + outer loop + vertex 0.965623 2.02357 2.58576 + vertex 0.961843 2.02204 2.58532 + vertex 0.962699 2.01969 2.58635 + endloop + endfacet + facet normal -0.456649 0.335341 0.824025 + outer loop + vertex 0.960538 2.03356 2.58066 + vertex 0.956659 2.03067 2.57968 + vertex 0.95892 2.02984 2.58127 + endloop + endfacet + facet normal -0.357018 0.301932 0.883954 + outer loop + vertex 0.95892 2.02984 2.58127 + vertex 0.963068 2.03144 2.5824 + vertex 0.960538 2.03356 2.58066 + endloop + endfacet + facet normal -0.357165 0.302484 0.883706 + outer loop + vertex 0.95892 2.02984 2.58127 + vertex 0.958346 2.02606 2.58233 + vertex 0.963068 2.03144 2.5824 + endloop + endfacet + facet normal -0.344611 0.291352 0.892389 + outer loop + vertex 0.958346 2.02606 2.58233 + vertex 0.963389 2.02632 2.5842 + vertex 0.963068 2.03144 2.5824 + endloop + endfacet + facet normal -0.460985 0.343079 0.818407 + outer loop + vertex 0.958089 2.03601 2.57825 + vertex 0.956659 2.03067 2.57968 + vertex 0.960538 2.03356 2.58066 + endloop + endfacet + facet normal -0.470592 0.332441 0.817328 + outer loop + vertex 0.962218 2.03719 2.58015 + vertex 0.958089 2.03601 2.57825 + vertex 0.960538 2.03356 2.58066 + endloop + endfacet + facet normal -0.380362 0.298916 0.875199 + outer loop + vertex 0.960538 2.03356 2.58066 + vertex 0.964391 2.03621 2.58142 + vertex 0.962218 2.03719 2.58015 + endloop + endfacet + facet normal -0.371826 0.284073 0.883769 + outer loop + vertex 0.963068 2.03144 2.5824 + vertex 0.964391 2.03621 2.58142 + vertex 0.960538 2.03356 2.58066 + endloop + endfacet + facet normal -0.415499 0.349725 0.839675 + outer loop + vertex 0.962218 2.03719 2.58015 + vertex 0.964888 2.0392 2.58063 + vertex 0.963247 2.04108 2.57903 + endloop + endfacet + facet normal -0.472243 0.355299 0.806691 + outer loop + vertex 0.962218 2.03719 2.58015 + vertex 0.963247 2.04108 2.57903 + vertex 0.958089 2.03601 2.57825 + endloop + endfacet + facet normal -0.455458 0.335458 0.824637 + outer loop + vertex 0.958089 2.03601 2.57825 + vertex 0.963247 2.04108 2.57903 + vertex 0.959169 2.04162 2.57656 + endloop + endfacet + facet normal -0.381759 0.296218 0.875508 + outer loop + vertex 0.964888 2.0392 2.58063 + vertex 0.962218 2.03719 2.58015 + vertex 0.964391 2.03621 2.58142 + endloop + endfacet + facet normal -0.506143 0.315161 0.802803 + outer loop + vertex 0.961448 2.04796 2.5755 + vertex 0.959559 2.0486 2.57406 + vertex 0.959194 2.04566 2.57498 + endloop + endfacet + facet normal -0.466225 0.266913 0.843441 + outer loop + vertex 0.959194 2.04566 2.57498 + vertex 0.96322 2.04601 2.57709 + vertex 0.961448 2.04796 2.5755 + endloop + endfacet + facet normal -0.461668 0.326246 0.82488 + outer loop + vertex 0.959194 2.04566 2.57498 + vertex 0.959169 2.04162 2.57656 + vertex 0.96322 2.04601 2.57709 + endloop + endfacet + facet normal -0.458855 0.323322 0.827596 + outer loop + vertex 0.959169 2.04162 2.57656 + vertex 0.963247 2.04108 2.57903 + vertex 0.96322 2.04601 2.57709 + endloop + endfacet + facet normal -0.461646 0.328471 0.824008 + outer loop + vertex 0.961448 2.04796 2.5755 + vertex 0.963842 2.04964 2.57617 + vertex 0.962026 2.05096 2.57462 + endloop + endfacet + facet normal -0.500044 0.32918 0.800997 + outer loop + vertex 0.961448 2.04796 2.5755 + vertex 0.962026 2.05096 2.57462 + vertex 0.959559 2.0486 2.57406 + endloop + endfacet + facet normal -0.512831 0.346236 0.785573 + outer loop + vertex 0.959559 2.0486 2.57406 + vertex 0.962026 2.05096 2.57462 + vertex 0.959478 2.05155 2.5727 + endloop + endfacet + facet normal -0.442686 0.291927 0.847825 + outer loop + vertex 0.963842 2.04964 2.57617 + vertex 0.961448 2.04796 2.5755 + vertex 0.96322 2.04601 2.57709 + endloop + endfacet + facet normal -0.496702 0.347206 0.795446 + outer loop + vertex 0.960313 2.05826 2.57024 + vertex 0.956734 2.05517 2.56936 + vertex 0.959339 2.05461 2.57123 + endloop + endfacet + facet normal -0.505986 0.348 0.789224 + outer loop + vertex 0.959339 2.05461 2.57123 + vertex 0.963216 2.05589 2.57315 + vertex 0.960313 2.05826 2.57024 + endloop + endfacet + facet normal -0.506578 0.355075 0.785684 + outer loop + vertex 0.959339 2.05461 2.57123 + vertex 0.959478 2.05155 2.5727 + vertex 0.963216 2.05589 2.57315 + endloop + endfacet + facet normal -0.508675 0.357116 0.783401 + outer loop + vertex 0.959478 2.05155 2.5727 + vertex 0.962026 2.05096 2.57462 + vertex 0.963216 2.05589 2.57315 + endloop + endfacet + facet normal -0.499482 0.35145 0.791834 + outer loop + vertex 0.957258 2.05959 2.56773 + vertex 0.956734 2.05517 2.56936 + vertex 0.960313 2.05826 2.57024 + endloop + endfacet + facet normal -0.502805 0.345092 0.792527 + outer loop + vertex 0.960984 2.06259 2.56879 + vertex 0.957258 2.05959 2.56773 + vertex 0.960313 2.05826 2.57024 + endloop + endfacet + facet normal -0.50128 0.34517 0.793459 + outer loop + vertex 0.960313 2.05826 2.57024 + vertex 0.964193 2.06143 2.57132 + vertex 0.960984 2.06259 2.56879 + endloop + endfacet + facet normal -0.504272 0.350233 0.789333 + outer loop + vertex 0.963216 2.05589 2.57315 + vertex 0.964193 2.06143 2.57132 + vertex 0.960313 2.05826 2.57024 + endloop + endfacet + facet normal -0.480566 0.316629 0.817803 + outer loop + vertex 0.961265 2.06732 2.56695 + vertex 0.956614 2.06508 2.56508 + vertex 0.958518 2.06341 2.56685 + endloop + endfacet + facet normal -0.504654 0.348298 0.789945 + outer loop + vertex 0.958518 2.06341 2.56685 + vertex 0.957258 2.05959 2.56773 + vertex 0.960984 2.06259 2.56879 + endloop + endfacet + facet normal -0.509447 0.337634 0.791497 + outer loop + vertex 0.961265 2.06732 2.56695 + vertex 0.958518 2.06341 2.56685 + vertex 0.960984 2.06259 2.56879 + endloop + endfacet + facet normal -0.512068 0.337204 0.789987 + outer loop + vertex 0.961265 2.06732 2.56695 + vertex 0.960984 2.06259 2.56879 + vertex 0.96428 2.06545 2.5697 + endloop + endfacet + facet normal -0.511566 0.337995 0.789975 + outer loop + vertex 0.961265 2.06732 2.56695 + vertex 0.96428 2.06545 2.5697 + vertex 0.964892 2.06854 2.56878 + endloop + endfacet + facet normal -0.507958 0.330752 0.79535 + outer loop + vertex 0.96428 2.06545 2.5697 + vertex 0.960984 2.06259 2.56879 + vertex 0.964193 2.06143 2.57132 + endloop + endfacet + facet normal -0.486933 0.341432 0.803941 + outer loop + vertex 0.958016 2.0706 2.56359 + vertex 0.956614 2.06508 2.56508 + vertex 0.961265 2.06732 2.56695 + endloop + endfacet + facet normal -0.476831 0.35267 0.805144 + outer loop + vertex 0.962328 2.07185 2.56559 + vertex 0.958016 2.0706 2.56359 + vertex 0.961265 2.06732 2.56695 + endloop + endfacet + facet normal -0.502299 0.353803 0.788999 + outer loop + vertex 0.961265 2.06732 2.56695 + vertex 0.964849 2.07147 2.56737 + vertex 0.962328 2.07185 2.56559 + endloop + endfacet + facet normal -0.513841 0.365025 0.776353 + outer loop + vertex 0.964892 2.06854 2.56878 + vertex 0.964849 2.07147 2.56737 + vertex 0.961265 2.06732 2.56695 + endloop + endfacet + facet normal -0.490874 0.356762 0.794836 + outer loop + vertex 0.962328 2.07185 2.56559 + vertex 0.964889 2.0744 2.56603 + vertex 0.962925 2.07585 2.56417 + endloop + endfacet + facet normal -0.477163 0.357551 0.80279 + outer loop + vertex 0.962328 2.07185 2.56559 + vertex 0.962925 2.07585 2.56417 + vertex 0.958016 2.0706 2.56359 + endloop + endfacet + facet normal -0.476686 0.35705 0.803297 + outer loop + vertex 0.958016 2.0706 2.56359 + vertex 0.962925 2.07585 2.56417 + vertex 0.959054 2.07631 2.56167 + endloop + endfacet + facet normal -0.498362 0.365849 0.785996 + outer loop + vertex 0.964889 2.0744 2.56603 + vertex 0.962328 2.07185 2.56559 + vertex 0.964849 2.07147 2.56737 + endloop + endfacet + facet normal -0.473594 0.354519 0.806241 + outer loop + vertex 0.961959 2.08298 2.5604 + vertex 0.959864 2.08366 2.55887 + vertex 0.959278 2.08048 2.55993 + endloop + endfacet + facet normal -0.476634 0.358454 0.802702 + outer loop + vertex 0.959278 2.08048 2.55993 + vertex 0.96314 2.08062 2.56216 + vertex 0.961959 2.08298 2.5604 + endloop + endfacet + facet normal -0.476375 0.36001 0.802159 + outer loop + vertex 0.959278 2.08048 2.55993 + vertex 0.959054 2.07631 2.56167 + vertex 0.96314 2.08062 2.56216 + endloop + endfacet + facet normal -0.47595 0.359554 0.802616 + outer loop + vertex 0.959054 2.07631 2.56167 + vertex 0.962925 2.07585 2.56417 + vertex 0.96314 2.08062 2.56216 + endloop + endfacet + facet normal -0.47137 0.351002 0.809078 + outer loop + vertex 0.961959 2.08298 2.5604 + vertex 0.964385 2.08424 2.56127 + vertex 0.963005 2.08638 2.55954 + endloop + endfacet + facet normal -0.474954 0.35151 0.806758 + outer loop + vertex 0.961959 2.08298 2.5604 + vertex 0.963005 2.08638 2.55954 + vertex 0.959864 2.08366 2.55887 + endloop + endfacet + facet normal -0.480492 0.359569 0.799899 + outer loop + vertex 0.959864 2.08366 2.55887 + vertex 0.963005 2.08638 2.55954 + vertex 0.959327 2.08676 2.55716 + endloop + endfacet + facet normal -0.474134 0.360217 0.803394 + outer loop + vertex 0.964385 2.08424 2.56127 + vertex 0.961959 2.08298 2.5604 + vertex 0.96314 2.08062 2.56216 + endloop + endfacet + facet normal -0.523205 0.356426 0.774091 + outer loop + vertex 0.961476 2.09323 2.55566 + vertex 0.959482 2.09385 2.55402 + vertex 0.959009 2.09063 2.55519 + endloop + endfacet + facet normal -0.502926 0.332925 0.797638 + outer loop + vertex 0.959009 2.09063 2.55519 + vertex 0.962842 2.0908 2.55753 + vertex 0.961476 2.09323 2.55566 + endloop + endfacet + facet normal -0.49844 0.360647 0.788347 + outer loop + vertex 0.959009 2.09063 2.55519 + vertex 0.959327 2.08676 2.55716 + vertex 0.962842 2.0908 2.55753 + endloop + endfacet + facet normal -0.484058 0.346738 0.803406 + outer loop + vertex 0.959327 2.08676 2.55716 + vertex 0.963005 2.08638 2.55954 + vertex 0.962842 2.0908 2.55753 + endloop + endfacet + facet normal -0.479976 0.373693 0.793711 + outer loop + vertex 0.961476 2.09323 2.55566 + vertex 0.963874 2.09446 2.55653 + vertex 0.962583 2.09662 2.55473 + endloop + endfacet + facet normal -0.513395 0.378197 0.77032 + outer loop + vertex 0.961476 2.09323 2.55566 + vertex 0.962583 2.09662 2.55473 + vertex 0.959482 2.09385 2.55402 + endloop + endfacet + facet normal -0.51871 0.386034 0.762835 + outer loop + vertex 0.959482 2.09385 2.55402 + vertex 0.962583 2.09662 2.55473 + vertex 0.959134 2.09684 2.55227 + endloop + endfacet + facet normal -0.474627 0.354853 0.805486 + outer loop + vertex 0.963874 2.09446 2.55653 + vertex 0.961476 2.09323 2.55566 + vertex 0.962842 2.0908 2.55753 + endloop + endfacet + facet normal -0.568373 0.354545 0.742462 + outer loop + vertex 0.961136 2.10295 2.55086 + vertex 0.959247 2.10348 2.54916 + vertex 0.958928 2.10051 2.55033 + endloop + endfacet + facet normal -0.53566 0.316218 0.782991 + outer loop + vertex 0.958928 2.10051 2.55033 + vertex 0.96271 2.10096 2.55274 + vertex 0.961136 2.10295 2.55086 + endloop + endfacet + facet normal -0.529162 0.372841 0.762218 + outer loop + vertex 0.958928 2.10051 2.55033 + vertex 0.959134 2.09684 2.55227 + vertex 0.96271 2.10096 2.55274 + endloop + endfacet + facet normal -0.523878 0.367543 0.768417 + outer loop + vertex 0.959134 2.09684 2.55227 + vertex 0.962583 2.09662 2.55473 + vertex 0.96271 2.10096 2.55274 + endloop + endfacet + facet normal -0.501656 0.38339 0.77547 + outer loop + vertex 0.961136 2.10295 2.55086 + vertex 0.963617 2.10462 2.55164 + vertex 0.961634 2.10584 2.54976 + endloop + endfacet + facet normal -0.557854 0.378908 0.738395 + outer loop + vertex 0.961136 2.10295 2.55086 + vertex 0.961634 2.10584 2.54976 + vertex 0.959247 2.10348 2.54916 + endloop + endfacet + facet normal -0.565264 0.389238 0.727303 + outer loop + vertex 0.959247 2.10348 2.54916 + vertex 0.961634 2.10584 2.54976 + vertex 0.958974 2.10646 2.54736 + endloop + endfacet + facet normal -0.491614 0.360284 0.792787 + outer loop + vertex 0.963617 2.10462 2.55164 + vertex 0.961136 2.10295 2.55086 + vertex 0.96271 2.10096 2.55274 + endloop + endfacet + facet normal -0.591005 0.389912 0.706174 + outer loop + vertex 0.961223 2.1125 2.546 + vertex 0.959497 2.11337 2.54407 + vertex 0.958981 2.1103 2.54534 + endloop + endfacet + facet normal -0.574309 0.364896 0.732816 + outer loop + vertex 0.958981 2.1103 2.54534 + vertex 0.962157 2.10987 2.54804 + vertex 0.961223 2.1125 2.546 + endloop + endfacet + facet normal -0.56781 0.383802 0.728209 + outer loop + vertex 0.958981 2.1103 2.54534 + vertex 0.958974 2.10646 2.54736 + vertex 0.962157 2.10987 2.54804 + endloop + endfacet + facet normal -0.567629 0.383581 0.728466 + outer loop + vertex 0.958974 2.10646 2.54736 + vertex 0.961634 2.10584 2.54976 + vertex 0.962157 2.10987 2.54804 + endloop + endfacet + facet normal -0.542875 0.429071 0.721931 + outer loop + vertex 0.961223 2.1125 2.546 + vertex 0.963492 2.11344 2.54715 + vertex 0.962027 2.11531 2.54493 + endloop + endfacet + facet normal -0.567562 0.4289 0.702793 + outer loop + vertex 0.961223 2.1125 2.546 + vertex 0.962027 2.11531 2.54493 + vertex 0.959497 2.11337 2.54407 + endloop + endfacet + facet normal -0.57516 0.446587 0.685383 + outer loop + vertex 0.959497 2.11337 2.54407 + vertex 0.962027 2.11531 2.54493 + vertex 0.95922 2.11616 2.54202 + endloop + endfacet + facet normal -0.539011 0.388653 0.747273 + outer loop + vertex 0.963492 2.11344 2.54715 + vertex 0.961223 2.1125 2.546 + vertex 0.962157 2.10987 2.54804 + endloop + endfacet + facet normal -0.551949 0.545996 0.63027 + outer loop + vertex 0.960935 2.12111 2.53968 + vertex 0.959008 2.1211 2.538 + vertex 0.959046 2.11931 2.53958 + endloop + endfacet + facet normal -0.540901 0.533329 0.650374 + outer loop + vertex 0.959046 2.11931 2.53958 + vertex 0.962578 2.11894 2.54283 + vertex 0.960935 2.12111 2.53968 + endloop + endfacet + facet normal -0.562469 0.486611 0.668459 + outer loop + vertex 0.959046 2.11931 2.53958 + vertex 0.95922 2.11616 2.54202 + vertex 0.962578 2.11894 2.54283 + endloop + endfacet + facet normal -0.557969 0.47839 0.678096 + outer loop + vertex 0.95922 2.11616 2.54202 + vertex 0.962027 2.11531 2.54493 + vertex 0.962578 2.11894 2.54283 + endloop + endfacet + facet normal -0.423608 0.820386 0.384089 + outer loop + vertex 0.96011 2.12656 2.53045 + vertex 0.957273 2.1261 2.52832 + vertex 0.958677 2.125 2.53221 + endloop + endfacet + facet normal -0.445856 0.817861 0.363753 + outer loop + vertex 0.962153 2.12634 2.53346 + vertex 0.96011 2.12656 2.53045 + vertex 0.958677 2.125 2.53221 + endloop + endfacet + facet normal -0.45606 0.774029 0.439191 + outer loop + vertex 0.962153 2.12634 2.53346 + vertex 0.958677 2.125 2.53221 + vertex 0.963637 2.12515 2.5371 + endloop + endfacet + facet normal -0.49672 0.721739 0.482039 + outer loop + vertex 0.963637 2.12515 2.5371 + vertex 0.958677 2.125 2.53221 + vertex 0.95966 2.12271 2.53665 + endloop + endfacet + facet normal -0.491804 0.666643 0.560104 + outer loop + vertex 0.960935 2.12111 2.53968 + vertex 0.95966 2.12271 2.53665 + vertex 0.959008 2.1211 2.538 + endloop + endfacet + facet normal -0.498147 0.66182 0.560218 + outer loop + vertex 0.960935 2.12111 2.53968 + vertex 0.964386 2.12239 2.54123 + vertex 0.95966 2.12271 2.53665 + endloop + endfacet + facet normal -0.481992 0.685862 0.545231 + outer loop + vertex 0.964386 2.12239 2.54123 + vertex 0.963637 2.12515 2.5371 + vertex 0.95966 2.12271 2.53665 + endloop + endfacet + facet normal -0.50393 0.565242 0.653112 + outer loop + vertex 0.964386 2.12239 2.54123 + vertex 0.960935 2.12111 2.53968 + vertex 0.962578 2.11894 2.54283 + endloop + endfacet + facet normal -0.165076 0.982652 0.0845272 + outer loop + vertex 0.965 2.1331 2.52 + vertex 0.96 2.13226 2.52 + vertex 0.965 2.13267 2.525 + endloop + endfacet + facet normal -0.597084 0.584752 0.54914 + outer loop + vertex 0.965 2.13267 2.525 + vertex 0.96 2.13226 2.52 + vertex 0.959539 2.12967 2.52226 + endloop + endfacet + facet normal -0.597018 0.604327 0.527596 + outer loop + vertex 0.965 2.13267 2.525 + vertex 0.959539 2.12967 2.52226 + vertex 0.964041 2.13 2.52698 + endloop + endfacet + facet normal -0.446582 0.814834 0.369607 + outer loop + vertex 0.964041 2.13 2.52698 + vertex 0.959539 2.12967 2.52226 + vertex 0.959105 2.12756 2.52639 + endloop + endfacet + facet normal -0.374212 0.875245 0.306449 + outer loop + vertex 0.96011 2.12656 2.53045 + vertex 0.959105 2.12756 2.52639 + vertex 0.957273 2.1261 2.52832 + endloop + endfacet + facet normal -0.409106 0.857904 0.310858 + outer loop + vertex 0.96011 2.12656 2.53045 + vertex 0.963577 2.12789 2.53137 + vertex 0.959105 2.12756 2.52639 + endloop + endfacet + facet normal -0.448224 0.823258 0.348341 + outer loop + vertex 0.963577 2.12789 2.53137 + vertex 0.964041 2.13 2.52698 + vertex 0.959105 2.12756 2.52639 + endloop + endfacet + facet normal -0.412278 0.844054 0.342929 + outer loop + vertex 0.963577 2.12789 2.53137 + vertex 0.96011 2.12656 2.53045 + vertex 0.962153 2.12634 2.53346 + endloop + endfacet + facet normal -0.298341 -0.930577 0.212177 + outer loop + vertex 0.97 0.892169 2.525 + vertex 0.97 0.893309 2.53 + vertex 0.965 0.893772 2.525 + endloop + endfacet + facet normal 0.0734707 -0.983627 -0.164561 + outer loop + vertex 0.97 0.893309 2.53 + vertex 0.9648 0.893614 2.52585 + vertex 0.965 0.893772 2.525 + endloop + endfacet + facet normal -0.0916439 -0.99492 0.0416579 + outer loop + vertex 0.97 0.893309 2.53 + vertex 0.966274 0.893602 2.5288 + vertex 0.9648 0.893614 2.52585 + endloop + endfacet + facet normal 0.194692 -0.626159 -0.754997 + outer loop + vertex 0.970579 0.892044 2.5312 + vertex 0.966274 0.893602 2.5288 + vertex 0.97 0.893309 2.53 + endloop + endfacet + facet normal -0.441111 -0.868087 0.227696 + outer loop + vertex 0.966274 0.893602 2.5288 + vertex 0.970579 0.892044 2.5312 + vertex 0.967658 0.893705 2.53187 + endloop + endfacet + facet normal -0.40695 -0.888267 0.213011 + outer loop + vertex 0.96322 0.895427 2.53057 + vertex 0.966274 0.893602 2.5288 + vertex 0.967658 0.893705 2.53187 + endloop + endfacet + facet normal -0.423419 -0.844957 0.326747 + outer loop + vertex 0.967658 0.893705 2.53187 + vertex 0.968073 0.89499 2.53573 + vertex 0.96322 0.895427 2.53057 + endloop + endfacet + facet normal -0.442151 -0.827583 0.345846 + outer loop + vertex 0.968073 0.89499 2.53573 + vertex 0.962681 0.897573 2.53502 + vertex 0.96322 0.895427 2.53057 + endloop + endfacet + facet normal -0.485347 -0.740374 0.465064 + outer loop + vertex 0.962698 0.899665 2.53833 + vertex 0.9675 0.89746 2.53983 + vertex 0.965624 0.899255 2.54073 + endloop + endfacet + facet normal -0.485417 -0.737795 0.469073 + outer loop + vertex 0.962698 0.899665 2.53833 + vertex 0.962681 0.897573 2.53502 + vertex 0.9675 0.89746 2.53983 + endloop + endfacet + facet normal -0.436739 -0.796078 0.418949 + outer loop + vertex 0.962681 0.897573 2.53502 + vertex 0.968073 0.89499 2.53573 + vertex 0.9675 0.89746 2.53983 + endloop + endfacet + facet normal -0.439733 -0.725182 0.529855 + outer loop + vertex 0.9675 0.89746 2.53983 + vertex 0.96741 0.899866 2.54305 + vertex 0.965624 0.899255 2.54073 + endloop + endfacet + facet normal -0.535023 -0.648701 0.541237 + outer loop + vertex 0.962698 0.899665 2.53833 + vertex 0.965624 0.899255 2.54073 + vertex 0.963424 0.901293 2.541 + endloop + endfacet + facet normal -0.548802 -0.539943 0.638184 + outer loop + vertex 0.967545 0.901947 2.54531 + vertex 0.965873 0.904375 2.54593 + vertex 0.963419 0.903849 2.54337 + endloop + endfacet + facet normal -0.549744 -0.598478 0.582757 + outer loop + vertex 0.96741 0.899866 2.54305 + vertex 0.967545 0.901947 2.54531 + vertex 0.963419 0.903849 2.54337 + endloop + endfacet + facet normal -0.527216 -0.5791 0.621841 + outer loop + vertex 0.96741 0.899866 2.54305 + vertex 0.963419 0.903849 2.54337 + vertex 0.963424 0.901293 2.541 + endloop + endfacet + facet normal -0.520585 -0.636732 0.568826 + outer loop + vertex 0.96741 0.899866 2.54305 + vertex 0.963424 0.901293 2.541 + vertex 0.965624 0.899255 2.54073 + endloop + endfacet + facet normal -0.485074 -0.513716 0.707672 + outer loop + vertex 0.967545 0.901947 2.54531 + vertex 0.969481 0.903028 2.54742 + vertex 0.965873 0.904375 2.54593 + endloop + endfacet + facet normal -0.564509 -0.511934 0.647498 + outer loop + vertex 0.963419 0.903849 2.54337 + vertex 0.965873 0.904375 2.54593 + vertex 0.963029 0.906741 2.54532 + endloop + endfacet + facet normal -0.530975 -0.454135 0.715421 + outer loop + vertex 0.965873 0.904375 2.54593 + vertex 0.965237 0.907283 2.5473 + vertex 0.963029 0.906741 2.54532 + endloop + endfacet + facet normal -0.480872 -0.458317 0.747468 + outer loop + vertex 0.965873 0.904375 2.54593 + vertex 0.969481 0.903028 2.54742 + vertex 0.965237 0.907283 2.5473 + endloop + endfacet + facet normal -0.475878 -0.453157 0.753783 + outer loop + vertex 0.969481 0.903028 2.54742 + vertex 0.968715 0.907395 2.54956 + vertex 0.965237 0.907283 2.5473 + endloop + endfacet + facet normal -0.500772 -0.424618 0.754273 + outer loop + vertex 0.96703 0.911383 2.5507 + vertex 0.964958 0.914425 2.55104 + vertex 0.96298 0.912606 2.5487 + endloop + endfacet + facet normal -0.500804 -0.426482 0.753199 + outer loop + vertex 0.96703 0.911383 2.5507 + vertex 0.96298 0.912606 2.5487 + vertex 0.968715 0.907395 2.54956 + endloop + endfacet + facet normal -0.488199 -0.409736 0.77057 + outer loop + vertex 0.968715 0.907395 2.54956 + vertex 0.96298 0.912606 2.5487 + vertex 0.965237 0.907283 2.5473 + endloop + endfacet + facet normal -0.449229 -0.39474 0.801482 + outer loop + vertex 0.96703 0.911383 2.5507 + vertex 0.968811 0.913075 2.55253 + vertex 0.964958 0.914425 2.55104 + endloop + endfacet + facet normal -0.500462 -0.424967 0.754282 + outer loop + vertex 0.96298 0.912606 2.5487 + vertex 0.964958 0.914425 2.55104 + vertex 0.962403 0.916503 2.55051 + endloop + endfacet + facet normal -0.474969 -0.384171 0.791718 + outer loop + vertex 0.964958 0.914425 2.55104 + vertex 0.964137 0.918087 2.55232 + vertex 0.962403 0.916503 2.55051 + endloop + endfacet + facet normal -0.447748 -0.38366 0.807668 + outer loop + vertex 0.964958 0.914425 2.55104 + vertex 0.968811 0.913075 2.55253 + vertex 0.964137 0.918087 2.55232 + endloop + endfacet + facet normal -0.441781 -0.377843 0.813673 + outer loop + vertex 0.968811 0.913075 2.55253 + vertex 0.968587 0.917689 2.55455 + vertex 0.964137 0.918087 2.55232 + endloop + endfacet + facet normal -0.453702 -0.40151 0.795578 + outer loop + vertex 0.967386 0.921589 2.55576 + vertex 0.965326 0.92461 2.55611 + vertex 0.963726 0.922736 2.55425 + endloop + endfacet + facet normal -0.452415 -0.387108 0.80341 + outer loop + vertex 0.967386 0.921589 2.55576 + vertex 0.963726 0.922736 2.55425 + vertex 0.968587 0.917689 2.55455 + endloop + endfacet + facet normal -0.441946 -0.376369 0.814266 + outer loop + vertex 0.968587 0.917689 2.55455 + vertex 0.963726 0.922736 2.55425 + vertex 0.964137 0.918087 2.55232 + endloop + endfacet + facet normal -0.433378 -0.389631 0.812632 + outer loop + vertex 0.967386 0.921589 2.55576 + vertex 0.969117 0.923216 2.55746 + vertex 0.965326 0.92461 2.55611 + endloop + endfacet + facet normal -0.464912 -0.390804 0.794437 + outer loop + vertex 0.963726 0.922736 2.55425 + vertex 0.965326 0.92461 2.55611 + vertex 0.962397 0.926672 2.55541 + endloop + endfacet + facet normal -0.460398 -0.382063 0.801288 + outer loop + vertex 0.965326 0.92461 2.55611 + vertex 0.964271 0.928324 2.55727 + vertex 0.962397 0.926672 2.55541 + endloop + endfacet + facet normal -0.43164 -0.379271 0.818437 + outer loop + vertex 0.965326 0.92461 2.55611 + vertex 0.969117 0.923216 2.55746 + vertex 0.964271 0.928324 2.55727 + endloop + endfacet + facet normal -0.431709 -0.379339 0.818369 + outer loop + vertex 0.969117 0.923216 2.55746 + vertex 0.968759 0.92783 2.55941 + vertex 0.964271 0.928324 2.55727 + endloop + endfacet + facet normal -0.438834 -0.37737 0.815486 + outer loop + vertex 0.967496 0.931714 2.56052 + vertex 0.965481 0.934721 2.56082 + vertex 0.963852 0.932947 2.55913 + endloop + endfacet + facet normal -0.438531 -0.375123 0.816684 + outer loop + vertex 0.967496 0.931714 2.56052 + vertex 0.963852 0.932947 2.55913 + vertex 0.968759 0.92783 2.55941 + endloop + endfacet + facet normal -0.432588 -0.369096 0.822579 + outer loop + vertex 0.968759 0.92783 2.55941 + vertex 0.963852 0.932947 2.55913 + vertex 0.964271 0.928324 2.55727 + endloop + endfacet + facet normal -0.450788 -0.384379 0.805632 + outer loop + vertex 0.967496 0.931714 2.56052 + vertex 0.969178 0.933288 2.56221 + vertex 0.965481 0.934721 2.56082 + endloop + endfacet + facet normal -0.44359 -0.372626 0.815094 + outer loop + vertex 0.963852 0.932947 2.55913 + vertex 0.965481 0.934721 2.56082 + vertex 0.962604 0.93682 2.56022 + endloop + endfacet + facet normal -0.444328 -0.373926 0.814096 + outer loop + vertex 0.965481 0.934721 2.56082 + vertex 0.96464 0.93838 2.56204 + vertex 0.962604 0.93682 2.56022 + endloop + endfacet + facet normal -0.448989 -0.374112 0.811449 + outer loop + vertex 0.965481 0.934721 2.56082 + vertex 0.969178 0.933288 2.56221 + vertex 0.96464 0.93838 2.56204 + endloop + endfacet + facet normal -0.454863 -0.379532 0.805639 + outer loop + vertex 0.969178 0.933288 2.56221 + vertex 0.968971 0.937798 2.56422 + vertex 0.96464 0.93838 2.56204 + endloop + endfacet + facet normal -0.460299 -0.367742 0.808016 + outer loop + vertex 0.968103 0.941463 2.56539 + vertex 0.966379 0.94483 2.56594 + vertex 0.965118 0.942273 2.56406 + endloop + endfacet + facet normal -0.460297 -0.367703 0.808036 + outer loop + vertex 0.968103 0.941463 2.56539 + vertex 0.965118 0.942273 2.56406 + vertex 0.968971 0.937798 2.56422 + endloop + endfacet + facet normal -0.456034 -0.363885 0.81217 + outer loop + vertex 0.968971 0.937798 2.56422 + vertex 0.965118 0.942273 2.56406 + vertex 0.96464 0.93838 2.56204 + endloop + endfacet + facet normal -0.464326 -0.369309 0.804992 + outer loop + vertex 0.968103 0.941463 2.56539 + vertex 0.97008 0.942434 2.56697 + vertex 0.966379 0.94483 2.56594 + endloop + endfacet + facet normal -0.462614 -0.366157 0.807414 + outer loop + vertex 0.962336 0.947094 2.56465 + vertex 0.965118 0.942273 2.56406 + vertex 0.966379 0.94483 2.56594 + endloop + endfacet + facet normal -0.461815 -0.363887 0.808896 + outer loop + vertex 0.964945 0.947549 2.56634 + vertex 0.962336 0.947094 2.56465 + vertex 0.966379 0.94483 2.56594 + endloop + endfacet + facet normal -0.470917 -0.36765 0.801917 + outer loop + vertex 0.966379 0.94483 2.56594 + vertex 0.968152 0.947688 2.56829 + vertex 0.964945 0.947549 2.56634 + endloop + endfacet + facet normal -0.46551 -0.371963 0.803084 + outer loop + vertex 0.97008 0.942434 2.56697 + vertex 0.968152 0.947688 2.56829 + vertex 0.966379 0.94483 2.56594 + endloop + endfacet + facet normal -0.464159 -0.356955 0.810641 + outer loop + vertex 0.962336 0.947094 2.56465 + vertex 0.964945 0.947549 2.56634 + vertex 0.963036 0.950435 2.56652 + endloop + endfacet + facet normal -0.480503 -0.354395 0.802198 + outer loop + vertex 0.968015 0.951817 2.57011 + vertex 0.966279 0.955651 2.57076 + vertex 0.963939 0.953711 2.56851 + endloop + endfacet + facet normal -0.483289 -0.366412 0.795094 + outer loop + vertex 0.968152 0.947688 2.56829 + vertex 0.968015 0.951817 2.57011 + vertex 0.963939 0.953711 2.56851 + endloop + endfacet + facet normal -0.471126 -0.358291 0.80602 + outer loop + vertex 0.968152 0.947688 2.56829 + vertex 0.963939 0.953711 2.56851 + vertex 0.963036 0.950435 2.56652 + endloop + endfacet + facet normal -0.472271 -0.361897 0.803735 + outer loop + vertex 0.968152 0.947688 2.56829 + vertex 0.963036 0.950435 2.56652 + vertex 0.964945 0.947549 2.56634 + endloop + endfacet + facet normal -0.434737 -0.339143 0.834257 + outer loop + vertex 0.968015 0.951817 2.57011 + vertex 0.970733 0.953246 2.57211 + vertex 0.966279 0.955651 2.57076 + endloop + endfacet + facet normal -0.4856 -0.347954 0.801948 + outer loop + vertex 0.96249 0.958453 2.56969 + vertex 0.963939 0.953711 2.56851 + vertex 0.966279 0.955651 2.57076 + endloop + endfacet + facet normal -0.488356 -0.353214 0.797965 + outer loop + vertex 0.964526 0.95924 2.57128 + vertex 0.96249 0.958453 2.56969 + vertex 0.966279 0.955651 2.57076 + endloop + endfacet + facet normal -0.461559 -0.343022 0.818107 + outer loop + vertex 0.966279 0.955651 2.57076 + vertex 0.96776 0.958224 2.57268 + vertex 0.964526 0.95924 2.57128 + endloop + endfacet + facet normal -0.44147 -0.358037 0.822748 + outer loop + vertex 0.970733 0.953246 2.57211 + vertex 0.96776 0.958224 2.57268 + vertex 0.966279 0.955651 2.57076 + endloop + endfacet + facet normal -0.493011 -0.343742 0.799238 + outer loop + vertex 0.96249 0.958453 2.56969 + vertex 0.964526 0.95924 2.57128 + vertex 0.962091 0.96146 2.57073 + endloop + endfacet + facet normal -0.496541 -0.348682 0.794901 + outer loop + vertex 0.964526 0.95924 2.57128 + vertex 0.963866 0.962812 2.57243 + vertex 0.962091 0.96146 2.57073 + endloop + endfacet + facet normal -0.462178 -0.348911 0.815262 + outer loop + vertex 0.964526 0.95924 2.57128 + vertex 0.96776 0.958224 2.57268 + vertex 0.963866 0.962812 2.57243 + endloop + endfacet + facet normal -0.458601 -0.345695 0.818646 + outer loop + vertex 0.96776 0.958224 2.57268 + vertex 0.968253 0.962307 2.57468 + vertex 0.963866 0.962812 2.57243 + endloop + endfacet + facet normal -0.45668 -0.364203 0.811665 + outer loop + vertex 0.967414 0.966178 2.57595 + vertex 0.965617 0.969038 2.57623 + vertex 0.963741 0.967311 2.5744 + endloop + endfacet + facet normal -0.456868 -0.366186 0.810666 + outer loop + vertex 0.967414 0.966178 2.57595 + vertex 0.963741 0.967311 2.5744 + vertex 0.968253 0.962307 2.57468 + endloop + endfacet + facet normal -0.456877 -0.366194 0.810657 + outer loop + vertex 0.968253 0.962307 2.57468 + vertex 0.963741 0.967311 2.5744 + vertex 0.963866 0.962812 2.57243 + endloop + endfacet + facet normal -0.354128 -0.306628 0.8835 + outer loop + vertex 0.967414 0.966178 2.57595 + vertex 0.969711 0.968426 2.57766 + vertex 0.965617 0.969038 2.57623 + endloop + endfacet + facet normal -0.4689 -0.350111 0.810898 + outer loop + vertex 0.963741 0.967311 2.5744 + vertex 0.965617 0.969038 2.57623 + vertex 0.962759 0.971248 2.57553 + endloop + endfacet + facet normal -0.448833 -0.316307 0.835763 + outer loop + vertex 0.965617 0.969038 2.57623 + vertex 0.96512 0.972421 2.57724 + vertex 0.962759 0.971248 2.57553 + endloop + endfacet + facet normal -0.354338 -0.315731 0.880204 + outer loop + vertex 0.965617 0.969038 2.57623 + vertex 0.969711 0.968426 2.57766 + vertex 0.96512 0.972421 2.57724 + endloop + endfacet + facet normal -0.362619 -0.325991 0.873062 + outer loop + vertex 0.969711 0.968426 2.57766 + vertex 0.96851 0.973587 2.57908 + vertex 0.96512 0.972421 2.57724 + endloop + endfacet + facet normal -0.384987 -0.334463 0.860186 + outer loop + vertex 0.968112 0.977266 2.58028 + vertex 0.966328 0.980861 2.58088 + vertex 0.963668 0.97782 2.57851 + endloop + endfacet + facet normal -0.385241 -0.323704 0.864179 + outer loop + vertex 0.968112 0.977266 2.58028 + vertex 0.963668 0.97782 2.57851 + vertex 0.96851 0.973587 2.57908 + endloop + endfacet + facet normal -0.371354 -0.30614 0.87657 + outer loop + vertex 0.96851 0.973587 2.57908 + vertex 0.963668 0.97782 2.57851 + vertex 0.96512 0.972421 2.57724 + endloop + endfacet + facet normal -0.267972 -0.286341 0.919891 + outer loop + vertex 0.968112 0.977266 2.58028 + vertex 0.970675 0.979716 2.58179 + vertex 0.966328 0.980861 2.58088 + endloop + endfacet + facet normal -0.393414 -0.326503 0.859431 + outer loop + vertex 0.962369 0.983044 2.5799 + vertex 0.963668 0.97782 2.57851 + vertex 0.966328 0.980861 2.58088 + endloop + endfacet + facet normal -0.400356 -0.343548 0.849523 + outer loop + vertex 0.964779 0.984348 2.58156 + vertex 0.962369 0.983044 2.5799 + vertex 0.966328 0.980861 2.58088 + endloop + endfacet + facet normal -0.283271 -0.303314 0.909812 + outer loop + vertex 0.966328 0.980861 2.58088 + vertex 0.96865 0.984353 2.58277 + vertex 0.964779 0.984348 2.58156 + endloop + endfacet + facet normal -0.272481 -0.310888 0.910551 + outer loop + vertex 0.970675 0.979716 2.58179 + vertex 0.96865 0.984353 2.58277 + vertex 0.966328 0.980861 2.58088 + endloop + endfacet + facet normal -0.406699 -0.333224 0.850622 + outer loop + vertex 0.962369 0.983044 2.5799 + vertex 0.964779 0.984348 2.58156 + vertex 0.962166 0.986237 2.58105 + endloop + endfacet + facet normal -0.383274 -0.294071 0.87557 + outer loop + vertex 0.964779 0.984348 2.58156 + vertex 0.964492 0.988357 2.58278 + vertex 0.962166 0.986237 2.58105 + endloop + endfacet + facet normal -0.283787 -0.297873 0.911447 + outer loop + vertex 0.964779 0.984348 2.58156 + vertex 0.96865 0.984353 2.58277 + vertex 0.964492 0.988357 2.58278 + endloop + endfacet + facet normal -0.299958 -0.31463 0.900574 + outer loop + vertex 0.96865 0.984353 2.58277 + vertex 0.968352 0.987668 2.58383 + vertex 0.964492 0.988357 2.58278 + endloop + endfacet + facet normal -0.297704 -0.286868 0.910538 + outer loop + vertex 0.968352 0.987668 2.58383 + vertex 0.968139 0.991007 2.58481 + vertex 0.964492 0.988357 2.58278 + endloop + endfacet + facet normal -0.287204 -0.300529 0.909503 + outer loop + vertex 0.964492 0.988357 2.58278 + vertex 0.968139 0.991007 2.58481 + vertex 0.963271 0.99348 2.58409 + endloop + endfacet + facet normal -0.293457 -0.314831 0.902643 + outer loop + vertex 0.963271 0.99348 2.58409 + vertex 0.968139 0.991007 2.58481 + vertex 0.966527 0.995488 2.58585 + endloop + endfacet + facet normal -0.290482 -0.319166 0.902083 + outer loop + vertex 0.962646 0.997133 2.58518 + vertex 0.963271 0.99348 2.58409 + vertex 0.966527 0.995488 2.58585 + endloop + endfacet + facet normal -0.283307 -0.298451 0.911408 + outer loop + vertex 0.966527 0.995488 2.58585 + vertex 0.964935 1.00009 2.58686 + vertex 0.962646 0.997133 2.58518 + endloop + endfacet + facet normal -0.166064 -0.26624 0.949494 + outer loop + vertex 0.970496 0.998476 2.58738 + vertex 0.964935 1.00009 2.58686 + vertex 0.966527 0.995488 2.58585 + endloop + endfacet + facet normal -0.171205 -0.286153 0.942765 + outer loop + vertex 0.970496 0.998476 2.58738 + vertex 0.96889 1.00322 2.58853 + vertex 0.964935 1.00009 2.58686 + endloop + endfacet + facet normal -0.156651 -0.30304 0.940014 + outer loop + vertex 0.964935 1.00009 2.58686 + vertex 0.96889 1.00322 2.58853 + vertex 0.964891 1.00413 2.58816 + endloop + endfacet + facet normal -0.153078 -0.284579 0.946352 + outer loop + vertex 0.96889 1.00322 2.58853 + vertex 0.967142 1.00763 2.58958 + vertex 0.964891 1.00413 2.58816 + endloop + endfacet + facet normal -0.198235 -0.255567 0.946249 + outer loop + vertex 0.964891 1.00413 2.58816 + vertex 0.967142 1.00763 2.58958 + vertex 0.96288 1.00684 2.58847 + endloop + endfacet + facet normal -0.180882 -0.309857 0.933418 + outer loop + vertex 0.967104 1.01151 2.59075 + vertex 0.965222 1.01397 2.5912 + vertex 0.962926 1.01086 2.58973 + endloop + endfacet + facet normal -0.185962 -0.287148 0.939662 + outer loop + vertex 0.967104 1.01151 2.59075 + vertex 0.962926 1.01086 2.58973 + vertex 0.967142 1.00763 2.58958 + endloop + endfacet + facet normal -0.189325 -0.291452 0.937663 + outer loop + vertex 0.967142 1.00763 2.58958 + vertex 0.962926 1.01086 2.58973 + vertex 0.96288 1.00684 2.58847 + endloop + endfacet + facet normal -0.0917189 -0.247284 0.964592 + outer loop + vertex 0.967104 1.01151 2.59075 + vertex 0.969602 1.01517 2.59193 + vertex 0.965222 1.01397 2.5912 + endloop + endfacet + facet normal -0.208528 -0.289766 0.934105 + outer loop + vertex 0.962926 1.01086 2.58973 + vertex 0.965222 1.01397 2.5912 + vertex 0.961659 1.01526 2.59081 + endloop + endfacet + facet normal -0.193581 -0.243719 0.95033 + outer loop + vertex 0.965222 1.01397 2.5912 + vertex 0.96557 1.01822 2.59237 + vertex 0.961659 1.01526 2.59081 + endloop + endfacet + facet normal -0.0891087 -0.255627 0.96266 + outer loop + vertex 0.965222 1.01397 2.5912 + vertex 0.969602 1.01517 2.59193 + vertex 0.96557 1.01822 2.59237 + endloop + endfacet + facet normal -0.0788499 -0.242685 0.966895 + outer loop + vertex 0.969602 1.01517 2.59193 + vertex 0.970208 1.01948 2.59306 + vertex 0.96557 1.01822 2.59237 + endloop + endfacet + facet normal -0.0769014 -0.249086 0.965423 + outer loop + vertex 0.970208 1.01948 2.59306 + vertex 0.968865 1.02281 2.59381 + vertex 0.96557 1.01822 2.59237 + endloop + endfacet + facet normal -0.0925061 -0.238311 0.966773 + outer loop + vertex 0.96557 1.01822 2.59237 + vertex 0.968865 1.02281 2.59381 + vertex 0.963873 1.02303 2.59339 + endloop + endfacet + facet normal -0.0928624 -0.254376 0.962637 + outer loop + vertex 0.968865 1.02281 2.59381 + vertex 0.967582 1.02686 2.59476 + vertex 0.963873 1.02303 2.59339 + endloop + endfacet + facet normal -0.103175 -0.244884 0.964047 + outer loop + vertex 0.963873 1.02303 2.59339 + vertex 0.967582 1.02686 2.59476 + vertex 0.962159 1.02782 2.59442 + endloop + endfacet + facet normal -0.105922 -0.262071 0.959218 + outer loop + vertex 0.962159 1.02782 2.59442 + vertex 0.967582 1.02686 2.59476 + vertex 0.966374 1.0309 2.59573 + endloop + endfacet + facet normal -0.0960348 -0.274573 0.956759 + outer loop + vertex 0.962257 1.03177 2.59557 + vertex 0.962159 1.02782 2.59442 + vertex 0.966374 1.0309 2.59573 + endloop + endfacet + facet normal -0.0906721 -0.247846 0.964547 + outer loop + vertex 0.966374 1.0309 2.59573 + vertex 0.9647 1.03533 2.59671 + vertex 0.962257 1.03177 2.59557 + endloop + endfacet + facet normal -0.0334919 -0.228155 0.973049 + outer loop + vertex 0.970104 1.03454 2.59671 + vertex 0.9647 1.03533 2.59671 + vertex 0.966374 1.0309 2.59573 + endloop + endfacet + facet normal -0.0336333 -0.229114 0.972818 + outer loop + vertex 0.970104 1.03454 2.59671 + vertex 0.969254 1.03883 2.59769 + vertex 0.9647 1.03533 2.59671 + endloop + endfacet + facet normal -0.0290111 -0.23479 0.971613 + outer loop + vertex 0.9647 1.03533 2.59671 + vertex 0.969254 1.03883 2.59769 + vertex 0.965155 1.03976 2.59779 + endloop + endfacet + facet normal -0.0259085 -0.221392 0.974841 + outer loop + vertex 0.969254 1.03883 2.59769 + vertex 0.96868 1.04331 2.59869 + vertex 0.965155 1.03976 2.59779 + endloop + endfacet + facet normal -0.0288943 -0.218569 0.975394 + outer loop + vertex 0.965155 1.03976 2.59779 + vertex 0.96868 1.04331 2.59869 + vertex 0.96379 1.04344 2.59858 + endloop + endfacet + facet normal -0.0291493 -0.230729 0.972581 + outer loop + vertex 0.96868 1.04331 2.59869 + vertex 0.967547 1.04749 2.59965 + vertex 0.96379 1.04344 2.59858 + endloop + endfacet + facet normal 0.01633 -0.203303 0.97898 + outer loop + vertex 0.963978 1.06329 2.60324 + vertex 0.968372 1.06799 2.60415 + vertex 0.963356 1.0677 2.60417 + endloop + endfacet + facet normal -0.222067 0.338444 0.914408 + outer loop + vertex 0.963389 2.02632 2.5842 + vertex 0.965623 2.02357 2.58576 + vertex 0.969028 2.02788 2.58499 + endloop + endfacet + facet normal -0.208423 0.276972 0.938001 + outer loop + vertex 0.969028 2.02788 2.58499 + vertex 0.968244 2.03181 2.58366 + vertex 0.963389 2.02632 2.5842 + endloop + endfacet + facet normal -0.24464 0.307195 0.919664 + outer loop + vertex 0.963389 2.02632 2.5842 + vertex 0.968244 2.03181 2.58366 + vertex 0.963068 2.03144 2.5824 + endloop + endfacet + facet normal -0.244779 0.259785 0.934128 + outer loop + vertex 0.968244 2.03181 2.58366 + vertex 0.968029 2.03608 2.58241 + vertex 0.963068 2.03144 2.5824 + endloop + endfacet + facet normal -0.244115 0.259074 0.934499 + outer loop + vertex 0.963068 2.03144 2.5824 + vertex 0.968029 2.03608 2.58241 + vertex 0.964391 2.03621 2.58142 + endloop + endfacet + facet normal -0.379624 0.383043 0.842118 + outer loop + vertex 0.966962 2.0419 2.58034 + vertex 0.963247 2.04108 2.57903 + vertex 0.964888 2.0392 2.58063 + endloop + endfacet + facet normal -0.276584 0.311085 0.909246 + outer loop + vertex 0.964888 2.0392 2.58063 + vertex 0.967799 2.03961 2.58138 + vertex 0.966962 2.0419 2.58034 + endloop + endfacet + facet normal -0.275477 0.289478 0.916687 + outer loop + vertex 0.964888 2.0392 2.58063 + vertex 0.964391 2.03621 2.58142 + vertex 0.967799 2.03961 2.58138 + endloop + endfacet + facet normal -0.244196 0.258305 0.934691 + outer loop + vertex 0.964391 2.03621 2.58142 + vertex 0.968029 2.03608 2.58241 + vertex 0.967799 2.03961 2.58138 + endloop + endfacet + facet normal -0.237322 0.341508 0.909423 + outer loop + vertex 0.966962 2.0419 2.58034 + vertex 0.970724 2.04346 2.58073 + vertex 0.96839 2.04611 2.57913 + endloop + endfacet + facet normal -0.379018 0.371766 0.847428 + outer loop + vertex 0.966962 2.0419 2.58034 + vertex 0.96839 2.04611 2.57913 + vertex 0.963247 2.04108 2.57903 + endloop + endfacet + facet normal -0.349915 0.341504 0.872315 + outer loop + vertex 0.963247 2.04108 2.57903 + vertex 0.96839 2.04611 2.57913 + vertex 0.96322 2.04601 2.57709 + endloop + endfacet + facet normal -0.232965 0.329599 0.914927 + outer loop + vertex 0.970724 2.04346 2.58073 + vertex 0.966962 2.0419 2.58034 + vertex 0.967799 2.03961 2.58138 + endloop + endfacet + facet normal -0.457743 0.333859 0.824021 + outer loop + vertex 0.965336 2.05313 2.57559 + vertex 0.962026 2.05096 2.57462 + vertex 0.963842 2.04964 2.57617 + endloop + endfacet + facet normal -0.356334 0.30052 0.884711 + outer loop + vertex 0.963842 2.04964 2.57617 + vertex 0.967794 2.05106 2.57728 + vertex 0.965336 2.05313 2.57559 + endloop + endfacet + facet normal -0.353218 0.287412 0.890298 + outer loop + vertex 0.963842 2.04964 2.57617 + vertex 0.96322 2.04601 2.57709 + vertex 0.967794 2.05106 2.57728 + endloop + endfacet + facet normal -0.355427 0.289473 0.88875 + outer loop + vertex 0.96322 2.04601 2.57709 + vertex 0.96839 2.04611 2.57913 + vertex 0.967794 2.05106 2.57728 + endloop + endfacet + facet normal -0.467382 0.355001 0.809647 + outer loop + vertex 0.963216 2.05589 2.57315 + vertex 0.962026 2.05096 2.57462 + vertex 0.965336 2.05313 2.57559 + endloop + endfacet + facet normal -0.467657 0.354748 0.809599 + outer loop + vertex 0.967163 2.05672 2.57507 + vertex 0.963216 2.05589 2.57315 + vertex 0.965336 2.05313 2.57559 + endloop + endfacet + facet normal -0.384077 0.320315 0.865958 + outer loop + vertex 0.965336 2.05313 2.57559 + vertex 0.968627 2.05513 2.57631 + vertex 0.967163 2.05672 2.57507 + endloop + endfacet + facet normal -0.367765 0.286836 0.884576 + outer loop + vertex 0.967794 2.05106 2.57728 + vertex 0.968627 2.05513 2.57631 + vertex 0.965336 2.05313 2.57559 + endloop + endfacet + facet normal -0.363623 0.365465 0.856863 + outer loop + vertex 0.967163 2.05672 2.57507 + vertex 0.970642 2.05866 2.57572 + vertex 0.96848 2.06102 2.57379 + endloop + endfacet + facet normal -0.467385 0.379835 0.798296 + outer loop + vertex 0.967163 2.05672 2.57507 + vertex 0.96848 2.06102 2.57379 + vertex 0.963216 2.05589 2.57315 + endloop + endfacet + facet normal -0.442741 0.351176 0.825019 + outer loop + vertex 0.963216 2.05589 2.57315 + vertex 0.96848 2.06102 2.57379 + vertex 0.964193 2.06143 2.57132 + endloop + endfacet + facet normal -0.3557 0.347724 0.867506 + outer loop + vertex 0.970642 2.05866 2.57572 + vertex 0.967163 2.05672 2.57507 + vertex 0.968627 2.05513 2.57631 + endloop + endfacet + facet normal -0.502778 0.33795 0.795616 + outer loop + vertex 0.966798 2.06796 2.57023 + vertex 0.964892 2.06854 2.56878 + vertex 0.96428 2.06545 2.5697 + endloop + endfacet + facet normal -0.463236 0.289588 0.837587 + outer loop + vertex 0.96428 2.06545 2.5697 + vertex 0.9683 2.06589 2.57177 + vertex 0.966798 2.06796 2.57023 + endloop + endfacet + facet normal -0.459921 0.339774 0.820382 + outer loop + vertex 0.96428 2.06545 2.5697 + vertex 0.964193 2.06143 2.57132 + vertex 0.9683 2.06589 2.57177 + endloop + endfacet + facet normal -0.448573 0.328213 0.8313 + outer loop + vertex 0.964193 2.06143 2.57132 + vertex 0.96848 2.06102 2.57379 + vertex 0.9683 2.06589 2.57177 + endloop + endfacet + facet normal -0.456173 0.357631 0.814865 + outer loop + vertex 0.966798 2.06796 2.57023 + vertex 0.969324 2.06952 2.57095 + vertex 0.968149 2.07158 2.56939 + endloop + endfacet + facet normal -0.49096 0.365125 0.790975 + outer loop + vertex 0.966798 2.06796 2.57023 + vertex 0.968149 2.07158 2.56939 + vertex 0.964892 2.06854 2.56878 + endloop + endfacet + facet normal -0.494706 0.370087 0.786322 + outer loop + vertex 0.964892 2.06854 2.56878 + vertex 0.968149 2.07158 2.56939 + vertex 0.964849 2.07147 2.56737 + endloop + endfacet + facet normal -0.436779 0.313086 0.843327 + outer loop + vertex 0.969324 2.06952 2.57095 + vertex 0.966798 2.06796 2.57023 + vertex 0.9683 2.06589 2.57177 + endloop + endfacet + facet normal -0.489991 0.35796 0.794842 + outer loop + vertex 0.966345 2.0772 2.56567 + vertex 0.962925 2.07585 2.56417 + vertex 0.964889 2.0744 2.56603 + endloop + endfacet + facet normal -0.486691 0.356591 0.79748 + outer loop + vertex 0.964889 2.0744 2.56603 + vertex 0.968349 2.07594 2.56745 + vertex 0.966345 2.0772 2.56567 + endloop + endfacet + facet normal -0.489055 0.36794 0.790851 + outer loop + vertex 0.964889 2.0744 2.56603 + vertex 0.964849 2.07147 2.56737 + vertex 0.968349 2.07594 2.56745 + endloop + endfacet + facet normal -0.494321 0.37216 0.785585 + outer loop + vertex 0.964849 2.07147 2.56737 + vertex 0.968149 2.07158 2.56939 + vertex 0.968349 2.07594 2.56745 + endloop + endfacet + facet normal -0.48551 0.35991 0.796709 + outer loop + vertex 0.966345 2.0772 2.56567 + vertex 0.968953 2.07963 2.56616 + vertex 0.966577 2.08021 2.56445 + endloop + endfacet + facet normal -0.490186 0.359233 0.794147 + outer loop + vertex 0.966345 2.0772 2.56567 + vertex 0.966577 2.08021 2.56445 + vertex 0.962925 2.07585 2.56417 + endloop + endfacet + facet normal -0.488166 0.357408 0.796212 + outer loop + vertex 0.962925 2.07585 2.56417 + vertex 0.966577 2.08021 2.56445 + vertex 0.96314 2.08062 2.56216 + endloop + endfacet + facet normal -0.484963 0.35919 0.797366 + outer loop + vertex 0.968953 2.07963 2.56616 + vertex 0.966345 2.0772 2.56567 + vertex 0.968349 2.07594 2.56745 + endloop + endfacet + facet normal -0.476215 0.346989 0.807972 + outer loop + vertex 0.966046 2.08671 2.56119 + vertex 0.963005 2.08638 2.55954 + vertex 0.964385 2.08424 2.56127 + endloop + endfacet + facet normal -0.492183 0.357265 0.793799 + outer loop + vertex 0.964385 2.08424 2.56127 + vertex 0.967275 2.08447 2.56296 + vertex 0.966046 2.08671 2.56119 + endloop + endfacet + facet normal -0.491372 0.363244 0.791586 + outer loop + vertex 0.964385 2.08424 2.56127 + vertex 0.96314 2.08062 2.56216 + vertex 0.967275 2.08447 2.56296 + endloop + endfacet + facet normal -0.487828 0.35855 0.795906 + outer loop + vertex 0.96314 2.08062 2.56216 + vertex 0.966577 2.08021 2.56445 + vertex 0.967275 2.08447 2.56296 + endloop + endfacet + facet normal -0.492839 0.345886 0.798419 + outer loop + vertex 0.966046 2.08671 2.56119 + vertex 0.968483 2.08823 2.56204 + vertex 0.966456 2.08984 2.56008 + endloop + endfacet + facet normal -0.476207 0.347065 0.807943 + outer loop + vertex 0.966046 2.08671 2.56119 + vertex 0.966456 2.08984 2.56008 + vertex 0.963005 2.08638 2.55954 + endloop + endfacet + facet normal -0.477392 0.348454 0.806645 + outer loop + vertex 0.963005 2.08638 2.55954 + vertex 0.966456 2.08984 2.56008 + vertex 0.962842 2.0908 2.55753 + endloop + endfacet + facet normal -0.496083 0.354265 0.792716 + outer loop + vertex 0.968483 2.08823 2.56204 + vertex 0.966046 2.08671 2.56119 + vertex 0.967275 2.08447 2.56296 + endloop + endfacet + facet normal -0.471474 0.380363 0.795636 + outer loop + vertex 0.965567 2.09689 2.55637 + vertex 0.962583 2.09662 2.55473 + vertex 0.963874 2.09446 2.55653 + endloop + endfacet + facet normal -0.463677 0.375385 0.802552 + outer loop + vertex 0.963874 2.09446 2.55653 + vertex 0.966975 2.09434 2.55837 + vertex 0.965567 2.09689 2.55637 + endloop + endfacet + facet normal -0.468519 0.35419 0.809345 + outer loop + vertex 0.963874 2.09446 2.55653 + vertex 0.962842 2.0908 2.55753 + vertex 0.966975 2.09434 2.55837 + endloop + endfacet + facet normal -0.472631 0.360186 0.804293 + outer loop + vertex 0.962842 2.0908 2.55753 + vertex 0.966456 2.08984 2.56008 + vertex 0.966975 2.09434 2.55837 + endloop + endfacet + facet normal -0.462031 0.379498 0.801567 + outer loop + vertex 0.965567 2.09689 2.55637 + vertex 0.968113 2.09826 2.55719 + vertex 0.966264 2.10012 2.55524 + endloop + endfacet + facet normal -0.471575 0.379591 0.795944 + outer loop + vertex 0.965567 2.09689 2.55637 + vertex 0.966264 2.10012 2.55524 + vertex 0.962583 2.09662 2.55473 + endloop + endfacet + facet normal -0.471015 0.378906 0.796602 + outer loop + vertex 0.962583 2.09662 2.55473 + vertex 0.966264 2.10012 2.55524 + vertex 0.96271 2.10096 2.55274 + endloop + endfacet + facet normal -0.461269 0.377155 0.80311 + outer loop + vertex 0.968113 2.09826 2.55719 + vertex 0.965567 2.09689 2.55637 + vertex 0.966975 2.09434 2.55837 + endloop + endfacet + facet normal -0.497572 0.389437 0.775088 + outer loop + vertex 0.965048 2.10822 2.55075 + vertex 0.961634 2.10584 2.54976 + vertex 0.963617 2.10462 2.55164 + endloop + endfacet + facet normal -0.453563 0.379709 0.806289 + outer loop + vertex 0.963617 2.10462 2.55164 + vertex 0.967859 2.10557 2.55358 + vertex 0.965048 2.10822 2.55075 + endloop + endfacet + facet normal -0.453252 0.357865 0.816391 + outer loop + vertex 0.963617 2.10462 2.55164 + vertex 0.96271 2.10096 2.55274 + vertex 0.967859 2.10557 2.55358 + endloop + endfacet + facet normal -0.470332 0.3806 0.796198 + outer loop + vertex 0.96271 2.10096 2.55274 + vertex 0.966264 2.10012 2.55524 + vertex 0.967859 2.10557 2.55358 + endloop + endfacet + facet normal -0.499344 0.393244 0.77202 + outer loop + vertex 0.962157 2.10987 2.54804 + vertex 0.961634 2.10584 2.54976 + vertex 0.965048 2.10822 2.55075 + endloop + endfacet + facet normal -0.505497 0.383715 0.77281 + outer loop + vertex 0.965941 2.1125 2.54921 + vertex 0.962157 2.10987 2.54804 + vertex 0.965048 2.10822 2.55075 + endloop + endfacet + facet normal -0.46162 0.384178 0.799571 + outer loop + vertex 0.965048 2.10822 2.55075 + vertex 0.969207 2.11132 2.55166 + vertex 0.965941 2.1125 2.54921 + endloop + endfacet + facet normal -0.456946 0.37596 0.806136 + outer loop + vertex 0.967859 2.10557 2.55358 + vertex 0.969207 2.11132 2.55166 + vertex 0.965048 2.10822 2.55075 + endloop + endfacet + facet normal -0.526735 0.444685 0.724435 + outer loop + vertex 0.966077 2.11679 2.54697 + vertex 0.962027 2.11531 2.54493 + vertex 0.963492 2.11344 2.54715 + endloop + endfacet + facet normal -0.504976 0.382561 0.773722 + outer loop + vertex 0.963492 2.11344 2.54715 + vertex 0.962157 2.10987 2.54804 + vertex 0.965941 2.1125 2.54921 + endloop + endfacet + facet normal -0.487013 0.416336 0.767778 + outer loop + vertex 0.966077 2.11679 2.54697 + vertex 0.963492 2.11344 2.54715 + vertex 0.965941 2.1125 2.54921 + endloop + endfacet + facet normal -0.489672 0.415713 0.766423 + outer loop + vertex 0.966077 2.11679 2.54697 + vertex 0.965941 2.1125 2.54921 + vertex 0.969504 2.11536 2.54993 + endloop + endfacet + facet normal -0.500997 0.395517 0.769785 + outer loop + vertex 0.966077 2.11679 2.54697 + vertex 0.969504 2.11536 2.54993 + vertex 0.969741 2.11809 2.54869 + endloop + endfacet + facet normal -0.465354 0.37671 0.800959 + outer loop + vertex 0.969504 2.11536 2.54993 + vertex 0.965941 2.1125 2.54921 + vertex 0.969207 2.11132 2.55166 + endloop + endfacet + facet normal -0.527836 0.484957 0.697284 + outer loop + vertex 0.962578 2.11894 2.54283 + vertex 0.962027 2.11531 2.54493 + vertex 0.966077 2.11679 2.54697 + endloop + endfacet + facet normal -0.540008 0.468652 0.699112 + outer loop + vertex 0.966175 2.12018 2.54477 + vertex 0.962578 2.11894 2.54283 + vertex 0.966077 2.11679 2.54697 + endloop + endfacet + facet normal -0.53068 0.471678 0.7042 + outer loop + vertex 0.966077 2.11679 2.54697 + vertex 0.968642 2.11968 2.54697 + vertex 0.966175 2.12018 2.54477 + endloop + endfacet + facet normal -0.504732 0.448677 0.737519 + outer loop + vertex 0.969741 2.11809 2.54869 + vertex 0.968642 2.11968 2.54697 + vertex 0.966077 2.11679 2.54697 + endloop + endfacet + facet normal -0.478569 0.758027 0.443134 + outer loop + vertex 0.964788 2.12692 2.53532 + vertex 0.962153 2.12634 2.53346 + vertex 0.963637 2.12515 2.5371 + endloop + endfacet + facet normal -0.478238 0.75808 0.443399 + outer loop + vertex 0.967013 2.12673 2.53804 + vertex 0.964788 2.12692 2.53532 + vertex 0.963637 2.12515 2.5371 + endloop + endfacet + facet normal -0.47619 0.703729 0.527265 + outer loop + vertex 0.967013 2.12673 2.53804 + vertex 0.963637 2.12515 2.5371 + vertex 0.968547 2.12507 2.54164 + endloop + endfacet + facet normal -0.491475 0.680556 0.543412 + outer loop + vertex 0.968547 2.12507 2.54164 + vertex 0.963637 2.12515 2.5371 + vertex 0.964386 2.12239 2.54123 + endloop + endfacet + facet normal -0.534615 0.56845 0.625341 + outer loop + vertex 0.966175 2.12018 2.54477 + vertex 0.964386 2.12239 2.54123 + vertex 0.962578 2.11894 2.54283 + endloop + endfacet + facet normal -0.502533 0.595951 0.626341 + outer loop + vertex 0.966175 2.12018 2.54477 + vertex 0.968787 2.12212 2.54502 + vertex 0.964386 2.12239 2.54123 + endloop + endfacet + facet normal -0.474701 0.646174 0.597593 + outer loop + vertex 0.968787 2.12212 2.54502 + vertex 0.968547 2.12507 2.54164 + vertex 0.964386 2.12239 2.54123 + endloop + endfacet + facet normal -0.482369 0.563282 0.670845 + outer loop + vertex 0.968787 2.12212 2.54502 + vertex 0.966175 2.12018 2.54477 + vertex 0.968642 2.11968 2.54697 + endloop + endfacet + facet normal -0.502867 0.85658 0.115734 + outer loop + vertex 0.97 2.135 2.52948 + vertex 0.968969 2.135 2.525 + vertex 0.965 2.13267 2.525 + endloop + endfacet + facet normal -0.556224 0.806242 0.201468 + outer loop + vertex 0.97 2.135 2.52948 + vertex 0.965 2.13267 2.525 + vertex 0.97 2.13487 2.53 + endloop + endfacet + facet normal -0.691656 0.573116 0.439488 + outer loop + vertex 0.97 2.13487 2.53 + vertex 0.965 2.13267 2.525 + vertex 0.964041 2.13 2.52698 + endloop + endfacet + facet normal -0.677064 0.484128 0.55426 + outer loop + vertex 0.97 2.13487 2.53 + vertex 0.964041 2.13 2.52698 + vertex 0.967799 2.13032 2.53128 + endloop + endfacet + facet normal -0.464337 0.8164 0.343341 + outer loop + vertex 0.967799 2.13032 2.53128 + vertex 0.964041 2.13 2.52698 + vertex 0.963577 2.12789 2.53137 + endloop + endfacet + facet normal -0.421263 0.842523 0.335696 + outer loop + vertex 0.964788 2.12692 2.53532 + vertex 0.963577 2.12789 2.53137 + vertex 0.962153 2.12634 2.53346 + endloop + endfacet + facet normal -0.428154 0.838585 0.336838 + outer loop + vertex 0.964788 2.12692 2.53532 + vertex 0.967504 2.12829 2.53534 + vertex 0.963577 2.12789 2.53137 + endloop + endfacet + facet normal -0.458805 0.807723 0.370244 + outer loop + vertex 0.967504 2.12829 2.53534 + vertex 0.967799 2.13032 2.53128 + vertex 0.963577 2.12789 2.53137 + endloop + endfacet + facet normal -0.417655 0.816834 0.397929 + outer loop + vertex 0.967504 2.12829 2.53534 + vertex 0.964788 2.12692 2.53532 + vertex 0.967013 2.12673 2.53804 + endloop + endfacet + facet normal -0.611579 0.778562 0.140754 + outer loop + vertex 0.97 2.13581 2.525 + vertex 0.968969 2.135 2.525 + vertex 0.97 2.135 2.52948 + endloop + endfacet + facet normal -0.479498 -0.680075 -0.554599 + outer loop + vertex 0.975 0.889266 2.53 + vertex 0.973959 0.89 2.53 + vertex 0.975 0.89 2.5291 + endloop + endfacet + facet normal -0.562524 -0.79783 0.216876 + outer loop + vertex 0.975 0.889266 2.53 + vertex 0.975 0.89 2.5327 + vertex 0.973959 0.89 2.53 + endloop + endfacet + facet normal -0.415965 -0.871749 0.258895 + outer loop + vertex 0.975 0.891064 2.535 + vertex 0.971091 0.892706 2.53425 + vertex 0.970579 0.892044 2.5312 + endloop + endfacet + facet normal -0.490153 -0.791089 0.365962 + outer loop + vertex 0.975 0.89 2.5327 + vertex 0.975 0.891064 2.535 + vertex 0.970579 0.892044 2.5312 + endloop + endfacet + facet normal -0.0876893 -0.705968 -0.702795 + outer loop + vertex 0.975 0.89 2.5327 + vertex 0.970579 0.892044 2.5312 + vertex 0.97 0.893309 2.53 + endloop + endfacet + facet normal -0.622562 -0.744852 0.240023 + outer loop + vertex 0.975 0.89 2.5327 + vertex 0.97 0.893309 2.53 + vertex 0.973959 0.89 2.53 + endloop + endfacet + facet normal -0.418116 -0.855243 0.306168 + outer loop + vertex 0.974573 0.891967 2.53694 + vertex 0.971091 0.892706 2.53425 + vertex 0.975 0.891064 2.535 + endloop + endfacet + facet normal -0.434108 -0.837561 0.331725 + outer loop + vertex 0.97203 0.89348 2.53743 + vertex 0.971091 0.892706 2.53425 + vertex 0.974573 0.891967 2.53694 + endloop + endfacet + facet normal -0.424929 -0.831008 0.358973 + outer loop + vertex 0.974573 0.891967 2.53694 + vertex 0.974596 0.893159 2.53973 + vertex 0.97203 0.89348 2.53743 + endloop + endfacet + facet normal -0.431364 -0.863964 0.259791 + outer loop + vertex 0.970579 0.892044 2.5312 + vertex 0.971091 0.892706 2.53425 + vertex 0.967658 0.893705 2.53187 + endloop + endfacet + facet normal -0.458201 -0.823169 0.335329 + outer loop + vertex 0.971091 0.892706 2.53425 + vertex 0.97203 0.89348 2.53743 + vertex 0.968073 0.89499 2.53573 + endloop + endfacet + facet normal -0.464391 -0.824145 0.324232 + outer loop + vertex 0.967658 0.893705 2.53187 + vertex 0.971091 0.892706 2.53425 + vertex 0.968073 0.89499 2.53573 + endloop + endfacet + facet normal -0.469054 -0.779299 0.415551 + outer loop + vertex 0.97203 0.89348 2.53743 + vertex 0.974596 0.893159 2.53973 + vertex 0.972533 0.894966 2.54079 + endloop + endfacet + facet normal -0.474554 -0.776244 0.415023 + outer loop + vertex 0.97203 0.89348 2.53743 + vertex 0.972533 0.894966 2.54079 + vertex 0.968073 0.89499 2.53573 + endloop + endfacet + facet normal -0.466588 -0.784773 0.407954 + outer loop + vertex 0.968073 0.89499 2.53573 + vertex 0.972533 0.894966 2.54079 + vertex 0.9675 0.89746 2.53983 + endloop + endfacet + facet normal -0.476869 -0.671845 0.566763 + outer loop + vertex 0.96741 0.899866 2.54305 + vertex 0.971699 0.897525 2.54388 + vertex 0.970264 0.900004 2.54561 + endloop + endfacet + facet normal -0.485686 -0.706568 0.514656 + outer loop + vertex 0.96741 0.899866 2.54305 + vertex 0.9675 0.89746 2.53983 + vertex 0.971699 0.897525 2.54388 + endloop + endfacet + facet normal -0.460302 -0.741012 0.488899 + outer loop + vertex 0.9675 0.89746 2.53983 + vertex 0.972533 0.894966 2.54079 + vertex 0.971699 0.897525 2.54388 + endloop + endfacet + facet normal -0.424709 -0.670597 0.608212 + outer loop + vertex 0.971699 0.897525 2.54388 + vertex 0.973749 0.899146 2.5471 + vertex 0.970264 0.900004 2.54561 + endloop + endfacet + facet normal -0.508366 -0.618748 0.598928 + outer loop + vertex 0.96741 0.899866 2.54305 + vertex 0.970264 0.900004 2.54561 + vertex 0.967545 0.901947 2.54531 + endloop + endfacet + facet normal -0.463864 -0.540487 0.701929 + outer loop + vertex 0.970264 0.900004 2.54561 + vertex 0.969481 0.903028 2.54742 + vertex 0.967545 0.901947 2.54531 + endloop + endfacet + facet normal -0.439227 -0.542556 0.716039 + outer loop + vertex 0.970264 0.900004 2.54561 + vertex 0.973749 0.899146 2.5471 + vertex 0.969481 0.903028 2.54742 + endloop + endfacet + facet normal -0.438473 -0.541812 0.717064 + outer loop + vertex 0.973749 0.899146 2.5471 + vertex 0.973964 0.90248 2.54975 + vertex 0.969481 0.903028 2.54742 + endloop + endfacet + facet normal -0.46079 -0.423855 0.779756 + outer loop + vertex 0.972392 0.906163 2.55107 + vertex 0.970092 0.909205 2.55136 + vertex 0.968715 0.907395 2.54956 + endloop + endfacet + facet normal -0.464187 -0.46733 0.752418 + outer loop + vertex 0.972392 0.906163 2.55107 + vertex 0.968715 0.907395 2.54956 + vertex 0.973964 0.90248 2.54975 + endloop + endfacet + facet normal -0.453433 -0.455322 0.766212 + outer loop + vertex 0.973964 0.90248 2.54975 + vertex 0.968715 0.907395 2.54956 + vertex 0.969481 0.903028 2.54742 + endloop + endfacet + facet normal -0.441214 -0.410805 0.797853 + outer loop + vertex 0.972392 0.906163 2.55107 + vertex 0.973829 0.908026 2.55282 + vertex 0.970092 0.909205 2.55136 + endloop + endfacet + facet normal -0.466082 -0.419204 0.779125 + outer loop + vertex 0.968715 0.907395 2.54956 + vertex 0.970092 0.909205 2.55136 + vertex 0.96703 0.911383 2.5507 + endloop + endfacet + facet normal -0.45163 -0.392136 0.801411 + outer loop + vertex 0.970092 0.909205 2.55136 + vertex 0.968811 0.913075 2.55253 + vertex 0.96703 0.911383 2.5507 + endloop + endfacet + facet normal -0.439177 -0.390362 0.80916 + outer loop + vertex 0.970092 0.909205 2.55136 + vertex 0.973829 0.908026 2.55282 + vertex 0.968811 0.913075 2.55253 + endloop + endfacet + facet normal -0.438403 -0.389546 0.809973 + outer loop + vertex 0.973829 0.908026 2.55282 + vertex 0.973541 0.912442 2.55479 + vertex 0.968811 0.913075 2.55253 + endloop + endfacet + facet normal -0.43409 -0.380386 0.816622 + outer loop + vertex 0.972419 0.91627 2.55593 + vertex 0.970325 0.919359 2.55626 + vertex 0.968587 0.917689 2.55455 + endloop + endfacet + facet normal -0.432588 -0.37168 0.821415 + outer loop + vertex 0.972419 0.91627 2.55593 + vertex 0.968587 0.917689 2.55455 + vertex 0.973541 0.912442 2.55479 + endloop + endfacet + facet normal -0.439226 -0.378242 0.81487 + outer loop + vertex 0.973541 0.912442 2.55479 + vertex 0.968587 0.917689 2.55455 + vertex 0.968811 0.913075 2.55253 + endloop + endfacet + facet normal -0.450465 -0.390056 0.80308 + outer loop + vertex 0.972419 0.91627 2.55593 + vertex 0.974016 0.918106 2.55772 + vertex 0.970325 0.919359 2.55626 + endloop + endfacet + facet normal -0.430321 -0.384418 0.816729 + outer loop + vertex 0.968587 0.917689 2.55455 + vertex 0.970325 0.919359 2.55626 + vertex 0.967386 0.921589 2.55576 + endloop + endfacet + facet normal -0.433489 -0.389511 0.812631 + outer loop + vertex 0.970325 0.919359 2.55626 + vertex 0.969117 0.923216 2.55746 + vertex 0.967386 0.921589 2.55576 + endloop + endfacet + facet normal -0.450654 -0.391633 0.802206 + outer loop + vertex 0.970325 0.919359 2.55626 + vertex 0.974016 0.918106 2.55772 + vertex 0.969117 0.923216 2.55746 + endloop + endfacet + facet normal -0.443579 -0.38448 0.809576 + outer loop + vertex 0.974016 0.918106 2.55772 + vertex 0.973611 0.922608 2.55963 + vertex 0.969117 0.923216 2.55746 + endloop + endfacet + facet normal -0.443465 -0.375932 0.813642 + outer loop + vertex 0.972503 0.926333 2.56076 + vertex 0.970405 0.929443 2.56105 + vertex 0.968759 0.92783 2.55941 + endloop + endfacet + facet normal -0.443773 -0.377511 0.812743 + outer loop + vertex 0.972503 0.926333 2.56076 + vertex 0.968759 0.92783 2.55941 + vertex 0.973611 0.922608 2.55963 + endloop + endfacet + facet normal -0.444066 -0.377796 0.812451 + outer loop + vertex 0.973611 0.922608 2.55963 + vertex 0.968759 0.92783 2.55941 + vertex 0.969117 0.923216 2.55746 + endloop + endfacet + facet normal -0.461963 -0.38694 0.79804 + outer loop + vertex 0.972503 0.926333 2.56076 + vertex 0.974084 0.927922 2.56244 + vertex 0.970405 0.929443 2.56105 + endloop + endfacet + facet normal -0.443517 -0.375876 0.81364 + outer loop + vertex 0.968759 0.92783 2.55941 + vertex 0.970405 0.929443 2.56105 + vertex 0.967496 0.931714 2.56052 + endloop + endfacet + facet normal -0.44966 -0.385623 0.805668 + outer loop + vertex 0.970405 0.929443 2.56105 + vertex 0.969178 0.933288 2.56221 + vertex 0.967496 0.931714 2.56052 + endloop + endfacet + facet normal -0.462016 -0.387223 0.797872 + outer loop + vertex 0.970405 0.929443 2.56105 + vertex 0.974084 0.927922 2.56244 + vertex 0.969178 0.933288 2.56221 + endloop + endfacet + facet normal -0.463095 -0.38826 0.796741 + outer loop + vertex 0.974084 0.927922 2.56244 + vertex 0.973614 0.932638 2.56447 + vertex 0.969178 0.933288 2.56221 + endloop + endfacet + facet normal -0.465066 -0.368521 0.804926 + outer loop + vertex 0.972386 0.936515 2.5656 + vertex 0.970601 0.939364 2.56587 + vertex 0.968971 0.937798 2.56422 + endloop + endfacet + facet normal -0.466927 -0.380881 0.798066 + outer loop + vertex 0.972386 0.936515 2.5656 + vertex 0.968971 0.937798 2.56422 + vertex 0.973614 0.932638 2.56447 + endloop + endfacet + facet normal -0.463872 -0.377977 0.801222 + outer loop + vertex 0.973614 0.932638 2.56447 + vertex 0.968971 0.937798 2.56422 + vertex 0.969178 0.933288 2.56221 + endloop + endfacet + facet normal -0.429952 -0.349165 0.832601 + outer loop + vertex 0.972386 0.936515 2.5656 + vertex 0.974159 0.938272 2.56725 + vertex 0.970601 0.939364 2.56587 + endloop + endfacet + facet normal -0.465581 -0.367948 0.80489 + outer loop + vertex 0.968971 0.937798 2.56422 + vertex 0.970601 0.939364 2.56587 + vertex 0.968103 0.941463 2.56539 + endloop + endfacet + facet normal -0.465337 -0.367586 0.805197 + outer loop + vertex 0.970601 0.939364 2.56587 + vertex 0.97008 0.942434 2.56697 + vertex 0.968103 0.941463 2.56539 + endloop + endfacet + facet normal -0.432173 -0.368384 0.823116 + outer loop + vertex 0.970601 0.939364 2.56587 + vertex 0.974159 0.938272 2.56725 + vertex 0.97008 0.942434 2.56697 + endloop + endfacet + facet normal -0.431463 -0.367641 0.82382 + outer loop + vertex 0.974159 0.938272 2.56725 + vertex 0.973744 0.942904 2.5691 + vertex 0.97008 0.942434 2.56697 + endloop + endfacet + facet normal -0.44581 -0.378247 0.811284 + outer loop + vertex 0.972687 0.946642 2.5703 + vertex 0.970924 0.949517 2.57067 + vertex 0.968152 0.947688 2.56829 + endloop + endfacet + facet normal -0.445913 -0.383845 0.808595 + outer loop + vertex 0.972687 0.946642 2.5703 + vertex 0.968152 0.947688 2.56829 + vertex 0.973744 0.942904 2.5691 + endloop + endfacet + facet normal -0.43221 -0.36512 0.82455 + outer loop + vertex 0.973744 0.942904 2.5691 + vertex 0.968152 0.947688 2.56829 + vertex 0.97008 0.942434 2.56697 + endloop + endfacet + facet normal -0.349347 -0.327665 0.877834 + outer loop + vertex 0.972687 0.946642 2.5703 + vertex 0.975158 0.949145 2.57221 + vertex 0.970924 0.949517 2.57067 + endloop + endfacet + facet normal -0.44986 -0.3726 0.811662 + outer loop + vertex 0.968152 0.947688 2.56829 + vertex 0.970924 0.949517 2.57067 + vertex 0.968015 0.951817 2.57011 + endloop + endfacet + facet normal -0.431677 -0.344259 0.833751 + outer loop + vertex 0.970924 0.949517 2.57067 + vertex 0.970733 0.953246 2.57211 + vertex 0.968015 0.951817 2.57011 + endloop + endfacet + facet normal -0.348127 -0.353324 0.868314 + outer loop + vertex 0.970924 0.949517 2.57067 + vertex 0.975158 0.949145 2.57221 + vertex 0.970733 0.953246 2.57211 + endloop + endfacet + facet normal -0.359632 -0.365997 0.858319 + outer loop + vertex 0.975158 0.949145 2.57221 + vertex 0.974093 0.952856 2.57335 + vertex 0.970733 0.953246 2.57211 + endloop + endfacet + facet normal -0.360588 -0.333197 0.871181 + outer loop + vertex 0.974093 0.952856 2.57335 + vertex 0.972897 0.956968 2.57443 + vertex 0.970733 0.953246 2.57211 + endloop + endfacet + facet normal -0.374757 -0.323504 0.868851 + outer loop + vertex 0.970733 0.953246 2.57211 + vertex 0.972897 0.956968 2.57443 + vertex 0.96776 0.958224 2.57268 + endloop + endfacet + facet normal -0.363657 -0.36783 0.855836 + outer loop + vertex 0.972227 0.961257 2.57592 + vertex 0.970349 0.964294 2.57642 + vertex 0.968253 0.962307 2.57468 + endloop + endfacet + facet normal -0.362241 -0.355778 0.861513 + outer loop + vertex 0.972227 0.961257 2.57592 + vertex 0.968253 0.962307 2.57468 + vertex 0.972897 0.956968 2.57443 + endloop + endfacet + facet normal -0.379071 -0.369796 0.848266 + outer loop + vertex 0.972897 0.956968 2.57443 + vertex 0.968253 0.962307 2.57468 + vertex 0.96776 0.958224 2.57268 + endloop + endfacet + facet normal -0.235125 -0.299863 0.924553 + outer loop + vertex 0.972227 0.961257 2.57592 + vertex 0.974682 0.96413 2.57747 + vertex 0.970349 0.964294 2.57642 + endloop + endfacet + facet normal -0.369156 -0.362105 0.855923 + outer loop + vertex 0.968253 0.962307 2.57468 + vertex 0.970349 0.964294 2.57642 + vertex 0.967414 0.966178 2.57595 + endloop + endfacet + facet normal -0.344466 -0.316702 0.883767 + outer loop + vertex 0.970349 0.964294 2.57642 + vertex 0.969711 0.968426 2.57766 + vertex 0.967414 0.966178 2.57595 + endloop + endfacet + facet normal -0.234688 -0.310866 0.921023 + outer loop + vertex 0.970349 0.964294 2.57642 + vertex 0.974682 0.96413 2.57747 + vertex 0.969711 0.968426 2.57766 + endloop + endfacet + facet normal -0.259515 -0.338875 0.904332 + outer loop + vertex 0.974682 0.96413 2.57747 + vertex 0.973691 0.967808 2.57857 + vertex 0.969711 0.968426 2.57766 + endloop + endfacet + facet normal -0.257363 -0.307948 0.915933 + outer loop + vertex 0.973691 0.967808 2.57857 + vertex 0.973306 0.97121 2.5796 + vertex 0.969711 0.968426 2.57766 + endloop + endfacet + facet normal -0.253681 -0.312373 0.915461 + outer loop + vertex 0.969711 0.968426 2.57766 + vertex 0.973306 0.97121 2.5796 + vertex 0.96851 0.973587 2.57908 + endloop + endfacet + facet normal -0.260037 -0.326678 0.90866 + outer loop + vertex 0.96851 0.973587 2.57908 + vertex 0.973306 0.97121 2.5796 + vertex 0.971834 0.97554 2.58074 + endloop + endfacet + facet normal -0.261247 -0.324873 0.90896 + outer loop + vertex 0.968112 0.977266 2.58028 + vertex 0.96851 0.973587 2.57908 + vertex 0.971834 0.97554 2.58074 + endloop + endfacet + facet normal -0.252117 -0.302504 0.9192 + outer loop + vertex 0.971834 0.97554 2.58074 + vertex 0.970675 0.979716 2.58179 + vertex 0.968112 0.977266 2.58028 + endloop + endfacet + facet normal -0.141933 -0.279607 0.949565 + outer loop + vertex 0.975687 0.978512 2.58219 + vertex 0.970675 0.979716 2.58179 + vertex 0.971834 0.97554 2.58074 + endloop + endfacet + facet normal -0.14369 -0.287811 0.946846 + outer loop + vertex 0.975687 0.978512 2.58219 + vertex 0.973878 0.983225 2.58335 + vertex 0.970675 0.979716 2.58179 + endloop + endfacet + facet normal -0.162907 -0.271076 0.948672 + outer loop + vertex 0.970675 0.979716 2.58179 + vertex 0.973878 0.983225 2.58335 + vertex 0.96865 0.984353 2.58277 + endloop + endfacet + facet normal -0.168385 -0.301703 0.938415 + outer loop + vertex 0.973878 0.983225 2.58335 + vertex 0.972132 0.987814 2.58451 + vertex 0.96865 0.984353 2.58277 + endloop + endfacet + facet normal -0.156059 -0.313267 0.936755 + outer loop + vertex 0.96865 0.984353 2.58277 + vertex 0.972132 0.987814 2.58451 + vertex 0.968352 0.987668 2.58383 + endloop + endfacet + facet normal -0.156786 -0.30814 0.938333 + outer loop + vertex 0.972237 0.991655 2.58571 + vertex 0.970306 0.994151 2.58621 + vertex 0.968139 0.991007 2.58481 + endloop + endfacet + facet normal -0.160639 -0.290607 0.943262 + outer loop + vertex 0.972237 0.991655 2.58571 + vertex 0.968139 0.991007 2.58481 + vertex 0.972132 0.987814 2.58451 + endloop + endfacet + facet normal -0.158421 -0.287947 0.944452 + outer loop + vertex 0.972132 0.987814 2.58451 + vertex 0.968139 0.991007 2.58481 + vertex 0.968352 0.987668 2.58383 + endloop + endfacet + facet normal -0.0770349 -0.251681 0.964739 + outer loop + vertex 0.972237 0.991655 2.58571 + vertex 0.974681 0.995311 2.58686 + vertex 0.970306 0.994151 2.58621 + endloop + endfacet + facet normal -0.189575 -0.28597 0.939299 + outer loop + vertex 0.968139 0.991007 2.58481 + vertex 0.970306 0.994151 2.58621 + vertex 0.966527 0.995488 2.58585 + endloop + endfacet + facet normal -0.178323 -0.250952 0.951433 + outer loop + vertex 0.970306 0.994151 2.58621 + vertex 0.970496 0.998476 2.58738 + vertex 0.966527 0.995488 2.58585 + endloop + endfacet + facet normal -0.074933 -0.258661 0.963057 + outer loop + vertex 0.970306 0.994151 2.58621 + vertex 0.974681 0.995311 2.58686 + vertex 0.970496 0.998476 2.58738 + endloop + endfacet + facet normal -0.0666528 -0.248267 0.966396 + outer loop + vertex 0.974681 0.995311 2.58686 + vertex 0.975211 0.99959 2.58799 + vertex 0.970496 0.998476 2.58738 + endloop + endfacet + facet normal -0.06306 -0.261665 0.963096 + outer loop + vertex 0.975211 0.99959 2.58799 + vertex 0.97379 1.00293 2.58881 + vertex 0.970496 0.998476 2.58738 + endloop + endfacet + facet normal -0.0697825 -0.256956 0.963901 + outer loop + vertex 0.970496 0.998476 2.58738 + vertex 0.97379 1.00293 2.58881 + vertex 0.96889 1.00322 2.58853 + endloop + endfacet + facet normal -0.0701781 -0.266 0.961415 + outer loop + vertex 0.97379 1.00293 2.58881 + vertex 0.972446 1.00697 2.58983 + vertex 0.96889 1.00322 2.58853 + endloop + endfacet + facet normal -0.0782396 -0.258802 0.962756 + outer loop + vertex 0.96889 1.00322 2.58853 + vertex 0.972446 1.00697 2.58983 + vertex 0.967142 1.00763 2.58958 + endloop + endfacet + facet normal -0.0801592 -0.275849 0.957853 + outer loop + vertex 0.967142 1.00763 2.58958 + vertex 0.972446 1.00697 2.58983 + vertex 0.971181 1.01096 2.59087 + endloop + endfacet + facet normal -0.0670566 -0.290487 0.954526 + outer loop + vertex 0.967104 1.01151 2.59075 + vertex 0.967142 1.00763 2.58958 + vertex 0.971181 1.01096 2.59087 + endloop + endfacet + facet normal -0.0638714 -0.265467 0.962002 + outer loop + vertex 0.971181 1.01096 2.59087 + vertex 0.969602 1.01517 2.59193 + vertex 0.967104 1.01151 2.59075 + endloop + endfacet + facet normal -0.0126943 -0.247964 0.968686 + outer loop + vertex 0.974933 1.01468 2.59187 + vertex 0.969602 1.01517 2.59193 + vertex 0.971181 1.01096 2.59087 + endloop + endfacet + facet normal -0.0121603 -0.242305 0.970124 + outer loop + vertex 0.974933 1.01468 2.59187 + vertex 0.974194 1.01893 2.59293 + vertex 0.969602 1.01517 2.59193 + endloop + endfacet + facet normal -0.00232066 -0.253561 0.967317 + outer loop + vertex 0.969602 1.01517 2.59193 + vertex 0.974194 1.01893 2.59293 + vertex 0.970208 1.01948 2.59306 + endloop + endfacet + facet normal 0.000289611 -0.235423 0.971893 + outer loop + vertex 0.974194 1.01893 2.59293 + vertex 0.973749 1.02318 2.59396 + vertex 0.970208 1.01948 2.59306 + endloop + endfacet + facet normal -0.0114867 -0.224771 0.974344 + outer loop + vertex 0.970208 1.01948 2.59306 + vertex 0.973749 1.02318 2.59396 + vertex 0.968865 1.02281 2.59381 + endloop + endfacet + facet normal -0.0103063 -0.239025 0.970959 + outer loop + vertex 0.973749 1.02318 2.59396 + vertex 0.972752 1.02705 2.5949 + vertex 0.968865 1.02281 2.59381 + endloop + endfacet + facet normal -0.0175197 -0.232767 0.972375 + outer loop + vertex 0.968865 1.02281 2.59381 + vertex 0.972752 1.02705 2.5949 + vertex 0.967582 1.02686 2.59476 + endloop + endfacet + facet normal -0.0199657 0.233765 0.972088 + outer loop + vertex 0.968049 1.99686 2.59319 + vertex 0.972455 2.00095 2.5923 + vertex 0.967422 2.00157 2.59204 + endloop + endfacet + facet normal -0.0214579 0.222715 0.974647 + outer loop + vertex 0.967422 2.00157 2.59204 + vertex 0.972455 2.00095 2.5923 + vertex 0.972164 2.0049 2.59139 + endloop + endfacet + facet normal -0.238098 0.269869 0.932995 + outer loop + vertex 0.973109 2.05163 2.57847 + vertex 0.972643 2.05619 2.57703 + vertex 0.967794 2.05106 2.57728 + endloop + endfacet + facet normal -0.240502 0.272079 0.931736 + outer loop + vertex 0.967794 2.05106 2.57728 + vertex 0.972643 2.05619 2.57703 + vertex 0.968627 2.05513 2.57631 + endloop + endfacet + facet normal -0.267281 0.340394 0.901495 + outer loop + vertex 0.970642 2.05866 2.57572 + vertex 0.974012 2.06015 2.57615 + vertex 0.973428 2.06264 2.57504 + endloop + endfacet + facet normal -0.342169 0.38524 0.857036 + outer loop + vertex 0.96848 2.06102 2.57379 + vertex 0.970642 2.05866 2.57572 + vertex 0.973428 2.06264 2.57504 + endloop + endfacet + facet normal -0.244844 0.293842 0.923963 + outer loop + vertex 0.972643 2.05619 2.57703 + vertex 0.970642 2.05866 2.57572 + vertex 0.968627 2.05513 2.57631 + endloop + endfacet + facet normal -0.248366 0.290969 0.923932 + outer loop + vertex 0.974012 2.06015 2.57615 + vertex 0.970642 2.05866 2.57572 + vertex 0.972643 2.05619 2.57703 + endloop + endfacet + facet normal -0.333212 0.340924 0.879057 + outer loop + vertex 0.973428 2.06264 2.57504 + vertex 0.973088 2.06631 2.57349 + vertex 0.96848 2.06102 2.57379 + endloop + endfacet + facet normal -0.342978 0.349035 0.87209 + outer loop + vertex 0.96848 2.06102 2.57379 + vertex 0.973088 2.06631 2.57349 + vertex 0.9683 2.06589 2.57177 + endloop + endfacet + facet normal -0.445332 0.365666 0.817293 + outer loop + vertex 0.971302 2.07241 2.57074 + vertex 0.968149 2.07158 2.56939 + vertex 0.969324 2.06952 2.57095 + endloop + endfacet + facet normal -0.341746 0.300176 0.890564 + outer loop + vertex 0.969324 2.06952 2.57095 + vertex 0.972902 2.0706 2.57197 + vertex 0.971302 2.07241 2.57074 + endloop + endfacet + facet normal -0.341172 0.297065 0.891826 + outer loop + vertex 0.969324 2.06952 2.57095 + vertex 0.9683 2.06589 2.57177 + vertex 0.972902 2.0706 2.57197 + endloop + endfacet + facet normal -0.344896 0.300819 0.889132 + outer loop + vertex 0.9683 2.06589 2.57177 + vertex 0.973088 2.06631 2.57349 + vertex 0.972902 2.0706 2.57197 + endloop + endfacet + facet normal -0.370672 0.380343 0.847315 + outer loop + vertex 0.971302 2.07241 2.57074 + vertex 0.974069 2.07434 2.57109 + vertex 0.972741 2.07635 2.5696 + endloop + endfacet + facet normal -0.446856 0.395229 0.802567 + outer loop + vertex 0.971302 2.07241 2.57074 + vertex 0.972741 2.07635 2.5696 + vertex 0.968149 2.07158 2.56939 + endloop + endfacet + facet normal -0.434393 0.382689 0.815385 + outer loop + vertex 0.968149 2.07158 2.56939 + vertex 0.972741 2.07635 2.5696 + vertex 0.968349 2.07594 2.56745 + endloop + endfacet + facet normal -0.328757 0.312142 0.89134 + outer loop + vertex 0.974069 2.07434 2.57109 + vertex 0.971302 2.07241 2.57074 + vertex 0.972902 2.0706 2.57197 + endloop + endfacet + facet normal -0.48617 0.358248 0.797056 + outer loop + vertex 0.970265 2.08331 2.56531 + vertex 0.966577 2.08021 2.56445 + vertex 0.968953 2.07963 2.56616 + endloop + endfacet + facet normal -0.428791 0.34644 0.834337 + outer loop + vertex 0.968953 2.07963 2.56616 + vertex 0.973008 2.08135 2.56753 + vertex 0.970265 2.08331 2.56531 + endloop + endfacet + facet normal -0.43221 0.360732 0.826479 + outer loop + vertex 0.968953 2.07963 2.56616 + vertex 0.968349 2.07594 2.56745 + vertex 0.973008 2.08135 2.56753 + endloop + endfacet + facet normal -0.436287 0.364298 0.822764 + outer loop + vertex 0.968349 2.07594 2.56745 + vertex 0.972741 2.07635 2.5696 + vertex 0.973008 2.08135 2.56753 + endloop + endfacet + facet normal -0.486403 0.358611 0.79675 + outer loop + vertex 0.967275 2.08447 2.56296 + vertex 0.966577 2.08021 2.56445 + vertex 0.970265 2.08331 2.56531 + endloop + endfacet + facet normal -0.490639 0.350117 0.797929 + outer loop + vertex 0.971014 2.08749 2.56393 + vertex 0.967275 2.08447 2.56296 + vertex 0.970265 2.08331 2.56531 + endloop + endfacet + facet normal -0.444602 0.350552 0.824283 + outer loop + vertex 0.970265 2.08331 2.56531 + vertex 0.974152 2.08639 2.56609 + vertex 0.971014 2.08749 2.56393 + endloop + endfacet + facet normal -0.435842 0.33686 0.834606 + outer loop + vertex 0.973008 2.08135 2.56753 + vertex 0.974152 2.08639 2.56609 + vertex 0.970265 2.08331 2.56531 + endloop + endfacet + facet normal -0.485034 0.356061 0.798726 + outer loop + vertex 0.970982 2.09216 2.5618 + vertex 0.966456 2.08984 2.56008 + vertex 0.968483 2.08823 2.56204 + endloop + endfacet + facet normal -0.492821 0.353769 0.794969 + outer loop + vertex 0.968483 2.08823 2.56204 + vertex 0.967275 2.08447 2.56296 + vertex 0.971014 2.08749 2.56393 + endloop + endfacet + facet normal -0.490484 0.359236 0.793962 + outer loop + vertex 0.970982 2.09216 2.5618 + vertex 0.968483 2.08823 2.56204 + vertex 0.971014 2.08749 2.56393 + endloop + endfacet + facet normal -0.469579 0.364108 0.804314 + outer loop + vertex 0.970982 2.09216 2.5618 + vertex 0.971014 2.08749 2.56393 + vertex 0.974357 2.09021 2.56465 + endloop + endfacet + facet normal -0.465913 0.369774 0.803861 + outer loop + vertex 0.970982 2.09216 2.5618 + vertex 0.974357 2.09021 2.56465 + vertex 0.975062 2.09337 2.56361 + endloop + endfacet + facet normal -0.451471 0.335795 0.82669 + outer loop + vertex 0.974357 2.09021 2.56465 + vertex 0.971014 2.08749 2.56393 + vertex 0.974152 2.08639 2.56609 + endloop + endfacet + facet normal -0.485831 0.358921 0.796959 + outer loop + vertex 0.966975 2.09434 2.55837 + vertex 0.966456 2.08984 2.56008 + vertex 0.970982 2.09216 2.5618 + endloop + endfacet + facet normal -0.47366 0.378544 0.795205 + outer loop + vertex 0.970883 2.09728 2.5593 + vertex 0.966975 2.09434 2.55837 + vertex 0.970982 2.09216 2.5618 + endloop + endfacet + facet normal -0.464384 0.380847 0.799564 + outer loop + vertex 0.970982 2.09216 2.5618 + vertex 0.97452 2.09652 2.56178 + vertex 0.970883 2.09728 2.5593 + endloop + endfacet + facet normal -0.46683 0.38282 0.797194 + outer loop + vertex 0.975062 2.09337 2.56361 + vertex 0.97452 2.09652 2.56178 + vertex 0.970982 2.09216 2.5618 + endloop + endfacet + facet normal -0.460207 0.381439 0.801695 + outer loop + vertex 0.971004 2.10219 2.55698 + vertex 0.966264 2.10012 2.55524 + vertex 0.968113 2.09826 2.55719 + endloop + endfacet + facet normal -0.473567 0.378377 0.79534 + outer loop + vertex 0.968113 2.09826 2.55719 + vertex 0.966975 2.09434 2.55837 + vertex 0.970883 2.09728 2.5593 + endloop + endfacet + facet normal -0.469051 0.387504 0.79362 + outer loop + vertex 0.971004 2.10219 2.55698 + vertex 0.968113 2.09826 2.55719 + vertex 0.970883 2.09728 2.5593 + endloop + endfacet + facet normal -0.470409 0.387221 0.792954 + outer loop + vertex 0.971004 2.10219 2.55698 + vertex 0.970883 2.09728 2.5593 + vertex 0.974131 2.1003 2.55975 + endloop + endfacet + facet normal -0.468849 0.389513 0.792755 + outer loop + vertex 0.971004 2.10219 2.55698 + vertex 0.974131 2.1003 2.55975 + vertex 0.974733 2.10341 2.55859 + endloop + endfacet + facet normal -0.46469 0.380047 0.799767 + outer loop + vertex 0.974131 2.1003 2.55975 + vertex 0.970883 2.09728 2.5593 + vertex 0.97452 2.09652 2.56178 + endloop + endfacet + facet normal -0.459795 0.379541 0.802831 + outer loop + vertex 0.967859 2.10557 2.55358 + vertex 0.966264 2.10012 2.55524 + vertex 0.971004 2.10219 2.55698 + endloop + endfacet + facet normal -0.445008 0.394443 0.803979 + outer loop + vertex 0.972261 2.10674 2.55544 + vertex 0.967859 2.10557 2.55358 + vertex 0.971004 2.10219 2.55698 + endloop + endfacet + facet normal -0.460288 0.395561 0.794775 + outer loop + vertex 0.971004 2.10219 2.55698 + vertex 0.974807 2.10631 2.55713 + vertex 0.972261 2.10674 2.55544 + endloop + endfacet + facet normal -0.4702 0.4051 0.784096 + outer loop + vertex 0.974733 2.10341 2.55859 + vertex 0.974807 2.10631 2.55713 + vertex 0.971004 2.10219 2.55698 + endloop + endfacet + facet normal -0.445533 0.380694 0.810292 + outer loop + vertex 0.972261 2.10674 2.55544 + vertex 0.975051 2.10925 2.5558 + vertex 0.97321 2.11086 2.55403 + endloop + endfacet + facet normal -0.444327 0.380651 0.810974 + outer loop + vertex 0.972261 2.10674 2.55544 + vertex 0.97321 2.11086 2.55403 + vertex 0.967859 2.10557 2.55358 + endloop + endfacet + facet normal -0.439367 0.375193 0.816203 + outer loop + vertex 0.967859 2.10557 2.55358 + vertex 0.97321 2.11086 2.55403 + vertex 0.969207 2.11132 2.55166 + endloop + endfacet + facet normal -0.459311 0.398276 0.793984 + outer loop + vertex 0.975051 2.10925 2.5558 + vertex 0.972261 2.10674 2.55544 + vertex 0.974807 2.10631 2.55713 + endloop + endfacet + facet normal -0.45402 0.40284 0.794724 + outer loop + vertex 0.971932 2.11777 2.5501 + vertex 0.969741 2.11809 2.54869 + vertex 0.969504 2.11536 2.54993 + endloop + endfacet + facet normal -0.437026 0.384498 0.813124 + outer loop + vertex 0.969504 2.11536 2.54993 + vertex 0.973442 2.11568 2.5519 + vertex 0.971932 2.11777 2.5501 + endloop + endfacet + facet normal -0.437506 0.380548 0.814722 + outer loop + vertex 0.969504 2.11536 2.54993 + vertex 0.969207 2.11132 2.55166 + vertex 0.973442 2.11568 2.5519 + endloop + endfacet + facet normal -0.437725 0.380773 0.814499 + outer loop + vertex 0.969207 2.11132 2.55166 + vertex 0.97321 2.11086 2.55403 + vertex 0.973442 2.11568 2.5519 + endloop + endfacet + facet normal -0.42781 0.485839 0.762194 + outer loop + vertex 0.971932 2.11777 2.5501 + vertex 0.974191 2.11917 2.55048 + vertex 0.97178 2.1205 2.54828 + endloop + endfacet + facet normal -0.422218 0.487517 0.764237 + outer loop + vertex 0.971932 2.11777 2.5501 + vertex 0.97178 2.1205 2.54828 + vertex 0.969741 2.11809 2.54869 + endloop + endfacet + facet normal -0.441372 0.500414 0.744833 + outer loop + vertex 0.969741 2.11809 2.54869 + vertex 0.97178 2.1205 2.54828 + vertex 0.968642 2.11968 2.54697 + endloop + endfacet + facet normal -0.395423 0.418386 0.817676 + outer loop + vertex 0.974191 2.11917 2.55048 + vertex 0.971932 2.11777 2.5501 + vertex 0.973442 2.11568 2.5519 + endloop + endfacet + facet normal -0.418485 0.743841 0.521124 + outer loop + vertex 0.970421 2.1277 2.53939 + vertex 0.967013 2.12673 2.53804 + vertex 0.968547 2.12507 2.54164 + endloop + endfacet + facet normal -0.425316 0.743895 0.515486 + outer loop + vertex 0.972606 2.12637 2.54312 + vertex 0.970421 2.1277 2.53939 + vertex 0.968547 2.12507 2.54164 + endloop + endfacet + facet normal -0.433374 0.672449 0.6 + outer loop + vertex 0.972606 2.12637 2.54312 + vertex 0.968547 2.12507 2.54164 + vertex 0.972388 2.12381 2.54583 + endloop + endfacet + facet normal -0.444991 0.658853 0.606544 + outer loop + vertex 0.972388 2.12381 2.54583 + vertex 0.968547 2.12507 2.54164 + vertex 0.968787 2.12212 2.54502 + endloop + endfacet + facet normal -0.438262 0.575974 0.690059 + outer loop + vertex 0.97178 2.1205 2.54828 + vertex 0.968787 2.12212 2.54502 + vertex 0.968642 2.11968 2.54697 + endloop + endfacet + facet normal -0.429292 0.586313 0.686983 + outer loop + vertex 0.972388 2.12381 2.54583 + vertex 0.968787 2.12212 2.54502 + vertex 0.97178 2.1205 2.54828 + endloop + endfacet + facet normal -0.189507 0.244969 0.95083 + outer loop + vertex 0.971247 2.13275 2.53079 + vertex 0.970168 2.135 2.53 + vertex 0.97 2.13487 2.53 + endloop + endfacet + facet normal -0.0819357 0.307216 0.948106 + outer loop + vertex 0.967799 2.13032 2.53128 + vertex 0.971247 2.13275 2.53079 + vertex 0.97 2.13487 2.53 + endloop + endfacet + facet normal -0.468716 0.757382 0.454619 + outer loop + vertex 0.971855 2.13028 2.53554 + vertex 0.971247 2.13275 2.53079 + vertex 0.967799 2.13032 2.53128 + endloop + endfacet + facet normal -0.396877 0.832291 0.387015 + outer loop + vertex 0.967504 2.12829 2.53534 + vertex 0.971855 2.13028 2.53554 + vertex 0.967799 2.13032 2.53128 + endloop + endfacet + facet normal -0.395637 0.823803 0.405981 + outer loop + vertex 0.967504 2.12829 2.53534 + vertex 0.967013 2.12673 2.53804 + vertex 0.970421 2.1277 2.53939 + endloop + endfacet + facet normal -0.394305 0.824838 0.405173 + outer loop + vertex 0.971855 2.13028 2.53554 + vertex 0.967504 2.12829 2.53534 + vertex 0.970421 2.1277 2.53939 + endloop + endfacet + facet normal -0.346151 0.834168 0.429353 + outer loop + vertex 0.971855 2.13028 2.53554 + vertex 0.970421 2.1277 2.53939 + vertex 0.97519 2.12874 2.54122 + endloop + endfacet + facet normal -0.459825 0.751168 0.473612 + outer loop + vertex 0.971855 2.13028 2.53554 + vertex 0.97519 2.12874 2.54122 + vertex 0.974609 2.13049 2.53788 + endloop + endfacet + facet normal -0.361648 0.790227 0.494724 + outer loop + vertex 0.97519 2.12874 2.54122 + vertex 0.970421 2.1277 2.53939 + vertex 0.972606 2.12637 2.54312 + endloop + endfacet + facet normal -0.467225 0.547502 0.69422 + outer loop + vertex 0.975 2.13696 2.53 + vertex 0.971247 2.13275 2.53079 + vertex 0.974912 2.13302 2.53305 + endloop + endfacet + facet normal -0.114268 0.281701 0.952674 + outer loop + vertex 0.970168 2.135 2.53 + vertex 0.971247 2.13275 2.53079 + vertex 0.975 2.13696 2.53 + endloop + endfacet + facet normal -0.350425 0.813163 0.464724 + outer loop + vertex 0.974912 2.13302 2.53305 + vertex 0.971855 2.13028 2.53554 + vertex 0.975116 2.13147 2.53592 + endloop + endfacet + facet normal -0.347392 0.812653 0.467883 + outer loop + vertex 0.971247 2.13275 2.53079 + vertex 0.971855 2.13028 2.53554 + vertex 0.974912 2.13302 2.53305 + endloop + endfacet + facet normal -0.356724 0.869697 0.341138 + outer loop + vertex 0.975116 2.13147 2.53592 + vertex 0.971855 2.13028 2.53554 + vertex 0.974609 2.13049 2.53788 + endloop + endfacet + facet normal -0.280015 -0.928764 0.242876 + outer loop + vertex 0.975 0.89 2.5327 + vertex 0.98 0.889094 2.535 + vertex 0.976995 0.89 2.535 + endloop + endfacet + facet normal -0.283403 -0.925419 0.251559 + outer loop + vertex 0.975 0.89 2.5327 + vertex 0.975 0.889266 2.53 + vertex 0.98 0.889094 2.535 + endloop + endfacet + facet normal -0.226608 -0.954518 0.193764 + outer loop + vertex 0.975 0.889266 2.53 + vertex 0.98 0.888079 2.53 + vertex 0.98 0.889094 2.535 + endloop + endfacet + facet normal 0.269515 0.893939 -0.358099 + outer loop + vertex 0.98 0.889094 2.535 + vertex 0.979559 0.889095 2.53467 + vertex 0.976995 0.89 2.535 + endloop + endfacet + facet normal -0.261459 -0.882807 0.390245 + outer loop + vertex 0.976995 0.89 2.535 + vertex 0.979559 0.889095 2.53467 + vertex 0.978032 0.890383 2.53656 + endloop + endfacet + facet normal -0.41599 -0.779966 0.467552 + outer loop + vertex 0.976995 0.89 2.535 + vertex 0.978032 0.890383 2.53656 + vertex 0.975 0.891064 2.535 + endloop + endfacet + facet normal -0.363889 -0.872479 0.326138 + outer loop + vertex 0.975 0.891064 2.535 + vertex 0.978032 0.890383 2.53656 + vertex 0.974573 0.891967 2.53694 + endloop + endfacet + facet normal -0.359133 -0.844703 0.396863 + outer loop + vertex 0.974596 0.893159 2.53973 + vertex 0.978031 0.892179 2.54075 + vertex 0.976252 0.893688 2.54235 + endloop + endfacet + facet normal -0.355104 -0.858437 0.370117 + outer loop + vertex 0.974596 0.893159 2.53973 + vertex 0.974573 0.891967 2.53694 + vertex 0.978031 0.892179 2.54075 + endloop + endfacet + facet normal -0.353428 -0.859752 0.368668 + outer loop + vertex 0.974573 0.891967 2.53694 + vertex 0.978032 0.890383 2.53656 + vertex 0.978031 0.892179 2.54075 + endloop + endfacet + facet normal -0.356383 -0.844513 0.399737 + outer loop + vertex 0.978031 0.892179 2.54075 + vertex 0.978788 0.893396 2.54399 + vertex 0.976252 0.893688 2.54235 + endloop + endfacet + facet normal -0.45206 -0.775076 0.441473 + outer loop + vertex 0.974596 0.893159 2.53973 + vertex 0.976252 0.893688 2.54235 + vertex 0.972533 0.894966 2.54079 + endloop + endfacet + facet normal -0.430172 -0.727577 0.5344 + outer loop + vertex 0.976252 0.893688 2.54235 + vertex 0.978788 0.893396 2.54399 + vertex 0.977099 0.895415 2.54538 + endloop + endfacet + facet normal -0.466664 -0.706215 0.532434 + outer loop + vertex 0.976252 0.893688 2.54235 + vertex 0.977099 0.895415 2.54538 + vertex 0.972533 0.894966 2.54079 + endloop + endfacet + facet normal -0.432485 -0.748545 0.50263 + outer loop + vertex 0.972533 0.894966 2.54079 + vertex 0.977099 0.895415 2.54538 + vertex 0.971699 0.897525 2.54388 + endloop + endfacet + facet normal -0.430036 -0.666144 0.609361 + outer loop + vertex 0.977099 0.895415 2.54538 + vertex 0.973749 0.899146 2.5471 + vertex 0.971699 0.897525 2.54388 + endloop + endfacet + facet normal -0.412868 -0.659414 0.628262 + outer loop + vertex 0.978803 0.898013 2.54923 + vertex 0.973749 0.899146 2.5471 + vertex 0.977099 0.895415 2.54538 + endloop + endfacet + facet normal -0.443411 -0.481327 0.756116 + outer loop + vertex 0.978695 0.900806 2.55146 + vertex 0.975567 0.904108 2.55173 + vertex 0.973964 0.90248 2.54975 + endloop + endfacet + facet normal -0.449875 -0.56741 0.68968 + outer loop + vertex 0.978695 0.900806 2.55146 + vertex 0.973964 0.90248 2.54975 + vertex 0.978803 0.898013 2.54923 + endloop + endfacet + facet normal -0.426585 -0.545842 0.721167 + outer loop + vertex 0.978803 0.898013 2.54923 + vertex 0.973964 0.90248 2.54975 + vertex 0.973749 0.899146 2.5471 + endloop + endfacet + facet normal -0.434805 -0.473952 0.765711 + outer loop + vertex 0.978695 0.900806 2.55146 + vertex 0.979099 0.903813 2.55355 + vertex 0.975567 0.904108 2.55173 + endloop + endfacet + facet normal -0.458784 -0.466408 0.756294 + outer loop + vertex 0.973964 0.90248 2.54975 + vertex 0.975567 0.904108 2.55173 + vertex 0.972392 0.906163 2.55107 + endloop + endfacet + facet normal -0.435029 -0.41616 0.798474 + outer loop + vertex 0.975567 0.904108 2.55173 + vertex 0.973829 0.908026 2.55282 + vertex 0.972392 0.906163 2.55107 + endloop + endfacet + facet normal -0.443933 -0.418407 0.792376 + outer loop + vertex 0.975567 0.904108 2.55173 + vertex 0.979099 0.903813 2.55355 + vertex 0.973829 0.908026 2.55282 + endloop + endfacet + facet normal -0.449111 -0.426104 0.785324 + outer loop + vertex 0.979099 0.903813 2.55355 + vertex 0.977629 0.9079 2.55493 + vertex 0.973829 0.908026 2.55282 + endloop + endfacet + facet normal -0.45503 -0.371804 0.809141 + outer loop + vertex 0.978093 0.910611 2.55651 + vertex 0.975468 0.914091 2.55663 + vertex 0.973541 0.912442 2.55479 + endloop + endfacet + facet normal -0.458052 -0.38817 0.799695 + outer loop + vertex 0.978093 0.910611 2.55651 + vertex 0.973541 0.912442 2.55479 + vertex 0.977629 0.9079 2.55493 + endloop + endfacet + facet normal -0.456593 -0.386813 0.801185 + outer loop + vertex 0.977629 0.9079 2.55493 + vertex 0.973541 0.912442 2.55479 + vertex 0.973829 0.908026 2.55282 + endloop + endfacet + facet normal -0.462888 -0.377476 0.802027 + outer loop + vertex 0.978093 0.910611 2.55651 + vertex 0.979022 0.913747 2.55852 + vertex 0.975468 0.914091 2.55663 + endloop + endfacet + facet normal -0.453131 -0.374056 0.809169 + outer loop + vertex 0.973541 0.912442 2.55479 + vertex 0.975468 0.914091 2.55663 + vertex 0.972419 0.91627 2.55593 + endloop + endfacet + facet normal -0.457874 -0.382889 0.802339 + outer loop + vertex 0.975468 0.914091 2.55663 + vertex 0.974016 0.918106 2.55772 + vertex 0.972419 0.91627 2.55593 + endloop + endfacet + facet normal -0.46215 -0.38367 0.799509 + outer loop + vertex 0.975468 0.914091 2.55663 + vertex 0.979022 0.913747 2.55852 + vertex 0.974016 0.918106 2.55772 + endloop + endfacet + facet normal -0.461381 -0.382612 0.800459 + outer loop + vertex 0.979022 0.913747 2.55852 + vertex 0.977637 0.918214 2.55986 + vertex 0.974016 0.918106 2.55772 + endloop + endfacet + facet normal -0.458473 -0.377748 0.804431 + outer loop + vertex 0.977178 0.921166 2.56099 + vertex 0.97535 0.924044 2.5613 + vertex 0.973611 0.922608 2.55963 + endloop + endfacet + facet normal -0.458838 -0.379717 0.803295 + outer loop + vertex 0.977178 0.921166 2.56099 + vertex 0.973611 0.922608 2.55963 + vertex 0.977637 0.918214 2.55986 + endloop + endfacet + facet normal -0.461463 -0.38226 0.80058 + outer loop + vertex 0.977637 0.918214 2.55986 + vertex 0.973611 0.922608 2.55963 + vertex 0.974016 0.918106 2.55772 + endloop + endfacet + facet normal -0.443525 -0.36955 0.816528 + outer loop + vertex 0.977178 0.921166 2.56099 + vertex 0.978835 0.922776 2.56262 + vertex 0.97535 0.924044 2.5613 + endloop + endfacet + facet normal -0.457395 -0.379053 0.80443 + outer loop + vertex 0.973611 0.922608 2.55963 + vertex 0.97535 0.924044 2.5613 + vertex 0.972503 0.926333 2.56076 + endloop + endfacet + facet normal -0.462264 -0.38662 0.798021 + outer loop + vertex 0.97535 0.924044 2.5613 + vertex 0.974084 0.927922 2.56244 + vertex 0.972503 0.926333 2.56076 + endloop + endfacet + facet normal -0.445828 -0.384327 0.808412 + outer loop + vertex 0.97535 0.924044 2.5613 + vertex 0.978835 0.922776 2.56262 + vertex 0.974084 0.927922 2.56244 + endloop + endfacet + facet normal -0.440798 -0.379515 0.813428 + outer loop + vertex 0.978835 0.922776 2.56262 + vertex 0.9786 0.927405 2.56465 + vertex 0.974084 0.927922 2.56244 + endloop + endfacet + facet normal -0.432753 -0.376967 0.818914 + outer loop + vertex 0.977435 0.931371 2.56591 + vertex 0.975323 0.934433 2.5662 + vertex 0.973614 0.932638 2.56447 + endloop + endfacet + facet normal -0.433821 -0.385164 0.814523 + outer loop + vertex 0.977435 0.931371 2.56591 + vertex 0.973614 0.932638 2.56447 + vertex 0.9786 0.927405 2.56465 + endloop + endfacet + facet normal -0.439732 -0.391002 0.80855 + outer loop + vertex 0.9786 0.927405 2.56465 + vertex 0.973614 0.932638 2.56447 + vertex 0.974084 0.927922 2.56244 + endloop + endfacet + facet normal -0.337213 -0.317504 0.886272 + outer loop + vertex 0.977435 0.931371 2.56591 + vertex 0.979681 0.933818 2.56764 + vertex 0.975323 0.934433 2.5662 + endloop + endfacet + facet normal -0.433381 -0.376331 0.818875 + outer loop + vertex 0.973614 0.932638 2.56447 + vertex 0.975323 0.934433 2.5662 + vertex 0.972386 0.936515 2.5656 + endloop + endfacet + facet normal -0.422575 -0.357024 0.833045 + outer loop + vertex 0.975323 0.934433 2.5662 + vertex 0.974159 0.938272 2.56725 + vertex 0.972386 0.936515 2.5656 + endloop + endfacet + facet normal -0.337613 -0.343197 0.876489 + outer loop + vertex 0.975323 0.934433 2.5662 + vertex 0.979681 0.933818 2.56764 + vertex 0.974159 0.938272 2.56725 + endloop + endfacet + facet normal -0.35142 -0.361421 0.863643 + outer loop + vertex 0.979681 0.933818 2.56764 + vertex 0.978234 0.939021 2.56923 + vertex 0.974159 0.938272 2.56725 + endloop + endfacet + facet normal -0.344187 -0.391198 0.853522 + outer loop + vertex 0.977759 0.942409 2.5705 + vertex 0.975766 0.94504 2.5709 + vertex 0.973744 0.942904 2.5691 + endloop + endfacet + facet normal -0.344721 -0.371577 0.862031 + outer loop + vertex 0.977759 0.942409 2.5705 + vertex 0.973744 0.942904 2.5691 + vertex 0.978234 0.939021 2.56923 + endloop + endfacet + facet normal -0.347161 -0.37447 0.859797 + outer loop + vertex 0.978234 0.939021 2.56923 + vertex 0.973744 0.942904 2.5691 + vertex 0.974159 0.938272 2.56725 + endloop + endfacet + facet normal -0.232045 -0.316365 0.91982 + outer loop + vertex 0.977759 0.942409 2.5705 + vertex 0.979844 0.945376 2.57204 + vertex 0.975766 0.94504 2.5709 + endloop + endfacet + facet normal -0.361969 -0.374483 0.853663 + outer loop + vertex 0.973744 0.942904 2.5691 + vertex 0.975766 0.94504 2.5709 + vertex 0.972687 0.946642 2.5703 + endloop + endfacet + facet normal -0.344746 -0.332274 0.87792 + outer loop + vertex 0.975766 0.94504 2.5709 + vertex 0.975158 0.949145 2.57221 + vertex 0.972687 0.946642 2.5703 + endloop + endfacet + facet normal -0.230144 -0.32761 0.916355 + outer loop + vertex 0.975766 0.94504 2.5709 + vertex 0.979844 0.945376 2.57204 + vertex 0.975158 0.949145 2.57221 + endloop + endfacet + facet normal -0.222458 -0.318284 0.921525 + outer loop + vertex 0.979844 0.945376 2.57204 + vertex 0.979864 0.94937 2.57343 + vertex 0.975158 0.949145 2.57221 + endloop + endfacet + facet normal -0.21956 -0.340191 0.914365 + outer loop + vertex 0.979864 0.94937 2.57343 + vertex 0.977648 0.953101 2.57428 + vertex 0.975158 0.949145 2.57221 + endloop + endfacet + facet normal -0.21656 -0.342084 0.914374 + outer loop + vertex 0.975158 0.949145 2.57221 + vertex 0.977648 0.953101 2.57428 + vertex 0.974093 0.952856 2.57335 + endloop + endfacet + facet normal -0.233216 -0.363591 0.901893 + outer loop + vertex 0.977367 0.956973 2.57558 + vertex 0.975315 0.959683 2.57615 + vertex 0.972897 0.956968 2.57443 + endloop + endfacet + facet normal -0.236796 -0.325063 0.915566 + outer loop + vertex 0.977367 0.956973 2.57558 + vertex 0.972897 0.956968 2.57443 + vertex 0.977648 0.953101 2.57428 + endloop + endfacet + facet normal -0.221878 -0.307105 0.92545 + outer loop + vertex 0.977648 0.953101 2.57428 + vertex 0.972897 0.956968 2.57443 + vertex 0.974093 0.952856 2.57335 + endloop + endfacet + facet normal -0.13124 -0.2956 0.946254 + outer loop + vertex 0.977367 0.956973 2.57558 + vertex 0.979626 0.960435 2.57698 + vertex 0.975315 0.959683 2.57615 + endloop + endfacet + facet normal -0.246822 -0.352076 0.902841 + outer loop + vertex 0.972897 0.956968 2.57443 + vertex 0.975315 0.959683 2.57615 + vertex 0.972227 0.961257 2.57592 + endloop + endfacet + facet normal -0.225806 -0.307692 0.924304 + outer loop + vertex 0.975315 0.959683 2.57615 + vertex 0.974682 0.96413 2.57747 + vertex 0.972227 0.961257 2.57592 + endloop + endfacet + facet normal -0.13018 -0.300226 0.944943 + outer loop + vertex 0.975315 0.959683 2.57615 + vertex 0.979626 0.960435 2.57698 + vertex 0.974682 0.96413 2.57747 + endloop + endfacet + facet normal -0.12636 -0.295387 0.946985 + outer loop + vertex 0.979626 0.960435 2.57698 + vertex 0.979674 0.964661 2.5783 + vertex 0.974682 0.96413 2.57747 + endloop + endfacet + facet normal -0.122125 -0.322271 0.938737 + outer loop + vertex 0.979674 0.964661 2.5783 + vertex 0.977447 0.968218 2.57924 + vertex 0.974682 0.96413 2.57747 + endloop + endfacet + facet normal -0.133008 -0.315294 0.939627 + outer loop + vertex 0.974682 0.96413 2.57747 + vertex 0.977447 0.968218 2.57924 + vertex 0.973691 0.967808 2.57857 + endloop + endfacet + facet normal -0.134879 -0.323183 0.936675 + outer loop + vertex 0.977312 0.971943 2.58043 + vertex 0.975428 0.974319 2.58098 + vertex 0.973306 0.97121 2.5796 + endloop + endfacet + facet normal -0.138764 -0.307333 0.94143 + outer loop + vertex 0.977312 0.971943 2.58043 + vertex 0.973306 0.97121 2.5796 + vertex 0.977447 0.968218 2.57924 + endloop + endfacet + facet normal -0.135099 -0.302515 0.943522 + outer loop + vertex 0.977447 0.968218 2.57924 + vertex 0.973306 0.97121 2.5796 + vertex 0.973691 0.967808 2.57857 + endloop + endfacet + facet normal -0.0602012 -0.269615 0.961085 + outer loop + vertex 0.977312 0.971943 2.58043 + vertex 0.979698 0.975539 2.58159 + vertex 0.975428 0.974319 2.58098 + endloop + endfacet + facet normal -0.166222 -0.302603 0.93851 + outer loop + vertex 0.973306 0.97121 2.5796 + vertex 0.975428 0.974319 2.58098 + vertex 0.971834 0.97554 2.58074 + endloop + endfacet + facet normal -0.154269 -0.264752 0.951897 + outer loop + vertex 0.975428 0.974319 2.58098 + vertex 0.975687 0.978512 2.58219 + vertex 0.971834 0.97554 2.58074 + endloop + endfacet + facet normal -0.059104 -0.27301 0.960194 + outer loop + vertex 0.975428 0.974319 2.58098 + vertex 0.979698 0.975539 2.58159 + vertex 0.975687 0.978512 2.58219 + endloop + endfacet + facet normal -0.0511505 -0.262937 0.963456 + outer loop + vertex 0.979698 0.975539 2.58159 + vertex 0.980263 0.979731 2.58276 + vertex 0.975687 0.978512 2.58219 + endloop + endfacet + facet normal -0.0494043 -0.268775 0.961935 + outer loop + vertex 0.980263 0.979731 2.58276 + vertex 0.978855 0.98304 2.58362 + vertex 0.975687 0.978512 2.58219 + endloop + endfacet + facet normal -0.0619047 -0.260518 0.963482 + outer loop + vertex 0.975687 0.978512 2.58219 + vertex 0.978855 0.98304 2.58362 + vertex 0.973878 0.983225 2.58335 + endloop + endfacet + facet normal -0.0622256 -0.275067 0.959409 + outer loop + vertex 0.978855 0.98304 2.58362 + vertex 0.977474 0.987069 2.58468 + vertex 0.973878 0.983225 2.58335 + endloop + endfacet + facet normal -0.0687296 -0.269389 0.960576 + outer loop + vertex 0.973878 0.983225 2.58335 + vertex 0.977474 0.987069 2.58468 + vertex 0.972132 0.987814 2.58451 + endloop + endfacet + facet normal -0.07015 -0.280328 0.957338 + outer loop + vertex 0.972132 0.987814 2.58451 + vertex 0.977474 0.987069 2.58468 + vertex 0.976242 0.991077 2.58576 + endloop + endfacet + facet normal -0.0559869 -0.296638 0.953347 + outer loop + vertex 0.972237 0.991655 2.58571 + vertex 0.972132 0.987814 2.58451 + vertex 0.976242 0.991077 2.58576 + endloop + endfacet + facet normal -0.0519225 -0.267643 0.962118 + outer loop + vertex 0.976242 0.991077 2.58576 + vertex 0.974681 0.995311 2.58686 + vertex 0.972237 0.991655 2.58571 + endloop + endfacet + facet normal -0.00431157 -0.251562 0.967832 + outer loop + vertex 0.979956 0.994805 2.58675 + vertex 0.974681 0.995311 2.58686 + vertex 0.976242 0.991077 2.58576 + endloop + endfacet + facet normal -0.00403588 -0.248838 0.968537 + outer loop + vertex 0.979956 0.994805 2.58675 + vertex 0.979184 0.998985 2.58782 + vertex 0.974681 0.995311 2.58686 + endloop + endfacet + facet normal 0.00299255 -0.256901 0.966433 + outer loop + vertex 0.974681 0.995311 2.58686 + vertex 0.979184 0.998985 2.58782 + vertex 0.975211 0.99959 2.58799 + endloop + endfacet + facet normal 0.0047138 -0.246376 0.969163 + outer loop + vertex 0.979184 0.998985 2.58782 + vertex 0.978542 1.00308 2.58887 + vertex 0.975211 0.99959 2.58799 + endloop + endfacet + facet normal -0.00402264 -0.238528 0.971127 + outer loop + vertex 0.975211 0.99959 2.58799 + vertex 0.978542 1.00308 2.58887 + vertex 0.97379 1.00293 2.58881 + endloop + endfacet + facet normal -0.00359129 -0.251256 0.967914 + outer loop + vertex 0.978542 1.00308 2.58887 + vertex 0.977485 1.00693 2.58986 + vertex 0.97379 1.00293 2.58881 + endloop + endfacet + facet normal -0.008224 -0.247242 0.968919 + outer loop + vertex 0.97379 1.00293 2.58881 + vertex 0.977485 1.00693 2.58986 + vertex 0.972446 1.00697 2.58983 + endloop + endfacet + facet normal 0.0540649 0.138076 0.988945 + outer loop + vertex 0.980536 1.81508 2.6259 + vertex 0.97892 1.81939 2.62538 + vertex 0.976487 1.81622 2.62596 + endloop + endfacet + facet normal 0.0550643 0.137318 0.988995 + outer loop + vertex 0.974339 1.8187 2.62573 + vertex 0.976487 1.81622 2.62596 + vertex 0.97892 1.81939 2.62538 + endloop + endfacet + facet normal -0.229948 0.316841 0.920182 + outer loop + vertex 0.973088 2.06631 2.57349 + vertex 0.977655 2.07105 2.573 + vertex 0.972902 2.0706 2.57197 + endloop + endfacet + facet normal -0.341215 0.401615 0.849869 + outer loop + vertex 0.976537 2.07727 2.57069 + vertex 0.972741 2.07635 2.5696 + vertex 0.974069 2.07434 2.57109 + endloop + endfacet + facet normal -0.235757 0.322032 0.916905 + outer loop + vertex 0.974069 2.07434 2.57109 + vertex 0.97722 2.07474 2.57175 + vertex 0.976537 2.07727 2.57069 + endloop + endfacet + facet normal -0.234055 0.291137 0.927609 + outer loop + vertex 0.974069 2.07434 2.57109 + vertex 0.972902 2.0706 2.57197 + vertex 0.97722 2.07474 2.57175 + endloop + endfacet + facet normal -0.22921 0.28623 0.930342 + outer loop + vertex 0.972902 2.0706 2.57197 + vertex 0.977655 2.07105 2.573 + vertex 0.97722 2.07474 2.57175 + endloop + endfacet + facet normal -0.201035 0.358639 0.911572 + outer loop + vertex 0.976537 2.07727 2.57069 + vertex 0.98052 2.07882 2.57096 + vertex 0.978318 2.08149 2.56942 + endloop + endfacet + facet normal -0.341022 0.399602 0.850895 + outer loop + vertex 0.976537 2.07727 2.57069 + vertex 0.978318 2.08149 2.56942 + vertex 0.972741 2.07635 2.5696 + endloop + endfacet + facet normal -0.319901 0.37728 0.869093 + outer loop + vertex 0.972741 2.07635 2.5696 + vertex 0.978318 2.08149 2.56942 + vertex 0.973008 2.08135 2.56753 + endloop + endfacet + facet normal -0.192836 0.335758 0.921998 + outer loop + vertex 0.98052 2.07882 2.57096 + vertex 0.976537 2.07727 2.57069 + vertex 0.97722 2.07474 2.57175 + endloop + endfacet + facet normal -0.32533 0.32464 0.888127 + outer loop + vertex 0.978318 2.08149 2.56942 + vertex 0.978215 2.08616 2.56768 + vertex 0.973008 2.08135 2.56753 + endloop + endfacet + facet normal -0.327483 0.327021 0.88646 + outer loop + vertex 0.973008 2.08135 2.56753 + vertex 0.978215 2.08616 2.56768 + vertex 0.974152 2.08639 2.56609 + endloop + endfacet + facet normal -0.411172 0.367598 0.834152 + outer loop + vertex 0.977213 2.09248 2.56506 + vertex 0.975062 2.09337 2.56361 + vertex 0.974357 2.09021 2.56465 + endloop + endfacet + facet normal -0.375304 0.31581 0.871442 + outer loop + vertex 0.974357 2.09021 2.56465 + vertex 0.977838 2.08988 2.56627 + vertex 0.977213 2.09248 2.56506 + endloop + endfacet + facet normal -0.368713 0.34509 0.863113 + outer loop + vertex 0.974357 2.09021 2.56465 + vertex 0.974152 2.08639 2.56609 + vertex 0.977838 2.08988 2.56627 + endloop + endfacet + facet normal -0.331346 0.304153 0.893141 + outer loop + vertex 0.974152 2.08639 2.56609 + vertex 0.978215 2.08616 2.56768 + vertex 0.977838 2.08988 2.56627 + endloop + endfacet + facet normal -0.296174 0.388271 0.872655 + outer loop + vertex 0.977213 2.09248 2.56506 + vertex 0.980607 2.09354 2.56574 + vertex 0.978716 2.09626 2.56389 + endloop + endfacet + facet normal -0.387676 0.410052 0.825569 + outer loop + vertex 0.977213 2.09248 2.56506 + vertex 0.978716 2.09626 2.56389 + vertex 0.975062 2.09337 2.56361 + endloop + endfacet + facet normal -0.388982 0.411853 0.824057 + outer loop + vertex 0.975062 2.09337 2.56361 + vertex 0.978716 2.09626 2.56389 + vertex 0.97452 2.09652 2.56178 + endloop + endfacet + facet normal -0.287242 0.346989 0.892799 + outer loop + vertex 0.980607 2.09354 2.56574 + vertex 0.977213 2.09248 2.56506 + vertex 0.977838 2.08988 2.56627 + endloop + endfacet + facet normal -0.464746 0.389609 0.795121 + outer loop + vertex 0.976635 2.10274 2.56002 + vertex 0.974733 2.10341 2.55859 + vertex 0.974131 2.1003 2.55975 + endloop + endfacet + facet normal -0.430342 0.35033 0.83191 + outer loop + vertex 0.974131 2.1003 2.55975 + vertex 0.978138 2.10061 2.5617 + vertex 0.976635 2.10274 2.56002 + endloop + endfacet + facet normal -0.425553 0.392438 0.815412 + outer loop + vertex 0.974131 2.1003 2.55975 + vertex 0.97452 2.09652 2.56178 + vertex 0.978138 2.10061 2.5617 + endloop + endfacet + facet normal -0.399208 0.369562 0.839081 + outer loop + vertex 0.97452 2.09652 2.56178 + vertex 0.978716 2.09626 2.56389 + vertex 0.978138 2.10061 2.5617 + endloop + endfacet + facet normal -0.428376 0.397962 0.811246 + outer loop + vertex 0.976635 2.10274 2.56002 + vertex 0.97913 2.10408 2.56069 + vertex 0.978191 2.10634 2.55908 + endloop + endfacet + facet normal -0.45687 0.40523 0.79187 + outer loop + vertex 0.976635 2.10274 2.56002 + vertex 0.978191 2.10634 2.55908 + vertex 0.974733 2.10341 2.55859 + endloop + endfacet + facet normal -0.458562 0.407597 0.789674 + outer loop + vertex 0.974733 2.10341 2.55859 + vertex 0.978191 2.10634 2.55908 + vertex 0.974807 2.10631 2.55713 + endloop + endfacet + facet normal -0.415573 0.362514 0.834196 + outer loop + vertex 0.97913 2.10408 2.56069 + vertex 0.976635 2.10274 2.56002 + vertex 0.978138 2.10061 2.5617 + endloop + endfacet + facet normal -0.448244 0.377567 0.81026 + outer loop + vertex 0.976876 2.11215 2.55545 + vertex 0.97321 2.11086 2.55403 + vertex 0.975051 2.10925 2.5558 + endloop + endfacet + facet normal -0.45552 0.381439 0.804367 + outer loop + vertex 0.975051 2.10925 2.5558 + vertex 0.978662 2.11071 2.55715 + vertex 0.976876 2.11215 2.55545 + endloop + endfacet + facet normal -0.458595 0.398381 0.794345 + outer loop + vertex 0.975051 2.10925 2.5558 + vertex 0.974807 2.10631 2.55713 + vertex 0.978662 2.11071 2.55715 + endloop + endfacet + facet normal -0.460229 0.399821 0.792674 + outer loop + vertex 0.974807 2.10631 2.55713 + vertex 0.978191 2.10634 2.55908 + vertex 0.978662 2.11071 2.55715 + endloop + endfacet + facet normal -0.460744 0.392258 0.796146 + outer loop + vertex 0.976876 2.11215 2.55545 + vertex 0.979693 2.11437 2.55599 + vertex 0.977757 2.1158 2.55416 + endloop + endfacet + facet normal -0.450205 0.391896 0.80233 + outer loop + vertex 0.976876 2.11215 2.55545 + vertex 0.977757 2.1158 2.55416 + vertex 0.97321 2.11086 2.55403 + endloop + endfacet + facet normal -0.438372 0.380672 0.814198 + outer loop + vertex 0.97321 2.11086 2.55403 + vertex 0.977757 2.1158 2.55416 + vertex 0.973442 2.11568 2.5519 + endloop + endfacet + facet normal -0.454635 0.382516 0.804356 + outer loop + vertex 0.979693 2.11437 2.55599 + vertex 0.976876 2.11215 2.55545 + vertex 0.978662 2.11071 2.55715 + endloop + endfacet + facet normal -0.399747 0.522163 0.753358 + outer loop + vertex 0.975407 2.12215 2.54905 + vertex 0.97178 2.1205 2.54828 + vertex 0.974191 2.11917 2.55048 + endloop + endfacet + facet normal -0.395652 0.521682 0.755848 + outer loop + vertex 0.974191 2.11917 2.55048 + vertex 0.977162 2.11955 2.55177 + vertex 0.975407 2.12215 2.54905 + endloop + endfacet + facet normal -0.406922 0.418517 0.811947 + outer loop + vertex 0.974191 2.11917 2.55048 + vertex 0.973442 2.11568 2.5519 + vertex 0.977162 2.11955 2.55177 + endloop + endfacet + facet normal -0.427761 0.437824 0.790779 + outer loop + vertex 0.973442 2.11568 2.5519 + vertex 0.977757 2.1158 2.55416 + vertex 0.977162 2.11955 2.55177 + endloop + endfacet + facet normal -0.395609 0.683491 0.61346 + outer loop + vertex 0.976289 2.12561 2.54633 + vertex 0.972606 2.12637 2.54312 + vertex 0.972388 2.12381 2.54583 + endloop + endfacet + facet normal -0.416979 0.588347 0.692803 + outer loop + vertex 0.972388 2.12381 2.54583 + vertex 0.97178 2.1205 2.54828 + vertex 0.975407 2.12215 2.54905 + endloop + endfacet + facet normal -0.378943 0.629528 0.678305 + outer loop + vertex 0.976289 2.12561 2.54633 + vertex 0.972388 2.12381 2.54583 + vertex 0.975407 2.12215 2.54905 + endloop + endfacet + facet normal -0.40569 0.62638 0.66563 + outer loop + vertex 0.976289 2.12561 2.54633 + vertex 0.975407 2.12215 2.54905 + vertex 0.979364 2.12354 2.55016 + endloop + endfacet + facet normal -0.417607 0.614872 0.668982 + outer loop + vertex 0.976289 2.12561 2.54633 + vertex 0.979364 2.12354 2.55016 + vertex 0.979264 2.12587 2.54796 + endloop + endfacet + facet normal -0.394365 0.522594 0.755891 + outer loop + vertex 0.979364 2.12354 2.55016 + vertex 0.975407 2.12215 2.54905 + vertex 0.977162 2.11955 2.55177 + endloop + endfacet + facet normal -0.247174 0.842712 0.478269 + outer loop + vertex 0.97519 2.12874 2.54122 + vertex 0.980206 2.12964 2.54222 + vertex 0.977262 2.13089 2.53851 + endloop + endfacet + facet normal -0.240134 0.842004 0.48308 + outer loop + vertex 0.974609 2.13049 2.53788 + vertex 0.97519 2.12874 2.54122 + vertex 0.977262 2.13089 2.53851 + endloop + endfacet + facet normal -0.315019 0.778243 0.543232 + outer loop + vertex 0.976289 2.12561 2.54633 + vertex 0.97519 2.12874 2.54122 + vertex 0.972606 2.12637 2.54312 + endloop + endfacet + facet normal -0.355121 0.761798 0.541805 + outer loop + vertex 0.976289 2.12561 2.54633 + vertex 0.979404 2.12752 2.5457 + vertex 0.97519 2.12874 2.54122 + endloop + endfacet + facet normal -0.245747 0.851471 0.463255 + outer loop + vertex 0.979404 2.12752 2.5457 + vertex 0.980206 2.12964 2.54222 + vertex 0.97519 2.12874 2.54122 + endloop + endfacet + facet normal -0.357907 0.764479 0.536167 + outer loop + vertex 0.979404 2.12752 2.5457 + vertex 0.976289 2.12561 2.54633 + vertex 0.979264 2.12587 2.54796 + endloop + endfacet + facet normal -0.121994 0.983997 0.129873 + outer loop + vertex 0.98 2.13758 2.53 + vertex 0.975 2.13696 2.53 + vertex 0.98 2.13692 2.535 + endloop + endfacet + facet normal -0.613805 0.491585 0.617728 + outer loop + vertex 0.98 2.13692 2.535 + vertex 0.975 2.13696 2.53 + vertex 0.974912 2.13302 2.53305 + endloop + endfacet + facet normal -0.532825 0.299086 0.791609 + outer loop + vertex 0.98 2.13692 2.535 + vertex 0.974912 2.13302 2.53305 + vertex 0.978455 2.13271 2.53555 + endloop + endfacet + facet normal -0.261406 0.841105 0.473508 + outer loop + vertex 0.978455 2.13271 2.53555 + vertex 0.974912 2.13302 2.53305 + vertex 0.975116 2.13147 2.53592 + endloop + endfacet + facet normal -0.225198 0.894017 0.387324 + outer loop + vertex 0.977262 2.13089 2.53851 + vertex 0.975116 2.13147 2.53592 + vertex 0.974609 2.13049 2.53788 + endloop + endfacet + facet normal -0.275487 0.863612 0.422234 + outer loop + vertex 0.978455 2.13271 2.53555 + vertex 0.975116 2.13147 2.53592 + vertex 0.977262 2.13089 2.53851 + endloop + endfacet + facet normal -0.162034 -0.931051 0.326938 + outer loop + vertex 0.979559 0.889095 2.53467 + vertex 0.982845 0.888622 2.53495 + vertex 0.981495 0.889453 2.53665 + endloop + endfacet + facet normal 0.156768 0.965716 -0.206923 + outer loop + vertex 0.979559 0.889095 2.53467 + vertex 0.98 0.889094 2.535 + vertex 0.982845 0.888622 2.53495 + endloop + endfacet + facet normal 0.153901 0.88148 0.446438 + outer loop + vertex 0.98 0.889094 2.535 + vertex 0.985 0.888221 2.535 + vertex 0.982845 0.888622 2.53495 + endloop + endfacet + facet normal -0.0882023 -0.920564 0.380502 + outer loop + vertex 0.982845 0.888622 2.53495 + vertex 0.985259 0.889511 2.53766 + vertex 0.981495 0.889453 2.53665 + endloop + endfacet + facet normal -0.24713 -0.881995 0.401263 + outer loop + vertex 0.979559 0.889095 2.53467 + vertex 0.981495 0.889453 2.53665 + vertex 0.978032 0.890383 2.53656 + endloop + endfacet + facet normal -0.0881927 -0.92058 0.380467 + outer loop + vertex 0.981495 0.889453 2.53665 + vertex 0.985259 0.889511 2.53766 + vertex 0.982778 0.890914 2.54048 + endloop + endfacet + facet normal -0.245762 -0.875495 0.416064 + outer loop + vertex 0.981495 0.889453 2.53665 + vertex 0.982778 0.890914 2.54048 + vertex 0.978032 0.890383 2.53656 + endloop + endfacet + facet normal -0.217438 -0.89707 0.38469 + outer loop + vertex 0.978032 0.890383 2.53656 + vertex 0.982778 0.890914 2.54048 + vertex 0.978031 0.892179 2.54075 + endloop + endfacet + facet normal -0.250016 -0.859803 0.445231 + outer loop + vertex 0.978788 0.893396 2.54399 + vertex 0.981683 0.892714 2.5443 + vertex 0.980365 0.893829 2.54572 + endloop + endfacet + facet normal -0.25032 -0.885902 0.390535 + outer loop + vertex 0.978788 0.893396 2.54399 + vertex 0.978031 0.892179 2.54075 + vertex 0.981683 0.892714 2.5443 + endloop + endfacet + facet normal -0.22081 -0.905199 0.363122 + outer loop + vertex 0.978031 0.892179 2.54075 + vertex 0.982778 0.890914 2.54048 + vertex 0.981683 0.892714 2.5443 + endloop + endfacet + facet normal -0.156689 -0.841151 0.517604 + outer loop + vertex 0.981683 0.892714 2.5443 + vertex 0.983252 0.894649 2.54792 + vertex 0.980365 0.893829 2.54572 + endloop + endfacet + facet normal -0.408207 -0.724065 0.555965 + outer loop + vertex 0.978788 0.893396 2.54399 + vertex 0.980365 0.893829 2.54572 + vertex 0.977099 0.895415 2.54538 + endloop + endfacet + facet normal -0.388941 -0.688928 0.61164 + outer loop + vertex 0.982981 0.897035 2.55079 + vertex 0.981074 0.898489 2.55121 + vertex 0.978803 0.898013 2.54923 + endloop + endfacet + facet normal -0.382402 -0.727275 0.569947 + outer loop + vertex 0.983252 0.894649 2.54792 + vertex 0.982981 0.897035 2.55079 + vertex 0.978803 0.898013 2.54923 + endloop + endfacet + facet normal -0.345215 -0.699695 0.625503 + outer loop + vertex 0.983252 0.894649 2.54792 + vertex 0.978803 0.898013 2.54923 + vertex 0.977099 0.895415 2.54538 + endloop + endfacet + facet normal -0.366508 -0.607095 0.705059 + outer loop + vertex 0.983252 0.894649 2.54792 + vertex 0.977099 0.895415 2.54538 + vertex 0.980365 0.893829 2.54572 + endloop + endfacet + facet normal -0.314364 -0.621968 0.717169 + outer loop + vertex 0.982981 0.897035 2.55079 + vertex 0.983521 0.899395 2.55307 + vertex 0.981074 0.898489 2.55121 + endloop + endfacet + facet normal -0.474764 -0.559895 0.679056 + outer loop + vertex 0.978803 0.898013 2.54923 + vertex 0.981074 0.898489 2.55121 + vertex 0.978695 0.900806 2.55146 + endloop + endfacet + facet normal -0.439326 -0.45359 0.775402 + outer loop + vertex 0.983244 0.902414 2.55508 + vertex 0.98135 0.905555 2.55584 + vertex 0.979099 0.903813 2.55355 + endloop + endfacet + facet normal -0.444967 -0.524192 0.726104 + outer loop + vertex 0.983521 0.899395 2.55307 + vertex 0.983244 0.902414 2.55508 + vertex 0.979099 0.903813 2.55355 + endloop + endfacet + facet normal -0.401269 -0.485915 0.776447 + outer loop + vertex 0.983521 0.899395 2.55307 + vertex 0.979099 0.903813 2.55355 + vertex 0.978695 0.900806 2.55146 + endloop + endfacet + facet normal -0.401885 -0.494861 0.770455 + outer loop + vertex 0.983521 0.899395 2.55307 + vertex 0.978695 0.900806 2.55146 + vertex 0.981074 0.898489 2.55121 + endloop + endfacet + facet normal -0.401258 -0.437747 0.804593 + outer loop + vertex 0.983244 0.902414 2.55508 + vertex 0.985448 0.903989 2.55703 + vertex 0.98135 0.905555 2.55584 + endloop + endfacet + facet normal -0.461256 -0.427782 0.777332 + outer loop + vertex 0.977629 0.9079 2.55493 + vertex 0.979099 0.903813 2.55355 + vertex 0.98135 0.905555 2.55584 + endloop + endfacet + facet normal -0.457996 -0.420252 0.783344 + outer loop + vertex 0.979966 0.907955 2.55632 + vertex 0.977629 0.9079 2.55493 + vertex 0.98135 0.905555 2.55584 + endloop + endfacet + facet normal -0.412031 -0.400696 0.818336 + outer loop + vertex 0.98135 0.905555 2.55584 + vertex 0.982815 0.908627 2.55808 + vertex 0.979966 0.907955 2.55632 + endloop + endfacet + facet normal -0.395795 -0.410673 0.821397 + outer loop + vertex 0.985448 0.903989 2.55703 + vertex 0.982815 0.908627 2.55808 + vertex 0.98135 0.905555 2.55584 + endloop + endfacet + facet normal -0.466617 -0.38477 0.796379 + outer loop + vertex 0.977629 0.9079 2.55493 + vertex 0.979966 0.907955 2.55632 + vertex 0.978093 0.910611 2.55651 + endloop + endfacet + facet normal -0.433623 -0.388342 0.813118 + outer loop + vertex 0.983144 0.912364 2.56006 + vertex 0.981419 0.915817 2.56079 + vertex 0.979022 0.913747 2.55852 + endloop + endfacet + facet normal -0.433883 -0.390333 0.812026 + outer loop + vertex 0.982815 0.908627 2.55808 + vertex 0.983144 0.912364 2.56006 + vertex 0.979022 0.913747 2.55852 + endloop + endfacet + facet normal -0.435304 -0.391282 0.810807 + outer loop + vertex 0.982815 0.908627 2.55808 + vertex 0.979022 0.913747 2.55852 + vertex 0.978093 0.910611 2.55651 + endloop + endfacet + facet normal -0.42819 -0.359944 0.828911 + outer loop + vertex 0.982815 0.908627 2.55808 + vertex 0.978093 0.910611 2.55651 + vertex 0.979966 0.907955 2.55632 + endloop + endfacet + facet normal -0.349523 -0.357531 0.866028 + outer loop + vertex 0.983144 0.912364 2.56006 + vertex 0.985427 0.914535 2.56187 + vertex 0.981419 0.915817 2.56079 + endloop + endfacet + facet normal -0.440832 -0.380044 0.813163 + outer loop + vertex 0.977637 0.918214 2.55986 + vertex 0.979022 0.913747 2.55852 + vertex 0.981419 0.915817 2.56079 + endloop + endfacet + facet normal -0.445028 -0.389256 0.806493 + outer loop + vertex 0.979738 0.919068 2.56143 + vertex 0.977637 0.918214 2.55986 + vertex 0.981419 0.915817 2.56079 + endloop + endfacet + facet normal -0.381293 -0.364753 0.849453 + outer loop + vertex 0.981419 0.915817 2.56079 + vertex 0.982857 0.91858 2.56262 + vertex 0.979738 0.919068 2.56143 + endloop + endfacet + facet normal -0.353973 -0.381829 0.853762 + outer loop + vertex 0.985427 0.914535 2.56187 + vertex 0.982857 0.91858 2.56262 + vertex 0.981419 0.915817 2.56079 + endloop + endfacet + facet normal -0.449924 -0.380178 0.808105 + outer loop + vertex 0.977637 0.918214 2.55986 + vertex 0.979738 0.919068 2.56143 + vertex 0.977178 0.921166 2.56099 + endloop + endfacet + facet normal -0.443065 -0.370048 0.816552 + outer loop + vertex 0.979738 0.919068 2.56143 + vertex 0.978835 0.922776 2.56262 + vertex 0.977178 0.921166 2.56099 + endloop + endfacet + facet normal -0.381288 -0.365473 0.849146 + outer loop + vertex 0.979738 0.919068 2.56143 + vertex 0.982857 0.91858 2.56262 + vertex 0.978835 0.922776 2.56262 + endloop + endfacet + facet normal -0.370679 -0.355304 0.858112 + outer loop + vertex 0.982857 0.91858 2.56262 + vertex 0.983404 0.92266 2.56454 + vertex 0.978835 0.922776 2.56262 + endloop + endfacet + facet normal -0.355559 -0.379461 0.854159 + outer loop + vertex 0.982561 0.926432 2.56587 + vertex 0.980548 0.929398 2.56635 + vertex 0.9786 0.927405 2.56465 + endloop + endfacet + facet normal -0.355531 -0.379171 0.854299 + outer loop + vertex 0.982561 0.926432 2.56587 + vertex 0.9786 0.927405 2.56465 + vertex 0.983404 0.92266 2.56454 + endloop + endfacet + facet normal -0.366067 -0.38963 0.845094 + outer loop + vertex 0.983404 0.92266 2.56454 + vertex 0.9786 0.927405 2.56465 + vertex 0.978835 0.922776 2.56262 + endloop + endfacet + facet normal -0.225667 -0.302917 0.925913 + outer loop + vertex 0.982561 0.926432 2.56587 + vertex 0.984977 0.929192 2.56736 + vertex 0.980548 0.929398 2.56635 + endloop + endfacet + facet normal -0.359306 -0.375832 0.854196 + outer loop + vertex 0.9786 0.927405 2.56465 + vertex 0.980548 0.929398 2.56635 + vertex 0.977435 0.931371 2.56591 + endloop + endfacet + facet normal -0.330763 -0.323586 0.886503 + outer loop + vertex 0.980548 0.929398 2.56635 + vertex 0.979681 0.933818 2.56764 + vertex 0.977435 0.931371 2.56591 + endloop + endfacet + facet normal -0.225371 -0.313417 0.922484 + outer loop + vertex 0.980548 0.929398 2.56635 + vertex 0.984977 0.929192 2.56736 + vertex 0.979681 0.933818 2.56764 + endloop + endfacet + facet normal -0.227862 -0.316176 0.92093 + outer loop + vertex 0.984977 0.929192 2.56736 + vertex 0.98466 0.933433 2.56874 + vertex 0.979681 0.933818 2.56764 + endloop + endfacet + facet normal -0.227831 -0.338298 0.913043 + outer loop + vertex 0.98466 0.933433 2.56874 + vertex 0.983025 0.937003 2.56965 + vertex 0.979681 0.933818 2.56764 + endloop + endfacet + facet normal -0.224849 -0.34121 0.912698 + outer loop + vertex 0.979681 0.933818 2.56764 + vertex 0.983025 0.937003 2.56965 + vertex 0.978234 0.939021 2.56923 + endloop + endfacet + facet normal -0.227636 -0.348562 0.909223 + outer loop + vertex 0.978234 0.939021 2.56923 + vertex 0.983025 0.937003 2.56965 + vertex 0.98165 0.941082 2.57087 + endloop + endfacet + facet normal -0.213046 -0.369086 0.904648 + outer loop + vertex 0.977759 0.942409 2.5705 + vertex 0.978234 0.939021 2.56923 + vertex 0.98165 0.941082 2.57087 + endloop + endfacet + facet normal -0.203329 -0.336385 0.919512 + outer loop + vertex 0.98165 0.941082 2.57087 + vertex 0.979844 0.945376 2.57204 + vertex 0.977759 0.942409 2.5705 + endloop + endfacet + facet normal -0.118051 -0.307281 0.944268 + outer loop + vertex 0.985153 0.944164 2.57231 + vertex 0.979844 0.945376 2.57204 + vertex 0.98165 0.941082 2.57087 + endloop + endfacet + facet normal -0.119434 -0.313856 0.941929 + outer loop + vertex 0.985153 0.944164 2.57231 + vertex 0.984014 0.948286 2.57354 + vertex 0.979844 0.945376 2.57204 + endloop + endfacet + facet normal -0.110701 -0.324977 0.939221 + outer loop + vertex 0.979844 0.945376 2.57204 + vertex 0.984014 0.948286 2.57354 + vertex 0.979864 0.94937 2.57343 + endloop + endfacet + facet normal -0.106669 -0.308927 0.945085 + outer loop + vertex 0.984014 0.948286 2.57354 + vertex 0.982823 0.952167 2.57467 + vertex 0.979864 0.94937 2.57343 + endloop + endfacet + facet normal -0.124515 -0.291539 0.94842 + outer loop + vertex 0.979864 0.94937 2.57343 + vertex 0.982823 0.952167 2.57467 + vertex 0.977648 0.953101 2.57428 + endloop + endfacet + facet normal -0.127705 -0.312153 0.941409 + outer loop + vertex 0.977648 0.953101 2.57428 + vertex 0.982823 0.952167 2.57467 + vertex 0.981466 0.956061 2.57578 + endloop + endfacet + facet normal -0.117327 -0.32417 0.938695 + outer loop + vertex 0.977367 0.956973 2.57558 + vertex 0.977648 0.953101 2.57428 + vertex 0.981466 0.956061 2.57578 + endloop + endfacet + facet normal -0.113712 -0.306549 0.945038 + outer loop + vertex 0.981466 0.956061 2.57578 + vertex 0.979626 0.960435 2.57698 + vertex 0.977367 0.956973 2.57558 + endloop + endfacet + facet normal -0.0473182 -0.282223 0.958181 + outer loop + vertex 0.985093 0.959636 2.57701 + vertex 0.979626 0.960435 2.57698 + vertex 0.981466 0.956061 2.57578 + endloop + endfacet + facet normal -0.0479165 -0.28637 0.95692 + outer loop + vertex 0.985093 0.959636 2.57701 + vertex 0.984077 0.963882 2.57823 + vertex 0.979626 0.960435 2.57698 + endloop + endfacet + facet normal -0.037619 -0.298484 0.953673 + outer loop + vertex 0.979626 0.960435 2.57698 + vertex 0.984077 0.963882 2.57823 + vertex 0.979674 0.964661 2.5783 + endloop + endfacet + facet normal 0.0694642 -0.224036 0.972102 + outer loop + vertex 0.983478 1.03177 2.59546 + vertex 0.983112 1.03455 2.59613 + vertex 0.98038 1.03213 2.59576 + endloop + endfacet + facet normal 0.221841 -0.0748353 0.972207 + outer loop + vertex 0.978816 1.36305 2.63996 + vertex 0.983592 1.36817 2.63926 + vertex 0.978965 1.36813 2.64032 + endloop + endfacet + facet normal 0.169703 -0.082421 0.982043 + outer loop + vertex 0.979628 1.3722 2.64054 + vertex 0.977007 1.36976 2.64079 + vertex 0.978965 1.36813 2.64032 + endloop + endfacet + facet normal 0.261493 -0.0961643 0.960403 + outer loop + vertex 0.979628 1.3722 2.64054 + vertex 0.978965 1.36813 2.64032 + vertex 0.983519 1.37369 2.63963 + endloop + endfacet + facet normal 0.221922 -0.0621937 0.973079 + outer loop + vertex 0.983519 1.37369 2.63963 + vertex 0.978965 1.36813 2.64032 + vertex 0.983592 1.36817 2.63926 + endloop + endfacet + facet normal 0.138489 -0.0481122 0.989195 + outer loop + vertex 0.979628 1.3722 2.64054 + vertex 0.977047 1.37289 2.64094 + vertex 0.977007 1.36976 2.64079 + endloop + endfacet + facet normal 0.259506 -0.0472484 0.964585 + outer loop + vertex 0.983519 1.37369 2.63963 + vertex 0.984614 1.3796 2.63963 + vertex 0.980721 1.3762 2.64051 + endloop + endfacet + facet normal 0.248994 -0.0597249 0.966662 + outer loop + vertex 0.979628 1.3722 2.64054 + vertex 0.983519 1.37369 2.63963 + vertex 0.980721 1.3762 2.64051 + endloop + endfacet + facet normal 0.143187 -0.0305695 0.989223 + outer loop + vertex 0.980721 1.3762 2.64051 + vertex 0.977047 1.37289 2.64094 + vertex 0.979628 1.3722 2.64054 + endloop + endfacet + facet normal 0.153776 -0.0426073 0.987187 + outer loop + vertex 0.977329 1.37727 2.64108 + vertex 0.977047 1.37289 2.64094 + vertex 0.980721 1.3762 2.64051 + endloop + endfacet + facet normal 0.261179 -0.0341838 0.964685 + outer loop + vertex 0.984614 1.3796 2.63963 + vertex 0.984955 1.38475 2.63972 + vertex 0.981224 1.38108 2.6406 + endloop + endfacet + facet normal 0.257015 -0.0441895 0.965397 + outer loop + vertex 0.980721 1.3762 2.64051 + vertex 0.984614 1.3796 2.63963 + vertex 0.981224 1.38108 2.6406 + endloop + endfacet + facet normal 0.15642 -0.0342266 0.987097 + outer loop + vertex 0.981224 1.38108 2.6406 + vertex 0.977329 1.37727 2.64108 + vertex 0.980721 1.3762 2.64051 + endloop + endfacet + facet normal 0.165067 -0.0432945 0.985332 + outer loop + vertex 0.97754 1.38214 2.64126 + vertex 0.977329 1.37727 2.64108 + vertex 0.981224 1.38108 2.6406 + endloop + endfacet + facet normal 0.26885 -0.0336171 0.962595 + outer loop + vertex 0.984955 1.38475 2.63972 + vertex 0.9851 1.3897 2.63985 + vertex 0.98148 1.38606 2.64073 + endloop + endfacet + facet normal 0.26654 -0.0400427 0.962992 + outer loop + vertex 0.981224 1.38108 2.6406 + vertex 0.984955 1.38475 2.63972 + vertex 0.98148 1.38606 2.64073 + endloop + endfacet + facet normal 0.167295 -0.0355422 0.985266 + outer loop + vertex 0.98148 1.38606 2.64073 + vertex 0.97754 1.38214 2.64126 + vertex 0.981224 1.38108 2.6406 + endloop + endfacet + facet normal 0.173015 -0.0414624 0.984046 + outer loop + vertex 0.977803 1.38724 2.64143 + vertex 0.97754 1.38214 2.64126 + vertex 0.98148 1.38606 2.64073 + endloop + endfacet + facet normal 0.279646 -0.0397095 0.959282 + outer loop + vertex 0.9851 1.3897 2.63985 + vertex 0.985132 1.39428 2.64003 + vertex 0.981808 1.39095 2.64086 + endloop + endfacet + facet normal 0.278216 -0.0436811 0.959525 + outer loop + vertex 0.98148 1.38606 2.64073 + vertex 0.9851 1.3897 2.63985 + vertex 0.981808 1.39095 2.64086 + endloop + endfacet + facet normal 0.174327 -0.0373454 0.983979 + outer loop + vertex 0.981808 1.39095 2.64086 + vertex 0.977803 1.38724 2.64143 + vertex 0.98148 1.38606 2.64073 + endloop + endfacet + facet normal 0.180999 -0.0447981 0.982462 + outer loop + vertex 0.978543 1.39297 2.64156 + vertex 0.977803 1.38724 2.64143 + vertex 0.981808 1.39095 2.64086 + endloop + endfacet + facet normal 0.294284 -0.0555984 0.954099 + outer loop + vertex 0.985132 1.39428 2.64003 + vertex 0.982457 1.39485 2.64089 + vertex 0.981808 1.39095 2.64086 + endloop + endfacet + facet normal 0.185287 -0.0377042 0.981961 + outer loop + vertex 0.982457 1.39485 2.64089 + vertex 0.978543 1.39297 2.64156 + vertex 0.981808 1.39095 2.64086 + endloop + endfacet + facet normal 0.18417 -0.0352787 0.982261 + outer loop + vertex 0.982457 1.39485 2.64089 + vertex 0.981889 1.39798 2.64111 + vertex 0.978543 1.39297 2.64156 + endloop + endfacet + facet normal 0.182728 -0.0342883 0.982565 + outer loop + vertex 0.981889 1.39798 2.64111 + vertex 0.978035 1.39798 2.64182 + vertex 0.978543 1.39297 2.64156 + endloop + endfacet + facet normal 0.182798 -0.0224535 0.982894 + outer loop + vertex 0.981889 1.39798 2.64111 + vertex 0.981898 1.4024 2.64121 + vertex 0.978035 1.39798 2.64182 + endloop + endfacet + facet normal 0.195452 -0.033904 0.980127 + outer loop + vertex 0.978035 1.39798 2.64182 + vertex 0.981898 1.4024 2.64121 + vertex 0.977986 1.40284 2.642 + endloop + endfacet + facet normal 0.196373 -0.0258318 0.980189 + outer loop + vertex 0.981898 1.4024 2.64121 + vertex 0.981997 1.40725 2.64132 + vertex 0.977986 1.40284 2.642 + endloop + endfacet + facet normal 0.203797 -0.0328507 0.978462 + outer loop + vertex 0.977986 1.40284 2.642 + vertex 0.981997 1.40725 2.64132 + vertex 0.978017 1.40778 2.64216 + endloop + endfacet + facet normal 0.204823 -0.0252092 0.978474 + outer loop + vertex 0.981997 1.40725 2.64132 + vertex 0.982059 1.41222 2.64143 + vertex 0.978017 1.40778 2.64216 + endloop + endfacet + facet normal 0.211687 -0.0317343 0.976822 + outer loop + vertex 0.978017 1.40778 2.64216 + vertex 0.982059 1.41222 2.64143 + vertex 0.978048 1.41279 2.64232 + endloop + endfacet + facet normal 0.212522 -0.0257944 0.976816 + outer loop + vertex 0.982059 1.41222 2.64143 + vertex 0.982111 1.41723 2.64155 + vertex 0.978048 1.41279 2.64232 + endloop + endfacet + facet normal 0.217876 -0.0309194 0.975487 + outer loop + vertex 0.978048 1.41279 2.64232 + vertex 0.982111 1.41723 2.64155 + vertex 0.978083 1.4178 2.64247 + endloop + endfacet + facet normal 0.218728 -0.0248755 0.975469 + outer loop + vertex 0.982111 1.41723 2.64155 + vertex 0.982171 1.42223 2.64167 + vertex 0.978083 1.4178 2.64247 + endloop + endfacet + facet normal 0.22271 -0.0287325 0.974461 + outer loop + vertex 0.978083 1.4178 2.64247 + vertex 0.982171 1.42223 2.64167 + vertex 0.978117 1.42279 2.64261 + endloop + endfacet + facet normal 0.223435 -0.0234829 0.974436 + outer loop + vertex 0.982171 1.42223 2.64167 + vertex 0.982237 1.42722 2.64177 + vertex 0.978117 1.42279 2.64261 + endloop + endfacet + facet normal 0.0555186 0.138603 0.988791 + outer loop + vertex 0.97892 1.81939 2.62538 + vertex 0.980536 1.81508 2.6259 + vertex 0.984791 1.81795 2.62526 + endloop + endfacet + facet normal -0.0335938 0.267964 0.962843 + outer loop + vertex 0.984051 2.05137 2.57941 + vertex 0.982726 2.05619 2.57803 + vertex 0.978384 2.05203 2.57903 + endloop + endfacet + facet normal -0.281594 0.398555 0.872845 + outer loop + vertex 0.978716 2.09626 2.56389 + vertex 0.980607 2.09354 2.56574 + vertex 0.983492 2.09737 2.56492 + endloop + endfacet + facet normal -0.276828 0.362403 0.889961 + outer loop + vertex 0.983492 2.09737 2.56492 + vertex 0.982917 2.101 2.56326 + vertex 0.978716 2.09626 2.56389 + endloop + endfacet + facet normal -0.315407 0.393094 0.86371 + outer loop + vertex 0.978716 2.09626 2.56389 + vertex 0.982917 2.101 2.56326 + vertex 0.978138 2.10061 2.5617 + endloop + endfacet + facet normal -0.413462 0.4066 0.814693 + outer loop + vertex 0.981437 2.1069 2.56044 + vertex 0.978191 2.10634 2.55908 + vertex 0.97913 2.10408 2.56069 + endloop + endfacet + facet normal -0.338655 0.350577 0.87316 + outer loop + vertex 0.97913 2.10408 2.56069 + vertex 0.982221 2.10453 2.5617 + vertex 0.981437 2.1069 2.56044 + endloop + endfacet + facet normal -0.338671 0.35176 0.872678 + outer loop + vertex 0.97913 2.10408 2.56069 + vertex 0.978138 2.10061 2.5617 + vertex 0.982221 2.10453 2.5617 + endloop + endfacet + facet normal -0.318356 0.330609 0.888452 + outer loop + vertex 0.978138 2.10061 2.5617 + vertex 0.982917 2.101 2.56326 + vertex 0.982221 2.10453 2.5617 + endloop + endfacet + facet normal -0.323649 0.390639 0.861773 + outer loop + vertex 0.981437 2.1069 2.56044 + vertex 0.985144 2.10873 2.56101 + vertex 0.98322 2.11112 2.5592 + endloop + endfacet + facet normal -0.413246 0.413646 0.811249 + outer loop + vertex 0.981437 2.1069 2.56044 + vertex 0.98322 2.11112 2.5592 + vertex 0.978191 2.10634 2.55908 + endloop + endfacet + facet normal -0.405788 0.405607 0.819036 + outer loop + vertex 0.978191 2.10634 2.55908 + vertex 0.98322 2.11112 2.5592 + vertex 0.978662 2.11071 2.55715 + endloop + endfacet + facet normal -0.312107 0.362094 0.878338 + outer loop + vertex 0.985144 2.10873 2.56101 + vertex 0.981437 2.1069 2.56044 + vertex 0.982221 2.10453 2.5617 + endloop + endfacet + facet normal -0.450643 0.405099 0.795497 + outer loop + vertex 0.981421 2.11728 2.55549 + vertex 0.977757 2.1158 2.55416 + vertex 0.979693 2.11437 2.55599 + endloop + endfacet + facet normal -0.404254 0.383505 0.830363 + outer loop + vertex 0.979693 2.11437 2.55599 + vertex 0.983268 2.1157 2.55711 + vertex 0.981421 2.11728 2.55549 + endloop + endfacet + facet normal -0.40303 0.377327 0.833781 + outer loop + vertex 0.979693 2.11437 2.55599 + vertex 0.978662 2.11071 2.55715 + vertex 0.983268 2.1157 2.55711 + endloop + endfacet + facet normal -0.408178 0.382038 0.829119 + outer loop + vertex 0.978662 2.11071 2.55715 + vertex 0.98322 2.11112 2.5592 + vertex 0.983268 2.1157 2.55711 + endloop + endfacet + facet normal -0.427867 0.46787 0.773322 + outer loop + vertex 0.981421 2.11728 2.55549 + vertex 0.983989 2.11937 2.55564 + vertex 0.981397 2.12045 2.55356 + endloop + endfacet + facet normal -0.459688 0.459496 0.759968 + outer loop + vertex 0.981421 2.11728 2.55549 + vertex 0.981397 2.12045 2.55356 + vertex 0.977757 2.1158 2.55416 + endloop + endfacet + facet normal -0.427173 0.438043 0.790975 + outer loop + vertex 0.977757 2.1158 2.55416 + vertex 0.981397 2.12045 2.55356 + vertex 0.977162 2.11955 2.55177 + endloop + endfacet + facet normal -0.382281 0.408001 0.829094 + outer loop + vertex 0.983989 2.11937 2.55564 + vertex 0.981421 2.11728 2.55549 + vertex 0.983268 2.1157 2.55711 + endloop + endfacet + facet normal -0.364434 0.666798 0.650052 + outer loop + vertex 0.979364 2.12354 2.55016 + vertex 0.98299 2.12383 2.5519 + vertex 0.981898 2.12594 2.54911 + endloop + endfacet + facet normal -0.323541 0.642854 0.694305 + outer loop + vertex 0.979264 2.12587 2.54796 + vertex 0.979364 2.12354 2.55016 + vertex 0.981898 2.12594 2.54911 + endloop + endfacet + facet normal -0.422996 0.529938 0.73501 + outer loop + vertex 0.981397 2.12045 2.55356 + vertex 0.979364 2.12354 2.55016 + vertex 0.977162 2.11955 2.55177 + endloop + endfacet + facet normal -0.396526 0.548535 0.736123 + outer loop + vertex 0.98299 2.12383 2.5519 + vertex 0.979364 2.12354 2.55016 + vertex 0.981397 2.12045 2.55356 + endloop + endfacet + facet normal -0.118686 0.894704 0.430603 + outer loop + vertex 0.980206 2.12964 2.54222 + vertex 0.985028 2.13015 2.5425 + vertex 0.981585 2.13153 2.53867 + endloop + endfacet + facet normal -0.149893 0.895544 0.418966 + outer loop + vertex 0.977262 2.13089 2.53851 + vertex 0.980206 2.12964 2.54222 + vertex 0.981585 2.13153 2.53867 + endloop + endfacet + facet normal -0.118638 0.898289 0.423086 + outer loop + vertex 0.985028 2.13015 2.5425 + vertex 0.980206 2.12964 2.54222 + vertex 0.984198 2.12801 2.5468 + endloop + endfacet + facet normal -0.197851 0.856224 0.477216 + outer loop + vertex 0.984198 2.12801 2.5468 + vertex 0.980206 2.12964 2.54222 + vertex 0.979404 2.12752 2.5457 + endloop + endfacet + facet normal -0.267556 0.785921 0.557443 + outer loop + vertex 0.981898 2.12594 2.54911 + vertex 0.979404 2.12752 2.5457 + vertex 0.979264 2.12587 2.54796 + endloop + endfacet + facet normal -0.206491 0.822623 0.529768 + outer loop + vertex 0.984198 2.12801 2.5468 + vertex 0.979404 2.12752 2.5457 + vertex 0.981898 2.12594 2.54911 + endloop + endfacet + facet normal -0.026715 0.333882 0.942236 + outer loop + vertex 0.985 2.13732 2.535 + vertex 0.98 2.13692 2.535 + vertex 0.983425 2.13394 2.53615 + endloop + endfacet + facet normal -0.163499 0.186676 0.968721 + outer loop + vertex 0.983425 2.13394 2.53615 + vertex 0.98 2.13692 2.535 + vertex 0.978455 2.13271 2.53555 + endloop + endfacet + facet normal -0.147698 0.867003 0.475911 + outer loop + vertex 0.981585 2.13153 2.53867 + vertex 0.978455 2.13271 2.53555 + vertex 0.977262 2.13089 2.53851 + endloop + endfacet + facet normal -0.262625 0.785376 0.560547 + outer loop + vertex 0.983425 2.13394 2.53615 + vertex 0.978455 2.13271 2.53555 + vertex 0.981585 2.13153 2.53867 + endloop + endfacet + facet normal 0.00664225 -0.851975 0.52354 + outer loop + vertex 0.99 0.88826 2.535 + vertex 0.986956 0.88875 2.53584 + vertex 0.985 0.888221 2.535 + endloop + endfacet + facet normal -0.138878 -0.657316 0.740708 + outer loop + vertex 0.986956 0.88875 2.53584 + vertex 0.982845 0.888622 2.53495 + vertex 0.985 0.888221 2.535 + endloop + endfacet + facet normal -0.0456072 -0.936462 0.347792 + outer loop + vertex 0.986956 0.88875 2.53584 + vertex 0.985259 0.889511 2.53766 + vertex 0.982845 0.888622 2.53495 + endloop + endfacet + facet normal 0.0337483 -0.911051 0.41091 + outer loop + vertex 0.989363 0.889893 2.53817 + vertex 0.985259 0.889511 2.53766 + vertex 0.986956 0.88875 2.53584 + endloop + endfacet + facet normal 0.0473712 -0.94417 0.326036 + outer loop + vertex 0.985259 0.889511 2.53766 + vertex 0.989363 0.889893 2.53817 + vertex 0.989151 0.890955 2.54128 + endloop + endfacet + facet normal -0.0457024 -0.909815 0.41249 + outer loop + vertex 0.982778 0.890914 2.54048 + vertex 0.985259 0.889511 2.53766 + vertex 0.989151 0.890955 2.54128 + endloop + endfacet + facet normal -0.0343728 -0.945557 0.323635 + outer loop + vertex 0.989151 0.890955 2.54128 + vertex 0.986457 0.892347 2.54506 + vertex 0.982778 0.890914 2.54048 + endloop + endfacet + facet normal -0.131983 -0.910786 0.391215 + outer loop + vertex 0.986457 0.892347 2.54506 + vertex 0.981683 0.892714 2.5443 + vertex 0.982778 0.890914 2.54048 + endloop + endfacet + facet normal -0.146504 -0.844567 0.515018 + outer loop + vertex 0.986457 0.892347 2.54506 + vertex 0.983252 0.894649 2.54792 + vertex 0.981683 0.892714 2.5443 + endloop + endfacet + facet normal -0.191809 -0.858534 0.47553 + outer loop + vertex 0.989772 0.893763 2.54895 + vertex 0.983252 0.894649 2.54792 + vertex 0.986457 0.892347 2.54506 + endloop + endfacet + facet normal -0.196756 -0.816072 0.543428 + outer loop + vertex 0.983252 0.894649 2.54792 + vertex 0.989772 0.893763 2.54895 + vertex 0.987702 0.896205 2.55187 + endloop + endfacet + facet normal -0.270347 -0.75201 0.60116 + outer loop + vertex 0.982981 0.897035 2.55079 + vertex 0.983252 0.894649 2.54792 + vertex 0.987702 0.896205 2.55187 + endloop + endfacet + facet normal -0.277313 -0.634558 0.72141 + outer loop + vertex 0.987702 0.896205 2.55187 + vertex 0.983521 0.899395 2.55307 + vertex 0.982981 0.897035 2.55079 + endloop + endfacet + facet normal -0.349218 -0.694197 0.629394 + outer loop + vertex 0.988137 0.898263 2.55438 + vertex 0.983521 0.899395 2.55307 + vertex 0.987702 0.896205 2.55187 + endloop + endfacet + facet normal -0.35139 -0.589447 0.727377 + outer loop + vertex 0.983521 0.899395 2.55307 + vertex 0.988137 0.898263 2.55438 + vertex 0.986786 0.90063 2.55565 + endloop + endfacet + facet normal -0.389699 -0.534836 0.749724 + outer loop + vertex 0.983244 0.902414 2.55508 + vertex 0.983521 0.899395 2.55307 + vertex 0.986786 0.90063 2.55565 + endloop + endfacet + facet normal -0.368122 -0.476452 0.798424 + outer loop + vertex 0.986786 0.90063 2.55565 + vertex 0.985448 0.903989 2.55703 + vertex 0.983244 0.902414 2.55508 + endloop + endfacet + facet normal -0.303839 -0.464603 0.831761 + outer loop + vertex 0.989827 0.902107 2.55758 + vertex 0.985448 0.903989 2.55703 + vertex 0.986786 0.90063 2.55565 + endloop + endfacet + facet normal -0.296522 -0.443477 0.845815 + outer loop + vertex 0.989827 0.902107 2.55758 + vertex 0.988712 0.906241 2.55936 + vertex 0.985448 0.903989 2.55703 + endloop + endfacet + facet normal -0.342003 -0.387947 0.85588 + outer loop + vertex 0.985448 0.903989 2.55703 + vertex 0.988712 0.906241 2.55936 + vertex 0.982815 0.908627 2.55808 + endloop + endfacet + facet normal -0.348966 -0.412986 0.841228 + outer loop + vertex 0.982815 0.908627 2.55808 + vertex 0.988712 0.906241 2.55936 + vertex 0.986801 0.91047 2.56064 + endloop + endfacet + facet normal -0.348839 -0.413193 0.841179 + outer loop + vertex 0.983144 0.912364 2.56006 + vertex 0.982815 0.908627 2.55808 + vertex 0.986801 0.91047 2.56064 + endloop + endfacet + facet normal -0.332752 -0.374645 0.8654 + outer loop + vertex 0.986801 0.91047 2.56064 + vertex 0.985427 0.914535 2.56187 + vertex 0.983144 0.912364 2.56006 + endloop + endfacet + facet normal -0.220368 -0.350272 0.910356 + outer loop + vertex 0.990377 0.913314 2.5626 + vertex 0.985427 0.914535 2.56187 + vertex 0.986801 0.91047 2.56064 + endloop + endfacet + facet normal -0.222129 -0.359921 0.906154 + outer loop + vertex 0.990377 0.913314 2.5626 + vertex 0.987743 0.918312 2.56394 + vertex 0.985427 0.914535 2.56187 + endloop + endfacet + facet normal -0.26361 -0.333856 0.905014 + outer loop + vertex 0.985427 0.914535 2.56187 + vertex 0.987743 0.918312 2.56394 + vertex 0.982857 0.91858 2.56262 + endloop + endfacet + facet normal -0.231687 -0.38247 0.894448 + outer loop + vertex 0.987567 0.922272 2.56546 + vertex 0.985591 0.924927 2.56608 + vertex 0.983404 0.92266 2.56454 + endloop + endfacet + facet normal -0.231611 -0.356308 0.905208 + outer loop + vertex 0.987567 0.922272 2.56546 + vertex 0.983404 0.92266 2.56454 + vertex 0.987743 0.918312 2.56394 + endloop + endfacet + facet normal -0.261164 -0.383143 0.885999 + outer loop + vertex 0.987743 0.918312 2.56394 + vertex 0.983404 0.92266 2.56454 + vertex 0.982857 0.91858 2.56262 + endloop + endfacet + facet normal -0.111222 -0.304874 0.945876 + outer loop + vertex 0.987567 0.922272 2.56546 + vertex 0.989719 0.925681 2.56681 + vertex 0.985591 0.924927 2.56608 + endloop + endfacet + facet normal -0.246346 -0.369395 0.896025 + outer loop + vertex 0.983404 0.92266 2.56454 + vertex 0.985591 0.924927 2.56608 + vertex 0.982561 0.926432 2.56587 + endloop + endfacet + facet normal -0.218458 -0.309064 0.925611 + outer loop + vertex 0.985591 0.924927 2.56608 + vertex 0.984977 0.929192 2.56736 + vertex 0.982561 0.926432 2.56587 + endloop + endfacet + facet normal -0.112304 -0.300253 0.947225 + outer loop + vertex 0.985591 0.924927 2.56608 + vertex 0.989719 0.925681 2.56681 + vertex 0.984977 0.929192 2.56736 + endloop + endfacet + facet normal -0.109799 -0.297072 0.948521 + outer loop + vertex 0.989719 0.925681 2.56681 + vertex 0.989838 0.929817 2.56812 + vertex 0.984977 0.929192 2.56736 + endloop + endfacet + facet normal -0.104459 -0.327244 0.939149 + outer loop + vertex 0.989838 0.929817 2.56812 + vertex 0.988005 0.932272 2.56877 + vertex 0.984977 0.929192 2.56736 + endloop + endfacet + facet normal -0.118357 -0.314775 0.941758 + outer loop + vertex 0.984977 0.929192 2.56736 + vertex 0.988005 0.932272 2.56877 + vertex 0.98466 0.933433 2.56874 + endloop + endfacet + facet normal -0.112102 -0.296563 0.948411 + outer loop + vertex 0.988005 0.932272 2.56877 + vertex 0.988092 0.936044 2.56996 + vertex 0.98466 0.933433 2.56874 + endloop + endfacet + facet normal -0.113389 -0.295025 0.948738 + outer loop + vertex 0.98466 0.933433 2.56874 + vertex 0.988092 0.936044 2.56996 + vertex 0.983025 0.937003 2.56965 + endloop + endfacet + facet normal -0.11786 -0.321602 0.939511 + outer loop + vertex 0.983025 0.937003 2.56965 + vertex 0.988092 0.936044 2.56996 + vertex 0.986359 0.940008 2.5711 + endloop + endfacet + facet normal -0.118563 -0.320896 0.939664 + outer loop + vertex 0.98165 0.941082 2.57087 + vertex 0.983025 0.937003 2.56965 + vertex 0.986359 0.940008 2.5711 + endloop + endfacet + facet normal -0.116117 -0.309286 0.943853 + outer loop + vertex 0.986359 0.940008 2.5711 + vertex 0.985153 0.944164 2.57231 + vertex 0.98165 0.941082 2.57087 + endloop + endfacet + facet normal -0.0313274 -0.288507 0.956965 + outer loop + vertex 0.990528 0.943551 2.5723 + vertex 0.985153 0.944164 2.57231 + vertex 0.986359 0.940008 2.5711 + endloop + endfacet + facet normal -0.0319239 -0.293715 0.95536 + outer loop + vertex 0.990528 0.943551 2.5723 + vertex 0.988974 0.947952 2.5736 + vertex 0.985153 0.944164 2.57231 + endloop + endfacet + facet normal -0.0319556 -0.293686 0.955368 + outer loop + vertex 0.985153 0.944164 2.57231 + vertex 0.988974 0.947952 2.5736 + vertex 0.984014 0.948286 2.57354 + endloop + endfacet + facet normal -0.0321205 -0.296287 0.954559 + outer loop + vertex 0.988974 0.947952 2.5736 + vertex 0.98768 0.951864 2.57477 + vertex 0.984014 0.948286 2.57354 + endloop + endfacet + facet normal -0.037794 -0.290967 0.955986 + outer loop + vertex 0.984014 0.948286 2.57354 + vertex 0.98768 0.951864 2.57477 + vertex 0.982823 0.952167 2.57467 + endloop + endfacet + facet normal -0.0378387 -0.291766 0.955741 + outer loop + vertex 0.982823 0.952167 2.57467 + vertex 0.98768 0.951864 2.57477 + vertex 0.986386 0.955645 2.57588 + endloop + endfacet + facet normal -0.0428802 -0.287022 0.956964 + outer loop + vertex 0.981466 0.956061 2.57578 + vertex 0.982823 0.952167 2.57467 + vertex 0.986386 0.955645 2.57588 + endloop + endfacet + facet normal -0.0428326 -0.286417 0.957147 + outer loop + vertex 0.986386 0.955645 2.57588 + vertex 0.985093 0.959636 2.57701 + vertex 0.981466 0.956061 2.57578 + endloop + endfacet + facet normal 0.0100357 -0.270824 0.962577 + outer loop + vertex 0.990127 0.959554 2.57694 + vertex 0.985093 0.959636 2.57701 + vertex 0.986386 0.955645 2.57588 + endloop + endfacet + facet normal 0.010093 -0.268025 0.963359 + outer loop + vertex 0.990127 0.959554 2.57694 + vertex 0.989187 0.963737 2.57811 + vertex 0.985093 0.959636 2.57701 + endloop + endfacet + facet normal 0.0730591 -0.223528 0.971956 + outer loop + vertex 0.983112 1.03455 2.59613 + vertex 0.983478 1.03177 2.59546 + vertex 0.986827 1.03542 2.59605 + endloop + endfacet + facet normal 0.267999 -0.018723 0.963237 + outer loop + vertex 0.984613 1.39754 2.64034 + vertex 0.981889 1.39798 2.64111 + vertex 0.982457 1.39485 2.64089 + endloop + endfacet + facet normal 0.269342 -0.00995651 0.962993 + outer loop + vertex 0.985218 1.40133 2.64021 + vertex 0.981889 1.39798 2.64111 + vertex 0.984613 1.39754 2.64034 + endloop + endfacet + facet normal 0.277257 0.0620724 0.958789 + outer loop + vertex 0.989058 1.70378 2.63432 + vertex 0.988131 1.70906 2.63425 + vertex 0.98505 1.70504 2.6354 + endloop + endfacet + facet normal 0.172101 0.0861166 0.981308 + outer loop + vertex 0.981014 1.70597 2.63602 + vertex 0.981839 1.70154 2.63627 + vertex 0.98505 1.70504 2.6354 + endloop + endfacet + facet normal 0.243587 0.0898417 0.965709 + outer loop + vertex 0.983899 1.70868 2.63535 + vertex 0.98505 1.70504 2.6354 + vertex 0.988131 1.70906 2.63425 + endloop + endfacet + facet normal 0.243902 0.0869056 0.965898 + outer loop + vertex 0.983899 1.70868 2.63535 + vertex 0.988131 1.70906 2.63425 + vertex 0.984619 1.71299 2.63478 + endloop + endfacet + facet normal 0.167852 0.0661395 0.983591 + outer loop + vertex 0.98505 1.70504 2.6354 + vertex 0.983899 1.70868 2.63535 + vertex 0.981014 1.70597 2.63602 + endloop + endfacet + facet normal -0.11198 0.316425 0.941985 + outer loop + vertex 0.984159 2.09483 2.56608 + vertex 0.987345 2.09469 2.5665 + vertex 0.98677 2.09741 2.56552 + endloop + endfacet + facet normal -0.0734075 0.324892 0.942898 + outer loop + vertex 0.990665 2.09833 2.56551 + vertex 0.98677 2.09741 2.56552 + vertex 0.987345 2.09469 2.5665 + endloop + endfacet + facet normal -0.240153 0.353014 0.904272 + outer loop + vertex 0.982917 2.101 2.56326 + vertex 0.987375 2.10618 2.56243 + vertex 0.982221 2.10453 2.5617 + endloop + endfacet + facet normal -0.245812 0.358638 0.90053 + outer loop + vertex 0.985144 2.10873 2.56101 + vertex 0.988815 2.11036 2.56136 + vertex 0.988242 2.11284 2.56022 + endloop + endfacet + facet normal -0.311317 0.40056 0.861762 + outer loop + vertex 0.98322 2.11112 2.5592 + vertex 0.985144 2.10873 2.56101 + vertex 0.988242 2.11284 2.56022 + endloop + endfacet + facet normal -0.229507 0.311805 0.922011 + outer loop + vertex 0.987375 2.10618 2.56243 + vertex 0.985144 2.10873 2.56101 + vertex 0.982221 2.10453 2.5617 + endloop + endfacet + facet normal -0.227774 0.313278 0.921941 + outer loop + vertex 0.988815 2.11036 2.56136 + vertex 0.985144 2.10873 2.56101 + vertex 0.987375 2.10618 2.56243 + endloop + endfacet + facet normal -0.309651 0.393397 0.865653 + outer loop + vertex 0.988242 2.11284 2.56022 + vertex 0.987857 2.11626 2.55852 + vertex 0.98322 2.11112 2.5592 + endloop + endfacet + facet normal -0.313428 0.396439 0.862901 + outer loop + vertex 0.98322 2.11112 2.5592 + vertex 0.987857 2.11626 2.55852 + vertex 0.983268 2.1157 2.55711 + endloop + endfacet + facet normal -0.379356 0.541054 0.750566 + outer loop + vertex 0.985431 2.12239 2.5542 + vertex 0.981397 2.12045 2.55356 + vertex 0.983989 2.11937 2.55564 + endloop + endfacet + facet normal -0.293714 0.523638 0.79971 + outer loop + vertex 0.983989 2.11937 2.55564 + vertex 0.987178 2.11986 2.55649 + vertex 0.985431 2.12239 2.5542 + endloop + endfacet + facet normal -0.293396 0.405294 0.865827 + outer loop + vertex 0.983989 2.11937 2.55564 + vertex 0.983268 2.1157 2.55711 + vertex 0.987178 2.11986 2.55649 + endloop + endfacet + facet normal -0.312875 0.421437 0.851176 + outer loop + vertex 0.983268 2.1157 2.55711 + vertex 0.987857 2.11626 2.55852 + vertex 0.987178 2.11986 2.55649 + endloop + endfacet + facet normal -0.288899 0.704039 0.648742 + outer loop + vertex 0.9861 2.12551 2.55146 + vertex 0.981898 2.12594 2.54911 + vertex 0.98299 2.12383 2.5519 + endloop + endfacet + facet normal -0.381077 0.546118 0.746013 + outer loop + vertex 0.98299 2.12383 2.5519 + vertex 0.981397 2.12045 2.55356 + vertex 0.985431 2.12239 2.5542 + endloop + endfacet + facet normal -0.262581 0.667917 0.696375 + outer loop + vertex 0.9861 2.12551 2.55146 + vertex 0.98299 2.12383 2.5519 + vertex 0.985431 2.12239 2.5542 + endloop + endfacet + facet normal -0.248879 0.668715 0.700628 + outer loop + vertex 0.9861 2.12551 2.55146 + vertex 0.985431 2.12239 2.5542 + vertex 0.989643 2.12359 2.55455 + endloop + endfacet + facet normal -0.262638 0.655422 0.708127 + outer loop + vertex 0.9861 2.12551 2.55146 + vertex 0.989643 2.12359 2.55455 + vertex 0.989252 2.12577 2.55239 + endloop + endfacet + facet normal -0.226977 0.564325 0.793737 + outer loop + vertex 0.989643 2.12359 2.55455 + vertex 0.985431 2.12239 2.5542 + vertex 0.987178 2.11986 2.55649 + endloop + endfacet + facet normal -0.0430062 0.853204 0.519802 + outer loop + vertex 0.985028 2.13015 2.5425 + vertex 0.990025 2.13039 2.54252 + vertex 0.986797 2.13218 2.5393 + endloop + endfacet + facet normal -0.164934 0.870644 0.463438 + outer loop + vertex 0.981585 2.13153 2.53867 + vertex 0.985028 2.13015 2.5425 + vertex 0.986797 2.13218 2.5393 + endloop + endfacet + facet normal -0.0458354 0.923202 0.381571 + outer loop + vertex 0.990025 2.13039 2.54252 + vertex 0.985028 2.13015 2.5425 + vertex 0.988973 2.12877 2.54629 + endloop + endfacet + facet normal -0.0983004 0.898773 0.427251 + outer loop + vertex 0.988973 2.12877 2.54629 + vertex 0.985028 2.13015 2.5425 + vertex 0.984198 2.12801 2.5468 + endloop + endfacet + facet normal -0.209121 0.823269 0.527728 + outer loop + vertex 0.9861 2.12551 2.55146 + vertex 0.984198 2.12801 2.5468 + vertex 0.981898 2.12594 2.54911 + endloop + endfacet + facet normal -0.199037 0.827084 0.525657 + outer loop + vertex 0.9861 2.12551 2.55146 + vertex 0.988892 2.12709 2.55002 + vertex 0.984198 2.12801 2.5468 + endloop + endfacet + facet normal -0.101893 0.907758 0.406932 + outer loop + vertex 0.988892 2.12709 2.55002 + vertex 0.988973 2.12877 2.54629 + vertex 0.984198 2.12801 2.5468 + endloop + endfacet + facet normal -0.216748 0.837111 0.502261 + outer loop + vertex 0.988892 2.12709 2.55002 + vertex 0.9861 2.12551 2.55146 + vertex 0.989252 2.12577 2.55239 + endloop + endfacet + facet normal 0.0177548 0.985042 0.171399 + outer loop + vertex 0.99 2.13723 2.535 + vertex 0.985 2.13732 2.535 + vertex 0.99 2.13636 2.54 + endloop + endfacet + facet normal -0.567387 0.490323 0.661556 + outer loop + vertex 0.99 2.13636 2.54 + vertex 0.985 2.13732 2.535 + vertex 0.983425 2.13394 2.53615 + endloop + endfacet + facet normal -0.170874 0.770783 0.613755 + outer loop + vertex 0.986797 2.13218 2.5393 + vertex 0.983425 2.13394 2.53615 + vertex 0.981585 2.13153 2.53867 + endloop + endfacet + facet normal -0.561789 0.302076 0.770158 + outer loop + vertex 0.99 2.13636 2.54 + vertex 0.983425 2.13394 2.53615 + vertex 0.986797 2.13218 2.5393 + endloop + endfacet + facet normal 0.399334 -0.888405 0.226426 + outer loop + vertex 0.991036 0.89 2.54 + vertex 0.99 0.88826 2.535 + vertex 0.993871 0.89 2.535 + endloop + endfacet + facet normal -0.0581019 -0.939051 0.338833 + outer loop + vertex 0.986956 0.88875 2.53584 + vertex 0.99 0.88826 2.535 + vertex 0.991036 0.89 2.54 + endloop + endfacet + facet normal -0.729128 0.195435 0.655879 + outer loop + vertex 0.991036 0.89 2.54 + vertex 0.989363 0.889893 2.53817 + vertex 0.986956 0.88875 2.53584 + endloop + endfacet + facet normal -0.400969 0.859625 0.316652 + outer loop + vertex 0.989363 0.889893 2.53817 + vertex 0.991036 0.89 2.54 + vertex 0.995 0.891849 2.54 + endloop + endfacet + facet normal 0.212573 -0.920055 0.329106 + outer loop + vertex 0.989363 0.889893 2.53817 + vertex 0.995 0.891849 2.54 + vertex 0.989151 0.890955 2.54128 + endloop + endfacet + facet normal 0.141204 -0.988932 -0.0455419 + outer loop + vertex 0.989151 0.890955 2.54128 + vertex 0.995 0.891849 2.54 + vertex 0.994045 0.891585 2.54277 + endloop + endfacet + facet normal 0.0496151 -0.968009 0.245961 + outer loop + vertex 0.994045 0.891585 2.54277 + vertex 0.991898 0.892231 2.54575 + vertex 0.989151 0.890955 2.54128 + endloop + endfacet + facet normal -0.0590586 -0.949691 0.307571 + outer loop + vertex 0.991898 0.892231 2.54575 + vertex 0.986457 0.892347 2.54506 + vertex 0.989151 0.890955 2.54128 + endloop + endfacet + facet normal -0.0690599 -0.917213 0.392366 + outer loop + vertex 0.991898 0.892231 2.54575 + vertex 0.989772 0.893763 2.54895 + vertex 0.986457 0.892347 2.54506 + endloop + endfacet + facet normal -0.0786508 -0.918815 0.386773 + outer loop + vertex 0.995199 0.893455 2.54932 + vertex 0.989772 0.893763 2.54895 + vertex 0.991898 0.892231 2.54575 + endloop + endfacet + facet normal -0.082352 -0.875083 0.476914 + outer loop + vertex 0.989772 0.893763 2.54895 + vertex 0.995199 0.893455 2.54932 + vertex 0.993451 0.895191 2.55221 + endloop + endfacet + facet normal -0.176009 -0.812761 0.555373 + outer loop + vertex 0.987702 0.896205 2.55187 + vertex 0.989772 0.893763 2.54895 + vertex 0.993451 0.895191 2.55221 + endloop + endfacet + facet normal -0.19606 -0.676543 0.709824 + outer loop + vertex 0.988137 0.898263 2.55438 + vertex 0.991894 0.897398 2.55459 + vertex 0.99028 0.899381 2.55604 + endloop + endfacet + facet normal -0.20654 -0.738926 0.64135 + outer loop + vertex 0.988137 0.898263 2.55438 + vertex 0.987702 0.896205 2.55187 + vertex 0.991894 0.897398 2.55459 + endloop + endfacet + facet normal -0.172624 -0.776721 0.605727 + outer loop + vertex 0.987702 0.896205 2.55187 + vertex 0.993451 0.895191 2.55221 + vertex 0.991894 0.897398 2.55459 + endloop + endfacet + facet normal -0.0938588 -0.634904 0.766868 + outer loop + vertex 0.991894 0.897398 2.55459 + vertex 0.994344 0.900122 2.55715 + vertex 0.99028 0.899381 2.55604 + endloop + endfacet + facet normal -0.291331 -0.575027 0.764507 + outer loop + vertex 0.988137 0.898263 2.55438 + vertex 0.99028 0.899381 2.55604 + vertex 0.986786 0.90063 2.55565 + endloop + endfacet + facet normal -0.273247 -0.508042 0.816841 + outer loop + vertex 0.99028 0.899381 2.55604 + vertex 0.989827 0.902107 2.55758 + vertex 0.986786 0.90063 2.55565 + endloop + endfacet + facet normal -0.140538 -0.505517 0.851294 + outer loop + vertex 0.99028 0.899381 2.55604 + vertex 0.994344 0.900122 2.55715 + vertex 0.989827 0.902107 2.55758 + endloop + endfacet + facet normal -0.144469 -0.5133 0.845962 + outer loop + vertex 0.994344 0.900122 2.55715 + vertex 0.993317 0.903935 2.55929 + vertex 0.989827 0.902107 2.55758 + endloop + endfacet + facet normal -0.213219 -0.412901 0.885466 + outer loop + vertex 0.992653 0.90705 2.56069 + vertex 0.990541 0.909262 2.56121 + vertex 0.988712 0.906241 2.55936 + endloop + endfacet + facet normal -0.205105 -0.436738 0.875895 + outer loop + vertex 0.992653 0.90705 2.56069 + vertex 0.988712 0.906241 2.55936 + vertex 0.993317 0.903935 2.55929 + endloop + endfacet + facet normal -0.20284 -0.4323 0.87862 + outer loop + vertex 0.993317 0.903935 2.55929 + vertex 0.988712 0.906241 2.55936 + vertex 0.989827 0.902107 2.55758 + endloop + endfacet + facet normal -0.107833 -0.325013 0.939542 + outer loop + vertex 0.992653 0.90705 2.56069 + vertex 0.994709 0.910439 2.56209 + vertex 0.990541 0.909262 2.56121 + endloop + endfacet + facet normal -0.258536 -0.385611 0.885699 + outer loop + vertex 0.988712 0.906241 2.55936 + vertex 0.990541 0.909262 2.56121 + vertex 0.986801 0.91047 2.56064 + endloop + endfacet + facet normal -0.243064 -0.324369 0.914169 + outer loop + vertex 0.990541 0.909262 2.56121 + vertex 0.990377 0.913314 2.5626 + vertex 0.986801 0.91047 2.56064 + endloop + endfacet + facet normal -0.107021 -0.327348 0.938824 + outer loop + vertex 0.990541 0.909262 2.56121 + vertex 0.994709 0.910439 2.56209 + vertex 0.990377 0.913314 2.5626 + endloop + endfacet + facet normal -0.0978447 -0.314474 0.94421 + outer loop + vertex 0.994709 0.910439 2.56209 + vertex 0.994859 0.914391 2.56343 + vertex 0.990377 0.913314 2.5626 + endloop + endfacet + facet normal -0.0938474 -0.327922 0.940032 + outer loop + vertex 0.994859 0.914391 2.56343 + vertex 0.993035 0.917487 2.56432 + vertex 0.990377 0.913314 2.5626 + endloop + endfacet + facet normal -0.116897 -0.314119 0.94216 + outer loop + vertex 0.990377 0.913314 2.5626 + vertex 0.993035 0.917487 2.56432 + vertex 0.987743 0.918312 2.56394 + endloop + endfacet + facet normal -0.120003 -0.338102 0.933427 + outer loop + vertex 0.987743 0.918312 2.56394 + vertex 0.993035 0.917487 2.56432 + vertex 0.991512 0.92137 2.56553 + endloop + endfacet + facet normal -0.100579 -0.359131 0.927852 + outer loop + vertex 0.987567 0.922272 2.56546 + vertex 0.987743 0.918312 2.56394 + vertex 0.991512 0.92137 2.56553 + endloop + endfacet + facet normal -0.0912204 -0.316797 0.944097 + outer loop + vertex 0.991512 0.92137 2.56553 + vertex 0.989719 0.925681 2.56681 + vertex 0.987567 0.922272 2.56546 + endloop + endfacet + facet normal -0.0265326 -0.293312 0.955648 + outer loop + vertex 0.995006 0.924998 2.56675 + vertex 0.989719 0.925681 2.56681 + vertex 0.991512 0.92137 2.56553 + endloop + endfacet + facet normal -0.0262216 -0.290972 0.956372 + outer loop + vertex 0.995006 0.924998 2.56675 + vertex 0.994054 0.929223 2.568 + vertex 0.989719 0.925681 2.56681 + endloop + endfacet + facet normal -0.016985 -0.301269 0.953388 + outer loop + vertex 0.989719 0.925681 2.56681 + vertex 0.994054 0.929223 2.568 + vertex 0.989838 0.929817 2.56812 + endloop + endfacet + facet normal -0.0152994 -0.289969 0.956914 + outer loop + vertex 0.994054 0.929223 2.568 + vertex 0.992849 0.933959 2.56942 + vertex 0.989838 0.929817 2.56812 + endloop + endfacet + facet normal -0.0320582 -0.278707 0.959841 + outer loop + vertex 0.989838 0.929817 2.56812 + vertex 0.992849 0.933959 2.56942 + vertex 0.988005 0.932272 2.56877 + endloop + endfacet + facet normal -0.0287901 -0.309063 0.950606 + outer loop + vertex 0.992006 0.937486 2.57055 + vertex 0.990174 0.939438 2.57113 + vertex 0.988092 0.936044 2.56996 + endloop + endfacet + facet normal -0.0283888 -0.31003 0.950303 + outer loop + vertex 0.992006 0.937486 2.57055 + vertex 0.988092 0.936044 2.56996 + vertex 0.992849 0.933959 2.56942 + endloop + endfacet + facet normal -0.0237222 -0.300231 0.953571 + outer loop + vertex 0.992849 0.933959 2.56942 + vertex 0.988092 0.936044 2.56996 + vertex 0.988005 0.932272 2.56877 + endloop + endfacet + facet normal 0.0161699 -0.270447 0.962599 + outer loop + vertex 0.992006 0.937486 2.57055 + vertex 0.994209 0.940929 2.57148 + vertex 0.990174 0.939438 2.57113 + endloop + endfacet + facet normal -0.0510408 -0.296471 0.953677 + outer loop + vertex 0.988092 0.936044 2.56996 + vertex 0.990174 0.939438 2.57113 + vertex 0.986359 0.940008 2.5711 + endloop + endfacet + facet normal -0.047317 -0.27119 0.961362 + outer loop + vertex 0.990174 0.939438 2.57113 + vertex 0.990528 0.943551 2.5723 + vertex 0.986359 0.940008 2.5711 + endloop + endfacet + facet normal 0.0186343 -0.27669 0.960778 + outer loop + vertex 0.990174 0.939438 2.57113 + vertex 0.994209 0.940929 2.57148 + vertex 0.990528 0.943551 2.5723 + endloop + endfacet + facet normal 0.0279162 -0.264654 0.963939 + outer loop + vertex 0.994209 0.940929 2.57148 + vertex 0.995342 0.945023 2.57257 + vertex 0.990528 0.943551 2.5723 + endloop + endfacet + facet normal 0.0320774 -0.277588 0.960164 + outer loop + vertex 0.995342 0.945023 2.57257 + vertex 0.994083 0.948389 2.57358 + vertex 0.990528 0.943551 2.5723 + endloop + endfacet + facet normal 0.409476 0.0267934 0.911928 + outer loop + vertex 0.992275 1.63135 2.63619 + vertex 0.991024 1.62699 2.63688 + vertex 0.994262 1.62918 2.63536 + endloop + endfacet + facet normal 0.363184 0.0623215 0.929631 + outer loop + vertex 0.989396 1.69884 2.63452 + vertex 0.993294 1.70152 2.63282 + vertex 0.989058 1.70378 2.63432 + endloop + endfacet + facet normal 0.355538 0.0453453 0.933561 + outer loop + vertex 0.993294 1.70152 2.63282 + vertex 0.992598 1.70713 2.63281 + vertex 0.989058 1.70378 2.63432 + endloop + endfacet + facet normal 0.316612 0.0231875 0.948272 + outer loop + vertex 0.994874 1.75367 2.62958 + vertex 0.99471 1.75878 2.62951 + vertex 0.991329 1.7555 2.63071 + endloop + endfacet + facet normal 0.2166 0.0361637 0.97559 + outer loop + vertex 0.987505 1.75678 2.63152 + vertex 0.987756 1.75166 2.63165 + vertex 0.991329 1.7555 2.63071 + endloop + endfacet + facet normal 0.307717 0.0214082 0.951237 + outer loop + vertex 0.99471 1.75878 2.62951 + vertex 0.994276 1.76395 2.62953 + vertex 0.991018 1.76053 2.63066 + endloop + endfacet + facet normal 0.31113 0.0294535 0.949911 + outer loop + vertex 0.991329 1.7555 2.63071 + vertex 0.99471 1.75878 2.62951 + vertex 0.991018 1.76053 2.63066 + endloop + endfacet + facet normal 0.212691 0.0236575 0.976833 + outer loop + vertex 0.991018 1.76053 2.63066 + vertex 0.987505 1.75678 2.63152 + vertex 0.991329 1.7555 2.63071 + endloop + endfacet + facet normal 0.192837 0.0430166 0.980288 + outer loop + vertex 0.987075 1.76176 2.63138 + vertex 0.987505 1.75678 2.63152 + vertex 0.991018 1.76053 2.63066 + endloop + endfacet + facet normal 0.281708 0.0481891 0.958289 + outer loop + vertex 0.994276 1.76395 2.62953 + vertex 0.993318 1.76938 2.62954 + vertex 0.990316 1.76544 2.63062 + endloop + endfacet + facet normal 0.281789 0.0484346 0.958253 + outer loop + vertex 0.991018 1.76053 2.63066 + vertex 0.994276 1.76395 2.62953 + vertex 0.990316 1.76544 2.63062 + endloop + endfacet + facet normal 0.190655 0.0355698 0.981012 + outer loop + vertex 0.990316 1.76544 2.63062 + vertex 0.987075 1.76176 2.63138 + vertex 0.991018 1.76053 2.63066 + endloop + endfacet + facet normal 0.159127 0.0642292 0.985167 + outer loop + vertex 0.985847 1.76692 2.63124 + vertex 0.987075 1.76176 2.63138 + vertex 0.990316 1.76544 2.63062 + endloop + endfacet + facet normal 0.248289 0.0756559 0.965727 + outer loop + vertex 0.989161 1.76941 2.6306 + vertex 0.990316 1.76544 2.63062 + vertex 0.993318 1.76938 2.62954 + endloop + endfacet + facet normal 0.247908 0.101899 0.96341 + outer loop + vertex 0.989161 1.76941 2.6306 + vertex 0.993318 1.76938 2.62954 + vertex 0.989356 1.77401 2.63007 + endloop + endfacet + facet normal 0.221636 0.0784128 0.971972 + outer loop + vertex 0.989356 1.77401 2.63007 + vertex 0.993318 1.76938 2.62954 + vertex 0.994257 1.77385 2.62896 + endloop + endfacet + facet normal 0.154087 0.0483912 0.986872 + outer loop + vertex 0.990316 1.76544 2.63062 + vertex 0.989161 1.76941 2.6306 + vertex 0.985847 1.76692 2.63124 + endloop + endfacet + facet normal 0.22154 0.0717104 0.972511 + outer loop + vertex 0.994257 1.77385 2.62896 + vertex 0.993464 1.7777 2.62886 + vertex 0.989356 1.77401 2.63007 + endloop + endfacet + facet normal -0.000753486 0.274169 0.961681 + outer loop + vertex 0.98728 2.07648 2.57225 + vertex 0.991441 2.07529 2.5726 + vertex 0.99245 2.07929 2.57146 + endloop + endfacet + facet normal -0.0174171 0.297962 0.954419 + outer loop + vertex 0.990665 2.09833 2.56551 + vertex 0.995519 2.09846 2.56556 + vertex 0.99414 2.10232 2.56433 + endloop + endfacet + facet normal -0.0729806 0.341222 0.937145 + outer loop + vertex 0.988254 2.10137 2.56421 + vertex 0.990665 2.09833 2.56551 + vertex 0.99414 2.10232 2.56433 + endloop + endfacet + facet normal -0.0456808 0.30214 0.952169 + outer loop + vertex 0.991869 2.09478 2.56669 + vertex 0.990665 2.09833 2.56551 + vertex 0.987345 2.09469 2.5665 + endloop + endfacet + facet normal -0.0177319 0.310974 0.950253 + outer loop + vertex 0.995519 2.09846 2.56556 + vertex 0.990665 2.09833 2.56551 + vertex 0.991869 2.09478 2.56669 + endloop + endfacet + facet normal -0.0645362 0.286678 0.955851 + outer loop + vertex 0.99414 2.10232 2.56433 + vertex 0.992707 2.10633 2.56303 + vertex 0.988254 2.10137 2.56421 + endloop + endfacet + facet normal -0.109644 0.708907 0.696727 + outer loop + vertex 0.989643 2.12359 2.55455 + vertex 0.994574 2.12349 2.55543 + vertex 0.992096 2.12576 2.55272 + endloop + endfacet + facet normal -0.0832205 0.694298 0.71486 + outer loop + vertex 0.989252 2.12577 2.55239 + vertex 0.989643 2.12359 2.55455 + vertex 0.992096 2.12576 2.55272 + endloop + endfacet + facet normal -0.20518 0.556021 0.805445 + outer loop + vertex 0.991667 2.12032 2.55732 + vertex 0.989643 2.12359 2.55455 + vertex 0.987178 2.11986 2.55649 + endloop + endfacet + facet normal -0.129365 0.593545 0.794336 + outer loop + vertex 0.994574 2.12349 2.55543 + vertex 0.989643 2.12359 2.55455 + vertex 0.991667 2.12032 2.55732 + endloop + endfacet + facet normal 0.0177904 0.768339 0.639795 + outer loop + vertex 0.990025 2.13039 2.54252 + vertex 0.995109 2.13041 2.54235 + vertex 0.992018 2.13255 2.53986 + endloop + endfacet + facet normal -0.118673 0.811362 0.572371 + outer loop + vertex 0.986797 2.13218 2.5393 + vertex 0.990025 2.13039 2.54252 + vertex 0.992018 2.13255 2.53986 + endloop + endfacet + facet normal 0.00828366 0.925935 0.377593 + outer loop + vertex 0.995109 2.13041 2.54235 + vertex 0.990025 2.13039 2.54252 + vertex 0.993828 2.12889 2.5461 + endloop + endfacet + facet normal -0.00675884 0.920277 0.39121 + outer loop + vertex 0.993828 2.12889 2.5461 + vertex 0.990025 2.13039 2.54252 + vertex 0.988973 2.12877 2.54629 + endloop + endfacet + facet normal -0.00773722 0.928271 0.371823 + outer loop + vertex 0.993828 2.12889 2.5461 + vertex 0.988973 2.12877 2.54629 + vertex 0.993013 2.12742 2.54975 + endloop + endfacet + facet normal -0.0458106 0.911096 0.409641 + outer loop + vertex 0.993013 2.12742 2.54975 + vertex 0.988973 2.12877 2.54629 + vertex 0.988892 2.12709 2.55002 + endloop + endfacet + facet normal -0.0565312 0.867174 0.494786 + outer loop + vertex 0.992096 2.12576 2.55272 + vertex 0.988892 2.12709 2.55002 + vertex 0.989252 2.12577 2.55239 + endloop + endfacet + facet normal -0.0385688 0.877252 0.478478 + outer loop + vertex 0.993013 2.12742 2.54975 + vertex 0.988892 2.12709 2.55002 + vertex 0.992096 2.12576 2.55272 + endloop + endfacet + facet normal -0.100376 -0.0886639 0.990991 + outer loop + vertex 0.992018 2.13255 2.53986 + vertex 0.99 2.13636 2.54 + vertex 0.986797 2.13218 2.5393 + endloop + endfacet + facet normal 0.00261429 -0.034395 0.999405 + outer loop + vertex 0.995 2.13674 2.54 + vertex 0.99 2.13636 2.54 + vertex 0.992018 2.13255 2.53986 + endloop + endfacet + facet normal 0.0609671 -0.992873 -0.102405 + outer loop + vertex 1 0.892156 2.54 + vertex 0.99812 0.89181 2.54224 + vertex 0.995 0.891849 2.54 + endloop + endfacet + facet normal 0.0445252 -0.995838 -0.0795211 + outer loop + vertex 0.99812 0.89181 2.54224 + vertex 0.994045 0.891585 2.54277 + vertex 0.995 0.891849 2.54 + endloop + endfacet + facet normal 0.0767213 -0.982186 0.171538 + outer loop + vertex 0.99812 0.89181 2.54224 + vertex 0.996794 0.892353 2.54594 + vertex 0.994045 0.891585 2.54277 + endloop + endfacet + facet normal 0.0155472 -0.974733 0.222831 + outer loop + vertex 0.996794 0.892353 2.54594 + vertex 0.991898 0.892231 2.54575 + vertex 0.994045 0.891585 2.54277 + endloop + endfacet + facet normal 0.0113207 -0.949281 0.314224 + outer loop + vertex 0.996794 0.892353 2.54594 + vertex 0.995199 0.893455 2.54932 + vertex 0.991898 0.892231 2.54575 + endloop + endfacet + facet normal 0.00485044 -0.950238 0.311488 + outer loop + vertex 1.00018 0.89347 2.54929 + vertex 0.995199 0.893455 2.54932 + vertex 0.996794 0.892353 2.54594 + endloop + endfacet + facet normal 0.00551286 -0.895607 0.444812 + outer loop + vertex 0.995199 0.893455 2.54932 + vertex 1.00018 0.89347 2.54929 + vertex 0.998594 0.894971 2.55233 + endloop + endfacet + facet normal -0.0492993 -0.868606 0.493044 + outer loop + vertex 0.993451 0.895191 2.55221 + vertex 0.995199 0.893455 2.54932 + vertex 0.998594 0.894971 2.55233 + endloop + endfacet + facet normal -0.0487165 -0.78108 0.622527 + outer loop + vertex 0.998594 0.894971 2.55233 + vertex 0.996769 0.89714 2.55491 + vertex 0.993451 0.895191 2.55221 + endloop + endfacet + facet normal -0.0824157 -0.757888 0.647158 + outer loop + vertex 0.996769 0.89714 2.55491 + vertex 0.991894 0.897398 2.55459 + vertex 0.993451 0.895191 2.55221 + endloop + endfacet + facet normal -0.0838141 -0.640587 0.763297 + outer loop + vertex 0.996769 0.89714 2.55491 + vertex 0.994344 0.900122 2.55715 + vertex 0.991894 0.897398 2.55459 + endloop + endfacet + facet normal -0.0414945 -0.62083 0.782846 + outer loop + vertex 0.999913 0.899828 2.55721 + vertex 0.994344 0.900122 2.55715 + vertex 0.996769 0.89714 2.55491 + endloop + endfacet + facet normal -0.0376473 -0.535399 0.84376 + outer loop + vertex 0.999913 0.899828 2.55721 + vertex 0.998091 0.903057 2.55918 + vertex 0.994344 0.900122 2.55715 + endloop + endfacet + facet normal -0.072833 -0.50267 0.861405 + outer loop + vertex 0.994344 0.900122 2.55715 + vertex 0.998091 0.903057 2.55918 + vertex 0.993317 0.903935 2.55929 + endloop + endfacet + facet normal -0.0597383 -0.435999 0.897962 + outer loop + vertex 0.993317 0.903935 2.55929 + vertex 0.998091 0.903057 2.55918 + vertex 0.996576 0.906556 2.56078 + endloop + endfacet + facet normal -0.0741919 -0.421375 0.903847 + outer loop + vertex 0.992653 0.90705 2.56069 + vertex 0.993317 0.903935 2.55929 + vertex 0.996576 0.906556 2.56078 + endloop + endfacet + facet normal -0.0657511 -0.348625 0.934953 + outer loop + vertex 0.996576 0.906556 2.56078 + vertex 0.994709 0.910439 2.56209 + vertex 0.992653 0.90705 2.56069 + endloop + endfacet + facet normal -0.0119883 -0.326253 0.945206 + outer loop + vertex 0.999937 0.909999 2.56201 + vertex 0.994709 0.910439 2.56209 + vertex 0.996576 0.906556 2.56078 + endloop + endfacet + facet normal -0.0101666 -0.305965 0.951988 + outer loop + vertex 0.999937 0.909999 2.56201 + vertex 0.998949 0.914019 2.56329 + vertex 0.994709 0.910439 2.56209 + endloop + endfacet + facet normal 0.00243304 -0.31943 0.947607 + outer loop + vertex 0.994709 0.910439 2.56209 + vertex 0.998949 0.914019 2.56329 + vertex 0.994859 0.914391 2.56343 + endloop + endfacet + facet normal 0.0041968 -0.302102 0.953266 + outer loop + vertex 0.998949 0.914019 2.56329 + vertex 0.997798 0.917718 2.56447 + vertex 0.994859 0.914391 2.56343 + endloop + endfacet + facet normal -0.0149556 -0.286637 0.957922 + outer loop + vertex 0.994859 0.914391 2.56343 + vertex 0.997798 0.917718 2.56447 + vertex 0.993035 0.917487 2.56432 + endloop + endfacet + facet normal -0.0136241 -0.309705 0.950735 + outer loop + vertex 0.993035 0.917487 2.56432 + vertex 0.997798 0.917718 2.56447 + vertex 0.996296 0.921166 2.56557 + endloop + endfacet + facet normal -0.0198572 -0.30469 0.952244 + outer loop + vertex 0.991512 0.92137 2.56553 + vertex 0.993035 0.917487 2.56432 + vertex 0.996296 0.921166 2.56557 + endloop + endfacet + facet normal -0.0196431 -0.299376 0.953933 + outer loop + vertex 0.996296 0.921166 2.56557 + vertex 0.995006 0.924998 2.56675 + vertex 0.991512 0.92137 2.56553 + endloop + endfacet + facet normal 0.0336289 -0.282857 0.958572 + outer loop + vertex 0.999877 0.925032 2.56658 + vertex 0.995006 0.924998 2.56675 + vertex 0.996296 0.921166 2.56557 + endloop + endfacet + facet normal 0.0336431 -0.277279 0.9602 + outer loop + vertex 0.999877 0.925032 2.56658 + vertex 0.999045 0.928991 2.56776 + vertex 0.995006 0.924998 2.56675 + endloop + endfacet + facet normal 0.0347201 -0.278285 0.959871 + outer loop + vertex 0.995006 0.924998 2.56675 + vertex 0.999045 0.928991 2.56776 + vertex 0.994054 0.929223 2.568 + endloop + endfacet + facet normal 0.0349123 -0.275114 0.960778 + outer loop + vertex 0.999045 0.928991 2.56776 + vertex 0.998281 0.933213 2.56899 + vertex 0.994054 0.929223 2.568 + endloop + endfacet + facet normal 0.037339 -0.277492 0.960002 + outer loop + vertex 0.994054 0.929223 2.568 + vertex 0.998281 0.933213 2.56899 + vertex 0.992849 0.933959 2.56942 + endloop + endfacet + facet normal 0.198546 -0.0965781 0.975322 + outer loop + vertex 0.993551 1.23324 2.6278 + vertex 0.998057 1.23819 2.62738 + vertex 0.993485 1.23817 2.62831 + endloop + endfacet + facet normal 0.198895 -0.0722931 0.977351 + outer loop + vertex 0.998057 1.23819 2.62738 + vertex 0.998014 1.24303 2.62774 + vertex 0.993485 1.23817 2.62831 + endloop + endfacet + facet normal 0.212851 -0.0857818 0.973312 + outer loop + vertex 0.993485 1.23817 2.62831 + vertex 0.998014 1.24303 2.62774 + vertex 0.993472 1.24313 2.62875 + endloop + endfacet + facet normal 0.213975 -0.0548548 0.975298 + outer loop + vertex 0.998014 1.24303 2.62774 + vertex 0.998025 1.24798 2.62802 + vertex 0.993472 1.24313 2.62875 + endloop + endfacet + facet normal 0.22621 -0.0668707 0.971781 + outer loop + vertex 0.993472 1.24313 2.62875 + vertex 0.998025 1.24798 2.62802 + vertex 0.993493 1.2482 2.62909 + endloop + endfacet + facet normal 0.227974 -0.0365769 0.97298 + outer loop + vertex 0.998025 1.24798 2.62802 + vertex 0.998021 1.25303 2.62821 + vertex 0.993493 1.2482 2.62909 + endloop + endfacet + facet normal 0.249652 -0.0580406 0.966595 + outer loop + vertex 0.993493 1.2482 2.62909 + vertex 0.998021 1.25303 2.62821 + vertex 0.993541 1.2534 2.62939 + endloop + endfacet + facet normal 0.251586 -0.0363232 0.967153 + outer loop + vertex 0.998021 1.25303 2.62821 + vertex 0.998058 1.25822 2.6284 + vertex 0.993541 1.2534 2.62939 + endloop + endfacet + facet normal 0.444685 -0.000558055 0.895687 + outer loop + vertex 1.00001 1.47426 2.63483 + vertex 0.999995 1.47926 2.63484 + vertex 0.996663 1.47597 2.63649 + endloop + endfacet + facet normal 0.443494 0.000966726 0.896277 + outer loop + vertex 0.999995 1.47926 2.63484 + vertex 0.999989 1.48425 2.63483 + vertex 0.99664 1.48096 2.63649 + endloop + endfacet + facet normal 0.443489 0.000953601 0.896279 + outer loop + vertex 0.996663 1.47597 2.63649 + vertex 0.999995 1.47926 2.63484 + vertex 0.99664 1.48096 2.63649 + endloop + endfacet + facet normal 0.443616 0.000813097 0.896217 + outer loop + vertex 0.99664 1.48096 2.63649 + vertex 0.999989 1.48425 2.63483 + vertex 0.996687 1.48595 2.63647 + endloop + endfacet + facet normal 0.447569 0.00559412 0.894232 + outer loop + vertex 0.999458 1.50952 2.63517 + vertex 1.00014 1.51338 2.63481 + vertex 0.997579 1.51141 2.6361 + endloop + endfacet + facet normal 0.447233 0.00614209 0.894397 + outer loop + vertex 1.00014 1.51338 2.63481 + vertex 0.997343 1.51371 2.63621 + vertex 0.997579 1.51141 2.6361 + endloop + endfacet + facet normal 0.438933 -0.000210753 0.89852 + outer loop + vertex 0.997543 1.52175 2.63606 + vertex 0.997214 1.51738 2.63622 + vertex 0.999359 1.52027 2.63518 + endloop + endfacet + facet normal 0.410472 0.0286731 0.911422 + outer loop + vertex 0.991024 1.62699 2.63688 + vertex 0.991581 1.62168 2.6368 + vertex 0.994712 1.62523 2.63528 + endloop + endfacet + facet normal 0.409636 0.0265113 0.911864 + outer loop + vertex 0.994712 1.62523 2.63528 + vertex 0.994262 1.62918 2.63536 + vertex 0.991024 1.62699 2.63688 + endloop + endfacet + facet normal 0.393539 0.0252569 0.918961 + outer loop + vertex 0.994874 1.75367 2.62958 + vertex 0.998585 1.75638 2.62791 + vertex 0.99471 1.75878 2.62951 + endloop + endfacet + facet normal 0.387498 0.0136327 0.92177 + outer loop + vertex 0.998585 1.75638 2.62791 + vertex 0.998074 1.76203 2.62804 + vertex 0.99471 1.75878 2.62951 + endloop + endfacet + facet normal 0.376198 0.0272742 0.926138 + outer loop + vertex 0.99471 1.75878 2.62951 + vertex 0.998074 1.76203 2.62804 + vertex 0.994276 1.76395 2.62953 + endloop + endfacet + facet normal 0.373011 0.0198336 0.927615 + outer loop + vertex 0.998074 1.76203 2.62804 + vertex 0.997701 1.7672 2.62808 + vertex 0.994276 1.76395 2.62953 + endloop + endfacet + facet normal 0.34072 0.0586328 0.938335 + outer loop + vertex 0.994276 1.76395 2.62953 + vertex 0.997701 1.7672 2.62808 + vertex 0.993318 1.76938 2.62954 + endloop + endfacet + facet normal 0.248833 0.0925454 0.964115 + outer loop + vertex 0.993105 1.78225 2.62854 + vertex 0.997035 1.78636 2.62713 + vertex 0.992907 1.78703 2.62814 + endloop + endfacet + facet normal 0.246042 0.0714093 0.966625 + outer loop + vertex 0.997035 1.78636 2.62713 + vertex 0.997011 1.79145 2.62676 + vertex 0.992907 1.78703 2.62814 + endloop + endfacet + facet normal 0.224234 0.0927571 0.970111 + outer loop + vertex 0.992907 1.78703 2.62814 + vertex 0.997011 1.79145 2.62676 + vertex 0.992893 1.79203 2.62766 + endloop + endfacet + facet normal 0.22241 0.0771913 0.971893 + outer loop + vertex 0.997011 1.79145 2.62676 + vertex 0.996774 1.79651 2.62642 + vertex 0.992893 1.79203 2.62766 + endloop + endfacet + facet normal 0.196782 0.10035 0.975298 + outer loop + vertex 0.992893 1.79203 2.62766 + vertex 0.996774 1.79651 2.62642 + vertex 0.992631 1.79694 2.62721 + endloop + endfacet + facet normal 0.195864 0.0893335 0.976553 + outer loop + vertex 0.996774 1.79651 2.62642 + vertex 0.99579 1.80164 2.62614 + vertex 0.992631 1.79694 2.62721 + endloop + endfacet + facet normal 0.160205 0.114199 0.980455 + outer loop + vertex 0.992631 1.79694 2.62721 + vertex 0.99579 1.80164 2.62614 + vertex 0.991705 1.80086 2.6269 + endloop + endfacet + facet normal 0.15971 0.116604 0.980253 + outer loop + vertex 0.992173 1.80537 2.62629 + vertex 0.991705 1.80086 2.6269 + vertex 0.99579 1.80164 2.62614 + endloop + endfacet + facet normal 0.00940102 0.302509 0.9531 + outer loop + vertex 0.992652 2.09079 2.56795 + vertex 0.997046 2.09438 2.56677 + vertex 0.991869 2.09478 2.56669 + endloop + endfacet + facet normal 0.0275612 0.288467 0.957093 + outer loop + vertex 0.995519 2.09846 2.56556 + vertex 0.999545 2.09804 2.56557 + vertex 0.999765 2.10208 2.56434 + endloop + endfacet + facet normal 0.0102394 0.306966 0.951665 + outer loop + vertex 0.99414 2.10232 2.56433 + vertex 0.995519 2.09846 2.56556 + vertex 0.999765 2.10208 2.56434 + endloop + endfacet + facet normal 0.00817901 0.28762 0.95771 + outer loop + vertex 0.997046 2.09438 2.56677 + vertex 0.995519 2.09846 2.56556 + vertex 0.991869 2.09478 2.56669 + endloop + endfacet + facet normal 0.0281808 0.294369 0.955276 + outer loop + vertex 0.999545 2.09804 2.56557 + vertex 0.995519 2.09846 2.56556 + vertex 0.997046 2.09438 2.56677 + endloop + endfacet + facet normal 0.00866518 0.270738 0.962614 + outer loop + vertex 0.999765 2.10208 2.56434 + vertex 0.997972 2.10646 2.56313 + vertex 0.99414 2.10232 2.56433 + endloop + endfacet + facet normal -0.0256026 0.299895 0.953629 + outer loop + vertex 0.99414 2.10232 2.56433 + vertex 0.997972 2.10646 2.56313 + vertex 0.992707 2.10633 2.56303 + endloop + endfacet + facet normal -0.0250764 0.271575 0.962091 + outer loop + vertex 0.997972 2.10646 2.56313 + vertex 0.996642 2.11042 2.56198 + vertex 0.992707 2.10633 2.56303 + endloop + endfacet + facet normal -0.0753262 0.44946 0.890119 + outer loop + vertex 0.998538 2.11743 2.55951 + vertex 0.996691 2.12057 2.55777 + vertex 0.992911 2.11655 2.55948 + endloop + endfacet + facet normal -0.101331 0.468594 0.877583 + outer loop + vertex 0.992911 2.11655 2.55948 + vertex 0.996691 2.12057 2.55777 + vertex 0.991667 2.12032 2.55732 + endloop + endfacet + facet normal -0.0255784 0.755507 0.654641 + outer loop + vertex 0.994574 2.12349 2.55543 + vertex 0.999535 2.12348 2.55563 + vertex 0.99659 2.12573 2.55292 + endloop + endfacet + facet normal -0.0231035 0.75458 0.655801 + outer loop + vertex 0.992096 2.12576 2.55272 + vertex 0.994574 2.12349 2.55543 + vertex 0.99659 2.12573 2.55292 + endloop + endfacet + facet normal -0.100678 0.57693 0.810565 + outer loop + vertex 0.996691 2.12057 2.55777 + vertex 0.994574 2.12349 2.55543 + vertex 0.991667 2.12032 2.55732 + endloop + endfacet + facet normal -0.031361 0.6113 0.790777 + outer loop + vertex 0.999535 2.12348 2.55563 + vertex 0.994574 2.12349 2.55543 + vertex 0.996691 2.12057 2.55777 + endloop + endfacet + facet normal 0.00781133 0.731809 0.681465 + outer loop + vertex 0.995109 2.13041 2.54235 + vertex 1.00074 2.13088 2.54178 + vertex 0.997013 2.13277 2.53979 + endloop + endfacet + facet normal -0.0230523 0.743061 0.668826 + outer loop + vertex 0.992018 2.13255 2.53986 + vertex 0.995109 2.13041 2.54235 + vertex 0.997013 2.13277 2.53979 + endloop + endfacet + facet normal -0.030385 0.898381 0.438164 + outer loop + vertex 1.00074 2.13088 2.54178 + vertex 0.995109 2.13041 2.54235 + vertex 0.998926 2.12884 2.54582 + endloop + endfacet + facet normal 0.029395 0.923022 0.383623 + outer loop + vertex 0.998926 2.12884 2.54582 + vertex 0.995109 2.13041 2.54235 + vertex 0.993828 2.12889 2.5461 + endloop + endfacet + facet normal 0.028219 0.932493 0.360084 + outer loop + vertex 0.998926 2.12884 2.54582 + vertex 0.993828 2.12889 2.5461 + vertex 0.99784 2.1274 2.54965 + endloop + endfacet + facet normal 0.0122781 0.926679 0.375654 + outer loop + vertex 0.99784 2.1274 2.54965 + vertex 0.993828 2.12889 2.5461 + vertex 0.993013 2.12742 2.54975 + endloop + endfacet + facet normal -0.0149414 0.874746 0.484352 + outer loop + vertex 0.99659 2.12573 2.55292 + vertex 0.993013 2.12742 2.54975 + vertex 0.992096 2.12576 2.55272 + endloop + endfacet + facet normal 0.0138234 0.888274 0.459106 + outer loop + vertex 0.99784 2.1274 2.54965 + vertex 0.993013 2.12742 2.54975 + vertex 0.99659 2.12573 2.55292 + endloop + endfacet + facet normal 0.0157276 -0.0437125 0.99892 + outer loop + vertex 0.997013 2.13277 2.53979 + vertex 0.995 2.13674 2.54 + vertex 0.992018 2.13255 2.53986 + endloop + endfacet + facet normal -0.00814538 -0.0557873 0.998409 + outer loop + vertex 1 2.13601 2.54 + vertex 0.995 2.13674 2.54 + vertex 0.997013 2.13277 2.53979 + endloop + endfacet + facet normal 0.0840989 -0.984746 -0.152326 + outer loop + vertex 1.005 0.892583 2.54 + vertex 1.00288 0.892083 2.54206 + vertex 1 0.892156 2.54 + endloop + endfacet + facet normal 0.0529817 -0.99262 -0.10908 + outer loop + vertex 1.00288 0.892083 2.54206 + vertex 0.99812 0.89181 2.54224 + vertex 1 0.892156 2.54 + endloop + endfacet + facet normal 0.0618958 -0.988389 0.138766 + outer loop + vertex 1.00288 0.892083 2.54206 + vertex 1.00154 0.89251 2.5457 + vertex 0.99812 0.89181 2.54224 + endloop + endfacet + facet normal 0.0407438 -0.986394 0.159267 + outer loop + vertex 1.00154 0.89251 2.5457 + vertex 0.996794 0.892353 2.54594 + vertex 0.99812 0.89181 2.54224 + endloop + endfacet + facet normal 0.0456486 -0.960697 0.27382 + outer loop + vertex 1.00154 0.89251 2.5457 + vertex 1.00018 0.89347 2.54929 + vertex 0.996794 0.892353 2.54594 + endloop + endfacet + facet normal 0.0356019 -0.962095 0.270382 + outer loop + vertex 1.00496 0.893577 2.54904 + vertex 1.00018 0.89347 2.54929 + vertex 1.00154 0.89251 2.5457 + endloop + endfacet + facet normal 0.0426993 -0.9007 0.432339 + outer loop + vertex 1.00018 0.89347 2.54929 + vertex 1.00496 0.893577 2.54904 + vertex 1.00348 0.894981 2.55212 + endloop + endfacet + facet normal 0.0221726 -0.891912 0.451666 + outer loop + vertex 0.998594 0.894971 2.55233 + vertex 1.00018 0.89347 2.54929 + vertex 1.00348 0.894981 2.55212 + endloop + endfacet + facet normal 0.0295671 -0.782951 0.621381 + outer loop + vertex 1.00348 0.894981 2.55212 + vertex 1.00189 0.897097 2.55486 + vertex 0.998594 0.894971 2.55233 + endloop + endfacet + facet normal 0.000677178 -0.765037 0.643986 + outer loop + vertex 1.00189 0.897097 2.55486 + vertex 0.996769 0.89714 2.55491 + vertex 0.998594 0.894971 2.55233 + endloop + endfacet + facet normal 0.0028922 -0.651818 0.75837 + outer loop + vertex 1.00189 0.897097 2.55486 + vertex 0.999913 0.899828 2.55721 + vertex 0.996769 0.89714 2.55491 + endloop + endfacet + facet normal 0.0459958 -0.633048 0.772745 + outer loop + vertex 1.00509 0.900009 2.55705 + vertex 0.999913 0.899828 2.55721 + vertex 1.00189 0.897097 2.55486 + endloop + endfacet + facet normal 0.044679 -0.530514 0.846498 + outer loop + vertex 1.00509 0.900009 2.55705 + vertex 1.0032 0.903078 2.55908 + vertex 0.999913 0.899828 2.55721 + endloop + endfacet + facet normal 0.01962 -0.512173 0.858658 + outer loop + vertex 0.999913 0.899828 2.55721 + vertex 1.0032 0.903078 2.55908 + vertex 0.998091 0.903057 2.55918 + endloop + endfacet + facet normal 0.0201645 -0.429835 0.902682 + outer loop + vertex 0.998091 0.903057 2.55918 + vertex 1.0032 0.903078 2.55908 + vertex 1.00139 0.90632 2.56066 + endloop + endfacet + facet normal 0.00198698 -0.414738 0.909939 + outer loop + vertex 0.996576 0.906556 2.56078 + vertex 0.998091 0.903057 2.55918 + vertex 1.00139 0.90632 2.56066 + endloop + endfacet + facet normal 0.00627222 -0.342092 0.939645 + outer loop + vertex 1.00139 0.90632 2.56066 + vertex 0.999937 0.909999 2.56201 + vertex 0.996576 0.906556 2.56078 + endloop + endfacet + facet normal 0.0460778 -0.327802 0.943622 + outer loop + vertex 1.00487 0.910009 2.56177 + vertex 0.999937 0.909999 2.56201 + vertex 1.00139 0.90632 2.56066 + endloop + endfacet + facet normal 0.0465977 -0.288881 0.95623 + outer loop + vertex 1.00487 0.910009 2.56177 + vertex 1.00396 0.914034 2.56303 + vertex 0.999937 0.909999 2.56201 + endloop + endfacet + facet normal 0.0501563 -0.292131 0.955062 + outer loop + vertex 0.999937 0.909999 2.56201 + vertex 1.00396 0.914034 2.56303 + vertex 0.998949 0.914019 2.56329 + endloop + endfacet + facet normal 0.0502412 -0.285264 0.957131 + outer loop + vertex 1.00396 0.914034 2.56303 + vertex 1.00322 0.918583 2.56443 + vertex 0.998949 0.914019 2.56329 + endloop + endfacet + facet normal 0.0531919 -0.287794 0.956214 + outer loop + vertex 0.998949 0.914019 2.56329 + vertex 1.00322 0.918583 2.56443 + vertex 0.997798 0.917718 2.56447 + endloop + endfacet + facet normal 0.071629 -0.277011 0.958193 + outer loop + vertex 1.00435 0.925315 2.56633 + vertex 0.999877 0.925032 2.56658 + vertex 1.00099 0.921609 2.56551 + endloop + endfacet + facet normal 0.21525 -0.114161 0.969863 + outer loop + vertex 0.998427 1.19326 2.62364 + vertex 1.0031 1.19814 2.62318 + vertex 0.998596 1.19829 2.6242 + endloop + endfacet + facet normal 0.216581 -0.0895995 0.972144 + outer loop + vertex 1.0031 1.19814 2.62318 + vertex 1.00323 1.20314 2.62361 + vertex 0.998596 1.19829 2.6242 + endloop + endfacet + facet normal 0.23633 -0.109295 0.965506 + outer loop + vertex 0.998596 1.19829 2.6242 + vertex 1.00323 1.20314 2.62361 + vertex 0.99882 1.20327 2.6247 + endloop + endfacet + facet normal 0.237727 -0.081986 0.967866 + outer loop + vertex 1.00323 1.20314 2.62361 + vertex 1.00335 1.20821 2.62401 + vertex 0.99882 1.20327 2.6247 + endloop + endfacet + facet normal 0.266513 -0.109838 0.957552 + outer loop + vertex 0.99882 1.20327 2.6247 + vertex 1.00335 1.20821 2.62401 + vertex 0.99897 1.20826 2.62523 + endloop + endfacet + facet normal 0.225733 -0.0927201 0.969767 + outer loop + vertex 0.999507 1.21232 2.6255 + vertex 0.997032 1.20986 2.62584 + vertex 0.99897 1.20826 2.62523 + endloop + endfacet + facet normal 0.305764 -0.101792 0.94665 + outer loop + vertex 0.999507 1.21232 2.6255 + vertex 0.99897 1.20826 2.62523 + vertex 1.00335 1.21376 2.62441 + endloop + endfacet + facet normal 0.267903 -0.0695227 0.960934 + outer loop + vertex 1.00335 1.21376 2.62441 + vertex 0.99897 1.20826 2.62523 + vertex 1.00335 1.20821 2.62401 + endloop + endfacet + facet normal 0.179099 -0.0440298 0.982845 + outer loop + vertex 0.999507 1.21232 2.6255 + vertex 0.996933 1.21302 2.626 + vertex 0.997032 1.20986 2.62584 + endloop + endfacet + facet normal 0.298877 -0.0416174 0.953384 + outer loop + vertex 1.00335 1.21376 2.62441 + vertex 1.00452 1.21979 2.62431 + vertex 1.00049 1.21635 2.62542 + endloop + endfacet + facet normal 0.28985 -0.0524866 0.955632 + outer loop + vertex 0.999507 1.21232 2.6255 + vertex 1.00335 1.21376 2.62441 + vertex 1.00049 1.21635 2.62542 + endloop + endfacet + facet normal 0.183881 -0.0261644 0.9826 + outer loop + vertex 1.00049 1.21635 2.62542 + vertex 0.996933 1.21302 2.626 + vertex 0.999507 1.21232 2.6255 + endloop + endfacet + facet normal 0.195855 -0.039425 0.97984 + outer loop + vertex 0.997094 1.21746 2.62614 + vertex 0.996933 1.21302 2.626 + vertex 1.00049 1.21635 2.62542 + endloop + endfacet + facet normal 0.299409 -0.040649 0.953258 + outer loop + vertex 1.00452 1.21979 2.62431 + vertex 1.00483 1.225 2.62443 + vertex 1.00094 1.22127 2.6255 + endloop + endfacet + facet normal 0.298981 -0.0417524 0.953345 + outer loop + vertex 1.00049 1.21635 2.62542 + vertex 1.00452 1.21979 2.62431 + vertex 1.00094 1.22127 2.6255 + endloop + endfacet + facet normal 0.197966 -0.0328775 0.979657 + outer loop + vertex 1.00094 1.22127 2.6255 + vertex 0.997094 1.21746 2.62614 + vertex 1.00049 1.21635 2.62542 + endloop + endfacet + facet normal 0.21233 -0.048003 0.976018 + outer loop + vertex 0.997272 1.22237 2.62635 + vertex 0.997094 1.21746 2.62614 + vertex 1.00094 1.22127 2.6255 + endloop + endfacet + facet normal 0.309812 -0.0553905 0.949183 + outer loop + vertex 1.00483 1.225 2.62443 + vertex 1.0049 1.2299 2.6247 + vertex 1.00121 1.22626 2.62569 + endloop + endfacet + facet normal 0.31047 -0.0534013 0.949082 + outer loop + vertex 1.00094 1.22127 2.6255 + vertex 1.00483 1.225 2.62443 + vertex 1.00121 1.22626 2.62569 + endloop + endfacet + facet normal 0.212031 -0.0490155 0.976033 + outer loop + vertex 1.00121 1.22626 2.62569 + vertex 0.997272 1.22237 2.62635 + vertex 1.00094 1.22127 2.6255 + endloop + endfacet + facet normal 0.227577 -0.0655431 0.971552 + outer loop + vertex 0.997621 1.22748 2.62661 + vertex 0.997272 1.22237 2.62635 + vertex 1.00121 1.22626 2.62569 + endloop + endfacet + facet normal 0.324027 -0.0658799 0.943751 + outer loop + vertex 1.0049 1.2299 2.6247 + vertex 1.005 1.23446 2.62498 + vertex 1.00163 1.23112 2.6259 + endloop + endfacet + facet normal 0.32264 -0.0697791 0.943946 + outer loop + vertex 1.00121 1.22626 2.62569 + vertex 1.0049 1.2299 2.6247 + vertex 1.00163 1.23112 2.6259 + endloop + endfacet + facet normal 0.228477 -0.0628729 0.971517 + outer loop + vertex 1.00163 1.23112 2.6259 + vertex 0.997621 1.22748 2.62661 + vertex 1.00121 1.22626 2.62569 + endloop + endfacet + facet normal 0.24286 -0.0796216 0.966788 + outer loop + vertex 0.998482 1.23318 2.62686 + vertex 0.997621 1.22748 2.62661 + vertex 1.00163 1.23112 2.6259 + endloop + endfacet + facet normal 0.342233 -0.0864971 0.935625 + outer loop + vertex 1.005 1.23446 2.62498 + vertex 1.00239 1.23503 2.62599 + vertex 1.00163 1.23112 2.6259 + endloop + endfacet + facet normal 0.249399 -0.0691763 0.965927 + outer loop + vertex 1.00239 1.23503 2.62599 + vertex 0.998482 1.23318 2.62686 + vertex 1.00163 1.23112 2.6259 + endloop + endfacet + facet normal 0.249809 -0.0701242 0.965753 + outer loop + vertex 1.00239 1.23503 2.62599 + vertex 1.00191 1.23817 2.62634 + vertex 0.998482 1.23318 2.62686 + endloop + endfacet + facet normal 0.258909 -0.0766719 0.962854 + outer loop + vertex 1.00191 1.23817 2.62634 + vertex 0.998057 1.23819 2.62738 + vertex 0.998482 1.23318 2.62686 + endloop + endfacet + facet normal 0.31098 -0.0139395 0.950314 + outer loop + vertex 1.00208 1.2524 2.62687 + vertex 1.00208 1.25742 2.62695 + vertex 0.998021 1.25303 2.62821 + endloop + endfacet + facet normal 0.448743 -0.0159014 0.893519 + outer loop + vertex 1.00197 1.35402 2.63126 + vertex 1.00266 1.35759 2.63098 + vertex 0.999081 1.35346 2.63271 + endloop + endfacet + facet normal 0.447721 0.0114986 0.894099 + outer loop + vertex 0.997214 1.51738 2.63622 + vertex 0.997343 1.51371 2.63621 + vertex 1.00014 1.51338 2.63481 + endloop + endfacet + facet normal 0.422211 0.0229663 0.906207 + outer loop + vertex 1.00549 1.75819 2.62469 + vertex 1.00508 1.76355 2.62474 + vertex 1.00178 1.76029 2.62637 + endloop + endfacet + facet normal 0.419944 0.0180231 0.907371 + outer loop + vertex 1.00222 1.75613 2.62624 + vertex 1.00549 1.75819 2.62469 + vertex 1.00178 1.76029 2.62637 + endloop + endfacet + facet normal 0.417846 0.0177697 0.908344 + outer loop + vertex 1.00178 1.76029 2.62637 + vertex 0.998585 1.75638 2.62791 + vertex 1.00222 1.75613 2.62624 + endloop + endfacet + facet normal 0.418832 0.016793 0.907908 + outer loop + vertex 0.998074 1.76203 2.62804 + vertex 0.998585 1.75638 2.62791 + vertex 1.00178 1.76029 2.62637 + endloop + endfacet + facet normal 0.432369 0.021201 0.901448 + outer loop + vertex 1.00508 1.76355 2.62474 + vertex 1.00478 1.76875 2.62477 + vertex 1.00144 1.76539 2.62645 + endloop + endfacet + facet normal 0.42945 0.0140191 0.902982 + outer loop + vertex 1.00178 1.76029 2.62637 + vertex 1.00508 1.76355 2.62474 + vertex 1.00144 1.76539 2.62645 + endloop + endfacet + facet normal 0.417427 0.0131317 0.908615 + outer loop + vertex 1.00144 1.76539 2.62645 + vertex 0.998074 1.76203 2.62804 + vertex 1.00178 1.76029 2.62637 + endloop + endfacet + facet normal 0.409572 0.0225879 0.911998 + outer loop + vertex 0.997701 1.7672 2.62808 + vertex 0.998074 1.76203 2.62804 + vertex 1.00144 1.76539 2.62645 + endloop + endfacet + facet normal 0.268425 0.102258 0.957858 + outer loop + vertex 0.99579 1.80164 2.62614 + vertex 0.996774 1.79651 2.62642 + vertex 0.999966 1.80026 2.62512 + endloop + endfacet + facet normal 0.260782 0.07569 0.962426 + outer loop + vertex 0.999966 1.80026 2.62512 + vertex 0.998927 1.80415 2.6251 + vertex 0.99579 1.80164 2.62614 + endloop + endfacet + facet normal 0.268606 0.103309 0.957694 + outer loop + vertex 0.99962 1.81324 2.62386 + vertex 1.00266 1.8165 2.62266 + vertex 0.998396 1.81727 2.62377 + endloop + endfacet + facet normal 0.264138 0.0727386 0.961738 + outer loop + vertex 1.00266 1.8165 2.62266 + vertex 1.00217 1.82141 2.62242 + vertex 0.998396 1.81727 2.62377 + endloop + endfacet + facet normal 0.234069 0.101853 0.96687 + outer loop + vertex 0.998396 1.81727 2.62377 + vertex 1.00217 1.82141 2.62242 + vertex 0.997933 1.82204 2.62338 + endloop + endfacet + facet normal 0.231878 0.0838541 0.969124 + outer loop + vertex 1.00217 1.82141 2.62242 + vertex 1.00203 1.82639 2.62202 + vertex 0.997933 1.82204 2.62338 + endloop + endfacet + facet normal 0.202727 0.112472 0.972755 + outer loop + vertex 0.997933 1.82204 2.62338 + vertex 1.00203 1.82639 2.62202 + vertex 0.997853 1.82694 2.62283 + endloop + endfacet + facet normal 0.201243 0.0984402 0.974582 + outer loop + vertex 1.00203 1.82639 2.62202 + vertex 1.00184 1.8313 2.62156 + vertex 0.997853 1.82694 2.62283 + endloop + endfacet + facet normal 0.170906 0.126932 0.977077 + outer loop + vertex 0.997853 1.82694 2.62283 + vertex 1.00184 1.8313 2.62156 + vertex 0.997551 1.83188 2.62224 + endloop + endfacet + facet normal 0.169174 0.111783 0.979227 + outer loop + vertex 1.00184 1.8313 2.62156 + vertex 1.0012 1.8359 2.62115 + vertex 0.997551 1.83188 2.62224 + endloop + endfacet + facet normal 0.137763 0.140583 0.980437 + outer loop + vertex 0.997551 1.83188 2.62224 + vertex 1.0012 1.8359 2.62115 + vertex 0.996443 1.83701 2.62166 + endloop + endfacet + facet normal 0.207383 0.141225 0.968012 + outer loop + vertex 1.00049 1.84018 2.62069 + vertex 1.00403 1.8387 2.62015 + vertex 1.00448 1.84278 2.61946 + endloop + endfacet + facet normal 0.135018 0.127801 0.982567 + outer loop + vertex 1.0012 1.8359 2.62115 + vertex 1.00049 1.84018 2.62069 + vertex 0.996443 1.83701 2.62166 + endloop + endfacet + facet normal 0.206177 0.138063 0.968726 + outer loop + vertex 1.00403 1.8387 2.62015 + vertex 1.00049 1.84018 2.62069 + vertex 1.0012 1.8359 2.62115 + endloop + endfacet + facet normal 0.0467235 0.348486 0.936149 + outer loop + vertex 1.00021 2.11409 2.56081 + vertex 1.00521 2.11375 2.56069 + vertex 1.00374 2.11745 2.55938 + endloop + endfacet + facet normal 0.0213851 0.371704 0.928105 + outer loop + vertex 0.998538 2.11743 2.55951 + vertex 1.00021 2.11409 2.56081 + vertex 1.00374 2.11745 2.55938 + endloop + endfacet + facet normal 0.0158963 0.289189 0.95714 + outer loop + vertex 1.00167 2.11028 2.56193 + vertex 1.00021 2.11409 2.56081 + vertex 0.996642 2.11042 2.56198 + endloop + endfacet + facet normal 0.0436985 0.298721 0.95334 + outer loop + vertex 1.00521 2.11375 2.56069 + vertex 1.00021 2.11409 2.56081 + vertex 1.00167 2.11028 2.56193 + endloop + endfacet + facet normal 0.0201995 0.456016 0.889743 + outer loop + vertex 1.00374 2.11745 2.55938 + vertex 1.00185 2.12071 2.55775 + vertex 0.998538 2.11743 2.55951 + endloop + endfacet + facet normal -0.0106109 0.480354 0.87701 + outer loop + vertex 0.998538 2.11743 2.55951 + vertex 1.00185 2.12071 2.55775 + vertex 0.996691 2.12057 2.55777 + endloop + endfacet + facet normal 0.0283005 0.778366 0.627173 + outer loop + vertex 0.999535 2.12348 2.55563 + vertex 1.00465 2.12346 2.55543 + vertex 1.00153 2.12566 2.55284 + endloop + endfacet + facet normal 0.0216674 0.780838 0.624357 + outer loop + vertex 0.99659 2.12573 2.55292 + vertex 0.999535 2.12348 2.55563 + vertex 1.00153 2.12566 2.55284 + endloop + endfacet + facet normal -0.0142208 0.600807 0.799268 + outer loop + vertex 1.00185 2.12071 2.55775 + vertex 0.999535 2.12348 2.55563 + vertex 0.996691 2.12057 2.55777 + endloop + endfacet + facet normal 0.0336721 0.625615 0.779405 + outer loop + vertex 1.00465 2.12346 2.55543 + vertex 0.999535 2.12348 2.55563 + vertex 1.00185 2.12071 2.55775 + endloop + endfacet + facet normal -0.218798 0.468819 0.855766 + outer loop + vertex 1.0026 2.135 2.54 + vertex 0.997013 2.13277 2.53979 + vertex 1.00074 2.13088 2.54178 + endloop + endfacet + facet normal 0.14224 0.338022 0.930327 + outer loop + vertex 1.0026 2.135 2.54 + vertex 1.00074 2.13088 2.54178 + vertex 1.005 2.13399 2.54 + endloop + endfacet + facet normal -0.0335483 0.530835 0.846811 + outer loop + vertex 1.005 2.13399 2.54 + vertex 1.00074 2.13088 2.54178 + vertex 1.00501 2.13006 2.54247 + endloop + endfacet + facet normal 0.10277 0.895689 0.432642 + outer loop + vertex 1.00501 2.13006 2.54247 + vertex 1.00074 2.13088 2.54178 + vertex 1.00383 2.1287 2.54555 + endloop + endfacet + facet normal 0.0517177 0.882697 0.467089 + outer loop + vertex 1.00383 2.1287 2.54555 + vertex 1.00074 2.13088 2.54178 + vertex 0.998926 2.12884 2.54582 + endloop + endfacet + facet normal 0.0465222 0.936046 0.348789 + outer loop + vertex 1.00383 2.1287 2.54555 + vertex 0.998926 2.12884 2.54582 + vertex 1.0029 2.12731 2.5494 + endloop + endfacet + facet normal 0.0336012 0.931821 0.361359 + outer loop + vertex 1.0029 2.12731 2.5494 + vertex 0.998926 2.12884 2.54582 + vertex 0.99784 2.1274 2.54965 + endloop + endfacet + facet normal 0.0206757 0.887095 0.461123 + outer loop + vertex 1.00153 2.12566 2.55284 + vertex 0.99784 2.1274 2.54965 + vertex 0.99659 2.12573 2.55292 + endloop + endfacet + facet normal 0.0371467 0.894268 0.445988 + outer loop + vertex 1.0029 2.12731 2.5494 + vertex 0.99784 2.1274 2.54965 + vertex 1.00153 2.12566 2.55284 + endloop + endfacet + facet normal -0.0181122 -0.0466273 0.998748 + outer loop + vertex 1.0026 2.135 2.54 + vertex 1 2.13601 2.54 + vertex 0.997013 2.13277 2.53979 + endloop + endfacet + facet normal 0.00691282 -0.987886 -0.155028 + outer loop + vertex 1.01 0.892618 2.54 + vertex 1.00802 0.892289 2.54201 + vertex 1.005 0.892583 2.54 + endloop + endfacet + facet normal 0.0371263 -0.979239 -0.199279 + outer loop + vertex 1.00802 0.892289 2.54201 + vertex 1.00288 0.892083 2.54206 + vertex 1.005 0.892583 2.54 + endloop + endfacet + facet normal 0.0410602 -0.990006 0.134917 + outer loop + vertex 1.00802 0.892289 2.54201 + vertex 1.00652 0.892704 2.54551 + vertex 1.00288 0.892083 2.54206 + endloop + endfacet + facet normal 0.0436251 -0.990255 0.132256 + outer loop + vertex 1.00652 0.892704 2.54551 + vertex 1.00154 0.89251 2.5457 + vertex 1.00288 0.892083 2.54206 + endloop + endfacet + facet normal 0.0474644 -0.964685 0.259093 + outer loop + vertex 1.00652 0.892704 2.54551 + vertex 1.00496 0.893577 2.54904 + vertex 1.00154 0.89251 2.5457 + endloop + endfacet + facet normal 0.0614768 -0.962365 0.264714 + outer loop + vertex 1.00972 0.893851 2.54893 + vertex 1.00496 0.893577 2.54904 + vertex 1.00652 0.892704 2.54551 + endloop + endfacet + facet normal 0.061815 -0.909116 0.411931 + outer loop + vertex 1.00496 0.893577 2.54904 + vertex 1.00972 0.893851 2.54893 + vertex 1.00754 0.894885 2.55154 + endloop + endfacet + facet normal 0.0393994 -0.901446 0.431095 + outer loop + vertex 1.00348 0.894981 2.55212 + vertex 1.00496 0.893577 2.54904 + vertex 1.00754 0.894885 2.55154 + endloop + endfacet + facet normal 0.0682697 -0.784564 0.616279 + outer loop + vertex 1.00754 0.894885 2.55154 + vertex 1.00725 0.897105 2.5544 + vertex 1.00348 0.894981 2.55212 + endloop + endfacet + facet normal 0.0546444 -0.77488 0.629742 + outer loop + vertex 1.00725 0.897105 2.5544 + vertex 1.00189 0.897097 2.55486 + vertex 1.00348 0.894981 2.55212 + endloop + endfacet + facet normal 0.0655953 -0.645642 0.760818 + outer loop + vertex 1.00725 0.897105 2.5544 + vertex 1.00509 0.900009 2.55705 + vertex 1.00189 0.897097 2.55486 + endloop + endfacet + facet normal 0.081783 -0.638031 0.765655 + outer loop + vertex 1.00984 0.900277 2.55677 + vertex 1.00509 0.900009 2.55705 + vertex 1.00725 0.897105 2.5544 + endloop + endfacet + facet normal 0.0798083 -0.502326 0.860987 + outer loop + vertex 1.00984 0.900277 2.55677 + vertex 1.00875 0.903907 2.55899 + vertex 1.00509 0.900009 2.55705 + endloop + endfacet + facet normal 0.0895875 -0.509058 0.856057 + outer loop + vertex 1.00509 0.900009 2.55705 + vertex 1.00875 0.903907 2.55899 + vertex 1.0032 0.903078 2.55908 + endloop + endfacet + facet normal 0.078331 -0.428828 0.899984 + outer loop + vertex 1.0032 0.903078 2.55908 + vertex 1.00875 0.903907 2.55899 + vertex 1.00619 0.90664 2.56051 + endloop + endfacet + facet normal 0.0554798 -0.413234 0.908933 + outer loop + vertex 1.00139 0.90632 2.56066 + vertex 1.0032 0.903078 2.55908 + vertex 1.00619 0.90664 2.56051 + endloop + endfacet + facet normal 0.0510734 -0.331988 0.9419 + outer loop + vertex 1.00619 0.90664 2.56051 + vertex 1.00487 0.910009 2.56177 + vertex 1.00139 0.90632 2.56066 + endloop + endfacet + facet normal 0.0725363 -0.27777 0.957905 + outer loop + vertex 1.00479 0.922539 2.56549 + vertex 1.00435 0.925315 2.56633 + vertex 1.00099 0.921609 2.56551 + endloop + endfacet + facet normal 0.093721 -0.274117 0.957119 + outer loop + vertex 1.00752 0.925065 2.56595 + vertex 1.00435 0.925315 2.56633 + vertex 1.00479 0.922539 2.56549 + endloop + endfacet + facet normal 0.0896257 -0.243836 0.965666 + outer loop + vertex 1.00348 0.992929 2.58449 + vertex 1.00788 0.997217 2.58516 + vertex 1.00343 0.99682 2.58547 + endloop + endfacet + facet normal 0.0896116 -0.243638 0.965717 + outer loop + vertex 1.00343 0.99682 2.58547 + vertex 1.00788 0.997217 2.58516 + vertex 1.00675 1.0005 2.58609 + endloop + endfacet + facet normal 0.259303 -0.152447 0.953689 + outer loop + vertex 1.00382 1.16832 2.61959 + vertex 1.00858 1.17318 2.61907 + vertex 1.00418 1.17326 2.62028 + endloop + endfacet + facet normal 0.239258 -0.161188 0.957483 + outer loop + vertex 1.0051 1.1772 2.62071 + vertex 1.00255 1.17501 2.62098 + vertex 1.00418 1.17326 2.62028 + endloop + endfacet + facet normal 0.329997 -0.178922 0.92687 + outer loop + vertex 1.0051 1.1772 2.62071 + vertex 1.00418 1.17326 2.62028 + vertex 1.00885 1.17859 2.61965 + endloop + endfacet + facet normal 0.261267 -0.114874 0.958407 + outer loop + vertex 1.00885 1.17859 2.61965 + vertex 1.00418 1.17326 2.62028 + vertex 1.00858 1.17318 2.61907 + endloop + endfacet + facet normal 0.199487 -0.112872 0.973378 + outer loop + vertex 1.0051 1.1772 2.62071 + vertex 1.00278 1.17816 2.6213 + vertex 1.00255 1.17501 2.62098 + endloop + endfacet + facet normal 0.336801 -0.10573 0.935621 + outer loop + vertex 1.00885 1.17859 2.61965 + vertex 1.01003 1.18416 2.61985 + vertex 1.00643 1.18106 2.6208 + endloop + endfacet + facet normal 0.315294 -0.128927 0.940196 + outer loop + vertex 1.0051 1.1772 2.62071 + vertex 1.00885 1.17859 2.61965 + vertex 1.00643 1.18106 2.6208 + endloop + endfacet + facet normal 0.207997 -0.0925213 0.973744 + outer loop + vertex 1.00643 1.18106 2.6208 + vertex 1.00278 1.17816 2.6213 + vertex 1.0051 1.1772 2.62071 + endloop + endfacet + facet normal 0.212473 -0.0984229 0.972198 + outer loop + vertex 1.00357 1.18316 2.62164 + vertex 1.00278 1.17816 2.6213 + vertex 1.00643 1.18106 2.6208 + endloop + endfacet + facet normal 0.346001 -0.117885 0.930799 + outer loop + vertex 1.01003 1.18416 2.61985 + vertex 1.00748 1.18492 2.6209 + vertex 1.00643 1.18106 2.6208 + endloop + endfacet + facet normal 0.221886 -0.0852159 0.971342 + outer loop + vertex 1.00748 1.18492 2.6209 + vertex 1.00357 1.18316 2.62164 + vertex 1.00643 1.18106 2.6208 + endloop + endfacet + facet normal 0.21985 -0.0803242 0.972221 + outer loop + vertex 1.00748 1.18492 2.6209 + vertex 1.00701 1.18814 2.62127 + vertex 1.00357 1.18316 2.62164 + endloop + endfacet + facet normal 0.233513 -0.0900699 0.968173 + outer loop + vertex 1.00701 1.18814 2.62127 + vertex 1.00305 1.18816 2.62222 + vertex 1.00357 1.18316 2.62164 + endloop + endfacet + facet normal 0.234046 -0.0675594 0.969875 + outer loop + vertex 1.00701 1.18814 2.62127 + vertex 1.00705 1.19267 2.62157 + vertex 1.00305 1.18816 2.62222 + endloop + endfacet + facet normal 0.260771 -0.0925393 0.960955 + outer loop + vertex 1.00305 1.18816 2.62222 + vertex 1.00705 1.19267 2.62157 + vertex 1.003 1.19314 2.62272 + endloop + endfacet + facet normal 0.263704 -0.0695951 0.96209 + outer loop + vertex 1.00705 1.19267 2.62157 + vertex 1.00718 1.19759 2.62189 + vertex 1.003 1.19314 2.62272 + endloop + endfacet + facet normal 0.287174 -0.0932409 0.95333 + outer loop + vertex 1.003 1.19314 2.62272 + vertex 1.00718 1.19759 2.62189 + vertex 1.0031 1.19814 2.62318 + endloop + endfacet + facet normal 0.290208 -0.0729077 0.954182 + outer loop + vertex 1.00718 1.19759 2.62189 + vertex 1.00731 1.20256 2.62223 + vertex 1.0031 1.19814 2.62318 + endloop + endfacet + facet normal 0.306467 -0.0898129 0.947635 + outer loop + vertex 1.0031 1.19814 2.62318 + vertex 1.00731 1.20256 2.62223 + vertex 1.00323 1.20314 2.62361 + endloop + endfacet + facet normal 0.309408 -0.0706019 0.948305 + outer loop + vertex 1.00731 1.20256 2.62223 + vertex 1.00745 1.20755 2.62256 + vertex 1.00323 1.20314 2.62361 + endloop + endfacet + facet normal 0.33681 -0.0679075 0.939121 + outer loop + vertex 1.00335 1.20821 2.62401 + vertex 1.00769 1.2127 2.62278 + vertex 1.00335 1.21376 2.62441 + endloop + endfacet + facet normal 0.421956 0.00492614 0.906603 + outer loop + vertex 1.00909 1.25492 2.62388 + vertex 1.00907 1.25992 2.62386 + vertex 1.00572 1.25635 2.62544 + endloop + endfacet + facet normal 0.419108 -0.00321906 0.907931 + outer loop + vertex 1.00571 1.25136 2.62543 + vertex 1.00909 1.25492 2.62388 + vertex 1.00572 1.25635 2.62544 + endloop + endfacet + facet normal 0.368898 -0.00328822 0.929464 + outer loop + vertex 1.00572 1.25635 2.62544 + vertex 1.00208 1.2524 2.62687 + vertex 1.00571 1.25136 2.62543 + endloop + endfacet + facet normal 0.378425 -0.0134578 0.925534 + outer loop + vertex 1.00208 1.25742 2.62695 + vertex 1.00208 1.2524 2.62687 + vertex 1.00572 1.25635 2.62544 + endloop + endfacet + facet normal 0.482485 -0.023796 0.875581 + outer loop + vertex 1.00266 1.35759 2.63098 + vertex 1.00197 1.35402 2.63126 + vertex 1.00436 1.35389 2.62995 + endloop + endfacet + facet normal 0.42053 0.0377423 0.906493 + outer loop + vertex 1.00837 1.75778 2.62337 + vertex 1.0089 1.76154 2.62297 + vertex 1.00549 1.75819 2.62469 + endloop + endfacet + facet normal 0.43185 0.0237523 0.901633 + outer loop + vertex 1.00549 1.75819 2.62469 + vertex 1.0089 1.76154 2.62297 + vertex 1.00508 1.76355 2.62474 + endloop + endfacet + facet normal 0.43483 0.030859 0.899984 + outer loop + vertex 1.0089 1.76154 2.62297 + vertex 1.00828 1.76701 2.62308 + vertex 1.00508 1.76355 2.62474 + endloop + endfacet + facet normal 0.442724 0.0218383 0.896392 + outer loop + vertex 1.00508 1.76355 2.62474 + vertex 1.00828 1.76701 2.62308 + vertex 1.00478 1.76875 2.62477 + endloop + endfacet + facet normal 0.248629 0.12304 0.960752 + outer loop + vertex 1.00448 1.84278 2.61946 + vertex 1.00716 1.84619 2.61833 + vertex 1.00361 1.84746 2.61908 + endloop + endfacet + facet normal 0.247425 0.119204 0.961546 + outer loop + vertex 1.00716 1.84619 2.61833 + vertex 1.00801 1.85073 2.61754 + vertex 1.00361 1.84746 2.61908 + endloop + endfacet + facet normal 0.244089 0.12382 0.961815 + outer loop + vertex 1.00361 1.84746 2.61908 + vertex 1.00801 1.85073 2.61754 + vertex 1.00336 1.85205 2.61856 + endloop + endfacet + facet normal 0.236657 0.0936925 0.967065 + outer loop + vertex 1.00801 1.85073 2.61754 + vertex 1.0073 1.85618 2.61719 + vertex 1.00336 1.85205 2.61856 + endloop + endfacet + facet normal 0.199658 0.130342 0.971158 + outer loop + vertex 1.00336 1.85205 2.61856 + vertex 1.0073 1.85618 2.61719 + vertex 1.0029 1.85688 2.618 + endloop + endfacet + facet normal 0.196666 0.107536 0.974555 + outer loop + vertex 1.0073 1.85618 2.61719 + vertex 1.0068 1.86121 2.61674 + vertex 1.0029 1.85688 2.618 + endloop + endfacet + facet normal 0.15893 0.142233 0.976991 + outer loop + vertex 1.0029 1.85688 2.618 + vertex 1.0068 1.86121 2.61674 + vertex 1.00243 1.8618 2.61736 + endloop + endfacet + facet normal 0.157321 0.128168 0.979195 + outer loop + vertex 1.0068 1.86121 2.61674 + vertex 1.00608 1.86583 2.61625 + vertex 1.00243 1.8618 2.61736 + endloop + endfacet + facet normal 0.0864567 0.451115 0.888268 + outer loop + vertex 1.00922 2.11679 2.55918 + vertex 1.00703 2.12057 2.55748 + vertex 1.00374 2.11745 2.55938 + endloop + endfacet + facet normal 0.0598263 0.473483 0.878769 + outer loop + vertex 1.00374 2.11745 2.55938 + vertex 1.00703 2.12057 2.55748 + vertex 1.00185 2.12071 2.55775 + endloop + endfacet + facet normal 0.0614669 0.782709 0.619346 + outer loop + vertex 1.00465 2.12346 2.55543 + vertex 1.0102 2.12349 2.55483 + vertex 1.00655 2.12565 2.55247 + endloop + endfacet + facet normal 0.0464116 0.788178 0.613695 + outer loop + vertex 1.00153 2.12566 2.55284 + vertex 1.00465 2.12346 2.55543 + vertex 1.00655 2.12565 2.55247 + endloop + endfacet + facet normal 0.0589487 0.60941 0.790661 + outer loop + vertex 1.00703 2.12057 2.55748 + vertex 1.00465 2.12346 2.55543 + vertex 1.00185 2.12071 2.55775 + endloop + endfacet + facet normal 0.0796142 0.619544 0.780914 + outer loop + vertex 1.0102 2.12349 2.55483 + vertex 1.00465 2.12346 2.55543 + vertex 1.00703 2.12057 2.55748 + endloop + endfacet + facet normal -0.0154014 0.481357 0.876389 + outer loop + vertex 1.01 2.13415 2.54 + vertex 1.005 2.13399 2.54 + vertex 1.0088 2.13031 2.54209 + endloop + endfacet + facet normal 0.0489585 0.530655 0.846173 + outer loop + vertex 1.0088 2.13031 2.54209 + vertex 1.005 2.13399 2.54 + vertex 1.00501 2.13006 2.54247 + endloop + endfacet + facet normal -0.0105673 0.875627 0.482872 + outer loop + vertex 1.0088 2.13031 2.54209 + vertex 1.00501 2.13006 2.54247 + vertex 1.0076 2.12871 2.54496 + endloop + endfacet + facet normal 0.0635167 0.904601 0.421501 + outer loop + vertex 1.0076 2.12871 2.54496 + vertex 1.00501 2.13006 2.54247 + vertex 1.00383 2.1287 2.54555 + endloop + endfacet + facet normal 0.0500532 0.941003 0.334677 + outer loop + vertex 1.0076 2.12871 2.54496 + vertex 1.00383 2.1287 2.54555 + vertex 1.00821 2.12731 2.54881 + endloop + endfacet + facet normal 0.0392788 0.936909 0.347358 + outer loop + vertex 1.00821 2.12731 2.54881 + vertex 1.00383 2.1287 2.54555 + vertex 1.0029 2.12731 2.5494 + endloop + endfacet + facet normal 0.0342916 0.894817 0.445115 + outer loop + vertex 1.00655 2.12565 2.55247 + vertex 1.0029 2.12731 2.5494 + vertex 1.00153 2.12566 2.55284 + endloop + endfacet + facet normal 0.0485192 0.900817 0.43148 + outer loop + vertex 1.00821 2.12731 2.54881 + vertex 1.0029 2.12731 2.5494 + vertex 1.00655 2.12565 2.55247 + endloop + endfacet + facet normal 0.007725 -0.990856 -0.134704 + outer loop + vertex 1.015 0.892657 2.54 + vertex 1.01332 0.892381 2.54194 + vertex 1.01 0.892618 2.54 + endloop + endfacet + facet normal 0.0151101 -0.989001 -0.147134 + outer loop + vertex 1.01332 0.892381 2.54194 + vertex 1.00802 0.892289 2.54201 + vertex 1.01 0.892618 2.54 + endloop + endfacet + facet normal 0.0190431 -0.987766 0.154779 + outer loop + vertex 1.01332 0.892381 2.54194 + vertex 1.01172 0.892893 2.54541 + vertex 1.00802 0.892289 2.54201 + endloop + endfacet + facet normal 0.038626 -0.990242 0.1339 + outer loop + vertex 1.01172 0.892893 2.54541 + vertex 1.00652 0.892704 2.54551 + vertex 1.00802 0.892289 2.54201 + endloop + endfacet + facet normal 0.040437 -0.958258 0.283032 + outer loop + vertex 1.01172 0.892893 2.54541 + vertex 1.00972 0.893851 2.54893 + vertex 1.00652 0.892704 2.54551 + endloop + endfacet + facet normal 0.0634528 -0.95346 0.294767 + outer loop + vertex 1.01477 0.894153 2.54883 + vertex 1.00972 0.893851 2.54893 + vertex 1.01172 0.892893 2.54541 + endloop + endfacet + facet normal 0.0627154 -0.873891 0.482059 + outer loop + vertex 1.00972 0.893851 2.54893 + vertex 1.01477 0.894153 2.54883 + vertex 1.01182 0.895831 2.55225 + endloop + endfacet + facet normal 0.12085 -0.884098 0.451404 + outer loop + vertex 1.00754 0.894885 2.55154 + vertex 1.00972 0.893851 2.54893 + vertex 1.01182 0.895831 2.55225 + endloop + endfacet + facet normal 0.101634 -0.755903 0.646747 + outer loop + vertex 1.01126 0.898065 2.55495 + vertex 1.01182 0.895831 2.55225 + vertex 1.01485 0.898004 2.55431 + endloop + endfacet + facet normal 0.0930093 -0.757451 0.646233 + outer loop + vertex 1.01126 0.898065 2.55495 + vertex 1.00725 0.897105 2.5544 + vertex 1.01182 0.895831 2.55225 + endloop + endfacet + facet normal 0.0714847 -0.784226 0.616344 + outer loop + vertex 1.00725 0.897105 2.5544 + vertex 1.00754 0.894885 2.55154 + vertex 1.01182 0.895831 2.55225 + endloop + endfacet + facet normal 0.0409032 -0.618781 0.784498 + outer loop + vertex 1.01126 0.898065 2.55495 + vertex 1.00984 0.900277 2.55677 + vertex 1.00725 0.897105 2.5544 + endloop + endfacet + facet normal 0.125824 -0.624507 0.770817 + outer loop + vertex 1.01485 0.898004 2.55431 + vertex 1.01324 0.899997 2.55619 + vertex 1.01126 0.898065 2.55495 + endloop + endfacet + facet normal 0.0855953 -0.599369 0.795883 + outer loop + vertex 1.01324 0.899997 2.55619 + vertex 1.00984 0.900277 2.55677 + vertex 1.01126 0.898065 2.55495 + endloop + endfacet + facet normal 0.106975 -0.486481 0.867117 + outer loop + vertex 1.01324 0.899997 2.55619 + vertex 1.01424 0.903539 2.55806 + vertex 1.00984 0.900277 2.55677 + endloop + endfacet + facet normal 0.113331 -0.49323 0.862485 + outer loop + vertex 1.01424 0.903539 2.55806 + vertex 1.00875 0.903907 2.55899 + vertex 1.00984 0.900277 2.55677 + endloop + endfacet + facet normal 0.124439 -0.419917 0.898991 + outer loop + vertex 1.01333 0.907355 2.55996 + vertex 1.00875 0.903907 2.55899 + vertex 1.01424 0.903539 2.55806 + endloop + endfacet + facet normal 0.0919477 -0.224203 0.970195 + outer loop + vertex 1.01017 1.0423 2.59564 + vertex 1.00638 1.04113 2.59573 + vertex 1.0084 1.03831 2.59489 + endloop + endfacet + facet normal 0.093414 -0.2248 0.969917 + outer loop + vertex 1.01017 1.0423 2.59564 + vertex 1.0084 1.03831 2.59489 + vertex 1.01339 1.04217 2.5953 + endloop + endfacet + facet normal 0.0910935 -0.221373 0.970925 + outer loop + vertex 1.01017 1.0423 2.59564 + vertex 1.00944 1.04484 2.59629 + vertex 1.00638 1.04113 2.59573 + endloop + endfacet + facet normal 0.0935516 -0.222542 0.970424 + outer loop + vertex 1.01339 1.04217 2.5953 + vertex 1.01282 1.0448 2.59596 + vertex 1.01017 1.0423 2.59564 + endloop + endfacet + facet normal 0.0921116 -0.221073 0.970898 + outer loop + vertex 1.01282 1.0448 2.59596 + vertex 1.00944 1.04484 2.59629 + vertex 1.01017 1.0423 2.59564 + endloop + endfacet + facet normal 0.0921486 -0.220023 0.971133 + outer loop + vertex 1.01282 1.0448 2.59596 + vertex 1.01423 1.04863 2.59669 + vertex 1.00944 1.04484 2.59629 + endloop + endfacet + facet normal 0.202781 -0.12718 0.97093 + outer loop + vertex 1.01343 1.13823 2.61341 + vertex 1.01373 1.14344 2.61403 + vertex 1.0087 1.13837 2.61442 + endloop + endfacet + facet normal 0.242334 -0.167606 0.955606 + outer loop + vertex 1.0087 1.13837 2.61442 + vertex 1.01373 1.14344 2.61403 + vertex 1.00905 1.1434 2.61521 + endloop + endfacet + facet normal 0.221014 -0.179609 0.958589 + outer loop + vertex 1.01002 1.14729 2.61572 + vertex 1.00736 1.14515 2.61593 + vertex 1.00905 1.1434 2.61521 + endloop + endfacet + facet normal 0.308255 -0.197838 0.930505 + outer loop + vertex 1.01002 1.14729 2.61572 + vertex 1.00905 1.1434 2.61521 + vertex 1.01385 1.14877 2.61476 + endloop + endfacet + facet normal 0.24322 -0.137211 0.960217 + outer loop + vertex 1.01385 1.14877 2.61476 + vertex 1.00905 1.1434 2.61521 + vertex 1.01373 1.14344 2.61403 + endloop + endfacet + facet normal 0.185591 -0.134052 0.97344 + outer loop + vertex 1.01002 1.14729 2.61572 + vertex 1.00767 1.14823 2.61629 + vertex 1.00736 1.14515 2.61593 + endloop + endfacet + facet normal 0.313068 -0.124062 0.941593 + outer loop + vertex 1.01385 1.14877 2.61476 + vertex 1.01509 1.15419 2.61506 + vertex 1.01145 1.15108 2.61586 + endloop + endfacet + facet normal 0.292259 -0.147263 0.944933 + outer loop + vertex 1.01002 1.14729 2.61572 + vertex 1.01385 1.14877 2.61476 + vertex 1.01145 1.15108 2.61586 + endloop + endfacet + facet normal 0.194867 -0.111588 0.974461 + outer loop + vertex 1.01145 1.15108 2.61586 + vertex 1.00767 1.14823 2.61629 + vertex 1.01002 1.14729 2.61572 + endloop + endfacet + facet normal 0.202479 -0.122147 0.971639 + outer loop + vertex 1.00859 1.15315 2.61672 + vertex 1.00767 1.14823 2.61629 + vertex 1.01145 1.15108 2.61586 + endloop + endfacet + facet normal 0.321982 -0.135675 0.936974 + outer loop + vertex 1.01509 1.15419 2.61506 + vertex 1.01261 1.15488 2.61602 + vertex 1.01145 1.15108 2.61586 + endloop + endfacet + facet normal 0.215012 -0.104538 0.971 + outer loop + vertex 1.01261 1.15488 2.61602 + vertex 1.00859 1.15315 2.61672 + vertex 1.01145 1.15108 2.61586 + endloop + endfacet + facet normal 0.213045 -0.0995856 0.971954 + outer loop + vertex 1.01261 1.15488 2.61602 + vertex 1.01218 1.15811 2.61644 + vertex 1.00859 1.15315 2.61672 + endloop + endfacet + facet normal 0.22983 -0.112033 0.966761 + outer loop + vertex 1.01218 1.15811 2.61644 + vertex 1.00813 1.15816 2.61741 + vertex 1.00859 1.15315 2.61672 + endloop + endfacet + facet normal 0.230683 -0.0884604 0.969 + outer loop + vertex 1.01218 1.15811 2.61644 + vertex 1.01224 1.16268 2.61684 + vertex 1.00813 1.15816 2.61741 + endloop + endfacet + facet normal 0.25811 -0.114603 0.959294 + outer loop + vertex 1.00813 1.15816 2.61741 + vertex 1.01224 1.16268 2.61684 + vertex 1.00814 1.16317 2.61801 + endloop + endfacet + facet normal 0.261733 -0.0887421 0.961052 + outer loop + vertex 1.01224 1.16268 2.61684 + vertex 1.01239 1.1676 2.61726 + vertex 1.00814 1.16317 2.61801 + endloop + endfacet + facet normal 0.286403 -0.114126 0.951288 + outer loop + vertex 1.00814 1.16317 2.61801 + vertex 1.01239 1.1676 2.61726 + vertex 1.00831 1.16818 2.61856 + endloop + endfacet + facet normal 0.290716 -0.0871974 0.952828 + outer loop + vertex 1.01239 1.1676 2.61726 + vertex 1.01261 1.17254 2.61764 + vertex 1.00831 1.16818 2.61856 + endloop + endfacet + facet normal 0.315954 -0.114387 0.941854 + outer loop + vertex 1.00831 1.16818 2.61856 + vertex 1.01261 1.17254 2.61764 + vertex 1.00858 1.17318 2.61907 + endloop + endfacet + facet normal 0.321976 -0.0801922 0.943345 + outer loop + vertex 1.01261 1.17254 2.61764 + vertex 1.01296 1.17758 2.61795 + vertex 1.00858 1.17318 2.61907 + endloop + endfacet + facet normal 0.354218 -0.116264 0.927908 + outer loop + vertex 1.00858 1.17318 2.61907 + vertex 1.01296 1.17758 2.61795 + vertex 1.00885 1.17859 2.61965 + endloop + endfacet + facet normal 0.353146 -0.0940325 0.930831 + outer loop + vertex 1.00974 1.18766 2.62032 + vertex 1.00748 1.18492 2.6209 + vertex 1.01003 1.18416 2.61985 + endloop + endfacet + facet normal 0.42618 -0.0839687 0.900733 + outer loop + vertex 1.00974 1.18766 2.62032 + vertex 1.01003 1.18416 2.61985 + vertex 1.01322 1.18898 2.61879 + endloop + endfacet + facet normal 0.319089 -0.0628314 0.94564 + outer loop + vertex 1.00974 1.18766 2.62032 + vertex 1.00701 1.18814 2.62127 + vertex 1.00748 1.18492 2.6209 + endloop + endfacet + facet normal 0.426769 -0.0564693 0.902596 + outer loop + vertex 1.01474 1.20988 2.61948 + vertex 1.01505 1.2147 2.61964 + vertex 1.01138 1.2114 2.62116 + endloop + endfacet + facet normal 0.425152 -0.0605857 0.903092 + outer loop + vertex 1.01114 1.20643 2.62094 + vertex 1.01474 1.20988 2.61948 + vertex 1.01138 1.2114 2.62116 + endloop + endfacet + facet normal 0.386025 -0.0594598 0.92057 + outer loop + vertex 1.01138 1.2114 2.62116 + vertex 1.00745 1.20755 2.62256 + vertex 1.01114 1.20643 2.62094 + endloop + endfacet + facet normal 0.406214 0.0679045 0.911252 + outer loop + vertex 1.01208 1.85099 2.61606 + vertex 1.01104 1.84668 2.61684 + vertex 1.01437 1.84874 2.6152 + endloop + endfacet + facet normal 0.274215 0.11438 0.954842 + outer loop + vertex 1.00951 1.87274 2.61446 + vertex 1.01296 1.86897 2.61392 + vertex 1.01362 1.87328 2.61322 + endloop + endfacet + facet normal 0.276622 0.0985972 0.955907 + outer loop + vertex 1.01362 1.87328 2.61322 + vertex 1.01227 1.87614 2.61331 + vertex 1.00951 1.87274 2.61446 + endloop + endfacet + facet normal 0.229457 0.139271 0.963303 + outer loop + vertex 1.00951 1.87274 2.61446 + vertex 1.01227 1.87614 2.61331 + vertex 1.00871 1.87743 2.61397 + endloop + endfacet + facet normal 0.229585 0.13967 0.963215 + outer loop + vertex 1.01227 1.87614 2.61331 + vertex 1.01308 1.88067 2.61246 + vertex 1.00871 1.87743 2.61397 + endloop + endfacet + facet normal 0.224162 0.147049 0.963394 + outer loop + vertex 1.00871 1.87743 2.61397 + vertex 1.01308 1.88067 2.61246 + vertex 1.00834 1.88202 2.61336 + endloop + endfacet + facet normal 0.217683 0.120838 0.96851 + outer loop + vertex 1.01308 1.88067 2.61246 + vertex 1.01197 1.88611 2.61203 + vertex 1.00834 1.88202 2.61336 + endloop + endfacet + facet normal 0.178934 0.156106 0.971398 + outer loop + vertex 1.00834 1.88202 2.61336 + vertex 1.01197 1.88611 2.61203 + vertex 1.00745 1.88665 2.61278 + endloop + endfacet + facet normal 0.177411 0.139389 0.974216 + outer loop + vertex 1.01197 1.88611 2.61203 + vertex 1.01058 1.89135 2.61154 + vertex 1.00745 1.88665 2.61278 + endloop + endfacet + facet normal 0.0857936 0.453308 0.887215 + outer loop + vertex 1.01367 2.11744 2.55842 + vertex 1.01197 2.12024 2.55715 + vertex 1.00922 2.11679 2.55918 + endloop + endfacet + facet normal 0.0880679 0.451815 0.887754 + outer loop + vertex 1.00922 2.11679 2.55918 + vertex 1.01197 2.12024 2.55715 + vertex 1.00703 2.12057 2.55748 + endloop + endfacet + facet normal 0.0983451 0.869197 0.484587 + outer loop + vertex 1.01495 2.12493 2.55261 + vertex 1.01274 2.12666 2.54995 + vertex 1.01071 2.12577 2.55197 + endloop + endfacet + facet normal 0.0535648 0.777405 0.626716 + outer loop + vertex 1.01071 2.12577 2.55197 + vertex 1.00655 2.12565 2.55247 + vertex 1.0102 2.12349 2.55483 + endloop + endfacet + facet normal 0.0583814 0.776778 0.627063 + outer loop + vertex 1.01071 2.12577 2.55197 + vertex 1.0102 2.12349 2.55483 + vertex 1.01495 2.12493 2.55261 + endloop + endfacet + facet normal 0.10214 0.721596 0.684738 + outer loop + vertex 1.01495 2.12493 2.55261 + vertex 1.0102 2.12349 2.55483 + vertex 1.01468 2.12244 2.55528 + endloop + endfacet + facet normal 0.0918433 0.611083 0.78622 + outer loop + vertex 1.01197 2.12024 2.55715 + vertex 1.0102 2.12349 2.55483 + vertex 1.00703 2.12057 2.55748 + endloop + endfacet + facet normal 0.0631524 0.602301 0.795767 + outer loop + vertex 1.01468 2.12244 2.55528 + vertex 1.0102 2.12349 2.55483 + vertex 1.01197 2.12024 2.55715 + endloop + endfacet + facet normal -0.0129589 0.462977 0.886276 + outer loop + vertex 1.015 2.13429 2.54 + vertex 1.01 2.13415 2.54 + vertex 1.01372 2.13021 2.54211 + endloop + endfacet + facet normal 0.00531318 0.476407 0.879209 + outer loop + vertex 1.01372 2.13021 2.54211 + vertex 1.01 2.13415 2.54 + vertex 1.0088 2.13031 2.54209 + endloop + endfacet + facet normal 0.0161352 0.886131 0.463154 + outer loop + vertex 1.01372 2.13021 2.54211 + vertex 1.0088 2.13031 2.54209 + vertex 1.01232 2.12814 2.54612 + endloop + endfacet + facet normal -0.0121615 0.875891 0.482356 + outer loop + vertex 1.01232 2.12814 2.54612 + vertex 1.0088 2.13031 2.54209 + vertex 1.0076 2.12871 2.54496 + endloop + endfacet + facet normal 0.0229777 0.905083 0.424614 + outer loop + vertex 1.01274 2.12666 2.54995 + vertex 1.00821 2.12731 2.54881 + vertex 1.01071 2.12577 2.55197 + endloop + endfacet + facet normal 0.0443218 0.93365 0.355433 + outer loop + vertex 1.01274 2.12666 2.54995 + vertex 1.01232 2.12814 2.54612 + vertex 1.00821 2.12731 2.54881 + endloop + endfacet + facet normal 0.0311554 0.940792 0.33755 + outer loop + vertex 1.01232 2.12814 2.54612 + vertex 1.0076 2.12871 2.54496 + vertex 1.00821 2.12731 2.54881 + endloop + endfacet + facet normal 0.0251965 0.905705 0.42316 + outer loop + vertex 1.01071 2.12577 2.55197 + vertex 1.00821 2.12731 2.54881 + vertex 1.00655 2.12565 2.55247 + endloop + endfacet + facet normal 0.00376867 -0.99103 -0.133583 + outer loop + vertex 1.02 0.892676 2.54 + vertex 1.0185 0.892432 2.54177 + vertex 1.015 0.892657 2.54 + endloop + endfacet + facet normal 0.0053732 -0.990597 -0.136706 + outer loop + vertex 1.0185 0.892432 2.54177 + vertex 1.01332 0.892381 2.54194 + vertex 1.015 0.892657 2.54 + endloop + endfacet + facet normal 0.015657 -0.983953 0.17774 + outer loop + vertex 1.0185 0.892432 2.54177 + vertex 1.01698 0.893036 2.54524 + vertex 1.01332 0.892381 2.54194 + endloop + endfacet + facet normal 0.0317388 -0.986535 0.160442 + outer loop + vertex 1.01698 0.893036 2.54524 + vertex 1.01172 0.892893 2.54541 + vertex 1.01332 0.892381 2.54194 + endloop + endfacet + facet normal 0.0355982 -0.947618 0.317416 + outer loop + vertex 1.01698 0.893036 2.54524 + vertex 1.01477 0.894153 2.54883 + vertex 1.01172 0.892893 2.54541 + endloop + endfacet + facet normal 0.0552228 -0.94303 0.328094 + outer loop + vertex 1.01995 0.894328 2.54846 + vertex 1.01477 0.894153 2.54883 + vertex 1.01698 0.893036 2.54524 + endloop + endfacet + facet normal 0.0650057 -0.860738 0.504881 + outer loop + vertex 1.01477 0.894153 2.54883 + vertex 1.01995 0.894328 2.54846 + vertex 1.01722 0.895981 2.55163 + endloop + endfacet + facet normal 0.0812092 -0.865692 0.493945 + outer loop + vertex 1.01182 0.895831 2.55225 + vertex 1.01477 0.894153 2.54883 + vertex 1.01722 0.895981 2.55163 + endloop + endfacet + facet normal 0.0962669 -0.752718 0.651267 + outer loop + vertex 1.01722 0.895981 2.55163 + vertex 1.01485 0.898004 2.55431 + vertex 1.01182 0.895831 2.55225 + endloop + endfacet + facet normal 0.125314 -0.736536 0.664689 + outer loop + vertex 1.01949 0.898378 2.55385 + vertex 1.01485 0.898004 2.55431 + vertex 1.01722 0.895981 2.55163 + endloop + endfacet + facet normal 0.126769 -0.602862 0.78771 + outer loop + vertex 1.01485 0.898004 2.55431 + vertex 1.01949 0.898378 2.55385 + vertex 1.01704 0.900833 2.55613 + endloop + endfacet + facet normal 0.147965 -0.612208 0.776729 + outer loop + vertex 1.01324 0.899997 2.55619 + vertex 1.01485 0.898004 2.55431 + vertex 1.01704 0.900833 2.55613 + endloop + endfacet + facet normal 0.122246 -0.488974 0.86369 + outer loop + vertex 1.01704 0.900833 2.55613 + vertex 1.01424 0.903539 2.55806 + vertex 1.01324 0.899997 2.55619 + endloop + endfacet + facet normal 0.131998 -0.481037 0.866706 + outer loop + vertex 1.01994 0.90458 2.55777 + vertex 1.01424 0.903539 2.55806 + vertex 1.01704 0.900833 2.55613 + endloop + endfacet + facet normal 0.117399 -0.387768 0.91425 + outer loop + vertex 1.01994 0.90458 2.55777 + vertex 1.01867 0.908572 2.55962 + vertex 1.01424 0.903539 2.55806 + endloop + endfacet + facet normal 0.151738 -0.412933 0.898032 + outer loop + vertex 1.01424 0.903539 2.55806 + vertex 1.01867 0.908572 2.55962 + vertex 1.01333 0.907355 2.55996 + endloop + endfacet + facet normal 0.159642 -0.196099 0.967502 + outer loop + vertex 1.01464 1.11811 2.61044 + vertex 1.01107 1.11649 2.6107 + vertex 1.01334 1.11373 2.60977 + endloop + endfacet + facet normal 0.261093 -0.22196 0.939449 + outer loop + vertex 1.01464 1.11811 2.61044 + vertex 1.01334 1.11373 2.60977 + vertex 1.0186 1.11906 2.60957 + endloop + endfacet + facet normal 0.291897 -0.156624 0.943538 + outer loop + vertex 1.0186 1.11906 2.60957 + vertex 1.01996 1.12434 2.61002 + vertex 1.0164 1.12163 2.61068 + endloop + endfacet + facet normal 0.255323 -0.189768 0.94805 + outer loop + vertex 1.01464 1.11811 2.61044 + vertex 1.0186 1.11906 2.60957 + vertex 1.0164 1.12163 2.61068 + endloop + endfacet + facet normal 0.187469 -0.139777 0.972275 + outer loop + vertex 1.0138 1.12366 2.61147 + vertex 1.01325 1.11982 2.61102 + vertex 1.0164 1.12163 2.61068 + endloop + endfacet + facet normal 0.294934 -0.161032 0.941851 + outer loop + vertex 1.01996 1.12434 2.61002 + vertex 1.01751 1.12507 2.61092 + vertex 1.0164 1.12163 2.61068 + endloop + endfacet + facet normal 0.194656 -0.130538 0.972147 + outer loop + vertex 1.01751 1.12507 2.61092 + vertex 1.0138 1.12366 2.61147 + vertex 1.0164 1.12163 2.61068 + endloop + endfacet + facet normal 0.189634 -0.116242 0.97495 + outer loop + vertex 1.01751 1.12507 2.61092 + vertex 1.01711 1.12814 2.61136 + vertex 1.0138 1.12366 2.61147 + endloop + endfacet + facet normal 0.199624 -0.123679 0.972036 + outer loop + vertex 1.01711 1.12814 2.61136 + vertex 1.01315 1.12821 2.61218 + vertex 1.0138 1.12366 2.61147 + endloop + endfacet + facet normal 0.200459 -0.102686 0.974306 + outer loop + vertex 1.01711 1.12814 2.61136 + vertex 1.01722 1.13257 2.6118 + vertex 1.01315 1.12821 2.61218 + endloop + endfacet + facet normal 0.224214 -0.125556 0.966418 + outer loop + vertex 1.01315 1.12821 2.61218 + vertex 1.01722 1.13257 2.6118 + vertex 1.01311 1.13308 2.61282 + endloop + endfacet + facet normal 0.228156 -0.0980487 0.968675 + outer loop + vertex 1.01722 1.13257 2.6118 + vertex 1.01762 1.13756 2.61221 + vertex 1.01311 1.13308 2.61282 + endloop + endfacet + facet normal 0.253896 -0.125268 0.959085 + outer loop + vertex 1.01311 1.13308 2.61282 + vertex 1.01762 1.13756 2.61221 + vertex 1.01343 1.13823 2.61341 + endloop + endfacet + facet normal 0.260095 -0.0906794 0.961316 + outer loop + vertex 1.01762 1.13756 2.61221 + vertex 1.01854 1.14324 2.6125 + vertex 1.01343 1.13823 2.61341 + endloop + endfacet + facet normal 0.295609 -0.129614 0.946475 + outer loop + vertex 1.01343 1.13823 2.61341 + vertex 1.01854 1.14324 2.6125 + vertex 1.01373 1.14344 2.61403 + endloop + endfacet + facet normal 0.297682 -0.101609 0.949242 + outer loop + vertex 1.01854 1.14324 2.6125 + vertex 1.0182 1.14836 2.61316 + vertex 1.01373 1.14344 2.61403 + endloop + endfacet + facet normal 0.331807 -0.135406 0.933579 + outer loop + vertex 1.01373 1.14344 2.61403 + vertex 1.0182 1.14836 2.61316 + vertex 1.01385 1.14877 2.61476 + endloop + endfacet + facet normal 0.33678 -0.0953451 0.936744 + outer loop + vertex 1.0182 1.14836 2.61316 + vertex 1.01843 1.15351 2.6136 + vertex 1.01385 1.14877 2.61476 + endloop + endfacet + facet normal 0.44849 -0.0494666 0.892418 + outer loop + vertex 1.02015 1.17979 2.61475 + vertex 1.02023 1.1843 2.61496 + vertex 1.01691 1.18104 2.61645 + endloop + endfacet + facet normal 0.456037 -0.0591574 0.887993 + outer loop + vertex 1.02023 1.1843 2.61496 + vertex 1.01754 1.18482 2.61638 + vertex 1.01691 1.18104 2.61645 + endloop + endfacet + facet normal 0.454713 -0.0645145 0.888298 + outer loop + vertex 1.01795 1.20818 2.61771 + vertex 1.01818 1.21313 2.61795 + vertex 1.01474 1.20988 2.61948 + endloop + endfacet + facet normal 0.449482 -0.0575206 0.891435 + outer loop + vertex 1.01474 1.20988 2.61948 + vertex 1.01818 1.21313 2.61795 + vertex 1.01505 1.2147 2.61964 + endloop + endfacet + facet normal 0.433387 -0.035694 0.900501 + outer loop + vertex 1.0141 1.22706 2.62053 + vertex 1.01217 1.22543 2.62139 + vertex 1.0134 1.22263 2.62069 + endloop + endfacet + facet normal 0.418531 0.0808707 0.904595 + outer loop + vertex 1.01104 1.84668 2.61684 + vertex 1.01174 1.84184 2.61695 + vertex 1.01483 1.8447 2.61527 + endloop + endfacet + facet normal 0.410131 0.0605483 0.910014 + outer loop + vertex 1.01483 1.8447 2.61527 + vertex 1.01437 1.84874 2.6152 + vertex 1.01104 1.84668 2.61684 + endloop + endfacet + facet normal 0.331077 0.110759 0.937081 + outer loop + vertex 1.01943 1.88849 2.60932 + vertex 1.01812 1.89418 2.60911 + vertex 1.01519 1.89004 2.61064 + endloop + endfacet + facet normal 0.260223 0.1223 0.957772 + outer loop + vertex 1.0143 1.8987 2.60957 + vertex 1.01812 1.89418 2.60911 + vertex 1.01889 1.89873 2.60832 + endloop + endfacet + facet normal 0.260798 0.106457 0.959506 + outer loop + vertex 1.01889 1.89873 2.60832 + vertex 1.01794 1.90243 2.60817 + vertex 1.0143 1.8987 2.60957 + endloop + endfacet + facet normal 0.232793 0.135214 0.963081 + outer loop + vertex 1.0143 1.8987 2.60957 + vertex 1.01794 1.90243 2.60817 + vertex 1.01455 1.90328 2.60887 + endloop + endfacet + facet normal 0.23003 0.122344 0.965463 + outer loop + vertex 1.01794 1.90243 2.60817 + vertex 1.01695 1.90591 2.60796 + vertex 1.01455 1.90328 2.60887 + endloop + endfacet + facet normal 0.185747 0.163993 0.968816 + outer loop + vertex 1.01455 1.90328 2.60887 + vertex 1.01695 1.90591 2.60796 + vertex 1.01342 1.90687 2.60848 + endloop + endfacet + facet normal 0.185257 0.16196 0.969252 + outer loop + vertex 1.01695 1.90591 2.60796 + vertex 1.01757 1.91034 2.60711 + vertex 1.01342 1.90687 2.60848 + endloop + endfacet + facet normal 0.172853 0.176662 0.968975 + outer loop + vertex 1.01342 1.90687 2.60848 + vertex 1.01757 1.91034 2.60711 + vertex 1.01254 1.91154 2.60778 + endloop + endfacet + facet normal 0.167119 0.149464 0.974542 + outer loop + vertex 1.01757 1.91034 2.60711 + vertex 1.01616 1.91544 2.60656 + vertex 1.01254 1.91154 2.60778 + endloop + endfacet + facet normal 0.15411 0.425092 0.891934 + outer loop + vertex 1.01686 2.11608 2.55852 + vertex 1.01692 2.1196 2.55683 + vertex 1.01367 2.11744 2.55842 + endloop + endfacet + facet normal 0.117957 0.467748 0.875955 + outer loop + vertex 1.01367 2.11744 2.55842 + vertex 1.01692 2.1196 2.55683 + vertex 1.01197 2.12024 2.55715 + endloop + endfacet + facet normal 0.0623574 0.87294 0.483825 + outer loop + vertex 1.01495 2.12493 2.55261 + vertex 1.01943 2.1252 2.55154 + vertex 1.01667 2.12666 2.54927 + endloop + endfacet + facet normal 0.0861949 0.866007 0.492546 + outer loop + vertex 1.01274 2.12666 2.54995 + vertex 1.01495 2.12493 2.55261 + vertex 1.01667 2.12666 2.54927 + endloop + endfacet + facet normal 0.113031 0.741187 0.661715 + outer loop + vertex 1.01943 2.1252 2.55154 + vertex 1.01495 2.12493 2.55261 + vertex 1.01921 2.12286 2.55419 + endloop + endfacet + facet normal 0.0953766 0.722421 0.684844 + outer loop + vertex 1.01921 2.12286 2.55419 + vertex 1.01495 2.12493 2.55261 + vertex 1.01468 2.12244 2.55528 + endloop + endfacet + facet normal 0.125326 0.550655 0.825271 + outer loop + vertex 1.01692 2.1196 2.55683 + vertex 1.01468 2.12244 2.55528 + vertex 1.01197 2.12024 2.55715 + endloop + endfacet + facet normal 0.142268 0.559295 0.816669 + outer loop + vertex 1.01921 2.12286 2.55419 + vertex 1.01468 2.12244 2.55528 + vertex 1.01692 2.1196 2.55683 + endloop + endfacet + facet normal 0.00257779 0.429049 0.903278 + outer loop + vertex 1.02 2.13426 2.54 + vertex 1.015 2.13429 2.54 + vertex 1.01889 2.13009 2.54199 + endloop + endfacet + facet normal 0.0326676 0.45143 0.891708 + outer loop + vertex 1.01889 2.13009 2.54199 + vertex 1.015 2.13429 2.54 + vertex 1.01372 2.13021 2.54211 + endloop + endfacet + facet normal 0.0325864 0.868494 0.494627 + outer loop + vertex 1.01889 2.13009 2.54199 + vertex 1.01372 2.13021 2.54211 + vertex 1.01788 2.12806 2.54562 + endloop + endfacet + facet normal 0.055907 0.879078 0.473388 + outer loop + vertex 1.01788 2.12806 2.54562 + vertex 1.01372 2.13021 2.54211 + vertex 1.01232 2.12814 2.54612 + endloop + endfacet + facet normal 0.0623276 0.933414 0.353346 + outer loop + vertex 1.01667 2.12666 2.54927 + vertex 1.01232 2.12814 2.54612 + vertex 1.01274 2.12666 2.54995 + endloop + endfacet + facet normal 0.0474749 0.927407 0.37103 + outer loop + vertex 1.01788 2.12806 2.54562 + vertex 1.01232 2.12814 2.54612 + vertex 1.01667 2.12666 2.54927 + endloop + endfacet + facet normal 0.0489406 -0.95966 -0.276869 + outer loop + vertex 1.025 0.892931 2.54 + vertex 1.02331 0.892464 2.54132 + vertex 1.02 0.892676 2.54 + endloop + endfacet + facet normal -0.00671199 -0.989798 -0.142317 + outer loop + vertex 1.02331 0.892464 2.54132 + vertex 1.0185 0.892432 2.54177 + vertex 1.02 0.892676 2.54 + endloop + endfacet + facet normal 0.023719 -0.982214 0.186259 + outer loop + vertex 1.02331 0.892464 2.54132 + vertex 1.02211 0.893104 2.54485 + vertex 1.0185 0.892432 2.54177 + endloop + endfacet + facet normal 0.0270269 -0.982831 0.182519 + outer loop + vertex 1.02211 0.893104 2.54485 + vertex 1.01698 0.893036 2.54524 + vertex 1.0185 0.892432 2.54177 + endloop + endfacet + facet normal 0.0386462 -0.938984 0.341783 + outer loop + vertex 1.02211 0.893104 2.54485 + vertex 1.01995 0.894328 2.54846 + vertex 1.01698 0.893036 2.54524 + endloop + endfacet + facet normal 0.0597288 -0.933848 0.352647 + outer loop + vertex 1.02503 0.894451 2.54792 + vertex 1.01995 0.894328 2.54846 + vertex 1.02211 0.893104 2.54485 + endloop + endfacet + facet normal 0.07647 -0.843198 0.532136 + outer loop + vertex 1.01995 0.894328 2.54846 + vertex 1.02503 0.894451 2.54792 + vertex 1.0224 0.896231 2.55112 + endloop + endfacet + facet normal 0.0918962 -0.848258 0.52155 + outer loop + vertex 1.01722 0.895981 2.55163 + vertex 1.01995 0.894328 2.54846 + vertex 1.0224 0.896231 2.55112 + endloop + endfacet + facet normal 0.101481 -0.727143 0.678944 + outer loop + vertex 1.0224 0.896231 2.55112 + vertex 1.01949 0.898378 2.55385 + vertex 1.01722 0.895981 2.55163 + endloop + endfacet + facet normal 0.1186 -0.715758 0.688204 + outer loop + vertex 1.0246 0.898836 2.55345 + vertex 1.01949 0.898378 2.55385 + vertex 1.0224 0.896231 2.55112 + endloop + endfacet + facet normal 0.11616 -0.592228 0.797354 + outer loop + vertex 1.01949 0.898378 2.55385 + vertex 1.0246 0.898836 2.55345 + vertex 1.02189 0.901426 2.55577 + endloop + endfacet + facet normal 0.131732 -0.599508 0.789453 + outer loop + vertex 1.01704 0.900833 2.55613 + vertex 1.01949 0.898378 2.55385 + vertex 1.02189 0.901426 2.55577 + endloop + endfacet + facet normal 0.122663 -0.475685 0.871021 + outer loop + vertex 1.02189 0.901426 2.55577 + vertex 1.01994 0.90458 2.55777 + vertex 1.01704 0.900833 2.55613 + endloop + endfacet + facet normal 0.119074 -0.477567 0.870489 + outer loop + vertex 1.025 0.904999 2.5573 + vertex 1.01994 0.90458 2.55777 + vertex 1.02189 0.901426 2.55577 + endloop + endfacet + facet normal 0.115143 -0.376208 0.919353 + outer loop + vertex 1.025 0.904999 2.5573 + vertex 1.02402 0.908768 2.55897 + vertex 1.01994 0.90458 2.55777 + endloop + endfacet + facet normal 0.181289 -0.163428 0.969755 + outer loop + vertex 1.02357 1.08828 2.60351 + vertex 1.02379 1.09337 2.60433 + vertex 1.01871 1.08831 2.60442 + endloop + endfacet + facet normal 0.214947 -0.197506 0.956446 + outer loop + vertex 1.01871 1.08831 2.60442 + vertex 1.02379 1.09337 2.60433 + vertex 1.01922 1.09331 2.60534 + endloop + endfacet + facet normal 0.18188 -0.204459 0.96183 + outer loop + vertex 1.02052 1.09711 2.6059 + vertex 1.01775 1.09524 2.60603 + vertex 1.01922 1.09331 2.60534 + endloop + endfacet + facet normal 0.278076 -0.232891 0.931899 + outer loop + vertex 1.02052 1.09711 2.6059 + vertex 1.01922 1.09331 2.60534 + vertex 1.02409 1.0984 2.60516 + endloop + endfacet + facet normal 0.215672 -0.17224 0.961155 + outer loop + vertex 1.02409 1.0984 2.60516 + vertex 1.01922 1.09331 2.60534 + vertex 1.02379 1.09337 2.60433 + endloop + endfacet + facet normal 0.155641 -0.164647 0.973995 + outer loop + vertex 1.02052 1.09711 2.6059 + vertex 1.01859 1.0988 2.6065 + vertex 1.01775 1.09524 2.60603 + endloop + endfacet + facet normal 0.26929 -0.203158 0.941387 + outer loop + vertex 1.02409 1.0984 2.60516 + vertex 1.02221 1.09996 2.60604 + vertex 1.02052 1.09711 2.6059 + endloop + endfacet + facet normal 0.171356 -0.146732 0.974221 + outer loop + vertex 1.02221 1.09996 2.60604 + vertex 1.01859 1.0988 2.6065 + vertex 1.02052 1.09711 2.6059 + endloop + endfacet + facet normal 0.165857 -0.128204 0.977781 + outer loop + vertex 1.02221 1.09996 2.60604 + vertex 1.02223 1.10309 2.60644 + vertex 1.01859 1.0988 2.6065 + endloop + endfacet + facet normal 0.179224 -0.139593 0.973855 + outer loop + vertex 1.02223 1.10309 2.60644 + vertex 1.01828 1.10322 2.60719 + vertex 1.01859 1.0988 2.6065 + endloop + endfacet + facet normal 0.180921 -0.108837 0.977457 + outer loop + vertex 1.02223 1.10309 2.60644 + vertex 1.02264 1.10762 2.60687 + vertex 1.01828 1.10322 2.60719 + endloop + endfacet + facet normal 0.211734 -0.140108 0.967232 + outer loop + vertex 1.01828 1.10322 2.60719 + vertex 1.02264 1.10762 2.60687 + vertex 1.01841 1.10821 2.60788 + endloop + endfacet + facet normal 0.217482 -0.104707 0.970432 + outer loop + vertex 1.02264 1.10762 2.60687 + vertex 1.02353 1.11326 2.60728 + vertex 1.01841 1.10821 2.60788 + endloop + endfacet + facet normal 0.255961 -0.145507 0.955673 + outer loop + vertex 1.01841 1.10821 2.60788 + vertex 1.02353 1.11326 2.60728 + vertex 1.01852 1.11354 2.60866 + endloop + endfacet + facet normal 0.258015 -0.121937 0.958415 + outer loop + vertex 1.02353 1.11326 2.60728 + vertex 1.02313 1.11845 2.60805 + vertex 1.01852 1.11354 2.60866 + endloop + endfacet + facet normal 0.294861 -0.158542 0.942296 + outer loop + vertex 1.01852 1.11354 2.60866 + vertex 1.02313 1.11845 2.60805 + vertex 1.0186 1.11906 2.60957 + endloop + endfacet + facet normal 0.30147 -0.118445 0.94609 + outer loop + vertex 1.02313 1.11845 2.60805 + vertex 1.02336 1.1236 2.60862 + vertex 1.0186 1.11906 2.60957 + endloop + endfacet + facet normal 0.344697 -0.168492 0.923469 + outer loop + vertex 1.0186 1.11906 2.60957 + vertex 1.02336 1.1236 2.60862 + vertex 1.01996 1.12434 2.61002 + endloop + endfacet + facet normal 0.4581 -0.0473444 0.887639 + outer loop + vertex 1.01963 1.18749 2.61544 + vertex 1.01754 1.18482 2.61638 + vertex 1.02023 1.1843 2.61496 + endloop + endfacet + facet normal 0.497421 -0.0499959 0.866067 + outer loop + vertex 1.02437 1.20973 2.61429 + vertex 1.02452 1.21472 2.6145 + vertex 1.02128 1.21143 2.61616 + endloop + endfacet + facet normal 0.471582 -0.0648804 0.879432 + outer loop + vertex 1.01818 1.21313 2.61795 + vertex 1.01795 1.20818 2.61771 + vertex 1.02128 1.21143 2.61616 + endloop + endfacet + facet normal 0.507109 -0.0267462 0.861467 + outer loop + vertex 1.02452 1.21472 2.6145 + vertex 1.02461 1.21972 2.61459 + vertex 1.02146 1.21641 2.61635 + endloop + endfacet + facet normal 0.497238 -0.0497553 0.866186 + outer loop + vertex 1.02128 1.21143 2.61616 + vertex 1.02452 1.21472 2.6145 + vertex 1.02146 1.21641 2.61635 + endloop + endfacet + facet normal 0.478424 -0.0494873 0.876733 + outer loop + vertex 1.02146 1.21641 2.61635 + vertex 1.01818 1.21313 2.61795 + vertex 1.02128 1.21143 2.61616 + endloop + endfacet + facet normal 0.476081 -0.0464419 0.878174 + outer loop + vertex 1.01835 1.21793 2.61811 + vertex 1.01818 1.21313 2.61795 + vertex 1.02146 1.21641 2.61635 + endloop + endfacet + facet normal 0.513057 -0.00853863 0.858312 + outer loop + vertex 1.02461 1.21972 2.61459 + vertex 1.02465 1.22474 2.61462 + vertex 1.02151 1.22137 2.61647 + endloop + endfacet + facet normal 0.506208 -0.0255876 0.862032 + outer loop + vertex 1.02146 1.21641 2.61635 + vertex 1.02461 1.21972 2.61459 + vertex 1.02151 1.22137 2.61647 + endloop + endfacet + facet normal 0.484179 -0.0256717 0.874592 + outer loop + vertex 1.02151 1.22137 2.61647 + vertex 1.01835 1.21793 2.61811 + vertex 1.02146 1.21641 2.61635 + endloop + endfacet + facet normal 0.480369 -0.0211197 0.876812 + outer loop + vertex 1.01805 1.22263 2.61839 + vertex 1.01835 1.21793 2.61811 + vertex 1.02151 1.22137 2.61647 + endloop + endfacet + facet normal 0.524323 -0.0121044 0.851434 + outer loop + vertex 1.02467 1.22981 2.61464 + vertex 1.02475 1.23486 2.61467 + vertex 1.02155 1.23175 2.61659 + endloop + endfacet + facet normal 0.529904 -0.020099 0.847819 + outer loop + vertex 1.02155 1.23175 2.61659 + vertex 1.02475 1.23486 2.61467 + vertex 1.02182 1.23691 2.61654 + endloop + endfacet + facet normal 0.461267 0.0040408 0.887252 + outer loop + vertex 1.02442 1.26019 2.61527 + vertex 1.02567 1.26446 2.6146 + vertex 1.02238 1.26249 2.61632 + endloop + endfacet + facet normal 0.484279 0.0303515 0.874387 + outer loop + vertex 1.02238 1.26249 2.61632 + vertex 1.02128 1.25833 2.61707 + vertex 1.02442 1.26019 2.61527 + endloop + endfacet + facet normal 0.50594 0.0224702 0.862276 + outer loop + vertex 1.02238 1.26249 2.61632 + vertex 1.01896 1.26317 2.61831 + vertex 1.02128 1.25833 2.61707 + endloop + endfacet + facet normal 0.386972 -0.0421442 0.921128 + outer loop + vertex 1.01985 1.30985 2.61946 + vertex 1.02371 1.31342 2.618 + vertex 1.0199 1.31471 2.61966 + endloop + endfacet + facet normal 0.381113 -0.06115 0.922504 + outer loop + vertex 1.02371 1.31342 2.618 + vertex 1.02388 1.31837 2.61826 + vertex 1.0199 1.31471 2.61966 + endloop + endfacet + facet normal 0.363231 -0.0384765 0.930904 + outer loop + vertex 1.0199 1.31471 2.61966 + vertex 1.02388 1.31837 2.61826 + vertex 1.01992 1.31957 2.61986 + endloop + endfacet + facet normal 0.358754 -0.0544886 0.93184 + outer loop + vertex 1.02388 1.31837 2.61826 + vertex 1.02386 1.32328 2.61855 + vertex 1.01992 1.31957 2.61986 + endloop + endfacet + facet normal 0.346898 0.126344 0.929354 + outer loop + vertex 1.02397 1.90873 2.60538 + vertex 1.02495 1.91301 2.60444 + vertex 1.02169 1.91074 2.60596 + endloop + endfacet + facet normal 0.332996 0.108544 0.93666 + outer loop + vertex 1.02169 1.91074 2.60596 + vertex 1.02078 1.90641 2.60679 + vertex 1.02397 1.90873 2.60538 + endloop + endfacet + facet normal 0.253887 0.129467 0.95853 + outer loop + vertex 1.02169 1.91074 2.60596 + vertex 1.01757 1.91034 2.60711 + vertex 1.02078 1.90641 2.60679 + endloop + endfacet + facet normal 0.273458 0.14608 0.950727 + outer loop + vertex 1.01757 1.91034 2.60711 + vertex 1.01695 1.90591 2.60796 + vertex 1.02078 1.90641 2.60679 + endloop + endfacet + facet normal 0.31899 0.118306 0.940345 + outer loop + vertex 1.02495 1.91301 2.60444 + vertex 1.0234 1.91879 2.60423 + vertex 1.02057 1.91461 2.60572 + endloop + endfacet + facet normal 0.329219 0.153287 0.931728 + outer loop + vertex 1.02169 1.91074 2.60596 + vertex 1.02495 1.91301 2.60444 + vertex 1.02057 1.91461 2.60572 + endloop + endfacet + facet normal 0.253458 0.132868 0.958178 + outer loop + vertex 1.02057 1.91461 2.60572 + vertex 1.01757 1.91034 2.60711 + vertex 1.02169 1.91074 2.60596 + endloop + endfacet + facet normal 0.215005 0.161512 0.963165 + outer loop + vertex 1.01616 1.91544 2.60656 + vertex 1.01757 1.91034 2.60711 + vertex 1.02057 1.91461 2.60572 + endloop + endfacet + facet normal 0.265772 0.158141 0.950977 + outer loop + vertex 1.0191 1.91846 2.60549 + vertex 1.02057 1.91461 2.60572 + vertex 1.0234 1.91879 2.60423 + endloop + endfacet + facet normal 0.26566 0.159107 0.950847 + outer loop + vertex 1.0191 1.91846 2.60549 + vertex 1.0234 1.91879 2.60423 + vertex 1.01972 1.92288 2.60458 + endloop + endfacet + facet normal 0.235613 0.131045 0.962971 + outer loop + vertex 1.01972 1.92288 2.60458 + vertex 1.0234 1.91879 2.60423 + vertex 1.02412 1.9234 2.60343 + endloop + endfacet + facet normal 0.211488 0.138442 0.967526 + outer loop + vertex 1.02057 1.91461 2.60572 + vertex 1.0191 1.91846 2.60549 + vertex 1.01616 1.91544 2.60656 + endloop + endfacet + facet normal 0.234948 0.13558 0.962506 + outer loop + vertex 1.02412 1.9234 2.60343 + vertex 1.0229 1.92711 2.6032 + vertex 1.01972 1.92288 2.60458 + endloop + endfacet + facet normal 0.118715 0.344591 0.931216 + outer loop + vertex 1.02374 2.11314 2.55859 + vertex 1.02126 2.11675 2.55757 + vertex 1.01911 2.11235 2.55947 + endloop + endfacet + facet normal 0.150367 0.329498 0.932106 + outer loop + vertex 1.01911 2.11235 2.55947 + vertex 1.02126 2.11675 2.55757 + vertex 1.01686 2.11608 2.55852 + endloop + endfacet + facet normal 0.138258 0.539453 0.830587 + outer loop + vertex 1.02485 2.11932 2.55585 + vertex 1.0233 2.12188 2.55445 + vertex 1.02105 2.12027 2.55587 + endloop + endfacet + facet normal 0.113129 0.437773 0.89194 + outer loop + vertex 1.02105 2.12027 2.55587 + vertex 1.02126 2.11675 2.55757 + vertex 1.02485 2.11932 2.55585 + endloop + endfacet + facet normal 0.135591 0.43762 0.888878 + outer loop + vertex 1.02105 2.12027 2.55587 + vertex 1.01692 2.1196 2.55683 + vertex 1.02126 2.11675 2.55757 + endloop + endfacet + facet normal 0.127596 0.427081 0.895166 + outer loop + vertex 1.01692 2.1196 2.55683 + vertex 1.01686 2.11608 2.55852 + vertex 1.02126 2.11675 2.55757 + endloop + endfacet + facet normal 0.137367 0.854072 0.501688 + outer loop + vertex 1.01943 2.1252 2.55154 + vertex 1.02403 2.12419 2.552 + vertex 1.02154 2.12641 2.54891 + endloop + endfacet + facet normal 0.0797223 0.88038 0.46752 + outer loop + vertex 1.01667 2.12666 2.54927 + vertex 1.01943 2.1252 2.55154 + vertex 1.02154 2.12641 2.54891 + endloop + endfacet + facet normal 0.0905182 0.584611 0.806248 + outer loop + vertex 1.0233 2.12188 2.55445 + vertex 1.01921 2.12286 2.55419 + vertex 1.02105 2.12027 2.55587 + endloop + endfacet + facet normal 0.125357 0.702688 0.700368 + outer loop + vertex 1.0233 2.12188 2.55445 + vertex 1.02403 2.12419 2.552 + vertex 1.01921 2.12286 2.55419 + endloop + endfacet + facet normal 0.0968385 0.743126 0.662107 + outer loop + vertex 1.02403 2.12419 2.552 + vertex 1.01943 2.1252 2.55154 + vertex 1.01921 2.12286 2.55419 + endloop + endfacet + facet normal 0.0923269 0.585396 0.805473 + outer loop + vertex 1.02105 2.12027 2.55587 + vertex 1.01921 2.12286 2.55419 + vertex 1.01692 2.1196 2.55683 + endloop + endfacet + facet normal 0.0714695 0.430573 0.899722 + outer loop + vertex 1.025 2.13343 2.54 + vertex 1.02 2.13426 2.54 + vertex 1.02393 2.12984 2.5418 + endloop + endfacet + facet normal 0.0532851 0.417409 0.907155 + outer loop + vertex 1.02393 2.12984 2.5418 + vertex 1.02 2.13426 2.54 + vertex 1.01889 2.13009 2.54199 + endloop + endfacet + facet normal 0.0598865 0.863366 0.501011 + outer loop + vertex 1.02393 2.12984 2.5418 + vertex 1.01889 2.13009 2.54199 + vertex 1.02311 2.12782 2.54539 + endloop + endfacet + facet normal 0.061038 0.863905 0.499942 + outer loop + vertex 1.02311 2.12782 2.54539 + vertex 1.01889 2.13009 2.54199 + vertex 1.01788 2.12806 2.54562 + endloop + endfacet + facet normal 0.0752482 0.922578 0.378402 + outer loop + vertex 1.02154 2.12641 2.54891 + vertex 1.01788 2.12806 2.54562 + vertex 1.01667 2.12666 2.54927 + endloop + endfacet + facet normal 0.0587207 0.917203 0.39407 + outer loop + vertex 1.02311 2.12782 2.54539 + vertex 1.01788 2.12806 2.54562 + vertex 1.02154 2.12641 2.54891 + endloop + endfacet + facet normal -0.0097366 -0.749326 -0.66213 + outer loop + vertex 1.03 0.892866 2.54 + vertex 1.02715 0.892433 2.54053 + vertex 1.025 0.892931 2.54 + endloop + endfacet + facet normal -0.0975063 -0.892343 -0.440701 + outer loop + vertex 1.02715 0.892433 2.54053 + vertex 1.02331 0.892464 2.54132 + vertex 1.025 0.892931 2.54 + endloop + endfacet + facet normal 0.0307808 -0.981631 0.18829 + outer loop + vertex 1.02715 0.892433 2.54053 + vertex 1.02727 0.893113 2.54406 + vertex 1.02331 0.892464 2.54132 + endloop + endfacet + facet normal 0.0306313 -0.981596 0.188498 + outer loop + vertex 1.02727 0.893113 2.54406 + vertex 1.02211 0.893104 2.54485 + vertex 1.02331 0.892464 2.54132 + endloop + endfacet + facet normal 0.0561005 -0.93292 0.355687 + outer loop + vertex 1.02727 0.893113 2.54406 + vertex 1.02503 0.894451 2.54792 + vertex 1.02211 0.893104 2.54485 + endloop + endfacet + facet normal 0.0440789 -0.935817 0.34972 + outer loop + vertex 1.02918 0.894428 2.54734 + vertex 1.02503 0.894451 2.54792 + vertex 1.02727 0.893113 2.54406 + endloop + endfacet + facet normal 0.0748148 -0.822985 0.563115 + outer loop + vertex 1.02503 0.894451 2.54792 + vertex 1.02918 0.894428 2.54734 + vertex 1.02815 0.896469 2.55046 + endloop + endfacet + facet normal 0.0972718 -0.833532 0.543841 + outer loop + vertex 1.0224 0.896231 2.55112 + vertex 1.02503 0.894451 2.54792 + vertex 1.02815 0.896469 2.55046 + endloop + endfacet + facet normal 0.109466 -0.712447 0.693135 + outer loop + vertex 1.02815 0.896469 2.55046 + vertex 1.0246 0.898836 2.55345 + vertex 1.0224 0.896231 2.55112 + endloop + endfacet + facet normal 0.123037 -0.702284 0.701184 + outer loop + vertex 1.03004 0.899738 2.5534 + vertex 1.0246 0.898836 2.55345 + vertex 1.02815 0.896469 2.55046 + endloop + endfacet + facet normal 0.105397 -0.590468 0.800149 + outer loop + vertex 1.0246 0.898836 2.55345 + vertex 1.03004 0.899738 2.5534 + vertex 1.02668 0.901932 2.55546 + endloop + endfacet + facet normal 0.113907 -0.593818 0.796496 + outer loop + vertex 1.02189 0.901426 2.55577 + vertex 1.0246 0.898836 2.55345 + vertex 1.02668 0.901932 2.55546 + endloop + endfacet + facet normal 0.105898 -0.468859 0.876902 + outer loop + vertex 1.02668 0.901932 2.55546 + vertex 1.025 0.904999 2.5573 + vertex 1.02189 0.901426 2.55577 + endloop + endfacet + facet normal 0.10468 -0.469432 0.876742 + outer loop + vertex 1.02951 0.905135 2.55684 + vertex 1.025 0.904999 2.5573 + vertex 1.02668 0.901932 2.55546 + endloop + endfacet + facet normal 0.11897 -0.375185 0.919283 + outer loop + vertex 1.025 0.904999 2.5573 + vertex 1.02908 0.908941 2.55838 + vertex 1.02402 0.908768 2.55897 + endloop + endfacet + facet normal 0.238542 -0.241793 0.94055 + outer loop + vertex 1.02882 1.0737 2.59994 + vertex 1.02712 1.07554 2.60084 + vertex 1.02509 1.07281 2.60066 + endloop + endfacet + facet normal 0.168309 -0.191518 0.96695 + outer loop + vertex 1.02712 1.07554 2.60084 + vertex 1.02401 1.07503 2.60128 + vertex 1.02509 1.07281 2.60066 + endloop + endfacet + facet normal 0.163667 -0.156718 0.973988 + outer loop + vertex 1.02712 1.07554 2.60084 + vertex 1.02725 1.07848 2.60129 + vertex 1.02401 1.07503 2.60128 + endloop + endfacet + facet normal 0.167313 -0.160143 0.972811 + outer loop + vertex 1.02725 1.07848 2.60129 + vertex 1.02341 1.07855 2.60197 + vertex 1.02401 1.07503 2.60128 + endloop + endfacet + facet normal 0.168507 -0.131881 0.976838 + outer loop + vertex 1.02725 1.07848 2.60129 + vertex 1.02764 1.08265 2.60179 + vertex 1.02341 1.07855 2.60197 + endloop + endfacet + facet normal 0.191606 -0.156058 0.968986 + outer loop + vertex 1.02341 1.07855 2.60197 + vertex 1.02764 1.08265 2.60179 + vertex 1.02341 1.08319 2.60272 + endloop + endfacet + facet normal 0.197017 -0.120426 0.972976 + outer loop + vertex 1.02764 1.08265 2.60179 + vertex 1.02856 1.08811 2.60228 + vertex 1.02341 1.08319 2.60272 + endloop + endfacet + facet normal 0.231201 -0.157326 0.960101 + outer loop + vertex 1.02341 1.08319 2.60272 + vertex 1.02856 1.08811 2.60228 + vertex 1.02357 1.08828 2.60351 + endloop + endfacet + facet normal 0.232764 -0.133805 0.963285 + outer loop + vertex 1.02856 1.08811 2.60228 + vertex 1.02822 1.09324 2.60308 + vertex 1.02357 1.08828 2.60351 + endloop + endfacet + facet normal 0.263794 -0.163988 0.950537 + outer loop + vertex 1.02357 1.08828 2.60351 + vertex 1.02822 1.09324 2.60308 + vertex 1.02379 1.09337 2.60433 + endloop + endfacet + facet normal 0.266058 -0.130097 0.955138 + outer loop + vertex 1.02822 1.09324 2.60308 + vertex 1.02842 1.09836 2.60372 + vertex 1.02379 1.09337 2.60433 + endloop + endfacet + facet normal 0.310145 -0.173347 0.934752 + outer loop + vertex 1.02379 1.09337 2.60433 + vertex 1.02842 1.09836 2.60372 + vertex 1.02409 1.0984 2.60516 + endloop + endfacet + facet normal 0.312658 -0.127717 0.94124 + outer loop + vertex 1.02865 1.104 2.6044 + vertex 1.02409 1.0984 2.60516 + vertex 1.02842 1.09836 2.60372 + endloop + endfacet + facet normal 0.5035 -0.0669286 0.861399 + outer loop + vertex 1.02732 1.20311 2.61205 + vertex 1.0275 1.20808 2.61233 + vertex 1.02419 1.20476 2.61401 + endloop + endfacet + facet normal 0.503881 -0.0674408 0.861136 + outer loop + vertex 1.02419 1.20476 2.61401 + vertex 1.0275 1.20808 2.61233 + vertex 1.02437 1.20973 2.61429 + endloop + endfacet + facet normal 0.509979 -0.052847 0.858562 + outer loop + vertex 1.0275 1.20808 2.61233 + vertex 1.02761 1.21304 2.61257 + vertex 1.02437 1.20973 2.61429 + endloop + endfacet + facet normal 0.50787 -0.0500486 0.859978 + outer loop + vertex 1.02437 1.20973 2.61429 + vertex 1.02761 1.21304 2.61257 + vertex 1.02452 1.21472 2.6145 + endloop + endfacet + facet normal 0.516686 -0.0288704 0.855688 + outer loop + vertex 1.02761 1.21304 2.61257 + vertex 1.02768 1.21801 2.6127 + vertex 1.02452 1.21472 2.6145 + endloop + endfacet + facet normal 0.515123 -0.026812 0.856697 + outer loop + vertex 1.02452 1.21472 2.6145 + vertex 1.02768 1.21801 2.6127 + vertex 1.02461 1.21972 2.61459 + endloop + endfacet + facet normal 0.522249 -0.00965415 0.852738 + outer loop + vertex 1.02768 1.21801 2.6127 + vertex 1.02772 1.22297 2.61273 + vertex 1.02461 1.21972 2.61459 + endloop + endfacet + facet normal 0.521423 -0.00856938 0.853255 + outer loop + vertex 1.02461 1.21972 2.61459 + vertex 1.02772 1.22297 2.61273 + vertex 1.02465 1.22474 2.61462 + endloop + endfacet + facet normal 0.487533 0.011911 0.873023 + outer loop + vertex 1.02128 1.25833 2.61707 + vertex 1.02181 1.2531 2.61685 + vertex 1.02485 1.25618 2.61511 + endloop + endfacet + facet normal 0.434328 0.0105027 0.900694 + outer loop + vertex 1.02442 1.26019 2.61527 + vertex 1.02485 1.25618 2.61511 + vertex 1.0281 1.25998 2.6135 + endloop + endfacet + facet normal 0.434471 0.013979 0.900577 + outer loop + vertex 1.02442 1.26019 2.61527 + vertex 1.0281 1.25998 2.6135 + vertex 1.02567 1.26446 2.6146 + endloop + endfacet + facet normal 0.400614 -0.00826162 0.91621 + outer loop + vertex 1.02567 1.26446 2.6146 + vertex 1.0281 1.25998 2.6135 + vertex 1.02945 1.26452 2.61295 + endloop + endfacet + facet normal 0.490141 0.0176706 0.871464 + outer loop + vertex 1.02485 1.25618 2.61511 + vertex 1.02442 1.26019 2.61527 + vertex 1.02128 1.25833 2.61707 + endloop + endfacet + facet normal 0.400683 -0.0156005 0.916084 + outer loop + vertex 1.02945 1.26452 2.61295 + vertex 1.02904 1.2686 2.6132 + vertex 1.02567 1.26446 2.6146 + endloop + endfacet + facet normal 0.387596 -0.00300302 0.921824 + outer loop + vertex 1.02567 1.26446 2.6146 + vertex 1.02904 1.2686 2.6132 + vertex 1.02517 1.26971 2.61483 + endloop + endfacet + facet normal 0.381845 -0.0260744 0.923858 + outer loop + vertex 1.02904 1.2686 2.6132 + vertex 1.02889 1.27351 2.6134 + vertex 1.02517 1.26971 2.61483 + endloop + endfacet + facet normal 0.371339 -0.0140794 0.928391 + outer loop + vertex 1.02517 1.26971 2.61483 + vertex 1.02889 1.27351 2.6134 + vertex 1.02499 1.27454 2.61497 + endloop + endfacet + facet normal 0.289616 0.0652152 0.954919 + outer loop + vertex 1.0256 1.72858 2.61487 + vertex 1.02846 1.72424 2.6143 + vertex 1.02981 1.72895 2.61357 + endloop + endfacet + facet normal 0.289973 0.061657 0.955047 + outer loop + vertex 1.02981 1.72895 2.61357 + vertex 1.0291 1.73298 2.61353 + vertex 1.0256 1.72858 2.61487 + endloop + endfacet + facet normal 0.313281 0.0412561 0.948764 + outer loop + vertex 1.0256 1.72858 2.61487 + vertex 1.0291 1.73298 2.61353 + vertex 1.02504 1.73399 2.61482 + endloop + endfacet + facet normal 0.313526 0.0424116 0.948632 + outer loop + vertex 1.0291 1.73298 2.61353 + vertex 1.02874 1.73785 2.61343 + vertex 1.02504 1.73399 2.61482 + endloop + endfacet + facet normal 0.331448 0.0233356 0.943185 + outer loop + vertex 1.02504 1.73399 2.61482 + vertex 1.02874 1.73785 2.61343 + vertex 1.02487 1.73909 2.61476 + endloop + endfacet + facet normal 0.331477 0.0234402 0.943172 + outer loop + vertex 1.02874 1.73785 2.61343 + vertex 1.02857 1.74266 2.61337 + vertex 1.02487 1.73909 2.61476 + endloop + endfacet + facet normal 0.347083 0.00518548 0.93782 + outer loop + vertex 1.02487 1.73909 2.61476 + vertex 1.02857 1.74266 2.61337 + vertex 1.02493 1.74411 2.61471 + endloop + endfacet + facet normal 0.349183 0.0112315 0.936987 + outer loop + vertex 1.02857 1.74266 2.61337 + vertex 1.02867 1.74746 2.61327 + vertex 1.02493 1.74411 2.61471 + endloop + endfacet + facet normal 0.354978 0.00386175 0.934867 + outer loop + vertex 1.02493 1.74411 2.61471 + vertex 1.02867 1.74746 2.61327 + vertex 1.02499 1.74912 2.61466 + endloop + endfacet + facet normal 0.364172 0.0276754 0.930921 + outer loop + vertex 1.02867 1.74746 2.61327 + vertex 1.02857 1.75248 2.61316 + vertex 1.02499 1.74912 2.61466 + endloop + endfacet + facet normal 0.367455 0.023655 0.929741 + outer loop + vertex 1.02499 1.74912 2.61466 + vertex 1.02857 1.75248 2.61316 + vertex 1.0248 1.7541 2.61461 + endloop + endfacet + facet normal 0.383533 0.0688551 0.920957 + outer loop + vertex 1.02857 1.75248 2.61316 + vertex 1.02791 1.75743 2.61307 + vertex 1.0248 1.7541 2.61461 + endloop + endfacet + facet normal 0.395171 0.0561129 0.916892 + outer loop + vertex 1.0248 1.7541 2.61461 + vertex 1.02791 1.75743 2.61307 + vertex 1.02442 1.7589 2.61449 + endloop + endfacet + facet normal 0.408839 0.0978894 0.907341 + outer loop + vertex 1.02791 1.75743 2.61307 + vertex 1.02699 1.76151 2.61304 + vertex 1.02442 1.7589 2.61449 + endloop + endfacet + facet normal 0.426424 0.0771765 0.901225 + outer loop + vertex 1.02442 1.7589 2.61449 + vertex 1.02699 1.76151 2.61304 + vertex 1.02423 1.76361 2.61417 + endloop + endfacet + facet normal 0.428304 0.080269 0.900063 + outer loop + vertex 1.02699 1.76151 2.61304 + vertex 1.0278 1.76613 2.61225 + vertex 1.02423 1.76361 2.61417 + endloop + endfacet + facet normal 0.432184 0.0737869 0.898762 + outer loop + vertex 1.02423 1.76361 2.61417 + vertex 1.0278 1.76613 2.61225 + vertex 1.024 1.76858 2.61387 + endloop + endfacet + facet normal 0.440747 0.090872 0.89302 + outer loop + vertex 1.0278 1.76613 2.61225 + vertex 1.02694 1.77178 2.6121 + vertex 1.024 1.76858 2.61387 + endloop + endfacet + facet normal 0.467916 0.0596572 0.881757 + outer loop + vertex 1.024 1.76858 2.61387 + vertex 1.02694 1.77178 2.6121 + vertex 1.02348 1.77362 2.61381 + endloop + endfacet + facet normal 0.469462 0.0635812 0.88066 + outer loop + vertex 1.02694 1.77178 2.6121 + vertex 1.02617 1.77732 2.61211 + vertex 1.02348 1.77362 2.61381 + endloop + endfacet + facet normal 0.43109 0.0571584 0.900497 + outer loop + vertex 1.0273 1.78156 2.6113 + vertex 1.02617 1.77732 2.61211 + vertex 1.02939 1.77921 2.61044 + endloop + endfacet + facet normal 0.356229 0.111293 0.927747 + outer loop + vertex 1.02078 1.90641 2.60679 + vertex 1.02171 1.90154 2.60701 + vertex 1.02466 1.90479 2.60549 + endloop + endfacet + facet normal 0.347748 0.0863435 0.933604 + outer loop + vertex 1.02466 1.90479 2.60549 + vertex 1.02397 1.90873 2.60538 + vertex 1.02078 1.90641 2.60679 + endloop + endfacet + facet normal 0.236023 0.16948 0.956854 + outer loop + vertex 1.0229 1.92711 2.6032 + vertex 1.0257 1.93146 2.60174 + vertex 1.02154 1.93078 2.60289 + endloop + endfacet + facet normal 0.304457 0.153764 0.940033 + outer loop + vertex 1.02903 1.93399 2.60033 + vertex 1.02933 1.93861 2.59947 + vertex 1.02634 1.93587 2.60089 + endloop + endfacet + facet normal 0.295585 0.13953 0.945072 + outer loop + vertex 1.02634 1.93587 2.60089 + vertex 1.0257 1.93146 2.60174 + vertex 1.02903 1.93399 2.60033 + endloop + endfacet + facet normal 0.209217 0.15597 0.965351 + outer loop + vertex 1.02634 1.93587 2.60089 + vertex 1.02167 1.9357 2.60193 + vertex 1.0257 1.93146 2.60174 + endloop + endfacet + facet normal 0.233915 0.179936 0.955462 + outer loop + vertex 1.02167 1.9357 2.60193 + vertex 1.02154 1.93078 2.60289 + vertex 1.0257 1.93146 2.60174 + endloop + endfacet + facet normal 0.278986 0.182881 0.94272 + outer loop + vertex 1.02488 1.939 2.60072 + vertex 1.02634 1.93587 2.60089 + vertex 1.02933 1.93861 2.59947 + endloop + endfacet + facet normal 0.278799 0.176751 0.943944 + outer loop + vertex 1.02488 1.939 2.60072 + vertex 1.02933 1.93861 2.59947 + vertex 1.02477 1.94366 2.59988 + endloop + endfacet + facet normal 0.238044 0.138549 0.961322 + outer loop + vertex 1.02477 1.94366 2.59988 + vertex 1.02933 1.93861 2.59947 + vertex 1.02961 1.9435 2.5987 + endloop + endfacet + facet normal 0.20949 0.15196 0.965931 + outer loop + vertex 1.02634 1.93587 2.60089 + vertex 1.02488 1.939 2.60072 + vertex 1.02167 1.9357 2.60193 + endloop + endfacet + facet normal 0.238036 0.123137 0.963419 + outer loop + vertex 1.02961 1.9435 2.5987 + vertex 1.02818 1.94749 2.59854 + vertex 1.02477 1.94366 2.59988 + endloop + endfacet + facet normal 0.203279 0.155332 0.966721 + outer loop + vertex 1.02477 1.94366 2.59988 + vertex 1.02818 1.94749 2.59854 + vertex 1.02461 1.94842 2.59915 + endloop + endfacet + facet normal 0.201796 0.148812 0.968057 + outer loop + vertex 1.02818 1.94749 2.59854 + vertex 1.02694 1.95104 2.59826 + vertex 1.02461 1.94842 2.59915 + endloop + endfacet + facet normal 0.153598 0.192137 0.969274 + outer loop + vertex 1.02461 1.94842 2.59915 + vertex 1.02694 1.95104 2.59826 + vertex 1.02337 1.95201 2.59863 + endloop + endfacet + facet normal 0.154572 0.196105 0.968324 + outer loop + vertex 1.02694 1.95104 2.59826 + vertex 1.02754 1.9554 2.59728 + vertex 1.02337 1.95201 2.59863 + endloop + endfacet + facet normal 0.119436 0.345016 0.930967 + outer loop + vertex 1.02374 2.11314 2.55859 + vertex 1.02657 2.11577 2.55725 + vertex 1.02126 2.11675 2.55757 + endloop + endfacet + facet normal 0.137078 0.538152 0.831626 + outer loop + vertex 1.02485 2.11932 2.55585 + vertex 1.02964 2.11853 2.55558 + vertex 1.02747 2.12168 2.5539 + endloop + endfacet + facet normal 0.136363 0.538735 0.831366 + outer loop + vertex 1.0233 2.12188 2.55445 + vertex 1.02485 2.11932 2.55585 + vertex 1.02747 2.12168 2.5539 + endloop + endfacet + facet normal 0.130919 0.417745 0.899083 + outer loop + vertex 1.02657 2.11577 2.55725 + vertex 1.02485 2.11932 2.55585 + vertex 1.02126 2.11675 2.55757 + endloop + endfacet + facet normal 0.120543 0.41398 0.902269 + outer loop + vertex 1.02964 2.11853 2.55558 + vertex 1.02485 2.11932 2.55585 + vertex 1.02657 2.11577 2.55725 + endloop + endfacet + facet normal 0.100027 0.833068 0.544051 + outer loop + vertex 1.02403 2.12419 2.552 + vertex 1.02984 2.1239 2.55138 + vertex 1.02669 2.12601 2.54872 + endloop + endfacet + facet normal 0.0838646 0.840595 0.535132 + outer loop + vertex 1.02154 2.12641 2.54891 + vertex 1.02403 2.12419 2.552 + vertex 1.02669 2.12601 2.54872 + endloop + endfacet + facet normal 0.127153 0.702246 0.700488 + outer loop + vertex 1.02747 2.12168 2.5539 + vertex 1.02403 2.12419 2.552 + vertex 1.0233 2.12188 2.55445 + endloop + endfacet + facet normal 0.111138 0.690811 0.714443 + outer loop + vertex 1.02984 2.1239 2.55138 + vertex 1.02403 2.12419 2.552 + vertex 1.02747 2.12168 2.5539 + endloop + endfacet + facet normal 0.00359988 0.3595 0.933138 + outer loop + vertex 1.03 2.13338 2.54 + vertex 1.025 2.13343 2.54 + vertex 1.02882 2.12957 2.54147 + endloop + endfacet + facet normal 0.0844588 0.426998 0.900299 + outer loop + vertex 1.02882 2.12957 2.54147 + vertex 1.025 2.13343 2.54 + vertex 1.02393 2.12984 2.5418 + endloop + endfacet + facet normal 0.0813598 0.869225 0.487677 + outer loop + vertex 1.02882 2.12957 2.54147 + vertex 1.02393 2.12984 2.5418 + vertex 1.0282 2.12757 2.54513 + endloop + endfacet + facet normal 0.0665364 0.86233 0.501956 + outer loop + vertex 1.0282 2.12757 2.54513 + vertex 1.02393 2.12984 2.5418 + vertex 1.02311 2.12782 2.54539 + endloop + endfacet + facet normal 0.0844549 0.911227 0.403154 + outer loop + vertex 1.02669 2.12601 2.54872 + vertex 1.02311 2.12782 2.54539 + vertex 1.02154 2.12641 2.54891 + endloop + endfacet + facet normal 0.0645858 0.904754 0.42101 + outer loop + vertex 1.0282 2.12757 2.54513 + vertex 1.02311 2.12782 2.54539 + vertex 1.02669 2.12601 2.54872 + endloop + endfacet + facet normal 0.00515251 -0.989069 -0.147361 + outer loop + vertex 1.035 0.892557 2.535 + vertex 1.03328 0.892209 2.53728 + vertex 1.03 0.892531 2.535 + endloop + endfacet + facet normal -0.142915 -0.98752 0.066173 + outer loop + vertex 1.03328 0.892209 2.53728 + vertex 1.03 0.892866 2.54 + vertex 1.03 0.892531 2.535 + endloop + endfacet + facet normal -0.162534 -0.985803 0.042137 + outer loop + vertex 1.03328 0.892209 2.53728 + vertex 1.03148 0.892678 2.54132 + vertex 1.03 0.892866 2.54 + endloop + endfacet + facet normal 0.100052 -0.963366 -0.248829 + outer loop + vertex 1.03148 0.892678 2.54132 + vertex 1.02715 0.892433 2.54053 + vertex 1.03 0.892866 2.54 + endloop + endfacet + facet normal 0.0602782 -0.967067 0.247282 + outer loop + vertex 1.03142 0.893655 2.54516 + vertex 1.03148 0.892678 2.54132 + vertex 1.03514 0.893689 2.54438 + endloop + endfacet + facet normal 0.0606453 -0.967044 0.247281 + outer loop + vertex 1.03142 0.893655 2.54516 + vertex 1.02727 0.893113 2.54406 + vertex 1.03148 0.892678 2.54132 + endloop + endfacet + facet normal 0.0210712 -0.98182 0.188639 + outer loop + vertex 1.02727 0.893113 2.54406 + vertex 1.02715 0.892433 2.54053 + vertex 1.03148 0.892678 2.54132 + endloop + endfacet + facet normal 0.0267258 -0.933056 0.358738 + outer loop + vertex 1.03142 0.893655 2.54516 + vertex 1.02918 0.894428 2.54734 + vertex 1.02727 0.893113 2.54406 + endloop + endfacet + facet normal 0.100479 -0.890674 0.443401 + outer loop + vertex 1.03514 0.893689 2.54438 + vertex 1.03314 0.895266 2.54801 + vertex 1.03142 0.893655 2.54516 + endloop + endfacet + facet normal 0.115188 -0.8927 0.435682 + outer loop + vertex 1.02918 0.894428 2.54734 + vertex 1.03142 0.893655 2.54516 + vertex 1.03314 0.895266 2.54801 + endloop + endfacet + facet normal 0.0785466 -0.822164 0.563806 + outer loop + vertex 1.02918 0.894428 2.54734 + vertex 1.03314 0.895266 2.54801 + vertex 1.02815 0.896469 2.55046 + endloop + endfacet + facet normal 0.112859 -0.781438 0.613692 + outer loop + vertex 1.02815 0.896469 2.55046 + vertex 1.03314 0.895266 2.54801 + vertex 1.03269 0.897522 2.55096 + endloop + endfacet + facet normal 0.0806114 -0.692203 0.717186 + outer loop + vertex 1.03269 0.897522 2.55096 + vertex 1.03004 0.899738 2.5534 + vertex 1.02815 0.896469 2.55046 + endloop + endfacet + facet normal 0.115752 -0.668928 0.734259 + outer loop + vertex 1.03517 0.899798 2.55264 + vertex 1.03004 0.899738 2.5534 + vertex 1.03269 0.897522 2.55096 + endloop + endfacet + facet normal 0.110472 -0.585496 0.803113 + outer loop + vertex 1.03036 0.902588 2.55543 + vertex 1.02668 0.901932 2.55546 + vertex 1.03004 0.899738 2.5534 + endloop + endfacet + facet normal 0.120243 -0.585564 0.801659 + outer loop + vertex 1.03036 0.902588 2.55543 + vertex 1.03004 0.899738 2.5534 + vertex 1.03372 0.902373 2.55477 + endloop + endfacet + facet normal 0.12423 -0.589364 0.798259 + outer loop + vertex 1.03372 0.902373 2.55477 + vertex 1.03004 0.899738 2.5534 + vertex 1.03517 0.899798 2.55264 + endloop + endfacet + facet normal 0.0883656 -0.458308 0.88439 + outer loop + vertex 1.03036 0.902588 2.55543 + vertex 1.02951 0.905135 2.55684 + vertex 1.02668 0.901932 2.55546 + endloop + endfacet + facet normal 0.138793 -0.485185 0.863326 + outer loop + vertex 1.03372 0.902373 2.55477 + vertex 1.03274 0.904704 2.55624 + vertex 1.03036 0.902588 2.55543 + endloop + endfacet + facet normal 0.103476 -0.453697 0.885128 + outer loop + vertex 1.03274 0.904704 2.55624 + vertex 1.02951 0.905135 2.55684 + vertex 1.03036 0.902588 2.55543 + endloop + endfacet + facet normal 0.122117 -0.365966 0.922581 + outer loop + vertex 1.03274 0.904704 2.55624 + vertex 1.03424 0.908603 2.55759 + vertex 1.02951 0.905135 2.55684 + endloop + endfacet + facet normal 0.163553 -0.130863 0.977817 + outer loop + vertex 1.03269 1.05833 2.59646 + vertex 1.03358 1.06323 2.59697 + vertex 1.02873 1.05852 2.59715 + endloop + endfacet + facet normal 0.196789 -0.165569 0.966365 + outer loop + vertex 1.02873 1.05852 2.59715 + vertex 1.03358 1.06323 2.59697 + vertex 1.02856 1.06332 2.59801 + endloop + endfacet + facet normal 0.197821 -0.144583 0.969517 + outer loop + vertex 1.03358 1.06323 2.59697 + vertex 1.03322 1.0683 2.5978 + vertex 1.02856 1.06332 2.59801 + endloop + endfacet + facet normal 0.228549 -0.173805 0.957892 + outer loop + vertex 1.02856 1.06332 2.59801 + vertex 1.03322 1.0683 2.5978 + vertex 1.02856 1.06846 2.59894 + endloop + endfacet + facet normal 0.230616 -0.145173 0.962154 + outer loop + vertex 1.03322 1.0683 2.5978 + vertex 1.03345 1.07357 2.59854 + vertex 1.02856 1.06846 2.59894 + endloop + endfacet + facet normal 0.279079 -0.193247 0.940622 + outer loop + vertex 1.02856 1.06846 2.59894 + vertex 1.03345 1.07357 2.59854 + vertex 1.02882 1.0737 2.59994 + endloop + endfacet + facet normal 0.277647 -0.20459 0.938645 + outer loop + vertex 1.02968 1.07768 2.60055 + vertex 1.02712 1.07554 2.60084 + vertex 1.02882 1.0737 2.59994 + endloop + endfacet + facet normal 0.350078 -0.216002 0.911476 + outer loop + vertex 1.02968 1.07768 2.60055 + vertex 1.02882 1.0737 2.59994 + vertex 1.03359 1.07915 2.5994 + endloop + endfacet + facet normal 0.282104 -0.153056 0.947096 + outer loop + vertex 1.03359 1.07915 2.5994 + vertex 1.02882 1.0737 2.59994 + vertex 1.03345 1.07357 2.59854 + endloop + endfacet + facet normal 0.240748 -0.157818 0.957671 + outer loop + vertex 1.02968 1.07768 2.60055 + vertex 1.02725 1.07848 2.60129 + vertex 1.02712 1.07554 2.60084 + endloop + endfacet + facet normal 0.332657 -0.155198 0.93019 + outer loop + vertex 1.02968 1.07768 2.60055 + vertex 1.03359 1.07915 2.5994 + vertex 1.03091 1.08149 2.60075 + endloop + endfacet + facet normal 0.25041 -0.130138 0.959353 + outer loop + vertex 1.03091 1.08149 2.60075 + vertex 1.02725 1.07848 2.60129 + vertex 1.02968 1.07768 2.60055 + endloop + endfacet + facet normal 0.355611 -0.1084 0.928327 + outer loop + vertex 1.03481 1.08484 2.59976 + vertex 1.03524 1.08944 2.60013 + vertex 1.03173 1.08609 2.60108 + endloop + endfacet + facet normal 0.370535 -0.126369 0.920182 + outer loop + vertex 1.03524 1.08944 2.60013 + vertex 1.03261 1.08993 2.60126 + vertex 1.03173 1.08609 2.60108 + endloop + endfacet + facet normal 0.497299 -0.0744394 0.86438 + outer loop + vertex 1.03426 1.2044 2.60809 + vertex 1.03406 1.20969 2.60866 + vertex 1.03072 1.20636 2.6103 + endloop + endfacet + facet normal 0.498769 -0.0711403 0.86381 + outer loop + vertex 1.03045 1.20128 2.61003 + vertex 1.03426 1.2044 2.60809 + vertex 1.03072 1.20636 2.6103 + endloop + endfacet + facet normal 0.511044 -0.0714012 0.856584 + outer loop + vertex 1.03072 1.20636 2.6103 + vertex 1.02732 1.20311 2.61205 + vertex 1.03045 1.20128 2.61003 + endloop + endfacet + facet normal 0.507918 -0.0669372 0.858801 + outer loop + vertex 1.0275 1.20808 2.61233 + vertex 1.02732 1.20311 2.61205 + vertex 1.03072 1.20636 2.6103 + endloop + endfacet + facet normal 0.490028 -0.056567 0.869869 + outer loop + vertex 1.03406 1.20969 2.60866 + vertex 1.03418 1.21469 2.60892 + vertex 1.0308 1.21138 2.61061 + endloop + endfacet + facet normal 0.487835 -0.0617914 0.870746 + outer loop + vertex 1.03072 1.20636 2.6103 + vertex 1.03406 1.20969 2.60866 + vertex 1.0308 1.21138 2.61061 + endloop + endfacet + facet normal 0.510275 -0.0613653 0.857819 + outer loop + vertex 1.0308 1.21138 2.61061 + vertex 1.0275 1.20808 2.61233 + vertex 1.03072 1.20636 2.6103 + endloop + endfacet + facet normal 0.504025 -0.0528825 0.862068 + outer loop + vertex 1.02761 1.21304 2.61257 + vertex 1.0275 1.20808 2.61233 + vertex 1.0308 1.21138 2.61061 + endloop + endfacet + facet normal 0.476941 -0.03923 0.878059 + outer loop + vertex 1.03418 1.21469 2.60892 + vertex 1.03441 1.21977 2.60902 + vertex 1.03088 1.21636 2.61078 + endloop + endfacet + facet normal 0.477005 -0.0390749 0.878032 + outer loop + vertex 1.0308 1.21138 2.61061 + vertex 1.03418 1.21469 2.60892 + vertex 1.03088 1.21636 2.61078 + endloop + endfacet + facet normal 0.509663 -0.038991 0.85949 + outer loop + vertex 1.03088 1.21636 2.61078 + vertex 1.02761 1.21304 2.61257 + vertex 1.0308 1.21138 2.61061 + endloop + endfacet + facet normal 0.502077 -0.0288666 0.864341 + outer loop + vertex 1.02768 1.21801 2.6127 + vertex 1.02761 1.21304 2.61257 + vertex 1.03088 1.21636 2.61078 + endloop + endfacet + facet normal 0.461415 -0.0185761 0.88699 + outer loop + vertex 1.03088 1.21636 2.61078 + vertex 1.03441 1.21977 2.60902 + vertex 1.03095 1.22133 2.61085 + endloop + endfacet + facet normal 0.50605 -0.0187774 0.8623 + outer loop + vertex 1.03095 1.22133 2.61085 + vertex 1.02768 1.21801 2.6127 + vertex 1.03088 1.21636 2.61078 + endloop + endfacet + facet normal 0.499064 -0.00956501 0.866513 + outer loop + vertex 1.02772 1.22297 2.61273 + vertex 1.02768 1.21801 2.6127 + vertex 1.03095 1.22133 2.61085 + endloop + endfacet + facet normal 0.457319 -0.0438917 0.888219 + outer loop + vertex 1.02826 1.24868 2.61312 + vertex 1.02801 1.24289 2.61296 + vertex 1.03142 1.24595 2.61136 + endloop + endfacet + facet normal 0.42128 -0.0332699 0.90632 + outer loop + vertex 1.03171 1.25326 2.61168 + vertex 1.02833 1.25452 2.6133 + vertex 1.02826 1.24868 2.61312 + endloop + endfacet + facet normal 0.416006 -0.0495963 0.908008 + outer loop + vertex 1.03171 1.25326 2.61168 + vertex 1.03188 1.25792 2.61186 + vertex 1.02833 1.25452 2.6133 + endloop + endfacet + facet normal 0.390218 -0.017399 0.920558 + outer loop + vertex 1.02833 1.25452 2.6133 + vertex 1.03188 1.25792 2.61186 + vertex 1.0281 1.25998 2.6135 + endloop + endfacet + facet normal 0.381529 -0.0358337 0.923662 + outer loop + vertex 1.03188 1.25792 2.61186 + vertex 1.03224 1.26273 2.6119 + vertex 1.0281 1.25998 2.6135 + endloop + endfacet + facet normal 0.357148 0.00681528 0.934023 + outer loop + vertex 1.0281 1.25998 2.6135 + vertex 1.03224 1.26273 2.6119 + vertex 1.02945 1.26452 2.61295 + endloop + endfacet + facet normal 0.33703 -0.0287116 0.941056 + outer loop + vertex 1.03224 1.26273 2.6119 + vertex 1.03264 1.26746 2.6119 + vertex 1.02945 1.26452 2.61295 + endloop + endfacet + facet normal 0.333154 -0.0239699 0.942568 + outer loop + vertex 1.02945 1.26452 2.61295 + vertex 1.03264 1.26746 2.6119 + vertex 1.02904 1.2686 2.6132 + endloop + endfacet + facet normal 0.326597 -0.0463354 0.944027 + outer loop + vertex 1.03264 1.26746 2.6119 + vertex 1.03335 1.27286 2.61192 + vertex 1.02904 1.2686 2.6132 + endloop + endfacet + facet normal 0.321309 0.101415 0.941528 + outer loop + vertex 1.03184 1.75617 2.61186 + vertex 1.03067 1.76155 2.61169 + vertex 1.02791 1.75743 2.61307 + endloop + endfacet + facet normal 0.344667 0.0835694 0.934998 + outer loop + vertex 1.02791 1.75743 2.61307 + vertex 1.03067 1.76155 2.61169 + vertex 1.02699 1.76151 2.61304 + endloop + endfacet + facet normal 0.254542 0.10491 0.961354 + outer loop + vertex 1.03405 1.76392 2.61043 + vertex 1.03523 1.76841 2.60962 + vertex 1.03156 1.76595 2.61087 + endloop + endfacet + facet normal 0.268699 0.123584 0.955263 + outer loop + vertex 1.03156 1.76595 2.61087 + vertex 1.03067 1.76155 2.61169 + vertex 1.03405 1.76392 2.61043 + endloop + endfacet + facet normal 0.347569 0.103234 0.931954 + outer loop + vertex 1.03156 1.76595 2.61087 + vertex 1.0278 1.76613 2.61225 + vertex 1.03067 1.76155 2.61169 + endloop + endfacet + facet normal 0.34395 0.100771 0.933565 + outer loop + vertex 1.0278 1.76613 2.61225 + vertex 1.02699 1.76151 2.61304 + vertex 1.03067 1.76155 2.61169 + endloop + endfacet + facet normal 0.271552 0.10909 0.956221 + outer loop + vertex 1.03523 1.76841 2.60962 + vertex 1.03426 1.7737 2.6093 + vertex 1.03082 1.77009 2.61069 + endloop + endfacet + facet normal 0.264811 0.0889603 0.960188 + outer loop + vertex 1.03156 1.76595 2.61087 + vertex 1.03523 1.76841 2.60962 + vertex 1.03082 1.77009 2.61069 + endloop + endfacet + facet normal 0.347564 0.102522 0.932035 + outer loop + vertex 1.03082 1.77009 2.61069 + vertex 1.0278 1.76613 2.61225 + vertex 1.03156 1.76595 2.61087 + endloop + endfacet + facet normal 0.371693 0.0812634 0.924792 + outer loop + vertex 1.02694 1.77178 2.6121 + vertex 1.0278 1.76613 2.61225 + vertex 1.03082 1.77009 2.61069 + endloop + endfacet + facet normal 0.303079 0.091267 0.948585 + outer loop + vertex 1.03426 1.7737 2.6093 + vertex 1.03342 1.77914 2.60904 + vertex 1.03003 1.7751 2.61051 + endloop + endfacet + facet normal 0.299903 0.079901 0.950618 + outer loop + vertex 1.03082 1.77009 2.61069 + vertex 1.03426 1.7737 2.6093 + vertex 1.03003 1.7751 2.61051 + endloop + endfacet + facet normal 0.375025 0.0907882 0.922558 + outer loop + vertex 1.03003 1.7751 2.61051 + vertex 1.02694 1.77178 2.6121 + vertex 1.03082 1.77009 2.61069 + endloop + endfacet + facet normal 0.407798 0.0549649 0.911416 + outer loop + vertex 1.02617 1.77732 2.61211 + vertex 1.02694 1.77178 2.6121 + vertex 1.03003 1.7751 2.61051 + endloop + endfacet + facet normal 0.329088 0.0669991 0.941919 + outer loop + vertex 1.02939 1.77921 2.61044 + vertex 1.03003 1.7751 2.61051 + vertex 1.03342 1.77914 2.60904 + endloop + endfacet + facet normal 0.32909 0.066775 0.941935 + outer loop + vertex 1.02939 1.77921 2.61044 + vertex 1.03342 1.77914 2.60904 + vertex 1.03066 1.78355 2.60969 + endloop + endfacet + facet normal 0.342354 0.075901 0.9365 + outer loop + vertex 1.03066 1.78355 2.60969 + vertex 1.03342 1.77914 2.60904 + vertex 1.03441 1.78359 2.60832 + endloop + endfacet + facet normal 0.419423 0.0803501 0.904228 + outer loop + vertex 1.03003 1.7751 2.61051 + vertex 1.02939 1.77921 2.61044 + vertex 1.02617 1.77732 2.61211 + endloop + endfacet + facet normal 0.342143 0.0816893 0.93609 + outer loop + vertex 1.03441 1.78359 2.60832 + vertex 1.03367 1.7874 2.60826 + vertex 1.03066 1.78355 2.60969 + endloop + endfacet + facet normal 0.377368 0.0499689 0.924714 + outer loop + vertex 1.03066 1.78355 2.60969 + vertex 1.03367 1.7874 2.60826 + vertex 1.03001 1.78891 2.60967 + endloop + endfacet + facet normal 0.386827 0.0784165 0.918812 + outer loop + vertex 1.03367 1.7874 2.60826 + vertex 1.03302 1.79222 2.60812 + vertex 1.03001 1.78891 2.60967 + endloop + endfacet + facet normal 0.411016 0.0523497 0.910124 + outer loop + vertex 1.03001 1.78891 2.60967 + vertex 1.03302 1.79222 2.60812 + vertex 1.02954 1.79385 2.6096 + endloop + endfacet + facet normal 0.422861 0.0846737 0.90223 + outer loop + vertex 1.03302 1.79222 2.60812 + vertex 1.03209 1.79644 2.60816 + vertex 1.02954 1.79385 2.6096 + endloop + endfacet + facet normal 0.450853 0.0508818 0.891147 + outer loop + vertex 1.02954 1.79385 2.6096 + vertex 1.03209 1.79644 2.60816 + vertex 1.02939 1.79867 2.6094 + endloop + endfacet + facet normal 0.450953 0.0510353 0.891088 + outer loop + vertex 1.03209 1.79644 2.60816 + vertex 1.03301 1.80114 2.60742 + vertex 1.02939 1.79867 2.6094 + endloop + endfacet + facet normal 0.436293 0.0784837 0.896375 + outer loop + vertex 1.03451 1.91246 2.60014 + vertex 1.03167 1.90745 2.60196 + vertex 1.03478 1.90842 2.60036 + endloop + endfacet + facet normal 0.24317 0.162369 0.956297 + outer loop + vertex 1.02818 1.94749 2.59854 + vertex 1.03098 1.95159 2.59714 + vertex 1.02694 1.95104 2.59826 + endloop + endfacet + facet normal 0.301753 0.15265 0.941086 + outer loop + vertex 1.03437 1.95411 2.5957 + vertex 1.03508 1.95833 2.59479 + vertex 1.03183 1.95596 2.59622 + endloop + endfacet + facet normal 0.29439 0.141373 0.945171 + outer loop + vertex 1.03183 1.95596 2.59622 + vertex 1.03098 1.95159 2.59714 + vertex 1.03437 1.95411 2.5957 + endloop + endfacet + facet normal 0.217165 0.160077 0.96292 + outer loop + vertex 1.03183 1.95596 2.59622 + vertex 1.02754 1.9554 2.59728 + vertex 1.03098 1.95159 2.59714 + endloop + endfacet + facet normal 0.239922 0.180975 0.953774 + outer loop + vertex 1.02754 1.9554 2.59728 + vertex 1.02694 1.95104 2.59826 + vertex 1.03098 1.95159 2.59714 + endloop + endfacet + facet normal 0.269394 0.154496 0.950557 + outer loop + vertex 1.03508 1.95833 2.59479 + vertex 1.03357 1.96362 2.59436 + vertex 1.03063 1.95961 2.59584 + endloop + endfacet + facet normal 0.276959 0.187399 0.942431 + outer loop + vertex 1.03183 1.95596 2.59622 + vertex 1.03508 1.95833 2.59479 + vertex 1.03063 1.95961 2.59584 + endloop + endfacet + facet normal 0.215652 0.16934 0.961675 + outer loop + vertex 1.03063 1.95961 2.59584 + vertex 1.02754 1.9554 2.59728 + vertex 1.03183 1.95596 2.59622 + endloop + endfacet + facet normal 0.126078 0.521714 0.843753 + outer loop + vertex 1.02964 2.11853 2.55558 + vertex 1.03385 2.11778 2.55541 + vertex 1.03313 2.12101 2.55352 + endloop + endfacet + facet normal 0.118234 0.529618 0.839956 + outer loop + vertex 1.02747 2.12168 2.5539 + vertex 1.02964 2.11853 2.55558 + vertex 1.03313 2.12101 2.55352 + endloop + endfacet + facet normal 0.13217 0.40303 0.905592 + outer loop + vertex 1.03189 2.1146 2.557 + vertex 1.02964 2.11853 2.55558 + vertex 1.02657 2.11577 2.55725 + endloop + endfacet + facet normal 0.105555 0.39099 0.914322 + outer loop + vertex 1.03385 2.11778 2.55541 + vertex 1.02964 2.11853 2.55558 + vertex 1.03189 2.1146 2.557 + endloop + endfacet + facet normal 0.0917145 0.822948 0.560664 + outer loop + vertex 1.02984 2.1239 2.55138 + vertex 1.03506 2.12375 2.55075 + vertex 1.03189 2.12576 2.54831 + endloop + endfacet + facet normal 0.0839991 0.826006 0.557367 + outer loop + vertex 1.02669 2.12601 2.54872 + vertex 1.02984 2.1239 2.55138 + vertex 1.03189 2.12576 2.54831 + endloop + endfacet + facet normal 0.128331 0.680466 0.721455 + outer loop + vertex 1.03313 2.12101 2.55352 + vertex 1.02984 2.1239 2.55138 + vertex 1.02747 2.12168 2.5539 + endloop + endfacet + facet normal 0.108377 0.668401 0.735864 + outer loop + vertex 1.03506 2.12375 2.55075 + vertex 1.02984 2.1239 2.55138 + vertex 1.03313 2.12101 2.55352 + endloop + endfacet + facet normal -0.00806301 0.575147 0.81801 + outer loop + vertex 1.035 2.13349 2.535 + vertex 1.03 2.13342 2.535 + vertex 1.03382 2.13057 2.53705 + endloop + endfacet + facet normal 0.5962 0.80281 0.00643136 + outer loop + vertex 1.03382 2.13057 2.53705 + vertex 1.03 2.13342 2.535 + vertex 1.03 2.13338 2.54 + endloop + endfacet + facet normal 0.708738 0.630837 0.315808 + outer loop + vertex 1.03382 2.13057 2.53705 + vertex 1.03 2.13338 2.54 + vertex 1.03353 2.12905 2.54073 + endloop + endfacet + facet normal 0.181525 0.305019 0.934886 + outer loop + vertex 1.03353 2.12905 2.54073 + vertex 1.03 2.13338 2.54 + vertex 1.02882 2.12957 2.54147 + endloop + endfacet + facet normal 0.163399 0.900497 0.402997 + outer loop + vertex 1.03353 2.12905 2.54073 + vertex 1.02882 2.12957 2.54147 + vertex 1.03317 2.12736 2.54465 + endloop + endfacet + facet normal 0.0851302 0.868674 0.488015 + outer loop + vertex 1.03317 2.12736 2.54465 + vertex 1.02882 2.12957 2.54147 + vertex 1.0282 2.12757 2.54513 + endloop + endfacet + facet normal 0.0772531 0.901856 0.425073 + outer loop + vertex 1.03189 2.12576 2.54831 + vertex 1.0282 2.12757 2.54513 + vertex 1.02669 2.12601 2.54872 + endloop + endfacet + facet normal 0.0802537 0.90294 0.422208 + outer loop + vertex 1.03317 2.12736 2.54465 + vertex 1.0282 2.12757 2.54513 + vertex 1.03189 2.12576 2.54831 + endloop + endfacet + facet normal 0.00530547 -0.98246 -0.186396 + outer loop + vertex 1.04 0.892584 2.535 + vertex 1.0381 0.892243 2.53675 + vertex 1.035 0.892557 2.535 + endloop + endfacet + facet normal -0.0106179 -0.987221 -0.159001 + outer loop + vertex 1.0381 0.892243 2.53675 + vertex 1.03328 0.892209 2.53728 + vertex 1.035 0.892557 2.535 + endloop + endfacet + facet normal 0.0214242 -0.991047 0.131786 + outer loop + vertex 1.0381 0.892243 2.53675 + vertex 1.03662 0.892704 2.54045 + vertex 1.03328 0.892209 2.53728 + endloop + endfacet + facet normal 0.0263967 -0.991597 0.126646 + outer loop + vertex 1.03662 0.892704 2.54045 + vertex 1.03148 0.892678 2.54132 + vertex 1.03328 0.892209 2.53728 + endloop + endfacet + facet normal 0.048881 -0.964371 0.26 + outer loop + vertex 1.03662 0.892704 2.54045 + vertex 1.03514 0.893689 2.54438 + vertex 1.03148 0.892678 2.54132 + endloop + endfacet + facet normal 0.0745109 -0.960355 0.268639 + outer loop + vertex 1.03974 0.893897 2.54385 + vertex 1.03514 0.893689 2.54438 + vertex 1.03662 0.892704 2.54045 + endloop + endfacet + facet normal 0.0887657 -0.906311 0.413185 + outer loop + vertex 1.03514 0.893689 2.54438 + vertex 1.03974 0.893897 2.54385 + vertex 1.03753 0.895028 2.54681 + endloop + endfacet + facet normal 0.0684674 -0.900268 0.429919 + outer loop + vertex 1.03314 0.895266 2.54801 + vertex 1.03514 0.893689 2.54438 + vertex 1.03753 0.895028 2.54681 + endloop + endfacet + facet normal 0.117942 -0.797995 0.591011 + outer loop + vertex 1.03753 0.895028 2.54681 + vertex 1.03731 0.897219 2.54981 + vertex 1.03314 0.895266 2.54801 + endloop + endfacet + facet normal 0.101387 -0.783279 0.613347 + outer loop + vertex 1.03731 0.897219 2.54981 + vertex 1.03269 0.897522 2.55096 + vertex 1.03314 0.895266 2.54801 + endloop + endfacet + facet normal 0.134943 -0.679907 0.720775 + outer loop + vertex 1.03731 0.897219 2.54981 + vertex 1.03517 0.899798 2.55264 + vertex 1.03269 0.897522 2.55096 + endloop + endfacet + facet normal 0.121558 -0.686616 0.716786 + outer loop + vertex 1.03976 0.900084 2.55214 + vertex 1.03517 0.899798 2.55264 + vertex 1.03731 0.897219 2.54981 + endloop + endfacet + facet normal 0.124791 -0.568829 0.812933 + outer loop + vertex 1.03976 0.900084 2.55214 + vertex 1.03832 0.902834 2.55429 + vertex 1.03517 0.899798 2.55264 + endloop + endfacet + facet normal 0.14289 -0.581199 0.801118 + outer loop + vertex 1.03517 0.899798 2.55264 + vertex 1.03832 0.902834 2.55429 + vertex 1.03372 0.902373 2.55477 + endloop + endfacet + facet normal 0.139066 -0.467047 0.873228 + outer loop + vertex 1.03372 0.902373 2.55477 + vertex 1.03832 0.902834 2.55429 + vertex 1.03661 0.905642 2.55606 + endloop + endfacet + facet normal 0.156059 -0.478463 0.864129 + outer loop + vertex 1.03274 0.904704 2.55624 + vertex 1.03372 0.902373 2.55477 + vertex 1.03661 0.905642 2.55606 + endloop + endfacet + facet normal 0.132027 -0.368892 0.920047 + outer loop + vertex 1.03661 0.905642 2.55606 + vertex 1.03424 0.908603 2.55759 + vertex 1.03274 0.904704 2.55624 + endloop + endfacet + facet normal 0.135682 -0.366243 0.920574 + outer loop + vertex 1.03987 0.909681 2.55719 + vertex 1.03424 0.908603 2.55759 + vertex 1.03661 0.905642 2.55606 + endloop + endfacet + facet normal 0.189171 -0.190376 0.963313 + outer loop + vertex 1.03369 1.03881 2.5922 + vertex 1.03813 1.04354 2.59227 + vertex 1.0335 1.04342 2.59315 + endloop + endfacet + facet normal 0.189412 -0.159152 0.968914 + outer loop + vertex 1.03813 1.04354 2.59227 + vertex 1.03837 1.04845 2.59303 + vertex 1.0335 1.04342 2.59315 + endloop + endfacet + facet normal 0.225966 -0.194858 0.954447 + outer loop + vertex 1.0335 1.04342 2.59315 + vertex 1.03837 1.04845 2.59303 + vertex 1.03367 1.0484 2.59413 + endloop + endfacet + facet normal 0.226977 -0.163759 0.960033 + outer loop + vertex 1.03837 1.04845 2.59303 + vertex 1.03867 1.05362 2.59383 + vertex 1.03367 1.0484 2.59413 + endloop + endfacet + facet normal 0.273381 -0.209485 0.938818 + outer loop + vertex 1.03367 1.0484 2.59413 + vertex 1.03867 1.05362 2.59383 + vertex 1.03405 1.05347 2.59515 + endloop + endfacet + facet normal 0.263577 -0.212687 0.940899 + outer loop + vertex 1.03503 1.05739 2.59576 + vertex 1.0324 1.05524 2.59601 + vertex 1.03405 1.05347 2.59515 + endloop + endfacet + facet normal 0.338179 -0.226903 0.913318 + outer loop + vertex 1.03503 1.05739 2.59576 + vertex 1.03405 1.05347 2.59515 + vertex 1.03883 1.05893 2.59473 + endloop + endfacet + facet normal 0.274345 -0.168524 0.94675 + outer loop + vertex 1.03883 1.05893 2.59473 + vertex 1.03405 1.05347 2.59515 + vertex 1.03867 1.05362 2.59383 + endloop + endfacet + facet normal 0.223948 -0.161841 0.96107 + outer loop + vertex 1.03503 1.05739 2.59576 + vertex 1.03269 1.05833 2.59646 + vertex 1.0324 1.05524 2.59601 + endloop + endfacet + facet normal 0.335469 -0.14744 0.930442 + outer loop + vertex 1.03883 1.05893 2.59473 + vertex 1.0401 1.06432 2.59513 + vertex 1.03643 1.06117 2.59595 + endloop + endfacet + facet normal 0.319003 -0.166406 0.933031 + outer loop + vertex 1.03503 1.05739 2.59576 + vertex 1.03883 1.05893 2.59473 + vertex 1.03643 1.06117 2.59595 + endloop + endfacet + facet normal 0.234564 -0.136565 0.96246 + outer loop + vertex 1.03643 1.06117 2.59595 + vertex 1.03269 1.05833 2.59646 + vertex 1.03503 1.05739 2.59576 + endloop + endfacet + facet normal 0.23901 -0.142787 0.960461 + outer loop + vertex 1.03358 1.06323 2.59697 + vertex 1.03269 1.05833 2.59646 + vertex 1.03643 1.06117 2.59595 + endloop + endfacet + facet normal 0.336162 -0.148353 0.930046 + outer loop + vertex 1.0401 1.06432 2.59513 + vertex 1.03758 1.06494 2.59614 + vertex 1.03643 1.06117 2.59595 + endloop + endfacet + facet normal 0.252045 -0.124298 0.9597 + outer loop + vertex 1.03758 1.06494 2.59614 + vertex 1.03358 1.06323 2.59697 + vertex 1.03643 1.06117 2.59595 + endloop + endfacet + facet normal 0.250994 -0.121538 0.960328 + outer loop + vertex 1.03758 1.06494 2.59614 + vertex 1.03722 1.06817 2.59664 + vertex 1.03358 1.06323 2.59697 + endloop + endfacet + facet normal 0.375187 -0.103456 0.921158 + outer loop + vertex 1.03488 1.09268 2.60064 + vertex 1.03261 1.08993 2.60126 + vertex 1.03524 1.08944 2.60013 + endloop + endfacet + facet normal 0.491843 -0.0492753 0.869289 + outer loop + vertex 1.03764 1.13329 2.60245 + vertex 1.03776 1.13827 2.60266 + vertex 1.03448 1.13494 2.60433 + endloop + endfacet + facet normal 0.488722 -0.0472637 0.871158 + outer loop + vertex 1.03425 1.14782 2.60524 + vertex 1.03176 1.14867 2.60668 + vertex 1.03231 1.14537 2.60619 + endloop + endfacet + facet normal 0.491162 -0.038465 0.870219 + outer loop + vertex 1.0348 1.15158 2.6051 + vertex 1.03176 1.14867 2.60668 + vertex 1.03425 1.14782 2.60524 + endloop + endfacet + facet normal 0.487515 -0.0536786 0.871463 + outer loop + vertex 1.03341 1.19899 2.60809 + vertex 1.03291 1.19396 2.60805 + vertex 1.03637 1.19665 2.60629 + endloop + endfacet + facet normal 0.404927 -0.0854921 0.910344 + outer loop + vertex 1.04 1.19962 2.60487 + vertex 1.04011 1.20403 2.60523 + vertex 1.03682 1.20133 2.60644 + endloop + endfacet + facet normal 0.474639 -0.0742391 0.877044 + outer loop + vertex 1.03682 1.20133 2.60644 + vertex 1.03341 1.19899 2.60809 + vertex 1.03637 1.19665 2.60629 + endloop + endfacet + facet normal 0.474928 -0.0748054 0.87684 + outer loop + vertex 1.03426 1.2044 2.60809 + vertex 1.03341 1.19899 2.60809 + vertex 1.03682 1.20133 2.60644 + endloop + endfacet + facet normal 0.398425 -0.0758944 0.914056 + outer loop + vertex 1.04011 1.20403 2.60523 + vertex 1.03752 1.20496 2.60643 + vertex 1.03682 1.20133 2.60644 + endloop + endfacet + facet normal 0.46237 -0.0882276 0.882287 + outer loop + vertex 1.03752 1.20496 2.60643 + vertex 1.03426 1.2044 2.60809 + vertex 1.03682 1.20133 2.60644 + endloop + endfacet + facet normal 0.462127 -0.0856529 0.882667 + outer loop + vertex 1.03752 1.20496 2.60643 + vertex 1.03718 1.20834 2.60694 + vertex 1.03426 1.2044 2.60809 + endloop + endfacet + facet normal 0.454361 -0.0785207 0.88735 + outer loop + vertex 1.03718 1.20834 2.60694 + vertex 1.03406 1.20969 2.60866 + vertex 1.03426 1.2044 2.60809 + endloop + endfacet + facet normal 0.455641 -0.0751072 0.886989 + outer loop + vertex 1.03718 1.20834 2.60694 + vertex 1.03739 1.21296 2.60722 + vertex 1.03406 1.20969 2.60866 + endloop + endfacet + facet normal 0.441294 -0.0567087 0.895569 + outer loop + vertex 1.03406 1.20969 2.60866 + vertex 1.03739 1.21296 2.60722 + vertex 1.03418 1.21469 2.60892 + endloop + endfacet + facet normal 0.44066 -0.058101 0.895792 + outer loop + vertex 1.03739 1.21296 2.60722 + vertex 1.03778 1.21799 2.60736 + vertex 1.03418 1.21469 2.60892 + endloop + endfacet + facet normal 0.425292 -0.0373589 0.904285 + outer loop + vertex 1.03418 1.21469 2.60892 + vertex 1.03778 1.21799 2.60736 + vertex 1.03441 1.21977 2.60902 + endloop + endfacet + facet normal 0.2124 0.107797 0.971219 + outer loop + vertex 1.03952 1.75876 2.60982 + vertex 1.03853 1.76425 2.60942 + vertex 1.035 1.75987 2.61068 + endloop + endfacet + facet normal 0.207281 0.084366 0.974637 + outer loop + vertex 1.03602 1.75496 2.61089 + vertex 1.03952 1.75876 2.60982 + vertex 1.035 1.75987 2.61068 + endloop + endfacet + facet normal 0.251251 0.0930214 0.963442 + outer loop + vertex 1.035 1.75987 2.61068 + vertex 1.03184 1.75617 2.61186 + vertex 1.03602 1.75496 2.61089 + endloop + endfacet + facet normal 0.256756 0.0880017 0.962462 + outer loop + vertex 1.03067 1.76155 2.61169 + vertex 1.03184 1.75617 2.61186 + vertex 1.035 1.75987 2.61068 + endloop + endfacet + facet normal 0.209249 0.110448 0.971605 + outer loop + vertex 1.03405 1.76392 2.61043 + vertex 1.035 1.75987 2.61068 + vertex 1.03853 1.76425 2.60942 + endloop + endfacet + facet normal 0.208459 0.118764 0.970793 + outer loop + vertex 1.03405 1.76392 2.61043 + vertex 1.03853 1.76425 2.60942 + vertex 1.03523 1.76841 2.60962 + endloop + endfacet + facet normal 0.203806 0.115005 0.972233 + outer loop + vertex 1.03523 1.76841 2.60962 + vertex 1.03853 1.76425 2.60942 + vertex 1.0397 1.76897 2.60862 + endloop + endfacet + facet normal 0.268778 0.123466 0.955256 + outer loop + vertex 1.035 1.75987 2.61068 + vertex 1.03405 1.76392 2.61043 + vertex 1.03067 1.76155 2.61169 + endloop + endfacet + facet normal 0.265296 0.0869389 0.960239 + outer loop + vertex 1.03916 1.79885 2.60549 + vertex 1.04034 1.80344 2.60475 + vertex 1.0367 1.80095 2.60598 + endloop + endfacet + facet normal 0.278646 0.103915 0.954755 + outer loop + vertex 1.0367 1.80095 2.60598 + vertex 1.0358 1.79638 2.60674 + vertex 1.03916 1.79885 2.60549 + endloop + endfacet + facet normal 0.366901 0.0819103 0.926647 + outer loop + vertex 1.0367 1.80095 2.60598 + vertex 1.03301 1.80114 2.60742 + vertex 1.0358 1.79638 2.60674 + endloop + endfacet + facet normal 0.288599 0.104156 0.951768 + outer loop + vertex 1.04034 1.80344 2.60475 + vertex 1.03945 1.80875 2.60444 + vertex 1.0361 1.80519 2.60584 + endloop + endfacet + facet normal 0.276268 0.0701118 0.95852 + outer loop + vertex 1.0367 1.80095 2.60598 + vertex 1.04034 1.80344 2.60475 + vertex 1.0361 1.80519 2.60584 + endloop + endfacet + facet normal 0.3669 0.081855 0.926652 + outer loop + vertex 1.0361 1.80519 2.60584 + vertex 1.03301 1.80114 2.60742 + vertex 1.0367 1.80095 2.60598 + endloop + endfacet + facet normal 0.391698 0.0596137 0.918161 + outer loop + vertex 1.03245 1.80682 2.60729 + vertex 1.03301 1.80114 2.60742 + vertex 1.0361 1.80519 2.60584 + endloop + endfacet + facet normal 0.326908 0.0960239 0.940165 + outer loop + vertex 1.03945 1.80875 2.60444 + vertex 1.03888 1.8136 2.60414 + vertex 1.0356 1.81024 2.60562 + endloop + endfacet + facet normal 0.319275 0.0725995 0.944877 + outer loop + vertex 1.0361 1.80519 2.60584 + vertex 1.03945 1.80875 2.60444 + vertex 1.0356 1.81024 2.60562 + endloop + endfacet + facet normal 0.398582 0.0790506 0.913719 + outer loop + vertex 1.0356 1.81024 2.60562 + vertex 1.03245 1.80682 2.60729 + vertex 1.0361 1.80519 2.60584 + endloop + endfacet + facet normal 0.422783 0.0524038 0.904714 + outer loop + vertex 1.03214 1.81195 2.60714 + vertex 1.03245 1.80682 2.60729 + vertex 1.0356 1.81024 2.60562 + endloop + endfacet + facet normal 0.362484 0.0805554 0.928502 + outer loop + vertex 1.03888 1.8136 2.60414 + vertex 1.03857 1.81844 2.60384 + vertex 1.03525 1.81522 2.60542 + endloop + endfacet + facet normal 0.356282 0.0637483 0.932201 + outer loop + vertex 1.0356 1.81024 2.60562 + vertex 1.03888 1.8136 2.60414 + vertex 1.03525 1.81522 2.60542 + endloop + endfacet + facet normal 0.428604 0.0675872 0.900961 + outer loop + vertex 1.03525 1.81522 2.60542 + vertex 1.03214 1.81195 2.60714 + vertex 1.0356 1.81024 2.60562 + endloop + endfacet + facet normal 0.452168 0.0398907 0.89104 + outer loop + vertex 1.03183 1.817 2.60707 + vertex 1.03214 1.81195 2.60714 + vertex 1.03525 1.81522 2.60542 + endloop + endfacet + facet normal 0.395274 0.0826744 0.914835 + outer loop + vertex 1.03857 1.81844 2.60384 + vertex 1.03783 1.8238 2.60368 + vertex 1.03482 1.82014 2.60531 + endloop + endfacet + facet normal 0.384868 0.054055 0.921387 + outer loop + vertex 1.03525 1.81522 2.60542 + vertex 1.03857 1.81844 2.60384 + vertex 1.03482 1.82014 2.60531 + endloop + endfacet + facet normal 0.460026 0.059768 0.885891 + outer loop + vertex 1.03482 1.82014 2.60531 + vertex 1.03183 1.817 2.60707 + vertex 1.03525 1.81522 2.60542 + endloop + endfacet + facet normal 0.481544 0.0335873 0.875778 + outer loop + vertex 1.03131 1.82237 2.60715 + vertex 1.03183 1.817 2.60707 + vertex 1.03482 1.82014 2.60531 + endloop + endfacet + facet normal 0.424049 0.0542182 0.904015 + outer loop + vertex 1.03432 1.82416 2.6053 + vertex 1.03482 1.82014 2.60531 + vertex 1.03783 1.8238 2.60368 + endloop + endfacet + facet normal 0.424687 0.0648174 0.903017 + outer loop + vertex 1.03432 1.82416 2.6053 + vertex 1.03783 1.8238 2.60368 + vertex 1.03537 1.82817 2.60452 + endloop + endfacet + facet normal 0.454171 0.0845813 0.88689 + outer loop + vertex 1.03537 1.82817 2.60452 + vertex 1.03783 1.8238 2.60368 + vertex 1.03813 1.8275 2.60317 + endloop + endfacet + facet normal 0.495399 0.0631274 0.866369 + outer loop + vertex 1.03482 1.82014 2.60531 + vertex 1.03432 1.82416 2.6053 + vertex 1.03131 1.82237 2.60715 + endloop + endfacet + facet normal 0.448787 0.0516322 0.892146 + outer loop + vertex 1.03813 1.8275 2.60317 + vertex 1.03856 1.83126 2.60274 + vertex 1.03537 1.82817 2.60452 + endloop + endfacet + facet normal 0.455544 0.042956 0.889176 + outer loop + vertex 1.03537 1.82817 2.60452 + vertex 1.03856 1.83126 2.60274 + vertex 1.03485 1.83354 2.60453 + endloop + endfacet + facet normal 0.465298 0.0637952 0.882852 + outer loop + vertex 1.03856 1.83126 2.60274 + vertex 1.03782 1.83677 2.60273 + vertex 1.03485 1.83354 2.60453 + endloop + endfacet + facet normal 0.446887 0.0788931 0.891105 + outer loop + vertex 1.03478 1.90842 2.60036 + vertex 1.03769 1.9087 2.59888 + vertex 1.03451 1.91246 2.60014 + endloop + endfacet + facet normal 0.242122 0.178479 0.953689 + outer loop + vertex 1.03435 1.96815 2.59341 + vertex 1.0371 1.97123 2.59213 + vertex 1.03283 1.97189 2.59309 + endloop + endfacet + facet normal 0.240477 0.163383 0.956805 + outer loop + vertex 1.0371 1.97123 2.59213 + vertex 1.03553 1.97611 2.59169 + vertex 1.03283 1.97189 2.59309 + endloop + endfacet + facet normal 0.19086 0.196683 0.961711 + outer loop + vertex 1.03283 1.97189 2.59309 + vertex 1.03553 1.97611 2.59169 + vertex 1.03134 1.97541 2.59267 + endloop + endfacet + facet normal 0.24313 0.179455 0.953249 + outer loop + vertex 1.03881 1.97876 2.59039 + vertex 1.0391 1.98331 2.58945 + vertex 1.03603 1.98031 2.5908 + endloop + endfacet + facet normal 0.240249 0.173814 0.955023 + outer loop + vertex 1.03603 1.98031 2.5908 + vertex 1.03553 1.97611 2.59169 + vertex 1.03881 1.97876 2.59039 + endloop + endfacet + facet normal 0.168768 0.18521 0.968098 + outer loop + vertex 1.03603 1.98031 2.5908 + vertex 1.03174 1.97971 2.59167 + vertex 1.03553 1.97611 2.59169 + endloop + endfacet + facet normal 0.18887 0.206306 0.960086 + outer loop + vertex 1.03174 1.97971 2.59167 + vertex 1.03134 1.97541 2.59267 + vertex 1.03553 1.97611 2.59169 + endloop + endfacet + facet normal 0.210128 0.213548 0.954067 + outer loop + vertex 1.0345 1.98315 2.59051 + vertex 1.03603 1.98031 2.5908 + vertex 1.0391 1.98331 2.58945 + endloop + endfacet + facet normal 0.211491 0.196592 0.957404 + outer loop + vertex 1.0345 1.98315 2.59051 + vertex 1.0391 1.98331 2.58945 + vertex 1.03489 1.98751 2.58952 + endloop + endfacet + facet normal 0.16762 0.191902 0.966994 + outer loop + vertex 1.03603 1.98031 2.5908 + vertex 1.0345 1.98315 2.59051 + vertex 1.03174 1.97971 2.59167 + endloop + endfacet + facet normal 0.11735 0.23937 0.963811 + outer loop + vertex 1.03282 2.0367 2.57837 + vertex 1.03699 2.04002 2.57704 + vertex 1.0313 2.0415 2.57737 + endloop + endfacet + facet normal 0.122175 0.252832 0.959765 + outer loop + vertex 1.03556 2.04469 2.57604 + vertex 1.03955 2.04358 2.57582 + vertex 1.03978 2.04773 2.5747 + endloop + endfacet + facet normal 0.118476 0.243984 0.962515 + outer loop + vertex 1.03699 2.04002 2.57704 + vertex 1.03556 2.04469 2.57604 + vertex 1.0313 2.0415 2.57737 + endloop + endfacet + facet normal 0.119974 0.244384 0.962228 + outer loop + vertex 1.03955 2.04358 2.57582 + vertex 1.03556 2.04469 2.57604 + vertex 1.03699 2.04002 2.57704 + endloop + endfacet + facet normal 0.146496 0.42213 0.89462 + outer loop + vertex 1.03385 2.11778 2.55541 + vertex 1.03621 2.11549 2.55611 + vertex 1.03817 2.11844 2.55439 + endloop + endfacet + facet normal 0.119569 0.521053 0.845108 + outer loop + vertex 1.03385 2.11778 2.55541 + vertex 1.03817 2.11844 2.55439 + vertex 1.03313 2.12101 2.55352 + endloop + endfacet + facet normal 0.133392 0.542829 0.829182 + outer loop + vertex 1.03313 2.12101 2.55352 + vertex 1.03817 2.11844 2.55439 + vertex 1.03772 2.12166 2.55235 + endloop + endfacet + facet normal 0.108605 0.389286 0.914692 + outer loop + vertex 1.03621 2.11549 2.55611 + vertex 1.03385 2.11778 2.55541 + vertex 1.03189 2.1146 2.557 + endloop + endfacet + facet normal 0.0967798 0.817684 0.567474 + outer loop + vertex 1.03506 2.12375 2.55075 + vertex 1.04033 2.12367 2.54996 + vertex 1.03684 2.12564 2.54771 + endloop + endfacet + facet normal 0.0877292 0.820964 0.5642 + outer loop + vertex 1.03189 2.12576 2.54831 + vertex 1.03506 2.12375 2.55075 + vertex 1.03684 2.12564 2.54771 + endloop + endfacet + facet normal 0.0890693 0.676797 0.730762 + outer loop + vertex 1.03772 2.12166 2.55235 + vertex 1.03506 2.12375 2.55075 + vertex 1.03313 2.12101 2.55352 + endloop + endfacet + facet normal 0.116402 0.695249 0.709281 + outer loop + vertex 1.04033 2.12367 2.54996 + vertex 1.03506 2.12375 2.55075 + vertex 1.03772 2.12166 2.55235 + endloop + endfacet + facet normal -0 0.451255 0.892395 + outer loop + vertex 1.04 2.13349 2.535 + vertex 1.035 2.13349 2.535 + vertex 1.03853 2.13 2.53677 + endloop + endfacet + facet normal 0.114389 0.537873 0.835229 + outer loop + vertex 1.03853 2.13 2.53677 + vertex 1.035 2.13349 2.535 + vertex 1.03382 2.13057 2.53705 + endloop + endfacet + facet normal 0.133085 0.876271 0.463074 + outer loop + vertex 1.03853 2.13 2.53677 + vertex 1.03382 2.13057 2.53705 + vertex 1.03739 2.12864 2.53967 + endloop + endfacet + facet normal 0.202192 0.899876 0.386448 + outer loop + vertex 1.03739 2.12864 2.53967 + vertex 1.03382 2.13057 2.53705 + vertex 1.03353 2.12905 2.54073 + endloop + endfacet + facet normal 0.177164 0.943946 0.278531 + outer loop + vertex 1.03739 2.12864 2.53967 + vertex 1.03353 2.12905 2.54073 + vertex 1.03838 2.12722 2.54384 + endloop + endfacet + facet normal 0.0864605 0.912 0.400974 + outer loop + vertex 1.03838 2.12722 2.54384 + vertex 1.03353 2.12905 2.54073 + vertex 1.03317 2.12736 2.54465 + endloop + endfacet + facet normal 0.0724134 0.904559 0.420155 + outer loop + vertex 1.03684 2.12564 2.54771 + vertex 1.03317 2.12736 2.54465 + vertex 1.03189 2.12576 2.54831 + endloop + endfacet + facet normal 0.0871162 0.909916 0.405541 + outer loop + vertex 1.03838 2.12722 2.54384 + vertex 1.03317 2.12736 2.54465 + vertex 1.03684 2.12564 2.54771 + endloop + endfacet + facet normal 0.0315925 -0.98118 -0.190493 + outer loop + vertex 1.045 0.892745 2.535 + vertex 1.043 0.892414 2.53638 + vertex 1.04 0.892584 2.535 + endloop + endfacet + facet normal 0.0216025 -0.985345 -0.169199 + outer loop + vertex 1.043 0.892414 2.53638 + vertex 1.0381 0.892243 2.53675 + vertex 1.04 0.892584 2.535 + endloop + endfacet + facet normal 0.045715 -0.987682 0.14965 + outer loop + vertex 1.043 0.892414 2.53638 + vertex 1.04163 0.892893 2.53996 + vertex 1.0381 0.892243 2.53675 + endloop + endfacet + facet normal 0.0514758 -0.988319 0.143442 + outer loop + vertex 1.04163 0.892893 2.53996 + vertex 1.03662 0.892704 2.54045 + vertex 1.0381 0.892243 2.53675 + endloop + endfacet + facet normal 0.0635689 -0.958471 0.278016 + outer loop + vertex 1.04163 0.892893 2.53996 + vertex 1.03974 0.893897 2.54385 + vertex 1.03662 0.892704 2.54045 + endloop + endfacet + facet normal 0.0878232 -0.953434 0.28853 + outer loop + vertex 1.04471 0.894194 2.54332 + vertex 1.03974 0.893897 2.54385 + vertex 1.04163 0.892893 2.53996 + endloop + endfacet + facet normal 0.101835 -0.882693 0.458784 + outer loop + vertex 1.03974 0.893897 2.54385 + vertex 1.04471 0.894194 2.54332 + vertex 1.04197 0.895897 2.54721 + endloop + endfacet + facet normal 0.134457 -0.887795 0.44016 + outer loop + vertex 1.03753 0.895028 2.54681 + vertex 1.03974 0.893897 2.54385 + vertex 1.04197 0.895897 2.54721 + endloop + endfacet + facet normal 0.115939 -0.782766 0.611421 + outer loop + vertex 1.04135 0.89809 2.55013 + vertex 1.04197 0.895897 2.54721 + vertex 1.04513 0.898051 2.54937 + endloop + endfacet + facet normal 0.120053 -0.781949 0.611672 + outer loop + vertex 1.04135 0.89809 2.55013 + vertex 1.03731 0.897219 2.54981 + vertex 1.04197 0.895897 2.54721 + endloop + endfacet + facet normal 0.10357 -0.799806 0.591256 + outer loop + vertex 1.03731 0.897219 2.54981 + vertex 1.03753 0.895028 2.54681 + vertex 1.04197 0.895897 2.54721 + endloop + endfacet + facet normal 0.0865303 -0.671885 0.735584 + outer loop + vertex 1.04135 0.89809 2.55013 + vertex 1.03976 0.900084 2.55214 + vertex 1.03731 0.897219 2.54981 + endloop + endfacet + facet normal 0.139426 -0.67784 0.721868 + outer loop + vertex 1.04513 0.898051 2.54937 + vertex 1.04332 0.899966 2.55151 + vertex 1.04135 0.89809 2.55013 + endloop + endfacet + facet normal 0.108885 -0.661001 0.742443 + outer loop + vertex 1.04332 0.899966 2.55151 + vertex 1.03976 0.900084 2.55214 + vertex 1.04135 0.89809 2.55013 + endloop + endfacet + facet normal 0.126607 -0.553854 0.822932 + outer loop + vertex 1.04332 0.899966 2.55151 + vertex 1.04406 0.903483 2.55377 + vertex 1.03976 0.900084 2.55214 + endloop + endfacet + facet normal 0.137406 -0.563506 0.814605 + outer loop + vertex 1.04406 0.903483 2.55377 + vertex 1.03832 0.902834 2.55429 + vertex 1.03976 0.900084 2.55214 + endloop + endfacet + facet normal 0.131216 -0.456375 0.880059 + outer loop + vertex 1.03832 0.902834 2.55429 + vertex 1.04406 0.903483 2.55377 + vertex 1.04135 0.906428 2.5557 + endloop + endfacet + facet normal 0.143796 -0.464526 0.873807 + outer loop + vertex 1.03661 0.905642 2.55606 + vertex 1.03832 0.902834 2.55429 + vertex 1.04135 0.906428 2.5557 + endloop + endfacet + facet normal 0.13068 -0.362786 0.922664 + outer loop + vertex 1.04135 0.906428 2.5557 + vertex 1.03987 0.909681 2.55719 + vertex 1.03661 0.905642 2.55606 + endloop + endfacet + facet normal 0.130799 -0.362734 0.922668 + outer loop + vertex 1.04452 0.910143 2.55671 + vertex 1.03987 0.909681 2.55719 + vertex 1.04135 0.906428 2.5557 + endloop + endfacet + facet normal 0.117466 -0.254192 0.959994 + outer loop + vertex 1.04434 0.980047 2.57645 + vertex 1.03908 0.978952 2.57681 + vertex 1.04126 0.976238 2.57582 + endloop + endfacet + facet normal 0.116115 -0.247046 0.962022 + outer loop + vertex 1.04434 0.980047 2.57645 + vertex 1.04387 0.983862 2.57749 + vertex 1.03908 0.978952 2.57681 + endloop + endfacet + facet normal 0.122477 -0.25294 0.959698 + outer loop + vertex 1.03908 0.978952 2.57681 + vertex 1.04387 0.983862 2.57749 + vertex 1.03868 0.983592 2.57808 + endloop + endfacet + facet normal 0.122362 -0.247704 0.961078 + outer loop + vertex 1.04387 0.983862 2.57749 + vertex 1.0436 0.988434 2.5787 + vertex 1.03868 0.983592 2.57808 + endloop + endfacet + facet normal 0.20574 -0.204898 0.956916 + outer loop + vertex 1.03867 1.02349 2.58792 + vertex 1.04348 1.02857 2.58797 + vertex 1.03864 1.02842 2.58898 + endloop + endfacet + facet normal 0.205921 -0.185843 0.96076 + outer loop + vertex 1.04348 1.02857 2.58797 + vertex 1.04362 1.03356 2.58891 + vertex 1.03864 1.02842 2.58898 + endloop + endfacet + facet normal 0.244419 -0.22335 0.943596 + outer loop + vertex 1.03864 1.02842 2.58898 + vertex 1.04362 1.03356 2.58891 + vertex 1.03903 1.03349 2.59008 + endloop + endfacet + facet normal 0.233308 -0.232526 0.944192 + outer loop + vertex 1.0403 1.03742 2.59073 + vertex 1.03755 1.0355 2.59094 + vertex 1.03903 1.03349 2.59008 + endloop + endfacet + facet normal 0.306352 -0.251726 0.918032 + outer loop + vertex 1.0403 1.03742 2.59073 + vertex 1.03903 1.03349 2.59008 + vertex 1.04385 1.03867 2.58989 + endloop + endfacet + facet normal 0.245556 -0.19401 0.94977 + outer loop + vertex 1.04385 1.03867 2.58989 + vertex 1.03903 1.03349 2.59008 + vertex 1.04362 1.03356 2.58891 + endloop + endfacet + facet normal 0.202485 -0.186412 0.96138 + outer loop + vertex 1.0403 1.03742 2.59073 + vertex 1.03839 1.03914 2.59147 + vertex 1.03755 1.0355 2.59094 + endloop + endfacet + facet normal 0.295249 -0.211027 0.931824 + outer loop + vertex 1.04385 1.03867 2.58989 + vertex 1.04197 1.04034 2.59087 + vertex 1.0403 1.03742 2.59073 + endloop + endfacet + facet normal 0.218494 -0.168524 0.961176 + outer loop + vertex 1.04197 1.04034 2.59087 + vertex 1.03839 1.03914 2.59147 + vertex 1.0403 1.03742 2.59073 + endloop + endfacet + facet normal 0.212456 -0.148186 0.965869 + outer loop + vertex 1.04197 1.04034 2.59087 + vertex 1.04199 1.0435 2.59135 + vertex 1.03839 1.03914 2.59147 + endloop + endfacet + facet normal 0.227086 -0.160433 0.960569 + outer loop + vertex 1.04199 1.0435 2.59135 + vertex 1.03813 1.04354 2.59227 + vertex 1.03839 1.03914 2.59147 + endloop + endfacet + facet normal 0.228464 -0.129916 0.964845 + outer loop + vertex 1.04199 1.0435 2.59135 + vertex 1.04245 1.048 2.59184 + vertex 1.03813 1.04354 2.59227 + endloop + endfacet + facet normal 0.478568 -0.0826472 0.874152 + outer loop + vertex 1.042 1.1734 2.60187 + vertex 1.04244 1.17816 2.60208 + vertex 1.03901 1.17475 2.60364 + endloop + endfacet + facet normal 0.459407 -0.057773 0.886345 + outer loop + vertex 1.03901 1.17475 2.60364 + vertex 1.04244 1.17816 2.60208 + vertex 1.03929 1.17989 2.60383 + endloop + endfacet + facet normal 0.444612 -0.0896606 0.891225 + outer loop + vertex 1.04244 1.17816 2.60208 + vertex 1.04345 1.18373 2.60214 + vertex 1.03929 1.17989 2.60383 + endloop + endfacet + facet normal 0.419407 -0.0558228 0.90608 + outer loop + vertex 1.03929 1.17989 2.60383 + vertex 1.04345 1.18373 2.60214 + vertex 1.03952 1.18501 2.60404 + endloop + endfacet + facet normal 0.412314 -0.0797743 0.907542 + outer loop + vertex 1.04345 1.18373 2.60214 + vertex 1.04333 1.18878 2.60264 + vertex 1.03952 1.18501 2.60404 + endloop + endfacet + facet normal 0.391611 -0.0548159 0.918497 + outer loop + vertex 1.03952 1.18501 2.60404 + vertex 1.04333 1.18878 2.60264 + vertex 1.03961 1.18997 2.6043 + endloop + endfacet + facet normal 0.382103 -0.0866795 0.920046 + outer loop + vertex 1.04333 1.18878 2.60264 + vertex 1.04365 1.19364 2.60297 + vertex 1.03961 1.18997 2.6043 + endloop + endfacet + facet normal 0.364543 -0.0641233 0.928976 + outer loop + vertex 1.03961 1.18997 2.6043 + vertex 1.04365 1.19364 2.60297 + vertex 1.03979 1.19486 2.60456 + endloop + endfacet + facet normal 0.3569 -0.0893614 0.929858 + outer loop + vertex 1.04365 1.19364 2.60297 + vertex 1.0439 1.19857 2.60334 + vertex 1.03979 1.19486 2.60456 + endloop + endfacet + facet normal 0.345183 -0.0744772 0.935576 + outer loop + vertex 1.03979 1.19486 2.60456 + vertex 1.0439 1.19857 2.60334 + vertex 1.04 1.19962 2.60487 + endloop + endfacet + facet normal 0.340713 -0.0912659 0.935727 + outer loop + vertex 1.0439 1.19857 2.60334 + vertex 1.04392 1.20346 2.60381 + vertex 1.04 1.19962 2.60487 + endloop + endfacet + facet normal 0.336071 -0.0859262 0.937909 + outer loop + vertex 1.04 1.19962 2.60487 + vertex 1.04392 1.20346 2.60381 + vertex 1.04011 1.20403 2.60523 + endloop + endfacet + facet normal 0.39612 -0.0828386 0.914454 + outer loop + vertex 1.03967 1.20727 2.60572 + vertex 1.03752 1.20496 2.60643 + vertex 1.04011 1.20403 2.60523 + endloop + endfacet + facet normal 0.34017 -0.0937897 0.935675 + outer loop + vertex 1.03967 1.20727 2.60572 + vertex 1.04011 1.20403 2.60523 + vertex 1.04352 1.20863 2.60445 + endloop + endfacet + facet normal 0.33542 -0.0899326 0.937766 + outer loop + vertex 1.04352 1.20863 2.60445 + vertex 1.04011 1.20403 2.60523 + vertex 1.04392 1.20346 2.60381 + endloop + endfacet + facet normal 0.407326 -0.0951353 0.908314 + outer loop + vertex 1.03967 1.20727 2.60572 + vertex 1.03718 1.20834 2.60694 + vertex 1.03752 1.20496 2.60643 + endloop + endfacet + facet normal 0.183015 0.0941436 0.978592 + outer loop + vertex 1.04418 1.75797 2.60902 + vertex 1.04359 1.76287 2.60866 + vertex 1.03952 1.75876 2.60982 + endloop + endfacet + facet normal 0.175516 0.101742 0.979205 + outer loop + vertex 1.03952 1.75876 2.60982 + vertex 1.04359 1.76287 2.60866 + vertex 1.03853 1.76425 2.60942 + endloop + endfacet + facet normal 0.178312 0.112958 0.977469 + outer loop + vertex 1.04359 1.76287 2.60866 + vertex 1.04326 1.76768 2.60817 + vertex 1.03853 1.76425 2.60942 + endloop + endfacet + facet normal 0.170157 0.124229 0.977555 + outer loop + vertex 1.03853 1.76425 2.60942 + vertex 1.04326 1.76768 2.60817 + vertex 1.0397 1.76897 2.60862 + endloop + endfacet + facet normal 0.34924 0.0990449 0.931784 + outer loop + vertex 1.03783 1.8238 2.60368 + vertex 1.04116 1.8271 2.60208 + vertex 1.03813 1.8275 2.60317 + endloop + endfacet + facet normal 0.28305 0.0893254 0.954936 + outer loop + vertex 1.04439 1.82927 2.60083 + vertex 1.04561 1.83355 2.60007 + vertex 1.04207 1.83116 2.60134 + endloop + endfacet + facet normal 0.295604 0.106242 0.949384 + outer loop + vertex 1.04207 1.83116 2.60134 + vertex 1.04116 1.8271 2.60208 + vertex 1.04439 1.82927 2.60083 + endloop + endfacet + facet normal 0.37068 0.0851349 0.924851 + outer loop + vertex 1.04207 1.83116 2.60134 + vertex 1.03856 1.83126 2.60274 + vertex 1.04116 1.8271 2.60208 + endloop + endfacet + facet normal 0.34653 0.0682944 0.935549 + outer loop + vertex 1.03856 1.83126 2.60274 + vertex 1.03813 1.8275 2.60317 + vertex 1.04116 1.8271 2.60208 + endloop + endfacet + facet normal 0.307886 0.103685 0.945757 + outer loop + vertex 1.04561 1.83355 2.60007 + vertex 1.04475 1.83881 2.59977 + vertex 1.04147 1.83522 2.60123 + endloop + endfacet + facet normal 0.295898 0.0691013 0.952717 + outer loop + vertex 1.04207 1.83116 2.60134 + vertex 1.04561 1.83355 2.60007 + vertex 1.04147 1.83522 2.60123 + endloop + endfacet + facet normal 0.370721 0.0793716 0.925346 + outer loop + vertex 1.04147 1.83522 2.60123 + vertex 1.03856 1.83126 2.60274 + vertex 1.04207 1.83116 2.60134 + endloop + endfacet + facet normal 0.398786 0.054951 0.915396 + outer loop + vertex 1.03782 1.83677 2.60273 + vertex 1.03856 1.83126 2.60274 + vertex 1.04147 1.83522 2.60123 + endloop + endfacet + facet normal 0.346717 0.103018 0.932295 + outer loop + vertex 1.04475 1.83881 2.59977 + vertex 1.04417 1.84371 2.59944 + vertex 1.04093 1.84027 2.60103 + endloop + endfacet + facet normal 0.337461 0.0736716 0.938452 + outer loop + vertex 1.04147 1.83522 2.60123 + vertex 1.04475 1.83881 2.59977 + vertex 1.04093 1.84027 2.60103 + endloop + endfacet + facet normal 0.407088 0.0799386 0.909884 + outer loop + vertex 1.04093 1.84027 2.60103 + vertex 1.03782 1.83677 2.60273 + vertex 1.04147 1.83522 2.60123 + endloop + endfacet + facet normal 0.431463 0.0537833 0.900526 + outer loop + vertex 1.03746 1.84194 2.60259 + vertex 1.03782 1.83677 2.60273 + vertex 1.04093 1.84027 2.60103 + endloop + endfacet + facet normal 0.382512 0.0921311 0.919346 + outer loop + vertex 1.04417 1.84371 2.59944 + vertex 1.04399 1.84855 2.59903 + vertex 1.04065 1.84534 2.60074 + endloop + endfacet + facet normal 0.375162 0.0724372 0.924125 + outer loop + vertex 1.04093 1.84027 2.60103 + vertex 1.04417 1.84371 2.59944 + vertex 1.04065 1.84534 2.60074 + endloop + endfacet + facet normal 0.43903 0.074319 0.895393 + outer loop + vertex 1.04065 1.84534 2.60074 + vertex 1.03746 1.84194 2.60259 + vertex 1.04093 1.84027 2.60103 + endloop + endfacet + facet normal 0.461774 0.0476839 0.885715 + outer loop + vertex 1.03734 1.84702 2.60238 + vertex 1.03746 1.84194 2.60259 + vertex 1.04065 1.84534 2.60074 + endloop + endfacet + facet normal 0.412205 0.085036 0.907114 + outer loop + vertex 1.04399 1.84855 2.59903 + vertex 1.04378 1.85354 2.59866 + vertex 1.04052 1.85037 2.60044 + endloop + endfacet + facet normal 0.404234 0.0658124 0.912285 + outer loop + vertex 1.04065 1.84534 2.60074 + vertex 1.04399 1.84855 2.59903 + vertex 1.04052 1.85037 2.60044 + endloop + endfacet + facet normal 0.4685 0.0655986 0.881025 + outer loop + vertex 1.04052 1.85037 2.60044 + vertex 1.03734 1.84702 2.60238 + vertex 1.04065 1.84534 2.60074 + endloop + endfacet + facet normal 0.492036 0.0483251 0.869233 + outer loop + vertex 1.04194 1.902 2.59697 + vertex 1.04152 1.90692 2.59694 + vertex 1.03853 1.90367 2.59881 + endloop + endfacet + facet normal 0.487164 0.05458 0.871603 + outer loop + vertex 1.042 1.91605 2.59609 + vertex 1.04095 1.91198 2.59694 + vertex 1.04401 1.9139 2.59511 + endloop + endfacet + facet normal 0.278195 0.141671 0.950019 + outer loop + vertex 1.0391 1.98331 2.58945 + vertex 1.04285 1.97889 2.58902 + vertex 1.04347 1.98334 2.58817 + endloop + endfacet + facet normal 0.278733 0.1295 0.951597 + outer loop + vertex 1.04347 1.98334 2.58817 + vertex 1.04226 1.98635 2.58812 + vertex 1.0391 1.98331 2.58945 + endloop + endfacet + facet normal 0.249337 0.161498 0.954856 + outer loop + vertex 1.0391 1.98331 2.58945 + vertex 1.04226 1.98635 2.58812 + vertex 1.03949 1.98793 2.58857 + endloop + endfacet + facet normal 0.250674 0.164072 0.954067 + outer loop + vertex 1.04226 1.98635 2.58812 + vertex 1.04282 1.99063 2.58723 + vertex 1.03949 1.98793 2.58857 + endloop + endfacet + facet normal 0.232213 0.187108 0.954499 + outer loop + vertex 1.03949 1.98793 2.58857 + vertex 1.04282 1.99063 2.58723 + vertex 1.03804 1.99174 2.58818 + endloop + endfacet + facet normal 0.226677 0.157663 0.961124 + outer loop + vertex 1.04282 1.99063 2.58723 + vertex 1.04081 1.99609 2.58681 + vertex 1.03804 1.99174 2.58818 + endloop + endfacet + facet normal 0.125412 0.247633 0.960703 + outer loop + vertex 1.04557 2.03969 2.57605 + vertex 1.04406 2.04435 2.57504 + vertex 1.04148 2.04092 2.57626 + endloop + endfacet + facet normal 0.122637 0.249659 0.960537 + outer loop + vertex 1.03955 2.04358 2.57582 + vertex 1.04148 2.04092 2.57626 + vertex 1.04406 2.04435 2.57504 + endloop + endfacet + facet normal 0.121961 0.252849 0.959788 + outer loop + vertex 1.03955 2.04358 2.57582 + vertex 1.04406 2.04435 2.57504 + vertex 1.03978 2.04773 2.5747 + endloop + endfacet + facet normal 0.117448 0.246154 0.962088 + outer loop + vertex 1.04148 2.04092 2.57626 + vertex 1.03955 2.04358 2.57582 + vertex 1.03699 2.04002 2.57704 + endloop + endfacet + facet normal 0.152483 0.505357 0.849331 + outer loop + vertex 1.04394 2.11694 2.55425 + vertex 1.04193 2.12067 2.55239 + vertex 1.03817 2.11844 2.55439 + endloop + endfacet + facet normal 0.120957 0.54246 0.831328 + outer loop + vertex 1.03817 2.11844 2.55439 + vertex 1.04193 2.12067 2.55239 + vertex 1.03772 2.12166 2.55235 + endloop + endfacet + facet normal 0.1187 0.883643 0.452864 + outer loop + vertex 1.04494 2.12483 2.54763 + vertex 1.04286 2.1265 2.54491 + vertex 1.04086 2.12567 2.54706 + endloop + endfacet + facet normal 0.087496 0.812058 0.576981 + outer loop + vertex 1.04086 2.12567 2.54706 + vertex 1.03684 2.12564 2.54771 + vertex 1.04033 2.12367 2.54996 + endloop + endfacet + facet normal 0.0867789 0.812172 0.576929 + outer loop + vertex 1.04086 2.12567 2.54706 + vertex 1.04033 2.12367 2.54996 + vertex 1.04494 2.12483 2.54763 + endloop + endfacet + facet normal 0.132704 0.7567 0.640153 + outer loop + vertex 1.04494 2.12483 2.54763 + vertex 1.04033 2.12367 2.54996 + vertex 1.04464 2.12253 2.55042 + endloop + endfacet + facet normal 0.152066 0.669789 0.726815 + outer loop + vertex 1.04193 2.12067 2.55239 + vertex 1.04033 2.12367 2.54996 + vertex 1.03772 2.12166 2.55235 + endloop + endfacet + facet normal 0.0944627 0.656603 0.748298 + outer loop + vertex 1.04464 2.12253 2.55042 + vertex 1.04033 2.12367 2.54996 + vertex 1.04193 2.12067 2.55239 + endloop + endfacet + facet normal 0.045563 0.464749 0.884269 + outer loop + vertex 1.045 2.133 2.535 + vertex 1.04 2.13349 2.535 + vertex 1.0436 2.12969 2.53681 + endloop + endfacet + facet normal 0.0188942 0.444814 0.895424 + outer loop + vertex 1.0436 2.12969 2.53681 + vertex 1.04 2.13349 2.535 + vertex 1.03853 2.13 2.53677 + endloop + endfacet + facet normal 0.0515108 0.910437 0.410428 + outer loop + vertex 1.0436 2.12969 2.53681 + vertex 1.03853 2.13 2.53677 + vertex 1.04233 2.12792 2.54089 + endloop + endfacet + facet normal 0.0234808 0.90164 0.43185 + outer loop + vertex 1.04233 2.12792 2.54089 + vertex 1.03853 2.13 2.53677 + vertex 1.03739 2.12864 2.53967 + endloop + endfacet + facet normal 0.0502848 0.91467 0.40106 + outer loop + vertex 1.04286 2.1265 2.54491 + vertex 1.03838 2.12722 2.54384 + vertex 1.04086 2.12567 2.54706 + endloop + endfacet + facet normal 0.0734991 0.943487 0.323156 + outer loop + vertex 1.04286 2.1265 2.54491 + vertex 1.04233 2.12792 2.54089 + vertex 1.03838 2.12722 2.54384 + endloop + endfacet + facet normal 0.0611434 0.949417 0.308006 + outer loop + vertex 1.04233 2.12792 2.54089 + vertex 1.03739 2.12864 2.53967 + vertex 1.03838 2.12722 2.54384 + endloop + endfacet + facet normal 0.0574237 0.916303 0.396347 + outer loop + vertex 1.04086 2.12567 2.54706 + vertex 1.03838 2.12722 2.54384 + vertex 1.03684 2.12564 2.54771 + endloop + endfacet + facet normal 0.101038 -0.872518 -0.478021 + outer loop + vertex 1.05 0.893324 2.535 + vertex 1.04716 0.892595 2.53573 + vertex 1.045 0.892745 2.535 + endloop + endfacet + facet normal 0.00788534 -0.974711 -0.223328 + outer loop + vertex 1.04716 0.892595 2.53573 + vertex 1.043 0.892414 2.53638 + vertex 1.045 0.892745 2.535 + endloop + endfacet + facet normal 0.0660715 -0.986629 0.148988 + outer loop + vertex 1.04716 0.892595 2.53573 + vertex 1.04708 0.893111 2.53919 + vertex 1.043 0.892414 2.53638 + endloop + endfacet + facet normal 0.0614939 -0.985928 0.155448 + outer loop + vertex 1.04708 0.893111 2.53919 + vertex 1.04163 0.892893 2.53996 + vertex 1.043 0.892414 2.53638 + endloop + endfacet + facet normal 0.0800167 -0.952091 0.295163 + outer loop + vertex 1.04708 0.893111 2.53919 + vertex 1.04471 0.894194 2.54332 + vertex 1.04163 0.892893 2.53996 + endloop + endfacet + facet normal 0.0735431 -0.953628 0.291865 + outer loop + vertex 1.04908 0.89429 2.54253 + vertex 1.04471 0.894194 2.54332 + vertex 1.04708 0.893111 2.53919 + endloop + endfacet + facet normal 0.102808 -0.880383 0.462986 + outer loop + vertex 1.04471 0.894194 2.54332 + vertex 1.04908 0.89429 2.54253 + vertex 1.04808 0.895992 2.54599 + endloop + endfacet + facet normal 0.105227 -0.881352 0.460593 + outer loop + vertex 1.04197 0.895897 2.54721 + vertex 1.04471 0.894194 2.54332 + vertex 1.04808 0.895992 2.54599 + endloop + endfacet + facet normal 0.131039 -0.791046 0.597557 + outer loop + vertex 1.04808 0.895992 2.54599 + vertex 1.04513 0.898051 2.54937 + vertex 1.04197 0.895897 2.54721 + endloop + endfacet + facet normal 0.132052 -0.790473 0.598093 + outer loop + vertex 1.0498 0.898486 2.54891 + vertex 1.04513 0.898051 2.54937 + vertex 1.04808 0.895992 2.54599 + endloop + endfacet + facet normal 0.133733 -0.672149 0.728238 + outer loop + vertex 1.04513 0.898051 2.54937 + vertex 1.0498 0.898486 2.54891 + vertex 1.0472 0.900758 2.55148 + endloop + endfacet + facet normal 0.143392 -0.675589 0.7232 + outer loop + vertex 1.04332 0.899966 2.55151 + vertex 1.04513 0.898051 2.54937 + vertex 1.0472 0.900758 2.55148 + endloop + endfacet + facet normal 0.119198 -0.553261 0.824435 + outer loop + vertex 1.0472 0.900758 2.55148 + vertex 1.04406 0.903483 2.55377 + vertex 1.04332 0.899966 2.55151 + endloop + endfacet + facet normal 0.119006 -0.553418 0.824358 + outer loop + vertex 1.04988 0.904066 2.55332 + vertex 1.04406 0.903483 2.55377 + vertex 1.0472 0.900758 2.55148 + endloop + endfacet + facet normal 0.134952 -0.453533 0.880963 + outer loop + vertex 1.04517 0.907333 2.55558 + vertex 1.04135 0.906428 2.5557 + vertex 1.04406 0.903483 2.55377 + endloop + endfacet + facet normal 0.11634 -0.450182 0.885325 + outer loop + vertex 1.04517 0.907333 2.55558 + vertex 1.04406 0.903483 2.55377 + vertex 1.04851 0.907143 2.55504 + endloop + endfacet + facet normal 0.11323 -0.447088 0.887295 + outer loop + vertex 1.04851 0.907143 2.55504 + vertex 1.04406 0.903483 2.55377 + vertex 1.04988 0.904066 2.55332 + endloop + endfacet + facet normal 0.111644 -0.348534 0.930623 + outer loop + vertex 1.04517 0.907333 2.55558 + vertex 1.04452 0.910143 2.55671 + vertex 1.04135 0.906428 2.5557 + endloop + endfacet + facet normal 0.19116 -0.236025 0.952759 + outer loop + vertex 1.04497 1.0179 2.58568 + vertex 1.04136 1.01619 2.58598 + vertex 1.04349 1.01362 2.58491 + endloop + endfacet + facet normal 0.277266 -0.260702 0.924747 + outer loop + vertex 1.04497 1.0179 2.58568 + vertex 1.04349 1.01362 2.58491 + vertex 1.04868 1.01881 2.58482 + endloop + endfacet + facet normal 0.222042 -0.205108 0.95322 + outer loop + vertex 1.04868 1.01881 2.58482 + vertex 1.04349 1.01362 2.58491 + vertex 1.04855 1.01356 2.58372 + endloop + endfacet + facet normal 0.180203 -0.211608 0.960598 + outer loop + vertex 1.04497 1.0179 2.58568 + vertex 1.04393 1.02018 2.58638 + vertex 1.04136 1.01619 2.58598 + endloop + endfacet + facet normal 0.273827 -0.240655 0.931184 + outer loop + vertex 1.04868 1.01881 2.58482 + vertex 1.04697 1.02075 2.58583 + vertex 1.04497 1.0179 2.58568 + endloop + endfacet + facet normal 0.210001 -0.197155 0.957616 + outer loop + vertex 1.04697 1.02075 2.58583 + vertex 1.04393 1.02018 2.58638 + vertex 1.04497 1.0179 2.58568 + endloop + endfacet + facet normal 0.204782 -0.161661 0.965365 + outer loop + vertex 1.04697 1.02075 2.58583 + vertex 1.04728 1.02387 2.58628 + vertex 1.04393 1.02018 2.58638 + endloop + endfacet + facet normal 0.211287 -0.167617 0.962944 + outer loop + vertex 1.04728 1.02387 2.58628 + vertex 1.04349 1.02388 2.58712 + vertex 1.04393 1.02018 2.58638 + endloop + endfacet + facet normal 0.212269 -0.138155 0.967396 + outer loop + vertex 1.04728 1.02387 2.58628 + vertex 1.04827 1.02872 2.58676 + vertex 1.04349 1.02388 2.58712 + endloop + endfacet + facet normal 0.246904 -0.173375 0.953404 + outer loop + vertex 1.04349 1.02388 2.58712 + vertex 1.04827 1.02872 2.58676 + vertex 1.04348 1.02857 2.58797 + endloop + endfacet + facet normal 0.247124 -0.156461 0.956269 + outer loop + vertex 1.04827 1.02872 2.58676 + vertex 1.04803 1.03357 2.58762 + vertex 1.04348 1.02857 2.58797 + endloop + endfacet + facet normal 0.276934 -0.184508 0.943008 + outer loop + vertex 1.04348 1.02857 2.58797 + vertex 1.04803 1.03357 2.58762 + vertex 1.04362 1.03356 2.58891 + endloop + endfacet + facet normal 0.278371 -0.152965 0.948215 + outer loop + vertex 1.04803 1.03357 2.58762 + vertex 1.04819 1.03859 2.58838 + vertex 1.04362 1.03356 2.58891 + endloop + endfacet + facet normal 0.320179 -0.193071 0.927474 + outer loop + vertex 1.04362 1.03356 2.58891 + vertex 1.04819 1.03859 2.58838 + vertex 1.04385 1.03867 2.58989 + endloop + endfacet + facet normal 0.318556 -0.183645 0.929944 + outer loop + vertex 1.04452 1.04279 2.59047 + vertex 1.04197 1.04034 2.59087 + vertex 1.04385 1.03867 2.58989 + endloop + endfacet + facet normal 0.374084 -0.189553 0.907816 + outer loop + vertex 1.04452 1.04279 2.59047 + vertex 1.04385 1.03867 2.58989 + vertex 1.04827 1.04414 2.58921 + endloop + endfacet + facet normal 0.323648 -0.145439 0.934933 + outer loop + vertex 1.04827 1.04414 2.58921 + vertex 1.04385 1.03867 2.58989 + vertex 1.04819 1.03859 2.58838 + endloop + endfacet + facet normal 0.284961 -0.145841 0.947379 + outer loop + vertex 1.04452 1.04279 2.59047 + vertex 1.04199 1.0435 2.59135 + vertex 1.04197 1.04034 2.59087 + endloop + endfacet + facet normal 0.455893 -0.0897565 0.885497 + outer loop + vertex 1.04774 1.14799 2.59738 + vertex 1.04871 1.15353 2.59744 + vertex 1.04457 1.14992 2.59921 + endloop + endfacet + facet normal 0.433797 -0.0577478 0.899158 + outer loop + vertex 1.04457 1.14992 2.59921 + vertex 1.04871 1.15353 2.59744 + vertex 1.04482 1.15503 2.59942 + endloop + endfacet + facet normal 0.422705 -0.0900181 0.901785 + outer loop + vertex 1.04871 1.15353 2.59744 + vertex 1.0487 1.15873 2.59797 + vertex 1.04482 1.15503 2.59942 + endloop + endfacet + facet normal 0.396106 -0.0563404 0.916475 + outer loop + vertex 1.04482 1.15503 2.59942 + vertex 1.0487 1.15873 2.59797 + vertex 1.04489 1.15992 2.59969 + endloop + endfacet + facet normal 0.387276 -0.0865155 0.917896 + outer loop + vertex 1.0487 1.15873 2.59797 + vertex 1.04885 1.16364 2.59837 + vertex 1.04489 1.15992 2.59969 + endloop + endfacet + facet normal 0.361496 -0.054486 0.93078 + outer loop + vertex 1.04489 1.15992 2.59969 + vertex 1.04885 1.16364 2.59837 + vertex 1.04494 1.16463 2.59995 + endloop + endfacet + facet normal 0.356051 -0.0769365 0.931294 + outer loop + vertex 1.04885 1.16364 2.59837 + vertex 1.04875 1.16847 2.59881 + vertex 1.04494 1.16463 2.59995 + endloop + endfacet + facet normal 0.335788 -0.0541792 0.940378 + outer loop + vertex 1.04494 1.16463 2.59995 + vertex 1.04875 1.16847 2.59881 + vertex 1.04491 1.16902 2.60021 + endloop + endfacet + facet normal 0.40808 -0.0540634 0.911344 + outer loop + vertex 1.04441 1.17231 2.60063 + vertex 1.04231 1.16997 2.60143 + vertex 1.04491 1.16902 2.60021 + endloop + endfacet + facet normal 0.319259 -0.0716038 0.944959 + outer loop + vertex 1.04441 1.17231 2.60063 + vertex 1.04491 1.16902 2.60021 + vertex 1.0483 1.17367 2.59942 + endloop + endfacet + facet normal 0.331677 -0.0815265 0.939864 + outer loop + vertex 1.0483 1.17367 2.59942 + vertex 1.04491 1.16902 2.60021 + vertex 1.04875 1.16847 2.59881 + endloop + endfacet + facet normal 0.43022 -0.0779412 0.899353 + outer loop + vertex 1.04441 1.17231 2.60063 + vertex 1.042 1.1734 2.60187 + vertex 1.04231 1.16997 2.60143 + endloop + endfacet + facet normal 0.309123 -0.0956146 0.946204 + outer loop + vertex 1.0483 1.17367 2.59942 + vertex 1.04927 1.17947 2.59969 + vertex 1.0453 1.17627 2.60066 + endloop + endfacet + facet normal 0.321672 -0.0797989 0.943483 + outer loop + vertex 1.04441 1.17231 2.60063 + vertex 1.0483 1.17367 2.59942 + vertex 1.0453 1.17627 2.60066 + endloop + endfacet + facet normal 0.420617 -0.101641 0.901527 + outer loop + vertex 1.0453 1.17627 2.60066 + vertex 1.042 1.1734 2.60187 + vertex 1.04441 1.17231 2.60063 + endloop + endfacet + facet normal 0.403299 -0.0773538 0.911793 + outer loop + vertex 1.04244 1.17816 2.60208 + vertex 1.042 1.1734 2.60187 + vertex 1.0453 1.17627 2.60066 + endloop + endfacet + facet normal 0.291878 -0.100015 0.951212 + outer loop + vertex 1.04927 1.17947 2.59969 + vertex 1.04973 1.18431 2.60005 + vertex 1.04612 1.18115 2.60083 + endloop + endfacet + facet normal 0.300312 -0.0834931 0.95018 + outer loop + vertex 1.0453 1.17627 2.60066 + vertex 1.04927 1.17947 2.59969 + vertex 1.04612 1.18115 2.60083 + endloop + endfacet + facet normal 0.391456 -0.0976247 0.915004 + outer loop + vertex 1.04612 1.18115 2.60083 + vertex 1.04244 1.17816 2.60208 + vertex 1.0453 1.17627 2.60066 + endloop + endfacet + facet normal 0.378017 -0.0779105 0.922514 + outer loop + vertex 1.04345 1.18373 2.60214 + vertex 1.04244 1.17816 2.60208 + vertex 1.04612 1.18115 2.60083 + endloop + endfacet + facet normal 0.27468 -0.0786348 0.958315 + outer loop + vertex 1.04973 1.18431 2.60005 + vertex 1.04706 1.18503 2.60088 + vertex 1.04612 1.18115 2.60083 + endloop + endfacet + facet normal 0.36022 -0.0988962 0.92761 + outer loop + vertex 1.04706 1.18503 2.60088 + vertex 1.04345 1.18373 2.60214 + vertex 1.04612 1.18115 2.60083 + endloop + endfacet + facet normal 0.361087 -0.101952 0.926942 + outer loop + vertex 1.04706 1.18503 2.60088 + vertex 1.04681 1.18818 2.60132 + vertex 1.04345 1.18373 2.60214 + endloop + endfacet + facet normal 0.340092 -0.0843138 0.936605 + outer loop + vertex 1.04681 1.18818 2.60132 + vertex 1.04333 1.18878 2.60264 + vertex 1.04345 1.18373 2.60214 + endloop + endfacet + facet normal 0.335367 -0.109461 0.935707 + outer loop + vertex 1.04681 1.18818 2.60132 + vertex 1.04732 1.19255 2.60165 + vertex 1.04333 1.18878 2.60264 + endloop + endfacet + facet normal 0.313788 -0.0840427 0.945766 + outer loop + vertex 1.04333 1.18878 2.60264 + vertex 1.04732 1.19255 2.60165 + vertex 1.04365 1.19364 2.60297 + endloop + endfacet + facet normal 0.306759 -0.107666 0.945678 + outer loop + vertex 1.04732 1.19255 2.60165 + vertex 1.04844 1.1979 2.6019 + vertex 1.04365 1.19364 2.60297 + endloop + endfacet + facet normal 0.29058 -0.0876446 0.952828 + outer loop + vertex 1.04365 1.19364 2.60297 + vertex 1.04844 1.1979 2.6019 + vertex 1.0439 1.19857 2.60334 + endloop + endfacet + facet normal 0.289198 -0.0961008 0.952433 + outer loop + vertex 1.04844 1.1979 2.6019 + vertex 1.04832 1.20301 2.60245 + vertex 1.0439 1.19857 2.60334 + endloop + endfacet + facet normal 0.286197 -0.0928646 0.95366 + outer loop + vertex 1.0439 1.19857 2.60334 + vertex 1.04832 1.20301 2.60245 + vertex 1.04392 1.20346 2.60381 + endloop + endfacet + facet normal 0.285661 -0.0972542 0.953383 + outer loop + vertex 1.04832 1.20301 2.60245 + vertex 1.04839 1.2081 2.60295 + vertex 1.04392 1.20346 2.60381 + endloop + endfacet + facet normal 0.284333 -0.0958727 0.95392 + outer loop + vertex 1.04392 1.20346 2.60381 + vertex 1.04839 1.2081 2.60295 + vertex 1.04352 1.20863 2.60445 + endloop + endfacet + facet normal 0.198508 0.120439 0.972671 + outer loop + vertex 1.04957 1.82262 2.60051 + vertex 1.04708 1.81617 2.60181 + vertex 1.0505 1.81832 2.60085 + endloop + endfacet + facet normal 0.289793 0.0976879 0.952091 + outer loop + vertex 1.04475 1.83881 2.59977 + vertex 1.04801 1.84239 2.59841 + vertex 1.04417 1.84371 2.59944 + endloop + endfacet + facet normal 0.295961 0.118988 0.94776 + outer loop + vertex 1.04801 1.84239 2.59841 + vertex 1.04713 1.84652 2.59817 + vertex 1.04417 1.84371 2.59944 + endloop + endfacet + facet normal 0.319726 0.0917486 0.943058 + outer loop + vertex 1.04417 1.84371 2.59944 + vertex 1.04713 1.84652 2.59817 + vertex 1.04399 1.84855 2.59903 + endloop + endfacet + facet normal 0.324288 0.0997914 0.94068 + outer loop + vertex 1.04713 1.84652 2.59817 + vertex 1.048 1.85119 2.59737 + vertex 1.04399 1.84855 2.59903 + endloop + endfacet + facet normal 0.333882 0.0840504 0.93886 + outer loop + vertex 1.04399 1.84855 2.59903 + vertex 1.048 1.85119 2.59737 + vertex 1.04378 1.85354 2.59866 + endloop + endfacet + facet normal 0.347058 0.111945 0.931139 + outer loop + vertex 1.048 1.85119 2.59737 + vertex 1.04689 1.85677 2.59711 + vertex 1.04378 1.85354 2.59866 + endloop + endfacet + facet normal 0.380068 0.075667 0.921858 + outer loop + vertex 1.04378 1.85354 2.59866 + vertex 1.04689 1.85677 2.59711 + vertex 1.04316 1.85848 2.59851 + endloop + endfacet + facet normal 0.385978 0.0918171 0.917927 + outer loop + vertex 1.04689 1.85677 2.59711 + vertex 1.04584 1.86219 2.59702 + vertex 1.04316 1.85848 2.59851 + endloop + endfacet + facet normal 0.42822 0.0548592 0.902008 + outer loop + vertex 1.04316 1.85848 2.59851 + vertex 1.04584 1.86219 2.59702 + vertex 1.04229 1.86265 2.59867 + endloop + endfacet + facet normal 0.428373 0.0567167 0.90182 + outer loop + vertex 1.04295 1.86759 2.59805 + vertex 1.04229 1.86265 2.59867 + vertex 1.04584 1.86219 2.59702 + endloop + endfacet + facet normal 0.531347 0.0449534 0.845961 + outer loop + vertex 1.04401 1.9139 2.59511 + vertex 1.04449 1.90989 2.59502 + vertex 1.04731 1.91345 2.59306 + endloop + endfacet + facet normal 0.531903 0.0527048 0.845164 + outer loop + vertex 1.04401 1.9139 2.59511 + vertex 1.04731 1.91345 2.59306 + vertex 1.045 1.91816 2.59422 + endloop + endfacet + facet normal 0.527854 0.0500583 0.847859 + outer loop + vertex 1.045 1.91816 2.59422 + vertex 1.04731 1.91345 2.59306 + vertex 1.04822 1.91789 2.59223 + endloop + endfacet + facet normal 0.527836 0.0495435 0.8479 + outer loop + vertex 1.04822 1.91789 2.59223 + vertex 1.04762 1.922 2.59236 + vertex 1.045 1.91816 2.59422 + endloop + endfacet + facet normal 0.221647 0.18068 0.958242 + outer loop + vertex 1.04423 2.00349 2.58465 + vertex 1.04729 2.00653 2.58337 + vertex 1.04447 2.00807 2.58373 + endloop + endfacet + facet normal 0.226964 0.191226 0.954945 + outer loop + vertex 1.04729 2.00653 2.58337 + vertex 1.04786 2.01061 2.58242 + vertex 1.04447 2.00807 2.58373 + endloop + endfacet + facet normal 0.197313 0.196383 0.960469 + outer loop + vertex 1.04786 2.01061 2.58242 + vertex 1.04625 2.01533 2.58178 + vertex 1.04299 2.01184 2.58316 + endloop + endfacet + facet normal 0.124181 0.50277 0.855454 + outer loop + vertex 1.04761 2.11708 2.55363 + vertex 1.04701 2.11981 2.55211 + vertex 1.04394 2.11694 2.55425 + endloop + endfacet + facet normal 0.130475 0.497578 0.85755 + outer loop + vertex 1.04394 2.11694 2.55425 + vertex 1.04701 2.11981 2.55211 + vertex 1.04193 2.12067 2.55239 + endloop + endfacet + facet normal 0.0659467 0.888165 0.454768 + outer loop + vertex 1.04494 2.12483 2.54763 + vertex 1.04936 2.12509 2.54648 + vertex 1.04668 2.1265 2.54413 + endloop + endfacet + facet normal 0.0976328 0.879241 0.466265 + outer loop + vertex 1.04286 2.1265 2.54491 + vertex 1.04494 2.12483 2.54763 + vertex 1.04668 2.1265 2.54413 + endloop + endfacet + facet normal 0.116752 0.772932 0.623655 + outer loop + vertex 1.04936 2.12509 2.54648 + vertex 1.04494 2.12483 2.54763 + vertex 1.04914 2.12286 2.54929 + endloop + endfacet + facet normal 0.104381 0.760834 0.640496 + outer loop + vertex 1.04914 2.12286 2.54929 + vertex 1.04494 2.12483 2.54763 + vertex 1.04464 2.12253 2.55042 + endloop + endfacet + facet normal 0.145472 0.612606 0.776886 + outer loop + vertex 1.04701 2.11981 2.55211 + vertex 1.04464 2.12253 2.55042 + vertex 1.04193 2.12067 2.55239 + endloop + endfacet + facet normal 0.148761 0.614272 0.774945 + outer loop + vertex 1.04914 2.12286 2.54929 + vertex 1.04464 2.12253 2.55042 + vertex 1.04701 2.11981 2.55211 + endloop + endfacet + facet normal 0.00546814 0.456873 0.889515 + outer loop + vertex 1.05 2.13294 2.535 + vertex 1.045 2.133 2.535 + vertex 1.04883 2.1295 2.53677 + endloop + endfacet + facet normal 0.0234976 0.47236 0.881093 + outer loop + vertex 1.04883 2.1295 2.53677 + vertex 1.045 2.133 2.535 + vertex 1.0436 2.12969 2.53681 + endloop + endfacet + facet normal 0.0355423 0.897742 0.439085 + outer loop + vertex 1.04883 2.1295 2.53677 + vertex 1.0436 2.12969 2.53681 + vertex 1.04784 2.12779 2.54034 + endloop + endfacet + facet normal 0.0621557 0.908632 0.412945 + outer loop + vertex 1.04784 2.12779 2.54034 + vertex 1.0436 2.12969 2.53681 + vertex 1.04233 2.12792 2.54089 + endloop + endfacet + facet normal 0.0683598 0.943624 0.323883 + outer loop + vertex 1.04668 2.1265 2.54413 + vertex 1.04233 2.12792 2.54089 + vertex 1.04286 2.1265 2.54491 + endloop + endfacet + facet normal 0.055505 0.939087 0.339167 + outer loop + vertex 1.04784 2.12779 2.54034 + vertex 1.04233 2.12792 2.54089 + vertex 1.04668 2.1265 2.54413 + endloop + endfacet + facet normal 0.0186963 -0.974137 -0.225183 + outer loop + vertex 1.055 0.89342 2.535 + vertex 1.05182 0.893015 2.53649 + vertex 1.05 0.893324 2.535 + endloop + endfacet + facet normal 0.142332 -0.919966 -0.365245 + outer loop + vertex 1.05182 0.893015 2.53649 + vertex 1.04716 0.892595 2.53573 + vertex 1.05 0.893324 2.535 + endloop + endfacet + facet normal 0.0861733 -0.976188 0.199074 + outer loop + vertex 1.0515 0.893722 2.5401 + vertex 1.05182 0.893015 2.53649 + vertex 1.05545 0.893803 2.53878 + endloop + endfacet + facet normal 0.0937729 -0.975381 0.199595 + outer loop + vertex 1.0515 0.893722 2.5401 + vertex 1.04708 0.893111 2.53919 + vertex 1.05182 0.893015 2.53649 + endloop + endfacet + facet normal 0.0647689 -0.986719 0.148968 + outer loop + vertex 1.04708 0.893111 2.53919 + vertex 1.04716 0.892595 2.53573 + vertex 1.05182 0.893015 2.53649 + endloop + endfacet + facet normal 0.0715285 -0.953432 0.293004 + outer loop + vertex 1.0515 0.893722 2.5401 + vertex 1.04908 0.89429 2.54253 + vertex 1.04708 0.893111 2.53919 + endloop + endfacet + facet normal 0.138803 -0.922326 0.360622 + outer loop + vertex 1.05545 0.893803 2.53878 + vertex 1.05335 0.895122 2.54296 + vertex 1.0515 0.893722 2.5401 + endloop + endfacet + facet normal 0.143821 -0.922739 0.357586 + outer loop + vertex 1.04908 0.89429 2.54253 + vertex 1.0515 0.893722 2.5401 + vertex 1.05335 0.895122 2.54296 + endloop + endfacet + facet normal 0.123626 -0.875712 0.466738 + outer loop + vertex 1.04908 0.89429 2.54253 + vertex 1.05335 0.895122 2.54296 + vertex 1.04808 0.895992 2.54599 + endloop + endfacet + facet normal 0.138829 -0.861156 0.489016 + outer loop + vertex 1.04808 0.895992 2.54599 + vertex 1.05335 0.895122 2.54296 + vertex 1.05259 0.896938 2.54638 + endloop + endfacet + facet normal 0.113385 -0.787144 0.606257 + outer loop + vertex 1.05259 0.896938 2.54638 + vertex 1.0498 0.898486 2.54891 + vertex 1.04808 0.895992 2.54599 + endloop + endfacet + facet normal 0.135338 -0.77188 0.621196 + outer loop + vertex 1.05455 0.898809 2.54828 + vertex 1.0498 0.898486 2.54891 + vertex 1.05259 0.896938 2.54638 + endloop + endfacet + facet normal 0.142294 -0.67736 0.721759 + outer loop + vertex 1.0498 0.898486 2.54891 + vertex 1.05455 0.898809 2.54828 + vertex 1.05221 0.901202 2.55098 + endloop + endfacet + facet normal 0.132372 -0.673048 0.727657 + outer loop + vertex 1.0472 0.900758 2.55148 + vertex 1.0498 0.898486 2.54891 + vertex 1.05221 0.901202 2.55098 + endloop + endfacet + facet normal 0.131389 -0.559969 0.818029 + outer loop + vertex 1.05221 0.901202 2.55098 + vertex 1.04988 0.904066 2.55332 + vertex 1.0472 0.900758 2.55148 + endloop + endfacet + facet normal 0.127397 -0.562379 0.817007 + outer loop + vertex 1.05517 0.904576 2.55284 + vertex 1.04988 0.904066 2.55332 + vertex 1.05221 0.901202 2.55098 + endloop + endfacet + facet normal 0.122349 -0.444685 0.887291 + outer loop + vertex 1.05517 0.904576 2.55284 + vertex 1.0532 0.907758 2.55471 + vertex 1.04988 0.904066 2.55332 + endloop + endfacet + facet normal 0.121181 -0.443853 0.887868 + outer loop + vertex 1.04988 0.904066 2.55332 + vertex 1.0532 0.907758 2.55471 + vertex 1.04851 0.907143 2.55504 + endloop + endfacet + facet normal 0.123645 -0.280914 0.951735 + outer loop + vertex 1.05413 0.9303 2.5613 + vertex 1.04892 0.929249 2.56166 + vertex 1.05103 0.926517 2.56058 + endloop + endfacet + facet normal 0.201923 -0.249861 0.946994 + outer loop + vertex 1.04766 0.999969 2.58114 + vertex 1.04829 0.997343 2.58031 + vertex 1.05092 1.00126 2.58078 + endloop + endfacet + facet normal 0.188094 -0.211552 0.959097 + outer loop + vertex 1.05092 1.00126 2.58078 + vertex 1.04877 1.00373 2.58175 + vertex 1.04766 0.999969 2.58114 + endloop + endfacet + facet normal 0.202296 -0.199118 0.958868 + outer loop + vertex 1.05258 1.00458 2.58112 + vertex 1.04877 1.00373 2.58175 + vertex 1.05092 1.00126 2.58078 + endloop + endfacet + facet normal 0.195768 -0.163809 0.966872 + outer loop + vertex 1.05258 1.00458 2.58112 + vertex 1.05269 1.00801 2.58168 + vertex 1.04877 1.00373 2.58175 + endloop + endfacet + facet normal 0.218397 -0.184678 0.958226 + outer loop + vertex 1.04877 1.00373 2.58175 + vertex 1.05269 1.00801 2.58168 + vertex 1.04854 1.00848 2.58272 + endloop + endfacet + facet normal 0.223777 -0.148476 0.963265 + outer loop + vertex 1.05269 1.00801 2.58168 + vertex 1.0535 1.01328 2.58231 + vertex 1.04854 1.00848 2.58272 + endloop + endfacet + facet normal 0.260445 -0.187701 0.947067 + outer loop + vertex 1.04854 1.00848 2.58272 + vertex 1.0535 1.01328 2.58231 + vertex 1.04855 1.01356 2.58372 + endloop + endfacet + facet normal 0.409993 -0.092704 0.907365 + outer loop + vertex 1.04966 1.05806 2.59026 + vertex 1.04692 1.05856 2.59155 + vertex 1.04736 1.05546 2.59103 + endloop + endfacet + facet normal 0.413185 -0.0754183 0.907519 + outer loop + vertex 1.05033 1.0618 2.59027 + vertex 1.04692 1.05856 2.59155 + vertex 1.04966 1.05806 2.59026 + endloop + endfacet + facet normal 0.453397 -0.0546754 0.88963 + outer loop + vertex 1.04977 1.12002 2.59452 + vertex 1.05379 1.12361 2.59269 + vertex 1.05001 1.12502 2.5947 + endloop + endfacet + facet normal 0.443764 -0.0840463 0.892194 + outer loop + vertex 1.05379 1.12361 2.59269 + vertex 1.05364 1.12888 2.59326 + vertex 1.05001 1.12502 2.5947 + endloop + endfacet + facet normal 0.41723 -0.053509 0.907224 + outer loop + vertex 1.05001 1.12502 2.5947 + vertex 1.05364 1.12888 2.59326 + vertex 1.04997 1.12952 2.59499 + endloop + endfacet + facet normal 0.458533 -0.0421778 0.887676 + outer loop + vertex 1.04937 1.13271 2.59545 + vertex 1.04737 1.13037 2.59637 + vertex 1.04997 1.12952 2.59499 + endloop + endfacet + facet normal 0.392627 -0.0588012 0.917816 + outer loop + vertex 1.04937 1.13271 2.59545 + vertex 1.04997 1.12952 2.59499 + vertex 1.05322 1.13411 2.59389 + endloop + endfacet + facet normal 0.413419 -0.076013 0.907363 + outer loop + vertex 1.05322 1.13411 2.59389 + vertex 1.04997 1.12952 2.59499 + vertex 1.05364 1.12888 2.59326 + endloop + endfacet + facet normal 0.471246 -0.0560061 0.880222 + outer loop + vertex 1.04937 1.13271 2.59545 + vertex 1.04691 1.13364 2.59683 + vertex 1.04737 1.13037 2.59637 + endloop + endfacet + facet normal 0.37871 -0.0786424 0.922168 + outer loop + vertex 1.05322 1.13411 2.59389 + vertex 1.05396 1.13974 2.59407 + vertex 1.05002 1.13649 2.59541 + endloop + endfacet + facet normal 0.392326 -0.0577578 0.918011 + outer loop + vertex 1.04937 1.13271 2.59545 + vertex 1.05322 1.13411 2.59389 + vertex 1.05002 1.13649 2.59541 + endloop + endfacet + facet normal 0.466437 -0.0708874 0.881709 + outer loop + vertex 1.05002 1.13649 2.59541 + vertex 1.04691 1.13364 2.59683 + vertex 1.04937 1.13271 2.59545 + endloop + endfacet + facet normal 0.455978 -0.0562142 0.888214 + outer loop + vertex 1.04703 1.13812 2.59705 + vertex 1.04691 1.13364 2.59683 + vertex 1.05002 1.13649 2.59541 + endloop + endfacet + facet normal 0.358962 -0.0849229 0.929481 + outer loop + vertex 1.05396 1.13974 2.59407 + vertex 1.05429 1.14476 2.5944 + vertex 1.05042 1.14128 2.59558 + endloop + endfacet + facet normal 0.367737 -0.0630378 0.927791 + outer loop + vertex 1.05002 1.13649 2.59541 + vertex 1.05396 1.13974 2.59407 + vertex 1.05042 1.14128 2.59558 + endloop + endfacet + facet normal 0.450298 -0.0686635 0.890234 + outer loop + vertex 1.05042 1.14128 2.59558 + vertex 1.04703 1.13812 2.59705 + vertex 1.05002 1.13649 2.59541 + endloop + endfacet + facet normal 0.441866 -0.0572223 0.895254 + outer loop + vertex 1.0473 1.14297 2.59723 + vertex 1.04703 1.13812 2.59705 + vertex 1.05042 1.14128 2.59558 + endloop + endfacet + facet normal 0.349239 -0.0725314 0.934222 + outer loop + vertex 1.05042 1.14128 2.59558 + vertex 1.05429 1.14476 2.5944 + vertex 1.0508 1.14617 2.59581 + endloop + endfacet + facet normal 0.432575 -0.0772563 0.898282 + outer loop + vertex 1.0508 1.14617 2.59581 + vertex 1.0473 1.14297 2.59723 + vertex 1.05042 1.14128 2.59558 + endloop + endfacet + facet normal 0.423881 -0.0654847 0.903348 + outer loop + vertex 1.04774 1.14799 2.59738 + vertex 1.0473 1.14297 2.59723 + vertex 1.0508 1.14617 2.59581 + endloop + endfacet + facet normal 0.241703 -0.0978351 0.965406 + outer loop + vertex 1.04832 1.20301 2.60245 + vertex 1.05342 1.20803 2.60168 + vertex 1.04839 1.2081 2.60295 + endloop + endfacet + facet normal 0.241645 -0.0993699 0.965263 + outer loop + vertex 1.05342 1.20803 2.60168 + vertex 1.05327 1.21315 2.60224 + vertex 1.04839 1.2081 2.60295 + endloop + endfacet + facet normal 0.232382 -0.0899773 0.968454 + outer loop + vertex 1.04839 1.2081 2.60295 + vertex 1.05327 1.21315 2.60224 + vertex 1.04847 1.21329 2.60341 + endloop + endfacet + facet normal 0.232136 -0.0948403 0.968049 + outer loop + vertex 1.05327 1.21315 2.60224 + vertex 1.05326 1.21804 2.60273 + vertex 1.04847 1.21329 2.60341 + endloop + endfacet + facet normal 0.21735 -0.0792493 0.972871 + outer loop + vertex 1.04847 1.21329 2.60341 + vertex 1.05326 1.21804 2.60273 + vertex 1.04868 1.21846 2.60378 + endloop + endfacet + facet normal 0.161921 0.113121 0.980299 + outer loop + vertex 1.0505 1.81832 2.60085 + vertex 1.05468 1.8187 2.60012 + vertex 1.04957 1.82262 2.60051 + endloop + endfacet + facet normal 0.320286 0.0968314 0.942359 + outer loop + vertex 1.05041 1.86832 2.59466 + vertex 1.05334 1.87225 2.59326 + vertex 1.04952 1.87351 2.59443 + endloop + endfacet + facet normal 0.325059 0.114672 0.938716 + outer loop + vertex 1.05334 1.87225 2.59326 + vertex 1.05226 1.87633 2.59314 + vertex 1.04952 1.87351 2.59443 + endloop + endfacet + facet normal 0.354126 0.0832324 0.931486 + outer loop + vertex 1.04952 1.87351 2.59443 + vertex 1.05226 1.87633 2.59314 + vertex 1.04908 1.87843 2.59416 + endloop + endfacet + facet normal 0.3588 0.0915431 0.928914 + outer loop + vertex 1.05226 1.87633 2.59314 + vertex 1.05286 1.88122 2.59242 + vertex 1.04908 1.87843 2.59416 + endloop + endfacet + facet normal 0.371836 0.071769 0.92552 + outer loop + vertex 1.04908 1.87843 2.59416 + vertex 1.05286 1.88122 2.59242 + vertex 1.04862 1.88351 2.59395 + endloop + endfacet + facet normal 0.386733 0.105599 0.916126 + outer loop + vertex 1.05286 1.88122 2.59242 + vertex 1.05139 1.88739 2.59233 + vertex 1.04862 1.88351 2.59395 + endloop + endfacet + facet normal 0.315661 0.152288 0.936572 + outer loop + vertex 1.05438 2.00897 2.58072 + vertex 1.05507 2.01315 2.57981 + vertex 1.05188 2.01086 2.58126 + endloop + endfacet + facet normal 0.312192 0.147146 0.938554 + outer loop + vertex 1.05188 2.01086 2.58126 + vertex 1.05111 2.00677 2.58215 + vertex 1.05438 2.00897 2.58072 + endloop + endfacet + facet normal 0.264506 0.158831 0.951215 + outer loop + vertex 1.05188 2.01086 2.58126 + vertex 1.04786 2.01061 2.58242 + vertex 1.05111 2.00677 2.58215 + endloop + endfacet + facet normal 0.29035 0.167778 0.942097 + outer loop + vertex 1.05507 2.01315 2.57981 + vertex 1.05348 2.01845 2.57936 + vertex 1.05069 2.0145 2.58092 + endloop + endfacet + facet normal 0.294108 0.183322 0.938026 + outer loop + vertex 1.05188 2.01086 2.58126 + vertex 1.05507 2.01315 2.57981 + vertex 1.05069 2.0145 2.58092 + endloop + endfacet + facet normal 0.262892 0.174183 0.948972 + outer loop + vertex 1.05069 2.0145 2.58092 + vertex 1.04786 2.01061 2.58242 + vertex 1.05188 2.01086 2.58126 + endloop + endfacet + facet normal 0.223599 0.204353 0.953018 + outer loop + vertex 1.04625 2.01533 2.58178 + vertex 1.04786 2.01061 2.58242 + vertex 1.05069 2.0145 2.58092 + endloop + endfacet + facet normal 0.251356 0.1974 0.947551 + outer loop + vertex 1.04914 2.01818 2.58056 + vertex 1.05069 2.0145 2.58092 + vertex 1.05348 2.01845 2.57936 + endloop + endfacet + facet normal 0.250111 0.208254 0.945555 + outer loop + vertex 1.04914 2.01818 2.58056 + vertex 1.05348 2.01845 2.57936 + vertex 1.04951 2.02249 2.57952 + endloop + endfacet + facet normal 0.220949 0.185566 0.957469 + outer loop + vertex 1.05069 2.0145 2.58092 + vertex 1.04914 2.01818 2.58056 + vertex 1.04625 2.01533 2.58178 + endloop + endfacet + facet normal 0.149936 0.234849 0.960398 + outer loop + vertex 1.05438 2.04314 2.57386 + vertex 1.05279 2.04669 2.57324 + vertex 1.04986 2.04262 2.57469 + endloop + endfacet + facet normal 0.173536 0.380555 0.90833 + outer loop + vertex 1.04831 2.11396 2.55481 + vertex 1.05132 2.11712 2.55291 + vertex 1.04761 2.11708 2.55363 + endloop + endfacet + facet normal 0.151405 0.584674 0.797015 + outer loop + vertex 1.0548 2.11943 2.55109 + vertex 1.05321 2.1219 2.54958 + vertex 1.05102 2.1204 2.55109 + endloop + endfacet + facet normal 0.126925 0.488411 0.863334 + outer loop + vertex 1.05102 2.1204 2.55109 + vertex 1.05132 2.11712 2.55291 + vertex 1.0548 2.11943 2.55109 + endloop + endfacet + facet normal 0.14709 0.488484 0.860086 + outer loop + vertex 1.05102 2.1204 2.55109 + vertex 1.04701 2.11981 2.55211 + vertex 1.05132 2.11712 2.55291 + endloop + endfacet + facet normal 0.160515 0.5062 0.847347 + outer loop + vertex 1.04701 2.11981 2.55211 + vertex 1.04761 2.11708 2.55363 + vertex 1.05132 2.11712 2.55291 + endloop + endfacet + facet normal 0.128153 0.868543 0.478758 + outer loop + vertex 1.04936 2.12509 2.54648 + vertex 1.05393 2.12414 2.54699 + vertex 1.05148 2.12629 2.54374 + endloop + endfacet + facet normal 0.0743881 0.891405 0.44706 + outer loop + vertex 1.04668 2.1265 2.54413 + vertex 1.04936 2.12509 2.54648 + vertex 1.05148 2.12629 2.54374 + endloop + endfacet + facet normal 0.0954362 0.635493 0.766186 + outer loop + vertex 1.05321 2.1219 2.54958 + vertex 1.04914 2.12286 2.54929 + vertex 1.05102 2.1204 2.55109 + endloop + endfacet + facet normal 0.125325 0.733017 0.668566 + outer loop + vertex 1.05321 2.1219 2.54958 + vertex 1.05393 2.12414 2.54699 + vertex 1.04914 2.12286 2.54929 + endloop + endfacet + facet normal 0.0924658 0.775886 0.62406 + outer loop + vertex 1.05393 2.12414 2.54699 + vertex 1.04936 2.12509 2.54648 + vertex 1.04914 2.12286 2.54929 + endloop + endfacet + facet normal 0.100483 0.637596 0.76379 + outer loop + vertex 1.05102 2.1204 2.55109 + vertex 1.04914 2.12286 2.54929 + vertex 1.04701 2.11981 2.55211 + endloop + endfacet + facet normal 0.00813171 0.451148 0.892412 + outer loop + vertex 1.055 2.13285 2.535 + vertex 1.05 2.13294 2.535 + vertex 1.05399 2.12935 2.53678 + endloop + endfacet + facet normal 0.0124577 0.454967 0.890421 + outer loop + vertex 1.05399 2.12935 2.53678 + vertex 1.05 2.13294 2.535 + vertex 1.04883 2.1295 2.53677 + endloop + endfacet + facet normal 0.0258153 0.888688 0.457785 + outer loop + vertex 1.05399 2.12935 2.53678 + vertex 1.04883 2.1295 2.53677 + vertex 1.05307 2.12761 2.54022 + endloop + endfacet + facet normal 0.0432522 0.89662 0.440684 + outer loop + vertex 1.05307 2.12761 2.54022 + vertex 1.04883 2.1295 2.53677 + vertex 1.04784 2.12779 2.54034 + endloop + endfacet + facet normal 0.0680447 0.937106 0.342347 + outer loop + vertex 1.05148 2.12629 2.54374 + vertex 1.04784 2.12779 2.54034 + vertex 1.04668 2.1265 2.54413 + endloop + endfacet + facet normal 0.042621 0.929556 0.366208 + outer loop + vertex 1.05307 2.12761 2.54022 + vertex 1.04784 2.12779 2.54034 + vertex 1.05148 2.12629 2.54374 + endloop + endfacet + facet normal 0.0125762 -0.149344 -0.988705 + outer loop + vertex 1.06 0.893841 2.535 + vertex 1.05761 0.893147 2.53507 + vertex 1.055 0.89342 2.535 + endloop + endfacet + facet normal -0.0824513 -0.902936 -0.421792 + outer loop + vertex 1.05761 0.893147 2.53507 + vertex 1.05182 0.893015 2.53649 + vertex 1.055 0.89342 2.535 + endloop + endfacet + facet normal 0.0749984 -0.97354 0.215861 + outer loop + vertex 1.05761 0.893147 2.53507 + vertex 1.05545 0.893803 2.53878 + vertex 1.05182 0.893015 2.53649 + endloop + endfacet + facet normal 0.0851815 -0.971453 0.221413 + outer loop + vertex 1.05934 0.893864 2.53755 + vertex 1.05545 0.893803 2.53878 + vertex 1.05761 0.893147 2.53507 + endloop + endfacet + facet normal 0.124794 -0.928761 0.34904 + outer loop + vertex 1.05545 0.893803 2.53878 + vertex 1.05934 0.893864 2.53755 + vertex 1.05857 0.895016 2.54089 + endloop + endfacet + facet normal 0.121313 -0.927544 0.353476 + outer loop + vertex 1.05335 0.895122 2.54296 + vertex 1.05545 0.893803 2.53878 + vertex 1.05857 0.895016 2.54089 + endloop + endfacet + facet normal 0.165935 -0.870658 0.463056 + outer loop + vertex 1.05857 0.895016 2.54089 + vertex 1.05747 0.897022 2.54506 + vertex 1.05335 0.895122 2.54296 + endloop + endfacet + facet normal 0.147078 -0.859307 0.489857 + outer loop + vertex 1.05747 0.897022 2.54506 + vertex 1.05259 0.896938 2.54638 + vertex 1.05335 0.895122 2.54296 + endloop + endfacet + facet normal 0.174067 -0.785089 0.59442 + outer loop + vertex 1.05747 0.897022 2.54506 + vertex 1.05455 0.898809 2.54828 + vertex 1.05259 0.896938 2.54638 + endloop + endfacet + facet normal 0.130149 -0.81176 0.569304 + outer loop + vertex 1.05817 0.898872 2.54754 + vertex 1.05455 0.898809 2.54828 + vertex 1.05747 0.897022 2.54506 + endloop + endfacet + facet normal 0.15486 -0.696813 0.700336 + outer loop + vertex 1.05455 0.898809 2.54828 + vertex 1.05817 0.898872 2.54754 + vertex 1.05785 0.901254 2.54998 + endloop + endfacet + facet normal 0.134315 -0.681968 0.718943 + outer loop + vertex 1.05221 0.901202 2.55098 + vertex 1.05455 0.898809 2.54828 + vertex 1.05785 0.901254 2.54998 + endloop + endfacet + facet normal 0.148635 -0.574404 0.804965 + outer loop + vertex 1.05785 0.901254 2.54998 + vertex 1.05517 0.904576 2.55284 + vertex 1.05221 0.901202 2.55098 + endloop + endfacet + facet normal 0.111888 -0.595747 0.79534 + outer loop + vertex 1.06034 0.905014 2.55244 + vertex 1.05517 0.904576 2.55284 + vertex 1.05785 0.901254 2.54998 + endloop + endfacet + facet normal 0.105939 -0.435934 0.893722 + outer loop + vertex 1.06034 0.905014 2.55244 + vertex 1.05869 0.908841 2.55451 + vertex 1.05517 0.904576 2.55284 + endloop + endfacet + facet normal 0.120737 -0.445558 0.887074 + outer loop + vertex 1.05517 0.904576 2.55284 + vertex 1.05869 0.908841 2.55451 + vertex 1.0532 0.907758 2.55471 + endloop + endfacet + facet normal 0.101176 -0.337066 0.936029 + outer loop + vertex 1.0532 0.907758 2.55471 + vertex 1.05869 0.908841 2.55451 + vertex 1.05616 0.911584 2.55577 + endloop + endfacet + facet normal 0.1115 -0.344024 0.932317 + outer loop + vertex 1.05153 0.910775 2.55602 + vertex 1.0532 0.907758 2.55471 + vertex 1.05616 0.911584 2.55577 + endloop + endfacet + facet normal 0.101706 -0.281073 0.954282 + outer loop + vertex 1.05616 0.911584 2.55577 + vertex 1.05478 0.914857 2.55688 + vertex 1.05153 0.910775 2.55602 + endloop + endfacet + facet normal 0.10087 -0.281419 0.954269 + outer loop + vertex 1.05936 0.915241 2.55651 + vertex 1.05478 0.914857 2.55688 + vertex 1.05616 0.911584 2.55577 + endloop + endfacet + facet normal 0.0998247 -0.264118 0.959311 + outer loop + vertex 1.05936 0.915241 2.55651 + vertex 1.05901 0.919129 2.55762 + vertex 1.05478 0.914857 2.55688 + endloop + endfacet + facet normal 0.104675 -0.268609 0.957545 + outer loop + vertex 1.05478 0.914857 2.55688 + vertex 1.05901 0.919129 2.55762 + vertex 1.05384 0.918938 2.55813 + endloop + endfacet + facet normal 0.10468 -0.269221 0.957373 + outer loop + vertex 1.05901 0.919129 2.55762 + vertex 1.05853 0.923538 2.55891 + vertex 1.05384 0.918938 2.55813 + endloop + endfacet + facet normal 0.120218 -0.278334 0.952931 + outer loop + vertex 1.05479 0.927688 2.56045 + vertex 1.05413 0.9303 2.5613 + vertex 1.05103 0.926517 2.56058 + endloop + endfacet + facet normal 0.105121 -0.282331 0.95354 + outer loop + vertex 1.05749 0.93018 2.56089 + vertex 1.05413 0.9303 2.5613 + vertex 1.05479 0.927688 2.56045 + endloop + endfacet + facet normal 0.0955059 -0.266287 0.959151 + outer loop + vertex 1.05529 0.946763 2.56589 + vertex 1.05381 0.943213 2.56505 + vertex 1.05833 0.946619 2.56554 + endloop + endfacet + facet normal 0.0949324 -0.273625 0.95714 + outer loop + vertex 1.05833 0.946619 2.56554 + vertex 1.05767 0.949214 2.56635 + vertex 1.05529 0.946763 2.56589 + endloop + endfacet + facet normal 0.165784 -0.24769 0.95455 + outer loop + vertex 1.05483 0.982835 2.57558 + vertex 1.05121 0.981299 2.57581 + vertex 1.05336 0.978591 2.57473 + endloop + endfacet + facet normal 0.195694 -0.25648 0.946532 + outer loop + vertex 1.05483 0.982835 2.57558 + vertex 1.05336 0.978591 2.57473 + vertex 1.05862 0.983621 2.57501 + endloop + endfacet + facet normal 0.164755 -0.224858 0.960362 + outer loop + vertex 1.05862 0.983621 2.57501 + vertex 1.05336 0.978591 2.57473 + vertex 1.05855 0.9785 2.57382 + endloop + endfacet + facet normal 0.158364 -0.229303 0.960386 + outer loop + vertex 1.05483 0.982835 2.57558 + vertex 1.05388 0.985151 2.57629 + vertex 1.05121 0.981299 2.57581 + endloop + endfacet + facet normal 0.191855 -0.232985 0.953368 + outer loop + vertex 1.05862 0.983621 2.57501 + vertex 1.0569 0.98555 2.57583 + vertex 1.05483 0.982835 2.57558 + endloop + endfacet + facet normal 0.176135 -0.221555 0.959109 + outer loop + vertex 1.0569 0.98555 2.57583 + vertex 1.05388 0.985151 2.57629 + vertex 1.05483 0.982835 2.57558 + endloop + endfacet + facet normal 0.173753 -0.196742 0.964937 + outer loop + vertex 1.0569 0.98555 2.57583 + vertex 1.05737 0.988596 2.57636 + vertex 1.05388 0.985151 2.57629 + endloop + endfacet + facet normal 0.183801 -0.206836 0.960956 + outer loop + vertex 1.05737 0.988596 2.57636 + vertex 1.05357 0.988809 2.57714 + vertex 1.05388 0.985151 2.57629 + endloop + endfacet + facet normal 0.18566 -0.187063 0.964644 + outer loop + vertex 1.05737 0.988596 2.57636 + vertex 1.05876 0.993437 2.57704 + vertex 1.05357 0.988809 2.57714 + endloop + endfacet + facet normal 0.211006 -0.215745 0.953379 + outer loop + vertex 1.05357 0.988809 2.57714 + vertex 1.05876 0.993437 2.57704 + vertex 1.05357 0.993514 2.5782 + endloop + endfacet + facet normal 0.212179 -0.196261 0.95732 + outer loop + vertex 1.05876 0.993437 2.57704 + vertex 1.05859 0.998667 2.57815 + vertex 1.05357 0.993514 2.5782 + endloop + endfacet + facet normal 0.241866 -0.225284 0.943794 + outer loop + vertex 1.05357 0.993514 2.5782 + vertex 1.05859 0.998667 2.57815 + vertex 1.05329 0.998732 2.57952 + endloop + endfacet + facet normal 0.365875 -0.123462 0.922439 + outer loop + vertex 1.05459 1.03316 2.58518 + vertex 1.05188 1.0336 2.58631 + vertex 1.0522 1.0305 2.58577 + endloop + endfacet + facet normal 0.389291 -0.0795061 0.917677 + outer loop + vertex 1.05941 1.10984 2.58906 + vertex 1.05944 1.11475 2.58947 + vertex 1.05571 1.11133 2.59076 + endloop + endfacet + facet normal 0.458997 -0.0515172 0.886943 + outer loop + vertex 1.05249 1.11303 2.59252 + vertex 1.05231 1.10811 2.59233 + vertex 1.05571 1.11133 2.59076 + endloop + endfacet + facet normal 0.370674 -0.0880817 0.924577 + outer loop + vertex 1.05944 1.11475 2.58947 + vertex 1.05962 1.1196 2.58986 + vertex 1.05593 1.1162 2.59101 + endloop + endfacet + facet normal 0.37899 -0.0662579 0.923026 + outer loop + vertex 1.05571 1.11133 2.59076 + vertex 1.05944 1.11475 2.58947 + vertex 1.05593 1.1162 2.59101 + endloop + endfacet + facet normal 0.451812 -0.0678474 0.889529 + outer loop + vertex 1.05593 1.1162 2.59101 + vertex 1.05249 1.11303 2.59252 + vertex 1.05571 1.11133 2.59076 + endloop + endfacet + facet normal 0.446582 -0.0606662 0.892684 + outer loop + vertex 1.05287 1.11805 2.59267 + vertex 1.05249 1.11303 2.59252 + vertex 1.05593 1.1162 2.59101 + endloop + endfacet + facet normal 0.349192 -0.098952 0.931812 + outer loop + vertex 1.05962 1.1196 2.58986 + vertex 1.05992 1.12414 2.59023 + vertex 1.05643 1.12097 2.5912 + endloop + endfacet + facet normal 0.359335 -0.0738171 0.930285 + outer loop + vertex 1.05593 1.1162 2.59101 + vertex 1.05962 1.1196 2.58986 + vertex 1.05643 1.12097 2.5912 + endloop + endfacet + facet normal 0.436499 -0.0804693 0.896099 + outer loop + vertex 1.05643 1.12097 2.5912 + vertex 1.05287 1.11805 2.59267 + vertex 1.05593 1.1162 2.59101 + endloop + endfacet + facet normal 0.433034 -0.0751759 0.898237 + outer loop + vertex 1.05379 1.12361 2.59269 + vertex 1.05287 1.11805 2.59267 + vertex 1.05643 1.12097 2.5912 + endloop + endfacet + facet normal 0.333782 -0.0797156 0.939274 + outer loop + vertex 1.05992 1.12414 2.59023 + vertex 1.0573 1.12478 2.59121 + vertex 1.05643 1.12097 2.5912 + endloop + endfacet + facet normal 0.41397 -0.0980059 0.904999 + outer loop + vertex 1.0573 1.12478 2.59121 + vertex 1.05379 1.12361 2.59269 + vertex 1.05643 1.12097 2.5912 + endloop + endfacet + facet normal 0.417507 -0.11277 0.901649 + outer loop + vertex 1.0573 1.12478 2.59121 + vertex 1.05719 1.12818 2.59169 + vertex 1.05379 1.12361 2.59269 + endloop + endfacet + facet normal 0.389158 -0.0883429 0.916925 + outer loop + vertex 1.05719 1.12818 2.59169 + vertex 1.05364 1.12888 2.59326 + vertex 1.05379 1.12361 2.59269 + endloop + endfacet + facet normal 0.381815 -0.123225 0.915988 + outer loop + vertex 1.05719 1.12818 2.59169 + vertex 1.05818 1.13348 2.59199 + vertex 1.05364 1.12888 2.59326 + endloop + endfacet + facet normal 0.347639 -0.0845203 0.933811 + outer loop + vertex 1.05364 1.12888 2.59326 + vertex 1.05818 1.13348 2.59199 + vertex 1.05322 1.13411 2.59389 + endloop + endfacet + facet normal 0.358945 0.0878254 0.929218 + outer loop + vertex 1.05483 1.89886 2.58975 + vertex 1.05799 1.90217 2.58821 + vertex 1.05433 1.90368 2.58948 + endloop + endfacet + facet normal 0.368229 0.115976 0.922473 + outer loop + vertex 1.05799 1.90217 2.58821 + vertex 1.05699 1.90634 2.58809 + vertex 1.05433 1.90368 2.58948 + endloop + endfacet + facet normal 0.407974 0.0699079 0.910313 + outer loop + vertex 1.05433 1.90368 2.58948 + vertex 1.05699 1.90634 2.58809 + vertex 1.0541 1.90848 2.58922 + endloop + endfacet + facet normal 0.410578 0.0742097 0.908801 + outer loop + vertex 1.05699 1.90634 2.58809 + vertex 1.05775 1.9111 2.58736 + vertex 1.0541 1.90848 2.58922 + endloop + endfacet + facet normal 0.419839 0.0591054 0.905672 + outer loop + vertex 1.0541 1.90848 2.58922 + vertex 1.05775 1.9111 2.58736 + vertex 1.05378 1.91346 2.58904 + endloop + endfacet + facet normal 0.435844 0.0936517 0.895136 + outer loop + vertex 1.05775 1.9111 2.58736 + vertex 1.0565 1.91716 2.58733 + vertex 1.05378 1.91346 2.58904 + endloop + endfacet + facet normal 0.472124 0.0596704 0.87951 + outer loop + vertex 1.05378 1.91346 2.58904 + vertex 1.0565 1.91716 2.58733 + vertex 1.05304 1.91772 2.58915 + endloop + endfacet + facet normal 0.403031 0.0850804 0.911223 + outer loop + vertex 1.0596 1.91918 2.5857 + vertex 1.06052 1.92345 2.5849 + vertex 1.05736 1.92151 2.58648 + endloop + endfacet + facet normal 0.412804 0.0962634 0.905719 + outer loop + vertex 1.05736 1.92151 2.58648 + vertex 1.0565 1.91716 2.58733 + vertex 1.0596 1.91918 2.5857 + endloop + endfacet + facet normal 0.488319 0.0742982 0.869497 + outer loop + vertex 1.05736 1.92151 2.58648 + vertex 1.05394 1.92217 2.58834 + vertex 1.0565 1.91716 2.58733 + endloop + endfacet + facet normal 0.472579 0.06434 0.878937 + outer loop + vertex 1.05394 1.92217 2.58834 + vertex 1.05304 1.91772 2.58915 + vertex 1.0565 1.91716 2.58733 + endloop + endfacet + facet normal 0.244874 0.213084 0.94585 + outer loop + vertex 1.05468 2.03384 2.5759 + vertex 1.05624 2.03077 2.57619 + vertex 1.05923 2.03362 2.57478 + endloop + endfacet + facet normal 0.244828 0.218213 0.944692 + outer loop + vertex 1.05468 2.03384 2.5759 + vertex 1.05923 2.03362 2.57478 + vertex 1.05461 2.03845 2.57486 + endloop + endfacet + facet normal 0.213142 0.198069 0.956734 + outer loop + vertex 1.05624 2.03077 2.57619 + vertex 1.05468 2.03384 2.5759 + vertex 1.05163 2.03071 2.57723 + endloop + endfacet + facet normal 0.138476 0.36576 0.92035 + outer loop + vertex 1.05407 2.11236 2.55439 + vertex 1.0567 2.11592 2.55258 + vertex 1.05132 2.11712 2.55291 + endloop + endfacet + facet normal 0.153852 0.569162 0.807703 + outer loop + vertex 1.0548 2.11943 2.55109 + vertex 1.05955 2.11858 2.55079 + vertex 1.05736 2.12168 2.54902 + endloop + endfacet + facet normal 0.139679 0.580317 0.802323 + outer loop + vertex 1.05321 2.1219 2.54958 + vertex 1.0548 2.11943 2.55109 + vertex 1.05736 2.12168 2.54902 + endloop + endfacet + facet normal 0.155783 0.455382 0.876561 + outer loop + vertex 1.0567 2.11592 2.55258 + vertex 1.0548 2.11943 2.55109 + vertex 1.05132 2.11712 2.55291 + endloop + endfacet + facet normal 0.136835 0.448073 0.883463 + outer loop + vertex 1.05955 2.11858 2.55079 + vertex 1.0548 2.11943 2.55109 + vertex 1.0567 2.11592 2.55258 + endloop + endfacet + facet normal 0.0894467 0.844424 0.528154 + outer loop + vertex 1.05393 2.12414 2.54699 + vertex 1.05971 2.1239 2.54639 + vertex 1.05662 2.12595 2.54363 + endloop + endfacet + facet normal 0.0669821 0.854274 0.515489 + outer loop + vertex 1.05148 2.12629 2.54374 + vertex 1.05393 2.12414 2.54699 + vertex 1.05662 2.12595 2.54363 + endloop + endfacet + facet normal 0.12943 0.732033 0.668861 + outer loop + vertex 1.05736 2.12168 2.54902 + vertex 1.05393 2.12414 2.54699 + vertex 1.05321 2.1219 2.54958 + endloop + endfacet + facet normal 0.100998 0.712988 0.693864 + outer loop + vertex 1.05971 2.1239 2.54639 + vertex 1.05393 2.12414 2.54699 + vertex 1.05736 2.12168 2.54902 + endloop + endfacet + facet normal 0.0256427 0.427478 0.903662 + outer loop + vertex 1.06 2.13255 2.535 + vertex 1.055 2.13285 2.535 + vertex 1.05891 2.12921 2.53661 + endloop + endfacet + facet normal 0.0430945 0.442681 0.895643 + outer loop + vertex 1.05891 2.12921 2.53661 + vertex 1.055 2.13285 2.535 + vertex 1.05399 2.12935 2.53678 + endloop + endfacet + facet normal 0.0409041 0.885539 0.462762 + outer loop + vertex 1.05891 2.12921 2.53661 + vertex 1.05399 2.12935 2.53678 + vertex 1.05819 2.12742 2.54011 + endloop + endfacet + facet normal 0.0426161 0.886341 0.461069 + outer loop + vertex 1.05819 2.12742 2.54011 + vertex 1.05399 2.12935 2.53678 + vertex 1.05307 2.12761 2.54022 + endloop + endfacet + facet normal 0.0684047 0.924166 0.375818 + outer loop + vertex 1.05662 2.12595 2.54363 + vertex 1.05307 2.12761 2.54022 + vertex 1.05148 2.12629 2.54374 + endloop + endfacet + facet normal 0.0424001 0.916008 0.398913 + outer loop + vertex 1.05819 2.12742 2.54011 + vertex 1.05307 2.12761 2.54022 + vertex 1.05662 2.12595 2.54363 + endloop + endfacet + facet normal 0.0887136 -0.9924 0.0852783 + outer loop + vertex 1.065 0.892962 2.53 + vertex 1.06212 0.892893 2.53219 + vertex 1.06 0.892515 2.53 + endloop + endfacet + facet normal -0.0919798 -0.96249 0.255251 + outer loop + vertex 1.06212 0.892893 2.53219 + vertex 1.06 0.893841 2.535 + vertex 1.06 0.892515 2.53 + endloop + endfacet + facet normal 0.0919193 -0.975942 0.197709 + outer loop + vertex 1.06148 0.893444 2.53521 + vertex 1.06212 0.892893 2.53219 + vertex 1.06542 0.89364 2.53434 + endloop + endfacet + facet normal 0.0683749 -0.978765 0.193248 + outer loop + vertex 1.06148 0.893444 2.53521 + vertex 1.05761 0.893147 2.53507 + vertex 1.06212 0.892893 2.53219 + endloop + endfacet + facet normal -0.258345 0.839387 -0.478212 + outer loop + vertex 1.05761 0.893147 2.53507 + vertex 1.06 0.893841 2.535 + vertex 1.06212 0.892893 2.53219 + endloop + endfacet + facet normal 0.0662952 -0.969939 0.234142 + outer loop + vertex 1.06148 0.893444 2.53521 + vertex 1.05934 0.893864 2.53755 + vertex 1.05761 0.893147 2.53507 + endloop + endfacet + facet normal 0.116102 -0.941833 0.315391 + outer loop + vertex 1.06542 0.89364 2.53434 + vertex 1.06317 0.894716 2.53839 + vertex 1.06148 0.893444 2.53521 + endloop + endfacet + facet normal 0.144433 -0.942706 0.300741 + outer loop + vertex 1.05934 0.893864 2.53755 + vertex 1.06148 0.893444 2.53521 + vertex 1.06317 0.894716 2.53839 + endloop + endfacet + facet normal 0.130403 -0.927649 0.349947 + outer loop + vertex 1.05934 0.893864 2.53755 + vertex 1.06317 0.894716 2.53839 + vertex 1.05857 0.895016 2.54089 + endloop + endfacet + facet normal 0.169004 -0.893226 0.416635 + outer loop + vertex 1.05857 0.895016 2.54089 + vertex 1.06317 0.894716 2.53839 + vertex 1.06183 0.896355 2.54244 + endloop + endfacet + facet normal 0.180342 -0.838564 0.514088 + outer loop + vertex 1.06313 0.899073 2.54642 + vertex 1.05747 0.897022 2.54506 + vertex 1.06183 0.896355 2.54244 + endloop + endfacet + facet normal 0.14183 -0.876715 0.459625 + outer loop + vertex 1.05747 0.897022 2.54506 + vertex 1.05857 0.895016 2.54089 + vertex 1.06183 0.896355 2.54244 + endloop + endfacet + facet normal 0.159383 -0.812076 0.561364 + outer loop + vertex 1.06313 0.899073 2.54642 + vertex 1.05817 0.898872 2.54754 + vertex 1.05747 0.897022 2.54506 + endloop + endfacet + facet normal 0.185427 -0.691053 0.698615 + outer loop + vertex 1.05817 0.898872 2.54754 + vertex 1.06313 0.899073 2.54642 + vertex 1.05785 0.901254 2.54998 + endloop + endfacet + facet normal 0.137571 -0.740434 0.6579 + outer loop + vertex 1.05785 0.901254 2.54998 + vertex 1.06313 0.899073 2.54642 + vertex 1.06255 0.902335 2.55021 + endloop + endfacet + facet normal 0.0956237 -0.589432 0.802139 + outer loop + vertex 1.06255 0.902335 2.55021 + vertex 1.06034 0.905014 2.55244 + vertex 1.05785 0.901254 2.54998 + endloop + endfacet + facet normal 0.104768 -0.584158 0.80485 + outer loop + vertex 1.06519 0.905249 2.55198 + vertex 1.06034 0.905014 2.55244 + vertex 1.06255 0.902335 2.55021 + endloop + endfacet + facet normal 0.106032 -0.437152 0.893116 + outer loop + vertex 1.06519 0.905249 2.55198 + vertex 1.06392 0.90884 2.55389 + vertex 1.06034 0.905014 2.55244 + endloop + endfacet + facet normal 0.104935 -0.436327 0.893648 + outer loop + vertex 1.06034 0.905014 2.55244 + vertex 1.06392 0.90884 2.55389 + vertex 1.05869 0.908841 2.55451 + endloop + endfacet + facet normal 0.104884 -0.333962 0.936733 + outer loop + vertex 1.05991 0.912504 2.55568 + vertex 1.05616 0.911584 2.55577 + vertex 1.05869 0.908841 2.55451 + endloop + endfacet + facet normal 0.106299 -0.334339 0.936439 + outer loop + vertex 1.05991 0.912504 2.55568 + vertex 1.05869 0.908841 2.55451 + vertex 1.06319 0.912352 2.55525 + endloop + endfacet + facet normal 0.10975 -0.338366 0.934593 + outer loop + vertex 1.06319 0.912352 2.55525 + vertex 1.05869 0.908841 2.55451 + vertex 1.06392 0.90884 2.55389 + endloop + endfacet + facet normal 0.0904574 -0.273001 0.957752 + outer loop + vertex 1.05991 0.912504 2.55568 + vertex 1.05936 0.915241 2.55651 + vertex 1.05616 0.911584 2.55577 + endloop + endfacet + facet normal 0.11057 -0.285782 0.951894 + outer loop + vertex 1.06319 0.912352 2.55525 + vertex 1.06253 0.91494 2.5561 + vertex 1.05991 0.912504 2.55568 + endloop + endfacet + facet normal 0.0965403 -0.27171 0.957525 + outer loop + vertex 1.06253 0.91494 2.5561 + vertex 1.05936 0.915241 2.55651 + vertex 1.05991 0.912504 2.55568 + endloop + endfacet + facet normal 0.0984136 -0.257179 0.96134 + outer loop + vertex 1.06253 0.91494 2.5561 + vertex 1.06412 0.918903 2.557 + vertex 1.05936 0.915241 2.55651 + endloop + endfacet + facet normal 0.103656 -0.263685 0.959023 + outer loop + vertex 1.06412 0.918903 2.557 + vertex 1.05901 0.919129 2.55762 + vertex 1.05936 0.915241 2.55651 + endloop + endfacet + facet normal 0.103086 -0.271108 0.957013 + outer loop + vertex 1.06412 0.918903 2.557 + vertex 1.06373 0.923622 2.55838 + vertex 1.05901 0.919129 2.55762 + endloop + endfacet + facet normal 0.101577 -0.269619 0.957595 + outer loop + vertex 1.05901 0.919129 2.55762 + vertex 1.06373 0.923622 2.55838 + vertex 1.05853 0.923538 2.55891 + endloop + endfacet + facet normal 0.101436 -0.280549 0.954465 + outer loop + vertex 1.06373 0.923622 2.55838 + vertex 1.06342 0.928359 2.5598 + vertex 1.05853 0.923538 2.55891 + endloop + endfacet + facet normal 0.0915247 -0.271184 0.958166 + outer loop + vertex 1.05853 0.923538 2.55891 + vertex 1.06342 0.928359 2.5598 + vertex 1.05814 0.92749 2.56006 + endloop + endfacet + facet normal 0.0929243 -0.28054 0.955334 + outer loop + vertex 1.05814 0.92749 2.56006 + vertex 1.06342 0.928359 2.5598 + vertex 1.06132 0.931222 2.56085 + endloop + endfacet + facet normal 0.0854361 -0.274661 0.957738 + outer loop + vertex 1.05749 0.93018 2.56089 + vertex 1.05814 0.92749 2.56006 + vertex 1.06132 0.931222 2.56085 + endloop + endfacet + facet normal 0.0868914 -0.280081 0.956036 + outer loop + vertex 1.06132 0.931222 2.56085 + vertex 1.05907 0.933997 2.56187 + vertex 1.05749 0.93018 2.56089 + endloop + endfacet + facet normal 0.0903862 -0.277417 0.956488 + outer loop + vertex 1.06443 0.934922 2.56163 + vertex 1.05907 0.933997 2.56187 + vertex 1.06132 0.931222 2.56085 + endloop + endfacet + facet normal 0.0888244 -0.267611 0.959424 + outer loop + vertex 1.06443 0.934922 2.56163 + vertex 1.0639 0.938753 2.56275 + vertex 1.05907 0.933997 2.56187 + endloop + endfacet + facet normal 0.097331 -0.27566 0.956315 + outer loop + vertex 1.05907 0.933997 2.56187 + vertex 1.0639 0.938753 2.56275 + vertex 1.05865 0.938563 2.56323 + endloop + endfacet + facet normal 0.0972746 -0.270073 0.957914 + outer loop + vertex 1.0639 0.938753 2.56275 + vertex 1.06346 0.943161 2.56403 + vertex 1.05865 0.938563 2.56323 + endloop + endfacet + facet normal 0.0993467 -0.272104 0.957126 + outer loop + vertex 1.05865 0.938563 2.56323 + vertex 1.06346 0.943161 2.56403 + vertex 1.05844 0.942892 2.56448 + endloop + endfacet + facet normal 0.0993996 -0.273996 0.95658 + outer loop + vertex 1.06346 0.943161 2.56403 + vertex 1.06277 0.947096 2.56523 + vertex 1.05844 0.942892 2.56448 + endloop + endfacet + facet normal 0.0960083 -0.270729 0.957856 + outer loop + vertex 1.05844 0.942892 2.56448 + vertex 1.06277 0.947096 2.56523 + vertex 1.05833 0.946619 2.56554 + endloop + endfacet + facet normal 0.0962949 -0.274029 0.956888 + outer loop + vertex 1.05833 0.946619 2.56554 + vertex 1.06277 0.947096 2.56523 + vertex 1.06155 0.950307 2.56628 + endloop + endfacet + facet normal 0.0955841 -0.273455 0.957124 + outer loop + vertex 1.05767 0.949214 2.56635 + vertex 1.05833 0.946619 2.56554 + vertex 1.06155 0.950307 2.56628 + endloop + endfacet + facet normal 0.0937445 -0.266799 0.959182 + outer loop + vertex 1.06155 0.950307 2.56628 + vertex 1.05915 0.953318 2.56735 + vertex 1.05767 0.949214 2.56635 + endloop + endfacet + facet normal 0.105943 -0.257538 0.960443 + outer loop + vertex 1.06486 0.954513 2.56704 + vertex 1.05915 0.953318 2.56735 + vertex 1.06155 0.950307 2.56628 + endloop + endfacet + facet normal 0.102993 -0.242321 0.964714 + outer loop + vertex 1.06486 0.954513 2.56704 + vertex 1.06393 0.958588 2.56816 + vertex 1.05915 0.953318 2.56735 + endloop + endfacet + facet normal 0.117989 -0.255136 0.959679 + outer loop + vertex 1.05915 0.953318 2.56735 + vertex 1.06393 0.958588 2.56816 + vertex 1.05867 0.958338 2.56874 + endloop + endfacet + facet normal 0.117682 -0.238917 0.963883 + outer loop + vertex 1.06393 0.958588 2.56816 + vertex 1.06355 0.963256 2.56936 + vertex 1.05867 0.958338 2.56874 + endloop + endfacet + facet normal 0.128998 -0.249616 0.959714 + outer loop + vertex 1.05867 0.958338 2.56874 + vertex 1.06355 0.963256 2.56936 + vertex 1.05844 0.963228 2.57004 + endloop + endfacet + facet normal 0.166553 -0.229028 0.959065 + outer loop + vertex 1.05889 0.973714 2.57262 + vertex 1.0636 0.978586 2.57297 + vertex 1.05855 0.9785 2.57382 + endloop + endfacet + facet normal 0.167091 -0.202532 0.964915 + outer loop + vertex 1.0636 0.978586 2.57297 + vertex 1.06351 0.983588 2.57403 + vertex 1.05855 0.9785 2.57382 + endloop + endfacet + facet normal 0.18969 -0.224198 0.955904 + outer loop + vertex 1.05855 0.9785 2.57382 + vertex 1.06351 0.983588 2.57403 + vertex 1.05862 0.983621 2.57501 + endloop + endfacet + facet normal 0.191261 -0.191516 0.962674 + outer loop + vertex 1.06369 0.988921 2.57506 + vertex 1.05862 0.983621 2.57501 + vertex 1.06351 0.983588 2.57403 + endloop + endfacet + facet normal 0.271342 -0.111088 0.956051 + outer loop + vertex 1.0636 1.11864 2.58862 + vertex 1.06369 1.12365 2.58918 + vertex 1.05962 1.1196 2.58986 + endloop + endfacet + facet normal 0.256706 -0.0954702 0.961763 + outer loop + vertex 1.05962 1.1196 2.58986 + vertex 1.06369 1.12365 2.58918 + vertex 1.05992 1.12414 2.59023 + endloop + endfacet + facet normal 0.25356 -0.116723 0.960252 + outer loop + vertex 1.06362 1.12894 2.58984 + vertex 1.05992 1.12414 2.59023 + vertex 1.06369 1.12365 2.58918 + endloop + endfacet + facet normal 0.207861 -0.13184 0.969233 + outer loop + vertex 1.06337 1.14826 2.59253 + vertex 1.06318 1.15316 2.59324 + vertex 1.05858 1.14873 2.59362 + endloop + endfacet + facet normal 0.381007 0.0896873 0.920212 + outer loop + vertex 1.06052 1.92345 2.5849 + vertex 1.06323 1.92725 2.5834 + vertex 1.05961 1.92861 2.58477 + endloop + endfacet + facet normal 0.387878 0.113599 0.914683 + outer loop + vertex 1.06323 1.92725 2.5834 + vertex 1.06211 1.9313 2.58338 + vertex 1.05961 1.92861 2.58477 + endloop + endfacet + facet normal 0.426602 0.0709972 0.901649 + outer loop + vertex 1.05961 1.92861 2.58477 + vertex 1.06211 1.9313 2.58338 + vertex 1.05931 1.93344 2.58453 + endloop + endfacet + facet normal 0.428398 0.0739441 0.900559 + outer loop + vertex 1.06211 1.9313 2.58338 + vertex 1.06302 1.93599 2.58256 + vertex 1.05931 1.93344 2.58453 + endloop + endfacet + facet normal 0.437547 0.0581718 0.897312 + outer loop + vertex 1.05931 1.93344 2.58453 + vertex 1.06302 1.93599 2.58256 + vertex 1.05925 1.93847 2.58424 + endloop + endfacet + facet normal 0.450363 0.0833629 0.888946 + outer loop + vertex 1.06302 1.93599 2.58256 + vertex 1.06243 1.94162 2.58233 + vertex 1.05925 1.93847 2.58424 + endloop + endfacet + facet normal 0.473213 0.054358 0.87927 + outer loop + vertex 1.05925 1.93847 2.58424 + vertex 1.06243 1.94162 2.58233 + vertex 1.05901 1.94355 2.58405 + endloop + endfacet + facet normal 0.478468 0.0669757 0.875547 + outer loop + vertex 1.06243 1.94162 2.58233 + vertex 1.06197 1.94679 2.58218 + vertex 1.05901 1.94355 2.58405 + endloop + endfacet + facet normal 0.502154 0.0466632 0.863518 + outer loop + vertex 1.06411 1.97356 2.57938 + vertex 1.06403 1.97856 2.57916 + vertex 1.06091 1.97518 2.58116 + endloop + endfacet + facet normal 0.226804 0.216672 0.949533 + outer loop + vertex 1.06404 2.0486 2.57053 + vertex 1.06409 2.05317 2.56948 + vertex 1.06107 2.0502 2.57088 + endloop + endfacet + facet normal 0.222835 0.208716 0.952251 + outer loop + vertex 1.06107 2.0502 2.57088 + vertex 1.06074 2.04599 2.57188 + vertex 1.06404 2.0486 2.57053 + endloop + endfacet + facet normal 0.182958 0.213589 0.959639 + outer loop + vertex 1.06107 2.0502 2.57088 + vertex 1.05674 2.0497 2.57181 + vertex 1.06074 2.04599 2.57188 + endloop + endfacet + facet normal 0.200623 0.243084 0.949031 + outer loop + vertex 1.05939 2.05306 2.5705 + vertex 1.06107 2.0502 2.57088 + vertex 1.06409 2.05317 2.56948 + endloop + endfacet + facet normal 0.199907 0.252504 0.94672 + outer loop + vertex 1.05939 2.05306 2.5705 + vertex 1.06409 2.05317 2.56948 + vertex 1.05949 2.05724 2.56936 + endloop + endfacet + facet normal 0.180063 0.231888 0.955931 + outer loop + vertex 1.06107 2.0502 2.57088 + vertex 1.05939 2.05306 2.5705 + vertex 1.05674 2.0497 2.57181 + endloop + endfacet + facet normal 0.156381 0.33932 0.927581 + outer loop + vertex 1.06197 2.11107 2.55358 + vertex 1.06186 2.11483 2.55223 + vertex 1.05867 2.11262 2.55357 + endloop + endfacet + facet normal 0.139042 0.361024 0.922133 + outer loop + vertex 1.05867 2.11262 2.55357 + vertex 1.06186 2.11483 2.55223 + vertex 1.0567 2.11592 2.55258 + endloop + endfacet + facet normal 0.134608 0.535677 0.833625 + outer loop + vertex 1.05955 2.11858 2.55079 + vertex 1.06364 2.11783 2.5506 + vertex 1.06295 2.12104 2.54865 + endloop + endfacet + facet normal 0.116738 0.5529 0.82503 + outer loop + vertex 1.05736 2.12168 2.54902 + vertex 1.05955 2.11858 2.55079 + vertex 1.06295 2.12104 2.54865 + endloop + endfacet + facet normal 0.152242 0.434492 0.887716 + outer loop + vertex 1.06186 2.11483 2.55223 + vertex 1.05955 2.11858 2.55079 + vertex 1.0567 2.11592 2.55258 + endloop + endfacet + facet normal 0.116151 0.41743 0.901255 + outer loop + vertex 1.06364 2.11783 2.5506 + vertex 1.05955 2.11858 2.55079 + vertex 1.06186 2.11483 2.55223 + endloop + endfacet + facet normal 0.0710105 0.829444 0.554058 + outer loop + vertex 1.05971 2.1239 2.54639 + vertex 1.06489 2.12383 2.54583 + vertex 1.06178 2.12578 2.54331 + endloop + endfacet + facet normal 0.0620662 0.83279 0.550098 + outer loop + vertex 1.05662 2.12595 2.54363 + vertex 1.05971 2.1239 2.54639 + vertex 1.06178 2.12578 2.54331 + endloop + endfacet + facet normal 0.12555 0.698973 0.704041 + outer loop + vertex 1.06295 2.12104 2.54865 + vertex 1.05971 2.1239 2.54639 + vertex 1.05736 2.12168 2.54902 + endloop + endfacet + facet normal 0.0884665 0.677569 0.730119 + outer loop + vertex 1.06489 2.12383 2.54583 + vertex 1.05971 2.1239 2.54639 + vertex 1.06295 2.12104 2.54865 + endloop + endfacet + facet normal 0.00319197 0.318772 0.947826 + outer loop + vertex 1.065 2.1325 2.535 + vertex 1.06 2.13255 2.535 + vertex 1.06355 2.12913 2.53614 + endloop + endfacet + facet normal 0.0995534 0.405746 0.908548 + outer loop + vertex 1.06355 2.12913 2.53614 + vertex 1.06 2.13255 2.535 + vertex 1.05891 2.12921 2.53661 + endloop + endfacet + facet normal 0.0620473 0.888237 0.455175 + outer loop + vertex 1.06355 2.12913 2.53614 + vertex 1.05891 2.12921 2.53661 + vertex 1.06309 2.12732 2.53972 + endloop + endfacet + facet normal 0.0531774 0.883972 0.464506 + outer loop + vertex 1.06309 2.12732 2.53972 + vertex 1.05891 2.12921 2.53661 + vertex 1.05819 2.12742 2.54011 + endloop + endfacet + facet normal 0.0556326 0.913227 0.403635 + outer loop + vertex 1.06178 2.12578 2.54331 + vertex 1.05819 2.12742 2.54011 + vertex 1.05662 2.12595 2.54363 + endloop + endfacet + facet normal 0.0493938 0.910973 0.409498 + outer loop + vertex 1.06309 2.12732 2.53972 + vertex 1.05819 2.12742 2.54011 + vertex 1.06178 2.12578 2.54331 + endloop + endfacet + facet normal 0.131787 -0.971879 -0.195148 + outer loop + vertex 1.07 0.89364 2.53 + vertex 1.06732 0.893059 2.53108 + vertex 1.065 0.892962 2.53 + endloop + endfacet + facet normal 0.0350199 -0.999282 0.014478 + outer loop + vertex 1.06732 0.893059 2.53108 + vertex 1.06212 0.892893 2.53219 + vertex 1.065 0.892962 2.53 + endloop + endfacet + facet normal 0.077629 -0.972744 0.218503 + outer loop + vertex 1.06732 0.893059 2.53108 + vertex 1.06542 0.89364 2.53434 + vertex 1.06212 0.892893 2.53219 + endloop + endfacet + facet normal 0.0815754 -0.971934 0.220656 + outer loop + vertex 1.07035 0.893863 2.5335 + vertex 1.06542 0.89364 2.53434 + vertex 1.06732 0.893059 2.53108 + endloop + endfacet + facet normal 0.0993153 -0.937265 0.334172 + outer loop + vertex 1.06542 0.89364 2.53434 + vertex 1.07035 0.893863 2.5335 + vertex 1.06848 0.895024 2.53731 + endloop + endfacet + facet normal 0.1183 -0.941204 0.316449 + outer loop + vertex 1.06317 0.894716 2.53839 + vertex 1.06542 0.89364 2.53434 + vertex 1.06848 0.895024 2.53731 + endloop + endfacet + facet normal 0.136078 -0.898718 0.416879 + outer loop + vertex 1.06848 0.895024 2.53731 + vertex 1.06635 0.896633 2.54148 + vertex 1.06317 0.894716 2.53839 + endloop + endfacet + facet normal 0.142868 -0.900401 0.410935 + outer loop + vertex 1.06635 0.896633 2.54148 + vertex 1.06183 0.896355 2.54244 + vertex 1.06317 0.894716 2.53839 + endloop + endfacet + facet normal 0.162313 -0.8386 0.520004 + outer loop + vertex 1.06635 0.896633 2.54148 + vertex 1.06313 0.899073 2.54642 + vertex 1.06183 0.896355 2.54244 + endloop + endfacet + facet normal 0.106917 -0.862012 0.495484 + outer loop + vertex 1.06925 0.898572 2.54423 + vertex 1.06313 0.899073 2.54642 + vertex 1.06635 0.896633 2.54148 + endloop + endfacet + facet normal 0.119049 -0.842772 0.52494 + outer loop + vertex 1.06313 0.899073 2.54642 + vertex 1.06925 0.898572 2.54423 + vertex 1.0678 0.89999 2.54683 + endloop + endfacet + facet normal 0.0873819 -0.74391 0.662543 + outer loop + vertex 1.0678 0.89999 2.54683 + vertex 1.06716 0.902095 2.54928 + vertex 1.06313 0.899073 2.54642 + endloop + endfacet + facet normal 0.0938354 -0.747665 0.657413 + outer loop + vertex 1.06716 0.902095 2.54928 + vertex 1.06255 0.902335 2.55021 + vertex 1.06313 0.899073 2.54642 + endloop + endfacet + facet normal 0.128711 -0.597649 0.791359 + outer loop + vertex 1.06716 0.902095 2.54928 + vertex 1.06519 0.905249 2.55198 + vertex 1.06255 0.902335 2.55021 + endloop + endfacet + facet normal 0.104017 -0.608873 0.786419 + outer loop + vertex 1.06966 0.905383 2.5515 + vertex 1.06519 0.905249 2.55198 + vertex 1.06716 0.902095 2.54928 + endloop + endfacet + facet normal 0.0887501 -0.283439 0.954875 + outer loop + vertex 1.06513 0.932267 2.56081 + vertex 1.06132 0.931222 2.56085 + vertex 1.06342 0.928359 2.5598 + endloop + endfacet + facet normal 0.117191 -0.294212 0.948528 + outer loop + vertex 1.06513 0.932267 2.56081 + vertex 1.06342 0.928359 2.5598 + vertex 1.06835 0.932134 2.56037 + endloop + endfacet + facet normal 0.086251 -0.274213 0.957793 + outer loop + vertex 1.06513 0.932267 2.56081 + vertex 1.06443 0.934922 2.56163 + vertex 1.06132 0.931222 2.56085 + endloop + endfacet + facet normal 0.117563 -0.289661 0.949882 + outer loop + vertex 1.06835 0.932134 2.56037 + vertex 1.06776 0.93476 2.56124 + vertex 1.06513 0.932267 2.56081 + endloop + endfacet + facet normal 0.0985654 -0.270915 0.957544 + outer loop + vertex 1.06776 0.93476 2.56124 + vertex 1.06443 0.934922 2.56163 + vertex 1.06513 0.932267 2.56081 + endloop + endfacet + facet normal 0.100338 -0.248478 0.963427 + outer loop + vertex 1.06776 0.93476 2.56124 + vertex 1.06919 0.93874 2.56212 + vertex 1.06443 0.934922 2.56163 + endloop + endfacet + facet normal 0.11317 -0.263762 0.957926 + outer loop + vertex 1.06919 0.93874 2.56212 + vertex 1.0639 0.938753 2.56275 + vertex 1.06443 0.934922 2.56163 + endloop + endfacet + facet normal 0.113319 -0.259433 0.95909 + outer loop + vertex 1.06919 0.93874 2.56212 + vertex 1.06872 0.943481 2.56346 + vertex 1.0639 0.938753 2.56275 + endloop + endfacet + facet normal 0.121341 -0.267147 0.955986 + outer loop + vertex 1.0639 0.938753 2.56275 + vertex 1.06872 0.943481 2.56346 + vertex 1.06346 0.943161 2.56403 + endloop + endfacet + facet normal 0.121327 -0.266695 0.956114 + outer loop + vertex 1.06872 0.943481 2.56346 + vertex 1.06843 0.948434 2.56487 + vertex 1.06346 0.943161 2.56403 + endloop + endfacet + facet normal 0.124151 -0.269185 0.955053 + outer loop + vertex 1.06346 0.943161 2.56403 + vertex 1.06843 0.948434 2.56487 + vertex 1.06277 0.947096 2.56523 + endloop + endfacet + facet normal 0.1276 -0.285134 0.949956 + outer loop + vertex 1.06277 0.947096 2.56523 + vertex 1.06843 0.948434 2.56487 + vertex 1.06622 0.95128 2.56602 + endloop + endfacet + facet normal 0.107397 -0.269797 0.956909 + outer loop + vertex 1.06155 0.950307 2.56628 + vertex 1.06277 0.947096 2.56523 + vertex 1.06622 0.95128 2.56602 + endloop + endfacet + facet normal 0.104891 -0.256766 0.960765 + outer loop + vertex 1.06622 0.95128 2.56602 + vertex 1.06486 0.954513 2.56704 + vertex 1.06155 0.950307 2.56628 + endloop + endfacet + facet normal 0.128347 -0.24684 0.960519 + outer loop + vertex 1.06939 0.955205 2.56661 + vertex 1.06486 0.954513 2.56704 + vertex 1.06622 0.95128 2.56602 + endloop + endfacet + facet normal 0.12519 -0.222284 0.966911 + outer loop + vertex 1.06939 0.955205 2.56661 + vertex 1.06896 0.958997 2.56754 + vertex 1.06486 0.954513 2.56704 + endloop + endfacet + facet normal 0.138151 -0.233618 0.962464 + outer loop + vertex 1.06486 0.954513 2.56704 + vertex 1.06896 0.958997 2.56754 + vertex 1.06393 0.958588 2.56816 + endloop + endfacet + facet normal 0.137428 -0.219529 0.965878 + outer loop + vertex 1.06896 0.958997 2.56754 + vertex 1.06864 0.96358 2.56862 + vertex 1.06393 0.958588 2.56816 + endloop + endfacet + facet normal 0.154288 -0.234886 0.9597 + outer loop + vertex 1.06393 0.958588 2.56816 + vertex 1.06864 0.96358 2.56862 + vertex 1.06355 0.963256 2.56936 + endloop + endfacet + facet normal 0.270444 -0.13675 0.952974 + outer loop + vertex 1.06352 1.00379 2.57779 + vertex 1.06796 1.0086 2.57722 + vertex 1.06365 1.00893 2.57849 + endloop + endfacet + facet normal 0.274671 -0.0959574 0.956738 + outer loop + vertex 1.06796 1.0086 2.57722 + vertex 1.06797 1.01344 2.57771 + vertex 1.06365 1.00893 2.57849 + endloop + endfacet + facet normal 0.293021 -0.114835 0.949185 + outer loop + vertex 1.06365 1.00893 2.57849 + vertex 1.06797 1.01344 2.57771 + vertex 1.06391 1.01402 2.57903 + endloop + endfacet + facet normal 0.297394 -0.0877772 0.950711 + outer loop + vertex 1.06797 1.01344 2.57771 + vertex 1.06804 1.01846 2.57815 + vertex 1.06391 1.01402 2.57903 + endloop + endfacet + facet normal 0.313257 -0.103817 0.943977 + outer loop + vertex 1.06391 1.01402 2.57903 + vertex 1.06804 1.01846 2.57815 + vertex 1.06371 1.01921 2.57967 + endloop + endfacet + facet normal 0.316807 -0.0847544 0.944696 + outer loop + vertex 1.06804 1.01846 2.57815 + vertex 1.06833 1.02366 2.57852 + vertex 1.06371 1.01921 2.57967 + endloop + endfacet + facet normal 0.326259 -0.0956859 0.940425 + outer loop + vertex 1.06371 1.01921 2.57967 + vertex 1.06833 1.02366 2.57852 + vertex 1.06472 1.02483 2.57989 + endloop + endfacet + facet normal 0.330418 -0.0826098 0.940213 + outer loop + vertex 1.06833 1.02366 2.57852 + vertex 1.06876 1.02889 2.57882 + vertex 1.06472 1.02483 2.57989 + endloop + endfacet + facet normal 0.334283 -0.0869152 0.938456 + outer loop + vertex 1.06472 1.02483 2.57989 + vertex 1.06876 1.02889 2.57882 + vertex 1.0651 1.02947 2.58018 + endloop + endfacet + facet normal 0.335528 -0.0794918 0.93867 + outer loop + vertex 1.0685 1.0342 2.57937 + vertex 1.0651 1.02947 2.58018 + vertex 1.06876 1.02889 2.57882 + endloop + endfacet + facet normal 0.208417 -0.10733 0.972133 + outer loop + vertex 1.06372 1.11369 2.58804 + vertex 1.06832 1.11816 2.58755 + vertex 1.0636 1.11864 2.58862 + endloop + endfacet + facet normal 0.310134 0.126479 0.942242 + outer loop + vertex 1.07033 1.93834 2.57972 + vertex 1.06943 1.94354 2.57932 + vertex 1.06616 1.94006 2.58086 + endloop + endfacet + facet normal 0.393628 0.0784931 0.915913 + outer loop + vertex 1.06243 1.94162 2.58233 + vertex 1.06302 1.93599 2.58256 + vertex 1.06616 1.94006 2.58086 + endloop + endfacet + facet normal 0.350351 0.116429 0.929354 + outer loop + vertex 1.06943 1.94354 2.57932 + vertex 1.06858 1.9484 2.57903 + vertex 1.06556 1.94505 2.58059 + endloop + endfacet + facet normal 0.34284 0.0925345 0.934825 + outer loop + vertex 1.06616 1.94006 2.58086 + vertex 1.06943 1.94354 2.57932 + vertex 1.06556 1.94505 2.58059 + endloop + endfacet + facet normal 0.400023 0.0981985 0.911229 + outer loop + vertex 1.06556 1.94505 2.58059 + vertex 1.06243 1.94162 2.58233 + vertex 1.06616 1.94006 2.58086 + endloop + endfacet + facet normal 0.431688 0.063517 0.899784 + outer loop + vertex 1.06197 1.94679 2.58218 + vertex 1.06243 1.94162 2.58233 + vertex 1.06556 1.94505 2.58059 + endloop + endfacet + facet normal 0.393679 0.102869 0.913474 + outer loop + vertex 1.06858 1.9484 2.57903 + vertex 1.06774 1.95352 2.57881 + vertex 1.06493 1.94998 2.58042 + endloop + endfacet + facet normal 0.385798 0.0796299 0.91914 + outer loop + vertex 1.06556 1.94505 2.58059 + vertex 1.06858 1.9484 2.57903 + vertex 1.06493 1.94998 2.58042 + endloop + endfacet + facet normal 0.439861 0.0856664 0.89397 + outer loop + vertex 1.06493 1.94998 2.58042 + vertex 1.06197 1.94679 2.58218 + vertex 1.06556 1.94505 2.58059 + endloop + endfacet + facet normal 0.467576 0.0535445 0.882329 + outer loop + vertex 1.06131 1.95219 2.58221 + vertex 1.06197 1.94679 2.58218 + vertex 1.06493 1.94998 2.58042 + endloop + endfacet + facet normal 0.425944 0.0720223 0.901878 + outer loop + vertex 1.06433 1.95399 2.58038 + vertex 1.06493 1.94998 2.58042 + vertex 1.06774 1.95352 2.57881 + endloop + endfacet + facet normal 0.426008 0.072801 0.901786 + outer loop + vertex 1.06433 1.95399 2.58038 + vertex 1.06774 1.95352 2.57881 + vertex 1.06533 1.95796 2.57959 + endloop + endfacet + facet normal 0.446752 0.0860626 0.890509 + outer loop + vertex 1.06533 1.95796 2.57959 + vertex 1.06774 1.95352 2.57881 + vertex 1.06825 1.9571 2.57821 + endloop + endfacet + facet normal 0.479429 0.0796653 0.873957 + outer loop + vertex 1.06493 1.94998 2.58042 + vertex 1.06433 1.95399 2.58038 + vertex 1.06131 1.95219 2.58221 + endloop + endfacet + facet normal 0.443151 0.0684167 0.893833 + outer loop + vertex 1.06825 1.9571 2.57821 + vertex 1.06861 1.96094 2.57774 + vertex 1.06533 1.95796 2.57959 + endloop + endfacet + facet normal 0.50365 0.0534075 0.862255 + outer loop + vertex 1.06403 1.97856 2.57916 + vertex 1.06715 1.98191 2.57713 + vertex 1.06389 1.98354 2.57893 + endloop + endfacet + facet normal 0.501388 0.0470255 0.863943 + outer loop + vertex 1.06715 1.98191 2.57713 + vertex 1.06697 1.98686 2.57697 + vertex 1.06389 1.98354 2.57893 + endloop + endfacet + facet normal 0.490323 0.0605391 0.869436 + outer loop + vertex 1.06389 1.98354 2.57893 + vertex 1.06697 1.98686 2.57697 + vertex 1.06352 1.98852 2.5788 + endloop + endfacet + facet normal 0.48524 0.0458852 0.873176 + outer loop + vertex 1.06697 1.98686 2.57697 + vertex 1.06655 1.99188 2.57694 + vertex 1.06352 1.98852 2.5788 + endloop + endfacet + facet normal 0.470223 0.0633642 0.88027 + outer loop + vertex 1.06352 1.98852 2.5788 + vertex 1.06655 1.99188 2.57694 + vertex 1.06278 1.99376 2.57882 + endloop + endfacet + facet normal 0.462461 0.0424852 0.885621 + outer loop + vertex 1.06655 1.99188 2.57694 + vertex 1.06604 1.99702 2.57696 + vertex 1.06278 1.99376 2.57882 + endloop + endfacet + facet normal 0.454341 0.0526713 0.889269 + outer loop + vertex 1.06278 1.99376 2.57882 + vertex 1.06604 1.99702 2.57696 + vertex 1.06326 1.99744 2.57835 + endloop + endfacet + facet normal 0.456004 0.0710941 0.887134 + outer loop + vertex 1.06366 2.00117 2.57785 + vertex 1.06326 1.99744 2.57835 + vertex 1.06604 1.99702 2.57696 + endloop + endfacet + facet normal 0.145224 0.4333 0.889473 + outer loop + vertex 1.07001 2.1148 2.55105 + vertex 1.06783 2.11864 2.54954 + vertex 1.06597 2.11564 2.5513 + endloop + endfacet + facet normal 0.129825 0.346557 0.929001 + outer loop + vertex 1.06597 2.11564 2.5513 + vertex 1.06637 2.11183 2.55267 + vertex 1.07001 2.1148 2.55105 + endloop + endfacet + facet normal 0.139441 0.347004 0.92744 + outer loop + vertex 1.06597 2.11564 2.5513 + vertex 1.06186 2.11483 2.55223 + vertex 1.06637 2.11183 2.55267 + endloop + endfacet + facet normal 0.134355 0.33986 0.93083 + outer loop + vertex 1.06186 2.11483 2.55223 + vertex 1.06197 2.11107 2.55358 + vertex 1.06637 2.11183 2.55267 + endloop + endfacet + facet normal 0.142454 0.434838 0.88917 + outer loop + vertex 1.06364 2.11783 2.5506 + vertex 1.06597 2.11564 2.5513 + vertex 1.06783 2.11864 2.54954 + endloop + endfacet + facet normal 0.110605 0.533461 0.838562 + outer loop + vertex 1.06364 2.11783 2.5506 + vertex 1.06783 2.11864 2.54954 + vertex 1.06295 2.12104 2.54865 + endloop + endfacet + facet normal 0.119329 0.547403 0.828318 + outer loop + vertex 1.06295 2.12104 2.54865 + vertex 1.06783 2.11864 2.54954 + vertex 1.06747 2.12181 2.54749 + endloop + endfacet + facet normal 0.12018 0.415289 0.901716 + outer loop + vertex 1.06597 2.11564 2.5513 + vertex 1.06364 2.11783 2.5506 + vertex 1.06186 2.11483 2.55223 + endloop + endfacet + facet normal 0.0669543 0.826191 0.559397 + outer loop + vertex 1.06489 2.12383 2.54583 + vertex 1.0701 2.12387 2.54515 + vertex 1.06666 2.12575 2.54278 + endloop + endfacet + facet normal 0.065421 0.8267 0.558827 + outer loop + vertex 1.06178 2.12578 2.54331 + vertex 1.06489 2.12383 2.54583 + vertex 1.06666 2.12575 2.54278 + endloop + endfacet + facet normal 0.0693633 0.685465 0.724794 + outer loop + vertex 1.06747 2.12181 2.54749 + vertex 1.06489 2.12383 2.54583 + vertex 1.06295 2.12104 2.54865 + endloop + endfacet + facet normal 0.0876805 0.697582 0.71112 + outer loop + vertex 1.0701 2.12387 2.54515 + vertex 1.06489 2.12383 2.54583 + vertex 1.06747 2.12181 2.54749 + endloop + endfacet + facet normal 0.0820769 0.651505 0.754191 + outer loop + vertex 1.07 2.13238 2.53 + vertex 1.065 2.13301 2.53 + vertex 1.06864 2.12993 2.53226 + endloop + endfacet + facet normal 0.613986 0.785243 0.0800894 + outer loop + vertex 1.06864 2.12993 2.53226 + vertex 1.065 2.13301 2.53 + vertex 1.065 2.1325 2.535 + endloop + endfacet + facet normal 0.717508 0.48499 0.499966 + outer loop + vertex 1.06864 2.12993 2.53226 + vertex 1.065 2.1325 2.535 + vertex 1.06733 2.12891 2.53514 + endloop + endfacet + facet normal 0.261943 0.206106 0.942818 + outer loop + vertex 1.06733 2.12891 2.53514 + vertex 1.065 2.1325 2.535 + vertex 1.06355 2.12913 2.53614 + endloop + endfacet + facet normal 0.146425 0.923992 0.353269 + outer loop + vertex 1.06733 2.12891 2.53514 + vertex 1.06355 2.12913 2.53614 + vertex 1.06818 2.12731 2.53896 + endloop + endfacet + facet normal 0.0695597 0.887402 0.455718 + outer loop + vertex 1.06818 2.12731 2.53896 + vertex 1.06355 2.12913 2.53614 + vertex 1.06309 2.12732 2.53972 + endloop + endfacet + facet normal 0.0497408 0.910909 0.409597 + outer loop + vertex 1.06666 2.12575 2.54278 + vertex 1.06309 2.12732 2.53972 + vertex 1.06178 2.12578 2.54331 + endloop + endfacet + facet normal 0.0610732 0.915115 0.39854 + outer loop + vertex 1.06818 2.12731 2.53896 + vertex 1.06309 2.12732 2.53972 + vertex 1.06666 2.12575 2.54278 + endloop + endfacet + facet normal 0.0234826 -0.832569 -0.553423 + outer loop + vertex 1.075 0.893781 2.53 + vertex 1.0724 0.893351 2.53054 + vertex 1.07 0.89364 2.53 + endloop + endfacet + facet normal -0.000246726 -0.880856 -0.473385 + outer loop + vertex 1.0724 0.893351 2.53054 + vertex 1.06732 0.893059 2.53108 + vertex 1.07 0.89364 2.53 + endloop + endfacet + facet normal 0.0798283 -0.971605 0.222734 + outer loop + vertex 1.0724 0.893351 2.53054 + vertex 1.07035 0.893863 2.5335 + vertex 1.06732 0.893059 2.53108 + endloop + endfacet + facet normal 0.0733271 -0.973078 0.218499 + outer loop + vertex 1.07531 0.89408 2.5328 + vertex 1.07035 0.893863 2.5335 + vertex 1.0724 0.893351 2.53054 + endloop + endfacet + facet normal 0.0892529 -0.935039 0.343128 + outer loop + vertex 1.07035 0.893863 2.5335 + vertex 1.07531 0.89408 2.5328 + vertex 1.07365 0.89523 2.53637 + endloop + endfacet + facet normal 0.0983894 -0.937499 0.33379 + outer loop + vertex 1.06848 0.895024 2.53731 + vertex 1.07035 0.893863 2.5335 + vertex 1.07365 0.89523 2.53637 + endloop + endfacet + facet normal 0.112457 -0.901087 0.418804 + outer loop + vertex 1.07365 0.89523 2.53637 + vertex 1.07167 0.896798 2.54028 + vertex 1.06848 0.895024 2.53731 + endloop + endfacet + facet normal 0.121048 -0.903544 0.411041 + outer loop + vertex 1.07167 0.896798 2.54028 + vertex 1.06635 0.896633 2.54148 + vertex 1.06848 0.895024 2.53731 + endloop + endfacet + facet normal 0.134048 -0.870777 0.473053 + outer loop + vertex 1.07167 0.896798 2.54028 + vertex 1.06925 0.898572 2.54423 + vertex 1.06635 0.896633 2.54148 + endloop + endfacet + facet normal 0.136777 -0.869704 0.474243 + outer loop + vertex 1.07449 0.898811 2.54316 + vertex 1.06925 0.898572 2.54423 + vertex 1.07167 0.896798 2.54028 + endloop + endfacet + facet normal 0.150093 -0.821506 0.550091 + outer loop + vertex 1.06925 0.898572 2.54423 + vertex 1.07449 0.898811 2.54316 + vertex 1.07175 0.900875 2.54699 + endloop + endfacet + facet normal 0.164117 -0.825203 0.540469 + outer loop + vertex 1.0678 0.89999 2.54683 + vertex 1.06925 0.898572 2.54423 + vertex 1.07175 0.900875 2.54699 + endloop + endfacet + facet normal 0.167058 -0.740598 0.65085 + outer loop + vertex 1.07111 0.903173 2.54976 + vertex 1.07175 0.900875 2.54699 + vertex 1.07493 0.903379 2.54902 + endloop + endfacet + facet normal 0.125475 -0.750151 0.649253 + outer loop + vertex 1.07111 0.903173 2.54976 + vertex 1.06716 0.902095 2.54928 + vertex 1.07175 0.900875 2.54699 + endloop + endfacet + facet normal 0.138594 -0.73277 0.666213 + outer loop + vertex 1.06716 0.902095 2.54928 + vertex 1.0678 0.89999 2.54683 + vertex 1.07175 0.900875 2.54699 + endloop + endfacet + facet normal 0.062676 -0.589991 0.804974 + outer loop + vertex 1.07111 0.903173 2.54976 + vertex 1.06966 0.905383 2.5515 + vertex 1.06716 0.902095 2.54928 + endloop + endfacet + facet normal 0.143284 -0.283374 0.948245 + outer loop + vertex 1.06776 0.93476 2.56124 + vertex 1.06835 0.932134 2.56037 + vertex 1.0714 0.936019 2.56107 + endloop + endfacet + facet normal 0.278857 -0.170399 0.945094 + outer loop + vertex 1.07037 1.00244 2.5758 + vertex 1.06766 1.00022 2.5762 + vertex 1.06946 0.998621 2.57538 + endloop + endfacet + facet normal 0.364613 -0.187123 0.912164 + outer loop + vertex 1.07037 1.00244 2.5758 + vertex 1.06946 0.998621 2.57538 + vertex 1.07377 1.00371 2.57471 + endloop + endfacet + facet normal 0.255611 -0.140034 0.956584 + outer loop + vertex 1.07037 1.00244 2.5758 + vertex 1.06827 1.00398 2.57659 + vertex 1.06766 1.00022 2.5762 + endloop + endfacet + facet normal 0.359169 -0.167437 0.91813 + outer loop + vertex 1.07377 1.00371 2.57471 + vertex 1.0719 1.00541 2.57575 + vertex 1.07037 1.00244 2.5758 + endloop + endfacet + facet normal 0.269509 -0.120543 0.955424 + outer loop + vertex 1.0719 1.00541 2.57575 + vertex 1.06827 1.00398 2.57659 + vertex 1.07037 1.00244 2.5758 + endloop + endfacet + facet normal 0.260897 -0.0956129 0.96062 + outer loop + vertex 1.0719 1.00541 2.57575 + vertex 1.07177 1.00852 2.57609 + vertex 1.06827 1.00398 2.57659 + endloop + endfacet + facet normal 0.281125 -0.112007 0.953113 + outer loop + vertex 1.07177 1.00852 2.57609 + vertex 1.06796 1.0086 2.57722 + vertex 1.06827 1.00398 2.57659 + endloop + endfacet + facet normal 0.282704 -0.0762354 0.956173 + outer loop + vertex 1.07177 1.00852 2.57609 + vertex 1.07187 1.01288 2.57641 + vertex 1.06796 1.0086 2.57722 + endloop + endfacet + facet normal 0.301886 -0.0951764 0.948581 + outer loop + vertex 1.06796 1.0086 2.57722 + vertex 1.07187 1.01288 2.57641 + vertex 1.06797 1.01344 2.57771 + endloop + endfacet + facet normal 0.305137 -0.0743687 0.9494 + outer loop + vertex 1.07187 1.01288 2.57641 + vertex 1.07197 1.01769 2.57675 + vertex 1.06797 1.01344 2.57771 + endloop + endfacet + facet normal 0.317791 -0.087462 0.944118 + outer loop + vertex 1.06797 1.01344 2.57771 + vertex 1.07197 1.01769 2.57675 + vertex 1.06804 1.01846 2.57815 + endloop + endfacet + facet normal 0.320113 -0.0760148 0.944325 + outer loop + vertex 1.07197 1.01769 2.57675 + vertex 1.07215 1.02267 2.57709 + vertex 1.06804 1.01846 2.57815 + endloop + endfacet + facet normal 0.328474 -0.0851305 0.940669 + outer loop + vertex 1.06804 1.01846 2.57815 + vertex 1.07215 1.02267 2.57709 + vertex 1.06833 1.02366 2.57852 + endloop + endfacet + facet normal 0.329802 -0.0799751 0.940656 + outer loop + vertex 1.07215 1.02267 2.57709 + vertex 1.07255 1.02778 2.57739 + vertex 1.06833 1.02366 2.57852 + endloop + endfacet + facet normal 0.332198 -0.0827198 0.939575 + outer loop + vertex 1.06833 1.02366 2.57852 + vertex 1.07255 1.02778 2.57739 + vertex 1.06876 1.02889 2.57882 + endloop + endfacet + facet normal 0.33228 -0.0824337 0.939571 + outer loop + vertex 1.07255 1.02778 2.57739 + vertex 1.07338 1.03348 2.57759 + vertex 1.06876 1.02889 2.57882 + endloop + endfacet + facet normal 0.330081 -0.0799531 0.94056 + outer loop + vertex 1.06876 1.02889 2.57882 + vertex 1.07338 1.03348 2.57759 + vertex 1.0685 1.0342 2.57937 + endloop + endfacet + facet normal 0.329315 -0.0847546 0.940408 + outer loop + vertex 1.07338 1.03348 2.57759 + vertex 1.07312 1.03873 2.57816 + vertex 1.0685 1.0342 2.57937 + endloop + endfacet + facet normal 0.321249 -0.0755912 0.943973 + outer loop + vertex 1.0685 1.0342 2.57937 + vertex 1.07312 1.03873 2.57816 + vertex 1.06925 1.03991 2.57957 + endloop + endfacet + facet normal 0.319267 -0.0822255 0.944091 + outer loop + vertex 1.07312 1.03873 2.57816 + vertex 1.0735 1.04393 2.57848 + vertex 1.06925 1.03991 2.57957 + endloop + endfacet + facet normal 0.30851 -0.0696166 0.94867 + outer loop + vertex 1.06925 1.03991 2.57957 + vertex 1.0735 1.04393 2.57848 + vertex 1.06957 1.04505 2.57984 + endloop + endfacet + facet normal 0.305094 -0.0816843 0.948813 + outer loop + vertex 1.0735 1.04393 2.57848 + vertex 1.07374 1.04908 2.57885 + vertex 1.06957 1.04505 2.57984 + endloop + endfacet + facet normal 0.293405 -0.0684103 0.953537 + outer loop + vertex 1.06957 1.04505 2.57984 + vertex 1.07374 1.04908 2.57885 + vertex 1.06975 1.05006 2.58015 + endloop + endfacet + facet normal 0.288982 -0.0862424 0.953442 + outer loop + vertex 1.07374 1.04908 2.57885 + vertex 1.07378 1.05413 2.57929 + vertex 1.06975 1.05006 2.58015 + endloop + endfacet + facet normal 0.276307 -0.0726513 0.95832 + outer loop + vertex 1.06975 1.05006 2.58015 + vertex 1.07378 1.05413 2.57929 + vertex 1.06985 1.05476 2.58047 + endloop + endfacet + facet normal 0.271688 -0.0993107 0.957248 + outer loop + vertex 1.07378 1.05413 2.57929 + vertex 1.07354 1.05918 2.57989 + vertex 1.06985 1.05476 2.58047 + endloop + endfacet + facet normal 0.252105 -0.0820407 0.964216 + outer loop + vertex 1.06985 1.05476 2.58047 + vertex 1.07354 1.05918 2.57989 + vertex 1.06974 1.05814 2.58079 + endloop + endfacet + facet normal 0.260131 -0.116494 0.95852 + outer loop + vertex 1.06974 1.05814 2.58079 + vertex 1.07354 1.05918 2.57989 + vertex 1.07103 1.06136 2.58083 + endloop + endfacet + facet normal 0.288728 -0.12786 0.948835 + outer loop + vertex 1.06796 1.05953 2.58152 + vertex 1.06974 1.05814 2.58079 + vertex 1.07103 1.06136 2.58083 + endloop + endfacet + facet normal 0.288772 -0.127942 0.948811 + outer loop + vertex 1.07103 1.06136 2.58083 + vertex 1.06851 1.06355 2.58189 + vertex 1.06796 1.05953 2.58152 + endloop + endfacet + facet normal 0.278469 -0.140464 0.950118 + outer loop + vertex 1.07238 1.06459 2.58091 + vertex 1.06851 1.06355 2.58189 + vertex 1.07103 1.06136 2.58083 + endloop + endfacet + facet normal 0.273187 -0.116328 0.954901 + outer loop + vertex 1.07238 1.06459 2.58091 + vertex 1.07244 1.06802 2.58131 + vertex 1.06851 1.06355 2.58189 + endloop + endfacet + facet normal 0.256179 -0.100554 0.961385 + outer loop + vertex 1.06851 1.06355 2.58189 + vertex 1.07244 1.06802 2.58131 + vertex 1.06836 1.06873 2.58248 + endloop + endfacet + facet normal 0.344563 0.0956347 0.933879 + outer loop + vertex 1.06858 1.9484 2.57903 + vertex 1.07119 1.95125 2.57777 + vertex 1.06774 1.95352 2.57881 + endloop + endfacet + facet normal 0.350839 0.106784 0.930328 + outer loop + vertex 1.07119 1.95125 2.57777 + vertex 1.07166 1.9561 2.57704 + vertex 1.06774 1.95352 2.57881 + endloop + endfacet + facet normal 0.351016 0.106491 0.930294 + outer loop + vertex 1.06774 1.95352 2.57881 + vertex 1.07166 1.9561 2.57704 + vertex 1.06825 1.9571 2.57821 + endloop + endfacet + facet normal 0.298492 0.113145 0.947682 + outer loop + vertex 1.07476 1.95871 2.57569 + vertex 1.07558 1.96305 2.57492 + vertex 1.07221 1.96071 2.57626 + endloop + endfacet + facet normal 0.30572 0.123355 0.944097 + outer loop + vertex 1.07221 1.96071 2.57626 + vertex 1.07166 1.9561 2.57704 + vertex 1.07476 1.95871 2.57569 + endloop + endfacet + facet normal 0.38393 0.109263 0.916875 + outer loop + vertex 1.07221 1.96071 2.57626 + vertex 1.06861 1.96094 2.57774 + vertex 1.07166 1.9561 2.57704 + endloop + endfacet + facet normal 0.345446 0.0824472 0.93481 + outer loop + vertex 1.06861 1.96094 2.57774 + vertex 1.06825 1.9571 2.57821 + vertex 1.07166 1.9561 2.57704 + endloop + endfacet + facet normal 0.328991 0.122741 0.936322 + outer loop + vertex 1.07558 1.96305 2.57492 + vertex 1.07453 1.9685 2.57457 + vertex 1.07138 1.96497 2.57614 + endloop + endfacet + facet normal 0.315334 0.0873614 0.944951 + outer loop + vertex 1.07221 1.96071 2.57626 + vertex 1.07558 1.96305 2.57492 + vertex 1.07138 1.96497 2.57614 + endloop + endfacet + facet normal 0.383796 0.0999372 0.917994 + outer loop + vertex 1.07138 1.96497 2.57614 + vertex 1.06861 1.96094 2.57774 + vertex 1.07221 1.96071 2.57626 + endloop + endfacet + facet normal 0.41924 0.0704089 0.905141 + outer loop + vertex 1.06769 1.9666 2.57772 + vertex 1.06861 1.96094 2.57774 + vertex 1.07138 1.96497 2.57614 + endloop + endfacet + facet normal 0.375927 0.109786 0.920123 + outer loop + vertex 1.07453 1.9685 2.57457 + vertex 1.07387 1.97353 2.57424 + vertex 1.07076 1.97013 2.57592 + endloop + endfacet + facet normal 0.367112 0.0843653 0.926343 + outer loop + vertex 1.07138 1.96497 2.57614 + vertex 1.07453 1.9685 2.57457 + vertex 1.07076 1.97013 2.57592 + endloop + endfacet + facet normal 0.425969 0.0903852 0.900212 + outer loop + vertex 1.07076 1.97013 2.57592 + vertex 1.06769 1.9666 2.57772 + vertex 1.07138 1.96497 2.57614 + endloop + endfacet + facet normal 0.473569 0.0553967 0.879013 + outer loop + vertex 1.07295 1.98254 2.57385 + vertex 1.07382 1.98704 2.5731 + vertex 1.07022 1.98486 2.57517 + endloop + endfacet + facet normal 0.50472 0.0470856 0.861998 + outer loop + vertex 1.06697 1.98686 2.57697 + vertex 1.06715 1.98191 2.57713 + vertex 1.07022 1.98486 2.57517 + endloop + endfacet + facet normal 0.486798 0.0607443 0.8714 + outer loop + vertex 1.07382 1.98704 2.5731 + vertex 1.07297 1.99281 2.57317 + vertex 1.07002 1.98984 2.57502 + endloop + endfacet + facet normal 0.478397 0.0454943 0.876964 + outer loop + vertex 1.07022 1.98486 2.57517 + vertex 1.07382 1.98704 2.5731 + vertex 1.07002 1.98984 2.57502 + endloop + endfacet + facet normal 0.504288 0.0461082 0.862304 + outer loop + vertex 1.07002 1.98984 2.57502 + vertex 1.06697 1.98686 2.57697 + vertex 1.07022 1.98486 2.57517 + endloop + endfacet + facet normal 0.503377 0.0473465 0.862768 + outer loop + vertex 1.06655 1.99188 2.57694 + vertex 1.06697 1.98686 2.57697 + vertex 1.07002 1.98984 2.57502 + endloop + endfacet + facet normal 0.503075 0.0382707 0.863395 + outer loop + vertex 1.07297 1.99281 2.57317 + vertex 1.07236 1.9984 2.57328 + vertex 1.06951 1.99487 2.57509 + endloop + endfacet + facet normal 0.503419 0.0390714 0.863158 + outer loop + vertex 1.07002 1.98984 2.57502 + vertex 1.07297 1.99281 2.57317 + vertex 1.06951 1.99487 2.57509 + endloop + endfacet + facet normal 0.499699 0.0386613 0.865336 + outer loop + vertex 1.06951 1.99487 2.57509 + vertex 1.06655 1.99188 2.57694 + vertex 1.07002 1.98984 2.57502 + endloop + endfacet + facet normal 0.494317 0.0456846 0.86808 + outer loop + vertex 1.06604 1.99702 2.57696 + vertex 1.06655 1.99188 2.57694 + vertex 1.06951 1.99487 2.57509 + endloop + endfacet + facet normal 0.507686 0.033274 0.8609 + outer loop + vertex 1.06903 1.99889 2.57522 + vertex 1.06951 1.99487 2.57509 + vertex 1.07236 1.9984 2.57328 + endloop + endfacet + facet normal 0.508418 0.0412637 0.860121 + outer loop + vertex 1.06903 1.99889 2.57522 + vertex 1.07236 1.9984 2.57328 + vertex 1.07007 2.00304 2.5744 + endloop + endfacet + facet normal 0.497914 0.0345386 0.866538 + outer loop + vertex 1.07007 2.00304 2.5744 + vertex 1.07236 1.9984 2.57328 + vertex 1.07337 2.00281 2.57252 + endloop + endfacet + facet normal 0.487343 0.0304997 0.872678 + outer loop + vertex 1.06951 1.99487 2.57509 + vertex 1.06903 1.99889 2.57522 + vertex 1.06604 1.99702 2.57696 + endloop + endfacet + facet normal 0.498 0.037006 0.866387 + outer loop + vertex 1.07337 2.00281 2.57252 + vertex 1.0728 2.00685 2.57268 + vertex 1.07007 2.00304 2.5744 + endloop + endfacet + facet normal 0.477025 0.0568307 0.87705 + outer loop + vertex 1.07007 2.00304 2.5744 + vertex 1.0728 2.00685 2.57268 + vertex 1.06941 2.00831 2.57442 + endloop + endfacet + facet normal 0.475955 0.0533916 0.877847 + outer loop + vertex 1.0728 2.00685 2.57268 + vertex 1.07236 2.01172 2.57262 + vertex 1.06941 2.00831 2.57442 + endloop + endfacet + facet normal 0.450979 0.0807379 0.888875 + outer loop + vertex 1.06941 2.00831 2.57442 + vertex 1.07236 2.01172 2.57262 + vertex 1.06879 2.01336 2.57428 + endloop + endfacet + facet normal 0.448359 0.0730105 0.890867 + outer loop + vertex 1.07236 2.01172 2.57262 + vertex 1.07183 2.01679 2.57247 + vertex 1.06879 2.01336 2.57428 + endloop + endfacet + facet normal 0.422502 0.101165 0.900699 + outer loop + vertex 1.06879 2.01336 2.57428 + vertex 1.07183 2.01679 2.57247 + vertex 1.06788 2.01869 2.57411 + endloop + endfacet + facet normal 0.417427 0.0873177 0.904506 + outer loop + vertex 1.07183 2.01679 2.57247 + vertex 1.07121 2.02198 2.57226 + vertex 1.06788 2.01869 2.57411 + endloop + endfacet + facet normal 0.400088 0.107934 0.910099 + outer loop + vertex 1.06788 2.01869 2.57411 + vertex 1.07121 2.02198 2.57226 + vertex 1.06824 2.0224 2.57351 + endloop + endfacet + facet normal 0.40465 0.0875672 0.910269 + outer loop + vertex 1.0744 2.02398 2.57062 + vertex 1.07528 2.02809 2.56983 + vertex 1.07219 2.026 2.5714 + endloop + endfacet + facet normal 0.40831 0.092408 0.908154 + outer loop + vertex 1.07219 2.026 2.5714 + vertex 1.07121 2.02198 2.57226 + vertex 1.0744 2.02398 2.57062 + endloop + endfacet + facet normal 0.373416 0.103829 0.921835 + outer loop + vertex 1.07219 2.026 2.5714 + vertex 1.06845 2.02618 2.5729 + vertex 1.07121 2.02198 2.57226 + endloop + endfacet + facet normal 0.401306 0.12436 0.907463 + outer loop + vertex 1.06845 2.02618 2.5729 + vertex 1.06824 2.0224 2.57351 + vertex 1.07121 2.02198 2.57226 + endloop + endfacet + facet normal 0.382663 0.0963737 0.918848 + outer loop + vertex 1.07528 2.02809 2.56983 + vertex 1.07436 2.03312 2.56968 + vertex 1.07133 2.02992 2.57128 + endloop + endfacet + facet normal 0.388973 0.113679 0.914209 + outer loop + vertex 1.07219 2.026 2.5714 + vertex 1.07528 2.02809 2.56983 + vertex 1.07133 2.02992 2.57128 + endloop + endfacet + facet normal 0.37343 0.110504 0.921053 + outer loop + vertex 1.07133 2.02992 2.57128 + vertex 1.06845 2.02618 2.5729 + vertex 1.07219 2.026 2.5714 + endloop + endfacet + facet normal 0.184156 0.236529 0.954013 + outer loop + vertex 1.07216 2.0713 2.56336 + vertex 1.07189 2.07584 2.56228 + vertex 1.06893 2.07278 2.56361 + endloop + endfacet + facet normal 0.137924 0.399796 0.906168 + outer loop + vertex 1.07001 2.1148 2.55105 + vertex 1.07495 2.11379 2.55075 + vertex 1.07322 2.11763 2.54932 + endloop + endfacet + facet normal 0.116002 0.420712 0.899747 + outer loop + vertex 1.06783 2.11864 2.54954 + vertex 1.07001 2.1148 2.55105 + vertex 1.07322 2.11763 2.54932 + endloop + endfacet + facet normal 0.135209 0.340717 0.930392 + outer loop + vertex 1.07165 2.11087 2.55225 + vertex 1.07001 2.1148 2.55105 + vertex 1.06637 2.11183 2.55267 + endloop + endfacet + facet normal 0.126847 0.3379 0.932595 + outer loop + vertex 1.07495 2.11379 2.55075 + vertex 1.07001 2.1148 2.55105 + vertex 1.07165 2.11087 2.55225 + endloop + endfacet + facet normal 0.130898 0.511093 0.8495 + outer loop + vertex 1.07322 2.11763 2.54932 + vertex 1.07151 2.12098 2.54756 + vertex 1.06783 2.11864 2.54954 + endloop + endfacet + facet normal 0.0983121 0.546987 0.831348 + outer loop + vertex 1.06783 2.11864 2.54954 + vertex 1.07151 2.12098 2.54756 + vertex 1.06747 2.12181 2.54749 + endloop + endfacet + facet normal 0.103229 0.891729 0.440639 + outer loop + vertex 1.0748 2.125 2.54298 + vertex 1.0727 2.12665 2.54013 + vertex 1.07065 2.12585 2.54223 + endloop + endfacet + facet normal 0.0585482 0.821193 0.567639 + outer loop + vertex 1.07065 2.12585 2.54223 + vertex 1.06666 2.12575 2.54278 + vertex 1.0701 2.12387 2.54515 + endloop + endfacet + facet normal 0.0655983 0.8202 0.568303 + outer loop + vertex 1.07065 2.12585 2.54223 + vertex 1.0701 2.12387 2.54515 + vertex 1.0748 2.125 2.54298 + endloop + endfacet + facet normal 0.110061 0.763974 0.635791 + outer loop + vertex 1.0748 2.125 2.54298 + vertex 1.0701 2.12387 2.54515 + vertex 1.07423 2.12278 2.54574 + endloop + endfacet + facet normal 0.12569 0.671221 0.730524 + outer loop + vertex 1.07151 2.12098 2.54756 + vertex 1.0701 2.12387 2.54515 + vertex 1.06747 2.12181 2.54749 + endloop + endfacet + facet normal 0.0656524 0.65823 0.749949 + outer loop + vertex 1.07423 2.12278 2.54574 + vertex 1.0701 2.12387 2.54515 + vertex 1.07151 2.12098 2.54756 + endloop + endfacet + facet normal -0.0109426 0.547692 0.836608 + outer loop + vertex 1.075 2.13248 2.53 + vertex 1.07 2.13238 2.53 + vertex 1.07364 2.12935 2.53203 + endloop + endfacet + facet normal 0.109825 0.641102 0.759557 + outer loop + vertex 1.07364 2.12935 2.53203 + vertex 1.07 2.13238 2.53 + vertex 1.06864 2.12993 2.53226 + endloop + endfacet + facet normal 0.123813 0.923249 0.363706 + outer loop + vertex 1.07364 2.12935 2.53203 + vertex 1.06864 2.12993 2.53226 + vertex 1.07224 2.12793 2.53611 + endloop + endfacet + facet normal 0.109047 0.920212 0.375924 + outer loop + vertex 1.07224 2.12793 2.53611 + vertex 1.06864 2.12993 2.53226 + vertex 1.06733 2.12891 2.53514 + endloop + endfacet + facet normal 0.0359863 0.921608 0.386449 + outer loop + vertex 1.0727 2.12665 2.54013 + vertex 1.06818 2.12731 2.53896 + vertex 1.07065 2.12585 2.54223 + endloop + endfacet + facet normal 0.0636667 0.952708 0.297142 + outer loop + vertex 1.0727 2.12665 2.54013 + vertex 1.07224 2.12793 2.53611 + vertex 1.06818 2.12731 2.53896 + endloop + endfacet + facet normal 0.113001 0.92555 0.36137 + outer loop + vertex 1.07224 2.12793 2.53611 + vertex 1.06733 2.12891 2.53514 + vertex 1.06818 2.12731 2.53896 + endloop + endfacet + facet normal 0.031868 0.920636 0.38912 + outer loop + vertex 1.07065 2.12585 2.54223 + vertex 1.06818 2.12731 2.53896 + vertex 1.06666 2.12575 2.54278 + endloop + endfacet + facet normal 0.0104456 -0.0620304 -0.99802 + outer loop + vertex 1.08 0.894623 2.53 + vertex 1.07801 0.893693 2.53004 + vertex 1.075 0.893781 2.53 + endloop + endfacet + facet normal -0.0135823 -0.747014 -0.664669 + outer loop + vertex 1.07801 0.893693 2.53004 + vertex 1.0724 0.893351 2.53054 + vertex 1.075 0.893781 2.53 + endloop + endfacet + facet normal 0.0783115 -0.974041 0.212394 + outer loop + vertex 1.07801 0.893693 2.53004 + vertex 1.07531 0.89408 2.5328 + vertex 1.0724 0.893351 2.53054 + endloop + endfacet + facet normal 0.0636395 -0.978003 0.198646 + outer loop + vertex 1.07936 0.894222 2.53221 + vertex 1.07531 0.89408 2.5328 + vertex 1.07801 0.893693 2.53004 + endloop + endfacet + facet normal 0.0833263 -0.935823 0.34248 + outer loop + vertex 1.07531 0.89408 2.5328 + vertex 1.07936 0.894222 2.53221 + vertex 1.07856 0.895254 2.53522 + endloop + endfacet + facet normal 0.084392 -0.936185 0.341228 + outer loop + vertex 1.07365 0.89523 2.53637 + vertex 1.07531 0.89408 2.5328 + vertex 1.07856 0.895254 2.53522 + endloop + endfacet + facet normal 0.105114 -0.896472 0.430452 + outer loop + vertex 1.07856 0.895254 2.53522 + vertex 1.07729 0.897044 2.53926 + vertex 1.07365 0.89523 2.53637 + endloop + endfacet + facet normal 0.115321 -0.900212 0.419905 + outer loop + vertex 1.07729 0.897044 2.53926 + vertex 1.07167 0.896798 2.54028 + vertex 1.07365 0.89523 2.53637 + endloop + endfacet + facet normal 0.125326 -0.866484 0.483218 + outer loop + vertex 1.07729 0.897044 2.53926 + vertex 1.07449 0.898811 2.54316 + vertex 1.07167 0.896798 2.54028 + endloop + endfacet + facet normal 0.126894 -0.865798 0.484036 + outer loop + vertex 1.07881 0.898955 2.54228 + vertex 1.07449 0.898811 2.54316 + vertex 1.07729 0.897044 2.53926 + endloop + endfacet + facet normal 0.140857 -0.815726 0.561027 + outer loop + vertex 1.07449 0.898811 2.54316 + vertex 1.07881 0.898955 2.54228 + vertex 1.07787 0.901158 2.54572 + endloop + endfacet + facet normal 0.151908 -0.820621 0.550913 + outer loop + vertex 1.07175 0.900875 2.54699 + vertex 1.07449 0.898811 2.54316 + vertex 1.07787 0.901158 2.54572 + endloop + endfacet + facet normal 0.168631 -0.741465 0.649456 + outer loop + vertex 1.07787 0.901158 2.54572 + vertex 1.07493 0.903379 2.54902 + vertex 1.07175 0.900875 2.54699 + endloop + endfacet + facet normal 0.203477 -0.71849 0.665108 + outer loop + vertex 1.08003 0.904586 2.54876 + vertex 1.07493 0.903379 2.54902 + vertex 1.07787 0.901158 2.54572 + endloop + endfacet + facet normal 0.1779 -0.583531 0.792365 + outer loop + vertex 1.07493 0.903379 2.54902 + vertex 1.08003 0.904586 2.54876 + vertex 1.07669 0.906357 2.55081 + endloop + endfacet + facet normal 0.210077 -0.593343 0.777053 + outer loop + vertex 1.07305 0.90521 2.55092 + vertex 1.07493 0.903379 2.54902 + vertex 1.07669 0.906357 2.55081 + endloop + endfacet + facet normal 0.157075 -0.413369 0.896913 + outer loop + vertex 1.07669 0.906357 2.55081 + vertex 1.07399 0.908813 2.55242 + vertex 1.07305 0.90521 2.55092 + endloop + endfacet + facet normal 0.169376 -0.401826 0.899916 + outer loop + vertex 1.07912 0.909843 2.55191 + vertex 1.07399 0.908813 2.55242 + vertex 1.07669 0.906357 2.55081 + endloop + endfacet + facet normal 0.198522 -0.236405 0.951158 + outer loop + vertex 1.07859 0.944207 2.5618 + vertex 1.07382 0.943856 2.5627 + vertex 1.07426 0.940025 2.56166 + endloop + endfacet + facet normal 0.301277 -0.117497 0.94627 + outer loop + vertex 1.0769 0.988532 2.57147 + vertex 1.07701 0.992962 2.57198 + vertex 1.07293 0.98856 2.57274 + endloop + endfacet + facet normal 0.323488 -0.139876 0.935837 + outer loop + vertex 1.07293 0.98856 2.57274 + vertex 1.07701 0.992962 2.57198 + vertex 1.07308 0.993486 2.57342 + endloop + endfacet + facet normal 0.328383 -0.10955 0.93817 + outer loop + vertex 1.07701 0.992962 2.57198 + vertex 1.07727 0.99788 2.57247 + vertex 1.07308 0.993486 2.57342 + endloop + endfacet + facet normal 0.356229 -0.139188 0.923974 + outer loop + vertex 1.07308 0.993486 2.57342 + vertex 1.07727 0.99788 2.57247 + vertex 1.07346 0.998535 2.57404 + endloop + endfacet + facet normal 0.362819 -0.105387 0.925881 + outer loop + vertex 1.07727 0.99788 2.57247 + vertex 1.07764 1.00308 2.57291 + vertex 1.07346 0.998535 2.57404 + endloop + endfacet + facet normal 0.396628 -0.14114 0.907064 + outer loop + vertex 1.07346 0.998535 2.57404 + vertex 1.07764 1.00308 2.57291 + vertex 1.07377 1.00371 2.57471 + endloop + endfacet + facet normal 0.322507 -0.0823934 0.942974 + outer loop + vertex 1.07312 1.03873 2.57816 + vertex 1.07727 1.04285 2.5771 + vertex 1.0735 1.04393 2.57848 + endloop + endfacet + facet normal 0.319038 -0.0946289 0.943006 + outer loop + vertex 1.07727 1.04285 2.5771 + vertex 1.07825 1.04839 2.57732 + vertex 1.0735 1.04393 2.57848 + endloop + endfacet + facet normal 0.308113 -0.0817596 0.94783 + outer loop + vertex 1.0735 1.04393 2.57848 + vertex 1.07825 1.04839 2.57732 + vertex 1.07374 1.04908 2.57885 + endloop + endfacet + facet normal 0.305098 -0.0998226 0.947075 + outer loop + vertex 1.07825 1.04839 2.57732 + vertex 1.07797 1.05349 2.57795 + vertex 1.07374 1.04908 2.57885 + endloop + endfacet + facet normal 0.292003 -0.0861815 0.952527 + outer loop + vertex 1.07374 1.04908 2.57885 + vertex 1.07797 1.05349 2.57795 + vertex 1.07378 1.05413 2.57929 + endloop + endfacet + facet normal 0.0781564 -0.16102 0.983852 + outer loop + vertex 1.07911 1.15043 2.59096 + vertex 1.07467 1.14971 2.5912 + vertex 1.07606 1.14676 2.5906 + endloop + endfacet + facet normal 0.0815011 -0.0875265 0.992823 + outer loop + vertex 1.07845 1.1931 2.59714 + vertex 1.07823 1.19795 2.59758 + vertex 1.07326 1.19295 2.59755 + endloop + endfacet + facet normal 0.0875047 -0.0934899 0.991767 + outer loop + vertex 1.07326 1.19295 2.59755 + vertex 1.07823 1.19795 2.59758 + vertex 1.07313 1.19788 2.59803 + endloop + endfacet + facet normal 0.235973 0.13598 0.962199 + outer loop + vertex 1.07868 1.95364 2.57541 + vertex 1.0792 1.95843 2.5746 + vertex 1.07584 1.95556 2.57583 + endloop + endfacet + facet normal 0.239498 0.141561 0.960521 + outer loop + vertex 1.07584 1.95556 2.57583 + vertex 1.07534 1.95121 2.5766 + vertex 1.07868 1.95364 2.57541 + endloop + endfacet + facet normal 0.291105 0.133322 0.947356 + outer loop + vertex 1.07584 1.95556 2.57583 + vertex 1.07166 1.9561 2.57704 + vertex 1.07534 1.95121 2.5766 + endloop + endfacet + facet normal 0.244694 0.12546 0.961449 + outer loop + vertex 1.07476 1.95871 2.57569 + vertex 1.07584 1.95556 2.57583 + vertex 1.0792 1.95843 2.5746 + endloop + endfacet + facet normal 0.244704 0.125798 0.961402 + outer loop + vertex 1.07476 1.95871 2.57569 + vertex 1.0792 1.95843 2.5746 + vertex 1.07558 1.96305 2.57492 + endloop + endfacet + facet normal 0.258801 0.137188 0.956139 + outer loop + vertex 1.07558 1.96305 2.57492 + vertex 1.0792 1.95843 2.5746 + vertex 1.07953 1.96322 2.57382 + endloop + endfacet + facet normal 0.291711 0.141003 0.946056 + outer loop + vertex 1.07584 1.95556 2.57583 + vertex 1.07476 1.95871 2.57569 + vertex 1.07166 1.9561 2.57704 + endloop + endfacet + facet normal 0.258668 0.138917 0.955925 + outer loop + vertex 1.07953 1.96322 2.57382 + vertex 1.07852 1.96714 2.57353 + vertex 1.07558 1.96305 2.57492 + endloop + endfacet + facet normal 0.288351 0.115768 0.950501 + outer loop + vertex 1.07558 1.96305 2.57492 + vertex 1.07852 1.96714 2.57353 + vertex 1.07453 1.9685 2.57457 + endloop + endfacet + facet normal 0.293136 0.132761 0.946808 + outer loop + vertex 1.07852 1.96714 2.57353 + vertex 1.07771 1.9721 2.57308 + vertex 1.07453 1.9685 2.57457 + endloop + endfacet + facet normal 0.322624 0.104215 0.940773 + outer loop + vertex 1.07453 1.9685 2.57457 + vertex 1.07771 1.9721 2.57308 + vertex 1.07387 1.97353 2.57424 + endloop + endfacet + facet normal 0.329413 0.126591 0.935661 + outer loop + vertex 1.07771 1.9721 2.57308 + vertex 1.07652 1.97647 2.57291 + vertex 1.07387 1.97353 2.57424 + endloop + endfacet + facet normal 0.366052 0.0893159 0.926298 + outer loop + vertex 1.07387 1.97353 2.57424 + vertex 1.07652 1.97647 2.57291 + vertex 1.0735 1.97836 2.57392 + endloop + endfacet + facet normal 0.392458 0.0678274 0.917266 + outer loop + vertex 1.0735 1.97836 2.57392 + vertex 1.07694 1.98158 2.57221 + vertex 1.07295 1.98254 2.57385 + endloop + endfacet + facet normal 0.348234 0.108488 0.931109 + outer loop + vertex 1.07992 1.98408 2.57077 + vertex 1.08053 1.98818 2.57006 + vertex 1.07743 1.98634 2.57143 + endloop + endfacet + facet normal 0.353502 0.115119 0.928323 + outer loop + vertex 1.07743 1.98634 2.57143 + vertex 1.07694 1.98158 2.57221 + vertex 1.07992 1.98408 2.57077 + endloop + endfacet + facet normal 0.431996 0.101712 0.896122 + outer loop + vertex 1.07743 1.98634 2.57143 + vertex 1.07382 1.98704 2.5731 + vertex 1.07694 1.98158 2.57221 + endloop + endfacet + facet normal 0.394051 0.076847 0.91587 + outer loop + vertex 1.07382 1.98704 2.5731 + vertex 1.07295 1.98254 2.57385 + vertex 1.07694 1.98158 2.57221 + endloop + endfacet + facet normal 0.381873 0.101123 0.918666 + outer loop + vertex 1.08053 1.98818 2.57006 + vertex 1.07969 1.99341 2.56984 + vertex 1.07659 1.99061 2.57143 + endloop + endfacet + facet normal 0.367516 0.0730482 0.927144 + outer loop + vertex 1.07743 1.98634 2.57143 + vertex 1.08053 1.98818 2.57006 + vertex 1.07659 1.99061 2.57143 + endloop + endfacet + facet normal 0.430018 0.0853673 0.898775 + outer loop + vertex 1.07659 1.99061 2.57143 + vertex 1.07382 1.98704 2.5731 + vertex 1.07743 1.98634 2.57143 + endloop + endfacet + facet normal 0.45956 0.0565734 0.886343 + outer loop + vertex 1.07297 1.99281 2.57317 + vertex 1.07382 1.98704 2.5731 + vertex 1.07659 1.99061 2.57143 + endloop + endfacet + facet normal 0.420527 0.0671539 0.904791 + outer loop + vertex 1.07969 1.99341 2.56984 + vertex 1.07933 1.99836 2.56963 + vertex 1.07601 1.9957 2.57138 + endloop + endfacet + facet normal 0.41572 0.0574764 0.907675 + outer loop + vertex 1.07659 1.99061 2.57143 + vertex 1.07969 1.99341 2.56984 + vertex 1.07601 1.9957 2.57138 + endloop + endfacet + facet normal 0.462328 0.0625742 0.884498 + outer loop + vertex 1.07601 1.9957 2.57138 + vertex 1.07297 1.99281 2.57317 + vertex 1.07659 1.99061 2.57143 + endloop + endfacet + facet normal 0.482398 0.0357476 0.875222 + outer loop + vertex 1.07236 1.9984 2.57328 + vertex 1.07297 1.99281 2.57317 + vertex 1.07601 1.9957 2.57138 + endloop + endfacet + facet normal 0.440364 0.0477848 0.896547 + outer loop + vertex 1.07933 1.99836 2.56963 + vertex 1.07919 2.00322 2.56945 + vertex 1.07593 2.0006 2.57118 + endloop + endfacet + facet normal 0.437336 0.0419539 0.898319 + outer loop + vertex 1.07601 1.9957 2.57138 + vertex 1.07933 1.99836 2.56963 + vertex 1.07593 2.0006 2.57118 + endloop + endfacet + facet normal 0.485713 0.041699 0.873123 + outer loop + vertex 1.07593 2.0006 2.57118 + vertex 1.07236 1.9984 2.57328 + vertex 1.07601 1.9957 2.57138 + endloop + endfacet + facet normal 0.48755 0.0378989 0.872272 + outer loop + vertex 1.07337 2.00281 2.57252 + vertex 1.07236 1.9984 2.57328 + vertex 1.07593 2.0006 2.57118 + endloop + endfacet + facet normal 0.451695 0.0373244 0.891391 + outer loop + vertex 1.07919 2.00322 2.56945 + vertex 1.07921 2.00823 2.56923 + vertex 1.07597 2.00527 2.57099 + endloop + endfacet + facet normal 0.449756 0.0334335 0.892526 + outer loop + vertex 1.07593 2.0006 2.57118 + vertex 1.07919 2.00322 2.56945 + vertex 1.07597 2.00527 2.57099 + endloop + endfacet + facet normal 0.483952 0.0323803 0.874495 + outer loop + vertex 1.07597 2.00527 2.57099 + vertex 1.07337 2.00281 2.57252 + vertex 1.07593 2.0006 2.57118 + endloop + endfacet + facet normal 0.482424 0.0344755 0.875259 + outer loop + vertex 1.0728 2.00685 2.57268 + vertex 1.07337 2.00281 2.57252 + vertex 1.07597 2.00527 2.57099 + endloop + endfacet + facet normal 0.456382 0.0479279 0.888492 + outer loop + vertex 1.07921 2.00823 2.56923 + vertex 1.07896 2.01339 2.56907 + vertex 1.07576 2.01008 2.5709 + endloop + endfacet + facet normal 0.451916 0.037025 0.891292 + outer loop + vertex 1.07597 2.00527 2.57099 + vertex 1.07921 2.00823 2.56923 + vertex 1.07576 2.01008 2.5709 + endloop + endfacet + facet normal 0.483764 0.0381161 0.874368 + outer loop + vertex 1.07576 2.01008 2.5709 + vertex 1.0728 2.00685 2.57268 + vertex 1.07597 2.00527 2.57099 + endloop + endfacet + facet normal 0.471198 0.0529907 0.880434 + outer loop + vertex 1.07236 2.01172 2.57262 + vertex 1.0728 2.00685 2.57268 + vertex 1.07576 2.01008 2.5709 + endloop + endfacet + facet normal 0.454739 0.0549649 0.888927 + outer loop + vertex 1.07896 2.01339 2.56907 + vertex 1.07862 2.01853 2.56893 + vertex 1.07544 2.01508 2.57077 + endloop + endfacet + facet normal 0.453468 0.0514543 0.889786 + outer loop + vertex 1.07576 2.01008 2.5709 + vertex 1.07896 2.01339 2.56907 + vertex 1.07544 2.01508 2.57077 + endloop + endfacet + facet normal 0.470969 0.0523496 0.880595 + outer loop + vertex 1.07544 2.01508 2.57077 + vertex 1.07236 2.01172 2.57262 + vertex 1.07576 2.01008 2.5709 + endloop + endfacet + facet normal 0.45281 0.0734022 0.88858 + outer loop + vertex 1.07183 2.01679 2.57247 + vertex 1.07236 2.01172 2.57262 + vertex 1.07544 2.01508 2.57077 + endloop + endfacet + facet normal 0.446216 0.0589418 0.892982 + outer loop + vertex 1.07862 2.01853 2.56893 + vertex 1.07799 2.02394 2.56889 + vertex 1.07498 2.02004 2.57065 + endloop + endfacet + facet normal 0.447546 0.063253 0.892021 + outer loop + vertex 1.07544 2.01508 2.57077 + vertex 1.07862 2.01853 2.56893 + vertex 1.07498 2.02004 2.57065 + endloop + endfacet + facet normal 0.449276 0.0633927 0.891141 + outer loop + vertex 1.07498 2.02004 2.57065 + vertex 1.07183 2.01679 2.57247 + vertex 1.07544 2.01508 2.57077 + endloop + endfacet + facet normal 0.428192 0.0884022 0.899354 + outer loop + vertex 1.07121 2.02198 2.57226 + vertex 1.07183 2.01679 2.57247 + vertex 1.07498 2.02004 2.57065 + endloop + endfacet + facet normal 0.43325 0.0714333 0.898439 + outer loop + vertex 1.0744 2.02398 2.57062 + vertex 1.07498 2.02004 2.57065 + vertex 1.07799 2.02394 2.56889 + endloop + endfacet + facet normal 0.433075 0.0791365 0.897877 + outer loop + vertex 1.0744 2.02398 2.57062 + vertex 1.07799 2.02394 2.56889 + vertex 1.07528 2.02809 2.56983 + endloop + endfacet + facet normal 0.41559 0.0655708 0.907185 + outer loop + vertex 1.07528 2.02809 2.56983 + vertex 1.07799 2.02394 2.56889 + vertex 1.07874 2.02837 2.56823 + endloop + endfacet + facet normal 0.420704 0.0696593 0.90452 + outer loop + vertex 1.07498 2.02004 2.57065 + vertex 1.0744 2.02398 2.57062 + vertex 1.07121 2.02198 2.57226 + endloop + endfacet + facet normal 0.414853 0.0733431 0.906928 + outer loop + vertex 1.07874 2.02837 2.56823 + vertex 1.07754 2.03144 2.56853 + vertex 1.07528 2.02809 2.56983 + endloop + endfacet + facet normal 0.385923 0.0969243 0.917425 + outer loop + vertex 1.07528 2.02809 2.56983 + vertex 1.07754 2.03144 2.56853 + vertex 1.07436 2.03312 2.56968 + endloop + endfacet + facet normal 0.386806 0.0990034 0.916831 + outer loop + vertex 1.07754 2.03144 2.56853 + vertex 1.07813 2.03601 2.56778 + vertex 1.07436 2.03312 2.56968 + endloop + endfacet + facet normal 0.146868 0.378264 0.913973 + outer loop + vertex 1.07495 2.11379 2.55075 + vertex 1.07913 2.11274 2.55051 + vertex 1.07879 2.11647 2.54902 + endloop + endfacet + facet normal 0.130953 0.397416 0.908246 + outer loop + vertex 1.07322 2.11763 2.54932 + vertex 1.07495 2.11379 2.55075 + vertex 1.07879 2.11647 2.54902 + endloop + endfacet + facet normal 0.142186 0.322281 0.935905 + outer loop + vertex 1.07692 2.10947 2.55193 + vertex 1.07495 2.11379 2.55075 + vertex 1.07165 2.11087 2.55225 + endloop + endfacet + facet normal 0.133385 0.318946 0.93834 + outer loop + vertex 1.07913 2.11274 2.55051 + vertex 1.07495 2.11379 2.55075 + vertex 1.07692 2.10947 2.55193 + endloop + endfacet + facet normal 0.145904 0.480122 0.864983 + outer loop + vertex 1.07879 2.11647 2.54902 + vertex 1.07629 2.12025 2.54734 + vertex 1.07322 2.11763 2.54932 + endloop + endfacet + facet normal 0.116653 0.506379 0.854384 + outer loop + vertex 1.07322 2.11763 2.54932 + vertex 1.07629 2.12025 2.54734 + vertex 1.07151 2.12098 2.54756 + endloop + endfacet + facet normal 0.0664997 0.894645 0.441801 + outer loop + vertex 1.0748 2.125 2.54298 + vertex 1.08012 2.12507 2.54202 + vertex 1.07673 2.12662 2.53941 + endloop + endfacet + facet normal 0.0875532 0.888542 0.450364 + outer loop + vertex 1.0727 2.12665 2.54013 + vertex 1.0748 2.125 2.54298 + vertex 1.07673 2.12662 2.53941 + endloop + endfacet + facet normal 0.104275 0.761052 0.640256 + outer loop + vertex 1.08012 2.12507 2.54202 + vertex 1.0748 2.125 2.54298 + vertex 1.07851 2.12285 2.54493 + endloop + endfacet + facet normal 0.10852 0.764266 0.635705 + outer loop + vertex 1.07851 2.12285 2.54493 + vertex 1.0748 2.125 2.54298 + vertex 1.07423 2.12278 2.54574 + endloop + endfacet + facet normal 0.128062 0.602264 0.787958 + outer loop + vertex 1.07629 2.12025 2.54734 + vertex 1.07423 2.12278 2.54574 + vertex 1.07151 2.12098 2.54756 + endloop + endfacet + facet normal 0.138907 0.607428 0.782135 + outer loop + vertex 1.07851 2.12285 2.54493 + vertex 1.07423 2.12278 2.54574 + vertex 1.07629 2.12025 2.54734 + endloop + endfacet + facet normal 0.0396943 0.509143 0.859766 + outer loop + vertex 1.08 2.13209 2.53 + vertex 1.075 2.13248 2.53 + vertex 1.07872 2.12916 2.53179 + endloop + endfacet + facet normal 0.0591612 0.525128 0.848965 + outer loop + vertex 1.07872 2.12916 2.53179 + vertex 1.075 2.13248 2.53 + vertex 1.07364 2.12935 2.53203 + endloop + endfacet + facet normal 0.0519681 0.931542 0.359901 + outer loop + vertex 1.07872 2.12916 2.53179 + vertex 1.07364 2.12935 2.53203 + vertex 1.07782 2.12777 2.53551 + endloop + endfacet + facet normal 0.0638358 0.935525 0.347446 + outer loop + vertex 1.07782 2.12777 2.53551 + vertex 1.07364 2.12935 2.53203 + vertex 1.07224 2.12793 2.53611 + endloop + endfacet + facet normal 0.0605046 0.952793 0.297532 + outer loop + vertex 1.07673 2.12662 2.53941 + vertex 1.07224 2.12793 2.53611 + vertex 1.0727 2.12665 2.54013 + endloop + endfacet + facet normal 0.05914 0.952351 0.299215 + outer loop + vertex 1.07782 2.12777 2.53551 + vertex 1.07224 2.12793 2.53611 + vertex 1.07673 2.12662 2.53941 + endloop + endfacet + facet normal 0.0348016 0.951048 0.307078 + outer loop + vertex 1.08198 0.893999 2.53051 + vertex 1.085 0.894052 2.53 + vertex 1.08593 0.894108 2.52972 + endloop + endfacet + facet normal 0.0512525 -0.978026 0.202087 + outer loop + vertex 1.08198 0.893999 2.53051 + vertex 1.07801 0.893693 2.53004 + vertex 1.085 0.894052 2.53 + endloop + endfacet + facet normal -0.00364611 -0.03193 -0.999483 + outer loop + vertex 1.07801 0.893693 2.53004 + vertex 1.08 0.894623 2.53 + vertex 1.085 0.894052 2.53 + endloop + endfacet + facet normal 0.0506619 -0.977137 0.206488 + outer loop + vertex 1.08198 0.893999 2.53051 + vertex 1.07936 0.894222 2.53221 + vertex 1.07801 0.893693 2.53004 + endloop + endfacet + facet normal 0.0864984 -0.949196 0.302565 + outer loop + vertex 1.08593 0.894108 2.52972 + vertex 1.08332 0.895 2.53327 + vertex 1.08198 0.893999 2.53051 + endloop + endfacet + facet normal 0.108564 -0.95017 0.292218 + outer loop + vertex 1.07936 0.894222 2.53221 + vertex 1.08198 0.893999 2.53051 + vertex 1.08332 0.895 2.53327 + endloop + endfacet + facet normal 0.0915538 -0.934425 0.344192 + outer loop + vertex 1.07936 0.894222 2.53221 + vertex 1.08332 0.895 2.53327 + vertex 1.07856 0.895254 2.53522 + endloop + endfacet + facet normal 0.116948 -0.907865 0.402623 + outer loop + vertex 1.07856 0.895254 2.53522 + vertex 1.08332 0.895 2.53327 + vertex 1.08211 0.896621 2.53727 + endloop + endfacet + facet normal 0.104788 -0.878496 0.466116 + outer loop + vertex 1.08129 0.898099 2.54024 + vertex 1.08211 0.896621 2.53727 + vertex 1.08503 0.898165 2.53953 + endloop + endfacet + facet normal 0.116077 -0.876053 0.468036 + outer loop + vertex 1.08129 0.898099 2.54024 + vertex 1.07729 0.897044 2.53926 + vertex 1.08211 0.896621 2.53727 + endloop + endfacet + facet normal 0.0980212 -0.898009 0.428918 + outer loop + vertex 1.07729 0.897044 2.53926 + vertex 1.07856 0.895254 2.53522 + vertex 1.08211 0.896621 2.53727 + endloop + endfacet + facet normal 0.106686 -0.863597 0.492765 + outer loop + vertex 1.08129 0.898099 2.54024 + vertex 1.07881 0.898955 2.54228 + vertex 1.07729 0.897044 2.53926 + endloop + endfacet + facet normal 0.114792 -0.8456 0.521329 + outer loop + vertex 1.08503 0.898165 2.53953 + vertex 1.08286 0.899988 2.54296 + vertex 1.08129 0.898099 2.54024 + endloop + endfacet + facet normal 0.129736 -0.847802 0.514198 + outer loop + vertex 1.07881 0.898955 2.54228 + vertex 1.08129 0.898099 2.54024 + vertex 1.08286 0.899988 2.54296 + endloop + endfacet + facet normal 0.115727 -0.821706 0.558037 + outer loop + vertex 1.07881 0.898955 2.54228 + vertex 1.08286 0.899988 2.54296 + vertex 1.07787 0.901158 2.54572 + endloop + endfacet + facet normal 0.150147 -0.782861 0.603808 + outer loop + vertex 1.07787 0.901158 2.54572 + vertex 1.08286 0.899988 2.54296 + vertex 1.08255 0.902384 2.54614 + endloop + endfacet + facet normal 0.119347 -0.700168 0.703933 + outer loop + vertex 1.08255 0.902384 2.54614 + vertex 1.08003 0.904586 2.54876 + vertex 1.07787 0.901158 2.54572 + endloop + endfacet + facet normal 0.173708 -0.664753 0.726588 + outer loop + vertex 1.08522 0.904926 2.54783 + vertex 1.08003 0.904586 2.54876 + vertex 1.08255 0.902384 2.54614 + endloop + endfacet + facet normal 0.198483 -0.559275 0.80487 + outer loop + vertex 1.08021 0.907461 2.55071 + vertex 1.07669 0.906357 2.55081 + vertex 1.08003 0.904586 2.54876 + endloop + endfacet + facet normal 0.210098 -0.558417 0.802514 + outer loop + vertex 1.08021 0.907461 2.55071 + vertex 1.08003 0.904586 2.54876 + vertex 1.08366 0.907659 2.54995 + endloop + endfacet + facet normal 0.182789 -0.534798 0.824972 + outer loop + vertex 1.08366 0.907659 2.54995 + vertex 1.08003 0.904586 2.54876 + vertex 1.08522 0.904926 2.54783 + endloop + endfacet + facet normal 0.148313 -0.389965 0.908807 + outer loop + vertex 1.08021 0.907461 2.55071 + vertex 1.07912 0.909843 2.55191 + vertex 1.07669 0.906357 2.55081 + endloop + endfacet + facet normal 0.338996 -0.135317 0.931005 + outer loop + vertex 1.08218 0.973377 2.56684 + vertex 1.08237 0.977998 2.56744 + vertex 1.07823 0.973634 2.56831 + endloop + endfacet + facet normal 0.375364 -0.173913 0.910416 + outer loop + vertex 1.07823 0.973634 2.56831 + vertex 1.08237 0.977998 2.56744 + vertex 1.07836 0.979069 2.5693 + endloop + endfacet + facet normal 0.38796 -0.130286 0.912421 + outer loop + vertex 1.08237 0.977998 2.56744 + vertex 1.0829 0.983202 2.56796 + vertex 1.07836 0.979069 2.5693 + endloop + endfacet + facet normal 0.418063 -0.169833 0.892401 + outer loop + vertex 1.07836 0.979069 2.5693 + vertex 1.0829 0.983202 2.56796 + vertex 1.07976 0.984538 2.56968 + endloop + endfacet + facet normal 0.448596 -0.109652 0.886983 + outer loop + vertex 1.08192 1.01395 2.57194 + vertex 1.08251 1.01867 2.57222 + vertex 1.07884 1.01519 2.57365 + endloop + endfacet + facet normal 0.405763 -0.109859 0.907352 + outer loop + vertex 1.08354 1.02411 2.57242 + vertex 1.08337 1.02915 2.57311 + vertex 1.07966 1.02533 2.57431 + endloop + endfacet + facet normal 0.385085 -0.10893 0.91643 + outer loop + vertex 1.08349 1.03923 2.57425 + vertex 1.08007 1.03463 2.57514 + vertex 1.08353 1.03399 2.57361 + endloop + endfacet + facet normal 0.194623 -0.133265 0.971783 + outer loop + vertex 1.07817 1.09332 2.58258 + vertex 1.08316 1.09851 2.58229 + vertex 1.07815 1.09816 2.58324 + endloop + endfacet + facet normal 0.19537 -0.152128 0.968859 + outer loop + vertex 1.08316 1.09851 2.58229 + vertex 1.08318 1.10319 2.58302 + vertex 1.07815 1.09816 2.58324 + endloop + endfacet + facet normal 0.153184 -0.154743 0.976007 + outer loop + vertex 1.08376 1.1184 2.58526 + vertex 1.07872 1.11341 2.58526 + vertex 1.08338 1.11327 2.5845 + endloop + endfacet + facet normal 0.0741213 -0.157761 0.984692 + outer loop + vertex 1.0798 1.14794 2.59051 + vertex 1.07911 1.15043 2.59096 + vertex 1.07606 1.14676 2.5906 + endloop + endfacet + facet normal 0.081546 -0.155639 0.984442 + outer loop + vertex 1.08215 1.15057 2.59073 + vertex 1.07911 1.15043 2.59096 + vertex 1.0798 1.14794 2.59051 + endloop + endfacet + facet normal 0.0785704 -0.0800582 0.993689 + outer loop + vertex 1.08362 1.1932 2.59674 + vertex 1.08336 1.19802 2.59715 + vertex 1.07845 1.1931 2.59714 + endloop + endfacet + facet normal 0.0858404 -0.0872988 0.992477 + outer loop + vertex 1.07845 1.1931 2.59714 + vertex 1.08336 1.19802 2.59715 + vertex 1.07823 1.19795 2.59758 + endloop + endfacet + facet normal 0.274391 -0.0455391 0.960539 + outer loop + vertex 1.08141 1.42501 2.62034 + vertex 1.08152 1.42846 2.62048 + vertex 1.07876 1.42474 2.62109 + endloop + endfacet + facet normal 0.255372 -0.0454392 0.965775 + outer loop + vertex 1.08152 1.42846 2.62048 + vertex 1.08141 1.43291 2.62071 + vertex 1.07806 1.42837 2.62138 + endloop + endfacet + facet normal 0.26578 -0.0535697 0.962544 + outer loop + vertex 1.07806 1.42837 2.62138 + vertex 1.08141 1.43291 2.62071 + vertex 1.07786 1.43296 2.6217 + endloop + endfacet + facet normal 0.266039 -0.042985 0.963003 + outer loop + vertex 1.08141 1.43291 2.62071 + vertex 1.08142 1.43775 2.62093 + vertex 1.07786 1.43296 2.6217 + endloop + endfacet + facet normal 0.280049 -0.0541003 0.95846 + outer loop + vertex 1.07786 1.43296 2.6217 + vertex 1.08142 1.43775 2.62093 + vertex 1.07787 1.43787 2.62197 + endloop + endfacet + facet normal 0.280754 -0.0381259 0.959022 + outer loop + vertex 1.08142 1.43775 2.62093 + vertex 1.0815 1.44275 2.6211 + vertex 1.07787 1.43787 2.62197 + endloop + endfacet + facet normal 0.297304 -0.0514461 0.953396 + outer loop + vertex 1.07787 1.43787 2.62197 + vertex 1.0815 1.44275 2.6211 + vertex 1.07793 1.44289 2.62222 + endloop + endfacet + facet normal 0.298193 -0.0333041 0.953924 + outer loop + vertex 1.0815 1.44275 2.6211 + vertex 1.08157 1.44778 2.62125 + vertex 1.07793 1.44289 2.62222 + endloop + endfacet + facet normal 0.31686 -0.0485468 0.947229 + outer loop + vertex 1.07793 1.44289 2.62222 + vertex 1.08157 1.44778 2.62125 + vertex 1.07797 1.44792 2.62247 + endloop + endfacet + facet normal 0.317868 -0.0267366 0.947758 + outer loop + vertex 1.08157 1.44778 2.62125 + vertex 1.08159 1.45278 2.62139 + vertex 1.07797 1.44792 2.62247 + endloop + endfacet + facet normal 0.341322 -0.0462046 0.93881 + outer loop + vertex 1.07797 1.44792 2.62247 + vertex 1.08159 1.45278 2.62139 + vertex 1.07798 1.45292 2.62271 + endloop + endfacet + facet normal 0.342336 -0.0234881 0.939284 + outer loop + vertex 1.08159 1.45278 2.62139 + vertex 1.0816 1.45777 2.62151 + vertex 1.07798 1.45292 2.62271 + endloop + endfacet + facet normal 0.359903 -0.0383133 0.932203 + outer loop + vertex 1.07798 1.45292 2.62271 + vertex 1.0816 1.45777 2.62151 + vertex 1.07798 1.4579 2.62291 + endloop + endfacet + facet normal 0.360484 -0.0248635 0.932434 + outer loop + vertex 1.0816 1.45777 2.62151 + vertex 1.08162 1.46276 2.62164 + vertex 1.07798 1.4579 2.62291 + endloop + endfacet + facet normal 0.371561 -0.0343756 0.927772 + outer loop + vertex 1.07798 1.4579 2.62291 + vertex 1.08162 1.46276 2.62164 + vertex 1.07798 1.46289 2.6231 + endloop + endfacet + facet normal 0.372195 -0.0180884 0.927978 + outer loop + vertex 1.08162 1.46276 2.62164 + vertex 1.08162 1.46776 2.62173 + vertex 1.07798 1.46289 2.6231 + endloop + endfacet + facet normal 0.391984 -0.0353639 0.919292 + outer loop + vertex 1.07798 1.46289 2.6231 + vertex 1.08162 1.46776 2.62173 + vertex 1.078 1.46789 2.62328 + endloop + endfacet + facet normal 0.392677 -0.0190536 0.919479 + outer loop + vertex 1.08162 1.46776 2.62173 + vertex 1.08165 1.47275 2.62183 + vertex 1.078 1.46789 2.62328 + endloop + endfacet + facet normal 0.403262 -0.0284466 0.914642 + outer loop + vertex 1.078 1.46789 2.62328 + vertex 1.08165 1.47275 2.62183 + vertex 1.07801 1.47289 2.62343 + endloop + endfacet + facet normal 0.40376 -0.0162488 0.914721 + outer loop + vertex 1.08165 1.47275 2.62183 + vertex 1.08166 1.47774 2.62191 + vertex 1.07801 1.47289 2.62343 + endloop + endfacet + facet normal 0.42041 -0.0312733 0.906795 + outer loop + vertex 1.07801 1.47289 2.62343 + vertex 1.08166 1.47774 2.62191 + vertex 1.07804 1.47789 2.62359 + endloop + endfacet + facet normal 0.420881 -0.0206971 0.90688 + outer loop + vertex 1.08166 1.47774 2.62191 + vertex 1.08169 1.48273 2.62201 + vertex 1.07804 1.47789 2.62359 + endloop + endfacet + facet normal 0.426016 -0.02539 0.904359 + outer loop + vertex 1.07804 1.47789 2.62359 + vertex 1.08169 1.48273 2.62201 + vertex 1.07805 1.48286 2.62373 + endloop + endfacet + facet normal 0.426412 -0.014815 0.904408 + outer loop + vertex 1.08169 1.48273 2.62201 + vertex 1.0817 1.48771 2.62208 + vertex 1.07805 1.48286 2.62373 + endloop + endfacet + facet normal 0.435906 -0.0235671 0.899684 + outer loop + vertex 1.07805 1.48286 2.62373 + vertex 1.0817 1.48771 2.62208 + vertex 1.07806 1.48781 2.62385 + endloop + endfacet + facet normal 0.436328 -0.009328 0.899739 + outer loop + vertex 1.0817 1.48771 2.62208 + vertex 1.08172 1.49271 2.62213 + vertex 1.07806 1.48781 2.62385 + endloop + endfacet + facet normal 0.444734 -0.0171061 0.895499 + outer loop + vertex 1.07806 1.48781 2.62385 + vertex 1.08172 1.49271 2.62213 + vertex 1.07805 1.49274 2.62395 + endloop + endfacet + facet normal 0.444924 -0.0010981 0.895568 + outer loop + vertex 1.08172 1.49271 2.62213 + vertex 1.08173 1.49775 2.62213 + vertex 1.07805 1.49274 2.62395 + endloop + endfacet + facet normal 0.452822 -0.00836042 0.891562 + outer loop + vertex 1.07805 1.49274 2.62395 + vertex 1.08173 1.49775 2.62213 + vertex 1.07802 1.49769 2.62401 + endloop + endfacet + facet normal 0.452752 -0.00173648 0.891635 + outer loop + vertex 1.08173 1.49775 2.62213 + vertex 1.08173 1.50283 2.62214 + vertex 1.07802 1.49769 2.62401 + endloop + endfacet + facet normal 0.455517 -0.00424919 0.890217 + outer loop + vertex 1.07802 1.49769 2.62401 + vertex 1.08173 1.50283 2.62214 + vertex 1.07801 1.50266 2.62404 + endloop + endfacet + facet normal 0.4554 -0.000824456 0.890287 + outer loop + vertex 1.08173 1.50283 2.62214 + vertex 1.08174 1.5079 2.62214 + vertex 1.07801 1.50266 2.62404 + endloop + endfacet + facet normal 0.450453 0.00360671 0.892793 + outer loop + vertex 1.07801 1.50266 2.62404 + vertex 1.08174 1.5079 2.62214 + vertex 1.07798 1.50766 2.62403 + endloop + endfacet + facet normal 0.450708 -0.00143099 0.89267 + outer loop + vertex 1.08174 1.5079 2.62214 + vertex 1.08174 1.51291 2.62215 + vertex 1.07798 1.50766 2.62403 + endloop + endfacet + facet normal 0.446541 0.00229528 0.89476 + outer loop + vertex 1.07798 1.50766 2.62403 + vertex 1.08174 1.51291 2.62215 + vertex 1.07798 1.51268 2.62403 + endloop + endfacet + facet normal 0.446603 0.00106884 0.894731 + outer loop + vertex 1.08174 1.51291 2.62215 + vertex 1.08173 1.51785 2.62214 + vertex 1.07798 1.51268 2.62403 + endloop + endfacet + facet normal 0.441213 0.00594729 0.897382 + outer loop + vertex 1.07798 1.51268 2.62403 + vertex 1.08173 1.51785 2.62214 + vertex 1.07796 1.51769 2.624 + endloop + endfacet + facet normal 0.441141 0.00784244 0.897403 + outer loop + vertex 1.08173 1.51785 2.62214 + vertex 1.08172 1.52277 2.62211 + vertex 1.07796 1.51769 2.624 + endloop + endfacet + facet normal 0.440887 0.00807631 0.897526 + outer loop + vertex 1.07796 1.51769 2.624 + vertex 1.08172 1.52277 2.62211 + vertex 1.07796 1.5227 2.62396 + endloop + endfacet + facet normal 0.440939 0.00516699 0.897522 + outer loop + vertex 1.08172 1.52277 2.62211 + vertex 1.0817 1.52772 2.62209 + vertex 1.07796 1.5227 2.62396 + endloop + endfacet + facet normal 0.435295 0.0103768 0.900228 + outer loop + vertex 1.07796 1.5227 2.62396 + vertex 1.0817 1.52772 2.62209 + vertex 1.07796 1.5277 2.6239 + endloop + endfacet + facet normal 0.435347 0.00394816 0.900254 + outer loop + vertex 1.0817 1.52772 2.62209 + vertex 1.08169 1.53271 2.62207 + vertex 1.07796 1.5277 2.6239 + endloop + endfacet + facet normal 0.422266 0.0158844 0.906333 + outer loop + vertex 1.07796 1.5277 2.6239 + vertex 1.08169 1.53271 2.62207 + vertex 1.07798 1.53271 2.6238 + endloop + endfacet + facet normal 0.422274 0.0147995 0.906348 + outer loop + vertex 1.08169 1.53271 2.62207 + vertex 1.08167 1.53769 2.622 + vertex 1.07798 1.53271 2.6238 + endloop + endfacet + facet normal 0.414351 0.0219214 0.909853 + outer loop + vertex 1.07798 1.53271 2.6238 + vertex 1.08167 1.53769 2.622 + vertex 1.078 1.53772 2.62367 + endloop + endfacet + facet normal 0.414362 0.0177764 0.909939 + outer loop + vertex 1.08167 1.53769 2.622 + vertex 1.08166 1.5427 2.62191 + vertex 1.078 1.53772 2.62367 + endloop + endfacet + facet normal 0.409585 0.0220211 0.912006 + outer loop + vertex 1.078 1.53772 2.62367 + vertex 1.08166 1.5427 2.62191 + vertex 1.07802 1.54276 2.62354 + endloop + endfacet + facet normal 0.409564 0.01772 0.912109 + outer loop + vertex 1.08166 1.5427 2.62191 + vertex 1.08164 1.5477 2.62182 + vertex 1.07802 1.54276 2.62354 + endloop + endfacet + facet normal 0.399369 0.0266585 0.916403 + outer loop + vertex 1.07802 1.54276 2.62354 + vertex 1.08164 1.5477 2.62182 + vertex 1.07802 1.54779 2.62339 + endloop + endfacet + facet normal 0.3992 0.0122243 0.916782 + outer loop + vertex 1.08164 1.5477 2.62182 + vertex 1.08162 1.5527 2.62176 + vertex 1.07802 1.54779 2.62339 + endloop + endfacet + facet normal 0.382019 0.0271242 0.923756 + outer loop + vertex 1.07802 1.54779 2.62339 + vertex 1.08162 1.5527 2.62176 + vertex 1.07802 1.5528 2.62325 + endloop + endfacet + facet normal 0.381967 0.0232883 0.923882 + outer loop + vertex 1.08162 1.5527 2.62176 + vertex 1.08156 1.55765 2.62166 + vertex 1.07802 1.5528 2.62325 + endloop + endfacet + facet normal 0.375266 0.029015 0.926463 + outer loop + vertex 1.07802 1.5528 2.62325 + vertex 1.08156 1.55765 2.62166 + vertex 1.07801 1.55778 2.62309 + endloop + endfacet + facet normal 0.375278 0.0296613 0.926438 + outer loop + vertex 1.08156 1.55765 2.62166 + vertex 1.08151 1.56264 2.62152 + vertex 1.07801 1.55778 2.62309 + endloop + endfacet + facet normal 0.362476 0.0403909 0.931118 + outer loop + vertex 1.07801 1.55778 2.62309 + vertex 1.08151 1.56264 2.62152 + vertex 1.07798 1.56274 2.62289 + endloop + endfacet + facet normal 0.362483 0.0412522 0.931077 + outer loop + vertex 1.08151 1.56264 2.62152 + vertex 1.08148 1.56769 2.62131 + vertex 1.07798 1.56274 2.62289 + endloop + endfacet + facet normal 0.353476 0.04861 0.93418 + outer loop + vertex 1.07798 1.56274 2.62289 + vertex 1.08148 1.56769 2.62131 + vertex 1.07797 1.56772 2.62263 + endloop + endfacet + facet normal 0.353538 0.0382985 0.934636 + outer loop + vertex 1.08148 1.56769 2.62131 + vertex 1.08149 1.57276 2.6211 + vertex 1.07797 1.56772 2.62263 + endloop + endfacet + facet normal 0.340684 0.0485883 0.938921 + outer loop + vertex 1.07797 1.56772 2.62263 + vertex 1.08149 1.57276 2.6211 + vertex 1.07803 1.57276 2.62235 + endloop + endfacet + facet normal 0.340949 0.0300346 0.939602 + outer loop + vertex 1.08149 1.57276 2.6211 + vertex 1.08152 1.57777 2.62093 + vertex 1.07803 1.57276 2.62235 + endloop + endfacet + facet normal 0.308784 0.0552276 0.949528 + outer loop + vertex 1.07803 1.57276 2.62235 + vertex 1.08152 1.57777 2.62093 + vertex 1.07804 1.57778 2.62206 + endloop + endfacet + facet normal 0.309034 0.0321503 0.950508 + outer loop + vertex 1.08152 1.57777 2.62093 + vertex 1.08134 1.58267 2.62082 + vertex 1.07804 1.57778 2.62206 + endloop + endfacet + facet normal 0.266037 0.0640362 0.961834 + outer loop + vertex 1.07804 1.57778 2.62206 + vertex 1.08134 1.58267 2.62082 + vertex 1.07772 1.58264 2.62182 + endloop + endfacet + facet normal 0.266418 0.0481844 0.962652 + outer loop + vertex 1.08134 1.58267 2.62082 + vertex 1.0804 1.58771 2.62083 + vertex 1.07772 1.58264 2.62182 + endloop + endfacet + facet normal 0.0606216 0.0977129 0.993367 + outer loop + vertex 1.08338 1.72228 2.60754 + vertex 1.08299 1.72723 2.60708 + vertex 1.07837 1.72211 2.60786 + endloop + endfacet + facet normal 0.272554 0.143217 0.951422 + outer loop + vertex 1.08388 1.97878 2.57037 + vertex 1.08412 1.98348 2.56959 + vertex 1.08106 1.98085 2.57086 + endloop + endfacet + facet normal 0.271603 0.141809 0.951904 + outer loop + vertex 1.08106 1.98085 2.57086 + vertex 1.08057 1.97641 2.57167 + vertex 1.08388 1.97878 2.57037 + endloop + endfacet + facet normal 0.329475 0.132261 0.934855 + outer loop + vertex 1.08106 1.98085 2.57086 + vertex 1.07694 1.98158 2.57221 + vertex 1.08057 1.97641 2.57167 + endloop + endfacet + facet normal 0.284567 0.128577 0.949994 + outer loop + vertex 1.07992 1.98408 2.57077 + vertex 1.08106 1.98085 2.57086 + vertex 1.08412 1.98348 2.56959 + endloop + endfacet + facet normal 0.283884 0.121587 0.951119 + outer loop + vertex 1.07992 1.98408 2.57077 + vertex 1.08412 1.98348 2.56959 + vertex 1.08053 1.98818 2.57006 + endloop + endfacet + facet normal 0.311734 0.144044 0.939188 + outer loop + vertex 1.08053 1.98818 2.57006 + vertex 1.08412 1.98348 2.56959 + vertex 1.08423 1.98806 2.56885 + endloop + endfacet + facet normal 0.33087 0.144492 0.932549 + outer loop + vertex 1.08106 1.98085 2.57086 + vertex 1.07992 1.98408 2.57077 + vertex 1.07694 1.98158 2.57221 + endloop + endfacet + facet normal 0.31195 0.129649 0.941211 + outer loop + vertex 1.08423 1.98806 2.56885 + vertex 1.08293 1.99139 2.56883 + vertex 1.08053 1.98818 2.57006 + endloop + endfacet + facet normal 0.351055 0.0966811 0.93135 + outer loop + vertex 1.08053 1.98818 2.57006 + vertex 1.08293 1.99139 2.56883 + vertex 1.07969 1.99341 2.56984 + endloop + endfacet + facet normal 0.348514 0.0918955 0.932788 + outer loop + vertex 1.08293 1.99139 2.56883 + vertex 1.08387 1.99634 2.56799 + vertex 1.07969 1.99341 2.56984 + endloop + endfacet + facet normal 0.366016 0.064208 0.928391 + outer loop + vertex 1.07969 1.99341 2.56984 + vertex 1.08387 1.99634 2.56799 + vertex 1.07933 1.99836 2.56963 + endloop + endfacet + facet normal 0.372705 0.0826293 0.924264 + outer loop + vertex 1.08387 1.99634 2.56799 + vertex 1.08215 2.00109 2.56825 + vertex 1.07933 1.99836 2.56963 + endloop + endfacet + facet normal 0.402016 0.0473505 0.914407 + outer loop + vertex 1.07933 1.99836 2.56963 + vertex 1.08215 2.00109 2.56825 + vertex 1.07919 2.00322 2.56945 + endloop + endfacet + facet normal 0.400158 0.0442093 0.915379 + outer loop + vertex 1.08215 2.00109 2.56825 + vertex 1.08311 2.00595 2.5676 + vertex 1.07919 2.00322 2.56945 + endloop + endfacet + facet normal 0.403545 0.0385268 0.914148 + outer loop + vertex 1.07919 2.00322 2.56945 + vertex 1.08311 2.00595 2.5676 + vertex 1.07921 2.00823 2.56923 + endloop + endfacet + facet normal 0.412431 0.0572195 0.90919 + outer loop + vertex 1.08311 2.00595 2.5676 + vertex 1.08259 2.01159 2.56748 + vertex 1.07921 2.00823 2.56923 + endloop + endfacet + facet normal 0.421069 0.0467462 0.905823 + outer loop + vertex 1.07921 2.00823 2.56923 + vertex 1.08259 2.01159 2.56748 + vertex 1.07896 2.01339 2.56907 + endloop + endfacet + facet normal 0.427102 0.0622261 0.90206 + outer loop + vertex 1.08259 2.01159 2.56748 + vertex 1.08224 2.01679 2.56729 + vertex 1.07896 2.01339 2.56907 + endloop + endfacet + facet normal 0.434203 0.0538657 0.899203 + outer loop + vertex 1.07896 2.01339 2.56907 + vertex 1.08224 2.01679 2.56729 + vertex 1.07862 2.01853 2.56893 + endloop + endfacet + facet normal 0.437113 0.0617485 0.897284 + outer loop + vertex 1.08224 2.01679 2.56729 + vertex 1.08187 2.02185 2.56712 + vertex 1.07862 2.01853 2.56893 + endloop + endfacet + facet normal 0.44002 0.0582567 0.896096 + outer loop + vertex 1.07862 2.01853 2.56893 + vertex 1.08187 2.02185 2.56712 + vertex 1.07799 2.02394 2.56889 + endloop + endfacet + facet normal 0.440158 0.058588 0.896007 + outer loop + vertex 1.08187 2.02185 2.56712 + vertex 1.08159 2.02672 2.56694 + vertex 1.07799 2.02394 2.56889 + endloop + endfacet + facet normal 0.439275 0.059971 0.896349 + outer loop + vertex 1.07799 2.02394 2.56889 + vertex 1.08159 2.02672 2.56694 + vertex 1.07874 2.02837 2.56823 + endloop + endfacet + facet normal 0.441558 0.0650673 0.89487 + outer loop + vertex 1.08159 2.02672 2.56694 + vertex 1.08097 2.03163 2.56689 + vertex 1.07874 2.02837 2.56823 + endloop + endfacet + facet normal 0.426055 0.0782718 0.901305 + outer loop + vertex 1.07874 2.02837 2.56823 + vertex 1.08097 2.03163 2.56689 + vertex 1.07754 2.03144 2.56853 + endloop + endfacet + facet normal 0.451133 0.0851726 0.888383 + outer loop + vertex 1.08408 2.03347 2.5652 + vertex 1.08503 2.03779 2.5643 + vertex 1.08187 2.03579 2.5661 + endloop + endfacet + facet normal 0.44194 0.0742877 0.893963 + outer loop + vertex 1.08187 2.03579 2.5661 + vertex 1.08097 2.03163 2.56689 + vertex 1.08408 2.03347 2.5652 + endloop + endfacet + facet normal 0.413749 0.0828396 0.906614 + outer loop + vertex 1.08187 2.03579 2.5661 + vertex 1.07813 2.03601 2.56778 + vertex 1.08097 2.03163 2.56689 + endloop + endfacet + facet normal 0.424987 0.0913464 0.900579 + outer loop + vertex 1.07813 2.03601 2.56778 + vertex 1.07754 2.03144 2.56853 + vertex 1.08097 2.03163 2.56689 + endloop + endfacet + facet normal 0.366725 0.140549 0.919651 + outer loop + vertex 1.07878 2.0535 2.56527 + vertex 1.07977 2.04955 2.56548 + vertex 1.0825 2.05352 2.56379 + endloop + endfacet + facet normal 0.365148 0.165825 0.916062 + outer loop + vertex 1.07878 2.0535 2.56527 + vertex 1.0825 2.05352 2.56379 + vertex 1.07905 2.05813 2.56433 + endloop + endfacet + facet normal 0.328923 0.131858 0.935106 + outer loop + vertex 1.07977 2.04955 2.56548 + vertex 1.07878 2.0535 2.56527 + vertex 1.07555 2.05122 2.56673 + endloop + endfacet + facet normal 0.173599 0.325403 0.929503 + outer loop + vertex 1.07913 2.11274 2.55051 + vertex 1.08121 2.1101 2.55105 + vertex 1.08381 2.11306 2.54952 + endloop + endfacet + facet normal 0.165944 0.378611 0.910558 + outer loop + vertex 1.07913 2.11274 2.55051 + vertex 1.08381 2.11306 2.54952 + vertex 1.07879 2.11647 2.54902 + endloop + endfacet + facet normal 0.147846 0.353801 0.923562 + outer loop + vertex 1.07879 2.11647 2.54902 + vertex 1.08381 2.11306 2.54952 + vertex 1.08263 2.11675 2.5483 + endloop + endfacet + facet normal 0.149511 0.308503 0.9394 + outer loop + vertex 1.08121 2.1101 2.55105 + vertex 1.07913 2.11274 2.55051 + vertex 1.07692 2.10947 2.55193 + endloop + endfacet + facet normal 0.128675 0.47672 0.869586 + outer loop + vertex 1.08263 2.11675 2.5483 + vertex 1.08174 2.11973 2.54679 + vertex 1.07879 2.11647 2.54902 + endloop + endfacet + facet normal 0.132626 0.473829 0.870572 + outer loop + vertex 1.07879 2.11647 2.54902 + vertex 1.08174 2.11973 2.54679 + vertex 1.07629 2.12025 2.54734 + endloop + endfacet + facet normal 0.0575984 0.895997 0.440309 + outer loop + vertex 1.08012 2.12507 2.54202 + vertex 1.08444 2.1252 2.54121 + vertex 1.08166 2.12655 2.53881 + endloop + endfacet + facet normal 0.0652408 0.894092 0.443106 + outer loop + vertex 1.07673 2.12662 2.53941 + vertex 1.08012 2.12507 2.54202 + vertex 1.08166 2.12655 2.53881 + endloop + endfacet + facet normal 0.0983865 0.763936 0.637748 + outer loop + vertex 1.08444 2.1252 2.54121 + vertex 1.08012 2.12507 2.54202 + vertex 1.08404 2.12295 2.54396 + endloop + endfacet + facet normal 0.0977507 0.763417 0.638466 + outer loop + vertex 1.08404 2.12295 2.54396 + vertex 1.08012 2.12507 2.54202 + vertex 1.07851 2.12285 2.54493 + endloop + endfacet + facet normal 0.13661 0.60879 0.781481 + outer loop + vertex 1.08174 2.11973 2.54679 + vertex 1.07851 2.12285 2.54493 + vertex 1.07629 2.12025 2.54734 + endloop + endfacet + facet normal 0.126808 0.602524 0.787963 + outer loop + vertex 1.08404 2.12295 2.54396 + vertex 1.07851 2.12285 2.54493 + vertex 1.08174 2.11973 2.54679 + endloop + endfacet + facet normal -0.0100955 0.459257 0.888246 + outer loop + vertex 1.085 2.1322 2.53 + vertex 1.08 2.13209 2.53 + vertex 1.08369 2.12901 2.53164 + endloop + endfacet + facet normal 0.0430576 0.507993 0.860284 + outer loop + vertex 1.08369 2.12901 2.53164 + vertex 1.08 2.13209 2.53 + vertex 1.07872 2.12916 2.53179 + endloop + endfacet + facet normal 0.04039 0.926185 0.374901 + outer loop + vertex 1.08369 2.12901 2.53164 + vertex 1.07872 2.12916 2.53179 + vertex 1.08294 2.12759 2.53522 + endloop + endfacet + facet normal 0.0541181 0.931259 0.360316 + outer loop + vertex 1.08294 2.12759 2.53522 + vertex 1.07872 2.12916 2.53179 + vertex 1.07782 2.12777 2.53551 + endloop + endfacet + facet normal 0.0484305 0.953764 0.296627 + outer loop + vertex 1.08166 2.12655 2.53881 + vertex 1.07782 2.12777 2.53551 + vertex 1.07673 2.12662 2.53941 + endloop + endfacet + facet normal 0.0511265 0.954508 0.293768 + outer loop + vertex 1.08294 2.12759 2.53522 + vertex 1.07782 2.12777 2.53551 + vertex 1.08166 2.12655 2.53881 + endloop + endfacet + facet normal -0.300918 -0.911454 -0.280534 + outer loop + vertex 1.08679 0.895 2.525 + vertex 1.085 0.894052 2.53 + vertex 1.085 0.895 2.52692 + endloop + endfacet + facet normal -0.295953 -0.913504 -0.279145 + outer loop + vertex 1.08679 0.895 2.525 + vertex 1.09 0.89396 2.525 + vertex 1.085 0.894052 2.53 + endloop + endfacet + facet normal -0.62541 -0.47816 -0.616624 + outer loop + vertex 1.09 0.89396 2.525 + vertex 1.08838 0.893678 2.52686 + vertex 1.085 0.894052 2.53 + endloop + endfacet + facet normal 0.135204 -0.956201 0.259615 + outer loop + vertex 1.08838 0.893678 2.52686 + vertex 1.08593 0.894108 2.52972 + vertex 1.085 0.894052 2.53 + endloop + endfacet + facet normal 0.032427 -0.983895 0.17578 + outer loop + vertex 1.09046 0.89405 2.52856 + vertex 1.08593 0.894108 2.52972 + vertex 1.08838 0.893678 2.52686 + endloop + endfacet + facet normal 0.0668288 -0.949037 0.307999 + outer loop + vertex 1.08593 0.894108 2.52972 + vertex 1.09046 0.89405 2.52856 + vertex 1.08865 0.895136 2.5323 + endloop + endfacet + facet normal 0.0782008 -0.95165 0.297063 + outer loop + vertex 1.08332 0.895 2.53327 + vertex 1.08593 0.894108 2.52972 + vertex 1.08865 0.895136 2.5323 + endloop + endfacet + facet normal 0.0951793 -0.913424 0.395725 + outer loop + vertex 1.08865 0.895136 2.5323 + vertex 1.08678 0.896586 2.5361 + vertex 1.08332 0.895 2.53327 + endloop + endfacet + facet normal 0.0934088 -0.912814 0.397548 + outer loop + vertex 1.08678 0.896586 2.5361 + vertex 1.08211 0.896621 2.53727 + vertex 1.08332 0.895 2.53327 + endloop + endfacet + facet normal 0.109669 -0.880503 0.46118 + outer loop + vertex 1.08678 0.896586 2.5361 + vertex 1.08503 0.898165 2.53953 + vertex 1.08211 0.896621 2.53727 + endloop + endfacet + facet normal 0.0958152 -0.884766 0.45608 + outer loop + vertex 1.08951 0.898339 2.53892 + vertex 1.08503 0.898165 2.53953 + vertex 1.08678 0.896586 2.5361 + endloop + endfacet + facet normal 0.101304 -0.857292 0.504765 + outer loop + vertex 1.08503 0.898165 2.53953 + vertex 1.08951 0.898339 2.53892 + vertex 1.08726 0.899728 2.54173 + endloop + endfacet + facet normal 0.0922655 -0.854202 0.51169 + outer loop + vertex 1.08286 0.899988 2.54296 + vertex 1.08503 0.898165 2.53953 + vertex 1.08726 0.899728 2.54173 + endloop + endfacet + facet normal 0.119634 -0.793327 0.596926 + outer loop + vertex 1.08726 0.899728 2.54173 + vertex 1.08716 0.902056 2.54485 + vertex 1.08286 0.899988 2.54296 + endloop + endfacet + facet normal 0.113977 -0.788437 0.604463 + outer loop + vertex 1.08716 0.902056 2.54485 + vertex 1.08255 0.902384 2.54614 + vertex 1.08286 0.899988 2.54296 + endloop + endfacet + facet normal 0.160437 -0.657319 0.736336 + outer loop + vertex 1.08716 0.902056 2.54485 + vertex 1.08522 0.904926 2.54783 + vertex 1.08255 0.902384 2.54614 + endloop + endfacet + facet normal 0.152435 -0.661045 0.7347 + outer loop + vertex 1.08986 0.905142 2.54706 + vertex 1.08522 0.904926 2.54783 + vertex 1.08716 0.902056 2.54485 + endloop + endfacet + facet normal 0.165967 -0.457907 0.87337 + outer loop + vertex 1.08986 0.905142 2.54706 + vertex 1.08884 0.909001 2.54928 + vertex 1.08522 0.904926 2.54783 + endloop + endfacet + facet normal 0.238131 -0.506271 0.828845 + outer loop + vertex 1.08522 0.904926 2.54783 + vertex 1.08884 0.909001 2.54928 + vertex 1.08366 0.907659 2.54995 + endloop + endfacet + facet normal 0.338786 -0.138073 0.930677 + outer loop + vertex 1.08743 0.958207 2.56204 + vertex 1.08842 0.963798 2.56251 + vertex 1.08349 0.958749 2.56356 + endloop + endfacet + facet normal 0.37756 -0.180646 0.908194 + outer loop + vertex 1.08349 0.958749 2.56356 + vertex 1.08842 0.963798 2.56251 + vertex 1.08373 0.964164 2.56453 + endloop + endfacet + facet normal 0.382338 -0.144238 0.912695 + outer loop + vertex 1.08842 0.963798 2.56251 + vertex 1.08831 0.968974 2.56337 + vertex 1.08373 0.964164 2.56453 + endloop + endfacet + facet normal 0.414762 -0.180084 0.891932 + outer loop + vertex 1.08373 0.964164 2.56453 + vertex 1.08831 0.968974 2.56337 + vertex 1.085 0.96954 2.56503 + endloop + endfacet + facet normal 0.424129 -0.135479 0.895411 + outer loop + vertex 1.08837 0.974212 2.56414 + vertex 1.085 0.96954 2.56503 + vertex 1.08831 0.968974 2.56337 + endloop + endfacet + facet normal 0.439013 -0.0896839 0.893994 + outer loop + vertex 1.08448 1.01309 2.57055 + vertex 1.08219 1.01057 2.57142 + vertex 1.08491 1.00982 2.57001 + endloop + endfacet + facet normal 0.401639 -0.0973794 0.910606 + outer loop + vertex 1.08448 1.01309 2.57055 + vertex 1.08491 1.00982 2.57001 + vertex 1.08828 1.01433 2.569 + endloop + endfacet + facet normal 0.410387 -0.104955 0.905851 + outer loop + vertex 1.08828 1.01433 2.569 + vertex 1.08491 1.00982 2.57001 + vertex 1.08845 1.00906 2.56832 + endloop + endfacet + facet normal 0.449005 -0.100966 0.887806 + outer loop + vertex 1.08448 1.01309 2.57055 + vertex 1.08192 1.01395 2.57194 + vertex 1.08219 1.01057 2.57142 + endloop + endfacet + facet normal 0.398609 -0.121137 0.909086 + outer loop + vertex 1.08828 1.01433 2.569 + vertex 1.08938 1.02001 2.56928 + vertex 1.08541 1.0169 2.5706 + endloop + endfacet + facet normal 0.405258 -0.112585 0.907244 + outer loop + vertex 1.08448 1.01309 2.57055 + vertex 1.08828 1.01433 2.569 + vertex 1.08541 1.0169 2.5706 + endloop + endfacet + facet normal 0.442488 -0.12141 0.888518 + outer loop + vertex 1.08541 1.0169 2.5706 + vertex 1.08192 1.01395 2.57194 + vertex 1.08448 1.01309 2.57055 + endloop + endfacet + facet normal 0.433678 -0.108216 0.894546 + outer loop + vertex 1.08251 1.01867 2.57222 + vertex 1.08192 1.01395 2.57194 + vertex 1.08541 1.0169 2.5706 + endloop + endfacet + facet normal 0.398395 -0.120805 0.909224 + outer loop + vertex 1.08541 1.0169 2.5706 + vertex 1.08938 1.02001 2.56928 + vertex 1.08625 1.02158 2.57086 + endloop + endfacet + facet normal 0.424745 -0.12483 0.896665 + outer loop + vertex 1.08625 1.02158 2.57086 + vertex 1.08251 1.01867 2.57222 + vertex 1.08541 1.0169 2.5706 + endloop + endfacet + facet normal 0.246749 -0.141572 0.958683 + outer loop + vertex 1.08842 1.08378 2.5787 + vertex 1.0887 1.08887 2.57938 + vertex 1.08442 1.08478 2.57987 + endloop + endfacet + facet normal 0.229912 -0.123175 0.965385 + outer loop + vertex 1.08442 1.08478 2.57987 + vertex 1.0887 1.08887 2.57938 + vertex 1.08504 1.08943 2.58032 + endloop + endfacet + facet normal 0.243794 -0.142433 0.959311 + outer loop + vertex 1.08523 1.09264 2.58075 + vertex 1.08254 1.09016 2.58106 + vertex 1.08504 1.08943 2.58032 + endloop + endfacet + facet normal 0.210261 -0.141488 0.967353 + outer loop + vertex 1.08523 1.09264 2.58075 + vertex 1.08504 1.08943 2.58032 + vertex 1.08884 1.09376 2.58013 + endloop + endfacet + facet normal 0.224372 -0.154108 0.962241 + outer loop + vertex 1.08884 1.09376 2.58013 + vertex 1.08504 1.08943 2.58032 + vertex 1.0887 1.08887 2.57938 + endloop + endfacet + facet normal 0.256688 -0.157114 0.953638 + outer loop + vertex 1.08523 1.09264 2.58075 + vertex 1.08319 1.09397 2.58152 + vertex 1.08254 1.09016 2.58106 + endloop + endfacet + facet normal 0.214859 -0.158413 0.963712 + outer loop + vertex 1.08884 1.09376 2.58013 + vertex 1.08698 1.0955 2.58083 + vertex 1.08523 1.09264 2.58075 + endloop + endfacet + facet normal 0.244303 -0.176176 0.953561 + outer loop + vertex 1.08698 1.0955 2.58083 + vertex 1.08319 1.09397 2.58152 + vertex 1.08523 1.09264 2.58075 + endloop + endfacet + facet normal 0.25261 -0.199947 0.946683 + outer loop + vertex 1.08698 1.0955 2.58083 + vertex 1.08809 1.09914 2.5813 + vertex 1.08319 1.09397 2.58152 + endloop + endfacet + facet normal 0.339923 -0.0307382 0.939951 + outer loop + vertex 1.08719 1.3622 2.61306 + vertex 1.08721 1.36739 2.61322 + vertex 1.08321 1.36299 2.61453 + endloop + endfacet + facet normal 0.401223 -0.0948926 0.911052 + outer loop + vertex 1.08321 1.36299 2.61453 + vertex 1.08721 1.36739 2.61322 + vertex 1.08337 1.36823 2.615 + endloop + endfacet + facet normal 0.337547 -0.130787 0.932179 + outer loop + vertex 1.08407 1.37233 2.61533 + vertex 1.08183 1.37024 2.61584 + vertex 1.08337 1.36823 2.615 + endloop + endfacet + facet normal 0.526151 -0.155195 0.83611 + outer loop + vertex 1.08407 1.37233 2.61533 + vertex 1.08337 1.36823 2.615 + vertex 1.08722 1.37321 2.61351 + endloop + endfacet + facet normal 0.411715 -0.0446227 0.910219 + outer loop + vertex 1.08722 1.37321 2.61351 + vertex 1.08337 1.36823 2.615 + vertex 1.08721 1.36739 2.61322 + endloop + endfacet + facet normal 0.287329 -0.0711494 0.955186 + outer loop + vertex 1.08407 1.37233 2.61533 + vertex 1.08184 1.37327 2.61607 + vertex 1.08183 1.37024 2.61584 + endloop + endfacet + facet normal 0.56127 -0.0331428 0.826969 + outer loop + vertex 1.08722 1.37321 2.61351 + vertex 1.08805 1.37929 2.61319 + vertex 1.08497 1.37625 2.61516 + endloop + endfacet + facet normal 0.515341 -0.0815219 0.853099 + outer loop + vertex 1.08407 1.37233 2.61533 + vertex 1.08722 1.37321 2.61351 + vertex 1.08497 1.37625 2.61516 + endloop + endfacet + facet normal 0.304089 -0.0288979 0.952205 + outer loop + vertex 1.08497 1.37625 2.61516 + vertex 1.08184 1.37327 2.61607 + vertex 1.08407 1.37233 2.61533 + endloop + endfacet + facet normal 0.325533 -0.0538671 0.943995 + outer loop + vertex 1.08192 1.37745 2.61628 + vertex 1.08184 1.37327 2.61607 + vertex 1.08497 1.37625 2.61516 + endloop + endfacet + facet normal 0.583133 -0.0272023 0.811921 + outer loop + vertex 1.08805 1.37929 2.61319 + vertex 1.0882 1.38462 2.61326 + vertex 1.08532 1.38118 2.61521 + endloop + endfacet + facet normal 0.572373 -0.0498632 0.818476 + outer loop + vertex 1.08497 1.37625 2.61516 + vertex 1.08805 1.37929 2.61319 + vertex 1.08532 1.38118 2.61521 + endloop + endfacet + facet normal 0.332718 -0.034241 0.942405 + outer loop + vertex 1.08532 1.38118 2.61521 + vertex 1.08192 1.37745 2.61628 + vertex 1.08497 1.37625 2.61516 + endloop + endfacet + facet normal 0.36064 -0.0630656 0.93057 + outer loop + vertex 1.082 1.3823 2.61657 + vertex 1.08192 1.37745 2.61628 + vertex 1.08532 1.38118 2.61521 + endloop + endfacet + facet normal 0.603171 -0.0140264 0.797489 + outer loop + vertex 1.0882 1.38462 2.61326 + vertex 1.08822 1.38968 2.61333 + vertex 1.08543 1.38623 2.61538 + endloop + endfacet + facet normal 0.593104 -0.0400184 0.804131 + outer loop + vertex 1.08532 1.38118 2.61521 + vertex 1.0882 1.38462 2.61326 + vertex 1.08543 1.38623 2.61538 + endloop + endfacet + facet normal 0.368024 -0.0392697 0.928987 + outer loop + vertex 1.08543 1.38623 2.61538 + vertex 1.082 1.3823 2.61657 + vertex 1.08532 1.38118 2.61521 + endloop + endfacet + facet normal 0.392126 -0.0636145 0.917709 + outer loop + vertex 1.08207 1.38733 2.61689 + vertex 1.082 1.3823 2.61657 + vertex 1.08543 1.38623 2.61538 + endloop + endfacet + facet normal 0.629628 -0.00614536 0.776872 + outer loop + vertex 1.08822 1.38968 2.61333 + vertex 1.08822 1.39465 2.61337 + vertex 1.08548 1.39128 2.61557 + endloop + endfacet + facet normal 0.61914 -0.0347459 0.784512 + outer loop + vertex 1.08543 1.38623 2.61538 + vertex 1.08822 1.38968 2.61333 + vertex 1.08548 1.39128 2.61557 + endloop + endfacet + facet normal 0.399869 -0.0373204 0.915812 + outer loop + vertex 1.08548 1.39128 2.61557 + vertex 1.08207 1.38733 2.61689 + vertex 1.08543 1.38623 2.61538 + endloop + endfacet + facet normal 0.418437 -0.0564362 0.906491 + outer loop + vertex 1.08211 1.39237 2.61719 + vertex 1.08207 1.38733 2.61689 + vertex 1.08548 1.39128 2.61557 + endloop + endfacet + facet normal 0.649099 -0.00632784 0.760677 + outer loop + vertex 1.08822 1.39465 2.61337 + vertex 1.08821 1.39959 2.61342 + vertex 1.08549 1.39628 2.61571 + endloop + endfacet + facet normal 0.642787 -0.0241316 0.765665 + outer loop + vertex 1.08548 1.39128 2.61557 + vertex 1.08822 1.39465 2.61337 + vertex 1.08549 1.39628 2.61571 + endloop + endfacet + facet normal 0.426558 -0.0275644 0.90404 + outer loop + vertex 1.08549 1.39628 2.61571 + vertex 1.08211 1.39237 2.61719 + vertex 1.08548 1.39128 2.61557 + endloop + endfacet + facet normal 0.448749 -0.051201 0.89219 + outer loop + vertex 1.08213 1.39735 2.61746 + vertex 1.08211 1.39237 2.61719 + vertex 1.08549 1.39628 2.61571 + endloop + endfacet + facet normal 0.668702 -0.0012528 0.74353 + outer loop + vertex 1.08821 1.39959 2.61342 + vertex 1.08818 1.40445 2.61345 + vertex 1.0855 1.40121 2.61586 + endloop + endfacet + facet normal 0.661093 -0.0236186 0.749932 + outer loop + vertex 1.08549 1.39628 2.61571 + vertex 1.08821 1.39959 2.61342 + vertex 1.0855 1.40121 2.61586 + endloop + endfacet + facet normal 0.455197 -0.027504 0.889966 + outer loop + vertex 1.0855 1.40121 2.61586 + vertex 1.08213 1.39735 2.61746 + vertex 1.08549 1.39628 2.61571 + endloop + endfacet + facet normal 0.475505 -0.0500792 0.878287 + outer loop + vertex 1.08214 1.4023 2.61774 + vertex 1.08213 1.39735 2.61746 + vertex 1.0855 1.40121 2.61586 + endloop + endfacet + facet normal 0.691654 -0.00263078 0.722224 + outer loop + vertex 1.08818 1.40445 2.61345 + vertex 1.08815 1.40932 2.6135 + vertex 1.0855 1.4061 2.61603 + endloop + endfacet + facet normal 0.684254 -0.0250645 0.728813 + outer loop + vertex 1.0855 1.40121 2.61586 + vertex 1.08818 1.40445 2.61345 + vertex 1.0855 1.4061 2.61603 + endloop + endfacet + facet normal 0.480862 -0.0301443 0.876278 + outer loop + vertex 1.0855 1.4061 2.61603 + vertex 1.08214 1.4023 2.61774 + vertex 1.0855 1.40121 2.61586 + endloop + endfacet + facet normal 0.497671 -0.0496791 0.865942 + outer loop + vertex 1.08214 1.40725 2.61802 + vertex 1.08214 1.4023 2.61774 + vertex 1.0855 1.4061 2.61603 + endloop + endfacet + facet normal 0.71384 0.00488965 0.700291 + outer loop + vertex 1.08815 1.40932 2.6135 + vertex 1.08807 1.41427 2.61355 + vertex 1.08547 1.411 2.61622 + endloop + endfacet + facet normal 0.704745 -0.023766 0.709062 + outer loop + vertex 1.0855 1.4061 2.61603 + vertex 1.08815 1.40932 2.6135 + vertex 1.08547 1.411 2.61622 + endloop + endfacet + facet normal 0.502812 -0.0311491 0.863835 + outer loop + vertex 1.08547 1.411 2.61622 + vertex 1.08214 1.40725 2.61802 + vertex 1.0855 1.4061 2.61603 + endloop + endfacet + facet normal 0.51921 -0.0508206 0.853134 + outer loop + vertex 1.08212 1.41227 2.61834 + vertex 1.08214 1.40725 2.61802 + vertex 1.08547 1.411 2.61622 + endloop + endfacet + facet normal 0.740626 0.00330642 0.671909 + outer loop + vertex 1.08807 1.41427 2.61355 + vertex 1.08797 1.41943 2.61364 + vertex 1.0854 1.41611 2.61649 + endloop + endfacet + facet normal 0.731622 -0.0248182 0.681258 + outer loop + vertex 1.08547 1.411 2.61622 + vertex 1.08807 1.41427 2.61355 + vertex 1.0854 1.41611 2.61649 + endloop + endfacet + facet normal 0.523497 -0.0363679 0.851251 + outer loop + vertex 1.0854 1.41611 2.61649 + vertex 1.08212 1.41227 2.61834 + vertex 1.08547 1.411 2.61622 + endloop + endfacet + facet normal 0.552034 -0.0706024 0.830827 + outer loop + vertex 1.0821 1.4174 2.61879 + vertex 1.08212 1.41227 2.61834 + vertex 1.0854 1.41611 2.61649 + endloop + endfacet + facet normal 0.779624 -0.00412327 0.626234 + outer loop + vertex 1.08797 1.41943 2.61364 + vertex 1.08806 1.42454 2.61355 + vertex 1.08534 1.42191 2.61693 + endloop + endfacet + facet normal 0.765208 -0.0409202 0.642482 + outer loop + vertex 1.0854 1.41611 2.61649 + vertex 1.08797 1.41943 2.61364 + vertex 1.08534 1.42191 2.61693 + endloop + endfacet + facet normal 0.556093 -0.057248 0.829146 + outer loop + vertex 1.08534 1.42191 2.61693 + vertex 1.0821 1.4174 2.61879 + vertex 1.0854 1.41611 2.61649 + endloop + endfacet + facet normal 0.609515 -0.114021 0.784532 + outer loop + vertex 1.08201 1.42208 2.61953 + vertex 1.0821 1.4174 2.61879 + vertex 1.08534 1.42191 2.61693 + endloop + endfacet + facet normal 0.845312 -0.0029379 0.534265 + outer loop + vertex 1.08806 1.42454 2.61355 + vertex 1.08815 1.42946 2.61344 + vertex 1.08649 1.42673 2.61605 + endloop + endfacet + facet normal 0.807178 -0.0868332 0.583887 + outer loop + vertex 1.08534 1.42191 2.61693 + vertex 1.08806 1.42454 2.61355 + vertex 1.08649 1.42673 2.61605 + endloop + endfacet + facet normal 0.582118 -0.102211 0.806655 + outer loop + vertex 1.08201 1.42208 2.61953 + vertex 1.08405 1.42686 2.61867 + vertex 1.08141 1.42501 2.62034 + endloop + endfacet + facet normal 0.60913 -0.117764 0.784278 + outer loop + vertex 1.08201 1.42208 2.61953 + vertex 1.08534 1.42191 2.61693 + vertex 1.08405 1.42686 2.61867 + endloop + endfacet + facet normal 0.729675 -0.0503552 0.681937 + outer loop + vertex 1.08534 1.42191 2.61693 + vertex 1.08649 1.42673 2.61605 + vertex 1.08405 1.42686 2.61867 + endloop + endfacet + facet normal 0.55866 -0.049511 0.827918 + outer loop + vertex 1.08405 1.42686 2.61867 + vertex 1.08152 1.42846 2.62048 + vertex 1.08141 1.42501 2.62034 + endloop + endfacet + facet normal 0.852476 0.00926656 0.522684 + outer loop + vertex 1.08815 1.42946 2.61344 + vertex 1.08807 1.43442 2.61348 + vertex 1.08628 1.43094 2.61646 + endloop + endfacet + facet normal 0.848356 -0.00947789 0.529341 + outer loop + vertex 1.08649 1.42673 2.61605 + vertex 1.08815 1.42946 2.61344 + vertex 1.08628 1.43094 2.61646 + endloop + endfacet + facet normal 0.73076 -0.0303886 0.681958 + outer loop + vertex 1.08649 1.42673 2.61605 + vertex 1.08628 1.43094 2.61646 + vertex 1.08405 1.42686 2.61867 + endloop + endfacet + facet normal 0.742425 -0.0440529 0.66848 + outer loop + vertex 1.08628 1.43094 2.61646 + vertex 1.08409 1.43214 2.61897 + vertex 1.08405 1.42686 2.61867 + endloop + endfacet + facet normal 0.557665 -0.0517009 0.828455 + outer loop + vertex 1.08409 1.43214 2.61897 + vertex 1.08152 1.42846 2.62048 + vertex 1.08405 1.42686 2.61867 + endloop + endfacet + facet normal 0.537513 -0.0318334 0.842654 + outer loop + vertex 1.08141 1.43291 2.62071 + vertex 1.08152 1.42846 2.62048 + vertex 1.08409 1.43214 2.61897 + endloop + endfacet + facet normal 0.865612 0.00275315 0.500708 + outer loop + vertex 1.08807 1.43442 2.61348 + vertex 1.08804 1.43947 2.6135 + vertex 1.08624 1.43588 2.61663 + endloop + endfacet + facet normal 0.86283 -0.0108743 0.505378 + outer loop + vertex 1.08628 1.43094 2.61646 + vertex 1.08807 1.43442 2.61348 + vertex 1.08624 1.43588 2.61663 + endloop + endfacet + facet normal 0.749457 -0.0173219 0.661827 + outer loop + vertex 1.08628 1.43094 2.61646 + vertex 1.08624 1.43588 2.61663 + vertex 1.08409 1.43214 2.61897 + endloop + endfacet + facet normal 0.757349 -0.0277584 0.652421 + outer loop + vertex 1.08624 1.43588 2.61663 + vertex 1.08411 1.43708 2.61916 + vertex 1.08409 1.43214 2.61897 + endloop + endfacet + facet normal 0.537012 -0.0341144 0.842885 + outer loop + vertex 1.08411 1.43708 2.61916 + vertex 1.08141 1.43291 2.62071 + vertex 1.08409 1.43214 2.61897 + endloop + endfacet + facet normal 0.541541 -0.0382026 0.839806 + outer loop + vertex 1.08142 1.43775 2.62093 + vertex 1.08141 1.43291 2.62071 + vertex 1.08411 1.43708 2.61916 + endloop + endfacet + facet normal 0.875675 -0.00373582 0.482886 + outer loop + vertex 1.08804 1.43947 2.6135 + vertex 1.08807 1.44446 2.6135 + vertex 1.08628 1.44087 2.61671 + endloop + endfacet + facet normal 0.873716 -0.0139271 0.486236 + outer loop + vertex 1.08624 1.43588 2.61663 + vertex 1.08804 1.43947 2.6135 + vertex 1.08628 1.44087 2.61671 + endloop + endfacet + facet normal 0.760421 -0.0156953 0.649241 + outer loop + vertex 1.08624 1.43588 2.61663 + vertex 1.08628 1.44087 2.61671 + vertex 1.08411 1.43708 2.61916 + endloop + endfacet + facet normal 0.767634 -0.0255483 0.640379 + outer loop + vertex 1.08628 1.44087 2.61671 + vertex 1.08419 1.44207 2.61927 + vertex 1.08411 1.43708 2.61916 + endloop + endfacet + facet normal 0.543779 -0.0265328 0.838809 + outer loop + vertex 1.08419 1.44207 2.61927 + vertex 1.08142 1.43775 2.62093 + vertex 1.08411 1.43708 2.61916 + endloop + endfacet + facet normal 0.556651 -0.0382285 0.829867 + outer loop + vertex 1.0815 1.44275 2.6211 + vertex 1.08142 1.43775 2.62093 + vertex 1.08419 1.44207 2.61927 + endloop + endfacet + facet normal 0.881929 -0.00142261 0.471381 + outer loop + vertex 1.08807 1.44446 2.6135 + vertex 1.08809 1.4494 2.61347 + vertex 1.08634 1.44586 2.61673 + endloop + endfacet + facet normal 0.879815 -0.012727 0.475145 + outer loop + vertex 1.08628 1.44087 2.61671 + vertex 1.08807 1.44446 2.6135 + vertex 1.08634 1.44586 2.61673 + endloop + endfacet + facet normal 0.771013 -0.0118795 0.636708 + outer loop + vertex 1.08628 1.44087 2.61671 + vertex 1.08634 1.44586 2.61673 + vertex 1.08419 1.44207 2.61927 + endloop + endfacet + facet normal 0.777096 -0.0204684 0.629049 + outer loop + vertex 1.08634 1.44586 2.61673 + vertex 1.08427 1.44709 2.61933 + vertex 1.08419 1.44207 2.61927 + endloop + endfacet + facet normal 0.560201 -0.0195103 0.828127 + outer loop + vertex 1.08427 1.44709 2.61933 + vertex 1.0815 1.44275 2.6211 + vertex 1.08419 1.44207 2.61927 + endloop + endfacet + facet normal 0.574748 -0.0330705 0.817662 + outer loop + vertex 1.08157 1.44778 2.62125 + vertex 1.0815 1.44275 2.6211 + vertex 1.08427 1.44709 2.61933 + endloop + endfacet + facet normal 0.887046 0.00279058 0.461673 + outer loop + vertex 1.08809 1.4494 2.61347 + vertex 1.08809 1.45435 2.61344 + vertex 1.08639 1.45084 2.61672 + endloop + endfacet + facet normal 0.884996 -0.00831282 0.465524 + outer loop + vertex 1.08634 1.44586 2.61673 + vertex 1.08809 1.4494 2.61347 + vertex 1.08639 1.45084 2.61672 + endloop + endfacet + facet normal 0.780336 -0.00710371 0.62532 + outer loop + vertex 1.08634 1.44586 2.61673 + vertex 1.08639 1.45084 2.61672 + vertex 1.08427 1.44709 2.61933 + endloop + endfacet + facet normal 0.785806 -0.0150704 0.618289 + outer loop + vertex 1.08639 1.45084 2.61672 + vertex 1.08432 1.4521 2.61939 + vertex 1.08427 1.44709 2.61933 + endloop + endfacet + facet normal 0.578095 -0.0149853 0.815832 + outer loop + vertex 1.08432 1.4521 2.61939 + vertex 1.08157 1.44778 2.62125 + vertex 1.08427 1.44709 2.61933 + endloop + endfacet + facet normal 0.587726 -0.0242087 0.808698 + outer loop + vertex 1.08159 1.45278 2.62139 + vertex 1.08157 1.44778 2.62125 + vertex 1.08432 1.4521 2.61939 + endloop + endfacet + facet normal 0.890267 0.00650979 0.455392 + outer loop + vertex 1.08809 1.45435 2.61344 + vertex 1.08807 1.45932 2.6134 + vertex 1.08641 1.45582 2.61671 + endloop + endfacet + facet normal 0.888847 -0.00133038 0.458203 + outer loop + vertex 1.08639 1.45084 2.61672 + vertex 1.08809 1.45435 2.61344 + vertex 1.08641 1.45582 2.61671 + endloop + endfacet + facet normal 0.789259 -0.000397978 0.61406 + outer loop + vertex 1.08639 1.45084 2.61672 + vertex 1.08641 1.45582 2.61671 + vertex 1.08432 1.4521 2.61939 + endloop + endfacet + facet normal 0.794221 -0.00783244 0.607578 + outer loop + vertex 1.08641 1.45582 2.61671 + vertex 1.08434 1.45709 2.61943 + vertex 1.08432 1.4521 2.61939 + endloop + endfacet + facet normal 0.590409 -0.00874064 0.807057 + outer loop + vertex 1.08434 1.45709 2.61943 + vertex 1.08159 1.45278 2.62139 + vertex 1.08432 1.4521 2.61939 + endloop + endfacet + facet normal 0.602019 -0.0201616 0.798227 + outer loop + vertex 1.0816 1.45777 2.62151 + vertex 1.08159 1.45278 2.62139 + vertex 1.08434 1.45709 2.61943 + endloop + endfacet + facet normal 0.892592 0.00973728 0.45076 + outer loop + vertex 1.08807 1.45932 2.6134 + vertex 1.08805 1.46432 2.61334 + vertex 1.0864 1.46081 2.61668 + endloop + endfacet + facet normal 0.89151 0.00364444 0.452987 + outer loop + vertex 1.08641 1.45582 2.61671 + vertex 1.08807 1.45932 2.6134 + vertex 1.0864 1.46081 2.61668 + endloop + endfacet + facet normal 0.797002 0.00448478 0.60396 + outer loop + vertex 1.08641 1.45582 2.61671 + vertex 1.0864 1.46081 2.61668 + vertex 1.08434 1.45709 2.61943 + endloop + endfacet + facet normal 0.80324 -0.00512491 0.595633 + outer loop + vertex 1.0864 1.46081 2.61668 + vertex 1.08435 1.46208 2.61946 + vertex 1.08434 1.45709 2.61943 + endloop + endfacet + facet normal 0.604329 -0.00613659 0.796711 + outer loop + vertex 1.08435 1.46208 2.61946 + vertex 1.0816 1.45777 2.62151 + vertex 1.08434 1.45709 2.61943 + endloop + endfacet + facet normal 0.620157 -0.0221955 0.784164 + outer loop + vertex 1.08162 1.46276 2.62164 + vertex 1.0816 1.45777 2.62151 + vertex 1.08435 1.46208 2.61946 + endloop + endfacet + facet normal 0.896449 0.010614 0.443019 + outer loop + vertex 1.08805 1.46432 2.61334 + vertex 1.08802 1.46932 2.61328 + vertex 1.0864 1.46581 2.61664 + endloop + endfacet + facet normal 0.895228 0.00359279 0.445595 + outer loop + vertex 1.0864 1.46081 2.61668 + vertex 1.08805 1.46432 2.61334 + vertex 1.0864 1.46581 2.61664 + endloop + endfacet + facet normal 0.805343 0.00451307 0.592792 + outer loop + vertex 1.0864 1.46081 2.61668 + vertex 1.0864 1.46581 2.61664 + vertex 1.08435 1.46208 2.61946 + endloop + endfacet + facet normal 0.808796 -0.000936432 0.588089 + outer loop + vertex 1.0864 1.46581 2.61664 + vertex 1.08435 1.46707 2.61947 + vertex 1.08435 1.46208 2.61946 + endloop + endfacet + facet normal 0.623485 -0.00142851 0.781834 + outer loop + vertex 1.08435 1.46707 2.61947 + vertex 1.08162 1.46276 2.62164 + vertex 1.08435 1.46208 2.61946 + endloop + endfacet + facet normal 0.636905 -0.0154941 0.770786 + outer loop + vertex 1.08162 1.46776 2.62173 + vertex 1.08162 1.46276 2.62164 + vertex 1.08435 1.46707 2.61947 + endloop + endfacet + facet normal 0.899565 0.012052 0.43662 + outer loop + vertex 1.08802 1.46932 2.61328 + vertex 1.08799 1.47433 2.61321 + vertex 1.08639 1.47081 2.61659 + endloop + endfacet + facet normal 0.8985 0.0057501 0.438937 + outer loop + vertex 1.0864 1.46581 2.61664 + vertex 1.08802 1.46932 2.61328 + vertex 1.08639 1.47081 2.61659 + endloop + endfacet + facet normal 0.810449 0.00699721 0.585768 + outer loop + vertex 1.0864 1.46581 2.61664 + vertex 1.08639 1.47081 2.61659 + vertex 1.08435 1.46707 2.61947 + endloop + endfacet + facet normal 0.817782 -0.00488732 0.575508 + outer loop + vertex 1.08639 1.47081 2.61659 + vertex 1.08436 1.47207 2.61949 + vertex 1.08435 1.46707 2.61947 + endloop + endfacet + facet normal 0.638534 -0.00503792 0.769577 + outer loop + vertex 1.08436 1.47207 2.61949 + vertex 1.08162 1.46776 2.62173 + vertex 1.08435 1.46707 2.61947 + endloop + endfacet + facet normal 0.649799 -0.0172134 0.759911 + outer loop + vertex 1.08165 1.47275 2.62183 + vertex 1.08162 1.46776 2.62173 + vertex 1.08436 1.47207 2.61949 + endloop + endfacet + facet normal 0.902916 0.00847127 0.429735 + outer loop + vertex 1.08799 1.47433 2.61321 + vertex 1.08797 1.47932 2.61315 + vertex 1.08638 1.4758 2.61655 + endloop + endfacet + facet normal 0.902385 0.00525307 0.430899 + outer loop + vertex 1.08639 1.47081 2.61659 + vertex 1.08799 1.47433 2.61321 + vertex 1.08638 1.4758 2.61655 + endloop + endfacet + facet normal 0.820069 0.00637948 0.572229 + outer loop + vertex 1.08639 1.47081 2.61659 + vertex 1.08638 1.4758 2.61655 + vertex 1.08436 1.47207 2.61949 + endloop + endfacet + facet normal 0.826986 -0.00525777 0.562198 + outer loop + vertex 1.08638 1.4758 2.61655 + vertex 1.08438 1.47706 2.61951 + vertex 1.08436 1.47207 2.61949 + endloop + endfacet + facet normal 0.651591 -0.00545371 0.758551 + outer loop + vertex 1.08438 1.47706 2.61951 + vertex 1.08165 1.47275 2.62183 + vertex 1.08436 1.47207 2.61949 + endloop + endfacet + facet normal 0.659568 -0.0142975 0.751509 + outer loop + vertex 1.08166 1.47774 2.62191 + vertex 1.08165 1.47275 2.62183 + vertex 1.08438 1.47706 2.61951 + endloop + endfacet + facet normal 0.906643 0.00786037 0.421825 + outer loop + vertex 1.08797 1.47932 2.61315 + vertex 1.08794 1.48433 2.61311 + vertex 1.08639 1.4808 2.61653 + endloop + endfacet + facet normal 0.905642 0.0017392 0.424039 + outer loop + vertex 1.08638 1.4758 2.61655 + vertex 1.08797 1.47932 2.61315 + vertex 1.08639 1.4808 2.61653 + endloop + endfacet + facet normal 0.828513 0.00242815 0.559965 + outer loop + vertex 1.08638 1.4758 2.61655 + vertex 1.08639 1.4808 2.61653 + vertex 1.08438 1.47706 2.61951 + endloop + endfacet + facet normal 0.832778 -0.00494805 0.553585 + outer loop + vertex 1.08639 1.4808 2.61653 + vertex 1.08439 1.48205 2.61954 + vertex 1.08438 1.47706 2.61951 + endloop + endfacet + facet normal 0.660847 -0.00562261 0.7505 + outer loop + vertex 1.08439 1.48205 2.61954 + vertex 1.08166 1.47774 2.62191 + vertex 1.08438 1.47706 2.61951 + endloop + endfacet + facet normal 0.672566 -0.0189439 0.739795 + outer loop + vertex 1.08169 1.48273 2.62201 + vertex 1.08166 1.47774 2.62191 + vertex 1.08439 1.48205 2.61954 + endloop + endfacet + facet normal 0.910284 0.00815576 0.413903 + outer loop + vertex 1.08794 1.48433 2.61311 + vertex 1.08792 1.48932 2.61306 + vertex 1.08638 1.4858 2.61651 + endloop + endfacet + facet normal 0.909217 0.00139643 0.41632 + outer loop + vertex 1.08639 1.4808 2.61653 + vertex 1.08794 1.48433 2.61311 + vertex 1.08638 1.4858 2.61651 + endloop + endfacet + facet normal 0.83406 0.00172657 0.551671 + outer loop + vertex 1.08639 1.4808 2.61653 + vertex 1.08638 1.4858 2.61651 + vertex 1.08439 1.48205 2.61954 + endloop + endfacet + facet normal 0.838434 -0.00600204 0.544971 + outer loop + vertex 1.08638 1.4858 2.61651 + vertex 1.08441 1.48704 2.61957 + vertex 1.08439 1.48205 2.61954 + endloop + endfacet + facet normal 0.674361 -0.00673264 0.738371 + outer loop + vertex 1.08441 1.48704 2.61957 + vertex 1.08169 1.48273 2.62201 + vertex 1.08439 1.48205 2.61954 + endloop + endfacet + facet normal 0.679527 -0.0127197 0.73354 + outer loop + vertex 1.0817 1.48771 2.62208 + vertex 1.08169 1.48273 2.62201 + vertex 1.08441 1.48704 2.61957 + endloop + endfacet + facet normal 0.912461 0.0136502 0.408936 + outer loop + vertex 1.08792 1.48932 2.61306 + vertex 1.0879 1.49428 2.61295 + vertex 1.08638 1.49081 2.61646 + endloop + endfacet + facet normal 0.911236 0.00572814 0.411846 + outer loop + vertex 1.08638 1.4858 2.61651 + vertex 1.08792 1.48932 2.61306 + vertex 1.08638 1.49081 2.61646 + endloop + endfacet + facet normal 0.840847 0.00701866 0.541228 + outer loop + vertex 1.08638 1.4858 2.61651 + vertex 1.08638 1.49081 2.61646 + vertex 1.08441 1.48704 2.61957 + endloop + endfacet + facet normal 0.843863 0.00158544 0.536557 + outer loop + vertex 1.08638 1.49081 2.61646 + vertex 1.08442 1.49207 2.61954 + vertex 1.08441 1.48704 2.61957 + endloop + endfacet + facet normal 0.681659 0.00306288 0.731663 + outer loop + vertex 1.08442 1.49207 2.61954 + vertex 1.0817 1.48771 2.62208 + vertex 1.08441 1.48704 2.61957 + endloop + endfacet + facet normal 0.691617 -0.00864321 0.722213 + outer loop + vertex 1.08172 1.49271 2.62213 + vertex 1.0817 1.48771 2.62208 + vertex 1.08442 1.49207 2.61954 + endloop + endfacet + facet normal 0.915638 0.0226853 0.401364 + outer loop + vertex 1.0879 1.49428 2.61295 + vertex 1.0879 1.49908 2.61267 + vertex 1.08641 1.49591 2.61626 + endloop + endfacet + facet normal 0.913628 0.0105959 0.406414 + outer loop + vertex 1.08638 1.49081 2.61646 + vertex 1.0879 1.49428 2.61295 + vertex 1.08641 1.49591 2.61626 + endloop + endfacet + facet normal 0.846402 0.0159236 0.532306 + outer loop + vertex 1.08638 1.49081 2.61646 + vertex 1.08641 1.49591 2.61626 + vertex 1.08442 1.49207 2.61954 + endloop + endfacet + facet normal 0.851225 0.00698066 0.524755 + outer loop + vertex 1.08641 1.49591 2.61626 + vertex 1.08446 1.49724 2.6194 + vertex 1.08442 1.49207 2.61954 + endloop + endfacet + facet normal 0.694306 0.0135286 0.719553 + outer loop + vertex 1.08446 1.49724 2.6194 + vertex 1.08172 1.49271 2.62213 + vertex 1.08442 1.49207 2.61954 + endloop + endfacet + facet normal 0.706757 -0.00127077 0.707455 + outer loop + vertex 1.08173 1.49775 2.62213 + vertex 1.08172 1.49271 2.62213 + vertex 1.08446 1.49724 2.6194 + endloop + endfacet + facet normal 0.920682 0.0278504 0.38932 + outer loop + vertex 1.0879 1.49908 2.61267 + vertex 1.08804 1.50286 2.61207 + vertex 1.08659 1.50158 2.6156 + endloop + endfacet + facet normal 0.917587 0.0170172 0.39717 + outer loop + vertex 1.08641 1.49591 2.61626 + vertex 1.0879 1.49908 2.61267 + vertex 1.08659 1.50158 2.6156 + endloop + endfacet + facet normal 0.855635 0.032856 0.516536 + outer loop + vertex 1.08641 1.49591 2.61626 + vertex 1.08659 1.50158 2.6156 + vertex 1.08446 1.49724 2.6194 + endloop + endfacet + facet normal 0.870377 0.00446456 0.492365 + outer loop + vertex 1.08659 1.50158 2.6156 + vertex 1.08447 1.5025 2.61934 + vertex 1.08446 1.49724 2.6194 + endloop + endfacet + facet normal 0.707519 0.00714456 0.706658 + outer loop + vertex 1.08447 1.5025 2.61934 + vertex 1.08173 1.49775 2.62213 + vertex 1.08446 1.49724 2.6194 + endloop + endfacet + facet normal 0.715208 -0.00184339 0.698909 + outer loop + vertex 1.08173 1.50283 2.62214 + vertex 1.08173 1.49775 2.62213 + vertex 1.08447 1.5025 2.61934 + endloop + endfacet + facet normal 0.936078 0.0120558 0.351585 + outer loop + vertex 1.08879 1.50558 2.60991 + vertex 1.08895 1.50959 2.60933 + vertex 1.08776 1.50618 2.61261 + endloop + endfacet + facet normal 0.93658 0.0208409 0.349833 + outer loop + vertex 1.08804 1.50286 2.61207 + vertex 1.08879 1.50558 2.60991 + vertex 1.08776 1.50618 2.61261 + endloop + endfacet + facet normal 0.922751 0.0139636 0.385144 + outer loop + vertex 1.08804 1.50286 2.61207 + vertex 1.08776 1.50618 2.61261 + vertex 1.08659 1.50158 2.6156 + endloop + endfacet + facet normal 0.923906 0.0119044 0.382434 + outer loop + vertex 1.08659 1.50158 2.6156 + vertex 1.08776 1.50618 2.61261 + vertex 1.08634 1.50692 2.61604 + endloop + endfacet + facet normal 0.869951 0.000336175 0.493138 + outer loop + vertex 1.08659 1.50158 2.6156 + vertex 1.08634 1.50692 2.61604 + vertex 1.08447 1.5025 2.61934 + endloop + endfacet + facet normal 0.870265 -0.00021008 0.492584 + outer loop + vertex 1.08634 1.50692 2.61604 + vertex 1.08444 1.50768 2.61939 + vertex 1.08447 1.5025 2.61934 + endloop + endfacet + facet normal 0.715121 -0.00329783 0.698993 + outer loop + vertex 1.08444 1.50768 2.61939 + vertex 1.08173 1.50283 2.62214 + vertex 1.08447 1.5025 2.61934 + endloop + endfacet + facet normal 0.713036 -0.000932553 0.701127 + outer loop + vertex 1.08174 1.5079 2.62214 + vertex 1.08173 1.50283 2.62214 + vertex 1.08444 1.50768 2.61939 + endloop + endfacet + facet normal 0.93642 0.00240421 0.350874 + outer loop + vertex 1.08895 1.50959 2.60933 + vertex 1.089 1.51456 2.60918 + vertex 1.08771 1.51085 2.61264 + endloop + endfacet + facet normal 0.937193 0.00888975 0.348697 + outer loop + vertex 1.08776 1.50618 2.61261 + vertex 1.08895 1.50959 2.60933 + vertex 1.08771 1.51085 2.61264 + endloop + endfacet + facet normal 0.923678 0.00851035 0.383074 + outer loop + vertex 1.08776 1.50618 2.61261 + vertex 1.08771 1.51085 2.61264 + vertex 1.08634 1.50692 2.61604 + endloop + endfacet + facet normal 0.927277 -0.000257236 0.374376 + outer loop + vertex 1.08771 1.51085 2.61264 + vertex 1.08629 1.51201 2.61616 + vertex 1.08634 1.50692 2.61604 + endloop + endfacet + facet normal 0.869921 -0.00366456 0.493177 + outer loop + vertex 1.08634 1.50692 2.61604 + vertex 1.08629 1.51201 2.61616 + vertex 1.08444 1.50768 2.61939 + endloop + endfacet + facet normal 0.870261 -0.00426198 0.492573 + outer loop + vertex 1.08629 1.51201 2.61616 + vertex 1.08443 1.51274 2.61946 + vertex 1.08444 1.50768 2.61939 + endloop + endfacet + facet normal 0.712781 -0.00708563 0.70135 + outer loop + vertex 1.08443 1.51274 2.61946 + vertex 1.08174 1.5079 2.62214 + vertex 1.08444 1.50768 2.61939 + endloop + endfacet + facet normal 0.707386 -0.0010581 0.706826 + outer loop + vertex 1.08174 1.51291 2.62215 + vertex 1.08174 1.5079 2.62214 + vertex 1.08443 1.51274 2.61946 + endloop + endfacet + facet normal 0.938076 -0.00444595 0.346402 + outer loop + vertex 1.089 1.51456 2.60918 + vertex 1.08894 1.51952 2.60939 + vertex 1.08767 1.51587 2.61279 + endloop + endfacet + facet normal 0.938266 -0.00287375 0.345904 + outer loop + vertex 1.08771 1.51085 2.61264 + vertex 1.089 1.51456 2.60918 + vertex 1.08767 1.51587 2.61279 + endloop + endfacet + facet normal 0.926861 -0.00382629 0.375384 + outer loop + vertex 1.08771 1.51085 2.61264 + vertex 1.08767 1.51587 2.61279 + vertex 1.08629 1.51201 2.61616 + endloop + endfacet + facet normal 0.928467 -0.00794487 0.371329 + outer loop + vertex 1.08767 1.51587 2.61279 + vertex 1.08623 1.51693 2.61641 + vertex 1.08629 1.51201 2.61616 + endloop + endfacet + facet normal 0.869162 -0.0148608 0.494304 + outer loop + vertex 1.08629 1.51201 2.61616 + vertex 1.08623 1.51693 2.61641 + vertex 1.08443 1.51274 2.61946 + endloop + endfacet + facet normal 0.864348 -0.00656569 0.502851 + outer loop + vertex 1.08623 1.51693 2.61641 + vertex 1.08439 1.51754 2.61958 + vertex 1.08443 1.51274 2.61946 + endloop + endfacet + facet normal 0.706955 -0.0129079 0.707141 + outer loop + vertex 1.08439 1.51754 2.61958 + vertex 1.08174 1.51291 2.62215 + vertex 1.08443 1.51274 2.61946 + endloop + endfacet + facet normal 0.694601 0.000980872 0.719395 + outer loop + vertex 1.08173 1.51785 2.62214 + vertex 1.08174 1.51291 2.62215 + vertex 1.08439 1.51754 2.61958 + endloop + endfacet + facet normal 0.939384 -0.0155639 0.342515 + outer loop + vertex 1.08894 1.51952 2.60939 + vertex 1.08884 1.52348 2.60985 + vertex 1.08754 1.52113 2.61332 + endloop + endfacet + facet normal 0.940118 -0.0104769 0.340689 + outer loop + vertex 1.08767 1.51587 2.61279 + vertex 1.08894 1.51952 2.60939 + vertex 1.08754 1.52113 2.61332 + endloop + endfacet + facet normal 0.92779 -0.0140221 0.372839 + outer loop + vertex 1.08767 1.51587 2.61279 + vertex 1.08754 1.52113 2.61332 + vertex 1.08623 1.51693 2.61641 + endloop + endfacet + facet normal 0.924096 -0.00604359 0.382113 + outer loop + vertex 1.08754 1.52113 2.61332 + vertex 1.08602 1.52091 2.61698 + vertex 1.08623 1.51693 2.61641 + endloop + endfacet + facet normal 0.862318 -0.0270745 0.505643 + outer loop + vertex 1.08623 1.51693 2.61641 + vertex 1.08602 1.52091 2.61698 + vertex 1.08439 1.51754 2.61958 + endloop + endfacet + facet normal 0.846395 0.00142778 0.532554 + outer loop + vertex 1.08602 1.52091 2.61698 + vertex 1.08443 1.52221 2.6195 + vertex 1.08439 1.51754 2.61958 + endloop + endfacet + facet normal 0.69489 0.00602176 0.719091 + outer loop + vertex 1.08443 1.52221 2.6195 + vertex 1.08173 1.51785 2.62214 + vertex 1.08439 1.51754 2.61958 + endloop + endfacet + facet normal 0.694073 0.00700066 0.719871 + outer loop + vertex 1.08172 1.52277 2.62211 + vertex 1.08173 1.51785 2.62214 + vertex 1.08443 1.52221 2.6195 + endloop + endfacet + facet normal 0.94017 -0.0194839 0.340148 + outer loop + vertex 1.08884 1.52348 2.60985 + vertex 1.08808 1.52541 2.61206 + vertex 1.08754 1.52113 2.61332 + endloop + endfacet + facet normal 0.925305 -0.0203022 0.378681 + outer loop + vertex 1.08808 1.52541 2.61206 + vertex 1.08796 1.52942 2.61256 + vertex 1.08655 1.52542 2.61581 + endloop + endfacet + facet normal 0.925489 -0.0063155 0.378721 + outer loop + vertex 1.08808 1.52541 2.61206 + vertex 1.08655 1.52542 2.61581 + vertex 1.08754 1.52113 2.61332 + endloop + endfacet + facet normal 0.924132 -0.00852083 0.381978 + outer loop + vertex 1.08754 1.52113 2.61332 + vertex 1.08655 1.52542 2.61581 + vertex 1.08602 1.52091 2.61698 + endloop + endfacet + facet normal 0.853701 0.0353118 0.519564 + outer loop + vertex 1.08602 1.52091 2.61698 + vertex 1.08655 1.52542 2.61581 + vertex 1.08443 1.52221 2.6195 + endloop + endfacet + facet normal 0.865795 0.00528657 0.500371 + outer loop + vertex 1.08655 1.52542 2.61581 + vertex 1.08446 1.52708 2.6194 + vertex 1.08443 1.52221 2.6195 + endloop + endfacet + facet normal 0.694457 0.0108644 0.719452 + outer loop + vertex 1.08446 1.52708 2.6194 + vertex 1.08172 1.52277 2.62211 + vertex 1.08443 1.52221 2.6195 + endloop + endfacet + facet normal 0.698739 0.00557093 0.715355 + outer loop + vertex 1.0817 1.52772 2.62209 + vertex 1.08172 1.52277 2.62211 + vertex 1.08446 1.52708 2.6194 + endloop + endfacet + facet normal 0.918999 -0.0199401 0.393756 + outer loop + vertex 1.08796 1.52942 2.61256 + vertex 1.0879 1.53429 2.61295 + vertex 1.08641 1.53079 2.61626 + endloop + endfacet + facet normal 0.9206 -0.00908783 0.390401 + outer loop + vertex 1.08655 1.52542 2.61581 + vertex 1.08796 1.52942 2.61256 + vertex 1.08641 1.53079 2.61626 + endloop + endfacet + facet normal 0.860399 -0.0205817 0.509204 + outer loop + vertex 1.08655 1.52542 2.61581 + vertex 1.08641 1.53079 2.61626 + vertex 1.08446 1.52708 2.6194 + endloop + endfacet + facet normal 0.851242 -0.0026282 0.524767 + outer loop + vertex 1.08641 1.53079 2.61626 + vertex 1.08441 1.53208 2.6195 + vertex 1.08446 1.52708 2.6194 + endloop + endfacet + facet normal 0.697051 -0.00841405 0.716972 + outer loop + vertex 1.08441 1.53208 2.6195 + vertex 1.0817 1.52772 2.62209 + vertex 1.08446 1.52708 2.6194 + endloop + endfacet + facet normal 0.686469 0.00420576 0.727147 + outer loop + vertex 1.08169 1.53271 2.62207 + vertex 1.0817 1.52772 2.62209 + vertex 1.08441 1.53208 2.6195 + endloop + endfacet + facet normal 0.912133 -0.0114377 0.409735 + outer loop + vertex 1.0879 1.53429 2.61295 + vertex 1.08789 1.53924 2.61311 + vertex 1.08634 1.53578 2.61646 + endloop + endfacet + facet normal 0.913255 -0.00465874 0.407363 + outer loop + vertex 1.08641 1.53079 2.61626 + vertex 1.0879 1.53429 2.61295 + vertex 1.08634 1.53578 2.61646 + endloop + endfacet + facet normal 0.849842 -0.0102639 0.526937 + outer loop + vertex 1.08641 1.53079 2.61626 + vertex 1.08634 1.53578 2.61646 + vertex 1.08441 1.53208 2.6195 + endloop + endfacet + facet normal 0.843549 0.00134425 0.537051 + outer loop + vertex 1.08634 1.53578 2.61646 + vertex 1.08438 1.53705 2.61954 + vertex 1.08441 1.53208 2.6195 + endloop + endfacet + facet normal 0.685813 -0.00118331 0.727777 + outer loop + vertex 1.08438 1.53705 2.61954 + vertex 1.08169 1.53271 2.62207 + vertex 1.08441 1.53208 2.6195 + endloop + endfacet + facet normal 0.673299 0.0132664 0.739251 + outer loop + vertex 1.08167 1.53769 2.622 + vertex 1.08169 1.53271 2.62207 + vertex 1.08438 1.53705 2.61954 + endloop + endfacet + facet normal 0.907419 -0.00349786 0.420212 + outer loop + vertex 1.08789 1.53924 2.61311 + vertex 1.0879 1.54423 2.61314 + vertex 1.08632 1.54074 2.61651 + endloop + endfacet + facet normal 0.90793 -0.000494173 0.419123 + outer loop + vertex 1.08634 1.53578 2.61646 + vertex 1.08789 1.53924 2.61311 + vertex 1.08632 1.54074 2.61651 + endloop + endfacet + facet normal 0.842927 -0.00198302 0.538025 + outer loop + vertex 1.08634 1.53578 2.61646 + vertex 1.08632 1.54074 2.61651 + vertex 1.08438 1.53705 2.61954 + endloop + endfacet + facet normal 0.837598 0.00757079 0.546235 + outer loop + vertex 1.08632 1.54074 2.61651 + vertex 1.08436 1.54203 2.61951 + vertex 1.08438 1.53705 2.61954 + endloop + endfacet + facet normal 0.672654 0.00804242 0.739913 + outer loop + vertex 1.08436 1.54203 2.61951 + vertex 1.08167 1.53769 2.622 + vertex 1.08438 1.53705 2.61954 + endloop + endfacet + facet normal 0.666263 0.0152501 0.745561 + outer loop + vertex 1.08166 1.5427 2.62191 + vertex 1.08167 1.53769 2.622 + vertex 1.08436 1.54203 2.61951 + endloop + endfacet + facet normal 0.905151 -7.83671e-05 0.425091 + outer loop + vertex 1.0879 1.54423 2.61314 + vertex 1.0879 1.54923 2.61314 + vertex 1.08632 1.54573 2.61651 + endloop + endfacet + facet normal 0.905428 0.00154443 0.424498 + outer loop + vertex 1.08632 1.54074 2.61651 + vertex 1.0879 1.54423 2.61314 + vertex 1.08632 1.54573 2.61651 + endloop + endfacet + facet normal 0.836431 0.00150126 0.548071 + outer loop + vertex 1.08632 1.54074 2.61651 + vertex 1.08632 1.54573 2.61651 + vertex 1.08436 1.54203 2.61951 + endloop + endfacet + facet normal 0.830821 0.0112497 0.556426 + outer loop + vertex 1.08632 1.54573 2.61651 + vertex 1.08432 1.54701 2.61946 + vertex 1.08436 1.54203 2.61951 + endloop + endfacet + facet normal 0.665833 0.0119434 0.746005 + outer loop + vertex 1.08432 1.54701 2.61946 + vertex 1.08166 1.5427 2.62191 + vertex 1.08436 1.54203 2.61951 + endloop + endfacet + facet normal 0.662269 0.0158959 0.749098 + outer loop + vertex 1.08164 1.5477 2.62182 + vertex 1.08166 1.5427 2.62191 + vertex 1.08432 1.54701 2.61946 + endloop + endfacet + facet normal 0.903317 0.00336459 0.428961 + outer loop + vertex 1.0879 1.54923 2.61314 + vertex 1.08787 1.55423 2.61316 + vertex 1.08629 1.55073 2.61651 + endloop + endfacet + facet normal 0.903447 0.00413868 0.42868 + outer loop + vertex 1.08632 1.54573 2.61651 + vertex 1.0879 1.54923 2.61314 + vertex 1.08629 1.55073 2.61651 + endloop + endfacet + facet normal 0.829338 0.00362585 0.558735 + outer loop + vertex 1.08632 1.54573 2.61651 + vertex 1.08629 1.55073 2.61651 + vertex 1.08432 1.54701 2.61946 + endloop + endfacet + facet normal 0.82795 0.00597694 0.56077 + outer loop + vertex 1.08629 1.55073 2.61651 + vertex 1.08429 1.55201 2.61945 + vertex 1.08432 1.54701 2.61946 + endloop + endfacet + facet normal 0.660803 0.00531987 0.75054 + outer loop + vertex 1.08429 1.55201 2.61945 + vertex 1.08164 1.5477 2.62182 + vertex 1.08432 1.54701 2.61946 + endloop + endfacet + facet normal 0.655484 0.0111211 0.755127 + outer loop + vertex 1.08162 1.5527 2.62176 + vertex 1.08164 1.5477 2.62182 + vertex 1.08429 1.55201 2.61945 + endloop + endfacet + facet normal 0.901965 0.0103034 0.431687 + outer loop + vertex 1.08787 1.55423 2.61316 + vertex 1.08782 1.5592 2.61315 + vertex 1.08624 1.55571 2.61653 + endloop + endfacet + facet normal 0.901538 0.0076907 0.432632 + outer loop + vertex 1.08629 1.55073 2.61651 + vertex 1.08787 1.55423 2.61316 + vertex 1.08624 1.55571 2.61653 + endloop + endfacet + facet normal 0.828053 0.00650196 0.560612 + outer loop + vertex 1.08629 1.55073 2.61651 + vertex 1.08624 1.55571 2.61653 + vertex 1.08429 1.55201 2.61945 + endloop + endfacet + facet normal 0.824552 0.0123143 0.565652 + outer loop + vertex 1.08624 1.55571 2.61653 + vertex 1.08423 1.55698 2.61943 + vertex 1.08429 1.55201 2.61945 + endloop + endfacet + facet normal 0.655478 0.0110785 0.755133 + outer loop + vertex 1.08423 1.55698 2.61943 + vertex 1.08162 1.5527 2.62176 + vertex 1.08429 1.55201 2.61945 + endloop + endfacet + facet normal 0.643774 0.0235042 0.764855 + outer loop + vertex 1.08156 1.55765 2.62166 + vertex 1.08162 1.5527 2.62176 + vertex 1.08423 1.55698 2.61943 + endloop + endfacet + facet normal 0.900271 0.0220359 0.434772 + outer loop + vertex 1.08782 1.5592 2.61315 + vertex 1.08775 1.56412 2.61304 + vertex 1.08617 1.5607 2.61648 + endloop + endfacet + facet normal 0.899387 0.016466 0.436843 + outer loop + vertex 1.08624 1.55571 2.61653 + vertex 1.08782 1.5592 2.61315 + vertex 1.08617 1.5607 2.61648 + endloop + endfacet + facet normal 0.825394 0.0167438 0.564309 + outer loop + vertex 1.08624 1.55571 2.61653 + vertex 1.08617 1.5607 2.61648 + vertex 1.08423 1.55698 2.61943 + endloop + endfacet + facet normal 0.820527 0.0246416 0.571076 + outer loop + vertex 1.08617 1.5607 2.61648 + vertex 1.08416 1.56198 2.61932 + vertex 1.08423 1.55698 2.61943 + endloop + endfacet + facet normal 0.644175 0.0265199 0.764419 + outer loop + vertex 1.08416 1.56198 2.61932 + vertex 1.08156 1.55765 2.62166 + vertex 1.08423 1.55698 2.61943 + endloop + endfacet + facet normal 0.643167 0.027565 0.765229 + outer loop + vertex 1.08151 1.56264 2.62152 + vertex 1.08156 1.55765 2.62166 + vertex 1.08416 1.56198 2.61932 + endloop + endfacet + facet normal 0.899173 0.0398523 0.435775 + outer loop + vertex 1.08775 1.56412 2.61304 + vertex 1.0877 1.56892 2.61271 + vertex 1.08613 1.56578 2.61623 + endloop + endfacet + facet normal 0.897315 0.0290889 0.440431 + outer loop + vertex 1.08617 1.5607 2.61648 + vertex 1.08775 1.56412 2.61304 + vertex 1.08613 1.56578 2.61623 + endloop + endfacet + facet normal 0.822387 0.0347271 0.567868 + outer loop + vertex 1.08617 1.5607 2.61648 + vertex 1.08613 1.56578 2.61623 + vertex 1.08416 1.56198 2.61932 + endloop + endfacet + facet normal 0.823078 0.0336104 0.566933 + outer loop + vertex 1.08613 1.56578 2.61623 + vertex 1.08413 1.56713 2.61906 + vertex 1.08416 1.56198 2.61932 + endloop + endfacet + facet normal 0.645023 0.0423247 0.76299 + outer loop + vertex 1.08413 1.56713 2.61906 + vertex 1.08151 1.56264 2.62152 + vertex 1.08416 1.56198 2.61932 + endloop + endfacet + facet normal 0.651155 0.0360697 0.758087 + outer loop + vertex 1.08148 1.56769 2.62131 + vertex 1.08151 1.56264 2.62152 + vertex 1.08413 1.56713 2.61906 + endloop + endfacet + facet normal 0.902709 0.0467119 0.427709 + outer loop + vertex 1.0877 1.56892 2.61271 + vertex 1.0878 1.57271 2.61209 + vertex 1.08624 1.57144 2.61551 + endloop + endfacet + facet normal 0.899974 0.0377937 0.434302 + outer loop + vertex 1.08613 1.56578 2.61623 + vertex 1.0877 1.56892 2.61271 + vertex 1.08624 1.57144 2.61551 + endloop + endfacet + facet normal 0.827028 0.0551575 0.559448 + outer loop + vertex 1.08613 1.56578 2.61623 + vertex 1.08624 1.57144 2.61551 + vertex 1.08413 1.56713 2.61906 + endloop + endfacet + facet normal 0.844511 0.0263177 0.534891 + outer loop + vertex 1.08624 1.57144 2.61551 + vertex 1.08408 1.57237 2.61887 + vertex 1.08413 1.56713 2.61906 + endloop + endfacet + facet normal 0.650818 0.0326508 0.758531 + outer loop + vertex 1.08408 1.57237 2.61887 + vertex 1.08148 1.56769 2.62131 + vertex 1.08413 1.56713 2.61906 + endloop + endfacet + facet normal 0.653442 0.0300703 0.756379 + outer loop + vertex 1.08149 1.57276 2.6211 + vertex 1.08148 1.56769 2.62131 + vertex 1.08408 1.57237 2.61887 + endloop + endfacet + facet normal 0.916212 0.00943656 0.400583 + outer loop + vertex 1.08862 1.57552 2.60998 + vertex 1.08878 1.57965 2.60953 + vertex 1.08745 1.57607 2.61266 + endloop + endfacet + facet normal 0.917274 0.0280797 0.397266 + outer loop + vertex 1.0878 1.57271 2.61209 + vertex 1.08862 1.57552 2.60998 + vertex 1.08745 1.57607 2.61266 + endloop + endfacet + facet normal 0.906868 0.0229685 0.420788 + outer loop + vertex 1.0878 1.57271 2.61209 + vertex 1.08745 1.57607 2.61266 + vertex 1.08624 1.57144 2.61551 + endloop + endfacet + facet normal 0.908686 0.0201577 0.416993 + outer loop + vertex 1.08624 1.57144 2.61551 + vertex 1.08745 1.57607 2.61266 + vertex 1.08592 1.57674 2.61595 + endloop + endfacet + facet normal 0.842239 0.00592483 0.539072 + outer loop + vertex 1.08624 1.57144 2.61551 + vertex 1.08592 1.57674 2.61595 + vertex 1.08408 1.57237 2.61887 + endloop + endfacet + facet normal 0.842671 0.00529596 0.538403 + outer loop + vertex 1.08592 1.57674 2.61595 + vertex 1.08404 1.57744 2.61888 + vertex 1.08408 1.57237 2.61887 + endloop + endfacet + facet normal 0.651409 0.00336967 0.758719 + outer loop + vertex 1.08404 1.57744 2.61888 + vertex 1.08149 1.57276 2.6211 + vertex 1.08408 1.57237 2.61887 + endloop + endfacet + facet normal 0.63048 0.0228899 0.775868 + outer loop + vertex 1.08152 1.57777 2.62093 + vertex 1.08149 1.57276 2.6211 + vertex 1.08404 1.57744 2.61888 + endloop + endfacet + facet normal 0.917728 -0.0159835 0.396889 + outer loop + vertex 1.08878 1.57965 2.60953 + vertex 1.08881 1.58467 2.60966 + vertex 1.08733 1.58078 2.61291 + endloop + endfacet + facet normal 0.919864 0.000785272 0.392236 + outer loop + vertex 1.08745 1.57607 2.61266 + vertex 1.08878 1.57965 2.60953 + vertex 1.08733 1.58078 2.61291 + endloop + endfacet + facet normal 0.907235 -0.00103457 0.420624 + outer loop + vertex 1.08745 1.57607 2.61266 + vertex 1.08733 1.58078 2.61291 + vertex 1.08592 1.57674 2.61595 + endloop + endfacet + facet normal 0.909822 -0.00620924 0.414952 + outer loop + vertex 1.08733 1.58078 2.61291 + vertex 1.0858 1.5816 2.61629 + vertex 1.08592 1.57674 2.61595 + endloop + endfacet + facet normal 0.840148 -0.0167356 0.542099 + outer loop + vertex 1.08592 1.57674 2.61595 + vertex 1.0858 1.5816 2.61629 + vertex 1.08404 1.57744 2.61888 + endloop + endfacet + facet normal 0.826165 0.00244297 0.563422 + outer loop + vertex 1.0858 1.5816 2.61629 + vertex 1.08395 1.58218 2.61899 + vertex 1.08404 1.57744 2.61888 + endloop + endfacet + facet normal 0.628369 -0.00622468 0.77789 + outer loop + vertex 1.08395 1.58218 2.61899 + vertex 1.08152 1.57777 2.62093 + vertex 1.08404 1.57744 2.61888 + endloop + endfacet + facet normal 0.576799 0.0389101 0.815959 + outer loop + vertex 1.08134 1.58267 2.62082 + vertex 1.08152 1.57777 2.62093 + vertex 1.08395 1.58218 2.61899 + endloop + endfacet + facet normal 0.912986 -0.0309328 0.406816 + outer loop + vertex 1.08881 1.58467 2.60966 + vertex 1.08874 1.58868 2.61011 + vertex 1.08713 1.58603 2.61354 + endloop + endfacet + facet normal 0.915869 -0.0115862 0.40131 + outer loop + vertex 1.08733 1.58078 2.61291 + vertex 1.08881 1.58467 2.60966 + vertex 1.08713 1.58603 2.61354 + endloop + endfacet + facet normal 0.909062 -0.013667 0.416437 + outer loop + vertex 1.08733 1.58078 2.61291 + vertex 1.08713 1.58603 2.61354 + vertex 1.0858 1.5816 2.61629 + endloop + endfacet + facet normal 0.89501 0.00890742 0.445957 + outer loop + vertex 1.08713 1.58603 2.61354 + vertex 1.08543 1.58555 2.61695 + vertex 1.0858 1.5816 2.61629 + endloop + endfacet + facet normal 0.824001 -0.0179695 0.566303 + outer loop + vertex 1.0858 1.5816 2.61629 + vertex 1.08543 1.58555 2.61695 + vertex 1.08395 1.58218 2.61899 + endloop + endfacet + facet normal 0.767988 0.0502033 0.638493 + outer loop + vertex 1.08543 1.58555 2.61695 + vertex 1.08361 1.5867 2.61905 + vertex 1.08395 1.58218 2.61899 + endloop + endfacet + facet normal 0.576192 0.0331216 0.816643 + outer loop + vertex 1.08361 1.5867 2.61905 + vertex 1.08134 1.58267 2.62082 + vertex 1.08395 1.58218 2.61899 + endloop + endfacet + facet normal 0.503587 0.0925791 0.85897 + outer loop + vertex 1.0804 1.58771 2.62083 + vertex 1.08134 1.58267 2.62082 + vertex 1.08361 1.5867 2.61905 + endloop + endfacet + facet normal 0.908983 -0.0159514 0.416528 + outer loop + vertex 1.08874 1.58868 2.61011 + vertex 1.08774 1.59048 2.61237 + vertex 1.08713 1.58603 2.61354 + endloop + endfacet + facet normal 0.863743 -0.00625035 0.503893 + outer loop + vertex 1.08774 1.59048 2.61237 + vertex 1.08753 1.59453 2.61277 + vertex 1.08544 1.59054 2.61631 + endloop + endfacet + facet normal 0.863809 0.0130931 0.50365 + outer loop + vertex 1.08774 1.59048 2.61237 + vertex 1.08544 1.59054 2.61631 + vertex 1.08713 1.58603 2.61354 + endloop + endfacet + facet normal 0.891039 0.0558228 0.45048 + outer loop + vertex 1.08713 1.58603 2.61354 + vertex 1.08544 1.59054 2.61631 + vertex 1.08543 1.58555 2.61695 + endloop + endfacet + facet normal 0.75107 0.148006 0.643419 + outer loop + vertex 1.08286 1.59041 2.61935 + vertex 1.08544 1.59054 2.61631 + vertex 1.08239 1.59444 2.61898 + endloop + endfacet + facet normal 0.756648 0.100404 0.646067 + outer loop + vertex 1.08286 1.59041 2.61935 + vertex 1.08361 1.5867 2.61905 + vertex 1.08544 1.59054 2.61631 + endloop + endfacet + facet normal 0.774148 0.0791566 0.628036 + outer loop + vertex 1.08361 1.5867 2.61905 + vertex 1.08543 1.58555 2.61695 + vertex 1.08544 1.59054 2.61631 + endloop + endfacet + facet normal 0.490235 0.0288925 0.871111 + outer loop + vertex 1.08361 1.5867 2.61905 + vertex 1.08286 1.59041 2.61935 + vertex 1.0804 1.58771 2.62083 + endloop + endfacet + facet normal 0.823211 -0.0042724 0.567719 + outer loop + vertex 1.08753 1.59453 2.61277 + vertex 1.08743 1.59935 2.61296 + vertex 1.08525 1.59619 2.6161 + endloop + endfacet + facet normal 0.834487 0.0489392 0.54885 + outer loop + vertex 1.08544 1.59054 2.61631 + vertex 1.08753 1.59453 2.61277 + vertex 1.08525 1.59619 2.6161 + endloop + endfacet + facet normal 0.692685 0.0502079 0.719491 + outer loop + vertex 1.08525 1.59619 2.6161 + vertex 1.08239 1.59444 2.61898 + vertex 1.08544 1.59054 2.61631 + endloop + endfacet + facet normal 0.687845 0.0639596 0.723034 + outer loop + vertex 1.08286 1.59838 2.61818 + vertex 1.08239 1.59444 2.61898 + vertex 1.08525 1.59619 2.6161 + endloop + endfacet + facet normal 0.795369 0.00431653 0.606111 + outer loop + vertex 1.08743 1.59935 2.61296 + vertex 1.08741 1.60425 2.61295 + vertex 1.08511 1.6008 2.61599 + endloop + endfacet + facet normal 0.802458 0.0377835 0.595511 + outer loop + vertex 1.08525 1.59619 2.6161 + vertex 1.08743 1.59935 2.61296 + vertex 1.08511 1.6008 2.61599 + endloop + endfacet + facet normal 0.675356 0.0374929 0.736538 + outer loop + vertex 1.08511 1.6008 2.61599 + vertex 1.08286 1.59838 2.61818 + vertex 1.08525 1.59619 2.6161 + endloop + endfacet + facet normal 0.644857 0.0863852 0.759405 + outer loop + vertex 1.08221 1.6022 2.6183 + vertex 1.08286 1.59838 2.61818 + vertex 1.08511 1.6008 2.61599 + endloop + endfacet + facet normal 0.773699 -0.00217632 0.633549 + outer loop + vertex 1.08741 1.60425 2.61295 + vertex 1.08747 1.60926 2.6129 + vertex 1.08498 1.60553 2.61593 + endloop + endfacet + facet normal 0.780229 0.0308393 0.624734 + outer loop + vertex 1.08511 1.6008 2.61599 + vertex 1.08741 1.60425 2.61295 + vertex 1.08498 1.60553 2.61593 + endloop + endfacet + facet normal 0.630179 0.0284812 0.775927 + outer loop + vertex 1.08498 1.60553 2.61593 + vertex 1.08221 1.6022 2.6183 + vertex 1.08511 1.6008 2.61599 + endloop + endfacet + facet normal 0.603663 0.06389 0.794676 + outer loop + vertex 1.08192 1.60676 2.61815 + vertex 1.08221 1.6022 2.6183 + vertex 1.08498 1.60553 2.61593 + endloop + endfacet + facet normal 0.75676 -0.00475729 0.653675 + outer loop + vertex 1.08747 1.60926 2.6129 + vertex 1.08756 1.6143 2.61283 + vertex 1.08497 1.61054 2.6158 + endloop + endfacet + facet normal 0.761522 0.0176368 0.647899 + outer loop + vertex 1.08498 1.60553 2.61593 + vertex 1.08747 1.60926 2.6129 + vertex 1.08497 1.61054 2.6158 + endloop + endfacet + facet normal 0.593742 0.0217704 0.804361 + outer loop + vertex 1.08497 1.61054 2.6158 + vertex 1.08192 1.60676 2.61815 + vertex 1.08498 1.60553 2.61593 + endloop + endfacet + facet normal 0.564571 0.0572011 0.8234 + outer loop + vertex 1.08173 1.61159 2.61795 + vertex 1.08192 1.60676 2.61815 + vertex 1.08497 1.61054 2.6158 + endloop + endfacet + facet normal 0.743993 -0.00385971 0.668176 + outer loop + vertex 1.08756 1.6143 2.61283 + vertex 1.08763 1.61933 2.61278 + vertex 1.08504 1.61567 2.61564 + endloop + endfacet + facet normal 0.747341 0.010127 0.664363 + outer loop + vertex 1.08497 1.61054 2.6158 + vertex 1.08756 1.6143 2.61283 + vertex 1.08504 1.61567 2.61564 + endloop + endfacet + facet normal 0.556541 0.0173986 0.830638 + outer loop + vertex 1.08504 1.61567 2.61564 + vertex 1.08173 1.61159 2.61795 + vertex 1.08497 1.61054 2.6158 + endloop + endfacet + facet normal 0.530559 0.0472778 0.846328 + outer loop + vertex 1.08174 1.61667 2.61766 + vertex 1.08173 1.61159 2.61795 + vertex 1.08504 1.61567 2.61564 + endloop + endfacet + facet normal 0.732268 -0.00348781 0.681008 + outer loop + vertex 1.08763 1.61933 2.61278 + vertex 1.08766 1.62433 2.61278 + vertex 1.08512 1.62082 2.61549 + endloop + endfacet + facet normal 0.735697 0.00912873 0.677249 + outer loop + vertex 1.08504 1.61567 2.61564 + vertex 1.08763 1.61933 2.61278 + vertex 1.08512 1.62082 2.61549 + endloop + endfacet + facet normal 0.524563 0.017558 0.851191 + outer loop + vertex 1.08512 1.62082 2.61549 + vertex 1.08174 1.61667 2.61766 + vertex 1.08504 1.61567 2.61564 + endloop + endfacet + facet normal 0.502551 0.0418593 0.863534 + outer loop + vertex 1.08186 1.62182 2.61734 + vertex 1.08174 1.61667 2.61766 + vertex 1.08512 1.62082 2.61549 + endloop + endfacet + facet normal 0.71497 -0.00542837 0.699134 + outer loop + vertex 1.08766 1.62433 2.61278 + vertex 1.08767 1.62927 2.6128 + vertex 1.08518 1.62591 2.61532 + endloop + endfacet + facet normal 0.720896 0.0139646 0.692902 + outer loop + vertex 1.08512 1.62082 2.61549 + vertex 1.08766 1.62433 2.61278 + vertex 1.08518 1.62591 2.61532 + endloop + endfacet + facet normal 0.498345 0.0223107 0.866692 + outer loop + vertex 1.08518 1.62591 2.61532 + vertex 1.08186 1.62182 2.61734 + vertex 1.08512 1.62082 2.61549 + endloop + endfacet + facet normal 0.477029 0.0450815 0.87773 + outer loop + vertex 1.082 1.62696 2.617 + vertex 1.08186 1.62182 2.61734 + vertex 1.08518 1.62591 2.61532 + endloop + endfacet + facet normal 0.694026 0.00659513 0.71992 + outer loop + vertex 1.08767 1.62927 2.6128 + vertex 1.08763 1.63414 2.61279 + vertex 1.08522 1.63089 2.61515 + endloop + endfacet + facet normal 0.698254 0.0193134 0.715589 + outer loop + vertex 1.08518 1.62591 2.61532 + vertex 1.08767 1.62927 2.6128 + vertex 1.08522 1.63089 2.61515 + endloop + endfacet + facet normal 0.472617 0.0267253 0.880863 + outer loop + vertex 1.08522 1.63089 2.61515 + vertex 1.082 1.62696 2.617 + vertex 1.08518 1.62591 2.61532 + endloop + endfacet + facet normal 0.445522 0.0548761 0.893587 + outer loop + vertex 1.08206 1.632 2.61666 + vertex 1.082 1.62696 2.617 + vertex 1.08522 1.63089 2.61515 + endloop + endfacet + facet normal 0.662025 0.0258421 0.749037 + outer loop + vertex 1.08763 1.63414 2.61279 + vertex 1.0874 1.63903 2.61283 + vertex 1.08508 1.63575 2.61499 + endloop + endfacet + facet normal 0.667769 0.0430073 0.743126 + outer loop + vertex 1.08522 1.63089 2.61515 + vertex 1.08763 1.63414 2.61279 + vertex 1.08508 1.63575 2.61499 + endloop + endfacet + facet normal 0.442034 0.0416267 0.896032 + outer loop + vertex 1.08508 1.63575 2.61499 + vertex 1.08206 1.632 2.61666 + vertex 1.08522 1.63089 2.61515 + endloop + endfacet + facet normal 0.404548 0.0785262 0.911139 + outer loop + vertex 1.08178 1.63694 2.61636 + vertex 1.08206 1.632 2.61666 + vertex 1.08508 1.63575 2.61499 + endloop + endfacet + facet normal 0.608305 0.0503324 0.792106 + outer loop + vertex 1.0874 1.63903 2.61283 + vertex 1.0867 1.64436 2.61303 + vertex 1.08453 1.64051 2.61494 + endloop + endfacet + facet normal 0.616978 0.0801512 0.782888 + outer loop + vertex 1.08508 1.63575 2.61499 + vertex 1.0874 1.63903 2.61283 + vertex 1.08453 1.64051 2.61494 + endloop + endfacet + facet normal 0.398384 0.056397 0.915483 + outer loop + vertex 1.08453 1.64051 2.61494 + vertex 1.08178 1.63694 2.61636 + vertex 1.08508 1.63575 2.61499 + endloop + endfacet + facet normal 0.334633 0.113504 0.935488 + outer loop + vertex 1.08064 1.64206 2.61614 + vertex 1.08178 1.63694 2.61636 + vertex 1.08453 1.64051 2.61494 + endloop + endfacet + facet normal 0.544914 0.105934 0.831773 + outer loop + vertex 1.08359 1.64443 2.61506 + vertex 1.08453 1.64051 2.61494 + vertex 1.0867 1.64436 2.61303 + endloop + endfacet + facet normal 0.544656 0.111831 0.83117 + outer loop + vertex 1.08359 1.64443 2.61506 + vertex 1.0867 1.64436 2.61303 + vertex 1.08363 1.64904 2.61441 + endloop + endfacet + facet normal 0.498366 0.0717905 0.863989 + outer loop + vertex 1.08363 1.64904 2.61441 + vertex 1.0867 1.64436 2.61303 + vertex 1.08739 1.64884 2.61226 + endloop + endfacet + facet normal 0.31204 0.0463885 0.948936 + outer loop + vertex 1.08453 1.64051 2.61494 + vertex 1.08359 1.64443 2.61506 + vertex 1.08064 1.64206 2.61614 + endloop + endfacet + facet normal 0.497414 0.0189888 0.867305 + outer loop + vertex 1.08739 1.64884 2.61226 + vertex 1.08685 1.65275 2.61248 + vertex 1.08363 1.64904 2.61441 + endloop + endfacet + facet normal 0.471478 0.0483519 0.880551 + outer loop + vertex 1.08363 1.64904 2.61441 + vertex 1.08685 1.65275 2.61248 + vertex 1.08389 1.65393 2.614 + endloop + endfacet + facet normal 0.466409 0.0310935 0.884023 + outer loop + vertex 1.08685 1.65275 2.61248 + vertex 1.08659 1.65734 2.61246 + vertex 1.08389 1.65393 2.614 + endloop + endfacet + facet normal 0.412076 0.0845856 0.907215 + outer loop + vertex 1.08389 1.65393 2.614 + vertex 1.08659 1.65734 2.61246 + vertex 1.08304 1.65784 2.61402 + endloop + endfacet + facet normal 0.408167 0.0425839 0.911914 + outer loop + vertex 1.08659 1.65734 2.61246 + vertex 1.08643 1.66212 2.61231 + vertex 1.08304 1.65784 2.61402 + endloop + endfacet + facet normal 0.372124 0.0764277 0.925031 + outer loop + vertex 1.08304 1.65784 2.61402 + vertex 1.08643 1.66212 2.61231 + vertex 1.0828 1.66246 2.61374 + endloop + endfacet + facet normal 0.370151 0.0434677 0.927954 + outer loop + vertex 1.08643 1.66212 2.61231 + vertex 1.08653 1.66711 2.61203 + vertex 1.0828 1.66246 2.61374 + endloop + endfacet + facet normal 0.328072 0.0820746 0.94108 + outer loop + vertex 1.0828 1.66246 2.61374 + vertex 1.08653 1.66711 2.61203 + vertex 1.08278 1.66726 2.61333 + endloop + endfacet + facet normal 0.327491 0.0465368 0.943708 + outer loop + vertex 1.08653 1.66711 2.61203 + vertex 1.08674 1.6722 2.61171 + vertex 1.08278 1.66726 2.61333 + endloop + endfacet + facet normal 0.126974 0.174558 0.976426 + outer loop + vertex 1.09052 1.9098 2.58091 + vertex 1.08918 1.9148 2.58019 + vertex 1.0864 1.9113 2.58118 + endloop + endfacet + facet normal 0.13045 0.171803 0.976456 + outer loop + vertex 1.0846 1.91433 2.58089 + vertex 1.0864 1.9113 2.58118 + vertex 1.08918 1.9148 2.58019 + endloop + endfacet + facet normal 0.248521 0.150127 0.956922 + outer loop + vertex 1.08388 1.97878 2.57037 + vertex 1.08535 1.97463 2.57064 + vertex 1.08814 1.97873 2.56927 + endloop + endfacet + facet normal 0.248646 0.145449 0.957612 + outer loop + vertex 1.08388 1.97878 2.57037 + vertex 1.08814 1.97873 2.56927 + vertex 1.08412 1.98348 2.56959 + endloop + endfacet + facet normal 0.260578 0.155891 0.952784 + outer loop + vertex 1.08412 1.98348 2.56959 + vertex 1.08814 1.97873 2.56927 + vertex 1.08851 1.98312 2.56845 + endloop + endfacet + facet normal 0.262494 0.154798 0.952436 + outer loop + vertex 1.08535 1.97463 2.57064 + vertex 1.08388 1.97878 2.57037 + vertex 1.08057 1.97641 2.57167 + endloop + endfacet + facet normal 0.260708 0.159428 0.952163 + outer loop + vertex 1.08851 1.98312 2.56845 + vertex 1.08706 1.98633 2.56831 + vertex 1.08412 1.98348 2.56959 + endloop + endfacet + facet normal 0.272247 0.146962 0.950938 + outer loop + vertex 1.08412 1.98348 2.56959 + vertex 1.08706 1.98633 2.56831 + vertex 1.08423 1.98806 2.56885 + endloop + endfacet + facet normal 0.281908 0.12318 0.951501 + outer loop + vertex 1.09022 1.99375 2.56622 + vertex 1.09074 1.99768 2.56556 + vertex 1.08772 1.99546 2.56674 + endloop + endfacet + facet normal 0.291517 0.13879 0.946443 + outer loop + vertex 1.08772 1.99546 2.56674 + vertex 1.08725 1.99102 2.56754 + vertex 1.09022 1.99375 2.56622 + endloop + endfacet + facet normal 0.331653 0.132336 0.934074 + outer loop + vertex 1.08772 1.99546 2.56674 + vertex 1.08387 1.99634 2.56799 + vertex 1.08725 1.99102 2.56754 + endloop + endfacet + facet normal 0.29313 0.10715 0.950049 + outer loop + vertex 1.09074 1.99768 2.56556 + vertex 1.08729 1.99842 2.56654 + vertex 1.08772 1.99546 2.56674 + endloop + endfacet + facet normal 0.328081 0.111297 0.93807 + outer loop + vertex 1.08729 1.99842 2.56654 + vertex 1.08387 1.99634 2.56799 + vertex 1.08772 1.99546 2.56674 + endloop + endfacet + facet normal 0.345621 0.0801086 0.934948 + outer loop + vertex 1.08729 1.99842 2.56654 + vertex 1.0858 2.00176 2.56681 + vertex 1.08387 1.99634 2.56799 + endloop + endfacet + facet normal 0.355312 0.0759385 0.931658 + outer loop + vertex 1.0858 2.00176 2.56681 + vertex 1.08215 2.00109 2.56825 + vertex 1.08387 1.99634 2.56799 + endloop + endfacet + facet normal 0.334379 0.0676089 0.940011 + outer loop + vertex 1.08887 2.00391 2.56557 + vertex 1.09021 2.00809 2.56479 + vertex 1.08683 2.00591 2.56615 + endloop + endfacet + facet normal 0.333061 0.0661088 0.940585 + outer loop + vertex 1.08683 2.00591 2.56615 + vertex 1.0858 2.00176 2.56681 + vertex 1.08887 2.00391 2.56557 + endloop + endfacet + facet normal 0.36284 0.0570073 0.930106 + outer loop + vertex 1.08683 2.00591 2.56615 + vertex 1.08311 2.00595 2.5676 + vertex 1.0858 2.00176 2.56681 + endloop + endfacet + facet normal 0.359256 0.0544144 0.931651 + outer loop + vertex 1.08311 2.00595 2.5676 + vertex 1.08215 2.00109 2.56825 + vertex 1.0858 2.00176 2.56681 + endloop + endfacet + facet normal 0.346324 0.0851769 0.93424 + outer loop + vertex 1.09021 2.00809 2.56479 + vertex 1.08948 2.0134 2.56458 + vertex 1.08634 2.01001 2.56605 + endloop + endfacet + facet normal 0.337063 0.0630433 0.939369 + outer loop + vertex 1.08683 2.00591 2.56615 + vertex 1.09021 2.00809 2.56479 + vertex 1.08634 2.01001 2.56605 + endloop + endfacet + facet normal 0.362716 0.0659185 0.929565 + outer loop + vertex 1.08634 2.01001 2.56605 + vertex 1.08311 2.00595 2.5676 + vertex 1.08683 2.00591 2.56615 + endloop + endfacet + facet normal 0.375365 0.0542076 0.92529 + outer loop + vertex 1.08259 2.01159 2.56748 + vertex 1.08311 2.00595 2.5676 + vertex 1.08634 2.01001 2.56605 + endloop + endfacet + facet normal 0.364347 0.0930858 0.926599 + outer loop + vertex 1.08948 2.0134 2.56458 + vertex 1.08908 2.01826 2.56425 + vertex 1.08587 2.01507 2.56583 + endloop + endfacet + facet normal 0.357051 0.0738876 0.931158 + outer loop + vertex 1.08634 2.01001 2.56605 + vertex 1.08948 2.0134 2.56458 + vertex 1.08587 2.01507 2.56583 + endloop + endfacet + facet normal 0.382745 0.0757854 0.92074 + outer loop + vertex 1.08587 2.01507 2.56583 + vertex 1.08259 2.01159 2.56748 + vertex 1.08634 2.01001 2.56605 + endloop + endfacet + facet normal 0.396424 0.0606677 0.916061 + outer loop + vertex 1.08224 2.01679 2.56729 + vertex 1.08259 2.01159 2.56748 + vertex 1.08587 2.01507 2.56583 + endloop + endfacet + facet normal 0.385063 0.0933911 0.918153 + outer loop + vertex 1.08908 2.01826 2.56425 + vertex 1.08855 2.0232 2.56397 + vertex 1.08547 2.02007 2.56558 + endloop + endfacet + facet normal 0.378407 0.0769448 0.922436 + outer loop + vertex 1.08587 2.01507 2.56583 + vertex 1.08908 2.01826 2.56425 + vertex 1.08547 2.02007 2.56558 + endloop + endfacet + facet normal 0.403124 0.078404 0.91178 + outer loop + vertex 1.08547 2.02007 2.56558 + vertex 1.08224 2.01679 2.56729 + vertex 1.08587 2.01507 2.56583 + endloop + endfacet + facet normal 0.418261 0.060664 0.906299 + outer loop + vertex 1.08187 2.02185 2.56712 + vertex 1.08224 2.01679 2.56729 + vertex 1.08547 2.02007 2.56558 + endloop + endfacet + facet normal 0.409968 0.0895537 0.907693 + outer loop + vertex 1.08855 2.0232 2.56397 + vertex 1.08749 2.02747 2.56402 + vertex 1.08498 2.02485 2.56542 + endloop + endfacet + facet normal 0.403625 0.0720105 0.912086 + outer loop + vertex 1.08547 2.02007 2.56558 + vertex 1.08855 2.0232 2.56397 + vertex 1.08498 2.02485 2.56542 + endloop + endfacet + facet normal 0.423317 0.073731 0.902976 + outer loop + vertex 1.08498 2.02485 2.56542 + vertex 1.08187 2.02185 2.56712 + vertex 1.08547 2.02007 2.56558 + endloop + endfacet + facet normal 0.435538 0.0584053 0.898273 + outer loop + vertex 1.08159 2.02672 2.56694 + vertex 1.08187 2.02185 2.56712 + vertex 1.08498 2.02485 2.56542 + endloop + endfacet + facet normal 0.436162 0.0816345 0.896158 + outer loop + vertex 1.08749 2.02747 2.56402 + vertex 1.08801 2.03249 2.56331 + vertex 1.08455 2.02948 2.56527 + endloop + endfacet + facet normal 0.428733 0.0678359 0.900881 + outer loop + vertex 1.08498 2.02485 2.56542 + vertex 1.08749 2.02747 2.56402 + vertex 1.08455 2.02948 2.56527 + endloop + endfacet + facet normal 0.439905 0.0686868 0.895414 + outer loop + vertex 1.08455 2.02948 2.56527 + vertex 1.08159 2.02672 2.56694 + vertex 1.08498 2.02485 2.56542 + endloop + endfacet + facet normal 0.442569 0.0651904 0.894362 + outer loop + vertex 1.08097 2.03163 2.56689 + vertex 1.08159 2.02672 2.56694 + vertex 1.08455 2.02948 2.56527 + endloop + endfacet + facet normal 0.445018 0.0693129 0.892835 + outer loop + vertex 1.08408 2.03347 2.5652 + vertex 1.08455 2.02948 2.56527 + vertex 1.08801 2.03249 2.56331 + endloop + endfacet + facet normal 0.447847 0.0862162 0.889944 + outer loop + vertex 1.08408 2.03347 2.5652 + vertex 1.08801 2.03249 2.56331 + vertex 1.08503 2.03779 2.5643 + endloop + endfacet + facet normal 0.460017 0.0943844 0.882879 + outer loop + vertex 1.08503 2.03779 2.5643 + vertex 1.08801 2.03249 2.56331 + vertex 1.08853 2.03758 2.5625 + endloop + endfacet + facet normal 0.444452 0.0692509 0.893122 + outer loop + vertex 1.08455 2.02948 2.56527 + vertex 1.08408 2.03347 2.5652 + vertex 1.08097 2.03163 2.56689 + endloop + endfacet + facet normal 0.459999 0.0909821 0.883246 + outer loop + vertex 1.08853 2.03758 2.5625 + vertex 1.08765 2.0418 2.56252 + vertex 1.08503 2.03779 2.5643 + endloop + endfacet + facet normal 0.462909 0.0885137 0.881975 + outer loop + vertex 1.08503 2.03779 2.5643 + vertex 1.08765 2.0418 2.56252 + vertex 1.08418 2.04325 2.5642 + endloop + endfacet + facet normal 0.461887 0.0850353 0.882853 + outer loop + vertex 1.08765 2.0418 2.56252 + vertex 1.08708 2.04668 2.56235 + vertex 1.08418 2.04325 2.5642 + endloop + endfacet + facet normal 0.451058 0.0965948 0.887252 + outer loop + vertex 1.08418 2.04325 2.5642 + vertex 1.08708 2.04668 2.56235 + vertex 1.08353 2.04825 2.56399 + endloop + endfacet + facet normal 0.448668 0.0891242 0.889244 + outer loop + vertex 1.08708 2.04668 2.56235 + vertex 1.08653 2.05157 2.56214 + vertex 1.08353 2.04825 2.56399 + endloop + endfacet + facet normal 0.423779 0.116653 0.898222 + outer loop + vertex 1.08353 2.04825 2.56399 + vertex 1.08653 2.05157 2.56214 + vertex 1.0825 2.05352 2.56379 + endloop + endfacet + facet normal 0.417614 0.0997102 0.903137 + outer loop + vertex 1.08653 2.05157 2.56214 + vertex 1.0859 2.05662 2.56187 + vertex 1.0825 2.05352 2.56379 + endloop + endfacet + facet normal 0.399398 0.123001 0.908489 + outer loop + vertex 1.0825 2.05352 2.56379 + vertex 1.0859 2.05662 2.56187 + vertex 1.08278 2.05723 2.56316 + endloop + endfacet + facet normal 0.435255 0.117968 0.892545 + outer loop + vertex 1.08912 2.05831 2.56012 + vertex 1.08982 2.06265 2.5592 + vertex 1.08681 2.06058 2.56094 + endloop + endfacet + facet normal 0.429629 0.110926 0.896166 + outer loop + vertex 1.08681 2.06058 2.56094 + vertex 1.0859 2.05662 2.56187 + vertex 1.08912 2.05831 2.56012 + endloop + endfacet + facet normal 0.375991 0.12831 0.917697 + outer loop + vertex 1.08681 2.06058 2.56094 + vertex 1.08304 2.06089 2.56245 + vertex 1.0859 2.05662 2.56187 + endloop + endfacet + facet normal 0.402216 0.147848 0.903528 + outer loop + vertex 1.08304 2.06089 2.56245 + vertex 1.08278 2.05723 2.56316 + vertex 1.0859 2.05662 2.56187 + endloop + endfacet + facet normal 0.408166 0.128485 0.903821 + outer loop + vertex 1.08982 2.06265 2.5592 + vertex 1.08799 2.06864 2.55918 + vertex 1.0856 2.06461 2.56083 + endloop + endfacet + facet normal 0.415666 0.150245 0.897022 + outer loop + vertex 1.08681 2.06058 2.56094 + vertex 1.08982 2.06265 2.5592 + vertex 1.0856 2.06461 2.56083 + endloop + endfacet + facet normal 0.376202 0.138888 0.916069 + outer loop + vertex 1.0856 2.06461 2.56083 + vertex 1.08304 2.06089 2.56245 + vertex 1.08681 2.06058 2.56094 + endloop + endfacet + facet normal 0.31367 0.182472 0.931834 + outer loop + vertex 1.08822 2.07622 2.55783 + vertex 1.08631 2.08166 2.55741 + vertex 1.08421 2.07827 2.55878 + endloop + endfacet + facet normal 0.178665 0.360798 0.915371 + outer loop + vertex 1.08874 2.11304 2.54857 + vertex 1.08636 2.1169 2.54751 + vertex 1.08381 2.11306 2.54952 + endloop + endfacet + facet normal 0.178468 0.360924 0.91536 + outer loop + vertex 1.08381 2.11306 2.54952 + vertex 1.08636 2.1169 2.54751 + vertex 1.08263 2.11675 2.5483 + endloop + endfacet + facet normal 0.167685 0.536153 0.827298 + outer loop + vertex 1.08996 2.11901 2.54583 + vertex 1.08844 2.12173 2.54438 + vertex 1.08602 2.12032 2.54579 + endloop + endfacet + facet normal 0.140822 0.456987 0.878255 + outer loop + vertex 1.08602 2.12032 2.54579 + vertex 1.08636 2.1169 2.54751 + vertex 1.08996 2.11901 2.54583 + endloop + endfacet + facet normal 0.143848 0.457032 0.877741 + outer loop + vertex 1.08602 2.12032 2.54579 + vertex 1.08174 2.11973 2.54679 + vertex 1.08636 2.1169 2.54751 + endloop + endfacet + facet normal 0.161894 0.482254 0.860942 + outer loop + vertex 1.08174 2.11973 2.54679 + vertex 1.08263 2.11675 2.5483 + vertex 1.08636 2.1169 2.54751 + endloop + endfacet + facet normal 0.142666 0.870926 0.470249 + outer loop + vertex 1.08444 2.1252 2.54121 + vertex 1.08914 2.12406 2.54189 + vertex 1.08655 2.12623 2.53865 + endloop + endfacet + facet normal 0.073141 0.901927 0.42565 + outer loop + vertex 1.08166 2.12655 2.53881 + vertex 1.08444 2.1252 2.54121 + vertex 1.08655 2.12623 2.53865 + endloop + endfacet + facet normal 0.0959338 0.614827 0.782805 + outer loop + vertex 1.08844 2.12173 2.54438 + vertex 1.08404 2.12295 2.54396 + vertex 1.08602 2.12032 2.54579 + endloop + endfacet + facet normal 0.129566 0.706279 0.695976 + outer loop + vertex 1.08844 2.12173 2.54438 + vertex 1.08914 2.12406 2.54189 + vertex 1.08404 2.12295 2.54396 + endloop + endfacet + facet normal 0.0930344 0.76472 0.637611 + outer loop + vertex 1.08914 2.12406 2.54189 + vertex 1.08444 2.1252 2.54121 + vertex 1.08404 2.12295 2.54396 + endloop + endfacet + facet normal 0.0993031 0.616279 0.781242 + outer loop + vertex 1.08602 2.12032 2.54579 + vertex 1.08404 2.12295 2.54396 + vertex 1.08174 2.11973 2.54679 + endloop + endfacet + facet normal 0.00677167 0.422655 0.906265 + outer loop + vertex 1.09 2.13212 2.53 + vertex 1.085 2.1322 2.53 + vertex 1.08861 2.12888 2.53152 + endloop + endfacet + facet normal 0.0323201 0.445189 0.894853 + outer loop + vertex 1.08861 2.12888 2.53152 + vertex 1.085 2.1322 2.53 + vertex 1.08369 2.12901 2.53164 + endloop + endfacet + facet normal 0.0326531 0.919638 0.391407 + outer loop + vertex 1.08861 2.12888 2.53152 + vertex 1.08369 2.12901 2.53164 + vertex 1.08794 2.12737 2.53512 + endloop + endfacet + facet normal 0.0474402 0.925383 0.376053 + outer loop + vertex 1.08794 2.12737 2.53512 + vertex 1.08369 2.12901 2.53164 + vertex 1.08294 2.12759 2.53522 + endloop + endfacet + facet normal 0.072021 0.951144 0.300229 + outer loop + vertex 1.08655 2.12623 2.53865 + vertex 1.08294 2.12759 2.53522 + vertex 1.08166 2.12655 2.53881 + endloop + endfacet + facet normal 0.047275 0.944935 0.323827 + outer loop + vertex 1.08794 2.12737 2.53512 + vertex 1.08294 2.12759 2.53522 + vertex 1.08655 2.12623 2.53865 + endloop + endfacet + facet normal -0.0516719 -0.932763 -0.356767 + outer loop + vertex 1.095 0.893683 2.525 + vertex 1.09309 0.893596 2.5255 + vertex 1.09 0.89396 2.525 + endloop + endfacet + facet normal -0.0793209 -0.973042 -0.216557 + outer loop + vertex 1.09309 0.893596 2.5255 + vertex 1.08838 0.893678 2.52686 + vertex 1.09 0.89396 2.525 + endloop + endfacet + facet normal 0.0332465 -0.984041 0.174809 + outer loop + vertex 1.09309 0.893596 2.5255 + vertex 1.09046 0.89405 2.52856 + vertex 1.08838 0.893678 2.52686 + endloop + endfacet + facet normal -0.00495768 -0.989746 0.142755 + outer loop + vertex 1.09418 0.893905 2.52769 + vertex 1.09046 0.89405 2.52856 + vertex 1.09309 0.893596 2.5255 + endloop + endfacet + facet normal 0.0384958 -0.946216 0.321237 + outer loop + vertex 1.09046 0.89405 2.52856 + vertex 1.09418 0.893905 2.52769 + vertex 1.09397 0.895108 2.53125 + endloop + endfacet + facet normal 0.0543397 -0.951543 0.302676 + outer loop + vertex 1.08865 0.895136 2.5323 + vertex 1.09046 0.89405 2.52856 + vertex 1.09397 0.895108 2.53125 + endloop + endfacet + facet normal 0.0742185 -0.912191 0.402987 + outer loop + vertex 1.09397 0.895108 2.53125 + vertex 1.09169 0.896721 2.53532 + vertex 1.08865 0.895136 2.5323 + endloop + endfacet + facet normal 0.0865931 -0.915721 0.392374 + outer loop + vertex 1.09169 0.896721 2.53532 + vertex 1.08678 0.896586 2.5361 + vertex 1.08865 0.895136 2.5323 + endloop + endfacet + facet normal 0.0957547 -0.884748 0.456128 + outer loop + vertex 1.09169 0.896721 2.53532 + vertex 1.08951 0.898339 2.53892 + vertex 1.08678 0.896586 2.5361 + endloop + endfacet + facet normal 0.0949152 -0.885035 0.455746 + outer loop + vertex 1.09438 0.89865 2.53851 + vertex 1.08951 0.898339 2.53892 + vertex 1.09169 0.896721 2.53532 + endloop + endfacet + facet normal 0.098054 -0.847616 0.521472 + outer loop + vertex 1.08951 0.898339 2.53892 + vertex 1.09438 0.89865 2.53851 + vertex 1.09164 0.900635 2.54225 + endloop + endfacet + facet normal 0.11521 -0.850806 0.512695 + outer loop + vertex 1.08726 0.899728 2.54173 + vertex 1.08951 0.898339 2.53892 + vertex 1.09164 0.900635 2.54225 + endloop + endfacet + facet normal 0.151669 -0.775015 0.613472 + outer loop + vertex 1.09126 0.902862 2.54516 + vertex 1.09164 0.900635 2.54225 + vertex 1.09496 0.903013 2.54444 + endloop + endfacet + facet normal 0.106799 -0.782568 0.613336 + outer loop + vertex 1.09126 0.902862 2.54516 + vertex 1.08716 0.902056 2.54485 + vertex 1.09164 0.900635 2.54225 + endloop + endfacet + facet normal 0.0937359 -0.795923 0.598097 + outer loop + vertex 1.08716 0.902056 2.54485 + vertex 1.08726 0.899728 2.54173 + vertex 1.09164 0.900635 2.54225 + endloop + endfacet + facet normal 0.0609106 -0.616932 0.784656 + outer loop + vertex 1.09126 0.902862 2.54516 + vertex 1.08986 0.905142 2.54706 + vertex 1.08716 0.902056 2.54485 + endloop + endfacet + facet normal 0.173944 -0.629082 0.757627 + outer loop + vertex 1.09496 0.903013 2.54444 + vertex 1.0933 0.904855 2.54635 + vertex 1.09126 0.902862 2.54516 + endloop + endfacet + facet normal 0.11617 -0.593164 0.796656 + outer loop + vertex 1.0933 0.904855 2.54635 + vertex 1.08986 0.905142 2.54706 + vertex 1.09126 0.902862 2.54516 + endloop + endfacet + facet normal 0.154196 -0.402089 0.902523 + outer loop + vertex 1.0933 0.904855 2.54635 + vertex 1.09426 0.908718 2.5479 + vertex 1.08986 0.905142 2.54706 + endloop + endfacet + facet normal 0.197787 -0.44848 0.871634 + outer loop + vertex 1.09426 0.908718 2.5479 + vertex 1.08884 0.909001 2.54928 + vertex 1.08986 0.905142 2.54706 + endloop + endfacet + facet normal 0.366392 -0.199136 0.908901 + outer loop + vertex 1.0894 0.952989 2.56043 + vertex 1.08685 0.950546 2.56092 + vertex 1.08875 0.948884 2.55979 + endloop + endfacet + facet normal 0.410796 -0.203031 0.888834 + outer loop + vertex 1.0894 0.952989 2.56043 + vertex 1.08875 0.948884 2.55979 + vertex 1.09308 0.954302 2.55903 + endloop + endfacet + facet normal 0.361165 -0.159112 0.918827 + outer loop + vertex 1.09308 0.954302 2.55903 + vertex 1.08875 0.948884 2.55979 + vertex 1.09305 0.948873 2.5581 + endloop + endfacet + facet normal 0.342312 -0.17104 0.923887 + outer loop + vertex 1.0894 0.952989 2.56043 + vertex 1.08691 0.953698 2.56148 + vertex 1.08685 0.950546 2.56092 + endloop + endfacet + facet normal 0.399716 -0.156632 0.903157 + outer loop + vertex 1.0894 0.952989 2.56043 + vertex 1.09308 0.954302 2.55903 + vertex 1.09057 0.956955 2.5606 + endloop + endfacet + facet normal 0.350924 -0.14312 0.925402 + outer loop + vertex 1.09057 0.956955 2.5606 + vertex 1.08691 0.953698 2.56148 + vertex 1.0894 0.952989 2.56043 + endloop + endfacet + facet normal 0.360216 -0.155056 0.919892 + outer loop + vertex 1.08743 0.958207 2.56204 + vertex 1.08691 0.953698 2.56148 + vertex 1.09057 0.956955 2.5606 + endloop + endfacet + facet normal 0.230097 -0.143862 0.962476 + outer loop + vertex 1.08836 1.07868 2.57795 + vertex 1.09325 1.08348 2.5775 + vertex 1.08842 1.08378 2.5787 + endloop + endfacet + facet normal 0.284303 -0.0249327 0.95841 + outer loop + vertex 1.09212 1.30739 2.60755 + vertex 1.09219 1.31256 2.60767 + vertex 1.08812 1.30796 2.60875 + endloop + endfacet + facet normal 0.32125 -0.0607063 0.945047 + outer loop + vertex 1.08812 1.30796 2.60875 + vertex 1.09219 1.31256 2.60767 + vertex 1.08799 1.31313 2.60913 + endloop + endfacet + facet normal 0.32495 -0.0339017 0.945123 + outer loop + vertex 1.09219 1.31256 2.60767 + vertex 1.09204 1.31797 2.60791 + vertex 1.08799 1.31313 2.60913 + endloop + endfacet + facet normal 0.37499 -0.0812295 0.923463 + outer loop + vertex 1.08799 1.31313 2.60913 + vertex 1.09204 1.31797 2.60791 + vertex 1.08741 1.31888 2.60987 + endloop + endfacet + facet normal 0.293832 -0.189272 0.93693 + outer loop + vertex 1.08901 1.32339 2.61028 + vertex 1.08675 1.32237 2.61078 + vertex 1.08741 1.31888 2.60987 + endloop + endfacet + facet normal 0.52062 -0.258272 0.813788 + outer loop + vertex 1.08901 1.32339 2.61028 + vertex 1.08741 1.31888 2.60987 + vertex 1.09199 1.32374 2.60849 + endloop + endfacet + facet normal 0.373478 -0.0887247 0.923386 + outer loop + vertex 1.09199 1.32374 2.60849 + vertex 1.08741 1.31888 2.60987 + vertex 1.09204 1.31797 2.60791 + endloop + endfacet + facet normal 0.274032 -0.138663 0.951672 + outer loop + vertex 1.08901 1.32339 2.61028 + vertex 1.0874 1.32533 2.61103 + vertex 1.08675 1.32237 2.61078 + endloop + endfacet + facet normal 0.604693 -0.0706232 0.793322 + outer loop + vertex 1.09199 1.32374 2.60849 + vertex 1.09293 1.32943 2.60828 + vertex 1.09019 1.32693 2.61014 + endloop + endfacet + facet normal 0.523009 -0.141209 0.840548 + outer loop + vertex 1.08901 1.32339 2.61028 + vertex 1.09199 1.32374 2.60849 + vertex 1.09019 1.32693 2.61014 + endloop + endfacet + facet normal 0.341347 -0.0768014 0.936795 + outer loop + vertex 1.09019 1.32693 2.61014 + vertex 1.0874 1.32533 2.61103 + vertex 1.08901 1.32339 2.61028 + endloop + endfacet + facet normal 0.34511 -0.0844889 0.934752 + outer loop + vertex 1.08804 1.32861 2.61109 + vertex 1.0874 1.32533 2.61103 + vertex 1.09019 1.32693 2.61014 + endloop + endfacet + facet normal 0.608205 -0.00493759 0.793764 + outer loop + vertex 1.09293 1.32943 2.60828 + vertex 1.09305 1.33452 2.60822 + vertex 1.09047 1.33135 2.61017 + endloop + endfacet + facet normal 0.588801 -0.0429117 0.807138 + outer loop + vertex 1.09019 1.32693 2.61014 + vertex 1.09293 1.32943 2.60828 + vertex 1.09047 1.33135 2.61017 + endloop + endfacet + facet normal 0.382245 -0.0306378 0.923553 + outer loop + vertex 1.09047 1.33135 2.61017 + vertex 1.08804 1.32861 2.61109 + vertex 1.09019 1.32693 2.61014 + endloop + endfacet + facet normal 0.356902 -0.00467405 0.93413 + outer loop + vertex 1.08731 1.3323 2.61139 + vertex 1.08804 1.32861 2.61109 + vertex 1.09047 1.33135 2.61017 + endloop + endfacet + facet normal 0.612007 0.0123315 0.790756 + outer loop + vertex 1.09305 1.33452 2.60822 + vertex 1.09299 1.33959 2.60819 + vertex 1.09033 1.33616 2.6103 + endloop + endfacet + facet normal 0.606382 -0.00258389 0.795169 + outer loop + vertex 1.09047 1.33135 2.61017 + vertex 1.09305 1.33452 2.60822 + vertex 1.09033 1.33616 2.6103 + endloop + endfacet + facet normal 0.354499 -0.0137461 0.934955 + outer loop + vertex 1.09033 1.33616 2.6103 + vertex 1.08731 1.3323 2.61139 + vertex 1.09047 1.33135 2.61017 + endloop + endfacet + facet normal 0.378406 -0.0352596 0.924968 + outer loop + vertex 1.08699 1.33728 2.61171 + vertex 1.08731 1.3323 2.61139 + vertex 1.09033 1.33616 2.6103 + endloop + endfacet + facet normal 0.637535 0.00598386 0.770398 + outer loop + vertex 1.09299 1.33959 2.60819 + vertex 1.09297 1.34466 2.60817 + vertex 1.09026 1.34122 2.61043 + endloop + endfacet + facet normal 0.63112 -0.0118589 0.775594 + outer loop + vertex 1.09033 1.33616 2.6103 + vertex 1.09299 1.33959 2.60819 + vertex 1.09026 1.34122 2.61043 + endloop + endfacet + facet normal 0.383239 -0.0188802 0.923456 + outer loop + vertex 1.09026 1.34122 2.61043 + vertex 1.08699 1.33728 2.61171 + vertex 1.09033 1.33616 2.6103 + endloop + endfacet + facet normal 0.420321 -0.0553936 0.905683 + outer loop + vertex 1.08697 1.34238 2.61203 + vertex 1.08699 1.33728 2.61171 + vertex 1.09026 1.34122 2.61043 + endloop + endfacet + facet normal 0.667148 -0.00956502 0.744863 + outer loop + vertex 1.09297 1.34466 2.60817 + vertex 1.09301 1.34971 2.60819 + vertex 1.09031 1.34627 2.61056 + endloop + endfacet + facet normal 0.661299 -0.0263649 0.749659 + outer loop + vertex 1.09026 1.34122 2.61043 + vertex 1.09297 1.34466 2.60817 + vertex 1.09031 1.34627 2.61056 + endloop + endfacet + facet normal 0.42864 -0.0280408 0.90304 + outer loop + vertex 1.09031 1.34627 2.61056 + vertex 1.08697 1.34238 2.61203 + vertex 1.09026 1.34122 2.61043 + endloop + endfacet + facet normal 0.455512 -0.0565575 0.888431 + outer loop + vertex 1.08705 1.34737 2.61231 + vertex 1.08697 1.34238 2.61203 + vertex 1.09031 1.34627 2.61056 + endloop + endfacet + facet normal 0.68951 -0.0126321 0.724166 + outer loop + vertex 1.09301 1.34971 2.60819 + vertex 1.09307 1.35471 2.60822 + vertex 1.09039 1.35124 2.61071 + endloop + endfacet + facet normal 0.683069 -0.0326341 0.729624 + outer loop + vertex 1.09031 1.34627 2.61056 + vertex 1.09301 1.34971 2.60819 + vertex 1.09039 1.35124 2.61071 + endloop + endfacet + facet normal 0.462077 -0.0335696 0.886204 + outer loop + vertex 1.09039 1.35124 2.61071 + vertex 1.08705 1.34737 2.61231 + vertex 1.09031 1.34627 2.61056 + endloop + endfacet + facet normal 0.486744 -0.0610391 0.87141 + outer loop + vertex 1.08713 1.35231 2.61261 + vertex 1.08705 1.34737 2.61231 + vertex 1.09039 1.35124 2.61071 + endloop + endfacet + facet normal 0.710192 0.000639864 0.704008 + outer loop + vertex 1.09307 1.35471 2.60822 + vertex 1.09306 1.35965 2.60823 + vertex 1.09045 1.35615 2.61086 + endloop + endfacet + facet normal 0.701351 -0.0303937 0.712168 + outer loop + vertex 1.09039 1.35124 2.61071 + vertex 1.09307 1.35471 2.60822 + vertex 1.09045 1.35615 2.61086 + endloop + endfacet + facet normal 0.494405 -0.0327549 0.868614 + outer loop + vertex 1.09045 1.35615 2.61086 + vertex 1.08713 1.35231 2.61261 + vertex 1.09039 1.35124 2.61071 + endloop + endfacet + facet normal 0.508386 -0.0489115 0.859739 + outer loop + vertex 1.08717 1.35723 2.61286 + vertex 1.08713 1.35231 2.61261 + vertex 1.09045 1.35615 2.61086 + endloop + endfacet + facet normal 0.730053 0.0163142 0.683196 + outer loop + vertex 1.09306 1.35965 2.60823 + vertex 1.09298 1.36454 2.6082 + vertex 1.09046 1.36103 2.61097 + endloop + endfacet + facet normal 0.721696 -0.016946 0.692002 + outer loop + vertex 1.09045 1.35615 2.61086 + vertex 1.09306 1.35965 2.60823 + vertex 1.09046 1.36103 2.61097 + endloop + endfacet + facet normal 0.515823 -0.0201997 0.856457 + outer loop + vertex 1.09046 1.36103 2.61097 + vertex 1.08717 1.35723 2.61286 + vertex 1.09045 1.35615 2.61086 + endloop + endfacet + facet normal 0.529257 -0.0361968 0.847689 + outer loop + vertex 1.08719 1.3622 2.61306 + vertex 1.08717 1.35723 2.61286 + vertex 1.09046 1.36103 2.61097 + endloop + endfacet + facet normal 0.749969 0.0372725 0.660422 + outer loop + vertex 1.09298 1.36454 2.6082 + vertex 1.09286 1.36941 2.60805 + vertex 1.09045 1.36599 2.61099 + endloop + endfacet + facet normal 0.74083 -0.000495735 0.671693 + outer loop + vertex 1.09046 1.36103 2.61097 + vertex 1.09298 1.36454 2.6082 + vertex 1.09045 1.36599 2.61099 + endloop + endfacet + facet normal 0.538353 -0.00192918 0.842717 + outer loop + vertex 1.09045 1.36599 2.61099 + vertex 1.08719 1.3622 2.61306 + vertex 1.09046 1.36103 2.61097 + endloop + endfacet + facet normal 0.559747 -0.0283024 0.82818 + outer loop + vertex 1.08721 1.36739 2.61322 + vertex 1.08719 1.3622 2.61306 + vertex 1.09045 1.36599 2.61099 + endloop + endfacet + facet normal 0.770462 0.0419868 0.636102 + outer loop + vertex 1.09286 1.36941 2.60805 + vertex 1.09286 1.3742 2.60774 + vertex 1.09046 1.37121 2.61084 + endloop + endfacet + facet normal 0.762877 0.0160515 0.646345 + outer loop + vertex 1.09045 1.36599 2.61099 + vertex 1.09286 1.36941 2.60805 + vertex 1.09046 1.37121 2.61084 + endloop + endfacet + facet normal 0.574494 0.021436 0.818228 + outer loop + vertex 1.09046 1.37121 2.61084 + vertex 1.08721 1.36739 2.61322 + vertex 1.09045 1.36599 2.61099 + endloop + endfacet + facet normal 0.620006 -0.0388306 0.783636 + outer loop + vertex 1.08722 1.37321 2.61351 + vertex 1.08721 1.36739 2.61322 + vertex 1.09046 1.37121 2.61084 + endloop + endfacet + facet normal 0.804706 0.0461032 0.59188 + outer loop + vertex 1.09286 1.3742 2.60774 + vertex 1.09307 1.37797 2.60716 + vertex 1.09085 1.37713 2.61024 + endloop + endfacet + facet normal 0.785935 0.0109379 0.618212 + outer loop + vertex 1.09046 1.37121 2.61084 + vertex 1.09286 1.3742 2.60774 + vertex 1.09085 1.37713 2.61024 + endloop + endfacet + facet normal 0.647254 0.0348603 0.761477 + outer loop + vertex 1.09085 1.37713 2.61024 + vertex 1.08722 1.37321 2.61351 + vertex 1.09046 1.37121 2.61084 + endloop + endfacet + facet normal 0.701668 -0.0583476 0.710111 + outer loop + vertex 1.08805 1.37929 2.61319 + vertex 1.08722 1.37321 2.61351 + vertex 1.09085 1.37713 2.61024 + endloop + endfacet + facet normal 0.873615 0.0618527 0.482671 + outer loop + vertex 1.09402 1.38055 2.60515 + vertex 1.09409 1.3845 2.60452 + vertex 1.09261 1.38139 2.6076 + endloop + endfacet + facet normal 0.873047 0.0557955 0.484434 + outer loop + vertex 1.09307 1.37797 2.60716 + vertex 1.09402 1.38055 2.60515 + vertex 1.09261 1.38139 2.6076 + endloop + endfacet + facet normal 0.806743 0.0335887 0.589946 + outer loop + vertex 1.09307 1.37797 2.60716 + vertex 1.09261 1.38139 2.6076 + vertex 1.09085 1.37713 2.61024 + endloop + endfacet + facet normal 0.824356 0.011445 0.565957 + outer loop + vertex 1.09085 1.37713 2.61024 + vertex 1.09261 1.38139 2.6076 + vertex 1.09057 1.38274 2.61053 + endloop + endfacet + facet normal 0.724581 -5.51319e-06 0.68919 + outer loop + vertex 1.09057 1.38274 2.61053 + vertex 1.08805 1.37929 2.61319 + vertex 1.09085 1.37713 2.61024 + endloop + endfacet + facet normal 0.743432 -0.0300264 0.668138 + outer loop + vertex 1.0882 1.38462 2.61326 + vertex 1.08805 1.37929 2.61319 + vertex 1.09057 1.38274 2.61053 + endloop + endfacet + facet normal 0.885087 0.0433714 0.4634 + outer loop + vertex 1.09409 1.3845 2.60452 + vertex 1.09402 1.38942 2.60419 + vertex 1.09244 1.38604 2.60753 + endloop + endfacet + facet normal 0.884388 0.0393218 0.465092 + outer loop + vertex 1.09261 1.38139 2.6076 + vertex 1.09409 1.3845 2.60452 + vertex 1.09244 1.38604 2.60753 + endloop + endfacet + facet normal 0.82957 0.0385747 0.557068 + outer loop + vertex 1.09261 1.38139 2.6076 + vertex 1.09244 1.38604 2.60753 + vertex 1.09057 1.38274 2.61053 + endloop + endfacet + facet normal 0.845829 0.00787573 0.533397 + outer loop + vertex 1.09244 1.38604 2.60753 + vertex 1.0905 1.38781 2.61058 + vertex 1.09057 1.38274 2.61053 + endloop + endfacet + facet normal 0.75593 0.00546517 0.65463 + outer loop + vertex 1.0905 1.38781 2.61058 + vertex 1.0882 1.38462 2.61326 + vertex 1.09057 1.38274 2.61053 + endloop + endfacet + facet normal 0.766401 -0.0124393 0.642241 + outer loop + vertex 1.08822 1.38968 2.61333 + vertex 1.0882 1.38462 2.61326 + vertex 1.0905 1.38781 2.61058 + endloop + endfacet + facet normal 0.894352 0.0320858 0.446212 + outer loop + vertex 1.09402 1.38942 2.60419 + vertex 1.09392 1.39444 2.60403 + vertex 1.09235 1.39093 2.60743 + endloop + endfacet + facet normal 0.893245 0.0251797 0.448865 + outer loop + vertex 1.09244 1.38604 2.60753 + vertex 1.09402 1.38942 2.60419 + vertex 1.09235 1.39093 2.60743 + endloop + endfacet + facet normal 0.850254 0.0259128 0.525734 + outer loop + vertex 1.09244 1.38604 2.60753 + vertex 1.09235 1.39093 2.60743 + vertex 1.0905 1.38781 2.61058 + endloop + endfacet + facet normal 0.857795 0.00953357 0.513904 + outer loop + vertex 1.09235 1.39093 2.60743 + vertex 1.09045 1.39276 2.61056 + vertex 1.0905 1.38781 2.61058 + endloop + endfacet + facet normal 0.773609 0.0091062 0.633598 + outer loop + vertex 1.09045 1.39276 2.61056 + vertex 1.08822 1.38968 2.61333 + vertex 1.0905 1.38781 2.61058 + endloop + endfacet + facet normal 0.781102 -0.00458335 0.624386 + outer loop + vertex 1.08822 1.39465 2.61337 + vertex 1.08822 1.38968 2.61333 + vertex 1.09045 1.39276 2.61056 + endloop + endfacet + facet normal 0.901236 0.0353365 0.431885 + outer loop + vertex 1.09392 1.39444 2.60403 + vertex 1.09379 1.39944 2.60388 + vertex 1.09227 1.39584 2.60735 + endloop + endfacet + facet normal 0.899233 0.0209367 0.436969 + outer loop + vertex 1.09235 1.39093 2.60743 + vertex 1.09392 1.39444 2.60403 + vertex 1.09227 1.39584 2.60735 + endloop + endfacet + facet normal 0.860712 0.0215712 0.508635 + outer loop + vertex 1.09235 1.39093 2.60743 + vertex 1.09227 1.39584 2.60735 + vertex 1.09045 1.39276 2.61056 + endloop + endfacet + facet normal 0.86591 0.00962428 0.500107 + outer loop + vertex 1.09227 1.39584 2.60735 + vertex 1.09042 1.39767 2.61053 + vertex 1.09045 1.39276 2.61056 + endloop + endfacet + facet normal 0.785752 0.00969316 0.618466 + outer loop + vertex 1.09042 1.39767 2.61053 + vertex 1.08822 1.39465 2.61337 + vertex 1.09045 1.39276 2.61056 + endloop + endfacet + facet normal 0.793255 -0.00482043 0.608871 + outer loop + vertex 1.08821 1.39959 2.61342 + vertex 1.08822 1.39465 2.61337 + vertex 1.09042 1.39767 2.61053 + endloop + endfacet + facet normal 0.908081 0.0400491 0.416875 + outer loop + vertex 1.09379 1.39944 2.60388 + vertex 1.09364 1.40447 2.60374 + vertex 1.09218 1.40076 2.60726 + endloop + endfacet + facet normal 0.906167 0.0239553 0.422241 + outer loop + vertex 1.09227 1.39584 2.60735 + vertex 1.09379 1.39944 2.60388 + vertex 1.09218 1.40076 2.60726 + endloop + endfacet + facet normal 0.869369 0.0245733 0.493553 + outer loop + vertex 1.09227 1.39584 2.60735 + vertex 1.09218 1.40076 2.60726 + vertex 1.09042 1.39767 2.61053 + endloop + endfacet + facet normal 0.874008 0.0136409 0.48572 + outer loop + vertex 1.09218 1.40076 2.60726 + vertex 1.09036 1.40255 2.61049 + vertex 1.09042 1.39767 2.61053 + endloop + endfacet + facet normal 0.799157 0.0138124 0.600964 + outer loop + vertex 1.09036 1.40255 2.61049 + vertex 1.08821 1.39959 2.61342 + vertex 1.09042 1.39767 2.61053 + endloop + endfacet + facet normal 0.805643 0.000646754 0.592401 + outer loop + vertex 1.08818 1.40445 2.61345 + vertex 1.08821 1.39959 2.61342 + vertex 1.09036 1.40255 2.61049 + endloop + endfacet + facet normal 0.913308 0.0592576 0.402935 + outer loop + vertex 1.09364 1.40447 2.60374 + vertex 1.09343 1.40943 2.60349 + vertex 1.09207 1.40569 2.60712 + endloop + endfacet + facet normal 0.910948 0.0334902 0.41116 + outer loop + vertex 1.09218 1.40076 2.60726 + vertex 1.09364 1.40447 2.60374 + vertex 1.09207 1.40569 2.60712 + endloop + endfacet + facet normal 0.878444 0.0346111 0.47659 + outer loop + vertex 1.09218 1.40076 2.60726 + vertex 1.09207 1.40569 2.60712 + vertex 1.09036 1.40255 2.61049 + endloop + endfacet + facet normal 0.883313 0.0229809 0.468219 + outer loop + vertex 1.09207 1.40569 2.60712 + vertex 1.09029 1.40745 2.61039 + vertex 1.09036 1.40255 2.61049 + endloop + endfacet + facet normal 0.812594 0.0242999 0.582323 + outer loop + vertex 1.09029 1.40745 2.61039 + vertex 1.08818 1.40445 2.61345 + vertex 1.09036 1.40255 2.61049 + endloop + endfacet + facet normal 0.824239 -0.00033444 0.566241 + outer loop + vertex 1.08815 1.40932 2.6135 + vertex 1.08818 1.40445 2.61345 + vertex 1.09029 1.40745 2.61039 + endloop + endfacet + facet normal 0.919672 0.0821503 0.383999 + outer loop + vertex 1.09343 1.40943 2.60349 + vertex 1.09321 1.41435 2.60296 + vertex 1.09194 1.41079 2.60675 + endloop + endfacet + facet normal 0.916921 0.0509966 0.395797 + outer loop + vertex 1.09207 1.40569 2.60712 + vertex 1.09343 1.40943 2.60349 + vertex 1.09194 1.41079 2.60675 + endloop + endfacet + facet normal 0.889121 0.0545604 0.454409 + outer loop + vertex 1.09207 1.40569 2.60712 + vertex 1.09194 1.41079 2.60675 + vertex 1.09029 1.40745 2.61039 + endloop + endfacet + facet normal 0.897952 0.0332449 0.438835 + outer loop + vertex 1.09194 1.41079 2.60675 + vertex 1.09022 1.41255 2.61015 + vertex 1.09029 1.40745 2.61039 + endloop + endfacet + facet normal 0.834123 0.0375083 0.550302 + outer loop + vertex 1.09022 1.41255 2.61015 + vertex 1.08815 1.40932 2.6135 + vertex 1.09029 1.40745 2.61039 + endloop + endfacet + facet normal 0.847461 0.00881142 0.530784 + outer loop + vertex 1.08807 1.41427 2.61355 + vertex 1.08815 1.40932 2.6135 + vertex 1.09022 1.41255 2.61015 + endloop + endfacet + facet normal 0.940604 0.0105943 0.339341 + outer loop + vertex 1.09321 1.41435 2.60296 + vertex 1.09339 1.41887 2.60233 + vertex 1.09209 1.41708 2.60597 + endloop + endfacet + facet normal 0.942886 0.0189776 0.332575 + outer loop + vertex 1.09194 1.41079 2.60675 + vertex 1.09321 1.41435 2.60296 + vertex 1.09209 1.41708 2.60597 + endloop + endfacet + facet normal 0.897969 0.0333441 0.438793 + outer loop + vertex 1.09194 1.41079 2.60675 + vertex 1.09209 1.41708 2.60597 + vertex 1.09022 1.41255 2.61015 + endloop + endfacet + facet normal 0.897558 0.0342309 0.439566 + outer loop + vertex 1.09209 1.41708 2.60597 + vertex 1.09008 1.41781 2.61002 + vertex 1.09022 1.41255 2.61015 + endloop + endfacet + facet normal 0.852898 0.035055 0.520899 + outer loop + vertex 1.09008 1.41781 2.61002 + vertex 1.08807 1.41427 2.61355 + vertex 1.09022 1.41255 2.61015 + endloop + endfacet + facet normal 0.865125 0.00873834 0.501479 + outer loop + vertex 1.08797 1.41943 2.61364 + vertex 1.08807 1.41427 2.61355 + vertex 1.09008 1.41781 2.61002 + endloop + endfacet + facet normal 0.932572 -0.344013 0.109383 + outer loop + vertex 1.0941 1.42183 2.60105 + vertex 1.095 1.425 2.60338 + vertex 1.09481 1.425 2.605 + endloop + endfacet + facet normal 0.972804 -0.231334 0.0117302 + outer loop + vertex 1.09339 1.41887 2.60233 + vertex 1.0941 1.42183 2.60105 + vertex 1.09481 1.425 2.605 + endloop + endfacet + facet normal 0.936333 -0.298406 0.185025 + outer loop + vertex 1.09339 1.41887 2.60233 + vertex 1.09481 1.425 2.605 + vertex 1.09209 1.41708 2.60597 + endloop + endfacet + facet normal 0.504398 -0.0680035 0.860789 + outer loop + vertex 1.09209 1.41708 2.60597 + vertex 1.09481 1.425 2.605 + vertex 1.09186 1.42286 2.60656 + endloop + endfacet + facet normal 0.894934 -0.00919283 0.446104 + outer loop + vertex 1.09209 1.41708 2.60597 + vertex 1.09186 1.42286 2.60656 + vertex 1.09008 1.41781 2.61002 + endloop + endfacet + facet normal 0.875276 0.0230655 0.483074 + outer loop + vertex 1.09186 1.42286 2.60656 + vertex 1.08992 1.42294 2.61007 + vertex 1.09008 1.41781 2.61002 + endloop + endfacet + facet normal 0.867635 0.0227026 0.496683 + outer loop + vertex 1.08992 1.42294 2.61007 + vertex 1.08797 1.41943 2.61364 + vertex 1.09008 1.41781 2.61002 + endloop + endfacet + facet normal 0.880875 -0.00845904 0.473274 + outer loop + vertex 1.08806 1.42454 2.61355 + vertex 1.08797 1.41943 2.61364 + vertex 1.08992 1.42294 2.61007 + endloop + endfacet + facet normal 0.427175 0.0683492 0.901582 + outer loop + vertex 1.09481 1.425 2.605 + vertex 1.09401 1.43 2.605 + vertex 1.09186 1.42286 2.60656 + endloop + endfacet + facet normal 0.565838 0.00964923 0.82446 + outer loop + vertex 1.09401 1.43 2.605 + vertex 1.0916 1.42783 2.60668 + vertex 1.09186 1.42286 2.60656 + endloop + endfacet + facet normal 0.875119 0.0333305 0.482759 + outer loop + vertex 1.09186 1.42286 2.60656 + vertex 1.0916 1.42783 2.60668 + vertex 1.08992 1.42294 2.61007 + endloop + endfacet + facet normal 0.88246 0.0218609 0.469879 + outer loop + vertex 1.0916 1.42783 2.60668 + vertex 1.08981 1.428 2.61003 + vertex 1.08992 1.42294 2.61007 + endloop + endfacet + facet normal 0.886474 0.0218849 0.462261 + outer loop + vertex 1.08981 1.428 2.61003 + vertex 1.08806 1.42454 2.61355 + vertex 1.08992 1.42294 2.61007 + endloop + endfacet + facet normal 0.897732 -0.00602413 0.4405 + outer loop + vertex 1.08815 1.42946 2.61344 + vertex 1.08806 1.42454 2.61355 + vertex 1.08981 1.428 2.61003 + endloop + endfacet + facet normal 0.568279 0.00567696 0.822817 + outer loop + vertex 1.09401 1.43 2.605 + vertex 1.09396 1.435 2.605 + vertex 1.0916 1.42783 2.60668 + endloop + endfacet + facet normal 0.541252 0.0187274 0.840652 + outer loop + vertex 1.09396 1.435 2.605 + vertex 1.09145 1.4329 2.60666 + vertex 1.0916 1.42783 2.60668 + endloop + endfacet + facet normal 0.882457 0.0274448 0.469592 + outer loop + vertex 1.0916 1.42783 2.60668 + vertex 1.09145 1.4329 2.60666 + vertex 1.08981 1.428 2.61003 + endloop + endfacet + facet normal 0.884666 0.0239689 0.465609 + outer loop + vertex 1.09145 1.4329 2.60666 + vertex 1.08972 1.43314 2.60994 + vertex 1.08981 1.428 2.61003 + endloop + endfacet + facet normal 0.902486 0.0236898 0.430067 + outer loop + vertex 1.08972 1.43314 2.60994 + vertex 1.08815 1.42946 2.61344 + vertex 1.08981 1.428 2.61003 + endloop + endfacet + facet normal 0.907862 0.0109989 0.419125 + outer loop + vertex 1.08807 1.43442 2.61348 + vertex 1.08815 1.42946 2.61344 + vertex 1.08972 1.43314 2.60994 + endloop + endfacet + facet normal 0.537651 0.0247393 0.842805 + outer loop + vertex 1.09396 1.435 2.605 + vertex 1.09373 1.44 2.605 + vertex 1.09145 1.4329 2.60666 + endloop + endfacet + facet normal 0.534703 0.0261131 0.844636 + outer loop + vertex 1.09373 1.44 2.605 + vertex 1.09134 1.43813 2.60657 + vertex 1.09145 1.4329 2.60666 + endloop + endfacet + facet normal 0.884689 0.0271745 0.465389 + outer loop + vertex 1.09145 1.4329 2.60666 + vertex 1.09134 1.43813 2.60657 + vertex 1.08972 1.43314 2.60994 + endloop + endfacet + facet normal 0.891095 0.0170478 0.453497 + outer loop + vertex 1.09134 1.43813 2.60657 + vertex 1.08965 1.43834 2.60988 + vertex 1.08972 1.43314 2.60994 + endloop + endfacet + facet normal 0.90859 0.0168476 0.41735 + outer loop + vertex 1.08965 1.43834 2.60988 + vertex 1.08807 1.43442 2.61348 + vertex 1.08972 1.43314 2.60994 + endloop + endfacet + facet normal 0.914259 0.00332858 0.405116 + outer loop + vertex 1.08804 1.43947 2.6135 + vertex 1.08807 1.43442 2.61348 + vertex 1.08965 1.43834 2.60988 + endloop + endfacet + facet normal 0.546247 0.00545687 0.837606 + outer loop + vertex 1.09373 1.44 2.605 + vertex 1.09368 1.445 2.605 + vertex 1.09134 1.43813 2.60657 + endloop + endfacet + facet normal 0.513127 0.0214048 0.858046 + outer loop + vertex 1.09368 1.445 2.605 + vertex 1.09128 1.44334 2.60648 + vertex 1.09134 1.43813 2.60657 + endloop + endfacet + facet normal 0.891111 0.0187159 0.453399 + outer loop + vertex 1.09134 1.43813 2.60657 + vertex 1.09128 1.44334 2.60648 + vertex 1.08965 1.43834 2.60988 + endloop + endfacet + facet normal 0.896824 0.00928522 0.44229 + outer loop + vertex 1.09128 1.44334 2.60648 + vertex 1.08962 1.44345 2.60983 + vertex 1.08965 1.43834 2.60988 + endloop + endfacet + facet normal 0.914884 0.00902991 0.403616 + outer loop + vertex 1.08962 1.44345 2.60983 + vertex 1.08804 1.43947 2.6135 + vertex 1.08965 1.43834 2.60988 + endloop + endfacet + facet normal 0.92006 -0.0039528 0.391758 + outer loop + vertex 1.08807 1.44446 2.6135 + vertex 1.08804 1.43947 2.6135 + vertex 1.08962 1.44345 2.60983 + endloop + endfacet + facet normal 0.524548 -0.00105052 0.85138 + outer loop + vertex 1.09368 1.445 2.605 + vertex 1.09369 1.45 2.605 + vertex 1.09128 1.44334 2.60648 + endloop + endfacet + facet normal 0.490073 0.0159016 0.871536 + outer loop + vertex 1.09369 1.45 2.605 + vertex 1.09122 1.44841 2.60642 + vertex 1.09128 1.44334 2.60648 + endloop + endfacet + facet normal 0.896832 0.0162511 0.442072 + outer loop + vertex 1.09128 1.44334 2.60648 + vertex 1.09122 1.44841 2.60642 + vertex 1.08962 1.44345 2.60983 + endloop + endfacet + facet normal 0.901906 0.00760176 0.431866 + outer loop + vertex 1.09122 1.44841 2.60642 + vertex 1.0896 1.44841 2.60979 + vertex 1.08962 1.44345 2.60983 + endloop + endfacet + facet normal 0.921162 0.00734202 0.38911 + outer loop + vertex 1.0896 1.44841 2.60979 + vertex 1.08807 1.44446 2.6135 + vertex 1.08962 1.44345 2.60983 + endloop + endfacet + facet normal 0.92475 -0.00205646 0.380569 + outer loop + vertex 1.08809 1.4494 2.61347 + vertex 1.08807 1.44446 2.6135 + vertex 1.0896 1.44841 2.60979 + endloop + endfacet + facet normal 0.486851 0.0224023 0.873198 + outer loop + vertex 1.09369 1.45 2.605 + vertex 1.09346 1.455 2.605 + vertex 1.09122 1.44841 2.60642 + endloop + endfacet + facet normal 0.513877 0.00987706 0.857807 + outer loop + vertex 1.09346 1.455 2.605 + vertex 1.09114 1.45337 2.60641 + vertex 1.09122 1.44841 2.60642 + endloop + endfacet + facet normal 0.901842 0.0140812 0.431837 + outer loop + vertex 1.09122 1.44841 2.60642 + vertex 1.09114 1.45337 2.60641 + vertex 1.0896 1.44841 2.60979 + endloop + endfacet + facet normal 0.905898 0.00707601 0.423437 + outer loop + vertex 1.09114 1.45337 2.60641 + vertex 1.08957 1.4533 2.60977 + vertex 1.0896 1.44841 2.60979 + endloop + endfacet + facet normal 0.925584 0.00696846 0.378478 + outer loop + vertex 1.08957 1.4533 2.60977 + vertex 1.08809 1.4494 2.61347 + vertex 1.0896 1.44841 2.60979 + endloop + endfacet + facet normal 0.927356 0.00220645 0.374174 + outer loop + vertex 1.08809 1.45435 2.61344 + vertex 1.08809 1.4494 2.61347 + vertex 1.08957 1.4533 2.60977 + endloop + endfacet + facet normal 0.515267 0.00721125 0.857 + outer loop + vertex 1.09346 1.455 2.605 + vertex 1.09339 1.46 2.605 + vertex 1.09114 1.45337 2.60641 + endloop + endfacet + facet normal 0.521799 0.00416452 0.853058 + outer loop + vertex 1.09339 1.46 2.605 + vertex 1.0911 1.45828 2.60641 + vertex 1.09114 1.45337 2.60641 + endloop + endfacet + facet normal 0.905876 0.00856391 0.423456 + outer loop + vertex 1.09114 1.45337 2.60641 + vertex 1.0911 1.45828 2.60641 + vertex 1.08957 1.4533 2.60977 + endloop + endfacet + facet normal 0.906114 0.00815312 0.422955 + outer loop + vertex 1.0911 1.45828 2.60641 + vertex 1.08954 1.45823 2.60975 + vertex 1.08957 1.4533 2.60977 + endloop + endfacet + facet normal 0.927914 0.00813894 0.372706 + outer loop + vertex 1.08954 1.45823 2.60975 + vertex 1.08809 1.45435 2.61344 + vertex 1.08957 1.4533 2.60977 + endloop + endfacet + facet normal 0.92873 0.00594017 0.37071 + outer loop + vertex 1.08807 1.45932 2.6134 + vertex 1.08809 1.45435 2.61344 + vertex 1.08954 1.45823 2.60975 + endloop + endfacet + facet normal 0.524068 0 0.851677 + outer loop + vertex 1.09339 1.46 2.605 + vertex 1.09339 1.465 2.605 + vertex 1.0911 1.45828 2.60641 + endloop + endfacet + facet normal 0.510385 0.00640578 0.859922 + outer loop + vertex 1.09339 1.465 2.605 + vertex 1.09103 1.46322 2.60641 + vertex 1.0911 1.45828 2.60641 + endloop + endfacet + facet normal 0.906062 0.0116916 0.422982 + outer loop + vertex 1.0911 1.45828 2.60641 + vertex 1.09103 1.46322 2.60641 + vertex 1.08954 1.45823 2.60975 + endloop + endfacet + facet normal 0.907545 0.00915172 0.419855 + outer loop + vertex 1.09103 1.46322 2.60641 + vertex 1.0895 1.46321 2.60973 + vertex 1.08954 1.45823 2.60975 + endloop + endfacet + facet normal 0.929029 0.00907303 0.369896 + outer loop + vertex 1.0895 1.46321 2.60973 + vertex 1.08807 1.45932 2.6134 + vertex 1.08954 1.45823 2.60975 + endloop + endfacet + facet normal 0.929052 0.00901201 0.36984 + outer loop + vertex 1.08805 1.46432 2.61334 + vertex 1.08807 1.45932 2.6134 + vertex 1.0895 1.46321 2.60973 + endloop + endfacet + facet normal 0.501523 0.0220611 0.864863 + outer loop + vertex 1.09339 1.465 2.605 + vertex 1.09317 1.47 2.605 + vertex 1.09103 1.46322 2.60641 + endloop + endfacet + facet normal 0.530427 0.00936289 0.847679 + outer loop + vertex 1.09317 1.47 2.605 + vertex 1.09097 1.4682 2.6064 + vertex 1.09103 1.46322 2.60641 + endloop + endfacet + facet normal 0.907512 0.012369 0.419845 + outer loop + vertex 1.09103 1.46322 2.60641 + vertex 1.09097 1.4682 2.6064 + vertex 1.0895 1.46321 2.60973 + endloop + endfacet + facet normal 0.907535 0.012329 0.419795 + outer loop + vertex 1.09097 1.4682 2.6064 + vertex 1.08945 1.46821 2.60967 + vertex 1.0895 1.46321 2.60973 + endloop + endfacet + facet normal 0.929332 0.011961 0.369051 + outer loop + vertex 1.08945 1.46821 2.60967 + vertex 1.08805 1.46432 2.61334 + vertex 1.0895 1.46321 2.60973 + endloop + endfacet + facet normal 0.930143 0.00979908 0.367067 + outer loop + vertex 1.08802 1.46932 2.61328 + vertex 1.08805 1.46432 2.61334 + vertex 1.08945 1.46821 2.60967 + endloop + endfacet + facet normal 0.537174 -0.00213881 0.843469 + outer loop + vertex 1.09317 1.47 2.605 + vertex 1.09319 1.475 2.605 + vertex 1.09097 1.4682 2.6064 + endloop + endfacet + facet normal 0.515049 0.00788165 0.857124 + outer loop + vertex 1.09319 1.475 2.605 + vertex 1.09095 1.47321 2.60636 + vertex 1.09097 1.4682 2.6064 + endloop + endfacet + facet normal 0.907576 0.00635739 0.41984 + outer loop + vertex 1.09097 1.4682 2.6064 + vertex 1.09095 1.47321 2.60636 + vertex 1.08945 1.46821 2.60967 + endloop + endfacet + facet normal 0.902971 0.0141312 0.429469 + outer loop + vertex 1.09095 1.47321 2.60636 + vertex 1.08941 1.47321 2.6096 + vertex 1.08945 1.46821 2.60967 + endloop + endfacet + facet normal 0.930485 0.0134491 0.366083 + outer loop + vertex 1.08941 1.47321 2.6096 + vertex 1.08802 1.46932 2.61328 + vertex 1.08945 1.46821 2.60967 + endloop + endfacet + facet normal 0.931332 0.0111785 0.364 + outer loop + vertex 1.08799 1.47433 2.61321 + vertex 1.08802 1.46932 2.61328 + vertex 1.08941 1.47321 2.6096 + endloop + endfacet + facet normal 0.528267 -0.014799 0.848949 + outer loop + vertex 1.09319 1.475 2.605 + vertex 1.09333 1.48 2.605 + vertex 1.09095 1.47321 2.60636 + endloop + endfacet + facet normal 0.476655 0.0092904 0.879041 + outer loop + vertex 1.09333 1.48 2.605 + vertex 1.09093 1.47821 2.60632 + vertex 1.09095 1.47321 2.60636 + endloop + endfacet + facet normal 0.903027 0.00800345 0.429508 + outer loop + vertex 1.09095 1.47321 2.60636 + vertex 1.09093 1.47821 2.60632 + vertex 1.08941 1.47321 2.6096 + endloop + endfacet + facet normal 0.901196 0.0110286 0.433272 + outer loop + vertex 1.09093 1.47821 2.60632 + vertex 1.08937 1.47823 2.60955 + vertex 1.08941 1.47321 2.6096 + endloop + endfacet + facet normal 0.931271 0.0105343 0.364176 + outer loop + vertex 1.08937 1.47823 2.60955 + vertex 1.08799 1.47433 2.61321 + vertex 1.08941 1.47321 2.6096 + endloop + endfacet + facet normal 0.932266 0.00784582 0.361688 + outer loop + vertex 1.08797 1.47932 2.61315 + vertex 1.08799 1.47433 2.61321 + vertex 1.08937 1.47823 2.60955 + endloop + endfacet + facet normal 0.478155 0.00669187 0.87825 + outer loop + vertex 1.09333 1.48 2.605 + vertex 1.09326 1.485 2.605 + vertex 1.09093 1.47821 2.60632 + endloop + endfacet + facet normal 0.468852 0.0108551 0.88321 + outer loop + vertex 1.09326 1.485 2.605 + vertex 1.09087 1.48322 2.60629 + vertex 1.09093 1.47821 2.60632 + endloop + endfacet + facet normal 0.901181 0.0127384 0.433256 + outer loop + vertex 1.09093 1.47821 2.60632 + vertex 1.09087 1.48322 2.60629 + vertex 1.08937 1.47823 2.60955 + endloop + endfacet + facet normal 0.902309 0.0108953 0.430952 + outer loop + vertex 1.09087 1.48322 2.60629 + vertex 1.08934 1.48323 2.6095 + vertex 1.08937 1.47823 2.60955 + endloop + endfacet + facet normal 0.932514 0.0104766 0.360983 + outer loop + vertex 1.08934 1.48323 2.6095 + vertex 1.08797 1.47932 2.61315 + vertex 1.08937 1.47823 2.60955 + endloop + endfacet + facet normal 0.933635 0.00744159 0.358148 + outer loop + vertex 1.08794 1.48433 2.61311 + vertex 1.08797 1.47932 2.61315 + vertex 1.08934 1.48323 2.6095 + endloop + endfacet + facet normal 0.466998 0.0140178 0.884147 + outer loop + vertex 1.09326 1.485 2.605 + vertex 1.09311 1.49 2.605 + vertex 1.09087 1.48322 2.60629 + endloop + endfacet + facet normal 0.478741 0.00895529 0.877911 + outer loop + vertex 1.09311 1.49 2.605 + vertex 1.09082 1.48822 2.60627 + vertex 1.09087 1.48322 2.60629 + endloop + endfacet + facet normal 0.902309 0.0108775 0.430952 + outer loop + vertex 1.09087 1.48322 2.60629 + vertex 1.09082 1.48822 2.60627 + vertex 1.08934 1.48323 2.6095 + endloop + endfacet + facet normal 0.902749 0.0101596 0.430048 + outer loop + vertex 1.09082 1.48822 2.60627 + vertex 1.0893 1.48824 2.60947 + vertex 1.08934 1.48323 2.6095 + endloop + endfacet + facet normal 0.933862 0.00985644 0.357498 + outer loop + vertex 1.0893 1.48824 2.60947 + vertex 1.08794 1.48433 2.61311 + vertex 1.08934 1.48323 2.6095 + endloop + endfacet + facet normal 0.934633 0.00775346 0.355529 + outer loop + vertex 1.08792 1.48932 2.61306 + vertex 1.08794 1.48433 2.61311 + vertex 1.0893 1.48824 2.60947 + endloop + endfacet + facet normal 0.48409 0 0.875018 + outer loop + vertex 1.09311 1.49 2.605 + vertex 1.09311 1.495 2.605 + vertex 1.09082 1.48822 2.60627 + endloop + endfacet + facet normal 0.468825 0.00669436 0.883266 + outer loop + vertex 1.09311 1.495 2.605 + vertex 1.09079 1.49323 2.60625 + vertex 1.09082 1.48822 2.60627 + endloop + endfacet + facet normal 0.902765 0.00768078 0.430066 + outer loop + vertex 1.09082 1.48822 2.60627 + vertex 1.09079 1.49323 2.60625 + vertex 1.0893 1.48824 2.60947 + endloop + endfacet + facet normal 0.898794 0.0140867 0.438144 + outer loop + vertex 1.09079 1.49323 2.60625 + vertex 1.08925 1.49321 2.60941 + vertex 1.0893 1.48824 2.60947 + endloop + endfacet + facet normal 0.935148 0.013478 0.354 + outer loop + vertex 1.08925 1.49321 2.60941 + vertex 1.08792 1.48932 2.61306 + vertex 1.0893 1.48824 2.60947 + endloop + endfacet + facet normal 0.935491 0.0125391 0.353127 + outer loop + vertex 1.0879 1.49428 2.61295 + vertex 1.08792 1.48932 2.61306 + vertex 1.08925 1.49321 2.60941 + endloop + endfacet + facet normal 0.47394 -0.00189834 0.880555 + outer loop + vertex 1.09311 1.495 2.605 + vertex 1.09313 1.5 2.605 + vertex 1.09079 1.49323 2.60625 + endloop + endfacet + facet normal 0.454559 0.00666052 0.890691 + outer loop + vertex 1.09313 1.5 2.605 + vertex 1.09075 1.49818 2.60623 + vertex 1.09079 1.49323 2.60625 + endloop + endfacet + facet normal 0.898857 0.00928717 0.438144 + outer loop + vertex 1.09079 1.49323 2.60625 + vertex 1.09075 1.49818 2.60623 + vertex 1.08925 1.49321 2.60941 + endloop + endfacet + facet normal 0.894406 0.0162594 0.446961 + outer loop + vertex 1.09075 1.49818 2.60623 + vertex 1.08919 1.49806 2.60935 + vertex 1.08925 1.49321 2.60941 + endloop + endfacet + facet normal 0.935759 0.0156056 0.352295 + outer loop + vertex 1.08919 1.49806 2.60935 + vertex 1.0879 1.49428 2.61295 + vertex 1.08925 1.49321 2.60941 + endloop + endfacet + facet normal 0.934152 0.0199975 0.356316 + outer loop + vertex 1.0879 1.49908 2.61267 + vertex 1.0879 1.49428 2.61295 + vertex 1.08919 1.49806 2.60935 + endloop + endfacet + facet normal 0.458586 0 0.88865 + outer loop + vertex 1.09313 1.5 2.605 + vertex 1.09313 1.505 2.605 + vertex 1.09075 1.49818 2.60623 + endloop + endfacet + facet normal 0.464164 -0.00247456 0.885746 + outer loop + vertex 1.09313 1.505 2.605 + vertex 1.09066 1.50306 2.60629 + vertex 1.09075 1.49818 2.60623 + endloop + endfacet + facet normal 0.894555 0.0109333 0.446824 + outer loop + vertex 1.09075 1.49818 2.60623 + vertex 1.09066 1.50306 2.60629 + vertex 1.08919 1.49806 2.60935 + endloop + endfacet + facet normal 0.888338 0.0200469 0.458752 + outer loop + vertex 1.09066 1.50306 2.60629 + vertex 1.08908 1.50248 2.60936 + vertex 1.08919 1.49806 2.60935 + endloop + endfacet + facet normal 0.934269 0.0214043 0.355927 + outer loop + vertex 1.08908 1.50248 2.60936 + vertex 1.0879 1.49908 2.61267 + vertex 1.08919 1.49806 2.60935 + endloop + endfacet + facet normal 0.933983 0.0221879 0.356628 + outer loop + vertex 1.08804 1.50286 2.61207 + vertex 1.0879 1.49908 2.61267 + vertex 1.08908 1.50248 2.60936 + endloop + endfacet + facet normal 0.461502 0.00184852 0.887137 + outer loop + vertex 1.09313 1.505 2.605 + vertex 1.09311 1.51 2.605 + vertex 1.09066 1.50306 2.60629 + endloop + endfacet + facet normal 0.545648 -0.0372077 0.837188 + outer loop + vertex 1.09311 1.51 2.605 + vertex 1.09036 1.50801 2.6067 + vertex 1.09066 1.50306 2.60629 + endloop + endfacet + facet normal 0.88824 0.0295249 0.458429 + outer loop + vertex 1.08879 1.50558 2.60991 + vertex 1.09036 1.50801 2.6067 + vertex 1.08895 1.50959 2.60933 + endloop + endfacet + facet normal 0.895496 0.00711995 0.445014 + outer loop + vertex 1.08879 1.50558 2.60991 + vertex 1.08908 1.50248 2.60936 + vertex 1.09036 1.50801 2.6067 + endloop + endfacet + facet normal 0.888818 0.0149079 0.458019 + outer loop + vertex 1.08908 1.50248 2.60936 + vertex 1.09066 1.50306 2.60629 + vertex 1.09036 1.50801 2.6067 + endloop + endfacet + facet normal 0.934087 0.026481 0.356062 + outer loop + vertex 1.08908 1.50248 2.60936 + vertex 1.08879 1.50558 2.60991 + vertex 1.08804 1.50286 2.61207 + endloop + endfacet + facet normal 0.527774 -0.00211397 0.849382 + outer loop + vertex 1.09311 1.51 2.605 + vertex 1.09313 1.515 2.605 + vertex 1.09036 1.50801 2.6067 + endloop + endfacet + facet normal 0.39894 0.064831 0.914682 + outer loop + vertex 1.09313 1.515 2.605 + vertex 1.09057 1.51385 2.6062 + vertex 1.09036 1.50801 2.6067 + endloop + endfacet + facet normal 0.883396 0.00845981 0.46855 + outer loop + vertex 1.09057 1.51385 2.6062 + vertex 1.08895 1.50959 2.60933 + vertex 1.09036 1.50801 2.6067 + endloop + endfacet + facet normal 0.884606 0.00634324 0.466297 + outer loop + vertex 1.089 1.51456 2.60918 + vertex 1.08895 1.50959 2.60933 + vertex 1.09057 1.51385 2.6062 + endloop + endfacet + facet normal 0.423925 0 0.905697 + outer loop + vertex 1.09313 1.515 2.605 + vertex 1.09313 1.52 2.605 + vertex 1.09057 1.51385 2.6062 + endloop + endfacet + facet normal 0.409483 0.00728622 0.912289 + outer loop + vertex 1.09313 1.52 2.605 + vertex 1.09058 1.51903 2.60615 + vertex 1.09057 1.51385 2.6062 + endloop + endfacet + facet normal 0.884274 0.00285953 0.466959 + outer loop + vertex 1.09058 1.51903 2.60615 + vertex 1.089 1.51456 2.60918 + vertex 1.09057 1.51385 2.6062 + endloop + endfacet + facet normal 0.891715 -0.00958242 0.452496 + outer loop + vertex 1.08894 1.51952 2.60939 + vertex 1.089 1.51456 2.60918 + vertex 1.09058 1.51903 2.60615 + endloop + endfacet + facet normal 0.411806 0 0.911272 + outer loop + vertex 1.09313 1.52 2.605 + vertex 1.09313 1.525 2.605 + vertex 1.09058 1.51903 2.60615 + endloop + endfacet + facet normal 0.485602 -0.0388263 0.873317 + outer loop + vertex 1.09313 1.525 2.605 + vertex 1.09046 1.52442 2.60646 + vertex 1.09058 1.51903 2.60615 + endloop + endfacet + facet normal 0.891944 -0.00622235 0.452102 + outer loop + vertex 1.09046 1.52442 2.60646 + vertex 1.08894 1.51952 2.60939 + vertex 1.09058 1.51903 2.60615 + endloop + endfacet + facet normal 0.904625 -0.0261433 0.425405 + outer loop + vertex 1.08884 1.52348 2.60985 + vertex 1.08894 1.51952 2.60939 + vertex 1.09046 1.52442 2.60646 + endloop + endfacet + facet normal 0.479295 0.000959893 0.877653 + outer loop + vertex 1.09313 1.525 2.605 + vertex 1.09312 1.53 2.605 + vertex 1.09046 1.52442 2.60646 + endloop + endfacet + facet normal 0.158214 0.178232 0.971186 + outer loop + vertex 1.09312 1.53 2.605 + vertex 1.09105 1.52952 2.60543 + vertex 1.09046 1.52442 2.60646 + endloop + endfacet + facet normal 0.939426 -0.0219483 0.34205 + outer loop + vertex 1.08884 1.52348 2.60985 + vertex 1.0894 1.52804 2.6086 + vertex 1.08808 1.52541 2.61206 + endloop + endfacet + facet normal 0.901268 0.00783911 0.433191 + outer loop + vertex 1.08884 1.52348 2.60985 + vertex 1.09046 1.52442 2.60646 + vertex 1.0894 1.52804 2.6086 + endloop + endfacet + facet normal 0.889286 -0.00992598 0.457243 + outer loop + vertex 1.09046 1.52442 2.60646 + vertex 1.09105 1.52952 2.60543 + vertex 1.0894 1.52804 2.6086 + endloop + endfacet + facet normal 0.938056 -0.0158958 0.346118 + outer loop + vertex 1.0894 1.52804 2.6086 + vertex 1.08796 1.52942 2.61256 + vertex 1.08808 1.52541 2.61206 + endloop + endfacet + facet normal 0.201403 0.000403354 0.979508 + outer loop + vertex 1.09312 1.53 2.605 + vertex 1.09311 1.535 2.605 + vertex 1.09105 1.52952 2.60543 + endloop + endfacet + facet normal 0.438328 -0.0952718 0.893751 + outer loop + vertex 1.09311 1.535 2.605 + vertex 1.09086 1.53338 2.60593 + vertex 1.09105 1.52952 2.60543 + endloop + endfacet + facet normal 0.890286 -0.0155579 0.455136 + outer loop + vertex 1.09105 1.52952 2.60543 + vertex 1.09086 1.53338 2.60593 + vertex 1.0894 1.52804 2.6086 + endloop + endfacet + facet normal 0.90043 -0.0288553 0.434043 + outer loop + vertex 1.09086 1.53338 2.60593 + vertex 1.08929 1.5332 2.60918 + vertex 1.0894 1.52804 2.6086 + endloop + endfacet + facet normal 0.93775 -0.0182618 0.346832 + outer loop + vertex 1.08929 1.5332 2.60918 + vertex 1.08796 1.52942 2.61256 + vertex 1.0894 1.52804 2.6086 + endloop + endfacet + facet normal 0.936989 -0.0160663 0.34899 + outer loop + vertex 1.0879 1.53429 2.61295 + vertex 1.08796 1.52942 2.61256 + vertex 1.08929 1.5332 2.60918 + endloop + endfacet + facet normal 0.389038 -0.0108986 0.921157 + outer loop + vertex 1.09311 1.535 2.605 + vertex 1.09325 1.54 2.605 + vertex 1.09086 1.53338 2.60593 + endloop + endfacet + facet normal 0.466065 -0.0440084 0.883655 + outer loop + vertex 1.09325 1.54 2.605 + vertex 1.09083 1.53819 2.60619 + vertex 1.09086 1.53338 2.60593 + endloop + endfacet + facet normal 0.900408 -0.0170032 0.434714 + outer loop + vertex 1.09086 1.53338 2.60593 + vertex 1.09083 1.53819 2.60619 + vertex 1.08929 1.5332 2.60918 + endloop + endfacet + facet normal 0.903633 -0.0221813 0.427732 + outer loop + vertex 1.09083 1.53819 2.60619 + vertex 1.08928 1.53815 2.60946 + vertex 1.08929 1.5332 2.60918 + endloop + endfacet + facet normal 0.936811 -0.0176601 0.349389 + outer loop + vertex 1.08928 1.53815 2.60946 + vertex 1.0879 1.53429 2.61295 + vertex 1.08929 1.5332 2.60918 + endloop + endfacet + facet normal 0.934015 -0.00968038 0.357104 + outer loop + vertex 1.08789 1.53924 2.61311 + vertex 1.0879 1.53429 2.61295 + vertex 1.08928 1.53815 2.60946 + endloop + endfacet + facet normal 0.436958 0.00525063 0.899466 + outer loop + vertex 1.09325 1.54 2.605 + vertex 1.09319 1.545 2.605 + vertex 1.09083 1.53819 2.60619 + endloop + endfacet + facet normal 0.495898 -0.0206629 0.868135 + outer loop + vertex 1.09319 1.545 2.605 + vertex 1.09084 1.54316 2.6063 + vertex 1.09083 1.53819 2.60619 + endloop + endfacet + facet normal 0.903751 -0.0121923 0.427884 + outer loop + vertex 1.09083 1.53819 2.60619 + vertex 1.09084 1.54316 2.6063 + vertex 1.08928 1.53815 2.60946 + endloop + endfacet + facet normal 0.902864 -0.0107091 0.429792 + outer loop + vertex 1.09084 1.54316 2.6063 + vertex 1.0893 1.54313 2.60954 + vertex 1.08928 1.53815 2.60946 + endloop + endfacet + facet normal 0.934012 -0.00970371 0.35711 + outer loop + vertex 1.0893 1.54313 2.60954 + vertex 1.08789 1.53924 2.61311 + vertex 1.08928 1.53815 2.60946 + endloop + endfacet + facet normal 0.931697 -0.00324548 0.363223 + outer loop + vertex 1.0879 1.54423 2.61314 + vertex 1.08789 1.53924 2.61311 + vertex 1.0893 1.54313 2.60954 + endloop + endfacet + facet normal 0.486551 -0.00487212 0.873639 + outer loop + vertex 1.09319 1.545 2.605 + vertex 1.09324 1.55 2.605 + vertex 1.09084 1.54316 2.6063 + endloop + endfacet + facet normal 0.484622 -0.00399188 0.874714 + outer loop + vertex 1.09324 1.55 2.605 + vertex 1.09086 1.54815 2.60631 + vertex 1.09084 1.54316 2.6063 + endloop + endfacet + facet normal 0.902888 -0.00440353 0.429853 + outer loop + vertex 1.09084 1.54316 2.6063 + vertex 1.09086 1.54815 2.60631 + vertex 1.0893 1.54313 2.60954 + endloop + endfacet + facet normal 0.90248 -0.00372224 0.430715 + outer loop + vertex 1.09086 1.54815 2.60631 + vertex 1.08932 1.54814 2.60954 + vertex 1.0893 1.54313 2.60954 + endloop + endfacet + facet normal 0.931632 -0.00385409 0.363383 + outer loop + vertex 1.08932 1.54814 2.60954 + vertex 1.0879 1.54423 2.61314 + vertex 1.0893 1.54313 2.60954 + endloop + endfacet + facet normal 0.93024 -6.05576e-05 0.366951 + outer loop + vertex 1.0879 1.54923 2.61314 + vertex 1.0879 1.54423 2.61314 + vertex 1.08932 1.54814 2.60954 + endloop + endfacet + facet normal 0.477688 0.007642 0.878496 + outer loop + vertex 1.09324 1.55 2.605 + vertex 1.09316 1.555 2.605 + vertex 1.09086 1.54815 2.60631 + endloop + endfacet + facet normal 0.49053 0.00197133 0.871422 + outer loop + vertex 1.09316 1.555 2.605 + vertex 1.09087 1.55315 2.60629 + vertex 1.09086 1.54815 2.60631 + endloop + endfacet + facet normal 0.902479 -0.000349757 0.430734 + outer loop + vertex 1.09086 1.54815 2.60631 + vertex 1.09087 1.55315 2.60629 + vertex 1.08932 1.54814 2.60954 + endloop + endfacet + facet normal 0.901837 0.000717459 0.432076 + outer loop + vertex 1.09087 1.55315 2.60629 + vertex 1.08932 1.55314 2.60953 + vertex 1.08932 1.54814 2.60954 + endloop + endfacet + facet normal 0.930308 0.000593323 0.366779 + outer loop + vertex 1.08932 1.55314 2.60953 + vertex 1.0879 1.54923 2.61314 + vertex 1.08932 1.54814 2.60954 + endloop + endfacet + facet normal 0.929163 0.00366929 0.369653 + outer loop + vertex 1.08787 1.55423 2.61316 + vertex 1.0879 1.54923 2.61314 + vertex 1.08932 1.55314 2.60953 + endloop + endfacet + facet normal 0.494765 -0.00494257 0.869013 + outer loop + vertex 1.09316 1.555 2.605 + vertex 1.09321 1.56 2.605 + vertex 1.09087 1.55315 2.60629 + endloop + endfacet + facet normal 0.477559 0.00274189 0.878595 + outer loop + vertex 1.09321 1.56 2.605 + vertex 1.09088 1.55811 2.60627 + vertex 1.09087 1.55315 2.60629 + endloop + endfacet + facet normal 0.901838 0.000227177 0.432075 + outer loop + vertex 1.09087 1.55315 2.60629 + vertex 1.09088 1.55811 2.60627 + vertex 1.08932 1.55314 2.60953 + endloop + endfacet + facet normal 0.897938 0.00668133 0.44007 + outer loop + vertex 1.09088 1.55811 2.60627 + vertex 1.08929 1.55808 2.60951 + vertex 1.08932 1.55314 2.60953 + endloop + endfacet + facet normal 0.929454 0.00663598 0.368877 + outer loop + vertex 1.08929 1.55808 2.60951 + vertex 1.08787 1.55423 2.61316 + vertex 1.08932 1.55314 2.60953 + endloop + endfacet + facet normal 0.928007 0.0105115 0.372414 + outer loop + vertex 1.08782 1.5592 2.61315 + vertex 1.08787 1.55423 2.61316 + vertex 1.08929 1.55808 2.60951 + endloop + endfacet + facet normal 0.482876 -0.00579073 0.87567 + outer loop + vertex 1.09321 1.56 2.605 + vertex 1.09327 1.565 2.605 + vertex 1.09088 1.55811 2.60627 + endloop + endfacet + facet normal 0.459178 0.00477776 0.888331 + outer loop + vertex 1.09327 1.565 2.605 + vertex 1.09086 1.56305 2.60626 + vertex 1.09088 1.55811 2.60627 + endloop + endfacet + facet normal 0.897957 0.00445586 0.44006 + outer loop + vertex 1.09088 1.55811 2.60627 + vertex 1.09086 1.56305 2.60626 + vertex 1.08929 1.55808 2.60951 + endloop + endfacet + facet normal 0.892488 0.013284 0.450875 + outer loop + vertex 1.09086 1.56305 2.60626 + vertex 1.08924 1.563 2.60948 + vertex 1.08929 1.55808 2.60951 + endloop + endfacet + facet normal 0.928255 0.0131099 0.371713 + outer loop + vertex 1.08924 1.563 2.60948 + vertex 1.08782 1.5592 2.61315 + vertex 1.08929 1.55808 2.60951 + endloop + endfacet + facet normal 0.925219 0.0211347 0.378844 + outer loop + vertex 1.08775 1.56412 2.61304 + vertex 1.08782 1.5592 2.61315 + vertex 1.08924 1.563 2.60948 + endloop + endfacet + facet normal 0.461063 0.00183577 0.887366 + outer loop + vertex 1.09327 1.565 2.605 + vertex 1.09325 1.57 2.605 + vertex 1.09086 1.56305 2.60626 + endloop + endfacet + facet normal 0.455498 0.00426293 0.890227 + outer loop + vertex 1.09325 1.57 2.605 + vertex 1.09083 1.56799 2.60625 + vertex 1.09086 1.56305 2.60626 + endloop + endfacet + facet normal 0.89258 0.00685503 0.450838 + outer loop + vertex 1.09086 1.56305 2.60626 + vertex 1.09083 1.56799 2.60625 + vertex 1.08924 1.563 2.60948 + endloop + endfacet + facet normal 0.881432 0.0239347 0.471703 + outer loop + vertex 1.09083 1.56799 2.60625 + vertex 1.08915 1.56784 2.6094 + vertex 1.08924 1.563 2.60948 + endloop + endfacet + facet normal 0.925408 0.0232493 0.378258 + outer loop + vertex 1.08915 1.56784 2.6094 + vertex 1.08775 1.56412 2.61304 + vertex 1.08924 1.563 2.60948 + endloop + endfacet + facet normal 0.920026 0.0368875 0.390118 + outer loop + vertex 1.0877 1.56892 2.61271 + vertex 1.08775 1.56412 2.61304 + vertex 1.08915 1.56784 2.6094 + endloop + endfacet + facet normal 0.464375 -0.00928906 0.88559 + outer loop + vertex 1.09325 1.57 2.605 + vertex 1.09335 1.575 2.605 + vertex 1.09083 1.56799 2.60625 + endloop + endfacet + facet normal 0.45941 -0.00703913 0.888196 + outer loop + vertex 1.09335 1.575 2.605 + vertex 1.09073 1.57294 2.60634 + vertex 1.09083 1.56799 2.60625 + endloop + endfacet + facet normal 0.881956 0.00814054 0.471261 + outer loop + vertex 1.09083 1.56799 2.60625 + vertex 1.09073 1.57294 2.60634 + vertex 1.08915 1.56784 2.6094 + endloop + endfacet + facet normal 0.868292 0.0268397 0.495326 + outer loop + vertex 1.09073 1.57294 2.60634 + vertex 1.089 1.57234 2.60941 + vertex 1.08915 1.56784 2.6094 + endloop + endfacet + facet normal 0.919332 0.028865 0.392423 + outer loop + vertex 1.089 1.57234 2.60941 + vertex 1.0877 1.56892 2.61271 + vertex 1.08915 1.56784 2.6094 + endloop + endfacet + facet normal 0.913554 0.0426382 0.404475 + outer loop + vertex 1.0878 1.57271 2.61209 + vertex 1.0877 1.56892 2.61271 + vertex 1.089 1.57234 2.60941 + endloop + endfacet + facet normal 0.453904 0.00181808 0.891049 + outer loop + vertex 1.09335 1.575 2.605 + vertex 1.09333 1.58 2.605 + vertex 1.09073 1.57294 2.60634 + endloop + endfacet + facet normal 0.548045 -0.043359 0.835324 + outer loop + vertex 1.09333 1.58 2.605 + vertex 1.0904 1.57807 2.60682 + vertex 1.09073 1.57294 2.60634 + endloop + endfacet + facet normal 0.863356 0.0228166 0.50408 + outer loop + vertex 1.08862 1.57552 2.60998 + vertex 1.0904 1.57807 2.60682 + vertex 1.08878 1.57965 2.60953 + endloop + endfacet + facet normal 0.866885 0.0132418 0.498333 + outer loop + vertex 1.08862 1.57552 2.60998 + vertex 1.089 1.57234 2.60941 + vertex 1.0904 1.57807 2.60682 + endloop + endfacet + facet normal 0.869974 0.0100723 0.492995 + outer loop + vertex 1.089 1.57234 2.60941 + vertex 1.09073 1.57294 2.60634 + vertex 1.0904 1.57807 2.60682 + endloop + endfacet + facet normal 0.913443 0.0353118 0.405431 + outer loop + vertex 1.089 1.57234 2.60941 + vertex 1.08862 1.57552 2.60998 + vertex 1.0878 1.57271 2.61209 + endloop + endfacet + facet normal 0.533663 -0.0117438 0.845616 + outer loop + vertex 1.09333 1.58 2.605 + vertex 1.09344 1.585 2.605 + vertex 1.0904 1.57807 2.60682 + endloop + endfacet + facet normal 0.465643 0.0283453 0.884519 + outer loop + vertex 1.09344 1.585 2.605 + vertex 1.09068 1.58418 2.60648 + vertex 1.0904 1.57807 2.60682 + endloop + endfacet + facet normal 0.855097 -0.0101634 0.518369 + outer loop + vertex 1.09068 1.58418 2.60648 + vertex 1.08878 1.57965 2.60953 + vertex 1.0904 1.57807 2.60682 + endloop + endfacet + facet normal 0.860454 -0.0185936 0.509188 + outer loop + vertex 1.08881 1.58467 2.60966 + vertex 1.08878 1.57965 2.60953 + vertex 1.09068 1.58418 2.60648 + endloop + endfacet + facet normal 0.478587 -0.0277501 0.877602 + outer loop + vertex 1.09344 1.585 2.605 + vertex 1.09373 1.59 2.605 + vertex 1.09068 1.58418 2.60648 + endloop + endfacet + facet normal 0.475094 -0.0254206 0.879568 + outer loop + vertex 1.09373 1.59 2.605 + vertex 1.09072 1.58972 2.60662 + vertex 1.09068 1.58418 2.60648 + endloop + endfacet + facet normal 0.860423 -0.0189656 0.509227 + outer loop + vertex 1.09072 1.58972 2.60662 + vertex 1.08881 1.58467 2.60966 + vertex 1.09068 1.58418 2.60648 + endloop + endfacet + facet normal 0.874649 -0.0401128 0.483095 + outer loop + vertex 1.08874 1.58868 2.61011 + vertex 1.08881 1.58467 2.60966 + vertex 1.09072 1.58972 2.60662 + endloop + endfacet + facet normal 0.475167 -0.0266115 0.879493 + outer loop + vertex 1.09373 1.59 2.605 + vertex 1.09401 1.595 2.605 + vertex 1.09072 1.58972 2.60662 + endloop + endfacet + facet normal 0.118701 0.222278 0.967731 + outer loop + vertex 1.09401 1.595 2.605 + vertex 1.09155 1.59458 2.6054 + vertex 1.09072 1.58972 2.60662 + endloop + endfacet + facet normal 0.907541 -0.0204491 0.419465 + outer loop + vertex 1.08874 1.58868 2.61011 + vertex 1.08947 1.59322 2.60875 + vertex 1.08774 1.59048 2.61237 + endloop + endfacet + facet normal 0.869248 0.00812236 0.49431 + outer loop + vertex 1.08874 1.58868 2.61011 + vertex 1.09072 1.58972 2.60662 + vertex 1.08947 1.59322 2.60875 + endloop + endfacet + facet normal 0.852533 -0.0149581 0.52246 + outer loop + vertex 1.09072 1.58972 2.60662 + vertex 1.09155 1.59458 2.6054 + vertex 1.08947 1.59322 2.60875 + endloop + endfacet + facet normal 0.901025 0.00259066 0.43376 + outer loop + vertex 1.08947 1.59322 2.60875 + vertex 1.08753 1.59453 2.61277 + vertex 1.08774 1.59048 2.61237 + endloop + endfacet + facet normal 0.159843 -0.00159679 0.987141 + outer loop + vertex 1.09401 1.595 2.605 + vertex 1.09406 1.6 2.605 + vertex 1.09155 1.59458 2.6054 + endloop + endfacet + facet normal 0.262933 -0.0510178 0.963464 + outer loop + vertex 1.09406 1.6 2.605 + vertex 1.09116 1.59782 2.60568 + vertex 1.09155 1.59458 2.6054 + endloop + endfacet + facet normal 0.838384 0.0554306 0.542255 + outer loop + vertex 1.09155 1.59458 2.6054 + vertex 1.09116 1.59782 2.60568 + vertex 1.08947 1.59322 2.60875 + endloop + endfacet + facet normal 0.891748 -0.0245998 0.451863 + outer loop + vertex 1.09116 1.59782 2.60568 + vertex 1.08934 1.59823 2.60928 + vertex 1.08947 1.59322 2.60875 + endloop + endfacet + facet normal 0.897484 -0.0232329 0.440434 + outer loop + vertex 1.08934 1.59823 2.60928 + vertex 1.08753 1.59453 2.61277 + vertex 1.08947 1.59322 2.60875 + endloop + endfacet + facet normal 0.887386 0.00107965 0.461026 + outer loop + vertex 1.08743 1.59935 2.61296 + vertex 1.08753 1.59453 2.61277 + vertex 1.08934 1.59823 2.60928 + endloop + endfacet + facet normal 0.503861 0.331604 0.797598 + outer loop + vertex 1.095 1.6 2.60176 + vertex 1.09448 1.60455 2.60019 + vertex 1.09271 1.60115 2.60273 + endloop + endfacet + facet normal 0.492442 0.858538 0.142877 + outer loop + vertex 1.09406 1.6 2.605 + vertex 1.095 1.6 2.60176 + vertex 1.09271 1.60115 2.60273 + endloop + endfacet + facet normal -0.391825 0.704346 0.591921 + outer loop + vertex 1.09406 1.6 2.605 + vertex 1.09271 1.60115 2.60273 + vertex 1.09116 1.59782 2.60568 + endloop + endfacet + facet normal 0.874733 0.0223285 0.484091 + outer loop + vertex 1.09271 1.60115 2.60273 + vertex 1.09097 1.60213 2.60581 + vertex 1.09116 1.59782 2.60568 + endloop + endfacet + facet normal 0.89402 0.0243179 0.447366 + outer loop + vertex 1.09116 1.59782 2.60568 + vertex 1.09097 1.60213 2.60581 + vertex 1.08934 1.59823 2.60928 + endloop + endfacet + facet normal 0.912382 -0.0176179 0.408961 + outer loop + vertex 1.09097 1.60213 2.60581 + vertex 1.08934 1.60315 2.6095 + vertex 1.08934 1.59823 2.60928 + endloop + endfacet + facet normal 0.88456 -0.0200861 0.465994 + outer loop + vertex 1.08934 1.60315 2.6095 + vertex 1.08743 1.59935 2.61296 + vertex 1.08934 1.59823 2.60928 + endloop + endfacet + facet normal 0.873468 0.00450561 0.48686 + outer loop + vertex 1.08741 1.60425 2.61295 + vertex 1.08743 1.59935 2.61296 + vertex 1.08934 1.60315 2.6095 + endloop + endfacet + facet normal 0.768887 -0.00686647 0.639348 + outer loop + vertex 1.09448 1.60455 2.60019 + vertex 1.09462 1.60957 2.60008 + vertex 1.09257 1.60573 2.6025 + endloop + endfacet + facet normal 0.782687 0.053425 0.620119 + outer loop + vertex 1.09271 1.60115 2.60273 + vertex 1.09448 1.60455 2.60019 + vertex 1.09257 1.60573 2.6025 + endloop + endfacet + facet normal 0.877449 0.0491151 0.47715 + outer loop + vertex 1.09271 1.60115 2.60273 + vertex 1.09257 1.60573 2.6025 + vertex 1.09097 1.60213 2.60581 + endloop + endfacet + facet normal 0.909368 -0.0218259 0.41542 + outer loop + vertex 1.09257 1.60573 2.6025 + vertex 1.09102 1.60706 2.60598 + vertex 1.09097 1.60213 2.60581 + endloop + endfacet + facet normal 0.911891 -0.0216621 0.409861 + outer loop + vertex 1.09097 1.60213 2.60581 + vertex 1.09102 1.60706 2.60598 + vertex 1.08934 1.60315 2.6095 + endloop + endfacet + facet normal 0.909158 -0.0148048 0.416188 + outer loop + vertex 1.09102 1.60706 2.60598 + vertex 1.0894 1.60812 2.60955 + vertex 1.08934 1.60315 2.6095 + endloop + endfacet + facet normal 0.870697 -0.0150934 0.491587 + outer loop + vertex 1.0894 1.60812 2.60955 + vertex 1.08741 1.60425 2.61295 + vertex 1.08934 1.60315 2.6095 + endloop + endfacet + facet normal 0.865714 -0.00465763 0.500518 + outer loop + vertex 1.08747 1.60926 2.6129 + vertex 1.08741 1.60425 2.61295 + vertex 1.0894 1.60812 2.60955 + endloop + endfacet + facet normal 0.791044 -0.0340478 0.610812 + outer loop + vertex 1.09462 1.60957 2.60008 + vertex 1.09469 1.61459 2.60027 + vertex 1.09265 1.61081 2.60271 + endloop + endfacet + facet normal 0.790521 -0.0360605 0.611372 + outer loop + vertex 1.09257 1.60573 2.6025 + vertex 1.09462 1.60957 2.60008 + vertex 1.09265 1.61081 2.60271 + endloop + endfacet + facet normal 0.907988 -0.0299477 0.417924 + outer loop + vertex 1.09257 1.60573 2.6025 + vertex 1.09265 1.61081 2.60271 + vertex 1.09102 1.60706 2.60598 + endloop + endfacet + facet normal 0.903502 -0.0190857 0.428159 + outer loop + vertex 1.09265 1.61081 2.60271 + vertex 1.09102 1.61192 2.60619 + vertex 1.09102 1.60706 2.60598 + endloop + endfacet + facet normal 0.908675 -0.0185992 0.41709 + outer loop + vertex 1.09102 1.60706 2.60598 + vertex 1.09102 1.61192 2.60619 + vertex 1.0894 1.60812 2.60955 + endloop + endfacet + facet normal 0.906731 -0.0139034 0.42148 + outer loop + vertex 1.09102 1.61192 2.60619 + vertex 1.08944 1.61292 2.60962 + vertex 1.0894 1.60812 2.60955 + endloop + endfacet + facet normal 0.864129 -0.0147544 0.503054 + outer loop + vertex 1.08944 1.61292 2.60962 + vertex 1.08747 1.60926 2.6129 + vertex 1.0894 1.60812 2.60955 + endloop + endfacet + facet normal 0.861155 -0.00847654 0.508272 + outer loop + vertex 1.08756 1.6143 2.61283 + vertex 1.08747 1.60926 2.6129 + vertex 1.08944 1.61292 2.60962 + endloop + endfacet + facet normal 0.804725 0.0391925 0.592352 + outer loop + vertex 1.09469 1.61459 2.60027 + vertex 1.09442 1.61857 2.60037 + vertex 1.09252 1.61609 2.60313 + endloop + endfacet + facet normal 0.787686 -0.0292798 0.615381 + outer loop + vertex 1.09265 1.61081 2.60271 + vertex 1.09469 1.61459 2.60027 + vertex 1.09252 1.61609 2.60313 + endloop + endfacet + facet normal 0.904548 -0.011439 0.426217 + outer loop + vertex 1.09265 1.61081 2.60271 + vertex 1.09252 1.61609 2.60313 + vertex 1.09102 1.61192 2.60619 + endloop + endfacet + facet normal 0.906426 -0.0151503 0.422092 + outer loop + vertex 1.09252 1.61609 2.60313 + vertex 1.09084 1.61587 2.60672 + vertex 1.09102 1.61192 2.60619 + endloop + endfacet + facet normal 0.906582 -0.0150982 0.42176 + outer loop + vertex 1.09102 1.61192 2.60619 + vertex 1.09084 1.61587 2.60672 + vertex 1.08944 1.61292 2.60962 + endloop + endfacet + facet normal 0.905095 -0.0111546 0.425063 + outer loop + vertex 1.09084 1.61587 2.60672 + vertex 1.08954 1.61762 2.60952 + vertex 1.08944 1.61292 2.60962 + endloop + endfacet + facet normal 0.86114 -0.00855191 0.508296 + outer loop + vertex 1.08954 1.61762 2.60952 + vertex 1.08756 1.6143 2.61283 + vertex 1.08944 1.61292 2.60962 + endloop + endfacet + facet normal 0.860564 -0.00721375 0.509292 + outer loop + vertex 1.08763 1.61933 2.61278 + vertex 1.08756 1.6143 2.61283 + vertex 1.08954 1.61762 2.60952 + endloop + endfacet + facet normal 0.80538 0.0378074 0.591552 + outer loop + vertex 1.09442 1.61857 2.60037 + vertex 1.09317 1.62045 2.60195 + vertex 1.09252 1.61609 2.60313 + endloop + endfacet + facet normal 0.898703 -0.023713 0.437917 + outer loop + vertex 1.09317 1.62045 2.60195 + vertex 1.09303 1.62441 2.60247 + vertex 1.09142 1.62036 2.60554 + endloop + endfacet + facet normal 0.898758 -0.0174755 0.438096 + outer loop + vertex 1.09317 1.62045 2.60195 + vertex 1.09142 1.62036 2.60554 + vertex 1.09252 1.61609 2.60313 + endloop + endfacet + facet normal 0.906316 -0.00673935 0.422547 + outer loop + vertex 1.09252 1.61609 2.60313 + vertex 1.09142 1.62036 2.60554 + vertex 1.09084 1.61587 2.60672 + endloop + endfacet + facet normal 0.90621 -0.00666606 0.422774 + outer loop + vertex 1.09084 1.61587 2.60672 + vertex 1.09142 1.62036 2.60554 + vertex 1.08954 1.61762 2.60952 + endloop + endfacet + facet normal 0.907216 -0.0106109 0.42053 + outer loop + vertex 1.09142 1.62036 2.60554 + vertex 1.08962 1.62247 2.60947 + vertex 1.08954 1.61762 2.60952 + endloop + endfacet + facet normal 0.860159 -0.00891337 0.509948 + outer loop + vertex 1.08962 1.62247 2.60947 + vertex 1.08763 1.61933 2.61278 + vertex 1.08954 1.61762 2.60952 + endloop + endfacet + facet normal 0.858243 -0.00425095 0.513226 + outer loop + vertex 1.08766 1.62433 2.61278 + vertex 1.08763 1.61933 2.61278 + vertex 1.08962 1.62247 2.60947 + endloop + endfacet + facet normal 0.89851 -0.0384819 0.437262 + outer loop + vertex 1.09303 1.62441 2.60247 + vertex 1.093 1.62925 2.60296 + vertex 1.09132 1.62562 2.60608 + endloop + endfacet + facet normal 0.900348 -0.0270885 0.434327 + outer loop + vertex 1.09142 1.62036 2.60554 + vertex 1.09303 1.62441 2.60247 + vertex 1.09132 1.62562 2.60608 + endloop + endfacet + facet normal 0.903698 -0.0263109 0.427361 + outer loop + vertex 1.09142 1.62036 2.60554 + vertex 1.09132 1.62562 2.60608 + vertex 1.08962 1.62247 2.60947 + endloop + endfacet + facet normal 0.90056 -0.0170409 0.434398 + outer loop + vertex 1.09132 1.62562 2.60608 + vertex 1.08962 1.62739 2.60968 + vertex 1.08962 1.62247 2.60947 + endloop + endfacet + facet normal 0.85396 -0.0207055 0.519927 + outer loop + vertex 1.08962 1.62739 2.60968 + vertex 1.08766 1.62433 2.61278 + vertex 1.08962 1.62247 2.60947 + endloop + endfacet + facet normal 0.847269 -0.00508468 0.53114 + outer loop + vertex 1.08767 1.62927 2.6128 + vertex 1.08766 1.62433 2.61278 + vertex 1.08962 1.62739 2.60968 + endloop + endfacet + facet normal 0.895595 -0.0506294 0.441979 + outer loop + vertex 1.093 1.62925 2.60296 + vertex 1.0931 1.63418 2.60331 + vertex 1.09134 1.63051 2.60645 + endloop + endfacet + facet normal 0.898039 -0.0373455 0.438329 + outer loop + vertex 1.09132 1.62562 2.60608 + vertex 1.093 1.62925 2.60296 + vertex 1.09134 1.63051 2.60645 + endloop + endfacet + facet normal 0.896035 -0.0376411 0.442385 + outer loop + vertex 1.09132 1.62562 2.60608 + vertex 1.09134 1.63051 2.60645 + vertex 1.08962 1.62739 2.60968 + endloop + endfacet + facet normal 0.889611 -0.0197218 0.456293 + outer loop + vertex 1.09134 1.63051 2.60645 + vertex 1.08964 1.63227 2.60985 + vertex 1.08962 1.62739 2.60968 + endloop + endfacet + facet normal 0.842311 -0.022424 0.538524 + outer loop + vertex 1.08964 1.63227 2.60985 + vertex 1.08767 1.62927 2.6128 + vertex 1.08962 1.62739 2.60968 + endloop + endfacet + facet normal 0.828586 0.00747748 0.559811 + outer loop + vertex 1.08763 1.63414 2.61279 + vertex 1.08767 1.62927 2.6128 + vertex 1.08964 1.63227 2.60985 + endloop + endfacet + facet normal 0.890674 -0.041986 0.452699 + outer loop + vertex 1.0931 1.63418 2.60331 + vertex 1.09323 1.63915 2.60351 + vertex 1.09143 1.63543 2.60671 + endloop + endfacet + facet normal 0.891083 -0.0398038 0.452092 + outer loop + vertex 1.09134 1.63051 2.60645 + vertex 1.0931 1.63418 2.60331 + vertex 1.09143 1.63543 2.60671 + endloop + endfacet + facet normal 0.884676 -0.0403389 0.464459 + outer loop + vertex 1.09134 1.63051 2.60645 + vertex 1.09143 1.63543 2.60671 + vertex 1.08964 1.63227 2.60985 + endloop + endfacet + facet normal 0.873728 -0.0124735 0.486255 + outer loop + vertex 1.09143 1.63543 2.60671 + vertex 1.08963 1.63717 2.60999 + vertex 1.08964 1.63227 2.60985 + endloop + endfacet + facet normal 0.821883 -0.0148675 0.569462 + outer loop + vertex 1.08963 1.63717 2.60999 + vertex 1.08763 1.63414 2.61279 + vertex 1.08964 1.63227 2.60985 + endloop + endfacet + facet normal 0.796472 0.0335434 0.603744 + outer loop + vertex 1.0874 1.63903 2.61283 + vertex 1.08763 1.63414 2.61279 + vertex 1.08963 1.63717 2.60999 + endloop + endfacet + facet normal 0.8855 -0.0323926 0.463509 + outer loop + vertex 1.09323 1.63915 2.60351 + vertex 1.09337 1.64419 2.60361 + vertex 1.09151 1.64043 2.60689 + endloop + endfacet + facet normal 0.885808 -0.0307227 0.463034 + outer loop + vertex 1.09143 1.63543 2.60671 + vertex 1.09323 1.63915 2.60351 + vertex 1.09151 1.64043 2.60689 + endloop + endfacet + facet normal 0.86901 -0.0315674 0.493787 + outer loop + vertex 1.09143 1.63543 2.60671 + vertex 1.09151 1.64043 2.60689 + vertex 1.08963 1.63717 2.60999 + endloop + endfacet + facet normal 0.852191 0.00608434 0.523196 + outer loop + vertex 1.09151 1.64043 2.60689 + vertex 1.08952 1.64216 2.61012 + vertex 1.08963 1.63717 2.60999 + endloop + endfacet + facet normal 0.787086 0.00215505 0.61684 + outer loop + vertex 1.08952 1.64216 2.61012 + vertex 1.0874 1.63903 2.61283 + vertex 1.08963 1.63717 2.60999 + endloop + endfacet + facet normal 0.743822 0.0726458 0.664419 + outer loop + vertex 1.0867 1.64436 2.61303 + vertex 1.0874 1.63903 2.61283 + vertex 1.08952 1.64216 2.61012 + endloop + endfacet + facet normal 0.882067 -0.016119 0.470848 + outer loop + vertex 1.09337 1.64419 2.60361 + vertex 1.09344 1.64921 2.60364 + vertex 1.09157 1.64545 2.60701 + endloop + endfacet + facet normal 0.881011 -0.0222468 0.472572 + outer loop + vertex 1.09151 1.64043 2.60689 + vertex 1.09337 1.64419 2.60361 + vertex 1.09157 1.64545 2.60701 + endloop + endfacet + facet normal 0.844924 -0.0232741 0.53438 + outer loop + vertex 1.09151 1.64043 2.60689 + vertex 1.09157 1.64545 2.60701 + vertex 1.08952 1.64216 2.61012 + endloop + endfacet + facet normal 0.833861 0.000210717 0.551974 + outer loop + vertex 1.09157 1.64545 2.60701 + vertex 1.08952 1.64706 2.61011 + vertex 1.08952 1.64216 2.61012 + endloop + endfacet + facet normal 0.718998 0.000490633 0.695012 + outer loop + vertex 1.08952 1.64706 2.61011 + vertex 1.0867 1.64436 2.61303 + vertex 1.08952 1.64216 2.61012 + endloop + endfacet + facet normal 0.714058 0.0110137 0.7 + outer loop + vertex 1.08739 1.64884 2.61226 + vertex 1.0867 1.64436 2.61303 + vertex 1.08952 1.64706 2.61011 + endloop + endfacet + facet normal 0.883495 -0.012643 0.468271 + outer loop + vertex 1.09344 1.64921 2.60364 + vertex 1.09348 1.65422 2.6037 + vertex 1.09163 1.65046 2.60709 + endloop + endfacet + facet normal 0.882691 -0.0175274 0.469626 + outer loop + vertex 1.09157 1.64545 2.60701 + vertex 1.09344 1.64921 2.60364 + vertex 1.09163 1.65046 2.60709 + endloop + endfacet + facet normal 0.829256 -0.018416 0.558565 + outer loop + vertex 1.09157 1.64545 2.60701 + vertex 1.09163 1.65046 2.60709 + vertex 1.08952 1.64706 2.61011 + endloop + endfacet + facet normal 0.818457 0.00246054 0.574563 + outer loop + vertex 1.09163 1.65046 2.60709 + vertex 1.08953 1.65177 2.61008 + vertex 1.08952 1.64706 2.61011 + endloop + endfacet + facet normal 0.710965 0.00343788 0.703219 + outer loop + vertex 1.08953 1.65177 2.61008 + vertex 1.08739 1.64884 2.61226 + vertex 1.08952 1.64706 2.61011 + endloop + endfacet + facet normal 0.676903 0.0513864 0.734277 + outer loop + vertex 1.08685 1.65275 2.61248 + vertex 1.08739 1.64884 2.61226 + vertex 1.08953 1.65177 2.61008 + endloop + endfacet + facet normal 0.88249 -0.0181663 0.469981 + outer loop + vertex 1.09348 1.65422 2.6037 + vertex 1.09354 1.65923 2.60378 + vertex 1.09166 1.65549 2.60717 + endloop + endfacet + facet normal 0.883432 -0.0125019 0.468393 + outer loop + vertex 1.09163 1.65046 2.60709 + vertex 1.09348 1.65422 2.6037 + vertex 1.09166 1.65549 2.60717 + endloop + endfacet + facet normal 0.815008 -0.0138296 0.579285 + outer loop + vertex 1.09163 1.65046 2.60709 + vertex 1.09166 1.65549 2.60717 + vertex 1.08953 1.65177 2.61008 + endloop + endfacet + facet normal 0.798546 0.0132291 0.601789 + outer loop + vertex 1.09166 1.65549 2.60717 + vertex 1.0894 1.65656 2.61014 + vertex 1.08953 1.65177 2.61008 + endloop + endfacet + facet normal 0.669071 0.00826607 0.743153 + outer loop + vertex 1.0894 1.65656 2.61014 + vertex 1.08685 1.65275 2.61248 + vertex 1.08953 1.65177 2.61008 + endloop + endfacet + facet normal 0.642242 0.0400185 0.765457 + outer loop + vertex 1.08659 1.65734 2.61246 + vertex 1.08685 1.65275 2.61248 + vertex 1.0894 1.65656 2.61014 + endloop + endfacet + facet normal 0.875967 -0.0152071 0.48213 + outer loop + vertex 1.09354 1.65923 2.60378 + vertex 1.09363 1.66426 2.60377 + vertex 1.09169 1.66058 2.60719 + endloop + endfacet + facet normal 0.877449 -0.00685958 0.479621 + outer loop + vertex 1.09166 1.65549 2.60717 + vertex 1.09354 1.65923 2.60378 + vertex 1.09169 1.66058 2.60719 + endloop + endfacet + facet normal 0.795089 -0.00690754 0.606454 + outer loop + vertex 1.09166 1.65549 2.60717 + vertex 1.09169 1.66058 2.60719 + vertex 1.0894 1.65656 2.61014 + endloop + endfacet + facet normal 0.782538 0.0119705 0.622488 + outer loop + vertex 1.09169 1.66058 2.60719 + vertex 1.08937 1.66156 2.61009 + vertex 1.0894 1.65656 2.61014 + endloop + endfacet + facet normal 0.638219 0.0125388 0.769753 + outer loop + vertex 1.08937 1.66156 2.61009 + vertex 1.08659 1.65734 2.61246 + vertex 1.0894 1.65656 2.61014 + endloop + endfacet + facet normal 0.60741 0.0458731 0.793063 + outer loop + vertex 1.08643 1.66212 2.61231 + vertex 1.08659 1.65734 2.61246 + vertex 1.08937 1.66156 2.61009 + endloop + endfacet + facet normal 0.872503 -0.017724 0.488288 + outer loop + vertex 1.09363 1.66426 2.60377 + vertex 1.09373 1.66929 2.60377 + vertex 1.09178 1.6657 2.60714 + endloop + endfacet + facet normal 0.873903 -0.0105236 0.485986 + outer loop + vertex 1.09169 1.66058 2.60719 + vertex 1.09363 1.66426 2.60377 + vertex 1.09178 1.6657 2.60714 + endloop + endfacet + facet normal 0.779383 -0.00738893 0.626504 + outer loop + vertex 1.09169 1.66058 2.60719 + vertex 1.09178 1.6657 2.60714 + vertex 1.08937 1.66156 2.61009 + endloop + endfacet + facet normal 0.773317 0.0014817 0.634018 + outer loop + vertex 1.09178 1.6657 2.60714 + vertex 1.08948 1.66663 2.60994 + vertex 1.08937 1.66156 2.61009 + endloop + endfacet + facet normal 0.603688 0.00985127 0.797159 + outer loop + vertex 1.08948 1.66663 2.60994 + vertex 1.08643 1.66212 2.61231 + vertex 1.08937 1.66156 2.61009 + endloop + endfacet + facet normal 0.582043 0.032538 0.812507 + outer loop + vertex 1.08653 1.66711 2.61203 + vertex 1.08643 1.66212 2.61231 + vertex 1.08948 1.66663 2.60994 + endloop + endfacet + facet normal 0.871468 -0.0271611 0.4897 + outer loop + vertex 1.09373 1.66929 2.60377 + vertex 1.09382 1.67421 2.60389 + vertex 1.09193 1.67072 2.60707 + endloop + endfacet + facet normal 0.873122 -0.0191529 0.487125 + outer loop + vertex 1.09178 1.6657 2.60714 + vertex 1.09373 1.66929 2.60377 + vertex 1.09193 1.67072 2.60707 + endloop + endfacet + facet normal 0.770702 -0.0140737 0.637041 + outer loop + vertex 1.09178 1.6657 2.60714 + vertex 1.09193 1.67072 2.60707 + vertex 1.08948 1.66663 2.60994 + endloop + endfacet + facet normal 0.769303 -0.0120234 0.638771 + outer loop + vertex 1.09193 1.67072 2.60707 + vertex 1.0897 1.67168 2.60977 + vertex 1.08948 1.66663 2.60994 + endloop + endfacet + facet normal 0.579079 0.00196421 0.815269 + outer loop + vertex 1.0897 1.67168 2.60977 + vertex 1.08653 1.66711 2.61203 + vertex 1.08948 1.66663 2.60994 + endloop + endfacet + facet normal 0.55118 0.0304386 0.833831 + outer loop + vertex 1.08674 1.6722 2.61171 + vertex 1.08653 1.66711 2.61203 + vertex 1.0897 1.67168 2.60977 + endloop + endfacet + facet normal 0.870776 -0.0334238 0.490543 + outer loop + vertex 1.09382 1.67421 2.60389 + vertex 1.09381 1.67892 2.60423 + vertex 1.09206 1.67559 2.60711 + endloop + endfacet + facet normal 0.871893 -0.0281303 0.488889 + outer loop + vertex 1.09193 1.67072 2.60707 + vertex 1.09382 1.67421 2.60389 + vertex 1.09206 1.67559 2.60711 + endloop + endfacet + facet normal 0.766581 -0.0263729 0.641606 + outer loop + vertex 1.09193 1.67072 2.60707 + vertex 1.09206 1.67559 2.60711 + vertex 1.0897 1.67168 2.60977 + endloop + endfacet + facet normal 0.752051 -0.00565547 0.659081 + outer loop + vertex 1.09206 1.67559 2.60711 + vertex 1.08981 1.67674 2.60969 + vertex 1.0897 1.67168 2.60977 + endloop + endfacet + facet normal 0.547904 0.00188518 0.836539 + outer loop + vertex 1.08981 1.67674 2.60969 + vertex 1.08674 1.6722 2.61171 + vertex 1.0897 1.67168 2.60977 + endloop + endfacet + facet normal 0.497957 0.0486512 0.865836 + outer loop + vertex 1.08669 1.67741 2.61145 + vertex 1.08674 1.6722 2.61171 + vertex 1.08981 1.67674 2.60969 + endloop + endfacet + facet normal 0.855037 -0.0354632 0.517353 + outer loop + vertex 1.09381 1.67892 2.60423 + vertex 1.0936 1.68276 2.60484 + vertex 1.09203 1.68029 2.60726 + endloop + endfacet + facet normal 0.86034 -0.0114819 0.509592 + outer loop + vertex 1.09206 1.67559 2.60711 + vertex 1.09381 1.67892 2.60423 + vertex 1.09203 1.68029 2.60726 + endloop + endfacet + facet normal 0.74936 -0.0172449 0.661938 + outer loop + vertex 1.09206 1.67559 2.60711 + vertex 1.09203 1.68029 2.60726 + vertex 1.08981 1.67674 2.60969 + endloop + endfacet + facet normal 0.709514 0.0362432 0.703759 + outer loop + vertex 1.09203 1.68029 2.60726 + vertex 1.08946 1.68235 2.60975 + vertex 1.08981 1.67674 2.60969 + endloop + endfacet + facet normal 0.494034 0.0212224 0.869184 + outer loop + vertex 1.08946 1.68235 2.60975 + vertex 1.08669 1.67741 2.61145 + vertex 1.08981 1.67674 2.60969 + endloop + endfacet + facet normal 0.408666 0.0828264 0.908918 + outer loop + vertex 1.08581 1.68259 2.61137 + vertex 1.08669 1.67741 2.61145 + vertex 1.08946 1.68235 2.60975 + endloop + endfacet + facet normal 0.829357 0.0212081 0.558317 + outer loop + vertex 1.0936 1.68276 2.60484 + vertex 1.09201 1.68495 2.60712 + vertex 1.09203 1.68029 2.60726 + endloop + endfacet + facet normal 0.634976 0.0404472 0.771473 + outer loop + vertex 1.09201 1.68495 2.60712 + vertex 1.09242 1.68891 2.60658 + vertex 1.08903 1.68865 2.60938 + endloop + endfacet + facet normal 0.66967 0.0891604 0.737288 + outer loop + vertex 1.09201 1.68495 2.60712 + vertex 1.08903 1.68865 2.60938 + vertex 1.08946 1.68235 2.60975 + endloop + endfacet + facet normal 0.705259 0.0252152 0.708501 + outer loop + vertex 1.09201 1.68495 2.60712 + vertex 1.08946 1.68235 2.60975 + vertex 1.09203 1.68029 2.60726 + endloop + endfacet + facet normal 0.628004 0.0884381 0.773168 + outer loop + vertex 1.08946 1.68235 2.60975 + vertex 1.08903 1.68865 2.60938 + vertex 1.08809 1.68515 2.61055 + endloop + endfacet + facet normal 0.401155 -0.0634911 0.913807 + outer loop + vertex 1.08946 1.68235 2.60975 + vertex 1.08809 1.68515 2.61055 + vertex 1.08581 1.68259 2.61137 + endloop + endfacet + facet normal 0.638547 -0.0343563 0.768816 + outer loop + vertex 1.09242 1.68891 2.60658 + vertex 1.09189 1.69274 2.60719 + vertex 1.08903 1.68865 2.60938 + endloop + endfacet + facet normal 0.561235 0.0503517 0.826124 + outer loop + vertex 1.08903 1.68865 2.60938 + vertex 1.09189 1.69274 2.60719 + vertex 1.08917 1.69395 2.60896 + endloop + endfacet + facet normal 0.547117 0.00264149 0.837052 + outer loop + vertex 1.09189 1.69274 2.60719 + vertex 1.09161 1.69729 2.60736 + vertex 1.08917 1.69395 2.60896 + endloop + endfacet + facet normal 0.458817 0.0893966 0.884022 + outer loop + vertex 1.08917 1.69395 2.60896 + vertex 1.09161 1.69729 2.60736 + vertex 1.08825 1.69788 2.60904 + endloop + endfacet + facet normal 0.452701 0.033656 0.891027 + outer loop + vertex 1.09161 1.69729 2.60736 + vertex 1.0914 1.70201 2.60729 + vertex 1.08825 1.69788 2.60904 + endloop + endfacet + facet normal 0.395348 0.0872845 0.914375 + outer loop + vertex 1.08825 1.69788 2.60904 + vertex 1.0914 1.70201 2.60729 + vertex 1.08784 1.70239 2.60879 + endloop + endfacet + facet normal 0.392715 0.0470777 0.918455 + outer loop + vertex 1.0914 1.70201 2.60729 + vertex 1.09139 1.70701 2.60703 + vertex 1.08784 1.70239 2.60879 + endloop + endfacet + facet normal 0.345401 0.089422 0.934185 + outer loop + vertex 1.08784 1.70239 2.60879 + vertex 1.09139 1.70701 2.60703 + vertex 1.08764 1.70715 2.60841 + endloop + endfacet + facet normal 0.344761 0.0386446 0.937895 + outer loop + vertex 1.09139 1.70701 2.60703 + vertex 1.09152 1.71215 2.60677 + vertex 1.08764 1.70715 2.60841 + endloop + endfacet + facet normal 0.299646 0.0778914 0.950866 + outer loop + vertex 1.08764 1.70715 2.60841 + vertex 1.09152 1.71215 2.60677 + vertex 1.0877 1.71219 2.60797 + endloop + endfacet + facet normal 0.300062 0.0328216 0.953355 + outer loop + vertex 1.09152 1.71215 2.60677 + vertex 1.09166 1.71713 2.60656 + vertex 1.0877 1.71219 2.60797 + endloop + endfacet + facet normal 0.252717 0.0738793 0.964715 + outer loop + vertex 1.0877 1.71219 2.60797 + vertex 1.09166 1.71713 2.60656 + vertex 1.0879 1.71728 2.60753 + endloop + endfacet + facet normal 0.252387 0.0564552 0.965978 + outer loop + vertex 1.09166 1.71713 2.60656 + vertex 1.09185 1.72191 2.60623 + vertex 1.0879 1.71728 2.60753 + endloop + endfacet + facet normal 0.227039 0.0646408 0.971738 + outer loop + vertex 1.09185 1.72191 2.60623 + vertex 1.09176 1.72662 2.60594 + vertex 1.08802 1.72231 2.6071 + endloop + endfacet + facet normal 0.132661 0.175931 0.975423 + outer loop + vertex 1.08918 1.9148 2.58019 + vertex 1.09052 1.9098 2.58091 + vertex 1.095 1.91279 2.57976 + endloop + endfacet + facet normal 0.258887 0.150161 0.954164 + outer loop + vertex 1.09022 1.99375 2.56622 + vertex 1.09154 1.99073 2.56634 + vertex 1.09466 1.99365 2.56503 + endloop + endfacet + facet normal 0.259271 0.127187 0.957393 + outer loop + vertex 1.09022 1.99375 2.56622 + vertex 1.09466 1.99365 2.56503 + vertex 1.09074 1.99768 2.56556 + endloop + endfacet + facet normal 0.273126 0.141437 0.951524 + outer loop + vertex 1.09074 1.99768 2.56556 + vertex 1.09466 1.99365 2.56503 + vertex 1.09448 1.99852 2.56436 + endloop + endfacet + facet normal 0.2755 0.157195 0.948361 + outer loop + vertex 1.09154 1.99073 2.56634 + vertex 1.09022 1.99375 2.56622 + vertex 1.08725 1.99102 2.56754 + endloop + endfacet + facet normal 0.291887 0.0997542 0.951237 + outer loop + vertex 1.08899 2.00093 2.56576 + vertex 1.08729 1.99842 2.56654 + vertex 1.09074 1.99768 2.56556 + endloop + endfacet + facet normal 0.291329 0.0994414 0.95144 + outer loop + vertex 1.08899 2.00093 2.56576 + vertex 1.09074 1.99768 2.56556 + vertex 1.09269 2.00299 2.56441 + endloop + endfacet + facet normal 0.28245 0.103198 0.953715 + outer loop + vertex 1.09269 2.00299 2.56441 + vertex 1.09074 1.99768 2.56556 + vertex 1.09448 1.99852 2.56436 + endloop + endfacet + facet normal 0.328576 0.0719196 0.941735 + outer loop + vertex 1.08899 2.00093 2.56576 + vertex 1.0858 2.00176 2.56681 + vertex 1.08729 1.99842 2.56654 + endloop + endfacet + facet normal 0.30571 0.0723311 0.949373 + outer loop + vertex 1.08887 2.00391 2.56557 + vertex 1.08899 2.00093 2.56576 + vertex 1.09269 2.00299 2.56441 + endloop + endfacet + facet normal 0.306831 0.0780624 0.948557 + outer loop + vertex 1.08887 2.00391 2.56557 + vertex 1.09269 2.00299 2.56441 + vertex 1.09021 2.00809 2.56479 + endloop + endfacet + facet normal 0.321928 0.0858313 0.942866 + outer loop + vertex 1.09021 2.00809 2.56479 + vertex 1.09269 2.00299 2.56441 + vertex 1.09416 2.0081 2.56344 + endloop + endfacet + facet normal 0.328769 0.0728328 0.941598 + outer loop + vertex 1.08899 2.00093 2.56576 + vertex 1.08887 2.00391 2.56557 + vertex 1.0858 2.00176 2.56681 + endloop + endfacet + facet normal 0.321694 0.0936032 0.942206 + outer loop + vertex 1.09416 2.0081 2.56344 + vertex 1.09317 2.01233 2.56336 + vertex 1.09021 2.00809 2.56479 + endloop + endfacet + facet normal 0.334255 0.0836935 0.938759 + outer loop + vertex 1.09021 2.00809 2.56479 + vertex 1.09317 2.01233 2.56336 + vertex 1.08948 2.0134 2.56458 + endloop + endfacet + facet normal 0.338175 0.100829 0.935666 + outer loop + vertex 1.09317 2.01233 2.56336 + vertex 1.09212 2.01638 2.5633 + vertex 1.08948 2.0134 2.56458 + endloop + endfacet + facet normal 0.346939 0.0920976 0.933355 + outer loop + vertex 1.08948 2.0134 2.56458 + vertex 1.09212 2.01638 2.5633 + vertex 1.08908 2.01826 2.56425 + endloop + endfacet + facet normal 0.353425 0.104471 0.929611 + outer loop + vertex 1.09212 2.01638 2.5633 + vertex 1.09279 2.02109 2.56252 + vertex 1.08908 2.01826 2.56425 + endloop + endfacet + facet normal 0.362356 0.0914895 0.927539 + outer loop + vertex 1.08908 2.01826 2.56425 + vertex 1.09279 2.02109 2.56252 + vertex 1.08855 2.0232 2.56397 + endloop + endfacet + facet normal 0.369245 0.108468 0.92298 + outer loop + vertex 1.09279 2.02109 2.56252 + vertex 1.09128 2.0271 2.56242 + vertex 1.08855 2.0232 2.56397 + endloop + endfacet + facet normal 0.396232 0.0860756 0.914107 + outer loop + vertex 1.08855 2.0232 2.56397 + vertex 1.09128 2.0271 2.56242 + vertex 1.08749 2.02747 2.56402 + endloop + endfacet + facet normal 0.376435 0.114983 0.91928 + outer loop + vertex 1.09452 2.02903 2.56085 + vertex 1.09539 2.03327 2.55996 + vertex 1.09205 2.03144 2.56156 + endloop + endfacet + facet normal 0.376435 0.114982 0.91928 + outer loop + vertex 1.09205 2.03144 2.56156 + vertex 1.09128 2.0271 2.56242 + vertex 1.09452 2.02903 2.56085 + endloop + endfacet + facet normal 0.419031 0.103957 0.902001 + outer loop + vertex 1.09205 2.03144 2.56156 + vertex 1.08801 2.03249 2.56331 + vertex 1.09128 2.0271 2.56242 + endloop + endfacet + facet normal 0.396334 0.0882282 0.913857 + outer loop + vertex 1.08801 2.03249 2.56331 + vertex 1.08749 2.02747 2.56402 + vertex 1.09128 2.0271 2.56242 + endloop + endfacet + facet normal 0.388397 0.12438 0.913059 + outer loop + vertex 1.09539 2.03327 2.55996 + vertex 1.09437 2.0384 2.5597 + vertex 1.09145 2.03553 2.56133 + endloop + endfacet + facet normal 0.380426 0.107117 0.918587 + outer loop + vertex 1.09205 2.03144 2.56156 + vertex 1.09539 2.03327 2.55996 + vertex 1.09145 2.03553 2.56133 + endloop + endfacet + facet normal 0.420411 0.111957 0.9004 + outer loop + vertex 1.09145 2.03553 2.56133 + vertex 1.08801 2.03249 2.56331 + vertex 1.09205 2.03144 2.56156 + endloop + endfacet + facet normal 0.429465 0.0998612 0.897545 + outer loop + vertex 1.08853 2.03758 2.5625 + vertex 1.08801 2.03249 2.56331 + vertex 1.09145 2.03553 2.56133 + endloop + endfacet + facet normal 0.407935 0.112499 0.906054 + outer loop + vertex 1.09437 2.0384 2.5597 + vertex 1.09391 2.04317 2.55931 + vertex 1.09098 2.04025 2.561 + endloop + endfacet + facet normal 0.404776 0.10508 0.908358 + outer loop + vertex 1.09145 2.03553 2.56133 + vertex 1.09437 2.0384 2.5597 + vertex 1.09098 2.04025 2.561 + endloop + endfacet + facet normal 0.433382 0.107 0.894836 + outer loop + vertex 1.09098 2.04025 2.561 + vertex 1.08853 2.03758 2.5625 + vertex 1.09145 2.03553 2.56133 + endloop + endfacet + facet normal 0.449585 0.0887911 0.888813 + outer loop + vertex 1.08765 2.0418 2.56252 + vertex 1.08853 2.03758 2.5625 + vertex 1.09098 2.04025 2.561 + endloop + endfacet + facet normal 0.428495 0.101262 0.897852 + outer loop + vertex 1.09391 2.04317 2.55931 + vertex 1.09344 2.0481 2.55898 + vertex 1.09048 2.04502 2.56074 + endloop + endfacet + facet normal 0.424818 0.0923507 0.900556 + outer loop + vertex 1.09098 2.04025 2.561 + vertex 1.09391 2.04317 2.55931 + vertex 1.09048 2.04502 2.56074 + endloop + endfacet + facet normal 0.451503 0.0944127 0.88726 + outer loop + vertex 1.09048 2.04502 2.56074 + vertex 1.08765 2.0418 2.56252 + vertex 1.09098 2.04025 2.561 + endloop + endfacet + facet normal 0.460155 0.0848653 0.883773 + outer loop + vertex 1.08708 2.04668 2.56235 + vertex 1.08765 2.0418 2.56252 + vertex 1.09048 2.04502 2.56074 + endloop + endfacet + facet normal 0.446036 0.0961857 0.889832 + outer loop + vertex 1.09344 2.0481 2.55898 + vertex 1.09248 2.05237 2.559 + vertex 1.08998 2.04976 2.56054 + endloop + endfacet + facet normal 0.442179 0.0853037 0.892861 + outer loop + vertex 1.09048 2.04502 2.56074 + vertex 1.09344 2.0481 2.55898 + vertex 1.08998 2.04976 2.56054 + endloop + endfacet + facet normal 0.460868 0.0868743 0.883206 + outer loop + vertex 1.08998 2.04976 2.56054 + vertex 1.08708 2.04668 2.56235 + vertex 1.09048 2.04502 2.56074 + endloop + endfacet + facet normal 0.458222 0.0899835 0.884271 + outer loop + vertex 1.08653 2.05157 2.56214 + vertex 1.08708 2.04668 2.56235 + vertex 1.08998 2.04976 2.56054 + endloop + endfacet + facet normal 0.456958 0.0895168 0.884973 + outer loop + vertex 1.09248 2.05237 2.559 + vertex 1.09303 2.05736 2.55821 + vertex 1.08959 2.05437 2.56029 + endloop + endfacet + facet normal 0.45493 0.085664 0.886398 + outer loop + vertex 1.08998 2.04976 2.56054 + vertex 1.09248 2.05237 2.559 + vertex 1.08959 2.05437 2.56029 + endloop + endfacet + facet normal 0.456585 0.0857569 0.885537 + outer loop + vertex 1.08959 2.05437 2.56029 + vertex 1.08653 2.05157 2.56214 + vertex 1.08998 2.04976 2.56054 + endloop + endfacet + facet normal 0.44415 0.102335 0.890089 + outer loop + vertex 1.0859 2.05662 2.56187 + vertex 1.08653 2.05157 2.56214 + vertex 1.08959 2.05437 2.56029 + endloop + endfacet + facet normal 0.454823 0.0925297 0.885762 + outer loop + vertex 1.08912 2.05831 2.56012 + vertex 1.08959 2.05437 2.56029 + vertex 1.09303 2.05736 2.55821 + endloop + endfacet + facet normal 0.457764 0.112098 0.881979 + outer loop + vertex 1.08912 2.05831 2.56012 + vertex 1.09303 2.05736 2.55821 + vertex 1.08982 2.06265 2.5592 + endloop + endfacet + facet normal 0.444395 0.1025 0.889948 + outer loop + vertex 1.08982 2.06265 2.5592 + vertex 1.09303 2.05736 2.55821 + vertex 1.09348 2.06243 2.5574 + endloop + endfacet + facet normal 0.438876 0.0909985 0.893928 + outer loop + vertex 1.08959 2.05437 2.56029 + vertex 1.08912 2.05831 2.56012 + vertex 1.0859 2.05662 2.56187 + endloop + endfacet + facet normal 0.444404 0.108105 0.889279 + outer loop + vertex 1.09348 2.06243 2.5574 + vertex 1.09223 2.06676 2.5575 + vertex 1.08982 2.06265 2.5592 + endloop + endfacet + facet normal 0.414422 0.130392 0.900695 + outer loop + vertex 1.08982 2.06265 2.5592 + vertex 1.09223 2.06676 2.5575 + vertex 1.08799 2.06864 2.55918 + endloop + endfacet + facet normal 0.40956 0.115691 0.904918 + outer loop + vertex 1.09223 2.06676 2.5575 + vertex 1.09115 2.07196 2.55733 + vertex 1.08799 2.06864 2.55918 + endloop + endfacet + facet normal 0.389573 0.13793 0.910609 + outer loop + vertex 1.08799 2.06864 2.55918 + vertex 1.09115 2.07196 2.55733 + vertex 1.08801 2.07254 2.55858 + endloop + endfacet + facet normal 0.421576 0.134152 0.896815 + outer loop + vertex 1.0941 2.07378 2.55571 + vertex 1.09501 2.07789 2.55467 + vertex 1.09198 2.07595 2.55638 + endloop + endfacet + facet normal 0.414742 0.126116 0.901157 + outer loop + vertex 1.09198 2.07595 2.55638 + vertex 1.09115 2.07196 2.55733 + vertex 1.0941 2.07378 2.55571 + endloop + endfacet + facet normal 0.364338 0.141193 0.920501 + outer loop + vertex 1.09198 2.07595 2.55638 + vertex 1.08822 2.07622 2.55783 + vertex 1.09115 2.07196 2.55733 + endloop + endfacet + facet normal 0.392035 0.161945 0.905584 + outer loop + vertex 1.08822 2.07622 2.55783 + vertex 1.08801 2.07254 2.55858 + vertex 1.09115 2.07196 2.55733 + endloop + endfacet + facet normal 0.395915 0.142413 0.907177 + outer loop + vertex 1.09501 2.07789 2.55467 + vertex 1.09345 2.08381 2.55442 + vertex 1.09086 2.07988 2.55617 + endloop + endfacet + facet normal 0.403916 0.164547 0.899875 + outer loop + vertex 1.09198 2.07595 2.55638 + vertex 1.09501 2.07789 2.55467 + vertex 1.09086 2.07988 2.55617 + endloop + endfacet + facet normal 0.364454 0.154308 0.918347 + outer loop + vertex 1.09086 2.07988 2.55617 + vertex 1.08822 2.07622 2.55783 + vertex 1.09198 2.07595 2.55638 + endloop + endfacet + facet normal 0.325483 0.186254 0.927022 + outer loop + vertex 1.08631 2.08166 2.55741 + vertex 1.08822 2.07622 2.55783 + vertex 1.09086 2.07988 2.55617 + endloop + endfacet + facet normal 0.177238 0.360075 0.915933 + outer loop + vertex 1.08874 2.11304 2.54857 + vertex 1.09204 2.11496 2.54717 + vertex 1.08636 2.1169 2.54751 + endloop + endfacet + facet normal 0.186022 0.490583 0.851307 + outer loop + vertex 1.08996 2.11901 2.54583 + vertex 1.09405 2.11777 2.54566 + vertex 1.09329 2.12106 2.54393 + endloop + endfacet + facet normal 0.151442 0.530602 0.833982 + outer loop + vertex 1.08844 2.12173 2.54438 + vertex 1.08996 2.11901 2.54583 + vertex 1.09329 2.12106 2.54393 + endloop + endfacet + facet normal 0.187817 0.393845 0.899784 + outer loop + vertex 1.09204 2.11496 2.54717 + vertex 1.08996 2.11901 2.54583 + vertex 1.08636 2.1169 2.54751 + endloop + endfacet + facet normal 0.15521 0.380999 0.911455 + outer loop + vertex 1.09405 2.11777 2.54566 + vertex 1.08996 2.11901 2.54583 + vertex 1.09204 2.11496 2.54717 + endloop + endfacet + facet normal 0.0753375 0.844777 0.529789 + outer loop + vertex 1.08914 2.12406 2.54189 + vertex 1.09483 2.1239 2.54134 + vertex 1.09162 2.12587 2.53864 + endloop + endfacet + facet normal 0.0608628 0.85074 0.522051 + outer loop + vertex 1.08655 2.12623 2.53865 + vertex 1.08914 2.12406 2.54189 + vertex 1.09162 2.12587 2.53864 + endloop + endfacet + facet normal 0.161797 0.698164 0.697416 + outer loop + vertex 1.09329 2.12106 2.54393 + vertex 1.08914 2.12406 2.54189 + vertex 1.08844 2.12173 2.54438 + endloop + endfacet + facet normal 0.0916789 0.643577 0.75987 + outer loop + vertex 1.09483 2.1239 2.54134 + vertex 1.08914 2.12406 2.54189 + vertex 1.09329 2.12106 2.54393 + endloop + endfacet + facet normal -0.0119055 0.662269 0.749172 + outer loop + vertex 1.095 2.13285 2.525 + vertex 1.09 2.13276 2.525 + vertex 1.09426 2.12996 2.52755 + endloop + endfacet + facet normal 0.499701 0.859184 0.110005 + outer loop + vertex 1.09426 2.12996 2.52755 + vertex 1.09 2.13276 2.525 + vertex 1.09 2.13212 2.53 + endloop + endfacet + facet normal 0.580244 0.727735 0.365676 + outer loop + vertex 1.09426 2.12996 2.52755 + vertex 1.09 2.13212 2.53 + vertex 1.09363 2.12856 2.53132 + endloop + endfacet + facet normal 0.0618964 0.402276 0.913424 + outer loop + vertex 1.09363 2.12856 2.53132 + vertex 1.09 2.13212 2.53 + vertex 1.08861 2.12888 2.53152 + endloop + endfacet + facet normal 0.0732335 0.934779 0.347599 + outer loop + vertex 1.09363 2.12856 2.53132 + vertex 1.08861 2.12888 2.53152 + vertex 1.09295 2.12721 2.5351 + endloop + endfacet + facet normal 0.0315126 0.919748 0.391243 + outer loop + vertex 1.09295 2.12721 2.5351 + vertex 1.08861 2.12888 2.53152 + vertex 1.08794 2.12737 2.53512 + endloop + endfacet + facet normal 0.0671626 0.9414 0.330539 + outer loop + vertex 1.09162 2.12587 2.53864 + vertex 1.08794 2.12737 2.53512 + vertex 1.08655 2.12623 2.53865 + endloop + endfacet + facet normal 0.0317571 0.931188 0.363154 + outer loop + vertex 1.09295 2.12721 2.5351 + vertex 1.08794 2.12737 2.53512 + vertex 1.09162 2.12587 2.53864 + endloop + endfacet + facet normal 0.0206542 -0.832781 -0.553217 + outer loop + vertex 1.09657 0.89365 2.526 + vertex 1.1 0.894399 2.525 + vertex 1.09945 0.893695 2.52604 + endloop + endfacet + facet normal 0.0740698 -0.903141 -0.422906 + outer loop + vertex 1.09657 0.89365 2.526 + vertex 1.09309 0.893596 2.5255 + vertex 1.1 0.894399 2.525 + endloop + endfacet + facet normal 0.133107 -0.929553 0.343823 + outer loop + vertex 1.09309 0.893596 2.5255 + vertex 1.095 0.893683 2.525 + vertex 1.1 0.894399 2.525 + endloop + endfacet + facet normal -0.004946 -0.989747 0.142749 + outer loop + vertex 1.09657 0.89365 2.526 + vertex 1.09418 0.893905 2.52769 + vertex 1.09309 0.893596 2.5255 + endloop + endfacet + facet normal 0.0123422 -0.973879 0.226732 + outer loop + vertex 1.09945 0.893695 2.52604 + vertex 1.09792 0.894258 2.52854 + vertex 1.09657 0.89365 2.526 + endloop + endfacet + facet normal 0.0441696 -0.976603 0.210466 + outer loop + vertex 1.09418 0.893905 2.52769 + vertex 1.09657 0.89365 2.526 + vertex 1.09792 0.894258 2.52854 + endloop + endfacet + facet normal 0.0164766 -0.947178 0.320285 + outer loop + vertex 1.09418 0.893905 2.52769 + vertex 1.09792 0.894258 2.52854 + vertex 1.09397 0.895108 2.53125 + endloop + endfacet + facet normal 0.0505242 -0.929866 0.364412 + outer loop + vertex 1.09397 0.895108 2.53125 + vertex 1.09792 0.894258 2.52854 + vertex 1.09852 0.895578 2.53182 + endloop + endfacet + facet normal 0.0403137 -0.90432 0.424948 + outer loop + vertex 1.09852 0.895578 2.53182 + vertex 1.09669 0.896922 2.53486 + vertex 1.09397 0.895108 2.53125 + endloop + endfacet + facet normal 0.0744864 -0.912117 0.403107 + outer loop + vertex 1.09669 0.896922 2.53486 + vertex 1.09169 0.896721 2.53532 + vertex 1.09397 0.895108 2.53125 + endloop + endfacet + facet normal 0.0791736 -0.880944 0.466551 + outer loop + vertex 1.09669 0.896922 2.53486 + vertex 1.09438 0.89865 2.53851 + vertex 1.09169 0.896721 2.53532 + endloop + endfacet + facet normal 0.0935697 -0.875938 0.473262 + outer loop + vertex 1.09947 0.898862 2.5379 + vertex 1.09438 0.89865 2.53851 + vertex 1.09669 0.896922 2.53486 + endloop + endfacet + facet normal 0.101419 -0.825202 0.555658 + outer loop + vertex 1.09438 0.89865 2.53851 + vertex 1.09947 0.898862 2.5379 + vertex 1.09721 0.900965 2.54143 + endloop + endfacet + facet normal 0.128422 -0.83404 0.536549 + outer loop + vertex 1.09164 0.900635 2.54225 + vertex 1.09438 0.89865 2.53851 + vertex 1.09721 0.900965 2.54143 + endloop + endfacet + facet normal 0.137676 -0.767282 0.626357 + outer loop + vertex 1.09721 0.900965 2.54143 + vertex 1.09496 0.903013 2.54444 + vertex 1.09164 0.900635 2.54225 + endloop + endfacet + facet normal 0.236703 -0.711034 0.662119 + outer loop + vertex 1.10022 0.904381 2.54403 + vertex 1.09496 0.903013 2.54444 + vertex 1.09721 0.900965 2.54143 + endloop + endfacet + facet normal 0.212209 -0.579724 0.786694 + outer loop + vertex 1.09496 0.903013 2.54444 + vertex 1.10022 0.904381 2.54403 + vertex 1.09694 0.906112 2.54619 + endloop + endfacet + facet normal 0.237181 -0.588075 0.773248 + outer loop + vertex 1.0933 0.904855 2.54635 + vertex 1.09496 0.903013 2.54444 + vertex 1.09694 0.906112 2.54619 + endloop + endfacet + facet normal 0.179849 -0.405905 0.896044 + outer loop + vertex 1.09694 0.906112 2.54619 + vertex 1.09426 0.908718 2.5479 + vertex 1.0933 0.904855 2.54635 + endloop + endfacet + facet normal 0.221707 -0.367612 0.903165 + outer loop + vertex 1.09926 0.909917 2.54717 + vertex 1.09426 0.908718 2.5479 + vertex 1.09694 0.906112 2.54619 + endloop + endfacet + facet normal 0.344824 -0.228663 0.91039 + outer loop + vertex 1.09459 0.937938 2.55552 + vertex 1.09187 0.935521 2.55594 + vertex 1.09377 0.93387 2.55481 + endloop + endfacet + facet normal 0.395152 -0.234927 0.888068 + outer loop + vertex 1.09459 0.937938 2.55552 + vertex 1.09377 0.93387 2.55481 + vertex 1.0984 0.939311 2.55419 + endloop + endfacet + facet normal 0.346048 -0.18952 0.918876 + outer loop + vertex 1.0984 0.939311 2.55419 + vertex 1.09377 0.93387 2.55481 + vertex 1.09814 0.933866 2.55316 + endloop + endfacet + facet normal 0.319059 -0.19676 0.927085 + outer loop + vertex 1.09459 0.937938 2.55552 + vertex 1.09216 0.938756 2.55653 + vertex 1.09187 0.935521 2.55594 + endloop + endfacet + facet normal 0.402842 -0.17126 0.899104 + outer loop + vertex 1.0984 0.939311 2.55419 + vertex 1.09971 0.944814 2.55465 + vertex 1.09603 0.941801 2.55573 + endloop + endfacet + facet normal 0.384636 -0.191111 0.903068 + outer loop + vertex 1.09459 0.937938 2.55552 + vertex 1.0984 0.939311 2.55419 + vertex 1.09603 0.941801 2.55573 + endloop + endfacet + facet normal 0.32831 -0.171513 0.928868 + outer loop + vertex 1.09603 0.941801 2.55573 + vertex 1.09216 0.938756 2.55653 + vertex 1.09459 0.937938 2.55552 + endloop + endfacet + facet normal 0.333011 -0.17826 0.925919 + outer loop + vertex 1.09329 0.943839 2.5571 + vertex 1.09216 0.938756 2.55653 + vertex 1.09603 0.941801 2.55573 + endloop + endfacet + facet normal 0.403566 -0.172334 0.898574 + outer loop + vertex 1.09971 0.944814 2.55465 + vertex 1.09719 0.945566 2.55593 + vertex 1.09603 0.941801 2.55573 + endloop + endfacet + facet normal 0.348289 -0.156582 0.924217 + outer loop + vertex 1.09719 0.945566 2.55593 + vertex 1.09329 0.943839 2.5571 + vertex 1.09603 0.941801 2.55573 + endloop + endfacet + facet normal 0.343219 -0.142257 0.92842 + outer loop + vertex 1.09719 0.945566 2.55593 + vertex 1.09682 0.948691 2.55654 + vertex 1.09329 0.943839 2.5571 + endloop + endfacet + facet normal 0.370375 -0.163642 0.914354 + outer loop + vertex 1.09682 0.948691 2.55654 + vertex 1.09305 0.948873 2.5581 + vertex 1.09329 0.943839 2.5571 + endloop + endfacet + facet normal 0.399849 -0.156668 0.903092 + outer loop + vertex 1.09305 0.948873 2.5581 + vertex 1.09701 0.953225 2.5571 + vertex 1.09308 0.954302 2.55903 + endloop + endfacet + facet normal 0.271762 -0.12156 0.954656 + outer loop + vertex 1.09484 1.03987 2.56987 + vertex 1.09889 1.04389 2.56923 + vertex 1.0951 1.04432 2.57037 + endloop + endfacet + facet normal 0.313351 -0.126489 0.941176 + outer loop + vertex 1.09486 1.04744 2.57087 + vertex 1.09243 1.04496 2.57134 + vertex 1.0951 1.04432 2.57037 + endloop + endfacet + facet normal 0.252472 -0.133937 0.958289 + outer loop + vertex 1.09486 1.04744 2.57087 + vertex 1.0951 1.04432 2.57037 + vertex 1.09862 1.04877 2.57006 + endloop + endfacet + facet normal 0.268167 -0.146765 0.952127 + outer loop + vertex 1.09862 1.04877 2.57006 + vertex 1.0951 1.04432 2.57037 + vertex 1.09889 1.04389 2.56923 + endloop + endfacet + facet normal 0.331864 -0.146431 0.931893 + outer loop + vertex 1.09486 1.04744 2.57087 + vertex 1.09236 1.04825 2.57188 + vertex 1.09243 1.04496 2.57134 + endloop + endfacet + facet normal 0.248055 -0.158064 0.955764 + outer loop + vertex 1.09862 1.04877 2.57006 + vertex 1.09937 1.05282 2.57054 + vertex 1.09606 1.05086 2.57107 + endloop + endfacet + facet normal 0.256575 -0.147361 0.955225 + outer loop + vertex 1.09486 1.04744 2.57087 + vertex 1.09862 1.04877 2.57006 + vertex 1.09606 1.05086 2.57107 + endloop + endfacet + facet normal 0.323914 -0.169573 0.930765 + outer loop + vertex 1.09606 1.05086 2.57107 + vertex 1.09236 1.04825 2.57188 + vertex 1.09486 1.04744 2.57087 + endloop + endfacet + facet normal 0.320059 -0.163351 0.933209 + outer loop + vertex 1.09365 1.05344 2.57235 + vertex 1.09236 1.04825 2.57188 + vertex 1.09606 1.05086 2.57107 + endloop + endfacet + facet normal 0.255642 -0.172101 0.95133 + outer loop + vertex 1.09937 1.05282 2.57054 + vertex 1.09778 1.05439 2.57125 + vertex 1.09606 1.05086 2.57107 + endloop + endfacet + facet normal 0.293614 -0.189908 0.93687 + outer loop + vertex 1.09778 1.05439 2.57125 + vertex 1.09365 1.05344 2.57235 + vertex 1.09606 1.05086 2.57107 + endloop + endfacet + facet normal 0.296611 -0.208911 0.931868 + outer loop + vertex 1.09778 1.05439 2.57125 + vertex 1.09875 1.05856 2.57187 + vertex 1.09365 1.05344 2.57235 + endloop + endfacet + facet normal 0.251258 -0.161576 0.954339 + outer loop + vertex 1.09875 1.05856 2.57187 + vertex 1.09363 1.05884 2.57327 + vertex 1.09365 1.05344 2.57235 + endloop + endfacet + facet normal 0.250192 -0.172557 0.952695 + outer loop + vertex 1.09875 1.05856 2.57187 + vertex 1.0983 1.06349 2.57288 + vertex 1.09363 1.05884 2.57327 + endloop + endfacet + facet normal 0.28864 -0.026841 0.957061 + outer loop + vertex 1.09708 1.26248 2.60223 + vertex 1.09709 1.26766 2.60237 + vertex 1.09305 1.26301 2.60346 + endloop + endfacet + facet normal 0.336443 -0.0726168 0.9389 + outer loop + vertex 1.09305 1.26301 2.60346 + vertex 1.09709 1.26766 2.60237 + vertex 1.09308 1.26812 2.60385 + endloop + endfacet + facet normal 0.341354 -0.0309226 0.939426 + outer loop + vertex 1.09709 1.26766 2.60237 + vertex 1.09708 1.27288 2.60255 + vertex 1.09308 1.26812 2.60385 + endloop + endfacet + facet normal 0.393263 -0.0809046 0.915859 + outer loop + vertex 1.09308 1.26812 2.60385 + vertex 1.09708 1.27288 2.60255 + vertex 1.09317 1.27324 2.60426 + endloop + endfacet + facet normal 0.395635 -0.0584213 0.916548 + outer loop + vertex 1.09708 1.27288 2.60255 + vertex 1.09706 1.27806 2.60289 + vertex 1.09317 1.27324 2.60426 + endloop + endfacet + facet normal 0.469366 -0.130133 0.873362 + outer loop + vertex 1.09317 1.27324 2.60426 + vertex 1.09706 1.27806 2.60289 + vertex 1.09343 1.27839 2.60489 + endloop + endfacet + facet normal 0.397399 -0.165251 0.902644 + outer loop + vertex 1.09419 1.28242 2.60529 + vertex 1.09203 1.28025 2.60585 + vertex 1.09343 1.27839 2.60489 + endloop + endfacet + facet normal 0.590912 -0.190028 0.784036 + outer loop + vertex 1.09419 1.28242 2.60529 + vertex 1.09343 1.27839 2.60489 + vertex 1.09707 1.28362 2.60341 + endloop + endfacet + facet normal 0.474985 -0.0833774 0.876035 + outer loop + vertex 1.09707 1.28362 2.60341 + vertex 1.09343 1.27839 2.60489 + vertex 1.09706 1.27806 2.60289 + endloop + endfacet + facet normal 0.315249 -0.0724325 0.946241 + outer loop + vertex 1.09419 1.28242 2.60529 + vertex 1.09201 1.28328 2.60609 + vertex 1.09203 1.28025 2.60585 + endloop + endfacet + facet normal 0.601562 -0.0392329 0.797862 + outer loop + vertex 1.09707 1.28362 2.60341 + vertex 1.09782 1.28951 2.60314 + vertex 1.09498 1.28637 2.60513 + endloop + endfacet + facet normal 0.567697 -0.0785054 0.819486 + outer loop + vertex 1.09419 1.28242 2.60529 + vertex 1.09707 1.28362 2.60341 + vertex 1.09498 1.28637 2.60513 + endloop + endfacet + facet normal 0.332227 -0.0262292 0.942835 + outer loop + vertex 1.09498 1.28637 2.60513 + vertex 1.09201 1.28328 2.60609 + vertex 1.09419 1.28242 2.60529 + endloop + endfacet + facet normal 0.352618 -0.0484625 0.934511 + outer loop + vertex 1.092 1.28752 2.60631 + vertex 1.09201 1.28328 2.60609 + vertex 1.09498 1.28637 2.60513 + endloop + endfacet + facet normal 0.617491 -0.00357627 0.78657 + outer loop + vertex 1.09782 1.28951 2.60314 + vertex 1.09795 1.29472 2.60306 + vertex 1.09523 1.29129 2.60518 + endloop + endfacet + facet normal 0.601716 -0.0394534 0.797735 + outer loop + vertex 1.09498 1.28637 2.60513 + vertex 1.09782 1.28951 2.60314 + vertex 1.09523 1.29129 2.60518 + endloop + endfacet + facet normal 0.35968 -0.0283551 0.932645 + outer loop + vertex 1.09523 1.29129 2.60518 + vertex 1.092 1.28752 2.60631 + vertex 1.09498 1.28637 2.60513 + endloop + endfacet + facet normal 0.387245 -0.0557557 0.92029 + outer loop + vertex 1.09198 1.2924 2.60661 + vertex 1.092 1.28752 2.60631 + vertex 1.09523 1.29129 2.60518 + endloop + endfacet + facet normal 0.648672 -0.00105381 0.761068 + outer loop + vertex 1.09795 1.29472 2.60306 + vertex 1.09794 1.29976 2.60308 + vertex 1.09527 1.29632 2.60534 + endloop + endfacet + facet normal 0.638074 -0.0305371 0.769369 + outer loop + vertex 1.09523 1.29129 2.60518 + vertex 1.09795 1.29472 2.60306 + vertex 1.09527 1.29632 2.60534 + endloop + endfacet + facet normal 0.394079 -0.033347 0.918472 + outer loop + vertex 1.09527 1.29632 2.60534 + vertex 1.09198 1.2924 2.60661 + vertex 1.09523 1.29129 2.60518 + endloop + endfacet + facet normal 0.425757 -0.065126 0.902491 + outer loop + vertex 1.09199 1.29741 2.60697 + vertex 1.09198 1.2924 2.60661 + vertex 1.09527 1.29632 2.60534 + endloop + endfacet + facet normal 0.678426 -0.00629447 0.734642 + outer loop + vertex 1.09794 1.29976 2.60308 + vertex 1.09792 1.30476 2.60313 + vertex 1.09529 1.30132 2.60554 + endloop + endfacet + facet normal 0.670345 -0.0307613 0.741412 + outer loop + vertex 1.09527 1.29632 2.60534 + vertex 1.09794 1.29976 2.60308 + vertex 1.09529 1.30132 2.60554 + endloop + endfacet + facet normal 0.434109 -0.036395 0.900125 + outer loop + vertex 1.09529 1.30132 2.60554 + vertex 1.09199 1.29741 2.60697 + vertex 1.09527 1.29632 2.60534 + endloop + endfacet + facet normal 0.464803 -0.0686776 0.882747 + outer loop + vertex 1.09205 1.30241 2.60732 + vertex 1.09199 1.29741 2.60697 + vertex 1.09529 1.30132 2.60554 + endloop + endfacet + facet normal 0.703228 0.0105631 0.710886 + outer loop + vertex 1.09792 1.30476 2.60313 + vertex 1.09791 1.30973 2.60307 + vertex 1.09533 1.30629 2.60568 + endloop + endfacet + facet normal 0.692014 -0.0259382 0.721418 + outer loop + vertex 1.09529 1.30132 2.60554 + vertex 1.09792 1.30476 2.60313 + vertex 1.09533 1.30629 2.60568 + endloop + endfacet + facet normal 0.476208 -0.0284502 0.878872 + outer loop + vertex 1.09533 1.30629 2.60568 + vertex 1.09205 1.30241 2.60732 + vertex 1.09529 1.30132 2.60554 + endloop + endfacet + facet normal 0.492869 -0.0467674 0.868846 + outer loop + vertex 1.09212 1.30739 2.60755 + vertex 1.09205 1.30241 2.60732 + vertex 1.09533 1.30629 2.60568 + endloop + endfacet + facet normal 0.724359 0.0308465 0.688732 + outer loop + vertex 1.09791 1.30973 2.60307 + vertex 1.09794 1.31456 2.60283 + vertex 1.09542 1.31134 2.60562 + endloop + endfacet + facet normal 0.713501 -0.00488407 0.700638 + outer loop + vertex 1.09533 1.30629 2.60568 + vertex 1.09791 1.30973 2.60307 + vertex 1.09542 1.31134 2.60562 + endloop + endfacet + facet normal 0.505547 0.000378985 0.862799 + outer loop + vertex 1.09542 1.31134 2.60562 + vertex 1.09212 1.30739 2.60755 + vertex 1.09533 1.30629 2.60568 + endloop + endfacet + facet normal 0.528324 -0.0255495 0.848658 + outer loop + vertex 1.09219 1.31256 2.60767 + vertex 1.09212 1.30739 2.60755 + vertex 1.09542 1.31134 2.60562 + endloop + endfacet + facet normal 0.756052 0.0437178 0.65305 + outer loop + vertex 1.09794 1.31456 2.60283 + vertex 1.09815 1.31834 2.60233 + vertex 1.09573 1.31697 2.60522 + endloop + endfacet + facet normal 0.738668 0.00689597 0.674034 + outer loop + vertex 1.09542 1.31134 2.60562 + vertex 1.09794 1.31456 2.60283 + vertex 1.09573 1.31697 2.60522 + endloop + endfacet + facet normal 0.543138 0.0297085 0.839117 + outer loop + vertex 1.09573 1.31697 2.60522 + vertex 1.09219 1.31256 2.60767 + vertex 1.09542 1.31134 2.60562 + endloop + endfacet + facet normal 0.585719 -0.0205717 0.810253 + outer loop + vertex 1.09204 1.31797 2.60791 + vertex 1.09219 1.31256 2.60767 + vertex 1.09573 1.31697 2.60522 + endloop + endfacet + facet normal 0.85758 0.064798 0.510253 + outer loop + vertex 1.0992 1.32101 2.60029 + vertex 1.09928 1.32481 2.59967 + vertex 1.09766 1.3215 2.60281 + endloop + endfacet + facet normal 0.857205 0.0540738 0.512128 + outer loop + vertex 1.09815 1.31834 2.60233 + vertex 1.0992 1.32101 2.60029 + vertex 1.09766 1.3215 2.60281 + endloop + endfacet + facet normal 0.762511 0.0188805 0.646699 + outer loop + vertex 1.09815 1.31834 2.60233 + vertex 1.09766 1.3215 2.60281 + vertex 1.09573 1.31697 2.60522 + endloop + endfacet + facet normal 0.770671 0.0103462 0.637149 + outer loop + vertex 1.09573 1.31697 2.60522 + vertex 1.09766 1.3215 2.60281 + vertex 1.09527 1.32227 2.60569 + endloop + endfacet + facet normal 0.58562 -0.0210935 0.810311 + outer loop + vertex 1.09527 1.32227 2.60569 + vertex 1.09204 1.31797 2.60791 + vertex 1.09573 1.31697 2.60522 + endloop + endfacet + facet normal 0.628386 -0.0717032 0.77459 + outer loop + vertex 1.09199 1.32374 2.60849 + vertex 1.09204 1.31797 2.60791 + vertex 1.09527 1.32227 2.60569 + endloop + endfacet + facet normal 0.87371 0.0461656 0.484252 + outer loop + vertex 1.09928 1.32481 2.59967 + vertex 1.09919 1.32957 2.59938 + vertex 1.0975 1.32599 2.60276 + endloop + endfacet + facet normal 0.872402 0.0358365 0.487473 + outer loop + vertex 1.09766 1.3215 2.60281 + vertex 1.09928 1.32481 2.59967 + vertex 1.0975 1.32599 2.60276 + endloop + endfacet + facet normal 0.773358 0.0341141 0.633051 + outer loop + vertex 1.09766 1.3215 2.60281 + vertex 1.0975 1.32599 2.60276 + vertex 1.09527 1.32227 2.60569 + endloop + endfacet + facet normal 0.799458 -0.00697162 0.600682 + outer loop + vertex 1.0975 1.32599 2.60276 + vertex 1.09529 1.32746 2.60573 + vertex 1.09527 1.32227 2.60569 + endloop + endfacet + facet normal 0.646851 -0.00773548 0.762577 + outer loop + vertex 1.09529 1.32746 2.60573 + vertex 1.09199 1.32374 2.60849 + vertex 1.09527 1.32227 2.60569 + endloop + endfacet + facet normal 0.69614 -0.0886905 0.712407 + outer loop + vertex 1.09293 1.32943 2.60828 + vertex 1.09199 1.32374 2.60849 + vertex 1.09529 1.32746 2.60573 + endloop + endfacet + facet normal 0.883483 0.050012 0.465785 + outer loop + vertex 1.09919 1.32957 2.59938 + vertex 1.09902 1.33457 2.59915 + vertex 1.09742 1.33091 2.60258 + endloop + endfacet + facet normal 0.880944 0.0313392 0.472181 + outer loop + vertex 1.0975 1.32599 2.60276 + vertex 1.09919 1.32957 2.59938 + vertex 1.09742 1.33091 2.60258 + endloop + endfacet + facet normal 0.808721 0.0342931 0.587192 + outer loop + vertex 1.0975 1.32599 2.60276 + vertex 1.09742 1.33091 2.60258 + vertex 1.09529 1.32746 2.60573 + endloop + endfacet + facet normal 0.827313 -0.000432306 0.561741 + outer loop + vertex 1.09742 1.33091 2.60258 + vertex 1.09538 1.33263 2.60559 + vertex 1.09529 1.32746 2.60573 + endloop + endfacet + facet normal 0.735697 0.00438913 0.677296 + outer loop + vertex 1.09538 1.33263 2.60559 + vertex 1.09293 1.32943 2.60828 + vertex 1.09529 1.32746 2.60573 + endloop + endfacet + facet normal 0.744037 -0.00977387 0.668066 + outer loop + vertex 1.09305 1.33452 2.60822 + vertex 1.09293 1.32943 2.60828 + vertex 1.09538 1.33263 2.60559 + endloop + endfacet + facet normal 0.890593 0.0611815 0.450666 + outer loop + vertex 1.09902 1.33457 2.59915 + vertex 1.09881 1.33965 2.5989 + vertex 1.09731 1.33595 2.60236 + endloop + endfacet + facet normal 0.887989 0.0407956 0.458052 + outer loop + vertex 1.09742 1.33091 2.60258 + vertex 1.09902 1.33457 2.59915 + vertex 1.09731 1.33595 2.60236 + endloop + endfacet + facet normal 0.837994 0.0433681 0.543953 + outer loop + vertex 1.09742 1.33091 2.60258 + vertex 1.09731 1.33595 2.60236 + vertex 1.09538 1.33263 2.60559 + endloop + endfacet + facet normal 0.845587 0.0284252 0.53308 + outer loop + vertex 1.09731 1.33595 2.60236 + vertex 1.09531 1.33773 2.60543 + vertex 1.09538 1.33263 2.60559 + endloop + endfacet + facet normal 0.75808 0.0307586 0.651436 + outer loop + vertex 1.09531 1.33773 2.60543 + vertex 1.09305 1.33452 2.60822 + vertex 1.09538 1.33263 2.60559 + endloop + endfacet + facet normal 0.768479 0.0132923 0.639736 + outer loop + vertex 1.09299 1.33959 2.60819 + vertex 1.09305 1.33452 2.60822 + vertex 1.09531 1.33773 2.60543 + endloop + endfacet + facet normal 0.897821 0.0556203 0.436834 + outer loop + vertex 1.09881 1.33965 2.5989 + vertex 1.09858 1.34477 2.5987 + vertex 1.09714 1.34105 2.60214 + endloop + endfacet + facet normal 0.896914 0.0482082 0.43957 + outer loop + vertex 1.09731 1.33595 2.60236 + vertex 1.09881 1.33965 2.5989 + vertex 1.09714 1.34105 2.60214 + endloop + endfacet + facet normal 0.850491 0.0504033 0.52357 + outer loop + vertex 1.09731 1.33595 2.60236 + vertex 1.09714 1.34105 2.60214 + vertex 1.09531 1.33773 2.60543 + endloop + endfacet + facet normal 0.860225 0.0305794 0.508996 + outer loop + vertex 1.09714 1.34105 2.60214 + vertex 1.09521 1.34282 2.60529 + vertex 1.09531 1.33773 2.60543 + endloop + endfacet + facet normal 0.774412 0.0323596 0.631854 + outer loop + vertex 1.09521 1.34282 2.60529 + vertex 1.09299 1.33959 2.60819 + vertex 1.09531 1.33773 2.60543 + endloop + endfacet + facet normal 0.789365 0.00597123 0.613895 + outer loop + vertex 1.09297 1.34466 2.60817 + vertex 1.09299 1.33959 2.60819 + vertex 1.09521 1.34282 2.60529 + endloop + endfacet + facet normal 0.908431 0.0373097 0.416367 + outer loop + vertex 1.09858 1.34477 2.5987 + vertex 1.0984 1.34978 2.59865 + vertex 1.09702 1.34616 2.60199 + endloop + endfacet + facet normal 0.907996 0.0338993 0.417604 + outer loop + vertex 1.09714 1.34105 2.60214 + vertex 1.09858 1.34477 2.5987 + vertex 1.09702 1.34616 2.60199 + endloop + endfacet + facet normal 0.861263 0.0354029 0.506925 + outer loop + vertex 1.09714 1.34105 2.60214 + vertex 1.09702 1.34616 2.60199 + vertex 1.09521 1.34282 2.60529 + endloop + endfacet + facet normal 0.871441 0.0134648 0.490316 + outer loop + vertex 1.09702 1.34616 2.60199 + vertex 1.09518 1.34791 2.60521 + vertex 1.09521 1.34282 2.60529 + endloop + endfacet + facet normal 0.79204 0.0148494 0.610288 + outer loop + vertex 1.09518 1.34791 2.60521 + vertex 1.09297 1.34466 2.60817 + vertex 1.09521 1.34282 2.60529 + endloop + endfacet + facet normal 0.805394 -0.0102576 0.592651 + outer loop + vertex 1.09301 1.34971 2.60819 + vertex 1.09297 1.34466 2.60817 + vertex 1.09518 1.34791 2.60521 + endloop + endfacet + facet normal 0.920879 0.0163307 0.389505 + outer loop + vertex 1.0984 1.34978 2.59865 + vertex 1.09828 1.35451 2.59873 + vertex 1.09698 1.35124 2.60195 + endloop + endfacet + facet normal 0.919989 0.0102421 0.391811 + outer loop + vertex 1.09702 1.34616 2.60199 + vertex 1.0984 1.34978 2.59865 + vertex 1.09698 1.35124 2.60195 + endloop + endfacet + facet normal 0.870828 0.0107019 0.491472 + outer loop + vertex 1.09702 1.34616 2.60199 + vertex 1.09698 1.35124 2.60195 + vertex 1.09518 1.34791 2.60521 + endloop + endfacet + facet normal 0.875212 0.000735926 0.48374 + outer loop + vertex 1.09698 1.35124 2.60195 + vertex 1.0952 1.35301 2.60516 + vertex 1.09518 1.34791 2.60521 + endloop + endfacet + facet normal 0.808976 0.00205016 0.587838 + outer loop + vertex 1.0952 1.35301 2.60516 + vertex 1.09301 1.34971 2.60819 + vertex 1.09518 1.34791 2.60521 + endloop + endfacet + facet normal 0.816697 -0.0130735 0.576918 + outer loop + vertex 1.09307 1.35471 2.60822 + vertex 1.09301 1.34971 2.60819 + vertex 1.0952 1.35301 2.60516 + endloop + endfacet + facet normal 0.926233 0.0677262 0.370818 + outer loop + vertex 1.09828 1.35451 2.59873 + vertex 1.09812 1.35882 2.59836 + vertex 1.09694 1.3563 2.60175 + endloop + endfacet + facet normal 0.918626 0.0221529 0.394506 + outer loop + vertex 1.09698 1.35124 2.60195 + vertex 1.09828 1.35451 2.59873 + vertex 1.09694 1.3563 2.60175 + endloop + endfacet + facet normal 0.880524 0.0249811 0.473342 + outer loop + vertex 1.09698 1.35124 2.60195 + vertex 1.09694 1.3563 2.60175 + vertex 1.0952 1.35301 2.60516 + endloop + endfacet + facet normal 0.881231 0.0233281 0.47211 + outer loop + vertex 1.09694 1.3563 2.60175 + vertex 1.09517 1.35814 2.60496 + vertex 1.0952 1.35301 2.60516 + endloop + endfacet + facet normal 0.82676 0.0265482 0.561929 + outer loop + vertex 1.09517 1.35814 2.60496 + vertex 1.09307 1.35471 2.60822 + vertex 1.0952 1.35301 2.60516 + endloop + endfacet + facet normal 0.839523 0.00106274 0.543323 + outer loop + vertex 1.09306 1.35965 2.60823 + vertex 1.09307 1.35471 2.60822 + vertex 1.09517 1.35814 2.60496 + endloop + endfacet + facet normal -0.670848 -0.190462 0.71672 + outer loop + vertex 1.1 1.36102 2.595 + vertex 1.09887 1.365 2.595 + vertex 1.09879 1.36168 2.59404 + endloop + endfacet + facet normal 0.933606 0.178969 0.310404 + outer loop + vertex 1.09812 1.35882 2.59836 + vertex 1.09788 1.36218 2.59714 + vertex 1.09677 1.36185 2.60067 + endloop + endfacet + facet normal 0.912741 0.105888 0.394579 + outer loop + vertex 1.09694 1.3563 2.60175 + vertex 1.09812 1.35882 2.59836 + vertex 1.09677 1.36185 2.60067 + endloop + endfacet + facet normal 0.896114 0.112154 0.42942 + outer loop + vertex 1.09694 1.3563 2.60175 + vertex 1.09677 1.36185 2.60067 + vertex 1.09517 1.35814 2.60496 + endloop + endfacet + facet normal 0.919736 0.0549189 0.388677 + outer loop + vertex 1.09677 1.36185 2.60067 + vertex 1.09496 1.3633 2.60474 + vertex 1.09517 1.35814 2.60496 + endloop + endfacet + facet normal 0.849932 0.0578886 0.523702 + outer loop + vertex 1.09496 1.3633 2.60474 + vertex 1.09306 1.35965 2.60823 + vertex 1.09517 1.35814 2.60496 + endloop + endfacet + facet normal 0.870136 0.0175777 0.492498 + outer loop + vertex 1.09298 1.36454 2.6082 + vertex 1.09306 1.35965 2.60823 + vertex 1.09496 1.3633 2.60474 + endloop + endfacet + facet normal 0.621335 -0.2308 0.748782 + outer loop + vertex 1.0981 1.36309 2.59505 + vertex 1.09879 1.36168 2.59404 + vertex 1.09887 1.365 2.595 + endloop + endfacet + facet normal 0.673653 -0.253366 0.69426 + outer loop + vertex 1.0981 1.36309 2.59505 + vertex 1.09887 1.365 2.595 + vertex 1.09741 1.3663 2.59689 + endloop + endfacet + facet normal 0.833054 0.16495 0.528026 + outer loop + vertex 1.09741 1.3663 2.59689 + vertex 1.09887 1.365 2.595 + vertex 1.09788 1.37 2.595 + endloop + endfacet + facet normal 0.980372 0.119798 0.156586 + outer loop + vertex 1.09788 1.36218 2.59714 + vertex 1.0981 1.36309 2.59505 + vertex 1.09741 1.3663 2.59689 + endloop + endfacet + facet normal 0.943024 0.124803 0.30843 + outer loop + vertex 1.09788 1.36218 2.59714 + vertex 1.09741 1.3663 2.59689 + vertex 1.09677 1.36185 2.60067 + endloop + endfacet + facet normal 0.966425 0.0695656 0.247354 + outer loop + vertex 1.09677 1.36185 2.60067 + vertex 1.09741 1.3663 2.59689 + vertex 1.09627 1.36786 2.60093 + endloop + endfacet + facet normal 0.920074 0.0594803 0.387204 + outer loop + vertex 1.09677 1.36185 2.60067 + vertex 1.09627 1.36786 2.60093 + vertex 1.09496 1.3633 2.60474 + endloop + endfacet + facet normal 0.922944 0.0536236 0.381181 + outer loop + vertex 1.09627 1.36786 2.60093 + vertex 1.0947 1.36835 2.60467 + vertex 1.09496 1.3633 2.60474 + endloop + endfacet + facet normal 0.874359 0.0524352 0.482438 + outer loop + vertex 1.0947 1.36835 2.60467 + vertex 1.09298 1.36454 2.6082 + vertex 1.09496 1.3633 2.60474 + endloop + endfacet + facet normal 0.883227 0.0347346 0.467658 + outer loop + vertex 1.09286 1.36941 2.60805 + vertex 1.09298 1.36454 2.6082 + vertex 1.0947 1.36835 2.60467 + endloop + endfacet + facet normal 0.611735 0.353774 -0.707548 + outer loop + vertex 1.095 1.375 2.59501 + vertex 1.09788 1.37 2.595 + vertex 1.095 1.37498 2.595 + endloop + endfacet + facet normal 0.71251 0.411541 -0.568299 + outer loop + vertex 1.095 1.375 2.59501 + vertex 1.09898 1.375 2.6 + vertex 1.09788 1.37 2.595 + endloop + endfacet + facet normal 0.98593 -0.155464 -0.0614315 + outer loop + vertex 1.09898 1.375 2.6 + vertex 1.09741 1.3663 2.59689 + vertex 1.09788 1.37 2.595 + endloop + endfacet + facet normal 0.886117 -0.289117 0.362227 + outer loop + vertex 1.09741 1.3663 2.59689 + vertex 1.09898 1.375 2.6 + vertex 1.09627 1.36786 2.60093 + endloop + endfacet + facet normal 0.437003 -0.0486358 0.898144 + outer loop + vertex 1.09898 1.375 2.6 + vertex 1.09615 1.37332 2.60129 + vertex 1.09627 1.36786 2.60093 + endloop + endfacet + facet normal 0.921528 -0.00495586 0.388281 + outer loop + vertex 1.09627 1.36786 2.60093 + vertex 1.09615 1.37332 2.60129 + vertex 1.0947 1.36835 2.60467 + endloop + endfacet + facet normal 0.899278 0.0340562 0.436049 + outer loop + vertex 1.09615 1.37332 2.60129 + vertex 1.09454 1.37308 2.60462 + vertex 1.0947 1.36835 2.60467 + endloop + endfacet + facet normal 0.883143 0.033889 0.467878 + outer loop + vertex 1.09454 1.37308 2.60462 + vertex 1.09286 1.36941 2.60805 + vertex 1.0947 1.36835 2.60467 + endloop + endfacet + facet normal 0.884512 0.0310205 0.465485 + outer loop + vertex 1.09286 1.3742 2.60774 + vertex 1.09286 1.36941 2.60805 + vertex 1.09454 1.37308 2.60462 + endloop + endfacet + facet normal 0.394284 0.038636 0.918176 + outer loop + vertex 1.09898 1.375 2.6 + vertex 1.09849 1.38 2.6 + vertex 1.09615 1.37332 2.60129 + endloop + endfacet + facet normal 0.528706 -0.0218909 0.848523 + outer loop + vertex 1.09849 1.38 2.6 + vertex 1.096 1.37801 2.6015 + vertex 1.09615 1.37332 2.60129 + endloop + endfacet + facet normal 0.900489 0.00869217 0.434791 + outer loop + vertex 1.09615 1.37332 2.60129 + vertex 1.096 1.37801 2.6015 + vertex 1.09454 1.37308 2.60462 + endloop + endfacet + facet normal 0.88925 0.0258547 0.45669 + outer loop + vertex 1.096 1.37801 2.6015 + vertex 1.0944 1.37741 2.60464 + vertex 1.09454 1.37308 2.60462 + endloop + endfacet + facet normal 0.883852 0.025619 0.467065 + outer loop + vertex 1.0944 1.37741 2.60464 + vertex 1.09286 1.3742 2.60774 + vertex 1.09454 1.37308 2.60462 + endloop + endfacet + facet normal 0.885454 0.0220874 0.464201 + outer loop + vertex 1.09307 1.37797 2.60716 + vertex 1.09286 1.3742 2.60774 + vertex 1.0944 1.37741 2.60464 + endloop + endfacet + facet normal 0.499917 0.0269964 0.865653 + outer loop + vertex 1.09849 1.38 2.6 + vertex 1.09822 1.385 2.6 + vertex 1.096 1.37801 2.6015 + endloop + endfacet + facet normal 0.626348 -0.0317604 0.778896 + outer loop + vertex 1.09822 1.385 2.6 + vertex 1.09566 1.38282 2.60197 + vertex 1.096 1.37801 2.6015 + endloop + endfacet + facet normal 0.868009 0.063523 0.492469 + outer loop + vertex 1.09402 1.38055 2.60515 + vertex 1.09566 1.38282 2.60197 + vertex 1.09409 1.3845 2.60452 + endloop + endfacet + facet normal 0.879519 0.0305858 0.47488 + outer loop + vertex 1.09402 1.38055 2.60515 + vertex 1.0944 1.37741 2.60464 + vertex 1.09566 1.38282 2.60197 + endloop + endfacet + facet normal 0.889947 0.0186858 0.455681 + outer loop + vertex 1.0944 1.37741 2.60464 + vertex 1.096 1.37801 2.6015 + vertex 1.09566 1.38282 2.60197 + endloop + endfacet + facet normal 0.886209 0.0334903 0.462074 + outer loop + vertex 1.0944 1.37741 2.60464 + vertex 1.09402 1.38055 2.60515 + vertex 1.09307 1.37797 2.60716 + endloop + endfacet + facet normal 0.609165 0.00121999 0.793043 + outer loop + vertex 1.09822 1.385 2.6 + vertex 1.09821 1.39 2.6 + vertex 1.09566 1.38282 2.60197 + endloop + endfacet + facet normal 0.462921 0.0778968 0.88297 + outer loop + vertex 1.09821 1.39 2.6 + vertex 1.09576 1.38863 2.6014 + vertex 1.09566 1.38282 2.60197 + endloop + endfacet + facet normal 0.860962 0.0341033 0.507525 + outer loop + vertex 1.09576 1.38863 2.6014 + vertex 1.09409 1.3845 2.60452 + vertex 1.09566 1.38282 2.60197 + endloop + endfacet + facet normal 0.852964 0.0466494 0.51988 + outer loop + vertex 1.09402 1.38942 2.60419 + vertex 1.09409 1.3845 2.60452 + vertex 1.09576 1.38863 2.6014 + endloop + endfacet + facet normal 0.492074 0.0127879 0.870459 + outer loop + vertex 1.09821 1.39 2.6 + vertex 1.09808 1.395 2.6 + vertex 1.09576 1.38863 2.6014 + endloop + endfacet + facet normal 0.41077 0.0511832 0.910301 + outer loop + vertex 1.09808 1.395 2.6 + vertex 1.09567 1.39383 2.60115 + vertex 1.09576 1.38863 2.6014 + endloop + endfacet + facet normal 0.852394 0.0401314 0.521357 + outer loop + vertex 1.09567 1.39383 2.60115 + vertex 1.09402 1.38942 2.60419 + vertex 1.09576 1.38863 2.6014 + endloop + endfacet + facet normal 0.856957 0.0335524 0.514294 + outer loop + vertex 1.09392 1.39444 2.60403 + vertex 1.09402 1.38942 2.60419 + vertex 1.09567 1.39383 2.60115 + endloop + endfacet + facet normal 0.430304 0.00344711 0.902678 + outer loop + vertex 1.09808 1.395 2.6 + vertex 1.09804 1.4 2.6 + vertex 1.09567 1.39383 2.60115 + endloop + endfacet + facet normal 0.352791 0.0392295 0.93488 + outer loop + vertex 1.09804 1.4 2.6 + vertex 1.09552 1.39897 2.60099 + vertex 1.09567 1.39383 2.60115 + endloop + endfacet + facet normal 0.857416 0.0410351 0.512985 + outer loop + vertex 1.09552 1.39897 2.60099 + vertex 1.09392 1.39444 2.60403 + vertex 1.09567 1.39383 2.60115 + endloop + endfacet + facet normal 0.86056 0.036605 0.508031 + outer loop + vertex 1.09379 1.39944 2.60388 + vertex 1.09392 1.39444 2.60403 + vertex 1.09552 1.39897 2.60099 + endloop + endfacet + facet normal 0.359248 0.0215499 0.932993 + outer loop + vertex 1.09804 1.4 2.6 + vertex 1.09774 1.405 2.6 + vertex 1.09552 1.39897 2.60099 + endloop + endfacet + facet normal 0.32614 0.0356712 0.944648 + outer loop + vertex 1.09774 1.405 2.6 + vertex 1.09535 1.40412 2.60086 + vertex 1.09552 1.39897 2.60099 + endloop + endfacet + facet normal 0.860756 0.0418621 0.507294 + outer loop + vertex 1.09535 1.40412 2.60086 + vertex 1.09379 1.39944 2.60388 + vertex 1.09552 1.39897 2.60099 + endloop + endfacet + facet normal 0.861267 0.0411674 0.506483 + outer loop + vertex 1.09364 1.40447 2.60374 + vertex 1.09379 1.39944 2.60388 + vertex 1.09535 1.40412 2.60086 + endloop + endfacet + facet normal 0.338489 -0.00134772 0.94097 + outer loop + vertex 1.09774 1.405 2.6 + vertex 1.09776 1.41 2.6 + vertex 1.09535 1.40412 2.60086 + endloop + endfacet + facet normal 0.250931 0.0383685 0.967244 + outer loop + vertex 1.09776 1.41 2.6 + vertex 1.09514 1.40917 2.60071 + vertex 1.09535 1.40412 2.60086 + endloop + endfacet + facet normal 0.861395 0.0504864 0.50542 + outer loop + vertex 1.09514 1.40917 2.60071 + vertex 1.09364 1.40447 2.60374 + vertex 1.09535 1.40412 2.60086 + endloop + endfacet + facet normal 0.852158 0.0625064 0.519538 + outer loop + vertex 1.09343 1.40943 2.60349 + vertex 1.09364 1.40447 2.60374 + vertex 1.09514 1.40917 2.60071 + endloop + endfacet + facet normal 0.259493 0.00986176 0.965695 + outer loop + vertex 1.09776 1.41 2.6 + vertex 1.09757 1.415 2.6 + vertex 1.09514 1.40917 2.60071 + endloop + endfacet + facet normal 0.163602 0.0522611 0.985141 + outer loop + vertex 1.09757 1.415 2.6 + vertex 1.0948 1.41399 2.60051 + vertex 1.09514 1.40917 2.60071 + endloop + endfacet + facet normal 0.851762 0.0812363 0.517593 + outer loop + vertex 1.0948 1.41399 2.60051 + vertex 1.09343 1.40943 2.60349 + vertex 1.09514 1.40917 2.60071 + endloop + endfacet + facet normal 0.840692 0.0947181 0.533166 + outer loop + vertex 1.09321 1.41435 2.60296 + vertex 1.09343 1.40943 2.60349 + vertex 1.0948 1.41399 2.60051 + endloop + endfacet + facet normal 0.17595 0.0179461 0.984236 + outer loop + vertex 1.09757 1.415 2.6 + vertex 1.09706 1.42 2.6 + vertex 1.0948 1.41399 2.60051 + endloop + endfacet + facet normal 0.0774549 0.0559347 0.995426 + outer loop + vertex 1.09706 1.42 2.6 + vertex 1.09431 1.41838 2.60031 + vertex 1.0948 1.41399 2.60051 + endloop + endfacet + facet normal 0.840057 0.119832 0.529098 + outer loop + vertex 1.09431 1.41838 2.60031 + vertex 1.09321 1.41435 2.60296 + vertex 1.0948 1.41399 2.60051 + endloop + endfacet + facet normal 0.912165 0.0214191 0.409264 + outer loop + vertex 1.09339 1.41887 2.60233 + vertex 1.09321 1.41435 2.60296 + vertex 1.09431 1.41838 2.60031 + endloop + endfacet + facet normal 0.937704 -0.334388 0.0943194 + outer loop + vertex 1.0941 1.42183 2.60105 + vertex 1.09534 1.425 2.6 + vertex 1.095 1.425 2.60338 + endloop + endfacet + facet normal 0.76872 -0.0909537 0.633085 + outer loop + vertex 1.0941 1.42183 2.60105 + vertex 1.09431 1.41838 2.60031 + vertex 1.09534 1.425 2.6 + endloop + endfacet + facet normal 0.0917721 0.0315687 0.99528 + outer loop + vertex 1.09431 1.41838 2.60031 + vertex 1.09706 1.42 2.6 + vertex 1.09534 1.425 2.6 + endloop + endfacet + facet normal 0.906317 -0.0372802 0.420951 + outer loop + vertex 1.09431 1.41838 2.60031 + vertex 1.0941 1.42183 2.60105 + vertex 1.09339 1.41887 2.60233 + endloop + endfacet + facet normal 0.672303 0.737181 0.0676239 + outer loop + vertex 1.09534 1.425 2.6 + vertex 1.095 1.42531 2.6 + vertex 1.095 1.425 2.60338 + endloop + endfacet + facet normal 0.80094 -0.551937 0.23208 + outer loop + vertex 1.09551 1.6 2.6 + vertex 1.095 1.6 2.60176 + vertex 1.095 1.59926 2.6 + endloop + endfacet + facet normal 0.91661 -0.298806 0.265596 + outer loop + vertex 1.09714 1.605 2.6 + vertex 1.095 1.6 2.60176 + vertex 1.09551 1.6 2.6 + endloop + endfacet + facet normal 0.014057 0.326641 0.945044 + outer loop + vertex 1.09448 1.60455 2.60019 + vertex 1.095 1.6 2.60176 + vertex 1.09714 1.605 2.6 + endloop + endfacet + facet normal 0.0738786 -0.00679726 0.997244 + outer loop + vertex 1.0976 1.61 2.6 + vertex 1.09448 1.60455 2.60019 + vertex 1.09714 1.605 2.6 + endloop + endfacet + facet normal 0.0234446 0.0221509 0.99948 + outer loop + vertex 1.09462 1.60957 2.60008 + vertex 1.09448 1.60455 2.60019 + vertex 1.0976 1.61 2.6 + endloop + endfacet + facet normal 0.0268325 -0.00123469 0.999639 + outer loop + vertex 1.09783 1.615 2.6 + vertex 1.09462 1.60957 2.60008 + vertex 1.0976 1.61 2.6 + endloop + endfacet + facet normal 0.0919081 -0.0397394 0.994974 + outer loop + vertex 1.09469 1.61459 2.60027 + vertex 1.09462 1.60957 2.60008 + vertex 1.09783 1.615 2.6 + endloop + endfacet + facet normal 0.0868573 -0.000519781 0.996221 + outer loop + vertex 1.09786 1.62 2.6 + vertex 1.09469 1.61459 2.60027 + vertex 1.09783 1.615 2.6 + endloop + endfacet + facet normal 0.115162 -0.0172567 0.993197 + outer loop + vertex 1.09442 1.61857 2.60037 + vertex 1.09469 1.61459 2.60027 + vertex 1.09786 1.62 2.6 + endloop + endfacet + facet normal 0.747252 -0.0601415 0.661814 + outer loop + vertex 1.09442 1.61857 2.60037 + vertex 1.09524 1.6234 2.59988 + vertex 1.09317 1.62045 2.60195 + endloop + endfacet + facet normal 0.0711504 0.0890208 0.993485 + outer loop + vertex 1.09442 1.61857 2.60037 + vertex 1.09786 1.62 2.6 + vertex 1.09524 1.6234 2.59988 + endloop + endfacet + facet normal -0.0441386 0.000353588 0.999025 + outer loop + vertex 1.09786 1.62 2.6 + vertex 1.0979 1.625 2.6 + vertex 1.09524 1.6234 2.59988 + endloop + endfacet + facet normal 0.746294 -0.0586141 0.66303 + outer loop + vertex 1.09524 1.6234 2.59988 + vertex 1.09303 1.62441 2.60247 + vertex 1.09317 1.62045 2.60195 + endloop + endfacet + facet normal -0.0437669 -0.000262959 0.999042 + outer loop + vertex 1.0979 1.625 2.6 + vertex 1.09787 1.63 2.6 + vertex 1.09524 1.6234 2.59988 + endloop + endfacet + facet normal 0.11806 -0.064487 0.99091 + outer loop + vertex 1.09787 1.63 2.6 + vertex 1.095 1.62883 2.60027 + vertex 1.09524 1.6234 2.59988 + endloop + endfacet + facet normal 0.756573 -0.0127941 0.653784 + outer loop + vertex 1.095 1.62883 2.60027 + vertex 1.09303 1.62441 2.60247 + vertex 1.09524 1.6234 2.59988 + endloop + endfacet + facet normal 0.795867 -0.055832 0.602891 + outer loop + vertex 1.093 1.62925 2.60296 + vertex 1.09303 1.62441 2.60247 + vertex 1.095 1.62883 2.60027 + endloop + endfacet + facet normal 0.092213 -0.000184677 0.995739 + outer loop + vertex 1.09787 1.63 2.6 + vertex 1.09788 1.635 2.6 + vertex 1.095 1.62883 2.60027 + endloop + endfacet + facet normal 0.220131 -0.060731 0.973578 + outer loop + vertex 1.09788 1.635 2.6 + vertex 1.09504 1.63383 2.60057 + vertex 1.095 1.62883 2.60027 + endloop + endfacet + facet normal 0.797472 -0.0418794 0.601901 + outer loop + vertex 1.09504 1.63383 2.60057 + vertex 1.093 1.62925 2.60296 + vertex 1.095 1.62883 2.60027 + endloop + endfacet + facet normal 0.81161 -0.0589612 0.581216 + outer loop + vertex 1.0931 1.63418 2.60331 + vertex 1.093 1.62925 2.60296 + vertex 1.09504 1.63383 2.60057 + endloop + endfacet + facet normal 0.197651 -0.00276616 0.980269 + outer loop + vertex 1.09788 1.635 2.6 + vertex 1.09795 1.64 2.6 + vertex 1.09504 1.63383 2.60057 + endloop + endfacet + facet normal 0.278834 -0.0430284 0.959375 + outer loop + vertex 1.09795 1.64 2.6 + vertex 1.09519 1.63881 2.60075 + vertex 1.09504 1.63383 2.60057 + endloop + endfacet + facet normal 0.812908 -0.0463553 0.580545 + outer loop + vertex 1.09519 1.63881 2.60075 + vertex 1.0931 1.63418 2.60331 + vertex 1.09504 1.63383 2.60057 + endloop + endfacet + facet normal 0.811712 -0.0448213 0.582336 + outer loop + vertex 1.09323 1.63915 2.60351 + vertex 1.0931 1.63418 2.60331 + vertex 1.09519 1.63881 2.60075 + endloop + endfacet + facet normal 0.270439 -0.0216387 0.962494 + outer loop + vertex 1.09795 1.64 2.6 + vertex 1.09835 1.645 2.6 + vertex 1.09519 1.63881 2.60075 + endloop + endfacet + facet normal 0.240002 -0.00512611 0.970759 + outer loop + vertex 1.09835 1.645 2.6 + vertex 1.09534 1.64375 2.60074 + vertex 1.09519 1.63881 2.60075 + endloop + endfacet + facet normal 0.813594 -0.023132 0.580974 + outer loop + vertex 1.09534 1.64375 2.60074 + vertex 1.09323 1.63915 2.60351 + vertex 1.09519 1.63881 2.60075 + endloop + endfacet + facet normal 0.820764 -0.0328366 0.570323 + outer loop + vertex 1.09337 1.64419 2.60361 + vertex 1.09323 1.63915 2.60351 + vertex 1.09534 1.64375 2.60074 + endloop + endfacet + facet normal 0.239496 -0.00383143 0.97089 + outer loop + vertex 1.09835 1.645 2.6 + vertex 1.09843 1.65 2.6 + vertex 1.09534 1.64375 2.60074 + endloop + endfacet + facet normal 0.199225 0.0171114 0.979804 + outer loop + vertex 1.09843 1.65 2.6 + vertex 1.09542 1.64867 2.60064 + vertex 1.09534 1.64375 2.60074 + endloop + endfacet + facet normal 0.823509 -0.000642386 0.567304 + outer loop + vertex 1.09542 1.64867 2.60064 + vertex 1.09337 1.64419 2.60361 + vertex 1.09534 1.64375 2.60074 + endloop + endfacet + facet normal 0.834039 -0.015943 0.551475 + outer loop + vertex 1.09344 1.64921 2.60364 + vertex 1.09337 1.64419 2.60361 + vertex 1.09542 1.64867 2.60064 + endloop + endfacet + facet normal 0.20579 0.00164856 0.978595 + outer loop + vertex 1.09843 1.65 2.6 + vertex 1.09839 1.655 2.6 + vertex 1.09542 1.64867 2.60064 + endloop + endfacet + facet normal 0.0461227 0.0784097 0.995854 + outer loop + vertex 1.09839 1.655 2.6 + vertex 1.09524 1.65338 2.60027 + vertex 1.09542 1.64867 2.60064 + endloop + endfacet + facet normal 0.839133 0.0721635 0.539118 + outer loop + vertex 1.09524 1.65338 2.60027 + vertex 1.09344 1.64921 2.60364 + vertex 1.09542 1.64867 2.60064 + endloop + endfacet + facet normal 0.887771 -0.0125693 0.460114 + outer loop + vertex 1.09348 1.65422 2.6037 + vertex 1.09344 1.64921 2.60364 + vertex 1.09524 1.65338 2.60027 + endloop + endfacet + facet normal 0.995801 -0.0637229 -0.0657188 + outer loop + vertex 1.09806 1.655 2.595 + vertex 1.09838 1.66 2.595 + vertex 1.09839 1.655 2.6 + endloop + endfacet + facet normal -0.00930872 0.707058 0.707094 + outer loop + vertex 1.09838 1.66 2.595 + vertex 1.09678 1.65803 2.59695 + vertex 1.09839 1.655 2.6 + endloop + endfacet + facet normal -0.252763 0.616759 0.745466 + outer loop + vertex 1.09839 1.655 2.6 + vertex 1.09678 1.65803 2.59695 + vertex 1.09524 1.65338 2.60027 + endloop + endfacet + facet normal 0.876009 0.0525623 0.479421 + outer loop + vertex 1.09678 1.65803 2.59695 + vertex 1.09507 1.65792 2.60009 + vertex 1.09524 1.65338 2.60027 + endloop + endfacet + facet normal 0.892976 0.051923 0.4471 + outer loop + vertex 1.09507 1.65792 2.60009 + vertex 1.09348 1.65422 2.6037 + vertex 1.09524 1.65338 2.60027 + endloop + endfacet + facet normal 0.921313 -0.0175162 0.388428 + outer loop + vertex 1.09354 1.65923 2.60378 + vertex 1.09348 1.65422 2.6037 + vertex 1.09507 1.65792 2.60009 + endloop + endfacet + facet normal 0.835982 -0.157179 0.525764 + outer loop + vertex 1.09838 1.66 2.595 + vertex 1.09932 1.665 2.595 + vertex 1.09678 1.65803 2.59695 + endloop + endfacet + facet normal 0.56756 0.0235526 0.822995 + outer loop + vertex 1.09932 1.665 2.595 + vertex 1.09649 1.66132 2.59706 + vertex 1.09678 1.65803 2.59695 + endloop + endfacet + facet normal 0.875349 0.0625862 0.479423 + outer loop + vertex 1.09678 1.65803 2.59695 + vertex 1.09649 1.66132 2.59706 + vertex 1.09507 1.65792 2.60009 + endloop + endfacet + facet normal 0.915532 -0.0235641 0.401554 + outer loop + vertex 1.09649 1.66132 2.59706 + vertex 1.09521 1.66256 2.60005 + vertex 1.09507 1.65792 2.60009 + endloop + endfacet + facet normal 0.920388 -0.0238074 0.390281 + outer loop + vertex 1.09521 1.66256 2.60005 + vertex 1.09354 1.65923 2.60378 + vertex 1.09507 1.65792 2.60009 + endloop + endfacet + facet normal 0.918056 -0.0161239 0.396122 + outer loop + vertex 1.09363 1.66426 2.60377 + vertex 1.09354 1.65923 2.60378 + vertex 1.09521 1.66256 2.60005 + endloop + endfacet + facet normal 0.211166 0.320258 0.923495 + outer loop + vertex 1.1 1.66741 2.595 + vertex 1.09893 1.66989 2.59438 + vertex 1.09722 1.66579 2.5962 + endloop + endfacet + facet normal 0.454956 -0.128361 0.881214 + outer loop + vertex 1.1 1.66741 2.595 + vertex 1.09722 1.66579 2.5962 + vertex 1.09932 1.665 2.595 + endloop + endfacet + facet normal 0.516482 0.0794345 0.852606 + outer loop + vertex 1.09932 1.665 2.595 + vertex 1.09722 1.66579 2.5962 + vertex 1.09649 1.66132 2.59706 + endloop + endfacet + facet normal 0.906638 -0.0683946 0.416329 + outer loop + vertex 1.09649 1.66132 2.59706 + vertex 1.09722 1.66579 2.5962 + vertex 1.09521 1.66256 2.60005 + endloop + endfacet + facet normal 0.896277 -0.030726 0.442429 + outer loop + vertex 1.09722 1.66579 2.5962 + vertex 1.09538 1.66748 2.60005 + vertex 1.09521 1.66256 2.60005 + endloop + endfacet + facet normal 0.915157 -0.0313854 0.401874 + outer loop + vertex 1.09538 1.66748 2.60005 + vertex 1.09363 1.66426 2.60377 + vertex 1.09521 1.66256 2.60005 + endloop + endfacet + facet normal 0.911306 -0.0183765 0.41132 + outer loop + vertex 1.09373 1.66929 2.60377 + vertex 1.09363 1.66426 2.60377 + vertex 1.09538 1.66748 2.60005 + endloop + endfacet + facet normal 0.764769 -0.0804846 0.639257 + outer loop + vertex 1.09893 1.66989 2.59438 + vertex 1.09913 1.67457 2.59473 + vertex 1.09707 1.67069 2.59671 + endloop + endfacet + facet normal 0.773201 -0.0418755 0.632777 + outer loop + vertex 1.09722 1.66579 2.5962 + vertex 1.09893 1.66989 2.59438 + vertex 1.09707 1.67069 2.59671 + endloop + endfacet + facet normal 0.898813 -0.0178009 0.43797 + outer loop + vertex 1.09722 1.66579 2.5962 + vertex 1.09707 1.67069 2.59671 + vertex 1.09538 1.66748 2.60005 + endloop + endfacet + facet normal 0.904214 -0.0333317 0.425776 + outer loop + vertex 1.09707 1.67069 2.59671 + vertex 1.09544 1.6725 2.60031 + vertex 1.09538 1.66748 2.60005 + endloop + endfacet + facet normal 0.908279 -0.0329365 0.417066 + outer loop + vertex 1.09544 1.6725 2.60031 + vertex 1.09373 1.66929 2.60377 + vertex 1.09538 1.66748 2.60005 + endloop + endfacet + facet normal 0.906081 -0.0261148 0.422297 + outer loop + vertex 1.09382 1.67421 2.60389 + vertex 1.09373 1.66929 2.60377 + vertex 1.09544 1.6725 2.60031 + endloop + endfacet + facet normal 0.756679 -0.0912761 0.647384 + outer loop + vertex 1.09913 1.67457 2.59473 + vertex 1.09944 1.67963 2.59508 + vertex 1.09718 1.67575 2.59717 + endloop + endfacet + facet normal 0.761314 -0.0762896 0.643879 + outer loop + vertex 1.09707 1.67069 2.59671 + vertex 1.09913 1.67457 2.59473 + vertex 1.09718 1.67575 2.59717 + endloop + endfacet + facet normal 0.897745 -0.060286 0.436371 + outer loop + vertex 1.09707 1.67069 2.59671 + vertex 1.09718 1.67575 2.59717 + vertex 1.09544 1.6725 2.60031 + endloop + endfacet + facet normal 0.889453 -0.0374099 0.455494 + outer loop + vertex 1.09718 1.67575 2.59717 + vertex 1.09546 1.67751 2.60068 + vertex 1.09544 1.6725 2.60031 + endloop + endfacet + facet normal 0.904131 -0.0352851 0.425795 + outer loop + vertex 1.09546 1.67751 2.60068 + vertex 1.09382 1.67421 2.60389 + vertex 1.09544 1.6725 2.60031 + endloop + endfacet + facet normal 0.901898 -0.0291357 0.430966 + outer loop + vertex 1.09381 1.67892 2.60423 + vertex 1.09382 1.67421 2.60389 + vertex 1.09546 1.67751 2.60068 + endloop + endfacet + facet normal 0.743466 -0.0655673 0.665552 + outer loop + vertex 1.09944 1.67963 2.59508 + vertex 1.09961 1.68463 2.59539 + vertex 1.09725 1.68092 2.59765 + endloop + endfacet + facet normal 0.741523 -0.0718548 0.667069 + outer loop + vertex 1.09718 1.67575 2.59717 + vertex 1.09944 1.67963 2.59508 + vertex 1.09725 1.68092 2.59765 + endloop + endfacet + facet normal 0.88517 -0.0546255 0.46205 + outer loop + vertex 1.09718 1.67575 2.59717 + vertex 1.09725 1.68092 2.59765 + vertex 1.09546 1.67751 2.60068 + endloop + endfacet + facet normal 0.880135 -0.0424352 0.472823 + outer loop + vertex 1.09725 1.68092 2.59765 + vertex 1.09533 1.68279 2.6014 + vertex 1.09546 1.67751 2.60068 + endloop + endfacet + facet normal 0.900541 -0.0364749 0.433239 + outer loop + vertex 1.09533 1.68279 2.6014 + vertex 1.09381 1.67892 2.60423 + vertex 1.09546 1.67751 2.60068 + endloop + endfacet + facet normal 0.893426 -0.02246 0.448649 + outer loop + vertex 1.0936 1.68276 2.60484 + vertex 1.09381 1.67892 2.60423 + vertex 1.09533 1.68279 2.6014 + endloop + endfacet + facet normal 0.760714 -0.00879439 0.649028 + outer loop + vertex 1.09961 1.68463 2.59539 + vertex 1.09947 1.68866 2.59561 + vertex 1.09726 1.68624 2.59817 + endloop + endfacet + facet normal 0.742878 -0.0647446 0.666289 + outer loop + vertex 1.09725 1.68092 2.59765 + vertex 1.09961 1.68463 2.59539 + vertex 1.09726 1.68624 2.59817 + endloop + endfacet + facet normal 0.879144 -0.0463943 0.474292 + outer loop + vertex 1.09725 1.68092 2.59765 + vertex 1.09726 1.68624 2.59817 + vertex 1.09533 1.68279 2.6014 + endloop + endfacet + facet normal 0.873686 -0.0329209 0.485374 + outer loop + vertex 1.09726 1.68624 2.59817 + vertex 1.09573 1.68651 2.60093 + vertex 1.09533 1.68279 2.6014 + endloop + endfacet + facet normal 0.825471 0.0121345 0.564314 + outer loop + vertex 1.0936 1.68276 2.60484 + vertex 1.09427 1.68682 2.60377 + vertex 1.09201 1.68495 2.60712 + endloop + endfacet + facet normal 0.893288 -0.0296848 0.448504 + outer loop + vertex 1.0936 1.68276 2.60484 + vertex 1.09533 1.68279 2.6014 + vertex 1.09427 1.68682 2.60377 + endloop + endfacet + facet normal 0.887397 -0.0376704 0.459465 + outer loop + vertex 1.09533 1.68279 2.6014 + vertex 1.09573 1.68651 2.60093 + vertex 1.09427 1.68682 2.60377 + endloop + endfacet + facet normal 0.831127 -0.00966684 0.555999 + outer loop + vertex 1.09427 1.68682 2.60377 + vertex 1.09242 1.68891 2.60658 + vertex 1.09201 1.68495 2.60712 + endloop + endfacet + facet normal 0.762962 -0.0137262 0.646298 + outer loop + vertex 1.09947 1.68866 2.59561 + vertex 1.09814 1.69053 2.59721 + vertex 1.09726 1.68624 2.59817 + endloop + endfacet + facet normal 0.867155 -0.0710981 0.492937 + outer loop + vertex 1.09814 1.69053 2.59721 + vertex 1.09814 1.69456 2.5978 + vertex 1.09623 1.69026 2.60053 + endloop + endfacet + facet normal 0.8672 -0.0693449 0.493108 + outer loop + vertex 1.09814 1.69053 2.59721 + vertex 1.09623 1.69026 2.60053 + vertex 1.09726 1.68624 2.59817 + endloop + endfacet + facet normal 0.870973 -0.0648118 0.487038 + outer loop + vertex 1.09726 1.68624 2.59817 + vertex 1.09623 1.69026 2.60053 + vertex 1.09573 1.68651 2.60093 + endloop + endfacet + facet normal 0.884487 -0.0693772 0.461377 + outer loop + vertex 1.09573 1.68651 2.60093 + vertex 1.09623 1.69026 2.60053 + vertex 1.09427 1.68682 2.60377 + endloop + endfacet + facet normal 0.874654 -0.0436722 0.482776 + outer loop + vertex 1.09623 1.69026 2.60053 + vertex 1.09425 1.69175 2.60425 + vertex 1.09427 1.68682 2.60377 + endloop + endfacet + facet normal 0.814618 -0.0531988 0.577553 + outer loop + vertex 1.09425 1.69175 2.60425 + vertex 1.09242 1.68891 2.60658 + vertex 1.09427 1.68682 2.60377 + endloop + endfacet + facet normal 0.780287 0.00823112 0.625368 + outer loop + vertex 1.09189 1.69274 2.60719 + vertex 1.09242 1.68891 2.60658 + vertex 1.09425 1.69175 2.60425 + endloop + endfacet + facet normal 0.875885 -0.0584465 0.478967 + outer loop + vertex 1.09814 1.69456 2.5978 + vertex 1.09821 1.69942 2.59826 + vertex 1.09623 1.6955 2.60141 + endloop + endfacet + facet normal 0.872182 -0.079881 0.482616 + outer loop + vertex 1.09623 1.69026 2.60053 + vertex 1.09814 1.69456 2.5978 + vertex 1.09623 1.6955 2.60141 + endloop + endfacet + facet normal 0.865984 -0.0816763 0.493357 + outer loop + vertex 1.09623 1.69026 2.60053 + vertex 1.09623 1.6955 2.60141 + vertex 1.09425 1.69175 2.60425 + endloop + endfacet + facet normal 0.846904 -0.0439331 0.529928 + outer loop + vertex 1.09623 1.6955 2.60141 + vertex 1.09417 1.6965 2.60477 + vertex 1.09425 1.69175 2.60425 + endloop + endfacet + facet normal 0.768212 -0.0570198 0.637651 + outer loop + vertex 1.09417 1.6965 2.60477 + vertex 1.09189 1.69274 2.60719 + vertex 1.09425 1.69175 2.60425 + endloop + endfacet + facet normal 0.712432 0.0178247 0.701515 + outer loop + vertex 1.09161 1.69729 2.60736 + vertex 1.09189 1.69274 2.60719 + vertex 1.09417 1.6965 2.60477 + endloop + endfacet + facet normal 0.883121 -0.0541673 0.466007 + outer loop + vertex 1.09821 1.69942 2.59826 + vertex 1.09839 1.70431 2.5985 + vertex 1.09638 1.70049 2.60186 + endloop + endfacet + facet normal 0.880516 -0.0687732 0.469 + outer loop + vertex 1.09623 1.6955 2.60141 + vertex 1.09821 1.69942 2.59826 + vertex 1.09638 1.70049 2.60186 + endloop + endfacet + facet normal 0.841373 -0.0736664 0.535411 + outer loop + vertex 1.09623 1.6955 2.60141 + vertex 1.09638 1.70049 2.60186 + vertex 1.09417 1.6965 2.60477 + endloop + endfacet + facet normal 0.815854 -0.0288459 0.577538 + outer loop + vertex 1.09638 1.70049 2.60186 + vertex 1.09422 1.70141 2.60496 + vertex 1.09417 1.6965 2.60477 + endloop + endfacet + facet normal 0.704376 -0.0328826 0.709065 + outer loop + vertex 1.09422 1.70141 2.60496 + vertex 1.09161 1.69729 2.60736 + vertex 1.09417 1.6965 2.60477 + endloop + endfacet + facet normal 0.641365 0.04028 0.766178 + outer loop + vertex 1.0914 1.70201 2.60729 + vertex 1.09161 1.69729 2.60736 + vertex 1.09422 1.70141 2.60496 + endloop + endfacet + facet normal 0.882692 -0.0481836 0.467475 + outer loop + vertex 1.09839 1.70431 2.5985 + vertex 1.09861 1.70922 2.59858 + vertex 1.0966 1.70554 2.60199 + endloop + endfacet + facet normal 0.882046 -0.0515465 0.468336 + outer loop + vertex 1.09638 1.70049 2.60186 + vertex 1.09839 1.70431 2.5985 + vertex 1.0966 1.70554 2.60199 + endloop + endfacet + facet normal 0.811934 -0.0512664 0.581494 + outer loop + vertex 1.09638 1.70049 2.60186 + vertex 1.0966 1.70554 2.60199 + vertex 1.09422 1.70141 2.60496 + endloop + endfacet + facet normal 0.787672 -0.0124734 0.615969 + outer loop + vertex 1.0966 1.70554 2.60199 + vertex 1.09435 1.70651 2.60489 + vertex 1.09422 1.70141 2.60496 + endloop + endfacet + facet normal 0.636029 -0.00633765 0.771639 + outer loop + vertex 1.09435 1.70651 2.60489 + vertex 1.0914 1.70201 2.60729 + vertex 1.09422 1.70141 2.60496 + endloop + endfacet + facet normal 0.590641 0.0417053 0.805856 + outer loop + vertex 1.09139 1.70701 2.60703 + vertex 1.0914 1.70201 2.60729 + vertex 1.09435 1.70651 2.60489 + endloop + endfacet + facet normal 0.87665 -0.041659 0.479322 + outer loop + vertex 1.09861 1.70922 2.59858 + vertex 1.09877 1.71426 2.59872 + vertex 1.09682 1.7107 2.60199 + endloop + endfacet + facet normal 0.877848 -0.03618 0.477572 + outer loop + vertex 1.0966 1.70554 2.60199 + vertex 1.09861 1.70922 2.59858 + vertex 1.09682 1.7107 2.60199 + endloop + endfacet + facet normal 0.784088 -0.0323425 0.619806 + outer loop + vertex 1.0966 1.70554 2.60199 + vertex 1.09682 1.7107 2.60199 + vertex 1.09435 1.70651 2.60489 + endloop + endfacet + facet normal 0.769427 -0.0107071 0.638645 + outer loop + vertex 1.09682 1.7107 2.60199 + vertex 1.09452 1.71173 2.60478 + vertex 1.09435 1.70651 2.60489 + endloop + endfacet + facet normal 0.586412 -0.00132454 0.810012 + outer loop + vertex 1.09452 1.71173 2.60478 + vertex 1.09139 1.70701 2.60703 + vertex 1.09435 1.70651 2.60489 + endloop + endfacet + facet normal 0.556739 0.0279796 0.830216 + outer loop + vertex 1.09152 1.71215 2.60677 + vertex 1.09139 1.70701 2.60703 + vertex 1.09452 1.71173 2.60478 + endloop + endfacet + facet normal 0.867643 -0.0444775 0.495194 + outer loop + vertex 1.09877 1.71426 2.59872 + vertex 1.09879 1.71934 2.59915 + vertex 1.09692 1.71592 2.60212 + endloop + endfacet + facet normal 0.87138 -0.0291704 0.489741 + outer loop + vertex 1.09682 1.7107 2.60199 + vertex 1.09877 1.71426 2.59872 + vertex 1.09692 1.71592 2.60212 + endloop + endfacet + facet normal 0.765428 -0.0308628 0.642781 + outer loop + vertex 1.09682 1.7107 2.60199 + vertex 1.09692 1.71592 2.60212 + vertex 1.09452 1.71173 2.60478 + endloop + endfacet + facet normal 0.751361 -0.0120403 0.659782 + outer loop + vertex 1.09692 1.71592 2.60212 + vertex 1.09458 1.71681 2.6048 + vertex 1.09452 1.71173 2.60478 + endloop + endfacet + facet normal 0.553174 -0.0102657 0.833003 + outer loop + vertex 1.09458 1.71681 2.6048 + vertex 1.09152 1.71215 2.60677 + vertex 1.09452 1.71173 2.60478 + endloop + endfacet + facet normal 0.517731 0.0224957 0.855248 + outer loop + vertex 1.09166 1.71713 2.60656 + vertex 1.09152 1.71215 2.60677 + vertex 1.09458 1.71681 2.6048 + endloop + endfacet + facet normal 0.84533 -0.05512 0.531393 + outer loop + vertex 1.09879 1.71934 2.59915 + vertex 1.09869 1.7234 2.59973 + vertex 1.09679 1.7213 2.60253 + endloop + endfacet + facet normal 0.855873 -0.0192197 0.516829 + outer loop + vertex 1.09692 1.71592 2.60212 + vertex 1.09879 1.71934 2.59915 + vertex 1.09679 1.7213 2.60253 + endloop + endfacet + facet normal 0.747569 -0.0329088 0.663369 + outer loop + vertex 1.09692 1.71592 2.60212 + vertex 1.09679 1.7213 2.60253 + vertex 1.09458 1.71681 2.6048 + endloop + endfacet + facet normal 0.716588 -0.000368387 0.697497 + outer loop + vertex 1.09679 1.7213 2.60253 + vertex 1.09434 1.72085 2.60505 + vertex 1.09458 1.71681 2.6048 + endloop + endfacet + facet normal 0.514091 -0.0222357 0.857447 + outer loop + vertex 1.09434 1.72085 2.60505 + vertex 1.09166 1.71713 2.60656 + vertex 1.09458 1.71681 2.6048 + endloop + endfacet + facet normal 0.443902 0.0437388 0.895007 + outer loop + vertex 1.09185 1.72191 2.60623 + vertex 1.09166 1.71713 2.60656 + vertex 1.09434 1.72085 2.60505 + endloop + endfacet + facet normal 0.841303 -0.0414203 0.538974 + outer loop + vertex 1.09869 1.7234 2.59973 + vertex 1.0976 1.7255 2.60159 + vertex 1.09679 1.7213 2.60253 + endloop + endfacet + facet normal 0.728502 -0.0165272 0.684844 + outer loop + vertex 1.0976 1.7255 2.60159 + vertex 1.09728 1.72928 2.60202 + vertex 1.09516 1.72537 2.60418 + endloop + endfacet + facet normal 0.727816 0.013183 0.685645 + outer loop + vertex 1.0976 1.7255 2.60159 + vertex 1.09516 1.72537 2.60418 + vertex 1.09679 1.7213 2.60253 + endloop + endfacet + facet normal 0.716234 0.00357457 0.697851 + outer loop + vertex 1.09679 1.7213 2.60253 + vertex 1.09516 1.72537 2.60418 + vertex 1.09434 1.72085 2.60505 + endloop + endfacet + facet normal 0.457284 0.0862439 0.885129 + outer loop + vertex 1.09516 1.72537 2.60418 + vertex 1.09185 1.72191 2.60623 + vertex 1.09434 1.72085 2.60505 + endloop + endfacet + facet normal 0.475964 0.0636741 0.877157 + outer loop + vertex 1.09176 1.72662 2.60594 + vertex 1.09185 1.72191 2.60623 + vertex 1.09516 1.72537 2.60418 + endloop + endfacet + facet normal 0.659218 -0.00628761 0.751926 + outer loop + vertex 1.09728 1.72928 2.60202 + vertex 1.09667 1.73424 2.60259 + vertex 1.09451 1.73021 2.60446 + endloop + endfacet + facet normal 0.668641 0.0476738 0.742055 + outer loop + vertex 1.09516 1.72537 2.60418 + vertex 1.09728 1.72928 2.60202 + vertex 1.09451 1.73021 2.60446 + endloop + endfacet + facet normal 0.461828 0.011485 0.886895 + outer loop + vertex 1.09451 1.73021 2.60446 + vertex 1.09176 1.72662 2.60594 + vertex 1.09516 1.72537 2.60418 + endloop + endfacet + facet normal 0.383531 0.0849074 0.919617 + outer loop + vertex 1.09102 1.73106 2.60583 + vertex 1.09176 1.72662 2.60594 + vertex 1.09451 1.73021 2.60446 + endloop + endfacet + facet normal 0.558118 0.0822686 0.825673 + outer loop + vertex 1.09352 1.73378 2.60477 + vertex 1.09451 1.73021 2.60446 + vertex 1.09667 1.73424 2.60259 + endloop + endfacet + facet normal 0.559316 0.0738978 0.825654 + outer loop + vertex 1.09352 1.73378 2.60477 + vertex 1.09667 1.73424 2.60259 + vertex 1.09396 1.73804 2.60409 + endloop + endfacet + facet normal 0.508051 0.023406 0.861009 + outer loop + vertex 1.09396 1.73804 2.60409 + vertex 1.09667 1.73424 2.60259 + vertex 1.09744 1.73869 2.60202 + endloop + endfacet + facet normal 0.371517 0.0221764 0.928161 + outer loop + vertex 1.09451 1.73021 2.60446 + vertex 1.09352 1.73378 2.60477 + vertex 1.09102 1.73106 2.60583 + endloop + endfacet + facet normal 0.513768 -0.0171102 0.857758 + outer loop + vertex 1.09744 1.73869 2.60202 + vertex 1.09681 1.74223 2.60247 + vertex 1.09396 1.73804 2.60409 + endloop + endfacet + facet normal 0.422251 0.0629214 0.904293 + outer loop + vertex 1.09396 1.73804 2.60409 + vertex 1.09681 1.74223 2.60247 + vertex 1.09318 1.74286 2.60412 + endloop + endfacet + facet normal 0.41731 0.0235124 0.90846 + outer loop + vertex 1.09681 1.74223 2.60247 + vertex 1.09664 1.74662 2.60243 + vertex 1.09318 1.74286 2.60412 + endloop + endfacet + facet normal 0.393057 0.050172 0.918144 + outer loop + vertex 1.09318 1.74286 2.60412 + vertex 1.09664 1.74662 2.60243 + vertex 1.09291 1.74731 2.60399 + endloop + endfacet + facet normal 0.389586 0.0256818 0.920632 + outer loop + vertex 1.09664 1.74662 2.60243 + vertex 1.0967 1.75147 2.60227 + vertex 1.09291 1.74731 2.60399 + endloop + endfacet + facet normal 0.36337 0.0534851 0.930108 + outer loop + vertex 1.09291 1.74731 2.60399 + vertex 1.0967 1.75147 2.60227 + vertex 1.0927 1.75195 2.6038 + endloop + endfacet + facet normal 0.35921 0.00920072 0.933211 + outer loop + vertex 1.0967 1.75147 2.60227 + vertex 1.09674 1.75652 2.60221 + vertex 1.0927 1.75195 2.6038 + endloop + endfacet + facet normal 0.320404 0.0479948 0.946064 + outer loop + vertex 1.0927 1.75195 2.6038 + vertex 1.09674 1.75652 2.60221 + vertex 1.09272 1.75688 2.60355 + endloop + endfacet + facet normal 0.318533 0.021224 0.947674 + outer loop + vertex 1.09674 1.75652 2.60221 + vertex 1.09688 1.76158 2.60204 + vertex 1.09272 1.75688 2.60355 + endloop + endfacet + facet normal 0.2837 0.0551274 0.957327 + outer loop + vertex 1.09272 1.75688 2.60355 + vertex 1.09688 1.76158 2.60204 + vertex 1.09289 1.76197 2.60321 + endloop + endfacet + facet normal 0.282267 0.0361947 0.958653 + outer loop + vertex 1.09688 1.76158 2.60204 + vertex 1.09702 1.7667 2.60181 + vertex 1.09289 1.76197 2.60321 + endloop + endfacet + facet normal 0.249705 0.0667794 0.966017 + outer loop + vertex 1.09289 1.76197 2.60321 + vertex 1.09702 1.7667 2.60181 + vertex 1.09303 1.76713 2.60281 + endloop + endfacet + facet normal 0.248546 0.0534115 0.967146 + outer loop + vertex 1.09702 1.7667 2.60181 + vertex 1.09684 1.77182 2.60157 + vertex 1.09303 1.76713 2.60281 + endloop + endfacet + facet normal 0.115469 0.171599 0.978377 + outer loop + vertex 1.09549 1.87629 2.58622 + vertex 1.09585 1.87209 2.58691 + vertex 1.09963 1.87776 2.58547 + endloop + endfacet + facet normal 0.115626 0.171186 0.97843 + outer loop + vertex 1.09459 1.87893 2.58586 + vertex 1.09549 1.87629 2.58622 + vertex 1.09963 1.87776 2.58547 + endloop + endfacet + facet normal 0.168335 0.183758 0.968451 + outer loop + vertex 1.09938 1.9581 2.57047 + vertex 1.09553 1.95962 2.57085 + vertex 1.09666 1.95458 2.57161 + endloop + endfacet + facet normal 0.251392 0.181102 0.950791 + outer loop + vertex 1.09466 1.99365 2.56503 + vertex 1.09943 1.98867 2.56472 + vertex 1.09924 1.99347 2.56386 + endloop + endfacet + facet normal 0.251491 0.159954 0.954551 + outer loop + vertex 1.09924 1.99347 2.56386 + vertex 1.09796 1.9972 2.56357 + vertex 1.09466 1.99365 2.56503 + endloop + endfacet + facet normal 0.270392 0.141441 0.952304 + outer loop + vertex 1.09466 1.99365 2.56503 + vertex 1.09796 1.9972 2.56357 + vertex 1.09448 1.99852 2.56436 + endloop + endfacet + facet normal 0.266583 0.12979 0.955033 + outer loop + vertex 1.09796 1.9972 2.56357 + vertex 1.09682 2.00103 2.56337 + vertex 1.09448 1.99852 2.56436 + endloop + endfacet + facet normal 0.290076 0.106266 0.951085 + outer loop + vertex 1.09448 1.99852 2.56436 + vertex 1.09682 2.00103 2.56337 + vertex 1.09269 2.00299 2.56441 + endloop + endfacet + facet normal 0.29206 0.111033 0.949933 + outer loop + vertex 1.09682 2.00103 2.56337 + vertex 1.09781 2.00568 2.56252 + vertex 1.09269 2.00299 2.56441 + endloop + endfacet + facet normal 0.301213 0.09294 0.949017 + outer loop + vertex 1.09269 2.00299 2.56441 + vertex 1.09781 2.00568 2.56252 + vertex 1.09416 2.0081 2.56344 + endloop + endfacet + facet normal 0.309682 0.107354 0.94476 + outer loop + vertex 1.09781 2.00568 2.56252 + vertex 1.097 2.01126 2.56215 + vertex 1.09416 2.0081 2.56344 + endloop + endfacet + facet normal 0.323187 0.0939426 0.941661 + outer loop + vertex 1.09416 2.0081 2.56344 + vertex 1.097 2.01126 2.56215 + vertex 1.09317 2.01233 2.56336 + endloop + endfacet + facet normal 0.326247 0.107652 0.939135 + outer loop + vertex 1.097 2.01126 2.56215 + vertex 1.0959 2.01655 2.56193 + vertex 1.09317 2.01233 2.56336 + endloop + endfacet + facet normal 0.336153 0.100318 0.936449 + outer loop + vertex 1.09317 2.01233 2.56336 + vertex 1.0959 2.01655 2.56193 + vertex 1.09212 2.01638 2.5633 + endloop + endfacet + facet normal 0.332741 0.123223 0.934933 + outer loop + vertex 1.09916 2.01879 2.5605 + vertex 1.09989 2.02302 2.55968 + vertex 1.09672 2.0209 2.56109 + endloop + endfacet + facet normal 0.328675 0.117914 0.937053 + outer loop + vertex 1.09672 2.0209 2.56109 + vertex 1.0959 2.01655 2.56193 + vertex 1.09916 2.01879 2.5605 + endloop + endfacet + facet normal 0.343778 0.114112 0.932092 + outer loop + vertex 1.09672 2.0209 2.56109 + vertex 1.09279 2.02109 2.56252 + vertex 1.0959 2.01655 2.56193 + endloop + endfacet + facet normal 0.335583 0.10802 0.935797 + outer loop + vertex 1.09279 2.02109 2.56252 + vertex 1.09212 2.01638 2.5633 + vertex 1.0959 2.01655 2.56193 + endloop + endfacet + facet normal 0.338629 0.128065 0.932164 + outer loop + vertex 1.09989 2.02302 2.55968 + vertex 1.09853 2.02861 2.55941 + vertex 1.09562 2.02495 2.56097 + endloop + endfacet + facet normal 0.335309 0.119122 0.934547 + outer loop + vertex 1.09672 2.0209 2.56109 + vertex 1.09989 2.02302 2.55968 + vertex 1.09562 2.02495 2.56097 + endloop + endfacet + facet normal 0.343802 0.121314 0.931173 + outer loop + vertex 1.09562 2.02495 2.56097 + vertex 1.09279 2.02109 2.56252 + vertex 1.09672 2.0209 2.56109 + endloop + endfacet + facet normal 0.361266 0.10652 0.926359 + outer loop + vertex 1.09128 2.0271 2.56242 + vertex 1.09279 2.02109 2.56252 + vertex 1.09562 2.02495 2.56097 + endloop + endfacet + facet normal 0.346104 0.121335 0.930317 + outer loop + vertex 1.09452 2.02903 2.56085 + vertex 1.09562 2.02495 2.56097 + vertex 1.09853 2.02861 2.55941 + endloop + endfacet + facet normal 0.346209 0.123388 0.930008 + outer loop + vertex 1.09452 2.02903 2.56085 + vertex 1.09853 2.02861 2.55941 + vertex 1.09539 2.03327 2.55996 + endloop + endfacet + facet normal 0.34763 0.124425 0.929339 + outer loop + vertex 1.09539 2.03327 2.55996 + vertex 1.09853 2.02861 2.55941 + vertex 1.09934 2.03316 2.5585 + endloop + endfacet + facet normal 0.369623 0.127384 0.920409 + outer loop + vertex 1.09562 2.02495 2.56097 + vertex 1.09452 2.02903 2.56085 + vertex 1.09128 2.0271 2.56242 + endloop + endfacet + facet normal 0.347514 0.130505 0.928549 + outer loop + vertex 1.09934 2.03316 2.5585 + vertex 1.09806 2.03722 2.55841 + vertex 1.09539 2.03327 2.55996 + endloop + endfacet + facet normal 0.361393 0.119592 0.924712 + outer loop + vertex 1.09539 2.03327 2.55996 + vertex 1.09806 2.03722 2.55841 + vertex 1.09437 2.0384 2.5597 + endloop + endfacet + facet normal 0.36384 0.12976 0.922379 + outer loop + vertex 1.09806 2.03722 2.55841 + vertex 1.09689 2.04121 2.55831 + vertex 1.09437 2.0384 2.5597 + endloop + endfacet + facet normal 0.382067 0.110947 0.917451 + outer loop + vertex 1.09437 2.0384 2.5597 + vertex 1.09689 2.04121 2.55831 + vertex 1.09391 2.04317 2.55931 + endloop + endfacet + facet normal 0.382902 0.112491 0.916914 + outer loop + vertex 1.09689 2.04121 2.55831 + vertex 1.09757 2.04594 2.55744 + vertex 1.09391 2.04317 2.55931 + endloop + endfacet + facet normal 0.392048 0.0988714 0.914616 + outer loop + vertex 1.09391 2.04317 2.55931 + vertex 1.09757 2.04594 2.55744 + vertex 1.09344 2.0481 2.55898 + endloop + endfacet + facet normal 0.398331 0.114137 0.910113 + outer loop + vertex 1.09757 2.04594 2.55744 + vertex 1.09618 2.052 2.55729 + vertex 1.09344 2.0481 2.55898 + endloop + endfacet + facet normal 0.424819 0.091388 0.900654 + outer loop + vertex 1.09344 2.0481 2.55898 + vertex 1.09618 2.052 2.55729 + vertex 1.09248 2.05237 2.559 + endloop + endfacet + facet normal 0.397334 0.112192 0.91079 + outer loop + vertex 1.09938 2.05394 2.55564 + vertex 1.10016 2.05806 2.55479 + vertex 1.097 2.05632 2.55638 + endloop + endfacet + facet normal 0.400102 0.115478 0.909166 + outer loop + vertex 1.097 2.05632 2.55638 + vertex 1.09618 2.052 2.55729 + vertex 1.09938 2.05394 2.55564 + endloop + endfacet + facet normal 0.438518 0.104723 0.8926 + outer loop + vertex 1.097 2.05632 2.55638 + vertex 1.09303 2.05736 2.55821 + vertex 1.09618 2.052 2.55729 + endloop + endfacet + facet normal 0.424998 0.0954856 0.900144 + outer loop + vertex 1.09303 2.05736 2.55821 + vertex 1.09248 2.05237 2.559 + vertex 1.09618 2.052 2.55729 + endloop + endfacet + facet normal 0.411063 0.118717 0.903844 + outer loop + vertex 1.10016 2.05806 2.55479 + vertex 1.0993 2.06312 2.55452 + vertex 1.09643 2.06036 2.55618 + endloop + endfacet + facet normal 0.402672 0.101533 0.909696 + outer loop + vertex 1.097 2.05632 2.55638 + vertex 1.10016 2.05806 2.55479 + vertex 1.09643 2.06036 2.55618 + endloop + endfacet + facet normal 0.438687 0.105719 0.8924 + outer loop + vertex 1.09643 2.06036 2.55618 + vertex 1.09303 2.05736 2.55821 + vertex 1.097 2.05632 2.55638 + endloop + endfacet + facet normal 0.440606 0.103118 0.891759 + outer loop + vertex 1.09348 2.06243 2.5574 + vertex 1.09303 2.05736 2.55821 + vertex 1.09643 2.06036 2.55618 + endloop + endfacet + facet normal 0.427314 0.114249 0.896855 + outer loop + vertex 1.0993 2.06312 2.55452 + vertex 1.09853 2.06818 2.55424 + vertex 1.0958 2.0651 2.55593 + endloop + endfacet + facet normal 0.422932 0.10414 0.900157 + outer loop + vertex 1.09643 2.06036 2.55618 + vertex 1.0993 2.06312 2.55452 + vertex 1.0958 2.0651 2.55593 + endloop + endfacet + facet normal 0.44228 0.106218 0.890565 + outer loop + vertex 1.0958 2.0651 2.55593 + vertex 1.09348 2.06243 2.5574 + vertex 1.09643 2.06036 2.55618 + endloop + endfacet + facet normal 0.441368 0.107197 0.8909 + outer loop + vertex 1.09223 2.06676 2.5575 + vertex 1.09348 2.06243 2.5574 + vertex 1.0958 2.0651 2.55593 + endloop + endfacet + facet normal 0.438845 0.115949 0.89105 + outer loop + vertex 1.09853 2.06818 2.55424 + vertex 1.09718 2.07312 2.55426 + vertex 1.09486 2.06983 2.55583 + endloop + endfacet + facet normal 0.43543 0.105512 0.894018 + outer loop + vertex 1.0958 2.0651 2.55593 + vertex 1.09853 2.06818 2.55424 + vertex 1.09486 2.06983 2.55583 + endloop + endfacet + facet normal 0.441158 0.106577 0.891079 + outer loop + vertex 1.09486 2.06983 2.55583 + vertex 1.09223 2.06676 2.5575 + vertex 1.0958 2.0651 2.55593 + endloop + endfacet + facet normal 0.42893 0.119412 0.895411 + outer loop + vertex 1.09115 2.07196 2.55733 + vertex 1.09223 2.06676 2.5575 + vertex 1.09486 2.06983 2.55583 + endloop + endfacet + facet normal 0.443207 0.112076 0.889386 + outer loop + vertex 1.0941 2.07378 2.55571 + vertex 1.09486 2.06983 2.55583 + vertex 1.09718 2.07312 2.55426 + endloop + endfacet + facet normal 0.444957 0.126393 0.886588 + outer loop + vertex 1.0941 2.07378 2.55571 + vertex 1.09718 2.07312 2.55426 + vertex 1.09501 2.07789 2.55467 + endloop + endfacet + facet normal 0.435405 0.121583 0.891987 + outer loop + vertex 1.09501 2.07789 2.55467 + vertex 1.09718 2.07312 2.55426 + vertex 1.09918 2.07685 2.55277 + endloop + endfacet + facet normal 0.424252 0.108714 0.898995 + outer loop + vertex 1.09486 2.06983 2.55583 + vertex 1.0941 2.07378 2.55571 + vertex 1.09115 2.07196 2.55733 + endloop + endfacet + facet normal 0.434338 0.114634 0.893426 + outer loop + vertex 1.09918 2.07685 2.55277 + vertex 1.09787 2.08169 2.55279 + vertex 1.09501 2.07789 2.55467 + endloop + endfacet + facet normal 0.402275 0.14396 0.90413 + outer loop + vertex 1.09501 2.07789 2.55467 + vertex 1.09787 2.08169 2.55279 + vertex 1.09345 2.08381 2.55442 + endloop + endfacet + facet normal 0.394079 0.12156 0.911002 + outer loop + vertex 1.09787 2.08169 2.55279 + vertex 1.09702 2.08661 2.5525 + vertex 1.09345 2.08381 2.55442 + endloop + endfacet + facet normal 0.249759 0.3347 0.908623 + outer loop + vertex 1.09946 2.11355 2.54593 + vertex 1.09883 2.1178 2.54454 + vertex 1.09626 2.11509 2.54624 + endloop + endfacet + facet normal 0.224676 0.277337 0.934133 + outer loop + vertex 1.09626 2.11509 2.54624 + vertex 1.09674 2.11082 2.5474 + vertex 1.09946 2.11355 2.54593 + endloop + endfacet + facet normal 0.198579 0.276064 0.940401 + outer loop + vertex 1.09626 2.11509 2.54624 + vertex 1.09204 2.11496 2.54717 + vertex 1.09674 2.11082 2.5474 + endloop + endfacet + facet normal 0.232672 0.313682 0.92058 + outer loop + vertex 1.09204 2.11496 2.54717 + vertex 1.09221 2.11114 2.54843 + vertex 1.09674 2.11082 2.5474 + endloop + endfacet + facet normal 0.209265 0.37079 0.904833 + outer loop + vertex 1.09405 2.11777 2.54566 + vertex 1.09626 2.11509 2.54624 + vertex 1.09883 2.1178 2.54454 + endloop + endfacet + facet normal 0.195334 0.491396 0.848749 + outer loop + vertex 1.09405 2.11777 2.54566 + vertex 1.09883 2.1178 2.54454 + vertex 1.09329 2.12106 2.54393 + endloop + endfacet + facet normal 0.152398 0.426558 0.891529 + outer loop + vertex 1.09329 2.12106 2.54393 + vertex 1.09883 2.1178 2.54454 + vertex 1.09775 2.12171 2.54285 + endloop + endfacet + facet normal 0.190368 0.357302 0.914383 + outer loop + vertex 1.09626 2.11509 2.54624 + vertex 1.09405 2.11777 2.54566 + vertex 1.09204 2.11496 2.54717 + endloop + endfacet + facet normal 0.0688483 0.816905 0.572648 + outer loop + vertex 1.09483 2.1239 2.54134 + vertex 1.0996 2.12382 2.54087 + vertex 1.09667 2.12575 2.53847 + endloop + endfacet + facet normal 0.0390285 0.827338 0.560347 + outer loop + vertex 1.09162 2.12587 2.53864 + vertex 1.09483 2.1239 2.54134 + vertex 1.09667 2.12575 2.53847 + endloop + endfacet + facet normal 0.0885087 0.644743 0.759258 + outer loop + vertex 1.09775 2.12171 2.54285 + vertex 1.09483 2.1239 2.54134 + vertex 1.09329 2.12106 2.54393 + endloop + endfacet + facet normal 0.0844386 0.641521 0.762444 + outer loop + vertex 1.0996 2.12382 2.54087 + vertex 1.09483 2.1239 2.54134 + vertex 1.09775 2.12171 2.54285 + endloop + endfacet + facet normal 0.0165759 0.5922 0.805621 + outer loop + vertex 1.1 2.13271 2.525 + vertex 1.095 2.13285 2.525 + vertex 1.09923 2.12979 2.52716 + endloop + endfacet + facet normal 0.0802237 0.646821 0.758411 + outer loop + vertex 1.09923 2.12979 2.52716 + vertex 1.095 2.13285 2.525 + vertex 1.09426 2.12996 2.52755 + endloop + endfacet + facet normal 0.0591078 0.931666 0.358476 + outer loop + vertex 1.09923 2.12979 2.52716 + vertex 1.09426 2.12996 2.52755 + vertex 1.09871 2.12833 2.53104 + endloop + endfacet + facet normal 0.0623657 0.932833 0.354872 + outer loop + vertex 1.09871 2.12833 2.53104 + vertex 1.09426 2.12996 2.52755 + vertex 1.09363 2.12856 2.53132 + endloop + endfacet + facet normal 0.0597962 0.955193 0.289881 + outer loop + vertex 1.09871 2.12833 2.53104 + vertex 1.09363 2.12856 2.53132 + vertex 1.09795 2.12717 2.53502 + endloop + endfacet + facet normal 0.0131566 0.940714 0.338945 + outer loop + vertex 1.09795 2.12717 2.53502 + vertex 1.09363 2.12856 2.53132 + vertex 1.09295 2.12721 2.5351 + endloop + endfacet + facet normal 0.0348655 0.930693 0.364137 + outer loop + vertex 1.09667 2.12575 2.53847 + vertex 1.09295 2.12721 2.5351 + vertex 1.09162 2.12587 2.53864 + endloop + endfacet + facet normal 0.0137714 0.923179 0.384124 + outer loop + vertex 1.09795 2.12717 2.53502 + vertex 1.09295 2.12721 2.5351 + vertex 1.09667 2.12575 2.53847 + endloop + endfacet + facet normal 0.0347387 -0.985965 0.163298 + outer loop + vertex 1.09945 0.893695 2.52604 + vertex 1.10268 0.893721 2.5255 + vertex 1.10136 0.894007 2.52751 + endloop + endfacet + facet normal -0.0912268 -0.801316 -0.591245 + outer loop + vertex 1.09945 0.893695 2.52604 + vertex 1.1 0.894399 2.525 + vertex 1.10268 0.893721 2.5255 + endloop + endfacet + facet normal 0.0066184 -0.580137 -0.814492 + outer loop + vertex 1.1 0.894399 2.525 + vertex 1.105 0.894456 2.525 + vertex 1.10268 0.893721 2.5255 + endloop + endfacet + facet normal 0.0583463 -0.982246 0.178292 + outer loop + vertex 1.10268 0.893721 2.5255 + vertex 1.10498 0.894305 2.52797 + vertex 1.10136 0.894007 2.52751 + endloop + endfacet + facet normal -0.00695541 -0.976471 0.215538 + outer loop + vertex 1.09945 0.893695 2.52604 + vertex 1.10136 0.894007 2.52751 + vertex 1.09792 0.894258 2.52854 + endloop + endfacet + facet normal 0.0321319 -0.934413 0.35474 + outer loop + vertex 1.10136 0.894007 2.52751 + vertex 1.10498 0.894305 2.52797 + vertex 1.10199 0.895083 2.53029 + endloop + endfacet + facet normal 0.0373148 -0.934629 0.353661 + outer loop + vertex 1.10136 0.894007 2.52751 + vertex 1.10199 0.895083 2.53029 + vertex 1.09792 0.894258 2.52854 + endloop + endfacet + facet normal 0.030102 -0.929368 0.367924 + outer loop + vertex 1.09792 0.894258 2.52854 + vertex 1.10199 0.895083 2.53029 + vertex 1.09852 0.895578 2.53182 + endloop + endfacet + facet normal 0.0643154 -0.898042 0.435183 + outer loop + vertex 1.10199 0.895083 2.53029 + vertex 1.10195 0.896969 2.53419 + vertex 1.09852 0.895578 2.53182 + endloop + endfacet + facet normal 0.0635691 -0.897676 0.436048 + outer loop + vertex 1.10195 0.896969 2.53419 + vertex 1.09669 0.896922 2.53486 + vertex 1.09852 0.895578 2.53182 + endloop + endfacet + facet normal 0.0701824 -0.868838 0.490096 + outer loop + vertex 1.10195 0.896969 2.53419 + vertex 1.09947 0.898862 2.5379 + vertex 1.09669 0.896922 2.53486 + endloop + endfacet + facet normal 0.0861532 -0.863006 0.497793 + outer loop + vertex 1.10362 0.898901 2.53725 + vertex 1.09947 0.898862 2.5379 + vertex 1.10195 0.896969 2.53419 + endloop + endfacet + facet normal 0.10239 -0.788799 0.606062 + outer loop + vertex 1.09947 0.898862 2.5379 + vertex 1.10362 0.898901 2.53725 + vertex 1.10293 0.901319 2.54051 + endloop + endfacet + facet normal 0.142171 -0.808169 0.571533 + outer loop + vertex 1.09721 0.900965 2.54143 + vertex 1.09947 0.898862 2.5379 + vertex 1.10293 0.901319 2.54051 + endloop + endfacet + facet normal 0.157453 -0.681298 0.714872 + outer loop + vertex 1.10293 0.901319 2.54051 + vertex 1.10022 0.904381 2.54403 + vertex 1.09721 0.900965 2.54143 + endloop + endfacet + facet normal 0.223105 -0.643257 0.732423 + outer loop + vertex 1.10546 0.904911 2.54289 + vertex 1.10022 0.904381 2.54403 + vertex 1.10293 0.901319 2.54051 + endloop + endfacet + facet normal 0.261843 -0.51922 0.813541 + outer loop + vertex 1.10053 0.907608 2.54599 + vertex 1.09694 0.906112 2.54619 + vertex 1.10022 0.904381 2.54403 + endloop + endfacet + facet normal 0.337247 -0.512132 0.789928 + outer loop + vertex 1.10053 0.907608 2.54599 + vertex 1.10022 0.904381 2.54403 + vertex 1.1044 0.908679 2.54503 + endloop + endfacet + facet normal 0.231823 -0.428988 0.873057 + outer loop + vertex 1.1044 0.908679 2.54503 + vertex 1.10022 0.904381 2.54403 + vertex 1.10546 0.904911 2.54289 + endloop + endfacet + facet normal 0.199515 -0.356575 0.912714 + outer loop + vertex 1.10053 0.907608 2.54599 + vertex 1.09926 0.909917 2.54717 + vertex 1.09694 0.906112 2.54619 + endloop + endfacet + facet normal 0.35771 -0.19186 0.913911 + outer loop + vertex 1.10192 0.933656 2.55164 + vertex 1.09814 0.933866 2.55316 + vertex 1.09824 0.928847 2.55207 + endloop + endfacet + facet normal 0.375423 -0.122162 0.918768 + outer loop + vertex 1.09801 0.998889 2.56295 + vertex 1.10207 1.00309 2.56185 + vertex 1.09849 1.00404 2.56343 + endloop + endfacet + facet normal 0.37233 -0.133332 0.918473 + outer loop + vertex 1.10207 1.00309 2.56185 + vertex 1.1032 1.00869 2.5622 + vertex 1.09849 1.00404 2.56343 + endloop + endfacet + facet normal 0.286626 -0.152713 0.945793 + outer loop + vertex 1.10354 1.02423 2.56455 + vertex 1.10443 1.02952 2.56513 + vertex 1.10051 1.02646 2.56583 + endloop + endfacet + facet normal 0.341777 -0.141935 0.929001 + outer loop + vertex 1.09736 1.02793 2.56721 + vertex 1.0969 1.02337 2.56668 + vertex 1.10051 1.02646 2.56583 + endloop + endfacet + facet normal 0.27606 -0.158784 0.947934 + outer loop + vertex 1.10443 1.02952 2.56513 + vertex 1.10464 1.03297 2.56565 + vertex 1.10139 1.03082 2.56623 + endloop + endfacet + facet normal 0.281729 -0.145843 0.948345 + outer loop + vertex 1.10051 1.02646 2.56583 + vertex 1.10443 1.02952 2.56513 + vertex 1.10139 1.03082 2.56623 + endloop + endfacet + facet normal 0.335695 -0.155031 0.929125 + outer loop + vertex 1.10139 1.03082 2.56623 + vertex 1.09736 1.02793 2.56721 + vertex 1.10051 1.02646 2.56583 + endloop + endfacet + facet normal 0.335673 -0.154996 0.929139 + outer loop + vertex 1.09881 1.03351 2.56762 + vertex 1.09736 1.02793 2.56721 + vertex 1.10139 1.03082 2.56623 + endloop + endfacet + facet normal 0.279881 -0.165123 0.945728 + outer loop + vertex 1.10464 1.03297 2.56565 + vertex 1.10291 1.0344 2.56641 + vertex 1.10139 1.03082 2.56623 + endloop + endfacet + facet normal 0.31304 -0.178541 0.932807 + outer loop + vertex 1.10291 1.0344 2.56641 + vertex 1.09881 1.03351 2.56762 + vertex 1.10139 1.03082 2.56623 + endloop + endfacet + facet normal 0.317271 -0.208537 0.925122 + outer loop + vertex 1.10291 1.0344 2.56641 + vertex 1.10382 1.03856 2.56704 + vertex 1.09881 1.03351 2.56762 + endloop + endfacet + facet normal 0.265534 -0.154157 0.951697 + outer loop + vertex 1.10382 1.03856 2.56704 + vertex 1.0989 1.03894 2.56847 + vertex 1.09881 1.03351 2.56762 + endloop + endfacet + facet normal 0.263171 -0.174189 0.948894 + outer loop + vertex 1.10382 1.03856 2.56704 + vertex 1.10341 1.04352 2.56806 + vertex 1.0989 1.03894 2.56847 + endloop + endfacet + facet normal 0.237026 -0.147443 0.96025 + outer loop + vertex 1.0989 1.03894 2.56847 + vertex 1.10341 1.04352 2.56806 + vertex 1.09889 1.04389 2.56923 + endloop + endfacet + facet normal 0.139134 -0.170242 0.97553 + outer loop + vertex 1.10054 1.16672 2.59095 + vertex 1.09919 1.16304 2.5905 + vertex 1.10366 1.16722 2.59059 + endloop + endfacet + facet normal 0.140495 -0.180293 0.973527 + outer loop + vertex 1.10366 1.16722 2.59059 + vertex 1.10278 1.16955 2.59115 + vertex 1.10054 1.16672 2.59095 + endloop + endfacet + facet normal 0.235008 -0.0773062 0.968914 + outer loop + vertex 1.10218 1.2226 2.59685 + vertex 1.10218 1.22756 2.59724 + vertex 1.09809 1.22312 2.59788 + endloop + endfacet + facet normal 0.303243 -0.0913621 0.948523 + outer loop + vertex 1.09806 1.2281 2.59842 + vertex 1.10211 1.23255 2.59756 + vertex 1.09808 1.23314 2.5989 + endloop + endfacet + facet normal 0.31063 -0.043225 0.949547 + outer loop + vertex 1.10211 1.23255 2.59756 + vertex 1.10211 1.23761 2.59778 + vertex 1.09808 1.23314 2.5989 + endloop + endfacet + facet normal 0.35769 -0.0906763 0.929428 + outer loop + vertex 1.09808 1.23314 2.5989 + vertex 1.10211 1.23761 2.59778 + vertex 1.09823 1.23823 2.59934 + endloop + endfacet + facet normal 0.366531 -0.0361786 0.929702 + outer loop + vertex 1.10211 1.23761 2.59778 + vertex 1.10221 1.24289 2.59795 + vertex 1.09823 1.23823 2.59934 + endloop + endfacet + facet normal 0.450409 -0.121424 0.884527 + outer loop + vertex 1.09823 1.23823 2.59934 + vertex 1.10221 1.24289 2.59795 + vertex 1.09845 1.24339 2.59993 + endloop + endfacet + facet normal 0.356369 -0.157535 0.920969 + outer loop + vertex 1.09917 1.24751 2.60036 + vertex 1.09678 1.24513 2.60088 + vertex 1.09845 1.24339 2.59993 + endloop + endfacet + facet normal 0.575208 -0.182647 0.797355 + outer loop + vertex 1.09917 1.24751 2.60036 + vertex 1.09845 1.24339 2.59993 + vertex 1.10221 1.24866 2.59843 + endloop + endfacet + facet normal 0.457683 -0.0733898 0.886081 + outer loop + vertex 1.10221 1.24866 2.59843 + vertex 1.09845 1.24339 2.59993 + vertex 1.10221 1.24289 2.59795 + endloop + endfacet + facet normal 0.307064 -0.102679 0.946133 + outer loop + vertex 1.09917 1.24751 2.60036 + vertex 1.09681 1.24823 2.60121 + vertex 1.09678 1.24513 2.60088 + endloop + endfacet + facet normal 0.60904 -0.0527797 0.791382 + outer loop + vertex 1.10221 1.24866 2.59843 + vertex 1.10295 1.25461 2.59825 + vertex 1.10006 1.25148 2.60027 + endloop + endfacet + facet normal 0.561639 -0.107825 0.820327 + outer loop + vertex 1.09917 1.24751 2.60036 + vertex 1.10221 1.24866 2.59843 + vertex 1.10006 1.25148 2.60027 + endloop + endfacet + facet normal 0.322542 -0.0508282 0.945189 + outer loop + vertex 1.10006 1.25148 2.60027 + vertex 1.09681 1.24823 2.60121 + vertex 1.09917 1.24751 2.60036 + endloop + endfacet + facet normal 0.358202 -0.0912543 0.929174 + outer loop + vertex 1.09702 1.25259 2.60155 + vertex 1.09681 1.24823 2.60121 + vertex 1.10006 1.25148 2.60027 + endloop + endfacet + facet normal 0.634898 -0.00854378 0.772549 + outer loop + vertex 1.10295 1.25461 2.59825 + vertex 1.10307 1.25981 2.59821 + vertex 1.10038 1.25638 2.60038 + endloop + endfacet + facet normal 0.613073 -0.0587725 0.787837 + outer loop + vertex 1.10006 1.25148 2.60027 + vertex 1.10295 1.25461 2.59825 + vertex 1.10038 1.25638 2.60038 + endloop + endfacet + facet normal 0.373509 -0.0464061 0.926465 + outer loop + vertex 1.10038 1.25638 2.60038 + vertex 1.09702 1.25259 2.60155 + vertex 1.10006 1.25148 2.60027 + endloop + endfacet + facet normal 0.403455 -0.0775712 0.911706 + outer loop + vertex 1.0971 1.25745 2.60193 + vertex 1.09702 1.25259 2.60155 + vertex 1.10038 1.25638 2.60038 + endloop + endfacet + facet normal 0.659008 0.0231969 0.751778 + outer loop + vertex 1.10307 1.25981 2.59821 + vertex 1.10299 1.26485 2.59813 + vertex 1.1004 1.2614 2.6005 + endloop + endfacet + facet normal 0.644056 -0.0206639 0.7647 + outer loop + vertex 1.10038 1.25638 2.60038 + vertex 1.10307 1.25981 2.59821 + vertex 1.1004 1.2614 2.6005 + endloop + endfacet + facet normal 0.419219 -0.0232385 0.907587 + outer loop + vertex 1.1004 1.2614 2.6005 + vertex 1.0971 1.25745 2.60193 + vertex 1.10038 1.25638 2.60038 + endloop + endfacet + facet normal 0.44717 -0.0519417 0.892939 + outer loop + vertex 1.09708 1.26248 2.60223 + vertex 1.0971 1.25745 2.60193 + vertex 1.1004 1.2614 2.6005 + endloop + endfacet + facet normal 0.681847 0.0538115 0.729513 + outer loop + vertex 1.10299 1.26485 2.59813 + vertex 1.10292 1.2697 2.59784 + vertex 1.10037 1.26651 2.60045 + endloop + endfacet + facet normal 0.667902 0.0112743 0.744164 + outer loop + vertex 1.1004 1.2614 2.6005 + vertex 1.10299 1.26485 2.59813 + vertex 1.10037 1.26651 2.60045 + endloop + endfacet + facet normal 0.464076 0.0114439 0.885721 + outer loop + vertex 1.10037 1.26651 2.60045 + vertex 1.09708 1.26248 2.60223 + vertex 1.1004 1.2614 2.6005 + endloop + endfacet + facet normal 0.498287 -0.0249758 0.866652 + outer loop + vertex 1.09709 1.26766 2.60237 + vertex 1.09708 1.26248 2.60223 + vertex 1.10037 1.26651 2.60045 + endloop + endfacet + facet normal 0.72355 0.0692147 0.686793 + outer loop + vertex 1.10292 1.2697 2.59784 + vertex 1.10309 1.2735 2.59727 + vertex 1.10062 1.27214 2.60002 + endloop + endfacet + facet normal 0.700981 0.0247592 0.71275 + outer loop + vertex 1.10037 1.26651 2.60045 + vertex 1.10292 1.2697 2.59784 + vertex 1.10062 1.27214 2.60002 + endloop + endfacet + facet normal 0.515916 0.0437009 0.855524 + outer loop + vertex 1.10062 1.27214 2.60002 + vertex 1.09709 1.26766 2.60237 + vertex 1.10037 1.26651 2.60045 + endloop + endfacet + facet normal 0.578032 -0.0261449 0.815595 + outer loop + vertex 1.09708 1.27288 2.60255 + vertex 1.09709 1.26766 2.60237 + vertex 1.10062 1.27214 2.60002 + endloop + endfacet + facet normal 0.83151 0.0800191 0.549717 + outer loop + vertex 1.10424 1.27604 2.59521 + vertex 1.10433 1.2799 2.59452 + vertex 1.10256 1.27669 2.59767 + endloop + endfacet + facet normal 0.831018 0.0715263 0.551627 + outer loop + vertex 1.10309 1.2735 2.59727 + vertex 1.10424 1.27604 2.59521 + vertex 1.10256 1.27669 2.59767 + endloop + endfacet + facet normal 0.732257 0.0392688 0.679895 + outer loop + vertex 1.10309 1.2735 2.59727 + vertex 1.10256 1.27669 2.59767 + vertex 1.10062 1.27214 2.60002 + endloop + endfacet + facet normal 0.752225 0.0197148 0.658612 + outer loop + vertex 1.10062 1.27214 2.60002 + vertex 1.10256 1.27669 2.59767 + vertex 1.10013 1.2773 2.60042 + endloop + endfacet + facet normal 0.580684 -0.00824079 0.814088 + outer loop + vertex 1.10013 1.2773 2.60042 + vertex 1.09708 1.27288 2.60255 + vertex 1.10062 1.27214 2.60002 + endloop + endfacet + facet normal 0.61856 -0.0488144 0.78422 + outer loop + vertex 1.09706 1.27806 2.60289 + vertex 1.09708 1.27288 2.60255 + vertex 1.10013 1.2773 2.60042 + endloop + endfacet + facet normal 0.854326 0.0469528 0.517613 + outer loop + vertex 1.10433 1.2799 2.59452 + vertex 1.10421 1.2847 2.59428 + vertex 1.10238 1.28113 2.59763 + endloop + endfacet + facet normal 0.853224 0.0389637 0.520087 + outer loop + vertex 1.10256 1.27669 2.59767 + vertex 1.10433 1.2799 2.59452 + vertex 1.10238 1.28113 2.59763 + endloop + endfacet + facet normal 0.753683 0.0361006 0.656246 + outer loop + vertex 1.10256 1.27669 2.59767 + vertex 1.10238 1.28113 2.59763 + vertex 1.10013 1.2773 2.60042 + endloop + endfacet + facet normal 0.781968 -0.00455575 0.623302 + outer loop + vertex 1.10238 1.28113 2.59763 + vertex 1.10004 1.28235 2.60057 + vertex 1.10013 1.2773 2.60042 + endloop + endfacet + facet normal 0.624788 -0.012152 0.7807 + outer loop + vertex 1.10004 1.28235 2.60057 + vertex 1.09706 1.27806 2.60289 + vertex 1.10013 1.2773 2.60042 + endloop + endfacet + facet normal 0.673685 -0.0706571 0.735633 + outer loop + vertex 1.09707 1.28362 2.60341 + vertex 1.09706 1.27806 2.60289 + vertex 1.10004 1.28235 2.60057 + endloop + endfacet + facet normal 0.867718 0.0416488 0.495309 + outer loop + vertex 1.10421 1.2847 2.59428 + vertex 1.10404 1.28963 2.59416 + vertex 1.1023 1.28599 2.59752 + endloop + endfacet + facet normal 0.865378 0.0252074 0.500485 + outer loop + vertex 1.10238 1.28113 2.59763 + vertex 1.10421 1.2847 2.59428 + vertex 1.1023 1.28599 2.59752 + endloop + endfacet + facet normal 0.787936 0.0263755 0.615191 + outer loop + vertex 1.10238 1.28113 2.59763 + vertex 1.1023 1.28599 2.59752 + vertex 1.10004 1.28235 2.60057 + endloop + endfacet + facet normal 0.808622 -0.00894734 0.588261 + outer loop + vertex 1.1023 1.28599 2.59752 + vertex 1.10013 1.28759 2.60053 + vertex 1.10004 1.28235 2.60057 + endloop + endfacet + facet normal 0.690059 -0.00588177 0.723729 + outer loop + vertex 1.10013 1.28759 2.60053 + vertex 1.09707 1.28362 2.60341 + vertex 1.10004 1.28235 2.60057 + endloop + endfacet + facet normal 0.725049 -0.0602205 0.686059 + outer loop + vertex 1.09782 1.28951 2.60314 + vertex 1.09707 1.28362 2.60341 + vertex 1.10013 1.28759 2.60053 + endloop + endfacet + facet normal 0.877357 0.0579958 0.476321 + outer loop + vertex 1.10404 1.28963 2.59416 + vertex 1.10381 1.29469 2.59396 + vertex 1.10222 1.29104 2.59734 + endloop + endfacet + facet normal 0.873309 0.0305405 0.486208 + outer loop + vertex 1.1023 1.28599 2.59752 + vertex 1.10404 1.28963 2.59416 + vertex 1.10222 1.29104 2.59734 + endloop + endfacet + facet normal 0.818732 0.0328951 0.573232 + outer loop + vertex 1.1023 1.28599 2.59752 + vertex 1.10222 1.29104 2.59734 + vertex 1.10013 1.28759 2.60053 + endloop + endfacet + facet normal 0.833236 0.00528161 0.552892 + outer loop + vertex 1.10222 1.29104 2.59734 + vertex 1.10022 1.29284 2.60034 + vertex 1.10013 1.28759 2.60053 + endloop + endfacet + facet normal 0.752635 0.0105336 0.658353 + outer loop + vertex 1.10022 1.29284 2.60034 + vertex 1.09782 1.28951 2.60314 + vertex 1.10013 1.28759 2.60053 + endloop + endfacet + facet normal 0.764364 -0.00941704 0.644716 + outer loop + vertex 1.09795 1.29472 2.60306 + vertex 1.09782 1.28951 2.60314 + vertex 1.10022 1.29284 2.60034 + endloop + endfacet + facet normal 0.888487 0.065931 0.454141 + outer loop + vertex 1.10381 1.29469 2.59396 + vertex 1.10354 1.29981 2.59377 + vertex 1.1021 1.29615 2.59711 + endloop + endfacet + facet normal 0.885204 0.0425008 0.463258 + outer loop + vertex 1.10222 1.29104 2.59734 + vertex 1.10381 1.29469 2.59396 + vertex 1.1021 1.29615 2.59711 + endloop + endfacet + facet normal 0.843175 0.0448178 0.535768 + outer loop + vertex 1.10222 1.29104 2.59734 + vertex 1.1021 1.29615 2.59711 + vertex 1.10022 1.29284 2.60034 + endloop + endfacet + facet normal 0.85434 0.0223701 0.519232 + outer loop + vertex 1.1021 1.29615 2.59711 + vertex 1.10018 1.29795 2.60019 + vertex 1.10022 1.29284 2.60034 + endloop + endfacet + facet normal 0.775728 0.0248337 0.630579 + outer loop + vertex 1.10018 1.29795 2.60019 + vertex 1.09795 1.29472 2.60306 + vertex 1.10022 1.29284 2.60034 + endloop + endfacet + facet normal 0.789768 -5.46863e-05 0.613406 + outer loop + vertex 1.09794 1.29976 2.60308 + vertex 1.09795 1.29472 2.60306 + vertex 1.10018 1.29795 2.60019 + endloop + endfacet + facet normal 0.902981 0.057152 0.425863 + outer loop + vertex 1.10354 1.29981 2.59377 + vertex 1.10326 1.30472 2.59369 + vertex 1.10195 1.30124 2.59694 + endloop + endfacet + facet normal 0.90088 0.0409555 0.432132 + outer loop + vertex 1.1021 1.29615 2.59711 + vertex 1.10354 1.29981 2.59377 + vertex 1.10195 1.30124 2.59694 + endloop + endfacet + facet normal 0.858864 0.0423017 0.510455 + outer loop + vertex 1.1021 1.29615 2.59711 + vertex 1.10195 1.30124 2.59694 + vertex 1.10018 1.29795 2.60019 + endloop + endfacet + facet normal 0.869371 0.0201523 0.493749 + outer loop + vertex 1.10195 1.30124 2.59694 + vertex 1.1001 1.303 2.60012 + vertex 1.10018 1.29795 2.60019 + endloop + endfacet + facet normal 0.79583 0.020544 0.605172 + outer loop + vertex 1.1001 1.303 2.60012 + vertex 1.09794 1.29976 2.60308 + vertex 1.10018 1.29795 2.60019 + endloop + endfacet + facet normal 0.809089 -0.00427266 0.58767 + outer loop + vertex 1.09792 1.30476 2.60313 + vertex 1.09794 1.29976 2.60308 + vertex 1.1001 1.303 2.60012 + endloop + endfacet + facet normal 0.917899 0.0564857 0.392774 + outer loop + vertex 1.10326 1.30472 2.59369 + vertex 1.10303 1.30951 2.59353 + vertex 1.10182 1.30631 2.59683 + endloop + endfacet + facet normal 0.914402 0.0319968 0.40354 + outer loop + vertex 1.10195 1.30124 2.59694 + vertex 1.10326 1.30472 2.59369 + vertex 1.10182 1.30631 2.59683 + endloop + endfacet + facet normal 0.872009 0.0326251 0.488401 + outer loop + vertex 1.10195 1.30124 2.59694 + vertex 1.10182 1.30631 2.59683 + vertex 1.1001 1.303 2.60012 + endloop + endfacet + facet normal 0.876444 0.0229158 0.480958 + outer loop + vertex 1.10182 1.30631 2.59683 + vertex 1.10002 1.30806 2.60003 + vertex 1.1001 1.303 2.60012 + endloop + endfacet + facet normal 0.816552 0.0236009 0.57679 + outer loop + vertex 1.10002 1.30806 2.60003 + vertex 1.09792 1.30476 2.60313 + vertex 1.1001 1.303 2.60012 + endloop + endfacet + facet normal 0.824065 0.00909303 0.566422 + outer loop + vertex 1.09791 1.30973 2.60307 + vertex 1.09792 1.30476 2.60313 + vertex 1.10002 1.30806 2.60003 + endloop + endfacet + facet normal -0.745762 -0.19046 0.638408 + outer loop + vertex 1.105 1.31453 2.59 + vertex 1.10488 1.315 2.59 + vertex 1.10426 1.3132 2.58874 + endloop + endfacet + facet normal 0.926598 0.0686548 0.369732 + outer loop + vertex 1.10303 1.30951 2.59353 + vertex 1.10284 1.31422 2.59315 + vertex 1.10168 1.31146 2.59656 + endloop + endfacet + facet normal 0.922558 0.0448835 0.383239 + outer loop + vertex 1.10182 1.30631 2.59683 + vertex 1.10303 1.30951 2.59353 + vertex 1.10168 1.31146 2.59656 + endloop + endfacet + facet normal 0.881431 0.0483847 0.469828 + outer loop + vertex 1.10182 1.30631 2.59683 + vertex 1.10168 1.31146 2.59656 + vertex 1.10002 1.30806 2.60003 + endloop + endfacet + facet normal 0.884125 0.0424606 0.465317 + outer loop + vertex 1.10168 1.31146 2.59656 + vertex 1.09991 1.31316 2.59977 + vertex 1.10002 1.30806 2.60003 + endloop + endfacet + facet normal 0.832578 0.045985 0.551996 + outer loop + vertex 1.09991 1.31316 2.59977 + vertex 1.09791 1.30973 2.60307 + vertex 1.10002 1.30806 2.60003 + endloop + endfacet + facet normal 0.844678 0.0223021 0.53481 + outer loop + vertex 1.09794 1.31456 2.60283 + vertex 1.09791 1.30973 2.60307 + vertex 1.09991 1.31316 2.59977 + endloop + endfacet + facet normal -0.569334 -0.125247 0.81251 + outer loop + vertex 1.10488 1.315 2.59 + vertex 1.10378 1.32 2.59 + vertex 1.1036 1.31577 2.58922 + endloop + endfacet + facet normal -0.619971 -0.296045 0.726632 + outer loop + vertex 1.10426 1.3132 2.58874 + vertex 1.10488 1.315 2.59 + vertex 1.1036 1.31577 2.58922 + endloop + endfacet + facet normal 0.934332 0.0156617 0.35606 + outer loop + vertex 1.10284 1.31422 2.59315 + vertex 1.10302 1.31826 2.59249 + vertex 1.10175 1.3175 2.59586 + endloop + endfacet + facet normal 0.93927 0.0290026 0.341953 + outer loop + vertex 1.10168 1.31146 2.59656 + vertex 1.10284 1.31422 2.59315 + vertex 1.10175 1.3175 2.59586 + endloop + endfacet + facet normal 0.884368 0.0438302 0.464727 + outer loop + vertex 1.10168 1.31146 2.59656 + vertex 1.10175 1.3175 2.59586 + vertex 1.09991 1.31316 2.59977 + endloop + endfacet + facet normal 0.879483 0.05328 0.472938 + outer loop + vertex 1.10175 1.3175 2.59586 + vertex 1.09969 1.31785 2.59966 + vertex 1.09991 1.31316 2.59977 + endloop + endfacet + facet normal 0.850001 0.0530556 0.524102 + outer loop + vertex 1.09969 1.31785 2.59966 + vertex 1.09794 1.31456 2.60283 + vertex 1.09991 1.31316 2.59977 + endloop + endfacet + facet normal 0.867937 0.0168098 0.49639 + outer loop + vertex 1.09815 1.31834 2.60233 + vertex 1.09794 1.31456 2.60283 + vertex 1.09969 1.31785 2.59966 + endloop + endfacet + facet normal 0.912418 -0.111452 0.393792 + outer loop + vertex 1.10337 1.31883 2.59062 + vertex 1.1036 1.31577 2.58922 + vertex 1.10378 1.32 2.59 + endloop + endfacet + facet normal 0.954288 -0.279519 0.105851 + outer loop + vertex 1.10337 1.31883 2.59062 + vertex 1.10378 1.32 2.59 + vertex 1.10469 1.325 2.595 + endloop + endfacet + facet normal 0.960028 0.0902508 -0.264955 + outer loop + vertex 1.10469 1.325 2.595 + vertex 1.10378 1.32 2.59 + vertex 1.10331 1.325 2.59 + endloop + endfacet + facet normal 0.957392 -0.272642 0.0952246 + outer loop + vertex 1.10302 1.31826 2.59249 + vertex 1.10337 1.31883 2.59062 + vertex 1.10469 1.325 2.595 + endloop + endfacet + facet normal 0.906873 -0.324652 0.268668 + outer loop + vertex 1.10302 1.31826 2.59249 + vertex 1.10469 1.325 2.595 + vertex 1.10175 1.3175 2.59586 + endloop + endfacet + facet normal 0.490722 -0.0928409 0.866356 + outer loop + vertex 1.10175 1.3175 2.59586 + vertex 1.10469 1.325 2.595 + vertex 1.10111 1.32326 2.59684 + endloop + endfacet + facet normal 0.853741 0.0659005 0.516512 + outer loop + vertex 1.0992 1.32101 2.60029 + vertex 1.10111 1.32326 2.59684 + vertex 1.09928 1.32481 2.59967 + endloop + endfacet + facet normal 0.864719 0.0331631 0.50116 + outer loop + vertex 1.0992 1.32101 2.60029 + vertex 1.09969 1.31785 2.59966 + vertex 1.10111 1.32326 2.59684 + endloop + endfacet + facet normal 0.879171 0.0163979 0.476225 + outer loop + vertex 1.09969 1.31785 2.59966 + vertex 1.10175 1.3175 2.59586 + vertex 1.10111 1.32326 2.59684 + endloop + endfacet + facet normal 0.868956 0.0353252 0.493627 + outer loop + vertex 1.09969 1.31785 2.59966 + vertex 1.0992 1.32101 2.60029 + vertex 1.09815 1.31834 2.60233 + endloop + endfacet + facet normal 0.428815 0.0711778 0.900584 + outer loop + vertex 1.10469 1.325 2.595 + vertex 1.10386 1.33 2.595 + vertex 1.10111 1.32326 2.59684 + endloop + endfacet + facet normal 0.420613 0.0754865 0.904094 + outer loop + vertex 1.10386 1.33 2.595 + vertex 1.10101 1.32894 2.59642 + vertex 1.10111 1.32326 2.59684 + endloop + endfacet + facet normal 0.851599 0.0544774 0.521355 + outer loop + vertex 1.10101 1.32894 2.59642 + vertex 1.09928 1.32481 2.59967 + vertex 1.10111 1.32326 2.59684 + endloop + endfacet + facet normal 0.855852 0.0477152 0.515016 + outer loop + vertex 1.09919 1.32957 2.59938 + vertex 1.09928 1.32481 2.59967 + vertex 1.10101 1.32894 2.59642 + endloop + endfacet + facet normal 0.428267 0.0522482 0.90214 + outer loop + vertex 1.10386 1.33 2.595 + vertex 1.10325 1.335 2.595 + vertex 1.10101 1.32894 2.59642 + endloop + endfacet + facet normal 0.443112 0.0451632 0.895328 + outer loop + vertex 1.10325 1.335 2.595 + vertex 1.10078 1.33399 2.59627 + vertex 1.10101 1.32894 2.59642 + endloop + endfacet + facet normal 0.85612 0.0530229 0.514049 + outer loop + vertex 1.10078 1.33399 2.59627 + vertex 1.09919 1.32957 2.59938 + vertex 1.10101 1.32894 2.59642 + endloop + endfacet + facet normal 0.857394 0.0512001 0.512108 + outer loop + vertex 1.09902 1.33457 2.59915 + vertex 1.09919 1.32957 2.59938 + vertex 1.10078 1.33399 2.59627 + endloop + endfacet + facet normal 0.449048 0.0278467 0.893074 + outer loop + vertex 1.10325 1.335 2.595 + vertex 1.10294 1.34 2.595 + vertex 1.10078 1.33399 2.59627 + endloop + endfacet + facet normal 0.406007 0.0474475 0.912637 + outer loop + vertex 1.10294 1.34 2.595 + vertex 1.10052 1.33907 2.59612 + vertex 1.10078 1.33399 2.59627 + endloop + endfacet + facet normal 0.857691 0.0583176 0.510848 + outer loop + vertex 1.10052 1.33907 2.59612 + vertex 1.09902 1.33457 2.59915 + vertex 1.10078 1.33399 2.59627 + endloop + endfacet + facet normal 0.85429 0.0629116 0.515975 + outer loop + vertex 1.09881 1.33965 2.5989 + vertex 1.09902 1.33457 2.59915 + vertex 1.10052 1.33907 2.59612 + endloop + endfacet + facet normal 0.415466 0.0191077 0.909408 + outer loop + vertex 1.10294 1.34 2.595 + vertex 1.10271 1.345 2.595 + vertex 1.10052 1.33907 2.59612 + endloop + endfacet + facet normal 0.33988 0.052541 0.939 + outer loop + vertex 1.10271 1.345 2.595 + vertex 1.10022 1.34416 2.59595 + vertex 1.10052 1.33907 2.59612 + endloop + endfacet + facet normal 0.854508 0.0689433 0.514843 + outer loop + vertex 1.10022 1.34416 2.59595 + vertex 1.09881 1.33965 2.5989 + vertex 1.10052 1.33907 2.59612 + endloop + endfacet + facet normal 0.863941 0.0565504 0.500409 + outer loop + vertex 1.09858 1.34477 2.5987 + vertex 1.09881 1.33965 2.5989 + vertex 1.10022 1.34416 2.59595 + endloop + endfacet + facet normal 0.346516 0.0311875 0.937525 + outer loop + vertex 1.10271 1.345 2.595 + vertex 1.10226 1.35 2.595 + vertex 1.10022 1.34416 2.59595 + endloop + endfacet + facet normal 0.314118 0.04427 0.948351 + outer loop + vertex 1.10226 1.35 2.595 + vertex 1.09981 1.34917 2.59585 + vertex 1.10022 1.34416 2.59595 + endloop + endfacet + facet normal 0.864796 0.0809464 0.495556 + outer loop + vertex 1.09981 1.34917 2.59585 + vertex 1.09858 1.34477 2.5987 + vertex 1.10022 1.34416 2.59595 + endloop + endfacet + facet normal 0.896496 0.0371715 0.441489 + outer loop + vertex 1.0984 1.34978 2.59865 + vertex 1.09858 1.34477 2.5987 + vertex 1.09981 1.34917 2.59585 + endloop + endfacet + facet normal 0.304285 0.0748542 0.949636 + outer loop + vertex 1.10226 1.35 2.595 + vertex 1.10103 1.355 2.595 + vertex 1.09981 1.34917 2.59585 + endloop + endfacet + facet normal 0.483524 0.0262431 0.874937 + outer loop + vertex 1.10103 1.355 2.595 + vertex 1.09939 1.35389 2.59594 + vertex 1.09981 1.34917 2.59585 + endloop + endfacet + facet normal 0.897736 0.0710253 0.434771 + outer loop + vertex 1.09939 1.35389 2.59594 + vertex 1.0984 1.34978 2.59865 + vertex 1.09981 1.34917 2.59585 + endloop + endfacet + facet normal 0.930922 0.0170286 0.36482 + outer loop + vertex 1.09828 1.35451 2.59873 + vertex 1.0984 1.34978 2.59865 + vertex 1.09939 1.35389 2.59594 + endloop + endfacet + facet normal 0.464209 0.0622001 0.883539 + outer loop + vertex 1.10103 1.355 2.595 + vertex 1.10036 1.36 2.595 + vertex 1.09939 1.35389 2.59594 + endloop + endfacet + facet normal 0.690225 0.00163357 0.723593 + outer loop + vertex 1.10036 1.36 2.595 + vertex 1.099 1.35731 2.5963 + vertex 1.09939 1.35389 2.59594 + endloop + endfacet + facet normal 0.93265 0.0685573 0.354208 + outer loop + vertex 1.099 1.35731 2.5963 + vertex 1.09828 1.35451 2.59873 + vertex 1.09939 1.35389 2.59594 + endloop + endfacet + facet normal 0.933632 0.0664115 0.352024 + outer loop + vertex 1.09812 1.35882 2.59836 + vertex 1.09828 1.35451 2.59873 + vertex 1.099 1.35731 2.5963 + endloop + endfacet + facet normal -0.679277 -0.239764 0.693611 + outer loop + vertex 1.09879 1.36168 2.59404 + vertex 1.10036 1.36 2.595 + vertex 1.1 1.36102 2.595 + endloop + endfacet + facet normal 0.366605 0.696251 0.617119 + outer loop + vertex 1.09879 1.36168 2.59404 + vertex 1.09869 1.3604 2.59554 + vertex 1.10036 1.36 2.595 + endloop + endfacet + facet normal 0.352219 0.257484 0.899802 + outer loop + vertex 1.09869 1.3604 2.59554 + vertex 1.099 1.35731 2.5963 + vertex 1.10036 1.36 2.595 + endloop + endfacet + facet normal 0.944435 0.165094 0.28423 + outer loop + vertex 1.09869 1.3604 2.59554 + vertex 1.09812 1.35882 2.59836 + vertex 1.099 1.35731 2.5963 + endloop + endfacet + facet normal 0.942459 0.171122 0.287207 + outer loop + vertex 1.09788 1.36218 2.59714 + vertex 1.09812 1.35882 2.59836 + vertex 1.09869 1.3604 2.59554 + endloop + endfacet + facet normal 0.926775 0.252892 0.277731 + outer loop + vertex 1.09879 1.36168 2.59404 + vertex 1.0981 1.36309 2.59505 + vertex 1.09869 1.3604 2.59554 + endloop + endfacet + facet normal 0.947043 0.244665 0.207965 + outer loop + vertex 1.09869 1.3604 2.59554 + vertex 1.0981 1.36309 2.59505 + vertex 1.09788 1.36218 2.59714 + endloop + endfacet + facet normal -0.304714 0.103535 0.9468 + outer loop + vertex 1.10088 1.67 2.595 + vertex 1.09893 1.66989 2.59438 + vertex 1.1 1.66741 2.595 + endloop + endfacet + facet normal -0.303257 0.0479146 0.951704 + outer loop + vertex 1.10167 1.675 2.595 + vertex 1.09893 1.66989 2.59438 + vertex 1.10088 1.67 2.595 + endloop + endfacet + facet normal -0.0956691 -0.06855 0.99305 + outer loop + vertex 1.09913 1.67457 2.59473 + vertex 1.09893 1.66989 2.59438 + vertex 1.10167 1.675 2.595 + endloop + endfacet + facet normal -0.10997 0.0160538 0.993805 + outer loop + vertex 1.1024 1.68 2.595 + vertex 1.09913 1.67457 2.59473 + vertex 1.10167 1.675 2.595 + endloop + endfacet + facet normal 0.0371698 -0.0726432 0.996665 + outer loop + vertex 1.09944 1.67963 2.59508 + vertex 1.09913 1.67457 2.59473 + vertex 1.1024 1.68 2.595 + endloop + endfacet + facet normal 0.028386 -0.00238496 0.999594 + outer loop + vertex 1.10282 1.685 2.595 + vertex 1.09944 1.67963 2.59508 + vertex 1.1024 1.68 2.595 + endloop + endfacet + facet normal 0.127094 -0.0646526 0.989781 + outer loop + vertex 1.09961 1.68463 2.59539 + vertex 1.09944 1.67963 2.59508 + vertex 1.10282 1.685 2.595 + endloop + endfacet + facet normal 0.121364 -0.0116491 0.99254 + outer loop + vertex 1.1033 1.69 2.595 + vertex 1.09961 1.68463 2.59539 + vertex 1.10282 1.685 2.595 + endloop + endfacet + facet normal 0.17288 -0.0477304 0.983786 + outer loop + vertex 1.09947 1.68866 2.59561 + vertex 1.09961 1.68463 2.59539 + vertex 1.1033 1.69 2.595 + endloop + endfacet + facet normal 0.71698 -0.0851217 0.691877 + outer loop + vertex 1.09947 1.68866 2.59561 + vertex 1.10054 1.69348 2.59509 + vertex 1.09814 1.69053 2.59721 + endloop + endfacet + facet normal 0.129657 0.0781722 0.988473 + outer loop + vertex 1.09947 1.68866 2.59561 + vertex 1.1033 1.69 2.595 + vertex 1.10054 1.69348 2.59509 + endloop + endfacet + facet normal 0.0302891 -0.000848525 0.999541 + outer loop + vertex 1.1033 1.69 2.595 + vertex 1.10344 1.695 2.595 + vertex 1.10054 1.69348 2.59509 + endloop + endfacet + facet normal 0.725045 -0.0991422 0.681529 + outer loop + vertex 1.10054 1.69348 2.59509 + vertex 1.09814 1.69456 2.5978 + vertex 1.09814 1.69053 2.59721 + endloop + endfacet + facet normal 0.0304182 -0.00109509 0.999537 + outer loop + vertex 1.10344 1.695 2.595 + vertex 1.10362 1.7 2.595 + vertex 1.10054 1.69348 2.59509 + endloop + endfacet + facet normal 0.104433 -0.036123 0.993876 + outer loop + vertex 1.10362 1.7 2.595 + vertex 1.1004 1.69883 2.5953 + vertex 1.10054 1.69348 2.59509 + endloop + endfacet + facet normal 0.747404 -0.00573341 0.664345 + outer loop + vertex 1.1004 1.69883 2.5953 + vertex 1.09814 1.69456 2.5978 + vertex 1.10054 1.69348 2.59509 + endloop + endfacet + facet normal 0.796301 -0.0687028 0.600987 + outer loop + vertex 1.09821 1.69942 2.59826 + vertex 1.09814 1.69456 2.5978 + vertex 1.1004 1.69883 2.5953 + endloop + endfacet + facet normal 0.091732 -0.000548953 0.995784 + outer loop + vertex 1.10362 1.7 2.595 + vertex 1.10365 1.705 2.595 + vertex 1.1004 1.69883 2.5953 + endloop + endfacet + facet normal -0.00573146 0.0510162 0.998681 + outer loop + vertex 1.10365 1.705 2.595 + vertex 1.10021 1.70345 2.59506 + vertex 1.1004 1.69883 2.5953 + endloop + endfacet + facet normal 0.809114 0.0618939 0.584383 + outer loop + vertex 1.10021 1.70345 2.59506 + vertex 1.09821 1.69942 2.59826 + vertex 1.1004 1.69883 2.5953 + endloop + endfacet + facet normal 0.875793 -0.0545575 0.479594 + outer loop + vertex 1.09839 1.70431 2.5985 + vertex 1.09821 1.69942 2.59826 + vertex 1.10021 1.70345 2.59506 + endloop + endfacet + facet normal 0.995156 -0.0517473 -0.0835861 + outer loop + vertex 1.10323 1.705 2.59 + vertex 1.10349 1.71 2.59 + vertex 1.10365 1.705 2.595 + endloop + endfacet + facet normal -0.0995812 0.702006 0.705175 + outer loop + vertex 1.10349 1.71 2.59 + vertex 1.10191 1.70795 2.59182 + vertex 1.10365 1.705 2.595 + endloop + endfacet + facet normal -0.270329 0.627966 0.729781 + outer loop + vertex 1.10365 1.705 2.595 + vertex 1.10191 1.70795 2.59182 + vertex 1.10021 1.70345 2.59506 + endloop + endfacet + facet normal 0.860079 0.0409276 0.508516 + outer loop + vertex 1.10191 1.70795 2.59182 + vertex 1.10011 1.70783 2.59489 + vertex 1.10021 1.70345 2.59506 + endloop + endfacet + facet normal 0.88616 0.0397732 0.461669 + outer loop + vertex 1.10011 1.70783 2.59489 + vertex 1.09839 1.70431 2.5985 + vertex 1.10021 1.70345 2.59506 + endloop + endfacet + facet normal 0.919121 -0.0485129 0.390978 + outer loop + vertex 1.09861 1.70922 2.59858 + vertex 1.09839 1.70431 2.5985 + vertex 1.10011 1.70783 2.59489 + endloop + endfacet + facet normal 0.852443 -0.243805 0.462493 + outer loop + vertex 1.10349 1.71 2.59 + vertex 1.10492 1.715 2.59 + vertex 1.10191 1.70795 2.59182 + endloop + endfacet + facet normal 0.483858 0.0197833 0.874923 + outer loop + vertex 1.10492 1.715 2.59 + vertex 1.10163 1.71114 2.5919 + vertex 1.10191 1.70795 2.59182 + endloop + endfacet + facet normal 0.85878 0.0623341 0.508539 + outer loop + vertex 1.10191 1.70795 2.59182 + vertex 1.10163 1.71114 2.5919 + vertex 1.10011 1.70783 2.59489 + endloop + endfacet + facet normal 0.908508 -0.0447391 0.415466 + outer loop + vertex 1.10163 1.71114 2.5919 + vertex 1.10032 1.71241 2.59492 + vertex 1.10011 1.70783 2.59489 + endloop + endfacet + facet normal 0.919734 -0.0450972 0.389943 + outer loop + vertex 1.10032 1.71241 2.59492 + vertex 1.09861 1.70922 2.59858 + vertex 1.10011 1.70783 2.59489 + endloop + endfacet + facet normal 0.918549 -0.0407256 0.393204 + outer loop + vertex 1.09877 1.71426 2.59872 + vertex 1.09861 1.70922 2.59858 + vertex 1.10032 1.71241 2.59492 + endloop + endfacet + facet normal 0.29318 0.24286 0.924697 + outer loop + vertex 1.105 1.71712 2.59 + vertex 1.10407 1.71981 2.58959 + vertex 1.10237 1.71562 2.59123 + endloop + endfacet + facet normal 0.430428 -0.0162403 0.902479 + outer loop + vertex 1.105 1.71712 2.59 + vertex 1.10237 1.71562 2.59123 + vertex 1.10492 1.715 2.59 + endloop + endfacet + facet normal 0.445106 0.0618552 0.893339 + outer loop + vertex 1.10492 1.715 2.59 + vertex 1.10237 1.71562 2.59123 + vertex 1.10163 1.71114 2.5919 + endloop + endfacet + facet normal 0.899899 -0.0834149 0.428047 + outer loop + vertex 1.10163 1.71114 2.5919 + vertex 1.10237 1.71562 2.59123 + vertex 1.10032 1.71241 2.59492 + endloop + endfacet + facet normal 0.893653 -0.0602656 0.444693 + outer loop + vertex 1.10237 1.71562 2.59123 + vertex 1.10049 1.71745 2.59526 + vertex 1.10032 1.71241 2.59492 + endloop + endfacet + facet normal 0.914669 -0.0579825 0.400024 + outer loop + vertex 1.10049 1.71745 2.59526 + vertex 1.09877 1.71426 2.59872 + vertex 1.10032 1.71241 2.59492 + endloop + endfacet + facet normal 0.908722 -0.0378103 0.415686 + outer loop + vertex 1.09879 1.71934 2.59915 + vertex 1.09877 1.71426 2.59872 + vertex 1.10049 1.71745 2.59526 + endloop + endfacet + facet normal 0.786068 -0.150415 0.599561 + outer loop + vertex 1.10407 1.71981 2.58959 + vertex 1.10449 1.72447 2.59019 + vertex 1.10225 1.72076 2.5922 + endloop + endfacet + facet normal 0.801952 -0.093426 0.590037 + outer loop + vertex 1.10237 1.71562 2.59123 + vertex 1.10407 1.71981 2.58959 + vertex 1.10225 1.72076 2.5922 + endloop + endfacet + facet normal 0.892794 -0.0638497 0.445916 + outer loop + vertex 1.10237 1.71562 2.59123 + vertex 1.10225 1.72076 2.5922 + vertex 1.10049 1.71745 2.59526 + endloop + endfacet + facet normal 0.89504 -0.0700988 0.440442 + outer loop + vertex 1.10225 1.72076 2.5922 + vertex 1.10044 1.72297 2.59624 + vertex 1.10049 1.71745 2.59526 + endloop + endfacet + facet normal 0.901666 -0.0676511 0.427108 + outer loop + vertex 1.10044 1.72297 2.59624 + vertex 1.09879 1.71934 2.59915 + vertex 1.10049 1.71745 2.59526 + endloop + endfacet + facet normal 0.890885 -0.0426495 0.452222 + outer loop + vertex 1.09869 1.7234 2.59973 + vertex 1.09879 1.71934 2.59915 + vertex 1.10044 1.72297 2.59624 + endloop + endfacet + facet normal 0.785647 -0.0983699 0.610804 + outer loop + vertex 1.10449 1.72447 2.59019 + vertex 1.10465 1.72842 2.59063 + vertex 1.10245 1.7261 2.59309 + endloop + endfacet + facet normal 0.773171 -0.13129 0.620459 + outer loop + vertex 1.10225 1.72076 2.5922 + vertex 1.10449 1.72447 2.59019 + vertex 1.10245 1.7261 2.59309 + endloop + endfacet + facet normal 0.883426 -0.107999 0.455955 + outer loop + vertex 1.10225 1.72076 2.5922 + vertex 1.10245 1.7261 2.59309 + vertex 1.10044 1.72297 2.59624 + endloop + endfacet + facet normal 0.871607 -0.0710888 0.485023 + outer loop + vertex 1.10245 1.7261 2.59309 + vertex 1.10093 1.72664 2.59589 + vertex 1.10044 1.72297 2.59624 + endloop + endfacet + facet normal 0.850249 -0.0250662 0.525783 + outer loop + vertex 1.09869 1.7234 2.59973 + vertex 1.09944 1.72726 2.5987 + vertex 1.0976 1.7255 2.60159 + endloop + endfacet + facet normal 0.890003 -0.0521481 0.452964 + outer loop + vertex 1.09869 1.7234 2.59973 + vertex 1.10044 1.72297 2.59624 + vertex 1.09944 1.72726 2.5987 + endloop + endfacet + facet normal 0.873903 -0.0718166 0.480765 + outer loop + vertex 1.10044 1.72297 2.59624 + vertex 1.10093 1.72664 2.59589 + vertex 1.09944 1.72726 2.5987 + endloop + endfacet + facet normal 0.840989 0.00938951 0.54097 + outer loop + vertex 1.09944 1.72726 2.5987 + vertex 1.09728 1.72928 2.60202 + vertex 1.0976 1.7255 2.60159 + endloop + endfacet + facet normal 0.773386 -0.0659107 0.6305 + outer loop + vertex 1.10465 1.72842 2.59063 + vertex 1.10349 1.73031 2.59225 + vertex 1.10245 1.7261 2.59309 + endloop + endfacet + facet normal 0.852889 -0.0992646 0.512569 + outer loop + vertex 1.10349 1.73031 2.59225 + vertex 1.10357 1.73439 2.59291 + vertex 1.10152 1.73036 2.59554 + endloop + endfacet + facet normal 0.851952 -0.108917 0.512166 + outer loop + vertex 1.10349 1.73031 2.59225 + vertex 1.10152 1.73036 2.59554 + vertex 1.10245 1.7261 2.59309 + endloop + endfacet + facet normal 0.868522 -0.0910099 0.487223 + outer loop + vertex 1.10245 1.7261 2.59309 + vertex 1.10152 1.73036 2.59554 + vertex 1.10093 1.72664 2.59589 + endloop + endfacet + facet normal 0.870585 -0.0916932 0.483399 + outer loop + vertex 1.10093 1.72664 2.59589 + vertex 1.10152 1.73036 2.59554 + vertex 1.09944 1.72726 2.5987 + endloop + endfacet + facet normal 0.857373 -0.0536911 0.511888 + outer loop + vertex 1.10152 1.73036 2.59554 + vertex 1.09938 1.73237 2.59932 + vertex 1.09944 1.72726 2.5987 + endloop + endfacet + facet normal 0.819496 -0.0611054 0.569818 + outer loop + vertex 1.09938 1.73237 2.59932 + vertex 1.09728 1.72928 2.60202 + vertex 1.09944 1.72726 2.5987 + endloop + endfacet + facet normal 0.77564 0.0218818 0.630797 + outer loop + vertex 1.09667 1.73424 2.60259 + vertex 1.09728 1.72928 2.60202 + vertex 1.09938 1.73237 2.59932 + endloop + endfacet + facet normal 0.85196 -0.0961957 0.514694 + outer loop + vertex 1.10357 1.73439 2.59291 + vertex 1.10367 1.73916 2.59363 + vertex 1.10158 1.73572 2.59645 + endloop + endfacet + facet normal 0.85172 -0.0971424 0.514914 + outer loop + vertex 1.10152 1.73036 2.59554 + vertex 1.10357 1.73439 2.59291 + vertex 1.10158 1.73572 2.59645 + endloop + endfacet + facet normal 0.843308 -0.099323 0.528173 + outer loop + vertex 1.10152 1.73036 2.59554 + vertex 1.10158 1.73572 2.59645 + vertex 1.09938 1.73237 2.59932 + endloop + endfacet + facet normal 0.82977 -0.0684038 0.553898 + outer loop + vertex 1.10158 1.73572 2.59645 + vertex 1.09949 1.73727 2.59977 + vertex 1.09938 1.73237 2.59932 + endloop + endfacet + facet normal 0.745596 -0.0762817 0.662018 + outer loop + vertex 1.09949 1.73727 2.59977 + vertex 1.09667 1.73424 2.60259 + vertex 1.09938 1.73237 2.59932 + endloop + endfacet + facet normal 0.726894 -0.0368051 0.685763 + outer loop + vertex 1.09744 1.73869 2.60202 + vertex 1.09667 1.73424 2.60259 + vertex 1.09949 1.73727 2.59977 + endloop + endfacet + facet normal 0.848794 -0.0962634 0.519887 + outer loop + vertex 1.10367 1.73916 2.59363 + vertex 1.10386 1.74381 2.59418 + vertex 1.10173 1.74069 2.59708 + endloop + endfacet + facet normal 0.85006 -0.0918215 0.51862 + outer loop + vertex 1.10158 1.73572 2.59645 + vertex 1.10367 1.73916 2.59363 + vertex 1.10173 1.74069 2.59708 + endloop + endfacet + facet normal 0.821566 -0.0964066 0.561903 + outer loop + vertex 1.10158 1.73572 2.59645 + vertex 1.10173 1.74069 2.59708 + vertex 1.09949 1.73727 2.59977 + endloop + endfacet + facet normal 0.800966 -0.056104 0.596075 + outer loop + vertex 1.10173 1.74069 2.59708 + vertex 1.09955 1.74179 2.60012 + vertex 1.09949 1.73727 2.59977 + endloop + endfacet + facet normal 0.717606 -0.0627062 0.69362 + outer loop + vertex 1.09955 1.74179 2.60012 + vertex 1.09744 1.73869 2.60202 + vertex 1.09949 1.73727 2.59977 + endloop + endfacet + facet normal 0.652795 0.0203439 0.757261 + outer loop + vertex 1.09681 1.74223 2.60247 + vertex 1.09744 1.73869 2.60202 + vertex 1.09955 1.74179 2.60012 + endloop + endfacet + facet normal 0.827852 -0.109604 0.550135 + outer loop + vertex 1.10386 1.74381 2.59418 + vertex 1.10404 1.74783 2.59472 + vertex 1.10177 1.7459 2.59774 + endloop + endfacet + facet normal 0.840325 -0.0745554 0.536931 + outer loop + vertex 1.10173 1.74069 2.59708 + vertex 1.10386 1.74381 2.59418 + vertex 1.10177 1.7459 2.59774 + endloop + endfacet + facet normal 0.794846 -0.0823515 0.601197 + outer loop + vertex 1.10173 1.74069 2.59708 + vertex 1.10177 1.7459 2.59774 + vertex 1.09955 1.74179 2.60012 + endloop + endfacet + facet normal 0.749347 -0.0226054 0.661791 + outer loop + vertex 1.10177 1.7459 2.59774 + vertex 1.09917 1.74548 2.60068 + vertex 1.09955 1.74179 2.60012 + endloop + endfacet + facet normal 0.645777 -0.0484974 0.761984 + outer loop + vertex 1.09917 1.74548 2.60068 + vertex 1.09681 1.74223 2.60247 + vertex 1.09955 1.74179 2.60012 + endloop + endfacet + facet normal 0.578863 0.0292288 0.814901 + outer loop + vertex 1.09664 1.74662 2.60243 + vertex 1.09681 1.74223 2.60247 + vertex 1.09917 1.74548 2.60068 + endloop + endfacet + facet normal 0.824178 -0.0916219 0.558871 + outer loop + vertex 1.10404 1.74783 2.59472 + vertex 1.1029 1.75021 2.59679 + vertex 1.10177 1.7459 2.59774 + endloop + endfacet + facet normal 0.739893 -0.0565582 0.670343 + outer loop + vertex 1.1029 1.75021 2.59679 + vertex 1.10279 1.75426 2.59725 + vertex 1.10018 1.75016 2.59978 + endloop + endfacet + facet normal 0.740245 -0.0449457 0.670833 + outer loop + vertex 1.1029 1.75021 2.59679 + vertex 1.10018 1.75016 2.59978 + vertex 1.10177 1.7459 2.59774 + endloop + endfacet + facet normal 0.750008 -0.0363544 0.660429 + outer loop + vertex 1.10177 1.7459 2.59774 + vertex 1.10018 1.75016 2.59978 + vertex 1.09917 1.74548 2.60068 + endloop + endfacet + facet normal 0.579189 0.0303721 0.814627 + outer loop + vertex 1.10018 1.75016 2.59978 + vertex 1.09664 1.74662 2.60243 + vertex 1.09917 1.74548 2.60068 + endloop + endfacet + facet normal 0.586506 0.019354 0.809714 + outer loop + vertex 1.0967 1.75147 2.60227 + vertex 1.09664 1.74662 2.60243 + vertex 1.10018 1.75016 2.59978 + endloop + endfacet + facet normal 0.710333 -0.0391905 0.702774 + outer loop + vertex 1.10279 1.75426 2.59725 + vertex 1.10274 1.75925 2.59758 + vertex 1.10007 1.75564 2.60007 + endloop + endfacet + facet normal 0.714708 -0.0228862 0.699048 + outer loop + vertex 1.10018 1.75016 2.59978 + vertex 1.10279 1.75426 2.59725 + vertex 1.10007 1.75564 2.60007 + endloop + endfacet + facet normal 0.573529 -0.0321797 0.818553 + outer loop + vertex 1.10007 1.75564 2.60007 + vertex 1.0967 1.75147 2.60227 + vertex 1.10018 1.75016 2.59978 + endloop + endfacet + facet normal 0.540337 0.00674644 0.841421 + outer loop + vertex 1.09674 1.75652 2.60221 + vertex 1.0967 1.75147 2.60227 + vertex 1.10007 1.75564 2.60007 + endloop + endfacet + facet normal 0.694574 -0.0166829 0.719228 + outer loop + vertex 1.10274 1.75925 2.59758 + vertex 1.10276 1.76425 2.59767 + vertex 1.10012 1.76071 2.60014 + endloop + endfacet + facet normal 0.694669 -0.0163643 0.719144 + outer loop + vertex 1.10007 1.75564 2.60007 + vertex 1.10274 1.75925 2.59758 + vertex 1.10012 1.76071 2.60014 + endloop + endfacet + facet normal 0.535876 -0.0167715 0.84413 + outer loop + vertex 1.10012 1.76071 2.60014 + vertex 1.09674 1.75652 2.60221 + vertex 1.10007 1.75564 2.60007 + endloop + endfacet + facet normal 0.509076 0.0129418 0.860624 + outer loop + vertex 1.09688 1.76158 2.60204 + vertex 1.09674 1.75652 2.60221 + vertex 1.10012 1.76071 2.60014 + endloop + endfacet + facet normal 0.683366 0.00178968 0.730074 + outer loop + vertex 1.10276 1.76425 2.59767 + vertex 1.10274 1.76922 2.59768 + vertex 1.1002 1.76572 2.60007 + endloop + endfacet + facet normal 0.682825 1.07992e-05 0.730582 + outer loop + vertex 1.10012 1.76071 2.60014 + vertex 1.10276 1.76425 2.59767 + vertex 1.1002 1.76572 2.60007 + endloop + endfacet + facet normal 0.507446 0.00463637 0.861671 + outer loop + vertex 1.1002 1.76572 2.60007 + vertex 1.09688 1.76158 2.60204 + vertex 1.10012 1.76071 2.60014 + endloop + endfacet + facet normal 0.486703 0.0267428 0.873158 + outer loop + vertex 1.09702 1.7667 2.60181 + vertex 1.09688 1.76158 2.60204 + vertex 1.1002 1.76572 2.60007 + endloop + endfacet + facet normal 0.669275 0.00985589 0.742949 + outer loop + vertex 1.10274 1.76922 2.59768 + vertex 1.10251 1.77421 2.59782 + vertex 1.10014 1.77074 2.6 + endloop + endfacet + facet normal 0.671678 0.0174953 0.740636 + outer loop + vertex 1.1002 1.76572 2.60007 + vertex 1.10274 1.76922 2.59768 + vertex 1.10014 1.77074 2.6 + endloop + endfacet + facet normal 0.484556 0.0173052 0.874589 + outer loop + vertex 1.10014 1.77074 2.6 + vertex 1.09702 1.7667 2.60181 + vertex 1.1002 1.76572 2.60007 + endloop + endfacet + facet normal 0.444557 0.0568708 0.893943 + outer loop + vertex 1.09684 1.77182 2.60157 + vertex 1.09702 1.7667 2.60181 + vertex 1.10014 1.77074 2.6 + endloop + endfacet + facet normal 0.623847 0.0246113 0.781159 + outer loop + vertex 1.10251 1.77421 2.59782 + vertex 1.10182 1.77943 2.59821 + vertex 1.09967 1.77565 2.60005 + endloop + endfacet + facet normal 0.632222 0.0539818 0.772905 + outer loop + vertex 1.10014 1.77074 2.6 + vertex 1.10251 1.77421 2.59782 + vertex 1.09967 1.77565 2.60005 + endloop + endfacet + facet normal 0.439035 0.0342967 0.897815 + outer loop + vertex 1.09967 1.77565 2.60005 + vertex 1.09684 1.77182 2.60157 + vertex 1.10014 1.77074 2.6 + endloop + endfacet + facet normal 0.369221 0.0962864 0.92434 + outer loop + vertex 1.09593 1.777 2.6014 + vertex 1.09684 1.77182 2.60157 + vertex 1.09967 1.77565 2.60005 + endloop + endfacet + facet normal 0.561993 0.0804389 0.823221 + outer loop + vertex 1.09883 1.7796 2.60023 + vertex 1.09967 1.77565 2.60005 + vertex 1.10182 1.77943 2.59821 + endloop + endfacet + facet normal 0.561726 0.102431 0.820958 + outer loop + vertex 1.09883 1.7796 2.60023 + vertex 1.10182 1.77943 2.59821 + vertex 1.09897 1.78395 2.5996 + endloop + endfacet + facet normal 0.512545 0.0604176 0.856532 + outer loop + vertex 1.09897 1.78395 2.5996 + vertex 1.10182 1.77943 2.59821 + vertex 1.10262 1.78347 2.59745 + endloop + endfacet + facet normal 0.349673 0.0300333 0.93639 + outer loop + vertex 1.09967 1.77565 2.60005 + vertex 1.09883 1.7796 2.60023 + vertex 1.09593 1.777 2.6014 + endloop + endfacet + facet normal 0.508031 0.00381934 0.861331 + outer loop + vertex 1.10262 1.78347 2.59745 + vertex 1.10224 1.78725 2.59765 + vertex 1.09897 1.78395 2.5996 + endloop + endfacet + facet normal 0.475487 0.0462202 0.878507 + outer loop + vertex 1.09897 1.78395 2.5996 + vertex 1.10224 1.78725 2.59765 + vertex 1.09926 1.78856 2.5992 + endloop + endfacet + facet normal 0.464825 0.0140024 0.885292 + outer loop + vertex 1.10224 1.78725 2.59765 + vertex 1.10197 1.79172 2.59772 + vertex 1.09926 1.78856 2.5992 + endloop + endfacet + facet normal 0.368329 0.114389 0.922631 + outer loop + vertex 1.09926 1.78856 2.5992 + vertex 1.10197 1.79172 2.59772 + vertex 1.0982 1.7923 2.59916 + endloop + endfacet + facet normal 0.361223 0.0456916 0.931359 + outer loop + vertex 1.10197 1.79172 2.59772 + vertex 1.10178 1.79641 2.59756 + vertex 1.0982 1.7923 2.59916 + endloop + endfacet + facet normal 0.285735 0.119105 0.950878 + outer loop + vertex 1.0982 1.7923 2.59916 + vertex 1.10178 1.79641 2.59756 + vertex 1.0978 1.79695 2.59869 + endloop + endfacet + facet normal 0.281825 0.0791858 0.956193 + outer loop + vertex 1.10178 1.79641 2.59756 + vertex 1.1018 1.80137 2.59715 + vertex 1.0978 1.79695 2.59869 + endloop + endfacet + facet normal 0.233795 0.125356 0.964171 + outer loop + vertex 1.0978 1.79695 2.59869 + vertex 1.1018 1.80137 2.59715 + vertex 1.09775 1.80187 2.59806 + endloop + endfacet + facet normal 0.230816 0.0935473 0.96849 + outer loop + vertex 1.1018 1.80137 2.59715 + vertex 1.10166 1.80631 2.59671 + vertex 1.09775 1.80187 2.59806 + endloop + endfacet + facet normal 0.158063 0.190901 0.9688 + outer loop + vertex 1.10109 1.95507 2.57079 + vertex 1.09666 1.95458 2.57161 + vertex 1.10118 1.95025 2.57173 + endloop + endfacet + facet normal 0.157925 0.191865 0.968632 + outer loop + vertex 1.10109 1.95507 2.57079 + vertex 1.09938 1.9581 2.57047 + vertex 1.09666 1.95458 2.57161 + endloop + endfacet + facet normal 0.239235 0.15606 0.958338 + outer loop + vertex 1.09924 1.99347 2.56386 + vertex 1.10154 1.99576 2.56291 + vertex 1.09796 1.9972 2.56357 + endloop + endfacet + facet normal 0.237384 0.150843 0.959633 + outer loop + vertex 1.10154 1.99576 2.56291 + vertex 1.10157 2.00063 2.56214 + vertex 1.09796 1.9972 2.56357 + endloop + endfacet + facet normal 0.258663 0.12755 0.95751 + outer loop + vertex 1.09796 1.9972 2.56357 + vertex 1.10157 2.00063 2.56214 + vertex 1.09682 2.00103 2.56337 + endloop + endfacet + facet normal 0.249726 0.141476 0.957926 + outer loop + vertex 1.10482 2.00369 2.56081 + vertex 1.10549 2.00816 2.55997 + vertex 1.102 2.00563 2.56126 + endloop + endfacet + facet normal 0.25295 0.146504 0.956322 + outer loop + vertex 1.102 2.00563 2.56126 + vertex 1.10157 2.00063 2.56214 + vertex 1.10482 2.00369 2.56081 + endloop + endfacet + facet normal 0.286941 0.142036 0.94736 + outer loop + vertex 1.102 2.00563 2.56126 + vertex 1.09781 2.00568 2.56252 + vertex 1.10157 2.00063 2.56214 + endloop + endfacet + facet normal 0.258304 0.119862 0.958599 + outer loop + vertex 1.09781 2.00568 2.56252 + vertex 1.09682 2.00103 2.56337 + vertex 1.10157 2.00063 2.56214 + endloop + endfacet + facet normal 0.272773 0.141542 0.95161 + outer loop + vertex 1.10549 2.00816 2.55997 + vertex 1.10404 2.01338 2.55961 + vertex 1.10099 2.00985 2.56101 + endloop + endfacet + facet normal 0.265534 0.119023 0.956726 + outer loop + vertex 1.102 2.00563 2.56126 + vertex 1.10549 2.00816 2.55997 + vertex 1.10099 2.00985 2.56101 + endloop + endfacet + facet normal 0.287474 0.123876 0.949744 + outer loop + vertex 1.10099 2.00985 2.56101 + vertex 1.09781 2.00568 2.56252 + vertex 1.102 2.00563 2.56126 + endloop + endfacet + facet normal 0.307511 0.107086 0.9455 + outer loop + vertex 1.097 2.01126 2.56215 + vertex 1.09781 2.00568 2.56252 + vertex 1.10099 2.00985 2.56101 + endloop + endfacet + facet normal 0.303621 0.130414 0.943826 + outer loop + vertex 1.10404 2.01338 2.55961 + vertex 1.10305 2.01862 2.55921 + vertex 1.10003 2.01477 2.56071 + endloop + endfacet + facet normal 0.299634 0.116474 0.946918 + outer loop + vertex 1.10099 2.00985 2.56101 + vertex 1.10404 2.01338 2.55961 + vertex 1.10003 2.01477 2.56071 + endloop + endfacet + facet normal 0.310817 0.11842 0.943064 + outer loop + vertex 1.10003 2.01477 2.56071 + vertex 1.097 2.01126 2.56215 + vertex 1.10099 2.00985 2.56101 + endloop + endfacet + facet normal 0.322809 0.106989 0.940398 + outer loop + vertex 1.0959 2.01655 2.56193 + vertex 1.097 2.01126 2.56215 + vertex 1.10003 2.01477 2.56071 + endloop + endfacet + facet normal 0.317922 0.118006 0.940744 + outer loop + vertex 1.09916 2.01879 2.5605 + vertex 1.10003 2.01477 2.56071 + vertex 1.10305 2.01862 2.55921 + endloop + endfacet + facet normal 0.317924 0.126683 0.939615 + outer loop + vertex 1.09916 2.01879 2.5605 + vertex 1.10305 2.01862 2.55921 + vertex 1.09989 2.02302 2.55968 + endloop + endfacet + facet normal 0.322783 0.130396 0.937448 + outer loop + vertex 1.09989 2.02302 2.55968 + vertex 1.10305 2.01862 2.55921 + vertex 1.10378 2.02305 2.55834 + endloop + endfacet + facet normal 0.32742 0.119865 0.937245 + outer loop + vertex 1.10003 2.01477 2.56071 + vertex 1.09916 2.01879 2.5605 + vertex 1.0959 2.01655 2.56193 + endloop + endfacet + facet normal 0.322634 0.133328 0.937086 + outer loop + vertex 1.10378 2.02305 2.55834 + vertex 1.10225 2.02635 2.5584 + vertex 1.09989 2.02302 2.55968 + endloop + endfacet + facet normal 0.331279 0.126417 0.935026 + outer loop + vertex 1.09989 2.02302 2.55968 + vertex 1.10225 2.02635 2.5584 + vertex 1.09853 2.02861 2.55941 + endloop + endfacet + facet normal 0.33163 0.127091 0.93481 + outer loop + vertex 1.10225 2.02635 2.5584 + vertex 1.10299 2.03083 2.55753 + vertex 1.09853 2.02861 2.55941 + endloop + endfacet + facet normal 0.330967 0.128461 0.934858 + outer loop + vertex 1.09853 2.02861 2.55941 + vertex 1.10299 2.03083 2.55753 + vertex 1.09934 2.03316 2.5585 + endloop + endfacet + facet normal 0.331968 0.130281 0.934251 + outer loop + vertex 1.10299 2.03083 2.55753 + vertex 1.10198 2.03613 2.55715 + vertex 1.09934 2.03316 2.5585 + endloop + endfacet + facet normal 0.33545 0.126827 0.933482 + outer loop + vertex 1.09934 2.03316 2.5585 + vertex 1.10198 2.03613 2.55715 + vertex 1.09806 2.03722 2.55841 + endloop + endfacet + facet normal 0.33659 0.132271 0.932315 + outer loop + vertex 1.10198 2.03613 2.55715 + vertex 1.1007 2.04136 2.55687 + vertex 1.09806 2.03722 2.55841 + endloop + endfacet + facet normal 0.346637 0.124878 0.92965 + outer loop + vertex 1.09806 2.03722 2.55841 + vertex 1.1007 2.04136 2.55687 + vertex 1.09689 2.04121 2.55831 + endloop + endfacet + facet normal 0.337719 0.136125 0.931352 + outer loop + vertex 1.10396 2.04361 2.55536 + vertex 1.10478 2.04779 2.55445 + vertex 1.1015 2.04574 2.55594 + endloop + endfacet + facet normal 0.336821 0.134954 0.931847 + outer loop + vertex 1.1015 2.04574 2.55594 + vertex 1.1007 2.04136 2.55687 + vertex 1.10396 2.04361 2.55536 + endloop + endfacet + facet normal 0.359287 0.129239 0.924235 + outer loop + vertex 1.1015 2.04574 2.55594 + vertex 1.09757 2.04594 2.55744 + vertex 1.1007 2.04136 2.55687 + endloop + endfacet + facet normal 0.347012 0.120113 0.930137 + outer loop + vertex 1.09757 2.04594 2.55744 + vertex 1.09689 2.04121 2.55831 + vertex 1.1007 2.04136 2.55687 + endloop + endfacet + facet normal 0.346657 0.134879 0.928244 + outer loop + vertex 1.10478 2.04779 2.55445 + vertex 1.10336 2.05359 2.55414 + vertex 1.10044 2.04984 2.55578 + endloop + endfacet + facet normal 0.343403 0.126489 0.930632 + outer loop + vertex 1.1015 2.04574 2.55594 + vertex 1.10478 2.04779 2.55445 + vertex 1.10044 2.04984 2.55578 + endloop + endfacet + facet normal 0.359284 0.130321 0.924084 + outer loop + vertex 1.10044 2.04984 2.55578 + vertex 1.09757 2.04594 2.55744 + vertex 1.1015 2.04574 2.55594 + endloop + endfacet + facet normal 0.382208 0.110614 0.917432 + outer loop + vertex 1.09618 2.052 2.55729 + vertex 1.09757 2.04594 2.55744 + vertex 1.10044 2.04984 2.55578 + endloop + endfacet + facet normal 0.358506 0.124357 0.925207 + outer loop + vertex 1.09938 2.05394 2.55564 + vertex 1.10044 2.04984 2.55578 + vertex 1.10336 2.05359 2.55414 + endloop + endfacet + facet normal 0.358449 0.122577 0.925467 + outer loop + vertex 1.09938 2.05394 2.55564 + vertex 1.10336 2.05359 2.55414 + vertex 1.10016 2.05806 2.55479 + endloop + endfacet + facet normal 0.367557 0.12974 0.920907 + outer loop + vertex 1.10016 2.05806 2.55479 + vertex 1.10336 2.05359 2.55414 + vertex 1.10371 2.05816 2.55336 + endloop + endfacet + facet normal 0.390828 0.132263 0.910912 + outer loop + vertex 1.10044 2.04984 2.55578 + vertex 1.09938 2.05394 2.55564 + vertex 1.09618 2.052 2.55729 + endloop + endfacet + facet normal 0.367401 0.131875 0.920666 + outer loop + vertex 1.10371 2.05816 2.55336 + vertex 1.10233 2.06132 2.55346 + vertex 1.10016 2.05806 2.55479 + endloop + endfacet + facet normal 0.388238 0.115379 0.914308 + outer loop + vertex 1.10016 2.05806 2.55479 + vertex 1.10233 2.06132 2.55346 + vertex 1.0993 2.06312 2.55452 + endloop + endfacet + facet normal 0.390962 0.121078 0.912408 + outer loop + vertex 1.10233 2.06132 2.55346 + vertex 1.10276 2.06594 2.55266 + vertex 1.0993 2.06312 2.55452 + endloop + endfacet + facet normal 0.398459 0.110594 0.910494 + outer loop + vertex 1.0993 2.06312 2.55452 + vertex 1.10276 2.06594 2.55266 + vertex 1.09853 2.06818 2.55424 + endloop + endfacet + facet normal 0.407829 0.133369 0.903265 + outer loop + vertex 1.10276 2.06594 2.55266 + vertex 1.10136 2.072 2.5524 + vertex 1.09853 2.06818 2.55424 + endloop + endfacet + facet normal 0.429767 0.113457 0.895783 + outer loop + vertex 1.09853 2.06818 2.55424 + vertex 1.10136 2.072 2.5524 + vertex 1.09718 2.07312 2.55426 + endloop + endfacet + facet normal 0.394164 0.125169 0.910477 + outer loop + vertex 1.10446 2.07388 2.55073 + vertex 1.10524 2.07799 2.54983 + vertex 1.10227 2.07617 2.55136 + endloop + endfacet + facet normal 0.403382 0.135493 0.904945 + outer loop + vertex 1.10227 2.07617 2.55136 + vertex 1.10136 2.072 2.5524 + vertex 1.10446 2.07388 2.55073 + endloop + endfacet + facet normal 0.434309 0.125524 0.891975 + outer loop + vertex 1.10227 2.07617 2.55136 + vertex 1.09918 2.07685 2.55277 + vertex 1.10136 2.072 2.5524 + endloop + endfacet + facet normal 0.431615 0.124199 0.893467 + outer loop + vertex 1.09918 2.07685 2.55277 + vertex 1.09718 2.07312 2.55426 + vertex 1.10136 2.072 2.5524 + endloop + endfacet + facet normal 0.40899 0.117013 0.905006 + outer loop + vertex 1.10524 2.07799 2.54983 + vertex 1.10435 2.08306 2.54958 + vertex 1.10156 2.08011 2.55122 + endloop + endfacet + facet normal 0.404341 0.106773 0.908355 + outer loop + vertex 1.10227 2.07617 2.55136 + vertex 1.10524 2.07799 2.54983 + vertex 1.10156 2.08011 2.55122 + endloop + endfacet + facet normal 0.432455 0.111351 0.894753 + outer loop + vertex 1.10156 2.08011 2.55122 + vertex 1.09918 2.07685 2.55277 + vertex 1.10227 2.07617 2.55136 + endloop + endfacet + facet normal 0.430104 0.11348 0.895619 + outer loop + vertex 1.09787 2.08169 2.55279 + vertex 1.09918 2.07685 2.55277 + vertex 1.10156 2.08011 2.55122 + endloop + endfacet + facet normal 0.421527 0.113145 0.899729 + outer loop + vertex 1.10435 2.08306 2.54958 + vertex 1.10356 2.08811 2.54931 + vertex 1.10073 2.08487 2.55104 + endloop + endfacet + facet normal 0.418799 0.105951 0.901877 + outer loop + vertex 1.10156 2.08011 2.55122 + vertex 1.10435 2.08306 2.54958 + vertex 1.10073 2.08487 2.55104 + endloop + endfacet + facet normal 0.428217 0.107426 0.897268 + outer loop + vertex 1.10073 2.08487 2.55104 + vertex 1.09787 2.08169 2.55279 + vertex 1.10156 2.08011 2.55122 + endloop + endfacet + facet normal 0.412675 0.124244 0.902365 + outer loop + vertex 1.09702 2.08661 2.5525 + vertex 1.09787 2.08169 2.55279 + vertex 1.10073 2.08487 2.55104 + endloop + endfacet + facet normal 0.41554 0.135415 0.899438 + outer loop + vertex 1.10356 2.08811 2.54931 + vertex 1.10204 2.09307 2.54927 + vertex 1.09978 2.08962 2.55083 + endloop + endfacet + facet normal 0.411998 0.12312 0.902828 + outer loop + vertex 1.10073 2.08487 2.55104 + vertex 1.10356 2.08811 2.54931 + vertex 1.09978 2.08962 2.55083 + endloop + endfacet + facet normal 0.412296 0.123173 0.902685 + outer loop + vertex 1.09978 2.08962 2.55083 + vertex 1.09702 2.08661 2.5525 + vertex 1.10073 2.08487 2.55104 + endloop + endfacet + facet normal 0.376969 0.1608 0.912161 + outer loop + vertex 1.09582 2.09155 2.55213 + vertex 1.09702 2.08661 2.5525 + vertex 1.09978 2.08962 2.55083 + endloop + endfacet + facet normal 0.395837 0.151193 0.905789 + outer loop + vertex 1.09876 2.09358 2.55062 + vertex 1.09978 2.08962 2.55083 + vertex 1.10204 2.09307 2.54927 + endloop + endfacet + facet normal 0.397983 0.183391 0.898875 + outer loop + vertex 1.09876 2.09358 2.55062 + vertex 1.10204 2.09307 2.54927 + vertex 1.09911 2.09823 2.54951 + endloop + endfacet + facet normal 0.368155 0.165711 0.914878 + outer loop + vertex 1.09911 2.09823 2.54951 + vertex 1.10204 2.09307 2.54927 + vertex 1.10404 2.09686 2.54778 + endloop + endfacet + facet normal 0.371116 0.145485 0.917119 + outer loop + vertex 1.09978 2.08962 2.55083 + vertex 1.09876 2.09358 2.55062 + vertex 1.09582 2.09155 2.55213 + endloop + endfacet + facet normal 0.365436 0.151405 0.918441 + outer loop + vertex 1.10404 2.09686 2.54778 + vertex 1.10256 2.10156 2.54759 + vertex 1.09911 2.09823 2.54951 + endloop + endfacet + facet normal 0.325008 0.225155 0.918518 + outer loop + vertex 1.10388 2.1087 2.54575 + vertex 1.10388 2.11323 2.54464 + vertex 1.10112 2.11055 2.54627 + endloop + endfacet + facet normal 0.310907 0.201263 0.928887 + outer loop + vertex 1.10112 2.11055 2.54627 + vertex 1.10094 2.10652 2.54721 + vertex 1.10388 2.1087 2.54575 + endloop + endfacet + facet normal 0.255202 0.20731 0.944402 + outer loop + vertex 1.10112 2.11055 2.54627 + vertex 1.09674 2.11082 2.5474 + vertex 1.10094 2.10652 2.54721 + endloop + endfacet + facet normal 0.288383 0.264166 0.920354 + outer loop + vertex 1.09946 2.11355 2.54593 + vertex 1.10112 2.11055 2.54627 + vertex 1.10388 2.11323 2.54464 + endloop + endfacet + facet normal 0.286882 0.336395 0.89696 + outer loop + vertex 1.09946 2.11355 2.54593 + vertex 1.10388 2.11323 2.54464 + vertex 1.09883 2.1178 2.54454 + endloop + endfacet + facet normal 0.225287 0.269179 0.93637 + outer loop + vertex 1.09883 2.1178 2.54454 + vertex 1.10388 2.11323 2.54464 + vertex 1.10381 2.11785 2.54333 + endloop + endfacet + facet normal 0.255121 0.247428 0.934715 + outer loop + vertex 1.10112 2.11055 2.54627 + vertex 1.09946 2.11355 2.54593 + vertex 1.09674 2.11082 2.5474 + endloop + endfacet + facet normal 0.215596 0.375702 0.901314 + outer loop + vertex 1.10381 2.11785 2.54333 + vertex 1.10181 2.12106 2.54247 + vertex 1.09883 2.1178 2.54454 + endloop + endfacet + facet normal 0.152897 0.426641 0.891403 + outer loop + vertex 1.09883 2.1178 2.54454 + vertex 1.10181 2.12106 2.54247 + vertex 1.09775 2.12171 2.54285 + endloop + endfacet + facet normal 0.121694 0.773319 0.622228 + outer loop + vertex 1.0996 2.12382 2.54087 + vertex 1.10412 2.12362 2.54024 + vertex 1.10145 2.12574 2.53812 + endloop + endfacet + facet normal 0.0446445 0.804512 0.592256 + outer loop + vertex 1.09667 2.12575 2.53847 + vertex 1.0996 2.12382 2.54087 + vertex 1.10145 2.12574 2.53812 + endloop + endfacet + facet normal 0.169665 0.591055 0.788586 + outer loop + vertex 1.10181 2.12106 2.54247 + vertex 1.0996 2.12382 2.54087 + vertex 1.09775 2.12171 2.54285 + endloop + endfacet + facet normal 0.138671 0.576081 0.805544 + outer loop + vertex 1.10412 2.12362 2.54024 + vertex 1.0996 2.12382 2.54087 + vertex 1.10181 2.12106 2.54247 + endloop + endfacet + facet normal -0.070803 0.49167 0.867898 + outer loop + vertex 1.105 2.13343 2.525 + vertex 1.1 2.13271 2.525 + vertex 1.1039 2.13003 2.52683 + endloop + endfacet + facet normal 0.0258441 0.590504 0.806621 + outer loop + vertex 1.1039 2.13003 2.52683 + vertex 1.1 2.13271 2.525 + vertex 1.09923 2.12979 2.52716 + endloop + endfacet + facet normal -0.022288 0.926064 0.376707 + outer loop + vertex 1.1039 2.13003 2.52683 + vertex 1.09923 2.12979 2.52716 + vertex 1.10358 2.12848 2.53064 + endloop + endfacet + facet normal 0.00029555 0.935951 0.35213 + outer loop + vertex 1.10358 2.12848 2.53064 + vertex 1.09923 2.12979 2.52716 + vertex 1.09871 2.12833 2.53104 + endloop + endfacet + facet normal -0.00564221 0.957437 0.288586 + outer loop + vertex 1.10358 2.12848 2.53064 + vertex 1.09871 2.12833 2.53104 + vertex 1.1029 2.12726 2.53467 + endloop + endfacet + facet normal 0.00221719 0.959923 0.280255 + outer loop + vertex 1.1029 2.12726 2.53467 + vertex 1.09871 2.12833 2.53104 + vertex 1.09795 2.12717 2.53502 + endloop + endfacet + facet normal 0.0301364 0.920675 0.389165 + outer loop + vertex 1.10145 2.12574 2.53812 + vertex 1.09795 2.12717 2.53502 + vertex 1.09667 2.12575 2.53847 + endloop + endfacet + facet normal 0.0117766 0.913541 0.406575 + outer loop + vertex 1.1029 2.12726 2.53467 + vertex 1.09795 2.12717 2.53502 + vertex 1.10145 2.12574 2.53812 + endloop + endfacet + facet normal -0.209074 -0.799817 -0.562655 + outer loop + vertex 1.11 0.893149 2.525 + vertex 1.1071 0.893594 2.52545 + vertex 1.105 0.894456 2.525 + endloop + endfacet + facet normal -0.025937 -0.509056 -0.860343 + outer loop + vertex 1.1071 0.893594 2.52545 + vertex 1.10268 0.893721 2.5255 + vertex 1.105 0.894456 2.525 + endloop + endfacet + facet normal -0.0246069 -0.967365 0.252191 + outer loop + vertex 1.1071 0.893594 2.52545 + vertex 1.10498 0.894305 2.52797 + vertex 1.10268 0.893721 2.5255 + endloop + endfacet + facet normal 0.00712205 -0.960859 0.276946 + outer loop + vertex 1.10973 0.894405 2.52819 + vertex 1.10498 0.894305 2.52797 + vertex 1.1071 0.893594 2.52545 + endloop + endfacet + facet normal -0.000456907 -0.910503 0.413501 + outer loop + vertex 1.10498 0.894305 2.52797 + vertex 1.10973 0.894405 2.52819 + vertex 1.10685 0.895999 2.5317 + endloop + endfacet + facet normal 0.0610024 -0.919995 0.387152 + outer loop + vertex 1.10199 0.895083 2.53029 + vertex 1.10498 0.894305 2.52797 + vertex 1.10685 0.895999 2.5317 + endloop + endfacet + facet normal 0.0802389 -0.870652 0.485311 + outer loop + vertex 1.10608 0.897868 2.53518 + vertex 1.10685 0.895999 2.5317 + vertex 1.11001 0.897872 2.53454 + endloop + endfacet + facet normal 0.073242 -0.871789 0.484375 + outer loop + vertex 1.10608 0.897868 2.53518 + vertex 1.10195 0.896969 2.53419 + vertex 1.10685 0.895999 2.5317 + endloop + endfacet + facet normal 0.0430161 -0.899165 0.43549 + outer loop + vertex 1.10195 0.896969 2.53419 + vertex 1.10199 0.895083 2.53029 + vertex 1.10685 0.895999 2.5317 + endloop + endfacet + facet normal 0.0650975 -0.859432 0.507088 + outer loop + vertex 1.10608 0.897868 2.53518 + vertex 1.10362 0.898901 2.53725 + vertex 1.10195 0.896969 2.53419 + endloop + endfacet + facet normal 0.0938233 -0.81716 0.568723 + outer loop + vertex 1.11001 0.897872 2.53454 + vertex 1.10764 0.899942 2.5379 + vertex 1.10608 0.897868 2.53518 + endloop + endfacet + facet normal 0.122209 -0.82203 0.556176 + outer loop + vertex 1.10362 0.898901 2.53725 + vertex 1.10608 0.897868 2.53518 + vertex 1.10764 0.899942 2.5379 + endloop + endfacet + facet normal 0.105245 -0.788264 0.606271 + outer loop + vertex 1.10362 0.898901 2.53725 + vertex 1.10764 0.899942 2.5379 + vertex 1.10293 0.901319 2.54051 + endloop + endfacet + facet normal 0.157925 -0.726532 0.668738 + outer loop + vertex 1.10293 0.901319 2.54051 + vertex 1.10764 0.899942 2.5379 + vertex 1.10735 0.902514 2.54077 + endloop + endfacet + facet normal 0.118404 -0.605623 0.786894 + outer loop + vertex 1.10735 0.902514 2.54077 + vertex 1.10546 0.904911 2.54289 + vertex 1.10293 0.901319 2.54051 + endloop + endfacet + facet normal 0.228141 -0.539966 0.810178 + outer loop + vertex 1.10969 0.905136 2.54185 + vertex 1.10546 0.904911 2.54289 + vertex 1.10735 0.902514 2.54077 + endloop + endfacet + facet normal 0.241457 -0.348446 0.905695 + outer loop + vertex 1.10969 0.905136 2.54185 + vertex 1.10896 0.908878 2.54349 + vertex 1.10546 0.904911 2.54289 + endloop + endfacet + facet normal 0.308643 -0.401213 0.86242 + outer loop + vertex 1.10546 0.904911 2.54289 + vertex 1.10896 0.908878 2.54349 + vertex 1.1044 0.908679 2.54503 + endloop + endfacet + facet normal 0.364239 -0.306182 0.879535 + outer loop + vertex 1.10508 0.912347 2.54602 + vertex 1.10244 0.910354 2.54642 + vertex 1.1044 0.908679 2.54503 + endloop + endfacet + facet normal 0.39379 -0.308055 0.866044 + outer loop + vertex 1.10508 0.912347 2.54602 + vertex 1.1044 0.908679 2.54503 + vertex 1.1087 0.91365 2.54484 + endloop + endfacet + facet normal 0.319777 -0.242032 0.916058 + outer loop + vertex 1.1087 0.91365 2.54484 + vertex 1.1044 0.908679 2.54503 + vertex 1.10896 0.908878 2.54349 + endloop + endfacet + facet normal 0.304641 -0.217423 0.927319 + outer loop + vertex 1.10508 0.912347 2.54602 + vertex 1.10318 0.914143 2.54707 + vertex 1.10244 0.910354 2.54642 + endloop + endfacet + facet normal 0.372419 -0.215341 0.902736 + outer loop + vertex 1.1087 0.91365 2.54484 + vertex 1.10667 0.915334 2.54608 + vertex 1.10508 0.912347 2.54602 + endloop + endfacet + facet normal 0.327541 -0.191884 0.925147 + outer loop + vertex 1.10667 0.915334 2.54608 + vertex 1.10318 0.914143 2.54707 + vertex 1.10508 0.912347 2.54602 + endloop + endfacet + facet normal 0.320667 -0.165496 0.932622 + outer loop + vertex 1.10667 0.915334 2.54608 + vertex 1.10678 0.918616 2.54662 + vertex 1.10318 0.914143 2.54707 + endloop + endfacet + facet normal 0.344549 -0.185962 0.920165 + outer loop + vertex 1.10678 0.918616 2.54662 + vertex 1.10308 0.918902 2.54807 + vertex 1.10318 0.914143 2.54707 + endloop + endfacet + facet normal 0.259432 -0.150783 0.953918 + outer loop + vertex 1.10384 1.01909 2.56365 + vertex 1.10847 1.02369 2.56312 + vertex 1.10354 1.02423 2.56455 + endloop + endfacet + facet normal 0.207254 -0.157344 0.965551 + outer loop + vertex 1.10443 1.02952 2.56513 + vertex 1.10853 1.03391 2.56497 + vertex 1.10464 1.03297 2.56565 + endloop + endfacet + facet normal 0.159965 -0.172508 0.971932 + outer loop + vertex 1.10278 1.16955 2.59115 + vertex 1.10366 1.16722 2.59059 + vertex 1.1062 1.17131 2.5909 + endloop + endfacet + facet normal 0.166415 -0.141649 0.975829 + outer loop + vertex 1.10775 1.17481 2.59115 + vertex 1.10376 1.17351 2.59164 + vertex 1.1062 1.17131 2.5909 + endloop + endfacet + facet normal 0.37848 -0.0632465 0.923446 + outer loop + vertex 1.10378 1.20377 2.59476 + vertex 1.10743 1.20783 2.59354 + vertex 1.10372 1.20867 2.59512 + endloop + endfacet + facet normal 0.281886 -0.0972458 0.954507 + outer loop + vertex 1.10412 1.21265 2.59541 + vertex 1.1018 1.21035 2.59586 + vertex 1.10372 1.20867 2.59512 + endloop + endfacet + facet normal 0.451562 -0.109341 0.885515 + outer loop + vertex 1.10412 1.21265 2.59541 + vertex 1.10372 1.20867 2.59512 + vertex 1.10731 1.21343 2.59388 + endloop + endfacet + facet normal 0.381978 -0.0470737 0.922972 + outer loop + vertex 1.10731 1.21343 2.59388 + vertex 1.10372 1.20867 2.59512 + vertex 1.10743 1.20783 2.59354 + endloop + endfacet + facet normal 0.270904 -0.0852588 0.958823 + outer loop + vertex 1.10412 1.21265 2.59541 + vertex 1.10176 1.21344 2.59615 + vertex 1.1018 1.21035 2.59586 + endloop + endfacet + facet normal 0.510645 -0.0347897 0.859088 + outer loop + vertex 1.10731 1.21343 2.59388 + vertex 1.10816 1.2192 2.59361 + vertex 1.10506 1.21651 2.59534 + endloop + endfacet + facet normal 0.449168 -0.0936094 0.88853 + outer loop + vertex 1.10412 1.21265 2.59541 + vertex 1.10731 1.21343 2.59388 + vertex 1.10506 1.21651 2.59534 + endloop + endfacet + facet normal 0.281851 -0.0517324 0.958063 + outer loop + vertex 1.10506 1.21651 2.59534 + vertex 1.10176 1.21344 2.59615 + vertex 1.10412 1.21265 2.59541 + endloop + endfacet + facet normal 0.313625 -0.0892545 0.945343 + outer loop + vertex 1.10203 1.21779 2.59647 + vertex 1.10176 1.21344 2.59615 + vertex 1.10506 1.21651 2.59534 + endloop + endfacet + facet normal 0.568632 0.00565051 0.822573 + outer loop + vertex 1.10816 1.2192 2.59361 + vertex 1.10841 1.22448 2.5934 + vertex 1.1055 1.22136 2.59543 + endloop + endfacet + facet normal 0.528783 -0.0638204 0.846354 + outer loop + vertex 1.10506 1.21651 2.59534 + vertex 1.10816 1.2192 2.59361 + vertex 1.1055 1.22136 2.59543 + endloop + endfacet + facet normal 0.330256 -0.0477765 0.942682 + outer loop + vertex 1.1055 1.22136 2.59543 + vertex 1.10203 1.21779 2.59647 + vertex 1.10506 1.21651 2.59534 + endloop + endfacet + facet normal 0.362835 -0.083688 0.928088 + outer loop + vertex 1.10218 1.2226 2.59685 + vertex 1.10203 1.21779 2.59647 + vertex 1.1055 1.22136 2.59543 + endloop + endfacet + facet normal 0.617607 0.0165181 0.786313 + outer loop + vertex 1.10841 1.22448 2.5934 + vertex 1.10837 1.22973 2.59332 + vertex 1.10559 1.22638 2.59557 + endloop + endfacet + facet normal 0.59621 -0.0334155 0.802133 + outer loop + vertex 1.1055 1.22136 2.59543 + vertex 1.10841 1.22448 2.5934 + vertex 1.10559 1.22638 2.59557 + endloop + endfacet + facet normal 0.380265 -0.0328796 0.924293 + outer loop + vertex 1.10559 1.22638 2.59557 + vertex 1.10218 1.2226 2.59685 + vertex 1.1055 1.22136 2.59543 + endloop + endfacet + facet normal 0.417009 -0.0722789 0.906024 + outer loop + vertex 1.10218 1.22756 2.59724 + vertex 1.10218 1.2226 2.59685 + vertex 1.10559 1.22638 2.59557 + endloop + endfacet + facet normal 0.651473 0.0287601 0.758127 + outer loop + vertex 1.10837 1.22973 2.59332 + vertex 1.10816 1.23483 2.5933 + vertex 1.10551 1.23142 2.59571 + endloop + endfacet + facet normal 0.637863 -0.011157 0.770069 + outer loop + vertex 1.10559 1.22638 2.59557 + vertex 1.10837 1.22973 2.59332 + vertex 1.10551 1.23142 2.59571 + endloop + endfacet + facet normal 0.433404 -0.0180475 0.901019 + outer loop + vertex 1.10551 1.23142 2.59571 + vertex 1.10218 1.22756 2.59724 + vertex 1.10559 1.22638 2.59557 + endloop + endfacet + facet normal 0.46233 -0.0492625 0.885338 + outer loop + vertex 1.10211 1.23255 2.59756 + vertex 1.10218 1.22756 2.59724 + vertex 1.10551 1.23142 2.59571 + endloop + endfacet + facet normal 0.67992 0.0521388 0.73143 + outer loop + vertex 1.10816 1.23483 2.5933 + vertex 1.10799 1.23977 2.59312 + vertex 1.1054 1.23642 2.59576 + endloop + endfacet + facet normal 0.666707 0.00783761 0.745279 + outer loop + vertex 1.10551 1.23142 2.59571 + vertex 1.10816 1.23483 2.5933 + vertex 1.1054 1.23642 2.59576 + endloop + endfacet + facet normal 0.476179 0.00220956 0.879346 + outer loop + vertex 1.1054 1.23642 2.59576 + vertex 1.10211 1.23255 2.59756 + vertex 1.10551 1.23142 2.59571 + endloop + endfacet + facet normal 0.513092 -0.0392729 0.857434 + outer loop + vertex 1.10211 1.23761 2.59778 + vertex 1.10211 1.23255 2.59756 + vertex 1.1054 1.23642 2.59576 + endloop + endfacet + facet normal 0.71695 0.0647724 0.694109 + outer loop + vertex 1.10799 1.23977 2.59312 + vertex 1.1079 1.24454 2.59276 + vertex 1.10538 1.24151 2.59565 + endloop + endfacet + facet normal 0.702749 0.0184528 0.711199 + outer loop + vertex 1.1054 1.23642 2.59576 + vertex 1.10799 1.23977 2.59312 + vertex 1.10538 1.24151 2.59565 + endloop + endfacet + facet normal 0.52913 0.0208205 0.848285 + outer loop + vertex 1.10538 1.24151 2.59565 + vertex 1.10211 1.23761 2.59778 + vertex 1.1054 1.23642 2.59576 + endloop + endfacet + facet normal 0.576719 -0.0366818 0.816118 + outer loop + vertex 1.10221 1.24289 2.59795 + vertex 1.10211 1.23761 2.59778 + vertex 1.10538 1.24151 2.59565 + endloop + endfacet + facet normal 0.768349 0.0768045 0.635406 + outer loop + vertex 1.1079 1.24454 2.59276 + vertex 1.10802 1.24829 2.59216 + vertex 1.10564 1.24721 2.59518 + endloop + endfacet + facet normal 0.741462 0.0221333 0.670629 + outer loop + vertex 1.10538 1.24151 2.59565 + vertex 1.1079 1.24454 2.59276 + vertex 1.10564 1.24721 2.59518 + endloop + endfacet + facet normal 0.598402 0.0394394 0.800225 + outer loop + vertex 1.10564 1.24721 2.59518 + vertex 1.10221 1.24289 2.59795 + vertex 1.10538 1.24151 2.59565 + endloop + endfacet + facet normal 0.673609 -0.0610001 0.736566 + outer loop + vertex 1.10221 1.24866 2.59843 + vertex 1.10221 1.24289 2.59795 + vertex 1.10564 1.24721 2.59518 + endloop + endfacet + facet normal 0.840027 0.088981 0.535199 + outer loop + vertex 1.1091 1.2509 2.59013 + vertex 1.10911 1.25491 2.58945 + vertex 1.10748 1.25164 2.59255 + endloop + endfacet + facet normal 0.838959 0.0734697 0.539213 + outer loop + vertex 1.10802 1.24829 2.59216 + vertex 1.1091 1.2509 2.59013 + vertex 1.10748 1.25164 2.59255 + endloop + endfacet + facet normal 0.77399 0.0522523 0.631038 + outer loop + vertex 1.10802 1.24829 2.59216 + vertex 1.10748 1.25164 2.59255 + vertex 1.10564 1.24721 2.59518 + endloop + endfacet + facet normal 0.809204 0.0117463 0.587411 + outer loop + vertex 1.10564 1.24721 2.59518 + vertex 1.10748 1.25164 2.59255 + vertex 1.1053 1.25276 2.59553 + endloop + endfacet + facet normal 0.687615 -0.00431296 0.726062 + outer loop + vertex 1.1053 1.25276 2.59553 + vertex 1.10221 1.24866 2.59843 + vertex 1.10564 1.24721 2.59518 + endloop + endfacet + facet normal 0.731493 -0.0713325 0.678108 + outer loop + vertex 1.10295 1.25461 2.59825 + vertex 1.10221 1.24866 2.59843 + vertex 1.1053 1.25276 2.59553 + endloop + endfacet + facet normal 0.86759 0.0778666 0.491146 + outer loop + vertex 1.10911 1.25491 2.58945 + vertex 1.10887 1.25988 2.58908 + vertex 1.1073 1.25634 2.59242 + endloop + endfacet + facet normal 0.862927 0.0471556 0.503123 + outer loop + vertex 1.10748 1.25164 2.59255 + vertex 1.10911 1.25491 2.58945 + vertex 1.1073 1.25634 2.59242 + endloop + endfacet + facet normal 0.814662 0.047396 0.577996 + outer loop + vertex 1.10748 1.25164 2.59255 + vertex 1.1073 1.25634 2.59242 + vertex 1.1053 1.25276 2.59553 + endloop + endfacet + facet normal 0.838852 0.00474091 0.544339 + outer loop + vertex 1.1073 1.25634 2.59242 + vertex 1.10532 1.25801 2.59546 + vertex 1.1053 1.25276 2.59553 + endloop + endfacet + facet normal 0.760004 0.00632846 0.649888 + outer loop + vertex 1.10532 1.25801 2.59546 + vertex 1.10295 1.25461 2.59825 + vertex 1.1053 1.25276 2.59553 + endloop + endfacet + facet normal 0.771332 -0.0127074 0.636306 + outer loop + vertex 1.10307 1.25981 2.59821 + vertex 1.10295 1.25461 2.59825 + vertex 1.10532 1.25801 2.59546 + endloop + endfacet + facet normal 0.89023 0.0708156 0.449974 + outer loop + vertex 1.10887 1.25988 2.58908 + vertex 1.10853 1.26478 2.58899 + vertex 1.10715 1.26138 2.59225 + endloop + endfacet + facet normal 0.886166 0.0416434 0.461493 + outer loop + vertex 1.1073 1.25634 2.59242 + vertex 1.10887 1.25988 2.58908 + vertex 1.10715 1.26138 2.59225 + endloop + endfacet + facet normal 0.847492 0.0426832 0.529089 + outer loop + vertex 1.1073 1.25634 2.59242 + vertex 1.10715 1.26138 2.59225 + vertex 1.10532 1.25801 2.59546 + endloop + endfacet + facet normal 0.854383 0.0291644 0.518825 + outer loop + vertex 1.10715 1.26138 2.59225 + vertex 1.10522 1.26311 2.59534 + vertex 1.10532 1.25801 2.59546 + endloop + endfacet + facet normal 0.784656 0.030125 0.619199 + outer loop + vertex 1.10522 1.26311 2.59534 + vertex 1.10307 1.25981 2.59821 + vertex 1.10532 1.25801 2.59546 + endloop + endfacet + facet normal 0.788953 0.0228156 0.61403 + outer loop + vertex 1.10299 1.26485 2.59813 + vertex 1.10307 1.25981 2.59821 + vertex 1.10522 1.26311 2.59534 + endloop + endfacet + facet normal 0.902989 0.094041 0.419246 + outer loop + vertex 1.10853 1.26478 2.58899 + vertex 1.10812 1.26953 2.5888 + vertex 1.10691 1.2664 2.59211 + endloop + endfacet + facet normal 0.897895 0.0550219 0.436758 + outer loop + vertex 1.10715 1.26138 2.59225 + vertex 1.10853 1.26478 2.58899 + vertex 1.10691 1.2664 2.59211 + endloop + endfacet + facet normal 0.859809 0.055218 0.507621 + outer loop + vertex 1.10715 1.26138 2.59225 + vertex 1.10691 1.2664 2.59211 + vertex 1.10522 1.26311 2.59534 + endloop + endfacet + facet normal 0.859948 0.0549448 0.507415 + outer loop + vertex 1.10691 1.2664 2.59211 + vertex 1.10501 1.26806 2.59515 + vertex 1.10522 1.26311 2.59534 + endloop + endfacet + facet normal 0.797789 0.0559983 0.60033 + outer loop + vertex 1.10501 1.26806 2.59515 + vertex 1.10299 1.26485 2.59813 + vertex 1.10522 1.26311 2.59534 + endloop + endfacet + facet normal 0.802632 0.047615 0.594572 + outer loop + vertex 1.10292 1.2697 2.59784 + vertex 1.10299 1.26485 2.59813 + vertex 1.10501 1.26806 2.59515 + endloop + endfacet + facet normal -0.612335 -0.374999 0.696004 + outer loop + vertex 1.11 1.27451 2.585 + vertex 1.1097 1.275 2.585 + vertex 1.10944 1.27317 2.58378 + endloop + endfacet + facet normal 0.912308 0.113175 0.393555 + outer loop + vertex 1.10812 1.26953 2.5888 + vertex 1.10771 1.27421 2.5884 + vertex 1.10658 1.27144 2.59183 + endloop + endfacet + facet normal 0.90808 0.0828612 0.410517 + outer loop + vertex 1.10691 1.2664 2.59211 + vertex 1.10812 1.26953 2.5888 + vertex 1.10658 1.27144 2.59183 + endloop + endfacet + facet normal 0.865142 0.0847634 0.494312 + outer loop + vertex 1.10691 1.2664 2.59211 + vertex 1.10658 1.27144 2.59183 + vertex 1.10501 1.26806 2.59515 + endloop + endfacet + facet normal 0.868739 0.077977 0.489093 + outer loop + vertex 1.10658 1.27144 2.59183 + vertex 1.10475 1.27272 2.59486 + vertex 1.10501 1.26806 2.59515 + endloop + endfacet + facet normal 0.810208 0.0802492 0.580623 + outer loop + vertex 1.10475 1.27272 2.59486 + vertex 1.10292 1.2697 2.59784 + vertex 1.10501 1.26806 2.59515 + endloop + endfacet + facet normal 0.829416 0.0451558 0.556803 + outer loop + vertex 1.10309 1.2735 2.59727 + vertex 1.10292 1.2697 2.59784 + vertex 1.10475 1.27272 2.59486 + endloop + endfacet + facet normal -0.570822 -0.109597 0.813727 + outer loop + vertex 1.1097 1.275 2.585 + vertex 1.10874 1.28 2.585 + vertex 1.10855 1.27576 2.58429 + endloop + endfacet + facet normal -0.646967 -0.355695 0.674474 + outer loop + vertex 1.10944 1.27317 2.58378 + vertex 1.1097 1.275 2.585 + vertex 1.10855 1.27576 2.58429 + endloop + endfacet + facet normal 0.921991 0.0351408 0.385613 + outer loop + vertex 1.10771 1.27421 2.5884 + vertex 1.10784 1.27826 2.58772 + vertex 1.10633 1.27759 2.59141 + endloop + endfacet + facet normal 0.93126 0.0626534 0.358927 + outer loop + vertex 1.10658 1.27144 2.59183 + vertex 1.10771 1.27421 2.5884 + vertex 1.10633 1.27759 2.59141 + endloop + endfacet + facet normal 0.862588 0.0706088 0.500955 + outer loop + vertex 1.10424 1.27604 2.59521 + vertex 1.10633 1.27759 2.59141 + vertex 1.10433 1.2799 2.59452 + endloop + endfacet + facet normal 0.860402 0.0794907 0.503379 + outer loop + vertex 1.10424 1.27604 2.59521 + vertex 1.10475 1.27272 2.59486 + vertex 1.10633 1.27759 2.59141 + endloop + endfacet + facet normal 0.867735 0.0691847 0.492188 + outer loop + vertex 1.10475 1.27272 2.59486 + vertex 1.10658 1.27144 2.59183 + vertex 1.10633 1.27759 2.59141 + endloop + endfacet + facet normal 0.83191 0.0701741 0.550455 + outer loop + vertex 1.10475 1.27272 2.59486 + vertex 1.10424 1.27604 2.59521 + vertex 1.10309 1.2735 2.59727 + endloop + endfacet + facet normal 0.893154 -0.11304 0.435315 + outer loop + vertex 1.10825 1.27882 2.58569 + vertex 1.10855 1.27576 2.58429 + vertex 1.10874 1.28 2.585 + endloop + endfacet + facet normal 0.941267 -0.311364 0.130645 + outer loop + vertex 1.10825 1.27882 2.58569 + vertex 1.10874 1.28 2.585 + vertex 1.1097 1.285 2.59 + endloop + endfacet + facet normal 0.952739 0.102899 -0.285831 + outer loop + vertex 1.1097 1.285 2.59 + vertex 1.10874 1.28 2.585 + vertex 1.1082 1.285 2.585 + endloop + endfacet + facet normal 0.948378 -0.297861 0.108894 + outer loop + vertex 1.10784 1.27826 2.58772 + vertex 1.10825 1.27882 2.58569 + vertex 1.1097 1.285 2.59 + endloop + endfacet + facet normal 0.887641 -0.346863 0.302952 + outer loop + vertex 1.10784 1.27826 2.58772 + vertex 1.1097 1.285 2.59 + vertex 1.10633 1.27759 2.59141 + endloop + endfacet + facet normal 0.332788 0.027401 0.942604 + outer loop + vertex 1.10633 1.27759 2.59141 + vertex 1.1097 1.285 2.59 + vertex 1.10631 1.28402 2.59123 + endloop + endfacet + facet normal 0.847487 0.0174675 0.530529 + outer loop + vertex 1.10631 1.28402 2.59123 + vertex 1.10433 1.2799 2.59452 + vertex 1.10633 1.27759 2.59141 + endloop + endfacet + facet normal 0.828542 0.0483812 0.557833 + outer loop + vertex 1.10421 1.2847 2.59428 + vertex 1.10433 1.2799 2.59452 + vertex 1.10631 1.28402 2.59123 + endloop + endfacet + facet normal 0.328158 0.0446275 0.943568 + outer loop + vertex 1.1097 1.285 2.59 + vertex 1.10902 1.29 2.59 + vertex 1.10631 1.28402 2.59123 + endloop + endfacet + facet normal 0.364479 0.0255368 0.930861 + outer loop + vertex 1.10902 1.29 2.59 + vertex 1.10599 1.28907 2.59121 + vertex 1.10631 1.28402 2.59123 + endloop + endfacet + facet normal 0.828841 0.0533583 0.556934 + outer loop + vertex 1.10599 1.28907 2.59121 + vertex 1.10421 1.2847 2.59428 + vertex 1.10631 1.28402 2.59123 + endloop + endfacet + facet normal 0.837187 0.0418141 0.545316 + outer loop + vertex 1.10404 1.28963 2.59416 + vertex 1.10421 1.2847 2.59428 + vertex 1.10599 1.28907 2.59121 + endloop + endfacet + facet normal 0.353106 0.0656743 0.933276 + outer loop + vertex 1.10902 1.29 2.59 + vertex 1.10809 1.295 2.59 + vertex 1.10599 1.28907 2.59121 + endloop + endfacet + facet normal 0.422757 0.0353592 0.905553 + outer loop + vertex 1.10809 1.295 2.59 + vertex 1.10563 1.29408 2.59119 + vertex 1.10599 1.28907 2.59121 + endloop + endfacet + facet normal 0.838097 0.0636016 0.541801 + outer loop + vertex 1.10563 1.29408 2.59119 + vertex 1.10404 1.28963 2.59416 + vertex 1.10599 1.28907 2.59121 + endloop + endfacet + facet normal 0.841874 0.0587038 0.536472 + outer loop + vertex 1.10381 1.29469 2.59396 + vertex 1.10404 1.28963 2.59416 + vertex 1.10563 1.29408 2.59119 + endloop + endfacet + facet normal 0.424551 0.0297185 0.904916 + outer loop + vertex 1.10809 1.295 2.59 + vertex 1.10774 1.3 2.59 + vertex 1.10563 1.29408 2.59119 + endloop + endfacet + facet normal 0.363928 0.0563368 0.929722 + outer loop + vertex 1.10774 1.3 2.59 + vertex 1.1052 1.29917 2.59104 + vertex 1.10563 1.29408 2.59119 + endloop + endfacet + facet normal 0.842871 0.0850582 0.53135 + outer loop + vertex 1.1052 1.29917 2.59104 + vertex 1.10381 1.29469 2.59396 + vertex 1.10563 1.29408 2.59119 + endloop + endfacet + facet normal 0.857686 0.066428 0.509865 + outer loop + vertex 1.10354 1.29981 2.59377 + vertex 1.10381 1.29469 2.59396 + vertex 1.1052 1.29917 2.59104 + endloop + endfacet + facet normal 0.365498 0.0511695 0.929405 + outer loop + vertex 1.10774 1.3 2.59 + vertex 1.10704 1.305 2.59 + vertex 1.1052 1.29917 2.59104 + endloop + endfacet + facet normal 0.359018 0.053635 0.931788 + outer loop + vertex 1.10704 1.305 2.59 + vertex 1.1047 1.30408 2.59095 + vertex 1.1052 1.29917 2.59104 + endloop + endfacet + facet normal 0.858692 0.0971348 0.503203 + outer loop + vertex 1.1047 1.30408 2.59095 + vertex 1.10354 1.29981 2.59377 + vertex 1.1052 1.29917 2.59104 + endloop + endfacet + facet normal 0.888949 0.0567908 0.454472 + outer loop + vertex 1.10326 1.30472 2.59369 + vertex 1.10354 1.29981 2.59377 + vertex 1.1047 1.30408 2.59095 + endloop + endfacet + facet normal 0.357962 0.056558 0.932022 + outer loop + vertex 1.10704 1.305 2.59 + vertex 1.10625 1.31 2.59 + vertex 1.1047 1.30408 2.59095 + endloop + endfacet + facet normal 0.482856 0.0147668 0.875575 + outer loop + vertex 1.10625 1.31 2.59 + vertex 1.10412 1.30794 2.59121 + vertex 1.1047 1.30408 2.59095 + endloop + endfacet + facet normal 0.889992 0.105034 0.443715 + outer loop + vertex 1.10412 1.30794 2.59121 + vertex 1.10326 1.30472 2.59369 + vertex 1.1047 1.30408 2.59095 + endloop + endfacet + facet normal 0.918853 0.0564565 0.390541 + outer loop + vertex 1.10303 1.30951 2.59353 + vertex 1.10326 1.30472 2.59369 + vertex 1.10412 1.30794 2.59121 + endloop + endfacet + facet normal -0.735934 -0.203074 0.645881 + outer loop + vertex 1.10426 1.3132 2.58874 + vertex 1.10625 1.31 2.59 + vertex 1.105 1.31453 2.59 + endloop + endfacet + facet normal 0.644104 0.5917 0.484789 + outer loop + vertex 1.10426 1.3132 2.58874 + vertex 1.10381 1.31231 2.59043 + vertex 1.10625 1.31 2.59 + endloop + endfacet + facet normal 0.340532 0.189212 0.920998 + outer loop + vertex 1.10381 1.31231 2.59043 + vertex 1.10412 1.30794 2.59121 + vertex 1.10625 1.31 2.59 + endloop + endfacet + facet normal 0.929055 0.127726 0.347192 + outer loop + vertex 1.10381 1.31231 2.59043 + vertex 1.10303 1.30951 2.59353 + vertex 1.10412 1.30794 2.59121 + endloop + endfacet + facet normal 0.95321 0.063695 0.295521 + outer loop + vertex 1.10284 1.31422 2.59315 + vertex 1.10303 1.30951 2.59353 + vertex 1.10381 1.31231 2.59043 + endloop + endfacet + facet normal 0.925156 0.17348 0.337627 + outer loop + vertex 1.1036 1.31577 2.58922 + vertex 1.10381 1.31231 2.59043 + vertex 1.10426 1.3132 2.58874 + endloop + endfacet + facet normal 0.975322 0.122796 0.183487 + outer loop + vertex 1.10328 1.31593 2.59079 + vertex 1.10381 1.31231 2.59043 + vertex 1.1036 1.31577 2.58922 + endloop + endfacet + facet normal 0.958226 0.112353 0.263022 + outer loop + vertex 1.10328 1.31593 2.59079 + vertex 1.10284 1.31422 2.59315 + vertex 1.10381 1.31231 2.59043 + endloop + endfacet + facet normal 0.984463 -0.0159921 0.174864 + outer loop + vertex 1.10302 1.31826 2.59249 + vertex 1.10284 1.31422 2.59315 + vertex 1.10328 1.31593 2.59079 + endloop + endfacet + facet normal 0.979926 -0.0170705 0.198628 + outer loop + vertex 1.1036 1.31577 2.58922 + vertex 1.10337 1.31883 2.59062 + vertex 1.10328 1.31593 2.59079 + endloop + endfacet + facet normal 0.983849 -0.0183909 0.178054 + outer loop + vertex 1.10328 1.31593 2.59079 + vertex 1.10337 1.31883 2.59062 + vertex 1.10302 1.31826 2.59249 + endloop + endfacet + facet normal -0.357181 0.018599 0.93385 + outer loop + vertex 1.10515 1.72 2.59 + vertex 1.10407 1.71981 2.58959 + vertex 1.105 1.71712 2.59 + endloop + endfacet + facet normal -0.374166 0.165383 0.912496 + outer loop + vertex 1.10736 1.725 2.59 + vertex 1.10407 1.71981 2.58959 + vertex 1.10515 1.72 2.59 + endloop + endfacet + facet normal 0.0917166 -0.136514 0.986383 + outer loop + vertex 1.10449 1.72447 2.59019 + vertex 1.10407 1.71981 2.58959 + vertex 1.10736 1.725 2.59 + endloop + endfacet + facet normal 0.0692326 -0.0112161 0.997537 + outer loop + vertex 1.10817 1.73 2.59 + vertex 1.10449 1.72447 2.59019 + vertex 1.10736 1.725 2.59 + endloop + endfacet + facet normal 0.226163 -0.116549 0.967092 + outer loop + vertex 1.10465 1.72842 2.59063 + vertex 1.10449 1.72447 2.59019 + vertex 1.10817 1.73 2.59 + endloop + endfacet + facet normal 0.731528 -0.125605 0.670142 + outer loop + vertex 1.10465 1.72842 2.59063 + vertex 1.10589 1.73327 2.59018 + vertex 1.10349 1.73031 2.59225 + endloop + endfacet + facet normal 0.154159 0.0516368 0.986696 + outer loop + vertex 1.10465 1.72842 2.59063 + vertex 1.10817 1.73 2.59 + vertex 1.10589 1.73327 2.59018 + endloop + endfacet + facet normal 0.0715393 -0.00643876 0.997417 + outer loop + vertex 1.10817 1.73 2.59 + vertex 1.10862 1.735 2.59 + vertex 1.10589 1.73327 2.59018 + endloop + endfacet + facet normal 0.729889 -0.122656 0.672471 + outer loop + vertex 1.10589 1.73327 2.59018 + vertex 1.10357 1.73439 2.59291 + vertex 1.10349 1.73031 2.59225 + endloop + endfacet + facet normal 0.0718258 -0.00689437 0.997393 + outer loop + vertex 1.10862 1.735 2.59 + vertex 1.1091 1.74 2.59 + vertex 1.10589 1.73327 2.59018 + endloop + endfacet + facet normal 0.217882 -0.077239 0.972914 + outer loop + vertex 1.1091 1.74 2.59 + vertex 1.10597 1.7385 2.59058 + vertex 1.10589 1.73327 2.59018 + endloop + endfacet + facet normal 0.74709 -0.0609652 0.661922 + outer loop + vertex 1.10597 1.7385 2.59058 + vertex 1.10357 1.73439 2.59291 + vertex 1.10589 1.73327 2.59018 + endloop + endfacet + facet normal 0.782673 -0.109588 0.61271 + outer loop + vertex 1.10367 1.73916 2.59363 + vertex 1.10357 1.73439 2.59291 + vertex 1.10597 1.7385 2.59058 + endloop + endfacet + facet normal 0.197127 -0.031146 0.979883 + outer loop + vertex 1.1091 1.74 2.59 + vertex 1.10989 1.745 2.59 + vertex 1.10597 1.7385 2.59058 + endloop + endfacet + facet normal 0.370699 -0.141511 0.917909 + outer loop + vertex 1.10989 1.745 2.59 + vertex 1.10568 1.74229 2.59128 + vertex 1.10597 1.7385 2.59058 + endloop + endfacet + facet normal 0.792382 -0.0525913 0.607754 + outer loop + vertex 1.10568 1.74229 2.59128 + vertex 1.10367 1.73916 2.59363 + vertex 1.10597 1.7385 2.59058 + endloop + endfacet + facet normal 0.818176 -0.100363 0.56614 + outer loop + vertex 1.10386 1.74381 2.59418 + vertex 1.10367 1.73916 2.59363 + vertex 1.10568 1.74229 2.59128 + endloop + endfacet + facet normal 0.193987 0.841251 0.504645 + outer loop + vertex 1.1085 1.74827 2.58509 + vertex 1.10785 1.74735 2.58686 + vertex 1.10989 1.745 2.59 + endloop + endfacet + facet normal -0.839796 0.310774 0.445154 + outer loop + vertex 1.1085 1.74827 2.58509 + vertex 1.10989 1.745 2.59 + vertex 1.10909 1.75 2.585 + endloop + endfacet + facet normal 0.934156 -0.166283 -0.315758 + outer loop + vertex 1.10909 1.75 2.585 + vertex 1.10989 1.745 2.59 + vertex 1.1082 1.745 2.585 + endloop + endfacet + facet normal 0.927162 -0.0726375 0.367551 + outer loop + vertex 1.10785 1.74735 2.58686 + vertex 1.10783 1.75018 2.58748 + vertex 1.10627 1.74706 2.5908 + endloop + endfacet + facet normal 0.52057 0.810102 0.269708 + outer loop + vertex 1.10785 1.74735 2.58686 + vertex 1.10627 1.74706 2.5908 + vertex 1.10989 1.745 2.59 + endloop + endfacet + facet normal 0.250894 0.0672998 0.965672 + outer loop + vertex 1.10989 1.745 2.59 + vertex 1.10627 1.74706 2.5908 + vertex 1.10568 1.74229 2.59128 + endloop + endfacet + facet normal 0.834704 -0.0472171 0.548671 + outer loop + vertex 1.10627 1.74706 2.5908 + vertex 1.10386 1.74381 2.59418 + vertex 1.10568 1.74229 2.59128 + endloop + endfacet + facet normal 0.855188 -0.105038 0.507563 + outer loop + vertex 1.10404 1.74783 2.59472 + vertex 1.10386 1.74381 2.59418 + vertex 1.10627 1.74706 2.5908 + endloop + endfacet + facet normal 0.400003 -0.0903279 0.912052 + outer loop + vertex 1.11 1.75403 2.585 + vertex 1.1085 1.74827 2.58509 + vertex 1.10909 1.75 2.585 + endloop + endfacet + facet normal 0.9165 -0.191002 0.35149 + outer loop + vertex 1.10783 1.75018 2.58748 + vertex 1.10844 1.75423 2.58809 + vertex 1.10697 1.75141 2.5904 + endloop + endfacet + facet normal 0.937139 -0.11989 0.327714 + outer loop + vertex 1.10627 1.74706 2.5908 + vertex 1.10783 1.75018 2.58748 + vertex 1.10697 1.75141 2.5904 + endloop + endfacet + facet normal 0.827368 -0.0866658 0.554934 + outer loop + vertex 1.10404 1.74783 2.59472 + vertex 1.10507 1.75189 2.59382 + vertex 1.1029 1.75021 2.59679 + endloop + endfacet + facet normal 0.855326 -0.104265 0.50749 + outer loop + vertex 1.10404 1.74783 2.59472 + vertex 1.10627 1.74706 2.5908 + vertex 1.10507 1.75189 2.59382 + endloop + endfacet + facet normal 0.864813 -0.0930859 0.49339 + outer loop + vertex 1.10627 1.74706 2.5908 + vertex 1.10697 1.75141 2.5904 + vertex 1.10507 1.75189 2.59382 + endloop + endfacet + facet normal 0.81843 -0.043324 0.572971 + outer loop + vertex 1.10507 1.75189 2.59382 + vertex 1.10279 1.75426 2.59725 + vertex 1.1029 1.75021 2.59679 + endloop + endfacet + facet normal 0.8852 -0.1492 0.440635 + outer loop + vertex 1.10844 1.75423 2.58809 + vertex 1.10894 1.75883 2.58865 + vertex 1.107 1.75545 2.59138 + endloop + endfacet + facet normal 0.89475 -0.114074 0.431752 + outer loop + vertex 1.10697 1.75141 2.5904 + vertex 1.10844 1.75423 2.58809 + vertex 1.107 1.75545 2.59138 + endloop + endfacet + facet normal 0.85906 -0.129223 0.495296 + outer loop + vertex 1.10697 1.75141 2.5904 + vertex 1.107 1.75545 2.59138 + vertex 1.10507 1.75189 2.59382 + endloop + endfacet + facet normal 0.829457 -0.0730564 0.553772 + outer loop + vertex 1.107 1.75545 2.59138 + vertex 1.10502 1.75729 2.59459 + vertex 1.10507 1.75189 2.59382 + endloop + endfacet + facet normal 0.80498 -0.0781952 0.588126 + outer loop + vertex 1.10502 1.75729 2.59459 + vertex 1.10279 1.75426 2.59725 + vertex 1.10507 1.75189 2.59382 + endloop + endfacet + facet normal 0.783078 -0.0331593 0.621039 + outer loop + vertex 1.10274 1.75925 2.59758 + vertex 1.10279 1.75426 2.59725 + vertex 1.10502 1.75729 2.59459 + endloop + endfacet + facet normal 0.847664 -0.0873251 0.523297 + outer loop + vertex 1.10894 1.75883 2.58865 + vertex 1.10923 1.7636 2.58896 + vertex 1.10713 1.76039 2.59184 + endloop + endfacet + facet normal 0.853026 -0.0688481 0.517307 + outer loop + vertex 1.107 1.75545 2.59138 + vertex 1.10894 1.75883 2.58865 + vertex 1.10713 1.76039 2.59184 + endloop + endfacet + facet normal 0.829951 -0.0715734 0.553225 + outer loop + vertex 1.107 1.75545 2.59138 + vertex 1.10713 1.76039 2.59184 + vertex 1.10502 1.75729 2.59459 + endloop + endfacet + facet normal 0.80991 -0.028897 0.585842 + outer loop + vertex 1.10713 1.76039 2.59184 + vertex 1.10502 1.76237 2.59485 + vertex 1.10502 1.75729 2.59459 + endloop + endfacet + facet normal 0.783948 -0.0306695 0.620069 + outer loop + vertex 1.10502 1.76237 2.59485 + vertex 1.10274 1.75925 2.59758 + vertex 1.10502 1.75729 2.59459 + endloop + endfacet + facet normal 0.775784 -0.0153238 0.630812 + outer loop + vertex 1.10276 1.76425 2.59767 + vertex 1.10274 1.75925 2.59758 + vertex 1.10502 1.76237 2.59485 + endloop + endfacet + facet normal 0.817669 -0.0396236 0.574324 + outer loop + vertex 1.10923 1.7636 2.58896 + vertex 1.10946 1.76835 2.58897 + vertex 1.10722 1.7654 2.59196 + endloop + endfacet + facet normal 0.821213 -0.0283215 0.569918 + outer loop + vertex 1.10713 1.76039 2.59184 + vertex 1.10923 1.7636 2.58896 + vertex 1.10722 1.7654 2.59196 + endloop + endfacet + facet normal 0.810047 -0.0284944 0.585672 + outer loop + vertex 1.10713 1.76039 2.59184 + vertex 1.10722 1.7654 2.59196 + vertex 1.10502 1.76237 2.59485 + endloop + endfacet + facet normal 0.799608 -0.00672038 0.600484 + outer loop + vertex 1.10722 1.7654 2.59196 + vertex 1.10502 1.76739 2.5949 + vertex 1.10502 1.76237 2.59485 + endloop + endfacet + facet normal 0.778588 -0.00696713 0.627497 + outer loop + vertex 1.10502 1.76739 2.5949 + vertex 1.10276 1.76425 2.59767 + vertex 1.10502 1.76237 2.59485 + endloop + endfacet + facet normal 0.773488 0.00228437 0.633806 + outer loop + vertex 1.10274 1.76922 2.59768 + vertex 1.10276 1.76425 2.59767 + vertex 1.10502 1.76739 2.5949 + endloop + endfacet + facet normal 0.801884 -0.015601 0.597276 + outer loop + vertex 1.10946 1.76835 2.58897 + vertex 1.10952 1.77326 2.58901 + vertex 1.10725 1.77039 2.59198 + endloop + endfacet + facet normal 0.804099 -0.0090021 0.594428 + outer loop + vertex 1.10722 1.7654 2.59196 + vertex 1.10946 1.76835 2.58897 + vertex 1.10725 1.77039 2.59198 + endloop + endfacet + facet normal 0.798851 -0.009007 0.601461 + outer loop + vertex 1.10722 1.7654 2.59196 + vertex 1.10725 1.77039 2.59198 + vertex 1.10502 1.76739 2.5949 + endloop + endfacet + facet normal 0.794908 -0.000954523 0.606729 + outer loop + vertex 1.10725 1.77039 2.59198 + vertex 1.10495 1.77238 2.595 + vertex 1.10502 1.76739 2.5949 + endloop + endfacet + facet normal 0.772148 -0.001861 0.63544 + outer loop + vertex 1.10495 1.77238 2.595 + vertex 1.10274 1.76922 2.59768 + vertex 1.10502 1.76739 2.5949 + endloop + endfacet + facet normal 0.761231 0.0166662 0.648267 + outer loop + vertex 1.10251 1.77421 2.59782 + vertex 1.10274 1.76922 2.59768 + vertex 1.10495 1.77238 2.595 + endloop + endfacet + facet normal 0.797184 -0.0140484 0.603572 + outer loop + vertex 1.10952 1.77326 2.58901 + vertex 1.10934 1.77825 2.58937 + vertex 1.10715 1.77541 2.5922 + endloop + endfacet + facet normal 0.79889 -0.00896499 0.601411 + outer loop + vertex 1.10725 1.77039 2.59198 + vertex 1.10952 1.77326 2.58901 + vertex 1.10715 1.77541 2.5922 + endloop + endfacet + facet normal 0.792152 -0.00949251 0.61025 + outer loop + vertex 1.10725 1.77039 2.59198 + vertex 1.10715 1.77541 2.5922 + vertex 1.10495 1.77238 2.595 + endloop + endfacet + facet normal 0.786816 0.000756469 0.617187 + outer loop + vertex 1.10715 1.77541 2.5922 + vertex 1.10468 1.77729 2.59534 + vertex 1.10495 1.77238 2.595 + endloop + endfacet + facet normal 0.754793 -0.00363133 0.655953 + outer loop + vertex 1.10468 1.77729 2.59534 + vertex 1.10251 1.77421 2.59782 + vertex 1.10495 1.77238 2.595 + endloop + endfacet + facet normal 0.723657 0.0446946 0.688711 + outer loop + vertex 1.10182 1.77943 2.59821 + vertex 1.10251 1.77421 2.59782 + vertex 1.10468 1.77729 2.59534 + endloop + endfacet + facet normal 0.795963 -0.0270284 0.604741 + outer loop + vertex 1.10934 1.77825 2.58937 + vertex 1.10914 1.78239 2.58982 + vertex 1.10686 1.78072 2.59274 + endloop + endfacet + facet normal 0.799202 -0.018399 0.600781 + outer loop + vertex 1.10715 1.77541 2.5922 + vertex 1.10934 1.77825 2.58937 + vertex 1.10686 1.78072 2.59274 + endloop + endfacet + facet normal 0.779974 -0.0219437 0.625427 + outer loop + vertex 1.10715 1.77541 2.5922 + vertex 1.10686 1.78072 2.59274 + vertex 1.10468 1.77729 2.59534 + endloop + endfacet + facet normal 0.77168 -0.00871217 0.635951 + outer loop + vertex 1.10686 1.78072 2.59274 + vertex 1.10433 1.78129 2.59583 + vertex 1.10468 1.77729 2.59534 + endloop + endfacet + facet normal 0.698411 -0.0248945 0.715264 + outer loop + vertex 1.10433 1.78129 2.59583 + vertex 1.10182 1.77943 2.59821 + vertex 1.10468 1.77729 2.59534 + endloop + endfacet + facet normal 0.688465 0.00120183 0.725269 + outer loop + vertex 1.10262 1.78347 2.59745 + vertex 1.10182 1.77943 2.59821 + vertex 1.10433 1.78129 2.59583 + endloop + endfacet + facet normal 0.799488 -0.0414995 0.599247 + outer loop + vertex 1.10914 1.78239 2.58982 + vertex 1.10783 1.78483 2.59174 + vertex 1.10686 1.78072 2.59274 + endloop + endfacet + facet normal 0.76879 -0.0539172 0.637225 + outer loop + vertex 1.10783 1.78483 2.59174 + vertex 1.10767 1.78894 2.59228 + vertex 1.10527 1.78533 2.59487 + endloop + endfacet + facet normal 0.771848 -0.0261599 0.635268 + outer loop + vertex 1.10783 1.78483 2.59174 + vertex 1.10527 1.78533 2.59487 + vertex 1.10686 1.78072 2.59274 + endloop + endfacet + facet normal 0.769639 -0.0281175 0.63786 + outer loop + vertex 1.10686 1.78072 2.59274 + vertex 1.10527 1.78533 2.59487 + vertex 1.10433 1.78129 2.59583 + endloop + endfacet + facet normal 0.693764 0.00916016 0.720144 + outer loop + vertex 1.10527 1.78533 2.59487 + vertex 1.10262 1.78347 2.59745 + vertex 1.10433 1.78129 2.59583 + endloop + endfacet + facet normal 0.686324 0.0289442 0.72672 + outer loop + vertex 1.10224 1.78725 2.59765 + vertex 1.10262 1.78347 2.59745 + vertex 1.10527 1.78533 2.59487 + endloop + endfacet + facet normal 0.745804 -0.055072 0.663885 + outer loop + vertex 1.10767 1.78894 2.59228 + vertex 1.10765 1.79399 2.59272 + vertex 1.10503 1.7905 2.59537 + endloop + endfacet + facet normal 0.753178 -0.0292505 0.657166 + outer loop + vertex 1.10527 1.78533 2.59487 + vertex 1.10767 1.78894 2.59228 + vertex 1.10503 1.7905 2.59537 + endloop + endfacet + facet normal 0.661401 -0.0424001 0.748833 + outer loop + vertex 1.10503 1.7905 2.59537 + vertex 1.10224 1.78725 2.59765 + vertex 1.10527 1.78533 2.59487 + endloop + endfacet + facet normal 0.615431 0.024455 0.787811 + outer loop + vertex 1.10197 1.79172 2.59772 + vertex 1.10224 1.78725 2.59765 + vertex 1.10503 1.7905 2.59537 + endloop + endfacet + facet normal 0.718137 -0.0419406 0.694637 + outer loop + vertex 1.10765 1.79399 2.59272 + vertex 1.10776 1.7991 2.59291 + vertex 1.10501 1.79546 2.59554 + endloop + endfacet + facet normal 0.724409 -0.0199716 0.689081 + outer loop + vertex 1.10503 1.7905 2.59537 + vertex 1.10765 1.79399 2.59272 + vertex 1.10501 1.79546 2.59554 + endloop + endfacet + facet normal 0.603169 -0.0241289 0.797249 + outer loop + vertex 1.10501 1.79546 2.59554 + vertex 1.10197 1.79172 2.59772 + vertex 1.10503 1.7905 2.59537 + endloop + endfacet + facet normal 0.542002 0.0499856 0.838889 + outer loop + vertex 1.10178 1.79641 2.59756 + vertex 1.10197 1.79172 2.59772 + vertex 1.10501 1.79546 2.59554 + endloop + endfacet + facet normal 0.681442 -0.02111 0.731567 + outer loop + vertex 1.10776 1.7991 2.59291 + vertex 1.10782 1.8041 2.593 + vertex 1.1051 1.80047 2.59543 + endloop + endfacet + facet normal 0.688165 0.00299239 0.725548 + outer loop + vertex 1.10501 1.79546 2.59554 + vertex 1.10776 1.7991 2.59291 + vertex 1.1051 1.80047 2.59543 + endloop + endfacet + facet normal 0.533868 0.00823819 0.845528 + outer loop + vertex 1.1051 1.80047 2.59543 + vertex 1.10178 1.79641 2.59756 + vertex 1.10501 1.79546 2.59554 + endloop + endfacet + facet normal 0.475743 0.0720174 0.876631 + outer loop + vertex 1.1018 1.80137 2.59715 + vertex 1.10178 1.79641 2.59756 + vertex 1.1051 1.80047 2.59543 + endloop + endfacet + facet normal 0.639618 0.0061214 0.768669 + outer loop + vertex 1.10782 1.8041 2.593 + vertex 1.10757 1.80881 2.59318 + vertex 1.10508 1.80541 2.59527 + endloop + endfacet + facet normal 0.645371 0.0271831 0.763386 + outer loop + vertex 1.1051 1.80047 2.59543 + vertex 1.10782 1.8041 2.593 + vertex 1.10508 1.80541 2.59527 + endloop + endfacet + facet normal 0.467884 0.030618 0.883259 + outer loop + vertex 1.10508 1.80541 2.59527 + vertex 1.1018 1.80137 2.59715 + vertex 1.1051 1.80047 2.59543 + endloop + endfacet + facet normal 0.405762 0.0932034 0.909214 + outer loop + vertex 1.10166 1.80631 2.59671 + vertex 1.1018 1.80137 2.59715 + vertex 1.10508 1.80541 2.59527 + endloop + endfacet + facet normal 0.580923 0.0458008 0.812669 + outer loop + vertex 1.10757 1.80881 2.59318 + vertex 1.10701 1.81368 2.5933 + vertex 1.10467 1.81004 2.59518 + endloop + endfacet + facet normal 0.586583 0.06842 0.806994 + outer loop + vertex 1.10508 1.80541 2.59527 + vertex 1.10757 1.80881 2.59318 + vertex 1.10467 1.81004 2.59518 + endloop + endfacet + facet normal 0.39815 0.0535703 0.915755 + outer loop + vertex 1.10467 1.81004 2.59518 + vertex 1.10166 1.80631 2.59671 + vertex 1.10508 1.80541 2.59527 + endloop + endfacet + facet normal 0.329157 0.117883 0.936888 + outer loop + vertex 1.10104 1.81097 2.59634 + vertex 1.10166 1.80631 2.59671 + vertex 1.10467 1.81004 2.59518 + endloop + endfacet + facet normal 0.5009 0.120221 0.857115 + outer loop + vertex 1.10369 1.81371 2.59523 + vertex 1.10467 1.81004 2.59518 + vertex 1.10701 1.81368 2.5933 + endloop + endfacet + facet normal 0.50159 0.106324 0.858547 + outer loop + vertex 1.10369 1.81371 2.59523 + vertex 1.10701 1.81368 2.5933 + vertex 1.10418 1.81784 2.59444 + endloop + endfacet + facet normal 0.462497 0.0729135 0.883618 + outer loop + vertex 1.10418 1.81784 2.59444 + vertex 1.10701 1.81368 2.5933 + vertex 1.10791 1.81787 2.59248 + endloop + endfacet + facet normal 0.319565 0.0705971 0.944931 + outer loop + vertex 1.10467 1.81004 2.59518 + vertex 1.10369 1.81371 2.59523 + vertex 1.10104 1.81097 2.59634 + endloop + endfacet + facet normal 0.464026 0.01115 0.885751 + outer loop + vertex 1.10791 1.81787 2.59248 + vertex 1.10726 1.82176 2.59277 + vertex 1.10418 1.81784 2.59444 + endloop + endfacet + facet normal 0.288032 0.125621 0.949346 + outer loop + vertex 1.10338 1.82274 2.5942 + vertex 1.10697 1.82642 2.59262 + vertex 1.10307 1.82725 2.59369 + endloop + endfacet + facet normal 0.283291 0.0973946 0.954076 + outer loop + vertex 1.10697 1.82642 2.59262 + vertex 1.10662 1.83133 2.59222 + vertex 1.10307 1.82725 2.59369 + endloop + endfacet + facet normal 0.291173 0.13902 0.946515 + outer loop + vertex 1.10678 2.0164 2.55839 + vertex 1.10756 2.021 2.55747 + vertex 1.10305 2.01862 2.55921 + endloop + endfacet + facet normal 0.292106 0.137234 0.946489 + outer loop + vertex 1.10305 2.01862 2.55921 + vertex 1.10756 2.021 2.55747 + vertex 1.10378 2.02305 2.55834 + endloop + endfacet + facet normal 0.296068 0.145628 0.944 + outer loop + vertex 1.10756 2.021 2.55747 + vertex 1.10614 2.02645 2.55708 + vertex 1.10378 2.02305 2.55834 + endloop + endfacet + facet normal 0.316006 0.13021 0.93978 + outer loop + vertex 1.10378 2.02305 2.55834 + vertex 1.10614 2.02645 2.55708 + vertex 1.10225 2.02635 2.5584 + endloop + endfacet + facet normal 0.299676 0.137349 0.944103 + outer loop + vertex 1.10936 2.02871 2.55571 + vertex 1.11026 2.03297 2.5548 + vertex 1.10691 2.03068 2.5562 + endloop + endfacet + facet normal 0.301769 0.140218 0.943014 + outer loop + vertex 1.10691 2.03068 2.5562 + vertex 1.10614 2.02645 2.55708 + vertex 1.10936 2.02871 2.55571 + endloop + endfacet + facet normal 0.322036 0.135276 0.937013 + outer loop + vertex 1.10691 2.03068 2.5562 + vertex 1.10299 2.03083 2.55753 + vertex 1.10614 2.02645 2.55708 + endloop + endfacet + facet normal 0.315978 0.130624 0.939732 + outer loop + vertex 1.10299 2.03083 2.55753 + vertex 1.10225 2.02635 2.5584 + vertex 1.10614 2.02645 2.55708 + endloop + endfacet + facet normal 0.310157 0.142431 0.939955 + outer loop + vertex 1.11026 2.03297 2.5548 + vertex 1.10895 2.03814 2.55445 + vertex 1.106 2.0347 2.55595 + endloop + endfacet + facet normal 0.305457 0.128526 0.943492 + outer loop + vertex 1.10691 2.03068 2.5562 + vertex 1.11026 2.03297 2.5548 + vertex 1.106 2.0347 2.55595 + endloop + endfacet + facet normal 0.322069 0.131938 0.937477 + outer loop + vertex 1.106 2.0347 2.55595 + vertex 1.10299 2.03083 2.55753 + vertex 1.10691 2.03068 2.5562 + endloop + endfacet + facet normal 0.325241 0.129185 0.936765 + outer loop + vertex 1.10198 2.03613 2.55715 + vertex 1.10299 2.03083 2.55753 + vertex 1.106 2.0347 2.55595 + endloop + endfacet + facet normal 0.321978 0.142618 0.935943 + outer loop + vertex 1.10895 2.03814 2.55445 + vertex 1.10775 2.0434 2.55406 + vertex 1.10492 2.03958 2.55562 + endloop + endfacet + facet normal 0.319423 0.133673 0.938137 + outer loop + vertex 1.106 2.0347 2.55595 + vertex 1.10895 2.03814 2.55445 + vertex 1.10492 2.03958 2.55562 + endloop + endfacet + facet normal 0.326926 0.135149 0.935336 + outer loop + vertex 1.10492 2.03958 2.55562 + vertex 1.10198 2.03613 2.55715 + vertex 1.106 2.0347 2.55595 + endloop + endfacet + facet normal 0.331235 0.131074 0.9344 + outer loop + vertex 1.1007 2.04136 2.55687 + vertex 1.10198 2.03613 2.55715 + vertex 1.10492 2.03958 2.55562 + endloop + endfacet + facet normal 0.327666 0.137873 0.934679 + outer loop + vertex 1.10396 2.04361 2.55536 + vertex 1.10492 2.03958 2.55562 + vertex 1.10775 2.0434 2.55406 + endloop + endfacet + facet normal 0.327671 0.138798 0.934541 + outer loop + vertex 1.10396 2.04361 2.55536 + vertex 1.10775 2.0434 2.55406 + vertex 1.10478 2.04779 2.55445 + endloop + endfacet + facet normal 0.331963 0.141884 0.932561 + outer loop + vertex 1.10478 2.04779 2.55445 + vertex 1.10775 2.0434 2.55406 + vertex 1.10816 2.04711 2.55335 + endloop + endfacet + facet normal 0.334038 0.139227 0.93222 + outer loop + vertex 1.10492 2.03958 2.55562 + vertex 1.10396 2.04361 2.55536 + vertex 1.1007 2.04136 2.55687 + endloop + endfacet + facet normal 0.331523 0.138618 0.933208 + outer loop + vertex 1.10816 2.04711 2.55335 + vertex 1.10831 2.05099 2.55273 + vertex 1.10478 2.04779 2.55445 + endloop + endfacet + facet normal 0.336521 0.132609 0.932292 + outer loop + vertex 1.10478 2.04779 2.55445 + vertex 1.10831 2.05099 2.55273 + vertex 1.10336 2.05359 2.55414 + endloop + endfacet + facet normal 0.338745 0.137672 0.930751 + outer loop + vertex 1.10831 2.05099 2.55273 + vertex 1.10702 2.05648 2.55238 + vertex 1.10336 2.05359 2.55414 + endloop + endfacet + facet normal 0.341916 0.133334 0.930223 + outer loop + vertex 1.10336 2.05359 2.55414 + vertex 1.10702 2.05648 2.55238 + vertex 1.10371 2.05816 2.55336 + endloop + endfacet + facet normal 0.342211 0.134038 0.930014 + outer loop + vertex 1.10702 2.05648 2.55238 + vertex 1.10591 2.06157 2.55206 + vertex 1.10371 2.05816 2.55336 + endloop + endfacet + facet normal 0.353481 0.125586 0.926973 + outer loop + vertex 1.10371 2.05816 2.55336 + vertex 1.10591 2.06157 2.55206 + vertex 1.10233 2.06132 2.55346 + endloop + endfacet + facet normal 0.341672 0.144364 0.928665 + outer loop + vertex 1.10908 2.06373 2.55058 + vertex 1.10975 2.06799 2.54966 + vertex 1.10661 2.06578 2.55117 + endloop + endfacet + facet normal 0.339048 0.140757 0.93018 + outer loop + vertex 1.10661 2.06578 2.55117 + vertex 1.10591 2.06157 2.55206 + vertex 1.10908 2.06373 2.55058 + endloop + endfacet + facet normal 0.36331 0.134994 0.921836 + outer loop + vertex 1.10661 2.06578 2.55117 + vertex 1.10276 2.06594 2.55266 + vertex 1.10591 2.06157 2.55206 + endloop + endfacet + facet normal 0.353318 0.127111 0.926828 + outer loop + vertex 1.10276 2.06594 2.55266 + vertex 1.10233 2.06132 2.55346 + vertex 1.10591 2.06157 2.55206 + endloop + endfacet + facet normal 0.347871 0.15205 0.925131 + outer loop + vertex 1.10975 2.06799 2.54966 + vertex 1.10832 2.07352 2.54929 + vertex 1.10551 2.06982 2.55096 + endloop + endfacet + facet normal 0.344003 0.140831 0.928347 + outer loop + vertex 1.10661 2.06578 2.55117 + vertex 1.10975 2.06799 2.54966 + vertex 1.10551 2.06982 2.55096 + endloop + endfacet + facet normal 0.363146 0.145585 0.920288 + outer loop + vertex 1.10551 2.06982 2.55096 + vertex 1.10276 2.06594 2.55266 + vertex 1.10661 2.06578 2.55117 + endloop + endfacet + facet normal 0.383929 0.128313 0.914404 + outer loop + vertex 1.10136 2.072 2.5524 + vertex 1.10276 2.06594 2.55266 + vertex 1.10551 2.06982 2.55096 + endloop + endfacet + facet normal 0.357261 0.143899 0.922853 + outer loop + vertex 1.10446 2.07388 2.55073 + vertex 1.10551 2.06982 2.55096 + vertex 1.10832 2.07352 2.54929 + endloop + endfacet + facet normal 0.356986 0.135279 0.924262 + outer loop + vertex 1.10446 2.07388 2.55073 + vertex 1.10832 2.07352 2.54929 + vertex 1.10524 2.07799 2.54983 + endloop + endfacet + facet normal 0.367449 0.143141 0.918962 + outer loop + vertex 1.10524 2.07799 2.54983 + vertex 1.10832 2.07352 2.54929 + vertex 1.10889 2.07798 2.54837 + endloop + endfacet + facet normal 0.393831 0.152496 0.906445 + outer loop + vertex 1.10551 2.06982 2.55096 + vertex 1.10446 2.07388 2.55073 + vertex 1.10136 2.072 2.5524 + endloop + endfacet + facet normal 0.367825 0.13575 0.919933 + outer loop + vertex 1.10889 2.07798 2.54837 + vertex 1.10743 2.08127 2.54847 + vertex 1.10524 2.07799 2.54983 + endloop + endfacet + facet normal 0.394263 0.114778 0.911802 + outer loop + vertex 1.10524 2.07799 2.54983 + vertex 1.10743 2.08127 2.54847 + vertex 1.10435 2.08306 2.54958 + endloop + endfacet + facet normal 0.394085 0.114395 0.911927 + outer loop + vertex 1.10743 2.08127 2.54847 + vertex 1.10784 2.08594 2.54771 + vertex 1.10435 2.08306 2.54958 + endloop + endfacet + facet normal 0.397319 0.109933 0.911072 + outer loop + vertex 1.10435 2.08306 2.54958 + vertex 1.10784 2.08594 2.54771 + vertex 1.10356 2.08811 2.54931 + endloop + endfacet + facet normal 0.404595 0.128495 0.905424 + outer loop + vertex 1.10784 2.08594 2.54771 + vertex 1.10641 2.09202 2.54748 + vertex 1.10356 2.08811 2.54931 + endloop + endfacet + facet normal 0.401536 0.131183 0.906399 + outer loop + vertex 1.10356 2.08811 2.54931 + vertex 1.10641 2.09202 2.54748 + vertex 1.10204 2.09307 2.54927 + endloop + endfacet + facet normal 0.392955 0.138829 0.909018 + outer loop + vertex 1.10951 2.09392 2.54586 + vertex 1.11034 2.09786 2.5449 + vertex 1.10734 2.09617 2.54646 + endloop + endfacet + facet normal 0.391861 0.137598 0.909677 + outer loop + vertex 1.10734 2.09617 2.54646 + vertex 1.10641 2.09202 2.54748 + vertex 1.10951 2.09392 2.54586 + endloop + endfacet + facet normal 0.392829 0.137289 0.909306 + outer loop + vertex 1.10734 2.09617 2.54646 + vertex 1.10404 2.09686 2.54778 + vertex 1.10641 2.09202 2.54748 + endloop + endfacet + facet normal 0.403287 0.142734 0.903873 + outer loop + vertex 1.10404 2.09686 2.54778 + vertex 1.10204 2.09307 2.54927 + vertex 1.10641 2.09202 2.54748 + endloop + endfacet + facet normal 0.394739 0.145623 0.90718 + outer loop + vertex 1.11034 2.09786 2.5449 + vertex 1.10921 2.10311 2.54455 + vertex 1.10648 2.10004 2.54623 + endloop + endfacet + facet normal 0.392284 0.140105 0.909112 + outer loop + vertex 1.10734 2.09617 2.54646 + vertex 1.11034 2.09786 2.5449 + vertex 1.10648 2.10004 2.54623 + endloop + endfacet + facet normal 0.393207 0.140286 0.908685 + outer loop + vertex 1.10648 2.10004 2.54623 + vertex 1.10404 2.09686 2.54778 + vertex 1.10734 2.09617 2.54646 + endloop + endfacet + facet normal 0.376983 0.154835 0.913187 + outer loop + vertex 1.10256 2.10156 2.54759 + vertex 1.10404 2.09686 2.54778 + vertex 1.10648 2.10004 2.54623 + endloop + endfacet + facet normal 0.38831 0.158295 0.907831 + outer loop + vertex 1.10921 2.10311 2.54455 + vertex 1.1076 2.10864 2.54427 + vertex 1.1052 2.10473 2.54598 + endloop + endfacet + facet normal 0.386944 0.153693 0.909204 + outer loop + vertex 1.10648 2.10004 2.54623 + vertex 1.10921 2.10311 2.54455 + vertex 1.1052 2.10473 2.54598 + endloop + endfacet + facet normal 0.375861 0.150954 0.914298 + outer loop + vertex 1.1052 2.10473 2.54598 + vertex 1.10256 2.10156 2.54759 + vertex 1.10648 2.10004 2.54623 + endloop + endfacet + facet normal 0.341865 0.183146 0.92173 + outer loop + vertex 1.10094 2.10652 2.54721 + vertex 1.10256 2.10156 2.54759 + vertex 1.1052 2.10473 2.54598 + endloop + endfacet + facet normal 0.365571 0.175 0.914184 + outer loop + vertex 1.10388 2.1087 2.54575 + vertex 1.1052 2.10473 2.54598 + vertex 1.1076 2.10864 2.54427 + endloop + endfacet + facet normal 0.362724 0.221845 0.905105 + outer loop + vertex 1.10388 2.1087 2.54575 + vertex 1.1076 2.10864 2.54427 + vertex 1.10388 2.11323 2.54464 + endloop + endfacet + facet normal 0.313961 0.180157 0.932187 + outer loop + vertex 1.10388 2.11323 2.54464 + vertex 1.1076 2.10864 2.54427 + vertex 1.10764 2.11246 2.54352 + endloop + endfacet + facet normal 0.336144 0.165933 0.927078 + outer loop + vertex 1.1052 2.10473 2.54598 + vertex 1.10388 2.1087 2.54575 + vertex 1.10094 2.10652 2.54721 + endloop + endfacet + facet normal 0.321381 0.240358 0.915938 + outer loop + vertex 1.10764 2.11246 2.54352 + vertex 1.10794 2.11606 2.54247 + vertex 1.10388 2.11323 2.54464 + endloop + endfacet + facet normal 0.304158 0.264439 0.915183 + outer loop + vertex 1.10388 2.11323 2.54464 + vertex 1.10794 2.11606 2.54247 + vertex 1.10381 2.11785 2.54333 + endloop + endfacet + facet normal 0.32116 0.313941 0.893475 + outer loop + vertex 1.10794 2.11606 2.54247 + vertex 1.10629 2.1205 2.5415 + vertex 1.10381 2.11785 2.54333 + endloop + endfacet + facet normal 0.239854 0.38778 0.889998 + outer loop + vertex 1.10381 2.11785 2.54333 + vertex 1.10629 2.1205 2.5415 + vertex 1.10181 2.12106 2.54247 + endloop + endfacet + facet normal 0.207542 0.700108 0.68321 + outer loop + vertex 1.10412 2.12362 2.54024 + vertex 1.10867 2.12338 2.5391 + vertex 1.10608 2.12575 2.53746 + endloop + endfacet + facet normal 0.0911176 0.758175 0.645653 + outer loop + vertex 1.10145 2.12574 2.53812 + vertex 1.10412 2.12362 2.54024 + vertex 1.10608 2.12575 2.53746 + endloop + endfacet + facet normal 0.241219 0.504021 0.829323 + outer loop + vertex 1.10629 2.1205 2.5415 + vertex 1.10412 2.12362 2.54024 + vertex 1.10181 2.12106 2.54247 + endloop + endfacet + facet normal 0.234653 0.50096 0.833053 + outer loop + vertex 1.10867 2.12338 2.5391 + vertex 1.10412 2.12362 2.54024 + vertex 1.10629 2.1205 2.5415 + endloop + endfacet + facet normal -0.0736452 0.438391 0.895762 + outer loop + vertex 1.11 2.13427 2.525 + vertex 1.105 2.13343 2.525 + vertex 1.10858 2.13035 2.5268 + endloop + endfacet + facet normal -0.0264326 0.481631 0.875975 + outer loop + vertex 1.10858 2.13035 2.5268 + vertex 1.105 2.13343 2.525 + vertex 1.1039 2.13003 2.52683 + endloop + endfacet + facet normal -0.0567937 0.89357 0.445317 + outer loop + vertex 1.10858 2.13035 2.5268 + vertex 1.1039 2.13003 2.52683 + vertex 1.10752 2.12877 2.52984 + endloop + endfacet + facet normal 0.00936828 0.925335 0.379036 + outer loop + vertex 1.10752 2.12877 2.52984 + vertex 1.1039 2.13003 2.52683 + vertex 1.10358 2.12848 2.53064 + endloop + endfacet + facet normal -0.00209366 0.94421 0.329338 + outer loop + vertex 1.10752 2.12877 2.52984 + vertex 1.10358 2.12848 2.53064 + vertex 1.10814 2.12736 2.53388 + endloop + endfacet + facet normal 0.0262577 0.955615 0.293445 + outer loop + vertex 1.10814 2.12736 2.53388 + vertex 1.10358 2.12848 2.53064 + vertex 1.1029 2.12726 2.53467 + endloop + endfacet + facet normal 0.0590898 0.904467 0.422432 + outer loop + vertex 1.10608 2.12575 2.53746 + vertex 1.1029 2.12726 2.53467 + vertex 1.10145 2.12574 2.53812 + endloop + endfacet + facet normal 0.0483728 0.900366 0.432436 + outer loop + vertex 1.10814 2.12736 2.53388 + vertex 1.1029 2.12726 2.53467 + vertex 1.10608 2.12575 2.53746 + endloop + endfacet + facet normal -0.383934 0.878906 0.283054 + outer loop + vertex 1.11 2.13576 2.52 + vertex 1.10826 2.135 2.52 + vertex 1.11 2.135 2.52236 + endloop + endfacet + facet normal -0.360372 -0.901828 -0.238407 + outer loop + vertex 1.115 0.892103 2.52 + vertex 1.11331 0.892266 2.52194 + vertex 1.11 0.894101 2.52 + endloop + endfacet + facet normal -0.399 -0.900769 -0.171504 + outer loop + vertex 1.11331 0.892266 2.52194 + vertex 1.11 0.893149 2.525 + vertex 1.11 0.894101 2.52 + endloop + endfacet + facet normal -0.0296994 -0.968462 0.247384 + outer loop + vertex 1.11331 0.892266 2.52194 + vertex 1.11179 0.893127 2.52513 + vertex 1.11 0.893149 2.525 + endloop + endfacet + facet normal -0.0484945 -0.847708 0.528241 + outer loop + vertex 1.11179 0.893127 2.52513 + vertex 1.1071 0.893594 2.52545 + vertex 1.11 0.893149 2.525 + endloop + endfacet + facet normal -0.0698122 -0.93657 0.343458 + outer loop + vertex 1.11179 0.893127 2.52513 + vertex 1.10973 0.894405 2.52819 + vertex 1.1071 0.893594 2.52545 + endloop + endfacet + facet normal -0.0563379 -0.934433 0.351655 + outer loop + vertex 1.11469 0.894094 2.52816 + vertex 1.10973 0.894405 2.52819 + vertex 1.11179 0.893127 2.52513 + endloop + endfacet + facet normal -0.0517497 -0.874639 0.482004 + outer loop + vertex 1.10973 0.894405 2.52819 + vertex 1.11469 0.894094 2.52816 + vertex 1.11234 0.895996 2.53136 + endloop + endfacet + facet normal 0.0261515 -0.901784 0.431395 + outer loop + vertex 1.10685 0.895999 2.5317 + vertex 1.10973 0.894405 2.52819 + vertex 1.11234 0.895996 2.53136 + endloop + endfacet + facet normal 0.0319986 -0.850169 0.525537 + outer loop + vertex 1.11234 0.895996 2.53136 + vertex 1.11001 0.897872 2.53454 + vertex 1.10685 0.895999 2.5317 + endloop + endfacet + facet normal 0.0939914 -0.825506 0.556512 + outer loop + vertex 1.11461 0.898127 2.53414 + vertex 1.11001 0.897872 2.53454 + vertex 1.11234 0.895996 2.53136 + endloop + endfacet + facet normal 0.0965221 -0.785665 0.611076 + outer loop + vertex 1.11001 0.897872 2.53454 + vertex 1.11461 0.898127 2.53414 + vertex 1.11201 0.899772 2.53666 + endloop + endfacet + facet normal 0.135109 -0.798665 0.586413 + outer loop + vertex 1.10764 0.899942 2.5379 + vertex 1.11001 0.897872 2.53454 + vertex 1.11201 0.899772 2.53666 + endloop + endfacet + facet normal 0.168878 -0.70176 0.692108 + outer loop + vertex 1.11201 0.899772 2.53666 + vertex 1.11148 0.902337 2.53939 + vertex 1.10764 0.899942 2.5379 + endloop + endfacet + facet normal 0.190468 -0.720601 0.666675 + outer loop + vertex 1.11148 0.902337 2.53939 + vertex 1.10735 0.902514 2.54077 + vertex 1.10764 0.899942 2.5379 + endloop + endfacet + facet normal 0.24222 -0.548446 0.800335 + outer loop + vertex 1.11148 0.902337 2.53939 + vertex 1.10969 0.905136 2.54185 + vertex 1.10735 0.902514 2.54077 + endloop + endfacet + facet normal 0.255134 -0.541067 0.801344 + outer loop + vertex 1.11287 0.905172 2.54087 + vertex 1.10969 0.905136 2.54185 + vertex 1.11148 0.902337 2.53939 + endloop + endfacet + facet normal 0.28468 -0.317228 0.904612 + outer loop + vertex 1.11287 0.905172 2.54087 + vertex 1.11276 0.90836 2.54202 + vertex 1.10969 0.905136 2.54185 + endloop + endfacet + facet normal 0.30065 -0.331876 0.894129 + outer loop + vertex 1.10969 0.905136 2.54185 + vertex 1.11276 0.90836 2.54202 + vertex 1.10896 0.908878 2.54349 + endloop + endfacet + facet normal 0.282931 -0.132132 0.949995 + outer loop + vertex 1.10829 0.999484 2.55901 + vertex 1.11349 1.00414 2.55811 + vertex 1.10933 1.0051 2.55948 + endloop + endfacet + facet normal 0.27413 -0.166297 0.947205 + outer loop + vertex 1.11349 1.00414 2.55811 + vertex 1.11369 1.00917 2.55893 + vertex 1.10933 1.0051 2.55948 + endloop + endfacet + facet normal 0.25062 -0.139668 0.957957 + outer loop + vertex 1.10933 1.0051 2.55948 + vertex 1.11369 1.00917 2.55893 + vertex 1.10979 1.00965 2.56002 + endloop + endfacet + facet normal 0.290874 -0.154023 0.944282 + outer loop + vertex 1.10962 1.01274 2.56058 + vertex 1.10709 1.01026 2.56096 + vertex 1.10979 1.00965 2.56002 + endloop + endfacet + facet normal 0.229735 -0.160297 0.959962 + outer loop + vertex 1.10962 1.01274 2.56058 + vertex 1.10979 1.00965 2.56002 + vertex 1.11349 1.01402 2.55987 + endloop + endfacet + facet normal 0.245271 -0.173645 0.953776 + outer loop + vertex 1.11349 1.01402 2.55987 + vertex 1.10979 1.00965 2.56002 + vertex 1.11369 1.00917 2.55893 + endloop + endfacet + facet normal 0.31014 -0.175123 0.934422 + outer loop + vertex 1.10962 1.01274 2.56058 + vertex 1.10709 1.01341 2.56155 + vertex 1.10709 1.01026 2.56096 + endloop + endfacet + facet normal 0.240124 -0.172864 0.955227 + outer loop + vertex 1.10944 1.17326 2.59044 + vertex 1.10775 1.17481 2.59115 + vertex 1.1062 1.17131 2.5909 + endloop + endfacet + facet normal 0.462809 -0.0786133 0.882965 + outer loop + vertex 1.11291 1.1735 2.589 + vertex 1.11373 1.17932 2.58908 + vertex 1.11061 1.17699 2.59051 + endloop + endfacet + facet normal 0.389252 -0.138863 0.910604 + outer loop + vertex 1.10944 1.17326 2.59044 + vertex 1.11291 1.1735 2.589 + vertex 1.11061 1.17699 2.59051 + endloop + endfacet + facet normal 0.295123 -0.110001 0.949106 + outer loop + vertex 1.11061 1.17699 2.59051 + vertex 1.10775 1.17481 2.59115 + vertex 1.10944 1.17326 2.59044 + endloop + endfacet + facet normal 0.285642 -0.0962568 0.95349 + outer loop + vertex 1.10752 1.17814 2.59155 + vertex 1.10775 1.17481 2.59115 + vertex 1.11061 1.17699 2.59051 + endloop + endfacet + facet normal 0.486545 -0.0340383 0.872992 + outer loop + vertex 1.11373 1.17932 2.58908 + vertex 1.1139 1.18441 2.58918 + vertex 1.1109 1.18156 2.59075 + endloop + endfacet + facet normal 0.460733 -0.0749781 0.884366 + outer loop + vertex 1.11061 1.17699 2.59051 + vertex 1.11373 1.17932 2.58908 + vertex 1.1109 1.18156 2.59075 + endloop + endfacet + facet normal 0.295903 -0.0681605 0.952783 + outer loop + vertex 1.1109 1.18156 2.59075 + vertex 1.10752 1.17814 2.59155 + vertex 1.11061 1.17699 2.59051 + endloop + endfacet + facet normal 0.31946 -0.0938022 0.942946 + outer loop + vertex 1.10743 1.18273 2.59204 + vertex 1.10752 1.17814 2.59155 + vertex 1.1109 1.18156 2.59075 + endloop + endfacet + facet normal 0.520163 -0.0231672 0.853753 + outer loop + vertex 1.1139 1.18441 2.58918 + vertex 1.11397 1.18937 2.58928 + vertex 1.11098 1.18641 2.59102 + endloop + endfacet + facet normal 0.502699 -0.0567565 0.862597 + outer loop + vertex 1.1109 1.18156 2.59075 + vertex 1.1139 1.18441 2.58918 + vertex 1.11098 1.18641 2.59102 + endloop + endfacet + facet normal 0.330908 -0.0586562 0.941838 + outer loop + vertex 1.11098 1.18641 2.59102 + vertex 1.10743 1.18273 2.59204 + vertex 1.1109 1.18156 2.59075 + endloop + endfacet + facet normal 0.358747 -0.0889496 0.929187 + outer loop + vertex 1.10742 1.18765 2.59251 + vertex 1.10743 1.18273 2.59204 + vertex 1.11098 1.18641 2.59102 + endloop + endfacet + facet normal 0.555458 -0.0188563 0.831331 + outer loop + vertex 1.11397 1.18937 2.58928 + vertex 1.11402 1.19428 2.58935 + vertex 1.11103 1.19134 2.59129 + endloop + endfacet + facet normal 0.539885 -0.0511771 0.840182 + outer loop + vertex 1.11098 1.18641 2.59102 + vertex 1.11397 1.18937 2.58928 + vertex 1.11103 1.19134 2.59129 + endloop + endfacet + facet normal 0.370119 -0.0541366 0.927406 + outer loop + vertex 1.11103 1.19134 2.59129 + vertex 1.10742 1.18765 2.59251 + vertex 1.11098 1.18641 2.59102 + endloop + endfacet + facet normal 0.388732 -0.0753807 0.918262 + outer loop + vertex 1.10742 1.19265 2.59292 + vertex 1.10742 1.18765 2.59251 + vertex 1.11103 1.19134 2.59129 + endloop + endfacet + facet normal 0.581176 0.00287324 0.813773 + outer loop + vertex 1.11402 1.19428 2.58935 + vertex 1.114 1.1992 2.58935 + vertex 1.11103 1.19626 2.59149 + endloop + endfacet + facet normal 0.565012 -0.0331466 0.824417 + outer loop + vertex 1.11103 1.19134 2.59129 + vertex 1.11402 1.19428 2.58935 + vertex 1.11103 1.19626 2.59149 + endloop + endfacet + facet normal 0.401367 -0.0367356 0.91518 + outer loop + vertex 1.11103 1.19626 2.59149 + vertex 1.10742 1.19265 2.59292 + vertex 1.11103 1.19134 2.59129 + endloop + endfacet + facet normal 0.417715 -0.0564054 0.906826 + outer loop + vertex 1.10745 1.19768 2.59322 + vertex 1.10742 1.19265 2.59292 + vertex 1.11103 1.19626 2.59149 + endloop + endfacet + facet normal 0.605922 0.0389615 0.79457 + outer loop + vertex 1.114 1.1992 2.58935 + vertex 1.11388 1.2042 2.5892 + vertex 1.11096 1.2012 2.59157 + endloop + endfacet + facet normal 0.587117 -0.0062274 0.809478 + outer loop + vertex 1.11103 1.19626 2.59149 + vertex 1.114 1.1992 2.58935 + vertex 1.11096 1.2012 2.59157 + endloop + endfacet + facet normal 0.433447 -0.00982849 0.901125 + outer loop + vertex 1.11096 1.2012 2.59157 + vertex 1.10745 1.19768 2.59322 + vertex 1.11103 1.19626 2.59149 + endloop + endfacet + facet normal 0.451062 -0.0317715 0.891927 + outer loop + vertex 1.10747 1.20271 2.59339 + vertex 1.10745 1.19768 2.59322 + vertex 1.11096 1.2012 2.59157 + endloop + endfacet + facet normal 0.638098 0.0736093 0.766428 + outer loop + vertex 1.11388 1.2042 2.5892 + vertex 1.11369 1.20938 2.58886 + vertex 1.11084 1.20623 2.59154 + endloop + endfacet + facet normal 0.617879 0.0206407 0.786002 + outer loop + vertex 1.11096 1.2012 2.59157 + vertex 1.11388 1.2042 2.5892 + vertex 1.11084 1.20623 2.59154 + endloop + endfacet + facet normal 0.468057 0.0176297 0.883523 + outer loop + vertex 1.11084 1.20623 2.59154 + vertex 1.10747 1.20271 2.59339 + vertex 1.11096 1.2012 2.59157 + endloop + endfacet + facet normal 0.499803 -0.0221697 0.865856 + outer loop + vertex 1.10743 1.20783 2.59354 + vertex 1.10747 1.20271 2.59339 + vertex 1.11084 1.20623 2.59154 + endloop + endfacet + facet normal 0.685635 0.0832398 0.723171 + outer loop + vertex 1.11369 1.20938 2.58886 + vertex 1.11341 1.21463 2.58852 + vertex 1.1107 1.21143 2.59146 + endloop + endfacet + facet normal 0.666971 0.0288621 0.744525 + outer loop + vertex 1.11084 1.20623 2.59154 + vertex 1.11369 1.20938 2.58886 + vertex 1.1107 1.21143 2.59146 + endloop + endfacet + facet normal 0.516644 0.0262959 0.855796 + outer loop + vertex 1.1107 1.21143 2.59146 + vertex 1.10743 1.20783 2.59354 + vertex 1.11084 1.20623 2.59154 + endloop + endfacet + facet normal 0.565976 -0.0370019 0.823591 + outer loop + vertex 1.10731 1.21343 2.59388 + vertex 1.10743 1.20783 2.59354 + vertex 1.1107 1.21143 2.59146 + endloop + endfacet + facet normal 0.745671 0.0891267 0.660327 + outer loop + vertex 1.11341 1.21463 2.58852 + vertex 1.11309 1.21976 2.58819 + vertex 1.1107 1.21675 2.59129 + endloop + endfacet + facet normal 0.723173 0.0211436 0.690344 + outer loop + vertex 1.1107 1.21143 2.59146 + vertex 1.11341 1.21463 2.58852 + vertex 1.1107 1.21675 2.59129 + endloop + endfacet + facet normal 0.59046 0.0249863 0.80668 + outer loop + vertex 1.1107 1.21675 2.59129 + vertex 1.10731 1.21343 2.59388 + vertex 1.1107 1.21143 2.59146 + endloop + endfacet + facet normal 0.640741 -0.0584421 0.76553 + outer loop + vertex 1.10816 1.2192 2.59361 + vertex 1.10731 1.21343 2.59388 + vertex 1.1107 1.21675 2.59129 + endloop + endfacet + facet normal 0.802343 0.0919256 0.589741 + outer loop + vertex 1.11309 1.21976 2.58819 + vertex 1.11289 1.22463 2.5877 + vertex 1.11082 1.22203 2.59093 + endloop + endfacet + facet normal 0.779784 0.0262067 0.6255 + outer loop + vertex 1.1107 1.21675 2.59129 + vertex 1.11309 1.21976 2.58819 + vertex 1.11082 1.22203 2.59093 + endloop + endfacet + facet normal 0.691174 0.0348869 0.721846 + outer loop + vertex 1.11082 1.22203 2.59093 + vertex 1.10816 1.2192 2.59361 + vertex 1.1107 1.21675 2.59129 + endloop + endfacet + facet normal 0.713384 -0.00599785 0.700748 + outer loop + vertex 1.10841 1.22448 2.5934 + vertex 1.10816 1.2192 2.59361 + vertex 1.11082 1.22203 2.59093 + endloop + endfacet + facet normal 0.84154 0.0871418 0.533119 + outer loop + vertex 1.11289 1.22463 2.5877 + vertex 1.11294 1.22838 2.58702 + vertex 1.11101 1.22766 2.59018 + endloop + endfacet + facet normal 0.822409 0.0475837 0.566903 + outer loop + vertex 1.11082 1.22203 2.59093 + vertex 1.11289 1.22463 2.5877 + vertex 1.11101 1.22766 2.59018 + endloop + endfacet + facet normal 0.745359 0.0629535 0.663684 + outer loop + vertex 1.11101 1.22766 2.59018 + vertex 1.10841 1.22448 2.5934 + vertex 1.11082 1.22203 2.59093 + endloop + endfacet + facet normal 0.770514 0.0156602 0.637231 + outer loop + vertex 1.10837 1.22973 2.59332 + vertex 1.10841 1.22448 2.5934 + vertex 1.11101 1.22766 2.59018 + endloop + endfacet + facet normal 0.895433 0.100255 0.433762 + outer loop + vertex 1.1137 1.23095 2.58494 + vertex 1.11356 1.23469 2.58438 + vertex 1.11242 1.23174 2.58742 + endloop + endfacet + facet normal 0.894869 0.0866035 0.437845 + outer loop + vertex 1.11294 1.22838 2.58702 + vertex 1.1137 1.23095 2.58494 + vertex 1.11242 1.23174 2.58742 + endloop + endfacet + facet normal 0.844823 0.0678345 0.530728 + outer loop + vertex 1.11294 1.22838 2.58702 + vertex 1.11242 1.23174 2.58742 + vertex 1.11101 1.22766 2.59018 + endloop + endfacet + facet normal 0.85385 0.0557824 0.517521 + outer loop + vertex 1.11101 1.22766 2.59018 + vertex 1.11242 1.23174 2.58742 + vertex 1.11051 1.23305 2.59042 + endloop + endfacet + facet normal 0.778933 0.0441105 0.625554 + outer loop + vertex 1.11051 1.23305 2.59042 + vertex 1.10837 1.22973 2.59332 + vertex 1.11101 1.22766 2.59018 + endloop + endfacet + facet normal 0.785297 0.0335625 0.618209 + outer loop + vertex 1.10816 1.23483 2.5933 + vertex 1.10837 1.22973 2.59332 + vertex 1.11051 1.23305 2.59042 + endloop + endfacet + facet normal 0.910734 0.0945043 0.402035 + outer loop + vertex 1.11356 1.23469 2.58438 + vertex 1.11323 1.23927 2.58403 + vertex 1.11212 1.23628 2.58726 + endloop + endfacet + facet normal 0.908067 0.0733205 0.412356 + outer loop + vertex 1.11242 1.23174 2.58742 + vertex 1.11356 1.23469 2.58438 + vertex 1.11212 1.23628 2.58726 + endloop + endfacet + facet normal 0.856204 0.0732863 0.511414 + outer loop + vertex 1.11242 1.23174 2.58742 + vertex 1.11212 1.23628 2.58726 + vertex 1.11051 1.23305 2.59042 + endloop + endfacet + facet normal 0.863152 0.0600347 0.501363 + outer loop + vertex 1.11212 1.23628 2.58726 + vertex 1.11025 1.23802 2.59027 + vertex 1.11051 1.23305 2.59042 + endloop + endfacet + facet normal 0.792023 0.0595869 0.607576 + outer loop + vertex 1.11025 1.23802 2.59027 + vertex 1.10816 1.23483 2.5933 + vertex 1.11051 1.23305 2.59042 + endloop + endfacet + facet normal 0.796711 0.0513642 0.602174 + outer loop + vertex 1.10799 1.23977 2.59312 + vertex 1.10816 1.23483 2.5933 + vertex 1.11025 1.23802 2.59027 + endloop + endfacet + facet normal -0.405712 -0.196527 0.892622 + outer loop + vertex 1.115 1.24372 2.58 + vertex 1.11438 1.245 2.58 + vertex 1.11446 1.24371 2.57975 + endloop + endfacet + facet normal 0.919234 0.0635097 0.388555 + outer loop + vertex 1.11323 1.23927 2.58403 + vertex 1.11301 1.24401 2.5838 + vertex 1.11189 1.24118 2.58691 + endloop + endfacet + facet normal 0.92058 0.0713318 0.383986 + outer loop + vertex 1.11212 1.23628 2.58726 + vertex 1.11323 1.23927 2.58403 + vertex 1.11189 1.24118 2.58691 + endloop + endfacet + facet normal 0.86626 0.0766829 0.493674 + outer loop + vertex 1.11212 1.23628 2.58726 + vertex 1.11189 1.24118 2.58691 + vertex 1.11025 1.23802 2.59027 + endloop + endfacet + facet normal 0.867601 0.0739339 0.491735 + outer loop + vertex 1.11189 1.24118 2.58691 + vertex 1.11004 1.24298 2.5899 + vertex 1.11025 1.23802 2.59027 + endloop + endfacet + facet normal 0.803119 0.078371 0.590642 + outer loop + vertex 1.11004 1.24298 2.5899 + vertex 1.10799 1.23977 2.59312 + vertex 1.11025 1.23802 2.59027 + endloop + endfacet + facet normal 0.814327 0.0580352 0.577498 + outer loop + vertex 1.1079 1.24454 2.59276 + vertex 1.10799 1.23977 2.59312 + vertex 1.11004 1.24298 2.5899 + endloop + endfacet + facet normal 0.93563 0.170293 -0.309187 + outer loop + vertex 1.11438 1.245 2.58 + vertex 1.11347 1.25 2.58 + vertex 1.115 1.25 2.58463 + endloop + endfacet + facet normal 0.96478 0.104084 -0.241591 + outer loop + vertex 1.11446 1.24371 2.57975 + vertex 1.11438 1.245 2.58 + vertex 1.115 1.25 2.58463 + endloop + endfacet + facet normal 0.874036 -0.0739754 0.480196 + outer loop + vertex 1.11301 1.24401 2.5838 + vertex 1.11339 1.24856 2.5838 + vertex 1.11191 1.2472 2.58628 + endloop + endfacet + facet normal 0.930118 0.0340603 0.365677 + outer loop + vertex 1.11189 1.24118 2.58691 + vertex 1.11301 1.24401 2.5838 + vertex 1.11191 1.2472 2.58628 + endloop + endfacet + facet normal 0.862525 0.0487855 0.503658 + outer loop + vertex 1.11189 1.24118 2.58691 + vertex 1.11191 1.2472 2.58628 + vertex 1.11004 1.24298 2.5899 + endloop + endfacet + facet normal 0.841575 0.0837643 0.533605 + outer loop + vertex 1.11191 1.2472 2.58628 + vertex 1.10971 1.24765 2.58969 + vertex 1.11004 1.24298 2.5899 + endloop + endfacet + facet normal 0.819342 0.0837243 0.567158 + outer loop + vertex 1.10971 1.24765 2.58969 + vertex 1.1079 1.24454 2.59276 + vertex 1.11004 1.24298 2.5899 + endloop + endfacet + facet normal 0.831779 0.0612351 0.551719 + outer loop + vertex 1.10802 1.24829 2.59216 + vertex 1.1079 1.24454 2.59276 + vertex 1.10971 1.24765 2.58969 + endloop + endfacet + facet normal -0.522732 -0.0568556 0.850599 + outer loop + vertex 1.11339 1.24856 2.5838 + vertex 1.115 1.25169 2.585 + vertex 1.11464 1.255 2.585 + endloop + endfacet + facet normal 0.885995 -0.245033 0.393664 + outer loop + vertex 1.11339 1.24856 2.5838 + vertex 1.11464 1.255 2.585 + vertex 1.11191 1.2472 2.58628 + endloop + endfacet + facet normal 0.501607 -0.0333308 0.864453 + outer loop + vertex 1.11191 1.2472 2.58628 + vertex 1.11464 1.255 2.585 + vertex 1.11112 1.25313 2.58697 + endloop + endfacet + facet normal 0.806232 0.0973564 0.583533 + outer loop + vertex 1.1091 1.2509 2.59013 + vertex 1.11112 1.25313 2.58697 + vertex 1.10911 1.25491 2.58945 + endloop + endfacet + facet normal 0.815512 0.0751519 0.573841 + outer loop + vertex 1.1091 1.2509 2.59013 + vertex 1.10971 1.24765 2.58969 + vertex 1.11112 1.25313 2.58697 + endloop + endfacet + facet normal 0.841465 0.0506397 0.537934 + outer loop + vertex 1.10971 1.24765 2.58969 + vertex 1.11191 1.2472 2.58628 + vertex 1.11112 1.25313 2.58697 + endloop + endfacet + facet normal 0.832997 0.0820894 0.547153 + outer loop + vertex 1.10971 1.24765 2.58969 + vertex 1.1091 1.2509 2.59013 + vertex 1.10802 1.24829 2.59216 + endloop + endfacet + facet normal 0.446657 0.0964811 0.889488 + outer loop + vertex 1.11464 1.255 2.585 + vertex 1.11356 1.26 2.585 + vertex 1.11112 1.25313 2.58697 + endloop + endfacet + facet normal 0.398153 0.119482 0.909504 + outer loop + vertex 1.11356 1.26 2.585 + vertex 1.11079 1.25902 2.58634 + vertex 1.11112 1.25313 2.58697 + endloop + endfacet + facet normal 0.808576 0.106839 0.578611 + outer loop + vertex 1.11079 1.25902 2.58634 + vertex 1.10911 1.25491 2.58945 + vertex 1.11112 1.25313 2.58697 + endloop + endfacet + facet normal 0.828158 0.0807483 0.554648 + outer loop + vertex 1.10887 1.25988 2.58908 + vertex 1.10911 1.25491 2.58945 + vertex 1.11079 1.25902 2.58634 + endloop + endfacet + facet normal 0.419408 0.0545172 0.906159 + outer loop + vertex 1.11356 1.26 2.585 + vertex 1.11291 1.265 2.585 + vertex 1.11079 1.25902 2.58634 + endloop + endfacet + facet normal 0.375437 0.0741117 0.92388 + outer loop + vertex 1.11291 1.265 2.585 + vertex 1.11027 1.26403 2.58615 + vertex 1.11079 1.25902 2.58634 + endloop + endfacet + facet normal 0.829852 0.106635 0.547699 + outer loop + vertex 1.11027 1.26403 2.58615 + vertex 1.10887 1.25988 2.58908 + vertex 1.11079 1.25902 2.58634 + endloop + endfacet + facet normal 0.858081 0.0696639 0.508768 + outer loop + vertex 1.10853 1.26478 2.58899 + vertex 1.10887 1.25988 2.58908 + vertex 1.11027 1.26403 2.58615 + endloop + endfacet + facet normal 0.386239 0.0417152 0.921455 + outer loop + vertex 1.11291 1.265 2.585 + vertex 1.11237 1.27 2.585 + vertex 1.11027 1.26403 2.58615 + endloop + endfacet + facet normal 0.427657 0.023704 0.90363 + outer loop + vertex 1.11237 1.27 2.585 + vertex 1.10951 1.26792 2.58641 + vertex 1.11027 1.26403 2.58615 + endloop + endfacet + facet normal 0.859769 0.135718 0.492319 + outer loop + vertex 1.10951 1.26792 2.58641 + vertex 1.10853 1.26478 2.58899 + vertex 1.11027 1.26403 2.58615 + endloop + endfacet + facet normal 0.887154 0.0939306 0.451812 + outer loop + vertex 1.10812 1.26953 2.5888 + vertex 1.10853 1.26478 2.58899 + vertex 1.10951 1.26792 2.58641 + endloop + endfacet + facet normal -0.650958 -0.342074 0.677671 + outer loop + vertex 1.10944 1.27317 2.58378 + vertex 1.11237 1.27 2.585 + vertex 1.11 1.27451 2.585 + endloop + endfacet + facet normal 0.53869 0.685505 0.489792 + outer loop + vertex 1.10944 1.27317 2.58378 + vertex 1.10896 1.27227 2.58557 + vertex 1.11237 1.27 2.585 + endloop + endfacet + facet normal 0.299687 0.217305 0.92896 + outer loop + vertex 1.10896 1.27227 2.58557 + vertex 1.10951 1.26792 2.58641 + vertex 1.11237 1.27 2.585 + endloop + endfacet + facet normal 0.899146 0.189301 0.394591 + outer loop + vertex 1.10896 1.27227 2.58557 + vertex 1.10812 1.26953 2.5888 + vertex 1.10951 1.26792 2.58641 + endloop + endfacet + facet normal 0.934977 0.110352 0.337107 + outer loop + vertex 1.10771 1.27421 2.5884 + vertex 1.10812 1.26953 2.5888 + vertex 1.10896 1.27227 2.58557 + endloop + endfacet + facet normal 0.901278 0.23934 0.36113 + outer loop + vertex 1.10855 1.27576 2.58429 + vertex 1.10896 1.27227 2.58557 + vertex 1.10944 1.27317 2.58378 + endloop + endfacet + facet normal 0.960741 0.188706 0.203389 + outer loop + vertex 1.10817 1.2759 2.58593 + vertex 1.10896 1.27227 2.58557 + vertex 1.10855 1.27576 2.58429 + endloop + endfacet + facet normal 0.939398 0.174926 0.294843 + outer loop + vertex 1.10817 1.2759 2.58593 + vertex 1.10771 1.27421 2.5884 + vertex 1.10896 1.27227 2.58557 + endloop + endfacet + facet normal 0.983096 -0.00138267 0.183088 + outer loop + vertex 1.10784 1.27826 2.58772 + vertex 1.10771 1.27421 2.5884 + vertex 1.10817 1.2759 2.58593 + endloop + endfacet + facet normal 0.974649 -0.00865883 0.223574 + outer loop + vertex 1.10855 1.27576 2.58429 + vertex 1.10825 1.27882 2.58569 + vertex 1.10817 1.2759 2.58593 + endloop + endfacet + facet normal 0.980642 -0.0111217 0.195494 + outer loop + vertex 1.10817 1.2759 2.58593 + vertex 1.10825 1.27882 2.58569 + vertex 1.10784 1.27826 2.58772 + endloop + endfacet + facet normal 0.943686 -0.0243808 0.329943 + outer loop + vertex 1.10862 1.75062 2.58491 + vertex 1.10785 1.74735 2.58686 + vertex 1.1085 1.74827 2.58509 + endloop + endfacet + facet normal 0.956919 -0.0541742 0.285256 + outer loop + vertex 1.10862 1.75062 2.58491 + vertex 1.10783 1.75018 2.58748 + vertex 1.10785 1.74735 2.58686 + endloop + endfacet + facet normal -0.28669 0.0895473 0.953829 + outer loop + vertex 1.11 1.75403 2.585 + vertex 1.10862 1.75062 2.58491 + vertex 1.1085 1.74827 2.58509 + endloop + endfacet + facet normal -0.735217 0.280461 0.617088 + outer loop + vertex 1.11 1.75403 2.585 + vertex 1.11037 1.755 2.585 + vertex 1.10862 1.75062 2.58491 + endloop + endfacet + facet normal 0.512025 -0.222557 0.829638 + outer loop + vertex 1.11037 1.755 2.585 + vertex 1.10941 1.75405 2.58534 + vertex 1.10862 1.75062 2.58491 + endloop + endfacet + facet normal 0.937166 -0.247075 0.24632 + outer loop + vertex 1.10941 1.75405 2.58534 + vertex 1.10783 1.75018 2.58748 + vertex 1.10862 1.75062 2.58491 + endloop + endfacet + facet normal 0.921762 -0.189774 0.338142 + outer loop + vertex 1.10844 1.75423 2.58809 + vertex 1.10783 1.75018 2.58748 + vertex 1.10941 1.75405 2.58534 + endloop + endfacet + facet normal 0.478435 -0.177969 0.8599 + outer loop + vertex 1.11037 1.755 2.585 + vertex 1.11223 1.76 2.585 + vertex 1.10941 1.75405 2.58534 + endloop + endfacet + facet normal 0.531326 -0.205172 0.821947 + outer loop + vertex 1.11223 1.76 2.585 + vertex 1.11045 1.75853 2.58578 + vertex 1.10941 1.75405 2.58534 + endloop + endfacet + facet normal 0.909116 -0.244517 0.337222 + outer loop + vertex 1.11045 1.75853 2.58578 + vertex 1.10844 1.75423 2.58809 + vertex 1.10941 1.75405 2.58534 + endloop + endfacet + facet normal 0.867337 -0.151289 0.474171 + outer loop + vertex 1.10894 1.75883 2.58865 + vertex 1.10844 1.75423 2.58809 + vertex 1.11045 1.75853 2.58578 + endloop + endfacet + facet normal 0.500008 -0.151005 0.852754 + outer loop + vertex 1.11223 1.76 2.585 + vertex 1.11374 1.765 2.585 + vertex 1.11045 1.75853 2.58578 + endloop + endfacet + facet normal 0.496089 -0.148688 0.855446 + outer loop + vertex 1.11374 1.765 2.585 + vertex 1.11119 1.76317 2.58616 + vertex 1.11045 1.75853 2.58578 + endloop + endfacet + facet normal 0.862515 -0.17637 0.474301 + outer loop + vertex 1.11119 1.76317 2.58616 + vertex 1.10894 1.75883 2.58865 + vertex 1.11045 1.75853 2.58578 + endloop + endfacet + facet normal 0.810093 -0.0887225 0.57955 + outer loop + vertex 1.10923 1.7636 2.58896 + vertex 1.10894 1.75883 2.58865 + vertex 1.11119 1.76317 2.58616 + endloop + endfacet + facet normal 0.456548 -0.0739633 0.886619 + outer loop + vertex 1.11374 1.765 2.585 + vertex 1.11455 1.77 2.585 + vertex 1.11119 1.76317 2.58616 + endloop + endfacet + facet normal 0.513509 -0.107963 0.851265 + outer loop + vertex 1.11455 1.77 2.585 + vertex 1.11122 1.76682 2.58661 + vertex 1.11119 1.76317 2.58616 + endloop + endfacet + facet normal 0.811834 -0.0764394 0.578863 + outer loop + vertex 1.11122 1.76682 2.58661 + vertex 1.10923 1.7636 2.58896 + vertex 1.11119 1.76317 2.58616 + endloop + endfacet + facet normal 0.789785 -0.0383965 0.612181 + outer loop + vertex 1.10946 1.76835 2.58897 + vertex 1.10923 1.7636 2.58896 + vertex 1.11122 1.76682 2.58661 + endloop + endfacet + facet normal 0.0658977 0.514099 0.855196 + outer loop + vertex 1.115 1.7724 2.585 + vertex 1.11307 1.77498 2.5836 + vertex 1.11198 1.7713 2.5859 + endloop + endfacet + facet normal 0.302981 -0.0568098 0.951302 + outer loop + vertex 1.115 1.7724 2.585 + vertex 1.11198 1.7713 2.5859 + vertex 1.11455 1.77 2.585 + endloop + endfacet + facet normal 0.365935 0.0846812 0.92678 + outer loop + vertex 1.11455 1.77 2.585 + vertex 1.11198 1.7713 2.5859 + vertex 1.11122 1.76682 2.58661 + endloop + endfacet + facet normal 0.789956 -0.0379074 0.611991 + outer loop + vertex 1.11198 1.7713 2.5859 + vertex 1.10946 1.76835 2.58897 + vertex 1.11122 1.76682 2.58661 + endloop + endfacet + facet normal 0.780167 -0.0155416 0.625378 + outer loop + vertex 1.10952 1.77326 2.58901 + vertex 1.10946 1.76835 2.58897 + vertex 1.11198 1.7713 2.5859 + endloop + endfacet + facet normal 0.864845 0.0818215 0.495327 + outer loop + vertex 1.11307 1.77498 2.5836 + vertex 1.11283 1.77936 2.58329 + vertex 1.11148 1.77625 2.58617 + endloop + endfacet + facet normal 0.861552 0.059888 0.504125 + outer loop + vertex 1.11198 1.7713 2.5859 + vertex 1.11307 1.77498 2.5836 + vertex 1.11148 1.77625 2.58617 + endloop + endfacet + facet normal 0.798646 0.0481409 0.599873 + outer loop + vertex 1.11148 1.77625 2.58617 + vertex 1.10952 1.77326 2.58901 + vertex 1.11198 1.7713 2.5859 + endloop + endfacet + facet normal 0.828628 -0.00974484 0.559715 + outer loop + vertex 1.10934 1.77825 2.58937 + vertex 1.10952 1.77326 2.58901 + vertex 1.11148 1.77625 2.58617 + endloop + endfacet + facet normal -0.327207 0.0602098 -0.943033 + outer loop + vertex 1.11305 1.78 2.58 + vertex 1.11397 1.785 2.58 + vertex 1.1136 1.78133 2.57989 + endloop + endfacet + facet normal 0.849973 -0.379815 -0.365084 + outer loop + vertex 1.115 1.78 2.58454 + vertex 1.11305 1.78 2.58 + vertex 1.1136 1.78133 2.57989 + endloop + endfacet + facet normal 0.894185 -0.0363719 0.446219 + outer loop + vertex 1.11283 1.77936 2.58329 + vertex 1.11319 1.78424 2.58298 + vertex 1.11131 1.78169 2.58654 + endloop + endfacet + facet normal 0.904987 -0.000347082 0.425439 + outer loop + vertex 1.11148 1.77625 2.58617 + vertex 1.11283 1.77936 2.58329 + vertex 1.11131 1.78169 2.58654 + endloop + endfacet + facet normal 0.827971 -0.0119356 0.560643 + outer loop + vertex 1.11131 1.78169 2.58654 + vertex 1.10934 1.77825 2.58937 + vertex 1.11148 1.77625 2.58617 + endloop + endfacet + facet normal 0.832241 -0.0197922 0.554061 + outer loop + vertex 1.10914 1.78239 2.58982 + vertex 1.10934 1.77825 2.58937 + vertex 1.11131 1.78169 2.58654 + endloop + endfacet + facet normal -0.0837889 0.0371974 -0.995789 + outer loop + vertex 1.115 1.78732 2.58 + vertex 1.1136 1.78133 2.57989 + vertex 1.11397 1.785 2.58 + endloop + endfacet + facet normal 0.894698 -0.096185 0.436193 + outer loop + vertex 1.11319 1.78424 2.58298 + vertex 1.11367 1.789 2.58304 + vertex 1.11216 1.78614 2.5855 + endloop + endfacet + facet normal 0.902896 -0.0746953 0.42332 + outer loop + vertex 1.11131 1.78169 2.58654 + vertex 1.11319 1.78424 2.58298 + vertex 1.11216 1.78614 2.5855 + endloop + endfacet + facet normal 0.803564 -0.0353148 0.59417 + outer loop + vertex 1.10914 1.78239 2.58982 + vertex 1.11007 1.78658 2.58881 + vertex 1.10783 1.78483 2.59174 + endloop + endfacet + facet normal 0.828433 -0.0495963 0.557888 + outer loop + vertex 1.10914 1.78239 2.58982 + vertex 1.11131 1.78169 2.58654 + vertex 1.11007 1.78658 2.58881 + endloop + endfacet + facet normal 0.842643 -0.0364181 0.53724 + outer loop + vertex 1.11131 1.78169 2.58654 + vertex 1.11216 1.78614 2.5855 + vertex 1.11007 1.78658 2.58881 + endloop + endfacet + facet normal 0.806289 -0.0462479 0.589711 + outer loop + vertex 1.11007 1.78658 2.58881 + vertex 1.10767 1.78894 2.59228 + vertex 1.10783 1.78483 2.59174 + endloop + endfacet + facet normal 0.866094 -0.104324 0.488873 + outer loop + vertex 1.11367 1.789 2.58304 + vertex 1.11398 1.79365 2.58349 + vertex 1.11206 1.79035 2.58617 + endloop + endfacet + facet normal 0.878686 -0.0551895 0.474199 + outer loop + vertex 1.11216 1.78614 2.5855 + vertex 1.11367 1.789 2.58304 + vertex 1.11206 1.79035 2.58617 + endloop + endfacet + facet normal 0.839515 -0.0664796 0.539254 + outer loop + vertex 1.11216 1.78614 2.5855 + vertex 1.11206 1.79035 2.58617 + vertex 1.11007 1.78658 2.58881 + endloop + endfacet + facet normal 0.831684 -0.052895 0.552725 + outer loop + vertex 1.11206 1.79035 2.58617 + vertex 1.10998 1.79211 2.58948 + vertex 1.11007 1.78658 2.58881 + endloop + endfacet + facet normal 0.801698 -0.0584856 0.594861 + outer loop + vertex 1.10998 1.79211 2.58948 + vertex 1.10767 1.78894 2.59228 + vertex 1.11007 1.78658 2.58881 + endloop + endfacet + facet normal 0.797301 -0.0493657 0.60156 + outer loop + vertex 1.10765 1.79399 2.59272 + vertex 1.10767 1.78894 2.59228 + vertex 1.10998 1.79211 2.58948 + endloop + endfacet + facet normal 0.840855 -0.0930642 0.5332 + outer loop + vertex 1.11398 1.79365 2.58349 + vertex 1.11433 1.79838 2.58376 + vertex 1.11217 1.79534 2.58663 + endloop + endfacet + facet normal 0.849335 -0.0663625 0.523666 + outer loop + vertex 1.11206 1.79035 2.58617 + vertex 1.11398 1.79365 2.58349 + vertex 1.11217 1.79534 2.58663 + endloop + endfacet + facet normal 0.826793 -0.0690714 0.558249 + outer loop + vertex 1.11206 1.79035 2.58617 + vertex 1.11217 1.79534 2.58663 + vertex 1.10998 1.79211 2.58948 + endloop + endfacet + facet normal 0.819967 -0.0542411 0.569834 + outer loop + vertex 1.11217 1.79534 2.58663 + vertex 1.11006 1.7973 2.58986 + vertex 1.10998 1.79211 2.58948 + endloop + endfacet + facet normal 0.795012 -0.0563547 0.603971 + outer loop + vertex 1.11006 1.7973 2.58986 + vertex 1.10765 1.79399 2.59272 + vertex 1.10998 1.79211 2.58948 + endloop + endfacet + facet normal 0.787048 -0.0405333 0.615558 + outer loop + vertex 1.10776 1.7991 2.59291 + vertex 1.10765 1.79399 2.59272 + vertex 1.11006 1.7973 2.58986 + endloop + endfacet + facet normal 0.824505 -0.069776 0.561536 + outer loop + vertex 1.11433 1.79838 2.58376 + vertex 1.11458 1.80323 2.58399 + vertex 1.11234 1.80037 2.58693 + endloop + endfacet + facet normal 0.827772 -0.0605123 0.557792 + outer loop + vertex 1.11217 1.79534 2.58663 + vertex 1.11433 1.79838 2.58376 + vertex 1.11234 1.80037 2.58693 + endloop + endfacet + facet normal 0.817658 -0.0610556 0.572458 + outer loop + vertex 1.11217 1.79534 2.58663 + vertex 1.11234 1.80037 2.58693 + vertex 1.11006 1.7973 2.58986 + endloop + endfacet + facet normal 0.809738 -0.0429723 0.585216 + outer loop + vertex 1.11234 1.80037 2.58693 + vertex 1.11014 1.80237 2.59011 + vertex 1.11006 1.7973 2.58986 + endloop + endfacet + facet normal 0.785888 -0.044123 0.616793 + outer loop + vertex 1.11014 1.80237 2.59011 + vertex 1.10776 1.7991 2.59291 + vertex 1.11006 1.7973 2.58986 + endloop + endfacet + facet normal 0.773238 -0.0203504 0.633789 + outer loop + vertex 1.10782 1.8041 2.593 + vertex 1.10776 1.7991 2.59291 + vertex 1.11014 1.80237 2.59011 + endloop + endfacet + facet normal 0.81137 -0.0567942 0.581768 + outer loop + vertex 1.11458 1.80323 2.58399 + vertex 1.11456 1.80809 2.5845 + vertex 1.11236 1.80537 2.5873 + endloop + endfacet + facet normal 0.815159 -0.0461003 0.5774 + outer loop + vertex 1.11234 1.80037 2.58693 + vertex 1.11458 1.80323 2.58399 + vertex 1.11236 1.80537 2.5873 + endloop + endfacet + facet normal 0.808447 -0.046756 0.586709 + outer loop + vertex 1.11234 1.80037 2.58693 + vertex 1.11236 1.80537 2.5873 + vertex 1.11014 1.80237 2.59011 + endloop + endfacet + facet normal 0.797823 -0.0241936 0.602407 + outer loop + vertex 1.11236 1.80537 2.5873 + vertex 1.11002 1.80723 2.59047 + vertex 1.11014 1.80237 2.59011 + endloop + endfacet + facet normal 0.771026 -0.0273947 0.636214 + outer loop + vertex 1.11002 1.80723 2.59047 + vertex 1.10782 1.8041 2.593 + vertex 1.11014 1.80237 2.59011 + endloop + endfacet + facet normal 0.745163 0.0154633 0.666703 + outer loop + vertex 1.10757 1.80881 2.59318 + vertex 1.10782 1.8041 2.593 + vertex 1.11002 1.80723 2.59047 + endloop + endfacet + facet normal 0.793051 -0.0539476 0.606762 + outer loop + vertex 1.11456 1.80809 2.5845 + vertex 1.1144 1.81219 2.58506 + vertex 1.11209 1.81065 2.58795 + endloop + endfacet + facet normal 0.801441 -0.0329605 0.597165 + outer loop + vertex 1.11236 1.80537 2.5873 + vertex 1.11456 1.80809 2.5845 + vertex 1.11209 1.81065 2.58795 + endloop + endfacet + facet normal 0.794666 -0.0343992 0.606071 + outer loop + vertex 1.11236 1.80537 2.5873 + vertex 1.11209 1.81065 2.58795 + vertex 1.11002 1.80723 2.59047 + endloop + endfacet + facet normal 0.775353 -0.00398422 0.631515 + outer loop + vertex 1.11209 1.81065 2.58795 + vertex 1.10953 1.81128 2.5911 + vertex 1.11002 1.80723 2.59047 + endloop + endfacet + facet normal 0.736072 -0.0157773 0.676719 + outer loop + vertex 1.10953 1.81128 2.5911 + vertex 1.10757 1.80881 2.59318 + vertex 1.11002 1.80723 2.59047 + endloop + endfacet + facet normal 0.688578 0.0604806 0.722636 + outer loop + vertex 1.10701 1.81368 2.5933 + vertex 1.10757 1.80881 2.59318 + vertex 1.10953 1.81128 2.5911 + endloop + endfacet + facet normal 0.791396 -0.0462024 0.609555 + outer loop + vertex 1.1144 1.81219 2.58506 + vertex 1.11305 1.81471 2.58701 + vertex 1.11209 1.81065 2.58795 + endloop + endfacet + facet normal 0.758264 -0.0582326 0.649342 + outer loop + vertex 1.11305 1.81471 2.58701 + vertex 1.11292 1.81886 2.58754 + vertex 1.11044 1.81543 2.59012 + endloop + endfacet + facet normal 0.762368 -0.0307428 0.646413 + outer loop + vertex 1.11305 1.81471 2.58701 + vertex 1.11044 1.81543 2.59012 + vertex 1.11209 1.81065 2.58795 + endloop + endfacet + facet normal 0.773521 -0.0209938 0.633423 + outer loop + vertex 1.11209 1.81065 2.58795 + vertex 1.11044 1.81543 2.59012 + vertex 1.10953 1.81128 2.5911 + endloop + endfacet + facet normal 0.67189 0.0267623 0.740167 + outer loop + vertex 1.11044 1.81543 2.59012 + vertex 1.10701 1.81368 2.5933 + vertex 1.10953 1.81128 2.5911 + endloop + endfacet + facet normal 0.680552 -0.00380491 0.73269 + outer loop + vertex 1.10791 1.81787 2.59248 + vertex 1.10701 1.81368 2.5933 + vertex 1.11044 1.81543 2.59012 + endloop + endfacet + facet normal 0.735669 -0.0599832 0.67468 + outer loop + vertex 1.11292 1.81886 2.58754 + vertex 1.11291 1.82387 2.58798 + vertex 1.11035 1.82055 2.59049 + endloop + endfacet + facet normal 0.744005 -0.0344416 0.667286 + outer loop + vertex 1.11044 1.81543 2.59012 + vertex 1.11292 1.81886 2.58754 + vertex 1.11035 1.82055 2.59049 + endloop + endfacet + facet normal 0.65992 -0.042118 0.750154 + outer loop + vertex 1.11035 1.82055 2.59049 + vertex 1.10791 1.81787 2.59248 + vertex 1.11044 1.81543 2.59012 + endloop + endfacet + facet normal 0.604512 0.0416368 0.795507 + outer loop + vertex 1.10726 1.82176 2.59277 + vertex 1.10791 1.81787 2.59248 + vertex 1.11035 1.82055 2.59049 + endloop + endfacet + facet normal 0.702098 -0.0402738 0.71094 + outer loop + vertex 1.11291 1.82387 2.58798 + vertex 1.11294 1.82883 2.58824 + vertex 1.11026 1.82532 2.59069 + endloop + endfacet + facet normal 0.709063 -0.0164479 0.704954 + outer loop + vertex 1.11035 1.82055 2.59049 + vertex 1.11291 1.82387 2.58798 + vertex 1.11026 1.82532 2.59069 + endloop + endfacet + facet normal 0.588616 -0.0229435 0.808087 + outer loop + vertex 1.11026 1.82532 2.59069 + vertex 1.10726 1.82176 2.59277 + vertex 1.11035 1.82055 2.59049 + endloop + endfacet + facet normal 0.519769 0.0606995 0.852148 + outer loop + vertex 1.10697 1.82642 2.59262 + vertex 1.10726 1.82176 2.59277 + vertex 1.11026 1.82532 2.59069 + endloop + endfacet + facet normal 0.652308 -0.00446054 0.757941 + outer loop + vertex 1.11294 1.82883 2.58824 + vertex 1.11276 1.83369 2.58843 + vertex 1.11016 1.83022 2.59064 + endloop + endfacet + facet normal 0.659369 0.0207844 0.751532 + outer loop + vertex 1.11026 1.82532 2.59069 + vertex 1.11294 1.82883 2.58824 + vertex 1.11016 1.83022 2.59064 + endloop + endfacet + facet normal 0.510348 0.0188356 0.859762 + outer loop + vertex 1.11016 1.83022 2.59064 + vertex 1.10697 1.82642 2.59262 + vertex 1.11026 1.82532 2.59069 + endloop + endfacet + facet normal 0.432254 0.103132 0.895835 + outer loop + vertex 1.10662 1.83133 2.59222 + vertex 1.10697 1.82642 2.59262 + vertex 1.11016 1.83022 2.59064 + endloop + endfacet + facet normal 0.576487 0.0570258 0.815114 + outer loop + vertex 1.11276 1.83369 2.58843 + vertex 1.11216 1.83892 2.58848 + vertex 1.10969 1.83516 2.59049 + endloop + endfacet + facet normal 0.582997 0.079783 0.808548 + outer loop + vertex 1.11016 1.83022 2.59064 + vertex 1.11276 1.83369 2.58843 + vertex 1.10969 1.83516 2.59049 + endloop + endfacet + facet normal 0.424326 0.0675717 0.902985 + outer loop + vertex 1.10969 1.83516 2.59049 + vertex 1.10662 1.83133 2.59222 + vertex 1.11016 1.83022 2.59064 + endloop + endfacet + facet normal 0.341922 0.145047 0.928467 + outer loop + vertex 1.10558 1.83668 2.59177 + vertex 1.10662 1.83133 2.59222 + vertex 1.10969 1.83516 2.59049 + endloop + endfacet + facet normal 0.517289 0.113697 0.848225 + outer loop + vertex 1.10882 1.83932 2.59047 + vertex 1.10969 1.83516 2.59049 + vertex 1.11216 1.83892 2.58848 + endloop + endfacet + facet normal 0.517656 0.127834 0.845985 + outer loop + vertex 1.10882 1.83932 2.59047 + vertex 1.11216 1.83892 2.58848 + vertex 1.10896 1.84398 2.58968 + endloop + endfacet + facet normal 0.46473 0.0859411 0.881272 + outer loop + vertex 1.10896 1.84398 2.58968 + vertex 1.11216 1.83892 2.58848 + vertex 1.113 1.84321 2.58762 + endloop + endfacet + facet normal 0.320285 0.0731343 0.944494 + outer loop + vertex 1.10969 1.83516 2.59049 + vertex 1.10882 1.83932 2.59047 + vertex 1.10558 1.83668 2.59177 + endloop + endfacet + facet normal 0.454148 0.00473817 0.890914 + outer loop + vertex 1.113 1.84321 2.58762 + vertex 1.11237 1.84723 2.58792 + vertex 1.10896 1.84398 2.58968 + endloop + endfacet + facet normal 0.140752 0.198937 0.969852 + outer loop + vertex 1.11462 1.96932 2.566 + vertex 1.11461 1.97398 2.56505 + vertex 1.11139 1.9707 2.56619 + endloop + endfacet + facet normal 0.140247 0.199424 0.969825 + outer loop + vertex 1.10966 1.9738 2.5658 + vertex 1.11139 1.9707 2.56619 + vertex 1.11461 1.97398 2.56505 + endloop + endfacet + facet normal 0.205845 0.182435 0.961429 + outer loop + vertex 1.11545 2.01948 2.55584 + vertex 1.11469 2.02401 2.55514 + vertex 1.11179 2.02118 2.5563 + endloop + endfacet + facet normal 0.203004 0.175837 0.96326 + outer loop + vertex 1.11179 2.02118 2.5563 + vertex 1.11121 2.01665 2.55725 + vertex 1.11545 2.01948 2.55584 + endloop + endfacet + facet normal 0.256295 0.166727 0.952111 + outer loop + vertex 1.11179 2.02118 2.5563 + vertex 1.10756 2.021 2.55747 + vertex 1.11121 2.01665 2.55725 + endloop + endfacet + facet normal 0.237665 0.150713 0.959584 + outer loop + vertex 1.10756 2.021 2.55747 + vertex 1.10678 2.0164 2.55839 + vertex 1.11121 2.01665 2.55725 + endloop + endfacet + facet normal 0.233731 0.173374 0.956719 + outer loop + vertex 1.11469 2.02401 2.55514 + vertex 1.11335 2.02885 2.55459 + vertex 1.11042 2.02496 2.55601 + endloop + endfacet + facet normal 0.230722 0.156538 0.960345 + outer loop + vertex 1.11179 2.02118 2.5563 + vertex 1.11469 2.02401 2.55514 + vertex 1.11042 2.02496 2.55601 + endloop + endfacet + facet normal 0.256418 0.165256 0.952334 + outer loop + vertex 1.11042 2.02496 2.55601 + vertex 1.10756 2.021 2.55747 + vertex 1.11179 2.02118 2.5563 + endloop + endfacet + facet normal 0.284968 0.14301 0.947809 + outer loop + vertex 1.10614 2.02645 2.55708 + vertex 1.10756 2.021 2.55747 + vertex 1.11042 2.02496 2.55601 + endloop + endfacet + facet normal 0.26127 0.151323 0.953331 + outer loop + vertex 1.10936 2.02871 2.55571 + vertex 1.11042 2.02496 2.55601 + vertex 1.11335 2.02885 2.55459 + endloop + endfacet + facet normal 0.261556 0.147444 0.95386 + outer loop + vertex 1.10936 2.02871 2.55571 + vertex 1.11335 2.02885 2.55459 + vertex 1.11026 2.03297 2.5548 + endloop + endfacet + facet normal 0.275547 0.158226 0.948176 + outer loop + vertex 1.11026 2.03297 2.5548 + vertex 1.11335 2.02885 2.55459 + vertex 1.11424 2.0331 2.55363 + endloop + endfacet + facet normal 0.289413 0.158482 0.943993 + outer loop + vertex 1.11042 2.02496 2.55601 + vertex 1.10936 2.02871 2.55571 + vertex 1.10614 2.02645 2.55708 + endloop + endfacet + facet normal 0.275838 0.154256 0.948746 + outer loop + vertex 1.11424 2.0331 2.55363 + vertex 1.11308 2.03702 2.55333 + vertex 1.11026 2.03297 2.5548 + endloop + endfacet + facet normal 0.295688 0.139109 0.945102 + outer loop + vertex 1.11026 2.03297 2.5548 + vertex 1.11308 2.03702 2.55333 + vertex 1.10895 2.03814 2.55445 + endloop + endfacet + facet normal 0.298499 0.152446 0.942156 + outer loop + vertex 1.11308 2.03702 2.55333 + vertex 1.1115 2.04119 2.55315 + vertex 1.10895 2.03814 2.55445 + endloop + endfacet + facet normal 0.311558 0.140534 0.939778 + outer loop + vertex 1.10895 2.03814 2.55445 + vertex 1.1115 2.04119 2.55315 + vertex 1.10775 2.0434 2.55406 + endloop + endfacet + facet normal 0.315219 0.147697 0.937455 + outer loop + vertex 1.1115 2.04119 2.55315 + vertex 1.11182 2.04615 2.55226 + vertex 1.10775 2.0434 2.55406 + endloop + endfacet + facet normal 0.317373 0.144374 0.937246 + outer loop + vertex 1.10775 2.0434 2.55406 + vertex 1.11182 2.04615 2.55226 + vertex 1.10816 2.04711 2.55335 + endloop + endfacet + facet normal 0.312997 0.150835 0.9377 + outer loop + vertex 1.11488 2.04876 2.55082 + vertex 1.11536 2.05289 2.54999 + vertex 1.11223 2.05076 2.55138 + endloop + endfacet + facet normal 0.313115 0.15101 0.937633 + outer loop + vertex 1.11223 2.05076 2.55138 + vertex 1.11182 2.04615 2.55226 + vertex 1.11488 2.04876 2.55082 + endloop + endfacet + facet normal 0.327914 0.148783 0.932918 + outer loop + vertex 1.11223 2.05076 2.55138 + vertex 1.10831 2.05099 2.55273 + vertex 1.11182 2.04615 2.55226 + endloop + endfacet + facet normal 0.316505 0.140007 0.938202 + outer loop + vertex 1.10831 2.05099 2.55273 + vertex 1.10816 2.04711 2.55335 + vertex 1.11182 2.04615 2.55226 + endloop + endfacet + facet normal 0.32401 0.147193 0.934533 + outer loop + vertex 1.11536 2.05289 2.54999 + vertex 1.11411 2.0581 2.54961 + vertex 1.11111 2.05487 2.55116 + endloop + endfacet + facet normal 0.320805 0.138866 0.93691 + outer loop + vertex 1.11223 2.05076 2.55138 + vertex 1.11536 2.05289 2.54999 + vertex 1.11111 2.05487 2.55116 + endloop + endfacet + facet normal 0.327876 0.140659 0.934191 + outer loop + vertex 1.11111 2.05487 2.55116 + vertex 1.10831 2.05099 2.55273 + vertex 1.11223 2.05076 2.55138 + endloop + endfacet + facet normal 0.333022 0.136465 0.932992 + outer loop + vertex 1.10702 2.05648 2.55238 + vertex 1.10831 2.05099 2.55273 + vertex 1.11111 2.05487 2.55116 + endloop + endfacet + facet normal 0.335072 0.140926 0.931594 + outer loop + vertex 1.11411 2.0581 2.54961 + vertex 1.11305 2.06362 2.54916 + vertex 1.11001 2.05975 2.55083 + endloop + endfacet + facet normal 0.333843 0.137127 0.932601 + outer loop + vertex 1.11111 2.05487 2.55116 + vertex 1.11411 2.0581 2.54961 + vertex 1.11001 2.05975 2.55083 + endloop + endfacet + facet normal 0.333191 0.136998 0.932853 + outer loop + vertex 1.11001 2.05975 2.55083 + vertex 1.10702 2.05648 2.55238 + vertex 1.11111 2.05487 2.55116 + endloop + endfacet + facet normal 0.337065 0.133049 0.932033 + outer loop + vertex 1.10591 2.06157 2.55206 + vertex 1.10702 2.05648 2.55238 + vertex 1.11001 2.05975 2.55083 + endloop + endfacet + facet normal 0.336814 0.139391 0.931196 + outer loop + vertex 1.10908 2.06373 2.55058 + vertex 1.11001 2.05975 2.55083 + vertex 1.11305 2.06362 2.54916 + endloop + endfacet + facet normal 0.33667 0.145512 0.930312 + outer loop + vertex 1.10908 2.06373 2.55058 + vertex 1.11305 2.06362 2.54916 + vertex 1.10975 2.06799 2.54966 + endloop + endfacet + facet normal 0.334818 0.144012 0.931213 + outer loop + vertex 1.10975 2.06799 2.54966 + vertex 1.11305 2.06362 2.54916 + vertex 1.11354 2.0682 2.54827 + endloop + endfacet + facet normal 0.339557 0.139967 0.930113 + outer loop + vertex 1.11001 2.05975 2.55083 + vertex 1.10908 2.06373 2.55058 + vertex 1.10591 2.06157 2.55206 + endloop + endfacet + facet normal 0.33413 0.150843 0.930378 + outer loop + vertex 1.11354 2.0682 2.54827 + vertex 1.11204 2.07139 2.54829 + vertex 1.10975 2.06799 2.54966 + endloop + endfacet + facet normal 0.336104 0.149329 0.929911 + outer loop + vertex 1.10975 2.06799 2.54966 + vertex 1.11204 2.07139 2.54829 + vertex 1.10832 2.07352 2.54929 + endloop + endfacet + facet normal 0.337246 0.151688 0.929116 + outer loop + vertex 1.11204 2.07139 2.54829 + vertex 1.1126 2.07583 2.54736 + vertex 1.10832 2.07352 2.54929 + endloop + endfacet + facet normal 0.338724 0.14888 0.929032 + outer loop + vertex 1.10832 2.07352 2.54929 + vertex 1.1126 2.07583 2.54736 + vertex 1.10889 2.07798 2.54837 + endloop + endfacet + facet normal 0.336086 0.143479 0.930838 + outer loop + vertex 1.1126 2.07583 2.54736 + vertex 1.11113 2.08141 2.54703 + vertex 1.10889 2.07798 2.54837 + endloop + endfacet + facet normal 0.354444 0.129603 0.926052 + outer loop + vertex 1.10889 2.07798 2.54837 + vertex 1.11113 2.08141 2.54703 + vertex 1.10743 2.08127 2.54847 + endloop + endfacet + facet normal 0.35017 0.138941 0.926324 + outer loop + vertex 1.11425 2.08361 2.54554 + vertex 1.11473 2.08796 2.5447 + vertex 1.11168 2.08576 2.54619 + endloop + endfacet + facet normal 0.348567 0.136743 0.927255 + outer loop + vertex 1.11168 2.08576 2.54619 + vertex 1.11113 2.08141 2.54703 + vertex 1.11425 2.08361 2.54554 + endloop + endfacet + facet normal 0.370345 0.132497 0.919396 + outer loop + vertex 1.11168 2.08576 2.54619 + vertex 1.10784 2.08594 2.54771 + vertex 1.11113 2.08141 2.54703 + endloop + endfacet + facet normal 0.355173 0.120329 0.927024 + outer loop + vertex 1.10784 2.08594 2.54771 + vertex 1.10743 2.08127 2.54847 + vertex 1.11113 2.08141 2.54703 + endloop + endfacet + facet normal 0.361603 0.146884 0.920689 + outer loop + vertex 1.11473 2.08796 2.5447 + vertex 1.11314 2.09351 2.54444 + vertex 1.11053 2.08987 2.54605 + endloop + endfacet + facet normal 0.35572 0.13062 0.92542 + outer loop + vertex 1.11168 2.08576 2.54619 + vertex 1.11473 2.08796 2.5447 + vertex 1.11053 2.08987 2.54605 + endloop + endfacet + facet normal 0.370327 0.134498 0.919113 + outer loop + vertex 1.11053 2.08987 2.54605 + vertex 1.10784 2.08594 2.54771 + vertex 1.11168 2.08576 2.54619 + endloop + endfacet + facet normal 0.383468 0.123883 0.915208 + outer loop + vertex 1.10641 2.09202 2.54748 + vertex 1.10784 2.08594 2.54771 + vertex 1.11053 2.08987 2.54605 + endloop + endfacet + facet normal 0.373803 0.136652 0.917386 + outer loop + vertex 1.10951 2.09392 2.54586 + vertex 1.11053 2.08987 2.54605 + vertex 1.11314 2.09351 2.54444 + endloop + endfacet + facet normal 0.374153 0.144492 0.916041 + outer loop + vertex 1.10951 2.09392 2.54586 + vertex 1.11314 2.09351 2.54444 + vertex 1.11034 2.09786 2.5449 + endloop + endfacet + facet normal 0.382948 0.150659 0.911401 + outer loop + vertex 1.11034 2.09786 2.5449 + vertex 1.11314 2.09351 2.54444 + vertex 1.11344 2.09716 2.54372 + endloop + endfacet + facet normal 0.390258 0.14043 0.909933 + outer loop + vertex 1.11053 2.08987 2.54605 + vertex 1.10951 2.09392 2.54586 + vertex 1.10641 2.09202 2.54748 + endloop + endfacet + facet normal 0.383373 0.1537 0.910715 + outer loop + vertex 1.11344 2.09716 2.54372 + vertex 1.11357 2.10093 2.54302 + vertex 1.11034 2.09786 2.5449 + endloop + endfacet + facet normal 0.390763 0.144893 0.909016 + outer loop + vertex 1.11034 2.09786 2.5449 + vertex 1.11357 2.10093 2.54302 + vertex 1.10921 2.10311 2.54455 + endloop + endfacet + facet normal 0.395685 0.15775 0.904736 + outer loop + vertex 1.11357 2.10093 2.54302 + vertex 1.11202 2.10653 2.54272 + vertex 1.10921 2.10311 2.54455 + endloop + endfacet + facet normal 0.393641 0.159721 0.905282 + outer loop + vertex 1.10921 2.10311 2.54455 + vertex 1.11202 2.10653 2.54272 + vertex 1.1076 2.10864 2.54427 + endloop + endfacet + facet normal 0.395774 0.165662 0.903282 + outer loop + vertex 1.11202 2.10653 2.54272 + vertex 1.11084 2.11191 2.54226 + vertex 1.1076 2.10864 2.54427 + endloop + endfacet + facet normal 0.388261 0.174126 0.90495 + outer loop + vertex 1.1076 2.10864 2.54427 + vertex 1.11084 2.11191 2.54226 + vertex 1.10764 2.11246 2.54352 + endloop + endfacet + facet normal 0.401176 0.214723 0.890478 + outer loop + vertex 1.11394 2.1138 2.54048 + vertex 1.11477 2.11743 2.53924 + vertex 1.11171 2.11593 2.54098 + endloop + endfacet + facet normal 0.389977 0.201097 0.898598 + outer loop + vertex 1.11171 2.11593 2.54098 + vertex 1.11084 2.11191 2.54226 + vertex 1.11394 2.1138 2.54048 + endloop + endfacet + facet normal 0.36666 0.208721 0.90664 + outer loop + vertex 1.11171 2.11593 2.54098 + vertex 1.10794 2.11606 2.54247 + vertex 1.11084 2.11191 2.54226 + endloop + endfacet + facet normal 0.392102 0.227312 0.891395 + outer loop + vertex 1.10794 2.11606 2.54247 + vertex 1.10764 2.11246 2.54352 + vertex 1.11084 2.11191 2.54226 + endloop + endfacet + facet normal 0.364578 0.275707 0.88942 + outer loop + vertex 1.11477 2.11743 2.53924 + vertex 1.11425 2.12043 2.53852 + vertex 1.11109 2.11983 2.54 + endloop + endfacet + facet normal 0.367016 0.280218 0.887005 + outer loop + vertex 1.11171 2.11593 2.54098 + vertex 1.11477 2.11743 2.53924 + vertex 1.11109 2.11983 2.54 + endloop + endfacet + facet normal 0.362159 0.279958 0.889081 + outer loop + vertex 1.11109 2.11983 2.54 + vertex 1.10794 2.11606 2.54247 + vertex 1.11171 2.11593 2.54098 + endloop + endfacet + facet normal 0.3234 0.314545 0.892454 + outer loop + vertex 1.10629 2.1205 2.5415 + vertex 1.10794 2.11606 2.54247 + vertex 1.11109 2.11983 2.54 + endloop + endfacet + facet normal 0.318948 0.665813 0.674512 + outer loop + vertex 1.11386 2.12329 2.53717 + vertex 1.11264 2.12629 2.53479 + vertex 1.11004 2.12554 2.53676 + endloop + endfacet + facet normal 0.163605 0.676302 0.718226 + outer loop + vertex 1.11004 2.12554 2.53676 + vertex 1.10608 2.12575 2.53746 + vertex 1.10867 2.12338 2.5391 + endloop + endfacet + facet normal 0.283848 0.61713 0.73388 + outer loop + vertex 1.11386 2.12329 2.53717 + vertex 1.11004 2.12554 2.53676 + vertex 1.10867 2.12338 2.5391 + endloop + endfacet + facet normal 0.321009 0.432158 0.84273 + outer loop + vertex 1.11386 2.12329 2.53717 + vertex 1.10867 2.12338 2.5391 + vertex 1.11109 2.11983 2.54 + endloop + endfacet + facet normal 0.31159 0.439496 0.842469 + outer loop + vertex 1.11386 2.12329 2.53717 + vertex 1.11109 2.11983 2.54 + vertex 1.11425 2.12043 2.53852 + endloop + endfacet + facet normal 0.323991 0.433696 0.840796 + outer loop + vertex 1.11109 2.11983 2.54 + vertex 1.10867 2.12338 2.5391 + vertex 1.10629 2.1205 2.5415 + endloop + endfacet + facet normal 0.94275 0.321438 0.0888866 + outer loop + vertex 1.11074 2.13314 2.52118 + vertex 1.11 2.135 2.52236 + vertex 1.11 2.13427 2.525 + endloop + endfacet + facet normal 0.591788 0.797095 -0.120109 + outer loop + vertex 1.11257 2.13205 2.52295 + vertex 1.11074 2.13314 2.52118 + vertex 1.11 2.13427 2.525 + endloop + endfacet + facet normal 0.676614 0.734333 0.0543099 + outer loop + vertex 1.11257 2.13205 2.52295 + vertex 1.11 2.13427 2.525 + vertex 1.11393 2.13053 2.52664 + endloop + endfacet + facet normal 0.0145724 0.413201 0.910523 + outer loop + vertex 1.11393 2.13053 2.52664 + vertex 1.11 2.13427 2.525 + vertex 1.10858 2.13035 2.5268 + endloop + endfacet + facet normal -0.0153193 0.886768 0.46196 + outer loop + vertex 1.11393 2.13053 2.52664 + vertex 1.10858 2.13035 2.5268 + vertex 1.11259 2.12821 2.53103 + endloop + endfacet + facet normal -0.0109927 0.888508 0.458729 + outer loop + vertex 1.11259 2.12821 2.53103 + vertex 1.10858 2.13035 2.5268 + vertex 1.10752 2.12877 2.52984 + endloop + endfacet + facet normal 0.110761 0.871564 0.477607 + outer loop + vertex 1.11264 2.12629 2.53479 + vertex 1.10814 2.12736 2.53388 + vertex 1.11004 2.12554 2.53676 + endloop + endfacet + facet normal 0.119055 0.884248 0.451587 + outer loop + vertex 1.11264 2.12629 2.53479 + vertex 1.11259 2.12821 2.53103 + vertex 1.10814 2.12736 2.53388 + endloop + endfacet + facet normal 0.0265411 0.945248 0.325272 + outer loop + vertex 1.11259 2.12821 2.53103 + vertex 1.10752 2.12877 2.52984 + vertex 1.10814 2.12736 2.53388 + endloop + endfacet + facet normal 0.129266 0.874582 0.467328 + outer loop + vertex 1.11004 2.12554 2.53676 + vertex 1.10814 2.12736 2.53388 + vertex 1.10608 2.12575 2.53746 + endloop + endfacet + facet normal 0.943972 0.314136 0.101168 + outer loop + vertex 1.11074 2.13314 2.52118 + vertex 1.11 2.13576 2.52 + vertex 1.11 2.135 2.52236 + endloop + endfacet + facet normal 0.0130411 0.414214 0.910086 + outer loop + vertex 1.11074 2.13314 2.52118 + vertex 1.11346 2.13357 2.52095 + vertex 1.11 2.13576 2.52 + endloop + endfacet + facet normal -0.118631 0.229911 0.965954 + outer loop + vertex 1.11346 2.13357 2.52095 + vertex 1.115 2.13834 2.52 + vertex 1.11 2.13576 2.52 + endloop + endfacet + facet normal -0.07852 0.810386 0.580611 + outer loop + vertex 1.11346 2.13357 2.52095 + vertex 1.11074 2.13314 2.52118 + vertex 1.11257 2.13205 2.52295 + endloop + endfacet + facet normal -0.667124 -0.0330512 -0.744214 + outer loop + vertex 1.1209 0.887735 2.51704 + vertex 1.11749 0.89 2.52 + vertex 1.12 0.89 2.51775 + endloop + endfacet + facet normal -0.411312 -0.887932 0.205909 + outer loop + vertex 1.1209 0.887735 2.51704 + vertex 1.11983 0.888759 2.51933 + vertex 1.11749 0.89 2.52 + endloop + endfacet + facet normal -0.314072 -0.836025 0.449913 + outer loop + vertex 1.11749 0.89 2.52 + vertex 1.11983 0.888759 2.51933 + vertex 1.11772 0.890575 2.52123 + endloop + endfacet + facet normal -0.581993 -0.689095 0.431778 + outer loop + vertex 1.11749 0.89 2.52 + vertex 1.11772 0.890575 2.52123 + vertex 1.115 0.892103 2.52 + endloop + endfacet + facet normal -0.381536 -0.887605 -0.258046 + outer loop + vertex 1.115 0.892103 2.52 + vertex 1.11772 0.890575 2.52123 + vertex 1.11331 0.892266 2.52194 + endloop + endfacet + facet normal -0.292979 -0.90002 0.322688 + outer loop + vertex 1.11772 0.890575 2.52123 + vertex 1.11653 0.892236 2.52478 + vertex 1.11331 0.892266 2.52194 + endloop + endfacet + facet normal -0.168941 -0.968806 0.181312 + outer loop + vertex 1.11653 0.892236 2.52478 + vertex 1.11179 0.893127 2.52513 + vertex 1.11331 0.892266 2.52194 + endloop + endfacet + facet normal -0.138029 -0.897845 0.418119 + outer loop + vertex 1.11653 0.892236 2.52478 + vertex 1.11469 0.894094 2.52816 + vertex 1.11179 0.893127 2.52513 + endloop + endfacet + facet normal -0.124466 -0.896676 0.42483 + outer loop + vertex 1.11961 0.893466 2.52828 + vertex 1.11469 0.894094 2.52816 + vertex 1.11653 0.892236 2.52478 + endloop + endfacet + facet normal -0.116838 -0.809336 0.575607 + outer loop + vertex 1.11469 0.894094 2.52816 + vertex 1.11961 0.893466 2.52828 + vertex 1.11726 0.895914 2.53124 + endloop + endfacet + facet normal -0.00196631 -0.860157 0.510026 + outer loop + vertex 1.11234 0.895996 2.53136 + vertex 1.11469 0.894094 2.52816 + vertex 1.11726 0.895914 2.53124 + endloop + endfacet + facet normal 0.00153583 -0.793985 0.607936 + outer loop + vertex 1.11726 0.895914 2.53124 + vertex 1.11461 0.898127 2.53414 + vertex 1.11234 0.895996 2.53136 + endloop + endfacet + facet normal 0.108411 -0.739703 0.664144 + outer loop + vertex 1.1194 0.898615 2.5339 + vertex 1.11461 0.898127 2.53414 + vertex 1.11726 0.895914 2.53124 + endloop + endfacet + facet normal 0.105549 -0.683202 0.722561 + outer loop + vertex 1.11461 0.898127 2.53414 + vertex 1.1194 0.898615 2.5339 + vertex 1.11615 0.901267 2.53688 + endloop + endfacet + facet normal 0.217062 -0.700465 0.679877 + outer loop + vertex 1.11201 0.899772 2.53666 + vertex 1.11461 0.898127 2.53414 + vertex 1.11615 0.901267 2.53688 + endloop + endfacet + facet normal 0.375072 -0.528709 0.761438 + outer loop + vertex 1.11507 0.904031 2.53933 + vertex 1.11615 0.901267 2.53688 + vertex 1.11922 0.905298 2.53817 + endloop + endfacet + facet normal 0.283026 -0.572078 0.76982 + outer loop + vertex 1.11507 0.904031 2.53933 + vertex 1.11148 0.902337 2.53939 + vertex 1.11615 0.901267 2.53688 + endloop + endfacet + facet normal 0.21312 -0.691118 0.690605 + outer loop + vertex 1.11148 0.902337 2.53939 + vertex 1.11201 0.899772 2.53666 + vertex 1.11615 0.901267 2.53688 + endloop + endfacet + facet normal 0.270492 -0.544691 0.793817 + outer loop + vertex 1.11507 0.904031 2.53933 + vertex 1.11287 0.905172 2.54087 + vertex 1.11148 0.902337 2.53939 + endloop + endfacet + facet normal 0.317133 -0.175644 0.931974 + outer loop + vertex 1.11336 0.998779 2.55716 + vertex 1.11197 0.993461 2.55663 + vertex 1.11591 0.996392 2.55585 + endloop + endfacet + facet normal 0.263014 -0.0945272 0.96015 + outer loop + vertex 1.11675 1.15018 2.58536 + vertex 1.1167 1.15331 2.58569 + vertex 1.11322 1.14929 2.58624 + endloop + endfacet + facet normal 0.284954 -0.0827793 0.95496 + outer loop + vertex 1.1167 1.15331 2.58569 + vertex 1.11648 1.15764 2.58613 + vertex 1.11284 1.15349 2.58685 + endloop + endfacet + facet normal 0.313657 -0.10999 0.943144 + outer loop + vertex 1.11284 1.15349 2.58685 + vertex 1.11648 1.15764 2.58613 + vertex 1.11253 1.15804 2.58749 + endloop + endfacet + facet normal 0.316245 -0.0892532 0.94447 + outer loop + vertex 1.11648 1.15764 2.58613 + vertex 1.11593 1.16276 2.58679 + vertex 1.11253 1.15804 2.58749 + endloop + endfacet + facet normal 0.328654 -0.0989595 0.939251 + outer loop + vertex 1.11253 1.15804 2.58749 + vertex 1.11593 1.16276 2.58679 + vertex 1.11193 1.16204 2.58812 + endloop + endfacet + facet normal 0.57775 0.0158841 0.816059 + outer loop + vertex 1.11888 1.16498 2.58528 + vertex 1.11945 1.16857 2.58481 + vertex 1.11709 1.16708 2.58651 + endloop + endfacet + facet normal 0.501251 -0.0761985 0.86194 + outer loop + vertex 1.11709 1.16708 2.58651 + vertex 1.11593 1.16276 2.58679 + vertex 1.11888 1.16498 2.58528 + endloop + endfacet + facet normal 0.400692 -0.0458351 0.915066 + outer loop + vertex 1.11709 1.16708 2.58651 + vertex 1.11331 1.16713 2.58816 + vertex 1.11593 1.16276 2.58679 + endloop + endfacet + facet normal 0.328391 -0.0969291 0.939555 + outer loop + vertex 1.11331 1.16713 2.58816 + vertex 1.11193 1.16204 2.58812 + vertex 1.11593 1.16276 2.58679 + endloop + endfacet + facet normal 0.60771 0.046614 0.79279 + outer loop + vertex 1.11945 1.16857 2.58481 + vertex 1.11976 1.17349 2.58427 + vertex 1.11669 1.17116 2.58677 + endloop + endfacet + facet normal 0.582465 0.00468856 0.812842 + outer loop + vertex 1.11709 1.16708 2.58651 + vertex 1.11945 1.16857 2.58481 + vertex 1.11669 1.17116 2.58677 + endloop + endfacet + facet normal 0.401292 -0.0196027 0.91574 + outer loop + vertex 1.11669 1.17116 2.58677 + vertex 1.11331 1.16713 2.58816 + vertex 1.11709 1.16708 2.58651 + endloop + endfacet + facet normal 0.465995 -0.0858135 0.880616 + outer loop + vertex 1.11291 1.1735 2.589 + vertex 1.11331 1.16713 2.58816 + vertex 1.11669 1.17116 2.58677 + endloop + endfacet + facet normal 0.660479 0.034991 0.750029 + outer loop + vertex 1.11976 1.17349 2.58427 + vertex 1.11925 1.17909 2.58446 + vertex 1.11658 1.17647 2.58694 + endloop + endfacet + facet normal 0.63521 -0.0118267 0.772249 + outer loop + vertex 1.11669 1.17116 2.58677 + vertex 1.11976 1.17349 2.58427 + vertex 1.11658 1.17647 2.58694 + endloop + endfacet + facet normal 0.499499 -0.0176582 0.866135 + outer loop + vertex 1.11658 1.17647 2.58694 + vertex 1.11291 1.1735 2.589 + vertex 1.11669 1.17116 2.58677 + endloop + endfacet + facet normal 0.540704 -0.0889431 0.836498 + outer loop + vertex 1.11373 1.17932 2.58908 + vertex 1.11291 1.1735 2.589 + vertex 1.11658 1.17647 2.58694 + endloop + endfacet + facet normal 0.70681 0.0443559 0.706011 + outer loop + vertex 1.11925 1.17909 2.58446 + vertex 1.11912 1.18442 2.58426 + vertex 1.11656 1.18182 2.58699 + endloop + endfacet + facet normal 0.681697 -0.00405343 0.731624 + outer loop + vertex 1.11658 1.17647 2.58694 + vertex 1.11925 1.17909 2.58446 + vertex 1.11656 1.18182 2.58699 + endloop + endfacet + facet normal 0.598125 -0.00490678 0.801388 + outer loop + vertex 1.11656 1.18182 2.58699 + vertex 1.11373 1.17932 2.58908 + vertex 1.11658 1.17647 2.58694 + endloop + endfacet + facet normal 0.615726 -0.0367244 0.787104 + outer loop + vertex 1.1139 1.18441 2.58918 + vertex 1.11373 1.17932 2.58908 + vertex 1.11656 1.18182 2.58699 + endloop + endfacet + facet normal 0.741756 0.0454864 0.669126 + outer loop + vertex 1.11912 1.18442 2.58426 + vertex 1.11902 1.18968 2.58401 + vertex 1.11656 1.18695 2.58692 + endloop + endfacet + facet normal 0.725065 0.00815276 0.688633 + outer loop + vertex 1.11656 1.18182 2.58699 + vertex 1.11912 1.18442 2.58426 + vertex 1.11656 1.18695 2.58692 + endloop + endfacet + facet normal 0.642796 0.00909895 0.765983 + outer loop + vertex 1.11656 1.18695 2.58692 + vertex 1.1139 1.18441 2.58918 + vertex 1.11656 1.18182 2.58699 + endloop + endfacet + facet normal 0.660592 -0.0233277 0.750383 + outer loop + vertex 1.11397 1.18937 2.58928 + vertex 1.1139 1.18441 2.58918 + vertex 1.11656 1.18695 2.58692 + endloop + endfacet + facet normal 0.778349 0.0515423 0.625712 + outer loop + vertex 1.11902 1.18968 2.58401 + vertex 1.11884 1.19483 2.58382 + vertex 1.11658 1.19197 2.58686 + endloop + endfacet + facet normal 0.761417 0.00543073 0.64824 + outer loop + vertex 1.11656 1.18695 2.58692 + vertex 1.11902 1.18968 2.58401 + vertex 1.11658 1.19197 2.58686 + endloop + endfacet + facet normal 0.676287 0.00688064 0.736606 + outer loop + vertex 1.11658 1.19197 2.58686 + vertex 1.11397 1.18937 2.58928 + vertex 1.11656 1.18695 2.58692 + endloop + endfacet + facet normal 0.689735 -0.0184887 0.723826 + outer loop + vertex 1.11402 1.19428 2.58935 + vertex 1.11397 1.18937 2.58928 + vertex 1.11658 1.19197 2.58686 + endloop + endfacet + facet normal 0.812323 0.0622448 0.579877 + outer loop + vertex 1.11884 1.19483 2.58382 + vertex 1.11862 1.19991 2.58358 + vertex 1.11656 1.19694 2.58678 + endloop + endfacet + facet normal 0.797288 0.0129624 0.603459 + outer loop + vertex 1.11658 1.19197 2.58686 + vertex 1.11884 1.19483 2.58382 + vertex 1.11656 1.19694 2.58678 + endloop + endfacet + facet normal 0.70506 0.0144238 0.709001 + outer loop + vertex 1.11656 1.19694 2.58678 + vertex 1.11402 1.19428 2.58935 + vertex 1.11658 1.19197 2.58686 + endloop + endfacet + facet normal 0.71075 0.00358455 0.703435 + outer loop + vertex 1.114 1.1992 2.58935 + vertex 1.11402 1.19428 2.58935 + vertex 1.11656 1.19694 2.58678 + endloop + endfacet + facet normal 0.833907 0.0789914 0.546223 + outer loop + vertex 1.11862 1.19991 2.58358 + vertex 1.11834 1.20495 2.58327 + vertex 1.11646 1.20196 2.58658 + endloop + endfacet + facet normal 0.8236 0.0393272 0.565806 + outer loop + vertex 1.11656 1.19694 2.58678 + vertex 1.11862 1.19991 2.58358 + vertex 1.11646 1.20196 2.58658 + endloop + endfacet + facet normal 0.726741 0.0420163 0.685626 + outer loop + vertex 1.11646 1.20196 2.58658 + vertex 1.114 1.1992 2.58935 + vertex 1.11656 1.19694 2.58678 + endloop + endfacet + facet normal 0.728588 0.0385915 0.683864 + outer loop + vertex 1.11388 1.2042 2.5892 + vertex 1.114 1.1992 2.58935 + vertex 1.11646 1.20196 2.58658 + endloop + endfacet + facet normal 0.843508 0.0938063 0.528862 + outer loop + vertex 1.11834 1.20495 2.58327 + vertex 1.11809 1.20976 2.58282 + vertex 1.11629 1.20709 2.58616 + endloop + endfacet + facet normal 0.83771 0.0713118 0.541439 + outer loop + vertex 1.11646 1.20196 2.58658 + vertex 1.11834 1.20495 2.58327 + vertex 1.11629 1.20709 2.58616 + endloop + endfacet + facet normal 0.743305 0.0782912 0.664355 + outer loop + vertex 1.11629 1.20709 2.58616 + vertex 1.11388 1.2042 2.5892 + vertex 1.11646 1.20196 2.58658 + endloop + endfacet + facet normal 0.747647 0.0704297 0.660352 + outer loop + vertex 1.11369 1.20938 2.58886 + vertex 1.11388 1.2042 2.5892 + vertex 1.11629 1.20709 2.58616 + endloop + endfacet + facet normal 0.845046 0.109382 0.523386 + outer loop + vertex 1.11809 1.20976 2.58282 + vertex 1.11806 1.21347 2.58209 + vertex 1.11621 1.21269 2.58523 + endloop + endfacet + facet normal 0.840849 0.0995639 0.532034 + outer loop + vertex 1.11629 1.20709 2.58616 + vertex 1.11809 1.20976 2.58282 + vertex 1.11621 1.21269 2.58523 + endloop + endfacet + facet normal 0.762632 0.115692 0.636403 + outer loop + vertex 1.11621 1.21269 2.58523 + vertex 1.11369 1.20938 2.58886 + vertex 1.11629 1.20709 2.58616 + endloop + endfacet + facet normal 0.781603 0.0816049 0.618415 + outer loop + vertex 1.11341 1.21463 2.58852 + vertex 1.11369 1.20938 2.58886 + vertex 1.11621 1.21269 2.58523 + endloop + endfacet + facet normal 0.902767 0.144355 0.405184 + outer loop + vertex 1.11853 1.21572 2.58015 + vertex 1.11825 1.21925 2.57952 + vertex 1.1174 1.21685 2.58225 + endloop + endfacet + facet normal 0.903469 0.156235 0.399167 + outer loop + vertex 1.11806 1.21347 2.58209 + vertex 1.11853 1.21572 2.58015 + vertex 1.1174 1.21685 2.58225 + endloop + endfacet + facet normal 0.83879 0.137686 0.526758 + outer loop + vertex 1.11806 1.21347 2.58209 + vertex 1.1174 1.21685 2.58225 + vertex 1.11621 1.21269 2.58523 + endloop + endfacet + facet normal 0.842489 0.133207 0.521986 + outer loop + vertex 1.11621 1.21269 2.58523 + vertex 1.1174 1.21685 2.58225 + vertex 1.11543 1.21812 2.58512 + endloop + endfacet + facet normal 0.790476 0.127233 0.599132 + outer loop + vertex 1.11543 1.21812 2.58512 + vertex 1.11341 1.21463 2.58852 + vertex 1.11621 1.21269 2.58523 + endloop + endfacet + facet normal 0.814817 0.0878205 0.573027 + outer loop + vertex 1.11309 1.21976 2.58819 + vertex 1.11341 1.21463 2.58852 + vertex 1.11543 1.21812 2.58512 + endloop + endfacet + facet normal 0.858143 0.0227262 0.512908 + outer loop + vertex 1.11825 1.21925 2.57952 + vertex 1.11836 1.22339 2.57915 + vertex 1.11701 1.22247 2.58145 + endloop + endfacet + facet normal 0.914124 0.119906 0.387299 + outer loop + vertex 1.1174 1.21685 2.58225 + vertex 1.11825 1.21925 2.57952 + vertex 1.11701 1.22247 2.58145 + endloop + endfacet + facet normal 0.842549 0.133955 0.521697 + outer loop + vertex 1.1174 1.21685 2.58225 + vertex 1.11701 1.22247 2.58145 + vertex 1.11543 1.21812 2.58512 + endloop + endfacet + facet normal 0.839222 0.138641 0.525819 + outer loop + vertex 1.11701 1.22247 2.58145 + vertex 1.11483 1.22325 2.58471 + vertex 1.11543 1.21812 2.58512 + endloop + endfacet + facet normal 0.822501 0.138776 0.551574 + outer loop + vertex 1.11483 1.22325 2.58471 + vertex 1.11309 1.21976 2.58819 + vertex 1.11543 1.21812 2.58512 + endloop + endfacet + facet normal 0.853148 0.08648 0.514451 + outer loop + vertex 1.11289 1.22463 2.5877 + vertex 1.11309 1.21976 2.58819 + vertex 1.11483 1.22325 2.58471 + endloop + endfacet + facet normal -0.372443 -0.0893521 0.923744 + outer loop + vertex 1.11836 1.22339 2.57915 + vertex 1.12 1.22529 2.58 + vertex 1.11887 1.23 2.58 + endloop + endfacet + facet normal 0.876737 -0.127528 0.463755 + outer loop + vertex 1.11836 1.22339 2.57915 + vertex 1.11887 1.23 2.58 + vertex 1.11701 1.22247 2.58145 + endloop + endfacet + facet normal 0.460863 0.0568836 0.885646 + outer loop + vertex 1.11701 1.22247 2.58145 + vertex 1.11887 1.23 2.58 + vertex 1.11613 1.22823 2.58154 + endloop + endfacet + facet normal 0.839259 0.119266 0.530491 + outer loop + vertex 1.11701 1.22247 2.58145 + vertex 1.11613 1.22823 2.58154 + vertex 1.11483 1.22325 2.58471 + endloop + endfacet + facet normal 0.832947 0.126194 0.538771 + outer loop + vertex 1.11613 1.22823 2.58154 + vertex 1.11427 1.22782 2.58451 + vertex 1.11483 1.22325 2.58471 + endloop + endfacet + facet normal 0.857525 0.127468 0.4984 + outer loop + vertex 1.11427 1.22782 2.58451 + vertex 1.11289 1.22463 2.5877 + vertex 1.11483 1.22325 2.58471 + endloop + endfacet + facet normal 0.886955 0.0725648 0.45612 + outer loop + vertex 1.11294 1.22838 2.58702 + vertex 1.11289 1.22463 2.5877 + vertex 1.11427 1.22782 2.58451 + endloop + endfacet + facet normal 0.442384 0.0911284 0.892184 + outer loop + vertex 1.11887 1.23 2.58 + vertex 1.11784 1.235 2.58 + vertex 1.11613 1.22823 2.58154 + endloop + endfacet + facet normal 0.53291 0.0574253 0.844221 + outer loop + vertex 1.11784 1.235 2.58 + vertex 1.11508 1.23311 2.58187 + vertex 1.11613 1.22823 2.58154 + endloop + endfacet + facet normal 0.877891 0.104615 0.467294 + outer loop + vertex 1.1137 1.23095 2.58494 + vertex 1.11508 1.23311 2.58187 + vertex 1.11356 1.23469 2.58438 + endloop + endfacet + facet normal 0.881184 0.0962409 0.462874 + outer loop + vertex 1.1137 1.23095 2.58494 + vertex 1.11427 1.22782 2.58451 + vertex 1.11508 1.23311 2.58187 + endloop + endfacet + facet normal 0.830093 0.142246 0.539177 + outer loop + vertex 1.11427 1.22782 2.58451 + vertex 1.11613 1.22823 2.58154 + vertex 1.11508 1.23311 2.58187 + endloop + endfacet + facet normal 0.887295 0.0990501 0.450441 + outer loop + vertex 1.11427 1.22782 2.58451 + vertex 1.1137 1.23095 2.58494 + vertex 1.11294 1.22838 2.58702 + endloop + endfacet + facet normal 0.51191 0.097273 0.853514 + outer loop + vertex 1.11784 1.235 2.58 + vertex 1.11689 1.24 2.58 + vertex 1.11508 1.23311 2.58187 + endloop + endfacet + facet normal 0.509863 0.098116 0.854642 + outer loop + vertex 1.11689 1.24 2.58 + vertex 1.11441 1.23764 2.58175 + vertex 1.11508 1.23311 2.58187 + endloop + endfacet + facet normal 0.88327 0.142394 0.446719 + outer loop + vertex 1.11441 1.23764 2.58175 + vertex 1.11356 1.23469 2.58438 + vertex 1.11508 1.23311 2.58187 + endloop + endfacet + facet normal 0.91077 0.0945008 0.401954 + outer loop + vertex 1.11323 1.23927 2.58403 + vertex 1.11356 1.23469 2.58438 + vertex 1.11441 1.23764 2.58175 + endloop + endfacet + facet normal -0.404823 -0.205668 0.890965 + outer loop + vertex 1.11446 1.24371 2.57975 + vertex 1.11689 1.24 2.58 + vertex 1.115 1.24372 2.58 + endloop + endfacet + facet normal 0.724832 0.506395 0.4671 + outer loop + vertex 1.11446 1.24371 2.57975 + vertex 1.11408 1.24268 2.58146 + vertex 1.11689 1.24 2.58 + endloop + endfacet + facet normal 0.520911 0.0827647 0.849589 + outer loop + vertex 1.11408 1.24268 2.58146 + vertex 1.11441 1.23764 2.58175 + vertex 1.11689 1.24 2.58 + endloop + endfacet + facet normal 0.90887 0.0838503 0.408565 + outer loop + vertex 1.11408 1.24268 2.58146 + vertex 1.11323 1.23927 2.58403 + vertex 1.11441 1.23764 2.58175 + endloop + endfacet + facet normal 0.920599 0.0634184 0.385324 + outer loop + vertex 1.11301 1.24401 2.5838 + vertex 1.11323 1.23927 2.58403 + vertex 1.11408 1.24268 2.58146 + endloop + endfacet + facet normal 0.978489 -0.172434 0.113255 + outer loop + vertex 1.115 1.25 2.58463 + vertex 1.11408 1.24268 2.58146 + vertex 1.11446 1.24371 2.57975 + endloop + endfacet + facet normal -0.518642 -0.283261 0.806705 + outer loop + vertex 1.11374 1.24694 2.58275 + vertex 1.11408 1.24268 2.58146 + vertex 1.115 1.25 2.58463 + endloop + endfacet + facet normal 0.893124 -0.0638695 0.445252 + outer loop + vertex 1.11374 1.24694 2.58275 + vertex 1.11301 1.24401 2.5838 + vertex 1.11408 1.24268 2.58146 + endloop + endfacet + facet normal 0.905133 -0.0766322 0.418165 + outer loop + vertex 1.11339 1.24856 2.5838 + vertex 1.11301 1.24401 2.5838 + vertex 1.11374 1.24694 2.58275 + endloop + endfacet + facet normal -0.685552 -0.15571 0.711178 + outer loop + vertex 1.115 1.25 2.58463 + vertex 1.115 1.25169 2.585 + vertex 1.11374 1.24694 2.58275 + endloop + endfacet + facet normal 0.305196 -0.473103 0.826456 + outer loop + vertex 1.11374 1.24694 2.58275 + vertex 1.115 1.25169 2.585 + vertex 1.11339 1.24856 2.5838 + endloop + endfacet + facet normal -0.830641 0.119252 0.543889 + outer loop + vertex 1.11392 1.77534 2.58271 + vertex 1.115 1.7724 2.585 + vertex 1.115 1.775 2.58443 + endloop + endfacet + facet normal 0.39787 0.649896 0.647561 + outer loop + vertex 1.11392 1.77534 2.58271 + vertex 1.11307 1.77498 2.5836 + vertex 1.115 1.7724 2.585 + endloop + endfacet + facet normal -0.848358 -0.0116351 0.529295 + outer loop + vertex 1.115 1.78 2.58454 + vertex 1.11392 1.77534 2.58271 + vertex 1.115 1.775 2.58443 + endloop + endfacet + facet normal -0.900426 0.0379577 0.43335 + outer loop + vertex 1.1135 1.77828 2.58157 + vertex 1.11392 1.77534 2.58271 + vertex 1.115 1.78 2.58454 + endloop + endfacet + facet normal 0.591368 0.36569 0.718717 + outer loop + vertex 1.1135 1.77828 2.58157 + vertex 1.11307 1.77498 2.5836 + vertex 1.11392 1.77534 2.58271 + endloop + endfacet + facet normal 0.94491 0.0737679 0.318908 + outer loop + vertex 1.11283 1.77936 2.58329 + vertex 1.11307 1.77498 2.5836 + vertex 1.1135 1.77828 2.58157 + endloop + endfacet + facet normal -0.916054 0.215953 0.337949 + outer loop + vertex 1.1136 1.78133 2.57989 + vertex 1.1135 1.77828 2.58157 + vertex 1.115 1.78 2.58454 + endloop + endfacet + facet normal 0.980599 -0.118525 -0.156136 + outer loop + vertex 1.11393 1.78344 2.58039 + vertex 1.1135 1.77828 2.58157 + vertex 1.1136 1.78133 2.57989 + endloop + endfacet + facet normal 0.933384 0.00309192 0.358865 + outer loop + vertex 1.11393 1.78344 2.58039 + vertex 1.11283 1.77936 2.58329 + vertex 1.1135 1.77828 2.58157 + endloop + endfacet + facet normal 0.9552 -0.0505977 0.291605 + outer loop + vertex 1.11319 1.78424 2.58298 + vertex 1.11283 1.77936 2.58329 + vertex 1.11393 1.78344 2.58039 + endloop + endfacet + facet normal 0.921183 -0.221022 0.320267 + outer loop + vertex 1.115 1.78732 2.58 + vertex 1.11393 1.78344 2.58039 + vertex 1.1136 1.78133 2.57989 + endloop + endfacet + facet normal 0.434071 -0.207314 -0.8767 + outer loop + vertex 1.115 1.78732 2.58 + vertex 1.11628 1.79 2.58 + vertex 1.11393 1.78344 2.58039 + endloop + endfacet + facet normal 0.388111 -0.0843418 0.917745 + outer loop + vertex 1.11628 1.79 2.58 + vertex 1.1148 1.78856 2.58049 + vertex 1.11393 1.78344 2.58039 + endloop + endfacet + facet normal 0.933029 -0.164049 0.320227 + outer loop + vertex 1.1148 1.78856 2.58049 + vertex 1.11319 1.78424 2.58298 + vertex 1.11393 1.78344 2.58039 + endloop + endfacet + facet normal 0.903364 -0.096829 0.417801 + outer loop + vertex 1.11367 1.789 2.58304 + vertex 1.11319 1.78424 2.58298 + vertex 1.1148 1.78856 2.58049 + endloop + endfacet + facet normal 0.380723 -0.0753858 0.921611 + outer loop + vertex 1.11628 1.79 2.58 + vertex 1.11727 1.795 2.58 + vertex 1.1148 1.78856 2.58049 + endloop + endfacet + facet normal 0.529973 -0.139239 0.836505 + outer loop + vertex 1.11727 1.795 2.58 + vertex 1.11557 1.7933 2.5808 + vertex 1.1148 1.78856 2.58049 + endloop + endfacet + facet normal 0.889174 -0.171248 0.424315 + outer loop + vertex 1.11557 1.7933 2.5808 + vertex 1.11367 1.789 2.58304 + vertex 1.1148 1.78856 2.58049 + endloop + endfacet + facet normal 0.849914 -0.10587 0.516177 + outer loop + vertex 1.11398 1.79365 2.58349 + vertex 1.11367 1.789 2.58304 + vertex 1.11557 1.7933 2.5808 + endloop + endfacet + facet normal 0.548425 -0.165627 0.819633 + outer loop + vertex 1.11727 1.795 2.58 + vertex 1.11878 1.8 2.58 + vertex 1.11557 1.7933 2.5808 + endloop + endfacet + facet normal 0.54065 -0.161182 0.825662 + outer loop + vertex 1.11878 1.8 2.58 + vertex 1.11581 1.79695 2.58135 + vertex 1.11557 1.7933 2.5808 + endloop + endfacet + facet normal 0.845222 -0.134755 0.517146 + outer loop + vertex 1.11581 1.79695 2.58135 + vertex 1.11398 1.79365 2.58349 + vertex 1.11557 1.7933 2.5808 + endloop + endfacet + facet normal 0.822217 -0.0932759 0.561479 + outer loop + vertex 1.11433 1.79838 2.58376 + vertex 1.11398 1.79365 2.58349 + vertex 1.11581 1.79695 2.58135 + endloop + endfacet + facet normal -0.381468 0.575167 0.723647 + outer loop + vertex 1.12 1.80469 2.58 + vertex 1.11816 1.80554 2.57835 + vertex 1.1168 1.8016 2.58076 + endloop + endfacet + facet normal 0.302078 -0.0785773 0.950039 + outer loop + vertex 1.12 1.80469 2.58 + vertex 1.1168 1.8016 2.58076 + vertex 1.11878 1.8 2.58 + endloop + endfacet + facet normal 0.383451 0.035022 0.922897 + outer loop + vertex 1.11878 1.8 2.58 + vertex 1.1168 1.8016 2.58076 + vertex 1.11581 1.79695 2.58135 + endloop + endfacet + facet normal 0.818884 -0.102277 0.564773 + outer loop + vertex 1.1168 1.8016 2.58076 + vertex 1.11433 1.79838 2.58376 + vertex 1.11581 1.79695 2.58135 + endloop + endfacet + facet normal 0.805501 -0.0700541 0.588439 + outer loop + vertex 1.11458 1.80323 2.58399 + vertex 1.11433 1.79838 2.58376 + vertex 1.1168 1.8016 2.58076 + endloop + endfacet + facet normal 0.875646 -0.00879316 0.482874 + outer loop + vertex 1.11816 1.80554 2.57835 + vertex 1.11826 1.80956 2.57823 + vertex 1.11663 1.80625 2.58114 + endloop + endfacet + facet normal 0.87581 -0.00737525 0.4826 + outer loop + vertex 1.1168 1.8016 2.58076 + vertex 1.11816 1.80554 2.57835 + vertex 1.11663 1.80625 2.58114 + endloop + endfacet + facet normal 0.820317 -0.0165463 0.57167 + outer loop + vertex 1.11663 1.80625 2.58114 + vertex 1.11458 1.80323 2.58399 + vertex 1.1168 1.8016 2.58076 + endloop + endfacet + facet normal 0.836767 -0.0527774 0.545009 + outer loop + vertex 1.11456 1.80809 2.5845 + vertex 1.11458 1.80323 2.58399 + vertex 1.11663 1.80625 2.58114 + endloop + endfacet + facet normal 0.80939 -0.469808 -0.352374 + outer loop + vertex 1.12 1.81348 2.575 + vertex 1.12 1.81 2.57964 + vertex 1.11798 1.81 2.575 + endloop + endfacet + facet normal 0.880745 -0.109336 0.460797 + outer loop + vertex 1.11826 1.80956 2.57823 + vertex 1.11881 1.8142 2.57829 + vertex 1.11667 1.81152 2.58174 + endloop + endfacet + facet normal 0.8966 -0.0576098 0.439078 + outer loop + vertex 1.11663 1.80625 2.58114 + vertex 1.11826 1.80956 2.57823 + vertex 1.11667 1.81152 2.58174 + endloop + endfacet + facet normal 0.831489 -0.0698918 0.551128 + outer loop + vertex 1.11667 1.81152 2.58174 + vertex 1.11456 1.80809 2.5845 + vertex 1.11663 1.80625 2.58114 + endloop + endfacet + facet normal 0.820282 -0.0478426 0.569955 + outer loop + vertex 1.1144 1.81219 2.58506 + vertex 1.11456 1.80809 2.5845 + vertex 1.11667 1.81152 2.58174 + endloop + endfacet + facet normal 0.881371 -0.103252 0.461003 + outer loop + vertex 1.11881 1.8142 2.57829 + vertex 1.11925 1.81893 2.57851 + vertex 1.11765 1.81598 2.5809 + endloop + endfacet + facet normal 0.880127 -0.106456 0.462648 + outer loop + vertex 1.11667 1.81152 2.58174 + vertex 1.11881 1.8142 2.57829 + vertex 1.11765 1.81598 2.5809 + endloop + endfacet + facet normal 0.786901 -0.0526718 0.614827 + outer loop + vertex 1.1144 1.81219 2.58506 + vertex 1.1154 1.81641 2.58415 + vertex 1.11305 1.81471 2.58701 + endloop + endfacet + facet normal 0.81724 -0.0690968 0.57214 + outer loop + vertex 1.1144 1.81219 2.58506 + vertex 1.11667 1.81152 2.58174 + vertex 1.1154 1.81641 2.58415 + endloop + endfacet + facet normal 0.81517 -0.0709765 0.574857 + outer loop + vertex 1.11667 1.81152 2.58174 + vertex 1.11765 1.81598 2.5809 + vertex 1.1154 1.81641 2.58415 + endloop + endfacet + facet normal 0.78695 -0.052874 0.614747 + outer loop + vertex 1.1154 1.81641 2.58415 + vertex 1.11292 1.81886 2.58754 + vertex 1.11305 1.81471 2.58701 + endloop + endfacet + facet normal 0.853891 -0.0754782 0.51495 + outer loop + vertex 1.11925 1.81893 2.57851 + vertex 1.11938 1.82366 2.57898 + vertex 1.11748 1.82027 2.58164 + endloop + endfacet + facet normal 0.85948 -0.0529686 0.508418 + outer loop + vertex 1.11765 1.81598 2.5809 + vertex 1.11925 1.81893 2.57851 + vertex 1.11748 1.82027 2.58164 + endloop + endfacet + facet normal 0.815736 -0.0661844 0.574625 + outer loop + vertex 1.11765 1.81598 2.5809 + vertex 1.11748 1.82027 2.58164 + vertex 1.1154 1.81641 2.58415 + endloop + endfacet + facet normal 0.808743 -0.0553286 0.585555 + outer loop + vertex 1.11748 1.82027 2.58164 + vertex 1.11527 1.82201 2.58485 + vertex 1.1154 1.81641 2.58415 + endloop + endfacet + facet normal 0.784095 -0.0599029 0.617743 + outer loop + vertex 1.11527 1.82201 2.58485 + vertex 1.11292 1.81886 2.58754 + vertex 1.1154 1.81641 2.58415 + endloop + endfacet + facet normal 0.781706 -0.055174 0.621202 + outer loop + vertex 1.11291 1.82387 2.58798 + vertex 1.11292 1.81886 2.58754 + vertex 1.11527 1.82201 2.58485 + endloop + endfacet + facet normal 0.834696 -0.0629787 0.547099 + outer loop + vertex 1.11938 1.82366 2.57898 + vertex 1.11957 1.82845 2.57925 + vertex 1.11745 1.82536 2.58212 + endloop + endfacet + facet normal 0.839525 -0.0467898 0.541303 + outer loop + vertex 1.11748 1.82027 2.58164 + vertex 1.11938 1.82366 2.57898 + vertex 1.11745 1.82536 2.58212 + endloop + endfacet + facet normal 0.810071 -0.0509818 0.584112 + outer loop + vertex 1.11748 1.82027 2.58164 + vertex 1.11745 1.82536 2.58212 + vertex 1.11527 1.82201 2.58485 + endloop + endfacet + facet normal 0.810027 -0.0508986 0.584179 + outer loop + vertex 1.11745 1.82536 2.58212 + vertex 1.11529 1.82719 2.58528 + vertex 1.11527 1.82201 2.58485 + endloop + endfacet + facet normal 0.782143 -0.0538799 0.620765 + outer loop + vertex 1.11529 1.82719 2.58528 + vertex 1.11291 1.82387 2.58798 + vertex 1.11527 1.82201 2.58485 + endloop + endfacet + facet normal 0.77275 -0.036693 0.633649 + outer loop + vertex 1.11294 1.82883 2.58824 + vertex 1.11291 1.82387 2.58798 + vertex 1.11529 1.82719 2.58528 + endloop + endfacet + facet normal 0.818748 -0.06931 0.569954 + outer loop + vertex 1.11957 1.82845 2.57925 + vertex 1.11971 1.83331 2.57963 + vertex 1.11747 1.83042 2.58251 + endloop + endfacet + facet normal 0.826902 -0.0451343 0.560532 + outer loop + vertex 1.11745 1.82536 2.58212 + vertex 1.11957 1.82845 2.57925 + vertex 1.11747 1.83042 2.58251 + endloop + endfacet + facet normal 0.811334 -0.0468004 0.582706 + outer loop + vertex 1.11745 1.82536 2.58212 + vertex 1.11747 1.83042 2.58251 + vertex 1.11529 1.82719 2.58528 + endloop + endfacet + facet normal 0.805102 -0.0345238 0.59213 + outer loop + vertex 1.11747 1.83042 2.58251 + vertex 1.11521 1.8321 2.58567 + vertex 1.11529 1.82719 2.58528 + endloop + endfacet + facet normal 0.772234 -0.0383826 0.634178 + outer loop + vertex 1.11521 1.8321 2.58567 + vertex 1.11294 1.82883 2.58824 + vertex 1.11529 1.82719 2.58528 + endloop + endfacet + facet normal 0.747229 0.00281142 0.664561 + outer loop + vertex 1.11276 1.83369 2.58843 + vertex 1.11294 1.82883 2.58824 + vertex 1.11521 1.8321 2.58567 + endloop + endfacet + facet normal 0.792765 -0.0713142 0.605341 + outer loop + vertex 1.11971 1.83331 2.57963 + vertex 1.11961 1.83738 2.58024 + vertex 1.11728 1.83571 2.5831 + endloop + endfacet + facet normal 0.805615 -0.0378728 0.591228 + outer loop + vertex 1.11747 1.83042 2.58251 + vertex 1.11971 1.83331 2.57963 + vertex 1.11728 1.83571 2.5831 + endloop + endfacet + facet normal 0.804064 -0.0381589 0.593317 + outer loop + vertex 1.11747 1.83042 2.58251 + vertex 1.11728 1.83571 2.5831 + vertex 1.11521 1.8321 2.58567 + endloop + endfacet + facet normal 0.781181 -0.00288912 0.624298 + outer loop + vertex 1.11728 1.83571 2.5831 + vertex 1.11476 1.83623 2.58625 + vertex 1.11521 1.8321 2.58567 + endloop + endfacet + facet normal 0.742492 -0.0134836 0.66972 + outer loop + vertex 1.11476 1.83623 2.58625 + vertex 1.11276 1.83369 2.58843 + vertex 1.11521 1.8321 2.58567 + endloop + endfacet + facet normal 0.690195 0.0708015 0.720151 + outer loop + vertex 1.11216 1.83892 2.58848 + vertex 1.11276 1.83369 2.58843 + vertex 1.11476 1.83623 2.58625 + endloop + endfacet + facet normal 0.786235 -0.0432571 0.616411 + outer loop + vertex 1.11961 1.83738 2.58024 + vertex 1.11825 1.83976 2.58215 + vertex 1.11728 1.83571 2.5831 + endloop + endfacet + facet normal 0.756031 -0.0535555 0.652341 + outer loop + vertex 1.11825 1.83976 2.58215 + vertex 1.11804 1.84378 2.58273 + vertex 1.11564 1.84046 2.58524 + endloop + endfacet + facet normal 0.759556 -0.0290375 0.649793 + outer loop + vertex 1.11825 1.83976 2.58215 + vertex 1.11564 1.84046 2.58524 + vertex 1.11728 1.83571 2.5831 + endloop + endfacet + facet normal 0.780512 -0.0106458 0.62505 + outer loop + vertex 1.11728 1.83571 2.5831 + vertex 1.11564 1.84046 2.58524 + vertex 1.11476 1.83623 2.58625 + endloop + endfacet + facet normal 0.673027 0.0389615 0.738591 + outer loop + vertex 1.11564 1.84046 2.58524 + vertex 1.11216 1.83892 2.58848 + vertex 1.11476 1.83623 2.58625 + endloop + endfacet + facet normal 0.679386 0.014191 0.733644 + outer loop + vertex 1.113 1.84321 2.58762 + vertex 1.11216 1.83892 2.58848 + vertex 1.11564 1.84046 2.58524 + endloop + endfacet + facet normal 0.724121 -0.0557132 0.687419 + outer loop + vertex 1.11804 1.84378 2.58273 + vertex 1.11786 1.84851 2.58329 + vertex 1.11541 1.84557 2.58563 + endloop + endfacet + facet normal 0.736062 -0.0207263 0.676597 + outer loop + vertex 1.11564 1.84046 2.58524 + vertex 1.11804 1.84378 2.58273 + vertex 1.11541 1.84557 2.58563 + endloop + endfacet + facet normal 0.653337 -0.0305946 0.756448 + outer loop + vertex 1.11541 1.84557 2.58563 + vertex 1.113 1.84321 2.58762 + vertex 1.11564 1.84046 2.58524 + endloop + endfacet + facet normal 0.613261 0.0374975 0.78899 + outer loop + vertex 1.11237 1.84723 2.58792 + vertex 1.113 1.84321 2.58762 + vertex 1.11541 1.84557 2.58563 + endloop + endfacet + facet normal 0.689329 -0.0359037 0.723558 + outer loop + vertex 1.11786 1.84851 2.58329 + vertex 1.11796 1.85322 2.58343 + vertex 1.11523 1.85028 2.58589 + endloop + endfacet + facet normal 0.698145 -0.0114674 0.715865 + outer loop + vertex 1.11541 1.84557 2.58563 + vertex 1.11786 1.84851 2.58329 + vertex 1.11523 1.85028 2.58589 + endloop + endfacet + facet normal 0.593518 -0.0202675 0.804566 + outer loop + vertex 1.11523 1.85028 2.58589 + vertex 1.11237 1.84723 2.58792 + vertex 1.11541 1.84557 2.58563 + endloop + endfacet + facet normal 0.539634 0.0539537 0.840169 + outer loop + vertex 1.11209 1.85176 2.58781 + vertex 1.11237 1.84723 2.58792 + vertex 1.11523 1.85028 2.58589 + endloop + endfacet + facet normal 0.649112 -0.0107396 0.760617 + outer loop + vertex 1.11796 1.85322 2.58343 + vertex 1.1181 1.85817 2.58339 + vertex 1.11519 1.8551 2.58583 + endloop + endfacet + facet normal 0.659236 0.0154971 0.751777 + outer loop + vertex 1.11523 1.85028 2.58589 + vertex 1.11796 1.85322 2.58343 + vertex 1.11519 1.8551 2.58583 + endloop + endfacet + facet normal 0.52732 0.0156122 0.849523 + outer loop + vertex 1.11519 1.8551 2.58583 + vertex 1.11209 1.85176 2.58781 + vertex 1.11523 1.85028 2.58589 + endloop + endfacet + facet normal 0.463076 0.0941759 0.881301 + outer loop + vertex 1.11181 1.85639 2.58746 + vertex 1.11209 1.85176 2.58781 + vertex 1.11519 1.8551 2.58583 + endloop + endfacet + facet normal 0.59324 0.0154461 0.804877 + outer loop + vertex 1.1181 1.85817 2.58339 + vertex 1.11787 1.8632 2.58346 + vertex 1.11504 1.85995 2.58561 + endloop + endfacet + facet normal 0.607155 0.054525 0.79271 + outer loop + vertex 1.11519 1.8551 2.58583 + vertex 1.1181 1.85817 2.58339 + vertex 1.11504 1.85995 2.58561 + endloop + endfacet + facet normal 0.45208 0.0539728 0.890343 + outer loop + vertex 1.11504 1.85995 2.58561 + vertex 1.11181 1.85639 2.58746 + vertex 1.11519 1.8551 2.58583 + endloop + endfacet + facet normal 0.381574 0.130771 0.915041 + outer loop + vertex 1.11142 1.86104 2.58696 + vertex 1.11181 1.85639 2.58746 + vertex 1.11504 1.85995 2.58561 + endloop + endfacet + facet normal 0.516383 0.0522232 0.854764 + outer loop + vertex 1.11787 1.8632 2.58346 + vertex 1.1172 1.86844 2.58354 + vertex 1.11452 1.86459 2.5854 + endloop + endfacet + facet normal 0.528529 0.0973139 0.843319 + outer loop + vertex 1.11504 1.85995 2.58561 + vertex 1.11787 1.8632 2.58346 + vertex 1.11452 1.86459 2.5854 + endloop + endfacet + facet normal 0.370951 0.083461 0.924894 + outer loop + vertex 1.11452 1.86459 2.5854 + vertex 1.11142 1.86104 2.58696 + vertex 1.11504 1.85995 2.58561 + endloop + endfacet + facet normal 0.292235 0.160056 0.942858 + outer loop + vertex 1.11068 1.86546 2.58644 + vertex 1.11142 1.86104 2.58696 + vertex 1.11452 1.86459 2.5854 + endloop + endfacet + facet normal 0.42295 0.13719 0.895707 + outer loop + vertex 1.11353 1.86829 2.5853 + vertex 1.11452 1.86459 2.5854 + vertex 1.1172 1.86844 2.58354 + endloop + endfacet + facet normal 0.424011 0.125324 0.896944 + outer loop + vertex 1.11353 1.86829 2.5853 + vertex 1.1172 1.86844 2.58354 + vertex 1.11423 1.87259 2.58437 + endloop + endfacet + facet normal 0.373542 0.0838715 0.923814 + outer loop + vertex 1.11423 1.87259 2.58437 + vertex 1.1172 1.86844 2.58354 + vertex 1.11813 1.87282 2.58277 + endloop + endfacet + facet normal 0.281887 0.100989 0.954118 + outer loop + vertex 1.11452 1.86459 2.5854 + vertex 1.11353 1.86829 2.5853 + vertex 1.11068 1.86546 2.58644 + endloop + endfacet + facet normal 0.143945 0.198848 0.969401 + outer loop + vertex 1.11462 1.96932 2.566 + vertex 1.11912 1.96977 2.56524 + vertex 1.11461 1.97398 2.56505 + endloop + endfacet + facet normal 0.326678 0.14776 0.933514 + outer loop + vertex 1.11536 2.05289 2.54999 + vertex 1.11759 2.05621 2.54869 + vertex 1.11411 2.0581 2.54961 + endloop + endfacet + facet normal 0.327738 0.150075 0.932773 + outer loop + vertex 1.11759 2.05621 2.54869 + vertex 1.11798 2.0609 2.5478 + vertex 1.11411 2.0581 2.54961 + endloop + endfacet + facet normal 0.334098 0.140769 0.931967 + outer loop + vertex 1.11411 2.0581 2.54961 + vertex 1.11798 2.0609 2.5478 + vertex 1.11305 2.06362 2.54916 + endloop + endfacet + facet normal 0.337218 0.147521 0.929796 + outer loop + vertex 1.11798 2.0609 2.5478 + vertex 1.11686 2.06648 2.54732 + vertex 1.11305 2.06362 2.54916 + endloop + endfacet + facet normal 0.34036 0.143049 0.92935 + outer loop + vertex 1.11305 2.06362 2.54916 + vertex 1.11686 2.06648 2.54732 + vertex 1.11354 2.0682 2.54827 + endloop + endfacet + facet normal 0.342247 0.147454 0.927968 + outer loop + vertex 1.11686 2.06648 2.54732 + vertex 1.11581 2.07152 2.5469 + vertex 1.11354 2.0682 2.54827 + endloop + endfacet + facet normal 0.336481 0.151961 0.929348 + outer loop + vertex 1.11354 2.0682 2.54827 + vertex 1.11581 2.07152 2.5469 + vertex 1.11204 2.07139 2.54829 + endloop + endfacet + facet normal 0.348751 0.154532 0.924388 + outer loop + vertex 1.11896 2.07354 2.54541 + vertex 1.11971 2.07761 2.54444 + vertex 1.11654 2.0756 2.54597 + endloop + endfacet + facet normal 0.345397 0.150057 0.926382 + outer loop + vertex 1.11654 2.0756 2.54597 + vertex 1.11581 2.07152 2.5469 + vertex 1.11896 2.07354 2.54541 + endloop + endfacet + facet normal 0.336946 0.152199 0.929141 + outer loop + vertex 1.11654 2.0756 2.54597 + vertex 1.1126 2.07583 2.54736 + vertex 1.11581 2.07152 2.5469 + endloop + endfacet + facet normal 0.336492 0.151837 0.929365 + outer loop + vertex 1.1126 2.07583 2.54736 + vertex 1.11204 2.07139 2.54829 + vertex 1.11581 2.07152 2.5469 + endloop + endfacet + facet normal 0.346794 0.145822 0.926536 + outer loop + vertex 1.11971 2.07761 2.54444 + vertex 1.11825 2.08341 2.54407 + vertex 1.11543 2.07956 2.54573 + endloop + endfacet + facet normal 0.349514 0.153273 0.924309 + outer loop + vertex 1.11654 2.0756 2.54597 + vertex 1.11971 2.07761 2.54444 + vertex 1.11543 2.07956 2.54573 + endloop + endfacet + facet normal 0.336943 0.150059 0.92949 + outer loop + vertex 1.11543 2.07956 2.54573 + vertex 1.1126 2.07583 2.54736 + vertex 1.11654 2.0756 2.54597 + endloop + endfacet + facet normal 0.342745 0.145074 0.928159 + outer loop + vertex 1.11113 2.08141 2.54703 + vertex 1.1126 2.07583 2.54736 + vertex 1.11543 2.07956 2.54573 + endloop + endfacet + facet normal 0.346212 0.146309 0.926677 + outer loop + vertex 1.11425 2.08361 2.54554 + vertex 1.11543 2.07956 2.54573 + vertex 1.11825 2.08341 2.54407 + endloop + endfacet + facet normal 0.346255 0.139638 0.92769 + outer loop + vertex 1.11425 2.08361 2.54554 + vertex 1.11825 2.08341 2.54407 + vertex 1.11473 2.08796 2.5447 + endloop + endfacet + facet normal 0.349154 0.142084 0.926231 + outer loop + vertex 1.11473 2.08796 2.5447 + vertex 1.11825 2.08341 2.54407 + vertex 1.11848 2.08812 2.54327 + endloop + endfacet + facet normal 0.342855 0.145394 0.928068 + outer loop + vertex 1.11543 2.07956 2.54573 + vertex 1.11425 2.08361 2.54554 + vertex 1.11113 2.08141 2.54703 + endloop + endfacet + facet normal 0.348636 0.147897 0.925516 + outer loop + vertex 1.11848 2.08812 2.54327 + vertex 1.11678 2.09147 2.54337 + vertex 1.11473 2.08796 2.5447 + endloop + endfacet + facet normal 0.35332 0.144683 0.924247 + outer loop + vertex 1.11473 2.08796 2.5447 + vertex 1.11678 2.09147 2.54337 + vertex 1.11314 2.09351 2.54444 + endloop + endfacet + facet normal 0.359801 0.158693 0.919435 + outer loop + vertex 1.11678 2.09147 2.54337 + vertex 1.11693 2.09622 2.54249 + vertex 1.11314 2.09351 2.54444 + endloop + endfacet + facet normal 0.36309 0.153768 0.918978 + outer loop + vertex 1.11314 2.09351 2.54444 + vertex 1.11693 2.09622 2.54249 + vertex 1.11344 2.09716 2.54372 + endloop + endfacet + facet normal 0.36374 0.176206 0.914683 + outer loop + vertex 1.11988 2.09872 2.54087 + vertex 1.12032 2.1028 2.53991 + vertex 1.1173 2.10072 2.54151 + endloop + endfacet + facet normal 0.359977 0.17055 0.91724 + outer loop + vertex 1.1173 2.10072 2.54151 + vertex 1.11693 2.09622 2.54249 + vertex 1.11988 2.09872 2.54087 + endloop + endfacet + facet normal 0.378522 0.167505 0.910309 + outer loop + vertex 1.1173 2.10072 2.54151 + vertex 1.11357 2.10093 2.54302 + vertex 1.11693 2.09622 2.54249 + endloop + endfacet + facet normal 0.363466 0.155828 0.918482 + outer loop + vertex 1.11357 2.10093 2.54302 + vertex 1.11344 2.09716 2.54372 + vertex 1.11693 2.09622 2.54249 + endloop + endfacet + facet normal 0.373937 0.177064 0.910395 + outer loop + vertex 1.12032 2.1028 2.53991 + vertex 1.11891 2.10803 2.53947 + vertex 1.11611 2.10482 2.54125 + endloop + endfacet + facet normal 0.370024 0.16655 0.913971 + outer loop + vertex 1.1173 2.10072 2.54151 + vertex 1.12032 2.1028 2.53991 + vertex 1.11611 2.10482 2.54125 + endloop + endfacet + facet normal 0.378503 0.168772 0.910083 + outer loop + vertex 1.11611 2.10482 2.54125 + vertex 1.11357 2.10093 2.54302 + vertex 1.1173 2.10072 2.54151 + endloop + endfacet + facet normal 0.393325 0.157157 0.905868 + outer loop + vertex 1.11202 2.10653 2.54272 + vertex 1.11357 2.10093 2.54302 + vertex 1.11611 2.10482 2.54125 + endloop + endfacet + facet normal 0.390761 0.183399 0.902037 + outer loop + vertex 1.11891 2.10803 2.53947 + vertex 1.1176 2.11348 2.53893 + vertex 1.11488 2.10979 2.54086 + endloop + endfacet + facet normal 0.385108 0.165888 0.90784 + outer loop + vertex 1.11611 2.10482 2.54125 + vertex 1.11891 2.10803 2.53947 + vertex 1.11488 2.10979 2.54086 + endloop + endfacet + facet normal 0.396742 0.168344 0.902361 + outer loop + vertex 1.11488 2.10979 2.54086 + vertex 1.11202 2.10653 2.54272 + vertex 1.11611 2.10482 2.54125 + endloop + endfacet + facet normal 0.398836 0.16621 0.901834 + outer loop + vertex 1.11084 2.11191 2.54226 + vertex 1.11202 2.10653 2.54272 + vertex 1.11488 2.10979 2.54086 + endloop + endfacet + facet normal 0.398145 0.176921 0.9001 + outer loop + vertex 1.11394 2.1138 2.54048 + vertex 1.11488 2.10979 2.54086 + vertex 1.1176 2.11348 2.53893 + endloop + endfacet + facet normal 0.39798 0.215849 0.89164 + outer loop + vertex 1.11394 2.1138 2.54048 + vertex 1.1176 2.11348 2.53893 + vertex 1.11477 2.11743 2.53924 + endloop + endfacet + facet normal 0.385102 0.20598 0.899594 + outer loop + vertex 1.11477 2.11743 2.53924 + vertex 1.1176 2.11348 2.53893 + vertex 1.1176 2.11706 2.53811 + endloop + endfacet + facet normal 0.403487 0.177924 0.897519 + outer loop + vertex 1.11488 2.10979 2.54086 + vertex 1.11394 2.1138 2.54048 + vertex 1.11084 2.11191 2.54226 + endloop + endfacet + facet normal 0.386337 0.261443 0.884529 + outer loop + vertex 1.1176 2.11706 2.53811 + vertex 1.11728 2.11995 2.53739 + vertex 1.11477 2.11743 2.53924 + endloop + endfacet + facet normal 0.372538 0.276247 0.885948 + outer loop + vertex 1.11477 2.11743 2.53924 + vertex 1.11728 2.11995 2.53739 + vertex 1.11425 2.12043 2.53852 + endloop + endfacet + facet normal 0.302921 0.588471 0.749627 + outer loop + vertex 1.11386 2.12329 2.53717 + vertex 1.11868 2.12261 2.53576 + vertex 1.11759 2.12559 2.53386 + endloop + endfacet + facet normal 0.227599 0.660856 0.71517 + outer loop + vertex 1.11264 2.12629 2.53479 + vertex 1.11386 2.12329 2.53717 + vertex 1.11759 2.12559 2.53386 + endloop + endfacet + facet normal 0.372677 0.436695 0.818785 + outer loop + vertex 1.11728 2.11995 2.53739 + vertex 1.11386 2.12329 2.53717 + vertex 1.11425 2.12043 2.53852 + endloop + endfacet + facet normal 0.309448 0.375391 0.873684 + outer loop + vertex 1.11868 2.12261 2.53576 + vertex 1.11386 2.12329 2.53717 + vertex 1.11728 2.11995 2.53739 + endloop + endfacet + facet normal -0.108203 0.890391 0.44215 + outer loop + vertex 1.11393 2.13053 2.52664 + vertex 1.11969 2.13074 2.52762 + vertex 1.11627 2.13209 2.52406 + endloop + endfacet + facet normal -0.135915 0.896864 0.420907 + outer loop + vertex 1.11257 2.13205 2.52295 + vertex 1.11393 2.13053 2.52664 + vertex 1.11627 2.13209 2.52406 + endloop + endfacet + facet normal -0.129833 0.798665 0.587603 + outer loop + vertex 1.11969 2.13074 2.52762 + vertex 1.11393 2.13053 2.52664 + vertex 1.11856 2.12842 2.53053 + endloop + endfacet + facet normal 0.00941194 0.883737 0.46789 + outer loop + vertex 1.11856 2.12842 2.53053 + vertex 1.11393 2.13053 2.52664 + vertex 1.11259 2.12821 2.53103 + endloop + endfacet + facet normal 0.206406 0.871816 0.444222 + outer loop + vertex 1.11759 2.12559 2.53386 + vertex 1.11259 2.12821 2.53103 + vertex 1.11264 2.12629 2.53479 + endloop + endfacet + facet normal 0.0291799 0.758076 0.651513 + outer loop + vertex 1.11856 2.12842 2.53053 + vertex 1.11259 2.12821 2.53103 + vertex 1.11759 2.12559 2.53386 + endloop + endfacet + facet normal 0.0795458 -0.175851 0.981198 + outer loop + vertex 1.118 2.13656 2.51944 + vertex 1.11867 2.14 2.52 + vertex 1.115 2.13834 2.52 + endloop + endfacet + facet normal 0.448006 0.524737 0.723838 + outer loop + vertex 1.118 2.13656 2.51944 + vertex 1.115 2.13834 2.52 + vertex 1.11723 2.13437 2.5215 + endloop + endfacet + facet normal -0.191718 0.250143 0.949038 + outer loop + vertex 1.11723 2.13437 2.5215 + vertex 1.115 2.13834 2.52 + vertex 1.11346 2.13357 2.52095 + endloop + endfacet + facet normal -0.172754 0.819797 0.545976 + outer loop + vertex 1.11627 2.13209 2.52406 + vertex 1.11346 2.13357 2.52095 + vertex 1.11257 2.13205 2.52295 + endloop + endfacet + facet normal -0.249425 0.767742 0.59022 + outer loop + vertex 1.11723 2.13437 2.5215 + vertex 1.11346 2.13357 2.52095 + vertex 1.11627 2.13209 2.52406 + endloop + endfacet + facet normal 0.788642 0.425519 0.443821 + outer loop + vertex 1.12 2.14275 2.515 + vertex 1.11867 2.14 2.52 + vertex 1.12059 2.1382 2.51832 + endloop + endfacet + facet normal -0.967671 0.207604 -0.143229 + outer loop + vertex 1.11941 2.14 2.515 + vertex 1.11867 2.14 2.52 + vertex 1.12 2.14275 2.515 + endloop + endfacet + facet normal 0.506796 -0.234628 0.829522 + outer loop + vertex 1.12059 2.1382 2.51832 + vertex 1.11867 2.14 2.52 + vertex 1.118 2.13656 2.51944 + endloop + endfacet + facet normal -0.493729 -0.498004 0.712898 + outer loop + vertex 1.125 0.883265 2.515 + vertex 1.12362 0.885057 2.5153 + vertex 1.12325 0.885 2.515 + endloop + endfacet + facet normal -0.58122 -0.767312 0.270954 + outer loop + vertex 1.12362 0.885057 2.5153 + vertex 1.12397 0.885703 2.51787 + vertex 1.1209 0.887735 2.51704 + endloop + endfacet + facet normal -0.732556 -0.372032 -0.570047 + outer loop + vertex 1.12362 0.885057 2.5153 + vertex 1.1209 0.887735 2.51704 + vertex 1.12134 0.89 2.515 + endloop + endfacet + facet normal -0.587685 -0.224493 0.777322 + outer loop + vertex 1.12362 0.885057 2.5153 + vertex 1.12134 0.89 2.515 + vertex 1.12325 0.885 2.515 + endloop + endfacet + facet normal -0.877864 -0.215309 -0.427782 + outer loop + vertex 1.12 0.89 2.51775 + vertex 1.12134 0.89 2.515 + vertex 1.1209 0.887735 2.51704 + endloop + endfacet + facet normal -0.451036 -0.81261 0.369095 + outer loop + vertex 1.11983 0.888759 2.51933 + vertex 1.12288 0.887306 2.51986 + vertex 1.12132 0.888956 2.52158 + endloop + endfacet + facet normal -0.448321 -0.874969 0.182861 + outer loop + vertex 1.11983 0.888759 2.51933 + vertex 1.1209 0.887735 2.51704 + vertex 1.12288 0.887306 2.51986 + endloop + endfacet + facet normal -0.581575 -0.758272 0.294608 + outer loop + vertex 1.1209 0.887735 2.51704 + vertex 1.12397 0.885703 2.51787 + vertex 1.12288 0.887306 2.51986 + endloop + endfacet + facet normal -0.389615 -0.815488 0.427994 + outer loop + vertex 1.12288 0.887306 2.51986 + vertex 1.12465 0.88821 2.52319 + vertex 1.12132 0.888956 2.52158 + endloop + endfacet + facet normal -0.412699 -0.842417 0.346429 + outer loop + vertex 1.11983 0.888759 2.51933 + vertex 1.12132 0.888956 2.52158 + vertex 1.11772 0.890575 2.52123 + endloop + endfacet + facet normal -0.399338 -0.794255 0.457918 + outer loop + vertex 1.12132 0.888956 2.52158 + vertex 1.12465 0.88821 2.52319 + vertex 1.12163 0.890724 2.52492 + endloop + endfacet + facet normal -0.40133 -0.793401 0.457656 + outer loop + vertex 1.12132 0.888956 2.52158 + vertex 1.12163 0.890724 2.52492 + vertex 1.11772 0.890575 2.52123 + endloop + endfacet + facet normal -0.276382 -0.902775 0.329561 + outer loop + vertex 1.11772 0.890575 2.52123 + vertex 1.12163 0.890724 2.52492 + vertex 1.11653 0.892236 2.52478 + endloop + endfacet + facet normal -0.25659 -0.818735 0.513648 + outer loop + vertex 1.12163 0.890724 2.52492 + vertex 1.11961 0.893466 2.52828 + vertex 1.11653 0.892236 2.52478 + endloop + endfacet + facet normal -0.152255 -0.808559 0.568375 + outer loop + vertex 1.12456 0.892817 2.52868 + vertex 1.11961 0.893466 2.52828 + vertex 1.12163 0.890724 2.52492 + endloop + endfacet + facet normal -0.148949 -0.706253 0.692113 + outer loop + vertex 1.11961 0.893466 2.52828 + vertex 1.12456 0.892817 2.52868 + vertex 1.12218 0.895854 2.53127 + endloop + endfacet + facet normal -0.0126283 -0.775983 0.630627 + outer loop + vertex 1.11726 0.895914 2.53124 + vertex 1.11961 0.893466 2.52828 + vertex 1.12218 0.895854 2.53127 + endloop + endfacet + facet normal -0.0120907 -0.696486 0.717469 + outer loop + vertex 1.12218 0.895854 2.53127 + vertex 1.1194 0.898615 2.5339 + vertex 1.11726 0.895914 2.53124 + endloop + endfacet + facet normal 0.157756 -0.594029 0.788824 + outer loop + vertex 1.12476 0.899647 2.53361 + vertex 1.1194 0.898615 2.5339 + vertex 1.12218 0.895854 2.53127 + endloop + endfacet + facet normal 0.152863 -0.561673 0.813116 + outer loop + vertex 1.1194 0.898615 2.5339 + vertex 1.12476 0.899647 2.53361 + vertex 1.12121 0.901954 2.53587 + endloop + endfacet + facet normal 0.235123 -0.584705 0.776426 + outer loop + vertex 1.11615 0.901267 2.53688 + vertex 1.1194 0.898615 2.5339 + vertex 1.12121 0.901954 2.53587 + endloop + endfacet + facet normal 0.234083 -0.452573 0.860455 + outer loop + vertex 1.12121 0.901954 2.53587 + vertex 1.11922 0.905298 2.53817 + vertex 1.11615 0.901267 2.53688 + endloop + endfacet + facet normal 0.303389 -0.410848 0.859743 + outer loop + vertex 1.12302 0.905016 2.53669 + vertex 1.11922 0.905298 2.53817 + vertex 1.12121 0.901954 2.53587 + endloop + endfacet + facet normal 0.327457 -0.167025 0.929986 + outer loop + vertex 1.12025 0.977456 2.55092 + vertex 1.11763 0.975122 2.55142 + vertex 1.12012 0.974288 2.55039 + endloop + endfacet + facet normal 0.262448 -0.167636 0.950273 + outer loop + vertex 1.12025 0.977456 2.55092 + vertex 1.12012 0.974288 2.55039 + vertex 1.12389 0.978615 2.55012 + endloop + endfacet + facet normal 0.347093 -0.191666 0.918036 + outer loop + vertex 1.12025 0.977456 2.55092 + vertex 1.11825 0.97916 2.55203 + vertex 1.11763 0.975122 2.55142 + endloop + endfacet + facet normal 0.266282 -0.182299 0.946499 + outer loop + vertex 1.12389 0.978615 2.55012 + vertex 1.12196 0.980324 2.55099 + vertex 1.12025 0.977456 2.55092 + endloop + endfacet + facet normal 0.326293 -0.217378 0.919935 + outer loop + vertex 1.12196 0.980324 2.55099 + vertex 1.11825 0.97916 2.55203 + vertex 1.12025 0.977456 2.55092 + endloop + endfacet + facet normal 0.329769 -0.233027 0.91485 + outer loop + vertex 1.12196 0.980324 2.55099 + vertex 1.12302 0.984153 2.55158 + vertex 1.11825 0.97916 2.55203 + endloop + endfacet + facet normal 0.28525 -0.188183 0.939798 + outer loop + vertex 1.12302 0.984153 2.55158 + vertex 1.11839 0.984209 2.553 + vertex 1.11825 0.97916 2.55203 + endloop + endfacet + facet normal 0.284148 -0.203999 0.936827 + outer loop + vertex 1.12302 0.984153 2.55158 + vertex 1.12319 0.98889 2.55256 + vertex 1.11839 0.984209 2.553 + endloop + endfacet + facet normal 0.228222 -0.0626291 0.971593 + outer loop + vertex 1.12178 1.1287 2.58097 + vertex 1.12178 1.13288 2.58124 + vertex 1.11818 1.12871 2.58182 + endloop + endfacet + facet normal 0.273884 -0.104158 0.956106 + outer loop + vertex 1.11818 1.12871 2.58182 + vertex 1.12178 1.13288 2.58124 + vertex 1.11794 1.13335 2.58239 + endloop + endfacet + facet normal 0.280501 -0.0558601 0.958227 + outer loop + vertex 1.12178 1.13288 2.58124 + vertex 1.1217 1.13772 2.58155 + vertex 1.11794 1.13335 2.58239 + endloop + endfacet + facet normal 0.33042 -0.102727 0.938227 + outer loop + vertex 1.11794 1.13335 2.58239 + vertex 1.1217 1.13772 2.58155 + vertex 1.11784 1.13833 2.58297 + endloop + endfacet + facet normal 0.336072 -0.0692574 0.939286 + outer loop + vertex 1.1217 1.13772 2.58155 + vertex 1.12149 1.14247 2.58197 + vertex 1.11784 1.13833 2.58297 + endloop + endfacet + facet normal 0.390462 -0.123639 0.912279 + outer loop + vertex 1.11784 1.13833 2.58297 + vertex 1.12149 1.14247 2.58197 + vertex 1.11786 1.14313 2.58361 + endloop + endfacet + facet normal 0.39597 -0.0956336 0.91327 + outer loop + vertex 1.12149 1.14247 2.58197 + vertex 1.12111 1.14626 2.58253 + vertex 1.11786 1.14313 2.58361 + endloop + endfacet + facet normal 0.436498 -0.14658 0.887684 + outer loop + vertex 1.11786 1.14313 2.58361 + vertex 1.12111 1.14626 2.58253 + vertex 1.11829 1.14782 2.58418 + endloop + endfacet + facet normal 0.709044 -0.039447 0.70406 + outer loop + vertex 1.12257 1.15019 2.58175 + vertex 1.12501 1.15397 2.5795 + vertex 1.12214 1.15387 2.58239 + endloop + endfacet + facet normal 0.592749 -0.0702176 0.802321 + outer loop + vertex 1.12257 1.15019 2.58175 + vertex 1.12214 1.15387 2.58239 + vertex 1.11959 1.15212 2.58412 + endloop + endfacet + facet normal 0.551142 -0.155916 0.819715 + outer loop + vertex 1.12257 1.15019 2.58175 + vertex 1.11959 1.15212 2.58412 + vertex 1.11829 1.14782 2.58418 + endloop + endfacet + facet normal 0.498696 -0.0128419 0.866682 + outer loop + vertex 1.12257 1.15019 2.58175 + vertex 1.11829 1.14782 2.58418 + vertex 1.12111 1.14626 2.58253 + endloop + endfacet + facet normal 0.471711 -0.131309 0.871921 + outer loop + vertex 1.11675 1.15018 2.58536 + vertex 1.11829 1.14782 2.58418 + vertex 1.11959 1.15212 2.58412 + endloop + endfacet + facet normal 0.447574 -0.0842078 0.890273 + outer loop + vertex 1.11959 1.15212 2.58412 + vertex 1.1167 1.15331 2.58569 + vertex 1.11675 1.15018 2.58536 + endloop + endfacet + facet normal 0.70908 -0.0138775 0.704992 + outer loop + vertex 1.12501 1.15397 2.5795 + vertex 1.123 1.15644 2.58158 + vertex 1.12214 1.15387 2.58239 + endloop + endfacet + facet normal 0.64228 0.00609902 0.766446 + outer loop + vertex 1.123 1.15644 2.58158 + vertex 1.12234 1.15995 2.5821 + vertex 1.12007 1.1564 2.58403 + endloop + endfacet + facet normal 0.641856 0.0280496 0.766312 + outer loop + vertex 1.123 1.15644 2.58158 + vertex 1.12007 1.1564 2.58403 + vertex 1.12214 1.15387 2.58239 + endloop + endfacet + facet normal 0.58352 -0.0485637 0.810645 + outer loop + vertex 1.12214 1.15387 2.58239 + vertex 1.12007 1.1564 2.58403 + vertex 1.11959 1.15212 2.58412 + endloop + endfacet + facet normal 0.465284 -0.0336537 0.884521 + outer loop + vertex 1.12007 1.1564 2.58403 + vertex 1.1167 1.15331 2.58569 + vertex 1.11959 1.15212 2.58412 + endloop + endfacet + facet normal 0.486557 -0.063964 0.871304 + outer loop + vertex 1.11648 1.15764 2.58613 + vertex 1.1167 1.15331 2.58569 + vertex 1.12007 1.1564 2.58403 + endloop + endfacet + facet normal 0.659374 -0.00296853 0.751809 + outer loop + vertex 1.12234 1.15995 2.5821 + vertex 1.12158 1.16492 2.58279 + vertex 1.11938 1.16115 2.5847 + endloop + endfacet + facet normal 0.657555 -0.0107628 0.75333 + outer loop + vertex 1.12007 1.1564 2.58403 + vertex 1.12234 1.15995 2.5821 + vertex 1.11938 1.16115 2.5847 + endloop + endfacet + facet normal 0.490065 -0.0518577 0.870142 + outer loop + vertex 1.11938 1.16115 2.5847 + vertex 1.11648 1.15764 2.58613 + vertex 1.12007 1.1564 2.58403 + endloop + endfacet + facet normal 0.497233 -0.0596304 0.865565 + outer loop + vertex 1.11593 1.16276 2.58679 + vertex 1.11648 1.15764 2.58613 + vertex 1.11938 1.16115 2.5847 + endloop + endfacet + facet normal 0.677447 -0.0219446 0.735245 + outer loop + vertex 1.11888 1.16498 2.58528 + vertex 1.11938 1.16115 2.5847 + vertex 1.12158 1.16492 2.58279 + endloop + endfacet + facet normal 0.677699 -0.0103945 0.735266 + outer loop + vertex 1.11888 1.16498 2.58528 + vertex 1.12158 1.16492 2.58279 + vertex 1.11945 1.16857 2.58481 + endloop + endfacet + facet normal 0.707994 0.0237052 0.70582 + outer loop + vertex 1.11945 1.16857 2.58481 + vertex 1.12158 1.16492 2.58279 + vertex 1.12188 1.16971 2.58233 + endloop + endfacet + facet normal 0.495166 -0.0650732 0.866358 + outer loop + vertex 1.11938 1.16115 2.5847 + vertex 1.11888 1.16498 2.58528 + vertex 1.11593 1.16276 2.58679 + endloop + endfacet + facet normal 0.802698 0.0887949 0.589738 + outer loop + vertex 1.12377 1.17138 2.5799 + vertex 1.12398 1.17511 2.57905 + vertex 1.12229 1.17311 2.58165 + endloop + endfacet + facet normal 0.778636 0.0304936 0.626735 + outer loop + vertex 1.12229 1.17311 2.58165 + vertex 1.12188 1.16971 2.58233 + vertex 1.12377 1.17138 2.5799 + endloop + endfacet + facet normal 0.722894 0.0497916 0.689163 + outer loop + vertex 1.12229 1.17311 2.58165 + vertex 1.11976 1.17349 2.58427 + vertex 1.12188 1.16971 2.58233 + endloop + endfacet + facet normal 0.706141 0.0310265 0.707391 + outer loop + vertex 1.11976 1.17349 2.58427 + vertex 1.11945 1.16857 2.58481 + vertex 1.12188 1.16971 2.58233 + endloop + endfacet + facet normal 0.810415 0.0965627 0.577843 + outer loop + vertex 1.12398 1.17511 2.57905 + vertex 1.12368 1.17989 2.57867 + vertex 1.12181 1.17693 2.58178 + endloop + endfacet + facet normal 0.806572 0.0802344 0.585666 + outer loop + vertex 1.12229 1.17311 2.58165 + vertex 1.12398 1.17511 2.57905 + vertex 1.12181 1.17693 2.58178 + endloop + endfacet + facet normal 0.723398 0.0662742 0.687243 + outer loop + vertex 1.12181 1.17693 2.58178 + vertex 1.11976 1.17349 2.58427 + vertex 1.12229 1.17311 2.58165 + endloop + endfacet + facet normal 0.73984 0.0449205 0.671282 + outer loop + vertex 1.11925 1.17909 2.58446 + vertex 1.11976 1.17349 2.58427 + vertex 1.12181 1.17693 2.58178 + endloop + endfacet + facet normal 0.827977 0.0775034 0.55538 + outer loop + vertex 1.12368 1.17989 2.57867 + vertex 1.12349 1.18479 2.57827 + vertex 1.12158 1.18198 2.58151 + endloop + endfacet + facet normal 0.82554 0.0684946 0.560171 + outer loop + vertex 1.12181 1.17693 2.58178 + vertex 1.12368 1.17989 2.57867 + vertex 1.12158 1.18198 2.58151 + endloop + endfacet + facet normal 0.748611 0.070162 0.659286 + outer loop + vertex 1.12158 1.18198 2.58151 + vertex 1.11925 1.17909 2.58446 + vertex 1.12181 1.17693 2.58178 + endloop + endfacet + facet normal 0.763213 0.0434293 0.644685 + outer loop + vertex 1.11912 1.18442 2.58426 + vertex 1.11925 1.17909 2.58446 + vertex 1.12158 1.18198 2.58151 + endloop + endfacet + facet normal 0.836334 0.0639003 0.544484 + outer loop + vertex 1.12349 1.18479 2.57827 + vertex 1.12361 1.1886 2.57764 + vertex 1.12168 1.18765 2.58071 + endloop + endfacet + facet normal 0.835377 0.0618461 0.546188 + outer loop + vertex 1.12158 1.18198 2.58151 + vertex 1.12349 1.18479 2.57827 + vertex 1.12168 1.18765 2.58071 + endloop + endfacet + facet normal 0.77501 0.0745584 0.627535 + outer loop + vertex 1.12168 1.18765 2.58071 + vertex 1.11912 1.18442 2.58426 + vertex 1.12158 1.18198 2.58151 + endloop + endfacet + facet normal 0.790662 0.0435961 0.610699 + outer loop + vertex 1.11902 1.18968 2.58401 + vertex 1.11912 1.18442 2.58426 + vertex 1.12168 1.18765 2.58071 + endloop + endfacet + facet normal 0.893363 0.174702 0.413983 + outer loop + vertex 1.1241 1.19111 2.5758 + vertex 1.12375 1.1947 2.57504 + vertex 1.12301 1.192 2.57778 + endloop + endfacet + facet normal 0.892356 0.14008 0.429044 + outer loop + vertex 1.12361 1.1886 2.57764 + vertex 1.1241 1.19111 2.5758 + vertex 1.12301 1.192 2.57778 + endloop + endfacet + facet normal 0.823095 0.122915 0.554442 + outer loop + vertex 1.12361 1.1886 2.57764 + vertex 1.12301 1.192 2.57778 + vertex 1.12168 1.18765 2.58071 + endloop + endfacet + facet normal 0.838998 0.104305 0.534044 + outer loop + vertex 1.12168 1.18765 2.58071 + vertex 1.12301 1.192 2.57778 + vertex 1.12106 1.19317 2.58062 + endloop + endfacet + facet normal 0.803955 0.10117 0.586022 + outer loop + vertex 1.12106 1.19317 2.58062 + vertex 1.11902 1.18968 2.58401 + vertex 1.12168 1.18765 2.58071 + endloop + endfacet + facet normal 0.832724 0.0507211 0.55136 + outer loop + vertex 1.11884 1.19483 2.58382 + vertex 1.11902 1.18968 2.58401 + vertex 1.12106 1.19317 2.58062 + endloop + endfacet + facet normal 0.879789 0.116597 0.460843 + outer loop + vertex 1.12375 1.1947 2.57504 + vertex 1.12359 1.19878 2.57432 + vertex 1.12246 1.19767 2.57675 + endloop + endfacet + facet normal 0.901679 0.159997 0.401716 + outer loop + vertex 1.12301 1.192 2.57778 + vertex 1.12375 1.1947 2.57504 + vertex 1.12246 1.19767 2.57675 + endloop + endfacet + facet normal 0.843435 0.173688 0.508379 + outer loop + vertex 1.12301 1.192 2.57778 + vertex 1.12246 1.19767 2.57675 + vertex 1.12106 1.19317 2.58062 + endloop + endfacet + facet normal 0.876931 0.125105 0.464049 + outer loop + vertex 1.12246 1.19767 2.57675 + vertex 1.12052 1.1985 2.5802 + vertex 1.12106 1.19317 2.58062 + endloop + endfacet + facet normal 0.844532 0.126303 0.520397 + outer loop + vertex 1.12052 1.1985 2.5802 + vertex 1.11884 1.19483 2.58382 + vertex 1.12106 1.19317 2.58062 + endloop + endfacet + facet normal 0.880598 0.0599728 0.470054 + outer loop + vertex 1.11862 1.19991 2.58358 + vertex 1.11884 1.19483 2.58382 + vertex 1.12052 1.1985 2.5802 + endloop + endfacet + facet normal -0.296445 -0.103463 0.949429 + outer loop + vertex 1.12359 1.19878 2.57432 + vertex 1.125 1.20096 2.575 + vertex 1.12359 1.205 2.575 + endloop + endfacet + facet normal 0.913961 -0.0445521 0.40335 + outer loop + vertex 1.12359 1.19878 2.57432 + vertex 1.12359 1.205 2.575 + vertex 1.12246 1.19767 2.57675 + endloop + endfacet + facet normal 0.565223 0.108012 0.817836 + outer loop + vertex 1.12246 1.19767 2.57675 + vertex 1.12359 1.205 2.575 + vertex 1.12148 1.20343 2.57666 + endloop + endfacet + facet normal 0.876109 0.155671 0.456288 + outer loop + vertex 1.12246 1.19767 2.57675 + vertex 1.12148 1.20343 2.57666 + vertex 1.12052 1.1985 2.5802 + endloop + endfacet + facet normal 0.899869 0.123823 0.418214 + outer loop + vertex 1.12148 1.20343 2.57666 + vertex 1.11994 1.20359 2.57993 + vertex 1.12052 1.1985 2.5802 + endloop + endfacet + facet normal 0.886207 0.123746 0.446457 + outer loop + vertex 1.11994 1.20359 2.57993 + vertex 1.11862 1.19991 2.58358 + vertex 1.12052 1.1985 2.5802 + endloop + endfacet + facet normal 0.910797 0.0747924 0.406022 + outer loop + vertex 1.11834 1.20495 2.58327 + vertex 1.11862 1.19991 2.58358 + vertex 1.11994 1.20359 2.57993 + endloop + endfacet + facet normal 0.569462 0.100226 0.815885 + outer loop + vertex 1.12359 1.205 2.575 + vertex 1.12271 1.21 2.575 + vertex 1.12148 1.20343 2.57666 + endloop + endfacet + facet normal 0.548133 0.107653 0.829434 + outer loop + vertex 1.12271 1.21 2.575 + vertex 1.12053 1.20819 2.57667 + vertex 1.12148 1.20343 2.57666 + endloop + endfacet + facet normal 0.893437 0.17759 0.412592 + outer loop + vertex 1.12148 1.20343 2.57666 + vertex 1.12053 1.20819 2.57667 + vertex 1.11994 1.20359 2.57993 + endloop + endfacet + facet normal 0.939767 0.108904 0.324003 + outer loop + vertex 1.12053 1.20819 2.57667 + vertex 1.11942 1.20828 2.57986 + vertex 1.11994 1.20359 2.57993 + endloop + endfacet + facet normal 0.912876 0.106982 0.39397 + outer loop + vertex 1.11942 1.20828 2.57986 + vertex 1.11834 1.20495 2.58327 + vertex 1.11994 1.20359 2.57993 + endloop + endfacet + facet normal 0.923588 0.083251 0.374239 + outer loop + vertex 1.11809 1.20976 2.58282 + vertex 1.11834 1.20495 2.58327 + vertex 1.11942 1.20828 2.57986 + endloop + endfacet + facet normal 0.484153 0.204313 0.850795 + outer loop + vertex 1.12271 1.21 2.575 + vertex 1.1206 1.215 2.575 + vertex 1.12053 1.20819 2.57667 + endloop + endfacet + facet normal 0.870362 0.109292 0.480131 + outer loop + vertex 1.1206 1.215 2.575 + vertex 1.11973 1.21179 2.5773 + vertex 1.12053 1.20819 2.57667 + endloop + endfacet + facet normal 0.93486 0.151383 0.321122 + outer loop + vertex 1.12053 1.20819 2.57667 + vertex 1.11973 1.21179 2.5773 + vertex 1.11942 1.20828 2.57986 + endloop + endfacet + facet normal 0.962056 0.100007 0.253864 + outer loop + vertex 1.11973 1.21179 2.5773 + vertex 1.11899 1.21254 2.57984 + vertex 1.11942 1.20828 2.57986 + endloop + endfacet + facet normal 0.924779 0.0967411 0.368002 + outer loop + vertex 1.11899 1.21254 2.57984 + vertex 1.11809 1.20976 2.58282 + vertex 1.11942 1.20828 2.57986 + endloop + endfacet + facet normal 0.932929 0.076763 0.351782 + outer loop + vertex 1.11806 1.21347 2.58209 + vertex 1.11809 1.20976 2.58282 + vertex 1.11899 1.21254 2.57984 + endloop + endfacet + facet normal 0.651133 0.488325 -0.581003 + outer loop + vertex 1.12 1.22 2.57853 + vertex 1.1206 1.215 2.575 + vertex 1.12 1.2158 2.575 + endloop + endfacet + facet normal 0.723295 -0.338242 0.602027 + outer loop + vertex 1.12 1.22 2.57853 + vertex 1.11922 1.2171 2.57784 + vertex 1.1206 1.215 2.575 + endloop + endfacet + facet normal 0.911613 0.0467511 0.408382 + outer loop + vertex 1.11922 1.2171 2.57784 + vertex 1.11973 1.21179 2.5773 + vertex 1.1206 1.215 2.575 + endloop + endfacet + facet normal 0.923268 0.137594 0.358671 + outer loop + vertex 1.11853 1.21572 2.58015 + vertex 1.11922 1.2171 2.57784 + vertex 1.11825 1.21925 2.57952 + endloop + endfacet + facet normal 0.934857 0.101026 0.340347 + outer loop + vertex 1.11853 1.21572 2.58015 + vertex 1.11899 1.21254 2.57984 + vertex 1.11922 1.2171 2.57784 + endloop + endfacet + facet normal 0.962239 0.0660972 0.264058 + outer loop + vertex 1.11899 1.21254 2.57984 + vertex 1.11973 1.21179 2.5773 + vertex 1.11922 1.2171 2.57784 + endloop + endfacet + facet normal 0.934144 0.100722 0.342389 + outer loop + vertex 1.11899 1.21254 2.57984 + vertex 1.11853 1.21572 2.58015 + vertex 1.11806 1.21347 2.58209 + endloop + endfacet + facet normal 0.137748 -0.265286 0.954279 + outer loop + vertex 1.12 1.225 2.57992 + vertex 1.11922 1.2171 2.57784 + vertex 1.12 1.22 2.57853 + endloop + endfacet + facet normal -0.596831 -0.149137 0.788385 + outer loop + vertex 1.11888 1.22152 2.57841 + vertex 1.11922 1.2171 2.57784 + vertex 1.12 1.225 2.57992 + endloop + endfacet + facet normal 0.866133 0.00132268 0.499812 + outer loop + vertex 1.11888 1.22152 2.57841 + vertex 1.11825 1.21925 2.57952 + vertex 1.11922 1.2171 2.57784 + endloop + endfacet + facet normal 0.843837 0.0251174 0.536012 + outer loop + vertex 1.11836 1.22339 2.57915 + vertex 1.11825 1.21925 2.57952 + vertex 1.11888 1.22152 2.57841 + endloop + endfacet + facet normal -0.425807 -0.240317 0.872317 + outer loop + vertex 1.12 1.225 2.57992 + vertex 1.12 1.22529 2.58 + vertex 1.11888 1.22152 2.57841 + endloop + endfacet + facet normal -0.0410542 -0.376669 0.925438 + outer loop + vertex 1.11888 1.22152 2.57841 + vertex 1.12 1.22529 2.58 + vertex 1.11836 1.22339 2.57915 + endloop + endfacet + facet normal -0.884414 0.129988 0.448236 + outer loop + vertex 1.11897 1.80601 2.57759 + vertex 1.12 1.80469 2.58 + vertex 1.12 1.805 2.57991 + endloop + endfacet + facet normal -0.0414186 0.868721 0.493567 + outer loop + vertex 1.11897 1.80601 2.57759 + vertex 1.11816 1.80554 2.57835 + vertex 1.12 1.80469 2.58 + endloop + endfacet + facet normal -0.910494 0.0223083 0.41292 + outer loop + vertex 1.12 1.81 2.57964 + vertex 1.11897 1.80601 2.57759 + vertex 1.12 1.805 2.57991 + endloop + endfacet + facet normal -0.966607 0.13745 0.216285 + outer loop + vertex 1.11915 1.8096 2.57608 + vertex 1.11897 1.80601 2.57759 + vertex 1.12 1.81 2.57964 + endloop + endfacet + facet normal 0.549887 0.301323 0.778992 + outer loop + vertex 1.11915 1.8096 2.57608 + vertex 1.11816 1.80554 2.57835 + vertex 1.11897 1.80601 2.57759 + endloop + endfacet + facet normal 0.924961 -0.0132709 0.379831 + outer loop + vertex 1.11826 1.80956 2.57823 + vertex 1.11816 1.80554 2.57835 + vertex 1.11915 1.8096 2.57608 + endloop + endfacet + facet normal -0.944567 0.262651 0.196998 + outer loop + vertex 1.12 1.81348 2.575 + vertex 1.11915 1.8096 2.57608 + vertex 1.12 1.81 2.57964 + endloop + endfacet + facet normal 0.404459 -0.327285 -0.853989 + outer loop + vertex 1.12 1.81348 2.575 + vertex 1.12123 1.815 2.575 + vertex 1.11915 1.8096 2.57608 + endloop + endfacet + facet normal 0.402389 0.02824 0.915033 + outer loop + vertex 1.12123 1.815 2.575 + vertex 1.11984 1.81375 2.57565 + vertex 1.11915 1.8096 2.57608 + endloop + endfacet + facet normal 0.919675 -0.114291 0.375681 + outer loop + vertex 1.11984 1.81375 2.57565 + vertex 1.11826 1.80956 2.57823 + vertex 1.11915 1.8096 2.57608 + endloop + endfacet + facet normal 0.918989 -0.112707 0.377832 + outer loop + vertex 1.11881 1.8142 2.57829 + vertex 1.11826 1.80956 2.57823 + vertex 1.11984 1.81375 2.57565 + endloop + endfacet + facet normal 0.499159 -0.107822 0.859776 + outer loop + vertex 1.12123 1.815 2.575 + vertex 1.12231 1.82 2.575 + vertex 1.11984 1.81375 2.57565 + endloop + endfacet + facet normal 0.489352 -0.103305 0.865946 + outer loop + vertex 1.12231 1.82 2.575 + vertex 1.12059 1.81847 2.57579 + vertex 1.11984 1.81375 2.57565 + endloop + endfacet + facet normal 0.910956 -0.155666 0.382005 + outer loop + vertex 1.12059 1.81847 2.57579 + vertex 1.11881 1.8142 2.57829 + vertex 1.11984 1.81375 2.57565 + endloop + endfacet + facet normal 0.885373 -0.103267 0.453267 + outer loop + vertex 1.11925 1.81893 2.57851 + vertex 1.11881 1.8142 2.57829 + vertex 1.12059 1.81847 2.57579 + endloop + endfacet + facet normal 0.476324 -0.0838334 0.875264 + outer loop + vertex 1.12231 1.82 2.575 + vertex 1.12319 1.825 2.575 + vertex 1.12059 1.81847 2.57579 + endloop + endfacet + facet normal 0.565941 -0.126896 0.814622 + outer loop + vertex 1.12319 1.825 2.575 + vertex 1.12117 1.8232 2.57612 + vertex 1.12059 1.81847 2.57579 + endloop + endfacet + facet normal 0.878628 -0.140839 0.456265 + outer loop + vertex 1.12117 1.8232 2.57612 + vertex 1.11925 1.81893 2.57851 + vertex 1.12059 1.81847 2.57579 + endloop + endfacet + facet normal 0.839363 -0.0773701 0.538037 + outer loop + vertex 1.11938 1.82366 2.57898 + vertex 1.11925 1.81893 2.57851 + vertex 1.12117 1.8232 2.57612 + endloop + endfacet + facet normal 0.584123 -0.158875 0.795964 + outer loop + vertex 1.12319 1.825 2.575 + vertex 1.12455 1.83 2.575 + vertex 1.12117 1.8232 2.57612 + endloop + endfacet + facet normal 0.546451 -0.135141 0.826516 + outer loop + vertex 1.12455 1.83 2.575 + vertex 1.12122 1.82692 2.5767 + vertex 1.12117 1.8232 2.57612 + endloop + endfacet + facet normal 0.836883 -0.0942204 0.539212 + outer loop + vertex 1.12122 1.82692 2.5767 + vertex 1.11938 1.82366 2.57898 + vertex 1.12117 1.8232 2.57612 + endloop + endfacet + facet normal 0.819861 -0.0636251 0.569016 + outer loop + vertex 1.11957 1.82845 2.57925 + vertex 1.11938 1.82366 2.57898 + vertex 1.12122 1.82692 2.5767 + endloop + endfacet + facet normal -0.0169215 0.610502 0.791834 + outer loop + vertex 1.125 1.83295 2.575 + vertex 1.12445 1.83508 2.57334 + vertex 1.12221 1.83145 2.57609 + endloop + endfacet + facet normal 0.392239 -0.059836 0.917915 + outer loop + vertex 1.125 1.83295 2.575 + vertex 1.12221 1.83145 2.57609 + vertex 1.12455 1.83 2.575 + endloop + endfacet + facet normal 0.436028 0.0243188 0.899604 + outer loop + vertex 1.12455 1.83 2.575 + vertex 1.12221 1.83145 2.57609 + vertex 1.12122 1.82692 2.5767 + endloop + endfacet + facet normal 0.807183 -0.0989735 0.581945 + outer loop + vertex 1.12221 1.83145 2.57609 + vertex 1.11957 1.82845 2.57925 + vertex 1.12122 1.82692 2.5767 + endloop + endfacet + facet normal 0.796868 -0.070987 0.599969 + outer loop + vertex 1.11971 1.83331 2.57963 + vertex 1.11957 1.82845 2.57925 + vertex 1.12221 1.83145 2.57609 + endloop + endfacet + facet normal 0.794213 -0.172231 0.58272 + outer loop + vertex 1.12445 1.83508 2.57334 + vertex 1.12438 1.83836 2.57441 + vertex 1.1221 1.83666 2.57702 + endloop + endfacet + facet normal 0.823004 -0.0817122 0.562127 + outer loop + vertex 1.12221 1.83145 2.57609 + vertex 1.12445 1.83508 2.57334 + vertex 1.1221 1.83666 2.57702 + endloop + endfacet + facet normal 0.790634 -0.0901327 0.605619 + outer loop + vertex 1.1221 1.83666 2.57702 + vertex 1.11971 1.83331 2.57963 + vertex 1.12221 1.83145 2.57609 + endloop + endfacet + facet normal 0.781993 -0.0736211 0.618924 + outer loop + vertex 1.11961 1.83738 2.58024 + vertex 1.11971 1.83331 2.57963 + vertex 1.1221 1.83666 2.57702 + endloop + endfacet + facet normal 0.838383 0.00556097 0.545053 + outer loop + vertex 1.12438 1.83836 2.57441 + vertex 1.12492 1.84273 2.57353 + vertex 1.12311 1.84073 2.57633 + endloop + endfacet + facet normal 0.777742 -0.0894075 0.622192 + outer loop + vertex 1.1221 1.83666 2.57702 + vertex 1.12438 1.83836 2.57441 + vertex 1.12311 1.84073 2.57633 + endloop + endfacet + facet normal 0.772903 -0.0628301 0.631406 + outer loop + vertex 1.11961 1.83738 2.58024 + vertex 1.12063 1.84144 2.57941 + vertex 1.11825 1.83976 2.58215 + endloop + endfacet + facet normal 0.78292 -0.0679983 0.618395 + outer loop + vertex 1.11961 1.83738 2.58024 + vertex 1.1221 1.83666 2.57702 + vertex 1.12063 1.84144 2.57941 + endloop + endfacet + facet normal 0.765107 -0.0835169 0.638463 + outer loop + vertex 1.1221 1.83666 2.57702 + vertex 1.12311 1.84073 2.57633 + vertex 1.12063 1.84144 2.57941 + endloop + endfacet + facet normal 0.769799 -0.0504932 0.636286 + outer loop + vertex 1.12063 1.84144 2.57941 + vertex 1.11804 1.84378 2.58273 + vertex 1.11825 1.83976 2.58215 + endloop + endfacet + facet normal 0.838241 -0.0220449 0.544855 + outer loop + vertex 1.12492 1.84273 2.57353 + vertex 1.12448 1.84845 2.57445 + vertex 1.12272 1.8451 2.57702 + endloop + endfacet + facet normal 0.842772 -0.0080275 0.538211 + outer loop + vertex 1.12311 1.84073 2.57633 + vertex 1.12492 1.84273 2.57353 + vertex 1.12272 1.8451 2.57702 + endloop + endfacet + facet normal 0.773717 -0.0292292 0.632857 + outer loop + vertex 1.12311 1.84073 2.57633 + vertex 1.12272 1.8451 2.57702 + vertex 1.12063 1.84144 2.57941 + endloop + endfacet + facet normal 0.787278 -0.0488625 0.614659 + outer loop + vertex 1.12272 1.8451 2.57702 + vertex 1.12028 1.8468 2.58028 + vertex 1.12063 1.84144 2.57941 + endloop + endfacet + facet normal 0.768486 -0.0538212 0.637599 + outer loop + vertex 1.12028 1.8468 2.58028 + vertex 1.11804 1.84378 2.58273 + vertex 1.12063 1.84144 2.57941 + endloop + endfacet + facet normal 0.765661 -0.0486594 0.641402 + outer loop + vertex 1.11786 1.84851 2.58329 + vertex 1.11804 1.84378 2.58273 + vertex 1.12028 1.8468 2.58028 + endloop + endfacet + facet normal 0.828801 -0.0707158 0.555057 + outer loop + vertex 1.12448 1.84845 2.57445 + vertex 1.12432 1.85261 2.57521 + vertex 1.12231 1.85068 2.57796 + endloop + endfacet + facet normal 0.842615 -0.0298396 0.537689 + outer loop + vertex 1.12272 1.8451 2.57702 + vertex 1.12448 1.84845 2.57445 + vertex 1.12231 1.85068 2.57796 + endloop + endfacet + facet normal 0.787947 -0.046606 0.613977 + outer loop + vertex 1.12272 1.8451 2.57702 + vertex 1.12231 1.85068 2.57796 + vertex 1.12028 1.8468 2.58028 + endloop + endfacet + facet normal 0.790839 -0.0505482 0.609933 + outer loop + vertex 1.12231 1.85068 2.57796 + vertex 1.11991 1.85104 2.58111 + vertex 1.12028 1.8468 2.58028 + endloop + endfacet + facet normal 0.761996 -0.0598445 0.64481 + outer loop + vertex 1.11991 1.85104 2.58111 + vertex 1.11786 1.84851 2.58329 + vertex 1.12028 1.8468 2.58028 + endloop + endfacet + facet normal 0.749291 -0.0353074 0.661299 + outer loop + vertex 1.11796 1.85322 2.58343 + vertex 1.11786 1.84851 2.58329 + vertex 1.11991 1.85104 2.58111 + endloop + endfacet + facet normal 0.830172 -0.0760951 0.55229 + outer loop + vertex 1.12432 1.85261 2.57521 + vertex 1.12326 1.85491 2.57712 + vertex 1.12231 1.85068 2.57796 + endloop + endfacet + facet normal 0.787688 -0.0675386 0.612361 + outer loop + vertex 1.12326 1.85491 2.57712 + vertex 1.12321 1.85895 2.57764 + vertex 1.12086 1.85552 2.58028 + endloop + endfacet + facet normal 0.789444 -0.0552379 0.611331 + outer loop + vertex 1.12326 1.85491 2.57712 + vertex 1.12086 1.85552 2.58028 + vertex 1.12231 1.85068 2.57796 + endloop + endfacet + facet normal 0.790466 -0.0543366 0.610091 + outer loop + vertex 1.12231 1.85068 2.57796 + vertex 1.12086 1.85552 2.58028 + vertex 1.11991 1.85104 2.58111 + endloop + endfacet + facet normal 0.748951 -0.0359833 0.661648 + outer loop + vertex 1.12086 1.85552 2.58028 + vertex 1.11796 1.85322 2.58343 + vertex 1.11991 1.85104 2.58111 + endloop + endfacet + facet normal 0.741576 -0.0141811 0.670719 + outer loop + vertex 1.1181 1.85817 2.58339 + vertex 1.11796 1.85322 2.58343 + vertex 1.12086 1.85552 2.58028 + endloop + endfacet + facet normal 0.762896 -0.0531948 0.64433 + outer loop + vertex 1.12321 1.85895 2.57764 + vertex 1.12318 1.86385 2.57808 + vertex 1.12072 1.86102 2.58075 + endloop + endfacet + facet normal 0.769412 -0.0355128 0.637764 + outer loop + vertex 1.12086 1.85552 2.58028 + vertex 1.12321 1.85895 2.57764 + vertex 1.12072 1.86102 2.58075 + endloop + endfacet + facet normal 0.729765 -0.0403074 0.682508 + outer loop + vertex 1.12072 1.86102 2.58075 + vertex 1.1181 1.85817 2.58339 + vertex 1.12086 1.85552 2.58028 + endloop + endfacet + facet normal 0.696976 0.0215321 0.716771 + outer loop + vertex 1.11787 1.8632 2.58346 + vertex 1.1181 1.85817 2.58339 + vertex 1.12072 1.86102 2.58075 + endloop + endfacet + facet normal 0.728351 -0.0375036 0.684177 + outer loop + vertex 1.12318 1.86385 2.57808 + vertex 1.12316 1.86876 2.57836 + vertex 1.12055 1.86606 2.581 + endloop + endfacet + facet normal 0.74035 -0.00733113 0.672181 + outer loop + vertex 1.12072 1.86102 2.58075 + vertex 1.12318 1.86385 2.57808 + vertex 1.12055 1.86606 2.581 + endloop + endfacet + facet normal 0.683637 -0.0121508 0.729721 + outer loop + vertex 1.12055 1.86606 2.581 + vertex 1.11787 1.8632 2.58346 + vertex 1.12072 1.86102 2.58075 + endloop + endfacet + facet normal 0.634503 0.0685601 0.769874 + outer loop + vertex 1.1172 1.86844 2.58354 + vertex 1.11787 1.8632 2.58346 + vertex 1.12055 1.86606 2.581 + endloop + endfacet + facet normal 0.703848 -0.0365659 0.709409 + outer loop + vertex 1.12316 1.86876 2.57836 + vertex 1.12319 1.87347 2.57858 + vertex 1.12058 1.87085 2.58103 + endloop + endfacet + facet normal 0.714922 -0.00988936 0.699134 + outer loop + vertex 1.12055 1.86606 2.581 + vertex 1.12316 1.86876 2.57836 + vertex 1.12058 1.87085 2.58103 + endloop + endfacet + facet normal 0.601157 -0.00962811 0.799073 + outer loop + vertex 1.12058 1.87085 2.58103 + vertex 1.1172 1.86844 2.58354 + vertex 1.12055 1.86606 2.581 + endloop + endfacet + facet normal 0.588431 0.0178505 0.80835 + outer loop + vertex 1.11813 1.87282 2.58277 + vertex 1.1172 1.86844 2.58354 + vertex 1.12058 1.87085 2.58103 + endloop + endfacet + facet normal 0.674122 -0.0254692 0.738181 + outer loop + vertex 1.12319 1.87347 2.57858 + vertex 1.12333 1.8781 2.57861 + vertex 1.12066 1.87538 2.58096 + endloop + endfacet + facet normal 0.684815 0.000417827 0.728717 + outer loop + vertex 1.12058 1.87085 2.58103 + vertex 1.12319 1.87347 2.57858 + vertex 1.12066 1.87538 2.58096 + endloop + endfacet + facet normal 0.580817 0.0033458 0.814027 + outer loop + vertex 1.12066 1.87538 2.58096 + vertex 1.11813 1.87282 2.58277 + vertex 1.12058 1.87085 2.58103 + endloop + endfacet + facet normal 0.516635 0.0928855 0.851152 + outer loop + vertex 1.11742 1.87667 2.58278 + vertex 1.11813 1.87282 2.58277 + vertex 1.12066 1.87538 2.58096 + endloop + endfacet + facet normal 0.621884 0.00740884 0.783075 + outer loop + vertex 1.12333 1.8781 2.57861 + vertex 1.12323 1.88311 2.57864 + vertex 1.12042 1.88004 2.5809 + endloop + endfacet + facet normal 0.635144 0.0412802 0.771289 + outer loop + vertex 1.12066 1.87538 2.58096 + vertex 1.12333 1.8781 2.57861 + vertex 1.12042 1.88004 2.5809 + endloop + endfacet + facet normal 0.501321 0.0356071 0.864528 + outer loop + vertex 1.12042 1.88004 2.5809 + vertex 1.11742 1.87667 2.58278 + vertex 1.12066 1.87538 2.58096 + endloop + endfacet + facet normal 0.422833 0.124177 0.897659 + outer loop + vertex 1.11674 1.8814 2.58244 + vertex 1.11742 1.87667 2.58278 + vertex 1.12042 1.88004 2.5809 + endloop + endfacet + facet normal 0.543056 0.0313508 0.839111 + outer loop + vertex 1.12323 1.88311 2.57864 + vertex 1.12252 1.88879 2.57889 + vertex 1.1198 1.88498 2.58079 + endloop + endfacet + facet normal 0.56345 0.0892 0.82132 + outer loop + vertex 1.12042 1.88004 2.5809 + vertex 1.12323 1.88311 2.57864 + vertex 1.1198 1.88498 2.58079 + endloop + endfacet + facet normal 0.408605 0.0717544 0.909887 + outer loop + vertex 1.1198 1.88498 2.58079 + vertex 1.11674 1.8814 2.58244 + vertex 1.12042 1.88004 2.5809 + endloop + endfacet + facet normal 0.316349 0.161888 0.934728 + outer loop + vertex 1.11548 1.88658 2.58198 + vertex 1.11674 1.8814 2.58244 + vertex 1.1198 1.88498 2.58079 + endloop + endfacet + facet normal 0.452589 0.118127 0.88386 + outer loop + vertex 1.11883 1.88919 2.58072 + vertex 1.1198 1.88498 2.58079 + vertex 1.12252 1.88879 2.57889 + endloop + endfacet + facet normal 0.452894 0.128051 0.882321 + outer loop + vertex 1.11883 1.88919 2.58072 + vertex 1.12252 1.88879 2.57889 + vertex 1.11919 1.89392 2.57985 + endloop + endfacet + facet normal 0.369776 0.0658796 0.926782 + outer loop + vertex 1.11919 1.89392 2.57985 + vertex 1.12252 1.88879 2.57889 + vertex 1.12346 1.89323 2.5782 + endloop + endfacet + facet normal 0.291865 0.0822072 0.95292 + outer loop + vertex 1.1198 1.88498 2.58079 + vertex 1.11883 1.88919 2.58072 + vertex 1.11548 1.88658 2.58198 + endloop + endfacet + facet normal 0.365575 0.0315017 0.930249 + outer loop + vertex 1.12346 1.89323 2.5782 + vertex 1.12309 1.89725 2.57821 + vertex 1.11919 1.89392 2.57985 + endloop + endfacet + facet normal 0.299701 0.156998 0.941027 + outer loop + vertex 1.11909 2.05295 2.54876 + vertex 1.12191 2.05593 2.54736 + vertex 1.11759 2.05621 2.54869 + endloop + endfacet + facet normal 0.293717 0.177912 0.93919 + outer loop + vertex 1.1248 2.05876 2.54591 + vertex 1.12519 2.06296 2.54499 + vertex 1.12203 2.06072 2.54641 + endloop + endfacet + facet normal 0.294749 0.179532 0.938558 + outer loop + vertex 1.12203 2.06072 2.54641 + vertex 1.12191 2.05593 2.54736 + vertex 1.1248 2.05876 2.54591 + endloop + endfacet + facet normal 0.326862 0.176714 0.928404 + outer loop + vertex 1.12203 2.06072 2.54641 + vertex 1.11798 2.0609 2.5478 + vertex 1.12191 2.05593 2.54736 + endloop + endfacet + facet normal 0.299661 0.154109 0.941517 + outer loop + vertex 1.11798 2.0609 2.5478 + vertex 1.11759 2.05621 2.54869 + vertex 1.12191 2.05593 2.54736 + endloop + endfacet + facet normal 0.315979 0.173268 0.93281 + outer loop + vertex 1.12519 2.06296 2.54499 + vertex 1.12385 2.06804 2.54451 + vertex 1.12089 2.06483 2.5461 + endloop + endfacet + facet normal 0.309454 0.155025 0.938193 + outer loop + vertex 1.12203 2.06072 2.54641 + vertex 1.12519 2.06296 2.54499 + vertex 1.12089 2.06483 2.5461 + endloop + endfacet + facet normal 0.327131 0.159403 0.931438 + outer loop + vertex 1.12089 2.06483 2.5461 + vertex 1.11798 2.0609 2.5478 + vertex 1.12203 2.06072 2.54641 + endloop + endfacet + facet normal 0.34065 0.148097 0.928453 + outer loop + vertex 1.11686 2.06648 2.54732 + vertex 1.11798 2.0609 2.5478 + vertex 1.12089 2.06483 2.5461 + endloop + endfacet + facet normal 0.340589 0.160458 0.926419 + outer loop + vertex 1.12385 2.06804 2.54451 + vertex 1.12268 2.07335 2.54402 + vertex 1.11985 2.06964 2.5457 + endloop + endfacet + facet normal 0.337726 0.151362 0.928995 + outer loop + vertex 1.12089 2.06483 2.5461 + vertex 1.12385 2.06804 2.54451 + vertex 1.11985 2.06964 2.5457 + endloop + endfacet + facet normal 0.341968 0.152144 0.927313 + outer loop + vertex 1.11985 2.06964 2.5457 + vertex 1.11686 2.06648 2.54732 + vertex 1.12089 2.06483 2.5461 + endloop + endfacet + facet normal 0.345841 0.14808 0.926534 + outer loop + vertex 1.11581 2.07152 2.5469 + vertex 1.11686 2.06648 2.54732 + vertex 1.11985 2.06964 2.5457 + endloop + endfacet + facet normal 0.35252 0.150108 0.923687 + outer loop + vertex 1.11896 2.07354 2.54541 + vertex 1.11985 2.06964 2.5457 + vertex 1.12268 2.07335 2.54402 + endloop + endfacet + facet normal 0.352489 0.153543 0.923134 + outer loop + vertex 1.11896 2.07354 2.54541 + vertex 1.12268 2.07335 2.54402 + vertex 1.11971 2.07761 2.54444 + endloop + endfacet + facet normal 0.360605 0.15961 0.918961 + outer loop + vertex 1.11971 2.07761 2.54444 + vertex 1.12268 2.07335 2.54402 + vertex 1.12287 2.07709 2.54329 + endloop + endfacet + facet normal 0.346133 0.148852 0.926302 + outer loop + vertex 1.11985 2.06964 2.5457 + vertex 1.11896 2.07354 2.54541 + vertex 1.11581 2.07152 2.5469 + endloop + endfacet + facet normal 0.359894 0.15192 0.920542 + outer loop + vertex 1.12287 2.07709 2.54329 + vertex 1.12308 2.08088 2.54259 + vertex 1.11971 2.07761 2.54444 + endloop + endfacet + facet normal 0.362183 0.149291 0.920074 + outer loop + vertex 1.11971 2.07761 2.54444 + vertex 1.12308 2.08088 2.54259 + vertex 1.11825 2.08341 2.54407 + endloop + endfacet + facet normal 0.359128 0.142114 0.922405 + outer loop + vertex 1.12308 2.08088 2.54259 + vertex 1.12188 2.08632 2.54221 + vertex 1.11825 2.08341 2.54407 + endloop + endfacet + facet normal 0.360035 0.140878 0.922241 + outer loop + vertex 1.11825 2.08341 2.54407 + vertex 1.12188 2.08632 2.54221 + vertex 1.11848 2.08812 2.54327 + endloop + endfacet + facet normal 0.362581 0.146831 0.920313 + outer loop + vertex 1.12188 2.08632 2.54221 + vertex 1.12053 2.09154 2.54191 + vertex 1.11848 2.08812 2.54327 + endloop + endfacet + facet normal 0.355803 0.15164 0.922177 + outer loop + vertex 1.11848 2.08812 2.54327 + vertex 1.12053 2.09154 2.54191 + vertex 1.11678 2.09147 2.54337 + endloop + endfacet + facet normal 0.367173 0.168609 0.914743 + outer loop + vertex 1.12359 2.09363 2.54035 + vertex 1.12394 2.09813 2.53938 + vertex 1.121 2.09565 2.54102 + endloop + endfacet + facet normal 0.360696 0.158903 0.919048 + outer loop + vertex 1.121 2.09565 2.54102 + vertex 1.12053 2.09154 2.54191 + vertex 1.12359 2.09363 2.54035 + endloop + endfacet + facet normal 0.356011 0.159802 0.920717 + outer loop + vertex 1.121 2.09565 2.54102 + vertex 1.11693 2.09622 2.54249 + vertex 1.12053 2.09154 2.54191 + endloop + endfacet + facet normal 0.355238 0.159156 0.921127 + outer loop + vertex 1.11693 2.09622 2.54249 + vertex 1.11678 2.09147 2.54337 + vertex 1.12053 2.09154 2.54191 + endloop + endfacet + facet normal 0.361486 0.175933 0.915629 + outer loop + vertex 1.11988 2.09872 2.54087 + vertex 1.121 2.09565 2.54102 + vertex 1.12394 2.09813 2.53938 + endloop + endfacet + facet normal 0.361531 0.176629 0.915477 + outer loop + vertex 1.11988 2.09872 2.54087 + vertex 1.12394 2.09813 2.53938 + vertex 1.12032 2.1028 2.53991 + endloop + endfacet + facet normal 0.360585 0.175834 0.916003 + outer loop + vertex 1.12032 2.1028 2.53991 + vertex 1.12394 2.09813 2.53938 + vertex 1.12404 2.10286 2.53843 + endloop + endfacet + facet normal 0.356983 0.174381 0.91769 + outer loop + vertex 1.121 2.09565 2.54102 + vertex 1.11988 2.09872 2.54087 + vertex 1.11693 2.09622 2.54249 + endloop + endfacet + facet normal 0.360338 0.178878 0.91551 + outer loop + vertex 1.12404 2.10286 2.53843 + vertex 1.12233 2.10619 2.53846 + vertex 1.12032 2.1028 2.53991 + endloop + endfacet + facet normal 0.36563 0.175152 0.914131 + outer loop + vertex 1.12032 2.1028 2.53991 + vertex 1.12233 2.10619 2.53846 + vertex 1.11891 2.10803 2.53947 + endloop + endfacet + facet normal 0.366841 0.177978 0.9131 + outer loop + vertex 1.12233 2.10619 2.53846 + vertex 1.12249 2.11088 2.53748 + vertex 1.11891 2.10803 2.53947 + endloop + endfacet + facet normal 0.366347 0.178644 0.913168 + outer loop + vertex 1.11891 2.10803 2.53947 + vertex 1.12249 2.11088 2.53748 + vertex 1.1176 2.11348 2.53893 + endloop + endfacet + facet normal 0.375457 0.200411 0.904913 + outer loop + vertex 1.12249 2.11088 2.53748 + vertex 1.12073 2.11658 2.53694 + vertex 1.1176 2.11348 2.53893 + endloop + endfacet + facet normal 0.369146 0.207417 0.90593 + outer loop + vertex 1.1176 2.11348 2.53893 + vertex 1.12073 2.11658 2.53694 + vertex 1.1176 2.11706 2.53811 + endloop + endfacet + facet normal 0.364966 0.303124 0.880293 + outer loop + vertex 1.12369 2.11861 2.5353 + vertex 1.1233 2.12249 2.53413 + vertex 1.12084 2.12029 2.5359 + endloop + endfacet + facet normal 0.336729 0.24486 0.909207 + outer loop + vertex 1.12084 2.12029 2.5359 + vertex 1.12073 2.11658 2.53694 + vertex 1.12369 2.11861 2.5353 + endloop + endfacet + facet normal 0.354882 0.242547 0.902901 + outer loop + vertex 1.12084 2.12029 2.5359 + vertex 1.11728 2.11995 2.53739 + vertex 1.12073 2.11658 2.53694 + endloop + endfacet + facet normal 0.371708 0.261388 0.890792 + outer loop + vertex 1.11728 2.11995 2.53739 + vertex 1.1176 2.11706 2.53811 + vertex 1.12073 2.11658 2.53694 + endloop + endfacet + facet normal 0.319427 0.353233 0.879314 + outer loop + vertex 1.11868 2.12261 2.53576 + vertex 1.12084 2.12029 2.5359 + vertex 1.1233 2.12249 2.53413 + endloop + endfacet + facet normal 0.283247 0.586887 0.758509 + outer loop + vertex 1.11868 2.12261 2.53576 + vertex 1.1233 2.12249 2.53413 + vertex 1.11759 2.12559 2.53386 + endloop + endfacet + facet normal 0.208229 0.45794 0.864252 + outer loop + vertex 1.11759 2.12559 2.53386 + vertex 1.1233 2.12249 2.53413 + vertex 1.12232 2.12621 2.53239 + endloop + endfacet + facet normal 0.330383 0.362909 0.871289 + outer loop + vertex 1.12084 2.12029 2.5359 + vertex 1.11868 2.12261 2.53576 + vertex 1.11728 2.11995 2.53739 + endloop + endfacet + facet normal -0.287096 0.770879 0.568613 + outer loop + vertex 1.12056 2.13306 2.52491 + vertex 1.11627 2.13209 2.52406 + vertex 1.11969 2.13074 2.52762 + endloop + endfacet + facet normal -0.207955 0.774648 0.597224 + outer loop + vertex 1.12373 2.13178 2.52768 + vertex 1.12056 2.13306 2.52491 + vertex 1.11969 2.13074 2.52762 + endloop + endfacet + facet normal -0.172606 0.629517 0.757572 + outer loop + vertex 1.12373 2.13178 2.52768 + vertex 1.11969 2.13074 2.52762 + vertex 1.1243 2.12887 2.53022 + endloop + endfacet + facet normal -0.0299089 0.786617 0.616717 + outer loop + vertex 1.1243 2.12887 2.53022 + vertex 1.11969 2.13074 2.52762 + vertex 1.11856 2.12842 2.53053 + endloop + endfacet + facet normal 0.107833 0.742366 0.66126 + outer loop + vertex 1.12232 2.12621 2.53239 + vertex 1.11856 2.12842 2.53053 + vertex 1.11759 2.12559 2.53386 + endloop + endfacet + facet normal -0.00970109 0.635811 0.771784 + outer loop + vertex 1.1243 2.12887 2.53022 + vertex 1.11856 2.12842 2.53053 + vertex 1.12232 2.12621 2.53239 + endloop + endfacet + facet normal -0.269286 0.709117 0.651643 + outer loop + vertex 1.12123 2.13558 2.52183 + vertex 1.118 2.13656 2.51944 + vertex 1.11723 2.13437 2.5215 + endloop + endfacet + facet normal -0.287256 0.766258 0.574745 + outer loop + vertex 1.11723 2.13437 2.5215 + vertex 1.11627 2.13209 2.52406 + vertex 1.12056 2.13306 2.52491 + endloop + endfacet + facet normal -0.28129 0.771347 0.570877 + outer loop + vertex 1.12123 2.13558 2.52183 + vertex 1.11723 2.13437 2.5215 + vertex 1.12056 2.13306 2.52491 + endloop + endfacet + facet normal -0.30322 0.768334 0.563667 + outer loop + vertex 1.12123 2.13558 2.52183 + vertex 1.12056 2.13306 2.52491 + vertex 1.12483 2.13439 2.5254 + endloop + endfacet + facet normal -0.404012 0.663074 0.630164 + outer loop + vertex 1.12123 2.13558 2.52183 + vertex 1.12483 2.13439 2.5254 + vertex 1.12413 2.13615 2.52309 + endloop + endfacet + facet normal -0.291385 0.695912 0.656354 + outer loop + vertex 1.12483 2.13439 2.5254 + vertex 1.12056 2.13306 2.52491 + vertex 1.12373 2.13178 2.52768 + endloop + endfacet + facet normal 0.167195 -0.224421 0.960042 + outer loop + vertex 1.1235 2.14191 2.51419 + vertex 1.12302 2.145 2.515 + vertex 1.12 2.14275 2.515 + endloop + endfacet + facet normal 0.308229 0.819053 0.483887 + outer loop + vertex 1.1235 2.14191 2.51419 + vertex 1.12 2.14275 2.515 + vertex 1.12389 2.14005 2.51709 + endloop + endfacet + facet normal -0.0288617 0.586488 0.809444 + outer loop + vertex 1.12389 2.14005 2.51709 + vertex 1.12 2.14275 2.515 + vertex 1.12059 2.1382 2.51832 + endloop + endfacet + facet normal -0.220671 0.762728 0.607907 + outer loop + vertex 1.12123 2.13558 2.52183 + vertex 1.12059 2.1382 2.51832 + vertex 1.118 2.13656 2.51944 + endloop + endfacet + facet normal -0.316561 0.732442 0.602758 + outer loop + vertex 1.12123 2.13558 2.52183 + vertex 1.12385 2.13761 2.52075 + vertex 1.12059 2.1382 2.51832 + endloop + endfacet + facet normal -0.253363 0.805464 0.535756 + outer loop + vertex 1.12385 2.13761 2.52075 + vertex 1.12389 2.14005 2.51709 + vertex 1.12059 2.1382 2.51832 + endloop + endfacet + facet normal -0.376696 0.766312 0.520448 + outer loop + vertex 1.12385 2.13761 2.52075 + vertex 1.12123 2.13558 2.52183 + vertex 1.12413 2.13615 2.52309 + endloop + endfacet + facet normal 0.118121 -0.716598 0.687412 + outer loop + vertex 1.125 2.145 2.51466 + vertex 1.12302 2.145 2.515 + vertex 1.12631 2.14376 2.51314 + endloop + endfacet + facet normal 0.438475 -0.162278 0.883971 + outer loop + vertex 1.12631 2.14376 2.51314 + vertex 1.12302 2.145 2.515 + vertex 1.1235 2.14191 2.51419 + endloop + endfacet + facet normal -0.550172 -0.775193 0.310462 + outer loop + vertex 1.12362 0.885057 2.5153 + vertex 1.12739 0.882429 2.51541 + vertex 1.12616 0.884084 2.51737 + endloop + endfacet + facet normal -0.279326 -0.362043 0.889327 + outer loop + vertex 1.12362 0.885057 2.5153 + vertex 1.125 0.883265 2.515 + vertex 1.12739 0.882429 2.51541 + endloop + endfacet + facet normal -0.356897 -0.739518 0.570735 + outer loop + vertex 1.125 0.883265 2.515 + vertex 1.13 0.880852 2.515 + vertex 1.12739 0.882429 2.51541 + endloop + endfacet + facet normal -0.409824 -0.807078 0.425052 + outer loop + vertex 1.12739 0.882429 2.51541 + vertex 1.12981 0.882836 2.51851 + vertex 1.12616 0.884084 2.51737 + endloop + endfacet + facet normal -0.530154 -0.802752 0.272996 + outer loop + vertex 1.12362 0.885057 2.5153 + vertex 1.12616 0.884084 2.51737 + vertex 1.12397 0.885703 2.51787 + endloop + endfacet + facet normal -0.414604 -0.777964 0.472097 + outer loop + vertex 1.12616 0.884084 2.51737 + vertex 1.12981 0.882836 2.51851 + vertex 1.12735 0.885708 2.52109 + endloop + endfacet + facet normal -0.450527 -0.756443 0.474152 + outer loop + vertex 1.12616 0.884084 2.51737 + vertex 1.12735 0.885708 2.52109 + vertex 1.12397 0.885703 2.51787 + endloop + endfacet + facet normal -0.406838 -0.806836 0.428367 + outer loop + vertex 1.12397 0.885703 2.51787 + vertex 1.12735 0.885708 2.52109 + vertex 1.12288 0.887306 2.51986 + endloop + endfacet + facet normal -0.407244 -0.803555 0.43411 + outer loop + vertex 1.12735 0.885708 2.52109 + vertex 1.12465 0.88821 2.52319 + vertex 1.12288 0.887306 2.51986 + endloop + endfacet + facet normal -0.311979 -0.785349 0.534693 + outer loop + vertex 1.12804 0.887812 2.52458 + vertex 1.12465 0.88821 2.52319 + vertex 1.12735 0.885708 2.52109 + endloop + endfacet + facet normal -0.331796 -0.728712 0.599075 + outer loop + vertex 1.12465 0.88821 2.52319 + vertex 1.12804 0.887812 2.52458 + vertex 1.12654 0.889966 2.52637 + endloop + endfacet + facet normal -0.290873 -0.754134 0.588791 + outer loop + vertex 1.12163 0.890724 2.52492 + vertex 1.12465 0.88821 2.52319 + vertex 1.12654 0.889966 2.52637 + endloop + endfacet + facet normal -0.297469 -0.717013 0.6304 + outer loop + vertex 1.12654 0.889966 2.52637 + vertex 1.12456 0.892817 2.52868 + vertex 1.12163 0.890724 2.52492 + endloop + endfacet + facet normal -0.084057 -0.661546 0.745179 + outer loop + vertex 1.12985 0.892444 2.52895 + vertex 1.12456 0.892817 2.52868 + vertex 1.12654 0.889966 2.52637 + endloop + endfacet + facet normal -0.0823343 -0.602196 0.794091 + outer loop + vertex 1.12456 0.892817 2.52868 + vertex 1.12985 0.892444 2.52895 + vertex 1.12711 0.895816 2.53122 + endloop + endfacet + facet normal 0.00222603 -0.647244 0.76228 + outer loop + vertex 1.12218 0.895854 2.53127 + vertex 1.12456 0.892817 2.52868 + vertex 1.12711 0.895816 2.53122 + endloop + endfacet + facet normal 0.00396084 -0.526886 0.849927 + outer loop + vertex 1.12711 0.895816 2.53122 + vertex 1.12476 0.899647 2.53361 + vertex 1.12218 0.895854 2.53127 + endloop + endfacet + facet normal 0.172302 -0.44234 0.88014 + outer loop + vertex 1.12979 0.899567 2.53258 + vertex 1.12476 0.899647 2.53361 + vertex 1.12711 0.895816 2.53122 + endloop + endfacet + facet normal 0.273809 -0.424602 0.862984 + outer loop + vertex 1.1248 0.903258 2.53537 + vertex 1.12121 0.901954 2.53587 + vertex 1.12476 0.899647 2.53361 + endloop + endfacet + facet normal 0.336972 -0.416285 0.844486 + outer loop + vertex 1.1248 0.903258 2.53537 + vertex 1.12476 0.899647 2.53361 + vertex 1.1289 0.904206 2.5342 + endloop + endfacet + facet normal 0.186522 -0.291811 0.938113 + outer loop + vertex 1.1289 0.904206 2.5342 + vertex 1.12476 0.899647 2.53361 + vertex 1.12979 0.899567 2.53258 + endloop + endfacet + facet normal 0.264972 -0.393736 0.880205 + outer loop + vertex 1.1248 0.903258 2.53537 + vertex 1.12302 0.905016 2.53669 + vertex 1.12121 0.901954 2.53587 + endloop + endfacet + facet normal 0.386233 -0.170434 0.906519 + outer loop + vertex 1.12858 0.929394 2.53927 + vertex 1.12478 0.924537 2.53998 + vertex 1.1284 0.924054 2.53835 + endloop + endfacet + facet normal 0.34391 -0.146793 0.927458 + outer loop + vertex 1.12457 0.957808 2.5457 + vertex 1.1221 0.95525 2.54621 + vertex 1.12485 0.954652 2.5451 + endloop + endfacet + facet normal 0.284614 -0.155662 0.94592 + outer loop + vertex 1.12457 0.957808 2.5457 + vertex 1.12485 0.954652 2.5451 + vertex 1.12863 0.959239 2.54471 + endloop + endfacet + facet normal 0.307512 -0.175434 0.935232 + outer loop + vertex 1.12863 0.959239 2.54471 + vertex 1.12485 0.954652 2.5451 + vertex 1.12886 0.954192 2.54369 + endloop + endfacet + facet normal 0.360147 -0.164274 0.918318 + outer loop + vertex 1.12457 0.957808 2.5457 + vertex 1.12205 0.958517 2.54682 + vertex 1.1221 0.95525 2.54621 + endloop + endfacet + facet normal 0.27437 -0.191617 0.94234 + outer loop + vertex 1.12863 0.959239 2.54471 + vertex 1.12998 0.964216 2.54533 + vertex 1.12592 0.961435 2.54595 + endloop + endfacet + facet normal 0.289463 -0.172477 0.941522 + outer loop + vertex 1.12457 0.957808 2.5457 + vertex 1.12863 0.959239 2.54471 + vertex 1.12592 0.961435 2.54595 + endloop + endfacet + facet normal 0.350949 -0.193603 0.916162 + outer loop + vertex 1.12592 0.961435 2.54595 + vertex 1.12205 0.958517 2.54682 + vertex 1.12457 0.957808 2.5457 + endloop + endfacet + facet normal 0.345819 -0.185743 0.919733 + outer loop + vertex 1.12342 0.963747 2.54736 + vertex 1.12205 0.958517 2.54682 + vertex 1.12592 0.961435 2.54595 + endloop + endfacet + facet normal 0.270622 -0.185637 0.944618 + outer loop + vertex 1.12998 0.964216 2.54533 + vertex 1.12757 0.965149 2.54621 + vertex 1.12592 0.961435 2.54595 + endloop + endfacet + facet normal 0.325911 -0.208636 0.922092 + outer loop + vertex 1.12757 0.965149 2.54621 + vertex 1.12342 0.963747 2.54736 + vertex 1.12592 0.961435 2.54595 + endloop + endfacet + facet normal 0.332986 -0.237337 0.912574 + outer loop + vertex 1.12757 0.965149 2.54621 + vertex 1.12841 0.96898 2.5469 + vertex 1.12342 0.963747 2.54736 + endloop + endfacet + facet normal 0.285636 -0.189837 0.939347 + outer loop + vertex 1.12841 0.96898 2.5469 + vertex 1.12358 0.969012 2.54837 + vertex 1.12342 0.963747 2.54736 + endloop + endfacet + facet normal 0.281238 -0.124212 0.951565 + outer loop + vertex 1.12312 1.10834 2.57729 + vertex 1.12701 1.11269 2.5767 + vertex 1.12301 1.11325 2.57796 + endloop + endfacet + facet normal 0.288686 -0.0776024 0.954274 + outer loop + vertex 1.12701 1.11269 2.5767 + vertex 1.12695 1.11767 2.57713 + vertex 1.12301 1.11325 2.57796 + endloop + endfacet + facet normal 0.34104 -0.128573 0.931215 + outer loop + vertex 1.12301 1.11325 2.57796 + vertex 1.12695 1.11767 2.57713 + vertex 1.123 1.11838 2.57867 + endloop + endfacet + facet normal 0.350441 -0.0805737 0.933112 + outer loop + vertex 1.12695 1.11767 2.57713 + vertex 1.12686 1.12285 2.57761 + vertex 1.123 1.11838 2.57867 + endloop + endfacet + facet normal 0.431143 -0.161167 0.887773 + outer loop + vertex 1.123 1.11838 2.57867 + vertex 1.12686 1.12285 2.57761 + vertex 1.12318 1.12365 2.57954 + endloop + endfacet + facet normal 0.422963 -0.179174 0.888256 + outer loop + vertex 1.12388 1.12772 2.58003 + vertex 1.12178 1.12572 2.58063 + vertex 1.12318 1.12365 2.57954 + endloop + endfacet + facet normal 0.561533 -0.193221 0.804578 + outer loop + vertex 1.12388 1.12772 2.58003 + vertex 1.12318 1.12365 2.57954 + vertex 1.12679 1.12851 2.57819 + endloop + endfacet + facet normal 0.448564 -0.0854149 0.88966 + outer loop + vertex 1.12679 1.12851 2.57819 + vertex 1.12318 1.12365 2.57954 + vertex 1.12686 1.12285 2.57761 + endloop + endfacet + facet normal 0.364689 -0.107019 0.924959 + outer loop + vertex 1.12388 1.12772 2.58003 + vertex 1.12178 1.1287 2.58097 + vertex 1.12178 1.12572 2.58063 + endloop + endfacet + facet normal 0.598507 -0.0261835 0.80069 + outer loop + vertex 1.12679 1.12851 2.57819 + vertex 1.12758 1.13448 2.5778 + vertex 1.12468 1.13157 2.57987 + endloop + endfacet + facet normal 0.548149 -0.0787077 0.832669 + outer loop + vertex 1.12388 1.12772 2.58003 + vertex 1.12679 1.12851 2.57819 + vertex 1.12468 1.13157 2.57987 + endloop + endfacet + facet normal 0.39187 -0.0429654 0.919017 + outer loop + vertex 1.12468 1.13157 2.57987 + vertex 1.12178 1.1287 2.58097 + vertex 1.12388 1.12772 2.58003 + endloop + endfacet + facet normal 0.404877 -0.0586128 0.912491 + outer loop + vertex 1.12178 1.13288 2.58124 + vertex 1.12178 1.1287 2.58097 + vertex 1.12468 1.13157 2.57987 + endloop + endfacet + facet normal 0.618245 0.0193164 0.785748 + outer loop + vertex 1.12758 1.13448 2.5778 + vertex 1.12765 1.13989 2.57761 + vertex 1.12491 1.13651 2.57985 + endloop + endfacet + facet normal 0.597287 -0.0242737 0.80166 + outer loop + vertex 1.12468 1.13157 2.57987 + vertex 1.12758 1.13448 2.5778 + vertex 1.12491 1.13651 2.57985 + endloop + endfacet + facet normal 0.421616 -0.015457 0.906643 + outer loop + vertex 1.12491 1.13651 2.57985 + vertex 1.12178 1.13288 2.58124 + vertex 1.12468 1.13157 2.57987 + endloop + endfacet + facet normal 0.452968 -0.0488634 0.890186 + outer loop + vertex 1.1217 1.13772 2.58155 + vertex 1.12178 1.13288 2.58124 + vertex 1.12491 1.13651 2.57985 + endloop + endfacet + facet normal 0.643067 0.0365113 0.764939 + outer loop + vertex 1.12765 1.13989 2.57761 + vertex 1.12729 1.14496 2.57766 + vertex 1.12475 1.14152 2.57997 + endloop + endfacet + facet normal 0.631713 0.00141492 0.775201 + outer loop + vertex 1.12491 1.13651 2.57985 + vertex 1.12765 1.13989 2.57761 + vertex 1.12475 1.14152 2.57997 + endloop + endfacet + facet normal 0.466098 -0.00648677 0.884709 + outer loop + vertex 1.12475 1.14152 2.57997 + vertex 1.1217 1.13772 2.58155 + vertex 1.12491 1.13651 2.57985 + endloop + endfacet + facet normal 0.511316 -0.0540867 0.857689 + outer loop + vertex 1.12149 1.14247 2.58197 + vertex 1.1217 1.13772 2.58155 + vertex 1.12475 1.14152 2.57997 + endloop + endfacet + facet normal 0.668709 0.0387638 0.742513 + outer loop + vertex 1.12729 1.14496 2.57766 + vertex 1.1266 1.14995 2.57803 + vertex 1.12417 1.14613 2.58042 + endloop + endfacet + facet normal 0.663245 0.0104925 0.748328 + outer loop + vertex 1.12475 1.14152 2.57997 + vertex 1.12729 1.14496 2.57766 + vertex 1.12417 1.14613 2.58042 + endloop + endfacet + facet normal 0.519692 -0.0181116 0.854162 + outer loop + vertex 1.12417 1.14613 2.58042 + vertex 1.12149 1.14247 2.58197 + vertex 1.12475 1.14152 2.57997 + endloop + endfacet + facet normal 0.565478 -0.0652662 0.822177 + outer loop + vertex 1.12111 1.14626 2.58253 + vertex 1.12149 1.14247 2.58197 + vertex 1.12417 1.14613 2.58042 + endloop + endfacet + facet normal 0.679165 0.0264772 0.733508 + outer loop + vertex 1.12257 1.15019 2.58175 + vertex 1.12417 1.14613 2.58042 + vertex 1.1266 1.14995 2.57803 + endloop + endfacet + facet normal 0.678491 -0.00162278 0.734607 + outer loop + vertex 1.12257 1.15019 2.58175 + vertex 1.1266 1.14995 2.57803 + vertex 1.12501 1.15397 2.5795 + endloop + endfacet + facet normal 0.737076 0.04336 0.674417 + outer loop + vertex 1.12501 1.15397 2.5795 + vertex 1.1266 1.14995 2.57803 + vertex 1.12727 1.15313 2.57709 + endloop + endfacet + facet normal 0.566579 -0.0468755 0.822673 + outer loop + vertex 1.12417 1.14613 2.58042 + vertex 1.12257 1.15019 2.58175 + vertex 1.12111 1.14626 2.58253 + endloop + endfacet + facet normal 0.806 0.0512975 0.589688 + outer loop + vertex 1.12781 1.15628 2.57605 + vertex 1.12886 1.16036 2.57428 + vertex 1.12731 1.15899 2.57651 + endloop + endfacet + facet normal 0.76654 0.0352014 0.641231 + outer loop + vertex 1.12781 1.15628 2.57605 + vertex 1.12731 1.15899 2.57651 + vertex 1.12529 1.15843 2.57895 + endloop + endfacet + facet normal 0.765306 0.0315104 0.642895 + outer loop + vertex 1.12781 1.15628 2.57605 + vertex 1.12529 1.15843 2.57895 + vertex 1.12501 1.15397 2.5795 + endloop + endfacet + facet normal 0.74275 0.0896806 0.663536 + outer loop + vertex 1.12781 1.15628 2.57605 + vertex 1.12501 1.15397 2.5795 + vertex 1.12727 1.15313 2.57709 + endloop + endfacet + facet normal 0.738518 0.036908 0.673223 + outer loop + vertex 1.123 1.15644 2.58158 + vertex 1.12501 1.15397 2.5795 + vertex 1.12529 1.15843 2.57895 + endloop + endfacet + facet normal 0.738049 0.038039 0.673674 + outer loop + vertex 1.12529 1.15843 2.57895 + vertex 1.12234 1.15995 2.5821 + vertex 1.123 1.15644 2.58158 + endloop + endfacet + facet normal 0.806867 0.0567521 0.588 + outer loop + vertex 1.12886 1.16036 2.57428 + vertex 1.12873 1.1648 2.57402 + vertex 1.12698 1.16181 2.57671 + endloop + endfacet + facet normal 0.805752 0.0520241 0.589964 + outer loop + vertex 1.12731 1.15899 2.57651 + vertex 1.12886 1.16036 2.57428 + vertex 1.12698 1.16181 2.57671 + endloop + endfacet + facet normal 0.76532 0.0437826 0.64216 + outer loop + vertex 1.12731 1.15899 2.57651 + vertex 1.12698 1.16181 2.57671 + vertex 1.12529 1.15843 2.57895 + endloop + endfacet + facet normal 0.767786 0.0407216 0.639411 + outer loop + vertex 1.12698 1.16181 2.57671 + vertex 1.12452 1.16303 2.57959 + vertex 1.12529 1.15843 2.57895 + endloop + endfacet + facet normal 0.736436 0.0304325 0.675822 + outer loop + vertex 1.12452 1.16303 2.57959 + vertex 1.12234 1.15995 2.5821 + vertex 1.12529 1.15843 2.57895 + endloop + endfacet + facet normal 0.742496 0.0209922 0.669521 + outer loop + vertex 1.12158 1.16492 2.58279 + vertex 1.12234 1.15995 2.5821 + vertex 1.12452 1.16303 2.57959 + endloop + endfacet + facet normal 0.812497 0.107379 0.57299 + outer loop + vertex 1.12873 1.1648 2.57402 + vertex 1.12845 1.16917 2.5736 + vertex 1.12666 1.16638 2.57667 + endloop + endfacet + facet normal 0.803214 0.062811 0.59237 + outer loop + vertex 1.12698 1.16181 2.57671 + vertex 1.12873 1.1648 2.57402 + vertex 1.12666 1.16638 2.57667 + endloop + endfacet + facet normal 0.771118 0.0608616 0.633777 + outer loop + vertex 1.12698 1.16181 2.57671 + vertex 1.12666 1.16638 2.57667 + vertex 1.12452 1.16303 2.57959 + endloop + endfacet + facet normal 0.778296 0.0494723 0.625945 + outer loop + vertex 1.12666 1.16638 2.57667 + vertex 1.12415 1.16778 2.57967 + vertex 1.12452 1.16303 2.57959 + endloop + endfacet + facet normal 0.749312 0.0466731 0.660571 + outer loop + vertex 1.12415 1.16778 2.57967 + vertex 1.12158 1.16492 2.58279 + vertex 1.12452 1.16303 2.57959 + endloop + endfacet + facet normal 0.76501 0.0142655 0.64386 + outer loop + vertex 1.12188 1.16971 2.58233 + vertex 1.12158 1.16492 2.58279 + vertex 1.12415 1.16778 2.57967 + endloop + endfacet + facet normal -0.444826 -0.207985 0.871132 + outer loop + vertex 1.13 1.17346 2.57 + vertex 1.12928 1.175 2.57 + vertex 1.12933 1.17212 2.56934 + endloop + endfacet + facet normal 0.835364 0.236077 0.496422 + outer loop + vertex 1.12845 1.16917 2.5736 + vertex 1.12823 1.17271 2.57228 + vertex 1.12616 1.17219 2.57601 + endloop + endfacet + facet normal 0.797444 0.133922 0.588343 + outer loop + vertex 1.12666 1.16638 2.57667 + vertex 1.12845 1.16917 2.5736 + vertex 1.12616 1.17219 2.57601 + endloop + endfacet + facet normal 0.842095 0.0739172 0.534241 + outer loop + vertex 1.12377 1.17138 2.5799 + vertex 1.12616 1.17219 2.57601 + vertex 1.12398 1.17511 2.57905 + endloop + endfacet + facet normal 0.844754 0.0561369 0.532203 + outer loop + vertex 1.12377 1.17138 2.5799 + vertex 1.12415 1.16778 2.57967 + vertex 1.12616 1.17219 2.57601 + endloop + endfacet + facet normal 0.790931 0.134343 0.596976 + outer loop + vertex 1.12415 1.16778 2.57967 + vertex 1.12666 1.16638 2.57667 + vertex 1.12616 1.17219 2.57601 + endloop + endfacet + facet normal 0.774274 0.0422777 0.631437 + outer loop + vertex 1.12415 1.16778 2.57967 + vertex 1.12377 1.17138 2.5799 + vertex 1.12188 1.16971 2.58233 + endloop + endfacet + facet normal 0.696491 -0.150292 0.70165 + outer loop + vertex 1.12872 1.17362 2.57026 + vertex 1.12933 1.17212 2.56934 + vertex 1.12928 1.175 2.57 + endloop + endfacet + facet normal 0.532261 -0.0568712 0.844668 + outer loop + vertex 1.12872 1.17362 2.57026 + vertex 1.12928 1.175 2.57 + vertex 1.12728 1.17717 2.57141 + endloop + endfacet + facet normal 0.657883 0.124995 0.742675 + outer loop + vertex 1.12728 1.17717 2.57141 + vertex 1.12928 1.175 2.57 + vertex 1.12833 1.18 2.57 + endloop + endfacet + facet normal 0.906112 0.258978 0.334502 + outer loop + vertex 1.12823 1.17271 2.57228 + vertex 1.12872 1.17362 2.57026 + vertex 1.12728 1.17717 2.57141 + endloop + endfacet + facet normal 0.824471 0.273262 0.495556 + outer loop + vertex 1.12823 1.17271 2.57228 + vertex 1.12728 1.17717 2.57141 + vertex 1.12616 1.17219 2.57601 + endloop + endfacet + facet normal 0.910236 0.151983 0.385191 + outer loop + vertex 1.12616 1.17219 2.57601 + vertex 1.12728 1.17717 2.57141 + vertex 1.12544 1.17816 2.57538 + endloop + endfacet + facet normal 0.867073 0.156091 0.473096 + outer loop + vertex 1.12544 1.17816 2.57538 + vertex 1.12398 1.17511 2.57905 + vertex 1.12616 1.17219 2.57601 + endloop + endfacet + facet normal 0.897911 0.0905122 0.430771 + outer loop + vertex 1.12368 1.17989 2.57867 + vertex 1.12398 1.17511 2.57905 + vertex 1.12544 1.17816 2.57538 + endloop + endfacet + facet normal 0.638555 0.139211 0.75688 + outer loop + vertex 1.12833 1.18 2.57 + vertex 1.12724 1.185 2.57 + vertex 1.12728 1.17717 2.57141 + endloop + endfacet + facet normal 0.792049 0.111875 0.600119 + outer loop + vertex 1.12724 1.185 2.57 + vertex 1.12589 1.18201 2.57234 + vertex 1.12728 1.17717 2.57141 + endloop + endfacet + facet normal 0.90771 0.188481 0.374884 + outer loop + vertex 1.12728 1.17717 2.57141 + vertex 1.12589 1.18201 2.57234 + vertex 1.12544 1.17816 2.57538 + endloop + endfacet + facet normal 0.94671 0.122912 0.297713 + outer loop + vertex 1.12589 1.18201 2.57234 + vertex 1.12481 1.18329 2.57523 + vertex 1.12544 1.17816 2.57538 + endloop + endfacet + facet normal 0.901048 0.120651 0.4166 + outer loop + vertex 1.12481 1.18329 2.57523 + vertex 1.12368 1.17989 2.57867 + vertex 1.12544 1.17816 2.57538 + endloop + endfacet + facet normal 0.926254 0.0661372 0.371052 + outer loop + vertex 1.12349 1.18479 2.57827 + vertex 1.12368 1.17989 2.57867 + vertex 1.12481 1.18329 2.57523 + endloop + endfacet + facet normal 0.860796 0.428471 -0.274669 + outer loop + vertex 1.125 1.19 2.57078 + vertex 1.12724 1.185 2.57 + vertex 1.125 1.1895 2.57 + endloop + endfacet + facet normal 0.843008 0.308951 0.440325 + outer loop + vertex 1.125 1.19 2.57078 + vertex 1.12508 1.18771 2.57224 + vertex 1.12724 1.185 2.57 + endloop + endfacet + facet normal 0.783622 0.122627 0.609015 + outer loop + vertex 1.12508 1.18771 2.57224 + vertex 1.12589 1.18201 2.57234 + vertex 1.12724 1.185 2.57 + endloop + endfacet + facet normal 0.946687 0.140116 0.290088 + outer loop + vertex 1.12589 1.18201 2.57234 + vertex 1.12508 1.18771 2.57224 + vertex 1.12481 1.18329 2.57523 + endloop + endfacet + facet normal 0.977285 0.0757749 0.197922 + outer loop + vertex 1.12508 1.18771 2.57224 + vertex 1.12443 1.18795 2.57533 + vertex 1.12481 1.18329 2.57523 + endloop + endfacet + facet normal 0.926473 0.0682048 0.370129 + outer loop + vertex 1.12443 1.18795 2.57533 + vertex 1.12349 1.18479 2.57827 + vertex 1.12481 1.18329 2.57523 + endloop + endfacet + facet normal 0.943857 0.0251883 0.329392 + outer loop + vertex 1.12361 1.1886 2.57764 + vertex 1.12349 1.18479 2.57827 + vertex 1.12443 1.18795 2.57533 + endloop + endfacet + facet normal 0.99946 0.0159603 -0.0287059 + outer loop + vertex 1.125 1.195 2.57356 + vertex 1.12508 1.18771 2.57224 + vertex 1.125 1.19 2.57078 + endloop + endfacet + facet normal 0.620534 -0.133807 0.772679 + outer loop + vertex 1.12443 1.19297 2.57366 + vertex 1.12508 1.18771 2.57224 + vertex 1.125 1.195 2.57356 + endloop + endfacet + facet normal 0.948194 0.151618 0.279178 + outer loop + vertex 1.1241 1.19111 2.5758 + vertex 1.12443 1.19297 2.57366 + vertex 1.12375 1.1947 2.57504 + endloop + endfacet + facet normal 0.974503 0.0708592 0.212894 + outer loop + vertex 1.1241 1.19111 2.5758 + vertex 1.12443 1.18795 2.57533 + vertex 1.12443 1.19297 2.57366 + endloop + endfacet + facet normal 0.977808 0.0661753 0.198777 + outer loop + vertex 1.12443 1.18795 2.57533 + vertex 1.12508 1.18771 2.57224 + vertex 1.12443 1.19297 2.57366 + endloop + endfacet + facet normal 0.945161 0.0513629 0.322541 + outer loop + vertex 1.12443 1.18795 2.57533 + vertex 1.1241 1.19111 2.5758 + vertex 1.12361 1.1886 2.57764 + endloop + endfacet + facet normal 0.680402 -0.153359 0.716613 + outer loop + vertex 1.125 1.2 2.57463 + vertex 1.12443 1.19297 2.57366 + vertex 1.125 1.195 2.57356 + endloop + endfacet + facet normal -0.641986 -0.0532962 0.764862 + outer loop + vertex 1.12413 1.19704 2.57369 + vertex 1.12443 1.19297 2.57366 + vertex 1.125 1.2 2.57463 + endloop + endfacet + facet normal 0.924463 0.0655975 0.375585 + outer loop + vertex 1.12413 1.19704 2.57369 + vertex 1.12375 1.1947 2.57504 + vertex 1.12443 1.19297 2.57366 + endloop + endfacet + facet normal 0.885355 0.11499 0.45047 + outer loop + vertex 1.12359 1.19878 2.57432 + vertex 1.12375 1.1947 2.57504 + vertex 1.12413 1.19704 2.57369 + endloop + endfacet + facet normal 0.215143 -0.351232 0.911235 + outer loop + vertex 1.125 1.2 2.57463 + vertex 1.125 1.20096 2.575 + vertex 1.12413 1.19704 2.57369 + endloop + endfacet + facet normal 0.0486498 -0.325347 0.944342 + outer loop + vertex 1.12413 1.19704 2.57369 + vertex 1.125 1.20096 2.575 + vertex 1.12359 1.19878 2.57432 + endloop + endfacet + facet normal -0.999815 0.00287423 0.0190108 + outer loop + vertex 1.12494 1.8356 2.57126 + vertex 1.125 1.83295 2.575 + vertex 1.125 1.835 2.57469 + endloop + endfacet + facet normal 0.835375 0.455008 0.30841 + outer loop + vertex 1.12494 1.8356 2.57126 + vertex 1.12445 1.83508 2.57334 + vertex 1.125 1.83295 2.575 + endloop + endfacet + facet normal -0.999397 0.0259761 0.0230394 + outer loop + vertex 1.125 1.83916 2.57 + vertex 1.12494 1.8356 2.57126 + vertex 1.125 1.835 2.57469 + endloop + endfacet + facet normal 0.344168 -0.319554 -0.882855 + outer loop + vertex 1.12578 1.84 2.57 + vertex 1.12494 1.8356 2.57126 + vertex 1.125 1.83916 2.57 + endloop + endfacet + facet normal -0.335827 -0.200048 -0.920435 + outer loop + vertex 1.12578 1.84 2.57 + vertex 1.126 1.83644 2.57069 + vertex 1.12494 1.8356 2.57126 + endloop + endfacet + facet normal -0.701025 -0.178291 -0.69049 + outer loop + vertex 1.12578 1.84 2.57 + vertex 1.1266 1.83719 2.56989 + vertex 1.126 1.83644 2.57069 + endloop + endfacet + facet normal 0.601314 -0.796943 -0.0574755 + outer loop + vertex 1.126 1.83644 2.57069 + vertex 1.12445 1.83508 2.57334 + vertex 1.12494 1.8356 2.57126 + endloop + endfacet + facet normal 0.886004 -0.252774 0.388718 + outer loop + vertex 1.126 1.83644 2.57069 + vertex 1.12602 1.83802 2.57168 + vertex 1.12445 1.83508 2.57334 + endloop + endfacet + facet normal 0.839049 -0.151703 0.522477 + outer loop + vertex 1.12602 1.83802 2.57168 + vertex 1.12438 1.83836 2.57441 + vertex 1.12445 1.83508 2.57334 + endloop + endfacet + facet normal 0.348334 0.136435 -0.927388 + outer loop + vertex 1.1266 1.83822 2.57004 + vertex 1.1266 1.83719 2.56989 + vertex 1.12578 1.84 2.57 + endloop + endfacet + facet normal 0.174685 0.0556848 -0.983048 + outer loop + vertex 1.1266 1.83822 2.57004 + vertex 1.12578 1.84 2.57 + vertex 1.12633 1.84251 2.57024 + endloop + endfacet + facet normal 0.51891 -0.194076 0.832506 + outer loop + vertex 1.12633 1.84251 2.57024 + vertex 1.12578 1.84 2.57 + vertex 1.12765 1.845 2.57 + endloop + endfacet + facet normal 0.940555 0.0423422 0.336991 + outer loop + vertex 1.12633 1.84251 2.57024 + vertex 1.12602 1.83802 2.57168 + vertex 1.1266 1.83822 2.57004 + endloop + endfacet + facet normal 0.919045 0.0606427 0.38946 + outer loop + vertex 1.12633 1.84251 2.57024 + vertex 1.12492 1.84273 2.57353 + vertex 1.12602 1.83802 2.57168 + endloop + endfacet + facet normal 0.85735 -0.00292231 0.514726 + outer loop + vertex 1.12492 1.84273 2.57353 + vertex 1.12438 1.83836 2.57441 + vertex 1.12602 1.83802 2.57168 + endloop + endfacet + facet normal 0.191861 -0.00690725 0.981398 + outer loop + vertex 1.12765 1.845 2.57 + vertex 1.12783 1.85 2.57 + vertex 1.12633 1.84251 2.57024 + endloop + endfacet + facet normal 0.674682 -0.111481 0.729641 + outer loop + vertex 1.12783 1.85 2.57 + vertex 1.12625 1.84795 2.57114 + vertex 1.12633 1.84251 2.57024 + endloop + endfacet + facet normal 0.916698 -0.052538 0.396111 + outer loop + vertex 1.12625 1.84795 2.57114 + vertex 1.12492 1.84273 2.57353 + vertex 1.12633 1.84251 2.57024 + endloop + endfacet + facet normal 0.880266 -0.00747734 0.474422 + outer loop + vertex 1.12448 1.84845 2.57445 + vertex 1.12492 1.84273 2.57353 + vertex 1.12625 1.84795 2.57114 + endloop + endfacet + facet normal 0.693605 -0.138711 0.706874 + outer loop + vertex 1.12783 1.85 2.57 + vertex 1.12883 1.855 2.57 + vertex 1.12625 1.84795 2.57114 + endloop + endfacet + facet normal 0.687215 -0.13526 0.713751 + outer loop + vertex 1.12883 1.855 2.57 + vertex 1.12602 1.85249 2.57223 + vertex 1.12625 1.84795 2.57114 + endloop + endfacet + facet normal 0.874132 -0.0697046 0.480661 + outer loop + vertex 1.12602 1.85249 2.57223 + vertex 1.12448 1.84845 2.57445 + vertex 1.12625 1.84795 2.57114 + endloop + endfacet + facet normal 0.866457 -0.0584832 0.495815 + outer loop + vertex 1.12432 1.85261 2.57521 + vertex 1.12448 1.84845 2.57445 + vertex 1.12602 1.85249 2.57223 + endloop + endfacet + facet normal -0.460074 0.574195 0.677224 + outer loop + vertex 1.13 1.85924 2.57 + vertex 1.12875 1.86026 2.56828 + vertex 1.1275 1.85667 2.57048 + endloop + endfacet + facet normal 0.257727 -0.07112 0.963597 + outer loop + vertex 1.13 1.85924 2.57 + vertex 1.1275 1.85667 2.57048 + vertex 1.12883 1.855 2.57 + endloop + endfacet + facet normal 0.515846 0.169501 0.839746 + outer loop + vertex 1.12883 1.855 2.57 + vertex 1.1275 1.85667 2.57048 + vertex 1.12602 1.85249 2.57223 + endloop + endfacet + facet normal 0.835841 -0.0672968 0.544831 + outer loop + vertex 1.12432 1.85261 2.57521 + vertex 1.12534 1.85669 2.57416 + vertex 1.12326 1.85491 2.57712 + endloop + endfacet + facet normal 0.86419 -0.0869823 0.495591 + outer loop + vertex 1.12432 1.85261 2.57521 + vertex 1.12602 1.85249 2.57223 + vertex 1.12534 1.85669 2.57416 + endloop + endfacet + facet normal 0.857954 -0.092461 0.505337 + outer loop + vertex 1.12602 1.85249 2.57223 + vertex 1.1275 1.85667 2.57048 + vertex 1.12534 1.85669 2.57416 + endloop + endfacet + facet normal 0.833977 -0.0587435 0.548663 + outer loop + vertex 1.12534 1.85669 2.57416 + vertex 1.12321 1.85895 2.57764 + vertex 1.12326 1.85491 2.57712 + endloop + endfacet + facet normal 0.905371 -0.100527 0.41255 + outer loop + vertex 1.12875 1.86026 2.56828 + vertex 1.12898 1.86417 2.56872 + vertex 1.12733 1.86045 2.57144 + endloop + endfacet + facet normal 0.909044 -0.0630907 0.411897 + outer loop + vertex 1.1275 1.85667 2.57048 + vertex 1.12875 1.86026 2.56828 + vertex 1.12733 1.86045 2.57144 + endloop + endfacet + facet normal 0.858225 -0.0891049 0.505481 + outer loop + vertex 1.1275 1.85667 2.57048 + vertex 1.12733 1.86045 2.57144 + vertex 1.12534 1.85669 2.57416 + endloop + endfacet + facet normal 0.859608 -0.0919028 0.502621 + outer loop + vertex 1.12733 1.86045 2.57144 + vertex 1.12545 1.86184 2.5749 + vertex 1.12534 1.85669 2.57416 + endloop + endfacet + facet normal 0.818308 -0.100127 0.565992 + outer loop + vertex 1.12545 1.86184 2.5749 + vertex 1.12321 1.85895 2.57764 + vertex 1.12534 1.85669 2.57416 + endloop + endfacet + facet normal 0.796851 -0.0491936 0.60217 + outer loop + vertex 1.12318 1.86385 2.57808 + vertex 1.12321 1.85895 2.57764 + vertex 1.12545 1.86184 2.5749 + endloop + endfacet + facet normal 0.903018 -0.101614 0.417412 + outer loop + vertex 1.12898 1.86417 2.56872 + vertex 1.12928 1.86887 2.56921 + vertex 1.12751 1.86515 2.57213 + endloop + endfacet + facet normal 0.903952 -0.0970114 0.416486 + outer loop + vertex 1.12733 1.86045 2.57144 + vertex 1.12898 1.86417 2.56872 + vertex 1.12751 1.86515 2.57213 + endloop + endfacet + facet normal 0.85519 -0.10843 0.506846 + outer loop + vertex 1.12733 1.86045 2.57144 + vertex 1.12751 1.86515 2.57213 + vertex 1.12545 1.86184 2.5749 + endloop + endfacet + facet normal 0.833343 -0.0590255 0.549596 + outer loop + vertex 1.12751 1.86515 2.57213 + vertex 1.1255 1.86679 2.57536 + vertex 1.12545 1.86184 2.5749 + endloop + endfacet + facet normal 0.791562 -0.0639742 0.60773 + outer loop + vertex 1.1255 1.86679 2.57536 + vertex 1.12318 1.86385 2.57808 + vertex 1.12545 1.86184 2.5749 + endloop + endfacet + facet normal 0.777465 -0.0341145 0.628 + outer loop + vertex 1.12316 1.86876 2.57836 + vertex 1.12318 1.86385 2.57808 + vertex 1.1255 1.86679 2.57536 + endloop + endfacet + facet normal 0.881241 -0.0801204 0.465827 + outer loop + vertex 1.12928 1.86887 2.56921 + vertex 1.12941 1.87364 2.5698 + vertex 1.12759 1.87015 2.57262 + endloop + endfacet + facet normal 0.885709 -0.0597283 0.460382 + outer loop + vertex 1.12751 1.86515 2.57213 + vertex 1.12928 1.86887 2.56921 + vertex 1.12759 1.87015 2.57262 + endloop + endfacet + facet normal 0.830727 -0.0679615 0.552516 + outer loop + vertex 1.12751 1.86515 2.57213 + vertex 1.12759 1.87015 2.57262 + vertex 1.1255 1.86679 2.57536 + endloop + endfacet + facet normal 0.817973 -0.0428048 0.573661 + outer loop + vertex 1.12759 1.87015 2.57262 + vertex 1.12547 1.87172 2.57577 + vertex 1.1255 1.86679 2.57536 + endloop + endfacet + facet normal 0.772489 -0.0480208 0.63321 + outer loop + vertex 1.12547 1.87172 2.57577 + vertex 1.12316 1.86876 2.57836 + vertex 1.1255 1.86679 2.57536 + endloop + endfacet + facet normal 0.765152 -0.0337815 0.642963 + outer loop + vertex 1.12319 1.87347 2.57858 + vertex 1.12316 1.86876 2.57836 + vertex 1.12547 1.87172 2.57577 + endloop + endfacet + facet normal 0.853266 -0.100519 0.511696 + outer loop + vertex 1.12941 1.87364 2.5698 + vertex 1.12949 1.87755 2.57042 + vertex 1.12753 1.87556 2.57329 + endloop + endfacet + facet normal 0.868524 -0.0514928 0.492965 + outer loop + vertex 1.12759 1.87015 2.57262 + vertex 1.12941 1.87364 2.5698 + vertex 1.12753 1.87556 2.57329 + endloop + endfacet + facet normal 0.812291 -0.0628722 0.579854 + outer loop + vertex 1.12759 1.87015 2.57262 + vertex 1.12753 1.87556 2.57329 + vertex 1.12547 1.87172 2.57577 + endloop + endfacet + facet normal 0.8011 -0.0459552 0.596763 + outer loop + vertex 1.12753 1.87556 2.57329 + vertex 1.12526 1.87586 2.57638 + vertex 1.12547 1.87172 2.57577 + endloop + endfacet + facet normal 0.757387 -0.0561686 0.650546 + outer loop + vertex 1.12526 1.87586 2.57638 + vertex 1.12319 1.87347 2.57858 + vertex 1.12547 1.87172 2.57577 + endloop + endfacet + facet normal 0.743044 -0.0270744 0.668694 + outer loop + vertex 1.12333 1.8781 2.57861 + vertex 1.12319 1.87347 2.57858 + vertex 1.12526 1.87586 2.57638 + endloop + endfacet + facet normal 0.851699 -0.0932644 0.515664 + outer loop + vertex 1.12949 1.87755 2.57042 + vertex 1.12855 1.87977 2.57238 + vertex 1.12753 1.87556 2.57329 + endloop + endfacet + facet normal 0.792136 -0.0772531 0.605436 + outer loop + vertex 1.12855 1.87977 2.57238 + vertex 1.12849 1.88382 2.57297 + vertex 1.12618 1.88034 2.57555 + endloop + endfacet + facet normal 0.794554 -0.060188 0.604203 + outer loop + vertex 1.12855 1.87977 2.57238 + vertex 1.12618 1.88034 2.57555 + vertex 1.12753 1.87556 2.57329 + endloop + endfacet + facet normal 0.800286 -0.0551881 0.597073 + outer loop + vertex 1.12753 1.87556 2.57329 + vertex 1.12618 1.88034 2.57555 + vertex 1.12526 1.87586 2.57638 + endloop + endfacet + facet normal 0.741665 -0.0296757 0.670114 + outer loop + vertex 1.12618 1.88034 2.57555 + vertex 1.12333 1.8781 2.57861 + vertex 1.12526 1.87586 2.57638 + endloop + endfacet + facet normal 0.727625 0.00989801 0.685904 + outer loop + vertex 1.12323 1.88311 2.57864 + vertex 1.12333 1.8781 2.57861 + vertex 1.12618 1.88034 2.57555 + endloop + endfacet + facet normal 0.751488 -0.0759226 0.655364 + outer loop + vertex 1.12849 1.88382 2.57297 + vertex 1.12846 1.88868 2.57357 + vertex 1.12594 1.88593 2.57614 + endloop + endfacet + facet normal 0.767188 -0.034635 0.640487 + outer loop + vertex 1.12618 1.88034 2.57555 + vertex 1.12849 1.88382 2.57297 + vertex 1.12594 1.88593 2.57614 + endloop + endfacet + facet normal 0.702136 -0.0447097 0.710638 + outer loop + vertex 1.12594 1.88593 2.57614 + vertex 1.12323 1.88311 2.57864 + vertex 1.12618 1.88034 2.57555 + endloop + endfacet + facet normal 0.649522 0.0483305 0.758805 + outer loop + vertex 1.12252 1.88879 2.57889 + vertex 1.12323 1.88311 2.57864 + vertex 1.12594 1.88593 2.57614 + endloop + endfacet + facet normal 0.715778 -0.0681439 0.694996 + outer loop + vertex 1.12846 1.88868 2.57357 + vertex 1.12849 1.89338 2.574 + vertex 1.12594 1.89087 2.57638 + endloop + endfacet + facet normal 0.731141 -0.0329439 0.68143 + outer loop + vertex 1.12594 1.88593 2.57614 + vertex 1.12846 1.88868 2.57357 + vertex 1.12594 1.89087 2.57638 + endloop + endfacet + facet normal 0.605717 -0.0387257 0.794737 + outer loop + vertex 1.12594 1.89087 2.57638 + vertex 1.12252 1.88879 2.57889 + vertex 1.12594 1.88593 2.57614 + endloop + endfacet + facet normal 0.590857 0.000185704 0.806776 + outer loop + vertex 1.12346 1.89323 2.5782 + vertex 1.12252 1.88879 2.57889 + vertex 1.12594 1.89087 2.57638 + endloop + endfacet + facet normal 0.687238 -0.0613072 0.723841 + outer loop + vertex 1.12849 1.89338 2.574 + vertex 1.1287 1.89794 2.57419 + vertex 1.1261 1.89541 2.57644 + endloop + endfacet + facet normal 0.699728 -0.0342278 0.713589 + outer loop + vertex 1.12594 1.89087 2.57638 + vertex 1.12849 1.89338 2.574 + vertex 1.1261 1.89541 2.57644 + endloop + endfacet + facet normal 0.571148 -0.0308646 0.820267 + outer loop + vertex 1.1261 1.89541 2.57644 + vertex 1.12346 1.89323 2.5782 + vertex 1.12594 1.89087 2.57638 + endloop + endfacet + facet normal 0.52653 0.0464482 0.848887 + outer loop + vertex 1.12309 1.89725 2.57821 + vertex 1.12346 1.89323 2.5782 + vertex 1.1261 1.89541 2.57644 + endloop + endfacet + facet normal 0.645843 -0.0589301 0.761192 + outer loop + vertex 1.1287 1.89794 2.57419 + vertex 1.1287 1.90178 2.57448 + vertex 1.12628 1.89978 2.57638 + endloop + endfacet + facet normal 0.6646 -0.0174548 0.746995 + outer loop + vertex 1.1261 1.89541 2.57644 + vertex 1.1287 1.89794 2.57419 + vertex 1.12628 1.89978 2.57638 + endloop + endfacet + facet normal 0.501734 -0.00933896 0.864972 + outer loop + vertex 1.12628 1.89978 2.57638 + vertex 1.12309 1.89725 2.57821 + vertex 1.1261 1.89541 2.57644 + endloop + endfacet + facet normal 0.447825 0.0772039 0.890782 + outer loop + vertex 1.12322 1.90227 2.57771 + vertex 1.12309 1.89725 2.57821 + vertex 1.12628 1.89978 2.57638 + endloop + endfacet + facet normal 0.616084 0.00224632 0.787677 + outer loop + vertex 1.1287 1.90178 2.57448 + vertex 1.12683 1.90356 2.57594 + vertex 1.12628 1.89978 2.57638 + endloop + endfacet + facet normal 0.426008 0.0434785 0.903674 + outer loop + vertex 1.12683 1.90356 2.57594 + vertex 1.12322 1.90227 2.57771 + vertex 1.12628 1.89978 2.57638 + endloop + endfacet + facet normal 0.412379 0.0859937 0.906945 + outer loop + vertex 1.12683 1.90356 2.57594 + vertex 1.12539 1.9073 2.57624 + vertex 1.12322 1.90227 2.57771 + endloop + endfacet + facet normal 0.297707 0.146118 0.943409 + outer loop + vertex 1.12539 1.9073 2.57624 + vertex 1.12143 1.90602 2.57769 + vertex 1.12322 1.90227 2.57771 + endloop + endfacet + facet normal 0.45832 0.11719 0.881028 + outer loop + vertex 1.12811 1.91003 2.57464 + vertex 1.12783 1.91416 2.57423 + vertex 1.12566 1.91145 2.57572 + endloop + endfacet + facet normal 0.443646 0.0831319 0.892338 + outer loop + vertex 1.12566 1.91145 2.57572 + vertex 1.12539 1.9073 2.57624 + vertex 1.12811 1.91003 2.57464 + endloop + endfacet + facet normal 0.228685 0.106587 0.967648 + outer loop + vertex 1.12566 1.91145 2.57572 + vertex 1.12133 1.91083 2.57681 + vertex 1.12539 1.9073 2.57624 + endloop + endfacet + facet normal 0.286717 0.177643 0.941401 + outer loop + vertex 1.12133 1.91083 2.57681 + vertex 1.12143 1.90602 2.57769 + vertex 1.12539 1.9073 2.57624 + endloop + endfacet + facet normal 0.229986 0.205574 0.951234 + outer loop + vertex 1.12944 2.05377 2.54579 + vertex 1.12936 2.05852 2.54478 + vertex 1.12626 2.05556 2.54617 + endloop + endfacet + facet normal 0.232324 0.210042 0.949688 + outer loop + vertex 1.12626 2.05556 2.54617 + vertex 1.12647 2.05083 2.54716 + vertex 1.12944 2.05377 2.54579 + endloop + endfacet + facet normal 0.27454 0.209559 0.938463 + outer loop + vertex 1.12626 2.05556 2.54617 + vertex 1.12191 2.05593 2.54736 + vertex 1.12647 2.05083 2.54716 + endloop + endfacet + facet normal 0.32433 0.157466 0.932746 + outer loop + vertex 1.12385 2.06804 2.54451 + vertex 1.12756 2.07106 2.54271 + vertex 1.12268 2.07335 2.54402 + endloop + endfacet + facet normal 0.333393 0.181005 0.925249 + outer loop + vertex 1.12756 2.07106 2.54271 + vertex 1.12605 2.07664 2.54216 + vertex 1.12268 2.07335 2.54402 + endloop + endfacet + facet normal 0.351544 0.160725 0.922271 + outer loop + vertex 1.12268 2.07335 2.54402 + vertex 1.12605 2.07664 2.54216 + vertex 1.12287 2.07709 2.54329 + endloop + endfacet + facet normal 0.339096 0.16413 0.926324 + outer loop + vertex 1.12921 2.07872 2.5406 + vertex 1.12994 2.08275 2.53962 + vertex 1.12682 2.08068 2.54113 + endloop + endfacet + facet normal 0.343121 0.169699 0.923835 + outer loop + vertex 1.12682 2.08068 2.54113 + vertex 1.12605 2.07664 2.54216 + vertex 1.12921 2.07872 2.5406 + endloop + endfacet + facet normal 0.365115 0.163625 0.91647 + outer loop + vertex 1.12682 2.08068 2.54113 + vertex 1.12308 2.08088 2.54259 + vertex 1.12605 2.07664 2.54216 + endloop + endfacet + facet normal 0.350991 0.153001 0.923794 + outer loop + vertex 1.12308 2.08088 2.54259 + vertex 1.12287 2.07709 2.54329 + vertex 1.12605 2.07664 2.54216 + endloop + endfacet + facet normal 0.355455 0.155918 0.921597 + outer loop + vertex 1.12994 2.08275 2.53962 + vertex 1.12881 2.0878 2.5392 + vertex 1.1259 2.08463 2.54086 + endloop + endfacet + facet normal 0.351297 0.144744 0.925008 + outer loop + vertex 1.12682 2.08068 2.54113 + vertex 1.12994 2.08275 2.53962 + vertex 1.1259 2.08463 2.54086 + endloop + endfacet + facet normal 0.365304 0.147601 0.919112 + outer loop + vertex 1.1259 2.08463 2.54086 + vertex 1.12308 2.08088 2.54259 + vertex 1.12682 2.08068 2.54113 + endloop + endfacet + facet normal 0.369354 0.144071 0.918053 + outer loop + vertex 1.12188 2.08632 2.54221 + vertex 1.12308 2.08088 2.54259 + vertex 1.1259 2.08463 2.54086 + endloop + endfacet + facet normal 0.37041 0.152372 0.916285 + outer loop + vertex 1.12881 2.0878 2.5392 + vertex 1.12743 2.09334 2.53884 + vertex 1.12475 2.08953 2.54056 + endloop + endfacet + facet normal 0.367491 0.143453 0.918897 + outer loop + vertex 1.1259 2.08463 2.54086 + vertex 1.12881 2.0878 2.5392 + vertex 1.12475 2.08953 2.54056 + endloop + endfacet + facet normal 0.369274 0.143825 0.918124 + outer loop + vertex 1.12475 2.08953 2.54056 + vertex 1.12188 2.08632 2.54221 + vertex 1.1259 2.08463 2.54086 + endloop + endfacet + facet normal 0.365628 0.147538 0.918993 + outer loop + vertex 1.12053 2.09154 2.54191 + vertex 1.12188 2.08632 2.54221 + vertex 1.12475 2.08953 2.54056 + endloop + endfacet + facet normal 0.371822 0.151205 0.915907 + outer loop + vertex 1.12359 2.09363 2.54035 + vertex 1.12475 2.08953 2.54056 + vertex 1.12743 2.09334 2.53884 + endloop + endfacet + facet normal 0.371907 0.167851 0.912968 + outer loop + vertex 1.12359 2.09363 2.54035 + vertex 1.12743 2.09334 2.53884 + vertex 1.12394 2.09813 2.53938 + endloop + endfacet + facet normal 0.364489 0.161988 0.91701 + outer loop + vertex 1.12394 2.09813 2.53938 + vertex 1.12743 2.09334 2.53884 + vertex 1.12748 2.0972 2.53814 + endloop + endfacet + facet normal 0.366494 0.149823 0.918278 + outer loop + vertex 1.12475 2.08953 2.54056 + vertex 1.12359 2.09363 2.54035 + vertex 1.12053 2.09154 2.54191 + endloop + endfacet + facet normal 0.366193 0.171761 0.914549 + outer loop + vertex 1.12748 2.0972 2.53814 + vertex 1.1277 2.10085 2.53736 + vertex 1.12394 2.09813 2.53938 + endloop + endfacet + facet normal 0.363616 0.175541 0.91486 + outer loop + vertex 1.12394 2.09813 2.53938 + vertex 1.1277 2.10085 2.53736 + vertex 1.12404 2.10286 2.53843 + endloop + endfacet + facet normal 0.363174 0.174542 0.915226 + outer loop + vertex 1.1277 2.10085 2.53736 + vertex 1.12604 2.10632 2.53698 + vertex 1.12404 2.10286 2.53843 + endloop + endfacet + facet normal 0.358361 0.177853 0.916485 + outer loop + vertex 1.12404 2.10286 2.53843 + vertex 1.12604 2.10632 2.53698 + vertex 1.12233 2.10619 2.53846 + endloop + endfacet + facet normal 0.362743 0.176889 0.914947 + outer loop + vertex 1.12906 2.10842 2.53539 + vertex 1.12961 2.11259 2.53436 + vertex 1.12652 2.11058 2.53598 + endloop + endfacet + facet normal 0.36111 0.17469 0.916015 + outer loop + vertex 1.12652 2.11058 2.53598 + vertex 1.12604 2.10632 2.53698 + vertex 1.12906 2.10842 2.53539 + endloop + endfacet + facet normal 0.354676 0.175943 0.918286 + outer loop + vertex 1.12652 2.11058 2.53598 + vertex 1.12249 2.11088 2.53748 + vertex 1.12604 2.10632 2.53698 + endloop + endfacet + facet normal 0.358256 0.178947 0.916314 + outer loop + vertex 1.12249 2.11088 2.53748 + vertex 1.12233 2.10619 2.53846 + vertex 1.12604 2.10632 2.53698 + endloop + endfacet + facet normal 0.358633 0.193351 0.913235 + outer loop + vertex 1.12961 2.11259 2.53436 + vertex 1.12768 2.11829 2.53391 + vertex 1.12521 2.11466 2.53565 + endloop + endfacet + facet normal 0.356349 0.187146 0.915419 + outer loop + vertex 1.12652 2.11058 2.53598 + vertex 1.12961 2.11259 2.53436 + vertex 1.12521 2.11466 2.53565 + endloop + endfacet + facet normal 0.35468 0.186669 0.916164 + outer loop + vertex 1.12521 2.11466 2.53565 + vertex 1.12249 2.11088 2.53748 + vertex 1.12652 2.11058 2.53598 + endloop + endfacet + facet normal 0.347126 0.192885 0.917768 + outer loop + vertex 1.12073 2.11658 2.53694 + vertex 1.12249 2.11088 2.53748 + vertex 1.12521 2.11466 2.53565 + endloop + endfacet + facet normal 0.335959 0.21103 0.917932 + outer loop + vertex 1.12369 2.11861 2.5353 + vertex 1.12521 2.11466 2.53565 + vertex 1.12768 2.11829 2.53391 + endloop + endfacet + facet normal 0.334379 0.303688 0.892168 + outer loop + vertex 1.12369 2.11861 2.5353 + vertex 1.12768 2.11829 2.53391 + vertex 1.1233 2.12249 2.53413 + endloop + endfacet + facet normal 0.255456 0.218664 0.941769 + outer loop + vertex 1.1233 2.12249 2.53413 + vertex 1.12768 2.11829 2.53391 + vertex 1.12739 2.12189 2.53316 + endloop + endfacet + facet normal 0.355285 0.217699 0.909054 + outer loop + vertex 1.12521 2.11466 2.53565 + vertex 1.12369 2.11861 2.5353 + vertex 1.12073 2.11658 2.53694 + endloop + endfacet + facet normal 0.263538 0.33389 0.905022 + outer loop + vertex 1.12739 2.12189 2.53316 + vertex 1.12704 2.12494 2.53214 + vertex 1.1233 2.12249 2.53413 + endloop + endfacet + facet normal 0.169615 0.452879 0.875289 + outer loop + vertex 1.1233 2.12249 2.53413 + vertex 1.12704 2.12494 2.53214 + vertex 1.12232 2.12621 2.53239 + endloop + endfacet + facet normal 0.0482345 0.485063 0.873148 + outer loop + vertex 1.1243 2.12887 2.53022 + vertex 1.12911 2.12779 2.53056 + vertex 1.12884 2.13174 2.52838 + endloop + endfacet + facet normal -0.0993166 0.64444 0.758178 + outer loop + vertex 1.12373 2.13178 2.52768 + vertex 1.1243 2.12887 2.53022 + vertex 1.12884 2.13174 2.52838 + endloop + endfacet + facet normal 0.188268 0.531878 0.825628 + outer loop + vertex 1.12704 2.12494 2.53214 + vertex 1.1243 2.12887 2.53022 + vertex 1.12232 2.12621 2.53239 + endloop + endfacet + facet normal 0.0416042 0.459875 0.887009 + outer loop + vertex 1.12911 2.12779 2.53056 + vertex 1.1243 2.12887 2.53022 + vertex 1.12704 2.12494 2.53214 + endloop + endfacet + facet normal -0.280158 0.682918 0.674636 + outer loop + vertex 1.12483 2.13439 2.5254 + vertex 1.12846 2.13527 2.52601 + vertex 1.12642 2.13681 2.52361 + endloop + endfacet + facet normal -0.34141 0.6935 0.634426 + outer loop + vertex 1.12413 2.13615 2.52309 + vertex 1.12483 2.13439 2.5254 + vertex 1.12642 2.13681 2.52361 + endloop + endfacet + facet normal -0.0950932 0.677465 0.729383 + outer loop + vertex 1.12884 2.13174 2.52838 + vertex 1.12483 2.13439 2.5254 + vertex 1.12373 2.13178 2.52768 + endloop + endfacet + facet normal -0.263387 0.517815 0.813938 + outer loop + vertex 1.12846 2.13527 2.52601 + vertex 1.12483 2.13439 2.5254 + vertex 1.12884 2.13174 2.52838 + endloop + endfacet + facet normal -0.191174 0.814847 0.547245 + outer loop + vertex 1.12589 2.14168 2.51537 + vertex 1.1235 2.14191 2.51419 + vertex 1.12389 2.14005 2.51709 + endloop + endfacet + facet normal -0.324609 0.846352 0.422276 + outer loop + vertex 1.12735 2.14088 2.51809 + vertex 1.12589 2.14168 2.51537 + vertex 1.12389 2.14005 2.51709 + endloop + endfacet + facet normal -0.335105 0.800511 0.496877 + outer loop + vertex 1.12735 2.14088 2.51809 + vertex 1.12389 2.14005 2.51709 + vertex 1.12704 2.13904 2.52086 + endloop + endfacet + facet normal -0.364484 0.775925 0.514871 + outer loop + vertex 1.12704 2.13904 2.52086 + vertex 1.12389 2.14005 2.51709 + vertex 1.12385 2.13761 2.52075 + endloop + endfacet + facet normal -0.341137 0.779944 0.524702 + outer loop + vertex 1.12642 2.13681 2.52361 + vertex 1.12385 2.13761 2.52075 + vertex 1.12413 2.13615 2.52309 + endloop + endfacet + facet normal -0.359589 0.763365 0.536628 + outer loop + vertex 1.12704 2.13904 2.52086 + vertex 1.12385 2.13761 2.52075 + vertex 1.12642 2.13681 2.52361 + endloop + endfacet + facet normal -0.797998 0.411703 -0.440114 + outer loop + vertex 1.125 2.145 2.51466 + vertex 1.13 2.14971 2.51 + vertex 1.12757 2.145 2.51 + endloop + endfacet + facet normal 0.720447 -0.083689 0.688441 + outer loop + vertex 1.125 2.145 2.51466 + vertex 1.12631 2.14376 2.51314 + vertex 1.13 2.14971 2.51 + endloop + endfacet + facet normal -0.180055 0.544463 0.819232 + outer loop + vertex 1.12631 2.14376 2.51314 + vertex 1.13032 2.14548 2.51288 + vertex 1.13 2.14971 2.51 + endloop + endfacet + facet normal -0.243529 0.730865 0.637597 + outer loop + vertex 1.12589 2.14168 2.51537 + vertex 1.12631 2.14376 2.51314 + vertex 1.1235 2.14191 2.51419 + endloop + endfacet + facet normal -0.394458 0.706963 0.587032 + outer loop + vertex 1.12589 2.14168 2.51537 + vertex 1.1296 2.14275 2.51658 + vertex 1.12631 2.14376 2.51314 + endloop + endfacet + facet normal -0.305858 0.792743 0.527266 + outer loop + vertex 1.1296 2.14275 2.51658 + vertex 1.13032 2.14548 2.51288 + vertex 1.12631 2.14376 2.51314 + endloop + endfacet + facet normal -0.377676 0.814065 0.441201 + outer loop + vertex 1.1296 2.14275 2.51658 + vertex 1.12589 2.14168 2.51537 + vertex 1.12735 2.14088 2.51809 + endloop + endfacet + facet normal -0.68661 -0.683058 0.248994 + outer loop + vertex 1.13466 0.876257 2.51047 + vertex 1.13077 0.88 2.51 + vertex 1.135 0.875748 2.51 + endloop + endfacet + facet normal -0.688237 -0.723176 -0.0578463 + outer loop + vertex 1.13214 0.878516 2.51226 + vertex 1.13077 0.88 2.51 + vertex 1.13466 0.876257 2.51047 + endloop + endfacet + facet normal -0.503083 -0.807188 0.308796 + outer loop + vertex 1.13466 0.876257 2.51047 + vertex 1.13508 0.877255 2.51375 + vertex 1.13214 0.878516 2.51226 + endloop + endfacet + facet normal -0.736362 -0.676585 0.00189283 + outer loop + vertex 1.13077 0.88 2.51 + vertex 1.13214 0.878516 2.51226 + vertex 1.13 0.880852 2.515 + endloop + endfacet + facet normal -0.620527 -0.783268 0.0379085 + outer loop + vertex 1.13 0.88061 2.51 + vertex 1.13077 0.88 2.51 + vertex 1.13 0.880852 2.515 + endloop + endfacet + facet normal -0.514328 -0.781906 0.352263 + outer loop + vertex 1.13214 0.878516 2.51226 + vertex 1.13508 0.877255 2.51375 + vertex 1.13246 0.879926 2.51586 + endloop + endfacet + facet normal -0.436479 -0.823809 0.361698 + outer loop + vertex 1.13214 0.878516 2.51226 + vertex 1.13246 0.879926 2.51586 + vertex 1.13 0.880852 2.515 + endloop + endfacet + facet normal -0.437462 -0.820423 0.368148 + outer loop + vertex 1.13 0.880852 2.515 + vertex 1.13246 0.879926 2.51586 + vertex 1.12739 0.882429 2.51541 + endloop + endfacet + facet normal -0.428801 -0.790316 0.437642 + outer loop + vertex 1.13246 0.879926 2.51586 + vertex 1.12981 0.882836 2.51851 + vertex 1.12739 0.882429 2.51541 + endloop + endfacet + facet normal -0.345198 -0.784555 0.515085 + outer loop + vertex 1.13437 0.881724 2.51988 + vertex 1.12981 0.882836 2.51851 + vertex 1.13246 0.879926 2.51586 + endloop + endfacet + facet normal -0.352859 -0.730425 0.584781 + outer loop + vertex 1.12981 0.882836 2.51851 + vertex 1.13437 0.881724 2.51988 + vertex 1.13249 0.884372 2.52205 + endloop + endfacet + facet normal -0.305071 -0.767046 0.564421 + outer loop + vertex 1.12735 0.885708 2.52109 + vertex 1.12981 0.882836 2.51851 + vertex 1.13249 0.884372 2.52205 + endloop + endfacet + facet normal -0.165335 -0.719323 0.674714 + outer loop + vertex 1.12804 0.887812 2.52458 + vertex 1.13143 0.887086 2.52464 + vertex 1.13009 0.889256 2.52662 + endloop + endfacet + facet normal -0.185691 -0.825124 0.533563 + outer loop + vertex 1.12804 0.887812 2.52458 + vertex 1.12735 0.885708 2.52109 + vertex 1.13143 0.887086 2.52464 + endloop + endfacet + facet normal -0.303846 -0.717009 0.627355 + outer loop + vertex 1.12735 0.885708 2.52109 + vertex 1.13249 0.884372 2.52205 + vertex 1.13143 0.887086 2.52464 + endloop + endfacet + facet normal 0.0419499 -0.660087 0.750017 + outer loop + vertex 1.13143 0.887086 2.52464 + vertex 1.13432 0.890342 2.52734 + vertex 1.13009 0.889256 2.52662 + endloop + endfacet + facet normal -0.189207 -0.70212 0.686461 + outer loop + vertex 1.12804 0.887812 2.52458 + vertex 1.13009 0.889256 2.52662 + vertex 1.12654 0.889966 2.52637 + endloop + endfacet + facet normal -0.173652 -0.588195 0.789855 + outer loop + vertex 1.13009 0.889256 2.52662 + vertex 1.12985 0.892444 2.52895 + vertex 1.12654 0.889966 2.52637 + endloop + endfacet + facet normal 0.0135313 -0.588252 0.808564 + outer loop + vertex 1.13009 0.889256 2.52662 + vertex 1.13432 0.890342 2.52734 + vertex 1.12985 0.892444 2.52895 + endloop + endfacet + facet normal 0.100681 -0.459624 0.882389 + outer loop + vertex 1.13432 0.890342 2.52734 + vertex 1.13463 0.894725 2.52959 + vertex 1.12985 0.892444 2.52895 + endloop + endfacet + facet normal 0.137488 -0.524778 0.840063 + outer loop + vertex 1.12985 0.892444 2.52895 + vertex 1.13463 0.894725 2.52959 + vertex 1.13151 0.896304 2.53109 + endloop + endfacet + facet normal 0.0824236 -0.510093 0.856161 + outer loop + vertex 1.12711 0.895816 2.53122 + vertex 1.12985 0.892444 2.52895 + vertex 1.13151 0.896304 2.53109 + endloop + endfacet + facet normal 0.0704232 -0.384338 0.920503 + outer loop + vertex 1.13151 0.896304 2.53109 + vertex 1.12979 0.899567 2.53258 + vertex 1.12711 0.895816 2.53122 + endloop + endfacet + facet normal 0.311396 -0.17857 0.933352 + outer loop + vertex 1.13339 0.939467 2.53932 + vertex 1.13457 0.944804 2.53995 + vertex 1.13045 0.941697 2.54073 + endloop + endfacet + facet normal 0.293103 -0.184379 0.938134 + outer loop + vertex 1.13457 0.944804 2.53995 + vertex 1.13522 0.948946 2.54056 + vertex 1.13148 0.946226 2.54119 + endloop + endfacet + facet normal 0.350858 -0.170898 0.920702 + outer loop + vertex 1.12879 0.948806 2.5427 + vertex 1.12731 0.943132 2.54221 + vertex 1.13148 0.946226 2.54119 + endloop + endfacet + facet normal 0.287223 -0.175497 0.94165 + outer loop + vertex 1.13522 0.948946 2.54056 + vertex 1.13284 0.949923 2.54147 + vertex 1.13148 0.946226 2.54119 + endloop + endfacet + facet normal 0.333075 -0.191018 0.923349 + outer loop + vertex 1.13284 0.949923 2.54147 + vertex 1.12879 0.948806 2.5427 + vertex 1.13148 0.946226 2.54119 + endloop + endfacet + facet normal 0.339926 -0.227984 0.9124 + outer loop + vertex 1.13284 0.949923 2.54147 + vertex 1.13356 0.953788 2.54216 + vertex 1.12879 0.948806 2.5427 + endloop + endfacet + facet normal 0.290468 -0.177652 0.940249 + outer loop + vertex 1.13356 0.953788 2.54216 + vertex 1.12886 0.954192 2.54369 + vertex 1.12879 0.948806 2.5427 + endloop + endfacet + facet normal 0.249096 -0.0975012 0.963558 + outer loop + vertex 1.13222 1.08816 2.57152 + vertex 1.13203 1.09276 2.57203 + vertex 1.12814 1.08841 2.5726 + endloop + endfacet + facet normal 0.2948 -0.140903 0.945113 + outer loop + vertex 1.12814 1.08841 2.5726 + vertex 1.13203 1.09276 2.57203 + vertex 1.12805 1.09332 2.57336 + endloop + endfacet + facet normal 0.303248 -0.0897915 0.948672 + outer loop + vertex 1.13203 1.09276 2.57203 + vertex 1.13201 1.09769 2.57251 + vertex 1.12805 1.09332 2.57336 + endloop + endfacet + facet normal 0.360129 -0.146588 0.921314 + outer loop + vertex 1.12805 1.09332 2.57336 + vertex 1.13201 1.09769 2.57251 + vertex 1.12827 1.09829 2.57407 + endloop + endfacet + facet normal 0.36947 -0.0963834 0.924231 + outer loop + vertex 1.13201 1.09769 2.57251 + vertex 1.13215 1.10282 2.57299 + vertex 1.12827 1.09829 2.57407 + endloop + endfacet + facet normal 0.448975 -0.17595 0.87605 + outer loop + vertex 1.12827 1.09829 2.57407 + vertex 1.13215 1.10282 2.57299 + vertex 1.12865 1.10334 2.57488 + endloop + endfacet + facet normal 0.417369 -0.174378 0.891849 + outer loop + vertex 1.12935 1.10743 2.57536 + vertex 1.1271 1.10506 2.57594 + vertex 1.12865 1.10334 2.57488 + endloop + endfacet + facet normal 0.57286 -0.18971 0.797397 + outer loop + vertex 1.12935 1.10743 2.57536 + vertex 1.12865 1.10334 2.57488 + vertex 1.13224 1.10847 2.57353 + endloop + endfacet + facet normal 0.464083 -0.0916634 0.881036 + outer loop + vertex 1.13224 1.10847 2.57353 + vertex 1.12865 1.10334 2.57488 + vertex 1.13215 1.10282 2.57299 + endloop + endfacet + facet normal 0.354487 -0.105834 0.929052 + outer loop + vertex 1.12935 1.10743 2.57536 + vertex 1.12701 1.10822 2.57634 + vertex 1.1271 1.10506 2.57594 + endloop + endfacet + facet normal 0.602315 -0.0288499 0.797737 + outer loop + vertex 1.13224 1.10847 2.57353 + vertex 1.133 1.11448 2.57317 + vertex 1.1301 1.11143 2.57525 + endloop + endfacet + facet normal 0.553879 -0.0817805 0.828571 + outer loop + vertex 1.12935 1.10743 2.57536 + vertex 1.13224 1.10847 2.57353 + vertex 1.1301 1.11143 2.57525 + endloop + endfacet + facet normal 0.373823 -0.0452279 0.926397 + outer loop + vertex 1.1301 1.11143 2.57525 + vertex 1.12701 1.10822 2.57634 + vertex 1.12935 1.10743 2.57536 + endloop + endfacet + facet normal 0.399976 -0.0747427 0.913473 + outer loop + vertex 1.12701 1.11269 2.5767 + vertex 1.12701 1.10822 2.57634 + vertex 1.1301 1.11143 2.57525 + endloop + endfacet + facet normal 0.622003 0.019856 0.782763 + outer loop + vertex 1.133 1.11448 2.57317 + vertex 1.13302 1.11983 2.57302 + vertex 1.13025 1.11641 2.5753 + endloop + endfacet + facet normal 0.601228 -0.027216 0.798614 + outer loop + vertex 1.1301 1.11143 2.57525 + vertex 1.133 1.11448 2.57317 + vertex 1.13025 1.11641 2.5753 + endloop + endfacet + facet normal 0.418579 -0.0226536 0.907898 + outer loop + vertex 1.13025 1.11641 2.5753 + vertex 1.12701 1.11269 2.5767 + vertex 1.1301 1.11143 2.57525 + endloop + endfacet + facet normal 0.462041 -0.0694189 0.884137 + outer loop + vertex 1.12695 1.11767 2.57713 + vertex 1.12701 1.11269 2.5767 + vertex 1.13025 1.11641 2.5753 + endloop + endfacet + facet normal 0.656107 0.0307916 0.75404 + outer loop + vertex 1.13302 1.11983 2.57302 + vertex 1.1328 1.12494 2.573 + vertex 1.13014 1.12151 2.57546 + endloop + endfacet + facet normal 0.643105 -0.00857647 0.76573 + outer loop + vertex 1.13025 1.11641 2.5753 + vertex 1.13302 1.11983 2.57302 + vertex 1.13014 1.12151 2.57546 + endloop + endfacet + facet normal 0.478982 -0.015706 0.877684 + outer loop + vertex 1.13014 1.12151 2.57546 + vertex 1.12695 1.11767 2.57713 + vertex 1.13025 1.11641 2.5753 + endloop + endfacet + facet normal 0.527616 -0.0696806 0.84662 + outer loop + vertex 1.12686 1.12285 2.57761 + vertex 1.12695 1.11767 2.57713 + vertex 1.13014 1.12151 2.57546 + endloop + endfacet + facet normal 0.695855 0.0373968 0.717208 + outer loop + vertex 1.1328 1.12494 2.573 + vertex 1.13267 1.12999 2.57286 + vertex 1.13001 1.12669 2.57561 + endloop + endfacet + facet normal 0.682042 -0.00560906 0.731291 + outer loop + vertex 1.13014 1.12151 2.57546 + vertex 1.1328 1.12494 2.573 + vertex 1.13001 1.12669 2.57561 + endloop + endfacet + facet normal 0.545613 -0.0121075 0.83795 + outer loop + vertex 1.13001 1.12669 2.57561 + vertex 1.12686 1.12285 2.57761 + vertex 1.13014 1.12151 2.57546 + endloop + endfacet + facet normal 0.596744 -0.0743194 0.798983 + outer loop + vertex 1.12679 1.12851 2.57819 + vertex 1.12686 1.12285 2.57761 + vertex 1.13001 1.12669 2.57561 + endloop + endfacet + facet normal 0.73333 0.0489514 0.678108 + outer loop + vertex 1.13267 1.12999 2.57286 + vertex 1.13266 1.13492 2.57252 + vertex 1.13012 1.13207 2.57547 + endloop + endfacet + facet normal 0.716559 0.00423077 0.697513 + outer loop + vertex 1.13001 1.12669 2.57561 + vertex 1.13267 1.12999 2.57286 + vertex 1.13012 1.13207 2.57547 + endloop + endfacet + facet normal 0.627296 0.00823812 0.778737 + outer loop + vertex 1.13012 1.13207 2.57547 + vertex 1.12679 1.12851 2.57819 + vertex 1.13001 1.12669 2.57561 + endloop + endfacet + facet normal 0.655477 -0.0367225 0.754322 + outer loop + vertex 1.12758 1.13448 2.5778 + vertex 1.12679 1.12851 2.57819 + vertex 1.13012 1.13207 2.57547 + endloop + endfacet + facet normal 0.76291 0.0612371 0.643598 + outer loop + vertex 1.13266 1.13492 2.57252 + vertex 1.13286 1.13876 2.57191 + vertex 1.13053 1.13791 2.57476 + endloop + endfacet + facet normal 0.743614 0.0292563 0.667969 + outer loop + vertex 1.13012 1.13207 2.57547 + vertex 1.13266 1.13492 2.57252 + vertex 1.13053 1.13791 2.57476 + endloop + endfacet + facet normal 0.694288 0.0389093 0.718645 + outer loop + vertex 1.13053 1.13791 2.57476 + vertex 1.12758 1.13448 2.5778 + vertex 1.13012 1.13207 2.57547 + endloop + endfacet + facet normal 0.70838 0.0153174 0.705665 + outer loop + vertex 1.12765 1.13989 2.57761 + vertex 1.12758 1.13448 2.5778 + vertex 1.13053 1.13791 2.57476 + endloop + endfacet + facet normal 0.824065 0.102193 0.557202 + outer loop + vertex 1.13391 1.14128 2.57002 + vertex 1.13388 1.145 2.56938 + vertex 1.13234 1.14211 2.57219 + endloop + endfacet + facet normal 0.822019 0.0814287 0.563608 + outer loop + vertex 1.13286 1.13876 2.57191 + vertex 1.13391 1.14128 2.57002 + vertex 1.13234 1.14211 2.57219 + endloop + endfacet + facet normal 0.762091 0.0653864 0.64416 + outer loop + vertex 1.13286 1.13876 2.57191 + vertex 1.13234 1.14211 2.57219 + vertex 1.13053 1.13791 2.57476 + endloop + endfacet + facet normal 0.770173 0.0565119 0.635327 + outer loop + vertex 1.13053 1.13791 2.57476 + vertex 1.13234 1.14211 2.57219 + vertex 1.13005 1.14331 2.57486 + endloop + endfacet + facet normal 0.719689 0.0508717 0.69243 + outer loop + vertex 1.13005 1.14331 2.57486 + vertex 1.12765 1.13989 2.57761 + vertex 1.13053 1.13791 2.57476 + endloop + endfacet + facet normal 0.724948 0.043192 0.687448 + outer loop + vertex 1.12729 1.14496 2.57766 + vertex 1.12765 1.13989 2.57761 + vertex 1.13005 1.14331 2.57486 + endloop + endfacet + facet normal 0.847998 0.117724 0.516759 + outer loop + vertex 1.13388 1.145 2.56938 + vertex 1.13359 1.14961 2.5688 + vertex 1.13212 1.14663 2.5719 + endloop + endfacet + facet normal 0.839444 0.0755377 0.53817 + outer loop + vertex 1.13234 1.14211 2.57219 + vertex 1.13388 1.145 2.56938 + vertex 1.13212 1.14663 2.5719 + endloop + endfacet + facet normal 0.773777 0.0782782 0.628604 + outer loop + vertex 1.13234 1.14211 2.57219 + vertex 1.13212 1.14663 2.5719 + vertex 1.13005 1.14331 2.57486 + endloop + endfacet + facet normal 0.779483 0.0693403 0.622574 + outer loop + vertex 1.13212 1.14663 2.5719 + vertex 1.12968 1.1482 2.57477 + vertex 1.13005 1.14331 2.57486 + endloop + endfacet + facet normal 0.730782 0.0667479 0.67934 + outer loop + vertex 1.12968 1.1482 2.57477 + vertex 1.12729 1.14496 2.57766 + vertex 1.13005 1.14331 2.57486 + endloop + endfacet + facet normal 0.738959 0.0538119 0.671598 + outer loop + vertex 1.1266 1.14995 2.57803 + vertex 1.12729 1.14496 2.57766 + vertex 1.12968 1.1482 2.57477 + endloop + endfacet + facet normal -0.746202 -0.185598 0.639324 + outer loop + vertex 1.135 1.1511 2.565 + vertex 1.13403 1.155 2.565 + vertex 1.13366 1.15255 2.56386 + endloop + endfacet + facet normal 0.868685 0.144023 0.473967 + outer loop + vertex 1.13359 1.14961 2.5688 + vertex 1.13306 1.15436 2.56835 + vertex 1.13177 1.15152 2.57156 + endloop + endfacet + facet normal 0.85984 0.095942 0.501469 + outer loop + vertex 1.13212 1.14663 2.5719 + vertex 1.13359 1.14961 2.5688 + vertex 1.13177 1.15152 2.57156 + endloop + endfacet + facet normal 0.785086 0.0983029 0.611536 + outer loop + vertex 1.13212 1.14663 2.5719 + vertex 1.13177 1.15152 2.57156 + vertex 1.12968 1.1482 2.57477 + endloop + endfacet + facet normal 0.792602 0.0859313 0.603654 + outer loop + vertex 1.13177 1.15152 2.57156 + vertex 1.12921 1.15271 2.57476 + vertex 1.12968 1.1482 2.57477 + endloop + endfacet + facet normal 0.744697 0.0810148 0.662467 + outer loop + vertex 1.12921 1.15271 2.57476 + vertex 1.1266 1.14995 2.57803 + vertex 1.12968 1.1482 2.57477 + endloop + endfacet + facet normal 0.771123 0.0249244 0.636198 + outer loop + vertex 1.12727 1.15313 2.57709 + vertex 1.1266 1.14995 2.57803 + vertex 1.12921 1.15271 2.57476 + endloop + endfacet + facet normal -0.296571 -0.0943106 0.950342 + outer loop + vertex 1.13403 1.155 2.565 + vertex 1.13244 1.16 2.565 + vertex 1.13217 1.15758 2.56468 + endloop + endfacet + facet normal -0.537494 -0.288044 0.792547 + outer loop + vertex 1.13366 1.15255 2.56386 + vertex 1.13403 1.155 2.565 + vertex 1.13217 1.15758 2.56468 + endloop + endfacet + facet normal 0.88296 0.216512 0.416539 + outer loop + vertex 1.13306 1.15436 2.56835 + vertex 1.13236 1.15832 2.56775 + vertex 1.13086 1.15749 2.57138 + endloop + endfacet + facet normal 0.866847 0.147456 0.47627 + outer loop + vertex 1.13177 1.15152 2.57156 + vertex 1.13306 1.15436 2.56835 + vertex 1.13086 1.15749 2.57138 + endloop + endfacet + facet normal 0.834873 0.0265453 0.549802 + outer loop + vertex 1.12781 1.15628 2.57605 + vertex 1.13086 1.15749 2.57138 + vertex 1.12886 1.16036 2.57428 + endloop + endfacet + facet normal 0.818871 0.115081 0.562323 + outer loop + vertex 1.12781 1.15628 2.57605 + vertex 1.12921 1.15271 2.57476 + vertex 1.13086 1.15749 2.57138 + endloop + endfacet + facet normal 0.797212 0.140153 0.587205 + outer loop + vertex 1.12921 1.15271 2.57476 + vertex 1.13177 1.15152 2.57156 + vertex 1.13086 1.15749 2.57138 + endloop + endfacet + facet normal 0.773558 0.0731001 0.629495 + outer loop + vertex 1.12921 1.15271 2.57476 + vertex 1.12781 1.15628 2.57605 + vertex 1.12727 1.15313 2.57709 + endloop + endfacet + facet normal 0.89625 0.408168 -0.173596 + outer loop + vertex 1.13186 1.15999 2.56631 + vertex 1.13 1.165 2.56847 + vertex 1.13086 1.16308 2.56837 + endloop + endfacet + facet normal 0.615836 0.493877 -0.613866 + outer loop + vertex 1.13217 1.15758 2.56468 + vertex 1.13 1.165 2.56847 + vertex 1.13186 1.15999 2.56631 + endloop + endfacet + facet normal 0.816597 0.43354 -0.381068 + outer loop + vertex 1.13217 1.15758 2.56468 + vertex 1.13 1.16195 2.565 + vertex 1.13 1.165 2.56847 + endloop + endfacet + facet normal -0.0971768 -0.121593 0.987812 + outer loop + vertex 1.13217 1.15758 2.56468 + vertex 1.13244 1.16 2.565 + vertex 1.13 1.16195 2.565 + endloop + endfacet + facet normal 0.95373 0.300226 0.0162021 + outer loop + vertex 1.13236 1.15832 2.56775 + vertex 1.13186 1.15999 2.56631 + vertex 1.13086 1.16308 2.56837 + endloop + endfacet + facet normal 0.880374 0.225155 0.417428 + outer loop + vertex 1.13236 1.15832 2.56775 + vertex 1.13086 1.16308 2.56837 + vertex 1.13086 1.15749 2.57138 + endloop + endfacet + facet normal 0.966531 0.121906 0.225737 + outer loop + vertex 1.13086 1.15749 2.57138 + vertex 1.13086 1.16308 2.56837 + vertex 1.13011 1.16358 2.5713 + endloop + endfacet + facet normal 0.866447 0.112676 0.486388 + outer loop + vertex 1.13011 1.16358 2.5713 + vertex 1.12886 1.16036 2.57428 + vertex 1.13086 1.15749 2.57138 + endloop + endfacet + facet normal 0.899834 0.0506344 0.433284 + outer loop + vertex 1.12873 1.1648 2.57402 + vertex 1.12886 1.16036 2.57428 + vertex 1.13011 1.16358 2.5713 + endloop + endfacet + facet normal -0.0203071 0.0439605 -0.998827 + outer loop + vertex 1.13 1.17 2.56869 + vertex 1.13086 1.16308 2.56837 + vertex 1.13 1.165 2.56847 + endloop + endfacet + facet normal 0.942312 0.101679 0.318919 + outer loop + vertex 1.12992 1.16843 2.56942 + vertex 1.13086 1.16308 2.56837 + vertex 1.13 1.17 2.56869 + endloop + endfacet + facet normal 0.96634 0.124217 0.225291 + outer loop + vertex 1.13086 1.16308 2.56837 + vertex 1.12992 1.16843 2.56942 + vertex 1.13011 1.16358 2.5713 + endloop + endfacet + facet normal 0.982384 0.0989032 0.158556 + outer loop + vertex 1.12992 1.16843 2.56942 + vertex 1.12965 1.16745 2.57171 + vertex 1.13011 1.16358 2.5713 + endloop + endfacet + facet normal 0.901108 0.0610036 0.429281 + outer loop + vertex 1.12965 1.16745 2.57171 + vertex 1.12873 1.1648 2.57402 + vertex 1.13011 1.16358 2.5713 + endloop + endfacet + facet normal 0.878682 0.101378 0.466519 + outer loop + vertex 1.12845 1.16917 2.5736 + vertex 1.12873 1.1648 2.57402 + vertex 1.12965 1.16745 2.57171 + endloop + endfacet + facet normal 0.998044 -0.0221324 0.0584633 + outer loop + vertex 1.13 1.17 2.56869 + vertex 1.13 1.17346 2.57 + vertex 1.12992 1.16843 2.56942 + endloop + endfacet + facet normal -0.612202 -0.0816434 0.786475 + outer loop + vertex 1.12933 1.17212 2.56934 + vertex 1.12992 1.16843 2.56942 + vertex 1.13 1.17346 2.57 + endloop + endfacet + facet normal 0.976297 0.160751 0.144923 + outer loop + vertex 1.12933 1.17212 2.56934 + vertex 1.12933 1.17073 2.57087 + vertex 1.12992 1.16843 2.56942 + endloop + endfacet + facet normal 0.974334 0.140833 0.17561 + outer loop + vertex 1.12933 1.17073 2.57087 + vertex 1.12965 1.16745 2.57171 + vertex 1.12992 1.16843 2.56942 + endloop + endfacet + facet normal 0.897511 0.19013 0.3979 + outer loop + vertex 1.12933 1.17073 2.57087 + vertex 1.12845 1.16917 2.5736 + vertex 1.12965 1.16745 2.57171 + endloop + endfacet + facet normal 0.891258 0.205152 0.404441 + outer loop + vertex 1.12823 1.17271 2.57228 + vertex 1.12845 1.16917 2.5736 + vertex 1.12933 1.17073 2.57087 + endloop + endfacet + facet normal 0.943211 0.246302 0.22291 + outer loop + vertex 1.12933 1.17212 2.56934 + vertex 1.12872 1.17362 2.57026 + vertex 1.12933 1.17073 2.57087 + endloop + endfacet + facet normal 0.904863 0.261973 0.335548 + outer loop + vertex 1.12933 1.17073 2.57087 + vertex 1.12872 1.17362 2.57026 + vertex 1.12823 1.17271 2.57228 + endloop + endfacet + facet normal 0.0948846 -0.762056 -0.640521 + outer loop + vertex 1.12682 1.83677 2.57043 + vertex 1.126 1.83644 2.57069 + vertex 1.1266 1.83719 2.56989 + endloop + endfacet + facet normal 0.437912 -0.480898 0.759585 + outer loop + vertex 1.12682 1.83677 2.57043 + vertex 1.12602 1.83802 2.57168 + vertex 1.126 1.83644 2.57069 + endloop + endfacet + facet normal 0.938528 0.0530057 -0.341111 + outer loop + vertex 1.1266 1.83719 2.56989 + vertex 1.1266 1.83822 2.57004 + vertex 1.12682 1.83677 2.57043 + endloop + endfacet + facet normal 0.908388 0.230933 0.348569 + outer loop + vertex 1.12682 1.83677 2.57043 + vertex 1.1266 1.83822 2.57004 + vertex 1.12602 1.83802 2.57168 + endloop + endfacet + facet normal -0.992271 0.0455547 0.115426 + outer loop + vertex 1.12965 1.86107 2.56625 + vertex 1.13 1.85924 2.57 + vertex 1.13 1.86 2.5697 + endloop + endfacet + facet normal 0.149668 0.894149 0.422016 + outer loop + vertex 1.12965 1.86107 2.56625 + vertex 1.12875 1.86026 2.56828 + vertex 1.13 1.85924 2.57 + endloop + endfacet + facet normal -0.939455 0.288289 0.185239 + outer loop + vertex 1.13 1.86302 2.565 + vertex 1.12965 1.86107 2.56625 + vertex 1.13 1.86 2.5697 + endloop + endfacet + facet normal 0.581229 -0.510754 -0.633485 + outer loop + vertex 1.13 1.86302 2.565 + vertex 1.13174 1.865 2.565 + vertex 1.12965 1.86107 2.56625 + endloop + endfacet + facet normal 0.460026 0.0372003 0.887126 + outer loop + vertex 1.13174 1.865 2.565 + vertex 1.1301 1.8642 2.56588 + vertex 1.12965 1.86107 2.56625 + endloop + endfacet + facet normal 0.922992 -0.0900888 0.374126 + outer loop + vertex 1.1301 1.8642 2.56588 + vertex 1.12875 1.86026 2.56828 + vertex 1.12965 1.86107 2.56625 + endloop + endfacet + facet normal 0.925894 -0.096488 0.365255 + outer loop + vertex 1.12898 1.86417 2.56872 + vertex 1.12875 1.86026 2.56828 + vertex 1.1301 1.8642 2.56588 + endloop + endfacet + facet normal 0.507581 -0.0944174 0.856415 + outer loop + vertex 1.13174 1.865 2.565 + vertex 1.13267 1.87 2.565 + vertex 1.1301 1.8642 2.56588 + endloop + endfacet + facet normal 0.527702 -0.105391 0.842866 + outer loop + vertex 1.13267 1.87 2.565 + vertex 1.13063 1.86864 2.5661 + vertex 1.1301 1.8642 2.56588 + endloop + endfacet + facet normal 0.922627 -0.128786 0.363557 + outer loop + vertex 1.13063 1.86864 2.5661 + vertex 1.12898 1.86417 2.56872 + vertex 1.1301 1.8642 2.56588 + endloop + endfacet + facet normal 0.909411 -0.100557 0.403558 + outer loop + vertex 1.12928 1.86887 2.56921 + vertex 1.12898 1.86417 2.56872 + vertex 1.13063 1.86864 2.5661 + endloop + endfacet + facet normal 0.490433 -0.0264843 0.871076 + outer loop + vertex 1.13267 1.87 2.565 + vertex 1.13294 1.875 2.565 + vertex 1.13063 1.86864 2.5661 + endloop + endfacet + facet normal 0.660419 -0.110436 0.742732 + outer loop + vertex 1.13294 1.875 2.565 + vertex 1.13103 1.87334 2.56645 + vertex 1.13063 1.86864 2.5661 + endloop + endfacet + facet normal 0.908693 -0.106408 0.403675 + outer loop + vertex 1.13103 1.87334 2.56645 + vertex 1.12928 1.86887 2.56921 + vertex 1.13063 1.86864 2.5661 + endloop + endfacet + facet normal 0.894058 -0.0774556 0.441205 + outer loop + vertex 1.12941 1.87364 2.5698 + vertex 1.12928 1.86887 2.56921 + vertex 1.13103 1.87334 2.56645 + endloop + endfacet + facet normal 0.663877 -0.118157 0.738449 + outer loop + vertex 1.13294 1.875 2.565 + vertex 1.13383 1.88 2.565 + vertex 1.13103 1.87334 2.56645 + endloop + endfacet + facet normal 0.709366 -0.148017 0.689123 + outer loop + vertex 1.13383 1.88 2.565 + vertex 1.13105 1.87754 2.56733 + vertex 1.13103 1.87334 2.56645 + endloop + endfacet + facet normal 0.891783 -0.097316 0.441874 + outer loop + vertex 1.13105 1.87754 2.56733 + vertex 1.12941 1.87364 2.5698 + vertex 1.13103 1.87334 2.56645 + endloop + endfacet + facet normal 0.888703 -0.0913205 0.449297 + outer loop + vertex 1.12949 1.87755 2.57042 + vertex 1.12941 1.87364 2.5698 + vertex 1.13105 1.87754 2.56733 + endloop + endfacet + facet normal -0.514512 0.601737 0.610892 + outer loop + vertex 1.135 1.884 2.565 + vertex 1.13375 1.88505 2.56291 + vertex 1.13254 1.88157 2.56533 + endloop + endfacet + facet normal 0.182999 -0.0535295 0.981655 + outer loop + vertex 1.135 1.884 2.565 + vertex 1.13254 1.88157 2.56533 + vertex 1.13383 1.88 2.565 + endloop + endfacet + facet normal 0.495598 0.232957 0.836728 + outer loop + vertex 1.13383 1.88 2.565 + vertex 1.13254 1.88157 2.56533 + vertex 1.13105 1.87754 2.56733 + endloop + endfacet + facet normal 0.861571 -0.0768456 0.501788 + outer loop + vertex 1.12949 1.87755 2.57042 + vertex 1.13051 1.88163 2.5693 + vertex 1.12855 1.87977 2.57238 + endloop + endfacet + facet normal 0.888124 -0.0980179 0.449031 + outer loop + vertex 1.12949 1.87755 2.57042 + vertex 1.13105 1.87754 2.56733 + vertex 1.13051 1.88163 2.5693 + endloop + endfacet + facet normal 0.88501 -0.101054 0.454473 + outer loop + vertex 1.13105 1.87754 2.56733 + vertex 1.13254 1.88157 2.56533 + vertex 1.13051 1.88163 2.5693 + endloop + endfacet + facet normal 0.858654 -0.0622078 0.508767 + outer loop + vertex 1.13051 1.88163 2.5693 + vertex 1.12849 1.88382 2.57297 + vertex 1.12855 1.87977 2.57238 + endloop + endfacet + facet normal 0.921089 -0.122369 0.369622 + outer loop + vertex 1.13375 1.88505 2.56291 + vertex 1.13397 1.88907 2.56369 + vertex 1.13238 1.88542 2.56645 + endloop + endfacet + facet normal 0.92804 -0.0668332 0.366436 + outer loop + vertex 1.13254 1.88157 2.56533 + vertex 1.13375 1.88505 2.56291 + vertex 1.13238 1.88542 2.56645 + endloop + endfacet + facet normal 0.885625 -0.0944825 0.454689 + outer loop + vertex 1.13254 1.88157 2.56533 + vertex 1.13238 1.88542 2.56645 + vertex 1.13051 1.88163 2.5693 + endloop + endfacet + facet normal 0.88867 -0.101645 0.447141 + outer loop + vertex 1.13238 1.88542 2.56645 + vertex 1.13062 1.8868 2.57025 + vertex 1.13051 1.88163 2.5693 + endloop + endfacet + facet normal 0.839788 -0.115837 0.530413 + outer loop + vertex 1.13062 1.8868 2.57025 + vertex 1.12849 1.88382 2.57297 + vertex 1.13051 1.88163 2.5693 + endloop + endfacet + facet normal 0.81908 -0.0649297 0.569993 + outer loop + vertex 1.12846 1.88868 2.57357 + vertex 1.12849 1.88382 2.57297 + vertex 1.13062 1.8868 2.57025 + endloop + endfacet + facet normal 0.913371 -0.135319 0.383981 + outer loop + vertex 1.13397 1.88907 2.56369 + vertex 1.13429 1.89384 2.56461 + vertex 1.13254 1.89024 2.56751 + endloop + endfacet + facet normal 0.918263 -0.113862 0.379247 + outer loop + vertex 1.13238 1.88542 2.56645 + vertex 1.13397 1.88907 2.56369 + vertex 1.13254 1.89024 2.56751 + endloop + endfacet + facet normal 0.881687 -0.128982 0.453863 + outer loop + vertex 1.13238 1.88542 2.56645 + vertex 1.13254 1.89024 2.56751 + vertex 1.13062 1.8868 2.57025 + endloop + endfacet + facet normal 0.861889 -0.0807149 0.500632 + outer loop + vertex 1.13254 1.89024 2.56751 + vertex 1.13064 1.8917 2.57101 + vertex 1.13062 1.8868 2.57025 + endloop + endfacet + facet normal 0.809548 -0.0929188 0.579653 + outer loop + vertex 1.13064 1.8917 2.57101 + vertex 1.12846 1.88868 2.57357 + vertex 1.13062 1.8868 2.57025 + endloop + endfacet + facet normal 0.793956 -0.0601901 0.604988 + outer loop + vertex 1.12849 1.89338 2.574 + vertex 1.12846 1.88868 2.57357 + vertex 1.13064 1.8917 2.57101 + endloop + endfacet + facet normal 0.884232 -0.12224 0.450768 + outer loop + vertex 1.13429 1.89384 2.56461 + vertex 1.13446 1.89786 2.56536 + vertex 1.13257 1.89572 2.56849 + endloop + endfacet + facet normal 0.895479 -0.0839031 0.437124 + outer loop + vertex 1.13254 1.89024 2.56751 + vertex 1.13429 1.89384 2.56461 + vertex 1.13257 1.89572 2.56849 + endloop + endfacet + facet normal 0.857923 -0.0957996 0.504768 + outer loop + vertex 1.13254 1.89024 2.56751 + vertex 1.13257 1.89572 2.56849 + vertex 1.13064 1.8917 2.57101 + endloop + endfacet + facet normal 0.840904 -0.0674475 0.536964 + outer loop + vertex 1.13257 1.89572 2.56849 + vertex 1.13045 1.89593 2.57184 + vertex 1.13064 1.8917 2.57101 + endloop + endfacet + facet normal 0.785706 -0.0846035 0.612787 + outer loop + vertex 1.13045 1.89593 2.57184 + vertex 1.12849 1.89338 2.574 + vertex 1.13064 1.8917 2.57101 + endloop + endfacet + facet normal 0.774439 -0.0615634 0.629646 + outer loop + vertex 1.1287 1.89794 2.57419 + vertex 1.12849 1.89338 2.574 + vertex 1.13045 1.89593 2.57184 + endloop + endfacet + facet normal 0.880495 -0.100572 0.463264 + outer loop + vertex 1.13446 1.89786 2.56536 + vertex 1.13356 1.90011 2.56756 + vertex 1.13257 1.89572 2.56849 + endloop + endfacet + facet normal 0.834112 -0.0990592 0.542627 + outer loop + vertex 1.13356 1.90011 2.56756 + vertex 1.13367 1.90416 2.56813 + vertex 1.13127 1.90102 2.57125 + endloop + endfacet + facet normal 0.838647 -0.0748598 0.539506 + outer loop + vertex 1.13356 1.90011 2.56756 + vertex 1.13127 1.90102 2.57125 + vertex 1.13257 1.89572 2.56849 + endloop + endfacet + facet normal 0.840405 -0.0731223 0.537003 + outer loop + vertex 1.13257 1.89572 2.56849 + vertex 1.13127 1.90102 2.57125 + vertex 1.13045 1.89593 2.57184 + endloop + endfacet + facet normal 0.778466 -0.053087 0.625438 + outer loop + vertex 1.13127 1.90102 2.57125 + vertex 1.1287 1.89794 2.57419 + vertex 1.13045 1.89593 2.57184 + endloop + endfacet + facet normal 0.776508 -0.0488163 0.628214 + outer loop + vertex 1.1287 1.90178 2.57448 + vertex 1.1287 1.89794 2.57419 + vertex 1.13127 1.90102 2.57125 + endloop + endfacet + facet normal 0.821497 -0.0879982 0.563382 + outer loop + vertex 1.13367 1.90416 2.56813 + vertex 1.13366 1.9087 2.56885 + vertex 1.13195 1.90617 2.57095 + endloop + endfacet + facet normal 0.825978 -0.077133 0.5584 + outer loop + vertex 1.13127 1.90102 2.57125 + vertex 1.13367 1.90416 2.56813 + vertex 1.13195 1.90617 2.57095 + endloop + endfacet + facet normal 0.632778 0.0312566 0.773702 + outer loop + vertex 1.1287 1.90178 2.57448 + vertex 1.12929 1.90593 2.57383 + vertex 1.12683 1.90356 2.57594 + endloop + endfacet + facet normal 0.781429 -0.0136423 0.623845 + outer loop + vertex 1.1287 1.90178 2.57448 + vertex 1.13127 1.90102 2.57125 + vertex 1.12929 1.90593 2.57383 + endloop + endfacet + facet normal 0.736207 -0.0582825 0.674243 + outer loop + vertex 1.13127 1.90102 2.57125 + vertex 1.13195 1.90617 2.57095 + vertex 1.12929 1.90593 2.57383 + endloop + endfacet + facet normal 0.557019 0.148807 0.817059 + outer loop + vertex 1.12929 1.90593 2.57383 + vertex 1.12539 1.9073 2.57624 + vertex 1.12683 1.90356 2.57594 + endloop + endfacet + facet normal 0.756341 -0.0606075 0.651364 + outer loop + vertex 1.13366 1.9087 2.56885 + vertex 1.13367 1.91324 2.56927 + vertex 1.131 1.91063 2.57212 + endloop + endfacet + facet normal 0.775361 -0.000629418 0.631518 + outer loop + vertex 1.13195 1.90617 2.57095 + vertex 1.13366 1.9087 2.56885 + vertex 1.131 1.91063 2.57212 + endloop + endfacet + facet normal 0.637878 0.117262 0.761158 + outer loop + vertex 1.12811 1.91003 2.57464 + vertex 1.131 1.91063 2.57212 + vertex 1.12783 1.91416 2.57423 + endloop + endfacet + facet normal 0.651045 0.0394225 0.758015 + outer loop + vertex 1.12811 1.91003 2.57464 + vertex 1.12929 1.90593 2.57383 + vertex 1.131 1.91063 2.57212 + endloop + endfacet + facet normal 0.735789 -0.0209852 0.676886 + outer loop + vertex 1.12929 1.90593 2.57383 + vertex 1.13195 1.90617 2.57095 + vertex 1.131 1.91063 2.57212 + endloop + endfacet + facet normal 0.521117 -0.016935 0.853317 + outer loop + vertex 1.12929 1.90593 2.57383 + vertex 1.12811 1.91003 2.57464 + vertex 1.12539 1.9073 2.57624 + endloop + endfacet + facet normal 0.708259 -0.046292 0.704433 + outer loop + vertex 1.13367 1.91324 2.56927 + vertex 1.13385 1.91795 2.5694 + vertex 1.13123 1.91568 2.57188 + endloop + endfacet + facet normal 0.730824 -0.000470261 0.682565 + outer loop + vertex 1.131 1.91063 2.57212 + vertex 1.13367 1.91324 2.56927 + vertex 1.13123 1.91568 2.57188 + endloop + endfacet + facet normal 0.565001 0.0138824 0.824973 + outer loop + vertex 1.13123 1.91568 2.57188 + vertex 1.12783 1.91416 2.57423 + vertex 1.131 1.91063 2.57212 + endloop + endfacet + facet normal 0.553306 0.0500352 0.831474 + outer loop + vertex 1.12885 1.91816 2.57332 + vertex 1.12783 1.91416 2.57423 + vertex 1.13123 1.91568 2.57188 + endloop + endfacet + facet normal 0.665043 -0.0638683 0.744069 + outer loop + vertex 1.13385 1.91795 2.5694 + vertex 1.13375 1.92179 2.56981 + vertex 1.13152 1.91993 2.57165 + endloop + endfacet + facet normal 0.691668 -0.00765898 0.722175 + outer loop + vertex 1.13123 1.91568 2.57188 + vertex 1.13385 1.91795 2.5694 + vertex 1.13152 1.91993 2.57165 + endloop + endfacet + facet normal 0.524454 0.0106343 0.851373 + outer loop + vertex 1.13152 1.91993 2.57165 + vertex 1.12885 1.91816 2.57332 + vertex 1.13123 1.91568 2.57188 + endloop + endfacet + facet normal 0.483483 0.0906774 0.870644 + outer loop + vertex 1.12877 1.9225 2.57291 + vertex 1.12885 1.91816 2.57332 + vertex 1.13152 1.91993 2.57165 + endloop + endfacet + facet normal 0.640331 -0.0107931 0.768023 + outer loop + vertex 1.13375 1.92179 2.56981 + vertex 1.13214 1.92345 2.57118 + vertex 1.13152 1.91993 2.57165 + endloop + endfacet + facet normal 0.446737 0.0400829 0.893767 + outer loop + vertex 1.13214 1.92345 2.57118 + vertex 1.12877 1.9225 2.57291 + vertex 1.13152 1.91993 2.57165 + endloop + endfacet + facet normal 0.444429 0.0494483 0.894448 + outer loop + vertex 1.13214 1.92345 2.57118 + vertex 1.13144 1.92693 2.57134 + vertex 1.12877 1.9225 2.57291 + endloop + endfacet + facet normal 0.335928 0.128349 0.933102 + outer loop + vertex 1.13144 1.92693 2.57134 + vertex 1.12757 1.9271 2.57271 + vertex 1.12877 1.9225 2.57291 + endloop + endfacet + facet normal 0.335708 0.0784342 0.938695 + outer loop + vertex 1.13144 1.92693 2.57134 + vertex 1.13044 1.93101 2.57135 + vertex 1.12757 1.9271 2.57271 + endloop + endfacet + facet normal 0.206558 0.181362 0.961479 + outer loop + vertex 1.12757 1.9271 2.57271 + vertex 1.13044 1.93101 2.57135 + vertex 1.12591 1.93179 2.57218 + endloop + endfacet + facet normal 0.201966 0.147274 0.968256 + outer loop + vertex 1.13044 1.93101 2.57135 + vertex 1.1299 1.93494 2.57087 + vertex 1.12591 1.93179 2.57218 + endloop + endfacet + facet normal 0.272343 0.154626 0.949695 + outer loop + vertex 1.13232 1.93367 2.57038 + vertex 1.1299 1.93494 2.57087 + vertex 1.13044 1.93101 2.57135 + endloop + endfacet + facet normal 0.261083 0.213973 0.941303 + outer loop + vertex 1.13459 2.07397 2.54006 + vertex 1.13308 2.07875 2.53939 + vertex 1.13033 2.07502 2.541 + endloop + endfacet + facet normal 0.343111 0.15357 0.926656 + outer loop + vertex 1.12994 2.08275 2.53962 + vertex 1.13226 2.08595 2.53823 + vertex 1.12881 2.0878 2.5392 + endloop + endfacet + facet normal 0.344851 0.157509 0.925348 + outer loop + vertex 1.13226 2.08595 2.53823 + vertex 1.13249 2.09062 2.53735 + vertex 1.12881 2.0878 2.5392 + endloop + endfacet + facet normal 0.351488 0.148217 0.924385 + outer loop + vertex 1.12881 2.0878 2.5392 + vertex 1.13249 2.09062 2.53735 + vertex 1.12743 2.09334 2.53884 + endloop + endfacet + facet normal 0.360925 0.169754 0.917015 + outer loop + vertex 1.13249 2.09062 2.53735 + vertex 1.13077 2.09651 2.53694 + vertex 1.12743 2.09334 2.53884 + endloop + endfacet + facet normal 0.367828 0.161713 0.915724 + outer loop + vertex 1.12743 2.09334 2.53884 + vertex 1.13077 2.09651 2.53694 + vertex 1.12748 2.0972 2.53814 + endloop + endfacet + facet normal 0.357989 0.173144 0.917532 + outer loop + vertex 1.13384 2.09847 2.53537 + vertex 1.13445 2.10252 2.53437 + vertex 1.13138 2.10056 2.53594 + endloop + endfacet + facet normal 0.357684 0.17273 0.917729 + outer loop + vertex 1.13138 2.10056 2.53594 + vertex 1.13077 2.09651 2.53694 + vertex 1.13384 2.09847 2.53537 + endloop + endfacet + facet normal 0.367711 0.170353 0.914204 + outer loop + vertex 1.13138 2.10056 2.53594 + vertex 1.1277 2.10085 2.53736 + vertex 1.13077 2.09651 2.53694 + endloop + endfacet + facet normal 0.369045 0.171368 0.913476 + outer loop + vertex 1.1277 2.10085 2.53736 + vertex 1.12748 2.0972 2.53814 + vertex 1.13077 2.09651 2.53694 + endloop + endfacet + facet normal 0.362591 0.177375 0.914913 + outer loop + vertex 1.13445 2.10252 2.53437 + vertex 1.13282 2.10818 2.53392 + vertex 1.13023 2.10447 2.53567 + endloop + endfacet + facet normal 0.359935 0.169966 0.917365 + outer loop + vertex 1.13138 2.10056 2.53594 + vertex 1.13445 2.10252 2.53437 + vertex 1.13023 2.10447 2.53567 + endloop + endfacet + facet normal 0.367722 0.17202 0.913887 + outer loop + vertex 1.13023 2.10447 2.53567 + vertex 1.1277 2.10085 2.53736 + vertex 1.13138 2.10056 2.53594 + endloop + endfacet + facet normal 0.364267 0.174838 0.914735 + outer loop + vertex 1.12604 2.10632 2.53698 + vertex 1.1277 2.10085 2.53736 + vertex 1.13023 2.10447 2.53567 + endloop + endfacet + facet normal 0.368103 0.172892 0.913569 + outer loop + vertex 1.12906 2.10842 2.53539 + vertex 1.13023 2.10447 2.53567 + vertex 1.13282 2.10818 2.53392 + endloop + endfacet + facet normal 0.368076 0.175709 0.913042 + outer loop + vertex 1.12906 2.10842 2.53539 + vertex 1.13282 2.10818 2.53392 + vertex 1.12961 2.11259 2.53436 + endloop + endfacet + facet normal 0.367259 0.175069 0.913494 + outer loop + vertex 1.12961 2.11259 2.53436 + vertex 1.13282 2.10818 2.53392 + vertex 1.13281 2.11202 2.53319 + endloop + endfacet + facet normal 0.363155 0.171584 0.915793 + outer loop + vertex 1.13023 2.10447 2.53567 + vertex 1.12906 2.10842 2.53539 + vertex 1.12604 2.10632 2.53698 + endloop + endfacet + facet normal 0.366984 0.172097 0.914169 + outer loop + vertex 1.13281 2.11202 2.53319 + vertex 1.13274 2.11586 2.53249 + vertex 1.12961 2.11259 2.53436 + endloop + endfacet + facet normal 0.349514 0.190594 0.91734 + outer loop + vertex 1.12961 2.11259 2.53436 + vertex 1.13274 2.11586 2.53249 + vertex 1.12768 2.11829 2.53391 + endloop + endfacet + facet normal 0.34516 0.179258 0.921266 + outer loop + vertex 1.13274 2.11586 2.53249 + vertex 1.13085 2.12138 2.53213 + vertex 1.12768 2.11829 2.53391 + endloop + endfacet + facet normal 0.308225 0.219649 0.925609 + outer loop + vertex 1.12768 2.11829 2.53391 + vertex 1.13085 2.12138 2.53213 + vertex 1.12739 2.12189 2.53316 + endloop + endfacet + facet normal 0.314872 0.248 0.916161 + outer loop + vertex 1.13385 2.12351 2.53065 + vertex 1.13384 2.1278 2.5295 + vertex 1.13106 2.12517 2.53117 + endloop + endfacet + facet normal 0.29982 0.218699 0.92859 + outer loop + vertex 1.13106 2.12517 2.53117 + vertex 1.13085 2.12138 2.53213 + vertex 1.13385 2.12351 2.53065 + endloop + endfacet + facet normal 0.215671 0.228527 0.949348 + outer loop + vertex 1.13106 2.12517 2.53117 + vertex 1.12704 2.12494 2.53214 + vertex 1.13085 2.12138 2.53213 + endloop + endfacet + facet normal 0.314049 0.334159 0.888657 + outer loop + vertex 1.12704 2.12494 2.53214 + vertex 1.12739 2.12189 2.53316 + vertex 1.13085 2.12138 2.53213 + endloop + endfacet + facet normal 0.203281 0.361866 0.909797 + outer loop + vertex 1.12911 2.12779 2.53056 + vertex 1.13106 2.12517 2.53117 + vertex 1.13384 2.1278 2.5295 + endloop + endfacet + facet normal 0.190585 0.484361 0.853857 + outer loop + vertex 1.12911 2.12779 2.53056 + vertex 1.13384 2.1278 2.5295 + vertex 1.12884 2.13174 2.52838 + endloop + endfacet + facet normal 0.023529 0.300641 0.953447 + outer loop + vertex 1.12884 2.13174 2.52838 + vertex 1.13384 2.1278 2.5295 + vertex 1.13384 2.13218 2.52812 + endloop + endfacet + facet normal 0.199098 0.359225 0.911766 + outer loop + vertex 1.13106 2.12517 2.53117 + vertex 1.12911 2.12779 2.53056 + vertex 1.12704 2.12494 2.53214 + endloop + endfacet + facet normal -0.264905 0.694443 0.66901 + outer loop + vertex 1.12989 2.13767 2.52409 + vertex 1.12642 2.13681 2.52361 + vertex 1.12846 2.13527 2.52601 + endloop + endfacet + facet normal -0.119886 0.663447 0.738557 + outer loop + vertex 1.12846 2.13527 2.52601 + vertex 1.132 2.13516 2.52669 + vertex 1.12989 2.13767 2.52409 + endloop + endfacet + facet normal -0.141218 0.540945 0.829118 + outer loop + vertex 1.12846 2.13527 2.52601 + vertex 1.12884 2.13174 2.52838 + vertex 1.132 2.13516 2.52669 + endloop + endfacet + facet normal 0.00884406 0.436799 0.899516 + outer loop + vertex 1.12884 2.13174 2.52838 + vertex 1.13384 2.13218 2.52812 + vertex 1.132 2.13516 2.52669 + endloop + endfacet + facet normal -0.321151 0.803854 0.50068 + outer loop + vertex 1.1309 2.14042 2.52111 + vertex 1.12735 2.14088 2.51809 + vertex 1.12704 2.13904 2.52086 + endloop + endfacet + facet normal -0.271541 0.777196 0.567655 + outer loop + vertex 1.12704 2.13904 2.52086 + vertex 1.12642 2.13681 2.52361 + vertex 1.12989 2.13767 2.52409 + endloop + endfacet + facet normal -0.307199 0.748877 0.587207 + outer loop + vertex 1.1309 2.14042 2.52111 + vertex 1.12704 2.13904 2.52086 + vertex 1.12989 2.13767 2.52409 + endloop + endfacet + facet normal -0.161839 0.751962 0.639031 + outer loop + vertex 1.1309 2.14042 2.52111 + vertex 1.12989 2.13767 2.52409 + vertex 1.13427 2.13828 2.52448 + endloop + endfacet + facet normal -0.315869 0.625738 0.713217 + outer loop + vertex 1.1309 2.14042 2.52111 + vertex 1.13427 2.13828 2.52448 + vertex 1.13429 2.14061 2.52245 + endloop + endfacet + facet normal -0.156547 0.643659 0.749131 + outer loop + vertex 1.13427 2.13828 2.52448 + vertex 1.12989 2.13767 2.52409 + vertex 1.132 2.13516 2.52669 + endloop + endfacet + facet normal -0.164371 0.237913 0.957277 + outer loop + vertex 1.1318 2.14829 2.51066 + vertex 1.13042 2.15 2.51 + vertex 1.13 2.14971 2.51 + endloop + endfacet + facet normal 0.145239 0.564644 0.812455 + outer loop + vertex 1.13032 2.14548 2.51288 + vertex 1.1318 2.14829 2.51066 + vertex 1.13 2.14971 2.51 + endloop + endfacet + facet normal -0.378701 0.68826 0.618777 + outer loop + vertex 1.13294 2.14654 2.5133 + vertex 1.1318 2.14829 2.51066 + vertex 1.13032 2.14548 2.51288 + endloop + endfacet + facet normal -0.39209 0.764196 0.512122 + outer loop + vertex 1.13294 2.14654 2.5133 + vertex 1.13032 2.14548 2.51288 + vertex 1.13394 2.14489 2.51654 + endloop + endfacet + facet normal -0.379334 0.777467 0.501647 + outer loop + vertex 1.13394 2.14489 2.51654 + vertex 1.13032 2.14548 2.51288 + vertex 1.1296 2.14275 2.51658 + endloop + endfacet + facet normal -0.324303 0.800581 0.503883 + outer loop + vertex 1.1309 2.14042 2.52111 + vertex 1.1296 2.14275 2.51658 + vertex 1.12735 2.14088 2.51809 + endloop + endfacet + facet normal -0.320317 0.802334 0.503644 + outer loop + vertex 1.1309 2.14042 2.52111 + vertex 1.13416 2.14234 2.52012 + vertex 1.1296 2.14275 2.51658 + endloop + endfacet + facet normal -0.364448 0.748332 0.554235 + outer loop + vertex 1.13416 2.14234 2.52012 + vertex 1.13394 2.14489 2.51654 + vertex 1.1296 2.14275 2.51658 + endloop + endfacet + facet normal -0.272989 0.763829 0.584845 + outer loop + vertex 1.13416 2.14234 2.52012 + vertex 1.1309 2.14042 2.52111 + vertex 1.13429 2.14061 2.52245 + endloop + endfacet + facet normal -0.489022 0.345547 0.800908 + outer loop + vertex 1.135 2.15435 2.51 + vertex 1.1318 2.14829 2.51066 + vertex 1.13502 2.14869 2.51246 + endloop + endfacet + facet normal -0.199158 0.209691 0.95727 + outer loop + vertex 1.13042 2.15 2.51 + vertex 1.1318 2.14829 2.51066 + vertex 1.135 2.15435 2.51 + endloop + endfacet + facet normal -0.426617 0.658674 0.619795 + outer loop + vertex 1.13502 2.14869 2.51246 + vertex 1.1318 2.14829 2.51066 + vertex 1.13294 2.14654 2.5133 + endloop + endfacet + facet normal -0.834858 -0.546973 0.0619027 + outer loop + vertex 1.13932 0.871891 2.50622 + vertex 1.13719 0.875 2.505 + vertex 1.14 0.870711 2.505 + endloop + endfacet + facet normal -0.808032 -0.583794 -0.079181 + outer loop + vertex 1.1367 0.875 2.51 + vertex 1.13719 0.875 2.505 + vertex 1.13932 0.871891 2.50622 + endloop + endfacet + facet normal -0.63081 -0.754002 0.183191 + outer loop + vertex 1.13842 0.873347 2.50911 + vertex 1.1367 0.875 2.51 + vertex 1.13932 0.871891 2.50622 + endloop + endfacet + facet normal -0.251113 0.243831 -0.936744 + outer loop + vertex 1.13678 0.87461 2.50988 + vertex 1.1367 0.875 2.51 + vertex 1.13842 0.873347 2.50911 + endloop + endfacet + facet normal -0.440735 -0.808066 0.390874 + outer loop + vertex 1.13842 0.873347 2.50911 + vertex 1.13886 0.874743 2.51249 + vertex 1.13678 0.87461 2.50988 + endloop + endfacet + facet normal -0.0382987 0.294074 -0.955015 + outer loop + vertex 1.1367 0.875 2.51 + vertex 1.13678 0.87461 2.50988 + vertex 1.13466 0.876257 2.51047 + endloop + endfacet + facet normal -0.329151 -0.74811 0.576187 + outer loop + vertex 1.135 0.875748 2.51 + vertex 1.1367 0.875 2.51 + vertex 1.13466 0.876257 2.51047 + endloop + endfacet + facet normal -0.398553 -0.811965 0.42646 + outer loop + vertex 1.13794 0.876915 2.51578 + vertex 1.13574 0.878166 2.51611 + vertex 1.13508 0.877255 2.51375 + endloop + endfacet + facet normal -0.398062 -0.812627 0.425657 + outer loop + vertex 1.13886 0.874743 2.51249 + vertex 1.13794 0.876915 2.51578 + vertex 1.13508 0.877255 2.51375 + endloop + endfacet + facet normal -0.451882 -0.836072 0.311105 + outer loop + vertex 1.13886 0.874743 2.51249 + vertex 1.13508 0.877255 2.51375 + vertex 1.13466 0.876257 2.51047 + endloop + endfacet + facet normal -0.480682 -0.769433 0.420615 + outer loop + vertex 1.13886 0.874743 2.51249 + vertex 1.13466 0.876257 2.51047 + vertex 1.13678 0.87461 2.50988 + endloop + endfacet + facet normal -0.330704 -0.735042 0.591902 + outer loop + vertex 1.13794 0.876915 2.51578 + vertex 1.13808 0.879038 2.5185 + vertex 1.13574 0.878166 2.51611 + endloop + endfacet + facet normal -0.451792 -0.781786 0.429762 + outer loop + vertex 1.13508 0.877255 2.51375 + vertex 1.13574 0.878166 2.51611 + vertex 1.13246 0.879926 2.51586 + endloop + endfacet + facet normal -0.261445 -0.693824 0.671011 + outer loop + vertex 1.13802 0.881717 2.52129 + vertex 1.13621 0.883547 2.52248 + vertex 1.13437 0.881724 2.51988 + endloop + endfacet + facet normal -0.259223 -0.700178 0.665248 + outer loop + vertex 1.13808 0.879038 2.5185 + vertex 1.13802 0.881717 2.52129 + vertex 1.13437 0.881724 2.51988 + endloop + endfacet + facet normal -0.365615 -0.772406 0.519341 + outer loop + vertex 1.13808 0.879038 2.5185 + vertex 1.13437 0.881724 2.51988 + vertex 1.13246 0.879926 2.51586 + endloop + endfacet + facet normal -0.401909 -0.660327 0.634379 + outer loop + vertex 1.13808 0.879038 2.5185 + vertex 1.13246 0.879926 2.51586 + vertex 1.13574 0.878166 2.51611 + endloop + endfacet + facet normal -0.0666723 -0.58796 0.806138 + outer loop + vertex 1.13802 0.881717 2.52129 + vertex 1.14024 0.884424 2.52345 + vertex 1.13621 0.883547 2.52248 + endloop + endfacet + facet normal -0.23403 -0.710671 0.663459 + outer loop + vertex 1.13437 0.881724 2.51988 + vertex 1.13621 0.883547 2.52248 + vertex 1.13249 0.884372 2.52205 + endloop + endfacet + facet normal -0.0582928 -0.609409 0.79071 + outer loop + vertex 1.13621 0.883547 2.52248 + vertex 1.14024 0.884424 2.52345 + vertex 1.13628 0.886574 2.52482 + endloop + endfacet + facet normal -0.220701 -0.592998 0.774367 + outer loop + vertex 1.13621 0.883547 2.52248 + vertex 1.13628 0.886574 2.52482 + vertex 1.13249 0.884372 2.52205 + endloop + endfacet + facet normal -0.100385 -0.706804 0.700251 + outer loop + vertex 1.13249 0.884372 2.52205 + vertex 1.13628 0.886574 2.52482 + vertex 1.13143 0.887086 2.52464 + endloop + endfacet + facet normal -0.0915532 -0.586878 0.804483 + outer loop + vertex 1.13628 0.886574 2.52482 + vertex 1.13432 0.890342 2.52734 + vertex 1.13143 0.887086 2.52464 + endloop + endfacet + facet normal 0.088784 -0.522274 0.848143 + outer loop + vertex 1.13902 0.890185 2.52675 + vertex 1.13432 0.890342 2.52734 + vertex 1.13628 0.886574 2.52482 + endloop + endfacet + facet normal 0.106294 -0.331969 0.937282 + outer loop + vertex 1.13902 0.890185 2.52675 + vertex 1.13873 0.894179 2.5282 + vertex 1.13432 0.890342 2.52734 + endloop + endfacet + facet normal 0.230074 -0.457047 0.85917 + outer loop + vertex 1.13432 0.890342 2.52734 + vertex 1.13873 0.894179 2.5282 + vertex 1.13463 0.894725 2.52959 + endloop + endfacet + facet normal 0.326504 -0.190385 0.925823 + outer loop + vertex 1.13804 0.934312 2.53668 + vertex 1.13345 0.934279 2.5383 + vertex 1.13329 0.928939 2.53726 + endloop + endfacet + facet normal 0.32487 -0.216516 0.920641 + outer loop + vertex 1.13804 0.934312 2.53668 + vertex 1.13816 0.939141 2.53778 + vertex 1.13345 0.934279 2.5383 + endloop + endfacet + facet normal 0.291504 -0.18219 0.939059 + outer loop + vertex 1.13345 0.934279 2.5383 + vertex 1.13816 0.939141 2.53778 + vertex 1.13339 0.939467 2.53932 + endloop + endfacet + facet normal 0.288842 -0.203872 0.935418 + outer loop + vertex 1.13816 0.939141 2.53778 + vertex 1.13848 0.944024 2.53874 + vertex 1.13339 0.939467 2.53932 + endloop + endfacet + facet normal 0.259491 -0.169093 0.950827 + outer loop + vertex 1.13339 0.939467 2.53932 + vertex 1.13848 0.944024 2.53874 + vertex 1.13457 0.944804 2.53995 + endloop + endfacet + facet normal 0.252033 -0.200229 0.946778 + outer loop + vertex 1.13848 0.944024 2.53874 + vertex 1.13881 0.948669 2.53964 + vertex 1.13457 0.944804 2.53995 + endloop + endfacet + facet normal 0.256337 -0.109264 0.960392 + outer loop + vertex 1.13706 1.06802 2.56669 + vertex 1.13715 1.0728 2.56721 + vertex 1.13309 1.06845 2.5678 + endloop + endfacet + facet normal 0.299552 -0.15219 0.941864 + outer loop + vertex 1.13309 1.06845 2.5678 + vertex 1.13715 1.0728 2.56721 + vertex 1.13314 1.07343 2.56859 + endloop + endfacet + facet normal 0.307126 -0.111569 0.945106 + outer loop + vertex 1.13715 1.0728 2.56721 + vertex 1.13719 1.07795 2.5678 + vertex 1.13314 1.07343 2.56859 + endloop + endfacet + facet normal 0.362356 -0.16611 0.917118 + outer loop + vertex 1.13314 1.07343 2.56859 + vertex 1.13719 1.07795 2.5678 + vertex 1.13309 1.07877 2.56957 + endloop + endfacet + facet normal 0.316645 -0.199397 0.927349 + outer loop + vertex 1.1341 1.08326 2.57019 + vertex 1.13104 1.08137 2.57083 + vertex 1.13309 1.07877 2.56957 + endloop + endfacet + facet normal 0.478914 -0.225014 0.848534 + outer loop + vertex 1.1341 1.08326 2.57019 + vertex 1.13309 1.07877 2.56957 + vertex 1.13721 1.08366 2.56854 + endloop + endfacet + facet normal 0.37284 -0.120372 0.920055 + outer loop + vertex 1.13721 1.08366 2.56854 + vertex 1.13309 1.07877 2.56957 + vertex 1.13719 1.07795 2.5678 + endloop + endfacet + facet normal 0.315306 -0.196906 0.928337 + outer loop + vertex 1.1341 1.08326 2.57019 + vertex 1.13253 1.08482 2.57106 + vertex 1.13104 1.08137 2.57083 + endloop + endfacet + facet normal 0.554543 -0.08081 0.828222 + outer loop + vertex 1.13721 1.08366 2.56854 + vertex 1.13807 1.08933 2.56852 + vertex 1.13518 1.08695 2.57022 + endloop + endfacet + facet normal 0.478202 -0.147343 0.865802 + outer loop + vertex 1.1341 1.08326 2.57019 + vertex 1.13721 1.08366 2.56854 + vertex 1.13518 1.08695 2.57022 + endloop + endfacet + facet normal 0.384281 -0.120154 0.915364 + outer loop + vertex 1.13518 1.08695 2.57022 + vertex 1.13253 1.08482 2.57106 + vertex 1.1341 1.08326 2.57019 + endloop + endfacet + facet normal 0.367001 -0.0947162 0.925386 + outer loop + vertex 1.13222 1.08816 2.57152 + vertex 1.13253 1.08482 2.57106 + vertex 1.13518 1.08695 2.57022 + endloop + endfacet + facet normal 0.570399 -0.0132532 0.821261 + outer loop + vertex 1.13807 1.08933 2.56852 + vertex 1.1382 1.09443 2.56851 + vertex 1.13536 1.09149 2.57044 + endloop + endfacet + facet normal 0.543538 -0.0610989 0.837158 + outer loop + vertex 1.13518 1.08695 2.57022 + vertex 1.13807 1.08933 2.56852 + vertex 1.13536 1.09149 2.57044 + endloop + endfacet + facet normal 0.380695 -0.0587371 0.922833 + outer loop + vertex 1.13536 1.09149 2.57044 + vertex 1.13222 1.08816 2.57152 + vertex 1.13518 1.08695 2.57022 + endloop + endfacet + facet normal 0.404419 -0.0850791 0.910608 + outer loop + vertex 1.13203 1.09276 2.57203 + vertex 1.13222 1.08816 2.57152 + vertex 1.13536 1.09149 2.57044 + endloop + endfacet + facet normal 0.60445 0.0210242 0.796366 + outer loop + vertex 1.1382 1.09443 2.56851 + vertex 1.13821 1.09961 2.56837 + vertex 1.13531 1.09639 2.57065 + endloop + endfacet + facet normal 0.581844 -0.0298874 0.812751 + outer loop + vertex 1.13536 1.09149 2.57044 + vertex 1.1382 1.09443 2.56851 + vertex 1.13531 1.09639 2.57065 + endloop + endfacet + facet normal 0.421241 -0.0353617 0.906259 + outer loop + vertex 1.13531 1.09639 2.57065 + vertex 1.13203 1.09276 2.57203 + vertex 1.13536 1.09149 2.57044 + endloop + endfacet + facet normal 0.463512 -0.0826691 0.882226 + outer loop + vertex 1.13201 1.09769 2.57251 + vertex 1.13203 1.09276 2.57203 + vertex 1.13531 1.09639 2.57065 + endloop + endfacet + facet normal 0.651089 0.0198881 0.758741 + outer loop + vertex 1.13821 1.09961 2.56837 + vertex 1.13816 1.10489 2.56827 + vertex 1.1353 1.10148 2.57082 + endloop + endfacet + facet normal 0.634788 -0.0232628 0.772336 + outer loop + vertex 1.13531 1.09639 2.57065 + vertex 1.13821 1.09961 2.56837 + vertex 1.1353 1.10148 2.57082 + endloop + endfacet + facet normal 0.481724 -0.0271359 0.875903 + outer loop + vertex 1.1353 1.10148 2.57082 + vertex 1.13201 1.09769 2.57251 + vertex 1.13531 1.09639 2.57065 + endloop + endfacet + facet normal 0.538022 -0.0930394 0.83778 + outer loop + vertex 1.13215 1.10282 2.57299 + vertex 1.13201 1.09769 2.57251 + vertex 1.1353 1.10148 2.57082 + endloop + endfacet + facet normal 0.69748 0.0336552 0.715813 + outer loop + vertex 1.13816 1.10489 2.56827 + vertex 1.13805 1.11009 2.56813 + vertex 1.13534 1.10673 2.57094 + endloop + endfacet + facet normal 0.678665 -0.0215847 0.73413 + outer loop + vertex 1.1353 1.10148 2.57082 + vertex 1.13816 1.10489 2.56827 + vertex 1.13534 1.10673 2.57094 + endloop + endfacet + facet normal 0.560958 -0.0228811 0.827528 + outer loop + vertex 1.13534 1.10673 2.57094 + vertex 1.13215 1.10282 2.57299 + vertex 1.1353 1.10148 2.57082 + endloop + endfacet + facet normal 0.610927 -0.0848282 0.78713 + outer loop + vertex 1.13224 1.10847 2.57353 + vertex 1.13215 1.10282 2.57299 + vertex 1.13534 1.10673 2.57094 + endloop + endfacet + facet normal 0.742302 0.0599854 0.667375 + outer loop + vertex 1.13805 1.11009 2.56813 + vertex 1.13802 1.11507 2.56772 + vertex 1.13552 1.11217 2.57076 + endloop + endfacet + facet normal 0.719544 -0.00203837 0.694444 + outer loop + vertex 1.13534 1.10673 2.57094 + vertex 1.13805 1.11009 2.56813 + vertex 1.13552 1.11217 2.57076 + endloop + endfacet + facet normal 0.642583 0.00278961 0.766211 + outer loop + vertex 1.13552 1.11217 2.57076 + vertex 1.13224 1.10847 2.57353 + vertex 1.13534 1.10673 2.57094 + endloop + endfacet + facet normal 0.67047 -0.040939 0.740806 + outer loop + vertex 1.133 1.11448 2.57317 + vertex 1.13224 1.10847 2.57353 + vertex 1.13552 1.11217 2.57076 + endloop + endfacet + facet normal 0.778751 0.0776288 0.622511 + outer loop + vertex 1.13802 1.11507 2.56772 + vertex 1.13818 1.11888 2.56705 + vertex 1.13589 1.11797 2.57003 + endloop + endfacet + facet normal 0.755322 0.0350676 0.654415 + outer loop + vertex 1.13552 1.11217 2.57076 + vertex 1.13802 1.11507 2.56772 + vertex 1.13589 1.11797 2.57003 + endloop + endfacet + facet normal 0.711058 0.0439097 0.701761 + outer loop + vertex 1.13589 1.11797 2.57003 + vertex 1.133 1.11448 2.57317 + vertex 1.13552 1.11217 2.57076 + endloop + endfacet + facet normal 0.727086 0.016803 0.686341 + outer loop + vertex 1.13302 1.11983 2.57302 + vertex 1.133 1.11448 2.57317 + vertex 1.13589 1.11797 2.57003 + endloop + endfacet + facet normal 0.841763 0.111784 0.528147 + outer loop + vertex 1.13911 1.12139 2.56511 + vertex 1.13895 1.1251 2.56459 + vertex 1.13758 1.12216 2.56738 + endloop + endfacet + facet normal 0.840896 0.0979918 0.532252 + outer loop + vertex 1.13818 1.11888 2.56705 + vertex 1.13911 1.12139 2.56511 + vertex 1.13758 1.12216 2.56738 + endloop + endfacet + facet normal 0.778728 0.0777378 0.622527 + outer loop + vertex 1.13818 1.11888 2.56705 + vertex 1.13758 1.12216 2.56738 + vertex 1.13589 1.11797 2.57003 + endloop + endfacet + facet normal 0.795187 0.0590394 0.603483 + outer loop + vertex 1.13589 1.11797 2.57003 + vertex 1.13758 1.12216 2.56738 + vertex 1.13537 1.12329 2.57019 + endloop + endfacet + facet normal 0.736707 0.0511007 0.674279 + outer loop + vertex 1.13537 1.12329 2.57019 + vertex 1.13302 1.11983 2.57302 + vertex 1.13589 1.11797 2.57003 + endloop + endfacet + facet normal 0.747787 0.0343886 0.663047 + outer loop + vertex 1.1328 1.12494 2.573 + vertex 1.13302 1.11983 2.57302 + vertex 1.13537 1.12329 2.57019 + endloop + endfacet + facet normal 0.864073 0.0895476 0.495338 + outer loop + vertex 1.13895 1.1251 2.56459 + vertex 1.13863 1.12977 2.56429 + vertex 1.13729 1.12666 2.5672 + endloop + endfacet + facet normal 0.861787 0.0770352 0.501387 + outer loop + vertex 1.13758 1.12216 2.56738 + vertex 1.13895 1.1251 2.56459 + vertex 1.13729 1.12666 2.5672 + endloop + endfacet + facet normal 0.797594 0.0767881 0.598287 + outer loop + vertex 1.13758 1.12216 2.56738 + vertex 1.13729 1.12666 2.5672 + vertex 1.13537 1.12329 2.57019 + endloop + endfacet + facet normal 0.808683 0.0589301 0.585285 + outer loop + vertex 1.13729 1.12666 2.5672 + vertex 1.13512 1.12826 2.57003 + vertex 1.13537 1.12329 2.57019 + endloop + endfacet + facet normal 0.753858 0.0584811 0.65443 + outer loop + vertex 1.13512 1.12826 2.57003 + vertex 1.1328 1.12494 2.573 + vertex 1.13537 1.12329 2.57019 + endloop + endfacet + facet normal 0.766889 0.0370693 0.640709 + outer loop + vertex 1.13267 1.12999 2.57286 + vertex 1.1328 1.12494 2.573 + vertex 1.13512 1.12826 2.57003 + endloop + endfacet + facet normal 0.966064 0.145828 -0.213203 + outer loop + vertex 1.14 1.13076 2.56 + vertex 1.13936 1.135 2.56 + vertex 1.14 1.135 2.5629 + endloop + endfacet + facet normal 0.871193 0.0804299 0.484308 + outer loop + vertex 1.13863 1.12977 2.56429 + vertex 1.13833 1.13456 2.56404 + vertex 1.13704 1.13161 2.56684 + endloop + endfacet + facet normal 0.870589 0.0778286 0.485817 + outer loop + vertex 1.13729 1.12666 2.5672 + vertex 1.13863 1.12977 2.56429 + vertex 1.13704 1.13161 2.56684 + endloop + endfacet + facet normal 0.813275 0.0814475 0.576151 + outer loop + vertex 1.13729 1.12666 2.5672 + vertex 1.13704 1.13161 2.56684 + vertex 1.13512 1.12826 2.57003 + endloop + endfacet + facet normal 0.820038 0.069864 0.568029 + outer loop + vertex 1.13704 1.13161 2.56684 + vertex 1.13491 1.13329 2.56971 + vertex 1.13512 1.12826 2.57003 + endloop + endfacet + facet normal 0.77563 0.071715 0.627101 + outer loop + vertex 1.13491 1.13329 2.56971 + vertex 1.13267 1.12999 2.57286 + vertex 1.13512 1.12826 2.57003 + endloop + endfacet + facet normal 0.791501 0.0442812 0.609562 + outer loop + vertex 1.13266 1.13492 2.57252 + vertex 1.13267 1.12999 2.57286 + vertex 1.13491 1.13329 2.56971 + endloop + endfacet + facet normal 0.828376 -0.0133019 0.560014 + outer loop + vertex 1.13833 1.13456 2.56404 + vertex 1.13851 1.13892 2.56388 + vertex 1.13689 1.13752 2.56625 + endloop + endfacet + facet normal 0.875929 0.0715085 0.47711 + outer loop + vertex 1.13704 1.13161 2.56684 + vertex 1.13833 1.13456 2.56404 + vertex 1.13689 1.13752 2.56625 + endloop + endfacet + facet normal 0.821894 0.0788499 0.564157 + outer loop + vertex 1.13704 1.13161 2.56684 + vertex 1.13689 1.13752 2.56625 + vertex 1.13491 1.13329 2.56971 + endloop + endfacet + facet normal 0.817267 0.0856839 0.569853 + outer loop + vertex 1.13689 1.13752 2.56625 + vertex 1.13452 1.138 2.56957 + vertex 1.13491 1.13329 2.56971 + endloop + endfacet + facet normal 0.800567 0.085009 0.593182 + outer loop + vertex 1.13452 1.138 2.56957 + vertex 1.13266 1.13492 2.57252 + vertex 1.13491 1.13329 2.56971 + endloop + endfacet + facet normal 0.822846 0.0460129 0.566399 + outer loop + vertex 1.13286 1.13876 2.57191 + vertex 1.13266 1.13492 2.57252 + vertex 1.13452 1.138 2.56957 + endloop + endfacet + facet normal -0.508623 -0.0591302 0.858957 + outer loop + vertex 1.13851 1.13892 2.56388 + vertex 1.14 1.14242 2.565 + vertex 1.1397 1.145 2.565 + endloop + endfacet + facet normal 0.860933 -0.250129 0.442978 + outer loop + vertex 1.13851 1.13892 2.56388 + vertex 1.1397 1.145 2.565 + vertex 1.13689 1.13752 2.56625 + endloop + endfacet + facet normal 0.434687 -0.0135758 0.900479 + outer loop + vertex 1.13689 1.13752 2.56625 + vertex 1.1397 1.145 2.565 + vertex 1.13547 1.14302 2.56701 + endloop + endfacet + facet normal 0.861157 0.092749 0.499806 + outer loop + vertex 1.13391 1.14128 2.57002 + vertex 1.13547 1.14302 2.56701 + vertex 1.13388 1.145 2.56938 + endloop + endfacet + facet normal 0.861734 0.0910544 0.499122 + outer loop + vertex 1.13391 1.14128 2.57002 + vertex 1.13452 1.138 2.56957 + vertex 1.13547 1.14302 2.56701 + endloop + endfacet + facet normal 0.816263 0.131896 0.562422 + outer loop + vertex 1.13452 1.138 2.56957 + vertex 1.13689 1.13752 2.56625 + vertex 1.13547 1.14302 2.56701 + endloop + endfacet + facet normal 0.825795 0.0762434 0.558793 + outer loop + vertex 1.13452 1.138 2.56957 + vertex 1.13391 1.14128 2.57002 + vertex 1.13286 1.13876 2.57191 + endloop + endfacet + facet normal 0.28462 0.209559 -0.935455 + outer loop + vertex 1.135 1.15 2.56469 + vertex 1.1397 1.145 2.565 + vertex 1.135 1.145 2.56357 + endloop + endfacet + facet normal -0.170909 -0.0998943 0.98021 + outer loop + vertex 1.13508 1.14842 2.56454 + vertex 1.1397 1.145 2.565 + vertex 1.135 1.15 2.56469 + endloop + endfacet + facet normal 0.222845 0.419319 0.880064 + outer loop + vertex 1.1397 1.145 2.565 + vertex 1.13508 1.14842 2.56454 + vertex 1.13547 1.14302 2.56701 + endloop + endfacet + facet normal 0.939666 0.196182 0.280251 + outer loop + vertex 1.13508 1.14842 2.56454 + vertex 1.13458 1.1476 2.5668 + vertex 1.13547 1.14302 2.56701 + endloop + endfacet + facet normal 0.881769 0.192012 0.43083 + outer loop + vertex 1.13458 1.1476 2.5668 + vertex 1.13388 1.145 2.56938 + vertex 1.13547 1.14302 2.56701 + endloop + endfacet + facet normal 0.92979 0.10216 0.353628 + outer loop + vertex 1.13359 1.14961 2.5688 + vertex 1.13388 1.145 2.56938 + vertex 1.13458 1.1476 2.5668 + endloop + endfacet + facet normal 0.963834 0.0722736 -0.256516 + outer loop + vertex 1.135 1.15 2.56469 + vertex 1.135 1.1511 2.565 + vertex 1.13508 1.14842 2.56454 + endloop + endfacet + facet normal -0.724166 -0.136666 0.675949 + outer loop + vertex 1.13366 1.15255 2.56386 + vertex 1.13508 1.14842 2.56454 + vertex 1.135 1.1511 2.565 + endloop + endfacet + facet normal 0.947384 0.3177 -0.0391221 + outer loop + vertex 1.13366 1.15255 2.56386 + vertex 1.13382 1.15231 2.56568 + vertex 1.13508 1.14842 2.56454 + endloop + endfacet + facet normal 0.933047 0.217546 0.286525 + outer loop + vertex 1.13382 1.15231 2.56568 + vertex 1.13458 1.1476 2.5668 + vertex 1.13508 1.14842 2.56454 + endloop + endfacet + facet normal 0.944521 0.211141 0.251593 + outer loop + vertex 1.13382 1.15231 2.56568 + vertex 1.13359 1.14961 2.5688 + vertex 1.13458 1.1476 2.5668 + endloop + endfacet + facet normal 0.974991 0.127959 0.18171 + outer loop + vertex 1.13306 1.15436 2.56835 + vertex 1.13359 1.14961 2.5688 + vertex 1.13382 1.15231 2.56568 + endloop + endfacet + facet normal 0.95567 0.29123 -0.0433656 + outer loop + vertex 1.13217 1.15758 2.56468 + vertex 1.13382 1.15231 2.56568 + vertex 1.13366 1.15255 2.56386 + endloop + endfacet + facet normal 0.89433 0.204012 -0.398188 + outer loop + vertex 1.13305 1.15652 2.5661 + vertex 1.13382 1.15231 2.56568 + vertex 1.13217 1.15758 2.56468 + endloop + endfacet + facet normal 0.974392 0.164225 0.15359 + outer loop + vertex 1.13305 1.15652 2.5661 + vertex 1.13306 1.15436 2.56835 + vertex 1.13382 1.15231 2.56568 + endloop + endfacet + facet normal 0.963226 0.195768 0.184039 + outer loop + vertex 1.13236 1.15832 2.56775 + vertex 1.13306 1.15436 2.56835 + vertex 1.13305 1.15652 2.5661 + endloop + endfacet + facet normal 0.894145 0.323477 -0.309624 + outer loop + vertex 1.13217 1.15758 2.56468 + vertex 1.13186 1.15999 2.56631 + vertex 1.13305 1.15652 2.5661 + endloop + endfacet + facet normal 0.946423 0.320196 0.0419174 + outer loop + vertex 1.13305 1.15652 2.5661 + vertex 1.13186 1.15999 2.56631 + vertex 1.13236 1.15832 2.56775 + endloop + endfacet + facet normal 0.896669 0.433582 0.0893997 + outer loop + vertex 1.13475 1.88548 2.56031 + vertex 1.135 1.884 2.565 + vertex 1.135 1.885 2.56015 + endloop + endfacet + facet normal 0.308883 0.911498 0.271592 + outer loop + vertex 1.13475 1.88548 2.56031 + vertex 1.13375 1.88505 2.56291 + vertex 1.135 1.884 2.565 + endloop + endfacet + facet normal 0.891815 0.451395 0.0301409 + outer loop + vertex 1.135 1.88501 2.56 + vertex 1.13475 1.88548 2.56031 + vertex 1.135 1.885 2.56015 + endloop + endfacet + facet normal 0.515228 -0.271553 0.812895 + outer loop + vertex 1.135 1.88501 2.56 + vertex 1.13763 1.89 2.56 + vertex 1.13475 1.88548 2.56031 + endloop + endfacet + facet normal 0.273475 -0.107624 0.955839 + outer loop + vertex 1.13763 1.89 2.56 + vertex 1.13524 1.88898 2.56057 + vertex 1.13475 1.88548 2.56031 + endloop + endfacet + facet normal 0.929829 -0.15469 0.333901 + outer loop + vertex 1.13524 1.88898 2.56057 + vertex 1.13375 1.88505 2.56291 + vertex 1.13475 1.88548 2.56031 + endloop + endfacet + facet normal 0.917536 -0.123776 0.377898 + outer loop + vertex 1.13397 1.88907 2.56369 + vertex 1.13375 1.88505 2.56291 + vertex 1.13524 1.88898 2.56057 + endloop + endfacet + facet normal 0.236836 -0.0132639 0.971459 + outer loop + vertex 1.13763 1.89 2.56 + vertex 1.13791 1.895 2.56 + vertex 1.13524 1.88898 2.56057 + endloop + endfacet + facet normal 0.57414 -0.178984 0.798955 + outer loop + vertex 1.13791 1.895 2.56 + vertex 1.13578 1.89355 2.5612 + vertex 1.13524 1.88898 2.56057 + endloop + endfacet + facet normal 0.912325 -0.160121 0.376861 + outer loop + vertex 1.13578 1.89355 2.5612 + vertex 1.13397 1.88907 2.56369 + vertex 1.13524 1.88898 2.56057 + endloop + endfacet + facet normal 0.902547 -0.139136 0.407493 + outer loop + vertex 1.13429 1.89384 2.56461 + vertex 1.13397 1.88907 2.56369 + vertex 1.13578 1.89355 2.5612 + endloop + endfacet + facet normal 0.522064 -0.059509 0.850828 + outer loop + vertex 1.13791 1.895 2.56 + vertex 1.13848 1.9 2.56 + vertex 1.13578 1.89355 2.5612 + endloop + endfacet + facet normal 0.716017 -0.173238 0.676246 + outer loop + vertex 1.13848 1.9 2.56 + vertex 1.13627 1.89857 2.56197 + vertex 1.13578 1.89355 2.5612 + endloop + endfacet + facet normal 0.900687 -0.150326 0.407634 + outer loop + vertex 1.13627 1.89857 2.56197 + vertex 1.13429 1.89384 2.56461 + vertex 1.13578 1.89355 2.5612 + endloop + endfacet + facet normal 0.885881 -0.121732 0.447657 + outer loop + vertex 1.13446 1.89786 2.56536 + vertex 1.13429 1.89384 2.56461 + vertex 1.13627 1.89857 2.56197 + endloop + endfacet + facet normal 0.709518 -0.144752 0.68966 + outer loop + vertex 1.13848 1.9 2.56 + vertex 1.1395 1.905 2.56 + vertex 1.13627 1.89857 2.56197 + endloop + endfacet + facet normal 0.496629 0.0166505 0.867803 + outer loop + vertex 1.1395 1.905 2.56 + vertex 1.13706 1.90211 2.56145 + vertex 1.13627 1.89857 2.56197 + endloop + endfacet + facet normal 0.879907 -0.10166 0.464144 + outer loop + vertex 1.13446 1.89786 2.56536 + vertex 1.13546 1.90198 2.56438 + vertex 1.13356 1.90011 2.56756 + endloop + endfacet + facet normal 0.886148 -0.106279 0.451051 + outer loop + vertex 1.13446 1.89786 2.56536 + vertex 1.13627 1.89857 2.56197 + vertex 1.13546 1.90198 2.56438 + endloop + endfacet + facet normal 0.872908 -0.124112 0.471835 + outer loop + vertex 1.13627 1.89857 2.56197 + vertex 1.13706 1.90211 2.56145 + vertex 1.13546 1.90198 2.56438 + endloop + endfacet + facet normal 0.878099 -0.0899638 0.469946 + outer loop + vertex 1.13546 1.90198 2.56438 + vertex 1.13367 1.90416 2.56813 + vertex 1.13356 1.90011 2.56756 + endloop + endfacet + facet normal 0.469939 0.224613 0.853643 + outer loop + vertex 1.14 1.90606 2.56 + vertex 1.13954 1.90929 2.5594 + vertex 1.13766 1.90551 2.56143 + endloop + endfacet + facet normal 0.548328 -0.258624 0.795267 + outer loop + vertex 1.14 1.90606 2.56 + vertex 1.13766 1.90551 2.56143 + vertex 1.1395 1.905 2.56 + endloop + endfacet + facet normal 0.593993 -0.100815 0.798128 + outer loop + vertex 1.1395 1.905 2.56 + vertex 1.13766 1.90551 2.56143 + vertex 1.13706 1.90211 2.56145 + endloop + endfacet + facet normal 0.870029 -0.151792 0.469051 + outer loop + vertex 1.13706 1.90211 2.56145 + vertex 1.13766 1.90551 2.56143 + vertex 1.13546 1.90198 2.56438 + endloop + endfacet + facet normal 0.860332 -0.124674 0.494253 + outer loop + vertex 1.13766 1.90551 2.56143 + vertex 1.13559 1.90693 2.5654 + vertex 1.13546 1.90198 2.56438 + endloop + endfacet + facet normal 0.866701 -0.122629 0.48352 + outer loop + vertex 1.13559 1.90693 2.5654 + vertex 1.13367 1.90416 2.56813 + vertex 1.13546 1.90198 2.56438 + endloop + endfacet + facet normal 0.852547 -0.0804208 0.516426 + outer loop + vertex 1.13366 1.9087 2.56885 + vertex 1.13367 1.90416 2.56813 + vertex 1.13559 1.90693 2.5654 + endloop + endfacet + facet normal 0.85958 0.0285402 0.510204 + outer loop + vertex 1.13954 1.90929 2.5594 + vertex 1.13916 1.91294 2.55985 + vertex 1.13742 1.91072 2.56291 + endloop + endfacet + facet normal 0.827072 -0.11698 0.549788 + outer loop + vertex 1.13766 1.90551 2.56143 + vertex 1.13954 1.90929 2.5594 + vertex 1.13742 1.91072 2.56291 + endloop + endfacet + facet normal 0.867265 -0.097666 0.488172 + outer loop + vertex 1.13766 1.90551 2.56143 + vertex 1.13742 1.91072 2.56291 + vertex 1.13559 1.90693 2.5654 + endloop + endfacet + facet normal 0.868208 -0.0994654 0.48613 + outer loop + vertex 1.13742 1.91072 2.56291 + vertex 1.1354 1.91099 2.56657 + vertex 1.13559 1.90693 2.5654 + endloop + endfacet + facet normal 0.842284 -0.112527 0.527158 + outer loop + vertex 1.1354 1.91099 2.56657 + vertex 1.13366 1.9087 2.56885 + vertex 1.13559 1.90693 2.5654 + endloop + endfacet + facet normal 0.820169 -0.0532947 0.569633 + outer loop + vertex 1.13367 1.91324 2.56927 + vertex 1.13366 1.9087 2.56885 + vertex 1.1354 1.91099 2.56657 + endloop + endfacet + facet normal 0.895017 -0.104483 0.433622 + outer loop + vertex 1.13916 1.91294 2.55985 + vertex 1.13826 1.91501 2.5622 + vertex 1.13742 1.91072 2.56291 + endloop + endfacet + facet normal 0.865681 -0.101359 0.490228 + outer loop + vertex 1.13826 1.91501 2.5622 + vertex 1.13827 1.91918 2.56305 + vertex 1.13623 1.91548 2.56588 + endloop + endfacet + facet normal 0.867297 -0.0897671 0.48963 + outer loop + vertex 1.13826 1.91501 2.5622 + vertex 1.13623 1.91548 2.56588 + vertex 1.13742 1.91072 2.56291 + endloop + endfacet + facet normal 0.869631 -0.0869227 0.48599 + outer loop + vertex 1.13742 1.91072 2.56291 + vertex 1.13623 1.91548 2.56588 + vertex 1.1354 1.91099 2.56657 + endloop + endfacet + facet normal 0.815701 -0.0631608 0.575016 + outer loop + vertex 1.13623 1.91548 2.56588 + vertex 1.13367 1.91324 2.56927 + vertex 1.1354 1.91099 2.56657 + endloop + endfacet + facet normal 0.811402 -0.046785 0.582613 + outer loop + vertex 1.13385 1.91795 2.5694 + vertex 1.13367 1.91324 2.56927 + vertex 1.13623 1.91548 2.56588 + endloop + endfacet + facet normal 0.836504 -0.114005 0.535971 + outer loop + vertex 1.13827 1.91918 2.56305 + vertex 1.13849 1.92394 2.56371 + vertex 1.13613 1.9215 2.56687 + endloop + endfacet + facet normal 0.851819 -0.0718289 0.518888 + outer loop + vertex 1.13623 1.91548 2.56588 + vertex 1.13827 1.91918 2.56305 + vertex 1.13613 1.9215 2.56687 + endloop + endfacet + facet normal 0.795734 -0.086069 0.5995 + outer loop + vertex 1.13613 1.9215 2.56687 + vertex 1.13385 1.91795 2.5694 + vertex 1.13623 1.91548 2.56588 + endloop + endfacet + facet normal 0.773637 -0.0489798 0.631733 + outer loop + vertex 1.13375 1.92179 2.56981 + vertex 1.13385 1.91795 2.5694 + vertex 1.13613 1.9215 2.56687 + endloop + endfacet + facet normal 0.828379 -0.107627 0.549731 + outer loop + vertex 1.13849 1.92394 2.56371 + vertex 1.13879 1.92833 2.56412 + vertex 1.13706 1.92599 2.56627 + endloop + endfacet + facet normal 0.832654 -0.0986301 0.54494 + outer loop + vertex 1.13613 1.9215 2.56687 + vertex 1.13849 1.92394 2.56371 + vertex 1.13706 1.92599 2.56627 + endloop + endfacet + facet normal 0.652049 0.0087317 0.758127 + outer loop + vertex 1.13375 1.92179 2.56981 + vertex 1.13461 1.92591 2.56903 + vertex 1.13214 1.92345 2.57118 + endloop + endfacet + facet normal 0.774313 -0.0408756 0.631481 + outer loop + vertex 1.13375 1.92179 2.56981 + vertex 1.13613 1.9215 2.56687 + vertex 1.13461 1.92591 2.56903 + endloop + endfacet + facet normal 0.746901 -0.0651512 0.661736 + outer loop + vertex 1.13613 1.9215 2.56687 + vertex 1.13706 1.92599 2.56627 + vertex 1.13461 1.92591 2.56903 + endloop + endfacet + facet normal 0.604236 0.0863798 0.792109 + outer loop + vertex 1.13461 1.92591 2.56903 + vertex 1.13144 1.92693 2.57134 + vertex 1.13214 1.92345 2.57118 + endloop + endfacet + facet normal 0.79137 -0.0954744 0.603837 + outer loop + vertex 1.13879 1.92833 2.56412 + vertex 1.13872 1.93212 2.56482 + vertex 1.1368 1.92978 2.56696 + endloop + endfacet + facet normal 0.804822 -0.0522464 0.591213 + outer loop + vertex 1.13706 1.92599 2.56627 + vertex 1.13879 1.92833 2.56412 + vertex 1.1368 1.92978 2.56696 + endloop + endfacet + facet normal 0.74675 -0.06917 0.661498 + outer loop + vertex 1.13706 1.92599 2.56627 + vertex 1.1368 1.92978 2.56696 + vertex 1.13461 1.92591 2.56903 + endloop + endfacet + facet normal 0.674428 0.0127748 0.73823 + outer loop + vertex 1.1368 1.92978 2.56696 + vertex 1.13398 1.93134 2.56951 + vertex 1.13461 1.92591 2.56903 + endloop + endfacet + facet normal 0.587742 -0.0034634 0.809041 + outer loop + vertex 1.13398 1.93134 2.56951 + vertex 1.13144 1.92693 2.57134 + vertex 1.13461 1.92591 2.56903 + endloop + endfacet + facet normal 0.451729 0.106953 0.885721 + outer loop + vertex 1.13044 1.93101 2.57135 + vertex 1.13144 1.92693 2.57134 + vertex 1.13398 1.93134 2.56951 + endloop + endfacet + facet normal 0.760167 -0.0284057 0.649106 + outer loop + vertex 1.13872 1.93212 2.56482 + vertex 1.13689 1.93425 2.56705 + vertex 1.1368 1.92978 2.56696 + endloop + endfacet + facet normal 0.544024 0.000363354 0.839069 + outer loop + vertex 1.13689 1.93425 2.56705 + vertex 1.13745 1.93807 2.56669 + vertex 1.13391 1.93709 2.56898 + endloop + endfacet + facet normal 0.594964 0.0803779 0.799723 + outer loop + vertex 1.13689 1.93425 2.56705 + vertex 1.13391 1.93709 2.56898 + vertex 1.13398 1.93134 2.56951 + endloop + endfacet + facet normal 0.661599 -0.0284574 0.749317 + outer loop + vertex 1.13689 1.93425 2.56705 + vertex 1.13398 1.93134 2.56951 + vertex 1.1368 1.92978 2.56696 + endloop + endfacet + facet normal 0.552213 0.0825945 0.829601 + outer loop + vertex 1.13398 1.93134 2.56951 + vertex 1.13391 1.93709 2.56898 + vertex 1.13232 1.93367 2.57038 + endloop + endfacet + facet normal 0.462356 -0.00255216 0.886691 + outer loop + vertex 1.13398 1.93134 2.56951 + vertex 1.13232 1.93367 2.57038 + vertex 1.13044 1.93101 2.57135 + endloop + endfacet + facet normal 0.540508 0.0179504 0.841148 + outer loop + vertex 1.13745 1.93807 2.56669 + vertex 1.13686 1.94158 2.56699 + vertex 1.13391 1.93709 2.56898 + endloop + endfacet + facet normal 0.41435 0.127428 0.901153 + outer loop + vertex 1.13391 1.93709 2.56898 + vertex 1.13686 1.94158 2.56699 + vertex 1.13323 1.94257 2.56852 + endloop + endfacet + facet normal 0.406668 0.0860319 0.909516 + outer loop + vertex 1.13686 1.94158 2.56699 + vertex 1.13645 1.94604 2.56675 + vertex 1.13323 1.94257 2.56852 + endloop + endfacet + facet normal 0.328264 0.168919 0.92936 + outer loop + vertex 1.13323 1.94257 2.56852 + vertex 1.13645 1.94604 2.56675 + vertex 1.13252 1.94702 2.56796 + endloop + endfacet + facet normal 0.319801 0.122265 0.939563 + outer loop + vertex 1.13645 1.94604 2.56675 + vertex 1.13568 1.95045 2.56644 + vertex 1.13252 1.94702 2.56796 + endloop + endfacet + facet normal 0.331097 0.175388 0.927154 + outer loop + vertex 1.13837 1.95333 2.56493 + vertex 1.13509 1.95485 2.56582 + vertex 1.13568 1.95045 2.56644 + endloop + endfacet + facet normal 0.270509 0.194224 0.942922 + outer loop + vertex 1.13951 2.08848 2.53553 + vertex 1.1397 2.0927 2.5346 + vertex 1.1366 2.09043 2.53596 + endloop + endfacet + facet normal 0.273034 0.198335 0.941337 + outer loop + vertex 1.1366 2.09043 2.53596 + vertex 1.13659 2.08568 2.53696 + vertex 1.13951 2.08848 2.53553 + endloop + endfacet + facet normal 0.322576 0.195068 0.926225 + outer loop + vertex 1.1366 2.09043 2.53596 + vertex 1.13249 2.09062 2.53735 + vertex 1.13659 2.08568 2.53696 + endloop + endfacet + facet normal 0.286601 0.163792 0.943945 + outer loop + vertex 1.13249 2.09062 2.53735 + vertex 1.13226 2.08595 2.53823 + vertex 1.13659 2.08568 2.53696 + endloop + endfacet + facet normal 0.295918 0.196854 0.934709 + outer loop + vertex 1.1397 2.0927 2.5346 + vertex 1.1377 2.09821 2.53408 + vertex 1.13512 2.09451 2.53567 + endloop + endfacet + facet normal 0.287439 0.170835 0.942441 + outer loop + vertex 1.1366 2.09043 2.53596 + vertex 1.1397 2.0927 2.5346 + vertex 1.13512 2.09451 2.53567 + endloop + endfacet + facet normal 0.322839 0.182672 0.928658 + outer loop + vertex 1.13512 2.09451 2.53567 + vertex 1.13249 2.09062 2.53735 + vertex 1.1366 2.09043 2.53596 + endloop + endfacet + facet normal 0.345017 0.165597 0.923873 + outer loop + vertex 1.13077 2.09651 2.53694 + vertex 1.13249 2.09062 2.53735 + vertex 1.13512 2.09451 2.53567 + endloop + endfacet + facet normal 0.324104 0.175073 0.929681 + outer loop + vertex 1.13384 2.09847 2.53537 + vertex 1.13512 2.09451 2.53567 + vertex 1.1377 2.09821 2.53408 + endloop + endfacet + facet normal 0.324116 0.180974 0.928546 + outer loop + vertex 1.13384 2.09847 2.53537 + vertex 1.1377 2.09821 2.53408 + vertex 1.13445 2.10252 2.53437 + endloop + endfacet + facet normal 0.338105 0.192008 0.921313 + outer loop + vertex 1.13445 2.10252 2.53437 + vertex 1.1377 2.09821 2.53408 + vertex 1.13781 2.10191 2.53326 + endloop + endfacet + facet normal 0.351339 0.183017 0.918186 + outer loop + vertex 1.13512 2.09451 2.53567 + vertex 1.13384 2.09847 2.53537 + vertex 1.13077 2.09651 2.53694 + endloop + endfacet + facet normal 0.337638 0.187399 0.922433 + outer loop + vertex 1.13781 2.10191 2.53326 + vertex 1.13774 2.10577 2.53251 + vertex 1.13445 2.10252 2.53437 + endloop + endfacet + facet normal 0.349719 0.174111 0.920534 + outer loop + vertex 1.13445 2.10252 2.53437 + vertex 1.13774 2.10577 2.53251 + vertex 1.13282 2.10818 2.53392 + endloop + endfacet + facet normal 0.356179 0.190701 0.914751 + outer loop + vertex 1.13774 2.10577 2.53251 + vertex 1.13594 2.11149 2.53201 + vertex 1.13282 2.10818 2.53392 + endloop + endfacet + facet normal 0.371335 0.174781 0.9119 + outer loop + vertex 1.13282 2.10818 2.53392 + vertex 1.13594 2.11149 2.53201 + vertex 1.13281 2.11202 2.53319 + endloop + endfacet + facet normal 0.363693 0.167314 0.91637 + outer loop + vertex 1.13894 2.11348 2.53042 + vertex 1.13953 2.11757 2.52944 + vertex 1.13649 2.11559 2.531 + endloop + endfacet + facet normal 0.369577 0.175188 0.912536 + outer loop + vertex 1.13649 2.11559 2.531 + vertex 1.13594 2.11149 2.53201 + vertex 1.13894 2.11348 2.53042 + endloop + endfacet + facet normal 0.374006 0.174194 0.91092 + outer loop + vertex 1.13649 2.11559 2.531 + vertex 1.13274 2.11586 2.53249 + vertex 1.13594 2.11149 2.53201 + endloop + endfacet + facet normal 0.371087 0.171875 0.912553 + outer loop + vertex 1.13274 2.11586 2.53249 + vertex 1.13281 2.11202 2.53319 + vertex 1.13594 2.11149 2.53201 + endloop + endfacet + facet normal 0.373357 0.158615 0.914027 + outer loop + vertex 1.13953 2.11757 2.52944 + vertex 1.13775 2.12336 2.52916 + vertex 1.13527 2.11957 2.53083 + endloop + endfacet + facet normal 0.371749 0.154224 0.915433 + outer loop + vertex 1.13649 2.11559 2.531 + vertex 1.13953 2.11757 2.52944 + vertex 1.13527 2.11957 2.53083 + endloop + endfacet + facet normal 0.373987 0.154865 0.914413 + outer loop + vertex 1.13527 2.11957 2.53083 + vertex 1.13274 2.11586 2.53249 + vertex 1.13649 2.11559 2.531 + endloop + endfacet + facet normal 0.343805 0.178834 0.921855 + outer loop + vertex 1.13085 2.12138 2.53213 + vertex 1.13274 2.11586 2.53249 + vertex 1.13527 2.11957 2.53083 + endloop + endfacet + facet normal 0.358993 0.169665 0.91779 + outer loop + vertex 1.13385 2.12351 2.53065 + vertex 1.13527 2.11957 2.53083 + vertex 1.13775 2.12336 2.52916 + endloop + endfacet + facet normal 0.355838 0.244362 0.902035 + outer loop + vertex 1.13385 2.12351 2.53065 + vertex 1.13775 2.12336 2.52916 + vertex 1.13384 2.1278 2.5295 + endloop + endfacet + facet normal 0.267122 0.162339 0.94989 + outer loop + vertex 1.13384 2.1278 2.5295 + vertex 1.13775 2.12336 2.52916 + vertex 1.13768 2.12722 2.52852 + endloop + endfacet + facet normal 0.338638 0.162735 0.926737 + outer loop + vertex 1.13527 2.11957 2.53083 + vertex 1.13385 2.12351 2.53065 + vertex 1.13085 2.12138 2.53213 + endloop + endfacet + facet normal 0.271795 0.211931 0.938729 + outer loop + vertex 1.13768 2.12722 2.52852 + vertex 1.13788 2.13066 2.52768 + vertex 1.13384 2.1278 2.5295 + endloop + endfacet + facet normal 0.210828 0.293835 0.932316 + outer loop + vertex 1.13384 2.1278 2.5295 + vertex 1.13788 2.13066 2.52768 + vertex 1.13384 2.13218 2.52812 + endloop + endfacet + facet normal 0.217412 0.313722 0.924289 + outer loop + vertex 1.13788 2.13066 2.52768 + vertex 1.13621 2.13482 2.52666 + vertex 1.13384 2.13218 2.52812 + endloop + endfacet + facet normal 0.0413144 0.452618 0.890747 + outer loop + vertex 1.13384 2.13218 2.52812 + vertex 1.13621 2.13482 2.52666 + vertex 1.132 2.13516 2.52669 + endloop + endfacet + facet normal 0.00485865 0.570363 0.821378 + outer loop + vertex 1.13427 2.13828 2.52448 + vertex 1.13833 2.13734 2.52511 + vertex 1.13783 2.14048 2.52293 + endloop + endfacet + facet normal -0.0789321 0.656226 0.750425 + outer loop + vertex 1.13429 2.14061 2.52245 + vertex 1.13427 2.13828 2.52448 + vertex 1.13783 2.14048 2.52293 + endloop + endfacet + facet normal 0.0489225 0.552836 0.831853 + outer loop + vertex 1.13621 2.13482 2.52666 + vertex 1.13427 2.13828 2.52448 + vertex 1.132 2.13516 2.52669 + endloop + endfacet + facet normal -0.00843474 0.530658 0.847544 + outer loop + vertex 1.13833 2.13734 2.52511 + vertex 1.13427 2.13828 2.52448 + vertex 1.13621 2.13482 2.52666 + endloop + endfacet + facet normal -0.459478 0.725065 0.512992 + outer loop + vertex 1.13542 2.14686 2.51508 + vertex 1.13294 2.14654 2.5133 + vertex 1.13394 2.14489 2.51654 + endloop + endfacet + facet normal -0.370646 0.716232 0.591298 + outer loop + vertex 1.13777 2.14625 2.51729 + vertex 1.13542 2.14686 2.51508 + vertex 1.13394 2.14489 2.51654 + endloop + endfacet + facet normal -0.358815 0.627671 0.690855 + outer loop + vertex 1.13777 2.14625 2.51729 + vertex 1.13394 2.14489 2.51654 + vertex 1.13893 2.14392 2.52001 + endloop + endfacet + facet normal -0.245361 0.783015 0.571565 + outer loop + vertex 1.13893 2.14392 2.52001 + vertex 1.13394 2.14489 2.51654 + vertex 1.13416 2.14234 2.52012 + endloop + endfacet + facet normal -0.0529124 0.79903 0.598958 + outer loop + vertex 1.13783 2.14048 2.52293 + vertex 1.13416 2.14234 2.52012 + vertex 1.13429 2.14061 2.52245 + endloop + endfacet + facet normal -0.204985 0.671122 0.712444 + outer loop + vertex 1.13893 2.14392 2.52001 + vertex 1.13416 2.14234 2.52012 + vertex 1.13783 2.14048 2.52293 + endloop + endfacet + facet normal 0.0590903 -0.123654 0.990564 + outer loop + vertex 1.13773 2.15259 2.50962 + vertex 1.13636 2.155 2.51 + vertex 1.135 2.15435 2.51 + endloop + endfacet + facet normal 0.543273 0.766865 0.34172 + outer loop + vertex 1.13773 2.15259 2.50962 + vertex 1.135 2.15435 2.51 + vertex 1.13862 2.15076 2.51232 + endloop + endfacet + facet normal -0.189028 0.390203 0.901116 + outer loop + vertex 1.13862 2.15076 2.51232 + vertex 1.135 2.15435 2.51 + vertex 1.13502 2.14869 2.51246 + endloop + endfacet + facet normal -0.480476 0.683249 0.54983 + outer loop + vertex 1.13542 2.14686 2.51508 + vertex 1.13502 2.14869 2.51246 + vertex 1.13294 2.14654 2.5133 + endloop + endfacet + facet normal -0.360994 0.738167 0.569906 + outer loop + vertex 1.13542 2.14686 2.51508 + vertex 1.13855 2.1482 2.51532 + vertex 1.13502 2.14869 2.51246 + endloop + endfacet + facet normal -0.383757 0.708111 0.592713 + outer loop + vertex 1.13855 2.1482 2.51532 + vertex 1.13862 2.15076 2.51232 + vertex 1.13502 2.14869 2.51246 + endloop + endfacet + facet normal -0.358406 0.729892 0.582068 + outer loop + vertex 1.13855 2.1482 2.51532 + vertex 1.13542 2.14686 2.51508 + vertex 1.13777 2.14625 2.51729 + endloop + endfacet + facet normal 0.408933 0.483793 0.773769 + outer loop + vertex 1.14 2.15992 2.505 + vertex 1.13636 2.155 2.51 + vertex 1.14011 2.15421 2.50851 + endloop + endfacet + facet normal -0.876908 0.42953 -0.215725 + outer loop + vertex 1.13759 2.155 2.505 + vertex 1.13636 2.155 2.51 + vertex 1.14 2.15992 2.505 + endloop + endfacet + facet normal 0.380549 0.0694915 0.922146 + outer loop + vertex 1.14011 2.15421 2.50851 + vertex 1.13636 2.155 2.51 + vertex 1.13773 2.15259 2.50962 + endloop + endfacet + facet normal -0.838187 -0.5396 0.0792128 + outer loop + vertex 1.14436 0.867516 2.50188 + vertex 1.14258 0.87 2.5 + vertex 1.145 0.866241 2.5 + endloop + endfacet + facet normal -0.764796 -0.633976 -0.114727 + outer loop + vertex 1.14183 0.87 2.505 + vertex 1.14258 0.87 2.5 + vertex 1.14436 0.867516 2.50188 + endloop + endfacet + facet normal -0.561365 -0.806112 0.187225 + outer loop + vertex 1.14388 0.868494 2.50466 + vertex 1.14183 0.87 2.505 + vertex 1.14436 0.867516 2.50188 + endloop + endfacet + facet normal -0.567516 -0.807974 0.158439 + outer loop + vertex 1.14221 0.869962 2.50617 + vertex 1.14183 0.87 2.505 + vertex 1.14388 0.868494 2.50466 + endloop + endfacet + facet normal -0.382998 -0.837284 0.390215 + outer loop + vertex 1.14388 0.868494 2.50466 + vertex 1.14542 0.869234 2.50776 + vertex 1.14221 0.869962 2.50617 + endloop + endfacet + facet normal -0.546697 -0.823576 0.151146 + outer loop + vertex 1.14183 0.87 2.505 + vertex 1.14221 0.869962 2.50617 + vertex 1.13932 0.871891 2.50622 + endloop + endfacet + facet normal -0.29649 -0.763084 0.574279 + outer loop + vertex 1.14 0.870711 2.505 + vertex 1.14183 0.87 2.505 + vertex 1.13932 0.871891 2.50622 + endloop + endfacet + facet normal -0.388526 -0.82718 0.405981 + outer loop + vertex 1.14221 0.869962 2.50617 + vertex 1.14542 0.869234 2.50776 + vertex 1.14223 0.871682 2.50969 + endloop + endfacet + facet normal -0.509195 -0.772392 0.379647 + outer loop + vertex 1.14221 0.869962 2.50617 + vertex 1.14223 0.871682 2.50969 + vertex 1.13932 0.871891 2.50622 + endloop + endfacet + facet normal -0.420248 -0.856344 0.300112 + outer loop + vertex 1.13932 0.871891 2.50622 + vertex 1.14223 0.871682 2.50969 + vertex 1.13842 0.873347 2.50911 + endloop + endfacet + facet normal -0.418106 -0.819212 0.392529 + outer loop + vertex 1.14223 0.871682 2.50969 + vertex 1.13886 0.874743 2.51249 + vertex 1.13842 0.873347 2.50911 + endloop + endfacet + facet normal -0.354449 -0.812903 0.46212 + outer loop + vertex 1.14442 0.873227 2.51409 + vertex 1.13886 0.874743 2.51249 + vertex 1.14223 0.871682 2.50969 + endloop + endfacet + facet normal -0.360924 -0.771429 0.524053 + outer loop + vertex 1.13886 0.874743 2.51249 + vertex 1.14442 0.873227 2.51409 + vertex 1.14233 0.876092 2.51687 + endloop + endfacet + facet normal -0.274417 -0.835911 0.47534 + outer loop + vertex 1.13794 0.876915 2.51578 + vertex 1.13886 0.874743 2.51249 + vertex 1.14233 0.876092 2.51687 + endloop + endfacet + facet normal -0.2883 -0.746991 0.599072 + outer loop + vertex 1.14233 0.876092 2.51687 + vertex 1.13808 0.879038 2.5185 + vertex 1.13794 0.876915 2.51578 + endloop + endfacet + facet normal -0.244521 -0.714931 0.655044 + outer loop + vertex 1.14288 0.878383 2.51957 + vertex 1.13808 0.879038 2.5185 + vertex 1.14233 0.876092 2.51687 + endloop + endfacet + facet normal -0.251045 -0.625802 0.738477 + outer loop + vertex 1.13808 0.879038 2.5185 + vertex 1.14288 0.878383 2.51957 + vertex 1.14157 0.880912 2.52127 + endloop + endfacet + facet normal -0.157857 -0.714727 0.681356 + outer loop + vertex 1.13802 0.881717 2.52129 + vertex 1.13808 0.879038 2.5185 + vertex 1.14157 0.880912 2.52127 + endloop + endfacet + facet normal -0.121024 -0.556217 0.822177 + outer loop + vertex 1.14157 0.880912 2.52127 + vertex 1.14024 0.884424 2.52345 + vertex 1.13802 0.881717 2.52129 + endloop + endfacet + facet normal 0.065912 -0.508142 0.858748 + outer loop + vertex 1.14536 0.883701 2.52263 + vertex 1.14024 0.884424 2.52345 + vertex 1.14157 0.880912 2.52127 + endloop + endfacet + facet normal 0.0156481 -0.51514 0.856963 + outer loop + vertex 1.14035 0.887745 2.52545 + vertex 1.13628 0.886574 2.52482 + vertex 1.14024 0.884424 2.52345 + endloop + endfacet + facet normal 0.250869 -0.504596 0.826104 + outer loop + vertex 1.14035 0.887745 2.52545 + vertex 1.14024 0.884424 2.52345 + vertex 1.14423 0.888522 2.52475 + endloop + endfacet + facet normal 0.0936126 -0.38126 0.919716 + outer loop + vertex 1.14423 0.888522 2.52475 + vertex 1.14024 0.884424 2.52345 + vertex 1.14536 0.883701 2.52263 + endloop + endfacet + facet normal -0.000411954 -0.472358 0.881407 + outer loop + vertex 1.14035 0.887745 2.52545 + vertex 1.13902 0.890185 2.52675 + vertex 1.13628 0.886574 2.52482 + endloop + endfacet + facet normal 0.244282 -0.435388 0.866466 + outer loop + vertex 1.14423 0.888522 2.52475 + vertex 1.14207 0.890244 2.52622 + vertex 1.14035 0.887745 2.52545 + endloop + endfacet + facet normal 0.166358 -0.393405 0.904189 + outer loop + vertex 1.14207 0.890244 2.52622 + vertex 1.13902 0.890185 2.52675 + vertex 1.14035 0.887745 2.52545 + endloop + endfacet + facet normal 0.172169 -0.248451 0.953221 + outer loop + vertex 1.14207 0.890244 2.52622 + vertex 1.14228 0.893473 2.52702 + vertex 1.13902 0.890185 2.52675 + endloop + endfacet + facet normal 0.242284 -0.315089 0.917615 + outer loop + vertex 1.14228 0.893473 2.52702 + vertex 1.13873 0.894179 2.5282 + vertex 1.13902 0.890185 2.52675 + endloop + endfacet + facet normal 0.27808 -0.178835 0.943763 + outer loop + vertex 1.14228 0.893473 2.52702 + vertex 1.14348 0.89867 2.52765 + vertex 1.13873 0.894179 2.5282 + endloop + endfacet + facet normal 0.347897 -0.25783 0.901383 + outer loop + vertex 1.13873 0.894179 2.5282 + vertex 1.14348 0.89867 2.52765 + vertex 1.13866 0.899085 2.52963 + endloop + endfacet + facet normal 0.31681 -0.171259 0.9329 + outer loop + vertex 1.14349 0.909253 2.52965 + vertex 1.14474 0.914423 2.53017 + vertex 1.14084 0.911481 2.53096 + endloop + endfacet + facet normal 0.38024 -0.170832 0.908974 + outer loop + vertex 1.13836 0.913804 2.53243 + vertex 1.1371 0.908357 2.53193 + vertex 1.14084 0.911481 2.53096 + endloop + endfacet + facet normal 0.313445 -0.166244 0.934941 + outer loop + vertex 1.14474 0.914423 2.53017 + vertex 1.14234 0.915339 2.53114 + vertex 1.14084 0.911481 2.53096 + endloop + endfacet + facet normal 0.367294 -0.186091 0.911299 + outer loop + vertex 1.14234 0.915339 2.53114 + vertex 1.13836 0.913804 2.53243 + vertex 1.14084 0.911481 2.53096 + endloop + endfacet + facet normal 0.380049 -0.232626 0.895236 + outer loop + vertex 1.14234 0.915339 2.53114 + vertex 1.14313 0.919244 2.53182 + vertex 1.13836 0.913804 2.53243 + endloop + endfacet + facet normal 0.330673 -0.186034 0.925228 + outer loop + vertex 1.14313 0.919244 2.53182 + vertex 1.13848 0.9192 2.53347 + vertex 1.13836 0.913804 2.53243 + endloop + endfacet + facet normal 0.328634 -0.219471 0.918603 + outer loop + vertex 1.14313 0.919244 2.53182 + vertex 1.14321 0.924124 2.53296 + vertex 1.13848 0.9192 2.53347 + endloop + endfacet + facet normal 0.29031 -0.180496 0.939756 + outer loop + vertex 1.13848 0.9192 2.53347 + vertex 1.14321 0.924124 2.53296 + vertex 1.13843 0.924396 2.53448 + endloop + endfacet + facet normal 0.287309 -0.20728 0.935141 + outer loop + vertex 1.14321 0.924124 2.53296 + vertex 1.14348 0.929045 2.53396 + vertex 1.13843 0.924396 2.53448 + endloop + endfacet + facet normal 0.255272 -0.17057 0.951705 + outer loop + vertex 1.13843 0.924396 2.53448 + vertex 1.14348 0.929045 2.53396 + vertex 1.13964 0.929496 2.53507 + endloop + endfacet + facet normal 0.248903 -0.118516 0.96125 + outer loop + vertex 1.14215 1.04839 2.56166 + vertex 1.14225 1.05292 2.56219 + vertex 1.13821 1.04853 2.56269 + endloop + endfacet + facet normal 0.298497 -0.166676 0.939744 + outer loop + vertex 1.13821 1.04853 2.56269 + vertex 1.14225 1.05292 2.56219 + vertex 1.13819 1.05357 2.56359 + endloop + endfacet + facet normal 0.3071 -0.121959 0.94383 + outer loop + vertex 1.14225 1.05292 2.56219 + vertex 1.14231 1.05804 2.56283 + vertex 1.13819 1.05357 2.56359 + endloop + endfacet + facet normal 0.375603 -0.191408 0.906799 + outer loop + vertex 1.13819 1.05357 2.56359 + vertex 1.14231 1.05804 2.56283 + vertex 1.13836 1.05888 2.56464 + endloop + endfacet + facet normal 0.371765 -0.210792 0.904078 + outer loop + vertex 1.13914 1.06299 2.56528 + vertex 1.13685 1.06096 2.56575 + vertex 1.13836 1.05888 2.56464 + endloop + endfacet + facet normal 0.484474 -0.223163 0.845862 + outer loop + vertex 1.13914 1.06299 2.56528 + vertex 1.13836 1.05888 2.56464 + vertex 1.14232 1.06369 2.56364 + endloop + endfacet + facet normal 0.390285 -0.132029 0.911178 + outer loop + vertex 1.14232 1.06369 2.56364 + vertex 1.13836 1.05888 2.56464 + vertex 1.14231 1.05804 2.56283 + endloop + endfacet + facet normal 0.33059 -0.157858 0.930479 + outer loop + vertex 1.13914 1.06299 2.56528 + vertex 1.13693 1.06394 2.56623 + vertex 1.13685 1.06096 2.56575 + endloop + endfacet + facet normal 0.525615 -0.0904511 0.845901 + outer loop + vertex 1.14232 1.06369 2.56364 + vertex 1.14324 1.06938 2.56368 + vertex 1.1401 1.06676 2.56535 + endloop + endfacet + facet normal 0.477076 -0.137835 0.867986 + outer loop + vertex 1.13914 1.06299 2.56528 + vertex 1.14232 1.06369 2.56364 + vertex 1.1401 1.06676 2.56535 + endloop + endfacet + facet normal 0.352201 -0.107185 0.929767 + outer loop + vertex 1.1401 1.06676 2.56535 + vertex 1.13693 1.06394 2.56623 + vertex 1.13914 1.06299 2.56528 + endloop + endfacet + facet normal 0.358954 -0.115923 0.926128 + outer loop + vertex 1.13706 1.06802 2.56669 + vertex 1.13693 1.06394 2.56623 + vertex 1.1401 1.06676 2.56535 + endloop + endfacet + facet normal 0.548538 -0.0423294 0.835053 + outer loop + vertex 1.14324 1.06938 2.56368 + vertex 1.14348 1.07445 2.56378 + vertex 1.1405 1.07149 2.56559 + endloop + endfacet + facet normal 0.523302 -0.0865154 0.847744 + outer loop + vertex 1.1401 1.06676 2.56535 + vertex 1.14324 1.06938 2.56368 + vertex 1.1405 1.07149 2.56559 + endloop + endfacet + facet normal 0.37386 -0.0780891 0.924192 + outer loop + vertex 1.1405 1.07149 2.56559 + vertex 1.13706 1.06802 2.56669 + vertex 1.1401 1.06676 2.56535 + endloop + endfacet + facet normal 0.398465 -0.106628 0.910964 + outer loop + vertex 1.13715 1.0728 2.56721 + vertex 1.13706 1.06802 2.56669 + vertex 1.1405 1.07149 2.56559 + endloop + endfacet + facet normal 0.584801 -0.00637798 0.811152 + outer loop + vertex 1.14348 1.07445 2.56378 + vertex 1.1435 1.07947 2.5638 + vertex 1.1406 1.07645 2.56588 + endloop + endfacet + facet normal 0.559767 -0.0588501 0.826558 + outer loop + vertex 1.1405 1.07149 2.56559 + vertex 1.14348 1.07445 2.56378 + vertex 1.1406 1.07645 2.56588 + endloop + endfacet + facet normal 0.414938 -0.060525 0.907834 + outer loop + vertex 1.1406 1.07645 2.56588 + vertex 1.13715 1.0728 2.56721 + vertex 1.1405 1.07149 2.56559 + endloop + endfacet + facet normal 0.453891 -0.105667 0.88477 + outer loop + vertex 1.13719 1.07795 2.5678 + vertex 1.13715 1.0728 2.56721 + vertex 1.1406 1.07645 2.56588 + endloop + endfacet + facet normal 0.636703 0.0198876 0.770853 + outer loop + vertex 1.1435 1.07947 2.5638 + vertex 1.14352 1.08465 2.56366 + vertex 1.14061 1.08159 2.56614 + endloop + endfacet + facet normal 0.608631 -0.0421422 0.792333 + outer loop + vertex 1.1406 1.07645 2.56588 + vertex 1.1435 1.07947 2.5638 + vertex 1.14061 1.08159 2.56614 + endloop + endfacet + facet normal 0.476271 -0.0462024 0.878084 + outer loop + vertex 1.14061 1.08159 2.56614 + vertex 1.13719 1.07795 2.5678 + vertex 1.1406 1.07645 2.56588 + endloop + endfacet + facet normal 0.527795 -0.110893 0.842102 + outer loop + vertex 1.13721 1.08366 2.56854 + vertex 1.13719 1.07795 2.5678 + vertex 1.14061 1.08159 2.56614 + endloop + endfacet + facet normal 0.69375 0.0386294 0.719179 + outer loop + vertex 1.14352 1.08465 2.56366 + vertex 1.14344 1.08992 2.56345 + vertex 1.14072 1.08688 2.56623 + endloop + endfacet + facet normal 0.665434 -0.0276456 0.745945 + outer loop + vertex 1.14061 1.08159 2.56614 + vertex 1.14352 1.08465 2.56366 + vertex 1.14072 1.08688 2.56623 + endloop + endfacet + facet normal 0.566066 -0.0269488 0.82392 + outer loop + vertex 1.14072 1.08688 2.56623 + vertex 1.13721 1.08366 2.56854 + vertex 1.14061 1.08159 2.56614 + endloop + endfacet + facet normal 0.602201 -0.0881157 0.793467 + outer loop + vertex 1.13807 1.08933 2.56852 + vertex 1.13721 1.08366 2.56854 + vertex 1.14072 1.08688 2.56623 + endloop + endfacet + facet normal 0.737817 0.0683584 0.67153 + outer loop + vertex 1.14344 1.08992 2.56345 + vertex 1.14321 1.09512 2.56317 + vertex 1.14081 1.09211 2.56612 + endloop + endfacet + facet normal 0.713587 0.00388665 0.700556 + outer loop + vertex 1.14072 1.08688 2.56623 + vertex 1.14344 1.08992 2.56345 + vertex 1.14081 1.09211 2.56612 + endloop + endfacet + facet normal 0.655886 0.00609764 0.754836 + outer loop + vertex 1.14081 1.09211 2.56612 + vertex 1.13807 1.08933 2.56852 + vertex 1.14072 1.08688 2.56623 + endloop + endfacet + facet normal 0.668305 -0.0157938 0.74372 + outer loop + vertex 1.1382 1.09443 2.56851 + vertex 1.13807 1.08933 2.56852 + vertex 1.14081 1.09211 2.56612 + endloop + endfacet + facet normal 0.769377 0.0691653 0.63504 + outer loop + vertex 1.14321 1.09512 2.56317 + vertex 1.14312 1.10003 2.56275 + vertex 1.14083 1.0973 2.56582 + endloop + endfacet + facet normal 0.756995 0.0344002 0.652515 + outer loop + vertex 1.14081 1.09211 2.56612 + vertex 1.14321 1.09512 2.56317 + vertex 1.14083 1.0973 2.56582 + endloop + endfacet + facet normal 0.693773 0.0383177 0.719174 + outer loop + vertex 1.14083 1.0973 2.56582 + vertex 1.1382 1.09443 2.56851 + vertex 1.14081 1.09211 2.56612 + endloop + endfacet + facet normal 0.705049 0.0184123 0.708919 + outer loop + vertex 1.13821 1.09961 2.56837 + vertex 1.1382 1.09443 2.56851 + vertex 1.14083 1.0973 2.56582 + endloop + endfacet + facet normal 0.789663 0.0552729 0.611045 + outer loop + vertex 1.14312 1.10003 2.56275 + vertex 1.14332 1.10382 2.56214 + vertex 1.14108 1.10296 2.56511 + endloop + endfacet + facet normal 0.782619 0.0423011 0.621063 + outer loop + vertex 1.14083 1.0973 2.56582 + vertex 1.14312 1.10003 2.56275 + vertex 1.14108 1.10296 2.56511 + endloop + endfacet + facet normal 0.719952 0.054077 0.691914 + outer loop + vertex 1.14108 1.10296 2.56511 + vertex 1.13821 1.09961 2.56837 + vertex 1.14083 1.0973 2.56582 + endloop + endfacet + facet normal 0.739326 0.0191516 0.673075 + outer loop + vertex 1.13816 1.10489 2.56827 + vertex 1.13821 1.09961 2.56837 + vertex 1.14108 1.10296 2.56511 + endloop + endfacet + facet normal 0.859231 0.113832 0.498763 + outer loop + vertex 1.14414 1.10622 2.56041 + vertex 1.14397 1.10995 2.55985 + vertex 1.14281 1.10715 2.56249 + endloop + endfacet + facet normal 0.855289 0.0779219 0.512258 + outer loop + vertex 1.14332 1.10382 2.56214 + vertex 1.14414 1.10622 2.56041 + vertex 1.14281 1.10715 2.56249 + endloop + endfacet + facet normal 0.789274 0.0573727 0.611355 + outer loop + vertex 1.14332 1.10382 2.56214 + vertex 1.14281 1.10715 2.56249 + vertex 1.14108 1.10296 2.56511 + endloop + endfacet + facet normal 0.791892 0.0543421 0.608239 + outer loop + vertex 1.14108 1.10296 2.56511 + vertex 1.14281 1.10715 2.56249 + vertex 1.14059 1.10835 2.56527 + endloop + endfacet + facet normal 0.747381 0.0486201 0.662614 + outer loop + vertex 1.14059 1.10835 2.56527 + vertex 1.13816 1.10489 2.56827 + vertex 1.14108 1.10296 2.56511 + endloop + endfacet + facet normal 0.757026 0.0331023 0.652545 + outer loop + vertex 1.13805 1.11009 2.56813 + vertex 1.13816 1.10489 2.56827 + vertex 1.14059 1.10835 2.56527 + endloop + endfacet + facet normal 0.85146 0.315607 -0.418817 + outer loop + vertex 1.145 1.11009 2.555 + vertex 1.14318 1.115 2.555 + vertex 1.145 1.115 2.5587 + endloop + endfacet + facet normal 0.870339 0.127718 0.475603 + outer loop + vertex 1.14397 1.10995 2.55985 + vertex 1.14356 1.11452 2.55937 + vertex 1.14243 1.11179 2.56217 + endloop + endfacet + facet normal 0.865013 0.103978 0.490857 + outer loop + vertex 1.14281 1.10715 2.56249 + vertex 1.14397 1.10995 2.55985 + vertex 1.14243 1.11179 2.56217 + endloop + endfacet + facet normal 0.799064 0.105596 0.591901 + outer loop + vertex 1.14281 1.10715 2.56249 + vertex 1.14243 1.11179 2.56217 + vertex 1.14059 1.10835 2.56527 + endloop + endfacet + facet normal 0.809433 0.089611 0.580334 + outer loop + vertex 1.14243 1.11179 2.56217 + vertex 1.14027 1.11343 2.56493 + vertex 1.14059 1.10835 2.56527 + endloop + endfacet + facet normal 0.771213 0.0905643 0.630102 + outer loop + vertex 1.14027 1.11343 2.56493 + vertex 1.13805 1.11009 2.56813 + vertex 1.14059 1.10835 2.56527 + endloop + endfacet + facet normal 0.792155 0.0552908 0.60781 + outer loop + vertex 1.13802 1.11507 2.56772 + vertex 1.13805 1.11009 2.56813 + vertex 1.14027 1.11343 2.56493 + endloop + endfacet + facet normal 0.834189 0.0563009 0.548597 + outer loop + vertex 1.14356 1.11452 2.55937 + vertex 1.1435 1.11863 2.55904 + vertex 1.14202 1.11758 2.56141 + endloop + endfacet + facet normal 0.871745 0.125187 0.473698 + outer loop + vertex 1.14243 1.11179 2.56217 + vertex 1.14356 1.11452 2.55937 + vertex 1.14202 1.11758 2.56141 + endloop + endfacet + facet normal 0.817229 0.132691 0.560829 + outer loop + vertex 1.14243 1.11179 2.56217 + vertex 1.14202 1.11758 2.56141 + vertex 1.14027 1.11343 2.56493 + endloop + endfacet + facet normal 0.829082 0.115962 0.54697 + outer loop + vertex 1.14202 1.11758 2.56141 + vertex 1.13978 1.11814 2.56469 + vertex 1.14027 1.11343 2.56493 + endloop + endfacet + facet normal 0.804563 0.115246 0.582578 + outer loop + vertex 1.13978 1.11814 2.56469 + vertex 1.13802 1.11507 2.56772 + vertex 1.14027 1.11343 2.56493 + endloop + endfacet + facet normal 0.835263 0.0620656 0.546337 + outer loop + vertex 1.13818 1.11888 2.56705 + vertex 1.13802 1.11507 2.56772 + vertex 1.13978 1.11814 2.56469 + endloop + endfacet + facet normal -0.435158 -0.0977277 0.895035 + outer loop + vertex 1.1435 1.11863 2.55904 + vertex 1.145 1.12077 2.56 + vertex 1.14405 1.125 2.56 + endloop + endfacet + facet normal 0.865724 -0.146351 0.478647 + outer loop + vertex 1.1435 1.11863 2.55904 + vertex 1.14405 1.125 2.56 + vertex 1.14202 1.11758 2.56141 + endloop + endfacet + facet normal 0.503192 0.0263373 0.863773 + outer loop + vertex 1.14202 1.11758 2.56141 + vertex 1.14405 1.125 2.56 + vertex 1.14046 1.12316 2.56215 + endloop + endfacet + facet normal 0.880468 0.104324 0.462486 + outer loop + vertex 1.13911 1.12139 2.56511 + vertex 1.14046 1.12316 2.56215 + vertex 1.13895 1.1251 2.56459 + endloop + endfacet + facet normal 0.875508 0.11819 0.468526 + outer loop + vertex 1.13911 1.12139 2.56511 + vertex 1.13978 1.11814 2.56469 + vertex 1.14046 1.12316 2.56215 + endloop + endfacet + facet normal 0.827425 0.159981 0.538307 + outer loop + vertex 1.13978 1.11814 2.56469 + vertex 1.14202 1.11758 2.56141 + vertex 1.14046 1.12316 2.56215 + endloop + endfacet + facet normal 0.838116 0.101847 0.5359 + outer loop + vertex 1.13978 1.11814 2.56469 + vertex 1.13911 1.12139 2.56511 + vertex 1.13818 1.11888 2.56705 + endloop + endfacet + facet normal 0.32148 0.236573 -0.916888 + outer loop + vertex 1.14 1.13 2.55987 + vertex 1.14405 1.125 2.56 + vertex 1.14 1.125 2.55858 + endloop + endfacet + facet normal 0.387102 0.335869 0.858687 + outer loop + vertex 1.1401 1.12886 2.56027 + vertex 1.14405 1.125 2.56 + vertex 1.14 1.13 2.55987 + endloop + endfacet + facet normal 0.364964 0.311907 0.87722 + outer loop + vertex 1.14405 1.125 2.56 + vertex 1.1401 1.12886 2.56027 + vertex 1.14046 1.12316 2.56215 + endloop + endfacet + facet normal 0.926466 0.169331 0.336136 + outer loop + vertex 1.1401 1.12886 2.56027 + vertex 1.13956 1.12786 2.56226 + vertex 1.14046 1.12316 2.56215 + endloop + endfacet + facet normal 0.891132 0.160428 0.424438 + outer loop + vertex 1.13956 1.12786 2.56226 + vertex 1.13895 1.1251 2.56459 + vertex 1.14046 1.12316 2.56215 + endloop + endfacet + facet normal 0.934388 0.0849202 0.345989 + outer loop + vertex 1.13863 1.12977 2.56429 + vertex 1.13895 1.1251 2.56459 + vertex 1.13956 1.12786 2.56226 + endloop + endfacet + facet normal 0.987008 0.0270782 -0.15837 + outer loop + vertex 1.14 1.13 2.55987 + vertex 1.14 1.13076 2.56 + vertex 1.1401 1.12886 2.56027 + endloop + endfacet + facet normal 0.997285 0.0415698 -0.0607758 + outer loop + vertex 1.14 1.135 2.5629 + vertex 1.1401 1.12886 2.56027 + vertex 1.14 1.13076 2.56 + endloop + endfacet + facet normal 0.225908 -0.380584 0.896728 + outer loop + vertex 1.14 1.135 2.5629 + vertex 1.13927 1.13311 2.56228 + vertex 1.1401 1.12886 2.56027 + endloop + endfacet + facet normal 0.957295 0.050334 0.284699 + outer loop + vertex 1.13927 1.13311 2.56228 + vertex 1.13956 1.12786 2.56226 + vertex 1.1401 1.12886 2.56027 + endloop + endfacet + facet normal 0.925272 0.0482741 0.376219 + outer loop + vertex 1.13927 1.13311 2.56228 + vertex 1.13863 1.12977 2.56429 + vertex 1.13956 1.12786 2.56226 + endloop + endfacet + facet normal 0.903757 0.0791184 0.420671 + outer loop + vertex 1.13833 1.13456 2.56404 + vertex 1.13863 1.12977 2.56429 + vertex 1.13927 1.13311 2.56228 + endloop + endfacet + facet normal 0.158865 -0.361927 0.91857 + outer loop + vertex 1.14 1.14 2.56487 + vertex 1.13927 1.13311 2.56228 + vertex 1.14 1.135 2.5629 + endloop + endfacet + facet normal -0.728933 -0.172134 0.66259 + outer loop + vertex 1.13901 1.13737 2.5631 + vertex 1.13927 1.13311 2.56228 + vertex 1.14 1.14 2.56487 + endloop + endfacet + facet normal 0.865153 -0.0424859 0.499705 + outer loop + vertex 1.13901 1.13737 2.5631 + vertex 1.13833 1.13456 2.56404 + vertex 1.13927 1.13311 2.56228 + endloop + endfacet + facet normal 0.828114 -0.0132765 0.560403 + outer loop + vertex 1.13851 1.13892 2.56388 + vertex 1.13833 1.13456 2.56404 + vertex 1.13901 1.13737 2.5631 + endloop + endfacet + facet normal -0.854482 -0.0278518 0.518734 + outer loop + vertex 1.14 1.14 2.56487 + vertex 1.14 1.14242 2.565 + vertex 1.13901 1.13737 2.5631 + endloop + endfacet + facet normal 0.219759 -0.381229 0.897981 + outer loop + vertex 1.13901 1.13737 2.5631 + vertex 1.14 1.14242 2.565 + vertex 1.13851 1.13892 2.56388 + endloop + endfacet + facet normal -0.158966 0.158158 0.974534 + outer loop + vertex 1.14392 1.91 2.56 + vertex 1.13954 1.90929 2.5594 + vertex 1.14 1.90606 2.56 + endloop + endfacet + facet normal 0.958762 -0.0747708 -0.274197 + outer loop + vertex 1.14249 1.91 2.555 + vertex 1.14288 1.915 2.555 + vertex 1.14392 1.91 2.56 + endloop + endfacet + facet normal 0.272717 0.708067 0.651358 + outer loop + vertex 1.14288 1.915 2.555 + vertex 1.14108 1.91398 2.55686 + vertex 1.14392 1.91 2.56 + endloop + endfacet + facet normal -0.198031 0.515855 0.833473 + outer loop + vertex 1.14108 1.91398 2.55686 + vertex 1.13954 1.90929 2.5594 + vertex 1.14392 1.91 2.56 + endloop + endfacet + facet normal 0.837774 0.0219515 0.545575 + outer loop + vertex 1.13916 1.91294 2.55985 + vertex 1.13954 1.90929 2.5594 + vertex 1.14108 1.91398 2.55686 + endloop + endfacet + facet normal 0.729996 -0.048193 0.68175 + outer loop + vertex 1.14288 1.915 2.555 + vertex 1.14321 1.92 2.555 + vertex 1.14108 1.91398 2.55686 + endloop + endfacet + facet normal 0.329941 0.169891 0.928588 + outer loop + vertex 1.14321 1.92 2.555 + vertex 1.14175 1.91862 2.55577 + vertex 1.14108 1.91398 2.55686 + endloop + endfacet + facet normal 0.901885 -0.0890592 0.422696 + outer loop + vertex 1.13916 1.91294 2.55985 + vertex 1.13996 1.91726 2.55905 + vertex 1.13826 1.91501 2.5622 + endloop + endfacet + facet normal 0.849405 -0.0606887 0.52424 + outer loop + vertex 1.13916 1.91294 2.55985 + vertex 1.14108 1.91398 2.55686 + vertex 1.13996 1.91726 2.55905 + endloop + endfacet + facet normal 0.880516 -0.0163043 0.473736 + outer loop + vertex 1.14108 1.91398 2.55686 + vertex 1.14175 1.91862 2.55577 + vertex 1.13996 1.91726 2.55905 + endloop + endfacet + facet normal 0.901646 -0.0878019 0.423468 + outer loop + vertex 1.13996 1.91726 2.55905 + vertex 1.13827 1.91918 2.56305 + vertex 1.13826 1.91501 2.5622 + endloop + endfacet + facet normal 0.555597 -0.128888 0.821401 + outer loop + vertex 1.14321 1.92 2.555 + vertex 1.14437 1.925 2.555 + vertex 1.14175 1.91862 2.55577 + endloop + endfacet + facet normal 0.747562 -0.231861 0.622407 + outer loop + vertex 1.14437 1.925 2.555 + vertex 1.14156 1.92121 2.55696 + vertex 1.14175 1.91862 2.55577 + endloop + endfacet + facet normal 0.892121 -0.134272 0.431382 + outer loop + vertex 1.14175 1.91862 2.55577 + vertex 1.14156 1.92121 2.55696 + vertex 1.13996 1.91726 2.55905 + endloop + endfacet + facet normal 0.890531 -0.131433 0.435522 + outer loop + vertex 1.14156 1.92121 2.55696 + vertex 1.14014 1.92217 2.56015 + vertex 1.13996 1.91726 2.55905 + endloop + endfacet + facet normal 0.888597 -0.132191 0.439229 + outer loop + vertex 1.14014 1.92217 2.56015 + vertex 1.13827 1.91918 2.56305 + vertex 1.13996 1.91726 2.55905 + endloop + endfacet + facet normal 0.880841 -0.10582 0.461434 + outer loop + vertex 1.13849 1.92394 2.56371 + vertex 1.13827 1.91918 2.56305 + vertex 1.14014 1.92217 2.56015 + endloop + endfacet + facet normal 0.642981 0.0946906 0.760006 + outer loop + vertex 1.145 1.92623 2.555 + vertex 1.14468 1.92859 2.55498 + vertex 1.14241 1.92601 2.55722 + endloop + endfacet + facet normal 0.631545 -0.323485 0.704633 + outer loop + vertex 1.145 1.92623 2.555 + vertex 1.14241 1.92601 2.55722 + vertex 1.14437 1.925 2.555 + endloop + endfacet + facet normal 0.702103 -0.16132 0.693562 + outer loop + vertex 1.14437 1.925 2.555 + vertex 1.14241 1.92601 2.55722 + vertex 1.14156 1.92121 2.55696 + endloop + endfacet + facet normal 0.878015 -0.178512 0.444099 + outer loop + vertex 1.14156 1.92121 2.55696 + vertex 1.14241 1.92601 2.55722 + vertex 1.14014 1.92217 2.56015 + endloop + endfacet + facet normal 0.864236 -0.140643 0.483027 + outer loop + vertex 1.14241 1.92601 2.55722 + vertex 1.1402 1.92632 2.56126 + vertex 1.14014 1.92217 2.56015 + endloop + endfacet + facet normal 0.870431 -0.137935 0.472571 + outer loop + vertex 1.1402 1.92632 2.56126 + vertex 1.13849 1.92394 2.56371 + vertex 1.14014 1.92217 2.56015 + endloop + endfacet + facet normal 0.860817 -0.104933 0.49798 + outer loop + vertex 1.13879 1.92833 2.56412 + vertex 1.13849 1.92394 2.56371 + vertex 1.1402 1.92632 2.56126 + endloop + endfacet + facet normal 0.757885 -0.107632 0.643449 + outer loop + vertex 1.14468 1.92859 2.55498 + vertex 1.14329 1.93041 2.55691 + vertex 1.14241 1.92601 2.55722 + endloop + endfacet + facet normal 0.856446 -0.132514 0.498938 + outer loop + vertex 1.14329 1.93041 2.55691 + vertex 1.14338 1.93448 2.55784 + vertex 1.14106 1.93132 2.56098 + endloop + endfacet + facet normal 0.855388 -0.137362 0.499442 + outer loop + vertex 1.14329 1.93041 2.55691 + vertex 1.14106 1.93132 2.56098 + vertex 1.14241 1.92601 2.55722 + endloop + endfacet + facet normal 0.866902 -0.12289 0.483093 + outer loop + vertex 1.14241 1.92601 2.55722 + vertex 1.14106 1.93132 2.56098 + vertex 1.1402 1.92632 2.56126 + endloop + endfacet + facet normal 0.854679 -0.119555 0.505204 + outer loop + vertex 1.14106 1.93132 2.56098 + vertex 1.13879 1.92833 2.56412 + vertex 1.1402 1.92632 2.56126 + endloop + endfacet + facet normal 0.84239 -0.0813978 0.532686 + outer loop + vertex 1.13872 1.93212 2.56482 + vertex 1.13879 1.92833 2.56412 + vertex 1.14106 1.93132 2.56098 + endloop + endfacet + facet normal 0.860649 -0.115455 0.495937 + outer loop + vertex 1.14338 1.93448 2.55784 + vertex 1.14351 1.93912 2.5587 + vertex 1.14187 1.93647 2.56093 + endloop + endfacet + facet normal 0.855303 -0.128756 0.501875 + outer loop + vertex 1.14106 1.93132 2.56098 + vertex 1.14338 1.93448 2.55784 + vertex 1.14187 1.93647 2.56093 + endloop + endfacet + facet normal 0.745424 -0.0568404 0.664163 + outer loop + vertex 1.13872 1.93212 2.56482 + vertex 1.13962 1.93633 2.56416 + vertex 1.13689 1.93425 2.56705 + endloop + endfacet + facet normal 0.839665 -0.0972787 0.534322 + outer loop + vertex 1.13872 1.93212 2.56482 + vertex 1.14106 1.93132 2.56098 + vertex 1.13962 1.93633 2.56416 + endloop + endfacet + facet normal 0.81722 -0.122115 0.56324 + outer loop + vertex 1.14106 1.93132 2.56098 + vertex 1.14187 1.93647 2.56093 + vertex 1.13962 1.93633 2.56416 + endloop + endfacet + facet normal 0.741673 -0.0448109 0.669263 + outer loop + vertex 1.13962 1.93633 2.56416 + vertex 1.13745 1.93807 2.56669 + vertex 1.13689 1.93425 2.56705 + endloop + endfacet + facet normal 0.837507 -0.129358 0.530893 + outer loop + vertex 1.14351 1.93912 2.5587 + vertex 1.14352 1.94292 2.55961 + vertex 1.14152 1.9408 2.56225 + endloop + endfacet + facet normal 0.850041 -0.0894583 0.519064 + outer loop + vertex 1.14187 1.93647 2.56093 + vertex 1.14351 1.93912 2.5587 + vertex 1.14152 1.9408 2.56225 + endloop + endfacet + facet normal 0.818415 -0.105984 0.564769 + outer loop + vertex 1.14187 1.93647 2.56093 + vertex 1.14152 1.9408 2.56225 + vertex 1.13962 1.93633 2.56416 + endloop + endfacet + facet normal 0.779417 -0.0644145 0.623185 + outer loop + vertex 1.14152 1.9408 2.56225 + vertex 1.13919 1.94043 2.56512 + vertex 1.13962 1.93633 2.56416 + endloop + endfacet + facet normal 0.725955 -0.0838499 0.682611 + outer loop + vertex 1.13919 1.94043 2.56512 + vertex 1.13745 1.93807 2.56669 + vertex 1.13962 1.93633 2.56416 + endloop + endfacet + facet normal 0.636999 0.039998 0.769827 + outer loop + vertex 1.13686 1.94158 2.56699 + vertex 1.13745 1.93807 2.56669 + vertex 1.13919 1.94043 2.56512 + endloop + endfacet + facet normal 0.828924 -0.0961512 0.551036 + outer loop + vertex 1.14352 1.94292 2.55961 + vertex 1.14242 1.94491 2.56161 + vertex 1.14152 1.9408 2.56225 + endloop + endfacet + facet normal 0.744841 -0.0521893 0.665198 + outer loop + vertex 1.14242 1.94491 2.56161 + vertex 1.14219 1.94876 2.56217 + vertex 1.13987 1.94471 2.56445 + endloop + endfacet + facet normal 0.74479 -0.0600043 0.664596 + outer loop + vertex 1.14242 1.94491 2.56161 + vertex 1.13987 1.94471 2.56445 + vertex 1.14152 1.9408 2.56225 + endloop + endfacet + facet normal 0.778299 -0.0248677 0.627401 + outer loop + vertex 1.14152 1.9408 2.56225 + vertex 1.13987 1.94471 2.56445 + vertex 1.13919 1.94043 2.56512 + endloop + endfacet + facet normal 0.63176 0.0212564 0.774873 + outer loop + vertex 1.13987 1.94471 2.56445 + vertex 1.13686 1.94158 2.56699 + vertex 1.13919 1.94043 2.56512 + endloop + endfacet + facet normal 0.581188 0.0967676 0.807995 + outer loop + vertex 1.13645 1.94604 2.56675 + vertex 1.13686 1.94158 2.56699 + vertex 1.13987 1.94471 2.56445 + endloop + endfacet + facet normal 0.66384 -0.00599994 0.747851 + outer loop + vertex 1.14219 1.94876 2.56217 + vertex 1.14166 1.95385 2.56268 + vertex 1.13926 1.9496 2.56478 + endloop + endfacet + facet normal 0.669813 0.0339588 0.741753 + outer loop + vertex 1.13987 1.94471 2.56445 + vertex 1.14219 1.94876 2.56217 + vertex 1.13926 1.9496 2.56478 + endloop + endfacet + facet normal 0.561997 0.0147126 0.827008 + outer loop + vertex 1.13926 1.9496 2.56478 + vertex 1.13645 1.94604 2.56675 + vertex 1.13987 1.94471 2.56445 + endloop + endfacet + facet normal 0.443451 0.140222 0.885262 + outer loop + vertex 1.13568 1.95045 2.56644 + vertex 1.13645 1.94604 2.56675 + vertex 1.13926 1.9496 2.56478 + endloop + endfacet + facet normal 0.551577 0.097318 0.828427 + outer loop + vertex 1.13837 1.95333 2.56493 + vertex 1.13926 1.9496 2.56478 + vertex 1.14166 1.95385 2.56268 + endloop + endfacet + facet normal 0.549356 0.110593 0.828238 + outer loop + vertex 1.13837 1.95333 2.56493 + vertex 1.14166 1.95385 2.56268 + vertex 1.139 1.95774 2.56392 + endloop + endfacet + facet normal 0.474216 0.0430214 0.879357 + outer loop + vertex 1.139 1.95774 2.56392 + vertex 1.14166 1.95385 2.56268 + vertex 1.14246 1.95817 2.56204 + endloop + endfacet + facet normal 0.432423 0.0661586 0.899241 + outer loop + vertex 1.13926 1.9496 2.56478 + vertex 1.13837 1.95333 2.56493 + vertex 1.13568 1.95045 2.56644 + endloop + endfacet + facet normal 0.471858 0.0624575 0.87946 + outer loop + vertex 1.14246 1.95817 2.56204 + vertex 1.14192 1.96163 2.56208 + vertex 1.139 1.95774 2.56392 + endloop + endfacet + facet normal 0.389491 0.138821 0.910508 + outer loop + vertex 1.139 1.95774 2.56392 + vertex 1.14192 1.96163 2.56208 + vertex 1.13823 1.96262 2.56351 + endloop + endfacet + facet normal 0.382471 0.101254 0.918403 + outer loop + vertex 1.14192 1.96163 2.56208 + vertex 1.14148 1.96597 2.56179 + vertex 1.13823 1.96262 2.56351 + endloop + endfacet + facet normal 0.282654 0.202333 0.93764 + outer loop + vertex 1.14179 2.09615 2.53329 + vertex 1.14169 2.10099 2.53227 + vertex 1.1377 2.09821 2.53408 + endloop + endfacet + facet normal 0.286237 0.197198 0.937647 + outer loop + vertex 1.1377 2.09821 2.53408 + vertex 1.14169 2.10099 2.53227 + vertex 1.13781 2.10191 2.53326 + endloop + endfacet + facet normal 0.267053 0.22179 0.937812 + outer loop + vertex 1.14464 2.10365 2.53081 + vertex 1.1448 2.10775 2.5298 + vertex 1.14171 2.10559 2.53119 + endloop + endfacet + facet normal 0.265924 0.219939 0.938569 + outer loop + vertex 1.14171 2.10559 2.53119 + vertex 1.14169 2.10099 2.53227 + vertex 1.14464 2.10365 2.53081 + endloop + endfacet + facet normal 0.316007 0.21617 0.923802 + outer loop + vertex 1.14171 2.10559 2.53119 + vertex 1.13774 2.10577 2.53251 + vertex 1.14169 2.10099 2.53227 + endloop + endfacet + facet normal 0.284961 0.189717 0.939577 + outer loop + vertex 1.13774 2.10577 2.53251 + vertex 1.13781 2.10191 2.53326 + vertex 1.14169 2.10099 2.53227 + endloop + endfacet + facet normal 0.289762 0.221585 0.931095 + outer loop + vertex 1.1448 2.10775 2.5298 + vertex 1.14276 2.11319 2.52914 + vertex 1.14023 2.10956 2.53079 + endloop + endfacet + facet normal 0.282644 0.199777 0.938191 + outer loop + vertex 1.14171 2.10559 2.53119 + vertex 1.1448 2.10775 2.5298 + vertex 1.14023 2.10956 2.53079 + endloop + endfacet + facet normal 0.316147 0.210983 0.924953 + outer loop + vertex 1.14023 2.10956 2.53079 + vertex 1.13774 2.10577 2.53251 + vertex 1.14171 2.10559 2.53119 + endloop + endfacet + facet normal 0.346766 0.188107 0.918896 + outer loop + vertex 1.13594 2.11149 2.53201 + vertex 1.13774 2.10577 2.53251 + vertex 1.14023 2.10956 2.53079 + endloop + endfacet + facet normal 0.324445 0.194866 0.925615 + outer loop + vertex 1.13894 2.11348 2.53042 + vertex 1.14023 2.10956 2.53079 + vertex 1.14276 2.11319 2.52914 + endloop + endfacet + facet normal 0.324294 0.176132 0.929414 + outer loop + vertex 1.13894 2.11348 2.53042 + vertex 1.14276 2.11319 2.52914 + vertex 1.13953 2.11757 2.52944 + endloop + endfacet + facet normal 0.355512 0.200297 0.912958 + outer loop + vertex 1.13953 2.11757 2.52944 + vertex 1.14276 2.11319 2.52914 + vertex 1.14287 2.11688 2.52829 + endloop + endfacet + facet normal 0.351931 0.202808 0.913791 + outer loop + vertex 1.14023 2.10956 2.53079 + vertex 1.13894 2.11348 2.53042 + vertex 1.13594 2.11149 2.53201 + endloop + endfacet + facet normal 0.351708 0.168302 0.920856 + outer loop + vertex 1.14287 2.11688 2.52829 + vertex 1.1428 2.12084 2.52759 + vertex 1.13953 2.11757 2.52944 + endloop + endfacet + facet normal 0.363065 0.155696 0.918663 + outer loop + vertex 1.13953 2.11757 2.52944 + vertex 1.1428 2.12084 2.52759 + vertex 1.13775 2.12336 2.52916 + endloop + endfacet + facet normal 0.363435 0.156623 0.918359 + outer loop + vertex 1.1428 2.12084 2.52759 + vertex 1.14104 2.12669 2.52729 + vertex 1.13775 2.12336 2.52916 + endloop + endfacet + facet normal 0.36137 0.158899 0.918783 + outer loop + vertex 1.13775 2.12336 2.52916 + vertex 1.14104 2.12669 2.52729 + vertex 1.13768 2.12722 2.52852 + endloop + endfacet + facet normal 0.383335 0.171783 0.907494 + outer loop + vertex 1.14411 2.12875 2.52568 + vertex 1.14467 2.1327 2.52469 + vertex 1.14165 2.13074 2.52634 + endloop + endfacet + facet normal 0.374147 0.15837 0.913747 + outer loop + vertex 1.14165 2.13074 2.52634 + vertex 1.14104 2.12669 2.52729 + vertex 1.14411 2.12875 2.52568 + endloop + endfacet + facet normal 0.328174 0.168923 0.929391 + outer loop + vertex 1.14165 2.13074 2.52634 + vertex 1.13788 2.13066 2.52768 + vertex 1.14104 2.12669 2.52729 + endloop + endfacet + facet normal 0.36438 0.199733 0.909579 + outer loop + vertex 1.13788 2.13066 2.52768 + vertex 1.13768 2.12722 2.52852 + vertex 1.14104 2.12669 2.52729 + endloop + endfacet + facet normal 0.355108 0.290237 0.888628 + outer loop + vertex 1.14467 2.1327 2.52469 + vertex 1.14252 2.13772 2.52391 + vertex 1.1403 2.1342 2.52595 + endloop + endfacet + facet normal 0.342534 0.236223 0.909323 + outer loop + vertex 1.14165 2.13074 2.52634 + vertex 1.14467 2.1327 2.52469 + vertex 1.1403 2.1342 2.52595 + endloop + endfacet + facet normal 0.322942 0.229604 0.918145 + outer loop + vertex 1.1403 2.1342 2.52595 + vertex 1.13788 2.13066 2.52768 + vertex 1.14165 2.13074 2.52634 + endloop + endfacet + facet normal 0.210054 0.311377 0.92678 + outer loop + vertex 1.13621 2.13482 2.52666 + vertex 1.13788 2.13066 2.52768 + vertex 1.1403 2.1342 2.52595 + endloop + endfacet + facet normal 0.223198 0.378823 0.898151 + outer loop + vertex 1.13833 2.13734 2.52511 + vertex 1.1403 2.1342 2.52595 + vertex 1.14252 2.13772 2.52391 + endloop + endfacet + facet normal 0.17553 0.579773 0.795646 + outer loop + vertex 1.13833 2.13734 2.52511 + vertex 1.14252 2.13772 2.52391 + vertex 1.13783 2.14048 2.52293 + endloop + endfacet + facet normal 0.0501116 0.407564 0.911801 + outer loop + vertex 1.13783 2.14048 2.52293 + vertex 1.14252 2.13772 2.52391 + vertex 1.14201 2.14151 2.52224 + endloop + endfacet + facet normal 0.215378 0.374863 0.901715 + outer loop + vertex 1.1403 2.1342 2.52595 + vertex 1.13833 2.13734 2.52511 + vertex 1.13621 2.13482 2.52666 + endloop + endfacet + facet normal -0.099213 0.593717 0.798534 + outer loop + vertex 1.13893 2.14392 2.52001 + vertex 1.1444 2.14383 2.52075 + vertex 1.14255 2.14696 2.5182 + endloop + endfacet + facet normal -0.232504 0.687205 0.688253 + outer loop + vertex 1.13777 2.14625 2.51729 + vertex 1.13893 2.14392 2.52001 + vertex 1.14255 2.14696 2.5182 + endloop + endfacet + facet normal -0.0366205 0.654107 0.755515 + outer loop + vertex 1.14201 2.14151 2.52224 + vertex 1.13893 2.14392 2.52001 + vertex 1.13783 2.14048 2.52293 + endloop + endfacet + facet normal -0.0976708 0.606885 0.788765 + outer loop + vertex 1.1444 2.14383 2.52075 + vertex 1.13893 2.14392 2.52001 + vertex 1.14201 2.14151 2.52224 + endloop + endfacet + facet normal -0.218775 0.772147 0.596596 + outer loop + vertex 1.14051 2.15229 2.51102 + vertex 1.13773 2.15259 2.50962 + vertex 1.13862 2.15076 2.51232 + endloop + endfacet + facet normal -0.320781 0.809223 0.492198 + outer loop + vertex 1.14228 2.15161 2.51329 + vertex 1.14051 2.15229 2.51102 + vertex 1.13862 2.15076 2.51232 + endloop + endfacet + facet normal -0.331534 0.717747 0.612311 + outer loop + vertex 1.14228 2.15161 2.51329 + vertex 1.13862 2.15076 2.51232 + vertex 1.14251 2.14988 2.51545 + endloop + endfacet + facet normal -0.326344 0.724059 0.60765 + outer loop + vertex 1.14251 2.14988 2.51545 + vertex 1.13862 2.15076 2.51232 + vertex 1.13855 2.1482 2.51532 + endloop + endfacet + facet normal -0.229985 0.735073 0.637789 + outer loop + vertex 1.14255 2.14696 2.5182 + vertex 1.13855 2.1482 2.51532 + vertex 1.13777 2.14625 2.51729 + endloop + endfacet + facet normal -0.298557 0.651548 0.697387 + outer loop + vertex 1.14251 2.14988 2.51545 + vertex 1.13855 2.1482 2.51532 + vertex 1.14255 2.14696 2.5182 + endloop + endfacet + facet normal 0.0902109 -0.19143 0.977352 + outer loop + vertex 1.14251 2.15749 2.50429 + vertex 1.14017 2.16 2.505 + vertex 1.14 2.15992 2.505 + endloop + endfacet + facet normal 0.706325 0.700875 0.0993894 + outer loop + vertex 1.14251 2.15749 2.50429 + vertex 1.14 2.15992 2.505 + vertex 1.14374 2.15582 2.50733 + endloop + endfacet + facet normal 0.0439526 0.524162 0.850484 + outer loop + vertex 1.14374 2.15582 2.50733 + vertex 1.14 2.15992 2.505 + vertex 1.14011 2.15421 2.50851 + endloop + endfacet + facet normal -0.229615 0.754776 0.614484 + outer loop + vertex 1.14051 2.15229 2.51102 + vertex 1.14011 2.15421 2.50851 + vertex 1.13773 2.15259 2.50962 + endloop + endfacet + facet normal -0.297506 0.734561 0.609844 + outer loop + vertex 1.14051 2.15229 2.51102 + vertex 1.14418 2.15333 2.51156 + vertex 1.14011 2.15421 2.50851 + endloop + endfacet + facet normal -0.203088 0.834274 0.512584 + outer loop + vertex 1.14418 2.15333 2.51156 + vertex 1.14374 2.15582 2.50733 + vertex 1.14011 2.15421 2.50851 + endloop + endfacet + facet normal -0.30321 0.821844 0.482323 + outer loop + vertex 1.14418 2.15333 2.51156 + vertex 1.14051 2.15229 2.51102 + vertex 1.14228 2.15161 2.51329 + endloop + endfacet + facet normal 0.448948 0.473699 0.757665 + outer loop + vertex 1.145 2.16342 2.5 + vertex 1.14017 2.16 2.505 + vertex 1.14497 2.15866 2.503 + endloop + endfacet + facet normal -0.773885 0.466144 -0.428733 + outer loop + vertex 1.14294 2.16 2.5 + vertex 1.14017 2.16 2.505 + vertex 1.145 2.16342 2.5 + endloop + endfacet + facet normal 0.412944 0.130982 0.901288 + outer loop + vertex 1.14497 2.15866 2.503 + vertex 1.14017 2.16 2.505 + vertex 1.14251 2.15749 2.50429 + endloop + endfacet + facet normal -0.147092 0.874841 -0.461538 + outer loop + vertex 1.15158 0.863709 2.49698 + vertex 1.14978 0.865 2.5 + vertex 1.15 0.865 2.49993 + endloop + endfacet + facet normal -0.806562 0.187098 -0.56076 + outer loop + vertex 1.15158 0.863709 2.49698 + vertex 1.15013 0.86425 2.49925 + vertex 1.14978 0.865 2.5 + endloop + endfacet + facet normal -0.339207 0.583537 -0.73785 + outer loop + vertex 1.14978 0.865 2.5 + vertex 1.15013 0.86425 2.49925 + vertex 1.14805 0.865621 2.50129 + endloop + endfacet + facet normal -0.249204 -0.959901 0.128408 + outer loop + vertex 1.14978 0.865 2.5 + vertex 1.14805 0.865621 2.50129 + vertex 1.145 0.866241 2.5 + endloop + endfacet + facet normal -0.35295 -0.826154 0.439199 + outer loop + vertex 1.145 0.866241 2.5 + vertex 1.14805 0.865621 2.50129 + vertex 1.14436 0.867516 2.50188 + endloop + endfacet + facet normal -0.39578 -0.866873 0.303132 + outer loop + vertex 1.14805 0.865621 2.50129 + vertex 1.14705 0.867312 2.50481 + vertex 1.14436 0.867516 2.50188 + endloop + endfacet + facet normal -0.348472 -0.901309 0.257312 + outer loop + vertex 1.14705 0.867312 2.50481 + vertex 1.14388 0.868494 2.50466 + vertex 1.14436 0.867516 2.50188 + endloop + endfacet + facet normal -0.33965 -0.862683 0.374721 + outer loop + vertex 1.14705 0.867312 2.50481 + vertex 1.14542 0.869234 2.50776 + vertex 1.14388 0.868494 2.50466 + endloop + endfacet + facet normal -0.245095 -0.868663 0.430527 + outer loop + vertex 1.14993 0.868409 2.50866 + vertex 1.14542 0.869234 2.50776 + vertex 1.14705 0.867312 2.50481 + endloop + endfacet + facet normal -0.249862 -0.841068 0.479764 + outer loop + vertex 1.14542 0.869234 2.50776 + vertex 1.14993 0.868409 2.50866 + vertex 1.1479 0.870906 2.51199 + endloop + endfacet + facet normal -0.313482 -0.805431 0.503001 + outer loop + vertex 1.14223 0.871682 2.50969 + vertex 1.14542 0.869234 2.50776 + vertex 1.1479 0.870906 2.51199 + endloop + endfacet + facet normal -0.295238 -0.845878 0.444214 + outer loop + vertex 1.1479 0.870906 2.51199 + vertex 1.14442 0.873227 2.51409 + vertex 1.14223 0.871682 2.50969 + endloop + endfacet + facet normal -0.214966 -0.813089 0.540996 + outer loop + vertex 1.14832 0.872913 2.51517 + vertex 1.14442 0.873227 2.51409 + vertex 1.1479 0.870906 2.51199 + endloop + endfacet + facet normal -0.226523 -0.771125 0.595024 + outer loop + vertex 1.14442 0.873227 2.51409 + vertex 1.14832 0.872913 2.51517 + vertex 1.14664 0.874602 2.51672 + endloop + endfacet + facet normal -0.241827 -0.760622 0.602472 + outer loop + vertex 1.14233 0.876092 2.51687 + vertex 1.14442 0.873227 2.51409 + vertex 1.14664 0.874602 2.51672 + endloop + endfacet + facet normal -0.0512034 -0.63739 0.768838 + outer loop + vertex 1.14288 0.878383 2.51957 + vertex 1.14732 0.877543 2.51917 + vertex 1.14504 0.879904 2.52098 + endloop + endfacet + facet normal -0.0832779 -0.752153 0.653705 + outer loop + vertex 1.14288 0.878383 2.51957 + vertex 1.14233 0.876092 2.51687 + vertex 1.14732 0.877543 2.51917 + endloop + endfacet + facet normal -0.182063 -0.605011 0.775122 + outer loop + vertex 1.14233 0.876092 2.51687 + vertex 1.14664 0.874602 2.51672 + vertex 1.14732 0.877543 2.51917 + endloop + endfacet + facet normal 0.101719 -0.540129 0.835412 + outer loop + vertex 1.14732 0.877543 2.51917 + vertex 1.14807 0.880813 2.5212 + vertex 1.14504 0.879904 2.52098 + endloop + endfacet + facet normal -0.104062 -0.591068 0.799881 + outer loop + vertex 1.14288 0.878383 2.51957 + vertex 1.14504 0.879904 2.52098 + vertex 1.14157 0.880912 2.52127 + endloop + endfacet + facet normal -0.037429 -0.396445 0.917295 + outer loop + vertex 1.14504 0.879904 2.52098 + vertex 1.14536 0.883701 2.52263 + vertex 1.14157 0.880912 2.52127 + endloop + endfacet + facet normal 0.054962 -0.402689 0.913685 + outer loop + vertex 1.14504 0.879904 2.52098 + vertex 1.14807 0.880813 2.5212 + vertex 1.14536 0.883701 2.52263 + endloop + endfacet + facet normal 0.176682 -0.299927 0.937458 + outer loop + vertex 1.14807 0.880813 2.5212 + vertex 1.14984 0.884623 2.52208 + vertex 1.14536 0.883701 2.52263 + endloop + endfacet + facet normal 0.169856 -0.258702 0.950906 + outer loop + vertex 1.14984 0.884623 2.52208 + vertex 1.14897 0.888774 2.52337 + vertex 1.14536 0.883701 2.52263 + endloop + endfacet + facet normal 0.27956 -0.329765 0.901722 + outer loop + vertex 1.14536 0.883701 2.52263 + vertex 1.14897 0.888774 2.52337 + vertex 1.14423 0.888522 2.52475 + endloop + endfacet + facet normal 0.354126 -0.311306 0.881864 + outer loop + vertex 1.14455 0.892339 2.52596 + vertex 1.14207 0.890244 2.52622 + vertex 1.14423 0.888522 2.52475 + endloop + endfacet + facet normal 0.382275 -0.310036 0.870484 + outer loop + vertex 1.14455 0.892339 2.52596 + vertex 1.14423 0.888522 2.52475 + vertex 1.14849 0.893915 2.52479 + endloop + endfacet + facet normal 0.282797 -0.231829 0.930742 + outer loop + vertex 1.14849 0.893915 2.52479 + vertex 1.14423 0.888522 2.52475 + vertex 1.14897 0.888774 2.52337 + endloop + endfacet + facet normal 0.304805 -0.248541 0.919413 + outer loop + vertex 1.14455 0.892339 2.52596 + vertex 1.14228 0.893473 2.52702 + vertex 1.14207 0.890244 2.52622 + endloop + endfacet + facet normal 0.355082 -0.185535 0.916239 + outer loop + vertex 1.14849 0.893915 2.52479 + vertex 1.14977 0.899304 2.52539 + vertex 1.14592 0.896251 2.52626 + endloop + endfacet + facet normal 0.349187 -0.192538 0.917059 + outer loop + vertex 1.14455 0.892339 2.52596 + vertex 1.14849 0.893915 2.52479 + vertex 1.14592 0.896251 2.52626 + endloop + endfacet + facet normal 0.336415 -0.188471 0.922661 + outer loop + vertex 1.14592 0.896251 2.52626 + vertex 1.14228 0.893473 2.52702 + vertex 1.14455 0.892339 2.52596 + endloop + endfacet + facet normal 0.337368 -0.189894 0.922021 + outer loop + vertex 1.14348 0.89867 2.52765 + vertex 1.14228 0.893473 2.52702 + vertex 1.14592 0.896251 2.52626 + endloop + endfacet + facet normal 0.333863 -0.154888 0.929809 + outer loop + vertex 1.14977 0.899304 2.52539 + vertex 1.14741 0.900212 2.52639 + vertex 1.14592 0.896251 2.52626 + endloop + endfacet + facet normal 0.360392 -0.164452 0.91819 + outer loop + vertex 1.14741 0.900212 2.52639 + vertex 1.14348 0.89867 2.52765 + vertex 1.14592 0.896251 2.52626 + endloop + endfacet + facet normal 0.37128 -0.201903 0.906304 + outer loop + vertex 1.14741 0.900212 2.52639 + vertex 1.14818 0.9042 2.52696 + vertex 1.14348 0.89867 2.52765 + endloop + endfacet + facet normal 0.349051 -0.181385 0.919382 + outer loop + vertex 1.14818 0.9042 2.52696 + vertex 1.14354 0.904016 2.52869 + vertex 1.14348 0.89867 2.52765 + endloop + endfacet + facet normal 0.348079 -0.209451 0.913768 + outer loop + vertex 1.14818 0.9042 2.52696 + vertex 1.14825 0.90909 2.52805 + vertex 1.14354 0.904016 2.52869 + endloop + endfacet + facet normal 0.307285 -0.168723 0.936541 + outer loop + vertex 1.14354 0.904016 2.52869 + vertex 1.14825 0.90909 2.52805 + vertex 1.14349 0.909253 2.52965 + endloop + endfacet + facet normal 0.304056 -0.204254 0.9305 + outer loop + vertex 1.14825 0.90909 2.52805 + vertex 1.14855 0.914015 2.52904 + vertex 1.14349 0.909253 2.52965 + endloop + endfacet + facet normal 0.265413 -0.160555 0.950673 + outer loop + vertex 1.14349 0.909253 2.52965 + vertex 1.14855 0.914015 2.52904 + vertex 1.14474 0.914423 2.53017 + endloop + endfacet + facet normal 0.257734 -0.210852 0.942929 + outer loop + vertex 1.14883 0.918757 2.53002 + vertex 1.14474 0.914423 2.53017 + vertex 1.14855 0.914015 2.52904 + endloop + endfacet + facet normal 0.335099 -0.125179 0.93383 + outer loop + vertex 1.14752 1.03796 2.55777 + vertex 1.14771 1.04305 2.55838 + vertex 1.14358 1.03846 2.55925 + endloop + endfacet + facet normal 0.394507 -0.184911 0.900096 + outer loop + vertex 1.14358 1.03846 2.55925 + vertex 1.14771 1.04305 2.55838 + vertex 1.14392 1.0435 2.56014 + endloop + endfacet + facet normal 0.373262 -0.184529 0.909189 + outer loop + vertex 1.14461 1.04761 2.56069 + vertex 1.14222 1.04521 2.56118 + vertex 1.14392 1.0435 2.56014 + endloop + endfacet + facet normal 0.502739 -0.197212 0.841642 + outer loop + vertex 1.14461 1.04761 2.56069 + vertex 1.14392 1.0435 2.56014 + vertex 1.14773 1.04857 2.55905 + endloop + endfacet + facet normal 0.406482 -0.110776 0.906919 + outer loop + vertex 1.14773 1.04857 2.55905 + vertex 1.14392 1.0435 2.56014 + vertex 1.14771 1.04305 2.55838 + endloop + endfacet + facet normal 0.326742 -0.132765 0.935742 + outer loop + vertex 1.14461 1.04761 2.56069 + vertex 1.14215 1.04839 2.56166 + vertex 1.14222 1.04521 2.56118 + endloop + endfacet + facet normal 0.53346 -0.0625905 0.843506 + outer loop + vertex 1.14773 1.04857 2.55905 + vertex 1.14855 1.05434 2.55896 + vertex 1.14545 1.05157 2.56071 + endloop + endfacet + facet normal 0.488312 -0.109381 0.865787 + outer loop + vertex 1.14461 1.04761 2.56069 + vertex 1.14773 1.04857 2.55905 + vertex 1.14545 1.05157 2.56071 + endloop + endfacet + facet normal 0.343767 -0.0790847 0.935719 + outer loop + vertex 1.14545 1.05157 2.56071 + vertex 1.14215 1.04839 2.56166 + vertex 1.14461 1.04761 2.56069 + endloop + endfacet + facet normal 0.375188 -0.1165 0.919599 + outer loop + vertex 1.14225 1.05292 2.56219 + vertex 1.14215 1.04839 2.56166 + vertex 1.14545 1.05157 2.56071 + endloop + endfacet + facet normal 0.565221 -0.0156581 0.824791 + outer loop + vertex 1.14855 1.05434 2.55896 + vertex 1.1487 1.05945 2.55895 + vertex 1.14572 1.05651 2.56094 + endloop + endfacet + facet normal 0.536675 -0.0677455 0.841065 + outer loop + vertex 1.14545 1.05157 2.56071 + vertex 1.14855 1.05434 2.55896 + vertex 1.14572 1.05651 2.56094 + endloop + endfacet + facet normal 0.395944 -0.0633439 0.916087 + outer loop + vertex 1.14572 1.05651 2.56094 + vertex 1.14225 1.05292 2.56219 + vertex 1.14545 1.05157 2.56071 + endloop + endfacet + facet normal 0.441535 -0.116686 0.889624 + outer loop + vertex 1.14231 1.05804 2.56283 + vertex 1.14225 1.05292 2.56219 + vertex 1.14572 1.05651 2.56094 + endloop + endfacet + facet normal 0.612761 -0.00682661 0.790238 + outer loop + vertex 1.1487 1.05945 2.55895 + vertex 1.14873 1.06449 2.55897 + vertex 1.14577 1.06165 2.56124 + endloop + endfacet + facet normal 0.589859 -0.0534523 0.805735 + outer loop + vertex 1.14572 1.05651 2.56094 + vertex 1.1487 1.05945 2.55895 + vertex 1.14577 1.06165 2.56124 + endloop + endfacet + facet normal 0.464944 -0.0568812 0.883511 + outer loop + vertex 1.14577 1.06165 2.56124 + vertex 1.14231 1.05804 2.56283 + vertex 1.14572 1.05651 2.56094 + endloop + endfacet + facet normal 0.517371 -0.123172 0.84685 + outer loop + vertex 1.14232 1.06369 2.56364 + vertex 1.14231 1.05804 2.56283 + vertex 1.14577 1.06165 2.56124 + endloop + endfacet + facet normal 0.662578 0.00428276 0.74898 + outer loop + vertex 1.14873 1.06449 2.55897 + vertex 1.14876 1.06959 2.55891 + vertex 1.14593 1.0669 2.56143 + endloop + endfacet + facet normal 0.636327 -0.0475969 0.769949 + outer loop + vertex 1.14577 1.06165 2.56124 + vertex 1.14873 1.06449 2.55897 + vertex 1.14593 1.0669 2.56143 + endloop + endfacet + facet normal 0.552077 -0.0473305 0.832448 + outer loop + vertex 1.14593 1.0669 2.56143 + vertex 1.14232 1.06369 2.56364 + vertex 1.14577 1.06165 2.56124 + endloop + endfacet + facet normal 0.582629 -0.0993075 0.806648 + outer loop + vertex 1.14324 1.06938 2.56368 + vertex 1.14232 1.06369 2.56364 + vertex 1.14593 1.0669 2.56143 + endloop + endfacet + facet normal 0.709496 0.0382464 0.703671 + outer loop + vertex 1.14876 1.06959 2.55891 + vertex 1.14875 1.07482 2.55864 + vertex 1.14613 1.07209 2.56144 + endloop + endfacet + facet normal 0.678198 -0.0258823 0.734423 + outer loop + vertex 1.14593 1.0669 2.56143 + vertex 1.14876 1.06959 2.55891 + vertex 1.14613 1.07209 2.56144 + endloop + endfacet + facet normal 0.627865 -0.024002 0.777952 + outer loop + vertex 1.14613 1.07209 2.56144 + vertex 1.14324 1.06938 2.56368 + vertex 1.14593 1.0669 2.56143 + endloop + endfacet + facet normal 0.63969 -0.0454638 0.767288 + outer loop + vertex 1.14348 1.07445 2.56378 + vertex 1.14324 1.06938 2.56368 + vertex 1.14613 1.07209 2.56144 + endloop + endfacet + facet normal 0.747161 0.0705794 0.660885 + outer loop + vertex 1.14875 1.07482 2.55864 + vertex 1.14851 1.08005 2.55835 + vertex 1.14614 1.07718 2.56134 + endloop + endfacet + facet normal 0.723489 0.0110764 0.690247 + outer loop + vertex 1.14613 1.07209 2.56144 + vertex 1.14875 1.07482 2.55864 + vertex 1.14614 1.07718 2.56134 + endloop + endfacet + facet normal 0.669557 0.0122539 0.74266 + outer loop + vertex 1.14614 1.07718 2.56134 + vertex 1.14348 1.07445 2.56378 + vertex 1.14613 1.07209 2.56144 + endloop + endfacet + facet normal 0.679993 -0.00640865 0.73319 + outer loop + vertex 1.1435 1.07947 2.5638 + vertex 1.14348 1.07445 2.56378 + vertex 1.14614 1.07718 2.56134 + endloop + endfacet + facet normal 0.779516 0.0753297 0.621836 + outer loop + vertex 1.14851 1.08005 2.55835 + vertex 1.14828 1.085 2.55805 + vertex 1.14611 1.08232 2.56108 + endloop + endfacet + facet normal 0.765591 0.0359549 0.642322 + outer loop + vertex 1.14614 1.07718 2.56134 + vertex 1.14851 1.08005 2.55835 + vertex 1.14611 1.08232 2.56108 + endloop + endfacet + facet normal 0.700366 0.0390376 0.712716 + outer loop + vertex 1.14611 1.08232 2.56108 + vertex 1.1435 1.07947 2.5638 + vertex 1.14614 1.07718 2.56134 + endloop + endfacet + facet normal 0.712165 0.0177944 0.701787 + outer loop + vertex 1.14352 1.08465 2.56366 + vertex 1.1435 1.07947 2.5638 + vertex 1.14611 1.08232 2.56108 + endloop + endfacet + facet normal 0.798706 0.0696929 0.597672 + outer loop + vertex 1.14828 1.085 2.55805 + vertex 1.14839 1.08883 2.55745 + vertex 1.14628 1.08798 2.56036 + endloop + endfacet + facet normal 0.79013 0.0539663 0.610558 + outer loop + vertex 1.14611 1.08232 2.56108 + vertex 1.14828 1.085 2.55805 + vertex 1.14628 1.08798 2.56036 + endloop + endfacet + facet normal 0.73137 0.0645157 0.678922 + outer loop + vertex 1.14628 1.08798 2.56036 + vertex 1.14352 1.08465 2.56366 + vertex 1.14611 1.08232 2.56108 + endloop + endfacet + facet normal 0.746631 0.0372753 0.664194 + outer loop + vertex 1.14344 1.08992 2.56345 + vertex 1.14352 1.08465 2.56366 + vertex 1.14628 1.08798 2.56036 + endloop + endfacet + facet normal 0.87714 0.181351 0.444676 + outer loop + vertex 1.14899 1.09119 2.55553 + vertex 1.14863 1.09482 2.55476 + vertex 1.14773 1.09231 2.55755 + endloop + endfacet + facet normal 0.875033 0.151843 0.459632 + outer loop + vertex 1.14839 1.08883 2.55745 + vertex 1.14899 1.09119 2.55553 + vertex 1.14773 1.09231 2.55755 + endloop + endfacet + facet normal 0.784989 0.13081 0.605542 + outer loop + vertex 1.14839 1.08883 2.55745 + vertex 1.14773 1.09231 2.55755 + vertex 1.14628 1.08798 2.56036 + endloop + endfacet + facet normal 0.804623 0.109912 0.583525 + outer loop + vertex 1.14628 1.08798 2.56036 + vertex 1.14773 1.09231 2.55755 + vertex 1.14561 1.0935 2.56025 + endloop + endfacet + facet normal 0.763675 0.105944 0.636849 + outer loop + vertex 1.14561 1.0935 2.56025 + vertex 1.14344 1.08992 2.56345 + vertex 1.14628 1.08798 2.56036 + endloop + endfacet + facet normal 0.788976 0.0672087 0.610738 + outer loop + vertex 1.14321 1.09512 2.56317 + vertex 1.14344 1.08992 2.56345 + vertex 1.14561 1.0935 2.56025 + endloop + endfacet + facet normal 0.854936 0.0940648 0.510134 + outer loop + vertex 1.14863 1.09482 2.55476 + vertex 1.14848 1.09897 2.55423 + vertex 1.14717 1.09784 2.55665 + endloop + endfacet + facet normal 0.888622 0.160566 0.429616 + outer loop + vertex 1.14773 1.09231 2.55755 + vertex 1.14863 1.09482 2.55476 + vertex 1.14717 1.09784 2.55665 + endloop + endfacet + facet normal 0.810253 0.173817 0.559713 + outer loop + vertex 1.14773 1.09231 2.55755 + vertex 1.14717 1.09784 2.55665 + vertex 1.14561 1.0935 2.56025 + endloop + endfacet + facet normal 0.844507 0.128428 0.519917 + outer loop + vertex 1.14717 1.09784 2.55665 + vertex 1.14503 1.09864 2.55992 + vertex 1.14561 1.0935 2.56025 + endloop + endfacet + facet normal 0.800003 0.127784 0.586231 + outer loop + vertex 1.14503 1.09864 2.55992 + vertex 1.14321 1.09512 2.56317 + vertex 1.14561 1.0935 2.56025 + endloop + endfacet + facet normal 0.840677 0.0622316 0.53795 + outer loop + vertex 1.14312 1.10003 2.56275 + vertex 1.14321 1.09512 2.56317 + vertex 1.14503 1.09864 2.55992 + endloop + endfacet + facet normal -0.284218 -0.101501 0.953372 + outer loop + vertex 1.14848 1.09897 2.55423 + vertex 1.15 1.10192 2.555 + vertex 1.1489 1.105 2.555 + endloop + endfacet + facet normal 0.893934 -0.116509 0.43279 + outer loop + vertex 1.14848 1.09897 2.55423 + vertex 1.1489 1.105 2.555 + vertex 1.14717 1.09784 2.55665 + endloop + endfacet + facet normal 0.520188 0.0699536 0.851182 + outer loop + vertex 1.14717 1.09784 2.55665 + vertex 1.1489 1.105 2.555 + vertex 1.14585 1.10316 2.55701 + endloop + endfacet + facet normal 0.843552 0.1736 0.508216 + outer loop + vertex 1.14717 1.09784 2.55665 + vertex 1.14585 1.10316 2.55701 + vertex 1.14503 1.09864 2.55992 + endloop + endfacet + facet normal 0.909549 0.095165 0.404555 + outer loop + vertex 1.14585 1.10316 2.55701 + vertex 1.14456 1.10309 2.55994 + vertex 1.14503 1.09864 2.55992 + endloop + endfacet + facet normal 0.844595 0.0873803 0.528227 + outer loop + vertex 1.14456 1.10309 2.55994 + vertex 1.14312 1.10003 2.56275 + vertex 1.14503 1.09864 2.55992 + endloop + endfacet + facet normal 0.875885 0.0299562 0.48159 + outer loop + vertex 1.14332 1.10382 2.56214 + vertex 1.14312 1.10003 2.56275 + vertex 1.14456 1.10309 2.55994 + endloop + endfacet + facet normal 0.289297 0.216317 -0.932477 + outer loop + vertex 1.145 1.11 2.55495 + vertex 1.1489 1.105 2.555 + vertex 1.145 1.105 2.55379 + endloop + endfacet + facet normal 0.525839 0.417581 0.741026 + outer loop + vertex 1.14516 1.1087 2.55557 + vertex 1.1489 1.105 2.555 + vertex 1.145 1.11 2.55495 + endloop + endfacet + facet normal 0.407273 0.277997 0.869969 + outer loop + vertex 1.1489 1.105 2.555 + vertex 1.14516 1.1087 2.55557 + vertex 1.14585 1.10316 2.55701 + endloop + endfacet + facet normal 0.952526 0.18222 0.243906 + outer loop + vertex 1.14516 1.1087 2.55557 + vertex 1.14481 1.10724 2.55806 + vertex 1.14585 1.10316 2.55701 + endloop + endfacet + facet normal 0.948005 0.0890898 0.305533 + outer loop + vertex 1.14414 1.10622 2.56041 + vertex 1.14481 1.10724 2.55806 + vertex 1.14397 1.10995 2.55985 + endloop + endfacet + facet normal 0.949788 0.0805918 0.302338 + outer loop + vertex 1.14414 1.10622 2.56041 + vertex 1.14456 1.10309 2.55994 + vertex 1.14481 1.10724 2.55806 + endloop + endfacet + facet normal 0.905699 0.12938 0.403695 + outer loop + vertex 1.14456 1.10309 2.55994 + vertex 1.14585 1.10316 2.55701 + vertex 1.14481 1.10724 2.55806 + endloop + endfacet + facet normal 0.877491 0.0451853 0.477461 + outer loop + vertex 1.14456 1.10309 2.55994 + vertex 1.14414 1.10622 2.56041 + vertex 1.14332 1.10382 2.56214 + endloop + endfacet + facet normal 0.990359 0.0673399 -0.121051 + outer loop + vertex 1.145 1.11 2.55495 + vertex 1.145 1.11009 2.555 + vertex 1.14516 1.1087 2.55557 + endloop + endfacet + facet normal 0.992026 0.0758492 -0.100653 + outer loop + vertex 1.145 1.115 2.5587 + vertex 1.14516 1.1087 2.55557 + vertex 1.145 1.11009 2.555 + endloop + endfacet + facet normal 0.101617 -0.440672 0.891898 + outer loop + vertex 1.145 1.115 2.5587 + vertex 1.14443 1.11296 2.55776 + vertex 1.14516 1.1087 2.55557 + endloop + endfacet + facet normal 0.979979 0.0742689 0.184728 + outer loop + vertex 1.14443 1.11296 2.55776 + vertex 1.14481 1.10724 2.55806 + vertex 1.14516 1.1087 2.55557 + endloop + endfacet + facet normal 0.944388 0.0788995 0.319228 + outer loop + vertex 1.14443 1.11296 2.55776 + vertex 1.14397 1.10995 2.55985 + vertex 1.14481 1.10724 2.55806 + endloop + endfacet + facet normal 0.91895 0.121595 0.375159 + outer loop + vertex 1.14356 1.11452 2.55937 + vertex 1.14397 1.10995 2.55985 + vertex 1.14443 1.11296 2.55776 + endloop + endfacet + facet normal -0.60227 -0.18923 0.77554 + outer loop + vertex 1.145 1.12 2.55992 + vertex 1.14443 1.11296 2.55776 + vertex 1.145 1.115 2.5587 + endloop + endfacet + facet normal -0.698299 -0.157675 0.698224 + outer loop + vertex 1.1441 1.11703 2.55835 + vertex 1.14443 1.11296 2.55776 + vertex 1.145 1.12 2.55992 + endloop + endfacet + facet normal 0.88228 0.00228372 0.470719 + outer loop + vertex 1.1441 1.11703 2.55835 + vertex 1.14356 1.11452 2.55937 + vertex 1.14443 1.11296 2.55776 + endloop + endfacet + facet normal 0.817187 0.0580813 0.573439 + outer loop + vertex 1.1435 1.11863 2.55904 + vertex 1.14356 1.11452 2.55937 + vertex 1.1441 1.11703 2.55835 + endloop + endfacet + facet normal -0.812883 -0.0600934 0.579318 + outer loop + vertex 1.145 1.12 2.55992 + vertex 1.145 1.12077 2.56 + vertex 1.1441 1.11703 2.55835 + endloop + endfacet + facet normal -0.0159571 -0.40039 0.916206 + outer loop + vertex 1.1441 1.11703 2.55835 + vertex 1.145 1.12077 2.56 + vertex 1.1435 1.11863 2.55904 + endloop + endfacet + facet normal -0.00737882 0.00808345 0.99994 + outer loop + vertex 1.14913 1.93 2.555 + vertex 1.14468 1.92859 2.55498 + vertex 1.145 1.92623 2.555 + endloop + endfacet + facet normal 0.757411 -0.10844 0.643871 + outer loop + vertex 1.14468 1.92859 2.55498 + vertex 1.14556 1.93266 2.55462 + vertex 1.14329 1.93041 2.55691 + endloop + endfacet + facet normal -0.0347126 0.0944835 0.994921 + outer loop + vertex 1.14468 1.92859 2.55498 + vertex 1.14913 1.93 2.555 + vertex 1.14556 1.93266 2.55462 + endloop + endfacet + facet normal -0.101488 0.00507405 0.994824 + outer loop + vertex 1.14913 1.93 2.555 + vertex 1.14938 1.935 2.555 + vertex 1.14556 1.93266 2.55462 + endloop + endfacet + facet normal 0.774251 -0.15664 0.613188 + outer loop + vertex 1.14556 1.93266 2.55462 + vertex 1.14338 1.93448 2.55784 + vertex 1.14329 1.93041 2.55691 + endloop + endfacet + facet normal 0.961248 -0.0749858 -0.265292 + outer loop + vertex 1.148 1.935 2.55 + vertex 1.14839 1.94 2.55 + vertex 1.14938 1.935 2.555 + endloop + endfacet + facet normal -0.355033 0.624962 0.695251 + outer loop + vertex 1.14839 1.94 2.55 + vertex 1.14681 1.93641 2.55242 + vertex 1.14938 1.935 2.555 + endloop + endfacet + facet normal -0.413643 0.559761 0.71803 + outer loop + vertex 1.14938 1.935 2.555 + vertex 1.14681 1.93641 2.55242 + vertex 1.14556 1.93266 2.55462 + endloop + endfacet + facet normal 0.855099 0.0186838 0.518128 + outer loop + vertex 1.14681 1.93641 2.55242 + vertex 1.14522 1.93743 2.55501 + vertex 1.14556 1.93266 2.55462 + endloop + endfacet + facet normal 0.831413 0.0139678 0.555479 + outer loop + vertex 1.14522 1.93743 2.55501 + vertex 1.14338 1.93448 2.55784 + vertex 1.14556 1.93266 2.55462 + endloop + endfacet + facet normal 0.881412 -0.109292 0.459529 + outer loop + vertex 1.14351 1.93912 2.5587 + vertex 1.14338 1.93448 2.55784 + vertex 1.14522 1.93743 2.55501 + endloop + endfacet + facet normal 0.434092 0.156551 0.887162 + outer loop + vertex 1.15 1.94373 2.55 + vertex 1.14967 1.94493 2.54995 + vertex 1.14738 1.94096 2.55177 + endloop + endfacet + facet normal 0.737848 -0.318471 0.595111 + outer loop + vertex 1.15 1.94373 2.55 + vertex 1.14738 1.94096 2.55177 + vertex 1.14839 1.94 2.55 + endloop + endfacet + facet normal 0.85971 -0.0332274 0.509701 + outer loop + vertex 1.14839 1.94 2.55 + vertex 1.14738 1.94096 2.55177 + vertex 1.14681 1.93641 2.55242 + endloop + endfacet + facet normal 0.846541 -0.0284663 0.531562 + outer loop + vertex 1.14681 1.93641 2.55242 + vertex 1.14738 1.94096 2.55177 + vertex 1.14522 1.93743 2.55501 + endloop + endfacet + facet normal 0.883369 -0.123853 0.452016 + outer loop + vertex 1.14738 1.94096 2.55177 + vertex 1.1454 1.94268 2.55611 + vertex 1.14522 1.93743 2.55501 + endloop + endfacet + facet normal 0.876278 -0.126335 0.464949 + outer loop + vertex 1.1454 1.94268 2.55611 + vertex 1.14351 1.93912 2.5587 + vertex 1.14522 1.93743 2.55501 + endloop + endfacet + facet normal 0.871927 -0.116271 0.475631 + outer loop + vertex 1.14352 1.94292 2.55961 + vertex 1.14351 1.93912 2.5587 + vertex 1.1454 1.94268 2.55611 + endloop + endfacet + facet normal 0.800607 -0.143469 0.581761 + outer loop + vertex 1.14967 1.94493 2.54995 + vertex 1.14986 1.94807 2.55045 + vertex 1.1476 1.94588 2.55303 + endloop + endfacet + facet normal 0.788287 -0.185898 0.586553 + outer loop + vertex 1.14738 1.94096 2.55177 + vertex 1.14967 1.94493 2.54995 + vertex 1.1476 1.94588 2.55303 + endloop + endfacet + facet normal 0.87338 -0.157631 0.460825 + outer loop + vertex 1.14738 1.94096 2.55177 + vertex 1.1476 1.94588 2.55303 + vertex 1.1454 1.94268 2.55611 + endloop + endfacet + facet normal 0.871978 -0.152439 0.465206 + outer loop + vertex 1.1476 1.94588 2.55303 + vertex 1.14609 1.94632 2.556 + vertex 1.1454 1.94268 2.55611 + endloop + endfacet + facet normal 0.830942 -0.0925765 0.548602 + outer loop + vertex 1.14352 1.94292 2.55961 + vertex 1.14449 1.94685 2.55881 + vertex 1.14242 1.94491 2.56161 + endloop + endfacet + facet normal 0.871775 -0.117419 0.475628 + outer loop + vertex 1.14352 1.94292 2.55961 + vertex 1.1454 1.94268 2.55611 + vertex 1.14449 1.94685 2.55881 + endloop + endfacet + facet normal 0.846684 -0.146208 0.511615 + outer loop + vertex 1.1454 1.94268 2.55611 + vertex 1.14609 1.94632 2.556 + vertex 1.14449 1.94685 2.55881 + endloop + endfacet + facet normal 0.815882 -0.0352411 0.577144 + outer loop + vertex 1.14449 1.94685 2.55881 + vertex 1.14219 1.94876 2.56217 + vertex 1.14242 1.94491 2.56161 + endloop + endfacet + facet normal 0.795191 -0.124029 0.593538 + outer loop + vertex 1.14986 1.94807 2.55045 + vertex 1.14869 1.94973 2.55238 + vertex 1.1476 1.94588 2.55303 + endloop + endfacet + facet normal 0.858778 -0.135312 0.494157 + outer loop + vertex 1.14869 1.94973 2.55238 + vertex 1.14872 1.95347 2.55335 + vertex 1.14675 1.94993 2.5558 + endloop + endfacet + facet normal 0.855288 -0.157795 0.493541 + outer loop + vertex 1.14869 1.94973 2.55238 + vertex 1.14675 1.94993 2.5558 + vertex 1.1476 1.94588 2.55303 + endloop + endfacet + facet normal 0.875601 -0.133492 0.464222 + outer loop + vertex 1.1476 1.94588 2.55303 + vertex 1.14675 1.94993 2.5558 + vertex 1.14609 1.94632 2.556 + endloop + endfacet + facet normal 0.850707 -0.126404 0.510216 + outer loop + vertex 1.14609 1.94632 2.556 + vertex 1.14675 1.94993 2.5558 + vertex 1.14449 1.94685 2.55881 + endloop + endfacet + facet normal 0.836001 -0.084507 0.542181 + outer loop + vertex 1.14675 1.94993 2.5558 + vertex 1.14452 1.95199 2.55956 + vertex 1.14449 1.94685 2.55881 + endloop + endfacet + facet normal 0.797089 -0.0921603 0.596787 + outer loop + vertex 1.14452 1.95199 2.55956 + vertex 1.14219 1.94876 2.56217 + vertex 1.14449 1.94685 2.55881 + endloop + endfacet + facet normal 0.740301 0.00968632 0.672205 + outer loop + vertex 1.14166 1.95385 2.56268 + vertex 1.14219 1.94876 2.56217 + vertex 1.14452 1.95199 2.55956 + endloop + endfacet + facet normal 0.846498 -0.115166 0.519786 + outer loop + vertex 1.14872 1.95347 2.55335 + vertex 1.14883 1.95812 2.55419 + vertex 1.14677 1.95519 2.5569 + endloop + endfacet + facet normal 0.847533 -0.111964 0.518798 + outer loop + vertex 1.14675 1.94993 2.5558 + vertex 1.14872 1.95347 2.55335 + vertex 1.14677 1.95519 2.5569 + endloop + endfacet + facet normal 0.823908 -0.119205 0.554044 + outer loop + vertex 1.14675 1.94993 2.5558 + vertex 1.14677 1.95519 2.5569 + vertex 1.14452 1.95199 2.55956 + endloop + endfacet + facet normal 0.798426 -0.0642019 0.59866 + outer loop + vertex 1.14677 1.95519 2.5569 + vertex 1.14454 1.95678 2.56005 + vertex 1.14452 1.95199 2.55956 + endloop + endfacet + facet normal 0.713187 -0.0740585 0.697051 + outer loop + vertex 1.14454 1.95678 2.56005 + vertex 1.14166 1.95385 2.56268 + vertex 1.14452 1.95199 2.55956 + endloop + endfacet + facet normal 0.68511 -0.0185496 0.728204 + outer loop + vertex 1.14246 1.95817 2.56204 + vertex 1.14166 1.95385 2.56268 + vertex 1.14454 1.95678 2.56005 + endloop + endfacet + facet normal 0.814581 -0.114926 0.568551 + outer loop + vertex 1.14883 1.95812 2.55419 + vertex 1.14891 1.96219 2.55491 + vertex 1.14669 1.96037 2.55771 + endloop + endfacet + facet normal 0.830468 -0.0740727 0.55212 + outer loop + vertex 1.14677 1.95519 2.5569 + vertex 1.14883 1.95812 2.55419 + vertex 1.14669 1.96037 2.55771 + endloop + endfacet + facet normal 0.792684 -0.0828268 0.60398 + outer loop + vertex 1.14677 1.95519 2.5569 + vertex 1.14669 1.96037 2.55771 + vertex 1.14454 1.95678 2.56005 + endloop + endfacet + facet normal 0.754048 -0.0255629 0.656322 + outer loop + vertex 1.14669 1.96037 2.55771 + vertex 1.14429 1.96043 2.56048 + vertex 1.14454 1.95678 2.56005 + endloop + endfacet + facet normal 0.677027 -0.040199 0.734859 + outer loop + vertex 1.14429 1.96043 2.56048 + vertex 1.14246 1.95817 2.56204 + vertex 1.14454 1.95678 2.56005 + endloop + endfacet + facet normal 0.587003 0.0815164 0.805471 + outer loop + vertex 1.14192 1.96163 2.56208 + vertex 1.14246 1.95817 2.56204 + vertex 1.14429 1.96043 2.56048 + endloop + endfacet + facet normal 0.807528 -0.0824939 0.584032 + outer loop + vertex 1.14891 1.96219 2.55491 + vertex 1.14766 1.9645 2.55696 + vertex 1.14669 1.96037 2.55771 + endloop + endfacet + facet normal 0.711449 -0.0430591 0.701418 + outer loop + vertex 1.14766 1.9645 2.55696 + vertex 1.1473 1.96833 2.55756 + vertex 1.14499 1.96452 2.55967 + endloop + endfacet + facet normal 0.711607 -0.0383929 0.701528 + outer loop + vertex 1.14766 1.9645 2.55696 + vertex 1.14499 1.96452 2.55967 + vertex 1.14669 1.96037 2.55771 + endloop + endfacet + facet normal 0.754543 0.000505015 0.65625 + outer loop + vertex 1.14669 1.96037 2.55771 + vertex 1.14499 1.96452 2.55967 + vertex 1.14429 1.96043 2.56048 + endloop + endfacet + facet normal 0.580901 0.0612854 0.811664 + outer loop + vertex 1.14499 1.96452 2.55967 + vertex 1.14192 1.96163 2.56208 + vertex 1.14429 1.96043 2.56048 + endloop + endfacet + facet normal 0.547359 0.111773 0.829401 + outer loop + vertex 1.14148 1.96597 2.56179 + vertex 1.14192 1.96163 2.56208 + vertex 1.14499 1.96452 2.55967 + endloop + endfacet + facet normal 0.624963 0.00318331 0.780648 + outer loop + vertex 1.1473 1.96833 2.55756 + vertex 1.14684 1.97332 2.55791 + vertex 1.14434 1.96941 2.55992 + endloop + endfacet + facet normal 0.633371 0.0438158 0.772606 + outer loop + vertex 1.14499 1.96452 2.55967 + vertex 1.1473 1.96833 2.55756 + vertex 1.14434 1.96941 2.55992 + endloop + endfacet + facet normal 0.524746 0.0252523 0.850884 + outer loop + vertex 1.14434 1.96941 2.55992 + vertex 1.14148 1.96597 2.56179 + vertex 1.14499 1.96452 2.55967 + endloop + endfacet + facet normal 0.420895 0.136525 0.896777 + outer loop + vertex 1.14071 1.97037 2.56148 + vertex 1.14148 1.96597 2.56179 + vertex 1.14434 1.96941 2.55992 + endloop + endfacet + facet normal 0.522567 0.102449 0.846421 + outer loop + vertex 1.14345 1.97316 2.56002 + vertex 1.14434 1.96941 2.55992 + vertex 1.14684 1.97332 2.55791 + endloop + endfacet + facet normal 0.520864 0.120772 0.845053 + outer loop + vertex 1.14345 1.97316 2.56002 + vertex 1.14684 1.97332 2.55791 + vertex 1.1441 1.97752 2.55899 + endloop + endfacet + facet normal 0.457416 0.0687794 0.886589 + outer loop + vertex 1.1441 1.97752 2.55899 + vertex 1.14684 1.97332 2.55791 + vertex 1.14785 1.97769 2.55705 + endloop + endfacet + facet normal 0.4097 0.0742018 0.909197 + outer loop + vertex 1.14434 1.96941 2.55992 + vertex 1.14345 1.97316 2.56002 + vertex 1.14071 1.97037 2.56148 + endloop + endfacet + facet normal 0.457668 0.0650281 0.886742 + outer loop + vertex 1.14785 1.97769 2.55705 + vertex 1.14692 1.98157 2.55724 + vertex 1.1441 1.97752 2.55899 + endloop + endfacet + facet normal 0.345541 0.159725 0.924711 + outer loop + vertex 1.1441 1.97752 2.55899 + vertex 1.14692 1.98157 2.55724 + vertex 1.14296 1.9824 2.55858 + endloop + endfacet + facet normal 0.34215 0.13511 0.929881 + outer loop + vertex 1.14692 1.98157 2.55724 + vertex 1.14554 1.98641 2.55705 + vertex 1.14296 1.9824 2.55858 + endloop + endfacet + facet normal 0.177467 0.219841 0.959258 + outer loop + vertex 1.15038 2.03457 2.54605 + vertex 1.14897 2.03949 2.54518 + vertex 1.14637 2.03621 2.54642 + endloop + endfacet + facet normal 0.185638 0.213354 0.959176 + outer loop + vertex 1.14463 2.03922 2.54608 + vertex 1.14637 2.03621 2.54642 + vertex 1.14897 2.03949 2.54518 + endloop + endfacet + facet normal 0.293433 0.206803 0.933343 + outer loop + vertex 1.14276 2.11319 2.52914 + vertex 1.14672 2.1159 2.52729 + vertex 1.14287 2.11688 2.52829 + endloop + endfacet + facet normal 0.277752 0.207257 0.938029 + outer loop + vertex 1.14966 2.11853 2.52577 + vertex 1.14986 2.12275 2.52478 + vertex 1.14676 2.12056 2.52618 + endloop + endfacet + facet normal 0.285949 0.220019 0.932644 + outer loop + vertex 1.14676 2.12056 2.52618 + vertex 1.14672 2.1159 2.52729 + vertex 1.14966 2.11853 2.52577 + endloop + endfacet + facet normal 0.340395 0.215368 0.915286 + outer loop + vertex 1.14676 2.12056 2.52618 + vertex 1.1428 2.12084 2.52759 + vertex 1.14672 2.1159 2.52729 + endloop + endfacet + facet normal 0.286726 0.17105 0.942619 + outer loop + vertex 1.1428 2.12084 2.52759 + vertex 1.14287 2.11688 2.52829 + vertex 1.14672 2.1159 2.52729 + endloop + endfacet + facet normal 0.311724 0.188458 0.931296 + outer loop + vertex 1.14986 2.12275 2.52478 + vertex 1.14792 2.12841 2.52428 + vertex 1.14534 2.12471 2.5259 + endloop + endfacet + facet normal 0.304693 0.168769 0.937379 + outer loop + vertex 1.14676 2.12056 2.52618 + vertex 1.14986 2.12275 2.52478 + vertex 1.14534 2.12471 2.5259 + endloop + endfacet + facet normal 0.34062 0.180084 0.922793 + outer loop + vertex 1.14534 2.12471 2.5259 + vertex 1.1428 2.12084 2.52759 + vertex 1.14676 2.12056 2.52618 + endloop + endfacet + facet normal 0.369227 0.158229 0.91577 + outer loop + vertex 1.14104 2.12669 2.52729 + vertex 1.1428 2.12084 2.52759 + vertex 1.14534 2.12471 2.5259 + endloop + endfacet + facet normal 0.350821 0.157609 0.923084 + outer loop + vertex 1.14411 2.12875 2.52568 + vertex 1.14534 2.12471 2.5259 + vertex 1.14792 2.12841 2.52428 + endloop + endfacet + facet normal 0.351228 0.179202 0.918981 + outer loop + vertex 1.14411 2.12875 2.52568 + vertex 1.14792 2.12841 2.52428 + vertex 1.14467 2.1327 2.52469 + endloop + endfacet + facet normal 0.342842 0.172415 0.923435 + outer loop + vertex 1.14467 2.1327 2.52469 + vertex 1.14792 2.12841 2.52428 + vertex 1.14808 2.13214 2.52353 + endloop + endfacet + facet normal 0.371043 0.163314 0.914142 + outer loop + vertex 1.14534 2.12471 2.5259 + vertex 1.14411 2.12875 2.52568 + vertex 1.14104 2.12669 2.52729 + endloop + endfacet + facet normal 0.344363 0.190305 0.919347 + outer loop + vertex 1.14808 2.13214 2.52353 + vertex 1.14795 2.13582 2.52282 + vertex 1.14467 2.1327 2.52469 + endloop + endfacet + facet normal 0.278066 0.262764 0.923923 + outer loop + vertex 1.14467 2.1327 2.52469 + vertex 1.14795 2.13582 2.52282 + vertex 1.14252 2.13772 2.52391 + endloop + endfacet + facet normal 0.273997 0.24812 0.929173 + outer loop + vertex 1.14795 2.13582 2.52282 + vertex 1.14602 2.14045 2.52215 + vertex 1.14252 2.13772 2.52391 + endloop + endfacet + facet normal 0.130518 0.413709 0.901005 + outer loop + vertex 1.14252 2.13772 2.52391 + vertex 1.14602 2.14045 2.52215 + vertex 1.14201 2.14151 2.52224 + endloop + endfacet + facet normal 0.106261 0.441862 0.890768 + outer loop + vertex 1.1444 2.14383 2.52075 + vertex 1.14837 2.14283 2.52077 + vertex 1.14802 2.14592 2.51928 + endloop + endfacet + facet normal -0.0386042 0.61835 0.784954 + outer loop + vertex 1.14255 2.14696 2.5182 + vertex 1.1444 2.14383 2.52075 + vertex 1.14802 2.14592 2.51928 + endloop + endfacet + facet normal 0.135317 0.432692 0.891329 + outer loop + vertex 1.14602 2.14045 2.52215 + vertex 1.1444 2.14383 2.52075 + vertex 1.14201 2.14151 2.52224 + endloop + endfacet + facet normal 0.100831 0.42048 0.901681 + outer loop + vertex 1.14837 2.14283 2.52077 + vertex 1.1444 2.14383 2.52075 + vertex 1.14602 2.14045 2.52215 + endloop + endfacet + facet normal -0.28798 0.731136 0.618472 + outer loop + vertex 1.14524 2.1516 2.51468 + vertex 1.14228 2.15161 2.51329 + vertex 1.14251 2.14988 2.51545 + endloop + endfacet + facet normal -0.190542 0.635142 0.748524 + outer loop + vertex 1.14251 2.14988 2.51545 + vertex 1.14745 2.1496 2.51694 + vertex 1.14524 2.1516 2.51468 + endloop + endfacet + facet normal -0.179199 0.672773 0.717819 + outer loop + vertex 1.14251 2.14988 2.51545 + vertex 1.14255 2.14696 2.5182 + vertex 1.14745 2.1496 2.51694 + endloop + endfacet + facet normal -0.0679812 0.527827 0.846627 + outer loop + vertex 1.14255 2.14696 2.5182 + vertex 1.14802 2.14592 2.51928 + vertex 1.14745 2.1496 2.51694 + endloop + endfacet + facet normal -0.0223329 0.872444 0.488203 + outer loop + vertex 1.14532 2.15696 2.50537 + vertex 1.14251 2.15749 2.50429 + vertex 1.14374 2.15582 2.50733 + endloop + endfacet + facet normal -0.187824 0.907617 0.375438 + outer loop + vertex 1.14733 2.15641 2.50769 + vertex 1.14532 2.15696 2.50537 + vertex 1.14374 2.15582 2.50733 + endloop + endfacet + facet normal -0.189573 0.869277 0.456529 + outer loop + vertex 1.14733 2.15641 2.50769 + vertex 1.14374 2.15582 2.50733 + vertex 1.14802 2.15505 2.51058 + endloop + endfacet + facet normal -0.238864 0.825616 0.511177 + outer loop + vertex 1.14802 2.15505 2.51058 + vertex 1.14374 2.15582 2.50733 + vertex 1.14418 2.15333 2.51156 + endloop + endfacet + facet normal -0.24724 0.80996 0.531824 + outer loop + vertex 1.14524 2.1516 2.51468 + vertex 1.14418 2.15333 2.51156 + vertex 1.14228 2.15161 2.51329 + endloop + endfacet + facet normal -0.18159 0.8332 0.522306 + outer loop + vertex 1.14524 2.1516 2.51468 + vertex 1.14915 2.15276 2.51419 + vertex 1.14418 2.15333 2.51156 + endloop + endfacet + facet normal -0.210506 0.79519 0.568647 + outer loop + vertex 1.14915 2.15276 2.51419 + vertex 1.14802 2.15505 2.51058 + vertex 1.14418 2.15333 2.51156 + endloop + endfacet + facet normal -0.113632 0.686198 0.718484 + outer loop + vertex 1.14915 2.15276 2.51419 + vertex 1.14524 2.1516 2.51468 + vertex 1.14745 2.1496 2.51694 + endloop + endfacet + facet normal 0.105452 -0.290332 0.951098 + outer loop + vertex 1.14858 2.16226 2.49925 + vertex 1.14935 2.165 2.5 + vertex 1.145 2.16342 2.5 + endloop + endfacet + facet normal 0.360972 0.766192 0.531648 + outer loop + vertex 1.14858 2.16226 2.49925 + vertex 1.145 2.16342 2.5 + vertex 1.14944 2.16 2.50192 + endloop + endfacet + facet normal 0.0446211 0.53174 0.845731 + outer loop + vertex 1.14944 2.16 2.50192 + vertex 1.145 2.16342 2.5 + vertex 1.14497 2.15866 2.503 + endloop + endfacet + facet normal -0.0727764 0.806073 0.587324 + outer loop + vertex 1.14532 2.15696 2.50537 + vertex 1.14497 2.15866 2.503 + vertex 1.14251 2.15749 2.50429 + endloop + endfacet + facet normal -0.209686 0.780273 0.589242 + outer loop + vertex 1.14532 2.15696 2.50537 + vertex 1.14863 2.15772 2.50554 + vertex 1.14497 2.15866 2.503 + endloop + endfacet + facet normal -0.133393 0.852158 0.505997 + outer loop + vertex 1.14863 2.15772 2.50554 + vertex 1.14944 2.16 2.50192 + vertex 1.14497 2.15866 2.503 + endloop + endfacet + facet normal -0.224586 0.887455 0.402472 + outer loop + vertex 1.14863 2.15772 2.50554 + vertex 1.14532 2.15696 2.50537 + vertex 1.14733 2.15641 2.50769 + endloop + endfacet + facet normal 0.102537 -0.289654 0.951623 + outer loop + vertex 1.15 2.16523 2.5 + vertex 1.14935 2.165 2.5 + vertex 1.14858 2.16226 2.49925 + endloop + endfacet + facet normal -0.825154 0.19846 -0.5289 + outer loop + vertex 1.15316 0.865 2.495 + vertex 1.15158 0.863709 2.49698 + vertex 1.15 0.865 2.49993 + endloop + endfacet + facet normal -0.518281 -0.465638 -0.717333 + outer loop + vertex 1.15316 0.865 2.495 + vertex 1.155 0.862952 2.495 + vertex 1.15158 0.863709 2.49698 + endloop + endfacet + facet normal -0.24543 -0.96792 -0.0538028 + outer loop + vertex 1.155 0.862952 2.495 + vertex 1.1546 0.862938 2.49707 + vertex 1.15158 0.863709 2.49698 + endloop + endfacet + facet normal -0.210704 -0.940439 0.266791 + outer loop + vertex 1.15013 0.86425 2.49925 + vertex 1.15288 0.863662 2.49934 + vertex 1.15126 0.864623 2.50145 + endloop + endfacet + facet normal -0.211708 -0.972529 0.0967792 + outer loop + vertex 1.15013 0.86425 2.49925 + vertex 1.15158 0.863709 2.49698 + vertex 1.15288 0.863662 2.49934 + endloop + endfacet + facet normal -0.249177 -0.961294 0.117576 + outer loop + vertex 1.15158 0.863709 2.49698 + vertex 1.1546 0.862938 2.49707 + vertex 1.15288 0.863662 2.49934 + endloop + endfacet + facet normal -0.12956 -0.936072 0.327084 + outer loop + vertex 1.15288 0.863662 2.49934 + vertex 1.15475 0.864539 2.50259 + vertex 1.15126 0.864623 2.50145 + endloop + endfacet + facet normal -0.297219 -0.904783 0.305005 + outer loop + vertex 1.15013 0.86425 2.49925 + vertex 1.15126 0.864623 2.50145 + vertex 1.14805 0.865621 2.50129 + endloop + endfacet + facet normal -0.157345 -0.896139 0.414943 + outer loop + vertex 1.15126 0.864623 2.50145 + vertex 1.15475 0.864539 2.50259 + vertex 1.15172 0.866173 2.50497 + endloop + endfacet + facet normal -0.289567 -0.861552 0.416988 + outer loop + vertex 1.15126 0.864623 2.50145 + vertex 1.15172 0.866173 2.50497 + vertex 1.14805 0.865621 2.50129 + endloop + endfacet + facet normal -0.232463 -0.901059 0.366134 + outer loop + vertex 1.14805 0.865621 2.50129 + vertex 1.15172 0.866173 2.50497 + vertex 1.14705 0.867312 2.50481 + endloop + endfacet + facet normal -0.228707 -0.877814 0.420876 + outer loop + vertex 1.15172 0.866173 2.50497 + vertex 1.14993 0.868409 2.50866 + vertex 1.14705 0.867312 2.50481 + endloop + endfacet + facet normal -0.118513 -0.873682 0.471842 + outer loop + vertex 1.15464 0.867921 2.50894 + vertex 1.14993 0.868409 2.50866 + vertex 1.15172 0.866173 2.50497 + endloop + endfacet + facet normal -0.118365 -0.833686 0.539404 + outer loop + vertex 1.14993 0.868409 2.50866 + vertex 1.15464 0.867921 2.50894 + vertex 1.153 0.870076 2.51192 + endloop + endfacet + facet normal -0.127235 -0.828603 0.545187 + outer loop + vertex 1.1479 0.870906 2.51199 + vertex 1.14993 0.868409 2.50866 + vertex 1.153 0.870076 2.51192 + endloop + endfacet + facet normal 0.00143177 -0.689459 0.724323 + outer loop + vertex 1.14832 0.872913 2.51517 + vertex 1.1519 0.87245 2.51472 + vertex 1.15041 0.874957 2.51711 + endloop + endfacet + facet normal -0.0418598 -0.842746 0.536681 + outer loop + vertex 1.14832 0.872913 2.51517 + vertex 1.1479 0.870906 2.51199 + vertex 1.1519 0.87245 2.51472 + endloop + endfacet + facet normal -0.118492 -0.780622 0.613668 + outer loop + vertex 1.1479 0.870906 2.51199 + vertex 1.153 0.870076 2.51192 + vertex 1.1519 0.87245 2.51472 + endloop + endfacet + facet normal 0.129234 -0.642759 0.755089 + outer loop + vertex 1.1519 0.87245 2.51472 + vertex 1.15494 0.87532 2.51665 + vertex 1.15041 0.874957 2.51711 + endloop + endfacet + facet normal -0.0121568 -0.682089 0.731168 + outer loop + vertex 1.14832 0.872913 2.51517 + vertex 1.15041 0.874957 2.51711 + vertex 1.14664 0.874602 2.51672 + endloop + endfacet + facet normal -0.0203166 -0.63805 0.769727 + outer loop + vertex 1.15041 0.874957 2.51711 + vertex 1.14732 0.877543 2.51917 + vertex 1.14664 0.874602 2.51672 + endloop + endfacet + facet normal 0.157461 -0.493831 0.855183 + outer loop + vertex 1.15041 0.874957 2.51711 + vertex 1.15314 0.879191 2.51905 + vertex 1.14732 0.877543 2.51917 + endloop + endfacet + facet normal 0.127796 -0.480428 0.867673 + outer loop + vertex 1.15041 0.874957 2.51711 + vertex 1.15494 0.87532 2.51665 + vertex 1.15314 0.879191 2.51905 + endloop + endfacet + facet normal 0.208253 -0.684597 0.69854 + outer loop + vertex 1.15314 0.879191 2.51905 + vertex 1.14991 0.879448 2.52027 + vertex 1.14732 0.877543 2.51917 + endloop + endfacet + facet normal 0.0324701 -0.531145 0.846659 + outer loop + vertex 1.14991 0.879448 2.52027 + vertex 1.14807 0.880813 2.5212 + vertex 1.14732 0.877543 2.51917 + endloop + endfacet + facet normal 0.348048 -0.35251 0.868677 + outer loop + vertex 1.15314 0.879191 2.51905 + vertex 1.15479 0.884095 2.52038 + vertex 1.1513 0.881894 2.52089 + endloop + endfacet + facet normal 0.296802 -0.389593 0.871852 + outer loop + vertex 1.14991 0.879448 2.52027 + vertex 1.15314 0.879191 2.51905 + vertex 1.1513 0.881894 2.52089 + endloop + endfacet + facet normal 0.203809 -0.347645 0.915208 + outer loop + vertex 1.1513 0.881894 2.52089 + vertex 1.14807 0.880813 2.5212 + vertex 1.14991 0.879448 2.52027 + endloop + endfacet + facet normal 0.191408 -0.305644 0.932708 + outer loop + vertex 1.14984 0.884623 2.52208 + vertex 1.14807 0.880813 2.5212 + vertex 1.1513 0.881894 2.52089 + endloop + endfacet + facet normal 0.305931 -0.275843 0.911217 + outer loop + vertex 1.15479 0.884095 2.52038 + vertex 1.15274 0.885189 2.5214 + vertex 1.1513 0.881894 2.52089 + endloop + endfacet + facet normal 0.268371 -0.261953 0.927015 + outer loop + vertex 1.15274 0.885189 2.5214 + vertex 1.14984 0.884623 2.52208 + vertex 1.1513 0.881894 2.52089 + endloop + endfacet + facet normal 0.261154 -0.205673 0.943132 + outer loop + vertex 1.15274 0.885189 2.5214 + vertex 1.15341 0.889067 2.52206 + vertex 1.14984 0.884623 2.52208 + endloop + endfacet + facet normal 0.288276 -0.227515 0.930126 + outer loop + vertex 1.15341 0.889067 2.52206 + vertex 1.14897 0.888774 2.52337 + vertex 1.14984 0.884623 2.52208 + endloop + endfacet + facet normal 0.288323 -0.211514 0.93388 + outer loop + vertex 1.15341 0.889067 2.52206 + vertex 1.1533 0.893911 2.52319 + vertex 1.14897 0.888774 2.52337 + endloop + endfacet + facet normal 0.307137 -0.227701 0.924023 + outer loop + vertex 1.14897 0.888774 2.52337 + vertex 1.1533 0.893911 2.52319 + vertex 1.14849 0.893915 2.52479 + endloop + endfacet + facet normal 0.30915 -0.19878 0.930007 + outer loop + vertex 1.1533 0.893911 2.52319 + vertex 1.15356 0.898947 2.52419 + vertex 1.14849 0.893915 2.52479 + endloop + endfacet + facet normal 0.283733 -0.171595 0.943425 + outer loop + vertex 1.14849 0.893915 2.52479 + vertex 1.15356 0.898947 2.52419 + vertex 1.14977 0.899304 2.52539 + endloop + endfacet + facet normal 0.329412 -0.166115 0.929459 + outer loop + vertex 1.15013 0.902654 2.52586 + vertex 1.14741 0.900212 2.52639 + vertex 1.14977 0.899304 2.52539 + endloop + endfacet + facet normal 0.252719 -0.161337 0.953993 + outer loop + vertex 1.15013 0.902654 2.52586 + vertex 1.14977 0.899304 2.52539 + vertex 1.15386 0.903821 2.52507 + endloop + endfacet + facet normal 0.281385 -0.18816 0.940966 + outer loop + vertex 1.15386 0.903821 2.52507 + vertex 1.14977 0.899304 2.52539 + vertex 1.15356 0.898947 2.52419 + endloop + endfacet + facet normal 0.356454 -0.19994 0.912669 + outer loop + vertex 1.15013 0.902654 2.52586 + vertex 1.14818 0.9042 2.52696 + vertex 1.14741 0.900212 2.52639 + endloop + endfacet + facet normal 0.26011 -0.189821 0.946737 + outer loop + vertex 1.15386 0.903821 2.52507 + vertex 1.15196 0.905544 2.52594 + vertex 1.15013 0.902654 2.52586 + endloop + endfacet + facet normal 0.330787 -0.233561 0.914346 + outer loop + vertex 1.15196 0.905544 2.52594 + vertex 1.14818 0.9042 2.52696 + vertex 1.15013 0.902654 2.52586 + endloop + endfacet + facet normal 0.340378 -0.271196 0.900331 + outer loop + vertex 1.15196 0.905544 2.52594 + vertex 1.15308 0.90929 2.52664 + vertex 1.14818 0.9042 2.52696 + endloop + endfacet + facet normal 0.282466 -0.213309 0.93526 + outer loop + vertex 1.15308 0.90929 2.52664 + vertex 1.14825 0.90909 2.52805 + vertex 1.14818 0.9042 2.52696 + endloop + endfacet + facet normal 0.341861 -0.196855 0.918901 + outer loop + vertex 1.14955 1.0278 2.55566 + vertex 1.14702 1.02541 2.55608 + vertex 1.14876 1.02363 2.55505 + endloop + endfacet + facet normal 0.458291 -0.21083 0.863435 + outer loop + vertex 1.14955 1.0278 2.55566 + vertex 1.14876 1.02363 2.55505 + vertex 1.1528 1.02866 2.55414 + endloop + endfacet + facet normal 0.362982 -0.123479 0.923578 + outer loop + vertex 1.1528 1.02866 2.55414 + vertex 1.14876 1.02363 2.55505 + vertex 1.15271 1.02306 2.55343 + endloop + endfacet + facet normal 0.306869 -0.156284 0.938833 + outer loop + vertex 1.14955 1.0278 2.55566 + vertex 1.14705 1.02859 2.5566 + vertex 1.14702 1.02541 2.55608 + endloop + endfacet + facet normal 0.499423 -0.0859484 0.862084 + outer loop + vertex 1.1528 1.02866 2.55414 + vertex 1.15379 1.03447 2.55415 + vertex 1.15054 1.03178 2.55576 + endloop + endfacet + facet normal 0.447636 -0.134867 0.883987 + outer loop + vertex 1.14955 1.0278 2.55566 + vertex 1.1528 1.02866 2.55414 + vertex 1.15054 1.03178 2.55576 + endloop + endfacet + facet normal 0.323572 -0.105358 0.94032 + outer loop + vertex 1.15054 1.03178 2.55576 + vertex 1.14705 1.02859 2.5566 + vertex 1.14955 1.0278 2.55566 + endloop + endfacet + facet normal 0.349607 -0.137396 0.926767 + outer loop + vertex 1.14731 1.03304 2.55717 + vertex 1.14705 1.02859 2.5566 + vertex 1.15054 1.03178 2.55576 + endloop + endfacet + facet normal 0.536086 -0.0385792 0.843281 + outer loop + vertex 1.15379 1.03447 2.55415 + vertex 1.15398 1.03962 2.55426 + vertex 1.15094 1.03669 2.55606 + endloop + endfacet + facet normal 0.503812 -0.0932119 0.858769 + outer loop + vertex 1.15054 1.03178 2.55576 + vertex 1.15379 1.03447 2.55415 + vertex 1.15094 1.03669 2.55606 + endloop + endfacet + facet normal 0.369037 -0.0862487 0.925404 + outer loop + vertex 1.15094 1.03669 2.55606 + vertex 1.14731 1.03304 2.55717 + vertex 1.15054 1.03178 2.55576 + endloop + endfacet + facet normal 0.404683 -0.127843 0.905477 + outer loop + vertex 1.14752 1.03796 2.55777 + vertex 1.14731 1.03304 2.55717 + vertex 1.15094 1.03669 2.55606 + endloop + endfacet + facet normal 0.583886 -0.014751 0.811702 + outer loop + vertex 1.15398 1.03962 2.55426 + vertex 1.15394 1.04464 2.55438 + vertex 1.15105 1.04169 2.55641 + endloop + endfacet + facet normal 0.556833 -0.0696357 0.8277 + outer loop + vertex 1.15094 1.03669 2.55606 + vertex 1.15398 1.03962 2.55426 + vertex 1.15105 1.04169 2.55641 + endloop + endfacet + facet normal 0.42402 -0.0721854 0.902772 + outer loop + vertex 1.15105 1.04169 2.55641 + vertex 1.14752 1.03796 2.55777 + vertex 1.15094 1.03669 2.55606 + endloop + endfacet + facet normal 0.467265 -0.12295 0.875527 + outer loop + vertex 1.14771 1.04305 2.55838 + vertex 1.14752 1.03796 2.55777 + vertex 1.15105 1.04169 2.55641 + endloop + endfacet + facet normal 0.636558 0.013156 0.771117 + outer loop + vertex 1.15394 1.04464 2.55438 + vertex 1.15391 1.04967 2.55432 + vertex 1.15108 1.04677 2.55671 + endloop + endfacet + facet normal 0.607048 -0.0503199 0.79307 + outer loop + vertex 1.15105 1.04169 2.55641 + vertex 1.15394 1.04464 2.55438 + vertex 1.15108 1.04677 2.55671 + endloop + endfacet + facet normal 0.491538 -0.0541282 0.869172 + outer loop + vertex 1.15108 1.04677 2.55671 + vertex 1.14771 1.04305 2.55838 + vertex 1.15105 1.04169 2.55641 + endloop + endfacet + facet normal 0.531644 -0.103326 0.840642 + outer loop + vertex 1.14773 1.04857 2.55905 + vertex 1.14771 1.04305 2.55838 + vertex 1.15108 1.04677 2.55671 + endloop + endfacet + facet normal 0.69118 0.0477911 0.7211 + outer loop + vertex 1.15391 1.04967 2.55432 + vertex 1.15393 1.05485 2.55396 + vertex 1.15122 1.05197 2.55675 + endloop + endfacet + facet normal 0.658311 -0.0234881 0.75238 + outer loop + vertex 1.15108 1.04677 2.55671 + vertex 1.15391 1.04967 2.55432 + vertex 1.15122 1.05197 2.55675 + endloop + endfacet + facet normal 0.564873 -0.0214358 0.824899 + outer loop + vertex 1.15122 1.05197 2.55675 + vertex 1.14773 1.04857 2.55905 + vertex 1.15108 1.04677 2.55671 + endloop + endfacet + facet normal 0.597254 -0.0723643 0.798781 + outer loop + vertex 1.14855 1.05434 2.55896 + vertex 1.14773 1.04857 2.55905 + vertex 1.15122 1.05197 2.55675 + endloop + endfacet + facet normal 0.738609 0.0641158 0.671078 + outer loop + vertex 1.15393 1.05485 2.55396 + vertex 1.15379 1.06003 2.55361 + vertex 1.15136 1.05713 2.55656 + endloop + endfacet + facet normal 0.714655 0.00479438 0.699461 + outer loop + vertex 1.15122 1.05197 2.55675 + vertex 1.15393 1.05485 2.55396 + vertex 1.15136 1.05713 2.55656 + endloop + endfacet + facet normal 0.642544 0.00916267 0.766194 + outer loop + vertex 1.15136 1.05713 2.55656 + vertex 1.14855 1.05434 2.55896 + vertex 1.15122 1.05197 2.55675 + endloop + endfacet + facet normal 0.658391 -0.0185402 0.752447 + outer loop + vertex 1.1487 1.05945 2.55895 + vertex 1.14855 1.05434 2.55896 + vertex 1.15136 1.05713 2.55656 + endloop + endfacet + facet normal 0.771515 0.0526357 0.63403 + outer loop + vertex 1.15379 1.06003 2.55361 + vertex 1.15355 1.06506 2.55349 + vertex 1.15135 1.06215 2.55641 + endloop + endfacet + facet normal 0.761132 0.0219522 0.648226 + outer loop + vertex 1.15136 1.05713 2.55656 + vertex 1.15379 1.06003 2.55361 + vertex 1.15135 1.06215 2.55641 + endloop + endfacet + facet normal 0.679002 0.0243537 0.733732 + outer loop + vertex 1.15135 1.06215 2.55641 + vertex 1.1487 1.05945 2.55895 + vertex 1.15136 1.05713 2.55656 + endloop + endfacet + facet normal 0.695896 -0.00688757 0.71811 + outer loop + vertex 1.14873 1.06449 2.55897 + vertex 1.1487 1.05945 2.55895 + vertex 1.15135 1.06215 2.55641 + endloop + endfacet + facet normal 0.796073 0.0411626 0.6038 + outer loop + vertex 1.15355 1.06506 2.55349 + vertex 1.15337 1.07003 2.55339 + vertex 1.15131 1.06717 2.55629 + endloop + endfacet + facet normal 0.788857 0.0195908 0.614265 + outer loop + vertex 1.15135 1.06215 2.55641 + vertex 1.15355 1.06506 2.55349 + vertex 1.15131 1.06717 2.55629 + endloop + endfacet + facet normal 0.708488 0.021132 0.705406 + outer loop + vertex 1.15131 1.06717 2.55629 + vertex 1.14873 1.06449 2.55897 + vertex 1.15135 1.06215 2.55641 + endloop + endfacet + facet normal 0.717648 0.00325246 0.696398 + outer loop + vertex 1.14876 1.06959 2.55891 + vertex 1.14873 1.06449 2.55897 + vertex 1.15131 1.06717 2.55629 + endloop + endfacet + facet normal 0.811406 0.0787133 0.579158 + outer loop + vertex 1.15337 1.07003 2.55339 + vertex 1.15316 1.07476 2.55304 + vertex 1.15128 1.07231 2.55601 + endloop + endfacet + facet normal 0.797211 0.0389648 0.602442 + outer loop + vertex 1.15131 1.06717 2.55629 + vertex 1.15337 1.07003 2.55339 + vertex 1.15128 1.07231 2.55601 + endloop + endfacet + facet normal 0.734938 0.0426638 0.676791 + outer loop + vertex 1.15128 1.07231 2.55601 + vertex 1.14876 1.06959 2.55891 + vertex 1.15131 1.06717 2.55629 + endloop + endfacet + facet normal 0.737909 0.0368306 0.673895 + outer loop + vertex 1.14875 1.07482 2.55864 + vertex 1.14876 1.06959 2.55891 + vertex 1.15128 1.07231 2.55601 + endloop + endfacet + facet normal 0.829406 0.218511 0.514138 + outer loop + vertex 1.15316 1.07476 2.55304 + vertex 1.15285 1.0785 2.55195 + vertex 1.15109 1.07803 2.555 + endloop + endfacet + facet normal 0.783475 0.133679 0.606875 + outer loop + vertex 1.15128 1.07231 2.55601 + vertex 1.15316 1.07476 2.55304 + vertex 1.15109 1.07803 2.555 + endloop + endfacet + facet normal 0.775545 0.13514 0.616658 + outer loop + vertex 1.15109 1.07803 2.555 + vertex 1.14875 1.07482 2.55864 + vertex 1.15128 1.07231 2.55601 + endloop + endfacet + facet normal 0.810951 0.0688671 0.581047 + outer loop + vertex 1.14851 1.08005 2.55835 + vertex 1.14875 1.07482 2.55864 + vertex 1.15109 1.07803 2.555 + endloop + endfacet + facet normal -0.0367395 -0.0246324 0.999021 + outer loop + vertex 1.1533 1.08025 2.54989 + vertex 1.155 1.08236 2.55 + vertex 1.15323 1.085 2.55 + endloop + endfacet + facet normal 0.695205 -0.00713523 0.718776 + outer loop + vertex 1.1516 1.08286 2.55156 + vertex 1.1533 1.08025 2.54989 + vertex 1.15323 1.085 2.55 + endloop + endfacet + facet normal 0.857434 0.284647 0.428699 + outer loop + vertex 1.15285 1.0785 2.55195 + vertex 1.1533 1.08025 2.54989 + vertex 1.1516 1.08286 2.55156 + endloop + endfacet + facet normal 0.811587 0.279181 0.513211 + outer loop + vertex 1.15285 1.0785 2.55195 + vertex 1.1516 1.08286 2.55156 + vertex 1.15109 1.07803 2.555 + endloop + endfacet + facet normal 0.907228 0.175854 0.382117 + outer loop + vertex 1.15109 1.07803 2.555 + vertex 1.1516 1.08286 2.55156 + vertex 1.15002 1.08335 2.55508 + endloop + endfacet + facet normal 0.82692 0.157491 0.539814 + outer loop + vertex 1.15002 1.08335 2.55508 + vertex 1.14851 1.08005 2.55835 + vertex 1.15109 1.07803 2.555 + endloop + endfacet + facet normal 0.876786 0.0710914 0.475596 + outer loop + vertex 1.14828 1.085 2.55805 + vertex 1.14851 1.08005 2.55835 + vertex 1.15002 1.08335 2.55508 + endloop + endfacet + facet normal 0.478267 0.248695 0.842266 + outer loop + vertex 1.15323 1.085 2.55 + vertex 1.15063 1.09 2.55 + vertex 1.1516 1.08286 2.55156 + endloop + endfacet + facet normal 0.90458 0.2043 0.374162 + outer loop + vertex 1.15063 1.09 2.55 + vertex 1.15029 1.08694 2.55249 + vertex 1.1516 1.08286 2.55156 + endloop + endfacet + facet normal 0.903705 0.203426 0.376742 + outer loop + vertex 1.1516 1.08286 2.55156 + vertex 1.15029 1.08694 2.55249 + vertex 1.15002 1.08335 2.55508 + endloop + endfacet + facet normal 0.958326 0.1161 0.261021 + outer loop + vertex 1.15029 1.08694 2.55249 + vertex 1.14945 1.08785 2.55518 + vertex 1.15002 1.08335 2.55508 + endloop + endfacet + facet normal 0.881384 0.101526 0.461362 + outer loop + vertex 1.14945 1.08785 2.55518 + vertex 1.14828 1.085 2.55805 + vertex 1.15002 1.08335 2.55508 + endloop + endfacet + facet normal 0.911445 0.0372746 0.40973 + outer loop + vertex 1.14839 1.08883 2.55745 + vertex 1.14828 1.085 2.55805 + vertex 1.14945 1.08785 2.55518 + endloop + endfacet + facet normal 0.493252 0.45702 -0.740159 + outer loop + vertex 1.15 1.09 2.54958 + vertex 1.15 1.09068 2.55 + vertex 1.15063 1.09 2.55 + endloop + endfacet + facet normal 0.559294 0.51821 -0.64703 + outer loop + vertex 1.15 1.095 2.55346 + vertex 1.15063 1.09 2.55 + vertex 1.15 1.09068 2.55 + endloop + endfacet + facet normal 0.839586 -0.233587 0.490441 + outer loop + vertex 1.15 1.095 2.55346 + vertex 1.14956 1.09246 2.553 + vertex 1.15063 1.09 2.55 + endloop + endfacet + facet normal 0.960735 0.103126 0.257592 + outer loop + vertex 1.14956 1.09246 2.553 + vertex 1.15029 1.08694 2.55249 + vertex 1.15063 1.09 2.55 + endloop + endfacet + facet normal 0.943611 0.155787 0.292111 + outer loop + vertex 1.14899 1.09119 2.55553 + vertex 1.14956 1.09246 2.553 + vertex 1.14863 1.09482 2.55476 + endloop + endfacet + facet normal 0.957477 0.103717 0.269222 + outer loop + vertex 1.14899 1.09119 2.55553 + vertex 1.14945 1.08785 2.55518 + vertex 1.14956 1.09246 2.553 + endloop + endfacet + facet normal 0.958591 0.102092 0.265857 + outer loop + vertex 1.14945 1.08785 2.55518 + vertex 1.15029 1.08694 2.55249 + vertex 1.14956 1.09246 2.553 + endloop + endfacet + facet normal 0.916338 0.085515 0.391168 + outer loop + vertex 1.14945 1.08785 2.55518 + vertex 1.14899 1.09119 2.55553 + vertex 1.14839 1.08883 2.55745 + endloop + endfacet + facet normal 0.375535 -0.228174 0.898282 + outer loop + vertex 1.15 1.1 2.55473 + vertex 1.14956 1.09246 2.553 + vertex 1.15 1.095 2.55346 + endloop + endfacet + facet normal -0.619671 -0.141503 0.772001 + outer loop + vertex 1.14909 1.09717 2.55348 + vertex 1.14956 1.09246 2.553 + vertex 1.15 1.1 2.55473 + endloop + endfacet + facet normal 0.907535 0.0480046 0.417224 + outer loop + vertex 1.14909 1.09717 2.55348 + vertex 1.14863 1.09482 2.55476 + vertex 1.14956 1.09246 2.553 + endloop + endfacet + facet normal 0.87085 0.0911628 0.483021 + outer loop + vertex 1.14848 1.09897 2.55423 + vertex 1.14863 1.09482 2.55476 + vertex 1.14909 1.09717 2.55348 + endloop + endfacet + facet normal -0.679604 -0.102203 0.726425 + outer loop + vertex 1.15 1.1 2.55473 + vertex 1.15 1.10192 2.555 + vertex 1.14909 1.09717 2.55348 + endloop + endfacet + facet normal 0.173019 -0.329632 0.92812 + outer loop + vertex 1.14909 1.09717 2.55348 + vertex 1.15 1.10192 2.555 + vertex 1.14848 1.09897 2.55423 + endloop + endfacet + facet normal -0.0271619 0.0331506 0.999081 + outer loop + vertex 1.15155 1.945 2.55 + vertex 1.14967 1.94493 2.54995 + vertex 1.15 1.94373 2.55 + endloop + endfacet + facet normal -0.0264944 0.0148368 0.999539 + outer loop + vertex 1.15435 1.95 2.55 + vertex 1.14967 1.94493 2.54995 + vertex 1.15155 1.945 2.55 + endloop + endfacet + facet normal 0.169856 -0.16626 0.971343 + outer loop + vertex 1.14986 1.94807 2.55045 + vertex 1.14967 1.94493 2.54995 + vertex 1.15435 1.95 2.55 + endloop + endfacet + facet normal 0.789001 -0.13516 0.59934 + outer loop + vertex 1.14986 1.94807 2.55045 + vertex 1.15093 1.95223 2.54999 + vertex 1.14869 1.94973 2.55238 + endloop + endfacet + facet normal 0.0599417 0.0941787 0.993749 + outer loop + vertex 1.14986 1.94807 2.55045 + vertex 1.15435 1.95 2.55 + vertex 1.15093 1.95223 2.54999 + endloop + endfacet + facet normal -0.00148744 6.84088e-05 0.999999 + outer loop + vertex 1.15435 1.95 2.55 + vertex 1.15458 1.955 2.55 + vertex 1.15093 1.95223 2.54999 + endloop + endfacet + facet normal 0.796969 -0.157785 0.583047 + outer loop + vertex 1.15093 1.95223 2.54999 + vertex 1.14872 1.95347 2.55335 + vertex 1.14869 1.94973 2.55238 + endloop + endfacet + facet normal 0.918222 -0.277286 -0.282809 + outer loop + vertex 1.15304 1.955 2.545 + vertex 1.15455 1.96 2.545 + vertex 1.15458 1.955 2.55 + endloop + endfacet + facet normal 0.00240624 0.707104 0.707106 + outer loop + vertex 1.15455 1.96 2.545 + vertex 1.15255 1.9574 2.54761 + vertex 1.15458 1.955 2.55 + endloop + endfacet + facet normal -0.36666 0.482862 0.795239 + outer loop + vertex 1.15458 1.955 2.55 + vertex 1.15255 1.9574 2.54761 + vertex 1.15093 1.95223 2.54999 + endloop + endfacet + facet normal 0.843999 -0.0175978 0.536056 + outer loop + vertex 1.15255 1.9574 2.54761 + vertex 1.15036 1.95624 2.55101 + vertex 1.15093 1.95223 2.54999 + endloop + endfacet + facet normal 0.830693 -0.0246008 0.556187 + outer loop + vertex 1.15036 1.95624 2.55101 + vertex 1.14872 1.95347 2.55335 + vertex 1.15093 1.95223 2.54999 + endloop + endfacet + facet normal 0.868864 -0.109026 0.482897 + outer loop + vertex 1.14883 1.95812 2.55419 + vertex 1.14872 1.95347 2.55335 + vertex 1.15036 1.95624 2.55101 + endloop + endfacet + facet normal 0.717534 0.0172615 0.696309 + outer loop + vertex 1.155 1.96075 2.545 + vertex 1.15332 1.96125 2.54672 + vertex 1.15255 1.9574 2.54761 + endloop + endfacet + facet normal 0.848667 -0.509254 0.142912 + outer loop + vertex 1.15455 1.96 2.545 + vertex 1.155 1.96075 2.545 + vertex 1.15255 1.9574 2.54761 + endloop + endfacet + facet normal 0.871858 -0.155268 0.464495 + outer loop + vertex 1.15332 1.96125 2.54672 + vertex 1.15339 1.96472 2.54774 + vertex 1.15113 1.96135 2.55087 + endloop + endfacet + facet normal 0.881429 -0.0684323 0.467332 + outer loop + vertex 1.15332 1.96125 2.54672 + vertex 1.15113 1.96135 2.55087 + vertex 1.15255 1.9574 2.54761 + endloop + endfacet + facet normal 0.853089 -0.113251 0.509326 + outer loop + vertex 1.15255 1.9574 2.54761 + vertex 1.15113 1.96135 2.55087 + vertex 1.15036 1.95624 2.55101 + endloop + endfacet + facet normal 0.86636 -0.115921 0.485781 + outer loop + vertex 1.15113 1.96135 2.55087 + vertex 1.14883 1.95812 2.55419 + vertex 1.15036 1.95624 2.55101 + endloop + endfacet + facet normal 0.86243 -0.103037 0.495578 + outer loop + vertex 1.14891 1.96219 2.55491 + vertex 1.14883 1.95812 2.55419 + vertex 1.15113 1.96135 2.55087 + endloop + endfacet + facet normal 0.870014 -0.1546 0.46816 + outer loop + vertex 1.15339 1.96472 2.54774 + vertex 1.15361 1.96906 2.54878 + vertex 1.15194 1.96633 2.55097 + endloop + endfacet + facet normal 0.87093 -0.152043 0.467294 + outer loop + vertex 1.15113 1.96135 2.55087 + vertex 1.15339 1.96472 2.54774 + vertex 1.15194 1.96633 2.55097 + endloop + endfacet + facet normal 0.804715 -0.0868951 0.587268 + outer loop + vertex 1.14891 1.96219 2.55491 + vertex 1.14978 1.96639 2.55433 + vertex 1.14766 1.9645 2.55696 + endloop + endfacet + facet normal 0.860943 -0.111061 0.49643 + outer loop + vertex 1.14891 1.96219 2.55491 + vertex 1.15113 1.96135 2.55087 + vertex 1.14978 1.96639 2.55433 + endloop + endfacet + facet normal 0.830769 -0.146962 0.536865 + outer loop + vertex 1.15113 1.96135 2.55087 + vertex 1.15194 1.96633 2.55097 + vertex 1.14978 1.96639 2.55433 + endloop + endfacet + facet normal 0.78582 -0.0229721 0.618028 + outer loop + vertex 1.14978 1.96639 2.55433 + vertex 1.1473 1.96833 2.55756 + vertex 1.14766 1.9645 2.55696 + endloop + endfacet + facet normal 0.846416 -0.139169 0.514015 + outer loop + vertex 1.15361 1.96906 2.54878 + vertex 1.15361 1.97276 2.54977 + vertex 1.15163 1.97081 2.5525 + endloop + endfacet + facet normal 0.854575 -0.114268 0.506601 + outer loop + vertex 1.15194 1.96633 2.55097 + vertex 1.15361 1.96906 2.54878 + vertex 1.15163 1.97081 2.5525 + endloop + endfacet + facet normal 0.833306 -0.126485 0.538148 + outer loop + vertex 1.15194 1.96633 2.55097 + vertex 1.15163 1.97081 2.5525 + vertex 1.14978 1.96639 2.55433 + endloop + endfacet + facet normal 0.793229 -0.0827805 0.603271 + outer loop + vertex 1.15163 1.97081 2.5525 + vertex 1.14928 1.97094 2.55561 + vertex 1.14978 1.96639 2.55433 + endloop + endfacet + facet normal 0.759716 -0.0976291 0.642884 + outer loop + vertex 1.14928 1.97094 2.55561 + vertex 1.1473 1.96833 2.55756 + vertex 1.14978 1.96639 2.55433 + endloop + endfacet + facet normal 0.691215 0.0134665 0.722524 + outer loop + vertex 1.14684 1.97332 2.55791 + vertex 1.1473 1.96833 2.55756 + vertex 1.14928 1.97094 2.55561 + endloop + endfacet + facet normal 0.843116 -0.122417 0.523612 + outer loop + vertex 1.15361 1.97276 2.54977 + vertex 1.1526 1.97493 2.55191 + vertex 1.15163 1.97081 2.5525 + endloop + endfacet + facet normal 0.776224 -0.0868978 0.62444 + outer loop + vertex 1.1526 1.97493 2.55191 + vertex 1.1526 1.97886 2.55246 + vertex 1.15026 1.97536 2.55487 + endloop + endfacet + facet normal 0.775508 -0.091922 0.62461 + outer loop + vertex 1.1526 1.97493 2.55191 + vertex 1.15026 1.97536 2.55487 + vertex 1.15163 1.97081 2.5525 + endloop + endfacet + facet normal 0.793847 -0.0753582 0.60343 + outer loop + vertex 1.15163 1.97081 2.5525 + vertex 1.15026 1.97536 2.55487 + vertex 1.14928 1.97094 2.55561 + endloop + endfacet + facet normal 0.671145 -0.0249499 0.740906 + outer loop + vertex 1.15026 1.97536 2.55487 + vertex 1.14684 1.97332 2.55791 + vertex 1.14928 1.97094 2.55561 + endloop + endfacet + facet normal 0.665273 -0.00667786 0.74657 + outer loop + vertex 1.14785 1.97769 2.55705 + vertex 1.14684 1.97332 2.55791 + vertex 1.15026 1.97536 2.55487 + endloop + endfacet + facet normal 0.728845 -0.0583127 0.682191 + outer loop + vertex 1.1526 1.97886 2.55246 + vertex 1.1525 1.98365 2.55298 + vertex 1.15015 1.9804 2.55521 + endloop + endfacet + facet normal 0.73849 -0.0277397 0.673693 + outer loop + vertex 1.15026 1.97536 2.55487 + vertex 1.1526 1.97886 2.55246 + vertex 1.15015 1.9804 2.55521 + endloop + endfacet + facet normal 0.64921 -0.035614 0.759775 + outer loop + vertex 1.15015 1.9804 2.55521 + vertex 1.14785 1.97769 2.55705 + vertex 1.15026 1.97536 2.55487 + endloop + endfacet + facet normal 0.554253 0.0910291 0.827356 + outer loop + vertex 1.14692 1.98157 2.55724 + vertex 1.14785 1.97769 2.55705 + vertex 1.15015 1.9804 2.55521 + endloop + endfacet + facet normal 0.636158 0.009007 0.771506 + outer loop + vertex 1.1525 1.98365 2.55298 + vertex 1.15193 1.9888 2.55338 + vertex 1.14953 1.98496 2.55541 + endloop + endfacet + facet normal 0.647218 0.0545693 0.760349 + outer loop + vertex 1.15015 1.9804 2.55521 + vertex 1.1525 1.98365 2.55298 + vertex 1.14953 1.98496 2.55541 + endloop + endfacet + facet normal 0.542239 0.0368846 0.839414 + outer loop + vertex 1.14953 1.98496 2.55541 + vertex 1.14692 1.98157 2.55724 + vertex 1.15015 1.9804 2.55521 + endloop + endfacet + facet normal 0.42331 0.156744 0.892323 + outer loop + vertex 1.14554 1.98641 2.55705 + vertex 1.14692 1.98157 2.55724 + vertex 1.14953 1.98496 2.55541 + endloop + endfacet + facet normal 0.537119 0.10558 0.836873 + outer loop + vertex 1.14865 1.98888 2.55548 + vertex 1.14953 1.98496 2.55541 + vertex 1.15193 1.9888 2.55338 + endloop + endfacet + facet normal 0.535414 0.140162 0.832878 + outer loop + vertex 1.14865 1.98888 2.55548 + vertex 1.15193 1.9888 2.55338 + vertex 1.14896 1.99359 2.55448 + endloop + endfacet + facet normal 0.459695 0.0814603 0.884333 + outer loop + vertex 1.14896 1.99359 2.55448 + vertex 1.15193 1.9888 2.55338 + vertex 1.15291 1.99294 2.55249 + endloop + endfacet + facet normal 0.401679 0.0739754 0.912788 + outer loop + vertex 1.14953 1.98496 2.55541 + vertex 1.14865 1.98888 2.55548 + vertex 1.14554 1.98641 2.55705 + endloop + endfacet + facet normal 0.457395 0.0581977 0.887357 + outer loop + vertex 1.15291 1.99294 2.55249 + vertex 1.15245 1.99681 2.55248 + vertex 1.14896 1.99359 2.55448 + endloop + endfacet + facet normal 0.412029 0.117307 0.903588 + outer loop + vertex 1.14896 1.99359 2.55448 + vertex 1.15245 1.99681 2.55248 + vertex 1.14924 1.99847 2.55372 + endloop + endfacet + facet normal 0.401608 0.0913109 0.911248 + outer loop + vertex 1.15245 1.99681 2.55248 + vertex 1.15175 2.00135 2.55233 + vertex 1.14924 1.99847 2.55372 + endloop + endfacet + facet normal 0.178124 0.220001 0.959099 + outer loop + vertex 1.14897 2.03949 2.54518 + vertex 1.15038 2.03457 2.54605 + vertex 1.15454 2.03735 2.54464 + endloop + endfacet + facet normal 0.304596 0.186264 0.934091 + outer loop + vertex 1.14986 2.12275 2.52478 + vertex 1.15195 2.12617 2.52342 + vertex 1.14792 2.12841 2.52428 + endloop + endfacet + facet normal 0.305125 0.187366 0.933699 + outer loop + vertex 1.15195 2.12617 2.52342 + vertex 1.15191 2.13113 2.52244 + vertex 1.14792 2.12841 2.52428 + endloop + endfacet + facet normal 0.312953 0.175677 0.93338 + outer loop + vertex 1.14792 2.12841 2.52428 + vertex 1.15191 2.13113 2.52244 + vertex 1.14808 2.13214 2.52353 + endloop + endfacet + facet normal 0.303326 0.189249 0.933905 + outer loop + vertex 1.15487 2.13379 2.52094 + vertex 1.15503 2.13794 2.52004 + vertex 1.15199 2.13579 2.52147 + endloop + endfacet + facet normal 0.303059 0.18882 0.934078 + outer loop + vertex 1.15199 2.13579 2.52147 + vertex 1.15191 2.13113 2.52244 + vertex 1.15487 2.13379 2.52094 + endloop + endfacet + facet normal 0.31235 0.188047 0.931169 + outer loop + vertex 1.15199 2.13579 2.52147 + vertex 1.14795 2.13582 2.52282 + vertex 1.15191 2.13113 2.52244 + endloop + endfacet + facet normal 0.315923 0.191211 0.929317 + outer loop + vertex 1.14795 2.13582 2.52282 + vertex 1.14808 2.13214 2.52353 + vertex 1.15191 2.13113 2.52244 + endloop + endfacet + facet normal 0.311065 0.244475 0.918406 + outer loop + vertex 1.15503 2.13794 2.52004 + vertex 1.15263 2.14316 2.51946 + vertex 1.15036 2.13954 2.5212 + endloop + endfacet + facet normal 0.298362 0.19637 0.934034 + outer loop + vertex 1.15199 2.13579 2.52147 + vertex 1.15503 2.13794 2.52004 + vertex 1.15036 2.13954 2.5212 + endloop + endfacet + facet normal 0.311572 0.201706 0.928567 + outer loop + vertex 1.15036 2.13954 2.5212 + vertex 1.14795 2.13582 2.52282 + vertex 1.15199 2.13579 2.52147 + endloop + endfacet + facet normal 0.255523 0.241414 0.936177 + outer loop + vertex 1.14602 2.14045 2.52215 + vertex 1.14795 2.13582 2.52282 + vertex 1.15036 2.13954 2.5212 + endloop + endfacet + facet normal 0.262751 0.277446 0.924113 + outer loop + vertex 1.14837 2.14283 2.52077 + vertex 1.15036 2.13954 2.5212 + vertex 1.15263 2.14316 2.51946 + endloop + endfacet + facet normal 0.231756 0.444023 0.865525 + outer loop + vertex 1.14837 2.14283 2.52077 + vertex 1.15263 2.14316 2.51946 + vertex 1.14802 2.14592 2.51928 + endloop + endfacet + facet normal 0.166661 0.339252 0.925814 + outer loop + vertex 1.14802 2.14592 2.51928 + vertex 1.15263 2.14316 2.51946 + vertex 1.15214 2.14768 2.5179 + endloop + endfacet + facet normal 0.260349 0.27613 0.925187 + outer loop + vertex 1.15036 2.13954 2.5212 + vertex 1.14837 2.14283 2.52077 + vertex 1.14602 2.14045 2.52215 + endloop + endfacet + facet normal 0.14782 0.54729 0.823786 + outer loop + vertex 1.15549 2.1496 2.51641 + vertex 1.15418 2.15259 2.51466 + vertex 1.15176 2.15074 2.51633 + endloop + endfacet + facet normal 0.121673 0.465397 0.876699 + outer loop + vertex 1.15176 2.15074 2.51633 + vertex 1.15214 2.14768 2.5179 + vertex 1.15549 2.1496 2.51641 + endloop + endfacet + facet normal 0.00652632 0.45751 0.88918 + outer loop + vertex 1.15176 2.15074 2.51633 + vertex 1.14745 2.1496 2.51694 + vertex 1.15214 2.14768 2.5179 + endloop + endfacet + facet normal 0.0510008 0.541456 0.839181 + outer loop + vertex 1.14745 2.1496 2.51694 + vertex 1.14802 2.14592 2.51928 + vertex 1.15214 2.14768 2.5179 + endloop + endfacet + facet normal -0.152703 0.835155 0.528392 + outer loop + vertex 1.14802 2.15505 2.51058 + vertex 1.15248 2.15488 2.51213 + vertex 1.15092 2.15659 2.50898 + endloop + endfacet + facet normal -0.206714 0.864419 0.458311 + outer loop + vertex 1.14733 2.15641 2.50769 + vertex 1.14802 2.15505 2.51058 + vertex 1.15092 2.15659 2.50898 + endloop + endfacet + facet normal -0.0427932 0.698397 0.71443 + outer loop + vertex 1.15418 2.15259 2.51466 + vertex 1.14915 2.15276 2.51419 + vertex 1.15176 2.15074 2.51633 + endloop + endfacet + facet normal -0.0390331 0.727641 0.684847 + outer loop + vertex 1.15418 2.15259 2.51466 + vertex 1.15248 2.15488 2.51213 + vertex 1.14915 2.15276 2.51419 + endloop + endfacet + facet normal -0.165961 0.809196 0.563612 + outer loop + vertex 1.15248 2.15488 2.51213 + vertex 1.14802 2.15505 2.51058 + vertex 1.14915 2.15276 2.51419 + endloop + endfacet + facet normal -0.0739254 0.676957 0.7323 + outer loop + vertex 1.15176 2.15074 2.51633 + vertex 1.14915 2.15276 2.51419 + vertex 1.14745 2.1496 2.51694 + endloop + endfacet + facet normal -0.133566 0.768159 0.626172 + outer loop + vertex 1.14944 2.16 2.50192 + vertex 1.15443 2.16041 2.50248 + vertex 1.15173 2.16214 2.49977 + endloop + endfacet + facet normal -0.0828651 0.747285 0.659316 + outer loop + vertex 1.14858 2.16226 2.49925 + vertex 1.14944 2.16 2.50192 + vertex 1.15173 2.16214 2.49977 + endloop + endfacet + facet normal -0.123922 0.881329 0.455963 + outer loop + vertex 1.15443 2.16041 2.50248 + vertex 1.14944 2.16 2.50192 + vertex 1.15377 2.15833 2.50632 + endloop + endfacet + facet normal -0.175914 0.850621 0.495477 + outer loop + vertex 1.15377 2.15833 2.50632 + vertex 1.14944 2.16 2.50192 + vertex 1.14863 2.15772 2.50554 + endloop + endfacet + facet normal -0.194087 0.886421 0.420223 + outer loop + vertex 1.15092 2.15659 2.50898 + vertex 1.14863 2.15772 2.50554 + vertex 1.14733 2.15641 2.50769 + endloop + endfacet + facet normal -0.168077 0.897966 0.406703 + outer loop + vertex 1.15377 2.15833 2.50632 + vertex 1.14863 2.15772 2.50554 + vertex 1.15092 2.15659 2.50898 + endloop + endfacet + facet normal -0.167308 -0.165622 0.971894 + outer loop + vertex 1.15173 2.16214 2.49977 + vertex 1.15 2.16523 2.5 + vertex 1.14858 2.16226 2.49925 + endloop + endfacet + facet normal 0.0137577 -0.066144 0.997715 + outer loop + vertex 1.155 2.16627 2.5 + vertex 1.15 2.16523 2.5 + vertex 1.15173 2.16214 2.49977 + endloop + endfacet + facet normal -0.180534 -0.981165 0.0687248 + outer loop + vertex 1.16 0.862032 2.495 + vertex 1.15833 0.862453 2.49662 + vertex 1.155 0.862952 2.495 + endloop + endfacet + facet normal -0.132682 -0.990632 -0.0322954 + outer loop + vertex 1.15833 0.862453 2.49662 + vertex 1.1546 0.862938 2.49707 + vertex 1.155 0.862952 2.495 + endloop + endfacet + facet normal -0.0980684 -0.968363 0.229468 + outer loop + vertex 1.15833 0.862453 2.49662 + vertex 1.15679 0.86334 2.49971 + vertex 1.1546 0.862938 2.49707 + endloop + endfacet + facet normal -0.101275 -0.96743 0.231995 + outer loop + vertex 1.15679 0.86334 2.49971 + vertex 1.15288 0.863662 2.49934 + vertex 1.1546 0.862938 2.49707 + endloop + endfacet + facet normal -0.107072 -0.942715 0.315948 + outer loop + vertex 1.15679 0.86334 2.49971 + vertex 1.15475 0.864539 2.50259 + vertex 1.15288 0.863662 2.49934 + endloop + endfacet + facet normal -0.0522969 -0.934761 0.351407 + outer loop + vertex 1.15948 0.86443 2.50301 + vertex 1.15475 0.864539 2.50259 + vertex 1.15679 0.86334 2.49971 + endloop + endfacet + facet normal -0.0587887 -0.898296 0.435441 + outer loop + vertex 1.15475 0.864539 2.50259 + vertex 1.15948 0.86443 2.50301 + vertex 1.15699 0.866054 2.50602 + endloop + endfacet + facet normal -0.111671 -0.879867 0.461913 + outer loop + vertex 1.15172 0.866173 2.50497 + vertex 1.15475 0.864539 2.50259 + vertex 1.15699 0.866054 2.50602 + endloop + endfacet + facet normal -0.112954 -0.876053 0.468799 + outer loop + vertex 1.15699 0.866054 2.50602 + vertex 1.15464 0.867921 2.50894 + vertex 1.15172 0.866173 2.50497 + endloop + endfacet + facet normal -0.00435395 -0.844173 0.536053 + outer loop + vertex 1.15936 0.868023 2.50914 + vertex 1.15464 0.867921 2.50894 + vertex 1.15699 0.866054 2.50602 + endloop + endfacet + facet normal -0.00659152 -0.817708 0.575595 + outer loop + vertex 1.15464 0.867921 2.50894 + vertex 1.15936 0.868023 2.50914 + vertex 1.15695 0.869687 2.51148 + endloop + endfacet + facet normal -0.0158201 -0.813625 0.581174 + outer loop + vertex 1.153 0.870076 2.51192 + vertex 1.15464 0.867921 2.50894 + vertex 1.15695 0.869687 2.51148 + endloop + endfacet + facet normal 0.00740863 -0.712833 0.701295 + outer loop + vertex 1.15695 0.869687 2.51148 + vertex 1.15677 0.872316 2.51415 + vertex 1.153 0.870076 2.51192 + endloop + endfacet + facet normal 0.0563036 -0.751374 0.65747 + outer loop + vertex 1.15677 0.872316 2.51415 + vertex 1.1519 0.87245 2.51472 + vertex 1.153 0.870076 2.51192 + endloop + endfacet + facet normal 0.0756849 -0.609149 0.789436 + outer loop + vertex 1.15677 0.872316 2.51415 + vertex 1.15494 0.87532 2.51665 + vertex 1.1519 0.87245 2.51472 + endloop + endfacet + facet normal 0.161441 -0.570132 0.805535 + outer loop + vertex 1.15926 0.875734 2.51607 + vertex 1.15494 0.87532 2.51665 + vertex 1.15677 0.872316 2.51415 + endloop + endfacet + facet normal 0.157568 -0.388388 0.907925 + outer loop + vertex 1.15926 0.875734 2.51607 + vertex 1.15855 0.879257 2.5177 + vertex 1.15494 0.87532 2.51665 + endloop + endfacet + facet normal 0.22281 -0.438298 0.870776 + outer loop + vertex 1.15494 0.87532 2.51665 + vertex 1.15855 0.879257 2.5177 + vertex 1.15314 0.879191 2.51905 + endloop + endfacet + facet normal 0.235186 -0.290335 0.927574 + outer loop + vertex 1.15855 0.879257 2.5177 + vertex 1.15851 0.883733 2.51911 + vertex 1.15314 0.879191 2.51905 + endloop + endfacet + facet normal 0.274512 -0.336439 0.900806 + outer loop + vertex 1.15314 0.879191 2.51905 + vertex 1.15851 0.883733 2.51911 + vertex 1.15479 0.884095 2.52038 + endloop + endfacet + facet normal 0.293083 -0.235831 0.926545 + outer loop + vertex 1.15878 0.88852 2.52025 + vertex 1.15479 0.884095 2.52038 + vertex 1.15851 0.883733 2.51911 + endloop + endfacet + facet normal 0.48469 -0.11087 0.867631 + outer loop + vertex 1.15721 1.0084 2.54952 + vertex 1.15937 1.01362 2.54898 + vertex 1.15573 1.01182 2.55078 + endloop + endfacet + facet normal 0.377135 -0.172833 0.909889 + outer loop + vertex 1.15438 1.00821 2.55066 + vertex 1.15721 1.0084 2.54952 + vertex 1.15573 1.01182 2.55078 + endloop + endfacet + facet normal 0.319568 -0.15227 0.935249 + outer loop + vertex 1.15573 1.01182 2.55078 + vertex 1.15285 1.00983 2.55144 + vertex 1.15438 1.00821 2.55066 + endloop + endfacet + facet normal 0.316095 -0.146564 0.937338 + outer loop + vertex 1.15268 1.01324 2.55203 + vertex 1.15285 1.00983 2.55144 + vertex 1.15573 1.01182 2.55078 + endloop + endfacet + facet normal 0.52927 -0.0259235 0.848057 + outer loop + vertex 1.15937 1.01362 2.54898 + vertex 1.15971 1.01981 2.54896 + vertex 1.15622 1.01652 2.55103 + endloop + endfacet + facet normal 0.479773 -0.096414 0.872079 + outer loop + vertex 1.15573 1.01182 2.55078 + vertex 1.15937 1.01362 2.54898 + vertex 1.15622 1.01652 2.55103 + endloop + endfacet + facet normal 0.343665 -0.0853357 0.935207 + outer loop + vertex 1.15622 1.01652 2.55103 + vertex 1.15268 1.01324 2.55203 + vertex 1.15573 1.01182 2.55078 + endloop + endfacet + facet normal 0.379593 -0.129949 0.915982 + outer loop + vertex 1.15263 1.01794 2.55272 + vertex 1.15268 1.01324 2.55203 + vertex 1.15622 1.01652 2.55103 + endloop + endfacet + facet normal 0.574264 -0.0391349 0.817734 + outer loop + vertex 1.15971 1.01981 2.54896 + vertex 1.15904 1.02516 2.54968 + vertex 1.15621 1.0217 2.5515 + endloop + endfacet + facet normal 0.560631 -0.0738791 0.824764 + outer loop + vertex 1.15622 1.01652 2.55103 + vertex 1.15971 1.01981 2.54896 + vertex 1.15621 1.0217 2.5515 + endloop + endfacet + facet normal 0.397291 -0.0825414 0.913973 + outer loop + vertex 1.15621 1.0217 2.5515 + vertex 1.15263 1.01794 2.55272 + vertex 1.15622 1.01652 2.55103 + endloop + endfacet + facet normal 0.438421 -0.129593 0.889378 + outer loop + vertex 1.15271 1.02306 2.55343 + vertex 1.15263 1.01794 2.55272 + vertex 1.15621 1.0217 2.5515 + endloop + endfacet + facet normal 0.608748 -0.0301048 0.792792 + outer loop + vertex 1.15904 1.02516 2.54968 + vertex 1.15856 1.02932 2.55021 + vertex 1.15611 1.02675 2.55199 + endloop + endfacet + facet normal 0.595649 -0.0656048 0.800561 + outer loop + vertex 1.15621 1.0217 2.5515 + vertex 1.15904 1.02516 2.54968 + vertex 1.15611 1.02675 2.55199 + endloop + endfacet + facet normal 0.457202 -0.0766225 0.886056 + outer loop + vertex 1.15611 1.02675 2.55199 + vertex 1.15271 1.02306 2.55343 + vertex 1.15621 1.0217 2.5515 + endloop + endfacet + facet normal 0.491996 -0.117692 0.862606 + outer loop + vertex 1.1528 1.02866 2.55414 + vertex 1.15271 1.02306 2.55343 + vertex 1.15611 1.02675 2.55199 + endloop + endfacet + facet normal 0.661067 0.0218988 0.750007 + outer loop + vertex 1.15856 1.02932 2.55021 + vertex 1.15953 1.03373 2.54922 + vertex 1.15639 1.03176 2.55205 + endloop + endfacet + facet normal 0.617391 -0.043463 0.785455 + outer loop + vertex 1.15611 1.02675 2.55199 + vertex 1.15856 1.02932 2.55021 + vertex 1.15639 1.03176 2.55205 + endloop + endfacet + facet normal 0.528065 -0.0391401 0.848301 + outer loop + vertex 1.15639 1.03176 2.55205 + vertex 1.1528 1.02866 2.55414 + vertex 1.15611 1.02675 2.55199 + endloop + endfacet + facet normal 0.561955 -0.0965025 0.82152 + outer loop + vertex 1.15379 1.03447 2.55415 + vertex 1.1528 1.02866 2.55414 + vertex 1.15639 1.03176 2.55205 + endloop + endfacet + facet normal 0.698252 0.0226274 0.715494 + outer loop + vertex 1.15953 1.03373 2.54922 + vertex 1.1593 1.03933 2.54927 + vertex 1.15668 1.03692 2.5519 + endloop + endfacet + facet normal 0.674679 -0.0172888 0.737909 + outer loop + vertex 1.15639 1.03176 2.55205 + vertex 1.15953 1.03373 2.54922 + vertex 1.15668 1.03692 2.5519 + endloop + endfacet + facet normal 0.619475 -0.0128353 0.784911 + outer loop + vertex 1.15668 1.03692 2.5519 + vertex 1.15379 1.03447 2.55415 + vertex 1.15639 1.03176 2.55205 + endloop + endfacet + facet normal 0.633511 -0.0407187 0.772662 + outer loop + vertex 1.15398 1.03962 2.55426 + vertex 1.15379 1.03447 2.55415 + vertex 1.15668 1.03692 2.5519 + endloop + endfacet + facet normal 0.719086 0.0366221 0.693955 + outer loop + vertex 1.1593 1.03933 2.54927 + vertex 1.15915 1.04456 2.54915 + vertex 1.15662 1.04208 2.5519 + endloop + endfacet + facet normal 0.704986 0.0084076 0.709171 + outer loop + vertex 1.15668 1.03692 2.5519 + vertex 1.1593 1.03933 2.54927 + vertex 1.15662 1.04208 2.5519 + endloop + endfacet + facet normal 0.661931 0.00787097 0.749524 + outer loop + vertex 1.15662 1.04208 2.5519 + vertex 1.15398 1.03962 2.55426 + vertex 1.15668 1.03692 2.5519 + endloop + endfacet + facet normal 0.672314 -0.0122138 0.740166 + outer loop + vertex 1.15394 1.04464 2.55438 + vertex 1.15398 1.03962 2.55426 + vertex 1.15662 1.04208 2.5519 + endloop + endfacet + facet normal 0.741228 0.0712987 0.667456 + outer loop + vertex 1.15915 1.04456 2.54915 + vertex 1.15899 1.04986 2.54877 + vertex 1.15652 1.04719 2.55179 + endloop + endfacet + facet normal 0.722601 0.0293396 0.690642 + outer loop + vertex 1.15662 1.04208 2.5519 + vertex 1.15915 1.04456 2.54915 + vertex 1.15652 1.04719 2.55179 + endloop + endfacet + facet normal 0.693313 0.02945 0.720035 + outer loop + vertex 1.15652 1.04719 2.55179 + vertex 1.15394 1.04464 2.55438 + vertex 1.15662 1.04208 2.5519 + endloop + endfacet + facet normal 0.70188 0.0127929 0.712181 + outer loop + vertex 1.15391 1.04967 2.55432 + vertex 1.15394 1.04464 2.55438 + vertex 1.15652 1.04719 2.55179 + endloop + endfacet + facet normal 0.771121 0.132661 0.622715 + outer loop + vertex 1.15899 1.04986 2.54877 + vertex 1.15861 1.05502 2.54813 + vertex 1.15645 1.05241 2.55136 + endloop + endfacet + facet normal 0.74476 0.0643653 0.664221 + outer loop + vertex 1.15652 1.04719 2.55179 + vertex 1.15899 1.04986 2.54877 + vertex 1.15645 1.05241 2.55136 + endloop + endfacet + facet normal 0.725684 0.0658082 0.684874 + outer loop + vertex 1.15645 1.05241 2.55136 + vertex 1.15391 1.04967 2.55432 + vertex 1.15652 1.04719 2.55179 + endloop + endfacet + facet normal 0.73683 0.0443684 0.674621 + outer loop + vertex 1.15393 1.05485 2.55396 + vertex 1.15391 1.04967 2.55432 + vertex 1.15645 1.05241 2.55136 + endloop + endfacet + facet normal 0.814206 0.206977 0.542429 + outer loop + vertex 1.15861 1.05502 2.54813 + vertex 1.15824 1.059 2.54717 + vertex 1.15638 1.05817 2.55029 + endloop + endfacet + facet normal 0.774695 0.125948 0.619664 + outer loop + vertex 1.15645 1.05241 2.55136 + vertex 1.15861 1.05502 2.54813 + vertex 1.15638 1.05817 2.55029 + endloop + endfacet + facet normal 0.768308 0.127283 0.627297 + outer loop + vertex 1.15638 1.05817 2.55029 + vertex 1.15393 1.05485 2.55396 + vertex 1.15645 1.05241 2.55136 + endloop + endfacet + facet normal 0.804407 0.0604333 0.590997 + outer loop + vertex 1.15379 1.06003 2.55361 + vertex 1.15393 1.05485 2.55396 + vertex 1.15638 1.05817 2.55029 + endloop + endfacet + facet normal 0.866049 0.263329 0.424991 + outer loop + vertex 1.1585 1.06099 2.54527 + vertex 1.15802 1.0639 2.54446 + vertex 1.15709 1.06304 2.54688 + endloop + endfacet + facet normal 0.868874 0.276772 0.410433 + outer loop + vertex 1.15824 1.059 2.54717 + vertex 1.1585 1.06099 2.54527 + vertex 1.15709 1.06304 2.54688 + endloop + endfacet + facet normal 0.79458 0.265263 0.546148 + outer loop + vertex 1.15824 1.059 2.54717 + vertex 1.15709 1.06304 2.54688 + vertex 1.15638 1.05817 2.55029 + endloop + endfacet + facet normal 0.899925 0.153256 0.408224 + outer loop + vertex 1.15638 1.05817 2.55029 + vertex 1.15709 1.06304 2.54688 + vertex 1.15544 1.06347 2.55036 + endloop + endfacet + facet normal 0.817964 0.136739 0.558781 + outer loop + vertex 1.15544 1.06347 2.55036 + vertex 1.15379 1.06003 2.55361 + vertex 1.15638 1.05817 2.55029 + endloop + endfacet + facet normal 0.866759 0.0537522 0.495823 + outer loop + vertex 1.15355 1.06506 2.55349 + vertex 1.15379 1.06003 2.55361 + vertex 1.15544 1.06347 2.55036 + endloop + endfacet + facet normal -0.175696 -0.12832 0.976046 + outer loop + vertex 1.15802 1.0639 2.54446 + vertex 1.16 1.06529 2.545 + vertex 1.15656 1.07 2.545 + endloop + endfacet + facet normal 0.896249 0.178143 0.406206 + outer loop + vertex 1.15802 1.0639 2.54446 + vertex 1.15656 1.07 2.545 + vertex 1.15709 1.06304 2.54688 + endloop + endfacet + facet normal 0.88901 0.181427 0.420412 + outer loop + vertex 1.15709 1.06304 2.54688 + vertex 1.15656 1.07 2.545 + vertex 1.15587 1.06716 2.54768 + endloop + endfacet + facet normal 0.896203 0.187089 0.402267 + outer loop + vertex 1.15709 1.06304 2.54688 + vertex 1.15587 1.06716 2.54768 + vertex 1.15544 1.06347 2.55036 + endloop + endfacet + facet normal 0.944827 0.112844 0.307518 + outer loop + vertex 1.15587 1.06716 2.54768 + vertex 1.15483 1.06839 2.55043 + vertex 1.15544 1.06347 2.55036 + endloop + endfacet + facet normal 0.873699 0.101426 0.475777 + outer loop + vertex 1.15483 1.06839 2.55043 + vertex 1.15355 1.06506 2.55349 + vertex 1.15544 1.06347 2.55036 + endloop + endfacet + facet normal 0.904944 0.0415217 0.4235 + outer loop + vertex 1.15337 1.07003 2.55339 + vertex 1.15355 1.06506 2.55349 + vertex 1.15483 1.06839 2.55043 + endloop + endfacet + facet normal 0.593006 0.560658 -0.577933 + outer loop + vertex 1.155 1.075 2.54825 + vertex 1.15656 1.07 2.545 + vertex 1.155 1.07165 2.545 + endloop + endfacet + facet normal 0.849053 -0.0750092 0.522956 + outer loop + vertex 1.155 1.075 2.54825 + vertex 1.15503 1.07261 2.54786 + vertex 1.15656 1.07 2.545 + endloop + endfacet + facet normal 0.918526 0.129812 0.373442 + outer loop + vertex 1.15503 1.07261 2.54786 + vertex 1.15587 1.06716 2.54768 + vertex 1.15656 1.07 2.545 + endloop + endfacet + facet normal 0.945046 0.136367 0.297138 + outer loop + vertex 1.15587 1.06716 2.54768 + vertex 1.15503 1.07261 2.54786 + vertex 1.15483 1.06839 2.55043 + endloop + endfacet + facet normal 0.970971 0.0892451 0.221926 + outer loop + vertex 1.15503 1.07261 2.54786 + vertex 1.15435 1.07316 2.55059 + vertex 1.15483 1.06839 2.55043 + endloop + endfacet + facet normal 0.910438 0.0771856 0.40638 + outer loop + vertex 1.15435 1.07316 2.55059 + vertex 1.15337 1.07003 2.55339 + vertex 1.15483 1.06839 2.55043 + endloop + endfacet + facet normal 0.913924 0.0701912 0.399769 + outer loop + vertex 1.15316 1.07476 2.55304 + vertex 1.15337 1.07003 2.55339 + vertex 1.15435 1.07316 2.55059 + endloop + endfacet + facet normal 0.960507 0.0561402 -0.272534 + outer loop + vertex 1.155 1.08 2.54928 + vertex 1.15503 1.07261 2.54786 + vertex 1.155 1.075 2.54825 + endloop + endfacet + facet normal 0.348582 -0.175521 0.920697 + outer loop + vertex 1.15427 1.07724 2.54903 + vertex 1.15503 1.07261 2.54786 + vertex 1.155 1.08 2.54928 + endloop + endfacet + facet normal 0.970208 0.104262 0.218691 + outer loop + vertex 1.15503 1.07261 2.54786 + vertex 1.15427 1.07724 2.54903 + vertex 1.15435 1.07316 2.55059 + endloop + endfacet + facet normal 0.956143 0.122145 0.266215 + outer loop + vertex 1.15427 1.07724 2.54903 + vertex 1.15385 1.07675 2.55076 + vertex 1.15435 1.07316 2.55059 + endloop + endfacet + facet normal 0.920041 0.111825 0.375527 + outer loop + vertex 1.15385 1.07675 2.55076 + vertex 1.15316 1.07476 2.55304 + vertex 1.15435 1.07316 2.55059 + endloop + endfacet + facet normal 0.87564 0.200586 0.43934 + outer loop + vertex 1.15285 1.0785 2.55195 + vertex 1.15316 1.07476 2.55304 + vertex 1.15385 1.07675 2.55076 + endloop + endfacet + facet normal 0.612486 -0.230676 0.756075 + outer loop + vertex 1.155 1.08 2.54928 + vertex 1.155 1.08236 2.55 + vertex 1.15427 1.07724 2.54903 + endloop + endfacet + facet normal 0.932654 0.217673 0.287706 + outer loop + vertex 1.15427 1.07724 2.54903 + vertex 1.1533 1.08025 2.54989 + vertex 1.15385 1.07675 2.55076 + endloop + endfacet + facet normal 0.19445 -0.209154 0.958355 + outer loop + vertex 1.155 1.08236 2.55 + vertex 1.1533 1.08025 2.54989 + vertex 1.15427 1.07724 2.54903 + endloop + endfacet + facet normal 0.887424 0.237431 0.3951 + outer loop + vertex 1.15385 1.07675 2.55076 + vertex 1.1533 1.08025 2.54989 + vertex 1.15285 1.0785 2.55195 + endloop + endfacet + facet normal -0.0313682 0.0245776 0.999206 + outer loop + vertex 1.15539 1.96433 2.54492 + vertex 1.155 1.96075 2.545 + vertex 1.15833 1.965 2.545 + endloop + endfacet + facet normal 0.704972 -0.0607938 0.706624 + outer loop + vertex 1.15332 1.96125 2.54672 + vertex 1.155 1.96075 2.545 + vertex 1.15539 1.96433 2.54492 + endloop + endfacet + facet normal 0.789638 -0.188843 0.58379 + outer loop + vertex 1.15539 1.96433 2.54492 + vertex 1.15339 1.96472 2.54774 + vertex 1.15332 1.96125 2.54672 + endloop + endfacet + facet normal -0.0270546 0.00546536 0.999619 + outer loop + vertex 1.15833 1.965 2.545 + vertex 1.15934 1.97 2.545 + vertex 1.15539 1.96433 2.54492 + endloop + endfacet + facet normal 0.208854 -0.158722 0.96498 + outer loop + vertex 1.15934 1.97 2.545 + vertex 1.15578 1.9685 2.54552 + vertex 1.15539 1.96433 2.54492 + endloop + endfacet + facet normal 0.795947 -0.158771 0.584174 + outer loop + vertex 1.15578 1.9685 2.54552 + vertex 1.15339 1.96472 2.54774 + vertex 1.15539 1.96433 2.54492 + endloop + endfacet + facet normal 0.805203 -0.174894 0.566622 + outer loop + vertex 1.15361 1.96906 2.54878 + vertex 1.15339 1.96472 2.54774 + vertex 1.15578 1.9685 2.54552 + endloop + endfacet + facet normal 0.150462 -0.011734 0.988546 + outer loop + vertex 1.15934 1.97 2.545 + vertex 1.15973 1.975 2.545 + vertex 1.15578 1.9685 2.54552 + endloop + endfacet + facet normal 0.357233 -0.142819 0.923032 + outer loop + vertex 1.15973 1.975 2.545 + vertex 1.15571 1.97293 2.54624 + vertex 1.15578 1.9685 2.54552 + endloop + endfacet + facet normal 0.823392 -0.0777834 0.562117 + outer loop + vertex 1.15571 1.97293 2.54624 + vertex 1.15361 1.96906 2.54878 + vertex 1.15578 1.9685 2.54552 + endloop + endfacet + facet normal 0.855131 -0.135527 0.500383 + outer loop + vertex 1.15361 1.97276 2.54977 + vertex 1.15361 1.96906 2.54878 + vertex 1.15571 1.97293 2.54624 + endloop + endfacet + facet normal 0.747612 0.0808277 0.659199 + outer loop + vertex 1.16 1.97716 2.54 + vertex 1.1597 1.97877 2.54014 + vertex 1.15793 1.97618 2.54247 + endloop + endfacet + facet normal 0.753615 -0.491956 0.43594 + outer loop + vertex 1.16 1.97716 2.54 + vertex 1.15793 1.97618 2.54247 + vertex 1.15859 1.975 2.54 + endloop + endfacet + facet normal 0.685314 0.711288 -0.156248 + outer loop + vertex 1.15859 1.975 2.54 + vertex 1.15793 1.97618 2.54247 + vertex 1.15973 1.975 2.545 + endloop + endfacet + facet normal -0.244445 0.801426 0.545861 + outer loop + vertex 1.15973 1.975 2.545 + vertex 1.15793 1.97618 2.54247 + vertex 1.15571 1.97293 2.54624 + endloop + endfacet + facet normal 0.877925 -0.0480163 0.476385 + outer loop + vertex 1.15793 1.97618 2.54247 + vertex 1.15617 1.97611 2.5457 + vertex 1.15571 1.97293 2.54624 + endloop + endfacet + facet normal 0.853314 -0.104941 0.510727 + outer loop + vertex 1.15361 1.97276 2.54977 + vertex 1.15462 1.97668 2.54889 + vertex 1.1526 1.97493 2.55191 + endloop + endfacet + facet normal 0.85749 -0.107736 0.503095 + outer loop + vertex 1.15361 1.97276 2.54977 + vertex 1.15571 1.97293 2.54624 + vertex 1.15462 1.97668 2.54889 + endloop + endfacet + facet normal 0.894035 -0.0557193 0.444518 + outer loop + vertex 1.15571 1.97293 2.54624 + vertex 1.15617 1.97611 2.5457 + vertex 1.15462 1.97668 2.54889 + endloop + endfacet + facet normal 0.847643 -0.0730487 0.525514 + outer loop + vertex 1.15462 1.97668 2.54889 + vertex 1.1526 1.97886 2.55246 + vertex 1.1526 1.97493 2.55191 + endloop + endfacet + facet normal 0.840034 -0.0945133 0.534237 + outer loop + vertex 1.1597 1.97877 2.54014 + vertex 1.15868 1.97999 2.54197 + vertex 1.15793 1.97618 2.54247 + endloop + endfacet + facet normal 0.879898 -0.188238 0.436287 + outer loop + vertex 1.15868 1.97999 2.54197 + vertex 1.15889 1.98394 2.54324 + vertex 1.15685 1.97984 2.5456 + endloop + endfacet + facet normal 0.88869 -0.115846 0.443632 + outer loop + vertex 1.15868 1.97999 2.54197 + vertex 1.15685 1.97984 2.5456 + vertex 1.15793 1.97618 2.54247 + endloop + endfacet + facet normal 0.870557 -0.144126 0.470488 + outer loop + vertex 1.15793 1.97618 2.54247 + vertex 1.15685 1.97984 2.5456 + vertex 1.15617 1.97611 2.5457 + endloop + endfacet + facet normal 0.879197 -0.146166 0.453484 + outer loop + vertex 1.15617 1.97611 2.5457 + vertex 1.15685 1.97984 2.5456 + vertex 1.15462 1.97668 2.54889 + endloop + endfacet + facet normal 0.870437 -0.113362 0.479049 + outer loop + vertex 1.15685 1.97984 2.5456 + vertex 1.15482 1.98185 2.54975 + vertex 1.15462 1.97668 2.54889 + endloop + endfacet + facet normal 0.82915 -0.122765 0.54538 + outer loop + vertex 1.15482 1.98185 2.54975 + vertex 1.1526 1.97886 2.55246 + vertex 1.15462 1.97668 2.54889 + endloop + endfacet + facet normal 0.797226 -0.0480665 0.601764 + outer loop + vertex 1.1525 1.98365 2.55298 + vertex 1.1526 1.97886 2.55246 + vertex 1.15482 1.98185 2.54975 + endloop + endfacet + facet normal 0.860982 -0.163008 0.481807 + outer loop + vertex 1.15889 1.98394 2.54324 + vertex 1.15909 1.98868 2.54449 + vertex 1.157 1.98525 2.54707 + endloop + endfacet + facet normal 0.863411 -0.154733 0.480186 + outer loop + vertex 1.15685 1.97984 2.5456 + vertex 1.15889 1.98394 2.54324 + vertex 1.157 1.98525 2.54707 + endloop + endfacet + facet normal 0.855348 -0.158095 0.493341 + outer loop + vertex 1.15685 1.97984 2.5456 + vertex 1.157 1.98525 2.54707 + vertex 1.15482 1.98185 2.54975 + endloop + endfacet + facet normal 0.825726 -0.0888476 0.55703 + outer loop + vertex 1.157 1.98525 2.54707 + vertex 1.15482 1.98681 2.55055 + vertex 1.15482 1.98185 2.54975 + endloop + endfacet + facet normal 0.780251 -0.0987084 0.617629 + outer loop + vertex 1.15482 1.98681 2.55055 + vertex 1.1525 1.98365 2.55298 + vertex 1.15482 1.98185 2.54975 + endloop + endfacet + facet normal 0.707871 0.0220724 0.705997 + outer loop + vertex 1.15193 1.9888 2.55338 + vertex 1.1525 1.98365 2.55298 + vertex 1.15482 1.98681 2.55055 + endloop + endfacet + facet normal 0.82934 -0.146653 0.539155 + outer loop + vertex 1.15909 1.98868 2.54449 + vertex 1.15917 1.99256 2.54542 + vertex 1.15705 1.99052 2.54813 + endloop + endfacet + facet normal 0.840572 -0.114861 0.529383 + outer loop + vertex 1.157 1.98525 2.54707 + vertex 1.15909 1.98868 2.54449 + vertex 1.15705 1.99052 2.54813 + endloop + endfacet + facet normal 0.815649 -0.121891 0.565561 + outer loop + vertex 1.157 1.98525 2.54707 + vertex 1.15705 1.99052 2.54813 + vertex 1.15482 1.98681 2.55055 + endloop + endfacet + facet normal 0.772607 -0.0521525 0.632739 + outer loop + vertex 1.15705 1.99052 2.54813 + vertex 1.15464 1.99077 2.55109 + vertex 1.15482 1.98681 2.55055 + endloop + endfacet + facet normal 0.673482 -0.0705792 0.735827 + outer loop + vertex 1.15464 1.99077 2.55109 + vertex 1.15193 1.9888 2.55338 + vertex 1.15482 1.98681 2.55055 + endloop + endfacet + facet normal 0.639513 0.0141487 0.76865 + outer loop + vertex 1.15291 1.99294 2.55249 + vertex 1.15193 1.9888 2.55338 + vertex 1.15464 1.99077 2.55109 + endloop + endfacet + facet normal 0.820047 -0.106125 0.562371 + outer loop + vertex 1.15917 1.99256 2.54542 + vertex 1.15811 1.99463 2.54736 + vertex 1.15705 1.99052 2.54813 + endloop + endfacet + facet normal 0.740816 -0.0680964 0.668247 + outer loop + vertex 1.15811 1.99463 2.54736 + vertex 1.15792 1.99838 2.54795 + vertex 1.15562 1.99485 2.55014 + endloop + endfacet + facet normal 0.741012 -0.0658943 0.668251 + outer loop + vertex 1.15811 1.99463 2.54736 + vertex 1.15562 1.99485 2.55014 + vertex 1.15705 1.99052 2.54813 + endloop + endfacet + facet normal 0.773661 -0.0384259 0.632434 + outer loop + vertex 1.15705 1.99052 2.54813 + vertex 1.15562 1.99485 2.55014 + vertex 1.15464 1.99077 2.55109 + endloop + endfacet + facet normal 0.645663 0.0225387 0.76329 + outer loop + vertex 1.15562 1.99485 2.55014 + vertex 1.15291 1.99294 2.55249 + vertex 1.15464 1.99077 2.55109 + endloop + endfacet + facet normal 0.621341 0.0772504 0.779723 + outer loop + vertex 1.15245 1.99681 2.55248 + vertex 1.15291 1.99294 2.55249 + vertex 1.15562 1.99485 2.55014 + endloop + endfacet + facet normal 0.667912 -0.0345813 0.743436 + outer loop + vertex 1.15792 1.99838 2.54795 + vertex 1.15774 2.00302 2.54833 + vertex 1.15517 1.99986 2.55049 + endloop + endfacet + facet normal 0.681309 0.0101614 0.731925 + outer loop + vertex 1.15562 1.99485 2.55014 + vertex 1.15792 1.99838 2.54795 + vertex 1.15517 1.99986 2.55049 + endloop + endfacet + facet normal 0.591252 -0.00307601 0.806481 + outer loop + vertex 1.15517 1.99986 2.55049 + vertex 1.15245 1.99681 2.55248 + vertex 1.15562 1.99485 2.55014 + endloop + endfacet + facet normal 0.506142 0.105409 0.855984 + outer loop + vertex 1.15175 2.00135 2.55233 + vertex 1.15245 1.99681 2.55248 + vertex 1.15517 1.99986 2.55049 + endloop + endfacet + facet normal 0.572018 0.010506 0.820174 + outer loop + vertex 1.15774 2.00302 2.54833 + vertex 1.15735 2.00848 2.54853 + vertex 1.1545 2.00464 2.55057 + endloop + endfacet + facet normal 0.590506 0.0698209 0.804007 + outer loop + vertex 1.15517 1.99986 2.55049 + vertex 1.15774 2.00302 2.54833 + vertex 1.1545 2.00464 2.55057 + endloop + endfacet + facet normal 0.491208 0.0549306 0.869309 + outer loop + vertex 1.1545 2.00464 2.55057 + vertex 1.15175 2.00135 2.55233 + vertex 1.15517 1.99986 2.55049 + endloop + endfacet + facet normal 0.384529 0.16492 0.908262 + outer loop + vertex 1.15034 2.00624 2.55204 + vertex 1.15175 2.00135 2.55233 + vertex 1.1545 2.00464 2.55057 + endloop + endfacet + facet normal 0.475305 0.110134 0.872901 + outer loop + vertex 1.15361 2.00873 2.55053 + vertex 1.1545 2.00464 2.55057 + vertex 1.15735 2.00848 2.54853 + endloop + endfacet + facet normal 0.475243 0.123767 0.871106 + outer loop + vertex 1.15361 2.00873 2.55053 + vertex 1.15735 2.00848 2.54853 + vertex 1.15414 2.01361 2.54955 + endloop + endfacet + facet normal 0.362537 0.0411292 0.931062 + outer loop + vertex 1.15414 2.01361 2.54955 + vertex 1.15735 2.00848 2.54853 + vertex 1.1586 2.01302 2.54784 + endloop + endfacet + facet normal 0.361102 0.085774 0.928573 + outer loop + vertex 1.1545 2.00464 2.55057 + vertex 1.15361 2.00873 2.55053 + vertex 1.15034 2.00624 2.55204 + endloop + endfacet + facet normal 0.361692 0.0328327 0.931719 + outer loop + vertex 1.1586 2.01302 2.54784 + vertex 1.15835 2.01733 2.54779 + vertex 1.15414 2.01361 2.54955 + endloop + endfacet + facet normal 0.220667 0.340946 0.913817 + outer loop + vertex 1.15263 2.14316 2.51946 + vertex 1.15707 2.14538 2.51757 + vertex 1.15214 2.14768 2.5179 + endloop + endfacet + facet normal 0.236014 0.427376 0.872724 + outer loop + vertex 1.15549 2.1496 2.51641 + vertex 1.15916 2.14821 2.5161 + vertex 1.1586 2.15125 2.51477 + endloop + endfacet + facet normal 0.146718 0.547024 0.824159 + outer loop + vertex 1.15418 2.15259 2.51466 + vertex 1.15549 2.1496 2.51641 + vertex 1.1586 2.15125 2.51477 + endloop + endfacet + facet normal 0.216581 0.331575 0.918233 + outer loop + vertex 1.15707 2.14538 2.51757 + vertex 1.15549 2.1496 2.51641 + vertex 1.15214 2.14768 2.5179 + endloop + endfacet + facet normal 0.202512 0.327597 0.922859 + outer loop + vertex 1.15916 2.14821 2.5161 + vertex 1.15549 2.1496 2.51641 + vertex 1.15707 2.14538 2.51757 + endloop + endfacet + facet normal -0.124009 0.845312 0.519681 + outer loop + vertex 1.15479 2.1565 2.51005 + vertex 1.15092 2.15659 2.50898 + vertex 1.15248 2.15488 2.51213 + endloop + endfacet + facet normal 0.0113658 0.783223 0.621637 + outer loop + vertex 1.15248 2.15488 2.51213 + vertex 1.15744 2.1546 2.5124 + vertex 1.15479 2.1565 2.51005 + endloop + endfacet + facet normal 0.00660924 0.743594 0.668599 + outer loop + vertex 1.15248 2.15488 2.51213 + vertex 1.15418 2.15259 2.51466 + vertex 1.15744 2.1546 2.5124 + endloop + endfacet + facet normal 0.166101 0.607454 0.776795 + outer loop + vertex 1.15418 2.15259 2.51466 + vertex 1.1586 2.15125 2.51477 + vertex 1.15744 2.1546 2.5124 + endloop + endfacet + facet normal -0.0917116 0.794026 0.600926 + outer loop + vertex 1.15519 2.16215 2.5003 + vertex 1.15173 2.16214 2.49977 + vertex 1.15443 2.16041 2.50248 + endloop + endfacet + facet normal -0.0913156 0.793989 0.601035 + outer loop + vertex 1.15768 2.16105 2.50212 + vertex 1.15519 2.16215 2.5003 + vertex 1.15443 2.16041 2.50248 + endloop + endfacet + facet normal -0.121704 0.874962 0.468646 + outer loop + vertex 1.15768 2.16105 2.50212 + vertex 1.15443 2.16041 2.50248 + vertex 1.15852 2.15955 2.50514 + endloop + endfacet + facet normal -0.113345 0.881707 0.45798 + outer loop + vertex 1.15852 2.15955 2.50514 + vertex 1.15443 2.16041 2.50248 + vertex 1.15377 2.15833 2.50632 + endloop + endfacet + facet normal -0.106942 0.880905 0.461052 + outer loop + vertex 1.15479 2.1565 2.51005 + vertex 1.15377 2.15833 2.50632 + vertex 1.15092 2.15659 2.50898 + endloop + endfacet + facet normal -0.0617293 0.8894 0.452942 + outer loop + vertex 1.15479 2.1565 2.51005 + vertex 1.15899 2.1573 2.50905 + vertex 1.15377 2.15833 2.50632 + endloop + endfacet + facet normal -0.0953439 0.857671 0.505283 + outer loop + vertex 1.15899 2.1573 2.50905 + vertex 1.15852 2.15955 2.50514 + vertex 1.15377 2.15833 2.50632 + endloop + endfacet + facet normal 0.00142161 0.777806 0.628503 + outer loop + vertex 1.15899 2.1573 2.50905 + vertex 1.15479 2.1565 2.51005 + vertex 1.15744 2.1546 2.5124 + endloop + endfacet + facet normal -0.0130827 0.545455 0.838038 + outer loop + vertex 1.16 2.16741 2.495 + vertex 1.155 2.16729 2.495 + vertex 1.15886 2.16423 2.49705 + endloop + endfacet + facet normal 0.556822 0.813872 0.166019 + outer loop + vertex 1.15886 2.16423 2.49705 + vertex 1.155 2.16729 2.495 + vertex 1.155 2.16627 2.5 + endloop + endfacet + facet normal -0.149726 0.0641223 0.986646 + outer loop + vertex 1.15519 2.16215 2.5003 + vertex 1.155 2.16627 2.5 + vertex 1.15173 2.16214 2.49977 + endloop + endfacet + facet normal 0.102911 0.0763302 0.991758 + outer loop + vertex 1.15519 2.16215 2.5003 + vertex 1.15833 2.16251 2.49994 + vertex 1.155 2.16627 2.5 + endloop + endfacet + facet normal 0.665352 0.581626 0.467993 + outer loop + vertex 1.15833 2.16251 2.49994 + vertex 1.15886 2.16423 2.49705 + vertex 1.155 2.16627 2.5 + endloop + endfacet + facet normal -0.0343191 0.835569 0.548312 + outer loop + vertex 1.15833 2.16251 2.49994 + vertex 1.15519 2.16215 2.5003 + vertex 1.15768 2.16105 2.50212 + endloop + endfacet + facet normal -0.0716736 -0.990023 0.121315 + outer loop + vertex 1.165 0.86167 2.495 + vertex 1.16312 0.861967 2.49631 + vertex 1.16 0.862032 2.495 + endloop + endfacet + facet normal -0.0891525 -0.982554 0.163218 + outer loop + vertex 1.16312 0.861967 2.49631 + vertex 1.15833 0.862453 2.49662 + vertex 1.16 0.862032 2.495 + endloop + endfacet + facet normal -0.0790232 -0.956917 0.279402 + outer loop + vertex 1.16312 0.861967 2.49631 + vertex 1.16159 0.863051 2.49959 + vertex 1.15833 0.862453 2.49662 + endloop + endfacet + facet normal -0.0521642 -0.966377 0.251781 + outer loop + vertex 1.16159 0.863051 2.49959 + vertex 1.15679 0.86334 2.49971 + vertex 1.15833 0.862453 2.49662 + endloop + endfacet + facet normal -0.0480345 -0.936121 0.348382 + outer loop + vertex 1.16159 0.863051 2.49959 + vertex 1.15948 0.86443 2.50301 + vertex 1.15679 0.86334 2.49971 + endloop + endfacet + facet normal -0.0136376 -0.930051 0.367177 + outer loop + vertex 1.16469 0.864282 2.50283 + vertex 1.15948 0.86443 2.50301 + vertex 1.16159 0.863051 2.49959 + endloop + endfacet + facet normal -0.00868681 -0.882435 0.470354 + outer loop + vertex 1.15948 0.86443 2.50301 + vertex 1.16469 0.864282 2.50283 + vertex 1.16216 0.86606 2.50611 + endloop + endfacet + facet normal -0.00744317 -0.882889 0.469523 + outer loop + vertex 1.15699 0.866054 2.50602 + vertex 1.15948 0.86443 2.50301 + vertex 1.16216 0.86606 2.50611 + endloop + endfacet + facet normal -0.00871725 -0.842647 0.538396 + outer loop + vertex 1.16216 0.86606 2.50611 + vertex 1.15936 0.868023 2.50914 + vertex 1.15699 0.866054 2.50602 + endloop + endfacet + facet normal 0.0631377 -0.809671 0.583478 + outer loop + vertex 1.1644 0.868299 2.50898 + vertex 1.15936 0.868023 2.50914 + vertex 1.16216 0.86606 2.50611 + endloop + endfacet + facet normal 0.0620395 -0.737243 0.672774 + outer loop + vertex 1.15936 0.868023 2.50914 + vertex 1.1644 0.868299 2.50898 + vertex 1.16125 0.870931 2.51215 + endloop + endfacet + facet normal 0.114524 -0.749715 0.651776 + outer loop + vertex 1.15695 0.869687 2.51148 + vertex 1.15936 0.868023 2.50914 + vertex 1.16125 0.870931 2.51215 + endloop + endfacet + facet normal 0.232597 -0.622104 0.747586 + outer loop + vertex 1.1607 0.873682 2.51461 + vertex 1.16125 0.870931 2.51215 + vertex 1.16477 0.874545 2.51407 + endloop + endfacet + facet normal 0.136058 -0.645129 0.751863 + outer loop + vertex 1.1607 0.873682 2.51461 + vertex 1.15677 0.872316 2.51415 + vertex 1.16125 0.870931 2.51215 + endloop + endfacet + facet normal 0.094361 -0.706771 0.701121 + outer loop + vertex 1.15677 0.872316 2.51415 + vertex 1.15695 0.869687 2.51148 + vertex 1.16125 0.870931 2.51215 + endloop + endfacet + facet normal 0.0877995 -0.535861 0.839729 + outer loop + vertex 1.1607 0.873682 2.51461 + vertex 1.15926 0.875734 2.51607 + vertex 1.15677 0.872316 2.51415 + endloop + endfacet + facet normal 0.172711 -0.487458 0.855895 + outer loop + vertex 1.16237 0.875993 2.51559 + vertex 1.15926 0.875734 2.51607 + vertex 1.1607 0.873682 2.51461 + endloop + endfacet + facet normal 0.263728 -0.0816985 0.961131 + outer loop + vertex 1.16185 0.99844 2.5465 + vertex 1.16163 1.00295 2.54695 + vertex 1.158 0.998648 2.54758 + endloop + endfacet + facet normal 0.336521 -0.147646 0.930029 + outer loop + vertex 1.158 0.998648 2.54758 + vertex 1.16163 1.00295 2.54695 + vertex 1.15773 1.00358 2.54846 + endloop + endfacet + facet normal 0.350401 -0.0716021 0.933859 + outer loop + vertex 1.16163 1.00295 2.54695 + vertex 1.16116 1.00843 2.54755 + vertex 1.15773 1.00358 2.54846 + endloop + endfacet + facet normal 0.443489 -0.146788 0.884178 + outer loop + vertex 1.15773 1.00358 2.54846 + vertex 1.16116 1.00843 2.54755 + vertex 1.15721 1.0084 2.54952 + endloop + endfacet + facet normal 0.650141 0.0650783 0.757021 + outer loop + vertex 1.16404 1.01049 2.54562 + vertex 1.1649 1.01432 2.54455 + vertex 1.16237 1.01276 2.54686 + endloop + endfacet + facet normal 0.569871 -0.0292678 0.821213 + outer loop + vertex 1.16237 1.01276 2.54686 + vertex 1.16116 1.00843 2.54755 + vertex 1.16404 1.01049 2.54562 + endloop + endfacet + facet normal 0.571424 -0.0298779 0.820111 + outer loop + vertex 1.16237 1.01276 2.54686 + vertex 1.15937 1.01362 2.54898 + vertex 1.16116 1.00843 2.54755 + endloop + endfacet + facet normal 0.445994 -0.092513 0.890242 + outer loop + vertex 1.15937 1.01362 2.54898 + vertex 1.15721 1.0084 2.54952 + vertex 1.16116 1.00843 2.54755 + endloop + endfacet + facet normal 0.679966 0.0604805 0.730745 + outer loop + vertex 1.1649 1.01432 2.54455 + vertex 1.16477 1.01871 2.54431 + vertex 1.16225 1.01662 2.54682 + endloop + endfacet + facet normal 0.66449 0.0266972 0.74682 + outer loop + vertex 1.16237 1.01276 2.54686 + vertex 1.1649 1.01432 2.54455 + vertex 1.16225 1.01662 2.54682 + endloop + endfacet + facet normal 0.581895 0.0247531 0.812887 + outer loop + vertex 1.16225 1.01662 2.54682 + vertex 1.15937 1.01362 2.54898 + vertex 1.16237 1.01276 2.54686 + endloop + endfacet + facet normal 0.619034 -0.0310542 0.78475 + outer loop + vertex 1.15971 1.01981 2.54896 + vertex 1.15937 1.01362 2.54898 + vertex 1.16225 1.01662 2.54682 + endloop + endfacet + facet normal 0.700888 0.0140643 0.713133 + outer loop + vertex 1.16477 1.01871 2.54431 + vertex 1.16268 1.02044 2.54632 + vertex 1.16225 1.01662 2.54682 + endloop + endfacet + facet normal 0.659596 0.0237569 0.751245 + outer loop + vertex 1.16268 1.02044 2.54632 + vertex 1.15971 1.01981 2.54896 + vertex 1.16225 1.01662 2.54682 + endloop + endfacet + facet normal 0.662467 0.00121847 0.74909 + outer loop + vertex 1.16268 1.02044 2.54632 + vertex 1.16201 1.02416 2.54692 + vertex 1.15971 1.01981 2.54896 + endloop + endfacet + facet normal 0.679131 -0.0147357 0.733869 + outer loop + vertex 1.16201 1.02416 2.54692 + vertex 1.15904 1.02516 2.54968 + vertex 1.15971 1.01981 2.54896 + endloop + endfacet + facet normal 0.682664 0.00434849 0.730719 + outer loop + vertex 1.16201 1.02416 2.54692 + vertex 1.16138 1.0291 2.54748 + vertex 1.15904 1.02516 2.54968 + endloop + endfacet + facet normal 0.69582 -0.0105097 0.718139 + outer loop + vertex 1.15904 1.02516 2.54968 + vertex 1.16138 1.0291 2.54748 + vertex 1.15856 1.02932 2.55021 + endloop + endfacet + facet normal 0.775712 0.0618028 0.628053 + outer loop + vertex 1.16374 1.03134 2.54474 + vertex 1.16405 1.03521 2.54398 + vertex 1.16221 1.03309 2.54646 + endloop + endfacet + facet normal 0.752159 0.0107506 0.658893 + outer loop + vertex 1.16221 1.03309 2.54646 + vertex 1.16138 1.0291 2.54748 + vertex 1.16374 1.03134 2.54474 + endloop + endfacet + facet normal 0.720857 0.0258213 0.692602 + outer loop + vertex 1.16221 1.03309 2.54646 + vertex 1.15953 1.03373 2.54922 + vertex 1.16138 1.0291 2.54748 + endloop + endfacet + facet normal 0.696525 0.00675728 0.717501 + outer loop + vertex 1.15953 1.03373 2.54922 + vertex 1.15856 1.02932 2.55021 + vertex 1.16138 1.0291 2.54748 + endloop + endfacet + facet normal 0.788697 0.0626875 0.611578 + outer loop + vertex 1.16405 1.03521 2.54398 + vertex 1.16377 1.03993 2.54386 + vertex 1.16189 1.03705 2.54658 + endloop + endfacet + facet normal 0.783538 0.0452148 0.619696 + outer loop + vertex 1.16221 1.03309 2.54646 + vertex 1.16405 1.03521 2.54398 + vertex 1.16189 1.03705 2.54658 + endloop + endfacet + facet normal 0.721979 0.038169 0.690861 + outer loop + vertex 1.16189 1.03705 2.54658 + vertex 1.15953 1.03373 2.54922 + vertex 1.16221 1.03309 2.54646 + endloop + endfacet + facet normal 0.731243 0.02433 0.681683 + outer loop + vertex 1.1593 1.03933 2.54927 + vertex 1.15953 1.03373 2.54922 + vertex 1.16189 1.03705 2.54658 + endloop + endfacet + facet normal 0.809814 0.075984 0.581746 + outer loop + vertex 1.16377 1.03993 2.54386 + vertex 1.16344 1.04484 2.54368 + vertex 1.16169 1.04204 2.54647 + endloop + endfacet + facet normal 0.79935 0.0440725 0.599247 + outer loop + vertex 1.16189 1.03705 2.54658 + vertex 1.16377 1.03993 2.54386 + vertex 1.16169 1.04204 2.54647 + endloop + endfacet + facet normal 0.738578 0.0432444 0.67278 + outer loop + vertex 1.16169 1.04204 2.54647 + vertex 1.1593 1.03933 2.54927 + vertex 1.16189 1.03705 2.54658 + endloop + endfacet + facet normal 0.742035 0.0366671 0.669358 + outer loop + vertex 1.15915 1.04456 2.54915 + vertex 1.1593 1.03933 2.54927 + vertex 1.16169 1.04204 2.54647 + endloop + endfacet + facet normal -0.695412 -0.678244 0.237461 + outer loop + vertex 1.165 1.04676 2.54 + vertex 1.16184 1.05 2.54 + vertex 1.16258 1.04906 2.5395 + endloop + endfacet + facet normal 0.83038 0.117226 0.544727 + outer loop + vertex 1.16344 1.04484 2.54368 + vertex 1.16296 1.0497 2.54336 + vertex 1.16147 1.04728 2.54615 + endloop + endfacet + facet normal 0.813233 0.0698351 0.577733 + outer loop + vertex 1.16169 1.04204 2.54647 + vertex 1.16344 1.04484 2.54368 + vertex 1.16147 1.04728 2.54615 + endloop + endfacet + facet normal 0.756544 0.0718031 0.649989 + outer loop + vertex 1.16147 1.04728 2.54615 + vertex 1.15915 1.04456 2.54915 + vertex 1.16169 1.04204 2.54647 + endloop + endfacet + facet normal 0.757227 0.0705011 0.649336 + outer loop + vertex 1.15899 1.04986 2.54877 + vertex 1.15915 1.04456 2.54915 + vertex 1.16147 1.04728 2.54615 + endloop + endfacet + facet normal 0.708053 0.450802 -0.543542 + outer loop + vertex 1.16184 1.05 2.54 + vertex 1.16 1.05289 2.54 + vertex 1.16 1.055 2.54175 + endloop + endfacet + facet normal -0.392669 0.171724 -0.903505 + outer loop + vertex 1.16184 1.05 2.54 + vertex 1.16 1.055 2.54175 + vertex 1.16258 1.04906 2.5395 + endloop + endfacet + facet normal -0.165131 0.286045 -0.94388 + outer loop + vertex 1.16258 1.04906 2.5395 + vertex 1.16 1.055 2.54175 + vertex 1.1619 1.05296 2.5408 + endloop + endfacet + facet normal 0.843264 0.224163 0.488526 + outer loop + vertex 1.16296 1.0497 2.54336 + vertex 1.16226 1.05344 2.54285 + vertex 1.16094 1.05297 2.54535 + endloop + endfacet + facet normal 0.809125 0.15563 0.566653 + outer loop + vertex 1.16147 1.04728 2.54615 + vertex 1.16296 1.0497 2.54336 + vertex 1.16094 1.05297 2.54535 + endloop + endfacet + facet normal 0.789162 0.157606 0.593619 + outer loop + vertex 1.16094 1.05297 2.54535 + vertex 1.15899 1.04986 2.54877 + vertex 1.16147 1.04728 2.54615 + endloop + endfacet + facet normal 0.805858 0.129671 0.577736 + outer loop + vertex 1.15861 1.05502 2.54813 + vertex 1.15899 1.04986 2.54877 + vertex 1.16094 1.05297 2.54535 + endloop + endfacet + facet normal 0.830172 0.0712137 0.552941 + outer loop + vertex 1.16174 1.05504 2.54181 + vertex 1.16 1.06 2.54378 + vertex 1.16051 1.05771 2.54331 + endloop + endfacet + facet normal 0.269184 0.435936 -0.858778 + outer loop + vertex 1.16174 1.05504 2.54181 + vertex 1.1619 1.05296 2.5408 + vertex 1.16 1.06 2.54378 + endloop + endfacet + facet normal -0.0591232 0.375542 -0.924918 + outer loop + vertex 1.1619 1.05296 2.5408 + vertex 1.16 1.055 2.54175 + vertex 1.16 1.06 2.54378 + endloop + endfacet + facet normal 0.924281 0.36777 0.102228 + outer loop + vertex 1.16226 1.05344 2.54285 + vertex 1.16174 1.05504 2.54181 + vertex 1.16051 1.05771 2.54331 + endloop + endfacet + facet normal 0.823876 0.284971 0.489917 + outer loop + vertex 1.16226 1.05344 2.54285 + vertex 1.16051 1.05771 2.54331 + vertex 1.16094 1.05297 2.54535 + endloop + endfacet + facet normal 0.87305 0.256945 0.414442 + outer loop + vertex 1.16094 1.05297 2.54535 + vertex 1.16051 1.05771 2.54331 + vertex 1.15951 1.05784 2.54534 + endloop + endfacet + facet normal 0.82509 0.243068 0.510044 + outer loop + vertex 1.15951 1.05784 2.54534 + vertex 1.15861 1.05502 2.54813 + vertex 1.16094 1.05297 2.54535 + endloop + endfacet + facet normal 0.859927 0.194147 0.472052 + outer loop + vertex 1.15824 1.059 2.54717 + vertex 1.15861 1.05502 2.54813 + vertex 1.15951 1.05784 2.54534 + endloop + endfacet + facet normal 0.00686151 0.203629 -0.979024 + outer loop + vertex 1.16 1.065 2.54482 + vertex 1.16051 1.05771 2.54331 + vertex 1.16 1.06 2.54378 + endloop + endfacet + facet normal -0.1416 -0.210644 0.967253 + outer loop + vertex 1.15917 1.06152 2.54394 + vertex 1.16051 1.05771 2.54331 + vertex 1.16 1.065 2.54482 + endloop + endfacet + facet normal 0.810293 0.279134 0.515276 + outer loop + vertex 1.1585 1.06099 2.54527 + vertex 1.15917 1.06152 2.54394 + vertex 1.15802 1.0639 2.54446 + endloop + endfacet + facet normal 0.814132 0.27051 0.513822 + outer loop + vertex 1.1585 1.06099 2.54527 + vertex 1.15951 1.05784 2.54534 + vertex 1.15917 1.06152 2.54394 + endloop + endfacet + facet normal 0.876598 0.23966 0.417299 + outer loop + vertex 1.15951 1.05784 2.54534 + vertex 1.16051 1.05771 2.54331 + vertex 1.15917 1.06152 2.54394 + endloop + endfacet + facet normal 0.863181 0.284113 0.417371 + outer loop + vertex 1.15951 1.05784 2.54534 + vertex 1.1585 1.06099 2.54527 + vertex 1.15824 1.059 2.54717 + endloop + endfacet + facet normal 0.795502 -0.31963 0.514795 + outer loop + vertex 1.16 1.065 2.54482 + vertex 1.16 1.06529 2.545 + vertex 1.15917 1.06152 2.54394 + endloop + endfacet + facet normal -0.0856479 -0.251968 0.963938 + outer loop + vertex 1.15917 1.06152 2.54394 + vertex 1.16 1.06529 2.545 + vertex 1.15802 1.0639 2.54446 + endloop + endfacet + facet normal 0.0768627 -0.0733429 0.99434 + outer loop + vertex 1.16271 1.98 2.54 + vertex 1.1597 1.97877 2.54014 + vertex 1.16 1.97716 2.54 + endloop + endfacet + facet normal 0.776583 -0.227333 0.58757 + outer loop + vertex 1.1597 1.97877 2.54014 + vertex 1.16098 1.98312 2.54013 + vertex 1.15868 1.97999 2.54197 + endloop + endfacet + facet normal 0.0520658 -0.0123503 0.998567 + outer loop + vertex 1.1597 1.97877 2.54014 + vertex 1.16271 1.98 2.54 + vertex 1.16098 1.98312 2.54013 + endloop + endfacet + facet normal 0.0506088 -0.0131593 0.998632 + outer loop + vertex 1.16271 1.98 2.54 + vertex 1.16401 1.985 2.54 + vertex 1.16098 1.98312 2.54013 + endloop + endfacet + facet normal 0.778081 -0.230287 0.58443 + outer loop + vertex 1.16098 1.98312 2.54013 + vertex 1.15889 1.98394 2.54324 + vertex 1.15868 1.97999 2.54197 + endloop + endfacet + facet normal 0.0464805 -0.00650724 0.998898 + outer loop + vertex 1.16401 1.985 2.54 + vertex 1.16471 1.99 2.54 + vertex 1.16098 1.98312 2.54013 + endloop + endfacet + facet normal 0.385375 -0.191734 0.902621 + outer loop + vertex 1.16471 1.99 2.54 + vertex 1.16132 1.98817 2.54106 + vertex 1.16098 1.98312 2.54013 + endloop + endfacet + facet normal 0.79908 -0.159264 0.579747 + outer loop + vertex 1.16132 1.98817 2.54106 + vertex 1.15889 1.98394 2.54324 + vertex 1.16098 1.98312 2.54013 + endloop + endfacet + facet normal 0.812607 -0.180166 0.554266 + outer loop + vertex 1.15909 1.98868 2.54449 + vertex 1.15889 1.98394 2.54324 + vertex 1.16132 1.98817 2.54106 + endloop + endfacet + facet normal 0.306387 -0.0171518 0.951753 + outer loop + vertex 1.16471 1.99 2.54 + vertex 1.16499 1.995 2.54 + vertex 1.16132 1.98817 2.54106 + endloop + endfacet + facet normal 0.602727 -0.204471 0.771305 + outer loop + vertex 1.16499 1.995 2.54 + vertex 1.16109 1.99244 2.54237 + vertex 1.16132 1.98817 2.54106 + endloop + endfacet + facet normal 0.823464 -0.126069 0.553184 + outer loop + vertex 1.16109 1.99244 2.54237 + vertex 1.15909 1.98868 2.54449 + vertex 1.16132 1.98817 2.54106 + endloop + endfacet + facet normal 0.834968 -0.144803 0.530906 + outer loop + vertex 1.15917 1.99256 2.54542 + vertex 1.15909 1.98868 2.54449 + vertex 1.16109 1.99244 2.54237 + endloop + endfacet + facet normal 0.372245 0.909281 0.186122 + outer loop + vertex 1.165 1.995 2.53998 + vertex 1.16406 1.99577 2.53813 + vertex 1.16499 1.995 2.54 + endloop + endfacet + facet normal 0.860955 -0.0594993 0.50519 + outer loop + vertex 1.16406 1.99577 2.53813 + vertex 1.16387 1.99899 2.53883 + vertex 1.16257 1.99618 2.54072 + endloop + endfacet + facet normal 0.46496 0.876266 0.126377 + outer loop + vertex 1.16406 1.99577 2.53813 + vertex 1.16257 1.99618 2.54072 + vertex 1.16499 1.995 2.54 + endloop + endfacet + facet normal 0.382104 0.242499 0.891735 + outer loop + vertex 1.16499 1.995 2.54 + vertex 1.16257 1.99618 2.54072 + vertex 1.16109 1.99244 2.54237 + endloop + endfacet + facet normal 0.825027 -0.0980892 0.556515 + outer loop + vertex 1.15917 1.99256 2.54542 + vertex 1.16017 1.99658 2.54465 + vertex 1.15811 1.99463 2.54736 + endloop + endfacet + facet normal 0.839787 -0.106397 0.532388 + outer loop + vertex 1.15917 1.99256 2.54542 + vertex 1.16109 1.99244 2.54237 + vertex 1.16017 1.99658 2.54465 + endloop + endfacet + facet normal 0.844952 -0.101279 0.525166 + outer loop + vertex 1.16109 1.99244 2.54237 + vertex 1.16257 1.99618 2.54072 + vertex 1.16017 1.99658 2.54465 + endloop + endfacet + facet normal 0.81234 -0.0505525 0.580989 + outer loop + vertex 1.16017 1.99658 2.54465 + vertex 1.15792 1.99838 2.54795 + vertex 1.15811 1.99463 2.54736 + endloop + endfacet + facet normal 0.841354 -0.222881 0.49239 + outer loop + vertex 1.16387 1.99899 2.53883 + vertex 1.16397 2.00251 2.54025 + vertex 1.1621 2.00083 2.54268 + endloop + endfacet + facet normal 0.884286 -0.103883 0.455243 + outer loop + vertex 1.16257 1.99618 2.54072 + vertex 1.16387 1.99899 2.53883 + vertex 1.1621 2.00083 2.54268 + endloop + endfacet + facet normal 0.839469 -0.138147 0.525553 + outer loop + vertex 1.16257 1.99618 2.54072 + vertex 1.1621 2.00083 2.54268 + vertex 1.16017 1.99658 2.54465 + endloop + endfacet + facet normal 0.817467 -0.109725 0.565427 + outer loop + vertex 1.1621 2.00083 2.54268 + vertex 1.15986 2.00095 2.54595 + vertex 1.16017 1.99658 2.54465 + endloop + endfacet + facet normal 0.787615 -0.12331 0.603703 + outer loop + vertex 1.15986 2.00095 2.54595 + vertex 1.15792 1.99838 2.54795 + vertex 1.16017 1.99658 2.54465 + endloop + endfacet + facet normal 0.735394 -0.0266587 0.677115 + outer loop + vertex 1.15774 2.00302 2.54833 + vertex 1.15792 1.99838 2.54795 + vertex 1.15986 2.00095 2.54595 + endloop + endfacet + facet normal 0.838286 -0.195437 0.509001 + outer loop + vertex 1.16397 2.00251 2.54025 + vertex 1.16313 2.00467 2.54246 + vertex 1.1621 2.00083 2.54268 + endloop + endfacet + facet normal 0.752885 -0.190819 0.629883 + outer loop + vertex 1.16313 2.00467 2.54246 + vertex 1.16344 2.00838 2.54321 + vertex 1.16078 2.00538 2.54548 + endloop + endfacet + facet normal 0.759113 -0.167111 0.629143 + outer loop + vertex 1.16313 2.00467 2.54246 + vertex 1.16078 2.00538 2.54548 + vertex 1.1621 2.00083 2.54268 + endloop + endfacet + facet normal 0.817321 -0.11107 0.565377 + outer loop + vertex 1.1621 2.00083 2.54268 + vertex 1.16078 2.00538 2.54548 + vertex 1.15986 2.00095 2.54595 + endloop + endfacet + facet normal 0.711863 -0.0751006 0.698291 + outer loop + vertex 1.16078 2.00538 2.54548 + vertex 1.15774 2.00302 2.54833 + vertex 1.15986 2.00095 2.54595 + endloop + endfacet + facet normal 0.67442 0.0207748 0.738055 + outer loop + vertex 1.15735 2.00848 2.54853 + vertex 1.15774 2.00302 2.54833 + vertex 1.16078 2.00538 2.54548 + endloop + endfacet + facet normal 0.678499 -0.190516 0.709466 + outer loop + vertex 1.16344 2.00838 2.54321 + vertex 1.16387 2.013 2.54404 + vertex 1.16105 2.0106 2.5461 + endloop + endfacet + facet normal 0.718119 -0.117341 0.685956 + outer loop + vertex 1.16078 2.00538 2.54548 + vertex 1.16344 2.00838 2.54321 + vertex 1.16105 2.0106 2.5461 + endloop + endfacet + facet normal 0.59418 -0.123703 0.794763 + outer loop + vertex 1.16105 2.0106 2.5461 + vertex 1.15735 2.00848 2.54853 + vertex 1.16078 2.00538 2.54548 + endloop + endfacet + facet normal 0.561432 -0.0294873 0.826997 + outer loop + vertex 1.1586 2.01302 2.54784 + vertex 1.15735 2.00848 2.54853 + vertex 1.16105 2.0106 2.5461 + endloop + endfacet + facet normal 0.601796 -0.169172 0.780527 + outer loop + vertex 1.16387 2.013 2.54404 + vertex 1.16373 2.01665 2.54494 + vertex 1.1614 2.01487 2.54635 + endloop + endfacet + facet normal 0.639101 -0.0982193 0.762826 + outer loop + vertex 1.16105 2.0106 2.5461 + vertex 1.16387 2.013 2.54404 + vertex 1.1614 2.01487 2.54635 + endloop + endfacet + facet normal 0.515901 -0.0931856 0.851565 + outer loop + vertex 1.1614 2.01487 2.54635 + vertex 1.1586 2.01302 2.54784 + vertex 1.16105 2.0106 2.5461 + endloop + endfacet + facet normal 0.450967 0.0376046 0.891748 + outer loop + vertex 1.15835 2.01733 2.54779 + vertex 1.1586 2.01302 2.54784 + vertex 1.1614 2.01487 2.54635 + endloop + endfacet + facet normal 0.540943 -0.0427051 0.839974 + outer loop + vertex 1.16373 2.01665 2.54494 + vertex 1.16179 2.01822 2.54627 + vertex 1.1614 2.01487 2.54635 + endloop + endfacet + facet normal 0.409266 -0.0261309 0.912041 + outer loop + vertex 1.16179 2.01822 2.54627 + vertex 1.15835 2.01733 2.54779 + vertex 1.1614 2.01487 2.54635 + endloop + endfacet + facet normal 0.386009 0.0758095 0.919375 + outer loop + vertex 1.16179 2.01822 2.54627 + vertex 1.16039 2.02179 2.54656 + vertex 1.15835 2.01733 2.54779 + endloop + endfacet + facet normal 0.181529 0.11754 0.976336 + outer loop + vertex 1.15936 2.03333 2.54472 + vertex 1.16409 2.02866 2.5444 + vertex 1.16418 2.03345 2.54381 + endloop + endfacet + facet normal 0.17668 0.205366 0.962605 + outer loop + vertex 1.16418 2.03345 2.54381 + vertex 1.16283 2.037 2.5433 + vertex 1.15936 2.03333 2.54472 + endloop + endfacet + facet normal 0.245277 0.418038 0.874691 + outer loop + vertex 1.1586 2.15125 2.51477 + vertex 1.16366 2.14816 2.51482 + vertex 1.16197 2.15278 2.51309 + endloop + endfacet + facet normal 0.131773 0.667161 0.733165 + outer loop + vertex 1.16487 2.15465 2.51137 + vertex 1.16318 2.15677 2.50974 + vertex 1.16121 2.15541 2.51133 + endloop + endfacet + facet normal 0.111564 0.57481 0.810646 + outer loop + vertex 1.16121 2.15541 2.51133 + vertex 1.16197 2.15278 2.51309 + vertex 1.16487 2.15465 2.51137 + endloop + endfacet + facet normal 0.10642 0.574109 0.811834 + outer loop + vertex 1.16121 2.15541 2.51133 + vertex 1.15744 2.1546 2.5124 + vertex 1.16197 2.15278 2.51309 + endloop + endfacet + facet normal 0.120575 0.601045 0.790068 + outer loop + vertex 1.15744 2.1546 2.5124 + vertex 1.1586 2.15125 2.51477 + vertex 1.16197 2.15278 2.51309 + endloop + endfacet + facet normal -0.0341504 0.870818 0.490418 + outer loop + vertex 1.15852 2.15955 2.50514 + vertex 1.16375 2.15883 2.50679 + vertex 1.16142 2.16087 2.50299 + endloop + endfacet + facet normal -0.0647515 0.88634 0.458486 + outer loop + vertex 1.15768 2.16105 2.50212 + vertex 1.15852 2.15955 2.50514 + vertex 1.16142 2.16087 2.50299 + endloop + endfacet + facet normal -0.008248 0.765895 0.642913 + outer loop + vertex 1.16318 2.15677 2.50974 + vertex 1.15899 2.1573 2.50905 + vertex 1.16121 2.15541 2.51133 + endloop + endfacet + facet normal 0.00991637 0.818851 0.57392 + outer loop + vertex 1.16318 2.15677 2.50974 + vertex 1.16375 2.15883 2.50679 + vertex 1.15899 2.1573 2.50905 + endloop + endfacet + facet normal -0.0387628 0.863983 0.502026 + outer loop + vertex 1.16375 2.15883 2.50679 + vertex 1.15852 2.15955 2.50514 + vertex 1.15899 2.1573 2.50905 + endloop + endfacet + facet normal 0.0117327 0.775402 0.631359 + outer loop + vertex 1.16121 2.15541 2.51133 + vertex 1.15899 2.1573 2.50905 + vertex 1.15744 2.1546 2.5124 + endloop + endfacet + facet normal 0.00458779 0.460349 0.887726 + outer loop + vertex 1.165 2.16736 2.495 + vertex 1.16 2.16741 2.495 + vertex 1.16376 2.16398 2.49676 + endloop + endfacet + facet normal 0.0771803 0.520765 0.850204 + outer loop + vertex 1.16376 2.16398 2.49676 + vertex 1.16 2.16741 2.495 + vertex 1.15886 2.16423 2.49705 + endloop + endfacet + facet normal 0.0737526 0.869702 0.488035 + outer loop + vertex 1.16376 2.16398 2.49676 + vertex 1.15886 2.16423 2.49705 + vertex 1.16285 2.16227 2.49994 + endloop + endfacet + facet normal 0.0446392 0.854333 0.517805 + outer loop + vertex 1.16285 2.16227 2.49994 + vertex 1.15886 2.16423 2.49705 + vertex 1.15833 2.16251 2.49994 + endloop + endfacet + facet normal -0.0849955 0.839874 0.536086 + outer loop + vertex 1.16142 2.16087 2.50299 + vertex 1.15833 2.16251 2.49994 + vertex 1.15768 2.16105 2.50212 + endloop + endfacet + facet normal 0.0469591 0.89963 0.434121 + outer loop + vertex 1.16285 2.16227 2.49994 + vertex 1.15833 2.16251 2.49994 + vertex 1.16142 2.16087 2.50299 + endloop + endfacet + facet normal -0.186241 -0.944387 0.271011 + outer loop + vertex 1.17 0.860684 2.495 + vertex 1.16725 0.861441 2.49575 + vertex 1.165 0.86167 2.495 + endloop + endfacet + facet normal -0.118759 -0.991444 0.0541809 + outer loop + vertex 1.16725 0.861441 2.49575 + vertex 1.16312 0.861967 2.49631 + vertex 1.165 0.86167 2.495 + endloop + endfacet + facet normal -0.0725766 -0.936666 0.342621 + outer loop + vertex 1.16725 0.861441 2.49575 + vertex 1.16715 0.862677 2.49911 + vertex 1.16312 0.861967 2.49631 + endloop + endfacet + facet normal -0.0382284 -0.953973 0.297447 + outer loop + vertex 1.16715 0.862677 2.49911 + vertex 1.16159 0.863051 2.49959 + vertex 1.16312 0.861967 2.49631 + endloop + endfacet + facet normal -0.0290762 -0.924583 0.37987 + outer loop + vertex 1.16715 0.862677 2.49911 + vertex 1.16469 0.864282 2.50283 + vertex 1.16159 0.863051 2.49959 + endloop + endfacet + facet normal -0.00359795 -0.918956 0.394345 + outer loop + vertex 1.16913 0.864097 2.50243 + vertex 1.16469 0.864282 2.50283 + vertex 1.16715 0.862677 2.49911 + endloop + endfacet + facet normal 0.00892448 -0.860694 0.509044 + outer loop + vertex 1.16469 0.864282 2.50283 + vertex 1.16913 0.864097 2.50243 + vertex 1.16794 0.865994 2.50566 + endloop + endfacet + facet normal 0.0284989 -0.869995 0.492236 + outer loop + vertex 1.16216 0.86606 2.50611 + vertex 1.16469 0.864282 2.50283 + vertex 1.16794 0.865994 2.50566 + endloop + endfacet + facet normal 0.0374784 -0.801333 0.597043 + outer loop + vertex 1.16794 0.865994 2.50566 + vertex 1.1644 0.868299 2.50898 + vertex 1.16216 0.86606 2.50611 + endloop + endfacet + facet normal 0.0818774 -0.775274 0.626295 + outer loop + vertex 1.16938 0.86857 2.50866 + vertex 1.1644 0.868299 2.50898 + vertex 1.16794 0.865994 2.50566 + endloop + endfacet + facet normal 0.0832112 -0.670805 0.736951 + outer loop + vertex 1.1644 0.868299 2.50898 + vertex 1.16938 0.86857 2.50866 + vertex 1.1667 0.871228 2.51138 + endloop + endfacet + facet normal 0.137707 -0.691113 0.709507 + outer loop + vertex 1.16125 0.870931 2.51215 + vertex 1.1644 0.868299 2.50898 + vertex 1.1667 0.871228 2.51138 + endloop + endfacet + facet normal 0.145112 -0.569565 0.809035 + outer loop + vertex 1.1667 0.871228 2.51138 + vertex 1.16477 0.874545 2.51407 + vertex 1.16125 0.870931 2.51215 + endloop + endfacet + facet normal 0.203843 -0.540944 0.815982 + outer loop + vertex 1.16986 0.874816 2.51297 + vertex 1.16477 0.874545 2.51407 + vertex 1.1667 0.871228 2.51138 + endloop + endfacet + facet normal 0.376346 -0.153882 0.91361 + outer loop + vertex 1.16433 0.997463 2.5455 + vertex 1.16199 0.99528 2.54609 + vertex 1.16363 0.993351 2.54509 + endloop + endfacet + facet normal 0.501689 -0.168758 0.848427 + outer loop + vertex 1.16433 0.997463 2.5455 + vertex 1.16363 0.993351 2.54509 + vertex 1.16775 0.998032 2.54359 + endloop + endfacet + facet normal 0.368536 -0.025583 0.929261 + outer loop + vertex 1.16775 0.998032 2.54359 + vertex 1.16363 0.993351 2.54509 + vertex 1.16686 0.99246 2.54378 + endloop + endfacet + facet normal 0.338132 -0.107122 0.934982 + outer loop + vertex 1.16433 0.997463 2.5455 + vertex 1.16185 0.99844 2.5465 + vertex 1.16199 0.99528 2.54609 + endloop + endfacet + facet normal 0.566863 0.0491342 0.822345 + outer loop + vertex 1.16775 0.998032 2.54359 + vertex 1.1677 1.00451 2.54323 + vertex 1.16487 1.00143 2.54536 + endloop + endfacet + facet normal 0.491988 -0.0388718 0.869734 + outer loop + vertex 1.16433 0.997463 2.5455 + vertex 1.16775 0.998032 2.54359 + vertex 1.16487 1.00143 2.54536 + endloop + endfacet + facet normal 0.369954 -0.0200531 0.928834 + outer loop + vertex 1.16487 1.00143 2.54536 + vertex 1.16185 0.99844 2.5465 + vertex 1.16433 0.997463 2.5455 + endloop + endfacet + facet normal 0.411196 -0.0693535 0.908905 + outer loop + vertex 1.16163 1.00295 2.54695 + vertex 1.16185 0.99844 2.5465 + vertex 1.16487 1.00143 2.54536 + endloop + endfacet + facet normal 0.607802 0.0953005 0.788349 + outer loop + vertex 1.1677 1.00451 2.54323 + vertex 1.16705 1.01025 2.54304 + vertex 1.16454 1.00643 2.54543 + endloop + endfacet + facet normal 0.582907 0.0272858 0.812081 + outer loop + vertex 1.16487 1.00143 2.54536 + vertex 1.1677 1.00451 2.54323 + vertex 1.16454 1.00643 2.54543 + endloop + endfacet + facet normal 0.444949 0.0170703 0.895393 + outer loop + vertex 1.16454 1.00643 2.54543 + vertex 1.16163 1.00295 2.54695 + vertex 1.16487 1.00143 2.54536 + endloop + endfacet + facet normal 0.507033 -0.0501313 0.860468 + outer loop + vertex 1.16116 1.00843 2.54755 + vertex 1.16163 1.00295 2.54695 + vertex 1.16454 1.00643 2.54543 + endloop + endfacet + facet normal 0.652139 0.0464494 0.756675 + outer loop + vertex 1.16404 1.01049 2.54562 + vertex 1.16454 1.00643 2.54543 + vertex 1.16705 1.01025 2.54304 + endloop + endfacet + facet normal 0.652309 0.0640955 0.755238 + outer loop + vertex 1.16404 1.01049 2.54562 + vertex 1.16705 1.01025 2.54304 + vertex 1.1649 1.01432 2.54455 + endloop + endfacet + facet normal 0.696188 0.103867 0.710305 + outer loop + vertex 1.1649 1.01432 2.54455 + vertex 1.16705 1.01025 2.54304 + vertex 1.1675 1.01449 2.54198 + endloop + endfacet + facet normal 0.541213 0.0289311 0.840388 + outer loop + vertex 1.16454 1.00643 2.54543 + vertex 1.16404 1.01049 2.54562 + vertex 1.16116 1.00843 2.54755 + endloop + endfacet + facet normal 0.698043 0.0849756 0.710996 + outer loop + vertex 1.1675 1.01449 2.54198 + vertex 1.1667 1.01715 2.54245 + vertex 1.1649 1.01432 2.54455 + endloop + endfacet + facet normal 0.717776 0.0595549 0.693723 + outer loop + vertex 1.1649 1.01432 2.54455 + vertex 1.1667 1.01715 2.54245 + vertex 1.16477 1.01871 2.54431 + endloop + endfacet + facet normal 0.842889 0.038201 0.53673 + outer loop + vertex 1.16737 1.02106 2.54128 + vertex 1.16843 1.0252 2.53934 + vertex 1.16712 1.02402 2.54148 + endloop + endfacet + facet normal 0.744513 0.0210425 0.667276 + outer loop + vertex 1.16737 1.02106 2.54128 + vertex 1.16712 1.02402 2.54148 + vertex 1.16505 1.02319 2.54381 + endloop + endfacet + facet normal 0.746963 0.0272434 0.664307 + outer loop + vertex 1.16737 1.02106 2.54128 + vertex 1.16505 1.02319 2.54381 + vertex 1.16477 1.01871 2.54431 + endloop + endfacet + facet normal 0.724544 0.0785158 0.684741 + outer loop + vertex 1.16737 1.02106 2.54128 + vertex 1.16477 1.01871 2.54431 + vertex 1.1667 1.01715 2.54245 + endloop + endfacet + facet normal 0.70896 0.0340318 0.704427 + outer loop + vertex 1.16268 1.02044 2.54632 + vertex 1.16477 1.01871 2.54431 + vertex 1.16505 1.02319 2.54381 + endloop + endfacet + facet normal 0.717312 0.0195714 0.696477 + outer loop + vertex 1.16505 1.02319 2.54381 + vertex 1.16201 1.02416 2.54692 + vertex 1.16268 1.02044 2.54632 + endloop + endfacet + facet normal -0.575803 -0.287875 0.765231 + outer loop + vertex 1.17 1.0287 2.535 + vertex 1.16935 1.03 2.535 + vertex 1.16901 1.0282 2.53406 + endloop + endfacet + facet normal 0.837308 0.134827 0.529847 + outer loop + vertex 1.16843 1.0252 2.53934 + vertex 1.16821 1.02959 2.53857 + vertex 1.1668 1.02697 2.54145 + endloop + endfacet + facet normal 0.825809 0.0927465 0.556271 + outer loop + vertex 1.16712 1.02402 2.54148 + vertex 1.16843 1.0252 2.53934 + vertex 1.1668 1.02697 2.54145 + endloop + endfacet + facet normal 0.730695 0.0839531 0.677523 + outer loop + vertex 1.16712 1.02402 2.54148 + vertex 1.1668 1.02697 2.54145 + vertex 1.16505 1.02319 2.54381 + endloop + endfacet + facet normal 0.758851 0.0531094 0.649095 + outer loop + vertex 1.1668 1.02697 2.54145 + vertex 1.16429 1.02774 2.54433 + vertex 1.16505 1.02319 2.54381 + endloop + endfacet + facet normal 0.720265 0.0416814 0.692446 + outer loop + vertex 1.16429 1.02774 2.54433 + vertex 1.16201 1.02416 2.54692 + vertex 1.16505 1.02319 2.54381 + endloop + endfacet + facet normal 0.737807 0.0177422 0.674778 + outer loop + vertex 1.16138 1.0291 2.54748 + vertex 1.16201 1.02416 2.54692 + vertex 1.16429 1.02774 2.54433 + endloop + endfacet + facet normal -0.525024 -0.38852 0.757233 + outer loop + vertex 1.16935 1.03 2.535 + vertex 1.16565 1.035 2.535 + vertex 1.16723 1.03268 2.53491 + endloop + endfacet + facet normal -0.463203 -0.33745 0.819494 + outer loop + vertex 1.16901 1.0282 2.53406 + vertex 1.16935 1.03 2.535 + vertex 1.16723 1.03268 2.53491 + endloop + endfacet + facet normal 0.860023 0.237366 0.451683 + outer loop + vertex 1.16821 1.02959 2.53857 + vertex 1.16754 1.03337 2.53785 + vertex 1.16603 1.03249 2.54119 + endloop + endfacet + facet normal 0.833134 0.142159 0.534489 + outer loop + vertex 1.1668 1.02697 2.54145 + vertex 1.16821 1.02959 2.53857 + vertex 1.16603 1.03249 2.54119 + endloop + endfacet + facet normal 0.833657 0.0422068 0.550668 + outer loop + vertex 1.16374 1.03134 2.54474 + vertex 1.16603 1.03249 2.54119 + vertex 1.16405 1.03521 2.54398 + endloop + endfacet + facet normal 0.829771 0.0621873 0.554629 + outer loop + vertex 1.16374 1.03134 2.54474 + vertex 1.16429 1.02774 2.54433 + vertex 1.16603 1.03249 2.54119 + endloop + endfacet + facet normal 0.763638 0.136788 0.630988 + outer loop + vertex 1.16429 1.02774 2.54433 + vertex 1.1668 1.02697 2.54145 + vertex 1.16603 1.03249 2.54119 + endloop + endfacet + facet normal 0.741343 0.0359278 0.670164 + outer loop + vertex 1.16429 1.02774 2.54433 + vertex 1.16374 1.03134 2.54474 + vertex 1.16138 1.0291 2.54748 + endloop + endfacet + facet normal 0.9252 0.378929 -0.0204289 + outer loop + vertex 1.16698 1.03505 2.53648 + vertex 1.165 1.04 2.53869 + vertex 1.1658 1.03802 2.53837 + endloop + endfacet + facet normal 0.510794 0.512499 -0.690242 + outer loop + vertex 1.16723 1.03268 2.53491 + vertex 1.165 1.04 2.53869 + vertex 1.16698 1.03505 2.53648 + endloop + endfacet + facet normal 0.599641 0.504079 -0.621558 + outer loop + vertex 1.16723 1.03268 2.53491 + vertex 1.165 1.03545 2.535 + vertex 1.165 1.04 2.53869 + endloop + endfacet + facet normal -0.0529516 -0.0764887 0.995663 + outer loop + vertex 1.16723 1.03268 2.53491 + vertex 1.16565 1.035 2.535 + vertex 1.165 1.03545 2.535 + endloop + endfacet + facet normal 0.937503 0.345742 0.0393902 + outer loop + vertex 1.16754 1.03337 2.53785 + vertex 1.16698 1.03505 2.53648 + vertex 1.1658 1.03802 2.53837 + endloop + endfacet + facet normal 0.849786 0.266585 0.454748 + outer loop + vertex 1.16754 1.03337 2.53785 + vertex 1.1658 1.03802 2.53837 + vertex 1.16603 1.03249 2.54119 + endloop + endfacet + facet normal 0.962781 0.152584 0.223095 + outer loop + vertex 1.16603 1.03249 2.54119 + vertex 1.1658 1.03802 2.53837 + vertex 1.16509 1.0385 2.54114 + endloop + endfacet + facet normal 0.866751 0.140063 0.47867 + outer loop + vertex 1.16509 1.0385 2.54114 + vertex 1.16405 1.03521 2.54398 + vertex 1.16603 1.03249 2.54119 + endloop + endfacet + facet normal 0.910872 0.0646676 0.40759 + outer loop + vertex 1.16377 1.03993 2.54386 + vertex 1.16405 1.03521 2.54398 + vertex 1.16509 1.0385 2.54114 + endloop + endfacet + facet normal -0.255787 0.0540338 -0.965222 + outer loop + vertex 1.165 1.045 2.53897 + vertex 1.1658 1.03802 2.53837 + vertex 1.165 1.04 2.53869 + endloop + endfacet + facet normal 0.570653 -0.00527946 0.821174 + outer loop + vertex 1.16446 1.04365 2.53934 + vertex 1.1658 1.03802 2.53837 + vertex 1.165 1.045 2.53897 + endloop + endfacet + facet normal 0.957571 0.192149 0.214794 + outer loop + vertex 1.1658 1.03802 2.53837 + vertex 1.16446 1.04365 2.53934 + vertex 1.16509 1.0385 2.54114 + endloop + endfacet + facet normal 0.989528 0.136962 0.0455611 + outer loop + vertex 1.16446 1.04365 2.53934 + vertex 1.16447 1.0428 2.5416 + vertex 1.16509 1.0385 2.54114 + endloop + endfacet + facet normal 0.913734 0.088397 0.39658 + outer loop + vertex 1.16447 1.0428 2.5416 + vertex 1.16377 1.03993 2.54386 + vertex 1.16509 1.0385 2.54114 + endloop + endfacet + facet normal 0.920711 0.0758468 0.382803 + outer loop + vertex 1.16344 1.04484 2.54368 + vertex 1.16377 1.03993 2.54386 + vertex 1.16447 1.0428 2.5416 + endloop + endfacet + facet normal 0.878737 -0.241077 0.411951 + outer loop + vertex 1.165 1.045 2.53897 + vertex 1.165 1.04676 2.54 + vertex 1.16446 1.04365 2.53934 + endloop + endfacet + facet normal -0.328379 -0.14104 0.933957 + outer loop + vertex 1.16258 1.04906 2.5395 + vertex 1.16446 1.04365 2.53934 + vertex 1.165 1.04676 2.54 + endloop + endfacet + facet normal 0.887054 0.31673 -0.335883 + outer loop + vertex 1.16258 1.04906 2.5395 + vertex 1.16364 1.04774 2.54104 + vertex 1.16446 1.04365 2.53934 + endloop + endfacet + facet normal 0.983261 0.172432 0.0588709 + outer loop + vertex 1.16364 1.04774 2.54104 + vertex 1.16447 1.0428 2.5416 + vertex 1.16446 1.04365 2.53934 + endloop + endfacet + facet normal 0.940725 0.190501 0.280615 + outer loop + vertex 1.16364 1.04774 2.54104 + vertex 1.16344 1.04484 2.54368 + vertex 1.16447 1.0428 2.5416 + endloop + endfacet + facet normal 0.975165 0.10861 0.193019 + outer loop + vertex 1.16296 1.0497 2.54336 + vertex 1.16344 1.04484 2.54368 + vertex 1.16364 1.04774 2.54104 + endloop + endfacet + facet normal 0.886938 0.279436 -0.367771 + outer loop + vertex 1.1619 1.05296 2.5408 + vertex 1.16364 1.04774 2.54104 + vertex 1.16258 1.04906 2.5395 + endloop + endfacet + facet normal 0.7378 0.2173 -0.639086 + outer loop + vertex 1.16298 1.05179 2.54166 + vertex 1.16364 1.04774 2.54104 + vertex 1.1619 1.05296 2.5408 + endloop + endfacet + facet normal 0.975914 0.130778 0.17461 + outer loop + vertex 1.16298 1.05179 2.54166 + vertex 1.16296 1.0497 2.54336 + vertex 1.16364 1.04774 2.54104 + endloop + endfacet + facet normal 0.93769 0.212704 0.274763 + outer loop + vertex 1.16226 1.05344 2.54285 + vertex 1.16296 1.0497 2.54336 + vertex 1.16298 1.05179 2.54166 + endloop + endfacet + facet normal 0.774828 0.321603 -0.544255 + outer loop + vertex 1.1619 1.05296 2.5408 + vertex 1.16174 1.05504 2.54181 + vertex 1.16298 1.05179 2.54166 + endloop + endfacet + facet normal 0.932384 0.35335 0.0761797 + outer loop + vertex 1.16298 1.05179 2.54166 + vertex 1.16174 1.05504 2.54181 + vertex 1.16226 1.05344 2.54285 + endloop + endfacet + facet normal 0.653834 -0.728018 0.206133 + outer loop + vertex 1.16657 1.995 2.535 + vertex 1.165 1.995 2.53998 + vertex 1.165 1.99359 2.535 + endloop + endfacet + facet normal -0.382793 0.76851 0.5127 + outer loop + vertex 1.165 1.995 2.53998 + vertex 1.16571 1.99803 2.53597 + vertex 1.16406 1.99577 2.53813 + endloop + endfacet + facet normal 0.939793 0.170305 0.296286 + outer loop + vertex 1.165 1.995 2.53998 + vertex 1.16657 1.995 2.535 + vertex 1.16571 1.99803 2.53597 + endloop + endfacet + facet normal 0.402881 -0.174858 0.898394 + outer loop + vertex 1.16657 1.995 2.535 + vertex 1.16874 2 2.535 + vertex 1.16571 1.99803 2.53597 + endloop + endfacet + facet normal 0.826048 -0.0732912 0.558814 + outer loop + vertex 1.16571 1.99803 2.53597 + vertex 1.16387 1.99899 2.53883 + vertex 1.16406 1.99577 2.53813 + endloop + endfacet + facet normal 0.338295 -0.0554738 0.939404 + outer loop + vertex 1.16874 2 2.535 + vertex 1.16956 2.005 2.535 + vertex 1.16571 1.99803 2.53597 + endloop + endfacet + facet normal 0.599713 -0.223562 0.768352 + outer loop + vertex 1.16956 2.005 2.535 + vertex 1.16569 2.00224 2.53722 + vertex 1.16571 1.99803 2.53597 + endloop + endfacet + facet normal 0.802165 -0.164562 0.573978 + outer loop + vertex 1.16569 2.00224 2.53722 + vertex 1.16387 1.99899 2.53883 + vertex 1.16571 1.99803 2.53597 + endloop + endfacet + facet normal 0.839203 -0.22408 0.495507 + outer loop + vertex 1.16397 2.00251 2.54025 + vertex 1.16387 1.99899 2.53883 + vertex 1.16569 2.00224 2.53722 + endloop + endfacet + facet normal 0.185392 0.639317 0.746259 + outer loop + vertex 1.17 2.00707 2.535 + vertex 1.16899 2.0083 2.5342 + vertex 1.16744 2.00629 2.5363 + endloop + endfacet + facet normal 0.475322 -0.101037 0.873991 + outer loop + vertex 1.17 2.00707 2.535 + vertex 1.16744 2.00629 2.5363 + vertex 1.16956 2.005 2.535 + endloop + endfacet + facet normal 0.511435 -0.0265263 0.858912 + outer loop + vertex 1.16956 2.005 2.535 + vertex 1.16744 2.00629 2.5363 + vertex 1.16569 2.00224 2.53722 + endloop + endfacet + facet normal 0.826631 -0.212292 0.521166 + outer loop + vertex 1.16397 2.00251 2.54025 + vertex 1.16498 2.00568 2.53994 + vertex 1.16313 2.00467 2.54246 + endloop + endfacet + facet normal 0.840346 -0.219234 0.495736 + outer loop + vertex 1.16397 2.00251 2.54025 + vertex 1.16569 2.00224 2.53722 + vertex 1.16498 2.00568 2.53994 + endloop + endfacet + facet normal 0.822454 -0.23902 0.516178 + outer loop + vertex 1.16569 2.00224 2.53722 + vertex 1.16744 2.00629 2.5363 + vertex 1.16498 2.00568 2.53994 + endloop + endfacet + facet normal 0.826157 -0.177598 0.534718 + outer loop + vertex 1.16498 2.00568 2.53994 + vertex 1.16344 2.00838 2.54321 + vertex 1.16313 2.00467 2.54246 + endloop + endfacet + facet normal 0.876892 -0.239167 0.416965 + outer loop + vertex 1.16899 2.0083 2.5342 + vertex 1.16821 2.00981 2.53671 + vertex 1.16744 2.00629 2.5363 + endloop + endfacet + facet normal 0.796932 -0.328213 0.507124 + outer loop + vertex 1.16821 2.00981 2.53671 + vertex 1.16865 2.01366 2.53851 + vertex 1.16622 2.01043 2.54023 + endloop + endfacet + facet normal 0.827353 -0.238825 0.508379 + outer loop + vertex 1.16821 2.00981 2.53671 + vertex 1.16622 2.01043 2.54023 + vertex 1.16744 2.00629 2.5363 + endloop + endfacet + facet normal 0.821497 -0.246193 0.514326 + outer loop + vertex 1.16744 2.00629 2.5363 + vertex 1.16622 2.01043 2.54023 + vertex 1.16498 2.00568 2.53994 + endloop + endfacet + facet normal 0.786995 -0.240555 0.568131 + outer loop + vertex 1.16622 2.01043 2.54023 + vertex 1.16344 2.00838 2.54321 + vertex 1.16498 2.00568 2.53994 + endloop + endfacet + facet normal 0.778294 -0.180528 0.601389 + outer loop + vertex 1.16387 2.013 2.54404 + vertex 1.16344 2.00838 2.54321 + vertex 1.16622 2.01043 2.54023 + endloop + endfacet + facet normal 0.675291 -0.353449 0.647345 + outer loop + vertex 1.16865 2.01366 2.53851 + vertex 1.16917 2.01728 2.53994 + vertex 1.16657 2.01667 2.54232 + endloop + endfacet + facet normal 0.756724 -0.24507 0.606061 + outer loop + vertex 1.16622 2.01043 2.54023 + vertex 1.16865 2.01366 2.53851 + vertex 1.16657 2.01667 2.54232 + endloop + endfacet + facet normal 0.739697 -0.250325 0.624649 + outer loop + vertex 1.16657 2.01667 2.54232 + vertex 1.16387 2.013 2.54404 + vertex 1.16622 2.01043 2.54023 + endloop + endfacet + facet normal 0.67096 -0.152705 0.725599 + outer loop + vertex 1.16373 2.01665 2.54494 + vertex 1.16387 2.013 2.54404 + vertex 1.16657 2.01667 2.54232 + endloop + endfacet + facet normal 0.682321 -0.288501 0.671719 + outer loop + vertex 1.16917 2.01728 2.53994 + vertex 1.16844 2.01929 2.54154 + vertex 1.16657 2.01667 2.54232 + endloop + endfacet + facet normal 0.545918 -0.0341861 0.837141 + outer loop + vertex 1.16373 2.01665 2.54494 + vertex 1.16407 2.02009 2.54486 + vertex 1.16179 2.01822 2.54627 + endloop + endfacet + facet normal 0.677567 -0.0498929 0.733767 + outer loop + vertex 1.16657 2.01667 2.54232 + vertex 1.16407 2.02009 2.54486 + vertex 1.16373 2.01665 2.54494 + endloop + endfacet + facet normal 0.591952 -0.155074 0.790914 + outer loop + vertex 1.16657 2.01667 2.54232 + vertex 1.16732 2.02282 2.54296 + vertex 1.16407 2.02009 2.54486 + endloop + endfacet + facet normal 0.554279 -0.153315 0.818089 + outer loop + vertex 1.16657 2.01667 2.54232 + vertex 1.16844 2.01929 2.54154 + vertex 1.16732 2.02282 2.54296 + endloop + endfacet + facet normal 0.458316 0.107077 0.882316 + outer loop + vertex 1.16407 2.02009 2.54486 + vertex 1.16039 2.02179 2.54656 + vertex 1.16179 2.01822 2.54627 + endloop + endfacet + facet normal 0.494145 0.0161378 0.86923 + outer loop + vertex 1.16352 2.02392 2.5451 + vertex 1.16407 2.02009 2.54486 + vertex 1.16732 2.02282 2.54296 + endloop + endfacet + facet normal 0.504245 0.0667357 0.860978 + outer loop + vertex 1.16352 2.02392 2.5451 + vertex 1.16732 2.02282 2.54296 + vertex 1.16409 2.02866 2.5444 + endloop + endfacet + facet normal 0.312986 -0.0604907 0.947829 + outer loop + vertex 1.16409 2.02866 2.5444 + vertex 1.16732 2.02282 2.54296 + vertex 1.16923 2.02824 2.54267 + endloop + endfacet + facet normal 0.421685 0.00341923 0.906736 + outer loop + vertex 1.16407 2.02009 2.54486 + vertex 1.16352 2.02392 2.5451 + vertex 1.16039 2.02179 2.54656 + endloop + endfacet + facet normal 0.175699 0.613174 0.77016 + outer loop + vertex 1.16487 2.15465 2.51137 + vertex 1.16951 2.15375 2.51102 + vertex 1.1673 2.15666 2.50921 + endloop + endfacet + facet normal 0.113059 0.659738 0.742943 + outer loop + vertex 1.16318 2.15677 2.50974 + vertex 1.16487 2.15465 2.51137 + vertex 1.1673 2.15666 2.50921 + endloop + endfacet + facet normal 0.191255 0.488738 0.851209 + outer loop + vertex 1.16668 2.15135 2.51285 + vertex 1.16487 2.15465 2.51137 + vertex 1.16197 2.15278 2.51309 + endloop + endfacet + facet normal 0.15609 0.475902 0.865536 + outer loop + vertex 1.16951 2.15375 2.51102 + vertex 1.16487 2.15465 2.51137 + vertex 1.16668 2.15135 2.51285 + endloop + endfacet + facet normal 0.0301866 0.857054 0.514341 + outer loop + vertex 1.16375 2.15883 2.50679 + vertex 1.16961 2.15878 2.50652 + vertex 1.16641 2.16072 2.50348 + endloop + endfacet + facet normal -0.0201235 0.874842 0.48399 + outer loop + vertex 1.16142 2.16087 2.50299 + vertex 1.16375 2.15883 2.50679 + vertex 1.16641 2.16072 2.50348 + endloop + endfacet + facet normal 0.0963483 0.807175 0.582396 + outer loop + vertex 1.1673 2.15666 2.50921 + vertex 1.16375 2.15883 2.50679 + vertex 1.16318 2.15677 2.50974 + endloop + endfacet + facet normal 0.0350357 0.769132 0.638129 + outer loop + vertex 1.16961 2.15878 2.50652 + vertex 1.16375 2.15883 2.50679 + vertex 1.1673 2.15666 2.50921 + endloop + endfacet + facet normal -0.00172363 0.430323 0.902673 + outer loop + vertex 1.17 2.16738 2.495 + vertex 1.165 2.16736 2.495 + vertex 1.16876 2.16398 2.49662 + endloop + endfacet + facet normal 0.0250517 0.454297 0.890498 + outer loop + vertex 1.16876 2.16398 2.49662 + vertex 1.165 2.16736 2.495 + vertex 1.16376 2.16398 2.49676 + endloop + endfacet + facet normal 0.0132785 0.887327 0.46095 + outer loop + vertex 1.16876 2.16398 2.49662 + vertex 1.16376 2.16398 2.49676 + vertex 1.16791 2.1622 2.50006 + endloop + endfacet + facet normal 0.000810852 0.880969 0.473174 + outer loop + vertex 1.16791 2.1622 2.50006 + vertex 1.16376 2.16398 2.49676 + vertex 1.16285 2.16227 2.49994 + endloop + endfacet + facet normal -0.0119076 0.911164 0.411872 + outer loop + vertex 1.16641 2.16072 2.50348 + vertex 1.16285 2.16227 2.49994 + vertex 1.16142 2.16087 2.50299 + endloop + endfacet + facet normal 0.00308656 0.916829 0.399268 + outer loop + vertex 1.16791 2.1622 2.50006 + vertex 1.16285 2.16227 2.49994 + vertex 1.16641 2.16072 2.50348 + endloop + endfacet + facet normal -0.424524 -0.882967 0.200371 + outer loop + vertex 1.175 0.859351 2.49 + vertex 1.175 0.86 2.49286 + vertex 1.17365 0.86 2.49 + endloop + endfacet + facet normal -0.0201468 -0.876119 0.481673 + outer loop + vertex 1.175 0.860569 2.495 + vertex 1.17178 0.861661 2.49685 + vertex 1.17 0.860684 2.495 + endloop + endfacet + facet normal -0.087769 -0.843628 0.529706 + outer loop + vertex 1.17178 0.861661 2.49685 + vertex 1.16725 0.861441 2.49575 + vertex 1.17 0.860684 2.495 + endloop + endfacet + facet normal 0.0326043 -0.918486 0.394106 + outer loop + vertex 1.17159 0.863171 2.50039 + vertex 1.17178 0.861661 2.49685 + vertex 1.17556 0.863092 2.49988 + endloop + endfacet + facet normal -0.010697 -0.919795 0.392253 + outer loop + vertex 1.17159 0.863171 2.50039 + vertex 1.16715 0.862677 2.49911 + vertex 1.17178 0.861661 2.49685 + endloop + endfacet + facet normal -0.0381156 -0.938126 0.344191 + outer loop + vertex 1.16715 0.862677 2.49911 + vertex 1.16725 0.861441 2.49575 + vertex 1.17178 0.861661 2.49685 + endloop + endfacet + facet normal -0.0129732 -0.916855 0.399009 + outer loop + vertex 1.17159 0.863171 2.50039 + vertex 1.16913 0.864097 2.50243 + vertex 1.16715 0.862677 2.49911 + endloop + endfacet + facet normal 0.0425183 -0.883849 0.465836 + outer loop + vertex 1.17556 0.863092 2.49988 + vertex 1.17319 0.864856 2.50344 + vertex 1.17159 0.863171 2.50039 + endloop + endfacet + facet normal 0.051313 -0.885362 0.462062 + outer loop + vertex 1.16913 0.864097 2.50243 + vertex 1.17159 0.863171 2.50039 + vertex 1.17319 0.864856 2.50344 + endloop + endfacet + facet normal 0.0327493 -0.856385 0.515298 + outer loop + vertex 1.16913 0.864097 2.50243 + vertex 1.17319 0.864856 2.50344 + vertex 1.16794 0.865994 2.50566 + endloop + endfacet + facet normal 0.060578 -0.823459 0.564132 + outer loop + vertex 1.16794 0.865994 2.50566 + vertex 1.17319 0.864856 2.50344 + vertex 1.17219 0.866838 2.50644 + endloop + endfacet + facet normal 0.0352196 -0.7665 0.641278 + outer loop + vertex 1.17219 0.866838 2.50644 + vertex 1.16938 0.86857 2.50866 + vertex 1.16794 0.865994 2.50566 + endloop + endfacet + facet normal 0.103332 -0.717389 0.688967 + outer loop + vertex 1.17407 0.869004 2.50841 + vertex 1.16938 0.86857 2.50866 + vertex 1.17219 0.866838 2.50644 + endloop + endfacet + facet normal 0.0992257 -0.62255 0.776264 + outer loop + vertex 1.16938 0.86857 2.50866 + vertex 1.17407 0.869004 2.50841 + vertex 1.17161 0.871505 2.51073 + endloop + endfacet + facet normal 0.1368 -0.638028 0.757764 + outer loop + vertex 1.1667 0.871228 2.51138 + vertex 1.16938 0.86857 2.50866 + vertex 1.17161 0.871505 2.51073 + endloop + endfacet + facet normal 0.141803 -0.50262 0.852799 + outer loop + vertex 1.17161 0.871505 2.51073 + vertex 1.16986 0.874816 2.51297 + vertex 1.1667 0.871228 2.51138 + endloop + endfacet + facet normal 0.175411 -0.486817 0.855711 + outer loop + vertex 1.17463 0.875065 2.51214 + vertex 1.16986 0.874816 2.51297 + vertex 1.17161 0.871505 2.51073 + endloop + endfacet + facet normal 0.300199 -0.00267512 0.953873 + outer loop + vertex 1.17178 0.988182 2.54176 + vertex 1.17093 0.993464 2.54204 + vertex 1.16764 0.988446 2.54306 + endloop + endfacet + facet normal 0.409487 -0.0835942 0.908478 + outer loop + vertex 1.16764 0.988446 2.54306 + vertex 1.17093 0.993464 2.54204 + vertex 1.16686 0.99246 2.54378 + endloop + endfacet + facet normal 0.567548 0.195707 0.799743 + outer loop + vertex 1.17441 0.996374 2.53969 + vertex 1.17374 1.0005 2.53916 + vertex 1.17156 0.998238 2.54126 + endloop + endfacet + facet normal 0.516162 0.0717302 0.853482 + outer loop + vertex 1.17156 0.998238 2.54126 + vertex 1.17093 0.993464 2.54204 + vertex 1.17441 0.996374 2.53969 + endloop + endfacet + facet normal 0.516579 0.0716349 0.853238 + outer loop + vertex 1.17156 0.998238 2.54126 + vertex 1.16775 0.998032 2.54359 + vertex 1.17093 0.993464 2.54204 + endloop + endfacet + facet normal 0.399759 -0.0310024 0.916096 + outer loop + vertex 1.16775 0.998032 2.54359 + vertex 1.16686 0.99246 2.54378 + vertex 1.17093 0.993464 2.54204 + endloop + endfacet + facet normal 0.622133 0.208938 0.754517 + outer loop + vertex 1.17374 1.0005 2.53916 + vertex 1.17344 1.00481 2.53821 + vertex 1.1708 1.00241 2.54105 + endloop + endfacet + facet normal 0.602039 0.148284 0.784577 + outer loop + vertex 1.17156 0.998238 2.54126 + vertex 1.17374 1.0005 2.53916 + vertex 1.1708 1.00241 2.54105 + endloop + endfacet + facet normal 0.510649 0.13494 0.849134 + outer loop + vertex 1.1708 1.00241 2.54105 + vertex 1.16775 0.998032 2.54359 + vertex 1.17156 0.998238 2.54126 + endloop + endfacet + facet normal 0.595592 0.048219 0.801839 + outer loop + vertex 1.1677 1.00451 2.54323 + vertex 1.16775 0.998032 2.54359 + vertex 1.1708 1.00241 2.54105 + endloop + endfacet + facet normal 0.695105 0.202141 0.689905 + outer loop + vertex 1.17344 1.00481 2.53821 + vertex 1.1735 1.00874 2.537 + vertex 1.17071 1.0081 2.54 + endloop + endfacet + facet normal 0.659657 0.147145 0.737022 + outer loop + vertex 1.1708 1.00241 2.54105 + vertex 1.17344 1.00481 2.53821 + vertex 1.17071 1.0081 2.54 + endloop + endfacet + facet normal 0.634326 0.150648 0.758245 + outer loop + vertex 1.17071 1.0081 2.54 + vertex 1.1677 1.00451 2.54323 + vertex 1.1708 1.00241 2.54105 + endloop + endfacet + facet normal 0.669834 0.1006 0.735664 + outer loop + vertex 1.16705 1.01025 2.54304 + vertex 1.1677 1.00451 2.54323 + vertex 1.17071 1.0081 2.54 + endloop + endfacet + facet normal 0.0947236 0.0484333 0.994325 + outer loop + vertex 1.175 1.01324 2.53 + vertex 1.1741 1.015 2.53 + vertex 1.17392 1.01405 2.53006 + endloop + endfacet + facet normal 0.79952 0.223235 0.557614 + outer loop + vertex 1.17457 1.01135 2.5345 + vertex 1.1736 1.01549 2.53423 + vertex 1.17251 1.01249 2.53701 + endloop + endfacet + facet normal 0.799151 0.210898 0.562921 + outer loop + vertex 1.1735 1.00874 2.537 + vertex 1.17457 1.01135 2.5345 + vertex 1.17251 1.01249 2.53701 + endloop + endfacet + facet normal 0.699628 0.184333 0.69032 + outer loop + vertex 1.1735 1.00874 2.537 + vertex 1.17251 1.01249 2.53701 + vertex 1.17071 1.0081 2.54 + endloop + endfacet + facet normal 0.73103 0.154054 0.664727 + outer loop + vertex 1.17071 1.0081 2.54 + vertex 1.17251 1.01249 2.53701 + vertex 1.16981 1.01341 2.53976 + endloop + endfacet + facet normal 0.681748 0.148077 0.716445 + outer loop + vertex 1.16981 1.01341 2.53976 + vertex 1.16705 1.01025 2.54304 + vertex 1.17071 1.0081 2.54 + endloop + endfacet + facet normal 0.712686 0.0981888 0.694577 + outer loop + vertex 1.1675 1.01449 2.54198 + vertex 1.16705 1.01025 2.54304 + vertex 1.16981 1.01341 2.53976 + endloop + endfacet + facet normal 0.596936 0.676097 -0.431926 + outer loop + vertex 1.1741 1.015 2.53 + vertex 1.17 1.01862 2.53 + vertex 1.17 1.02 2.53216 + endloop + endfacet + facet normal 0.441679 -0.0252538 0.896818 + outer loop + vertex 1.1741 1.015 2.53 + vertex 1.17 1.02 2.53216 + vertex 1.17392 1.01405 2.53006 + endloop + endfacet + facet normal -0.212669 0.197263 -0.957005 + outer loop + vertex 1.17392 1.01405 2.53006 + vertex 1.17 1.02 2.53216 + vertex 1.17226 1.01841 2.53133 + endloop + endfacet + facet normal 0.81665 0.309068 0.487401 + outer loop + vertex 1.1736 1.01549 2.53423 + vertex 1.17266 1.01893 2.53363 + vertex 1.17145 1.01763 2.53648 + endloop + endfacet + facet normal 0.801179 0.22118 0.55605 + outer loop + vertex 1.17251 1.01249 2.53701 + vertex 1.1736 1.01549 2.53423 + vertex 1.17145 1.01763 2.53648 + endloop + endfacet + facet normal 0.732491 0.216174 0.645543 + outer loop + vertex 1.17251 1.01249 2.53701 + vertex 1.17145 1.01763 2.53648 + vertex 1.16981 1.01341 2.53976 + endloop + endfacet + facet normal 0.7952 0.147322 0.588178 + outer loop + vertex 1.17145 1.01763 2.53648 + vertex 1.16892 1.01758 2.53991 + vertex 1.16981 1.01341 2.53976 + endloop + endfacet + facet normal 0.717151 0.127092 0.685232 + outer loop + vertex 1.16892 1.01758 2.53991 + vertex 1.1675 1.01449 2.54198 + vertex 1.16981 1.01341 2.53976 + endloop + endfacet + facet normal 0.738211 0.104791 0.666381 + outer loop + vertex 1.1667 1.01715 2.54245 + vertex 1.1675 1.01449 2.54198 + vertex 1.16892 1.01758 2.53991 + endloop + endfacet + facet normal 0.922327 0.360157 0.139999 + outer loop + vertex 1.17196 1.0205 2.53241 + vertex 1.17 1.025 2.53374 + vertex 1.17057 1.02337 2.53421 + endloop + endfacet + facet normal 0.541272 0.446604 -0.712439 + outer loop + vertex 1.17196 1.0205 2.53241 + vertex 1.17226 1.01841 2.53133 + vertex 1.17 1.025 2.53374 + endloop + endfacet + facet normal -0.137017 0.298472 -0.944532 + outer loop + vertex 1.17226 1.01841 2.53133 + vertex 1.17 1.02 2.53216 + vertex 1.17 1.025 2.53374 + endloop + endfacet + facet normal 0.905432 0.423721 0.0255614 + outer loop + vertex 1.17266 1.01893 2.53363 + vertex 1.17196 1.0205 2.53241 + vertex 1.17057 1.02337 2.53421 + endloop + endfacet + facet normal 0.811203 0.319411 0.489823 + outer loop + vertex 1.17266 1.01893 2.53363 + vertex 1.17057 1.02337 2.53421 + vertex 1.17145 1.01763 2.53648 + endloop + endfacet + facet normal 0.898587 0.274352 0.34245 + outer loop + vertex 1.17145 1.01763 2.53648 + vertex 1.17057 1.02337 2.53421 + vertex 1.16964 1.02205 2.53771 + endloop + endfacet + facet normal 0.839202 0.0417183 0.542217 + outer loop + vertex 1.16737 1.02106 2.54128 + vertex 1.16964 1.02205 2.53771 + vertex 1.16843 1.0252 2.53934 + endloop + endfacet + facet normal 0.817648 0.144937 0.557176 + outer loop + vertex 1.16737 1.02106 2.54128 + vertex 1.16892 1.01758 2.53991 + vertex 1.16964 1.02205 2.53771 + endloop + endfacet + facet normal 0.793054 0.163501 0.586799 + outer loop + vertex 1.16892 1.01758 2.53991 + vertex 1.17145 1.01763 2.53648 + vertex 1.16964 1.02205 2.53771 + endloop + endfacet + facet normal 0.743609 0.0693501 0.665008 + outer loop + vertex 1.16892 1.01758 2.53991 + vertex 1.16737 1.02106 2.54128 + vertex 1.1667 1.01715 2.54245 + endloop + endfacet + facet normal 0.862664 0.163048 -0.478777 + outer loop + vertex 1.17 1.025 2.53374 + vertex 1.17 1.0287 2.535 + vertex 1.17057 1.02337 2.53421 + endloop + endfacet + facet normal -0.625271 -0.179584 0.759464 + outer loop + vertex 1.16901 1.0282 2.53406 + vertex 1.17057 1.02337 2.53421 + vertex 1.17 1.0287 2.535 + endloop + endfacet + facet normal 0.949849 0.308283 0.0524217 + outer loop + vertex 1.16901 1.0282 2.53406 + vertex 1.16911 1.02754 2.53605 + vertex 1.17057 1.02337 2.53421 + endloop + endfacet + facet normal 0.930277 0.184535 0.317066 + outer loop + vertex 1.16911 1.02754 2.53605 + vertex 1.16964 1.02205 2.53771 + vertex 1.17057 1.02337 2.53421 + endloop + endfacet + facet normal 0.926595 0.18697 0.326288 + outer loop + vertex 1.16911 1.02754 2.53605 + vertex 1.16843 1.0252 2.53934 + vertex 1.16964 1.02205 2.53771 + endloop + endfacet + facet normal 0.958815 0.0950515 0.267656 + outer loop + vertex 1.16821 1.02959 2.53857 + vertex 1.16843 1.0252 2.53934 + vertex 1.16911 1.02754 2.53605 + endloop + endfacet + facet normal 0.93186 0.356134 0.0693137 + outer loop + vertex 1.16723 1.03268 2.53491 + vertex 1.16911 1.02754 2.53605 + vertex 1.16901 1.0282 2.53406 + endloop + endfacet + facet normal 0.861448 0.212568 -0.461219 + outer loop + vertex 1.16826 1.0317 2.53638 + vertex 1.16911 1.02754 2.53605 + vertex 1.16723 1.03268 2.53491 + endloop + endfacet + facet normal 0.963123 0.18008 0.199913 + outer loop + vertex 1.16826 1.0317 2.53638 + vertex 1.16821 1.02959 2.53857 + vertex 1.16911 1.02754 2.53605 + endloop + endfacet + facet normal 0.950244 0.210856 0.229294 + outer loop + vertex 1.16754 1.03337 2.53785 + vertex 1.16821 1.02959 2.53857 + vertex 1.16826 1.0317 2.53638 + endloop + endfacet + facet normal 0.86152 0.341546 -0.375672 + outer loop + vertex 1.16723 1.03268 2.53491 + vertex 1.16698 1.03505 2.53648 + vertex 1.16826 1.0317 2.53638 + endloop + endfacet + facet normal 0.932763 0.356356 0.0544292 + outer loop + vertex 1.16826 1.0317 2.53638 + vertex 1.16698 1.03505 2.53648 + vertex 1.16754 1.03337 2.53785 + endloop + endfacet + facet normal 0.530112 -0.599719 0.599431 + outer loop + vertex 1.17047 2.00978 2.53135 + vertex 1.17 2.00802 2.53 + vertex 1.17224 2.01 2.53 + endloop + endfacet + facet normal 0.973281 -0.225583 -0.0428535 + outer loop + vertex 1.17 2.00707 2.535 + vertex 1.17 2.00802 2.53 + vertex 1.17047 2.00978 2.53135 + endloop + endfacet + facet normal 0.403534 0.708935 0.578421 + outer loop + vertex 1.17047 2.00978 2.53135 + vertex 1.16899 2.0083 2.5342 + vertex 1.17 2.00707 2.535 + endloop + endfacet + facet normal 0.61059 -0.103793 0.785116 + outer loop + vertex 1.17224 2.01 2.53 + vertex 1.17309 2.015 2.53 + vertex 1.17047 2.00978 2.53135 + endloop + endfacet + facet normal 0.837074 -0.302821 0.455638 + outer loop + vertex 1.17309 2.015 2.53 + vertex 1.17177 2.01394 2.53173 + vertex 1.17047 2.00978 2.53135 + endloop + endfacet + facet normal 0.859487 -0.273277 0.431975 + outer loop + vertex 1.16899 2.0083 2.5342 + vertex 1.16984 2.01166 2.53462 + vertex 1.16821 2.00981 2.53671 + endloop + endfacet + facet normal 0.904531 -0.2716 0.328721 + outer loop + vertex 1.16899 2.0083 2.5342 + vertex 1.17047 2.00978 2.53135 + vertex 1.16984 2.01166 2.53462 + endloop + endfacet + facet normal 0.886084 -0.308239 0.346184 + outer loop + vertex 1.17047 2.00978 2.53135 + vertex 1.17177 2.01394 2.53173 + vertex 1.16984 2.01166 2.53462 + endloop + endfacet + facet normal 0.861033 -0.292905 0.415727 + outer loop + vertex 1.16984 2.01166 2.53462 + vertex 1.16865 2.01366 2.53851 + vertex 1.16821 2.00981 2.53671 + endloop + endfacet + facet normal 0.81682 -0.438195 0.37522 + outer loop + vertex 1.175 2.01849 2.53 + vertex 1.17294 2.01647 2.53213 + vertex 1.17177 2.01394 2.53173 + endloop + endfacet + facet normal 0.82056 -0.449071 0.353577 + outer loop + vertex 1.17309 2.015 2.53 + vertex 1.175 2.01849 2.53 + vertex 1.17177 2.01394 2.53173 + endloop + endfacet + facet normal 0.737595 -0.601826 0.3062 + outer loop + vertex 1.17294 2.01647 2.53213 + vertex 1.17337 2.01793 2.53395 + vertex 1.17143 2.01668 2.53619 + endloop + endfacet + facet normal 0.833918 -0.439473 0.333834 + outer loop + vertex 1.17294 2.01647 2.53213 + vertex 1.17143 2.01668 2.53619 + vertex 1.17177 2.01394 2.53173 + endloop + endfacet + facet normal 0.881276 -0.369564 0.294575 + outer loop + vertex 1.17177 2.01394 2.53173 + vertex 1.17143 2.01668 2.53619 + vertex 1.16984 2.01166 2.53462 + endloop + endfacet + facet normal 0.802408 -0.392835 0.449246 + outer loop + vertex 1.17143 2.01668 2.53619 + vertex 1.16865 2.01366 2.53851 + vertex 1.16984 2.01166 2.53462 + endloop + endfacet + facet normal 0.787965 -0.321235 0.52528 + outer loop + vertex 1.16917 2.01728 2.53994 + vertex 1.16865 2.01366 2.53851 + vertex 1.17143 2.01668 2.53619 + endloop + endfacet + facet normal 0.761619 -0.536382 0.363636 + outer loop + vertex 1.17337 2.01793 2.53395 + vertex 1.17328 2.01907 2.53583 + vertex 1.17143 2.01668 2.53619 + endloop + endfacet + facet normal 0.694503 -0.277739 0.663722 + outer loop + vertex 1.16917 2.01728 2.53994 + vertex 1.17024 2.02042 2.54014 + vertex 1.16844 2.01929 2.54154 + endloop + endfacet + facet normal 0.794444 -0.303136 0.526276 + outer loop + vertex 1.17143 2.01668 2.53619 + vertex 1.17024 2.02042 2.54014 + vertex 1.16917 2.01728 2.53994 + endloop + endfacet + facet normal 0.679568 -0.41954 0.601808 + outer loop + vertex 1.17143 2.01668 2.53619 + vertex 1.17316 2.02188 2.53786 + vertex 1.17024 2.02042 2.54014 + endloop + endfacet + facet normal 0.660923 -0.419832 0.62203 + outer loop + vertex 1.17143 2.01668 2.53619 + vertex 1.17328 2.01907 2.53583 + vertex 1.17316 2.02188 2.53786 + endloop + endfacet + facet normal 0.650389 -0.0966347 0.753429 + outer loop + vertex 1.17024 2.02042 2.54014 + vertex 1.16732 2.02282 2.54296 + vertex 1.16844 2.01929 2.54154 + endloop + endfacet + facet normal 0.613571 -0.350252 0.707711 + outer loop + vertex 1.17316 2.02188 2.53786 + vertex 1.17377 2.02627 2.53949 + vertex 1.17116 2.02474 2.541 + endloop + endfacet + facet normal 0.673854 -0.281158 0.68328 + outer loop + vertex 1.17024 2.02042 2.54014 + vertex 1.17316 2.02188 2.53786 + vertex 1.17116 2.02474 2.541 + endloop + endfacet + facet normal 0.542664 -0.275072 0.793632 + outer loop + vertex 1.17116 2.02474 2.541 + vertex 1.16732 2.02282 2.54296 + vertex 1.17024 2.02042 2.54014 + endloop + endfacet + facet normal 0.502297 -0.132171 0.854534 + outer loop + vertex 1.16923 2.02824 2.54267 + vertex 1.16732 2.02282 2.54296 + vertex 1.17116 2.02474 2.541 + endloop + endfacet + facet normal 0.588881 -0.247378 0.769431 + outer loop + vertex 1.17377 2.02627 2.53949 + vertex 1.17233 2.02836 2.54127 + vertex 1.17116 2.02474 2.541 + endloop + endfacet + facet normal 0.411307 -0.198998 0.889509 + outer loop + vertex 1.17233 2.02836 2.54127 + vertex 1.16923 2.02824 2.54267 + vertex 1.17116 2.02474 2.541 + endloop + endfacet + facet normal 0.414186 -0.0710047 0.907419 + outer loop + vertex 1.17233 2.02836 2.54127 + vertex 1.17175 2.03181 2.54181 + vertex 1.16923 2.02824 2.54267 + endloop + endfacet + facet normal 0.172924 0.535209 0.82683 + outer loop + vertex 1.16951 2.15375 2.51102 + vertex 1.17365 2.15284 2.51074 + vertex 1.17296 2.15599 2.50885 + endloop + endfacet + facet normal 0.120304 0.589161 0.799009 + outer loop + vertex 1.1673 2.15666 2.50921 + vertex 1.16951 2.15375 2.51102 + vertex 1.17296 2.15599 2.50885 + endloop + endfacet + facet normal 0.201536 0.4325 0.878822 + outer loop + vertex 1.17182 2.14997 2.51235 + vertex 1.16951 2.15375 2.51102 + vertex 1.16668 2.15135 2.51285 + endloop + endfacet + facet normal 0.150201 0.408588 0.900275 + outer loop + vertex 1.17365 2.15284 2.51074 + vertex 1.16951 2.15375 2.51102 + vertex 1.17182 2.14997 2.51235 + endloop + endfacet + facet normal 0.0539915 0.834078 0.548999 + outer loop + vertex 1.16961 2.15878 2.50652 + vertex 1.17483 2.15872 2.5061 + vertex 1.17166 2.16066 2.50347 + endloop + endfacet + facet normal 0.0109951 0.848496 0.529087 + outer loop + vertex 1.16641 2.16072 2.50348 + vertex 1.16961 2.15878 2.50652 + vertex 1.17166 2.16066 2.50347 + endloop + endfacet + facet normal 0.128282 0.721339 0.680598 + outer loop + vertex 1.17296 2.15599 2.50885 + vertex 1.16961 2.15878 2.50652 + vertex 1.1673 2.15666 2.50921 + endloop + endfacet + facet normal 0.0664587 0.684841 0.725656 + outer loop + vertex 1.17483 2.15872 2.5061 + vertex 1.16961 2.15878 2.50652 + vertex 1.17296 2.15599 2.50885 + endloop + endfacet + facet normal -0.0122622 0.360668 0.932614 + outer loop + vertex 1.175 2.16755 2.495 + vertex 1.17 2.16738 2.495 + vertex 1.17366 2.16404 2.49634 + endloop + endfacet + facet normal 0.0466454 0.415472 0.908409 + outer loop + vertex 1.17366 2.16404 2.49634 + vertex 1.17 2.16738 2.495 + vertex 1.16876 2.16398 2.49662 + endloop + endfacet + facet normal 0.015377 0.886935 0.461638 + outer loop + vertex 1.17366 2.16404 2.49634 + vertex 1.16876 2.16398 2.49662 + vertex 1.17296 2.16217 2.49995 + endloop + endfacet + facet normal 0.0156246 0.887059 0.461392 + outer loop + vertex 1.17296 2.16217 2.49995 + vertex 1.16876 2.16398 2.49662 + vertex 1.16791 2.1622 2.50006 + endloop + endfacet + facet normal 0.0116169 0.915396 0.402387 + outer loop + vertex 1.17166 2.16066 2.50347 + vertex 1.16791 2.1622 2.50006 + vertex 1.16641 2.16072 2.50348 + endloop + endfacet + facet normal 0.0143502 0.91646 0.399869 + outer loop + vertex 1.17296 2.16217 2.49995 + vertex 1.16791 2.1622 2.50006 + vertex 1.17166 2.16066 2.50347 + endloop + endfacet + facet normal 0.0432639 -0.974292 0.221096 + outer loop + vertex 1.18 0.859573 2.49 + vertex 1.175 0.86 2.49286 + vertex 1.175 0.859351 2.49 + endloop + endfacet + facet normal -0.114089 -0.992144 -0.0513249 + outer loop + vertex 1.18079 0.859451 2.49061 + vertex 1.175 0.86 2.49286 + vertex 1.18 0.859573 2.49 + endloop + endfacet + facet normal 0.038947 -0.943279 0.329709 + outer loop + vertex 1.175 0.86 2.49286 + vertex 1.18079 0.859451 2.49061 + vertex 1.17849 0.860282 2.49325 + endloop + endfacet + facet normal 0.0489486 -0.965259 0.256668 + outer loop + vertex 1.175 0.860569 2.495 + vertex 1.175 0.86 2.49286 + vertex 1.17849 0.860282 2.49325 + endloop + endfacet + facet normal 0.138406 -0.895092 0.423857 + outer loop + vertex 1.17849 0.860282 2.49325 + vertex 1.17704 0.86154 2.49639 + vertex 1.175 0.860569 2.495 + endloop + endfacet + facet normal 0.0291226 -0.838072 0.544781 + outer loop + vertex 1.17704 0.86154 2.49639 + vertex 1.17178 0.861661 2.49685 + vertex 1.175 0.860569 2.495 + endloop + endfacet + facet normal 0.0156357 -0.911144 0.411792 + outer loop + vertex 1.17704 0.86154 2.49639 + vertex 1.17556 0.863092 2.49988 + vertex 1.17178 0.861661 2.49685 + endloop + endfacet + facet normal 0.0467795 -0.905208 0.422387 + outer loop + vertex 1.18031 0.863146 2.49946 + vertex 1.17556 0.863092 2.49988 + vertex 1.17704 0.86154 2.49639 + endloop + endfacet + facet normal 0.051972 -0.871989 0.486759 + outer loop + vertex 1.17556 0.863092 2.49988 + vertex 1.18031 0.863146 2.49946 + vertex 1.17843 0.864881 2.50277 + endloop + endfacet + facet normal 0.064671 -0.876543 0.476958 + outer loop + vertex 1.17319 0.864856 2.50344 + vertex 1.17556 0.863092 2.49988 + vertex 1.17843 0.864881 2.50277 + endloop + endfacet + facet normal 0.0781302 -0.806673 0.585811 + outer loop + vertex 1.17843 0.864881 2.50277 + vertex 1.17642 0.866894 2.50581 + vertex 1.17319 0.864856 2.50344 + endloop + endfacet + facet normal 0.0951148 -0.815761 0.570515 + outer loop + vertex 1.17642 0.866894 2.50581 + vertex 1.17219 0.866838 2.50644 + vertex 1.17319 0.864856 2.50344 + endloop + endfacet + facet normal 0.110724 -0.720129 0.684949 + outer loop + vertex 1.17642 0.866894 2.50581 + vertex 1.17407 0.869004 2.50841 + vertex 1.17219 0.866838 2.50644 + endloop + endfacet + facet normal 0.154915 -0.693654 0.703453 + outer loop + vertex 1.17938 0.870008 2.50823 + vertex 1.17407 0.869004 2.50841 + vertex 1.17642 0.866894 2.50581 + endloop + endfacet + facet normal 0.139593 -0.596948 0.790042 + outer loop + vertex 1.17407 0.869004 2.50841 + vertex 1.17938 0.870008 2.50823 + vertex 1.17622 0.872011 2.5103 + endloop + endfacet + facet normal 0.13892 -0.596672 0.790369 + outer loop + vertex 1.17161 0.871505 2.51073 + vertex 1.17407 0.869004 2.50841 + vertex 1.17622 0.872011 2.5103 + endloop + endfacet + facet normal 0.131991 -0.45905 0.878551 + outer loop + vertex 1.17622 0.872011 2.5103 + vertex 1.17463 0.875065 2.51214 + vertex 1.17161 0.871505 2.51073 + endloop + endfacet + facet normal 0.163358 -0.444151 0.880934 + outer loop + vertex 1.17893 0.875387 2.5115 + vertex 1.17463 0.875065 2.51214 + vertex 1.17622 0.872011 2.5103 + endloop + endfacet + facet normal 0.414737 0.0182603 0.909758 + outer loop + vertex 1.17776 0.983945 2.5395 + vertex 1.17787 0.988642 2.53935 + vertex 1.17509 0.986762 2.54066 + endloop + endfacet + facet normal 0.35021 -0.0531321 0.935163 + outer loop + vertex 1.17434 0.98304 2.54073 + vertex 1.17776 0.983945 2.5395 + vertex 1.17509 0.986762 2.54066 + endloop + endfacet + facet normal 0.295931 -0.0417231 0.954298 + outer loop + vertex 1.17509 0.986762 2.54066 + vertex 1.172 0.983991 2.5415 + vertex 1.17434 0.98304 2.54073 + endloop + endfacet + facet normal 0.298512 -0.0448974 0.953349 + outer loop + vertex 1.17178 0.988182 2.54176 + vertex 1.172 0.983991 2.5415 + vertex 1.17509 0.986762 2.54066 + endloop + endfacet + facet normal 0.456892 0.173577 0.872422 + outer loop + vertex 1.17787 0.988642 2.53935 + vertex 1.17892 0.991451 2.53825 + vertex 1.17547 0.991615 2.54002 + endloop + endfacet + facet normal 0.370931 0.0926958 0.924023 + outer loop + vertex 1.17509 0.986762 2.54066 + vertex 1.17787 0.988642 2.53935 + vertex 1.17547 0.991615 2.54002 + endloop + endfacet + facet normal 0.351168 0.0951884 0.931461 + outer loop + vertex 1.17547 0.991615 2.54002 + vertex 1.17178 0.988182 2.54176 + vertex 1.17509 0.986762 2.54066 + endloop + endfacet + facet normal 0.413243 0.017763 0.910447 + outer loop + vertex 1.17093 0.993464 2.54204 + vertex 1.17178 0.988182 2.54176 + vertex 1.17547 0.991615 2.54002 + endloop + endfacet + facet normal 0.612838 0.283107 0.737753 + outer loop + vertex 1.1783 0.995197 2.53737 + vertex 1.17905 0.999225 2.53521 + vertex 1.17634 0.998738 2.53765 + endloop + endfacet + facet normal 0.589706 0.197187 0.783176 + outer loop + vertex 1.17634 0.998738 2.53765 + vertex 1.17374 1.0005 2.53916 + vertex 1.17441 0.996374 2.53969 + endloop + endfacet + facet normal 0.549782 0.2434 0.79906 + outer loop + vertex 1.1783 0.995197 2.53737 + vertex 1.17634 0.998738 2.53765 + vertex 1.17441 0.996374 2.53969 + endloop + endfacet + facet normal 0.542721 0.176744 0.821106 + outer loop + vertex 1.1783 0.995197 2.53737 + vertex 1.17441 0.996374 2.53969 + vertex 1.17547 0.991615 2.54002 + endloop + endfacet + facet normal 0.450295 0.27164 0.850556 + outer loop + vertex 1.1783 0.995197 2.53737 + vertex 1.17547 0.991615 2.54002 + vertex 1.17892 0.991451 2.53825 + endloop + endfacet + facet normal 0.456038 0.161311 0.875219 + outer loop + vertex 1.17547 0.991615 2.54002 + vertex 1.17441 0.996374 2.53969 + vertex 1.17093 0.993464 2.54204 + endloop + endfacet + facet normal 0.663085 0.33721 0.668287 + outer loop + vertex 1.17905 0.999225 2.53521 + vertex 1.17877 1.00342 2.53337 + vertex 1.17622 1.00226 2.53648 + endloop + endfacet + facet normal 0.61812 0.265111 0.74003 + outer loop + vertex 1.17634 0.998738 2.53765 + vertex 1.17905 0.999225 2.53521 + vertex 1.17622 1.00226 2.53648 + endloop + endfacet + facet normal 0.613381 0.266135 0.743596 + outer loop + vertex 1.17622 1.00226 2.53648 + vertex 1.17374 1.0005 2.53916 + vertex 1.17634 0.998738 2.53765 + endloop + endfacet + facet normal 0.646256 0.206282 0.734711 + outer loop + vertex 1.17344 1.00481 2.53821 + vertex 1.17374 1.0005 2.53916 + vertex 1.17622 1.00226 2.53648 + endloop + endfacet + facet normal -0.199932 -0.177687 0.963563 + outer loop + vertex 1.18 1.00991 2.53 + vertex 1.17992 1.01 2.53 + vertex 1.17739 1.00927 2.52934 + endloop + endfacet + facet normal 0.736731 0.375112 0.562599 + outer loop + vertex 1.17877 1.00342 2.53337 + vertex 1.17762 1.00658 2.53277 + vertex 1.17588 1.00676 2.53493 + endloop + endfacet + facet normal 0.687776 0.283208 0.668399 + outer loop + vertex 1.17622 1.00226 2.53648 + vertex 1.17877 1.00342 2.53337 + vertex 1.17588 1.00676 2.53493 + endloop + endfacet + facet normal 0.681059 0.284827 0.674561 + outer loop + vertex 1.17588 1.00676 2.53493 + vertex 1.17344 1.00481 2.53821 + vertex 1.17622 1.00226 2.53648 + endloop + endfacet + facet normal 0.730434 0.191063 0.655714 + outer loop + vertex 1.1735 1.00874 2.537 + vertex 1.17344 1.00481 2.53821 + vertex 1.17588 1.00676 2.53493 + endloop + endfacet + facet normal 0.238147 0.361632 -0.901393 + outer loop + vertex 1.175 1.01 2.5287 + vertex 1.175 1.01324 2.53 + vertex 1.17992 1.01 2.53 + endloop + endfacet + facet normal 0.895354 0.380044 -0.232181 + outer loop + vertex 1.17619 1.00978 2.53186 + vertex 1.17392 1.01405 2.53006 + vertex 1.17427 1.01446 2.53209 + endloop + endfacet + facet normal 0.798039 0.539181 0.269105 + outer loop + vertex 1.17739 1.00927 2.52934 + vertex 1.17392 1.01405 2.53006 + vertex 1.17619 1.00978 2.53186 + endloop + endfacet + facet normal -0.115806 -0.230275 0.96621 + outer loop + vertex 1.17739 1.00927 2.52934 + vertex 1.175 1.01324 2.53 + vertex 1.17392 1.01405 2.53006 + endloop + endfacet + facet normal -0.17221 -0.261506 0.949715 + outer loop + vertex 1.17739 1.00927 2.52934 + vertex 1.17992 1.01 2.53 + vertex 1.175 1.01324 2.53 + endloop + endfacet + facet normal 0.954286 0.235494 0.184067 + outer loop + vertex 1.17427 1.01446 2.53209 + vertex 1.1736 1.01549 2.53423 + vertex 1.17457 1.01135 2.5345 + endloop + endfacet + facet normal 0.877292 0.344497 0.334187 + outer loop + vertex 1.17619 1.00978 2.53186 + vertex 1.17427 1.01446 2.53209 + vertex 1.17457 1.01135 2.5345 + endloop + endfacet + facet normal 0.882889 0.285849 0.372555 + outer loop + vertex 1.17619 1.00978 2.53186 + vertex 1.17457 1.01135 2.5345 + vertex 1.17588 1.00676 2.53493 + endloop + endfacet + facet normal 0.707648 0.465375 0.531658 + outer loop + vertex 1.17619 1.00978 2.53186 + vertex 1.17588 1.00676 2.53493 + vertex 1.17762 1.00658 2.53277 + endloop + endfacet + facet normal 0.750433 0.269677 0.603428 + outer loop + vertex 1.17588 1.00676 2.53493 + vertex 1.17457 1.01135 2.5345 + vertex 1.1735 1.00874 2.537 + endloop + endfacet + facet normal 0.884293 0.403526 -0.23493 + outer loop + vertex 1.17226 1.01841 2.53133 + vertex 1.17427 1.01446 2.53209 + vertex 1.17392 1.01405 2.53006 + endloop + endfacet + facet normal 0.762654 0.273955 -0.585924 + outer loop + vertex 1.17338 1.01758 2.5324 + vertex 1.17427 1.01446 2.53209 + vertex 1.17226 1.01841 2.53133 + endloop + endfacet + facet normal 0.951484 0.253398 0.174552 + outer loop + vertex 1.17338 1.01758 2.5324 + vertex 1.1736 1.01549 2.53423 + vertex 1.17427 1.01446 2.53209 + endloop + endfacet + facet normal 0.929377 0.293934 0.223297 + outer loop + vertex 1.17266 1.01893 2.53363 + vertex 1.1736 1.01549 2.53423 + vertex 1.17338 1.01758 2.5324 + endloop + endfacet + facet normal 0.77053 0.377336 -0.513713 + outer loop + vertex 1.17226 1.01841 2.53133 + vertex 1.17196 1.0205 2.53241 + vertex 1.17338 1.01758 2.5324 + endloop + endfacet + facet normal 0.897885 0.437644 0.0476418 + outer loop + vertex 1.17338 1.01758 2.5324 + vertex 1.17196 1.0205 2.53241 + vertex 1.17266 1.01893 2.53363 + endloop + endfacet + facet normal -0.919534 -0.216999 -0.327671 + outer loop + vertex 1.17555 2.02035 2.52722 + vertex 1.175 2.01849 2.53 + vertex 1.175 2.02 2.529 + endloop + endfacet + facet normal 0.791395 0.423914 0.440444 + outer loop + vertex 1.17441 2.0186 2.53096 + vertex 1.175 2.01849 2.53 + vertex 1.17555 2.02035 2.52722 + endloop + endfacet + facet normal 0.805978 -0.263215 0.530206 + outer loop + vertex 1.17294 2.01647 2.53213 + vertex 1.175 2.01849 2.53 + vertex 1.17441 2.0186 2.53096 + endloop + endfacet + facet normal 0.854059 -0.485751 0.186092 + outer loop + vertex 1.17441 2.0186 2.53096 + vertex 1.17337 2.01793 2.53395 + vertex 1.17294 2.01647 2.53213 + endloop + endfacet + facet normal -0.762561 -0.547961 -0.34386 + outer loop + vertex 1.175 2.02251 2.525 + vertex 1.17555 2.02035 2.52722 + vertex 1.175 2.02 2.529 + endloop + endfacet + facet normal 0.396958 -0.605795 -0.689519 + outer loop + vertex 1.1788 2.025 2.525 + vertex 1.17555 2.02035 2.52722 + vertex 1.175 2.02251 2.525 + endloop + endfacet + facet normal 0.454522 -0.621479 -0.638102 + outer loop + vertex 1.1788 2.025 2.525 + vertex 1.17775 2.02256 2.52663 + vertex 1.17555 2.02035 2.52722 + endloop + endfacet + facet normal -0.887235 0.0803449 -0.454267 + outer loop + vertex 1.1788 2.025 2.525 + vertex 1.17878 2.02392 2.52486 + vertex 1.17775 2.02256 2.52663 + endloop + endfacet + facet normal 0.683707 -0.724173 0.0901036 + outer loop + vertex 1.17775 2.02256 2.52663 + vertex 1.17867 2.02376 2.52931 + vertex 1.17647 2.02187 2.53082 + endloop + endfacet + facet normal 0.719721 -0.685907 0.107389 + outer loop + vertex 1.17775 2.02256 2.52663 + vertex 1.17647 2.02187 2.53082 + vertex 1.17555 2.02035 2.52722 + endloop + endfacet + facet normal 0.846082 -0.532945 0.0107173 + outer loop + vertex 1.17555 2.02035 2.52722 + vertex 1.17647 2.02187 2.53082 + vertex 1.17441 2.0186 2.53096 + endloop + endfacet + facet normal 0.842825 -0.440558 0.309118 + outer loop + vertex 1.17337 2.01793 2.53395 + vertex 1.17462 2.02061 2.53437 + vertex 1.17328 2.01907 2.53583 + endloop + endfacet + facet normal 0.875004 -0.439107 0.203843 + outer loop + vertex 1.17337 2.01793 2.53395 + vertex 1.17441 2.0186 2.53096 + vertex 1.17462 2.02061 2.53437 + endloop + endfacet + facet normal 0.824376 -0.50884 0.247965 + outer loop + vertex 1.17441 2.0186 2.53096 + vertex 1.17647 2.02187 2.53082 + vertex 1.17462 2.02061 2.53437 + endloop + endfacet + facet normal 0.838342 -0.294384 0.458826 + outer loop + vertex 1.17462 2.02061 2.53437 + vertex 1.17316 2.02188 2.53786 + vertex 1.17328 2.01907 2.53583 + endloop + endfacet + facet normal -0.148433 0.132929 -0.979948 + outer loop + vertex 1.18 2.02634 2.525 + vertex 1.17878 2.02392 2.52486 + vertex 1.1788 2.025 2.525 + endloop + endfacet + facet normal 0.729363 -0.621544 0.285854 + outer loop + vertex 1.17867 2.02376 2.52931 + vertex 1.17836 2.02482 2.5324 + vertex 1.17647 2.02187 2.53082 + endloop + endfacet + facet normal 0.633802 -0.600348 0.487726 + outer loop + vertex 1.17836 2.02482 2.5324 + vertex 1.17913 2.02716 2.53428 + vertex 1.17657 2.02592 2.53607 + endloop + endfacet + facet normal 0.596487 -0.641745 0.482044 + outer loop + vertex 1.17836 2.02482 2.5324 + vertex 1.17657 2.02592 2.53607 + vertex 1.17647 2.02187 2.53082 + endloop + endfacet + facet normal 0.859771 -0.412978 0.300405 + outer loop + vertex 1.17647 2.02187 2.53082 + vertex 1.17657 2.02592 2.53607 + vertex 1.17462 2.02061 2.53437 + endloop + endfacet + facet normal 0.763094 -0.434386 0.478536 + outer loop + vertex 1.17657 2.02592 2.53607 + vertex 1.17316 2.02188 2.53786 + vertex 1.17462 2.02061 2.53437 + endloop + endfacet + facet normal 0.713447 -0.33075 0.617736 + outer loop + vertex 1.17377 2.02627 2.53949 + vertex 1.17316 2.02188 2.53786 + vertex 1.17657 2.02592 2.53607 + endloop + endfacet + facet normal 0.647484 -0.491741 0.582199 + outer loop + vertex 1.17913 2.02716 2.53428 + vertex 1.17891 2.02888 2.53597 + vertex 1.17657 2.02592 2.53607 + endloop + endfacet + facet normal 0.606197 -0.228889 0.761666 + outer loop + vertex 1.17377 2.02627 2.53949 + vertex 1.17486 2.03008 2.53977 + vertex 1.17233 2.02836 2.54127 + endloop + endfacet + facet normal 0.735126 -0.255738 0.627844 + outer loop + vertex 1.17657 2.02592 2.53607 + vertex 1.17486 2.03008 2.53977 + vertex 1.17377 2.02627 2.53949 + endloop + endfacet + facet normal 0.603606 -0.376661 0.702699 + outer loop + vertex 1.17657 2.02592 2.53607 + vertex 1.17885 2.03256 2.53768 + vertex 1.17486 2.03008 2.53977 + endloop + endfacet + facet normal 0.489273 -0.359636 0.794528 + outer loop + vertex 1.17657 2.02592 2.53607 + vertex 1.17891 2.02888 2.53597 + vertex 1.17885 2.03256 2.53768 + endloop + endfacet + facet normal 0.530033 -0.0419695 0.846938 + outer loop + vertex 1.17486 2.03008 2.53977 + vertex 1.17175 2.03181 2.54181 + vertex 1.17233 2.02836 2.54127 + endloop + endfacet + facet normal 0.503524 -0.147656 0.851271 + outer loop + vertex 1.17885 2.03256 2.53768 + vertex 1.17826 2.03909 2.53916 + vertex 1.17484 2.03486 2.54045 + endloop + endfacet + facet normal 0.518117 -0.117314 0.847226 + outer loop + vertex 1.17486 2.03008 2.53977 + vertex 1.17885 2.03256 2.53768 + vertex 1.17484 2.03486 2.54045 + endloop + endfacet + facet normal 0.495677 -0.11922 0.860285 + outer loop + vertex 1.17484 2.03486 2.54045 + vertex 1.17175 2.03181 2.54181 + vertex 1.17486 2.03008 2.53977 + endloop + endfacet + facet normal 0.196183 0.41138 0.8901 + outer loop + vertex 1.17365 2.15284 2.51074 + vertex 1.17594 2.15047 2.51134 + vertex 1.17796 2.15328 2.50959 + endloop + endfacet + facet normal 0.166944 0.534792 0.828328 + outer loop + vertex 1.17365 2.15284 2.51074 + vertex 1.17796 2.15328 2.50959 + vertex 1.17296 2.15599 2.50885 + endloop + endfacet + facet normal 0.149258 0.507656 0.848532 + outer loop + vertex 1.17296 2.15599 2.50885 + vertex 1.17796 2.15328 2.50959 + vertex 1.1776 2.15662 2.50766 + endloop + endfacet + facet normal 0.174904 0.393945 0.902339 + outer loop + vertex 1.17594 2.15047 2.51134 + vertex 1.17365 2.15284 2.51074 + vertex 1.17182 2.14997 2.51235 + endloop + endfacet + facet normal 0.0900632 0.816871 0.569745 + outer loop + vertex 1.17483 2.15872 2.5061 + vertex 1.17958 2.15862 2.5055 + vertex 1.17661 2.16058 2.50316 + endloop + endfacet + facet normal 0.048397 0.831303 0.553709 + outer loop + vertex 1.17166 2.16066 2.50347 + vertex 1.17483 2.15872 2.5061 + vertex 1.17661 2.16058 2.50316 + endloop + endfacet + facet normal 0.0975152 0.672009 0.734094 + outer loop + vertex 1.1776 2.15662 2.50766 + vertex 1.17483 2.15872 2.5061 + vertex 1.17296 2.15599 2.50885 + endloop + endfacet + facet normal 0.107144 0.678961 0.726314 + outer loop + vertex 1.17958 2.15862 2.5055 + vertex 1.17483 2.15872 2.5061 + vertex 1.1776 2.15662 2.50766 + endloop + endfacet + facet normal 0.0499303 -0.341636 0.938505 + outer loop + vertex 1.17864 2.16744 2.48911 + vertex 1.17938 2.17 2.49 + vertex 1.175 2.16936 2.49 + endloop + endfacet + facet normal 0.502571 0.752158 0.42624 + outer loop + vertex 1.17864 2.16744 2.48911 + vertex 1.175 2.16936 2.49 + vertex 1.17926 2.16571 2.49141 + endloop + endfacet + facet normal 0.568986 0.773248 0.279897 + outer loop + vertex 1.17926 2.16571 2.49141 + vertex 1.175 2.16936 2.49 + vertex 1.175 2.16755 2.495 + endloop + endfacet + facet normal 0.630426 0.658141 0.411598 + outer loop + vertex 1.17926 2.16571 2.49141 + vertex 1.175 2.16755 2.495 + vertex 1.17846 2.16386 2.49559 + endloop + endfacet + facet normal 0.157103 0.299235 0.941157 + outer loop + vertex 1.17846 2.16386 2.49559 + vertex 1.175 2.16755 2.495 + vertex 1.17366 2.16404 2.49634 + endloop + endfacet + facet normal 0.0962896 0.908472 0.406702 + outer loop + vertex 1.17846 2.16386 2.49559 + vertex 1.17366 2.16404 2.49634 + vertex 1.17785 2.16215 2.49956 + endloop + endfacet + facet normal 0.0405168 0.884302 0.465153 + outer loop + vertex 1.17785 2.16215 2.49956 + vertex 1.17366 2.16404 2.49634 + vertex 1.17296 2.16217 2.49995 + endloop + endfacet + facet normal 0.0402687 0.912255 0.407638 + outer loop + vertex 1.17661 2.16058 2.50316 + vertex 1.17296 2.16217 2.49995 + vertex 1.17166 2.16066 2.50347 + endloop + endfacet + facet normal 0.0364032 0.910774 0.411297 + outer loop + vertex 1.17785 2.16215 2.49956 + vertex 1.17296 2.16217 2.49995 + vertex 1.17661 2.16058 2.50316 + endloop + endfacet + facet normal 0.0552623 -0.342916 0.937739 + outer loop + vertex 1.18 2.1701 2.49 + vertex 1.17938 2.17 2.49 + vertex 1.17864 2.16744 2.48911 + endloop + endfacet + facet normal -0.0464989 -0.989249 -0.138655 + outer loop + vertex 1.185 0.859338 2.49 + vertex 1.18079 0.859451 2.49061 + vertex 1.18 0.859573 2.49 + endloop + endfacet + facet normal -0.00645656 -0.990143 0.13991 + outer loop + vertex 1.18581 0.859349 2.49011 + vertex 1.18079 0.859451 2.49061 + vertex 1.185 0.859338 2.49 + endloop + endfacet + facet normal 0.0141017 -0.94062 0.339169 + outer loop + vertex 1.18079 0.859451 2.49061 + vertex 1.18581 0.859349 2.49011 + vertex 1.18362 0.860271 2.49276 + endloop + endfacet + facet normal 0.0288698 -0.946327 0.321917 + outer loop + vertex 1.17849 0.860282 2.49325 + vertex 1.18079 0.859451 2.49061 + vertex 1.18362 0.860271 2.49276 + endloop + endfacet + facet normal 0.0354831 -0.920015 0.390274 + outer loop + vertex 1.18362 0.860271 2.49276 + vertex 1.18194 0.861608 2.49607 + vertex 1.17849 0.860282 2.49325 + endloop + endfacet + facet normal 0.0379252 -0.92099 0.387736 + outer loop + vertex 1.18194 0.861608 2.49607 + vertex 1.17704 0.86154 2.49639 + vertex 1.17849 0.860282 2.49325 + endloop + endfacet + facet normal 0.0402974 -0.902855 0.428052 + outer loop + vertex 1.18194 0.861608 2.49607 + vertex 1.18031 0.863146 2.49946 + vertex 1.17704 0.86154 2.49639 + endloop + endfacet + facet normal 0.0641753 -0.897195 0.436946 + outer loop + vertex 1.18493 0.863249 2.499 + vertex 1.18031 0.863146 2.49946 + vertex 1.18194 0.861608 2.49607 + endloop + endfacet + facet normal 0.0703654 -0.8593 0.506608 + outer loop + vertex 1.18031 0.863146 2.49946 + vertex 1.18493 0.863249 2.499 + vertex 1.18321 0.864973 2.50216 + endloop + endfacet + facet normal 0.0804921 -0.863219 0.498371 + outer loop + vertex 1.17843 0.864881 2.50277 + vertex 1.18031 0.863146 2.49946 + vertex 1.18321 0.864973 2.50216 + endloop + endfacet + facet normal 0.0937388 -0.784054 0.613573 + outer loop + vertex 1.18321 0.864973 2.50216 + vertex 1.18143 0.867153 2.50522 + vertex 1.17843 0.864881 2.50277 + endloop + endfacet + facet normal 0.112136 -0.792759 0.599132 + outer loop + vertex 1.18143 0.867153 2.50522 + vertex 1.17642 0.866894 2.50581 + vertex 1.17843 0.864881 2.50277 + endloop + endfacet + facet normal 0.121145 -0.678131 0.724888 + outer loop + vertex 1.18143 0.867153 2.50522 + vertex 1.17938 0.870008 2.50823 + vertex 1.17642 0.866894 2.50581 + endloop + endfacet + facet normal 0.151788 -0.663927 0.73223 + outer loop + vertex 1.18481 0.870197 2.50728 + vertex 1.17938 0.870008 2.50823 + vertex 1.18143 0.867153 2.50522 + endloop + endfacet + facet normal 0.172491 -0.563466 0.807931 + outer loop + vertex 1.17994 0.873054 2.51024 + vertex 1.17622 0.872011 2.5103 + vertex 1.17938 0.870008 2.50823 + endloop + endfacet + facet normal 0.228557 -0.564092 0.793449 + outer loop + vertex 1.17994 0.873054 2.51024 + vertex 1.17938 0.870008 2.50823 + vertex 1.18399 0.873837 2.50963 + endloop + endfacet + facet normal 0.166207 -0.507927 0.845213 + outer loop + vertex 1.18399 0.873837 2.50963 + vertex 1.17938 0.870008 2.50823 + vertex 1.18481 0.870197 2.50728 + endloop + endfacet + facet normal 0.13563 -0.426602 0.894212 + outer loop + vertex 1.17994 0.873054 2.51024 + vertex 1.17893 0.875387 2.5115 + vertex 1.17622 0.872011 2.5103 + endloop + endfacet + facet normal 0.361785 0.139563 0.921756 + outer loop + vertex 1.18266 0.982437 2.5378 + vertex 1.18132 0.988329 2.53744 + vertex 1.17776 0.983945 2.5395 + endloop + endfacet + facet normal 0.486566 0.0154809 0.873506 + outer loop + vertex 1.17776 0.983945 2.5395 + vertex 1.18132 0.988329 2.53744 + vertex 1.17787 0.988642 2.53935 + endloop + endfacet + facet normal 0.604954 0.337439 0.721225 + outer loop + vertex 1.18429 0.991468 2.5342 + vertex 1.18221 0.995789 2.53393 + vertex 1.18113 0.992559 2.53635 + endloop + endfacet + facet normal 0.598467 0.22488 0.768939 + outer loop + vertex 1.18113 0.992559 2.53635 + vertex 1.18132 0.988329 2.53744 + vertex 1.18429 0.991468 2.5342 + endloop + endfacet + facet normal 0.564987 0.229444 0.792556 + outer loop + vertex 1.18113 0.992559 2.53635 + vertex 1.17892 0.991451 2.53825 + vertex 1.18132 0.988329 2.53744 + endloop + endfacet + facet normal 0.490376 0.155188 0.857582 + outer loop + vertex 1.17892 0.991451 2.53825 + vertex 1.17787 0.988642 2.53935 + vertex 1.18132 0.988329 2.53744 + endloop + endfacet + facet normal 0.548978 0.607906 0.573649 + outer loop + vertex 1.185 0.997941 2.525 + vertex 1.18272 1 2.525 + vertex 1.18285 0.999497 2.52541 + endloop + endfacet + facet normal 0.589656 0.34819 0.728745 + outer loop + vertex 1.1783 0.995197 2.53737 + vertex 1.18113 0.992559 2.53635 + vertex 1.18221 0.995789 2.53393 + endloop + endfacet + facet normal 0.60919 0.285011 0.740038 + outer loop + vertex 1.1783 0.995197 2.53737 + vertex 1.18221 0.995789 2.53393 + vertex 1.17905 0.999225 2.53521 + endloop + endfacet + facet normal 0.661897 0.365291 0.654564 + outer loop + vertex 1.17905 0.999225 2.53521 + vertex 1.18221 0.995789 2.53393 + vertex 1.18158 0.999898 2.53228 + endloop + endfacet + facet normal 0.543608 0.27367 0.79347 + outer loop + vertex 1.18113 0.992559 2.53635 + vertex 1.1783 0.995197 2.53737 + vertex 1.17892 0.991451 2.53825 + endloop + endfacet + facet normal 0.779468 0.561248 -0.278265 + outer loop + vertex 1.18223 1.00124 2.52743 + vertex 1.18 1.005 2.52875 + vertex 1.18026 1.0047 2.52887 + endloop + endfacet + facet normal 0.79608 0.556712 -0.237337 + outer loop + vertex 1.18285 0.999497 2.52541 + vertex 1.18 1.005 2.52875 + vertex 1.18223 1.00124 2.52743 + endloop + endfacet + facet normal 0.528949 0.623705 -0.575504 + outer loop + vertex 1.18285 0.999497 2.52541 + vertex 1.18 1.00154 2.525 + vertex 1.18 1.005 2.52875 + endloop + endfacet + facet normal 0.363287 0.641672 0.675484 + outer loop + vertex 1.18285 0.999497 2.52541 + vertex 1.18272 1 2.525 + vertex 1.18 1.00154 2.525 + endloop + endfacet + facet normal 0.867912 0.496713 -0.0021493 + outer loop + vertex 1.18263 1.00056 2.52952 + vertex 1.18223 1.00124 2.52743 + vertex 1.18026 1.0047 2.52887 + endloop + endfacet + facet normal 0.817369 0.509855 0.268246 + outer loop + vertex 1.18073 1.00289 2.53085 + vertex 1.18263 1.00056 2.52952 + vertex 1.18026 1.0047 2.52887 + endloop + endfacet + facet normal 0.808766 0.422093 0.409555 + outer loop + vertex 1.18073 1.00289 2.53085 + vertex 1.18158 0.999898 2.53228 + vertex 1.18263 1.00056 2.52952 + endloop + endfacet + facet normal 0.748987 0.444307 0.491538 + outer loop + vertex 1.18073 1.00289 2.53085 + vertex 1.17877 1.00342 2.53337 + vertex 1.18158 0.999898 2.53228 + endloop + endfacet + facet normal 0.674734 0.333607 0.658362 + outer loop + vertex 1.17877 1.00342 2.53337 + vertex 1.17905 0.999225 2.53521 + vertex 1.18158 0.999898 2.53228 + endloop + endfacet + facet normal 0.594124 0.198454 -0.779508 + outer loop + vertex 1.18 1.005 2.52875 + vertex 1.18 1.00991 2.53 + vertex 1.18026 1.0047 2.52887 + endloop + endfacet + facet normal -0.188789 -0.217214 0.957693 + outer loop + vertex 1.17739 1.00927 2.52934 + vertex 1.18026 1.0047 2.52887 + vertex 1.18 1.00991 2.53 + endloop + endfacet + facet normal 0.821739 0.484654 0.299759 + outer loop + vertex 1.17739 1.00927 2.52934 + vertex 1.17869 1.00607 2.53096 + vertex 1.18026 1.0047 2.52887 + endloop + endfacet + facet normal 0.812749 0.514416 0.273525 + outer loop + vertex 1.17869 1.00607 2.53096 + vertex 1.18073 1.00289 2.53085 + vertex 1.18026 1.0047 2.52887 + endloop + endfacet + facet normal 0.743312 0.462454 0.483346 + outer loop + vertex 1.17869 1.00607 2.53096 + vertex 1.17877 1.00342 2.53337 + vertex 1.18073 1.00289 2.53085 + endloop + endfacet + facet normal 0.839576 0.379744 0.388468 + outer loop + vertex 1.17762 1.00658 2.53277 + vertex 1.17877 1.00342 2.53337 + vertex 1.17869 1.00607 2.53096 + endloop + endfacet + facet normal 0.825127 0.482798 0.29338 + outer loop + vertex 1.17739 1.00927 2.52934 + vertex 1.17619 1.00978 2.53186 + vertex 1.17869 1.00607 2.53096 + endloop + endfacet + facet normal 0.814647 0.461817 0.350821 + outer loop + vertex 1.17869 1.00607 2.53096 + vertex 1.17619 1.00978 2.53186 + vertex 1.17762 1.00658 2.53277 + endloop + endfacet + facet normal 0.704937 -0.697736 -0.127388 + outer loop + vertex 1.18046 2.02533 2.52645 + vertex 1.17775 2.02256 2.52663 + vertex 1.17878 2.02392 2.52486 + endloop + endfacet + facet normal 0.71546 -0.695498 0.0663341 + outer loop + vertex 1.18046 2.02533 2.52645 + vertex 1.17867 2.02376 2.52931 + vertex 1.17775 2.02256 2.52663 + endloop + endfacet + facet normal 0.782383 -0.366481 -0.503555 + outer loop + vertex 1.18 2.02634 2.525 + vertex 1.18046 2.02533 2.52645 + vertex 1.17878 2.02392 2.52486 + endloop + endfacet + facet normal 0.548348 -0.594802 -0.587814 + outer loop + vertex 1.18397 2.03 2.525 + vertex 1.18046 2.02533 2.52645 + vertex 1.18 2.02634 2.525 + endloop + endfacet + facet normal -0.138812 -0.196761 -0.970575 + outer loop + vertex 1.18397 2.03 2.525 + vertex 1.18299 2.02739 2.52567 + vertex 1.18046 2.02533 2.52645 + endloop + endfacet + facet normal -0.817953 0.166356 -0.550708 + outer loop + vertex 1.18397 2.03 2.525 + vertex 1.18389 2.02852 2.52468 + vertex 1.18299 2.02739 2.52567 + endloop + endfacet + facet normal 0.711867 -0.639538 0.290236 + outer loop + vertex 1.17867 2.02376 2.52931 + vertex 1.1808 2.02703 2.53128 + vertex 1.17836 2.02482 2.5324 + endloop + endfacet + facet normal 0.780847 -0.604629 0.157167 + outer loop + vertex 1.18046 2.02533 2.52645 + vertex 1.1808 2.02703 2.53128 + vertex 1.17867 2.02376 2.52931 + endloop + endfacet + facet normal 0.594746 -0.770653 0.228847 + outer loop + vertex 1.18046 2.02533 2.52645 + vertex 1.18293 2.02786 2.52852 + vertex 1.1808 2.02703 2.53128 + endloop + endfacet + facet normal 0.650171 -0.74772 0.134879 + outer loop + vertex 1.18046 2.02533 2.52645 + vertex 1.18299 2.02739 2.52567 + vertex 1.18293 2.02786 2.52852 + endloop + endfacet + facet normal 0.707344 -0.569322 0.418971 + outer loop + vertex 1.1808 2.02703 2.53128 + vertex 1.17913 2.02716 2.53428 + vertex 1.17836 2.02482 2.5324 + endloop + endfacet + facet normal -0.24252 0.219089 -0.945084 + outer loop + vertex 1.185 2.03114 2.525 + vertex 1.18389 2.02852 2.52468 + vertex 1.18397 2.03 2.525 + endloop + endfacet + facet normal 0.655538 -0.693497 0.298884 + outer loop + vertex 1.18293 2.02786 2.52852 + vertex 1.18311 2.02913 2.53108 + vertex 1.1808 2.02703 2.53128 + endloop + endfacet + facet normal 0.663031 -0.481181 0.573458 + outer loop + vertex 1.17913 2.02716 2.53428 + vertex 1.18061 2.02994 2.5349 + vertex 1.17891 2.02888 2.53597 + endloop + endfacet + facet normal 0.748691 -0.496654 0.439087 + outer loop + vertex 1.1808 2.02703 2.53128 + vertex 1.18061 2.02994 2.5349 + vertex 1.17913 2.02716 2.53428 + endloop + endfacet + facet normal 0.607467 -0.603143 0.516916 + outer loop + vertex 1.1808 2.02703 2.53128 + vertex 1.18298 2.03093 2.53327 + vertex 1.18061 2.02994 2.5349 + endloop + endfacet + facet normal 0.593278 -0.603376 0.532878 + outer loop + vertex 1.1808 2.02703 2.53128 + vertex 1.18311 2.02913 2.53108 + vertex 1.18298 2.03093 2.53327 + endloop + endfacet + facet normal 0.639115 -0.31443 0.701901 + outer loop + vertex 1.18061 2.02994 2.5349 + vertex 1.17885 2.03256 2.53768 + vertex 1.17891 2.02888 2.53597 + endloop + endfacet + facet normal 0.624998 -0.472222 0.621598 + outer loop + vertex 1.18298 2.03093 2.53327 + vertex 1.18228 2.0333 2.53577 + vertex 1.18061 2.02994 2.5349 + endloop + endfacet + facet normal 0.506172 -0.443602 0.739599 + outer loop + vertex 1.18228 2.0333 2.53577 + vertex 1.17885 2.03256 2.53768 + vertex 1.18061 2.02994 2.5349 + endloop + endfacet + facet normal 0.51162 -0.328738 0.793836 + outer loop + vertex 1.18228 2.0333 2.53577 + vertex 1.18307 2.03765 2.53707 + vertex 1.17885 2.03256 2.53768 + endloop + endfacet + facet normal 0.3473 -0.177549 0.920793 + outer loop + vertex 1.18307 2.03765 2.53707 + vertex 1.17826 2.03909 2.53916 + vertex 1.17885 2.03256 2.53768 + endloop + endfacet + facet normal 0.360726 -0.135636 0.922757 + outer loop + vertex 1.18307 2.03765 2.53707 + vertex 1.18252 2.04243 2.53798 + vertex 1.17826 2.03909 2.53916 + endloop + endfacet + facet normal 0.212235 0.446239 0.869383 + outer loop + vertex 1.1832 2.15126 2.50935 + vertex 1.18234 2.15563 2.50732 + vertex 1.17796 2.15328 2.50959 + endloop + endfacet + facet normal 0.166923 0.507643 0.845243 + outer loop + vertex 1.17796 2.15328 2.50959 + vertex 1.18234 2.15563 2.50732 + vertex 1.1776 2.15662 2.50766 + endloop + endfacet + facet normal 0.108363 0.796313 0.5951 + outer loop + vertex 1.17958 2.15862 2.5055 + vertex 1.18405 2.15867 2.50461 + vertex 1.18123 2.16055 2.50262 + endloop + endfacet + facet normal 0.0737722 0.808685 0.583598 + outer loop + vertex 1.17661 2.16058 2.50316 + vertex 1.17958 2.15862 2.5055 + vertex 1.18123 2.16055 2.50262 + endloop + endfacet + facet normal 0.186067 0.630229 0.753784 + outer loop + vertex 1.18234 2.15563 2.50732 + vertex 1.17958 2.15862 2.5055 + vertex 1.1776 2.15662 2.50766 + endloop + endfacet + facet normal 0.14721 0.609652 0.77888 + outer loop + vertex 1.18405 2.15867 2.50461 + vertex 1.17958 2.15862 2.5055 + vertex 1.18234 2.15563 2.50732 + endloop + endfacet + facet normal -0.009204 0.814108 0.580641 + outer loop + vertex 1.17926 2.16571 2.49141 + vertex 1.18531 2.16573 2.49148 + vertex 1.18193 2.16726 2.48928 + endloop + endfacet + facet normal 0.0107424 0.802154 0.59702 + outer loop + vertex 1.17864 2.16744 2.48911 + vertex 1.17926 2.16571 2.49141 + vertex 1.18193 2.16726 2.48928 + endloop + endfacet + facet normal -0.00850766 0.857256 0.514821 + outer loop + vertex 1.18531 2.16573 2.49148 + vertex 1.17926 2.16571 2.49141 + vertex 1.18274 2.16381 2.49463 + endloop + endfacet + facet normal 0.104925 0.901959 0.418881 + outer loop + vertex 1.18274 2.16381 2.49463 + vertex 1.17926 2.16571 2.49141 + vertex 1.17846 2.16386 2.49559 + endloop + endfacet + facet normal 0.091803 0.928822 0.358973 + outer loop + vertex 1.18274 2.16381 2.49463 + vertex 1.17846 2.16386 2.49559 + vertex 1.18302 2.16213 2.49891 + endloop + endfacet + facet normal 0.0543382 0.913774 0.402573 + outer loop + vertex 1.18302 2.16213 2.49891 + vertex 1.17846 2.16386 2.49559 + vertex 1.17785 2.16215 2.49956 + endloop + endfacet + facet normal 0.0550333 0.907545 0.416333 + outer loop + vertex 1.18123 2.16055 2.50262 + vertex 1.17785 2.16215 2.49956 + vertex 1.17661 2.16058 2.50316 + endloop + endfacet + facet normal 0.0559401 0.907871 0.415502 + outer loop + vertex 1.18302 2.16213 2.49891 + vertex 1.17785 2.16215 2.49956 + vertex 1.18123 2.16055 2.50262 + endloop + endfacet + facet normal -0.0660599 -0.286827 0.955702 + outer loop + vertex 1.18193 2.16726 2.48928 + vertex 1.18 2.1701 2.49 + vertex 1.17864 2.16744 2.48911 + endloop + endfacet + facet normal -0.00446089 -0.248147 0.968712 + outer loop + vertex 1.185 2.17001 2.49 + vertex 1.18 2.1701 2.49 + vertex 1.18193 2.16726 2.48928 + endloop + endfacet + facet normal -0.0432874 -0.917224 0.396012 + outer loop + vertex 1.19 0.859102 2.49 + vertex 1.18581 0.859349 2.49011 + vertex 1.185 0.859338 2.49 + endloop + endfacet + facet normal 0.0629873 0.977321 0.202177 + outer loop + vertex 1.19029 0.859244 2.48922 + vertex 1.18581 0.859349 2.49011 + vertex 1.19 0.859102 2.49 + endloop + endfacet + facet normal 0.0479504 -0.935046 0.351268 + outer loop + vertex 1.18581 0.859349 2.49011 + vertex 1.19029 0.859244 2.48922 + vertex 1.18845 0.860262 2.49218 + endloop + endfacet + facet normal 0.0412124 -0.932527 0.35874 + outer loop + vertex 1.18362 0.860271 2.49276 + vertex 1.18581 0.859349 2.49011 + vertex 1.18845 0.860262 2.49218 + endloop + endfacet + facet normal 0.0466262 -0.913651 0.403817 + outer loop + vertex 1.18845 0.860262 2.49218 + vertex 1.18685 0.861707 2.49564 + vertex 1.18362 0.860271 2.49276 + endloop + endfacet + facet normal 0.0531855 -0.915999 0.397639 + outer loop + vertex 1.18685 0.861707 2.49564 + vertex 1.18194 0.861608 2.49607 + vertex 1.18362 0.860271 2.49276 + endloop + endfacet + facet normal 0.0567228 -0.894663 0.443126 + outer loop + vertex 1.18685 0.861707 2.49564 + vertex 1.18493 0.863249 2.499 + vertex 1.18194 0.861608 2.49607 + endloop + endfacet + facet normal 0.0943581 -0.883242 0.459326 + outer loop + vertex 1.18951 0.863458 2.49846 + vertex 1.18493 0.863249 2.499 + vertex 1.18685 0.861707 2.49564 + endloop + endfacet + facet normal 0.0988584 -0.855592 0.508124 + outer loop + vertex 1.18493 0.863249 2.499 + vertex 1.18951 0.863458 2.49846 + vertex 1.18731 0.864865 2.50126 + endloop + endfacet + facet normal 0.0910563 -0.852763 0.5143 + outer loop + vertex 1.18321 0.864973 2.50216 + vertex 1.18493 0.863249 2.499 + vertex 1.18731 0.864865 2.50126 + endloop + endfacet + facet normal 0.115078 -0.780416 0.61458 + outer loop + vertex 1.18731 0.864865 2.50126 + vertex 1.18691 0.867207 2.5043 + vertex 1.18321 0.864973 2.50216 + endloop + endfacet + facet normal 0.11084 -0.777584 0.618933 + outer loop + vertex 1.18691 0.867207 2.5043 + vertex 1.18143 0.867153 2.50522 + vertex 1.18321 0.864973 2.50216 + endloop + endfacet + facet normal 0.131066 -0.651207 0.747497 + outer loop + vertex 1.18691 0.867207 2.5043 + vertex 1.18481 0.870197 2.50728 + vertex 1.18143 0.867153 2.50522 + endloop + endfacet + facet normal 0.134281 -0.649695 0.748241 + outer loop + vertex 1.18951 0.87042 2.50663 + vertex 1.18481 0.870197 2.50728 + vertex 1.18691 0.867207 2.5043 + endloop + endfacet + facet normal 0.143019 -0.45862 0.877048 + outer loop + vertex 1.18951 0.87042 2.50663 + vertex 1.18893 0.874021 2.50861 + vertex 1.18481 0.870197 2.50728 + endloop + endfacet + facet normal 0.19304 -0.500886 0.843712 + outer loop + vertex 1.18481 0.870197 2.50728 + vertex 1.18893 0.874021 2.50861 + vertex 1.18399 0.873837 2.50963 + endloop + endfacet + facet normal 0.406431 0.325363 0.853787 + outer loop + vertex 1.18953 0.98174 2.53554 + vertex 1.18853 0.984545 2.53495 + vertex 1.18658 0.982874 2.53651 + endloop + endfacet + facet normal 0.351363 0.117493 0.928838 + outer loop + vertex 1.18658 0.982874 2.53651 + vertex 1.18628 0.978856 2.53714 + vertex 1.18953 0.98174 2.53554 + endloop + endfacet + facet normal 0.297532 0.124249 0.946592 + outer loop + vertex 1.18658 0.982874 2.53651 + vertex 1.18266 0.982437 2.5378 + vertex 1.18628 0.978856 2.53714 + endloop + endfacet + facet normal 0.474856 0.480802 0.737117 + outer loop + vertex 1.18853 0.984545 2.53495 + vertex 1.1893 0.986844 2.53295 + vertex 1.18591 0.986758 2.53519 + endloop + endfacet + facet normal 0.380133 0.355991 0.85368 + outer loop + vertex 1.18658 0.982874 2.53651 + vertex 1.18853 0.984545 2.53495 + vertex 1.18591 0.986758 2.53519 + endloop + endfacet + facet normal 0.257106 0.35082 0.900456 + outer loop + vertex 1.18591 0.986758 2.53519 + vertex 1.18266 0.982437 2.5378 + vertex 1.18658 0.982874 2.53651 + endloop + endfacet + facet normal 0.477667 0.16222 0.863434 + outer loop + vertex 1.18132 0.988329 2.53744 + vertex 1.18266 0.982437 2.5378 + vertex 1.18591 0.986758 2.53519 + endloop + endfacet + facet normal 0.751818 0.526138 0.397428 + outer loop + vertex 1.18855 0.990505 2.53055 + vertex 1.18738 0.994045 2.52808 + vertex 1.18556 0.994476 2.53095 + endloop + endfacet + facet normal 0.694186 0.373789 0.615132 + outer loop + vertex 1.18556 0.994476 2.53095 + vertex 1.18221 0.995789 2.53393 + vertex 1.18429 0.991468 2.5342 + endloop + endfacet + facet normal 0.644134 0.420532 0.63894 + outer loop + vertex 1.18855 0.990505 2.53055 + vertex 1.18556 0.994476 2.53095 + vertex 1.18429 0.991468 2.5342 + endloop + endfacet + facet normal 0.653041 0.363674 0.664288 + outer loop + vertex 1.18855 0.990505 2.53055 + vertex 1.18429 0.991468 2.5342 + vertex 1.18591 0.986758 2.53519 + endloop + endfacet + facet normal 0.449527 0.552975 0.70153 + outer loop + vertex 1.18855 0.990505 2.53055 + vertex 1.18591 0.986758 2.53519 + vertex 1.1893 0.986844 2.53295 + endloop + endfacet + facet normal 0.504362 0.339742 0.793848 + outer loop + vertex 1.18591 0.986758 2.53519 + vertex 1.18429 0.991468 2.5342 + vertex 1.18132 0.988329 2.53744 + endloop + endfacet + facet normal -0.0681977 -0.906855 0.415889 + outer loop + vertex 1.185 0.995 2.52341 + vertex 1.18674 0.994686 2.52301 + vertex 1.19 0.995 2.52423 + endloop + endfacet + facet normal -0.115143 0.472418 -0.873821 + outer loop + vertex 1.185 0.997941 2.525 + vertex 1.18674 0.994686 2.52301 + vertex 1.185 0.995 2.52341 + endloop + endfacet + facet normal 0.744539 0.666707 -0.0341047 + outer loop + vertex 1.18285 0.999497 2.52541 + vertex 1.1848 0.997448 2.52793 + vertex 1.18655 0.995342 2.52503 + endloop + endfacet + facet normal 0.323299 0.204713 0.923889 + outer loop + vertex 1.18285 0.999497 2.52541 + vertex 1.18655 0.995342 2.52503 + vertex 1.185 0.997941 2.525 + endloop + endfacet + facet normal 0.855299 0.510682 -0.0875651 + outer loop + vertex 1.185 0.997941 2.525 + vertex 1.18655 0.995342 2.52503 + vertex 1.18674 0.994686 2.52301 + endloop + endfacet + facet normal 0.795799 0.604069 0.04248 + outer loop + vertex 1.18738 0.994045 2.52808 + vertex 1.18655 0.995342 2.52503 + vertex 1.1848 0.997448 2.52793 + endloop + endfacet + facet normal 0.730415 0.569258 0.377412 + outer loop + vertex 1.18738 0.994045 2.52808 + vertex 1.1848 0.997448 2.52793 + vertex 1.18556 0.994476 2.53095 + endloop + endfacet + facet normal 0.839072 0.477695 0.260319 + outer loop + vertex 1.18556 0.994476 2.53095 + vertex 1.1848 0.997448 2.52793 + vertex 1.1838 0.997597 2.53089 + endloop + endfacet + facet normal 0.691732 0.401908 0.599981 + outer loop + vertex 1.1838 0.997597 2.53089 + vertex 1.18221 0.995789 2.53393 + vertex 1.18556 0.994476 2.53095 + endloop + endfacet + facet normal 0.72945 0.349028 0.588288 + outer loop + vertex 1.18158 0.999898 2.53228 + vertex 1.18221 0.995789 2.53393 + vertex 1.1838 0.997597 2.53089 + endloop + endfacet + facet normal 0.822743 0.529792 -0.205949 + outer loop + vertex 1.18285 0.999497 2.52541 + vertex 1.18223 1.00124 2.52743 + vertex 1.1848 0.997448 2.52793 + endloop + endfacet + facet normal 0.848848 0.457628 0.26464 + outer loop + vertex 1.1848 0.997448 2.52793 + vertex 1.18263 1.00056 2.52952 + vertex 1.1838 0.997597 2.53089 + endloop + endfacet + facet normal 0.826085 0.562878 0.0274041 + outer loop + vertex 1.18223 1.00124 2.52743 + vertex 1.18263 1.00056 2.52952 + vertex 1.1848 0.997448 2.52793 + endloop + endfacet + facet normal 0.767121 0.492906 0.410571 + outer loop + vertex 1.1838 0.997597 2.53089 + vertex 1.18263 1.00056 2.52952 + vertex 1.18158 0.999898 2.53228 + endloop + endfacet + facet normal 0.752915 -0.65506 -0.0633696 + outer loop + vertex 1.1849 2.0295 2.52654 + vertex 1.18299 2.02739 2.52567 + vertex 1.18389 2.02852 2.52468 + endloop + endfacet + facet normal 0.70872 -0.693916 0.127264 + outer loop + vertex 1.1849 2.0295 2.52654 + vertex 1.18293 2.02786 2.52852 + vertex 1.18299 2.02739 2.52567 + endloop + endfacet + facet normal 0.889606 -0.340842 -0.304019 + outer loop + vertex 1.1849 2.0295 2.52654 + vertex 1.18389 2.02852 2.52468 + vertex 1.185 2.03114 2.525 + endloop + endfacet + facet normal 0.268183 -0.669487 -0.692723 + outer loop + vertex 1.1849 2.0295 2.52654 + vertex 1.185 2.03114 2.525 + vertex 1.18717 2.03156 2.52543 + endloop + endfacet + facet normal 0.264758 -0.553921 -0.789351 + outer loop + vertex 1.18717 2.03156 2.52543 + vertex 1.185 2.03114 2.525 + vertex 1.19 2.03353 2.525 + endloop + endfacet + facet normal 0.742041 -0.619566 0.255957 + outer loop + vertex 1.18293 2.02786 2.52852 + vertex 1.18536 2.03177 2.53096 + vertex 1.18311 2.02913 2.53108 + endloop + endfacet + facet normal 0.752584 -0.614338 0.237078 + outer loop + vertex 1.1849 2.0295 2.52654 + vertex 1.18536 2.03177 2.53096 + vertex 1.18293 2.02786 2.52852 + endloop + endfacet + facet normal 0.644658 -0.705287 0.294933 + outer loop + vertex 1.1849 2.0295 2.52654 + vertex 1.18761 2.03275 2.52838 + vertex 1.18536 2.03177 2.53096 + endloop + endfacet + facet normal 0.706606 -0.68663 0.171018 + outer loop + vertex 1.1849 2.0295 2.52654 + vertex 1.18717 2.03156 2.52543 + vertex 1.18761 2.03275 2.52838 + endloop + endfacet + facet normal 0.67341 -0.550112 0.493858 + outer loop + vertex 1.18536 2.03177 2.53096 + vertex 1.18298 2.03093 2.53327 + vertex 1.18311 2.02913 2.53108 + endloop + endfacet + facet normal 0.668739 -0.665801 0.330905 + outer loop + vertex 1.18761 2.03275 2.52838 + vertex 1.18785 2.03433 2.53109 + vertex 1.18536 2.03177 2.53096 + endloop + endfacet + facet normal 0.588992 -0.498359 0.636182 + outer loop + vertex 1.18298 2.03093 2.53327 + vertex 1.18485 2.03481 2.53457 + vertex 1.18228 2.0333 2.53577 + endloop + endfacet + facet normal 0.685801 -0.506802 0.52233 + outer loop + vertex 1.18536 2.03177 2.53096 + vertex 1.18485 2.03481 2.53457 + vertex 1.18298 2.03093 2.53327 + endloop + endfacet + facet normal 0.57891 -0.582272 0.570809 + outer loop + vertex 1.18536 2.03177 2.53096 + vertex 1.18755 2.03614 2.5332 + vertex 1.18485 2.03481 2.53457 + endloop + endfacet + facet normal 0.570184 -0.582334 0.579463 + outer loop + vertex 1.18536 2.03177 2.53096 + vertex 1.18785 2.03433 2.53109 + vertex 1.18755 2.03614 2.5332 + endloop + endfacet + facet normal 0.550377 -0.327993 0.767793 + outer loop + vertex 1.18485 2.03481 2.53457 + vertex 1.18307 2.03765 2.53707 + vertex 1.18228 2.0333 2.53577 + endloop + endfacet + facet normal 0.571951 -0.450238 0.685681 + outer loop + vertex 1.18755 2.03614 2.5332 + vertex 1.18648 2.03832 2.53552 + vertex 1.18485 2.03481 2.53457 + endloop + endfacet + facet normal 0.441714 -0.418739 0.79344 + outer loop + vertex 1.18648 2.03832 2.53552 + vertex 1.18307 2.03765 2.53707 + vertex 1.18485 2.03481 2.53457 + endloop + endfacet + facet normal 0.439468 -0.239968 0.865611 + outer loop + vertex 1.18648 2.03832 2.53552 + vertex 1.18632 2.04177 2.53656 + vertex 1.18307 2.03765 2.53707 + endloop + endfacet + facet normal 0.326323 -0.141837 0.934556 + outer loop + vertex 1.18632 2.04177 2.53656 + vertex 1.18252 2.04243 2.53798 + vertex 1.18307 2.03765 2.53707 + endloop + endfacet + facet normal 0.168533 0.522727 0.835675 + outer loop + vertex 1.19019 2.15508 2.50607 + vertex 1.18948 2.15717 2.5049 + vertex 1.18693 2.15666 2.50574 + endloop + endfacet + facet normal 0.144712 0.479937 0.865286 + outer loop + vertex 1.18693 2.15666 2.50574 + vertex 1.18703 2.15316 2.50766 + vertex 1.19019 2.15508 2.50607 + endloop + endfacet + facet normal 0.188397 0.477361 0.858273 + outer loop + vertex 1.18693 2.15666 2.50574 + vertex 1.18234 2.15563 2.50732 + vertex 1.18703 2.15316 2.50766 + endloop + endfacet + facet normal 0.168562 0.442855 0.880606 + outer loop + vertex 1.18234 2.15563 2.50732 + vertex 1.1832 2.15126 2.50935 + vertex 1.18703 2.15316 2.50766 + endloop + endfacet + facet normal 0.170586 0.834525 0.523898 + outer loop + vertex 1.18882 2.1591 2.50305 + vertex 1.18722 2.16124 2.50016 + vertex 1.18498 2.16047 2.50212 + endloop + endfacet + facet normal 0.0966068 0.789838 0.605659 + outer loop + vertex 1.18498 2.16047 2.50212 + vertex 1.18123 2.16055 2.50262 + vertex 1.18405 2.15867 2.50461 + endloop + endfacet + facet normal 0.130174 0.780473 0.611487 + outer loop + vertex 1.18882 2.1591 2.50305 + vertex 1.18498 2.16047 2.50212 + vertex 1.18405 2.15867 2.50461 + endloop + endfacet + facet normal 0.178819 0.662425 0.727473 + outer loop + vertex 1.18882 2.1591 2.50305 + vertex 1.18405 2.15867 2.50461 + vertex 1.18693 2.15666 2.50574 + endloop + endfacet + facet normal 0.0886732 0.705433 0.703208 + outer loop + vertex 1.18882 2.1591 2.50305 + vertex 1.18693 2.15666 2.50574 + vertex 1.18948 2.15717 2.5049 + endloop + endfacet + facet normal 0.128419 0.617573 0.775959 + outer loop + vertex 1.18693 2.15666 2.50574 + vertex 1.18405 2.15867 2.50461 + vertex 1.18234 2.15563 2.50732 + endloop + endfacet + facet normal -0.398383 0.343857 0.850325 + outer loop + vertex 1.18583 2.17 2.49 + vertex 1.18193 2.16726 2.48928 + vertex 1.18531 2.16573 2.49148 + endloop + endfacet + facet normal 0.00393307 0.327578 0.944816 + outer loop + vertex 1.18583 2.17 2.49 + vertex 1.18531 2.16573 2.49148 + vertex 1.19 2.16995 2.49 + endloop + endfacet + facet normal -0.14253 0.465373 0.873563 + outer loop + vertex 1.19 2.16995 2.49 + vertex 1.18531 2.16573 2.49148 + vertex 1.19017 2.16481 2.49277 + endloop + endfacet + facet normal 0.0339952 0.86924 0.493219 + outer loop + vertex 1.19017 2.16481 2.49277 + vertex 1.18531 2.16573 2.49148 + vertex 1.18763 2.16295 2.49623 + endloop + endfacet + facet normal -0.0145187 0.859345 0.511189 + outer loop + vertex 1.18763 2.16295 2.49623 + vertex 1.18531 2.16573 2.49148 + vertex 1.18274 2.16381 2.49463 + endloop + endfacet + facet normal 0.0638759 0.901444 0.428156 + outer loop + vertex 1.18722 2.16124 2.50016 + vertex 1.18302 2.16213 2.49891 + vertex 1.18498 2.16047 2.50212 + endloop + endfacet + facet normal 0.0734484 0.912026 0.403503 + outer loop + vertex 1.18722 2.16124 2.50016 + vertex 1.18763 2.16295 2.49623 + vertex 1.18302 2.16213 2.49891 + endloop + endfacet + facet normal 0.0463831 0.930754 0.362692 + outer loop + vertex 1.18763 2.16295 2.49623 + vertex 1.18274 2.16381 2.49463 + vertex 1.18302 2.16213 2.49891 + endloop + endfacet + facet normal 0.0746051 0.903272 0.422533 + outer loop + vertex 1.18498 2.16047 2.50212 + vertex 1.18302 2.16213 2.49891 + vertex 1.18123 2.16055 2.50262 + endloop + endfacet + facet normal -0.00301188 -0.249663 0.968328 + outer loop + vertex 1.18583 2.17 2.49 + vertex 1.185 2.17001 2.49 + vertex 1.18193 2.16726 2.48928 + endloop + endfacet + facet normal -0.531178 -0.672096 -0.515885 + outer loop + vertex 1.19372 0.86 2.485 + vertex 1.19 0.859102 2.49 + vertex 1.19 0.86 2.48883 + endloop + endfacet + facet normal -0.524969 -0.679457 -0.512588 + outer loop + vertex 1.19372 0.86 2.485 + vertex 1.195 0.859011 2.485 + vertex 1.19 0.859102 2.49 + endloop + endfacet + facet normal -0.566112 0.588895 -0.576818 + outer loop + vertex 1.195 0.859011 2.485 + vertex 1.19305 0.858773 2.48667 + vertex 1.19 0.859102 2.49 + endloop + endfacet + facet normal 0.438921 0.840022 0.318922 + outer loop + vertex 1.19305 0.858773 2.48667 + vertex 1.19029 0.859244 2.48922 + vertex 1.19 0.859102 2.49 + endloop + endfacet + facet normal 0.0659488 -0.966037 0.249848 + outer loop + vertex 1.19469 0.859274 2.48818 + vertex 1.19029 0.859244 2.48922 + vertex 1.19305 0.858773 2.48667 + endloop + endfacet + facet normal 0.0864173 -0.937637 0.336704 + outer loop + vertex 1.19029 0.859244 2.48922 + vertex 1.19469 0.859274 2.48818 + vertex 1.19248 0.860114 2.49109 + endloop + endfacet + facet normal 0.0639952 -0.930826 0.359816 + outer loop + vertex 1.18845 0.860262 2.49218 + vertex 1.19029 0.859244 2.48922 + vertex 1.19248 0.860114 2.49109 + endloop + endfacet + facet normal 0.0817843 -0.903212 0.421331 + outer loop + vertex 1.19248 0.860114 2.49109 + vertex 1.19208 0.86174 2.49465 + vertex 1.18845 0.860262 2.49218 + endloop + endfacet + facet normal 0.0847955 -0.904608 0.417725 + outer loop + vertex 1.19208 0.86174 2.49465 + vertex 1.18685 0.861707 2.49564 + vertex 1.18845 0.860262 2.49218 + endloop + endfacet + facet normal 0.0927645 -0.882777 0.460542 + outer loop + vertex 1.19208 0.86174 2.49465 + vertex 1.18951 0.863458 2.49846 + vertex 1.18685 0.861707 2.49564 + endloop + endfacet + facet normal 0.114766 -0.874317 0.471591 + outer loop + vertex 1.19355 0.863636 2.49781 + vertex 1.18951 0.863458 2.49846 + vertex 1.19208 0.86174 2.49465 + endloop + endfacet + facet normal 0.123861 -0.832932 0.539335 + outer loop + vertex 1.18951 0.863458 2.49846 + vertex 1.19355 0.863636 2.49781 + vertex 1.19216 0.865847 2.50154 + endloop + endfacet + facet normal 0.138419 -0.836772 0.529766 + outer loop + vertex 1.18731 0.864865 2.50126 + vertex 1.18951 0.863458 2.49846 + vertex 1.19216 0.865847 2.50154 + endloop + endfacet + facet normal 0.161401 -0.762042 0.627091 + outer loop + vertex 1.19104 0.868247 2.50475 + vertex 1.19216 0.865847 2.50154 + vertex 1.19475 0.868558 2.50417 + endloop + endfacet + facet normal 0.128075 -0.771869 0.622747 + outer loop + vertex 1.19104 0.868247 2.50475 + vertex 1.18691 0.867207 2.5043 + vertex 1.19216 0.865847 2.50154 + endloop + endfacet + facet normal 0.121876 -0.779336 0.61464 + outer loop + vertex 1.18691 0.867207 2.5043 + vertex 1.18731 0.864865 2.50126 + vertex 1.19216 0.865847 2.50154 + endloop + endfacet + facet normal 0.0738646 -0.622908 0.7788 + outer loop + vertex 1.19104 0.868247 2.50475 + vertex 1.18951 0.87042 2.50663 + vertex 1.18691 0.867207 2.5043 + endloop + endfacet + facet normal 0.170571 -0.632245 0.755759 + outer loop + vertex 1.19475 0.868558 2.50417 + vertex 1.1929 0.870274 2.50602 + vertex 1.19104 0.868247 2.50475 + endloop + endfacet + facet normal 0.115589 -0.602801 0.789475 + outer loop + vertex 1.1929 0.870274 2.50602 + vertex 1.18951 0.87042 2.50663 + vertex 1.19104 0.868247 2.50475 + endloop + endfacet + facet normal 0.142376 -0.421555 0.895556 + outer loop + vertex 1.1929 0.870274 2.50602 + vertex 1.19391 0.873877 2.50755 + vertex 1.18951 0.87042 2.50663 + endloop + endfacet + facet normal 0.171317 -0.452918 0.874938 + outer loop + vertex 1.19391 0.873877 2.50755 + vertex 1.18893 0.874021 2.50861 + vertex 1.18951 0.87042 2.50663 + endloop + endfacet + facet normal 0.450066 0.43218 0.781448 + outer loop + vertex 1.18953 0.98174 2.53554 + vertex 1.19343 0.981196 2.5336 + vertex 1.1918 0.984612 2.53264 + endloop + endfacet + facet normal 0.533817 0.352873 0.768453 + outer loop + vertex 1.18853 0.984545 2.53495 + vertex 1.18953 0.98174 2.53554 + vertex 1.1918 0.984612 2.53264 + endloop + endfacet + facet normal 0.28057 0.20253 0.938223 + outer loop + vertex 1.19067 0.978427 2.53591 + vertex 1.18953 0.98174 2.53554 + vertex 1.18628 0.978856 2.53714 + endloop + endfacet + facet normal 0.45983 0.254219 0.85084 + outer loop + vertex 1.19343 0.981196 2.5336 + vertex 1.18953 0.98174 2.53554 + vertex 1.19067 0.978427 2.53591 + endloop + endfacet + facet normal 0.0301567 0.0770232 -0.996573 + outer loop + vertex 1.195 0.988289 2.52 + vertex 1.19063 0.99 2.52 + vertex 1.19344 0.989292 2.52003 + endloop + endfacet + facet normal 0.527167 0.615343 0.586044 + outer loop + vertex 1.19453 0.986382 2.52902 + vertex 1.19385 0.988041 2.52789 + vertex 1.19189 0.987752 2.52995 + endloop + endfacet + facet normal 0.517544 0.54807 0.65709 + outer loop + vertex 1.19189 0.987752 2.52995 + vertex 1.1918 0.984612 2.53264 + vertex 1.19453 0.986382 2.52902 + endloop + endfacet + facet normal 0.553872 0.532458 0.640089 + outer loop + vertex 1.19189 0.987752 2.52995 + vertex 1.1893 0.986844 2.53295 + vertex 1.1918 0.984612 2.53264 + endloop + endfacet + facet normal 0.503611 0.463925 0.7288 + outer loop + vertex 1.1893 0.986844 2.53295 + vertex 1.18853 0.984545 2.53495 + vertex 1.1918 0.984612 2.53264 + endloop + endfacet + facet normal 0.279078 -0.279164 0.918794 + outer loop + vertex 1.19211 0.990889 2.52234 + vertex 1.19 0.995 2.52423 + vertex 1.18951 0.992764 2.5237 + endloop + endfacet + facet normal 0.898826 0.326211 0.292744 + outer loop + vertex 1.19344 0.989292 2.52003 + vertex 1.19 0.995 2.52423 + vertex 1.19211 0.990889 2.52234 + endloop + endfacet + facet normal 0.198815 0.65569 -0.728384 + outer loop + vertex 1.19344 0.989292 2.52003 + vertex 1.19 0.990301 2.52 + vertex 1.19 0.995 2.52423 + endloop + endfacet + facet normal 0.0227783 0.0476676 -0.998603 + outer loop + vertex 1.19344 0.989292 2.52003 + vertex 1.19063 0.99 2.52 + vertex 1.19 0.990301 2.52 + endloop + endfacet + facet normal 0.624147 0.770545 0.129232 + outer loop + vertex 1.19278 0.989763 2.52583 + vertex 1.19211 0.990889 2.52234 + vertex 1.18951 0.992764 2.5237 + endloop + endfacet + facet normal 0.624835 0.770236 0.127741 + outer loop + vertex 1.18929 0.99249 2.52643 + vertex 1.19278 0.989763 2.52583 + vertex 1.18951 0.992764 2.5237 + endloop + endfacet + facet normal 0.758896 0.522432 0.38877 + outer loop + vertex 1.18929 0.99249 2.52643 + vertex 1.18738 0.994045 2.52808 + vertex 1.18855 0.990505 2.53055 + endloop + endfacet + facet normal 0.600962 0.672191 0.432439 + outer loop + vertex 1.19278 0.989763 2.52583 + vertex 1.18929 0.99249 2.52643 + vertex 1.18855 0.990505 2.53055 + endloop + endfacet + facet normal 0.614282 0.649644 0.447907 + outer loop + vertex 1.19278 0.989763 2.52583 + vertex 1.18855 0.990505 2.53055 + vertex 1.19189 0.987752 2.52995 + endloop + endfacet + facet normal 0.377425 0.798143 0.469593 + outer loop + vertex 1.19278 0.989763 2.52583 + vertex 1.19189 0.987752 2.52995 + vertex 1.19385 0.988041 2.52789 + endloop + endfacet + facet normal 0.55302 0.533755 0.639746 + outer loop + vertex 1.19189 0.987752 2.52995 + vertex 1.18855 0.990505 2.53055 + vertex 1.1893 0.986844 2.53295 + endloop + endfacet + facet normal -0.333736 -0.148251 0.930936 + outer loop + vertex 1.19 0.995 2.52423 + vertex 1.18674 0.994686 2.52301 + vertex 1.18951 0.992764 2.5237 + endloop + endfacet + facet normal 0.683898 0.718383 0.127316 + outer loop + vertex 1.18951 0.992764 2.5237 + vertex 1.18655 0.995342 2.52503 + vertex 1.18929 0.99249 2.52643 + endloop + endfacet + facet normal 0.591395 0.781293 -0.199586 + outer loop + vertex 1.18674 0.994686 2.52301 + vertex 1.18655 0.995342 2.52503 + vertex 1.18951 0.992764 2.5237 + endloop + endfacet + facet normal 0.686334 0.717271 0.12028 + outer loop + vertex 1.18929 0.99249 2.52643 + vertex 1.18655 0.995342 2.52503 + vertex 1.18738 0.994045 2.52808 + endloop + endfacet + facet normal -0.952002 -0.14913 -0.267307 + outer loop + vertex 1.19062 2.03518 2.52187 + vertex 1.19 2.03353 2.525 + vertex 1.19 2.035 2.52418 + endloop + endfacet + facet normal 0.974841 -0.206367 0.0842458 + outer loop + vertex 1.19013 2.03438 2.52559 + vertex 1.19 2.03353 2.525 + vertex 1.19062 2.03518 2.52187 + endloop + endfacet + facet normal 0.484995 -0.548765 0.680909 + outer loop + vertex 1.18717 2.03156 2.52543 + vertex 1.19 2.03353 2.525 + vertex 1.19013 2.03438 2.52559 + endloop + endfacet + facet normal 0.671701 -0.716536 0.188134 + outer loop + vertex 1.19013 2.03438 2.52559 + vertex 1.18761 2.03275 2.52838 + vertex 1.18717 2.03156 2.52543 + endloop + endfacet + facet normal -0.860743 -0.434564 -0.265096 + outer loop + vertex 1.19 2.03755 2.52 + vertex 1.19062 2.03518 2.52187 + vertex 1.19 2.035 2.52418 + endloop + endfacet + facet normal 0.295868 -0.543422 -0.785592 + outer loop + vertex 1.1945 2.04 2.52 + vertex 1.19062 2.03518 2.52187 + vertex 1.19 2.03755 2.52 + endloop + endfacet + facet normal 0.465012 -0.619933 -0.632018 + outer loop + vertex 1.1945 2.04 2.52 + vertex 1.1927 2.03628 2.52233 + vertex 1.19062 2.03518 2.52187 + endloop + endfacet + facet normal -0.919562 0.263797 -0.291234 + outer loop + vertex 1.1945 2.04 2.52 + vertex 1.19381 2.03772 2.52013 + vertex 1.1927 2.03628 2.52233 + endloop + endfacet + facet normal 0.565597 -0.823978 -0.0340459 + outer loop + vertex 1.1927 2.03628 2.52233 + vertex 1.19255 2.03605 2.52534 + vertex 1.19013 2.03438 2.52559 + endloop + endfacet + facet normal 0.484058 -0.866389 -0.122711 + outer loop + vertex 1.19062 2.03518 2.52187 + vertex 1.1927 2.03628 2.52233 + vertex 1.19013 2.03438 2.52559 + endloop + endfacet + facet normal 0.710578 -0.632747 0.307749 + outer loop + vertex 1.18761 2.03275 2.52838 + vertex 1.1903 2.03696 2.53083 + vertex 1.18785 2.03433 2.53109 + endloop + endfacet + facet normal 0.723291 -0.628403 0.286286 + outer loop + vertex 1.19013 2.03438 2.52559 + vertex 1.1903 2.03696 2.53083 + vertex 1.18761 2.03275 2.52838 + endloop + endfacet + facet normal 0.472902 -0.796279 0.377231 + outer loop + vertex 1.19013 2.03438 2.52559 + vertex 1.19274 2.03713 2.52813 + vertex 1.1903 2.03696 2.53083 + endloop + endfacet + facet normal 0.566613 -0.780635 0.263741 + outer loop + vertex 1.19013 2.03438 2.52559 + vertex 1.19255 2.03605 2.52534 + vertex 1.19274 2.03713 2.52813 + endloop + endfacet + facet normal 0.635875 -0.539403 0.552003 + outer loop + vertex 1.1903 2.03696 2.53083 + vertex 1.18755 2.03614 2.5332 + vertex 1.18785 2.03433 2.53109 + endloop + endfacet + facet normal 0.0873047 -0.0823759 -0.99277 + outer loop + vertex 1.195 2.04053 2.52 + vertex 1.19381 2.03772 2.52013 + vertex 1.1945 2.04 2.52 + endloop + endfacet + facet normal 0.541581 -0.713425 0.444651 + outer loop + vertex 1.19274 2.03713 2.52813 + vertex 1.19308 2.03901 2.53073 + vertex 1.1903 2.03696 2.53083 + endloop + endfacet + facet normal 0.579794 -0.443831 0.683266 + outer loop + vertex 1.18755 2.03614 2.5332 + vertex 1.18921 2.0402 2.53442 + vertex 1.18648 2.03832 2.53552 + endloop + endfacet + facet normal 0.655607 -0.451377 0.605341 + outer loop + vertex 1.1903 2.03696 2.53083 + vertex 1.18921 2.0402 2.53442 + vertex 1.18755 2.03614 2.5332 + endloop + endfacet + facet normal 0.519945 -0.550361 0.653269 + outer loop + vertex 1.1903 2.03696 2.53083 + vertex 1.1937 2.04246 2.53276 + vertex 1.18921 2.0402 2.53442 + endloop + endfacet + facet normal 0.407319 -0.515826 0.753667 + outer loop + vertex 1.1903 2.03696 2.53083 + vertex 1.19308 2.03901 2.53073 + vertex 1.1937 2.04246 2.53276 + endloop + endfacet + facet normal 0.494527 -0.229189 0.8384 + outer loop + vertex 1.18921 2.0402 2.53442 + vertex 1.18632 2.04177 2.53656 + vertex 1.18648 2.03832 2.53552 + endloop + endfacet + facet normal 0.470389 -0.170493 0.865833 + outer loop + vertex 1.1937 2.04246 2.53276 + vertex 1.19311 2.04876 2.53432 + vertex 1.18961 2.04476 2.53543 + endloop + endfacet + facet normal 0.43852 -0.230528 0.868652 + outer loop + vertex 1.18921 2.0402 2.53442 + vertex 1.1937 2.04246 2.53276 + vertex 1.18961 2.04476 2.53543 + endloop + endfacet + facet normal 0.494765 -0.228733 0.838385 + outer loop + vertex 1.18961 2.04476 2.53543 + vertex 1.18632 2.04177 2.53656 + vertex 1.18921 2.0402 2.53442 + endloop + endfacet + facet normal 0.220624 0.523847 0.822745 + outer loop + vertex 1.19019 2.15508 2.50607 + vertex 1.19441 2.15383 2.50573 + vertex 1.19239 2.15693 2.5043 + endloop + endfacet + facet normal 0.21411 0.529669 0.820736 + outer loop + vertex 1.18948 2.15717 2.5049 + vertex 1.19019 2.15508 2.50607 + vertex 1.19239 2.15693 2.5043 + endloop + endfacet + facet normal 0.202062 0.406831 0.890876 + outer loop + vertex 1.19159 2.15138 2.50744 + vertex 1.19019 2.15508 2.50607 + vertex 1.18703 2.15316 2.50766 + endloop + endfacet + facet normal 0.190878 0.403983 0.89463 + outer loop + vertex 1.19441 2.15383 2.50573 + vertex 1.19019 2.15508 2.50607 + vertex 1.19159 2.15138 2.50744 + endloop + endfacet + facet normal 0.143348 0.825595 0.545751 + outer loop + vertex 1.18882 2.1591 2.50305 + vertex 1.1943 2.159 2.50176 + vertex 1.19128 2.16108 2.4994 + endloop + endfacet + facet normal 0.13317 0.830181 0.541354 + outer loop + vertex 1.18722 2.16124 2.50016 + vertex 1.18882 2.1591 2.50305 + vertex 1.19128 2.16108 2.4994 + endloop + endfacet + facet normal 0.198496 0.713417 0.672038 + outer loop + vertex 1.19239 2.15693 2.5043 + vertex 1.18882 2.1591 2.50305 + vertex 1.18948 2.15717 2.5049 + endloop + endfacet + facet normal 0.176926 0.693265 0.698628 + outer loop + vertex 1.1943 2.159 2.50176 + vertex 1.18882 2.1591 2.50305 + vertex 1.19239 2.15693 2.5043 + endloop + endfacet + facet normal 0.0555718 0.427521 0.902296 + outer loop + vertex 1.195 2.1693 2.49 + vertex 1.19 2.16995 2.49 + vertex 1.19432 2.16514 2.49201 + endloop + endfacet + facet normal 0.121009 0.473685 0.872341 + outer loop + vertex 1.19432 2.16514 2.49201 + vertex 1.19 2.16995 2.49 + vertex 1.19017 2.16481 2.49277 + endloop + endfacet + facet normal 0.0340145 0.835268 0.54879 + outer loop + vertex 1.19432 2.16514 2.49201 + vertex 1.19017 2.16481 2.49277 + vertex 1.19312 2.16277 2.49569 + endloop + endfacet + facet normal 0.077999 0.852662 0.516608 + outer loop + vertex 1.19312 2.16277 2.49569 + vertex 1.19017 2.16481 2.49277 + vertex 1.18763 2.16295 2.49623 + endloop + endfacet + facet normal 0.110749 0.907408 0.405395 + outer loop + vertex 1.19128 2.16108 2.4994 + vertex 1.18763 2.16295 2.49623 + vertex 1.18722 2.16124 2.50016 + endloop + endfacet + facet normal 0.0720488 0.894109 0.442017 + outer loop + vertex 1.19312 2.16277 2.49569 + vertex 1.18763 2.16295 2.49623 + vertex 1.19128 2.16108 2.4994 + endloop + endfacet + facet normal -0.360266 0.877059 0.317766 + outer loop + vertex 1.195 2.17129 2.485 + vertex 1.19186 2.17 2.485 + vertex 1.195 2.17 2.48856 + endloop + endfacet + facet normal -0.0105354 -0.774563 -0.632409 + outer loop + vertex 1.2 0.858943 2.485 + vertex 1.19793 0.858769 2.48525 + vertex 1.195 0.859011 2.485 + endloop + endfacet + facet normal -0.0626807 -0.975301 -0.211801 + outer loop + vertex 1.19793 0.858769 2.48525 + vertex 1.19305 0.858773 2.48667 + vertex 1.195 0.859011 2.485 + endloop + endfacet + facet normal 0.070817 -0.966978 0.244824 + outer loop + vertex 1.19793 0.858769 2.48525 + vertex 1.19469 0.859274 2.48818 + vertex 1.19305 0.858773 2.48667 + endloop + endfacet + facet normal 0.0674275 -0.968111 0.241276 + outer loop + vertex 1.19866 0.859357 2.4874 + vertex 1.19469 0.859274 2.48818 + vertex 1.19793 0.858769 2.48525 + endloop + endfacet + facet normal 0.0920508 -0.923616 0.372101 + outer loop + vertex 1.19469 0.859274 2.48818 + vertex 1.19866 0.859357 2.4874 + vertex 1.19736 0.860842 2.49141 + endloop + endfacet + facet normal 0.114718 -0.927664 0.355359 + outer loop + vertex 1.19248 0.860114 2.49109 + vertex 1.19469 0.859274 2.48818 + vertex 1.19736 0.860842 2.49141 + endloop + endfacet + facet normal 0.115611 -0.89017 0.440716 + outer loop + vertex 1.1962 0.862695 2.49546 + vertex 1.19736 0.860842 2.49141 + vertex 1.20024 0.862894 2.4948 + endloop + endfacet + facet normal 0.119546 -0.88929 0.441443 + outer loop + vertex 1.1962 0.862695 2.49546 + vertex 1.19208 0.86174 2.49465 + vertex 1.19736 0.860842 2.49141 + endloop + endfacet + facet normal 0.10616 -0.900071 0.422614 + outer loop + vertex 1.19208 0.86174 2.49465 + vertex 1.19248 0.860114 2.49109 + vertex 1.19736 0.860842 2.49141 + endloop + endfacet + facet normal 0.109638 -0.873844 0.473683 + outer loop + vertex 1.1962 0.862695 2.49546 + vertex 1.19355 0.863636 2.49781 + vertex 1.19208 0.86174 2.49465 + endloop + endfacet + facet normal 0.12444 -0.853457 0.506089 + outer loop + vertex 1.20024 0.862894 2.4948 + vertex 1.19771 0.864759 2.49857 + vertex 1.1962 0.862695 2.49546 + endloop + endfacet + facet normal 0.139463 -0.854876 0.499738 + outer loop + vertex 1.19355 0.863636 2.49781 + vertex 1.1962 0.862695 2.49546 + vertex 1.19771 0.864759 2.49857 + endloop + endfacet + facet normal 0.126078 -0.832307 0.539786 + outer loop + vertex 1.19355 0.863636 2.49781 + vertex 1.19771 0.864759 2.49857 + vertex 1.19216 0.865847 2.50154 + endloop + endfacet + facet normal 0.150914 -0.803663 0.57563 + outer loop + vertex 1.19216 0.865847 2.50154 + vertex 1.19771 0.864759 2.49857 + vertex 1.19712 0.867031 2.50189 + endloop + endfacet + facet normal 0.133816 -0.752696 0.644626 + outer loop + vertex 1.19712 0.867031 2.50189 + vertex 1.19475 0.868558 2.50417 + vertex 1.19216 0.865847 2.50154 + endloop + endfacet + facet normal 0.206928 -0.698953 0.684577 + outer loop + vertex 1.19967 0.869717 2.50386 + vertex 1.19475 0.868558 2.50417 + vertex 1.19712 0.867031 2.50189 + endloop + endfacet + facet normal 0.186518 -0.585143 0.789189 + outer loop + vertex 1.19475 0.868558 2.50417 + vertex 1.19967 0.869717 2.50386 + vertex 1.19652 0.871445 2.50589 + endloop + endfacet + facet normal 0.220698 -0.595922 0.77212 + outer loop + vertex 1.1929 0.870274 2.50602 + vertex 1.19475 0.868558 2.50417 + vertex 1.19652 0.871445 2.50589 + endloop + endfacet + facet normal 0.170035 -0.426291 0.888461 + outer loop + vertex 1.19652 0.871445 2.50589 + vertex 1.19391 0.873877 2.50755 + vertex 1.1929 0.870274 2.50602 + endloop + endfacet + facet normal 0.190101 -0.407899 0.893017 + outer loop + vertex 1.19894 0.874923 2.50696 + vertex 1.19391 0.873877 2.50755 + vertex 1.19652 0.871445 2.50589 + endloop + endfacet + facet normal 0.208275 -0.248695 0.945924 + outer loop + vertex 1.19834 0.887244 2.51058 + vertex 1.19751 0.889701 2.51141 + vertex 1.19524 0.88688 2.51116 + endloop + endfacet + facet normal 0.488152 -0.0123026 0.872672 + outer loop + vertex 1.19428 0.977645 2.53436 + vertex 1.19147 0.975615 2.5359 + vertex 1.19326 0.973238 2.53487 + endloop + endfacet + facet normal 0.362935 0.0234767 0.931519 + outer loop + vertex 1.19428 0.977645 2.53436 + vertex 1.19326 0.973238 2.53487 + vertex 1.19777 0.976043 2.53304 + endloop + endfacet + facet normal 0.330024 0.0822548 0.940382 + outer loop + vertex 1.19777 0.976043 2.53304 + vertex 1.19326 0.973238 2.53487 + vertex 1.19681 0.972144 2.53372 + endloop + endfacet + facet normal 0.413939 0.113644 0.903183 + outer loop + vertex 1.19428 0.977645 2.53436 + vertex 1.19067 0.978427 2.53591 + vertex 1.19147 0.975615 2.5359 + endloop + endfacet + facet normal 0.540996 0.513825 0.665813 + outer loop + vertex 1.19832 0.980727 2.53056 + vertex 1.19833 0.983572 2.52836 + vertex 1.19578 0.983793 2.53025 + endloop + endfacet + facet normal 0.525909 0.451338 0.720912 + outer loop + vertex 1.19578 0.983793 2.53025 + vertex 1.1918 0.984612 2.53264 + vertex 1.19343 0.981196 2.5336 + endloop + endfacet + facet normal 0.495312 0.481711 0.722924 + outer loop + vertex 1.19832 0.980727 2.53056 + vertex 1.19578 0.983793 2.53025 + vertex 1.19343 0.981196 2.5336 + endloop + endfacet + facet normal 0.524311 0.296854 0.798108 + outer loop + vertex 1.19832 0.980727 2.53056 + vertex 1.19343 0.981196 2.5336 + vertex 1.19428 0.977645 2.53436 + endloop + endfacet + facet normal 0.471782 0.36904 0.800769 + outer loop + vertex 1.19832 0.980727 2.53056 + vertex 1.19428 0.977645 2.53436 + vertex 1.19777 0.976043 2.53304 + endloop + endfacet + facet normal 0.430993 0.286861 0.855544 + outer loop + vertex 1.19428 0.977645 2.53436 + vertex 1.19343 0.981196 2.5336 + vertex 1.19067 0.978427 2.53591 + endloop + endfacet + facet normal 0.0218614 0.0641481 -0.997701 + outer loop + vertex 1.2 0.986585 2.52 + vertex 1.195 0.988289 2.52 + vertex 1.19344 0.989292 2.52003 + endloop + endfacet + facet normal 0.338681 0.815639 0.469071 + outer loop + vertex 1.19755 0.987305 2.52051 + vertex 1.2 0.986585 2.52 + vertex 1.19344 0.989292 2.52003 + endloop + endfacet + facet normal 0.640833 0.668934 0.376644 + outer loop + vertex 1.1978 0.985785 2.52605 + vertex 1.19636 0.988067 2.52445 + vertex 1.1954 0.987777 2.5266 + endloop + endfacet + facet normal 0.565785 0.609931 0.554863 + outer loop + vertex 1.1954 0.987777 2.5266 + vertex 1.19385 0.988041 2.52789 + vertex 1.19453 0.986382 2.52902 + endloop + endfacet + facet normal 0.604307 0.576921 0.549523 + outer loop + vertex 1.1978 0.985785 2.52605 + vertex 1.1954 0.987777 2.5266 + vertex 1.19453 0.986382 2.52902 + endloop + endfacet + facet normal 0.610145 0.561376 0.559089 + outer loop + vertex 1.1978 0.985785 2.52605 + vertex 1.19453 0.986382 2.52902 + vertex 1.19578 0.983793 2.53025 + endloop + endfacet + facet normal 0.471488 0.687472 0.552342 + outer loop + vertex 1.1978 0.985785 2.52605 + vertex 1.19578 0.983793 2.53025 + vertex 1.19833 0.983572 2.52836 + endloop + endfacet + facet normal 0.508584 0.558402 0.655385 + outer loop + vertex 1.19578 0.983793 2.53025 + vertex 1.19453 0.986382 2.52902 + vertex 1.1918 0.984612 2.53264 + endloop + endfacet + facet normal 0.445142 0.870625 -0.209431 + outer loop + vertex 1.19344 0.989292 2.52003 + vertex 1.19535 0.988812 2.5221 + vertex 1.19755 0.987305 2.52051 + endloop + endfacet + facet normal 0.503713 0.818754 -0.275527 + outer loop + vertex 1.19211 0.990889 2.52234 + vertex 1.19535 0.988812 2.5221 + vertex 1.19344 0.989292 2.52003 + endloop + endfacet + facet normal 0.50475 0.796472 0.332955 + outer loop + vertex 1.19636 0.988067 2.52445 + vertex 1.19278 0.989763 2.52583 + vertex 1.1954 0.987777 2.5266 + endloop + endfacet + facet normal 0.45337 0.88704 0.0872722 + outer loop + vertex 1.19636 0.988067 2.52445 + vertex 1.19535 0.988812 2.5221 + vertex 1.19278 0.989763 2.52583 + endloop + endfacet + facet normal 0.540224 0.825563 0.163107 + outer loop + vertex 1.19535 0.988812 2.5221 + vertex 1.19211 0.990889 2.52234 + vertex 1.19278 0.989763 2.52583 + endloop + endfacet + facet normal 0.472019 0.782177 0.406691 + outer loop + vertex 1.1954 0.987777 2.5266 + vertex 1.19278 0.989763 2.52583 + vertex 1.19385 0.988041 2.52789 + endloop + endfacet + facet normal 0.443231 -0.835246 -0.325438 + outer loop + vertex 1.19459 2.03767 2.52132 + vertex 1.1927 2.03628 2.52233 + vertex 1.19381 2.03772 2.52013 + endloop + endfacet + facet normal 0.575094 -0.816512 -0.0507512 + outer loop + vertex 1.19531 2.03794 2.52509 + vertex 1.1927 2.03628 2.52233 + vertex 1.19459 2.03767 2.52132 + endloop + endfacet + facet normal 0.563348 -0.825509 -0.0342674 + outer loop + vertex 1.19255 2.03605 2.52534 + vertex 1.1927 2.03628 2.52233 + vertex 1.19531 2.03794 2.52509 + endloop + endfacet + facet normal 0.561522 -0.783775 0.26531 + outer loop + vertex 1.19531 2.03794 2.52509 + vertex 1.19274 2.03713 2.52813 + vertex 1.19255 2.03605 2.52534 + endloop + endfacet + facet normal 0.776085 -0.353801 -0.522032 + outer loop + vertex 1.19459 2.03767 2.52132 + vertex 1.19381 2.03772 2.52013 + vertex 1.195 2.04053 2.52 + endloop + endfacet + facet normal 0.315905 -0.435508 -0.842933 + outer loop + vertex 1.19459 2.03767 2.52132 + vertex 1.195 2.04053 2.52 + vertex 1.19725 2.03914 2.52156 + endloop + endfacet + facet normal 0.136945 -0.633981 -0.761127 + outer loop + vertex 1.19725 2.03914 2.52156 + vertex 1.195 2.04053 2.52 + vertex 1.2 2.04161 2.52 + endloop + endfacet + facet normal 0.409104 -0.908712 -0.0829274 + outer loop + vertex 1.19725 2.03914 2.52156 + vertex 1.19882 2.0396 2.52426 + vertex 1.19531 2.03794 2.52509 + endloop + endfacet + facet normal 0.484884 -0.874085 -0.0293778 + outer loop + vertex 1.19459 2.03767 2.52132 + vertex 1.19725 2.03914 2.52156 + vertex 1.19531 2.03794 2.52509 + endloop + endfacet + facet normal 0.490138 -0.735709 0.467437 + outer loop + vertex 1.19274 2.03713 2.52813 + vertex 1.19551 2.03989 2.52957 + vertex 1.19308 2.03901 2.53073 + endloop + endfacet + facet normal 0.590991 -0.749055 0.299409 + outer loop + vertex 1.19531 2.03794 2.52509 + vertex 1.19551 2.03989 2.52957 + vertex 1.19274 2.03713 2.52813 + endloop + endfacet + facet normal 0.387426 -0.851583 0.35314 + outer loop + vertex 1.19531 2.03794 2.52509 + vertex 1.19903 2.04061 2.52743 + vertex 1.19551 2.03989 2.52957 + endloop + endfacet + facet normal 0.460249 -0.854673 0.240218 + outer loop + vertex 1.19531 2.03794 2.52509 + vertex 1.19882 2.0396 2.52426 + vertex 1.19903 2.04061 2.52743 + endloop + endfacet + facet normal 0.514401 -0.50113 0.695888 + outer loop + vertex 1.19551 2.03989 2.52957 + vertex 1.1937 2.04246 2.53276 + vertex 1.19308 2.03901 2.53073 + endloop + endfacet + facet normal 0.466279 -0.707534 0.531017 + outer loop + vertex 1.19903 2.04061 2.52743 + vertex 1.19901 2.04303 2.53067 + vertex 1.19551 2.03989 2.52957 + endloop + endfacet + facet normal 0.341557 -0.627355 0.699832 + outer loop + vertex 1.19901 2.04303 2.53067 + vertex 1.1937 2.04246 2.53276 + vertex 1.19551 2.03989 2.52957 + endloop + endfacet + facet normal 0.369849 -0.422284 0.82758 + outer loop + vertex 1.19901 2.04303 2.53067 + vertex 1.19891 2.04712 2.53281 + vertex 1.1937 2.04246 2.53276 + endloop + endfacet + facet normal 0.187134 -0.219641 0.957465 + outer loop + vertex 1.19891 2.04712 2.53281 + vertex 1.19311 2.04876 2.53432 + vertex 1.1937 2.04246 2.53276 + endloop + endfacet + facet normal 0.217566 0.495329 0.84102 + outer loop + vertex 1.19441 2.15383 2.50573 + vertex 1.19852 2.15257 2.50541 + vertex 1.19773 2.15596 2.50362 + endloop + endfacet + facet normal 0.199897 0.51528 0.833383 + outer loop + vertex 1.19239 2.15693 2.5043 + vertex 1.19441 2.15383 2.50573 + vertex 1.19773 2.15596 2.50362 + endloop + endfacet + facet normal 0.214482 0.380257 0.899668 + outer loop + vertex 1.19666 2.14965 2.50696 + vertex 1.19441 2.15383 2.50573 + vertex 1.19159 2.15138 2.50744 + endloop + endfacet + facet normal 0.183918 0.36732 0.911729 + outer loop + vertex 1.19852 2.15257 2.50541 + vertex 1.19441 2.15383 2.50573 + vertex 1.19666 2.14965 2.50696 + endloop + endfacet + facet normal 0.14506 0.809317 0.569177 + outer loop + vertex 1.1943 2.159 2.50176 + vertex 1.19946 2.1588 2.50073 + vertex 1.19636 2.16091 2.49852 + endloop + endfacet + facet normal 0.125506 0.817762 0.561706 + outer loop + vertex 1.19128 2.16108 2.4994 + vertex 1.1943 2.159 2.50176 + vertex 1.19636 2.16091 2.49852 + endloop + endfacet + facet normal 0.212564 0.672754 0.708674 + outer loop + vertex 1.19773 2.15596 2.50362 + vertex 1.1943 2.159 2.50176 + vertex 1.19239 2.15693 2.5043 + endloop + endfacet + facet normal 0.172866 0.648113 0.741665 + outer loop + vertex 1.19946 2.1588 2.50073 + vertex 1.1943 2.159 2.50176 + vertex 1.19773 2.15596 2.50362 + endloop + endfacet + facet normal -0.0220712 0.306534 0.951604 + outer loop + vertex 1.2 2.16966 2.49 + vertex 1.195 2.1693 2.49 + vertex 1.19891 2.16504 2.49146 + endloop + endfacet + facet normal 0.116959 0.417004 0.901348 + outer loop + vertex 1.19891 2.16504 2.49146 + vertex 1.195 2.1693 2.49 + vertex 1.19432 2.16514 2.49201 + endloop + endfacet + facet normal 0.0863551 0.810287 0.579636 + outer loop + vertex 1.19891 2.16504 2.49146 + vertex 1.19432 2.16514 2.49201 + vertex 1.19812 2.16266 2.49491 + endloop + endfacet + facet normal 0.105847 0.820069 0.56239 + outer loop + vertex 1.19812 2.16266 2.49491 + vertex 1.19432 2.16514 2.49201 + vertex 1.19312 2.16277 2.49569 + endloop + endfacet + facet normal 0.109252 0.883455 0.4556 + outer loop + vertex 1.19636 2.16091 2.49852 + vertex 1.19312 2.16277 2.49569 + vertex 1.19128 2.16108 2.4994 + endloop + endfacet + facet normal 0.0927903 0.877497 0.47052 + outer loop + vertex 1.19812 2.16266 2.49491 + vertex 1.19312 2.16277 2.49569 + vertex 1.19636 2.16091 2.49852 + endloop + endfacet + facet normal -0.0340419 0.939649 0.340443 + outer loop + vertex 1.2 2.17 2.48906 + vertex 1.195 2.17129 2.485 + vertex 1.195 2.17 2.48856 + endloop + endfacet + facet normal 0.0542452 0.968998 0.24104 + outer loop + vertex 1.2 2.17101 2.485 + vertex 1.195 2.17129 2.485 + vertex 1.2 2.17 2.48906 + endloop + endfacet + facet normal -0.00693346 -0.733713 -0.679424 + outer loop + vertex 1.20171 0.859031 2.48552 + vertex 1.205 0.859479 2.485 + vertex 1.20609 0.859251 2.48524 + endloop + endfacet + facet normal 0.0861446 -0.956012 -0.280392 + outer loop + vertex 1.20171 0.859031 2.48552 + vertex 1.19793 0.858769 2.48525 + vertex 1.205 0.859479 2.485 + endloop + endfacet + facet normal 0.104639 -0.976067 0.19064 + outer loop + vertex 1.19793 0.858769 2.48525 + vertex 1.2 0.858943 2.485 + vertex 1.205 0.859479 2.485 + endloop + endfacet + facet normal 0.049369 -0.967676 0.247316 + outer loop + vertex 1.20171 0.859031 2.48552 + vertex 1.19866 0.859357 2.4874 + vertex 1.19793 0.858769 2.48525 + endloop + endfacet + facet normal 0.0688275 -0.938629 0.337992 + outer loop + vertex 1.20609 0.859251 2.48524 + vertex 1.20286 0.860123 2.48832 + vertex 1.20171 0.859031 2.48552 + endloop + endfacet + facet normal 0.10063 -0.940133 0.325612 + outer loop + vertex 1.19866 0.859357 2.4874 + vertex 1.20171 0.859031 2.48552 + vertex 1.20286 0.860123 2.48832 + endloop + endfacet + facet normal 0.0878361 -0.924453 0.371042 + outer loop + vertex 1.19866 0.859357 2.4874 + vertex 1.20286 0.860123 2.48832 + vertex 1.19736 0.860842 2.49141 + endloop + endfacet + facet normal 0.106832 -0.909664 0.40137 + outer loop + vertex 1.19736 0.860842 2.49141 + vertex 1.20286 0.860123 2.48832 + vertex 1.2023 0.861629 2.49188 + endloop + endfacet + facet normal 0.0981374 -0.886061 0.453062 + outer loop + vertex 1.2023 0.861629 2.49188 + vertex 1.20024 0.862894 2.4948 + vertex 1.19736 0.860842 2.49141 + endloop + endfacet + facet normal 0.103701 -0.883891 0.45605 + outer loop + vertex 1.20479 0.86314 2.49424 + vertex 1.20024 0.862894 2.4948 + vertex 1.2023 0.861629 2.49188 + endloop + endfacet + facet normal 0.108647 -0.853401 0.509807 + outer loop + vertex 1.20024 0.862894 2.4948 + vertex 1.20479 0.86314 2.49424 + vertex 1.20309 0.864838 2.49744 + endloop + endfacet + facet normal 0.117261 -0.856443 0.502748 + outer loop + vertex 1.19771 0.864759 2.49857 + vertex 1.20024 0.862894 2.4948 + vertex 1.20309 0.864838 2.49744 + endloop + endfacet + facet normal 0.135702 -0.791476 0.595945 + outer loop + vertex 1.20309 0.864838 2.49744 + vertex 1.20156 0.867079 2.50077 + vertex 1.19771 0.864759 2.49857 + endloop + endfacet + facet normal 0.154168 -0.80297 0.575735 + outer loop + vertex 1.20156 0.867079 2.50077 + vertex 1.19712 0.867031 2.50189 + vertex 1.19771 0.864759 2.49857 + endloop + endfacet + facet normal 0.18445 -0.689359 0.700544 + outer loop + vertex 1.20156 0.867079 2.50077 + vertex 1.19967 0.869717 2.50386 + vertex 1.19712 0.867031 2.50189 + endloop + endfacet + facet normal 0.189707 -0.686835 0.701619 + outer loop + vertex 1.2049 0.869984 2.50271 + vertex 1.19967 0.869717 2.50386 + vertex 1.20156 0.867079 2.50077 + endloop + endfacet + facet normal 0.214489 -0.552937 0.805143 + outer loop + vertex 1.20002 0.872563 2.50572 + vertex 1.19652 0.871445 2.50589 + vertex 1.19967 0.869717 2.50386 + endloop + endfacet + facet normal 0.226048 -0.552508 0.80227 + outer loop + vertex 1.20002 0.872563 2.50572 + vertex 1.19967 0.869717 2.50386 + vertex 1.20344 0.872778 2.50491 + endloop + endfacet + facet normal 0.207807 -0.535569 0.818524 + outer loop + vertex 1.20344 0.872778 2.50491 + vertex 1.19967 0.869717 2.50386 + vertex 1.2049 0.869984 2.50271 + endloop + endfacet + facet normal 0.168995 -0.39614 0.902504 + outer loop + vertex 1.20002 0.872563 2.50572 + vertex 1.19894 0.874923 2.50696 + vertex 1.19652 0.871445 2.50589 + endloop + endfacet + facet normal 0.202966 -0.250703 0.946548 + outer loop + vertex 1.19751 0.889701 2.51141 + vertex 1.19834 0.887244 2.51058 + vertex 1.20118 0.891338 2.51105 + endloop + endfacet + facet normal 0.313789 0.599837 0.736024 + outer loop + vertex 1.20594 0.976693 2.52973 + vertex 1.20462 0.978948 2.52845 + vertex 1.20199 0.978015 2.53034 + endloop + endfacet + facet normal 0.255458 0.34922 0.901547 + outer loop + vertex 1.20199 0.978015 2.53034 + vertex 1.20152 0.97352 2.53221 + vertex 1.20594 0.976693 2.52973 + endloop + endfacet + facet normal 0.402153 0.316394 0.859167 + outer loop + vertex 1.20199 0.978015 2.53034 + vertex 1.19777 0.976043 2.53304 + vertex 1.20152 0.97352 2.53221 + endloop + endfacet + facet normal 0.276577 0.0981233 0.955969 + outer loop + vertex 1.19777 0.976043 2.53304 + vertex 1.19681 0.972144 2.53372 + vertex 1.20152 0.97352 2.53221 + endloop + endfacet + facet normal 0.527969 0.722837 0.445819 + outer loop + vertex 1.20353 0.981042 2.52632 + vertex 1.20264 0.98319 2.5239 + vertex 1.20054 0.983373 2.52609 + endloop + endfacet + facet normal 0.655881 0.46097 0.597768 + outer loop + vertex 1.20054 0.983373 2.52609 + vertex 1.19833 0.983572 2.52836 + vertex 1.19832 0.980727 2.53056 + endloop + endfacet + facet normal 0.456609 0.64794 0.609657 + outer loop + vertex 1.20353 0.981042 2.52632 + vertex 1.20054 0.983373 2.52609 + vertex 1.19832 0.980727 2.53056 + endloop + endfacet + facet normal 0.482182 0.600791 0.637613 + outer loop + vertex 1.20353 0.981042 2.52632 + vertex 1.19832 0.980727 2.53056 + vertex 1.20199 0.978015 2.53034 + endloop + endfacet + facet normal 0.190281 0.747562 0.636353 + outer loop + vertex 1.20353 0.981042 2.52632 + vertex 1.20199 0.978015 2.53034 + vertex 1.20462 0.978948 2.52845 + endloop + endfacet + facet normal 0.350468 0.406073 0.843965 + outer loop + vertex 1.20199 0.978015 2.53034 + vertex 1.19832 0.980727 2.53056 + vertex 1.19777 0.976043 2.53304 + endloop + endfacet + facet normal -0.092819 -0.610593 0.786487 + outer loop + vertex 1.2 0.985 2.51872 + vertex 1.20168 0.9845 2.51853 + vertex 1.205 0.985 2.51931 + endloop + endfacet + facet normal 0.0985531 0.62524 -0.774185 + outer loop + vertex 1.2 0.986585 2.52 + vertex 1.20168 0.9845 2.51853 + vertex 1.2 0.985 2.51872 + endloop + endfacet + facet normal 0.603167 0.793848 -0.0774239 + outer loop + vertex 1.19755 0.987305 2.52051 + vertex 1.19803 0.987145 2.52258 + vertex 1.2009 0.984869 2.52161 + endloop + endfacet + facet normal 0.339639 0.731915 0.590717 + outer loop + vertex 1.19755 0.987305 2.52051 + vertex 1.2009 0.984869 2.52161 + vertex 1.2 0.986585 2.52 + endloop + endfacet + facet normal 0.816333 0.560135 0.140891 + outer loop + vertex 1.2 0.986585 2.52 + vertex 1.2009 0.984869 2.52161 + vertex 1.20168 0.9845 2.51853 + endloop + endfacet + facet normal 0.696207 0.651372 0.30168 + outer loop + vertex 1.19803 0.987145 2.52258 + vertex 1.19636 0.988067 2.52445 + vertex 1.1978 0.985785 2.52605 + endloop + endfacet + facet normal 0.653189 0.689178 0.313652 + outer loop + vertex 1.2009 0.984869 2.52161 + vertex 1.19803 0.987145 2.52258 + vertex 1.1978 0.985785 2.52605 + endloop + endfacet + facet normal 0.630565 0.719248 0.291667 + outer loop + vertex 1.2009 0.984869 2.52161 + vertex 1.1978 0.985785 2.52605 + vertex 1.20054 0.983373 2.52609 + endloop + endfacet + facet normal 0.40739 0.855702 0.319073 + outer loop + vertex 1.2009 0.984869 2.52161 + vertex 1.20054 0.983373 2.52609 + vertex 1.20264 0.98319 2.5239 + endloop + endfacet + facet normal 0.570165 0.65375 0.497516 + outer loop + vertex 1.20054 0.983373 2.52609 + vertex 1.1978 0.985785 2.52605 + vertex 1.19833 0.983572 2.52836 + endloop + endfacet + facet normal 0.535299 0.842668 -0.0580092 + outer loop + vertex 1.19755 0.987305 2.52051 + vertex 1.19535 0.988812 2.5221 + vertex 1.19803 0.987145 2.52258 + endloop + endfacet + facet normal 0.522038 0.851644 0.0466725 + outer loop + vertex 1.19803 0.987145 2.52258 + vertex 1.19535 0.988812 2.5221 + vertex 1.19636 0.988067 2.52445 + endloop + endfacet + facet normal 0.369265 -0.712882 -0.59619 + outer loop + vertex 1.205 2.0442 2.52 + vertex 1.20124 2.0409 2.52161 + vertex 1.2 2.04161 2.52 + endloop + endfacet + facet normal 0.334899 -0.740948 -0.582099 + outer loop + vertex 1.20124 2.0409 2.52161 + vertex 1.19725 2.03914 2.52156 + vertex 1.2 2.04161 2.52 + endloop + endfacet + facet normal 0.386309 -0.92225 0.01485 + outer loop + vertex 1.20138 2.04102 2.52509 + vertex 1.20124 2.0409 2.52161 + vertex 1.20368 2.04196 2.52343 + endloop + endfacet + facet normal 0.482637 -0.875772 0.00916779 + outer loop + vertex 1.20138 2.04102 2.52509 + vertex 1.19882 2.0396 2.52426 + vertex 1.20124 2.0409 2.52161 + endloop + endfacet + facet normal 0.404288 -0.91115 -0.0797291 + outer loop + vertex 1.19882 2.0396 2.52426 + vertex 1.19725 2.03914 2.52156 + vertex 1.20124 2.0409 2.52161 + endloop + endfacet + facet normal 0.405842 -0.878626 0.251612 + outer loop + vertex 1.20138 2.04102 2.52509 + vertex 1.19903 2.04061 2.52743 + vertex 1.19882 2.0396 2.52426 + endloop + endfacet + facet normal 0.519461 -0.813852 0.260394 + outer loop + vertex 1.20368 2.04196 2.52343 + vertex 1.20359 2.04318 2.52745 + vertex 1.20138 2.04102 2.52509 + endloop + endfacet + facet normal 0.46531 -0.824867 0.321063 + outer loop + vertex 1.19903 2.04061 2.52743 + vertex 1.20138 2.04102 2.52509 + vertex 1.20359 2.04318 2.52745 + endloop + endfacet + facet normal 0.410306 -0.729608 0.547102 + outer loop + vertex 1.19903 2.04061 2.52743 + vertex 1.20359 2.04318 2.52745 + vertex 1.19901 2.04303 2.53067 + endloop + endfacet + facet normal 0.424382 -0.704976 0.568251 + outer loop + vertex 1.19901 2.04303 2.53067 + vertex 1.20359 2.04318 2.52745 + vertex 1.20247 2.0454 2.53103 + endloop + endfacet + facet normal 0.21588 -0.447214 0.867984 + outer loop + vertex 1.20247 2.0454 2.53103 + vertex 1.19891 2.04712 2.53281 + vertex 1.19901 2.04303 2.53067 + endloop + endfacet + facet normal 0.239172 -0.41119 0.879613 + outer loop + vertex 1.2038 2.04803 2.5319 + vertex 1.19891 2.04712 2.53281 + vertex 1.20247 2.0454 2.53103 + endloop + endfacet + facet normal 0.21764 0.375948 0.90072 + outer loop + vertex 1.19852 2.15257 2.50541 + vertex 1.20079 2.14986 2.50599 + vertex 1.20328 2.15253 2.50428 + endloop + endfacet + facet normal 0.205203 0.494408 0.844661 + outer loop + vertex 1.19852 2.15257 2.50541 + vertex 1.20328 2.15253 2.50428 + vertex 1.19773 2.15596 2.50362 + endloop + endfacet + facet normal 0.205785 0.495229 0.844038 + outer loop + vertex 1.19773 2.15596 2.50362 + vertex 1.20328 2.15253 2.50428 + vertex 1.20238 2.15642 2.50221 + endloop + endfacet + facet normal 0.195794 0.360014 0.91217 + outer loop + vertex 1.20079 2.14986 2.50599 + vertex 1.19852 2.15257 2.50541 + vertex 1.19666 2.14965 2.50696 + endloop + endfacet + facet normal 0.143919 0.796284 0.587553 + outer loop + vertex 1.19946 2.1588 2.50073 + vertex 1.20481 2.15864 2.49963 + vertex 1.20138 2.16075 2.49762 + endloop + endfacet + facet normal 0.130365 0.80205 0.582856 + outer loop + vertex 1.19636 2.16091 2.49852 + vertex 1.19946 2.1588 2.50073 + vertex 1.20138 2.16075 2.49762 + endloop + endfacet + facet normal 0.158366 0.654521 0.739271 + outer loop + vertex 1.20238 2.15642 2.50221 + vertex 1.19946 2.1588 2.50073 + vertex 1.19773 2.15596 2.50362 + endloop + endfacet + facet normal 0.169388 0.66221 0.729922 + outer loop + vertex 1.20481 2.15864 2.49963 + vertex 1.19946 2.1588 2.50073 + vertex 1.20238 2.15642 2.50221 + endloop + endfacet + facet normal 0.632516 0.774415 -0.0143087 + outer loop + vertex 1.2 2.16966 2.49 + vertex 1.20496 2.16557 2.48782 + vertex 1.20204 2.16792 2.48584 + endloop + endfacet + facet normal 0.831525 0.522375 0.188919 + outer loop + vertex 1.2 2.17 2.48906 + vertex 1.2 2.16966 2.49 + vertex 1.20204 2.16792 2.48584 + endloop + endfacet + facet normal 0.649882 0.470372 0.596996 + outer loop + vertex 1.20496 2.16557 2.48782 + vertex 1.2 2.16966 2.49 + vertex 1.20305 2.16467 2.49062 + endloop + endfacet + facet normal 0.215798 0.248178 0.944372 + outer loop + vertex 1.20305 2.16467 2.49062 + vertex 1.2 2.16966 2.49 + vertex 1.19891 2.16504 2.49146 + endloop + endfacet + facet normal 0.180841 0.837902 0.514992 + outer loop + vertex 1.20305 2.16467 2.49062 + vertex 1.19891 2.16504 2.49146 + vertex 1.20345 2.16249 2.49403 + endloop + endfacet + facet normal 0.122784 0.803121 0.583028 + outer loop + vertex 1.20345 2.16249 2.49403 + vertex 1.19891 2.16504 2.49146 + vertex 1.19812 2.16266 2.49491 + endloop + endfacet + facet normal 0.113579 0.871196 0.477617 + outer loop + vertex 1.20138 2.16075 2.49762 + vertex 1.19812 2.16266 2.49491 + vertex 1.19636 2.16091 2.49852 + endloop + endfacet + facet normal 0.108224 0.869129 0.482599 + outer loop + vertex 1.20345 2.16249 2.49403 + vertex 1.19812 2.16266 2.49491 + vertex 1.20138 2.16075 2.49762 + endloop + endfacet + facet normal 0.808088 0.571642 0.142197 + outer loop + vertex 1.20204 2.16792 2.48584 + vertex 1.2 2.17101 2.485 + vertex 1.2 2.17 2.48906 + endloop + endfacet + facet normal 0.0314622 0.28089 0.959224 + outer loop + vertex 1.205 2.17045 2.485 + vertex 1.2 2.17101 2.485 + vertex 1.20204 2.16792 2.48584 + endloop + endfacet + facet normal -0.0633703 -0.847152 -0.527559 + outer loop + vertex 1.21 0.859105 2.485 + vertex 1.20609 0.859251 2.48524 + vertex 1.205 0.859479 2.485 + endloop + endfacet + facet normal 0.0705331 0.474091 0.877646 + outer loop + vertex 1.21098 0.859426 2.48475 + vertex 1.20609 0.859251 2.48524 + vertex 1.21 0.859105 2.485 + endloop + endfacet + facet normal 0.0718008 -0.917707 0.390715 + outer loop + vertex 1.20609 0.859251 2.48524 + vertex 1.21098 0.859426 2.48475 + vertex 1.20857 0.860377 2.48743 + endloop + endfacet + facet normal 0.0981311 -0.92577 0.36513 + outer loop + vertex 1.20286 0.860123 2.48832 + vertex 1.20609 0.859251 2.48524 + vertex 1.20857 0.860377 2.48743 + endloop + endfacet + facet normal 0.102979 -0.910469 0.400553 + outer loop + vertex 1.20857 0.860377 2.48743 + vertex 1.20654 0.861713 2.49098 + vertex 1.20286 0.860123 2.48832 + endloop + endfacet + facet normal 0.102602 -0.91032 0.400986 + outer loop + vertex 1.20654 0.861713 2.49098 + vertex 1.2023 0.861629 2.49188 + vertex 1.20286 0.860123 2.48832 + endloop + endfacet + facet normal 0.112232 -0.886573 0.448767 + outer loop + vertex 1.20654 0.861713 2.49098 + vertex 1.20479 0.86314 2.49424 + vertex 1.2023 0.861629 2.49188 + endloop + endfacet + facet normal 0.106035 -0.888577 0.446305 + outer loop + vertex 1.20938 0.8635 2.49387 + vertex 1.20479 0.86314 2.49424 + vertex 1.20654 0.861713 2.49098 + endloop + endfacet + facet normal 0.10801 -0.860417 0.498013 + outer loop + vertex 1.20479 0.86314 2.49424 + vertex 1.20938 0.8635 2.49387 + vertex 1.20719 0.864765 2.49653 + endloop + endfacet + facet normal 0.0979905 -0.856926 0.506039 + outer loop + vertex 1.20309 0.864838 2.49744 + vertex 1.20479 0.86314 2.49424 + vertex 1.20719 0.864765 2.49653 + endloop + endfacet + facet normal 0.119533 -0.793168 0.597156 + outer loop + vertex 1.20719 0.864765 2.49653 + vertex 1.20699 0.867082 2.49964 + vertex 1.20309 0.864838 2.49744 + endloop + endfacet + facet normal 0.123281 -0.795665 0.593059 + outer loop + vertex 1.20699 0.867082 2.49964 + vertex 1.20156 0.867079 2.50077 + vertex 1.20309 0.864838 2.49744 + endloop + endfacet + facet normal 0.152054 -0.663938 0.732165 + outer loop + vertex 1.20699 0.867082 2.49964 + vertex 1.2049 0.869984 2.50271 + vertex 1.20156 0.867079 2.50077 + endloop + endfacet + facet normal 0.153712 -0.663142 0.732541 + outer loop + vertex 1.20966 0.870285 2.50199 + vertex 1.2049 0.869984 2.50271 + vertex 1.20699 0.867082 2.49964 + endloop + endfacet + facet normal 0.162059 -0.469013 0.868195 + outer loop + vertex 1.20966 0.870285 2.50199 + vertex 1.20856 0.874109 2.50425 + vertex 1.2049 0.869984 2.50271 + endloop + endfacet + facet normal 0.239818 -0.519859 0.819898 + outer loop + vertex 1.2049 0.869984 2.50271 + vertex 1.20856 0.874109 2.50425 + vertex 1.20344 0.872778 2.50491 + endloop + endfacet + facet normal 0.214518 -0.384031 0.898054 + outer loop + vertex 1.20344 0.872778 2.50491 + vertex 1.20856 0.874109 2.50425 + vertex 1.20586 0.876398 2.50588 + endloop + endfacet + facet normal 0.338262 0.822622 0.457024 + outer loop + vertex 1.21027 0.977514 2.52709 + vertex 1.20917 0.979249 2.52479 + vertex 1.20692 0.979207 2.52653 + endloop + endfacet + facet normal 0.459556 0.625315 0.630705 + outer loop + vertex 1.20692 0.979207 2.52653 + vertex 1.20462 0.978948 2.52845 + vertex 1.20594 0.976693 2.52973 + endloop + endfacet + facet normal 0.255365 0.7214 0.643716 + outer loop + vertex 1.20692 0.979207 2.52653 + vertex 1.20594 0.976693 2.52973 + vertex 1.21027 0.977514 2.52709 + endloop + endfacet + facet normal 0.260012 0.714737 0.649264 + outer loop + vertex 1.21027 0.977514 2.52709 + vertex 1.20594 0.976693 2.52973 + vertex 1.20951 0.975203 2.52994 + endloop + endfacet + facet normal 0.173604 0.445138 0.878472 + outer loop + vertex 1.20664 0.973086 2.53142 + vertex 1.20594 0.976693 2.52973 + vertex 1.20152 0.97352 2.53221 + endloop + endfacet + facet normal 0.131882 0.441312 0.88761 + outer loop + vertex 1.20951 0.975203 2.52994 + vertex 1.20594 0.976693 2.52973 + vertex 1.20664 0.973086 2.53142 + endloop + endfacet + facet normal 0.515321 -0.146172 0.84444 + outer loop + vertex 1.205 0.985 2.51931 + vertex 1.20442 0.982974 2.51931 + vertex 1.20754 0.981248 2.51711 + endloop + endfacet + facet normal 0.641494 0.662033 -0.387553 + outer loop + vertex 1.205 0.985 2.51931 + vertex 1.20754 0.981248 2.51711 + vertex 1.205 0.982477 2.515 + endloop + endfacet + facet normal 0.373955 0.92334 0.0871791 + outer loop + vertex 1.205 0.982477 2.515 + vertex 1.20754 0.981248 2.51711 + vertex 1.21 0.980452 2.515 + endloop + endfacet + facet normal 0.534822 0.838986 0.100337 + outer loop + vertex 1.20748 0.980687 2.52211 + vertex 1.20754 0.981248 2.51711 + vertex 1.20442 0.982974 2.51931 + endloop + endfacet + facet normal 0.509729 0.849466 0.13632 + outer loop + vertex 1.2041 0.982678 2.52234 + vertex 1.20748 0.980687 2.52211 + vertex 1.20442 0.982974 2.51931 + endloop + endfacet + facet normal 0.630301 0.681584 0.371703 + outer loop + vertex 1.2041 0.982678 2.52234 + vertex 1.20264 0.98319 2.5239 + vertex 1.20353 0.981042 2.52632 + endloop + endfacet + facet normal 0.486578 0.780917 0.391677 + outer loop + vertex 1.20748 0.980687 2.52211 + vertex 1.2041 0.982678 2.52234 + vertex 1.20353 0.981042 2.52632 + endloop + endfacet + facet normal 0.432455 0.83668 0.33608 + outer loop + vertex 1.20748 0.980687 2.52211 + vertex 1.20353 0.981042 2.52632 + vertex 1.20692 0.979207 2.52653 + endloop + endfacet + facet normal 0.243274 0.909759 0.336388 + outer loop + vertex 1.20748 0.980687 2.52211 + vertex 1.20692 0.979207 2.52653 + vertex 1.20917 0.979249 2.52479 + endloop + endfacet + facet normal 0.373448 0.750657 0.545023 + outer loop + vertex 1.20692 0.979207 2.52653 + vertex 1.20353 0.981042 2.52632 + vertex 1.20462 0.978948 2.52845 + endloop + endfacet + facet normal -0.238249 0.0693393 0.968726 + outer loop + vertex 1.205 0.985 2.51931 + vertex 1.20168 0.9845 2.51853 + vertex 1.20442 0.982974 2.51931 + endloop + endfacet + facet normal 0.53736 0.832068 0.137504 + outer loop + vertex 1.20442 0.982974 2.51931 + vertex 1.2009 0.984869 2.52161 + vertex 1.2041 0.982678 2.52234 + endloop + endfacet + facet normal 0.482856 0.875513 0.018072 + outer loop + vertex 1.20168 0.9845 2.51853 + vertex 1.2009 0.984869 2.52161 + vertex 1.20442 0.982974 2.51931 + endloop + endfacet + facet normal 0.516855 0.828379 0.215987 + outer loop + vertex 1.2041 0.982678 2.52234 + vertex 1.2009 0.984869 2.52161 + vertex 1.20264 0.98319 2.5239 + endloop + endfacet + facet normal -0.998443 -0.0386772 -0.040186 + outer loop + vertex 1.20512 2.04383 2.51728 + vertex 1.205 2.0442 2.52 + vertex 1.205 2.045 2.51923 + endloop + endfacet + facet normal -0.983901 0.165466 -0.0675255 + outer loop + vertex 1.20473 2.04254 2.51989 + vertex 1.205 2.0442 2.52 + vertex 1.20512 2.04383 2.51728 + endloop + endfacet + facet normal -0.486727 0.134487 -0.863139 + outer loop + vertex 1.20124 2.0409 2.52161 + vertex 1.205 2.0442 2.52 + vertex 1.20473 2.04254 2.51989 + endloop + endfacet + facet normal 0.412691 -0.910463 -0.0272621 + outer loop + vertex 1.20473 2.04254 2.51989 + vertex 1.20368 2.04196 2.52343 + vertex 1.20124 2.0409 2.52161 + endloop + endfacet + facet normal -0.998104 -0.052764 -0.0316834 + outer loop + vertex 1.20512 2.04383 2.51728 + vertex 1.205 2.045 2.51923 + vertex 1.205 2.04754 2.515 + endloop + endfacet + facet normal 0.191842 -0.509149 -0.839026 + outer loop + vertex 1.20512 2.04383 2.51728 + vertex 1.205 2.04754 2.515 + vertex 1.20785 2.04442 2.51754 + endloop + endfacet + facet normal -0.0351238 -0.650706 -0.758517 + outer loop + vertex 1.20785 2.04442 2.51754 + vertex 1.205 2.04754 2.515 + vertex 1.21 2.04727 2.515 + endloop + endfacet + facet normal 0.473836 -0.877434 -0.0747552 + outer loop + vertex 1.20785 2.04442 2.51754 + vertex 1.20687 2.04346 2.52265 + vertex 1.20473 2.04254 2.51989 + endloop + endfacet + facet normal 0.232379 -0.885857 -0.401568 + outer loop + vertex 1.20512 2.04383 2.51728 + vertex 1.20785 2.04442 2.51754 + vertex 1.20473 2.04254 2.51989 + endloop + endfacet + facet normal 0.421346 -0.906581 -0.0240631 + outer loop + vertex 1.20368 2.04196 2.52343 + vertex 1.20473 2.04254 2.51989 + vertex 1.20687 2.04346 2.52265 + endloop + endfacet + facet normal 0.463966 -0.844231 0.268347 + outer loop + vertex 1.20368 2.04196 2.52343 + vertex 1.20687 2.04346 2.52265 + vertex 1.20359 2.04318 2.52745 + endloop + endfacet + facet normal 0.407519 -0.884452 0.227316 + outer loop + vertex 1.20359 2.04318 2.52745 + vertex 1.20687 2.04346 2.52265 + vertex 1.20839 2.04509 2.52629 + endloop + endfacet + facet normal 0.422475 -0.762979 0.489262 + outer loop + vertex 1.20839 2.04509 2.52629 + vertex 1.20595 2.04603 2.52985 + vertex 1.20359 2.04318 2.52745 + endloop + endfacet + facet normal 0.330193 -0.753335 0.568735 + outer loop + vertex 1.20595 2.04603 2.52985 + vertex 1.20247 2.0454 2.53103 + vertex 1.20359 2.04318 2.52745 + endloop + endfacet + facet normal 0.360276 -0.451686 0.816199 + outer loop + vertex 1.20595 2.04603 2.52985 + vertex 1.2038 2.04803 2.5319 + vertex 1.20247 2.0454 2.53103 + endloop + endfacet + facet normal 0.31958 -0.490027 0.811013 + outer loop + vertex 1.20708 2.04825 2.53075 + vertex 1.2038 2.04803 2.5319 + vertex 1.20595 2.04603 2.52985 + endloop + endfacet + facet normal 0.336506 -0.0824323 0.938067 + outer loop + vertex 1.20708 2.04825 2.53075 + vertex 1.20566 2.05125 2.53152 + vertex 1.2038 2.04803 2.5319 + endloop + endfacet + facet normal 0.189299 0.472681 0.860662 + outer loop + vertex 1.20748 2.15214 2.50356 + vertex 1.20704 2.15513 2.50202 + vertex 1.20328 2.15253 2.50428 + endloop + endfacet + facet normal 0.171386 0.492275 0.8534 + outer loop + vertex 1.20328 2.15253 2.50428 + vertex 1.20704 2.15513 2.50202 + vertex 1.20238 2.15642 2.50221 + endloop + endfacet + facet normal 0.147807 0.844674 0.51447 + outer loop + vertex 1.20875 2.15991 2.49719 + vertex 1.20757 2.16151 2.49488 + vertex 1.20531 2.16072 2.49684 + endloop + endfacet + facet normal 0.12619 0.785227 0.606214 + outer loop + vertex 1.20531 2.16072 2.49684 + vertex 1.20138 2.16075 2.49762 + vertex 1.20481 2.15864 2.49963 + endloop + endfacet + facet normal 0.124568 0.785532 0.606153 + outer loop + vertex 1.20531 2.16072 2.49684 + vertex 1.20481 2.15864 2.49963 + vertex 1.20875 2.15991 2.49719 + endloop + endfacet + facet normal 0.164822 0.742831 0.648873 + outer loop + vertex 1.20875 2.15991 2.49719 + vertex 1.20481 2.15864 2.49963 + vertex 1.20965 2.15762 2.49958 + endloop + endfacet + facet normal 0.206663 0.63661 0.742979 + outer loop + vertex 1.20704 2.15513 2.50202 + vertex 1.20481 2.15864 2.49963 + vertex 1.20238 2.15642 2.50221 + endloop + endfacet + facet normal 0.139362 0.615977 0.775339 + outer loop + vertex 1.20965 2.15762 2.49958 + vertex 1.20481 2.15864 2.49963 + vertex 1.20704 2.15513 2.50202 + endloop + endfacet + facet normal 0.2 0.823688 0.530602 + outer loop + vertex 1.20496 2.16557 2.48782 + vertex 1.21035 2.16471 2.48713 + vertex 1.20713 2.16691 2.48493 + endloop + endfacet + facet normal 0.256472 0.789739 0.557256 + outer loop + vertex 1.20204 2.16792 2.48584 + vertex 1.20496 2.16557 2.48782 + vertex 1.20713 2.16691 2.48493 + endloop + endfacet + facet normal 0.196639 0.877306 0.437798 + outer loop + vertex 1.21035 2.16471 2.48713 + vertex 1.20496 2.16557 2.48782 + vertex 1.208 2.16313 2.49134 + endloop + endfacet + facet normal 0.210728 0.879337 0.427037 + outer loop + vertex 1.208 2.16313 2.49134 + vertex 1.20496 2.16557 2.48782 + vertex 1.20305 2.16467 2.49062 + endloop + endfacet + facet normal 0.106384 0.872108 0.477608 + outer loop + vertex 1.20757 2.16151 2.49488 + vertex 1.20345 2.16249 2.49403 + vertex 1.20531 2.16072 2.49684 + endloop + endfacet + facet normal 0.123446 0.89716 0.424105 + outer loop + vertex 1.20757 2.16151 2.49488 + vertex 1.208 2.16313 2.49134 + vertex 1.20345 2.16249 2.49403 + endloop + endfacet + facet normal 0.184885 0.837477 0.514247 + outer loop + vertex 1.208 2.16313 2.49134 + vertex 1.20305 2.16467 2.49062 + vertex 1.20345 2.16249 2.49403 + endloop + endfacet + facet normal 0.101952 0.871304 0.480036 + outer loop + vertex 1.20531 2.16072 2.49684 + vertex 1.20345 2.16249 2.49403 + vertex 1.20138 2.16075 2.49762 + endloop + endfacet + facet normal 0.193853 0.0968636 0.976237 + outer loop + vertex 1.20713 2.16691 2.48493 + vertex 1.205 2.17045 2.485 + vertex 1.20204 2.16792 2.48584 + endloop + endfacet + facet normal -0.00104289 -0.0208692 0.999782 + outer loop + vertex 1.21 2.1702 2.485 + vertex 1.205 2.17045 2.485 + vertex 1.20713 2.16691 2.48493 + endloop + endfacet + facet normal -0.0326778 0.678014 0.734322 + outer loop + vertex 1.215 0.859346 2.485 + vertex 1.21098 0.859426 2.48475 + vertex 1.21 0.859105 2.485 + endloop + endfacet + facet normal -0.00480527 0.928835 0.370463 + outer loop + vertex 1.2151 0.85966 2.48421 + vertex 1.21098 0.859426 2.48475 + vertex 1.215 0.859346 2.485 + endloop + endfacet + facet normal 0.108574 -0.886903 0.449016 + outer loop + vertex 1.21098 0.859426 2.48475 + vertex 1.2151 0.85966 2.48421 + vertex 1.21424 0.860645 2.48637 + endloop + endfacet + facet normal 0.122093 -0.89539 0.428217 + outer loop + vertex 1.20857 0.860377 2.48743 + vertex 1.21098 0.859426 2.48475 + vertex 1.21424 0.860645 2.48637 + endloop + endfacet + facet normal 0.117734 -0.908227 0.401574 + outer loop + vertex 1.21424 0.860645 2.48637 + vertex 1.21167 0.862057 2.49032 + vertex 1.20857 0.860377 2.48743 + endloop + endfacet + facet normal 0.113616 -0.907084 0.405327 + outer loop + vertex 1.21167 0.862057 2.49032 + vertex 1.20654 0.861713 2.49098 + vertex 1.20857 0.860377 2.48743 + endloop + endfacet + facet normal 0.116766 -0.891549 0.437614 + outer loop + vertex 1.21167 0.862057 2.49032 + vertex 1.20938 0.8635 2.49387 + vertex 1.20654 0.861713 2.49098 + endloop + endfacet + facet normal 0.118693 -0.890827 0.438564 + outer loop + vertex 1.21437 0.863974 2.49348 + vertex 1.20938 0.8635 2.49387 + vertex 1.21167 0.862057 2.49032 + endloop + endfacet + facet normal 0.120569 -0.850962 0.511201 + outer loop + vertex 1.20938 0.8635 2.49387 + vertex 1.21437 0.863974 2.49348 + vertex 1.21163 0.865793 2.49715 + endloop + endfacet + facet normal 0.125576 -0.851901 0.508424 + outer loop + vertex 1.20719 0.864765 2.49653 + vertex 1.20938 0.8635 2.49387 + vertex 1.21163 0.865793 2.49715 + endloop + endfacet + facet normal 0.146029 -0.771488 0.619259 + outer loop + vertex 1.21113 0.86803 2.50006 + vertex 1.21163 0.865793 2.49715 + vertex 1.2148 0.868087 2.49926 + endloop + endfacet + facet normal 0.116255 -0.77712 0.618522 + outer loop + vertex 1.21113 0.86803 2.50006 + vertex 1.20699 0.867082 2.49964 + vertex 1.21163 0.865793 2.49715 + endloop + endfacet + facet normal 0.0999435 -0.795493 0.597663 + outer loop + vertex 1.20699 0.867082 2.49964 + vertex 1.20719 0.864765 2.49653 + vertex 1.21163 0.865793 2.49715 + endloop + endfacet + facet normal 0.0650877 -0.623515 0.779098 + outer loop + vertex 1.21113 0.86803 2.50006 + vertex 1.20966 0.870285 2.50199 + vertex 1.20699 0.867082 2.49964 + endloop + endfacet + facet normal 0.172512 -0.636798 0.751483 + outer loop + vertex 1.2148 0.868087 2.49926 + vertex 1.21308 0.869983 2.50126 + vertex 1.21113 0.86803 2.50006 + endloop + endfacet + facet normal 0.113165 -0.601812 0.790579 + outer loop + vertex 1.21308 0.869983 2.50126 + vertex 1.20966 0.870285 2.50199 + vertex 1.21113 0.86803 2.50006 + endloop + endfacet + facet normal 0.149593 -0.428333 0.891153 + outer loop + vertex 1.21308 0.869983 2.50126 + vertex 1.21399 0.873769 2.50293 + vertex 1.20966 0.870285 2.50199 + endloop + endfacet + facet normal 0.182416 -0.462783 0.8675 + outer loop + vertex 1.21399 0.873769 2.50293 + vertex 1.20856 0.874109 2.50425 + vertex 1.20966 0.870285 2.50199 + endloop + endfacet + facet normal 0.0985408 0.478204 0.872703 + outer loop + vertex 1.215 0.979456 2.515 + vertex 1.21236 0.98 2.515 + vertex 1.21421 0.978818 2.51544 + endloop + endfacet + facet normal 0.280242 0.869751 0.4062 + outer loop + vertex 1.21027 0.977514 2.52709 + vertex 1.21459 0.977079 2.52505 + vertex 1.21141 0.978907 2.52332 + endloop + endfacet + facet normal 0.399247 0.814127 0.421663 + outer loop + vertex 1.20917 0.979249 2.52479 + vertex 1.21027 0.977514 2.52709 + vertex 1.21141 0.978907 2.52332 + endloop + endfacet + facet normal 0.34511 0.746191 0.569296 + outer loop + vertex 1.21459 0.977079 2.52505 + vertex 1.21027 0.977514 2.52709 + vertex 1.21355 0.974728 2.52875 + endloop + endfacet + facet normal 0.27399 0.709786 0.648948 + outer loop + vertex 1.21355 0.974728 2.52875 + vertex 1.21027 0.977514 2.52709 + vertex 1.20951 0.975203 2.52994 + endloop + endfacet + facet normal 0.134836 0.438106 0.888753 + outer loop + vertex 1.21068 0.972879 2.53091 + vertex 1.20951 0.975203 2.52994 + vertex 1.20664 0.973086 2.53142 + endloop + endfacet + facet normal 0.298111 0.490721 0.818733 + outer loop + vertex 1.21355 0.974728 2.52875 + vertex 1.20951 0.975203 2.52994 + vertex 1.21068 0.972879 2.53091 + endloop + endfacet + facet normal 0.133929 0.6993 -0.70217 + outer loop + vertex 1.21 0.98 2.51455 + vertex 1.21 0.980452 2.515 + vertex 1.21236 0.98 2.515 + endloop + endfacet + facet normal 0.293758 0.70094 0.649914 + outer loop + vertex 1.21236 0.98 2.515 + vertex 1.21145 0.979556 2.51589 + vertex 1.21421 0.978818 2.51544 + endloop + endfacet + facet normal 0.155411 0.811466 0.563357 + outer loop + vertex 1.21236 0.98 2.515 + vertex 1.21 0.980452 2.515 + vertex 1.21145 0.979556 2.51589 + endloop + endfacet + facet normal 0.437261 0.88182 0.176627 + outer loop + vertex 1.21 0.980452 2.515 + vertex 1.20754 0.981248 2.51711 + vertex 1.21145 0.979556 2.51589 + endloop + endfacet + facet normal 0.400609 0.916179 0.011291 + outer loop + vertex 1.21145 0.979556 2.51589 + vertex 1.20754 0.981248 2.51711 + vertex 1.21131 0.979573 2.51938 + endloop + endfacet + facet normal 0.348574 0.93098 0.108498 + outer loop + vertex 1.21131 0.979573 2.51938 + vertex 1.20754 0.981248 2.51711 + vertex 1.20748 0.980687 2.52211 + endloop + endfacet + facet normal 0.322375 0.903314 0.283015 + outer loop + vertex 1.21141 0.978907 2.52332 + vertex 1.20748 0.980687 2.52211 + vertex 1.20917 0.979249 2.52479 + endloop + endfacet + facet normal 0.371036 0.917138 0.145568 + outer loop + vertex 1.21131 0.979573 2.51938 + vertex 1.20748 0.980687 2.52211 + vertex 1.21141 0.978907 2.52332 + endloop + endfacet + facet normal 0.134406 -0.533337 -0.835156 + outer loop + vertex 1.215 2.04853 2.515 + vertex 1.21172 2.04575 2.51625 + vertex 1.21 2.04727 2.515 + endloop + endfacet + facet normal -0.0292531 -0.653343 -0.756497 + outer loop + vertex 1.21172 2.04575 2.51625 + vertex 1.20785 2.04442 2.51754 + vertex 1.21 2.04727 2.515 + endloop + endfacet + facet normal 0.295184 -0.951105 -0.0909179 + outer loop + vertex 1.21172 2.04575 2.51625 + vertex 1.21175 2.0453 2.52103 + vertex 1.20785 2.04442 2.51754 + endloop + endfacet + facet normal 0.316143 -0.941493 -0.116814 + outer loop + vertex 1.21175 2.0453 2.52103 + vertex 1.20687 2.04346 2.52265 + vertex 1.20785 2.04442 2.51754 + endloop + endfacet + facet normal 0.230635 -0.929432 0.288033 + outer loop + vertex 1.21164 2.04686 2.52614 + vertex 1.21175 2.0453 2.52103 + vertex 1.2148 2.04681 2.52346 + endloop + endfacet + facet normal 0.468627 -0.842192 0.266648 + outer loop + vertex 1.21164 2.04686 2.52614 + vertex 1.20839 2.04509 2.52629 + vertex 1.21175 2.0453 2.52103 + endloop + endfacet + facet normal 0.408683 -0.884082 0.226666 + outer loop + vertex 1.20839 2.04509 2.52629 + vertex 1.20687 2.04346 2.52265 + vertex 1.21175 2.0453 2.52103 + endloop + endfacet + facet normal 0.434838 -0.761752 0.48026 + outer loop + vertex 1.20886 2.04699 2.52886 + vertex 1.20839 2.04509 2.52629 + vertex 1.21164 2.04686 2.52614 + endloop + endfacet + facet normal 0.417925 -0.766826 0.487152 + outer loop + vertex 1.20595 2.04603 2.52985 + vertex 1.20839 2.04509 2.52629 + vertex 1.20886 2.04699 2.52886 + endloop + endfacet + facet normal 0.422609 -0.515801 0.745219 + outer loop + vertex 1.20886 2.04699 2.52886 + vertex 1.20708 2.04825 2.53075 + vertex 1.20595 2.04603 2.52985 + endloop + endfacet + facet normal 0.44561 -0.715619 0.537886 + outer loop + vertex 1.2148 2.04681 2.52346 + vertex 1.21465 2.04892 2.52638 + vertex 1.21164 2.04686 2.52614 + endloop + endfacet + facet normal 0.481469 -0.314259 0.818186 + outer loop + vertex 1.21465 2.04892 2.52638 + vertex 1.21385 2.05332 2.52854 + vertex 1.21019 2.04965 2.52929 + endloop + endfacet + facet normal 0.359613 -0.609762 0.706306 + outer loop + vertex 1.21465 2.04892 2.52638 + vertex 1.21019 2.04965 2.52929 + vertex 1.21164 2.04686 2.52614 + endloop + endfacet + facet normal 0.625843 -0.417882 0.658555 + outer loop + vertex 1.21164 2.04686 2.52614 + vertex 1.21019 2.04965 2.52929 + vertex 1.20886 2.04699 2.52886 + endloop + endfacet + facet normal 0.527599 -0.385217 0.757131 + outer loop + vertex 1.21019 2.04965 2.52929 + vertex 1.20708 2.04825 2.53075 + vertex 1.20886 2.04699 2.52886 + endloop + endfacet + facet normal 0.433283 -0.0272334 0.900846 + outer loop + vertex 1.20566 2.05125 2.53152 + vertex 1.20708 2.04825 2.53075 + vertex 1.21019 2.04965 2.52929 + endloop + endfacet + facet normal 0.22894 0.546482 0.80557 + outer loop + vertex 1.21476 2.15394 2.50098 + vertex 1.21329 2.15656 2.49961 + vertex 1.21107 2.15528 2.50112 + endloop + endfacet + facet normal 0.194838 0.444999 0.874079 + outer loop + vertex 1.21107 2.15528 2.50112 + vertex 1.21126 2.152 2.50274 + vertex 1.21476 2.15394 2.50098 + endloop + endfacet + facet normal 0.18074 0.445537 0.87683 + outer loop + vertex 1.21107 2.15528 2.50112 + vertex 1.20704 2.15513 2.50202 + vertex 1.21126 2.152 2.50274 + endloop + endfacet + facet normal 0.204606 0.473052 0.856947 + outer loop + vertex 1.20704 2.15513 2.50202 + vertex 1.20748 2.15214 2.50356 + vertex 1.21126 2.152 2.50274 + endloop + endfacet + facet normal 0.187618 0.826112 0.531355 + outer loop + vertex 1.20875 2.15991 2.49719 + vertex 1.21376 2.15888 2.49702 + vertex 1.21137 2.16125 2.49417 + endloop + endfacet + facet normal 0.154824 0.845319 0.511337 + outer loop + vertex 1.20757 2.16151 2.49488 + vertex 1.20875 2.15991 2.49719 + vertex 1.21137 2.16125 2.49417 + endloop + endfacet + facet normal 0.169594 0.611009 0.773244 + outer loop + vertex 1.21329 2.15656 2.49961 + vertex 1.20965 2.15762 2.49958 + vertex 1.21107 2.15528 2.50112 + endloop + endfacet + facet normal 0.200197 0.712884 0.6721 + outer loop + vertex 1.21329 2.15656 2.49961 + vertex 1.21376 2.15888 2.49702 + vertex 1.20965 2.15762 2.49958 + endloop + endfacet + facet normal 0.174448 0.74337 0.645732 + outer loop + vertex 1.21376 2.15888 2.49702 + vertex 1.20875 2.15991 2.49719 + vertex 1.20965 2.15762 2.49958 + endloop + endfacet + facet normal 0.153536 0.606072 0.780451 + outer loop + vertex 1.21107 2.15528 2.50112 + vertex 1.20965 2.15762 2.49958 + vertex 1.20704 2.15513 2.50202 + endloop + endfacet + facet normal 0.0530377 0.737962 0.672755 + outer loop + vertex 1.21035 2.16471 2.48713 + vertex 1.21554 2.1653 2.48607 + vertex 1.21218 2.1671 2.48436 + endloop + endfacet + facet normal 0.04701 0.740211 0.670729 + outer loop + vertex 1.20713 2.16691 2.48493 + vertex 1.21035 2.16471 2.48713 + vertex 1.21218 2.1671 2.48436 + endloop + endfacet + facet normal 0.00325432 0.865099 0.50159 + outer loop + vertex 1.21554 2.1653 2.48607 + vertex 1.21035 2.16471 2.48713 + vertex 1.21341 2.16287 2.49028 + endloop + endfacet + facet normal 0.123923 0.904744 0.407532 + outer loop + vertex 1.21341 2.16287 2.49028 + vertex 1.21035 2.16471 2.48713 + vertex 1.208 2.16313 2.49134 + endloop + endfacet + facet normal 0.14201 0.894019 0.424927 + outer loop + vertex 1.21137 2.16125 2.49417 + vertex 1.208 2.16313 2.49134 + vertex 1.20757 2.16151 2.49488 + endloop + endfacet + facet normal 0.12908 0.889868 0.437577 + outer loop + vertex 1.21341 2.16287 2.49028 + vertex 1.208 2.16313 2.49134 + vertex 1.21137 2.16125 2.49417 + endloop + endfacet + facet normal 0.116226 -0.122623 0.985624 + outer loop + vertex 1.21218 2.1671 2.48436 + vertex 1.21 2.1702 2.485 + vertex 1.20713 2.16691 2.48493 + endloop + endfacet + facet normal 0.00439554 -0.199959 0.979794 + outer loop + vertex 1.215 2.17031 2.485 + vertex 1.21 2.1702 2.485 + vertex 1.21218 2.1671 2.48436 + endloop + endfacet + facet normal -0.556081 -0.810471 0.18415 + outer loop + vertex 1.21899 0.86 2.48 + vertex 1.22 0.859307 2.48 + vertex 1.22 0.86 2.48305 + endloop + endfacet + facet normal 0.179046 -0.813041 -0.553992 + outer loop + vertex 1.215 0.86 2.48404 + vertex 1.21797 0.86 2.485 + vertex 1.215 0.859346 2.485 + endloop + endfacet + facet normal -0.202237 0.91835 0.340195 + outer loop + vertex 1.21797 0.86 2.485 + vertex 1.2151 0.85966 2.48421 + vertex 1.215 0.859346 2.485 + endloop + endfacet + facet normal -0.230475 0.850711 0.472411 + outer loop + vertex 1.2151 0.85966 2.48421 + vertex 1.21797 0.86 2.485 + vertex 1.22 0.86055 2.485 + endloop + endfacet + facet normal 0.0907547 -0.891435 0.443968 + outer loop + vertex 1.2151 0.85966 2.48421 + vertex 1.22 0.86055 2.485 + vertex 1.21424 0.860645 2.48637 + endloop + endfacet + facet normal 0.120561 -0.816772 0.564223 + outer loop + vertex 1.21424 0.860645 2.48637 + vertex 1.22 0.86055 2.485 + vertex 1.21795 0.861252 2.48645 + endloop + endfacet + facet normal 0.139006 -0.905907 0.400012 + outer loop + vertex 1.21795 0.861252 2.48645 + vertex 1.217 0.862471 2.48955 + vertex 1.21424 0.860645 2.48637 + endloop + endfacet + facet normal 0.129121 -0.90403 0.407502 + outer loop + vertex 1.217 0.862471 2.48955 + vertex 1.21167 0.862057 2.49032 + vertex 1.21424 0.860645 2.48637 + endloop + endfacet + facet normal 0.131463 -0.893537 0.429312 + outer loop + vertex 1.217 0.862471 2.48955 + vertex 1.21437 0.863974 2.49348 + vertex 1.21167 0.862057 2.49032 + endloop + endfacet + facet normal 0.121472 -0.897426 0.424113 + outer loop + vertex 1.21861 0.864232 2.49281 + vertex 1.21437 0.863974 2.49348 + vertex 1.217 0.862471 2.48955 + endloop + endfacet + facet normal 0.133035 -0.845128 0.517746 + outer loop + vertex 1.21437 0.863974 2.49348 + vertex 1.21861 0.864232 2.49281 + vertex 1.21765 0.866103 2.49611 + endloop + endfacet + facet normal 0.133115 -0.84516 0.517672 + outer loop + vertex 1.21163 0.865793 2.49715 + vertex 1.21437 0.863974 2.49348 + vertex 1.21765 0.866103 2.49611 + endloop + endfacet + facet normal 0.146816 -0.771916 0.61854 + outer loop + vertex 1.21765 0.866103 2.49611 + vertex 1.2148 0.868087 2.49926 + vertex 1.21163 0.865793 2.49715 + endloop + endfacet + facet normal 0.197245 -0.739473 0.643641 + outer loop + vertex 1.21933 0.8689 2.49881 + vertex 1.2148 0.868087 2.49926 + vertex 1.21765 0.866103 2.49611 + endloop + endfacet + facet normal 0.185039 -0.594416 0.78258 + outer loop + vertex 1.2148 0.868087 2.49926 + vertex 1.21933 0.8689 2.49881 + vertex 1.21671 0.871003 2.50103 + endloop + endfacet + facet normal 0.220503 -0.606396 0.763978 + outer loop + vertex 1.21308 0.869983 2.50126 + vertex 1.2148 0.868087 2.49926 + vertex 1.21671 0.871003 2.50103 + endloop + endfacet + facet normal 0.179511 -0.432261 0.8837 + outer loop + vertex 1.21671 0.871003 2.50103 + vertex 1.21399 0.873769 2.50293 + vertex 1.21308 0.869983 2.50126 + endloop + endfacet + facet normal 0.197558 -0.416935 0.887207 + outer loop + vertex 1.21932 0.874832 2.50225 + vertex 1.21399 0.873769 2.50293 + vertex 1.21671 0.871003 2.50103 + endloop + endfacet + facet normal 0.409253 -0.0698175 0.909746 + outer loop + vertex 1.21338 0.97198 2.53033 + vertex 1.21138 0.970586 2.53112 + vertex 1.21326 0.968515 2.53012 + endloop + endfacet + facet normal 0.380673 -0.069588 0.922087 + outer loop + vertex 1.21338 0.97198 2.53033 + vertex 1.21326 0.968515 2.53012 + vertex 1.21663 0.971802 2.52898 + endloop + endfacet + facet normal 0.290868 0.0344716 0.956142 + outer loop + vertex 1.21663 0.971802 2.52898 + vertex 1.21326 0.968515 2.53012 + vertex 1.21778 0.967931 2.52877 + endloop + endfacet + facet normal 0.258847 0.168411 0.951124 + outer loop + vertex 1.21338 0.97198 2.53033 + vertex 1.21068 0.972879 2.53091 + vertex 1.21138 0.970586 2.53112 + endloop + endfacet + facet normal 0.203978 0.976948 0.0629685 + outer loop + vertex 1.21421 0.978818 2.51544 + vertex 1.21475 0.978524 2.51824 + vertex 1.21821 0.977881 2.51701 + endloop + endfacet + facet normal -0.131265 0.666973 0.733428 + outer loop + vertex 1.21421 0.978818 2.51544 + vertex 1.21821 0.977881 2.51701 + vertex 1.215 0.979456 2.515 + endloop + endfacet + facet normal 0.0053832 0.79085 0.611986 + outer loop + vertex 1.215 0.979456 2.515 + vertex 1.21821 0.977881 2.51701 + vertex 1.22 0.979422 2.515 + endloop + endfacet + facet normal 0.241843 0.953236 0.181256 + outer loop + vertex 1.21827 0.976926 2.52195 + vertex 1.21821 0.977881 2.51701 + vertex 1.21475 0.978524 2.51824 + endloop + endfacet + facet normal 0.332424 0.938912 0.0891043 + outer loop + vertex 1.21432 0.978358 2.52158 + vertex 1.21827 0.976926 2.52195 + vertex 1.21475 0.978524 2.51824 + endloop + endfacet + facet normal 0.347357 0.887923 0.301555 + outer loop + vertex 1.21432 0.978358 2.52158 + vertex 1.21141 0.978907 2.52332 + vertex 1.21459 0.977079 2.52505 + endloop + endfacet + facet normal 0.298419 0.902471 0.310631 + outer loop + vertex 1.21432 0.978358 2.52158 + vertex 1.21459 0.977079 2.52505 + vertex 1.21827 0.976926 2.52195 + endloop + endfacet + facet normal 0.385248 0.822726 0.417979 + outer loop + vertex 1.21827 0.976926 2.52195 + vertex 1.21459 0.977079 2.52505 + vertex 1.21833 0.974641 2.52639 + endloop + endfacet + facet normal 0.365168 0.446281 0.816998 + outer loop + vertex 1.21663 0.971802 2.52898 + vertex 1.21355 0.974728 2.52875 + vertex 1.21338 0.97198 2.53033 + endloop + endfacet + facet normal 0.396285 0.476552 0.784766 + outer loop + vertex 1.21663 0.971802 2.52898 + vertex 1.21833 0.974641 2.52639 + vertex 1.21355 0.974728 2.52875 + endloop + endfacet + facet normal 0.295029 0.767651 0.56892 + outer loop + vertex 1.21833 0.974641 2.52639 + vertex 1.21459 0.977079 2.52505 + vertex 1.21355 0.974728 2.52875 + endloop + endfacet + facet normal 0.328003 0.454945 0.827913 + outer loop + vertex 1.21338 0.97198 2.53033 + vertex 1.21355 0.974728 2.52875 + vertex 1.21068 0.972879 2.53091 + endloop + endfacet + facet normal 0.265349 0.962874 0.0496395 + outer loop + vertex 1.21421 0.978818 2.51544 + vertex 1.21145 0.979556 2.51589 + vertex 1.21475 0.978524 2.51824 + endloop + endfacet + facet normal 0.316734 0.944481 0.0873754 + outer loop + vertex 1.21475 0.978524 2.51824 + vertex 1.21131 0.979573 2.51938 + vertex 1.21432 0.978358 2.52158 + endloop + endfacet + facet normal 0.293595 0.955905 0.0068851 + outer loop + vertex 1.21145 0.979556 2.51589 + vertex 1.21131 0.979573 2.51938 + vertex 1.21475 0.978524 2.51824 + endloop + endfacet + facet normal 0.270711 0.95032 0.153647 + outer loop + vertex 1.21432 0.978358 2.52158 + vertex 1.21131 0.979573 2.51938 + vertex 1.21141 0.978907 2.52332 + endloop + endfacet + facet normal -0.14619 0.479611 -0.865218 + outer loop + vertex 1.215 2.04853 2.515 + vertex 1.22 2.05 2.51497 + vertex 1.21741 2.04774 2.51415 + endloop + endfacet + facet normal 0.191635 -0.666606 -0.720356 + outer loop + vertex 1.215 2.05 2.51364 + vertex 1.22 2.05 2.51497 + vertex 1.215 2.04853 2.515 + endloop + endfacet + facet normal -0.433675 -0.607224 -0.665737 + outer loop + vertex 1.21741 2.04774 2.51415 + vertex 1.21553 2.04641 2.51659 + vertex 1.215 2.04853 2.515 + endloop + endfacet + facet normal 0.170989 -0.564209 -0.807732 + outer loop + vertex 1.21553 2.04641 2.51659 + vertex 1.21172 2.04575 2.51625 + vertex 1.215 2.04853 2.515 + endloop + endfacet + facet normal 0.207188 -0.977612 -0.0367111 + outer loop + vertex 1.21609 2.04639 2.52036 + vertex 1.21553 2.04641 2.51659 + vertex 1.2187 2.04701 2.51845 + endloop + endfacet + facet normal 0.236194 -0.970839 -0.0410329 + outer loop + vertex 1.21609 2.04639 2.52036 + vertex 1.21175 2.0453 2.52103 + vertex 1.21553 2.04641 2.51659 + endloop + endfacet + facet normal 0.178025 -0.979643 -0.0927721 + outer loop + vertex 1.21175 2.0453 2.52103 + vertex 1.21172 2.04575 2.51625 + vertex 1.21553 2.04641 2.51659 + endloop + endfacet + facet normal 0.269687 -0.932366 0.240755 + outer loop + vertex 1.21609 2.04639 2.52036 + vertex 1.2148 2.04681 2.52346 + vertex 1.21175 2.0453 2.52103 + endloop + endfacet + facet normal 0.364791 -0.909393 0.199831 + outer loop + vertex 1.2187 2.04701 2.51845 + vertex 1.21901 2.0481 2.52283 + vertex 1.21609 2.04639 2.52036 + endloop + endfacet + facet normal 0.317502 -0.912494 0.257967 + outer loop + vertex 1.2148 2.04681 2.52346 + vertex 1.21609 2.04639 2.52036 + vertex 1.21901 2.0481 2.52283 + endloop + endfacet + facet normal 0.316979 -0.762055 0.56462 + outer loop + vertex 1.2148 2.04681 2.52346 + vertex 1.21901 2.0481 2.52283 + vertex 1.21465 2.04892 2.52638 + endloop + endfacet + facet normal 0.345384 -0.728372 0.591763 + outer loop + vertex 1.21465 2.04892 2.52638 + vertex 1.21901 2.0481 2.52283 + vertex 1.21786 2.05047 2.52643 + endloop + endfacet + facet normal 0.184529 -0.405721 0.895176 + outer loop + vertex 1.21786 2.05047 2.52643 + vertex 1.21385 2.05332 2.52854 + vertex 1.21465 2.04892 2.52638 + endloop + endfacet + facet normal 0.132185 -0.464704 0.875544 + outer loop + vertex 1.21961 2.05296 2.52748 + vertex 1.21385 2.05332 2.52854 + vertex 1.21786 2.05047 2.52643 + endloop + endfacet + facet normal 0.228803 0.540623 0.809553 + outer loop + vertex 1.21476 2.15394 2.50098 + vertex 1.21872 2.15271 2.50067 + vertex 1.21791 2.15588 2.49879 + endloop + endfacet + facet normal 0.224677 0.54517 0.807657 + outer loop + vertex 1.21329 2.15656 2.49961 + vertex 1.21476 2.15394 2.50098 + vertex 1.21791 2.15588 2.49879 + endloop + endfacet + facet normal 0.221271 0.407963 0.885779 + outer loop + vertex 1.21683 2.14994 2.5023 + vertex 1.21476 2.15394 2.50098 + vertex 1.21126 2.152 2.50274 + endloop + endfacet + facet normal 0.190939 0.396311 0.898042 + outer loop + vertex 1.21872 2.15271 2.50067 + vertex 1.21476 2.15394 2.50098 + vertex 1.21683 2.14994 2.5023 + endloop + endfacet + facet normal 0.156642 0.820726 0.549428 + outer loop + vertex 1.21376 2.15888 2.49702 + vertex 1.21983 2.15873 2.4955 + vertex 1.21614 2.16091 2.4933 + endloop + endfacet + facet normal 0.158807 0.819745 0.550271 + outer loop + vertex 1.21137 2.16125 2.49417 + vertex 1.21376 2.15888 2.49702 + vertex 1.21614 2.16091 2.4933 + endloop + endfacet + facet normal 0.224007 0.706776 0.671036 + outer loop + vertex 1.21791 2.15588 2.49879 + vertex 1.21376 2.15888 2.49702 + vertex 1.21329 2.15656 2.49961 + endloop + endfacet + facet normal 0.192277 0.682781 0.704869 + outer loop + vertex 1.21983 2.15873 2.4955 + vertex 1.21376 2.15888 2.49702 + vertex 1.21791 2.15588 2.49879 + endloop + endfacet + facet normal -0.320253 0.265273 0.909433 + outer loop + vertex 1.2164 2.17 2.485 + vertex 1.21218 2.1671 2.48436 + vertex 1.21554 2.1653 2.48607 + endloop + endfacet + facet normal 0.0489998 0.212485 0.975935 + outer loop + vertex 1.2164 2.17 2.485 + vertex 1.21554 2.1653 2.48607 + vertex 1.22 2.16917 2.485 + endloop + endfacet + facet normal 0.0263447 0.237298 0.97108 + outer loop + vertex 1.22 2.16917 2.485 + vertex 1.21554 2.1653 2.48607 + vertex 1.21865 2.16473 2.48612 + endloop + endfacet + facet normal 0.140017 0.820752 0.553861 + outer loop + vertex 1.21865 2.16473 2.48612 + vertex 1.21554 2.1653 2.48607 + vertex 1.21823 2.16268 2.48927 + endloop + endfacet + facet normal 0.147059 0.822527 0.549385 + outer loop + vertex 1.21823 2.16268 2.48927 + vertex 1.21554 2.1653 2.48607 + vertex 1.21341 2.16287 2.49028 + endloop + endfacet + facet normal 0.143802 0.884812 0.443203 + outer loop + vertex 1.21614 2.16091 2.4933 + vertex 1.21341 2.16287 2.49028 + vertex 1.21137 2.16125 2.49417 + endloop + endfacet + facet normal 0.129208 0.881473 0.454215 + outer loop + vertex 1.21823 2.16268 2.48927 + vertex 1.21341 2.16287 2.49028 + vertex 1.21614 2.16091 2.4933 + endloop + endfacet + facet normal 0.215547 0.973608 0.0750112 + outer loop + vertex 1.21814 2.17 2.48 + vertex 1.215 2.17031 2.485 + vertex 1.2164 2.17 2.485 + endloop + endfacet + facet normal 0.316669 0.93804 0.140722 + outer loop + vertex 1.215 2.17106 2.48 + vertex 1.215 2.17031 2.485 + vertex 1.21814 2.17 2.48 + endloop + endfacet + facet normal -0.0365474 -0.165082 0.985602 + outer loop + vertex 1.2164 2.17 2.485 + vertex 1.215 2.17031 2.485 + vertex 1.21218 2.1671 2.48436 + endloop + endfacet + facet normal 0.186503 -0.958036 0.217679 + outer loop + vertex 1.22356 0.86 2.48 + vertex 1.22 0.86 2.48305 + vertex 1.22 0.859307 2.48 + endloop + endfacet + facet normal 0.224035 -0.835931 0.501026 + outer loop + vertex 1.225 0.86189 2.485 + vertex 1.22141 0.862022 2.48682 + vertex 1.22 0.86055 2.485 + endloop + endfacet + facet normal 0.121086 -0.81633 0.564751 + outer loop + vertex 1.22141 0.862022 2.48682 + vertex 1.21795 0.861252 2.48645 + vertex 1.22 0.86055 2.485 + endloop + endfacet + facet normal 0.146735 -0.911427 0.384407 + outer loop + vertex 1.22093 0.863495 2.4905 + vertex 1.22141 0.862022 2.48682 + vertex 1.22473 0.86365 2.48942 + endloop + endfacet + facet normal 0.14407 -0.911916 0.384256 + outer loop + vertex 1.22093 0.863495 2.4905 + vertex 1.217 0.862471 2.48955 + vertex 1.22141 0.862022 2.48682 + endloop + endfacet + facet normal 0.157187 -0.901256 0.403771 + outer loop + vertex 1.217 0.862471 2.48955 + vertex 1.21795 0.861252 2.48645 + vertex 1.22141 0.862022 2.48682 + endloop + endfacet + facet normal 0.131962 -0.898187 0.419341 + outer loop + vertex 1.22093 0.863495 2.4905 + vertex 1.21861 0.864232 2.49281 + vertex 1.217 0.862471 2.48955 + endloop + endfacet + facet normal 0.163881 -0.878245 0.449253 + outer loop + vertex 1.22473 0.86365 2.48942 + vertex 1.22271 0.865277 2.49334 + vertex 1.22093 0.863495 2.4905 + endloop + endfacet + facet normal 0.16651 -0.878508 0.44777 + outer loop + vertex 1.21861 0.864232 2.49281 + vertex 1.22093 0.863495 2.4905 + vertex 1.22271 0.865277 2.49334 + endloop + endfacet + facet normal 0.147787 -0.841346 0.5199 + outer loop + vertex 1.21861 0.864232 2.49281 + vertex 1.22271 0.865277 2.49334 + vertex 1.21765 0.866103 2.49611 + endloop + endfacet + facet normal 0.181858 -0.801216 0.570071 + outer loop + vertex 1.21765 0.866103 2.49611 + vertex 1.22271 0.865277 2.49334 + vertex 1.22218 0.867402 2.49649 + endloop + endfacet + facet normal 0.154326 -0.732494 0.66305 + outer loop + vertex 1.22218 0.867402 2.49649 + vertex 1.21933 0.8689 2.49881 + vertex 1.21765 0.866103 2.49611 + endloop + endfacet + facet normal 0.229398 -0.664325 0.711371 + outer loop + vertex 1.22451 0.870243 2.49839 + vertex 1.21933 0.8689 2.49881 + vertex 1.22218 0.867402 2.49649 + endloop + endfacet + facet normal 0.209645 -0.559903 0.801597 + outer loop + vertex 1.21933 0.8689 2.49881 + vertex 1.22451 0.870243 2.49839 + vertex 1.22114 0.872032 2.50052 + endloop + endfacet + facet normal 0.221225 -0.56352 0.79593 + outer loop + vertex 1.21671 0.871003 2.50103 + vertex 1.21933 0.8689 2.49881 + vertex 1.22114 0.872032 2.50052 + endloop + endfacet + facet normal 0.197501 -0.416905 0.887234 + outer loop + vertex 1.22114 0.872032 2.50052 + vertex 1.21932 0.874832 2.50225 + vertex 1.21671 0.871003 2.50103 + endloop + endfacet + facet normal 0.204108 -0.412848 0.887635 + outer loop + vertex 1.22369 0.875497 2.50155 + vertex 1.21932 0.874832 2.50225 + vertex 1.22114 0.872032 2.50052 + endloop + endfacet + facet normal 0.24647 0.10237 0.963729 + outer loop + vertex 1.22174 0.967243 2.52783 + vertex 1.22182 0.971225 2.52739 + vertex 1.21778 0.967931 2.52877 + endloop + endfacet + facet normal 0.297045 0.0364166 0.954169 + outer loop + vertex 1.21778 0.967931 2.52877 + vertex 1.22182 0.971225 2.52739 + vertex 1.21663 0.971802 2.52898 + endloop + endfacet + facet normal 0.182306 0.706075 0.684268 + outer loop + vertex 1.225 0.978131 2.515 + vertex 1.22 0.979422 2.515 + vertex 1.22336 0.976863 2.51675 + endloop + endfacet + facet normal 0.173611 0.700262 0.692454 + outer loop + vertex 1.22336 0.976863 2.51675 + vertex 1.22 0.979422 2.515 + vertex 1.21821 0.977881 2.51701 + endloop + endfacet + facet normal 0.200002 0.957098 0.209675 + outer loop + vertex 1.22336 0.976863 2.51675 + vertex 1.21821 0.977881 2.51701 + vertex 1.22237 0.976306 2.52023 + endloop + endfacet + facet normal 0.221396 0.957969 0.182424 + outer loop + vertex 1.22237 0.976306 2.52023 + vertex 1.21821 0.977881 2.51701 + vertex 1.21827 0.976926 2.52195 + endloop + endfacet + facet normal 0.277532 0.899793 0.336674 + outer loop + vertex 1.22237 0.976306 2.52023 + vertex 1.21827 0.976926 2.52195 + vertex 1.22356 0.974434 2.52425 + endloop + endfacet + facet normal 0.216563 0.869359 0.444201 + outer loop + vertex 1.22356 0.974434 2.52425 + vertex 1.21827 0.976926 2.52195 + vertex 1.21833 0.974641 2.52639 + endloop + endfacet + facet normal 0.30171 0.536361 0.788218 + outer loop + vertex 1.22182 0.971225 2.52739 + vertex 1.21833 0.974641 2.52639 + vertex 1.21663 0.971802 2.52898 + endloop + endfacet + facet normal 0.333275 0.559954 0.758538 + outer loop + vertex 1.22356 0.974434 2.52425 + vertex 1.21833 0.974641 2.52639 + vertex 1.22182 0.971225 2.52739 + endloop + endfacet + facet normal 0.208538 0.112501 -0.971522 + outer loop + vertex 1.22014 2.05 2.515 + vertex 1.21741 2.04774 2.51415 + vertex 1.22 2.05 2.51497 + endloop + endfacet + facet normal 0.459379 -0.232541 -0.85726 + outer loop + vertex 1.21965 2.04777 2.51534 + vertex 1.21741 2.04774 2.51415 + vertex 1.22014 2.05 2.515 + endloop + endfacet + facet normal 0.197734 -0.917017 -0.346382 + outer loop + vertex 1.21553 2.04641 2.51659 + vertex 1.21741 2.04774 2.51415 + vertex 1.21965 2.04777 2.51534 + endloop + endfacet + facet normal 0.268611 -0.951398 -0.150634 + outer loop + vertex 1.21965 2.04777 2.51534 + vertex 1.2187 2.04701 2.51845 + vertex 1.21553 2.04641 2.51659 + endloop + endfacet + facet normal 0.460042 -0.810525 -0.362506 + outer loop + vertex 1.225 2.05096 2.515 + vertex 1.22313 2.0483 2.51857 + vertex 1.21965 2.04777 2.51534 + endloop + endfacet + facet normal 0.031162 -0.157741 -0.986989 + outer loop + vertex 1.22014 2.05 2.515 + vertex 1.225 2.05096 2.515 + vertex 1.21965 2.04777 2.51534 + endloop + endfacet + facet normal 0.280427 -0.948651 -0.146359 + outer loop + vertex 1.2187 2.04701 2.51845 + vertex 1.21965 2.04777 2.51534 + vertex 1.22313 2.0483 2.51857 + endloop + endfacet + facet normal 0.267227 -0.939513 0.214252 + outer loop + vertex 1.2187 2.04701 2.51845 + vertex 1.22313 2.0483 2.51857 + vertex 1.21901 2.0481 2.52283 + endloop + endfacet + facet normal 0.186854 -0.973079 0.134918 + outer loop + vertex 1.21901 2.0481 2.52283 + vertex 1.22313 2.0483 2.51857 + vertex 1.2239 2.04903 2.52276 + endloop + endfacet + facet normal 0.166321 -0.835464 0.523772 + outer loop + vertex 1.2239 2.04903 2.52276 + vertex 1.22201 2.05037 2.5255 + vertex 1.21901 2.0481 2.52283 + endloop + endfacet + facet normal 0.107169 -0.813519 0.571579 + outer loop + vertex 1.22201 2.05037 2.5255 + vertex 1.21786 2.05047 2.52643 + vertex 1.21901 2.0481 2.52283 + endloop + endfacet + facet normal 0.178673 -0.48825 0.854217 + outer loop + vertex 1.22201 2.05037 2.5255 + vertex 1.21961 2.05296 2.52748 + vertex 1.21786 2.05047 2.52643 + endloop + endfacet + facet normal 0.0903277 -0.551192 0.829475 + outer loop + vertex 1.22434 2.05271 2.5268 + vertex 1.21961 2.05296 2.52748 + vertex 1.22201 2.05037 2.5255 + endloop + endfacet + facet normal 0.222282 0.411391 0.883939 + outer loop + vertex 1.21872 2.15271 2.50067 + vertex 1.22096 2.15015 2.5013 + vertex 1.22327 2.15272 2.49953 + endloop + endfacet + facet normal 0.205308 0.538995 0.816905 + outer loop + vertex 1.21872 2.15271 2.50067 + vertex 1.22327 2.15272 2.49953 + vertex 1.21791 2.15588 2.49879 + endloop + endfacet + facet normal 0.205082 0.538674 0.817173 + outer loop + vertex 1.21791 2.15588 2.49879 + vertex 1.22327 2.15272 2.49953 + vertex 1.22239 2.15619 2.49746 + endloop + endfacet + facet normal 0.196686 0.392614 0.898426 + outer loop + vertex 1.22096 2.15015 2.5013 + vertex 1.21872 2.15271 2.50067 + vertex 1.21683 2.14994 2.5023 + endloop + endfacet + facet normal 0.153949 0.866184 0.475421 + outer loop + vertex 1.22441 2.15981 2.49281 + vertex 1.22213 2.16167 2.49017 + vertex 1.22015 2.16078 2.49242 + endloop + endfacet + facet normal 0.148277 0.81596 0.558769 + outer loop + vertex 1.22015 2.16078 2.49242 + vertex 1.21614 2.16091 2.4933 + vertex 1.21983 2.15873 2.4955 + endloop + endfacet + facet normal 0.135278 0.818146 0.558871 + outer loop + vertex 1.22015 2.16078 2.49242 + vertex 1.21983 2.15873 2.4955 + vertex 1.22441 2.15981 2.49281 + endloop + endfacet + facet normal 0.166921 0.783337 0.598766 + outer loop + vertex 1.22441 2.15981 2.49281 + vertex 1.21983 2.15873 2.4955 + vertex 1.22446 2.15767 2.4956 + endloop + endfacet + facet normal 0.158712 0.697908 0.698381 + outer loop + vertex 1.22239 2.15619 2.49746 + vertex 1.21983 2.15873 2.4955 + vertex 1.21791 2.15588 2.49879 + endloop + endfacet + facet normal 0.143298 0.690533 0.708964 + outer loop + vertex 1.22446 2.15767 2.4956 + vertex 1.21983 2.15873 2.4955 + vertex 1.22239 2.15619 2.49746 + endloop + endfacet + facet normal 0.0728799 0.325399 0.942764 + outer loop + vertex 1.225 2.16805 2.485 + vertex 1.22 2.16917 2.485 + vertex 1.22206 2.16403 2.48662 + endloop + endfacet + facet normal -0.0838822 0.26788 0.959794 + outer loop + vertex 1.22206 2.16403 2.48662 + vertex 1.22 2.16917 2.485 + vertex 1.21865 2.16473 2.48612 + endloop + endfacet + facet normal 0.124114 0.881662 0.455268 + outer loop + vertex 1.22213 2.16167 2.49017 + vertex 1.21823 2.16268 2.48927 + vertex 1.22015 2.16078 2.49242 + endloop + endfacet + facet normal 0.0889973 0.830554 0.549782 + outer loop + vertex 1.22213 2.16167 2.49017 + vertex 1.22206 2.16403 2.48662 + vertex 1.21823 2.16268 2.48927 + endloop + endfacet + facet normal 0.0915313 0.828529 0.552414 + outer loop + vertex 1.22206 2.16403 2.48662 + vertex 1.21865 2.16473 2.48612 + vertex 1.21823 2.16268 2.48927 + endloop + endfacet + facet normal 0.12738 0.882089 0.453535 + outer loop + vertex 1.22015 2.16078 2.49242 + vertex 1.21823 2.16268 2.48927 + vertex 1.21614 2.16091 2.4933 + endloop + endfacet + facet normal 0.172182 -0.948183 0.267025 + outer loop + vertex 1.23 0.861223 2.48 + vertex 1.22783 0.861337 2.4818 + vertex 1.225 0.860315 2.48 + endloop + endfacet + facet normal 0.15122 -0.942828 0.296997 + outer loop + vertex 1.22783 0.861337 2.4818 + vertex 1.225 0.86189 2.485 + vertex 1.225 0.860315 2.48 + endloop + endfacet + facet normal 0.195583 -0.922498 0.332782 + outer loop + vertex 1.22783 0.861337 2.4818 + vertex 1.22637 0.862355 2.48548 + vertex 1.225 0.86189 2.485 + endloop + endfacet + facet normal 0.167464 -0.903465 0.394597 + outer loop + vertex 1.22637 0.862355 2.48548 + vertex 1.22141 0.862022 2.48682 + vertex 1.225 0.86189 2.485 + endloop + endfacet + facet normal 0.161213 -0.915547 0.368489 + outer loop + vertex 1.22637 0.862355 2.48548 + vertex 1.22473 0.86365 2.48942 + vertex 1.22141 0.862022 2.48682 + endloop + endfacet + facet normal 0.133707 -0.923484 0.359583 + outer loop + vertex 1.22945 0.863948 2.48843 + vertex 1.22473 0.86365 2.48942 + vertex 1.22637 0.862355 2.48548 + endloop + endfacet + facet normal 0.146294 -0.891245 0.429278 + outer loop + vertex 1.22473 0.86365 2.48942 + vertex 1.22945 0.863948 2.48843 + vertex 1.22736 0.865188 2.49172 + endloop + endfacet + facet normal 0.135995 -0.888136 0.438999 + outer loop + vertex 1.22271 0.865277 2.49334 + vertex 1.22473 0.86365 2.48942 + vertex 1.22736 0.865188 2.49172 + endloop + endfacet + facet normal 0.180004 -0.808074 0.560905 + outer loop + vertex 1.22736 0.865188 2.49172 + vertex 1.22709 0.867384 2.49497 + vertex 1.22271 0.865277 2.49334 + endloop + endfacet + facet normal 0.174181 -0.802987 0.569976 + outer loop + vertex 1.22709 0.867384 2.49497 + vertex 1.22218 0.867402 2.49649 + vertex 1.22271 0.865277 2.49334 + endloop + endfacet + facet normal 0.220464 -0.660962 0.717304 + outer loop + vertex 1.22709 0.867384 2.49497 + vertex 1.22451 0.870243 2.49839 + vertex 1.22218 0.867402 2.49649 + endloop + endfacet + facet normal 0.195388 -0.675748 0.710766 + outer loop + vertex 1.22964 0.870427 2.49716 + vertex 1.22451 0.870243 2.49839 + vertex 1.22709 0.867384 2.49497 + endloop + endfacet + facet normal 0.23008 -0.534952 0.812951 + outer loop + vertex 1.22477 0.873248 2.5003 + vertex 1.22114 0.872032 2.50052 + vertex 1.22451 0.870243 2.49839 + endloop + endfacet + facet normal 0.245455 -0.53388 0.80915 + outer loop + vertex 1.22477 0.873248 2.5003 + vertex 1.22451 0.870243 2.49839 + vertex 1.22887 0.873956 2.49952 + endloop + endfacet + facet normal 0.218659 -0.509472 0.832242 + outer loop + vertex 1.22887 0.873956 2.49952 + vertex 1.22451 0.870243 2.49839 + vertex 1.22964 0.870427 2.49716 + endloop + endfacet + facet normal 0.191809 -0.405611 0.893694 + outer loop + vertex 1.22477 0.873248 2.5003 + vertex 1.22369 0.875497 2.50155 + vertex 1.22114 0.872032 2.50052 + endloop + endfacet + facet normal 0.208302 -0.3976 0.893602 + outer loop + vertex 1.22685 0.875693 2.5009 + vertex 1.22369 0.875497 2.50155 + vertex 1.22477 0.873248 2.5003 + endloop + endfacet + facet normal 0.190776 -0.263856 0.945508 + outer loop + vertex 1.22514 0.891962 2.50607 + vertex 1.22375 0.888279 2.50533 + vertex 1.2283 0.892271 2.50552 + endloop + endfacet + facet normal 0.19135 -0.276266 0.94184 + outer loop + vertex 1.2283 0.892271 2.50552 + vertex 1.22749 0.894707 2.5064 + vertex 1.22514 0.891962 2.50607 + endloop + endfacet + facet normal 0.243091 0.629238 0.738218 + outer loop + vertex 1.22998 0.971315 2.52549 + vertex 1.22818 0.973366 2.52433 + vertex 1.2263 0.972024 2.5261 + endloop + endfacet + facet normal 0.202408 0.23529 0.950615 + outer loop + vertex 1.2263 0.972024 2.5261 + vertex 1.22636 0.968675 2.52691 + vertex 1.22998 0.971315 2.52549 + endloop + endfacet + facet normal 0.229848 0.234314 0.944599 + outer loop + vertex 1.2263 0.972024 2.5261 + vertex 1.22182 0.971225 2.52739 + vertex 1.22636 0.968675 2.52691 + endloop + endfacet + facet normal 0.161517 0.105899 0.981172 + outer loop + vertex 1.22182 0.971225 2.52739 + vertex 1.22174 0.967243 2.52783 + vertex 1.22636 0.968675 2.52691 + endloop + endfacet + facet normal 0.146714 0.970294 0.192364 + outer loop + vertex 1.23 0.975787 2.51 + vertex 1.225 0.976543 2.51 + vertex 1.22852 0.975622 2.51197 + endloop + endfacet + facet normal 0.386429 0.879052 -0.279178 + outer loop + vertex 1.22852 0.975622 2.51197 + vertex 1.225 0.976543 2.51 + vertex 1.225 0.978131 2.515 + endloop + endfacet + facet normal 0.600373 0.798953 0.0350326 + outer loop + vertex 1.22852 0.975622 2.51197 + vertex 1.225 0.978131 2.515 + vertex 1.22825 0.975651 2.51589 + endloop + endfacet + facet normal 0.282932 0.629618 0.723554 + outer loop + vertex 1.22825 0.975651 2.51589 + vertex 1.225 0.978131 2.515 + vertex 1.22336 0.976863 2.51675 + endloop + endfacet + facet normal 0.265834 0.947591 0.177209 + outer loop + vertex 1.22825 0.975651 2.51589 + vertex 1.22336 0.976863 2.51675 + vertex 1.22751 0.974962 2.52067 + endloop + endfacet + facet normal 0.229244 0.94896 0.216615 + outer loop + vertex 1.22751 0.974962 2.52067 + vertex 1.22336 0.976863 2.51675 + vertex 1.22237 0.976306 2.52023 + endloop + endfacet + facet normal 0.149905 0.703231 0.694978 + outer loop + vertex 1.22818 0.973366 2.52433 + vertex 1.22356 0.974434 2.52425 + vertex 1.2263 0.972024 2.5261 + endloop + endfacet + facet normal 0.203987 0.910377 0.360004 + outer loop + vertex 1.22818 0.973366 2.52433 + vertex 1.22751 0.974962 2.52067 + vertex 1.22356 0.974434 2.52425 + endloop + endfacet + facet normal 0.206086 0.90906 0.36213 + outer loop + vertex 1.22751 0.974962 2.52067 + vertex 1.22237 0.976306 2.52023 + vertex 1.22356 0.974434 2.52425 + endloop + endfacet + facet normal 0.0922855 0.66993 0.736666 + outer loop + vertex 1.2263 0.972024 2.5261 + vertex 1.22356 0.974434 2.52425 + vertex 1.22182 0.971225 2.52739 + endloop + endfacet + facet normal 0.0056053 -0.699711 -0.714404 + outer loop + vertex 1.23 2.05256 2.51 + vertex 1.22892 2.0498 2.5127 + vertex 1.225 2.05252 2.51 + endloop + endfacet + facet normal -0.41667 -0.867804 -0.270744 + outer loop + vertex 1.22892 2.0498 2.5127 + vertex 1.225 2.05096 2.515 + vertex 1.225 2.05252 2.51 + endloop + endfacet + facet normal -0.398038 -0.888441 -0.228557 + outer loop + vertex 1.22892 2.0498 2.5127 + vertex 1.22824 2.04901 2.51696 + vertex 1.225 2.05096 2.515 + endloop + endfacet + facet normal -0.0904649 -0.775691 -0.624596 + outer loop + vertex 1.22824 2.04901 2.51696 + vertex 1.22313 2.0483 2.51857 + vertex 1.225 2.05096 2.515 + endloop + endfacet + facet normal 0.15965 -0.984401 0.0739294 + outer loop + vertex 1.22824 2.04901 2.51696 + vertex 1.22776 2.04926 2.52131 + vertex 1.22313 2.0483 2.51857 + endloop + endfacet + facet normal 0.114274 -0.982089 0.149812 + outer loop + vertex 1.22776 2.04926 2.52131 + vertex 1.2239 2.04903 2.52276 + vertex 1.22313 2.0483 2.51857 + endloop + endfacet + facet normal 0.203067 -0.893235 0.401117 + outer loop + vertex 1.22776 2.04926 2.52131 + vertex 1.22657 2.05054 2.52477 + vertex 1.2239 2.04903 2.52276 + endloop + endfacet + facet normal 0.111397 -0.860035 0.497926 + outer loop + vertex 1.22657 2.05054 2.52477 + vertex 1.22201 2.05037 2.5255 + vertex 1.2239 2.04903 2.52276 + endloop + endfacet + facet normal 0.148596 -0.589491 0.79399 + outer loop + vertex 1.22657 2.05054 2.52477 + vertex 1.22434 2.05271 2.5268 + vertex 1.22201 2.05037 2.5255 + endloop + endfacet + facet normal 0.0755445 -0.638289 0.766081 + outer loop + vertex 1.22838 2.05242 2.52616 + vertex 1.22434 2.05271 2.5268 + vertex 1.22657 2.05054 2.52477 + endloop + endfacet + facet normal 0.176478 0.24592 0.953089 + outer loop + vertex 1.22904 2.07776 2.52044 + vertex 1.22497 2.07932 2.5208 + vertex 1.22659 2.07451 2.52174 + endloop + endfacet + facet normal 0.180782 0.527905 0.82984 + outer loop + vertex 1.22731 2.15243 2.49883 + vertex 1.22687 2.15508 2.49724 + vertex 1.22327 2.15272 2.49953 + endloop + endfacet + facet normal 0.17318 0.536017 0.826253 + outer loop + vertex 1.22327 2.15272 2.49953 + vertex 1.22687 2.15508 2.49724 + vertex 1.22239 2.15619 2.49746 + endloop + endfacet + facet normal 0.124581 0.871249 0.474767 + outer loop + vertex 1.22441 2.15981 2.49281 + vertex 1.22903 2.15999 2.49128 + vertex 1.22597 2.1616 2.48913 + endloop + endfacet + facet normal 0.14639 0.864543 0.480765 + outer loop + vertex 1.22213 2.16167 2.49017 + vertex 1.22441 2.15981 2.49281 + vertex 1.22597 2.1616 2.48913 + endloop + endfacet + facet normal 0.162314 0.797912 0.580509 + outer loop + vertex 1.22903 2.15999 2.49128 + vertex 1.22441 2.15981 2.49281 + vertex 1.22901 2.15784 2.49424 + endloop + endfacet + facet normal 0.150688 0.785266 0.600541 + outer loop + vertex 1.22901 2.15784 2.49424 + vertex 1.22441 2.15981 2.49281 + vertex 1.22446 2.15767 2.4956 + endloop + endfacet + facet normal 0.196948 0.648556 0.735246 + outer loop + vertex 1.22687 2.15508 2.49724 + vertex 1.22446 2.15767 2.4956 + vertex 1.22239 2.15619 2.49746 + endloop + endfacet + facet normal 0.196145 0.648165 0.735806 + outer loop + vertex 1.22901 2.15784 2.49424 + vertex 1.22446 2.15767 2.4956 + vertex 1.22687 2.15508 2.49724 + endloop + endfacet + facet normal -0.0270414 0.450793 0.892219 + outer loop + vertex 1.23 2.16904 2.48 + vertex 1.225 2.16874 2.48 + vertex 1.22826 2.16535 2.48181 + endloop + endfacet + facet normal 0.690822 0.716237 0.0988407 + outer loop + vertex 1.22826 2.16535 2.48181 + vertex 1.225 2.16874 2.48 + vertex 1.225 2.16805 2.485 + endloop + endfacet + facet normal 0.788585 0.415041 0.453734 + outer loop + vertex 1.22826 2.16535 2.48181 + vertex 1.225 2.16805 2.485 + vertex 1.2272 2.16346 2.48538 + endloop + endfacet + facet normal 0.250102 0.197952 0.947768 + outer loop + vertex 1.2272 2.16346 2.48538 + vertex 1.225 2.16805 2.485 + vertex 1.22206 2.16403 2.48662 + endloop + endfacet + facet normal 0.162642 0.823453 0.543574 + outer loop + vertex 1.22597 2.1616 2.48913 + vertex 1.22206 2.16403 2.48662 + vertex 1.22213 2.16167 2.49017 + endloop + endfacet + facet normal 0.211025 0.845794 0.49 + outer loop + vertex 1.2272 2.16346 2.48538 + vertex 1.22206 2.16403 2.48662 + vertex 1.22597 2.1616 2.48913 + endloop + endfacet + facet normal 0.019933 -0.958226 0.285318 + outer loop + vertex 1.235 0.861327 2.48 + vertex 1.23183 0.861509 2.48083 + vertex 1.23 0.861223 2.48 + endloop + endfacet + facet normal 0.0812043 -0.983798 0.159837 + outer loop + vertex 1.23183 0.861509 2.48083 + vertex 1.22783 0.861337 2.4818 + vertex 1.23 0.861223 2.48 + endloop + endfacet + facet normal 0.116945 -0.941842 0.315051 + outer loop + vertex 1.23183 0.861509 2.48083 + vertex 1.23163 0.862627 2.48425 + vertex 1.22783 0.861337 2.4818 + endloop + endfacet + facet normal 0.121295 -0.943276 0.309059 + outer loop + vertex 1.23163 0.862627 2.48425 + vertex 1.22637 0.862355 2.48548 + vertex 1.22783 0.861337 2.4818 + endloop + endfacet + facet normal 0.132402 -0.923201 0.36079 + outer loop + vertex 1.23163 0.862627 2.48425 + vertex 1.22945 0.863948 2.48843 + vertex 1.22637 0.862355 2.48548 + endloop + endfacet + facet normal 0.118001 -0.927529 0.354635 + outer loop + vertex 1.23366 0.864202 2.48769 + vertex 1.22945 0.863948 2.48843 + vertex 1.23163 0.862627 2.48425 + endloop + endfacet + facet normal 0.133126 -0.878912 0.458029 + outer loop + vertex 1.22945 0.863948 2.48843 + vertex 1.23366 0.864202 2.48769 + vertex 1.23239 0.866064 2.49163 + endloop + endfacet + facet normal 0.161156 -0.885185 0.436435 + outer loop + vertex 1.22736 0.865188 2.49172 + vertex 1.22945 0.863948 2.48843 + vertex 1.23239 0.866064 2.49163 + endloop + endfacet + facet normal 0.159471 -0.796472 0.583267 + outer loop + vertex 1.23127 0.868277 2.49496 + vertex 1.23239 0.866064 2.49163 + vertex 1.23483 0.868399 2.49416 + endloop + endfacet + facet normal 0.169871 -0.793304 0.584647 + outer loop + vertex 1.23127 0.868277 2.49496 + vertex 1.22709 0.867384 2.49497 + vertex 1.23239 0.866064 2.49163 + endloop + endfacet + facet normal 0.150662 -0.813298 0.562003 + outer loop + vertex 1.22709 0.867384 2.49497 + vertex 1.22736 0.865188 2.49172 + vertex 1.23239 0.866064 2.49163 + endloop + endfacet + facet normal 0.140253 -0.653451 0.743862 + outer loop + vertex 1.23127 0.868277 2.49496 + vertex 1.22964 0.870427 2.49716 + vertex 1.22709 0.867384 2.49497 + endloop + endfacet + facet normal 0.187213 -0.661592 0.726118 + outer loop + vertex 1.23483 0.868399 2.49416 + vertex 1.23311 0.870175 2.49622 + vertex 1.23127 0.868277 2.49496 + endloop + endfacet + facet normal 0.155852 -0.645482 0.747705 + outer loop + vertex 1.23311 0.870175 2.49622 + vertex 1.22964 0.870427 2.49716 + vertex 1.23127 0.868277 2.49496 + endloop + endfacet + facet normal 0.192466 -0.500335 0.84417 + outer loop + vertex 1.23311 0.870175 2.49622 + vertex 1.23413 0.873748 2.4981 + vertex 1.22964 0.870427 2.49716 + endloop + endfacet + facet normal 0.204382 -0.5134 0.833456 + outer loop + vertex 1.23413 0.873748 2.4981 + vertex 1.22887 0.873956 2.49952 + vertex 1.22964 0.870427 2.49716 + endloop + endfacet + facet normal 0.189529 -0.276933 0.942012 + outer loop + vertex 1.22749 0.894707 2.5064 + vertex 1.2283 0.892271 2.50552 + vertex 1.23123 0.896273 2.50611 + endloop + endfacet + facet normal 0.179029 -0.267244 0.946852 + outer loop + vertex 1.23006 0.946935 2.52095 + vertex 1.22868 0.943299 2.52018 + vertex 1.23313 0.947135 2.52042 + endloop + endfacet + facet normal 0.179276 -0.283619 0.94203 + outer loop + vertex 1.23313 0.947135 2.52042 + vertex 1.23237 0.949611 2.52131 + vertex 1.23006 0.946935 2.52095 + endloop + endfacet + facet normal 0.271832 0.686368 0.674542 + outer loop + vertex 1.22998 0.971315 2.52549 + vertex 1.23406 0.970998 2.52417 + vertex 1.23178 0.973118 2.52293 + endloop + endfacet + facet normal 0.312252 0.659375 0.683903 + outer loop + vertex 1.22818 0.973366 2.52433 + vertex 1.22998 0.971315 2.52549 + vertex 1.23178 0.973118 2.52293 + endloop + endfacet + facet normal 0.199612 0.238955 0.950292 + outer loop + vertex 1.23115 0.968539 2.52594 + vertex 1.22998 0.971315 2.52549 + vertex 1.22636 0.968675 2.52691 + endloop + endfacet + facet normal 0.315388 0.280577 0.906536 + outer loop + vertex 1.23406 0.970998 2.52417 + vertex 1.22998 0.971315 2.52549 + vertex 1.23115 0.968539 2.52594 + endloop + endfacet + facet normal -0.101165 -0.722698 0.68372 + outer loop + vertex 1.23 0.975 2.50921 + vertex 1.23291 0.974538 2.50915 + vertex 1.235 0.975 2.50995 + endloop + endfacet + facet normal 0.0979742 0.705007 -0.7024 + outer loop + vertex 1.23 0.975787 2.51 + vertex 1.23291 0.974538 2.50915 + vertex 1.23 0.975 2.50921 + endloop + endfacet + facet normal 0.398328 0.91713 0.0143841 + outer loop + vertex 1.23291 0.974538 2.50915 + vertex 1.23 0.975787 2.51 + vertex 1.23257 0.974652 2.51135 + endloop + endfacet + facet normal 0.263155 0.924325 0.276356 + outer loop + vertex 1.23257 0.974652 2.51135 + vertex 1.23 0.975787 2.51 + vertex 1.22852 0.975622 2.51197 + endloop + endfacet + facet normal 0.23197 0.972698 -0.00691501 + outer loop + vertex 1.23257 0.974652 2.51135 + vertex 1.22852 0.975622 2.51197 + vertex 1.23198 0.974813 2.51443 + endloop + endfacet + facet normal 0.222042 0.975006 0.0077823 + outer loop + vertex 1.23198 0.974813 2.51443 + vertex 1.22852 0.975622 2.51197 + vertex 1.22825 0.975651 2.51589 + endloop + endfacet + facet normal 0.243493 0.967576 0.0671467 + outer loop + vertex 1.23198 0.974813 2.51443 + vertex 1.22825 0.975651 2.51589 + vertex 1.23307 0.974237 2.51879 + endloop + endfacet + facet normal 0.183439 0.968635 0.167619 + outer loop + vertex 1.23307 0.974237 2.51879 + vertex 1.22825 0.975651 2.51589 + vertex 1.22751 0.974962 2.52067 + endloop + endfacet + facet normal 0.203256 0.910471 0.360179 + outer loop + vertex 1.23178 0.973118 2.52293 + vertex 1.22751 0.974962 2.52067 + vertex 1.22818 0.973366 2.52433 + endloop + endfacet + facet normal 0.228686 0.919565 0.319534 + outer loop + vertex 1.23307 0.974237 2.51879 + vertex 1.22751 0.974962 2.52067 + vertex 1.23178 0.973118 2.52293 + endloop + endfacet + facet normal -0.0312782 -0.679742 -0.732784 + outer loop + vertex 1.235 2.05233 2.51 + vertex 1.2337 2.04982 2.51238 + vertex 1.23 2.05256 2.51 + endloop + endfacet + facet normal -0.044181 -0.689033 -0.723382 + outer loop + vertex 1.2337 2.04982 2.51238 + vertex 1.22892 2.0498 2.5127 + vertex 1.23 2.05256 2.51 + endloop + endfacet + facet normal -0.00315555 -0.99088 -0.134713 + outer loop + vertex 1.2337 2.04982 2.51238 + vertex 1.23295 2.04926 2.51654 + vertex 1.22892 2.0498 2.5127 + endloop + endfacet + facet normal 0.0373457 -0.983638 -0.176243 + outer loop + vertex 1.23295 2.04926 2.51654 + vertex 1.22824 2.04901 2.51696 + vertex 1.22892 2.0498 2.5127 + endloop + endfacet + facet normal 0.0613119 -0.99443 0.0857367 + outer loop + vertex 1.23295 2.04926 2.51654 + vertex 1.23166 2.04949 2.52015 + vertex 1.22824 2.04901 2.51696 + endloop + endfacet + facet normal 0.0799419 -0.994624 0.065817 + outer loop + vertex 1.23166 2.04949 2.52015 + vertex 1.22776 2.04926 2.52131 + vertex 1.22824 2.04901 2.51696 + endloop + endfacet + facet normal 0.161012 -0.921898 0.352391 + outer loop + vertex 1.23166 2.04949 2.52015 + vertex 1.23136 2.05088 2.52391 + vertex 1.22776 2.04926 2.52131 + endloop + endfacet + facet normal 0.133843 -0.913296 0.384677 + outer loop + vertex 1.23136 2.05088 2.52391 + vertex 1.22657 2.05054 2.52477 + vertex 1.22776 2.04926 2.52131 + endloop + endfacet + facet normal 0.175345 -0.688107 0.704105 + outer loop + vertex 1.23136 2.05088 2.52391 + vertex 1.22838 2.05242 2.52616 + vertex 1.22657 2.05054 2.52477 + endloop + endfacet + facet normal 0.211115 -0.653033 0.727309 + outer loop + vertex 1.23146 2.05337 2.52612 + vertex 1.22838 2.05242 2.52616 + vertex 1.23136 2.05088 2.52391 + endloop + endfacet + facet normal 0.176225 0.250683 0.951894 + outer loop + vertex 1.23091 2.07492 2.52083 + vertex 1.22659 2.07451 2.52174 + vertex 1.23117 2.07058 2.52192 + endloop + endfacet + facet normal 0.176965 0.245555 0.953093 + outer loop + vertex 1.23091 2.07492 2.52083 + vertex 1.22904 2.07776 2.52044 + vertex 1.22659 2.07451 2.52174 + endloop + endfacet + facet normal 0.210657 0.295944 0.931687 + outer loop + vertex 1.23017 2.14457 2.50112 + vertex 1.23425 2.14291 2.50073 + vertex 1.23396 2.14722 2.49942 + endloop + endfacet + facet normal 0.199813 0.310033 0.929491 + outer loop + vertex 1.22803 2.14925 2.50002 + vertex 1.23017 2.14457 2.50112 + vertex 1.23396 2.14722 2.49942 + endloop + endfacet + facet normal 0.201587 0.271348 0.941134 + outer loop + vertex 1.23425 2.14291 2.50073 + vertex 1.23017 2.14457 2.50112 + vertex 1.23198 2.13979 2.50211 + endloop + endfacet + facet normal 0.220891 0.381282 0.897681 + outer loop + vertex 1.23396 2.14722 2.49942 + vertex 1.23113 2.15222 2.498 + vertex 1.22803 2.14925 2.50002 + endloop + endfacet + facet normal 0.197166 0.619282 0.760011 + outer loop + vertex 1.2346 2.1544 2.496 + vertex 1.23313 2.15684 2.49438 + vertex 1.23088 2.15544 2.49611 + endloop + endfacet + facet normal 0.168409 0.508521 0.84442 + outer loop + vertex 1.23088 2.15544 2.49611 + vertex 1.23113 2.15222 2.498 + vertex 1.2346 2.1544 2.496 + endloop + endfacet + facet normal 0.191461 0.50771 0.839984 + outer loop + vertex 1.23088 2.15544 2.49611 + vertex 1.22687 2.15508 2.49724 + vertex 1.23113 2.15222 2.498 + endloop + endfacet + facet normal 0.208292 0.528388 0.823055 + outer loop + vertex 1.22687 2.15508 2.49724 + vertex 1.22731 2.15243 2.49883 + vertex 1.23113 2.15222 2.498 + endloop + endfacet + facet normal 0.160456 0.87461 0.457505 + outer loop + vertex 1.22903 2.15999 2.49128 + vertex 1.23428 2.15907 2.49119 + vertex 1.23089 2.16128 2.48815 + endloop + endfacet + facet normal 0.14594 0.880382 0.451253 + outer loop + vertex 1.22597 2.1616 2.48913 + vertex 1.22903 2.15999 2.49128 + vertex 1.23089 2.16128 2.48815 + endloop + endfacet + facet normal 0.137515 0.673578 0.726211 + outer loop + vertex 1.23313 2.15684 2.49438 + vertex 1.22901 2.15784 2.49424 + vertex 1.23088 2.15544 2.49611 + endloop + endfacet + facet normal 0.16741 0.778963 0.604311 + outer loop + vertex 1.23313 2.15684 2.49438 + vertex 1.23428 2.15907 2.49119 + vertex 1.22901 2.15784 2.49424 + endloop + endfacet + facet normal 0.149505 0.799593 0.581635 + outer loop + vertex 1.23428 2.15907 2.49119 + vertex 1.22903 2.15999 2.49128 + vertex 1.22901 2.15784 2.49424 + endloop + endfacet + facet normal 0.143068 0.675609 0.723246 + outer loop + vertex 1.23088 2.15544 2.49611 + vertex 1.22901 2.15784 2.49424 + vertex 1.22687 2.15508 2.49724 + endloop + endfacet + facet normal 0.0446926 0.223479 0.973684 + outer loop + vertex 1.235 2.16804 2.48 + vertex 1.23 2.16904 2.48 + vertex 1.23242 2.16497 2.48082 + endloop + endfacet + facet normal 0.246598 0.33064 0.91097 + outer loop + vertex 1.23242 2.16497 2.48082 + vertex 1.23 2.16904 2.48 + vertex 1.22826 2.16535 2.48181 + endloop + endfacet + facet normal 0.201266 0.822725 0.531616 + outer loop + vertex 1.23242 2.16497 2.48082 + vertex 1.22826 2.16535 2.48181 + vertex 1.23276 2.16278 2.48408 + endloop + endfacet + facet normal 0.220277 0.833736 0.506323 + outer loop + vertex 1.23276 2.16278 2.48408 + vertex 1.22826 2.16535 2.48181 + vertex 1.2272 2.16346 2.48538 + endloop + endfacet + facet normal 0.150538 0.864517 0.47953 + outer loop + vertex 1.23089 2.16128 2.48815 + vertex 1.2272 2.16346 2.48538 + vertex 1.22597 2.1616 2.48913 + endloop + endfacet + facet normal 0.206257 0.883635 0.420294 + outer loop + vertex 1.23276 2.16278 2.48408 + vertex 1.2272 2.16346 2.48538 + vertex 1.23089 2.16128 2.48815 + endloop + endfacet + facet normal 0.178334 -0.907092 0.381288 + outer loop + vertex 1.24 0.86231 2.48 + vertex 1.23647 0.862341 2.48173 + vertex 1.235 0.861327 2.48 + endloop + endfacet + facet normal 0.0701421 -0.884987 0.460303 + outer loop + vertex 1.23647 0.862341 2.48173 + vertex 1.23183 0.861509 2.48083 + vertex 1.235 0.861327 2.48 + endloop + endfacet + facet normal 0.124049 -0.936494 0.328009 + outer loop + vertex 1.23608 0.86353 2.48527 + vertex 1.23647 0.862341 2.48173 + vertex 1.23999 0.863728 2.48435 + endloop + endfacet + facet normal 0.115339 -0.937792 0.327481 + outer loop + vertex 1.23608 0.86353 2.48527 + vertex 1.23163 0.862627 2.48425 + vertex 1.23647 0.862341 2.48173 + endloop + endfacet + facet normal 0.108485 -0.942901 0.31491 + outer loop + vertex 1.23163 0.862627 2.48425 + vertex 1.23183 0.861509 2.48083 + vertex 1.23647 0.862341 2.48173 + endloop + endfacet + facet normal 0.105184 -0.926367 0.361636 + outer loop + vertex 1.23608 0.86353 2.48527 + vertex 1.23366 0.864202 2.48769 + vertex 1.23163 0.862627 2.48425 + endloop + endfacet + facet normal 0.139577 -0.905273 0.401248 + outer loop + vertex 1.23999 0.863728 2.48435 + vertex 1.23782 0.865178 2.48838 + vertex 1.23608 0.86353 2.48527 + endloop + endfacet + facet normal 0.14682 -0.905792 0.397474 + outer loop + vertex 1.23366 0.864202 2.48769 + vertex 1.23608 0.86353 2.48527 + vertex 1.23782 0.865178 2.48838 + endloop + endfacet + facet normal 0.13073 -0.879522 0.457548 + outer loop + vertex 1.23366 0.864202 2.48769 + vertex 1.23782 0.865178 2.48838 + vertex 1.23239 0.866064 2.49163 + endloop + endfacet + facet normal 0.156288 -0.855512 0.493633 + outer loop + vertex 1.23239 0.866064 2.49163 + vertex 1.23782 0.865178 2.48838 + vertex 1.23719 0.867009 2.49176 + endloop + endfacet + facet normal 0.140942 -0.79066 0.595812 + outer loop + vertex 1.23719 0.867009 2.49176 + vertex 1.23483 0.868399 2.49416 + vertex 1.23239 0.866064 2.49163 + endloop + endfacet + facet normal 0.198173 -0.751476 0.629295 + outer loop + vertex 1.23892 0.869045 2.49364 + vertex 1.23483 0.868399 2.49416 + vertex 1.23719 0.867009 2.49176 + endloop + endfacet + facet normal 0.194743 -0.63446 0.748021 + outer loop + vertex 1.23483 0.868399 2.49416 + vertex 1.23892 0.869045 2.49364 + vertex 1.23674 0.871143 2.49599 + endloop + endfacet + facet normal 0.218145 -0.642026 0.734993 + outer loop + vertex 1.23311 0.870175 2.49622 + vertex 1.23483 0.868399 2.49416 + vertex 1.23674 0.871143 2.49599 + endloop + endfacet + facet normal 0.187127 -0.499665 0.845765 + outer loop + vertex 1.23674 0.871143 2.49599 + vertex 1.23413 0.873748 2.4981 + vertex 1.23311 0.870175 2.49622 + endloop + endfacet + facet normal 0.199168 -0.48997 0.848682 + outer loop + vertex 1.2395 0.874833 2.49747 + vertex 1.23413 0.873748 2.4981 + vertex 1.23674 0.871143 2.49599 + endloop + endfacet + facet normal 0.17691 -0.284418 0.942237 + outer loop + vertex 1.23237 0.949611 2.52131 + vertex 1.23313 0.947135 2.52042 + vertex 1.23606 0.951097 2.52107 + endloop + endfacet + facet normal 0.0212337 0.549211 0.835414 + outer loop + vertex 1.24 0.974857 2.51 + vertex 1.2363 0.975 2.51 + vertex 1.23913 0.974099 2.51052 + endloop + endfacet + facet normal 0.415327 0.792962 0.445774 + outer loop + vertex 1.23896 0.970883 2.52179 + vertex 1.23712 0.973276 2.51924 + vertex 1.23546 0.972743 2.52174 + endloop + endfacet + facet normal 0.285062 0.693227 0.661949 + outer loop + vertex 1.23546 0.972743 2.52174 + vertex 1.23178 0.973118 2.52293 + vertex 1.23406 0.970998 2.52417 + endloop + endfacet + facet normal 0.341105 0.659359 0.669995 + outer loop + vertex 1.23896 0.970883 2.52179 + vertex 1.23546 0.972743 2.52174 + vertex 1.23406 0.970998 2.52417 + endloop + endfacet + facet normal 0.425443 0.275305 0.862094 + outer loop + vertex 1.23896 0.970883 2.52179 + vertex 1.23406 0.970998 2.52417 + vertex 1.23477 0.968023 2.52477 + endloop + endfacet + facet normal 0.373826 0.348326 0.859607 + outer loop + vertex 1.23896 0.970883 2.52179 + vertex 1.23477 0.968023 2.52477 + vertex 1.23757 0.966924 2.52399 + endloop + endfacet + facet normal 0.331253 0.2618 0.906495 + outer loop + vertex 1.23477 0.968023 2.52477 + vertex 1.23406 0.970998 2.52417 + vertex 1.23115 0.968539 2.52594 + endloop + endfacet + facet normal -0.0208539 -0.84047 0.541456 + outer loop + vertex 1.235 0.975 2.50995 + vertex 1.23291 0.974538 2.50915 + vertex 1.2363 0.975 2.51 + endloop + endfacet + facet normal 0.135757 0.779519 0.611491 + outer loop + vertex 1.2363 0.975 2.51 + vertex 1.23615 0.974206 2.51105 + vertex 1.23913 0.974099 2.51052 + endloop + endfacet + facet normal -0.248148 0.788929 0.562151 + outer loop + vertex 1.2363 0.975 2.51 + vertex 1.23291 0.974538 2.50915 + vertex 1.23615 0.974206 2.51105 + endloop + endfacet + facet normal 0.120788 0.992142 -0.0326303 + outer loop + vertex 1.23291 0.974538 2.50915 + vertex 1.23257 0.974652 2.51135 + vertex 1.23615 0.974206 2.51105 + endloop + endfacet + facet normal 0.125521 0.991827 0.0228987 + outer loop + vertex 1.23615 0.974206 2.51105 + vertex 1.23257 0.974652 2.51135 + vertex 1.23614 0.974113 2.51513 + endloop + endfacet + facet normal 0.169277 0.985377 -0.0194549 + outer loop + vertex 1.23614 0.974113 2.51513 + vertex 1.23257 0.974652 2.51135 + vertex 1.23198 0.974813 2.51443 + endloop + endfacet + facet normal 0.1842 0.928946 0.321138 + outer loop + vertex 1.23712 0.973276 2.51924 + vertex 1.23307 0.974237 2.51879 + vertex 1.23546 0.972743 2.52174 + endloop + endfacet + facet normal 0.212933 0.966151 0.145641 + outer loop + vertex 1.23712 0.973276 2.51924 + vertex 1.23614 0.974113 2.51513 + vertex 1.23307 0.974237 2.51879 + endloop + endfacet + facet normal 0.150406 0.984273 0.0926582 + outer loop + vertex 1.23614 0.974113 2.51513 + vertex 1.23198 0.974813 2.51443 + vertex 1.23307 0.974237 2.51879 + endloop + endfacet + facet normal 0.195912 0.929656 0.312024 + outer loop + vertex 1.23546 0.972743 2.52174 + vertex 1.23307 0.974237 2.51879 + vertex 1.23178 0.973118 2.52293 + endloop + endfacet + facet normal 0.0297025 -0.674871 -0.737337 + outer loop + vertex 1.24 2.05255 2.51 + vertex 1.23855 2.05003 2.51225 + vertex 1.235 2.05233 2.51 + endloop + endfacet + facet normal 0.00971589 -0.691229 -0.72257 + outer loop + vertex 1.23855 2.05003 2.51225 + vertex 1.2337 2.04982 2.51238 + vertex 1.235 2.05233 2.51 + endloop + endfacet + facet normal 0.039119 -0.995234 -0.0893262 + outer loop + vertex 1.23855 2.05003 2.51225 + vertex 1.23784 2.04961 2.51656 + vertex 1.2337 2.04982 2.51238 + endloop + endfacet + facet normal 0.0714524 -0.990069 -0.121069 + outer loop + vertex 1.23784 2.04961 2.51656 + vertex 1.23295 2.04926 2.51654 + vertex 1.2337 2.04982 2.51238 + endloop + endfacet + facet normal 0.068093 -0.969735 0.234471 + outer loop + vertex 1.23784 2.04961 2.51656 + vertex 1.23599 2.05061 2.52124 + vertex 1.23295 2.04926 2.51654 + endloop + endfacet + facet normal 0.21456 -0.9668 0.138786 + outer loop + vertex 1.23599 2.05061 2.52124 + vertex 1.23166 2.04949 2.52015 + vertex 1.23295 2.04926 2.51654 + endloop + endfacet + facet normal 0.421738 -0.739089 0.525247 + outer loop + vertex 1.23478 2.05236 2.52467 + vertex 1.23599 2.05061 2.52124 + vertex 1.23876 2.05407 2.52389 + endloop + endfacet + facet normal 0.24515 -0.826091 0.50742 + outer loop + vertex 1.23478 2.05236 2.52467 + vertex 1.23136 2.05088 2.52391 + vertex 1.23599 2.05061 2.52124 + endloop + endfacet + facet normal 0.150099 -0.923802 0.352221 + outer loop + vertex 1.23136 2.05088 2.52391 + vertex 1.23166 2.04949 2.52015 + vertex 1.23599 2.05061 2.52124 + endloop + endfacet + facet normal 0.121843 -0.661004 0.740424 + outer loop + vertex 1.23478 2.05236 2.52467 + vertex 1.23146 2.05337 2.52612 + vertex 1.23136 2.05088 2.52391 + endloop + endfacet + facet normal 0.194588 0.291248 0.936648 + outer loop + vertex 1.23396 2.14722 2.49942 + vertex 1.23889 2.143 2.49971 + vertex 1.23862 2.14735 2.49842 + endloop + endfacet + facet normal 0.187846 0.359658 0.91398 + outer loop + vertex 1.23862 2.14735 2.49842 + vertex 1.23652 2.15082 2.49748 + vertex 1.23396 2.14722 2.49942 + endloop + endfacet + facet normal 0.181832 0.363723 0.913588 + outer loop + vertex 1.23396 2.14722 2.49942 + vertex 1.23652 2.15082 2.49748 + vertex 1.23113 2.15222 2.498 + endloop + endfacet + facet normal 0.212274 0.602887 0.769069 + outer loop + vertex 1.2346 2.1544 2.496 + vertex 1.23921 2.15333 2.49556 + vertex 1.23712 2.15639 2.49374 + endloop + endfacet + facet normal 0.193553 0.618269 0.761762 + outer loop + vertex 1.23313 2.15684 2.49438 + vertex 1.2346 2.1544 2.496 + vertex 1.23712 2.15639 2.49374 + endloop + endfacet + facet normal 0.203617 0.467127 0.860426 + outer loop + vertex 1.23652 2.15082 2.49748 + vertex 1.2346 2.1544 2.496 + vertex 1.23113 2.15222 2.498 + endloop + endfacet + facet normal 0.189034 0.461835 0.866588 + outer loop + vertex 1.23921 2.15333 2.49556 + vertex 1.2346 2.1544 2.496 + vertex 1.23652 2.15082 2.49748 + endloop + endfacet + facet normal 0.150149 0.899064 0.411266 + outer loop + vertex 1.23972 2.15999 2.48796 + vertex 1.23755 2.16175 2.48491 + vertex 1.23526 2.16101 2.48736 + endloop + endfacet + facet normal 0.140123 0.868411 0.475635 + outer loop + vertex 1.23526 2.16101 2.48736 + vertex 1.23089 2.16128 2.48815 + vertex 1.23428 2.15907 2.49119 + endloop + endfacet + facet normal 0.134842 0.869644 0.474906 + outer loop + vertex 1.23526 2.16101 2.48736 + vertex 1.23428 2.15907 2.49119 + vertex 1.23972 2.15999 2.48796 + endloop + endfacet + facet normal 0.167441 0.837258 0.520541 + outer loop + vertex 1.23972 2.15999 2.48796 + vertex 1.23428 2.15907 2.49119 + vertex 1.23943 2.15794 2.49136 + endloop + endfacet + facet normal 0.185741 0.772922 0.606705 + outer loop + vertex 1.23712 2.15639 2.49374 + vertex 1.23428 2.15907 2.49119 + vertex 1.23313 2.15684 2.49438 + endloop + endfacet + facet normal 0.146513 0.758362 0.635154 + outer loop + vertex 1.23943 2.15794 2.49136 + vertex 1.23428 2.15907 2.49119 + vertex 1.23712 2.15639 2.49374 + endloop + endfacet + facet normal 0.0425871 0.343374 0.938233 + outer loop + vertex 1.24 2.16742 2.48 + vertex 1.235 2.16804 2.48 + vertex 1.2374 2.16379 2.48145 + endloop + endfacet + facet normal -0.0489085 0.29694 0.953643 + outer loop + vertex 1.2374 2.16379 2.48145 + vertex 1.235 2.16804 2.48 + vertex 1.23242 2.16497 2.48082 + endloop + endfacet + facet normal 0.128135 0.910108 0.394062 + outer loop + vertex 1.23755 2.16175 2.48491 + vertex 1.23276 2.16278 2.48408 + vertex 1.23526 2.16101 2.48736 + endloop + endfacet + facet normal 0.0985754 0.859323 0.501843 + outer loop + vertex 1.23755 2.16175 2.48491 + vertex 1.2374 2.16379 2.48145 + vertex 1.23276 2.16278 2.48408 + endloop + endfacet + facet normal 0.128747 0.829357 0.543683 + outer loop + vertex 1.2374 2.16379 2.48145 + vertex 1.23242 2.16497 2.48082 + vertex 1.23276 2.16278 2.48408 + endloop + endfacet + facet normal 0.127914 0.910074 0.394212 + outer loop + vertex 1.23526 2.16101 2.48736 + vertex 1.23276 2.16278 2.48408 + vertex 1.23089 2.16128 2.48815 + endloop + endfacet + facet normal 0.0848125 -0.948611 0.304866 + outer loop + vertex 1.245 0.862757 2.48 + vertex 1.24192 0.862783 2.48094 + vertex 1.24 0.86231 2.48 + endloop + endfacet + facet normal 0.114138 -0.961252 0.250933 + outer loop + vertex 1.24192 0.862783 2.48094 + vertex 1.23647 0.862341 2.48173 + vertex 1.24 0.86231 2.48 + endloop + endfacet + facet normal 0.123399 -0.936309 0.328783 + outer loop + vertex 1.24192 0.862783 2.48094 + vertex 1.23999 0.863728 2.48435 + vertex 1.23647 0.862341 2.48173 + endloop + endfacet + facet normal 0.14424 -0.92975 0.338763 + outer loop + vertex 1.24455 0.864122 2.48349 + vertex 1.23999 0.863728 2.48435 + vertex 1.24192 0.862783 2.48094 + endloop + endfacet + facet normal 0.153192 -0.904646 0.397679 + outer loop + vertex 1.23999 0.863728 2.48435 + vertex 1.24455 0.864122 2.48349 + vertex 1.24243 0.865216 2.4868 + endloop + endfacet + facet normal 0.145988 -0.903072 0.403917 + outer loop + vertex 1.23782 0.865178 2.48838 + vertex 1.23999 0.863728 2.48435 + vertex 1.24243 0.865216 2.4868 + endloop + endfacet + facet normal 0.181237 -0.842041 0.508055 + outer loop + vertex 1.24243 0.865216 2.4868 + vertex 1.24183 0.867291 2.49045 + vertex 1.23782 0.865178 2.48838 + endloop + endfacet + facet normal 0.190459 -0.847397 0.495625 + outer loop + vertex 1.24183 0.867291 2.49045 + vertex 1.23719 0.867009 2.49176 + vertex 1.23782 0.865178 2.48838 + endloop + endfacet + facet normal 0.218779 -0.756772 0.615981 + outer loop + vertex 1.24183 0.867291 2.49045 + vertex 1.23892 0.869045 2.49364 + vertex 1.23719 0.867009 2.49176 + endloop + endfacet + facet normal 0.223866 -0.753127 0.618614 + outer loop + vertex 1.24254 0.869845 2.4933 + vertex 1.23892 0.869045 2.49364 + vertex 1.24183 0.867291 2.49045 + endloop + endfacet + facet normal 0.208017 -0.626244 0.751364 + outer loop + vertex 1.23892 0.869045 2.49364 + vertex 1.24254 0.869845 2.4933 + vertex 1.24096 0.871899 2.49545 + endloop + endfacet + facet normal 0.207089 -0.625918 0.751891 + outer loop + vertex 1.23674 0.871143 2.49599 + vertex 1.23892 0.869045 2.49364 + vertex 1.24096 0.871899 2.49545 + endloop + endfacet + facet normal 0.194881 -0.487682 0.850992 + outer loop + vertex 1.24096 0.871899 2.49545 + vertex 1.2395 0.874833 2.49747 + vertex 1.23674 0.871143 2.49599 + endloop + endfacet + facet normal 0.196964 -0.486703 0.851073 + outer loop + vertex 1.24397 0.875302 2.4967 + vertex 1.2395 0.874833 2.49747 + vertex 1.24096 0.871899 2.49545 + endloop + endfacet + facet normal 0.194609 -0.371874 0.907654 + outer loop + vertex 1.24397 0.875302 2.4967 + vertex 1.24361 0.879165 2.49836 + vertex 1.2395 0.874833 2.49747 + endloop + endfacet + facet normal 0.0441883 0.993471 0.105184 + outer loop + vertex 1.23913 0.974099 2.51052 + vertex 1.23994 0.973728 2.51369 + vertex 1.2443 0.973753 2.51162 + endloop + endfacet + facet normal -0.116362 0.649693 0.751238 + outer loop + vertex 1.23913 0.974099 2.51052 + vertex 1.2443 0.973753 2.51162 + vertex 1.24 0.974857 2.51 + endloop + endfacet + facet normal -0.00589749 0.819068 0.573666 + outer loop + vertex 1.24 0.974857 2.51 + vertex 1.2443 0.973753 2.51162 + vertex 1.245 0.974893 2.51 + endloop + endfacet + facet normal 0.10383 0.967539 0.230408 + outer loop + vertex 1.24355 0.972423 2.51754 + vertex 1.2443 0.973753 2.51162 + vertex 1.23994 0.973728 2.51369 + endloop + endfacet + facet normal 0.181409 0.970524 0.158666 + outer loop + vertex 1.23953 0.973161 2.51762 + vertex 1.24355 0.972423 2.51754 + vertex 1.23994 0.973728 2.51369 + endloop + endfacet + facet normal 0.364154 0.795175 0.484859 + outer loop + vertex 1.23953 0.973161 2.51762 + vertex 1.23712 0.973276 2.51924 + vertex 1.23896 0.970883 2.52179 + endloop + endfacet + facet normal 0.166505 0.855371 0.490526 + outer loop + vertex 1.23953 0.973161 2.51762 + vertex 1.23896 0.970883 2.52179 + vertex 1.24355 0.972423 2.51754 + endloop + endfacet + facet normal 0.185396 0.842252 0.506202 + outer loop + vertex 1.24355 0.972423 2.51754 + vertex 1.23896 0.970883 2.52179 + vertex 1.2439 0.970147 2.5212 + endloop + endfacet + facet normal 0.173419 0.432473 0.884813 + outer loop + vertex 1.24146 0.967402 2.523 + vertex 1.23896 0.970883 2.52179 + vertex 1.23757 0.966924 2.52399 + endloop + endfacet + facet normal 0.169189 0.430109 0.886782 + outer loop + vertex 1.2439 0.970147 2.5212 + vertex 1.23896 0.970883 2.52179 + vertex 1.24146 0.967402 2.523 + endloop + endfacet + facet normal 0.0535424 0.993262 0.102781 + outer loop + vertex 1.23913 0.974099 2.51052 + vertex 1.23615 0.974206 2.51105 + vertex 1.23994 0.973728 2.51369 + endloop + endfacet + facet normal 0.158004 0.974897 0.15688 + outer loop + vertex 1.23994 0.973728 2.51369 + vertex 1.23614 0.974113 2.51513 + vertex 1.23953 0.973161 2.51762 + endloop + endfacet + facet normal 0.109384 0.993736 0.022903 + outer loop + vertex 1.23615 0.974206 2.51105 + vertex 1.23614 0.974113 2.51513 + vertex 1.23994 0.973728 2.51369 + endloop + endfacet + facet normal 0.154749 0.974708 0.161239 + outer loop + vertex 1.23953 0.973161 2.51762 + vertex 1.23614 0.974113 2.51513 + vertex 1.23712 0.973276 2.51924 + endloop + endfacet + facet normal -0.350967 -0.0249496 -0.936055 + outer loop + vertex 1.24 2.05255 2.51 + vertex 1.245 2.055 2.50806 + vertex 1.24549 2.05144 2.50797 + endloop + endfacet + facet normal 0.0286685 -0.65584 -0.754355 + outer loop + vertex 1.24 2.055 2.50787 + vertex 1.245 2.055 2.50806 + vertex 1.24 2.05255 2.51 + endloop + endfacet + facet normal -0.330449 -0.836835 -0.436476 + outer loop + vertex 1.24549 2.05144 2.50797 + vertex 1.24369 2.05007 2.51197 + vertex 1.24 2.05255 2.51 + endloop + endfacet + facet normal -0.0367988 -0.653415 -0.756105 + outer loop + vertex 1.24369 2.05007 2.51197 + vertex 1.23855 2.05003 2.51225 + vertex 1.24 2.05255 2.51 + endloop + endfacet + facet normal 0.00467232 -0.998188 -0.0599939 + outer loop + vertex 1.24369 2.05007 2.51197 + vertex 1.24286 2.0498 2.51638 + vertex 1.23855 2.05003 2.51225 + endloop + endfacet + facet normal 0.033748 -0.99535 -0.090216 + outer loop + vertex 1.24286 2.0498 2.51638 + vertex 1.23784 2.04961 2.51656 + vertex 1.23855 2.05003 2.51225 + endloop + endfacet + facet normal 0.0461402 -0.955422 0.291616 + outer loop + vertex 1.24286 2.0498 2.51638 + vertex 1.24151 2.05101 2.52056 + vertex 1.23784 2.04961 2.51656 + endloop + endfacet + facet normal 0.0994699 -0.964225 0.245716 + outer loop + vertex 1.24151 2.05101 2.52056 + vertex 1.23599 2.05061 2.52124 + vertex 1.23784 2.04961 2.51656 + endloop + endfacet + facet normal 0.138066 -0.669243 0.730104 + outer loop + vertex 1.24151 2.05101 2.52056 + vertex 1.23876 2.05407 2.52389 + vertex 1.23599 2.05061 2.52124 + endloop + endfacet + facet normal 0.0476042 -0.715038 0.697463 + outer loop + vertex 1.2447 2.05334 2.52273 + vertex 1.23876 2.05407 2.52389 + vertex 1.24151 2.05101 2.52056 + endloop + endfacet + facet normal 0.187638 0.359555 0.914064 + outer loop + vertex 1.23862 2.14735 2.49842 + vertex 1.24165 2.14945 2.49697 + vertex 1.23652 2.15082 2.49748 + endloop + endfacet + facet normal 0.210794 0.580467 0.786526 + outer loop + vertex 1.23921 2.15333 2.49556 + vertex 1.24322 2.15219 2.49532 + vertex 1.2424 2.15525 2.49328 + endloop + endfacet + facet normal 0.195167 0.59671 0.778362 + outer loop + vertex 1.23712 2.15639 2.49374 + vertex 1.23921 2.15333 2.49556 + vertex 1.2424 2.15525 2.49328 + endloop + endfacet + facet normal 0.206513 0.446262 0.870748 + outer loop + vertex 1.24165 2.14945 2.49697 + vertex 1.23921 2.15333 2.49556 + vertex 1.23652 2.15082 2.49748 + endloop + endfacet + facet normal 0.174213 0.431215 0.88527 + outer loop + vertex 1.24322 2.15219 2.49532 + vertex 1.23921 2.15333 2.49556 + vertex 1.24165 2.14945 2.49697 + endloop + endfacet + facet normal 0.157495 0.892789 0.422047 + outer loop + vertex 1.23972 2.15999 2.48796 + vertex 1.24536 2.15981 2.48624 + vertex 1.24156 2.16163 2.4838 + endloop + endfacet + facet normal 0.141284 0.897903 0.416904 + outer loop + vertex 1.23755 2.16175 2.48491 + vertex 1.23972 2.15999 2.48796 + vertex 1.24156 2.16163 2.4838 + endloop + endfacet + facet normal 0.182958 0.839816 0.511112 + outer loop + vertex 1.24536 2.15981 2.48624 + vertex 1.23972 2.15999 2.48796 + vertex 1.24374 2.15784 2.49005 + endloop + endfacet + facet normal 0.175949 0.83566 0.520302 + outer loop + vertex 1.24374 2.15784 2.49005 + vertex 1.23972 2.15999 2.48796 + vertex 1.23943 2.15794 2.49136 + endloop + endfacet + facet normal 0.210842 0.71327 0.668424 + outer loop + vertex 1.2424 2.15525 2.49328 + vertex 1.23943 2.15794 2.49136 + vertex 1.23712 2.15639 2.49374 + endloop + endfacet + facet normal 0.216574 0.716102 0.663546 + outer loop + vertex 1.24374 2.15784 2.49005 + vertex 1.23943 2.15794 2.49136 + vertex 1.2424 2.15525 2.49328 + endloop + endfacet + facet normal 0.00890009 0.111299 0.993747 + outer loop + vertex 1.245 2.16702 2.48 + vertex 1.24 2.16742 2.48 + vertex 1.24347 2.1638 2.48037 + endloop + endfacet + facet normal 0.16787 0.258917 0.9512 + outer loop + vertex 1.24347 2.1638 2.48037 + vertex 1.24 2.16742 2.48 + vertex 1.2374 2.16379 2.48145 + endloop + endfacet + facet normal 0.161608 0.853368 0.495627 + outer loop + vertex 1.24156 2.16163 2.4838 + vertex 1.2374 2.16379 2.48145 + vertex 1.23755 2.16175 2.48491 + endloop + endfacet + facet normal 0.0996911 0.815452 0.570176 + outer loop + vertex 1.24347 2.1638 2.48037 + vertex 1.2374 2.16379 2.48145 + vertex 1.24156 2.16163 2.4838 + endloop + endfacet + facet normal -0.0415024 0.435075 0.899437 + outer loop + vertex 1.25 0.863234 2.48 + vertex 1.24714 0.863143 2.47991 + vertex 1.245 0.862757 2.48 + endloop + endfacet + facet normal 0.168155 -0.800926 0.574666 + outer loop + vertex 1.24714 0.863143 2.47991 + vertex 1.24192 0.862783 2.48094 + vertex 1.245 0.862757 2.48 + endloop + endfacet + facet normal 0.132678 -0.927505 0.349472 + outer loop + vertex 1.24714 0.863143 2.47991 + vertex 1.24455 0.864122 2.48349 + vertex 1.24192 0.862783 2.48094 + endloop + endfacet + facet normal 0.156362 -0.918168 0.36403 + outer loop + vertex 1.24841 0.864432 2.48262 + vertex 1.24455 0.864122 2.48349 + vertex 1.24714 0.863143 2.47991 + endloop + endfacet + facet normal 0.171644 -0.878785 0.445282 + outer loop + vertex 1.24455 0.864122 2.48349 + vertex 1.24841 0.864432 2.48262 + vertex 1.24731 0.866375 2.48688 + endloop + endfacet + facet normal 0.203125 -0.883249 0.422625 + outer loop + vertex 1.24243 0.865216 2.4868 + vertex 1.24455 0.864122 2.48349 + vertex 1.24731 0.866375 2.48688 + endloop + endfacet + facet normal 0.145305 -0.805494 0.574514 + outer loop + vertex 1.24647 0.869631 2.49165 + vertex 1.24731 0.866375 2.48688 + vertex 1.25022 0.868844 2.4896 + endloop + endfacet + facet normal 0.244743 -0.780632 0.575077 + outer loop + vertex 1.24647 0.869631 2.49165 + vertex 1.24183 0.867291 2.49045 + vertex 1.24731 0.866375 2.48688 + endloop + endfacet + facet normal 0.191341 -0.839627 0.508345 + outer loop + vertex 1.24183 0.867291 2.49045 + vertex 1.24243 0.865216 2.4868 + vertex 1.24731 0.866375 2.48688 + endloop + endfacet + facet normal 0.219306 -0.753367 0.619954 + outer loop + vertex 1.24647 0.869631 2.49165 + vertex 1.24254 0.869845 2.4933 + vertex 1.24183 0.867291 2.49045 + endloop + endfacet + facet normal 0.198695 -0.737157 0.645848 + outer loop + vertex 1.25022 0.868844 2.4896 + vertex 1.24952 0.870577 2.49179 + vertex 1.24647 0.869631 2.49165 + endloop + endfacet + facet normal 0.221658 -0.618453 0.753912 + outer loop + vertex 1.24254 0.869845 2.4933 + vertex 1.245 0.87238 2.49466 + vertex 1.24096 0.871899 2.49545 + endloop + endfacet + facet normal 0.266497 -0.642871 0.71812 + outer loop + vertex 1.24647 0.869631 2.49165 + vertex 1.245 0.87238 2.49466 + vertex 1.24254 0.869845 2.4933 + endloop + endfacet + facet normal 0.241259 -0.654554 0.716487 + outer loop + vertex 1.24647 0.869631 2.49165 + vertex 1.24971 0.87331 2.49392 + vertex 1.245 0.87238 2.49466 + endloop + endfacet + facet normal 0.154592 -0.613688 0.774267 + outer loop + vertex 1.24647 0.869631 2.49165 + vertex 1.24952 0.870577 2.49179 + vertex 1.24971 0.87331 2.49392 + endloop + endfacet + facet normal 0.22379 -0.504155 0.834114 + outer loop + vertex 1.245 0.87238 2.49466 + vertex 1.24397 0.875302 2.4967 + vertex 1.24096 0.871899 2.49545 + endloop + endfacet + facet normal 0.232546 -0.533834 0.812984 + outer loop + vertex 1.24971 0.87331 2.49392 + vertex 1.24727 0.875262 2.4959 + vertex 1.245 0.87238 2.49466 + endloop + endfacet + facet normal 0.195969 -0.514487 0.834805 + outer loop + vertex 1.24727 0.875262 2.4959 + vertex 1.24397 0.875302 2.4967 + vertex 1.245 0.87238 2.49466 + endloop + endfacet + facet normal 0.211518 -0.396796 0.893204 + outer loop + vertex 1.24727 0.875262 2.4959 + vertex 1.24837 0.879023 2.49731 + vertex 1.24397 0.875302 2.4967 + endloop + endfacet + facet normal 0.189083 -0.372731 0.908471 + outer loop + vertex 1.24837 0.879023 2.49731 + vertex 1.24361 0.879165 2.49836 + vertex 1.24397 0.875302 2.4967 + endloop + endfacet + facet normal 0.390032 -0.753207 0.529674 + outer loop + vertex 1.24778 0.973796 2.50996 + vertex 1.24989 0.973725 2.5083 + vertex 1.25 0.974973 2.51 + endloop + endfacet + facet normal 0.333146 -0.650848 0.68221 + outer loop + vertex 1.24778 0.973796 2.50996 + vertex 1.25 0.974973 2.51 + vertex 1.2443 0.973753 2.51162 + endloop + endfacet + facet normal -0.0131357 0.82048 0.571524 + outer loop + vertex 1.2443 0.973753 2.51162 + vertex 1.25 0.974973 2.51 + vertex 1.245 0.974893 2.51 + endloop + endfacet + facet normal 0.0266508 0.996276 0.0819964 + outer loop + vertex 1.2481 0.973593 2.51233 + vertex 1.24778 0.973796 2.50996 + vertex 1.2443 0.973753 2.51162 + endloop + endfacet + facet normal -0.00303542 0.971766 0.235927 + outer loop + vertex 1.2481 0.973593 2.51233 + vertex 1.2443 0.973753 2.51162 + vertex 1.2489 0.972673 2.51613 + endloop + endfacet + facet normal 0.0128195 0.975281 0.220597 + outer loop + vertex 1.2489 0.972673 2.51613 + vertex 1.2443 0.973753 2.51162 + vertex 1.24355 0.972423 2.51754 + endloop + endfacet + facet normal 0.0902556 0.86477 0.49399 + outer loop + vertex 1.2489 0.972673 2.51613 + vertex 1.24355 0.972423 2.51754 + vertex 1.24805 0.970573 2.51996 + endloop + endfacet + facet normal 0.0689781 0.84994 0.522344 + outer loop + vertex 1.24805 0.970573 2.51996 + vertex 1.24355 0.972423 2.51754 + vertex 1.2439 0.970147 2.5212 + endloop + endfacet + facet normal 0.142495 0.450314 0.881427 + outer loop + vertex 1.24615 0.967594 2.52214 + vertex 1.2439 0.970147 2.5212 + vertex 1.24146 0.967402 2.523 + endloop + endfacet + facet normal 0.203069 0.490932 0.8472 + outer loop + vertex 1.24805 0.970573 2.51996 + vertex 1.2439 0.970147 2.5212 + vertex 1.24615 0.967594 2.52214 + endloop + endfacet + facet normal 0.0147701 0.999591 -0.0244688 + outer loop + vertex 1.24989 0.973725 2.5083 + vertex 1.24778 0.973796 2.50996 + vertex 1.25022 0.973778 2.51069 + endloop + endfacet + facet normal -0.0189373 0.995928 0.0881431 + outer loop + vertex 1.25022 0.973778 2.51069 + vertex 1.24778 0.973796 2.50996 + vertex 1.2481 0.973593 2.51233 + endloop + endfacet + facet normal -0.167933 -0.695989 -0.698139 + outer loop + vertex 1.24549 2.05144 2.50797 + vertex 1.24784 2.05374 2.50512 + vertex 1.25113 2.05115 2.50691 + endloop + endfacet + facet normal -0.735095 -0.0843452 -0.672697 + outer loop + vertex 1.245 2.055 2.50806 + vertex 1.24784 2.05374 2.50512 + vertex 1.24549 2.05144 2.50797 + endloop + endfacet + facet normal -0.104851 -0.949883 -0.294498 + outer loop + vertex 1.25113 2.05115 2.50691 + vertex 1.249 2.04993 2.51158 + vertex 1.24549 2.05144 2.50797 + endloop + endfacet + facet normal -0.0485292 -0.937634 -0.344221 + outer loop + vertex 1.249 2.04993 2.51158 + vertex 1.24369 2.05007 2.51197 + vertex 1.24549 2.05144 2.50797 + endloop + endfacet + facet normal -0.0262429 -0.999517 -0.0166156 + outer loop + vertex 1.249 2.04993 2.51158 + vertex 1.24788 2.04989 2.5162 + vertex 1.24369 2.05007 2.51197 + endloop + endfacet + facet normal 0.0155649 -0.998198 -0.0579512 + outer loop + vertex 1.24788 2.04989 2.5162 + vertex 1.24286 2.0498 2.51638 + vertex 1.24369 2.05007 2.51197 + endloop + endfacet + facet normal 0.0274192 -0.958796 0.282769 + outer loop + vertex 1.24788 2.04989 2.5162 + vertex 1.24662 2.051 2.52011 + vertex 1.24286 2.0498 2.51638 + endloop + endfacet + facet normal 0.0245714 -0.958091 0.28541 + outer loop + vertex 1.24662 2.051 2.52011 + vertex 1.24151 2.05101 2.52056 + vertex 1.24286 2.0498 2.51638 + endloop + endfacet + facet normal 0.060254 -0.723358 0.687839 + outer loop + vertex 1.24662 2.051 2.52011 + vertex 1.2447 2.05334 2.52273 + vertex 1.24151 2.05101 2.52056 + endloop + endfacet + facet normal 0.067393 -0.720337 0.690343 + outer loop + vertex 1.2495 2.05323 2.52215 + vertex 1.2447 2.05334 2.52273 + vertex 1.24662 2.051 2.52011 + endloop + endfacet + facet normal -0.707572 -0.546358 -0.448146 + outer loop + vertex 1.24784 2.05374 2.50512 + vertex 1.245 2.055 2.50806 + vertex 1.245 2.05751 2.505 + endloop + endfacet + facet normal 0.000122118 -0.030488 -0.999535 + outer loop + vertex 1.25 2.05753 2.505 + vertex 1.24784 2.05374 2.50512 + vertex 1.245 2.05751 2.505 + endloop + endfacet + facet normal 0.232756 0.455824 0.859098 + outer loop + vertex 1.2486 2.14858 2.49581 + vertex 1.24727 2.15202 2.49434 + vertex 1.24549 2.14977 2.49602 + endloop + endfacet + facet normal 0.191733 0.336831 0.921837 + outer loop + vertex 1.24549 2.14977 2.49602 + vertex 1.24632 2.14576 2.49731 + vertex 1.2486 2.14858 2.49581 + endloop + endfacet + facet normal 0.199159 0.337752 0.919923 + outer loop + vertex 1.24549 2.14977 2.49602 + vertex 1.24165 2.14945 2.49697 + vertex 1.24632 2.14576 2.49731 + endloop + endfacet + facet normal 0.227421 0.45961 0.858509 + outer loop + vertex 1.24322 2.15219 2.49532 + vertex 1.24549 2.14977 2.49602 + vertex 1.24727 2.15202 2.49434 + endloop + endfacet + facet normal 0.215048 0.580713 0.785192 + outer loop + vertex 1.24322 2.15219 2.49532 + vertex 1.24727 2.15202 2.49434 + vertex 1.2424 2.15525 2.49328 + endloop + endfacet + facet normal 0.225249 0.592274 0.773612 + outer loop + vertex 1.2424 2.15525 2.49328 + vertex 1.24727 2.15202 2.49434 + vertex 1.24724 2.15533 2.49182 + endloop + endfacet + facet normal 0.183431 0.426291 0.885793 + outer loop + vertex 1.24549 2.14977 2.49602 + vertex 1.24322 2.15219 2.49532 + vertex 1.24165 2.14945 2.49697 + endloop + endfacet + facet normal 0.131541 0.826537 0.547297 + outer loop + vertex 1.24936 2.16048 2.48328 + vertex 1.24762 2.16257 2.48055 + vertex 1.24543 2.1615 2.48268 + endloop + endfacet + facet normal 0.153437 0.891085 0.427112 + outer loop + vertex 1.24543 2.1615 2.48268 + vertex 1.24156 2.16163 2.4838 + vertex 1.24536 2.15981 2.48624 + endloop + endfacet + facet normal 0.166224 0.889119 0.426422 + outer loop + vertex 1.24543 2.1615 2.48268 + vertex 1.24536 2.15981 2.48624 + vertex 1.24936 2.16048 2.48328 + endloop + endfacet + facet normal 0.170203 0.886099 0.431115 + outer loop + vertex 1.24936 2.16048 2.48328 + vertex 1.24536 2.15981 2.48624 + vertex 1.24893 2.15912 2.48625 + endloop + endfacet + facet normal 0.15952 0.833288 0.529324 + outer loop + vertex 1.24893 2.15912 2.48625 + vertex 1.24536 2.15981 2.48624 + vertex 1.2486 2.15757 2.4888 + endloop + endfacet + facet normal 0.179844 0.84094 0.510368 + outer loop + vertex 1.2486 2.15757 2.4888 + vertex 1.24536 2.15981 2.48624 + vertex 1.24374 2.15784 2.49005 + endloop + endfacet + facet normal 0.189081 0.726604 0.660526 + outer loop + vertex 1.24724 2.15533 2.49182 + vertex 1.24374 2.15784 2.49005 + vertex 1.2424 2.15525 2.49328 + endloop + endfacet + facet normal 0.207827 0.738926 0.640934 + outer loop + vertex 1.2486 2.15757 2.4888 + vertex 1.24374 2.15784 2.49005 + vertex 1.24724 2.15533 2.49182 + endloop + endfacet + facet normal 0.20472 0.775791 0.596857 + outer loop + vertex 1.24762 2.16257 2.48055 + vertex 1.24347 2.1638 2.48037 + vertex 1.24543 2.1615 2.48268 + endloop + endfacet + facet normal -0.00218096 0.131955 0.991253 + outer loop + vertex 1.24762 2.16257 2.48055 + vertex 1.25 2.16672 2.48 + vertex 1.24347 2.1638 2.48037 + endloop + endfacet + facet normal 0.00674269 0.112315 0.99365 + outer loop + vertex 1.25 2.16672 2.48 + vertex 1.245 2.16702 2.48 + vertex 1.24347 2.1638 2.48037 + endloop + endfacet + facet normal 0.199693 0.774659 0.600021 + outer loop + vertex 1.24543 2.1615 2.48268 + vertex 1.24347 2.1638 2.48037 + vertex 1.24156 2.16163 2.4838 + endloop + endfacet + facet normal 0.0933667 -0.982829 0.159154 + outer loop + vertex 1.255 0.862917 2.475 + vertex 1.25181 0.862926 2.47692 + vertex 1.25 0.862442 2.475 + endloop + endfacet + facet normal 0.0970808 -0.983022 0.155701 + outer loop + vertex 1.25181 0.862926 2.47692 + vertex 1.25 0.863234 2.48 + vertex 1.25 0.862442 2.475 + endloop + endfacet + facet normal 0.159396 -0.933525 0.32113 + outer loop + vertex 1.25077 0.86381 2.48001 + vertex 1.25181 0.862926 2.47692 + vertex 1.25472 0.863992 2.47858 + endloop + endfacet + facet normal 0.162459 -0.932718 0.321938 + outer loop + vertex 1.25077 0.86381 2.48001 + vertex 1.24714 0.863143 2.47991 + vertex 1.25181 0.862926 2.47692 + endloop + endfacet + facet normal -0.0280367 0.992858 -0.115961 + outer loop + vertex 1.24714 0.863143 2.47991 + vertex 1.25 0.863234 2.48 + vertex 1.25181 0.862926 2.47692 + endloop + endfacet + facet normal 0.158651 -0.918197 0.362966 + outer loop + vertex 1.25077 0.86381 2.48001 + vertex 1.24841 0.864432 2.48262 + vertex 1.24714 0.863143 2.47991 + endloop + endfacet + facet normal 0.180179 -0.906451 0.381945 + outer loop + vertex 1.25472 0.863992 2.47858 + vertex 1.25249 0.865382 2.48293 + vertex 1.25077 0.86381 2.48001 + endloop + endfacet + facet normal 0.181734 -0.906513 0.38106 + outer loop + vertex 1.24841 0.864432 2.48262 + vertex 1.25077 0.86381 2.48001 + vertex 1.25249 0.865382 2.48293 + endloop + endfacet + facet normal 0.1704 -0.879114 0.445109 + outer loop + vertex 1.24841 0.864432 2.48262 + vertex 1.25249 0.865382 2.48293 + vertex 1.24731 0.866375 2.48688 + endloop + endfacet + facet normal 0.178951 -0.872497 0.454672 + outer loop + vertex 1.24731 0.866375 2.48688 + vertex 1.25249 0.865382 2.48293 + vertex 1.25211 0.867244 2.48666 + endloop + endfacet + facet normal 0.173048 -0.814782 0.55334 + outer loop + vertex 1.25211 0.867244 2.48666 + vertex 1.25022 0.868844 2.4896 + vertex 1.24731 0.866375 2.48688 + endloop + endfacet + facet normal 0.194286 -0.804444 0.561359 + outer loop + vertex 1.25432 0.869046 2.48847 + vertex 1.25022 0.868844 2.4896 + vertex 1.25211 0.867244 2.48666 + endloop + endfacet + facet normal 0.217135 -0.719905 0.659234 + outer loop + vertex 1.25022 0.868844 2.4896 + vertex 1.25432 0.869046 2.48847 + vertex 1.25249 0.871142 2.49136 + endloop + endfacet + facet normal 0.232212 -0.72582 0.647505 + outer loop + vertex 1.24952 0.870577 2.49179 + vertex 1.25022 0.868844 2.4896 + vertex 1.25249 0.871142 2.49136 + endloop + endfacet + facet normal 0.22624 -0.608256 0.760816 + outer loop + vertex 1.25249 0.871142 2.49136 + vertex 1.24971 0.87331 2.49392 + vertex 1.24952 0.870577 2.49179 + endloop + endfacet + facet normal 0.230693 -0.604505 0.762466 + outer loop + vertex 1.25502 0.87441 2.49319 + vertex 1.24971 0.87331 2.49392 + vertex 1.25249 0.871142 2.49136 + endloop + endfacet + facet normal 0.255215 -0.512454 0.819912 + outer loop + vertex 1.25006 0.876811 2.496 + vertex 1.24727 0.875262 2.4959 + vertex 1.24971 0.87331 2.49392 + endloop + endfacet + facet normal 0.232199 -0.513752 0.825919 + outer loop + vertex 1.25006 0.876811 2.496 + vertex 1.24971 0.87331 2.49392 + vertex 1.25343 0.877245 2.49533 + endloop + endfacet + facet normal 0.220074 -0.505335 0.834388 + outer loop + vertex 1.25343 0.877245 2.49533 + vertex 1.24971 0.87331 2.49392 + vertex 1.25502 0.87441 2.49319 + endloop + endfacet + facet normal 0.185601 -0.392099 0.901005 + outer loop + vertex 1.25006 0.876811 2.496 + vertex 1.24837 0.879023 2.49731 + vertex 1.24727 0.875262 2.4959 + endloop + endfacet + facet normal 0.229954 -0.403318 0.885695 + outer loop + vertex 1.25343 0.877245 2.49533 + vertex 1.25222 0.879531 2.49668 + vertex 1.25006 0.876811 2.496 + endloop + endfacet + facet normal 0.198881 -0.38269 0.902216 + outer loop + vertex 1.25222 0.879531 2.49668 + vertex 1.24837 0.879023 2.49731 + vertex 1.25006 0.876811 2.496 + endloop + endfacet + facet normal 0.193942 -0.309357 0.930959 + outer loop + vertex 1.25222 0.879531 2.49668 + vertex 1.25371 0.883665 2.49774 + vertex 1.24837 0.879023 2.49731 + endloop + endfacet + facet normal -0.328296 0.285247 -0.900476 + outer loop + vertex 1.25205 0.973387 2.50632 + vertex 1.25581 0.97339 2.50495 + vertex 1.255 0.972626 2.505 + endloop + endfacet + facet normal -0.0820498 -0.931226 0.355086 + outer loop + vertex 1.25205 0.973387 2.50632 + vertex 1.255 0.972626 2.505 + vertex 1.25 0.974973 2.51 + endloop + endfacet + facet normal -0.0261178 0.894616 -0.446071 + outer loop + vertex 1.25 0.974973 2.51 + vertex 1.255 0.972626 2.505 + vertex 1.25 0.97248 2.505 + endloop + endfacet + facet normal 0.373508 -0.758214 0.534419 + outer loop + vertex 1.25205 0.973387 2.50632 + vertex 1.25 0.974973 2.51 + vertex 1.24989 0.973725 2.5083 + endloop + endfacet + facet normal -0.0487982 0.942937 0.329375 + outer loop + vertex 1.2489 0.972673 2.51613 + vertex 1.25408 0.972547 2.51726 + vertex 1.25139 0.973511 2.5141 + endloop + endfacet + facet normal -0.114041 0.959847 0.256296 + outer loop + vertex 1.2481 0.973593 2.51233 + vertex 1.2489 0.972673 2.51613 + vertex 1.25139 0.973511 2.5141 + endloop + endfacet + facet normal -0.114 0.783072 0.611394 + outer loop + vertex 1.25408 0.972547 2.51726 + vertex 1.2489 0.972673 2.51613 + vertex 1.25317 0.970645 2.51952 + endloop + endfacet + facet normal 0.0291454 0.87377 0.485466 + outer loop + vertex 1.25317 0.970645 2.51952 + vertex 1.2489 0.972673 2.51613 + vertex 1.24805 0.970573 2.51996 + endloop + endfacet + facet normal 0.107356 0.542091 0.833434 + outer loop + vertex 1.25117 0.967753 2.52139 + vertex 1.24805 0.970573 2.51996 + vertex 1.24615 0.967594 2.52214 + endloop + endfacet + facet normal 0.0660251 0.508984 0.85824 + outer loop + vertex 1.25317 0.970645 2.51952 + vertex 1.24805 0.970573 2.51996 + vertex 1.25117 0.967753 2.52139 + endloop + endfacet + facet normal -0.0613184 0.984128 -0.166529 + outer loop + vertex 1.25581 0.97339 2.50495 + vertex 1.25205 0.973387 2.50632 + vertex 1.25354 0.973815 2.5083 + endloop + endfacet + facet normal -0.0248185 0.980837 -0.193245 + outer loop + vertex 1.24989 0.973725 2.5083 + vertex 1.25354 0.973815 2.5083 + vertex 1.25205 0.973387 2.50632 + endloop + endfacet + facet normal -0.0249307 0.999508 -0.0190288 + outer loop + vertex 1.24989 0.973725 2.5083 + vertex 1.25022 0.973778 2.51069 + vertex 1.25354 0.973815 2.5083 + endloop + endfacet + facet normal -0.0247748 0.999516 -0.0188122 + outer loop + vertex 1.25022 0.973778 2.51069 + vertex 1.25397 0.973906 2.51253 + vertex 1.25354 0.973815 2.5083 + endloop + endfacet + facet normal -0.0210994 0.996126 0.0853691 + outer loop + vertex 1.25139 0.973511 2.5141 + vertex 1.25022 0.973778 2.51069 + vertex 1.2481 0.973593 2.51233 + endloop + endfacet + facet normal -0.0863829 0.990463 0.107336 + outer loop + vertex 1.25397 0.973906 2.51253 + vertex 1.25022 0.973778 2.51069 + vertex 1.25139 0.973511 2.5141 + endloop + endfacet + facet normal -0.687125 -0.236348 -0.687021 + outer loop + vertex 1.25574 2.05195 2.50452 + vertex 1.25421 2.055 2.505 + vertex 1.255 2.055 2.50421 + endloop + endfacet + facet normal 0.0821124 -0.493691 -0.865752 + outer loop + vertex 1.25421 2.055 2.505 + vertex 1.25113 2.05115 2.50691 + vertex 1.24784 2.05374 2.50512 + endloop + endfacet + facet normal -0.447109 -0.0834463 -0.890579 + outer loop + vertex 1.25421 2.055 2.505 + vertex 1.25574 2.05195 2.50452 + vertex 1.25113 2.05115 2.50691 + endloop + endfacet + facet normal -0.126582 -0.840444 -0.526907 + outer loop + vertex 1.25574 2.05195 2.50452 + vertex 1.2553 2.04994 2.50783 + vertex 1.25113 2.05115 2.50691 + endloop + endfacet + facet normal -0.240727 -0.956512 -0.164726 + outer loop + vertex 1.2553 2.04994 2.50783 + vertex 1.25392 2.04965 2.51151 + vertex 1.25113 2.05115 2.50691 + endloop + endfacet + facet normal -0.0585146 -0.959419 -0.275846 + outer loop + vertex 1.25392 2.04965 2.51151 + vertex 1.249 2.04993 2.51158 + vertex 1.25113 2.05115 2.50691 + endloop + endfacet + facet normal -0.0563268 -0.998011 0.0283098 + outer loop + vertex 1.25392 2.04965 2.51151 + vertex 1.2528 2.04984 2.51599 + vertex 1.249 2.04993 2.51158 + endloop + endfacet + facet normal -0.00899821 -0.999882 -0.0124182 + outer loop + vertex 1.2528 2.04984 2.51599 + vertex 1.24788 2.04989 2.5162 + vertex 1.249 2.04993 2.51158 + endloop + endfacet + facet normal 0.00396858 -0.956555 0.291524 + outer loop + vertex 1.2528 2.04984 2.51599 + vertex 1.25146 2.05099 2.51978 + vertex 1.24788 2.04989 2.5162 + endloop + endfacet + facet normal 0.0168601 -0.959943 0.279688 + outer loop + vertex 1.25146 2.05099 2.51978 + vertex 1.24662 2.051 2.52011 + vertex 1.24788 2.04989 2.5162 + endloop + endfacet + facet normal 0.0461722 -0.706999 0.705706 + outer loop + vertex 1.25146 2.05099 2.51978 + vertex 1.2495 2.05323 2.52215 + vertex 1.24662 2.051 2.52011 + endloop + endfacet + facet normal 0.0287587 -0.714824 0.698713 + outer loop + vertex 1.25429 2.05299 2.5217 + vertex 1.2495 2.05323 2.52215 + vertex 1.25146 2.05099 2.51978 + endloop + endfacet + facet normal -0.013618 -0.0226621 -0.99965 + outer loop + vertex 1.25421 2.055 2.505 + vertex 1.24784 2.05374 2.50512 + vertex 1.25 2.05753 2.505 + endloop + endfacet + facet normal 0.178562 0.268748 0.946515 + outer loop + vertex 1.25331 2.10295 2.5087 + vertex 1.25174 2.10579 2.50819 + vertex 1.24868 2.10295 2.50957 + endloop + endfacet + facet normal 0.245593 0.71582 0.653671 + outer loop + vertex 1.25428 2.15431 2.49062 + vertex 1.25232 2.15642 2.48906 + vertex 1.25064 2.1554 2.4908 + endloop + endfacet + facet normal 0.222064 0.620905 0.751774 + outer loop + vertex 1.25064 2.1554 2.4908 + vertex 1.25134 2.15293 2.49264 + vertex 1.25428 2.15431 2.49062 + endloop + endfacet + facet normal 0.212511 0.620494 0.754868 + outer loop + vertex 1.25064 2.1554 2.4908 + vertex 1.24724 2.15533 2.49182 + vertex 1.25134 2.15293 2.49264 + endloop + endfacet + facet normal 0.19346 0.596215 0.779167 + outer loop + vertex 1.24724 2.15533 2.49182 + vertex 1.24727 2.15202 2.49434 + vertex 1.25134 2.15293 2.49264 + endloop + endfacet + facet normal 0.204035 0.843593 0.49671 + outer loop + vertex 1.24936 2.16048 2.48328 + vertex 1.25451 2.16008 2.48185 + vertex 1.2515 2.16224 2.47942 + endloop + endfacet + facet normal 0.216928 0.837712 0.501179 + outer loop + vertex 1.24762 2.16257 2.48055 + vertex 1.24936 2.16048 2.48328 + vertex 1.2515 2.16224 2.47942 + endloop + endfacet + facet normal 0.193925 0.870244 0.452845 + outer loop + vertex 1.25451 2.16008 2.48185 + vertex 1.24936 2.16048 2.48328 + vertex 1.25253 2.15832 2.48608 + endloop + endfacet + facet normal 0.215159 0.875437 0.432801 + outer loop + vertex 1.25253 2.15832 2.48608 + vertex 1.24936 2.16048 2.48328 + vertex 1.24893 2.15912 2.48625 + endloop + endfacet + facet normal 0.190312 0.757349 0.624663 + outer loop + vertex 1.25232 2.15642 2.48906 + vertex 1.2486 2.15757 2.4888 + vertex 1.25064 2.1554 2.4908 + endloop + endfacet + facet normal 0.214565 0.816074 0.536643 + outer loop + vertex 1.25232 2.15642 2.48906 + vertex 1.25253 2.15832 2.48608 + vertex 1.2486 2.15757 2.4888 + endloop + endfacet + facet normal 0.208171 0.822576 0.529182 + outer loop + vertex 1.25253 2.15832 2.48608 + vertex 1.24893 2.15912 2.48625 + vertex 1.2486 2.15757 2.4888 + endloop + endfacet + facet normal 0.174073 0.752136 0.635603 + outer loop + vertex 1.25064 2.1554 2.4908 + vertex 1.2486 2.15757 2.4888 + vertex 1.24724 2.15533 2.49182 + endloop + endfacet + facet normal 0.0369344 0.335747 0.941228 + outer loop + vertex 1.255 2.16714 2.475 + vertex 1.25 2.16769 2.475 + vertex 1.25319 2.16405 2.47617 + endloop + endfacet + facet normal 0.723548 0.677637 0.131476 + outer loop + vertex 1.25319 2.16405 2.47617 + vertex 1.25 2.16769 2.475 + vertex 1.25 2.16672 2.48 + endloop + endfacet + facet normal 0.276095 -0.0319043 0.960601 + outer loop + vertex 1.2515 2.16224 2.47942 + vertex 1.25 2.16672 2.48 + vertex 1.24762 2.16257 2.48055 + endloop + endfacet + facet normal 0.816866 0.204014 0.539545 + outer loop + vertex 1.25319 2.16405 2.47617 + vertex 1.25 2.16672 2.48 + vertex 1.2515 2.16224 2.47942 + endloop + endfacet + facet normal 0.0363428 -0.837312 0.545517 + outer loop + vertex 1.26 0.863134 2.475 + vertex 1.25765 0.863226 2.4753 + vertex 1.255 0.862917 2.475 + endloop + endfacet + facet normal 0.0960208 -0.981852 0.163544 + outer loop + vertex 1.25765 0.863226 2.4753 + vertex 1.25181 0.862926 2.47692 + vertex 1.255 0.862917 2.475 + endloop + endfacet + facet normal 0.143739 -0.927627 0.344742 + outer loop + vertex 1.25765 0.863226 2.4753 + vertex 1.25472 0.863992 2.47858 + vertex 1.25181 0.862926 2.47692 + endloop + endfacet + facet normal 0.172412 -0.914031 0.367181 + outer loop + vertex 1.25886 0.864171 2.47708 + vertex 1.25472 0.863992 2.47858 + vertex 1.25765 0.863226 2.4753 + endloop + endfacet + facet normal 0.174764 -0.910785 0.37407 + outer loop + vertex 1.25472 0.863992 2.47858 + vertex 1.25886 0.864171 2.47708 + vertex 1.25792 0.865385 2.48048 + endloop + endfacet + facet normal 0.17158 -0.909546 0.378531 + outer loop + vertex 1.25249 0.865382 2.48293 + vertex 1.25472 0.863992 2.47858 + vertex 1.25792 0.865385 2.48048 + endloop + endfacet + facet normal 0.194853 -0.881503 0.430098 + outer loop + vertex 1.25792 0.865385 2.48048 + vertex 1.25663 0.867238 2.48486 + vertex 1.25249 0.865382 2.48293 + endloop + endfacet + facet normal 0.179358 -0.872413 0.454672 + outer loop + vertex 1.25663 0.867238 2.48486 + vertex 1.25211 0.867244 2.48666 + vertex 1.25249 0.865382 2.48293 + endloop + endfacet + facet normal 0.214716 -0.811519 0.543447 + outer loop + vertex 1.25663 0.867238 2.48486 + vertex 1.25432 0.869046 2.48847 + vertex 1.25211 0.867244 2.48666 + endloop + endfacet + facet normal 0.172847 -0.832123 0.526968 + outer loop + vertex 1.25795 0.869107 2.48738 + vertex 1.25432 0.869046 2.48847 + vertex 1.25663 0.867238 2.48486 + endloop + endfacet + facet normal 0.210408 -0.723266 0.657735 + outer loop + vertex 1.25432 0.869046 2.48847 + vertex 1.25795 0.869107 2.48738 + vertex 1.25746 0.871517 2.49019 + endloop + endfacet + facet normal 0.210571 -0.723363 0.657576 + outer loop + vertex 1.25249 0.871142 2.49136 + vertex 1.25432 0.869046 2.48847 + vertex 1.25746 0.871517 2.49019 + endloop + endfacet + facet normal 0.22692 -0.602914 0.764854 + outer loop + vertex 1.25746 0.871517 2.49019 + vertex 1.25502 0.87441 2.49319 + vertex 1.25249 0.871142 2.49136 + endloop + endfacet + facet normal 0.213795 -0.611122 0.762116 + outer loop + vertex 1.25994 0.875183 2.49243 + vertex 1.25502 0.87441 2.49319 + vertex 1.25746 0.871517 2.49019 + endloop + endfacet + facet normal 0.206928 -0.476167 0.854661 + outer loop + vertex 1.25994 0.875183 2.49243 + vertex 1.25848 0.878744 2.49477 + vertex 1.25502 0.87441 2.49319 + endloop + endfacet + facet normal 0.0247955 -0.0968566 -0.994989 + outer loop + vertex 1.26 0.973906 2.505 + vertex 1.255 0.972626 2.505 + vertex 1.25581 0.97339 2.50495 + endloop + endfacet + facet normal 0.12295 -0.988967 -0.0826298 + outer loop + vertex 1.25935 0.973904 2.50405 + vertex 1.26 0.973906 2.505 + vertex 1.25581 0.97339 2.50495 + endloop + endfacet + facet normal -0.139337 0.907671 0.395876 + outer loop + vertex 1.25485 0.973451 2.51545 + vertex 1.25139 0.973511 2.5141 + vertex 1.25408 0.972547 2.51726 + endloop + endfacet + facet normal -0.0799364 0.904254 0.419447 + outer loop + vertex 1.25762 0.972737 2.51752 + vertex 1.25485 0.973451 2.51545 + vertex 1.25408 0.972547 2.51726 + endloop + endfacet + facet normal -0.0899547 0.727708 0.679963 + outer loop + vertex 1.25762 0.972737 2.51752 + vertex 1.25408 0.972547 2.51726 + vertex 1.25854 0.970856 2.51966 + endloop + endfacet + facet normal -0.0461687 0.774135 0.631335 + outer loop + vertex 1.25854 0.970856 2.51966 + vertex 1.25408 0.972547 2.51726 + vertex 1.25317 0.970645 2.51952 + endloop + endfacet + facet normal 0.0529524 0.51591 0.855005 + outer loop + vertex 1.25675 0.967758 2.52104 + vertex 1.25317 0.970645 2.51952 + vertex 1.25117 0.967753 2.52139 + endloop + endfacet + facet normal -0.0392818 0.42694 0.903426 + outer loop + vertex 1.25854 0.970856 2.51966 + vertex 1.25317 0.970645 2.51952 + vertex 1.25675 0.967758 2.52104 + endloop + endfacet + facet normal -0.182854 0.969128 -0.165391 + outer loop + vertex 1.25581 0.97339 2.50495 + vertex 1.25912 0.974351 2.50692 + vertex 1.25935 0.973904 2.50405 + endloop + endfacet + facet normal -0.147337 0.963796 -0.222237 + outer loop + vertex 1.25354 0.973815 2.5083 + vertex 1.25912 0.974351 2.50692 + vertex 1.25581 0.97339 2.50495 + endloop + endfacet + facet normal -0.0971795 0.995245 -0.00665545 + outer loop + vertex 1.25912 0.974351 2.50692 + vertex 1.25354 0.973815 2.5083 + vertex 1.25818 0.97429 2.51161 + endloop + endfacet + facet normal -0.0935054 0.995548 -0.0118407 + outer loop + vertex 1.25818 0.97429 2.51161 + vertex 1.25354 0.973815 2.5083 + vertex 1.25397 0.973906 2.51253 + endloop + endfacet + facet normal -0.0486912 0.984619 0.167796 + outer loop + vertex 1.25485 0.973451 2.51545 + vertex 1.25397 0.973906 2.51253 + vertex 1.25139 0.973511 2.5141 + endloop + endfacet + facet normal -0.0488 0.984608 0.167827 + outer loop + vertex 1.25485 0.973451 2.51545 + vertex 1.25823 0.973626 2.51541 + vertex 1.25397 0.973906 2.51253 + endloop + endfacet + facet normal -0.0521078 0.983609 0.172622 + outer loop + vertex 1.25823 0.973626 2.51541 + vertex 1.25818 0.97429 2.51161 + vertex 1.25397 0.973906 2.51253 + endloop + endfacet + facet normal -0.0430013 0.925159 0.377137 + outer loop + vertex 1.25823 0.973626 2.51541 + vertex 1.25485 0.973451 2.51545 + vertex 1.25762 0.972737 2.51752 + endloop + endfacet + facet normal 0.22832 -0.688429 -0.688429 + outer loop + vertex 1.25574 2.05195 2.50452 + vertex 1.26 2.055 2.50288 + vertex 1.26 2.05288 2.505 + endloop + endfacet + facet normal -0.253824 -0.157758 -0.954298 + outer loop + vertex 1.255 2.055 2.50421 + vertex 1.26 2.055 2.50288 + vertex 1.25574 2.05195 2.50452 + endloop + endfacet + facet normal 0.223864 -0.646873 -0.729 + outer loop + vertex 1.26 2.05288 2.505 + vertex 1.25902 2.04997 2.50728 + vertex 1.25574 2.05195 2.50452 + endloop + endfacet + facet normal -0.0700811 -0.848648 -0.524294 + outer loop + vertex 1.25902 2.04997 2.50728 + vertex 1.2553 2.04994 2.50783 + vertex 1.25574 2.05195 2.50452 + endloop + endfacet + facet normal -0.0141811 -0.987643 -0.156075 + outer loop + vertex 1.25902 2.04997 2.50728 + vertex 1.25826 2.04933 2.51141 + vertex 1.2553 2.04994 2.50783 + endloop + endfacet + facet normal -0.0758754 -0.991502 -0.105673 + outer loop + vertex 1.25826 2.04933 2.51141 + vertex 1.25392 2.04965 2.51151 + vertex 1.2553 2.04994 2.50783 + endloop + endfacet + facet normal -0.0719213 -0.994757 0.0726975 + outer loop + vertex 1.25826 2.04933 2.51141 + vertex 1.25742 2.0497 2.51566 + vertex 1.25392 2.04965 2.51151 + endloop + endfacet + facet normal -0.0278085 -0.998983 0.0354905 + outer loop + vertex 1.25742 2.0497 2.51566 + vertex 1.2528 2.04984 2.51599 + vertex 1.25392 2.04965 2.51151 + endloop + endfacet + facet normal -0.00805459 -0.956981 0.29004 + outer loop + vertex 1.25742 2.0497 2.51566 + vertex 1.25615 2.05084 2.51938 + vertex 1.2528 2.04984 2.51599 + endloop + endfacet + facet normal -0.00609934 -0.957531 0.288265 + outer loop + vertex 1.25615 2.05084 2.51938 + vertex 1.25146 2.05099 2.51978 + vertex 1.2528 2.04984 2.51599 + endloop + endfacet + facet normal 0.0357487 -0.719632 0.693435 + outer loop + vertex 1.25615 2.05084 2.51938 + vertex 1.25429 2.05299 2.5217 + vertex 1.25146 2.05099 2.51978 + endloop + endfacet + facet normal -0.0402991 -0.749962 0.660253 + outer loop + vertex 1.25832 2.05233 2.5212 + vertex 1.25429 2.05299 2.5217 + vertex 1.25615 2.05084 2.51938 + endloop + endfacet + facet normal 0.177907 0.268423 0.94673 + outer loop + vertex 1.25331 2.10295 2.5087 + vertex 1.25637 2.10577 2.50732 + vertex 1.25174 2.10579 2.50819 + endloop + endfacet + facet normal 0.176706 0.293671 0.939432 + outer loop + vertex 1.25882 2.12759 2.50043 + vertex 1.2548 2.12901 2.50074 + vertex 1.2565 2.12438 2.50187 + endloop + endfacet + facet normal 0.233462 0.461577 0.855828 + outer loop + vertex 1.25873 2.14657 2.49422 + vertex 1.25636 2.15103 2.49246 + vertex 1.25261 2.14886 2.49465 + endloop + endfacet + facet normal 0.2303 0.720899 0.653656 + outer loop + vertex 1.25428 2.15431 2.49062 + vertex 1.25945 2.15355 2.48964 + vertex 1.25606 2.15617 2.48795 + endloop + endfacet + facet normal 0.241653 0.714401 0.656685 + outer loop + vertex 1.25232 2.15642 2.48906 + vertex 1.25428 2.15431 2.49062 + vertex 1.25606 2.15617 2.48795 + endloop + endfacet + facet normal 0.249196 0.588565 0.769086 + outer loop + vertex 1.25636 2.15103 2.49246 + vertex 1.25428 2.15431 2.49062 + vertex 1.25134 2.15293 2.49264 + endloop + endfacet + facet normal 0.233586 0.583544 0.777762 + outer loop + vertex 1.25945 2.15355 2.48964 + vertex 1.25428 2.15431 2.49062 + vertex 1.25636 2.15103 2.49246 + endloop + endfacet + facet normal 0.173918 0.894236 0.412425 + outer loop + vertex 1.25451 2.16008 2.48185 + vertex 1.25946 2.15991 2.48012 + vertex 1.25613 2.16159 2.4779 + endloop + endfacet + facet normal 0.264476 0.86002 0.43637 + outer loop + vertex 1.2515 2.16224 2.47942 + vertex 1.25451 2.16008 2.48185 + vertex 1.25613 2.16159 2.4779 + endloop + endfacet + facet normal 0.184406 0.87683 0.444032 + outer loop + vertex 1.25946 2.15991 2.48012 + vertex 1.25451 2.16008 2.48185 + vertex 1.25825 2.15802 2.48437 + endloop + endfacet + facet normal 0.18045 0.875305 0.448642 + outer loop + vertex 1.25825 2.15802 2.48437 + vertex 1.25451 2.16008 2.48185 + vertex 1.25253 2.15832 2.48608 + endloop + endfacet + facet normal 0.212754 0.816467 0.536766 + outer loop + vertex 1.25606 2.15617 2.48795 + vertex 1.25253 2.15832 2.48608 + vertex 1.25232 2.15642 2.48906 + endloop + endfacet + facet normal 0.206004 0.812662 0.545107 + outer loop + vertex 1.25825 2.15802 2.48437 + vertex 1.25253 2.15832 2.48608 + vertex 1.25606 2.15617 2.48795 + endloop + endfacet + facet normal 0.000614372 0.00749088 0.999972 + outer loop + vertex 1.26 2.16673 2.475 + vertex 1.255 2.16714 2.475 + vertex 1.25858 2.16347 2.47503 + endloop + endfacet + facet normal 0.226282 0.227315 0.947166 + outer loop + vertex 1.25858 2.16347 2.47503 + vertex 1.255 2.16714 2.475 + vertex 1.25319 2.16405 2.47617 + endloop + endfacet + facet normal 0.297281 0.759065 0.579175 + outer loop + vertex 1.25613 2.16159 2.4779 + vertex 1.25319 2.16405 2.47617 + vertex 1.2515 2.16224 2.47942 + endloop + endfacet + facet normal 0.217794 0.720116 0.658786 + outer loop + vertex 1.25858 2.16347 2.47503 + vertex 1.25319 2.16405 2.47617 + vertex 1.25613 2.16159 2.4779 + endloop + endfacet + facet normal 0.0459222 0.666623 0.743979 + outer loop + vertex 1.26161 0.863857 2.47514 + vertex 1.265 0.863781 2.475 + vertex 1.26531 0.864283 2.47453 + endloop + endfacet + facet normal 0.0413884 -0.0128687 0.99906 + outer loop + vertex 1.26161 0.863857 2.47514 + vertex 1.25765 0.863226 2.4753 + vertex 1.265 0.863781 2.475 + endloop + endfacet + facet normal 0.0774892 -0.598881 0.79708 + outer loop + vertex 1.25765 0.863226 2.4753 + vertex 1.26 0.863134 2.475 + vertex 1.265 0.863781 2.475 + endloop + endfacet + facet normal 0.160474 -0.913123 0.374773 + outer loop + vertex 1.26161 0.863857 2.47514 + vertex 1.25886 0.864171 2.47708 + vertex 1.25765 0.863226 2.4753 + endloop + endfacet + facet normal 0.169132 -0.902315 0.396512 + outer loop + vertex 1.26531 0.864283 2.47453 + vertex 1.26367 0.865214 2.47735 + vertex 1.26161 0.863857 2.47514 + endloop + endfacet + facet normal 0.174076 -0.903172 0.392401 + outer loop + vertex 1.25886 0.864171 2.47708 + vertex 1.26161 0.863857 2.47514 + vertex 1.26367 0.865214 2.47735 + endloop + endfacet + facet normal 0.176606 -0.910292 0.374405 + outer loop + vertex 1.25886 0.864171 2.47708 + vertex 1.26367 0.865214 2.47735 + vertex 1.25792 0.865385 2.48048 + endloop + endfacet + facet normal 0.189482 -0.897871 0.397397 + outer loop + vertex 1.25792 0.865385 2.48048 + vertex 1.26367 0.865214 2.47735 + vertex 1.26167 0.866903 2.48212 + endloop + endfacet + facet normal 0.19376 -0.868265 0.456697 + outer loop + vertex 1.2604 0.868295 2.48531 + vertex 1.26167 0.866903 2.48212 + vertex 1.26437 0.868633 2.48426 + endloop + endfacet + facet normal 0.190016 -0.869577 0.455774 + outer loop + vertex 1.2604 0.868295 2.48531 + vertex 1.25663 0.867238 2.48486 + vertex 1.26167 0.866903 2.48212 + endloop + endfacet + facet normal 0.172801 -0.887903 0.426344 + outer loop + vertex 1.25663 0.867238 2.48486 + vertex 1.25792 0.865385 2.48048 + vertex 1.26167 0.866903 2.48212 + endloop + endfacet + facet normal 0.170824 -0.831951 0.527898 + outer loop + vertex 1.2604 0.868295 2.48531 + vertex 1.25795 0.869107 2.48738 + vertex 1.25663 0.867238 2.48486 + endloop + endfacet + facet normal 0.21504 -0.800355 0.559634 + outer loop + vertex 1.26437 0.868633 2.48426 + vertex 1.2615 0.870076 2.48743 + vertex 1.2604 0.868295 2.48531 + endloop + endfacet + facet normal 0.210191 -0.800052 0.561905 + outer loop + vertex 1.25795 0.869107 2.48738 + vertex 1.2604 0.868295 2.48531 + vertex 1.2615 0.870076 2.48743 + endloop + endfacet + facet normal 0.189258 -0.728442 0.658448 + outer loop + vertex 1.25795 0.869107 2.48738 + vertex 1.2615 0.870076 2.48743 + vertex 1.25746 0.871517 2.49019 + endloop + endfacet + facet normal 0.201827 -0.71468 0.6697 + outer loop + vertex 1.25746 0.871517 2.49019 + vertex 1.2615 0.870076 2.48743 + vertex 1.26246 0.87265 2.48989 + endloop + endfacet + facet normal 0.1824 -0.600073 0.778873 + outer loop + vertex 1.26246 0.87265 2.48989 + vertex 1.25994 0.875183 2.49243 + vertex 1.25746 0.871517 2.49019 + endloop + endfacet + facet normal 0.186071 -0.59752 0.779966 + outer loop + vertex 1.26437 0.875631 2.49171 + vertex 1.25994 0.875183 2.49243 + vertex 1.26246 0.87265 2.48989 + endloop + endfacet + facet normal 0.186423 -0.464626 0.865661 + outer loop + vertex 1.26437 0.875631 2.49171 + vertex 1.26351 0.879015 2.49372 + vertex 1.25994 0.875183 2.49243 + endloop + endfacet + facet normal 0.204077 -0.477355 0.854684 + outer loop + vertex 1.25994 0.875183 2.49243 + vertex 1.26351 0.879015 2.49372 + vertex 1.25848 0.878744 2.49477 + endloop + endfacet + facet normal 0.208441 -0.382878 0.899976 + outer loop + vertex 1.2629 0.882467 2.49533 + vertex 1.25848 0.878744 2.49477 + vertex 1.26351 0.879015 2.49372 + endloop + endfacet + facet normal 0.507302 -0.788301 -0.348176 + outer loop + vertex 1.2617 0.975 2.505 + vertex 1.26 0.973906 2.505 + vertex 1.25935 0.973904 2.50405 + endloop + endfacet + facet normal -0.0277627 0.615854 0.787371 + outer loop + vertex 1.25854 0.970856 2.51966 + vertex 1.26286 0.970006 2.52047 + vertex 1.26229 0.972162 2.51877 + endloop + endfacet + facet normal -0.0918486 0.72716 0.680295 + outer loop + vertex 1.25762 0.972737 2.51752 + vertex 1.25854 0.970856 2.51966 + vertex 1.26229 0.972162 2.51877 + endloop + endfacet + facet normal -0.0713157 0.441441 0.894452 + outer loop + vertex 1.26085 0.968657 2.52093 + vertex 1.25854 0.970856 2.51966 + vertex 1.25675 0.967758 2.52104 + endloop + endfacet + facet normal -0.0856175 0.429167 0.899158 + outer loop + vertex 1.26286 0.970006 2.52047 + vertex 1.25854 0.970856 2.51966 + vertex 1.26085 0.968657 2.52093 + endloop + endfacet + facet normal 0.0485106 0.994268 0.0952796 + outer loop + vertex 1.265 0.975 2.50332 + vertex 1.2617 0.975 2.505 + vertex 1.26349 0.974953 2.50458 + endloop + endfacet + facet normal 0.121688 -0.785983 0.606154 + outer loop + vertex 1.25935 0.973904 2.50405 + vertex 1.26349 0.974953 2.50458 + vertex 1.2617 0.975 2.505 + endloop + endfacet + facet normal -0.222011 0.960608 -0.167166 + outer loop + vertex 1.25935 0.973904 2.50405 + vertex 1.25912 0.974351 2.50692 + vertex 1.26349 0.974953 2.50458 + endloop + endfacet + facet normal -0.168687 0.983736 -0.0617105 + outer loop + vertex 1.25912 0.974351 2.50692 + vertex 1.26403 0.97525 2.50784 + vertex 1.26349 0.974953 2.50458 + endloop + endfacet + facet normal -0.185372 0.982239 0.0290477 + outer loop + vertex 1.26403 0.97525 2.50784 + vertex 1.25912 0.974351 2.50692 + vertex 1.26302 0.974956 2.51131 + endloop + endfacet + facet normal -0.1373 0.990419 -0.0147729 + outer loop + vertex 1.26302 0.974956 2.51131 + vertex 1.25912 0.974351 2.50692 + vertex 1.25818 0.97429 2.51161 + endloop + endfacet + facet normal -0.120757 0.970675 0.207865 + outer loop + vertex 1.26302 0.974956 2.51131 + vertex 1.25818 0.97429 2.51161 + vertex 1.26342 0.974013 2.51595 + endloop + endfacet + facet normal -0.0910407 0.980771 0.172625 + outer loop + vertex 1.26342 0.974013 2.51595 + vertex 1.25818 0.97429 2.51161 + vertex 1.25823 0.973626 2.51541 + endloop + endfacet + facet normal 0.00930209 0.920686 0.390192 + outer loop + vertex 1.26229 0.972162 2.51877 + vertex 1.25823 0.973626 2.51541 + vertex 1.25762 0.972737 2.51752 + endloop + endfacet + facet normal -0.116775 0.850709 0.512502 + outer loop + vertex 1.26342 0.974013 2.51595 + vertex 1.25823 0.973626 2.51541 + vertex 1.26229 0.972162 2.51877 + endloop + endfacet + facet normal -0.0740164 -0.660807 -0.746898 + outer loop + vertex 1.265 2.05232 2.505 + vertex 1.26359 2.04991 2.50727 + vertex 1.26 2.05288 2.505 + endloop + endfacet + facet normal -0.00975541 -0.614879 -0.788561 + outer loop + vertex 1.26359 2.04991 2.50727 + vertex 1.25902 2.04997 2.50728 + vertex 1.26 2.05288 2.505 + endloop + endfacet + facet normal -0.0134087 -0.989924 -0.140966 + outer loop + vertex 1.26359 2.04991 2.50727 + vertex 1.26259 2.04934 2.51142 + vertex 1.25902 2.04997 2.50728 + endloop + endfacet + facet normal 0.0012065 -0.988178 -0.153309 + outer loop + vertex 1.26259 2.04934 2.51142 + vertex 1.25826 2.04933 2.51141 + vertex 1.25902 2.04997 2.50728 + endloop + endfacet + facet normal 0.000720189 -0.997439 0.0715148 + outer loop + vertex 1.26259 2.04934 2.51142 + vertex 1.26119 2.04959 2.51498 + vertex 1.25826 2.04933 2.51141 + endloop + endfacet + facet normal -0.0146751 -0.996349 0.0841013 + outer loop + vertex 1.26119 2.04959 2.51498 + vertex 1.25742 2.0497 2.51566 + vertex 1.25826 2.04933 2.51141 + endloop + endfacet + facet normal 0.0273133 -0.950614 0.309173 + outer loop + vertex 1.26119 2.04959 2.51498 + vertex 1.26097 2.05084 2.51884 + vertex 1.25742 2.0497 2.51566 + endloop + endfacet + facet normal 0.0336001 -0.952456 0.302819 + outer loop + vertex 1.26097 2.05084 2.51884 + vertex 1.25615 2.05084 2.51938 + vertex 1.25742 2.0497 2.51566 + endloop + endfacet + facet normal 0.0652472 -0.80984 0.583011 + outer loop + vertex 1.26097 2.05084 2.51884 + vertex 1.25832 2.05233 2.5212 + vertex 1.25615 2.05084 2.51938 + endloop + endfacet + facet normal 0.184661 -0.724956 0.66358 + outer loop + vertex 1.26137 2.05306 2.52116 + vertex 1.25832 2.05233 2.5212 + vertex 1.26097 2.05084 2.51884 + endloop + endfacet + facet normal 0.178599 0.294259 0.93889 + outer loop + vertex 1.25882 2.12759 2.50043 + vertex 1.26076 2.12484 2.50092 + vertex 1.26341 2.12792 2.49945 + endloop + endfacet + facet normal 0.177163 0.293347 0.939447 + outer loop + vertex 1.26076 2.12484 2.50092 + vertex 1.25882 2.12759 2.50043 + vertex 1.2565 2.12438 2.50187 + endloop + endfacet + facet normal 0.193491 0.458044 0.867615 + outer loop + vertex 1.26266 2.1463 2.49349 + vertex 1.262 2.14944 2.49198 + vertex 1.25873 2.14657 2.49422 + endloop + endfacet + facet normal 0.201795 0.450273 0.869789 + outer loop + vertex 1.25873 2.14657 2.49422 + vertex 1.262 2.14944 2.49198 + vertex 1.25636 2.15103 2.49246 + endloop + endfacet + facet normal 0.200827 0.783389 0.588193 + outer loop + vertex 1.26341 2.15497 2.48708 + vertex 1.26214 2.15686 2.485 + vertex 1.25984 2.156 2.48692 + endloop + endfacet + facet normal 0.214269 0.710752 0.670016 + outer loop + vertex 1.25984 2.156 2.48692 + vertex 1.25606 2.15617 2.48795 + vertex 1.25945 2.15355 2.48964 + endloop + endfacet + facet normal 0.178248 0.718758 0.672022 + outer loop + vertex 1.25984 2.156 2.48692 + vertex 1.25945 2.15355 2.48964 + vertex 1.26341 2.15497 2.48708 + endloop + endfacet + facet normal 0.205907 0.686775 0.697096 + outer loop + vertex 1.26341 2.15497 2.48708 + vertex 1.25945 2.15355 2.48964 + vertex 1.26463 2.15222 2.48943 + endloop + endfacet + facet normal 0.231876 0.584993 0.777185 + outer loop + vertex 1.262 2.14944 2.49198 + vertex 1.25945 2.15355 2.48964 + vertex 1.25636 2.15103 2.49246 + endloop + endfacet + facet normal 0.17961 0.567508 0.803539 + outer loop + vertex 1.26463 2.15222 2.48943 + vertex 1.25945 2.15355 2.48964 + vertex 1.262 2.14944 2.49198 + endloop + endfacet + facet normal 0.0882756 0.808288 0.582133 + outer loop + vertex 1.26433 2.16021 2.47777 + vertex 1.26273 2.16221 2.47524 + vertex 1.26019 2.16128 2.47691 + endloop + endfacet + facet normal 0.168454 0.892191 0.419068 + outer loop + vertex 1.26019 2.16128 2.47691 + vertex 1.25613 2.16159 2.4779 + vertex 1.25946 2.15991 2.48012 + endloop + endfacet + facet normal 0.146077 0.897476 0.41617 + outer loop + vertex 1.26019 2.16128 2.47691 + vertex 1.25946 2.15991 2.48012 + vertex 1.26433 2.16021 2.47777 + endloop + endfacet + facet normal 0.158365 0.883912 0.440023 + outer loop + vertex 1.26433 2.16021 2.47777 + vertex 1.25946 2.15991 2.48012 + vertex 1.26308 2.15832 2.48202 + endloop + endfacet + facet normal 0.155885 0.820038 0.550669 + outer loop + vertex 1.26214 2.15686 2.485 + vertex 1.25825 2.15802 2.48437 + vertex 1.25984 2.156 2.48692 + endloop + endfacet + facet normal 0.179083 0.859254 0.479179 + outer loop + vertex 1.26214 2.15686 2.485 + vertex 1.26308 2.15832 2.48202 + vertex 1.25825 2.15802 2.48437 + endloop + endfacet + facet normal 0.158485 0.883977 0.439848 + outer loop + vertex 1.26308 2.15832 2.48202 + vertex 1.25946 2.15991 2.48012 + vertex 1.25825 2.15802 2.48437 + endloop + endfacet + facet normal 0.182903 0.823721 0.536684 + outer loop + vertex 1.25984 2.156 2.48692 + vertex 1.25825 2.15802 2.48437 + vertex 1.25606 2.15617 2.48795 + endloop + endfacet + facet normal 0.182917 0.715436 0.674309 + outer loop + vertex 1.26273 2.16221 2.47524 + vertex 1.25858 2.16347 2.47503 + vertex 1.26019 2.16128 2.47691 + endloop + endfacet + facet normal -0.0282041 0.0770623 0.996627 + outer loop + vertex 1.26273 2.16221 2.47524 + vertex 1.265 2.16615 2.475 + vertex 1.25858 2.16347 2.47503 + endloop + endfacet + facet normal 0.000856439 0.0073852 0.999972 + outer loop + vertex 1.265 2.16615 2.475 + vertex 1.26 2.16673 2.475 + vertex 1.25858 2.16347 2.47503 + endloop + endfacet + facet normal 0.213443 0.723045 0.656999 + outer loop + vertex 1.26019 2.16128 2.47691 + vertex 1.25858 2.16347 2.47503 + vertex 1.25613 2.16159 2.4779 + endloop + endfacet + facet normal -0.219814 0.735709 0.640636 + outer loop + vertex 1.26908 0.865 2.475 + vertex 1.26531 0.864283 2.47453 + vertex 1.265 0.863781 2.475 + endloop + endfacet + facet normal -0.199968 0.498514 0.843502 + outer loop + vertex 1.26531 0.864283 2.47453 + vertex 1.26908 0.865 2.475 + vertex 1.27 0.865369 2.475 + endloop + endfacet + facet normal 0.169284 -0.902256 0.396581 + outer loop + vertex 1.26531 0.864283 2.47453 + vertex 1.27 0.865369 2.475 + vertex 1.26367 0.865214 2.47735 + endloop + endfacet + facet normal 0.179701 -0.88686 0.425661 + outer loop + vertex 1.26367 0.865214 2.47735 + vertex 1.27 0.865369 2.475 + vertex 1.26815 0.865967 2.47703 + endloop + endfacet + facet normal 0.179861 -0.901094 0.394563 + outer loop + vertex 1.26815 0.865967 2.47703 + vertex 1.26709 0.867143 2.4802 + vertex 1.26367 0.865214 2.47735 + endloop + endfacet + facet normal 0.179904 -0.901105 0.394518 + outer loop + vertex 1.26709 0.867143 2.4802 + vertex 1.26167 0.866903 2.48212 + vertex 1.26367 0.865214 2.47735 + endloop + endfacet + facet normal 0.198783 -0.869794 0.451602 + outer loop + vertex 1.26709 0.867143 2.4802 + vertex 1.26437 0.868633 2.48426 + vertex 1.26167 0.866903 2.48212 + endloop + endfacet + facet normal 0.178892 -0.879139 0.441715 + outer loop + vertex 1.26852 0.868917 2.48315 + vertex 1.26437 0.868633 2.48426 + vertex 1.26709 0.867143 2.4802 + endloop + endfacet + facet normal 0.204148 -0.807023 0.55411 + outer loop + vertex 1.26437 0.868633 2.48426 + vertex 1.26852 0.868917 2.48315 + vertex 1.26704 0.871055 2.48681 + endloop + endfacet + facet normal 0.204866 -0.807226 0.553549 + outer loop + vertex 1.2615 0.870076 2.48743 + vertex 1.26437 0.868633 2.48426 + vertex 1.26704 0.871055 2.48681 + endloop + endfacet + facet normal 0.194448 -0.72568 0.659983 + outer loop + vertex 1.26591 0.873488 2.48981 + vertex 1.26704 0.871055 2.48681 + vertex 1.26952 0.873732 2.48902 + endloop + endfacet + facet normal 0.190394 -0.727096 0.659607 + outer loop + vertex 1.26591 0.873488 2.48981 + vertex 1.26246 0.87265 2.48989 + vertex 1.26704 0.871055 2.48681 + endloop + endfacet + facet normal 0.201572 -0.71467 0.669788 + outer loop + vertex 1.26246 0.87265 2.48989 + vertex 1.2615 0.870076 2.48743 + vertex 1.26704 0.871055 2.48681 + endloop + endfacet + facet normal 0.159528 -0.588312 0.792742 + outer loop + vertex 1.26591 0.873488 2.48981 + vertex 1.26437 0.875631 2.49171 + vertex 1.26246 0.87265 2.48989 + endloop + endfacet + facet normal 0.210315 -0.602802 0.769673 + outer loop + vertex 1.26952 0.873732 2.48902 + vertex 1.26761 0.875482 2.49091 + vertex 1.26591 0.873488 2.48981 + endloop + endfacet + facet normal 0.170292 -0.582443 0.794833 + outer loop + vertex 1.26761 0.875482 2.49091 + vertex 1.26437 0.875631 2.49171 + vertex 1.26591 0.873488 2.48981 + endloop + endfacet + facet normal 0.193571 -0.460664 0.86621 + outer loop + vertex 1.26761 0.875482 2.49091 + vertex 1.26861 0.879053 2.49259 + vertex 1.26437 0.875631 2.49171 + endloop + endfacet + facet normal 0.194971 -0.462119 0.86512 + outer loop + vertex 1.26861 0.879053 2.49259 + vertex 1.26351 0.879015 2.49372 + vertex 1.26437 0.875631 2.49171 + endloop + endfacet + facet normal 0.203324 -0.371463 0.905911 + outer loop + vertex 1.26861 0.879053 2.49259 + vertex 1.26813 0.883782 2.49463 + vertex 1.26351 0.879015 2.49372 + endloop + endfacet + facet normal 0.214863 -0.381346 0.899116 + outer loop + vertex 1.26351 0.879015 2.49372 + vertex 1.26813 0.883782 2.49463 + vertex 1.2629 0.882467 2.49533 + endloop + endfacet + facet normal 0.185218 -0.28871 0.93933 + outer loop + vertex 1.26867 0.905493 2.50144 + vertex 1.26364 0.904173 2.50202 + vertex 1.26579 0.901568 2.5008 + endloop + endfacet + facet normal 0.172404 -0.296505 0.939341 + outer loop + vertex 1.26876 0.955357 2.51637 + vertex 1.26369 0.954067 2.51689 + vertex 1.26573 0.951449 2.51569 + endloop + endfacet + facet normal 0.0377589 0.196642 0.979748 + outer loop + vertex 1.26286 0.970006 2.52047 + vertex 1.26333 0.967793 2.5209 + vertex 1.26719 0.969726 2.52036 + endloop + endfacet + facet normal 0.0604904 0.629261 0.774836 + outer loop + vertex 1.26286 0.970006 2.52047 + vertex 1.26719 0.969726 2.52036 + vertex 1.26229 0.972162 2.51877 + endloop + endfacet + facet normal -0.578515 0.0838142 0.811354 + outer loop + vertex 1.26832 0.972204 2.52091 + vertex 1.26671 0.972717 2.51971 + vertex 1.26719 0.969726 2.52036 + endloop + endfacet + facet normal -0.226228 0.173188 0.958555 + outer loop + vertex 1.26671 0.972717 2.51971 + vertex 1.26229 0.972162 2.51877 + vertex 1.26719 0.969726 2.52036 + endloop + endfacet + facet normal -0.4341 0.456634 0.776558 + outer loop + vertex 1.26832 0.972204 2.52091 + vertex 1.26858 0.973021 2.52058 + vertex 1.26671 0.972717 2.51971 + endloop + endfacet + facet normal 0.0812766 0.205041 0.975373 + outer loop + vertex 1.26333 0.967793 2.5209 + vertex 1.26286 0.970006 2.52047 + vertex 1.26085 0.968657 2.52093 + endloop + endfacet + facet normal -0.089188 0.68886 -0.719387 + outer loop + vertex 1.265 0.975 2.50332 + vertex 1.27 0.977402 2.505 + vertex 1.27 0.975 2.5027 + endloop + endfacet + facet normal -0.311536 0.886973 -0.340917 + outer loop + vertex 1.26349 0.974953 2.50458 + vertex 1.27 0.977402 2.505 + vertex 1.265 0.975 2.50332 + endloop + endfacet + facet normal -0.351586 0.880674 0.317492 + outer loop + vertex 1.27 0.977402 2.505 + vertex 1.26349 0.974953 2.50458 + vertex 1.26845 0.975926 2.50738 + endloop + endfacet + facet normal -0.157177 0.985509 -0.0637789 + outer loop + vertex 1.26845 0.975926 2.50738 + vertex 1.26349 0.974953 2.50458 + vertex 1.26403 0.97525 2.50784 + endloop + endfacet + facet normal -0.142095 0.986407 0.082519 + outer loop + vertex 1.26845 0.975926 2.50738 + vertex 1.26403 0.97525 2.50784 + vertex 1.26778 0.975494 2.51139 + endloop + endfacet + facet normal -0.112734 0.992312 0.0510718 + outer loop + vertex 1.26778 0.975494 2.51139 + vertex 1.26403 0.97525 2.50784 + vertex 1.26302 0.974956 2.51131 + endloop + endfacet + facet normal -0.113178 0.980359 0.161514 + outer loop + vertex 1.26778 0.975494 2.51139 + vertex 1.26302 0.974956 2.51131 + vertex 1.26695 0.974834 2.51481 + endloop + endfacet + facet normal -0.156626 0.965103 0.209869 + outer loop + vertex 1.26695 0.974834 2.51481 + vertex 1.26302 0.974956 2.51131 + vertex 1.26342 0.974013 2.51595 + endloop + endfacet + facet normal -0.209186 0.853465 0.477325 + outer loop + vertex 1.26671 0.972717 2.51971 + vertex 1.26342 0.974013 2.51595 + vertex 1.26229 0.972162 2.51877 + endloop + endfacet + facet normal -0.17076 0.875819 0.451422 + outer loop + vertex 1.26671 0.972717 2.51971 + vertex 1.26856 0.973652 2.5186 + vertex 1.26342 0.974013 2.51595 + endloop + endfacet + facet normal -0.108218 0.934934 0.337916 + outer loop + vertex 1.26856 0.973652 2.5186 + vertex 1.26695 0.974834 2.51481 + vertex 1.26342 0.974013 2.51595 + endloop + endfacet + facet normal -0.283936 0.912657 0.294002 + outer loop + vertex 1.26856 0.973652 2.5186 + vertex 1.26671 0.972717 2.51971 + vertex 1.26858 0.973021 2.52058 + endloop + endfacet + facet normal -0.0231671 -0.681414 -0.731531 + outer loop + vertex 1.27 2.05215 2.505 + vertex 1.26851 2.04966 2.50736 + vertex 1.265 2.05232 2.505 + endloop + endfacet + facet normal -0.020441 -0.679485 -0.733405 + outer loop + vertex 1.26851 2.04966 2.50736 + vertex 1.26359 2.04991 2.50727 + vertex 1.265 2.05232 2.505 + endloop + endfacet + facet normal -0.0496586 -0.996695 -0.0642955 + outer loop + vertex 1.26851 2.04966 2.50736 + vertex 1.26748 2.04944 2.51158 + vertex 1.26359 2.04991 2.50727 + endloop + endfacet + facet normal 0.0258774 -0.990956 -0.131669 + outer loop + vertex 1.26748 2.04944 2.51158 + vertex 1.26259 2.04934 2.51142 + vertex 1.26359 2.04991 2.50727 + endloop + endfacet + facet normal 0.0130446 -0.973218 0.229513 + outer loop + vertex 1.26748 2.04944 2.51158 + vertex 1.26549 2.05051 2.5162 + vertex 1.26259 2.04934 2.51142 + endloop + endfacet + facet normal 0.168543 -0.97626 0.136049 + outer loop + vertex 1.26549 2.05051 2.5162 + vertex 1.26119 2.04959 2.51498 + vertex 1.26259 2.04934 2.51142 + endloop + endfacet + facet normal 0.438584 -0.749954 0.495189 + outer loop + vertex 1.26442 2.05216 2.51966 + vertex 1.26549 2.05051 2.5162 + vertex 1.26844 2.05394 2.5188 + endloop + endfacet + facet normal 0.213251 -0.853662 0.475169 + outer loop + vertex 1.26442 2.05216 2.51966 + vertex 1.26097 2.05084 2.51884 + vertex 1.26549 2.05051 2.5162 + endloop + endfacet + facet normal 0.111403 -0.943613 0.311744 + outer loop + vertex 1.26097 2.05084 2.51884 + vertex 1.26119 2.04959 2.51498 + vertex 1.26549 2.05051 2.5162 + endloop + endfacet + facet normal 0.116451 -0.726728 0.676983 + outer loop + vertex 1.26442 2.05216 2.51966 + vertex 1.26137 2.05306 2.52116 + vertex 1.26097 2.05084 2.51884 + endloop + endfacet + facet normal 0.204189 0.540851 0.815958 + outer loop + vertex 1.2689 2.14846 2.49107 + vertex 1.26876 2.15095 2.48945 + vertex 1.26607 2.14958 2.49104 + endloop + endfacet + facet normal 0.16526 0.444709 0.880297 + outer loop + vertex 1.26607 2.14958 2.49104 + vertex 1.26652 2.14609 2.49272 + vertex 1.2689 2.14846 2.49107 + endloop + endfacet + facet normal 0.186788 0.445243 0.87571 + outer loop + vertex 1.26607 2.14958 2.49104 + vertex 1.262 2.14944 2.49198 + vertex 1.26652 2.14609 2.49272 + endloop + endfacet + facet normal 0.198089 0.458411 0.866383 + outer loop + vertex 1.262 2.14944 2.49198 + vertex 1.26266 2.1463 2.49349 + vertex 1.26652 2.14609 2.49272 + endloop + endfacet + facet normal 0.205257 0.783925 0.585944 + outer loop + vertex 1.26341 2.15497 2.48708 + vertex 1.2686 2.1539 2.48669 + vertex 1.26603 2.15648 2.48414 + endloop + endfacet + facet normal 0.205277 0.783912 0.585955 + outer loop + vertex 1.26214 2.15686 2.485 + vertex 1.26341 2.15497 2.48708 + vertex 1.26603 2.15648 2.48414 + endloop + endfacet + facet normal 0.172325 0.580231 0.796013 + outer loop + vertex 1.26876 2.15095 2.48945 + vertex 1.26463 2.15222 2.48943 + vertex 1.26607 2.14958 2.49104 + endloop + endfacet + facet normal 0.202168 0.676196 0.70844 + outer loop + vertex 1.26876 2.15095 2.48945 + vertex 1.2686 2.1539 2.48669 + vertex 1.26463 2.15222 2.48943 + endloop + endfacet + facet normal 0.193704 0.685451 0.70188 + outer loop + vertex 1.2686 2.1539 2.48669 + vertex 1.26341 2.15497 2.48708 + vertex 1.26463 2.15222 2.48943 + endloop + endfacet + facet normal 0.164475 0.577958 0.79932 + outer loop + vertex 1.26607 2.14958 2.49104 + vertex 1.26463 2.15222 2.48943 + vertex 1.262 2.14944 2.49198 + endloop + endfacet + facet normal 0.120485 0.723768 0.679443 + outer loop + vertex 1.26433 2.16021 2.47777 + vertex 1.27023 2.16053 2.47639 + vertex 1.26693 2.16249 2.47488 + endloop + endfacet + facet normal -0.000124918 0.784992 0.619506 + outer loop + vertex 1.26273 2.16221 2.47524 + vertex 1.26433 2.16021 2.47777 + vertex 1.26693 2.16249 2.47488 + endloop + endfacet + facet normal 0.0801376 0.841009 0.535054 + outer loop + vertex 1.27023 2.16053 2.47639 + vertex 1.26433 2.16021 2.47777 + vertex 1.26797 2.15817 2.48043 + endloop + endfacet + facet normal 0.170062 0.880728 0.442038 + outer loop + vertex 1.26797 2.15817 2.48043 + vertex 1.26433 2.16021 2.47777 + vertex 1.26308 2.15832 2.48202 + endloop + endfacet + facet normal 0.189286 0.856115 0.480872 + outer loop + vertex 1.26603 2.15648 2.48414 + vertex 1.26308 2.15832 2.48202 + vertex 1.26214 2.15686 2.485 + endloop + endfacet + facet normal 0.183848 0.854035 0.486645 + outer loop + vertex 1.26797 2.15817 2.48043 + vertex 1.26308 2.15832 2.48202 + vertex 1.26603 2.15648 2.48414 + endloop + endfacet + facet normal 0.0850285 0.0118484 0.996308 + outer loop + vertex 1.26693 2.16249 2.47488 + vertex 1.265 2.16615 2.475 + vertex 1.26273 2.16221 2.47524 + endloop + endfacet + facet normal -0.00555041 -0.0360373 0.999335 + outer loop + vertex 1.27 2.16538 2.475 + vertex 1.265 2.16615 2.475 + vertex 1.26693 2.16249 2.47488 + endloop + endfacet + facet normal 0.180367 -0.885899 0.427377 + outer loop + vertex 1.275 0.866387 2.475 + vertex 1.27194 0.866795 2.47714 + vertex 1.27 0.865369 2.475 + endloop + endfacet + facet normal 0.181161 -0.886039 0.42675 + outer loop + vertex 1.27194 0.866795 2.47714 + vertex 1.26815 0.865967 2.47703 + vertex 1.27 0.865369 2.475 + endloop + endfacet + facet normal 0.186597 -0.898851 0.396545 + outer loop + vertex 1.27114 0.868177 2.48065 + vertex 1.27194 0.866795 2.47714 + vertex 1.27511 0.868407 2.4793 + endloop + endfacet + facet normal 0.185482 -0.899143 0.396406 + outer loop + vertex 1.27114 0.868177 2.48065 + vertex 1.26709 0.867143 2.4802 + vertex 1.27194 0.866795 2.47714 + endloop + endfacet + facet normal 0.185016 -0.899545 0.395712 + outer loop + vertex 1.26709 0.867143 2.4802 + vertex 1.26815 0.865967 2.47703 + vertex 1.27194 0.866795 2.47714 + endloop + endfacet + facet normal 0.175103 -0.879016 0.443474 + outer loop + vertex 1.27114 0.868177 2.48065 + vertex 1.26852 0.868917 2.48315 + vertex 1.26709 0.867143 2.4802 + endloop + endfacet + facet normal 0.207265 -0.861308 0.463885 + outer loop + vertex 1.27511 0.868407 2.4793 + vertex 1.27278 0.870039 2.48337 + vertex 1.27114 0.868177 2.48065 + endloop + endfacet + facet normal 0.202303 -0.860993 0.466653 + outer loop + vertex 1.26852 0.868917 2.48315 + vertex 1.27114 0.868177 2.48065 + vertex 1.27278 0.870039 2.48337 + endloop + endfacet + facet normal 0.185527 -0.813897 0.550591 + outer loop + vertex 1.26852 0.868917 2.48315 + vertex 1.27278 0.870039 2.48337 + vertex 1.26704 0.871055 2.48681 + endloop + endfacet + facet normal 0.197799 -0.799694 0.566891 + outer loop + vertex 1.26704 0.871055 2.48681 + vertex 1.27278 0.870039 2.48337 + vertex 1.27212 0.872207 2.48666 + endloop + endfacet + facet normal 0.183037 -0.721524 0.667758 + outer loop + vertex 1.27212 0.872207 2.48666 + vertex 1.26952 0.873732 2.48902 + vertex 1.26704 0.871055 2.48681 + endloop + endfacet + facet normal 0.219108 -0.691644 0.6882 + outer loop + vertex 1.27456 0.874861 2.48855 + vertex 1.26952 0.873732 2.48902 + vertex 1.27212 0.872207 2.48666 + endloop + endfacet + facet normal 0.203989 -0.583563 0.78603 + outer loop + vertex 1.26952 0.873732 2.48902 + vertex 1.27456 0.874861 2.48855 + vertex 1.27124 0.876617 2.49072 + endloop + endfacet + facet normal 0.22667 -0.590368 0.774653 + outer loop + vertex 1.26761 0.875482 2.49091 + vertex 1.26952 0.873732 2.48902 + vertex 1.27124 0.876617 2.49072 + endloop + endfacet + facet normal 0.190937 -0.460296 0.866989 + outer loop + vertex 1.27124 0.876617 2.49072 + vertex 1.26861 0.879053 2.49259 + vertex 1.26761 0.875482 2.49091 + endloop + endfacet + facet normal 0.192071 -0.45929 0.867272 + outer loop + vertex 1.27378 0.880058 2.49198 + vertex 1.26861 0.879053 2.49259 + vertex 1.27124 0.876617 2.49072 + endloop + endfacet + facet normal 0.178956 -0.363056 0.914421 + outer loop + vertex 1.27378 0.880058 2.49198 + vertex 1.27339 0.88388 2.49357 + vertex 1.26861 0.879053 2.49259 + endloop + endfacet + facet normal 0.190892 -0.373528 0.907765 + outer loop + vertex 1.26861 0.879053 2.49259 + vertex 1.27339 0.88388 2.49357 + vertex 1.26813 0.883782 2.49463 + endloop + endfacet + facet normal 0.183874 -0.287812 0.939869 + outer loop + vertex 1.26951 0.903059 2.50052 + vertex 1.26867 0.905493 2.50144 + vertex 1.26579 0.901568 2.5008 + endloop + endfacet + facet normal 0.184252 -0.287669 0.939839 + outer loop + vertex 1.27183 0.905739 2.50089 + vertex 1.26867 0.905493 2.50144 + vertex 1.26951 0.903059 2.50052 + endloop + endfacet + facet normal 0.181677 -0.303031 0.935503 + outer loop + vertex 1.26947 0.952915 2.51544 + vertex 1.26876 0.955357 2.51637 + vertex 1.26573 0.951449 2.51569 + endloop + endfacet + facet normal 0.184528 -0.30211 0.935243 + outer loop + vertex 1.27188 0.955603 2.51583 + vertex 1.26876 0.955357 2.51637 + vertex 1.26947 0.952915 2.51544 + endloop + endfacet + facet normal 0.429344 -0.37768 0.820379 + outer loop + vertex 1.26919 0.972381 2.52054 + vertex 1.26832 0.972204 2.52091 + vertex 1.26719 0.969726 2.52036 + endloop + endfacet + facet normal 0.428758 -0.377273 0.820872 + outer loop + vertex 1.26919 0.972381 2.52054 + vertex 1.26719 0.969726 2.52036 + vertex 1.27126 0.972024 2.51929 + endloop + endfacet + facet normal 0.335202 0.261082 0.905249 + outer loop + vertex 1.26919 0.972381 2.52054 + vertex 1.26858 0.973021 2.52058 + vertex 1.26832 0.972204 2.52091 + endloop + endfacet + facet normal -0.0419893 0.928881 0.367991 + outer loop + vertex 1.275 0.977628 2.505 + vertex 1.27 0.977402 2.505 + vertex 1.27374 0.976606 2.50744 + endloop + endfacet + facet normal -0.117763 0.876295 0.46716 + outer loop + vertex 1.27374 0.976606 2.50744 + vertex 1.27 0.977402 2.505 + vertex 1.26845 0.975926 2.50738 + endloop + endfacet + facet normal -0.127463 0.977435 0.168444 + outer loop + vertex 1.27374 0.976606 2.50744 + vertex 1.26845 0.975926 2.50738 + vertex 1.27295 0.975806 2.51148 + endloop + endfacet + facet normal -0.061733 0.993392 0.0967502 + outer loop + vertex 1.27295 0.975806 2.51148 + vertex 1.26845 0.975926 2.50738 + vertex 1.26778 0.975494 2.51139 + endloop + endfacet + facet normal -0.0629553 0.954426 0.291731 + outer loop + vertex 1.27295 0.975806 2.51148 + vertex 1.26778 0.975494 2.51139 + vertex 1.27176 0.974387 2.51587 + endloop + endfacet + facet normal 0.047291 0.978694 0.199804 + outer loop + vertex 1.27176 0.974387 2.51587 + vertex 1.26778 0.975494 2.51139 + vertex 1.26695 0.974834 2.51481 + endloop + endfacet + facet normal 0.38967 0.823495 0.412327 + outer loop + vertex 1.27126 0.972024 2.51929 + vertex 1.26856 0.973652 2.5186 + vertex 1.26919 0.972381 2.52054 + endloop + endfacet + facet normal 0.311218 0.760765 0.569544 + outer loop + vertex 1.27126 0.972024 2.51929 + vertex 1.27176 0.974387 2.51587 + vertex 1.26856 0.973652 2.5186 + endloop + endfacet + facet normal 0.0258862 0.95727 0.288036 + outer loop + vertex 1.27176 0.974387 2.51587 + vertex 1.26695 0.974834 2.51481 + vertex 1.26856 0.973652 2.5186 + endloop + endfacet + facet normal 0.719997 0.663999 0.201765 + outer loop + vertex 1.26919 0.972381 2.52054 + vertex 1.26856 0.973652 2.5186 + vertex 1.26858 0.973021 2.52058 + endloop + endfacet + facet normal -0.00395632 -0.658493 -0.752577 + outer loop + vertex 1.275 2.05212 2.505 + vertex 1.27358 2.04942 2.50737 + vertex 1.27 2.05215 2.505 + endloop + endfacet + facet normal -0.0316545 -0.678543 -0.733878 + outer loop + vertex 1.27358 2.04942 2.50737 + vertex 1.26851 2.04966 2.50736 + vertex 1.27 2.05215 2.505 + endloop + endfacet + facet normal -0.0483986 -0.998366 -0.0303655 + outer loop + vertex 1.27358 2.04942 2.50737 + vertex 1.27268 2.04934 2.51147 + vertex 1.26851 2.04966 2.50736 + endloop + endfacet + facet normal -0.0216973 -0.998107 -0.057552 + outer loop + vertex 1.27268 2.04934 2.51147 + vertex 1.26748 2.04944 2.51158 + vertex 1.26851 2.04966 2.50736 + endloop + endfacet + facet normal -0.0114976 -0.941504 0.336806 + outer loop + vertex 1.27268 2.04934 2.51147 + vertex 1.27118 2.05081 2.51554 + vertex 1.26748 2.04944 2.51158 + endloop + endfacet + facet normal 0.0820201 -0.96299 0.256755 + outer loop + vertex 1.27118 2.05081 2.51554 + vertex 1.26549 2.05051 2.5162 + vertex 1.26748 2.04944 2.51158 + endloop + endfacet + facet normal 0.121947 -0.662754 0.738841 + outer loop + vertex 1.27118 2.05081 2.51554 + vertex 1.26844 2.05394 2.5188 + vertex 1.26549 2.05051 2.5162 + endloop + endfacet + facet normal 0.0519776 -0.698142 0.71407 + outer loop + vertex 1.27456 2.05318 2.51761 + vertex 1.26844 2.05394 2.5188 + vertex 1.27118 2.05081 2.51554 + endloop + endfacet + facet normal 0.215437 0.453766 0.864687 + outer loop + vertex 1.27464 2.14501 2.49144 + vertex 1.27273 2.14872 2.48997 + vertex 1.27077 2.14626 2.49174 + endloop + endfacet + facet normal 0.190263 0.364888 0.911404 + outer loop + vertex 1.27077 2.14626 2.49174 + vertex 1.27114 2.14254 2.49316 + vertex 1.27464 2.14501 2.49144 + endloop + endfacet + facet normal 0.193665 0.364948 0.910663 + outer loop + vertex 1.27077 2.14626 2.49174 + vertex 1.26652 2.14609 2.49272 + vertex 1.27114 2.14254 2.49316 + endloop + endfacet + facet normal 0.219337 0.450984 0.865162 + outer loop + vertex 1.2689 2.14846 2.49107 + vertex 1.27077 2.14626 2.49174 + vertex 1.27273 2.14872 2.48997 + endloop + endfacet + facet normal 0.199328 0.54121 0.816921 + outer loop + vertex 1.2689 2.14846 2.49107 + vertex 1.27273 2.14872 2.48997 + vertex 1.26876 2.15095 2.48945 + endloop + endfacet + facet normal 0.226123 0.580817 0.781998 + outer loop + vertex 1.26876 2.15095 2.48945 + vertex 1.27273 2.14872 2.48997 + vertex 1.27226 2.15173 2.48787 + endloop + endfacet + facet normal 0.185105 0.42784 0.884697 + outer loop + vertex 1.27077 2.14626 2.49174 + vertex 1.2689 2.14846 2.49107 + vertex 1.26652 2.14609 2.49272 + endloop + endfacet + facet normal 0.177551 0.794255 0.581063 + outer loop + vertex 1.2686 2.1539 2.48669 + vertex 1.27457 2.1538 2.485 + vertex 1.27088 2.15607 2.48302 + endloop + endfacet + facet normal 0.201106 0.782758 0.588937 + outer loop + vertex 1.26603 2.15648 2.48414 + vertex 1.2686 2.1539 2.48669 + vertex 1.27088 2.15607 2.48302 + endloop + endfacet + facet normal 0.173371 0.679112 0.713267 + outer loop + vertex 1.27226 2.15173 2.48787 + vertex 1.2686 2.1539 2.48669 + vertex 1.26876 2.15095 2.48945 + endloop + endfacet + facet normal 0.202877 0.70861 0.675806 + outer loop + vertex 1.27457 2.1538 2.485 + vertex 1.2686 2.1539 2.48669 + vertex 1.27226 2.15173 2.48787 + endloop + endfacet + facet normal -0.202174 0.359533 0.910967 + outer loop + vertex 1.27193 2.165 2.475 + vertex 1.26693 2.16249 2.47488 + vertex 1.27023 2.16053 2.47639 + endloop + endfacet + facet normal 0.0665639 0.272445 0.959866 + outer loop + vertex 1.27193 2.165 2.475 + vertex 1.27023 2.16053 2.47639 + vertex 1.275 2.16425 2.475 + endloop + endfacet + facet normal 0.0992826 0.233269 0.967331 + outer loop + vertex 1.275 2.16425 2.475 + vertex 1.27023 2.16053 2.47639 + vertex 1.27362 2.15985 2.4762 + endloop + endfacet + facet normal 0.189239 0.788222 0.585572 + outer loop + vertex 1.27362 2.15985 2.4762 + vertex 1.27023 2.16053 2.47639 + vertex 1.27306 2.15784 2.47909 + endloop + endfacet + facet normal 0.202979 0.792356 0.575301 + outer loop + vertex 1.27306 2.15784 2.47909 + vertex 1.27023 2.16053 2.47639 + vertex 1.26797 2.15817 2.48043 + endloop + endfacet + facet normal 0.183399 0.854218 0.486495 + outer loop + vertex 1.27088 2.15607 2.48302 + vertex 1.26797 2.15817 2.48043 + vertex 1.26603 2.15648 2.48414 + endloop + endfacet + facet normal 0.183743 0.854317 0.48619 + outer loop + vertex 1.27306 2.15784 2.47909 + vertex 1.26797 2.15817 2.48043 + vertex 1.27088 2.15607 2.48302 + endloop + endfacet + facet normal 0.137865 0.700135 -0.700574 + outer loop + vertex 1.27 2.165 2.47462 + vertex 1.27 2.16538 2.475 + vertex 1.27193 2.165 2.475 + endloop + endfacet + facet normal -0.00682859 -0.0346784 0.999375 + outer loop + vertex 1.27193 2.165 2.475 + vertex 1.27 2.16538 2.475 + vertex 1.26693 2.16249 2.47488 + endloop + endfacet + facet normal 0.105622 -0.784712 0.610795 + outer loop + vertex 1.28 0.86706 2.475 + vertex 1.27778 0.86736 2.47577 + vertex 1.275 0.866387 2.475 + endloop + endfacet + facet normal 0.187292 -0.880146 0.436193 + outer loop + vertex 1.27778 0.86736 2.47577 + vertex 1.27194 0.866795 2.47714 + vertex 1.275 0.866387 2.475 + endloop + endfacet + facet normal 0.181184 -0.897034 0.403115 + outer loop + vertex 1.27778 0.86736 2.47577 + vertex 1.27511 0.868407 2.4793 + vertex 1.27194 0.866795 2.47714 + endloop + endfacet + facet normal 0.184103 -0.895631 0.404909 + outer loop + vertex 1.27899 0.868652 2.47808 + vertex 1.27511 0.868407 2.4793 + vertex 1.27778 0.86736 2.47577 + endloop + endfacet + facet normal 0.190553 -0.883574 0.42777 + outer loop + vertex 1.27511 0.868407 2.4793 + vertex 1.27899 0.868652 2.47808 + vertex 1.27817 0.870038 2.4813 + endloop + endfacet + facet normal 0.172241 -0.876331 0.449862 + outer loop + vertex 1.27278 0.870039 2.48337 + vertex 1.27511 0.868407 2.4793 + vertex 1.27817 0.870038 2.4813 + endloop + endfacet + facet normal 0.205675 -0.818037 0.537134 + outer loop + vertex 1.27817 0.870038 2.4813 + vertex 1.2772 0.872301 2.48512 + vertex 1.27278 0.870039 2.48337 + endloop + endfacet + facet normal 0.186186 -0.80271 0.566561 + outer loop + vertex 1.2772 0.872301 2.48512 + vertex 1.27212 0.872207 2.48666 + vertex 1.27278 0.870039 2.48337 + endloop + endfacet + facet normal 0.220569 -0.692231 0.687143 + outer loop + vertex 1.2772 0.872301 2.48512 + vertex 1.27456 0.874861 2.48855 + vertex 1.27212 0.872207 2.48666 + endloop + endfacet + facet normal 0.190955 -0.710146 0.677665 + outer loop + vertex 1.27972 0.875165 2.48741 + vertex 1.27456 0.874861 2.48855 + vertex 1.2772 0.872301 2.48512 + endloop + endfacet + facet normal 0.207798 -0.579149 0.788293 + outer loop + vertex 1.27482 0.877683 2.49055 + vertex 1.27124 0.876617 2.49072 + vertex 1.27456 0.874861 2.48855 + endloop + endfacet + facet normal 0.204922 -0.579323 0.788918 + outer loop + vertex 1.27482 0.877683 2.49055 + vertex 1.27456 0.874861 2.48855 + vertex 1.27839 0.877772 2.48969 + endloop + endfacet + facet normal 0.207352 -0.581615 0.786594 + outer loop + vertex 1.27839 0.877772 2.48969 + vertex 1.27456 0.874861 2.48855 + vertex 1.27972 0.875165 2.48741 + endloop + endfacet + facet normal 0.172964 -0.448681 0.876795 + outer loop + vertex 1.27482 0.877683 2.49055 + vertex 1.27378 0.880058 2.49198 + vertex 1.27124 0.876617 2.49072 + endloop + endfacet + facet normal 0.217767 -0.474572 0.852854 + outer loop + vertex 1.27839 0.877772 2.48969 + vertex 1.27716 0.880001 2.49125 + vertex 1.27482 0.877683 2.49055 + endloop + endfacet + facet normal 0.18135 -0.44507 0.87694 + outer loop + vertex 1.27716 0.880001 2.49125 + vertex 1.27378 0.880058 2.49198 + vertex 1.27482 0.877683 2.49055 + endloop + endfacet + facet normal 0.18968 -0.36938 0.909714 + outer loop + vertex 1.27716 0.880001 2.49125 + vertex 1.2786 0.883894 2.49253 + vertex 1.27378 0.880058 2.49198 + endloop + endfacet + facet normal 0.183606 -0.362324 0.913789 + outer loop + vertex 1.2786 0.883894 2.49253 + vertex 1.27339 0.88388 2.49357 + vertex 1.27378 0.880058 2.49198 + endloop + endfacet + facet normal -0.0153956 0.962349 0.271381 + outer loop + vertex 1.28 0.977708 2.505 + vertex 1.275 0.977628 2.505 + vertex 1.27877 0.976973 2.50754 + endloop + endfacet + facet normal -0.0750508 0.932777 0.352555 + outer loop + vertex 1.27877 0.976973 2.50754 + vertex 1.275 0.977628 2.505 + vertex 1.27374 0.976606 2.50744 + endloop + endfacet + facet normal -0.0752811 0.977609 0.196505 + outer loop + vertex 1.27877 0.976973 2.50754 + vertex 1.27374 0.976606 2.50744 + vertex 1.27829 0.976145 2.51147 + endloop + endfacet + facet normal -0.0620026 0.981348 0.181965 + outer loop + vertex 1.27829 0.976145 2.51147 + vertex 1.27374 0.976606 2.50744 + vertex 1.27295 0.975806 2.51148 + endloop + endfacet + facet normal -0.0579432 0.92464 0.376409 + outer loop + vertex 1.27829 0.976145 2.51147 + vertex 1.27295 0.975806 2.51148 + vertex 1.27741 0.974562 2.51522 + endloop + endfacet + facet normal 0.00572418 0.95093 0.309354 + outer loop + vertex 1.27741 0.974562 2.51522 + vertex 1.27295 0.975806 2.51148 + vertex 1.27176 0.974387 2.51587 + endloop + endfacet + facet normal 0.18266 0.796894 0.575843 + outer loop + vertex 1.27574 0.971932 2.518 + vertex 1.27176 0.974387 2.51587 + vertex 1.27126 0.972024 2.51929 + endloop + endfacet + facet normal 0.0584103 0.70713 0.704667 + outer loop + vertex 1.27741 0.974562 2.51522 + vertex 1.27176 0.974387 2.51587 + vertex 1.27574 0.971932 2.518 + endloop + endfacet + facet normal -0.0851385 -0.608134 -0.789256 + outer loop + vertex 1.28 2.05142 2.505 + vertex 1.27854 2.04895 2.50706 + vertex 1.275 2.05212 2.505 + endloop + endfacet + facet normal -0.107385 -0.623398 -0.774495 + outer loop + vertex 1.27854 2.04895 2.50706 + vertex 1.27358 2.04942 2.50737 + vertex 1.275 2.05212 2.505 + endloop + endfacet + facet normal -0.0941187 -0.995462 -0.0140657 + outer loop + vertex 1.27854 2.04895 2.50706 + vertex 1.27788 2.04896 2.51112 + vertex 1.27358 2.04942 2.50737 + endloop + endfacet + facet normal -0.0749747 -0.99653 -0.0361449 + outer loop + vertex 1.27788 2.04896 2.51112 + vertex 1.27268 2.04934 2.51147 + vertex 1.27358 2.04942 2.50737 + endloop + endfacet + facet normal -0.0432714 -0.929153 0.367154 + outer loop + vertex 1.27788 2.04896 2.51112 + vertex 1.27648 2.05056 2.51501 + vertex 1.27268 2.04934 2.51147 + endloop + endfacet + facet normal -0.0111089 -0.941463 0.336935 + outer loop + vertex 1.27648 2.05056 2.51501 + vertex 1.27118 2.05081 2.51554 + vertex 1.27268 2.04934 2.51147 + endloop + endfacet + facet normal 0.0397019 -0.689018 0.723656 + outer loop + vertex 1.27648 2.05056 2.51501 + vertex 1.27456 2.05318 2.51761 + vertex 1.27118 2.05081 2.51554 + endloop + endfacet + facet normal 0.0214389 -0.69628 0.71745 + outer loop + vertex 1.2794 2.05265 2.51695 + vertex 1.27456 2.05318 2.51761 + vertex 1.27648 2.05056 2.51501 + endloop + endfacet + facet normal 0.200873 0.42812 0.881115 + outer loop + vertex 1.27464 2.14501 2.49144 + vertex 1.27935 2.1438 2.49095 + vertex 1.27719 2.14709 2.48985 + endloop + endfacet + facet normal 0.185759 0.443391 0.876868 + outer loop + vertex 1.27273 2.14872 2.48997 + vertex 1.27464 2.14501 2.49144 + vertex 1.27719 2.14709 2.48985 + endloop + endfacet + facet normal 0.19276 0.361825 0.9121 + outer loop + vertex 1.27658 2.14102 2.49261 + vertex 1.27464 2.14501 2.49144 + vertex 1.27114 2.14254 2.49316 + endloop + endfacet + facet normal 0.186751 0.359533 0.914254 + outer loop + vertex 1.27935 2.1438 2.49095 + vertex 1.27464 2.14501 2.49144 + vertex 1.27658 2.14102 2.49261 + endloop + endfacet + facet normal 0.221001 0.544795 0.808923 + outer loop + vertex 1.27719 2.14709 2.48985 + vertex 1.2771 2.15036 2.48766 + vertex 1.27273 2.14872 2.48997 + endloop + endfacet + facet normal 0.196911 0.581434 0.789405 + outer loop + vertex 1.27273 2.14872 2.48997 + vertex 1.2771 2.15036 2.48766 + vertex 1.27226 2.15173 2.48787 + endloop + endfacet + facet normal 0.196152 0.854108 0.481689 + outer loop + vertex 1.27858 2.15499 2.48204 + vertex 1.2769 2.15673 2.47964 + vertex 1.27487 2.1559 2.48193 + endloop + endfacet + facet normal 0.189312 0.801411 0.567363 + outer loop + vertex 1.27487 2.1559 2.48193 + vertex 1.27088 2.15607 2.48302 + vertex 1.27457 2.1538 2.485 + endloop + endfacet + facet normal 0.181135 0.803064 0.567695 + outer loop + vertex 1.27487 2.1559 2.48193 + vertex 1.27457 2.1538 2.485 + vertex 1.27858 2.15499 2.48204 + endloop + endfacet + facet normal 0.19408 0.790906 0.580345 + outer loop + vertex 1.27858 2.15499 2.48204 + vertex 1.27457 2.1538 2.485 + vertex 1.27983 2.15272 2.48471 + endloop + endfacet + facet normal 0.224375 0.694917 0.683189 + outer loop + vertex 1.2771 2.15036 2.48766 + vertex 1.27457 2.1538 2.485 + vertex 1.27226 2.15173 2.48787 + endloop + endfacet + facet normal 0.178687 0.68165 0.709524 + outer loop + vertex 1.27983 2.15272 2.48471 + vertex 1.27457 2.1538 2.485 + vertex 1.2771 2.15036 2.48766 + endloop + endfacet + facet normal 0.0391731 0.261214 0.964486 + outer loop + vertex 1.28 2.1635 2.475 + vertex 1.275 2.16425 2.475 + vertex 1.27709 2.15907 2.47632 + endloop + endfacet + facet normal 0.0254834 0.256165 0.966297 + outer loop + vertex 1.27709 2.15907 2.47632 + vertex 1.275 2.16425 2.475 + vertex 1.27362 2.15985 2.4762 + endloop + endfacet + facet normal 0.1823 0.862344 0.472365 + outer loop + vertex 1.2769 2.15673 2.47964 + vertex 1.27306 2.15784 2.47909 + vertex 1.27487 2.1559 2.48193 + endloop + endfacet + facet normal 0.15092 0.804106 0.575011 + outer loop + vertex 1.2769 2.15673 2.47964 + vertex 1.27709 2.15907 2.47632 + vertex 1.27306 2.15784 2.47909 + endloop + endfacet + facet normal 0.160455 0.795116 0.584846 + outer loop + vertex 1.27709 2.15907 2.47632 + vertex 1.27362 2.15985 2.4762 + vertex 1.27306 2.15784 2.47909 + endloop + endfacet + facet normal 0.168058 0.860802 0.480392 + outer loop + vertex 1.27487 2.1559 2.48193 + vertex 1.27306 2.15784 2.47909 + vertex 1.27088 2.15607 2.48302 + endloop + endfacet + facet normal 0.276667 0.12379 0.952959 + outer loop + vertex 1.28158 0.868222 2.47595 + vertex 1.285 0.867868 2.475 + vertex 1.2854 0.868541 2.4748 + endloop + endfacet + facet normal 0.124402 -0.694017 0.709129 + outer loop + vertex 1.28158 0.868222 2.47595 + vertex 1.27778 0.86736 2.47577 + vertex 1.285 0.867868 2.475 + endloop + endfacet + facet normal 0.121839 -0.753951 0.645533 + outer loop + vertex 1.27778 0.86736 2.47577 + vertex 1.28 0.86706 2.475 + vertex 1.285 0.867868 2.475 + endloop + endfacet + facet normal 0.184224 -0.895634 0.404848 + outer loop + vertex 1.28158 0.868222 2.47595 + vertex 1.27899 0.868652 2.47808 + vertex 1.27778 0.86736 2.47577 + endloop + endfacet + facet normal 0.196482 -0.893154 0.404563 + outer loop + vertex 1.2854 0.868541 2.4748 + vertex 1.28286 0.869773 2.47875 + vertex 1.28158 0.868222 2.47595 + endloop + endfacet + facet normal 0.187703 -0.893207 0.408594 + outer loop + vertex 1.27899 0.868652 2.47808 + vertex 1.28158 0.868222 2.47595 + vertex 1.28286 0.869773 2.47875 + endloop + endfacet + facet normal 0.18242 -0.885818 0.426673 + outer loop + vertex 1.27899 0.868652 2.47808 + vertex 1.28286 0.869773 2.47875 + vertex 1.27817 0.870038 2.4813 + endloop + endfacet + facet normal 0.201389 -0.865123 0.459353 + outer loop + vertex 1.27817 0.870038 2.4813 + vertex 1.28286 0.869773 2.47875 + vertex 1.28184 0.871661 2.48275 + endloop + endfacet + facet normal 0.194018 -0.796345 0.57288 + outer loop + vertex 1.28138 0.873378 2.48529 + vertex 1.28184 0.871661 2.48275 + vertex 1.28484 0.873554 2.48437 + endloop + endfacet + facet normal 0.182301 -0.799236 0.572703 + outer loop + vertex 1.28138 0.873378 2.48529 + vertex 1.2772 0.872301 2.48512 + vertex 1.28184 0.871661 2.48275 + endloop + endfacet + facet normal 0.157498 -0.831418 0.53286 + outer loop + vertex 1.2772 0.872301 2.48512 + vertex 1.27817 0.870038 2.4813 + vertex 1.28184 0.871661 2.48275 + endloop + endfacet + facet normal 0.149962 -0.694726 0.703468 + outer loop + vertex 1.28138 0.873378 2.48529 + vertex 1.27972 0.875165 2.48741 + vertex 1.2772 0.872301 2.48512 + endloop + endfacet + facet normal 0.218694 -0.695775 0.684157 + outer loop + vertex 1.28484 0.873554 2.48437 + vertex 1.28334 0.875194 2.48652 + vertex 1.28138 0.873378 2.48529 + endloop + endfacet + facet normal 0.182522 -0.676457 0.713507 + outer loop + vertex 1.28334 0.875194 2.48652 + vertex 1.27972 0.875165 2.48741 + vertex 1.28138 0.873378 2.48529 + endloop + endfacet + facet normal 0.203051 -0.564785 0.799868 + outer loop + vertex 1.28334 0.875194 2.48652 + vertex 1.28393 0.878651 2.48881 + vertex 1.27972 0.875165 2.48741 + endloop + endfacet + facet normal 0.217397 -0.577057 0.787238 + outer loop + vertex 1.28393 0.878651 2.48881 + vertex 1.27839 0.877772 2.48969 + vertex 1.27972 0.875165 2.48741 + endloop + endfacet + facet normal -0.141112 0.928345 0.343893 + outer loop + vertex 1.285 0.978468 2.505 + vertex 1.28 0.977708 2.505 + vertex 1.28371 0.977346 2.5075 + endloop + endfacet + facet normal -0.0711742 0.966735 0.245678 + outer loop + vertex 1.28371 0.977346 2.5075 + vertex 1.28 0.977708 2.505 + vertex 1.27877 0.976973 2.50754 + endloop + endfacet + facet normal -0.0719905 0.974536 0.21236 + outer loop + vertex 1.28371 0.977346 2.5075 + vertex 1.27877 0.976973 2.50754 + vertex 1.28344 0.976463 2.51146 + endloop + endfacet + facet normal -0.0599612 0.978257 0.19854 + outer loop + vertex 1.28344 0.976463 2.51146 + vertex 1.27877 0.976973 2.50754 + vertex 1.27829 0.976145 2.51147 + endloop + endfacet + facet normal -0.0551333 0.904544 0.422801 + outer loop + vertex 1.28344 0.976463 2.51146 + vertex 1.27829 0.976145 2.51147 + vertex 1.28276 0.974808 2.51491 + endloop + endfacet + facet normal -0.0201932 0.922895 0.384521 + outer loop + vertex 1.28276 0.974808 2.51491 + vertex 1.27829 0.976145 2.51147 + vertex 1.27741 0.974562 2.51522 + endloop + endfacet + facet normal 0.0804362 0.699209 0.710378 + outer loop + vertex 1.28098 0.972096 2.51724 + vertex 1.27741 0.974562 2.51522 + vertex 1.27574 0.971932 2.518 + endloop + endfacet + facet normal 0.0143116 0.646412 0.762855 + outer loop + vertex 1.28276 0.974808 2.51491 + vertex 1.27741 0.974562 2.51522 + vertex 1.28098 0.972096 2.51724 + endloop + endfacet + facet normal -0.0787809 -0.437657 -0.895684 + outer loop + vertex 1.285 2.05052 2.505 + vertex 1.28234 2.04851 2.50622 + vertex 1.28 2.05142 2.505 + endloop + endfacet + facet normal -0.241751 -0.533275 -0.810663 + outer loop + vertex 1.28234 2.04851 2.50622 + vertex 1.27854 2.04895 2.50706 + vertex 1.28 2.05142 2.505 + endloop + endfacet + facet normal -0.133987 -0.987186 -0.0866647 + outer loop + vertex 1.28234 2.04851 2.50622 + vertex 1.28353 2.04799 2.5103 + vertex 1.27854 2.04895 2.50706 + endloop + endfacet + facet normal -0.172391 -0.984663 -0.0268463 + outer loop + vertex 1.28353 2.04799 2.5103 + vertex 1.27788 2.04896 2.51112 + vertex 1.27854 2.04895 2.50706 + endloop + endfacet + facet normal -0.103247 -0.921056 0.375496 + outer loop + vertex 1.28353 2.04799 2.5103 + vertex 1.28141 2.04995 2.51453 + vertex 1.27788 2.04896 2.51112 + endloop + endfacet + facet normal -0.0803817 -0.931473 0.354818 + outer loop + vertex 1.28141 2.04995 2.51453 + vertex 1.27648 2.05056 2.51501 + vertex 1.27788 2.04896 2.51112 + endloop + endfacet + facet normal -0.0105068 -0.672589 0.739942 + outer loop + vertex 1.28141 2.04995 2.51453 + vertex 1.2794 2.05265 2.51695 + vertex 1.27648 2.05056 2.51501 + endloop + endfacet + facet normal -0.0718617 -0.695574 0.714852 + outer loop + vertex 1.28353 2.0517 2.51645 + vertex 1.2794 2.05265 2.51695 + vertex 1.28141 2.04995 2.51453 + endloop + endfacet + facet normal 0.198104 0.440577 0.875584 + outer loop + vertex 1.27935 2.1438 2.49095 + vertex 1.2835 2.14267 2.49058 + vertex 1.28231 2.14682 2.48876 + endloop + endfacet + facet normal 0.208426 0.431868 0.877524 + outer loop + vertex 1.27719 2.14709 2.48985 + vertex 1.27935 2.1438 2.49095 + vertex 1.28231 2.14682 2.48876 + endloop + endfacet + facet normal 0.188761 0.357713 0.914555 + outer loop + vertex 1.28175 2.13954 2.49212 + vertex 1.27935 2.1438 2.49095 + vertex 1.27658 2.14102 2.49261 + endloop + endfacet + facet normal 0.178019 0.352757 0.918625 + outer loop + vertex 1.2835 2.14267 2.49058 + vertex 1.27935 2.1438 2.49095 + vertex 1.28175 2.13954 2.49212 + endloop + endfacet + facet normal 0.211045 0.66373 0.717581 + outer loop + vertex 1.28498 2.14956 2.48633 + vertex 1.2834 2.15182 2.48471 + vertex 1.28142 2.15043 2.48658 + endloop + endfacet + facet normal 0.18867 0.541628 0.819172 + outer loop + vertex 1.28142 2.15043 2.48658 + vertex 1.28231 2.14682 2.48876 + vertex 1.28498 2.14956 2.48633 + endloop + endfacet + facet normal 0.19672 0.542234 0.816874 + outer loop + vertex 1.28142 2.15043 2.48658 + vertex 1.2771 2.15036 2.48766 + vertex 1.28231 2.14682 2.48876 + endloop + endfacet + facet normal 0.200721 0.546853 0.812811 + outer loop + vertex 1.2771 2.15036 2.48766 + vertex 1.27719 2.14709 2.48985 + vertex 1.28231 2.14682 2.48876 + endloop + endfacet + facet normal 0.197871 0.859602 0.471095 + outer loop + vertex 1.27858 2.15499 2.48204 + vertex 1.28418 2.15406 2.48137 + vertex 1.28072 2.15643 2.47851 + endloop + endfacet + facet normal 0.207062 0.855321 0.474922 + outer loop + vertex 1.2769 2.15673 2.47964 + vertex 1.27858 2.15499 2.48204 + vertex 1.28072 2.15643 2.47851 + endloop + endfacet + facet normal 0.174922 0.692027 0.700357 + outer loop + vertex 1.2834 2.15182 2.48471 + vertex 1.27983 2.15272 2.48471 + vertex 1.28142 2.15043 2.48658 + endloop + endfacet + facet normal 0.199716 0.790764 0.578624 + outer loop + vertex 1.2834 2.15182 2.48471 + vertex 1.28418 2.15406 2.48137 + vertex 1.27983 2.15272 2.48471 + endloop + endfacet + facet normal 0.199244 0.791203 0.578186 + outer loop + vertex 1.28418 2.15406 2.48137 + vertex 1.27858 2.15499 2.48204 + vertex 1.27983 2.15272 2.48471 + endloop + endfacet + facet normal 0.166484 0.689725 0.704672 + outer loop + vertex 1.28142 2.15043 2.48658 + vertex 1.27983 2.15272 2.48471 + vertex 1.2771 2.15036 2.48766 + endloop + endfacet + facet normal -0.0446786 0.392041 0.918862 + outer loop + vertex 1.285 2.16372 2.47 + vertex 1.28 2.16315 2.47 + vertex 1.2823 2.16065 2.47118 + endloop + endfacet + facet normal 0.744937 0.665506 -0.0465864 + outer loop + vertex 1.2823 2.16065 2.47118 + vertex 1.28 2.16315 2.47 + vertex 1.28 2.1635 2.475 + endloop + endfacet + facet normal 0.885868 0.399022 0.236682 + outer loop + vertex 1.2823 2.16065 2.47118 + vertex 1.28 2.1635 2.475 + vertex 1.28247 2.15837 2.47441 + endloop + endfacet + facet normal 0.340051 0.0557774 0.938751 + outer loop + vertex 1.28247 2.15837 2.47441 + vertex 1.28 2.1635 2.475 + vertex 1.27709 2.15907 2.47632 + endloop + endfacet + facet normal 0.229686 0.789555 0.569076 + outer loop + vertex 1.28072 2.15643 2.47851 + vertex 1.27709 2.15907 2.47632 + vertex 1.2769 2.15673 2.47964 + endloop + endfacet + facet normal 0.2853 0.81388 0.506165 + outer loop + vertex 1.28247 2.15837 2.47441 + vertex 1.27709 2.15907 2.47632 + vertex 1.28072 2.15643 2.47851 + endloop + endfacet + facet normal 0.0761602 -0.971382 0.224983 + outer loop + vertex 1.29 0.867524 2.47 + vertex 1.28747 0.867634 2.47133 + vertex 1.285 0.867132 2.47 + endloop + endfacet + facet normal 0.121809 -0.981971 0.144549 + outer loop + vertex 1.28747 0.867634 2.47133 + vertex 1.285 0.867868 2.475 + vertex 1.285 0.867132 2.47 + endloop + endfacet + facet normal 0.783253 -0.297066 0.546138 + outer loop + vertex 1.28747 0.867634 2.47133 + vertex 1.2854 0.868541 2.4748 + vertex 1.285 0.867868 2.475 + endloop + endfacet + facet normal 0.178433 -0.920522 0.347565 + outer loop + vertex 1.2898 0.868822 2.47328 + vertex 1.2854 0.868541 2.4748 + vertex 1.28747 0.867634 2.47133 + endloop + endfacet + facet normal 0.192274 -0.89983 0.391581 + outer loop + vertex 1.2854 0.868541 2.4748 + vertex 1.2898 0.868822 2.47328 + vertex 1.28811 0.870218 2.47732 + endloop + endfacet + facet normal 0.184756 -0.898301 0.398649 + outer loop + vertex 1.28286 0.869773 2.47875 + vertex 1.2854 0.868541 2.4748 + vertex 1.28811 0.870218 2.47732 + endloop + endfacet + facet normal 0.195639 -0.873187 0.446396 + outer loop + vertex 1.28811 0.870218 2.47732 + vertex 1.28641 0.871849 2.48125 + vertex 1.28286 0.869773 2.47875 + endloop + endfacet + facet normal 0.185735 -0.869607 0.457478 + outer loop + vertex 1.28641 0.871849 2.48125 + vertex 1.28184 0.871661 2.48275 + vertex 1.28286 0.869773 2.47875 + endloop + endfacet + facet normal 0.213482 -0.80752 0.549852 + outer loop + vertex 1.28641 0.871849 2.48125 + vertex 1.28484 0.873554 2.48437 + vertex 1.28184 0.871661 2.48275 + endloop + endfacet + facet normal 0.214257 -0.807176 0.550055 + outer loop + vertex 1.289 0.874159 2.48364 + vertex 1.28484 0.873554 2.48437 + vertex 1.28641 0.871849 2.48125 + endloop + endfacet + facet normal 0.221746 -0.68798 0.691023 + outer loop + vertex 1.28484 0.873554 2.48437 + vertex 1.289 0.874159 2.48364 + vertex 1.28699 0.87618 2.48629 + endloop + endfacet + facet normal 0.228376 -0.690188 0.686648 + outer loop + vertex 1.28334 0.875194 2.48652 + vertex 1.28484 0.873554 2.48437 + vertex 1.28699 0.87618 2.48629 + endloop + endfacet + facet normal 0.2014 -0.564781 0.800288 + outer loop + vertex 1.28699 0.87618 2.48629 + vertex 1.28393 0.878651 2.48881 + vertex 1.28334 0.875194 2.48652 + endloop + endfacet + facet normal 0.201307 -0.564862 0.800254 + outer loop + vertex 1.28963 0.879609 2.48805 + vertex 1.28393 0.878651 2.48881 + vertex 1.28699 0.87618 2.48629 + endloop + endfacet + facet normal -0.102337 0.907273 0.407902 + outer loop + vertex 1.29 0.979032 2.505 + vertex 1.285 0.978468 2.505 + vertex 1.28869 0.977901 2.50719 + endloop + endfacet + facet normal -0.0795033 0.924122 0.373735 + outer loop + vertex 1.28869 0.977901 2.50719 + vertex 1.285 0.978468 2.505 + vertex 1.28371 0.977346 2.5075 + endloop + endfacet + facet normal -0.0913786 0.962968 0.253658 + outer loop + vertex 1.28869 0.977901 2.50719 + vertex 1.28371 0.977346 2.5075 + vertex 1.28839 0.976774 2.51136 + endloop + endfacet + facet normal -0.0568439 0.975277 0.213548 + outer loop + vertex 1.28839 0.976774 2.51136 + vertex 1.28371 0.977346 2.5075 + vertex 1.28344 0.976463 2.51146 + endloop + endfacet + facet normal -0.0464485 0.890187 0.453221 + outer loop + vertex 1.28839 0.976774 2.51136 + vertex 1.28344 0.976463 2.51146 + vertex 1.2879 0.975062 2.51467 + endloop + endfacet + facet normal -0.0243773 0.903313 0.428288 + outer loop + vertex 1.2879 0.975062 2.51467 + vertex 1.28344 0.976463 2.51146 + vertex 1.28276 0.974808 2.51491 + endloop + endfacet + facet normal 0.049646 0.632147 0.773256 + outer loop + vertex 1.28624 0.972361 2.51669 + vertex 1.28276 0.974808 2.51491 + vertex 1.28098 0.972096 2.51724 + endloop + endfacet + facet normal 0.00865413 0.595619 0.80322 + outer loop + vertex 1.2879 0.975062 2.51467 + vertex 1.28276 0.974808 2.51491 + vertex 1.28624 0.972361 2.51669 + endloop + endfacet + facet normal -0.157836 0.426464 -0.890627 + outer loop + vertex 1.29089 2.04723 2.50307 + vertex 1.28746 2.05 2.505 + vertex 1.29 2.05 2.50455 + endloop + endfacet + facet normal -0.677442 -0.415437 -0.607029 + outer loop + vertex 1.29089 2.04723 2.50307 + vertex 1.28913 2.04677 2.50535 + vertex 1.28746 2.05 2.505 + endloop + endfacet + facet normal -0.255501 -0.947331 0.193087 + outer loop + vertex 1.29042 2.04619 2.5111 + vertex 1.28752 2.04719 2.51215 + vertex 1.28743 2.0467 2.50965 + endloop + endfacet + facet normal -0.21651 -0.93307 0.287234 + outer loop + vertex 1.29042 2.04619 2.5111 + vertex 1.2893 2.04729 2.5138 + vertex 1.28752 2.04719 2.51215 + endloop + endfacet + facet normal -0.419532 -0.308801 -0.853601 + outer loop + vertex 1.28746 2.05 2.505 + vertex 1.28913 2.04677 2.50535 + vertex 1.2861 2.04752 2.50657 + endloop + endfacet + facet normal -0.103582 -0.490033 -0.865528 + outer loop + vertex 1.28746 2.05 2.505 + vertex 1.2861 2.04752 2.50657 + vertex 1.285 2.05052 2.505 + endloop + endfacet + facet normal -0.0429897 -0.47491 -0.878984 + outer loop + vertex 1.285 2.05052 2.505 + vertex 1.2861 2.04752 2.50657 + vertex 1.28234 2.04851 2.50622 + endloop + endfacet + facet normal -0.277954 -0.941061 0.192734 + outer loop + vertex 1.28743 2.0467 2.50965 + vertex 1.28752 2.04719 2.51215 + vertex 1.28353 2.04799 2.5103 + endloop + endfacet + facet normal -0.327593 -0.938735 -0.107048 + outer loop + vertex 1.28743 2.0467 2.50965 + vertex 1.28353 2.04799 2.5103 + vertex 1.2861 2.04752 2.50657 + endloop + endfacet + facet normal -0.250274 -0.966867 -0.0503183 + outer loop + vertex 1.2861 2.04752 2.50657 + vertex 1.28353 2.04799 2.5103 + vertex 1.28234 2.04851 2.50622 + endloop + endfacet + facet normal -0.356836 -0.828227 0.432098 + outer loop + vertex 1.28752 2.04719 2.51215 + vertex 1.2893 2.04729 2.5138 + vertex 1.28626 2.049 2.51457 + endloop + endfacet + facet normal -0.363902 -0.827387 0.427792 + outer loop + vertex 1.28752 2.04719 2.51215 + vertex 1.28626 2.049 2.51457 + vertex 1.28353 2.04799 2.5103 + endloop + endfacet + facet normal -0.184833 -0.923632 0.335769 + outer loop + vertex 1.28353 2.04799 2.5103 + vertex 1.28626 2.049 2.51457 + vertex 1.28141 2.04995 2.51453 + endloop + endfacet + facet normal -0.135532 -0.652434 0.745628 + outer loop + vertex 1.28626 2.049 2.51457 + vertex 1.28353 2.0517 2.51645 + vertex 1.28141 2.04995 2.51453 + endloop + endfacet + facet normal -0.0120154 -0.57679 0.816804 + outer loop + vertex 1.28799 2.05173 2.51653 + vertex 1.28353 2.0517 2.51645 + vertex 1.28626 2.049 2.51457 + endloop + endfacet + facet normal 0.196079 0.371812 0.907364 + outer loop + vertex 1.2835 2.14267 2.49058 + vertex 1.28582 2.13994 2.4912 + vertex 1.28813 2.14279 2.48953 + endloop + endfacet + facet normal 0.187733 0.438959 0.878676 + outer loop + vertex 1.2835 2.14267 2.49058 + vertex 1.28813 2.14279 2.48953 + vertex 1.28231 2.14682 2.48876 + endloop + endfacet + facet normal 0.196089 0.449667 0.871406 + outer loop + vertex 1.28231 2.14682 2.48876 + vertex 1.28813 2.14279 2.48953 + vertex 1.28724 2.14684 2.48764 + endloop + endfacet + facet normal 0.173541 0.355213 0.918535 + outer loop + vertex 1.28582 2.13994 2.4912 + vertex 1.2835 2.14267 2.49058 + vertex 1.28175 2.13954 2.49212 + endloop + endfacet + facet normal 0.214017 0.67033 0.710531 + outer loop + vertex 1.28498 2.14956 2.48633 + vertex 1.28923 2.14905 2.48554 + vertex 1.28697 2.15161 2.4838 + endloop + endfacet + facet normal 0.220299 0.666424 0.712284 + outer loop + vertex 1.2834 2.15182 2.48471 + vertex 1.28498 2.14956 2.48633 + vertex 1.28697 2.15161 2.4838 + endloop + endfacet + facet normal 0.183552 0.545422 0.817816 + outer loop + vertex 1.28724 2.14684 2.48764 + vertex 1.28498 2.14956 2.48633 + vertex 1.28231 2.14682 2.48876 + endloop + endfacet + facet normal 0.217158 0.563291 0.797211 + outer loop + vertex 1.28923 2.14905 2.48554 + vertex 1.28498 2.14956 2.48633 + vertex 1.28724 2.14684 2.48764 + endloop + endfacet + facet normal 0.175295 0.893958 0.412445 + outer loop + vertex 1.28937 2.15506 2.47766 + vertex 1.28711 2.15687 2.4747 + vertex 1.2849 2.15609 2.47733 + endloop + endfacet + facet normal 0.202171 0.860866 0.466943 + outer loop + vertex 1.2849 2.15609 2.47733 + vertex 1.28072 2.15643 2.47851 + vertex 1.28418 2.15406 2.48137 + endloop + endfacet + facet normal 0.16594 0.869657 0.46493 + outer loop + vertex 1.2849 2.15609 2.47733 + vertex 1.28418 2.15406 2.48137 + vertex 1.28937 2.15506 2.47766 + endloop + endfacet + facet normal 0.182723 0.855482 0.484523 + outer loop + vertex 1.28937 2.15506 2.47766 + vertex 1.28418 2.15406 2.48137 + vertex 1.28913 2.15316 2.48111 + endloop + endfacet + facet normal 0.193378 0.792546 0.578339 + outer loop + vertex 1.28697 2.15161 2.4838 + vertex 1.28418 2.15406 2.48137 + vertex 1.2834 2.15182 2.48471 + endloop + endfacet + facet normal 0.175707 0.786307 0.592325 + outer loop + vertex 1.28913 2.15316 2.48111 + vertex 1.28418 2.15406 2.48137 + vertex 1.28697 2.15161 2.4838 + endloop + endfacet + facet normal 0.0658971 0.305136 0.950026 + outer loop + vertex 1.29 2.16264 2.47 + vertex 1.285 2.16372 2.47 + vertex 1.28704 2.15903 2.47137 + endloop + endfacet + facet normal 0.0670951 0.30559 0.949796 + outer loop + vertex 1.28704 2.15903 2.47137 + vertex 1.285 2.16372 2.47 + vertex 1.2823 2.16065 2.47118 + endloop + endfacet + facet normal 0.246685 0.852831 0.460245 + outer loop + vertex 1.28711 2.15687 2.4747 + vertex 1.28247 2.15837 2.47441 + vertex 1.2849 2.15609 2.47733 + endloop + endfacet + facet normal 0.231526 0.818774 0.525361 + outer loop + vertex 1.28711 2.15687 2.4747 + vertex 1.28704 2.15903 2.47137 + vertex 1.28247 2.15837 2.47441 + endloop + endfacet + facet normal 0.251406 0.79621 0.550314 + outer loop + vertex 1.28704 2.15903 2.47137 + vertex 1.2823 2.16065 2.47118 + vertex 1.28247 2.15837 2.47441 + endloop + endfacet + facet normal 0.207242 0.847438 0.488774 + outer loop + vertex 1.2849 2.15609 2.47733 + vertex 1.28247 2.15837 2.47441 + vertex 1.28072 2.15643 2.47851 + endloop + endfacet + facet normal 0.0582175 -0.614139 0.787048 + outer loop + vertex 1.295 0.867998 2.47 + vertex 1.29271 0.868005 2.47018 + vertex 1.29 0.867524 2.47 + endloop + endfacet + facet normal 0.142189 -0.927151 0.346659 + outer loop + vertex 1.29271 0.868005 2.47018 + vertex 1.28747 0.867634 2.47133 + vertex 1.29 0.867524 2.47 + endloop + endfacet + facet normal 0.148408 -0.913328 0.379218 + outer loop + vertex 1.29271 0.868005 2.47018 + vertex 1.2898 0.868822 2.47328 + vertex 1.28747 0.867634 2.47133 + endloop + endfacet + facet normal 0.177968 -0.897803 0.402836 + outer loop + vertex 1.29385 0.869093 2.4721 + vertex 1.2898 0.868822 2.47328 + vertex 1.29271 0.868005 2.47018 + endloop + endfacet + facet normal 0.17562 -0.902277 0.393769 + outer loop + vertex 1.2898 0.868822 2.47328 + vertex 1.29385 0.869093 2.4721 + vertex 1.29303 0.870428 2.47552 + endloop + endfacet + facet normal 0.180407 -0.903835 0.38799 + outer loop + vertex 1.28811 0.870218 2.47732 + vertex 1.2898 0.868822 2.47328 + vertex 1.29303 0.870428 2.47552 + endloop + endfacet + facet normal 0.200356 -0.872204 0.446227 + outer loop + vertex 1.29303 0.870428 2.47552 + vertex 1.29175 0.872509 2.48016 + vertex 1.28811 0.870218 2.47732 + endloop + endfacet + facet normal 0.199229 -0.871863 0.447395 + outer loop + vertex 1.29175 0.872509 2.48016 + vertex 1.28641 0.871849 2.48125 + vertex 1.28811 0.870218 2.47732 + endloop + endfacet + facet normal 0.212397 -0.806643 0.551556 + outer loop + vertex 1.29175 0.872509 2.48016 + vertex 1.289 0.874159 2.48364 + vertex 1.28641 0.871849 2.48125 + endloop + endfacet + facet normal 0.206762 -0.810045 0.548705 + outer loop + vertex 1.2927 0.874911 2.48335 + vertex 1.289 0.874159 2.48364 + vertex 1.29175 0.872509 2.48016 + endloop + endfacet + facet normal 0.194357 -0.694832 0.692412 + outer loop + vertex 1.289 0.874159 2.48364 + vertex 1.2927 0.874911 2.48335 + vertex 1.29127 0.876868 2.48572 + endloop + endfacet + facet normal 0.204535 -0.698369 0.685891 + outer loop + vertex 1.28699 0.87618 2.48629 + vertex 1.289 0.874159 2.48364 + vertex 1.29127 0.876868 2.48572 + endloop + endfacet + facet normal 0.198492 -0.563532 0.801893 + outer loop + vertex 1.29127 0.876868 2.48572 + vertex 1.28963 0.879609 2.48805 + vertex 1.28699 0.87618 2.48629 + endloop + endfacet + facet normal 0.196226 -0.56468 0.801644 + outer loop + vertex 1.29426 0.880045 2.48722 + vertex 1.28963 0.879609 2.48805 + vertex 1.29127 0.876868 2.48572 + endloop + endfacet + facet normal 0.19782 -0.453048 0.869261 + outer loop + vertex 1.29426 0.880045 2.48722 + vertex 1.29338 0.883884 2.48942 + vertex 1.28963 0.879609 2.48805 + endloop + endfacet + facet normal -0.41472 0.457602 -0.786516 + outer loop + vertex 1.29271 0.978271 2.50168 + vertex 1.29619 0.978572 2.50002 + vertex 1.295 0.977457 2.5 + endloop + endfacet + facet normal -0.4198 -0.897189 -0.137183 + outer loop + vertex 1.29271 0.978271 2.50168 + vertex 1.295 0.977457 2.5 + vertex 1.29 0.979032 2.505 + endloop + endfacet + facet normal 0.00458842 0.955097 -0.296259 + outer loop + vertex 1.29 0.979032 2.505 + vertex 1.295 0.977457 2.5 + vertex 1.29 0.977481 2.5 + endloop + endfacet + facet normal 0.318155 0.947075 0.0427318 + outer loop + vertex 1.29148 0.97854 2.5049 + vertex 1.29271 0.978271 2.50168 + vertex 1.29 0.979032 2.505 + endloop + endfacet + facet normal 0.2931 0.766566 0.571375 + outer loop + vertex 1.28869 0.977901 2.50719 + vertex 1.29148 0.97854 2.5049 + vertex 1.29 0.979032 2.505 + endloop + endfacet + facet normal -0.157616 0.984003 0.0830398 + outer loop + vertex 1.29228 0.978386 2.50824 + vertex 1.29148 0.97854 2.5049 + vertex 1.28869 0.977901 2.50719 + endloop + endfacet + facet normal -0.235005 0.890646 0.389259 + outer loop + vertex 1.29228 0.978386 2.50824 + vertex 1.28869 0.977901 2.50719 + vertex 1.29323 0.977183 2.51157 + endloop + endfacet + facet normal -0.0925616 0.962883 0.25355 + outer loop + vertex 1.29323 0.977183 2.51157 + vertex 1.28869 0.977901 2.50719 + vertex 1.28839 0.976774 2.51136 + endloop + endfacet + facet normal -0.0944554 0.834513 0.542832 + outer loop + vertex 1.29323 0.977183 2.51157 + vertex 1.28839 0.976774 2.51136 + vertex 1.29264 0.975211 2.5145 + endloop + endfacet + facet normal -0.0114244 0.888965 0.457832 + outer loop + vertex 1.29264 0.975211 2.5145 + vertex 1.28839 0.976774 2.51136 + vertex 1.2879 0.975062 2.51467 + endloop + endfacet + facet normal 0.027562 0.58793 0.808442 + outer loop + vertex 1.29125 0.972706 2.51627 + vertex 1.2879 0.975062 2.51467 + vertex 1.28624 0.972361 2.51669 + endloop + endfacet + facet normal 0.0113968 0.572605 0.819752 + outer loop + vertex 1.29264 0.975211 2.5145 + vertex 1.2879 0.975062 2.51467 + vertex 1.29125 0.972706 2.51627 + endloop + endfacet + facet normal -0.176858 0.964522 -0.196004 + outer loop + vertex 1.29619 0.978572 2.50002 + vertex 1.29271 0.978271 2.50168 + vertex 1.29482 0.978999 2.50336 + endloop + endfacet + facet normal -0.13825 0.990384 -0.00513426 + outer loop + vertex 1.29482 0.978999 2.50336 + vertex 1.29148 0.97854 2.5049 + vertex 1.29462 0.978992 2.50737 + endloop + endfacet + facet normal -0.206171 0.965432 -0.159482 + outer loop + vertex 1.29271 0.978271 2.50168 + vertex 1.29148 0.97854 2.5049 + vertex 1.29482 0.978999 2.50336 + endloop + endfacet + facet normal -0.215124 0.971836 0.0962119 + outer loop + vertex 1.29462 0.978992 2.50737 + vertex 1.29148 0.97854 2.5049 + vertex 1.29228 0.978386 2.50824 + endloop + endfacet + facet normal -0.276938 -0.775163 -0.567827 + outer loop + vertex 1.29089 2.04723 2.50307 + vertex 1.29247 2.04865 2.50037 + vertex 1.29557 2.04636 2.50197 + endloop + endfacet + facet normal -0.861858 -0.00465779 -0.507129 + outer loop + vertex 1.29 2.05 2.50455 + vertex 1.29247 2.04865 2.50037 + vertex 1.29089 2.04723 2.50307 + endloop + endfacet + facet normal -0.188853 -0.959054 -0.211067 + outer loop + vertex 1.28913 2.04677 2.50535 + vertex 1.29303 2.04561 2.50715 + vertex 1.28921 2.04621 2.50786 + endloop + endfacet + facet normal -0.142515 -0.942934 -0.300939 + outer loop + vertex 1.28913 2.04677 2.50535 + vertex 1.29089 2.04723 2.50307 + vertex 1.29303 2.04561 2.50715 + endloop + endfacet + facet normal -0.233536 -0.939216 -0.251662 + outer loop + vertex 1.29089 2.04723 2.50307 + vertex 1.29557 2.04636 2.50197 + vertex 1.29303 2.04561 2.50715 + endloop + endfacet + facet normal -0.201569 -0.976829 0.0719341 + outer loop + vertex 1.28921 2.04621 2.50786 + vertex 1.29042 2.04619 2.5111 + vertex 1.28743 2.0467 2.50965 + endloop + endfacet + facet normal -0.145195 -0.988096 0.0508343 + outer loop + vertex 1.28921 2.04621 2.50786 + vertex 1.29303 2.04561 2.50715 + vertex 1.29042 2.04619 2.5111 + endloop + endfacet + facet normal -0.170762 -0.984745 0.0334469 + outer loop + vertex 1.29303 2.04561 2.50715 + vertex 1.29381 2.04563 2.51172 + vertex 1.29042 2.04619 2.5111 + endloop + endfacet + facet normal -0.213043 -0.774276 0.59591 + outer loop + vertex 1.2893 2.04729 2.5138 + vertex 1.29205 2.04674 2.51408 + vertex 1.28972 2.04842 2.51542 + endloop + endfacet + facet normal -0.213752 -0.933322 0.28848 + outer loop + vertex 1.2893 2.04729 2.5138 + vertex 1.29042 2.04619 2.5111 + vertex 1.29205 2.04674 2.51408 + endloop + endfacet + facet normal -0.208413 -0.935313 0.285927 + outer loop + vertex 1.29042 2.04619 2.5111 + vertex 1.29381 2.04563 2.51172 + vertex 1.29205 2.04674 2.51408 + endloop + endfacet + facet normal -0.1168 -0.715153 0.68914 + outer loop + vertex 1.29205 2.04674 2.51408 + vertex 1.29268 2.04843 2.51594 + vertex 1.28972 2.04842 2.51542 + endloop + endfacet + facet normal -0.793227 -0.532181 -0.295929 + outer loop + vertex 1.29247 2.04865 2.50037 + vertex 1.29 2.05 2.50455 + vertex 1.29 2.05253 2.5 + endloop + endfacet + facet normal -0.027283 -0.111817 -0.993354 + outer loop + vertex 1.295 2.05131 2.5 + vertex 1.29247 2.04865 2.50037 + vertex 1.29 2.05253 2.5 + endloop + endfacet + facet normal -0.309818 -0.929423 -0.200464 + outer loop + vertex 1.28913 2.04677 2.50535 + vertex 1.28921 2.04621 2.50786 + vertex 1.2861 2.04752 2.50657 + endloop + endfacet + facet normal -0.354657 -0.930348 -0.0931186 + outer loop + vertex 1.28921 2.04621 2.50786 + vertex 1.28743 2.0467 2.50965 + vertex 1.2861 2.04752 2.50657 + endloop + endfacet + facet normal -0.273108 -0.75409 0.597294 + outer loop + vertex 1.2893 2.04729 2.5138 + vertex 1.28972 2.04842 2.51542 + vertex 1.28626 2.049 2.51457 + endloop + endfacet + facet normal -0.282557 -0.433352 0.855785 + outer loop + vertex 1.28972 2.04842 2.51542 + vertex 1.28799 2.05173 2.51653 + vertex 1.28626 2.049 2.51457 + endloop + endfacet + facet normal -0.157507 -0.386056 0.908929 + outer loop + vertex 1.28972 2.04842 2.51542 + vertex 1.29268 2.04843 2.51594 + vertex 1.28799 2.05173 2.51653 + endloop + endfacet + facet normal -0.0573275 -0.253737 0.965573 + outer loop + vertex 1.29268 2.04843 2.51594 + vertex 1.29312 2.05097 2.51663 + vertex 1.28799 2.05173 2.51653 + endloop + endfacet + facet normal 0.182809 0.467228 0.865031 + outer loop + vertex 1.29233 2.14244 2.48883 + vertex 1.29187 2.14556 2.48725 + vertex 1.28813 2.14279 2.48953 + endloop + endfacet + facet normal 0.199023 0.449943 0.870598 + outer loop + vertex 1.28813 2.14279 2.48953 + vertex 1.29187 2.14556 2.48725 + vertex 1.28724 2.14684 2.48764 + endloop + endfacet + facet normal 0.20598 0.679029 0.704622 + outer loop + vertex 1.28923 2.14905 2.48554 + vertex 1.29363 2.14885 2.48444 + vertex 1.29121 2.15127 2.48282 + endloop + endfacet + facet normal 0.218109 0.672013 0.707691 + outer loop + vertex 1.28697 2.15161 2.4838 + vertex 1.28923 2.14905 2.48554 + vertex 1.29121 2.15127 2.48282 + endloop + endfacet + facet normal 0.223052 0.559175 0.798481 + outer loop + vertex 1.29187 2.14556 2.48725 + vertex 1.28923 2.14905 2.48554 + vertex 1.28724 2.14684 2.48764 + endloop + endfacet + facet normal 0.223863 0.559548 0.797992 + outer loop + vertex 1.29363 2.14885 2.48444 + vertex 1.28923 2.14905 2.48554 + vertex 1.29187 2.14556 2.48725 + endloop + endfacet + facet normal 0.160705 0.892521 0.421402 + outer loop + vertex 1.28937 2.15506 2.47766 + vertex 1.29405 2.1551 2.47578 + vertex 1.29122 2.15667 2.47355 + endloop + endfacet + facet normal 0.161742 0.892177 0.421735 + outer loop + vertex 1.28711 2.15687 2.4747 + vertex 1.28937 2.15506 2.47766 + vertex 1.29122 2.15667 2.47355 + endloop + endfacet + facet normal 0.183443 0.859281 0.477478 + outer loop + vertex 1.29405 2.1551 2.47578 + vertex 1.28937 2.15506 2.47766 + vertex 1.29365 2.15321 2.47934 + endloop + endfacet + facet normal 0.179281 0.85614 0.484647 + outer loop + vertex 1.29365 2.15321 2.47934 + vertex 1.28937 2.15506 2.47766 + vertex 1.28913 2.15316 2.48111 + endloop + endfacet + facet normal 0.202006 0.770605 0.604451 + outer loop + vertex 1.29121 2.15127 2.48282 + vertex 1.28913 2.15316 2.48111 + vertex 1.28697 2.15161 2.4838 + endloop + endfacet + facet normal 0.22114 0.777522 0.58869 + outer loop + vertex 1.29365 2.15321 2.47934 + vertex 1.28913 2.15316 2.48111 + vertex 1.29121 2.15127 2.48282 + endloop + endfacet + facet normal 0.0141443 0.110476 0.993778 + outer loop + vertex 1.295 2.162 2.47 + vertex 1.29 2.16264 2.47 + vertex 1.29278 2.15855 2.47041 + endloop + endfacet + facet normal 0.176988 0.217849 0.959801 + outer loop + vertex 1.29278 2.15855 2.47041 + vertex 1.29 2.16264 2.47 + vertex 1.28704 2.15903 2.47137 + endloop + endfacet + facet normal 0.189167 0.826062 0.530884 + outer loop + vertex 1.29122 2.15667 2.47355 + vertex 1.28704 2.15903 2.47137 + vertex 1.28711 2.15687 2.4747 + endloop + endfacet + facet normal 0.160743 0.808464 0.566169 + outer loop + vertex 1.29278 2.15855 2.47041 + vertex 1.28704 2.15903 2.47137 + vertex 1.29122 2.15667 2.47355 + endloop + endfacet + facet normal 0.107231 0.386584 0.915999 + outer loop + vertex 1.29657 0.868739 2.47022 + vertex 1.3 0.86832 2.47 + vertex 1.30022 0.86924 2.46959 + endloop + endfacet + facet normal 0.0337694 -0.243036 0.969429 + outer loop + vertex 1.29657 0.868739 2.47022 + vertex 1.29271 0.868005 2.47018 + vertex 1.3 0.86832 2.47 + endloop + endfacet + facet normal 0.0481886 -0.748306 0.661601 + outer loop + vertex 1.29271 0.868005 2.47018 + vertex 1.295 0.867998 2.47 + vertex 1.3 0.86832 2.47 + endloop + endfacet + facet normal 0.16537 -0.897044 0.409835 + outer loop + vertex 1.29657 0.868739 2.47022 + vertex 1.29385 0.869093 2.4721 + vertex 1.29271 0.868005 2.47018 + endloop + endfacet + facet normal 0.195932 -0.883385 0.425725 + outer loop + vertex 1.30022 0.86924 2.46959 + vertex 1.29857 0.870283 2.47251 + vertex 1.29657 0.868739 2.47022 + endloop + endfacet + facet normal 0.184416 -0.881546 0.434588 + outer loop + vertex 1.29385 0.869093 2.4721 + vertex 1.29657 0.868739 2.47022 + vertex 1.29857 0.870283 2.47251 + endloop + endfacet + facet normal 0.191885 -0.897988 0.395977 + outer loop + vertex 1.29385 0.869093 2.4721 + vertex 1.29857 0.870283 2.47251 + vertex 1.29303 0.870428 2.47552 + endloop + endfacet + facet normal 0.2026 -0.886908 0.415148 + outer loop + vertex 1.29303 0.870428 2.47552 + vertex 1.29857 0.870283 2.47251 + vertex 1.29687 0.872236 2.47751 + endloop + endfacet + facet normal 0.161106 -0.846918 0.506729 + outer loop + vertex 1.29644 0.874635 2.48166 + vertex 1.29687 0.872236 2.47751 + vertex 1.3001 0.873943 2.47934 + endloop + endfacet + facet normal 0.217501 -0.834912 0.505584 + outer loop + vertex 1.29644 0.874635 2.48166 + vertex 1.29175 0.872509 2.48016 + vertex 1.29687 0.872236 2.47751 + endloop + endfacet + facet normal 0.18319 -0.877229 0.443745 + outer loop + vertex 1.29175 0.872509 2.48016 + vertex 1.29303 0.870428 2.47552 + vertex 1.29687 0.872236 2.47751 + endloop + endfacet + facet normal 0.191117 -0.810482 0.553709 + outer loop + vertex 1.29644 0.874635 2.48166 + vertex 1.2927 0.874911 2.48335 + vertex 1.29175 0.872509 2.48016 + endloop + endfacet + facet normal 0.182649 -0.825339 0.534281 + outer loop + vertex 1.3001 0.873943 2.47934 + vertex 1.2996 0.875301 2.48161 + vertex 1.29644 0.874635 2.48166 + endloop + endfacet + facet normal 0.199038 -0.692559 0.693359 + outer loop + vertex 1.2927 0.874911 2.48335 + vertex 1.29523 0.877118 2.48483 + vertex 1.29127 0.876868 2.48572 + endloop + endfacet + facet normal 0.243313 -0.7167 0.653559 + outer loop + vertex 1.29644 0.874635 2.48166 + vertex 1.29523 0.877118 2.48483 + vertex 1.2927 0.874911 2.48335 + endloop + endfacet + facet normal 0.200313 -0.733061 0.649997 + outer loop + vertex 1.29644 0.874635 2.48166 + vertex 1.29951 0.877335 2.48376 + vertex 1.29523 0.877118 2.48483 + endloop + endfacet + facet normal 0.161466 -0.713567 0.681727 + outer loop + vertex 1.29644 0.874635 2.48166 + vertex 1.2996 0.875301 2.48161 + vertex 1.29951 0.877335 2.48376 + endloop + endfacet + facet normal 0.213248 -0.575097 0.789803 + outer loop + vertex 1.29523 0.877118 2.48483 + vertex 1.29426 0.880045 2.48722 + vertex 1.29127 0.876868 2.48572 + endloop + endfacet + facet normal 0.221629 -0.611573 0.759512 + outer loop + vertex 1.29951 0.877335 2.48376 + vertex 1.29773 0.879701 2.48618 + vertex 1.29523 0.877118 2.48483 + endloop + endfacet + facet normal 0.179271 -0.586431 0.789912 + outer loop + vertex 1.29773 0.879701 2.48618 + vertex 1.29426 0.880045 2.48722 + vertex 1.29523 0.877118 2.48483 + endloop + endfacet + facet normal 0.209458 -0.47617 0.854043 + outer loop + vertex 1.29773 0.879701 2.48618 + vertex 1.29877 0.883645 2.48812 + vertex 1.29426 0.880045 2.48722 + endloop + endfacet + facet normal 0.189632 -0.455304 0.869907 + outer loop + vertex 1.29877 0.883645 2.48812 + vertex 1.29338 0.883884 2.48942 + vertex 1.29426 0.880045 2.48722 + endloop + endfacet + facet normal -0.00903042 0.0265603 -0.999606 + outer loop + vertex 1.3 0.979157 2.5 + vertex 1.295 0.977457 2.5 + vertex 1.29619 0.978572 2.50002 + endloop + endfacet + facet normal 0.144562 -0.949411 -0.278785 + outer loop + vertex 1.29971 0.979373 2.49911 + vertex 1.3 0.979157 2.5 + vertex 1.29619 0.978572 2.50002 + endloop + endfacet + facet normal -0.283519 0.873007 0.396831 + outer loop + vertex 1.29516 0.978345 2.51039 + vertex 1.29228 0.978386 2.50824 + vertex 1.29323 0.977183 2.51157 + endloop + endfacet + facet normal -0.128979 0.803945 0.580549 + outer loop + vertex 1.29814 0.976894 2.51306 + vertex 1.29516 0.978345 2.51039 + vertex 1.29323 0.977183 2.51157 + endloop + endfacet + facet normal -0.17729 0.676436 0.714844 + outer loop + vertex 1.29814 0.976894 2.51306 + vertex 1.29323 0.977183 2.51157 + vertex 1.29688 0.974879 2.51466 + endloop + endfacet + facet normal 0.0437037 0.824473 0.564212 + outer loop + vertex 1.29688 0.974879 2.51466 + vertex 1.29323 0.977183 2.51157 + vertex 1.29264 0.975211 2.5145 + endloop + endfacet + facet normal 0.0434153 0.560183 0.827231 + outer loop + vertex 1.29541 0.972837 2.51596 + vertex 1.29264 0.975211 2.5145 + vertex 1.29125 0.972706 2.51627 + endloop + endfacet + facet normal 0.0105891 0.533257 0.845887 + outer loop + vertex 1.29688 0.974879 2.51466 + vertex 1.29264 0.975211 2.5145 + vertex 1.29541 0.972837 2.51596 + endloop + endfacet + facet normal -0.257417 0.953584 -0.156251 + outer loop + vertex 1.29619 0.978572 2.50002 + vertex 1.29961 0.97982 2.502 + vertex 1.29971 0.979373 2.49911 + endloop + endfacet + facet normal -0.223328 0.951098 -0.213396 + outer loop + vertex 1.29482 0.978999 2.50336 + vertex 1.29961 0.97982 2.502 + vertex 1.29619 0.978572 2.50002 + endloop + endfacet + facet normal -0.166746 0.985968 0.00797183 + outer loop + vertex 1.29961 0.97982 2.502 + vertex 1.29482 0.978999 2.50336 + vertex 1.29849 0.979591 2.50684 + endloop + endfacet + facet normal -0.153899 0.988069 -0.00591591 + outer loop + vertex 1.29849 0.979591 2.50684 + vertex 1.29482 0.978999 2.50336 + vertex 1.29462 0.978992 2.50737 + endloop + endfacet + facet normal -0.160694 0.958916 0.23379 + outer loop + vertex 1.29516 0.978345 2.51039 + vertex 1.29462 0.978992 2.50737 + vertex 1.29228 0.978386 2.50824 + endloop + endfacet + facet normal -0.119715 0.966245 0.228119 + outer loop + vertex 1.29516 0.978345 2.51039 + vertex 1.2986 0.97869 2.51073 + vertex 1.29462 0.978992 2.50737 + endloop + endfacet + facet normal -0.118732 0.966632 0.226992 + outer loop + vertex 1.2986 0.97869 2.51073 + vertex 1.29849 0.979591 2.50684 + vertex 1.29462 0.978992 2.50737 + endloop + endfacet + facet normal -0.138383 0.797331 0.587463 + outer loop + vertex 1.2986 0.97869 2.51073 + vertex 1.29516 0.978345 2.51039 + vertex 1.29814 0.976894 2.51306 + endloop + endfacet + facet normal -0.396749 -0.639436 -0.658568 + outer loop + vertex 1.3 2.04794 2.5 + vertex 1.29668 2.05 2.5 + vertex 1.3 2.05 2.498 + endloop + endfacet + facet normal 0.0831862 -0.495147 -0.864818 + outer loop + vertex 1.29668 2.05 2.5 + vertex 1.29557 2.04636 2.50197 + vertex 1.29247 2.04865 2.50037 + endloop + endfacet + facet normal -0.249453 -0.402041 -0.880986 + outer loop + vertex 1.29668 2.05 2.5 + vertex 1.3 2.04794 2.5 + vertex 1.29557 2.04636 2.50197 + endloop + endfacet + facet normal -0.0651803 -0.703429 -0.707771 + outer loop + vertex 1.3 2.04794 2.5 + vertex 1.29997 2.04502 2.5029 + vertex 1.29557 2.04636 2.50197 + endloop + endfacet + facet normal -0.246565 -0.947935 -0.201559 + outer loop + vertex 1.29997 2.04502 2.5029 + vertex 1.29829 2.04469 2.50649 + vertex 1.29557 2.04636 2.50197 + endloop + endfacet + facet normal -0.194641 -0.952421 -0.234542 + outer loop + vertex 1.29829 2.04469 2.50649 + vertex 1.29303 2.04561 2.50715 + vertex 1.29557 2.04636 2.50197 + endloop + endfacet + facet normal -0.166566 -0.985402 0.0351986 + outer loop + vertex 1.29829 2.04469 2.50649 + vertex 1.29724 2.04503 2.51081 + vertex 1.29303 2.04561 2.50715 + endloop + endfacet + facet normal -0.164138 -0.985908 0.0323241 + outer loop + vertex 1.29724 2.04503 2.51081 + vertex 1.29381 2.04563 2.51172 + vertex 1.29303 2.04561 2.50715 + endloop + endfacet + facet normal -0.081894 -0.945035 0.316547 + outer loop + vertex 1.29724 2.04503 2.51081 + vertex 1.29575 2.04627 2.51414 + vertex 1.29381 2.04563 2.51172 + endloop + endfacet + facet normal -0.124122 -0.92988 0.346289 + outer loop + vertex 1.29575 2.04627 2.51414 + vertex 1.29205 2.04674 2.51408 + vertex 1.29381 2.04563 2.51172 + endloop + endfacet + facet normal -0.103338 -0.718592 0.687712 + outer loop + vertex 1.29575 2.04627 2.51414 + vertex 1.29268 2.04843 2.51594 + vertex 1.29205 2.04674 2.51408 + endloop + endfacet + facet normal -0.0597714 -0.687057 0.724141 + outer loop + vertex 1.29729 2.04815 2.51605 + vertex 1.29268 2.04843 2.51594 + vertex 1.29575 2.04627 2.51414 + endloop + endfacet + facet normal -0.0617811 -0.0792248 -0.99494 + outer loop + vertex 1.29668 2.05 2.5 + vertex 1.29247 2.04865 2.50037 + vertex 1.295 2.05131 2.5 + endloop + endfacet + facet normal -0.0394114 -0.256846 0.965648 + outer loop + vertex 1.29312 2.05097 2.51663 + vertex 1.29268 2.04843 2.51594 + vertex 1.29729 2.04815 2.51605 + endloop + endfacet + facet normal 0.207093 0.3739 0.904053 + outer loop + vertex 1.29298 2.13913 2.49005 + vertex 1.29628 2.14234 2.48797 + vertex 1.29233 2.14244 2.48883 + endloop + endfacet + facet normal 0.182815 0.539741 0.821741 + outer loop + vertex 1.29992 2.14456 2.48605 + vertex 1.2992 2.14684 2.48471 + vertex 1.29651 2.14632 2.48565 + endloop + endfacet + facet normal 0.153234 0.490751 0.857719 + outer loop + vertex 1.29651 2.14632 2.48565 + vertex 1.29628 2.14234 2.48797 + vertex 1.29992 2.14456 2.48605 + endloop + endfacet + facet normal 0.212813 0.4825 0.84965 + outer loop + vertex 1.29651 2.14632 2.48565 + vertex 1.29187 2.14556 2.48725 + vertex 1.29628 2.14234 2.48797 + endloop + endfacet + facet normal 0.200153 0.467709 0.860922 + outer loop + vertex 1.29187 2.14556 2.48725 + vertex 1.29233 2.14244 2.48883 + vertex 1.29628 2.14234 2.48797 + endloop + endfacet + facet normal 0.243565 0.744426 0.621697 + outer loop + vertex 1.29859 2.14919 2.48267 + vertex 1.29749 2.15196 2.47978 + vertex 1.29487 2.15105 2.4819 + endloop + endfacet + facet normal 0.21604 0.683885 0.69687 + outer loop + vertex 1.29487 2.15105 2.4819 + vertex 1.29121 2.15127 2.48282 + vertex 1.29363 2.14885 2.48444 + endloop + endfacet + facet normal 0.201482 0.690072 0.695129 + outer loop + vertex 1.29859 2.14919 2.48267 + vertex 1.29487 2.15105 2.4819 + vertex 1.29363 2.14885 2.48444 + endloop + endfacet + facet normal 0.227215 0.617755 0.752829 + outer loop + vertex 1.29859 2.14919 2.48267 + vertex 1.29363 2.14885 2.48444 + vertex 1.29651 2.14632 2.48565 + endloop + endfacet + facet normal 0.126439 0.669181 0.732264 + outer loop + vertex 1.29859 2.14919 2.48267 + vertex 1.29651 2.14632 2.48565 + vertex 1.2992 2.14684 2.48471 + endloop + endfacet + facet normal 0.177687 0.581121 0.794182 + outer loop + vertex 1.29651 2.14632 2.48565 + vertex 1.29363 2.14885 2.48444 + vertex 1.29187 2.14556 2.48725 + endloop + endfacet + facet normal 0.188998 0.876679 0.442394 + outer loop + vertex 1.29405 2.1551 2.47578 + vertex 1.29893 2.15405 2.47579 + vertex 1.29604 2.15628 2.4726 + endloop + endfacet + facet normal 0.15561 0.890888 0.426737 + outer loop + vertex 1.29122 2.15667 2.47355 + vertex 1.29405 2.1551 2.47578 + vertex 1.29604 2.15628 2.4726 + endloop + endfacet + facet normal 0.191478 0.792905 0.578479 + outer loop + vertex 1.29749 2.15196 2.47978 + vertex 1.29365 2.15321 2.47934 + vertex 1.29487 2.15105 2.4819 + endloop + endfacet + facet normal 0.212147 0.832696 0.511479 + outer loop + vertex 1.29749 2.15196 2.47978 + vertex 1.29893 2.15405 2.47579 + vertex 1.29365 2.15321 2.47934 + endloop + endfacet + facet normal 0.185108 0.858925 0.477475 + outer loop + vertex 1.29893 2.15405 2.47579 + vertex 1.29405 2.1551 2.47578 + vertex 1.29365 2.15321 2.47934 + endloop + endfacet + facet normal 0.193259 0.793018 0.577731 + outer loop + vertex 1.29487 2.15105 2.4819 + vertex 1.29365 2.15321 2.47934 + vertex 1.29121 2.15127 2.48282 + endloop + endfacet + facet normal -0.0023926 -0.0460333 0.998937 + outer loop + vertex 1.3 2.16174 2.47 + vertex 1.295 2.162 2.47 + vertex 1.29846 2.15824 2.46984 + endloop + endfacet + facet normal 0.104294 0.0524069 0.993165 + outer loop + vertex 1.29846 2.15824 2.46984 + vertex 1.295 2.162 2.47 + vertex 1.29278 2.15855 2.47041 + endloop + endfacet + facet normal 0.176644 0.802191 0.570338 + outer loop + vertex 1.29604 2.15628 2.4726 + vertex 1.29278 2.15855 2.47041 + vertex 1.29122 2.15667 2.47355 + endloop + endfacet + facet normal 0.106937 0.76483 0.635295 + outer loop + vertex 1.29846 2.15824 2.46984 + vertex 1.29278 2.15855 2.47041 + vertex 1.29604 2.15628 2.4726 + endloop + endfacet + facet normal -0.190704 0.439297 0.877867 + outer loop + vertex 1.30387 0.87 2.47 + vertex 1.30022 0.86924 2.46959 + vertex 1.3 0.86832 2.47 + endloop + endfacet + facet normal -0.159867 0.24883 0.955262 + outer loop + vertex 1.30022 0.86924 2.46959 + vertex 1.30387 0.87 2.47 + vertex 1.305 0.870726 2.47 + endloop + endfacet + facet normal 0.231392 -0.867644 0.440058 + outer loop + vertex 1.30022 0.86924 2.46959 + vertex 1.305 0.870726 2.47 + vertex 1.29857 0.870283 2.47251 + endloop + endfacet + facet normal 0.199777 -0.914963 0.350616 + outer loop + vertex 1.29857 0.870283 2.47251 + vertex 1.305 0.870726 2.47 + vertex 1.30288 0.871096 2.47217 + endloop + endfacet + facet normal 0.199769 -0.896846 0.394663 + outer loop + vertex 1.30288 0.871096 2.47217 + vertex 1.30193 0.872291 2.47537 + vertex 1.29857 0.870283 2.47251 + endloop + endfacet + facet normal 0.1835 -0.892974 0.411004 + outer loop + vertex 1.30193 0.872291 2.47537 + vertex 1.29687 0.872236 2.47751 + vertex 1.29857 0.870283 2.47251 + endloop + endfacet + facet normal 0.201585 -0.867696 0.454387 + outer loop + vertex 1.30193 0.872291 2.47537 + vertex 1.3001 0.873943 2.47934 + vertex 1.29687 0.872236 2.47751 + endloop + endfacet + facet normal 0.180696 -0.87556 0.448045 + outer loop + vertex 1.30353 0.874017 2.4781 + vertex 1.3001 0.873943 2.47934 + vertex 1.30193 0.872291 2.47537 + endloop + endfacet + facet normal 0.215117 -0.808795 0.547334 + outer loop + vertex 1.3001 0.873943 2.47934 + vertex 1.30353 0.874017 2.4781 + vertex 1.30291 0.875851 2.48105 + endloop + endfacet + facet normal 0.224853 -0.813383 0.536515 + outer loop + vertex 1.2996 0.875301 2.48161 + vertex 1.3001 0.873943 2.47934 + vertex 1.30291 0.875851 2.48105 + endloop + endfacet + facet normal 0.229357 -0.702344 0.673876 + outer loop + vertex 1.30291 0.875851 2.48105 + vertex 1.29951 0.877335 2.48376 + vertex 1.2996 0.875301 2.48161 + endloop + endfacet + facet normal 0.22203 -0.709638 0.668668 + outer loop + vertex 1.30418 0.878775 2.48373 + vertex 1.29951 0.877335 2.48376 + vertex 1.30291 0.875851 2.48105 + endloop + endfacet + facet normal 0.187049 -0.594504 0.782034 + outer loop + vertex 1.29951 0.877335 2.48376 + vertex 1.30418 0.878775 2.48373 + vertex 1.30157 0.880941 2.486 + endloop + endfacet + facet normal 0.230654 -0.606345 0.761015 + outer loop + vertex 1.29773 0.879701 2.48618 + vertex 1.29951 0.877335 2.48376 + vertex 1.30157 0.880941 2.486 + endloop + endfacet + facet normal 0.192439 -0.474192 0.859133 + outer loop + vertex 1.30157 0.880941 2.486 + vertex 1.29877 0.883645 2.48812 + vertex 1.29773 0.879701 2.48618 + endloop + endfacet + facet normal 0.198525 -0.469031 0.86058 + outer loop + vertex 1.3043 0.884925 2.48755 + vertex 1.29877 0.883645 2.48812 + vertex 1.30157 0.880941 2.486 + endloop + endfacet + facet normal 0.500267 -0.789236 -0.356146 + outer loop + vertex 1.30133 0.98 2.5 + vertex 1.3 0.979157 2.5 + vertex 1.29971 0.979373 2.49911 + endloop + endfacet + facet normal 0.070862 0.391285 0.917537 + outer loop + vertex 1.29688 0.974879 2.51466 + vertex 1.29818 0.972234 2.51568 + vertex 1.30106 0.973434 2.51495 + endloop + endfacet + facet normal 0.136292 0.560477 0.816878 + outer loop + vertex 1.29688 0.974879 2.51466 + vertex 1.30106 0.973434 2.51495 + vertex 1.29814 0.976894 2.51306 + endloop + endfacet + facet normal -0.205264 0.32907 0.921727 + outer loop + vertex 1.29814 0.976894 2.51306 + vertex 1.30106 0.973434 2.51495 + vertex 1.30322 0.977188 2.51409 + endloop + endfacet + facet normal 0.183211 0.43286 0.882647 + outer loop + vertex 1.29818 0.972234 2.51568 + vertex 1.29688 0.974879 2.51466 + vertex 1.29541 0.972837 2.51596 + endloop + endfacet + facet normal -0.316053 0.671243 -0.67048 + outer loop + vertex 1.305 0.98 2.49827 + vertex 1.30133 0.98 2.5 + vertex 1.305 0.981728 2.5 + endloop + endfacet + facet normal 0.421963 -0.896178 -0.137162 + outer loop + vertex 1.29971 0.979373 2.49911 + vertex 1.305 0.981728 2.5 + vertex 1.30133 0.98 2.5 + endloop + endfacet + facet normal -0.380253 0.91197 -0.154008 + outer loop + vertex 1.29971 0.979373 2.49911 + vertex 1.29961 0.97982 2.502 + vertex 1.305 0.981728 2.5 + endloop + endfacet + facet normal -0.241778 0.939065 0.244336 + outer loop + vertex 1.29961 0.97982 2.502 + vertex 1.30441 0.980801 2.50298 + vertex 1.305 0.981728 2.5 + endloop + endfacet + facet normal -0.209245 0.976778 0.0460593 + outer loop + vertex 1.30441 0.980801 2.50298 + vertex 1.29961 0.97982 2.502 + vertex 1.30298 0.980326 2.50658 + endloop + endfacet + facet normal -0.160965 0.986916 0.00935439 + outer loop + vertex 1.30298 0.980326 2.50658 + vertex 1.29961 0.97982 2.502 + vertex 1.29849 0.979591 2.50684 + endloop + endfacet + facet normal -0.145916 0.966748 0.210017 + outer loop + vertex 1.30298 0.980326 2.50658 + vertex 1.29849 0.979591 2.50684 + vertex 1.30334 0.979357 2.51129 + endloop + endfacet + facet normal -0.161534 0.960473 0.226712 + outer loop + vertex 1.30334 0.979357 2.51129 + vertex 1.29849 0.979591 2.50684 + vertex 1.2986 0.97869 2.51073 + endloop + endfacet + facet normal -0.163706 0.796578 0.581948 + outer loop + vertex 1.30322 0.977188 2.51409 + vertex 1.2986 0.97869 2.51073 + vertex 1.29814 0.976894 2.51306 + endloop + endfacet + facet normal -0.180006 0.781337 0.597587 + outer loop + vertex 1.30334 0.979357 2.51129 + vertex 1.2986 0.97869 2.51073 + vertex 1.30322 0.977188 2.51409 + endloop + endfacet + facet normal -0.107772 -0.681998 -0.72337 + outer loop + vertex 1.305 2.04715 2.5 + vertex 1.30381 2.04478 2.50242 + vertex 1.3 2.04794 2.5 + endloop + endfacet + facet normal -0.133957 -0.69817 -0.703288 + outer loop + vertex 1.30381 2.04478 2.50242 + vertex 1.29997 2.04502 2.5029 + vertex 1.3 2.04794 2.5 + endloop + endfacet + facet normal -0.0819414 -0.985863 -0.14615 + outer loop + vertex 1.30381 2.04478 2.50242 + vertex 1.30277 2.04424 2.50661 + vertex 1.29997 2.04502 2.5029 + endloop + endfacet + facet normal -0.0965924 -0.986112 -0.135104 + outer loop + vertex 1.30277 2.04424 2.50661 + vertex 1.29829 2.04469 2.50649 + vertex 1.29997 2.04502 2.5029 + endloop + endfacet + facet normal -0.101833 -0.994103 0.0372629 + outer loop + vertex 1.30277 2.04424 2.50661 + vertex 1.30108 2.04454 2.51007 + vertex 1.29829 2.04469 2.50649 + endloop + endfacet + facet normal -0.115647 -0.992125 0.0481027 + outer loop + vertex 1.30108 2.04454 2.51007 + vertex 1.29724 2.04503 2.51081 + vertex 1.29829 2.04469 2.50649 + endloop + endfacet + facet normal -0.0606096 -0.950469 0.304853 + outer loop + vertex 1.30108 2.04454 2.51007 + vertex 1.3006 2.04575 2.51374 + vertex 1.29724 2.04503 2.51081 + endloop + endfacet + facet normal -0.0747267 -0.944601 0.319601 + outer loop + vertex 1.3006 2.04575 2.51374 + vertex 1.29575 2.04627 2.51414 + vertex 1.29724 2.04503 2.51081 + endloop + endfacet + facet normal -0.0166893 -0.705998 0.708017 + outer loop + vertex 1.3006 2.04575 2.51374 + vertex 1.29729 2.04815 2.51605 + vertex 1.29575 2.04627 2.51414 + endloop + endfacet + facet normal -0.0935164 -0.754994 0.64903 + outer loop + vertex 1.30148 2.04739 2.51577 + vertex 1.29729 2.04815 2.51605 + vertex 1.3006 2.04575 2.51374 + endloop + endfacet + facet normal 0.202824 0.556982 0.805378 + outer loop + vertex 1.29992 2.14456 2.48605 + vertex 1.3042 2.14353 2.48568 + vertex 1.30214 2.14667 2.48403 + endloop + endfacet + facet normal 0.219091 0.544181 0.809856 + outer loop + vertex 1.2992 2.14684 2.48471 + vertex 1.29992 2.14456 2.48605 + vertex 1.30214 2.14667 2.48403 + endloop + endfacet + facet normal 0.186753 0.449431 0.873576 + outer loop + vertex 1.30152 2.14091 2.48758 + vertex 1.29992 2.14456 2.48605 + vertex 1.29628 2.14234 2.48797 + endloop + endfacet + facet normal 0.182891 0.44832 0.874963 + outer loop + vertex 1.3042 2.14353 2.48568 + vertex 1.29992 2.14456 2.48605 + vertex 1.30152 2.14091 2.48758 + endloop + endfacet + facet normal 0.18952 0.762263 0.6189 + outer loop + vertex 1.29859 2.14919 2.48267 + vertex 1.3041 2.14904 2.48117 + vertex 1.30145 2.15154 2.47889 + endloop + endfacet + facet normal 0.219749 0.744309 0.630646 + outer loop + vertex 1.29749 2.15196 2.47978 + vertex 1.29859 2.14919 2.48267 + vertex 1.30145 2.15154 2.47889 + endloop + endfacet + facet normal 0.203701 0.671779 0.712193 + outer loop + vertex 1.30214 2.14667 2.48403 + vertex 1.29859 2.14919 2.48267 + vertex 1.2992 2.14684 2.48471 + endloop + endfacet + facet normal 0.210447 0.677346 0.704922 + outer loop + vertex 1.3041 2.14904 2.48117 + vertex 1.29859 2.14919 2.48267 + vertex 1.30214 2.14667 2.48403 + endloop + endfacet + facet normal 0.129757 0.776032 0.617202 + outer loop + vertex 1.30403 2.15483 2.47234 + vertex 1.30247 2.15687 2.47011 + vertex 1.30005 2.15589 2.47185 + endloop + endfacet + facet normal 0.170601 0.873157 0.456609 + outer loop + vertex 1.30005 2.15589 2.47185 + vertex 1.29604 2.15628 2.4726 + vertex 1.29893 2.15405 2.47579 + endloop + endfacet + facet normal 0.174915 0.871952 0.457279 + outer loop + vertex 1.30005 2.15589 2.47185 + vertex 1.29893 2.15405 2.47579 + vertex 1.30403 2.15483 2.47234 + endloop + endfacet + facet normal 0.18982 0.858547 0.476303 + outer loop + vertex 1.30403 2.15483 2.47234 + vertex 1.29893 2.15405 2.47579 + vertex 1.30374 2.15296 2.47583 + endloop + endfacet + facet normal 0.202457 0.836136 0.509791 + outer loop + vertex 1.30145 2.15154 2.47889 + vertex 1.29893 2.15405 2.47579 + vertex 1.29749 2.15196 2.47978 + endloop + endfacet + facet normal 0.18361 0.832719 0.522366 + outer loop + vertex 1.30374 2.15296 2.47583 + vertex 1.29893 2.15405 2.47579 + vertex 1.30145 2.15154 2.47889 + endloop + endfacet + facet normal 0.197197 0.711517 0.674431 + outer loop + vertex 1.30247 2.15687 2.47011 + vertex 1.29846 2.15824 2.46984 + vertex 1.30005 2.15589 2.47185 + endloop + endfacet + facet normal -0.0479814 0.0589955 0.997104 + outer loop + vertex 1.30247 2.15687 2.47011 + vertex 1.305 2.16077 2.47 + vertex 1.29846 2.15824 2.46984 + endloop + endfacet + facet normal -0.00841821 -0.0433872 0.999023 + outer loop + vertex 1.305 2.16077 2.47 + vertex 1.3 2.16174 2.47 + vertex 1.29846 2.15824 2.46984 + endloop + endfacet + facet normal 0.195936 0.711233 0.675097 + outer loop + vertex 1.30005 2.15589 2.47185 + vertex 1.29846 2.15824 2.46984 + vertex 1.29604 2.15628 2.4726 + endloop + endfacet + facet normal 0.12471 -0.911591 0.391725 + outer loop + vertex 1.31 0.87141 2.47 + vertex 1.30652 0.87194 2.47234 + vertex 1.305 0.870726 2.47 + endloop + endfacet + facet normal 0.196588 -0.916725 0.347805 + outer loop + vertex 1.30652 0.87194 2.47234 + vertex 1.30288 0.871096 2.47217 + vertex 1.305 0.870726 2.47 + endloop + endfacet + facet normal 0.191363 -0.895207 0.402474 + outer loop + vertex 1.30573 0.873319 2.47579 + vertex 1.30652 0.87194 2.47234 + vertex 1.30953 0.873606 2.47462 + endloop + endfacet + facet normal 0.197789 -0.893458 0.403251 + outer loop + vertex 1.30573 0.873319 2.47579 + vertex 1.30193 0.872291 2.47537 + vertex 1.30652 0.87194 2.47234 + endloop + endfacet + facet normal 0.190516 -0.899612 0.39294 + outer loop + vertex 1.30193 0.872291 2.47537 + vertex 1.30288 0.871096 2.47217 + vertex 1.30652 0.87194 2.47234 + endloop + endfacet + facet normal 0.188653 -0.876094 0.443701 + outer loop + vertex 1.30573 0.873319 2.47579 + vertex 1.30353 0.874017 2.4781 + vertex 1.30193 0.872291 2.47537 + endloop + endfacet + facet normal 0.209619 -0.85678 0.471157 + outer loop + vertex 1.30953 0.873606 2.47462 + vertex 1.30743 0.875158 2.47837 + vertex 1.30573 0.873319 2.47579 + endloop + endfacet + facet normal 0.218102 -0.857461 0.466038 + outer loop + vertex 1.30353 0.874017 2.4781 + vertex 1.30573 0.873319 2.47579 + vertex 1.30743 0.875158 2.47837 + endloop + endfacet + facet normal 0.199487 -0.813182 0.546753 + outer loop + vertex 1.30353 0.874017 2.4781 + vertex 1.30743 0.875158 2.47837 + vertex 1.30291 0.875851 2.48105 + endloop + endfacet + facet normal 0.223907 -0.783103 0.580186 + outer loop + vertex 1.30291 0.875851 2.48105 + vertex 1.30743 0.875158 2.47837 + vertex 1.30697 0.87732 2.48147 + endloop + endfacet + facet normal 0.18582 -0.70672 0.682655 + outer loop + vertex 1.30697 0.87732 2.48147 + vertex 1.30418 0.878775 2.48373 + vertex 1.30291 0.875851 2.48105 + endloop + endfacet + facet normal 0.213275 -0.68135 0.700197 + outer loop + vertex 1.30925 0.880097 2.48348 + vertex 1.30418 0.878775 2.48373 + vertex 1.30697 0.87732 2.48147 + endloop + endfacet + facet normal 0.19117 -0.578413 0.793028 + outer loop + vertex 1.30418 0.878775 2.48373 + vertex 1.30925 0.880097 2.48348 + vertex 1.30606 0.882039 2.48566 + endloop + endfacet + facet normal 0.202513 -0.581823 0.787699 + outer loop + vertex 1.30157 0.880941 2.486 + vertex 1.30418 0.878775 2.48373 + vertex 1.30606 0.882039 2.48566 + endloop + endfacet + facet normal 0.178859 -0.459275 0.870101 + outer loop + vertex 1.30606 0.882039 2.48566 + vertex 1.3043 0.884925 2.48755 + vertex 1.30157 0.880941 2.486 + endloop + endfacet + facet normal 0.180523 -0.458348 0.870246 + outer loop + vertex 1.30877 0.88542 2.48688 + vertex 1.3043 0.884925 2.48755 + vertex 1.30606 0.882039 2.48566 + endloop + endfacet + facet normal -0.36853 0.433964 0.822108 + outer loop + vertex 1.30695 0.977398 2.51565 + vertex 1.30611 0.978526 2.51468 + vertex 1.30322 0.977188 2.51409 + endloop + endfacet + facet normal -0.368476 -0.201266 0.907589 + outer loop + vertex 1.30695 0.977398 2.51565 + vertex 1.30322 0.977188 2.51409 + vertex 1.30724 0.974339 2.51509 + endloop + endfacet + facet normal -0.0592007 0.255027 0.96512 + outer loop + vertex 1.30724 0.974339 2.51509 + vertex 1.30322 0.977188 2.51409 + vertex 1.30106 0.973434 2.51495 + endloop + endfacet + facet normal -0.411976 0.399021 0.819181 + outer loop + vertex 1.30695 0.977398 2.51565 + vertex 1.30781 0.978353 2.51562 + vertex 1.30611 0.978526 2.51468 + endloop + endfacet + facet normal -0.147189 0.924601 0.351352 + outer loop + vertex 1.31 0.982524 2.5 + vertex 1.305 0.981728 2.5 + vertex 1.30862 0.981386 2.50242 + endloop + endfacet + facet normal -0.0956459 0.955661 0.278504 + outer loop + vertex 1.30862 0.981386 2.50242 + vertex 1.305 0.981728 2.5 + vertex 1.30441 0.980801 2.50298 + endloop + endfacet + facet normal -0.122454 0.986431 0.109353 + outer loop + vertex 1.30862 0.981386 2.50242 + vertex 1.30441 0.980801 2.50298 + vertex 1.30768 0.980808 2.50658 + endloop + endfacet + facet normal -0.101675 0.990694 0.090485 + outer loop + vertex 1.30768 0.980808 2.50658 + vertex 1.30441 0.980801 2.50298 + vertex 1.30298 0.980326 2.50658 + endloop + endfacet + facet normal -0.100906 0.983016 0.15329 + outer loop + vertex 1.30768 0.980808 2.50658 + vertex 1.30298 0.980326 2.50658 + vertex 1.30668 0.98015 2.51014 + endloop + endfacet + facet normal -0.156846 0.964935 0.210474 + outer loop + vertex 1.30668 0.98015 2.51014 + vertex 1.30298 0.980326 2.50658 + vertex 1.30334 0.979357 2.51129 + endloop + endfacet + facet normal -0.442441 0.71795 0.537395 + outer loop + vertex 1.30611 0.978526 2.51468 + vertex 1.30334 0.979357 2.51129 + vertex 1.30322 0.977188 2.51409 + endloop + endfacet + facet normal -0.0741215 0.952826 0.294326 + outer loop + vertex 1.30611 0.978526 2.51468 + vertex 1.30813 0.978956 2.51379 + vertex 1.30334 0.979357 2.51129 + endloop + endfacet + facet normal -0.102617 0.932751 0.34561 + outer loop + vertex 1.30813 0.978956 2.51379 + vertex 1.30668 0.98015 2.51014 + vertex 1.30334 0.979357 2.51129 + endloop + endfacet + facet normal -0.0704461 0.950787 0.301729 + outer loop + vertex 1.30813 0.978956 2.51379 + vertex 1.30611 0.978526 2.51468 + vertex 1.30781 0.978353 2.51562 + endloop + endfacet + facet normal -0.0449899 -0.681723 -0.730226 + outer loop + vertex 1.31 2.04682 2.5 + vertex 1.3085 2.04435 2.5024 + vertex 1.305 2.04715 2.5 + endloop + endfacet + facet normal -0.0657835 -0.695283 -0.715719 + outer loop + vertex 1.3085 2.04435 2.5024 + vertex 1.30381 2.04478 2.50242 + vertex 1.305 2.04715 2.5 + endloop + endfacet + facet normal -0.0902301 -0.993845 -0.0642662 + outer loop + vertex 1.3085 2.04435 2.5024 + vertex 1.30748 2.04417 2.50664 + vertex 1.30381 2.04478 2.50242 + endloop + endfacet + facet normal -0.0141698 -0.991398 -0.130112 + outer loop + vertex 1.30748 2.04417 2.50664 + vertex 1.30277 2.04424 2.50661 + vertex 1.30381 2.04478 2.50242 + endloop + endfacet + facet normal -0.0161682 -0.976093 0.216753 + outer loop + vertex 1.30748 2.04417 2.50664 + vertex 1.30537 2.04522 2.51124 + vertex 1.30277 2.04424 2.50661 + endloop + endfacet + facet normal 0.11676 -0.982745 0.143455 + outer loop + vertex 1.30537 2.04522 2.51124 + vertex 1.30108 2.04454 2.51007 + vertex 1.30277 2.04424 2.50661 + endloop + endfacet + facet normal 0.436856 -0.757513 0.48511 + outer loop + vertex 1.30423 2.04669 2.51455 + vertex 1.30537 2.04522 2.51124 + vertex 1.30833 2.04853 2.51374 + endloop + endfacet + facet normal 0.131321 -0.88938 0.437901 + outer loop + vertex 1.30423 2.04669 2.51455 + vertex 1.3006 2.04575 2.51374 + vertex 1.30537 2.04522 2.51124 + endloop + endfacet + facet normal 0.0630368 -0.945555 0.319299 + outer loop + vertex 1.3006 2.04575 2.51374 + vertex 1.30108 2.04454 2.51007 + vertex 1.30537 2.04522 2.51124 + endloop + endfacet + facet normal 0.0679045 -0.791033 0.607994 + outer loop + vertex 1.30423 2.04669 2.51455 + vertex 1.30148 2.04739 2.51577 + vertex 1.3006 2.04575 2.51374 + endloop + endfacet + facet normal 0.187206 0.568131 0.801362 + outer loop + vertex 1.3042 2.14353 2.48568 + vertex 1.308 2.14261 2.48545 + vertex 1.3074 2.14576 2.48335 + endloop + endfacet + facet normal 0.199831 0.555829 0.806921 + outer loop + vertex 1.30214 2.14667 2.48403 + vertex 1.3042 2.14353 2.48568 + vertex 1.3074 2.14576 2.48335 + endloop + endfacet + facet normal 0.181622 0.449407 0.87467 + outer loop + vertex 1.30648 2.13975 2.48715 + vertex 1.3042 2.14353 2.48568 + vertex 1.30152 2.14091 2.48758 + endloop + endfacet + facet normal 0.160958 0.440343 0.883284 + outer loop + vertex 1.308 2.14261 2.48545 + vertex 1.3042 2.14353 2.48568 + vertex 1.30648 2.13975 2.48715 + endloop + endfacet + facet normal 0.190503 0.776705 0.600365 + outer loop + vertex 1.3041 2.14904 2.48117 + vertex 1.30964 2.14876 2.47978 + vertex 1.30607 2.15114 2.47783 + endloop + endfacet + facet normal 0.207317 0.768618 0.605183 + outer loop + vertex 1.30145 2.15154 2.47889 + vertex 1.3041 2.14904 2.48117 + vertex 1.30607 2.15114 2.47783 + endloop + endfacet + facet normal 0.207754 0.678826 0.704297 + outer loop + vertex 1.3074 2.14576 2.48335 + vertex 1.3041 2.14904 2.48117 + vertex 1.30214 2.14667 2.48403 + endloop + endfacet + facet normal 0.211158 0.680504 0.70166 + outer loop + vertex 1.30964 2.14876 2.47978 + vertex 1.3041 2.14904 2.48117 + vertex 1.3074 2.14576 2.48335 + endloop + endfacet + facet normal 0.0987005 0.766862 0.634178 + outer loop + vertex 1.30403 2.15483 2.47234 + vertex 1.30905 2.15556 2.47069 + vertex 1.30589 2.15695 2.46949 + endloop + endfacet + facet normal 0.0961697 0.767906 0.633303 + outer loop + vertex 1.30247 2.15687 2.47011 + vertex 1.30403 2.15483 2.47234 + vertex 1.30589 2.15695 2.46949 + endloop + endfacet + facet normal 0.0907436 0.781989 0.616651 + outer loop + vertex 1.30905 2.15556 2.47069 + vertex 1.30403 2.15483 2.47234 + vertex 1.30811 2.15289 2.47421 + endloop + endfacet + facet normal 0.191502 0.8582 0.476257 + outer loop + vertex 1.30811 2.15289 2.47421 + vertex 1.30403 2.15483 2.47234 + vertex 1.30374 2.15296 2.47583 + endloop + endfacet + facet normal 0.194629 0.826752 0.527826 + outer loop + vertex 1.30607 2.15114 2.47783 + vertex 1.30374 2.15296 2.47583 + vertex 1.30145 2.15154 2.47889 + endloop + endfacet + facet normal 0.206286 0.830399 0.517575 + outer loop + vertex 1.30811 2.15289 2.47421 + vertex 1.30374 2.15296 2.47583 + vertex 1.30607 2.15114 2.47783 + endloop + endfacet + facet normal -0.110976 -0.460743 0.880568 + outer loop + vertex 1.305 2.16 2.46923 + vertex 1.30668 2.15842 2.46861 + vertex 1.31 2.16 2.46986 + endloop + endfacet + facet normal 0.377319 0.654941 -0.654739 + outer loop + vertex 1.305 2.16077 2.47 + vertex 1.30668 2.15842 2.46861 + vertex 1.305 2.16 2.46923 + endloop + endfacet + facet normal 0.179979 -0.0894515 0.979595 + outer loop + vertex 1.30589 2.15695 2.46949 + vertex 1.305 2.16077 2.47 + vertex 1.30247 2.15687 2.47011 + endloop + endfacet + facet normal 0.687277 0.0634239 0.723621 + outer loop + vertex 1.30668 2.15842 2.46861 + vertex 1.305 2.16077 2.47 + vertex 1.30589 2.15695 2.46949 + endloop + endfacet + facet normal 0.119928 -0.815871 0.56566 + outer loop + vertex 1.315 0.872145 2.47 + vertex 1.31173 0.872478 2.47117 + vertex 1.31 0.87141 2.47 + endloop + endfacet + facet normal 0.196812 -0.851846 0.485411 + outer loop + vertex 1.31173 0.872478 2.47117 + vertex 1.30652 0.87194 2.47234 + vertex 1.31 0.87141 2.47 + endloop + endfacet + facet normal 0.184244 -0.893116 0.410363 + outer loop + vertex 1.31173 0.872478 2.47117 + vertex 1.30953 0.873606 2.47462 + vertex 1.30652 0.87194 2.47234 + endloop + endfacet + facet normal 0.18738 -0.891747 0.411917 + outer loop + vertex 1.31423 0.874049 2.47344 + vertex 1.30953 0.873606 2.47462 + vertex 1.31173 0.872478 2.47117 + endloop + endfacet + facet normal 0.194128 -0.873977 0.445509 + outer loop + vertex 1.30953 0.873606 2.47462 + vertex 1.31423 0.874049 2.47344 + vertex 1.31201 0.875216 2.47669 + endloop + endfacet + facet normal 0.179506 -0.869736 0.459713 + outer loop + vertex 1.30743 0.875158 2.47837 + vertex 1.30953 0.873606 2.47462 + vertex 1.31201 0.875216 2.47669 + endloop + endfacet + facet normal 0.212965 -0.805312 0.55328 + outer loop + vertex 1.31201 0.875216 2.47669 + vertex 1.31182 0.877417 2.47997 + vertex 1.30743 0.875158 2.47837 + endloop + endfacet + facet normal 0.195146 -0.790246 0.580887 + outer loop + vertex 1.31182 0.877417 2.47997 + vertex 1.30697 0.87732 2.48147 + vertex 1.30743 0.875158 2.47837 + endloop + endfacet + facet normal 0.227124 -0.686137 0.691108 + outer loop + vertex 1.31182 0.877417 2.47997 + vertex 1.30925 0.880097 2.48348 + vertex 1.30697 0.87732 2.48147 + endloop + endfacet + facet normal 0.182628 -0.711874 0.678146 + outer loop + vertex 1.31436 0.880344 2.48236 + vertex 1.30925 0.880097 2.48348 + vertex 1.31182 0.877417 2.47997 + endloop + endfacet + facet normal 0.192441 -0.577077 0.793693 + outer loop + vertex 1.30959 0.882971 2.48548 + vertex 1.30606 0.882039 2.48566 + vertex 1.30925 0.880097 2.48348 + endloop + endfacet + facet normal 0.193379 -0.577047 0.793487 + outer loop + vertex 1.30959 0.882971 2.48548 + vertex 1.30925 0.880097 2.48348 + vertex 1.31308 0.882961 2.48462 + endloop + endfacet + facet normal 0.200196 -0.583563 0.787004 + outer loop + vertex 1.31308 0.882961 2.48462 + vertex 1.30925 0.880097 2.48348 + vertex 1.31436 0.880344 2.48236 + endloop + endfacet + facet normal 0.162469 -0.447237 0.879535 + outer loop + vertex 1.30959 0.882971 2.48548 + vertex 1.30877 0.88542 2.48688 + vertex 1.30606 0.882039 2.48566 + endloop + endfacet + facet normal -0.046763 0.946635 0.318896 + outer loop + vertex 1.315 0.982771 2.5 + vertex 1.31 0.982524 2.5 + vertex 1.31353 0.981894 2.50239 + endloop + endfacet + facet normal -0.0929534 0.9202 0.380252 + outer loop + vertex 1.31353 0.981894 2.50239 + vertex 1.31 0.982524 2.5 + vertex 1.30862 0.981386 2.50242 + endloop + endfacet + facet normal -0.100039 0.978258 0.181669 + outer loop + vertex 1.31353 0.981894 2.50239 + vertex 1.30862 0.981386 2.50242 + vertex 1.31283 0.981056 2.50651 + endloop + endfacet + facet normal -0.0461002 0.990802 0.127222 + outer loop + vertex 1.31283 0.981056 2.50651 + vertex 1.30862 0.981386 2.50242 + vertex 1.30768 0.980808 2.50658 + endloop + endfacet + facet normal -0.042108 0.953298 0.299082 + outer loop + vertex 1.31283 0.981056 2.50651 + vertex 1.30768 0.980808 2.50658 + vertex 1.31157 0.979587 2.51102 + endloop + endfacet + facet normal 0.0761176 0.97647 0.201774 + outer loop + vertex 1.31157 0.979587 2.51102 + vertex 1.30768 0.980808 2.50658 + vertex 1.30668 0.98015 2.51014 + endloop + endfacet + facet normal 0.392588 0.7457 0.538336 + outer loop + vertex 1.31107 0.977041 2.5143 + vertex 1.30813 0.978956 2.51379 + vertex 1.30862 0.977446 2.51552 + endloop + endfacet + facet normal 0.357666 0.71007 0.606527 + outer loop + vertex 1.31107 0.977041 2.5143 + vertex 1.31157 0.979587 2.51102 + vertex 1.30813 0.978956 2.51379 + endloop + endfacet + facet normal 0.0579012 0.955423 0.289509 + outer loop + vertex 1.31157 0.979587 2.51102 + vertex 1.30668 0.98015 2.51014 + vertex 1.30813 0.978956 2.51379 + endloop + endfacet + facet normal 0.722088 0.610298 0.325768 + outer loop + vertex 1.30862 0.977446 2.51552 + vertex 1.30813 0.978956 2.51379 + vertex 1.30781 0.978353 2.51562 + endloop + endfacet + facet normal -0.0670775 -0.645002 -0.761231 + outer loop + vertex 1.315 2.0463 2.5 + vertex 1.3134 2.0438 2.50226 + vertex 1.31 2.04682 2.5 + endloop + endfacet + facet normal -0.0954755 -0.662975 -0.742529 + outer loop + vertex 1.3134 2.0438 2.50226 + vertex 1.3085 2.04435 2.5024 + vertex 1.31 2.04682 2.5 + endloop + endfacet + facet normal -0.112091 -0.993689 0.00430801 + outer loop + vertex 1.3134 2.0438 2.50226 + vertex 1.3125 2.04392 2.50639 + vertex 1.3085 2.04435 2.5024 + endloop + endfacet + facet normal -0.0528401 -0.997063 -0.0554425 + outer loop + vertex 1.3125 2.04392 2.50639 + vertex 1.30748 2.04417 2.50664 + vertex 1.3085 2.04435 2.5024 + endloop + endfacet + facet normal -0.0293116 -0.935327 0.352567 + outer loop + vertex 1.3125 2.04392 2.50639 + vertex 1.31104 2.0455 2.51047 + vertex 1.30748 2.04417 2.50664 + endloop + endfacet + facet normal 0.0821164 -0.96247 0.258665 + outer loop + vertex 1.31104 2.0455 2.51047 + vertex 1.30537 2.04522 2.51124 + vertex 1.30748 2.04417 2.50664 + endloop + endfacet + facet normal 0.131411 -0.669991 0.730645 + outer loop + vertex 1.31104 2.0455 2.51047 + vertex 1.30833 2.04853 2.51374 + vertex 1.30537 2.04522 2.51124 + endloop + endfacet + facet normal 0.0872872 -0.693127 0.71551 + outer loop + vertex 1.31437 2.04798 2.51246 + vertex 1.30833 2.04853 2.51374 + vertex 1.31104 2.0455 2.51047 + endloop + endfacet + facet normal 0.198283 0.467547 0.861443 + outer loop + vertex 1.31425 2.13923 2.48586 + vertex 1.31164 2.14278 2.48454 + vertex 1.31032 2.14031 2.48618 + endloop + endfacet + facet normal 0.176529 0.373757 0.910573 + outer loop + vertex 1.31032 2.14031 2.48618 + vertex 1.311 2.13653 2.4876 + vertex 1.31425 2.13923 2.48586 + endloop + endfacet + facet normal 0.175855 0.373694 0.910729 + outer loop + vertex 1.31032 2.14031 2.48618 + vertex 1.30648 2.13975 2.48715 + vertex 1.311 2.13653 2.4876 + endloop + endfacet + facet normal 0.193824 0.469787 0.861239 + outer loop + vertex 1.308 2.14261 2.48545 + vertex 1.31032 2.14031 2.48618 + vertex 1.31164 2.14278 2.48454 + endloop + endfacet + facet normal 0.174907 0.567816 0.804359 + outer loop + vertex 1.308 2.14261 2.48545 + vertex 1.31164 2.14278 2.48454 + vertex 1.3074 2.14576 2.48335 + endloop + endfacet + facet normal 0.189769 0.583117 0.789913 + outer loop + vertex 1.3074 2.14576 2.48335 + vertex 1.31164 2.14278 2.48454 + vertex 1.31274 2.14562 2.48218 + endloop + endfacet + facet normal 0.158938 0.441341 0.883151 + outer loop + vertex 1.31032 2.14031 2.48618 + vertex 1.308 2.14261 2.48545 + vertex 1.30648 2.13975 2.48715 + endloop + endfacet + facet normal 0.203713 0.835717 0.509979 + outer loop + vertex 1.31338 2.15 2.47689 + vertex 1.31185 2.15172 2.47468 + vertex 1.30975 2.15096 2.47676 + endloop + endfacet + facet normal 0.206737 0.786244 0.582305 + outer loop + vertex 1.30975 2.15096 2.47676 + vertex 1.30607 2.15114 2.47783 + vertex 1.30964 2.14876 2.47978 + endloop + endfacet + facet normal 0.188699 0.789517 0.584 + outer loop + vertex 1.30975 2.15096 2.47676 + vertex 1.30964 2.14876 2.47978 + vertex 1.31338 2.15 2.47689 + endloop + endfacet + facet normal 0.182779 0.794859 0.578612 + outer loop + vertex 1.31338 2.15 2.47689 + vertex 1.30964 2.14876 2.47978 + vertex 1.31478 2.14775 2.47953 + endloop + endfacet + facet normal 0.171755 0.699896 0.693286 + outer loop + vertex 1.31274 2.14562 2.48218 + vertex 1.30964 2.14876 2.47978 + vertex 1.3074 2.14576 2.48335 + endloop + endfacet + facet normal 0.169698 0.698965 0.694731 + outer loop + vertex 1.31478 2.14775 2.47953 + vertex 1.30964 2.14876 2.47978 + vertex 1.31274 2.14562 2.48218 + endloop + endfacet + facet normal -0.266336 0.206933 0.941405 + outer loop + vertex 1.31007 2.16 2.47 + vertex 1.30589 2.15695 2.46949 + vertex 1.30905 2.15556 2.47069 + endloop + endfacet + facet normal 0.0388276 0.14391 0.988829 + outer loop + vertex 1.31007 2.16 2.47 + vertex 1.30905 2.15556 2.47069 + vertex 1.315 2.15867 2.47 + endloop + endfacet + facet normal -0.0896797 0.375 0.922677 + outer loop + vertex 1.315 2.15867 2.47 + vertex 1.30905 2.15556 2.47069 + vertex 1.31264 2.15363 2.47182 + endloop + endfacet + facet normal 0.198452 0.839384 0.506016 + outer loop + vertex 1.31185 2.15172 2.47468 + vertex 1.30811 2.15289 2.47421 + vertex 1.30975 2.15096 2.47676 + endloop + endfacet + facet normal 0.175527 0.795651 0.579767 + outer loop + vertex 1.31185 2.15172 2.47468 + vertex 1.31264 2.15363 2.47182 + vertex 1.30811 2.15289 2.47421 + endloop + endfacet + facet normal 0.206482 0.752683 0.625166 + outer loop + vertex 1.31264 2.15363 2.47182 + vertex 1.30905 2.15556 2.47069 + vertex 1.30811 2.15289 2.47421 + endloop + endfacet + facet normal 0.188701 0.838313 0.51149 + outer loop + vertex 1.30975 2.15096 2.47676 + vertex 1.30811 2.15289 2.47421 + vertex 1.30607 2.15114 2.47783 + endloop + endfacet + facet normal -0.490654 0.835984 0.245745 + outer loop + vertex 1.31 2.16 2.46986 + vertex 1.30668 2.15842 2.46861 + vertex 1.31007 2.16 2.47 + endloop + endfacet + facet normal -0.527146 0.626313 0.574325 + outer loop + vertex 1.31007 2.16 2.47 + vertex 1.30668 2.15842 2.46861 + vertex 1.30589 2.15695 2.46949 + endloop + endfacet + facet normal -0.0742237 0.419818 0.904568 + outer loop + vertex 1.32 0.873029 2.47 + vertex 1.31713 0.872982 2.46979 + vertex 1.315 0.872145 2.47 + endloop + endfacet + facet normal 0.261168 -0.447613 0.855239 + outer loop + vertex 1.31713 0.872982 2.46979 + vertex 1.31173 0.872478 2.47117 + vertex 1.315 0.872145 2.47 + endloop + endfacet + facet normal 0.188565 -0.892015 0.410794 + outer loop + vertex 1.31713 0.872982 2.46979 + vertex 1.31423 0.874049 2.47344 + vertex 1.31173 0.872478 2.47117 + endloop + endfacet + facet normal 0.184276 -0.894186 0.408013 + outer loop + vertex 1.31843 0.874379 2.47226 + vertex 1.31423 0.874049 2.47344 + vertex 1.31713 0.872982 2.46979 + endloop + endfacet + facet normal 0.194708 -0.8705 0.452017 + outer loop + vertex 1.31423 0.874049 2.47344 + vertex 1.31843 0.874379 2.47226 + vertex 1.31717 0.876243 2.47639 + endloop + endfacet + facet normal 0.199319 -0.871461 0.448137 + outer loop + vertex 1.31201 0.875216 2.47669 + vertex 1.31423 0.874049 2.47344 + vertex 1.31717 0.876243 2.47639 + endloop + endfacet + facet normal 0.182088 -0.816896 0.547289 + outer loop + vertex 1.31616 0.87844 2.48001 + vertex 1.31717 0.876243 2.47639 + vertex 1.31979 0.878666 2.47914 + endloop + endfacet + facet normal 0.187112 -0.815418 0.547798 + outer loop + vertex 1.31616 0.87844 2.48001 + vertex 1.31182 0.877417 2.47997 + vertex 1.31717 0.876243 2.47639 + endloop + endfacet + facet normal 0.193122 -0.809275 0.554777 + outer loop + vertex 1.31182 0.877417 2.47997 + vertex 1.31201 0.875216 2.47669 + vertex 1.31717 0.876243 2.47639 + endloop + endfacet + facet normal 0.159316 -0.703454 0.692655 + outer loop + vertex 1.31616 0.87844 2.48001 + vertex 1.31436 0.880344 2.48236 + vertex 1.31182 0.877417 2.47997 + endloop + endfacet + facet normal 0.205314 -0.712419 0.671048 + outer loop + vertex 1.31979 0.878666 2.47914 + vertex 1.31804 0.880337 2.48145 + vertex 1.31616 0.87844 2.48001 + endloop + endfacet + facet normal 0.170692 -0.697187 0.696271 + outer loop + vertex 1.31804 0.880337 2.48145 + vertex 1.31436 0.880344 2.48236 + vertex 1.31616 0.87844 2.48001 + endloop + endfacet + facet normal 0.195356 -0.574111 0.795131 + outer loop + vertex 1.31804 0.880337 2.48145 + vertex 1.31864 0.883754 2.48377 + vertex 1.31436 0.880344 2.48236 + endloop + endfacet + facet normal 0.204135 -0.581851 0.78726 + outer loop + vertex 1.31864 0.883754 2.48377 + vertex 1.31308 0.882961 2.48462 + vertex 1.31436 0.880344 2.48236 + endloop + endfacet + facet normal -0.119052 0.947873 0.295574 + outer loop + vertex 1.32 0.983399 2.5 + vertex 1.315 0.982771 2.5 + vertex 1.31849 0.982436 2.50248 + endloop + endfacet + facet normal -0.109448 0.952933 0.282737 + outer loop + vertex 1.31849 0.982436 2.50248 + vertex 1.315 0.982771 2.5 + vertex 1.31353 0.981894 2.50239 + endloop + endfacet + facet normal -0.109935 0.964434 0.240379 + outer loop + vertex 1.31849 0.982436 2.50248 + vertex 1.31353 0.981894 2.50239 + vertex 1.31811 0.981419 2.50638 + endloop + endfacet + facet normal -0.0628568 0.980088 0.188352 + outer loop + vertex 1.31811 0.981419 2.50638 + vertex 1.31353 0.981894 2.50239 + vertex 1.31283 0.981056 2.50651 + endloop + endfacet + facet normal -0.0531169 0.914739 0.400539 + outer loop + vertex 1.31811 0.981419 2.50638 + vertex 1.31283 0.981056 2.50651 + vertex 1.31735 0.979709 2.51019 + endloop + endfacet + facet normal 0.0253729 0.948306 0.316341 + outer loop + vertex 1.31735 0.979709 2.51019 + vertex 1.31283 0.981056 2.50651 + vertex 1.31157 0.979587 2.51102 + endloop + endfacet + facet normal 0.189185 0.761226 0.620278 + outer loop + vertex 1.31573 0.976982 2.51295 + vertex 1.31157 0.979587 2.51102 + vertex 1.31107 0.977041 2.5143 + endloop + endfacet + facet normal 0.0897931 0.681276 0.726499 + outer loop + vertex 1.31735 0.979709 2.51019 + vertex 1.31157 0.979587 2.51102 + vertex 1.31573 0.976982 2.51295 + endloop + endfacet + facet normal -0.0891901 -0.564579 -0.820546 + outer loop + vertex 1.32 2.04551 2.5 + vertex 1.31858 2.04317 2.50176 + vertex 1.315 2.0463 2.5 + endloop + endfacet + facet normal -0.148534 -0.609129 -0.779038 + outer loop + vertex 1.31858 2.04317 2.50176 + vertex 1.3134 2.0438 2.50226 + vertex 1.315 2.0463 2.5 + endloop + endfacet + facet normal -0.121302 -0.992529 -0.0130967 + outer loop + vertex 1.31858 2.04317 2.50176 + vertex 1.31735 2.04326 2.50599 + vertex 1.3134 2.0438 2.50226 + endloop + endfacet + facet normal -0.133109 -0.991101 -0.000387132 + outer loop + vertex 1.31735 2.04326 2.50599 + vertex 1.3125 2.04392 2.50639 + vertex 1.3134 2.0438 2.50226 + endloop + endfacet + facet normal -0.0889991 -0.909055 0.40706 + outer loop + vertex 1.31735 2.04326 2.50599 + vertex 1.31626 2.04511 2.50988 + vertex 1.3125 2.04392 2.50639 + endloop + endfacet + facet normal -0.029984 -0.935388 0.352351 + outer loop + vertex 1.31626 2.04511 2.50988 + vertex 1.31104 2.0455 2.51047 + vertex 1.3125 2.04392 2.50639 + endloop + endfacet + facet normal 0.0368824 -0.656124 0.753751 + outer loop + vertex 1.31626 2.04511 2.50988 + vertex 1.31437 2.04798 2.51246 + vertex 1.31104 2.0455 2.51047 + endloop + endfacet + facet normal 0.0149954 -0.664576 0.74707 + outer loop + vertex 1.31928 2.04744 2.51188 + vertex 1.31437 2.04798 2.51246 + vertex 1.31626 2.04511 2.50988 + endloop + endfacet + facet normal 0.188171 0.46427 0.865474 + outer loop + vertex 1.31425 2.13923 2.48586 + vertex 1.31836 2.13809 2.48558 + vertex 1.31721 2.14215 2.48365 + endloop + endfacet + facet normal 0.18979 0.462911 0.865849 + outer loop + vertex 1.31164 2.14278 2.48454 + vertex 1.31425 2.13923 2.48586 + vertex 1.31721 2.14215 2.48365 + endloop + endfacet + facet normal 0.17457 0.375812 0.910105 + outer loop + vertex 1.31661 2.13497 2.48717 + vertex 1.31425 2.13923 2.48586 + vertex 1.311 2.13653 2.4876 + endloop + endfacet + facet normal 0.165662 0.371885 0.913377 + outer loop + vertex 1.31836 2.13809 2.48558 + vertex 1.31425 2.13923 2.48586 + vertex 1.31661 2.13497 2.48717 + endloop + endfacet + facet normal 0.203963 0.684842 0.699565 + outer loop + vertex 1.31988 2.14463 2.48131 + vertex 1.31826 2.14681 2.47965 + vertex 1.31645 2.14553 2.48144 + endloop + endfacet + facet normal 0.176936 0.56744 0.80418 + outer loop + vertex 1.31645 2.14553 2.48144 + vertex 1.31721 2.14215 2.48365 + vertex 1.31988 2.14463 2.48131 + endloop + endfacet + facet normal 0.174558 0.567304 0.804795 + outer loop + vertex 1.31645 2.14553 2.48144 + vertex 1.31274 2.14562 2.48218 + vertex 1.31721 2.14215 2.48365 + endloop + endfacet + facet normal 0.191315 0.58255 0.789958 + outer loop + vertex 1.31274 2.14562 2.48218 + vertex 1.31164 2.14278 2.48454 + vertex 1.31721 2.14215 2.48365 + endloop + endfacet + facet normal 0.196527 0.839001 0.5074 + outer loop + vertex 1.31338 2.15 2.47689 + vertex 1.31894 2.14904 2.47632 + vertex 1.31564 2.15143 2.47365 + endloop + endfacet + facet normal 0.202989 0.835629 0.510411 + outer loop + vertex 1.31185 2.15172 2.47468 + vertex 1.31338 2.15 2.47689 + vertex 1.31564 2.15143 2.47365 + endloop + endfacet + facet normal 0.168667 0.711029 0.682634 + outer loop + vertex 1.31826 2.14681 2.47965 + vertex 1.31478 2.14775 2.47953 + vertex 1.31645 2.14553 2.48144 + endloop + endfacet + facet normal 0.195565 0.79627 0.572457 + outer loop + vertex 1.31826 2.14681 2.47965 + vertex 1.31894 2.14904 2.47632 + vertex 1.31478 2.14775 2.47953 + endloop + endfacet + facet normal 0.195807 0.796049 0.572682 + outer loop + vertex 1.31894 2.14904 2.47632 + vertex 1.31338 2.15 2.47689 + vertex 1.31478 2.14775 2.47953 + endloop + endfacet + facet normal 0.15498 0.707071 0.68995 + outer loop + vertex 1.31645 2.14553 2.48144 + vertex 1.31478 2.14775 2.47953 + vertex 1.31274 2.14562 2.48218 + endloop + endfacet + facet normal 0.00263777 0.00942063 0.999952 + outer loop + vertex 1.32 2.15727 2.47 + vertex 1.315 2.15867 2.47 + vertex 1.31779 2.15366 2.47004 + endloop + endfacet + facet normal 0.320389 0.185678 0.92891 + outer loop + vertex 1.31779 2.15366 2.47004 + vertex 1.315 2.15867 2.47 + vertex 1.31264 2.15363 2.47182 + endloop + endfacet + facet normal 0.218696 0.782488 0.582996 + outer loop + vertex 1.31564 2.15143 2.47365 + vertex 1.31264 2.15363 2.47182 + vertex 1.31185 2.15172 2.47468 + endloop + endfacet + facet normal 0.202188 0.774087 0.599925 + outer loop + vertex 1.31779 2.15366 2.47004 + vertex 1.31264 2.15363 2.47182 + vertex 1.31564 2.15143 2.47365 + endloop + endfacet + facet normal 0.139457 -0.963074 0.230306 + outer loop + vertex 1.325 0.87282 2.465 + vertex 1.3226 0.872821 2.46646 + vertex 1.32 0.872096 2.465 + endloop + endfacet + facet normal 0.168962 -0.9689 0.180791 + outer loop + vertex 1.3226 0.872821 2.46646 + vertex 1.32 0.873029 2.47 + vertex 1.32 0.872096 2.465 + endloop + endfacet + facet normal 0.194765 -0.90698 0.373436 + outer loop + vertex 1.32093 0.873736 2.46955 + vertex 1.3226 0.872821 2.46646 + vertex 1.32412 0.87388 2.46824 + endloop + endfacet + facet normal 0.202851 -0.903789 0.376853 + outer loop + vertex 1.32093 0.873736 2.46955 + vertex 1.31713 0.872982 2.46979 + vertex 1.3226 0.872821 2.46646 + endloop + endfacet + facet normal -0.0114054 0.997693 -0.0669271 + outer loop + vertex 1.31713 0.872982 2.46979 + vertex 1.32 0.873029 2.47 + vertex 1.3226 0.872821 2.46646 + endloop + endfacet + facet normal 0.202348 -0.894476 0.398707 + outer loop + vertex 1.32093 0.873736 2.46955 + vertex 1.31843 0.874379 2.47226 + vertex 1.31713 0.872982 2.46979 + endloop + endfacet + facet normal 0.202154 -0.897287 0.392441 + outer loop + vertex 1.32412 0.87388 2.46824 + vertex 1.32302 0.875409 2.4723 + vertex 1.32093 0.873736 2.46955 + endloop + endfacet + facet normal 0.198058 -0.896929 0.395336 + outer loop + vertex 1.31843 0.874379 2.47226 + vertex 1.32093 0.873736 2.46955 + vertex 1.32302 0.875409 2.4723 + endloop + endfacet + facet normal 0.191862 -0.871377 0.451544 + outer loop + vertex 1.31843 0.874379 2.47226 + vertex 1.32302 0.875409 2.4723 + vertex 1.31717 0.876243 2.47639 + endloop + endfacet + facet normal 0.193391 -0.870044 0.453456 + outer loop + vertex 1.31717 0.876243 2.47639 + vertex 1.32302 0.875409 2.4723 + vertex 1.32205 0.877325 2.47639 + endloop + endfacet + facet normal 0.181691 -0.816792 0.547576 + outer loop + vertex 1.32205 0.877325 2.47639 + vertex 1.31979 0.878666 2.47914 + vertex 1.31717 0.876243 2.47639 + endloop + endfacet + facet normal 0.212496 -0.7981 0.56381 + outer loop + vertex 1.32386 0.879346 2.47857 + vertex 1.31979 0.878666 2.47914 + vertex 1.32205 0.877325 2.47639 + endloop + endfacet + facet normal 0.212606 -0.698835 0.682955 + outer loop + vertex 1.31979 0.878666 2.47914 + vertex 1.32386 0.879346 2.47857 + vertex 1.32172 0.881311 2.48125 + endloop + endfacet + facet normal 0.223166 -0.701586 0.676738 + outer loop + vertex 1.31804 0.880337 2.48145 + vertex 1.31979 0.878666 2.47914 + vertex 1.32172 0.881311 2.48125 + endloop + endfacet + facet normal 0.196012 -0.574114 0.794967 + outer loop + vertex 1.32172 0.881311 2.48125 + vertex 1.31864 0.883754 2.48377 + vertex 1.31804 0.880337 2.48145 + endloop + endfacet + facet normal 0.192781 -0.576914 0.793729 + outer loop + vertex 1.3244 0.884677 2.48304 + vertex 1.31864 0.883754 2.48377 + vertex 1.32172 0.881311 2.48125 + endloop + endfacet + facet normal 0.0486512 -0.147984 0.987792 + outer loop + vertex 1.32317 0.983752 2.4999 + vertex 1.32487 0.985 2.5 + vertex 1.32 0.983399 2.5 + endloop + endfacet + facet normal -0.101061 0.970805 0.21754 + outer loop + vertex 1.32317 0.983752 2.4999 + vertex 1.32 0.983399 2.5 + vertex 1.32322 0.983162 2.50256 + endloop + endfacet + facet normal -0.149957 0.949036 0.277208 + outer loop + vertex 1.32322 0.983162 2.50256 + vertex 1.32 0.983399 2.5 + vertex 1.31849 0.982436 2.50248 + endloop + endfacet + facet normal -0.149601 0.945419 0.289486 + outer loop + vertex 1.32322 0.983162 2.50256 + vertex 1.31849 0.982436 2.50248 + vertex 1.32311 0.981956 2.50643 + endloop + endfacet + facet normal -0.105945 0.964761 0.240857 + outer loop + vertex 1.32311 0.981956 2.50643 + vertex 1.31849 0.982436 2.50248 + vertex 1.31811 0.981419 2.50638 + endloop + endfacet + facet normal -0.098538 0.874735 0.474477 + outer loop + vertex 1.32311 0.981956 2.50643 + vertex 1.31811 0.981419 2.50638 + vertex 1.32268 0.980056 2.50985 + endloop + endfacet + facet normal -0.0335496 0.914092 0.404116 + outer loop + vertex 1.32268 0.980056 2.50985 + vertex 1.31811 0.981419 2.50638 + vertex 1.31735 0.979709 2.51019 + endloop + endfacet + facet normal 0.0897972 0.681274 0.7265 + outer loop + vertex 1.32109 0.977132 2.51214 + vertex 1.31735 0.979709 2.51019 + vertex 1.31573 0.976982 2.51295 + endloop + endfacet + facet normal 0.0107691 0.614099 0.789156 + outer loop + vertex 1.32268 0.980056 2.50985 + vertex 1.31735 0.979709 2.51019 + vertex 1.32109 0.977132 2.51214 + endloop + endfacet + facet normal 0.419136 0.0337347 0.907297 + outer loop + vertex 1.325 0.985 2.49994 + vertex 1.32487 0.985 2.5 + vertex 1.32563 0.984205 2.49968 + endloop + endfacet + facet normal 0.132403 -0.25948 0.956629 + outer loop + vertex 1.32563 0.984205 2.49968 + vertex 1.32487 0.985 2.5 + vertex 1.32317 0.983752 2.4999 + endloop + endfacet + facet normal -0.146676 0.123075 -0.981498 + outer loop + vertex 1.32663 2.04227 2.49912 + vertex 1.32306 2.045 2.5 + vertex 1.325 2.045 2.49971 + endloop + endfacet + facet normal -0.600501 -0.625041 -0.49872 + outer loop + vertex 1.32519 2.04131 2.50206 + vertex 1.32306 2.045 2.5 + vertex 1.32663 2.04227 2.49912 + endloop + endfacet + facet normal -0.231255 -0.572615 -0.786533 + outer loop + vertex 1.32225 2.04193 2.50248 + vertex 1.32306 2.045 2.5 + vertex 1.32519 2.04131 2.50206 + endloop + endfacet + facet normal -0.221624 -0.966581 -0.128858 + outer loop + vertex 1.32519 2.04131 2.50206 + vertex 1.32416 2.04117 2.50488 + vertex 1.32225 2.04193 2.50248 + endloop + endfacet + facet normal -0.0570477 -0.617017 -0.784879 + outer loop + vertex 1.32306 2.045 2.5 + vertex 1.32225 2.04193 2.50248 + vertex 1.31858 2.04317 2.50176 + endloop + endfacet + facet normal -0.0937478 -0.562509 -0.821459 + outer loop + vertex 1.32 2.04551 2.5 + vertex 1.32306 2.045 2.5 + vertex 1.31858 2.04317 2.50176 + endloop + endfacet + facet normal -0.343602 -0.938826 -0.0233072 + outer loop + vertex 1.32225 2.04193 2.50248 + vertex 1.32416 2.04117 2.50488 + vertex 1.32141 2.04216 2.50551 + endloop + endfacet + facet normal -0.318454 -0.94781 -0.0155985 + outer loop + vertex 1.32225 2.04193 2.50248 + vertex 1.32141 2.04216 2.50551 + vertex 1.31858 2.04317 2.50176 + endloop + endfacet + facet normal -0.268819 -0.961522 -0.0566674 + outer loop + vertex 1.31858 2.04317 2.50176 + vertex 1.32141 2.04216 2.50551 + vertex 1.31735 2.04326 2.50599 + endloop + endfacet + facet normal -0.192801 -0.888419 0.41658 + outer loop + vertex 1.32141 2.04216 2.50551 + vertex 1.32141 2.04402 2.50949 + vertex 1.31735 2.04326 2.50599 + endloop + endfacet + facet normal -0.162654 -0.908086 0.385906 + outer loop + vertex 1.32141 2.04402 2.50949 + vertex 1.31626 2.04511 2.50988 + vertex 1.31735 2.04326 2.50599 + endloop + endfacet + facet normal -0.0667212 -0.601145 0.79635 + outer loop + vertex 1.32141 2.04402 2.50949 + vertex 1.31928 2.04744 2.51188 + vertex 1.31626 2.04511 2.50988 + endloop + endfacet + facet normal -0.100347 -0.613125 0.783586 + outer loop + vertex 1.32443 2.04649 2.51181 + vertex 1.31928 2.04744 2.51188 + vertex 1.32141 2.04402 2.50949 + endloop + endfacet + facet normal 0.191329 0.39575 0.898207 + outer loop + vertex 1.31836 2.13809 2.48558 + vertex 1.32077 2.13542 2.48624 + vertex 1.32256 2.13842 2.48454 + endloop + endfacet + facet normal 0.178693 0.462892 0.868217 + outer loop + vertex 1.31836 2.13809 2.48558 + vertex 1.32256 2.13842 2.48454 + vertex 1.31721 2.14215 2.48365 + endloop + endfacet + facet normal 0.187938 0.474232 0.860107 + outer loop + vertex 1.31721 2.14215 2.48365 + vertex 1.32256 2.13842 2.48454 + vertex 1.32207 2.14204 2.48265 + endloop + endfacet + facet normal 0.162578 0.373547 0.913253 + outer loop + vertex 1.32077 2.13542 2.48624 + vertex 1.31836 2.13809 2.48558 + vertex 1.31661 2.13497 2.48717 + endloop + endfacet + facet normal 0.212596 0.689012 0.692867 + outer loop + vertex 1.31988 2.14463 2.48131 + vertex 1.32411 2.14407 2.48057 + vertex 1.32179 2.14657 2.4788 + endloop + endfacet + facet normal 0.214425 0.687905 0.693403 + outer loop + vertex 1.31826 2.14681 2.47965 + vertex 1.31988 2.14463 2.48131 + vertex 1.32179 2.14657 2.4788 + endloop + endfacet + facet normal 0.178454 0.56627 0.804669 + outer loop + vertex 1.32207 2.14204 2.48265 + vertex 1.31988 2.14463 2.48131 + vertex 1.31721 2.14215 2.48365 + endloop + endfacet + facet normal 0.214511 0.585114 0.782065 + outer loop + vertex 1.32411 2.14407 2.48057 + vertex 1.31988 2.14463 2.48131 + vertex 1.32207 2.14204 2.48265 + endloop + endfacet + facet normal 0.195428 0.865376 0.461446 + outer loop + vertex 1.32421 2.15004 2.47257 + vertex 1.32201 2.152 2.46983 + vertex 1.31969 2.15114 2.47242 + endloop + endfacet + facet normal 0.209532 0.84319 0.495102 + outer loop + vertex 1.31969 2.15114 2.47242 + vertex 1.31564 2.15143 2.47365 + vertex 1.31894 2.14904 2.47632 + endloop + endfacet + facet normal 0.190228 0.848319 0.494133 + outer loop + vertex 1.31969 2.15114 2.47242 + vertex 1.31894 2.14904 2.47632 + vertex 1.32421 2.15004 2.47257 + endloop + endfacet + facet normal 0.186177 0.851942 0.489422 + outer loop + vertex 1.32421 2.15004 2.47257 + vertex 1.31894 2.14904 2.47632 + vertex 1.32391 2.14808 2.47611 + endloop + endfacet + facet normal 0.192834 0.796992 0.57238 + outer loop + vertex 1.32179 2.14657 2.4788 + vertex 1.31894 2.14904 2.47632 + vertex 1.31826 2.14681 2.47965 + endloop + endfacet + facet normal 0.178738 0.792048 0.583707 + outer loop + vertex 1.32391 2.14808 2.47611 + vertex 1.31894 2.14904 2.47632 + vertex 1.32179 2.14657 2.4788 + endloop + endfacet + facet normal 0.0821395 0.391142 0.916658 + outer loop + vertex 1.325 2.15828 2.465 + vertex 1.32 2.15933 2.465 + vertex 1.32242 2.15447 2.46686 + endloop + endfacet + facet normal 0.842161 0.498573 0.205401 + outer loop + vertex 1.32242 2.15447 2.46686 + vertex 1.32 2.15933 2.465 + vertex 1.32 2.15727 2.47 + endloop + endfacet + facet normal 0.329848 0.76781 0.549244 + outer loop + vertex 1.32201 2.152 2.46983 + vertex 1.31779 2.15366 2.47004 + vertex 1.31969 2.15114 2.47242 + endloop + endfacet + facet normal 0.310989 0.709126 0.632792 + outer loop + vertex 1.32201 2.152 2.46983 + vertex 1.32242 2.15447 2.46686 + vertex 1.31779 2.15366 2.47004 + endloop + endfacet + facet normal 0.571441 -0.342599 0.745709 + outer loop + vertex 1.32242 2.15447 2.46686 + vertex 1.32 2.15727 2.47 + vertex 1.31779 2.15366 2.47004 + endloop + endfacet + facet normal 0.238065 0.755816 0.609974 + outer loop + vertex 1.31969 2.15114 2.47242 + vertex 1.31779 2.15366 2.47004 + vertex 1.31564 2.15143 2.47365 + endloop + endfacet + facet normal 0.241071 -0.226248 0.943767 + outer loop + vertex 1.32673 0.873445 2.46595 + vertex 1.33 0.872969 2.465 + vertex 1.33077 0.873928 2.46503 + endloop + endfacet + facet normal 0.178873 -0.482106 0.857659 + outer loop + vertex 1.32673 0.873445 2.46595 + vertex 1.3226 0.872821 2.46646 + vertex 1.33 0.872969 2.465 + endloop + endfacet + facet normal 0.0297403 -0.998317 0.0497939 + outer loop + vertex 1.3226 0.872821 2.46646 + vertex 1.325 0.87282 2.465 + vertex 1.33 0.872969 2.465 + endloop + endfacet + facet normal 0.183987 -0.905694 0.381924 + outer loop + vertex 1.32673 0.873445 2.46595 + vertex 1.32412 0.87388 2.46824 + vertex 1.3226 0.872821 2.46646 + endloop + endfacet + facet normal 0.196251 -0.898834 0.391896 + outer loop + vertex 1.33077 0.873928 2.46503 + vertex 1.32795 0.874862 2.46859 + vertex 1.32673 0.873445 2.46595 + endloop + endfacet + facet normal 0.194575 -0.898855 0.392683 + outer loop + vertex 1.32412 0.87388 2.46824 + vertex 1.32673 0.873445 2.46595 + vertex 1.32795 0.874862 2.46859 + endloop + endfacet + facet normal 0.19485 -0.899417 0.391257 + outer loop + vertex 1.32412 0.87388 2.46824 + vertex 1.32795 0.874862 2.46859 + vertex 1.32302 0.875409 2.4723 + endloop + endfacet + facet normal 0.19519 -0.899163 0.391672 + outer loop + vertex 1.32302 0.875409 2.4723 + vertex 1.32795 0.874862 2.46859 + vertex 1.32708 0.876117 2.4719 + endloop + endfacet + facet normal 0.196105 -0.86193 0.467567 + outer loop + vertex 1.32708 0.876117 2.4719 + vertex 1.32645 0.877718 2.47512 + vertex 1.32302 0.875409 2.4723 + endloop + endfacet + facet normal 0.208856 -0.865636 0.455031 + outer loop + vertex 1.32645 0.877718 2.47512 + vertex 1.32205 0.877325 2.47639 + vertex 1.32302 0.875409 2.4723 + endloop + endfacet + facet normal 0.231064 -0.801495 0.551558 + outer loop + vertex 1.32645 0.877718 2.47512 + vertex 1.32386 0.879346 2.47857 + vertex 1.32205 0.877325 2.47639 + endloop + endfacet + facet normal 0.222621 -0.806574 0.547612 + outer loop + vertex 1.32738 0.880064 2.47819 + vertex 1.32386 0.879346 2.47857 + vertex 1.32645 0.877718 2.47512 + endloop + endfacet + facet normal 0.215522 -0.7053 0.675354 + outer loop + vertex 1.32386 0.879346 2.47857 + vertex 1.32738 0.880064 2.47819 + vertex 1.32599 0.881992 2.48065 + endloop + endfacet + facet normal 0.206659 -0.702574 0.680941 + outer loop + vertex 1.32172 0.881311 2.48125 + vertex 1.32386 0.879346 2.47857 + vertex 1.32599 0.881992 2.48065 + endloop + endfacet + facet normal 0.202213 -0.581415 0.788078 + outer loop + vertex 1.32599 0.881992 2.48065 + vertex 1.3244 0.884677 2.48304 + vertex 1.32172 0.881311 2.48125 + endloop + endfacet + facet normal 0.194518 -0.585196 0.787216 + outer loop + vertex 1.32906 0.885113 2.48221 + vertex 1.3244 0.884677 2.48304 + vertex 1.32599 0.881992 2.48065 + endloop + endfacet + facet normal 0.196702 -0.474944 0.857751 + outer loop + vertex 1.32906 0.885113 2.48221 + vertex 1.32835 0.888873 2.48446 + vertex 1.3244 0.884677 2.48304 + endloop + endfacet + facet normal -0.176155 0.960209 0.21672 + outer loop + vertex 1.32521 0.983842 2.50116 + vertex 1.32317 0.983752 2.4999 + vertex 1.32322 0.983162 2.50256 + endloop + endfacet + facet normal -0.196796 0.962181 0.18836 + outer loop + vertex 1.32678 0.9837 2.50352 + vertex 1.32521 0.983842 2.50116 + vertex 1.32322 0.983162 2.50256 + endloop + endfacet + facet normal -0.226424 0.919311 0.32187 + outer loop + vertex 1.32678 0.9837 2.50352 + vertex 1.32322 0.983162 2.50256 + vertex 1.32777 0.982823 2.50672 + endloop + endfacet + facet normal -0.192203 0.938724 0.286103 + outer loop + vertex 1.32777 0.982823 2.50672 + vertex 1.32322 0.983162 2.50256 + vertex 1.32311 0.981956 2.50643 + endloop + endfacet + facet normal -0.18602 0.821239 0.539411 + outer loop + vertex 1.32777 0.982823 2.50672 + vertex 1.32311 0.981956 2.50643 + vertex 1.32772 0.980772 2.50982 + endloop + endfacet + facet normal -0.122188 0.87366 0.470945 + outer loop + vertex 1.32772 0.980772 2.50982 + vertex 1.32311 0.981956 2.50643 + vertex 1.32268 0.980056 2.50985 + endloop + endfacet + facet normal -0.0111575 0.621461 0.783366 + outer loop + vertex 1.32653 0.97773 2.51175 + vertex 1.32268 0.980056 2.50985 + vertex 1.32109 0.977132 2.51214 + endloop + endfacet + facet normal -0.0750228 0.553504 0.82946 + outer loop + vertex 1.32772 0.980772 2.50982 + vertex 1.32268 0.980056 2.50985 + vertex 1.32653 0.97773 2.51175 + endloop + endfacet + facet normal 0.151005 0.655153 0.740252 + outer loop + vertex 1.325 0.985 2.49994 + vertex 1.32909 0.984513 2.49954 + vertex 1.33 0.985 2.49892 + endloop + endfacet + facet normal 0.063122 -0.265365 0.96208 + outer loop + vertex 1.32563 0.984205 2.49968 + vertex 1.32909 0.984513 2.49954 + vertex 1.325 0.985 2.49994 + endloop + endfacet + facet normal -0.161242 0.968055 0.192018 + outer loop + vertex 1.32521 0.983842 2.50116 + vertex 1.32563 0.984205 2.49968 + vertex 1.32317 0.983752 2.4999 + endloop + endfacet + facet normal -0.172708 0.966774 0.188467 + outer loop + vertex 1.32521 0.983842 2.50116 + vertex 1.3288 0.98426 2.5023 + vertex 1.32563 0.984205 2.49968 + endloop + endfacet + facet normal -0.0850117 0.993008 0.0819059 + outer loop + vertex 1.3288 0.98426 2.5023 + vertex 1.32909 0.984513 2.49954 + vertex 1.32563 0.984205 2.49968 + endloop + endfacet + facet normal -0.167085 0.971314 0.16921 + outer loop + vertex 1.3288 0.98426 2.5023 + vertex 1.32521 0.983842 2.50116 + vertex 1.32678 0.9837 2.50352 + endloop + endfacet + facet normal -0.22621 0.0570107 -0.972409 + outer loop + vertex 1.32663 2.04227 2.49912 + vertex 1.33 2.045 2.4985 + vertex 1.33056 2.04129 2.49815 + endloop + endfacet + facet normal -0.23466 0.0680778 -0.969691 + outer loop + vertex 1.325 2.045 2.49971 + vertex 1.33 2.045 2.4985 + vertex 1.32663 2.04227 2.49912 + endloop + endfacet + facet normal -0.305531 -0.89152 -0.33443 + outer loop + vertex 1.33056 2.04129 2.49815 + vertex 1.32907 2.04036 2.50199 + vertex 1.32663 2.04227 2.49912 + endloop + endfacet + facet normal -0.224428 -0.888023 -0.401307 + outer loop + vertex 1.32907 2.04036 2.50199 + vertex 1.32519 2.04131 2.50206 + vertex 1.32663 2.04227 2.49912 + endloop + endfacet + facet normal -0.209843 -0.941636 0.263227 + outer loop + vertex 1.32416 2.04117 2.50488 + vertex 1.32768 2.04074 2.50617 + vertex 1.32466 2.04193 2.508 + endloop + endfacet + facet normal -0.0897549 -0.992599 -0.0818055 + outer loop + vertex 1.32416 2.04117 2.50488 + vertex 1.32519 2.04131 2.50206 + vertex 1.32768 2.04074 2.50617 + endloop + endfacet + facet normal -0.237396 -0.971354 0.0107088 + outer loop + vertex 1.32519 2.04131 2.50206 + vertex 1.32907 2.04036 2.50199 + vertex 1.32768 2.04074 2.50617 + endloop + endfacet + facet normal -0.1651 -0.92963 0.32944 + outer loop + vertex 1.3276 2.04196 2.50955 + vertex 1.32466 2.04193 2.508 + vertex 1.32768 2.04074 2.50617 + endloop + endfacet + facet normal -0.285188 -0.782721 0.553187 + outer loop + vertex 1.32546 2.04343 2.51053 + vertex 1.32466 2.04193 2.508 + vertex 1.3276 2.04196 2.50955 + endloop + endfacet + facet normal -0.100366 -0.647636 0.75531 + outer loop + vertex 1.3276 2.04196 2.50955 + vertex 1.32884 2.044 2.51147 + vertex 1.32546 2.04343 2.51053 + endloop + endfacet + facet normal -0.271114 -0.924264 0.268761 + outer loop + vertex 1.32416 2.04117 2.50488 + vertex 1.32466 2.04193 2.508 + vertex 1.32141 2.04216 2.50551 + endloop + endfacet + facet normal -0.258659 -0.79334 0.551096 + outer loop + vertex 1.32466 2.04193 2.508 + vertex 1.32546 2.04343 2.51053 + vertex 1.32141 2.04402 2.50949 + endloop + endfacet + facet normal -0.362405 -0.843866 0.395668 + outer loop + vertex 1.32141 2.04216 2.50551 + vertex 1.32466 2.04193 2.508 + vertex 1.32141 2.04402 2.50949 + endloop + endfacet + facet normal -0.284138 -0.447916 0.847724 + outer loop + vertex 1.32546 2.04343 2.51053 + vertex 1.32443 2.04649 2.51181 + vertex 1.32141 2.04402 2.50949 + endloop + endfacet + facet normal -0.174536 -0.427729 0.886897 + outer loop + vertex 1.32546 2.04343 2.51053 + vertex 1.32884 2.044 2.51147 + vertex 1.32443 2.04649 2.51181 + endloop + endfacet + facet normal -0.101471 -0.306364 0.946491 + outer loop + vertex 1.32884 2.044 2.51147 + vertex 1.32781 2.04661 2.5122 + vertex 1.32443 2.04649 2.51181 + endloop + endfacet + facet normal 0.203721 0.469956 0.858859 + outer loop + vertex 1.32782 2.13629 2.48446 + vertex 1.32683 2.14065 2.48231 + vertex 1.32256 2.13842 2.48454 + endloop + endfacet + facet normal 0.200501 0.474413 0.857165 + outer loop + vertex 1.32256 2.13842 2.48454 + vertex 1.32683 2.14065 2.48231 + vertex 1.32207 2.14204 2.48265 + endloop + endfacet + facet normal 0.207342 0.694822 0.688645 + outer loop + vertex 1.32411 2.14407 2.48057 + vertex 1.32853 2.14386 2.47945 + vertex 1.32605 2.1462 2.47784 + endloop + endfacet + facet normal 0.215462 0.690202 0.690795 + outer loop + vertex 1.32179 2.14657 2.4788 + vertex 1.32411 2.14407 2.48057 + vertex 1.32605 2.1462 2.47784 + endloop + endfacet + facet normal 0.225299 0.577175 0.784926 + outer loop + vertex 1.32683 2.14065 2.48231 + vertex 1.32411 2.14407 2.48057 + vertex 1.32207 2.14204 2.48265 + endloop + endfacet + facet normal 0.226139 0.577572 0.784392 + outer loop + vertex 1.32853 2.14386 2.47945 + vertex 1.32411 2.14407 2.48057 + vertex 1.32683 2.14065 2.48231 + endloop + endfacet + facet normal 0.188242 0.872271 0.45134 + outer loop + vertex 1.32421 2.15004 2.47257 + vertex 1.32959 2.15009 2.47024 + vertex 1.32621 2.15179 2.46836 + endloop + endfacet + facet normal 0.203143 0.866459 0.456049 + outer loop + vertex 1.32201 2.152 2.46983 + vertex 1.32421 2.15004 2.47257 + vertex 1.32621 2.15179 2.46836 + endloop + endfacet + facet normal 0.196526 0.860392 0.470216 + outer loop + vertex 1.32959 2.15009 2.47024 + vertex 1.32421 2.15004 2.47257 + vertex 1.32845 2.14807 2.47441 + endloop + endfacet + facet normal 0.184407 0.852298 0.489471 + outer loop + vertex 1.32845 2.14807 2.47441 + vertex 1.32421 2.15004 2.47257 + vertex 1.32391 2.14808 2.47611 + endloop + endfacet + facet normal 0.201363 0.778797 0.594078 + outer loop + vertex 1.32605 2.1462 2.47784 + vertex 1.32391 2.14808 2.47611 + vertex 1.32179 2.14657 2.4788 + endloop + endfacet + facet normal 0.218044 0.784866 0.580037 + outer loop + vertex 1.32845 2.14807 2.47441 + vertex 1.32391 2.14808 2.47611 + vertex 1.32605 2.1462 2.47784 + endloop + endfacet + facet normal 0.017383 0.0653545 0.997711 + outer loop + vertex 1.33 2.15695 2.465 + vertex 1.325 2.15828 2.465 + vertex 1.32855 2.1539 2.46522 + endloop + endfacet + facet normal 0.271097 0.267289 0.924696 + outer loop + vertex 1.32855 2.1539 2.46522 + vertex 1.325 2.15828 2.465 + vertex 1.32242 2.15447 2.46686 + endloop + endfacet + facet normal 0.259325 0.72461 0.638507 + outer loop + vertex 1.32621 2.15179 2.46836 + vertex 1.32242 2.15447 2.46686 + vertex 1.32201 2.152 2.46983 + endloop + endfacet + facet normal 0.241899 0.711778 0.659436 + outer loop + vertex 1.32855 2.1539 2.46522 + vertex 1.32242 2.15447 2.46686 + vertex 1.32621 2.15179 2.46836 + endloop + endfacet + facet normal 0.01273 -0.0442621 0.998939 + outer loop + vertex 1.335 0.874407 2.465 + vertex 1.33077 0.873928 2.46503 + vertex 1.33 0.872969 2.465 + endloop + endfacet + facet normal -0.107844 0.967917 0.226949 + outer loop + vertex 1.33473 0.874538 2.46431 + vertex 1.33077 0.873928 2.46503 + vertex 1.335 0.874407 2.465 + endloop + endfacet + facet normal 0.209404 -0.896223 0.391069 + outer loop + vertex 1.33077 0.873928 2.46503 + vertex 1.33473 0.874538 2.46431 + vertex 1.33387 0.875432 2.46682 + endloop + endfacet + facet normal 0.204811 -0.894435 0.397539 + outer loop + vertex 1.32795 0.874862 2.46859 + vertex 1.33077 0.873928 2.46503 + vertex 1.33387 0.875432 2.46682 + endloop + endfacet + facet normal 0.207682 -0.888572 0.409034 + outer loop + vertex 1.33387 0.875432 2.46682 + vertex 1.33101 0.877032 2.47175 + vertex 1.32795 0.874862 2.46859 + endloop + endfacet + facet normal 0.222924 -0.890857 0.395827 + outer loop + vertex 1.33101 0.877032 2.47175 + vertex 1.32708 0.876117 2.4719 + vertex 1.32795 0.874862 2.46859 + endloop + endfacet + facet normal 0.159701 -0.850958 0.500366 + outer loop + vertex 1.33101 0.879732 2.47634 + vertex 1.33101 0.877032 2.47175 + vertex 1.33467 0.878985 2.4739 + endloop + endfacet + facet normal 0.237927 -0.837288 0.49228 + outer loop + vertex 1.33101 0.879732 2.47634 + vertex 1.32645 0.877718 2.47512 + vertex 1.33101 0.877032 2.47175 + endloop + endfacet + facet normal 0.217748 -0.856037 0.468814 + outer loop + vertex 1.32645 0.877718 2.47512 + vertex 1.32708 0.876117 2.4719 + vertex 1.33101 0.877032 2.47175 + endloop + endfacet + facet normal 0.208514 -0.807149 0.552297 + outer loop + vertex 1.33101 0.879732 2.47634 + vertex 1.32738 0.880064 2.47819 + vertex 1.32645 0.877718 2.47512 + endloop + endfacet + facet normal 0.185179 -0.826779 0.531173 + outer loop + vertex 1.33467 0.878985 2.4739 + vertex 1.33423 0.880439 2.47632 + vertex 1.33101 0.879732 2.47634 + endloop + endfacet + facet normal 0.209226 -0.70833 0.674161 + outer loop + vertex 1.32738 0.880064 2.47819 + vertex 1.32992 0.882247 2.4797 + vertex 1.32599 0.881992 2.48065 + endloop + endfacet + facet normal 0.25561 -0.732466 0.630997 + outer loop + vertex 1.33101 0.879732 2.47634 + vertex 1.32992 0.882247 2.4797 + vertex 1.32738 0.880064 2.47819 + endloop + endfacet + facet normal 0.196953 -0.753291 0.627505 + outer loop + vertex 1.33101 0.879732 2.47634 + vertex 1.33422 0.88247 2.47862 + vertex 1.32992 0.882247 2.4797 + endloop + endfacet + facet normal 0.166542 -0.738846 0.65297 + outer loop + vertex 1.33101 0.879732 2.47634 + vertex 1.33423 0.880439 2.47632 + vertex 1.33422 0.88247 2.47862 + endloop + endfacet + facet normal 0.224417 -0.603561 0.765083 + outer loop + vertex 1.32992 0.882247 2.4797 + vertex 1.32906 0.885113 2.48221 + vertex 1.32599 0.881992 2.48065 + endloop + endfacet + facet normal 0.218113 -0.642737 0.734382 + outer loop + vertex 1.33422 0.88247 2.47862 + vertex 1.33252 0.884794 2.48116 + vertex 1.32992 0.882247 2.4797 + endloop + endfacet + facet normal 0.176787 -0.618385 0.765732 + outer loop + vertex 1.33252 0.884794 2.48116 + vertex 1.32906 0.885113 2.48221 + vertex 1.32992 0.882247 2.4797 + endloop + endfacet + facet normal 0.208425 -0.507709 0.835937 + outer loop + vertex 1.33252 0.884794 2.48116 + vertex 1.33373 0.88863 2.48319 + vertex 1.32906 0.885113 2.48221 + endloop + endfacet + facet normal 0.181634 -0.478571 0.859057 + outer loop + vertex 1.33373 0.88863 2.48319 + vertex 1.32835 0.888873 2.48446 + vertex 1.32906 0.885113 2.48221 + endloop + endfacet + facet normal -0.267658 0.904972 0.330735 + outer loop + vertex 1.32959 0.98383 2.50544 + vertex 1.32678 0.9837 2.50352 + vertex 1.32777 0.982823 2.50672 + endloop + endfacet + facet normal -0.243485 0.900053 0.361413 + outer loop + vertex 1.33151 0.983362 2.5079 + vertex 1.32959 0.98383 2.50544 + vertex 1.32777 0.982823 2.50672 + endloop + endfacet + facet normal -0.293303 0.755295 0.586091 + outer loop + vertex 1.33151 0.983362 2.5079 + vertex 1.32777 0.982823 2.50672 + vertex 1.33194 0.981952 2.50993 + endloop + endfacet + facet normal -0.240083 0.811808 0.532286 + outer loop + vertex 1.33194 0.981952 2.50993 + vertex 1.32777 0.982823 2.50672 + vertex 1.32772 0.980772 2.50982 + endloop + endfacet + facet normal -0.0948039 0.558033 0.824385 + outer loop + vertex 1.33234 0.97892 2.51161 + vertex 1.32772 0.980772 2.50982 + vertex 1.32653 0.97773 2.51175 + endloop + endfacet + facet normal -0.151319 0.463758 0.872944 + outer loop + vertex 1.33194 0.981952 2.50993 + vertex 1.32772 0.980772 2.50982 + vertex 1.33234 0.97892 2.51161 + endloop + endfacet + facet normal 0.0478101 0.895408 0.442671 + outer loop + vertex 1.33 0.985 2.49892 + vertex 1.33358 0.984821 2.4989 + vertex 1.335 0.985 2.49838 + endloop + endfacet + facet normal 0.042135 0.752948 0.65673 + outer loop + vertex 1.32909 0.984513 2.49954 + vertex 1.33358 0.984821 2.4989 + vertex 1.33 0.985 2.49892 + endloop + endfacet + facet normal -0.0704437 0.997414 -0.0142789 + outer loop + vertex 1.33358 0.984821 2.4989 + vertex 1.32909 0.984513 2.49954 + vertex 1.33329 0.984849 2.50226 + endloop + endfacet + facet normal -0.128895 0.988668 0.076947 + outer loop + vertex 1.33329 0.984849 2.50226 + vertex 1.32909 0.984513 2.49954 + vertex 1.3288 0.98426 2.5023 + endloop + endfacet + facet normal -0.163879 0.970943 0.174395 + outer loop + vertex 1.32959 0.98383 2.50544 + vertex 1.3288 0.98426 2.5023 + vertex 1.32678 0.9837 2.50352 + endloop + endfacet + facet normal -0.140364 0.975556 0.169079 + outer loop + vertex 1.32959 0.98383 2.50544 + vertex 1.33337 0.984223 2.50631 + vertex 1.3288 0.98426 2.5023 + endloop + endfacet + facet normal -0.127065 0.979876 0.153941 + outer loop + vertex 1.33337 0.984223 2.50631 + vertex 1.33329 0.984849 2.50226 + vertex 1.3288 0.98426 2.5023 + endloop + endfacet + facet normal -0.168459 0.935766 0.309781 + outer loop + vertex 1.33337 0.984223 2.50631 + vertex 1.32959 0.98383 2.50544 + vertex 1.33151 0.983362 2.5079 + endloop + endfacet + facet normal -0.211617 -0.697419 -0.684708 + outer loop + vertex 1.33056 2.04129 2.49815 + vertex 1.33229 2.04355 2.49531 + vertex 1.33554 2.04086 2.49705 + endloop + endfacet + facet normal -0.82563 -0.0729747 -0.559474 + outer loop + vertex 1.33 2.045 2.4985 + vertex 1.33229 2.04355 2.49531 + vertex 1.33056 2.04129 2.49815 + endloop + endfacet + facet normal -0.14959 -0.938255 -0.311929 + outer loop + vertex 1.33554 2.04086 2.49705 + vertex 1.3336 2.03964 2.50164 + vertex 1.33056 2.04129 2.49815 + endloop + endfacet + facet normal -0.171202 -0.940311 -0.294117 + outer loop + vertex 1.3336 2.03964 2.50164 + vertex 1.32907 2.04036 2.50199 + vertex 1.33056 2.04129 2.49815 + endloop + endfacet + facet normal -0.153901 -0.987772 0.0249284 + outer loop + vertex 1.3336 2.03964 2.50164 + vertex 1.33239 2.03994 2.50599 + vertex 1.32907 2.04036 2.50199 + endloop + endfacet + facet normal -0.166505 -0.985397 0.035626 + outer loop + vertex 1.33239 2.03994 2.50599 + vertex 1.32768 2.04074 2.50617 + vertex 1.32907 2.04036 2.50199 + endloop + endfacet + facet normal -0.1454 -0.928949 0.340459 + outer loop + vertex 1.33239 2.03994 2.50599 + vertex 1.33111 2.0414 2.50942 + vertex 1.32768 2.04074 2.50617 + endloop + endfacet + facet normal -0.136103 -0.933551 0.331599 + outer loop + vertex 1.33111 2.0414 2.50942 + vertex 1.3276 2.04196 2.50955 + vertex 1.32768 2.04074 2.50617 + endloop + endfacet + facet normal -0.0757519 -0.657399 0.749726 + outer loop + vertex 1.33111 2.0414 2.50942 + vertex 1.32884 2.044 2.51147 + vertex 1.3276 2.04196 2.50955 + endloop + endfacet + facet normal -0.115831 -0.675353 0.728342 + outer loop + vertex 1.33386 2.04308 2.51142 + vertex 1.32884 2.044 2.51147 + vertex 1.33111 2.0414 2.50942 + endloop + endfacet + facet normal -0.798245 -0.489498 -0.350994 + outer loop + vertex 1.33229 2.04355 2.49531 + vertex 1.33 2.045 2.4985 + vertex 1.33 2.04751 2.495 + endloop + endfacet + facet normal 0.000311637 -0.0778035 -0.996969 + outer loop + vertex 1.335 2.04753 2.495 + vertex 1.33229 2.04355 2.49531 + vertex 1.33 2.04751 2.495 + endloop + endfacet + facet normal -0.0183713 -0.161813 0.98665 + outer loop + vertex 1.33386 2.04308 2.51142 + vertex 1.33138 2.04675 2.51197 + vertex 1.32884 2.044 2.51147 + endloop + endfacet + facet normal 0.0729753 -0.242768 0.967336 + outer loop + vertex 1.32884 2.044 2.51147 + vertex 1.33138 2.04675 2.51197 + vertex 1.32781 2.04661 2.5122 + endloop + endfacet + facet normal 0.179001 0.582617 0.79279 + outer loop + vertex 1.33487 2.13984 2.48109 + vertex 1.33411 2.14197 2.47969 + vertex 1.33146 2.14152 2.48062 + endloop + endfacet + facet normal 0.146959 0.529453 0.835513 + outer loop + vertex 1.33146 2.14152 2.48062 + vertex 1.33161 2.13808 2.48278 + vertex 1.33487 2.13984 2.48109 + endloop + endfacet + facet normal 0.20149 0.525979 0.826286 + outer loop + vertex 1.33146 2.14152 2.48062 + vertex 1.32683 2.14065 2.48231 + vertex 1.33161 2.13808 2.48278 + endloop + endfacet + facet normal 0.165033 0.466212 0.869144 + outer loop + vertex 1.32683 2.14065 2.48231 + vertex 1.32782 2.13629 2.48446 + vertex 1.33161 2.13808 2.48278 + endloop + endfacet + facet normal 0.235417 0.755449 0.611454 + outer loop + vertex 1.3335 2.14424 2.4776 + vertex 1.33218 2.14682 2.47493 + vertex 1.3297 2.14596 2.47694 + endloop + endfacet + facet normal 0.213561 0.697931 0.683582 + outer loop + vertex 1.3297 2.14596 2.47694 + vertex 1.32605 2.1462 2.47784 + vertex 1.32853 2.14386 2.47945 + endloop + endfacet + facet normal 0.199755 0.703632 0.681909 + outer loop + vertex 1.3335 2.14424 2.4776 + vertex 1.3297 2.14596 2.47694 + vertex 1.32853 2.14386 2.47945 + endloop + endfacet + facet normal 0.222633 0.644779 0.731228 + outer loop + vertex 1.3335 2.14424 2.4776 + vertex 1.32853 2.14386 2.47945 + vertex 1.33146 2.14152 2.48062 + endloop + endfacet + facet normal 0.131919 0.69051 0.711191 + outer loop + vertex 1.3335 2.14424 2.4776 + vertex 1.33146 2.14152 2.48062 + vertex 1.33411 2.14197 2.47969 + endloop + endfacet + facet normal 0.169997 0.602908 0.779489 + outer loop + vertex 1.33146 2.14152 2.48062 + vertex 1.32853 2.14386 2.47945 + vertex 1.32683 2.14065 2.48231 + endloop + endfacet + facet normal 0.134019 0.795565 0.59086 + outer loop + vertex 1.33439 2.15051 2.46746 + vertex 1.33279 2.15251 2.46513 + vertex 1.33034 2.15154 2.46699 + endloop + endfacet + facet normal 0.197489 0.876682 0.438665 + outer loop + vertex 1.33034 2.15154 2.46699 + vertex 1.32621 2.15179 2.46836 + vertex 1.32959 2.15009 2.47024 + endloop + endfacet + facet normal 0.174274 0.882887 0.43605 + outer loop + vertex 1.33034 2.15154 2.46699 + vertex 1.32959 2.15009 2.47024 + vertex 1.33439 2.15051 2.46746 + endloop + endfacet + facet normal 0.186679 0.870371 0.455637 + outer loop + vertex 1.33439 2.15051 2.46746 + vertex 1.32959 2.15009 2.47024 + vertex 1.33322 2.14852 2.47174 + endloop + endfacet + facet normal 0.187895 0.798885 0.571382 + outer loop + vertex 1.33218 2.14682 2.47493 + vertex 1.32845 2.14807 2.47441 + vertex 1.3297 2.14596 2.47694 + endloop + endfacet + facet normal 0.207512 0.833127 0.512677 + outer loop + vertex 1.33218 2.14682 2.47493 + vertex 1.33322 2.14852 2.47174 + vertex 1.32845 2.14807 2.47441 + endloop + endfacet + facet normal 0.179399 0.865346 0.467966 + outer loop + vertex 1.33322 2.14852 2.47174 + vertex 1.32959 2.15009 2.47024 + vertex 1.32845 2.14807 2.47441 + endloop + endfacet + facet normal 0.192038 0.799183 0.569586 + outer loop + vertex 1.3297 2.14596 2.47694 + vertex 1.32845 2.14807 2.47441 + vertex 1.32605 2.1462 2.47784 + endloop + endfacet + facet normal 0.241874 0.692701 0.679457 + outer loop + vertex 1.33279 2.15251 2.46513 + vertex 1.32855 2.1539 2.46522 + vertex 1.33034 2.15154 2.46699 + endloop + endfacet + facet normal 0.0276744 0.0178722 0.999457 + outer loop + vertex 1.33279 2.15251 2.46513 + vertex 1.335 2.1565 2.465 + vertex 1.32855 2.1539 2.46522 + endloop + endfacet + facet normal 0.0063505 0.0705774 0.997486 + outer loop + vertex 1.335 2.1565 2.465 + vertex 1.33 2.15695 2.465 + vertex 1.32855 2.1539 2.46522 + endloop + endfacet + facet normal 0.262689 0.698312 0.665849 + outer loop + vertex 1.33034 2.15154 2.46699 + vertex 1.32855 2.1539 2.46522 + vertex 1.32621 2.15179 2.46836 + endloop + endfacet + facet normal 0.213888 -0.688896 -0.692585 + outer loop + vertex 1.33691 0.875 2.465 + vertex 1.335 0.874407 2.465 + vertex 1.335 0.875 2.46441 + endloop + endfacet + facet normal -0.284143 0.915175 0.285863 + outer loop + vertex 1.33691 0.875 2.465 + vertex 1.33473 0.874538 2.46431 + vertex 1.335 0.874407 2.465 + endloop + endfacet + facet normal -0.296894 0.891541 0.342065 + outer loop + vertex 1.33473 0.874538 2.46431 + vertex 1.33691 0.875 2.465 + vertex 1.34 0.876029 2.465 + endloop + endfacet + facet normal 0.20318 -0.898263 0.389669 + outer loop + vertex 1.33473 0.874538 2.46431 + vertex 1.34 0.876029 2.465 + vertex 1.33387 0.875432 2.46682 + endloop + endfacet + facet normal 0.187525 -0.925932 0.327847 + outer loop + vertex 1.33387 0.875432 2.46682 + vertex 1.34 0.876029 2.465 + vertex 1.33782 0.876198 2.46672 + endloop + endfacet + facet normal 0.184496 -0.902955 0.388114 + outer loop + vertex 1.33782 0.876198 2.46672 + vertex 1.33668 0.877301 2.46983 + vertex 1.33387 0.875432 2.46682 + endloop + endfacet + facet normal 0.17622 -0.901626 0.39499 + outer loop + vertex 1.33668 0.877301 2.46983 + vertex 1.33101 0.877032 2.47175 + vertex 1.33387 0.875432 2.46682 + endloop + endfacet + facet normal 0.195189 -0.868374 0.455881 + outer loop + vertex 1.33668 0.877301 2.46983 + vertex 1.33467 0.878985 2.4739 + vertex 1.33101 0.877032 2.47175 + endloop + endfacet + facet normal 0.163396 -0.880422 0.445151 + outer loop + vertex 1.33829 0.879075 2.47275 + vertex 1.33467 0.878985 2.4739 + vertex 1.33668 0.877301 2.46983 + endloop + endfacet + facet normal 0.19212 -0.819174 0.540411 + outer loop + vertex 1.33467 0.878985 2.4739 + vertex 1.33829 0.879075 2.47275 + vertex 1.33765 0.880968 2.47585 + endloop + endfacet + facet normal 0.20037 -0.822934 0.531632 + outer loop + vertex 1.33423 0.880439 2.47632 + vertex 1.33467 0.878985 2.4739 + vertex 1.33765 0.880968 2.47585 + endloop + endfacet + facet normal 0.202641 -0.733732 0.648517 + outer loop + vertex 1.33765 0.880968 2.47585 + vertex 1.33422 0.88247 2.47862 + vertex 1.33423 0.880439 2.47632 + endloop + endfacet + facet normal 0.203196 -0.733218 0.648924 + outer loop + vertex 1.33901 0.88387 2.4787 + vertex 1.33422 0.88247 2.47862 + vertex 1.33765 0.880968 2.47585 + endloop + endfacet + facet normal 0.170155 -0.626714 0.760445 + outer loop + vertex 1.33422 0.88247 2.47862 + vertex 1.33901 0.88387 2.4787 + vertex 1.33644 0.886 2.48103 + endloop + endfacet + facet normal 0.22095 -0.641202 0.734875 + outer loop + vertex 1.33252 0.884794 2.48116 + vertex 1.33422 0.88247 2.47862 + vertex 1.33644 0.886 2.48103 + endloop + endfacet + facet normal 0.182229 -0.503926 0.844305 + outer loop + vertex 1.33644 0.886 2.48103 + vertex 1.33373 0.88863 2.48319 + vertex 1.33252 0.884794 2.48116 + endloop + endfacet + facet normal 0.189012 -0.498389 0.846099 + outer loop + vertex 1.33928 0.889865 2.48267 + vertex 1.33373 0.88863 2.48319 + vertex 1.33644 0.886 2.48103 + endloop + endfacet + facet normal -0.257731 0.773968 -0.578401 + outer loop + vertex 1.34 0.984139 2.495 + vertex 1.335 0.982474 2.495 + vertex 1.335 0.985 2.49838 + endloop + endfacet + facet normal -0.457644 -0.743524 -0.48758 + outer loop + vertex 1.33918 0.984777 2.4948 + vertex 1.34 0.984139 2.495 + vertex 1.335 0.985 2.49838 + endloop + endfacet + facet normal -0.256085 0.768031 0.586983 + outer loop + vertex 1.33441 0.983168 2.50942 + vertex 1.33151 0.983362 2.5079 + vertex 1.33194 0.981952 2.50993 + endloop + endfacet + facet normal -0.155317 0.635333 0.756458 + outer loop + vertex 1.33194 0.981952 2.50993 + vertex 1.33634 0.98163 2.5111 + vertex 1.33441 0.983168 2.50942 + endloop + endfacet + facet normal -0.198319 0.454879 0.86819 + outer loop + vertex 1.33194 0.981952 2.50993 + vertex 1.33234 0.97892 2.51161 + vertex 1.33634 0.98163 2.5111 + endloop + endfacet + facet normal -0.146578 0.961876 -0.230888 + outer loop + vertex 1.335 0.985 2.49838 + vertex 1.33926 0.985442 2.49752 + vertex 1.33918 0.984777 2.4948 + endloop + endfacet + facet normal -0.075126 0.987759 0.136707 + outer loop + vertex 1.33358 0.984821 2.4989 + vertex 1.33926 0.985442 2.49752 + vertex 1.335 0.985 2.49838 + endloop + endfacet + facet normal -0.116409 0.992701 -0.0315204 + outer loop + vertex 1.33926 0.985442 2.49752 + vertex 1.33358 0.984821 2.4989 + vertex 1.33819 0.985455 2.50185 + endloop + endfacet + facet normal -0.124465 0.992045 -0.0188375 + outer loop + vertex 1.33819 0.985455 2.50185 + vertex 1.33358 0.984821 2.4989 + vertex 1.33329 0.984849 2.50226 + endloop + endfacet + facet normal -0.112647 0.987035 0.114338 + outer loop + vertex 1.33819 0.985455 2.50185 + vertex 1.33329 0.984849 2.50226 + vertex 1.33812 0.984961 2.50605 + endloop + endfacet + facet normal -0.143478 0.977614 0.1539 + outer loop + vertex 1.33812 0.984961 2.50605 + vertex 1.33329 0.984849 2.50226 + vertex 1.33337 0.984223 2.50631 + endloop + endfacet + facet normal -0.124632 0.926123 0.356038 + outer loop + vertex 1.33441 0.983168 2.50942 + vertex 1.33337 0.984223 2.50631 + vertex 1.33151 0.983362 2.5079 + endloop + endfacet + facet normal -0.118689 0.927486 0.354518 + outer loop + vertex 1.33441 0.983168 2.50942 + vertex 1.33792 0.983639 2.50936 + vertex 1.33337 0.984223 2.50631 + endloop + endfacet + facet normal -0.123925 0.924035 0.361664 + outer loop + vertex 1.33792 0.983639 2.50936 + vertex 1.33812 0.984961 2.50605 + vertex 1.33337 0.984223 2.50631 + endloop + endfacet + facet normal -0.0807381 0.689106 0.720149 + outer loop + vertex 1.33792 0.983639 2.50936 + vertex 1.33441 0.983168 2.50942 + vertex 1.33634 0.98163 2.5111 + endloop + endfacet + facet normal 0.0786773 -0.471806 -0.878185 + outer loop + vertex 1.33751 2.045 2.495 + vertex 1.33554 2.04086 2.49705 + vertex 1.33229 2.04355 2.49531 + endloop + endfacet + facet normal -0.302905 -0.302905 -0.903602 + outer loop + vertex 1.33751 2.045 2.495 + vertex 1.34 2.04251 2.495 + vertex 1.33554 2.04086 2.49705 + endloop + endfacet + facet normal -0.087933 -0.673456 -0.733978 + outer loop + vertex 1.34 2.04251 2.495 + vertex 1.3401 2.03941 2.49783 + vertex 1.33554 2.04086 2.49705 + endloop + endfacet + facet normal -0.254954 -0.935139 -0.245996 + outer loop + vertex 1.3401 2.03941 2.49783 + vertex 1.3383 2.03895 2.50144 + vertex 1.33554 2.04086 2.49705 + endloop + endfacet + facet normal -0.150915 -0.937889 -0.312393 + outer loop + vertex 1.3383 2.03895 2.50144 + vertex 1.3336 2.03964 2.50164 + vertex 1.33554 2.04086 2.49705 + endloop + endfacet + facet normal -0.142942 -0.988362 0.0520361 + outer loop + vertex 1.3383 2.03895 2.50144 + vertex 1.33709 2.03936 2.50575 + vertex 1.3336 2.03964 2.50164 + endloop + endfacet + facet normal -0.12206 -0.991938 0.0340601 + outer loop + vertex 1.33709 2.03936 2.50575 + vertex 1.33239 2.03994 2.50599 + vertex 1.3336 2.03964 2.50164 + endloop + endfacet + facet normal -0.101362 -0.942049 0.319795 + outer loop + vertex 1.33709 2.03936 2.50575 + vertex 1.33574 2.0407 2.5093 + vertex 1.33239 2.03994 2.50599 + endloop + endfacet + facet normal -0.130322 -0.92908 0.34616 + outer loop + vertex 1.33574 2.0407 2.5093 + vertex 1.33111 2.0414 2.50942 + vertex 1.33239 2.03994 2.50599 + endloop + endfacet + facet normal -0.0867884 -0.699865 0.708983 + outer loop + vertex 1.33574 2.0407 2.5093 + vertex 1.33386 2.04308 2.51142 + vertex 1.33111 2.0414 2.50942 + endloop + endfacet + facet normal -0.11055 -0.708269 0.697233 + outer loop + vertex 1.338 2.04216 2.51114 + vertex 1.33386 2.04308 2.51142 + vertex 1.33574 2.0407 2.5093 + endloop + endfacet + facet normal -0.0464018 -0.0460366 -0.997861 + outer loop + vertex 1.33751 2.045 2.495 + vertex 1.33229 2.04355 2.49531 + vertex 1.335 2.04753 2.495 + endloop + endfacet + facet normal 0.172628 0.395742 0.901991 + outer loop + vertex 1.33853 2.13186 2.48432 + vertex 1.33638 2.13627 2.4828 + vertex 1.33264 2.1336 2.48468 + endloop + endfacet + facet normal 0.190996 0.596848 0.77929 + outer loop + vertex 1.33487 2.13984 2.48109 + vertex 1.3392 2.13873 2.48088 + vertex 1.33716 2.14181 2.47902 + endloop + endfacet + facet normal 0.204609 0.585976 0.784071 + outer loop + vertex 1.33411 2.14197 2.47969 + vertex 1.33487 2.13984 2.48109 + vertex 1.33716 2.14181 2.47902 + endloop + endfacet + facet normal 0.181277 0.48523 0.855389 + outer loop + vertex 1.33638 2.13627 2.4828 + vertex 1.33487 2.13984 2.48109 + vertex 1.33161 2.13808 2.48278 + endloop + endfacet + facet normal 0.165231 0.481114 0.860946 + outer loop + vertex 1.3392 2.13873 2.48088 + vertex 1.33487 2.13984 2.48109 + vertex 1.33638 2.13627 2.4828 + endloop + endfacet + facet normal 0.18387 0.780096 0.598032 + outer loop + vertex 1.3335 2.14424 2.4776 + vertex 1.3396 2.14423 2.47574 + vertex 1.33611 2.14662 2.4737 + endloop + endfacet + facet normal 0.230164 0.755172 0.613791 + outer loop + vertex 1.33218 2.14682 2.47493 + vertex 1.3335 2.14424 2.4776 + vertex 1.33611 2.14662 2.4737 + endloop + endfacet + facet normal 0.191044 0.692299 0.695862 + outer loop + vertex 1.33716 2.14181 2.47902 + vertex 1.3335 2.14424 2.4776 + vertex 1.33411 2.14197 2.47969 + endloop + endfacet + facet normal 0.20777 0.706283 0.676754 + outer loop + vertex 1.3396 2.14423 2.47574 + vertex 1.3335 2.14424 2.4776 + vertex 1.33716 2.14181 2.47902 + endloop + endfacet + facet normal 0.11198 0.722207 0.682552 + outer loop + vertex 1.33439 2.15051 2.46746 + vertex 1.33983 2.15113 2.46592 + vertex 1.33693 2.15279 2.46464 + endloop + endfacet + facet normal 0.0255537 0.767079 0.641044 + outer loop + vertex 1.33279 2.15251 2.46513 + vertex 1.33439 2.15051 2.46746 + vertex 1.33693 2.15279 2.46464 + endloop + endfacet + facet normal 0.0753691 0.806001 0.587096 + outer loop + vertex 1.33983 2.15113 2.46592 + vertex 1.33439 2.15051 2.46746 + vertex 1.33836 2.14851 2.4697 + endloop + endfacet + facet normal 0.18282 0.871475 0.455092 + outer loop + vertex 1.33836 2.14851 2.4697 + vertex 1.33439 2.15051 2.46746 + vertex 1.33322 2.14852 2.47174 + endloop + endfacet + facet normal 0.202549 0.834796 0.511948 + outer loop + vertex 1.33611 2.14662 2.4737 + vertex 1.33322 2.14852 2.47174 + vertex 1.33218 2.14682 2.47493 + endloop + endfacet + facet normal 0.204482 0.835591 0.509877 + outer loop + vertex 1.33836 2.14851 2.4697 + vertex 1.33322 2.14852 2.47174 + vertex 1.33611 2.14662 2.4737 + endloop + endfacet + facet normal 0.120708 -0.0339257 0.992108 + outer loop + vertex 1.33693 2.15279 2.46464 + vertex 1.335 2.1565 2.465 + vertex 1.33279 2.15251 2.46513 + endloop + endfacet + facet normal -0.0189845 -0.106653 0.994115 + outer loop + vertex 1.34 2.15561 2.465 + vertex 1.335 2.1565 2.465 + vertex 1.33693 2.15279 2.46464 + endloop + endfacet + facet normal 0.12124 -0.915755 0.383006 + outer loop + vertex 1.345 0.876691 2.465 + vertex 1.34152 0.877065 2.46699 + vertex 1.34 0.876029 2.465 + endloop + endfacet + facet normal 0.191807 -0.923214 0.332995 + outer loop + vertex 1.34152 0.877065 2.46699 + vertex 1.33782 0.876198 2.46672 + vertex 1.34 0.876029 2.465 + endloop + endfacet + facet normal 0.18876 -0.901666 0.389059 + outer loop + vertex 1.34062 0.87836 2.47043 + vertex 1.34152 0.877065 2.46699 + vertex 1.3447 0.878686 2.46921 + endloop + endfacet + facet normal 0.183444 -0.903127 0.388215 + outer loop + vertex 1.34062 0.87836 2.47043 + vertex 1.33668 0.877301 2.46983 + vertex 1.34152 0.877065 2.46699 + endloop + endfacet + facet normal 0.183175 -0.903369 0.387776 + outer loop + vertex 1.33668 0.877301 2.46983 + vertex 1.33782 0.876198 2.46672 + vertex 1.34152 0.877065 2.46699 + endloop + endfacet + facet normal 0.169238 -0.880817 0.442177 + outer loop + vertex 1.34062 0.87836 2.47043 + vertex 1.33829 0.879075 2.47275 + vertex 1.33668 0.877301 2.46983 + endloop + endfacet + facet normal 0.20709 -0.863212 0.460412 + outer loop + vertex 1.3447 0.878686 2.46921 + vertex 1.34243 0.880245 2.47315 + vertex 1.34062 0.87836 2.47043 + endloop + endfacet + facet normal 0.198267 -0.86242 0.465748 + outer loop + vertex 1.33829 0.879075 2.47275 + vertex 1.34062 0.87836 2.47043 + vertex 1.34243 0.880245 2.47315 + endloop + endfacet + facet normal 0.179826 -0.822352 0.539815 + outer loop + vertex 1.33829 0.879075 2.47275 + vertex 1.34243 0.880245 2.47315 + vertex 1.33765 0.880968 2.47585 + endloop + endfacet + facet normal 0.19943 -0.798366 0.56819 + outer loop + vertex 1.33765 0.880968 2.47585 + vertex 1.34243 0.880245 2.47315 + vertex 1.34182 0.882422 2.47643 + endloop + endfacet + facet normal 0.162088 -0.729352 0.66466 + outer loop + vertex 1.34182 0.882422 2.47643 + vertex 1.33901 0.88387 2.4787 + vertex 1.33765 0.880968 2.47585 + endloop + endfacet + facet normal 0.194574 -0.700571 0.686543 + outer loop + vertex 1.34417 0.885131 2.47853 + vertex 1.33901 0.88387 2.4787 + vertex 1.34182 0.882422 2.47643 + endloop + endfacet + facet normal 0.175117 -0.608971 0.77362 + outer loop + vertex 1.33901 0.88387 2.4787 + vertex 1.34417 0.885131 2.47853 + vertex 1.34102 0.887042 2.48074 + endloop + endfacet + facet normal 0.187842 -0.613027 0.767407 + outer loop + vertex 1.33644 0.886 2.48103 + vertex 1.33901 0.88387 2.4787 + vertex 1.34102 0.887042 2.48074 + endloop + endfacet + facet normal 0.164585 -0.485699 0.858492 + outer loop + vertex 1.34102 0.887042 2.48074 + vertex 1.33928 0.889865 2.48267 + vertex 1.33644 0.886 2.48103 + endloop + endfacet + facet normal 0.170632 -0.482436 0.859151 + outer loop + vertex 1.34382 0.890354 2.48205 + vertex 1.33928 0.889865 2.48267 + vertex 1.34102 0.887042 2.48074 + endloop + endfacet + facet normal 0.166882 -0.386329 0.907138 + outer loop + vertex 1.34382 0.890354 2.48205 + vertex 1.34336 0.893973 2.48367 + vertex 1.33928 0.889865 2.48267 + endloop + endfacet + facet normal 0.135851 -0.134111 -0.98161 + outer loop + vertex 1.34085 0.985 2.495 + vertex 1.34 0.984139 2.495 + vertex 1.33918 0.984777 2.4948 + endloop + endfacet + facet normal 0.148131 -0.248081 -0.957347 + outer loop + vertex 1.33918 0.984777 2.4948 + vertex 1.345 0.987478 2.495 + vertex 1.34085 0.985 2.495 + endloop + endfacet + facet normal -0.405932 0.890384 -0.206 + outer loop + vertex 1.33918 0.984777 2.4948 + vertex 1.33926 0.985442 2.49752 + vertex 1.345 0.987478 2.495 + endloop + endfacet + facet normal -0.210832 0.937589 0.276544 + outer loop + vertex 1.33926 0.985442 2.49752 + vertex 1.3447 0.986532 2.49797 + vertex 1.345 0.987478 2.495 + endloop + endfacet + facet normal -0.198302 0.979847 0.0240065 + outer loop + vertex 1.3447 0.986532 2.49797 + vertex 1.33926 0.985442 2.49752 + vertex 1.34337 0.986174 2.50166 + endloop + endfacet + facet normal -0.138725 0.989639 -0.0370202 + outer loop + vertex 1.34337 0.986174 2.50166 + vertex 1.33926 0.985442 2.49752 + vertex 1.33819 0.985455 2.50185 + endloop + endfacet + facet normal -0.13178 0.983463 0.124238 + outer loop + vertex 1.34337 0.986174 2.50166 + vertex 1.33819 0.985455 2.50185 + vertex 1.34309 0.985606 2.50586 + endloop + endfacet + facet normal -0.123504 0.985772 0.114019 + outer loop + vertex 1.34309 0.985606 2.50586 + vertex 1.33819 0.985455 2.50185 + vertex 1.33812 0.984961 2.50605 + endloop + endfacet + facet normal -0.106518 0.927641 0.35796 + outer loop + vertex 1.34309 0.985606 2.50586 + vertex 1.33812 0.984961 2.50605 + vertex 1.34275 0.984253 2.50926 + endloop + endfacet + facet normal -0.110364 0.92524 0.362976 + outer loop + vertex 1.34275 0.984253 2.50926 + vertex 1.33812 0.984961 2.50605 + vertex 1.33792 0.983639 2.50936 + endloop + endfacet + facet normal -0.0789576 0.688436 0.720987 + outer loop + vertex 1.34128 0.982055 2.51124 + vertex 1.33792 0.983639 2.50936 + vertex 1.33634 0.98163 2.5111 + endloop + endfacet + facet normal -0.0740302 0.693607 0.71654 + outer loop + vertex 1.34275 0.984253 2.50926 + vertex 1.33792 0.983639 2.50936 + vertex 1.34128 0.982055 2.51124 + endloop + endfacet + facet normal 0.00085812 -0.428478 -0.903552 + outer loop + vertex 1.345 2.04252 2.495 + vertex 1.345 2.03902 2.49666 + vertex 1.34 2.04251 2.495 + endloop + endfacet + facet normal -0.224388 -0.661347 -0.715731 + outer loop + vertex 1.345 2.03902 2.49666 + vertex 1.3401 2.03941 2.49783 + vertex 1.34 2.04251 2.495 + endloop + endfacet + facet normal -0.121001 -0.976814 -0.176616 + outer loop + vertex 1.345 2.03902 2.49666 + vertex 1.34302 2.03843 2.50127 + vertex 1.3401 2.03941 2.49783 + endloop + endfacet + facet normal -0.115349 -0.976629 -0.181357 + outer loop + vertex 1.34302 2.03843 2.50127 + vertex 1.3383 2.03895 2.50144 + vertex 1.3401 2.03941 2.49783 + endloop + endfacet + facet normal -0.107883 -0.991368 0.0745057 + outer loop + vertex 1.34302 2.03843 2.50127 + vertex 1.34108 2.03892 2.50506 + vertex 1.3383 2.03895 2.50144 + endloop + endfacet + facet normal -0.0962988 -0.99319 0.06557 + outer loop + vertex 1.34108 2.03892 2.50506 + vertex 1.33709 2.03936 2.50575 + vertex 1.3383 2.03895 2.50144 + endloop + endfacet + facet normal -0.0379332 -0.931441 0.361911 + outer loop + vertex 1.34108 2.03892 2.50506 + vertex 1.34068 2.04042 2.50887 + vertex 1.33709 2.03936 2.50575 + endloop + endfacet + facet normal -0.0236153 -0.9374 0.347453 + outer loop + vertex 1.34068 2.04042 2.50887 + vertex 1.33574 2.0407 2.5093 + vertex 1.33709 2.03936 2.50575 + endloop + endfacet + facet normal 0.00809519 -0.788276 0.615269 + outer loop + vertex 1.34068 2.04042 2.50887 + vertex 1.338 2.04216 2.51114 + vertex 1.33574 2.0407 2.5093 + endloop + endfacet + facet normal 0.142194 -0.696564 0.703263 + outer loop + vertex 1.34113 2.04289 2.51122 + vertex 1.338 2.04216 2.51114 + vertex 1.34068 2.04042 2.50887 + endloop + endfacet + facet normal 0.148828 0.386913 0.910027 + outer loop + vertex 1.33853 2.13186 2.48432 + vertex 1.34163 2.13496 2.48249 + vertex 1.33638 2.13627 2.4828 + endloop + endfacet + facet normal 0.171874 0.59964 0.781595 + outer loop + vertex 1.3392 2.13873 2.48088 + vertex 1.3431 2.13778 2.48075 + vertex 1.34246 2.14079 2.47858 + endloop + endfacet + facet normal 0.179018 0.592579 0.785368 + outer loop + vertex 1.33716 2.14181 2.47902 + vertex 1.3392 2.13873 2.48088 + vertex 1.34246 2.14079 2.47858 + endloop + endfacet + facet normal 0.168592 0.478075 0.861987 + outer loop + vertex 1.34163 2.13496 2.48249 + vertex 1.3392 2.13873 2.48088 + vertex 1.33638 2.13627 2.4828 + endloop + endfacet + facet normal 0.14199 0.465798 0.873425 + outer loop + vertex 1.3431 2.13778 2.48075 + vertex 1.3392 2.13873 2.48088 + vertex 1.34163 2.13496 2.48249 + endloop + endfacet + facet normal 0.202634 0.83383 0.513485 + outer loop + vertex 1.34417 2.14536 2.47272 + vertex 1.34225 2.14736 2.47022 + vertex 1.34004 2.14655 2.47242 + endloop + endfacet + facet normal 0.202909 0.790638 0.577685 + outer loop + vertex 1.34004 2.14655 2.47242 + vertex 1.33611 2.14662 2.4737 + vertex 1.3396 2.14423 2.47574 + endloop + endfacet + facet normal 0.186453 0.794376 0.578103 + outer loop + vertex 1.34004 2.14655 2.47242 + vertex 1.3396 2.14423 2.47574 + vertex 1.34417 2.14536 2.47272 + endloop + endfacet + facet normal 0.190789 0.789786 0.582956 + outer loop + vertex 1.34417 2.14536 2.47272 + vertex 1.3396 2.14423 2.47574 + vertex 1.34443 2.14301 2.47581 + endloop + endfacet + facet normal 0.192966 0.714865 0.67211 + outer loop + vertex 1.34246 2.14079 2.47858 + vertex 1.3396 2.14423 2.47574 + vertex 1.33716 2.14181 2.47902 + endloop + endfacet + facet normal 0.168174 0.706732 0.687203 + outer loop + vertex 1.34443 2.14301 2.47581 + vertex 1.3396 2.14423 2.47574 + vertex 1.34246 2.14079 2.47858 + endloop + endfacet + facet normal -0.198179 0.356637 0.912981 + outer loop + vertex 1.34258 2.155 2.465 + vertex 1.33693 2.15279 2.46464 + vertex 1.33983 2.15113 2.46592 + endloop + endfacet + facet normal 0.0556343 0.192342 0.97975 + outer loop + vertex 1.34258 2.155 2.465 + vertex 1.33983 2.15113 2.46592 + vertex 1.345 2.1543 2.465 + endloop + endfacet + facet normal -0.122022 0.453722 0.88275 + outer loop + vertex 1.345 2.1543 2.465 + vertex 1.33983 2.15113 2.46592 + vertex 1.34301 2.14923 2.46733 + endloop + endfacet + facet normal 0.182746 0.8474 0.498515 + outer loop + vertex 1.34225 2.14736 2.47022 + vertex 1.33836 2.14851 2.4697 + vertex 1.34004 2.14655 2.47242 + endloop + endfacet + facet normal 0.162457 0.808866 0.565105 + outer loop + vertex 1.34225 2.14736 2.47022 + vertex 1.34301 2.14923 2.46733 + vertex 1.33836 2.14851 2.4697 + endloop + endfacet + facet normal 0.189987 0.77121 0.60757 + outer loop + vertex 1.34301 2.14923 2.46733 + vertex 1.33983 2.15113 2.46592 + vertex 1.33836 2.14851 2.4697 + endloop + endfacet + facet normal 0.178677 0.846968 0.500718 + outer loop + vertex 1.34004 2.14655 2.47242 + vertex 1.33836 2.14851 2.4697 + vertex 1.33611 2.14662 2.4737 + endloop + endfacet + facet normal 0.164898 0.697291 -0.697563 + outer loop + vertex 1.34 2.155 2.46439 + vertex 1.34 2.15561 2.465 + vertex 1.34258 2.155 2.465 + endloop + endfacet + facet normal -0.0239568 -0.101304 0.994567 + outer loop + vertex 1.34258 2.155 2.465 + vertex 1.34 2.15561 2.465 + vertex 1.33693 2.15279 2.46464 + endloop + endfacet + facet normal 0.152169 -0.76158 0.629953 + outer loop + vertex 1.35 0.87769 2.465 + vertex 1.34757 0.877789 2.46571 + vertex 1.345 0.876691 2.465 + endloop + endfacet + facet normal 0.210141 -0.827048 0.521375 + outer loop + vertex 1.34757 0.877789 2.46571 + vertex 1.34152 0.877065 2.46699 + vertex 1.345 0.876691 2.465 + endloop + endfacet + facet normal 0.190519 -0.90221 0.386937 + outer loop + vertex 1.34757 0.877789 2.46571 + vertex 1.3447 0.878686 2.46921 + vertex 1.34152 0.877065 2.46699 + endloop + endfacet + facet normal 0.197282 -0.898745 0.391584 + outer loop + vertex 1.34881 0.879034 2.46794 + vertex 1.3447 0.878686 2.46921 + vertex 1.34757 0.877789 2.46571 + endloop + endfacet + facet normal 0.20447 -0.884826 0.418659 + outer loop + vertex 1.3447 0.878686 2.46921 + vertex 1.34881 0.879034 2.46794 + vertex 1.34786 0.880353 2.47119 + endloop + endfacet + facet normal 0.179962 -0.874978 0.449475 + outer loop + vertex 1.34243 0.880245 2.47315 + vertex 1.3447 0.878686 2.46921 + vertex 1.34786 0.880353 2.47119 + endloop + endfacet + facet normal 0.208724 -0.820611 0.532008 + outer loop + vertex 1.34786 0.880353 2.47119 + vertex 1.34676 0.882598 2.47508 + vertex 1.34243 0.880245 2.47315 + endloop + endfacet + facet normal 0.18287 -0.802539 0.567882 + outer loop + vertex 1.34676 0.882598 2.47508 + vertex 1.34182 0.882422 2.47643 + vertex 1.34243 0.880245 2.47315 + endloop + endfacet + facet normal 0.209072 -0.705691 0.67697 + outer loop + vertex 1.34676 0.882598 2.47508 + vertex 1.34417 0.885131 2.47853 + vertex 1.34182 0.882422 2.47643 + endloop + endfacet + facet normal 0.176683 -0.724408 0.666345 + outer loop + vertex 1.34928 0.885364 2.47742 + vertex 1.34417 0.885131 2.47853 + vertex 1.34676 0.882598 2.47508 + endloop + endfacet + facet normal 0.182714 -0.601332 0.777828 + outer loop + vertex 1.34463 0.887935 2.48058 + vertex 1.34102 0.887042 2.48074 + vertex 1.34417 0.885131 2.47853 + endloop + endfacet + facet normal 0.188129 -0.601296 0.776563 + outer loop + vertex 1.34463 0.887935 2.48058 + vertex 1.34417 0.885131 2.47853 + vertex 1.3481 0.887891 2.47971 + endloop + endfacet + facet normal 0.19383 -0.606937 0.770751 + outer loop + vertex 1.3481 0.887891 2.47971 + vertex 1.34417 0.885131 2.47853 + vertex 1.34928 0.885364 2.47742 + endloop + endfacet + facet normal 0.154744 -0.472354 0.867719 + outer loop + vertex 1.34463 0.887935 2.48058 + vertex 1.34382 0.890354 2.48205 + vertex 1.34102 0.887042 2.48074 + endloop + endfacet + facet normal 0.205724 -0.499982 0.841246 + outer loop + vertex 1.3481 0.887891 2.47971 + vertex 1.34704 0.890119 2.48129 + vertex 1.34463 0.887935 2.48058 + endloop + endfacet + facet normal 0.168642 -0.467686 0.867658 + outer loop + vertex 1.34704 0.890119 2.48129 + vertex 1.34382 0.890354 2.48205 + vertex 1.34463 0.887935 2.48058 + endloop + endfacet + facet normal 0.181142 -0.397998 0.899325 + outer loop + vertex 1.34704 0.890119 2.48129 + vertex 1.34852 0.893927 2.48268 + vertex 1.34382 0.890354 2.48205 + endloop + endfacet + facet normal 0.170735 -0.385641 0.906714 + outer loop + vertex 1.34852 0.893927 2.48268 + vertex 1.34336 0.893973 2.48367 + vertex 1.34382 0.890354 2.48205 + endloop + endfacet + facet normal 0.00160895 0.999769 0.021442 + outer loop + vertex 1.35 0.98747 2.495 + vertex 1.345 0.987478 2.495 + vertex 1.34971 0.98743 2.49689 + endloop + endfacet + facet normal -0.106919 0.950628 0.291332 + outer loop + vertex 1.34971 0.98743 2.49689 + vertex 1.345 0.987478 2.495 + vertex 1.3447 0.986532 2.49797 + endloop + endfacet + facet normal -0.16576 0.984985 0.0482522 + outer loop + vertex 1.34971 0.98743 2.49689 + vertex 1.3447 0.986532 2.49797 + vertex 1.34821 0.986952 2.50148 + endloop + endfacet + facet normal -0.157197 0.986779 0.0394534 + outer loop + vertex 1.34821 0.986952 2.50148 + vertex 1.3447 0.986532 2.49797 + vertex 1.34337 0.986174 2.50166 + endloop + endfacet + facet normal -0.150188 0.973318 0.173481 + outer loop + vertex 1.34821 0.986952 2.50148 + vertex 1.34337 0.986174 2.50166 + vertex 1.34792 0.986172 2.50561 + endloop + endfacet + facet normal -0.109068 0.986003 0.126102 + outer loop + vertex 1.34792 0.986172 2.50561 + vertex 1.34337 0.986174 2.50166 + vertex 1.34309 0.985606 2.50586 + endloop + endfacet + facet normal -0.089664 0.927037 0.364091 + outer loop + vertex 1.34792 0.986172 2.50561 + vertex 1.34309 0.985606 2.50586 + vertex 1.34765 0.984814 2.509 + endloop + endfacet + facet normal -0.0868042 0.928761 0.360372 + outer loop + vertex 1.34765 0.984814 2.509 + vertex 1.34309 0.985606 2.50586 + vertex 1.34275 0.984253 2.50926 + endloop + endfacet + facet normal -0.0402936 0.682724 0.729564 + outer loop + vertex 1.34663 0.982503 2.51112 + vertex 1.34275 0.984253 2.50926 + vertex 1.34128 0.982055 2.51124 + endloop + endfacet + facet normal -0.0389165 0.684298 0.728164 + outer loop + vertex 1.34765 0.984814 2.509 + vertex 1.34275 0.984253 2.50926 + vertex 1.34663 0.982503 2.51112 + endloop + endfacet + facet normal -0.644806 -0.610909 -0.459364 + outer loop + vertex 1.3485 2.03678 2.49665 + vertex 1.34773 2.03707 2.49734 + vertex 1.34793 2.03787 2.496 + endloop + endfacet + facet normal -0.150861 -0.958183 0.24316 + outer loop + vertex 1.3485 2.03678 2.49665 + vertex 1.34914 2.03685 2.49733 + vertex 1.34773 2.03707 2.49734 + endloop + endfacet + facet normal -0.411102 -0.756328 -0.508884 + outer loop + vertex 1.34793 2.03787 2.496 + vertex 1.34773 2.03707 2.49734 + vertex 1.345 2.03902 2.49666 + endloop + endfacet + facet normal -0.254832 -0.0942595 -0.96238 + outer loop + vertex 1.34793 2.03787 2.496 + vertex 1.345 2.03902 2.49666 + vertex 1.35 2.04246 2.495 + endloop + endfacet + facet normal -0.00514862 -0.42847 -0.903542 + outer loop + vertex 1.35 2.04246 2.495 + vertex 1.345 2.03902 2.49666 + vertex 1.345 2.04252 2.495 + endloop + endfacet + facet normal -0.152555 -0.966722 0.205367 + outer loop + vertex 1.34773 2.03707 2.49734 + vertex 1.34914 2.03685 2.49733 + vertex 1.34827 2.03759 2.50017 + endloop + endfacet + facet normal -0.602224 -0.757025 0.253455 + outer loop + vertex 1.34773 2.03707 2.49734 + vertex 1.34827 2.03759 2.50017 + vertex 1.345 2.03902 2.49666 + endloop + endfacet + facet normal -0.196253 -0.958563 -0.206499 + outer loop + vertex 1.345 2.03902 2.49666 + vertex 1.34827 2.03759 2.50017 + vertex 1.34302 2.03843 2.50127 + endloop + endfacet + facet normal -0.0964667 -0.958319 0.268921 + outer loop + vertex 1.34827 2.03759 2.50017 + vertex 1.34546 2.0395 2.50599 + vertex 1.34302 2.03843 2.50127 + endloop + endfacet + facet normal 0.0926188 -0.979999 0.176135 + outer loop + vertex 1.34546 2.0395 2.50599 + vertex 1.34108 2.03892 2.50506 + vertex 1.34302 2.03843 2.50127 + endloop + endfacet + facet normal 0.418016 -0.706189 0.571454 + outer loop + vertex 1.34417 2.04174 2.5097 + vertex 1.34546 2.0395 2.50599 + vertex 1.34821 2.04336 2.50874 + endloop + endfacet + facet normal 0.17755 -0.814007 0.553054 + outer loop + vertex 1.34417 2.04174 2.5097 + vertex 1.34068 2.04042 2.50887 + vertex 1.34546 2.0395 2.50599 + endloop + endfacet + facet normal 0.0446606 -0.928261 0.369239 + outer loop + vertex 1.34068 2.04042 2.50887 + vertex 1.34108 2.03892 2.50506 + vertex 1.34546 2.0395 2.50599 + endloop + endfacet + facet normal 0.0955963 -0.696003 0.711647 + outer loop + vertex 1.34417 2.04174 2.5097 + vertex 1.34113 2.04289 2.51122 + vertex 1.34068 2.04042 2.50887 + endloop + endfacet + facet normal 0.165059 0.332157 0.92867 + outer loop + vertex 1.34857 2.12692 2.48433 + vertex 1.34613 2.13187 2.48299 + vertex 1.34291 2.12863 2.48472 + endloop + endfacet + facet normal 0.170616 0.327063 0.929473 + outer loop + vertex 1.34291 2.12863 2.48472 + vertex 1.34613 2.13187 2.48299 + vertex 1.34237 2.1319 2.48367 + endloop + endfacet + facet normal 0.202067 0.497455 0.843628 + outer loop + vertex 1.3494 2.13447 2.48123 + vertex 1.34671 2.13793 2.47983 + vertex 1.34547 2.13554 2.48154 + endloop + endfacet + facet normal 0.177767 0.390457 0.903295 + outer loop + vertex 1.34547 2.13554 2.48154 + vertex 1.34613 2.13187 2.48299 + vertex 1.3494 2.13447 2.48123 + endloop + endfacet + facet normal 0.166655 0.389472 0.905836 + outer loop + vertex 1.34547 2.13554 2.48154 + vertex 1.34163 2.13496 2.48249 + vertex 1.34613 2.13187 2.48299 + endloop + endfacet + facet normal 0.166774 0.38963 0.905746 + outer loop + vertex 1.34163 2.13496 2.48249 + vertex 1.34237 2.1319 2.48367 + vertex 1.34613 2.13187 2.48299 + endloop + endfacet + facet normal 0.19398 0.501355 0.843217 + outer loop + vertex 1.3431 2.13778 2.48075 + vertex 1.34547 2.13554 2.48154 + vertex 1.34671 2.13793 2.47983 + endloop + endfacet + facet normal 0.174103 0.599716 0.781044 + outer loop + vertex 1.3431 2.13778 2.48075 + vertex 1.34671 2.13793 2.47983 + vertex 1.34246 2.14079 2.47858 + endloop + endfacet + facet normal 0.193447 0.61951 0.760779 + outer loop + vertex 1.34246 2.14079 2.47858 + vertex 1.34671 2.13793 2.47983 + vertex 1.34755 2.14064 2.47741 + endloop + endfacet + facet normal 0.147741 0.463104 0.873903 + outer loop + vertex 1.34547 2.13554 2.48154 + vertex 1.3431 2.13778 2.48075 + vertex 1.34163 2.13496 2.48249 + endloop + endfacet + facet normal 0.199105 0.836785 0.510047 + outer loop + vertex 1.34417 2.14536 2.47272 + vertex 1.34855 2.14528 2.47115 + vertex 1.34591 2.14709 2.4692 + endloop + endfacet + facet normal 0.205223 0.834223 0.511815 + outer loop + vertex 1.34225 2.14736 2.47022 + vertex 1.34417 2.14536 2.47272 + vertex 1.34591 2.14709 2.4692 + endloop + endfacet + facet normal 0.211602 0.810495 0.546189 + outer loop + vertex 1.34855 2.14528 2.47115 + vertex 1.34417 2.14536 2.47272 + vertex 1.34882 2.1431 2.47427 + endloop + endfacet + facet normal 0.189391 0.789946 0.583195 + outer loop + vertex 1.34882 2.1431 2.47427 + vertex 1.34417 2.14536 2.47272 + vertex 1.34443 2.14301 2.47581 + endloop + endfacet + facet normal 0.179867 0.700543 0.69057 + outer loop + vertex 1.34755 2.14064 2.47741 + vertex 1.34443 2.14301 2.47581 + vertex 1.34246 2.14079 2.47858 + endloop + endfacet + facet normal 0.215984 0.72414 0.654959 + outer loop + vertex 1.34882 2.1431 2.47427 + vertex 1.34443 2.14301 2.47581 + vertex 1.34755 2.14064 2.47741 + endloop + endfacet + facet normal 0.033108 0.236486 0.971071 + outer loop + vertex 1.35 2.1536 2.465 + vertex 1.345 2.1543 2.465 + vertex 1.34756 2.14934 2.46612 + endloop + endfacet + facet normal 0.234872 0.328188 0.914947 + outer loop + vertex 1.34756 2.14934 2.46612 + vertex 1.345 2.1543 2.465 + vertex 1.34301 2.14923 2.46733 + endloop + endfacet + facet normal 0.218104 0.792699 0.569261 + outer loop + vertex 1.34591 2.14709 2.4692 + vertex 1.34301 2.14923 2.46733 + vertex 1.34225 2.14736 2.47022 + endloop + endfacet + facet normal 0.150113 0.757955 0.6348 + outer loop + vertex 1.34756 2.14934 2.46612 + vertex 1.34301 2.14923 2.46733 + vertex 1.34591 2.14709 2.4692 + endloop + endfacet + facet normal 0.240616 0.564505 0.789581 + outer loop + vertex 1.35151 0.878705 2.46568 + vertex 1.355 0.878172 2.465 + vertex 1.35541 0.87912 2.4642 + endloop + endfacet + facet normal 0.107524 -0.439008 0.892026 + outer loop + vertex 1.35151 0.878705 2.46568 + vertex 1.34757 0.877789 2.46571 + vertex 1.355 0.878172 2.465 + endloop + endfacet + facet normal 0.0868634 -0.901141 0.424736 + outer loop + vertex 1.34757 0.877789 2.46571 + vertex 1.35 0.87769 2.465 + vertex 1.355 0.878172 2.465 + endloop + endfacet + facet normal 0.211344 -0.898884 0.383852 + outer loop + vertex 1.35151 0.878705 2.46568 + vertex 1.34881 0.879034 2.46794 + vertex 1.34757 0.877789 2.46571 + endloop + endfacet + facet normal 0.239417 -0.89351 0.379894 + outer loop + vertex 1.35541 0.87912 2.4642 + vertex 1.35285 0.88015 2.46823 + vertex 1.35151 0.878705 2.46568 + endloop + endfacet + facet normal 0.218213 -0.893993 0.391356 + outer loop + vertex 1.34881 0.879034 2.46794 + vertex 1.35151 0.878705 2.46568 + vertex 1.35285 0.88015 2.46823 + endloop + endfacet + facet normal 0.212882 -0.882184 0.420039 + outer loop + vertex 1.34881 0.879034 2.46794 + vertex 1.35285 0.88015 2.46823 + vertex 1.34786 0.880353 2.47119 + endloop + endfacet + facet normal 0.222472 -0.872238 0.435553 + outer loop + vertex 1.34786 0.880353 2.47119 + vertex 1.35285 0.88015 2.46823 + vertex 1.35163 0.881976 2.47252 + endloop + endfacet + facet normal 0.200295 -0.811827 0.548469 + outer loop + vertex 1.35095 0.88365 2.47524 + vertex 1.35163 0.881976 2.47252 + vertex 1.35469 0.883735 2.474 + endloop + endfacet + facet normal 0.184512 -0.816326 0.547328 + outer loop + vertex 1.35095 0.88365 2.47524 + vertex 1.34676 0.882598 2.47508 + vertex 1.35163 0.881976 2.47252 + endloop + endfacet + facet normal 0.172401 -0.831528 0.528052 + outer loop + vertex 1.34676 0.882598 2.47508 + vertex 1.34786 0.880353 2.47119 + vertex 1.35163 0.881976 2.47252 + endloop + endfacet + facet normal 0.15446 -0.716184 0.680604 + outer loop + vertex 1.35095 0.88365 2.47524 + vertex 1.34928 0.885364 2.47742 + vertex 1.34676 0.882598 2.47508 + endloop + endfacet + facet normal 0.231278 -0.725803 0.647858 + outer loop + vertex 1.35469 0.883735 2.474 + vertex 1.3531 0.885345 2.47637 + vertex 1.35095 0.88365 2.47524 + endloop + endfacet + facet normal 0.186595 -0.69825 0.691108 + outer loop + vertex 1.3531 0.885345 2.47637 + vertex 1.34928 0.885364 2.47742 + vertex 1.35095 0.88365 2.47524 + endloop + endfacet + facet normal 0.208788 -0.60283 0.770068 + outer loop + vertex 1.3531 0.885345 2.47637 + vertex 1.35375 0.888609 2.47875 + vertex 1.34928 0.885364 2.47742 + endloop + endfacet + facet normal 0.207298 -0.601401 0.771585 + outer loop + vertex 1.35375 0.888609 2.47875 + vertex 1.3481 0.887891 2.47971 + vertex 1.34928 0.885364 2.47742 + endloop + endfacet + facet normal 0.206133 -0.497922 0.842367 + outer loop + vertex 1.3481 0.887891 2.47971 + vertex 1.35375 0.888609 2.47875 + vertex 1.35086 0.891179 2.48098 + endloop + endfacet + facet normal 0.207892 -0.498987 0.841305 + outer loop + vertex 1.34704 0.890119 2.48129 + vertex 1.3481 0.887891 2.47971 + vertex 1.35086 0.891179 2.48098 + endloop + endfacet + facet normal 0.184872 -0.399007 0.898118 + outer loop + vertex 1.35086 0.891179 2.48098 + vertex 1.34852 0.893927 2.48268 + vertex 1.34704 0.890119 2.48129 + endloop + endfacet + facet normal 0.171616 -0.409129 0.896192 + outer loop + vertex 1.35381 0.894898 2.48211 + vertex 1.34852 0.893927 2.48268 + vertex 1.35086 0.891179 2.48098 + endloop + endfacet + facet normal -0.37664 0.12739 -0.917559 + outer loop + vertex 1.35319 0.988214 2.49578 + vertex 1.35584 0.988719 2.49476 + vertex 1.355 0.987943 2.495 + endloop + endfacet + facet normal -0.34668 0.27098 -0.897988 + outer loop + vertex 1.35319 0.988214 2.49578 + vertex 1.355 0.987943 2.495 + vertex 1.34971 0.98743 2.49689 + endloop + endfacet + facet normal -0.0941819 0.995532 0.00676926 + outer loop + vertex 1.34971 0.98743 2.49689 + vertex 1.355 0.987943 2.495 + vertex 1.35 0.98747 2.495 + endloop + endfacet + facet normal -0.238589 0.968991 -0.0642757 + outer loop + vertex 1.35292 0.988307 2.49818 + vertex 1.35319 0.988214 2.49578 + vertex 1.34971 0.98743 2.49689 + endloop + endfacet + facet normal -0.307535 0.94347 0.123638 + outer loop + vertex 1.35292 0.988307 2.49818 + vertex 1.34971 0.98743 2.49689 + vertex 1.35277 0.987797 2.50168 + endloop + endfacet + facet normal -0.18395 0.982038 0.0420077 + outer loop + vertex 1.35277 0.987797 2.50168 + vertex 1.34971 0.98743 2.49689 + vertex 1.34821 0.986952 2.50148 + endloop + endfacet + facet normal -0.187222 0.957046 0.221384 + outer loop + vertex 1.35277 0.987797 2.50168 + vertex 1.34821 0.986952 2.50148 + vertex 1.35169 0.986808 2.50504 + endloop + endfacet + facet normal -0.138524 0.974848 0.174593 + outer loop + vertex 1.35169 0.986808 2.50504 + vertex 1.34821 0.986952 2.50148 + vertex 1.34792 0.986172 2.50561 + endloop + endfacet + facet normal -0.0812641 0.885448 0.457578 + outer loop + vertex 1.35169 0.986808 2.50504 + vertex 1.34792 0.986172 2.50561 + vertex 1.35251 0.985095 2.50851 + endloop + endfacet + facet normal -0.0161965 0.928642 0.370624 + outer loop + vertex 1.35251 0.985095 2.50851 + vertex 1.34792 0.986172 2.50561 + vertex 1.34765 0.984814 2.509 + endloop + endfacet + facet normal -0.0634178 0.689217 0.721774 + outer loop + vertex 1.3506 0.983453 2.51056 + vertex 1.34765 0.984814 2.509 + vertex 1.34663 0.982503 2.51112 + endloop + endfacet + facet normal 0.0198033 0.77133 0.636128 + outer loop + vertex 1.35251 0.985095 2.50851 + vertex 1.34765 0.984814 2.509 + vertex 1.3506 0.983453 2.51056 + endloop + endfacet + facet normal -0.21998 0.971362 -0.0898002 + outer loop + vertex 1.35584 0.988719 2.49476 + vertex 1.35319 0.988214 2.49578 + vertex 1.35595 0.988986 2.49738 + endloop + endfacet + facet normal -0.23462 0.969987 -0.0638675 + outer loop + vertex 1.35595 0.988986 2.49738 + vertex 1.35319 0.988214 2.49578 + vertex 1.35292 0.988307 2.49818 + endloop + endfacet + facet normal -0.0889998 -0.545061 -0.833659 + outer loop + vertex 1.34935 2.03765 2.49599 + vertex 1.3485 2.03678 2.49665 + vertex 1.34793 2.03787 2.496 + endloop + endfacet + facet normal 0.499491 -0.776668 -0.383791 + outer loop + vertex 1.34935 2.03765 2.49599 + vertex 1.34914 2.03685 2.49733 + vertex 1.3485 2.03678 2.49665 + endloop + endfacet + facet normal -0.0353304 -0.196775 -0.979812 + outer loop + vertex 1.34935 2.03765 2.49599 + vertex 1.34793 2.03787 2.496 + vertex 1.35 2.04246 2.495 + endloop + endfacet + facet normal 0.262428 -0.228272 -0.937563 + outer loop + vertex 1.34935 2.03765 2.49599 + vertex 1.35 2.04246 2.495 + vertex 1.35212 2.03795 2.49669 + endloop + endfacet + facet normal -0.0771438 -0.381922 -0.920969 + outer loop + vertex 1.35212 2.03795 2.49669 + vertex 1.35 2.04246 2.495 + vertex 1.355 2.04145 2.495 + endloop + endfacet + facet normal 0.214758 -0.853779 -0.474278 + outer loop + vertex 1.34914 2.03685 2.49733 + vertex 1.34935 2.03765 2.49599 + vertex 1.35212 2.03795 2.49669 + endloop + endfacet + facet normal 0.39054 -0.854485 0.342541 + outer loop + vertex 1.34914 2.03685 2.49733 + vertex 1.35212 2.03795 2.49669 + vertex 1.34827 2.03759 2.50017 + endloop + endfacet + facet normal -0.0924397 -0.974544 -0.204252 + outer loop + vertex 1.34827 2.03759 2.50017 + vertex 1.35212 2.03795 2.49669 + vertex 1.35251 2.03708 2.5007 + endloop + endfacet + facet normal -0.154728 -0.928192 0.338406 + outer loop + vertex 1.35251 2.03708 2.5007 + vertex 1.35144 2.03882 2.50501 + vertex 1.34827 2.03759 2.50017 + endloop + endfacet + facet normal -0.0621763 -0.95654 0.284896 + outer loop + vertex 1.35144 2.03882 2.50501 + vertex 1.34546 2.0395 2.50599 + vertex 1.34827 2.03759 2.50017 + endloop + endfacet + facet normal 0.0604931 -0.608452 0.791281 + outer loop + vertex 1.35144 2.03882 2.50501 + vertex 1.34821 2.04336 2.50874 + vertex 1.34546 2.0395 2.50599 + endloop + endfacet + facet normal -0.0533216 -0.657161 0.751862 + outer loop + vertex 1.35478 2.04199 2.50802 + vertex 1.34821 2.04336 2.50874 + vertex 1.35144 2.03882 2.50501 + endloop + endfacet + facet normal 0.101888 -0.0386293 0.994046 + outer loop + vertex 1.35478 2.04199 2.50802 + vertex 1.35271 2.04692 2.50842 + vertex 1.34821 2.04336 2.50874 + endloop + endfacet + facet normal 0.152508 0.332825 0.930575 + outer loop + vertex 1.35244 2.12694 2.48369 + vertex 1.35184 2.13023 2.48261 + vertex 1.34857 2.12692 2.48433 + endloop + endfacet + facet normal 0.156915 0.32883 0.931262 + outer loop + vertex 1.34857 2.12692 2.48433 + vertex 1.35184 2.13023 2.48261 + vertex 1.34613 2.13187 2.48299 + endloop + endfacet + facet normal 0.190723 0.506894 0.840644 + outer loop + vertex 1.3494 2.13447 2.48123 + vertex 1.35348 2.1334 2.48094 + vertex 1.35218 2.13732 2.47888 + endloop + endfacet + facet normal 0.202494 0.49769 0.843387 + outer loop + vertex 1.34671 2.13793 2.47983 + vertex 1.3494 2.13447 2.48123 + vertex 1.35218 2.13732 2.47888 + endloop + endfacet + facet normal 0.173828 0.394688 0.902222 + outer loop + vertex 1.35184 2.13023 2.48261 + vertex 1.3494 2.13447 2.48123 + vertex 1.34613 2.13187 2.48299 + endloop + endfacet + facet normal 0.164758 0.390588 0.905702 + outer loop + vertex 1.35348 2.1334 2.48094 + vertex 1.3494 2.13447 2.48123 + vertex 1.35184 2.13023 2.48261 + endloop + endfacet + facet normal 0.2155 0.725088 0.654069 + outer loop + vertex 1.35468 2.13964 2.47636 + vertex 1.35287 2.14184 2.47452 + vertex 1.35114 2.14063 2.47643 + endloop + endfacet + facet normal 0.18861 0.621505 0.760367 + outer loop + vertex 1.35114 2.14063 2.47643 + vertex 1.35218 2.13732 2.47888 + vertex 1.35468 2.13964 2.47636 + endloop + endfacet + facet normal 0.207431 0.622925 0.754279 + outer loop + vertex 1.35114 2.14063 2.47643 + vertex 1.34755 2.14064 2.47741 + vertex 1.35218 2.13732 2.47888 + endloop + endfacet + facet normal 0.201183 0.617074 0.760753 + outer loop + vertex 1.34755 2.14064 2.47741 + vertex 1.34671 2.13793 2.47983 + vertex 1.35218 2.13732 2.47888 + endloop + endfacet + facet normal 0.219637 0.83287 0.508023 + outer loop + vertex 1.34855 2.14528 2.47115 + vertex 1.35361 2.14401 2.47103 + vertex 1.35038 2.14659 2.4682 + endloop + endfacet + facet normal 0.206362 0.839464 0.502707 + outer loop + vertex 1.34591 2.14709 2.4692 + vertex 1.34855 2.14528 2.47115 + vertex 1.35038 2.14659 2.4682 + endloop + endfacet + facet normal 0.191333 0.74182 0.642725 + outer loop + vertex 1.35287 2.14184 2.47452 + vertex 1.34882 2.1431 2.47427 + vertex 1.35114 2.14063 2.47643 + endloop + endfacet + facet normal 0.217531 0.807164 0.548787 + outer loop + vertex 1.35287 2.14184 2.47452 + vertex 1.35361 2.14401 2.47103 + vertex 1.34882 2.1431 2.47427 + endloop + endfacet + facet normal 0.21482 0.81005 0.545592 + outer loop + vertex 1.35361 2.14401 2.47103 + vertex 1.34855 2.14528 2.47115 + vertex 1.34882 2.1431 2.47427 + endloop + endfacet + facet normal 0.179379 0.737735 0.650823 + outer loop + vertex 1.35114 2.14063 2.47643 + vertex 1.34882 2.1431 2.47427 + vertex 1.34755 2.14064 2.47741 + endloop + endfacet + facet normal 0.0118051 0.0412755 0.999078 + outer loop + vertex 1.355 2.15217 2.465 + vertex 1.35 2.1536 2.465 + vertex 1.35292 2.14883 2.46516 + endloop + endfacet + facet normal 0.187574 0.148116 0.971019 + outer loop + vertex 1.35292 2.14883 2.46516 + vertex 1.35 2.1536 2.465 + vertex 1.34756 2.14934 2.46612 + endloop + endfacet + facet normal 0.226834 0.724122 0.651301 + outer loop + vertex 1.35038 2.14659 2.4682 + vertex 1.34756 2.14934 2.46612 + vertex 1.34591 2.14709 2.4692 + endloop + endfacet + facet normal 0.188833 0.707618 0.680896 + outer loop + vertex 1.35292 2.14883 2.46516 + vertex 1.34756 2.14934 2.46612 + vertex 1.35038 2.14659 2.4682 + endloop + endfacet + facet normal -0.325797 -0.887532 -0.325797 + outer loop + vertex 1.35502 0.88 2.46 + vertex 1.355 0.878172 2.465 + vertex 1.355 0.88 2.46002 + endloop + endfacet + facet normal -0.307291 -0.893356 -0.327853 + outer loop + vertex 1.35502 0.88 2.46 + vertex 1.36 0.878287 2.46 + vertex 1.355 0.878172 2.465 + endloop + endfacet + facet normal 0.702263 -0.133972 0.699198 + outer loop + vertex 1.36 0.878287 2.46 + vertex 1.35853 0.878782 2.46157 + vertex 1.355 0.878172 2.465 + endloop + endfacet + facet normal 0.629476 0.324673 0.705938 + outer loop + vertex 1.35853 0.878782 2.46157 + vertex 1.35541 0.87912 2.4642 + vertex 1.355 0.878172 2.465 + endloop + endfacet + facet normal 0.215771 -0.902629 0.37243 + outer loop + vertex 1.35915 0.879641 2.4633 + vertex 1.35541 0.87912 2.4642 + vertex 1.35853 0.878782 2.46157 + endloop + endfacet + facet normal 0.21336 -0.908647 0.358939 + outer loop + vertex 1.35541 0.87912 2.4642 + vertex 1.35915 0.879641 2.4633 + vertex 1.35824 0.880471 2.46594 + endloop + endfacet + facet normal 0.209395 -0.907395 0.364401 + outer loop + vertex 1.35285 0.88015 2.46823 + vertex 1.35541 0.87912 2.4642 + vertex 1.35824 0.880471 2.46594 + endloop + endfacet + facet normal 0.222298 -0.890477 0.397032 + outer loop + vertex 1.35824 0.880471 2.46594 + vertex 1.35691 0.882085 2.4703 + vertex 1.35285 0.88015 2.46823 + endloop + endfacet + facet normal 0.19927 -0.879562 0.432045 + outer loop + vertex 1.35691 0.882085 2.4703 + vertex 1.35163 0.881976 2.47252 + vertex 1.35285 0.88015 2.46823 + endloop + endfacet + facet normal 0.230176 -0.829907 0.508206 + outer loop + vertex 1.35691 0.882085 2.4703 + vertex 1.35469 0.883735 2.474 + vertex 1.35163 0.881976 2.47252 + endloop + endfacet + facet normal 0.195873 -0.846511 0.495028 + outer loop + vertex 1.35849 0.883969 2.4729 + vertex 1.35469 0.883735 2.474 + vertex 1.35691 0.882085 2.4703 + endloop + endfacet + facet normal 0.230792 -0.733644 0.639142 + outer loop + vertex 1.35469 0.883735 2.474 + vertex 1.35849 0.883969 2.4729 + vertex 1.35762 0.886144 2.47571 + endloop + endfacet + facet normal 0.223924 -0.729978 0.645748 + outer loop + vertex 1.3531 0.885345 2.47637 + vertex 1.35469 0.883735 2.474 + vertex 1.35762 0.886144 2.47571 + endloop + endfacet + facet normal 0.219321 -0.60281 0.76715 + outer loop + vertex 1.35762 0.886144 2.47571 + vertex 1.35375 0.888609 2.47875 + vertex 1.3531 0.885345 2.47637 + endloop + endfacet + facet normal 0.192267 -0.628581 0.753604 + outer loop + vertex 1.3596 0.889506 2.47801 + vertex 1.35375 0.888609 2.47875 + vertex 1.35762 0.886144 2.47571 + endloop + endfacet + facet normal 0.193764 -0.508752 0.838825 + outer loop + vertex 1.35463 0.892262 2.48076 + vertex 1.35086 0.891179 2.48098 + vertex 1.35375 0.888609 2.47875 + endloop + endfacet + facet normal 0.17491 -0.507039 0.843989 + outer loop + vertex 1.35463 0.892262 2.48076 + vertex 1.35375 0.888609 2.47875 + vertex 1.35801 0.892239 2.48005 + endloop + endfacet + facet normal 0.185581 -0.516658 0.835838 + outer loop + vertex 1.35801 0.892239 2.48005 + vertex 1.35375 0.888609 2.47875 + vertex 1.3596 0.889506 2.47801 + endloop + endfacet + facet normal 0.167835 -0.40669 0.898017 + outer loop + vertex 1.35463 0.892262 2.48076 + vertex 1.35381 0.894898 2.48211 + vertex 1.35086 0.891179 2.48098 + endloop + endfacet + facet normal 0.183841 -0.430223 0.883805 + outer loop + vertex 1.35801 0.892239 2.48005 + vertex 1.35716 0.894754 2.48145 + vertex 1.35463 0.892262 2.48076 + endloop + endfacet + facet normal 0.159422 -0.409466 0.898288 + outer loop + vertex 1.35716 0.894754 2.48145 + vertex 1.35381 0.894898 2.48211 + vertex 1.35463 0.892262 2.48076 + endloop + endfacet + facet normal 0.165561 -0.359109 0.918494 + outer loop + vertex 1.35716 0.894754 2.48145 + vertex 1.35866 0.898766 2.48275 + vertex 1.35381 0.894898 2.48211 + endloop + endfacet + facet normal 0.207569 -0.483343 -0.850468 + outer loop + vertex 1.35979 0.99 2.495 + vertex 1.355 0.987943 2.495 + vertex 1.35584 0.988719 2.49476 + endloop + endfacet + facet normal -0.30316 0.944833 0.124032 + outer loop + vertex 1.35513 0.988726 2.50037 + vertex 1.35292 0.988307 2.49818 + vertex 1.35277 0.987797 2.50168 + endloop + endfacet + facet normal -0.24397 0.942403 0.228814 + outer loop + vertex 1.35644 0.988394 2.50314 + vertex 1.35513 0.988726 2.50037 + vertex 1.35277 0.987797 2.50168 + endloop + endfacet + facet normal -0.306288 0.852954 0.42268 + outer loop + vertex 1.35644 0.988394 2.50314 + vertex 1.35277 0.987797 2.50168 + vertex 1.35611 0.986811 2.5061 + endloop + endfacet + facet normal -0.0631649 0.962753 0.262899 + outer loop + vertex 1.35611 0.986811 2.5061 + vertex 1.35277 0.987797 2.50168 + vertex 1.35169 0.986808 2.50504 + endloop + endfacet + facet normal 0.142624 0.603193 0.78474 + outer loop + vertex 1.35716 0.983251 2.50908 + vertex 1.35251 0.985095 2.50851 + vertex 1.35324 0.98253 2.51034 + endloop + endfacet + facet normal 0.172752 0.661895 0.729418 + outer loop + vertex 1.35716 0.983251 2.50908 + vertex 1.35611 0.986811 2.5061 + vertex 1.35251 0.985095 2.50851 + endloop + endfacet + facet normal -0.110374 0.880066 0.461846 + outer loop + vertex 1.35611 0.986811 2.5061 + vertex 1.35169 0.986808 2.50504 + vertex 1.35251 0.985095 2.50851 + endloop + endfacet + facet normal 0.272539 0.610665 0.743512 + outer loop + vertex 1.35324 0.98253 2.51034 + vertex 1.35251 0.985095 2.50851 + vertex 1.3506 0.983453 2.51056 + endloop + endfacet + facet normal 0.535205 -0.261389 0.803263 + outer loop + vertex 1.36 0.99 2.49486 + vertex 1.35979 0.99 2.495 + vertex 1.35927 0.989499 2.49518 + endloop + endfacet + facet normal -0.218995 0.523582 0.823349 + outer loop + vertex 1.35584 0.988719 2.49476 + vertex 1.35927 0.989499 2.49518 + vertex 1.35979 0.99 2.495 + endloop + endfacet + facet normal -0.210151 0.973477 -0.090442 + outer loop + vertex 1.35584 0.988719 2.49476 + vertex 1.35595 0.988986 2.49738 + vertex 1.35927 0.989499 2.49518 + endloop + endfacet + facet normal -0.178079 0.983218 -0.0396241 + outer loop + vertex 1.35595 0.988986 2.49738 + vertex 1.35981 0.989723 2.49832 + vertex 1.35927 0.989499 2.49518 + endloop + endfacet + facet normal -0.212121 0.976888 0.0263476 + outer loop + vertex 1.35513 0.988726 2.50037 + vertex 1.35595 0.988986 2.49738 + vertex 1.35292 0.988307 2.49818 + endloop + endfacet + facet normal -0.139859 0.98904 0.0473225 + outer loop + vertex 1.35513 0.988726 2.50037 + vertex 1.35883 0.989193 2.50155 + vertex 1.35595 0.988986 2.49738 + endloop + endfacet + facet normal -0.209257 0.973139 0.0959827 + outer loop + vertex 1.35883 0.989193 2.50155 + vertex 1.35981 0.989723 2.49832 + vertex 1.35595 0.988986 2.49738 + endloop + endfacet + facet normal -0.186057 0.96121 0.203613 + outer loop + vertex 1.35883 0.989193 2.50155 + vertex 1.35513 0.988726 2.50037 + vertex 1.35644 0.988394 2.50314 + endloop + endfacet + facet normal -0.357002 -0.00228337 -0.934101 + outer loop + vertex 1.36169 2.03726 2.49423 + vertex 1.35966 2.04 2.495 + vertex 1.36 2.04 2.49487 + endloop + endfacet + facet normal -0.750202 -0.411356 -0.517671 + outer loop + vertex 1.36014 2.03609 2.49741 + vertex 1.35966 2.04 2.495 + vertex 1.36169 2.03726 2.49423 + endloop + endfacet + facet normal -0.334836 -0.524483 -0.782817 + outer loop + vertex 1.35608 2.03669 2.49875 + vertex 1.35966 2.04 2.495 + vertex 1.36014 2.03609 2.49741 + endloop + endfacet + facet normal -0.188115 -0.972279 -0.138874 + outer loop + vertex 1.35902 2.03567 2.50191 + vertex 1.35608 2.03669 2.49875 + vertex 1.36014 2.03609 2.49741 + endloop + endfacet + facet normal -0.293637 -0.955263 -0.0353616 + outer loop + vertex 1.35538 2.03674 2.50318 + vertex 1.35608 2.03669 2.49875 + vertex 1.35902 2.03567 2.50191 + endloop + endfacet + facet normal -0.216509 -0.957743 0.189345 + outer loop + vertex 1.35868 2.03653 2.5059 + vertex 1.35538 2.03674 2.50318 + vertex 1.35902 2.03567 2.50191 + endloop + endfacet + facet normal -0.400978 -0.81153 0.425012 + outer loop + vertex 1.35571 2.03825 2.50638 + vertex 1.35538 2.03674 2.50318 + vertex 1.35868 2.03653 2.5059 + endloop + endfacet + facet normal -0.265195 -0.656888 0.705811 + outer loop + vertex 1.35868 2.03653 2.5059 + vertex 1.35925 2.03911 2.50851 + vertex 1.35571 2.03825 2.50638 + endloop + endfacet + facet normal 0.0728357 -0.78101 -0.620256 + outer loop + vertex 1.35966 2.04 2.495 + vertex 1.35608 2.03669 2.49875 + vertex 1.35212 2.03795 2.49669 + endloop + endfacet + facet normal -0.111113 -0.357081 -0.927441 + outer loop + vertex 1.355 2.04145 2.495 + vertex 1.35966 2.04 2.495 + vertex 1.35212 2.03795 2.49669 + endloop + endfacet + facet normal -0.111031 -0.9938 -0.00584504 + outer loop + vertex 1.35608 2.03669 2.49875 + vertex 1.35538 2.03674 2.50318 + vertex 1.35251 2.03708 2.5007 + endloop + endfacet + facet normal -0.208015 -0.959541 -0.189765 + outer loop + vertex 1.35212 2.03795 2.49669 + vertex 1.35608 2.03669 2.49875 + vertex 1.35251 2.03708 2.5007 + endloop + endfacet + facet normal -0.255065 -0.863842 0.434419 + outer loop + vertex 1.35538 2.03674 2.50318 + vertex 1.35571 2.03825 2.50638 + vertex 1.35144 2.03882 2.50501 + endloop + endfacet + facet normal -0.344914 -0.896434 0.278282 + outer loop + vertex 1.35251 2.03708 2.5007 + vertex 1.35538 2.03674 2.50318 + vertex 1.35144 2.03882 2.50501 + endloop + endfacet + facet normal -0.327884 -0.445259 0.833208 + outer loop + vertex 1.35571 2.03825 2.50638 + vertex 1.35478 2.04199 2.50802 + vertex 1.35144 2.03882 2.50501 + endloop + endfacet + facet normal -0.378471 -0.447787 0.81009 + outer loop + vertex 1.35571 2.03825 2.50638 + vertex 1.35925 2.03911 2.50851 + vertex 1.35478 2.04199 2.50802 + endloop + endfacet + facet normal -0.150604 -0.0642179 0.986506 + outer loop + vertex 1.35925 2.03911 2.50851 + vertex 1.35928 2.0429 2.50876 + vertex 1.35478 2.04199 2.50802 + endloop + endfacet + facet normal 0.0428116 -0.0636656 0.997053 + outer loop + vertex 1.35478 2.04199 2.50802 + vertex 1.35761 2.04645 2.50818 + vertex 1.35271 2.04692 2.50842 + endloop + endfacet + facet normal 0.173992 0.433293 0.884299 + outer loop + vertex 1.35987 2.12983 2.48138 + vertex 1.35754 2.13391 2.47984 + vertex 1.3559 2.13089 2.48164 + endloop + endfacet + facet normal 0.152988 0.344498 0.926237 + outer loop + vertex 1.3559 2.13089 2.48164 + vertex 1.35621 2.12705 2.48302 + vertex 1.35987 2.12983 2.48138 + endloop + endfacet + facet normal 0.163717 0.344689 0.92433 + outer loop + vertex 1.3559 2.13089 2.48164 + vertex 1.35184 2.13023 2.48261 + vertex 1.35621 2.12705 2.48302 + endloop + endfacet + facet normal 0.154695 0.33307 0.930126 + outer loop + vertex 1.35184 2.13023 2.48261 + vertex 1.35244 2.12694 2.48369 + vertex 1.35621 2.12705 2.48302 + endloop + endfacet + facet normal 0.186678 0.426741 0.884897 + outer loop + vertex 1.35348 2.1334 2.48094 + vertex 1.3559 2.13089 2.48164 + vertex 1.35754 2.13391 2.47984 + endloop + endfacet + facet normal 0.167131 0.502953 0.848001 + outer loop + vertex 1.35348 2.1334 2.48094 + vertex 1.35754 2.13391 2.47984 + vertex 1.35218 2.13732 2.47888 + endloop + endfacet + facet normal 0.190829 0.533464 0.824015 + outer loop + vertex 1.35218 2.13732 2.47888 + vertex 1.35754 2.13391 2.47984 + vertex 1.35688 2.13722 2.47785 + endloop + endfacet + facet normal 0.15059 0.397582 0.905125 + outer loop + vertex 1.3559 2.13089 2.48164 + vertex 1.35348 2.1334 2.48094 + vertex 1.35184 2.13023 2.48261 + endloop + endfacet + facet normal 0.212642 0.735478 0.643316 + outer loop + vertex 1.35468 2.13964 2.47636 + vertex 1.359 2.13898 2.47569 + vertex 1.35655 2.1414 2.47373 + endloop + endfacet + facet normal 0.225668 0.727912 0.64747 + outer loop + vertex 1.35287 2.14184 2.47452 + vertex 1.35468 2.13964 2.47636 + vertex 1.35655 2.1414 2.47373 + endloop + endfacet + facet normal 0.178251 0.628853 0.756816 + outer loop + vertex 1.35688 2.13722 2.47785 + vertex 1.35468 2.13964 2.47636 + vertex 1.35218 2.13732 2.47888 + endloop + endfacet + facet normal 0.213025 0.645882 0.733114 + outer loop + vertex 1.359 2.13898 2.47569 + vertex 1.35468 2.13964 2.47636 + vertex 1.35688 2.13722 2.47785 + endloop + endfacet + facet normal 0.172116 0.758188 0.628909 + outer loop + vertex 1.35892 2.14495 2.46738 + vertex 1.35716 2.14725 2.46509 + vertex 1.35445 2.1461 2.46721 + endloop + endfacet + facet normal 0.222809 0.833743 0.505202 + outer loop + vertex 1.35445 2.1461 2.46721 + vertex 1.35038 2.14659 2.4682 + vertex 1.35361 2.14401 2.47103 + endloop + endfacet + facet normal 0.198241 0.840844 0.503668 + outer loop + vertex 1.35445 2.1461 2.46721 + vertex 1.35361 2.14401 2.47103 + vertex 1.35892 2.14495 2.46738 + endloop + endfacet + facet normal 0.207848 0.831455 0.51525 + outer loop + vertex 1.35892 2.14495 2.46738 + vertex 1.35361 2.14401 2.47103 + vertex 1.3586 2.14281 2.47095 + endloop + endfacet + facet normal 0.21405 0.808167 0.548679 + outer loop + vertex 1.35655 2.1414 2.47373 + vertex 1.35361 2.14401 2.47103 + vertex 1.35287 2.14184 2.47452 + endloop + endfacet + facet normal 0.202101 0.804653 0.558291 + outer loop + vertex 1.3586 2.14281 2.47095 + vertex 1.35361 2.14401 2.47103 + vertex 1.35655 2.1414 2.47373 + endloop + endfacet + facet normal 0.262454 0.668403 0.695956 + outer loop + vertex 1.35716 2.14725 2.46509 + vertex 1.35292 2.14883 2.46516 + vertex 1.35445 2.1461 2.46721 + endloop + endfacet + facet normal 0.0201867 0.00764389 0.999767 + outer loop + vertex 1.35716 2.14725 2.46509 + vertex 1.36 2.15138 2.465 + vertex 1.35292 2.14883 2.46516 + endloop + endfacet + facet normal 0.00699322 0.0442675 0.998995 + outer loop + vertex 1.36 2.15138 2.465 + vertex 1.355 2.15217 2.465 + vertex 1.35292 2.14883 2.46516 + endloop + endfacet + facet normal 0.250575 0.666441 0.702188 + outer loop + vertex 1.35445 2.1461 2.46721 + vertex 1.35292 2.14883 2.46516 + vertex 1.35038 2.14659 2.4682 + endloop + endfacet + facet normal 0.249624 -0.885043 0.392921 + outer loop + vertex 1.36053 0.88 2.465 + vertex 1.365 0.879041 2.46 + vertex 1.365 0.88 2.46216 + endloop + endfacet + facet normal 0.105697 -0.954854 0.277637 + outer loop + vertex 1.36053 0.88 2.465 + vertex 1.35853 0.878782 2.46157 + vertex 1.365 0.879041 2.46 + endloop + endfacet + facet normal 0.135949 -0.901521 0.410825 + outer loop + vertex 1.35853 0.878782 2.46157 + vertex 1.36 0.878287 2.46 + vertex 1.365 0.879041 2.46 + endloop + endfacet + facet normal -0.458215 -0.718522 0.523226 + outer loop + vertex 1.36053 0.88 2.465 + vertex 1.35915 0.879641 2.4633 + vertex 1.35853 0.878782 2.46157 + endloop + endfacet + facet normal -0.317406 0.9465 0.0582409 + outer loop + vertex 1.35915 0.879641 2.4633 + vertex 1.36053 0.88 2.465 + vertex 1.365 0.881499 2.465 + endloop + endfacet + facet normal 0.18828 -0.916567 0.352782 + outer loop + vertex 1.35915 0.879641 2.4633 + vertex 1.365 0.881499 2.465 + vertex 1.35824 0.880471 2.46594 + endloop + endfacet + facet normal 0.191413 -0.898399 0.395273 + outer loop + vertex 1.35824 0.880471 2.46594 + vertex 1.365 0.881499 2.465 + vertex 1.36191 0.881916 2.46744 + endloop + endfacet + facet normal 0.206636 -0.881728 0.424096 + outer loop + vertex 1.36092 0.883229 2.47066 + vertex 1.36191 0.881916 2.46744 + vertex 1.36479 0.883465 2.46926 + endloop + endfacet + facet normal 0.213297 -0.87957 0.425278 + outer loop + vertex 1.36092 0.883229 2.47066 + vertex 1.35691 0.882085 2.4703 + vertex 1.36191 0.881916 2.46744 + endloop + endfacet + facet normal 0.193373 -0.89958 0.391616 + outer loop + vertex 1.35691 0.882085 2.4703 + vertex 1.35824 0.880471 2.46594 + vertex 1.36191 0.881916 2.46744 + endloop + endfacet + facet normal 0.197779 -0.846676 0.493987 + outer loop + vertex 1.36092 0.883229 2.47066 + vertex 1.35849 0.883969 2.4729 + vertex 1.35691 0.882085 2.4703 + endloop + endfacet + facet normal 0.238809 -0.817351 0.524316 + outer loop + vertex 1.36479 0.883465 2.46926 + vertex 1.36257 0.885211 2.47299 + vertex 1.36092 0.883229 2.47066 + endloop + endfacet + facet normal 0.236287 -0.817084 0.525874 + outer loop + vertex 1.35849 0.883969 2.4729 + vertex 1.36092 0.883229 2.47066 + vertex 1.36257 0.885211 2.47299 + endloop + endfacet + facet normal 0.2103 -0.740616 0.638171 + outer loop + vertex 1.35849 0.883969 2.4729 + vertex 1.36257 0.885211 2.47299 + vertex 1.35762 0.886144 2.47571 + endloop + endfacet + facet normal 0.217687 -0.729908 0.647956 + outer loop + vertex 1.35762 0.886144 2.47571 + vertex 1.36257 0.885211 2.47299 + vertex 1.36206 0.887603 2.47586 + endloop + endfacet + facet normal 0.179459 -0.625129 0.75961 + outer loop + vertex 1.36206 0.887603 2.47586 + vertex 1.3596 0.889506 2.47801 + vertex 1.35762 0.886144 2.47571 + endloop + endfacet + facet normal 0.19482 -0.612555 0.766043 + outer loop + vertex 1.36453 0.890272 2.47737 + vertex 1.3596 0.889506 2.47801 + vertex 1.36206 0.887603 2.47586 + endloop + endfacet + facet normal 0.18695 -0.515956 0.835966 + outer loop + vertex 1.3596 0.889506 2.47801 + vertex 1.36264 0.893009 2.47949 + vertex 1.35801 0.892239 2.48005 + endloop + endfacet + facet normal 0.183444 -0.430365 0.883818 + outer loop + vertex 1.35716 0.894754 2.48145 + vertex 1.35801 0.892239 2.48005 + vertex 1.36096 0.895838 2.48119 + endloop + endfacet + facet normal 0.165496 -0.359091 0.918512 + outer loop + vertex 1.36096 0.895838 2.48119 + vertex 1.35866 0.898766 2.48275 + vertex 1.35716 0.894754 2.48145 + endloop + endfacet + facet normal -0.223072 0.869512 0.440668 + outer loop + vertex 1.35923 0.98819 2.50496 + vertex 1.35644 0.988394 2.50314 + vertex 1.35611 0.986811 2.5061 + endloop + endfacet + facet normal -0.106523 0.765664 0.63436 + outer loop + vertex 1.35611 0.986811 2.5061 + vertex 1.361 0.986396 2.50742 + vertex 1.35923 0.98819 2.50496 + endloop + endfacet + facet normal -0.159219 0.606166 0.779238 + outer loop + vertex 1.35611 0.986811 2.5061 + vertex 1.35716 0.983251 2.50908 + vertex 1.361 0.986396 2.50742 + endloop + endfacet + facet normal 0.0499934 0.417753 0.907184 + outer loop + vertex 1.35716 0.983251 2.50908 + vertex 1.36266 0.98306 2.50886 + vertex 1.361 0.986396 2.50742 + endloop + endfacet + facet normal -0.073778 0.953336 -0.29276 + outer loop + vertex 1.36 0.99 2.49486 + vertex 1.36398 0.990201 2.49451 + vertex 1.365 0.99 2.4936 + endloop + endfacet + facet normal 0.0521398 0.484202 0.873402 + outer loop + vertex 1.35927 0.989499 2.49518 + vertex 1.36398 0.990201 2.49451 + vertex 1.36 0.99 2.49486 + endloop + endfacet + facet normal -0.151296 0.988084 -0.0282939 + outer loop + vertex 1.36398 0.990201 2.49451 + vertex 1.35927 0.989499 2.49518 + vertex 1.36348 0.990211 2.49756 + endloop + endfacet + facet normal -0.141212 0.988893 -0.0463576 + outer loop + vertex 1.36348 0.990211 2.49756 + vertex 1.35927 0.989499 2.49518 + vertex 1.35981 0.989723 2.49832 + endloop + endfacet + facet normal -0.115481 0.990166 0.0789653 + outer loop + vertex 1.36348 0.990211 2.49756 + vertex 1.35981 0.989723 2.49832 + vertex 1.36328 0.989876 2.50147 + endloop + endfacet + facet normal -0.148624 0.982085 0.115846 + outer loop + vertex 1.36328 0.989876 2.50147 + vertex 1.35981 0.989723 2.49832 + vertex 1.35883 0.989193 2.50155 + endloop + endfacet + facet normal -0.121921 0.948063 0.29379 + outer loop + vertex 1.35923 0.98819 2.50496 + vertex 1.35883 0.989193 2.50155 + vertex 1.35644 0.988394 2.50314 + endloop + endfacet + facet normal -0.114643 0.949139 0.293245 + outer loop + vertex 1.35923 0.98819 2.50496 + vertex 1.36278 0.988607 2.50499 + vertex 1.35883 0.989193 2.50155 + endloop + endfacet + facet normal -0.138182 0.937861 0.318313 + outer loop + vertex 1.36278 0.988607 2.50499 + vertex 1.36328 0.989876 2.50147 + vertex 1.35883 0.989193 2.50155 + endloop + endfacet + facet normal -0.0969203 0.770014 0.630623 + outer loop + vertex 1.36278 0.988607 2.50499 + vertex 1.35923 0.98819 2.50496 + vertex 1.361 0.986396 2.50742 + endloop + endfacet + facet normal 0.206778 -0.62256 -0.75476 + outer loop + vertex 1.36169 2.03726 2.49423 + vertex 1.365 2.04 2.49288 + vertex 1.365 2.03743 2.495 + endloop + endfacet + facet normal -0.369739 -0.0113343 -0.929066 + outer loop + vertex 1.36 2.04 2.49487 + vertex 1.365 2.04 2.49288 + vertex 1.36169 2.03726 2.49423 + endloop + endfacet + facet normal 0.187643 -0.738634 -0.647464 + outer loop + vertex 1.365 2.03743 2.495 + vertex 1.36405 2.03539 2.49705 + vertex 1.36169 2.03726 2.49423 + endloop + endfacet + facet normal -0.198143 -0.884735 -0.42188 + outer loop + vertex 1.36405 2.03539 2.49705 + vertex 1.36014 2.03609 2.49741 + vertex 1.36169 2.03726 2.49423 + endloop + endfacet + facet normal -0.187665 -0.972095 -0.140759 + outer loop + vertex 1.36405 2.03539 2.49705 + vertex 1.363 2.03499 2.50123 + vertex 1.36014 2.03609 2.49741 + endloop + endfacet + facet normal -0.189654 -0.97193 -0.139222 + outer loop + vertex 1.363 2.03499 2.50123 + vertex 1.35902 2.03567 2.50191 + vertex 1.36014 2.03609 2.49741 + endloop + endfacet + facet normal -0.157894 -0.985639 0.0598812 + outer loop + vertex 1.363 2.03499 2.50123 + vertex 1.36226 2.03536 2.50541 + vertex 1.35902 2.03567 2.50191 + endloop + endfacet + facet normal -0.28363 -0.941853 0.180186 + outer loop + vertex 1.36226 2.03536 2.50541 + vertex 1.35868 2.03653 2.5059 + vertex 1.35902 2.03567 2.50191 + endloop + endfacet + facet normal -0.450262 -0.484522 0.750002 + outer loop + vertex 1.35925 2.03911 2.50851 + vertex 1.36197 2.03659 2.50852 + vertex 1.36268 2.03822 2.50999 + endloop + endfacet + facet normal -0.512995 -0.552741 0.656745 + outer loop + vertex 1.35925 2.03911 2.50851 + vertex 1.35868 2.03653 2.5059 + vertex 1.36197 2.03659 2.50852 + endloop + endfacet + facet normal -0.251032 -0.907567 0.336607 + outer loop + vertex 1.35868 2.03653 2.5059 + vertex 1.36226 2.03536 2.50541 + vertex 1.36197 2.03659 2.50852 + endloop + endfacet + facet normal -0.483637 -0.46334 0.742571 + outer loop + vertex 1.36197 2.03659 2.50852 + vertex 1.36439 2.03685 2.51025 + vertex 1.36268 2.03822 2.50999 + endloop + endfacet + facet normal -0.248775 0.181923 0.951323 + outer loop + vertex 1.36268 2.03822 2.50999 + vertex 1.36562 2.03861 2.51069 + vertex 1.36338 2.04159 2.50953 + endloop + endfacet + facet normal -0.345143 0.197529 0.917529 + outer loop + vertex 1.36268 2.03822 2.50999 + vertex 1.36338 2.04159 2.50953 + vertex 1.35925 2.03911 2.50851 + endloop + endfacet + facet normal -0.203596 -0.0632164 0.977012 + outer loop + vertex 1.35925 2.03911 2.50851 + vertex 1.36338 2.04159 2.50953 + vertex 1.35928 2.0429 2.50876 + endloop + endfacet + facet normal -0.217672 -0.0877868 0.972066 + outer loop + vertex 1.36562 2.03861 2.51069 + vertex 1.36268 2.03822 2.50999 + vertex 1.36439 2.03685 2.51025 + endloop + endfacet + facet normal 0.0773781 0.290832 0.95364 + outer loop + vertex 1.36101 2.05038 2.50713 + vertex 1.35976 2.05446 2.50598 + vertex 1.35616 2.05081 2.50739 + endloop + endfacet + facet normal 0.150557 0.426184 0.89202 + outer loop + vertex 1.35987 2.12983 2.48138 + vertex 1.36462 2.12871 2.48112 + vertex 1.36298 2.13246 2.4796 + endloop + endfacet + facet normal 0.152572 0.424214 0.892617 + outer loop + vertex 1.35754 2.13391 2.47984 + vertex 1.35987 2.12983 2.48138 + vertex 1.36298 2.13246 2.4796 + endloop + endfacet + facet normal 0.149433 0.348619 0.925275 + outer loop + vertex 1.36158 2.12583 2.48261 + vertex 1.35987 2.12983 2.48138 + vertex 1.35621 2.12705 2.48302 + endloop + endfacet + facet normal 0.133139 0.343081 0.929822 + outer loop + vertex 1.36462 2.12871 2.48112 + vertex 1.35987 2.12983 2.48138 + vertex 1.36158 2.12583 2.48261 + endloop + endfacet + facet normal 0.180207 0.539808 0.822273 + outer loop + vertex 1.36298 2.13246 2.4796 + vertex 1.36119 2.13604 2.47765 + vertex 1.35754 2.13391 2.47984 + endloop + endfacet + facet normal 0.185855 0.533237 0.825298 + outer loop + vertex 1.35754 2.13391 2.47984 + vertex 1.36119 2.13604 2.47765 + vertex 1.35688 2.13722 2.47785 + endloop + endfacet + facet normal 0.19742 0.748321 0.633278 + outer loop + vertex 1.359 2.13898 2.47569 + vertex 1.36422 2.13849 2.47464 + vertex 1.36096 2.1409 2.47281 + endloop + endfacet + facet normal 0.21744 0.737322 0.639591 + outer loop + vertex 1.35655 2.1414 2.47373 + vertex 1.359 2.13898 2.47569 + vertex 1.36096 2.1409 2.47281 + endloop + endfacet + facet normal 0.212507 0.64627 0.732923 + outer loop + vertex 1.36119 2.13604 2.47765 + vertex 1.359 2.13898 2.47569 + vertex 1.35688 2.13722 2.47785 + endloop + endfacet + facet normal 0.208166 0.644749 0.735503 + outer loop + vertex 1.36422 2.13849 2.47464 + vertex 1.359 2.13898 2.47569 + vertex 1.36119 2.13604 2.47765 + endloop + endfacet + facet normal 0.063041 0.790187 0.609615 + outer loop + vertex 1.35892 2.14495 2.46738 + vertex 1.3646 2.14589 2.46557 + vertex 1.36168 2.14739 2.46393 + endloop + endfacet + facet normal 0.141766 0.750972 0.644937 + outer loop + vertex 1.35716 2.14725 2.46509 + vertex 1.35892 2.14495 2.46738 + vertex 1.36168 2.14739 2.46393 + endloop + endfacet + facet normal 0.0839043 0.751115 0.654818 + outer loop + vertex 1.3646 2.14589 2.46557 + vertex 1.35892 2.14495 2.46738 + vertex 1.36313 2.14288 2.46922 + endloop + endfacet + facet normal 0.186104 0.83607 0.516094 + outer loop + vertex 1.36313 2.14288 2.46922 + vertex 1.35892 2.14495 2.46738 + vertex 1.3586 2.14281 2.47095 + endloop + endfacet + facet normal 0.208315 0.80111 0.561095 + outer loop + vertex 1.36096 2.1409 2.47281 + vertex 1.3586 2.14281 2.47095 + vertex 1.35655 2.1414 2.47373 + endloop + endfacet + facet normal 0.20497 0.799883 0.56407 + outer loop + vertex 1.36313 2.14288 2.46922 + vertex 1.3586 2.14281 2.47095 + vertex 1.36096 2.1409 2.47281 + endloop + endfacet + facet normal 0.0121745 0.467614 0.883849 + outer loop + vertex 1.365 2.15181 2.46 + vertex 1.36 2.15194 2.46 + vertex 1.36434 2.14937 2.4613 + endloop + endfacet + facet normal 0.484651 0.869271 0.0973687 + outer loop + vertex 1.36434 2.14937 2.4613 + vertex 1.36 2.15194 2.46 + vertex 1.36 2.15138 2.465 + endloop + endfacet + facet normal 0.250271 -0.151317 0.956278 + outer loop + vertex 1.36168 2.14739 2.46393 + vertex 1.36 2.15138 2.465 + vertex 1.35716 2.14725 2.46509 + endloop + endfacet + facet normal 0.66849 0.0835602 0.739012 + outer loop + vertex 1.36434 2.14937 2.4613 + vertex 1.36 2.15138 2.465 + vertex 1.36168 2.14739 2.46393 + endloop + endfacet + facet normal 0.23718 -0.887897 0.394188 + outer loop + vertex 1.36859 0.88 2.46 + vertex 1.365 0.88 2.46216 + vertex 1.365 0.879041 2.46 + endloop + endfacet + facet normal 0.319842 -0.784305 0.53157 + outer loop + vertex 1.365 0.88 2.46216 + vertex 1.36859 0.88 2.46 + vertex 1.37 0.880575 2.46 + endloop + endfacet + facet normal 0.290306 -0.846272 0.446706 + outer loop + vertex 1.365 0.88 2.46216 + vertex 1.37 0.880575 2.46 + vertex 1.365 0.881499 2.465 + endloop + endfacet + facet normal 0.443121 -0.691198 0.570867 + outer loop + vertex 1.365 0.881499 2.465 + vertex 1.37 0.880575 2.46 + vertex 1.36795 0.881057 2.46217 + endloop + endfacet + facet normal 0.226756 -0.897932 0.377226 + outer loop + vertex 1.36795 0.881057 2.46217 + vertex 1.36703 0.882132 2.46528 + vertex 1.365 0.881499 2.465 + endloop + endfacet + facet normal 0.215078 -0.880638 0.42216 + outer loop + vertex 1.36703 0.882132 2.46528 + vertex 1.36191 0.881916 2.46744 + vertex 1.365 0.881499 2.465 + endloop + endfacet + facet normal 0.212765 -0.883967 0.416334 + outer loop + vertex 1.36703 0.882132 2.46528 + vertex 1.36479 0.883465 2.46926 + vertex 1.36191 0.881916 2.46744 + endloop + endfacet + facet normal 0.186398 -0.895048 0.405147 + outer loop + vertex 1.36863 0.883715 2.46805 + vertex 1.36479 0.883465 2.46926 + vertex 1.36703 0.882132 2.46528 + endloop + endfacet + facet normal 0.207763 -0.851458 0.481513 + outer loop + vertex 1.36479 0.883465 2.46926 + vertex 1.36863 0.883715 2.46805 + vertex 1.36774 0.885225 2.4711 + endloop + endfacet + facet normal 0.187383 -0.842277 0.505429 + outer loop + vertex 1.36257 0.885211 2.47299 + vertex 1.36479 0.883465 2.46926 + vertex 1.36774 0.885225 2.4711 + endloop + endfacet + facet normal 0.223399 -0.764736 0.604377 + outer loop + vertex 1.36774 0.885225 2.4711 + vertex 1.36672 0.887652 2.47455 + vertex 1.36257 0.885211 2.47299 + endloop + endfacet + facet normal 0.190254 -0.736775 0.648819 + outer loop + vertex 1.36672 0.887652 2.47455 + vertex 1.36206 0.887603 2.47586 + vertex 1.36257 0.885211 2.47299 + endloop + endfacet + facet normal 0.217535 -0.624557 0.750071 + outer loop + vertex 1.36672 0.887652 2.47455 + vertex 1.36453 0.890272 2.47737 + vertex 1.36206 0.887603 2.47586 + endloop + endfacet + facet normal 0.17999 -0.646524 0.741357 + outer loop + vertex 1.36917 0.890712 2.47662 + vertex 1.36453 0.890272 2.47737 + vertex 1.36672 0.887652 2.47455 + endloop + endfacet + facet normal 0.15475 -0.369703 0.916173 + outer loop + vertex 1.36876 0.900418 2.48168 + vertex 1.36423 0.899905 2.48223 + vertex 1.36554 0.896749 2.48074 + endloop + endfacet + facet normal 0.0249851 0.318373 0.947636 + outer loop + vertex 1.36769 0.983255 2.50867 + vertex 1.36572 0.986576 2.5076 + vertex 1.36266 0.98306 2.50886 + endloop + endfacet + facet normal -0.0503343 0.375896 0.925294 + outer loop + vertex 1.36266 0.98306 2.50886 + vertex 1.36572 0.986576 2.5076 + vertex 1.361 0.986396 2.50742 + endloop + endfacet + facet normal -0.124327 0.670558 -0.731365 + outer loop + vertex 1.365 0.99 2.4936 + vertex 1.37 0.992454 2.495 + vertex 1.37 0.99 2.49275 + endloop + endfacet + facet normal -0.271493 0.830573 -0.486252 + outer loop + vertex 1.36398 0.990201 2.49451 + vertex 1.37 0.992454 2.495 + vertex 1.365 0.99 2.4936 + endloop + endfacet + facet normal -0.353707 0.869846 0.343889 + outer loop + vertex 1.37 0.992454 2.495 + vertex 1.36398 0.990201 2.49451 + vertex 1.36843 0.990931 2.49723 + endloop + endfacet + facet normal -0.145733 0.988945 -0.0273764 + outer loop + vertex 1.36843 0.990931 2.49723 + vertex 1.36398 0.990201 2.49451 + vertex 1.36348 0.990211 2.49756 + endloop + endfacet + facet normal -0.135979 0.984506 0.110713 + outer loop + vertex 1.36843 0.990931 2.49723 + vertex 1.36348 0.990211 2.49756 + vertex 1.36793 0.990405 2.5013 + endloop + endfacet + facet normal -0.109843 0.99078 0.0793017 + outer loop + vertex 1.36793 0.990405 2.5013 + vertex 1.36348 0.990211 2.49756 + vertex 1.36328 0.989876 2.50147 + endloop + endfacet + facet normal -0.0952636 0.941358 0.323682 + outer loop + vertex 1.36793 0.990405 2.5013 + vertex 1.36328 0.989876 2.50147 + vertex 1.36731 0.989063 2.50502 + endloop + endfacet + facet normal -0.0968143 0.940649 0.325279 + outer loop + vertex 1.36731 0.989063 2.50502 + vertex 1.36328 0.989876 2.50147 + vertex 1.36278 0.988607 2.50499 + endloop + endfacet + facet normal -0.0541979 0.757594 0.650472 + outer loop + vertex 1.36572 0.986576 2.5076 + vertex 1.36278 0.988607 2.50499 + vertex 1.361 0.986396 2.50742 + endloop + endfacet + facet normal -0.0789674 0.741723 0.666042 + outer loop + vertex 1.36731 0.989063 2.50502 + vertex 1.36278 0.988607 2.50499 + vertex 1.36572 0.986576 2.5076 + endloop + endfacet + facet normal -0.0632805 -0.718898 -0.692229 + outer loop + vertex 1.37 2.03699 2.495 + vertex 1.3685 2.03505 2.49715 + vertex 1.365 2.03743 2.495 + endloop + endfacet + facet normal -0.0372775 -0.699793 -0.713373 + outer loop + vertex 1.3685 2.03505 2.49715 + vertex 1.36405 2.03539 2.49705 + vertex 1.365 2.03743 2.495 + endloop + endfacet + facet normal -0.0745801 -0.992254 -0.0993477 + outer loop + vertex 1.3685 2.03505 2.49715 + vertex 1.36746 2.03471 2.50133 + vertex 1.36405 2.03539 2.49705 + endloop + endfacet + facet normal -0.060258 -0.992023 -0.110723 + outer loop + vertex 1.36746 2.03471 2.50133 + vertex 1.363 2.03499 2.50123 + vertex 1.36405 2.03539 2.49705 + endloop + endfacet + facet normal -0.0637786 -0.997293 0.036581 + outer loop + vertex 1.36746 2.03471 2.50133 + vertex 1.36591 2.03494 2.50488 + vertex 1.363 2.03499 2.50123 + endloop + endfacet + facet normal -0.105255 -0.991994 0.0697817 + outer loop + vertex 1.36591 2.03494 2.50488 + vertex 1.36226 2.03536 2.50541 + vertex 1.363 2.03499 2.50123 + endloop + endfacet + facet normal -0.081397 -0.972447 0.218452 + outer loop + vertex 1.36591 2.03494 2.50488 + vertex 1.36585 2.03576 2.50853 + vertex 1.36226 2.03536 2.50541 + endloop + endfacet + facet normal -0.19781 -0.917384 0.345367 + outer loop + vertex 1.36585 2.03576 2.50853 + vertex 1.36197 2.03659 2.50852 + vertex 1.36226 2.03536 2.50541 + endloop + endfacet + facet normal -0.193153 -0.895252 0.401516 + outer loop + vertex 1.36585 2.03576 2.50853 + vertex 1.36439 2.03685 2.51025 + vertex 1.36197 2.03659 2.50852 + endloop + endfacet + facet normal -0.0554008 -0.864838 0.498985 + outer loop + vertex 1.36665 2.03691 2.51061 + vertex 1.36439 2.03685 2.51025 + vertex 1.36585 2.03576 2.50853 + endloop + endfacet + facet normal 0.133337 0.415433 0.899798 + outer loop + vertex 1.36462 2.12871 2.48112 + vertex 1.36854 2.12793 2.48089 + vertex 1.36781 2.13106 2.47956 + endloop + endfacet + facet normal 0.129587 0.419603 0.89841 + outer loop + vertex 1.36298 2.13246 2.4796 + vertex 1.36462 2.12871 2.48112 + vertex 1.36781 2.13106 2.47956 + endloop + endfacet + facet normal 0.132659 0.343537 0.929723 + outer loop + vertex 1.36668 2.12482 2.48226 + vertex 1.36462 2.12871 2.48112 + vertex 1.36158 2.12583 2.48261 + endloop + endfacet + facet normal 0.11989 0.337909 0.933512 + outer loop + vertex 1.36854 2.12793 2.48089 + vertex 1.36462 2.12871 2.48112 + vertex 1.36668 2.12482 2.48226 + endloop + endfacet + facet normal 0.160771 0.528841 0.833354 + outer loop + vertex 1.36781 2.13106 2.47956 + vertex 1.36677 2.13494 2.4773 + vertex 1.36298 2.13246 2.4796 + endloop + endfacet + facet normal 0.156817 0.533076 0.831407 + outer loop + vertex 1.36298 2.13246 2.4796 + vertex 1.36677 2.13494 2.4773 + vertex 1.36119 2.13604 2.47765 + endloop + endfacet + facet normal 0.183221 0.805136 0.564081 + outer loop + vertex 1.36821 2.13992 2.47181 + vertex 1.36685 2.14177 2.46962 + vertex 1.36463 2.14079 2.47173 + endloop + endfacet + facet normal 0.205958 0.753295 0.624603 + outer loop + vertex 1.36463 2.14079 2.47173 + vertex 1.36096 2.1409 2.47281 + vertex 1.36422 2.13849 2.47464 + endloop + endfacet + facet normal 0.171067 0.760993 0.6258 + outer loop + vertex 1.36463 2.14079 2.47173 + vertex 1.36422 2.13849 2.47464 + vertex 1.36821 2.13992 2.47181 + endloop + endfacet + facet normal 0.165399 0.766491 0.620592 + outer loop + vertex 1.36821 2.13992 2.47181 + vertex 1.36422 2.13849 2.47464 + vertex 1.36938 2.13755 2.47442 + endloop + endfacet + facet normal 0.176612 0.668143 0.722767 + outer loop + vertex 1.36677 2.13494 2.4773 + vertex 1.36422 2.13849 2.47464 + vertex 1.36119 2.13604 2.47765 + endloop + endfacet + facet normal 0.150903 0.659763 0.736166 + outer loop + vertex 1.36938 2.13755 2.47442 + vertex 1.36422 2.13849 2.47464 + vertex 1.36677 2.13494 2.4773 + endloop + endfacet + facet normal -0.310653 0.359236 0.880025 + outer loop + vertex 1.36774 2.15 2.465 + vertex 1.36168 2.14739 2.46393 + vertex 1.3646 2.14589 2.46557 + endloop + endfacet + facet normal 0.0238363 0.119674 0.992527 + outer loop + vertex 1.36774 2.15 2.465 + vertex 1.3646 2.14589 2.46557 + vertex 1.37 2.14955 2.465 + endloop + endfacet + facet normal -0.134957 0.343876 0.929266 + outer loop + vertex 1.37 2.14955 2.465 + vertex 1.3646 2.14589 2.46557 + vertex 1.36783 2.14394 2.46676 + endloop + endfacet + facet normal 0.180448 0.80715 0.562092 + outer loop + vertex 1.36685 2.14177 2.46962 + vertex 1.36313 2.14288 2.46922 + vertex 1.36463 2.14079 2.47173 + endloop + endfacet + facet normal 0.158622 0.75902 0.631448 + outer loop + vertex 1.36685 2.14177 2.46962 + vertex 1.36783 2.14394 2.46676 + vertex 1.36313 2.14288 2.46922 + endloop + endfacet + facet normal 0.187827 0.718428 0.669763 + outer loop + vertex 1.36783 2.14394 2.46676 + vertex 1.3646 2.14589 2.46557 + vertex 1.36313 2.14288 2.46922 + endloop + endfacet + facet normal 0.188023 0.808047 0.558307 + outer loop + vertex 1.36463 2.14079 2.47173 + vertex 1.36313 2.14288 2.46922 + vertex 1.36096 2.1409 2.47281 + endloop + endfacet + facet normal -0.0505242 0.991306 -0.121491 + outer loop + vertex 1.37 2.15 2.46406 + vertex 1.36434 2.14937 2.4613 + vertex 1.36774 2.15 2.465 + endloop + endfacet + facet normal -0.2312 0.937289 0.260838 + outer loop + vertex 1.37 2.15 2.46406 + vertex 1.37 2.15113 2.46 + vertex 1.36434 2.14937 2.4613 + endloop + endfacet + facet normal 0.0620433 0.45622 0.887701 + outer loop + vertex 1.37 2.15113 2.46 + vertex 1.365 2.15181 2.46 + vertex 1.36434 2.14937 2.4613 + endloop + endfacet + facet normal -0.419635 0.876284 0.236713 + outer loop + vertex 1.36774 2.15 2.465 + vertex 1.36434 2.14937 2.4613 + vertex 1.36168 2.14739 2.46393 + endloop + endfacet + facet normal 0.204725 -0.908271 0.364871 + outer loop + vertex 1.375 0.881702 2.46 + vertex 1.37165 0.881813 2.46216 + vertex 1.37 0.880575 2.46 + endloop + endfacet + facet normal 0.187149 -0.906908 0.377482 + outer loop + vertex 1.37165 0.881813 2.46216 + vertex 1.36795 0.881057 2.46217 + vertex 1.37 0.880575 2.46 + endloop + endfacet + facet normal 0.189678 -0.907044 0.37589 + outer loop + vertex 1.37093 0.883135 2.46571 + vertex 1.37165 0.881813 2.46216 + vertex 1.37489 0.883538 2.46469 + endloop + endfacet + facet normal 0.192245 -0.906391 0.376162 + outer loop + vertex 1.37093 0.883135 2.46571 + vertex 1.36703 0.882132 2.46528 + vertex 1.37165 0.881813 2.46216 + endloop + endfacet + facet normal 0.187734 -0.90992 0.369868 + outer loop + vertex 1.36703 0.882132 2.46528 + vertex 1.36795 0.881057 2.46217 + vertex 1.37165 0.881813 2.46216 + endloop + endfacet + facet normal 0.186172 -0.895039 0.405273 + outer loop + vertex 1.37093 0.883135 2.46571 + vertex 1.36863 0.883715 2.46805 + vertex 1.36703 0.882132 2.46528 + endloop + endfacet + facet normal 0.200971 -0.880082 0.430194 + outer loop + vertex 1.37489 0.883538 2.46469 + vertex 1.37248 0.884958 2.46871 + vertex 1.37093 0.883135 2.46571 + endloop + endfacet + facet normal 0.210375 -0.880202 0.425425 + outer loop + vertex 1.36863 0.883715 2.46805 + vertex 1.37093 0.883135 2.46571 + vertex 1.37248 0.884958 2.46871 + endloop + endfacet + facet normal 0.193187 -0.856013 0.479501 + outer loop + vertex 1.36863 0.883715 2.46805 + vertex 1.37248 0.884958 2.46871 + vertex 1.36774 0.885225 2.4711 + endloop + endfacet + facet normal 0.216243 -0.825177 0.521844 + outer loop + vertex 1.36774 0.885225 2.4711 + vertex 1.37248 0.884958 2.46871 + vertex 1.37121 0.886981 2.47244 + endloop + endfacet + facet normal 0.193004 -0.750004 0.632648 + outer loop + vertex 1.37061 0.888782 2.47476 + vertex 1.37121 0.886981 2.47244 + vertex 1.37418 0.889028 2.47396 + endloop + endfacet + facet normal 0.184711 -0.752356 0.632331 + outer loop + vertex 1.37061 0.888782 2.47476 + vertex 1.36672 0.887652 2.47455 + vertex 1.37121 0.886981 2.47244 + endloop + endfacet + facet normal 0.164898 -0.782913 0.599879 + outer loop + vertex 1.36672 0.887652 2.47455 + vertex 1.36774 0.885225 2.4711 + vertex 1.37121 0.886981 2.47244 + endloop + endfacet + facet normal 0.142613 -0.630967 0.762589 + outer loop + vertex 1.37061 0.888782 2.47476 + vertex 1.36917 0.890712 2.47662 + vertex 1.36672 0.887652 2.47455 + endloop + endfacet + facet normal 0.207647 -0.653259 0.728104 + outer loop + vertex 1.37418 0.889028 2.47396 + vertex 1.37258 0.89062 2.47584 + vertex 1.37061 0.888782 2.47476 + endloop + endfacet + facet normal 0.15821 -0.622801 0.766217 + outer loop + vertex 1.37258 0.89062 2.47584 + vertex 1.36917 0.890712 2.47662 + vertex 1.37061 0.888782 2.47476 + endloop + endfacet + facet normal 0.175583 -0.527681 0.831098 + outer loop + vertex 1.37258 0.89062 2.47584 + vertex 1.37355 0.893925 2.47774 + vertex 1.36917 0.890712 2.47662 + endloop + endfacet + facet normal -0.00960279 0.299888 0.953926 + outer loop + vertex 1.36769 0.983255 2.50867 + vertex 1.37059 0.986855 2.50756 + vertex 1.36572 0.986576 2.5076 + endloop + endfacet + facet normal -0.061 0.910506 0.408971 + outer loop + vertex 1.375 0.992789 2.495 + vertex 1.37 0.992454 2.495 + vertex 1.37355 0.991681 2.49725 + endloop + endfacet + facet normal -0.127287 0.85904 0.495831 + outer loop + vertex 1.37355 0.991681 2.49725 + vertex 1.37 0.992454 2.495 + vertex 1.36843 0.990931 2.49723 + endloop + endfacet + facet normal -0.143009 0.973307 0.179507 + outer loop + vertex 1.37355 0.991681 2.49725 + vertex 1.36843 0.990931 2.49723 + vertex 1.37294 0.990852 2.50126 + endloop + endfacet + facet normal -0.0872573 0.989253 0.11732 + outer loop + vertex 1.37294 0.990852 2.50126 + vertex 1.36843 0.990931 2.49723 + vertex 1.36793 0.990405 2.5013 + endloop + endfacet + facet normal -0.0807687 0.938278 0.33632 + outer loop + vertex 1.37294 0.990852 2.50126 + vertex 1.36793 0.990405 2.5013 + vertex 1.37222 0.989435 2.50504 + endloop + endfacet + facet normal -0.0724269 0.941999 0.327709 + outer loop + vertex 1.37222 0.989435 2.50504 + vertex 1.36793 0.990405 2.5013 + vertex 1.36731 0.989063 2.50502 + endloop + endfacet + facet normal -0.0364302 0.730734 0.681689 + outer loop + vertex 1.37059 0.986855 2.50756 + vertex 1.36731 0.989063 2.50502 + vertex 1.36572 0.986576 2.5076 + endloop + endfacet + facet normal -0.056707 0.716407 0.695375 + outer loop + vertex 1.37222 0.989435 2.50504 + vertex 1.36731 0.989063 2.50502 + vertex 1.37059 0.986855 2.50756 + endloop + endfacet + facet normal -0.0242653 -0.713715 -0.700016 + outer loop + vertex 1.375 2.03682 2.495 + vertex 1.37333 2.03462 2.4973 + vertex 1.37 2.03699 2.495 + endloop + endfacet + facet normal -0.0435433 -0.726712 -0.68556 + outer loop + vertex 1.37333 2.03462 2.4973 + vertex 1.3685 2.03505 2.49715 + vertex 1.37 2.03699 2.495 + endloop + endfacet + facet normal -0.0868275 -0.994475 -0.0589972 + outer loop + vertex 1.37333 2.03462 2.4973 + vertex 1.37234 2.03445 2.50152 + vertex 1.3685 2.03505 2.49715 + endloop + endfacet + facet normal -0.0481929 -0.994505 -0.0929416 + outer loop + vertex 1.37234 2.03445 2.50152 + vertex 1.36746 2.03471 2.50133 + vertex 1.3685 2.03505 2.49715 + endloop + endfacet + facet normal -0.0583032 -0.981664 0.181486 + outer loop + vertex 1.37234 2.03445 2.50152 + vertex 1.37094 2.03549 2.50668 + vertex 1.36746 2.03471 2.50133 + endloop + endfacet + facet normal 0.0743452 -0.992535 0.0966839 + outer loop + vertex 1.37094 2.03549 2.50668 + vertex 1.36591 2.03494 2.50488 + vertex 1.36746 2.03471 2.50133 + endloop + endfacet + facet normal 0.358686 -0.781405 0.510638 + outer loop + vertex 1.36907 2.0367 2.50984 + vertex 1.37094 2.03549 2.50668 + vertex 1.37302 2.03854 2.50989 + endloop + endfacet + facet normal 0.0985821 -0.908676 0.405695 + outer loop + vertex 1.36907 2.0367 2.50984 + vertex 1.36585 2.03576 2.50853 + vertex 1.37094 2.03549 2.50668 + endloop + endfacet + facet normal 0.0280141 -0.974902 0.220866 + outer loop + vertex 1.36585 2.03576 2.50853 + vertex 1.36591 2.03494 2.50488 + vertex 1.37094 2.03549 2.50668 + endloop + endfacet + facet normal 0.0686448 -0.884395 0.461663 + outer loop + vertex 1.36907 2.0367 2.50984 + vertex 1.36665 2.03691 2.51061 + vertex 1.36585 2.03576 2.50853 + endloop + endfacet + facet normal 0.109546 0.32366 0.939811 + outer loop + vertex 1.37494 2.10991 2.48626 + vertex 1.37323 2.11413 2.48501 + vertex 1.37094 2.11071 2.48645 + endloop + endfacet + facet normal 0.1115 0.32243 0.940004 + outer loop + vertex 1.36887 2.11319 2.48585 + vertex 1.37094 2.11071 2.48645 + vertex 1.37323 2.11413 2.48501 + endloop + endfacet + facet normal 0.151845 0.365548 0.918323 + outer loop + vertex 1.36854 2.12793 2.48089 + vertex 1.37079 2.12574 2.48139 + vertex 1.37256 2.12889 2.47985 + endloop + endfacet + facet normal 0.134953 0.41566 0.899452 + outer loop + vertex 1.36854 2.12793 2.48089 + vertex 1.37256 2.12889 2.47985 + vertex 1.36781 2.13106 2.47956 + endloop + endfacet + facet normal 0.156961 0.460383 0.873734 + outer loop + vertex 1.36781 2.13106 2.47956 + vertex 1.37256 2.12889 2.47985 + vertex 1.37141 2.13287 2.47796 + endloop + endfacet + facet normal 0.120938 0.337316 0.933591 + outer loop + vertex 1.37079 2.12574 2.48139 + vertex 1.36854 2.12793 2.48089 + vertex 1.36668 2.12482 2.48226 + endloop + endfacet + facet normal 0.168402 0.669924 0.723078 + outer loop + vertex 1.37451 2.13462 2.47618 + vertex 1.37298 2.1368 2.47451 + vertex 1.37088 2.1355 2.47621 + endloop + endfacet + facet normal 0.144679 0.567973 0.810231 + outer loop + vertex 1.37088 2.1355 2.47621 + vertex 1.37141 2.13287 2.47796 + vertex 1.37451 2.13462 2.47618 + endloop + endfacet + facet normal 0.137618 0.567572 0.811741 + outer loop + vertex 1.37088 2.1355 2.47621 + vertex 1.36677 2.13494 2.4773 + vertex 1.37141 2.13287 2.47796 + endloop + endfacet + facet normal 0.112845 0.522684 0.845025 + outer loop + vertex 1.36677 2.13494 2.4773 + vertex 1.36781 2.13106 2.47956 + vertex 1.37141 2.13287 2.47796 + endloop + endfacet + facet normal 0.166168 0.818694 0.549662 + outer loop + vertex 1.36821 2.13992 2.47181 + vertex 1.37383 2.13909 2.47135 + vertex 1.37069 2.14159 2.46857 + endloop + endfacet + facet normal 0.189477 0.805937 0.56086 + outer loop + vertex 1.36685 2.14177 2.46962 + vertex 1.36821 2.13992 2.47181 + vertex 1.37069 2.14159 2.46857 + endloop + endfacet + facet normal 0.128652 0.703008 0.699449 + outer loop + vertex 1.37298 2.1368 2.47451 + vertex 1.36938 2.13755 2.47442 + vertex 1.37088 2.1355 2.47621 + endloop + endfacet + facet normal 0.147637 0.782448 0.604961 + outer loop + vertex 1.37298 2.1368 2.47451 + vertex 1.37383 2.13909 2.47135 + vertex 1.36938 2.13755 2.47442 + endloop + endfacet + facet normal 0.164287 0.766397 0.621004 + outer loop + vertex 1.37383 2.13909 2.47135 + vertex 1.36821 2.13992 2.47181 + vertex 1.36938 2.13755 2.47442 + endloop + endfacet + facet normal 0.095299 0.692361 0.71523 + outer loop + vertex 1.37088 2.1355 2.47621 + vertex 1.36938 2.13755 2.47442 + vertex 1.36677 2.13494 2.4773 + endloop + endfacet + facet normal 0.564374 0.824846 0.0333221 + outer loop + vertex 1.37 2.14955 2.465 + vertex 1.37443 2.14668 2.46103 + vertex 1.37181 2.1485 2.46033 + endloop + endfacet + facet normal 0.853625 0.469786 0.225001 + outer loop + vertex 1.37 2.15 2.46406 + vertex 1.37 2.14955 2.465 + vertex 1.37181 2.1485 2.46033 + endloop + endfacet + facet normal 0.740943 0.366425 0.562792 + outer loop + vertex 1.37443 2.14668 2.46103 + vertex 1.37 2.14955 2.465 + vertex 1.37301 2.14385 2.46475 + endloop + endfacet + facet normal 0.359459 0.149882 0.921046 + outer loop + vertex 1.37301 2.14385 2.46475 + vertex 1.37 2.14955 2.465 + vertex 1.36783 2.14394 2.46676 + endloop + endfacet + facet normal 0.207204 0.743278 0.636085 + outer loop + vertex 1.37069 2.14159 2.46857 + vertex 1.36783 2.14394 2.46676 + vertex 1.36685 2.14177 2.46962 + endloop + endfacet + facet normal 0.245301 0.761692 0.59971 + outer loop + vertex 1.37301 2.14385 2.46475 + vertex 1.36783 2.14394 2.46676 + vertex 1.37069 2.14159 2.46857 + endloop + endfacet + facet normal 0.803896 0.572996 0.159459 + outer loop + vertex 1.37181 2.1485 2.46033 + vertex 1.37 2.15113 2.46 + vertex 1.37 2.15 2.46406 + endloop + endfacet + facet normal 0.0208883 0.137408 0.990294 + outer loop + vertex 1.375 2.15037 2.46 + vertex 1.37 2.15113 2.46 + vertex 1.37181 2.1485 2.46033 + endloop + endfacet + facet normal 0.0960654 -0.89619 0.433146 + outer loop + vertex 1.38 0.882238 2.46 + vertex 1.37702 0.882491 2.46118 + vertex 1.375 0.881702 2.46 + endloop + endfacet + facet normal 0.175573 -0.930756 0.32073 + outer loop + vertex 1.37702 0.882491 2.46118 + vertex 1.37165 0.881813 2.46216 + vertex 1.375 0.881702 2.46 + endloop + endfacet + facet normal 0.183611 -0.905483 0.382607 + outer loop + vertex 1.37702 0.882491 2.46118 + vertex 1.37489 0.883538 2.46469 + vertex 1.37165 0.881813 2.46216 + endloop + endfacet + facet normal 0.19023 -0.902748 0.385821 + outer loop + vertex 1.37961 0.883997 2.46343 + vertex 1.37489 0.883538 2.46469 + vertex 1.37702 0.882491 2.46118 + endloop + endfacet + facet normal 0.197459 -0.886217 0.419081 + outer loop + vertex 1.37489 0.883538 2.46469 + vertex 1.37961 0.883997 2.46343 + vertex 1.37783 0.885428 2.46729 + endloop + endfacet + facet normal 0.190636 -0.884595 0.425616 + outer loop + vertex 1.37248 0.884958 2.46871 + vertex 1.37489 0.883538 2.46469 + vertex 1.37783 0.885428 2.46729 + endloop + endfacet + facet normal 0.207237 -0.838857 0.50336 + outer loop + vertex 1.37783 0.885428 2.46729 + vertex 1.37601 0.887221 2.47103 + vertex 1.37248 0.884958 2.46871 + endloop + endfacet + facet normal 0.193596 -0.832961 0.518359 + outer loop + vertex 1.37601 0.887221 2.47103 + vertex 1.37121 0.886981 2.47244 + vertex 1.37248 0.884958 2.46871 + endloop + endfacet + facet normal 0.216179 -0.764638 0.60712 + outer loop + vertex 1.37601 0.887221 2.47103 + vertex 1.37418 0.889028 2.47396 + vertex 1.37121 0.886981 2.47244 + endloop + endfacet + facet normal 0.213291 -0.766142 0.606245 + outer loop + vertex 1.37921 0.890023 2.47345 + vertex 1.37418 0.889028 2.47396 + vertex 1.37601 0.887221 2.47103 + endloop + endfacet + facet normal 0.203018 -0.648407 0.733725 + outer loop + vertex 1.37418 0.889028 2.47396 + vertex 1.37921 0.890023 2.47345 + vertex 1.37626 0.891711 2.47576 + endloop + endfacet + facet normal 0.21074 -0.651242 0.729022 + outer loop + vertex 1.37258 0.89062 2.47584 + vertex 1.37418 0.889028 2.47396 + vertex 1.37626 0.891711 2.47576 + endloop + endfacet + facet normal 0.17657 -0.527804 0.83081 + outer loop + vertex 1.37626 0.891711 2.47576 + vertex 1.37355 0.893925 2.47774 + vertex 1.37258 0.89062 2.47584 + endloop + endfacet + facet normal 0.168036 -0.535453 0.82768 + outer loop + vertex 1.37887 0.894931 2.47731 + vertex 1.37355 0.893925 2.47774 + vertex 1.37626 0.891711 2.47576 + endloop + endfacet + facet normal -0.132183 0.928203 0.347802 + outer loop + vertex 1.38 0.993501 2.495 + vertex 1.375 0.992789 2.495 + vertex 1.37835 0.992422 2.49725 + endloop + endfacet + facet normal -0.142386 0.921305 0.361835 + outer loop + vertex 1.37835 0.992422 2.49725 + vertex 1.375 0.992789 2.495 + vertex 1.37355 0.991681 2.49725 + endloop + endfacet + facet normal -0.148459 0.960832 0.234011 + outer loop + vertex 1.37835 0.992422 2.49725 + vertex 1.37355 0.991681 2.49725 + vertex 1.378 0.991393 2.50125 + endloop + endfacet + facet normal -0.104363 0.976959 0.186171 + outer loop + vertex 1.378 0.991393 2.50125 + vertex 1.37355 0.991681 2.49725 + vertex 1.37294 0.990852 2.50126 + endloop + endfacet + facet normal -0.0973927 0.912882 0.396435 + outer loop + vertex 1.378 0.991393 2.50125 + vertex 1.37294 0.990852 2.50126 + vertex 1.37732 0.989705 2.50497 + endloop + endfacet + facet normal -0.0454072 0.93823 0.343019 + outer loop + vertex 1.37732 0.989705 2.50497 + vertex 1.37294 0.990852 2.50126 + vertex 1.37222 0.989435 2.50504 + endloop + endfacet + facet normal -0.00314163 0.700448 0.713696 + outer loop + vertex 1.37565 0.987053 2.50739 + vertex 1.37222 0.989435 2.50504 + vertex 1.37059 0.986855 2.50756 + endloop + endfacet + facet normal -0.0269391 0.682559 0.730334 + outer loop + vertex 1.37732 0.989705 2.50497 + vertex 1.37222 0.989435 2.50504 + vertex 1.37565 0.987053 2.50739 + endloop + endfacet + facet normal -0.0199909 -0.666518 -0.745221 + outer loop + vertex 1.38 2.03667 2.495 + vertex 1.37823 2.03412 2.49733 + vertex 1.375 2.03682 2.495 + endloop + endfacet + facet normal -0.0670393 -0.696403 -0.714512 + outer loop + vertex 1.37823 2.03412 2.49733 + vertex 1.37333 2.03462 2.4973 + vertex 1.375 2.03682 2.495 + endloop + endfacet + facet normal -0.10058 -0.994427 -0.031586 + outer loop + vertex 1.37823 2.03412 2.49733 + vertex 1.37723 2.03409 2.50154 + vertex 1.37333 2.03462 2.4973 + endloop + endfacet + facet normal -0.0741657 -0.995668 -0.0560795 + outer loop + vertex 1.37723 2.03409 2.50154 + vertex 1.37234 2.03445 2.50152 + vertex 1.37333 2.03462 2.4973 + endloop + endfacet + facet normal -0.0739155 -0.984242 0.160639 + outer loop + vertex 1.37723 2.03409 2.50154 + vertex 1.37584 2.03481 2.50534 + vertex 1.37234 2.03445 2.50152 + endloop + endfacet + facet normal -0.0880378 -0.98093 0.17328 + outer loop + vertex 1.37584 2.03481 2.50534 + vertex 1.37094 2.03549 2.50668 + vertex 1.37234 2.03445 2.50152 + endloop + endfacet + facet normal -0.180024 -0.60965 0.771958 + outer loop + vertex 1.37302 2.03854 2.50989 + vertex 1.37678 2.03621 2.50893 + vertex 1.37737 2.03792 2.51042 + endloop + endfacet + facet normal -0.206436 -0.639394 0.740648 + outer loop + vertex 1.37302 2.03854 2.50989 + vertex 1.37094 2.03549 2.50668 + vertex 1.37678 2.03621 2.50893 + endloop + endfacet + facet normal -0.0272224 -0.928865 0.369417 + outer loop + vertex 1.37094 2.03549 2.50668 + vertex 1.37584 2.03481 2.50534 + vertex 1.37678 2.03621 2.50893 + endloop + endfacet + facet normal -0.45771 -0.488757 0.74271 + outer loop + vertex 1.37678 2.03621 2.50893 + vertex 1.37853 2.03689 2.51045 + vertex 1.37737 2.03792 2.51042 + endloop + endfacet + facet normal 0.0486797 0.0860564 0.9951 + outer loop + vertex 1.37956 2.0379 2.51031 + vertex 1.37737 2.03792 2.51042 + vertex 1.37853 2.03689 2.51045 + endloop + endfacet + facet normal 0.111245 0.324228 0.939415 + outer loop + vertex 1.37323 2.11413 2.48501 + vertex 1.37494 2.10991 2.48626 + vertex 1.37823 2.11301 2.4848 + endloop + endfacet + facet normal 0.154967 0.438838 0.885103 + outer loop + vertex 1.37807 2.12759 2.47953 + vertex 1.37626 2.13144 2.47794 + vertex 1.37256 2.12889 2.47985 + endloop + endfacet + facet normal 0.138794 0.457342 0.878393 + outer loop + vertex 1.37256 2.12889 2.47985 + vertex 1.37626 2.13144 2.47794 + vertex 1.37141 2.13287 2.47796 + endloop + endfacet + facet normal 0.176638 0.664194 0.726392 + outer loop + vertex 1.37451 2.13462 2.47618 + vertex 1.37918 2.13369 2.47589 + vertex 1.37689 2.13649 2.47389 + endloop + endfacet + facet normal 0.168713 0.67002 0.722917 + outer loop + vertex 1.37298 2.1368 2.47451 + vertex 1.37451 2.13462 2.47618 + vertex 1.37689 2.13649 2.47389 + endloop + endfacet + facet normal 0.164385 0.545124 0.822081 + outer loop + vertex 1.37626 2.13144 2.47794 + vertex 1.37451 2.13462 2.47618 + vertex 1.37141 2.13287 2.47796 + endloop + endfacet + facet normal 0.158399 0.54319 0.824533 + outer loop + vertex 1.37918 2.13369 2.47589 + vertex 1.37451 2.13462 2.47618 + vertex 1.37626 2.13144 2.47794 + endloop + endfacet + facet normal 0.169985 0.857104 0.48629 + outer loop + vertex 1.37909 2.14017 2.46815 + vertex 1.37714 2.1422 2.46526 + vertex 1.37473 2.14137 2.46756 + endloop + endfacet + facet normal 0.179857 0.823311 0.53834 + outer loop + vertex 1.37473 2.14137 2.46756 + vertex 1.37069 2.14159 2.46857 + vertex 1.37383 2.13909 2.47135 + endloop + endfacet + facet normal 0.155664 0.82955 0.536299 + outer loop + vertex 1.37473 2.14137 2.46756 + vertex 1.37383 2.13909 2.47135 + vertex 1.37909 2.14017 2.46815 + endloop + endfacet + facet normal 0.15284 0.832437 0.532623 + outer loop + vertex 1.37909 2.14017 2.46815 + vertex 1.37383 2.13909 2.47135 + vertex 1.37902 2.13805 2.47148 + endloop + endfacet + facet normal 0.158793 0.779566 0.605857 + outer loop + vertex 1.37689 2.13649 2.47389 + vertex 1.37383 2.13909 2.47135 + vertex 1.37298 2.1368 2.47451 + endloop + endfacet + facet normal 0.138318 0.770949 0.621696 + outer loop + vertex 1.37902 2.13805 2.47148 + vertex 1.37383 2.13909 2.47135 + vertex 1.37689 2.13649 2.47389 + endloop + endfacet + facet normal -0.0334958 0.318992 0.947165 + outer loop + vertex 1.37685 2.15 2.46 + vertex 1.37181 2.1485 2.46033 + vertex 1.37443 2.14668 2.46103 + endloop + endfacet + facet normal 0.0581006 0.257765 0.964459 + outer loop + vertex 1.37685 2.15 2.46 + vertex 1.37443 2.14668 2.46103 + vertex 1.38 2.14929 2.46 + endloop + endfacet + facet normal -0.0221314 0.408168 0.912639 + outer loop + vertex 1.38 2.14929 2.46 + vertex 1.37443 2.14668 2.46103 + vertex 1.37789 2.14421 2.46222 + endloop + endfacet + facet normal 0.251353 0.796693 0.549638 + outer loop + vertex 1.37714 2.1422 2.46526 + vertex 1.37301 2.14385 2.46475 + vertex 1.37473 2.14137 2.46756 + endloop + endfacet + facet normal 0.241548 0.780393 0.576751 + outer loop + vertex 1.37714 2.1422 2.46526 + vertex 1.37789 2.14421 2.46222 + vertex 1.37301 2.14385 2.46475 + endloop + endfacet + facet normal 0.283221 0.708068 0.646859 + outer loop + vertex 1.37789 2.14421 2.46222 + vertex 1.37443 2.14668 2.46103 + vertex 1.37301 2.14385 2.46475 + endloop + endfacet + facet normal 0.189027 0.790526 0.582527 + outer loop + vertex 1.37473 2.14137 2.46756 + vertex 1.37301 2.14385 2.46475 + vertex 1.37069 2.14159 2.46857 + endloop + endfacet + facet normal 0.139993 0.700369 -0.699918 + outer loop + vertex 1.375 2.15 2.45963 + vertex 1.375 2.15037 2.46 + vertex 1.37685 2.15 2.46 + endloop + endfacet + facet normal 0.0258181 0.129165 0.991287 + outer loop + vertex 1.37685 2.15 2.46 + vertex 1.375 2.15037 2.46 + vertex 1.37181 2.1485 2.46033 + endloop + endfacet + facet normal 0.0901236 -0.509167 0.855936 + outer loop + vertex 1.385 0.883123 2.46 + vertex 1.38252 0.883188 2.4603 + vertex 1.38 0.882238 2.46 + endloop + endfacet + facet normal 0.197677 -0.730531 0.653642 + outer loop + vertex 1.38252 0.883188 2.4603 + vertex 1.37702 0.882491 2.46118 + vertex 1.38 0.882238 2.46 + endloop + endfacet + facet normal 0.178055 -0.899934 0.398014 + outer loop + vertex 1.38252 0.883188 2.4603 + vertex 1.37961 0.883997 2.46343 + vertex 1.37702 0.882491 2.46118 + endloop + endfacet + facet normal 0.202219 -0.886174 0.416896 + outer loop + vertex 1.3836 0.884333 2.46221 + vertex 1.37961 0.883997 2.46343 + vertex 1.38252 0.883188 2.4603 + endloop + endfacet + facet normal 0.199282 -0.892017 0.405699 + outer loop + vertex 1.37961 0.883997 2.46343 + vertex 1.3836 0.884333 2.46221 + vertex 1.38274 0.885605 2.46543 + endloop + endfacet + facet normal 0.190491 -0.888801 0.416828 + outer loop + vertex 1.37783 0.885428 2.46729 + vertex 1.37961 0.883997 2.46343 + vertex 1.38274 0.885605 2.46543 + endloop + endfacet + facet normal 0.211892 -0.853252 0.47651 + outer loop + vertex 1.38274 0.885605 2.46543 + vertex 1.38159 0.887689 2.46967 + vertex 1.37783 0.885428 2.46729 + endloop + endfacet + facet normal 0.192576 -0.844879 0.499094 + outer loop + vertex 1.38159 0.887689 2.46967 + vertex 1.37601 0.887221 2.47103 + vertex 1.37783 0.885428 2.46729 + endloop + endfacet + facet normal 0.21229 -0.765739 0.607105 + outer loop + vertex 1.38159 0.887689 2.46967 + vertex 1.37921 0.890023 2.47345 + vertex 1.37601 0.887221 2.47103 + endloop + endfacet + facet normal 0.171851 -0.785851 0.594058 + outer loop + vertex 1.38418 0.890255 2.47232 + vertex 1.37921 0.890023 2.47345 + vertex 1.38159 0.887689 2.46967 + endloop + endfacet + facet normal 0.189702 -0.661074 0.725944 + outer loop + vertex 1.37989 0.892687 2.4757 + vertex 1.37626 0.891711 2.47576 + vertex 1.37921 0.890023 2.47345 + endloop + endfacet + facet normal 0.176544 -0.660773 0.729528 + outer loop + vertex 1.37989 0.892687 2.4757 + vertex 1.37921 0.890023 2.47345 + vertex 1.38325 0.8926 2.4748 + endloop + endfacet + facet normal 0.193214 -0.676806 0.710354 + outer loop + vertex 1.38325 0.8926 2.4748 + vertex 1.37921 0.890023 2.47345 + vertex 1.38418 0.890255 2.47232 + endloop + endfacet + facet normal 0.155895 -0.5288 0.834307 + outer loop + vertex 1.37989 0.892687 2.4757 + vertex 1.37887 0.894931 2.47731 + vertex 1.37626 0.891711 2.47576 + endloop + endfacet + facet normal 0.197233 -0.568782 0.79849 + outer loop + vertex 1.38325 0.8926 2.4748 + vertex 1.3823 0.894767 2.47658 + vertex 1.37989 0.892687 2.4757 + endloop + endfacet + facet normal -0.137015 0.948869 0.284386 + outer loop + vertex 1.385 0.994223 2.495 + vertex 1.38 0.993501 2.495 + vertex 1.38256 0.993344 2.49676 + endloop + endfacet + facet normal -0.165699 0.931216 0.324623 + outer loop + vertex 1.38256 0.993344 2.49676 + vertex 1.38 0.993501 2.495 + vertex 1.37835 0.992422 2.49725 + endloop + endfacet + facet normal -0.180507 0.953823 0.240082 + outer loop + vertex 1.38256 0.993344 2.49676 + vertex 1.37835 0.992422 2.49725 + vertex 1.38323 0.992369 2.50113 + endloop + endfacet + facet normal -0.173232 0.957413 0.230978 + outer loop + vertex 1.38323 0.992369 2.50113 + vertex 1.37835 0.992422 2.49725 + vertex 1.378 0.991393 2.50125 + endloop + endfacet + facet normal -0.150492 0.865633 0.477527 + outer loop + vertex 1.38323 0.992369 2.50113 + vertex 1.378 0.991393 2.50125 + vertex 1.38256 0.990197 2.50486 + endloop + endfacet + facet normal -0.0770123 0.913146 0.400291 + outer loop + vertex 1.38256 0.990197 2.50486 + vertex 1.378 0.991393 2.50125 + vertex 1.37732 0.989705 2.50497 + endloop + endfacet + facet normal 0.0197205 0.666722 0.745045 + outer loop + vertex 1.38092 0.987236 2.50709 + vertex 1.37732 0.989705 2.50497 + vertex 1.37565 0.987053 2.50739 + endloop + endfacet + facet normal -0.040573 0.615049 0.787444 + outer loop + vertex 1.38256 0.990197 2.50486 + vertex 1.37732 0.989705 2.50497 + vertex 1.38092 0.987236 2.50709 + endloop + endfacet + facet normal -0.0970687 -0.577825 -0.810368 + outer loop + vertex 1.385 2.03583 2.495 + vertex 1.38298 2.03348 2.49692 + vertex 1.38 2.03667 2.495 + endloop + endfacet + facet normal -0.149488 -0.608227 -0.77956 + outer loop + vertex 1.38298 2.03348 2.49692 + vertex 1.37823 2.03412 2.49733 + vertex 1.38 2.03667 2.495 + endloop + endfacet + facet normal -0.136231 -0.990113 -0.0334326 + outer loop + vertex 1.38298 2.03348 2.49692 + vertex 1.38209 2.03346 2.50128 + vertex 1.37823 2.03412 2.49733 + endloop + endfacet + facet normal -0.130821 -0.990646 -0.0388012 + outer loop + vertex 1.38209 2.03346 2.50128 + vertex 1.37723 2.03409 2.50154 + vertex 1.37823 2.03412 2.49733 + endloop + endfacet + facet normal -0.109228 -0.954656 0.276948 + outer loop + vertex 1.38209 2.03346 2.50128 + vertex 1.38041 2.03508 2.5062 + vertex 1.37723 2.03409 2.50154 + endloop + endfacet + facet normal 0.0200443 -0.980753 0.194221 + outer loop + vertex 1.38041 2.03508 2.5062 + vertex 1.37584 2.03481 2.50534 + vertex 1.37723 2.03409 2.50154 + endloop + endfacet + facet normal 0.458283 -0.780883 0.424499 + outer loop + vertex 1.37986 2.03657 2.50953 + vertex 1.38041 2.03508 2.5062 + vertex 1.38316 2.03802 2.50865 + endloop + endfacet + facet normal 0.0236858 -0.911303 0.411054 + outer loop + vertex 1.37986 2.03657 2.50953 + vertex 1.37678 2.03621 2.50893 + vertex 1.38041 2.03508 2.5062 + endloop + endfacet + facet normal -0.0154764 -0.930155 0.36684 + outer loop + vertex 1.37678 2.03621 2.50893 + vertex 1.37584 2.03481 2.50534 + vertex 1.38041 2.03508 2.5062 + endloop + endfacet + facet normal 0.0333075 -0.92782 0.371537 + outer loop + vertex 1.37986 2.03657 2.50953 + vertex 1.37853 2.03689 2.51045 + vertex 1.37678 2.03621 2.50893 + endloop + endfacet + facet normal 0.129526 0.363982 0.922356 + outer loop + vertex 1.37956 2.12364 2.48088 + vertex 1.38345 2.12271 2.4807 + vertex 1.38295 2.12602 2.47946 + endloop + endfacet + facet normal 0.129623 0.363865 0.922388 + outer loop + vertex 1.37807 2.12759 2.47953 + vertex 1.37956 2.12364 2.48088 + vertex 1.38295 2.12602 2.47946 + endloop + endfacet + facet normal 0.12489 0.33894 0.932482 + outer loop + vertex 1.38134 2.11954 2.48213 + vertex 1.37956 2.12364 2.48088 + vertex 1.37631 2.12085 2.48233 + endloop + endfacet + facet normal 0.123959 0.33861 0.932726 + outer loop + vertex 1.38345 2.12271 2.4807 + vertex 1.37956 2.12364 2.48088 + vertex 1.38134 2.11954 2.48213 + endloop + endfacet + facet normal 0.149262 0.426502 0.892086 + outer loop + vertex 1.38295 2.12602 2.47946 + vertex 1.38186 2.13016 2.47766 + vertex 1.37807 2.12759 2.47953 + endloop + endfacet + facet normal 0.142353 0.434656 0.889275 + outer loop + vertex 1.37807 2.12759 2.47953 + vertex 1.38186 2.13016 2.47766 + vertex 1.37626 2.13144 2.47794 + endloop + endfacet + facet normal 0.154167 0.653945 0.740667 + outer loop + vertex 1.37918 2.13369 2.47589 + vertex 1.38338 2.13288 2.47573 + vertex 1.38222 2.13568 2.4735 + endloop + endfacet + facet normal 0.153181 0.654794 0.740122 + outer loop + vertex 1.37689 2.13649 2.47389 + vertex 1.37918 2.13369 2.47589 + vertex 1.38222 2.13568 2.4735 + endloop + endfacet + facet normal 0.163053 0.538887 0.826447 + outer loop + vertex 1.38186 2.13016 2.47766 + vertex 1.37918 2.13369 2.47589 + vertex 1.37626 2.13144 2.47794 + endloop + endfacet + facet normal 0.132821 0.523529 0.841591 + outer loop + vertex 1.38338 2.13288 2.47573 + vertex 1.37918 2.13369 2.47589 + vertex 1.38186 2.13016 2.47766 + endloop + endfacet + facet normal 0.151592 0.869473 0.470146 + outer loop + vertex 1.37909 2.14017 2.46815 + vertex 1.38456 2.13994 2.46681 + vertex 1.38117 2.14191 2.46426 + endloop + endfacet + facet normal 0.180073 0.858373 0.480385 + outer loop + vertex 1.37714 2.1422 2.46526 + vertex 1.37909 2.14017 2.46815 + vertex 1.38117 2.14191 2.46426 + endloop + endfacet + facet normal 0.160131 0.845794 0.508911 + outer loop + vertex 1.38456 2.13994 2.46681 + vertex 1.37909 2.14017 2.46815 + vertex 1.38322 2.1381 2.47029 + endloop + endfacet + facet normal 0.141538 0.83397 0.533349 + outer loop + vertex 1.38322 2.1381 2.47029 + vertex 1.37909 2.14017 2.46815 + vertex 1.37902 2.13805 2.47148 + endloop + endfacet + facet normal 0.161014 0.757321 0.632882 + outer loop + vertex 1.38222 2.13568 2.4735 + vertex 1.37902 2.13805 2.47148 + vertex 1.37689 2.13649 2.47389 + endloop + endfacet + facet normal 0.168437 0.761433 0.625978 + outer loop + vertex 1.38322 2.1381 2.47029 + vertex 1.37902 2.13805 2.47148 + vertex 1.38222 2.13568 2.4735 + endloop + endfacet + facet normal 0.0623016 0.217832 0.973996 + outer loop + vertex 1.385 2.14786 2.46 + vertex 1.38 2.14929 2.46 + vertex 1.38272 2.14416 2.46097 + endloop + endfacet + facet normal 0.241317 0.302931 0.921954 + outer loop + vertex 1.38272 2.14416 2.46097 + vertex 1.38 2.14929 2.46 + vertex 1.37789 2.14421 2.46222 + endloop + endfacet + facet normal 0.198931 0.793605 0.574993 + outer loop + vertex 1.38117 2.14191 2.46426 + vertex 1.37789 2.14421 2.46222 + vertex 1.37714 2.1422 2.46526 + endloop + endfacet + facet normal 0.165303 0.775783 0.608962 + outer loop + vertex 1.38272 2.14416 2.46097 + vertex 1.37789 2.14421 2.46222 + vertex 1.38117 2.14191 2.46426 + endloop + endfacet + facet normal 0.0847072 0.574742 0.813939 + outer loop + vertex 1.38625 0.884035 2.46028 + vertex 1.39 0.883881 2.46 + vertex 1.38985 0.884522 2.45956 + endloop + endfacet + facet normal 0.0621204 -0.252709 0.965546 + outer loop + vertex 1.38625 0.884035 2.46028 + vertex 1.38252 0.883188 2.4603 + vertex 1.39 0.883881 2.46 + endloop + endfacet + facet normal 0.0849216 -0.560174 0.82401 + outer loop + vertex 1.38252 0.883188 2.4603 + vertex 1.385 0.883123 2.46 + vertex 1.39 0.883881 2.46 + endloop + endfacet + facet normal 0.203229 -0.886204 0.416341 + outer loop + vertex 1.38625 0.884035 2.46028 + vertex 1.3836 0.884333 2.46221 + vertex 1.38252 0.883188 2.4603 + endloop + endfacet + facet normal 0.201905 -0.890423 0.407899 + outer loop + vertex 1.38985 0.884522 2.45956 + vertex 1.38822 0.885453 2.4624 + vertex 1.38625 0.884035 2.46028 + endloop + endfacet + facet normal 0.198632 -0.889919 0.410598 + outer loop + vertex 1.3836 0.884333 2.46221 + vertex 1.38625 0.884035 2.46028 + vertex 1.38822 0.885453 2.4624 + endloop + endfacet + facet normal 0.199344 -0.891999 0.405709 + outer loop + vertex 1.3836 0.884333 2.46221 + vertex 1.38822 0.885453 2.4624 + vertex 1.38274 0.885605 2.46543 + endloop + endfacet + facet normal 0.204878 -0.886249 0.415437 + outer loop + vertex 1.38274 0.885605 2.46543 + vertex 1.38822 0.885453 2.4624 + vertex 1.38635 0.88719 2.46703 + endloop + endfacet + facet normal 0.18252 -0.852704 0.489472 + outer loop + vertex 1.3857 0.888766 2.47002 + vertex 1.38635 0.88719 2.46703 + vertex 1.38933 0.888858 2.46882 + endloop + endfacet + facet normal 0.182252 -0.852773 0.489451 + outer loop + vertex 1.3857 0.888766 2.47002 + vertex 1.38159 0.887689 2.46967 + vertex 1.38635 0.88719 2.46703 + endloop + endfacet + facet normal 0.170887 -0.865234 0.471346 + outer loop + vertex 1.38159 0.887689 2.46967 + vertex 1.38274 0.885605 2.46543 + vertex 1.38635 0.88719 2.46703 + endloop + endfacet + facet normal 0.15323 -0.780075 0.606633 + outer loop + vertex 1.3857 0.888766 2.47002 + vertex 1.38418 0.890255 2.47232 + vertex 1.38159 0.887689 2.46967 + endloop + endfacet + facet normal 0.208822 -0.791723 0.574079 + outer loop + vertex 1.38933 0.888858 2.46882 + vertex 1.38782 0.890256 2.4713 + vertex 1.3857 0.888766 2.47002 + endloop + endfacet + facet normal 0.171104 -0.771437 0.612869 + outer loop + vertex 1.38782 0.890256 2.4713 + vertex 1.38418 0.890255 2.47232 + vertex 1.3857 0.888766 2.47002 + endloop + endfacet + facet normal 0.194853 -0.689032 0.698045 + outer loop + vertex 1.38782 0.890256 2.4713 + vertex 1.38829 0.892806 2.47369 + vertex 1.38418 0.890255 2.47232 + endloop + endfacet + facet normal 0.185019 -0.679561 0.709905 + outer loop + vertex 1.38829 0.892806 2.47369 + vertex 1.38325 0.8926 2.4748 + vertex 1.38418 0.890255 2.47232 + endloop + endfacet + facet normal -0.381338 0.804859 0.454734 + outer loop + vertex 1.38602 0.994172 2.49595 + vertex 1.38664 0.995 2.495 + vertex 1.385 0.994223 2.495 + endloop + endfacet + facet normal -0.172886 0.955714 0.23816 + outer loop + vertex 1.38256 0.993344 2.49676 + vertex 1.38602 0.994172 2.49595 + vertex 1.385 0.994223 2.495 + endloop + endfacet + facet normal -0.204461 0.971534 0.119651 + outer loop + vertex 1.38605 0.993766 2.49929 + vertex 1.38602 0.994172 2.49595 + vertex 1.38256 0.993344 2.49676 + endloop + endfacet + facet normal -0.293343 0.922659 0.250301 + outer loop + vertex 1.38323 0.992369 2.50113 + vertex 1.38605 0.993766 2.49929 + vertex 1.38256 0.993344 2.49676 + endloop + endfacet + facet normal -0.260432 0.918527 0.297461 + outer loop + vertex 1.38745 0.993149 2.50242 + vertex 1.38605 0.993766 2.49929 + vertex 1.38323 0.992369 2.50113 + endloop + endfacet + facet normal -0.319285 0.729434 0.604966 + outer loop + vertex 1.38745 0.993149 2.50242 + vertex 1.38323 0.992369 2.50113 + vertex 1.3881 0.991265 2.50503 + endloop + endfacet + facet normal -0.181331 0.863452 0.470712 + outer loop + vertex 1.3881 0.991265 2.50503 + vertex 1.38323 0.992369 2.50113 + vertex 1.38256 0.990197 2.50486 + endloop + endfacet + facet normal -0.0311451 0.611956 0.790279 + outer loop + vertex 1.38644 0.98781 2.50686 + vertex 1.38256 0.990197 2.50486 + vertex 1.38092 0.987236 2.50709 + endloop + endfacet + facet normal -0.12514 0.510131 0.850945 + outer loop + vertex 1.3881 0.991265 2.50503 + vertex 1.38256 0.990197 2.50486 + vertex 1.38644 0.98781 2.50686 + endloop + endfacet + facet normal 0.1012 0.953656 0.283371 + outer loop + vertex 1.39 0.995 2.4938 + vertex 1.38664 0.995 2.495 + vertex 1.38951 0.994668 2.49509 + endloop + endfacet + facet normal -0.135923 0.990518 0.0199968 + outer loop + vertex 1.38951 0.994668 2.49509 + vertex 1.38602 0.994172 2.49595 + vertex 1.38927 0.994568 2.49842 + endloop + endfacet + facet normal 0.0627499 0.731179 0.679294 + outer loop + vertex 1.38664 0.995 2.495 + vertex 1.38602 0.994172 2.49595 + vertex 1.38951 0.994668 2.49509 + endloop + endfacet + facet normal -0.199412 0.967755 0.153896 + outer loop + vertex 1.38927 0.994568 2.49842 + vertex 1.38605 0.993766 2.49929 + vertex 1.38921 0.994085 2.50138 + endloop + endfacet + facet normal -0.209313 0.970511 0.119567 + outer loop + vertex 1.38602 0.994172 2.49595 + vertex 1.38605 0.993766 2.49929 + vertex 1.38927 0.994568 2.49842 + endloop + endfacet + facet normal -0.296537 0.903115 0.310562 + outer loop + vertex 1.38921 0.994085 2.50138 + vertex 1.38605 0.993766 2.49929 + vertex 1.38745 0.993149 2.50242 + endloop + endfacet + facet normal -0.0266584 -0.341728 -0.939421 + outer loop + vertex 1.39 2.03544 2.495 + vertex 1.38729 2.03312 2.49592 + vertex 1.385 2.03583 2.495 + endloop + endfacet + facet normal -0.235207 -0.484893 -0.842352 + outer loop + vertex 1.38729 2.03312 2.49592 + vertex 1.38298 2.03348 2.49692 + vertex 1.385 2.03583 2.495 + endloop + endfacet + facet normal -0.124259 -0.974248 -0.188151 + outer loop + vertex 1.38729 2.03312 2.49592 + vertex 1.38652 2.03241 2.50011 + vertex 1.38298 2.03348 2.49692 + endloop + endfacet + facet normal -0.242425 -0.968611 -0.0549807 + outer loop + vertex 1.38652 2.03241 2.50011 + vertex 1.38209 2.03346 2.50128 + vertex 1.38298 2.03348 2.49692 + endloop + endfacet + facet normal -0.144368 -0.944253 0.29588 + outer loop + vertex 1.38652 2.03241 2.50011 + vertex 1.38614 2.03406 2.50517 + vertex 1.38209 2.03346 2.50128 + endloop + endfacet + facet normal -0.12082 -0.954417 0.272931 + outer loop + vertex 1.38614 2.03406 2.50517 + vertex 1.38041 2.03508 2.5062 + vertex 1.38209 2.03346 2.50128 + endloop + endfacet + facet normal 0.0205483 -0.650793 0.758977 + outer loop + vertex 1.38614 2.03406 2.50517 + vertex 1.38316 2.03802 2.50865 + vertex 1.38041 2.03508 2.5062 + endloop + endfacet + facet normal -0.0578843 -0.682914 0.728202 + outer loop + vertex 1.3895 2.03675 2.50796 + vertex 1.38316 2.03802 2.50865 + vertex 1.38614 2.03406 2.50517 + endloop + endfacet + facet normal 0.0633695 0.322738 0.944365 + outer loop + vertex 1.3833 2.05356 2.50487 + vertex 1.38704 2.05664 2.50357 + vertex 1.38225 2.05731 2.50366 + endloop + endfacet + facet normal 0.0673259 0.338923 0.938402 + outer loop + vertex 1.38843 2.10786 2.48572 + vertex 1.38445 2.10849 2.48578 + vertex 1.38615 2.10447 2.48711 + endloop + endfacet + facet normal 0.0749773 0.362593 0.928926 + outer loop + vertex 1.38962 2.11982 2.48122 + vertex 1.38757 2.12383 2.47982 + vertex 1.38557 2.12046 2.4813 + endloop + endfacet + facet normal 0.0731461 0.350298 0.933778 + outer loop + vertex 1.38557 2.12046 2.4813 + vertex 1.38575 2.11649 2.48278 + vertex 1.38962 2.11982 2.48122 + endloop + endfacet + facet normal 0.105771 0.350537 0.930557 + outer loop + vertex 1.38557 2.12046 2.4813 + vertex 1.38134 2.11954 2.48213 + vertex 1.38575 2.11649 2.48278 + endloop + endfacet + facet normal 0.103093 0.347337 0.932056 + outer loop + vertex 1.38345 2.12271 2.4807 + vertex 1.38557 2.12046 2.4813 + vertex 1.38757 2.12383 2.47982 + endloop + endfacet + facet normal 0.09832 0.361124 0.92732 + outer loop + vertex 1.38345 2.12271 2.4807 + vertex 1.38757 2.12383 2.47982 + vertex 1.38295 2.12602 2.47946 + endloop + endfacet + facet normal 0.117622 0.39882 0.909455 + outer loop + vertex 1.38295 2.12602 2.47946 + vertex 1.38757 2.12383 2.47982 + vertex 1.38669 2.12801 2.47811 + endloop + endfacet + facet normal 0.105997 0.349743 0.93083 + outer loop + vertex 1.38557 2.12046 2.4813 + vertex 1.38345 2.12271 2.4807 + vertex 1.38134 2.11954 2.48213 + endloop + endfacet + facet normal 0.121155 0.580434 0.805244 + outer loop + vertex 1.38969 2.13019 2.47662 + vertex 1.38735 2.13339 2.47466 + vertex 1.38593 2.13097 2.47662 + endloop + endfacet + facet normal 0.0975055 0.465642 0.879585 + outer loop + vertex 1.38593 2.13097 2.47662 + vertex 1.38669 2.12801 2.47811 + vertex 1.38969 2.13019 2.47662 + endloop + endfacet + facet normal 0.129939 0.470482 0.87279 + outer loop + vertex 1.38593 2.13097 2.47662 + vertex 1.38186 2.13016 2.47766 + vertex 1.38669 2.12801 2.47811 + endloop + endfacet + facet normal 0.104231 0.418929 0.902017 + outer loop + vertex 1.38186 2.13016 2.47766 + vertex 1.38295 2.12602 2.47946 + vertex 1.38669 2.12801 2.47811 + endloop + endfacet + facet normal 0.144574 0.569798 0.808968 + outer loop + vertex 1.38338 2.13288 2.47573 + vertex 1.38593 2.13097 2.47662 + vertex 1.38735 2.13339 2.47466 + endloop + endfacet + facet normal 0.118938 0.648317 0.752023 + outer loop + vertex 1.38338 2.13288 2.47573 + vertex 1.38735 2.13339 2.47466 + vertex 1.38222 2.13568 2.4735 + endloop + endfacet + facet normal 0.151602 0.696112 0.701745 + outer loop + vertex 1.38222 2.13568 2.4735 + vertex 1.38735 2.13339 2.47466 + vertex 1.38644 2.13614 2.47213 + endloop + endfacet + facet normal 0.108265 0.534767 0.838035 + outer loop + vertex 1.38593 2.13097 2.47662 + vertex 1.38338 2.13288 2.47573 + vertex 1.38186 2.13016 2.47766 + endloop + endfacet + facet normal 0.148775 0.87881 0.453386 + outer loop + vertex 1.38456 2.13994 2.46681 + vertex 1.38989 2.13967 2.46558 + vertex 1.38596 2.14161 2.46311 + endloop + endfacet + facet normal 0.164121 0.874149 0.457085 + outer loop + vertex 1.38117 2.14191 2.46426 + vertex 1.38456 2.13994 2.46681 + vertex 1.38596 2.14161 2.46311 + endloop + endfacet + facet normal 0.155198 0.860388 0.485435 + outer loop + vertex 1.38989 2.13967 2.46558 + vertex 1.38456 2.13994 2.46681 + vertex 1.38809 2.13784 2.4694 + endloop + endfacet + facet normal 0.137169 0.852839 0.503836 + outer loop + vertex 1.38809 2.13784 2.4694 + vertex 1.38456 2.13994 2.46681 + vertex 1.38322 2.1381 2.47029 + endloop + endfacet + facet normal 0.11638 0.775611 0.620389 + outer loop + vertex 1.38644 2.13614 2.47213 + vertex 1.38322 2.1381 2.47029 + vertex 1.38222 2.13568 2.4735 + endloop + endfacet + facet normal 0.149162 0.796759 0.585598 + outer loop + vertex 1.38809 2.13784 2.4694 + vertex 1.38322 2.1381 2.47029 + vertex 1.38644 2.13614 2.47213 + endloop + endfacet + facet normal 0.00712085 0.0374742 0.999272 + outer loop + vertex 1.39 2.14691 2.46 + vertex 1.385 2.14786 2.46 + vertex 1.38814 2.1437 2.46013 + endloop + endfacet + facet normal 0.164246 0.155134 0.974144 + outer loop + vertex 1.38814 2.1437 2.46013 + vertex 1.385 2.14786 2.46 + vertex 1.38272 2.14416 2.46097 + endloop + endfacet + facet normal 0.195326 0.763914 0.615047 + outer loop + vertex 1.38596 2.14161 2.46311 + vertex 1.38272 2.14416 2.46097 + vertex 1.38117 2.14191 2.46426 + endloop + endfacet + facet normal 0.163537 0.747557 0.64375 + outer loop + vertex 1.38814 2.1437 2.46013 + vertex 1.38272 2.14416 2.46097 + vertex 1.38596 2.14161 2.46311 + endloop + endfacet + facet normal 0.270276 -0.681117 -0.680464 + outer loop + vertex 1.39282 0.885 2.46 + vertex 1.39 0.883881 2.46 + vertex 1.39 0.885 2.45888 + endloop + endfacet + facet normal -0.205089 0.516841 0.831152 + outer loop + vertex 1.39282 0.885 2.46 + vertex 1.38985 0.884522 2.45956 + vertex 1.39 0.883881 2.46 + endloop + endfacet + facet normal -0.19617 0.404962 0.893042 + outer loop + vertex 1.38985 0.884522 2.45956 + vertex 1.39282 0.885 2.46 + vertex 1.395 0.886056 2.46 + endloop + endfacet + facet normal 0.226451 -0.879568 0.418425 + outer loop + vertex 1.38985 0.884522 2.45956 + vertex 1.395 0.886056 2.46 + vertex 1.38822 0.885453 2.4624 + endloop + endfacet + facet normal 0.184725 -0.940455 0.285343 + outer loop + vertex 1.38822 0.885453 2.4624 + vertex 1.395 0.886056 2.46 + vertex 1.39259 0.886181 2.46197 + endloop + endfacet + facet normal 0.188638 -0.899925 0.39313 + outer loop + vertex 1.39259 0.886181 2.46197 + vertex 1.39151 0.887301 2.46505 + vertex 1.38822 0.885453 2.4624 + endloop + endfacet + facet normal 0.175269 -0.896336 0.407261 + outer loop + vertex 1.39151 0.887301 2.46505 + vertex 1.38635 0.88719 2.46703 + vertex 1.38822 0.885453 2.4624 + endloop + endfacet + facet normal 0.198449 -0.860147 0.469856 + outer loop + vertex 1.39151 0.887301 2.46505 + vertex 1.38933 0.888858 2.46882 + vertex 1.38635 0.88719 2.46703 + endloop + endfacet + facet normal 0.173355 -0.870937 0.459801 + outer loop + vertex 1.39315 0.889054 2.46775 + vertex 1.38933 0.888858 2.46882 + vertex 1.39151 0.887301 2.46505 + endloop + endfacet + facet normal 0.201603 -0.792907 0.575026 + outer loop + vertex 1.38933 0.888858 2.46882 + vertex 1.39315 0.889054 2.46775 + vertex 1.39229 0.891012 2.47076 + endloop + endfacet + facet normal 0.2041 -0.79408 0.57252 + outer loop + vertex 1.38782 0.890256 2.4713 + vertex 1.38933 0.888858 2.46882 + vertex 1.39229 0.891012 2.47076 + endloop + endfacet + facet normal 0.201382 -0.688752 0.696467 + outer loop + vertex 1.39229 0.891012 2.47076 + vertex 1.38829 0.892806 2.47369 + vertex 1.38782 0.890256 2.4713 + endloop + endfacet + facet normal 0.185292 -0.70508 0.684492 + outer loop + vertex 1.39385 0.894069 2.47348 + vertex 1.38829 0.892806 2.47369 + vertex 1.39229 0.891012 2.47076 + endloop + endfacet + facet normal 0.162435 -0.586699 0.793347 + outer loop + vertex 1.38829 0.892806 2.47369 + vertex 1.39385 0.894069 2.47348 + vertex 1.39124 0.896476 2.4758 + endloop + endfacet + facet normal 0.1388 -0.490202 0.860486 + outer loop + vertex 1.39435 0.900136 2.47738 + vertex 1.38929 0.899514 2.47784 + vertex 1.39124 0.896476 2.4758 + endloop + endfacet + facet normal -0.238097 0.682683 0.690836 + outer loop + vertex 1.3881 0.991265 2.50503 + vertex 1.39253 0.991869 2.50597 + vertex 1.39079 0.99326 2.50399 + endloop + endfacet + facet normal -0.308848 0.733579 0.605372 + outer loop + vertex 1.38745 0.993149 2.50242 + vertex 1.3881 0.991265 2.50503 + vertex 1.39079 0.99326 2.50399 + endloop + endfacet + facet normal -0.0927776 0.49995 0.86107 + outer loop + vertex 1.39242 0.988861 2.5069 + vertex 1.3881 0.991265 2.50503 + vertex 1.38644 0.98781 2.50686 + endloop + endfacet + facet normal -0.234788 0.294924 0.926226 + outer loop + vertex 1.39253 0.991869 2.50597 + vertex 1.3881 0.991265 2.50503 + vertex 1.39242 0.988861 2.5069 + endloop + endfacet + facet normal -0.012666 0.977372 -0.211148 + outer loop + vertex 1.39 0.995 2.4938 + vertex 1.39395 0.995181 2.4944 + vertex 1.395 0.995 2.4935 + endloop + endfacet + facet normal -0.0782249 0.972255 0.220455 + outer loop + vertex 1.38951 0.994668 2.49509 + vertex 1.39395 0.995181 2.4944 + vertex 1.39 0.995 2.4938 + endloop + endfacet + facet normal -0.116894 0.99306 -0.0129597 + outer loop + vertex 1.39395 0.995181 2.4944 + vertex 1.38951 0.994668 2.49509 + vertex 1.3934 0.995162 2.49791 + endloop + endfacet + facet normal -0.14014 0.989936 0.019676 + outer loop + vertex 1.3934 0.995162 2.49791 + vertex 1.38951 0.994668 2.49509 + vertex 1.38927 0.994568 2.49842 + endloop + endfacet + facet normal -0.122973 0.981367 0.147636 + outer loop + vertex 1.3934 0.995162 2.49791 + vertex 1.38927 0.994568 2.49842 + vertex 1.39308 0.994498 2.50206 + endloop + endfacet + facet normal -0.132072 0.978708 0.15712 + outer loop + vertex 1.39308 0.994498 2.50206 + vertex 1.38927 0.994568 2.49842 + vertex 1.38921 0.994085 2.50138 + endloop + endfacet + facet normal -0.223963 0.88219 0.414225 + outer loop + vertex 1.39079 0.99326 2.50399 + vertex 1.38921 0.994085 2.50138 + vertex 1.38745 0.993149 2.50242 + endloop + endfacet + facet normal -0.16475 0.907504 0.386386 + outer loop + vertex 1.39308 0.994498 2.50206 + vertex 1.38921 0.994085 2.50138 + vertex 1.39079 0.99326 2.50399 + endloop + endfacet + facet normal -0.337695 -0.355353 -0.8716 + outer loop + vertex 1.39607 2.03237 2.49399 + vertex 1.39069 2.035 2.495 + vertex 1.395 2.035 2.49333 + endloop + endfacet + facet normal -0.454939 -0.740769 -0.494259 + outer loop + vertex 1.39434 2.03095 2.49771 + vertex 1.39069 2.035 2.495 + vertex 1.39607 2.03237 2.49399 + endloop + endfacet + facet normal -0.271327 -0.692233 -0.668726 + outer loop + vertex 1.39032 2.03164 2.49863 + vertex 1.39069 2.035 2.495 + vertex 1.39434 2.03095 2.49771 + endloop + endfacet + facet normal -0.194254 -0.973881 -0.117565 + outer loop + vertex 1.39346 2.03058 2.5022 + vertex 1.39032 2.03164 2.49863 + vertex 1.39434 2.03095 2.49771 + endloop + endfacet + facet normal -0.313697 -0.949509 -0.00515648 + outer loop + vertex 1.38996 2.03174 2.50318 + vertex 1.39032 2.03164 2.49863 + vertex 1.39346 2.03058 2.5022 + endloop + endfacet + facet normal -0.235548 -0.937148 0.257431 + outer loop + vertex 1.39279 2.03162 2.50534 + vertex 1.38996 2.03174 2.50318 + vertex 1.39346 2.03058 2.5022 + endloop + endfacet + facet normal -0.377783 -0.808242 0.451691 + outer loop + vertex 1.39049 2.03322 2.50627 + vertex 1.38996 2.03174 2.50318 + vertex 1.39279 2.03162 2.50534 + endloop + endfacet + facet normal -0.125234 -0.629307 0.767 + outer loop + vertex 1.39279 2.03162 2.50534 + vertex 1.39418 2.03404 2.50755 + vertex 1.39049 2.03322 2.50627 + endloop + endfacet + facet normal 0.224659 -0.726251 -0.649683 + outer loop + vertex 1.39069 2.035 2.495 + vertex 1.39032 2.03164 2.49863 + vertex 1.38729 2.03312 2.49592 + endloop + endfacet + facet normal -0.139863 -0.219384 -0.965562 + outer loop + vertex 1.39 2.03544 2.495 + vertex 1.39069 2.035 2.495 + vertex 1.38729 2.03312 2.49592 + endloop + endfacet + facet normal -0.197075 -0.980377 0.00477106 + outer loop + vertex 1.39032 2.03164 2.49863 + vertex 1.38996 2.03174 2.50318 + vertex 1.38652 2.03241 2.50011 + endloop + endfacet + facet normal -0.272218 -0.939227 -0.209165 + outer loop + vertex 1.38729 2.03312 2.49592 + vertex 1.39032 2.03164 2.49863 + vertex 1.38652 2.03241 2.50011 + endloop + endfacet + facet normal -0.278879 -0.846668 0.453188 + outer loop + vertex 1.38996 2.03174 2.50318 + vertex 1.39049 2.03322 2.50627 + vertex 1.38614 2.03406 2.50517 + endloop + endfacet + facet normal -0.401764 -0.879354 0.255583 + outer loop + vertex 1.38652 2.03241 2.50011 + vertex 1.38996 2.03174 2.50318 + vertex 1.38614 2.03406 2.50517 + endloop + endfacet + facet normal -0.301586 -0.478742 0.824531 + outer loop + vertex 1.39049 2.03322 2.50627 + vertex 1.3895 2.03675 2.50796 + vertex 1.38614 2.03406 2.50517 + endloop + endfacet + facet normal -0.194633 -0.467 0.862571 + outer loop + vertex 1.39049 2.03322 2.50627 + vertex 1.39418 2.03404 2.50755 + vertex 1.3895 2.03675 2.50796 + endloop + endfacet + facet normal 0.053988 0.347026 0.9363 + outer loop + vertex 1.39048 2.10564 2.48643 + vertex 1.38843 2.10786 2.48572 + vertex 1.38615 2.10447 2.48711 + endloop + endfacet + facet normal 0.0637217 0.401845 0.913488 + outer loop + vertex 1.39291 2.12313 2.47976 + vertex 1.39131 2.12684 2.47824 + vertex 1.38757 2.12383 2.47982 + endloop + endfacet + facet normal 0.0727516 0.392402 0.916912 + outer loop + vertex 1.38757 2.12383 2.47982 + vertex 1.39131 2.12684 2.47824 + vertex 1.38669 2.12801 2.47811 + endloop + endfacet + facet normal 0.0754299 0.561765 0.823851 + outer loop + vertex 1.38969 2.13019 2.47662 + vertex 1.39413 2.12966 2.47657 + vertex 1.39183 2.13226 2.47501 + endloop + endfacet + facet normal 0.0774892 0.560276 0.824673 + outer loop + vertex 1.38735 2.13339 2.47466 + vertex 1.38969 2.13019 2.47662 + vertex 1.39183 2.13226 2.47501 + endloop + endfacet + facet normal 0.0935182 0.469879 0.877763 + outer loop + vertex 1.39131 2.12684 2.47824 + vertex 1.38969 2.13019 2.47662 + vertex 1.38669 2.12801 2.47811 + endloop + endfacet + facet normal 0.0637178 0.459449 0.885916 + outer loop + vertex 1.39413 2.12966 2.47657 + vertex 1.38969 2.13019 2.47662 + vertex 1.39131 2.12684 2.47824 + endloop + endfacet + facet normal 0.117969 0.687231 0.716796 + outer loop + vertex 1.39183 2.13226 2.47501 + vertex 1.39124 2.13512 2.47237 + vertex 1.38735 2.13339 2.47466 + endloop + endfacet + facet normal 0.112753 0.692881 0.712182 + outer loop + vertex 1.38735 2.13339 2.47466 + vertex 1.39124 2.13512 2.47237 + vertex 1.38644 2.13614 2.47213 + endloop + endfacet + facet normal 0.096864 0.822898 0.559871 + outer loop + vertex 1.39398 2.14026 2.46301 + vertex 1.39222 2.14225 2.46039 + vertex 1.38991 2.14132 2.46216 + endloop + endfacet + facet normal 0.169062 0.887747 0.428162 + outer loop + vertex 1.38991 2.14132 2.46216 + vertex 1.38596 2.14161 2.46311 + vertex 1.38989 2.13967 2.46558 + endloop + endfacet + facet normal 0.141845 0.891674 0.429881 + outer loop + vertex 1.38991 2.14132 2.46216 + vertex 1.38989 2.13967 2.46558 + vertex 1.39398 2.14026 2.46301 + endloop + endfacet + facet normal 0.12648 0.904045 0.408296 + outer loop + vertex 1.39398 2.14026 2.46301 + vertex 1.38989 2.13967 2.46558 + vertex 1.39359 2.139 2.46592 + endloop + endfacet + facet normal 0.114266 0.871594 0.476725 + outer loop + vertex 1.39359 2.139 2.46592 + vertex 1.38989 2.13967 2.46558 + vertex 1.39323 2.13749 2.46876 + endloop + endfacet + facet normal 0.117887 0.872751 0.473718 + outer loop + vertex 1.39323 2.13749 2.46876 + vertex 1.38989 2.13967 2.46558 + vertex 1.38809 2.13784 2.4694 + endloop + endfacet + facet normal 0.141992 0.799836 0.583181 + outer loop + vertex 1.39124 2.13512 2.47237 + vertex 1.38809 2.13784 2.4694 + vertex 1.38644 2.13614 2.47213 + endloop + endfacet + facet normal 0.127442 0.794496 0.593746 + outer loop + vertex 1.39323 2.13749 2.46876 + vertex 1.38809 2.13784 2.4694 + vertex 1.39124 2.13512 2.47237 + endloop + endfacet + facet normal 0.214163 0.721057 0.658947 + outer loop + vertex 1.39222 2.14225 2.46039 + vertex 1.38814 2.1437 2.46013 + vertex 1.38991 2.14132 2.46216 + endloop + endfacet + facet normal -0.0242919 0.108822 0.993764 + outer loop + vertex 1.39222 2.14225 2.46039 + vertex 1.395 2.14645 2.46 + vertex 1.38814 2.1437 2.46013 + endloop + endfacet + facet normal 0.0036326 0.0394925 0.999213 + outer loop + vertex 1.395 2.14645 2.46 + vertex 1.39 2.14691 2.46 + vertex 1.38814 2.1437 2.46013 + endloop + endfacet + facet normal 0.211892 0.720504 0.660284 + outer loop + vertex 1.38991 2.14132 2.46216 + vertex 1.38814 2.1437 2.46013 + vertex 1.38596 2.14161 2.46311 + endloop + endfacet + facet normal 0.0677277 -0.932907 0.35369 + outer loop + vertex 1.4 0.886419 2.46 + vertex 1.39643 0.886936 2.46205 + vertex 1.395 0.886056 2.46 + endloop + endfacet + facet normal 0.179842 -0.94314 0.279541 + outer loop + vertex 1.39643 0.886936 2.46205 + vertex 1.39259 0.886181 2.46197 + vertex 1.395 0.886056 2.46 + endloop + endfacet + facet normal 0.170626 -0.899622 0.401955 + outer loop + vertex 1.39557 0.888288 2.46544 + vertex 1.39643 0.886936 2.46205 + vertex 1.39964 0.888501 2.46419 + endloop + endfacet + facet normal 0.179822 -0.897213 0.403328 + outer loop + vertex 1.39557 0.888288 2.46544 + vertex 1.39151 0.887301 2.46505 + vertex 1.39643 0.886936 2.46205 + endloop + endfacet + facet normal 0.170292 -0.905473 0.388741 + outer loop + vertex 1.39151 0.887301 2.46505 + vertex 1.39259 0.886181 2.46197 + vertex 1.39643 0.886936 2.46205 + endloop + endfacet + facet normal 0.167649 -0.870406 0.462912 + outer loop + vertex 1.39557 0.888288 2.46544 + vertex 1.39315 0.889054 2.46775 + vertex 1.39151 0.887301 2.46505 + endloop + endfacet + facet normal 0.194363 -0.851201 0.487525 + outer loop + vertex 1.39964 0.888501 2.46419 + vertex 1.39742 0.890188 2.46802 + vertex 1.39557 0.888288 2.46544 + endloop + endfacet + facet normal 0.19614 -0.851425 0.486421 + outer loop + vertex 1.39315 0.889054 2.46775 + vertex 1.39557 0.888288 2.46544 + vertex 1.39742 0.890188 2.46802 + endloop + endfacet + facet normal 0.177153 -0.800309 0.57282 + outer loop + vertex 1.39315 0.889054 2.46775 + vertex 1.39742 0.890188 2.46802 + vertex 1.39229 0.891012 2.47076 + endloop + endfacet + facet normal 0.193205 -0.779016 0.596494 + outer loop + vertex 1.39229 0.891012 2.47076 + vertex 1.39742 0.890188 2.46802 + vertex 1.39682 0.892471 2.47119 + endloop + endfacet + facet normal 0.158643 -0.701039 0.695254 + outer loop + vertex 1.39682 0.892471 2.47119 + vertex 1.39385 0.894069 2.47348 + vertex 1.39229 0.891012 2.47076 + endloop + endfacet + facet normal 0.169827 -0.690916 0.702705 + outer loop + vertex 1.3992 0.895162 2.47326 + vertex 1.39385 0.894069 2.47348 + vertex 1.39682 0.892471 2.47119 + endloop + endfacet + facet normal 0.154419 -0.598727 0.785927 + outer loop + vertex 1.39385 0.894069 2.47348 + vertex 1.3992 0.895162 2.47326 + vertex 1.39605 0.897228 2.47546 + endloop + endfacet + facet normal 0.149047 -0.596635 0.788551 + outer loop + vertex 1.39124 0.896476 2.4758 + vertex 1.39385 0.894069 2.47348 + vertex 1.39605 0.897228 2.47546 + endloop + endfacet + facet normal 0.137443 -0.489352 0.861188 + outer loop + vertex 1.39605 0.897228 2.47546 + vertex 1.39435 0.900136 2.47738 + vertex 1.39124 0.896476 2.4758 + endloop + endfacet + facet normal 0.123148 -0.496444 0.859289 + outer loop + vertex 1.39882 0.900357 2.47687 + vertex 1.39435 0.900136 2.47738 + vertex 1.39605 0.897228 2.47546 + endloop + endfacet + facet normal 0.00276983 0.812412 -0.583077 + outer loop + vertex 1.4 0.992471 2.49 + vertex 1.395 0.992488 2.49 + vertex 1.395 0.995 2.4935 + endloop + endfacet + facet normal -0.0728515 0.756084 -0.650407 + outer loop + vertex 1.4 0.995 2.49294 + vertex 1.4 0.992471 2.49 + vertex 1.395 0.995 2.4935 + endloop + endfacet + facet normal -0.225706 0.691561 0.686149 + outer loop + vertex 1.39414 0.993287 2.50506 + vertex 1.39079 0.99326 2.50399 + vertex 1.39253 0.991869 2.50597 + endloop + endfacet + facet normal -0.0723782 0.592196 0.802537 + outer loop + vertex 1.39253 0.991869 2.50597 + vertex 1.39623 0.991612 2.50649 + vertex 1.39414 0.993287 2.50506 + endloop + endfacet + facet normal -0.113503 0.297194 0.948047 + outer loop + vertex 1.39253 0.991869 2.50597 + vertex 1.39242 0.988861 2.5069 + vertex 1.39623 0.991612 2.50649 + endloop + endfacet + facet normal -0.00365935 0.151271 0.988486 + outer loop + vertex 1.39242 0.988861 2.5069 + vertex 1.39832 0.988439 2.50698 + vertex 1.39623 0.991612 2.50649 + endloop + endfacet + facet normal -0.0874316 0.618916 -0.780576 + outer loop + vertex 1.395 0.995 2.4935 + vertex 1.4 0.997598 2.495 + vertex 1.4 0.995 2.49294 + endloop + endfacet + facet normal -0.280792 0.824263 -0.491678 + outer loop + vertex 1.39395 0.995181 2.4944 + vertex 1.4 0.997598 2.495 + vertex 1.395 0.995 2.4935 + endloop + endfacet + facet normal -0.37856 0.867758 0.322007 + outer loop + vertex 1.4 0.997598 2.495 + vertex 1.39395 0.995181 2.4944 + vertex 1.39833 0.995937 2.49751 + endloop + endfacet + facet normal -0.156675 0.987463 -0.0192386 + outer loop + vertex 1.39833 0.995937 2.49751 + vertex 1.39395 0.995181 2.4944 + vertex 1.3934 0.995162 2.49791 + endloop + endfacet + facet normal -0.141736 0.978528 0.149648 + outer loop + vertex 1.39833 0.995937 2.49751 + vertex 1.3934 0.995162 2.49791 + vertex 1.39785 0.995248 2.50156 + endloop + endfacet + facet normal -0.138852 0.979475 0.146115 + outer loop + vertex 1.39785 0.995248 2.50156 + vertex 1.3934 0.995162 2.49791 + vertex 1.39308 0.994498 2.50206 + endloop + endfacet + facet normal -0.13948 0.900499 0.411881 + outer loop + vertex 1.39414 0.993287 2.50506 + vertex 1.39308 0.994498 2.50206 + vertex 1.39079 0.99326 2.50399 + endloop + endfacet + facet normal -0.111163 0.907617 0.404813 + outer loop + vertex 1.39414 0.993287 2.50506 + vertex 1.39755 0.993828 2.50479 + vertex 1.39308 0.994498 2.50206 + endloop + endfacet + facet normal -0.102864 0.913864 0.392774 + outer loop + vertex 1.39755 0.993828 2.50479 + vertex 1.39785 0.995248 2.50156 + vertex 1.39308 0.994498 2.50206 + endloop + endfacet + facet normal -0.0351686 0.621622 0.782527 + outer loop + vertex 1.39755 0.993828 2.50479 + vertex 1.39414 0.993287 2.50506 + vertex 1.39623 0.991612 2.50649 + endloop + endfacet + facet normal 0.243652 -0.660308 -0.710372 + outer loop + vertex 1.39607 2.03237 2.49399 + vertex 1.4 2.035 2.49289 + vertex 1.4 2.03273 2.495 + endloop + endfacet + facet normal -0.084338 -0.273658 -0.958122 + outer loop + vertex 1.395 2.035 2.49333 + vertex 1.4 2.035 2.49289 + vertex 1.39607 2.03237 2.49399 + endloop + endfacet + facet normal 0.228435 -0.751353 -0.619101 + outer loop + vertex 1.4 2.03273 2.495 + vertex 1.39876 2.03027 2.49753 + vertex 1.39607 2.03237 2.49399 + endloop + endfacet + facet normal -0.155197 -0.896896 -0.414115 + outer loop + vertex 1.39876 2.03027 2.49753 + vertex 1.39434 2.03095 2.49771 + vertex 1.39607 2.03237 2.49399 + endloop + endfacet + facet normal -0.155322 -0.982557 -0.10226 + outer loop + vertex 1.39876 2.03027 2.49753 + vertex 1.39761 2.02999 2.50194 + vertex 1.39434 2.03095 2.49771 + endloop + endfacet + facet normal -0.146707 -0.983149 -0.109067 + outer loop + vertex 1.39761 2.02999 2.50194 + vertex 1.39346 2.03058 2.5022 + vertex 1.39434 2.03095 2.49771 + endloop + endfacet + facet normal -0.118469 -0.953529 0.277032 + outer loop + vertex 1.39761 2.02999 2.50194 + vertex 1.3963 2.03119 2.5055 + vertex 1.39346 2.03058 2.5022 + endloop + endfacet + facet normal -0.128252 -0.949975 0.28478 + outer loop + vertex 1.3963 2.03119 2.5055 + vertex 1.39279 2.03162 2.50534 + vertex 1.39346 2.03058 2.5022 + endloop + endfacet + facet normal -0.112259 -0.634602 0.764642 + outer loop + vertex 1.3963 2.03119 2.5055 + vertex 1.39418 2.03404 2.50755 + vertex 1.39279 2.03162 2.50534 + endloop + endfacet + facet normal -0.0941871 -0.627248 0.773103 + outer loop + vertex 1.39931 2.03342 2.50767 + vertex 1.39418 2.03404 2.50755 + vertex 1.3963 2.03119 2.5055 + endloop + endfacet + facet normal -0.0529069 -0.797459 -0.601049 + outer loop + vertex 1.4 2.035 2.49289 + vertex 1.395 2.035 2.49333 + vertex 1.395 2.03751 2.49 + endloop + endfacet + facet normal 0.00150947 -0.753711 -0.657204 + outer loop + vertex 1.4 2.03752 2.49 + vertex 1.4 2.035 2.49289 + vertex 1.395 2.03751 2.49 + endloop + endfacet + facet normal 0.0377354 0.398806 0.916259 + outer loop + vertex 1.3979 2.12275 2.47972 + vertex 1.39613 2.12634 2.47823 + vertex 1.39291 2.12313 2.47976 + endloop + endfacet + facet normal 0.0426925 0.394599 0.917861 + outer loop + vertex 1.39291 2.12313 2.47976 + vertex 1.39613 2.12634 2.47823 + vertex 1.39131 2.12684 2.47824 + endloop + endfacet + facet normal 0.052611 0.592273 0.804018 + outer loop + vertex 1.39413 2.12966 2.47657 + vertex 1.39891 2.12947 2.4764 + vertex 1.39611 2.13276 2.47416 + endloop + endfacet + facet normal 0.0949042 0.573101 0.813971 + outer loop + vertex 1.39183 2.13226 2.47501 + vertex 1.39413 2.12966 2.47657 + vertex 1.39611 2.13276 2.47416 + endloop + endfacet + facet normal 0.0504082 0.469988 0.881232 + outer loop + vertex 1.39613 2.12634 2.47823 + vertex 1.39413 2.12966 2.47657 + vertex 1.39131 2.12684 2.47824 + endloop + endfacet + facet normal 0.0505841 0.470067 0.88118 + outer loop + vertex 1.39891 2.12947 2.4764 + vertex 1.39413 2.12966 2.47657 + vertex 1.39613 2.12634 2.47823 + endloop + endfacet + facet normal 0.0931797 0.808437 0.58116 + outer loop + vertex 1.39922 2.13475 2.47181 + vertex 1.39722 2.13658 2.4696 + vertex 1.3954 2.13541 2.47151 + endloop + endfacet + facet normal 0.0681969 0.714786 0.69601 + outer loop + vertex 1.3954 2.13541 2.47151 + vertex 1.39611 2.13276 2.47416 + vertex 1.39922 2.13475 2.47181 + endloop + endfacet + facet normal 0.0924403 0.716589 0.691342 + outer loop + vertex 1.3954 2.13541 2.47151 + vertex 1.39124 2.13512 2.47237 + vertex 1.39611 2.13276 2.47416 + endloop + endfacet + facet normal 0.0642955 0.684704 0.72598 + outer loop + vertex 1.39124 2.13512 2.47237 + vertex 1.39183 2.13226 2.47501 + vertex 1.39611 2.13276 2.47416 + endloop + endfacet + facet normal 0.129682 0.855751 0.500871 + outer loop + vertex 1.39398 2.14026 2.46301 + vertex 1.39922 2.13993 2.46222 + vertex 1.39606 2.1418 2.45985 + endloop + endfacet + facet normal 0.172254 0.836787 0.519727 + outer loop + vertex 1.39222 2.14225 2.46039 + vertex 1.39398 2.14026 2.46301 + vertex 1.39606 2.1418 2.45985 + endloop + endfacet + facet normal 0.119174 0.903619 0.411425 + outer loop + vertex 1.39922 2.13993 2.46222 + vertex 1.39398 2.14026 2.46301 + vertex 1.3973 2.13834 2.46626 + endloop + endfacet + facet normal 0.123023 0.904616 0.408086 + outer loop + vertex 1.3973 2.13834 2.46626 + vertex 1.39398 2.14026 2.46301 + vertex 1.39359 2.139 2.46592 + endloop + endfacet + facet normal 0.0704305 0.820657 0.567064 + outer loop + vertex 1.39722 2.13658 2.4696 + vertex 1.39323 2.13749 2.46876 + vertex 1.3954 2.13541 2.47151 + endloop + endfacet + facet normal 0.104291 0.877757 0.467618 + outer loop + vertex 1.39722 2.13658 2.4696 + vertex 1.3973 2.13834 2.46626 + vertex 1.39323 2.13749 2.46876 + endloop + endfacet + facet normal 0.110979 0.872102 0.476573 + outer loop + vertex 1.3973 2.13834 2.46626 + vertex 1.39359 2.139 2.46592 + vertex 1.39323 2.13749 2.46876 + endloop + endfacet + facet normal 0.0609246 0.817734 0.572364 + outer loop + vertex 1.3954 2.13541 2.47151 + vertex 1.39323 2.13749 2.46876 + vertex 1.39124 2.13512 2.47237 + endloop + endfacet + facet normal -0.12643 -0.346018 0.92967 + outer loop + vertex 1.395 2.145 2.45855 + vertex 1.39743 2.14296 2.45812 + vertex 1.4 2.145 2.45923 + endloop + endfacet + facet normal 0.425098 0.640036 -0.640036 + outer loop + vertex 1.395 2.14645 2.46 + vertex 1.39743 2.14296 2.45812 + vertex 1.395 2.145 2.45855 + endloop + endfacet + facet normal 0.14011 -0.000414291 0.990136 + outer loop + vertex 1.39606 2.1418 2.45985 + vertex 1.395 2.14645 2.46 + vertex 1.39222 2.14225 2.46039 + endloop + endfacet + facet normal 0.727063 0.144073 0.671284 + outer loop + vertex 1.39743 2.14296 2.45812 + vertex 1.395 2.14645 2.46 + vertex 1.39606 2.1418 2.45985 + endloop + endfacet + facet normal 0.155535 -0.782347 0.603111 + outer loop + vertex 1.405 0.887413 2.46 + vertex 1.40245 0.887548 2.46083 + vertex 1.4 0.886419 2.46 + endloop + endfacet + facet normal 0.192559 -0.817852 0.542254 + outer loop + vertex 1.40245 0.887548 2.46083 + vertex 1.39643 0.886936 2.46205 + vertex 1.4 0.886419 2.46 + endloop + endfacet + facet normal 0.17225 -0.900204 0.399953 + outer loop + vertex 1.40245 0.887548 2.46083 + vertex 1.39964 0.888501 2.46419 + vertex 1.39643 0.886936 2.46205 + endloop + endfacet + facet normal 0.16433 -0.904115 0.394426 + outer loop + vertex 1.40364 0.888761 2.46312 + vertex 1.39964 0.888501 2.46419 + vertex 1.40245 0.887548 2.46083 + endloop + endfacet + facet normal 0.176722 -0.876752 0.447298 + outer loop + vertex 1.39964 0.888501 2.46419 + vertex 1.40364 0.888761 2.46312 + vertex 1.40277 0.890152 2.46619 + endloop + endfacet + facet normal 0.155824 -0.867522 0.47236 + outer loop + vertex 1.39742 0.890188 2.46802 + vertex 1.39964 0.888501 2.46419 + vertex 1.40277 0.890152 2.46619 + endloop + endfacet + facet normal 0.186739 -0.806152 0.561469 + outer loop + vertex 1.40277 0.890152 2.46619 + vertex 1.40176 0.89251 2.46991 + vertex 1.39742 0.890188 2.46802 + endloop + endfacet + facet normal 0.161271 -0.786619 0.596006 + outer loop + vertex 1.40176 0.89251 2.46991 + vertex 1.39682 0.892471 2.47119 + vertex 1.39742 0.890188 2.46802 + endloop + endfacet + facet normal 0.185673 -0.697097 0.692519 + outer loop + vertex 1.40176 0.89251 2.46991 + vertex 1.3992 0.895162 2.47326 + vertex 1.39682 0.892471 2.47119 + endloop + endfacet + facet normal 0.14394 -0.720011 0.678871 + outer loop + vertex 1.40417 0.895191 2.47224 + vertex 1.3992 0.895162 2.47326 + vertex 1.40176 0.89251 2.46991 + endloop + endfacet + facet normal 0.141488 -0.61101 0.778876 + outer loop + vertex 1.39967 0.897946 2.47536 + vertex 1.39605 0.897228 2.47546 + vertex 1.3992 0.895162 2.47326 + endloop + endfacet + facet normal 0.146709 -0.611096 0.777842 + outer loop + vertex 1.39967 0.897946 2.47536 + vertex 1.3992 0.895162 2.47326 + vertex 1.40304 0.897715 2.47455 + endloop + endfacet + facet normal 0.160846 -0.625239 0.763678 + outer loop + vertex 1.40304 0.897715 2.47455 + vertex 1.3992 0.895162 2.47326 + vertex 1.40417 0.895191 2.47224 + endloop + endfacet + facet normal 0.120564 -0.494757 0.860628 + outer loop + vertex 1.39967 0.897946 2.47536 + vertex 1.39882 0.900357 2.47687 + vertex 1.39605 0.897228 2.47546 + endloop + endfacet + facet normal 0.165475 -0.529114 0.83226 + outer loop + vertex 1.40304 0.897715 2.47455 + vertex 1.40204 0.9 2.4762 + vertex 1.39967 0.897946 2.47536 + endloop + endfacet + facet normal 0.124564 -0.493461 0.860802 + outer loop + vertex 1.40204 0.9 2.4762 + vertex 1.39882 0.900357 2.47687 + vertex 1.39967 0.897946 2.47536 + endloop + endfacet + facet normal 0.137277 -0.434188 0.890301 + outer loop + vertex 1.40204 0.9 2.4762 + vertex 1.40339 0.90368 2.47779 + vertex 1.39882 0.900357 2.47687 + endloop + endfacet + facet normal -0.00869796 0.148022 0.988946 + outer loop + vertex 1.39832 0.988439 2.50698 + vertex 1.40103 0.991986 2.50647 + vertex 1.39623 0.991612 2.50649 + endloop + endfacet + facet normal -0.0708842 0.897268 0.435759 + outer loop + vertex 1.405 0.997993 2.495 + vertex 1.4 0.997598 2.495 + vertex 1.40339 0.996697 2.49741 + endloop + endfacet + facet normal -0.119215 0.862973 0.490984 + outer loop + vertex 1.40339 0.996697 2.49741 + vertex 1.4 0.997598 2.495 + vertex 1.39833 0.995937 2.49751 + endloop + endfacet + facet normal -0.141381 0.969359 0.200883 + outer loop + vertex 1.40339 0.996697 2.49741 + vertex 1.39833 0.995937 2.49751 + vertex 1.4029 0.995804 2.50137 + endloop + endfacet + facet normal -0.102288 0.982598 0.155042 + outer loop + vertex 1.4029 0.995804 2.50137 + vertex 1.39833 0.995937 2.49751 + vertex 1.39785 0.995248 2.50156 + endloop + endfacet + facet normal -0.0859184 0.915691 0.392592 + outer loop + vertex 1.4029 0.995804 2.50137 + vertex 1.39785 0.995248 2.50156 + vertex 1.40236 0.994359 2.50462 + endloop + endfacet + facet normal -0.0874659 0.914688 0.394583 + outer loop + vertex 1.40236 0.994359 2.50462 + vertex 1.39785 0.995248 2.50156 + vertex 1.39755 0.993828 2.50479 + endloop + endfacet + facet normal -0.0465559 0.625536 0.778805 + outer loop + vertex 1.40103 0.991986 2.50647 + vertex 1.39755 0.993828 2.50479 + vertex 1.39623 0.991612 2.50649 + endloop + endfacet + facet normal -0.0430178 0.629489 0.775818 + outer loop + vertex 1.40236 0.994359 2.50462 + vertex 1.39755 0.993828 2.50479 + vertex 1.40103 0.991986 2.50647 + endloop + endfacet + facet normal -0.0509933 -0.728478 -0.683169 + outer loop + vertex 1.405 2.03238 2.495 + vertex 1.40328 2.03007 2.49759 + vertex 1.4 2.03273 2.495 + endloop + endfacet + facet normal -0.021544 -0.711173 -0.702687 + outer loop + vertex 1.40328 2.03007 2.49759 + vertex 1.39876 2.03027 2.49753 + vertex 1.4 2.03273 2.495 + endloop + endfacet + facet normal -0.0428708 -0.995725 -0.0818173 + outer loop + vertex 1.40328 2.03007 2.49759 + vertex 1.4023 2.02976 2.5019 + vertex 1.39876 2.03027 2.49753 + endloop + endfacet + facet normal -0.050402 -0.995853 -0.0757414 + outer loop + vertex 1.4023 2.02976 2.5019 + vertex 1.39761 2.02999 2.50194 + vertex 1.39876 2.03027 2.49753 + endloop + endfacet + facet normal -0.0454216 -0.957268 0.285614 + outer loop + vertex 1.4023 2.02976 2.5019 + vertex 1.40097 2.03091 2.50555 + vertex 1.39761 2.02999 2.50194 + endloop + endfacet + facet normal -0.0601755 -0.952615 0.298167 + outer loop + vertex 1.40097 2.03091 2.50555 + vertex 1.3963 2.03119 2.5055 + vertex 1.39761 2.02999 2.50194 + endloop + endfacet + facet normal -0.0480228 -0.663655 0.746496 + outer loop + vertex 1.40097 2.03091 2.50555 + vertex 1.39931 2.03342 2.50767 + vertex 1.3963 2.03119 2.5055 + endloop + endfacet + facet normal -0.0350517 -0.659089 0.751248 + outer loop + vertex 1.40421 2.03314 2.50765 + vertex 1.39931 2.03342 2.50767 + vertex 1.40097 2.03091 2.50555 + endloop + endfacet + facet normal 0.0398877 0.399673 0.915789 + outer loop + vertex 1.3979 2.12275 2.47972 + vertex 1.40106 2.12611 2.47812 + vertex 1.39613 2.12634 2.47823 + endloop + endfacet + facet normal 0.0596699 0.59768 0.799511 + outer loop + vertex 1.39891 2.12947 2.4764 + vertex 1.40393 2.12927 2.47618 + vertex 1.40151 2.13224 2.47414 + endloop + endfacet + facet normal 0.0610964 0.596791 0.800067 + outer loop + vertex 1.39611 2.13276 2.47416 + vertex 1.39891 2.12947 2.4764 + vertex 1.40151 2.13224 2.47414 + endloop + endfacet + facet normal 0.0425506 0.475677 0.87859 + outer loop + vertex 1.40106 2.12611 2.47812 + vertex 1.39891 2.12947 2.4764 + vertex 1.39613 2.12634 2.47823 + endloop + endfacet + facet normal 0.0583219 0.48322 0.873554 + outer loop + vertex 1.40393 2.12927 2.47618 + vertex 1.39891 2.12947 2.4764 + vertex 1.40106 2.12611 2.47812 + endloop + endfacet + facet normal 0.0934873 0.824937 0.557439 + outer loop + vertex 1.39922 2.13475 2.47181 + vertex 1.40399 2.13449 2.4714 + vertex 1.40107 2.13654 2.46886 + endloop + endfacet + facet normal 0.116366 0.815922 0.566331 + outer loop + vertex 1.39722 2.13658 2.4696 + vertex 1.39922 2.13475 2.47181 + vertex 1.40107 2.13654 2.46886 + endloop + endfacet + facet normal 0.0719775 0.711902 0.69858 + outer loop + vertex 1.40151 2.13224 2.47414 + vertex 1.39922 2.13475 2.47181 + vertex 1.39611 2.13276 2.47416 + endloop + endfacet + facet normal 0.0988304 0.722783 0.683972 + outer loop + vertex 1.40399 2.13449 2.4714 + vertex 1.39922 2.13475 2.47181 + vertex 1.40151 2.13224 2.47414 + endloop + endfacet + facet normal 0.0206877 0.87249 0.488194 + outer loop + vertex 1.39922 2.13993 2.46222 + vertex 1.40489 2.1403 2.46133 + vertex 1.40047 2.14156 2.45924 + endloop + endfacet + facet normal 0.115175 0.84932 0.515161 + outer loop + vertex 1.39606 2.1418 2.45985 + vertex 1.39922 2.13993 2.46222 + vertex 1.40047 2.14156 2.45924 + endloop + endfacet + facet normal 0.0188069 0.877904 0.478466 + outer loop + vertex 1.40489 2.1403 2.46133 + vertex 1.39922 2.13993 2.46222 + vertex 1.40279 2.13823 2.46519 + endloop + endfacet + facet normal 0.0967444 0.909969 0.403234 + outer loop + vertex 1.40279 2.13823 2.46519 + vertex 1.39922 2.13993 2.46222 + vertex 1.3973 2.13834 2.46626 + endloop + endfacet + facet normal 0.0982187 0.878362 0.467797 + outer loop + vertex 1.40107 2.13654 2.46886 + vertex 1.3973 2.13834 2.46626 + vertex 1.39722 2.13658 2.4696 + endloop + endfacet + facet normal 0.106897 0.882478 0.458046 + outer loop + vertex 1.40279 2.13823 2.46519 + vertex 1.3973 2.13834 2.46626 + vertex 1.40107 2.13654 2.46886 + endloop + endfacet + facet normal -0.120729 -0.491698 0.862356 + outer loop + vertex 1.4 2.145 2.45923 + vertex 1.4011 2.14294 2.45821 + vertex 1.405 2.145 2.45993 + endloop + endfacet + facet normal -0.0239052 -0.453932 0.890715 + outer loop + vertex 1.39743 2.14296 2.45812 + vertex 1.4011 2.14294 2.45821 + vertex 1.4 2.145 2.45923 + endloop + endfacet + facet normal 0.12561 0.774638 0.619805 + outer loop + vertex 1.40047 2.14156 2.45924 + vertex 1.39743 2.14296 2.45812 + vertex 1.39606 2.1418 2.45985 + endloop + endfacet + facet normal -0.0152818 0.607239 0.794372 + outer loop + vertex 1.4011 2.14294 2.45821 + vertex 1.39743 2.14296 2.45812 + vertex 1.40047 2.14156 2.45924 + endloop + endfacet + facet normal 0.267299 -0.178879 0.946865 + outer loop + vertex 1.40632 0.888442 2.4611 + vertex 1.41 0.888091 2.46 + vertex 1.41053 0.888909 2.46001 + endloop + endfacet + facet normal 0.125857 -0.744466 0.655691 + outer loop + vertex 1.40632 0.888442 2.4611 + vertex 1.40245 0.887548 2.46083 + vertex 1.41 0.888091 2.46 + endloop + endfacet + facet normal 0.116629 -0.860092 0.496627 + outer loop + vertex 1.40245 0.887548 2.46083 + vertex 1.405 0.887413 2.46 + vertex 1.41 0.888091 2.46 + endloop + endfacet + facet normal 0.181755 -0.904581 0.385613 + outer loop + vertex 1.40632 0.888442 2.4611 + vertex 1.40364 0.888761 2.46312 + vertex 1.40245 0.887548 2.46083 + endloop + endfacet + facet normal 0.202252 -0.897426 0.392073 + outer loop + vertex 1.41053 0.888909 2.46001 + vertex 1.40762 0.88989 2.46375 + vertex 1.40632 0.888442 2.4611 + endloop + endfacet + facet normal 0.191441 -0.897454 0.3974 + outer loop + vertex 1.40364 0.888761 2.46312 + vertex 1.40632 0.888442 2.4611 + vertex 1.40762 0.88989 2.46375 + endloop + endfacet + facet normal 0.177587 -0.876508 0.447434 + outer loop + vertex 1.40364 0.888761 2.46312 + vertex 1.40762 0.88989 2.46375 + vertex 1.40277 0.890152 2.46619 + endloop + endfacet + facet normal 0.193872 -0.856857 0.477713 + outer loop + vertex 1.40277 0.890152 2.46619 + vertex 1.40762 0.88989 2.46375 + vertex 1.4064 0.891799 2.46767 + endloop + endfacet + facet normal 0.166188 -0.795119 0.583239 + outer loop + vertex 1.40584 0.893523 2.47018 + vertex 1.4064 0.891799 2.46767 + vertex 1.40943 0.893611 2.46927 + endloop + endfacet + facet normal 0.159518 -0.796758 0.582864 + outer loop + vertex 1.40584 0.893523 2.47018 + vertex 1.40176 0.89251 2.46991 + vertex 1.4064 0.891799 2.46767 + endloop + endfacet + facet normal 0.143931 -0.817778 0.557246 + outer loop + vertex 1.40176 0.89251 2.46991 + vertex 1.40277 0.890152 2.46619 + vertex 1.4064 0.891799 2.46767 + endloop + endfacet + facet normal 0.132674 -0.715757 0.685631 + outer loop + vertex 1.40584 0.893523 2.47018 + vertex 1.40417 0.895191 2.47224 + vertex 1.40176 0.89251 2.46991 + endloop + endfacet + facet normal 0.184711 -0.724875 0.663655 + outer loop + vertex 1.40943 0.893611 2.46927 + vertex 1.40777 0.895138 2.47141 + vertex 1.40584 0.893523 2.47018 + endloop + endfacet + facet normal 0.150619 -0.705859 0.692153 + outer loop + vertex 1.40777 0.895138 2.47141 + vertex 1.40417 0.895191 2.47224 + vertex 1.40584 0.893523 2.47018 + endloop + endfacet + facet normal 0.167065 -0.630353 0.758119 + outer loop + vertex 1.40777 0.895138 2.47141 + vertex 1.40814 0.897924 2.47364 + vertex 1.40417 0.895191 2.47224 + endloop + endfacet + facet normal 0.161427 -0.625027 0.763729 + outer loop + vertex 1.40814 0.897924 2.47364 + vertex 1.40304 0.897715 2.47455 + vertex 1.40417 0.895191 2.47224 + endloop + endfacet + facet normal 0.169118 -0.535007 0.827748 + outer loop + vertex 1.40304 0.897715 2.47455 + vertex 1.40814 0.897924 2.47364 + vertex 1.40599 0.900882 2.47599 + endloop + endfacet + facet normal 0.162099 -0.530459 0.832068 + outer loop + vertex 1.40204 0.9 2.4762 + vertex 1.40304 0.897715 2.47455 + vertex 1.40599 0.900882 2.47599 + endloop + endfacet + facet normal 0.143896 -0.435814 0.888459 + outer loop + vertex 1.40599 0.900882 2.47599 + vertex 1.40339 0.90368 2.47779 + vertex 1.40204 0.9 2.4762 + endloop + endfacet + facet normal 0.127984 -0.448204 0.884722 + outer loop + vertex 1.40915 0.904775 2.47751 + vertex 1.40339 0.90368 2.47779 + vertex 1.40599 0.900882 2.47599 + endloop + endfacet + facet normal -0.214889 0.822063 0.52729 + outer loop + vertex 1.41 0.9993 2.495 + vertex 1.405 0.997993 2.495 + vertex 1.40817 0.997318 2.49734 + endloop + endfacet + facet normal -0.112094 0.90428 0.411962 + outer loop + vertex 1.40817 0.997318 2.49734 + vertex 1.405 0.997993 2.495 + vertex 1.40339 0.996697 2.49741 + endloop + endfacet + facet normal -0.121015 0.957558 0.261607 + outer loop + vertex 1.40817 0.997318 2.49734 + vertex 1.40339 0.996697 2.49741 + vertex 1.40804 0.996228 2.50127 + endloop + endfacet + facet normal -0.076482 0.974682 0.210109 + outer loop + vertex 1.40804 0.996228 2.50127 + vertex 1.40339 0.996697 2.49741 + vertex 1.4029 0.995804 2.50137 + endloop + endfacet + facet normal -0.0667794 0.905689 0.41865 + outer loop + vertex 1.40804 0.996228 2.50127 + vertex 1.4029 0.995804 2.50137 + vertex 1.40768 0.994708 2.50451 + endloop + endfacet + facet normal -0.0511915 0.91579 0.398381 + outer loop + vertex 1.40768 0.994708 2.50451 + vertex 1.4029 0.995804 2.50137 + vertex 1.40236 0.994359 2.50462 + endloop + endfacet + facet normal -0.0404718 0.628677 0.776613 + outer loop + vertex 1.40627 0.992484 2.50635 + vertex 1.40236 0.994359 2.50462 + vertex 1.40103 0.991986 2.50647 + endloop + endfacet + facet normal -0.02545 0.646813 0.762224 + outer loop + vertex 1.40768 0.994708 2.50451 + vertex 1.40236 0.994359 2.50462 + vertex 1.40627 0.992484 2.50635 + endloop + endfacet + facet normal -0.00928812 -0.662537 -0.748972 + outer loop + vertex 1.41 2.03231 2.495 + vertex 1.40792 2.02975 2.49729 + vertex 1.405 2.03238 2.495 + endloop + endfacet + facet normal -0.0943274 -0.711237 -0.696595 + outer loop + vertex 1.40792 2.02975 2.49729 + vertex 1.40328 2.03007 2.49759 + vertex 1.405 2.03238 2.495 + endloop + endfacet + facet normal -0.0724774 -0.99601 -0.0520689 + outer loop + vertex 1.40792 2.02975 2.49729 + vertex 1.40715 2.02957 2.50171 + vertex 1.40328 2.03007 2.49759 + endloop + endfacet + facet normal -0.0412427 -0.995824 -0.0814527 + outer loop + vertex 1.40715 2.02957 2.50171 + vertex 1.4023 2.02976 2.5019 + vertex 1.40328 2.03007 2.49759 + endloop + endfacet + facet normal -0.0237956 -0.948984 0.314426 + outer loop + vertex 1.40715 2.02957 2.50171 + vertex 1.40595 2.03085 2.50546 + vertex 1.4023 2.02976 2.5019 + endloop + endfacet + facet normal -0.006812 -0.954339 0.298649 + outer loop + vertex 1.40595 2.03085 2.50546 + vertex 1.40097 2.03091 2.50555 + vertex 1.4023 2.02976 2.5019 + endloop + endfacet + facet normal 0.00417422 -0.690078 0.723723 + outer loop + vertex 1.40595 2.03085 2.50546 + vertex 1.40421 2.03314 2.50765 + vertex 1.40097 2.03091 2.50555 + endloop + endfacet + facet normal 0.0436332 -0.673556 0.737847 + outer loop + vertex 1.40905 2.03314 2.50737 + vertex 1.40421 2.03314 2.50765 + vertex 1.40595 2.03085 2.50546 + endloop + endfacet + facet normal 0.0855632 0.613414 0.785112 + outer loop + vertex 1.40393 2.12927 2.47618 + vertex 1.40895 2.12905 2.4758 + vertex 1.40661 2.13199 2.47376 + endloop + endfacet + facet normal 0.0881871 0.611737 0.786131 + outer loop + vertex 1.40151 2.13224 2.47414 + vertex 1.40393 2.12927 2.47618 + vertex 1.40661 2.13199 2.47376 + endloop + endfacet + facet normal 0.0672515 0.476861 0.876402 + outer loop + vertex 1.40616 2.12588 2.47785 + vertex 1.40393 2.12927 2.47618 + vertex 1.40106 2.12611 2.47812 + endloop + endfacet + facet normal 0.0862742 0.486085 0.869642 + outer loop + vertex 1.40895 2.12905 2.4758 + vertex 1.40393 2.12927 2.47618 + vertex 1.40616 2.12588 2.47785 + endloop + endfacet + facet normal 0.0954339 0.835066 0.541809 + outer loop + vertex 1.40399 2.13449 2.4714 + vertex 1.40952 2.13433 2.47067 + vertex 1.40597 2.13639 2.46812 + endloop + endfacet + facet normal 0.107161 0.830681 0.546339 + outer loop + vertex 1.40107 2.13654 2.46886 + vertex 1.40399 2.13449 2.4714 + vertex 1.40597 2.13639 2.46812 + endloop + endfacet + facet normal 0.0857495 0.729986 0.678062 + outer loop + vertex 1.40661 2.13199 2.47376 + vertex 1.40399 2.13449 2.4714 + vertex 1.40151 2.13224 2.47414 + endloop + endfacet + facet normal 0.108652 0.740247 0.663498 + outer loop + vertex 1.40952 2.13433 2.47067 + vertex 1.40399 2.13449 2.4714 + vertex 1.40661 2.13199 2.47376 + endloop + endfacet + facet normal -0.347659 0.265975 0.899105 + outer loop + vertex 1.40506 2.145 2.46 + vertex 1.40047 2.14156 2.45924 + vertex 1.40489 2.1403 2.46133 + endloop + endfacet + facet normal 0.112355 0.265564 0.957524 + outer loop + vertex 1.40506 2.145 2.46 + vertex 1.40489 2.1403 2.46133 + vertex 1.41 2.14291 2.46 + endloop + endfacet + facet normal 0.0415062 0.385879 0.921615 + outer loop + vertex 1.41 2.14291 2.46 + vertex 1.40489 2.1403 2.46133 + vertex 1.40876 2.13954 2.46147 + endloop + endfacet + facet normal 0.149113 0.859082 0.489637 + outer loop + vertex 1.40876 2.13954 2.46147 + vertex 1.40489 2.1403 2.46133 + vertex 1.40819 2.13798 2.46438 + endloop + endfacet + facet normal 0.117207 0.848473 0.516098 + outer loop + vertex 1.40819 2.13798 2.46438 + vertex 1.40489 2.1403 2.46133 + vertex 1.40279 2.13823 2.46519 + endloop + endfacet + facet normal 0.0949161 0.885919 0.454024 + outer loop + vertex 1.40597 2.13639 2.46812 + vertex 1.40279 2.13823 2.46519 + vertex 1.40107 2.13654 2.46886 + endloop + endfacet + facet normal 0.108097 0.890237 0.442484 + outer loop + vertex 1.40819 2.13798 2.46438 + vertex 1.40279 2.13823 2.46519 + vertex 1.40597 2.13639 2.46812 + endloop + endfacet + facet normal 0.346539 -0.571908 0.743526 + outer loop + vertex 1.41 2.145 2.45438 + vertex 1.40867 2.145 2.455 + vertex 1.40933 2.1438 2.45376 + endloop + endfacet + facet normal 0.44152 0.749415 -0.493393 + outer loop + vertex 1.41 2.145 2.45619 + vertex 1.40933 2.1438 2.45376 + vertex 1.40867 2.145 2.455 + endloop + endfacet + facet normal -0.567325 0.664586 0.486279 + outer loop + vertex 1.40506 2.145 2.46 + vertex 1.405 2.145 2.45993 + vertex 1.4011 2.14294 2.45821 + endloop + endfacet + facet normal -0.568223 0.646405 0.509199 + outer loop + vertex 1.40506 2.145 2.46 + vertex 1.4011 2.14294 2.45821 + vertex 1.40047 2.14156 2.45924 + endloop + endfacet + facet normal -0.488825 -0.587671 -0.644743 + outer loop + vertex 1.4143 0.89 2.455 + vertex 1.41 0.888091 2.46 + vertex 1.41 0.89 2.45826 + endloop + endfacet + facet normal -0.538721 -0.520891 -0.662157 + outer loop + vertex 1.4143 0.89 2.455 + vertex 1.415 0.889276 2.455 + vertex 1.41 0.888091 2.46 + endloop + endfacet + facet normal -0.0317257 -0.964974 -0.260419 + outer loop + vertex 1.415 0.889276 2.455 + vertex 1.41438 0.88873 2.4571 + vertex 1.41 0.888091 2.46 + endloop + endfacet + facet normal 0.551058 -0.360038 0.7528 + outer loop + vertex 1.41438 0.88873 2.4571 + vertex 1.41053 0.888909 2.46001 + vertex 1.41 0.888091 2.46 + endloop + endfacet + facet normal 0.14124 -0.958804 0.246466 + outer loop + vertex 1.41502 0.889343 2.45912 + vertex 1.41053 0.888909 2.46001 + vertex 1.41438 0.88873 2.4571 + endloop + endfacet + facet normal 0.161114 -0.915542 0.368545 + outer loop + vertex 1.41053 0.888909 2.46001 + vertex 1.41502 0.889343 2.45912 + vertex 1.41365 0.890293 2.46208 + endloop + endfacet + facet normal 0.162818 -0.916115 0.366365 + outer loop + vertex 1.40762 0.88989 2.46375 + vertex 1.41053 0.888909 2.46001 + vertex 1.41365 0.890293 2.46208 + endloop + endfacet + facet normal 0.183616 -0.873002 0.451833 + outer loop + vertex 1.41365 0.890293 2.46208 + vertex 1.41115 0.891854 2.46611 + vertex 1.40762 0.88989 2.46375 + endloop + endfacet + facet normal 0.165246 -0.86543 0.472995 + outer loop + vertex 1.41115 0.891854 2.46611 + vertex 1.4064 0.891799 2.46767 + vertex 1.40762 0.88989 2.46375 + endloop + endfacet + facet normal 0.191079 -0.810495 0.553703 + outer loop + vertex 1.41115 0.891854 2.46611 + vertex 1.40943 0.893611 2.46927 + vertex 1.4064 0.891799 2.46767 + endloop + endfacet + facet normal 0.175925 -0.817033 0.549096 + outer loop + vertex 1.41397 0.89398 2.46837 + vertex 1.40943 0.893611 2.46927 + vertex 1.41115 0.891854 2.46611 + endloop + endfacet + facet normal 0.19107 -0.723646 0.663196 + outer loop + vertex 1.40943 0.893611 2.46927 + vertex 1.41397 0.89398 2.46837 + vertex 1.41176 0.896019 2.47123 + endloop + endfacet + facet normal 0.1885 -0.722648 0.665017 + outer loop + vertex 1.40777 0.895138 2.47141 + vertex 1.40943 0.893611 2.46927 + vertex 1.41176 0.896019 2.47123 + endloop + endfacet + facet normal 0.172091 -0.630219 0.757106 + outer loop + vertex 1.41176 0.896019 2.47123 + vertex 1.40814 0.897924 2.47364 + vertex 1.40777 0.895138 2.47141 + endloop + endfacet + facet normal 0.165568 -0.637114 0.752777 + outer loop + vertex 1.41428 0.899495 2.47362 + vertex 1.40814 0.897924 2.47364 + vertex 1.41176 0.896019 2.47123 + endloop + endfacet + facet normal 0.142874 -0.547451 0.824551 + outer loop + vertex 1.40814 0.897924 2.47364 + vertex 1.41428 0.899495 2.47362 + vertex 1.41092 0.901755 2.4757 + endloop + endfacet + facet normal 0.145509 -0.548675 0.823275 + outer loop + vertex 1.40599 0.900882 2.47599 + vertex 1.40814 0.897924 2.47364 + vertex 1.41092 0.901755 2.4757 + endloop + endfacet + facet normal 0.131668 -0.450532 0.882997 + outer loop + vertex 1.41092 0.901755 2.4757 + vertex 1.40915 0.904775 2.47751 + vertex 1.40599 0.900882 2.47599 + endloop + endfacet + facet normal 0.112789 -0.460169 0.880638 + outer loop + vertex 1.41389 0.905177 2.47711 + vertex 1.40915 0.904775 2.47751 + vertex 1.41092 0.901755 2.4757 + endloop + endfacet + facet normal 0.109845 -0.394076 0.91249 + outer loop + vertex 1.41389 0.905177 2.47711 + vertex 1.41324 0.90866 2.47869 + vertex 1.40915 0.904775 2.47751 + endloop + endfacet + facet normal 0.105511 -0.390188 0.91467 + outer loop + vertex 1.40915 0.904775 2.47751 + vertex 1.41324 0.90866 2.47869 + vertex 1.40791 0.90874 2.47934 + endloop + endfacet + facet normal 0.0985328 -0.323524 0.941076 + outer loop + vertex 1.41278 0.926915 2.48542 + vertex 1.41237 0.929735 2.48643 + vertex 1.40967 0.927365 2.4859 + endloop + endfacet + facet normal -0.192651 0.784287 -0.589728 + outer loop + vertex 1.41295 0.998073 2.49146 + vertex 1.41648 0.997989 2.4902 + vertex 1.415 0.997475 2.49 + endloop + endfacet + facet normal -0.105975 -0.963532 0.245715 + outer loop + vertex 1.41295 0.998073 2.49146 + vertex 1.415 0.997475 2.49 + vertex 1.41 0.9993 2.495 + endloop + endfacet + facet normal 0.00300421 0.94034 -0.340224 + outer loop + vertex 1.41 0.9993 2.495 + vertex 1.415 0.997475 2.49 + vertex 1.41 0.997491 2.49 + endloop + endfacet + facet normal 0.396746 0.917835 0.0131031 + outer loop + vertex 1.41228 0.998333 2.49373 + vertex 1.41295 0.998073 2.49146 + vertex 1.41 0.9993 2.495 + endloop + endfacet + facet normal 0.414959 0.90829 0.0530938 + outer loop + vertex 1.41228 0.998333 2.49373 + vertex 1.41 0.9993 2.495 + vertex 1.41278 0.997901 2.49719 + endloop + endfacet + facet normal -0.0790801 0.790786 0.606963 + outer loop + vertex 1.41278 0.997901 2.49719 + vertex 1.41 0.9993 2.495 + vertex 1.40817 0.997318 2.49734 + endloop + endfacet + facet normal -0.108466 0.943732 0.312419 + outer loop + vertex 1.41278 0.997901 2.49719 + vertex 1.40817 0.997318 2.49734 + vertex 1.41304 0.996603 2.50119 + endloop + endfacet + facet normal -0.0679328 0.961974 0.26456 + outer loop + vertex 1.41304 0.996603 2.50119 + vertex 1.40817 0.997318 2.49734 + vertex 1.40804 0.996228 2.50127 + endloop + endfacet + facet normal -0.0595489 0.889836 0.452377 + outer loop + vertex 1.41304 0.996603 2.50119 + vertex 1.40804 0.996228 2.50127 + vertex 1.41301 0.994992 2.50436 + endloop + endfacet + facet normal -0.0367339 0.905832 0.422041 + outer loop + vertex 1.41301 0.994992 2.50436 + vertex 1.40804 0.996228 2.50127 + vertex 1.40768 0.994708 2.50451 + endloop + endfacet + facet normal 0.0220008 0.629025 0.777074 + outer loop + vertex 1.412 0.992497 2.50617 + vertex 1.40768 0.994708 2.50451 + vertex 1.40627 0.992484 2.50635 + endloop + endfacet + facet normal -0.00946189 0.590255 0.807161 + outer loop + vertex 1.41301 0.994992 2.50436 + vertex 1.40768 0.994708 2.50451 + vertex 1.412 0.992497 2.50617 + endloop + endfacet + facet normal -0.0517704 0.976462 -0.209382 + outer loop + vertex 1.41648 0.997989 2.4902 + vertex 1.41295 0.998073 2.49146 + vertex 1.41506 0.998493 2.4929 + endloop + endfacet + facet normal -0.0990143 0.984834 -0.142469 + outer loop + vertex 1.41506 0.998493 2.4929 + vertex 1.41295 0.998073 2.49146 + vertex 1.41228 0.998333 2.49373 + endloop + endfacet + facet normal 0.00117507 -0.58674 -0.809775 + outer loop + vertex 1.415 2.03252 2.49 + vertex 1.41337 2.02983 2.49194 + vertex 1.41 2.03251 2.49 + endloop + endfacet + facet normal -0.610506 -0.791378 -0.0316612 + outer loop + vertex 1.41337 2.02983 2.49194 + vertex 1.41 2.03231 2.495 + vertex 1.41 2.03251 2.49 + endloop + endfacet + facet normal -0.717037 -0.642787 -0.269598 + outer loop + vertex 1.41337 2.02983 2.49194 + vertex 1.41252 2.02898 2.49625 + vertex 1.41 2.03231 2.495 + endloop + endfacet + facet normal -0.269863 -0.510778 -0.81626 + outer loop + vertex 1.41252 2.02898 2.49625 + vertex 1.40792 2.02975 2.49729 + vertex 1.41 2.03231 2.495 + endloop + endfacet + facet normal -0.165249 -0.98625 0.00179178 + outer loop + vertex 1.41252 2.02898 2.49625 + vertex 1.41204 2.02907 2.50105 + vertex 1.40792 2.02975 2.49729 + endloop + endfacet + facet normal -0.111134 -0.992076 -0.0585992 + outer loop + vertex 1.41204 2.02907 2.50105 + vertex 1.40715 2.02957 2.50171 + vertex 1.40792 2.02975 2.49729 + endloop + endfacet + facet normal -0.0526053 -0.939484 0.338529 + outer loop + vertex 1.41204 2.02907 2.50105 + vertex 1.41102 2.03058 2.50509 + vertex 1.40715 2.02957 2.50171 + endloop + endfacet + facet normal -0.0279429 -0.949277 0.313197 + outer loop + vertex 1.41102 2.03058 2.50509 + vertex 1.40595 2.03085 2.50546 + vertex 1.40715 2.02957 2.50171 + endloop + endfacet + facet normal 0.0205727 -0.656147 0.754352 + outer loop + vertex 1.41102 2.03058 2.50509 + vertex 1.40905 2.03314 2.50737 + vertex 1.40595 2.03085 2.50546 + endloop + endfacet + facet normal 0.00386759 -0.663512 0.748155 + outer loop + vertex 1.41413 2.03273 2.50698 + vertex 1.40905 2.03314 2.50737 + vertex 1.41102 2.03058 2.50509 + endloop + endfacet + facet normal 0.100714 0.325095 0.940303 + outer loop + vertex 1.41487 2.10004 2.4863 + vertex 1.41314 2.10421 2.48505 + vertex 1.41086 2.10082 2.48646 + endloop + endfacet + facet normal 0.102627 0.323893 0.940511 + outer loop + vertex 1.40877 2.10322 2.48587 + vertex 1.41086 2.10082 2.48646 + vertex 1.41314 2.10421 2.48505 + endloop + endfacet + facet normal 0.104756 0.613132 0.783004 + outer loop + vertex 1.40895 2.12905 2.4758 + vertex 1.4139 2.12868 2.47543 + vertex 1.41159 2.13159 2.47346 + endloop + endfacet + facet normal 0.0966647 0.618539 0.779786 + outer loop + vertex 1.40661 2.13199 2.47376 + vertex 1.40895 2.12905 2.4758 + vertex 1.41159 2.13159 2.47346 + endloop + endfacet + facet normal 0.0881727 0.484765 0.870189 + outer loop + vertex 1.41122 2.12576 2.4774 + vertex 1.40895 2.12905 2.4758 + vertex 1.40616 2.12588 2.47785 + endloop + endfacet + facet normal 0.101853 0.491603 0.864843 + outer loop + vertex 1.4139 2.12868 2.47543 + vertex 1.40895 2.12905 2.4758 + vertex 1.41122 2.12576 2.4774 + endloop + endfacet + facet normal 0.135906 0.886797 0.441724 + outer loop + vertex 1.41432 2.13523 2.46828 + vertex 1.41228 2.13699 2.46538 + vertex 1.41011 2.13627 2.46749 + endloop + endfacet + facet normal 0.105419 0.840164 0.531988 + outer loop + vertex 1.41011 2.13627 2.46749 + vertex 1.40597 2.13639 2.46812 + vertex 1.40952 2.13433 2.47067 + endloop + endfacet + facet normal 0.107424 0.839813 0.532141 + outer loop + vertex 1.41011 2.13627 2.46749 + vertex 1.40952 2.13433 2.47067 + vertex 1.41432 2.13523 2.46828 + endloop + endfacet + facet normal 0.11749 0.828218 0.547952 + outer loop + vertex 1.41432 2.13523 2.46828 + vertex 1.40952 2.13433 2.47067 + vertex 1.41401 2.13327 2.47132 + endloop + endfacet + facet normal 0.0995885 0.745551 0.658966 + outer loop + vertex 1.41159 2.13159 2.47346 + vertex 1.40952 2.13433 2.47067 + vertex 1.40661 2.13199 2.47376 + endloop + endfacet + facet normal 0.0792828 0.739698 0.668253 + outer loop + vertex 1.41401 2.13327 2.47132 + vertex 1.40952 2.13433 2.47067 + vertex 1.41159 2.13159 2.47346 + endloop + endfacet + facet normal 0.0760814 0.463955 0.882586 + outer loop + vertex 1.415 2.14209 2.46 + vertex 1.41 2.14291 2.46 + vertex 1.41235 2.1388 2.46196 + endloop + endfacet + facet normal -0.0397606 0.411155 0.910698 + outer loop + vertex 1.41235 2.1388 2.46196 + vertex 1.41 2.14291 2.46 + vertex 1.40876 2.13954 2.46147 + endloop + endfacet + facet normal 0.114272 0.89866 0.423499 + outer loop + vertex 1.41228 2.13699 2.46538 + vertex 1.40819 2.13798 2.46438 + vertex 1.41011 2.13627 2.46749 + endloop + endfacet + facet normal 0.0985724 0.878414 0.467624 + outer loop + vertex 1.41228 2.13699 2.46538 + vertex 1.41235 2.1388 2.46196 + vertex 1.40819 2.13798 2.46438 + endloop + endfacet + facet normal 0.111882 0.86654 0.486406 + outer loop + vertex 1.41235 2.1388 2.46196 + vertex 1.40876 2.13954 2.46147 + vertex 1.40819 2.13798 2.46438 + endloop + endfacet + facet normal 0.0922544 0.895534 0.435325 + outer loop + vertex 1.41011 2.13627 2.46749 + vertex 1.40819 2.13798 2.46438 + vertex 1.40597 2.13639 2.46812 + endloop + endfacet + facet normal -0.306742 -0.2931 0.905539 + outer loop + vertex 1.41 2.145 2.45438 + vertex 1.40933 2.1438 2.45376 + vertex 1.41183 2.145 2.455 + endloop + endfacet + facet normal -0.244771 0.893559 -0.37635 + outer loop + vertex 1.41183 2.145 2.455 + vertex 1.40933 2.1438 2.45376 + vertex 1.41 2.145 2.45619 + endloop + endfacet + facet normal 0.191716 -0.933793 0.302119 + outer loop + vertex 1.41948 0.89 2.46 + vertex 1.42 0.888489 2.455 + vertex 1.42 0.89 2.45967 + endloop + endfacet + facet normal 0.0694233 -0.952916 0.29518 + outer loop + vertex 1.41948 0.89 2.46 + vertex 1.41438 0.88873 2.4571 + vertex 1.42 0.888489 2.455 + endloop + endfacet + facet normal -0.148813 -0.945417 -0.289898 + outer loop + vertex 1.41438 0.88873 2.4571 + vertex 1.415 0.889276 2.455 + vertex 1.42 0.888489 2.455 + endloop + endfacet + facet normal 0.0894657 -0.960559 0.263291 + outer loop + vertex 1.41948 0.89 2.46 + vertex 1.41502 0.889343 2.45912 + vertex 1.41438 0.88873 2.4571 + endloop + endfacet + facet normal -0.237524 0.656995 0.715499 + outer loop + vertex 1.41502 0.889343 2.45912 + vertex 1.41948 0.89 2.46 + vertex 1.42 0.890188 2.46 + endloop + endfacet + facet normal 0.0974215 -0.933602 0.344813 + outer loop + vertex 1.41502 0.889343 2.45912 + vertex 1.42 0.890188 2.46 + vertex 1.41365 0.890293 2.46208 + endloop + endfacet + facet normal 0.156657 -0.838979 0.521126 + outer loop + vertex 1.41365 0.890293 2.46208 + vertex 1.42 0.890188 2.46 + vertex 1.41734 0.890918 2.46197 + endloop + endfacet + facet normal 0.161049 -0.876153 0.454334 + outer loop + vertex 1.41734 0.890918 2.46197 + vertex 1.4163 0.892212 2.46484 + vertex 1.41365 0.890293 2.46208 + endloop + endfacet + facet normal 0.17112 -0.878421 0.446201 + outer loop + vertex 1.4163 0.892212 2.46484 + vertex 1.41115 0.891854 2.46611 + vertex 1.41365 0.890293 2.46208 + endloop + endfacet + facet normal 0.189581 -0.82212 0.536821 + outer loop + vertex 1.4163 0.892212 2.46484 + vertex 1.41397 0.89398 2.46837 + vertex 1.41115 0.891854 2.46611 + endloop + endfacet + facet normal 0.15936 -0.836596 0.524129 + outer loop + vertex 1.41793 0.894165 2.46746 + vertex 1.41397 0.89398 2.46837 + vertex 1.4163 0.892212 2.46484 + endloop + endfacet + facet normal 0.182113 -0.7448 0.641956 + outer loop + vertex 1.41397 0.89398 2.46837 + vertex 1.41793 0.894165 2.46746 + vertex 1.4174 0.896499 2.47032 + endloop + endfacet + facet normal 0.168625 -0.736572 0.655001 + outer loop + vertex 1.41176 0.896019 2.47123 + vertex 1.41397 0.89398 2.46837 + vertex 1.4174 0.896499 2.47032 + endloop + endfacet + facet normal 0.175423 -0.640667 0.747511 + outer loop + vertex 1.4174 0.896499 2.47032 + vertex 1.41428 0.899495 2.47362 + vertex 1.41176 0.896019 2.47123 + endloop + endfacet + facet normal 0.138167 -0.664734 0.734193 + outer loop + vertex 1.41975 0.899695 2.47277 + vertex 1.41428 0.899495 2.47362 + vertex 1.4174 0.896499 2.47032 + endloop + endfacet + facet normal 0.132596 -0.557873 0.819266 + outer loop + vertex 1.41476 0.902684 2.47571 + vertex 1.41092 0.901755 2.4757 + vertex 1.41428 0.899495 2.47362 + endloop + endfacet + facet normal 0.12618 -0.557674 0.820413 + outer loop + vertex 1.41476 0.902684 2.47571 + vertex 1.41428 0.899495 2.47362 + vertex 1.41811 0.902446 2.47503 + endloop + endfacet + facet normal 0.145823 -0.575598 0.804626 + outer loop + vertex 1.41811 0.902446 2.47503 + vertex 1.41428 0.899495 2.47362 + vertex 1.41975 0.899695 2.47277 + endloop + endfacet + facet normal 0.107939 -0.456905 0.882942 + outer loop + vertex 1.41476 0.902684 2.47571 + vertex 1.41389 0.905177 2.47711 + vertex 1.41092 0.901755 2.4757 + endloop + endfacet + facet normal 0.139928 -0.485256 0.863103 + outer loop + vertex 1.41811 0.902446 2.47503 + vertex 1.41716 0.904857 2.47654 + vertex 1.41476 0.902684 2.47571 + endloop + endfacet + facet normal 0.107587 -0.457018 0.882927 + outer loop + vertex 1.41716 0.904857 2.47654 + vertex 1.41389 0.905177 2.47711 + vertex 1.41476 0.902684 2.47571 + endloop + endfacet + facet normal 0.116652 -0.405904 0.906441 + outer loop + vertex 1.41716 0.904857 2.47654 + vertex 1.41855 0.908559 2.47802 + vertex 1.41389 0.905177 2.47711 + endloop + endfacet + facet normal 0.107235 -0.394606 0.912572 + outer loop + vertex 1.41855 0.908559 2.47802 + vertex 1.41324 0.90866 2.47869 + vertex 1.41389 0.905177 2.47711 + endloop + endfacet + facet normal 0.0990758 -0.323436 0.941049 + outer loop + vertex 1.41237 0.929735 2.48643 + vertex 1.41278 0.926915 2.48542 + vertex 1.41609 0.930529 2.48631 + endloop + endfacet + facet normal -0.00689517 0.379036 -0.925356 + outer loop + vertex 1.42 0.997566 2.49 + vertex 1.415 0.997475 2.49 + vertex 1.41648 0.997989 2.4902 + endloop + endfacet + facet normal -0.098072 -0.381858 -0.919003 + outer loop + vertex 1.42085 0.998459 2.48954 + vertex 1.42 0.997566 2.49 + vertex 1.41648 0.997989 2.4902 + endloop + endfacet + facet normal -0.186388 0.971137 0.148839 + outer loop + vertex 1.41458 0.998504 2.49551 + vertex 1.41228 0.998333 2.49373 + vertex 1.41278 0.997901 2.49719 + endloop + endfacet + facet normal -0.142743 0.97029 0.19535 + outer loop + vertex 1.41656 0.998255 2.49818 + vertex 1.41458 0.998504 2.49551 + vertex 1.41278 0.997901 2.49719 + endloop + endfacet + facet normal -0.194915 0.884922 0.422992 + outer loop + vertex 1.41656 0.998255 2.49818 + vertex 1.41278 0.997901 2.49719 + vertex 1.41802 0.99701 2.50146 + endloop + endfacet + facet normal -0.0940092 0.945405 0.312043 + outer loop + vertex 1.41802 0.99701 2.50146 + vertex 1.41278 0.997901 2.49719 + vertex 1.41304 0.996603 2.50119 + endloop + endfacet + facet normal -0.0972615 0.839079 0.535244 + outer loop + vertex 1.41802 0.99701 2.50146 + vertex 1.41304 0.996603 2.50119 + vertex 1.41775 0.995211 2.50423 + endloop + endfacet + facet normal -0.0290396 0.890946 0.45318 + outer loop + vertex 1.41775 0.995211 2.50423 + vertex 1.41304 0.996603 2.50119 + vertex 1.41301 0.994992 2.50436 + endloop + endfacet + facet normal -0.0149114 0.591656 0.806053 + outer loop + vertex 1.41708 0.993137 2.5058 + vertex 1.41301 0.994992 2.50436 + vertex 1.412 0.992497 2.50617 + endloop + endfacet + facet normal -0.006396 0.603554 0.797296 + outer loop + vertex 1.41775 0.995211 2.50423 + vertex 1.41301 0.994992 2.50436 + vertex 1.41708 0.993137 2.5058 + endloop + endfacet + facet normal -0.139104 0.962067 -0.234685 + outer loop + vertex 1.41648 0.997989 2.4902 + vertex 1.4192 0.998946 2.49251 + vertex 1.42085 0.998459 2.48954 + endloop + endfacet + facet normal -0.128411 0.960561 -0.246643 + outer loop + vertex 1.41506 0.998493 2.4929 + vertex 1.4192 0.998946 2.49251 + vertex 1.41648 0.997989 2.4902 + endloop + endfacet + facet normal -0.0618891 0.997963 -0.0154526 + outer loop + vertex 1.41458 0.998504 2.49551 + vertex 1.41506 0.998493 2.4929 + vertex 1.41228 0.998333 2.49373 + endloop + endfacet + facet normal -0.0867115 0.996032 -0.0200221 + outer loop + vertex 1.41458 0.998504 2.49551 + vertex 1.41858 0.998874 2.49663 + vertex 1.41506 0.998493 2.4929 + endloop + endfacet + facet normal -0.108708 0.994073 0.000895947 + outer loop + vertex 1.41858 0.998874 2.49663 + vertex 1.4192 0.998946 2.49251 + vertex 1.41506 0.998493 2.4929 + endloop + endfacet + facet normal -0.145453 0.969498 0.197276 + outer loop + vertex 1.41858 0.998874 2.49663 + vertex 1.41458 0.998504 2.49551 + vertex 1.41656 0.998255 2.49818 + endloop + endfacet + facet normal 0.000585607 -0.146203 -0.989254 + outer loop + vertex 1.42 2.03254 2.49 + vertex 1.41866 2.02925 2.49049 + vertex 1.415 2.03252 2.49 + endloop + endfacet + facet normal -0.28343 -0.443369 -0.850348 + outer loop + vertex 1.41866 2.02925 2.49049 + vertex 1.41337 2.02983 2.49194 + vertex 1.415 2.03252 2.49 + endloop + endfacet + facet normal -0.198498 -0.913392 -0.355405 + outer loop + vertex 1.41866 2.02925 2.49049 + vertex 1.41703 2.02796 2.49471 + vertex 1.41337 2.02983 2.49194 + endloop + endfacet + facet normal -0.290813 -0.925811 -0.241459 + outer loop + vertex 1.41703 2.02796 2.49471 + vertex 1.41252 2.02898 2.49625 + vertex 1.41337 2.02983 2.49194 + endloop + endfacet + facet normal -0.222391 -0.97491 -0.00966479 + outer loop + vertex 1.41703 2.02796 2.49471 + vertex 1.41658 2.02801 2.49978 + vertex 1.41252 2.02898 2.49625 + endloop + endfacet + facet normal -0.226641 -0.973968 -0.00450328 + outer loop + vertex 1.41658 2.02801 2.49978 + vertex 1.41204 2.02907 2.50105 + vertex 1.41252 2.02898 2.49625 + endloop + endfacet + facet normal -0.140086 -0.948761 0.283248 + outer loop + vertex 1.41658 2.02801 2.49978 + vertex 1.41649 2.02945 2.50454 + vertex 1.41204 2.02907 2.50105 + endloop + endfacet + facet normal -0.162047 -0.936855 0.309908 + outer loop + vertex 1.41649 2.02945 2.50454 + vertex 1.41102 2.03058 2.50509 + vertex 1.41204 2.02907 2.50105 + endloop + endfacet + facet normal -0.049362 -0.618466 0.78426 + outer loop + vertex 1.41649 2.02945 2.50454 + vertex 1.41413 2.03273 2.50698 + vertex 1.41102 2.03058 2.50509 + endloop + endfacet + facet normal -0.164905 -0.662158 0.730995 + outer loop + vertex 1.4195 2.03147 2.50705 + vertex 1.41413 2.03273 2.50698 + vertex 1.41649 2.02945 2.50454 + endloop + endfacet + facet normal 0.097922 0.324127 0.940932 + outer loop + vertex 1.41314 2.10421 2.48505 + vertex 1.41487 2.10004 2.4863 + vertex 1.4182 2.10315 2.48489 + endloop + endfacet + facet normal 0.11584 0.610239 0.783702 + outer loop + vertex 1.4139 2.12868 2.47543 + vertex 1.4188 2.12805 2.47519 + vertex 1.41641 2.13105 2.47321 + endloop + endfacet + facet normal 0.108887 0.615025 0.780953 + outer loop + vertex 1.41159 2.13159 2.47346 + vertex 1.4139 2.12868 2.47543 + vertex 1.41641 2.13105 2.47321 + endloop + endfacet + facet normal 0.103802 0.490193 0.865411 + outer loop + vertex 1.41606 2.12538 2.47704 + vertex 1.4139 2.12868 2.47543 + vertex 1.41122 2.12576 2.4774 + endloop + endfacet + facet normal 0.104567 0.49055 0.865116 + outer loop + vertex 1.4188 2.12805 2.47519 + vertex 1.4139 2.12868 2.47543 + vertex 1.41606 2.12538 2.47704 + endloop + endfacet + facet normal 0.131812 0.898406 0.418918 + outer loop + vertex 1.41432 2.13523 2.46828 + vertex 1.41966 2.13496 2.46719 + vertex 1.41616 2.13672 2.46451 + endloop + endfacet + facet normal 0.157767 0.889812 0.428186 + outer loop + vertex 1.41228 2.13699 2.46538 + vertex 1.41432 2.13523 2.46828 + vertex 1.41616 2.13672 2.46451 + endloop + endfacet + facet normal 0.150003 0.838721 0.523494 + outer loop + vertex 1.41966 2.13496 2.46719 + vertex 1.41432 2.13523 2.46828 + vertex 1.41823 2.13313 2.47053 + endloop + endfacet + facet normal 0.129286 0.826427 0.547999 + outer loop + vertex 1.41823 2.13313 2.47053 + vertex 1.41432 2.13523 2.46828 + vertex 1.41401 2.13327 2.47132 + endloop + endfacet + facet normal 0.1155 0.714802 0.689723 + outer loop + vertex 1.41641 2.13105 2.47321 + vertex 1.41401 2.13327 2.47132 + vertex 1.41159 2.13159 2.47346 + endloop + endfacet + facet normal 0.148184 0.73046 0.666686 + outer loop + vertex 1.41823 2.13313 2.47053 + vertex 1.41401 2.13327 2.47132 + vertex 1.41641 2.13105 2.47321 + endloop + endfacet + facet normal -0.00100533 0.250993 0.967988 + outer loop + vertex 1.42 2.14211 2.46 + vertex 1.415 2.14209 2.46 + vertex 1.41739 2.13843 2.46095 + endloop + endfacet + facet normal 0.20791 0.370856 0.905118 + outer loop + vertex 1.41739 2.13843 2.46095 + vertex 1.415 2.14209 2.46 + vertex 1.41235 2.1388 2.46196 + endloop + endfacet + facet normal 0.164552 0.870144 0.464512 + outer loop + vertex 1.41616 2.13672 2.46451 + vertex 1.41235 2.1388 2.46196 + vertex 1.41228 2.13699 2.46538 + endloop + endfacet + facet normal 0.158953 0.867743 0.47091 + outer loop + vertex 1.41739 2.13843 2.46095 + vertex 1.41235 2.1388 2.46196 + vertex 1.41616 2.13672 2.46451 + endloop + endfacet + facet normal 0.0939599 -0.947232 0.306467 + outer loop + vertex 1.425 0.888985 2.455 + vertex 1.42 0.89 2.45967 + vertex 1.42 0.888489 2.455 + endloop + endfacet + facet normal 0.161132 -0.914442 0.371258 + outer loop + vertex 1.425 0.89 2.4575 + vertex 1.42 0.89 2.45967 + vertex 1.425 0.888985 2.455 + endloop + endfacet + facet normal 0.194046 -0.82012 0.538283 + outer loop + vertex 1.425 0.891371 2.46 + vertex 1.42093 0.891761 2.46206 + vertex 1.42 0.890188 2.46 + endloop + endfacet + facet normal 0.17932 -0.819438 0.544394 + outer loop + vertex 1.42093 0.891761 2.46206 + vertex 1.41734 0.890918 2.46197 + vertex 1.42 0.890188 2.46 + endloop + endfacet + facet normal 0.198816 -0.868669 0.453748 + outer loop + vertex 1.42015 0.893295 2.46534 + vertex 1.42093 0.891761 2.46206 + vertex 1.42405 0.893623 2.46426 + endloop + endfacet + facet normal 0.18651 -0.872077 0.452433 + outer loop + vertex 1.42015 0.893295 2.46534 + vertex 1.4163 0.892212 2.46484 + vertex 1.42093 0.891761 2.46206 + endloop + endfacet + facet normal 0.192343 -0.866201 0.461194 + outer loop + vertex 1.4163 0.892212 2.46484 + vertex 1.41734 0.890918 2.46197 + vertex 1.42093 0.891761 2.46206 + endloop + endfacet + facet normal 0.168092 -0.837736 0.519561 + outer loop + vertex 1.42015 0.893295 2.46534 + vertex 1.41793 0.894165 2.46746 + vertex 1.4163 0.892212 2.46484 + endloop + endfacet + facet normal 0.215967 -0.819639 0.530613 + outer loop + vertex 1.42405 0.893623 2.46426 + vertex 1.42161 0.895122 2.46757 + vertex 1.42015 0.893295 2.46534 + endloop + endfacet + facet normal 0.196837 -0.817443 0.541334 + outer loop + vertex 1.41793 0.894165 2.46746 + vertex 1.42015 0.893295 2.46534 + vertex 1.42161 0.895122 2.46757 + endloop + endfacet + facet normal 0.175435 -0.74637 0.641992 + outer loop + vertex 1.41793 0.894165 2.46746 + vertex 1.42161 0.895122 2.46757 + vertex 1.4174 0.896499 2.47032 + endloop + endfacet + facet normal 0.167014 -0.7554 0.633622 + outer loop + vertex 1.4174 0.896499 2.47032 + vertex 1.42161 0.895122 2.46757 + vertex 1.42266 0.897511 2.47014 + endloop + endfacet + facet normal 0.153765 -0.670066 0.726201 + outer loop + vertex 1.42266 0.897511 2.47014 + vertex 1.41975 0.899695 2.47277 + vertex 1.4174 0.896499 2.47032 + endloop + endfacet + facet normal 0.139058 -0.680972 0.718986 + outer loop + vertex 1.42427 0.900048 2.47223 + vertex 1.41975 0.899695 2.47277 + vertex 1.42266 0.897511 2.47014 + endloop + endfacet + facet normal 0.141157 -0.579407 0.802722 + outer loop + vertex 1.42427 0.900048 2.47223 + vertex 1.42263 0.902734 2.47446 + vertex 1.41975 0.899695 2.47277 + endloop + endfacet + facet normal 0.13963 -0.578478 0.803658 + outer loop + vertex 1.41975 0.899695 2.47277 + vertex 1.42263 0.902734 2.47446 + vertex 1.41811 0.902446 2.47503 + endloop + endfacet + facet normal 0.141247 -0.487968 0.861358 + outer loop + vertex 1.41811 0.902446 2.47503 + vertex 1.42263 0.902734 2.47446 + vertex 1.42098 0.905667 2.47639 + endloop + endfacet + facet normal 0.138149 -0.485908 0.863023 + outer loop + vertex 1.41716 0.904857 2.47654 + vertex 1.41811 0.902446 2.47503 + vertex 1.42098 0.905667 2.47639 + endloop + endfacet + facet normal 0.123263 -0.407701 0.904758 + outer loop + vertex 1.42098 0.905667 2.47639 + vertex 1.41855 0.908559 2.47802 + vertex 1.41716 0.904857 2.47654 + endloop + endfacet + facet normal 0.11485 -0.413842 0.903075 + outer loop + vertex 1.42431 0.90956 2.47775 + vertex 1.41855 0.908559 2.47802 + vertex 1.42098 0.905667 2.47639 + endloop + endfacet + facet normal 0.108605 -0.372829 0.921522 + outer loop + vertex 1.42431 0.90956 2.47775 + vertex 1.42312 0.913599 2.47952 + vertex 1.41855 0.908559 2.47802 + endloop + endfacet + facet normal 0.13226 -0.55154 -0.823596 + outer loop + vertex 1.425 0.998765 2.49 + vertex 1.42 0.997566 2.49 + vertex 1.42085 0.998459 2.48954 + endloop + endfacet + facet normal 0.11994 -0.847622 -0.516867 + outer loop + vertex 1.42465 0.999341 2.48898 + vertex 1.425 0.998765 2.49 + vertex 1.42085 0.998459 2.48954 + endloop + endfacet + facet normal -0.228389 0.871998 0.432965 + outer loop + vertex 1.41999 0.998136 2.50023 + vertex 1.41656 0.998255 2.49818 + vertex 1.41802 0.99701 2.50146 + endloop + endfacet + facet normal -0.151247 0.837499 0.525091 + outer loop + vertex 1.42317 0.996862 2.50318 + vertex 1.41999 0.998136 2.50023 + vertex 1.41802 0.99701 2.50146 + endloop + endfacet + facet normal -0.218308 0.668125 0.711303 + outer loop + vertex 1.42317 0.996862 2.50318 + vertex 1.41802 0.99701 2.50146 + vertex 1.422 0.994992 2.50458 + endloop + endfacet + facet normal -0.000961397 0.838835 0.544385 + outer loop + vertex 1.422 0.994992 2.50458 + vertex 1.41802 0.99701 2.50146 + vertex 1.41775 0.995211 2.50423 + endloop + endfacet + facet normal -0.0133629 0.60494 0.796159 + outer loop + vertex 1.42053 0.993516 2.50557 + vertex 1.41775 0.995211 2.50423 + vertex 1.41708 0.993137 2.5058 + endloop + endfacet + facet normal -0.0361924 0.580922 0.813154 + outer loop + vertex 1.422 0.994992 2.50458 + vertex 1.41775 0.995211 2.50423 + vertex 1.42053 0.993516 2.50557 + endloop + endfacet + facet normal -0.250773 0.943194 -0.217939 + outer loop + vertex 1.42085 0.998459 2.48954 + vertex 1.42449 0.999952 2.49181 + vertex 1.42465 0.999341 2.48898 + endloop + endfacet + facet normal -0.214479 0.937934 -0.272542 + outer loop + vertex 1.4192 0.998946 2.49251 + vertex 1.42449 0.999952 2.49181 + vertex 1.42085 0.998459 2.48954 + endloop + endfacet + facet normal -0.187205 0.982319 -0.00197643 + outer loop + vertex 1.42449 0.999952 2.49181 + vertex 1.4192 0.998946 2.49251 + vertex 1.42325 0.999726 2.49648 + endloop + endfacet + facet normal -0.179627 0.983684 -0.00999235 + outer loop + vertex 1.42325 0.999726 2.49648 + vertex 1.4192 0.998946 2.49251 + vertex 1.41858 0.998874 2.49663 + endloop + endfacet + facet normal -0.110303 0.964266 0.240881 + outer loop + vertex 1.41999 0.998136 2.50023 + vertex 1.41858 0.998874 2.49663 + vertex 1.41656 0.998255 2.49818 + endloop + endfacet + facet normal -0.199065 0.941778 0.270975 + outer loop + vertex 1.41999 0.998136 2.50023 + vertex 1.42404 0.998748 2.50108 + vertex 1.41858 0.998874 2.49663 + endloop + endfacet + facet normal -0.166928 0.958284 0.232006 + outer loop + vertex 1.42404 0.998748 2.50108 + vertex 1.42325 0.999726 2.49648 + vertex 1.41858 0.998874 2.49663 + endloop + endfacet + facet normal -0.240037 0.769595 0.591698 + outer loop + vertex 1.42404 0.998748 2.50108 + vertex 1.41999 0.998136 2.50023 + vertex 1.42317 0.996862 2.50318 + endloop + endfacet + facet normal -0.218599 -0.87328 -0.435426 + outer loop + vertex 1.42595 2.02648 2.49217 + vertex 1.42136 2.02705 2.49335 + vertex 1.42297 2.02823 2.49016 + endloop + endfacet + facet normal -0.164535 -0.970279 -0.177442 + outer loop + vertex 1.42452 2.02582 2.49712 + vertex 1.42136 2.02705 2.49335 + vertex 1.42595 2.02648 2.49217 + endloop + endfacet + facet normal -0.260261 -0.960925 -0.094268 + outer loop + vertex 1.42058 2.02677 2.49826 + vertex 1.42136 2.02705 2.49335 + vertex 1.42452 2.02582 2.49712 + endloop + endfacet + facet normal -0.226425 -0.973466 0.0331053 + outer loop + vertex 1.42372 2.02616 2.5017 + vertex 1.42058 2.02677 2.49826 + vertex 1.42452 2.02582 2.49712 + endloop + endfacet + facet normal -0.300293 -0.948053 0.104973 + outer loop + vertex 1.42028 2.02737 2.50279 + vertex 1.42058 2.02677 2.49826 + vertex 1.42372 2.02616 2.5017 + endloop + endfacet + facet normal -0.252938 -0.936572 0.2426 + outer loop + vertex 1.423 2.02715 2.50477 + vertex 1.42028 2.02737 2.50279 + vertex 1.42372 2.02616 2.5017 + endloop + endfacet + facet normal -0.361924 -0.840738 0.402704 + outer loop + vertex 1.42069 2.02858 2.50567 + vertex 1.42028 2.02737 2.50279 + vertex 1.423 2.02715 2.50477 + endloop + endfacet + facet normal -0.141437 -0.682248 0.71731 + outer loop + vertex 1.423 2.02715 2.50477 + vertex 1.42384 2.02908 2.50678 + vertex 1.42069 2.02858 2.50567 + endloop + endfacet + facet normal -0.237838 -0.864892 -0.442035 + outer loop + vertex 1.42297 2.02823 2.49016 + vertex 1.42136 2.02705 2.49335 + vertex 1.41866 2.02925 2.49049 + endloop + endfacet + facet normal -0.0760367 -0.000529839 -0.997105 + outer loop + vertex 1.42297 2.02823 2.49016 + vertex 1.41866 2.02925 2.49049 + vertex 1.425 2.03202 2.49 + endloop + endfacet + facet normal -0.0145728 -0.140125 -0.990027 + outer loop + vertex 1.425 2.03202 2.49 + vertex 1.41866 2.02925 2.49049 + vertex 1.42 2.03254 2.49 + endloop + endfacet + facet normal -0.233253 -0.968202 -0.09043 + outer loop + vertex 1.42136 2.02705 2.49335 + vertex 1.42058 2.02677 2.49826 + vertex 1.41703 2.02796 2.49471 + endloop + endfacet + facet normal -0.30508 -0.871596 -0.383726 + outer loop + vertex 1.41866 2.02925 2.49049 + vertex 1.42136 2.02705 2.49335 + vertex 1.41703 2.02796 2.49471 + endloop + endfacet + facet normal -0.256186 -0.960396 0.109585 + outer loop + vertex 1.42058 2.02677 2.49826 + vertex 1.42028 2.02737 2.50279 + vertex 1.41658 2.02801 2.49978 + endloop + endfacet + facet normal -0.301857 -0.953204 -0.0168583 + outer loop + vertex 1.41703 2.02796 2.49471 + vertex 1.42058 2.02677 2.49826 + vertex 1.41658 2.02801 2.49978 + endloop + endfacet + facet normal -0.289024 -0.86805 0.403676 + outer loop + vertex 1.42028 2.02737 2.50279 + vertex 1.42069 2.02858 2.50567 + vertex 1.41649 2.02945 2.50454 + endloop + endfacet + facet normal -0.368121 -0.892226 0.261573 + outer loop + vertex 1.41658 2.02801 2.49978 + vertex 1.42028 2.02737 2.50279 + vertex 1.41649 2.02945 2.50454 + endloop + endfacet + facet normal -0.320755 -0.511868 0.796936 + outer loop + vertex 1.42069 2.02858 2.50567 + vertex 1.4195 2.03147 2.50705 + vertex 1.41649 2.02945 2.50454 + endloop + endfacet + facet normal -0.216383 -0.491077 0.843814 + outer loop + vertex 1.42069 2.02858 2.50567 + vertex 1.42384 2.02908 2.50678 + vertex 1.4195 2.03147 2.50705 + endloop + endfacet + facet normal -0.131026 -0.345409 0.92926 + outer loop + vertex 1.42384 2.02908 2.50678 + vertex 1.42274 2.03157 2.50755 + vertex 1.4195 2.03147 2.50705 + endloop + endfacet + facet normal 0.113069 0.623537 0.773574 + outer loop + vertex 1.4188 2.12805 2.47519 + vertex 1.4228 2.12734 2.47518 + vertex 1.42181 2.13028 2.47295 + endloop + endfacet + facet normal 0.124318 0.614129 0.779353 + outer loop + vertex 1.41641 2.13105 2.47321 + vertex 1.4188 2.12805 2.47519 + vertex 1.42181 2.13028 2.47295 + endloop + endfacet + facet normal 0.113517 0.483374 0.868023 + outer loop + vertex 1.42122 2.1244 2.47691 + vertex 1.4188 2.12805 2.47519 + vertex 1.41606 2.12538 2.47704 + endloop + endfacet + facet normal 0.0859354 0.470019 0.878463 + outer loop + vertex 1.4228 2.12734 2.47518 + vertex 1.4188 2.12805 2.47519 + vertex 1.42122 2.1244 2.47691 + endloop + endfacet + facet normal 0.141313 0.908921 0.392293 + outer loop + vertex 1.41966 2.13496 2.46719 + vertex 1.42493 2.13467 2.46595 + vertex 1.42093 2.13639 2.46341 + endloop + endfacet + facet normal 0.153641 0.905656 0.395197 + outer loop + vertex 1.41616 2.13672 2.46451 + vertex 1.41966 2.13496 2.46719 + vertex 1.42093 2.13639 2.46341 + endloop + endfacet + facet normal 0.163662 0.850308 0.500191 + outer loop + vertex 1.42493 2.13467 2.46595 + vertex 1.41966 2.13496 2.46719 + vertex 1.42322 2.13281 2.46967 + endloop + endfacet + facet normal 0.143051 0.841011 0.521764 + outer loop + vertex 1.42322 2.13281 2.46967 + vertex 1.41966 2.13496 2.46719 + vertex 1.41823 2.13313 2.47053 + endloop + endfacet + facet normal 0.136029 0.73623 0.662919 + outer loop + vertex 1.42181 2.13028 2.47295 + vertex 1.41823 2.13313 2.47053 + vertex 1.41641 2.13105 2.47321 + endloop + endfacet + facet normal 0.158275 0.748303 0.644198 + outer loop + vertex 1.42322 2.13281 2.46967 + vertex 1.41823 2.13313 2.47053 + vertex 1.42181 2.13028 2.47295 + endloop + endfacet + facet normal -0.42728 0.858073 -0.284854 + outer loop + vertex 1.42 2.14 2.45503 + vertex 1.425 2.14248 2.455 + vertex 1.42002 2.14 2.455 + endloop + endfacet + facet normal -0.417057 0.836608 -0.355175 + outer loop + vertex 1.42 2.14 2.45503 + vertex 1.42 2.14211 2.46 + vertex 1.425 2.14248 2.455 + endloop + endfacet + facet normal 0.707563 -0.0900825 0.700884 + outer loop + vertex 1.42 2.14211 2.46 + vertex 1.42297 2.13924 2.45663 + vertex 1.425 2.14248 2.455 + endloop + endfacet + facet normal 0.825279 0.440635 0.353207 + outer loop + vertex 1.42297 2.13924 2.45663 + vertex 1.42 2.14211 2.46 + vertex 1.42255 2.13777 2.45946 + endloop + endfacet + facet normal 0.283096 0.0471051 0.957934 + outer loop + vertex 1.42255 2.13777 2.45946 + vertex 1.42 2.14211 2.46 + vertex 1.41739 2.13843 2.46095 + endloop + endfacet + facet normal 0.168645 0.86484 0.472875 + outer loop + vertex 1.42093 2.13639 2.46341 + vertex 1.41739 2.13843 2.46095 + vertex 1.41616 2.13672 2.46451 + endloop + endfacet + facet normal 0.229759 0.886103 0.402533 + outer loop + vertex 1.42255 2.13777 2.45946 + vertex 1.41739 2.13843 2.46095 + vertex 1.42093 2.13639 2.46341 + endloop + endfacet + facet normal 0.245571 -0.687119 -0.683786 + outer loop + vertex 1.42784 0.89 2.455 + vertex 1.425 0.888985 2.455 + vertex 1.425 0.89 2.45398 + endloop + endfacet + facet normal 0.314354 -0.879579 0.357103 + outer loop + vertex 1.42784 0.89 2.455 + vertex 1.425 0.89 2.4575 + vertex 1.425 0.888985 2.455 + endloop + endfacet + facet normal 0.0653587 -0.57034 0.818804 + outer loop + vertex 1.43 0.891944 2.46 + vertex 1.42664 0.892294 2.46051 + vertex 1.425 0.891371 2.46 + endloop + endfacet + facet normal 0.235766 -0.757444 0.608846 + outer loop + vertex 1.42664 0.892294 2.46051 + vertex 1.42093 0.891761 2.46206 + vertex 1.425 0.891371 2.46 + endloop + endfacet + facet normal 0.202981 -0.87013 0.44908 + outer loop + vertex 1.42664 0.892294 2.46051 + vertex 1.42405 0.893623 2.46426 + vertex 1.42093 0.891761 2.46206 + endloop + endfacet + facet normal 0.181271 -0.880632 0.437754 + outer loop + vertex 1.42821 0.893949 2.46319 + vertex 1.42405 0.893623 2.46426 + vertex 1.42664 0.892294 2.46051 + endloop + endfacet + facet normal 0.195647 -0.839989 0.506103 + outer loop + vertex 1.42405 0.893623 2.46426 + vertex 1.42821 0.893949 2.46319 + vertex 1.42713 0.896013 2.46703 + endloop + endfacet + facet normal 0.184789 -0.836775 0.515422 + outer loop + vertex 1.42161 0.895122 2.46757 + vertex 1.42405 0.893623 2.46426 + vertex 1.42713 0.896013 2.46703 + endloop + endfacet + facet normal 0.149599 -0.781246 0.606032 + outer loop + vertex 1.42615 0.898249 2.47016 + vertex 1.42713 0.896013 2.46703 + vertex 1.42963 0.898356 2.46944 + endloop + endfacet + facet normal 0.160974 -0.778 0.607292 + outer loop + vertex 1.42615 0.898249 2.47016 + vertex 1.42266 0.897511 2.47014 + vertex 1.42713 0.896013 2.46703 + endloop + endfacet + facet normal 0.182678 -0.756356 0.628136 + outer loop + vertex 1.42266 0.897511 2.47014 + vertex 1.42161 0.895122 2.46757 + vertex 1.42713 0.896013 2.46703 + endloop + endfacet + facet normal 0.139912 -0.681199 0.718605 + outer loop + vertex 1.42615 0.898249 2.47016 + vertex 1.42427 0.900048 2.47223 + vertex 1.42266 0.897511 2.47014 + endloop + endfacet + facet normal 0.16595 -0.697041 0.697563 + outer loop + vertex 1.42963 0.898356 2.46944 + vertex 1.42768 0.899942 2.47149 + vertex 1.42615 0.898249 2.47016 + endloop + endfacet + facet normal 0.135024 -0.684156 0.716728 + outer loop + vertex 1.42768 0.899942 2.47149 + vertex 1.42427 0.900048 2.47223 + vertex 1.42615 0.898249 2.47016 + endloop + endfacet + facet normal 0.153303 -0.596221 0.788047 + outer loop + vertex 1.42768 0.899942 2.47149 + vertex 1.42788 0.902889 2.47368 + vertex 1.42427 0.900048 2.47223 + endloop + endfacet + facet normal 0.136306 -0.581689 0.801909 + outer loop + vertex 1.42788 0.902889 2.47368 + vertex 1.42263 0.902734 2.47446 + vertex 1.42427 0.900048 2.47223 + endloop + endfacet + facet normal 0.141604 -0.501395 0.853552 + outer loop + vertex 1.42263 0.902734 2.47446 + vertex 1.42788 0.902889 2.47368 + vertex 1.42585 0.906207 2.47596 + endloop + endfacet + facet normal 0.129961 -0.49342 0.860027 + outer loop + vertex 1.42098 0.905667 2.47639 + vertex 1.42263 0.902734 2.47446 + vertex 1.42585 0.906207 2.47596 + endloop + endfacet + facet normal 0.125273 -0.421082 0.89833 + outer loop + vertex 1.42585 0.906207 2.47596 + vertex 1.42431 0.90956 2.47775 + vertex 1.42098 0.905667 2.47639 + endloop + endfacet + facet normal 0.109234 -0.427854 0.897223 + outer loop + vertex 1.42931 0.909973 2.47734 + vertex 1.42431 0.90956 2.47775 + vertex 1.42585 0.906207 2.47596 + endloop + endfacet + facet normal 0.101752 -0.374833 0.921492 + outer loop + vertex 1.42431 0.90956 2.47775 + vertex 1.42832 0.913518 2.47892 + vertex 1.42312 0.913599 2.47952 + endloop + endfacet + facet normal 0.531013 -0.649261 -0.544504 + outer loop + vertex 1.42651 1 2.49 + vertex 1.425 0.998765 2.49 + vertex 1.42465 0.999341 2.48898 + endloop + endfacet + facet normal -0.080573 0.340954 0.936621 + outer loop + vertex 1.422 0.994992 2.50458 + vertex 1.42291 0.992556 2.50554 + vertex 1.42685 0.994081 2.50533 + endloop + endfacet + facet normal -0.0102476 0.602151 0.798317 + outer loop + vertex 1.422 0.994992 2.50458 + vertex 1.42685 0.994081 2.50533 + vertex 1.42317 0.996862 2.50318 + endloop + endfacet + facet normal -0.52108 0.210526 0.827136 + outer loop + vertex 1.429 0.996534 2.50606 + vertex 1.42716 0.997298 2.5047 + vertex 1.42685 0.994081 2.50533 + endloop + endfacet + facet normal -0.368181 0.211135 0.905464 + outer loop + vertex 1.42716 0.997298 2.5047 + vertex 1.42317 0.996862 2.50318 + vertex 1.42685 0.994081 2.50533 + endloop + endfacet + facet normal -0.42337 0.411128 0.807299 + outer loop + vertex 1.429 0.996534 2.50606 + vertex 1.42978 0.997645 2.5059 + vertex 1.42716 0.997298 2.5047 + endloop + endfacet + facet normal 0.177953 0.419427 0.890176 + outer loop + vertex 1.42291 0.992556 2.50554 + vertex 1.422 0.994992 2.50458 + vertex 1.42053 0.993516 2.50557 + endloop + endfacet + facet normal -0.388347 0.651608 -0.651608 + outer loop + vertex 1.43 1 2.48792 + vertex 1.42651 1 2.49 + vertex 1.43 1.00208 2.49 + endloop + endfacet + facet normal 0.479364 -0.804324 -0.351102 + outer loop + vertex 1.42465 0.999341 2.48898 + vertex 1.43 1.00208 2.49 + vertex 1.42651 1 2.49 + endloop + endfacet + facet normal -0.412383 0.885289 -0.214951 + outer loop + vertex 1.42465 0.999341 2.48898 + vertex 1.42449 0.999952 2.49181 + vertex 1.43 1.00208 2.49 + endloop + endfacet + facet normal -0.283528 0.930839 0.230543 + outer loop + vertex 1.42449 0.999952 2.49181 + vertex 1.42934 1.00113 2.49303 + vertex 1.43 1.00208 2.49 + endloop + endfacet + facet normal -0.24118 0.970168 0.0246211 + outer loop + vertex 1.42934 1.00113 2.49303 + vertex 1.42449 0.999952 2.49181 + vertex 1.42783 1.00067 2.49644 + endloop + endfacet + facet normal -0.201132 0.979547 -0.00578902 + outer loop + vertex 1.42783 1.00067 2.49644 + vertex 1.42449 0.999952 2.49181 + vertex 1.42325 0.999726 2.49648 + endloop + endfacet + facet normal -0.196434 0.964369 0.177221 + outer loop + vertex 1.42783 1.00067 2.49644 + vertex 1.42325 0.999726 2.49648 + vertex 1.42788 0.999915 2.50057 + endloop + endfacet + facet normal -0.252761 0.936775 0.242003 + outer loop + vertex 1.42788 0.999915 2.50057 + vertex 1.42325 0.999726 2.49648 + vertex 1.42404 0.998748 2.50108 + endloop + endfacet + facet normal -0.299679 0.768093 0.565884 + outer loop + vertex 1.42716 0.997298 2.5047 + vertex 1.42404 0.998748 2.50108 + vertex 1.42317 0.996862 2.50318 + endloop + endfacet + facet normal -0.371083 0.70638 0.602764 + outer loop + vertex 1.42716 0.997298 2.5047 + vertex 1.42894 0.998761 2.50408 + vertex 1.42404 0.998748 2.50108 + endloop + endfacet + facet normal -0.226247 0.90294 0.365392 + outer loop + vertex 1.42894 0.998761 2.50408 + vertex 1.42788 0.999915 2.50057 + vertex 1.42404 0.998748 2.50108 + endloop + endfacet + facet normal -0.369824 0.705578 0.604474 + outer loop + vertex 1.42894 0.998761 2.50408 + vertex 1.42716 0.997298 2.5047 + vertex 1.42978 0.997645 2.5059 + endloop + endfacet + facet normal 0.208045 -0.564602 -0.798713 + outer loop + vertex 1.42716 2.03 2.49 + vertex 1.42595 2.02648 2.49217 + vertex 1.42297 2.02823 2.49016 + endloop + endfacet + facet normal -0.33316 -0.409581 -0.849263 + outer loop + vertex 1.42716 2.03 2.49 + vertex 1.43 2.02769 2.49 + vertex 1.42595 2.02648 2.49217 + endloop + endfacet + facet normal -0.0859093 -0.794117 -0.601662 + outer loop + vertex 1.43 2.02769 2.49 + vertex 1.42995 2.02536 2.49308 + vertex 1.42595 2.02648 2.49217 + endloop + endfacet + facet normal -0.235905 -0.960603 -0.146939 + outer loop + vertex 1.42995 2.02536 2.49308 + vertex 1.4287 2.02511 2.49677 + vertex 1.42595 2.02648 2.49217 + endloop + endfacet + facet normal -0.180819 -0.966596 -0.181651 + outer loop + vertex 1.4287 2.02511 2.49677 + vertex 1.42452 2.02582 2.49712 + vertex 1.42595 2.02648 2.49217 + endloop + endfacet + facet normal -0.164824 -0.985308 0.0447342 + outer loop + vertex 1.4287 2.02511 2.49677 + vertex 1.42766 2.02548 2.50122 + vertex 1.42452 2.02582 2.49712 + endloop + endfacet + facet normal -0.164831 -0.985307 0.0447392 + outer loop + vertex 1.42766 2.02548 2.50122 + vertex 1.42372 2.02616 2.5017 + vertex 1.42452 2.02582 2.49712 + endloop + endfacet + facet normal -0.129464 -0.950707 0.281773 + outer loop + vertex 1.42766 2.02548 2.50122 + vertex 1.42629 2.02671 2.50472 + vertex 1.42372 2.02616 2.5017 + endloop + endfacet + facet normal -0.124453 -0.952533 0.277834 + outer loop + vertex 1.42629 2.02671 2.50472 + vertex 1.423 2.02715 2.50477 + vertex 1.42372 2.02616 2.5017 + endloop + endfacet + facet normal -0.0838101 -0.699499 0.709702 + outer loop + vertex 1.42629 2.02671 2.50472 + vertex 1.42384 2.02908 2.50678 + vertex 1.423 2.02715 2.50477 + endloop + endfacet + facet normal -0.0719344 -0.69347 0.716885 + outer loop + vertex 1.42873 2.02854 2.50674 + vertex 1.42384 2.02908 2.50678 + vertex 1.42629 2.02671 2.50472 + endloop + endfacet + facet normal -0.0257863 -0.0275728 -0.999287 + outer loop + vertex 1.42716 2.03 2.49 + vertex 1.42297 2.02823 2.49016 + vertex 1.425 2.03202 2.49 + endloop + endfacet + facet normal 0.0824756 -0.260753 0.961876 + outer loop + vertex 1.42384 2.02908 2.50678 + vertex 1.42619 2.03199 2.50736 + vertex 1.42274 2.03157 2.50755 + endloop + endfacet + facet normal 0.142861 0.526203 0.838272 + outer loop + vertex 1.4228 2.12734 2.47518 + vertex 1.42523 2.12528 2.47606 + vertex 1.42624 2.12773 2.47435 + endloop + endfacet + facet normal 0.115933 0.623932 0.772831 + outer loop + vertex 1.4228 2.12734 2.47518 + vertex 1.42624 2.12773 2.47435 + vertex 1.42181 2.13028 2.47295 + endloop + endfacet + facet normal 0.152618 0.664855 0.731215 + outer loop + vertex 1.42181 2.13028 2.47295 + vertex 1.42624 2.12773 2.47435 + vertex 1.42679 2.13034 2.47186 + endloop + endfacet + facet normal 0.0822536 0.471681 0.877925 + outer loop + vertex 1.42523 2.12528 2.47606 + vertex 1.4228 2.12734 2.47518 + vertex 1.42122 2.1244 2.47691 + endloop + endfacet + facet normal 0.152184 0.929852 0.334987 + outer loop + vertex 1.42907 2.13525 2.46299 + vertex 1.42693 2.13674 2.45984 + vertex 1.42491 2.13615 2.46239 + endloop + endfacet + facet normal 0.152439 0.913285 0.377721 + outer loop + vertex 1.42491 2.13615 2.46239 + vertex 1.42093 2.13639 2.46341 + vertex 1.42493 2.13467 2.46595 + endloop + endfacet + facet normal 0.142646 0.914624 0.378305 + outer loop + vertex 1.42491 2.13615 2.46239 + vertex 1.42493 2.13467 2.46595 + vertex 1.42907 2.13525 2.46299 + endloop + endfacet + facet normal 0.165195 0.898487 0.406734 + outer loop + vertex 1.42907 2.13525 2.46299 + vertex 1.42493 2.13467 2.46595 + vertex 1.42852 2.13394 2.4661 + endloop + endfacet + facet normal 0.151883 0.852578 0.500042 + outer loop + vertex 1.42852 2.13394 2.4661 + vertex 1.42493 2.13467 2.46595 + vertex 1.42819 2.13245 2.46875 + endloop + endfacet + facet normal 0.154584 0.853504 0.497629 + outer loop + vertex 1.42819 2.13245 2.46875 + vertex 1.42493 2.13467 2.46595 + vertex 1.42322 2.13281 2.46967 + endloop + endfacet + facet normal 0.13135 0.75737 0.639639 + outer loop + vertex 1.42679 2.13034 2.47186 + vertex 1.42322 2.13281 2.46967 + vertex 1.42181 2.13028 2.47295 + endloop + endfacet + facet normal 0.168882 0.779452 0.603269 + outer loop + vertex 1.42819 2.13245 2.46875 + vertex 1.42322 2.13281 2.46967 + vertex 1.42679 2.13034 2.47186 + endloop + endfacet + facet normal 0.00819842 0.341816 0.939731 + outer loop + vertex 1.43 2.14236 2.455 + vertex 1.425 2.14248 2.455 + vertex 1.4271 2.13853 2.45642 + endloop + endfacet + facet normal 0.114161 0.38888 0.914188 + outer loop + vertex 1.4271 2.13853 2.45642 + vertex 1.425 2.14248 2.455 + vertex 1.42297 2.13924 2.45663 + endloop + endfacet + facet normal 0.184136 0.915772 0.357009 + outer loop + vertex 1.42693 2.13674 2.45984 + vertex 1.42255 2.13777 2.45946 + vertex 1.42491 2.13615 2.46239 + endloop + endfacet + facet normal 0.164254 0.870594 0.463774 + outer loop + vertex 1.42693 2.13674 2.45984 + vertex 1.4271 2.13853 2.45642 + vertex 1.42255 2.13777 2.45946 + endloop + endfacet + facet normal 0.173928 0.862023 0.476094 + outer loop + vertex 1.4271 2.13853 2.45642 + vertex 1.42297 2.13924 2.45663 + vertex 1.42255 2.13777 2.45946 + endloop + endfacet + facet normal 0.152994 0.912187 0.380142 + outer loop + vertex 1.42491 2.13615 2.46239 + vertex 1.42255 2.13777 2.45946 + vertex 1.42093 2.13639 2.46341 + endloop + endfacet + facet normal 0.0639851 -0.981254 0.181789 + outer loop + vertex 1.435 0.891924 2.455 + vertex 1.43161 0.892144 2.45738 + vertex 1.43 0.891598 2.455 + endloop + endfacet + facet normal 0.23018 -0.970827 0.0671806 + outer loop + vertex 1.43161 0.892144 2.45738 + vertex 1.43 0.891944 2.46 + vertex 1.43 0.891598 2.455 + endloop + endfacet + facet normal 0.167875 -0.917364 0.360916 + outer loop + vertex 1.43073 0.893278 2.46068 + vertex 1.43161 0.892144 2.45738 + vertex 1.43498 0.893588 2.45948 + endloop + endfacet + facet normal 0.204014 -0.907489 0.367208 + outer loop + vertex 1.43073 0.893278 2.46068 + vertex 1.42664 0.892294 2.46051 + vertex 1.43161 0.892144 2.45738 + endloop + endfacet + facet normal 0.125594 0.980318 0.152323 + outer loop + vertex 1.42664 0.892294 2.46051 + vertex 1.43 0.891944 2.46 + vertex 1.43161 0.892144 2.45738 + endloop + endfacet + facet normal 0.195196 -0.881429 0.430095 + outer loop + vertex 1.43073 0.893278 2.46068 + vertex 1.42821 0.893949 2.46319 + vertex 1.42664 0.892294 2.46051 + endloop + endfacet + facet normal 0.182941 -0.887796 0.422315 + outer loop + vertex 1.43498 0.893588 2.45948 + vertex 1.43257 0.89509 2.46368 + vertex 1.43073 0.893278 2.46068 + endloop + endfacet + facet normal 0.184684 -0.887911 0.421314 + outer loop + vertex 1.42821 0.893949 2.46319 + vertex 1.43073 0.893278 2.46068 + vertex 1.43257 0.89509 2.46368 + endloop + endfacet + facet normal 0.165276 -0.848757 0.502291 + outer loop + vertex 1.42821 0.893949 2.46319 + vertex 1.43257 0.89509 2.46368 + vertex 1.42713 0.896013 2.46703 + endloop + endfacet + facet normal 0.164424 -0.849602 0.501141 + outer loop + vertex 1.42713 0.896013 2.46703 + vertex 1.43257 0.89509 2.46368 + vertex 1.43195 0.896968 2.46707 + endloop + endfacet + facet normal 0.150026 -0.781396 0.605733 + outer loop + vertex 1.43195 0.896968 2.46707 + vertex 1.42963 0.898356 2.46944 + vertex 1.42713 0.896013 2.46703 + endloop + endfacet + facet normal 0.159941 -0.774841 0.611588 + outer loop + vertex 1.43405 0.898859 2.46892 + vertex 1.42963 0.898356 2.46944 + vertex 1.43195 0.896968 2.46707 + endloop + endfacet + facet normal 0.161287 -0.690434 0.705186 + outer loop + vertex 1.42963 0.898356 2.46944 + vertex 1.43405 0.898859 2.46892 + vertex 1.43145 0.90086 2.47147 + endloop + endfacet + facet normal 0.171338 -0.693399 0.699887 + outer loop + vertex 1.42768 0.899942 2.47149 + vertex 1.42963 0.898356 2.46944 + vertex 1.43145 0.90086 2.47147 + endloop + endfacet + facet normal 0.148038 -0.596474 0.788863 + outer loop + vertex 1.43145 0.90086 2.47147 + vertex 1.42788 0.902889 2.47368 + vertex 1.42768 0.899942 2.47149 + endloop + endfacet + facet normal 0.142761 -0.602135 0.785527 + outer loop + vertex 1.43391 0.904408 2.47375 + vertex 1.42788 0.902889 2.47368 + vertex 1.43145 0.90086 2.47147 + endloop + endfacet + facet normal 0.119668 -0.513207 0.849881 + outer loop + vertex 1.42788 0.902889 2.47368 + vertex 1.43391 0.904408 2.47375 + vertex 1.43075 0.90682 2.47565 + endloop + endfacet + facet normal 0.119023 -0.512879 0.850169 + outer loop + vertex 1.42585 0.906207 2.47596 + vertex 1.42788 0.902889 2.47368 + vertex 1.43075 0.90682 2.47565 + endloop + endfacet + facet normal 0.111585 -0.429604 0.896097 + outer loop + vertex 1.43075 0.90682 2.47565 + vertex 1.42931 0.909973 2.47734 + vertex 1.42585 0.906207 2.47596 + endloop + endfacet + facet normal 0.100828 -0.434064 0.895222 + outer loop + vertex 1.4338 0.910227 2.47696 + vertex 1.42931 0.909973 2.47734 + vertex 1.43075 0.90682 2.47565 + endloop + endfacet + facet normal 0.0998301 -0.378884 0.920044 + outer loop + vertex 1.4338 0.910227 2.47696 + vertex 1.43316 0.913696 2.47845 + vertex 1.42931 0.909973 2.47734 + endloop + endfacet + facet normal -0.0819561 -0.217662 0.972577 + outer loop + vertex 1.429 0.996534 2.50606 + vertex 1.42685 0.994081 2.50533 + vertex 1.43087 0.996391 2.50618 + endloop + endfacet + facet normal -0.0521632 0.178773 0.982507 + outer loop + vertex 1.43087 0.996391 2.50618 + vertex 1.42978 0.997645 2.5059 + vertex 1.429 0.996534 2.50606 + endloop + endfacet + facet normal 0.0517275 0.264718 0.962938 + outer loop + vertex 1.43139 0.998095 2.50569 + vertex 1.42978 0.997645 2.5059 + vertex 1.43087 0.996391 2.50618 + endloop + endfacet + facet normal -0.0847001 0.962497 0.257732 + outer loop + vertex 1.435 1.00252 2.49 + vertex 1.43 1.00208 2.49 + vertex 1.43355 1.0017 2.49257 + endloop + endfacet + facet normal -0.100325 0.955261 0.27823 + outer loop + vertex 1.43355 1.0017 2.49257 + vertex 1.43 1.00208 2.49 + vertex 1.42934 1.00113 2.49303 + endloop + endfacet + facet normal -0.124534 0.987364 0.0979948 + outer loop + vertex 1.43355 1.0017 2.49257 + vertex 1.42934 1.00113 2.49303 + vertex 1.43255 1.00117 2.49668 + endloop + endfacet + facet normal -0.110203 0.990238 0.085343 + outer loop + vertex 1.43255 1.00117 2.49668 + vertex 1.42934 1.00113 2.49303 + vertex 1.42783 1.00067 2.49644 + endloop + endfacet + facet normal -0.112798 0.981876 0.1523 + outer loop + vertex 1.43255 1.00117 2.49668 + vertex 1.42783 1.00067 2.49644 + vertex 1.4314 1.00052 2.5 + endloop + endfacet + facet normal -0.139151 0.974077 0.178354 + outer loop + vertex 1.4314 1.00052 2.5 + vertex 1.42783 1.00067 2.49644 + vertex 1.42788 0.999915 2.50057 + endloop + endfacet + facet normal -0.0936433 0.914231 0.394225 + outer loop + vertex 1.4314 1.00052 2.5 + vertex 1.42788 0.999915 2.50057 + vertex 1.4324 0.999086 2.50357 + endloop + endfacet + facet normal -0.0409604 0.945417 0.323278 + outer loop + vertex 1.4324 0.999086 2.50357 + vertex 1.42788 0.999915 2.50057 + vertex 1.42894 0.998761 2.50408 + endloop + endfacet + facet normal -0.150924 0.809508 0.567379 + outer loop + vertex 1.43139 0.998095 2.50569 + vertex 1.42894 0.998761 2.50408 + vertex 1.42978 0.997645 2.5059 + endloop + endfacet + facet normal -0.0240741 0.909594 0.4148 + outer loop + vertex 1.4324 0.999086 2.50357 + vertex 1.42894 0.998761 2.50408 + vertex 1.43139 0.998095 2.50569 + endloop + endfacet + facet normal -0.0217196 -0.724152 -0.689298 + outer loop + vertex 1.435 2.02754 2.49 + vertex 1.43371 2.02522 2.49247 + vertex 1.43 2.02769 2.49 + endloop + endfacet + facet normal -0.125744 -0.790449 -0.599482 + outer loop + vertex 1.43371 2.02522 2.49247 + vertex 1.42995 2.02536 2.49308 + vertex 1.43 2.02769 2.49 + endloop + endfacet + facet normal -0.0566819 -0.990209 -0.127566 + outer loop + vertex 1.43371 2.02522 2.49247 + vertex 1.43309 2.02471 2.49676 + vertex 1.42995 2.02536 2.49308 + endloop + endfacet + facet normal -0.089904 -0.990984 -0.0993334 + outer loop + vertex 1.43309 2.02471 2.49676 + vertex 1.4287 2.02511 2.49677 + vertex 1.42995 2.02536 2.49308 + endloop + endfacet + facet normal -0.0896264 -0.993068 0.0760505 + outer loop + vertex 1.43309 2.02471 2.49676 + vertex 1.43215 2.02512 2.50109 + vertex 1.4287 2.02511 2.49677 + endloop + endfacet + facet normal -0.0771479 -0.994826 0.0660953 + outer loop + vertex 1.43215 2.02512 2.50109 + vertex 1.42766 2.02548 2.50122 + vertex 1.4287 2.02511 2.49677 + endloop + endfacet + facet normal -0.067528 -0.952628 0.296545 + outer loop + vertex 1.43215 2.02512 2.50109 + vertex 1.43075 2.02632 2.50462 + vertex 1.42766 2.02548 2.50122 + endloop + endfacet + facet normal -0.0750094 -0.950122 0.302723 + outer loop + vertex 1.43075 2.02632 2.50462 + vertex 1.42629 2.02671 2.50472 + vertex 1.42766 2.02548 2.50122 + endloop + endfacet + facet normal -0.0449229 -0.711799 0.700945 + outer loop + vertex 1.43075 2.02632 2.50462 + vertex 1.42873 2.02854 2.50674 + vertex 1.42629 2.02671 2.50472 + endloop + endfacet + facet normal -0.0611643 -0.718646 0.692681 + outer loop + vertex 1.43369 2.02802 2.50664 + vertex 1.42873 2.02854 2.50674 + vertex 1.43075 2.02632 2.50462 + endloop + endfacet + facet normal 0.146299 0.54443 0.82595 + outer loop + vertex 1.42909 2.12454 2.47583 + vertex 1.43396 2.12363 2.47557 + vertex 1.43117 2.12753 2.4735 + endloop + endfacet + facet normal 0.165551 0.533679 0.829325 + outer loop + vertex 1.42624 2.12773 2.47435 + vertex 1.42909 2.12454 2.47583 + vertex 1.43117 2.12753 2.4735 + endloop + endfacet + facet normal 0.12584 0.414145 0.90147 + outer loop + vertex 1.43396 2.12363 2.47557 + vertex 1.42909 2.12454 2.47583 + vertex 1.43113 2.12076 2.47729 + endloop + endfacet + facet normal 0.18742 0.77725 0.60063 + outer loop + vertex 1.43423 2.12921 2.47127 + vertex 1.43204 2.13125 2.46931 + vertex 1.43039 2.13027 2.4711 + endloop + endfacet + facet normal 0.153664 0.674878 0.721753 + outer loop + vertex 1.43039 2.13027 2.4711 + vertex 1.43117 2.12753 2.4735 + vertex 1.43423 2.12921 2.47127 + endloop + endfacet + facet normal 0.165948 0.675486 0.718457 + outer loop + vertex 1.43039 2.13027 2.4711 + vertex 1.42679 2.13034 2.47186 + vertex 1.43117 2.12753 2.4735 + endloop + endfacet + facet normal 0.154111 0.664526 0.731201 + outer loop + vertex 1.42679 2.13034 2.47186 + vertex 1.42624 2.12773 2.47435 + vertex 1.43117 2.12753 2.4735 + endloop + endfacet + facet normal 0.0712452 0.9041 0.42134 + outer loop + vertex 1.42907 2.13525 2.46299 + vertex 1.43492 2.13544 2.4616 + vertex 1.43127 2.13701 2.45885 + endloop + endfacet + facet normal 0.0355864 0.913079 0.406227 + outer loop + vertex 1.42693 2.13674 2.45984 + vertex 1.42907 2.13525 2.46299 + vertex 1.43127 2.13701 2.45885 + endloop + endfacet + facet normal 0.0917458 0.860033 0.501922 + outer loop + vertex 1.43492 2.13544 2.4616 + vertex 1.42907 2.13525 2.46299 + vertex 1.43219 2.1331 2.4661 + endloop + endfacet + facet normal 0.203946 0.889129 0.409702 + outer loop + vertex 1.43219 2.1331 2.4661 + vertex 1.42907 2.13525 2.46299 + vertex 1.42852 2.13394 2.4661 + endloop + endfacet + facet normal 0.161325 0.794207 0.585841 + outer loop + vertex 1.43204 2.13125 2.46931 + vertex 1.42819 2.13245 2.46875 + vertex 1.43039 2.13027 2.4711 + endloop + endfacet + facet normal 0.190697 0.846718 0.496692 + outer loop + vertex 1.43204 2.13125 2.46931 + vertex 1.43219 2.1331 2.4661 + vertex 1.42819 2.13245 2.46875 + endloop + endfacet + facet normal 0.193579 0.8439 0.50036 + outer loop + vertex 1.43219 2.1331 2.4661 + vertex 1.42852 2.13394 2.4661 + vertex 1.42819 2.13245 2.46875 + endloop + endfacet + facet normal 0.142945 0.788699 0.59793 + outer loop + vertex 1.43039 2.13027 2.4711 + vertex 1.42819 2.13245 2.46875 + vertex 1.42679 2.13034 2.47186 + endloop + endfacet + facet normal 0.0122932 0.256014 0.966595 + outer loop + vertex 1.435 2.14212 2.455 + vertex 1.43 2.14236 2.455 + vertex 1.43367 2.13921 2.45579 + endloop + endfacet + facet normal 0.0594367 0.306795 0.949918 + outer loop + vertex 1.43367 2.13921 2.45579 + vertex 1.43 2.14236 2.455 + vertex 1.4271 2.13853 2.45642 + endloop + endfacet + facet normal 0.0508555 0.88377 0.465151 + outer loop + vertex 1.43127 2.13701 2.45885 + vertex 1.4271 2.13853 2.45642 + vertex 1.42693 2.13674 2.45984 + endloop + endfacet + facet normal -0.0310994 0.822793 0.56749 + outer loop + vertex 1.43367 2.13921 2.45579 + vertex 1.4271 2.13853 2.45642 + vertex 1.43127 2.13701 2.45885 + endloop + endfacet + facet normal 0.0792514 -0.904769 0.418464 + outer loop + vertex 1.44 0.892362 2.455 + vertex 1.4371 0.892579 2.45602 + vertex 1.435 0.891924 2.455 + endloop + endfacet + facet normal 0.148972 -0.942514 0.299122 + outer loop + vertex 1.4371 0.892579 2.45602 + vertex 1.43161 0.892144 2.45738 + vertex 1.435 0.891924 2.455 + endloop + endfacet + facet normal 0.163648 -0.915851 0.366656 + outer loop + vertex 1.4371 0.892579 2.45602 + vertex 1.43498 0.893588 2.45948 + vertex 1.43161 0.892144 2.45738 + endloop + endfacet + facet normal 0.144355 -0.922917 0.356911 + outer loop + vertex 1.43986 0.893862 2.45822 + vertex 1.43498 0.893588 2.45948 + vertex 1.4371 0.892579 2.45602 + endloop + endfacet + facet normal 0.155313 -0.901547 0.403846 + outer loop + vertex 1.43498 0.893588 2.45948 + vertex 1.43986 0.893862 2.45822 + vertex 1.43811 0.89528 2.46206 + endloop + endfacet + facet normal 0.150865 -0.900252 0.408395 + outer loop + vertex 1.43257 0.89509 2.46368 + vertex 1.43498 0.893588 2.45948 + vertex 1.43811 0.89528 2.46206 + endloop + endfacet + facet normal 0.171136 -0.859111 0.482329 + outer loop + vertex 1.43811 0.89528 2.46206 + vertex 1.43625 0.897028 2.46583 + vertex 1.43257 0.89509 2.46368 + endloop + endfacet + facet normal 0.15636 -0.851409 0.500654 + outer loop + vertex 1.43625 0.897028 2.46583 + vertex 1.43195 0.896968 2.46707 + vertex 1.43257 0.89509 2.46368 + endloop + endfacet + facet normal 0.182464 -0.783163 0.594444 + outer loop + vertex 1.43625 0.897028 2.46583 + vertex 1.43405 0.898859 2.46892 + vertex 1.43195 0.896968 2.46707 + endloop + endfacet + facet normal 0.151781 -0.798932 0.581954 + outer loop + vertex 1.43891 0.899159 2.46806 + vertex 1.43405 0.898859 2.46892 + vertex 1.43625 0.897028 2.46583 + endloop + endfacet + facet normal 0.16483 -0.706286 0.68847 + outer loop + vertex 1.43405 0.898859 2.46892 + vertex 1.43891 0.899159 2.46806 + vertex 1.43653 0.901458 2.47099 + endloop + endfacet + facet normal 0.148584 -0.699322 0.699194 + outer loop + vertex 1.43145 0.90086 2.47147 + vertex 1.43405 0.898859 2.46892 + vertex 1.43653 0.901458 2.47099 + endloop + endfacet + facet normal 0.145328 -0.603129 0.784292 + outer loop + vertex 1.43653 0.901458 2.47099 + vertex 1.43391 0.904408 2.47375 + vertex 1.43145 0.90086 2.47147 + endloop + endfacet + facet normal 0.122279 -0.617094 0.777331 + outer loop + vertex 1.43942 0.904482 2.47294 + vertex 1.43391 0.904408 2.47375 + vertex 1.43653 0.901458 2.47099 + endloop + endfacet + facet normal 0.11317 -0.519434 0.846983 + outer loop + vertex 1.43457 0.907666 2.47566 + vertex 1.43075 0.90682 2.47565 + vertex 1.43391 0.904408 2.47375 + endloop + endfacet + facet normal 0.110075 -0.519152 0.847564 + outer loop + vertex 1.43457 0.907666 2.47566 + vertex 1.43391 0.904408 2.47375 + vertex 1.43791 0.907386 2.47505 + endloop + endfacet + facet normal 0.12934 -0.538453 0.83267 + outer loop + vertex 1.43791 0.907386 2.47505 + vertex 1.43391 0.904408 2.47375 + vertex 1.43942 0.904482 2.47294 + endloop + endfacet + facet normal 0.0928406 -0.428308 0.898851 + outer loop + vertex 1.43457 0.907666 2.47566 + vertex 1.4338 0.910227 2.47696 + vertex 1.43075 0.90682 2.47565 + endloop + endfacet + facet normal 0.122345 -0.451513 0.883837 + outer loop + vertex 1.43791 0.907386 2.47505 + vertex 1.43702 0.909855 2.47643 + vertex 1.43457 0.907666 2.47566 + endloop + endfacet + facet normal 0.0960202 -0.427405 0.898947 + outer loop + vertex 1.43702 0.909855 2.47643 + vertex 1.4338 0.910227 2.47696 + vertex 1.43457 0.907666 2.47566 + endloop + endfacet + facet normal 0.104243 -0.382832 0.917918 + outer loop + vertex 1.43702 0.909855 2.47643 + vertex 1.43837 0.913604 2.47784 + vertex 1.4338 0.910227 2.47696 + endloop + endfacet + facet normal 0.100779 -0.378698 0.920017 + outer loop + vertex 1.43837 0.913604 2.47784 + vertex 1.43316 0.913696 2.47845 + vertex 1.4338 0.910227 2.47696 + endloop + endfacet + facet normal -0.0698506 0.970136 0.232285 + outer loop + vertex 1.44 1.00288 2.49 + vertex 1.435 1.00252 2.49 + vertex 1.43843 1.00218 2.49245 + endloop + endfacet + facet normal -0.0876176 0.962662 0.256136 + outer loop + vertex 1.43843 1.00218 2.49245 + vertex 1.435 1.00252 2.49 + vertex 1.43355 1.0017 2.49257 + endloop + endfacet + facet normal -0.0919695 0.98258 0.161485 + outer loop + vertex 1.43843 1.00218 2.49245 + vertex 1.43355 1.0017 2.49257 + vertex 1.43765 1.00141 2.49671 + endloop + endfacet + facet normal -0.0469157 0.99197 0.117452 + outer loop + vertex 1.43765 1.00141 2.49671 + vertex 1.43355 1.0017 2.49257 + vertex 1.43255 1.00117 2.49668 + endloop + endfacet + facet normal -0.0456791 0.944523 0.325254 + outer loop + vertex 1.43765 1.00141 2.49671 + vertex 1.43255 1.00117 2.49668 + vertex 1.43633 0.999822 2.50113 + endloop + endfacet + facet normal 0.0878185 0.971552 0.219944 + outer loop + vertex 1.43633 0.999822 2.50113 + vertex 1.43255 1.00117 2.49668 + vertex 1.4314 1.00052 2.5 + endloop + endfacet + facet normal 0.30907 0.731228 0.608097 + outer loop + vertex 1.4359 0.996939 2.50437 + vertex 1.4324 0.999086 2.50357 + vertex 1.43309 0.997111 2.50559 + endloop + endfacet + facet normal 0.278287 0.699762 0.657944 + outer loop + vertex 1.4359 0.996939 2.50437 + vertex 1.43633 0.999822 2.50113 + vertex 1.4324 0.999086 2.50357 + endloop + endfacet + facet normal 0.0499698 0.931329 0.360734 + outer loop + vertex 1.43633 0.999822 2.50113 + vertex 1.4314 1.00052 2.5 + vertex 1.4324 0.999086 2.50357 + endloop + endfacet + facet normal 0.442702 0.712601 0.544257 + outer loop + vertex 1.43309 0.997111 2.50559 + vertex 1.4324 0.999086 2.50357 + vertex 1.43139 0.998095 2.50569 + endloop + endfacet + facet normal 0.00127077 -0.634537 -0.772891 + outer loop + vertex 1.44 2.02755 2.49 + vertex 1.43842 2.02493 2.49215 + vertex 1.435 2.02754 2.49 + endloop + endfacet + facet normal -0.0926265 -0.702257 -0.705873 + outer loop + vertex 1.43842 2.02493 2.49215 + vertex 1.43371 2.02522 2.49247 + vertex 1.435 2.02754 2.49 + endloop + endfacet + facet normal -0.0714793 -0.988422 -0.133837 + outer loop + vertex 1.43842 2.02493 2.49215 + vertex 1.43776 2.02439 2.49645 + vertex 1.43371 2.02522 2.49247 + endloop + endfacet + facet normal -0.0752557 -0.98865 -0.130033 + outer loop + vertex 1.43776 2.02439 2.49645 + vertex 1.43309 2.02471 2.49676 + vertex 1.43371 2.02522 2.49247 + endloop + endfacet + facet normal -0.0604739 -0.993396 0.0975079 + outer loop + vertex 1.43776 2.02439 2.49645 + vertex 1.43694 2.02489 2.50098 + vertex 1.43309 2.02471 2.49676 + endloop + endfacet + facet normal -0.0472213 -0.995219 0.0854935 + outer loop + vertex 1.43694 2.02489 2.50098 + vertex 1.43215 2.02512 2.50109 + vertex 1.43309 2.02471 2.49676 + endloop + endfacet + facet normal -0.0401381 -0.954823 0.294451 + outer loop + vertex 1.43694 2.02489 2.50098 + vertex 1.43548 2.02605 2.50453 + vertex 1.43215 2.02512 2.50109 + endloop + endfacet + facet normal -0.0500272 -0.95162 0.303176 + outer loop + vertex 1.43548 2.02605 2.50453 + vertex 1.43075 2.02632 2.50462 + vertex 1.43215 2.02512 2.50109 + endloop + endfacet + facet normal -0.0314237 -0.742318 0.669311 + outer loop + vertex 1.43548 2.02605 2.50453 + vertex 1.43369 2.02802 2.50664 + vertex 1.43075 2.02632 2.50462 + endloop + endfacet + facet normal -0.0618358 -0.753773 0.654219 + outer loop + vertex 1.43793 2.0274 2.50633 + vertex 1.43369 2.02802 2.50664 + vertex 1.43548 2.02605 2.50453 + endloop + endfacet + facet normal 0.096084 0.327067 0.940104 + outer loop + vertex 1.43811 2.09784 2.4847 + vertex 1.43706 2.10172 2.48346 + vertex 1.43289 2.09899 2.48483 + endloop + endfacet + facet normal 0.12323 0.539489 0.832926 + outer loop + vertex 1.43396 2.12363 2.47557 + vertex 1.43816 2.12276 2.47552 + vertex 1.43727 2.12609 2.47349 + endloop + endfacet + facet normal 0.127351 0.535573 0.834831 + outer loop + vertex 1.43117 2.12753 2.4735 + vertex 1.43396 2.12363 2.47557 + vertex 1.43727 2.12609 2.47349 + endloop + endfacet + facet normal 0.117468 0.421161 0.899347 + outer loop + vertex 1.43626 2.1196 2.47716 + vertex 1.43396 2.12363 2.47557 + vertex 1.43113 2.12076 2.47729 + endloop + endfacet + facet normal 0.0977993 0.412445 0.905718 + outer loop + vertex 1.43816 2.12276 2.47552 + vertex 1.43396 2.12363 2.47557 + vertex 1.43626 2.1196 2.47716 + endloop + endfacet + facet normal 0.157015 0.798798 0.580748 + outer loop + vertex 1.43423 2.12921 2.47127 + vertex 1.43899 2.12871 2.47068 + vertex 1.43586 2.13092 2.46848 + endloop + endfacet + facet normal 0.197307 0.780574 0.593105 + outer loop + vertex 1.43204 2.13125 2.46931 + vertex 1.43423 2.12921 2.47127 + vertex 1.43586 2.13092 2.46848 + endloop + endfacet + facet normal 0.158861 0.669975 0.725187 + outer loop + vertex 1.43727 2.12609 2.47349 + vertex 1.43423 2.12921 2.47127 + vertex 1.43117 2.12753 2.4735 + endloop + endfacet + facet normal 0.161491 0.671272 0.723405 + outer loop + vertex 1.43899 2.12871 2.47068 + vertex 1.43423 2.12921 2.47127 + vertex 1.43727 2.12609 2.47349 + endloop + endfacet + facet normal -0.400102 0.459604 0.792895 + outer loop + vertex 1.43698 2.14 2.46 + vertex 1.43127 2.13701 2.45885 + vertex 1.43492 2.13544 2.4616 + endloop + endfacet + facet normal 0.114332 0.283026 0.952273 + outer loop + vertex 1.43698 2.14 2.46 + vertex 1.43492 2.13544 2.4616 + vertex 1.44 2.13878 2.46 + endloop + endfacet + facet normal 0.0594128 0.356915 0.932246 + outer loop + vertex 1.44 2.13878 2.46 + vertex 1.43492 2.13544 2.4616 + vertex 1.43912 2.13426 2.46178 + endloop + endfacet + facet normal 0.20461 0.817078 0.538997 + outer loop + vertex 1.43912 2.13426 2.46178 + vertex 1.43492 2.13544 2.4616 + vertex 1.43746 2.13261 2.46492 + endloop + endfacet + facet normal 0.197654 0.815918 0.543333 + outer loop + vertex 1.43746 2.13261 2.46492 + vertex 1.43492 2.13544 2.4616 + vertex 1.43219 2.1331 2.4661 + endloop + endfacet + facet normal 0.182366 0.84825 0.497206 + outer loop + vertex 1.43586 2.13092 2.46848 + vertex 1.43219 2.1331 2.4661 + vertex 1.43204 2.13125 2.46931 + endloop + endfacet + facet normal 0.188965 0.851168 0.489699 + outer loop + vertex 1.43746 2.13261 2.46492 + vertex 1.43219 2.1331 2.4661 + vertex 1.43586 2.13092 2.46848 + endloop + endfacet + facet normal -0.0765851 0.989195 -0.125013 + outer loop + vertex 1.44 2.14 2.45815 + vertex 1.43367 2.13921 2.45579 + vertex 1.43698 2.14 2.46 + endloop + endfacet + facet normal -0.262661 0.872244 0.412553 + outer loop + vertex 1.44 2.14 2.45815 + vertex 1.44 2.14149 2.455 + vertex 1.43367 2.13921 2.45579 + endloop + endfacet + facet normal 0.0312199 0.247822 0.968303 + outer loop + vertex 1.44 2.14149 2.455 + vertex 1.435 2.14212 2.455 + vertex 1.43367 2.13921 2.45579 + endloop + endfacet + facet normal -0.4872 0.843856 0.22482 + outer loop + vertex 1.43698 2.14 2.46 + vertex 1.43367 2.13921 2.45579 + vertex 1.43127 2.13701 2.45885 + endloop + endfacet + facet normal 0.117532 -0.825388 0.552197 + outer loop + vertex 1.445 0.893074 2.455 + vertex 1.44267 0.893175 2.45565 + vertex 1.44 0.892362 2.455 + endloop + endfacet + facet normal 0.125074 -0.835976 0.534322 + outer loop + vertex 1.44267 0.893175 2.45565 + vertex 1.4371 0.892579 2.45602 + vertex 1.44 0.892362 2.455 + endloop + endfacet + facet normal 0.123381 -0.916835 0.379726 + outer loop + vertex 1.44267 0.893175 2.45565 + vertex 1.43986 0.893862 2.45822 + vertex 1.4371 0.892579 2.45602 + endloop + endfacet + facet normal 0.105474 -0.925953 0.362611 + outer loop + vertex 1.44395 0.89426 2.45805 + vertex 1.43986 0.893862 2.45822 + vertex 1.44267 0.893175 2.45565 + endloop + endfacet + facet normal 0.105508 -0.902415 0.41775 + outer loop + vertex 1.43986 0.893862 2.45822 + vertex 1.44395 0.89426 2.45805 + vertex 1.4431 0.895295 2.46049 + endloop + endfacet + facet normal 0.125963 -0.910548 0.393745 + outer loop + vertex 1.43811 0.89528 2.46206 + vertex 1.43986 0.893862 2.45822 + vertex 1.4431 0.895295 2.46049 + endloop + endfacet + facet normal 0.150815 -0.867788 0.473496 + outer loop + vertex 1.4431 0.895295 2.46049 + vertex 1.44162 0.897229 2.46451 + vertex 1.43811 0.89528 2.46206 + endloop + endfacet + facet normal 0.149219 -0.867109 0.475243 + outer loop + vertex 1.44162 0.897229 2.46451 + vertex 1.43625 0.897028 2.46583 + vertex 1.43811 0.89528 2.46206 + endloop + endfacet + facet normal 0.169561 -0.805849 0.567324 + outer loop + vertex 1.44162 0.897229 2.46451 + vertex 1.43891 0.899159 2.46806 + vertex 1.43625 0.897028 2.46583 + endloop + endfacet + facet normal 0.132217 -0.82509 0.549313 + outer loop + vertex 1.44294 0.899234 2.46721 + vertex 1.43891 0.899159 2.46806 + vertex 1.44162 0.897229 2.46451 + endloop + endfacet + facet normal 0.154778 -0.732168 0.663305 + outer loop + vertex 1.43891 0.899159 2.46806 + vertex 1.44294 0.899234 2.46721 + vertex 1.4422 0.901619 2.47001 + endloop + endfacet + facet normal 0.137833 -0.721547 0.678507 + outer loop + vertex 1.43653 0.901458 2.47099 + vertex 1.43891 0.899159 2.46806 + vertex 1.4422 0.901619 2.47001 + endloop + endfacet + facet normal 0.149451 -0.632091 0.760345 + outer loop + vertex 1.4422 0.901619 2.47001 + vertex 1.43942 0.904482 2.47294 + vertex 1.43653 0.901458 2.47099 + endloop + endfacet + facet normal 0.132591 -0.642628 0.754618 + outer loop + vertex 1.44444 0.904895 2.47241 + vertex 1.43942 0.904482 2.47294 + vertex 1.4422 0.901619 2.47001 + endloop + endfacet + facet normal 0.132302 -0.543871 0.828674 + outer loop + vertex 1.44444 0.904895 2.47241 + vertex 1.44243 0.907724 2.47459 + vertex 1.43942 0.904482 2.47294 + endloop + endfacet + facet normal 0.126041 -0.539871 0.832258 + outer loop + vertex 1.43942 0.904482 2.47294 + vertex 1.44243 0.907724 2.47459 + vertex 1.43791 0.907386 2.47505 + endloop + endfacet + facet normal 0.124692 -0.451278 0.883629 + outer loop + vertex 1.43791 0.907386 2.47505 + vertex 1.44243 0.907724 2.47459 + vertex 1.44082 0.91068 2.47632 + endloop + endfacet + facet normal 0.124148 -0.4509 0.883898 + outer loop + vertex 1.43702 0.909855 2.47643 + vertex 1.43791 0.907386 2.47505 + vertex 1.44082 0.91068 2.47632 + endloop + endfacet + facet normal 0.110727 -0.384606 0.916416 + outer loop + vertex 1.44082 0.91068 2.47632 + vertex 1.43837 0.913604 2.47784 + vertex 1.43702 0.909855 2.47643 + endloop + endfacet + facet normal 0.108547 -0.386214 0.916 + outer loop + vertex 1.44413 0.91465 2.4776 + vertex 1.43837 0.913604 2.47784 + vertex 1.44082 0.91068 2.47632 + endloop + endfacet + facet normal -0.136998 0.964758 0.224662 + outer loop + vertex 1.445 1.00359 2.49 + vertex 1.44 1.00288 2.49 + vertex 1.44365 1.00287 2.49226 + endloop + endfacet + facet normal -0.121508 0.97229 0.199721 + outer loop + vertex 1.44365 1.00287 2.49226 + vertex 1.44 1.00288 2.49 + vertex 1.43843 1.00218 2.49245 + endloop + endfacet + facet normal -0.121367 0.971831 0.202026 + outer loop + vertex 1.44365 1.00287 2.49226 + vertex 1.43843 1.00218 2.49245 + vertex 1.44287 1.00188 2.49657 + endloop + endfacet + facet normal -0.084361 0.98302 0.162955 + outer loop + vertex 1.44287 1.00188 2.49657 + vertex 1.43843 1.00218 2.49245 + vertex 1.43765 1.00141 2.49671 + endloop + endfacet + facet normal -0.071024 0.908436 0.411945 + outer loop + vertex 1.44287 1.00188 2.49657 + vertex 1.43765 1.00141 2.49671 + vertex 1.44209 1.00002 2.50052 + endloop + endfacet + facet normal 0.0024251 0.941002 0.338392 + outer loop + vertex 1.44209 1.00002 2.50052 + vertex 1.43765 1.00141 2.49671 + vertex 1.43633 0.999822 2.50113 + endloop + endfacet + facet normal 0.144008 0.730545 0.667507 + outer loop + vertex 1.44054 0.997041 2.50326 + vertex 1.43633 0.999822 2.50113 + vertex 1.4359 0.996939 2.50437 + endloop + endfacet + facet normal 0.0552883 0.659324 0.749824 + outer loop + vertex 1.44209 1.00002 2.50052 + vertex 1.43633 0.999822 2.50113 + vertex 1.44054 0.997041 2.50326 + endloop + endfacet + facet normal 0.00276216 -0.459736 -0.888052 + outer loop + vertex 1.445 2.02758 2.49 + vertex 1.44325 2.02454 2.49157 + vertex 1.44 2.02755 2.49 + endloop + endfacet + facet normal -0.143212 -0.574493 -0.805883 + outer loop + vertex 1.44325 2.02454 2.49157 + vertex 1.43842 2.02493 2.49215 + vertex 1.44 2.02755 2.49 + endloop + endfacet + facet normal -0.0995681 -0.980506 -0.169394 + outer loop + vertex 1.44325 2.02454 2.49157 + vertex 1.44258 2.02387 2.4958 + vertex 1.43842 2.02493 2.49215 + endloop + endfacet + facet normal -0.124682 -0.982098 -0.1412 + outer loop + vertex 1.44258 2.02387 2.4958 + vertex 1.43776 2.02439 2.49645 + vertex 1.43842 2.02493 2.49215 + endloop + endfacet + facet normal -0.0944373 -0.991339 0.0912643 + outer loop + vertex 1.44258 2.02387 2.4958 + vertex 1.44191 2.02437 2.50054 + vertex 1.43776 2.02439 2.49645 + endloop + endfacet + facet normal -0.0943478 -0.991356 0.0911735 + outer loop + vertex 1.44191 2.02437 2.50054 + vertex 1.43694 2.02489 2.50098 + vertex 1.43776 2.02439 2.49645 + endloop + endfacet + facet normal -0.0708911 -0.948673 0.308211 + outer loop + vertex 1.44191 2.02437 2.50054 + vertex 1.44031 2.02573 2.50434 + vertex 1.43694 2.02489 2.50098 + endloop + endfacet + facet normal -0.0511597 -0.955602 0.290184 + outer loop + vertex 1.44031 2.02573 2.50434 + vertex 1.43548 2.02605 2.50453 + vertex 1.43694 2.02489 2.50098 + endloop + endfacet + facet normal -0.0257864 -0.780173 0.625032 + outer loop + vertex 1.44031 2.02573 2.50434 + vertex 1.43793 2.0274 2.50633 + vertex 1.43548 2.02605 2.50453 + endloop + endfacet + facet normal 0.0594792 -0.72797 0.683024 + outer loop + vertex 1.44233 2.02772 2.50629 + vertex 1.43793 2.0274 2.50633 + vertex 1.44031 2.02573 2.50434 + endloop + endfacet + facet normal 0.0974116 0.327352 0.939868 + outer loop + vertex 1.43811 2.09784 2.4847 + vertex 1.4411 2.10054 2.48345 + vertex 1.43706 2.10172 2.48346 + endloop + endfacet + facet normal 0.128014 0.451775 0.8829 + outer loop + vertex 1.43816 2.12276 2.47552 + vertex 1.4405 2.12054 2.47631 + vertex 1.4423 2.12355 2.47451 + endloop + endfacet + facet normal 0.100873 0.536481 0.837862 + outer loop + vertex 1.43816 2.12276 2.47552 + vertex 1.4423 2.12355 2.47451 + vertex 1.43727 2.12609 2.47349 + endloop + endfacet + facet normal 0.135492 0.588639 0.79696 + outer loop + vertex 1.43727 2.12609 2.47349 + vertex 1.4423 2.12355 2.47451 + vertex 1.44177 2.12661 2.47234 + endloop + endfacet + facet normal 0.088257 0.417487 0.904387 + outer loop + vertex 1.4405 2.12054 2.47631 + vertex 1.43816 2.12276 2.47552 + vertex 1.43626 2.1196 2.47716 + endloop + endfacet + facet normal 0.126272 0.820059 0.558174 + outer loop + vertex 1.43899 2.12871 2.47068 + vertex 1.44427 2.12848 2.46981 + vertex 1.44064 2.13054 2.46761 + endloop + endfacet + facet normal 0.167616 0.803861 0.570712 + outer loop + vertex 1.43586 2.13092 2.46848 + vertex 1.43899 2.12871 2.47068 + vertex 1.44064 2.13054 2.46761 + endloop + endfacet + facet normal 0.100913 0.696873 0.71006 + outer loop + vertex 1.44177 2.12661 2.47234 + vertex 1.43899 2.12871 2.47068 + vertex 1.43727 2.12609 2.47349 + endloop + endfacet + facet normal 0.141469 0.723416 0.675763 + outer loop + vertex 1.44427 2.12848 2.46981 + vertex 1.43899 2.12871 2.47068 + vertex 1.44177 2.12661 2.47234 + endloop + endfacet + facet normal 0.387929 0.76946 0.507388 + outer loop + vertex 1.44412 2.14 2.455 + vertex 1.44 2.14 2.45815 + vertex 1.44 2.13878 2.46 + endloop + endfacet + facet normal 0.373442 0.782279 0.498579 + outer loop + vertex 1.44412 2.14 2.455 + vertex 1.44 2.13878 2.46 + vertex 1.445 2.13958 2.455 + endloop + endfacet + facet normal 0.642076 0.325463 0.694127 + outer loop + vertex 1.445 2.13958 2.455 + vertex 1.44 2.13878 2.46 + vertex 1.44407 2.1353 2.45787 + endloop + endfacet + facet normal 0.663723 0.382238 0.642935 + outer loop + vertex 1.44407 2.1353 2.45787 + vertex 1.44 2.13878 2.46 + vertex 1.44219 2.13422 2.46045 + endloop + endfacet + facet normal 0.386821 0.272738 0.880899 + outer loop + vertex 1.44219 2.13422 2.46045 + vertex 1.44 2.13878 2.46 + vertex 1.43912 2.13426 2.46178 + endloop + endfacet + facet normal 0.22364 0.844012 0.487472 + outer loop + vertex 1.44219 2.13422 2.46045 + vertex 1.43912 2.13426 2.46178 + vertex 1.44251 2.13215 2.4639 + endloop + endfacet + facet normal 0.184086 0.825962 0.532822 + outer loop + vertex 1.44251 2.13215 2.4639 + vertex 1.43912 2.13426 2.46178 + vertex 1.43746 2.13261 2.46492 + endloop + endfacet + facet normal 0.15575 0.863103 0.480411 + outer loop + vertex 1.44064 2.13054 2.46761 + vertex 1.43746 2.13261 2.46492 + vertex 1.43586 2.13092 2.46848 + endloop + endfacet + facet normal 0.173919 0.868949 0.463335 + outer loop + vertex 1.44251 2.13215 2.4639 + vertex 1.43746 2.13261 2.46492 + vertex 1.44064 2.13054 2.46761 + endloop + endfacet + facet normal 0.310719 0.859239 0.406402 + outer loop + vertex 1.44412 2.14 2.455 + vertex 1.44 2.14149 2.455 + vertex 1.44 2.14 2.45815 + endloop + endfacet + facet normal 0.0540397 -0.936365 0.346845 + outer loop + vertex 1.4457 0.895 2.46 + vertex 1.45 0.893396 2.455 + vertex 1.45 0.895 2.45933 + endloop + endfacet + facet normal 0.0591398 -0.934629 0.350674 + outer loop + vertex 1.4457 0.895 2.46 + vertex 1.44267 0.893175 2.45565 + vertex 1.45 0.893396 2.455 + endloop + endfacet + facet normal 0.0599385 -0.930594 0.361113 + outer loop + vertex 1.44267 0.893175 2.45565 + vertex 1.445 0.893074 2.455 + vertex 1.45 0.893396 2.455 + endloop + endfacet + facet normal -0.173405 -0.859468 0.480879 + outer loop + vertex 1.4457 0.895 2.46 + vertex 1.44395 0.89426 2.45805 + vertex 1.44267 0.893175 2.45565 + endloop + endfacet + facet normal -0.110537 0.958227 -0.263786 + outer loop + vertex 1.44395 0.89426 2.45805 + vertex 1.4457 0.895 2.46 + vertex 1.45 0.895496 2.46 + endloop + endfacet + facet normal 0.0556672 -0.912664 0.404901 + outer loop + vertex 1.44395 0.89426 2.45805 + vertex 1.45 0.895496 2.46 + vertex 1.4431 0.895295 2.46049 + endloop + endfacet + facet normal 0.064939 -0.817054 0.572893 + outer loop + vertex 1.4431 0.895295 2.46049 + vertex 1.45 0.895496 2.46 + vertex 1.44661 0.896788 2.46223 + endloop + endfacet + facet normal 0.181141 -0.843241 0.506096 + outer loop + vertex 1.44539 0.898317 2.46521 + vertex 1.44661 0.896788 2.46223 + vertex 1.44921 0.89854 2.46422 + endloop + endfacet + facet normal 0.153379 -0.852602 0.499544 + outer loop + vertex 1.44539 0.898317 2.46521 + vertex 1.44162 0.897229 2.46451 + vertex 1.44661 0.896788 2.46223 + endloop + endfacet + facet normal 0.138502 -0.871371 0.47067 + outer loop + vertex 1.44162 0.897229 2.46451 + vertex 1.4431 0.895295 2.46049 + vertex 1.44661 0.896788 2.46223 + endloop + endfacet + facet normal 0.136725 -0.825583 0.547466 + outer loop + vertex 1.44539 0.898317 2.46521 + vertex 1.44294 0.899234 2.46721 + vertex 1.44162 0.897229 2.46451 + endloop + endfacet + facet normal 0.195075 -0.798423 0.56962 + outer loop + vertex 1.44921 0.89854 2.46422 + vertex 1.44649 0.900136 2.46739 + vertex 1.44539 0.898317 2.46521 + endloop + endfacet + facet normal 0.173285 -0.796629 0.579098 + outer loop + vertex 1.44294 0.899234 2.46721 + vertex 1.44539 0.898317 2.46521 + vertex 1.44649 0.900136 2.46739 + endloop + endfacet + facet normal 0.152739 -0.732685 0.663207 + outer loop + vertex 1.44294 0.899234 2.46721 + vertex 1.44649 0.900136 2.46739 + vertex 1.4422 0.901619 2.47001 + endloop + endfacet + facet normal 0.1543 -0.73094 0.66477 + outer loop + vertex 1.4422 0.901619 2.47001 + vertex 1.44649 0.900136 2.46739 + vertex 1.44734 0.902614 2.46991 + endloop + endfacet + facet normal 0.139345 -0.644923 0.751437 + outer loop + vertex 1.44734 0.902614 2.46991 + vertex 1.44444 0.904895 2.47241 + vertex 1.4422 0.901619 2.47001 + endloop + endfacet + facet normal 0.135793 -0.647616 0.749769 + outer loop + vertex 1.44906 0.905385 2.47199 + vertex 1.44444 0.904895 2.47241 + vertex 1.44734 0.902614 2.46991 + endloop + endfacet + facet normal 0.131983 -0.546923 0.826714 + outer loop + vertex 1.44906 0.905385 2.47199 + vertex 1.44732 0.908194 2.47413 + vertex 1.44444 0.904895 2.47241 + endloop + endfacet + facet normal 0.129461 -0.545441 0.828091 + outer loop + vertex 1.44444 0.904895 2.47241 + vertex 1.44732 0.908194 2.47413 + vertex 1.44243 0.907724 2.47459 + endloop + endfacet + facet normal 0.125919 -0.458429 0.879765 + outer loop + vertex 1.44243 0.907724 2.47459 + vertex 1.44732 0.908194 2.47413 + vertex 1.44559 0.911269 2.47598 + endloop + endfacet + facet normal 0.119334 -0.453859 0.883047 + outer loop + vertex 1.44082 0.91068 2.47632 + vertex 1.44243 0.907724 2.47459 + vertex 1.44559 0.911269 2.47598 + endloop + endfacet + facet normal 0.113621 -0.389765 0.913878 + outer loop + vertex 1.44559 0.911269 2.47598 + vertex 1.44413 0.91465 2.4776 + vertex 1.44082 0.91068 2.47632 + endloop + endfacet + facet normal 0.108946 -0.391658 0.913638 + outer loop + vertex 1.44917 0.915088 2.47719 + vertex 1.44413 0.91465 2.4776 + vertex 1.44559 0.911269 2.47598 + endloop + endfacet + facet normal -0.216526 0.727892 0.650608 + outer loop + vertex 1.44705 1.00367 2.49059 + vertex 1.44974 1.005 2.49 + vertex 1.445 1.00359 2.49 + endloop + endfacet + facet normal -0.108675 0.96432 0.241407 + outer loop + vertex 1.44365 1.00287 2.49226 + vertex 1.44705 1.00367 2.49059 + vertex 1.445 1.00359 2.49 + endloop + endfacet + facet normal -0.188594 0.978272 0.0861168 + outer loop + vertex 1.44745 1.00351 2.4933 + vertex 1.44705 1.00367 2.49059 + vertex 1.44365 1.00287 2.49226 + endloop + endfacet + facet normal -0.220535 0.949983 0.221128 + outer loop + vertex 1.44745 1.00351 2.4933 + vertex 1.44365 1.00287 2.49226 + vertex 1.44782 1.0028 2.49673 + endloop + endfacet + facet normal -0.185495 0.964362 0.18867 + outer loop + vertex 1.44782 1.0028 2.49673 + vertex 1.44365 1.00287 2.49226 + vertex 1.44287 1.00188 2.49657 + endloop + endfacet + facet normal -0.17585 0.859853 0.479301 + outer loop + vertex 1.44782 1.0028 2.49673 + vertex 1.44287 1.00188 2.49657 + vertex 1.44733 1.00068 2.50035 + endloop + endfacet + facet normal -0.100648 0.908304 0.406023 + outer loop + vertex 1.44733 1.00068 2.50035 + vertex 1.44287 1.00188 2.49657 + vertex 1.44209 1.00002 2.50052 + endloop + endfacet + facet normal 0.0274609 0.668047 0.743612 + outer loop + vertex 1.44584 0.997412 2.50273 + vertex 1.44209 1.00002 2.50052 + vertex 1.44054 0.997041 2.50326 + endloop + endfacet + facet normal -0.0496612 0.602278 0.79674 + outer loop + vertex 1.44733 1.00068 2.50035 + vertex 1.44209 1.00002 2.50052 + vertex 1.44584 0.997412 2.50273 + endloop + endfacet + facet normal 0.350133 0.216804 0.911264 + outer loop + vertex 1.45 1.005 2.4899 + vertex 1.44974 1.005 2.49 + vertex 1.45029 1.00432 2.48995 + endloop + endfacet + facet normal -0.18366 0.981539 0.0533886 + outer loop + vertex 1.45029 1.00432 2.48995 + vertex 1.44705 1.00367 2.49059 + vertex 1.45004 1.00412 2.49271 + endloop + endfacet + facet normal 0.1782 0.0732253 0.981266 + outer loop + vertex 1.44974 1.005 2.49 + vertex 1.44705 1.00367 2.49059 + vertex 1.45029 1.00432 2.48995 + endloop + endfacet + facet normal -0.207616 0.974182 0.0886848 + outer loop + vertex 1.45004 1.00412 2.49271 + vertex 1.44705 1.00367 2.49059 + vertex 1.44745 1.00351 2.4933 + endloop + endfacet + facet normal -0.0222738 -0.236993 -0.971256 + outer loop + vertex 1.45 2.02711 2.49 + vertex 1.44816 2.02425 2.49074 + vertex 1.445 2.02758 2.49 + endloop + endfacet + facet normal -0.176007 -0.369621 -0.91236 + outer loop + vertex 1.44816 2.02425 2.49074 + vertex 1.44325 2.02454 2.49157 + vertex 1.445 2.02758 2.49 + endloop + endfacet + facet normal -0.105994 -0.949756 -0.294499 + outer loop + vertex 1.44816 2.02425 2.49074 + vertex 1.44718 2.02314 2.49468 + vertex 1.44325 2.02454 2.49157 + endloop + endfacet + facet normal -0.199377 -0.962794 -0.182416 + outer loop + vertex 1.44718 2.02314 2.49468 + vertex 1.44258 2.02387 2.4958 + vertex 1.44325 2.02454 2.49157 + endloop + endfacet + facet normal -0.15232 -0.987982 0.0262658 + outer loop + vertex 1.44718 2.02314 2.49468 + vertex 1.44666 2.02334 2.49957 + vertex 1.44258 2.02387 2.4958 + endloop + endfacet + facet normal -0.19624 -0.977661 0.0752898 + outer loop + vertex 1.44666 2.02334 2.49957 + vertex 1.44191 2.02437 2.50054 + vertex 1.44258 2.02387 2.4958 + endloop + endfacet + facet normal -0.155577 -0.9555 0.25063 + outer loop + vertex 1.44666 2.02334 2.49957 + vertex 1.4459 2.02463 2.504 + vertex 1.44191 2.02437 2.50054 + endloop + endfacet + facet normal -0.169804 -0.948743 0.26656 + outer loop + vertex 1.4459 2.02463 2.504 + vertex 1.44031 2.02573 2.50434 + vertex 1.44191 2.02437 2.50054 + endloop + endfacet + facet normal -0.0825587 -0.652839 0.752984 + outer loop + vertex 1.4459 2.02463 2.504 + vertex 1.44233 2.02772 2.50629 + vertex 1.44031 2.02573 2.50434 + endloop + endfacet + facet normal -0.182642 -0.712543 0.67744 + outer loop + vertex 1.44845 2.02605 2.50618 + vertex 1.44233 2.02772 2.50629 + vertex 1.4459 2.02463 2.504 + endloop + endfacet + facet normal 0.119188 0.577231 0.807836 + outer loop + vertex 1.44754 2.12254 2.47446 + vertex 1.44599 2.12567 2.47245 + vertex 1.4423 2.12355 2.47451 + endloop + endfacet + facet normal 0.109791 0.587559 0.801698 + outer loop + vertex 1.4423 2.12355 2.47451 + vertex 1.44599 2.12567 2.47245 + vertex 1.44177 2.12661 2.47234 + endloop + endfacet + facet normal 0.145801 0.88543 0.441311 + outer loop + vertex 1.44901 2.12946 2.46724 + vertex 1.44681 2.13115 2.46458 + vertex 1.44471 2.13038 2.46681 + endloop + endfacet + facet normal 0.138717 0.827271 0.544408 + outer loop + vertex 1.44471 2.13038 2.46681 + vertex 1.44064 2.13054 2.46761 + vertex 1.44427 2.12848 2.46981 + endloop + endfacet + facet normal 0.123688 0.829974 0.543916 + outer loop + vertex 1.44471 2.13038 2.46681 + vertex 1.44427 2.12848 2.46981 + vertex 1.44901 2.12946 2.46724 + endloop + endfacet + facet normal 0.1409 0.810707 0.568245 + outer loop + vertex 1.44901 2.12946 2.46724 + vertex 1.44427 2.12848 2.46981 + vertex 1.44876 2.12732 2.47036 + endloop + endfacet + facet normal 0.142864 0.722493 0.676456 + outer loop + vertex 1.44599 2.12567 2.47245 + vertex 1.44427 2.12848 2.46981 + vertex 1.44177 2.12661 2.47234 + endloop + endfacet + facet normal 0.100025 0.712925 0.69407 + outer loop + vertex 1.44876 2.12732 2.47036 + vertex 1.44427 2.12848 2.46981 + vertex 1.44599 2.12567 2.47245 + endloop + endfacet + facet normal 0.158961 0.407587 0.899224 + outer loop + vertex 1.45 2.13763 2.455 + vertex 1.445 2.13958 2.455 + vertex 1.44815 2.1347 2.45665 + endloop + endfacet + facet normal 0.314238 0.480478 0.818777 + outer loop + vertex 1.44815 2.1347 2.45665 + vertex 1.445 2.13958 2.455 + vertex 1.44407 2.1353 2.45787 + endloop + endfacet + facet normal 0.268848 0.827364 0.493142 + outer loop + vertex 1.44815 2.1347 2.45665 + vertex 1.44407 2.1353 2.45787 + vertex 1.44665 2.13274 2.46076 + endloop + endfacet + facet normal 0.237142 0.822447 0.517053 + outer loop + vertex 1.44665 2.13274 2.46076 + vertex 1.44407 2.1353 2.45787 + vertex 1.44219 2.13422 2.46045 + endloop + endfacet + facet normal 0.137223 0.890001 0.43482 + outer loop + vertex 1.44681 2.13115 2.46458 + vertex 1.44251 2.13215 2.4639 + vertex 1.44471 2.13038 2.46681 + endloop + endfacet + facet normal 0.152462 0.914605 0.374505 + outer loop + vertex 1.44681 2.13115 2.46458 + vertex 1.44665 2.13274 2.46076 + vertex 1.44251 2.13215 2.4639 + endloop + endfacet + facet normal 0.245467 0.840368 0.483247 + outer loop + vertex 1.44665 2.13274 2.46076 + vertex 1.44219 2.13422 2.46045 + vertex 1.44251 2.13215 2.4639 + endloop + endfacet + facet normal 0.121677 0.887261 0.44493 + outer loop + vertex 1.44471 2.13038 2.46681 + vertex 1.44251 2.13215 2.4639 + vertex 1.44064 2.13054 2.46761 + endloop + endfacet + facet normal -0.276756 0.925536 0.258437 + outer loop + vertex 1.45 0.893396 2.455 + vertex 1.455 0.895 2.45461 + vertex 1.45199 0.894156 2.45441 + endloop + endfacet + facet normal 0.168898 -0.696092 -0.697803 + outer loop + vertex 1.45 0.895 2.4534 + vertex 1.455 0.895 2.45461 + vertex 1.45 0.893396 2.455 + endloop + endfacet + facet normal 0.419189 -0.851369 0.315361 + outer loop + vertex 1.45199 0.894156 2.45441 + vertex 1.45 0.895 2.45933 + vertex 1.45 0.893396 2.455 + endloop + endfacet + facet normal 0.206711 -0.94699 0.245927 + outer loop + vertex 1.45348 0.894612 2.45491 + vertex 1.45 0.895 2.45933 + vertex 1.45199 0.894156 2.45441 + endloop + endfacet + facet normal 0.426677 -0.807695 0.40691 + outer loop + vertex 1.45 0.895 2.45933 + vertex 1.45348 0.894612 2.45491 + vertex 1.45291 0.895337 2.45694 + endloop + endfacet + facet normal 0.50193 -0.695119 0.51466 + outer loop + vertex 1.45 0.895496 2.46 + vertex 1.45 0.895 2.45933 + vertex 1.45291 0.895337 2.45694 + endloop + endfacet + facet normal 0.472341 -0.733681 0.488473 + outer loop + vertex 1.45291 0.895337 2.45694 + vertex 1.45175 0.896863 2.46036 + vertex 1.45 0.895496 2.46 + endloop + endfacet + facet normal 0.287646 -0.571046 0.768873 + outer loop + vertex 1.45175 0.896863 2.46036 + vertex 1.44661 0.896788 2.46223 + vertex 1.45 0.895496 2.46 + endloop + endfacet + facet normal 0.192233 -0.847252 0.495187 + outer loop + vertex 1.45175 0.896863 2.46036 + vertex 1.44921 0.89854 2.46422 + vertex 1.44661 0.896788 2.46223 + endloop + endfacet + facet normal 0.170243 -0.857668 0.485205 + outer loop + vertex 1.45319 0.898737 2.46317 + vertex 1.44921 0.89854 2.46422 + vertex 1.45175 0.896863 2.46036 + endloop + endfacet + facet normal 0.185821 -0.812218 0.552967 + outer loop + vertex 1.44921 0.89854 2.46422 + vertex 1.45319 0.898737 2.46317 + vertex 1.4519 0.900957 2.46686 + endloop + endfacet + facet normal 0.176906 -0.809608 0.559678 + outer loop + vertex 1.44649 0.900136 2.46739 + vertex 1.44921 0.89854 2.46422 + vertex 1.4519 0.900957 2.46686 + endloop + endfacet + facet normal 0.148608 -0.751628 0.642629 + outer loop + vertex 1.45087 0.903388 2.46994 + vertex 1.4519 0.900957 2.46686 + vertex 1.45442 0.903427 2.46917 + endloop + endfacet + facet normal 0.158467 -0.748742 0.643641 + outer loop + vertex 1.45087 0.903388 2.46994 + vertex 1.44734 0.902614 2.46991 + vertex 1.4519 0.900957 2.46686 + endloop + endfacet + facet normal 0.174708 -0.73182 0.658723 + outer loop + vertex 1.44734 0.902614 2.46991 + vertex 1.44649 0.900136 2.46739 + vertex 1.4519 0.900957 2.46686 + endloop + endfacet + facet normal 0.13531 -0.647475 0.749979 + outer loop + vertex 1.45087 0.903388 2.46994 + vertex 1.44906 0.905385 2.47199 + vertex 1.44734 0.902614 2.46991 + endloop + endfacet + facet normal 0.166875 -0.661755 0.730912 + outer loop + vertex 1.45442 0.903427 2.46917 + vertex 1.45258 0.905264 2.47125 + vertex 1.45087 0.903388 2.46994 + endloop + endfacet + facet normal 0.135999 -0.647074 0.750199 + outer loop + vertex 1.45258 0.905264 2.47125 + vertex 1.44906 0.905385 2.47199 + vertex 1.45087 0.903388 2.46994 + endloop + endfacet + facet normal 0.152623 -0.559376 0.814742 + outer loop + vertex 1.45258 0.905264 2.47125 + vertex 1.45318 0.908754 2.47354 + vertex 1.44906 0.905385 2.47199 + endloop + endfacet + facet normal 0.136068 -0.54491 0.827381 + outer loop + vertex 1.45318 0.908754 2.47354 + vertex 1.44732 0.908194 2.47413 + vertex 1.44906 0.905385 2.47199 + endloop + endfacet + facet normal -0.305577 0.925157 0.225182 + outer loop + vertex 1.44999 1.00382 2.49547 + vertex 1.44745 1.00351 2.4933 + vertex 1.44782 1.0028 2.49673 + endloop + endfacet + facet normal -0.269112 0.920295 0.283965 + outer loop + vertex 1.45155 1.00349 2.49803 + vertex 1.44999 1.00382 2.49547 + vertex 1.44782 1.0028 2.49673 + endloop + endfacet + facet normal -0.329008 0.781995 0.529375 + outer loop + vertex 1.45155 1.00349 2.49803 + vertex 1.44782 1.0028 2.49673 + vertex 1.4517 1.00197 2.50037 + endloop + endfacet + facet normal -0.252337 0.849675 0.463009 + outer loop + vertex 1.4517 1.00197 2.50037 + vertex 1.44782 1.0028 2.49673 + vertex 1.44733 1.00068 2.50035 + endloop + endfacet + facet normal -0.0934093 0.613264 0.784335 + outer loop + vertex 1.45178 0.998449 2.50263 + vertex 1.44733 1.00068 2.50035 + vertex 1.44584 0.997412 2.50273 + endloop + endfacet + facet normal -0.159853 0.530073 0.832748 + outer loop + vertex 1.4517 1.00197 2.50037 + vertex 1.44733 1.00068 2.50035 + vertex 1.45178 0.998449 2.50263 + endloop + endfacet + facet normal -0.0319979 0.991883 -0.12306 + outer loop + vertex 1.45 1.005 2.4899 + vertex 1.45422 1.00509 2.48951 + vertex 1.455 1.005 2.4886 + endloop + endfacet + facet normal 0.0904004 0.11192 0.989597 + outer loop + vertex 1.45029 1.00432 2.48995 + vertex 1.45422 1.00509 2.48951 + vertex 1.45 1.005 2.4899 + endloop + endfacet + facet normal -0.185635 0.980589 0.0631335 + outer loop + vertex 1.45422 1.00509 2.48951 + vertex 1.45029 1.00432 2.48995 + vertex 1.45381 1.00482 2.49249 + endloop + endfacet + facet normal -0.1792 0.982338 0.0538526 + outer loop + vertex 1.45381 1.00482 2.49249 + vertex 1.45029 1.00432 2.48995 + vertex 1.45004 1.00412 2.49271 + endloop + endfacet + facet normal -0.204877 0.97364 0.100249 + outer loop + vertex 1.44999 1.00382 2.49547 + vertex 1.45004 1.00412 2.49271 + vertex 1.44745 1.00351 2.4933 + endloop + endfacet + facet normal -0.16269 0.981414 0.101781 + outer loop + vertex 1.44999 1.00382 2.49547 + vertex 1.45356 1.00431 2.49653 + vertex 1.45004 1.00412 2.49271 + endloop + endfacet + facet normal -0.17486 0.978068 0.113168 + outer loop + vertex 1.45356 1.00431 2.49653 + vertex 1.45381 1.00482 2.49249 + vertex 1.45004 1.00412 2.49271 + endloop + endfacet + facet normal -0.201054 0.948112 0.246296 + outer loop + vertex 1.45356 1.00431 2.49653 + vertex 1.44999 1.00382 2.49547 + vertex 1.45155 1.00349 2.49803 + endloop + endfacet + facet normal -0.543094 -0.20776 -0.813563 + outer loop + vertex 1.4568 2.02253 2.48937 + vertex 1.45491 2.025 2.49 + vertex 1.455 2.025 2.48994 + endloop + endfacet + facet normal -0.757 -0.460439 -0.463623 + outer loop + vertex 1.45553 2.02151 2.49245 + vertex 1.45491 2.025 2.49 + vertex 1.4568 2.02253 2.48937 + endloop + endfacet + facet normal -0.319797 -0.582589 -0.747209 + outer loop + vertex 1.45162 2.02246 2.49339 + vertex 1.45491 2.025 2.49 + vertex 1.45553 2.02151 2.49245 + endloop + endfacet + facet normal -0.2644 -0.955024 -0.134245 + outer loop + vertex 1.45465 2.02111 2.49708 + vertex 1.45162 2.02246 2.49339 + vertex 1.45553 2.02151 2.49245 + endloop + endfacet + facet normal -0.291974 -0.950106 -0.109771 + outer loop + vertex 1.45084 2.02215 2.49821 + vertex 1.45162 2.02246 2.49339 + vertex 1.45465 2.02111 2.49708 + endloop + endfacet + facet normal -0.257658 -0.966039 0.0195096 + outer loop + vertex 1.45384 2.02141 2.50147 + vertex 1.45084 2.02215 2.49821 + vertex 1.45465 2.02111 2.49708 + endloop + endfacet + facet normal -0.30887 -0.948481 0.0705895 + outer loop + vertex 1.45024 2.02266 2.50251 + vertex 1.45084 2.02215 2.49821 + vertex 1.45384 2.02141 2.50147 + endloop + endfacet + facet normal -0.284116 -0.946345 0.153979 + outer loop + vertex 1.45277 2.02219 2.5043 + vertex 1.45024 2.02266 2.50251 + vertex 1.45384 2.02141 2.50147 + endloop + endfacet + facet normal -0.365381 -0.886467 0.28403 + outer loop + vertex 1.45017 2.02352 2.50511 + vertex 1.45024 2.02266 2.50251 + vertex 1.45277 2.02219 2.5043 + endloop + endfacet + facet normal -0.220407 -0.78299 0.581676 + outer loop + vertex 1.45277 2.02219 2.5043 + vertex 1.45291 2.02335 2.50591 + vertex 1.45017 2.02352 2.50511 + endloop + endfacet + facet normal 0.0268311 -0.812557 -0.582264 + outer loop + vertex 1.45491 2.025 2.49 + vertex 1.45162 2.02246 2.49339 + vertex 1.44816 2.02425 2.49074 + endloop + endfacet + facet normal -0.0850859 -0.197995 -0.976503 + outer loop + vertex 1.45 2.02711 2.49 + vertex 1.45491 2.025 2.49 + vertex 1.44816 2.02425 2.49074 + endloop + endfacet + facet normal -0.175097 -0.980152 -0.0929649 + outer loop + vertex 1.45162 2.02246 2.49339 + vertex 1.45084 2.02215 2.49821 + vertex 1.44718 2.02314 2.49468 + endloop + endfacet + facet normal -0.231101 -0.919723 -0.317336 + outer loop + vertex 1.44816 2.02425 2.49074 + vertex 1.45162 2.02246 2.49339 + vertex 1.44718 2.02314 2.49468 + endloop + endfacet + facet normal -0.250872 -0.964656 0.0806304 + outer loop + vertex 1.45084 2.02215 2.49821 + vertex 1.45024 2.02266 2.50251 + vertex 1.44666 2.02334 2.49957 + endloop + endfacet + facet normal -0.272194 -0.962159 0.0126415 + outer loop + vertex 1.44718 2.02314 2.49468 + vertex 1.45084 2.02215 2.49821 + vertex 1.44666 2.02334 2.49957 + endloop + endfacet + facet normal -0.310625 -0.904716 0.291549 + outer loop + vertex 1.45024 2.02266 2.50251 + vertex 1.45017 2.02352 2.50511 + vertex 1.4459 2.02463 2.504 + endloop + endfacet + facet normal -0.344865 -0.915673 0.206424 + outer loop + vertex 1.44666 2.02334 2.49957 + vertex 1.45024 2.02266 2.50251 + vertex 1.4459 2.02463 2.504 + endloop + endfacet + facet normal -0.340765 -0.554299 0.759363 + outer loop + vertex 1.45017 2.02352 2.50511 + vertex 1.44845 2.02605 2.50618 + vertex 1.4459 2.02463 2.504 + endloop + endfacet + facet normal -0.270668 -0.52637 0.806024 + outer loop + vertex 1.45017 2.02352 2.50511 + vertex 1.45291 2.02335 2.50591 + vertex 1.44845 2.02605 2.50618 + endloop + endfacet + facet normal -0.0977295 -0.255705 0.961803 + outer loop + vertex 1.45291 2.02335 2.50591 + vertex 1.45293 2.0256 2.50652 + vertex 1.44845 2.02605 2.50618 + endloop + endfacet + facet normal 0.122939 0.566182 0.815061 + outer loop + vertex 1.45175 2.1215 2.47455 + vertex 1.45133 2.12468 2.4724 + vertex 1.44754 2.12254 2.47446 + endloop + endfacet + facet normal 0.114429 0.575911 0.809465 + outer loop + vertex 1.44754 2.12254 2.47446 + vertex 1.45133 2.12468 2.4724 + vertex 1.44599 2.12567 2.47245 + endloop + endfacet + facet normal 0.117455 0.897645 0.42478 + outer loop + vertex 1.44901 2.12946 2.46724 + vertex 1.45412 2.12965 2.46543 + vertex 1.45068 2.13108 2.46336 + endloop + endfacet + facet normal 0.153528 0.886838 0.43583 + outer loop + vertex 1.44681 2.13115 2.46458 + vertex 1.44901 2.12946 2.46724 + vertex 1.45068 2.13108 2.46336 + endloop + endfacet + facet normal 0.153626 0.839553 0.521105 + outer loop + vertex 1.45412 2.12965 2.46543 + vertex 1.44901 2.12946 2.46724 + vertex 1.45337 2.12746 2.46918 + endloop + endfacet + facet normal 0.120542 0.813673 0.568688 + outer loop + vertex 1.45337 2.12746 2.46918 + vertex 1.44901 2.12946 2.46724 + vertex 1.44876 2.12732 2.47036 + endloop + endfacet + facet normal 0.133865 0.684474 0.716642 + outer loop + vertex 1.45133 2.12468 2.4724 + vertex 1.44876 2.12732 2.47036 + vertex 1.44599 2.12567 2.47245 + endloop + endfacet + facet normal 0.157959 0.695676 0.700774 + outer loop + vertex 1.45337 2.12746 2.46918 + vertex 1.44876 2.12732 2.47036 + vertex 1.45133 2.12468 2.4724 + endloop + endfacet + facet normal 0.00887719 0.221893 0.975031 + outer loop + vertex 1.455 2.13743 2.455 + vertex 1.45 2.13763 2.455 + vertex 1.45212 2.13443 2.45571 + endloop + endfacet + facet normal 0.239527 0.358375 0.902327 + outer loop + vertex 1.45212 2.13443 2.45571 + vertex 1.45 2.13763 2.455 + vertex 1.44815 2.1347 2.45665 + endloop + endfacet + facet normal 0.174454 0.85684 0.485172 + outer loop + vertex 1.45212 2.13443 2.45571 + vertex 1.44815 2.1347 2.45665 + vertex 1.45225 2.13246 2.45914 + endloop + endfacet + facet normal 0.181265 0.860088 0.476855 + outer loop + vertex 1.45225 2.13246 2.45914 + vertex 1.44815 2.1347 2.45665 + vertex 1.44665 2.13274 2.46076 + endloop + endfacet + facet normal 0.135191 0.916666 0.376093 + outer loop + vertex 1.45068 2.13108 2.46336 + vertex 1.44665 2.13274 2.46076 + vertex 1.44681 2.13115 2.46458 + endloop + endfacet + facet normal 0.149546 0.921977 0.357203 + outer loop + vertex 1.45225 2.13246 2.45914 + vertex 1.44665 2.13274 2.46076 + vertex 1.45068 2.13108 2.46336 + endloop + endfacet + facet normal 0.170313 -0.39127 -0.904379 + outer loop + vertex 1.45707 0.895 2.455 + vertex 1.45199 0.894156 2.45441 + vertex 1.455 0.895 2.45461 + endloop + endfacet + facet normal 0.0784596 -0.844104 0.530408 + outer loop + vertex 1.45707 0.895 2.455 + vertex 1.45348 0.894612 2.45491 + vertex 1.45199 0.894156 2.45441 + endloop + endfacet + facet normal -0.048299 0.233139 0.971243 + outer loop + vertex 1.45348 0.894612 2.45491 + vertex 1.45707 0.895 2.455 + vertex 1.46 0.895607 2.455 + endloop + endfacet + facet normal 0.135595 -0.920634 0.366125 + outer loop + vertex 1.45348 0.894612 2.45491 + vertex 1.46 0.895607 2.455 + vertex 1.45291 0.895337 2.45694 + endloop + endfacet + facet normal 0.174449 -0.836525 0.519417 + outer loop + vertex 1.45291 0.895337 2.45694 + vertex 1.46 0.895607 2.455 + vertex 1.45672 0.896599 2.4577 + endloop + endfacet + facet normal 0.17208 -0.883326 0.436032 + outer loop + vertex 1.4557 0.897934 2.46081 + vertex 1.45672 0.896599 2.4577 + vertex 1.45976 0.898186 2.45971 + endloop + endfacet + facet normal 0.18863 -0.878303 0.439322 + outer loop + vertex 1.4557 0.897934 2.46081 + vertex 1.45175 0.896863 2.46036 + vertex 1.45672 0.896599 2.4577 + endloop + endfacet + facet normal 0.19766 -0.868179 0.455188 + outer loop + vertex 1.45175 0.896863 2.46036 + vertex 1.45291 0.895337 2.45694 + vertex 1.45672 0.896599 2.4577 + endloop + endfacet + facet normal 0.178426 -0.858172 0.481358 + outer loop + vertex 1.4557 0.897934 2.46081 + vertex 1.45319 0.898737 2.46317 + vertex 1.45175 0.896863 2.46036 + endloop + endfacet + facet normal 0.182358 -0.85807 0.480064 + outer loop + vertex 1.45976 0.898186 2.45971 + vertex 1.4573 0.899854 2.46363 + vertex 1.4557 0.897934 2.46081 + endloop + endfacet + facet normal 0.178969 -0.857805 0.48181 + outer loop + vertex 1.45319 0.898737 2.46317 + vertex 1.4557 0.897934 2.46081 + vertex 1.4573 0.899854 2.46363 + endloop + endfacet + facet normal 0.161229 -0.820045 0.549119 + outer loop + vertex 1.45319 0.898737 2.46317 + vertex 1.4573 0.899854 2.46363 + vertex 1.4519 0.900957 2.46686 + endloop + endfacet + facet normal 0.161366 -0.819897 0.549299 + outer loop + vertex 1.4519 0.900957 2.46686 + vertex 1.4573 0.899854 2.46363 + vertex 1.45666 0.90187 2.46683 + endloop + endfacet + facet normal 0.148935 -0.751754 0.642405 + outer loop + vertex 1.45666 0.90187 2.46683 + vertex 1.45442 0.903427 2.46917 + vertex 1.4519 0.900957 2.46686 + endloop + endfacet + facet normal 0.160207 -0.744372 0.648263 + outer loop + vertex 1.4588 0.903901 2.46863 + vertex 1.45442 0.903427 2.46917 + vertex 1.45666 0.90187 2.46683 + endloop + endfacet + facet normal 0.161577 -0.660201 0.733503 + outer loop + vertex 1.45442 0.903427 2.46917 + vertex 1.4588 0.903901 2.46863 + vertex 1.45643 0.906089 2.47112 + endloop + endfacet + facet normal 0.166541 -0.661964 0.7308 + outer loop + vertex 1.45258 0.905264 2.47125 + vertex 1.45442 0.903427 2.46917 + vertex 1.45643 0.906089 2.47112 + endloop + endfacet + facet normal 0.147364 -0.559196 0.815833 + outer loop + vertex 1.45643 0.906089 2.47112 + vertex 1.45318 0.908754 2.47354 + vertex 1.45258 0.905264 2.47125 + endloop + endfacet + facet normal 0.132332 -0.571892 0.809585 + outer loop + vertex 1.45912 0.909359 2.47299 + vertex 1.45318 0.908754 2.47354 + vertex 1.45643 0.906089 2.47112 + endloop + endfacet + facet normal -0.294178 0.792651 0.534007 + outer loop + vertex 1.45425 1.0033 2.4998 + vertex 1.45155 1.00349 2.49803 + vertex 1.4517 1.00197 2.50037 + endloop + endfacet + facet normal -0.193279 0.676654 0.710481 + outer loop + vertex 1.4517 1.00197 2.50037 + vertex 1.45589 1.00152 2.50195 + vertex 1.45425 1.0033 2.4998 + endloop + endfacet + facet normal -0.250595 0.518322 0.817646 + outer loop + vertex 1.4517 1.00197 2.50037 + vertex 1.45178 0.998449 2.50263 + vertex 1.45589 1.00152 2.50195 + endloop + endfacet + facet normal -0.0694235 0.304987 0.949823 + outer loop + vertex 1.45178 0.998449 2.50263 + vertex 1.45756 0.998249 2.50312 + vertex 1.45589 1.00152 2.50195 + endloop + endfacet + facet normal -0.0968946 0.600054 -0.79407 + outer loop + vertex 1.455 1.005 2.4886 + vertex 1.46 1.00766 2.49 + vertex 1.46 1.005 2.48799 + endloop + endfacet + facet normal -0.347879 0.855618 -0.383274 + outer loop + vertex 1.45422 1.00509 2.48951 + vertex 1.46 1.00766 2.49 + vertex 1.455 1.005 2.4886 + endloop + endfacet + facet normal -0.399871 0.819951 0.409614 + outer loop + vertex 1.46 1.00766 2.49 + vertex 1.45422 1.00509 2.48951 + vertex 1.45849 1.00578 2.49228 + endloop + endfacet + facet normal -0.199285 0.978038 0.0610465 + outer loop + vertex 1.45849 1.00578 2.49228 + vertex 1.45422 1.00509 2.48951 + vertex 1.45381 1.00482 2.49249 + endloop + endfacet + facet normal -0.193188 0.968693 0.155923 + outer loop + vertex 1.45849 1.00578 2.49228 + vertex 1.45381 1.00482 2.49249 + vertex 1.45801 1.00503 2.49636 + endloop + endfacet + facet normal -0.155861 0.981093 0.114737 + outer loop + vertex 1.45801 1.00503 2.49636 + vertex 1.45381 1.00482 2.49249 + vertex 1.45356 1.00431 2.49653 + endloop + endfacet + facet normal -0.143051 0.937282 0.317866 + outer loop + vertex 1.45425 1.0033 2.4998 + vertex 1.45356 1.00431 2.49653 + vertex 1.45155 1.00349 2.49803 + endloop + endfacet + facet normal -0.122176 0.941296 0.314698 + outer loop + vertex 1.45425 1.0033 2.4998 + vertex 1.45758 1.00369 2.49994 + vertex 1.45356 1.00431 2.49653 + endloop + endfacet + facet normal -0.139657 0.932288 0.33367 + outer loop + vertex 1.45758 1.00369 2.49994 + vertex 1.45801 1.00503 2.49636 + vertex 1.45356 1.00431 2.49653 + endloop + endfacet + facet normal -0.11238 0.720123 0.684685 + outer loop + vertex 1.45758 1.00369 2.49994 + vertex 1.45425 1.0033 2.4998 + vertex 1.45589 1.00152 2.50195 + endloop + endfacet + facet normal 0.270793 -0.665202 -0.695828 + outer loop + vertex 1.4568 2.02253 2.48937 + vertex 1.46 2.025 2.48826 + vertex 1.46 2.02318 2.49 + endloop + endfacet + facet normal -0.318456 -0.013307 -0.947844 + outer loop + vertex 1.455 2.025 2.48994 + vertex 1.46 2.025 2.48826 + vertex 1.4568 2.02253 2.48937 + endloop + endfacet + facet normal 0.270957 -0.694475 -0.666548 + outer loop + vertex 1.46 2.02318 2.49 + vertex 1.45917 2.02073 2.49222 + vertex 1.4568 2.02253 2.48937 + endloop + endfacet + facet normal -0.218597 -0.896077 -0.386343 + outer loop + vertex 1.45917 2.02073 2.49222 + vertex 1.45553 2.02151 2.49245 + vertex 1.4568 2.02253 2.48937 + endloop + endfacet + facet normal -0.217684 -0.966468 -0.13621 + outer loop + vertex 1.45917 2.02073 2.49222 + vertex 1.45837 2.02031 2.49643 + vertex 1.45553 2.02151 2.49245 + endloop + endfacet + facet normal -0.228245 -0.965119 -0.128258 + outer loop + vertex 1.45837 2.02031 2.49643 + vertex 1.45465 2.02111 2.49708 + vertex 1.45553 2.02151 2.49245 + endloop + endfacet + facet normal -0.204357 -0.978575 0.0250921 + outer loop + vertex 1.45837 2.02031 2.49643 + vertex 1.45752 2.0206 2.50074 + vertex 1.45465 2.02111 2.49708 + endloop + endfacet + facet normal -0.209391 -0.977396 0.0292065 + outer loop + vertex 1.45752 2.0206 2.50074 + vertex 1.45384 2.02141 2.50147 + vertex 1.45465 2.02111 2.49708 + endloop + endfacet + facet normal -0.173112 -0.964935 0.197314 + outer loop + vertex 1.45752 2.0206 2.50074 + vertex 1.45592 2.02159 2.50417 + vertex 1.45384 2.02141 2.50147 + endloop + endfacet + facet normal -0.176131 -0.963922 0.19958 + outer loop + vertex 1.45592 2.02159 2.50417 + vertex 1.45277 2.02219 2.5043 + vertex 1.45384 2.02141 2.50147 + endloop + endfacet + facet normal -0.128183 -0.800187 0.585892 + outer loop + vertex 1.45592 2.02159 2.50417 + vertex 1.45291 2.02335 2.50591 + vertex 1.45277 2.02219 2.5043 + endloop + endfacet + facet normal -0.0507161 -0.745719 0.664327 + outer loop + vertex 1.45714 2.02318 2.50604 + vertex 1.45291 2.02335 2.50591 + vertex 1.45592 2.02159 2.50417 + endloop + endfacet + facet normal -0.03965 -0.257249 0.965531 + outer loop + vertex 1.45293 2.0256 2.50652 + vertex 1.45291 2.02335 2.50591 + vertex 1.45714 2.02318 2.50604 + endloop + endfacet + facet normal 0.119408 0.46096 0.87935 + outer loop + vertex 1.45385 2.11853 2.47572 + vertex 1.4579 2.11792 2.47549 + vertex 1.45668 2.12181 2.47362 + endloop + endfacet + facet normal 0.138884 0.446958 0.883708 + outer loop + vertex 1.45175 2.1215 2.47455 + vertex 1.45385 2.11853 2.47572 + vertex 1.45668 2.12181 2.47362 + endloop + endfacet + facet normal 0.107442 0.362022 0.925957 + outer loop + vertex 1.4579 2.11792 2.47549 + vertex 1.45385 2.11853 2.47572 + vertex 1.4561 2.11452 2.47702 + endloop + endfacet + facet normal 0.141174 0.705417 0.694591 + outer loop + vertex 1.45929 2.12451 2.47126 + vertex 1.45734 2.12651 2.46962 + vertex 1.45552 2.12518 2.47135 + endloop + endfacet + facet normal 0.122119 0.582942 0.803284 + outer loop + vertex 1.45552 2.12518 2.47135 + vertex 1.45668 2.12181 2.47362 + vertex 1.45929 2.12451 2.47126 + endloop + endfacet + facet normal 0.132087 0.584521 0.800555 + outer loop + vertex 1.45552 2.12518 2.47135 + vertex 1.45133 2.12468 2.4724 + vertex 1.45668 2.12181 2.47362 + endloop + endfacet + facet normal 0.118736 0.566092 0.815746 + outer loop + vertex 1.45133 2.12468 2.4724 + vertex 1.45175 2.1215 2.47455 + vertex 1.45668 2.12181 2.47362 + endloop + endfacet + facet normal 0.161803 0.919502 0.358241 + outer loop + vertex 1.45888 2.13 2.4628 + vertex 1.45673 2.13156 2.45976 + vertex 1.45463 2.13098 2.4622 + endloop + endfacet + facet normal 0.138991 0.907689 0.395957 + outer loop + vertex 1.45463 2.13098 2.4622 + vertex 1.45068 2.13108 2.46336 + vertex 1.45412 2.12965 2.46543 + endloop + endfacet + facet normal 0.152965 0.904969 0.39703 + outer loop + vertex 1.45463 2.13098 2.4622 + vertex 1.45412 2.12965 2.46543 + vertex 1.45888 2.13 2.4628 + endloop + endfacet + facet normal 0.173944 0.884768 0.432354 + outer loop + vertex 1.45888 2.13 2.4628 + vertex 1.45412 2.12965 2.46543 + vertex 1.45789 2.12816 2.46697 + endloop + endfacet + facet normal 0.100487 0.732952 0.672818 + outer loop + vertex 1.45734 2.12651 2.46962 + vertex 1.45337 2.12746 2.46918 + vertex 1.45552 2.12518 2.47135 + endloop + endfacet + facet normal 0.137803 0.828483 0.542795 + outer loop + vertex 1.45734 2.12651 2.46962 + vertex 1.45789 2.12816 2.46697 + vertex 1.45337 2.12746 2.46918 + endloop + endfacet + facet normal 0.12332 0.845969 0.518776 + outer loop + vertex 1.45789 2.12816 2.46697 + vertex 1.45412 2.12965 2.46543 + vertex 1.45337 2.12746 2.46918 + endloop + endfacet + facet normal 0.0851321 0.72677 0.681585 + outer loop + vertex 1.45552 2.12518 2.47135 + vertex 1.45337 2.12746 2.46918 + vertex 1.45133 2.12468 2.4724 + endloop + endfacet + facet normal 0.0163356 0.326891 0.944921 + outer loop + vertex 1.46 2.13718 2.455 + vertex 1.455 2.13743 2.455 + vertex 1.45688 2.13345 2.45634 + endloop + endfacet + facet normal -0.0676227 0.290493 0.954485 + outer loop + vertex 1.45688 2.13345 2.45634 + vertex 1.455 2.13743 2.455 + vertex 1.45212 2.13443 2.45571 + endloop + endfacet + facet normal 0.139248 0.92962 0.3412 + outer loop + vertex 1.45673 2.13156 2.45976 + vertex 1.45225 2.13246 2.45914 + vertex 1.45463 2.13098 2.4622 + endloop + endfacet + facet normal 0.106841 0.868334 0.484335 + outer loop + vertex 1.45673 2.13156 2.45976 + vertex 1.45688 2.13345 2.45634 + vertex 1.45225 2.13246 2.45914 + endloop + endfacet + facet normal 0.112094 0.863684 0.491411 + outer loop + vertex 1.45688 2.13345 2.45634 + vertex 1.45212 2.13443 2.45571 + vertex 1.45225 2.13246 2.45914 + endloop + endfacet + facet normal 0.126231 0.928006 0.350529 + outer loop + vertex 1.45463 2.13098 2.4622 + vertex 1.45225 2.13246 2.45914 + vertex 1.45068 2.13108 2.46336 + endloop + endfacet + facet normal 0.149036 -0.792724 0.591081 + outer loop + vertex 1.465 0.896547 2.455 + vertex 1.46195 0.896922 2.45627 + vertex 1.46 0.895607 2.455 + endloop + endfacet + facet normal 0.198206 -0.817216 0.541176 + outer loop + vertex 1.46195 0.896922 2.45627 + vertex 1.45672 0.896599 2.4577 + vertex 1.46 0.895607 2.455 + endloop + endfacet + facet normal 0.173232 -0.88378 0.434653 + outer loop + vertex 1.46195 0.896922 2.45627 + vertex 1.45976 0.898186 2.45971 + vertex 1.45672 0.896599 2.4577 + endloop + endfacet + facet normal 0.163859 -0.887758 0.430158 + outer loop + vertex 1.46458 0.898475 2.45848 + vertex 1.45976 0.898186 2.45971 + vertex 1.46195 0.896922 2.45627 + endloop + endfacet + facet normal 0.169798 -0.873295 0.456646 + outer loop + vertex 1.45976 0.898186 2.45971 + vertex 1.46458 0.898475 2.45848 + vertex 1.46274 0.90007 2.46221 + endloop + endfacet + facet normal 0.156976 -0.869199 0.468883 + outer loop + vertex 1.4573 0.899854 2.46363 + vertex 1.45976 0.898186 2.45971 + vertex 1.46274 0.90007 2.46221 + endloop + endfacet + facet normal 0.171948 -0.828899 0.532316 + outer loop + vertex 1.46274 0.90007 2.46221 + vertex 1.46088 0.901942 2.46572 + vertex 1.4573 0.899854 2.46363 + endloop + endfacet + facet normal 0.157406 -0.820814 0.549079 + outer loop + vertex 1.46088 0.901942 2.46572 + vertex 1.45666 0.90187 2.46683 + vertex 1.4573 0.899854 2.46363 + endloop + endfacet + facet normal 0.17861 -0.751765 0.634782 + outer loop + vertex 1.46088 0.901942 2.46572 + vertex 1.4588 0.903901 2.46863 + vertex 1.45666 0.90187 2.46683 + endloop + endfacet + facet normal 0.155311 -0.763969 0.626283 + outer loop + vertex 1.46334 0.904364 2.46807 + vertex 1.4588 0.903901 2.46863 + vertex 1.46088 0.901942 2.46572 + endloop + endfacet + facet normal 0.157913 -0.673297 0.722311 + outer loop + vertex 1.4588 0.903901 2.46863 + vertex 1.46334 0.904364 2.46807 + vertex 1.46123 0.906668 2.47068 + endloop + endfacet + facet normal 0.147981 -0.669031 0.728354 + outer loop + vertex 1.45643 0.906089 2.47112 + vertex 1.4588 0.903901 2.46863 + vertex 1.46123 0.906668 2.47068 + endloop + endfacet + facet normal 0.143901 -0.577845 0.80336 + outer loop + vertex 1.46123 0.906668 2.47068 + vertex 1.45912 0.909359 2.47299 + vertex 1.45643 0.906089 2.47112 + endloop + endfacet + facet normal 0.135924 -0.582437 0.801431 + outer loop + vertex 1.4642 0.909948 2.47256 + vertex 1.45912 0.909359 2.47299 + vertex 1.46123 0.906668 2.47068 + endloop + endfacet + facet normal 0.11888 -0.299365 0.946704 + outer loop + vertex 1.45913 0.972709 2.49552 + vertex 1.45536 0.97169 2.49568 + vertex 1.45759 0.968701 2.49445 + endloop + endfacet + facet normal 0.120474 -0.299881 0.946339 + outer loop + vertex 1.45913 0.972709 2.49552 + vertex 1.45759 0.968701 2.49445 + vertex 1.46242 0.97251 2.49504 + endloop + endfacet + facet normal 0.115134 -0.284747 0.951663 + outer loop + vertex 1.45913 0.972709 2.49552 + vertex 1.45862 0.975441 2.4964 + vertex 1.45536 0.97169 2.49568 + endloop + endfacet + facet normal 0.121506 -0.289963 0.949293 + outer loop + vertex 1.46242 0.97251 2.49504 + vertex 1.46177 0.975207 2.49595 + vertex 1.45913 0.972709 2.49552 + endloop + endfacet + facet normal 0.116021 -0.284563 0.951611 + outer loop + vertex 1.46177 0.975207 2.49595 + vertex 1.45862 0.975441 2.4964 + vertex 1.45913 0.972709 2.49552 + endloop + endfacet + facet normal 0.116765 -0.278068 0.953438 + outer loop + vertex 1.46177 0.975207 2.49595 + vertex 1.46331 0.979081 2.49689 + vertex 1.45862 0.975441 2.4964 + endloop + endfacet + facet normal -0.0842453 0.297828 0.950895 + outer loop + vertex 1.45756 0.998249 2.50312 + vertex 1.46057 1.00168 2.50231 + vertex 1.45589 1.00152 2.50195 + endloop + endfacet + facet normal -0.132108 0.825661 0.54848 + outer loop + vertex 1.465 1.00846 2.49 + vertex 1.46 1.00766 2.49 + vertex 1.46352 1.00672 2.49226 + endloop + endfacet + facet normal -0.148602 0.809781 0.567602 + outer loop + vertex 1.46352 1.00672 2.49226 + vertex 1.46 1.00766 2.49 + vertex 1.45849 1.00578 2.49228 + endloop + endfacet + facet normal -0.177821 0.95742 0.227434 + outer loop + vertex 1.46352 1.00672 2.49226 + vertex 1.45849 1.00578 2.49228 + vertex 1.46284 1.00565 2.49626 + endloop + endfacet + facet normal -0.121098 0.978635 0.166158 + outer loop + vertex 1.46284 1.00565 2.49626 + vertex 1.45849 1.00578 2.49228 + vertex 1.45801 1.00503 2.49636 + endloop + endfacet + facet normal -0.110438 0.927406 0.357381 + outer loop + vertex 1.46284 1.00565 2.49626 + vertex 1.45801 1.00503 2.49636 + vertex 1.46213 1.00414 2.49996 + endloop + endfacet + facet normal -0.0938869 0.935551 0.340485 + outer loop + vertex 1.46213 1.00414 2.49996 + vertex 1.45801 1.00503 2.49636 + vertex 1.45758 1.00369 2.49994 + endloop + endfacet + facet normal -0.0790916 0.709088 0.70067 + outer loop + vertex 1.46057 1.00168 2.50231 + vertex 1.45758 1.00369 2.49994 + vertex 1.45589 1.00152 2.50195 + endloop + endfacet + facet normal -0.0739679 0.712855 0.6974 + outer loop + vertex 1.46213 1.00414 2.49996 + vertex 1.45758 1.00369 2.49994 + vertex 1.46057 1.00168 2.50231 + endloop + endfacet + facet normal -0.119329 -0.710333 -0.693677 + outer loop + vertex 1.465 2.02234 2.49 + vertex 1.46342 2.02037 2.49228 + vertex 1.46 2.02318 2.49 + endloop + endfacet + facet normal -0.0433127 -0.662038 -0.748217 + outer loop + vertex 1.46342 2.02037 2.49228 + vertex 1.45917 2.02073 2.49222 + vertex 1.46 2.02318 2.49 + endloop + endfacet + facet normal -0.0799334 -0.989382 -0.121386 + outer loop + vertex 1.46342 2.02037 2.49228 + vertex 1.46238 2.01995 2.49644 + vertex 1.45917 2.02073 2.49222 + endloop + endfacet + facet normal -0.0896726 -0.989428 -0.11398 + outer loop + vertex 1.46238 2.01995 2.49644 + vertex 1.45837 2.02031 2.49643 + vertex 1.45917 2.02073 2.49222 + endloop + endfacet + facet normal -0.0907572 -0.995583 0.0240229 + outer loop + vertex 1.46238 2.01995 2.49644 + vertex 1.46095 2.02017 2.5 + vertex 1.45837 2.02031 2.49643 + endloop + endfacet + facet normal -0.116969 -0.9922 0.0430962 + outer loop + vertex 1.46095 2.02017 2.5 + vertex 1.45752 2.0206 2.50074 + vertex 1.45837 2.02031 2.49643 + endloop + endfacet + facet normal -0.0715542 -0.968182 0.239799 + outer loop + vertex 1.46095 2.02017 2.5 + vertex 1.46048 2.02113 2.50374 + vertex 1.45752 2.0206 2.50074 + endloop + endfacet + facet normal -0.075512 -0.966961 0.243483 + outer loop + vertex 1.46048 2.02113 2.50374 + vertex 1.45592 2.02159 2.50417 + vertex 1.45752 2.0206 2.50074 + endloop + endfacet + facet normal -0.0163615 -0.757797 0.652285 + outer loop + vertex 1.46048 2.02113 2.50374 + vertex 1.45714 2.02318 2.50604 + vertex 1.45592 2.02159 2.50417 + endloop + endfacet + facet normal -0.0906967 -0.805086 0.586183 + outer loop + vertex 1.46125 2.02256 2.50583 + vertex 1.45714 2.02318 2.50604 + vertex 1.46048 2.02113 2.50374 + endloop + endfacet + facet normal 0.129249 0.393754 0.910084 + outer loop + vertex 1.4579 2.11792 2.47549 + vertex 1.46036 2.11553 2.47617 + vertex 1.46218 2.11873 2.47453 + endloop + endfacet + facet normal 0.110507 0.459163 0.881452 + outer loop + vertex 1.4579 2.11792 2.47549 + vertex 1.46218 2.11873 2.47453 + vertex 1.45668 2.12181 2.47362 + endloop + endfacet + facet normal 0.12941 0.487651 0.863394 + outer loop + vertex 1.45668 2.12181 2.47362 + vertex 1.46218 2.11873 2.47453 + vertex 1.46162 2.12217 2.47267 + endloop + endfacet + facet normal 0.0984395 0.366451 0.925215 + outer loop + vertex 1.46036 2.11553 2.47617 + vertex 1.4579 2.11792 2.47549 + vertex 1.4561 2.11452 2.47702 + endloop + endfacet + facet normal 0.161847 0.737606 0.655548 + outer loop + vertex 1.45929 2.12451 2.47126 + vertex 1.46385 2.12408 2.47062 + vertex 1.4611 2.12636 2.46873 + endloop + endfacet + facet normal 0.186645 0.724412 0.66362 + outer loop + vertex 1.45734 2.12651 2.46962 + vertex 1.45929 2.12451 2.47126 + vertex 1.4611 2.12636 2.46873 + endloop + endfacet + facet normal 0.109521 0.591327 0.79896 + outer loop + vertex 1.46162 2.12217 2.47267 + vertex 1.45929 2.12451 2.47126 + vertex 1.45668 2.12181 2.47362 + endloop + endfacet + facet normal 0.166134 0.625488 0.762341 + outer loop + vertex 1.46385 2.12408 2.47062 + vertex 1.45929 2.12451 2.47126 + vertex 1.46162 2.12217 2.47267 + endloop + endfacet + facet normal 0.165496 0.910931 0.377909 + outer loop + vertex 1.45888 2.13 2.4628 + vertex 1.46489 2.12971 2.46086 + vertex 1.46089 2.13141 2.45851 + endloop + endfacet + facet normal 0.14385 0.917804 0.370059 + outer loop + vertex 1.45673 2.13156 2.45976 + vertex 1.45888 2.13 2.4628 + vertex 1.46089 2.13141 2.45851 + endloop + endfacet + facet normal 0.176325 0.893015 0.414045 + outer loop + vertex 1.46489 2.12971 2.46086 + vertex 1.45888 2.13 2.4628 + vertex 1.46274 2.12807 2.46531 + endloop + endfacet + facet normal 0.162682 0.887603 0.430924 + outer loop + vertex 1.46274 2.12807 2.46531 + vertex 1.45888 2.13 2.4628 + vertex 1.45789 2.12816 2.46697 + endloop + endfacet + facet normal 0.161925 0.823075 0.54436 + outer loop + vertex 1.4611 2.12636 2.46873 + vertex 1.45789 2.12816 2.46697 + vertex 1.45734 2.12651 2.46962 + endloop + endfacet + facet normal 0.18908 0.838692 0.510729 + outer loop + vertex 1.46274 2.12807 2.46531 + vertex 1.45789 2.12816 2.46697 + vertex 1.4611 2.12636 2.46873 + endloop + endfacet + facet normal 0.00210673 0.065844 0.997828 + outer loop + vertex 1.465 2.13702 2.455 + vertex 1.46 2.13718 2.455 + vertex 1.46321 2.13355 2.45523 + endloop + endfacet + facet normal 0.165722 0.208742 0.963827 + outer loop + vertex 1.46321 2.13355 2.45523 + vertex 1.46 2.13718 2.455 + vertex 1.45688 2.13345 2.45634 + endloop + endfacet + facet normal 0.175554 0.858472 0.481878 + outer loop + vertex 1.46089 2.13141 2.45851 + vertex 1.45688 2.13345 2.45634 + vertex 1.45673 2.13156 2.45976 + endloop + endfacet + facet normal 0.0899557 0.803432 0.588562 + outer loop + vertex 1.46321 2.13355 2.45523 + vertex 1.45688 2.13345 2.45634 + vertex 1.46089 2.13141 2.45851 + endloop + endfacet + facet normal 0.12369 -0.633677 0.763646 + outer loop + vertex 1.47 0.897523 2.455 + vertex 1.46765 0.897609 2.45545 + vertex 1.465 0.896547 2.455 + endloop + endfacet + facet normal 0.182606 -0.733873 0.654283 + outer loop + vertex 1.46765 0.897609 2.45545 + vertex 1.46195 0.896922 2.45627 + vertex 1.465 0.896547 2.455 + endloop + endfacet + facet normal 0.168408 -0.889077 0.425654 + outer loop + vertex 1.46765 0.897609 2.45545 + vertex 1.46458 0.898475 2.45848 + vertex 1.46195 0.896922 2.45627 + endloop + endfacet + facet normal 0.161695 -0.893017 0.41997 + outer loop + vertex 1.46863 0.898796 2.4576 + vertex 1.46458 0.898475 2.45848 + vertex 1.46765 0.897609 2.45545 + endloop + endfacet + facet normal 0.164909 -0.883573 0.438296 + outer loop + vertex 1.46458 0.898475 2.45848 + vertex 1.46863 0.898796 2.4576 + vertex 1.46763 0.900173 2.46075 + endloop + endfacet + facet normal 0.153057 -0.87931 0.450984 + outer loop + vertex 1.46274 0.90007 2.46221 + vertex 1.46458 0.898475 2.45848 + vertex 1.46763 0.900173 2.46075 + endloop + endfacet + facet normal 0.171518 -0.83937 0.51579 + outer loop + vertex 1.46763 0.900173 2.46075 + vertex 1.46625 0.902455 2.46492 + vertex 1.46274 0.90007 2.46221 + endloop + endfacet + facet normal 0.158528 -0.834269 0.528075 + outer loop + vertex 1.46625 0.902455 2.46492 + vertex 1.46088 0.901942 2.46572 + vertex 1.46274 0.90007 2.46221 + endloop + endfacet + facet normal 0.165744 -0.767609 0.619116 + outer loop + vertex 1.46625 0.902455 2.46492 + vertex 1.46334 0.904364 2.46807 + vertex 1.46088 0.901942 2.46572 + endloop + endfacet + facet normal 0.147314 -0.779264 0.609135 + outer loop + vertex 1.46714 0.905005 2.46797 + vertex 1.46334 0.904364 2.46807 + vertex 1.46625 0.902455 2.46492 + endloop + endfacet + facet normal 0.13395 -0.683349 0.717698 + outer loop + vertex 1.46334 0.904364 2.46807 + vertex 1.46714 0.905005 2.46797 + vertex 1.46571 0.907109 2.47024 + endloop + endfacet + facet normal 0.137313 -0.684719 0.715754 + outer loop + vertex 1.46123 0.906668 2.47068 + vertex 1.46334 0.904364 2.46807 + vertex 1.46571 0.907109 2.47024 + endloop + endfacet + facet normal 0.135608 -0.582257 0.801616 + outer loop + vertex 1.46571 0.907109 2.47024 + vertex 1.4642 0.909948 2.47256 + vertex 1.46123 0.906668 2.47068 + endloop + endfacet + facet normal 0.126408 -0.586092 0.800323 + outer loop + vertex 1.46883 0.91014 2.47197 + vertex 1.4642 0.909948 2.47256 + vertex 1.46571 0.907109 2.47024 + endloop + endfacet + facet normal 0.130237 -0.490929 0.86141 + outer loop + vertex 1.46883 0.91014 2.47197 + vertex 1.46804 0.913927 2.47425 + vertex 1.4642 0.909948 2.47256 + endloop + endfacet + facet normal 0.134951 -0.341828 0.930022 + outer loop + vertex 1.46887 0.995536 2.50175 + vertex 1.46432 0.995026 2.50223 + vertex 1.46556 0.991781 2.50086 + endloop + endfacet + facet normal -0.101131 0.842785 0.528665 + outer loop + vertex 1.47 1.00906 2.49 + vertex 1.465 1.00846 2.49 + vertex 1.46847 1.00742 2.49233 + endloop + endfacet + facet normal -0.123115 0.823973 0.553092 + outer loop + vertex 1.46847 1.00742 2.49233 + vertex 1.465 1.00846 2.49 + vertex 1.46352 1.00672 2.49226 + endloop + endfacet + facet normal -0.136793 0.947784 0.288086 + outer loop + vertex 1.46847 1.00742 2.49233 + vertex 1.46352 1.00672 2.49226 + vertex 1.46789 1.00615 2.49623 + endloop + endfacet + facet normal -0.0941959 0.965245 0.243782 + outer loop + vertex 1.46789 1.00615 2.49623 + vertex 1.46352 1.00672 2.49226 + vertex 1.46284 1.00565 2.49626 + endloop + endfacet + facet normal -0.0882838 0.913087 0.398093 + outer loop + vertex 1.46789 1.00615 2.49623 + vertex 1.46284 1.00565 2.49626 + vertex 1.46713 1.0045 2.49985 + endloop + endfacet + facet normal -0.0586378 0.92817 0.367508 + outer loop + vertex 1.46713 1.0045 2.49985 + vertex 1.46284 1.00565 2.49626 + vertex 1.46213 1.00414 2.49996 + endloop + endfacet + facet normal -0.0189611 0.696678 0.717134 + outer loop + vertex 1.46552 1.00196 2.50216 + vertex 1.46213 1.00414 2.49996 + vertex 1.46057 1.00168 2.50231 + endloop + endfacet + facet normal -0.0331655 0.685187 0.727612 + outer loop + vertex 1.46713 1.0045 2.49985 + vertex 1.46213 1.00414 2.49996 + vertex 1.46552 1.00196 2.50216 + endloop + endfacet + facet normal -0.0306998 -0.69753 -0.715897 + outer loop + vertex 1.47 2.02212 2.49 + vertex 1.46821 2.01997 2.49218 + vertex 1.465 2.02234 2.49 + endloop + endfacet + facet normal -0.0776702 -0.728557 -0.680567 + outer loop + vertex 1.46821 2.01997 2.49218 + vertex 1.46342 2.02037 2.49228 + vertex 1.465 2.02234 2.49 + endloop + endfacet + facet normal -0.0864184 -0.994224 -0.0636365 + outer loop + vertex 1.46821 2.01997 2.49218 + vertex 1.46713 2.01978 2.49651 + vertex 1.46342 2.02037 2.49228 + endloop + endfacet + facet normal -0.0332091 -0.993361 -0.110138 + outer loop + vertex 1.46713 2.01978 2.49651 + vertex 1.46238 2.01995 2.49644 + vertex 1.46342 2.02037 2.49228 + endloop + endfacet + facet normal -0.037197 -0.982835 0.180699 + outer loop + vertex 1.46713 2.01978 2.49651 + vertex 1.46509 2.02073 2.50124 + vertex 1.46238 2.01995 2.49644 + endloop + endfacet + facet normal 0.103764 -0.989326 0.102309 + outer loop + vertex 1.46509 2.02073 2.50124 + vertex 1.46095 2.02017 2.5 + vertex 1.46238 2.01995 2.49644 + endloop + endfacet + facet normal 0.417949 -0.802133 0.426498 + outer loop + vertex 1.464 2.02198 2.50466 + vertex 1.46509 2.02073 2.50124 + vertex 1.46811 2.02373 2.50392 + endloop + endfacet + facet normal 0.125037 -0.918105 0.376097 + outer loop + vertex 1.464 2.02198 2.50466 + vertex 1.46048 2.02113 2.50374 + vertex 1.46509 2.02073 2.50124 + endloop + endfacet + facet normal 0.0549006 -0.96546 0.254701 + outer loop + vertex 1.46048 2.02113 2.50374 + vertex 1.46095 2.02017 2.5 + vertex 1.46509 2.02073 2.50124 + endloop + endfacet + facet normal 0.0591652 -0.83306 0.55001 + outer loop + vertex 1.464 2.02198 2.50466 + vertex 1.46125 2.02256 2.50583 + vertex 1.46048 2.02113 2.50374 + endloop + endfacet + facet normal 0.135548 0.495591 0.857914 + outer loop + vertex 1.46779 2.11737 2.47443 + vertex 1.46611 2.12108 2.47255 + vertex 1.46218 2.11873 2.47453 + endloop + endfacet + facet normal 0.14147 0.488375 0.86109 + outer loop + vertex 1.46218 2.11873 2.47453 + vertex 1.46611 2.12108 2.47255 + vertex 1.46162 2.12217 2.47267 + endloop + endfacet + facet normal 0.161535 0.76489 0.623579 + outer loop + vertex 1.46385 2.12408 2.47062 + vertex 1.46929 2.12363 2.46976 + vertex 1.46578 2.12603 2.46772 + endloop + endfacet + facet normal 0.188912 0.751158 0.632514 + outer loop + vertex 1.4611 2.12636 2.46873 + vertex 1.46385 2.12408 2.47062 + vertex 1.46578 2.12603 2.46772 + endloop + endfacet + facet normal 0.171065 0.621799 0.764266 + outer loop + vertex 1.46611 2.12108 2.47255 + vertex 1.46385 2.12408 2.47062 + vertex 1.46162 2.12217 2.47267 + endloop + endfacet + facet normal 0.171767 0.622079 0.763881 + outer loop + vertex 1.46929 2.12363 2.46976 + vertex 1.46385 2.12408 2.47062 + vertex 1.46611 2.12108 2.47255 + endloop + endfacet + facet normal 0.0244462 0.772746 0.634244 + outer loop + vertex 1.47011 2.13089 2.45743 + vertex 1.46805 2.13281 2.45517 + vertex 1.46519 2.13134 2.45708 + endloop + endfacet + facet normal 0.149209 0.904014 0.400619 + outer loop + vertex 1.46519 2.13134 2.45708 + vertex 1.46089 2.13141 2.45851 + vertex 1.46489 2.12971 2.46086 + endloop + endfacet + facet normal 0.0539984 0.915755 0.398092 + outer loop + vertex 1.46519 2.13134 2.45708 + vertex 1.46489 2.12971 2.46086 + vertex 1.47011 2.13089 2.45743 + endloop + endfacet + facet normal 0.148163 0.843398 0.516457 + outer loop + vertex 1.47011 2.13089 2.45743 + vertex 1.46489 2.12971 2.46086 + vertex 1.46872 2.12901 2.4609 + endloop + endfacet + facet normal 0.158828 0.89608 0.414505 + outer loop + vertex 1.46872 2.12901 2.4609 + vertex 1.46489 2.12971 2.46086 + vertex 1.46798 2.12767 2.46409 + endloop + endfacet + facet normal 0.164436 0.897208 0.409852 + outer loop + vertex 1.46798 2.12767 2.46409 + vertex 1.46489 2.12971 2.46086 + vertex 1.46274 2.12807 2.46531 + endloop + endfacet + facet normal 0.168139 0.846761 0.504703 + outer loop + vertex 1.46578 2.12603 2.46772 + vertex 1.46274 2.12807 2.46531 + vertex 1.4611 2.12636 2.46873 + endloop + endfacet + facet normal 0.180248 0.851093 0.493104 + outer loop + vertex 1.46798 2.12767 2.46409 + vertex 1.46274 2.12807 2.46531 + vertex 1.46578 2.12603 2.46772 + endloop + endfacet + facet normal 0.115085 0.694776 0.709959 + outer loop + vertex 1.46805 2.13281 2.45517 + vertex 1.46321 2.13355 2.45523 + vertex 1.46519 2.13134 2.45708 + endloop + endfacet + facet normal 0.0175506 0.0360994 0.999194 + outer loop + vertex 1.46805 2.13281 2.45517 + vertex 1.47 2.13669 2.455 + vertex 1.46321 2.13355 2.45523 + endloop + endfacet + facet normal 0.004275 0.0647315 0.997894 + outer loop + vertex 1.47 2.13669 2.455 + vertex 1.465 2.13702 2.455 + vertex 1.46321 2.13355 2.45523 + endloop + endfacet + facet normal 0.225487 0.7346 0.639936 + outer loop + vertex 1.46519 2.13134 2.45708 + vertex 1.46321 2.13355 2.45523 + vertex 1.46089 2.13141 2.45851 + endloop + endfacet + facet normal 0.190371 -0.563304 0.804019 + outer loop + vertex 1.47155 0.898529 2.45581 + vertex 1.475 0.898536 2.455 + vertex 1.47575 0.898978 2.45513 + endloop + endfacet + facet normal 0.137063 -0.806212 0.575531 + outer loop + vertex 1.47155 0.898529 2.45581 + vertex 1.46765 0.897609 2.45545 + vertex 1.475 0.898536 2.455 + endloop + endfacet + facet normal 0.125948 -0.621635 0.773115 + outer loop + vertex 1.46765 0.897609 2.45545 + vertex 1.47 0.897523 2.455 + vertex 1.475 0.898536 2.455 + endloop + endfacet + facet normal 0.172443 -0.893251 0.415169 + outer loop + vertex 1.47155 0.898529 2.45581 + vertex 1.46863 0.898796 2.4576 + vertex 1.46765 0.897609 2.45545 + endloop + endfacet + facet normal 0.162464 -0.896318 0.412576 + outer loop + vertex 1.47575 0.898978 2.45513 + vertex 1.47264 0.899924 2.45841 + vertex 1.47155 0.898529 2.45581 + endloop + endfacet + facet normal 0.168913 -0.896366 0.409874 + outer loop + vertex 1.46863 0.898796 2.4576 + vertex 1.47155 0.898529 2.45581 + vertex 1.47264 0.899924 2.45841 + endloop + endfacet + facet normal 0.160137 -0.884913 0.437362 + outer loop + vertex 1.46863 0.898796 2.4576 + vertex 1.47264 0.899924 2.45841 + vertex 1.46763 0.900173 2.46075 + endloop + endfacet + facet normal 0.173731 -0.868253 0.464708 + outer loop + vertex 1.46763 0.900173 2.46075 + vertex 1.47264 0.899924 2.45841 + vertex 1.47126 0.901995 2.4628 + endloop + endfacet + facet normal 0.111288 -0.818929 0.563001 + outer loop + vertex 1.47088 0.904574 2.46662 + vertex 1.47126 0.901995 2.4628 + vertex 1.47456 0.903723 2.46466 + endloop + endfacet + facet normal 0.164269 -0.810318 0.562494 + outer loop + vertex 1.47088 0.904574 2.46662 + vertex 1.46625 0.902455 2.46492 + vertex 1.47126 0.901995 2.4628 + endloop + endfacet + facet normal 0.138485 -0.848901 0.510087 + outer loop + vertex 1.46625 0.902455 2.46492 + vertex 1.46763 0.900173 2.46075 + vertex 1.47126 0.901995 2.4628 + endloop + endfacet + facet normal 0.131103 -0.778773 0.613453 + outer loop + vertex 1.47088 0.904574 2.46662 + vertex 1.46714 0.905005 2.46797 + vertex 1.46625 0.902455 2.46492 + endloop + endfacet + facet normal 0.127713 -0.80038 0.585731 + outer loop + vertex 1.47456 0.903723 2.46466 + vertex 1.47395 0.9052 2.46681 + vertex 1.47088 0.904574 2.46662 + endloop + endfacet + facet normal 0.131071 -0.684595 0.717043 + outer loop + vertex 1.46714 0.905005 2.46797 + vertex 1.46972 0.907198 2.46959 + vertex 1.46571 0.907109 2.47024 + endloop + endfacet + facet normal 0.166645 -0.705579 0.688758 + outer loop + vertex 1.47088 0.904574 2.46662 + vertex 1.46972 0.907198 2.46959 + vertex 1.46714 0.905005 2.46797 + endloop + endfacet + facet normal 0.13467 -0.71573 0.68527 + outer loop + vertex 1.47088 0.904574 2.46662 + vertex 1.47402 0.907262 2.46881 + vertex 1.46972 0.907198 2.46959 + endloop + endfacet + facet normal 0.0988141 -0.695371 0.711825 + outer loop + vertex 1.47088 0.904574 2.46662 + vertex 1.47395 0.9052 2.46681 + vertex 1.47402 0.907262 2.46881 + endloop + endfacet + facet normal 0.14099 -0.595669 0.790759 + outer loop + vertex 1.46972 0.907198 2.46959 + vertex 1.46883 0.91014 2.47197 + vertex 1.46571 0.907109 2.47024 + endloop + endfacet + facet normal 0.148158 -0.624106 0.767164 + outer loop + vertex 1.47402 0.907262 2.46881 + vertex 1.47235 0.909686 2.47111 + vertex 1.46972 0.907198 2.46959 + endloop + endfacet + facet normal 0.114888 -0.602665 0.789681 + outer loop + vertex 1.47235 0.909686 2.47111 + vertex 1.46883 0.91014 2.47197 + vertex 1.46972 0.907198 2.46959 + endloop + endfacet + facet normal 0.139868 -0.515111 0.845635 + outer loop + vertex 1.47235 0.909686 2.47111 + vertex 1.47345 0.91338 2.47318 + vertex 1.46883 0.91014 2.47197 + endloop + endfacet + facet normal 0.120265 -0.493136 0.861599 + outer loop + vertex 1.47345 0.91338 2.47318 + vertex 1.46804 0.913927 2.47425 + vertex 1.46883 0.91014 2.47197 + endloop + endfacet + facet normal 0.141519 -0.346936 0.92715 + outer loop + vertex 1.46937 0.992815 2.50066 + vertex 1.46887 0.995536 2.50175 + vertex 1.46556 0.991781 2.50086 + endloop + endfacet + facet normal 0.140626 -0.347127 0.927215 + outer loop + vertex 1.47205 0.995316 2.50119 + vertex 1.46887 0.995536 2.50175 + vertex 1.46937 0.992815 2.50066 + endloop + endfacet + facet normal -0.0890189 0.872772 0.479942 + outer loop + vertex 1.475 1.00957 2.49 + vertex 1.47 1.00906 2.49 + vertex 1.47362 1.00817 2.4923 + endloop + endfacet + facet normal -0.120177 0.846438 0.518748 + outer loop + vertex 1.47362 1.00817 2.4923 + vertex 1.47 1.00906 2.49 + vertex 1.46847 1.00742 2.49233 + endloop + endfacet + facet normal -0.134118 0.935605 0.326582 + outer loop + vertex 1.47362 1.00817 2.4923 + vertex 1.46847 1.00742 2.49233 + vertex 1.47297 1.00669 2.49625 + endloop + endfacet + facet normal -0.103236 0.950237 0.293926 + outer loop + vertex 1.47297 1.00669 2.49625 + vertex 1.46847 1.00742 2.49233 + vertex 1.46789 1.00615 2.49623 + endloop + endfacet + facet normal -0.0964764 0.881375 0.462461 + outer loop + vertex 1.47297 1.00669 2.49625 + vertex 1.46789 1.00615 2.49623 + vertex 1.4723 1.00483 2.49966 + endloop + endfacet + facet normal -0.044126 0.912368 0.406985 + outer loop + vertex 1.4723 1.00483 2.49966 + vertex 1.46789 1.00615 2.49623 + vertex 1.46713 1.0045 2.49985 + endloop + endfacet + facet normal 0.0180856 0.667663 0.744244 + outer loop + vertex 1.47067 1.0022 2.50182 + vertex 1.46713 1.0045 2.49985 + vertex 1.46552 1.00196 2.50216 + endloop + endfacet + facet normal -0.0129477 0.640175 0.76812 + outer loop + vertex 1.4723 1.00483 2.49966 + vertex 1.46713 1.0045 2.49985 + vertex 1.47067 1.0022 2.50182 + endloop + endfacet + facet normal -0.00841104 -0.524977 -0.851075 + outer loop + vertex 1.475 2.02204 2.49 + vertex 1.473 2.01947 2.4916 + vertex 1.47 2.02212 2.49 + endloop + endfacet + facet normal -0.155668 -0.634782 -0.756848 + outer loop + vertex 1.473 2.01947 2.4916 + vertex 1.46821 2.01997 2.49218 + vertex 1.47 2.02212 2.49 + endloop + endfacet + facet normal -0.109496 -0.99189 -0.0645306 + outer loop + vertex 1.473 2.01947 2.4916 + vertex 1.47233 2.01927 2.49592 + vertex 1.46821 2.01997 2.49218 + endloop + endfacet + facet normal -0.105995 -0.992011 -0.068412 + outer loop + vertex 1.47233 2.01927 2.49592 + vertex 1.46713 2.01978 2.49651 + vertex 1.46821 2.01997 2.49218 + endloop + endfacet + facet normal -0.0623063 -0.956336 0.285552 + outer loop + vertex 1.47233 2.01927 2.49592 + vertex 1.47087 2.02072 2.50046 + vertex 1.46713 2.01978 2.49651 + endloop + endfacet + facet normal 0.0260888 -0.977987 0.207029 + outer loop + vertex 1.47087 2.02072 2.50046 + vertex 1.46509 2.02073 2.50124 + vertex 1.46713 2.01978 2.49651 + endloop + endfacet + facet normal 0.0920113 -0.713268 0.694826 + outer loop + vertex 1.47087 2.02072 2.50046 + vertex 1.46811 2.02373 2.50392 + vertex 1.46509 2.02073 2.50124 + endloop + endfacet + facet normal 0.0169996 -0.74711 0.664483 + outer loop + vertex 1.47432 2.02284 2.50276 + vertex 1.46811 2.02373 2.50392 + vertex 1.47087 2.02072 2.50046 + endloop + endfacet + facet normal 0.132104 0.487633 0.862996 + outer loop + vertex 1.47264 2.11593 2.4745 + vertex 1.47177 2.11997 2.47235 + vertex 1.46779 2.11737 2.47443 + endloop + endfacet + facet normal 0.127238 0.493168 0.860579 + outer loop + vertex 1.46779 2.11737 2.47443 + vertex 1.47177 2.11997 2.47235 + vertex 1.46611 2.12108 2.47255 + endloop + endfacet + facet normal 0.167249 0.850334 0.498958 + outer loop + vertex 1.4732 2.12497 2.46722 + vertex 1.47177 2.12664 2.46485 + vertex 1.46966 2.12586 2.46688 + endloop + endfacet + facet normal 0.166721 0.768011 0.618355 + outer loop + vertex 1.46966 2.12586 2.46688 + vertex 1.46578 2.12603 2.46772 + vertex 1.46929 2.12363 2.46976 + endloop + endfacet + facet normal 0.136667 0.773595 0.618768 + outer loop + vertex 1.46966 2.12586 2.46688 + vertex 1.46929 2.12363 2.46976 + vertex 1.4732 2.12497 2.46722 + endloop + endfacet + facet normal 0.145058 0.765206 0.627231 + outer loop + vertex 1.4732 2.12497 2.46722 + vertex 1.46929 2.12363 2.46976 + vertex 1.47438 2.12267 2.46975 + endloop + endfacet + facet normal 0.151917 0.637507 0.755318 + outer loop + vertex 1.47177 2.11997 2.47235 + vertex 1.46929 2.12363 2.46976 + vertex 1.46611 2.12108 2.47255 + endloop + endfacet + facet normal 0.119098 0.626035 0.770646 + outer loop + vertex 1.47438 2.12267 2.46975 + vertex 1.46929 2.12363 2.46976 + vertex 1.47177 2.11997 2.47235 + endloop + endfacet + facet normal -0.18991 0.656093 0.730394 + outer loop + vertex 1.47494 2.135 2.455 + vertex 1.46805 2.13281 2.45517 + vertex 1.47011 2.13089 2.45743 + endloop + endfacet + facet normal 0.172085 0.34417 0.923003 + outer loop + vertex 1.47494 2.135 2.455 + vertex 1.47011 2.13089 2.45743 + vertex 1.475 2.13497 2.455 + endloop + endfacet + facet normal 0.0543104 0.462748 0.884825 + outer loop + vertex 1.475 2.13497 2.455 + vertex 1.47011 2.13089 2.45743 + vertex 1.47439 2.12983 2.45772 + endloop + endfacet + facet normal 0.177035 0.850199 0.495802 + outer loop + vertex 1.47439 2.12983 2.45772 + vertex 1.47011 2.13089 2.45743 + vertex 1.47219 2.12819 2.46132 + endloop + endfacet + facet normal 0.138042 0.846537 0.51412 + outer loop + vertex 1.47219 2.12819 2.46132 + vertex 1.47011 2.13089 2.45743 + vertex 1.46872 2.12901 2.4609 + endloop + endfacet + facet normal 0.139672 0.867672 0.477113 + outer loop + vertex 1.47177 2.12664 2.46485 + vertex 1.46798 2.12767 2.46409 + vertex 1.46966 2.12586 2.46688 + endloop + endfacet + facet normal 0.160275 0.896523 0.412988 + outer loop + vertex 1.47177 2.12664 2.46485 + vertex 1.47219 2.12819 2.46132 + vertex 1.46798 2.12767 2.46409 + endloop + endfacet + facet normal 0.161659 0.8954 0.41488 + outer loop + vertex 1.47219 2.12819 2.46132 + vertex 1.46872 2.12901 2.4609 + vertex 1.46798 2.12767 2.46409 + endloop + endfacet + facet normal 0.140616 0.867791 0.47662 + outer loop + vertex 1.46966 2.12586 2.46688 + vertex 1.46798 2.12767 2.46409 + vertex 1.46578 2.12603 2.46772 + endloop + endfacet + facet normal 0.0131117 0.0383277 0.999179 + outer loop + vertex 1.47494 2.135 2.455 + vertex 1.47 2.13669 2.455 + vertex 1.46805 2.13281 2.45517 + endloop + endfacet + facet normal 0.0540377 -0.369138 0.927802 + outer loop + vertex 1.48 0.899268 2.455 + vertex 1.47575 0.898978 2.45513 + vertex 1.475 0.898536 2.455 + endloop + endfacet + facet normal -0.0652702 0.994261 0.0847658 + outer loop + vertex 1.48015 0.899333 2.45435 + vertex 1.47575 0.898978 2.45513 + vertex 1.48 0.899268 2.455 + endloop + endfacet + facet normal 0.145352 -0.900119 0.41068 + outer loop + vertex 1.47575 0.898978 2.45513 + vertex 1.48015 0.899333 2.45435 + vertex 1.47882 0.900193 2.45671 + endloop + endfacet + facet normal 0.150356 -0.902777 0.402973 + outer loop + vertex 1.47264 0.899924 2.45841 + vertex 1.47575 0.898978 2.45513 + vertex 1.47882 0.900193 2.45671 + endloop + endfacet + facet normal 0.1594 -0.884393 0.43868 + outer loop + vertex 1.47882 0.900193 2.45671 + vertex 1.47614 0.901819 2.46096 + vertex 1.47264 0.899924 2.45841 + endloop + endfacet + facet normal 0.141014 -0.877344 0.458675 + outer loop + vertex 1.47614 0.901819 2.46096 + vertex 1.47126 0.901995 2.4628 + vertex 1.47264 0.899924 2.45841 + endloop + endfacet + facet normal 0.159466 -0.848291 0.504949 + outer loop + vertex 1.47614 0.901819 2.46096 + vertex 1.47456 0.903723 2.46466 + vertex 1.47126 0.901995 2.4628 + endloop + endfacet + facet normal 0.154545 -0.849947 0.503692 + outer loop + vertex 1.47891 0.903777 2.46342 + vertex 1.47456 0.903723 2.46466 + vertex 1.47614 0.901819 2.46096 + endloop + endfacet + facet normal 0.178041 -0.788653 0.588497 + outer loop + vertex 1.47456 0.903723 2.46466 + vertex 1.47891 0.903777 2.46342 + vertex 1.47696 0.905648 2.46651 + endloop + endfacet + facet normal 0.175714 -0.787678 0.590499 + outer loop + vertex 1.47395 0.9052 2.46681 + vertex 1.47456 0.903723 2.46466 + vertex 1.47696 0.905648 2.46651 + endloop + endfacet + facet normal 0.172233 -0.689653 0.703359 + outer loop + vertex 1.47696 0.905648 2.46651 + vertex 1.47402 0.907262 2.46881 + vertex 1.47395 0.9052 2.46681 + endloop + endfacet + facet normal 0.164279 -0.69678 0.698219 + outer loop + vertex 1.47895 0.908352 2.46874 + vertex 1.47402 0.907262 2.46881 + vertex 1.47696 0.905648 2.46651 + endloop + endfacet + facet normal 0.146964 -0.613411 0.775969 + outer loop + vertex 1.47402 0.907262 2.46881 + vertex 1.47895 0.908352 2.46874 + vertex 1.4764 0.910753 2.47112 + endloop + endfacet + facet normal 0.160111 -0.618143 0.769587 + outer loop + vertex 1.47235 0.909686 2.47111 + vertex 1.47402 0.907262 2.46881 + vertex 1.4764 0.910753 2.47112 + endloop + endfacet + facet normal 0.132415 -0.513953 0.847537 + outer loop + vertex 1.4764 0.910753 2.47112 + vertex 1.47345 0.91338 2.47318 + vertex 1.47235 0.909686 2.47111 + endloop + endfacet + facet normal 0.137893 -0.50931 0.849464 + outer loop + vertex 1.4792 0.914549 2.47295 + vertex 1.47345 0.91338 2.47318 + vertex 1.4764 0.910753 2.47112 + endloop + endfacet + facet normal -0.171956 0.583849 0.793443 + outer loop + vertex 1.47653 1.00901 2.49075 + vertex 1.47646 1.01 2.49 + vertex 1.475 1.00957 2.49 + endloop + endfacet + facet normal 0.0460934 0.839775 0.540975 + outer loop + vertex 1.47362 1.00817 2.4923 + vertex 1.47653 1.00901 2.49075 + vertex 1.475 1.00957 2.49 + endloop + endfacet + facet normal -0.155941 0.960985 0.228453 + outer loop + vertex 1.47739 1.00852 2.49339 + vertex 1.47653 1.00901 2.49075 + vertex 1.47362 1.00817 2.4923 + endloop + endfacet + facet normal -0.18 0.929393 0.322224 + outer loop + vertex 1.47739 1.00852 2.49339 + vertex 1.47362 1.00817 2.4923 + vertex 1.47788 1.00753 2.49652 + endloop + endfacet + facet normal -0.175731 0.931579 0.318244 + outer loop + vertex 1.47788 1.00753 2.49652 + vertex 1.47362 1.00817 2.4923 + vertex 1.47297 1.00669 2.49625 + endloop + endfacet + facet normal -0.16974 0.826448 0.536817 + outer loop + vertex 1.47788 1.00753 2.49652 + vertex 1.47297 1.00669 2.49625 + vertex 1.4775 1.00546 2.49959 + endloop + endfacet + facet normal -0.09957 0.881356 0.461842 + outer loop + vertex 1.4775 1.00546 2.49959 + vertex 1.47297 1.00669 2.49625 + vertex 1.4723 1.00483 2.49966 + endloop + endfacet + facet normal -0.00505973 0.637322 0.770581 + outer loop + vertex 1.47607 1.00266 2.50148 + vertex 1.4723 1.00483 2.49966 + vertex 1.47067 1.0022 2.50182 + endloop + endfacet + facet normal -0.058633 0.579668 0.81274 + outer loop + vertex 1.4775 1.00546 2.49959 + vertex 1.4723 1.00483 2.49966 + vertex 1.47607 1.00266 2.50148 + endloop + endfacet + facet normal 0.142362 0.756898 0.637839 + outer loop + vertex 1.48 1.01 2.48921 + vertex 1.47646 1.01 2.49 + vertex 1.47959 1.00943 2.48998 + endloop + endfacet + facet normal -0.107318 0.987622 0.114393 + outer loop + vertex 1.47959 1.00943 2.48998 + vertex 1.47653 1.00901 2.49075 + vertex 1.47986 1.00913 2.49281 + endloop + endfacet + facet normal 0.114731 0.600874 0.791067 + outer loop + vertex 1.47646 1.01 2.49 + vertex 1.47653 1.00901 2.49075 + vertex 1.47959 1.00943 2.48998 + endloop + endfacet + facet normal -0.18126 0.954794 0.235613 + outer loop + vertex 1.47986 1.00913 2.49281 + vertex 1.47653 1.00901 2.49075 + vertex 1.47739 1.00852 2.49339 + endloop + endfacet + facet normal -0.0044622 -0.223339 -0.974731 + outer loop + vertex 1.48 2.02194 2.49 + vertex 1.47687 2.01919 2.49064 + vertex 1.475 2.02204 2.49 + endloop + endfacet + facet normal -0.248892 -0.365945 -0.896737 + outer loop + vertex 1.47687 2.01919 2.49064 + vertex 1.473 2.01947 2.4916 + vertex 1.475 2.02204 2.49 + endloop + endfacet + facet normal -0.131401 -0.960015 -0.247196 + outer loop + vertex 1.47687 2.01919 2.49064 + vertex 1.47749 2.01814 2.49438 + vertex 1.473 2.01947 2.4916 + endloop + endfacet + facet normal -0.235525 -0.968336 -0.0827857 + outer loop + vertex 1.47749 2.01814 2.49438 + vertex 1.47233 2.01927 2.49592 + vertex 1.473 2.01947 2.4916 + endloop + endfacet + facet normal -0.139958 -0.962388 0.232855 + outer loop + vertex 1.47749 2.01814 2.49438 + vertex 1.4768 2.01954 2.49975 + vertex 1.47233 2.01927 2.49592 + endloop + endfacet + facet normal -0.158393 -0.954203 0.253787 + outer loop + vertex 1.4768 2.01954 2.49975 + vertex 1.47087 2.02072 2.50046 + vertex 1.47233 2.01927 2.49592 + endloop + endfacet + facet normal -0.0509172 -0.694349 0.717835 + outer loop + vertex 1.4768 2.01954 2.49975 + vertex 1.47432 2.02284 2.50276 + vertex 1.47087 2.02072 2.50046 + endloop + endfacet + facet normal -0.104045 -0.712495 0.693921 + outer loop + vertex 1.4797 2.02192 2.50263 + vertex 1.47432 2.02284 2.50276 + vertex 1.4768 2.01954 2.49975 + endloop + endfacet + facet normal 0.15796 0.63559 0.755694 + outer loop + vertex 1.47937 2.11982 2.47132 + vertex 1.47787 2.12197 2.46983 + vertex 1.4759 2.12059 2.4714 + endloop + endfacet + facet normal 0.135407 0.524318 0.840687 + outer loop + vertex 1.4759 2.12059 2.4714 + vertex 1.47629 2.11788 2.47303 + vertex 1.47937 2.11982 2.47132 + endloop + endfacet + facet normal 0.115415 0.52349 0.844179 + outer loop + vertex 1.4759 2.12059 2.4714 + vertex 1.47177 2.11997 2.47235 + vertex 1.47629 2.11788 2.47303 + endloop + endfacet + facet normal 0.0928834 0.483227 0.870554 + outer loop + vertex 1.47177 2.11997 2.47235 + vertex 1.47264 2.11593 2.4745 + vertex 1.47629 2.11788 2.47303 + endloop + endfacet + facet normal 0.164825 0.856422 0.489259 + outer loop + vertex 1.4732 2.12497 2.46722 + vertex 1.47818 2.12411 2.46706 + vertex 1.47551 2.12632 2.46408 + endloop + endfacet + facet normal 0.175281 0.851197 0.494712 + outer loop + vertex 1.47177 2.12664 2.46485 + vertex 1.4732 2.12497 2.46722 + vertex 1.47551 2.12632 2.46408 + endloop + endfacet + facet normal 0.118147 0.668218 0.734524 + outer loop + vertex 1.47787 2.12197 2.46983 + vertex 1.47438 2.12267 2.46975 + vertex 1.4759 2.12059 2.4714 + endloop + endfacet + facet normal 0.142272 0.776488 0.613861 + outer loop + vertex 1.47787 2.12197 2.46983 + vertex 1.47818 2.12411 2.46706 + vertex 1.47438 2.12267 2.46975 + endloop + endfacet + facet normal 0.153481 0.766099 0.624128 + outer loop + vertex 1.47818 2.12411 2.46706 + vertex 1.4732 2.12497 2.46722 + vertex 1.47438 2.12267 2.46975 + endloop + endfacet + facet normal 0.0752344 0.652436 0.7541 + outer loop + vertex 1.4759 2.12059 2.4714 + vertex 1.47438 2.12267 2.46975 + vertex 1.47177 2.11997 2.47235 + endloop + endfacet + facet normal 0.14362 0.370151 0.917803 + outer loop + vertex 1.48 2.13303 2.455 + vertex 1.475 2.13497 2.455 + vertex 1.47826 2.12983 2.45656 + endloop + endfacet + facet normal 0.260191 0.428085 0.865473 + outer loop + vertex 1.47826 2.12983 2.45656 + vertex 1.475 2.13497 2.455 + vertex 1.47439 2.12983 2.45772 + endloop + endfacet + facet normal 0.156577 0.841333 0.517342 + outer loop + vertex 1.47826 2.12983 2.45656 + vertex 1.47439 2.12983 2.45772 + vertex 1.47711 2.12778 2.46025 + endloop + endfacet + facet normal 0.180693 0.848559 0.497291 + outer loop + vertex 1.47711 2.12778 2.46025 + vertex 1.47439 2.12983 2.45772 + vertex 1.47219 2.12819 2.46132 + endloop + endfacet + facet normal 0.162323 0.896122 0.413058 + outer loop + vertex 1.47551 2.12632 2.46408 + vertex 1.47219 2.12819 2.46132 + vertex 1.47177 2.12664 2.46485 + endloop + endfacet + facet normal 0.165642 0.89706 0.40969 + outer loop + vertex 1.47711 2.12778 2.46025 + vertex 1.47219 2.12819 2.46132 + vertex 1.47551 2.12632 2.46408 + endloop + endfacet + facet normal 0.110483 -0.701832 -0.703723 + outer loop + vertex 1.48465 0.9 2.455 + vertex 1.48 0.899268 2.455 + vertex 1.48 0.9 2.45427 + endloop + endfacet + facet normal -0.155191 0.985835 0.0635991 + outer loop + vertex 1.48465 0.9 2.455 + vertex 1.48015 0.899333 2.45435 + vertex 1.48 0.899268 2.455 + endloop + endfacet + facet normal -0.193025 0.877278 0.43946 + outer loop + vertex 1.48015 0.899333 2.45435 + vertex 1.48465 0.9 2.455 + vertex 1.485 0.900077 2.455 + endloop + endfacet + facet normal 0.0894498 -0.918225 0.385827 + outer loop + vertex 1.48015 0.899333 2.45435 + vertex 1.485 0.900077 2.455 + vertex 1.47882 0.900193 2.45671 + endloop + endfacet + facet normal 0.139655 -0.81623 0.560594 + outer loop + vertex 1.47882 0.900193 2.45671 + vertex 1.485 0.900077 2.455 + vertex 1.48263 0.900739 2.45656 + endloop + endfacet + facet normal 0.14493 -0.886533 0.439381 + outer loop + vertex 1.48263 0.900739 2.45656 + vertex 1.48138 0.902008 2.45953 + vertex 1.47882 0.900193 2.45671 + endloop + endfacet + facet normal 0.151004 -0.887823 0.434705 + outer loop + vertex 1.48138 0.902008 2.45953 + vertex 1.47614 0.901819 2.46096 + vertex 1.47882 0.900193 2.45671 + endloop + endfacet + facet normal 0.165948 -0.853606 0.49378 + outer loop + vertex 1.48138 0.902008 2.45953 + vertex 1.47891 0.903777 2.46342 + vertex 1.47614 0.901819 2.46096 + endloop + endfacet + facet normal 0.152019 -0.859678 0.487693 + outer loop + vertex 1.48274 0.903899 2.46244 + vertex 1.47891 0.903777 2.46342 + vertex 1.48138 0.902008 2.45953 + endloop + endfacet + facet normal 0.175092 -0.79086 0.586416 + outer loop + vertex 1.47891 0.903777 2.46342 + vertex 1.48274 0.903899 2.46244 + vertex 1.48204 0.906108 2.46562 + endloop + endfacet + facet normal 0.174245 -0.790465 0.587201 + outer loop + vertex 1.47696 0.905648 2.46651 + vertex 1.47891 0.903777 2.46342 + vertex 1.48204 0.906108 2.46562 + endloop + endfacet + facet normal 0.183835 -0.70245 0.687581 + outer loop + vertex 1.48204 0.906108 2.46562 + vertex 1.47895 0.908352 2.46874 + vertex 1.47696 0.905648 2.46651 + endloop + endfacet + facet normal 0.164012 -0.716476 0.678057 + outer loop + vertex 1.48368 0.909182 2.46848 + vertex 1.47895 0.908352 2.46874 + vertex 1.48204 0.906108 2.46562 + endloop + endfacet + facet normal 0.151416 -0.613829 0.774782 + outer loop + vertex 1.47895 0.908352 2.46874 + vertex 1.48368 0.909182 2.46848 + vertex 1.48127 0.911611 2.47087 + endloop + endfacet + facet normal 0.14816 -0.612572 0.776405 + outer loop + vertex 1.4764 0.910753 2.47112 + vertex 1.47895 0.908352 2.46874 + vertex 1.48127 0.911611 2.47087 + endloop + endfacet + facet normal 0.13347 -0.507043 0.851524 + outer loop + vertex 1.48127 0.911611 2.47087 + vertex 1.4792 0.914549 2.47295 + vertex 1.4764 0.910753 2.47112 + endloop + endfacet + facet normal 0.133597 -0.506969 0.851548 + outer loop + vertex 1.48427 0.915132 2.4725 + vertex 1.4792 0.914549 2.47295 + vertex 1.48127 0.911611 2.47087 + endloop + endfacet + facet normal 0.127595 -0.417685 0.899588 + outer loop + vertex 1.48427 0.915132 2.4725 + vertex 1.48299 0.918933 2.47444 + vertex 1.4792 0.914549 2.47295 + endloop + endfacet + facet normal -0.273615 0.903912 0.328753 + outer loop + vertex 1.47999 1.00856 2.49543 + vertex 1.47739 1.00852 2.49339 + vertex 1.47788 1.00753 2.49652 + endloop + endfacet + facet normal -0.252077 0.896783 0.363646 + outer loop + vertex 1.48159 1.00807 2.49775 + vertex 1.47999 1.00856 2.49543 + vertex 1.47788 1.00753 2.49652 + endloop + endfacet + facet normal -0.305283 0.746611 0.591079 + outer loop + vertex 1.48159 1.00807 2.49775 + vertex 1.47788 1.00753 2.49652 + vertex 1.48189 1.00666 2.49969 + endloop + endfacet + facet normal -0.236157 0.818671 0.523458 + outer loop + vertex 1.48189 1.00666 2.49969 + vertex 1.47788 1.00753 2.49652 + vertex 1.4775 1.00546 2.49959 + endloop + endfacet + facet normal -0.0627703 0.580958 0.811509 + outer loop + vertex 1.4824 1.0035 2.50137 + vertex 1.4775 1.00546 2.49959 + vertex 1.47607 1.00266 2.50148 + endloop + endfacet + facet normal -0.14285 0.445979 0.883571 + outer loop + vertex 1.48189 1.00666 2.49969 + vertex 1.4775 1.00546 2.49959 + vertex 1.4824 1.0035 2.50137 + endloop + endfacet + facet normal 0.0497906 0.510048 0.858704 + outer loop + vertex 1.48 1.01 2.48921 + vertex 1.48363 1.00972 2.48916 + vertex 1.485 1.01 2.48892 + endloop + endfacet + facet normal 0.0677772 0.783446 0.617753 + outer loop + vertex 1.47959 1.00943 2.48998 + vertex 1.48363 1.00972 2.48916 + vertex 1.48 1.01 2.48921 + endloop + endfacet + facet normal -0.0732131 0.99731 -0.00341162 + outer loop + vertex 1.48363 1.00972 2.48916 + vertex 1.47959 1.00943 2.48998 + vertex 1.4835 1.00972 2.49248 + endloop + endfacet + facet normal -0.149579 0.98171 0.117775 + outer loop + vertex 1.4835 1.00972 2.49248 + vertex 1.47959 1.00943 2.48998 + vertex 1.47986 1.00913 2.49281 + endloop + endfacet + facet normal -0.186522 0.958255 0.216697 + outer loop + vertex 1.47999 1.00856 2.49543 + vertex 1.47986 1.00913 2.49281 + vertex 1.47739 1.00852 2.49339 + endloop + endfacet + facet normal -0.18085 0.959353 0.216647 + outer loop + vertex 1.47999 1.00856 2.49543 + vertex 1.48353 1.00903 2.49632 + vertex 1.47986 1.00913 2.49281 + endloop + endfacet + facet normal -0.14288 0.973721 0.17735 + outer loop + vertex 1.48353 1.00903 2.49632 + vertex 1.4835 1.00972 2.49248 + vertex 1.47986 1.00913 2.49281 + endloop + endfacet + facet normal -0.205897 0.918912 0.336463 + outer loop + vertex 1.48353 1.00903 2.49632 + vertex 1.47999 1.00856 2.49543 + vertex 1.48159 1.00807 2.49775 + endloop + endfacet + facet normal -0.286182 -0.95465 0.0821172 + outer loop + vertex 1.4847 2.01608 2.49665 + vertex 1.48088 2.01733 2.49798 + vertex 1.48159 2.01681 2.49439 + endloop + endfacet + facet normal -0.24424 -0.94939 0.197496 + outer loop + vertex 1.48347 2.0171 2.50003 + vertex 1.48088 2.01733 2.49798 + vertex 1.4847 2.01608 2.49665 + endloop + endfacet + facet normal -0.38265 -0.839975 0.384736 + outer loop + vertex 1.48103 2.01865 2.501 + vertex 1.48088 2.01733 2.49798 + vertex 1.48347 2.0171 2.50003 + endloop + endfacet + facet normal -0.153257 -0.684276 0.712936 + outer loop + vertex 1.48347 2.0171 2.50003 + vertex 1.48433 2.01923 2.50226 + vertex 1.48103 2.01865 2.501 + endloop + endfacet + facet normal -0.0880869 -0.284159 -0.954722 + outer loop + vertex 1.485 2.02039 2.49 + vertex 1.4811 2.01826 2.49099 + vertex 1.48 2.02194 2.49 + endloop + endfacet + facet normal 0.0239619 -0.2539 -0.966934 + outer loop + vertex 1.4811 2.01826 2.49099 + vertex 1.47687 2.01919 2.49064 + vertex 1.48 2.02194 2.49 + endloop + endfacet + facet normal -0.307938 -0.948296 0.0768672 + outer loop + vertex 1.48159 2.01681 2.49439 + vertex 1.48088 2.01733 2.49798 + vertex 1.47749 2.01814 2.49438 + endloop + endfacet + facet normal -0.289523 -0.894761 -0.33997 + outer loop + vertex 1.48159 2.01681 2.49439 + vertex 1.47749 2.01814 2.49438 + vertex 1.4811 2.01826 2.49099 + endloop + endfacet + facet normal -0.189534 -0.953198 -0.235563 + outer loop + vertex 1.4811 2.01826 2.49099 + vertex 1.47749 2.01814 2.49438 + vertex 1.47687 2.01919 2.49064 + endloop + endfacet + facet normal -0.299832 -0.869091 0.393422 + outer loop + vertex 1.48088 2.01733 2.49798 + vertex 1.48103 2.01865 2.501 + vertex 1.4768 2.01954 2.49975 + endloop + endfacet + facet normal -0.40614 -0.895686 0.1811 + outer loop + vertex 1.47749 2.01814 2.49438 + vertex 1.48088 2.01733 2.49798 + vertex 1.4768 2.01954 2.49975 + endloop + endfacet + facet normal -0.342094 -0.525292 0.779127 + outer loop + vertex 1.48103 2.01865 2.501 + vertex 1.4797 2.02192 2.50263 + vertex 1.4768 2.01954 2.49975 + endloop + endfacet + facet normal -0.229442 -0.505763 0.831601 + outer loop + vertex 1.48103 2.01865 2.501 + vertex 1.48433 2.01923 2.50226 + vertex 1.4797 2.02192 2.50263 + endloop + endfacet + facet normal -0.0635303 -0.239524 0.96881 + outer loop + vertex 1.48433 2.01923 2.50226 + vertex 1.4836 2.02282 2.5031 + vertex 1.4797 2.02192 2.50263 + endloop + endfacet + facet normal 0.15985 0.656045 0.7376 + outer loop + vertex 1.47937 2.11982 2.47132 + vertex 1.48389 2.11911 2.47097 + vertex 1.48165 2.12189 2.46898 + endloop + endfacet + facet normal 0.179197 0.642834 0.74475 + outer loop + vertex 1.47787 2.12197 2.46983 + vertex 1.47937 2.11982 2.47132 + vertex 1.48165 2.12189 2.46898 + endloop + endfacet + facet normal 0.142341 0.516539 0.84435 + outer loop + vertex 1.48094 2.11663 2.47301 + vertex 1.47937 2.11982 2.47132 + vertex 1.47629 2.11788 2.47303 + endloop + endfacet + facet normal 0.146154 0.517693 0.842991 + outer loop + vertex 1.48389 2.11911 2.47097 + vertex 1.47937 2.11982 2.47132 + vertex 1.48094 2.11663 2.47301 + endloop + endfacet + facet normal 0.138963 0.866044 0.480267 + outer loop + vertex 1.47818 2.12411 2.46706 + vertex 1.48414 2.12396 2.46559 + vertex 1.4803 2.12596 2.4631 + endloop + endfacet + facet normal 0.16459 0.856369 0.489431 + outer loop + vertex 1.47551 2.12632 2.46408 + vertex 1.47818 2.12411 2.46706 + vertex 1.4803 2.12596 2.4631 + endloop + endfacet + facet normal 0.152675 0.774672 0.613655 + outer loop + vertex 1.48165 2.12189 2.46898 + vertex 1.47818 2.12411 2.46706 + vertex 1.47787 2.12197 2.46983 + endloop + endfacet + facet normal 0.166223 0.783214 0.599121 + outer loop + vertex 1.48414 2.12396 2.46559 + vertex 1.47818 2.12411 2.46706 + vertex 1.48165 2.12189 2.46898 + endloop + endfacet + facet normal 0.0341352 0.213373 0.976374 + outer loop + vertex 1.485 2.13223 2.455 + vertex 1.48 2.13303 2.455 + vertex 1.4821 2.12954 2.45569 + endloop + endfacet + facet normal 0.233035 0.321554 0.917768 + outer loop + vertex 1.4821 2.12954 2.45569 + vertex 1.48 2.13303 2.455 + vertex 1.47826 2.12983 2.45656 + endloop + endfacet + facet normal 0.18158 0.831168 0.525536 + outer loop + vertex 1.4821 2.12954 2.45569 + vertex 1.47826 2.12983 2.45656 + vertex 1.48214 2.12747 2.45896 + endloop + endfacet + facet normal 0.185074 0.832894 0.52157 + outer loop + vertex 1.48214 2.12747 2.45896 + vertex 1.47826 2.12983 2.45656 + vertex 1.47711 2.12778 2.46025 + endloop + endfacet + facet normal 0.150776 0.901683 0.405259 + outer loop + vertex 1.4803 2.12596 2.4631 + vertex 1.47711 2.12778 2.46025 + vertex 1.47551 2.12632 2.46408 + endloop + endfacet + facet normal 0.15783 0.903487 0.398498 + outer loop + vertex 1.48214 2.12747 2.45896 + vertex 1.47711 2.12778 2.46025 + vertex 1.4803 2.12596 2.4631 + endloop + endfacet + facet normal 0.125909 -0.813337 0.568005 + outer loop + vertex 1.49 0.900851 2.455 + vertex 1.48612 0.901567 2.45688 + vertex 1.485 0.900077 2.455 + endloop + endfacet + facet normal 0.140273 -0.815646 0.561289 + outer loop + vertex 1.48612 0.901567 2.45688 + vertex 1.48263 0.900739 2.45656 + vertex 1.485 0.900077 2.455 + endloop + endfacet + facet normal 0.199439 -0.866142 0.458282 + outer loop + vertex 1.48507 0.903082 2.46021 + vertex 1.48612 0.901567 2.45688 + vertex 1.48895 0.903546 2.4594 + endloop + endfacet + facet normal 0.171129 -0.874807 0.453242 + outer loop + vertex 1.48507 0.903082 2.46021 + vertex 1.48138 0.902008 2.45953 + vertex 1.48612 0.901567 2.45688 + endloop + endfacet + facet normal 0.166346 -0.879707 0.445472 + outer loop + vertex 1.48138 0.902008 2.45953 + vertex 1.48263 0.900739 2.45656 + vertex 1.48612 0.901567 2.45688 + endloop + endfacet + facet normal 0.161258 -0.860229 0.483737 + outer loop + vertex 1.48507 0.903082 2.46021 + vertex 1.48274 0.903899 2.46244 + vertex 1.48138 0.902008 2.45953 + endloop + endfacet + facet normal 0.206642 -0.834471 0.51084 + outer loop + vertex 1.48895 0.903546 2.4594 + vertex 1.48622 0.904965 2.46282 + vertex 1.48507 0.903082 2.46021 + endloop + endfacet + facet normal 0.199281 -0.834329 0.513987 + outer loop + vertex 1.48274 0.903899 2.46244 + vertex 1.48507 0.903082 2.46021 + vertex 1.48622 0.904965 2.46282 + endloop + endfacet + facet normal 0.177819 -0.790166 0.58653 + outer loop + vertex 1.48274 0.903899 2.46244 + vertex 1.48622 0.904965 2.46282 + vertex 1.48204 0.906108 2.46562 + endloop + endfacet + facet normal 0.187387 -0.780251 0.596737 + outer loop + vertex 1.48204 0.906108 2.46562 + vertex 1.48622 0.904965 2.46282 + vertex 1.48695 0.907522 2.46593 + endloop + endfacet + facet normal 0.163926 -0.716463 0.678092 + outer loop + vertex 1.48695 0.907522 2.46593 + vertex 1.48368 0.909182 2.46848 + vertex 1.48204 0.906108 2.46562 + endloop + endfacet + facet normal 0.163127 -0.717176 0.67753 + outer loop + vertex 1.48739 0.909947 2.46839 + vertex 1.48368 0.909182 2.46848 + vertex 1.48695 0.907522 2.46593 + endloop + endfacet + facet normal 0.145349 -0.620831 0.770352 + outer loop + vertex 1.48368 0.909182 2.46848 + vertex 1.48739 0.909947 2.46839 + vertex 1.48578 0.912101 2.47043 + endloop + endfacet + facet normal 0.142475 -0.619722 0.771781 + outer loop + vertex 1.48127 0.911611 2.47087 + vertex 1.48368 0.909182 2.46848 + vertex 1.48578 0.912101 2.47043 + endloop + endfacet + facet normal 0.138001 -0.509655 0.849239 + outer loop + vertex 1.48578 0.912101 2.47043 + vertex 1.48427 0.915132 2.4725 + vertex 1.48127 0.911611 2.47087 + endloop + endfacet + facet normal 0.131944 -0.512252 0.848639 + outer loop + vertex 1.48882 0.91516 2.47181 + vertex 1.48427 0.915132 2.4725 + vertex 1.48578 0.912101 2.47043 + endloop + endfacet + facet normal 0.137954 -0.431432 0.891535 + outer loop + vertex 1.48882 0.91516 2.47181 + vertex 1.4881 0.918757 2.47366 + vertex 1.48427 0.915132 2.4725 + endloop + endfacet + facet normal 0.123714 -0.418967 0.899534 + outer loop + vertex 1.48427 0.915132 2.4725 + vertex 1.4881 0.918757 2.47366 + vertex 1.48299 0.918933 2.47444 + endloop + endfacet + facet normal 0.125453 -0.361142 0.924033 + outer loop + vertex 1.48433 0.922618 2.4757 + vertex 1.48055 0.92168 2.47585 + vertex 1.48299 0.918933 2.47444 + endloop + endfacet + facet normal 0.122199 -0.360233 0.924824 + outer loop + vertex 1.48433 0.922618 2.4757 + vertex 1.48299 0.918933 2.47444 + vertex 1.48749 0.922285 2.47515 + endloop + endfacet + facet normal 0.128727 -0.368142 0.920815 + outer loop + vertex 1.48749 0.922285 2.47515 + vertex 1.48299 0.918933 2.47444 + vertex 1.4881 0.918757 2.47366 + endloop + endfacet + facet normal 0.118385 -0.330813 0.936241 + outer loop + vertex 1.48433 0.922618 2.4757 + vertex 1.48379 0.925325 2.47673 + vertex 1.48055 0.92168 2.47585 + endloop + endfacet + facet normal 0.126248 -0.335867 0.93341 + outer loop + vertex 1.48749 0.922285 2.47515 + vertex 1.48694 0.92498 2.4762 + vertex 1.48433 0.922618 2.4757 + endloop + endfacet + facet normal 0.120711 -0.330309 0.936122 + outer loop + vertex 1.48694 0.92498 2.4762 + vertex 1.48379 0.925325 2.47673 + vertex 1.48433 0.922618 2.4757 + endloop + endfacet + facet normal 0.121702 -0.324284 0.938098 + outer loop + vertex 1.48694 0.92498 2.4762 + vertex 1.48851 0.928874 2.47734 + vertex 1.48379 0.925325 2.47673 + endloop + endfacet + facet normal 0.128103 -0.299075 0.945592 + outer loop + vertex 1.48421 0.967521 2.49072 + vertex 1.48045 0.966499 2.49091 + vertex 1.48267 0.963523 2.48967 + endloop + endfacet + facet normal 0.125979 -0.298387 0.946094 + outer loop + vertex 1.48421 0.967521 2.49072 + vertex 1.48267 0.963523 2.48967 + vertex 1.48749 0.967331 2.49023 + endloop + endfacet + facet normal 0.127757 -0.297717 0.946067 + outer loop + vertex 1.48421 0.967521 2.49072 + vertex 1.48373 0.970286 2.49166 + vertex 1.48045 0.966499 2.49091 + endloop + endfacet + facet normal 0.126261 -0.295664 0.946911 + outer loop + vertex 1.48749 0.967331 2.49023 + vertex 1.48688 0.970043 2.49116 + vertex 1.48421 0.967521 2.49072 + endloop + endfacet + facet normal 0.128252 -0.297619 0.946031 + outer loop + vertex 1.48688 0.970043 2.49116 + vertex 1.48373 0.970286 2.49166 + vertex 1.48421 0.967521 2.49072 + endloop + endfacet + facet normal 0.127707 -0.301975 0.944723 + outer loop + vertex 1.48688 0.970043 2.49116 + vertex 1.48847 0.973964 2.49219 + vertex 1.48373 0.970286 2.49166 + endloop + endfacet + facet normal 0.0016827 0.840208 -0.542262 + outer loop + vertex 1.49 1.00746 2.485 + vertex 1.485 1.00747 2.485 + vertex 1.485 1.01 2.48892 + endloop + endfacet + facet normal -0.669765 -0.227502 -0.706865 + outer loop + vertex 1.48943 1.00941 2.48491 + vertex 1.49 1.00746 2.485 + vertex 1.485 1.01 2.48892 + endloop + endfacet + facet normal -0.288376 0.752191 0.592493 + outer loop + vertex 1.48436 1.00796 2.49924 + vertex 1.48159 1.00807 2.49775 + vertex 1.48189 1.00666 2.49969 + endloop + endfacet + facet normal -0.196324 0.632548 0.749226 + outer loop + vertex 1.48189 1.00666 2.49969 + vertex 1.48633 1.00657 2.50092 + vertex 1.48436 1.00796 2.49924 + endloop + endfacet + facet normal -0.234622 0.426118 0.873714 + outer loop + vertex 1.48189 1.00666 2.49969 + vertex 1.4824 1.0035 2.50137 + vertex 1.48633 1.00657 2.50092 + endloop + endfacet + facet normal -0.163422 0.934142 -0.317289 + outer loop + vertex 1.485 1.01 2.48892 + vertex 1.48921 1.0103 2.48765 + vertex 1.48943 1.00941 2.48491 + endloop + endfacet + facet normal 0.260443 -0.662722 0.702118 + outer loop + vertex 1.48363 1.00972 2.48916 + vertex 1.48921 1.0103 2.48765 + vertex 1.485 1.01 2.48892 + endloop + endfacet + facet normal -0.114941 0.99249 -0.0418531 + outer loop + vertex 1.48921 1.0103 2.48765 + vertex 1.48363 1.00972 2.48916 + vertex 1.48807 1.01035 2.49194 + endloop + endfacet + facet normal -0.137101 0.990539 -0.00601041 + outer loop + vertex 1.48807 1.01035 2.49194 + vertex 1.48363 1.00972 2.48916 + vertex 1.4835 1.00972 2.49248 + endloop + endfacet + facet normal -0.121742 0.985467 0.11846 + outer loop + vertex 1.48807 1.01035 2.49194 + vertex 1.4835 1.00972 2.49248 + vertex 1.48798 1.00985 2.49606 + endloop + endfacet + facet normal -0.167898 0.969809 0.176866 + outer loop + vertex 1.48798 1.00985 2.49606 + vertex 1.4835 1.00972 2.49248 + vertex 1.48353 1.00903 2.49632 + endloop + endfacet + facet normal -0.168237 0.909038 0.381244 + outer loop + vertex 1.48436 1.00796 2.49924 + vertex 1.48353 1.00903 2.49632 + vertex 1.48159 1.00807 2.49775 + endloop + endfacet + facet normal -0.163689 0.910228 0.380382 + outer loop + vertex 1.48436 1.00796 2.49924 + vertex 1.48781 1.00856 2.49929 + vertex 1.48353 1.00903 2.49632 + endloop + endfacet + facet normal -0.14818 0.921204 0.359758 + outer loop + vertex 1.48781 1.00856 2.49929 + vertex 1.48798 1.00985 2.49606 + vertex 1.48353 1.00903 2.49632 + endloop + endfacet + facet normal -0.129819 0.686236 0.7157 + outer loop + vertex 1.48781 1.00856 2.49929 + vertex 1.48436 1.00796 2.49924 + vertex 1.48633 1.00657 2.50092 + endloop + endfacet + facet normal -0.322504 -0.722376 -0.611689 + outer loop + vertex 1.48815 2.01605 2.49328 + vertex 1.48552 2.02 2.49 + vertex 1.49 2.018 2.49 + endloop + endfacet + facet normal 0.0319029 -0.625967 -0.779197 + outer loop + vertex 1.48405 2.01673 2.49257 + vertex 1.48552 2.02 2.49 + vertex 1.48815 2.01605 2.49328 + endloop + endfacet + facet normal -0.134422 -0.981643 -0.13531 + outer loop + vertex 1.48405 2.01673 2.49257 + vertex 1.4847 2.01608 2.49665 + vertex 1.48159 2.01681 2.49439 + endloop + endfacet + facet normal -0.139623 -0.981044 -0.134384 + outer loop + vertex 1.48405 2.01673 2.49257 + vertex 1.48815 2.01605 2.49328 + vertex 1.4847 2.01608 2.49665 + endloop + endfacet + facet normal -0.119466 -0.986308 -0.113683 + outer loop + vertex 1.48815 2.01605 2.49328 + vertex 1.4885 2.01551 2.49759 + vertex 1.4847 2.01608 2.49665 + endloop + endfacet + facet normal -0.205652 -0.942812 0.262321 + outer loop + vertex 1.4885 2.01551 2.49759 + vertex 1.48676 2.01662 2.50023 + vertex 1.4847 2.01608 2.49665 + endloop + endfacet + facet normal -0.152122 -0.960209 0.234217 + outer loop + vertex 1.48676 2.01662 2.50023 + vertex 1.48347 2.0171 2.50003 + vertex 1.4847 2.01608 2.49665 + endloop + endfacet + facet normal -0.142016 -0.687759 0.711912 + outer loop + vertex 1.48676 2.01662 2.50023 + vertex 1.48433 2.01923 2.50226 + vertex 1.48347 2.0171 2.50003 + endloop + endfacet + facet normal -0.119455 -0.677514 0.725744 + outer loop + vertex 1.48903 2.01845 2.50231 + vertex 1.48433 2.01923 2.50226 + vertex 1.48676 2.01662 2.50023 + endloop + endfacet + facet normal 0.0781248 -0.637072 -0.766835 + outer loop + vertex 1.48552 2.02 2.49 + vertex 1.48405 2.01673 2.49257 + vertex 1.4811 2.01826 2.49099 + endloop + endfacet + facet normal -0.143163 -0.190855 -0.971123 + outer loop + vertex 1.485 2.02039 2.49 + vertex 1.48552 2.02 2.49 + vertex 1.4811 2.01826 2.49099 + endloop + endfacet + facet normal -0.284467 -0.895915 -0.341195 + outer loop + vertex 1.48405 2.01673 2.49257 + vertex 1.48159 2.01681 2.49439 + vertex 1.4811 2.01826 2.49099 + endloop + endfacet + facet normal -0.0488638 -0.237574 0.97014 + outer loop + vertex 1.48903 2.01845 2.50231 + vertex 1.48747 2.0217 2.50303 + vertex 1.48433 2.01923 2.50226 + endloop + endfacet + facet normal -0.0493698 -0.23697 0.970262 + outer loop + vertex 1.48433 2.01923 2.50226 + vertex 1.48747 2.0217 2.50303 + vertex 1.4836 2.02282 2.5031 + endloop + endfacet + facet normal 0.141378 0.657604 0.73998 + outer loop + vertex 1.48389 2.11911 2.47097 + vertex 1.48884 2.11834 2.47071 + vertex 1.48655 2.12128 2.46853 + endloop + endfacet + facet normal 0.149341 0.651818 0.743525 + outer loop + vertex 1.48165 2.12189 2.46898 + vertex 1.48389 2.11911 2.47097 + vertex 1.48655 2.12128 2.46853 + endloop + endfacet + facet normal 0.138778 0.524192 0.840216 + outer loop + vertex 1.48608 2.11569 2.47275 + vertex 1.48389 2.11911 2.47097 + vertex 1.48094 2.11663 2.47301 + endloop + endfacet + facet normal 0.125461 0.518543 0.845797 + outer loop + vertex 1.48884 2.11834 2.47071 + vertex 1.48389 2.11911 2.47097 + vertex 1.48608 2.11569 2.47275 + endloop + endfacet + facet normal 0.171926 0.902265 0.395424 + outer loop + vertex 1.48885 2.12472 2.46256 + vertex 1.48652 2.12645 2.45963 + vertex 1.48443 2.12578 2.46207 + endloop + endfacet + facet normal 0.153688 0.872904 0.463054 + outer loop + vertex 1.48443 2.12578 2.46207 + vertex 1.4803 2.12596 2.4631 + vertex 1.48414 2.12396 2.46559 + endloop + endfacet + facet normal 0.157211 0.87229 0.463027 + outer loop + vertex 1.48443 2.12578 2.46207 + vertex 1.48414 2.12396 2.46559 + vertex 1.48885 2.12472 2.46256 + endloop + endfacet + facet normal 0.164194 0.866005 0.472308 + outer loop + vertex 1.48885 2.12472 2.46256 + vertex 1.48414 2.12396 2.46559 + vertex 1.4889 2.12279 2.46608 + endloop + endfacet + facet normal 0.152812 0.790192 0.593503 + outer loop + vertex 1.48655 2.12128 2.46853 + vertex 1.48414 2.12396 2.46559 + vertex 1.48165 2.12189 2.46898 + endloop + endfacet + facet normal 0.130062 0.784235 0.606679 + outer loop + vertex 1.4889 2.12279 2.46608 + vertex 1.48414 2.12396 2.46559 + vertex 1.48655 2.12128 2.46853 + endloop + endfacet + facet normal 0.00307556 0.307138 0.95166 + outer loop + vertex 1.49 2.13218 2.455 + vertex 1.485 2.13223 2.455 + vertex 1.48671 2.12838 2.45624 + endloop + endfacet + facet normal -0.0409255 0.28913 0.956415 + outer loop + vertex 1.48671 2.12838 2.45624 + vertex 1.485 2.13223 2.455 + vertex 1.4821 2.12954 2.45569 + endloop + endfacet + facet normal 0.152708 0.91162 0.381613 + outer loop + vertex 1.48652 2.12645 2.45963 + vertex 1.48214 2.12747 2.45896 + vertex 1.48443 2.12578 2.46207 + endloop + endfacet + facet normal 0.122973 0.859196 0.496649 + outer loop + vertex 1.48652 2.12645 2.45963 + vertex 1.48671 2.12838 2.45624 + vertex 1.48214 2.12747 2.45896 + endloop + endfacet + facet normal 0.14687 0.835873 0.528909 + outer loop + vertex 1.48671 2.12838 2.45624 + vertex 1.4821 2.12954 2.45569 + vertex 1.48214 2.12747 2.45896 + endloop + endfacet + facet normal 0.137561 0.909723 0.391766 + outer loop + vertex 1.48443 2.12578 2.46207 + vertex 1.48214 2.12747 2.45896 + vertex 1.4803 2.12596 2.4631 + endloop + endfacet + facet normal 0.175369 -0.685031 0.707091 + outer loop + vertex 1.495 0.902131 2.455 + vertex 1.49147 0.902272 2.45601 + vertex 1.49 0.900851 2.455 + endloop + endfacet + facet normal 0.203999 -0.699084 0.685322 + outer loop + vertex 1.49147 0.902272 2.45601 + vertex 1.48612 0.901567 2.45688 + vertex 1.49 0.900851 2.455 + endloop + endfacet + facet normal 0.190075 -0.863661 0.466864 + outer loop + vertex 1.49147 0.902272 2.45601 + vertex 1.48895 0.903546 2.4594 + vertex 1.48612 0.901567 2.45688 + endloop + endfacet + facet normal 0.185313 -0.866108 0.464237 + outer loop + vertex 1.49392 0.904087 2.45842 + vertex 1.48895 0.903546 2.4594 + vertex 1.49147 0.902272 2.45601 + endloop + endfacet + facet normal 0.191756 -0.836388 0.513503 + outer loop + vertex 1.48895 0.903546 2.4594 + vertex 1.49392 0.904087 2.45842 + vertex 1.4913 0.906168 2.46279 + endloop + endfacet + facet normal 0.201263 -0.837605 0.50785 + outer loop + vertex 1.48622 0.904965 2.46282 + vertex 1.48895 0.903546 2.4594 + vertex 1.4913 0.906168 2.46279 + endloop + endfacet + facet normal 0.127358 -0.779051 0.613888 + outer loop + vertex 1.49106 0.909341 2.46686 + vertex 1.4913 0.906168 2.46279 + vertex 1.49479 0.908326 2.4648 + endloop + endfacet + facet normal 0.201253 -0.767214 0.608999 + outer loop + vertex 1.49106 0.909341 2.46686 + vertex 1.48695 0.907522 2.46593 + vertex 1.4913 0.906168 2.46279 + endloop + endfacet + facet normal 0.188193 -0.78022 0.596523 + outer loop + vertex 1.48695 0.907522 2.46593 + vertex 1.48622 0.904965 2.46282 + vertex 1.4913 0.906168 2.46279 + endloop + endfacet + facet normal 0.163573 -0.717163 0.677438 + outer loop + vertex 1.49106 0.909341 2.46686 + vertex 1.48739 0.909947 2.46839 + vertex 1.48695 0.907522 2.46593 + endloop + endfacet + facet normal 0.147327 -0.755454 0.638423 + outer loop + vertex 1.49479 0.908326 2.4648 + vertex 1.49396 0.909954 2.46692 + vertex 1.49106 0.909341 2.46686 + endloop + endfacet + facet normal 0.148933 -0.618943 0.771187 + outer loop + vertex 1.48739 0.909947 2.46839 + vertex 1.48975 0.912122 2.46968 + vertex 1.48578 0.912101 2.47043 + endloop + endfacet + facet normal 0.198028 -0.650064 0.733623 + outer loop + vertex 1.49106 0.909341 2.46686 + vertex 1.48975 0.912122 2.46968 + vertex 1.48739 0.909947 2.46839 + endloop + endfacet + facet normal 0.149405 -0.668143 0.728878 + outer loop + vertex 1.49106 0.909341 2.46686 + vertex 1.4939 0.912136 2.46884 + vertex 1.48975 0.912122 2.46968 + endloop + endfacet + facet normal 0.123948 -0.654347 0.745967 + outer loop + vertex 1.49106 0.909341 2.46686 + vertex 1.49396 0.909954 2.46692 + vertex 1.4939 0.912136 2.46884 + endloop + endfacet + facet normal 0.159851 -0.532236 0.831368 + outer loop + vertex 1.48975 0.912122 2.46968 + vertex 1.48882 0.91516 2.47181 + vertex 1.48578 0.912101 2.47043 + endloop + endfacet + facet normal 0.165121 -0.564875 0.808487 + outer loop + vertex 1.4939 0.912136 2.46884 + vertex 1.49225 0.914675 2.47095 + vertex 1.48975 0.912122 2.46968 + endloop + endfacet + facet normal 0.129597 -0.541187 0.830856 + outer loop + vertex 1.49225 0.914675 2.47095 + vertex 1.48882 0.91516 2.47181 + vertex 1.48975 0.912122 2.46968 + endloop + endfacet + facet normal 0.15349 -0.454088 0.877636 + outer loop + vertex 1.49225 0.914675 2.47095 + vertex 1.49336 0.918603 2.47279 + vertex 1.48882 0.91516 2.47181 + endloop + endfacet + facet normal 0.133931 -0.432327 0.891715 + outer loop + vertex 1.49336 0.918603 2.47279 + vertex 1.4881 0.918757 2.47366 + vertex 1.48882 0.91516 2.47181 + endloop + endfacet + facet normal 0.139519 -0.37665 0.915789 + outer loop + vertex 1.49336 0.918603 2.47279 + vertex 1.49207 0.922649 2.47465 + vertex 1.4881 0.918757 2.47366 + endloop + endfacet + facet normal 0.129741 -0.367941 0.920753 + outer loop + vertex 1.4881 0.918757 2.47366 + vertex 1.49207 0.922649 2.47465 + vertex 1.48749 0.922285 2.47515 + endloop + endfacet + facet normal 0.100148 -0.345641 0.933007 + outer loop + vertex 1.48819 0.993696 2.49841 + vertex 1.49303 0.998791 2.49978 + vertex 1.4873 0.997707 2.49999 + endloop + endfacet + facet normal 0.0988384 -0.33816 0.935884 + outer loop + vertex 1.4873 0.997707 2.49999 + vertex 1.49303 0.998791 2.49978 + vertex 1.49074 1.00177 2.50109 + endloop + endfacet + facet normal 0.0741532 -0.319666 0.944624 + outer loop + vertex 1.48585 1.00093 2.50119 + vertex 1.4873 0.997707 2.49999 + vertex 1.49074 1.00177 2.50109 + endloop + endfacet + facet normal 0.0499421 -0.173663 0.983538 + outer loop + vertex 1.49074 1.00177 2.50109 + vertex 1.48867 1.00438 2.50166 + vertex 1.48585 1.00093 2.50119 + endloop + endfacet + facet normal 0.0242671 -0.193454 0.980809 + outer loop + vertex 1.4935 1.00498 2.50166 + vertex 1.48867 1.00438 2.50166 + vertex 1.49074 1.00177 2.50109 + endloop + endfacet + facet normal 0.0372191 -0.0367789 -0.99863 + outer loop + vertex 1.49251 1.01 2.485 + vertex 1.49 1.00746 2.485 + vertex 1.48943 1.00941 2.48491 + endloop + endfacet + facet normal -0.0240977 0.192103 0.981079 + outer loop + vertex 1.4935 1.00498 2.50166 + vertex 1.49122 1.00713 2.50118 + vertex 1.48867 1.00438 2.50166 + endloop + endfacet + facet normal -0.0788279 0.240508 0.967441 + outer loop + vertex 1.48867 1.00438 2.50166 + vertex 1.49122 1.00713 2.50118 + vertex 1.48633 1.00657 2.50092 + endloop + endfacet + facet normal 0.0373221 -0.0373221 -0.998606 + outer loop + vertex 1.48943 1.00941 2.48491 + vertex 1.495 1.01249 2.485 + vertex 1.49251 1.01 2.485 + endloop + endfacet + facet normal -0.456231 0.834425 -0.309174 + outer loop + vertex 1.48943 1.00941 2.48491 + vertex 1.48921 1.0103 2.48765 + vertex 1.495 1.01249 2.485 + endloop + endfacet + facet normal -0.213787 0.929569 0.300326 + outer loop + vertex 1.48921 1.0103 2.48765 + vertex 1.49441 1.01137 2.48804 + vertex 1.495 1.01249 2.485 + endloop + endfacet + facet normal -0.202322 0.979239 0.0125126 + outer loop + vertex 1.49441 1.01137 2.48804 + vertex 1.48921 1.0103 2.48765 + vertex 1.49315 1.01107 2.49167 + endloop + endfacet + facet normal -0.14155 0.988725 -0.0488605 + outer loop + vertex 1.49315 1.01107 2.49167 + vertex 1.48921 1.0103 2.48765 + vertex 1.48807 1.01035 2.49194 + endloop + endfacet + facet normal -0.13213 0.984456 0.115708 + outer loop + vertex 1.49315 1.01107 2.49167 + vertex 1.48807 1.01035 2.49194 + vertex 1.49283 1.01053 2.49587 + endloop + endfacet + facet normal -0.134017 0.983927 0.118017 + outer loop + vertex 1.49283 1.01053 2.49587 + vertex 1.48807 1.01035 2.49194 + vertex 1.48798 1.00985 2.49606 + endloop + endfacet + facet normal -0.116392 0.92548 0.360471 + outer loop + vertex 1.49283 1.01053 2.49587 + vertex 1.48798 1.00985 2.49606 + vertex 1.49251 1.00918 2.49924 + endloop + endfacet + facet normal -0.118094 0.924404 0.362673 + outer loop + vertex 1.49251 1.00918 2.49924 + vertex 1.48798 1.00985 2.49606 + vertex 1.48781 1.00856 2.49929 + endloop + endfacet + facet normal -0.116168 0.681608 0.722437 + outer loop + vertex 1.49122 1.00713 2.50118 + vertex 1.48781 1.00856 2.49929 + vertex 1.48633 1.00657 2.50092 + endloop + endfacet + facet normal -0.0865388 0.714802 0.693952 + outer loop + vertex 1.49251 1.00918 2.49924 + vertex 1.48781 1.00856 2.49929 + vertex 1.49122 1.00713 2.50118 + endloop + endfacet + facet normal -0.0971841 -0.771422 -0.628859 + outer loop + vertex 1.495 2.01737 2.49 + vertex 1.49321 2.01551 2.49256 + vertex 1.49 2.018 2.49 + endloop + endfacet + facet normal -0.166991 -0.803082 -0.571991 + outer loop + vertex 1.49321 2.01551 2.49256 + vertex 1.48815 2.01605 2.49328 + vertex 1.49 2.018 2.49 + endloop + endfacet + facet normal -0.116004 -0.990218 -0.0775302 + outer loop + vertex 1.49321 2.01551 2.49256 + vertex 1.49228 2.01529 2.49675 + vertex 1.48815 2.01605 2.49328 + endloop + endfacet + facet normal -0.0826519 -0.989669 -0.117152 + outer loop + vertex 1.49228 2.01529 2.49675 + vertex 1.4885 2.01551 2.49759 + vertex 1.48815 2.01605 2.49328 + endloop + endfacet + facet normal 0.00849243 -0.958216 0.285921 + outer loop + vertex 1.49228 2.01529 2.49675 + vertex 1.491 2.01632 2.50023 + vertex 1.4885 2.01551 2.49759 + endloop + endfacet + facet normal -0.0671729 -0.934295 0.350115 + outer loop + vertex 1.491 2.01632 2.50023 + vertex 1.48676 2.01662 2.50023 + vertex 1.4885 2.01551 2.49759 + endloop + endfacet + facet normal -0.0511957 -0.721915 0.690086 + outer loop + vertex 1.491 2.01632 2.50023 + vertex 1.48903 2.01845 2.50231 + vertex 1.48676 2.01662 2.50023 + endloop + endfacet + facet normal 0.0065702 -0.695889 0.718119 + outer loop + vertex 1.49366 2.0183 2.50212 + vertex 1.48903 2.01845 2.50231 + vertex 1.491 2.01632 2.50023 + endloop + endfacet + facet normal 0.128591 0.663104 0.737399 + outer loop + vertex 1.48884 2.11834 2.47071 + vertex 1.49286 2.11762 2.47066 + vertex 1.49191 2.12036 2.46836 + endloop + endfacet + facet normal 0.137043 0.65593 0.742277 + outer loop + vertex 1.48655 2.12128 2.46853 + vertex 1.48884 2.11834 2.47071 + vertex 1.49191 2.12036 2.46836 + endloop + endfacet + facet normal 0.123284 0.520245 0.845071 + outer loop + vertex 1.49147 2.11486 2.47247 + vertex 1.48884 2.11834 2.47071 + vertex 1.48608 2.11569 2.47275 + endloop + endfacet + facet normal 0.102548 0.509333 0.854438 + outer loop + vertex 1.49286 2.11762 2.47066 + vertex 1.48884 2.11834 2.47071 + vertex 1.49147 2.11486 2.47247 + endloop + endfacet + facet normal 0.179408 0.902109 0.392444 + outer loop + vertex 1.48885 2.12472 2.46256 + vertex 1.49449 2.12443 2.46065 + vertex 1.49053 2.12623 2.45833 + endloop + endfacet + facet normal 0.176981 0.902884 0.391762 + outer loop + vertex 1.48652 2.12645 2.45963 + vertex 1.48885 2.12472 2.46256 + vertex 1.49053 2.12623 2.45833 + endloop + endfacet + facet normal 0.191313 0.881998 0.430672 + outer loop + vertex 1.49449 2.12443 2.46065 + vertex 1.48885 2.12472 2.46256 + vertex 1.49307 2.12267 2.46489 + endloop + endfacet + facet normal 0.160577 0.86651 0.472627 + outer loop + vertex 1.49307 2.12267 2.46489 + vertex 1.48885 2.12472 2.46256 + vertex 1.4889 2.12279 2.46608 + endloop + endfacet + facet normal 0.152532 0.770079 0.619445 + outer loop + vertex 1.49191 2.12036 2.46836 + vertex 1.4889 2.12279 2.46608 + vertex 1.48655 2.12128 2.46853 + endloop + endfacet + facet normal 0.190724 0.786968 0.586776 + outer loop + vertex 1.49307 2.12267 2.46489 + vertex 1.4889 2.12279 2.46608 + vertex 1.49191 2.12036 2.46836 + endloop + endfacet + facet normal -0.000556508 -0.00897755 0.99996 + outer loop + vertex 1.495 2.13187 2.455 + vertex 1.49 2.13218 2.455 + vertex 1.49282 2.12829 2.45497 + endloop + endfacet + facet normal 0.203398 0.139034 0.969174 + outer loop + vertex 1.49282 2.12829 2.45497 + vertex 1.49 2.13218 2.455 + vertex 1.48671 2.12838 2.45624 + endloop + endfacet + facet normal 0.206641 0.84498 0.493262 + outer loop + vertex 1.49053 2.12623 2.45833 + vertex 1.48671 2.12838 2.45624 + vertex 1.48652 2.12645 2.45963 + endloop + endfacet + facet normal 0.133646 0.801987 0.582199 + outer loop + vertex 1.49282 2.12829 2.45497 + vertex 1.48671 2.12838 2.45624 + vertex 1.49053 2.12623 2.45833 + endloop + endfacet + facet normal 0.0835266 -0.417215 0.904961 + outer loop + vertex 1.5 0.903132 2.455 + vertex 1.49721 0.903086 2.45524 + vertex 1.495 0.902131 2.455 + endloop + endfacet + facet normal 0.190952 -0.628959 0.753623 + outer loop + vertex 1.49721 0.903086 2.45524 + vertex 1.49147 0.902272 2.45601 + vertex 1.495 0.902131 2.455 + endloop + endfacet + facet normal 0.18539 -0.866126 0.464172 + outer loop + vertex 1.49721 0.903086 2.45524 + vertex 1.49392 0.904087 2.45842 + vertex 1.49147 0.902272 2.45601 + endloop + endfacet + facet normal 0.15731 -0.883762 0.440702 + outer loop + vertex 1.49821 0.90432 2.45736 + vertex 1.49392 0.904087 2.45842 + vertex 1.49721 0.903086 2.45524 + endloop + endfacet + facet normal 0.165733 -0.861749 0.479502 + outer loop + vertex 1.49392 0.904087 2.45842 + vertex 1.49821 0.90432 2.45736 + vertex 1.49729 0.906145 2.46095 + endloop + endfacet + facet normal 0.148777 -0.855133 0.496602 + outer loop + vertex 1.4913 0.906168 2.46279 + vertex 1.49392 0.904087 2.45842 + vertex 1.49729 0.906145 2.46095 + endloop + endfacet + facet normal 0.170623 -0.80564 0.567302 + outer loop + vertex 1.49729 0.906145 2.46095 + vertex 1.49479 0.908326 2.4648 + vertex 1.4913 0.906168 2.46279 + endloop + endfacet + facet normal 0.147778 -0.816229 0.558509 + outer loop + vertex 1.49911 0.90857 2.46402 + vertex 1.49479 0.908326 2.4648 + vertex 1.49729 0.906145 2.46095 + endloop + endfacet + facet normal 0.160687 -0.740115 0.653001 + outer loop + vertex 1.49479 0.908326 2.4648 + vertex 1.49911 0.90857 2.46402 + vertex 1.49676 0.910469 2.46675 + endloop + endfacet + facet normal 0.177044 -0.745572 0.642477 + outer loop + vertex 1.49396 0.909954 2.46692 + vertex 1.49479 0.908326 2.4648 + vertex 1.49676 0.910469 2.46675 + endloop + endfacet + facet normal 0.165486 -0.649693 0.741966 + outer loop + vertex 1.49676 0.910469 2.46675 + vertex 1.4939 0.912136 2.46884 + vertex 1.49396 0.909954 2.46692 + endloop + endfacet + facet normal 0.167405 -0.647869 0.743129 + outer loop + vertex 1.49863 0.913373 2.46886 + vertex 1.4939 0.912136 2.46884 + vertex 1.49676 0.910469 2.46675 + endloop + endfacet + facet normal 0.142825 -0.55471 0.819694 + outer loop + vertex 1.4939 0.912136 2.46884 + vertex 1.49863 0.913373 2.46886 + vertex 1.49617 0.915798 2.47093 + endloop + endfacet + facet normal 0.167351 -0.563717 0.808837 + outer loop + vertex 1.49225 0.914675 2.47095 + vertex 1.4939 0.912136 2.46884 + vertex 1.49617 0.915798 2.47093 + endloop + endfacet + facet normal 0.135589 -0.451145 0.882091 + outer loop + vertex 1.49617 0.915798 2.47093 + vertex 1.49336 0.918603 2.47279 + vertex 1.49225 0.914675 2.47095 + endloop + endfacet + facet normal 0.139347 -0.448041 0.883087 + outer loop + vertex 1.49907 0.919778 2.47249 + vertex 1.49336 0.918603 2.47279 + vertex 1.49617 0.915798 2.47093 + endloop + endfacet + facet normal 0.125653 -0.371981 0.919696 + outer loop + vertex 1.49907 0.919778 2.47249 + vertex 1.49776 0.923798 2.47429 + vertex 1.49336 0.918603 2.47279 + endloop + endfacet + facet normal 0.134426 -0.378306 0.915868 + outer loop + vertex 1.49336 0.918603 2.47279 + vertex 1.49776 0.923798 2.47429 + vertex 1.49207 0.922649 2.47465 + endloop + endfacet + facet normal 0.127996 -0.34173 0.931041 + outer loop + vertex 1.49207 0.922649 2.47465 + vertex 1.49776 0.923798 2.47429 + vertex 1.49534 0.926706 2.47569 + endloop + endfacet + facet normal 0.121125 -0.329202 0.936459 + outer loop + vertex 1.49862 0.930421 2.47657 + vertex 1.49403 0.929943 2.477 + vertex 1.49534 0.926706 2.47569 + endloop + endfacet + facet normal 0.00590498 0.982827 0.184434 + outer loop + vertex 1.5 1.01246 2.485 + vertex 1.495 1.01249 2.485 + vertex 1.49849 1.01205 2.48724 + endloop + endfacet + facet normal -0.0915986 0.940248 0.327937 + outer loop + vertex 1.49849 1.01205 2.48724 + vertex 1.495 1.01249 2.485 + vertex 1.49441 1.01137 2.48804 + endloop + endfacet + facet normal -0.155464 0.986945 0.0420819 + outer loop + vertex 1.49849 1.01205 2.48724 + vertex 1.49441 1.01137 2.48804 + vertex 1.49794 1.01178 2.49144 + endloop + endfacet + facet normal -0.146548 0.988665 0.0326223 + outer loop + vertex 1.49794 1.01178 2.49144 + vertex 1.49441 1.01137 2.48804 + vertex 1.49315 1.01107 2.49167 + endloop + endfacet + facet normal -0.138513 0.977034 0.161923 + outer loop + vertex 1.49794 1.01178 2.49144 + vertex 1.49315 1.01107 2.49167 + vertex 1.49768 1.01106 2.49558 + endloop + endfacet + facet normal -0.101027 0.987796 0.118547 + outer loop + vertex 1.49768 1.01106 2.49558 + vertex 1.49315 1.01107 2.49167 + vertex 1.49283 1.01053 2.49587 + endloop + endfacet + facet normal -0.0803199 0.930992 0.356093 + outer loop + vertex 1.49768 1.01106 2.49558 + vertex 1.49283 1.01053 2.49587 + vertex 1.4974 1.00971 2.49904 + endloop + endfacet + facet normal -0.0864641 0.927364 0.364034 + outer loop + vertex 1.4974 1.00971 2.49904 + vertex 1.49283 1.01053 2.49587 + vertex 1.49251 1.00918 2.49924 + endloop + endfacet + facet normal -0.0346408 0.70028 0.713027 + outer loop + vertex 1.49646 1.00743 2.50114 + vertex 1.49251 1.00918 2.49924 + vertex 1.49122 1.00713 2.50118 + endloop + endfacet + facet normal -0.045659 0.687841 0.724424 + outer loop + vertex 1.4974 1.00971 2.49904 + vertex 1.49251 1.00918 2.49924 + vertex 1.49646 1.00743 2.50114 + endloop + endfacet + facet normal 0.00703083 -0.702129 -0.712015 + outer loop + vertex 1.5 2.01742 2.49 + vertex 1.49815 2.01515 2.49222 + vertex 1.495 2.01737 2.49 + endloop + endfacet + facet normal -0.0993269 -0.770485 -0.629673 + outer loop + vertex 1.49815 2.01515 2.49222 + vertex 1.49321 2.01551 2.49256 + vertex 1.495 2.01737 2.49 + endloop + endfacet + facet normal -0.0755698 -0.996184 -0.0436566 + outer loop + vertex 1.49815 2.01515 2.49222 + vertex 1.49712 2.01505 2.49627 + vertex 1.49321 2.01551 2.49256 + endloop + endfacet + facet normal -0.0558261 -0.996359 -0.0644444 + outer loop + vertex 1.49712 2.01505 2.49627 + vertex 1.49228 2.01529 2.49675 + vertex 1.49321 2.01551 2.49256 + endloop + endfacet + facet normal -0.0187461 -0.956567 0.290908 + outer loop + vertex 1.49712 2.01505 2.49627 + vertex 1.49572 2.01618 2.49991 + vertex 1.49228 2.01529 2.49675 + endloop + endfacet + facet normal -0.00812954 -0.959882 0.280286 + outer loop + vertex 1.49572 2.01618 2.49991 + vertex 1.491 2.01632 2.50023 + vertex 1.49228 2.01529 2.49675 + endloop + endfacet + facet normal 0.0275135 -0.710088 0.703575 + outer loop + vertex 1.49572 2.01618 2.49991 + vertex 1.49366 2.0183 2.50212 + vertex 1.491 2.01632 2.50023 + endloop + endfacet + facet normal 0.0159411 -0.715735 0.69819 + outer loop + vertex 1.49867 2.01804 2.50174 + vertex 1.49366 2.0183 2.50212 + vertex 1.49572 2.01618 2.49991 + endloop + endfacet + facet normal 0.176417 0.557767 0.811032 + outer loop + vertex 1.49912 2.11488 2.47124 + vertex 1.49628 2.11796 2.46974 + vertex 1.49528 2.11566 2.47154 + endloop + endfacet + facet normal 0.155342 0.422244 0.893073 + outer loop + vertex 1.49528 2.11566 2.47154 + vertex 1.49593 2.11215 2.47308 + vertex 1.49912 2.11488 2.47124 + endloop + endfacet + facet normal 0.13279 0.420115 0.897703 + outer loop + vertex 1.49528 2.11566 2.47154 + vertex 1.49147 2.11486 2.47247 + vertex 1.49593 2.11215 2.47308 + endloop + endfacet + facet normal 0.163382 0.562816 0.810274 + outer loop + vertex 1.49286 2.11762 2.47066 + vertex 1.49528 2.11566 2.47154 + vertex 1.49628 2.11796 2.46974 + endloop + endfacet + facet normal 0.1335 0.663651 0.736033 + outer loop + vertex 1.49286 2.11762 2.47066 + vertex 1.49628 2.11796 2.46974 + vertex 1.49191 2.12036 2.46836 + endloop + endfacet + facet normal 0.168712 0.702095 0.691808 + outer loop + vertex 1.49191 2.12036 2.46836 + vertex 1.49628 2.11796 2.46974 + vertex 1.49676 2.12041 2.46713 + endloop + endfacet + facet normal 0.10349 0.50894 0.854558 + outer loop + vertex 1.49528 2.11566 2.47154 + vertex 1.49286 2.11762 2.47066 + vertex 1.49147 2.11486 2.47247 + endloop + endfacet + facet normal 0.0459024 0.790086 0.611274 + outer loop + vertex 1.49928 2.12541 2.45726 + vertex 1.49712 2.1274 2.45485 + vertex 1.49457 2.12603 2.45682 + endloop + endfacet + facet normal 0.187738 0.9054 0.380795 + outer loop + vertex 1.49457 2.12603 2.45682 + vertex 1.49053 2.12623 2.45833 + vertex 1.49449 2.12443 2.46065 + endloop + endfacet + facet normal 0.0842623 0.919284 0.384469 + outer loop + vertex 1.49457 2.12603 2.45682 + vertex 1.49449 2.12443 2.46065 + vertex 1.49928 2.12541 2.45726 + endloop + endfacet + facet normal 0.158148 0.866338 0.473758 + outer loop + vertex 1.49928 2.12541 2.45726 + vertex 1.49449 2.12443 2.46065 + vertex 1.49816 2.1237 2.46077 + endloop + endfacet + facet normal 0.16561 0.894516 0.415228 + outer loop + vertex 1.49816 2.1237 2.46077 + vertex 1.49449 2.12443 2.46065 + vertex 1.49792 2.12233 2.46381 + endloop + endfacet + facet normal 0.156714 0.892279 0.423413 + outer loop + vertex 1.49792 2.12233 2.46381 + vertex 1.49449 2.12443 2.46065 + vertex 1.49307 2.12267 2.46489 + endloop + endfacet + facet normal 0.139663 0.802535 0.580027 + outer loop + vertex 1.49676 2.12041 2.46713 + vertex 1.49307 2.12267 2.46489 + vertex 1.49191 2.12036 2.46836 + endloop + endfacet + facet normal 0.177613 0.823502 0.538793 + outer loop + vertex 1.49792 2.12233 2.46381 + vertex 1.49307 2.12267 2.46489 + vertex 1.49676 2.12041 2.46713 + endloop + endfacet + facet normal 0.162794 0.69728 0.698068 + outer loop + vertex 1.49712 2.1274 2.45485 + vertex 1.49282 2.12829 2.45497 + vertex 1.49457 2.12603 2.45682 + endloop + endfacet + facet normal 0.01612 -0.057275 0.998228 + outer loop + vertex 1.49712 2.1274 2.45485 + vertex 1.5 2.13089 2.455 + vertex 1.49282 2.12829 2.45497 + endloop + endfacet + facet normal -0.00163162 -0.00832338 0.999964 + outer loop + vertex 1.5 2.13089 2.455 + vertex 1.495 2.13187 2.455 + vertex 1.49282 2.12829 2.45497 + endloop + endfacet + facet normal 0.272233 0.726682 0.630731 + outer loop + vertex 1.49457 2.12603 2.45682 + vertex 1.49282 2.12829 2.45497 + vertex 1.49053 2.12623 2.45833 + endloop + endfacet + facet normal -0.0156709 0.930924 0.364878 + outer loop + vertex 1.50114 0.903937 2.45547 + vertex 1.505 0.904188 2.455 + vertex 1.50511 0.904313 2.45469 + endloop + endfacet + facet normal 0.127247 -0.763348 0.633331 + outer loop + vertex 1.50114 0.903937 2.45547 + vertex 1.49721 0.903086 2.45524 + vertex 1.505 0.904188 2.455 + endloop + endfacet + facet normal 0.0839436 -0.397477 0.913765 + outer loop + vertex 1.49721 0.903086 2.45524 + vertex 1.5 0.903132 2.455 + vertex 1.505 0.904188 2.455 + endloop + endfacet + facet normal 0.165373 -0.884085 0.437087 + outer loop + vertex 1.50114 0.903937 2.45547 + vertex 1.49821 0.90432 2.45736 + vertex 1.49721 0.903086 2.45524 + endloop + endfacet + facet normal 0.168518 -0.889326 0.42509 + outer loop + vertex 1.50511 0.904313 2.45469 + vertex 1.50242 0.905304 2.45782 + vertex 1.50114 0.903937 2.45547 + endloop + endfacet + facet normal 0.159871 -0.888803 0.4295 + outer loop + vertex 1.49821 0.90432 2.45736 + vertex 1.50114 0.903937 2.45547 + vertex 1.50242 0.905304 2.45782 + endloop + endfacet + facet normal 0.14918 -0.865951 0.477362 + outer loop + vertex 1.49821 0.90432 2.45736 + vertex 1.50242 0.905304 2.45782 + vertex 1.49729 0.906145 2.46095 + endloop + endfacet + facet normal 0.151218 -0.864032 0.480189 + outer loop + vertex 1.49729 0.906145 2.46095 + vertex 1.50242 0.905304 2.45782 + vertex 1.5017 0.907096 2.46128 + endloop + endfacet + facet normal 0.13428 -0.814149 0.564916 + outer loop + vertex 1.5017 0.907096 2.46128 + vertex 1.49911 0.90857 2.46402 + vertex 1.49729 0.906145 2.46095 + endloop + endfacet + facet normal 0.153236 -0.802546 0.576575 + outer loop + vertex 1.50371 0.908954 2.46333 + vertex 1.49911 0.90857 2.46402 + vertex 1.5017 0.907096 2.46128 + endloop + endfacet + facet normal 0.160115 -0.732653 0.6615 + outer loop + vertex 1.49911 0.90857 2.46402 + vertex 1.50371 0.908954 2.46333 + vertex 1.50132 0.91112 2.4663 + endloop + endfacet + facet normal 0.168495 -0.735348 0.656409 + outer loop + vertex 1.49676 0.910469 2.46675 + vertex 1.49911 0.90857 2.46402 + vertex 1.50132 0.91112 2.4663 + endloop + endfacet + facet normal 0.16443 -0.64699 0.744558 + outer loop + vertex 1.50132 0.91112 2.4663 + vertex 1.49863 0.913373 2.46886 + vertex 1.49676 0.910469 2.46675 + endloop + endfacet + facet normal 0.172591 -0.641002 0.747882 + outer loop + vertex 1.50406 0.914603 2.46866 + vertex 1.49863 0.913373 2.46886 + vertex 1.50132 0.91112 2.4663 + endloop + endfacet + facet normal 0.154686 -0.550348 0.820481 + outer loop + vertex 1.49863 0.913373 2.46886 + vertex 1.50406 0.914603 2.46866 + vertex 1.50087 0.916804 2.47074 + endloop + endfacet + facet normal 0.150809 -0.548788 0.822246 + outer loop + vertex 1.49617 0.915798 2.47093 + vertex 1.49863 0.913373 2.46886 + vertex 1.50087 0.916804 2.47074 + endloop + endfacet + facet normal 0.130797 -0.443273 0.886793 + outer loop + vertex 1.50087 0.916804 2.47074 + vertex 1.49907 0.919778 2.47249 + vertex 1.49617 0.915798 2.47093 + endloop + endfacet + facet normal 0.133651 -0.441744 0.88713 + outer loop + vertex 1.50376 0.920235 2.47201 + vertex 1.49907 0.919778 2.47249 + vertex 1.50087 0.916804 2.47074 + endloop + endfacet + facet normal 0.12952 -0.37071 0.919673 + outer loop + vertex 1.49907 0.919778 2.47249 + vertex 1.5032 0.923884 2.47356 + vertex 1.49776 0.923798 2.47429 + endloop + endfacet + facet normal 0.126762 -0.342671 0.930864 + outer loop + vertex 1.49917 0.92769 2.47553 + vertex 1.49534 0.926706 2.47569 + vertex 1.49776 0.923798 2.47429 + endloop + endfacet + facet normal 0.127072 -0.342759 0.930789 + outer loop + vertex 1.49917 0.92769 2.47553 + vertex 1.49776 0.923798 2.47429 + vertex 1.50254 0.927519 2.47501 + endloop + endfacet + facet normal 0.124078 -0.331523 0.935252 + outer loop + vertex 1.49917 0.92769 2.47553 + vertex 1.49862 0.930421 2.47657 + vertex 1.49534 0.926706 2.47569 + endloop + endfacet + facet normal -0.171007 0.982811 0.0695584 + outer loop + vertex 1.505 1.01333 2.485 + vertex 1.5 1.01246 2.485 + vertex 1.50273 1.01282 2.48656 + endloop + endfacet + facet normal -0.169102 0.98338 0.0660961 + outer loop + vertex 1.50273 1.01282 2.48656 + vertex 1.5 1.01246 2.485 + vertex 1.49849 1.01205 2.48724 + endloop + endfacet + facet normal -0.169528 0.983475 0.0635403 + outer loop + vertex 1.50273 1.01282 2.48656 + vertex 1.49849 1.01205 2.48724 + vertex 1.50282 1.01254 2.49123 + endloop + endfacet + facet normal -0.150851 0.987633 0.0427252 + outer loop + vertex 1.50282 1.01254 2.49123 + vertex 1.49849 1.01205 2.48724 + vertex 1.49794 1.01178 2.49144 + endloop + endfacet + facet normal -0.142347 0.972303 0.185374 + outer loop + vertex 1.50282 1.01254 2.49123 + vertex 1.49794 1.01178 2.49144 + vertex 1.50157 1.01165 2.49492 + endloop + endfacet + facet normal -0.121029 0.979109 0.163397 + outer loop + vertex 1.50157 1.01165 2.49492 + vertex 1.49794 1.01178 2.49144 + vertex 1.49768 1.01106 2.49558 + endloop + endfacet + facet normal -0.061291 0.895474 0.440874 + outer loop + vertex 1.50157 1.01165 2.49492 + vertex 1.49768 1.01106 2.49558 + vertex 1.50229 1.00993 2.49852 + endloop + endfacet + facet normal -0.00251933 0.931894 0.362721 + outer loop + vertex 1.50229 1.00993 2.49852 + vertex 1.49768 1.01106 2.49558 + vertex 1.4974 1.00971 2.49904 + endloop + endfacet + facet normal -0.0593671 0.690344 0.721041 + outer loop + vertex 1.50039 1.0083 2.50064 + vertex 1.4974 1.00971 2.49904 + vertex 1.49646 1.00743 2.50114 + endloop + endfacet + facet normal 0.0324347 0.778247 0.62712 + outer loop + vertex 1.50229 1.00993 2.49852 + vertex 1.4974 1.00971 2.49904 + vertex 1.50039 1.0083 2.50064 + endloop + endfacet + facet normal -0.0243402 -0.553035 -0.832802 + outer loop + vertex 1.505 2.0172 2.49 + vertex 1.50295 2.01465 2.49176 + vertex 1.5 2.01742 2.49 + endloop + endfacet + facet normal -0.139899 -0.631567 -0.762595 + outer loop + vertex 1.50295 2.01465 2.49176 + vertex 1.49815 2.01515 2.49222 + vertex 1.5 2.01742 2.49 + endloop + endfacet + facet normal -0.109589 -0.992221 -0.0590645 + outer loop + vertex 1.50295 2.01465 2.49176 + vertex 1.50209 2.0145 2.4958 + vertex 1.49815 2.01515 2.49222 + endloop + endfacet + facet normal -0.114659 -0.991967 -0.0534342 + outer loop + vertex 1.50209 2.0145 2.4958 + vertex 1.49712 2.01505 2.49627 + vertex 1.49815 2.01515 2.49222 + endloop + endfacet + facet normal -0.0784161 -0.954804 0.286707 + outer loop + vertex 1.50209 2.0145 2.4958 + vertex 1.50071 2.01573 2.49953 + vertex 1.49712 2.01505 2.49627 + endloop + endfacet + facet normal -0.0656909 -0.959568 0.273705 + outer loop + vertex 1.50071 2.01573 2.49953 + vertex 1.49572 2.01618 2.49991 + vertex 1.49712 2.01505 2.49627 + endloop + endfacet + facet normal -0.00839829 -0.696307 0.717695 + outer loop + vertex 1.50071 2.01573 2.49953 + vertex 1.49867 2.01804 2.50174 + vertex 1.49572 2.01618 2.49991 + endloop + endfacet + facet normal -0.120079 -0.740757 0.660954 + outer loop + vertex 1.50321 2.01694 2.50134 + vertex 1.49867 2.01804 2.50174 + vertex 1.50071 2.01573 2.49953 + endloop + endfacet + facet normal 0.169998 0.563241 0.808616 + outer loop + vertex 1.49912 2.11488 2.47124 + vertex 1.50399 2.11391 2.47088 + vertex 1.50118 2.11775 2.4688 + endloop + endfacet + facet normal 0.177984 0.558727 0.810029 + outer loop + vertex 1.49628 2.11796 2.46974 + vertex 1.49912 2.11488 2.47124 + vertex 1.50118 2.11775 2.4688 + endloop + endfacet + facet normal 0.1457 0.431627 0.890208 + outer loop + vertex 1.5013 2.11105 2.47273 + vertex 1.49912 2.11488 2.47124 + vertex 1.49593 2.11215 2.47308 + endloop + endfacet + facet normal 0.1502 0.433529 0.888534 + outer loop + vertex 1.50399 2.11391 2.47088 + vertex 1.49912 2.11488 2.47124 + vertex 1.5013 2.11105 2.47273 + endloop + endfacet + facet normal 0.183396 0.810814 0.555829 + outer loop + vertex 1.50417 2.11936 2.46652 + vertex 1.50186 2.12125 2.46453 + vertex 1.50032 2.12035 2.46634 + endloop + endfacet + facet normal 0.149625 0.704276 0.69398 + outer loop + vertex 1.50032 2.12035 2.46634 + vertex 1.50118 2.11775 2.4688 + vertex 1.50417 2.11936 2.46652 + endloop + endfacet + facet normal 0.163322 0.705088 0.690056 + outer loop + vertex 1.50032 2.12035 2.46634 + vertex 1.49676 2.12041 2.46713 + vertex 1.50118 2.11775 2.4688 + endloop + endfacet + facet normal 0.161723 0.703611 0.691937 + outer loop + vertex 1.49676 2.12041 2.46713 + vertex 1.49628 2.11796 2.46974 + vertex 1.50118 2.11775 2.4688 + endloop + endfacet + facet normal -0.341268 0.551578 0.761117 + outer loop + vertex 1.50166 2.13 2.455 + vertex 1.49712 2.1274 2.45485 + vertex 1.49928 2.12541 2.45726 + endloop + endfacet + facet normal 0.181028 0.35774 0.916106 + outer loop + vertex 1.50166 2.13 2.455 + vertex 1.49928 2.12541 2.45726 + vertex 1.505 2.12831 2.455 + endloop + endfacet + facet normal 0.0570313 0.541629 0.838681 + outer loop + vertex 1.505 2.12831 2.455 + vertex 1.49928 2.12541 2.45726 + vertex 1.50388 2.12419 2.45774 + endloop + endfacet + facet normal 0.183992 0.871777 0.45404 + outer loop + vertex 1.50388 2.12419 2.45774 + vertex 1.49928 2.12541 2.45726 + vertex 1.50177 2.12282 2.46123 + endloop + endfacet + facet normal 0.151002 0.868332 0.472438 + outer loop + vertex 1.50177 2.12282 2.46123 + vertex 1.49928 2.12541 2.45726 + vertex 1.49816 2.1237 2.46077 + endloop + endfacet + facet normal 0.133632 0.838989 0.527485 + outer loop + vertex 1.50186 2.12125 2.46453 + vertex 1.49792 2.12233 2.46381 + vertex 1.50032 2.12035 2.46634 + endloop + endfacet + facet normal 0.167899 0.892099 0.419486 + outer loop + vertex 1.50186 2.12125 2.46453 + vertex 1.50177 2.12282 2.46123 + vertex 1.49792 2.12233 2.46381 + endloop + endfacet + facet normal 0.164707 0.894681 0.415232 + outer loop + vertex 1.50177 2.12282 2.46123 + vertex 1.49816 2.1237 2.46077 + vertex 1.49792 2.12233 2.46381 + endloop + endfacet + facet normal 0.129712 0.837833 0.530292 + outer loop + vertex 1.50032 2.12035 2.46634 + vertex 1.49792 2.12233 2.46381 + vertex 1.49676 2.12041 2.46713 + endloop + endfacet + facet normal -0.289565 0.807306 0.514207 + outer loop + vertex 1.505 2.13 2.45281 + vertex 1.505 2.13179 2.45 + vertex 1.50001 2.13 2.45 + endloop + endfacet + facet normal 0.46663 0.870555 -0.156175 + outer loop + vertex 1.50166 2.13 2.455 + vertex 1.5 2.13 2.45004 + vertex 1.5 2.13089 2.455 + endloop + endfacet + facet normal -0.016353 -0.0305086 0.999401 + outer loop + vertex 1.50166 2.13 2.455 + vertex 1.5 2.13089 2.455 + vertex 1.49712 2.1274 2.45485 + endloop + endfacet + facet normal -0.24411 0.887645 -0.390509 + outer loop + vertex 1.505 0.904188 2.455 + vertex 1.51 0.905 2.45372 + vertex 1.50762 0.904228 2.45345 + endloop + endfacet + facet normal -0.0187787 -0.809433 -0.586912 + outer loop + vertex 1.505 0.905 2.45388 + vertex 1.51 0.905 2.45372 + vertex 1.505 0.904188 2.455 + endloop + endfacet + facet normal 0.238863 0.872136 0.426993 + outer loop + vertex 1.50762 0.904228 2.45345 + vertex 1.50511 0.904313 2.45469 + vertex 1.505 0.904188 2.455 + endloop + endfacet + facet normal 0.141555 -0.925211 0.352062 + outer loop + vertex 1.50915 0.904653 2.45396 + vertex 1.50511 0.904313 2.45469 + vertex 1.50762 0.904228 2.45345 + endloop + endfacet + facet normal 0.151855 -0.892752 0.424186 + outer loop + vertex 1.50511 0.904313 2.45469 + vertex 1.50915 0.904653 2.45396 + vertex 1.50803 0.905448 2.45603 + endloop + endfacet + facet normal 0.156377 -0.895517 0.416648 + outer loop + vertex 1.50242 0.905304 2.45782 + vertex 1.50511 0.904313 2.45469 + vertex 1.50803 0.905448 2.45603 + endloop + endfacet + facet normal 0.168853 -0.873075 0.457414 + outer loop + vertex 1.50803 0.905448 2.45603 + vertex 1.50639 0.907127 2.45984 + vertex 1.50242 0.905304 2.45782 + endloop + endfacet + facet normal 0.152925 -0.863646 0.480344 + outer loop + vertex 1.50639 0.907127 2.45984 + vertex 1.5017 0.907096 2.46128 + vertex 1.50242 0.905304 2.45782 + endloop + endfacet + facet normal 0.176897 -0.809598 0.559695 + outer loop + vertex 1.50639 0.907127 2.45984 + vertex 1.50371 0.908954 2.46333 + vertex 1.5017 0.907096 2.46128 + endloop + endfacet + facet normal 0.141561 -0.828181 0.542289 + outer loop + vertex 1.50762 0.909023 2.46241 + vertex 1.50371 0.908954 2.46333 + vertex 1.50639 0.907127 2.45984 + endloop + endfacet + facet normal 0.167202 -0.733337 0.658985 + outer loop + vertex 1.50371 0.908954 2.46333 + vertex 1.50762 0.909023 2.46241 + vertex 1.50693 0.911463 2.4653 + endloop + endfacet + facet normal 0.163091 -0.730953 0.662653 + outer loop + vertex 1.50132 0.91112 2.4663 + vertex 1.50371 0.908954 2.46333 + vertex 1.50693 0.911463 2.4653 + endloop + endfacet + facet normal 0.172819 -0.641093 0.747752 + outer loop + vertex 1.50693 0.911463 2.4653 + vertex 1.50406 0.914603 2.46866 + vertex 1.50132 0.91112 2.4663 + endloop + endfacet + facet normal 0.163818 -0.646507 0.745113 + outer loop + vertex 1.50955 0.914922 2.46773 + vertex 1.50406 0.914603 2.46866 + vertex 1.50693 0.911463 2.4653 + endloop + endfacet + facet normal 0.153817 -0.551213 0.820063 + outer loop + vertex 1.50458 0.917738 2.47067 + vertex 1.50087 0.916804 2.47074 + vertex 1.50406 0.914603 2.46866 + endloop + endfacet + facet normal 0.165054 -0.551544 0.817653 + outer loop + vertex 1.50458 0.917738 2.47067 + vertex 1.50406 0.914603 2.46866 + vertex 1.50802 0.917715 2.46996 + endloop + endfacet + facet normal 0.170148 -0.556255 0.813407 + outer loop + vertex 1.50802 0.917715 2.46996 + vertex 1.50406 0.914603 2.46866 + vertex 1.50955 0.914922 2.46773 + endloop + endfacet + facet normal 0.126416 -0.436915 0.890575 + outer loop + vertex 1.50458 0.917738 2.47067 + vertex 1.50376 0.920235 2.47201 + vertex 1.50087 0.916804 2.47074 + endloop + endfacet + facet normal 0.176108 -0.463457 0.868443 + outer loop + vertex 1.50802 0.917715 2.46996 + vertex 1.50701 0.920003 2.47138 + vertex 1.50458 0.917738 2.47067 + endloop + endfacet + facet normal 0.140557 -0.432338 0.890689 + outer loop + vertex 1.50701 0.920003 2.47138 + vertex 1.50376 0.920235 2.47201 + vertex 1.50458 0.917738 2.47067 + endloop + endfacet + facet normal 0.148649 -0.379521 0.913163 + outer loop + vertex 1.50701 0.920003 2.47138 + vertex 1.50847 0.923776 2.47271 + vertex 1.50376 0.920235 2.47201 + endloop + endfacet + facet normal -0.32316 0.936585 0.135557 + outer loop + vertex 1.50668 1.0138 2.48578 + vertex 1.50984 1.015 2.485 + vertex 1.505 1.01333 2.485 + endloop + endfacet + facet normal -0.246992 0.967924 -0.0460249 + outer loop + vertex 1.50273 1.01282 2.48656 + vertex 1.50668 1.0138 2.48578 + vertex 1.505 1.01333 2.485 + endloop + endfacet + facet normal -0.233684 0.971941 0.0268852 + outer loop + vertex 1.50626 1.01359 2.48938 + vertex 1.50668 1.0138 2.48578 + vertex 1.50273 1.01282 2.48656 + endloop + endfacet + facet normal -0.261566 0.963047 0.064212 + outer loop + vertex 1.50282 1.01254 2.49123 + vertex 1.50626 1.01359 2.48938 + vertex 1.50273 1.01282 2.48656 + endloop + endfacet + facet normal -0.219026 0.964966 0.144457 + outer loop + vertex 1.50696 1.01321 2.49305 + vertex 1.50626 1.01359 2.48938 + vertex 1.50282 1.01254 2.49123 + endloop + endfacet + facet normal -0.302786 0.880052 0.365827 + outer loop + vertex 1.50696 1.01321 2.49305 + vertex 1.50282 1.01254 2.49123 + vertex 1.50611 1.01164 2.4961 + endloop + endfacet + facet normal -0.0544234 0.974904 0.215869 + outer loop + vertex 1.50611 1.01164 2.4961 + vertex 1.50282 1.01254 2.49123 + vertex 1.50157 1.01165 2.49492 + endloop + endfacet + facet normal 0.126264 0.609789 0.782441 + outer loop + vertex 1.50688 1.00808 2.49922 + vertex 1.50229 1.00993 2.49852 + vertex 1.50299 1.00733 2.50042 + endloop + endfacet + facet normal 0.158942 0.669443 0.725661 + outer loop + vertex 1.50688 1.00808 2.49922 + vertex 1.50611 1.01164 2.4961 + vertex 1.50229 1.00993 2.49852 + endloop + endfacet + facet normal -0.114796 0.886927 0.447418 + outer loop + vertex 1.50611 1.01164 2.4961 + vertex 1.50157 1.01165 2.49492 + vertex 1.50229 1.00993 2.49852 + endloop + endfacet + facet normal 0.28844 0.617066 0.732142 + outer loop + vertex 1.50299 1.00733 2.50042 + vertex 1.50229 1.00993 2.49852 + vertex 1.50039 1.0083 2.50064 + endloop + endfacet + facet normal 0.252765 0.824491 0.506285 + outer loop + vertex 1.51 1.015 2.48492 + vertex 1.50984 1.015 2.485 + vertex 1.51036 1.01475 2.48515 + endloop + endfacet + facet normal -0.245288 0.968866 0.0336652 + outer loop + vertex 1.51036 1.01475 2.48515 + vertex 1.50668 1.0138 2.48578 + vertex 1.50978 1.01449 2.48836 + endloop + endfacet + facet normal 0.00906435 0.529229 0.848431 + outer loop + vertex 1.50984 1.015 2.485 + vertex 1.50668 1.0138 2.48578 + vertex 1.51036 1.01475 2.48515 + endloop + endfacet + facet normal -0.216663 0.970625 0.104612 + outer loop + vertex 1.50978 1.01449 2.48836 + vertex 1.50626 1.01359 2.48938 + vertex 1.50976 1.01406 2.49235 + endloop + endfacet + facet normal -0.239422 0.970564 0.0261356 + outer loop + vertex 1.50668 1.0138 2.48578 + vertex 1.50626 1.01359 2.48938 + vertex 1.50978 1.01449 2.48836 + endloop + endfacet + facet normal -0.253108 0.955732 0.150039 + outer loop + vertex 1.50976 1.01406 2.49235 + vertex 1.50626 1.01359 2.48938 + vertex 1.50696 1.01321 2.49305 + endloop + endfacet + facet normal -0.0157009 -0.313891 -0.949329 + outer loop + vertex 1.51 2.01695 2.49 + vertex 1.50761 2.01415 2.49096 + vertex 1.505 2.0172 2.49 + endloop + endfacet + facet normal -0.195493 -0.444216 -0.874331 + outer loop + vertex 1.50761 2.01415 2.49096 + vertex 1.50295 2.01465 2.49176 + vertex 1.505 2.0172 2.49 + endloop + endfacet + facet normal -0.136455 -0.970281 -0.199839 + outer loop + vertex 1.50761 2.01415 2.49096 + vertex 1.50671 2.01347 2.49489 + vertex 1.50295 2.01465 2.49176 + endloop + endfacet + facet normal -0.232452 -0.968949 -0.0842839 + outer loop + vertex 1.50671 2.01347 2.49489 + vertex 1.50209 2.0145 2.4958 + vertex 1.50295 2.01465 2.49176 + endloop + endfacet + facet normal -0.168272 -0.958616 0.229652 + outer loop + vertex 1.50671 2.01347 2.49489 + vertex 1.50605 2.01462 2.49921 + vertex 1.50209 2.0145 2.4958 + endloop + endfacet + facet normal -0.183171 -0.951629 0.246678 + outer loop + vertex 1.50605 2.01462 2.49921 + vertex 1.50071 2.01573 2.49953 + vertex 1.50209 2.0145 2.4958 + endloop + endfacet + facet normal -0.11579 -0.744489 0.657517 + outer loop + vertex 1.50605 2.01462 2.49921 + vertex 1.50321 2.01694 2.50134 + vertex 1.50071 2.01573 2.49953 + endloop + endfacet + facet normal -0.063902 -0.715807 0.695369 + outer loop + vertex 1.5079 2.0167 2.50152 + vertex 1.50321 2.01694 2.50134 + vertex 1.50605 2.01462 2.49921 + endloop + endfacet + facet normal 0.155337 0.55042 0.82031 + outer loop + vertex 1.50399 2.11391 2.47088 + vertex 1.50813 2.11296 2.47074 + vertex 1.50726 2.11626 2.46869 + endloop + endfacet + facet normal 0.151023 0.554566 0.81832 + outer loop + vertex 1.50118 2.11775 2.4688 + vertex 1.50399 2.11391 2.47088 + vertex 1.50726 2.11626 2.46869 + endloop + endfacet + facet normal 0.14439 0.438154 0.887227 + outer loop + vertex 1.50639 2.10997 2.47244 + vertex 1.50399 2.11391 2.47088 + vertex 1.5013 2.11105 2.47273 + endloop + endfacet + facet normal 0.130567 0.431839 0.89245 + outer loop + vertex 1.50813 2.11296 2.47074 + vertex 1.50399 2.11391 2.47088 + vertex 1.50639 2.10997 2.47244 + endloop + endfacet + facet normal 0.171709 0.81851 0.548231 + outer loop + vertex 1.50417 2.11936 2.46652 + vertex 1.50897 2.11884 2.4658 + vertex 1.50562 2.12093 2.46373 + endloop + endfacet + facet normal 0.187198 0.812123 0.552642 + outer loop + vertex 1.50186 2.12125 2.46453 + vertex 1.50417 2.11936 2.46652 + vertex 1.50562 2.12093 2.46373 + endloop + endfacet + facet normal 0.178963 0.677414 0.713501 + outer loop + vertex 1.50726 2.11626 2.46869 + vertex 1.50417 2.11936 2.46652 + vertex 1.50118 2.11775 2.4688 + endloop + endfacet + facet normal 0.180796 0.678316 0.71218 + outer loop + vertex 1.50897 2.11884 2.4658 + vertex 1.50417 2.11936 2.46652 + vertex 1.50726 2.11626 2.46869 + endloop + endfacet + facet normal 0.0510031 0.392374 0.918391 + outer loop + vertex 1.51 2.12766 2.455 + vertex 1.505 2.12831 2.455 + vertex 1.5079 2.12419 2.4566 + endloop + endfacet + facet normal 0.236986 0.492059 0.837685 + outer loop + vertex 1.5079 2.12419 2.4566 + vertex 1.505 2.12831 2.455 + vertex 1.50388 2.12419 2.45774 + endloop + endfacet + facet normal 0.136871 0.86577 0.481361 + outer loop + vertex 1.5079 2.12419 2.4566 + vertex 1.50388 2.12419 2.45774 + vertex 1.50683 2.12234 2.46023 + endloop + endfacet + facet normal 0.17165 0.877071 0.448646 + outer loop + vertex 1.50683 2.12234 2.46023 + vertex 1.50388 2.12419 2.45774 + vertex 1.50177 2.12282 2.46123 + endloop + endfacet + facet normal 0.16559 0.892427 0.419706 + outer loop + vertex 1.50562 2.12093 2.46373 + vertex 1.50177 2.12282 2.46123 + vertex 1.50186 2.12125 2.46453 + endloop + endfacet + facet normal 0.167115 0.893032 0.417813 + outer loop + vertex 1.50683 2.12234 2.46023 + vertex 1.50177 2.12282 2.46123 + vertex 1.50562 2.12093 2.46373 + endloop + endfacet + facet normal 0.297752 0.805185 0.512856 + outer loop + vertex 1.50984 2.13 2.45 + vertex 1.505 2.13179 2.45 + vertex 1.505 2.13 2.45281 + endloop + endfacet + facet normal -0.365962 -0.894588 0.256483 + outer loop + vertex 1.51247 0.905 2.45 + vertex 1.515 0.903965 2.45 + vertex 1.515 0.905 2.45361 + endloop + endfacet + facet normal 0.311563 -0.76055 -0.569642 + outer loop + vertex 1.51 0.905 2.45372 + vertex 1.51234 0.905 2.455 + vertex 1.50762 0.904228 2.45345 + endloop + endfacet + facet normal -0.308626 -0.0223695 0.950921 + outer loop + vertex 1.51234 0.905 2.455 + vertex 1.50915 0.904653 2.45396 + vertex 1.50762 0.904228 2.45345 + endloop + endfacet + facet normal -0.216316 0.907563 0.359913 + outer loop + vertex 1.50915 0.904653 2.45396 + vertex 1.51234 0.905 2.455 + vertex 1.515 0.905634 2.455 + endloop + endfacet + facet normal 0.0827356 -0.914748 0.395464 + outer loop + vertex 1.50915 0.904653 2.45396 + vertex 1.515 0.905634 2.455 + vertex 1.50803 0.905448 2.45603 + endloop + endfacet + facet normal 0.105072 -0.818765 0.564432 + outer loop + vertex 1.50803 0.905448 2.45603 + vertex 1.515 0.905634 2.455 + vertex 1.51164 0.906867 2.45741 + endloop + endfacet + facet normal 0.191996 -0.86053 0.471833 + outer loop + vertex 1.51018 0.908164 2.46037 + vertex 1.51164 0.906867 2.45741 + vertex 1.51417 0.908483 2.45933 + endloop + endfacet + facet normal 0.171905 -0.868292 0.465316 + outer loop + vertex 1.51018 0.908164 2.46037 + vertex 1.50639 0.907127 2.45984 + vertex 1.51164 0.906867 2.45741 + endloop + endfacet + facet normal 0.167876 -0.873408 0.45714 + outer loop + vertex 1.50639 0.907127 2.45984 + vertex 1.50803 0.905448 2.45603 + vertex 1.51164 0.906867 2.45741 + endloop + endfacet + facet normal 0.150741 -0.829007 0.53854 + outer loop + vertex 1.51018 0.908164 2.46037 + vertex 1.50762 0.909023 2.46241 + vertex 1.50639 0.907127 2.45984 + endloop + endfacet + facet normal 0.210378 -0.801014 0.560462 + outer loop + vertex 1.51417 0.908483 2.45933 + vertex 1.51126 0.909955 2.46253 + vertex 1.51018 0.908164 2.46037 + endloop + endfacet + facet normal 0.186535 -0.799426 0.571071 + outer loop + vertex 1.50762 0.909023 2.46241 + vertex 1.51018 0.908164 2.46037 + vertex 1.51126 0.909955 2.46253 + endloop + endfacet + facet normal 0.166836 -0.733428 0.658976 + outer loop + vertex 1.50762 0.909023 2.46241 + vertex 1.51126 0.909955 2.46253 + vertex 1.50693 0.911463 2.4653 + endloop + endfacet + facet normal 0.171668 -0.728109 0.663617 + outer loop + vertex 1.50693 0.911463 2.4653 + vertex 1.51126 0.909955 2.46253 + vertex 1.51226 0.912499 2.46506 + endloop + endfacet + facet normal 0.159252 -0.644784 0.747591 + outer loop + vertex 1.51226 0.912499 2.46506 + vertex 1.50955 0.914922 2.46773 + vertex 1.50693 0.911463 2.4653 + endloop + endfacet + facet normal 0.16045 -0.643953 0.748051 + outer loop + vertex 1.51424 0.915349 2.46709 + vertex 1.50955 0.914922 2.46773 + vertex 1.51226 0.912499 2.46506 + endloop + endfacet + facet normal 0.161607 -0.536335 0.828389 + outer loop + vertex 1.51424 0.915349 2.46709 + vertex 1.51317 0.918694 2.46947 + vertex 1.50955 0.914922 2.46773 + endloop + endfacet + facet normal 0.182808 -0.550323 0.814693 + outer loop + vertex 1.50955 0.914922 2.46773 + vertex 1.51317 0.918694 2.46947 + vertex 1.50802 0.917715 2.46996 + endloop + endfacet + facet normal 0.170409 -0.455366 0.873843 + outer loop + vertex 1.50802 0.917715 2.46996 + vertex 1.51317 0.918694 2.46947 + vertex 1.51074 0.921097 2.47119 + endloop + endfacet + facet normal 0.180533 -0.461571 0.868539 + outer loop + vertex 1.50701 0.920003 2.47138 + vertex 1.50802 0.917715 2.46996 + vertex 1.51074 0.921097 2.47119 + endloop + endfacet + facet normal 0.159491 -0.3826 0.910044 + outer loop + vertex 1.51074 0.921097 2.47119 + vertex 1.50847 0.923776 2.47271 + vertex 1.50701 0.920003 2.47138 + endloop + endfacet + facet normal -0.275821 0.884701 0.375802 + outer loop + vertex 1.50948 1.01305 2.49527 + vertex 1.50696 1.01321 2.49305 + vertex 1.50611 1.01164 2.4961 + endloop + endfacet + facet normal -0.154059 0.749735 0.643555 + outer loop + vertex 1.50611 1.01164 2.4961 + vertex 1.51079 1.01127 2.49765 + vertex 1.50948 1.01305 2.49527 + endloop + endfacet + facet normal -0.202645 0.619384 0.758484 + outer loop + vertex 1.50611 1.01164 2.4961 + vertex 1.50688 1.00808 2.49922 + vertex 1.51079 1.01127 2.49765 + endloop + endfacet + facet normal 0.0334942 0.406224 0.913159 + outer loop + vertex 1.50688 1.00808 2.49922 + vertex 1.51227 1.00793 2.49908 + vertex 1.51079 1.01127 2.49765 + endloop + endfacet + facet normal -0.187391 0.667461 -0.72068 + outer loop + vertex 1.51 1.015 2.48492 + vertex 1.515 1.01649 2.485 + vertex 1.515 1.015 2.48362 + endloop + endfacet + facet normal -0.169927 0.525541 0.833626 + outer loop + vertex 1.51036 1.01475 2.48515 + vertex 1.515 1.01649 2.485 + vertex 1.51 1.015 2.48492 + endloop + endfacet + facet normal -0.338925 0.920671 0.193636 + outer loop + vertex 1.515 1.01649 2.485 + vertex 1.51036 1.01475 2.48515 + vertex 1.51396 1.01557 2.48754 + endloop + endfacet + facet normal -0.244046 0.96917 0.0339119 + outer loop + vertex 1.51396 1.01557 2.48754 + vertex 1.51036 1.01475 2.48515 + vertex 1.50978 1.01449 2.48836 + endloop + endfacet + facet normal -0.228115 0.967097 0.112633 + outer loop + vertex 1.51396 1.01557 2.48754 + vertex 1.50978 1.01449 2.48836 + vertex 1.51341 1.01495 2.49178 + endloop + endfacet + facet normal -0.220748 0.969717 0.104493 + outer loop + vertex 1.51341 1.01495 2.49178 + vertex 1.50978 1.01449 2.48836 + vertex 1.50976 1.01406 2.49235 + endloop + endfacet + facet normal -0.207315 0.930606 0.30165 + outer loop + vertex 1.50948 1.01305 2.49527 + vertex 1.50976 1.01406 2.49235 + vertex 1.50696 1.01321 2.49305 + endloop + endfacet + facet normal -0.160916 0.937488 0.308581 + outer loop + vertex 1.50948 1.01305 2.49527 + vertex 1.51279 1.01357 2.49541 + vertex 1.50976 1.01406 2.49235 + endloop + endfacet + facet normal -0.177209 0.929517 0.323412 + outer loop + vertex 1.51279 1.01357 2.49541 + vertex 1.51341 1.01495 2.49178 + vertex 1.50976 1.01406 2.49235 + endloop + endfacet + facet normal -0.145926 0.753068 0.641557 + outer loop + vertex 1.51279 1.01357 2.49541 + vertex 1.50948 1.01305 2.49527 + vertex 1.51079 1.01127 2.49765 + endloop + endfacet + facet normal -0.971851 -0.0491147 -0.230418 + outer loop + vertex 1.51273 1.41136 2.55609 + vertex 1.51227 1.41283 2.55768 + vertex 1.5129 1.41498 2.55458 + endloop + endfacet + facet normal -0.978939 -0.136196 -0.152085 + outer loop + vertex 1.51237 1.41001 2.55961 + vertex 1.51227 1.41283 2.55768 + vertex 1.51273 1.41136 2.55609 + endloop + endfacet + facet normal -0.995052 -0.0764347 -0.063483 + outer loop + vertex 1.51204 1.41325 2.56077 + vertex 1.51227 1.41283 2.55768 + vertex 1.51237 1.41001 2.55961 + endloop + endfacet + facet normal -0.982849 -0.140822 0.119065 + outer loop + vertex 1.51275 1.41052 2.56341 + vertex 1.51204 1.41325 2.56077 + vertex 1.51237 1.41001 2.55961 + endloop + endfacet + facet normal -0.978622 -0.0668238 0.194508 + outer loop + vertex 1.51263 1.41482 2.56428 + vertex 1.51204 1.41325 2.56077 + vertex 1.51275 1.41052 2.56341 + endloop + endfacet + facet normal -0.756613 -0.150217 0.636373 + outer loop + vertex 1.51275 1.41052 2.56341 + vertex 1.51499 1.41263 2.56657 + vertex 1.51263 1.41482 2.56428 + endloop + endfacet + facet normal -0.975547 -0.0138041 -0.219356 + outer loop + vertex 1.5129 1.41498 2.55458 + vertex 1.5122 1.4161 2.55763 + vertex 1.51296 1.41948 2.55404 + endloop + endfacet + facet normal -0.976246 -0.0257692 -0.215126 + outer loop + vertex 1.51227 1.41283 2.55768 + vertex 1.5122 1.4161 2.55763 + vertex 1.5129 1.41498 2.55458 + endloop + endfacet + facet normal -0.997199 -0.0240875 -0.0708038 + outer loop + vertex 1.51227 1.41283 2.55768 + vertex 1.51204 1.41325 2.56077 + vertex 1.5122 1.4161 2.55763 + endloop + endfacet + facet normal -0.997035 -0.0259118 -0.0724534 + outer loop + vertex 1.5122 1.4161 2.55763 + vertex 1.51204 1.41325 2.56077 + vertex 1.5119 1.4174 2.56124 + endloop + endfacet + facet normal -0.980325 -0.0550612 0.189554 + outer loop + vertex 1.51204 1.41325 2.56077 + vertex 1.51263 1.41482 2.56428 + vertex 1.5119 1.4174 2.56124 + endloop + endfacet + facet normal -0.979849 -0.0506252 0.193215 + outer loop + vertex 1.5119 1.4174 2.56124 + vertex 1.51263 1.41482 2.56428 + vertex 1.51248 1.41961 2.56473 + endloop + endfacet + facet normal -0.770891 -0.0850115 0.631269 + outer loop + vertex 1.51263 1.41482 2.56428 + vertex 1.51453 1.41794 2.56702 + vertex 1.51248 1.41961 2.56473 + endloop + endfacet + facet normal -0.746452 -0.120243 0.654485 + outer loop + vertex 1.51499 1.41263 2.56657 + vertex 1.51453 1.41794 2.56702 + vertex 1.51263 1.41482 2.56428 + endloop + endfacet + facet normal -0.975636 -0.0151902 -0.21887 + outer loop + vertex 1.51296 1.41948 2.55404 + vertex 1.51213 1.42053 2.55765 + vertex 1.51293 1.42433 2.55382 + endloop + endfacet + facet normal -0.975565 -0.0137213 -0.219281 + outer loop + vertex 1.5122 1.4161 2.55763 + vertex 1.51213 1.42053 2.55765 + vertex 1.51296 1.41948 2.55404 + endloop + endfacet + facet normal -0.996958 -0.0143635 -0.0766084 + outer loop + vertex 1.5122 1.4161 2.55763 + vertex 1.5119 1.4174 2.56124 + vertex 1.51213 1.42053 2.55765 + endloop + endfacet + facet normal -0.997045 -0.0132758 -0.0756678 + outer loop + vertex 1.51213 1.42053 2.55765 + vertex 1.5119 1.4174 2.56124 + vertex 1.51182 1.42216 2.56147 + endloop + endfacet + facet normal -0.983735 -0.0252485 0.17784 + outer loop + vertex 1.5119 1.4174 2.56124 + vertex 1.51248 1.41961 2.56473 + vertex 1.51182 1.42216 2.56147 + endloop + endfacet + facet normal -0.983546 -0.0235755 0.179112 + outer loop + vertex 1.51182 1.42216 2.56147 + vertex 1.51248 1.41961 2.56473 + vertex 1.51242 1.42462 2.56506 + endloop + endfacet + facet normal -0.777721 -0.0503962 0.626587 + outer loop + vertex 1.51248 1.41961 2.56473 + vertex 1.5144 1.42299 2.56739 + vertex 1.51242 1.42462 2.56506 + endloop + endfacet + facet normal -0.76579 -0.067374 0.639551 + outer loop + vertex 1.51453 1.41794 2.56702 + vertex 1.5144 1.42299 2.56739 + vertex 1.51248 1.41961 2.56473 + endloop + endfacet + facet normal -0.976128 -0.0150297 -0.216675 + outer loop + vertex 1.51293 1.42433 2.55382 + vertex 1.51207 1.42544 2.55761 + vertex 1.5129 1.42939 2.55363 + endloop + endfacet + facet normal -0.976048 -0.0133632 -0.217146 + outer loop + vertex 1.51213 1.42053 2.55765 + vertex 1.51207 1.42544 2.55761 + vertex 1.51293 1.42433 2.55382 + endloop + endfacet + facet normal -0.997034 -0.012715 -0.0759053 + outer loop + vertex 1.51213 1.42053 2.55765 + vertex 1.51182 1.42216 2.56147 + vertex 1.51207 1.42544 2.55761 + endloop + endfacet + facet normal -0.997404 -0.00763499 -0.0716088 + outer loop + vertex 1.51207 1.42544 2.55761 + vertex 1.51182 1.42216 2.56147 + vertex 1.51177 1.4272 2.5616 + endloop + endfacet + facet normal -0.984918 -0.013594 0.17249 + outer loop + vertex 1.51182 1.42216 2.56147 + vertex 1.51242 1.42462 2.56506 + vertex 1.51177 1.4272 2.5616 + endloop + endfacet + facet normal -0.986878 -0.0337114 0.157909 + outer loop + vertex 1.51177 1.4272 2.5616 + vertex 1.51242 1.42462 2.56506 + vertex 1.51231 1.4298 2.56548 + endloop + endfacet + facet normal -0.783851 -0.0667121 0.617356 + outer loop + vertex 1.51242 1.42462 2.56506 + vertex 1.51432 1.42815 2.56786 + vertex 1.51231 1.4298 2.56548 + endloop + endfacet + facet normal -0.782851 -0.0681333 0.618467 + outer loop + vertex 1.5144 1.42299 2.56739 + vertex 1.51432 1.42815 2.56786 + vertex 1.51242 1.42462 2.56506 + endloop + endfacet + facet normal -0.97621 -0.0188968 -0.216004 + outer loop + vertex 1.5129 1.42939 2.55363 + vertex 1.51202 1.43053 2.55749 + vertex 1.51284 1.4345 2.55344 + endloop + endfacet + facet normal -0.976048 -0.0153837 -0.217009 + outer loop + vertex 1.51207 1.42544 2.55761 + vertex 1.51202 1.43053 2.55749 + vertex 1.5129 1.42939 2.55363 + endloop + endfacet + facet normal -0.997497 -0.0120526 -0.0696687 + outer loop + vertex 1.51207 1.42544 2.55761 + vertex 1.51177 1.4272 2.5616 + vertex 1.51202 1.43053 2.55749 + endloop + endfacet + facet normal -0.997186 -0.0163687 -0.0731546 + outer loop + vertex 1.51202 1.43053 2.55749 + vertex 1.51177 1.4272 2.5616 + vertex 1.51168 1.43231 2.56166 + endloop + endfacet + facet normal -0.988769 -0.0189298 0.14825 + outer loop + vertex 1.51177 1.4272 2.5616 + vertex 1.51231 1.4298 2.56548 + vertex 1.51168 1.43231 2.56166 + endloop + endfacet + facet normal -0.990824 -0.0832441 0.106482 + outer loop + vertex 1.51168 1.43231 2.56166 + vertex 1.51231 1.4298 2.56548 + vertex 1.51192 1.43509 2.56606 + endloop + endfacet + facet normal -0.840571 -0.118913 0.528489 + outer loop + vertex 1.51231 1.4298 2.56548 + vertex 1.51389 1.43355 2.56885 + vertex 1.51192 1.43509 2.56606 + endloop + endfacet + facet normal -0.806776 -0.167471 0.566628 + outer loop + vertex 1.51432 1.42815 2.56786 + vertex 1.51389 1.43355 2.56885 + vertex 1.51231 1.4298 2.56548 + endloop + endfacet + facet normal -0.975546 -0.00825461 -0.219641 + outer loop + vertex 1.51284 1.4345 2.55344 + vertex 1.51196 1.43564 2.55729 + vertex 1.5128 1.43968 2.55341 + endloop + endfacet + facet normal -0.976097 -0.0193951 -0.216468 + outer loop + vertex 1.51202 1.43053 2.55749 + vertex 1.51196 1.43564 2.55729 + vertex 1.51284 1.4345 2.55344 + endloop + endfacet + facet normal -0.997147 -0.0139437 -0.074184 + outer loop + vertex 1.51202 1.43053 2.55749 + vertex 1.51168 1.43231 2.56166 + vertex 1.51196 1.43564 2.55729 + endloop + endfacet + facet normal -0.99597 -0.0283455 -0.0850904 + outer loop + vertex 1.51196 1.43564 2.55729 + vertex 1.51168 1.43231 2.56166 + vertex 1.51157 1.43722 2.5614 + endloop + endfacet + facet normal -0.997541 -0.0202471 0.0670923 + outer loop + vertex 1.51168 1.43231 2.56166 + vertex 1.51192 1.43509 2.56606 + vertex 1.51157 1.43722 2.5614 + endloop + endfacet + facet normal -0.995073 -0.0933158 0.0334873 + outer loop + vertex 1.51157 1.43722 2.5614 + vertex 1.51192 1.43509 2.56606 + vertex 1.5115 1.43909 2.56474 + endloop + endfacet + facet normal -0.828769 -0.443252 0.34157 + outer loop + vertex 1.51257 1.43649 2.56944 + vertex 1.51192 1.43509 2.56606 + vertex 1.51389 1.43355 2.56885 + endloop + endfacet + facet normal -0.964928 -0.120551 0.2332 + outer loop + vertex 1.51257 1.43649 2.56944 + vertex 1.51194 1.43962 2.56848 + vertex 1.51192 1.43509 2.56606 + endloop + endfacet + facet normal -0.990221 -0.0626426 0.124655 + outer loop + vertex 1.51194 1.43962 2.56848 + vertex 1.5115 1.43909 2.56474 + vertex 1.51192 1.43509 2.56606 + endloop + endfacet + facet normal -0.927071 -0.0714992 0.368003 + outer loop + vertex 1.51257 1.43649 2.56944 + vertex 1.51286 1.43892 2.57067 + vertex 1.51194 1.43962 2.56848 + endloop + endfacet + facet normal -0.969704 0.0293195 -0.242517 + outer loop + vertex 1.5128 1.43968 2.55341 + vertex 1.51191 1.44073 2.55711 + vertex 1.51285 1.44498 2.55388 + endloop + endfacet + facet normal -0.973073 -0.0184681 -0.229754 + outer loop + vertex 1.51196 1.43564 2.55729 + vertex 1.51191 1.44073 2.55711 + vertex 1.5128 1.43968 2.55341 + endloop + endfacet + facet normal -0.995788 -0.0139089 -0.0906223 + outer loop + vertex 1.51196 1.43564 2.55729 + vertex 1.51157 1.43722 2.5614 + vertex 1.51191 1.44073 2.55711 + endloop + endfacet + facet normal -0.995218 -0.0200437 -0.0955978 + outer loop + vertex 1.51191 1.44073 2.55711 + vertex 1.51157 1.43722 2.5614 + vertex 1.51149 1.44194 2.56116 + endloop + endfacet + facet normal -0.999825 -0.0158421 -0.00999266 + outer loop + vertex 1.51157 1.43722 2.5614 + vertex 1.5115 1.43909 2.56474 + vertex 1.51149 1.44194 2.56116 + endloop + endfacet + facet normal -0.999995 0.000696324 0.00315256 + outer loop + vertex 1.51149 1.44194 2.56116 + vertex 1.5115 1.43909 2.56474 + vertex 1.51151 1.4431 2.56529 + endloop + endfacet + facet normal -0.992863 -0.0151734 0.118295 + outer loop + vertex 1.5115 1.43909 2.56474 + vertex 1.51194 1.43962 2.56848 + vertex 1.51151 1.4431 2.56529 + endloop + endfacet + facet normal -0.989789 0.00723942 0.142356 + outer loop + vertex 1.51151 1.4431 2.56529 + vertex 1.51194 1.43962 2.56848 + vertex 1.51203 1.44472 2.56884 + endloop + endfacet + facet normal -0.892208 -0.0160461 0.45134 + outer loop + vertex 1.51194 1.43962 2.56848 + vertex 1.51304 1.44247 2.57074 + vertex 1.51203 1.44472 2.56884 + endloop + endfacet + facet normal -0.916659 0.0357419 0.398068 + outer loop + vertex 1.51286 1.43892 2.57067 + vertex 1.51304 1.44247 2.57074 + vertex 1.51194 1.43962 2.56848 + endloop + endfacet + facet normal -0.953585 0.0437298 -0.297933 + outer loop + vertex 1.51285 1.44498 2.55388 + vertex 1.51188 1.44586 2.5571 + vertex 1.5129 1.45017 2.55445 + endloop + endfacet + facet normal -0.95828 -0.00612684 -0.285766 + outer loop + vertex 1.51191 1.44073 2.55711 + vertex 1.51188 1.44586 2.5571 + vertex 1.51285 1.44498 2.55388 + endloop + endfacet + facet normal -0.994991 -0.00588544 -0.0997946 + outer loop + vertex 1.51191 1.44073 2.55711 + vertex 1.51149 1.44194 2.56116 + vertex 1.51188 1.44586 2.5571 + endloop + endfacet + facet normal -0.99535 -0.0022237 -0.0962956 + outer loop + vertex 1.51188 1.44586 2.5571 + vertex 1.51149 1.44194 2.56116 + vertex 1.51148 1.44687 2.56119 + endloop + endfacet + facet normal -0.999988 -0.00280507 0.00413887 + outer loop + vertex 1.51149 1.44194 2.56116 + vertex 1.51151 1.4431 2.56529 + vertex 1.51148 1.44687 2.56119 + endloop + endfacet + facet normal -0.999858 0.00852825 0.0145417 + outer loop + vertex 1.51148 1.44687 2.56119 + vertex 1.51151 1.4431 2.56529 + vertex 1.51155 1.44805 2.56545 + endloop + endfacet + facet normal -0.989608 0.00417232 0.143731 + outer loop + vertex 1.51151 1.4431 2.56529 + vertex 1.51203 1.44472 2.56884 + vertex 1.51155 1.44805 2.56545 + endloop + endfacet + facet normal -0.985607 0.028074 0.166705 + outer loop + vertex 1.51155 1.44805 2.56545 + vertex 1.51203 1.44472 2.56884 + vertex 1.51219 1.44978 2.56893 + endloop + endfacet + facet normal -0.853646 0.0171422 0.520571 + outer loop + vertex 1.51203 1.44472 2.56884 + vertex 1.51331 1.44725 2.57086 + vertex 1.51219 1.44978 2.56893 + endloop + endfacet + facet normal -0.864594 0.0383422 0.501006 + outer loop + vertex 1.51304 1.44247 2.57074 + vertex 1.51331 1.44725 2.57086 + vertex 1.51203 1.44472 2.56884 + endloop + endfacet + facet normal -0.924559 -0.0207423 -0.380475 + outer loop + vertex 1.5129 1.45017 2.55445 + vertex 1.51183 1.45106 2.55702 + vertex 1.51281 1.45499 2.55441 + endloop + endfacet + facet normal -0.923957 -0.015046 -0.382201 + outer loop + vertex 1.51188 1.44586 2.5571 + vertex 1.51183 1.45106 2.55702 + vertex 1.5129 1.45017 2.55445 + endloop + endfacet + facet normal -0.995503 -0.0114483 -0.0940375 + outer loop + vertex 1.51188 1.44586 2.5571 + vertex 1.51148 1.44687 2.56119 + vertex 1.51183 1.45106 2.55702 + endloop + endfacet + facet normal -0.996031 -0.0061922 -0.0887944 + outer loop + vertex 1.51183 1.45106 2.55702 + vertex 1.51148 1.44687 2.56119 + vertex 1.51146 1.45213 2.56106 + endloop + endfacet + facet normal -0.999834 -0.00350783 0.0178814 + outer loop + vertex 1.51148 1.44687 2.56119 + vertex 1.51155 1.44805 2.56545 + vertex 1.51146 1.45213 2.56106 + endloop + endfacet + facet normal -0.999742 0.00163556 0.0226547 + outer loop + vertex 1.51146 1.45213 2.56106 + vertex 1.51155 1.44805 2.56545 + vertex 1.51156 1.45319 2.56546 + endloop + endfacet + facet normal -0.983738 0.00153642 0.179603 + outer loop + vertex 1.51155 1.44805 2.56545 + vertex 1.51219 1.44978 2.56893 + vertex 1.51156 1.45319 2.56546 + endloop + endfacet + facet normal -0.979175 0.0247288 0.201508 + outer loop + vertex 1.51156 1.45319 2.56546 + vertex 1.51219 1.44978 2.56893 + vertex 1.51233 1.45495 2.56898 + endloop + endfacet + facet normal -0.8108 0.0166135 0.585088 + outer loop + vertex 1.51219 1.44978 2.56893 + vertex 1.51364 1.45236 2.57087 + vertex 1.51233 1.45495 2.56898 + endloop + endfacet + facet normal -0.831284 0.0519719 0.553413 + outer loop + vertex 1.51331 1.44725 2.57086 + vertex 1.51364 1.45236 2.57087 + vertex 1.51219 1.44978 2.56893 + endloop + endfacet + facet normal -0.899277 -0.00805502 -0.437305 + outer loop + vertex 1.51281 1.45499 2.55441 + vertex 1.51181 1.45682 2.55644 + vertex 1.51292 1.45908 2.55412 + endloop + endfacet + facet normal -0.910783 -0.0441157 -0.410523 + outer loop + vertex 1.51183 1.45106 2.55702 + vertex 1.51181 1.45682 2.55644 + vertex 1.51281 1.45499 2.55441 + endloop + endfacet + facet normal -0.996109 -0.0115972 -0.0873639 + outer loop + vertex 1.51183 1.45106 2.55702 + vertex 1.51146 1.45213 2.56106 + vertex 1.51181 1.45682 2.55644 + endloop + endfacet + facet normal -0.995515 -0.017224 -0.0930258 + outer loop + vertex 1.51181 1.45682 2.55644 + vertex 1.51146 1.45213 2.56106 + vertex 1.51138 1.45742 2.56093 + endloop + endfacet + facet normal -0.999544 -0.0144669 0.0265189 + outer loop + vertex 1.51146 1.45213 2.56106 + vertex 1.51156 1.45319 2.56546 + vertex 1.51138 1.45742 2.56093 + endloop + endfacet + facet normal -0.999447 -0.00843245 0.0321592 + outer loop + vertex 1.51138 1.45742 2.56093 + vertex 1.51156 1.45319 2.56546 + vertex 1.51152 1.45832 2.56541 + endloop + endfacet + facet normal -0.976266 -0.00655253 0.216475 + outer loop + vertex 1.51156 1.45319 2.56546 + vertex 1.51233 1.45495 2.56898 + vertex 1.51152 1.45832 2.56541 + endloop + endfacet + facet normal -0.974281 0.00326375 0.225312 + outer loop + vertex 1.51152 1.45832 2.56541 + vertex 1.51233 1.45495 2.56898 + vertex 1.51236 1.46007 2.56901 + endloop + endfacet + facet normal -0.745214 -0.00058603 0.666825 + outer loop + vertex 1.51233 1.45495 2.56898 + vertex 1.51415 1.45795 2.57101 + vertex 1.51236 1.46007 2.56901 + endloop + endfacet + facet normal -0.783651 0.0550395 0.618759 + outer loop + vertex 1.51364 1.45236 2.57087 + vertex 1.51415 1.45795 2.57101 + vertex 1.51233 1.45495 2.56898 + endloop + endfacet + facet normal 0.288895 -0.0342133 -0.956749 + outer loop + vertex 1.515 1.46472 2.555 + vertex 1.51265 1.4619 2.55439 + vertex 1.515 1.465 2.55499 + endloop + endfacet + facet normal 0.125615 0.107891 -0.986195 + outer loop + vertex 1.51292 1.45908 2.55412 + vertex 1.51265 1.4619 2.55439 + vertex 1.515 1.46472 2.555 + endloop + endfacet + facet normal -0.886801 -0.0379887 -0.460588 + outer loop + vertex 1.51292 1.45908 2.55412 + vertex 1.51181 1.45682 2.55644 + vertex 1.51265 1.4619 2.55439 + endloop + endfacet + facet normal -0.914982 -0.0102924 -0.403364 + outer loop + vertex 1.51181 1.45682 2.55644 + vertex 1.51162 1.46193 2.55674 + vertex 1.51265 1.4619 2.55439 + endloop + endfacet + facet normal -0.995336 -0.0319202 -0.0910317 + outer loop + vertex 1.51181 1.45682 2.55644 + vertex 1.51138 1.45742 2.56093 + vertex 1.51162 1.46193 2.55674 + endloop + endfacet + facet normal -0.996086 -0.0258347 -0.0845327 + outer loop + vertex 1.51162 1.46193 2.55674 + vertex 1.51138 1.45742 2.56093 + vertex 1.51125 1.46253 2.5609 + endloop + endfacet + facet normal -0.99905 -0.0252377 0.0355312 + outer loop + vertex 1.51138 1.45742 2.56093 + vertex 1.51152 1.45832 2.56541 + vertex 1.51125 1.46253 2.5609 + endloop + endfacet + facet normal -0.999021 -0.0224574 0.0381243 + outer loop + vertex 1.51125 1.46253 2.5609 + vertex 1.51152 1.45832 2.56541 + vertex 1.5114 1.46335 2.56541 + endloop + endfacet + facet normal -0.971313 -0.0218345 0.236802 + outer loop + vertex 1.51152 1.45832 2.56541 + vertex 1.51236 1.46007 2.56901 + vertex 1.5114 1.46335 2.56541 + endloop + endfacet + facet normal -0.97076 -0.0189276 0.239303 + outer loop + vertex 1.5114 1.46335 2.56541 + vertex 1.51236 1.46007 2.56901 + vertex 1.51227 1.46503 2.56907 + endloop + endfacet + facet normal -0.76989 -0.0207156 0.637841 + outer loop + vertex 1.51236 1.46007 2.56901 + vertex 1.51395 1.46306 2.57104 + vertex 1.51227 1.46503 2.56907 + endloop + endfacet + facet normal -0.761182 -0.0320823 0.647744 + outer loop + vertex 1.51415 1.45795 2.57101 + vertex 1.51395 1.46306 2.57104 + vertex 1.51236 1.46007 2.56901 + endloop + endfacet + facet normal 0.252263 -0.0270745 -0.96728 + outer loop + vertex 1.515 1.465 2.55499 + vertex 1.51257 1.46591 2.55433 + vertex 1.515 1.47 2.55485 + endloop + endfacet + facet normal 0.258524 -0.00946746 -0.965958 + outer loop + vertex 1.51265 1.4619 2.55439 + vertex 1.51257 1.46591 2.55433 + vertex 1.515 1.465 2.55499 + endloop + endfacet + facet normal -0.914783 -0.026178 -0.403096 + outer loop + vertex 1.51265 1.4619 2.55439 + vertex 1.51162 1.46193 2.55674 + vertex 1.51257 1.46591 2.55433 + endloop + endfacet + facet normal -0.918171 -0.0208613 -0.395635 + outer loop + vertex 1.51257 1.46591 2.55433 + vertex 1.51162 1.46193 2.55674 + vertex 1.51152 1.46683 2.55672 + endloop + endfacet + facet normal -0.99614 -0.0209426 -0.0852473 + outer loop + vertex 1.51162 1.46193 2.55674 + vertex 1.51125 1.46253 2.5609 + vertex 1.51152 1.46683 2.55672 + endloop + endfacet + facet normal -0.995012 -0.0304923 -0.0949786 + outer loop + vertex 1.51152 1.46683 2.55672 + vertex 1.51125 1.46253 2.5609 + vertex 1.5111 1.46755 2.56086 + endloop + endfacet + facet normal -0.998788 -0.0295076 0.0394006 + outer loop + vertex 1.51125 1.46253 2.5609 + vertex 1.5114 1.46335 2.56541 + vertex 1.5111 1.46755 2.56086 + endloop + endfacet + facet normal -0.998758 -0.0264643 0.0422093 + outer loop + vertex 1.5111 1.46755 2.56086 + vertex 1.5114 1.46335 2.56541 + vertex 1.51127 1.46833 2.56545 + endloop + endfacet + facet normal -0.969661 -0.0273678 0.242918 + outer loop + vertex 1.5114 1.46335 2.56541 + vertex 1.51227 1.46503 2.56907 + vertex 1.51127 1.46833 2.56545 + endloop + endfacet + facet normal -0.967617 -0.0169069 0.251857 + outer loop + vertex 1.51127 1.46833 2.56545 + vertex 1.51227 1.46503 2.56907 + vertex 1.51222 1.46995 2.56918 + endloop + endfacet + facet normal -0.763309 -0.0226821 0.645635 + outer loop + vertex 1.51227 1.46503 2.56907 + vertex 1.51396 1.46789 2.57117 + vertex 1.51222 1.46995 2.56918 + endloop + endfacet + facet normal -0.767786 -0.0162722 0.6405 + outer loop + vertex 1.51395 1.46306 2.57104 + vertex 1.51396 1.46789 2.57117 + vertex 1.51227 1.46503 2.56907 + endloop + endfacet + facet normal 0.252454 -0.0232475 -0.967329 + outer loop + vertex 1.515 1.47 2.55485 + vertex 1.51252 1.47069 2.55419 + vertex 1.515 1.475 2.55473 + endloop + endfacet + facet normal 0.251554 -0.0266272 -0.967477 + outer loop + vertex 1.51257 1.46591 2.55433 + vertex 1.51252 1.47069 2.55419 + vertex 1.515 1.47 2.55485 + endloop + endfacet + facet normal -0.918191 -0.0210317 -0.395579 + outer loop + vertex 1.51257 1.46591 2.55433 + vertex 1.51152 1.46683 2.55672 + vertex 1.51252 1.47069 2.55419 + endloop + endfacet + facet normal -0.910916 -0.0331896 -0.411255 + outer loop + vertex 1.51252 1.47069 2.55419 + vertex 1.51152 1.46683 2.55672 + vertex 1.51139 1.4718 2.55661 + endloop + endfacet + facet normal -0.995036 -0.0286555 -0.095302 + outer loop + vertex 1.51152 1.46683 2.55672 + vertex 1.5111 1.46755 2.56086 + vertex 1.51139 1.4718 2.55661 + endloop + endfacet + facet normal -0.995252 -0.0268864 -0.0935479 + outer loop + vertex 1.51139 1.4718 2.55661 + vertex 1.5111 1.46755 2.56086 + vertex 1.51096 1.47258 2.56087 + endloop + endfacet + facet normal -0.998737 -0.0270903 0.042314 + outer loop + vertex 1.5111 1.46755 2.56086 + vertex 1.51127 1.46833 2.56545 + vertex 1.51096 1.47258 2.56087 + endloop + endfacet + facet normal -0.998595 -0.019637 0.0492224 + outer loop + vertex 1.51096 1.47258 2.56087 + vertex 1.51127 1.46833 2.56545 + vertex 1.51118 1.47333 2.56549 + endloop + endfacet + facet normal -0.967155 -0.0206072 0.253352 + outer loop + vertex 1.51127 1.46833 2.56545 + vertex 1.51222 1.46995 2.56918 + vertex 1.51118 1.47333 2.56549 + endloop + endfacet + facet normal -0.964033 -0.00615497 0.265712 + outer loop + vertex 1.51118 1.47333 2.56549 + vertex 1.51222 1.46995 2.56918 + vertex 1.5122 1.47493 2.56924 + endloop + endfacet + facet normal -0.750494 -0.0102228 0.660798 + outer loop + vertex 1.51222 1.46995 2.56918 + vertex 1.51402 1.47282 2.57127 + vertex 1.5122 1.47493 2.56924 + endloop + endfacet + facet normal -0.754352 -0.00463974 0.656454 + outer loop + vertex 1.51396 1.46789 2.57117 + vertex 1.51402 1.47282 2.57127 + vertex 1.51222 1.46995 2.56918 + endloop + endfacet + facet normal 0.243789 -0.00194229 -0.969826 + outer loop + vertex 1.515 1.475 2.55473 + vertex 1.51246 1.47564 2.55409 + vertex 1.515 1.48 2.55472 + endloop + endfacet + facet normal 0.240456 -0.0159407 -0.970529 + outer loop + vertex 1.51252 1.47069 2.55419 + vertex 1.51246 1.47564 2.55409 + vertex 1.515 1.475 2.55473 + endloop + endfacet + facet normal -0.908884 -0.0194748 -0.416594 + outer loop + vertex 1.51252 1.47069 2.55419 + vertex 1.51139 1.4718 2.55661 + vertex 1.51246 1.47564 2.55409 + endloop + endfacet + facet normal -0.906441 -0.0235005 -0.421679 + outer loop + vertex 1.51246 1.47564 2.55409 + vertex 1.51139 1.4718 2.55661 + vertex 1.51127 1.47685 2.55658 + endloop + endfacet + facet normal -0.995277 -0.0238003 -0.0941155 + outer loop + vertex 1.51139 1.4718 2.55661 + vertex 1.51096 1.47258 2.56087 + vertex 1.51127 1.47685 2.55658 + endloop + endfacet + facet normal -0.995443 -0.02237 -0.0927015 + outer loop + vertex 1.51127 1.47685 2.55658 + vertex 1.51096 1.47258 2.56087 + vertex 1.51085 1.47763 2.56088 + endloop + endfacet + facet normal -0.998501 -0.0228499 0.0497358 + outer loop + vertex 1.51096 1.47258 2.56087 + vertex 1.51118 1.47333 2.56549 + vertex 1.51085 1.47763 2.56088 + endloop + endfacet + facet normal -0.998126 -0.0117779 0.0600453 + outer loop + vertex 1.51085 1.47763 2.56088 + vertex 1.51118 1.47333 2.56549 + vertex 1.51112 1.47834 2.56552 + endloop + endfacet + facet normal -0.963253 -0.0126878 0.268297 + outer loop + vertex 1.51118 1.47333 2.56549 + vertex 1.5122 1.47493 2.56924 + vertex 1.51112 1.47834 2.56552 + endloop + endfacet + facet normal -0.960657 -0.00156932 0.277733 + outer loop + vertex 1.51112 1.47834 2.56552 + vertex 1.5122 1.47493 2.56924 + vertex 1.5122 1.47993 2.56927 + endloop + endfacet + facet normal -0.749637 -0.00381308 0.661838 + outer loop + vertex 1.5122 1.47493 2.56924 + vertex 1.51406 1.4778 2.57136 + vertex 1.5122 1.47993 2.56927 + endloop + endfacet + facet normal -0.748266 -0.00583535 0.663373 + outer loop + vertex 1.51402 1.47282 2.57127 + vertex 1.51406 1.4778 2.57136 + vertex 1.5122 1.47493 2.56924 + endloop + endfacet + facet normal 0.242 -0.0716097 -0.96763 + outer loop + vertex 1.515 1.48 2.55472 + vertex 1.51239 1.48068 2.55402 + vertex 1.515 1.485 2.55435 + endloop + endfacet + facet normal 0.257637 -0.0105357 -0.966184 + outer loop + vertex 1.51246 1.47564 2.55409 + vertex 1.51239 1.48068 2.55402 + vertex 1.515 1.48 2.55472 + endloop + endfacet + facet normal -0.905433 -0.0174732 -0.424129 + outer loop + vertex 1.51246 1.47564 2.55409 + vertex 1.51127 1.47685 2.55658 + vertex 1.51239 1.48068 2.55402 + endloop + endfacet + facet normal -0.906754 -0.0152479 -0.421385 + outer loop + vertex 1.51239 1.48068 2.55402 + vertex 1.51127 1.47685 2.55658 + vertex 1.51118 1.48193 2.55658 + endloop + endfacet + facet normal -0.995458 -0.0167568 -0.0937201 + outer loop + vertex 1.51127 1.47685 2.55658 + vertex 1.51085 1.47763 2.56088 + vertex 1.51118 1.48193 2.55658 + endloop + endfacet + facet normal -0.995758 -0.0139637 -0.09095 + outer loop + vertex 1.51118 1.48193 2.55658 + vertex 1.51085 1.47763 2.56088 + vertex 1.51078 1.48266 2.56089 + endloop + endfacet + facet normal -0.998071 -0.014269 0.0604214 + outer loop + vertex 1.51085 1.47763 2.56088 + vertex 1.51112 1.47834 2.56552 + vertex 1.51078 1.48266 2.56089 + endloop + endfacet + facet normal -0.997715 -0.00698752 0.0671964 + outer loop + vertex 1.51078 1.48266 2.56089 + vertex 1.51112 1.47834 2.56552 + vertex 1.51109 1.48333 2.56554 + endloop + endfacet + facet normal -0.959953 -0.00750504 0.280061 + outer loop + vertex 1.51112 1.47834 2.56552 + vertex 1.5122 1.47993 2.56927 + vertex 1.51109 1.48333 2.56554 + endloop + endfacet + facet normal -0.958934 -0.00327422 0.283611 + outer loop + vertex 1.51109 1.48333 2.56554 + vertex 1.5122 1.47993 2.56927 + vertex 1.51219 1.48492 2.56929 + endloop + endfacet + facet normal -0.745422 -0.00506258 0.666574 + outer loop + vertex 1.5122 1.47993 2.56927 + vertex 1.51409 1.4828 2.5714 + vertex 1.51219 1.48492 2.56929 + endloop + endfacet + facet normal -0.74819 -0.000938789 0.663484 + outer loop + vertex 1.51406 1.4778 2.57136 + vertex 1.51409 1.4828 2.5714 + vertex 1.5122 1.47993 2.56927 + endloop + endfacet + facet normal 0.136218 -0.00788871 -0.990647 + outer loop + vertex 1.515 1.485 2.55435 + vertex 1.51235 1.48575 2.55398 + vertex 1.515 1.49 2.55431 + endloop + endfacet + facet normal 0.136672 -0.00627017 -0.990596 + outer loop + vertex 1.51239 1.48068 2.55402 + vertex 1.51235 1.48575 2.55398 + vertex 1.515 1.485 2.55435 + endloop + endfacet + facet normal -0.906022 -0.0110219 -0.423086 + outer loop + vertex 1.51239 1.48068 2.55402 + vertex 1.51118 1.48193 2.55658 + vertex 1.51235 1.48575 2.55398 + endloop + endfacet + facet normal -0.906168 -0.0107691 -0.42278 + outer loop + vertex 1.51235 1.48575 2.55398 + vertex 1.51118 1.48193 2.55658 + vertex 1.51112 1.48697 2.55658 + endloop + endfacet + facet normal -0.995751 -0.0115515 -0.0913614 + outer loop + vertex 1.51118 1.48193 2.55658 + vertex 1.51078 1.48266 2.56089 + vertex 1.51112 1.48697 2.55658 + endloop + endfacet + facet normal -0.996298 -0.00590856 -0.0857634 + outer loop + vertex 1.51112 1.48697 2.55658 + vertex 1.51078 1.48266 2.56089 + vertex 1.51075 1.48765 2.56091 + endloop + endfacet + facet normal -0.997725 -0.00642168 0.0671161 + outer loop + vertex 1.51078 1.48266 2.56089 + vertex 1.51109 1.48333 2.56554 + vertex 1.51075 1.48765 2.56091 + endloop + endfacet + facet normal -0.997585 -0.0040341 0.0693333 + outer loop + vertex 1.51075 1.48765 2.56091 + vertex 1.51109 1.48333 2.56554 + vertex 1.51107 1.4883 2.56555 + endloop + endfacet + facet normal -0.958794 -0.00445073 0.284068 + outer loop + vertex 1.51109 1.48333 2.56554 + vertex 1.51219 1.48492 2.56929 + vertex 1.51107 1.4883 2.56555 + endloop + endfacet + facet normal -0.95861 -0.00369023 0.2847 + outer loop + vertex 1.51107 1.4883 2.56555 + vertex 1.51219 1.48492 2.56929 + vertex 1.51218 1.4899 2.56932 + endloop + endfacet + facet normal -0.73732 -0.00489271 0.675526 + outer loop + vertex 1.51219 1.48492 2.56929 + vertex 1.51411 1.48781 2.57141 + vertex 1.51218 1.4899 2.56932 + endloop + endfacet + facet normal -0.741955 0.00190803 0.670447 + outer loop + vertex 1.51409 1.4828 2.5714 + vertex 1.51411 1.48781 2.57141 + vertex 1.51219 1.48492 2.56929 + endloop + endfacet + facet normal 0.124852 0.0317292 -0.991668 + outer loop + vertex 1.515 1.49 2.55431 + vertex 1.51233 1.4908 2.554 + vertex 1.515 1.495 2.55447 + endloop + endfacet + facet normal 0.116827 0.0044039 -0.993142 + outer loop + vertex 1.51235 1.48575 2.55398 + vertex 1.51233 1.4908 2.554 + vertex 1.515 1.49 2.55431 + endloop + endfacet + facet normal -0.904762 -0.00266662 -0.42591 + outer loop + vertex 1.51235 1.48575 2.55398 + vertex 1.51112 1.48697 2.55658 + vertex 1.51233 1.4908 2.554 + endloop + endfacet + facet normal -0.906605 0.000560313 -0.42198 + outer loop + vertex 1.51233 1.4908 2.554 + vertex 1.51112 1.48697 2.55658 + vertex 1.51111 1.49197 2.55661 + endloop + endfacet + facet normal -0.996255 -0.00148954 -0.0864523 + outer loop + vertex 1.51112 1.48697 2.55658 + vertex 1.51075 1.48765 2.56091 + vertex 1.51111 1.49197 2.55661 + endloop + endfacet + facet normal -0.996143 -0.00274569 -0.0877052 + outer loop + vertex 1.51111 1.49197 2.55661 + vertex 1.51075 1.48765 2.56091 + vertex 1.51073 1.49261 2.56092 + endloop + endfacet + facet normal -0.997598 -0.00310436 0.0692043 + outer loop + vertex 1.51075 1.48765 2.56091 + vertex 1.51107 1.4883 2.56555 + vertex 1.51073 1.49261 2.56092 + endloop + endfacet + facet normal -0.997579 -0.00279792 0.0694881 + outer loop + vertex 1.51073 1.49261 2.56092 + vertex 1.51107 1.4883 2.56555 + vertex 1.51105 1.49327 2.56556 + endloop + endfacet + facet normal -0.958684 -0.00306449 0.284456 + outer loop + vertex 1.51107 1.4883 2.56555 + vertex 1.51218 1.4899 2.56932 + vertex 1.51105 1.49327 2.56556 + endloop + endfacet + facet normal -0.95834 -0.00164778 0.285626 + outer loop + vertex 1.51105 1.49327 2.56556 + vertex 1.51218 1.4899 2.56932 + vertex 1.51217 1.49489 2.56933 + endloop + endfacet + facet normal -0.737312 -0.00261825 0.675548 + outer loop + vertex 1.51218 1.4899 2.56932 + vertex 1.51412 1.4928 2.57145 + vertex 1.51217 1.49489 2.56933 + endloop + endfacet + facet normal -0.736667 -0.00356391 0.676246 + outer loop + vertex 1.51411 1.48781 2.57141 + vertex 1.51412 1.4928 2.57145 + vertex 1.51218 1.4899 2.56932 + endloop + endfacet + facet normal 0.163116 0.0216826 -0.986369 + outer loop + vertex 1.515 1.495 2.55447 + vertex 1.51233 1.4958 2.55405 + vertex 1.515 1.5 2.55458 + endloop + endfacet + facet normal 0.159496 0.00916404 -0.987156 + outer loop + vertex 1.51233 1.4908 2.554 + vertex 1.51233 1.4958 2.55405 + vertex 1.515 1.495 2.55447 + endloop + endfacet + facet normal -0.906 0.00404544 -0.423259 + outer loop + vertex 1.51233 1.4908 2.554 + vertex 1.51111 1.49197 2.55661 + vertex 1.51233 1.4958 2.55405 + endloop + endfacet + facet normal -0.903136 -0.00093934 -0.429354 + outer loop + vertex 1.51233 1.4958 2.55405 + vertex 1.51111 1.49197 2.55661 + vertex 1.51111 1.49693 2.5566 + endloop + endfacet + facet normal -0.996121 -0.0007768 -0.0879962 + outer loop + vertex 1.51111 1.49197 2.55661 + vertex 1.51073 1.49261 2.56092 + vertex 1.51111 1.49693 2.5566 + endloop + endfacet + facet normal -0.996154 -0.000395317 -0.0876168 + outer loop + vertex 1.51111 1.49693 2.5566 + vertex 1.51073 1.49261 2.56092 + vertex 1.51073 1.49758 2.56092 + endloop + endfacet + facet normal -0.997605 -0.000501321 0.0691631 + outer loop + vertex 1.51073 1.49261 2.56092 + vertex 1.51105 1.49327 2.56556 + vertex 1.51073 1.49758 2.56092 + endloop + endfacet + facet normal -0.997646 -0.00115187 0.0685622 + outer loop + vertex 1.51073 1.49758 2.56092 + vertex 1.51105 1.49327 2.56556 + vertex 1.51105 1.49826 2.56557 + endloop + endfacet + facet normal -0.958374 -0.00135856 0.285512 + outer loop + vertex 1.51105 1.49327 2.56556 + vertex 1.51217 1.49489 2.56933 + vertex 1.51105 1.49826 2.56557 + endloop + endfacet + facet normal -0.957828 0.000864001 0.28734 + outer loop + vertex 1.51105 1.49826 2.56557 + vertex 1.51217 1.49489 2.56933 + vertex 1.51218 1.49988 2.56934 + endloop + endfacet + facet normal -0.733478 -0.000479172 0.679713 + outer loop + vertex 1.51217 1.49489 2.56933 + vertex 1.51415 1.49779 2.57146 + vertex 1.51218 1.49988 2.56934 + endloop + endfacet + facet normal -0.735092 0.00189846 0.677965 + outer loop + vertex 1.51412 1.4928 2.57145 + vertex 1.51415 1.49779 2.57146 + vertex 1.51217 1.49489 2.56933 + endloop + endfacet + facet normal 0.189366 -0.0372894 -0.981198 + outer loop + vertex 1.515 1.5 2.55458 + vertex 1.51233 1.50078 2.55404 + vertex 1.515 1.505 2.55439 + endloop + endfacet + facet normal 0.199315 -0.00216786 -0.979933 + outer loop + vertex 1.51233 1.4958 2.55405 + vertex 1.51233 1.50078 2.55404 + vertex 1.515 1.5 2.55458 + endloop + endfacet + facet normal -0.902971 2.22061e-05 -0.429702 + outer loop + vertex 1.51233 1.4958 2.55405 + vertex 1.51111 1.49693 2.5566 + vertex 1.51233 1.50078 2.55404 + endloop + endfacet + facet normal -0.904978 0.00350727 -0.425445 + outer loop + vertex 1.51233 1.50078 2.55404 + vertex 1.51111 1.49693 2.5566 + vertex 1.51112 1.5019 2.55661 + endloop + endfacet + facet normal -0.996104 0.0030941 -0.0881336 + outer loop + vertex 1.51111 1.49693 2.5566 + vertex 1.51073 1.49758 2.56092 + vertex 1.51112 1.5019 2.55661 + endloop + endfacet + facet normal -0.995875 0.000478475 -0.090738 + outer loop + vertex 1.51112 1.5019 2.55661 + vertex 1.51073 1.49758 2.56092 + vertex 1.51073 1.50256 2.56092 + endloop + endfacet + facet normal -0.997663 0.000517414 0.0683191 + outer loop + vertex 1.51073 1.49758 2.56092 + vertex 1.51105 1.49826 2.56557 + vertex 1.51073 1.50256 2.56092 + endloop + endfacet + facet normal -0.997723 -0.000440034 0.0674364 + outer loop + vertex 1.51073 1.50256 2.56092 + vertex 1.51105 1.49826 2.56557 + vertex 1.51105 1.50326 2.56557 + endloop + endfacet + facet normal -0.957662 -0.000539493 0.287893 + outer loop + vertex 1.51105 1.49826 2.56557 + vertex 1.51218 1.49988 2.56934 + vertex 1.51105 1.50326 2.56557 + endloop + endfacet + facet normal -0.956976 0.00222517 0.290158 + outer loop + vertex 1.51105 1.50326 2.56557 + vertex 1.51218 1.49988 2.56934 + vertex 1.5122 1.50488 2.56935 + endloop + endfacet + facet normal -0.730834 0.000776205 0.682555 + outer loop + vertex 1.51218 1.49988 2.56934 + vertex 1.51418 1.50279 2.57148 + vertex 1.5122 1.50488 2.56935 + endloop + endfacet + facet normal -0.732006 0.00251141 0.681294 + outer loop + vertex 1.51415 1.49779 2.57146 + vertex 1.51418 1.50279 2.57148 + vertex 1.51218 1.49988 2.56934 + endloop + endfacet + facet normal 0.142247 0 -0.989831 + outer loop + vertex 1.515 1.505 2.55439 + vertex 1.51234 1.50575 2.55401 + vertex 1.515 1.51 2.55439 + endloop + endfacet + facet normal 0.140653 -0.00578795 -0.990042 + outer loop + vertex 1.51233 1.50078 2.55404 + vertex 1.51234 1.50575 2.55401 + vertex 1.515 1.505 2.55439 + endloop + endfacet + facet normal -0.90572 -0.000879849 -0.423876 + outer loop + vertex 1.51233 1.50078 2.55404 + vertex 1.51112 1.5019 2.55661 + vertex 1.51234 1.50575 2.55401 + endloop + endfacet + facet normal -0.906573 0.00062827 -0.422049 + outer loop + vertex 1.51234 1.50575 2.55401 + vertex 1.51112 1.5019 2.55661 + vertex 1.51113 1.50688 2.5566 + endloop + endfacet + facet normal -0.99586 0.00145714 -0.0908871 + outer loop + vertex 1.51112 1.5019 2.55661 + vertex 1.51073 1.50256 2.56092 + vertex 1.51113 1.50688 2.5566 + endloop + endfacet + facet normal -0.995835 0.00117609 -0.0911661 + outer loop + vertex 1.51113 1.50688 2.5566 + vertex 1.51073 1.50256 2.56092 + vertex 1.51074 1.50757 2.56091 + endloop + endfacet + facet normal -0.997742 0.00152568 0.067145 + outer loop + vertex 1.51073 1.50256 2.56092 + vertex 1.51105 1.50326 2.56557 + vertex 1.51074 1.50757 2.56091 + endloop + endfacet + facet normal -0.997908 -0.00119748 0.0646368 + outer loop + vertex 1.51074 1.50757 2.56091 + vertex 1.51105 1.50326 2.56557 + vertex 1.51104 1.50825 2.56558 + endloop + endfacet + facet normal -0.956531 -0.00150964 0.291628 + outer loop + vertex 1.51105 1.50326 2.56557 + vertex 1.5122 1.50488 2.56935 + vertex 1.51104 1.50825 2.56558 + endloop + endfacet + facet normal -0.956211 -0.000223101 0.292678 + outer loop + vertex 1.51104 1.50825 2.56558 + vertex 1.5122 1.50488 2.56935 + vertex 1.5122 1.50988 2.56936 + endloop + endfacet + facet normal -0.728186 -0.00120795 0.685379 + outer loop + vertex 1.5122 1.50488 2.56935 + vertex 1.51421 1.50779 2.5715 + vertex 1.5122 1.50988 2.56936 + endloop + endfacet + facet normal -0.730281 0.00190046 0.683144 + outer loop + vertex 1.51418 1.50279 2.57148 + vertex 1.51421 1.50779 2.5715 + vertex 1.5122 1.50488 2.56935 + endloop + endfacet + facet normal 0.148532 0 -0.988908 + outer loop + vertex 1.515 1.51 2.55439 + vertex 1.51235 1.51073 2.55399 + vertex 1.515 1.515 2.55439 + endloop + endfacet + facet normal 0.147607 -0.00342219 -0.98904 + outer loop + vertex 1.51234 1.50575 2.55401 + vertex 1.51235 1.51073 2.55399 + vertex 1.515 1.51 2.55439 + endloop + endfacet + facet normal -0.906748 -0.000415725 -0.421673 + outer loop + vertex 1.51234 1.50575 2.55401 + vertex 1.51113 1.50688 2.5566 + vertex 1.51235 1.51073 2.55399 + endloop + endfacet + facet normal -0.908139 0.00206506 -0.418665 + outer loop + vertex 1.51235 1.51073 2.55399 + vertex 1.51113 1.50688 2.5566 + vertex 1.51114 1.51188 2.5566 + endloop + endfacet + facet normal -0.995816 0.0023521 -0.0913512 + outer loop + vertex 1.51113 1.50688 2.5566 + vertex 1.51074 1.50757 2.56091 + vertex 1.51114 1.51188 2.5566 + endloop + endfacet + facet normal -0.995482 -0.0012601 -0.0949411 + outer loop + vertex 1.51114 1.51188 2.5566 + vertex 1.51074 1.50757 2.56091 + vertex 1.51073 1.51257 2.5609 + endloop + endfacet + facet normal -0.99791 -0.00101942 0.0646108 + outer loop + vertex 1.51074 1.50757 2.56091 + vertex 1.51104 1.50825 2.56558 + vertex 1.51073 1.51257 2.5609 + endloop + endfacet + facet normal -0.99779 0.000971438 0.0664414 + outer loop + vertex 1.51073 1.51257 2.5609 + vertex 1.51104 1.50825 2.56558 + vertex 1.51105 1.51325 2.56557 + endloop + endfacet + facet normal -0.956367 0.00108353 0.292165 + outer loop + vertex 1.51104 1.50825 2.56558 + vertex 1.5122 1.50988 2.56936 + vertex 1.51105 1.51325 2.56557 + endloop + endfacet + facet normal -0.956659 -8.72106e-05 0.29121 + outer loop + vertex 1.51105 1.51325 2.56557 + vertex 1.5122 1.50988 2.56936 + vertex 1.5122 1.51488 2.56936 + endloop + endfacet + facet normal -0.727686 0.000376518 0.68591 + outer loop + vertex 1.5122 1.50988 2.56936 + vertex 1.51422 1.51278 2.5715 + vertex 1.5122 1.51488 2.56936 + endloop + endfacet + facet normal -0.727527 0.000141794 0.686079 + outer loop + vertex 1.51421 1.50779 2.5715 + vertex 1.51422 1.51278 2.5715 + vertex 1.5122 1.50988 2.56936 + endloop + endfacet + facet normal 0.156759 -0.00197795 -0.987635 + outer loop + vertex 1.515 1.515 2.55439 + vertex 1.51235 1.51574 2.55397 + vertex 1.515 1.52 2.55438 + endloop + endfacet + facet normal 0.156005 -0.00475645 -0.987745 + outer loop + vertex 1.51235 1.51073 2.55399 + vertex 1.51235 1.51574 2.55397 + vertex 1.515 1.515 2.55439 + endloop + endfacet + facet normal -0.908817 -0.00198574 -0.41719 + outer loop + vertex 1.51235 1.51073 2.55399 + vertex 1.51114 1.51188 2.5566 + vertex 1.51235 1.51574 2.55397 + endloop + endfacet + facet normal -0.908226 -0.00304498 -0.418469 + outer loop + vertex 1.51235 1.51574 2.55397 + vertex 1.51114 1.51188 2.5566 + vertex 1.51114 1.51689 2.55658 + endloop + endfacet + facet normal -0.995486 -0.00151797 -0.0949004 + outer loop + vertex 1.51114 1.51188 2.5566 + vertex 1.51073 1.51257 2.5609 + vertex 1.51114 1.51689 2.55658 + endloop + endfacet + facet normal -0.995786 0.0017269 -0.0916858 + outer loop + vertex 1.51114 1.51689 2.55658 + vertex 1.51073 1.51257 2.5609 + vertex 1.51074 1.51757 2.5609 + endloop + endfacet + facet normal -0.997795 0.00161726 0.0663471 + outer loop + vertex 1.51073 1.51257 2.5609 + vertex 1.51105 1.51325 2.56557 + vertex 1.51074 1.51757 2.5609 + endloop + endfacet + facet normal -0.997752 0.00229502 0.0669709 + outer loop + vertex 1.51074 1.51757 2.5609 + vertex 1.51105 1.51325 2.56557 + vertex 1.51106 1.51826 2.56557 + endloop + endfacet + facet normal -0.956953 0.00240578 0.290232 + outer loop + vertex 1.51105 1.51325 2.56557 + vertex 1.5122 1.51488 2.56936 + vertex 1.51106 1.51826 2.56557 + endloop + endfacet + facet normal -0.958512 -0.00395482 0.285026 + outer loop + vertex 1.51106 1.51826 2.56557 + vertex 1.5122 1.51488 2.56936 + vertex 1.51218 1.51986 2.56937 + endloop + endfacet + facet normal -0.728965 -0.00358965 0.684542 + outer loop + vertex 1.5122 1.51488 2.56936 + vertex 1.51419 1.51777 2.5715 + vertex 1.51218 1.51986 2.56937 + endloop + endfacet + facet normal -0.729344 -0.00303188 0.68414 + outer loop + vertex 1.51422 1.51278 2.5715 + vertex 1.51419 1.51777 2.5715 + vertex 1.5122 1.51488 2.56936 + endloop + endfacet + facet normal 0.153476 -0.0177609 -0.987993 + outer loop + vertex 1.515 1.52 2.55438 + vertex 1.51235 1.52074 2.55396 + vertex 1.515 1.525 2.55429 + endloop + endfacet + facet normal 0.157667 -0.00255763 -0.987489 + outer loop + vertex 1.51235 1.51574 2.55397 + vertex 1.51235 1.52074 2.55396 + vertex 1.515 1.52 2.55438 + endloop + endfacet + facet normal -0.907687 0.000189477 -0.419647 + outer loop + vertex 1.51235 1.51574 2.55397 + vertex 1.51114 1.51689 2.55658 + vertex 1.51235 1.52074 2.55396 + endloop + endfacet + facet normal -0.909456 0.00337263 -0.415787 + outer loop + vertex 1.51235 1.52074 2.55396 + vertex 1.51114 1.51689 2.55658 + vertex 1.51116 1.5219 2.55658 + endloop + endfacet + facet normal -0.995757 0.00345055 -0.0919545 + outer loop + vertex 1.51114 1.51689 2.55658 + vertex 1.51074 1.51757 2.5609 + vertex 1.51116 1.5219 2.55658 + endloop + endfacet + facet normal -0.995813 0.00408806 -0.0913218 + outer loop + vertex 1.51116 1.5219 2.55658 + vertex 1.51074 1.51757 2.5609 + vertex 1.51076 1.52257 2.56091 + endloop + endfacet + facet normal -0.997763 0.00396035 0.0667263 + outer loop + vertex 1.51074 1.51757 2.5609 + vertex 1.51106 1.51826 2.56557 + vertex 1.51076 1.52257 2.56091 + endloop + endfacet + facet normal -0.997799 0.00340958 0.0662185 + outer loop + vertex 1.51076 1.52257 2.56091 + vertex 1.51106 1.51826 2.56557 + vertex 1.51107 1.52325 2.56557 + endloop + endfacet + facet normal -0.959337 0.00321556 0.282246 + outer loop + vertex 1.51106 1.51826 2.56557 + vertex 1.51218 1.51986 2.56937 + vertex 1.51107 1.52325 2.56557 + endloop + endfacet + facet normal -0.959737 0.00157471 0.280895 + outer loop + vertex 1.51107 1.52325 2.56557 + vertex 1.51218 1.51986 2.56937 + vertex 1.51218 1.52487 2.56933 + endloop + endfacet + facet normal -0.736128 0.004282 0.676829 + outer loop + vertex 1.51218 1.51986 2.56937 + vertex 1.51414 1.52276 2.57148 + vertex 1.51218 1.52487 2.56933 + endloop + endfacet + facet normal -0.729693 -0.00509561 0.683756 + outer loop + vertex 1.51419 1.51777 2.5715 + vertex 1.51414 1.52276 2.57148 + vertex 1.51218 1.51986 2.56937 + endloop + endfacet + facet normal 0.125526 -0.00198687 -0.992088 + outer loop + vertex 1.515 1.525 2.55429 + vertex 1.51237 1.52575 2.55396 + vertex 1.515 1.53 2.55428 + endloop + endfacet + facet normal 0.125985 -0.00034304 -0.992032 + outer loop + vertex 1.51235 1.52074 2.55396 + vertex 1.51237 1.52575 2.55396 + vertex 1.515 1.525 2.55429 + endloop + endfacet + facet normal -0.909546 0.00283775 -0.415593 + outer loop + vertex 1.51235 1.52074 2.55396 + vertex 1.51116 1.5219 2.55658 + vertex 1.51237 1.52575 2.55396 + endloop + endfacet + facet normal -0.913309 0.00978389 -0.407149 + outer loop + vertex 1.51237 1.52575 2.55396 + vertex 1.51116 1.5219 2.55658 + vertex 1.5112 1.5269 2.55661 + endloop + endfacet + facet normal -0.995717 0.00872097 -0.0920369 + outer loop + vertex 1.51116 1.5219 2.55658 + vertex 1.51076 1.52257 2.56091 + vertex 1.5112 1.5269 2.55661 + endloop + endfacet + facet normal -0.995995 0.012191 -0.0885749 + outer loop + vertex 1.5112 1.5269 2.55661 + vertex 1.51076 1.52257 2.56091 + vertex 1.51082 1.52757 2.56092 + endloop + endfacet + facet normal -0.997816 0.0117216 0.065008 + outer loop + vertex 1.51076 1.52257 2.56091 + vertex 1.51107 1.52325 2.56557 + vertex 1.51082 1.52757 2.56092 + endloop + endfacet + facet normal -0.998001 0.00905771 0.0625436 + outer loop + vertex 1.51082 1.52757 2.56092 + vertex 1.51107 1.52325 2.56557 + vertex 1.51112 1.52825 2.56556 + endloop + endfacet + facet normal -0.960584 0.00927837 0.277836 + outer loop + vertex 1.51107 1.52325 2.56557 + vertex 1.51218 1.52487 2.56933 + vertex 1.51112 1.52825 2.56556 + endloop + endfacet + facet normal -0.963256 -0.00187643 0.268578 + outer loop + vertex 1.51112 1.52825 2.56556 + vertex 1.51218 1.52487 2.56933 + vertex 1.51217 1.52985 2.56932 + endloop + endfacet + facet normal -0.744812 -0.000483749 0.667274 + outer loop + vertex 1.51218 1.52487 2.56933 + vertex 1.51407 1.52776 2.57144 + vertex 1.51217 1.52985 2.56932 + endloop + endfacet + facet normal -0.741094 -0.00590841 0.671376 + outer loop + vertex 1.51414 1.52276 2.57148 + vertex 1.51407 1.52776 2.57144 + vertex 1.51218 1.52487 2.56933 + endloop + endfacet + facet normal 0.122118 0.0396755 -0.991722 + outer loop + vertex 1.515 1.53 2.55428 + vertex 1.5124 1.53073 2.55399 + vertex 1.515 1.535 2.55448 + endloop + endfacet + facet normal 0.112913 0.0059309 -0.993587 + outer loop + vertex 1.51237 1.52575 2.55396 + vertex 1.5124 1.53073 2.55399 + vertex 1.515 1.53 2.55428 + endloop + endfacet + facet normal -0.913576 0.00821668 -0.406585 + outer loop + vertex 1.51237 1.52575 2.55396 + vertex 1.5112 1.5269 2.55661 + vertex 1.5124 1.53073 2.55399 + endloop + endfacet + facet normal -0.914939 0.0107927 -0.403447 + outer loop + vertex 1.5124 1.53073 2.55399 + vertex 1.5112 1.5269 2.55661 + vertex 1.51125 1.53187 2.55661 + endloop + endfacet + facet normal -0.996015 0.0114125 -0.0884557 + outer loop + vertex 1.5112 1.5269 2.55661 + vertex 1.51082 1.52757 2.56092 + vertex 1.51125 1.53187 2.55661 + endloop + endfacet + facet normal -0.996323 0.0156836 -0.0842287 + outer loop + vertex 1.51125 1.53187 2.55661 + vertex 1.51082 1.52757 2.56092 + vertex 1.5109 1.53255 2.56092 + endloop + endfacet + facet normal -0.997978 0.0159262 0.0615261 + outer loop + vertex 1.51082 1.52757 2.56092 + vertex 1.51112 1.52825 2.56556 + vertex 1.5109 1.53255 2.56092 + endloop + endfacet + facet normal -0.99829 0.0113781 0.0573309 + outer loop + vertex 1.5109 1.53255 2.56092 + vertex 1.51112 1.52825 2.56556 + vertex 1.51117 1.53323 2.56555 + endloop + endfacet + facet normal -0.964636 0.0113529 0.263343 + outer loop + vertex 1.51112 1.52825 2.56556 + vertex 1.51217 1.52985 2.56932 + vertex 1.51117 1.53323 2.56555 + endloop + endfacet + facet normal -0.965814 0.00634043 0.25916 + outer loop + vertex 1.51117 1.53323 2.56555 + vertex 1.51217 1.52985 2.56932 + vertex 1.51219 1.53486 2.56928 + endloop + endfacet + facet normal -0.756722 0.00863655 0.65368 + outer loop + vertex 1.51217 1.52985 2.56932 + vertex 1.514 1.53276 2.5714 + vertex 1.51219 1.53486 2.56928 + endloop + endfacet + facet normal -0.747138 -0.00525478 0.664649 + outer loop + vertex 1.51407 1.52776 2.57144 + vertex 1.514 1.53276 2.5714 + vertex 1.51217 1.52985 2.56932 + endloop + endfacet + facet normal 0.17685 0.0236001 -0.983955 + outer loop + vertex 1.515 1.535 2.55448 + vertex 1.51245 1.53567 2.55404 + vertex 1.515 1.54 2.5546 + endloop + endfacet + facet normal 0.172912 0.00797142 -0.984905 + outer loop + vertex 1.5124 1.53073 2.55399 + vertex 1.51245 1.53567 2.55404 + vertex 1.515 1.535 2.55448 + endloop + endfacet + facet normal -0.914358 0.0141596 -0.404658 + outer loop + vertex 1.5124 1.53073 2.55399 + vertex 1.51125 1.53187 2.55661 + vertex 1.51245 1.53567 2.55404 + endloop + endfacet + facet normal -0.91604 0.0173631 -0.400712 + outer loop + vertex 1.51245 1.53567 2.55404 + vertex 1.51125 1.53187 2.55661 + vertex 1.51135 1.5368 2.55661 + endloop + endfacet + facet normal -0.996227 0.0188322 -0.0847206 + outer loop + vertex 1.51125 1.53187 2.55661 + vertex 1.5109 1.53255 2.56092 + vertex 1.51135 1.5368 2.55661 + endloop + endfacet + facet normal -0.996329 0.0204615 -0.0831215 + outer loop + vertex 1.51135 1.5368 2.55661 + vertex 1.5109 1.53255 2.56092 + vertex 1.511 1.5375 2.5609 + endloop + endfacet + facet normal -0.998216 0.0209697 0.0559096 + outer loop + vertex 1.5109 1.53255 2.56092 + vertex 1.51117 1.53323 2.56555 + vertex 1.511 1.5375 2.5609 + endloop + endfacet + facet normal -0.998484 0.0170531 0.0523278 + outer loop + vertex 1.511 1.5375 2.5609 + vertex 1.51117 1.53323 2.56555 + vertex 1.51126 1.5382 2.56553 + endloop + endfacet + facet normal -0.966884 0.0174236 0.25462 + outer loop + vertex 1.51117 1.53323 2.56555 + vertex 1.51219 1.53486 2.56928 + vertex 1.51126 1.5382 2.56553 + endloop + endfacet + facet normal -0.968821 0.00899783 0.247599 + outer loop + vertex 1.51126 1.5382 2.56553 + vertex 1.51219 1.53486 2.56928 + vertex 1.51223 1.53985 2.56925 + endloop + endfacet + facet normal -0.768678 0.00997797 0.639559 + outer loop + vertex 1.51219 1.53486 2.56928 + vertex 1.51395 1.53776 2.57135 + vertex 1.51223 1.53985 2.56925 + endloop + endfacet + facet normal -0.761359 -0.000749337 0.64833 + outer loop + vertex 1.514 1.53276 2.5714 + vertex 1.51395 1.53776 2.57135 + vertex 1.51219 1.53486 2.56928 + endloop + endfacet + facet normal 0.218231 -0.019494 -0.975702 + outer loop + vertex 1.515 1.54 2.5546 + vertex 1.51252 1.54061 2.55403 + vertex 1.515 1.545 2.5545 + endloop + endfacet + facet normal 0.221863 -0.00402528 -0.975069 + outer loop + vertex 1.51245 1.53567 2.55404 + vertex 1.51252 1.54061 2.55403 + vertex 1.515 1.54 2.5546 + endloop + endfacet + facet normal -0.916991 0.0119316 -0.39873 + outer loop + vertex 1.51245 1.53567 2.55404 + vertex 1.51135 1.5368 2.55661 + vertex 1.51252 1.54061 2.55403 + endloop + endfacet + facet normal -0.920987 0.0197009 -0.389095 + outer loop + vertex 1.51252 1.54061 2.55403 + vertex 1.51135 1.5368 2.55661 + vertex 1.51146 1.54173 2.5566 + endloop + endfacet + facet normal -0.996259 0.0224854 -0.0834444 + outer loop + vertex 1.51135 1.5368 2.55661 + vertex 1.511 1.5375 2.5609 + vertex 1.51146 1.54173 2.5566 + endloop + endfacet + facet normal -0.996337 0.0238312 -0.0821277 + outer loop + vertex 1.51146 1.54173 2.5566 + vertex 1.511 1.5375 2.5609 + vertex 1.51113 1.54245 2.56086 + endloop + endfacet + facet normal -0.998379 0.0250365 0.051106 + outer loop + vertex 1.511 1.5375 2.5609 + vertex 1.51126 1.5382 2.56553 + vertex 1.51113 1.54245 2.56086 + endloop + endfacet + facet normal -0.998521 0.0230104 0.0492677 + outer loop + vertex 1.51113 1.54245 2.56086 + vertex 1.51126 1.5382 2.56553 + vertex 1.51137 1.54319 2.56548 + endloop + endfacet + facet normal -0.97018 0.0243729 0.241157 + outer loop + vertex 1.51126 1.5382 2.56553 + vertex 1.51223 1.53985 2.56925 + vertex 1.51137 1.54319 2.56548 + endloop + endfacet + facet normal -0.972953 0.0118442 0.2307 + outer loop + vertex 1.51137 1.54319 2.56548 + vertex 1.51223 1.53985 2.56925 + vertex 1.51227 1.54483 2.5692 + endloop + endfacet + facet normal -0.783643 0.0136456 0.621062 + outer loop + vertex 1.51223 1.53985 2.56925 + vertex 1.51391 1.54273 2.57131 + vertex 1.51227 1.54483 2.5692 + endloop + endfacet + facet normal -0.773954 -0.0007368 0.633241 + outer loop + vertex 1.51395 1.53776 2.57135 + vertex 1.51391 1.54273 2.57131 + vertex 1.51223 1.53985 2.56925 + endloop + endfacet + facet normal 0.20163 0.00387644 -0.979454 + outer loop + vertex 1.515 1.545 2.5545 + vertex 1.51258 1.54559 2.554 + vertex 1.515 1.55 2.55452 + endloop + endfacet + facet normal 0.198811 -0.00807312 -0.980005 + outer loop + vertex 1.51252 1.54061 2.55403 + vertex 1.51258 1.54559 2.554 + vertex 1.515 1.545 2.5545 + endloop + endfacet + facet normal -0.922787 0.00917067 -0.385201 + outer loop + vertex 1.51252 1.54061 2.55403 + vertex 1.51146 1.54173 2.5566 + vertex 1.51258 1.54559 2.554 + endloop + endfacet + facet normal -0.925539 0.0145574 -0.378373 + outer loop + vertex 1.51258 1.54559 2.554 + vertex 1.51146 1.54173 2.5566 + vertex 1.51156 1.54673 2.55655 + endloop + endfacet + facet normal -0.99651 0.0188821 -0.0813123 + outer loop + vertex 1.51146 1.54173 2.5566 + vertex 1.51113 1.54245 2.56086 + vertex 1.51156 1.54673 2.55655 + endloop + endfacet + facet normal -0.996829 0.0245951 -0.075674 + outer loop + vertex 1.51156 1.54673 2.55655 + vertex 1.51113 1.54245 2.56086 + vertex 1.51125 1.54745 2.56082 + endloop + endfacet + facet normal -0.998477 0.025657 0.0488422 + outer loop + vertex 1.51113 1.54245 2.56086 + vertex 1.51137 1.54319 2.56548 + vertex 1.51125 1.54745 2.56082 + endloop + endfacet + facet normal -0.99864 0.0232617 0.0466527 + outer loop + vertex 1.51125 1.54745 2.56082 + vertex 1.51137 1.54319 2.56548 + vertex 1.51149 1.5482 2.56542 + endloop + endfacet + facet normal -0.973968 0.0245604 0.225352 + outer loop + vertex 1.51137 1.54319 2.56548 + vertex 1.51227 1.54483 2.5692 + vertex 1.51149 1.5482 2.56542 + endloop + endfacet + facet normal -0.977973 0.00493604 0.208674 + outer loop + vertex 1.51149 1.5482 2.56542 + vertex 1.51227 1.54483 2.5692 + vertex 1.51229 1.54978 2.56914 + endloop + endfacet + facet normal -0.812526 0.00934882 0.582851 + outer loop + vertex 1.51227 1.54483 2.5692 + vertex 1.51381 1.54764 2.5713 + vertex 1.51229 1.54978 2.56914 + endloop + endfacet + facet normal -0.797158 -0.0145305 0.603596 + outer loop + vertex 1.51391 1.54273 2.57131 + vertex 1.51381 1.54764 2.5713 + vertex 1.51227 1.54483 2.5692 + endloop + endfacet + facet normal 0.201462 0.0391551 -0.978713 + outer loop + vertex 1.515 1.55 2.55452 + vertex 1.51263 1.55068 2.55406 + vertex 1.515 1.555 2.55472 + endloop + endfacet + facet normal 0.19322 0.0086882 -0.981117 + outer loop + vertex 1.51258 1.54559 2.554 + vertex 1.51263 1.55068 2.55406 + vertex 1.515 1.55 2.55452 + endloop + endfacet + facet normal -0.925939 0.0121829 -0.377476 + outer loop + vertex 1.51258 1.54559 2.554 + vertex 1.51156 1.54673 2.55655 + vertex 1.51263 1.55068 2.55406 + endloop + endfacet + facet normal -0.927084 0.0143161 -0.37458 + outer loop + vertex 1.51263 1.55068 2.55406 + vertex 1.51156 1.54673 2.55655 + vertex 1.51164 1.55183 2.55655 + endloop + endfacet + facet normal -0.997138 0.0151061 -0.0740798 + outer loop + vertex 1.51156 1.54673 2.55655 + vertex 1.51125 1.54745 2.56082 + vertex 1.51164 1.55183 2.55655 + endloop + endfacet + facet normal -0.997542 0.0227328 -0.0662856 + outer loop + vertex 1.51164 1.55183 2.55655 + vertex 1.51125 1.54745 2.56082 + vertex 1.51137 1.55254 2.56081 + endloop + endfacet + facet normal -0.998646 0.0228851 0.046714 + outer loop + vertex 1.51125 1.54745 2.56082 + vertex 1.51149 1.5482 2.56542 + vertex 1.51137 1.55254 2.56081 + endloop + endfacet + facet normal -0.998866 0.0194256 0.0434621 + outer loop + vertex 1.51137 1.55254 2.56081 + vertex 1.51149 1.5482 2.56542 + vertex 1.51158 1.55323 2.56538 + endloop + endfacet + facet normal -0.97909 0.0202674 0.202415 + outer loop + vertex 1.51149 1.5482 2.56542 + vertex 1.51229 1.54978 2.56914 + vertex 1.51158 1.55323 2.56538 + endloop + endfacet + facet normal -0.98403 -0.00741378 0.17785 + outer loop + vertex 1.51158 1.55323 2.56538 + vertex 1.51229 1.54978 2.56914 + vertex 1.51224 1.5546 2.56906 + endloop + endfacet + facet normal -0.843626 -0.000225909 0.536931 + outer loop + vertex 1.51229 1.54978 2.56914 + vertex 1.5136 1.55247 2.5712 + vertex 1.51224 1.5546 2.56906 + endloop + endfacet + facet normal -0.828243 -0.0251885 0.559802 + outer loop + vertex 1.51381 1.54764 2.5713 + vertex 1.5136 1.55247 2.5712 + vertex 1.51229 1.54978 2.56914 + endloop + endfacet + facet normal 0.220853 0.0039065 -0.975299 + outer loop + vertex 1.515 1.555 2.55472 + vertex 1.51264 1.55585 2.55419 + vertex 1.515 1.56 2.55474 + endloop + endfacet + facet normal 0.227685 0.0239395 -0.97344 + outer loop + vertex 1.51263 1.55068 2.55406 + vertex 1.51264 1.55585 2.55419 + vertex 1.515 1.555 2.55472 + endloop + endfacet + facet normal -0.927445 0.0122309 -0.37376 + outer loop + vertex 1.51263 1.55068 2.55406 + vertex 1.51164 1.55183 2.55655 + vertex 1.51264 1.55585 2.55419 + endloop + endfacet + facet normal -0.933367 0.0228558 -0.358196 + outer loop + vertex 1.51264 1.55585 2.55419 + vertex 1.51164 1.55183 2.55655 + vertex 1.5117 1.55699 2.5567 + endloop + endfacet + facet normal -0.997766 0.0152348 -0.0650487 + outer loop + vertex 1.51164 1.55183 2.55655 + vertex 1.51137 1.55254 2.56081 + vertex 1.5117 1.55699 2.5567 + endloop + endfacet + facet normal -0.998094 0.0221353 -0.0576076 + outer loop + vertex 1.5117 1.55699 2.5567 + vertex 1.51137 1.55254 2.56081 + vertex 1.51147 1.55761 2.56092 + endloop + endfacet + facet normal -0.99886 0.0198899 0.0433917 + outer loop + vertex 1.51137 1.55254 2.56081 + vertex 1.51158 1.55323 2.56538 + vertex 1.51147 1.55761 2.56092 + endloop + endfacet + facet normal -0.99909 0.0159687 0.0395481 + outer loop + vertex 1.51147 1.55761 2.56092 + vertex 1.51158 1.55323 2.56538 + vertex 1.51166 1.55825 2.56539 + endloop + endfacet + facet normal -0.985402 0.0155205 0.169537 + outer loop + vertex 1.51158 1.55323 2.56538 + vertex 1.51224 1.5546 2.56906 + vertex 1.51166 1.55825 2.56539 + endloop + endfacet + facet normal -0.986022 0.0120469 0.16618 + outer loop + vertex 1.51166 1.55825 2.56539 + vertex 1.51224 1.5546 2.56906 + vertex 1.51228 1.55953 2.56896 + endloop + endfacet + facet normal -0.894002 0.0169753 0.447741 + outer loop + vertex 1.51224 1.5546 2.56906 + vertex 1.51322 1.55662 2.57096 + vertex 1.51228 1.55953 2.56896 + endloop + endfacet + facet normal -0.863744 -0.0484662 0.501595 + outer loop + vertex 1.5136 1.55247 2.5712 + vertex 1.51322 1.55662 2.57096 + vertex 1.51224 1.5546 2.56906 + endloop + endfacet + facet normal 0.136767 -0.0178046 -0.990443 + outer loop + vertex 1.515 1.56 2.55474 + vertex 1.51267 1.56105 2.5544 + vertex 1.515 1.565 2.55465 + endloop + endfacet + facet normal 0.16163 0.0390305 -0.986079 + outer loop + vertex 1.51264 1.55585 2.55419 + vertex 1.51267 1.56105 2.5544 + vertex 1.515 1.56 2.55474 + endloop + endfacet + facet normal -0.933957 0.0194114 -0.356859 + outer loop + vertex 1.51264 1.55585 2.55419 + vertex 1.5117 1.55699 2.5567 + vertex 1.51267 1.56105 2.5544 + endloop + endfacet + facet normal -0.945139 0.0406467 -0.324128 + outer loop + vertex 1.51267 1.56105 2.5544 + vertex 1.5117 1.55699 2.5567 + vertex 1.5118 1.56198 2.55706 + endloop + endfacet + facet normal -0.99808 0.0226016 -0.0576754 + outer loop + vertex 1.5117 1.55699 2.5567 + vertex 1.51147 1.55761 2.56092 + vertex 1.5118 1.56198 2.55706 + endloop + endfacet + facet normal -0.99812 0.0235768 -0.0565756 + outer loop + vertex 1.5118 1.56198 2.55706 + vertex 1.51147 1.55761 2.56092 + vertex 1.51158 1.56247 2.56115 + endloop + endfacet + facet normal -0.999053 0.0191028 0.0390964 + outer loop + vertex 1.51147 1.55761 2.56092 + vertex 1.51166 1.55825 2.56539 + vertex 1.51158 1.56247 2.56115 + endloop + endfacet + facet normal -0.999439 0.0114303 0.0314667 + outer loop + vertex 1.51158 1.56247 2.56115 + vertex 1.51166 1.55825 2.56539 + vertex 1.51172 1.5633 2.56543 + endloop + endfacet + facet normal -0.985938 0.010295 0.166794 + outer loop + vertex 1.51166 1.55825 2.56539 + vertex 1.51228 1.55953 2.56896 + vertex 1.51172 1.5633 2.56543 + endloop + endfacet + facet normal -0.988919 -0.00750076 0.148268 + outer loop + vertex 1.51172 1.5633 2.56543 + vertex 1.51228 1.55953 2.56896 + vertex 1.51223 1.56476 2.56892 + endloop + endfacet + facet normal -0.81698 -0.0022174 0.576662 + outer loop + vertex 1.51228 1.55953 2.56896 + vertex 1.51375 1.56137 2.57105 + vertex 1.51223 1.56476 2.56892 + endloop + endfacet + facet normal -0.848074 0.0835536 0.523249 + outer loop + vertex 1.51322 1.55662 2.57096 + vertex 1.51375 1.56137 2.57105 + vertex 1.51228 1.55953 2.56896 + endloop + endfacet + facet normal -0.0795182 0.00399272 -0.996825 + outer loop + vertex 1.515 1.565 2.55465 + vertex 1.51288 1.56678 2.55483 + vertex 1.515 1.57 2.55467 + endloop + endfacet + facet normal -0.019953 0.0750025 -0.996984 + outer loop + vertex 1.51267 1.56105 2.5544 + vertex 1.51288 1.56678 2.55483 + vertex 1.515 1.565 2.55465 + endloop + endfacet + facet normal -0.942275 0.0588737 -0.329624 + outer loop + vertex 1.51267 1.56105 2.5544 + vertex 1.5118 1.56198 2.55706 + vertex 1.51288 1.56678 2.55483 + endloop + endfacet + facet normal -0.948197 0.0693284 -0.310025 + outer loop + vertex 1.51288 1.56678 2.55483 + vertex 1.5118 1.56198 2.55706 + vertex 1.51186 1.56601 2.55776 + endloop + endfacet + facet normal -0.998053 0.0257164 -0.0568275 + outer loop + vertex 1.5118 1.56198 2.55706 + vertex 1.51158 1.56247 2.56115 + vertex 1.51186 1.56601 2.55776 + endloop + endfacet + facet normal -0.998026 0.0249362 -0.0576396 + outer loop + vertex 1.51186 1.56601 2.55776 + vertex 1.51158 1.56247 2.56115 + vertex 1.51169 1.56724 2.56126 + endloop + endfacet + facet normal -0.999308 0.0230216 0.0292191 + outer loop + vertex 1.51158 1.56247 2.56115 + vertex 1.51172 1.5633 2.56543 + vertex 1.51169 1.56724 2.56126 + endloop + endfacet + facet normal -0.999946 -0.0101578 -0.00214205 + outer loop + vertex 1.51169 1.56724 2.56126 + vertex 1.51172 1.5633 2.56543 + vertex 1.51167 1.56835 2.56555 + endloop + endfacet + facet normal -0.988479 -0.0135957 0.150747 + outer loop + vertex 1.51172 1.5633 2.56543 + vertex 1.51223 1.56476 2.56892 + vertex 1.51167 1.56835 2.56555 + endloop + endfacet + facet normal -0.992569 -0.0528292 0.109617 + outer loop + vertex 1.51167 1.56835 2.56555 + vertex 1.51223 1.56476 2.56892 + vertex 1.51196 1.56992 2.56893 + endloop + endfacet + facet normal -0.864029 -0.0469252 0.501251 + outer loop + vertex 1.51223 1.56476 2.56892 + vertex 1.51324 1.56715 2.57088 + vertex 1.51196 1.56992 2.56893 + endloop + endfacet + facet normal -0.856233 -0.0599401 0.513101 + outer loop + vertex 1.51375 1.56137 2.57105 + vertex 1.51324 1.56715 2.57088 + vertex 1.51223 1.56476 2.56892 + endloop + endfacet + facet normal -0.181376 0.0719191 -0.980781 + outer loop + vertex 1.515 1.57 2.55467 + vertex 1.51288 1.56678 2.55483 + vertex 1.515 1.5745 2.555 + endloop + endfacet + facet normal 0.134715 -0.550351 -0.823994 + outer loop + vertex 1.515 1.5745 2.555 + vertex 1.51237 1.57101 2.5569 + vertex 1.51327 1.57535 2.55415 + endloop + endfacet + facet normal -0.745277 0.219061 -0.629742 + outer loop + vertex 1.515 1.5745 2.555 + vertex 1.51288 1.56678 2.55483 + vertex 1.51237 1.57101 2.5569 + endloop + endfacet + facet normal -0.947499 0.0416922 -0.317028 + outer loop + vertex 1.51288 1.56678 2.55483 + vertex 1.51186 1.56601 2.55776 + vertex 1.51237 1.57101 2.5569 + endloop + endfacet + facet normal -0.992999 0.0874207 -0.0794364 + outer loop + vertex 1.51186 1.56601 2.55776 + vertex 1.51169 1.56724 2.56126 + vertex 1.51237 1.57101 2.5569 + endloop + endfacet + facet normal -0.989423 0.0113791 -0.144609 + outer loop + vertex 1.51237 1.57101 2.5569 + vertex 1.51169 1.56724 2.56126 + vertex 1.5117 1.57208 2.56157 + endloop + endfacet + facet normal -0.999982 0.00260827 -0.00542515 + outer loop + vertex 1.51169 1.56724 2.56126 + vertex 1.51167 1.56835 2.56555 + vertex 1.5117 1.57208 2.56157 + endloop + endfacet + facet normal -0.999099 -0.0267288 -0.0329634 + outer loop + vertex 1.5117 1.57208 2.56157 + vertex 1.51167 1.56835 2.56555 + vertex 1.51153 1.57315 2.56578 + endloop + endfacet + facet normal -0.994371 -0.0331543 0.100634 + outer loop + vertex 1.51167 1.56835 2.56555 + vertex 1.51196 1.56992 2.56893 + vertex 1.51153 1.57315 2.56578 + endloop + endfacet + facet normal -0.994624 -0.0369979 0.0967184 + outer loop + vertex 1.51153 1.57315 2.56578 + vertex 1.51196 1.56992 2.56893 + vertex 1.51179 1.57452 2.56895 + endloop + endfacet + facet normal -0.899605 -0.0348134 0.435315 + outer loop + vertex 1.51196 1.56992 2.56893 + vertex 1.51279 1.57203 2.57081 + vertex 1.51179 1.57452 2.56895 + endloop + endfacet + facet normal -0.878846 -0.0749901 0.471175 + outer loop + vertex 1.51324 1.56715 2.57088 + vertex 1.51279 1.57203 2.57081 + vertex 1.51196 1.56992 2.56893 + endloop + endfacet + facet normal -0.957332 -0.108652 -0.267789 + outer loop + vertex 1.51327 1.57535 2.55415 + vertex 1.51211 1.57641 2.55785 + vertex 1.51286 1.57871 2.55424 + endloop + endfacet + facet normal -0.953973 0.00665151 -0.299817 + outer loop + vertex 1.51237 1.57101 2.5569 + vertex 1.51211 1.57641 2.55785 + vertex 1.51327 1.57535 2.55415 + endloop + endfacet + facet normal -0.990332 -0.0237773 -0.136667 + outer loop + vertex 1.51237 1.57101 2.5569 + vertex 1.5117 1.57208 2.56157 + vertex 1.51211 1.57641 2.55785 + endloop + endfacet + facet normal -0.993511 -0.00374106 -0.113676 + outer loop + vertex 1.51211 1.57641 2.55785 + vertex 1.5117 1.57208 2.56157 + vertex 1.51159 1.57619 2.56242 + endloop + endfacet + facet normal -0.999196 -0.0202786 -0.0345945 + outer loop + vertex 1.5117 1.57208 2.56157 + vertex 1.51153 1.57315 2.56578 + vertex 1.51159 1.57619 2.56242 + endloop + endfacet + facet normal -0.999911 0.0123009 -0.00512237 + outer loop + vertex 1.51159 1.57619 2.56242 + vertex 1.51153 1.57315 2.56578 + vertex 1.51159 1.57784 2.56578 + endloop + endfacet + facet normal -0.99707 0.0122823 0.0754955 + outer loop + vertex 1.51153 1.57315 2.56578 + vertex 1.51179 1.57452 2.56895 + vertex 1.51159 1.57784 2.56578 + endloop + endfacet + facet normal -0.972041 0.128995 0.196208 + outer loop + vertex 1.51159 1.57784 2.56578 + vertex 1.51179 1.57452 2.56895 + vertex 1.51235 1.57863 2.56902 + endloop + endfacet + facet normal -0.924139 0.119363 0.362931 + outer loop + vertex 1.51179 1.57452 2.56895 + vertex 1.51259 1.57563 2.57061 + vertex 1.51235 1.57863 2.56902 + endloop + endfacet + facet normal -0.895007 -0.0255029 0.445323 + outer loop + vertex 1.51279 1.57203 2.57081 + vertex 1.51259 1.57563 2.57061 + vertex 1.51179 1.57452 2.56895 + endloop + endfacet + facet normal -0.97496 -0.0286335 -0.22053 + outer loop + vertex 1.51286 1.57871 2.55424 + vertex 1.51211 1.57641 2.55785 + vertex 1.51231 1.58047 2.55645 + endloop + endfacet + facet normal -0.99237 -0.00284104 -0.123263 + outer loop + vertex 1.51231 1.58047 2.55645 + vertex 1.51176 1.58127 2.56081 + vertex 1.51227 1.58333 2.55669 + endloop + endfacet + facet normal -0.992179 0.00524536 -0.124716 + outer loop + vertex 1.51231 1.58047 2.55645 + vertex 1.51211 1.57641 2.55785 + vertex 1.51176 1.58127 2.56081 + endloop + endfacet + facet normal -0.993528 -0.00166056 -0.113577 + outer loop + vertex 1.51211 1.57641 2.55785 + vertex 1.51159 1.57619 2.56242 + vertex 1.51176 1.58127 2.56081 + endloop + endfacet + facet normal -0.999452 0.0300766 -0.0138047 + outer loop + vertex 1.51159 1.57619 2.56242 + vertex 1.51159 1.57784 2.56578 + vertex 1.51176 1.58127 2.56081 + endloop + endfacet + facet normal -0.991202 0.122455 0.0502259 + outer loop + vertex 1.51176 1.58127 2.56081 + vertex 1.51159 1.57784 2.56578 + vertex 1.51228 1.58324 2.56614 + endloop + endfacet + facet normal -0.634021 0.329667 0.699526 + outer loop + vertex 1.51484 1.58258 2.56941 + vertex 1.51235 1.57863 2.56902 + vertex 1.51382 1.57814 2.57058 + endloop + endfacet + facet normal -0.692606 0.374744 0.616331 + outer loop + vertex 1.51484 1.58258 2.56941 + vertex 1.51228 1.58324 2.56614 + vertex 1.51235 1.57863 2.56902 + endloop + endfacet + facet normal -0.973349 0.11019 0.201121 + outer loop + vertex 1.51228 1.58324 2.56614 + vertex 1.51159 1.57784 2.56578 + vertex 1.51235 1.57863 2.56902 + endloop + endfacet + facet normal -0.637761 0.32081 0.700244 + outer loop + vertex 1.51382 1.57814 2.57058 + vertex 1.51235 1.57863 2.56902 + vertex 1.51259 1.57563 2.57061 + endloop + endfacet + facet normal -0.978693 0.0199635 -0.204358 + outer loop + vertex 1.51271 1.58585 2.55485 + vertex 1.51198 1.58655 2.5584 + vertex 1.51271 1.58871 2.55513 + endloop + endfacet + facet normal -0.978622 0.0211438 -0.204577 + outer loop + vertex 1.51227 1.58333 2.55669 + vertex 1.51198 1.58655 2.5584 + vertex 1.51271 1.58585 2.55485 + endloop + endfacet + facet normal -0.991168 -0.0190405 -0.131235 + outer loop + vertex 1.51227 1.58333 2.55669 + vertex 1.51176 1.58127 2.56081 + vertex 1.51198 1.58655 2.5584 + endloop + endfacet + facet normal -0.997336 0.00803649 -0.0725001 + outer loop + vertex 1.51176 1.58127 2.56081 + vertex 1.51168 1.58606 2.56255 + vertex 1.51198 1.58655 2.5584 + endloop + endfacet + facet normal -0.99116 -0.0607456 0.117947 + outer loop + vertex 1.51176 1.58127 2.56081 + vertex 1.51228 1.58324 2.56614 + vertex 1.51168 1.58606 2.56255 + endloop + endfacet + facet normal -0.982364 0.0263639 0.185108 + outer loop + vertex 1.51168 1.58606 2.56255 + vertex 1.51228 1.58324 2.56614 + vertex 1.5123 1.58895 2.56545 + endloop + endfacet + facet normal -0.760404 0.0810752 0.64437 + outer loop + vertex 1.51228 1.58324 2.56614 + vertex 1.51446 1.58785 2.56813 + vertex 1.5123 1.58895 2.56545 + endloop + endfacet + facet normal -0.774691 0.096212 0.624977 + outer loop + vertex 1.51484 1.58258 2.56941 + vertex 1.51446 1.58785 2.56813 + vertex 1.51228 1.58324 2.56614 + endloop + endfacet + facet normal -0.977911 0.0132635 -0.208602 + outer loop + vertex 1.51271 1.58871 2.55513 + vertex 1.51198 1.58655 2.5584 + vertex 1.51223 1.59046 2.55748 + endloop + endfacet + facet normal -0.992877 0.0404365 -0.112076 + outer loop + vertex 1.51223 1.59046 2.55748 + vertex 1.51178 1.59077 2.56154 + vertex 1.51227 1.59423 2.55849 + endloop + endfacet + facet normal -0.993041 0.036928 -0.111828 + outer loop + vertex 1.51223 1.59046 2.55748 + vertex 1.51198 1.58655 2.5584 + vertex 1.51178 1.59077 2.56154 + endloop + endfacet + facet normal -0.997336 0.00746023 -0.0725678 + outer loop + vertex 1.51198 1.58655 2.5584 + vertex 1.51168 1.58606 2.56255 + vertex 1.51178 1.59077 2.56154 + endloop + endfacet + facet normal -0.986123 0.0561163 0.156244 + outer loop + vertex 1.51168 1.58606 2.56255 + vertex 1.5123 1.58895 2.56545 + vertex 1.51178 1.59077 2.56154 + endloop + endfacet + facet normal -0.989428 0.0259884 0.142677 + outer loop + vertex 1.51178 1.59077 2.56154 + vertex 1.5123 1.58895 2.56545 + vertex 1.51241 1.59399 2.5653 + endloop + endfacet + facet normal -0.74873 0.0363541 0.661878 + outer loop + vertex 1.5123 1.58895 2.56545 + vertex 1.51438 1.59295 2.56759 + vertex 1.51241 1.59399 2.5653 + endloop + endfacet + facet normal -0.766543 0.0575862 0.639606 + outer loop + vertex 1.51446 1.58785 2.56813 + vertex 1.51438 1.59295 2.56759 + vertex 1.5123 1.58895 2.56545 + endloop + endfacet + facet normal -0.994357 0.0356359 -0.0999204 + outer loop + vertex 1.51227 1.59423 2.55849 + vertex 1.51193 1.59651 2.56265 + vertex 1.5123 1.59798 2.55956 + endloop + endfacet + facet normal -0.993334 0.0461998 -0.105613 + outer loop + vertex 1.51178 1.59077 2.56154 + vertex 1.51193 1.59651 2.56265 + vertex 1.51227 1.59423 2.55849 + endloop + endfacet + facet normal -0.985293 -0.00740887 0.170713 + outer loop + vertex 1.51178 1.59077 2.56154 + vertex 1.51241 1.59399 2.5653 + vertex 1.51193 1.59651 2.56265 + endloop + endfacet + facet normal -0.975735 0.041053 0.21507 + outer loop + vertex 1.51193 1.59651 2.56265 + vertex 1.51241 1.59399 2.5653 + vertex 1.51269 1.59839 2.56573 + endloop + endfacet + facet normal -0.670758 -0.0300406 0.741068 + outer loop + vertex 1.51241 1.59399 2.5653 + vertex 1.51451 1.59788 2.56735 + vertex 1.51269 1.59839 2.56573 + endloop + endfacet + facet normal -0.745034 0.0503824 0.665121 + outer loop + vertex 1.51438 1.59295 2.56759 + vertex 1.51451 1.59788 2.56735 + vertex 1.51241 1.59399 2.5653 + endloop + endfacet + facet normal -0.994238 0.0282891 -0.103398 + outer loop + vertex 1.5123 1.59798 2.55956 + vertex 1.51193 1.59651 2.56265 + vertex 1.51212 1.60032 2.56188 + endloop + endfacet + facet normal -0.98984 0.0208322 0.140651 + outer loop + vertex 1.51212 1.60032 2.56188 + vertex 1.51258 1.60219 2.56485 + vertex 1.51231 1.60452 2.5626 + endloop + endfacet + facet normal -0.991467 0.0711188 0.109247 + outer loop + vertex 1.51212 1.60032 2.56188 + vertex 1.51193 1.59651 2.56265 + vertex 1.51258 1.60219 2.56485 + endloop + endfacet + facet normal -0.974078 0.0243443 0.2249 + outer loop + vertex 1.51193 1.59651 2.56265 + vertex 1.51269 1.59839 2.56573 + vertex 1.51258 1.60219 2.56485 + endloop + endfacet + facet normal -0.74693 0.129272 0.652214 + outer loop + vertex 1.51269 1.59839 2.56573 + vertex 1.5146 1.6026 2.56708 + vertex 1.51258 1.60219 2.56485 + endloop + endfacet + facet normal -0.656493 0.0561585 0.752239 + outer loop + vertex 1.51451 1.59788 2.56735 + vertex 1.5146 1.6026 2.56708 + vertex 1.51269 1.59839 2.56573 + endloop + endfacet + facet normal -0.986347 0.0180793 0.163687 + outer loop + vertex 1.51231 1.60452 2.5626 + vertex 1.51281 1.60741 2.56528 + vertex 1.51253 1.60919 2.56339 + endloop + endfacet + facet normal -0.988132 0.0305815 0.150534 + outer loop + vertex 1.51258 1.60219 2.56485 + vertex 1.51281 1.60741 2.56528 + vertex 1.51231 1.60452 2.5626 + endloop + endfacet + facet normal -0.645828 -0.034528 0.762702 + outer loop + vertex 1.51258 1.60219 2.56485 + vertex 1.51461 1.60728 2.5668 + vertex 1.51281 1.60741 2.56528 + endloop + endfacet + facet normal -0.744497 0.0415228 0.666334 + outer loop + vertex 1.5146 1.6026 2.56708 + vertex 1.51461 1.60728 2.5668 + vertex 1.51258 1.60219 2.56485 + endloop + endfacet + facet normal -0.985743 0.131823 0.104562 + outer loop + vertex 1.51253 1.60919 2.56339 + vertex 1.51297 1.61084 2.56544 + vertex 1.51312 1.61288 2.56429 + endloop + endfacet + facet normal -0.982894 0.0364995 0.18052 + outer loop + vertex 1.51281 1.60741 2.56528 + vertex 1.51297 1.61084 2.56544 + vertex 1.51253 1.60919 2.56339 + endloop + endfacet + facet normal -0.591387 -0.0104003 0.806321 + outer loop + vertex 1.51281 1.60741 2.56528 + vertex 1.5145 1.61143 2.56657 + vertex 1.51297 1.61084 2.56544 + endloop + endfacet + facet normal -0.643452 0.0246348 0.76509 + outer loop + vertex 1.51461 1.60728 2.5668 + vertex 1.5145 1.61143 2.56657 + vertex 1.51281 1.60741 2.56528 + endloop + endfacet + facet normal -0.874661 0.286112 0.39129 + outer loop + vertex 1.51312 1.61288 2.56429 + vertex 1.51297 1.61084 2.56544 + vertex 1.51412 1.61392 2.56577 + endloop + endfacet + facet normal -0.62436 0.152069 0.766191 + outer loop + vertex 1.51412 1.61392 2.56577 + vertex 1.51297 1.61084 2.56544 + vertex 1.5145 1.61143 2.56657 + endloop + endfacet + facet normal -0.472925 -0.670132 -0.572071 + outer loop + vertex 1.51468 2.01162 2.4926 + vertex 1.51303 2.015 2.49 + vertex 1.515 2.01361 2.49 + endloop + endfacet + facet normal -0.335368 -0.671368 -0.660904 + outer loop + vertex 1.5109 2.01251 2.49361 + vertex 1.51303 2.015 2.49 + vertex 1.51468 2.01162 2.4926 + endloop + endfacet + facet normal -0.255567 -0.960962 -0.106004 + outer loop + vertex 1.5138 2.0114 2.49676 + vertex 1.5109 2.01251 2.49361 + vertex 1.51468 2.01162 2.4926 + endloop + endfacet + facet normal -0.336342 -0.941414 -0.0247628 + outer loop + vertex 1.51022 2.01265 2.49778 + vertex 1.5109 2.01251 2.49361 + vertex 1.5138 2.0114 2.49676 + endloop + endfacet + facet normal -0.285592 -0.945325 0.157473 + outer loop + vertex 1.5127 2.0122 2.4996 + vertex 1.51022 2.01265 2.49778 + vertex 1.5138 2.0114 2.49676 + endloop + endfacet + facet normal -0.385535 -0.868192 0.31242 + outer loop + vertex 1.51006 2.01365 2.50039 + vertex 1.51022 2.01265 2.49778 + vertex 1.5127 2.0122 2.4996 + endloop + endfacet + facet normal -0.207264 -0.727985 0.653513 + outer loop + vertex 1.5127 2.0122 2.4996 + vertex 1.5128 2.01358 2.50117 + vertex 1.51006 2.01365 2.50039 + endloop + endfacet + facet normal 0.0309837 -0.831368 -0.554858 + outer loop + vertex 1.51303 2.015 2.49 + vertex 1.5109 2.01251 2.49361 + vertex 1.50761 2.01415 2.49096 + endloop + endfacet + facet normal -0.138346 -0.214996 -0.966766 + outer loop + vertex 1.51 2.01695 2.49 + vertex 1.51303 2.015 2.49 + vertex 1.50761 2.01415 2.49096 + endloop + endfacet + facet normal -0.224388 -0.974485 -0.00536373 + outer loop + vertex 1.5109 2.01251 2.49361 + vertex 1.51022 2.01265 2.49778 + vertex 1.50671 2.01347 2.49489 + endloop + endfacet + facet normal -0.282686 -0.932064 -0.226596 + outer loop + vertex 1.50761 2.01415 2.49096 + vertex 1.5109 2.01251 2.49361 + vertex 1.50671 2.01347 2.49489 + endloop + endfacet + facet normal -0.310694 -0.892755 0.326279 + outer loop + vertex 1.51022 2.01265 2.49778 + vertex 1.51006 2.01365 2.50039 + vertex 1.50605 2.01462 2.49921 + endloop + endfacet + facet normal -0.367503 -0.911154 0.186388 + outer loop + vertex 1.50671 2.01347 2.49489 + vertex 1.51022 2.01265 2.49778 + vertex 1.50605 2.01462 2.49921 + endloop + endfacet + facet normal -0.353027 -0.536562 0.766468 + outer loop + vertex 1.51006 2.01365 2.50039 + vertex 1.5079 2.0167 2.50152 + vertex 1.50605 2.01462 2.49921 + endloop + endfacet + facet normal -0.252183 -0.490431 0.834195 + outer loop + vertex 1.51006 2.01365 2.50039 + vertex 1.5128 2.01358 2.50117 + vertex 1.5079 2.0167 2.50152 + endloop + endfacet + facet normal 0.153949 0.476831 0.865408 + outer loop + vertex 1.51435 2.10973 2.47135 + vertex 1.51227 2.11347 2.46966 + vertex 1.51045 2.11068 2.47152 + endloop + endfacet + facet normal 0.132698 0.379959 0.915436 + outer loop + vertex 1.51045 2.11068 2.47152 + vertex 1.5108 2.10683 2.47307 + vertex 1.51435 2.10973 2.47135 + endloop + endfacet + facet normal 0.140537 0.380172 0.914177 + outer loop + vertex 1.51045 2.11068 2.47152 + vertex 1.50639 2.10997 2.47244 + vertex 1.5108 2.10683 2.47307 + endloop + endfacet + facet normal 0.168505 0.468565 0.86721 + outer loop + vertex 1.50813 2.11296 2.47074 + vertex 1.51045 2.11068 2.47152 + vertex 1.51227 2.11347 2.46966 + endloop + endfacet + facet normal 0.146764 0.549513 0.822493 + outer loop + vertex 1.50813 2.11296 2.47074 + vertex 1.51227 2.11347 2.46966 + vertex 1.50726 2.11626 2.46869 + endloop + endfacet + facet normal 0.177615 0.592158 0.786004 + outer loop + vertex 1.50726 2.11626 2.46869 + vertex 1.51227 2.11347 2.46966 + vertex 1.51192 2.1166 2.46738 + endloop + endfacet + facet normal 0.126078 0.434181 0.891959 + outer loop + vertex 1.51045 2.11068 2.47152 + vertex 1.50813 2.11296 2.47074 + vertex 1.50639 2.10997 2.47244 + endloop + endfacet + facet normal 0.174742 0.823784 0.539301 + outer loop + vertex 1.50897 2.11884 2.4658 + vertex 1.51438 2.1185 2.46456 + vertex 1.51042 2.12057 2.46268 + endloop + endfacet + facet normal 0.178905 0.822197 0.540356 + outer loop + vertex 1.50562 2.12093 2.46373 + vertex 1.50897 2.11884 2.4658 + vertex 1.51042 2.12057 2.46268 + endloop + endfacet + facet normal 0.147901 0.692868 0.705733 + outer loop + vertex 1.51192 2.1166 2.46738 + vertex 1.50897 2.11884 2.4658 + vertex 1.50726 2.11626 2.46869 + endloop + endfacet + facet normal 0.196546 0.724922 0.660195 + outer loop + vertex 1.51438 2.1185 2.46456 + vertex 1.50897 2.11884 2.4658 + vertex 1.51192 2.1166 2.46738 + endloop + endfacet + facet normal 0.0205245 0.18324 0.982854 + outer loop + vertex 1.515 2.1271 2.455 + vertex 1.51 2.12766 2.455 + vertex 1.51188 2.12409 2.45563 + endloop + endfacet + facet normal 0.234505 0.286475 0.928945 + outer loop + vertex 1.51188 2.12409 2.45563 + vertex 1.51 2.12766 2.455 + vertex 1.5079 2.12419 2.4566 + endloop + endfacet + facet normal 0.150112 0.836865 0.526425 + outer loop + vertex 1.51188 2.12409 2.45563 + vertex 1.5079 2.12419 2.4566 + vertex 1.51207 2.12204 2.45883 + endloop + endfacet + facet normal 0.179564 0.854152 0.488039 + outer loop + vertex 1.51207 2.12204 2.45883 + vertex 1.5079 2.12419 2.4566 + vertex 1.50683 2.12234 2.46023 + endloop + endfacet + facet normal 0.157251 0.895883 0.415531 + outer loop + vertex 1.51042 2.12057 2.46268 + vertex 1.50683 2.12234 2.46023 + vertex 1.50562 2.12093 2.46373 + endloop + endfacet + facet normal 0.161284 0.897388 0.410709 + outer loop + vertex 1.51207 2.12204 2.45883 + vertex 1.50683 2.12234 2.46023 + vertex 1.51042 2.12057 2.46268 + endloop + endfacet + facet normal 0.205881 -0.690279 -0.693634 + outer loop + vertex 1.51847 0.905 2.45 + vertex 1.515 0.903965 2.45 + vertex 1.515 0.905 2.44897 + endloop + endfacet + facet normal 0.275604 -0.924043 0.264928 + outer loop + vertex 1.51847 0.905 2.45 + vertex 1.515 0.905 2.45361 + vertex 1.515 0.903965 2.45 + endloop + endfacet + facet normal 0.145663 -0.541889 0.827731 + outer loop + vertex 1.52 0.906978 2.455 + vertex 1.51708 0.907257 2.4557 + vertex 1.515 0.905634 2.455 + endloop + endfacet + facet normal 0.270497 -0.651214 0.70905 + outer loop + vertex 1.51708 0.907257 2.4557 + vertex 1.51164 0.906867 2.45741 + vertex 1.515 0.905634 2.455 + endloop + endfacet + facet normal 0.206276 -0.865222 0.456991 + outer loop + vertex 1.51708 0.907257 2.4557 + vertex 1.51417 0.908483 2.45933 + vertex 1.51164 0.906867 2.45741 + endloop + endfacet + facet normal 0.168442 -0.885316 0.433409 + outer loop + vertex 1.51826 0.908711 2.45821 + vertex 1.51417 0.908483 2.45933 + vertex 1.51708 0.907257 2.4557 + endloop + endfacet + facet normal 0.194381 -0.817974 0.541419 + outer loop + vertex 1.51417 0.908483 2.45933 + vertex 1.51826 0.908711 2.45821 + vertex 1.51684 0.910827 2.46192 + endloop + endfacet + facet normal 0.187619 -0.816056 0.546673 + outer loop + vertex 1.51126 0.909955 2.46253 + vertex 1.51417 0.908483 2.45933 + vertex 1.51684 0.910827 2.46192 + endloop + endfacet + facet normal 0.163717 -0.746983 0.64437 + outer loop + vertex 1.51585 0.913285 2.46502 + vertex 1.51684 0.910827 2.46192 + vertex 1.51932 0.91336 2.46422 + endloop + endfacet + facet normal 0.171109 -0.744793 0.644984 + outer loop + vertex 1.51585 0.913285 2.46502 + vertex 1.51226 0.912499 2.46506 + vertex 1.51684 0.910827 2.46192 + endloop + endfacet + facet normal 0.186304 -0.728975 0.6587 + outer loop + vertex 1.51226 0.912499 2.46506 + vertex 1.51126 0.909955 2.46253 + vertex 1.51684 0.910827 2.46192 + endloop + endfacet + facet normal 0.149585 -0.640239 0.753471 + outer loop + vertex 1.51585 0.913285 2.46502 + vertex 1.51424 0.915349 2.46709 + vertex 1.51226 0.912499 2.46506 + endloop + endfacet + facet normal 0.18179 -0.657084 0.731568 + outer loop + vertex 1.51932 0.91336 2.46422 + vertex 1.51762 0.915146 2.46625 + vertex 1.51585 0.913285 2.46502 + endloop + endfacet + facet normal 0.149103 -0.640493 0.75335 + outer loop + vertex 1.51762 0.915146 2.46625 + vertex 1.51424 0.915349 2.46709 + vertex 1.51585 0.913285 2.46502 + endloop + endfacet + facet normal 0.169723 -0.55377 0.815189 + outer loop + vertex 1.51762 0.915146 2.46625 + vertex 1.51849 0.918372 2.46826 + vertex 1.51424 0.915349 2.46709 + endloop + endfacet + facet normal 0.155144 -0.538361 0.82831 + outer loop + vertex 1.51849 0.918372 2.46826 + vertex 1.51317 0.918694 2.46947 + vertex 1.51424 0.915349 2.46709 + endloop + endfacet + facet normal -0.0819611 0.361673 0.928695 + outer loop + vertex 1.51227 1.00793 2.49908 + vertex 1.51548 1.01167 2.49791 + vertex 1.51079 1.01127 2.49765 + endloop + endfacet + facet normal -0.232261 0.936526 0.262628 + outer loop + vertex 1.52 1.01773 2.485 + vertex 1.515 1.01649 2.485 + vertex 1.51931 1.01709 2.48668 + endloop + endfacet + facet normal -0.227001 0.942016 0.247134 + outer loop + vertex 1.51931 1.01709 2.48668 + vertex 1.515 1.01649 2.485 + vertex 1.51396 1.01557 2.48754 + endloop + endfacet + facet normal -0.254519 0.960815 0.109798 + outer loop + vertex 1.51931 1.01709 2.48668 + vertex 1.51396 1.01557 2.48754 + vertex 1.51766 1.01613 2.49129 + endloop + endfacet + facet normal -0.253267 0.961294 0.10849 + outer loop + vertex 1.51766 1.01613 2.49129 + vertex 1.51396 1.01557 2.48754 + vertex 1.51341 1.01495 2.49178 + endloop + endfacet + facet normal -0.213814 0.916258 0.338754 + outer loop + vertex 1.51766 1.01613 2.49129 + vertex 1.51341 1.01495 2.49178 + vertex 1.51711 1.01451 2.49531 + endloop + endfacet + facet normal -0.194399 0.927364 0.319696 + outer loop + vertex 1.51711 1.01451 2.49531 + vertex 1.51341 1.01495 2.49178 + vertex 1.51279 1.01357 2.49541 + endloop + endfacet + facet normal -0.0993495 0.737854 0.667609 + outer loop + vertex 1.51548 1.01167 2.49791 + vertex 1.51279 1.01357 2.49541 + vertex 1.51079 1.01127 2.49765 + endloop + endfacet + facet normal -0.13828 0.711222 0.689233 + outer loop + vertex 1.51711 1.01451 2.49531 + vertex 1.51279 1.01357 2.49541 + vertex 1.51548 1.01167 2.49791 + endloop + endfacet + facet normal -0.982521 -0.178622 -0.0524057 + outer loop + vertex 1.51769 1.30227 2.55011 + vertex 1.51717 1.30488 2.5509 + vertex 1.51743 1.30424 2.54824 + endloop + endfacet + facet normal -0.969381 -0.222926 0.102976 + outer loop + vertex 1.51769 1.30227 2.55011 + vertex 1.51786 1.30268 2.55264 + vertex 1.51717 1.30488 2.5509 + endloop + endfacet + facet normal -0.968872 -0.0587646 -0.240487 + outer loop + vertex 1.51782 1.30617 2.54568 + vertex 1.51717 1.30732 2.54805 + vertex 1.51787 1.31008 2.54454 + endloop + endfacet + facet normal -0.970124 -0.097006 -0.22237 + outer loop + vertex 1.51743 1.30424 2.54824 + vertex 1.51717 1.30732 2.54805 + vertex 1.51782 1.30617 2.54568 + endloop + endfacet + facet normal -0.993122 -0.0901341 -0.0747231 + outer loop + vertex 1.51743 1.30424 2.54824 + vertex 1.51717 1.30488 2.5509 + vertex 1.51717 1.30732 2.54805 + endloop + endfacet + facet normal -0.997976 -0.0495306 -0.0398858 + outer loop + vertex 1.51717 1.30488 2.5509 + vertex 1.51693 1.30926 2.55155 + vertex 1.51717 1.30732 2.54805 + endloop + endfacet + facet normal -0.981478 -0.0803542 0.173908 + outer loop + vertex 1.51717 1.30488 2.5509 + vertex 1.51762 1.30592 2.55387 + vertex 1.51693 1.30926 2.55155 + endloop + endfacet + facet normal -0.969225 -0.149003 0.195961 + outer loop + vertex 1.51786 1.30268 2.55264 + vertex 1.51762 1.30592 2.55387 + vertex 1.51717 1.30488 2.5509 + endloop + endfacet + facet normal -0.96091 0.0236717 -0.275846 + outer loop + vertex 1.51787 1.31008 2.54454 + vertex 1.51704 1.31162 2.54756 + vertex 1.51802 1.31499 2.54445 + endloop + endfacet + facet normal -0.969725 -0.0552177 -0.237876 + outer loop + vertex 1.51717 1.30732 2.54805 + vertex 1.51704 1.31162 2.54756 + vertex 1.51787 1.31008 2.54454 + endloop + endfacet + facet normal -0.998241 -0.0341466 -0.0484648 + outer loop + vertex 1.51717 1.30732 2.54805 + vertex 1.51693 1.30926 2.55155 + vertex 1.51704 1.31162 2.54756 + endloop + endfacet + facet normal -0.995275 -0.0685788 -0.068737 + outer loop + vertex 1.51704 1.31162 2.54756 + vertex 1.51693 1.30926 2.55155 + vertex 1.51672 1.31358 2.55029 + endloop + endfacet + facet normal -0.972333 -0.0392774 0.230273 + outer loop + vertex 1.5177 1.30967 2.55488 + vertex 1.51693 1.30926 2.55155 + vertex 1.51762 1.30592 2.55387 + endloop + endfacet + facet normal -0.973243 -0.023524 0.228571 + outer loop + vertex 1.5177 1.30967 2.55488 + vertex 1.51742 1.31415 2.55415 + vertex 1.51693 1.30926 2.55155 + endloop + endfacet + facet normal -0.98381 0.00387556 0.179175 + outer loop + vertex 1.51742 1.31415 2.55415 + vertex 1.51672 1.31358 2.55029 + vertex 1.51693 1.30926 2.55155 + endloop + endfacet + facet normal -0.765193 0.0567781 0.641293 + outer loop + vertex 1.5177 1.30967 2.55488 + vertex 1.51986 1.3126 2.5572 + vertex 1.51742 1.31415 2.55415 + endloop + endfacet + facet normal -0.925284 0.0198184 -0.378757 + outer loop + vertex 1.51802 1.31499 2.54445 + vertex 1.51695 1.31633 2.54714 + vertex 1.51807 1.31982 2.54459 + endloop + endfacet + facet normal -0.936057 -0.0502056 -0.348248 + outer loop + vertex 1.51704 1.31162 2.54756 + vertex 1.51695 1.31633 2.54714 + vertex 1.51802 1.31499 2.54445 + endloop + endfacet + facet normal -0.994866 -0.0291181 -0.0969197 + outer loop + vertex 1.51704 1.31162 2.54756 + vertex 1.51672 1.31358 2.55029 + vertex 1.51695 1.31633 2.54714 + endloop + endfacet + facet normal -0.997325 -0.00153328 -0.0730836 + outer loop + vertex 1.51695 1.31633 2.54714 + vertex 1.51672 1.31358 2.55029 + vertex 1.51668 1.31788 2.55076 + endloop + endfacet + facet normal -0.982509 -0.0294598 0.183868 + outer loop + vertex 1.51672 1.31358 2.55029 + vertex 1.51742 1.31415 2.55415 + vertex 1.51668 1.31788 2.55076 + endloop + endfacet + facet normal -0.983367 -0.0347072 0.178284 + outer loop + vertex 1.51668 1.31788 2.55076 + vertex 1.51742 1.31415 2.55415 + vertex 1.51737 1.31991 2.555 + endloop + endfacet + facet normal -0.797859 -0.0945118 0.59539 + outer loop + vertex 1.51742 1.31415 2.55415 + vertex 1.51956 1.31811 2.55764 + vertex 1.51737 1.31991 2.555 + endloop + endfacet + facet normal -0.799781 -0.0915974 0.593262 + outer loop + vertex 1.51986 1.3126 2.5572 + vertex 1.51956 1.31811 2.55764 + vertex 1.51742 1.31415 2.55415 + endloop + endfacet + facet normal -0.881499 -0.0501802 -0.469513 + outer loop + vertex 1.51807 1.31982 2.54459 + vertex 1.51686 1.32172 2.54664 + vertex 1.51804 1.32354 2.54423 + endloop + endfacet + facet normal -0.883556 -0.0564707 -0.464908 + outer loop + vertex 1.51695 1.31633 2.54714 + vertex 1.51686 1.32172 2.54664 + vertex 1.51807 1.31982 2.54459 + endloop + endfacet + facet normal -0.997682 -0.0214957 -0.0645667 + outer loop + vertex 1.51695 1.31633 2.54714 + vertex 1.51668 1.31788 2.55076 + vertex 1.51686 1.32172 2.54664 + endloop + endfacet + facet normal -0.996826 -0.0309518 -0.0733484 + outer loop + vertex 1.51686 1.32172 2.54664 + vertex 1.51668 1.31788 2.55076 + vertex 1.5165 1.32304 2.55103 + endloop + endfacet + facet normal -0.982254 -0.0436642 0.182405 + outer loop + vertex 1.51668 1.31788 2.55076 + vertex 1.51737 1.31991 2.555 + vertex 1.5165 1.32304 2.55103 + endloop + endfacet + facet normal -0.984978 -0.0856503 0.149944 + outer loop + vertex 1.5165 1.32304 2.55103 + vertex 1.51737 1.31991 2.555 + vertex 1.51704 1.3252 2.55582 + endloop + endfacet + facet normal -0.814958 -0.138616 0.562698 + outer loop + vertex 1.51737 1.31991 2.555 + vertex 1.51945 1.32334 2.55885 + vertex 1.51704 1.3252 2.55582 + endloop + endfacet + facet normal -0.809422 -0.148191 0.568221 + outer loop + vertex 1.51956 1.31811 2.55764 + vertex 1.51945 1.32334 2.55885 + vertex 1.51737 1.31991 2.555 + endloop + endfacet + facet normal 0.267265 -0.139055 -0.953537 + outer loop + vertex 1.52 1.3276 2.545 + vertex 1.51766 1.32644 2.54451 + vertex 1.52 1.33 2.54465 + endloop + endfacet + facet normal 0.147643 0.114921 -0.982341 + outer loop + vertex 1.51804 1.32354 2.54423 + vertex 1.51766 1.32644 2.54451 + vertex 1.52 1.3276 2.545 + endloop + endfacet + facet normal -0.874118 -0.0698043 -0.480672 + outer loop + vertex 1.51804 1.32354 2.54423 + vertex 1.51686 1.32172 2.54664 + vertex 1.51766 1.32644 2.54451 + endloop + endfacet + facet normal -0.913627 -0.0292069 -0.405503 + outer loop + vertex 1.51686 1.32172 2.54664 + vertex 1.51655 1.32693 2.54697 + vertex 1.51766 1.32644 2.54451 + endloop + endfacet + facet normal -0.996287 -0.0553174 -0.0659786 + outer loop + vertex 1.51686 1.32172 2.54664 + vertex 1.5165 1.32304 2.55103 + vertex 1.51655 1.32693 2.54697 + endloop + endfacet + facet normal -0.995525 -0.0614263 -0.0718147 + outer loop + vertex 1.51655 1.32693 2.54697 + vertex 1.5165 1.32304 2.55103 + vertex 1.5162 1.32809 2.55089 + endloop + endfacet + facet normal -0.98909 -0.0550849 0.136626 + outer loop + vertex 1.5165 1.32304 2.55103 + vertex 1.51704 1.3252 2.55582 + vertex 1.5162 1.32809 2.55089 + endloop + endfacet + facet normal -0.985378 -0.150459 0.0799493 + outer loop + vertex 1.5162 1.32809 2.55089 + vertex 1.51704 1.3252 2.55582 + vertex 1.51627 1.32948 2.55445 + endloop + endfacet + facet normal -0.822705 -0.386494 0.416868 + outer loop + vertex 1.51843 1.32624 2.55953 + vertex 1.51704 1.3252 2.55582 + vertex 1.51945 1.32334 2.55885 + endloop + endfacet + facet normal -0.911249 -0.149338 0.383828 + outer loop + vertex 1.51843 1.32624 2.55953 + vertex 1.51746 1.32966 2.55856 + vertex 1.51704 1.3252 2.55582 + endloop + endfacet + facet normal -0.956462 -0.0814259 0.280269 + outer loop + vertex 1.51746 1.32966 2.55856 + vertex 1.51627 1.32948 2.55445 + vertex 1.51704 1.3252 2.55582 + endloop + endfacet + facet normal -0.741316 -0.0194062 0.670875 + outer loop + vertex 1.51843 1.32624 2.55953 + vertex 1.51974 1.32921 2.56106 + vertex 1.51746 1.32966 2.55856 + endloop + endfacet + facet normal 0.104979 -0.0397538 -0.99368 + outer loop + vertex 1.52 1.33 2.54465 + vertex 1.51747 1.33087 2.54435 + vertex 1.52 1.335 2.54445 + endloop + endfacet + facet normal 0.10753 -0.0323262 -0.993676 + outer loop + vertex 1.51766 1.32644 2.54451 + vertex 1.51747 1.33087 2.54435 + vertex 1.52 1.33 2.54465 + endloop + endfacet + facet normal -0.914466 -0.053026 -0.401174 + outer loop + vertex 1.51766 1.32644 2.54451 + vertex 1.51655 1.32693 2.54697 + vertex 1.51747 1.33087 2.54435 + endloop + endfacet + facet normal -0.913959 -0.0538386 -0.402219 + outer loop + vertex 1.51747 1.33087 2.54435 + vertex 1.51655 1.32693 2.54697 + vertex 1.51635 1.33202 2.54675 + endloop + endfacet + facet normal -0.996066 -0.0434743 -0.0772165 + outer loop + vertex 1.51655 1.32693 2.54697 + vertex 1.5162 1.32809 2.55089 + vertex 1.51635 1.33202 2.54675 + endloop + endfacet + facet normal -0.9943 -0.0570656 -0.0900617 + outer loop + vertex 1.51635 1.33202 2.54675 + vertex 1.5162 1.32809 2.55089 + vertex 1.51594 1.33295 2.55067 + endloop + endfacet + facet normal -0.997811 -0.0513797 0.0416358 + outer loop + vertex 1.5162 1.32809 2.55089 + vertex 1.51627 1.32948 2.55445 + vertex 1.51594 1.33295 2.55067 + endloop + endfacet + facet normal -0.997794 -0.0359381 0.0558149 + outer loop + vertex 1.51594 1.33295 2.55067 + vertex 1.51627 1.32948 2.55445 + vertex 1.51617 1.33351 2.55515 + endloop + endfacet + facet normal -0.957137 -0.073626 0.280122 + outer loop + vertex 1.51627 1.32948 2.55445 + vertex 1.51746 1.32966 2.55856 + vertex 1.51617 1.33351 2.55515 + endloop + endfacet + facet normal -0.954558 -0.0628095 0.291331 + outer loop + vertex 1.51617 1.33351 2.55515 + vertex 1.51746 1.32966 2.55856 + vertex 1.51729 1.33492 2.55912 + endloop + endfacet + facet normal -0.698752 -0.0986155 0.708534 + outer loop + vertex 1.51746 1.32966 2.55856 + vertex 1.51961 1.33328 2.56118 + vertex 1.51729 1.33492 2.55912 + endloop + endfacet + facet normal -0.742898 -0.0431334 0.668014 + outer loop + vertex 1.51974 1.32921 2.56106 + vertex 1.51961 1.33328 2.56118 + vertex 1.51746 1.32966 2.55856 + endloop + endfacet + facet normal 0.111355 -0.0198986 -0.993581 + outer loop + vertex 1.52 1.335 2.54445 + vertex 1.51738 1.33588 2.54414 + vertex 1.52 1.34 2.54435 + endloop + endfacet + facet normal 0.104777 -0.0396295 -0.993706 + outer loop + vertex 1.51747 1.33087 2.54435 + vertex 1.51738 1.33588 2.54414 + vertex 1.52 1.335 2.54445 + endloop + endfacet + facet normal -0.91123 -0.0338248 -0.410507 + outer loop + vertex 1.51747 1.33087 2.54435 + vertex 1.51635 1.33202 2.54675 + vertex 1.51738 1.33588 2.54414 + endloop + endfacet + facet normal -0.910801 -0.0345443 -0.411398 + outer loop + vertex 1.51738 1.33588 2.54414 + vertex 1.51635 1.33202 2.54675 + vertex 1.5162 1.33712 2.54665 + endloop + endfacet + facet normal -0.994867 -0.0307258 -0.0964154 + outer loop + vertex 1.51635 1.33202 2.54675 + vertex 1.51594 1.33295 2.55067 + vertex 1.5162 1.33712 2.54665 + endloop + endfacet + facet normal -0.994888 -0.0305666 -0.0962515 + outer loop + vertex 1.5162 1.33712 2.54665 + vertex 1.51594 1.33295 2.55067 + vertex 1.51577 1.33783 2.55088 + endloop + endfacet + facet normal -0.997743 -0.0371158 0.0559581 + outer loop + vertex 1.51594 1.33295 2.55067 + vertex 1.51617 1.33351 2.55515 + vertex 1.51577 1.33783 2.55088 + endloop + endfacet + facet normal -0.997817 -0.0423214 0.0506933 + outer loop + vertex 1.51577 1.33783 2.55088 + vertex 1.51617 1.33351 2.55515 + vertex 1.51598 1.33841 2.55553 + endloop + endfacet + facet normal -0.955052 -0.0596966 0.290366 + outer loop + vertex 1.51617 1.33351 2.55515 + vertex 1.51729 1.33492 2.55912 + vertex 1.51598 1.33841 2.55553 + endloop + endfacet + facet normal -0.955046 -0.0596675 0.290392 + outer loop + vertex 1.51598 1.33841 2.55553 + vertex 1.51729 1.33492 2.55912 + vertex 1.51708 1.33995 2.55947 + endloop + endfacet + facet normal -0.686987 -0.0788981 0.722374 + outer loop + vertex 1.51729 1.33492 2.55912 + vertex 1.51948 1.33806 2.56155 + vertex 1.51708 1.33995 2.55947 + endloop + endfacet + facet normal -0.69082 -0.0738031 0.719251 + outer loop + vertex 1.51961 1.33328 2.56118 + vertex 1.51948 1.33806 2.56155 + vertex 1.51729 1.33492 2.55912 + endloop + endfacet + facet normal 0.0796589 -0.0159213 -0.996695 + outer loop + vertex 1.52 1.34 2.54435 + vertex 1.51732 1.34095 2.54412 + vertex 1.52 1.345 2.54427 + endloop + endfacet + facet normal 0.0843697 -0.00261348 -0.996431 + outer loop + vertex 1.51738 1.33588 2.54414 + vertex 1.51732 1.34095 2.54412 + vertex 1.52 1.34 2.54435 + endloop + endfacet + facet normal -0.906999 -0.0116404 -0.420972 + outer loop + vertex 1.51738 1.33588 2.54414 + vertex 1.5162 1.33712 2.54665 + vertex 1.51732 1.34095 2.54412 + endloop + endfacet + facet normal -0.91221 -0.00266409 -0.409714 + outer loop + vertex 1.51732 1.34095 2.54412 + vertex 1.5162 1.33712 2.54665 + vertex 1.51608 1.34205 2.54689 + endloop + endfacet + facet normal -0.994983 -0.0196193 -0.0981006 + outer loop + vertex 1.5162 1.33712 2.54665 + vertex 1.51577 1.33783 2.55088 + vertex 1.51608 1.34205 2.54689 + endloop + endfacet + facet normal -0.993647 -0.0296088 -0.108574 + outer loop + vertex 1.51608 1.34205 2.54689 + vertex 1.51577 1.33783 2.55088 + vertex 1.51559 1.34259 2.55117 + endloop + endfacet + facet normal -0.997941 -0.0397082 0.0503752 + outer loop + vertex 1.51577 1.33783 2.55088 + vertex 1.51598 1.33841 2.55553 + vertex 1.51559 1.34259 2.55117 + endloop + endfacet + facet normal -0.997955 -0.0419083 0.0482656 + outer loop + vertex 1.51559 1.34259 2.55117 + vertex 1.51598 1.33841 2.55553 + vertex 1.51578 1.34334 2.55574 + endloop + endfacet + facet normal -0.956577 -0.0502079 0.287122 + outer loop + vertex 1.51598 1.33841 2.55553 + vertex 1.51708 1.33995 2.55947 + vertex 1.51578 1.34334 2.55574 + endloop + endfacet + facet normal -0.956842 -0.0515426 0.286002 + outer loop + vertex 1.51578 1.34334 2.55574 + vertex 1.51708 1.33995 2.55947 + vertex 1.51688 1.34495 2.5597 + endloop + endfacet + facet normal -0.683887 -0.060737 0.727055 + outer loop + vertex 1.51708 1.33995 2.55947 + vertex 1.51938 1.34304 2.56189 + vertex 1.51688 1.34495 2.5597 + endloop + endfacet + facet normal -0.681344 -0.0642546 0.729137 + outer loop + vertex 1.51948 1.33806 2.56155 + vertex 1.51938 1.34304 2.56189 + vertex 1.51708 1.33995 2.55947 + endloop + endfacet + facet normal -0.0637371 0.0776162 -0.994944 + outer loop + vertex 1.52 1.345 2.54427 + vertex 1.51744 1.34643 2.54455 + vertex 1.52 1.35 2.54466 + endloop + endfacet + facet normal -0.0632401 0.078496 -0.994907 + outer loop + vertex 1.51732 1.34095 2.54412 + vertex 1.51744 1.34643 2.54455 + vertex 1.52 1.345 2.54427 + endloop + endfacet + facet normal -0.902598 0.0523864 -0.427285 + outer loop + vertex 1.51732 1.34095 2.54412 + vertex 1.51608 1.34205 2.54689 + vertex 1.51744 1.34643 2.54455 + endloop + endfacet + facet normal -0.889974 0.033763 -0.454759 + outer loop + vertex 1.51744 1.34643 2.54455 + vertex 1.51608 1.34205 2.54689 + vertex 1.51591 1.34603 2.54751 + endloop + endfacet + facet normal -0.993712 -0.0248157 -0.109185 + outer loop + vertex 1.51608 1.34205 2.54689 + vertex 1.51559 1.34259 2.55117 + vertex 1.51591 1.34603 2.54751 + endloop + endfacet + facet normal -0.994608 -0.0173496 -0.102246 + outer loop + vertex 1.51591 1.34603 2.54751 + vertex 1.51559 1.34259 2.55117 + vertex 1.51551 1.34725 2.55116 + endloop + endfacet + facet normal -0.998875 -0.017025 0.044259 + outer loop + vertex 1.51559 1.34259 2.55117 + vertex 1.51578 1.34334 2.55574 + vertex 1.51551 1.34725 2.55116 + endloop + endfacet + facet normal -0.998945 -0.0369796 0.027218 + outer loop + vertex 1.51551 1.34725 2.55116 + vertex 1.51578 1.34334 2.55574 + vertex 1.5156 1.34823 2.5558 + endloop + endfacet + facet normal -0.958809 -0.0388906 0.281376 + outer loop + vertex 1.51578 1.34334 2.55574 + vertex 1.51688 1.34495 2.5597 + vertex 1.5156 1.34823 2.5558 + endloop + endfacet + facet normal -0.958899 -0.0393683 0.281004 + outer loop + vertex 1.5156 1.34823 2.5558 + vertex 1.51688 1.34495 2.5597 + vertex 1.51671 1.34995 2.55984 + endloop + endfacet + facet normal -0.703812 -0.0429396 0.709088 + outer loop + vertex 1.51688 1.34495 2.5597 + vertex 1.51923 1.34804 2.56222 + vertex 1.51671 1.34995 2.55984 + endloop + endfacet + facet normal -0.686649 -0.0680798 0.723794 + outer loop + vertex 1.51938 1.34304 2.56189 + vertex 1.51923 1.34804 2.56222 + vertex 1.51688 1.34495 2.5597 + endloop + endfacet + facet normal -0.222217 0.190136 -0.956278 + outer loop + vertex 1.52 1.35 2.54466 + vertex 1.51744 1.34643 2.54455 + vertex 1.52 1.35171 2.545 + endloop + endfacet + facet normal -0.296167 -0.308949 -0.90379 + outer loop + vertex 1.52 1.35171 2.545 + vertex 1.5165 1.35077 2.54647 + vertex 1.51811 1.35545 2.54434 + endloop + endfacet + facet normal -0.435192 0.284669 -0.85415 + outer loop + vertex 1.52 1.35171 2.545 + vertex 1.51744 1.34643 2.54455 + vertex 1.5165 1.35077 2.54647 + endloop + endfacet + facet normal -0.889134 0.0100139 -0.457537 + outer loop + vertex 1.51744 1.34643 2.54455 + vertex 1.51591 1.34603 2.54751 + vertex 1.5165 1.35077 2.54647 + endloop + endfacet + facet normal -0.986111 0.0925837 -0.137887 + outer loop + vertex 1.51591 1.34603 2.54751 + vertex 1.51551 1.34725 2.55116 + vertex 1.5165 1.35077 2.54647 + endloop + endfacet + facet normal -0.974099 -0.0262975 -0.224587 + outer loop + vertex 1.5165 1.35077 2.54647 + vertex 1.51551 1.34725 2.55116 + vertex 1.51541 1.35213 2.55104 + endloop + endfacet + facet normal -0.999503 -0.0206741 0.0237872 + outer loop + vertex 1.51551 1.34725 2.55116 + vertex 1.5156 1.34823 2.5558 + vertex 1.51541 1.35213 2.55104 + endloop + endfacet + facet normal -0.999291 -0.0359044 0.0113117 + outer loop + vertex 1.51541 1.35213 2.55104 + vertex 1.5156 1.34823 2.5558 + vertex 1.51543 1.35317 2.55582 + endloop + endfacet + facet normal -0.959529 -0.0352004 0.2794 + outer loop + vertex 1.5156 1.34823 2.5558 + vertex 1.51671 1.34995 2.55984 + vertex 1.51543 1.35317 2.55582 + endloop + endfacet + facet normal -0.959343 -0.0341685 0.280168 + outer loop + vertex 1.51543 1.35317 2.55582 + vertex 1.51671 1.34995 2.55984 + vertex 1.51657 1.35494 2.55994 + endloop + endfacet + facet normal -0.720036 -0.0353815 0.693034 + outer loop + vertex 1.51671 1.34995 2.55984 + vertex 1.51911 1.35303 2.56249 + vertex 1.51657 1.35494 2.55994 + endloop + endfacet + facet normal -0.707901 -0.0544283 0.704212 + outer loop + vertex 1.51923 1.34804 2.56222 + vertex 1.51911 1.35303 2.56249 + vertex 1.51671 1.34995 2.55984 + endloop + endfacet + facet normal -0.783076 -0.0204248 -0.621591 + outer loop + vertex 1.51811 1.35545 2.54434 + vertex 1.51614 1.35619 2.5468 + vertex 1.51789 1.36026 2.54446 + endloop + endfacet + facet normal -0.782269 -0.0143786 -0.622775 + outer loop + vertex 1.5165 1.35077 2.54647 + vertex 1.51614 1.35619 2.5468 + vertex 1.51811 1.35545 2.54434 + endloop + endfacet + facet normal -0.974758 -0.0515533 -0.217232 + outer loop + vertex 1.5165 1.35077 2.54647 + vertex 1.51541 1.35213 2.55104 + vertex 1.51614 1.35619 2.5468 + endloop + endfacet + facet normal -0.979243 -0.0327873 -0.20002 + outer loop + vertex 1.51614 1.35619 2.5468 + vertex 1.51541 1.35213 2.55104 + vertex 1.51523 1.35715 2.5511 + endloop + endfacet + facet normal -0.999284 -0.0360863 0.0113515 + outer loop + vertex 1.51541 1.35213 2.55104 + vertex 1.51543 1.35317 2.55582 + vertex 1.51523 1.35715 2.5511 + endloop + endfacet + facet normal -0.999252 -0.0372566 0.0103637 + outer loop + vertex 1.51523 1.35715 2.5511 + vertex 1.51543 1.35317 2.55582 + vertex 1.51524 1.35815 2.55585 + endloop + endfacet + facet normal -0.958882 -0.0372338 0.281351 + outer loop + vertex 1.51543 1.35317 2.55582 + vertex 1.51657 1.35494 2.55994 + vertex 1.51524 1.35815 2.55585 + endloop + endfacet + facet normal -0.957546 -0.0298315 0.286731 + outer loop + vertex 1.51524 1.35815 2.55585 + vertex 1.51657 1.35494 2.55994 + vertex 1.51644 1.35993 2.56002 + endloop + endfacet + facet normal -0.73191 -0.0306215 0.680713 + outer loop + vertex 1.51657 1.35494 2.55994 + vertex 1.51901 1.35801 2.56271 + vertex 1.51644 1.35993 2.56002 + endloop + endfacet + facet normal -0.723288 -0.0450274 0.689077 + outer loop + vertex 1.51911 1.35303 2.56249 + vertex 1.51901 1.35801 2.56271 + vertex 1.51657 1.35494 2.55994 + endloop + endfacet + facet normal -0.795492 0.0404481 -0.604613 + outer loop + vertex 1.51789 1.36026 2.54446 + vertex 1.51604 1.36119 2.54695 + vertex 1.51805 1.36512 2.54457 + endloop + endfacet + facet normal -0.802941 0.00279453 -0.596052 + outer loop + vertex 1.51614 1.35619 2.5468 + vertex 1.51604 1.36119 2.54695 + vertex 1.51789 1.36026 2.54446 + endloop + endfacet + facet normal -0.978816 -0.0129874 -0.204331 + outer loop + vertex 1.51614 1.35619 2.5468 + vertex 1.51523 1.35715 2.5511 + vertex 1.51604 1.36119 2.54695 + endloop + endfacet + facet normal -0.977731 -0.0180813 -0.209081 + outer loop + vertex 1.51604 1.36119 2.54695 + vertex 1.51523 1.35715 2.5511 + vertex 1.51512 1.36213 2.55116 + endloop + endfacet + facet normal -0.999751 -0.0211858 0.00697763 + outer loop + vertex 1.51523 1.35715 2.5511 + vertex 1.51524 1.35815 2.55585 + vertex 1.51512 1.36213 2.55116 + endloop + endfacet + facet normal -0.99978 -0.019018 0.0088189 + outer loop + vertex 1.51512 1.36213 2.55116 + vertex 1.51524 1.35815 2.55585 + vertex 1.51515 1.36314 2.55588 + endloop + endfacet + facet normal -0.958879 -0.020377 0.283082 + outer loop + vertex 1.51524 1.35815 2.55585 + vertex 1.51644 1.35993 2.56002 + vertex 1.51515 1.36314 2.55588 + endloop + endfacet + facet normal -0.959174 -0.0219367 0.281964 + outer loop + vertex 1.51515 1.36314 2.55588 + vertex 1.51644 1.35993 2.56002 + vertex 1.51636 1.36495 2.56016 + endloop + endfacet + facet normal -0.739494 -0.0297501 0.672505 + outer loop + vertex 1.51644 1.35993 2.56002 + vertex 1.51894 1.36301 2.56291 + vertex 1.51636 1.36495 2.56016 + endloop + endfacet + facet normal -0.734489 -0.0385237 0.677526 + outer loop + vertex 1.51901 1.35801 2.56271 + vertex 1.51894 1.36301 2.56291 + vertex 1.51644 1.35993 2.56002 + endloop + endfacet + facet normal -0.767883 0.142279 -0.62459 + outer loop + vertex 1.51805 1.36512 2.54457 + vertex 1.51616 1.36612 2.54713 + vertex 1.51857 1.37003 2.54505 + endloop + endfacet + facet normal -0.79528 0.0401591 -0.604911 + outer loop + vertex 1.51604 1.36119 2.54695 + vertex 1.51616 1.36612 2.54713 + vertex 1.51805 1.36512 2.54457 + endloop + endfacet + facet normal -0.975156 0.0307646 -0.219372 + outer loop + vertex 1.51604 1.36119 2.54695 + vertex 1.51512 1.36213 2.55116 + vertex 1.51616 1.36612 2.54713 + endloop + endfacet + facet normal -0.971852 0.013933 -0.235179 + outer loop + vertex 1.51616 1.36612 2.54713 + vertex 1.51512 1.36213 2.55116 + vertex 1.51516 1.36707 2.55129 + endloop + endfacet + facet normal -0.999963 0.00803285 0.00298921 + outer loop + vertex 1.51512 1.36213 2.55116 + vertex 1.51515 1.36314 2.55588 + vertex 1.51516 1.36707 2.55129 + endloop + endfacet + facet normal -0.999936 -0.00640716 -0.00933261 + outer loop + vertex 1.51516 1.36707 2.55129 + vertex 1.51515 1.36314 2.55588 + vertex 1.51511 1.36809 2.55604 + endloop + endfacet + facet normal -0.960078 -0.0150824 0.279326 + outer loop + vertex 1.51515 1.36314 2.55588 + vertex 1.51636 1.36495 2.56016 + vertex 1.51511 1.36809 2.55604 + endloop + endfacet + facet normal -0.963537 -0.0349076 0.265289 + outer loop + vertex 1.51511 1.36809 2.55604 + vertex 1.51636 1.36495 2.56016 + vertex 1.51628 1.37 2.56053 + endloop + endfacet + facet normal -0.739809 -0.060123 0.670126 + outer loop + vertex 1.51636 1.36495 2.56016 + vertex 1.51889 1.36811 2.56323 + vertex 1.51628 1.37 2.56053 + endloop + endfacet + facet normal -0.7458 -0.0496959 0.664314 + outer loop + vertex 1.51894 1.36301 2.56291 + vertex 1.51889 1.36811 2.56323 + vertex 1.51636 1.36495 2.56016 + endloop + endfacet + facet normal -0.576343 0.502865 -0.644171 + outer loop + vertex 1.51857 1.37003 2.54505 + vertex 1.51656 1.37104 2.54763 + vertex 1.52 1.375 2.54765 + endloop + endfacet + facet normal -0.757845 0.128034 -0.639749 + outer loop + vertex 1.51616 1.36612 2.54713 + vertex 1.51656 1.37104 2.54763 + vertex 1.51857 1.37003 2.54505 + endloop + endfacet + facet normal -0.961621 0.105055 -0.253472 + outer loop + vertex 1.51616 1.36612 2.54713 + vertex 1.51516 1.36707 2.55129 + vertex 1.51656 1.37104 2.54763 + endloop + endfacet + facet normal -0.945488 0.0346213 -0.323811 + outer loop + vertex 1.51656 1.37104 2.54763 + vertex 1.51516 1.36707 2.55129 + vertex 1.51526 1.37193 2.55151 + endloop + endfacet + facet normal -0.99965 0.021518 -0.0153735 + outer loop + vertex 1.51516 1.36707 2.55129 + vertex 1.51511 1.36809 2.55604 + vertex 1.51526 1.37193 2.55151 + endloop + endfacet + facet normal -0.999375 -0.00196382 -0.0352973 + outer loop + vertex 1.51526 1.37193 2.55151 + vertex 1.51511 1.36809 2.55604 + vertex 1.51509 1.37301 2.55628 + endloop + endfacet + facet normal -0.965995 -0.0163399 0.258045 + outer loop + vertex 1.51511 1.36809 2.55604 + vertex 1.51628 1.37 2.56053 + vertex 1.51509 1.37301 2.55628 + endloop + endfacet + facet normal -0.973429 -0.081301 0.214069 + outer loop + vertex 1.51509 1.37301 2.55628 + vertex 1.51628 1.37 2.56053 + vertex 1.51599 1.3751 2.56114 + endloop + endfacet + facet normal -0.762687 -0.120081 0.635522 + outer loop + vertex 1.51628 1.37 2.56053 + vertex 1.51869 1.37343 2.56407 + vertex 1.51599 1.3751 2.56114 + endloop + endfacet + facet normal -0.75767 -0.128161 0.63993 + outer loop + vertex 1.51889 1.36811 2.56323 + vertex 1.51869 1.37343 2.56407 + vertex 1.51628 1.37 2.56053 + endloop + endfacet + facet normal -0.157473 0.043374 -0.98657 + outer loop + vertex 1.52 1.375 2.54765 + vertex 1.51686 1.37593 2.54819 + vertex 1.52 1.38 2.54787 + endloop + endfacet + facet normal -0.134093 0.120608 -0.983602 + outer loop + vertex 1.51656 1.37104 2.54763 + vertex 1.51686 1.37593 2.54819 + vertex 1.52 1.375 2.54765 + endloop + endfacet + facet normal -0.937397 0.0949912 -0.335059 + outer loop + vertex 1.51656 1.37104 2.54763 + vertex 1.51526 1.37193 2.55151 + vertex 1.51686 1.37593 2.54819 + endloop + endfacet + facet normal -0.910295 0.0190216 -0.413523 + outer loop + vertex 1.51686 1.37593 2.54819 + vertex 1.51526 1.37193 2.55151 + vertex 1.51528 1.37688 2.5517 + endloop + endfacet + facet normal -0.99931 0.0048366 -0.0368285 + outer loop + vertex 1.51526 1.37193 2.55151 + vertex 1.51509 1.37301 2.55628 + vertex 1.51528 1.37688 2.5517 + endloop + endfacet + facet normal -0.9971 -0.0328702 -0.0686351 + outer loop + vertex 1.51528 1.37688 2.5517 + vertex 1.51509 1.37301 2.55628 + vertex 1.51494 1.37782 2.55625 + endloop + endfacet + facet normal -0.980601 -0.0307214 0.193595 + outer loop + vertex 1.51509 1.37301 2.55628 + vertex 1.51599 1.3751 2.56114 + vertex 1.51494 1.37782 2.55625 + endloop + endfacet + facet normal -0.980646 -0.147496 0.128758 + outer loop + vertex 1.51494 1.37782 2.55625 + vertex 1.51599 1.3751 2.56114 + vertex 1.51522 1.37911 2.55989 + endloop + endfacet + facet normal -0.774431 -0.414638 0.477841 + outer loop + vertex 1.51747 1.37629 2.56457 + vertex 1.51599 1.3751 2.56114 + vertex 1.51869 1.37343 2.56407 + endloop + endfacet + facet normal -0.894256 -0.126119 0.429418 + outer loop + vertex 1.51747 1.37629 2.56457 + vertex 1.51656 1.37954 2.56362 + vertex 1.51599 1.3751 2.56114 + endloop + endfacet + facet normal -0.936523 -0.0723208 0.343065 + outer loop + vertex 1.51656 1.37954 2.56362 + vertex 1.51522 1.37911 2.55989 + vertex 1.51599 1.3751 2.56114 + endloop + endfacet + facet normal -0.772599 -0.0326825 0.634053 + outer loop + vertex 1.51747 1.37629 2.56457 + vertex 1.51829 1.37888 2.56571 + vertex 1.51656 1.37954 2.56362 + endloop + endfacet + facet normal -0.221401 -0.0292356 -0.974745 + outer loop + vertex 1.52 1.38 2.54787 + vertex 1.51683 1.38136 2.54855 + vertex 1.52 1.385 2.54772 + endloop + endfacet + facet normal -0.183058 0.063575 -0.981044 + outer loop + vertex 1.51686 1.37593 2.54819 + vertex 1.51683 1.38136 2.54855 + vertex 1.52 1.38 2.54787 + endloop + endfacet + facet normal -0.909918 0.0221407 -0.414197 + outer loop + vertex 1.51686 1.37593 2.54819 + vertex 1.51528 1.37688 2.5517 + vertex 1.51683 1.38136 2.54855 + endloop + endfacet + facet normal -0.904046 0.0108913 -0.427296 + outer loop + vertex 1.51683 1.38136 2.54855 + vertex 1.51528 1.37688 2.5517 + vertex 1.51524 1.38244 2.55194 + endloop + endfacet + facet normal -0.997217 -0.0051081 -0.0743737 + outer loop + vertex 1.51528 1.37688 2.5517 + vertex 1.51494 1.37782 2.55625 + vertex 1.51524 1.38244 2.55194 + endloop + endfacet + facet normal -0.993132 -0.0388897 -0.110346 + outer loop + vertex 1.51524 1.38244 2.55194 + vertex 1.51494 1.37782 2.55625 + vertex 1.51476 1.38253 2.5562 + endloop + endfacet + facet normal -0.995199 -0.0369538 0.0906287 + outer loop + vertex 1.51494 1.37782 2.55625 + vertex 1.51522 1.37911 2.55989 + vertex 1.51476 1.38253 2.5562 + endloop + endfacet + facet normal -0.994003 -0.0182287 0.107819 + outer loop + vertex 1.51476 1.38253 2.5562 + vertex 1.51522 1.37911 2.55989 + vertex 1.51522 1.38303 2.56054 + endloop + endfacet + facet normal -0.938041 -0.0567844 0.34184 + outer loop + vertex 1.51522 1.37911 2.55989 + vertex 1.51656 1.37954 2.56362 + vertex 1.51522 1.38303 2.56054 + endloop + endfacet + facet normal -0.925485 -0.0198262 0.378265 + outer loop + vertex 1.51522 1.38303 2.56054 + vertex 1.51656 1.37954 2.56362 + vertex 1.5166 1.38481 2.56402 + endloop + endfacet + facet normal -0.660754 -0.0501591 0.748925 + outer loop + vertex 1.51656 1.37954 2.56362 + vertex 1.5189 1.38308 2.56593 + vertex 1.5166 1.38481 2.56402 + endloop + endfacet + facet normal -0.754202 0.0747842 0.65237 + outer loop + vertex 1.51829 1.37888 2.56571 + vertex 1.5189 1.38308 2.56593 + vertex 1.51656 1.37954 2.56362 + endloop + endfacet + facet normal -0.607773 -0.0110937 -0.794033 + outer loop + vertex 1.52 1.385 2.54772 + vertex 1.51693 1.39 2.55 + vertex 1.52 1.39 2.54765 + endloop + endfacet + facet normal -0.413146 0.155494 -0.897292 + outer loop + vertex 1.51683 1.38136 2.54855 + vertex 1.51693 1.39 2.55 + vertex 1.52 1.385 2.54772 + endloop + endfacet + facet normal -0.891386 0.0853933 -0.445128 + outer loop + vertex 1.51683 1.38136 2.54855 + vertex 1.51524 1.38244 2.55194 + vertex 1.51693 1.39 2.55 + endloop + endfacet + facet normal -0.764385 0.00560541 -0.644736 + outer loop + vertex 1.51693 1.39 2.55 + vertex 1.51524 1.38244 2.55194 + vertex 1.5151 1.38793 2.55215 + endloop + endfacet + facet normal -0.99363 -0.0207063 -0.110774 + outer loop + vertex 1.51524 1.38244 2.55194 + vertex 1.51476 1.38253 2.5562 + vertex 1.5151 1.38793 2.55215 + endloop + endfacet + facet normal -0.992286 -0.0282369 -0.120708 + outer loop + vertex 1.5151 1.38793 2.55215 + vertex 1.51476 1.38253 2.5562 + vertex 1.5146 1.38731 2.55641 + endloop + endfacet + facet normal -0.993196 -0.0381 0.110046 + outer loop + vertex 1.51476 1.38253 2.5562 + vertex 1.51522 1.38303 2.56054 + vertex 1.5146 1.38731 2.55641 + endloop + endfacet + facet normal -0.99311 -0.0369758 0.111198 + outer loop + vertex 1.5146 1.38731 2.55641 + vertex 1.51522 1.38303 2.56054 + vertex 1.51507 1.38791 2.56079 + endloop + endfacet + facet normal -0.919149 -0.0492993 0.390813 + outer loop + vertex 1.51522 1.38303 2.56054 + vertex 1.5166 1.38481 2.56402 + vertex 1.51507 1.38791 2.56079 + endloop + endfacet + facet normal -0.916469 -0.0404096 0.39806 + outer loop + vertex 1.51507 1.38791 2.56079 + vertex 1.5166 1.38481 2.56402 + vertex 1.51645 1.38989 2.56419 + endloop + endfacet + facet normal -0.622657 -0.0444448 0.781231 + outer loop + vertex 1.5166 1.38481 2.56402 + vertex 1.51884 1.38812 2.56599 + vertex 1.51645 1.38989 2.56419 + endloop + endfacet + facet normal -0.646864 -0.01687 0.762419 + outer loop + vertex 1.5189 1.38308 2.56593 + vertex 1.51884 1.38812 2.56599 + vertex 1.5166 1.38481 2.56402 + endloop + endfacet + facet normal -0.754451 -0.0150915 -0.656183 + outer loop + vertex 1.51693 1.39 2.55 + vertex 1.5151 1.38793 2.55215 + vertex 1.51683 1.395 2.55 + endloop + endfacet + facet normal -0.744498 -0.0209166 -0.667297 + outer loop + vertex 1.51683 1.395 2.55 + vertex 1.5151 1.38793 2.55215 + vertex 1.51487 1.39284 2.55225 + endloop + endfacet + facet normal -0.991521 -0.0427243 -0.122722 + outer loop + vertex 1.5151 1.38793 2.55215 + vertex 1.5146 1.38731 2.55641 + vertex 1.51487 1.39284 2.55225 + endloop + endfacet + facet normal -0.989525 -0.0518512 -0.134732 + outer loop + vertex 1.51487 1.39284 2.55225 + vertex 1.5146 1.38731 2.55641 + vertex 1.51433 1.39225 2.55649 + endloop + endfacet + facet normal -0.991941 -0.0559897 0.113657 + outer loop + vertex 1.5146 1.38731 2.55641 + vertex 1.51507 1.38791 2.56079 + vertex 1.51433 1.39225 2.55649 + endloop + endfacet + facet normal -0.992207 -0.0610233 0.10863 + outer loop + vertex 1.51433 1.39225 2.55649 + vertex 1.51507 1.38791 2.56079 + vertex 1.51476 1.39296 2.56086 + endloop + endfacet + facet normal -0.911267 -0.0600948 0.407408 + outer loop + vertex 1.51507 1.38791 2.56079 + vertex 1.51645 1.38989 2.56419 + vertex 1.51476 1.39296 2.56086 + endloop + endfacet + facet normal -0.911737 -0.0617671 0.406104 + outer loop + vertex 1.51476 1.39296 2.56086 + vertex 1.51645 1.38989 2.56419 + vertex 1.51616 1.39493 2.5643 + endloop + endfacet + facet normal -0.577492 -0.0507756 0.814816 + outer loop + vertex 1.51645 1.38989 2.56419 + vertex 1.51893 1.39315 2.56614 + vertex 1.51616 1.39493 2.5643 + endloop + endfacet + facet normal -0.609011 -0.0138701 0.79304 + outer loop + vertex 1.51884 1.38812 2.56599 + vertex 1.51893 1.39315 2.56614 + vertex 1.51645 1.38989 2.56419 + endloop + endfacet + facet normal -0.753254 -0.00299915 -0.657723 + outer loop + vertex 1.51683 1.395 2.55 + vertex 1.51487 1.39284 2.55225 + vertex 1.51681 1.4 2.55 + endloop + endfacet + facet normal -0.715939 -0.025657 -0.697691 + outer loop + vertex 1.51681 1.4 2.55 + vertex 1.51487 1.39284 2.55225 + vertex 1.51467 1.39781 2.55228 + endloop + endfacet + facet normal -0.990272 -0.0402432 -0.133201 + outer loop + vertex 1.51487 1.39284 2.55225 + vertex 1.51433 1.39225 2.55649 + vertex 1.51467 1.39781 2.55228 + endloop + endfacet + facet normal -0.984262 -0.0643711 -0.164576 + outer loop + vertex 1.51467 1.39781 2.55228 + vertex 1.51433 1.39225 2.55649 + vertex 1.514 1.39728 2.55649 + endloop + endfacet + facet normal -0.991868 -0.0652337 0.109283 + outer loop + vertex 1.51433 1.39225 2.55649 + vertex 1.51476 1.39296 2.56086 + vertex 1.514 1.39728 2.55649 + endloop + endfacet + facet normal -0.992324 -0.0889301 0.0859345 + outer loop + vertex 1.514 1.39728 2.55649 + vertex 1.51476 1.39296 2.56086 + vertex 1.51432 1.39796 2.56094 + endloop + endfacet + facet normal -0.904544 -0.0867033 0.417472 + outer loop + vertex 1.51476 1.39296 2.56086 + vertex 1.51616 1.39493 2.5643 + vertex 1.51432 1.39796 2.56094 + endloop + endfacet + facet normal -0.909969 -0.109269 0.40002 + outer loop + vertex 1.51432 1.39796 2.56094 + vertex 1.51616 1.39493 2.5643 + vertex 1.51566 1.39985 2.5645 + endloop + endfacet + facet normal -0.539192 -0.0900659 0.837353 + outer loop + vertex 1.51616 1.39493 2.5643 + vertex 1.51877 1.39823 2.56633 + vertex 1.51566 1.39985 2.5645 + endloop + endfacet + facet normal -0.576195 -0.0476057 0.815925 + outer loop + vertex 1.51893 1.39315 2.56614 + vertex 1.51877 1.39823 2.56633 + vertex 1.51616 1.39493 2.5643 + endloop + endfacet + facet normal -0.727929 -0.00145784 -0.685651 + outer loop + vertex 1.51681 1.4 2.55 + vertex 1.51467 1.39781 2.55228 + vertex 1.5168 1.405 2.55 + endloop + endfacet + facet normal -0.697165 -0.0203807 -0.716621 + outer loop + vertex 1.5168 1.405 2.55 + vertex 1.51467 1.39781 2.55228 + vertex 1.51449 1.40284 2.5523 + endloop + endfacet + facet normal -0.986391 -0.0332373 -0.161022 + outer loop + vertex 1.51467 1.39781 2.55228 + vertex 1.514 1.39728 2.55649 + vertex 1.51449 1.40284 2.5523 + endloop + endfacet + facet normal -0.977465 -0.0642109 -0.201096 + outer loop + vertex 1.51449 1.40284 2.5523 + vertex 1.514 1.39728 2.55649 + vertex 1.51364 1.40233 2.55663 + endloop + endfacet + facet normal -0.993822 -0.0730114 0.0835895 + outer loop + vertex 1.514 1.39728 2.55649 + vertex 1.51432 1.39796 2.56094 + vertex 1.51364 1.40233 2.55663 + endloop + endfacet + facet normal -0.992311 -0.117761 0.0380998 + outer loop + vertex 1.51364 1.40233 2.55663 + vertex 1.51432 1.39796 2.56094 + vertex 1.51376 1.40276 2.56127 + endloop + endfacet + facet normal -0.902571 -0.132633 0.409602 + outer loop + vertex 1.51432 1.39796 2.56094 + vertex 1.51566 1.39985 2.5645 + vertex 1.51376 1.40276 2.56127 + endloop + endfacet + facet normal -0.909094 -0.168696 0.380907 + outer loop + vertex 1.51376 1.40276 2.56127 + vertex 1.51566 1.39985 2.5645 + vertex 1.51497 1.40447 2.56491 + endloop + endfacet + facet normal -0.496578 -0.148588 0.85518 + outer loop + vertex 1.51566 1.39985 2.5645 + vertex 1.5183 1.40324 2.56662 + vertex 1.51497 1.40447 2.56491 + endloop + endfacet + facet normal -0.542413 -0.0998923 0.834152 + outer loop + vertex 1.51877 1.39823 2.56633 + vertex 1.5183 1.40324 2.56662 + vertex 1.51566 1.39985 2.5645 + endloop + endfacet + facet normal -0.710881 0.00852521 -0.703261 + outer loop + vertex 1.5168 1.405 2.55 + vertex 1.51449 1.40284 2.5523 + vertex 1.51686 1.41 2.55 + endloop + endfacet + facet normal -0.675894 -0.0138543 -0.736868 + outer loop + vertex 1.51686 1.41 2.55 + vertex 1.51449 1.40284 2.5523 + vertex 1.51431 1.40791 2.55238 + endloop + endfacet + facet normal -0.979675 -0.0331252 -0.19784 + outer loop + vertex 1.51449 1.40284 2.5523 + vertex 1.51364 1.40233 2.55663 + vertex 1.51431 1.40791 2.55238 + endloop + endfacet + facet normal -0.963379 -0.0793881 -0.256121 + outer loop + vertex 1.51431 1.40791 2.55238 + vertex 1.51364 1.40233 2.55663 + vertex 1.51309 1.4074 2.5571 + endloop + endfacet + facet normal -0.993236 -0.10993 0.0373896 + outer loop + vertex 1.51364 1.40233 2.55663 + vertex 1.51376 1.40276 2.56127 + vertex 1.51309 1.4074 2.5571 + endloop + endfacet + facet normal -0.987426 -0.157247 -0.0162378 + outer loop + vertex 1.51309 1.4074 2.5571 + vertex 1.51376 1.40276 2.56127 + vertex 1.5131 1.40682 2.56218 + endloop + endfacet + facet normal -0.884517 -0.234202 0.403458 + outer loop + vertex 1.51376 1.40276 2.56127 + vertex 1.51497 1.40447 2.56491 + vertex 1.5131 1.40682 2.56218 + endloop + endfacet + facet normal -0.88372 -0.226429 0.409597 + outer loop + vertex 1.5131 1.40682 2.56218 + vertex 1.51497 1.40447 2.56491 + vertex 1.51418 1.40817 2.56524 + endloop + endfacet + facet normal -0.44268 -0.174047 0.879626 + outer loop + vertex 1.51497 1.40447 2.56491 + vertex 1.51759 1.40861 2.56704 + vertex 1.51418 1.40817 2.56524 + endloop + endfacet + facet normal -0.492978 -0.13213 0.859951 + outer loop + vertex 1.5183 1.40324 2.56662 + vertex 1.51759 1.40861 2.56704 + vertex 1.51497 1.40447 2.56491 + endloop + endfacet + facet normal -0.68855 0.0151523 -0.725031 + outer loop + vertex 1.51686 1.41 2.55 + vertex 1.51431 1.40791 2.55238 + vertex 1.51697 1.415 2.55 + endloop + endfacet + facet normal -0.627432 -0.0256966 -0.778247 + outer loop + vertex 1.51697 1.415 2.55 + vertex 1.51431 1.40791 2.55238 + vertex 1.51405 1.41318 2.55242 + endloop + endfacet + facet normal -0.914357 -0.117287 -0.38755 + outer loop + vertex 1.51273 1.41136 2.55609 + vertex 1.5129 1.41498 2.55458 + vertex 1.51405 1.41318 2.55242 + endloop + endfacet + facet normal -0.89013 -0.189308 -0.414525 + outer loop + vertex 1.51273 1.41136 2.55609 + vertex 1.51405 1.41318 2.55242 + vertex 1.51309 1.4074 2.5571 + endloop + endfacet + facet normal -0.966318 -0.0457848 -0.253247 + outer loop + vertex 1.51309 1.4074 2.5571 + vertex 1.51405 1.41318 2.55242 + vertex 1.51431 1.40791 2.55238 + endloop + endfacet + facet normal -0.969097 -0.245254 -0.0264929 + outer loop + vertex 1.51309 1.4074 2.5571 + vertex 1.5131 1.40682 2.56218 + vertex 1.51237 1.41001 2.55961 + endloop + endfacet + facet normal -0.980174 -0.12976 -0.149739 + outer loop + vertex 1.51273 1.41136 2.55609 + vertex 1.51309 1.4074 2.5571 + vertex 1.51237 1.41001 2.55961 + endloop + endfacet + facet normal -0.88639 -0.21962 0.407528 + outer loop + vertex 1.5131 1.40682 2.56218 + vertex 1.51418 1.40817 2.56524 + vertex 1.51275 1.41052 2.56341 + endloop + endfacet + facet normal -0.984151 -0.132334 0.118048 + outer loop + vertex 1.51237 1.41001 2.55961 + vertex 1.5131 1.40682 2.56218 + vertex 1.51275 1.41052 2.56341 + endloop + endfacet + facet normal -0.806377 -0.0290307 0.590689 + outer loop + vertex 1.51418 1.40817 2.56524 + vertex 1.51499 1.41263 2.56657 + vertex 1.51275 1.41052 2.56341 + endloop + endfacet + facet normal -0.441233 -0.181766 0.878792 + outer loop + vertex 1.51418 1.40817 2.56524 + vertex 1.51759 1.40861 2.56704 + vertex 1.51499 1.41263 2.56657 + endloop + endfacet + facet normal -0.307864 -0.0876281 0.947387 + outer loop + vertex 1.51759 1.40861 2.56704 + vertex 1.51876 1.41362 2.56789 + vertex 1.51499 1.41263 2.56657 + endloop + endfacet + facet normal -0.64003 0.00767554 -0.768312 + outer loop + vertex 1.51697 1.415 2.55 + vertex 1.51405 1.41318 2.55242 + vertex 1.51703 1.42 2.55 + endloop + endfacet + facet normal -0.354241 -0.170718 -0.919439 + outer loop + vertex 1.51703 1.42 2.55 + vertex 1.51405 1.41318 2.55242 + vertex 1.5143 1.41894 2.55125 + endloop + endfacet + facet normal -0.898665 -0.0493673 -0.435848 + outer loop + vertex 1.5143 1.41894 2.55125 + vertex 1.51405 1.41318 2.55242 + vertex 1.5129 1.41498 2.55458 + endloop + endfacet + facet normal -0.903832 -0.0393307 -0.426076 + outer loop + vertex 1.51296 1.41948 2.55404 + vertex 1.5143 1.41894 2.55125 + vertex 1.5129 1.41498 2.55458 + endloop + endfacet + facet normal -0.302284 -0.108435 0.94703 + outer loop + vertex 1.51876 1.41362 2.56789 + vertex 1.51808 1.41753 2.56812 + vertex 1.51499 1.41263 2.56657 + endloop + endfacet + facet normal -0.304984 -0.106527 0.946381 + outer loop + vertex 1.51499 1.41263 2.56657 + vertex 1.51808 1.41753 2.56812 + vertex 1.51453 1.41794 2.56702 + endloop + endfacet + facet normal -0.414075 -0.00496578 -0.910229 + outer loop + vertex 1.51703 1.42 2.55 + vertex 1.5143 1.41894 2.55125 + vertex 1.51697 1.425 2.55 + endloop + endfacet + facet normal -0.30094 -0.0634039 -0.951533 + outer loop + vertex 1.51697 1.425 2.55 + vertex 1.5143 1.41894 2.55125 + vertex 1.51438 1.424 2.55088 + endloop + endfacet + facet normal -0.90265 -0.0156153 -0.430092 + outer loop + vertex 1.51438 1.424 2.55088 + vertex 1.5143 1.41894 2.55125 + vertex 1.51296 1.41948 2.55404 + endloop + endfacet + facet normal -0.896991 -0.0252547 -0.441327 + outer loop + vertex 1.51293 1.42433 2.55382 + vertex 1.51438 1.424 2.55088 + vertex 1.51296 1.41948 2.55404 + endloop + endfacet + facet normal -0.302404 -0.0730594 0.950376 + outer loop + vertex 1.51808 1.41753 2.56812 + vertex 1.51786 1.42238 2.56842 + vertex 1.51453 1.41794 2.56702 + endloop + endfacet + facet normal -0.296853 -0.0776514 0.951761 + outer loop + vertex 1.51453 1.41794 2.56702 + vertex 1.51786 1.42238 2.56842 + vertex 1.5144 1.42299 2.56739 + endloop + endfacet + facet normal -0.3267 0.00914445 -0.945084 + outer loop + vertex 1.51697 1.425 2.55 + vertex 1.51438 1.424 2.55088 + vertex 1.51711 1.43 2.55 + endloop + endfacet + facet normal -0.229744 -0.038967 -0.972471 + outer loop + vertex 1.51711 1.43 2.55 + vertex 1.51438 1.424 2.55088 + vertex 1.51443 1.42903 2.55067 + endloop + endfacet + facet normal -0.896597 -0.0109436 -0.442713 + outer loop + vertex 1.51443 1.42903 2.55067 + vertex 1.51438 1.424 2.55088 + vertex 1.51293 1.42433 2.55382 + endloop + endfacet + facet normal -0.888781 -0.0234557 -0.457731 + outer loop + vertex 1.5129 1.42939 2.55363 + vertex 1.51443 1.42903 2.55067 + vertex 1.51293 1.42433 2.55382 + endloop + endfacet + facet normal -0.296004 -0.0714666 0.952509 + outer loop + vertex 1.51786 1.42238 2.56842 + vertex 1.5178 1.42742 2.56878 + vertex 1.5144 1.42299 2.56739 + endloop + endfacet + facet normal -0.272399 -0.0912443 0.957848 + outer loop + vertex 1.5144 1.42299 2.56739 + vertex 1.5178 1.42742 2.56878 + vertex 1.51432 1.42815 2.56786 + endloop + endfacet + facet normal -0.246845 0.0108642 -0.968994 + outer loop + vertex 1.51711 1.43 2.55 + vertex 1.51443 1.42903 2.55067 + vertex 1.51733 1.435 2.55 + endloop + endfacet + facet normal -0.180575 -0.0229836 -0.983293 + outer loop + vertex 1.51733 1.435 2.55 + vertex 1.51443 1.42903 2.55067 + vertex 1.51444 1.4341 2.55055 + endloop + endfacet + facet normal -0.888267 -0.00853872 -0.459249 + outer loop + vertex 1.51444 1.4341 2.55055 + vertex 1.51443 1.42903 2.55067 + vertex 1.5129 1.42939 2.55363 + endloop + endfacet + facet normal -0.875623 -0.0276641 -0.482202 + outer loop + vertex 1.51284 1.4345 2.55344 + vertex 1.51444 1.4341 2.55055 + vertex 1.5129 1.42939 2.55363 + endloop + endfacet + facet normal -0.27375 -0.0991064 0.956681 + outer loop + vertex 1.5178 1.42742 2.56878 + vertex 1.51769 1.43264 2.56929 + vertex 1.51432 1.42815 2.56786 + endloop + endfacet + facet normal -0.157758 -0.190004 0.969026 + outer loop + vertex 1.51432 1.42815 2.56786 + vertex 1.51769 1.43264 2.56929 + vertex 1.51389 1.43355 2.56885 + endloop + endfacet + facet normal -0.188256 0.0022576 -0.982117 + outer loop + vertex 1.51733 1.435 2.55 + vertex 1.51444 1.4341 2.55055 + vertex 1.51739 1.44 2.55 + endloop + endfacet + facet normal -0.182646 -0.000642914 -0.983178 + outer loop + vertex 1.51739 1.44 2.55 + vertex 1.51444 1.4341 2.55055 + vertex 1.51439 1.43914 2.55056 + endloop + endfacet + facet normal -0.874773 -0.0082657 -0.484463 + outer loop + vertex 1.51439 1.43914 2.55056 + vertex 1.51444 1.4341 2.55055 + vertex 1.51284 1.4345 2.55344 + endloop + endfacet + facet normal -0.874545 -0.00859336 -0.484869 + outer loop + vertex 1.5128 1.43968 2.55341 + vertex 1.51439 1.43914 2.55056 + vertex 1.51284 1.4345 2.55344 + endloop + endfacet + facet normal -0.474465 -0.374811 0.796492 + outer loop + vertex 1.51388 1.4372 2.57056 + vertex 1.51257 1.43649 2.56944 + vertex 1.51389 1.43355 2.56885 + endloop + endfacet + facet normal 0.2125 -0.414718 0.884789 + outer loop + vertex 1.51388 1.4372 2.57056 + vertex 1.51389 1.43355 2.56885 + vertex 1.51728 1.43813 2.57018 + endloop + endfacet + facet normal -0.15339 -0.16968 0.973489 + outer loop + vertex 1.51728 1.43813 2.57018 + vertex 1.51389 1.43355 2.56885 + vertex 1.51769 1.43264 2.56929 + endloop + endfacet + facet normal -0.182925 0.000366346 -0.983127 + outer loop + vertex 1.51739 1.44 2.55 + vertex 1.51439 1.43914 2.55056 + vertex 1.5174 1.445 2.55 + endloop + endfacet + facet normal -0.380118 0.107876 -0.918626 + outer loop + vertex 1.5174 1.445 2.55 + vertex 1.51439 1.43914 2.55056 + vertex 1.51444 1.44433 2.55115 + endloop + endfacet + facet normal -0.866891 0.0644993 -0.494307 + outer loop + vertex 1.51444 1.44433 2.55115 + vertex 1.51439 1.43914 2.55056 + vertex 1.5128 1.43968 2.55341 + endloop + endfacet + facet normal -0.856877 0.0519114 -0.512901 + outer loop + vertex 1.51285 1.44498 2.55388 + vertex 1.51444 1.44433 2.55115 + vertex 1.5128 1.43968 2.55341 + endloop + endfacet + facet normal -0.361881 0.0036151 -0.932217 + outer loop + vertex 1.5174 1.445 2.55 + vertex 1.51444 1.44433 2.55115 + vertex 1.51745 1.45 2.55 + endloop + endfacet + facet normal -0.845006 0.370808 -0.385313 + outer loop + vertex 1.51745 1.45 2.55 + vertex 1.51444 1.44433 2.55115 + vertex 1.51517 1.45 2.555 + endloop + endfacet + facet normal -0.719776 0.451347 -0.527455 + outer loop + vertex 1.51517 1.45 2.555 + vertex 1.51444 1.44433 2.55115 + vertex 1.51285 1.44498 2.55388 + endloop + endfacet + facet normal 0.240658 0.104754 -0.964941 + outer loop + vertex 1.5129 1.45017 2.55445 + vertex 1.51517 1.45 2.555 + vertex 1.51285 1.44498 2.55388 + endloop + endfacet + facet normal 0.234443 -0.00328107 -0.972124 + outer loop + vertex 1.51524 1.455 2.555 + vertex 1.51517 1.45 2.555 + vertex 1.5129 1.45017 2.55445 + endloop + endfacet + facet normal 0.235553 -0.00384855 -0.971854 + outer loop + vertex 1.51281 1.45499 2.55441 + vertex 1.51524 1.455 2.555 + vertex 1.5129 1.45017 2.55445 + endloop + endfacet + facet normal 0.235544 0.000471729 -0.971864 + outer loop + vertex 1.51523 1.46 2.555 + vertex 1.51524 1.455 2.555 + vertex 1.51281 1.45499 2.55441 + endloop + endfacet + facet normal 0.381608 -0.0760235 -0.921193 + outer loop + vertex 1.51292 1.45908 2.55412 + vertex 1.51523 1.46 2.555 + vertex 1.51281 1.45499 2.55441 + endloop + endfacet + facet normal 0.350465 0.0170745 -0.93642 + outer loop + vertex 1.51523 1.46 2.555 + vertex 1.51292 1.45908 2.55412 + vertex 1.515 1.46472 2.555 + endloop + endfacet + facet normal 0.424186 -0.0424692 -0.904579 + outer loop + vertex 1.51505 1.575 2.555 + vertex 1.515 1.5745 2.555 + vertex 1.51327 1.57535 2.55415 + endloop + endfacet + facet normal -0.89658 0 -0.442882 + outer loop + vertex 1.51752 1.575 2.55 + vertex 1.51505 1.575 2.555 + vertex 1.51752 1.58 2.55 + endloop + endfacet + facet normal -0.260354 -0.615391 -0.743983 + outer loop + vertex 1.51752 1.58 2.55 + vertex 1.51505 1.575 2.555 + vertex 1.51441 1.57956 2.55145 + endloop + endfacet + facet normal 0.259858 -0.570258 -0.779281 + outer loop + vertex 1.51441 1.57956 2.55145 + vertex 1.51505 1.575 2.555 + vertex 1.51327 1.57535 2.55415 + endloop + endfacet + facet normal -0.85807 -0.0897243 -0.505634 + outer loop + vertex 1.51286 1.57871 2.55424 + vertex 1.51441 1.57956 2.55145 + vertex 1.51327 1.57535 2.55415 + endloop + endfacet + facet normal -0.422629 -0.00760758 -0.906271 + outer loop + vertex 1.51752 1.58 2.55 + vertex 1.51441 1.57956 2.55145 + vertex 1.51743 1.585 2.55 + endloop + endfacet + facet normal -0.0876173 -0.211238 -0.9735 + outer loop + vertex 1.51743 1.585 2.55 + vertex 1.51441 1.57956 2.55145 + vertex 1.51484 1.58448 2.55035 + endloop + endfacet + facet normal -0.96765 0.013053 -0.251959 + outer loop + vertex 1.51286 1.57871 2.55424 + vertex 1.51231 1.58047 2.55645 + vertex 1.51316 1.58274 2.5533 + endloop + endfacet + facet normal -0.865387 -0.0524137 -0.498356 + outer loop + vertex 1.51286 1.57871 2.55424 + vertex 1.51316 1.58274 2.5533 + vertex 1.51441 1.57956 2.55145 + endloop + endfacet + facet normal -0.857909 -0.0414932 -0.512124 + outer loop + vertex 1.51441 1.57956 2.55145 + vertex 1.51316 1.58274 2.5533 + vertex 1.51484 1.58448 2.55035 + endloop + endfacet + facet normal -0.966878 0.00840781 -0.2551 + outer loop + vertex 1.51316 1.58274 2.5533 + vertex 1.51231 1.58047 2.55645 + vertex 1.51227 1.58333 2.55669 + endloop + endfacet + facet normal -0.131703 -0.00210697 -0.991287 + outer loop + vertex 1.51743 1.585 2.55 + vertex 1.51484 1.58448 2.55035 + vertex 1.51735 1.59 2.55 + endloop + endfacet + facet normal -0.506379 0.177842 -0.843773 + outer loop + vertex 1.51735 1.59 2.55 + vertex 1.51484 1.58448 2.55035 + vertex 1.51415 1.58875 2.55166 + endloop + endfacet + facet normal -0.923132 0.0371566 -0.382683 + outer loop + vertex 1.51271 1.58585 2.55485 + vertex 1.51271 1.58871 2.55513 + vertex 1.51415 1.58875 2.55166 + endloop + endfacet + facet normal -0.926976 0.0512354 -0.371606 + outer loop + vertex 1.51271 1.58585 2.55485 + vertex 1.51415 1.58875 2.55166 + vertex 1.51316 1.58274 2.5533 + endloop + endfacet + facet normal -0.871838 0.00999201 -0.489692 + outer loop + vertex 1.51316 1.58274 2.5533 + vertex 1.51415 1.58875 2.55166 + vertex 1.51484 1.58448 2.55035 + endloop + endfacet + facet normal -0.9678 -0.0148694 -0.251281 + outer loop + vertex 1.51316 1.58274 2.5533 + vertex 1.51227 1.58333 2.55669 + vertex 1.51271 1.58585 2.55485 + endloop + endfacet + facet normal -0.278903 0.208003 0.937522 + outer loop + vertex 1.51484 1.58258 2.56941 + vertex 1.51817 1.5878 2.56925 + vertex 1.51446 1.58785 2.56813 + endloop + endfacet + facet normal -0.452921 -0.0226445 -0.891263 + outer loop + vertex 1.51735 1.59 2.55 + vertex 1.51415 1.58875 2.55166 + vertex 1.5171 1.595 2.55 + endloop + endfacet + facet normal -0.186849 -0.168727 -0.96779 + outer loop + vertex 1.5171 1.595 2.55 + vertex 1.51415 1.58875 2.55166 + vertex 1.51472 1.59438 2.55057 + endloop + endfacet + facet normal -0.970092 0.0534157 -0.236789 + outer loop + vertex 1.51271 1.58871 2.55513 + vertex 1.51223 1.59046 2.55748 + vertex 1.51321 1.59299 2.55406 + endloop + endfacet + facet normal -0.923599 0.0113643 -0.383191 + outer loop + vertex 1.51271 1.58871 2.55513 + vertex 1.51321 1.59299 2.55406 + vertex 1.51415 1.58875 2.55166 + endloop + endfacet + facet normal -0.919481 0.0176819 -0.392737 + outer loop + vertex 1.51415 1.58875 2.55166 + vertex 1.51321 1.59299 2.55406 + vertex 1.51472 1.59438 2.55057 + endloop + endfacet + facet normal -0.971856 0.0702915 -0.224845 + outer loop + vertex 1.51321 1.59299 2.55406 + vertex 1.51223 1.59046 2.55748 + vertex 1.51227 1.59423 2.55849 + endloop + endfacet + facet normal -0.285744 0.0826335 0.954737 + outer loop + vertex 1.51817 1.5878 2.56925 + vertex 1.51791 1.59258 2.56876 + vertex 1.51446 1.58785 2.56813 + endloop + endfacet + facet normal -0.304396 0.0971856 0.947575 + outer loop + vertex 1.51446 1.58785 2.56813 + vertex 1.51791 1.59258 2.56876 + vertex 1.51438 1.59295 2.56759 + endloop + endfacet + facet normal -0.230612 -0.00691675 -0.973021 + outer loop + vertex 1.5171 1.595 2.55 + vertex 1.51472 1.59438 2.55057 + vertex 1.51695 1.6 2.55 + endloop + endfacet + facet normal -0.521726 0.121407 -0.84443 + outer loop + vertex 1.51695 1.6 2.55 + vertex 1.51472 1.59438 2.55057 + vertex 1.5145 1.59842 2.55129 + endloop + endfacet + facet normal -0.919658 0.0190801 -0.392257 + outer loop + vertex 1.51472 1.59438 2.55057 + vertex 1.51321 1.59299 2.55406 + vertex 1.5145 1.59842 2.55129 + endloop + endfacet + facet normal -0.949735 0.0707393 -0.304958 + outer loop + vertex 1.5145 1.59842 2.55129 + vertex 1.51321 1.59299 2.55406 + vertex 1.51318 1.5985 2.55541 + endloop + endfacet + facet normal -0.974336 0.0495992 -0.219566 + outer loop + vertex 1.51318 1.5985 2.55541 + vertex 1.51321 1.59299 2.55406 + vertex 1.51227 1.59423 2.55849 + endloop + endfacet + facet normal -0.97764 0.0642395 -0.200236 + outer loop + vertex 1.5123 1.59798 2.55956 + vertex 1.51318 1.5985 2.55541 + vertex 1.51227 1.59423 2.55849 + endloop + endfacet + facet normal -0.307587 0.070422 0.94891 + outer loop + vertex 1.51791 1.59258 2.56876 + vertex 1.5179 1.59759 2.56838 + vertex 1.51438 1.59295 2.56759 + endloop + endfacet + facet normal -0.28543 0.0522502 0.956974 + outer loop + vertex 1.51438 1.59295 2.56759 + vertex 1.5179 1.59759 2.56838 + vertex 1.51451 1.59788 2.56735 + endloop + endfacet + facet normal -0.461169 -0.00737774 -0.887282 + outer loop + vertex 1.51695 1.6 2.55 + vertex 1.5145 1.59842 2.55129 + vertex 1.51687 1.605 2.55 + endloop + endfacet + facet normal -0.586783 0.0533958 -0.807981 + outer loop + vertex 1.51687 1.605 2.55 + vertex 1.5145 1.59842 2.55129 + vertex 1.51451 1.60324 2.5516 + endloop + endfacet + facet normal -0.952178 0.0216402 -0.304776 + outer loop + vertex 1.5145 1.59842 2.55129 + vertex 1.51318 1.5985 2.55541 + vertex 1.51451 1.60324 2.5516 + endloop + endfacet + facet normal -0.95399 0.0271066 -0.298609 + outer loop + vertex 1.51451 1.60324 2.5516 + vertex 1.51318 1.5985 2.55541 + vertex 1.51359 1.60335 2.55455 + endloop + endfacet + facet normal -0.98701 0.0697847 -0.144711 + outer loop + vertex 1.5123 1.59798 2.55956 + vertex 1.51212 1.60032 2.56188 + vertex 1.51274 1.60237 2.55867 + endloop + endfacet + facet normal -0.977876 0.0574517 -0.201143 + outer loop + vertex 1.5123 1.59798 2.55956 + vertex 1.51274 1.60237 2.55867 + vertex 1.51318 1.5985 2.55541 + endloop + endfacet + facet normal -0.980432 0.0484426 -0.190807 + outer loop + vertex 1.51318 1.5985 2.55541 + vertex 1.51274 1.60237 2.55867 + vertex 1.51359 1.60335 2.55455 + endloop + endfacet + facet normal -0.987001 0.0693869 -0.144964 + outer loop + vertex 1.51274 1.60237 2.55867 + vertex 1.51212 1.60032 2.56188 + vertex 1.51231 1.60452 2.5626 + endloop + endfacet + facet normal -0.283496 0.0721688 0.956254 + outer loop + vertex 1.5179 1.59759 2.56838 + vertex 1.51799 1.60266 2.56802 + vertex 1.51451 1.59788 2.56735 + endloop + endfacet + facet normal -0.269235 0.0611266 0.961133 + outer loop + vertex 1.51451 1.59788 2.56735 + vertex 1.51799 1.60266 2.56802 + vertex 1.5146 1.6026 2.56708 + endloop + endfacet + facet normal -0.550956 -0.0187317 -0.834324 + outer loop + vertex 1.51687 1.605 2.55 + vertex 1.51451 1.60324 2.5516 + vertex 1.5167 1.61 2.55 + endloop + endfacet + facet normal -0.63964 0.0256662 -0.768246 + outer loop + vertex 1.5167 1.61 2.55 + vertex 1.51451 1.60324 2.5516 + vertex 1.51451 1.60797 2.55176 + endloop + endfacet + facet normal -0.954466 0.0100321 -0.298151 + outer loop + vertex 1.51451 1.60324 2.5516 + vertex 1.51359 1.60335 2.55455 + vertex 1.51451 1.60797 2.55176 + endloop + endfacet + facet normal -0.965821 0.0374981 -0.256482 + outer loop + vertex 1.51451 1.60797 2.55176 + vertex 1.51359 1.60335 2.55455 + vertex 1.51348 1.60726 2.55552 + endloop + endfacet + facet normal -0.980156 0.0223296 -0.196966 + outer loop + vertex 1.51359 1.60335 2.55455 + vertex 1.51274 1.60237 2.55867 + vertex 1.51348 1.60726 2.55552 + endloop + endfacet + facet normal -0.985863 0.0463698 -0.161012 + outer loop + vertex 1.51348 1.60726 2.55552 + vertex 1.51274 1.60237 2.55867 + vertex 1.51281 1.60778 2.5598 + endloop + endfacet + facet normal -0.990822 0.0398168 -0.129177 + outer loop + vertex 1.51281 1.60778 2.5598 + vertex 1.51274 1.60237 2.55867 + vertex 1.51231 1.60452 2.5626 + endloop + endfacet + facet normal -0.992743 0.0631578 -0.10233 + outer loop + vertex 1.51253 1.60919 2.56339 + vertex 1.51281 1.60778 2.5598 + vertex 1.51231 1.60452 2.5626 + endloop + endfacet + facet normal -0.269234 0.0610467 0.961138 + outer loop + vertex 1.51799 1.60266 2.56802 + vertex 1.5179 1.60765 2.56768 + vertex 1.5146 1.6026 2.56708 + endloop + endfacet + facet normal -0.26553 0.0584816 0.962327 + outer loop + vertex 1.5146 1.6026 2.56708 + vertex 1.5179 1.60765 2.56768 + vertex 1.51461 1.60728 2.5668 + endloop + endfacet + facet normal -0.620563 -0.00868489 -0.784109 + outer loop + vertex 1.5167 1.61 2.55 + vertex 1.51451 1.60797 2.55176 + vertex 1.51663 1.615 2.55 + endloop + endfacet + facet normal -0.705271 0.035894 -0.708028 + outer loop + vertex 1.51663 1.615 2.55 + vertex 1.51451 1.60797 2.55176 + vertex 1.51443 1.61282 2.55208 + endloop + endfacet + facet normal -0.964808 0.00204348 -0.262949 + outer loop + vertex 1.51451 1.60797 2.55176 + vertex 1.51348 1.60726 2.55552 + vertex 1.51443 1.61282 2.55208 + endloop + endfacet + facet normal -0.974016 0.0272016 -0.224841 + outer loop + vertex 1.51443 1.61282 2.55208 + vertex 1.51348 1.60726 2.55552 + vertex 1.51348 1.61236 2.55616 + endloop + endfacet + facet normal -0.987281 0.0188436 -0.157863 + outer loop + vertex 1.51348 1.60726 2.55552 + vertex 1.51281 1.60778 2.5598 + vertex 1.51348 1.61236 2.55616 + endloop + endfacet + facet normal -0.993465 0.0821967 -0.0791898 + outer loop + vertex 1.51348 1.61236 2.55616 + vertex 1.51281 1.60778 2.5598 + vertex 1.51319 1.61345 2.56085 + endloop + endfacet + facet normal -0.989816 0.087993 -0.111896 + outer loop + vertex 1.51319 1.61345 2.56085 + vertex 1.51281 1.60778 2.5598 + vertex 1.51253 1.60919 2.56339 + endloop + endfacet + facet normal -0.987635 0.15672 0.00391813 + outer loop + vertex 1.51312 1.61288 2.56429 + vertex 1.51319 1.61345 2.56085 + vertex 1.51253 1.60919 2.56339 + endloop + endfacet + facet normal -0.264772 0.0501251 0.963007 + outer loop + vertex 1.5179 1.60765 2.56768 + vertex 1.51756 1.6122 2.56735 + vertex 1.51461 1.60728 2.5668 + endloop + endfacet + facet normal -0.257984 0.0458246 0.965062 + outer loop + vertex 1.51461 1.60728 2.5668 + vertex 1.51756 1.6122 2.56735 + vertex 1.5145 1.61143 2.56657 + endloop + endfacet + facet normal -0.68859 0.00274168 -0.725146 + outer loop + vertex 1.51663 1.615 2.55 + vertex 1.51443 1.61282 2.55208 + vertex 1.51665 1.62 2.55 + endloop + endfacet + facet normal -0.710892 0.0160133 -0.703119 + outer loop + vertex 1.51665 1.62 2.55 + vertex 1.51443 1.61282 2.55208 + vertex 1.51438 1.6179 2.55224 + endloop + endfacet + facet normal -0.973664 -0.00162552 -0.227981 + outer loop + vertex 1.51443 1.61282 2.55208 + vertex 1.51348 1.61236 2.55616 + vertex 1.51438 1.6179 2.55224 + endloop + endfacet + facet normal -0.981262 0.0258297 -0.190938 + outer loop + vertex 1.51438 1.6179 2.55224 + vertex 1.51348 1.61236 2.55616 + vertex 1.51359 1.61759 2.55628 + endloop + endfacet + facet normal -0.997563 0.0232959 -0.0657642 + outer loop + vertex 1.51348 1.61236 2.55616 + vertex 1.51319 1.61345 2.56085 + vertex 1.51359 1.61759 2.55628 + endloop + endfacet + facet normal -0.995237 0.0974703 0.00164418 + outer loop + vertex 1.51359 1.61759 2.55628 + vertex 1.51319 1.61345 2.56085 + vertex 1.5137 1.61862 2.55987 + endloop + endfacet + facet normal -0.874574 0.292257 0.38692 + outer loop + vertex 1.51312 1.61288 2.56429 + vertex 1.51412 1.61392 2.56577 + vertex 1.51468 1.61803 2.56394 + endloop + endfacet + facet normal -0.955845 0.292604 0.0272605 + outer loop + vertex 1.51312 1.61288 2.56429 + vertex 1.51468 1.61803 2.56394 + vertex 1.51319 1.61345 2.56085 + endloop + endfacet + facet normal -0.957311 0.140972 0.252355 + outer loop + vertex 1.51319 1.61345 2.56085 + vertex 1.51468 1.61803 2.56394 + vertex 1.5137 1.61862 2.55987 + endloop + endfacet + facet normal -0.560074 0.400163 0.725388 + outer loop + vertex 1.51412 1.61392 2.56577 + vertex 1.51716 1.61662 2.56663 + vertex 1.51468 1.61803 2.56394 + endloop + endfacet + facet normal -0.437136 0.214914 0.873341 + outer loop + vertex 1.51412 1.61392 2.56577 + vertex 1.5145 1.61143 2.56657 + vertex 1.51716 1.61662 2.56663 + endloop + endfacet + facet normal -0.276158 0.13148 0.952077 + outer loop + vertex 1.5145 1.61143 2.56657 + vertex 1.51756 1.6122 2.56735 + vertex 1.51716 1.61662 2.56663 + endloop + endfacet + facet normal -0.6989 -0.00978123 -0.715153 + outer loop + vertex 1.51665 1.62 2.55 + vertex 1.51438 1.6179 2.55224 + vertex 1.51658 1.625 2.55 + endloop + endfacet + facet normal -0.729426 0.00950105 -0.683994 + outer loop + vertex 1.51658 1.625 2.55 + vertex 1.51438 1.6179 2.55224 + vertex 1.51445 1.62293 2.55224 + endloop + endfacet + facet normal -0.981321 0.013058 -0.191933 + outer loop + vertex 1.51438 1.6179 2.55224 + vertex 1.51359 1.61759 2.55628 + vertex 1.51445 1.62293 2.55224 + endloop + endfacet + facet normal -0.988128 0.0492285 -0.145533 + outer loop + vertex 1.51445 1.62293 2.55224 + vertex 1.51359 1.61759 2.55628 + vertex 1.51384 1.62255 2.55626 + endloop + endfacet + facet normal -0.99861 0.0504758 0.0151967 + outer loop + vertex 1.51359 1.61759 2.55628 + vertex 1.5137 1.61862 2.55987 + vertex 1.51384 1.62255 2.55626 + endloop + endfacet + facet normal -0.990087 0.112949 0.0834832 + outer loop + vertex 1.51384 1.62255 2.55626 + vertex 1.5137 1.61862 2.55987 + vertex 1.51425 1.62297 2.56055 + endloop + endfacet + facet normal -0.965552 0.0844825 0.246114 + outer loop + vertex 1.5137 1.61862 2.55987 + vertex 1.51468 1.61803 2.56394 + vertex 1.51425 1.62297 2.56055 + endloop + endfacet + facet normal -0.933047 0.144454 0.329478 + outer loop + vertex 1.51425 1.62297 2.56055 + vertex 1.51468 1.61803 2.56394 + vertex 1.51577 1.62462 2.56413 + endloop + endfacet + facet normal -0.625445 0.0803764 0.776118 + outer loop + vertex 1.51468 1.61803 2.56394 + vertex 1.518 1.62242 2.56616 + vertex 1.51577 1.62462 2.56413 + endloop + endfacet + facet normal -0.684155 0.157082 0.71222 + outer loop + vertex 1.51716 1.61662 2.56663 + vertex 1.518 1.62242 2.56616 + vertex 1.51468 1.61803 2.56394 + endloop + endfacet + facet normal -0.731067 0.0131597 -0.682179 + outer loop + vertex 1.51658 1.625 2.55 + vertex 1.51445 1.62293 2.55224 + vertex 1.51667 1.63 2.55 + endloop + endfacet + facet normal -0.74277 0.0209428 -0.669219 + outer loop + vertex 1.51667 1.63 2.55 + vertex 1.51445 1.62293 2.55224 + vertex 1.51463 1.62779 2.55219 + endloop + endfacet + facet normal -0.988525 0.0349626 -0.146953 + outer loop + vertex 1.51445 1.62293 2.55224 + vertex 1.51384 1.62255 2.55626 + vertex 1.51463 1.62779 2.55219 + endloop + endfacet + facet normal -0.991528 0.0601104 -0.115148 + outer loop + vertex 1.51463 1.62779 2.55219 + vertex 1.51384 1.62255 2.55626 + vertex 1.51412 1.62741 2.55637 + endloop + endfacet + facet normal -0.994435 0.0556977 0.0894292 + outer loop + vertex 1.51384 1.62255 2.55626 + vertex 1.51425 1.62297 2.56055 + vertex 1.51412 1.62741 2.55637 + endloop + endfacet + facet normal -0.990259 0.0793625 0.114408 + outer loop + vertex 1.51412 1.62741 2.55637 + vertex 1.51425 1.62297 2.56055 + vertex 1.51469 1.62816 2.56075 + endloop + endfacet + facet normal -0.928909 0.0647133 0.36461 + outer loop + vertex 1.51425 1.62297 2.56055 + vertex 1.51577 1.62462 2.56413 + vertex 1.51469 1.62816 2.56075 + endloop + endfacet + facet normal -0.938531 0.0408637 0.342769 + outer loop + vertex 1.51469 1.62816 2.56075 + vertex 1.51577 1.62462 2.56413 + vertex 1.51602 1.62978 2.56419 + endloop + endfacet + facet normal -0.684909 0.0248964 0.728203 + outer loop + vertex 1.51577 1.62462 2.56413 + vertex 1.51803 1.62771 2.56615 + vertex 1.51602 1.62978 2.56419 + endloop + endfacet + facet normal -0.669797 0.00453981 0.74253 + outer loop + vertex 1.518 1.62242 2.56616 + vertex 1.51803 1.62771 2.56615 + vertex 1.51577 1.62462 2.56413 + endloop + endfacet + facet normal -0.733953 0.0029398 -0.679194 + outer loop + vertex 1.51667 1.63 2.55 + vertex 1.51463 1.62779 2.55219 + vertex 1.51669 1.635 2.55 + endloop + endfacet + facet normal -0.71754 -0.00700431 -0.696482 + outer loop + vertex 1.51669 1.635 2.55 + vertex 1.51463 1.62779 2.55219 + vertex 1.51478 1.63218 2.552 + endloop + endfacet + facet normal -0.992596 0.0279647 -0.1182 + outer loop + vertex 1.51463 1.62779 2.55219 + vertex 1.51412 1.62741 2.55637 + vertex 1.51478 1.63218 2.552 + endloop + endfacet + facet normal -0.994175 0.048079 -0.0964588 + outer loop + vertex 1.51478 1.63218 2.552 + vertex 1.51412 1.62741 2.55637 + vertex 1.51437 1.63239 2.55633 + endloop + endfacet + facet normal -0.991575 0.0494406 0.119726 + outer loop + vertex 1.51412 1.62741 2.55637 + vertex 1.51469 1.62816 2.56075 + vertex 1.51437 1.63239 2.55633 + endloop + endfacet + facet normal -0.993084 0.0396889 0.110493 + outer loop + vertex 1.51437 1.63239 2.55633 + vertex 1.51469 1.62816 2.56075 + vertex 1.51489 1.63325 2.56074 + endloop + endfacet + facet normal -0.938215 0.0381136 0.343947 + outer loop + vertex 1.51469 1.62816 2.56075 + vertex 1.51602 1.62978 2.56419 + vertex 1.51489 1.63325 2.56074 + endloop + endfacet + facet normal -0.945657 0.016552 0.324744 + outer loop + vertex 1.51489 1.63325 2.56074 + vertex 1.51602 1.62978 2.56419 + vertex 1.51609 1.63453 2.56416 + endloop + endfacet + facet normal -0.768603 0.0159642 0.639527 + outer loop + vertex 1.51602 1.62978 2.56419 + vertex 1.51756 1.63183 2.56599 + vertex 1.51609 1.63453 2.56416 + endloop + endfacet + facet normal -0.726293 -0.0560495 0.685096 + outer loop + vertex 1.51803 1.62771 2.56615 + vertex 1.51756 1.63183 2.56599 + vertex 1.51602 1.62978 2.56419 + endloop + endfacet + facet normal -0.249432 0.00193941 -0.96839 + outer loop + vertex 1.52 1.635 2.54768 + vertex 1.51653 1.63605 2.54858 + vertex 1.52 1.64 2.54769 + endloop + endfacet + facet normal -0.36845 -0.766764 -0.525659 + outer loop + vertex 1.51669 1.635 2.55 + vertex 1.51653 1.63605 2.54858 + vertex 1.52 1.635 2.54768 + endloop + endfacet + facet normal 0.439953 -0.698371 -0.564553 + outer loop + vertex 1.51669 1.635 2.55 + vertex 1.51478 1.63218 2.552 + vertex 1.51653 1.63605 2.54858 + endloop + endfacet + facet normal -0.890032 0.000297973 -0.455898 + outer loop + vertex 1.51653 1.63605 2.54858 + vertex 1.51478 1.63218 2.552 + vertex 1.51493 1.63659 2.55171 + endloop + endfacet + facet normal -0.995048 0.0274434 -0.0955368 + outer loop + vertex 1.51478 1.63218 2.552 + vertex 1.51437 1.63239 2.55633 + vertex 1.51493 1.63659 2.55171 + endloop + endfacet + facet normal -0.994934 0.0255739 -0.0972214 + outer loop + vertex 1.51493 1.63659 2.55171 + vertex 1.51437 1.63239 2.55633 + vertex 1.51451 1.63743 2.55619 + endloop + endfacet + facet normal -0.993198 0.0315203 0.112094 + outer loop + vertex 1.51437 1.63239 2.55633 + vertex 1.51489 1.63325 2.56074 + vertex 1.51451 1.63743 2.55619 + endloop + endfacet + facet normal -0.994594 0.0202657 0.101844 + outer loop + vertex 1.51451 1.63743 2.55619 + vertex 1.51489 1.63325 2.56074 + vertex 1.51498 1.63822 2.56066 + endloop + endfacet + facet normal -0.946245 0.022682 0.322654 + outer loop + vertex 1.51489 1.63325 2.56074 + vertex 1.51609 1.63453 2.56416 + vertex 1.51498 1.63822 2.56066 + endloop + endfacet + facet normal -0.946246 0.0226785 0.322651 + outer loop + vertex 1.51498 1.63822 2.56066 + vertex 1.51609 1.63453 2.56416 + vertex 1.51618 1.63908 2.5641 + endloop + endfacet + facet normal -0.707126 0.0226515 0.706724 + outer loop + vertex 1.51609 1.63453 2.56416 + vertex 1.51811 1.63604 2.56613 + vertex 1.51618 1.63908 2.5641 + endloop + endfacet + facet normal -0.723925 0.0719933 0.686111 + outer loop + vertex 1.51756 1.63183 2.56599 + vertex 1.51811 1.63604 2.56613 + vertex 1.51609 1.63453 2.56416 + endloop + endfacet + facet normal -0.145068 0.00198153 -0.98942 + outer loop + vertex 1.52 1.64 2.54769 + vertex 1.51668 1.64035 2.54818 + vertex 1.52 1.645 2.5477 + endloop + endfacet + facet normal -0.153691 -0.08575 -0.984391 + outer loop + vertex 1.51653 1.63605 2.54858 + vertex 1.51668 1.64035 2.54818 + vertex 1.52 1.64 2.54769 + endloop + endfacet + facet normal -0.890741 -0.0106356 -0.454386 + outer loop + vertex 1.51653 1.63605 2.54858 + vertex 1.51493 1.63659 2.55171 + vertex 1.51668 1.64035 2.54818 + endloop + endfacet + facet normal -0.893206 -0.00501078 -0.44962 + outer loop + vertex 1.51668 1.64035 2.54818 + vertex 1.51493 1.63659 2.55171 + vertex 1.51503 1.64157 2.55146 + endloop + endfacet + facet normal -0.995337 0.0150434 -0.095274 + outer loop + vertex 1.51493 1.63659 2.55171 + vertex 1.51451 1.63743 2.55619 + vertex 1.51503 1.64157 2.55146 + endloop + endfacet + facet normal -0.995225 0.0134211 -0.0966785 + outer loop + vertex 1.51503 1.64157 2.55146 + vertex 1.51451 1.63743 2.55619 + vertex 1.51459 1.6425 2.55608 + endloop + endfacet + facet normal -0.994597 0.0174898 0.102329 + outer loop + vertex 1.51451 1.63743 2.55619 + vertex 1.51498 1.63822 2.56066 + vertex 1.51459 1.6425 2.55608 + endloop + endfacet + facet normal -0.989229 0.0540265 0.136039 + outer loop + vertex 1.51459 1.6425 2.55608 + vertex 1.51498 1.63822 2.56066 + vertex 1.51526 1.64308 2.5607 + endloop + endfacet + facet normal -0.947392 0.0502222 0.316112 + outer loop + vertex 1.51498 1.63822 2.56066 + vertex 1.51618 1.63908 2.5641 + vertex 1.51526 1.64308 2.5607 + endloop + endfacet + facet normal -0.896712 0.147732 0.417233 + outer loop + vertex 1.51526 1.64308 2.5607 + vertex 1.51618 1.63908 2.5641 + vertex 1.51689 1.64329 2.56414 + endloop + endfacet + facet normal -0.773699 0.124921 0.621116 + outer loop + vertex 1.51618 1.63908 2.5641 + vertex 1.51766 1.64005 2.56575 + vertex 1.51689 1.64329 2.56414 + endloop + endfacet + facet normal -0.738356 -0.0190662 0.674142 + outer loop + vertex 1.51811 1.63604 2.56613 + vertex 1.51766 1.64005 2.56575 + vertex 1.51618 1.63908 2.5641 + endloop + endfacet + facet normal -0.033531 -0.520782 -0.853031 + outer loop + vertex 1.52 1.645 2.5477 + vertex 1.51648 1.64543 2.54757 + vertex 1.51851 1.64962 2.54494 + endloop + endfacet + facet normal 0.0213241 -0.117118 -0.992889 + outer loop + vertex 1.51668 1.64035 2.54818 + vertex 1.51648 1.64543 2.54757 + vertex 1.52 1.645 2.5477 + endloop + endfacet + facet normal -0.901642 -0.086608 -0.423722 + outer loop + vertex 1.51668 1.64035 2.54818 + vertex 1.51503 1.64157 2.55146 + vertex 1.51648 1.64543 2.54757 + endloop + endfacet + facet normal -0.926474 -0.0286255 -0.375269 + outer loop + vertex 1.51648 1.64543 2.54757 + vertex 1.51503 1.64157 2.55146 + vertex 1.51495 1.64676 2.55126 + endloop + endfacet + facet normal -0.995741 -0.0186728 -0.0902861 + outer loop + vertex 1.51503 1.64157 2.55146 + vertex 1.51459 1.6425 2.55608 + vertex 1.51495 1.64676 2.55126 + endloop + endfacet + facet normal -0.998453 0.0339788 -0.044013 + outer loop + vertex 1.51495 1.64676 2.55126 + vertex 1.51459 1.6425 2.55608 + vertex 1.51476 1.64756 2.55613 + endloop + endfacet + facet normal -0.989784 0.0320689 0.138925 + outer loop + vertex 1.51459 1.6425 2.55608 + vertex 1.51526 1.64308 2.5607 + vertex 1.51476 1.64756 2.55613 + endloop + endfacet + facet normal -0.952869 0.158454 0.258713 + outer loop + vertex 1.51476 1.64756 2.55613 + vertex 1.51526 1.64308 2.5607 + vertex 1.51627 1.64847 2.56113 + endloop + endfacet + facet normal -0.505139 0.294579 0.811208 + outer loop + vertex 1.51973 1.64728 2.56446 + vertex 1.51689 1.64329 2.56414 + vertex 1.51896 1.6427 2.56564 + endloop + endfacet + facet normal -0.581754 0.355477 0.731573 + outer loop + vertex 1.51973 1.64728 2.56446 + vertex 1.51627 1.64847 2.56113 + vertex 1.51689 1.64329 2.56414 + endloop + endfacet + facet normal -0.898026 0.135396 0.41859 + outer loop + vertex 1.51627 1.64847 2.56113 + vertex 1.51526 1.64308 2.5607 + vertex 1.51689 1.64329 2.56414 + endloop + endfacet + facet normal -0.509569 0.282669 0.812673 + outer loop + vertex 1.51896 1.6427 2.56564 + vertex 1.51689 1.64329 2.56414 + vertex 1.51766 1.64005 2.56575 + endloop + endfacet + facet normal -0.670962 -0.149989 -0.726164 + outer loop + vertex 1.51851 1.64962 2.54494 + vertex 1.51601 1.65078 2.54701 + vertex 1.51787 1.65481 2.54446 + endloop + endfacet + facet normal -0.668497 -0.135648 -0.73124 + outer loop + vertex 1.51648 1.64543 2.54757 + vertex 1.51601 1.65078 2.54701 + vertex 1.51851 1.64962 2.54494 + endloop + endfacet + facet normal -0.931116 -0.118464 -0.344947 + outer loop + vertex 1.51648 1.64543 2.54757 + vertex 1.51495 1.64676 2.55126 + vertex 1.51601 1.65078 2.54701 + endloop + endfacet + facet normal -0.964507 -0.023336 -0.263025 + outer loop + vertex 1.51601 1.65078 2.54701 + vertex 1.51495 1.64676 2.55126 + vertex 1.51486 1.65192 2.55114 + endloop + endfacet + facet normal -0.999202 -0.0186135 -0.0353484 + outer loop + vertex 1.51495 1.64676 2.55126 + vertex 1.51476 1.64756 2.55613 + vertex 1.51486 1.65192 2.55114 + endloop + endfacet + facet normal -0.999322 0.0350036 0.011441 + outer loop + vertex 1.51486 1.65192 2.55114 + vertex 1.51476 1.64756 2.55613 + vertex 1.51494 1.6527 2.55606 + endloop + endfacet + facet normal -0.958586 0.0370638 0.28238 + outer loop + vertex 1.51476 1.64756 2.55613 + vertex 1.51627 1.64847 2.56113 + vertex 1.51494 1.6527 2.55606 + endloop + endfacet + facet normal -0.950437 0.0654214 0.303956 + outer loop + vertex 1.51494 1.6527 2.55606 + vertex 1.51627 1.64847 2.56113 + vertex 1.51641 1.65441 2.5603 + endloop + endfacet + facet normal -0.689125 0.116232 0.71526 + outer loop + vertex 1.51627 1.64847 2.56113 + vertex 1.51919 1.65263 2.56327 + vertex 1.51641 1.65441 2.5603 + endloop + endfacet + facet normal -0.67266 0.0951659 0.733806 + outer loop + vertex 1.51973 1.64728 2.56446 + vertex 1.51919 1.65263 2.56327 + vertex 1.51627 1.64847 2.56113 + endloop + endfacet + facet normal -0.747426 -0.0916254 -0.657997 + outer loop + vertex 1.51787 1.65481 2.54446 + vertex 1.51574 1.65602 2.54671 + vertex 1.51752 1.65971 2.54418 + endloop + endfacet + facet normal -0.744388 -0.0762958 -0.663374 + outer loop + vertex 1.51601 1.65078 2.54701 + vertex 1.51574 1.65602 2.54671 + vertex 1.51787 1.65481 2.54446 + endloop + endfacet + facet normal -0.965583 -0.0639819 -0.252103 + outer loop + vertex 1.51601 1.65078 2.54701 + vertex 1.51486 1.65192 2.55114 + vertex 1.51574 1.65602 2.54671 + endloop + endfacet + facet normal -0.979119 -0.00825776 -0.203119 + outer loop + vertex 1.51574 1.65602 2.54671 + vertex 1.51486 1.65192 2.55114 + vertex 1.51485 1.65703 2.55094 + endloop + endfacet + facet normal -0.999856 0.000135636 0.0169814 + outer loop + vertex 1.51486 1.65192 2.55114 + vertex 1.51494 1.6527 2.55606 + vertex 1.51485 1.65703 2.55094 + endloop + endfacet + facet normal -0.998707 0.0292504 0.0415806 + outer loop + vertex 1.51485 1.65703 2.55094 + vertex 1.51494 1.6527 2.55606 + vertex 1.51508 1.65779 2.55587 + endloop + endfacet + facet normal -0.948553 0.0380187 0.314327 + outer loop + vertex 1.51494 1.6527 2.55606 + vertex 1.51641 1.65441 2.5603 + vertex 1.51508 1.65779 2.55587 + endloop + endfacet + facet normal -0.946052 0.0471693 0.320563 + outer loop + vertex 1.51508 1.65779 2.55587 + vertex 1.51641 1.65441 2.5603 + vertex 1.51657 1.65952 2.56003 + endloop + endfacet + facet normal -0.700507 0.0603816 0.711086 + outer loop + vertex 1.51641 1.65441 2.5603 + vertex 1.51919 1.65775 2.56275 + vertex 1.51657 1.65952 2.56003 + endloop + endfacet + facet normal -0.70656 0.0704928 0.704134 + outer loop + vertex 1.51919 1.65263 2.56327 + vertex 1.51919 1.65775 2.56275 + vertex 1.51641 1.65441 2.5603 + endloop + endfacet + facet normal -0.76149 -0.0630184 -0.645106 + outer loop + vertex 1.51752 1.65971 2.54418 + vertex 1.51577 1.6616 2.54606 + vertex 1.51755 1.66342 2.54377 + endloop + endfacet + facet normal -0.764865 -0.0709716 -0.640269 + outer loop + vertex 1.51574 1.65602 2.54671 + vertex 1.51577 1.6616 2.54606 + vertex 1.51752 1.65971 2.54418 + endloop + endfacet + facet normal -0.979472 -0.0185793 -0.200724 + outer loop + vertex 1.51574 1.65602 2.54671 + vertex 1.51485 1.65703 2.55094 + vertex 1.51577 1.6616 2.54606 + endloop + endfacet + facet normal -0.985363 0.0157283 -0.169743 + outer loop + vertex 1.51577 1.6616 2.54606 + vertex 1.51485 1.65703 2.55094 + vertex 1.51495 1.66211 2.55085 + endloop + endfacet + facet normal -0.998877 0.0198419 0.0430308 + outer loop + vertex 1.51485 1.65703 2.55094 + vertex 1.51508 1.65779 2.55587 + vertex 1.51495 1.66211 2.55085 + endloop + endfacet + facet normal -0.997364 0.0401418 0.060449 + outer loop + vertex 1.51495 1.66211 2.55085 + vertex 1.51508 1.65779 2.55587 + vertex 1.51528 1.6628 2.55578 + endloop + endfacet + facet normal -0.945688 0.0428021 0.322244 + outer loop + vertex 1.51508 1.65779 2.55587 + vertex 1.51657 1.65952 2.56003 + vertex 1.51528 1.6628 2.55578 + endloop + endfacet + facet normal -0.943691 0.0498102 0.327058 + outer loop + vertex 1.51528 1.6628 2.55578 + vertex 1.51657 1.65952 2.56003 + vertex 1.51679 1.66455 2.55987 + endloop + endfacet + facet normal -0.711219 0.051867 0.701054 + outer loop + vertex 1.51657 1.65952 2.56003 + vertex 1.51926 1.66274 2.56252 + vertex 1.51679 1.66455 2.55987 + endloop + endfacet + facet normal -0.706575 0.0439587 0.706272 + outer loop + vertex 1.51919 1.65775 2.56275 + vertex 1.51926 1.66274 2.56252 + vertex 1.51657 1.65952 2.56003 + endloop + endfacet + facet normal 0.352424 -0.16646 -0.920917 + outer loop + vertex 1.52 1.66668 2.545 + vertex 1.51708 1.66632 2.54395 + vertex 1.52 1.67 2.5444 + endloop + endfacet + facet normal 0.325233 0.10964 -0.939256 + outer loop + vertex 1.51755 1.66342 2.54377 + vertex 1.51708 1.66632 2.54395 + vertex 1.52 1.66668 2.545 + endloop + endfacet + facet normal -0.751627 -0.0840935 -0.654206 + outer loop + vertex 1.51755 1.66342 2.54377 + vertex 1.51577 1.6616 2.54606 + vertex 1.51708 1.66632 2.54395 + endloop + endfacet + facet normal -0.86378 0.0144256 -0.503663 + outer loop + vertex 1.51577 1.6616 2.54606 + vertex 1.51559 1.66663 2.54651 + vertex 1.51708 1.66632 2.54395 + endloop + endfacet + facet normal -0.985926 -0.019591 -0.166031 + outer loop + vertex 1.51577 1.6616 2.54606 + vertex 1.51495 1.66211 2.55085 + vertex 1.51559 1.66663 2.54651 + endloop + endfacet + facet normal -0.992852 0.0298848 -0.115551 + outer loop + vertex 1.51559 1.66663 2.54651 + vertex 1.51495 1.66211 2.55085 + vertex 1.51509 1.66713 2.55091 + endloop + endfacet + facet normal -0.997679 0.0276902 0.0622056 + outer loop + vertex 1.51495 1.66211 2.55085 + vertex 1.51528 1.6628 2.55578 + vertex 1.51509 1.66713 2.55091 + endloop + endfacet + facet normal -0.99589 0.045742 0.0781751 + outer loop + vertex 1.51509 1.66713 2.55091 + vertex 1.51528 1.6628 2.55578 + vertex 1.51551 1.66785 2.55575 + endloop + endfacet + facet normal -0.943294 0.0452764 0.328856 + outer loop + vertex 1.51528 1.6628 2.55578 + vertex 1.51679 1.66455 2.55987 + vertex 1.51551 1.66785 2.55575 + endloop + endfacet + facet normal -0.943566 0.0443512 0.328201 + outer loop + vertex 1.51551 1.66785 2.55575 + vertex 1.51679 1.66455 2.55987 + vertex 1.51697 1.66961 2.55973 + endloop + endfacet + facet normal -0.712074 0.0459325 0.7006 + outer loop + vertex 1.51679 1.66455 2.55987 + vertex 1.51935 1.66774 2.56227 + vertex 1.51697 1.66961 2.55973 + endloop + endfacet + facet normal -0.712955 0.0473907 0.699607 + outer loop + vertex 1.51926 1.66274 2.56252 + vertex 1.51935 1.66774 2.56227 + vertex 1.51679 1.66455 2.55987 + endloop + endfacet + facet normal 0.126969 -0.0317206 -0.991399 + outer loop + vertex 1.52 1.67 2.5444 + vertex 1.51702 1.67068 2.544 + vertex 1.52 1.675 2.54424 + endloop + endfacet + facet normal 0.137159 0.0131492 -0.990462 + outer loop + vertex 1.51708 1.66632 2.54395 + vertex 1.51702 1.67068 2.544 + vertex 1.52 1.67 2.5444 + endloop + endfacet + facet normal -0.864874 -0.00472533 -0.501967 + outer loop + vertex 1.51708 1.66632 2.54395 + vertex 1.51559 1.66663 2.54651 + vertex 1.51702 1.67068 2.544 + endloop + endfacet + facet normal -0.887234 0.0289245 -0.460412 + outer loop + vertex 1.51702 1.67068 2.544 + vertex 1.51559 1.66663 2.54651 + vertex 1.51568 1.67151 2.54664 + endloop + endfacet + facet normal -0.993181 0.0212977 -0.114625 + outer loop + vertex 1.51559 1.66663 2.54651 + vertex 1.51509 1.66713 2.55091 + vertex 1.51568 1.67151 2.54664 + endloop + endfacet + facet normal -0.994582 0.0395157 -0.0961557 + outer loop + vertex 1.51568 1.67151 2.54664 + vertex 1.51509 1.66713 2.55091 + vertex 1.51528 1.67211 2.551 + endloop + endfacet + facet normal -0.996156 0.0366834 0.0795473 + outer loop + vertex 1.51509 1.66713 2.55091 + vertex 1.51551 1.66785 2.55575 + vertex 1.51528 1.67211 2.551 + endloop + endfacet + facet normal -0.994958 0.0468935 0.0886537 + outer loop + vertex 1.51528 1.67211 2.551 + vertex 1.51551 1.66785 2.55575 + vertex 1.51574 1.67288 2.55573 + endloop + endfacet + facet normal -0.943641 0.0451442 0.327878 + outer loop + vertex 1.51551 1.66785 2.55575 + vertex 1.51697 1.66961 2.55973 + vertex 1.51574 1.67288 2.55573 + endloop + endfacet + facet normal -0.946387 0.0357615 0.321051 + outer loop + vertex 1.51574 1.67288 2.55573 + vertex 1.51697 1.66961 2.55973 + vertex 1.51712 1.67465 2.55959 + endloop + endfacet + facet normal -0.718038 0.0398977 0.694859 + outer loop + vertex 1.51697 1.66961 2.55973 + vertex 1.51935 1.67272 2.56201 + vertex 1.51712 1.67465 2.55959 + endloop + endfacet + facet normal -0.715913 0.0365284 0.697234 + outer loop + vertex 1.51935 1.66774 2.56227 + vertex 1.51935 1.67272 2.56201 + vertex 1.51697 1.66961 2.55973 + endloop + endfacet + facet normal 0.0489963 0.0379309 -0.998078 + outer loop + vertex 1.52 1.675 2.54424 + vertex 1.51713 1.67554 2.54412 + vertex 1.52 1.68 2.54443 + endloop + endfacet + facet normal 0.0464265 0.0242098 -0.998628 + outer loop + vertex 1.51702 1.67068 2.544 + vertex 1.51713 1.67554 2.54412 + vertex 1.52 1.675 2.54424 + endloop + endfacet + facet normal -0.886856 0.0313701 -0.46098 + outer loop + vertex 1.51702 1.67068 2.544 + vertex 1.51568 1.67151 2.54664 + vertex 1.51713 1.67554 2.54412 + endloop + endfacet + facet normal -0.90101 0.055681 -0.430209 + outer loop + vertex 1.51713 1.67554 2.54412 + vertex 1.51568 1.67151 2.54664 + vertex 1.51586 1.67638 2.54689 + endloop + endfacet + facet normal -0.994434 0.0422466 -0.0965212 + outer loop + vertex 1.51568 1.67151 2.54664 + vertex 1.51528 1.67211 2.551 + vertex 1.51586 1.67638 2.54689 + endloop + endfacet + facet normal -0.994885 0.0516899 -0.0867821 + outer loop + vertex 1.51586 1.67638 2.54689 + vertex 1.51528 1.67211 2.551 + vertex 1.51552 1.67693 2.55116 + endloop + endfacet + facet normal -0.994994 0.0457467 0.0888447 + outer loop + vertex 1.51528 1.67211 2.551 + vertex 1.51574 1.67288 2.55573 + vertex 1.51552 1.67693 2.55116 + endloop + endfacet + facet normal -0.99449 0.0496897 0.0923104 + outer loop + vertex 1.51552 1.67693 2.55116 + vertex 1.51574 1.67288 2.55573 + vertex 1.51599 1.6779 2.55568 + endloop + endfacet + facet normal -0.947747 0.0497418 0.315121 + outer loop + vertex 1.51574 1.67288 2.55573 + vertex 1.51712 1.67465 2.55959 + vertex 1.51599 1.6779 2.55568 + endloop + endfacet + facet normal -0.953849 0.0281433 0.298966 + outer loop + vertex 1.51599 1.6779 2.55568 + vertex 1.51712 1.67465 2.55959 + vertex 1.51721 1.6797 2.55942 + endloop + endfacet + facet normal -0.753965 0.0358585 0.655935 + outer loop + vertex 1.51712 1.67465 2.55959 + vertex 1.51918 1.67756 2.5618 + vertex 1.51721 1.6797 2.55942 + endloop + endfacet + facet normal -0.733482 0.00314 0.679701 + outer loop + vertex 1.51935 1.67272 2.56201 + vertex 1.51918 1.67756 2.5618 + vertex 1.51712 1.67465 2.55959 + endloop + endfacet + facet normal -0.0163776 0.0578785 -0.998189 + outer loop + vertex 1.52 1.68 2.54443 + vertex 1.51744 1.68119 2.54454 + vertex 1.52 1.685 2.54472 + endloop + endfacet + facet normal -0.0084586 0.0748184 -0.997161 + outer loop + vertex 1.51713 1.67554 2.54412 + vertex 1.51744 1.68119 2.54454 + vertex 1.52 1.68 2.54443 + endloop + endfacet + facet normal -0.896275 0.0817741 -0.435894 + outer loop + vertex 1.51713 1.67554 2.54412 + vertex 1.51586 1.67638 2.54689 + vertex 1.51744 1.68119 2.54454 + endloop + endfacet + facet normal -0.897696 0.083866 -0.43256 + outer loop + vertex 1.51744 1.68119 2.54454 + vertex 1.51586 1.67638 2.54689 + vertex 1.51598 1.68046 2.54745 + endloop + endfacet + facet normal -0.995592 0.039193 -0.0852096 + outer loop + vertex 1.51586 1.67638 2.54689 + vertex 1.51552 1.67693 2.55116 + vertex 1.51598 1.68046 2.54745 + endloop + endfacet + facet normal -0.996047 0.0629425 -0.0626741 + outer loop + vertex 1.51598 1.68046 2.54745 + vertex 1.51552 1.67693 2.55116 + vertex 1.51583 1.68179 2.55105 + endloop + endfacet + facet normal -0.99385 0.0662974 0.0886976 + outer loop + vertex 1.51552 1.67693 2.55116 + vertex 1.51599 1.6779 2.55568 + vertex 1.51583 1.68179 2.55105 + endloop + endfacet + facet normal -0.996777 0.0419968 0.0683582 + outer loop + vertex 1.51583 1.68179 2.55105 + vertex 1.51599 1.6779 2.55568 + vertex 1.51619 1.68298 2.55558 + endloop + endfacet + facet normal -0.955521 0.0447537 0.291506 + outer loop + vertex 1.51599 1.6779 2.55568 + vertex 1.51721 1.6797 2.55942 + vertex 1.51619 1.68298 2.55558 + endloop + endfacet + facet normal -0.967163 -0.00274366 0.254141 + outer loop + vertex 1.51619 1.68298 2.55558 + vertex 1.51721 1.6797 2.55942 + vertex 1.51717 1.68477 2.55929 + endloop + endfacet + facet normal -0.763701 0.00924043 0.645504 + outer loop + vertex 1.51721 1.6797 2.55942 + vertex 1.51904 1.68244 2.56155 + vertex 1.51717 1.68477 2.55929 + endloop + endfacet + facet normal -0.76529 0.011801 0.643577 + outer loop + vertex 1.51918 1.67756 2.5618 + vertex 1.51904 1.68244 2.56155 + vertex 1.51721 1.6797 2.55942 + endloop + endfacet + facet normal -0.0774437 0.0985571 -0.992113 + outer loop + vertex 1.52 1.685 2.54472 + vertex 1.51744 1.68119 2.54454 + vertex 1.52 1.68782 2.545 + endloop + endfacet + facet normal -0.125639 -0.393547 -0.910679 + outer loop + vertex 1.52 1.68782 2.545 + vertex 1.51678 1.68564 2.54639 + vertex 1.51804 1.6903 2.5442 + endloop + endfacet + facet normal -0.524403 0.258366 -0.811325 + outer loop + vertex 1.52 1.68782 2.545 + vertex 1.51744 1.68119 2.54454 + vertex 1.51678 1.68564 2.54639 + endloop + endfacet + facet normal -0.896414 0.0497107 -0.440421 + outer loop + vertex 1.51744 1.68119 2.54454 + vertex 1.51598 1.68046 2.54745 + vertex 1.51678 1.68564 2.54639 + endloop + endfacet + facet normal -0.986724 0.135747 -0.0891523 + outer loop + vertex 1.51598 1.68046 2.54745 + vertex 1.51583 1.68179 2.55105 + vertex 1.51678 1.68564 2.54639 + endloop + endfacet + facet normal -0.985169 0.0417626 -0.166429 + outer loop + vertex 1.51678 1.68564 2.54639 + vertex 1.51583 1.68179 2.55105 + vertex 1.51608 1.68698 2.55089 + endloop + endfacet + facet normal -0.996568 0.0494342 0.0663943 + outer loop + vertex 1.51583 1.68179 2.55105 + vertex 1.51619 1.68298 2.55558 + vertex 1.51608 1.68698 2.55089 + endloop + endfacet + facet normal -0.999327 0.012099 0.0346256 + outer loop + vertex 1.51608 1.68698 2.55089 + vertex 1.51619 1.68298 2.55558 + vertex 1.51625 1.68809 2.55554 + endloop + endfacet + facet normal -0.968963 0.0133718 0.246845 + outer loop + vertex 1.51619 1.68298 2.55558 + vertex 1.51717 1.68477 2.55929 + vertex 1.51625 1.68809 2.55554 + endloop + endfacet + facet normal -0.978526 -0.0396152 0.202281 + outer loop + vertex 1.51625 1.68809 2.55554 + vertex 1.51717 1.68477 2.55929 + vertex 1.51694 1.68967 2.55915 + endloop + endfacet + facet normal -0.796552 -0.0195302 0.604254 + outer loop + vertex 1.51717 1.68477 2.55929 + vertex 1.51863 1.68741 2.56132 + vertex 1.51694 1.68967 2.55915 + endloop + endfacet + facet normal -0.785767 -0.0356674 0.617494 + outer loop + vertex 1.51904 1.68244 2.56155 + vertex 1.51863 1.68741 2.56132 + vertex 1.51717 1.68477 2.55929 + endloop + endfacet + facet normal -0.862686 -0.0376209 -0.504339 + outer loop + vertex 1.51804 1.6903 2.5442 + vertex 1.51669 1.69155 2.54641 + vertex 1.51795 1.69402 2.54407 + endloop + endfacet + facet normal -0.856887 -0.0117705 -0.515371 + outer loop + vertex 1.51678 1.68564 2.54639 + vertex 1.51669 1.69155 2.54641 + vertex 1.51804 1.6903 2.5442 + endloop + endfacet + facet normal -0.988574 -0.0156247 -0.149926 + outer loop + vertex 1.51678 1.68564 2.54639 + vertex 1.51608 1.68698 2.55089 + vertex 1.51669 1.69155 2.54641 + endloop + endfacet + facet normal -0.992806 0.0154779 -0.118728 + outer loop + vertex 1.51669 1.69155 2.54641 + vertex 1.51608 1.68698 2.55089 + vertex 1.51613 1.69203 2.55115 + endloop + endfacet + facet normal -0.999334 0.00766036 0.0356904 + outer loop + vertex 1.51608 1.68698 2.55089 + vertex 1.51625 1.68809 2.55554 + vertex 1.51613 1.69203 2.55115 + endloop + endfacet + facet normal -0.999656 -0.00309566 0.0260633 + outer loop + vertex 1.51613 1.69203 2.55115 + vertex 1.51625 1.68809 2.55554 + vertex 1.51624 1.69308 2.55555 + endloop + endfacet + facet normal -0.982317 -0.00328132 0.187199 + outer loop + vertex 1.51625 1.68809 2.55554 + vertex 1.51694 1.68967 2.55915 + vertex 1.51624 1.69308 2.55555 + endloop + endfacet + facet normal -0.982488 -0.00429251 0.186274 + outer loop + vertex 1.51624 1.69308 2.55555 + vertex 1.51694 1.68967 2.55915 + vertex 1.5169 1.69419 2.55904 + endloop + endfacet + facet normal -0.889932 0.00315917 0.456081 + outer loop + vertex 1.51694 1.68967 2.55915 + vertex 1.5179 1.6914 2.56102 + vertex 1.5169 1.69419 2.55904 + endloop + endfacet + facet normal -0.835902 -0.113727 0.536968 + outer loop + vertex 1.51863 1.68741 2.56132 + vertex 1.5179 1.6914 2.56102 + vertex 1.51694 1.68967 2.55915 + endloop + endfacet + facet normal 0.118423 -0.0346603 -0.992358 + outer loop + vertex 1.52 1.69914 2.545 + vertex 1.51776 1.69687 2.54481 + vertex 1.52 1.7 2.54497 + endloop + endfacet + facet normal -0.161249 0.238148 -0.95775 + outer loop + vertex 1.51795 1.69402 2.54407 + vertex 1.51776 1.69687 2.54481 + vertex 1.52 1.69914 2.545 + endloop + endfacet + facet normal -0.90125 0.0521548 -0.430149 + outer loop + vertex 1.51795 1.69402 2.54407 + vertex 1.51669 1.69155 2.54641 + vertex 1.51776 1.69687 2.54481 + endloop + endfacet + facet normal -0.925296 0.0745575 -0.371845 + outer loop + vertex 1.51669 1.69155 2.54641 + vertex 1.5165 1.69552 2.54768 + vertex 1.51776 1.69687 2.54481 + endloop + endfacet + facet normal -0.993177 -0.010584 -0.116136 + outer loop + vertex 1.51669 1.69155 2.54641 + vertex 1.51613 1.69203 2.55115 + vertex 1.5165 1.69552 2.54768 + endloop + endfacet + facet normal -0.996072 0.019194 -0.0864398 + outer loop + vertex 1.5165 1.69552 2.54768 + vertex 1.51613 1.69203 2.55115 + vertex 1.51621 1.69685 2.55125 + endloop + endfacet + facet normal -0.99963 0.0169765 0.0212546 + outer loop + vertex 1.51613 1.69203 2.55115 + vertex 1.51624 1.69308 2.55555 + vertex 1.51621 1.69685 2.55125 + endloop + endfacet + facet normal -0.998071 0.0433908 0.0443938 + outer loop + vertex 1.51621 1.69685 2.55125 + vertex 1.51624 1.69308 2.55555 + vertex 1.51645 1.69801 2.55555 + endloop + endfacet + facet normal -0.98421 0.0427325 0.171768 + outer loop + vertex 1.51624 1.69308 2.55555 + vertex 1.5169 1.69419 2.55904 + vertex 1.51645 1.69801 2.55555 + endloop + endfacet + facet normal -0.935826 0.172299 0.307479 + outer loop + vertex 1.51645 1.69801 2.55555 + vertex 1.5169 1.69419 2.55904 + vertex 1.51766 1.69846 2.55896 + endloop + endfacet + facet normal -0.814991 0.155827 0.558129 + outer loop + vertex 1.5169 1.69419 2.55904 + vertex 1.51834 1.69477 2.56098 + vertex 1.51766 1.69846 2.55896 + endloop + endfacet + facet normal -0.813684 0.111707 0.570474 + outer loop + vertex 1.5179 1.6914 2.56102 + vertex 1.51834 1.69477 2.56098 + vertex 1.5169 1.69419 2.55904 + endloop + endfacet + facet normal -0.0271011 0.0696687 -0.997202 + outer loop + vertex 1.52 1.7 2.54497 + vertex 1.51776 1.69687 2.54481 + vertex 1.52 1.70043 2.545 + endloop + endfacet + facet normal -0.479173 -0.301651 -0.824257 + outer loop + vertex 1.52 1.70043 2.545 + vertex 1.51703 1.70017 2.54682 + vertex 1.5182 1.70457 2.54453 + endloop + endfacet + facet normal -0.509559 0.361695 -0.780722 + outer loop + vertex 1.52 1.70043 2.545 + vertex 1.51776 1.69687 2.54481 + vertex 1.51703 1.70017 2.54682 + endloop + endfacet + facet normal -0.920627 0.0336303 -0.388991 + outer loop + vertex 1.51776 1.69687 2.54481 + vertex 1.5165 1.69552 2.54768 + vertex 1.51703 1.70017 2.54682 + endloop + endfacet + facet normal -0.989235 0.0925967 -0.113314 + outer loop + vertex 1.5165 1.69552 2.54768 + vertex 1.51621 1.69685 2.55125 + vertex 1.51703 1.70017 2.54682 + endloop + endfacet + facet normal -0.987964 0.0468561 -0.147419 + outer loop + vertex 1.51703 1.70017 2.54682 + vertex 1.51621 1.69685 2.55125 + vertex 1.51645 1.70189 2.55125 + endloop + endfacet + facet normal -0.997942 0.0472475 0.0433452 + outer loop + vertex 1.51621 1.69685 2.55125 + vertex 1.51645 1.69801 2.55555 + vertex 1.51645 1.70189 2.55125 + endloop + endfacet + facet normal -0.977837 0.15507 0.140669 + outer loop + vertex 1.51645 1.70189 2.55125 + vertex 1.51645 1.69801 2.55555 + vertex 1.51733 1.70342 2.5557 + endloop + endfacet + facet normal -0.565246 0.341512 0.75091 + outer loop + vertex 1.52025 1.70245 2.5591 + vertex 1.51766 1.69846 2.55896 + vertex 1.51954 1.69795 2.56061 + endloop + endfacet + facet normal -0.639475 0.393079 0.660727 + outer loop + vertex 1.52025 1.70245 2.5591 + vertex 1.51733 1.70342 2.5557 + vertex 1.51766 1.69846 2.55896 + endloop + endfacet + facet normal -0.93898 0.144069 0.312348 + outer loop + vertex 1.51733 1.70342 2.5557 + vertex 1.51645 1.69801 2.55555 + vertex 1.51766 1.69846 2.55896 + endloop + endfacet + facet normal -0.578554 0.307628 0.755408 + outer loop + vertex 1.51954 1.69795 2.56061 + vertex 1.51766 1.69846 2.55896 + vertex 1.51834 1.69477 2.56098 + endloop + endfacet + facet normal -0.906658 -0.0809976 -0.414018 + outer loop + vertex 1.5182 1.70457 2.54453 + vertex 1.51687 1.70543 2.54727 + vertex 1.51785 1.70909 2.5444 + endloop + endfacet + facet normal -0.898544 0.0100682 -0.438768 + outer loop + vertex 1.51703 1.70017 2.54682 + vertex 1.51687 1.70543 2.54727 + vertex 1.5182 1.70457 2.54453 + endloop + endfacet + facet normal -0.992311 -0.0196928 -0.122194 + outer loop + vertex 1.51703 1.70017 2.54682 + vertex 1.51645 1.70189 2.55125 + vertex 1.51687 1.70543 2.54727 + endloop + endfacet + facet normal -0.996864 0.045409 -0.0648087 + outer loop + vertex 1.51687 1.70543 2.54727 + vertex 1.51645 1.70189 2.55125 + vertex 1.51667 1.7068 2.55132 + endloop + endfacet + facet normal -0.982673 0.0413626 0.180676 + outer loop + vertex 1.51645 1.70189 2.55125 + vertex 1.51733 1.70342 2.5557 + vertex 1.51667 1.7068 2.55132 + endloop + endfacet + facet normal -0.980113 0.0548603 0.190704 + outer loop + vertex 1.51667 1.7068 2.55132 + vertex 1.51733 1.70342 2.5557 + vertex 1.5174 1.70854 2.55455 + endloop + endfacet + facet normal -0.76634 0.149482 0.624802 + outer loop + vertex 1.51733 1.70342 2.5557 + vertex 1.51943 1.70749 2.5573 + vertex 1.5174 1.70854 2.55455 + endloop + endfacet + facet normal -0.736619 0.117902 0.665951 + outer loop + vertex 1.52025 1.70245 2.5591 + vertex 1.51943 1.70749 2.5573 + vertex 1.51733 1.70342 2.5557 + endloop + endfacet + facet normal -0.966142 -0.00774153 -0.257894 + outer loop + vertex 1.51785 1.70909 2.5444 + vertex 1.51695 1.70988 2.54775 + vertex 1.51768 1.71271 2.54492 + endloop + endfacet + facet normal -0.961778 0.0470334 -0.269761 + outer loop + vertex 1.51687 1.70543 2.54727 + vertex 1.51695 1.70988 2.54775 + vertex 1.51785 1.70909 2.5444 + endloop + endfacet + facet normal -0.998024 0.0245437 -0.0578388 + outer loop + vertex 1.51687 1.70543 2.54727 + vertex 1.51667 1.7068 2.55132 + vertex 1.51695 1.70988 2.54775 + endloop + endfacet + facet normal -0.997438 0.0688464 -0.0194201 + outer loop + vertex 1.51695 1.70988 2.54775 + vertex 1.51667 1.7068 2.55132 + vertex 1.51695 1.71082 2.55144 + endloop + endfacet + facet normal -0.81963 0.161845 0.549557 + outer loop + vertex 1.51768 1.71172 2.55403 + vertex 1.5174 1.70854 2.55455 + vertex 1.51883 1.7109 2.556 + endloop + endfacet + facet normal -0.965339 0.123145 0.23012 + outer loop + vertex 1.51768 1.71172 2.55403 + vertex 1.51695 1.71082 2.55144 + vertex 1.5174 1.70854 2.55455 + endloop + endfacet + facet normal -0.980402 0.0615799 0.187135 + outer loop + vertex 1.51695 1.71082 2.55144 + vertex 1.51667 1.7068 2.55132 + vertex 1.5174 1.70854 2.55455 + endloop + endfacet + facet normal -0.781598 0.0974809 0.616119 + outer loop + vertex 1.51883 1.7109 2.556 + vertex 1.5174 1.70854 2.55455 + vertex 1.51943 1.70749 2.5573 + endloop + endfacet + facet normal -0.983623 0.128662 -0.126224 + outer loop + vertex 1.51768 1.71271 2.54492 + vertex 1.51695 1.70988 2.54775 + vertex 1.51737 1.71376 2.54843 + endloop + endfacet + facet normal -0.97427 0.214104 0.0704112 + outer loop + vertex 1.51737 1.71376 2.54843 + vertex 1.51695 1.71082 2.55144 + vertex 1.51763 1.71376 2.55201 + endloop + endfacet + facet normal -0.993109 0.113095 -0.0307113 + outer loop + vertex 1.51695 1.70988 2.54775 + vertex 1.51695 1.71082 2.55144 + vertex 1.51737 1.71376 2.54843 + endloop + endfacet + facet normal -0.960704 0.18417 0.207678 + outer loop + vertex 1.51763 1.71376 2.55201 + vertex 1.51695 1.71082 2.55144 + vertex 1.51768 1.71172 2.55403 + endloop + endfacet + facet normal -0.134425 -0.640123 -0.756421 + outer loop + vertex 1.52 2.01256 2.49 + vertex 1.51855 2.01061 2.4919 + vertex 1.515 2.01361 2.49 + endloop + endfacet + facet normal -0.300063 -0.738957 -0.603245 + outer loop + vertex 1.51855 2.01061 2.4919 + vertex 1.51468 2.01162 2.4926 + vertex 1.515 2.01361 2.49 + endloop + endfacet + facet normal -0.262224 -0.962758 -0.0658385 + outer loop + vertex 1.51855 2.01061 2.4919 + vertex 1.51783 2.01053 2.49603 + vertex 1.51468 2.01162 2.4926 + endloop + endfacet + facet normal -0.226671 -0.96879 -0.100334 + outer loop + vertex 1.51783 2.01053 2.49603 + vertex 1.5138 2.0114 2.49676 + vertex 1.51468 2.01162 2.4926 + endloop + endfacet + facet normal -0.168571 -0.96198 0.214891 + outer loop + vertex 1.51783 2.01053 2.49603 + vertex 1.51594 2.01164 2.49951 + vertex 1.5138 2.0114 2.49676 + endloop + endfacet + facet normal -0.162435 -0.964046 0.210311 + outer loop + vertex 1.51594 2.01164 2.49951 + vertex 1.5127 2.0122 2.4996 + vertex 1.5138 2.0114 2.49676 + endloop + endfacet + facet normal -0.110991 -0.742788 0.660263 + outer loop + vertex 1.51594 2.01164 2.49951 + vertex 1.5128 2.01358 2.50117 + vertex 1.5127 2.0122 2.4996 + endloop + endfacet + facet normal -0.044497 -0.689086 0.723312 + outer loop + vertex 1.51712 2.0134 2.50126 + vertex 1.5128 2.01358 2.50117 + vertex 1.51594 2.01164 2.49951 + endloop + endfacet + facet normal 0.142969 0.46186 0.875354 + outer loop + vertex 1.51435 2.10973 2.47135 + vertex 1.51908 2.10891 2.47101 + vertex 1.51689 2.112 2.46974 + endloop + endfacet + facet normal 0.134587 0.46935 0.872695 + outer loop + vertex 1.51227 2.11347 2.46966 + vertex 1.51435 2.10973 2.47135 + vertex 1.51689 2.112 2.46974 + endloop + endfacet + facet normal 0.126159 0.386814 0.913487 + outer loop + vertex 1.5163 2.10591 2.4727 + vertex 1.51435 2.10973 2.47135 + vertex 1.5108 2.10683 2.47307 + endloop + endfacet + facet normal 0.132953 0.389528 0.911368 + outer loop + vertex 1.51908 2.10891 2.47101 + vertex 1.51435 2.10973 2.47135 + vertex 1.5163 2.10591 2.4727 + endloop + endfacet + facet normal 0.17238 0.583033 0.793951 + outer loop + vertex 1.51689 2.112 2.46974 + vertex 1.51676 2.11517 2.46744 + vertex 1.51227 2.11347 2.46966 + endloop + endfacet + facet normal 0.166007 0.592513 0.78827 + outer loop + vertex 1.51227 2.11347 2.46966 + vertex 1.51676 2.11517 2.46744 + vertex 1.51192 2.1166 2.46738 + endloop + endfacet + facet normal 0.198145 0.879502 0.432683 + outer loop + vertex 1.51867 2.11968 2.46112 + vertex 1.51634 2.12115 2.45921 + vertex 1.51447 2.12044 2.46151 + endloop + endfacet + facet normal 0.181357 0.828228 0.530233 + outer loop + vertex 1.51447 2.12044 2.46151 + vertex 1.51042 2.12057 2.46268 + vertex 1.51438 2.1185 2.46456 + endloop + endfacet + facet normal 0.197148 0.825451 0.528927 + outer loop + vertex 1.51447 2.12044 2.46151 + vertex 1.51438 2.1185 2.46456 + vertex 1.51867 2.11968 2.46112 + endloop + endfacet + facet normal 0.197725 0.82496 0.529478 + outer loop + vertex 1.51867 2.11968 2.46112 + vertex 1.51438 2.1185 2.46456 + vertex 1.51934 2.11732 2.46455 + endloop + endfacet + facet normal 0.204848 0.7194 0.663702 + outer loop + vertex 1.51676 2.11517 2.46744 + vertex 1.51438 2.1185 2.46456 + vertex 1.51192 2.1166 2.46738 + endloop + endfacet + facet normal 0.170788 0.710987 0.68215 + outer loop + vertex 1.51934 2.11732 2.46455 + vertex 1.51438 2.1185 2.46456 + vertex 1.51676 2.11517 2.46744 + endloop + endfacet + facet normal 0.0132456 0.206989 0.978254 + outer loop + vertex 1.52 2.12678 2.455 + vertex 1.515 2.1271 2.455 + vertex 1.51731 2.1229 2.45586 + endloop + endfacet + facet normal 0.00241596 0.201279 0.979531 + outer loop + vertex 1.51731 2.1229 2.45586 + vertex 1.515 2.1271 2.455 + vertex 1.51188 2.12409 2.45563 + endloop + endfacet + facet normal 0.152745 0.902494 0.402709 + outer loop + vertex 1.51634 2.12115 2.45921 + vertex 1.51207 2.12204 2.45883 + vertex 1.51447 2.12044 2.46151 + endloop + endfacet + facet normal 0.136171 0.860473 0.490962 + outer loop + vertex 1.51634 2.12115 2.45921 + vertex 1.51731 2.1229 2.45586 + vertex 1.51207 2.12204 2.45883 + endloop + endfacet + facet normal 0.159645 0.835855 0.525224 + outer loop + vertex 1.51731 2.1229 2.45586 + vertex 1.51188 2.12409 2.45563 + vertex 1.51207 2.12204 2.45883 + endloop + endfacet + facet normal 0.147846 0.901584 0.406555 + outer loop + vertex 1.51447 2.12044 2.46151 + vertex 1.51207 2.12204 2.45883 + vertex 1.51042 2.12057 2.46268 + endloop + endfacet + facet normal -0.583715 -0.498415 -0.640983 + outer loop + vertex 1.52291 0.91 2.45 + vertex 1.52 0.906978 2.455 + vertex 1.52 0.91 2.45265 + endloop + endfacet + facet normal -0.669649 -0.395349 -0.628704 + outer loop + vertex 1.52291 0.91 2.45 + vertex 1.525 0.90646 2.45 + vertex 1.52 0.906978 2.455 + endloop + endfacet + facet normal 0.708762 0.0477923 0.703827 + outer loop + vertex 1.525 0.90646 2.45 + vertex 1.52201 0.907304 2.45295 + vertex 1.52 0.906978 2.455 + endloop + endfacet + facet normal 0.174235 -0.927625 0.330385 + outer loop + vertex 1.52083 0.908086 2.45577 + vertex 1.52201 0.907304 2.45295 + vertex 1.52464 0.908338 2.45447 + endloop + endfacet + facet normal 0.196754 -0.920428 0.337786 + outer loop + vertex 1.52083 0.908086 2.45577 + vertex 1.51708 0.907257 2.4557 + vertex 1.52201 0.907304 2.45295 + endloop + endfacet + facet normal 0.163802 0.936442 0.310234 + outer loop + vertex 1.51708 0.907257 2.4557 + vertex 1.52 0.906978 2.455 + vertex 1.52201 0.907304 2.45295 + endloop + endfacet + facet normal 0.187379 -0.885705 0.424754 + outer loop + vertex 1.52083 0.908086 2.45577 + vertex 1.51826 0.908711 2.45821 + vertex 1.51708 0.907257 2.4557 + endloop + endfacet + facet normal 0.204573 -0.880185 0.428281 + outer loop + vertex 1.52464 0.908338 2.45447 + vertex 1.5223 0.909745 2.45848 + vertex 1.52083 0.908086 2.45577 + endloop + endfacet + facet normal 0.196248 -0.879949 0.432639 + outer loop + vertex 1.51826 0.908711 2.45821 + vertex 1.52083 0.908086 2.45577 + vertex 1.5223 0.909745 2.45848 + endloop + endfacet + facet normal 0.175046 -0.824685 0.537823 + outer loop + vertex 1.51826 0.908711 2.45821 + vertex 1.5223 0.909745 2.45848 + vertex 1.51684 0.910827 2.46192 + endloop + endfacet + facet normal 0.181785 -0.81762 0.546307 + outer loop + vertex 1.51684 0.910827 2.46192 + vertex 1.5223 0.909745 2.45848 + vertex 1.52166 0.911821 2.4618 + endloop + endfacet + facet normal 0.170019 -0.749264 0.640076 + outer loop + vertex 1.52166 0.911821 2.4618 + vertex 1.51932 0.91336 2.46422 + vertex 1.51684 0.910827 2.46192 + endloop + endfacet + facet normal 0.194614 -0.732035 0.652878 + outer loop + vertex 1.52353 0.913991 2.46367 + vertex 1.51932 0.91336 2.46422 + vertex 1.52166 0.911821 2.4618 + endloop + endfacet + facet normal 0.192922 -0.648666 0.736215 + outer loop + vertex 1.51932 0.91336 2.46422 + vertex 1.52353 0.913991 2.46367 + vertex 1.52131 0.916084 2.4661 + endloop + endfacet + facet normal 0.194505 -0.649204 0.735324 + outer loop + vertex 1.51762 0.915146 2.46625 + vertex 1.51932 0.91336 2.46422 + vertex 1.52131 0.916084 2.4661 + endloop + endfacet + facet normal 0.173493 -0.554139 0.814144 + outer loop + vertex 1.52131 0.916084 2.4661 + vertex 1.51849 0.918372 2.46826 + vertex 1.51762 0.915146 2.46625 + endloop + endfacet + facet normal 0.165483 -0.561084 0.811048 + outer loop + vertex 1.52405 0.919517 2.46792 + vertex 1.51849 0.918372 2.46826 + vertex 1.52131 0.916084 2.4661 + endloop + endfacet + facet normal 0.151893 -0.479099 0.864519 + outer loop + vertex 1.52405 0.919517 2.46792 + vertex 1.52248 0.922553 2.46987 + vertex 1.51849 0.918372 2.46826 + endloop + endfacet + facet normal 0.268539 -0.949148 -0.164331 + outer loop + vertex 1.52289 1.01815 2.48559 + vertex 1.52547 1.01906 2.48453 + vertex 1.525 1.01885 2.485 + endloop + endfacet + facet normal 0.380798 -0.473657 0.79413 + outer loop + vertex 1.52289 1.01815 2.48559 + vertex 1.525 1.01885 2.485 + vertex 1.51931 1.01709 2.48668 + endloop + endfacet + facet normal -0.210305 0.938885 0.27252 + outer loop + vertex 1.51931 1.01709 2.48668 + vertex 1.525 1.01885 2.485 + vertex 1.52 1.01773 2.485 + endloop + endfacet + facet normal -0.292122 0.955955 -0.0285436 + outer loop + vertex 1.52237 1.01807 2.48805 + vertex 1.52289 1.01815 2.48559 + vertex 1.51931 1.01709 2.48668 + endloop + endfacet + facet normal -0.339827 0.936015 0.0916203 + outer loop + vertex 1.52237 1.01807 2.48805 + vertex 1.51931 1.01709 2.48668 + vertex 1.52157 1.01748 2.49111 + endloop + endfacet + facet normal -0.322033 0.943177 0.0819231 + outer loop + vertex 1.52157 1.01748 2.49111 + vertex 1.51931 1.01709 2.48668 + vertex 1.51766 1.01613 2.49129 + endloop + endfacet + facet normal -0.296709 0.900877 0.316836 + outer loop + vertex 1.52157 1.01748 2.49111 + vertex 1.51766 1.01613 2.49129 + vertex 1.52176 1.01612 2.49513 + endloop + endfacet + facet normal -0.29968 0.898773 0.319997 + outer loop + vertex 1.52176 1.01612 2.49513 + vertex 1.51766 1.01613 2.49129 + vertex 1.51711 1.01451 2.49531 + endloop + endfacet + facet normal -0.154384 0.714334 0.682563 + outer loop + vertex 1.52133 1.01272 2.49813 + vertex 1.51711 1.01451 2.49531 + vertex 1.51548 1.01167 2.49791 + endloop + endfacet + facet normal -0.202444 0.66226 0.721407 + outer loop + vertex 1.52176 1.01612 2.49513 + vertex 1.51711 1.01451 2.49531 + vertex 1.52133 1.01272 2.49813 + endloop + endfacet + facet normal -0.34186 0.939495 -0.0219391 + outer loop + vertex 1.52547 1.01906 2.48453 + vertex 1.52289 1.01815 2.48559 + vertex 1.52572 1.01922 2.48732 + endloop + endfacet + facet normal -0.333271 0.942079 -0.0376533 + outer loop + vertex 1.52572 1.01922 2.48732 + vertex 1.52289 1.01815 2.48559 + vertex 1.52237 1.01807 2.48805 + endloop + endfacet + facet normal -0.993123 -0.104778 -0.0522264 + outer loop + vertex 1.52245 1.24711 2.54095 + vertex 1.52209 1.24975 2.54252 + vertex 1.52222 1.25019 2.53904 + endloop + endfacet + facet normal -0.982813 -0.17288 0.0647454 + outer loop + vertex 1.52245 1.24711 2.54095 + vertex 1.52265 1.24693 2.54353 + vertex 1.52209 1.24975 2.54252 + endloop + endfacet + facet normal -0.989437 -0.0840118 -0.118138 + outer loop + vertex 1.52222 1.25019 2.53904 + vertex 1.52179 1.25326 2.54052 + vertex 1.52212 1.25338 2.53761 + endloop + endfacet + facet normal -0.99187 -0.115444 -0.0535314 + outer loop + vertex 1.52209 1.24975 2.54252 + vertex 1.52179 1.25326 2.54052 + vertex 1.52222 1.25019 2.53904 + endloop + endfacet + facet normal -0.964748 -0.105974 0.240896 + outer loop + vertex 1.52279 1.24953 2.54525 + vertex 1.52209 1.24975 2.54252 + vertex 1.52265 1.24693 2.54353 + endloop + endfacet + facet normal -0.963878 -0.115711 0.239898 + outer loop + vertex 1.52279 1.24953 2.54525 + vertex 1.52221 1.2542 2.54518 + vertex 1.52209 1.24975 2.54252 + endloop + endfacet + facet normal -0.994802 -0.0298097 0.0973674 + outer loop + vertex 1.52221 1.2542 2.54518 + vertex 1.52179 1.25326 2.54052 + vertex 1.52209 1.24975 2.54252 + endloop + endfacet + facet normal -0.791144 -0.088196 0.605238 + outer loop + vertex 1.52279 1.24953 2.54525 + vertex 1.52469 1.25177 2.54806 + vertex 1.52221 1.2542 2.54518 + endloop + endfacet + facet normal -0.90342 0.0062809 -0.428712 + outer loop + vertex 1.52278 1.25611 2.53577 + vertex 1.52188 1.25669 2.53767 + vertex 1.52307 1.26034 2.53522 + endloop + endfacet + facet normal -0.909445 -0.0590401 -0.411611 + outer loop + vertex 1.52212 1.25338 2.53761 + vertex 1.52188 1.25669 2.53767 + vertex 1.52278 1.25611 2.53577 + endloop + endfacet + facet normal -0.9905 -0.0710629 -0.117731 + outer loop + vertex 1.52212 1.25338 2.53761 + vertex 1.52179 1.25326 2.54052 + vertex 1.52188 1.25669 2.53767 + endloop + endfacet + facet normal -0.989961 -0.0735437 -0.120703 + outer loop + vertex 1.52179 1.25326 2.54052 + vertex 1.5214 1.25763 2.54107 + vertex 1.52188 1.25669 2.53767 + endloop + endfacet + facet normal -0.988481 -0.102416 0.111428 + outer loop + vertex 1.52179 1.25326 2.54052 + vertex 1.52221 1.2542 2.54518 + vertex 1.5214 1.25763 2.54107 + endloop + endfacet + facet normal -0.982104 -0.183487 0.0424831 + outer loop + vertex 1.5214 1.25763 2.54107 + vertex 1.52221 1.2542 2.54518 + vertex 1.52126 1.25916 2.54444 + endloop + endfacet + facet normal -0.833891 -0.301346 0.462403 + outer loop + vertex 1.5238 1.25576 2.54904 + vertex 1.52221 1.2542 2.54518 + vertex 1.52469 1.25177 2.54806 + endloop + endfacet + facet normal -0.861089 -0.239429 0.448553 + outer loop + vertex 1.5238 1.25576 2.54904 + vertex 1.52242 1.25959 2.54845 + vertex 1.52221 1.2542 2.54518 + endloop + endfacet + facet normal -0.94661 -0.140128 0.290332 + outer loop + vertex 1.52242 1.25959 2.54845 + vertex 1.52126 1.25916 2.54444 + vertex 1.52221 1.2542 2.54518 + endloop + endfacet + facet normal -0.673479 -0.129239 0.72782 + outer loop + vertex 1.5238 1.25576 2.54904 + vertex 1.52526 1.25919 2.55101 + vertex 1.52242 1.25959 2.54845 + endloop + endfacet + facet normal -0.855514 -0.0317086 -0.516808 + outer loop + vertex 1.52307 1.26034 2.53522 + vertex 1.52167 1.26136 2.53747 + vertex 1.52312 1.2654 2.53483 + endloop + endfacet + facet normal -0.860059 -0.0603541 -0.506612 + outer loop + vertex 1.52188 1.25669 2.53767 + vertex 1.52167 1.26136 2.53747 + vertex 1.52307 1.26034 2.53522 + endloop + endfacet + facet normal -0.990614 -0.0492171 -0.127518 + outer loop + vertex 1.52188 1.25669 2.53767 + vertex 1.5214 1.25763 2.54107 + vertex 1.52167 1.26136 2.53747 + endloop + endfacet + facet normal -0.979594 -0.0968877 -0.176093 + outer loop + vertex 1.52167 1.26136 2.53747 + vertex 1.5214 1.25763 2.54107 + vertex 1.52092 1.26244 2.54106 + endloop + endfacet + facet normal -0.995149 -0.0983269 0.00320116 + outer loop + vertex 1.5214 1.25763 2.54107 + vertex 1.52126 1.25916 2.54444 + vertex 1.52092 1.26244 2.54106 + endloop + endfacet + facet normal -0.995951 -0.0890635 0.0122556 + outer loop + vertex 1.52092 1.26244 2.54106 + vertex 1.52126 1.25916 2.54444 + vertex 1.52089 1.26337 2.5453 + endloop + endfacet + facet normal -0.94643 -0.141209 0.290397 + outer loop + vertex 1.52126 1.25916 2.54444 + vertex 1.52242 1.25959 2.54845 + vertex 1.52089 1.26337 2.5453 + endloop + endfacet + facet normal -0.946855 -0.143469 0.287894 + outer loop + vertex 1.52089 1.26337 2.5453 + vertex 1.52242 1.25959 2.54845 + vertex 1.52188 1.26502 2.54938 + endloop + endfacet + facet normal -0.68422 -0.1882 0.704573 + outer loop + vertex 1.52242 1.25959 2.54845 + vertex 1.52456 1.26338 2.55155 + vertex 1.52188 1.26502 2.54938 + endloop + endfacet + facet normal -0.670888 -0.202853 0.713274 + outer loop + vertex 1.52526 1.25919 2.55101 + vertex 1.52456 1.26338 2.55155 + vertex 1.52242 1.25959 2.54845 + endloop + endfacet + facet normal -0.821456 -0.0197582 -0.569929 + outer loop + vertex 1.52312 1.2654 2.53483 + vertex 1.52144 1.26644 2.53722 + vertex 1.52313 1.27052 2.53464 + endloop + endfacet + facet normal -0.829157 -0.0661407 -0.55509 + outer loop + vertex 1.52167 1.26136 2.53747 + vertex 1.52144 1.26644 2.53722 + vertex 1.52312 1.2654 2.53483 + endloop + endfacet + facet normal -0.980471 -0.0552422 -0.188747 + outer loop + vertex 1.52167 1.26136 2.53747 + vertex 1.52092 1.26244 2.54106 + vertex 1.52144 1.26644 2.53722 + endloop + endfacet + facet normal -0.97469 -0.0764743 -0.210075 + outer loop + vertex 1.52144 1.26644 2.53722 + vertex 1.52092 1.26244 2.54106 + vertex 1.52051 1.26733 2.54117 + endloop + endfacet + facet normal -0.996476 -0.0831639 0.0109458 + outer loop + vertex 1.52092 1.26244 2.54106 + vertex 1.52089 1.26337 2.5453 + vertex 1.52051 1.26733 2.54117 + endloop + endfacet + facet normal -0.995954 -0.089752 0.00457884 + outer loop + vertex 1.52051 1.26733 2.54117 + vertex 1.52089 1.26337 2.5453 + vertex 1.52045 1.26829 2.54572 + endloop + endfacet + facet normal -0.954882 -0.109458 0.276079 + outer loop + vertex 1.52089 1.26337 2.5453 + vertex 1.52188 1.26502 2.54938 + vertex 1.52045 1.26829 2.54572 + endloop + endfacet + facet normal -0.952306 -0.0915215 0.291097 + outer loop + vertex 1.52045 1.26829 2.54572 + vertex 1.52188 1.26502 2.54938 + vertex 1.52153 1.27005 2.54983 + endloop + endfacet + facet normal -0.711587 -0.111354 0.693718 + outer loop + vertex 1.52188 1.26502 2.54938 + vertex 1.52416 1.26815 2.55221 + vertex 1.52153 1.27005 2.54983 + endloop + endfacet + facet normal -0.677322 -0.158659 0.718374 + outer loop + vertex 1.52456 1.26338 2.55155 + vertex 1.52416 1.26815 2.55221 + vertex 1.52188 1.26502 2.54938 + endloop + endfacet + facet normal -0.789544 0.0172201 -0.613452 + outer loop + vertex 1.52313 1.27052 2.53464 + vertex 1.52122 1.27145 2.53712 + vertex 1.5232 1.2754 2.53469 + endloop + endfacet + facet normal -0.800298 -0.0461858 -0.597821 + outer loop + vertex 1.52144 1.26644 2.53722 + vertex 1.52122 1.27145 2.53712 + vertex 1.52313 1.27052 2.53464 + endloop + endfacet + facet normal -0.975082 -0.0460784 -0.217005 + outer loop + vertex 1.52144 1.26644 2.53722 + vertex 1.52051 1.26733 2.54117 + vertex 1.52122 1.27145 2.53712 + endloop + endfacet + facet normal -0.971491 -0.0590827 -0.229595 + outer loop + vertex 1.52122 1.27145 2.53712 + vertex 1.52051 1.26733 2.54117 + vertex 1.52019 1.27229 2.54125 + endloop + endfacet + facet normal -0.997922 -0.0644224 -0.000777655 + outer loop + vertex 1.52051 1.26733 2.54117 + vertex 1.52045 1.26829 2.54572 + vertex 1.52019 1.27229 2.54125 + endloop + endfacet + facet normal -0.998283 -0.0583824 0.00464453 + outer loop + vertex 1.52019 1.27229 2.54125 + vertex 1.52045 1.26829 2.54572 + vertex 1.52016 1.27328 2.5459 + endloop + endfacet + facet normal -0.957319 -0.0658776 0.281427 + outer loop + vertex 1.52045 1.26829 2.54572 + vertex 1.52153 1.27005 2.54983 + vertex 1.52016 1.27328 2.5459 + endloop + endfacet + facet normal -0.954194 -0.0475897 0.29538 + outer loop + vertex 1.52016 1.27328 2.5459 + vertex 1.52153 1.27005 2.54983 + vertex 1.52136 1.27511 2.55009 + endloop + endfacet + facet normal -0.723337 -0.0596282 0.687915 + outer loop + vertex 1.52153 1.27005 2.54983 + vertex 1.52397 1.27314 2.55266 + vertex 1.52136 1.27511 2.55009 + endloop + endfacet + facet normal -0.70469 -0.0890116 0.70391 + outer loop + vertex 1.52416 1.26815 2.55221 + vertex 1.52397 1.27314 2.55266 + vertex 1.52153 1.27005 2.54983 + endloop + endfacet + facet normal -0.747237 0.124618 -0.652769 + outer loop + vertex 1.5232 1.2754 2.53469 + vertex 1.52112 1.27628 2.53723 + vertex 1.52354 1.28012 2.53519 + endloop + endfacet + facet normal -0.775086 -0.00135916 -0.631854 + outer loop + vertex 1.52122 1.27145 2.53712 + vertex 1.52112 1.27628 2.53723 + vertex 1.5232 1.2754 2.53469 + endloop + endfacet + facet normal -0.971057 -0.015013 -0.238377 + outer loop + vertex 1.52122 1.27145 2.53712 + vertex 1.52019 1.27229 2.54125 + vertex 1.52112 1.27628 2.53723 + endloop + endfacet + facet normal -0.969304 -0.0219642 -0.244881 + outer loop + vertex 1.52112 1.27628 2.53723 + vertex 1.52019 1.27229 2.54125 + vertex 1.52004 1.27718 2.5414 + endloop + endfacet + facet normal -0.999537 -0.0304034 -0.00135713 + outer loop + vertex 1.52019 1.27229 2.54125 + vertex 1.52016 1.27328 2.5459 + vertex 1.52004 1.27718 2.5414 + endloop + endfacet + facet normal -0.999382 -0.0347831 -0.00515882 + outer loop + vertex 1.52004 1.27718 2.5414 + vertex 1.52016 1.27328 2.5459 + vertex 1.51998 1.27828 2.54604 + endloop + endfacet + facet normal -0.95517 -0.0417341 0.2931 + outer loop + vertex 1.52016 1.27328 2.5459 + vertex 1.52136 1.27511 2.55009 + vertex 1.51998 1.27828 2.54604 + endloop + endfacet + facet normal -0.955417 -0.0431287 0.292092 + outer loop + vertex 1.51998 1.27828 2.54604 + vertex 1.52136 1.27511 2.55009 + vertex 1.52123 1.28024 2.55043 + endloop + endfacet + facet normal -0.724615 -0.0634228 0.68623 + outer loop + vertex 1.52136 1.27511 2.55009 + vertex 1.52393 1.2783 2.55309 + vertex 1.52123 1.28024 2.55043 + endloop + endfacet + facet normal -0.72459 -0.0634632 0.686252 + outer loop + vertex 1.52397 1.27314 2.55266 + vertex 1.52393 1.2783 2.55309 + vertex 1.52136 1.27511 2.55009 + endloop + endfacet + facet normal -0.54657 0.531917 -0.646781 + outer loop + vertex 1.52354 1.28012 2.53519 + vertex 1.52136 1.28106 2.5378 + vertex 1.525 1.285 2.53797 + endloop + endfacet + facet normal -0.741145 0.116295 -0.661196 + outer loop + vertex 1.52112 1.27628 2.53723 + vertex 1.52136 1.28106 2.5378 + vertex 1.52354 1.28012 2.53519 + endloop + endfacet + facet normal -0.960947 0.0801565 -0.264871 + outer loop + vertex 1.52112 1.27628 2.53723 + vertex 1.52004 1.27718 2.5414 + vertex 1.52136 1.28106 2.5378 + endloop + endfacet + facet normal -0.939361 0.000294534 -0.342929 + outer loop + vertex 1.52136 1.28106 2.5378 + vertex 1.52004 1.27718 2.5414 + vertex 1.51998 1.28204 2.54159 + endloop + endfacet + facet normal -0.99986 -0.0132542 -0.0102513 + outer loop + vertex 1.52004 1.27718 2.5414 + vertex 1.51998 1.27828 2.54604 + vertex 1.51998 1.28204 2.54159 + endloop + endfacet + facet normal -0.999377 -0.0274155 -0.0222051 + outer loop + vertex 1.51998 1.28204 2.54159 + vertex 1.51998 1.27828 2.54604 + vertex 1.51984 1.28327 2.5462 + endloop + endfacet + facet normal -0.956615 -0.0357928 0.289147 + outer loop + vertex 1.51998 1.27828 2.54604 + vertex 1.52123 1.28024 2.55043 + vertex 1.51984 1.28327 2.5462 + endloop + endfacet + facet normal -0.963449 -0.0907855 0.252038 + outer loop + vertex 1.51984 1.28327 2.5462 + vertex 1.52123 1.28024 2.55043 + vertex 1.52088 1.28546 2.55097 + endloop + endfacet + facet normal -0.748497 -0.11787 0.652579 + outer loop + vertex 1.52123 1.28024 2.55043 + vertex 1.52381 1.2836 2.55399 + vertex 1.52088 1.28546 2.55097 + endloop + endfacet + facet normal -0.742565 -0.127652 0.657497 + outer loop + vertex 1.52393 1.2783 2.55309 + vertex 1.52381 1.2836 2.55399 + vertex 1.52123 1.28024 2.55043 + endloop + endfacet + facet normal -0.114621 -0.00795782 -0.993377 + outer loop + vertex 1.525 1.285 2.53797 + vertex 1.5216 1.28584 2.53836 + vertex 1.525 1.29 2.53793 + endloop + endfacet + facet normal -0.0827945 0.118356 -0.989514 + outer loop + vertex 1.52136 1.28106 2.5378 + vertex 1.5216 1.28584 2.53836 + vertex 1.525 1.285 2.53797 + endloop + endfacet + facet normal -0.928103 0.0883645 -0.361686 + outer loop + vertex 1.52136 1.28106 2.5378 + vertex 1.51998 1.28204 2.54159 + vertex 1.5216 1.28584 2.53836 + endloop + endfacet + facet normal -0.892964 -0.00172248 -0.450124 + outer loop + vertex 1.5216 1.28584 2.53836 + vertex 1.51998 1.28204 2.54159 + vertex 1.51991 1.28688 2.5417 + endloop + endfacet + facet normal -0.999578 -0.0126639 -0.0261493 + outer loop + vertex 1.51998 1.28204 2.54159 + vertex 1.51984 1.28327 2.5462 + vertex 1.51991 1.28688 2.5417 + endloop + endfacet + facet normal -0.996291 -0.0586482 -0.0629655 + outer loop + vertex 1.51991 1.28688 2.5417 + vertex 1.51984 1.28327 2.5462 + vertex 1.51957 1.28807 2.54606 + endloop + endfacet + facet normal -0.970877 -0.0490131 0.234512 + outer loop + vertex 1.51984 1.28327 2.5462 + vertex 1.52088 1.28546 2.55097 + vertex 1.51957 1.28807 2.54606 + endloop + endfacet + facet normal -0.968034 -0.197618 0.154455 + outer loop + vertex 1.51957 1.28807 2.54606 + vertex 1.52088 1.28546 2.55097 + vertex 1.51985 1.28952 2.54969 + endloop + endfacet + facet normal -0.77015 -0.376787 0.514685 + outer loop + vertex 1.5227 1.28659 2.55451 + vertex 1.52088 1.28546 2.55097 + vertex 1.52381 1.2836 2.55399 + endloop + endfacet + facet normal -0.853029 -0.173787 0.492076 + outer loop + vertex 1.5227 1.28659 2.55451 + vertex 1.52148 1.28992 2.55358 + vertex 1.52088 1.28546 2.55097 + endloop + endfacet + facet normal -0.912722 -0.10827 0.393975 + outer loop + vertex 1.52148 1.28992 2.55358 + vertex 1.51985 1.28952 2.54969 + vertex 1.52088 1.28546 2.55097 + endloop + endfacet + facet normal -0.669253 -0.037062 0.74211 + outer loop + vertex 1.5227 1.28659 2.55451 + vertex 1.52404 1.2895 2.55587 + vertex 1.52148 1.28992 2.55358 + endloop + endfacet + facet normal -0.160277 -0.0177886 -0.986912 + outer loop + vertex 1.525 1.29 2.53793 + vertex 1.52157 1.29066 2.53848 + vertex 1.525 1.295 2.53784 + endloop + endfacet + facet normal -0.152535 0.023614 -0.988016 + outer loop + vertex 1.5216 1.28584 2.53836 + vertex 1.52157 1.29066 2.53848 + vertex 1.525 1.29 2.53793 + endloop + endfacet + facet normal -0.892141 0.0048271 -0.451731 + outer loop + vertex 1.5216 1.28584 2.53836 + vertex 1.51991 1.28688 2.5417 + vertex 1.52157 1.29066 2.53848 + endloop + endfacet + facet normal -0.880271 -0.0193953 -0.474075 + outer loop + vertex 1.52157 1.29066 2.53848 + vertex 1.51991 1.28688 2.5417 + vertex 1.51982 1.29175 2.54167 + endloop + endfacet + facet normal -0.997088 -0.0195903 -0.0737068 + outer loop + vertex 1.51991 1.28688 2.5417 + vertex 1.51957 1.28807 2.54606 + vertex 1.51982 1.29175 2.54167 + endloop + endfacet + facet normal -0.992066 -0.062289 -0.109205 + outer loop + vertex 1.51982 1.29175 2.54167 + vertex 1.51957 1.28807 2.54606 + vertex 1.51929 1.29272 2.54597 + endloop + endfacet + facet normal -0.993239 -0.0581373 0.100479 + outer loop + vertex 1.51957 1.28807 2.54606 + vertex 1.51985 1.28952 2.54969 + vertex 1.51929 1.29272 2.54597 + endloop + endfacet + facet normal -0.993352 -0.0628188 0.0964654 + outer loop + vertex 1.51929 1.29272 2.54597 + vertex 1.51985 1.28952 2.54969 + vertex 1.51967 1.29357 2.55053 + endloop + endfacet + facet normal -0.91089 -0.121054 0.394493 + outer loop + vertex 1.51985 1.28952 2.54969 + vertex 1.52148 1.28992 2.55358 + vertex 1.51967 1.29357 2.55053 + endloop + endfacet + facet normal -0.906047 -0.105932 0.409704 + outer loop + vertex 1.51967 1.29357 2.55053 + vertex 1.52148 1.28992 2.55358 + vertex 1.52124 1.29508 2.55437 + endloop + endfacet + facet normal -0.568259 -0.15096 0.808883 + outer loop + vertex 1.52148 1.28992 2.55358 + vertex 1.52399 1.29348 2.55601 + vertex 1.52124 1.29508 2.55437 + endloop + endfacet + facet normal -0.669099 -0.0347024 0.742362 + outer loop + vertex 1.52404 1.2895 2.55587 + vertex 1.52399 1.29348 2.55601 + vertex 1.52148 1.28992 2.55358 + endloop + endfacet + facet normal -0.170232 -0.00587337 -0.985387 + outer loop + vertex 1.525 1.295 2.53784 + vertex 1.52153 1.29569 2.53843 + vertex 1.525 1.3 2.53781 + endloop + endfacet + facet normal -0.170869 -0.00916923 -0.985251 + outer loop + vertex 1.52157 1.29066 2.53848 + vertex 1.52153 1.29569 2.53843 + vertex 1.525 1.295 2.53784 + endloop + endfacet + facet normal -0.878962 -0.0093555 -0.4768 + outer loop + vertex 1.52157 1.29066 2.53848 + vertex 1.51982 1.29175 2.54167 + vertex 1.52153 1.29569 2.53843 + endloop + endfacet + facet normal -0.876825 -0.013423 -0.480622 + outer loop + vertex 1.52153 1.29569 2.53843 + vertex 1.51982 1.29175 2.54167 + vertex 1.51976 1.29692 2.54163 + endloop + endfacet + facet normal -0.99262 -0.0116971 -0.120705 + outer loop + vertex 1.51982 1.29175 2.54167 + vertex 1.51929 1.29272 2.54597 + vertex 1.51976 1.29692 2.54163 + endloop + endfacet + facet normal -0.986886 -0.0472012 -0.154366 + outer loop + vertex 1.51976 1.29692 2.54163 + vertex 1.51929 1.29272 2.54597 + vertex 1.519 1.2977 2.54627 + endloop + endfacet + facet normal -0.993379 -0.0624877 0.0964064 + outer loop + vertex 1.51929 1.29272 2.54597 + vertex 1.51967 1.29357 2.55053 + vertex 1.519 1.2977 2.54627 + endloop + endfacet + facet normal -0.991304 -0.127363 0.0330844 + outer loop + vertex 1.519 1.2977 2.54627 + vertex 1.51967 1.29357 2.55053 + vertex 1.519 1.29913 2.55164 + endloop + endfacet + facet normal -0.879923 -0.193956 0.433725 + outer loop + vertex 1.51967 1.29357 2.55053 + vertex 1.52124 1.29508 2.55437 + vertex 1.519 1.29913 2.55164 + endloop + endfacet + facet normal -0.86346 -0.153279 0.480564 + outer loop + vertex 1.519 1.29913 2.55164 + vertex 1.52124 1.29508 2.55437 + vertex 1.52107 1.29928 2.55541 + endloop + endfacet + facet normal -0.419828 -0.234005 0.876918 + outer loop + vertex 1.52124 1.29508 2.55437 + vertex 1.52397 1.29822 2.55652 + vertex 1.52107 1.29928 2.55541 + endloop + endfacet + facet normal -0.547635 -0.0920937 0.831634 + outer loop + vertex 1.52399 1.29348 2.55601 + vertex 1.52397 1.29822 2.55652 + vertex 1.52124 1.29508 2.55437 + endloop + endfacet + facet normal -0.209445 -0.0371342 -0.977115 + outer loop + vertex 1.525 1.3 2.53781 + vertex 1.52162 1.30145 2.53848 + vertex 1.525 1.305 2.53762 + endloop + endfacet + facet normal -0.189947 0.010526 -0.981738 + outer loop + vertex 1.52153 1.29569 2.53843 + vertex 1.52162 1.30145 2.53848 + vertex 1.525 1.3 2.53781 + endloop + endfacet + facet normal -0.871805 0.017182 -0.489551 + outer loop + vertex 1.52153 1.29569 2.53843 + vertex 1.51976 1.29692 2.54163 + vertex 1.52162 1.30145 2.53848 + endloop + endfacet + facet normal -0.863785 0.00395326 -0.503845 + outer loop + vertex 1.52162 1.30145 2.53848 + vertex 1.51976 1.29692 2.54163 + vertex 1.51969 1.30272 2.5418 + endloop + endfacet + facet normal -0.986917 -0.00783404 -0.161037 + outer loop + vertex 1.51976 1.29692 2.54163 + vertex 1.519 1.2977 2.54627 + vertex 1.51969 1.30272 2.5418 + endloop + endfacet + facet normal -0.950936 -0.122337 -0.284173 + outer loop + vertex 1.51969 1.30272 2.5418 + vertex 1.519 1.2977 2.54627 + vertex 1.51832 1.30262 2.54641 + endloop + endfacet + facet normal -0.934294 -0.302055 -0.189362 + outer loop + vertex 1.51769 1.30227 2.55011 + vertex 1.51743 1.30424 2.54824 + vertex 1.51832 1.30262 2.54641 + endloop + endfacet + facet normal -0.868899 -0.455872 -0.192861 + outer loop + vertex 1.51769 1.30227 2.55011 + vertex 1.51832 1.30262 2.54641 + vertex 1.519 1.29913 2.55164 + endloop + endfacet + facet normal -0.989896 -0.137224 0.0357101 + outer loop + vertex 1.519 1.29913 2.55164 + vertex 1.51832 1.30262 2.54641 + vertex 1.519 1.2977 2.54627 + endloop + endfacet + facet normal -0.935859 -0.33189 0.118392 + outer loop + vertex 1.51786 1.30268 2.55264 + vertex 1.51769 1.30227 2.55011 + vertex 1.519 1.29913 2.55164 + endloop + endfacet + facet normal -0.712461 -0.391785 0.582154 + outer loop + vertex 1.51786 1.30268 2.55264 + vertex 1.519 1.29913 2.55164 + vertex 1.51963 1.3034 2.55528 + endloop + endfacet + facet normal -0.836979 -0.278546 0.47104 + outer loop + vertex 1.51963 1.3034 2.55528 + vertex 1.519 1.29913 2.55164 + vertex 1.52107 1.29928 2.55541 + endloop + endfacet + facet normal -0.424093 -0.119706 0.897672 + outer loop + vertex 1.52107 1.29928 2.55541 + vertex 1.52337 1.30307 2.55701 + vertex 1.51963 1.3034 2.55528 + endloop + endfacet + facet normal -0.396981 -0.140165 0.907061 + outer loop + vertex 1.52397 1.29822 2.55652 + vertex 1.52337 1.30307 2.55701 + vertex 1.52107 1.29928 2.55541 + endloop + endfacet + facet normal -0.633959 0.00925547 -0.773311 + outer loop + vertex 1.525 1.305 2.53762 + vertex 1.52217 1.31 2.54 + vertex 1.525 1.31 2.53768 + endloop + endfacet + facet normal -0.420408 0.18486 -0.888304 + outer loop + vertex 1.52162 1.30145 2.53848 + vertex 1.52217 1.31 2.54 + vertex 1.525 1.305 2.53762 + endloop + endfacet + facet normal -0.828957 0.148925 -0.539121 + outer loop + vertex 1.52162 1.30145 2.53848 + vertex 1.51969 1.30272 2.5418 + vertex 1.52217 1.31 2.54 + endloop + endfacet + facet normal -0.601508 0.00717149 -0.798834 + outer loop + vertex 1.52217 1.31 2.54 + vertex 1.51969 1.30272 2.5418 + vertex 1.51931 1.30839 2.54214 + endloop + endfacet + facet normal -0.886183 -0.120124 -0.447494 + outer loop + vertex 1.51782 1.30617 2.54568 + vertex 1.51787 1.31008 2.54454 + vertex 1.51931 1.30839 2.54214 + endloop + endfacet + facet normal -0.842241 -0.220458 -0.491965 + outer loop + vertex 1.51782 1.30617 2.54568 + vertex 1.51931 1.30839 2.54214 + vertex 1.51832 1.30262 2.54641 + endloop + endfacet + facet normal -0.957502 -0.0470252 -0.284566 + outer loop + vertex 1.51832 1.30262 2.54641 + vertex 1.51931 1.30839 2.54214 + vertex 1.51969 1.30272 2.5418 + endloop + endfacet + facet normal -0.937936 -0.191851 -0.288909 + outer loop + vertex 1.51832 1.30262 2.54641 + vertex 1.51743 1.30424 2.54824 + vertex 1.51782 1.30617 2.54568 + endloop + endfacet + facet normal -0.761126 -0.28078 0.584679 + outer loop + vertex 1.51762 1.30592 2.55387 + vertex 1.51786 1.30268 2.55264 + vertex 1.51963 1.3034 2.55528 + endloop + endfacet + facet normal -0.738823 -0.237332 0.630725 + outer loop + vertex 1.51896 1.30775 2.55613 + vertex 1.51762 1.30592 2.55387 + vertex 1.51963 1.3034 2.55528 + endloop + endfacet + facet normal -0.31436 -0.228925 0.921288 + outer loop + vertex 1.51963 1.3034 2.55528 + vertex 1.52246 1.30859 2.55753 + vertex 1.51896 1.30775 2.55613 + endloop + endfacet + facet normal -0.424598 -0.155961 0.891848 + outer loop + vertex 1.52337 1.30307 2.55701 + vertex 1.52246 1.30859 2.55753 + vertex 1.51963 1.3034 2.55528 + endloop + endfacet + facet normal -0.603239 0.0120665 -0.797469 + outer loop + vertex 1.52217 1.31 2.54 + vertex 1.51931 1.30839 2.54214 + vertex 1.52227 1.315 2.54 + endloop + endfacet + facet normal -0.543809 -0.0279011 -0.838745 + outer loop + vertex 1.52227 1.315 2.54 + vertex 1.51931 1.30839 2.54214 + vertex 1.51957 1.31423 2.54177 + endloop + endfacet + facet normal -0.855566 0.00610741 -0.517657 + outer loop + vertex 1.51957 1.31423 2.54177 + vertex 1.51931 1.30839 2.54214 + vertex 1.51787 1.31008 2.54454 + endloop + endfacet + facet normal -0.862391 0.0166942 -0.505967 + outer loop + vertex 1.51802 1.31499 2.54445 + vertex 1.51957 1.31423 2.54177 + vertex 1.51787 1.31008 2.54454 + endloop + endfacet + facet normal -0.798094 -0.139179 0.586239 + outer loop + vertex 1.51762 1.30592 2.55387 + vertex 1.51896 1.30775 2.55613 + vertex 1.5177 1.30967 2.55488 + endloop + endfacet + facet normal -0.719983 -0.01804 0.693757 + outer loop + vertex 1.51896 1.30775 2.55613 + vertex 1.51986 1.3126 2.5572 + vertex 1.5177 1.30967 2.55488 + endloop + endfacet + facet normal -0.338782 -0.141293 0.930195 + outer loop + vertex 1.51896 1.30775 2.55613 + vertex 1.52246 1.30859 2.55753 + vertex 1.51986 1.3126 2.5572 + endloop + endfacet + facet normal -0.297464 -0.113045 0.948017 + outer loop + vertex 1.52246 1.30859 2.55753 + vertex 1.52357 1.31383 2.55851 + vertex 1.51986 1.3126 2.5572 + endloop + endfacet + facet normal -0.555137 0.0288666 -0.831258 + outer loop + vertex 1.52227 1.315 2.54 + vertex 1.51957 1.31423 2.54177 + vertex 1.52253 1.32 2.54 + endloop + endfacet + facet normal -0.886337 0.367378 -0.281851 + outer loop + vertex 1.52253 1.32 2.54 + vertex 1.51957 1.31423 2.54177 + vertex 1.52094 1.32 2.545 + endloop + endfacet + facet normal -0.699831 0.467528 -0.54005 + outer loop + vertex 1.52094 1.32 2.545 + vertex 1.51957 1.31423 2.54177 + vertex 1.51802 1.31499 2.54445 + endloop + endfacet + facet normal 0.140618 0.0261475 -0.989719 + outer loop + vertex 1.51807 1.31982 2.54459 + vertex 1.52094 1.32 2.545 + vertex 1.51802 1.31499 2.54445 + endloop + endfacet + facet normal -0.293893 -0.123548 0.94782 + outer loop + vertex 1.52357 1.31383 2.55851 + vertex 1.52303 1.31779 2.55886 + vertex 1.51986 1.3126 2.5572 + endloop + endfacet + facet normal -0.337013 -0.0937579 0.93682 + outer loop + vertex 1.51986 1.3126 2.5572 + vertex 1.52303 1.31779 2.55886 + vertex 1.51956 1.31811 2.55764 + endloop + endfacet + facet normal 0.141367 0.0144188 -0.989852 + outer loop + vertex 1.52043 1.325 2.545 + vertex 1.52094 1.32 2.545 + vertex 1.51807 1.31982 2.54459 + endloop + endfacet + facet normal 0.353658 -0.087194 -0.931302 + outer loop + vertex 1.51804 1.32354 2.54423 + vertex 1.52043 1.325 2.545 + vertex 1.51807 1.31982 2.54459 + endloop + endfacet + facet normal -0.338611 -0.131743 0.931658 + outer loop + vertex 1.52303 1.31779 2.55886 + vertex 1.52301 1.32266 2.55954 + vertex 1.51956 1.31811 2.55764 + endloop + endfacet + facet normal -0.225619 -0.224082 0.948095 + outer loop + vertex 1.51956 1.31811 2.55764 + vertex 1.52301 1.32266 2.55954 + vertex 1.51945 1.32334 2.55885 + endloop + endfacet + facet normal 0.280605 0.0464072 -0.958701 + outer loop + vertex 1.52043 1.325 2.545 + vertex 1.51804 1.32354 2.54423 + vertex 1.52 1.3276 2.545 + endloop + endfacet + facet normal -0.485665 -0.357978 0.797484 + outer loop + vertex 1.52021 1.32666 2.5608 + vertex 1.51843 1.32624 2.55953 + vertex 1.51945 1.32334 2.55885 + endloop + endfacet + facet normal 0.204293 -0.529686 0.823224 + outer loop + vertex 1.52021 1.32666 2.5608 + vertex 1.51945 1.32334 2.55885 + vertex 1.52319 1.32756 2.56064 + endloop + endfacet + facet normal -0.223107 -0.206031 0.952772 + outer loop + vertex 1.52319 1.32756 2.56064 + vertex 1.51945 1.32334 2.55885 + vertex 1.52301 1.32266 2.55954 + endloop + endfacet + facet normal -0.543387 -0.182995 0.819294 + outer loop + vertex 1.52021 1.32666 2.5608 + vertex 1.51974 1.32921 2.56106 + vertex 1.51843 1.32624 2.55953 + endloop + endfacet + facet normal 0.243367 -0.0473437 -0.968778 + outer loop + vertex 1.52064 1.355 2.545 + vertex 1.52 1.35171 2.545 + vertex 1.51811 1.35545 2.54434 + endloop + endfacet + facet normal 0.247343 -0.0247325 -0.968612 + outer loop + vertex 1.52114 1.36 2.545 + vertex 1.52064 1.355 2.545 + vertex 1.51811 1.35545 2.54434 + endloop + endfacet + facet normal 0.166267 0.0317636 -0.985569 + outer loop + vertex 1.51789 1.36026 2.54446 + vertex 1.52114 1.36 2.545 + vertex 1.51811 1.35545 2.54434 + endloop + endfacet + facet normal 0.164168 0.00361268 -0.986426 + outer loop + vertex 1.52103 1.365 2.545 + vertex 1.52114 1.36 2.545 + vertex 1.51789 1.36026 2.54446 + endloop + endfacet + facet normal 0.143074 0.0179473 -0.989549 + outer loop + vertex 1.51805 1.36512 2.54457 + vertex 1.52103 1.365 2.545 + vertex 1.51789 1.36026 2.54446 + endloop + endfacet + facet normal 0.141157 -0.0304909 -0.989518 + outer loop + vertex 1.52211 1.37 2.545 + vertex 1.52103 1.365 2.545 + vertex 1.51805 1.36512 2.54457 + endloop + endfacet + facet normal -0.0129318 0.0981233 -0.99509 + outer loop + vertex 1.51857 1.37003 2.54505 + vertex 1.52211 1.37 2.545 + vertex 1.51805 1.36512 2.54457 + endloop + endfacet + facet normal -0.013877 0.000499588 -0.999904 + outer loop + vertex 1.52229 1.375 2.545 + vertex 1.52211 1.37 2.545 + vertex 1.51857 1.37003 2.54505 + endloop + endfacet + facet normal -0.660239 0.48843 -0.570544 + outer loop + vertex 1.52 1.375 2.54765 + vertex 1.52229 1.375 2.545 + vertex 1.51857 1.37003 2.54505 + endloop + endfacet + facet normal -0.732378 0.00144929 -0.680897 + outer loop + vertex 1.52252 1.65 2.545 + vertex 1.52251 1.645 2.545 + vertex 1.52 1.645 2.5477 + endloop + endfacet + facet normal 0.0606034 -0.497732 -0.865211 + outer loop + vertex 1.51851 1.64962 2.54494 + vertex 1.52252 1.65 2.545 + vertex 1.52 1.645 2.5477 + endloop + endfacet + facet normal 0.0148588 0.00323902 -0.999884 + outer loop + vertex 1.52143 1.655 2.545 + vertex 1.52252 1.65 2.545 + vertex 1.51851 1.64962 2.54494 + endloop + endfacet + facet normal 0.152832 -0.0717207 -0.985646 + outer loop + vertex 1.51787 1.65481 2.54446 + vertex 1.52143 1.655 2.545 + vertex 1.51851 1.64962 2.54494 + endloop + endfacet + facet normal 0.149089 0.0080511 -0.988791 + outer loop + vertex 1.52116 1.66 2.545 + vertex 1.52143 1.655 2.545 + vertex 1.51787 1.65481 2.54446 + endloop + endfacet + facet normal 0.224012 -0.0410496 -0.973721 + outer loop + vertex 1.51752 1.65971 2.54418 + vertex 1.52116 1.66 2.545 + vertex 1.51787 1.65481 2.54446 + endloop + endfacet + facet normal 0.218146 0.0357777 -0.97526 + outer loop + vertex 1.52034 1.665 2.545 + vertex 1.52116 1.66 2.545 + vertex 1.51752 1.65971 2.54418 + endloop + endfacet + facet normal 0.448087 -0.100223 -0.888354 + outer loop + vertex 1.51755 1.66342 2.54377 + vertex 1.52034 1.665 2.545 + vertex 1.51752 1.65971 2.54418 + endloop + endfacet + facet normal 0.366537 0.0741761 -0.927442 + outer loop + vertex 1.52034 1.665 2.545 + vertex 1.51755 1.66342 2.54377 + vertex 1.52 1.66668 2.545 + endloop + endfacet + facet normal 0.337146 -0.0371104 -0.940721 + outer loop + vertex 1.52024 1.69 2.545 + vertex 1.52 1.68782 2.545 + vertex 1.51804 1.6903 2.5442 + endloop + endfacet + facet normal 0.342632 0.00616759 -0.939449 + outer loop + vertex 1.52015 1.695 2.545 + vertex 1.52024 1.69 2.545 + vertex 1.51804 1.6903 2.5442 + endloop + endfacet + facet normal 0.395264 -0.021134 -0.918325 + outer loop + vertex 1.51795 1.69402 2.54407 + vertex 1.52015 1.695 2.545 + vertex 1.51804 1.6903 2.5442 + endloop + endfacet + facet normal 0.382157 0.0138434 -0.923994 + outer loop + vertex 1.52015 1.695 2.545 + vertex 1.51795 1.69402 2.54407 + vertex 1.52 1.69914 2.545 + endloop + endfacet + facet normal 0.215815 -0.0160555 -0.976302 + outer loop + vertex 1.52034 1.705 2.545 + vertex 1.52 1.70043 2.545 + vertex 1.5182 1.70457 2.54453 + endloop + endfacet + facet normal 0.00662733 0.316611 0.948532 + outer loop + vertex 1.51954 1.69795 2.56061 + vertex 1.52357 1.69873 2.56032 + vertex 1.52025 1.70245 2.5591 + endloop + endfacet + facet normal 0.213589 -0.0042725 -0.976914 + outer loop + vertex 1.52044 1.71 2.545 + vertex 1.52034 1.705 2.545 + vertex 1.5182 1.70457 2.54453 + endloop + endfacet + facet normal 0.229914 -0.0113434 -0.973145 + outer loop + vertex 1.51785 1.70909 2.5444 + vertex 1.52044 1.71 2.545 + vertex 1.5182 1.70457 2.54453 + endloop + endfacet + facet normal -0.346934 0.264998 0.899674 + outer loop + vertex 1.52025 1.70245 2.5591 + vertex 1.52311 1.70753 2.5587 + vertex 1.51943 1.70749 2.5573 + endloop + endfacet + facet normal -0.926677 -0.0500423 -0.372513 + outer loop + vertex 1.52245 1.71 2.54 + vertex 1.52044 1.71 2.545 + vertex 1.52218 1.715 2.54 + endloop + endfacet + facet normal -0.170875 -0.666349 -0.725796 + outer loop + vertex 1.52218 1.715 2.54 + vertex 1.52044 1.71 2.545 + vertex 1.51933 1.71392 2.54167 + endloop + endfacet + facet normal 0.366836 -0.540367 -0.757254 + outer loop + vertex 1.51933 1.71392 2.54167 + vertex 1.52044 1.71 2.545 + vertex 1.51785 1.70909 2.5444 + endloop + endfacet + facet normal -0.895927 0.0223937 -0.443637 + outer loop + vertex 1.51768 1.71271 2.54492 + vertex 1.51933 1.71392 2.54167 + vertex 1.51785 1.70909 2.5444 + endloop + endfacet + facet normal -0.767412 0.288946 0.572354 + outer loop + vertex 1.5194 1.71478 2.5548 + vertex 1.51768 1.71172 2.55403 + vertex 1.51883 1.7109 2.556 + endloop + endfacet + facet normal -0.490669 0.322311 0.809543 + outer loop + vertex 1.51883 1.7109 2.556 + vertex 1.52211 1.71228 2.55744 + vertex 1.5194 1.71478 2.5548 + endloop + endfacet + facet normal -0.472766 0.239953 0.847888 + outer loop + vertex 1.51883 1.7109 2.556 + vertex 1.51943 1.70749 2.5573 + vertex 1.52211 1.71228 2.55744 + endloop + endfacet + facet normal -0.353398 0.171258 0.919663 + outer loop + vertex 1.51943 1.70749 2.5573 + vertex 1.52311 1.70753 2.5587 + vertex 1.52211 1.71228 2.55744 + endloop + endfacet + facet normal -0.502633 -0.00703444 -0.864471 + outer loop + vertex 1.52218 1.715 2.54 + vertex 1.51933 1.71392 2.54167 + vertex 1.52211 1.72 2.54 + endloop + endfacet + facet normal 0.220063 -0.350118 -0.910489 + outer loop + vertex 1.52211 1.72 2.54 + vertex 1.51933 1.71392 2.54167 + vertex 1.51973 1.71826 2.5401 + endloop + endfacet + facet normal -0.983973 0.126556 -0.125624 + outer loop + vertex 1.51768 1.71271 2.54492 + vertex 1.51737 1.71376 2.54843 + vertex 1.51834 1.71713 2.54428 + endloop + endfacet + facet normal -0.900839 0.0700546 -0.428463 + outer loop + vertex 1.51768 1.71271 2.54492 + vertex 1.51834 1.71713 2.54428 + vertex 1.51933 1.71392 2.54167 + endloop + endfacet + facet normal -0.945741 -0.0289145 -0.323631 + outer loop + vertex 1.51933 1.71392 2.54167 + vertex 1.51834 1.71713 2.54428 + vertex 1.51973 1.71826 2.5401 + endloop + endfacet + facet normal -0.967145 0.253552 -0.0185193 + outer loop + vertex 1.5184 1.7178 2.55023 + vertex 1.51834 1.71713 2.54428 + vertex 1.51737 1.71376 2.54843 + endloop + endfacet + facet normal -0.973922 0.21569 0.0703862 + outer loop + vertex 1.51763 1.71376 2.55201 + vertex 1.5184 1.7178 2.55023 + vertex 1.51737 1.71376 2.54843 + endloop + endfacet + facet normal -0.839103 0.373658 0.395331 + outer loop + vertex 1.51763 1.71376 2.55201 + vertex 1.51768 1.71172 2.55403 + vertex 1.5194 1.71478 2.5548 + endloop + endfacet + facet normal -0.84529 0.341372 0.411035 + outer loop + vertex 1.51763 1.71376 2.55201 + vertex 1.5194 1.71478 2.5548 + vertex 1.5184 1.7178 2.55023 + endloop + endfacet + facet normal -0.922229 0.197362 0.332478 + outer loop + vertex 1.5184 1.7178 2.55023 + vertex 1.5194 1.71478 2.5548 + vertex 1.52033 1.71998 2.55429 + endloop + endfacet + facet normal -0.598476 0.182601 0.780053 + outer loop + vertex 1.5194 1.71478 2.5548 + vertex 1.5228 1.71768 2.55672 + vertex 1.52033 1.71998 2.55429 + endloop + endfacet + facet normal -0.596586 0.178851 0.782366 + outer loop + vertex 1.52211 1.71228 2.55744 + vertex 1.5228 1.71768 2.55672 + vertex 1.5194 1.71478 2.5548 + endloop + endfacet + facet normal -0.100845 0.00194506 -0.9949 + outer loop + vertex 1.525 1.72 2.53765 + vertex 1.52147 1.72118 2.53801 + vertex 1.525 1.725 2.53766 + endloop + endfacet + facet normal -0.327477 -0.854723 -0.402751 + outer loop + vertex 1.52211 1.72 2.54 + vertex 1.52147 1.72118 2.53801 + vertex 1.525 1.72 2.53765 + endloop + endfacet + facet normal 0.476453 -0.680128 -0.557152 + outer loop + vertex 1.52211 1.72 2.54 + vertex 1.51973 1.71826 2.5401 + vertex 1.52147 1.72118 2.53801 + endloop + endfacet + facet normal -0.802161 0.0525566 -0.594791 + outer loop + vertex 1.52147 1.72118 2.53801 + vertex 1.51973 1.71826 2.5401 + vertex 1.51941 1.72172 2.54084 + endloop + endfacet + facet normal -0.946753 -0.0192964 -0.321381 + outer loop + vertex 1.51973 1.71826 2.5401 + vertex 1.51834 1.71713 2.54428 + vertex 1.51941 1.72172 2.54084 + endloop + endfacet + facet normal -0.978882 0.0923222 -0.182393 + outer loop + vertex 1.51941 1.72172 2.54084 + vertex 1.51834 1.71713 2.54428 + vertex 1.51858 1.72236 2.54562 + endloop + endfacet + facet normal -0.998969 0.045078 0.00539071 + outer loop + vertex 1.51834 1.71713 2.54428 + vertex 1.5184 1.7178 2.55023 + vertex 1.51858 1.72236 2.54562 + endloop + endfacet + facet normal -0.990224 0.116665 0.0764629 + outer loop + vertex 1.51858 1.72236 2.54562 + vertex 1.5184 1.7178 2.55023 + vertex 1.51907 1.72329 2.55055 + endloop + endfacet + facet normal -0.917337 0.089145 0.388003 + outer loop + vertex 1.5184 1.7178 2.55023 + vertex 1.52033 1.71998 2.55429 + vertex 1.51907 1.72329 2.55055 + endloop + endfacet + facet normal -0.93106 0.0533796 0.360939 + outer loop + vertex 1.51907 1.72329 2.55055 + vertex 1.52033 1.71998 2.55429 + vertex 1.52058 1.72469 2.55425 + endloop + endfacet + facet normal -0.658399 0.0426455 0.75146 + outer loop + vertex 1.52033 1.71998 2.55429 + vertex 1.52289 1.72255 2.55639 + vertex 1.52058 1.72469 2.55425 + endloop + endfacet + facet normal -0.669852 0.0635273 0.739772 + outer loop + vertex 1.5228 1.71768 2.55672 + vertex 1.52289 1.72255 2.55639 + vertex 1.52033 1.71998 2.55429 + endloop + endfacet + facet normal -0.143284 -0.00391688 -0.989674 + outer loop + vertex 1.525 1.725 2.53766 + vertex 1.52132 1.72551 2.53819 + vertex 1.525 1.73 2.53764 + endloop + endfacet + facet normal -0.137706 0.0364874 -0.989801 + outer loop + vertex 1.52147 1.72118 2.53801 + vertex 1.52132 1.72551 2.53819 + vertex 1.525 1.725 2.53766 + endloop + endfacet + facet normal -0.808469 -0.00416387 -0.588525 + outer loop + vertex 1.52147 1.72118 2.53801 + vertex 1.51941 1.72172 2.54084 + vertex 1.52132 1.72551 2.53819 + endloop + endfacet + facet normal -0.852083 0.066249 -0.519197 + outer loop + vertex 1.52132 1.72551 2.53819 + vertex 1.51941 1.72172 2.54084 + vertex 1.51937 1.72658 2.54152 + endloop + endfacet + facet normal -0.984712 0.0166403 -0.173391 + outer loop + vertex 1.51941 1.72172 2.54084 + vertex 1.51858 1.72236 2.54562 + vertex 1.51937 1.72658 2.54152 + endloop + endfacet + facet normal -0.989305 0.0544872 -0.135303 + outer loop + vertex 1.51937 1.72658 2.54152 + vertex 1.51858 1.72236 2.54562 + vertex 1.51879 1.72749 2.54616 + endloop + endfacet + facet normal -0.99517 0.0307842 0.0932134 + outer loop + vertex 1.51858 1.72236 2.54562 + vertex 1.51907 1.72329 2.55055 + vertex 1.51879 1.72749 2.54616 + endloop + endfacet + facet normal -0.991582 0.0557929 0.116846 + outer loop + vertex 1.51879 1.72749 2.54616 + vertex 1.51907 1.72329 2.55055 + vertex 1.51937 1.72821 2.55072 + endloop + endfacet + facet normal -0.930263 0.0436598 0.364288 + outer loop + vertex 1.51907 1.72329 2.55055 + vertex 1.52058 1.72469 2.55425 + vertex 1.51937 1.72821 2.55072 + endloop + endfacet + facet normal -0.923122 0.0614334 0.379567 + outer loop + vertex 1.51937 1.72821 2.55072 + vertex 1.52058 1.72469 2.55425 + vertex 1.52085 1.72897 2.55422 + endloop + endfacet + facet normal -0.756751 0.0527868 0.651569 + outer loop + vertex 1.52058 1.72469 2.55425 + vertex 1.5223 1.72629 2.55611 + vertex 1.52085 1.72897 2.55422 + endloop + endfacet + facet normal -0.708274 -0.0591414 0.703456 + outer loop + vertex 1.52289 1.72255 2.55639 + vertex 1.5223 1.72629 2.55611 + vertex 1.52058 1.72469 2.55425 + endloop + endfacet + facet normal -0.211476 0.0214799 -0.977147 + outer loop + vertex 1.525 1.73 2.53764 + vertex 1.52132 1.73045 2.53845 + vertex 1.525 1.735 2.53775 + endloop + endfacet + facet normal -0.207864 0.0506315 -0.976846 + outer loop + vertex 1.52132 1.72551 2.53819 + vertex 1.52132 1.73045 2.53845 + vertex 1.525 1.73 2.53764 + endloop + endfacet + facet normal -0.859407 0.0262125 -0.51062 + outer loop + vertex 1.52132 1.72551 2.53819 + vertex 1.51937 1.72658 2.54152 + vertex 1.52132 1.73045 2.53845 + endloop + endfacet + facet normal -0.867331 0.0418187 -0.495973 + outer loop + vertex 1.52132 1.73045 2.53845 + vertex 1.51937 1.72658 2.54152 + vertex 1.51945 1.73165 2.54181 + endloop + endfacet + facet normal -0.991335 0.0228483 -0.129354 + outer loop + vertex 1.51937 1.72658 2.54152 + vertex 1.51879 1.72749 2.54616 + vertex 1.51945 1.73165 2.54181 + endloop + endfacet + facet normal -0.992763 0.0398668 -0.11328 + outer loop + vertex 1.51945 1.73165 2.54181 + vertex 1.51879 1.72749 2.54616 + vertex 1.51897 1.73252 2.5463 + endloop + endfacet + facet normal -0.992161 0.0332025 0.120476 + outer loop + vertex 1.51879 1.72749 2.54616 + vertex 1.51937 1.72821 2.55072 + vertex 1.51897 1.73252 2.5463 + endloop + endfacet + facet normal -0.978896 0.095895 0.180465 + outer loop + vertex 1.51897 1.73252 2.5463 + vertex 1.51937 1.72821 2.55072 + vertex 1.51985 1.73304 2.55079 + endloop + endfacet + facet normal -0.923311 0.0876037 0.373928 + outer loop + vertex 1.51937 1.72821 2.55072 + vertex 1.52085 1.72897 2.55422 + vertex 1.51985 1.73304 2.55079 + endloop + endfacet + facet normal -0.831899 0.223233 0.508047 + outer loop + vertex 1.51985 1.73304 2.55079 + vertex 1.52085 1.72897 2.55422 + vertex 1.52196 1.73316 2.55418 + endloop + endfacet + facet normal -0.667066 0.181871 0.722458 + outer loop + vertex 1.52085 1.72897 2.55422 + vertex 1.52304 1.72953 2.55609 + vertex 1.52196 1.73316 2.55418 + endloop + endfacet + facet normal -0.666278 0.156209 0.729159 + outer loop + vertex 1.5223 1.72629 2.55611 + vertex 1.52304 1.72953 2.55609 + vertex 1.52085 1.72897 2.55422 + endloop + endfacet + facet normal -0.196641 0.0391942 -0.979692 + outer loop + vertex 1.525 1.735 2.53775 + vertex 1.52137 1.73541 2.5385 + vertex 1.525 1.74 2.53795 + endloop + endfacet + facet normal -0.199791 0.0116199 -0.97977 + outer loop + vertex 1.52132 1.73045 2.53845 + vertex 1.52137 1.73541 2.5385 + vertex 1.525 1.735 2.53775 + endloop + endfacet + facet normal -0.872301 0.0139781 -0.48877 + outer loop + vertex 1.52132 1.73045 2.53845 + vertex 1.51945 1.73165 2.54181 + vertex 1.52137 1.73541 2.5385 + endloop + endfacet + facet normal -0.873429 0.0163975 -0.486675 + outer loop + vertex 1.52137 1.73541 2.5385 + vertex 1.51945 1.73165 2.54181 + vertex 1.51956 1.73664 2.54179 + endloop + endfacet + facet normal -0.993765 0.0204164 -0.109609 + outer loop + vertex 1.51945 1.73165 2.54181 + vertex 1.51897 1.73252 2.5463 + vertex 1.51956 1.73664 2.54179 + endloop + endfacet + facet normal -0.995375 0.0752552 -0.059707 + outer loop + vertex 1.51956 1.73664 2.54179 + vertex 1.51897 1.73252 2.5463 + vertex 1.51935 1.73755 2.54631 + endloop + endfacet + facet normal -0.980297 0.0736447 0.183286 + outer loop + vertex 1.51897 1.73252 2.5463 + vertex 1.51985 1.73304 2.55079 + vertex 1.51935 1.73755 2.54631 + endloop + endfacet + facet normal -0.927221 0.2072 0.311977 + outer loop + vertex 1.51935 1.73755 2.54631 + vertex 1.51985 1.73304 2.55079 + vertex 1.52116 1.73851 2.55104 + endloop + endfacet + facet normal -0.464968 0.312125 0.828482 + outer loop + vertex 1.52501 1.73723 2.55436 + vertex 1.52196 1.73316 2.55418 + vertex 1.5244 1.73268 2.55573 + endloop + endfacet + facet normal -0.534185 0.367053 0.761524 + outer loop + vertex 1.52501 1.73723 2.55436 + vertex 1.52116 1.73851 2.55104 + vertex 1.52196 1.73316 2.55418 + endloop + endfacet + facet normal -0.839211 0.176784 0.514269 + outer loop + vertex 1.52116 1.73851 2.55104 + vertex 1.51985 1.73304 2.55079 + vertex 1.52196 1.73316 2.55418 + endloop + endfacet + facet normal -0.469445 0.297985 0.83116 + outer loop + vertex 1.5244 1.73268 2.55573 + vertex 1.52196 1.73316 2.55418 + vertex 1.52304 1.72953 2.55609 + endloop + endfacet + facet normal -0.108333 0.0198579 -0.993916 + outer loop + vertex 1.525 1.74 2.53795 + vertex 1.52143 1.7403 2.53835 + vertex 1.525 1.745 2.53805 + endloop + endfacet + facet normal -0.112312 -0.0291884 -0.993244 + outer loop + vertex 1.52137 1.73541 2.5385 + vertex 1.52143 1.7403 2.53835 + vertex 1.525 1.74 2.53795 + endloop + endfacet + facet normal -0.876736 -0.00375277 -0.480957 + outer loop + vertex 1.52137 1.73541 2.5385 + vertex 1.51956 1.73664 2.54179 + vertex 1.52143 1.7403 2.53835 + endloop + endfacet + facet normal -0.880268 0.00418972 -0.474458 + outer loop + vertex 1.52143 1.7403 2.53835 + vertex 1.51956 1.73664 2.54179 + vertex 1.51969 1.74157 2.54159 + endloop + endfacet + facet normal -0.998463 0.0245994 -0.0496733 + outer loop + vertex 1.51956 1.73664 2.54179 + vertex 1.51935 1.73755 2.54631 + vertex 1.51969 1.74157 2.54159 + endloop + endfacet + facet normal -0.996967 0.0777061 -0.00439334 + outer loop + vertex 1.51969 1.74157 2.54159 + vertex 1.51935 1.73755 2.54631 + vertex 1.51975 1.74268 2.54611 + endloop + endfacet + facet normal -0.936478 0.0862183 0.339965 + outer loop + vertex 1.51935 1.73755 2.54631 + vertex 1.52116 1.73851 2.55104 + vertex 1.51975 1.74268 2.54611 + endloop + endfacet + facet normal -0.934293 0.0921764 0.344382 + outer loop + vertex 1.51975 1.74268 2.54611 + vertex 1.52116 1.73851 2.55104 + vertex 1.5214 1.74455 2.55007 + endloop + endfacet + facet normal -0.656401 0.14481 0.740384 + outer loop + vertex 1.52116 1.73851 2.55104 + vertex 1.52426 1.74266 2.55298 + vertex 1.5214 1.74455 2.55007 + endloop + endfacet + facet normal -0.627817 0.10934 0.770643 + outer loop + vertex 1.52501 1.73723 2.55436 + vertex 1.52426 1.74266 2.55298 + vertex 1.52116 1.73851 2.55104 + endloop + endfacet + facet normal 0.0363064 -0.555603 -0.830654 + outer loop + vertex 1.525 1.745 2.53805 + vertex 1.52124 1.74522 2.53774 + vertex 1.52341 1.74934 2.53508 + endloop + endfacet + facet normal 0.074551 -0.118689 -0.990129 + outer loop + vertex 1.52143 1.7403 2.53835 + vertex 1.52124 1.74522 2.53774 + vertex 1.525 1.745 2.53805 + endloop + endfacet + facet normal -0.891549 -0.0882309 -0.444246 + outer loop + vertex 1.52143 1.7403 2.53835 + vertex 1.51969 1.74157 2.54159 + vertex 1.52124 1.74522 2.53774 + endloop + endfacet + facet normal -0.933056 0.0191283 -0.359223 + outer loop + vertex 1.52124 1.74522 2.53774 + vertex 1.51969 1.74157 2.54159 + vertex 1.51989 1.74652 2.54133 + endloop + endfacet + facet normal -0.999166 0.0405589 0.00478549 + outer loop + vertex 1.51969 1.74157 2.54159 + vertex 1.51975 1.74268 2.54611 + vertex 1.51989 1.74652 2.54133 + endloop + endfacet + facet normal -0.9969 0.0725233 0.030503 + outer loop + vertex 1.51989 1.74652 2.54133 + vertex 1.51975 1.74268 2.54611 + vertex 1.52012 1.74777 2.54581 + endloop + endfacet + facet normal -0.933908 0.0865706 0.346873 + outer loop + vertex 1.51975 1.74268 2.54611 + vertex 1.5214 1.74455 2.55007 + vertex 1.52012 1.74777 2.54581 + endloop + endfacet + facet normal -0.939057 0.0706538 0.336423 + outer loop + vertex 1.52012 1.74777 2.54581 + vertex 1.5214 1.74455 2.55007 + vertex 1.52165 1.74971 2.5497 + endloop + endfacet + facet normal -0.705295 0.0860444 0.703672 + outer loop + vertex 1.5214 1.74455 2.55007 + vertex 1.5241 1.74776 2.55239 + vertex 1.52165 1.74971 2.5497 + endloop + endfacet + facet normal -0.690927 0.061886 0.720271 + outer loop + vertex 1.52426 1.74266 2.55298 + vertex 1.5241 1.74776 2.55239 + vertex 1.5214 1.74455 2.55007 + endloop + endfacet + facet normal -0.682671 -0.103985 -0.723289 + outer loop + vertex 1.52341 1.74934 2.53508 + vertex 1.52106 1.75028 2.53716 + vertex 1.52309 1.75447 2.53465 + endloop + endfacet + facet normal -0.683174 -0.107381 -0.722317 + outer loop + vertex 1.52124 1.74522 2.53774 + vertex 1.52106 1.75028 2.53716 + vertex 1.52341 1.74934 2.53508 + endloop + endfacet + facet normal -0.941422 -0.0714917 -0.329565 + outer loop + vertex 1.52124 1.74522 2.53774 + vertex 1.51989 1.74652 2.54133 + vertex 1.52106 1.75028 2.53716 + endloop + endfacet + facet normal -0.972298 0.0503918 -0.228247 + outer loop + vertex 1.52106 1.75028 2.53716 + vertex 1.51989 1.74652 2.54133 + vertex 1.52019 1.7515 2.54116 + endloop + endfacet + facet normal -0.997566 0.0610258 0.0337399 + outer loop + vertex 1.51989 1.74652 2.54133 + vertex 1.52012 1.74777 2.54581 + vertex 1.52019 1.7515 2.54116 + endloop + endfacet + facet normal -0.995012 0.0846621 0.0527644 + outer loop + vertex 1.52019 1.7515 2.54116 + vertex 1.52012 1.74777 2.54581 + vertex 1.52054 1.7528 2.54567 + endloop + endfacet + facet normal -0.940481 0.0881361 0.328217 + outer loop + vertex 1.52012 1.74777 2.54581 + vertex 1.52165 1.74971 2.5497 + vertex 1.52054 1.7528 2.54567 + endloop + endfacet + facet normal -0.953511 0.0440897 0.298116 + outer loop + vertex 1.52054 1.7528 2.54567 + vertex 1.52165 1.74971 2.5497 + vertex 1.52181 1.75476 2.54945 + endloop + endfacet + facet normal -0.750309 0.0550064 0.658795 + outer loop + vertex 1.52165 1.74971 2.5497 + vertex 1.52393 1.75263 2.55204 + vertex 1.52181 1.75476 2.54945 + endloop + endfacet + facet normal -0.731623 0.0223268 0.681344 + outer loop + vertex 1.5241 1.74776 2.55239 + vertex 1.52393 1.75263 2.55204 + vertex 1.52165 1.74971 2.5497 + endloop + endfacet + facet normal -0.798864 0.00389579 -0.601499 + outer loop + vertex 1.52309 1.75447 2.53465 + vertex 1.52123 1.75544 2.53712 + vertex 1.52305 1.75966 2.53474 + endloop + endfacet + facet normal -0.795431 0.021161 -0.605675 + outer loop + vertex 1.52106 1.75028 2.53716 + vertex 1.52123 1.75544 2.53712 + vertex 1.52309 1.75447 2.53465 + endloop + endfacet + facet normal -0.974519 0.0294819 -0.222359 + outer loop + vertex 1.52106 1.75028 2.53716 + vertex 1.52019 1.7515 2.54116 + vertex 1.52123 1.75544 2.53712 + endloop + endfacet + facet normal -0.981406 0.0807468 -0.174133 + outer loop + vertex 1.52123 1.75544 2.53712 + vertex 1.52019 1.7515 2.54116 + vertex 1.5206 1.75659 2.54121 + endloop + endfacet + facet normal -0.995362 0.0794156 0.0542943 + outer loop + vertex 1.52019 1.7515 2.54116 + vertex 1.52054 1.7528 2.54567 + vertex 1.5206 1.75659 2.54121 + endloop + endfacet + facet normal -0.996835 0.0666194 0.0433753 + outer loop + vertex 1.5206 1.75659 2.54121 + vertex 1.52054 1.7528 2.54567 + vertex 1.52087 1.75787 2.54561 + endloop + endfacet + facet normal -0.95556 0.0665027 0.287198 + outer loop + vertex 1.52054 1.7528 2.54567 + vertex 1.52181 1.75476 2.54945 + vertex 1.52087 1.75787 2.54561 + endloop + endfacet + facet normal -0.96901 0.0125305 0.246702 + outer loop + vertex 1.52087 1.75787 2.54561 + vertex 1.52181 1.75476 2.54945 + vertex 1.5218 1.75962 2.54916 + endloop + endfacet + facet normal -0.785136 0.0353953 0.618311 + outer loop + vertex 1.52181 1.75476 2.54945 + vertex 1.52364 1.75744 2.55162 + vertex 1.5218 1.75962 2.54916 + endloop + endfacet + facet normal -0.770209 0.00956961 0.63772 + outer loop + vertex 1.52393 1.75263 2.55204 + vertex 1.52364 1.75744 2.55162 + vertex 1.52181 1.75476 2.54945 + endloop + endfacet + facet normal -0.855621 0.039735 -0.516076 + outer loop + vertex 1.52305 1.75966 2.53474 + vertex 1.52145 1.76067 2.53746 + vertex 1.52302 1.76479 2.53518 + endloop + endfacet + facet normal -0.849195 0.0697892 -0.523448 + outer loop + vertex 1.52123 1.75544 2.53712 + vertex 1.52145 1.76067 2.53746 + vertex 1.52305 1.75966 2.53474 + endloop + endfacet + facet normal -0.984594 0.0526501 -0.166739 + outer loop + vertex 1.52123 1.75544 2.53712 + vertex 1.5206 1.75659 2.54121 + vertex 1.52145 1.76067 2.53746 + endloop + endfacet + facet normal -0.986661 0.0723195 -0.14584 + outer loop + vertex 1.52145 1.76067 2.53746 + vertex 1.5206 1.75659 2.54121 + vertex 1.52091 1.76161 2.54158 + endloop + endfacet + facet normal -0.997218 0.0589241 0.0456443 + outer loop + vertex 1.5206 1.75659 2.54121 + vertex 1.52087 1.75787 2.54561 + vertex 1.52091 1.76161 2.54158 + endloop + endfacet + facet normal -0.998626 0.0426083 0.0305102 + outer loop + vertex 1.52091 1.76161 2.54158 + vertex 1.52087 1.75787 2.54561 + vertex 1.52108 1.76263 2.54569 + endloop + endfacet + facet normal -0.971324 0.0382158 0.234669 + outer loop + vertex 1.52087 1.75787 2.54561 + vertex 1.5218 1.75962 2.54916 + vertex 1.52108 1.76263 2.54569 + endloop + endfacet + facet normal -0.971747 0.0364181 0.233199 + outer loop + vertex 1.52108 1.76263 2.54569 + vertex 1.5218 1.75962 2.54916 + vertex 1.5219 1.76396 2.5489 + endloop + endfacet + facet normal -0.839734 0.051661 0.540534 + outer loop + vertex 1.5218 1.75962 2.54916 + vertex 1.52311 1.76141 2.55103 + vertex 1.5219 1.76396 2.5489 + endloop + endfacet + facet normal -0.809041 -0.0197783 0.587419 + outer loop + vertex 1.52364 1.75744 2.55162 + vertex 1.52311 1.76141 2.55103 + vertex 1.5218 1.75962 2.54916 + endloop + endfacet + facet normal -0.916773 -0.0115559 -0.399241 + outer loop + vertex 1.52302 1.76479 2.53518 + vertex 1.52161 1.76607 2.53838 + vertex 1.52276 1.76891 2.53565 + endloop + endfacet + facet normal -0.895268 0.100138 -0.434129 + outer loop + vertex 1.52145 1.76067 2.53746 + vertex 1.52161 1.76607 2.53838 + vertex 1.52302 1.76479 2.53518 + endloop + endfacet + facet normal -0.988497 0.0529477 -0.141668 + outer loop + vertex 1.52145 1.76067 2.53746 + vertex 1.52091 1.76161 2.54158 + vertex 1.52161 1.76607 2.53838 + endloop + endfacet + facet normal -0.990723 0.0724859 -0.114951 + outer loop + vertex 1.52161 1.76607 2.53838 + vertex 1.52091 1.76161 2.54158 + vertex 1.5211 1.76554 2.54245 + endloop + endfacet + facet normal -0.998695 0.0405663 0.03102 + outer loop + vertex 1.52091 1.76161 2.54158 + vertex 1.52108 1.76263 2.54569 + vertex 1.5211 1.76554 2.54245 + endloop + endfacet + facet normal -0.994481 0.080644 0.067106 + outer loop + vertex 1.5211 1.76554 2.54245 + vertex 1.52108 1.76263 2.54569 + vertex 1.52142 1.76691 2.54568 + endloop + endfacet + facet normal -0.973204 0.0790693 0.21592 + outer loop + vertex 1.52108 1.76263 2.54569 + vertex 1.5219 1.76396 2.5489 + vertex 1.52142 1.76691 2.54568 + endloop + endfacet + facet normal -0.930268 0.191701 0.312812 + outer loop + vertex 1.52142 1.76691 2.54568 + vertex 1.5219 1.76396 2.5489 + vertex 1.52264 1.76778 2.54875 + endloop + endfacet + facet normal -0.773095 0.173042 0.61023 + outer loop + vertex 1.5219 1.76396 2.5489 + vertex 1.5236 1.76471 2.55084 + vertex 1.52264 1.76778 2.54875 + endloop + endfacet + facet normal -0.771682 0.148791 0.61836 + outer loop + vertex 1.52311 1.76141 2.55103 + vertex 1.5236 1.76471 2.55084 + vertex 1.5219 1.76396 2.5489 + endloop + endfacet + facet normal -0.935666 0.0430938 -0.350245 + outer loop + vertex 1.52276 1.76891 2.53565 + vertex 1.52161 1.76607 2.53838 + vertex 1.52205 1.77044 2.53773 + endloop + endfacet + facet normal -0.989583 0.117746 -0.0828356 + outer loop + vertex 1.52205 1.77044 2.53773 + vertex 1.52164 1.76975 2.54166 + vertex 1.52225 1.77321 2.53925 + endloop + endfacet + facet normal -0.992195 0.0879988 -0.0883478 + outer loop + vertex 1.52205 1.77044 2.53773 + vertex 1.52161 1.76607 2.53838 + vertex 1.52164 1.76975 2.54166 + endloop + endfacet + facet normal -0.988106 0.107341 -0.110107 + outer loop + vertex 1.52161 1.76607 2.53838 + vertex 1.5211 1.76554 2.54245 + vertex 1.52164 1.76975 2.54166 + endloop + endfacet + facet normal -0.989739 0.136236 0.0430786 + outer loop + vertex 1.5211 1.76554 2.54245 + vertex 1.52142 1.76691 2.54568 + vertex 1.52164 1.76975 2.54166 + endloop + endfacet + facet normal -0.963048 0.241585 0.119064 + outer loop + vertex 1.52164 1.76975 2.54166 + vertex 1.52142 1.76691 2.54568 + vertex 1.52244 1.77086 2.54589 + endloop + endfacet + facet normal -0.582737 0.386691 0.714764 + outer loop + vertex 1.52506 1.77149 2.54872 + vertex 1.52264 1.76778 2.54875 + vertex 1.52461 1.76775 2.55038 + endloop + endfacet + facet normal -0.700437 0.461998 0.544009 + outer loop + vertex 1.52506 1.77149 2.54872 + vertex 1.52244 1.77086 2.54589 + vertex 1.52264 1.76778 2.54875 + endloop + endfacet + facet normal -0.926703 0.22288 0.302564 + outer loop + vertex 1.52244 1.77086 2.54589 + vertex 1.52142 1.76691 2.54568 + vertex 1.52264 1.76778 2.54875 + endloop + endfacet + facet normal -0.600917 0.31255 0.73567 + outer loop + vertex 1.52461 1.76775 2.55038 + vertex 1.52264 1.76778 2.54875 + vertex 1.5236 1.76471 2.55084 + endloop + endfacet + facet normal -0.975525 0.212555 0.0563217 + outer loop + vertex 1.52225 1.77321 2.53925 + vertex 1.52164 1.76975 2.54166 + vertex 1.52267 1.77415 2.54294 + endloop + endfacet + facet normal -0.878175 0.352044 0.323841 + outer loop + vertex 1.52267 1.77415 2.54294 + vertex 1.52244 1.77086 2.54589 + vertex 1.52405 1.77447 2.54632 + endloop + endfacet + facet normal -0.972663 0.189236 0.134595 + outer loop + vertex 1.52164 1.76975 2.54166 + vertex 1.52244 1.77086 2.54589 + vertex 1.52267 1.77415 2.54294 + endloop + endfacet + facet normal -0.738182 0.253812 0.625033 + outer loop + vertex 1.52405 1.77447 2.54632 + vertex 1.52244 1.77086 2.54589 + vertex 1.52506 1.77149 2.54872 + endloop + endfacet + facet normal -0.0221654 -0.34638 -0.937833 + outer loop + vertex 1.525 2.01224 2.49 + vertex 1.52208 2.00993 2.49092 + vertex 1.52 2.01256 2.49 + endloop + endfacet + facet normal -0.320763 -0.529461 -0.785355 + outer loop + vertex 1.52208 2.00993 2.49092 + vertex 1.51855 2.01061 2.4919 + vertex 1.52 2.01256 2.49 + endloop + endfacet + facet normal -0.208311 -0.975272 -0.0738276 + outer loop + vertex 1.52208 2.00993 2.49092 + vertex 1.52312 2.00939 2.49519 + vertex 1.51855 2.01061 2.4919 + endloop + endfacet + facet normal -0.21898 -0.973974 -0.058495 + outer loop + vertex 1.52312 2.00939 2.49519 + vertex 1.51783 2.01053 2.49603 + vertex 1.51855 2.01061 2.4919 + endloop + endfacet + facet normal -0.145764 -0.928786 0.340749 + outer loop + vertex 1.52312 2.00939 2.49519 + vertex 1.52078 2.01133 2.49948 + vertex 1.51783 2.01053 2.49603 + endloop + endfacet + facet normal -0.0589548 -0.959993 0.273749 + outer loop + vertex 1.52078 2.01133 2.49948 + vertex 1.51594 2.01164 2.49951 + vertex 1.51783 2.01053 2.49603 + endloop + endfacet + facet normal -0.0393348 -0.691013 0.721771 + outer loop + vertex 1.52078 2.01133 2.49948 + vertex 1.51712 2.0134 2.50126 + vertex 1.51594 2.01164 2.49951 + endloop + endfacet + facet normal -0.113242 -0.755781 0.644958 + outer loop + vertex 1.52092 2.01275 2.50117 + vertex 1.51712 2.0134 2.50126 + vertex 1.52078 2.01133 2.49948 + endloop + endfacet + facet normal 0.144221 0.494608 0.857066 + outer loop + vertex 1.51908 2.10891 2.47101 + vertex 1.52315 2.10819 2.47074 + vertex 1.5219 2.11199 2.46876 + endloop + endfacet + facet normal 0.169637 0.475756 0.863064 + outer loop + vertex 1.51689 2.112 2.46974 + vertex 1.51908 2.10891 2.47101 + vertex 1.5219 2.11199 2.46876 + endloop + endfacet + facet normal 0.127373 0.394071 0.910211 + outer loop + vertex 1.52145 2.10499 2.47237 + vertex 1.51908 2.10891 2.47101 + vertex 1.5163 2.10591 2.4727 + endloop + endfacet + facet normal 0.130242 0.39546 0.909202 + outer loop + vertex 1.52315 2.10819 2.47074 + vertex 1.51908 2.10891 2.47101 + vertex 1.52145 2.10499 2.47237 + endloop + endfacet + facet normal 0.190978 0.711959 0.675753 + outer loop + vertex 1.52443 2.11446 2.46632 + vertex 1.52265 2.11641 2.46477 + vertex 1.52093 2.11523 2.4665 + endloop + endfacet + facet normal 0.171461 0.596871 0.783802 + outer loop + vertex 1.52093 2.11523 2.4665 + vertex 1.5219 2.11199 2.46876 + vertex 1.52443 2.11446 2.46632 + endloop + endfacet + facet normal 0.167113 0.596443 0.785067 + outer loop + vertex 1.52093 2.11523 2.4665 + vertex 1.51676 2.11517 2.46744 + vertex 1.5219 2.11199 2.46876 + endloop + endfacet + facet normal 0.156638 0.584178 0.796367 + outer loop + vertex 1.51676 2.11517 2.46744 + vertex 1.51689 2.112 2.46974 + vertex 1.5219 2.11199 2.46876 + endloop + endfacet + facet normal 0.19751 0.879331 0.433322 + outer loop + vertex 1.51902 2.12102 2.45823 + vertex 1.51634 2.12115 2.45921 + vertex 1.51867 2.11968 2.46112 + endloop + endfacet + facet normal 0.0918265 0.898504 0.429253 + outer loop + vertex 1.51902 2.12102 2.45823 + vertex 1.51867 2.11968 2.46112 + vertex 1.52397 2.1211 2.45701 + endloop + endfacet + facet normal 0.188518 0.827248 0.529266 + outer loop + vertex 1.52397 2.1211 2.45701 + vertex 1.51867 2.11968 2.46112 + vertex 1.52295 2.11815 2.46199 + endloop + endfacet + facet normal 0.157584 0.735607 0.658824 + outer loop + vertex 1.52265 2.11641 2.46477 + vertex 1.51934 2.11732 2.46455 + vertex 1.52093 2.11523 2.4665 + endloop + endfacet + facet normal 0.189988 0.823292 0.534878 + outer loop + vertex 1.52265 2.11641 2.46477 + vertex 1.52295 2.11815 2.46199 + vertex 1.51934 2.11732 2.46455 + endloop + endfacet + facet normal 0.187414 0.825726 0.532027 + outer loop + vertex 1.52295 2.11815 2.46199 + vertex 1.51867 2.11968 2.46112 + vertex 1.51934 2.11732 2.46455 + endloop + endfacet + facet normal 0.139091 0.730582 0.668509 + outer loop + vertex 1.52093 2.11523 2.4665 + vertex 1.51934 2.11732 2.46455 + vertex 1.51676 2.11517 2.46744 + endloop + endfacet + facet normal -0.0177286 0.633383 0.773635 + outer loop + vertex 1.525 2.1272 2.45 + vertex 1.52 2.12706 2.45 + vertex 1.52387 2.12426 2.45238 + endloop + endfacet + facet normal 0.567269 0.822245 0.046031 + outer loop + vertex 1.52387 2.12426 2.45238 + vertex 1.52 2.12706 2.45 + vertex 1.52 2.12678 2.455 + endloop + endfacet + facet normal 0.125038 0.819951 0.558611 + outer loop + vertex 1.52397 2.1211 2.45701 + vertex 1.51731 2.1229 2.45586 + vertex 1.51902 2.12102 2.45823 + endloop + endfacet + facet normal 0.125603 0.820983 0.556966 + outer loop + vertex 1.52397 2.1211 2.45701 + vertex 1.52387 2.12426 2.45238 + vertex 1.51731 2.1229 2.45586 + endloop + endfacet + facet normal 0.48694 -0.147365 0.860914 + outer loop + vertex 1.52387 2.12426 2.45238 + vertex 1.52 2.12678 2.455 + vertex 1.51731 2.1229 2.45586 + endloop + endfacet + facet normal 0.220668 0.835931 0.502519 + outer loop + vertex 1.51902 2.12102 2.45823 + vertex 1.51731 2.1229 2.45586 + vertex 1.51634 2.12115 2.45921 + endloop + endfacet + facet normal 0.156905 -0.794045 0.587259 + outer loop + vertex 1.53 0.907448 2.45 + vertex 1.52677 0.907575 2.45104 + vertex 1.525 0.90646 2.45 + endloop + endfacet + facet normal 0.244101 -0.83872 0.486788 + outer loop + vertex 1.52677 0.907575 2.45104 + vertex 1.52201 0.907304 2.45295 + vertex 1.525 0.90646 2.45 + endloop + endfacet + facet normal 0.181689 -0.930133 0.319127 + outer loop + vertex 1.52677 0.907575 2.45104 + vertex 1.52464 0.908338 2.45447 + vertex 1.52201 0.907304 2.45295 + endloop + endfacet + facet normal 0.166312 -0.935789 0.31087 + outer loop + vertex 1.52911 0.90874 2.45329 + vertex 1.52464 0.908338 2.45447 + vertex 1.52677 0.907575 2.45104 + endloop + endfacet + facet normal 0.184976 -0.900494 0.393567 + outer loop + vertex 1.52464 0.908338 2.45447 + vertex 1.52911 0.90874 2.45329 + vertex 1.52693 0.909755 2.45664 + endloop + endfacet + facet normal 0.165661 -0.896355 0.411223 + outer loop + vertex 1.5223 0.909745 2.45848 + vertex 1.52464 0.908338 2.45447 + vertex 1.52693 0.909755 2.45664 + endloop + endfacet + facet normal 0.211743 -0.822774 0.527454 + outer loop + vertex 1.52693 0.909755 2.45664 + vertex 1.52638 0.912015 2.46038 + vertex 1.5223 0.909745 2.45848 + endloop + endfacet + facet normal 0.197597 -0.813596 0.546825 + outer loop + vertex 1.52638 0.912015 2.46038 + vertex 1.52166 0.911821 2.4618 + vertex 1.5223 0.909745 2.45848 + endloop + endfacet + facet normal 0.221144 -0.73979 0.635457 + outer loop + vertex 1.52638 0.912015 2.46038 + vertex 1.52353 0.913991 2.46367 + vertex 1.52166 0.911821 2.4618 + endloop + endfacet + facet normal 0.202442 -0.752399 0.626827 + outer loop + vertex 1.52722 0.91472 2.46336 + vertex 1.52353 0.913991 2.46367 + vertex 1.52638 0.912015 2.46038 + endloop + endfacet + facet normal 0.192742 -0.659927 0.726187 + outer loop + vertex 1.52353 0.913991 2.46367 + vertex 1.52722 0.91472 2.46336 + vertex 1.52569 0.91681 2.46566 + endloop + endfacet + facet normal 0.18189 -0.65604 0.73248 + outer loop + vertex 1.52131 0.916084 2.4661 + vertex 1.52353 0.913991 2.46367 + vertex 1.52569 0.91681 2.46566 + endloop + endfacet + facet normal 0.174254 -0.565502 0.806129 + outer loop + vertex 1.52569 0.91681 2.46566 + vertex 1.52405 0.919517 2.46792 + vertex 1.52131 0.916084 2.4661 + endloop + endfacet + facet normal 0.157435 -0.573719 0.803779 + outer loop + vertex 1.52883 0.919955 2.46729 + vertex 1.52405 0.919517 2.46792 + vertex 1.52569 0.91681 2.46566 + endloop + endfacet + facet normal 0.156814 -0.49305 0.855752 + outer loop + vertex 1.52883 0.919955 2.46729 + vertex 1.52812 0.923674 2.46957 + vertex 1.52405 0.919517 2.46792 + endloop + endfacet + facet normal 0.143342 -0.483062 0.863773 + outer loop + vertex 1.52405 0.919517 2.46792 + vertex 1.52812 0.923674 2.46957 + vertex 1.52248 0.922553 2.46987 + endloop + endfacet + facet normal 0.449909 -0.891982 0.0441637 + outer loop + vertex 1.52728 1.02 2.485 + vertex 1.525 1.01885 2.485 + vertex 1.52547 1.01906 2.48453 + endloop + endfacet + facet normal -0.350842 0.93229 0.0880064 + outer loop + vertex 1.52439 1.01858 2.49069 + vertex 1.52237 1.01807 2.48805 + vertex 1.52157 1.01748 2.49111 + endloop + endfacet + facet normal -0.325086 0.918647 0.224515 + outer loop + vertex 1.52542 1.01802 2.49444 + vertex 1.52439 1.01858 2.49069 + vertex 1.52157 1.01748 2.49111 + endloop + endfacet + facet normal -0.391561 0.8665 0.309609 + outer loop + vertex 1.52176 1.01612 2.49513 + vertex 1.52542 1.01802 2.49444 + vertex 1.52157 1.01748 2.49111 + endloop + endfacet + facet normal -0.311844 0.79128 0.525956 + outer loop + vertex 1.52176 1.01612 2.49513 + vertex 1.52749 1.01619 2.49843 + vertex 1.52542 1.01802 2.49444 + endloop + endfacet + facet normal -0.39033 0.636251 0.665453 + outer loop + vertex 1.52176 1.01612 2.49513 + vertex 1.52133 1.01272 2.49813 + vertex 1.52749 1.01619 2.49843 + endloop + endfacet + facet normal -0.170734 0.220323 0.960369 + outer loop + vertex 1.52133 1.01272 2.49813 + vertex 1.52642 1.01221 2.49915 + vertex 1.52749 1.01619 2.49843 + endloop + endfacet + facet normal -0.321558 0.61162 -0.722856 + outer loop + vertex 1.53 1.02 2.48379 + vertex 1.52728 1.02 2.485 + vertex 1.53 1.02143 2.485 + endloop + endfacet + facet normal 0.465157 -0.884752 -0.0290145 + outer loop + vertex 1.52547 1.01906 2.48453 + vertex 1.53 1.02143 2.485 + vertex 1.52728 1.02 2.485 + endloop + endfacet + facet normal -0.462296 0.886686 -0.00834289 + outer loop + vertex 1.52547 1.01906 2.48453 + vertex 1.52572 1.01922 2.48732 + vertex 1.53 1.02143 2.485 + endloop + endfacet + facet normal -0.389709 0.909087 0.147268 + outer loop + vertex 1.52572 1.01922 2.48732 + vertex 1.52931 1.02063 2.48814 + vertex 1.53 1.02143 2.485 + endloop + endfacet + facet normal -0.314271 0.94762 0.0570126 + outer loop + vertex 1.52439 1.01858 2.49069 + vertex 1.52572 1.01922 2.48732 + vertex 1.52237 1.01807 2.48805 + endloop + endfacet + facet normal -0.292606 0.953901 0.0667451 + outer loop + vertex 1.52439 1.01858 2.49069 + vertex 1.52814 1.01962 2.49227 + vertex 1.52572 1.01922 2.48732 + endloop + endfacet + facet normal -0.384914 0.915768 0.11494 + outer loop + vertex 1.52814 1.01962 2.49227 + vertex 1.52931 1.02063 2.48814 + vertex 1.52572 1.01922 2.48732 + endloop + endfacet + facet normal -0.328021 0.909207 0.256408 + outer loop + vertex 1.52814 1.01962 2.49227 + vertex 1.52542 1.01802 2.49444 + vertex 1.52952 1.01874 2.49715 + endloop + endfacet + facet normal -0.348999 0.908575 0.229547 + outer loop + vertex 1.52439 1.01858 2.49069 + vertex 1.52542 1.01802 2.49444 + vertex 1.52814 1.01962 2.49227 + endloop + endfacet + facet normal -0.486826 0.669437 0.561119 + outer loop + vertex 1.52952 1.01874 2.49715 + vertex 1.52542 1.01802 2.49444 + vertex 1.52749 1.01619 2.49843 + endloop + endfacet + facet normal -0.976795 -0.165931 -0.135421 + outer loop + vertex 1.52765 1.1977 2.53073 + vertex 1.52705 1.20005 2.5322 + vertex 1.52741 1.20076 2.5287 + endloop + endfacet + facet normal -0.971803 -0.234561 -0.0240913 + outer loop + vertex 1.52765 1.1977 2.53073 + vertex 1.52763 1.19749 2.53353 + vertex 1.52705 1.20005 2.5322 + endloop + endfacet + facet normal -0.975363 -0.118237 -0.186243 + outer loop + vertex 1.52741 1.20076 2.5287 + vertex 1.52677 1.20351 2.53032 + vertex 1.52728 1.20387 2.5274 + endloop + endfacet + facet normal -0.979624 -0.150793 -0.132658 + outer loop + vertex 1.52705 1.20005 2.5322 + vertex 1.52677 1.20351 2.53032 + vertex 1.52741 1.20076 2.5287 + endloop + endfacet + facet normal -0.979964 -0.170295 0.1033 + outer loop + vertex 1.52739 1.19979 2.53503 + vertex 1.52705 1.20005 2.5322 + vertex 1.52763 1.19749 2.53353 + endloop + endfacet + facet normal -0.987514 -0.113403 0.109341 + outer loop + vertex 1.52739 1.19979 2.53503 + vertex 1.52688 1.20376 2.53453 + vertex 1.52705 1.20005 2.5322 + endloop + endfacet + facet normal -0.997498 -0.0640032 0.0300262 + outer loop + vertex 1.52688 1.20376 2.53453 + vertex 1.52677 1.20351 2.53032 + vertex 1.52705 1.20005 2.5322 + endloop + endfacet + facet normal -0.951971 -0.0858734 0.293899 + outer loop + vertex 1.52739 1.19979 2.53503 + vertex 1.52788 1.20179 2.53719 + vertex 1.52688 1.20376 2.53453 + endloop + endfacet + facet normal -0.859103 0.143621 -0.491239 + outer loop + vertex 1.52818 1.20645 2.52578 + vertex 1.52704 1.20683 2.52789 + vertex 1.52871 1.21015 2.52594 + endloop + endfacet + facet normal -0.878766 0.00769566 -0.47719 + outer loop + vertex 1.52728 1.20387 2.5274 + vertex 1.52704 1.20683 2.52789 + vertex 1.52818 1.20645 2.52578 + endloop + endfacet + facet normal -0.982501 -0.0509023 -0.179169 + outer loop + vertex 1.52728 1.20387 2.5274 + vertex 1.52677 1.20351 2.53032 + vertex 1.52704 1.20683 2.52789 + endloop + endfacet + facet normal -0.986101 -0.0378633 -0.161775 + outer loop + vertex 1.52677 1.20351 2.53032 + vertex 1.52643 1.20773 2.5314 + vertex 1.52704 1.20683 2.52789 + endloop + endfacet + facet normal -0.99565 -0.087741 0.0313477 + outer loop + vertex 1.52677 1.20351 2.53032 + vertex 1.52688 1.20376 2.53453 + vertex 1.52643 1.20773 2.5314 + endloop + endfacet + facet normal -0.996064 -0.0737914 0.0490987 + outer loop + vertex 1.52643 1.20773 2.5314 + vertex 1.52688 1.20376 2.53453 + vertex 1.52651 1.20972 2.53592 + endloop + endfacet + facet normal -0.949858 -0.126197 0.286084 + outer loop + vertex 1.52688 1.20376 2.53453 + vertex 1.52777 1.2058 2.5384 + vertex 1.52651 1.20972 2.53592 + endloop + endfacet + facet normal -0.954425 -0.108797 0.277915 + outer loop + vertex 1.52788 1.20179 2.53719 + vertex 1.52777 1.2058 2.5384 + vertex 1.52688 1.20376 2.53453 + endloop + endfacet + facet normal -0.616243 0.513751 -0.596913 + outer loop + vertex 1.52871 1.21015 2.52594 + vertex 1.52708 1.21112 2.52845 + vertex 1.53 1.215 2.52878 + endloop + endfacet + facet normal -0.821862 0.0821933 -0.563727 + outer loop + vertex 1.52704 1.20683 2.52789 + vertex 1.52708 1.21112 2.52845 + vertex 1.52871 1.21015 2.52594 + endloop + endfacet + facet normal -0.98315 0.033686 -0.179672 + outer loop + vertex 1.52704 1.20683 2.52789 + vertex 1.52643 1.20773 2.5314 + vertex 1.52708 1.21112 2.52845 + endloop + endfacet + facet normal -0.958917 -0.0563437 -0.278034 + outer loop + vertex 1.52708 1.21112 2.52845 + vertex 1.52643 1.20773 2.5314 + vertex 1.52607 1.21262 2.53165 + endloop + endfacet + facet normal -0.995817 -0.0763354 0.0502113 + outer loop + vertex 1.52643 1.20773 2.5314 + vertex 1.52651 1.20972 2.53592 + vertex 1.52607 1.21262 2.53165 + endloop + endfacet + facet normal -0.990053 -0.140569 0.00592451 + outer loop + vertex 1.52607 1.21262 2.53165 + vertex 1.52651 1.20972 2.53592 + vertex 1.52581 1.21455 2.53491 + endloop + endfacet + facet normal -0.94131 -0.100625 0.322195 + outer loop + vertex 1.5278 1.20998 2.5398 + vertex 1.52651 1.20972 2.53592 + vertex 1.52777 1.2058 2.5384 + endloop + endfacet + facet normal -0.93695 -0.133516 0.322952 + outer loop + vertex 1.5278 1.20998 2.5398 + vertex 1.52696 1.21478 2.53934 + vertex 1.52651 1.20972 2.53592 + endloop + endfacet + facet normal -0.963413 -0.0847401 0.254273 + outer loop + vertex 1.52696 1.21478 2.53934 + vertex 1.52581 1.21455 2.53491 + vertex 1.52651 1.20972 2.53592 + endloop + endfacet + facet normal -0.715424 -0.058834 0.696209 + outer loop + vertex 1.5278 1.20998 2.5398 + vertex 1.5301 1.21285 2.5424 + vertex 1.52696 1.21478 2.53934 + endloop + endfacet + facet normal -0.0276104 -0.0638366 -0.997578 + outer loop + vertex 1.53 1.215 2.52878 + vertex 1.52706 1.2159 2.5288 + vertex 1.53 1.22 2.52846 + endloop + endfacet + facet normal 0.0142804 0.0731702 -0.997217 + outer loop + vertex 1.52708 1.21112 2.52845 + vertex 1.52706 1.2159 2.5288 + vertex 1.53 1.215 2.52878 + endloop + endfacet + facet normal -0.950479 0.018116 -0.310261 + outer loop + vertex 1.52708 1.21112 2.52845 + vertex 1.52607 1.21262 2.53165 + vertex 1.52706 1.2159 2.5288 + endloop + endfacet + facet normal -0.912708 -0.0732066 -0.402001 + outer loop + vertex 1.52706 1.2159 2.5288 + vertex 1.52607 1.21262 2.53165 + vertex 1.5257 1.21736 2.53164 + endloop + endfacet + facet normal -0.996424 -0.0784841 -0.0312819 + outer loop + vertex 1.52607 1.21262 2.53165 + vertex 1.52581 1.21455 2.53491 + vertex 1.5257 1.21736 2.53164 + endloop + endfacet + facet normal -0.997534 -0.0668816 -0.0212983 + outer loop + vertex 1.5257 1.21736 2.53164 + vertex 1.52581 1.21455 2.53491 + vertex 1.52552 1.21869 2.53575 + endloop + endfacet + facet normal -0.959399 -0.120418 0.255054 + outer loop + vertex 1.52581 1.21455 2.53491 + vertex 1.52696 1.21478 2.53934 + vertex 1.52552 1.21869 2.53575 + endloop + endfacet + facet normal -0.963395 -0.155531 0.218356 + outer loop + vertex 1.52552 1.21869 2.53575 + vertex 1.52696 1.21478 2.53934 + vertex 1.52632 1.22061 2.54068 + endloop + endfacet + facet normal -0.758364 -0.223522 0.612309 + outer loop + vertex 1.52696 1.21478 2.53934 + vertex 1.52928 1.21864 2.54362 + vertex 1.52632 1.22061 2.54068 + endloop + endfacet + facet normal -0.749093 -0.236343 0.618871 + outer loop + vertex 1.5301 1.21285 2.5424 + vertex 1.52928 1.21864 2.54362 + vertex 1.52696 1.21478 2.53934 + endloop + endfacet + facet normal -0.118538 0.00397716 -0.992942 + outer loop + vertex 1.53 1.22 2.52846 + vertex 1.52688 1.22077 2.52884 + vertex 1.53 1.225 2.52848 + endloop + endfacet + facet normal -0.119007 0.00204237 -0.992891 + outer loop + vertex 1.52706 1.2159 2.5288 + vertex 1.52688 1.22077 2.52884 + vertex 1.53 1.22 2.52846 + endloop + endfacet + facet normal -0.906676 -0.0313145 -0.420663 + outer loop + vertex 1.52706 1.2159 2.5288 + vertex 1.5257 1.21736 2.53164 + vertex 1.52688 1.22077 2.52884 + endloop + endfacet + facet normal -0.904596 -0.0354305 -0.424795 + outer loop + vertex 1.52688 1.22077 2.52884 + vertex 1.5257 1.21736 2.53164 + vertex 1.52544 1.22214 2.53178 + endloop + endfacet + facet normal -0.998288 -0.0523945 -0.026014 + outer loop + vertex 1.5257 1.21736 2.53164 + vertex 1.52552 1.21869 2.53575 + vertex 1.52544 1.22214 2.53178 + endloop + endfacet + facet normal -0.994415 -0.0885279 -0.0574544 + outer loop + vertex 1.52544 1.22214 2.53178 + vertex 1.52552 1.21869 2.53575 + vertex 1.52509 1.22338 2.53594 + endloop + endfacet + facet normal -0.975562 -0.0966544 0.197322 + outer loop + vertex 1.52552 1.21869 2.53575 + vertex 1.52632 1.22061 2.54068 + vertex 1.52509 1.22338 2.53594 + endloop + endfacet + facet normal -0.968067 -0.217194 0.12519 + outer loop + vertex 1.52509 1.22338 2.53594 + vertex 1.52632 1.22061 2.54068 + vertex 1.52527 1.22467 2.53958 + endloop + endfacet + facet normal -0.762151 -0.453725 0.4618 + outer loop + vertex 1.52795 1.22171 2.54444 + vertex 1.52632 1.22061 2.54068 + vertex 1.52928 1.21864 2.54362 + endloop + endfacet + facet normal -0.874813 -0.205681 0.438631 + outer loop + vertex 1.52795 1.22171 2.54444 + vertex 1.52675 1.22496 2.54358 + vertex 1.52632 1.22061 2.54068 + endloop + endfacet + facet normal -0.924385 -0.143885 0.353283 + outer loop + vertex 1.52675 1.22496 2.54358 + vertex 1.52527 1.22467 2.53958 + vertex 1.52632 1.22061 2.54068 + endloop + endfacet + facet normal -0.677199 -0.0543513 0.73379 + outer loop + vertex 1.52795 1.22171 2.54444 + vertex 1.52939 1.22468 2.54599 + vertex 1.52675 1.22496 2.54358 + endloop + endfacet + facet normal -0.12078 -0.0376985 -0.991963 + outer loop + vertex 1.53 1.225 2.52848 + vertex 1.52678 1.22583 2.52884 + vertex 1.53 1.23 2.52829 + endloop + endfacet + facet normal -0.111571 -0.00122934 -0.993756 + outer loop + vertex 1.52688 1.22077 2.52884 + vertex 1.52678 1.22583 2.52884 + vertex 1.53 1.225 2.52848 + endloop + endfacet + facet normal -0.901861 -0.0178097 -0.431658 + outer loop + vertex 1.52688 1.22077 2.52884 + vertex 1.52544 1.22214 2.53178 + vertex 1.52678 1.22583 2.52884 + endloop + endfacet + facet normal -0.896765 -0.0276003 -0.441646 + outer loop + vertex 1.52678 1.22583 2.52884 + vertex 1.52544 1.22214 2.53178 + vertex 1.52526 1.22706 2.53183 + endloop + endfacet + facet normal -0.99667 -0.035201 -0.0735459 + outer loop + vertex 1.52544 1.22214 2.53178 + vertex 1.52509 1.22338 2.53594 + vertex 1.52526 1.22706 2.53183 + endloop + endfacet + facet normal -0.991537 -0.0730397 -0.107329 + outer loop + vertex 1.52526 1.22706 2.53183 + vertex 1.52509 1.22338 2.53594 + vertex 1.52476 1.22781 2.536 + endloop + endfacet + facet normal -0.994176 -0.0759363 0.0764695 + outer loop + vertex 1.52509 1.22338 2.53594 + vertex 1.52527 1.22467 2.53958 + vertex 1.52476 1.22781 2.536 + endloop + endfacet + facet normal -0.994189 -0.0678268 0.083597 + outer loop + vertex 1.52476 1.22781 2.536 + vertex 1.52527 1.22467 2.53958 + vertex 1.52509 1.22832 2.5404 + endloop + endfacet + facet normal -0.927302 -0.124649 0.35295 + outer loop + vertex 1.52527 1.22467 2.53958 + vertex 1.52675 1.22496 2.54358 + vertex 1.52509 1.22832 2.5404 + endloop + endfacet + facet normal -0.923402 -0.108238 0.368257 + outer loop + vertex 1.52509 1.22832 2.5404 + vertex 1.52675 1.22496 2.54358 + vertex 1.52644 1.22988 2.54424 + endloop + endfacet + facet normal -0.612728 -0.143939 0.777075 + outer loop + vertex 1.52675 1.22496 2.54358 + vertex 1.52925 1.2286 2.54622 + vertex 1.52644 1.22988 2.54424 + endloop + endfacet + facet normal -0.677416 -0.0672021 0.732524 + outer loop + vertex 1.52939 1.22468 2.54599 + vertex 1.52925 1.2286 2.54622 + vertex 1.52675 1.22496 2.54358 + endloop + endfacet + facet normal -0.190163 0.00196617 -0.981751 + outer loop + vertex 1.53 1.23 2.52829 + vertex 1.52681 1.23112 2.52891 + vertex 1.53 1.235 2.5283 + endloop + endfacet + facet normal -0.186061 0.0140591 -0.982438 + outer loop + vertex 1.52678 1.22583 2.52884 + vertex 1.52681 1.23112 2.52891 + vertex 1.53 1.23 2.52829 + endloop + endfacet + facet normal -0.890643 0.0113494 -0.454561 + outer loop + vertex 1.52678 1.22583 2.52884 + vertex 1.52526 1.22706 2.53183 + vertex 1.52681 1.23112 2.52891 + endloop + endfacet + facet normal -0.894284 0.0180899 -0.447134 + outer loop + vertex 1.52681 1.23112 2.52891 + vertex 1.52526 1.22706 2.53183 + vertex 1.52521 1.23204 2.53213 + endloop + endfacet + facet normal -0.992753 -0.00250645 -0.12015 + outer loop + vertex 1.52526 1.22706 2.53183 + vertex 1.52476 1.22781 2.536 + vertex 1.52521 1.23204 2.53213 + endloop + endfacet + facet normal -0.988221 -0.0302894 -0.150007 + outer loop + vertex 1.52521 1.23204 2.53213 + vertex 1.52476 1.22781 2.536 + vertex 1.52455 1.2323 2.53644 + endloop + endfacet + facet normal -0.995223 -0.0530611 0.0819521 + outer loop + vertex 1.52476 1.22781 2.536 + vertex 1.52509 1.22832 2.5404 + vertex 1.52455 1.2323 2.53644 + endloop + endfacet + facet normal -0.995353 -0.076596 0.058364 + outer loop + vertex 1.52455 1.2323 2.53644 + vertex 1.52509 1.22832 2.5404 + vertex 1.52477 1.23294 2.54089 + endloop + endfacet + facet normal -0.924277 -0.104626 0.367104 + outer loop + vertex 1.52509 1.22832 2.5404 + vertex 1.52644 1.22988 2.54424 + vertex 1.52477 1.23294 2.54089 + endloop + endfacet + facet normal -0.926018 -0.113273 0.360083 + outer loop + vertex 1.52477 1.23294 2.54089 + vertex 1.52644 1.22988 2.54424 + vertex 1.52603 1.23475 2.54472 + endloop + endfacet + facet normal -0.592775 -0.127726 0.795176 + outer loop + vertex 1.52644 1.22988 2.54424 + vertex 1.52901 1.23324 2.5467 + vertex 1.52603 1.23475 2.54472 + endloop + endfacet + facet normal -0.6058 -0.112282 0.787654 + outer loop + vertex 1.52925 1.2286 2.54622 + vertex 1.52901 1.23324 2.5467 + vertex 1.52644 1.22988 2.54424 + endloop + endfacet + facet normal -0.320772 0.153272 -0.934673 + outer loop + vertex 1.53 1.235 2.5283 + vertex 1.52709 1.23751 2.52971 + vertex 1.53 1.24 2.52912 + endloop + endfacet + facet normal -0.338158 0.131519 -0.931854 + outer loop + vertex 1.52681 1.23112 2.52891 + vertex 1.52709 1.23751 2.52971 + vertex 1.53 1.235 2.5283 + endloop + endfacet + facet normal -0.880962 0.0969398 -0.46315 + outer loop + vertex 1.52681 1.23112 2.52891 + vertex 1.52521 1.23204 2.53213 + vertex 1.52709 1.23751 2.52971 + endloop + endfacet + facet normal -0.880456 0.0962783 -0.46425 + outer loop + vertex 1.52709 1.23751 2.52971 + vertex 1.52521 1.23204 2.53213 + vertex 1.52514 1.23672 2.53324 + endloop + endfacet + facet normal -0.987995 0.021266 -0.153017 + outer loop + vertex 1.52521 1.23204 2.53213 + vertex 1.52455 1.2323 2.53644 + vertex 1.52514 1.23672 2.53324 + endloop + endfacet + facet normal -0.984295 0.00381573 -0.176489 + outer loop + vertex 1.52514 1.23672 2.53324 + vertex 1.52455 1.2323 2.53644 + vertex 1.52449 1.2376 2.53693 + endloop + endfacet + facet normal -0.998597 -0.0175233 0.0499716 + outer loop + vertex 1.52455 1.2323 2.53644 + vertex 1.52477 1.23294 2.54089 + vertex 1.52449 1.2376 2.53693 + endloop + endfacet + facet normal -0.99594 -0.0849918 -0.0296657 + outer loop + vertex 1.52449 1.2376 2.53693 + vertex 1.52477 1.23294 2.54089 + vertex 1.52432 1.23803 2.54134 + endloop + endfacet + facet normal -0.926069 -0.113084 0.360011 + outer loop + vertex 1.52477 1.23294 2.54089 + vertex 1.52603 1.23475 2.54472 + vertex 1.52432 1.23803 2.54134 + endloop + endfacet + facet normal -0.928149 -0.123273 0.351203 + outer loop + vertex 1.52432 1.23803 2.54134 + vertex 1.52603 1.23475 2.54472 + vertex 1.52558 1.23978 2.54529 + endloop + endfacet + facet normal -0.582001 -0.142998 0.800517 + outer loop + vertex 1.52603 1.23475 2.54472 + vertex 1.52863 1.23814 2.54721 + vertex 1.52558 1.23978 2.54529 + endloop + endfacet + facet normal -0.593333 -0.129815 0.79442 + outer loop + vertex 1.52901 1.23324 2.5467 + vertex 1.52863 1.23814 2.54721 + vertex 1.52603 1.23475 2.54472 + endloop + endfacet + facet normal -0.335109 0.171981 -0.92635 + outer loop + vertex 1.53 1.24 2.52912 + vertex 1.52709 1.23751 2.52971 + vertex 1.53 1.24474 2.53 + endloop + endfacet + facet normal -0.798392 0.156741 -0.58138 + outer loop + vertex 1.53 1.24474 2.53 + vertex 1.52641 1.245 2.535 + vertex 1.53 1.245 2.53007 + endloop + endfacet + facet normal -0.759214 0.327987 -0.562156 + outer loop + vertex 1.53 1.24474 2.53 + vertex 1.52709 1.23751 2.52971 + vertex 1.52641 1.245 2.535 + endloop + endfacet + facet normal -0.873435 0.225433 -0.431615 + outer loop + vertex 1.52709 1.23751 2.52971 + vertex 1.52514 1.23672 2.53324 + vertex 1.52641 1.245 2.535 + endloop + endfacet + facet normal -0.957119 0.192429 -0.216549 + outer loop + vertex 1.52514 1.23672 2.53324 + vertex 1.52449 1.2376 2.53693 + vertex 1.52641 1.245 2.535 + endloop + endfacet + facet normal -0.738832 0.0163353 -0.673692 + outer loop + vertex 1.52641 1.245 2.535 + vertex 1.52449 1.2376 2.53693 + vertex 1.5242 1.24311 2.53737 + endloop + endfacet + facet normal -0.998269 -0.0485054 -0.033262 + outer loop + vertex 1.52449 1.2376 2.53693 + vertex 1.52432 1.23803 2.54134 + vertex 1.5242 1.24311 2.53737 + endloop + endfacet + facet normal -0.98715 -0.111502 -0.114467 + outer loop + vertex 1.5242 1.24311 2.53737 + vertex 1.52432 1.23803 2.54134 + vertex 1.52357 1.24366 2.54231 + endloop + endfacet + facet normal -0.909321 -0.185153 0.372631 + outer loop + vertex 1.52432 1.23803 2.54134 + vertex 1.52558 1.23978 2.54529 + vertex 1.52357 1.24366 2.54231 + endloop + endfacet + facet normal -0.89537 -0.139332 0.422964 + outer loop + vertex 1.52357 1.24366 2.54231 + vertex 1.52558 1.23978 2.54529 + vertex 1.52537 1.24399 2.54623 + endloop + endfacet + facet normal -0.502338 -0.213182 0.837979 + outer loop + vertex 1.52558 1.23978 2.54529 + vertex 1.52827 1.24316 2.54776 + vertex 1.52537 1.24399 2.54623 + endloop + endfacet + facet normal -0.577976 -0.129382 0.805732 + outer loop + vertex 1.52863 1.23814 2.54721 + vertex 1.52827 1.24316 2.54776 + vertex 1.52558 1.23978 2.54529 + endloop + endfacet + facet normal -0.709063 -0.0552976 -0.702973 + outer loop + vertex 1.52641 1.245 2.535 + vertex 1.5242 1.24311 2.53737 + vertex 1.52602 1.25 2.535 + endloop + endfacet + facet normal -0.647967 -0.0898159 -0.756354 + outer loop + vertex 1.52602 1.25 2.535 + vertex 1.5242 1.24311 2.53737 + vertex 1.52343 1.24809 2.53745 + endloop + endfacet + facet normal -0.905379 -0.269699 -0.32795 + outer loop + vertex 1.52245 1.24711 2.54095 + vertex 1.52222 1.25019 2.53904 + vertex 1.52343 1.24809 2.53745 + endloop + endfacet + facet normal -0.842012 -0.410864 -0.349582 + outer loop + vertex 1.52245 1.24711 2.54095 + vertex 1.52343 1.24809 2.53745 + vertex 1.52357 1.24366 2.54231 + endloop + endfacet + facet normal -0.982382 -0.151526 -0.109383 + outer loop + vertex 1.52357 1.24366 2.54231 + vertex 1.52343 1.24809 2.53745 + vertex 1.5242 1.24311 2.53737 + endloop + endfacet + facet normal -0.955725 -0.289184 0.0544379 + outer loop + vertex 1.52265 1.24693 2.54353 + vertex 1.52245 1.24711 2.54095 + vertex 1.52357 1.24366 2.54231 + endloop + endfacet + facet normal -0.782121 -0.399147 0.478507 + outer loop + vertex 1.52265 1.24693 2.54353 + vertex 1.52357 1.24366 2.54231 + vertex 1.52405 1.24699 2.54587 + endloop + endfacet + facet normal -0.849353 -0.323529 0.417048 + outer loop + vertex 1.52405 1.24699 2.54587 + vertex 1.52357 1.24366 2.54231 + vertex 1.52537 1.24399 2.54623 + endloop + endfacet + facet normal -0.529948 -0.132077 0.837682 + outer loop + vertex 1.52537 1.24399 2.54623 + vertex 1.52763 1.24843 2.54836 + vertex 1.52405 1.24699 2.54587 + endloop + endfacet + facet normal -0.495183 -0.157731 0.854351 + outer loop + vertex 1.52827 1.24316 2.54776 + vertex 1.52763 1.24843 2.54836 + vertex 1.52537 1.24399 2.54623 + endloop + endfacet + facet normal -0.682228 -0.0109305 -0.731058 + outer loop + vertex 1.52602 1.25 2.535 + vertex 1.52343 1.24809 2.53745 + vertex 1.52594 1.255 2.535 + endloop + endfacet + facet normal -0.173118 -0.272338 -0.9465 + outer loop + vertex 1.52594 1.255 2.535 + vertex 1.52343 1.24809 2.53745 + vertex 1.52321 1.25303 2.53607 + endloop + endfacet + facet normal -0.879332 -0.164259 -0.446984 + outer loop + vertex 1.52321 1.25303 2.53607 + vertex 1.52343 1.24809 2.53745 + vertex 1.52222 1.25019 2.53904 + endloop + endfacet + facet normal -0.817139 -0.257693 -0.515634 + outer loop + vertex 1.52212 1.25338 2.53761 + vertex 1.52321 1.25303 2.53607 + vertex 1.52222 1.25019 2.53904 + endloop + endfacet + facet normal -0.819325 -0.284202 0.497932 + outer loop + vertex 1.52265 1.24693 2.54353 + vertex 1.52405 1.24699 2.54587 + vertex 1.52279 1.24953 2.54525 + endloop + endfacet + facet normal -0.729185 -0.201534 0.653967 + outer loop + vertex 1.52405 1.24699 2.54587 + vertex 1.52469 1.25177 2.54806 + vertex 1.52279 1.24953 2.54525 + endloop + endfacet + facet normal -0.450916 -0.320403 0.833077 + outer loop + vertex 1.52405 1.24699 2.54587 + vertex 1.52763 1.24843 2.54836 + vertex 1.52469 1.25177 2.54806 + endloop + endfacet + facet normal -0.330752 -0.206546 0.920837 + outer loop + vertex 1.52763 1.24843 2.54836 + vertex 1.52865 1.25391 2.54996 + vertex 1.52469 1.25177 2.54806 + endloop + endfacet + facet normal -0.0917371 -0.12246 -0.988225 + outer loop + vertex 1.52278 1.25611 2.53577 + vertex 1.52307 1.26034 2.53522 + vertex 1.52586 1.26 2.535 + endloop + endfacet + facet normal -0.106589 -0.110691 -0.988123 + outer loop + vertex 1.52278 1.25611 2.53577 + vertex 1.52586 1.26 2.535 + vertex 1.52321 1.25303 2.53607 + endloop + endfacet + facet normal -0.360073 -0.00576041 -0.932906 + outer loop + vertex 1.52321 1.25303 2.53607 + vertex 1.52586 1.26 2.535 + vertex 1.52594 1.255 2.535 + endloop + endfacet + facet normal -0.824186 -0.166815 -0.541194 + outer loop + vertex 1.52321 1.25303 2.53607 + vertex 1.52212 1.25338 2.53761 + vertex 1.52278 1.25611 2.53577 + endloop + endfacet + facet normal -0.192243 -0.429357 0.882437 + outer loop + vertex 1.52469 1.25177 2.54806 + vertex 1.52865 1.25391 2.54996 + vertex 1.52638 1.25595 2.55046 + endloop + endfacet + facet normal -0.438946 -0.307388 0.844298 + outer loop + vertex 1.5238 1.25576 2.54904 + vertex 1.52469 1.25177 2.54806 + vertex 1.52638 1.25595 2.55046 + endloop + endfacet + facet normal -0.441221 -0.296526 0.846993 + outer loop + vertex 1.52638 1.25595 2.55046 + vertex 1.52526 1.25919 2.55101 + vertex 1.5238 1.25576 2.54904 + endloop + endfacet + facet normal -0.127343 -0.208706 0.969652 + outer loop + vertex 1.52861 1.25963 2.55154 + vertex 1.52526 1.25919 2.55101 + vertex 1.52638 1.25595 2.55046 + endloop + endfacet + facet normal -0.0770271 0.00508519 -0.997016 + outer loop + vertex 1.52619 1.265 2.535 + vertex 1.52586 1.26 2.535 + vertex 1.52307 1.26034 2.53522 + endloop + endfacet + facet normal 0.0456946 -0.0769533 -0.995987 + outer loop + vertex 1.52312 1.2654 2.53483 + vertex 1.52619 1.265 2.535 + vertex 1.52307 1.26034 2.53522 + endloop + endfacet + facet normal -0.131069 -0.185402 0.973882 + outer loop + vertex 1.52861 1.25963 2.55154 + vertex 1.52824 1.26325 2.55218 + vertex 1.52526 1.25919 2.55101 + endloop + endfacet + facet normal -0.173939 -0.153648 0.972696 + outer loop + vertex 1.52526 1.25919 2.55101 + vertex 1.52824 1.26325 2.55218 + vertex 1.52456 1.26338 2.55155 + endloop + endfacet + facet normal 0.0554647 -0.00255087 -0.998457 + outer loop + vertex 1.52642 1.27 2.535 + vertex 1.52619 1.265 2.535 + vertex 1.52312 1.2654 2.53483 + endloop + endfacet + facet normal 0.103541 -0.0372112 -0.993929 + outer loop + vertex 1.52313 1.27052 2.53464 + vertex 1.52642 1.27 2.535 + vertex 1.52312 1.2654 2.53483 + endloop + endfacet + facet normal -0.173999 -0.162532 0.97124 + outer loop + vertex 1.52824 1.26325 2.55218 + vertex 1.52794 1.26765 2.55287 + vertex 1.52456 1.26338 2.55155 + endloop + endfacet + facet normal -0.186997 -0.15204 0.970524 + outer loop + vertex 1.52456 1.26338 2.55155 + vertex 1.52794 1.26765 2.55287 + vertex 1.52416 1.26815 2.55221 + endloop + endfacet + facet normal 0.109537 0.000877486 -0.993982 + outer loop + vertex 1.52638 1.275 2.535 + vertex 1.52642 1.27 2.535 + vertex 1.52313 1.27052 2.53464 + endloop + endfacet + facet normal 0.0990416 0.00857978 -0.995046 + outer loop + vertex 1.5232 1.2754 2.53469 + vertex 1.52638 1.275 2.535 + vertex 1.52313 1.27052 2.53464 + endloop + endfacet + facet normal 0.0962924 -0.0136737 -0.995259 + outer loop + vertex 1.52709 1.28 2.535 + vertex 1.52638 1.275 2.535 + vertex 1.5232 1.2754 2.53469 + endloop + endfacet + facet normal -0.0492635 0.109284 -0.992789 + outer loop + vertex 1.52354 1.28012 2.53519 + vertex 1.52709 1.28 2.535 + vertex 1.5232 1.2754 2.53469 + endloop + endfacet + facet normal -0.0532272 0.00457742 -0.998572 + outer loop + vertex 1.52752 1.285 2.535 + vertex 1.52709 1.28 2.535 + vertex 1.52354 1.28012 2.53519 + endloop + endfacet + facet normal -0.654865 0.512268 -0.555639 + outer loop + vertex 1.525 1.285 2.53797 + vertex 1.52752 1.285 2.535 + vertex 1.52354 1.28012 2.53519 + endloop + endfacet + facet normal -0.768525 -0.0783861 -0.635 + outer loop + vertex 1.52701 1.75 2.535 + vertex 1.52752 1.745 2.535 + vertex 1.525 1.745 2.53805 + endloop + endfacet + facet normal 0.0815377 -0.542692 -0.835965 + outer loop + vertex 1.52341 1.74934 2.53508 + vertex 1.52701 1.75 2.535 + vertex 1.525 1.745 2.53805 + endloop + endfacet + facet normal -0.0210661 -0.00181163 -0.999776 + outer loop + vertex 1.52658 1.755 2.535 + vertex 1.52701 1.75 2.535 + vertex 1.52341 1.74934 2.53508 + endloop + endfacet + facet normal 0.112046 -0.0762069 -0.990777 + outer loop + vertex 1.52309 1.75447 2.53465 + vertex 1.52658 1.755 2.535 + vertex 1.52341 1.74934 2.53508 + endloop + endfacet + facet normal 0.1002 0.00480899 -0.994956 + outer loop + vertex 1.52634 1.76 2.535 + vertex 1.52658 1.755 2.535 + vertex 1.52309 1.75447 2.53465 + endloop + endfacet + facet normal 0.0782115 0.0178615 -0.996777 + outer loop + vertex 1.52305 1.75966 2.53474 + vertex 1.52634 1.76 2.535 + vertex 1.52309 1.75447 2.53465 + endloop + endfacet + facet normal 0.0800469 0.000160311 -0.996791 + outer loop + vertex 1.52633 1.765 2.535 + vertex 1.52634 1.76 2.535 + vertex 1.52305 1.75966 2.53474 + endloop + endfacet + facet normal -0.0585057 0.0852596 -0.99464 + outer loop + vertex 1.52302 1.76479 2.53518 + vertex 1.52633 1.765 2.535 + vertex 1.52305 1.75966 2.53474 + endloop + endfacet + facet normal -0.0530587 -0.00541175 -0.998577 + outer loop + vertex 1.52582 1.77 2.535 + vertex 1.52633 1.765 2.535 + vertex 1.52302 1.76479 2.53518 + endloop + endfacet + facet normal -0.240743 0.0967384 -0.965756 + outer loop + vertex 1.52276 1.76891 2.53565 + vertex 1.52582 1.77 2.535 + vertex 1.52302 1.76479 2.53518 + endloop + endfacet + facet normal 0.10062 0.24025 0.965482 + outer loop + vertex 1.52856 1.76414 2.5514 + vertex 1.52875 1.76862 2.55026 + vertex 1.52584 1.76539 2.55137 + endloop + endfacet + facet normal 0.0566154 0.144953 0.987818 + outer loop + vertex 1.52584 1.76539 2.55137 + vertex 1.52622 1.76087 2.55201 + vertex 1.52856 1.76414 2.5514 + endloop + endfacet + facet normal -0.259781 0.114701 0.958831 + outer loop + vertex 1.52584 1.76539 2.55137 + vertex 1.5236 1.76471 2.55084 + vertex 1.52622 1.76087 2.55201 + endloop + endfacet + facet normal -0.285776 0.0953426 0.953542 + outer loop + vertex 1.5236 1.76471 2.55084 + vertex 1.52311 1.76141 2.55103 + vertex 1.52622 1.76087 2.55201 + endloop + endfacet + facet normal -0.901155 0.139883 -0.410307 + outer loop + vertex 1.52276 1.76891 2.53565 + vertex 1.52205 1.77044 2.53773 + vertex 1.52351 1.77388 2.5357 + endloop + endfacet + facet normal -0.223231 0.0428051 -0.973825 + outer loop + vertex 1.52276 1.76891 2.53565 + vertex 1.52351 1.77388 2.5357 + vertex 1.52582 1.77 2.535 + endloop + endfacet + facet normal -0.284748 0.00341483 -0.958596 + outer loop + vertex 1.52582 1.77 2.535 + vertex 1.52351 1.77388 2.5357 + vertex 1.52588 1.775 2.535 + endloop + endfacet + facet normal -0.931142 0.225536 -0.286546 + outer loop + vertex 1.52351 1.77388 2.5357 + vertex 1.52205 1.77044 2.53773 + vertex 1.52225 1.77321 2.53925 + endloop + endfacet + facet normal -0.0519363 0.365007 0.929555 + outer loop + vertex 1.52461 1.76775 2.55038 + vertex 1.52584 1.76539 2.55137 + vertex 1.52875 1.76862 2.55026 + endloop + endfacet + facet normal -0.0620901 0.41064 0.909681 + outer loop + vertex 1.52461 1.76775 2.55038 + vertex 1.52875 1.76862 2.55026 + vertex 1.52506 1.77149 2.54872 + endloop + endfacet + facet normal -0.228631 0.217121 0.948992 + outer loop + vertex 1.52506 1.77149 2.54872 + vertex 1.52875 1.76862 2.55026 + vertex 1.52896 1.77348 2.54921 + endloop + endfacet + facet normal -0.290148 0.238919 0.926678 + outer loop + vertex 1.52584 1.76539 2.55137 + vertex 1.52461 1.76775 2.55038 + vertex 1.5236 1.76471 2.55084 + endloop + endfacet + facet normal -0.295442 0.0283658 -0.954939 + outer loop + vertex 1.52588 1.775 2.535 + vertex 1.52351 1.77388 2.5357 + vertex 1.52636 1.78 2.535 + endloop + endfacet + facet normal 0.183991 -0.196001 -0.963188 + outer loop + vertex 1.52636 1.78 2.535 + vertex 1.52351 1.77388 2.5357 + vertex 1.52391 1.77878 2.53478 + endloop + endfacet + facet normal -0.975383 0.213257 0.0561263 + outer loop + vertex 1.52225 1.77321 2.53925 + vertex 1.52267 1.77415 2.54294 + vertex 1.5232 1.7776 2.53903 + endloop + endfacet + facet normal -0.936644 0.18788 -0.295633 + outer loop + vertex 1.52225 1.77321 2.53925 + vertex 1.5232 1.7776 2.53903 + vertex 1.52351 1.77388 2.5357 + endloop + endfacet + facet normal -0.987201 0.0535935 -0.150208 + outer loop + vertex 1.52351 1.77388 2.5357 + vertex 1.5232 1.7776 2.53903 + vertex 1.52391 1.77878 2.53478 + endloop + endfacet + facet normal -0.917272 0.351799 0.186681 + outer loop + vertex 1.5248 1.7789 2.54446 + vertex 1.5232 1.7776 2.53903 + vertex 1.52267 1.77415 2.54294 + endloop + endfacet + facet normal -0.894828 0.293849 0.336059 + outer loop + vertex 1.52405 1.77447 2.54632 + vertex 1.5248 1.7789 2.54446 + vertex 1.52267 1.77415 2.54294 + endloop + endfacet + facet normal -0.587381 0.396263 0.705662 + outer loop + vertex 1.52405 1.77447 2.54632 + vertex 1.52766 1.77708 2.54786 + vertex 1.5248 1.7789 2.54446 + endloop + endfacet + facet normal -0.582097 0.381675 0.717975 + outer loop + vertex 1.52405 1.77447 2.54632 + vertex 1.52506 1.77149 2.54872 + vertex 1.52766 1.77708 2.54786 + endloop + endfacet + facet normal -0.248184 0.259358 0.933348 + outer loop + vertex 1.52506 1.77149 2.54872 + vertex 1.52896 1.77348 2.54921 + vertex 1.52766 1.77708 2.54786 + endloop + endfacet + facet normal -0.939558 -0.0732731 -0.334459 + outer loop + vertex 1.52814 1.78 2.53 + vertex 1.52636 1.78 2.535 + vertex 1.52775 1.785 2.53 + endloop + endfacet + facet normal 0.322589 -0.712647 -0.622954 + outer loop + vertex 1.52775 1.785 2.53 + vertex 1.52636 1.78 2.535 + vertex 1.52511 1.78236 2.53166 + endloop + endfacet + facet normal 0.392401 -0.676269 -0.623444 + outer loop + vertex 1.52636 1.78 2.535 + vertex 1.52391 1.77878 2.53478 + vertex 1.52511 1.78236 2.53166 + endloop + endfacet + facet normal -0.95205 0.0551182 -0.300937 + outer loop + vertex 1.52511 1.78236 2.53166 + vertex 1.52391 1.77878 2.53478 + vertex 1.5239 1.7823 2.53547 + endloop + endfacet + facet normal -0.987136 0.0268294 -0.157614 + outer loop + vertex 1.52391 1.77878 2.53478 + vertex 1.5232 1.7776 2.53903 + vertex 1.5239 1.7823 2.53547 + endloop + endfacet + facet normal -0.984353 0.172692 0.0350331 + outer loop + vertex 1.5239 1.7823 2.53547 + vertex 1.5232 1.7776 2.53903 + vertex 1.52418 1.78286 2.54042 + endloop + endfacet + facet normal -0.960145 0.109904 0.256988 + outer loop + vertex 1.5232 1.7776 2.53903 + vertex 1.5248 1.7789 2.54446 + vertex 1.52418 1.78286 2.54042 + endloop + endfacet + facet normal -0.929534 0.180523 0.321524 + outer loop + vertex 1.52418 1.78286 2.54042 + vertex 1.5248 1.7789 2.54446 + vertex 1.52597 1.78461 2.54462 + endloop + endfacet + facet normal -0.662892 0.114651 0.739885 + outer loop + vertex 1.5248 1.7789 2.54446 + vertex 1.52838 1.78261 2.54709 + vertex 1.52597 1.78461 2.54462 + endloop + endfacet + facet normal -0.700482 0.18711 0.688705 + outer loop + vertex 1.52766 1.77708 2.54786 + vertex 1.52838 1.78261 2.54709 + vertex 1.5248 1.7789 2.54446 + endloop + endfacet + facet normal -0.157886 -0.00395517 -0.987449 + outer loop + vertex 1.53 1.785 2.52795 + vertex 1.52684 1.78577 2.52845 + vertex 1.53 1.79 2.52793 + endloop + endfacet + facet normal -0.27139 -0.915216 -0.297872 + outer loop + vertex 1.52775 1.785 2.53 + vertex 1.52684 1.78577 2.52845 + vertex 1.53 1.785 2.52795 + endloop + endfacet + facet normal 0.364912 -0.728144 -0.580212 + outer loop + vertex 1.52775 1.785 2.53 + vertex 1.52511 1.78236 2.53166 + vertex 1.52684 1.78577 2.52845 + endloop + endfacet + facet normal -0.849725 -0.0614822 -0.523628 + outer loop + vertex 1.52684 1.78577 2.52845 + vertex 1.52511 1.78236 2.53166 + vertex 1.52496 1.78623 2.53144 + endloop + endfacet + facet normal -0.951693 -0.0527461 -0.302486 + outer loop + vertex 1.52511 1.78236 2.53166 + vertex 1.5239 1.7823 2.53547 + vertex 1.52496 1.78623 2.53144 + endloop + endfacet + facet normal -0.98213 0.106782 -0.154976 + outer loop + vertex 1.52496 1.78623 2.53144 + vertex 1.5239 1.7823 2.53547 + vertex 1.52433 1.78703 2.53601 + endloop + endfacet + facet normal -0.995339 0.0849119 0.045714 + outer loop + vertex 1.5239 1.7823 2.53547 + vertex 1.52418 1.78286 2.54042 + vertex 1.52433 1.78703 2.53601 + endloop + endfacet + facet normal -0.987654 0.129496 0.0881454 + outer loop + vertex 1.52433 1.78703 2.53601 + vertex 1.52418 1.78286 2.54042 + vertex 1.52488 1.78796 2.54079 + endloop + endfacet + facet normal -0.929591 0.101774 0.354263 + outer loop + vertex 1.52418 1.78286 2.54042 + vertex 1.52597 1.78461 2.54462 + vertex 1.52488 1.78796 2.54079 + endloop + endfacet + facet normal -0.936094 0.0849057 0.341348 + outer loop + vertex 1.52488 1.78796 2.54079 + vertex 1.52597 1.78461 2.54462 + vertex 1.52642 1.78962 2.5446 + endloop + endfacet + facet normal -0.70136 0.0649335 0.709844 + outer loop + vertex 1.52597 1.78461 2.54462 + vertex 1.5286 1.78753 2.54695 + vertex 1.52642 1.78962 2.5446 + endloop + endfacet + facet normal -0.693636 0.0510863 0.718512 + outer loop + vertex 1.52838 1.78261 2.54709 + vertex 1.5286 1.78753 2.54695 + vertex 1.52597 1.78461 2.54462 + endloop + endfacet + facet normal -0.112124 0.0218383 -0.993454 + outer loop + vertex 1.53 1.79 2.52793 + vertex 1.52677 1.79011 2.5283 + vertex 1.53 1.795 2.52804 + endloop + endfacet + facet normal -0.113994 -0.0374821 -0.992774 + outer loop + vertex 1.52684 1.78577 2.52845 + vertex 1.52677 1.79011 2.5283 + vertex 1.53 1.79 2.52793 + endloop + endfacet + facet normal -0.848918 -0.0327384 -0.52751 + outer loop + vertex 1.52684 1.78577 2.52845 + vertex 1.52496 1.78623 2.53144 + vertex 1.52677 1.79011 2.5283 + endloop + endfacet + facet normal -0.891964 0.050646 -0.44926 + outer loop + vertex 1.52677 1.79011 2.5283 + vertex 1.52496 1.78623 2.53144 + vertex 1.52518 1.79118 2.53156 + endloop + endfacet + facet normal -0.988238 0.0472045 -0.145453 + outer loop + vertex 1.52496 1.78623 2.53144 + vertex 1.52433 1.78703 2.53601 + vertex 1.52518 1.79118 2.53156 + endloop + endfacet + facet normal -0.990238 0.0856363 -0.109981 + outer loop + vertex 1.52518 1.79118 2.53156 + vertex 1.52433 1.78703 2.53601 + vertex 1.52476 1.79215 2.53612 + endloop + endfacet + facet normal -0.991851 0.0814446 0.0979746 + outer loop + vertex 1.52433 1.78703 2.53601 + vertex 1.52488 1.78796 2.54079 + vertex 1.52476 1.79215 2.53612 + endloop + endfacet + facet normal -0.991795 0.0817699 0.098265 + outer loop + vertex 1.52476 1.79215 2.53612 + vertex 1.52488 1.78796 2.54079 + vertex 1.52529 1.79304 2.54072 + endloop + endfacet + facet normal -0.93583 0.0806444 0.3431 + outer loop + vertex 1.52488 1.78796 2.54079 + vertex 1.52642 1.78962 2.5446 + vertex 1.52529 1.79304 2.54072 + endloop + endfacet + facet normal -0.953283 0.027007 0.300868 + outer loop + vertex 1.52529 1.79304 2.54072 + vertex 1.52642 1.78962 2.5446 + vertex 1.52648 1.79438 2.54436 + endloop + endfacet + facet normal -0.748046 0.0424362 0.662288 + outer loop + vertex 1.52642 1.78962 2.5446 + vertex 1.52843 1.79215 2.54672 + vertex 1.52648 1.79438 2.54436 + endloop + endfacet + facet normal -0.728669 0.00819395 0.684818 + outer loop + vertex 1.5286 1.78753 2.54695 + vertex 1.52843 1.79215 2.54672 + vertex 1.52642 1.78962 2.5446 + endloop + endfacet + facet normal -0.145884 0.039547 -0.988511 + outer loop + vertex 1.53 1.795 2.52804 + vertex 1.52688 1.79527 2.52851 + vertex 1.53 1.8 2.52824 + endloop + endfacet + facet normal -0.145472 0.0441474 -0.988377 + outer loop + vertex 1.52677 1.79011 2.5283 + vertex 1.52688 1.79527 2.52851 + vertex 1.53 1.795 2.52804 + endloop + endfacet + facet normal -0.89397 0.0390596 -0.446421 + outer loop + vertex 1.52677 1.79011 2.5283 + vertex 1.52518 1.79118 2.53156 + vertex 1.52688 1.79527 2.52851 + endloop + endfacet + facet normal -0.901081 0.0540937 -0.430264 + outer loop + vertex 1.52688 1.79527 2.52851 + vertex 1.52518 1.79118 2.53156 + vertex 1.52544 1.79646 2.5317 + endloop + endfacet + facet normal -0.993436 0.050248 -0.102764 + outer loop + vertex 1.52518 1.79118 2.53156 + vertex 1.52476 1.79215 2.53612 + vertex 1.52544 1.79646 2.5317 + endloop + endfacet + facet normal -0.993957 0.0649919 -0.0884635 + outer loop + vertex 1.52544 1.79646 2.5317 + vertex 1.52476 1.79215 2.53612 + vertex 1.5251 1.79733 2.53614 + endloop + endfacet + facet normal -0.992727 0.0643515 0.101743 + outer loop + vertex 1.52476 1.79215 2.53612 + vertex 1.52529 1.79304 2.54072 + vertex 1.5251 1.79733 2.53614 + endloop + endfacet + facet normal -0.994933 0.0492119 0.087673 + outer loop + vertex 1.5251 1.79733 2.53614 + vertex 1.52529 1.79304 2.54072 + vertex 1.52553 1.79804 2.5406 + endloop + endfacet + facet normal -0.95495 0.0522818 0.292124 + outer loop + vertex 1.52529 1.79304 2.54072 + vertex 1.52648 1.79438 2.54436 + vertex 1.52553 1.79804 2.5406 + endloop + endfacet + facet normal -0.955797 0.0496757 0.289802 + outer loop + vertex 1.52553 1.79804 2.5406 + vertex 1.52648 1.79438 2.54436 + vertex 1.52664 1.7989 2.54413 + endloop + endfacet + facet normal -0.80336 0.0595092 0.592512 + outer loop + vertex 1.52648 1.79438 2.54436 + vertex 1.52797 1.796 2.54623 + vertex 1.52664 1.7989 2.54413 + endloop + endfacet + facet normal -0.774664 -0.0127087 0.632246 + outer loop + vertex 1.52843 1.79215 2.54672 + vertex 1.52797 1.796 2.54623 + vertex 1.52648 1.79438 2.54436 + endloop + endfacet + facet normal -0.199868 0.122516 -0.972133 + outer loop + vertex 1.53 1.8 2.52824 + vertex 1.52702 1.80057 2.52892 + vertex 1.53 1.805 2.52887 + endloop + endfacet + facet normal -0.208272 0.0813895 -0.974679 + outer loop + vertex 1.52688 1.79527 2.52851 + vertex 1.52702 1.80057 2.52892 + vertex 1.53 1.8 2.52824 + endloop + endfacet + facet normal -0.900627 0.0563816 -0.430919 + outer loop + vertex 1.52688 1.79527 2.52851 + vertex 1.52544 1.79646 2.5317 + vertex 1.52702 1.80057 2.52892 + endloop + endfacet + facet normal -0.907976 0.0713903 -0.412895 + outer loop + vertex 1.52702 1.80057 2.52892 + vertex 1.52544 1.79646 2.5317 + vertex 1.52568 1.80159 2.53205 + endloop + endfacet + facet normal -0.994877 0.0528562 -0.0861712 + outer loop + vertex 1.52544 1.79646 2.5317 + vertex 1.5251 1.79733 2.53614 + vertex 1.52568 1.80159 2.53205 + endloop + endfacet + facet normal -0.995037 0.0579472 -0.0808884 + outer loop + vertex 1.52568 1.80159 2.53205 + vertex 1.5251 1.79733 2.53614 + vertex 1.52537 1.80223 2.53631 + endloop + endfacet + facet normal -0.994829 0.0520602 0.0872098 + outer loop + vertex 1.5251 1.79733 2.53614 + vertex 1.52553 1.79804 2.5406 + vertex 1.52537 1.80223 2.53631 + endloop + endfacet + facet normal -0.989666 0.0828128 0.117063 + outer loop + vertex 1.52537 1.80223 2.53631 + vertex 1.52553 1.79804 2.5406 + vertex 1.52594 1.80299 2.5406 + endloop + endfacet + facet normal -0.955936 0.0798679 0.282503 + outer loop + vertex 1.52553 1.79804 2.5406 + vertex 1.52664 1.7989 2.54413 + vertex 1.52594 1.80299 2.5406 + endloop + endfacet + facet normal -0.896486 0.191242 0.399673 + outer loop + vertex 1.52594 1.80299 2.5406 + vertex 1.52664 1.7989 2.54413 + vertex 1.52754 1.80331 2.54403 + endloop + endfacet + facet normal -0.727076 0.162847 0.666965 + outer loop + vertex 1.52664 1.7989 2.54413 + vertex 1.52858 1.79945 2.54611 + vertex 1.52754 1.80331 2.54403 + endloop + endfacet + facet normal -0.726808 0.150886 0.670062 + outer loop + vertex 1.52797 1.796 2.54623 + vertex 1.52858 1.79945 2.54611 + vertex 1.52664 1.7989 2.54413 + endloop + endfacet + facet normal -0.245654 0.0772687 -0.966273 + outer loop + vertex 1.53 1.805 2.52887 + vertex 1.52735 1.80627 2.52965 + vertex 1.53 1.81 2.52927 + endloop + endfacet + facet normal -0.218044 0.13481 -0.966583 + outer loop + vertex 1.52702 1.80057 2.52892 + vertex 1.52735 1.80627 2.52965 + vertex 1.53 1.805 2.52887 + endloop + endfacet + facet normal -0.900828 0.105869 -0.42107 + outer loop + vertex 1.52702 1.80057 2.52892 + vertex 1.52568 1.80159 2.53205 + vertex 1.52735 1.80627 2.52965 + endloop + endfacet + facet normal -0.909171 0.120349 -0.398654 + outer loop + vertex 1.52735 1.80627 2.52965 + vertex 1.52568 1.80159 2.53205 + vertex 1.52586 1.80563 2.53284 + endloop + endfacet + facet normal -0.994735 0.0621336 -0.0815025 + outer loop + vertex 1.52568 1.80159 2.53205 + vertex 1.52537 1.80223 2.53631 + vertex 1.52586 1.80563 2.53284 + endloop + endfacet + facet normal -0.993855 0.10252 -0.041731 + outer loop + vertex 1.52586 1.80563 2.53284 + vertex 1.52537 1.80223 2.53631 + vertex 1.52586 1.80704 2.53644 + endloop + endfacet + facet normal -0.988628 0.0977056 0.114316 + outer loop + vertex 1.52537 1.80223 2.53631 + vertex 1.52594 1.80299 2.5406 + vertex 1.52586 1.80704 2.53644 + endloop + endfacet + facet normal -0.965745 0.176332 0.190379 + outer loop + vertex 1.52586 1.80704 2.53644 + vertex 1.52594 1.80299 2.5406 + vertex 1.52702 1.80858 2.54089 + endloop + endfacet + facet normal -0.519231 0.302348 0.799366 + outer loop + vertex 1.5302 1.80748 2.54419 + vertex 1.52754 1.80331 2.54403 + vertex 1.52976 1.8028 2.54567 + endloop + endfacet + facet normal -0.606784 0.361697 0.707805 + outer loop + vertex 1.5302 1.80748 2.54419 + vertex 1.52702 1.80858 2.54089 + vertex 1.52754 1.80331 2.54403 + endloop + endfacet + facet normal -0.901231 0.152762 0.405519 + outer loop + vertex 1.52702 1.80858 2.54089 + vertex 1.52594 1.80299 2.5406 + vertex 1.52754 1.80331 2.54403 + endloop + endfacet + facet normal -0.523281 0.290407 0.801149 + outer loop + vertex 1.52976 1.8028 2.54567 + vertex 1.52754 1.80331 2.54403 + vertex 1.52858 1.79945 2.54611 + endloop + endfacet + facet normal -0.410507 0.202212 -0.889153 + outer loop + vertex 1.53 1.81 2.52927 + vertex 1.52735 1.80627 2.52965 + vertex 1.53 1.81321 2.53 + endloop + endfacet + facet normal -0.142276 -0.471846 -0.870126 + outer loop + vertex 1.53 1.81321 2.53 + vertex 1.52678 1.8104 2.53205 + vertex 1.52813 1.81462 2.52954 + endloop + endfacet + facet normal -0.682526 0.294794 -0.668771 + outer loop + vertex 1.53 1.81321 2.53 + vertex 1.52735 1.80627 2.52965 + vertex 1.52678 1.8104 2.53205 + endloop + endfacet + facet normal -0.909566 0.107476 -0.40142 + outer loop + vertex 1.52735 1.80627 2.52965 + vertex 1.52586 1.80563 2.53284 + vertex 1.52678 1.8104 2.53205 + endloop + endfacet + facet normal -0.981781 0.176411 -0.0706011 + outer loop + vertex 1.52586 1.80563 2.53284 + vertex 1.52586 1.80704 2.53644 + vertex 1.52678 1.8104 2.53205 + endloop + endfacet + facet normal -0.986437 0.0970676 -0.132365 + outer loop + vertex 1.52678 1.8104 2.53205 + vertex 1.52586 1.80704 2.53644 + vertex 1.52632 1.81199 2.53666 + endloop + endfacet + facet normal -0.971027 0.0798727 0.225227 + outer loop + vertex 1.52586 1.80704 2.53644 + vertex 1.52702 1.80858 2.54089 + vertex 1.52632 1.81199 2.53666 + endloop + endfacet + facet normal -0.976699 0.0561924 0.207125 + outer loop + vertex 1.52632 1.81199 2.53666 + vertex 1.52702 1.80858 2.54089 + vertex 1.52717 1.81434 2.54007 + endloop + endfacet + facet normal -0.732344 0.116353 0.67092 + outer loop + vertex 1.52702 1.80858 2.54089 + vertex 1.52931 1.81297 2.54263 + vertex 1.52717 1.81434 2.54007 + endloop + endfacet + facet normal -0.701924 0.0861447 0.707023 + outer loop + vertex 1.5302 1.80748 2.54419 + vertex 1.52931 1.81297 2.54263 + vertex 1.52702 1.80858 2.54089 + endloop + endfacet + facet normal -0.950743 -0.035083 -0.307988 + outer loop + vertex 1.52813 1.81462 2.52954 + vertex 1.52685 1.81559 2.5334 + vertex 1.52779 1.81803 2.53021 + endloop + endfacet + facet normal -0.936178 0.100185 -0.336947 + outer loop + vertex 1.52678 1.8104 2.53205 + vertex 1.52685 1.81559 2.5334 + vertex 1.52813 1.81462 2.52954 + endloop + endfacet + facet normal -0.992499 0.0431625 -0.114382 + outer loop + vertex 1.52678 1.8104 2.53205 + vertex 1.52632 1.81199 2.53666 + vertex 1.52685 1.81559 2.5334 + endloop + endfacet + facet normal -0.994042 0.0812051 -0.0727013 + outer loop + vertex 1.52685 1.81559 2.5334 + vertex 1.52632 1.81199 2.53666 + vertex 1.5266 1.81602 2.53735 + endloop + endfacet + facet normal -0.973856 0.0287287 0.225344 + outer loop + vertex 1.52632 1.81199 2.53666 + vertex 1.52717 1.81434 2.54007 + vertex 1.5266 1.81602 2.53735 + endloop + endfacet + facet normal -0.965742 0.0708233 0.249654 + outer loop + vertex 1.5266 1.81602 2.53735 + vertex 1.52717 1.81434 2.54007 + vertex 1.52738 1.81853 2.53966 + endloop + endfacet + facet normal -0.781996 0.0971573 0.615665 + outer loop + vertex 1.52717 1.81434 2.54007 + vertex 1.52898 1.81762 2.54184 + vertex 1.52738 1.81853 2.53966 + endloop + endfacet + facet normal -0.752038 0.058606 0.656509 + outer loop + vertex 1.52931 1.81297 2.54263 + vertex 1.52898 1.81762 2.54184 + vertex 1.52717 1.81434 2.54007 + endloop + endfacet + facet normal -0.972726 0.105379 -0.20664 + outer loop + vertex 1.52779 1.81803 2.53021 + vertex 1.52685 1.81559 2.5334 + vertex 1.52738 1.81956 2.53291 + endloop + endfacet + facet normal -0.98092 0.181203 -0.0704395 + outer loop + vertex 1.52738 1.81956 2.53291 + vertex 1.52713 1.81961 2.53654 + vertex 1.52781 1.82247 2.53446 + endloop + endfacet + facet normal -0.989755 0.124314 -0.0702267 + outer loop + vertex 1.52738 1.81956 2.53291 + vertex 1.52685 1.81559 2.5334 + vertex 1.52713 1.81961 2.53654 + endloop + endfacet + facet normal -0.988453 0.130081 -0.0777188 + outer loop + vertex 1.52685 1.81559 2.5334 + vertex 1.5266 1.81602 2.53735 + vertex 1.52713 1.81961 2.53654 + endloop + endfacet + facet normal -0.974561 0.176474 0.13816 + outer loop + vertex 1.5266 1.81602 2.53735 + vertex 1.52738 1.81853 2.53966 + vertex 1.52713 1.81961 2.53654 + endloop + endfacet + facet normal -0.978744 0.157141 0.131783 + outer loop + vertex 1.52713 1.81961 2.53654 + vertex 1.52738 1.81853 2.53966 + vertex 1.52782 1.82154 2.53935 + endloop + endfacet + facet normal -0.800362 0.176216 0.573035 + outer loop + vertex 1.52738 1.81853 2.53966 + vertex 1.52905 1.82128 2.54115 + vertex 1.52782 1.82154 2.53935 + endloop + endfacet + facet normal -0.771484 0.131958 0.622414 + outer loop + vertex 1.52898 1.81762 2.54184 + vertex 1.52905 1.82128 2.54115 + vertex 1.52738 1.81853 2.53966 + endloop + endfacet + facet normal -0.964228 0.26119 0.0452074 + outer loop + vertex 1.52781 1.82247 2.53446 + vertex 1.52713 1.81961 2.53654 + vertex 1.52829 1.82371 2.53763 + endloop + endfacet + facet normal -0.854491 0.424574 0.299301 + outer loop + vertex 1.52829 1.82371 2.53763 + vertex 1.52782 1.82154 2.53935 + vertex 1.52922 1.82383 2.54009 + endloop + endfacet + facet normal -0.964452 0.257508 0.0593399 + outer loop + vertex 1.52713 1.81961 2.53654 + vertex 1.52782 1.82154 2.53935 + vertex 1.52829 1.82371 2.53763 + endloop + endfacet + facet normal -0.770698 0.287619 0.568595 + outer loop + vertex 1.52922 1.82383 2.54009 + vertex 1.52782 1.82154 2.53935 + vertex 1.52905 1.82128 2.54115 + endloop + endfacet + facet normal -0.463887 -0.851958 0.242851 + outer loop + vertex 1.52972 2.00627 2.49609 + vertex 1.52719 2.00814 2.4978 + vertex 1.52677 2.00742 2.49448 + endloop + endfacet + facet normal -0.53891 -0.834706 0.113323 + outer loop + vertex 1.52916 2.00707 2.49929 + vertex 1.52719 2.00814 2.4978 + vertex 1.52972 2.00627 2.49609 + endloop + endfacet + facet normal -0.669204 -0.573353 0.472686 + outer loop + vertex 1.52853 2.00849 2.50011 + vertex 1.52719 2.00814 2.4978 + vertex 1.52916 2.00707 2.49929 + endloop + endfacet + facet normal -0.630665 -0.580742 0.514783 + outer loop + vertex 1.52916 2.00707 2.49929 + vertex 1.52995 2.00745 2.50069 + vertex 1.52853 2.00849 2.50011 + endloop + endfacet + facet normal -0.0988404 -0.34087 -0.9349 + outer loop + vertex 1.53 2.01079 2.49 + vertex 1.52613 2.00872 2.49116 + vertex 1.525 2.01224 2.49 + endloop + endfacet + facet normal -0.0408804 -0.325412 -0.944688 + outer loop + vertex 1.52613 2.00872 2.49116 + vertex 1.52208 2.00993 2.49092 + vertex 1.525 2.01224 2.49 + endloop + endfacet + facet normal -0.423345 -0.872989 0.242217 + outer loop + vertex 1.52677 2.00742 2.49448 + vertex 1.52719 2.00814 2.4978 + vertex 1.52312 2.00939 2.49519 + endloop + endfacet + facet normal -0.496293 -0.836358 -0.232805 + outer loop + vertex 1.52677 2.00742 2.49448 + vertex 1.52312 2.00939 2.49519 + vertex 1.52613 2.00872 2.49116 + endloop + endfacet + facet normal -0.283046 -0.957623 -0.0533223 + outer loop + vertex 1.52613 2.00872 2.49116 + vertex 1.52312 2.00939 2.49519 + vertex 1.52208 2.00993 2.49092 + endloop + endfacet + facet normal 0.0989938 -0.885133 0.454686 + outer loop + vertex 1.52078 2.01133 2.49948 + vertex 1.52312 2.00939 2.49519 + vertex 1.52669 2.01208 2.49966 + endloop + endfacet + facet normal 0.105133 -0.916865 0.385105 + outer loop + vertex 1.52078 2.01133 2.49948 + vertex 1.52669 2.01208 2.49966 + vertex 1.52303 2.01212 2.50075 + endloop + endfacet + facet normal -0.577975 -0.407632 0.706952 + outer loop + vertex 1.52312 2.00939 2.49519 + vertex 1.52719 2.00814 2.4978 + vertex 1.52669 2.01208 2.49966 + endloop + endfacet + facet normal -0.364416 -0.0701226 0.928592 + outer loop + vertex 1.5303 2.00907 2.50085 + vertex 1.52669 2.01208 2.49966 + vertex 1.52853 2.00849 2.50011 + endloop + endfacet + facet normal -0.791063 -0.340842 0.507982 + outer loop + vertex 1.52719 2.00814 2.4978 + vertex 1.52853 2.00849 2.50011 + vertex 1.52669 2.01208 2.49966 + endloop + endfacet + facet normal -0.382466 -0.00957647 0.92392 + outer loop + vertex 1.52853 2.00849 2.50011 + vertex 1.52995 2.00745 2.50069 + vertex 1.5303 2.00907 2.50085 + endloop + endfacet + facet normal -0.0961117 -0.75789 0.645264 + outer loop + vertex 1.52078 2.01133 2.49948 + vertex 1.52303 2.01212 2.50075 + vertex 1.52092 2.01275 2.50117 + endloop + endfacet + facet normal 0.16581 0.433799 0.885622 + outer loop + vertex 1.52315 2.10819 2.47074 + vertex 1.52555 2.10578 2.47147 + vertex 1.52723 2.10877 2.46969 + endloop + endfacet + facet normal 0.149361 0.495551 0.855641 + outer loop + vertex 1.52315 2.10819 2.47074 + vertex 1.52723 2.10877 2.46969 + vertex 1.5219 2.11199 2.46876 + endloop + endfacet + facet normal 0.170077 0.523719 0.834741 + outer loop + vertex 1.5219 2.11199 2.46876 + vertex 1.52723 2.10877 2.46969 + vertex 1.52675 2.1121 2.4677 + endloop + endfacet + facet normal 0.123575 0.398745 0.908698 + outer loop + vertex 1.52555 2.10578 2.47147 + vertex 1.52315 2.10819 2.47074 + vertex 1.52145 2.10499 2.47237 + endloop + endfacet + facet normal 0.202438 0.743916 0.636874 + outer loop + vertex 1.52443 2.11446 2.46632 + vertex 1.52867 2.11396 2.46557 + vertex 1.52603 2.11623 2.46374 + endloop + endfacet + facet normal 0.234305 0.727181 0.64522 + outer loop + vertex 1.52265 2.11641 2.46477 + vertex 1.52443 2.11446 2.46632 + vertex 1.52603 2.11623 2.46374 + endloop + endfacet + facet normal 0.155908 0.607714 0.778701 + outer loop + vertex 1.52675 2.1121 2.4677 + vertex 1.52443 2.11446 2.46632 + vertex 1.5219 2.11199 2.46876 + endloop + endfacet + facet normal 0.208359 0.637687 0.74158 + outer loop + vertex 1.52867 2.11396 2.46557 + vertex 1.52443 2.11446 2.46632 + vertex 1.52675 2.1121 2.4677 + endloop + endfacet + facet normal 0.13903 0.277509 0.95061 + outer loop + vertex 1.52994 2.125 2.455 + vertex 1.52397 2.1211 2.45701 + vertex 1.53 2.12497 2.455 + endloop + endfacet + facet normal 0.0838499 0.353696 0.931594 + outer loop + vertex 1.53 2.12497 2.455 + vertex 1.52397 2.1211 2.45701 + vertex 1.52901 2.11988 2.45702 + endloop + endfacet + facet normal 0.195107 0.809763 0.553369 + outer loop + vertex 1.52901 2.11988 2.45702 + vertex 1.52397 2.1211 2.45701 + vertex 1.5274 2.11804 2.46028 + endloop + endfacet + facet normal 0.223658 0.817535 0.530673 + outer loop + vertex 1.5274 2.11804 2.46028 + vertex 1.52397 2.1211 2.45701 + vertex 1.52295 2.11815 2.46199 + endloop + endfacet + facet normal 0.205556 0.819841 0.534423 + outer loop + vertex 1.52603 2.11623 2.46374 + vertex 1.52295 2.11815 2.46199 + vertex 1.52265 2.11641 2.46477 + endloop + endfacet + facet normal 0.219074 0.826725 0.5182 + outer loop + vertex 1.5274 2.11804 2.46028 + vertex 1.52295 2.11815 2.46199 + vertex 1.52603 2.11623 2.46374 + endloop + endfacet + facet normal -0.0732998 0.991182 -0.110389 + outer loop + vertex 1.53 2.125 2.45496 + vertex 1.52387 2.12426 2.45238 + vertex 1.52994 2.125 2.455 + endloop + endfacet + facet normal -0.256701 0.900092 0.35205 + outer loop + vertex 1.53 2.125 2.45496 + vertex 1.53 2.12694 2.45 + vertex 1.52387 2.12426 2.45238 + endloop + endfacet + facet normal 0.0323019 0.621485 0.78276 + outer loop + vertex 1.53 2.12694 2.45 + vertex 1.525 2.1272 2.45 + vertex 1.52387 2.12426 2.45238 + endloop + endfacet + facet normal -0.326478 0.777617 0.53733 + outer loop + vertex 1.52994 2.125 2.455 + vertex 1.52387 2.12426 2.45238 + vertex 1.52397 2.1211 2.45701 + endloop + endfacet + facet normal 0.0238191 -0.123928 0.992005 + outer loop + vertex 1.535 0.908409 2.45 + vertex 1.53189 0.90807 2.45003 + vertex 1.53 0.907448 2.45 + endloop + endfacet + facet normal 0.204956 -0.661875 0.721051 + outer loop + vertex 1.53189 0.90807 2.45003 + vertex 1.52677 0.907575 2.45104 + vertex 1.53 0.907448 2.45 + endloop + endfacet + facet normal 0.153337 -0.933782 0.323325 + outer loop + vertex 1.53189 0.90807 2.45003 + vertex 1.52911 0.90874 2.45329 + vertex 1.52677 0.907575 2.45104 + endloop + endfacet + facet normal 0.150315 -0.935073 0.321004 + outer loop + vertex 1.53298 0.909062 2.45241 + vertex 1.52911 0.90874 2.45329 + vertex 1.53189 0.90807 2.45003 + endloop + endfacet + facet normal 0.172584 -0.881553 0.439408 + outer loop + vertex 1.52911 0.90874 2.45329 + vertex 1.53298 0.909062 2.45241 + vertex 1.53187 0.910972 2.45668 + endloop + endfacet + facet normal 0.214687 -0.887009 0.408809 + outer loop + vertex 1.52693 0.909755 2.45664 + vertex 1.52911 0.90874 2.45329 + vertex 1.53187 0.910972 2.45668 + endloop + endfacet + facet normal 0.128433 -0.818006 0.560688 + outer loop + vertex 1.53105 0.914249 2.46165 + vertex 1.53187 0.910972 2.45668 + vertex 1.5348 0.913445 2.45962 + endloop + endfacet + facet normal 0.227522 -0.795309 0.561887 + outer loop + vertex 1.53105 0.914249 2.46165 + vertex 1.52638 0.912015 2.46038 + vertex 1.53187 0.910972 2.45668 + endloop + endfacet + facet normal 0.198493 -0.826049 0.527487 + outer loop + vertex 1.52638 0.912015 2.46038 + vertex 1.52693 0.909755 2.45664 + vertex 1.53187 0.910972 2.45668 + endloop + endfacet + facet normal 0.188353 -0.752583 0.630985 + outer loop + vertex 1.53105 0.914249 2.46165 + vertex 1.52722 0.91472 2.46336 + vertex 1.52638 0.912015 2.46038 + endloop + endfacet + facet normal 0.160933 -0.779473 0.605411 + outer loop + vertex 1.5348 0.913445 2.45962 + vertex 1.53403 0.91503 2.46187 + vertex 1.53105 0.914249 2.46165 + endloop + endfacet + facet normal 0.179297 -0.666717 0.723423 + outer loop + vertex 1.52722 0.91472 2.46336 + vertex 1.52976 0.917044 2.46487 + vertex 1.52569 0.91681 2.46566 + endloop + endfacet + facet normal 0.221666 -0.690336 0.688694 + outer loop + vertex 1.53105 0.914249 2.46165 + vertex 1.52976 0.917044 2.46487 + vertex 1.52722 0.91472 2.46336 + endloop + endfacet + facet normal 0.16243 -0.711734 0.683412 + outer loop + vertex 1.53105 0.914249 2.46165 + vertex 1.53402 0.917159 2.46398 + vertex 1.52976 0.917044 2.46487 + endloop + endfacet + facet normal 0.132227 -0.697548 0.704232 + outer loop + vertex 1.53105 0.914249 2.46165 + vertex 1.53403 0.91503 2.46187 + vertex 1.53402 0.917159 2.46398 + endloop + endfacet + facet normal 0.186771 -0.592519 0.783606 + outer loop + vertex 1.52976 0.917044 2.46487 + vertex 1.52883 0.919955 2.46729 + vertex 1.52569 0.91681 2.46566 + endloop + endfacet + facet normal 0.176087 -0.626125 0.759579 + outer loop + vertex 1.53402 0.917159 2.46398 + vertex 1.53236 0.919594 2.46637 + vertex 1.52976 0.917044 2.46487 + endloop + endfacet + facet normal 0.142852 -0.605792 0.782694 + outer loop + vertex 1.53236 0.919594 2.46637 + vertex 1.52883 0.919955 2.46729 + vertex 1.52976 0.917044 2.46487 + endloop + endfacet + facet normal 0.162045 -0.535711 0.828707 + outer loop + vertex 1.53236 0.919594 2.46637 + vertex 1.53349 0.923157 2.46845 + vertex 1.52883 0.919955 2.46729 + endloop + endfacet + facet normal 0.129734 -0.498911 0.856888 + outer loop + vertex 1.53349 0.923157 2.46845 + vertex 1.52812 0.923674 2.46957 + vertex 1.52883 0.919955 2.46729 + endloop + endfacet + facet normal 0.121797 -0.426444 0.896276 + outer loop + vertex 1.5296 0.927293 2.47109 + vertex 1.52576 0.926439 2.4712 + vertex 1.52812 0.923674 2.46957 + endloop + endfacet + facet normal 0.115413 -0.424562 0.898013 + outer loop + vertex 1.5296 0.927293 2.47109 + vertex 1.52812 0.923674 2.46957 + vertex 1.53279 0.92687 2.47048 + endloop + endfacet + facet normal 0.138903 -0.453854 0.880183 + outer loop + vertex 1.53279 0.92687 2.47048 + vertex 1.52812 0.923674 2.46957 + vertex 1.53349 0.923157 2.46845 + endloop + endfacet + facet normal 0.112001 -0.379372 0.91844 + outer loop + vertex 1.5296 0.927293 2.47109 + vertex 1.52897 0.929969 2.47227 + vertex 1.52576 0.926439 2.4712 + endloop + endfacet + facet normal 0.121846 -0.394417 0.910818 + outer loop + vertex 1.53279 0.92687 2.47048 + vertex 1.53221 0.929566 2.47172 + vertex 1.5296 0.927293 2.47109 + endloop + endfacet + facet normal 0.107748 -0.380402 0.918523 + outer loop + vertex 1.53221 0.929566 2.47172 + vertex 1.52897 0.929969 2.47227 + vertex 1.5296 0.927293 2.47109 + endloop + endfacet + facet normal 0.111344 -0.361346 0.92576 + outer loop + vertex 1.53221 0.929566 2.47172 + vertex 1.53353 0.933401 2.47306 + vertex 1.52897 0.929969 2.47227 + endloop + endfacet + facet normal -0.465418 0.260181 0.845986 + outer loop + vertex 1.53141 1.01718 2.50028 + vertex 1.53092 1.01814 2.49972 + vertex 1.52749 1.01619 2.49843 + endloop + endfacet + facet normal -0.353084 -0.272413 0.895055 + outer loop + vertex 1.53141 1.01718 2.50028 + vertex 1.52749 1.01619 2.49843 + vertex 1.53181 1.01436 2.49958 + endloop + endfacet + facet normal -0.162823 0.218507 0.962155 + outer loop + vertex 1.53181 1.01436 2.49958 + vertex 1.52749 1.01619 2.49843 + vertex 1.52642 1.01221 2.49915 + endloop + endfacet + facet normal -0.500679 0.234594 0.833238 + outer loop + vertex 1.53141 1.01718 2.50028 + vertex 1.53228 1.01826 2.5005 + vertex 1.53092 1.01814 2.49972 + endloop + endfacet + facet normal -0.390266 0.911868 0.127238 + outer loop + vertex 1.535 1.02357 2.485 + vertex 1.53 1.02143 2.485 + vertex 1.53231 1.02217 2.48681 + endloop + endfacet + facet normal -0.400922 0.90477 0.143713 + outer loop + vertex 1.53231 1.02217 2.48681 + vertex 1.53 1.02143 2.485 + vertex 1.52931 1.02063 2.48814 + endloop + endfacet + facet normal -0.419396 0.902367 0.0991971 + outer loop + vertex 1.53231 1.02217 2.48681 + vertex 1.52931 1.02063 2.48814 + vertex 1.53174 1.0214 2.49141 + endloop + endfacet + facet normal -0.421487 0.901189 0.10103 + outer loop + vertex 1.53174 1.0214 2.49141 + vertex 1.52931 1.02063 2.48814 + vertex 1.52814 1.01962 2.49227 + endloop + endfacet + facet normal -0.377763 0.889248 0.257942 + outer loop + vertex 1.53174 1.0214 2.49141 + vertex 1.52814 1.01962 2.49227 + vertex 1.53215 1.02019 2.49617 + endloop + endfacet + facet normal -0.386719 0.882343 0.268177 + outer loop + vertex 1.53215 1.02019 2.49617 + vertex 1.52814 1.01962 2.49227 + vertex 1.52952 1.01874 2.49715 + endloop + endfacet + facet normal -0.563526 0.682387 0.465602 + outer loop + vertex 1.53092 1.01814 2.49972 + vertex 1.52952 1.01874 2.49715 + vertex 1.52749 1.01619 2.49843 + endloop + endfacet + facet normal -0.345863 0.854642 0.387254 + outer loop + vertex 1.53092 1.01814 2.49972 + vertex 1.53252 1.01894 2.49939 + vertex 1.52952 1.01874 2.49715 + endloop + endfacet + facet normal -0.336904 0.863876 0.374452 + outer loop + vertex 1.53252 1.01894 2.49939 + vertex 1.53215 1.02019 2.49617 + vertex 1.52952 1.01874 2.49715 + endloop + endfacet + facet normal -0.326444 0.836924 0.439309 + outer loop + vertex 1.53252 1.01894 2.49939 + vertex 1.53092 1.01814 2.49972 + vertex 1.53228 1.01826 2.5005 + endloop + endfacet + facet normal -0.800763 -0.239614 -0.548966 + outer loop + vertex 1.53309 1.16215 2.52106 + vertex 1.53201 1.16419 2.52175 + vertex 1.53326 1.16501 2.51957 + endloop + endfacet + facet normal -0.882891 -0.370388 -0.288645 + outer loop + vertex 1.53241 1.16109 2.52449 + vertex 1.53201 1.16419 2.52175 + vertex 1.53309 1.16215 2.52106 + endloop + endfacet + facet normal -0.986004 -0.162349 -0.0379229 + outer loop + vertex 1.53168 1.16522 2.52591 + vertex 1.53201 1.16419 2.52175 + vertex 1.53241 1.16109 2.52449 + endloop + endfacet + facet normal -0.979975 -0.192208 0.0520112 + outer loop + vertex 1.53241 1.16109 2.52449 + vertex 1.53246 1.16181 2.52807 + vertex 1.53168 1.16522 2.52591 + endloop + endfacet + facet normal 0.291095 -0.157508 -0.943639 + outer loop + vertex 1.535 1.16976 2.52 + vertex 1.53257 1.16737 2.51965 + vertex 1.535 1.17 2.51996 + endloop + endfacet + facet normal 0.0861246 0.0582816 -0.994578 + outer loop + vertex 1.53326 1.16501 2.51957 + vertex 1.53257 1.16737 2.51965 + vertex 1.535 1.16976 2.52 + endloop + endfacet + facet normal -0.809255 -0.217683 -0.545637 + outer loop + vertex 1.53326 1.16501 2.51957 + vertex 1.53201 1.16419 2.52175 + vertex 1.53257 1.16737 2.51965 + endloop + endfacet + facet normal -0.896997 -0.122199 -0.42481 + outer loop + vertex 1.53201 1.16419 2.52175 + vertex 1.5314 1.16797 2.52194 + vertex 1.53257 1.16737 2.51965 + endloop + endfacet + facet normal -0.986899 -0.156442 -0.0394482 + outer loop + vertex 1.53201 1.16419 2.52175 + vertex 1.53168 1.16522 2.52591 + vertex 1.5314 1.16797 2.52194 + endloop + endfacet + facet normal -0.991874 -0.125951 -0.0179679 + outer loop + vertex 1.5314 1.16797 2.52194 + vertex 1.53168 1.16522 2.52591 + vertex 1.53113 1.16966 2.52495 + endloop + endfacet + facet normal -0.974681 -0.0962262 0.201833 + outer loop + vertex 1.53254 1.16479 2.52989 + vertex 1.53168 1.16522 2.52591 + vertex 1.53246 1.16181 2.52807 + endloop + endfacet + facet normal -0.972789 -0.118673 0.198994 + outer loop + vertex 1.53254 1.16479 2.52989 + vertex 1.5319 1.16988 2.52979 + vertex 1.53168 1.16522 2.52591 + endloop + endfacet + facet normal -0.983245 -0.0861976 0.160619 + outer loop + vertex 1.5319 1.16988 2.52979 + vertex 1.53113 1.16966 2.52495 + vertex 1.53168 1.16522 2.52591 + endloop + endfacet + facet normal -0.810109 -0.0914114 0.579109 + outer loop + vertex 1.53254 1.16479 2.52989 + vertex 1.53456 1.16705 2.53307 + vertex 1.5319 1.16988 2.52979 + endloop + endfacet + facet normal 0.0884055 -0.161189 -0.982956 + outer loop + vertex 1.535 1.17 2.51996 + vertex 1.5322 1.17109 2.51953 + vertex 1.535 1.175 2.51914 + endloop + endfacet + facet normal 0.145379 -0.0175312 -0.989221 + outer loop + vertex 1.53257 1.16737 2.51965 + vertex 1.5322 1.17109 2.51953 + vertex 1.535 1.17 2.51996 + endloop + endfacet + facet normal -0.896995 -0.102282 -0.430045 + outer loop + vertex 1.53257 1.16737 2.51965 + vertex 1.5314 1.16797 2.52194 + vertex 1.5322 1.17109 2.51953 + endloop + endfacet + facet normal -0.909561 -0.0816032 -0.407481 + outer loop + vertex 1.5322 1.17109 2.51953 + vertex 1.5314 1.16797 2.52194 + vertex 1.53106 1.1725 2.5218 + endloop + endfacet + facet normal -0.995977 -0.076956 -0.0459061 + outer loop + vertex 1.5314 1.16797 2.52194 + vertex 1.53113 1.16966 2.52495 + vertex 1.53106 1.1725 2.5218 + endloop + endfacet + facet normal -0.996621 -0.0712907 -0.0407893 + outer loop + vertex 1.53106 1.1725 2.5218 + vertex 1.53113 1.16966 2.52495 + vertex 1.53082 1.17371 2.52557 + endloop + endfacet + facet normal -0.981778 -0.100874 0.161046 + outer loop + vertex 1.53113 1.16966 2.52495 + vertex 1.5319 1.16988 2.52979 + vertex 1.53082 1.17371 2.52557 + endloop + endfacet + facet normal -0.979527 -0.181231 0.0876451 + outer loop + vertex 1.53082 1.17371 2.52557 + vertex 1.5319 1.16988 2.52979 + vertex 1.53091 1.17496 2.52922 + endloop + endfacet + facet normal -0.850282 -0.293643 0.436801 + outer loop + vertex 1.53368 1.17109 2.53406 + vertex 1.5319 1.16988 2.52979 + vertex 1.53456 1.16705 2.53307 + endloop + endfacet + facet normal -0.869082 -0.243696 0.430474 + outer loop + vertex 1.53368 1.17109 2.53406 + vertex 1.53224 1.175 2.53338 + vertex 1.5319 1.16988 2.52979 + endloop + endfacet + facet normal -0.941161 -0.149593 0.303048 + outer loop + vertex 1.53224 1.175 2.53338 + vertex 1.53091 1.17496 2.52922 + vertex 1.5319 1.16988 2.52979 + endloop + endfacet + facet normal -0.672939 -0.120227 0.729862 + outer loop + vertex 1.53368 1.17109 2.53406 + vertex 1.53521 1.17441 2.53601 + vertex 1.53224 1.175 2.53338 + endloop + endfacet + facet normal -0.0819845 -0.0478008 -0.995487 + outer loop + vertex 1.535 1.175 2.51914 + vertex 1.53211 1.17591 2.51933 + vertex 1.535 1.18 2.5189 + endloop + endfacet + facet normal -0.0801324 -0.0418286 -0.995906 + outer loop + vertex 1.5322 1.17109 2.51953 + vertex 1.53211 1.17591 2.51933 + vertex 1.535 1.175 2.51914 + endloop + endfacet + facet normal -0.901214 -0.0352424 -0.431939 + outer loop + vertex 1.5322 1.17109 2.51953 + vertex 1.53106 1.1725 2.5218 + vertex 1.53211 1.17591 2.51933 + endloop + endfacet + facet normal -0.915831 -0.00873065 -0.40147 + outer loop + vertex 1.53211 1.17591 2.51933 + vertex 1.53106 1.1725 2.5218 + vertex 1.53091 1.17722 2.52203 + endloop + endfacet + facet normal -0.998101 -0.027974 -0.0548848 + outer loop + vertex 1.53106 1.1725 2.5218 + vertex 1.53082 1.17371 2.52557 + vertex 1.53091 1.17722 2.52203 + endloop + endfacet + facet normal -0.990367 -0.0838903 -0.110163 + outer loop + vertex 1.53091 1.17722 2.52203 + vertex 1.53082 1.17371 2.52557 + vertex 1.5304 1.17815 2.52593 + endloop + endfacet + facet normal -0.993406 -0.097936 0.0596103 + outer loop + vertex 1.53082 1.17371 2.52557 + vertex 1.53091 1.17496 2.52922 + vertex 1.5304 1.17815 2.52593 + endloop + endfacet + facet normal -0.992866 -0.108614 0.0491874 + outer loop + vertex 1.5304 1.17815 2.52593 + vertex 1.53091 1.17496 2.52922 + vertex 1.53054 1.17885 2.53026 + endloop + endfacet + facet normal -0.937869 -0.170533 0.302193 + outer loop + vertex 1.53091 1.17496 2.52922 + vertex 1.53224 1.175 2.53338 + vertex 1.53054 1.17885 2.53026 + endloop + endfacet + facet normal -0.937461 -0.168335 0.304679 + outer loop + vertex 1.53054 1.17885 2.53026 + vertex 1.53224 1.175 2.53338 + vertex 1.53161 1.18025 2.53432 + endloop + endfacet + facet normal -0.676646 -0.208065 0.7063 + outer loop + vertex 1.53224 1.175 2.53338 + vertex 1.53443 1.1785 2.5365 + vertex 1.53161 1.18025 2.53432 + endloop + endfacet + facet normal -0.672645 -0.212733 0.708726 + outer loop + vertex 1.53521 1.17441 2.53601 + vertex 1.53443 1.1785 2.5365 + vertex 1.53224 1.175 2.53338 + endloop + endfacet + facet normal -0.198952 0.152967 -0.967998 + outer loop + vertex 1.535 1.18 2.5189 + vertex 1.53236 1.18128 2.51964 + vertex 1.535 1.185 2.51969 + endloop + endfacet + facet normal -0.240413 0.0671914 -0.968342 + outer loop + vertex 1.53211 1.17591 2.51933 + vertex 1.53236 1.18128 2.51964 + vertex 1.535 1.18 2.5189 + endloop + endfacet + facet normal -0.899859 0.0666984 -0.431052 + outer loop + vertex 1.53211 1.17591 2.51933 + vertex 1.53091 1.17722 2.52203 + vertex 1.53236 1.18128 2.51964 + endloop + endfacet + facet normal -0.880362 0.0350745 -0.473004 + outer loop + vertex 1.53236 1.18128 2.51964 + vertex 1.53091 1.17722 2.52203 + vertex 1.53073 1.18114 2.52265 + endloop + endfacet + facet normal -0.991911 -0.0256391 -0.12432 + outer loop + vertex 1.53091 1.17722 2.52203 + vertex 1.5304 1.17815 2.52593 + vertex 1.53073 1.18114 2.52265 + endloop + endfacet + facet normal -0.989377 -0.0421658 -0.139123 + outer loop + vertex 1.53073 1.18114 2.52265 + vertex 1.5304 1.17815 2.52593 + vertex 1.53018 1.18246 2.52619 + endloop + endfacet + facet normal -0.997735 -0.0536854 0.0405235 + outer loop + vertex 1.5304 1.17815 2.52593 + vertex 1.53054 1.17885 2.53026 + vertex 1.53018 1.18246 2.52619 + endloop + endfacet + facet normal -0.993907 -0.109798 -0.00963691 + outer loop + vertex 1.53018 1.18246 2.52619 + vertex 1.53054 1.17885 2.53026 + vertex 1.53002 1.18346 2.5308 + endloop + endfacet + facet normal -0.944608 -0.140051 0.296819 + outer loop + vertex 1.53054 1.17885 2.53026 + vertex 1.53161 1.18025 2.53432 + vertex 1.53002 1.18346 2.5308 + endloop + endfacet + facet normal -0.944258 -0.137223 0.299242 + outer loop + vertex 1.53002 1.18346 2.5308 + vertex 1.53161 1.18025 2.53432 + vertex 1.53108 1.18519 2.53491 + endloop + endfacet + facet normal -0.667946 -0.159407 0.726937 + outer loop + vertex 1.53161 1.18025 2.53432 + vertex 1.53393 1.18326 2.53711 + vertex 1.53108 1.18519 2.53491 + endloop + endfacet + facet normal -0.66558 -0.16259 0.728401 + outer loop + vertex 1.53443 1.1785 2.5365 + vertex 1.53393 1.18326 2.53711 + vertex 1.53161 1.18025 2.53432 + endloop + endfacet + facet normal -0.701266 0.503999 -0.504193 + outer loop + vertex 1.535 1.185 2.51969 + vertex 1.53236 1.18128 2.51964 + vertex 1.535 1.18531 2.52 + endloop + endfacet + facet normal -0.452674 -0.0907811 -0.887043 + outer loop + vertex 1.535 1.18531 2.52 + vertex 1.53152 1.18558 2.52175 + vertex 1.53404 1.19009 2.52 + endloop + endfacet + facet normal -0.401635 0.338132 -0.851091 + outer loop + vertex 1.535 1.18531 2.52 + vertex 1.53236 1.18128 2.51964 + vertex 1.53152 1.18558 2.52175 + endloop + endfacet + facet normal -0.879807 0.0597704 -0.471558 + outer loop + vertex 1.53236 1.18128 2.51964 + vertex 1.53073 1.18114 2.52265 + vertex 1.53152 1.18558 2.52175 + endloop + endfacet + facet normal -0.970764 0.131073 -0.201091 + outer loop + vertex 1.53073 1.18114 2.52265 + vertex 1.53018 1.18246 2.52619 + vertex 1.53152 1.18558 2.52175 + endloop + endfacet + facet normal -0.950252 -0.0326583 -0.309767 + outer loop + vertex 1.53152 1.18558 2.52175 + vertex 1.53018 1.18246 2.52619 + vertex 1.52995 1.18718 2.52639 + endloop + endfacet + facet normal -0.998627 -0.0468269 -0.0234705 + outer loop + vertex 1.53018 1.18246 2.52619 + vertex 1.53002 1.18346 2.5308 + vertex 1.52995 1.18718 2.52639 + endloop + endfacet + facet normal -0.993885 -0.0917306 -0.0614604 + outer loop + vertex 1.52995 1.18718 2.52639 + vertex 1.53002 1.18346 2.5308 + vertex 1.52953 1.18844 2.53132 + endloop + endfacet + facet normal -0.947329 -0.124949 0.294883 + outer loop + vertex 1.53002 1.18346 2.5308 + vertex 1.53108 1.18519 2.53491 + vertex 1.52953 1.18844 2.53132 + endloop + endfacet + facet normal -0.946955 -0.122177 0.297236 + outer loop + vertex 1.52953 1.18844 2.53132 + vertex 1.53108 1.18519 2.53491 + vertex 1.53069 1.19029 2.53578 + endloop + endfacet + facet normal -0.634331 -0.175365 0.752908 + outer loop + vertex 1.53108 1.18519 2.53491 + vertex 1.53363 1.18834 2.5378 + vertex 1.53069 1.19029 2.53578 + endloop + endfacet + facet normal -0.661618 -0.138634 0.736914 + outer loop + vertex 1.53393 1.18326 2.53711 + vertex 1.53363 1.18834 2.5378 + vertex 1.53108 1.18519 2.53491 + endloop + endfacet + facet normal -0.516451 0.506423 -0.690517 + outer loop + vertex 1.53404 1.19009 2.52 + vertex 1.53146 1.19111 2.52268 + vertex 1.535 1.195 2.52288 + endloop + endfacet + facet normal -0.693506 0.111332 -0.711796 + outer loop + vertex 1.53152 1.18558 2.52175 + vertex 1.53146 1.19111 2.52268 + vertex 1.53404 1.19009 2.52 + endloop + endfacet + facet normal -0.941598 0.0450207 -0.333715 + outer loop + vertex 1.53152 1.18558 2.52175 + vertex 1.52995 1.18718 2.52639 + vertex 1.53146 1.19111 2.52268 + endloop + endfacet + facet normal -0.916054 -0.0275318 -0.400109 + outer loop + vertex 1.53146 1.19111 2.52268 + vertex 1.52995 1.18718 2.52639 + vertex 1.52958 1.19245 2.52688 + endloop + endfacet + facet normal -0.995562 -0.0644718 -0.0685485 + outer loop + vertex 1.52995 1.18718 2.52639 + vertex 1.52953 1.18844 2.53132 + vertex 1.52958 1.19245 2.52688 + endloop + endfacet + facet normal -0.987633 -0.111142 -0.110581 + outer loop + vertex 1.52958 1.19245 2.52688 + vertex 1.52953 1.18844 2.53132 + vertex 1.52875 1.19425 2.53247 + endloop + endfacet + facet normal -0.928478 -0.188449 0.320024 + outer loop + vertex 1.52953 1.18844 2.53132 + vertex 1.53069 1.19029 2.53578 + vertex 1.52875 1.19425 2.53247 + endloop + endfacet + facet normal -0.924803 -0.169457 0.340624 + outer loop + vertex 1.52875 1.19425 2.53247 + vertex 1.53069 1.19029 2.53578 + vertex 1.53048 1.19486 2.53748 + endloop + endfacet + facet normal -0.523182 -0.319118 0.790218 + outer loop + vertex 1.53069 1.19029 2.53578 + vertex 1.5335 1.19364 2.53899 + vertex 1.53048 1.19486 2.53748 + endloop + endfacet + facet normal -0.637017 -0.183834 0.748608 + outer loop + vertex 1.53363 1.18834 2.5378 + vertex 1.5335 1.19364 2.53899 + vertex 1.53069 1.19029 2.53578 + endloop + endfacet + facet normal -0.176822 -0.0334435 -0.983674 + outer loop + vertex 1.535 1.195 2.52288 + vertex 1.53143 1.19675 2.52346 + vertex 1.535 1.2 2.52271 + endloop + endfacet + facet normal -0.0937022 0.137018 -0.986127 + outer loop + vertex 1.53146 1.19111 2.52268 + vertex 1.53143 1.19675 2.52346 + vertex 1.535 1.195 2.52288 + endloop + endfacet + facet normal -0.905219 0.0546061 -0.421423 + outer loop + vertex 1.53146 1.19111 2.52268 + vertex 1.52958 1.19245 2.52688 + vertex 1.53143 1.19675 2.52346 + endloop + endfacet + facet normal -0.829697 -0.0819098 -0.552172 + outer loop + vertex 1.53143 1.19675 2.52346 + vertex 1.52958 1.19245 2.52688 + vertex 1.52889 1.1983 2.52705 + endloop + endfacet + facet normal -0.887992 -0.30039 -0.34819 + outer loop + vertex 1.52765 1.1977 2.53073 + vertex 1.52741 1.20076 2.5287 + vertex 1.52889 1.1983 2.52705 + endloop + endfacet + facet normal -0.826801 -0.440183 -0.3502 + outer loop + vertex 1.52765 1.1977 2.53073 + vertex 1.52889 1.1983 2.52705 + vertex 1.52875 1.19425 2.53247 + endloop + endfacet + facet normal -0.987524 -0.112582 -0.1101 + outer loop + vertex 1.52875 1.19425 2.53247 + vertex 1.52889 1.1983 2.52705 + vertex 1.52958 1.19245 2.52688 + endloop + endfacet + facet normal -0.947946 -0.316993 -0.0302263 + outer loop + vertex 1.52763 1.19749 2.53353 + vertex 1.52765 1.1977 2.53073 + vertex 1.52875 1.19425 2.53247 + endloop + endfacet + facet normal -0.829201 -0.409904 0.380005 + outer loop + vertex 1.52763 1.19749 2.53353 + vertex 1.52875 1.19425 2.53247 + vertex 1.52873 1.19819 2.53669 + endloop + endfacet + facet normal -0.862696 -0.371089 0.343581 + outer loop + vertex 1.52873 1.19819 2.53669 + vertex 1.52875 1.19425 2.53247 + vertex 1.53048 1.19486 2.53748 + endloop + endfacet + facet normal -0.533378 -0.400961 0.744808 + outer loop + vertex 1.5324 1.19656 2.53977 + vertex 1.53048 1.19486 2.53748 + vertex 1.5335 1.19364 2.53899 + endloop + endfacet + facet normal -0.629513 -0.270787 0.728277 + outer loop + vertex 1.5324 1.19656 2.53977 + vertex 1.5312 1.19899 2.53964 + vertex 1.53048 1.19486 2.53748 + endloop + endfacet + facet normal -0.71812 -0.21999 0.660234 + outer loop + vertex 1.5312 1.19899 2.53964 + vertex 1.52873 1.19819 2.53669 + vertex 1.53048 1.19486 2.53748 + endloop + endfacet + facet normal -0.360852 -0.126771 0.923967 + outer loop + vertex 1.5324 1.19656 2.53977 + vertex 1.53405 1.19982 2.54086 + vertex 1.5312 1.19899 2.53964 + endloop + endfacet + facet normal -0.572853 -0.0246121 -0.819289 + outer loop + vertex 1.535 1.2 2.52271 + vertex 1.53151 1.205 2.525 + vertex 1.535 1.205 2.52256 + endloop + endfacet + facet normal -0.35283 0.174734 -0.919227 + outer loop + vertex 1.53143 1.19675 2.52346 + vertex 1.53151 1.205 2.525 + vertex 1.535 1.2 2.52271 + endloop + endfacet + facet normal -0.784672 0.120904 -0.608007 + outer loop + vertex 1.53143 1.19675 2.52346 + vertex 1.52889 1.1983 2.52705 + vertex 1.53151 1.205 2.525 + endloop + endfacet + facet normal -0.165224 -0.228292 -0.959471 + outer loop + vertex 1.53151 1.205 2.525 + vertex 1.52889 1.1983 2.52705 + vertex 1.52873 1.20367 2.52579 + endloop + endfacet + facet normal -0.836264 -0.148141 -0.527936 + outer loop + vertex 1.52873 1.20367 2.52579 + vertex 1.52889 1.1983 2.52705 + vertex 1.52741 1.20076 2.5287 + endloop + endfacet + facet normal -0.728216 -0.289793 -0.621065 + outer loop + vertex 1.52728 1.20387 2.5274 + vertex 1.52873 1.20367 2.52579 + vertex 1.52741 1.20076 2.5287 + endloop + endfacet + facet normal -0.864352 -0.334485 0.375519 + outer loop + vertex 1.52763 1.19749 2.53353 + vertex 1.52873 1.19819 2.53669 + vertex 1.52739 1.19979 2.53503 + endloop + endfacet + facet normal -0.858944 -0.26516 0.438069 + outer loop + vertex 1.52788 1.20179 2.53719 + vertex 1.52739 1.19979 2.53503 + vertex 1.52873 1.19819 2.53669 + endloop + endfacet + facet normal -0.694466 -0.258972 0.671306 + outer loop + vertex 1.52788 1.20179 2.53719 + vertex 1.52873 1.19819 2.53669 + vertex 1.5299 1.20325 2.53985 + endloop + endfacet + facet normal -0.708713 -0.248738 0.660193 + outer loop + vertex 1.5299 1.20325 2.53985 + vertex 1.52873 1.19819 2.53669 + vertex 1.5312 1.19899 2.53964 + endloop + endfacet + facet normal -0.348867 -0.152531 0.924676 + outer loop + vertex 1.5312 1.19899 2.53964 + vertex 1.53362 1.2036 2.54131 + vertex 1.5299 1.20325 2.53985 + endloop + endfacet + facet normal -0.353977 -0.149327 0.923256 + outer loop + vertex 1.53405 1.19982 2.54086 + vertex 1.53362 1.2036 2.54131 + vertex 1.5312 1.19899 2.53964 + endloop + endfacet + facet normal -0.296147 0.0829573 -0.951533 + outer loop + vertex 1.52818 1.20645 2.52578 + vertex 1.52871 1.21015 2.52594 + vertex 1.53168 1.21 2.525 + endloop + endfacet + facet normal -0.177331 -0.0408529 -0.983303 + outer loop + vertex 1.52818 1.20645 2.52578 + vertex 1.53168 1.21 2.525 + vertex 1.52873 1.20367 2.52579 + endloop + endfacet + facet normal -0.279129 0.00948999 -0.960207 + outer loop + vertex 1.52873 1.20367 2.52579 + vertex 1.53168 1.21 2.525 + vertex 1.53151 1.205 2.525 + endloop + endfacet + facet normal -0.743033 -0.150025 -0.652222 + outer loop + vertex 1.52873 1.20367 2.52579 + vertex 1.52728 1.20387 2.5274 + vertex 1.52818 1.20645 2.52578 + endloop + endfacet + facet normal -0.714746 -0.218295 0.664444 + outer loop + vertex 1.52777 1.2058 2.5384 + vertex 1.52788 1.20179 2.53719 + vertex 1.5299 1.20325 2.53985 + endloop + endfacet + facet normal -0.728563 -0.243578 0.640207 + outer loop + vertex 1.52935 1.20786 2.54097 + vertex 1.52777 1.2058 2.5384 + vertex 1.5299 1.20325 2.53985 + endloop + endfacet + facet normal -0.264264 -0.258111 0.92927 + outer loop + vertex 1.5299 1.20325 2.53985 + vertex 1.53285 1.20877 2.54222 + vertex 1.52935 1.20786 2.54097 + endloop + endfacet + facet normal -0.339865 -0.212113 0.916242 + outer loop + vertex 1.53362 1.2036 2.54131 + vertex 1.53285 1.20877 2.54222 + vertex 1.5299 1.20325 2.53985 + endloop + endfacet + facet normal -0.298613 0.0459848 -0.953266 + outer loop + vertex 1.53245 1.215 2.525 + vertex 1.53168 1.21 2.525 + vertex 1.52871 1.21015 2.52594 + endloop + endfacet + facet normal -0.737815 0.476371 -0.478225 + outer loop + vertex 1.53 1.215 2.52878 + vertex 1.53245 1.215 2.525 + vertex 1.52871 1.21015 2.52594 + endloop + endfacet + facet normal -0.754482 -0.203448 0.623992 + outer loop + vertex 1.52777 1.2058 2.5384 + vertex 1.52935 1.20786 2.54097 + vertex 1.5278 1.20998 2.5398 + endloop + endfacet + facet normal -0.687348 -0.101993 0.719132 + outer loop + vertex 1.52935 1.20786 2.54097 + vertex 1.5301 1.21285 2.5424 + vertex 1.5278 1.20998 2.5398 + endloop + endfacet + facet normal -0.274637 -0.225588 0.934711 + outer loop + vertex 1.52935 1.20786 2.54097 + vertex 1.53285 1.20877 2.54222 + vertex 1.5301 1.21285 2.5424 + endloop + endfacet + facet normal -0.217558 -0.188024 0.957766 + outer loop + vertex 1.53285 1.20877 2.54222 + vertex 1.53393 1.21392 2.54348 + vertex 1.5301 1.21285 2.5424 + endloop + endfacet + facet normal -0.207966 -0.218113 0.953508 + outer loop + vertex 1.53393 1.21392 2.54348 + vertex 1.53325 1.21797 2.54426 + vertex 1.5301 1.21285 2.5424 + endloop + endfacet + facet normal -0.191485 -0.228619 0.954498 + outer loop + vertex 1.5301 1.21285 2.5424 + vertex 1.53325 1.21797 2.54426 + vertex 1.52928 1.21864 2.54362 + endloop + endfacet + facet normal -0.429876 -0.402835 0.808041 + outer loop + vertex 1.5299 1.22212 2.54568 + vertex 1.52795 1.22171 2.54444 + vertex 1.52928 1.21864 2.54362 + endloop + endfacet + facet normal 0.163722 -0.524399 0.835584 + outer loop + vertex 1.5299 1.22212 2.54568 + vertex 1.52928 1.21864 2.54362 + vertex 1.53308 1.22284 2.54551 + endloop + endfacet + facet normal -0.194323 -0.251174 0.948235 + outer loop + vertex 1.53308 1.22284 2.54551 + vertex 1.52928 1.21864 2.54362 + vertex 1.53325 1.21797 2.54426 + endloop + endfacet + facet normal -0.747833 0.172814 -0.641 + outer loop + vertex 1.53006 1.245 2.53 + vertex 1.53 1.24474 2.53 + vertex 1.53 1.245 2.53007 + endloop + endfacet + facet normal 0.197997 -0.0575161 -0.978514 + outer loop + vertex 1.53052 1.815 2.53 + vertex 1.53 1.81321 2.53 + vertex 1.52813 1.81462 2.52954 + endloop + endfacet + facet normal -0.929101 0.0036993 -0.369806 + outer loop + vertex 1.53251 1.815 2.525 + vertex 1.53052 1.815 2.53 + vertex 1.53253 1.82 2.525 + endloop + endfacet + facet normal -0.346279 -0.590086 -0.729307 + outer loop + vertex 1.53253 1.82 2.525 + vertex 1.53052 1.815 2.53 + vertex 1.52945 1.81927 2.52705 + endloop + endfacet + facet normal 0.240205 -0.509992 -0.82596 + outer loop + vertex 1.52945 1.81927 2.52705 + vertex 1.53052 1.815 2.53 + vertex 1.52813 1.81462 2.52954 + endloop + endfacet + facet normal -0.885666 0.00228324 -0.464318 + outer loop + vertex 1.52779 1.81803 2.53021 + vertex 1.52945 1.81927 2.52705 + vertex 1.52813 1.81462 2.52954 + endloop + endfacet + facet normal -0.551848 -0.0143412 -0.833821 + outer loop + vertex 1.53253 1.82 2.525 + vertex 1.52945 1.81927 2.52705 + vertex 1.5324 1.825 2.525 + endloop + endfacet + facet normal -0.297389 -0.182394 -0.937172 + outer loop + vertex 1.5324 1.825 2.525 + vertex 1.52945 1.81927 2.52705 + vertex 1.52995 1.82437 2.5259 + endloop + endfacet + facet normal -0.96717 0.128827 -0.219058 + outer loop + vertex 1.52779 1.81803 2.53021 + vertex 1.52738 1.81956 2.53291 + vertex 1.52851 1.82307 2.53 + endloop + endfacet + facet normal -0.897058 0.109878 -0.428035 + outer loop + vertex 1.52779 1.81803 2.53021 + vertex 1.52851 1.82307 2.53 + vertex 1.52945 1.81927 2.52705 + endloop + endfacet + facet normal -0.945031 0.0192854 -0.326411 + outer loop + vertex 1.52945 1.81927 2.52705 + vertex 1.52851 1.82307 2.53 + vertex 1.52995 1.82437 2.5259 + endloop + endfacet + facet normal -0.970126 0.208336 -0.124307 + outer loop + vertex 1.52851 1.82307 2.53 + vertex 1.52738 1.81956 2.53291 + vertex 1.52781 1.82247 2.53446 + endloop + endfacet + facet normal -0.411999 0.175666 0.894091 + outer loop + vertex 1.52898 1.81762 2.54184 + vertex 1.53122 1.82048 2.54231 + vertex 1.52905 1.82128 2.54115 + endloop + endfacet + facet normal -0.342089 -0.0109454 -0.939604 + outer loop + vertex 1.5324 1.825 2.525 + vertex 1.52995 1.82437 2.5259 + vertex 1.53224 1.83 2.525 + endloop + endfacet + facet normal -0.582924 0.108443 -0.805258 + outer loop + vertex 1.53224 1.83 2.525 + vertex 1.52995 1.82437 2.5259 + vertex 1.52989 1.82833 2.52648 + endloop + endfacet + facet normal -0.945941 0.0317253 -0.322782 + outer loop + vertex 1.52995 1.82437 2.5259 + vertex 1.52851 1.82307 2.53 + vertex 1.52989 1.82833 2.52648 + endloop + endfacet + facet normal -0.967961 0.0991047 -0.230716 + outer loop + vertex 1.52989 1.82833 2.52648 + vertex 1.52851 1.82307 2.53 + vertex 1.52912 1.82845 2.52977 + endloop + endfacet + facet normal -0.964964 0.258235 0.0464731 + outer loop + vertex 1.52781 1.82247 2.53446 + vertex 1.52829 1.82371 2.53763 + vertex 1.52905 1.82714 2.5343 + endloop + endfacet + facet normal -0.960777 0.251413 -0.117044 + outer loop + vertex 1.52781 1.82247 2.53446 + vertex 1.52905 1.82714 2.5343 + vertex 1.52851 1.82307 2.53 + endloop + endfacet + facet normal -0.993478 0.112542 0.0183247 + outer loop + vertex 1.52851 1.82307 2.53 + vertex 1.52905 1.82714 2.5343 + vertex 1.52912 1.82845 2.52977 + endloop + endfacet + facet normal -0.833261 0.468428 0.293686 + outer loop + vertex 1.53088 1.82751 2.53889 + vertex 1.52905 1.82714 2.5343 + vertex 1.52829 1.82371 2.53763 + endloop + endfacet + facet normal -0.833794 0.470291 0.28916 + outer loop + vertex 1.52922 1.82383 2.54009 + vertex 1.53088 1.82751 2.53889 + vertex 1.52829 1.82371 2.53763 + endloop + endfacet + facet normal -0.422403 0.446781 0.788646 + outer loop + vertex 1.52922 1.82383 2.54009 + vertex 1.53192 1.82415 2.54135 + vertex 1.53088 1.82751 2.53889 + endloop + endfacet + facet normal -0.429607 0.372254 0.822718 + outer loop + vertex 1.52922 1.82383 2.54009 + vertex 1.52905 1.82128 2.54115 + vertex 1.53192 1.82415 2.54135 + endloop + endfacet + facet normal -0.360616 0.299053 0.883472 + outer loop + vertex 1.52905 1.82128 2.54115 + vertex 1.53122 1.82048 2.54231 + vertex 1.53192 1.82415 2.54135 + endloop + endfacet + facet normal -0.526601 -0.0105338 -0.850047 + outer loop + vertex 1.53224 1.83 2.525 + vertex 1.52989 1.82833 2.52648 + vertex 1.53214 1.835 2.525 + endloop + endfacet + facet normal -0.728428 0.0956645 -0.678411 + outer loop + vertex 1.53214 1.835 2.525 + vertex 1.52989 1.82833 2.52648 + vertex 1.53015 1.83293 2.52685 + endloop + endfacet + facet normal -0.970324 0.0736302 -0.230327 + outer loop + vertex 1.52989 1.82833 2.52648 + vertex 1.52912 1.82845 2.52977 + vertex 1.53015 1.83293 2.52685 + endloop + endfacet + facet normal -0.981659 0.168719 -0.0887609 + outer loop + vertex 1.53015 1.83293 2.52685 + vertex 1.52912 1.82845 2.52977 + vertex 1.52969 1.83249 2.53105 + endloop + endfacet + facet normal -0.990675 0.134018 0.0245579 + outer loop + vertex 1.52912 1.82845 2.52977 + vertex 1.52905 1.82714 2.5343 + vertex 1.52969 1.83249 2.53105 + endloop + endfacet + facet normal -0.931582 0.264061 0.249855 + outer loop + vertex 1.52969 1.83249 2.53105 + vertex 1.52905 1.82714 2.5343 + vertex 1.53121 1.83329 2.53586 + endloop + endfacet + facet normal -0.46186 0.344187 0.817448 + outer loop + vertex 1.53491 1.83222 2.53919 + vertex 1.53088 1.82751 2.53889 + vertex 1.53411 1.82778 2.54061 + endloop + endfacet + facet normal -0.539042 0.415627 0.73259 + outer loop + vertex 1.53491 1.83222 2.53919 + vertex 1.53121 1.83329 2.53586 + vertex 1.53088 1.82751 2.53889 + endloop + endfacet + facet normal -0.909973 0.232874 0.343101 + outer loop + vertex 1.53121 1.83329 2.53586 + vertex 1.52905 1.82714 2.5343 + vertex 1.53088 1.82751 2.53889 + endloop + endfacet + facet normal -0.449856 0.432813 0.781219 + outer loop + vertex 1.53411 1.82778 2.54061 + vertex 1.53088 1.82751 2.53889 + vertex 1.53192 1.82415 2.54135 + endloop + endfacet + facet normal -0.695659 0.0292076 -0.717778 + outer loop + vertex 1.53214 1.835 2.525 + vertex 1.53015 1.83293 2.52685 + vertex 1.53235 1.84 2.525 + endloop + endfacet + facet normal -0.742457 0.0568875 -0.667474 + outer loop + vertex 1.53235 1.84 2.525 + vertex 1.53015 1.83293 2.52685 + vertex 1.53039 1.83702 2.52693 + endloop + endfacet + facet normal -0.993073 0.0593747 -0.101389 + outer loop + vertex 1.53015 1.83293 2.52685 + vertex 1.52969 1.83249 2.53105 + vertex 1.53039 1.83702 2.52693 + endloop + endfacet + facet normal -0.990699 0.134908 -0.0177836 + outer loop + vertex 1.53039 1.83702 2.52693 + vertex 1.52969 1.83249 2.53105 + vertex 1.53038 1.83755 2.53132 + endloop + endfacet + facet normal -0.952736 0.113538 0.281786 + outer loop + vertex 1.52969 1.83249 2.53105 + vertex 1.53121 1.83329 2.53586 + vertex 1.53038 1.83755 2.53132 + endloop + endfacet + facet normal -0.953053 0.112693 0.281052 + outer loop + vertex 1.53038 1.83755 2.53132 + vertex 1.53121 1.83329 2.53586 + vertex 1.53172 1.83954 2.53506 + endloop + endfacet + facet normal -0.683821 0.146226 0.714847 + outer loop + vertex 1.53121 1.83329 2.53586 + vertex 1.53418 1.83757 2.53783 + vertex 1.53172 1.83954 2.53506 + endloop + endfacet + facet normal -0.648647 0.103765 0.753983 + outer loop + vertex 1.53491 1.83222 2.53919 + vertex 1.53418 1.83757 2.53783 + vertex 1.53121 1.83329 2.53586 + endloop + endfacet + facet normal -0.167226 -0.481722 -0.860221 + outer loop + vertex 1.535 1.84 2.52286 + vertex 1.53185 1.84071 2.52308 + vertex 1.535 1.845 2.52006 + endloop + endfacet + facet normal -0.228038 -0.931805 -0.28238 + outer loop + vertex 1.53235 1.84 2.525 + vertex 1.53185 1.84071 2.52308 + vertex 1.535 1.84 2.52286 + endloop + endfacet + facet normal 0.617836 -0.67232 -0.407754 + outer loop + vertex 1.53235 1.84 2.525 + vertex 1.53039 1.83702 2.52693 + vertex 1.53185 1.84071 2.52308 + endloop + endfacet + facet normal -0.940406 0.0183798 -0.339556 + outer loop + vertex 1.53185 1.84071 2.52308 + vertex 1.53039 1.83702 2.52693 + vertex 1.53059 1.84133 2.52659 + endloop + endfacet + facet normal -0.998842 0.0475502 -0.00730853 + outer loop + vertex 1.53039 1.83702 2.52693 + vertex 1.53038 1.83755 2.53132 + vertex 1.53059 1.84133 2.52659 + endloop + endfacet + facet normal -0.997587 0.0687523 0.00967965 + outer loop + vertex 1.53059 1.84133 2.52659 + vertex 1.53038 1.83755 2.53132 + vertex 1.53073 1.84275 2.53092 + endloop + endfacet + facet normal -0.951794 0.0876879 0.293938 + outer loop + vertex 1.53038 1.83755 2.53132 + vertex 1.53172 1.83954 2.53506 + vertex 1.53073 1.84275 2.53092 + endloop + endfacet + facet normal -0.966022 0.034448 0.256155 + outer loop + vertex 1.53073 1.84275 2.53092 + vertex 1.53172 1.83954 2.53506 + vertex 1.53175 1.84475 2.53449 + endloop + endfacet + facet normal -0.759459 0.0761245 0.646086 + outer loop + vertex 1.53172 1.83954 2.53506 + vertex 1.53378 1.84254 2.53713 + vertex 1.53175 1.84475 2.53449 + endloop + endfacet + facet normal -0.732956 0.0350122 0.679374 + outer loop + vertex 1.53418 1.83757 2.53783 + vertex 1.53378 1.84254 2.53713 + vertex 1.53172 1.83954 2.53506 + endloop + endfacet + facet normal -0.539282 -0.296053 -0.78837 + outer loop + vertex 1.535 1.845 2.52006 + vertex 1.53169 1.84497 2.52234 + vertex 1.53315 1.84914 2.51977 + endloop + endfacet + facet normal -0.558042 -0.162328 -0.81378 + outer loop + vertex 1.53185 1.84071 2.52308 + vertex 1.53169 1.84497 2.52234 + vertex 1.535 1.845 2.52006 + endloop + endfacet + facet normal -0.942729 -0.090703 -0.320992 + outer loop + vertex 1.53185 1.84071 2.52308 + vertex 1.53059 1.84133 2.52659 + vertex 1.53169 1.84497 2.52234 + endloop + endfacet + facet normal -0.973994 0.0317806 -0.224333 + outer loop + vertex 1.53169 1.84497 2.52234 + vertex 1.53059 1.84133 2.52659 + vertex 1.53082 1.8463 2.5263 + endloop + endfacet + facet normal -0.99876 0.0468393 0.0168824 + outer loop + vertex 1.53059 1.84133 2.52659 + vertex 1.53073 1.84275 2.53092 + vertex 1.53082 1.8463 2.5263 + endloop + endfacet + facet normal -0.999454 0.0325137 0.00583005 + outer loop + vertex 1.53082 1.8463 2.5263 + vertex 1.53073 1.84275 2.53092 + vertex 1.5309 1.84781 2.53064 + endloop + endfacet + facet normal -0.96707 0.0450999 0.250483 + outer loop + vertex 1.53073 1.84275 2.53092 + vertex 1.53175 1.84475 2.53449 + vertex 1.5309 1.84781 2.53064 + endloop + endfacet + facet normal -0.978301 -0.012869 0.206786 + outer loop + vertex 1.5309 1.84781 2.53064 + vertex 1.53175 1.84475 2.53449 + vertex 1.53161 1.84948 2.53414 + endloop + endfacet + facet normal -0.792173 0.0223588 0.609887 + outer loop + vertex 1.53175 1.84475 2.53449 + vertex 1.53338 1.84728 2.53651 + vertex 1.53161 1.84948 2.53414 + endloop + endfacet + facet normal -0.787511 0.0143635 0.616133 + outer loop + vertex 1.53378 1.84254 2.53713 + vertex 1.53338 1.84728 2.53651 + vertex 1.53175 1.84475 2.53449 + endloop + endfacet + facet normal -0.854005 0.0180029 -0.519953 + outer loop + vertex 1.53315 1.84914 2.51977 + vertex 1.53162 1.84995 2.52231 + vertex 1.5331 1.85403 2.52002 + endloop + endfacet + facet normal -0.858596 -0.0141607 -0.512457 + outer loop + vertex 1.53169 1.84497 2.52234 + vertex 1.53162 1.84995 2.52231 + vertex 1.53315 1.84914 2.51977 + endloop + endfacet + facet normal -0.977687 -0.0145145 -0.209563 + outer loop + vertex 1.53169 1.84497 2.52234 + vertex 1.53082 1.8463 2.5263 + vertex 1.53162 1.84995 2.52231 + endloop + endfacet + facet normal -0.987171 0.051454 -0.151148 + outer loop + vertex 1.53162 1.84995 2.52231 + vertex 1.53082 1.8463 2.5263 + vertex 1.53105 1.85138 2.52651 + endloop + endfacet + facet normal -0.998953 0.0457363 0.00121767 + outer loop + vertex 1.53082 1.8463 2.5263 + vertex 1.5309 1.84781 2.53064 + vertex 1.53105 1.85138 2.52651 + endloop + endfacet + facet normal -0.999411 0.032823 -0.00997288 + outer loop + vertex 1.53105 1.85138 2.52651 + vertex 1.5309 1.84781 2.53064 + vertex 1.53105 1.85254 2.53085 + endloop + endfacet + facet normal -0.981483 0.023463 0.190105 + outer loop + vertex 1.5309 1.84781 2.53064 + vertex 1.53161 1.84948 2.53414 + vertex 1.53105 1.85254 2.53085 + endloop + endfacet + facet normal -0.979614 0.0325597 0.198235 + outer loop + vertex 1.53105 1.85254 2.53085 + vertex 1.53161 1.84948 2.53414 + vertex 1.53173 1.8536 2.53405 + endloop + endfacet + facet normal -0.841783 0.0360394 0.538612 + outer loop + vertex 1.53161 1.84948 2.53414 + vertex 1.53284 1.85113 2.53594 + vertex 1.53173 1.8536 2.53405 + endloop + endfacet + facet normal -0.814646 -0.0287321 0.579246 + outer loop + vertex 1.53338 1.84728 2.53651 + vertex 1.53284 1.85113 2.53594 + vertex 1.53161 1.84948 2.53414 + endloop + endfacet + facet normal -0.912155 0.0667485 -0.404373 + outer loop + vertex 1.5331 1.85403 2.52002 + vertex 1.53187 1.85486 2.52294 + vertex 1.53311 1.85792 2.52066 + endloop + endfacet + facet normal -0.906352 0.0982921 -0.410931 + outer loop + vertex 1.53162 1.84995 2.52231 + vertex 1.53187 1.85486 2.52294 + vertex 1.5331 1.85403 2.52002 + endloop + endfacet + facet normal -0.985079 0.0700474 -0.157206 + outer loop + vertex 1.53162 1.84995 2.52231 + vertex 1.53105 1.85138 2.52651 + vertex 1.53187 1.85486 2.52294 + endloop + endfacet + facet normal -0.986825 0.111963 -0.116795 + outer loop + vertex 1.53187 1.85486 2.52294 + vertex 1.53105 1.85138 2.52651 + vertex 1.53152 1.85654 2.52752 + endloop + endfacet + facet normal -0.995117 0.095054 -0.0265825 + outer loop + vertex 1.53105 1.85138 2.52651 + vertex 1.53105 1.85254 2.53085 + vertex 1.53152 1.85654 2.52752 + endloop + endfacet + facet normal -0.992912 0.118829 0.00237138 + outer loop + vertex 1.53152 1.85654 2.52752 + vertex 1.53105 1.85254 2.53085 + vertex 1.53148 1.85612 2.53157 + endloop + endfacet + facet normal -0.979908 0.0809827 0.182272 + outer loop + vertex 1.53105 1.85254 2.53085 + vertex 1.53173 1.8536 2.53405 + vertex 1.53148 1.85612 2.53157 + endloop + endfacet + facet normal -0.907813 0.244286 0.340882 + outer loop + vertex 1.53148 1.85612 2.53157 + vertex 1.53173 1.8536 2.53405 + vertex 1.53263 1.8573 2.53379 + endloop + endfacet + facet normal -0.739227 0.224114 0.635071 + outer loop + vertex 1.53173 1.8536 2.53405 + vertex 1.53343 1.85439 2.53574 + vertex 1.53263 1.8573 2.53379 + endloop + endfacet + facet normal -0.735503 0.172966 0.655071 + outer loop + vertex 1.53284 1.85113 2.53594 + vertex 1.53343 1.85439 2.53574 + vertex 1.53173 1.8536 2.53405 + endloop + endfacet + facet normal -0.941701 0.159251 -0.296375 + outer loop + vertex 1.53311 1.85792 2.52066 + vertex 1.53187 1.85486 2.52294 + vertex 1.53243 1.85949 2.52364 + endloop + endfacet + facet normal -0.979597 0.17595 -0.0971198 + outer loop + vertex 1.53243 1.85949 2.52364 + vertex 1.53152 1.85654 2.52752 + vertex 1.53232 1.8608 2.52714 + endloop + endfacet + facet normal -0.98229 0.138507 -0.126183 + outer loop + vertex 1.53187 1.85486 2.52294 + vertex 1.53152 1.85654 2.52752 + vertex 1.53243 1.85949 2.52364 + endloop + endfacet + facet normal -0.966676 0.232646 0.106829 + outer loop + vertex 1.53232 1.8608 2.52714 + vertex 1.53252 1.86 2.53068 + vertex 1.53314 1.86343 2.52877 + endloop + endfacet + facet normal -0.976252 0.193017 0.098372 + outer loop + vertex 1.53232 1.8608 2.52714 + vertex 1.53152 1.85654 2.52752 + vertex 1.53252 1.86 2.53068 + endloop + endfacet + facet normal -0.964539 0.263337 0.0178193 + outer loop + vertex 1.53152 1.85654 2.52752 + vertex 1.53148 1.85612 2.53157 + vertex 1.53252 1.86 2.53068 + endloop + endfacet + facet normal -0.544431 0.421276 0.725342 + outer loop + vertex 1.53504 1.86109 2.5334 + vertex 1.53263 1.8573 2.53379 + vertex 1.53458 1.85748 2.53515 + endloop + endfacet + facet normal -0.723123 0.50881 0.467124 + outer loop + vertex 1.53504 1.86109 2.5334 + vertex 1.53252 1.86 2.53068 + vertex 1.53263 1.8573 2.53379 + endloop + endfacet + facet normal -0.901196 0.311091 0.301775 + outer loop + vertex 1.53252 1.86 2.53068 + vertex 1.53148 1.85612 2.53157 + vertex 1.53263 1.8573 2.53379 + endloop + endfacet + facet normal -0.556894 0.352479 0.752082 + outer loop + vertex 1.53458 1.85748 2.53515 + vertex 1.53263 1.8573 2.53379 + vertex 1.53343 1.85439 2.53574 + endloop + endfacet + facet normal -0.882264 0.339565 0.326046 + outer loop + vertex 1.53314 1.86343 2.52877 + vertex 1.53252 1.86 2.53068 + vertex 1.53417 1.86386 2.53113 + endloop + endfacet + facet normal -0.757595 0.254177 0.601203 + outer loop + vertex 1.53417 1.86386 2.53113 + vertex 1.53252 1.86 2.53068 + vertex 1.53504 1.86109 2.5334 + endloop + endfacet + facet normal -0.386219 -0.510125 -0.76851 + outer loop + vertex 1.53284 2.00546 2.49197 + vertex 1.53076 2.01 2.49 + vertex 1.535 2.00679 2.49 + endloop + endfacet + facet normal -0.246291 -0.478261 -0.842975 + outer loop + vertex 1.5289 2.0069 2.4923 + vertex 1.53076 2.01 2.49 + vertex 1.53284 2.00546 2.49197 + endloop + endfacet + facet normal -0.32006 -0.943403 -0.0869048 + outer loop + vertex 1.5289 2.0069 2.4923 + vertex 1.52972 2.00627 2.49609 + vertex 1.52677 2.00742 2.49448 + endloop + endfacet + facet normal -0.347874 -0.934182 -0.0792974 + outer loop + vertex 1.5289 2.0069 2.4923 + vertex 1.53284 2.00546 2.49197 + vertex 1.52972 2.00627 2.49609 + endloop + endfacet + facet normal -0.324752 -0.943902 -0.0598726 + outer loop + vertex 1.53284 2.00546 2.49197 + vertex 1.53353 2.00494 2.49641 + vertex 1.52972 2.00627 2.49609 + endloop + endfacet + facet normal -0.337906 -0.903409 0.263955 + outer loop + vertex 1.53353 2.00494 2.49641 + vertex 1.53158 2.00659 2.49955 + vertex 1.52972 2.00627 2.49609 + endloop + endfacet + facet normal -0.211682 -0.956413 0.201158 + outer loop + vertex 1.53158 2.00659 2.49955 + vertex 1.52916 2.00707 2.49929 + vertex 1.52972 2.00627 2.49609 + endloop + endfacet + facet normal -0.219483 -0.902396 0.370822 + outer loop + vertex 1.53158 2.00659 2.49955 + vertex 1.52995 2.00745 2.50069 + vertex 1.52916 2.00707 2.49929 + endloop + endfacet + facet normal -0.101427 -0.857025 0.505193 + outer loop + vertex 1.53126 2.00752 2.50107 + vertex 1.52995 2.00745 2.50069 + vertex 1.53158 2.00659 2.49955 + endloop + endfacet + facet normal -0.0450532 -0.578216 -0.814639 + outer loop + vertex 1.53076 2.01 2.49 + vertex 1.5289 2.0069 2.4923 + vertex 1.52613 2.00872 2.49116 + endloop + endfacet + facet normal -0.191435 -0.184156 -0.964074 + outer loop + vertex 1.53 2.01079 2.49 + vertex 1.53076 2.01 2.49 + vertex 1.52613 2.00872 2.49116 + endloop + endfacet + facet normal -0.460773 -0.852731 -0.246044 + outer loop + vertex 1.5289 2.0069 2.4923 + vertex 1.52677 2.00742 2.49448 + vertex 1.52613 2.00872 2.49116 + endloop + endfacet + facet normal 0.0550701 0.272662 0.960532 + outer loop + vertex 1.5303 2.00907 2.50085 + vertex 1.53267 2.00843 2.5009 + vertex 1.53319 2.01167 2.49995 + endloop + endfacet + facet normal -0.0192032 0.347211 0.93759 + outer loop + vertex 1.52669 2.01208 2.49966 + vertex 1.5303 2.00907 2.50085 + vertex 1.53319 2.01167 2.49995 + endloop + endfacet + facet normal -0.276723 -0.0360952 0.960271 + outer loop + vertex 1.53126 2.00752 2.50107 + vertex 1.5303 2.00907 2.50085 + vertex 1.52995 2.00745 2.50069 + endloop + endfacet + facet normal 0.0220412 0.153525 0.987899 + outer loop + vertex 1.53267 2.00843 2.5009 + vertex 1.5303 2.00907 2.50085 + vertex 1.53126 2.00752 2.50107 + endloop + endfacet + facet normal 0.182928 0.52788 0.829385 + outer loop + vertex 1.53185 2.10715 2.4697 + vertex 1.53153 2.11071 2.46751 + vertex 1.52723 2.10877 2.46969 + endloop + endfacet + facet normal 0.185687 0.523921 0.83128 + outer loop + vertex 1.52723 2.10877 2.46969 + vertex 1.53153 2.11071 2.46751 + vertex 1.52675 2.1121 2.4677 + endloop + endfacet + facet normal 0.19537 0.765363 0.61323 + outer loop + vertex 1.52867 2.11396 2.46557 + vertex 1.53313 2.11366 2.46451 + vertex 1.53029 2.11587 2.46266 + endloop + endfacet + facet normal 0.221885 0.752773 0.619758 + outer loop + vertex 1.52603 2.11623 2.46374 + vertex 1.52867 2.11396 2.46557 + vertex 1.53029 2.11587 2.46266 + endloop + endfacet + facet normal 0.214103 0.633736 0.743329 + outer loop + vertex 1.53153 2.11071 2.46751 + vertex 1.52867 2.11396 2.46557 + vertex 1.52675 2.1121 2.4677 + endloop + endfacet + facet normal 0.21713 0.635152 0.74124 + outer loop + vertex 1.53313 2.11366 2.46451 + vertex 1.52867 2.11396 2.46557 + vertex 1.53153 2.11071 2.46751 + endloop + endfacet + facet normal 0.634919 0.769618 0.0675726 + outer loop + vertex 1.53 2.12497 2.455 + vertex 1.53484 2.12125 2.45185 + vertex 1.53192 2.12377 2.45062 + endloop + endfacet + facet normal 0.882283 0.375764 0.283511 + outer loop + vertex 1.53 2.125 2.45496 + vertex 1.53 2.12497 2.455 + vertex 1.53192 2.12377 2.45062 + endloop + endfacet + facet normal 0.687074 0.36037 0.630922 + outer loop + vertex 1.53484 2.12125 2.45185 + vertex 1.53 2.12497 2.455 + vertex 1.53236 2.11984 2.45536 + endloop + endfacet + facet normal 0.430932 0.259303 0.864326 + outer loop + vertex 1.53236 2.11984 2.45536 + vertex 1.53 2.12497 2.455 + vertex 1.52901 2.11988 2.45702 + endloop + endfacet + facet normal 0.266269 0.813127 0.517616 + outer loop + vertex 1.53236 2.11984 2.45536 + vertex 1.52901 2.11988 2.45702 + vertex 1.53234 2.11751 2.45903 + endloop + endfacet + facet normal 0.22742 0.795695 0.561381 + outer loop + vertex 1.53234 2.11751 2.45903 + vertex 1.52901 2.11988 2.45702 + vertex 1.5274 2.11804 2.46028 + endloop + endfacet + facet normal 0.202195 0.833091 0.514856 + outer loop + vertex 1.53029 2.11587 2.46266 + vertex 1.5274 2.11804 2.46028 + vertex 1.52603 2.11623 2.46374 + endloop + endfacet + facet normal 0.216792 0.837669 0.501311 + outer loop + vertex 1.53234 2.11751 2.45903 + vertex 1.5274 2.11804 2.46028 + vertex 1.53029 2.11587 2.46266 + endloop + endfacet + facet normal 0.817729 0.536058 0.209667 + outer loop + vertex 1.53192 2.12377 2.45062 + vertex 1.53 2.12694 2.45 + vertex 1.53 2.125 2.45496 + endloop + endfacet + facet normal 0.0248627 0.207155 0.977992 + outer loop + vertex 1.535 2.12634 2.45 + vertex 1.53 2.12694 2.45 + vertex 1.53192 2.12377 2.45062 + endloop + endfacet + facet normal -0.325202 0.780095 -0.534504 + outer loop + vertex 1.535 0.908409 2.45 + vertex 1.54 0.91 2.44928 + vertex 1.53759 0.90862 2.44873 + endloop + endfacet + facet normal 0.122153 -0.701588 -0.702035 + outer loop + vertex 1.535 0.91 2.44841 + vertex 1.54 0.91 2.44928 + vertex 1.535 0.908409 2.45 + endloop + endfacet + facet normal 0.13732 -0.965619 0.220733 + outer loop + vertex 1.53551 0.908685 2.45031 + vertex 1.53759 0.90862 2.44873 + vertex 1.53933 0.909056 2.44955 + endloop + endfacet + facet normal 0.14586 -0.961757 0.231839 + outer loop + vertex 1.53551 0.908685 2.45031 + vertex 1.53189 0.90807 2.45003 + vertex 1.53759 0.90862 2.44873 + endloop + endfacet + facet normal -0.108989 0.992381 -0.0574609 + outer loop + vertex 1.53189 0.90807 2.45003 + vertex 1.535 0.908409 2.45 + vertex 1.53759 0.90862 2.44873 + endloop + endfacet + facet normal 0.133783 -0.934971 0.328529 + outer loop + vertex 1.53551 0.908685 2.45031 + vertex 1.53298 0.909062 2.45241 + vertex 1.53189 0.90807 2.45003 + endloop + endfacet + facet normal 0.162938 -0.912215 0.375918 + outer loop + vertex 1.53933 0.909056 2.44955 + vertex 1.53714 0.910059 2.45294 + vertex 1.53551 0.908685 2.45031 + endloop + endfacet + facet normal 0.17208 -0.912746 0.370517 + outer loop + vertex 1.53298 0.909062 2.45241 + vertex 1.53551 0.908685 2.45031 + vertex 1.53714 0.910059 2.45294 + endloop + endfacet + facet normal 0.157099 -0.885565 0.437143 + outer loop + vertex 1.53298 0.909062 2.45241 + vertex 1.53714 0.910059 2.45294 + vertex 1.53187 0.910972 2.45668 + endloop + endfacet + facet normal 0.168009 -0.876882 0.45039 + outer loop + vertex 1.53187 0.910972 2.45668 + vertex 1.53714 0.910059 2.45294 + vertex 1.53676 0.911865 2.4566 + endloop + endfacet + facet normal 0.160653 -0.828152 0.536987 + outer loop + vertex 1.53676 0.911865 2.4566 + vertex 1.5348 0.913445 2.45962 + vertex 1.53187 0.910972 2.45668 + endloop + endfacet + facet normal 0.167341 -0.825063 0.539693 + outer loop + vertex 1.53901 0.913664 2.45865 + vertex 1.5348 0.913445 2.45962 + vertex 1.53676 0.911865 2.4566 + endloop + endfacet + facet normal 0.180637 -0.772137 0.609241 + outer loop + vertex 1.5348 0.913445 2.45962 + vertex 1.53901 0.913664 2.45865 + vertex 1.53694 0.915529 2.46163 + endloop + endfacet + facet normal 0.182331 -0.7727 0.608021 + outer loop + vertex 1.53403 0.91503 2.46187 + vertex 1.5348 0.913445 2.45962 + vertex 1.53694 0.915529 2.46163 + endloop + endfacet + facet normal 0.176184 -0.692682 0.699393 + outer loop + vertex 1.53694 0.915529 2.46163 + vertex 1.53402 0.917159 2.46398 + vertex 1.53403 0.91503 2.46187 + endloop + endfacet + facet normal 0.167769 -0.700077 0.694079 + outer loop + vertex 1.53888 0.91826 2.46391 + vertex 1.53402 0.917159 2.46398 + vertex 1.53694 0.915529 2.46163 + endloop + endfacet + facet normal 0.15152 -0.624137 0.766482 + outer loop + vertex 1.53402 0.917159 2.46398 + vertex 1.53888 0.91826 2.46391 + vertex 1.53636 0.920619 2.46633 + endloop + endfacet + facet normal 0.168498 -0.629916 0.758165 + outer loop + vertex 1.53236 0.919594 2.46637 + vertex 1.53402 0.917159 2.46398 + vertex 1.53636 0.920619 2.46633 + endloop + endfacet + facet normal 0.14435 -0.533036 0.833688 + outer loop + vertex 1.53636 0.920619 2.46633 + vertex 1.53349 0.923157 2.46845 + vertex 1.53236 0.919594 2.46637 + endloop + endfacet + facet normal 0.134686 -0.541012 0.83016 + outer loop + vertex 1.53904 0.924118 2.46818 + vertex 1.53349 0.923157 2.46845 + vertex 1.53636 0.920619 2.46633 + endloop + endfacet + facet normal 0.123058 -0.45955 0.879585 + outer loop + vertex 1.53904 0.924118 2.46818 + vertex 1.53737 0.92718 2.47001 + vertex 1.53349 0.923157 2.46845 + endloop + endfacet + facet normal 0.120571 -0.457665 0.880912 + outer loop + vertex 1.53349 0.923157 2.46845 + vertex 1.53737 0.92718 2.47001 + vertex 1.53279 0.92687 2.47048 + endloop + endfacet + facet normal 0.119436 -0.397729 0.909696 + outer loop + vertex 1.53279 0.92687 2.47048 + vertex 1.53737 0.92718 2.47001 + vertex 1.53599 0.930371 2.47159 + endloop + endfacet + facet normal 0.116674 -0.395618 0.910974 + outer loop + vertex 1.53221 0.929566 2.47172 + vertex 1.53279 0.92687 2.47048 + vertex 1.53599 0.930371 2.47159 + endloop + endfacet + facet normal 0.109826 -0.360939 0.9261 + outer loop + vertex 1.53599 0.930371 2.47159 + vertex 1.53353 0.933401 2.47306 + vertex 1.53221 0.929566 2.47172 + endloop + endfacet + facet normal -0.50785 0.827479 -0.239512 + outer loop + vertex 1.53563 1.02415 2.48567 + vertex 1.53733 1.025 2.485 + vertex 1.535 1.02357 2.485 + endloop + endfacet + facet normal -0.550861 0.813315 -0.187274 + outer loop + vertex 1.53231 1.02217 2.48681 + vertex 1.53563 1.02415 2.48567 + vertex 1.535 1.02357 2.485 + endloop + endfacet + facet normal -0.503583 0.863159 0.0368876 + outer loop + vertex 1.53473 1.02345 2.48976 + vertex 1.53563 1.02415 2.48567 + vertex 1.53231 1.02217 2.48681 + endloop + endfacet + facet normal -0.536937 0.840345 0.0742854 + outer loop + vertex 1.53174 1.0214 2.49141 + vertex 1.53473 1.02345 2.48976 + vertex 1.53231 1.02217 2.48681 + endloop + endfacet + facet normal -0.486381 0.854334 0.183158 + outer loop + vertex 1.53526 1.02254 2.49541 + vertex 1.53473 1.02345 2.48976 + vertex 1.53174 1.0214 2.49141 + endloop + endfacet + facet normal -0.544791 0.80052 0.24974 + outer loop + vertex 1.53215 1.02019 2.49617 + vertex 1.53526 1.02254 2.49541 + vertex 1.53174 1.0214 2.49141 + endloop + endfacet + facet normal -0.805373 0.36821 0.464537 + outer loop + vertex 1.53775 1.023 2.49937 + vertex 1.53526 1.02254 2.49541 + vertex 1.5361 1.01931 2.49943 + endloop + endfacet + facet normal -0.679845 0.314855 0.662327 + outer loop + vertex 1.53775 1.023 2.49937 + vertex 1.5361 1.01931 2.49943 + vertex 1.53846 1.02195 2.50059 + endloop + endfacet + facet normal -0.366125 0.686303 0.628443 + outer loop + vertex 1.53526 1.02254 2.49541 + vertex 1.53215 1.02019 2.49617 + vertex 1.5361 1.01931 2.49943 + endloop + endfacet + facet normal -0.072454 0.617674 0.78309 + outer loop + vertex 1.53306 1.01778 2.50035 + vertex 1.5361 1.01931 2.49943 + vertex 1.53252 1.01894 2.49939 + endloop + endfacet + facet normal -0.100314 0.923413 0.370467 + outer loop + vertex 1.53215 1.02019 2.49617 + vertex 1.53252 1.01894 2.49939 + vertex 1.5361 1.01931 2.49943 + endloop + endfacet + facet normal -0.611956 0.39053 0.687748 + outer loop + vertex 1.53846 1.02195 2.50059 + vertex 1.54024 1.02402 2.50101 + vertex 1.53775 1.023 2.49937 + endloop + endfacet + facet normal 0.521828 0.674868 0.521775 + outer loop + vertex 1.53306 1.01778 2.50035 + vertex 1.53252 1.01894 2.49939 + vertex 1.53228 1.01826 2.5005 + endloop + endfacet + facet normal -0.55106 0.83139 -0.07158 + outer loop + vertex 1.54 1.02699 2.485 + vertex 1.53563 1.02415 2.48567 + vertex 1.53789 1.02582 2.48765 + endloop + endfacet + facet normal -0.534646 0.717291 -0.446818 + outer loop + vertex 1.53733 1.025 2.485 + vertex 1.53563 1.02415 2.48567 + vertex 1.54 1.02699 2.485 + endloop + endfacet + facet normal -0.587273 0.80888 0.0286919 + outer loop + vertex 1.53789 1.02582 2.48765 + vertex 1.53473 1.02345 2.48976 + vertex 1.53755 1.02539 2.49263 + endloop + endfacet + facet normal -0.59726 0.802026 0.0059496 + outer loop + vertex 1.53563 1.02415 2.48567 + vertex 1.53473 1.02345 2.48976 + vertex 1.53789 1.02582 2.48765 + endloop + endfacet + facet normal -0.70441 0.696756 0.135417 + outer loop + vertex 1.53755 1.02539 2.49263 + vertex 1.53526 1.02254 2.49541 + vertex 1.53828 1.02523 2.49727 + endloop + endfacet + facet normal -0.675592 0.715399 0.178269 + outer loop + vertex 1.53473 1.02345 2.48976 + vertex 1.53526 1.02254 2.49541 + vertex 1.53755 1.02539 2.49263 + endloop + endfacet + facet normal -0.763497 0.528833 0.370686 + outer loop + vertex 1.53828 1.02523 2.49727 + vertex 1.53775 1.023 2.49937 + vertex 1.53973 1.02542 2.49999 + endloop + endfacet + facet normal -0.734641 0.548692 0.399048 + outer loop + vertex 1.53526 1.02254 2.49541 + vertex 1.53775 1.023 2.49937 + vertex 1.53828 1.02523 2.49727 + endloop + endfacet + facet normal -0.60738 0.307906 0.732314 + outer loop + vertex 1.53973 1.02542 2.49999 + vertex 1.53775 1.023 2.49937 + vertex 1.54024 1.02402 2.50101 + endloop + endfacet + facet normal -0.974431 -0.174739 -0.141248 + outer loop + vertex 1.53784 1.1227 2.51596 + vertex 1.53716 1.12517 2.51755 + vertex 1.53759 1.12574 2.51391 + endloop + endfacet + facet normal -0.97141 -0.231602 -0.052173 + outer loop + vertex 1.53784 1.1227 2.51596 + vertex 1.53773 1.12249 2.51881 + vertex 1.53716 1.12517 2.51755 + endloop + endfacet + facet normal -0.975305 -0.126627 -0.180956 + outer loop + vertex 1.53759 1.12574 2.51391 + vertex 1.53691 1.12863 2.51551 + vertex 1.53745 1.12879 2.51254 + endloop + endfacet + facet normal -0.978817 -0.151177 -0.138064 + outer loop + vertex 1.53716 1.12517 2.51755 + vertex 1.53691 1.12863 2.51551 + vertex 1.53759 1.12574 2.51391 + endloop + endfacet + facet normal -0.981406 -0.185134 0.0506812 + outer loop + vertex 1.53737 1.12485 2.52044 + vertex 1.53716 1.12517 2.51755 + vertex 1.53773 1.12249 2.51881 + endloop + endfacet + facet normal -0.993543 -0.0955288 0.0612169 + outer loop + vertex 1.53737 1.12485 2.52044 + vertex 1.53693 1.12935 2.52021 + vertex 1.53716 1.12517 2.51755 + endloop + endfacet + facet normal -0.997851 -0.0644141 0.0119867 + outer loop + vertex 1.53693 1.12935 2.52021 + vertex 1.53691 1.12863 2.51551 + vertex 1.53716 1.12517 2.51755 + endloop + endfacet + facet normal -0.967101 -0.0838407 0.240179 + outer loop + vertex 1.53737 1.12485 2.52044 + vertex 1.53776 1.12652 2.52259 + vertex 1.53693 1.12935 2.52021 + endloop + endfacet + facet normal -0.85873 0.118307 -0.498585 + outer loop + vertex 1.53828 1.13129 2.51085 + vertex 1.53717 1.13184 2.51288 + vertex 1.53877 1.13514 2.51092 + endloop + endfacet + facet normal -0.881377 -0.0254737 -0.471727 + outer loop + vertex 1.53745 1.12879 2.51254 + vertex 1.53717 1.13184 2.51288 + vertex 1.53828 1.13129 2.51085 + endloop + endfacet + facet normal -0.981574 -0.0672347 -0.178862 + outer loop + vertex 1.53745 1.12879 2.51254 + vertex 1.53691 1.12863 2.51551 + vertex 1.53717 1.13184 2.51288 + endloop + endfacet + facet normal -0.985748 -0.0515342 -0.16014 + outer loop + vertex 1.53691 1.12863 2.51551 + vertex 1.53657 1.13286 2.51627 + vertex 1.53717 1.13184 2.51288 + endloop + endfacet + facet normal -0.99637 -0.0838135 0.01493 + outer loop + vertex 1.53691 1.12863 2.51551 + vertex 1.53693 1.12935 2.52021 + vertex 1.53657 1.13286 2.51627 + endloop + endfacet + facet normal -0.994434 -0.105271 -0.0043866 + outer loop + vertex 1.53657 1.13286 2.51627 + vertex 1.53693 1.12935 2.52021 + vertex 1.53638 1.13451 2.51967 + endloop + endfacet + facet normal -0.958877 -0.0480699 0.279723 + outer loop + vertex 1.53801 1.12989 2.52402 + vertex 1.53693 1.12935 2.52021 + vertex 1.53776 1.12652 2.52259 + endloop + endfacet + facet normal -0.948541 -0.130292 0.288606 + outer loop + vertex 1.53801 1.12989 2.52402 + vertex 1.53732 1.13475 2.52396 + vertex 1.53693 1.12935 2.52021 + endloop + endfacet + facet normal -0.97262 -0.079685 0.218313 + outer loop + vertex 1.53732 1.13475 2.52396 + vertex 1.53638 1.13451 2.51967 + vertex 1.53693 1.12935 2.52021 + endloop + endfacet + facet normal -0.719092 -0.0936289 0.688579 + outer loop + vertex 1.53801 1.12989 2.52402 + vertex 1.54023 1.13294 2.52675 + vertex 1.53732 1.13475 2.52396 + endloop + endfacet + facet normal -0.614245 0.499273 -0.611088 + outer loop + vertex 1.53877 1.13514 2.51092 + vertex 1.53725 1.13625 2.51335 + vertex 1.54 1.14 2.51365 + endloop + endfacet + facet normal -0.830651 0.0729422 -0.551994 + outer loop + vertex 1.53717 1.13184 2.51288 + vertex 1.53725 1.13625 2.51335 + vertex 1.53877 1.13514 2.51092 + endloop + endfacet + facet normal -0.981885 0.036566 -0.185917 + outer loop + vertex 1.53717 1.13184 2.51288 + vertex 1.53657 1.13286 2.51627 + vertex 1.53725 1.13625 2.51335 + endloop + endfacet + facet normal -0.961791 -0.0406058 -0.270755 + outer loop + vertex 1.53725 1.13625 2.51335 + vertex 1.53657 1.13286 2.51627 + vertex 1.53629 1.13756 2.51655 + endloop + endfacet + facet normal -0.997989 -0.0568627 -0.028013 + outer loop + vertex 1.53657 1.13286 2.51627 + vertex 1.53638 1.13451 2.51967 + vertex 1.53629 1.13756 2.51655 + endloop + endfacet + facet normal -0.997364 -0.0637088 -0.0347296 + outer loop + vertex 1.53629 1.13756 2.51655 + vertex 1.53638 1.13451 2.51967 + vertex 1.53607 1.13876 2.52071 + endloop + endfacet + facet normal -0.967723 -0.123465 0.219702 + outer loop + vertex 1.53638 1.13451 2.51967 + vertex 1.53732 1.13475 2.52396 + vertex 1.53607 1.13876 2.52071 + endloop + endfacet + facet normal -0.971554 -0.165337 0.169547 + outer loop + vertex 1.53607 1.13876 2.52071 + vertex 1.53732 1.13475 2.52396 + vertex 1.53658 1.14076 2.52559 + endloop + endfacet + facet normal -0.765093 -0.253925 0.591738 + outer loop + vertex 1.53732 1.13475 2.52396 + vertex 1.53937 1.13882 2.52835 + vertex 1.53658 1.14076 2.52559 + endloop + endfacet + facet normal -0.749203 -0.274031 0.602994 + outer loop + vertex 1.54023 1.13294 2.52675 + vertex 1.53937 1.13882 2.52835 + vertex 1.53732 1.13475 2.52396 + endloop + endfacet + facet normal -0.04348 -0.0438805 -0.99809 + outer loop + vertex 1.54 1.14 2.51365 + vertex 1.53727 1.1411 2.51372 + vertex 1.54 1.145 2.51343 + endloop + endfacet + facet normal 0.00475639 0.0763114 -0.997073 + outer loop + vertex 1.53725 1.13625 2.51335 + vertex 1.53727 1.1411 2.51372 + vertex 1.54 1.14 2.51365 + endloop + endfacet + facet normal -0.954757 0.0264107 -0.296213 + outer loop + vertex 1.53725 1.13625 2.51335 + vertex 1.53629 1.13756 2.51655 + vertex 1.53727 1.1411 2.51372 + endloop + endfacet + facet normal -0.926634 -0.043167 -0.373477 + outer loop + vertex 1.53727 1.1411 2.51372 + vertex 1.53629 1.13756 2.51655 + vertex 1.53598 1.14231 2.51678 + endloop + endfacet + facet normal -0.997309 -0.064718 -0.0344364 + outer loop + vertex 1.53629 1.13756 2.51655 + vertex 1.53607 1.13876 2.52071 + vertex 1.53598 1.14231 2.51678 + endloop + endfacet + facet normal -0.990383 -0.113676 -0.0788679 + outer loop + vertex 1.53598 1.14231 2.51678 + vertex 1.53607 1.13876 2.52071 + vertex 1.53551 1.14349 2.52097 + endloop + endfacet + facet normal -0.980102 -0.12525 0.153988 + outer loop + vertex 1.53607 1.13876 2.52071 + vertex 1.53658 1.14076 2.52559 + vertex 1.53551 1.14349 2.52097 + endloop + endfacet + facet normal -0.966684 -0.242595 0.0816728 + outer loop + vertex 1.53551 1.14349 2.52097 + vertex 1.53658 1.14076 2.52559 + vertex 1.53547 1.14485 2.52458 + endloop + endfacet + facet normal -0.764755 -0.473543 0.436929 + outer loop + vertex 1.53799 1.14195 2.52932 + vertex 1.53658 1.14076 2.52559 + vertex 1.53937 1.13882 2.52835 + endloop + endfacet + facet normal -0.880279 -0.243177 0.407399 + outer loop + vertex 1.53799 1.14195 2.52932 + vertex 1.53674 1.14519 2.52856 + vertex 1.53658 1.14076 2.52559 + endloop + endfacet + facet normal -0.933709 -0.17672 0.311379 + outer loop + vertex 1.53674 1.14519 2.52856 + vertex 1.53547 1.14485 2.52458 + vertex 1.53658 1.14076 2.52559 + endloop + endfacet + facet normal -0.688585 -0.0964002 0.718719 + outer loop + vertex 1.53799 1.14195 2.52932 + vertex 1.53931 1.14484 2.53098 + vertex 1.53674 1.14519 2.52856 + endloop + endfacet + facet normal -0.134288 -0.0534584 -0.989499 + outer loop + vertex 1.54 1.145 2.51343 + vertex 1.53711 1.146 2.51377 + vertex 1.54 1.15 2.51316 + endloop + endfacet + facet normal -0.114198 0.00592763 -0.99344 + outer loop + vertex 1.53727 1.1411 2.51372 + vertex 1.53711 1.146 2.51377 + vertex 1.54 1.145 2.51343 + endloop + endfacet + facet normal -0.924918 -0.0268843 -0.379216 + outer loop + vertex 1.53727 1.1411 2.51372 + vertex 1.53598 1.14231 2.51678 + vertex 1.53711 1.146 2.51377 + endloop + endfacet + facet normal -0.911642 -0.0539743 -0.407427 + outer loop + vertex 1.53711 1.146 2.51377 + vertex 1.53598 1.14231 2.51678 + vertex 1.53565 1.14714 2.51689 + endloop + endfacet + facet normal -0.993495 -0.0663694 -0.0925406 + outer loop + vertex 1.53598 1.14231 2.51678 + vertex 1.53551 1.14349 2.52097 + vertex 1.53565 1.14714 2.51689 + endloop + endfacet + facet normal -0.982608 -0.120904 -0.140941 + outer loop + vertex 1.53565 1.14714 2.51689 + vertex 1.53551 1.14349 2.52097 + vertex 1.53495 1.14794 2.52106 + endloop + endfacet + facet normal -0.991344 -0.125885 0.0372837 + outer loop + vertex 1.53551 1.14349 2.52097 + vertex 1.53547 1.14485 2.52458 + vertex 1.53495 1.14794 2.52106 + endloop + endfacet + facet normal -0.991366 -0.125653 0.0374907 + outer loop + vertex 1.53495 1.14794 2.52106 + vertex 1.53547 1.14485 2.52458 + vertex 1.53504 1.14857 2.5255 + endloop + endfacet + facet normal -0.931694 -0.186725 0.311576 + outer loop + vertex 1.53547 1.14485 2.52458 + vertex 1.53674 1.14519 2.52856 + vertex 1.53504 1.14857 2.5255 + endloop + endfacet + facet normal -0.926382 -0.155673 0.342903 + outer loop + vertex 1.53504 1.14857 2.5255 + vertex 1.53674 1.14519 2.52856 + vertex 1.53623 1.15015 2.52943 + endloop + endfacet + facet normal -0.596585 -0.197623 0.777838 + outer loop + vertex 1.53674 1.14519 2.52856 + vertex 1.53913 1.14876 2.5313 + vertex 1.53623 1.15015 2.52943 + endloop + endfacet + facet normal -0.688554 -0.091331 0.719411 + outer loop + vertex 1.53931 1.14484 2.53098 + vertex 1.53913 1.14876 2.5313 + vertex 1.53674 1.14519 2.52856 + endloop + endfacet + facet normal -0.229864 0.00389815 -0.973215 + outer loop + vertex 1.54 1.15 2.51316 + vertex 1.53699 1.1511 2.51388 + vertex 1.54 1.155 2.51318 + endloop + endfacet + facet normal -0.225917 0.0151926 -0.974028 + outer loop + vertex 1.53711 1.146 2.51377 + vertex 1.53699 1.1511 2.51388 + vertex 1.54 1.15 2.51316 + endloop + endfacet + facet normal -0.907217 -0.0125443 -0.420476 + outer loop + vertex 1.53711 1.146 2.51377 + vertex 1.53565 1.14714 2.51689 + vertex 1.53699 1.1511 2.51388 + endloop + endfacet + facet normal -0.896824 -0.031817 -0.441243 + outer loop + vertex 1.53699 1.1511 2.51388 + vertex 1.53565 1.14714 2.51689 + vertex 1.53532 1.15206 2.5172 + endloop + endfacet + facet normal -0.986479 -0.0561963 -0.153955 + outer loop + vertex 1.53565 1.14714 2.51689 + vertex 1.53495 1.14794 2.52106 + vertex 1.53532 1.15206 2.5172 + endloop + endfacet + facet normal -0.978281 -0.0883972 -0.187487 + outer loop + vertex 1.53532 1.15206 2.5172 + vertex 1.53495 1.14794 2.52106 + vertex 1.53442 1.15253 2.52166 + endloop + endfacet + facet normal -0.992181 -0.119322 0.0366035 + outer loop + vertex 1.53495 1.14794 2.52106 + vertex 1.53504 1.14857 2.5255 + vertex 1.53442 1.15253 2.52166 + endloop + endfacet + facet normal -0.989993 -0.140366 0.0145384 + outer loop + vertex 1.53442 1.15253 2.52166 + vertex 1.53504 1.14857 2.5255 + vertex 1.53439 1.15325 2.52639 + endloop + endfacet + facet normal -0.914323 -0.194915 0.354995 + outer loop + vertex 1.53504 1.14857 2.5255 + vertex 1.53623 1.15015 2.52943 + vertex 1.53439 1.15325 2.52639 + endloop + endfacet + facet normal -0.912073 -0.180876 0.367977 + outer loop + vertex 1.53439 1.15325 2.52639 + vertex 1.53623 1.15015 2.52943 + vertex 1.53567 1.15489 2.53038 + endloop + endfacet + facet normal -0.532531 -0.225665 0.815773 + outer loop + vertex 1.53623 1.15015 2.52943 + vertex 1.53877 1.1534 2.53199 + vertex 1.53567 1.15489 2.53038 + endloop + endfacet + facet normal -0.58881 -0.162741 0.791719 + outer loop + vertex 1.53913 1.14876 2.5313 + vertex 1.53877 1.1534 2.53199 + vertex 1.53623 1.15015 2.52943 + endloop + endfacet + facet normal -0.421561 0.0633208 -0.904586 + outer loop + vertex 1.54 1.155 2.51318 + vertex 1.53708 1.15731 2.5147 + vertex 1.54 1.16 2.51353 + endloop + endfacet + facet normal -0.37718 0.127865 -0.917271 + outer loop + vertex 1.53699 1.1511 2.51388 + vertex 1.53708 1.15731 2.5147 + vertex 1.54 1.155 2.51318 + endloop + endfacet + facet normal -0.882397 0.0748734 -0.464509 + outer loop + vertex 1.53699 1.1511 2.51388 + vertex 1.53532 1.15206 2.5172 + vertex 1.53708 1.15731 2.5147 + endloop + endfacet + facet normal -0.867922 0.0562461 -0.493506 + outer loop + vertex 1.53708 1.15731 2.5147 + vertex 1.53532 1.15206 2.5172 + vertex 1.53493 1.1568 2.51842 + endloop + endfacet + facet normal -0.980522 -0.0302189 -0.194071 + outer loop + vertex 1.53532 1.15206 2.5172 + vertex 1.53442 1.15253 2.52166 + vertex 1.53493 1.1568 2.51842 + endloop + endfacet + facet normal -0.962738 -0.0808548 -0.258066 + outer loop + vertex 1.53493 1.1568 2.51842 + vertex 1.53442 1.15253 2.52166 + vertex 1.53374 1.15803 2.52248 + endloop + endfacet + facet normal -0.992175 -0.12427 0.0120543 + outer loop + vertex 1.53442 1.15253 2.52166 + vertex 1.53439 1.15325 2.52639 + vertex 1.53374 1.15803 2.52248 + endloop + endfacet + facet normal -0.987067 -0.157581 -0.0294575 + outer loop + vertex 1.53374 1.15803 2.52248 + vertex 1.53439 1.15325 2.52639 + vertex 1.53356 1.15811 2.52796 + endloop + endfacet + facet normal -0.875835 -0.276367 0.395644 + outer loop + vertex 1.53439 1.15325 2.52639 + vertex 1.53567 1.15489 2.53038 + vertex 1.53356 1.15811 2.52796 + endloop + endfacet + facet normal -0.853043 -0.195043 0.484021 + outer loop + vertex 1.53356 1.15811 2.52796 + vertex 1.53567 1.15489 2.53038 + vertex 1.53536 1.15898 2.53149 + endloop + endfacet + facet normal -0.438903 -0.265431 0.858435 + outer loop + vertex 1.53567 1.15489 2.53038 + vertex 1.53831 1.15826 2.53277 + vertex 1.53536 1.15898 2.53149 + endloop + endfacet + facet normal -0.521232 -0.183074 0.833548 + outer loop + vertex 1.53877 1.1534 2.53199 + vertex 1.53831 1.15826 2.53277 + vertex 1.53567 1.15489 2.53038 + endloop + endfacet + facet normal -0.593246 0.322682 -0.73752 + outer loop + vertex 1.54 1.16 2.51353 + vertex 1.53708 1.15731 2.5147 + vertex 1.54 1.16336 2.515 + endloop + endfacet + facet normal -0.64211 0.393215 -0.658086 + outer loop + vertex 1.54 1.16336 2.515 + vertex 1.53588 1.165 2.52 + vertex 1.54 1.165 2.51598 + endloop + endfacet + facet normal -0.662273 0.35229 -0.661277 + outer loop + vertex 1.54 1.16336 2.515 + vertex 1.53708 1.15731 2.5147 + vertex 1.53588 1.165 2.52 + endloop + endfacet + facet normal -0.861189 0.190464 -0.471251 + outer loop + vertex 1.53708 1.15731 2.5147 + vertex 1.53493 1.1568 2.51842 + vertex 1.53588 1.165 2.52 + endloop + endfacet + facet normal 0.141511 -0.463474 -0.874738 + outer loop + vertex 1.53309 1.16215 2.52106 + vertex 1.53326 1.16501 2.51957 + vertex 1.53588 1.165 2.52 + endloop + endfacet + facet normal -0.023138 -0.328447 -0.944239 + outer loop + vertex 1.53309 1.16215 2.52106 + vertex 1.53588 1.165 2.52 + vertex 1.53374 1.15803 2.52248 + endloop + endfacet + facet normal -0.93024 0.170372 -0.325002 + outer loop + vertex 1.53374 1.15803 2.52248 + vertex 1.53588 1.165 2.52 + vertex 1.53493 1.1568 2.51842 + endloop + endfacet + facet normal -0.922856 -0.384368 -0.0244471 + outer loop + vertex 1.53374 1.15803 2.52248 + vertex 1.53356 1.15811 2.52796 + vertex 1.53241 1.16109 2.52449 + endloop + endfacet + facet normal -0.936763 -0.236366 -0.25808 + outer loop + vertex 1.53309 1.16215 2.52106 + vertex 1.53374 1.15803 2.52248 + vertex 1.53241 1.16109 2.52449 + endloop + endfacet + facet normal -0.955485 -0.286489 0.0705086 + outer loop + vertex 1.53246 1.16181 2.52807 + vertex 1.53241 1.16109 2.52449 + vertex 1.53356 1.15811 2.52796 + endloop + endfacet + facet normal -0.855519 -0.267489 0.443324 + outer loop + vertex 1.53246 1.16181 2.52807 + vertex 1.53356 1.15811 2.52796 + vertex 1.53392 1.162 2.53101 + endloop + endfacet + facet normal -0.81349 -0.309684 0.492271 + outer loop + vertex 1.53392 1.162 2.53101 + vertex 1.53356 1.15811 2.52796 + vertex 1.53536 1.15898 2.53149 + endloop + endfacet + facet normal -0.523563 -0.116285 0.844014 + outer loop + vertex 1.53536 1.15898 2.53149 + vertex 1.53755 1.16354 2.53347 + vertex 1.53392 1.162 2.53101 + endloop + endfacet + facet normal -0.429468 -0.179336 0.885097 + outer loop + vertex 1.53831 1.15826 2.53277 + vertex 1.53755 1.16354 2.53347 + vertex 1.53536 1.15898 2.53149 + endloop + endfacet + facet normal 0.161535 0.0298636 -0.986415 + outer loop + vertex 1.53588 1.165 2.52 + vertex 1.53326 1.16501 2.51957 + vertex 1.535 1.16976 2.52 + endloop + endfacet + facet normal -0.860964 -0.246957 0.444695 + outer loop + vertex 1.53246 1.16181 2.52807 + vertex 1.53392 1.162 2.53101 + vertex 1.53254 1.16479 2.52989 + endloop + endfacet + facet normal -0.78503 -0.146082 0.601987 + outer loop + vertex 1.53392 1.162 2.53101 + vertex 1.53456 1.16705 2.53307 + vertex 1.53254 1.16479 2.52989 + endloop + endfacet + facet normal -0.451452 -0.287183 0.844818 + outer loop + vertex 1.53392 1.162 2.53101 + vertex 1.53755 1.16354 2.53347 + vertex 1.53456 1.16705 2.53307 + endloop + endfacet + facet normal -0.349146 -0.191814 0.917227 + outer loop + vertex 1.53755 1.16354 2.53347 + vertex 1.53853 1.16912 2.53501 + vertex 1.53456 1.16705 2.53307 + endloop + endfacet + facet normal -0.204115 -0.432677 0.878139 + outer loop + vertex 1.53456 1.16705 2.53307 + vertex 1.53853 1.16912 2.53501 + vertex 1.5363 1.17119 2.53551 + endloop + endfacet + facet normal -0.453147 -0.304616 0.837775 + outer loop + vertex 1.53368 1.17109 2.53406 + vertex 1.53456 1.16705 2.53307 + vertex 1.5363 1.17119 2.53551 + endloop + endfacet + facet normal -0.456455 -0.28638 0.842399 + outer loop + vertex 1.5363 1.17119 2.53551 + vertex 1.53521 1.17441 2.53601 + vertex 1.53368 1.17109 2.53406 + endloop + endfacet + facet normal -0.136186 -0.197541 0.970789 + outer loop + vertex 1.53851 1.17483 2.53656 + vertex 1.53521 1.17441 2.53601 + vertex 1.5363 1.17119 2.53551 + endloop + endfacet + facet normal -0.140082 -0.172781 0.974948 + outer loop + vertex 1.53851 1.17483 2.53656 + vertex 1.53819 1.17841 2.53715 + vertex 1.53521 1.17441 2.53601 + endloop + endfacet + facet normal -0.171172 -0.149276 0.973867 + outer loop + vertex 1.53521 1.17441 2.53601 + vertex 1.53819 1.17841 2.53715 + vertex 1.53443 1.1785 2.5365 + endloop + endfacet + facet normal -0.000201962 0.000108945 -1 + outer loop + vertex 1.53753 1.19 2.52 + vertex 1.535 1.18531 2.52 + vertex 1.53404 1.19009 2.52 + endloop + endfacet + facet normal -0.000204919 -8.15904e-07 -1 + outer loop + vertex 1.53751 1.195 2.52 + vertex 1.53753 1.19 2.52 + vertex 1.53404 1.19009 2.52 + endloop + endfacet + facet normal -0.665203 0.470539 -0.57974 + outer loop + vertex 1.535 1.195 2.52288 + vertex 1.53751 1.195 2.52 + vertex 1.53404 1.19009 2.52 + endloop + endfacet + facet normal 0.210824 -0.0447235 0.9765 + outer loop + vertex 1.53648 1.42983 2.5659 + vertex 1.53605 1.43299 2.56614 + vertex 1.53251 1.42799 2.56667 + endloop + endfacet + facet normal -0.891282 0.0837881 -0.445641 + outer loop + vertex 1.5355 1.85 2.52 + vertex 1.53503 1.845 2.52 + vertex 1.535 1.845 2.52006 + endloop + endfacet + facet normal 0.106736 -0.0226199 -0.99403 + outer loop + vertex 1.53315 1.84914 2.51977 + vertex 1.5355 1.85 2.52 + vertex 1.535 1.845 2.52006 + endloop + endfacet + facet normal 0.0984703 0.000197208 -0.99514 + outer loop + vertex 1.53549 1.855 2.52 + vertex 1.5355 1.85 2.52 + vertex 1.53315 1.84914 2.51977 + endloop + endfacet + facet normal -0.0300163 0.0515111 -0.998221 + outer loop + vertex 1.5331 1.85403 2.52002 + vertex 1.53549 1.855 2.52 + vertex 1.53315 1.84914 2.51977 + endloop + endfacet + facet normal -0.0096142 0.00128822 -0.999953 + outer loop + vertex 1.53616 1.86 2.52 + vertex 1.53549 1.855 2.52 + vertex 1.5331 1.85403 2.52002 + endloop + endfacet + facet normal -0.307089 0.153804 -0.93917 + outer loop + vertex 1.53311 1.85792 2.52066 + vertex 1.53616 1.86 2.52 + vertex 1.5331 1.85403 2.52002 + endloop + endfacet + facet normal -0.927436 0.201123 -0.315295 + outer loop + vertex 1.53311 1.85792 2.52066 + vertex 1.53243 1.85949 2.52364 + vertex 1.53421 1.86293 2.5206 + endloop + endfacet + facet normal -0.237692 0.0420727 -0.970429 + outer loop + vertex 1.53311 1.85792 2.52066 + vertex 1.53421 1.86293 2.5206 + vertex 1.53616 1.86 2.52 + endloop + endfacet + facet normal -0.250393 0.033055 -0.96758 + outer loop + vertex 1.53616 1.86 2.52 + vertex 1.53421 1.86293 2.5206 + vertex 1.53682 1.865 2.52 + endloop + endfacet + facet normal -0.931637 0.243214 -0.27 + outer loop + vertex 1.53335 1.86438 2.52488 + vertex 1.53421 1.86293 2.5206 + vertex 1.53243 1.85949 2.52364 + endloop + endfacet + facet normal -0.971536 0.210014 -0.109599 + outer loop + vertex 1.53232 1.8608 2.52714 + vertex 1.53335 1.86438 2.52488 + vertex 1.53243 1.85949 2.52364 + endloop + endfacet + facet normal -0.958085 0.285985 0.0168988 + outer loop + vertex 1.53335 1.86438 2.52488 + vertex 1.53232 1.8608 2.52714 + vertex 1.53314 1.86343 2.52877 + endloop + endfacet + facet normal -0.00979236 0.362156 0.932066 + outer loop + vertex 1.53458 1.85748 2.53515 + vertex 1.53576 1.85512 2.53608 + vertex 1.53857 1.85834 2.53486 + endloop + endfacet + facet normal -0.0289618 0.439198 0.897923 + outer loop + vertex 1.53458 1.85748 2.53515 + vertex 1.53857 1.85834 2.53486 + vertex 1.53504 1.86109 2.5334 + endloop + endfacet + facet normal -0.209593 0.234186 0.94933 + outer loop + vertex 1.53504 1.86109 2.5334 + vertex 1.53857 1.85834 2.53486 + vertex 1.53845 1.86297 2.53369 + endloop + endfacet + facet normal -0.217277 0.262004 0.94029 + outer loop + vertex 1.53576 1.85512 2.53608 + vertex 1.53458 1.85748 2.53515 + vertex 1.53343 1.85439 2.53574 + endloop + endfacet + facet normal -0.232366 0.00882528 -0.972588 + outer loop + vertex 1.53682 1.865 2.52 + vertex 1.53421 1.86293 2.5206 + vertex 1.53701 1.87 2.52 + endloop + endfacet + facet normal -0.348909 0.0581646 -0.93535 + outer loop + vertex 1.53701 1.87 2.52 + vertex 1.53421 1.86293 2.5206 + vertex 1.53441 1.86803 2.52085 + endloop + endfacet + facet normal -0.975842 0.0487387 -0.212971 + outer loop + vertex 1.53421 1.86293 2.5206 + vertex 1.53335 1.86438 2.52488 + vertex 1.53441 1.86803 2.52085 + endloop + endfacet + facet normal -0.980709 0.157232 -0.116136 + outer loop + vertex 1.53441 1.86803 2.52085 + vertex 1.53335 1.86438 2.52488 + vertex 1.53416 1.86901 2.52436 + endloop + endfacet + facet normal -0.89001 0.309289 0.334995 + outer loop + vertex 1.53314 1.86343 2.52877 + vertex 1.53417 1.86386 2.53113 + vertex 1.53473 1.868 2.52878 + endloop + endfacet + facet normal -0.943959 0.328857 0.0281744 + outer loop + vertex 1.53314 1.86343 2.52877 + vertex 1.53473 1.868 2.52878 + vertex 1.53335 1.86438 2.52488 + endloop + endfacet + facet normal -0.967924 0.186861 0.167949 + outer loop + vertex 1.53335 1.86438 2.52488 + vertex 1.53473 1.868 2.52878 + vertex 1.53416 1.86901 2.52436 + endloop + endfacet + facet normal -0.622639 0.447776 0.64173 + outer loop + vertex 1.53417 1.86386 2.53113 + vertex 1.53706 1.86627 2.53226 + vertex 1.53473 1.868 2.52878 + endloop + endfacet + facet normal -0.596408 0.387649 0.70287 + outer loop + vertex 1.53417 1.86386 2.53113 + vertex 1.53504 1.86109 2.5334 + vertex 1.53706 1.86627 2.53226 + endloop + endfacet + facet normal -0.242885 0.2982 0.923084 + outer loop + vertex 1.53504 1.86109 2.5334 + vertex 1.53845 1.86297 2.53369 + vertex 1.53706 1.86627 2.53226 + endloop + endfacet + facet normal -0.994804 -0.00796925 -0.101492 + outer loop + vertex 1.53752 1.87 2.515 + vertex 1.53701 1.87 2.52 + vertex 1.53748 1.875 2.515 + endloop + endfacet + facet normal 0.247739 -0.696602 -0.673328 + outer loop + vertex 1.53748 1.875 2.515 + vertex 1.53701 1.87 2.52 + vertex 1.53549 1.87231 2.51705 + endloop + endfacet + facet normal 0.29118 -0.67452 -0.678408 + outer loop + vertex 1.53701 1.87 2.52 + vertex 1.53441 1.86803 2.52085 + vertex 1.53549 1.87231 2.51705 + endloop + endfacet + facet normal -0.973426 0.0455679 -0.224421 + outer loop + vertex 1.53549 1.87231 2.51705 + vertex 1.53441 1.86803 2.52085 + vertex 1.53461 1.87246 2.5209 + endloop + endfacet + facet normal -0.995309 0.0447734 -0.085762 + outer loop + vertex 1.53441 1.86803 2.52085 + vertex 1.53416 1.86901 2.52436 + vertex 1.53461 1.87246 2.5209 + endloop + endfacet + facet normal -0.988891 0.147603 0.0175676 + outer loop + vertex 1.53461 1.87246 2.5209 + vertex 1.53416 1.86901 2.52436 + vertex 1.53476 1.87296 2.52536 + endloop + endfacet + facet normal -0.981897 0.112157 0.152642 + outer loop + vertex 1.53416 1.86901 2.52436 + vertex 1.53473 1.868 2.52878 + vertex 1.53476 1.87296 2.52536 + endloop + endfacet + facet normal -0.93851 0.200472 0.281086 + outer loop + vertex 1.53476 1.87296 2.52536 + vertex 1.53473 1.868 2.52878 + vertex 1.536 1.8736 2.52904 + endloop + endfacet + facet normal -0.763782 0.144769 0.62903 + outer loop + vertex 1.53473 1.868 2.52878 + vertex 1.53715 1.87058 2.53113 + vertex 1.536 1.8736 2.52904 + endloop + endfacet + facet normal -0.774715 0.174321 0.607806 + outer loop + vertex 1.53706 1.86627 2.53226 + vertex 1.53715 1.87058 2.53113 + vertex 1.53473 1.868 2.52878 + endloop + endfacet + facet normal -0.318681 0.0246244 -0.947542 + outer loop + vertex 1.54 1.875 2.51255 + vertex 1.53692 1.87586 2.51361 + vertex 1.54 1.88 2.51268 + endloop + endfacet + facet normal -0.366612 -0.850532 -0.377083 + outer loop + vertex 1.53748 1.875 2.515 + vertex 1.53692 1.87586 2.51361 + vertex 1.54 1.875 2.51255 + endloop + endfacet + facet normal 0.36476 -0.720022 -0.590355 + outer loop + vertex 1.53748 1.875 2.515 + vertex 1.53549 1.87231 2.51705 + vertex 1.53692 1.87586 2.51361 + endloop + endfacet + facet normal -0.901241 -0.053443 -0.430011 + outer loop + vertex 1.53692 1.87586 2.51361 + vertex 1.53549 1.87231 2.51705 + vertex 1.53541 1.87629 2.51673 + endloop + endfacet + facet normal -0.974403 -0.0382485 -0.22153 + outer loop + vertex 1.53549 1.87231 2.51705 + vertex 1.53461 1.87246 2.5209 + vertex 1.53541 1.87629 2.51673 + endloop + endfacet + facet normal -0.990128 0.0839072 -0.112273 + outer loop + vertex 1.53541 1.87629 2.51673 + vertex 1.53461 1.87246 2.5209 + vertex 1.53498 1.8772 2.52121 + endloop + endfacet + facet normal -0.996816 0.0753899 0.0259535 + outer loop + vertex 1.53461 1.87246 2.5209 + vertex 1.53476 1.87296 2.52536 + vertex 1.53498 1.8772 2.52121 + endloop + endfacet + facet normal -0.983262 0.150157 0.103195 + outer loop + vertex 1.53498 1.8772 2.52121 + vertex 1.53476 1.87296 2.52536 + vertex 1.53556 1.87797 2.52566 + endloop + endfacet + facet normal -0.946065 0.132645 0.295579 + outer loop + vertex 1.53476 1.87296 2.52536 + vertex 1.536 1.8736 2.52904 + vertex 1.53556 1.87797 2.52566 + endloop + endfacet + facet normal -0.860155 0.254636 0.441921 + outer loop + vertex 1.53556 1.87797 2.52566 + vertex 1.536 1.8736 2.52904 + vertex 1.53735 1.87816 2.52904 + endloop + endfacet + facet normal -0.66423 0.196834 0.721149 + outer loop + vertex 1.536 1.8736 2.52904 + vertex 1.53836 1.87425 2.53104 + vertex 1.53735 1.87816 2.52904 + endloop + endfacet + facet normal -0.66458 0.237416 0.708496 + outer loop + vertex 1.53715 1.87058 2.53113 + vertex 1.53836 1.87425 2.53104 + vertex 1.536 1.8736 2.52904 + endloop + endfacet + facet normal -0.252895 0.059859 -0.96564 + outer loop + vertex 1.54 1.88 2.51268 + vertex 1.53703 1.87998 2.51346 + vertex 1.54 1.885 2.51299 + endloop + endfacet + facet normal -0.252818 -0.0287177 -0.967088 + outer loop + vertex 1.53692 1.87586 2.51361 + vertex 1.53703 1.87998 2.51346 + vertex 1.54 1.88 2.51268 + endloop + endfacet + facet normal -0.899178 0.00800215 -0.437509 + outer loop + vertex 1.53692 1.87586 2.51361 + vertex 1.53541 1.87629 2.51673 + vertex 1.53703 1.87998 2.51346 + endloop + endfacet + facet normal -0.920351 0.062947 -0.385994 + outer loop + vertex 1.53703 1.87998 2.51346 + vertex 1.53541 1.87629 2.51673 + vertex 1.5357 1.88111 2.51681 + endloop + endfacet + facet normal -0.99218 0.0624243 -0.108087 + outer loop + vertex 1.53541 1.87629 2.51673 + vertex 1.53498 1.8772 2.52121 + vertex 1.5357 1.88111 2.51681 + endloop + endfacet + facet normal -0.992112 0.101936 -0.0729569 + outer loop + vertex 1.5357 1.88111 2.51681 + vertex 1.53498 1.8772 2.52121 + vertex 1.5355 1.88242 2.52133 + endloop + endfacet + facet normal -0.988822 0.0972835 0.112989 + outer loop + vertex 1.53498 1.8772 2.52121 + vertex 1.53556 1.87797 2.52566 + vertex 1.5355 1.88242 2.52133 + endloop + endfacet + facet normal -0.955724 0.198855 0.216908 + outer loop + vertex 1.5355 1.88242 2.52133 + vertex 1.53556 1.87797 2.52566 + vertex 1.53679 1.8837 2.52585 + endloop + endfacet + facet normal -0.468862 0.306092 0.828539 + outer loop + vertex 1.54003 1.88219 2.52907 + vertex 1.53735 1.87816 2.52904 + vertex 1.53974 1.87758 2.5306 + endloop + endfacet + facet normal -0.563076 0.369447 0.739226 + outer loop + vertex 1.54003 1.88219 2.52907 + vertex 1.53679 1.8837 2.52585 + vertex 1.53735 1.87816 2.52904 + endloop + endfacet + facet normal -0.873968 0.17377 0.453855 + outer loop + vertex 1.53679 1.8837 2.52585 + vertex 1.53556 1.87797 2.52566 + vertex 1.53735 1.87816 2.52904 + endloop + endfacet + facet normal -0.470133 0.302498 0.829138 + outer loop + vertex 1.53974 1.87758 2.5306 + vertex 1.53735 1.87816 2.52904 + vertex 1.53836 1.87425 2.53104 + endloop + endfacet + facet normal -0.242969 0.201178 -0.948943 + outer loop + vertex 1.54 1.885 2.51299 + vertex 1.53727 1.88482 2.51365 + vertex 1.54 1.89 2.51405 + endloop + endfacet + facet normal -0.238181 0.0507536 -0.969894 + outer loop + vertex 1.53703 1.87998 2.51346 + vertex 1.53727 1.88482 2.51365 + vertex 1.54 1.885 2.51299 + endloop + endfacet + facet normal -0.92075 0.0607103 -0.385401 + outer loop + vertex 1.53703 1.87998 2.51346 + vertex 1.5357 1.88111 2.51681 + vertex 1.53727 1.88482 2.51365 + endloop + endfacet + facet normal -0.924051 0.0703488 -0.37574 + outer loop + vertex 1.53727 1.88482 2.51365 + vertex 1.5357 1.88111 2.51681 + vertex 1.536 1.88618 2.51703 + endloop + endfacet + facet normal -0.996258 0.060918 -0.0613056 + outer loop + vertex 1.5357 1.88111 2.51681 + vertex 1.5355 1.88242 2.52133 + vertex 1.536 1.88618 2.51703 + endloop + endfacet + facet normal -0.995728 0.0816706 -0.0430724 + outer loop + vertex 1.536 1.88618 2.51703 + vertex 1.5355 1.88242 2.52133 + vertex 1.53594 1.88777 2.52136 + endloop + endfacet + facet normal -0.96413 0.0773538 0.253908 + outer loop + vertex 1.5355 1.88242 2.52133 + vertex 1.53679 1.8837 2.52585 + vertex 1.53594 1.88777 2.52136 + endloop + endfacet + facet normal -0.970238 0.0559149 0.23561 + outer loop + vertex 1.53594 1.88777 2.52136 + vertex 1.53679 1.8837 2.52585 + vertex 1.53691 1.8897 2.52489 + endloop + endfacet + facet normal -0.733124 0.120111 0.669405 + outer loop + vertex 1.53679 1.8837 2.52585 + vertex 1.53894 1.88755 2.52751 + vertex 1.53691 1.8897 2.52489 + endloop + endfacet + facet normal -0.686939 0.0711605 0.723222 + outer loop + vertex 1.54003 1.88219 2.52907 + vertex 1.53894 1.88755 2.52751 + vertex 1.53679 1.8837 2.52585 + endloop + endfacet + facet normal -0.00513692 -0.675982 -0.7369 + outer loop + vertex 1.54 1.89 2.51405 + vertex 1.53724 1.89015 2.51393 + vertex 1.53878 1.89297 2.51134 + endloop + endfacet + facet normal 0.0472244 0.0518761 -0.997536 + outer loop + vertex 1.53727 1.88482 2.51365 + vertex 1.53724 1.89015 2.51393 + vertex 1.54 1.89 2.51405 + endloop + endfacet + facet normal -0.934243 0.0127529 -0.356408 + outer loop + vertex 1.53727 1.88482 2.51365 + vertex 1.536 1.88618 2.51703 + vertex 1.53724 1.89015 2.51393 + endloop + endfacet + facet normal -0.959676 0.0915686 -0.265775 + outer loop + vertex 1.53724 1.89015 2.51393 + vertex 1.536 1.88618 2.51703 + vertex 1.5362 1.89046 2.51776 + endloop + endfacet + facet normal -0.997996 0.0540117 -0.0329621 + outer loop + vertex 1.536 1.88618 2.51703 + vertex 1.53594 1.88777 2.52136 + vertex 1.5362 1.89046 2.51776 + endloop + endfacet + facet normal -0.995962 0.0895576 -0.0063043 + outer loop + vertex 1.5362 1.89046 2.51776 + vertex 1.53594 1.88777 2.52136 + vertex 1.53642 1.89316 2.52147 + endloop + endfacet + facet normal -0.971687 0.0827635 0.221303 + outer loop + vertex 1.53594 1.88777 2.52136 + vertex 1.53691 1.8897 2.52489 + vertex 1.53642 1.89316 2.52147 + endloop + endfacet + facet normal -0.97771 0.0615434 0.200736 + outer loop + vertex 1.53642 1.89316 2.52147 + vertex 1.53691 1.8897 2.52489 + vertex 1.53713 1.89325 2.52491 + endloop + endfacet + facet normal -0.740961 0.0444124 0.670078 + outer loop + vertex 1.53691 1.8897 2.52489 + vertex 1.53865 1.89189 2.52667 + vertex 1.53713 1.89325 2.52491 + endloop + endfacet + facet normal -0.756744 0.0736904 0.649545 + outer loop + vertex 1.53894 1.88755 2.52751 + vertex 1.53865 1.89189 2.52667 + vertex 1.53691 1.8897 2.52489 + endloop + endfacet + facet normal -0.829119 -0.0558043 -0.55628 + outer loop + vertex 1.53878 1.89297 2.51134 + vertex 1.53724 1.89015 2.51393 + vertex 1.53765 1.89448 2.51288 + endloop + endfacet + facet normal -0.96853 0.125769 -0.214784 + outer loop + vertex 1.53765 1.89448 2.51288 + vertex 1.53682 1.89432 2.51652 + vertex 1.53769 1.89734 2.51437 + endloop + endfacet + facet normal -0.97469 0.0396716 -0.220014 + outer loop + vertex 1.53765 1.89448 2.51288 + vertex 1.53724 1.89015 2.51393 + vertex 1.53682 1.89432 2.51652 + endloop + endfacet + facet normal -0.961912 0.0687618 -0.264571 + outer loop + vertex 1.53724 1.89015 2.51393 + vertex 1.5362 1.89046 2.51776 + vertex 1.53682 1.89432 2.51652 + endloop + endfacet + facet normal -0.983828 0.177571 0.0234875 + outer loop + vertex 1.53694 1.89627 2.51975 + vertex 1.53642 1.89316 2.52147 + vertex 1.53703 1.89643 2.52212 + endloop + endfacet + facet normal -0.989082 0.139876 -0.0463843 + outer loop + vertex 1.53694 1.89627 2.51975 + vertex 1.53682 1.89432 2.51652 + vertex 1.53642 1.89316 2.52147 + endloop + endfacet + facet normal -0.988658 0.143094 -0.0455959 + outer loop + vertex 1.53682 1.89432 2.51652 + vertex 1.5362 1.89046 2.51776 + vertex 1.53642 1.89316 2.52147 + endloop + endfacet + facet normal -0.8825 0.361636 0.300686 + outer loop + vertex 1.53703 1.89643 2.52212 + vertex 1.53734 1.89559 2.52404 + vertex 1.53778 1.8973 2.5233 + endloop + endfacet + facet normal -0.966829 0.136369 0.215974 + outer loop + vertex 1.53703 1.89643 2.52212 + vertex 1.53642 1.89316 2.52147 + vertex 1.53734 1.89559 2.52404 + endloop + endfacet + facet normal -0.967827 0.157698 0.196068 + outer loop + vertex 1.53642 1.89316 2.52147 + vertex 1.53713 1.89325 2.52491 + vertex 1.53734 1.89559 2.52404 + endloop + endfacet + facet normal -0.745963 0.288238 0.600382 + outer loop + vertex 1.53713 1.89325 2.52491 + vertex 1.53847 1.89476 2.52585 + vertex 1.53734 1.89559 2.52404 + endloop + endfacet + facet normal -0.683058 0.163245 0.711887 + outer loop + vertex 1.53865 1.89189 2.52667 + vertex 1.53847 1.89476 2.52585 + vertex 1.53713 1.89325 2.52491 + endloop + endfacet + facet normal -0.973083 0.204624 -0.106014 + outer loop + vertex 1.53769 1.89734 2.51437 + vertex 1.53682 1.89432 2.51652 + vertex 1.53746 1.89782 2.51737 + endloop + endfacet + facet normal -0.976315 0.199718 -0.0831991 + outer loop + vertex 1.53746 1.89782 2.51737 + vertex 1.53682 1.89432 2.51652 + vertex 1.53694 1.89627 2.51975 + endloop + endfacet + facet normal -0.547486 0.450501 0.7052 + outer loop + vertex 1.53778 1.8973 2.5233 + vertex 1.53734 1.89559 2.52404 + vertex 1.53976 1.89742 2.52475 + endloop + endfacet + facet normal -0.583282 0.533756 0.61228 + outer loop + vertex 1.53976 1.89742 2.52475 + vertex 1.53734 1.89559 2.52404 + vertex 1.53847 1.89476 2.52585 + endloop + endfacet + facet normal -0.251483 -0.247992 -0.935551 + outer loop + vertex 1.53855 2.00153 2.49112 + vertex 1.53928 2.005 2.49 + vertex 1.54 2.00427 2.49 + endloop + endfacet + facet normal -0.679272 -0.0913798 -0.728175 + outer loop + vertex 1.53609 2.00285 2.49325 + vertex 1.53928 2.005 2.49 + vertex 1.53855 2.00153 2.49112 + endloop + endfacet + facet normal -0.638548 -0.708873 -0.299593 + outer loop + vertex 1.53867 1.99989 2.49474 + vertex 1.53609 2.00285 2.49325 + vertex 1.53855 2.00153 2.49112 + endloop + endfacet + facet normal -0.773864 -0.625077 0.102045 + outer loop + vertex 1.53659 2.00289 2.49733 + vertex 1.53609 2.00285 2.49325 + vertex 1.53867 1.99989 2.49474 + endloop + endfacet + facet normal -0.786268 -0.612933 0.0780702 + outer loop + vertex 1.53881 2.00022 2.49873 + vertex 1.53659 2.00289 2.49733 + vertex 1.53867 1.99989 2.49474 + endloop + endfacet + facet normal -0.785662 -0.413724 0.459965 + outer loop + vertex 1.53809 2.0029 2.4999 + vertex 1.53659 2.00289 2.49733 + vertex 1.53881 2.00022 2.49873 + endloop + endfacet + facet normal -0.738126 -0.427936 0.521575 + outer loop + vertex 1.53881 2.00022 2.49873 + vertex 1.54024 2.00037 2.50087 + vertex 1.53809 2.0029 2.4999 + endloop + endfacet + facet normal -0.260986 -0.666742 -0.698098 + outer loop + vertex 1.53928 2.005 2.49 + vertex 1.53609 2.00285 2.49325 + vertex 1.53284 2.00546 2.49197 + endloop + endfacet + facet normal -0.266506 -0.637314 -0.723053 + outer loop + vertex 1.535 2.00679 2.49 + vertex 1.53928 2.005 2.49 + vertex 1.53284 2.00546 2.49197 + endloop + endfacet + facet normal -0.570886 -0.817196 0.0792468 + outer loop + vertex 1.53609 2.00285 2.49325 + vertex 1.53659 2.00289 2.49733 + vertex 1.53353 2.00494 2.49641 + endloop + endfacet + facet normal -0.628385 -0.777875 0.00659256 + outer loop + vertex 1.53284 2.00546 2.49197 + vertex 1.53609 2.00285 2.49325 + vertex 1.53353 2.00494 2.49641 + endloop + endfacet + facet normal 0.100124 -0.854515 0.509685 + outer loop + vertex 1.53158 2.00659 2.49955 + vertex 1.53353 2.00494 2.49641 + vertex 1.53632 2.00725 2.49972 + endloop + endfacet + facet normal 0.111398 -0.90871 0.40229 + outer loop + vertex 1.53158 2.00659 2.49955 + vertex 1.53632 2.00725 2.49972 + vertex 1.53277 2.00728 2.50077 + endloop + endfacet + facet normal -0.515493 -0.435705 0.737854 + outer loop + vertex 1.53353 2.00494 2.49641 + vertex 1.53659 2.00289 2.49733 + vertex 1.53632 2.00725 2.49972 + endloop + endfacet + facet normal -0.364046 -0.108755 0.92501 + outer loop + vertex 1.54035 2.00369 2.50089 + vertex 1.53632 2.00725 2.49972 + vertex 1.53809 2.0029 2.4999 + endloop + endfacet + facet normal -0.819711 -0.312921 0.479745 + outer loop + vertex 1.53659 2.00289 2.49733 + vertex 1.53809 2.0029 2.4999 + vertex 1.53632 2.00725 2.49972 + endloop + endfacet + facet normal -0.40174 0.0103924 0.915695 + outer loop + vertex 1.53809 2.0029 2.4999 + vertex 1.54024 2.00037 2.50087 + vertex 1.54035 2.00369 2.50089 + endloop + endfacet + facet normal -0.0367861 -0.854961 0.517386 + outer loop + vertex 1.53158 2.00659 2.49955 + vertex 1.53277 2.00728 2.50077 + vertex 1.53126 2.00752 2.50107 + endloop + endfacet + facet normal 0.157204 0.457084 0.875421 + outer loop + vertex 1.53399 2.10387 2.47089 + vertex 1.53797 2.10308 2.47059 + vertex 1.53686 2.10724 2.46862 + endloop + endfacet + facet normal 0.183286 0.438042 0.880071 + outer loop + vertex 1.53185 2.10715 2.4697 + vertex 1.53399 2.10387 2.47089 + vertex 1.53686 2.10724 2.46862 + endloop + endfacet + facet normal 0.142026 0.369438 0.918338 + outer loop + vertex 1.53628 2.09981 2.47217 + vertex 1.53399 2.10387 2.47089 + vertex 1.53123 2.10083 2.47254 + endloop + endfacet + facet normal 0.143425 0.37008 0.917862 + outer loop + vertex 1.53797 2.10308 2.47059 + vertex 1.53399 2.10387 2.47089 + vertex 1.53628 2.09981 2.47217 + endloop + endfacet + facet normal 0.165424 0.63594 0.7538 + outer loop + vertex 1.5397 2.11 2.46625 + vertex 1.53878 2.11196 2.4648 + vertex 1.53625 2.11138 2.46585 + endloop + endfacet + facet normal 0.130071 0.565 0.814774 + outer loop + vertex 1.53625 2.11138 2.46585 + vertex 1.53686 2.10724 2.46862 + vertex 1.5397 2.11 2.46625 + endloop + endfacet + facet normal 0.202029 0.565451 0.799656 + outer loop + vertex 1.53625 2.11138 2.46585 + vertex 1.53153 2.11071 2.46751 + vertex 1.53686 2.10724 2.46862 + endloop + endfacet + facet normal 0.171114 0.528218 0.831689 + outer loop + vertex 1.53153 2.11071 2.46751 + vertex 1.53185 2.10715 2.4697 + vertex 1.53686 2.10724 2.46862 + endloop + endfacet + facet normal 0.229369 0.828569 0.510748 + outer loop + vertex 1.53804 2.11393 2.46265 + vertex 1.53637 2.11619 2.45974 + vertex 1.53408 2.11549 2.4619 + endloop + endfacet + facet normal 0.198675 0.767 0.610114 + outer loop + vertex 1.53408 2.11549 2.4619 + vertex 1.53029 2.11587 2.46266 + vertex 1.53313 2.11366 2.46451 + endloop + endfacet + facet normal 0.188039 0.770687 0.608838 + outer loop + vertex 1.53804 2.11393 2.46265 + vertex 1.53408 2.11549 2.4619 + vertex 1.53313 2.11366 2.46451 + endloop + endfacet + facet normal 0.219685 0.697768 0.681805 + outer loop + vertex 1.53804 2.11393 2.46265 + vertex 1.53313 2.11366 2.46451 + vertex 1.53625 2.11138 2.46585 + endloop + endfacet + facet normal 0.0984585 0.74917 0.65502 + outer loop + vertex 1.53804 2.11393 2.46265 + vertex 1.53625 2.11138 2.46585 + vertex 1.53878 2.11196 2.4648 + endloop + endfacet + facet normal 0.166681 0.6567 0.735501 + outer loop + vertex 1.53625 2.11138 2.46585 + vertex 1.53313 2.11366 2.46451 + vertex 1.53153 2.11071 2.46751 + endloop + endfacet + facet normal 0.00304451 0.441844 0.897087 + outer loop + vertex 1.53718 2.125 2.45 + vertex 1.53192 2.12377 2.45062 + vertex 1.53484 2.12125 2.45185 + endloop + endfacet + facet normal 0.196287 0.333432 0.922114 + outer loop + vertex 1.53718 2.125 2.45 + vertex 1.53484 2.12125 2.45185 + vertex 1.54 2.12334 2.45 + endloop + endfacet + facet normal 0.140735 0.439745 0.887027 + outer loop + vertex 1.54 2.12334 2.45 + vertex 1.53484 2.12125 2.45185 + vertex 1.53903 2.11941 2.4521 + endloop + endfacet + facet normal 0.32241 0.801117 0.504245 + outer loop + vertex 1.53903 2.11941 2.4521 + vertex 1.53484 2.12125 2.45185 + vertex 1.53676 2.118 2.45579 + endloop + endfacet + facet normal 0.284164 0.802761 0.524238 + outer loop + vertex 1.53676 2.118 2.45579 + vertex 1.53484 2.12125 2.45185 + vertex 1.53236 2.11984 2.45536 + endloop + endfacet + facet normal 0.195021 0.854009 0.482323 + outer loop + vertex 1.53637 2.11619 2.45974 + vertex 1.53234 2.11751 2.45903 + vertex 1.53408 2.11549 2.4619 + endloop + endfacet + facet normal 0.213576 0.879686 0.424896 + outer loop + vertex 1.53637 2.11619 2.45974 + vertex 1.53676 2.118 2.45579 + vertex 1.53234 2.11751 2.45903 + endloop + endfacet + facet normal 0.287288 0.807972 0.514439 + outer loop + vertex 1.53676 2.118 2.45579 + vertex 1.53236 2.11984 2.45536 + vertex 1.53234 2.11751 2.45903 + endloop + endfacet + facet normal 0.18271 0.852925 0.489015 + outer loop + vertex 1.53408 2.11549 2.4619 + vertex 1.53234 2.11751 2.45903 + vertex 1.53029 2.11587 2.46266 + endloop + endfacet + facet normal 0.0845632 0.137581 0.986874 + outer loop + vertex 1.53718 2.125 2.45 + vertex 1.535 2.12634 2.45 + vertex 1.53192 2.12377 2.45062 + endloop + endfacet + facet normal -0.121702 0.937272 -0.326665 + outer loop + vertex 1.53759 0.90862 2.44873 + vertex 1.545 0.91 2.44993 + vertex 1.54158 0.909066 2.44852 + endloop + endfacet + facet normal 0.127079 0.16755 -0.977639 + outer loop + vertex 1.54 0.91 2.44928 + vertex 1.545 0.91 2.44993 + vertex 1.53759 0.90862 2.44873 + endloop + endfacet + facet normal 0.12042 -0.959832 0.253419 + outer loop + vertex 1.54158 0.909066 2.44852 + vertex 1.53933 0.909056 2.44955 + vertex 1.53759 0.90862 2.44873 + endloop + endfacet + facet normal 0.152232 -0.934074 0.323003 + outer loop + vertex 1.54346 0.909541 2.44901 + vertex 1.53933 0.909056 2.44955 + vertex 1.54158 0.909066 2.44852 + endloop + endfacet + facet normal 0.157707 -0.908208 0.387667 + outer loop + vertex 1.53933 0.909056 2.44955 + vertex 1.54346 0.909541 2.44901 + vertex 1.54277 0.910276 2.45101 + endloop + endfacet + facet normal 0.163801 -0.911872 0.376375 + outer loop + vertex 1.53714 0.910059 2.45294 + vertex 1.53933 0.909056 2.44955 + vertex 1.54277 0.910276 2.45101 + endloop + endfacet + facet normal 0.181923 -0.883045 0.432592 + outer loop + vertex 1.54277 0.910276 2.45101 + vertex 1.54143 0.911913 2.45492 + vertex 1.53714 0.910059 2.45294 + endloop + endfacet + facet normal 0.170795 -0.876333 0.45041 + outer loop + vertex 1.54143 0.911913 2.45492 + vertex 1.53676 0.911865 2.4566 + vertex 1.53714 0.910059 2.45294 + endloop + endfacet + facet normal 0.194395 -0.833429 0.517307 + outer loop + vertex 1.54143 0.911913 2.45492 + vertex 1.53901 0.913664 2.45865 + vertex 1.53676 0.911865 2.4566 + endloop + endfacet + facet normal 0.160816 -0.849216 0.502961 + outer loop + vertex 1.54291 0.913827 2.45768 + vertex 1.53901 0.913664 2.45865 + vertex 1.54143 0.911913 2.45492 + endloop + endfacet + facet normal 0.18121 -0.782227 0.596057 + outer loop + vertex 1.53901 0.913664 2.45865 + vertex 1.54291 0.913827 2.45768 + vertex 1.54204 0.916022 2.46082 + endloop + endfacet + facet normal 0.170603 -0.77733 0.605518 + outer loop + vertex 1.53694 0.915529 2.46163 + vertex 1.53901 0.913664 2.45865 + vertex 1.54204 0.916022 2.46082 + endloop + endfacet + facet normal 0.176582 -0.702476 0.689453 + outer loop + vertex 1.54204 0.916022 2.46082 + vertex 1.53888 0.91826 2.46391 + vertex 1.53694 0.915529 2.46163 + endloop + endfacet + facet normal 0.155431 -0.717647 0.67884 + outer loop + vertex 1.54383 0.919105 2.46367 + vertex 1.53888 0.91826 2.46391 + vertex 1.54204 0.916022 2.46082 + endloop + endfacet + facet normal 0.144309 -0.628244 0.764516 + outer loop + vertex 1.53888 0.91826 2.46391 + vertex 1.54383 0.919105 2.46367 + vertex 1.54122 0.92143 2.46608 + endloop + endfacet + facet normal 0.145116 -0.628558 0.764105 + outer loop + vertex 1.53636 0.920619 2.46633 + vertex 1.53888 0.91826 2.46391 + vertex 1.54122 0.92143 2.46608 + endloop + endfacet + facet normal 0.133953 -0.54064 0.830521 + outer loop + vertex 1.54122 0.92143 2.46608 + vertex 1.53904 0.924118 2.46818 + vertex 1.53636 0.920619 2.46633 + endloop + endfacet + facet normal 0.124996 -0.546167 0.828298 + outer loop + vertex 1.54402 0.924687 2.4678 + vertex 1.53904 0.924118 2.46818 + vertex 1.54122 0.92143 2.46608 + endloop + endfacet + facet normal 0.119488 -0.466052 0.876652 + outer loop + vertex 1.54402 0.924687 2.4678 + vertex 1.54231 0.927684 2.46963 + vertex 1.53904 0.924118 2.46818 + endloop + endfacet + facet normal 0.115449 -0.463187 0.878709 + outer loop + vertex 1.53904 0.924118 2.46818 + vertex 1.54231 0.927684 2.46963 + vertex 1.53737 0.92718 2.47001 + endloop + endfacet + facet normal 0.111611 -0.402915 0.908406 + outer loop + vertex 1.53737 0.92718 2.47001 + vertex 1.54231 0.927684 2.46963 + vertex 1.54077 0.930921 2.47125 + endloop + endfacet + facet normal 0.109894 -0.401615 0.909191 + outer loop + vertex 1.53599 0.930371 2.47159 + vertex 1.53737 0.92718 2.47001 + vertex 1.54077 0.930921 2.47125 + endloop + endfacet + facet normal 0.0993287 -0.304919 0.947184 + outer loop + vertex 1.53829 0.978906 2.488 + vertex 1.54285 0.983227 2.48891 + vertex 1.53776 0.982975 2.48936 + endloop + endfacet + facet normal 0.0993295 -0.304961 0.947171 + outer loop + vertex 1.54285 0.983227 2.48891 + vertex 1.54204 0.987107 2.49024 + vertex 1.53776 0.982975 2.48936 + endloop + endfacet + facet normal 0.0957655 -0.301578 0.94862 + outer loop + vertex 1.53776 0.982975 2.48936 + vertex 1.54204 0.987107 2.49024 + vertex 1.53752 0.986728 2.49058 + endloop + endfacet + facet normal -0.142619 -0.29084 0.946082 + outer loop + vertex 1.53846 1.02195 2.50059 + vertex 1.5361 1.01931 2.49943 + vertex 1.54059 1.02182 2.50087 + endloop + endfacet + facet normal -0.13518 -0.081098 0.987497 + outer loop + vertex 1.54059 1.02182 2.50087 + vertex 1.54024 1.02402 2.50101 + vertex 1.53846 1.02195 2.50059 + endloop + endfacet + facet normal -0.121491 -0.0790575 0.989439 + outer loop + vertex 1.54352 1.02488 2.50148 + vertex 1.54024 1.02402 2.50101 + vertex 1.54059 1.02182 2.50087 + endloop + endfacet + facet normal -0.541805 0.768642 -0.340054 + outer loop + vertex 1.54144 1.02835 2.48577 + vertex 1.54427 1.03 2.485 + vertex 1.54 1.02699 2.485 + endloop + endfacet + facet normal -0.628366 0.760374 -0.164283 + outer loop + vertex 1.53789 1.02582 2.48765 + vertex 1.54144 1.02835 2.48577 + vertex 1.54 1.02699 2.485 + endloop + endfacet + facet normal -0.605622 0.791811 -0.0790967 + outer loop + vertex 1.54041 1.02798 2.48998 + vertex 1.54144 1.02835 2.48577 + vertex 1.53789 1.02582 2.48765 + endloop + endfacet + facet normal -0.66052 0.750578 0.0186239 + outer loop + vertex 1.53755 1.02539 2.49263 + vertex 1.54041 1.02798 2.48998 + vertex 1.53789 1.02582 2.48765 + endloop + endfacet + facet normal -0.670754 0.741679 -0.00112684 + outer loop + vertex 1.54022 1.02782 2.49504 + vertex 1.54041 1.02798 2.48998 + vertex 1.53755 1.02539 2.49263 + endloop + endfacet + facet normal -0.730364 0.668863 0.138532 + outer loop + vertex 1.53828 1.02523 2.49727 + vertex 1.54022 1.02782 2.49504 + vertex 1.53755 1.02539 2.49263 + endloop + endfacet + facet normal -0.720082 0.676143 0.155925 + outer loop + vertex 1.54098 1.02773 2.49891 + vertex 1.54022 1.02782 2.49504 + vertex 1.53828 1.02523 2.49727 + endloop + endfacet + facet normal -0.741932 0.567812 0.356548 + outer loop + vertex 1.53973 1.02542 2.49999 + vertex 1.54098 1.02773 2.49891 + vertex 1.53828 1.02523 2.49727 + endloop + endfacet + facet normal -0.575924 0.580725 0.575386 + outer loop + vertex 1.53973 1.02542 2.49999 + vertex 1.54309 1.02761 2.50115 + vertex 1.54098 1.02773 2.49891 + endloop + endfacet + facet normal -0.50977 0.374374 0.774583 + outer loop + vertex 1.53973 1.02542 2.49999 + vertex 1.54024 1.02402 2.50101 + vertex 1.54309 1.02761 2.50115 + endloop + endfacet + facet normal -0.165483 0.0932732 0.981792 + outer loop + vertex 1.54024 1.02402 2.50101 + vertex 1.54352 1.02488 2.50148 + vertex 1.54309 1.02761 2.50115 + endloop + endfacet + facet normal -0.577239 0.569335 -0.585365 + outer loop + vertex 1.545 1.03 2.48428 + vertex 1.54427 1.03 2.485 + vertex 1.545 1.03074 2.485 + endloop + endfacet + facet normal -0.576738 0.768516 -0.277051 + outer loop + vertex 1.545 1.03074 2.485 + vertex 1.54144 1.02835 2.48577 + vertex 1.54413 1.0309 2.48727 + endloop + endfacet + facet normal -0.478047 0.471502 -0.741051 + outer loop + vertex 1.54427 1.03 2.485 + vertex 1.54144 1.02835 2.48577 + vertex 1.545 1.03074 2.485 + endloop + endfacet + facet normal -0.666156 0.736115 -0.119883 + outer loop + vertex 1.54413 1.0309 2.48727 + vertex 1.54041 1.02798 2.48998 + vertex 1.54282 1.03059 2.49262 + endloop + endfacet + facet normal -0.657401 0.747442 -0.0956827 + outer loop + vertex 1.54144 1.02835 2.48577 + vertex 1.54041 1.02798 2.48998 + vertex 1.54413 1.0309 2.48727 + endloop + endfacet + facet normal -0.725788 0.687853 0.00945366 + outer loop + vertex 1.54282 1.03059 2.49262 + vertex 1.54022 1.02782 2.49504 + vertex 1.54283 1.03054 2.49734 + endloop + endfacet + facet normal -0.732244 0.681022 -0.00532489 + outer loop + vertex 1.54041 1.02798 2.48998 + vertex 1.54022 1.02782 2.49504 + vertex 1.54282 1.03059 2.49262 + endloop + endfacet + facet normal -0.727595 0.630689 0.269883 + outer loop + vertex 1.54283 1.03054 2.49734 + vertex 1.54098 1.02773 2.49891 + vertex 1.54371 1.03033 2.5002 + endloop + endfacet + facet normal -0.778176 0.605837 0.165539 + outer loop + vertex 1.54022 1.02782 2.49504 + vertex 1.54098 1.02773 2.49891 + vertex 1.54283 1.03054 2.49734 + endloop + endfacet + facet normal -0.663333 0.376306 0.646826 + outer loop + vertex 1.54371 1.03033 2.5002 + vertex 1.54098 1.02773 2.49891 + vertex 1.54309 1.02761 2.50115 + endloop + endfacet + facet normal -0.971684 -0.230927 -0.0500222 + outer loop + vertex 1.54289 1.08767 2.5103 + vertex 1.54229 1.09003 2.51111 + vertex 1.54254 1.08952 2.50859 + endloop + endfacet + facet normal -0.948064 -0.287874 0.135286 + outer loop + vertex 1.54289 1.08767 2.5103 + vertex 1.54313 1.088 2.51268 + vertex 1.54229 1.09003 2.51111 + endloop + endfacet + facet normal -0.899295 -0.146901 -0.411932 + outer loop + vertex 1.54309 1.09168 2.50627 + vertex 1.54206 1.09261 2.50819 + vertex 1.54299 1.09536 2.50519 + endloop + endfacet + facet normal -0.900262 -0.188598 -0.392377 + outer loop + vertex 1.54254 1.08952 2.50859 + vertex 1.54206 1.09261 2.50819 + vertex 1.54309 1.09168 2.50627 + endloop + endfacet + facet normal -0.984947 -0.15978 -0.065948 + outer loop + vertex 1.54254 1.08952 2.50859 + vertex 1.54229 1.09003 2.51111 + vertex 1.54206 1.09261 2.50819 + endloop + endfacet + facet normal -0.995053 -0.098704 -0.0112805 + outer loop + vertex 1.54229 1.09003 2.51111 + vertex 1.54183 1.09459 2.51153 + vertex 1.54206 1.09261 2.50819 + endloop + endfacet + facet normal -0.960573 -0.119689 0.250947 + outer loop + vertex 1.54229 1.09003 2.51111 + vertex 1.5429 1.09104 2.51394 + vertex 1.54183 1.09459 2.51153 + endloop + endfacet + facet normal -0.945387 -0.182714 0.269923 + outer loop + vertex 1.54313 1.088 2.51268 + vertex 1.5429 1.09104 2.51394 + vertex 1.54229 1.09003 2.51111 + endloop + endfacet + facet normal -0.860256 -0.172965 -0.479628 + outer loop + vertex 1.54299 1.09536 2.50519 + vertex 1.54162 1.09743 2.5069 + vertex 1.54279 1.09847 2.50443 + endloop + endfacet + facet normal -0.868831 -0.201155 -0.452403 + outer loop + vertex 1.54206 1.09261 2.50819 + vertex 1.54162 1.09743 2.5069 + vertex 1.54299 1.09536 2.50519 + endloop + endfacet + facet normal -0.995366 -0.0952262 -0.0133635 + outer loop + vertex 1.54206 1.09261 2.50819 + vertex 1.54183 1.09459 2.51153 + vertex 1.54162 1.09743 2.5069 + endloop + endfacet + facet normal -0.98922 -0.140471 -0.0413801 + outer loop + vertex 1.54162 1.09743 2.5069 + vertex 1.54183 1.09459 2.51153 + vertex 1.54121 1.09938 2.51002 + endloop + endfacet + facet normal -0.954403 -0.0963998 0.282527 + outer loop + vertex 1.54286 1.09473 2.51505 + vertex 1.54183 1.09459 2.51153 + vertex 1.5429 1.09104 2.51394 + endloop + endfacet + facet normal -0.951915 -0.118138 0.282668 + outer loop + vertex 1.54286 1.09473 2.51505 + vertex 1.54207 1.0994 2.51436 + vertex 1.54183 1.09459 2.51153 + endloop + endfacet + facet normal -0.978766 -0.0648773 0.194445 + outer loop + vertex 1.54207 1.0994 2.51436 + vertex 1.54121 1.09938 2.51002 + vertex 1.54183 1.09459 2.51153 + endloop + endfacet + facet normal -0.764371 -0.0334929 0.643906 + outer loop + vertex 1.54286 1.09473 2.51505 + vertex 1.54489 1.09741 2.5176 + vertex 1.54207 1.0994 2.51436 + endloop + endfacet + facet normal 0.135564 -0.286698 -0.948381 + outer loop + vertex 1.545 1.1006 2.505 + vertex 1.5423 1.1014 2.50437 + vertex 1.545 1.105 2.50367 + endloop + endfacet + facet normal 0.231866 0.0193592 -0.972555 + outer loop + vertex 1.54279 1.09847 2.50443 + vertex 1.5423 1.1014 2.50437 + vertex 1.545 1.1006 2.505 + endloop + endfacet + facet normal -0.866635 -0.153917 -0.474609 + outer loop + vertex 1.54279 1.09847 2.50443 + vertex 1.54162 1.09743 2.5069 + vertex 1.5423 1.1014 2.50437 + endloop + endfacet + facet normal -0.917085 -0.0903751 -0.388314 + outer loop + vertex 1.54162 1.09743 2.5069 + vertex 1.54116 1.10248 2.50681 + vertex 1.5423 1.1014 2.50437 + endloop + endfacet + facet normal -0.993169 -0.0913423 -0.0726083 + outer loop + vertex 1.54162 1.09743 2.5069 + vertex 1.54121 1.09938 2.51002 + vertex 1.54116 1.10248 2.50681 + endloop + endfacet + facet normal -0.997397 -0.0590406 -0.0413872 + outer loop + vertex 1.54116 1.10248 2.50681 + vertex 1.54121 1.09938 2.51002 + vertex 1.54093 1.10367 2.51072 + endloop + endfacet + facet normal -0.976298 -0.0957507 0.1941 + outer loop + vertex 1.54121 1.09938 2.51002 + vertex 1.54207 1.0994 2.51436 + vertex 1.54093 1.10367 2.51072 + endloop + endfacet + facet normal -0.979616 -0.13682 0.14708 + outer loop + vertex 1.54093 1.10367 2.51072 + vertex 1.54207 1.0994 2.51436 + vertex 1.54143 1.10532 2.51562 + endloop + endfacet + facet normal -0.844177 -0.197039 0.49854 + outer loop + vertex 1.54207 1.0994 2.51436 + vertex 1.54377 1.10226 2.51837 + vertex 1.54143 1.10532 2.51562 + endloop + endfacet + facet normal -0.802499 -0.26927 0.532437 + outer loop + vertex 1.54489 1.09741 2.5176 + vertex 1.54377 1.10226 2.51837 + vertex 1.54207 1.0994 2.51436 + endloop + endfacet + facet normal -0.176305 -0.0667777 -0.982068 + outer loop + vertex 1.545 1.105 2.50367 + vertex 1.54221 1.10607 2.5041 + vertex 1.545 1.11 2.50333 + endloop + endfacet + facet normal -0.174204 -0.0609952 -0.982819 + outer loop + vertex 1.5423 1.1014 2.50437 + vertex 1.54221 1.10607 2.5041 + vertex 1.545 1.105 2.50367 + endloop + endfacet + facet normal -0.912072 -0.0408461 -0.407991 + outer loop + vertex 1.5423 1.1014 2.50437 + vertex 1.54116 1.10248 2.50681 + vertex 1.54221 1.10607 2.5041 + endloop + endfacet + facet normal -0.922905 -0.0199403 -0.38451 + outer loop + vertex 1.54221 1.10607 2.5041 + vertex 1.54116 1.10248 2.50681 + vertex 1.541 1.10725 2.50694 + endloop + endfacet + facet normal -0.998256 -0.0319484 -0.0496358 + outer loop + vertex 1.54116 1.10248 2.50681 + vertex 1.54093 1.10367 2.51072 + vertex 1.541 1.10725 2.50694 + endloop + endfacet + facet normal -0.991808 -0.082494 -0.0975243 + outer loop + vertex 1.541 1.10725 2.50694 + vertex 1.54093 1.10367 2.51072 + vertex 1.54052 1.10829 2.51099 + endloop + endfacet + facet normal -0.986383 -0.095579 0.133839 + outer loop + vertex 1.54093 1.10367 2.51072 + vertex 1.54143 1.10532 2.51562 + vertex 1.54052 1.10829 2.51099 + endloop + endfacet + facet normal -0.976031 -0.209537 0.0588113 + outer loop + vertex 1.54052 1.10829 2.51099 + vertex 1.54143 1.10532 2.51562 + vertex 1.54044 1.1097 2.51466 + endloop + endfacet + facet normal -0.863155 -0.284596 0.417096 + outer loop + vertex 1.54313 1.10592 2.51954 + vertex 1.54143 1.10532 2.51562 + vertex 1.54377 1.10226 2.51837 + endloop + endfacet + facet normal -0.873188 -0.252885 0.416643 + outer loop + vertex 1.54313 1.10592 2.51954 + vertex 1.54172 1.10986 2.51897 + vertex 1.54143 1.10532 2.51562 + endloop + endfacet + facet normal -0.945905 -0.15243 0.286406 + outer loop + vertex 1.54172 1.10986 2.51897 + vertex 1.54044 1.1097 2.51466 + vertex 1.54143 1.10532 2.51562 + endloop + endfacet + facet normal -0.648684 -0.123246 0.751012 + outer loop + vertex 1.54313 1.10592 2.51954 + vertex 1.54489 1.10902 2.52157 + vertex 1.54172 1.10986 2.51897 + endloop + endfacet + facet normal -0.34881 0.09879 -0.931972 + outer loop + vertex 1.545 1.11 2.50333 + vertex 1.54248 1.11146 2.50443 + vertex 1.545 1.115 2.50386 + endloop + endfacet + facet normal -0.36153 0.0748305 -0.929353 + outer loop + vertex 1.54221 1.10607 2.5041 + vertex 1.54248 1.11146 2.50443 + vertex 1.545 1.11 2.50333 + endloop + endfacet + facet normal -0.906977 0.0702518 -0.415279 + outer loop + vertex 1.54221 1.10607 2.5041 + vertex 1.541 1.10725 2.50694 + vertex 1.54248 1.11146 2.50443 + endloop + endfacet + facet normal -0.894097 0.047785 -0.445318 + outer loop + vertex 1.54248 1.11146 2.50443 + vertex 1.541 1.10725 2.50694 + vertex 1.54089 1.11123 2.50759 + endloop + endfacet + facet normal -0.993133 -0.00860738 -0.116671 + outer loop + vertex 1.541 1.10725 2.50694 + vertex 1.54052 1.10829 2.51099 + vertex 1.54089 1.11123 2.50759 + endloop + endfacet + facet normal -0.98717 -0.0498628 -0.151686 + outer loop + vertex 1.54089 1.11123 2.50759 + vertex 1.54052 1.10829 2.51099 + vertex 1.54028 1.11274 2.5111 + endloop + endfacet + facet normal -0.998524 -0.0542974 -0.00130603 + outer loop + vertex 1.54052 1.10829 2.51099 + vertex 1.54044 1.1097 2.51466 + vertex 1.54028 1.11274 2.5111 + endloop + endfacet + facet normal -0.995462 -0.0897286 -0.0316732 + outer loop + vertex 1.54028 1.11274 2.5111 + vertex 1.54044 1.1097 2.51466 + vertex 1.54003 1.11373 2.51587 + endloop + endfacet + facet normal -0.941163 -0.180014 0.286018 + outer loop + vertex 1.54044 1.1097 2.51466 + vertex 1.54172 1.10986 2.51897 + vertex 1.54003 1.11373 2.51587 + endloop + endfacet + facet normal -0.943228 -0.194046 0.26957 + outer loop + vertex 1.54003 1.11373 2.51587 + vertex 1.54172 1.10986 2.51897 + vertex 1.54104 1.11527 2.52051 + endloop + endfacet + facet normal -0.618286 -0.285566 0.732239 + outer loop + vertex 1.54172 1.10986 2.51897 + vertex 1.54406 1.1135 2.52237 + vertex 1.54104 1.11527 2.52051 + endloop + endfacet + facet normal -0.652773 -0.247954 0.715825 + outer loop + vertex 1.54489 1.10902 2.52157 + vertex 1.54406 1.1135 2.52237 + vertex 1.54172 1.10986 2.51897 + endloop + endfacet + facet normal -0.755372 0.463388 -0.46334 + outer loop + vertex 1.545 1.115 2.50386 + vertex 1.54248 1.11146 2.50443 + vertex 1.545 1.11614 2.505 + endloop + endfacet + facet normal -0.473544 0.553663 -0.684992 + outer loop + vertex 1.545 1.11614 2.505 + vertex 1.54183 1.11627 2.50729 + vertex 1.545 1.12 2.50812 + endloop + endfacet + facet normal -0.532403 0.379172 -0.75682 + outer loop + vertex 1.545 1.11614 2.505 + vertex 1.54248 1.11146 2.50443 + vertex 1.54183 1.11627 2.50729 + endloop + endfacet + facet normal -0.888915 0.140374 -0.436033 + outer loop + vertex 1.54248 1.11146 2.50443 + vertex 1.54089 1.11123 2.50759 + vertex 1.54183 1.11627 2.50729 + endloop + endfacet + facet normal -0.957041 0.164912 -0.23849 + outer loop + vertex 1.54089 1.11123 2.50759 + vertex 1.54028 1.11274 2.5111 + vertex 1.54183 1.11627 2.50729 + endloop + endfacet + facet normal -0.929398 0.011922 -0.368886 + outer loop + vertex 1.54183 1.11627 2.50729 + vertex 1.54028 1.11274 2.5111 + vertex 1.54004 1.11815 2.51186 + endloop + endfacet + facet normal -0.998398 -0.0369099 -0.0428835 + outer loop + vertex 1.54028 1.11274 2.5111 + vertex 1.54003 1.11373 2.51587 + vertex 1.54004 1.11815 2.51186 + endloop + endfacet + facet normal -0.979725 -0.133613 -0.149285 + outer loop + vertex 1.54004 1.11815 2.51186 + vertex 1.54003 1.11373 2.51587 + vertex 1.53902 1.11933 2.51752 + endloop + endfacet + facet normal -0.924981 -0.251684 0.284719 + outer loop + vertex 1.54003 1.11373 2.51587 + vertex 1.54104 1.11527 2.52051 + vertex 1.53902 1.11933 2.51752 + endloop + endfacet + facet normal -0.923909 -0.243491 0.295133 + outer loop + vertex 1.53902 1.11933 2.51752 + vertex 1.54104 1.11527 2.52051 + vertex 1.54049 1.11983 2.52253 + endloop + endfacet + facet normal -0.485051 -0.403442 0.775861 + outer loop + vertex 1.54104 1.11527 2.52051 + vertex 1.54358 1.11869 2.52387 + vertex 1.54049 1.11983 2.52253 + endloop + endfacet + facet normal -0.615066 -0.271839 0.740134 + outer loop + vertex 1.54406 1.1135 2.52237 + vertex 1.54358 1.11869 2.52387 + vertex 1.54104 1.11527 2.52051 + endloop + endfacet + facet normal -0.582351 -0.0276227 -0.812468 + outer loop + vertex 1.545 1.12 2.50812 + vertex 1.54214 1.125 2.51 + vertex 1.545 1.125 2.50795 + endloop + endfacet + facet normal -0.102746 0.298044 -0.949006 + outer loop + vertex 1.54183 1.11627 2.50729 + vertex 1.54214 1.125 2.51 + vertex 1.545 1.12 2.50812 + endloop + endfacet + facet normal -0.894817 0.160569 -0.416557 + outer loop + vertex 1.54183 1.11627 2.50729 + vertex 1.54004 1.11815 2.51186 + vertex 1.54214 1.125 2.51 + endloop + endfacet + facet normal -0.60717 -0.0300512 -0.794004 + outer loop + vertex 1.54214 1.125 2.51 + vertex 1.54004 1.11815 2.51186 + vertex 1.53919 1.12371 2.5123 + endloop + endfacet + facet normal -0.845376 -0.344321 -0.408391 + outer loop + vertex 1.53784 1.1227 2.51596 + vertex 1.53759 1.12574 2.51391 + vertex 1.53919 1.12371 2.5123 + endloop + endfacet + facet normal -0.779 -0.467748 -0.417578 + outer loop + vertex 1.53784 1.1227 2.51596 + vertex 1.53919 1.12371 2.5123 + vertex 1.53902 1.11933 2.51752 + endloop + endfacet + facet normal -0.979233 -0.138333 -0.148209 + outer loop + vertex 1.53902 1.11933 2.51752 + vertex 1.53919 1.12371 2.5123 + vertex 1.54004 1.11815 2.51186 + endloop + endfacet + facet normal -0.932731 -0.355524 -0.0601294 + outer loop + vertex 1.53773 1.12249 2.51881 + vertex 1.53784 1.1227 2.51596 + vertex 1.53902 1.11933 2.51752 + endloop + endfacet + facet normal -0.824919 -0.466618 0.319025 + outer loop + vertex 1.53773 1.12249 2.51881 + vertex 1.53902 1.11933 2.51752 + vertex 1.53862 1.12302 2.5219 + endloop + endfacet + facet normal -0.850026 -0.437983 0.292621 + outer loop + vertex 1.53862 1.12302 2.5219 + vertex 1.53902 1.11933 2.51752 + vertex 1.54049 1.11983 2.52253 + endloop + endfacet + facet normal -0.490035 -0.456284 0.742745 + outer loop + vertex 1.54226 1.12164 2.52481 + vertex 1.54049 1.11983 2.52253 + vertex 1.54358 1.11869 2.52387 + endloop + endfacet + facet normal -0.599803 -0.331242 0.728365 + outer loop + vertex 1.54226 1.12164 2.52481 + vertex 1.54089 1.12398 2.52475 + vertex 1.54049 1.11983 2.52253 + endloop + endfacet + facet normal -0.70312 -0.281102 0.653149 + outer loop + vertex 1.54089 1.12398 2.52475 + vertex 1.53862 1.12302 2.5219 + vertex 1.54049 1.11983 2.52253 + endloop + endfacet + facet normal -0.330016 -0.167981 0.928909 + outer loop + vertex 1.54226 1.12164 2.52481 + vertex 1.54377 1.12502 2.52596 + vertex 1.54089 1.12398 2.52475 + endloop + endfacet + facet normal -0.601749 -0.048148 -0.797232 + outer loop + vertex 1.54214 1.125 2.51 + vertex 1.53919 1.12371 2.5123 + vertex 1.54174 1.13 2.51 + endloop + endfacet + facet normal -0.167404 -0.278372 -0.945772 + outer loop + vertex 1.54174 1.13 2.51 + vertex 1.53919 1.12371 2.5123 + vertex 1.53884 1.12849 2.51096 + endloop + endfacet + facet normal -0.812584 -0.211828 -0.542989 + outer loop + vertex 1.53884 1.12849 2.51096 + vertex 1.53919 1.12371 2.5123 + vertex 1.53759 1.12574 2.51391 + endloop + endfacet + facet normal -0.741947 -0.303115 -0.598026 + outer loop + vertex 1.53745 1.12879 2.51254 + vertex 1.53884 1.12849 2.51096 + vertex 1.53759 1.12574 2.51391 + endloop + endfacet + facet normal -0.881302 -0.351809 0.315494 + outer loop + vertex 1.53773 1.12249 2.51881 + vertex 1.53862 1.12302 2.5219 + vertex 1.53737 1.12485 2.52044 + endloop + endfacet + facet normal -0.875361 -0.292204 0.385175 + outer loop + vertex 1.53776 1.12652 2.52259 + vertex 1.53737 1.12485 2.52044 + vertex 1.53862 1.12302 2.5219 + endloop + endfacet + facet normal -0.709848 -0.301051 0.636776 + outer loop + vertex 1.53776 1.12652 2.52259 + vertex 1.53862 1.12302 2.5219 + vertex 1.53941 1.12729 2.52478 + endloop + endfacet + facet normal -0.688227 -0.316022 0.653049 + outer loop + vertex 1.53941 1.12729 2.52478 + vertex 1.53862 1.12302 2.5219 + vertex 1.54089 1.12398 2.52475 + endloop + endfacet + facet normal -0.360405 -0.171671 0.916863 + outer loop + vertex 1.54089 1.12398 2.52475 + vertex 1.54304 1.12925 2.52658 + vertex 1.53941 1.12729 2.52478 + endloop + endfacet + facet normal -0.32092 -0.191519 0.92754 + outer loop + vertex 1.54377 1.12502 2.52596 + vertex 1.54304 1.12925 2.52658 + vertex 1.54089 1.12398 2.52475 + endloop + endfacet + facet normal -0.285933 0.0524609 -0.956812 + outer loop + vertex 1.53828 1.13129 2.51085 + vertex 1.53877 1.13514 2.51092 + vertex 1.54181 1.135 2.51 + endloop + endfacet + facet normal -0.16388 -0.0699948 -0.983994 + outer loop + vertex 1.53828 1.13129 2.51085 + vertex 1.54181 1.135 2.51 + vertex 1.53884 1.12849 2.51096 + endloop + endfacet + facet normal -0.315889 0.00442846 -0.948786 + outer loop + vertex 1.53884 1.12849 2.51096 + vertex 1.54181 1.135 2.51 + vertex 1.54174 1.13 2.51 + endloop + endfacet + facet normal -0.753893 -0.176697 -0.63279 + outer loop + vertex 1.53884 1.12849 2.51096 + vertex 1.53745 1.12879 2.51254 + vertex 1.53828 1.13129 2.51085 + endloop + endfacet + facet normal -0.744798 -0.212988 0.632386 + outer loop + vertex 1.53776 1.12652 2.52259 + vertex 1.53941 1.12729 2.52478 + vertex 1.53801 1.12989 2.52402 + endloop + endfacet + facet normal -0.677783 -0.151422 0.719501 + outer loop + vertex 1.53941 1.12729 2.52478 + vertex 1.54023 1.13294 2.52675 + vertex 1.53801 1.12989 2.52402 + endloop + endfacet + facet normal -0.30367 -0.27295 0.912843 + outer loop + vertex 1.53941 1.12729 2.52478 + vertex 1.54304 1.12925 2.52658 + vertex 1.54023 1.13294 2.52675 + endloop + endfacet + facet normal -0.216649 -0.208359 0.953756 + outer loop + vertex 1.54304 1.12925 2.52658 + vertex 1.544 1.13429 2.5279 + vertex 1.54023 1.13294 2.52675 + endloop + endfacet + facet normal -0.287073 0.0315731 -0.957388 + outer loop + vertex 1.54236 1.14 2.51 + vertex 1.54181 1.135 2.51 + vertex 1.53877 1.13514 2.51092 + endloop + endfacet + facet normal -0.745641 0.45998 -0.482117 + outer loop + vertex 1.54 1.14 2.51365 + vertex 1.54236 1.14 2.51 + vertex 1.53877 1.13514 2.51092 + endloop + endfacet + facet normal -0.19215 -0.26854 0.943909 + outer loop + vertex 1.544 1.13429 2.5279 + vertex 1.54327 1.13821 2.52887 + vertex 1.54023 1.13294 2.52675 + endloop + endfacet + facet normal -0.168514 -0.282382 0.944385 + outer loop + vertex 1.54023 1.13294 2.52675 + vertex 1.54327 1.13821 2.52887 + vertex 1.53937 1.13882 2.52835 + endloop + endfacet + facet normal -0.43542 -0.43661 0.787262 + outer loop + vertex 1.53985 1.14232 2.53056 + vertex 1.53799 1.14195 2.52932 + vertex 1.53937 1.13882 2.52835 + endloop + endfacet + facet normal 0.156887 -0.542408 0.825336 + outer loop + vertex 1.53985 1.14232 2.53056 + vertex 1.53937 1.13882 2.52835 + vertex 1.54307 1.14297 2.53038 + endloop + endfacet + facet normal -0.171046 -0.304625 0.936988 + outer loop + vertex 1.54307 1.14297 2.53038 + vertex 1.53937 1.13882 2.52835 + vertex 1.54327 1.13821 2.52887 + endloop + endfacet + facet normal -0.699201 0.366703 -0.613715 + outer loop + vertex 1.54086 1.165 2.515 + vertex 1.54 1.16336 2.515 + vertex 1.54 1.165 2.51598 + endloop + endfacet + facet normal 0.0329931 -0.271173 0.961965 + outer loop + vertex 1.53755 1.16354 2.53347 + vertex 1.54246 1.16825 2.53463 + vertex 1.53853 1.16912 2.53501 + endloop + endfacet + facet normal 0.203582 -0.0458261 0.977985 + outer loop + vertex 1.53873 1.43245 2.56555 + vertex 1.53605 1.43299 2.56614 + vertex 1.53648 1.42983 2.5659 + endloop + endfacet + facet normal 0.204312 -0.0422363 0.977994 + outer loop + vertex 1.53947 1.43621 2.56556 + vertex 1.53605 1.43299 2.56614 + vertex 1.53873 1.43245 2.56555 + endloop + endfacet + facet normal -0.84903 -0.0475495 -0.526201 + outer loop + vertex 1.54223 1.895 2.51 + vertex 1.54251 1.89 2.51 + vertex 1.54 1.89 2.51405 + endloop + endfacet + facet normal 0.0919627 -0.651202 -0.753312 + outer loop + vertex 1.53878 1.89297 2.51134 + vertex 1.54223 1.895 2.51 + vertex 1.54 1.89 2.51405 + endloop + endfacet + facet normal -0.786369 0.0377879 -0.6166 + outer loop + vertex 1.53878 1.89297 2.51134 + vertex 1.53765 1.89448 2.51288 + vertex 1.53923 1.89843 2.51111 + endloop + endfacet + facet normal -0.356467 -0.0105097 -0.934249 + outer loop + vertex 1.53878 1.89297 2.51134 + vertex 1.53923 1.89843 2.51111 + vertex 1.54223 1.895 2.51 + endloop + endfacet + facet normal -0.386497 -0.040969 -0.92138 + outer loop + vertex 1.54223 1.895 2.51 + vertex 1.53923 1.89843 2.51111 + vertex 1.5417 1.9 2.51 + endloop + endfacet + facet normal -0.910263 0.201691 -0.361582 + outer loop + vertex 1.53923 1.89843 2.51111 + vertex 1.53765 1.89448 2.51288 + vertex 1.53769 1.89734 2.51437 + endloop + endfacet + facet normal -0.864968 0.501823 -0.00213284 + outer loop + vertex 1.53863 1.89919 2.52106 + vertex 1.53694 1.89627 2.51975 + vertex 1.53703 1.89643 2.52212 + endloop + endfacet + facet normal -0.831973 0.537029 0.139358 + outer loop + vertex 1.53863 1.89919 2.52106 + vertex 1.53703 1.89643 2.52212 + vertex 1.53778 1.8973 2.5233 + endloop + endfacet + facet normal -0.250507 0.254471 0.934072 + outer loop + vertex 1.53865 1.89189 2.52667 + vertex 1.5415 1.89434 2.52677 + vertex 1.53847 1.89476 2.52585 + endloop + endfacet + facet normal -0.413898 0.00993718 -0.910269 + outer loop + vertex 1.5417 1.9 2.51 + vertex 1.53923 1.89843 2.51111 + vertex 1.54182 1.905 2.51 + endloop + endfacet + facet normal -0.347353 -0.0208968 -0.937502 + outer loop + vertex 1.54182 1.905 2.51 + vertex 1.53923 1.89843 2.51111 + vertex 1.53971 1.90408 2.5108 + endloop + endfacet + facet normal -0.964479 0.239694 -0.111026 + outer loop + vertex 1.53769 1.89734 2.51437 + vertex 1.53746 1.89782 2.51737 + vertex 1.53873 1.90191 2.51523 + endloop + endfacet + facet normal -0.902993 0.2677 -0.336066 + outer loop + vertex 1.53769 1.89734 2.51437 + vertex 1.53873 1.90191 2.51523 + vertex 1.53923 1.89843 2.51111 + endloop + endfacet + facet normal -0.980731 0.0733965 -0.181053 + outer loop + vertex 1.53923 1.89843 2.51111 + vertex 1.53873 1.90191 2.51523 + vertex 1.53971 1.90408 2.5108 + endloop + endfacet + facet normal -0.880533 0.461662 0.107378 + outer loop + vertex 1.53746 1.89782 2.51737 + vertex 1.53694 1.89627 2.51975 + vertex 1.53863 1.89919 2.52106 + endloop + endfacet + facet normal -0.918071 0.364741 0.15527 + outer loop + vertex 1.53746 1.89782 2.51737 + vertex 1.53863 1.89919 2.52106 + vertex 1.53873 1.90191 2.51523 + endloop + endfacet + facet normal -0.918219 0.364432 0.155123 + outer loop + vertex 1.53873 1.90191 2.51523 + vertex 1.53863 1.89919 2.52106 + vertex 1.54056 1.90442 2.52018 + endloop + endfacet + facet normal -0.584071 0.339677 0.737211 + outer loop + vertex 1.5436 1.90188 2.52376 + vertex 1.54056 1.90442 2.52018 + vertex 1.53863 1.89919 2.52106 + endloop + endfacet + facet normal -0.605232 0.630032 0.486573 + outer loop + vertex 1.5436 1.90188 2.52376 + vertex 1.53863 1.89919 2.52106 + vertex 1.53976 1.89742 2.52475 + endloop + endfacet + facet normal -0.260841 0.418609 0.869901 + outer loop + vertex 1.5436 1.90188 2.52376 + vertex 1.53976 1.89742 2.52475 + vertex 1.54355 1.89774 2.52573 + endloop + endfacet + facet normal -0.412184 0.766317 0.492811 + outer loop + vertex 1.53976 1.89742 2.52475 + vertex 1.53863 1.89919 2.52106 + vertex 1.53778 1.8973 2.5233 + endloop + endfacet + facet normal -0.202451 0.454565 0.867401 + outer loop + vertex 1.5415 1.89434 2.52677 + vertex 1.53976 1.89742 2.52475 + vertex 1.53847 1.89476 2.52585 + endloop + endfacet + facet normal -0.2607 0.422234 0.86819 + outer loop + vertex 1.54355 1.89774 2.52573 + vertex 1.53976 1.89742 2.52475 + vertex 1.5415 1.89434 2.52677 + endloop + endfacet + facet normal -0.356696 0.00356331 -0.934214 + outer loop + vertex 1.54182 1.905 2.51 + vertex 1.53971 1.90408 2.5108 + vertex 1.54187 1.91 2.51 + endloop + endfacet + facet normal -0.728636 0.176561 -0.661752 + outer loop + vertex 1.54187 1.91 2.51 + vertex 1.53971 1.90408 2.5108 + vertex 1.53988 1.90791 2.51164 + endloop + endfacet + facet normal -0.980817 0.0820746 -0.17681 + outer loop + vertex 1.53971 1.90408 2.5108 + vertex 1.53873 1.90191 2.51523 + vertex 1.53988 1.90791 2.51164 + endloop + endfacet + facet normal -0.985205 0.167803 -0.0348377 + outer loop + vertex 1.53988 1.90791 2.51164 + vertex 1.53873 1.90191 2.51523 + vertex 1.53972 1.9079 2.51596 + endloop + endfacet + facet normal -0.949348 0.121746 0.289683 + outer loop + vertex 1.53873 1.90191 2.51523 + vertex 1.54056 1.90442 2.52018 + vertex 1.53972 1.9079 2.51596 + endloop + endfacet + facet normal -0.953498 0.109821 0.28068 + outer loop + vertex 1.53972 1.9079 2.51596 + vertex 1.54056 1.90442 2.52018 + vertex 1.54109 1.90956 2.51995 + endloop + endfacet + facet normal -0.706715 0.103104 0.699945 + outer loop + vertex 1.54056 1.90442 2.52018 + vertex 1.54338 1.90734 2.52259 + vertex 1.54109 1.90956 2.51995 + endloop + endfacet + facet normal -0.713989 0.118277 0.690095 + outer loop + vertex 1.5436 1.90188 2.52376 + vertex 1.54338 1.90734 2.52259 + vertex 1.54056 1.90442 2.52018 + endloop + endfacet + facet normal -0.646036 0.0180828 -0.763093 + outer loop + vertex 1.54187 1.91 2.51 + vertex 1.53988 1.90791 2.51164 + vertex 1.54201 1.915 2.51 + endloop + endfacet + facet normal -0.716861 0.0551303 -0.695033 + outer loop + vertex 1.54201 1.915 2.51 + vertex 1.53988 1.90791 2.51164 + vertex 1.54009 1.91245 2.51177 + endloop + endfacet + facet normal -0.99817 0.0487245 -0.0358141 + outer loop + vertex 1.53988 1.90791 2.51164 + vertex 1.53972 1.9079 2.51596 + vertex 1.54009 1.91245 2.51177 + endloop + endfacet + facet normal -0.996616 0.0821965 0.000673374 + outer loop + vertex 1.54009 1.91245 2.51177 + vertex 1.53972 1.9079 2.51596 + vertex 1.54014 1.91302 2.5161 + endloop + endfacet + facet normal -0.952388 0.0708463 0.296542 + outer loop + vertex 1.53972 1.9079 2.51596 + vertex 1.54109 1.90956 2.51995 + vertex 1.54014 1.91302 2.5161 + endloop + endfacet + facet normal -0.96024 0.0452549 0.275482 + outer loop + vertex 1.54014 1.91302 2.5161 + vertex 1.54109 1.90956 2.51995 + vertex 1.54121 1.91432 2.51962 + endloop + endfacet + facet normal -0.745497 0.066684 0.663165 + outer loop + vertex 1.54109 1.90956 2.51995 + vertex 1.54316 1.91199 2.52204 + vertex 1.54121 1.91432 2.51962 + endloop + endfacet + facet normal -0.734874 0.0460486 0.676638 + outer loop + vertex 1.54338 1.90734 2.52259 + vertex 1.54316 1.91199 2.52204 + vertex 1.54109 1.90956 2.51995 + endloop + endfacet + facet normal -0.0433726 -0.209516 -0.976843 + outer loop + vertex 1.545 1.91515 2.505 + vertex 1.5427 1.9163 2.50486 + vertex 1.545 1.92 2.50396 + endloop + endfacet + facet normal -0.125838 -0.367429 -0.921499 + outer loop + vertex 1.545 1.915 2.50506 + vertex 1.5427 1.9163 2.50486 + vertex 1.545 1.91515 2.505 + endloop + endfacet + facet normal -0.454589 -0.847139 -0.275145 + outer loop + vertex 1.545 1.915 2.50506 + vertex 1.54201 1.915 2.51 + vertex 1.5427 1.9163 2.50486 + endloop + endfacet + facet normal -0.576845 -0.770181 -0.272158 + outer loop + vertex 1.54201 1.915 2.51 + vertex 1.54095 1.91658 2.50775 + vertex 1.5427 1.9163 2.50486 + endloop + endfacet + facet normal 0.327934 -0.692572 -0.642497 + outer loop + vertex 1.54201 1.915 2.51 + vertex 1.54009 1.91245 2.51177 + vertex 1.54095 1.91658 2.50775 + endloop + endfacet + facet normal -0.982489 0.0250146 -0.184633 + outer loop + vertex 1.54095 1.91658 2.50775 + vertex 1.54009 1.91245 2.51177 + vertex 1.54022 1.91703 2.51174 + endloop + endfacet + facet normal -0.999601 0.0271016 0.00795422 + outer loop + vertex 1.54009 1.91245 2.51177 + vertex 1.54014 1.91302 2.5161 + vertex 1.54022 1.91703 2.51174 + endloop + endfacet + facet normal -0.996399 0.0701656 0.047599 + outer loop + vertex 1.54022 1.91703 2.51174 + vertex 1.54014 1.91302 2.5161 + vertex 1.54048 1.91793 2.51585 + endloop + endfacet + facet normal -0.961463 0.0785642 0.26347 + outer loop + vertex 1.54014 1.91302 2.5161 + vertex 1.54121 1.91432 2.51962 + vertex 1.54048 1.91793 2.51585 + endloop + endfacet + facet normal -0.949996 0.110662 0.291996 + outer loop + vertex 1.54048 1.91793 2.51585 + vertex 1.54121 1.91432 2.51962 + vertex 1.54158 1.91876 2.51913 + endloop + endfacet + facet normal -0.796688 0.130755 0.590077 + outer loop + vertex 1.54121 1.91432 2.51962 + vertex 1.54278 1.91584 2.52139 + vertex 1.54158 1.91876 2.51913 + endloop + endfacet + facet normal -0.763574 0.0326862 0.644892 + outer loop + vertex 1.54316 1.91199 2.52204 + vertex 1.54278 1.91584 2.52139 + vertex 1.54121 1.91432 2.51962 + endloop + endfacet + facet normal -0.33415 0.0207586 -0.942291 + outer loop + vertex 1.545 1.92 2.50396 + vertex 1.54246 1.92106 2.50489 + vertex 1.545 1.925 2.50407 + endloop + endfacet + facet normal -0.346319 -0.0120199 -0.93804 + outer loop + vertex 1.5427 1.9163 2.50486 + vertex 1.54246 1.92106 2.50489 + vertex 1.545 1.92 2.50396 + endloop + endfacet + facet normal -0.857365 -0.0409825 -0.513075 + outer loop + vertex 1.5427 1.9163 2.50486 + vertex 1.54095 1.91658 2.50775 + vertex 1.54246 1.92106 2.50489 + endloop + endfacet + facet normal -0.898354 0.0203158 -0.438803 + outer loop + vertex 1.54246 1.92106 2.50489 + vertex 1.54095 1.91658 2.50775 + vertex 1.54085 1.92035 2.50815 + endloop + endfacet + facet normal -0.983436 -0.00903127 -0.181029 + outer loop + vertex 1.54095 1.91658 2.50775 + vertex 1.54022 1.91703 2.51174 + vertex 1.54085 1.92035 2.50815 + endloop + endfacet + facet normal -0.991797 0.0854472 -0.095064 + outer loop + vertex 1.54085 1.92035 2.50815 + vertex 1.54022 1.91703 2.51174 + vertex 1.54065 1.92176 2.51151 + endloop + endfacet + facet normal -0.994825 0.0922188 0.0426578 + outer loop + vertex 1.54022 1.91703 2.51174 + vertex 1.54048 1.91793 2.51585 + vertex 1.54065 1.92176 2.51151 + endloop + endfacet + facet normal -0.985433 0.144703 0.0893492 + outer loop + vertex 1.54065 1.92176 2.51151 + vertex 1.54048 1.91793 2.51585 + vertex 1.54113 1.92262 2.51549 + endloop + endfacet + facet normal -0.947526 0.154066 0.280104 + outer loop + vertex 1.54048 1.91793 2.51585 + vertex 1.54158 1.91876 2.51913 + vertex 1.54113 1.92262 2.51549 + endloop + endfacet + facet normal -0.873123 0.276912 0.401219 + outer loop + vertex 1.54113 1.92262 2.51549 + vertex 1.54158 1.91876 2.51913 + vertex 1.54267 1.92289 2.51864 + endloop + endfacet + facet normal -0.69744 0.261993 0.667036 + outer loop + vertex 1.54158 1.91876 2.51913 + vertex 1.54357 1.91925 2.52102 + vertex 1.54267 1.92289 2.51864 + endloop + endfacet + facet normal -0.698834 0.236552 0.675036 + outer loop + vertex 1.54278 1.91584 2.52139 + vertex 1.54357 1.91925 2.52102 + vertex 1.54158 1.91876 2.51913 + endloop + endfacet + facet normal -0.580163 0.212007 -0.786425 + outer loop + vertex 1.545 1.925 2.50407 + vertex 1.54246 1.92106 2.50489 + vertex 1.545 1.92845 2.505 + endloop + endfacet + facet normal -0.188875 -0.386292 -0.902831 + outer loop + vertex 1.545 1.92845 2.505 + vertex 1.54176 1.9252 2.50707 + vertex 1.5432 1.92962 2.50488 + endloop + endfacet + facet normal -0.68514 0.246582 -0.685405 + outer loop + vertex 1.545 1.92845 2.505 + vertex 1.54246 1.92106 2.50489 + vertex 1.54176 1.9252 2.50707 + endloop + endfacet + facet normal -0.900677 0.0743332 -0.428083 + outer loop + vertex 1.54246 1.92106 2.50489 + vertex 1.54085 1.92035 2.50815 + vertex 1.54176 1.9252 2.50707 + endloop + endfacet + facet normal -0.979797 0.156691 -0.124285 + outer loop + vertex 1.54085 1.92035 2.50815 + vertex 1.54065 1.92176 2.51151 + vertex 1.54176 1.9252 2.50707 + endloop + endfacet + facet normal -0.980396 0.144775 -0.133652 + outer loop + vertex 1.54176 1.9252 2.50707 + vertex 1.54065 1.92176 2.51151 + vertex 1.54135 1.92636 2.51135 + endloop + endfacet + facet normal -0.984328 0.15317 0.0873896 + outer loop + vertex 1.54065 1.92176 2.51151 + vertex 1.54113 1.92262 2.51549 + vertex 1.54135 1.92636 2.51135 + endloop + endfacet + facet normal -0.943857 0.268009 0.193144 + outer loop + vertex 1.54135 1.92636 2.51135 + vertex 1.54113 1.92262 2.51549 + vertex 1.54241 1.92727 2.51526 + endloop + endfacet + facet normal -0.514804 0.391957 0.762461 + outer loop + vertex 1.54509 1.92659 2.51838 + vertex 1.54267 1.92289 2.51864 + vertex 1.5448 1.92248 2.52029 + endloop + endfacet + facet normal -0.623265 0.453994 0.636734 + outer loop + vertex 1.54509 1.92659 2.51838 + vertex 1.54241 1.92727 2.51526 + vertex 1.54267 1.92289 2.51864 + endloop + endfacet + facet normal -0.876796 0.260135 0.404424 + outer loop + vertex 1.54241 1.92727 2.51526 + vertex 1.54113 1.92262 2.51549 + vertex 1.54267 1.92289 2.51864 + endloop + endfacet + facet normal -0.52266 0.371121 0.767526 + outer loop + vertex 1.5448 1.92248 2.52029 + vertex 1.54267 1.92289 2.51864 + vertex 1.54357 1.91925 2.52102 + endloop + endfacet + facet normal -0.922282 0.0234727 -0.385805 + outer loop + vertex 1.5432 1.92962 2.50488 + vertex 1.54199 1.92967 2.50777 + vertex 1.54301 1.93263 2.50551 + endloop + endfacet + facet normal -0.916658 0.107151 -0.385041 + outer loop + vertex 1.54176 1.9252 2.50707 + vertex 1.54199 1.92967 2.50777 + vertex 1.5432 1.92962 2.50488 + endloop + endfacet + facet normal -0.991134 0.0683149 -0.11396 + outer loop + vertex 1.54176 1.9252 2.50707 + vertex 1.54135 1.92636 2.51135 + vertex 1.54199 1.92967 2.50777 + endloop + endfacet + facet normal -0.982338 0.187101 -0.00238835 + outer loop + vertex 1.54199 1.92967 2.50777 + vertex 1.54135 1.92636 2.51135 + vertex 1.54211 1.93037 2.51148 + endloop + endfacet + facet normal -0.786049 0.283907 0.549112 + outer loop + vertex 1.54293 1.9311 2.51403 + vertex 1.54241 1.92727 2.51526 + vertex 1.54407 1.93014 2.51616 + endloop + endfacet + facet normal -0.946896 0.208326 0.244923 + outer loop + vertex 1.54293 1.9311 2.51403 + vertex 1.54211 1.93037 2.51148 + vertex 1.54241 1.92727 2.51526 + endloop + endfacet + facet normal -0.959786 0.175521 0.219098 + outer loop + vertex 1.54211 1.93037 2.51148 + vertex 1.54135 1.92636 2.51135 + vertex 1.54241 1.92727 2.51526 + endloop + endfacet + facet normal -0.71804 0.208538 0.664026 + outer loop + vertex 1.54407 1.93014 2.51616 + vertex 1.54241 1.92727 2.51526 + vertex 1.54509 1.92659 2.51838 + endloop + endfacet + facet normal -0.964445 0.209452 -0.161171 + outer loop + vertex 1.54301 1.93263 2.50551 + vertex 1.54199 1.92967 2.50777 + vertex 1.54268 1.93343 2.50849 + endloop + endfacet + facet normal -0.960308 0.264977 0.0871506 + outer loop + vertex 1.54268 1.93343 2.50849 + vertex 1.54211 1.93037 2.51148 + vertex 1.54296 1.93332 2.51188 + endloop + endfacet + facet normal -0.983193 0.182563 -0.00151024 + outer loop + vertex 1.54199 1.92967 2.50777 + vertex 1.54211 1.93037 2.51148 + vertex 1.54268 1.93343 2.50849 + endloop + endfacet + facet normal -0.942068 0.240017 0.234307 + outer loop + vertex 1.54296 1.93332 2.51188 + vertex 1.54211 1.93037 2.51148 + vertex 1.54293 1.9311 2.51403 + endloop + endfacet + facet normal -0.766248 -0.638682 -0.0703506 + outer loop + vertex 1.5425 1.99534 2.49638 + vertex 1.54056 1.99754 2.4975 + vertex 1.54113 1.99719 2.49453 + endloop + endfacet + facet normal -0.736275 -0.674684 0.0519761 + outer loop + vertex 1.54269 1.99534 2.4991 + vertex 1.54056 1.99754 2.4975 + vertex 1.5425 1.99534 2.49638 + endloop + endfacet + facet normal -0.769572 -0.611762 0.183048 + outer loop + vertex 1.54078 1.99799 2.49994 + vertex 1.54056 1.99754 2.4975 + vertex 1.54269 1.99534 2.4991 + endloop + endfacet + facet normal -0.588222 -0.596248 0.546336 + outer loop + vertex 1.54269 1.99534 2.4991 + vertex 1.54328 1.99675 2.50128 + vertex 1.54078 1.99799 2.49994 + endloop + endfacet + facet normal -0.220825 -0.28238 -0.933541 + outer loop + vertex 1.545 2.00036 2.49 + vertex 1.54132 1.99914 2.49124 + vertex 1.54 2.00427 2.49 + endloop + endfacet + facet normal -0.198008 -0.278068 -0.939931 + outer loop + vertex 1.54132 1.99914 2.49124 + vertex 1.53855 2.00153 2.49112 + vertex 1.54 2.00427 2.49 + endloop + endfacet + facet normal -0.741201 -0.668403 -0.0621134 + outer loop + vertex 1.54113 1.99719 2.49453 + vertex 1.54056 1.99754 2.4975 + vertex 1.53867 1.99989 2.49474 + endloop + endfacet + facet normal -0.694731 -0.600314 -0.396197 + outer loop + vertex 1.54113 1.99719 2.49453 + vertex 1.53867 1.99989 2.49474 + vertex 1.54132 1.99914 2.49124 + endloop + endfacet + facet normal -0.614447 -0.726241 -0.308268 + outer loop + vertex 1.54132 1.99914 2.49124 + vertex 1.53867 1.99989 2.49474 + vertex 1.53855 2.00153 2.49112 + endloop + endfacet + facet normal -0.783725 -0.594134 0.181049 + outer loop + vertex 1.54056 1.99754 2.4975 + vertex 1.54078 1.99799 2.49994 + vertex 1.53881 2.00022 2.49873 + endloop + endfacet + facet normal -0.818919 -0.568905 0.0756196 + outer loop + vertex 1.53867 1.99989 2.49474 + vertex 1.54056 1.99754 2.4975 + vertex 1.53881 2.00022 2.49873 + endloop + endfacet + facet normal -0.757237 -0.380555 0.530821 + outer loop + vertex 1.54078 1.99799 2.49994 + vertex 1.54024 2.00037 2.50087 + vertex 1.53881 2.00022 2.49873 + endloop + endfacet + facet normal -0.580143 -0.408586 0.704622 + outer loop + vertex 1.54078 1.99799 2.49994 + vertex 1.54328 1.99675 2.50128 + vertex 1.54024 2.00037 2.50087 + endloop + endfacet + facet normal 0.154693 0.396651 0.904842 + outer loop + vertex 1.53797 2.10308 2.47059 + vertex 1.54038 2.10056 2.47128 + vertex 1.54222 2.10372 2.46958 + endloop + endfacet + facet normal 0.140091 0.454509 0.879657 + outer loop + vertex 1.53797 2.10308 2.47059 + vertex 1.54222 2.10372 2.46958 + vertex 1.53686 2.10724 2.46862 + endloop + endfacet + facet normal 0.154923 0.473638 0.866986 + outer loop + vertex 1.53686 2.10724 2.46862 + vertex 1.54222 2.10372 2.46958 + vertex 1.54164 2.10736 2.4677 + endloop + endfacet + facet normal 0.130181 0.376602 0.917182 + outer loop + vertex 1.54038 2.10056 2.47128 + vertex 1.53797 2.10308 2.47059 + vertex 1.53628 2.09981 2.47217 + endloop + endfacet + facet normal 0.174466 0.662281 0.72866 + outer loop + vertex 1.5397 2.11 2.46625 + vertex 1.54387 2.10932 2.46587 + vertex 1.54167 2.11191 2.46404 + endloop + endfacet + facet normal 0.204253 0.642784 0.738316 + outer loop + vertex 1.53878 2.11196 2.4648 + vertex 1.5397 2.11 2.46625 + vertex 1.54167 2.11191 2.46404 + endloop + endfacet + facet normal 0.143746 0.554896 0.819407 + outer loop + vertex 1.54164 2.10736 2.4677 + vertex 1.5397 2.11 2.46625 + vertex 1.53686 2.10724 2.46862 + endloop + endfacet + facet normal 0.165845 0.564991 0.808258 + outer loop + vertex 1.54387 2.10932 2.46587 + vertex 1.5397 2.11 2.46625 + vertex 1.54164 2.10736 2.4677 + endloop + endfacet + facet normal 0.162617 0.849391 0.502086 + outer loop + vertex 1.53804 2.11393 2.46265 + vertex 1.544 2.11393 2.46073 + vertex 1.54035 2.11592 2.45854 + endloop + endfacet + facet normal 0.212632 0.827548 0.51957 + outer loop + vertex 1.53637 2.11619 2.45974 + vertex 1.53804 2.11393 2.46265 + vertex 1.54035 2.11592 2.45854 + endloop + endfacet + facet normal 0.178071 0.754068 0.632196 + outer loop + vertex 1.54167 2.11191 2.46404 + vertex 1.53804 2.11393 2.46265 + vertex 1.53878 2.11196 2.4648 + endloop + endfacet + facet normal 0.196454 0.769883 0.607195 + outer loop + vertex 1.544 2.11393 2.46073 + vertex 1.53804 2.11393 2.46265 + vertex 1.54167 2.11191 2.46404 + endloop + endfacet + facet normal 0.0498944 0.265439 0.962836 + outer loop + vertex 1.545 2.1224 2.45 + vertex 1.54 2.12334 2.45 + vertex 1.54231 2.11961 2.45091 + endloop + endfacet + facet normal 0.292746 0.393816 0.871326 + outer loop + vertex 1.54231 2.11961 2.45091 + vertex 1.54 2.12334 2.45 + vertex 1.53903 2.11941 2.4521 + endloop + endfacet + facet normal 0.142078 0.834327 0.532646 + outer loop + vertex 1.54231 2.11961 2.45091 + vertex 1.53903 2.11941 2.4521 + vertex 1.54226 2.11746 2.45429 + endloop + endfacet + facet normal 0.209883 0.863441 0.458714 + outer loop + vertex 1.54226 2.11746 2.45429 + vertex 1.53903 2.11941 2.4521 + vertex 1.53676 2.118 2.45579 + endloop + endfacet + facet normal 0.187776 0.885481 0.425045 + outer loop + vertex 1.54035 2.11592 2.45854 + vertex 1.53676 2.118 2.45579 + vertex 1.53637 2.11619 2.45974 + endloop + endfacet + facet normal 0.199691 0.888979 0.412117 + outer loop + vertex 1.54226 2.11746 2.45429 + vertex 1.53676 2.118 2.45579 + vertex 1.54035 2.11592 2.45854 + endloop + endfacet + facet normal 0.119824 0.667349 -0.735043 + outer loop + vertex 1.54543 0.91 2.45 + vertex 1.54158 0.909066 2.44852 + vertex 1.545 0.91 2.44993 + endloop + endfacet + facet normal -0.261694 0.962333 0.0736928 + outer loop + vertex 1.54543 0.91 2.45 + vertex 1.54346 0.909541 2.44901 + vertex 1.54158 0.909066 2.44852 + endloop + endfacet + facet normal -0.181651 0.97895 -0.0930595 + outer loop + vertex 1.54346 0.909541 2.44901 + vertex 1.54543 0.91 2.45 + vertex 1.55 0.910848 2.45 + endloop + endfacet + facet normal 0.125753 -0.916521 0.379704 + outer loop + vertex 1.54346 0.909541 2.44901 + vertex 1.55 0.910848 2.45 + vertex 1.54277 0.910276 2.45101 + endloop + endfacet + facet normal 0.139318 -0.844464 0.517177 + outer loop + vertex 1.54277 0.910276 2.45101 + vertex 1.55 0.910848 2.45 + vertex 1.5467 0.911746 2.45235 + endloop + endfacet + facet normal 0.203103 -0.871728 0.445914 + outer loop + vertex 1.54546 0.913039 2.45545 + vertex 1.5467 0.911746 2.45235 + vertex 1.54947 0.913317 2.45416 + endloop + endfacet + facet normal 0.18714 -0.877354 0.441848 + outer loop + vertex 1.54546 0.913039 2.45545 + vertex 1.54143 0.911913 2.45492 + vertex 1.5467 0.911746 2.45235 + endloop + endfacet + facet normal 0.182527 -0.882857 0.432721 + outer loop + vertex 1.54143 0.911913 2.45492 + vertex 1.54277 0.910276 2.45101 + vertex 1.5467 0.911746 2.45235 + endloop + endfacet + facet normal 0.17222 -0.850203 0.497488 + outer loop + vertex 1.54546 0.913039 2.45545 + vertex 1.54291 0.913827 2.45768 + vertex 1.54143 0.911913 2.45492 + endloop + endfacet + facet normal 0.219814 -0.833908 0.50624 + outer loop + vertex 1.54947 0.913317 2.45416 + vertex 1.54713 0.915037 2.45802 + vertex 1.54546 0.913039 2.45545 + endloop + endfacet + facet normal 0.197057 -0.831588 0.519258 + outer loop + vertex 1.54291 0.913827 2.45768 + vertex 1.54546 0.913039 2.45545 + vertex 1.54713 0.915037 2.45802 + endloop + endfacet + facet normal 0.177067 -0.783421 0.595734 + outer loop + vertex 1.54291 0.913827 2.45768 + vertex 1.54713 0.915037 2.45802 + vertex 1.54204 0.916022 2.46082 + endloop + endfacet + facet normal 0.175209 -0.785767 0.593188 + outer loop + vertex 1.54204 0.916022 2.46082 + vertex 1.54713 0.915037 2.45802 + vertex 1.5466 0.917392 2.46129 + endloop + endfacet + facet normal 0.144879 -0.715621 0.683298 + outer loop + vertex 1.5466 0.917392 2.46129 + vertex 1.54383 0.919105 2.46367 + vertex 1.54204 0.916022 2.46082 + endloop + endfacet + facet normal 0.150032 -0.711592 0.686387 + outer loop + vertex 1.54913 0.920026 2.46347 + vertex 1.54383 0.919105 2.46367 + vertex 1.5466 0.917392 2.46129 + endloop + endfacet + facet normal 0.13989 -0.637555 0.757598 + outer loop + vertex 1.54383 0.919105 2.46367 + vertex 1.54913 0.920026 2.46347 + vertex 1.546 0.922077 2.46577 + endloop + endfacet + facet normal 0.134177 -0.6354 0.760436 + outer loop + vertex 1.54122 0.92143 2.46608 + vertex 1.54383 0.919105 2.46367 + vertex 1.546 0.922077 2.46577 + endloop + endfacet + facet normal 0.126447 -0.547003 0.827526 + outer loop + vertex 1.546 0.922077 2.46577 + vertex 1.54402 0.924687 2.4678 + vertex 1.54122 0.92143 2.46608 + endloop + endfacet + facet normal 0.115123 -0.553511 0.824847 + outer loop + vertex 1.54864 0.925048 2.4674 + vertex 1.54402 0.924687 2.4678 + vertex 1.546 0.922077 2.46577 + endloop + endfacet + facet normal 0.113062 -0.472364 0.874122 + outer loop + vertex 1.54864 0.925048 2.4674 + vertex 1.54731 0.928094 2.46922 + vertex 1.54402 0.924687 2.4678 + endloop + endfacet + facet normal 0.113491 -0.302535 0.946357 + outer loop + vertex 1.54344 0.978688 2.48739 + vertex 1.54811 0.98364 2.48841 + vertex 1.54285 0.983227 2.48891 + endloop + endfacet + facet normal 0.104755 -0.299067 0.948465 + outer loop + vertex 1.54086 0.99041 2.49141 + vertex 1.54204 0.987107 2.49024 + vertex 1.54549 0.991195 2.49115 + endloop + endfacet + facet normal -0.109095 -0.650868 -0.751311 + outer loop + vertex 1.54653 1.03328 2.48654 + vertex 1.54815 1.03455 2.4852 + vertex 1.55 1.03448 2.485 + endloop + endfacet + facet normal -0.452995 0.191707 -0.870657 + outer loop + vertex 1.54653 1.03328 2.48654 + vertex 1.55 1.03448 2.485 + vertex 1.54413 1.0309 2.48727 + endloop + endfacet + facet normal -0.575587 0.769511 -0.276682 + outer loop + vertex 1.54413 1.0309 2.48727 + vertex 1.55 1.03448 2.485 + vertex 1.545 1.03074 2.485 + endloop + endfacet + facet normal -0.719468 0.658374 -0.221155 + outer loop + vertex 1.54529 1.03319 2.49029 + vertex 1.54653 1.03328 2.48654 + vertex 1.54413 1.0309 2.48727 + endloop + endfacet + facet normal -0.781659 0.603883 -0.155997 + outer loop + vertex 1.54282 1.03059 2.49262 + vertex 1.54529 1.03319 2.49029 + vertex 1.54413 1.0309 2.48727 + endloop + endfacet + facet normal -0.76184 0.640953 -0.0937025 + outer loop + vertex 1.54523 1.0339 2.49567 + vertex 1.54529 1.03319 2.49029 + vertex 1.54282 1.03059 2.49262 + endloop + endfacet + facet normal -0.812169 0.583358 0.00864353 + outer loop + vertex 1.54283 1.03054 2.49734 + vertex 1.54523 1.0339 2.49567 + vertex 1.54282 1.03059 2.49262 + endloop + endfacet + facet normal -0.76997 0.62125 0.145585 + outer loop + vertex 1.54566 1.03348 2.49973 + vertex 1.54523 1.0339 2.49567 + vertex 1.54283 1.03054 2.49734 + endloop + endfacet + facet normal -0.796332 0.534208 0.283686 + outer loop + vertex 1.54371 1.03033 2.5002 + vertex 1.54566 1.03348 2.49973 + vertex 1.54283 1.03054 2.49734 + endloop + endfacet + facet normal -0.56516 0.451476 0.690481 + outer loop + vertex 1.54371 1.03033 2.5002 + vertex 1.54757 1.03269 2.50182 + vertex 1.54566 1.03348 2.49973 + endloop + endfacet + facet normal -0.546358 0.383639 0.744523 + outer loop + vertex 1.54371 1.03033 2.5002 + vertex 1.54309 1.02761 2.50115 + vertex 1.54757 1.03269 2.50182 + endloop + endfacet + facet normal -0.744631 0.547849 -0.381294 + outer loop + vertex 1.54815 1.03455 2.4852 + vertex 1.54653 1.03328 2.48654 + vertex 1.54725 1.03527 2.48799 + endloop + endfacet + facet normal -0.810495 0.554892 -0.187599 + outer loop + vertex 1.54725 1.03527 2.48799 + vertex 1.54529 1.03319 2.49029 + vertex 1.54691 1.03631 2.49254 + endloop + endfacet + facet normal -0.830374 0.491904 -0.261744 + outer loop + vertex 1.54653 1.03328 2.48654 + vertex 1.54529 1.03319 2.49029 + vertex 1.54725 1.03527 2.48799 + endloop + endfacet + facet normal -0.861702 0.501718 -0.0758228 + outer loop + vertex 1.54691 1.03631 2.49254 + vertex 1.54523 1.0339 2.49567 + vertex 1.5471 1.03724 2.4965 + endloop + endfacet + facet normal -0.862012 0.501087 -0.0764748 + outer loop + vertex 1.54529 1.03319 2.49029 + vertex 1.54523 1.0339 2.49567 + vertex 1.54691 1.03631 2.49254 + endloop + endfacet + facet normal -0.923283 0.371606 0.0972491 + outer loop + vertex 1.5471 1.03724 2.4965 + vertex 1.5472 1.03676 2.49932 + vertex 1.54828 1.03956 2.4988 + endloop + endfacet + facet normal -0.878324 0.464829 0.111718 + outer loop + vertex 1.5471 1.03724 2.4965 + vertex 1.54523 1.0339 2.49567 + vertex 1.5472 1.03676 2.49932 + endloop + endfacet + facet normal -0.888588 0.437161 0.138929 + outer loop + vertex 1.54523 1.0339 2.49567 + vertex 1.54566 1.03348 2.49973 + vertex 1.5472 1.03676 2.49932 + endloop + endfacet + facet normal -0.779791 0.425745 0.458985 + outer loop + vertex 1.54566 1.03348 2.49973 + vertex 1.54895 1.0372 2.50187 + vertex 1.5472 1.03676 2.49932 + endloop + endfacet + facet normal -0.68264 0.20013 0.702816 + outer loop + vertex 1.54757 1.03269 2.50182 + vertex 1.54895 1.0372 2.50187 + vertex 1.54566 1.03348 2.49973 + endloop + endfacet + facet normal -0.876223 0.388595 0.285005 + outer loop + vertex 1.54828 1.03956 2.4988 + vertex 1.5472 1.03676 2.49932 + vertex 1.54924 1.03998 2.5012 + endloop + endfacet + facet normal -0.823142 0.215134 0.525505 + outer loop + vertex 1.54924 1.03998 2.5012 + vertex 1.5472 1.03676 2.49932 + vertex 1.54895 1.0372 2.50187 + endloop + endfacet + facet normal -0.817018 -0.201426 -0.540286 + outer loop + vertex 1.54806 1.06232 2.49671 + vertex 1.54697 1.06359 2.49788 + vertex 1.54794 1.06589 2.49555 + endloop + endfacet + facet normal -0.845735 -0.404172 -0.348393 + outer loop + vertex 1.54752 1.06072 2.49989 + vertex 1.54697 1.06359 2.49788 + vertex 1.54806 1.06232 2.49671 + endloop + endfacet + facet normal -0.975766 -0.214822 -0.0416184 + outer loop + vertex 1.54676 1.06396 2.50086 + vertex 1.54697 1.06359 2.49788 + vertex 1.54752 1.06072 2.49989 + endloop + endfacet + facet normal -0.961068 -0.255383 0.105491 + outer loop + vertex 1.54789 1.06091 2.50373 + vertex 1.54676 1.06396 2.50086 + vertex 1.54752 1.06072 2.49989 + endloop + endfacet + facet normal -0.965591 -0.176106 0.191368 + outer loop + vertex 1.54733 1.06504 2.50474 + vertex 1.54676 1.06396 2.50086 + vertex 1.54789 1.06091 2.50373 + endloop + endfacet + facet normal -0.825641 -0.235736 0.512588 + outer loop + vertex 1.54789 1.06091 2.50373 + vertex 1.54961 1.06209 2.50705 + vertex 1.54733 1.06504 2.50474 + endloop + endfacet + facet normal -0.86775 -0.0739556 -0.491468 + outer loop + vertex 1.54794 1.06589 2.49555 + vertex 1.54665 1.06694 2.49769 + vertex 1.54775 1.07022 2.49525 + endloop + endfacet + facet normal -0.872548 -0.112244 -0.47546 + outer loop + vertex 1.54697 1.06359 2.49788 + vertex 1.54665 1.06694 2.49769 + vertex 1.54794 1.06589 2.49555 + endloop + endfacet + facet normal -0.993395 -0.0992961 -0.0574996 + outer loop + vertex 1.54697 1.06359 2.49788 + vertex 1.54676 1.06396 2.50086 + vertex 1.54665 1.06694 2.49769 + endloop + endfacet + facet normal -0.992585 -0.104376 -0.0623002 + outer loop + vertex 1.54665 1.06694 2.49769 + vertex 1.54676 1.06396 2.50086 + vertex 1.54629 1.06824 2.50119 + endloop + endfacet + facet normal -0.976599 -0.121141 0.177704 + outer loop + vertex 1.54676 1.06396 2.50086 + vertex 1.54733 1.06504 2.50474 + vertex 1.54629 1.06824 2.50119 + endloop + endfacet + facet normal -0.976617 -0.163563 0.139525 + outer loop + vertex 1.54629 1.06824 2.50119 + vertex 1.54733 1.06504 2.50474 + vertex 1.54663 1.07011 2.50577 + endloop + endfacet + facet normal -0.857912 -0.213744 0.467226 + outer loop + vertex 1.54733 1.06504 2.50474 + vertex 1.54909 1.06659 2.50868 + vertex 1.54663 1.07011 2.50577 + endloop + endfacet + facet normal -0.835396 -0.269473 0.47906 + outer loop + vertex 1.54961 1.06209 2.50705 + vertex 1.54909 1.06659 2.50868 + vertex 1.54733 1.06504 2.50474 + endloop + endfacet + facet normal -0.855499 0.112072 -0.50553 + outer loop + vertex 1.54775 1.07022 2.49525 + vertex 1.54655 1.07147 2.49756 + vertex 1.54828 1.07511 2.49544 + endloop + endfacet + facet normal -0.893873 -0.0322689 -0.447157 + outer loop + vertex 1.54665 1.06694 2.49769 + vertex 1.54655 1.07147 2.49756 + vertex 1.54775 1.07022 2.49525 + endloop + endfacet + facet normal -0.995438 -0.0246541 -0.0921715 + outer loop + vertex 1.54665 1.06694 2.49769 + vertex 1.54629 1.06824 2.50119 + vertex 1.54655 1.07147 2.49756 + endloop + endfacet + facet normal -0.987852 -0.0747614 -0.136233 + outer loop + vertex 1.54655 1.07147 2.49756 + vertex 1.54629 1.06824 2.50119 + vertex 1.54594 1.07298 2.50114 + endloop + endfacet + facet normal -0.991927 -0.0728899 0.103769 + outer loop + vertex 1.54629 1.06824 2.50119 + vertex 1.54663 1.07011 2.50577 + vertex 1.54594 1.07298 2.50114 + endloop + endfacet + facet normal -0.979452 -0.200391 0.022757 + outer loop + vertex 1.54594 1.07298 2.50114 + vertex 1.54663 1.07011 2.50577 + vertex 1.54569 1.07461 2.50468 + endloop + endfacet + facet normal -0.87778 -0.316862 0.359306 + outer loop + vertex 1.54812 1.0704 2.50966 + vertex 1.54663 1.07011 2.50577 + vertex 1.54909 1.06659 2.50868 + endloop + endfacet + facet normal -0.904294 -0.225335 0.362596 + outer loop + vertex 1.54812 1.0704 2.50966 + vertex 1.54683 1.07483 2.5092 + vertex 1.54663 1.07011 2.50577 + endloop + endfacet + facet normal -0.95809 -0.140935 0.2494 + outer loop + vertex 1.54683 1.07483 2.5092 + vertex 1.54569 1.07461 2.50468 + vertex 1.54663 1.07011 2.50577 + endloop + endfacet + facet normal -0.655303 -0.112992 0.746867 + outer loop + vertex 1.54812 1.0704 2.50966 + vertex 1.55025 1.07335 2.51198 + vertex 1.54683 1.07483 2.5092 + endloop + endfacet + facet normal -0.55617 0.524243 -0.64486 + outer loop + vertex 1.54828 1.07511 2.49544 + vertex 1.54682 1.07641 2.49775 + vertex 1.55 1.08 2.49793 + endloop + endfacet + facet normal -0.827074 0.0679489 -0.55797 + outer loop + vertex 1.54655 1.07147 2.49756 + vertex 1.54682 1.07641 2.49775 + vertex 1.54828 1.07511 2.49544 + endloop + endfacet + facet normal -0.979318 0.0624194 -0.192458 + outer loop + vertex 1.54655 1.07147 2.49756 + vertex 1.54594 1.07298 2.50114 + vertex 1.54682 1.07641 2.49775 + endloop + endfacet + facet normal -0.955896 -0.0409444 -0.290839 + outer loop + vertex 1.54682 1.07641 2.49775 + vertex 1.54594 1.07298 2.50114 + vertex 1.54571 1.07766 2.50123 + endloop + endfacet + facet normal -0.997667 -0.047489 -0.0490423 + outer loop + vertex 1.54594 1.07298 2.50114 + vertex 1.54569 1.07461 2.50468 + vertex 1.54571 1.07766 2.50123 + endloop + endfacet + facet normal -0.995312 -0.0688327 -0.0679349 + outer loop + vertex 1.54571 1.07766 2.50123 + vertex 1.54569 1.07461 2.50468 + vertex 1.54533 1.07866 2.50583 + endloop + endfacet + facet normal -0.955817 -0.155374 0.249547 + outer loop + vertex 1.54569 1.07461 2.50468 + vertex 1.54683 1.07483 2.5092 + vertex 1.54533 1.07866 2.50583 + endloop + endfacet + facet normal -0.959229 -0.216433 0.181761 + outer loop + vertex 1.54533 1.07866 2.50583 + vertex 1.54683 1.07483 2.5092 + vertex 1.54587 1.08065 2.51107 + endloop + endfacet + facet normal -0.6683 -0.325073 0.669106 + outer loop + vertex 1.54683 1.07483 2.5092 + vertex 1.54907 1.07883 2.51338 + vertex 1.54587 1.08065 2.51107 + endloop + endfacet + facet normal -0.676822 -0.315909 0.664916 + outer loop + vertex 1.55025 1.07335 2.51198 + vertex 1.54907 1.07883 2.51338 + vertex 1.54683 1.07483 2.5092 + endloop + endfacet + facet normal -0.0926817 0.0139098 -0.995599 + outer loop + vertex 1.55 1.08 2.49793 + vertex 1.54708 1.08138 2.49822 + vertex 1.55 1.085 2.498 + endloop + endfacet + facet normal -0.053212 0.0968159 -0.993879 + outer loop + vertex 1.54682 1.07641 2.49775 + vertex 1.54708 1.08138 2.49822 + vertex 1.55 1.08 2.49793 + endloop + endfacet + facet normal -0.940709 0.0803286 -0.329566 + outer loop + vertex 1.54682 1.07641 2.49775 + vertex 1.54571 1.07766 2.50123 + vertex 1.54708 1.08138 2.49822 + endloop + endfacet + facet normal -0.910505 0.0012989 -0.413496 + outer loop + vertex 1.54708 1.08138 2.49822 + vertex 1.54571 1.07766 2.50123 + vertex 1.54548 1.08249 2.50176 + endloop + endfacet + facet normal -0.996445 -0.0394723 -0.0744198 + outer loop + vertex 1.54571 1.07766 2.50123 + vertex 1.54533 1.07866 2.50583 + vertex 1.54548 1.08249 2.50176 + endloop + endfacet + facet normal -0.981767 -0.118718 -0.148458 + outer loop + vertex 1.54548 1.08249 2.50176 + vertex 1.54533 1.07866 2.50583 + vertex 1.54463 1.08355 2.50654 + endloop + endfacet + facet normal -0.973118 -0.162859 0.162844 + outer loop + vertex 1.54533 1.07866 2.50583 + vertex 1.54587 1.08065 2.51107 + vertex 1.54463 1.08355 2.50654 + endloop + endfacet + facet normal -0.939212 -0.341077 0.0393308 + outer loop + vertex 1.54463 1.08355 2.50654 + vertex 1.54587 1.08065 2.51107 + vertex 1.54416 1.08539 2.51128 + endloop + endfacet + facet normal -0.674322 -0.524067 0.520233 + outer loop + vertex 1.54758 1.08186 2.5145 + vertex 1.54587 1.08065 2.51107 + vertex 1.54907 1.07883 2.51338 + endloop + endfacet + facet normal -0.784174 -0.349048 0.513066 + outer loop + vertex 1.54758 1.08186 2.5145 + vertex 1.54634 1.08461 2.51448 + vertex 1.54587 1.08065 2.51107 + endloop + endfacet + facet normal -0.817981 -0.31669 0.480224 + outer loop + vertex 1.54634 1.08461 2.51448 + vertex 1.54416 1.08539 2.51128 + vertex 1.54587 1.08065 2.51107 + endloop + endfacet + facet normal -0.456885 -0.199125 0.866952 + outer loop + vertex 1.54758 1.08186 2.5145 + vertex 1.54909 1.08497 2.51602 + vertex 1.54634 1.08461 2.51448 + endloop + endfacet + facet normal -0.259422 -0.0347462 -0.965139 + outer loop + vertex 1.55 1.085 2.498 + vertex 1.54708 1.08674 2.49872 + vertex 1.55 1.09 2.49782 + endloop + endfacet + facet normal -0.187307 0.0912894 -0.97805 + outer loop + vertex 1.54708 1.08138 2.49822 + vertex 1.54708 1.08674 2.49872 + vertex 1.55 1.085 2.498 + endloop + endfacet + facet normal -0.905183 0.0397171 -0.423162 + outer loop + vertex 1.54708 1.08138 2.49822 + vertex 1.54548 1.08249 2.50176 + vertex 1.54708 1.08674 2.49872 + endloop + endfacet + facet normal -0.902992 0.0352859 -0.428206 + outer loop + vertex 1.54708 1.08674 2.49872 + vertex 1.54548 1.08249 2.50176 + vertex 1.54536 1.08819 2.50248 + endloop + endfacet + facet normal -0.984482 0.00115803 -0.175484 + outer loop + vertex 1.54548 1.08249 2.50176 + vertex 1.54463 1.08355 2.50654 + vertex 1.54536 1.08819 2.50248 + endloop + endfacet + facet normal -0.931032 -0.146339 -0.334312 + outer loop + vertex 1.54536 1.08819 2.50248 + vertex 1.54463 1.08355 2.50654 + vertex 1.54375 1.08827 2.50692 + endloop + endfacet + facet normal -0.851328 -0.434483 -0.29405 + outer loop + vertex 1.54289 1.08767 2.5103 + vertex 1.54254 1.08952 2.50859 + vertex 1.54375 1.08827 2.50692 + endloop + endfacet + facet normal -0.774543 -0.558614 -0.296704 + outer loop + vertex 1.54289 1.08767 2.5103 + vertex 1.54375 1.08827 2.50692 + vertex 1.54416 1.08539 2.51128 + endloop + endfacet + facet normal -0.983126 -0.180916 -0.0270612 + outer loop + vertex 1.54416 1.08539 2.51128 + vertex 1.54375 1.08827 2.50692 + vertex 1.54463 1.08355 2.50654 + endloop + endfacet + facet normal -0.88958 -0.43157 0.149649 + outer loop + vertex 1.54313 1.088 2.51268 + vertex 1.54289 1.08767 2.5103 + vertex 1.54416 1.08539 2.51128 + endloop + endfacet + facet normal -0.561204 -0.551956 0.616762 + outer loop + vertex 1.54313 1.088 2.51268 + vertex 1.54416 1.08539 2.51128 + vertex 1.54498 1.08877 2.51505 + endloop + endfacet + facet normal -0.815328 -0.331265 0.474872 + outer loop + vertex 1.54498 1.08877 2.51505 + vertex 1.54416 1.08539 2.51128 + vertex 1.54634 1.08461 2.51448 + endloop + endfacet + facet normal -0.372445 -0.244035 0.895395 + outer loop + vertex 1.54634 1.08461 2.51448 + vertex 1.54865 1.08878 2.51658 + vertex 1.54498 1.08877 2.51505 + endloop + endfacet + facet normal -0.460202 -0.182279 0.868901 + outer loop + vertex 1.54909 1.08497 2.51602 + vertex 1.54865 1.08878 2.51658 + vertex 1.54634 1.08461 2.51448 + endloop + endfacet + facet normal -0.731252 -0.00679749 -0.682074 + outer loop + vertex 1.55 1.09 2.49782 + vertex 1.54792 1.095 2.5 + vertex 1.55 1.095 2.49777 + endloop + endfacet + facet normal -0.46965 0.181361 -0.864024 + outer loop + vertex 1.54708 1.08674 2.49872 + vertex 1.54792 1.095 2.5 + vertex 1.55 1.09 2.49782 + endloop + endfacet + facet normal -0.87237 0.159838 -0.461977 + outer loop + vertex 1.54708 1.08674 2.49872 + vertex 1.54536 1.08819 2.50248 + vertex 1.54792 1.095 2.5 + endloop + endfacet + facet normal -0.922004 0.234689 -0.307943 + outer loop + vertex 1.54792 1.095 2.5 + vertex 1.54536 1.08819 2.50248 + vertex 1.54625 1.095 2.505 + endloop + endfacet + facet normal -0.0880443 -0.28252 -0.955212 + outer loop + vertex 1.54309 1.09168 2.50627 + vertex 1.54299 1.09536 2.50519 + vertex 1.54625 1.095 2.505 + endloop + endfacet + facet normal -0.161993 -0.215145 -0.963053 + outer loop + vertex 1.54309 1.09168 2.50627 + vertex 1.54625 1.095 2.505 + vertex 1.54375 1.08827 2.50692 + endloop + endfacet + facet normal -0.910612 0.242935 -0.334318 + outer loop + vertex 1.54375 1.08827 2.50692 + vertex 1.54625 1.095 2.505 + vertex 1.54536 1.08819 2.50248 + endloop + endfacet + facet normal -0.862352 -0.249704 -0.440451 + outer loop + vertex 1.54375 1.08827 2.50692 + vertex 1.54254 1.08952 2.50859 + vertex 1.54309 1.09168 2.50627 + endloop + endfacet + facet normal -0.693225 -0.320391 0.645592 + outer loop + vertex 1.5429 1.09104 2.51394 + vertex 1.54313 1.088 2.51268 + vertex 1.54498 1.08877 2.51505 + endloop + endfacet + facet normal -0.683548 -0.302337 0.664345 + outer loop + vertex 1.54433 1.0928 2.51621 + vertex 1.5429 1.09104 2.51394 + vertex 1.54498 1.08877 2.51505 + endloop + endfacet + facet normal -0.273648 -0.306916 0.911548 + outer loop + vertex 1.54498 1.08877 2.51505 + vertex 1.5478 1.09381 2.5176 + vertex 1.54433 1.0928 2.51621 + endloop + endfacet + facet normal -0.372474 -0.243744 0.895462 + outer loop + vertex 1.54865 1.08878 2.51658 + vertex 1.5478 1.09381 2.5176 + vertex 1.54498 1.08877 2.51505 + endloop + endfacet + facet normal -0.0605174 -0.0117405 -0.998098 + outer loop + vertex 1.54528 1.1 2.505 + vertex 1.54625 1.095 2.505 + vertex 1.54299 1.09536 2.50519 + endloop + endfacet + facet normal 0.335836 -0.204449 -0.919464 + outer loop + vertex 1.54279 1.09847 2.50443 + vertex 1.54528 1.1 2.505 + vertex 1.54299 1.09536 2.50519 + endloop + endfacet + facet normal -0.75378 -0.197353 0.626791 + outer loop + vertex 1.5429 1.09104 2.51394 + vertex 1.54433 1.0928 2.51621 + vertex 1.54286 1.09473 2.51505 + endloop + endfacet + facet normal -0.709409 -0.122683 0.694038 + outer loop + vertex 1.54433 1.0928 2.51621 + vertex 1.54489 1.09741 2.5176 + vertex 1.54286 1.09473 2.51505 + endloop + endfacet + facet normal -0.297416 -0.241686 0.923651 + outer loop + vertex 1.54433 1.0928 2.51621 + vertex 1.5478 1.09381 2.5176 + vertex 1.54489 1.09741 2.5176 + endloop + endfacet + facet normal -0.278321 -0.226279 0.933454 + outer loop + vertex 1.5478 1.09381 2.5176 + vertex 1.54869 1.09882 2.51908 + vertex 1.54489 1.09741 2.5176 + endloop + endfacet + facet normal 0.174371 0.0813822 -0.981311 + outer loop + vertex 1.54528 1.1 2.505 + vertex 1.54279 1.09847 2.50443 + vertex 1.545 1.1006 2.505 + endloop + endfacet + facet normal -0.231474 -0.332698 0.914184 + outer loop + vertex 1.54869 1.09882 2.51908 + vertex 1.54731 1.10198 2.51988 + vertex 1.54489 1.09741 2.5176 + endloop + endfacet + facet normal -0.396425 -0.232381 0.88817 + outer loop + vertex 1.54489 1.09741 2.5176 + vertex 1.54731 1.10198 2.51988 + vertex 1.54377 1.10226 2.51837 + endloop + endfacet + facet normal -0.386844 -0.388077 0.83651 + outer loop + vertex 1.54377 1.10226 2.51837 + vertex 1.54731 1.10198 2.51988 + vertex 1.54598 1.10538 2.52084 + endloop + endfacet + facet normal -0.441952 -0.34298 0.82888 + outer loop + vertex 1.54313 1.10592 2.51954 + vertex 1.54377 1.10226 2.51837 + vertex 1.54598 1.10538 2.52084 + endloop + endfacet + facet normal -0.441549 -0.301447 0.845083 + outer loop + vertex 1.54598 1.10538 2.52084 + vertex 1.54489 1.10902 2.52157 + vertex 1.54313 1.10592 2.51954 + endloop + endfacet + facet normal -0.113077 -0.226668 0.967386 + outer loop + vertex 1.54887 1.10922 2.52208 + vertex 1.54489 1.10902 2.52157 + vertex 1.54598 1.10538 2.52084 + endloop + endfacet + facet normal -0.111867 -0.241943 0.96382 + outer loop + vertex 1.54887 1.10922 2.52208 + vertex 1.54809 1.11316 2.52298 + vertex 1.54489 1.10902 2.52157 + endloop + endfacet + facet normal -0.163575 -0.202495 0.965525 + outer loop + vertex 1.54489 1.10902 2.52157 + vertex 1.54809 1.11316 2.52298 + vertex 1.54406 1.1135 2.52237 + endloop + endfacet + facet normal -0.695028 0.451961 -0.559167 + outer loop + vertex 1.54751 1.12 2.505 + vertex 1.545 1.11614 2.505 + vertex 1.545 1.12 2.50812 + endloop + endfacet + facet normal 0.189419 -0.156381 0.969363 + outer loop + vertex 1.54792 1.23868 2.54503 + vertex 1.54956 1.24381 2.54554 + vertex 1.54554 1.24102 2.54587 + endloop + endfacet + facet normal 0.19017 -0.157502 0.969035 + outer loop + vertex 1.54956 1.24381 2.54554 + vertex 1.54719 1.24464 2.54614 + vertex 1.54554 1.24102 2.54587 + endloop + endfacet + facet normal -0.811316 -0.216523 -0.543032 + outer loop + vertex 1.54504 1.915 2.505 + vertex 1.545 1.915 2.50506 + vertex 1.545 1.91515 2.505 + endloop + endfacet + facet normal 0.0547746 -0.0197917 -0.998303 + outer loop + vertex 1.54556 1.93 2.505 + vertex 1.545 1.92845 2.505 + vertex 1.5432 1.92962 2.50488 + endloop + endfacet + facet normal -0.0404878 0.424879 0.904344 + outer loop + vertex 1.5448 1.92248 2.52029 + vertex 1.54867 1.9234 2.52004 + vertex 1.54509 1.92659 2.51838 + endloop + endfacet + facet normal -0.200607 0.264988 0.943153 + outer loop + vertex 1.54509 1.92659 2.51838 + vertex 1.54867 1.9234 2.52004 + vertex 1.54847 1.92791 2.51872 + endloop + endfacet + facet normal 0.0515691 0.000103278 -0.998669 + outer loop + vertex 1.54555 1.935 2.505 + vertex 1.54556 1.93 2.505 + vertex 1.5432 1.92962 2.50488 + endloop + endfacet + facet normal -0.346886 0.172548 -0.921899 + outer loop + vertex 1.54301 1.93263 2.50551 + vertex 1.54555 1.935 2.505 + vertex 1.5432 1.92962 2.50488 + endloop + endfacet + facet normal -0.767984 0.319211 0.555252 + outer loop + vertex 1.54449 1.93398 2.51453 + vertex 1.54293 1.9311 2.51403 + vertex 1.54407 1.93014 2.51616 + endloop + endfacet + facet normal -0.486172 0.385692 0.784142 + outer loop + vertex 1.54407 1.93014 2.51616 + vertex 1.54697 1.93151 2.51728 + vertex 1.54449 1.93398 2.51453 + endloop + endfacet + facet normal -0.480405 0.360838 0.799379 + outer loop + vertex 1.54407 1.93014 2.51616 + vertex 1.54509 1.92659 2.51838 + vertex 1.54697 1.93151 2.51728 + endloop + endfacet + facet normal -0.20848 0.287182 0.934913 + outer loop + vertex 1.54509 1.92659 2.51838 + vertex 1.54847 1.92791 2.51872 + vertex 1.54697 1.93151 2.51728 + endloop + endfacet + facet normal -0.935364 -0.0729666 -0.346078 + outer loop + vertex 1.5474 1.935 2.5 + vertex 1.54555 1.935 2.505 + vertex 1.54701 1.94 2.5 + endloop + endfacet + facet normal 0.439923 -0.695976 -0.567525 + outer loop + vertex 1.54701 1.94 2.5 + vertex 1.54555 1.935 2.505 + vertex 1.5451 1.9381 2.50085 + endloop + endfacet + facet normal -0.974764 0.164994 -0.150374 + outer loop + vertex 1.54301 1.93263 2.50551 + vertex 1.54268 1.93343 2.50849 + vertex 1.54383 1.93687 2.5048 + endloop + endfacet + facet normal -0.0551704 -0.15458 -0.986439 + outer loop + vertex 1.54301 1.93263 2.50551 + vertex 1.54383 1.93687 2.5048 + vertex 1.54555 1.935 2.505 + endloop + endfacet + facet normal -0.651501 -0.640327 -0.406851 + outer loop + vertex 1.54555 1.935 2.505 + vertex 1.54383 1.93687 2.5048 + vertex 1.5451 1.9381 2.50085 + endloop + endfacet + facet normal -0.954203 0.298543 -0.0191959 + outer loop + vertex 1.54387 1.93731 2.51014 + vertex 1.54383 1.93687 2.5048 + vertex 1.54268 1.93343 2.50849 + endloop + endfacet + facet normal -0.962734 0.256048 0.0870731 + outer loop + vertex 1.54296 1.93332 2.51188 + vertex 1.54387 1.93731 2.51014 + vertex 1.54268 1.93343 2.50849 + endloop + endfacet + facet normal -0.837767 0.385828 0.386371 + outer loop + vertex 1.54296 1.93332 2.51188 + vertex 1.54293 1.9311 2.51403 + vertex 1.54449 1.93398 2.51453 + endloop + endfacet + facet normal -0.843553 0.363619 0.395221 + outer loop + vertex 1.54296 1.93332 2.51188 + vertex 1.54449 1.93398 2.51453 + vertex 1.54387 1.93731 2.51014 + endloop + endfacet + facet normal -0.907273 0.26311 0.328068 + outer loop + vertex 1.54387 1.93731 2.51014 + vertex 1.54449 1.93398 2.51453 + vertex 1.54561 1.93863 2.5139 + endloop + endfacet + facet normal -0.64326 0.253254 0.72255 + outer loop + vertex 1.54449 1.93398 2.51453 + vertex 1.54693 1.93571 2.5161 + vertex 1.54561 1.93863 2.5139 + endloop + endfacet + facet normal -0.627992 0.206353 0.750363 + outer loop + vertex 1.54697 1.93151 2.51728 + vertex 1.54693 1.93571 2.5161 + vertex 1.54449 1.93398 2.51453 + endloop + endfacet + facet normal -0.226411 0.0389366 -0.973253 + outer loop + vertex 1.55 1.94 2.49739 + vertex 1.54668 1.94098 2.4982 + vertex 1.55 1.945 2.49759 + endloop + endfacet + facet normal -0.348283 -0.848234 -0.398996 + outer loop + vertex 1.54701 1.94 2.5 + vertex 1.54668 1.94098 2.4982 + vertex 1.55 1.94 2.49739 + endloop + endfacet + facet normal 0.499738 -0.718724 -0.483422 + outer loop + vertex 1.54701 1.94 2.5 + vertex 1.5451 1.9381 2.50085 + vertex 1.54668 1.94098 2.4982 + endloop + endfacet + facet normal -0.856754 -0.00238793 -0.515719 + outer loop + vertex 1.54668 1.94098 2.4982 + vertex 1.5451 1.9381 2.50085 + vertex 1.54496 1.94143 2.50107 + endloop + endfacet + facet normal -0.950712 -0.0199316 -0.309435 + outer loop + vertex 1.5451 1.9381 2.50085 + vertex 1.54383 1.93687 2.5048 + vertex 1.54496 1.94143 2.50107 + endloop + endfacet + facet normal -0.981899 0.124148 -0.143043 + outer loop + vertex 1.54496 1.94143 2.50107 + vertex 1.54383 1.93687 2.5048 + vertex 1.54436 1.94209 2.5057 + endloop + endfacet + facet normal -0.994861 0.101221 -0.00254627 + outer loop + vertex 1.54383 1.93687 2.5048 + vertex 1.54387 1.93731 2.51014 + vertex 1.54436 1.94209 2.5057 + endloop + endfacet + facet normal -0.97433 0.19907 0.105126 + outer loop + vertex 1.54436 1.94209 2.5057 + vertex 1.54387 1.93731 2.51014 + vertex 1.54502 1.9428 2.51042 + endloop + endfacet + facet normal -0.915436 0.17335 0.363218 + outer loop + vertex 1.54387 1.93731 2.51014 + vertex 1.54561 1.93863 2.5139 + vertex 1.54502 1.9428 2.51042 + endloop + endfacet + facet normal -0.840588 0.271854 0.468516 + outer loop + vertex 1.54502 1.9428 2.51042 + vertex 1.54561 1.93863 2.5139 + vertex 1.54696 1.94297 2.51381 + endloop + endfacet + facet normal -0.618741 0.20818 0.757509 + outer loop + vertex 1.54561 1.93863 2.5139 + vertex 1.54813 1.93911 2.51582 + vertex 1.54696 1.94297 2.51381 + endloop + endfacet + facet normal -0.616388 0.27656 0.737279 + outer loop + vertex 1.54693 1.93571 2.5161 + vertex 1.54813 1.93911 2.51582 + vertex 1.54561 1.93863 2.5139 + endloop + endfacet + facet normal -0.167259 0.0824979 -0.982455 + outer loop + vertex 1.55 1.945 2.49759 + vertex 1.54683 1.94537 2.49816 + vertex 1.55 1.95 2.49801 + endloop + endfacet + facet normal -0.177525 -0.00308657 -0.984111 + outer loop + vertex 1.54668 1.94098 2.4982 + vertex 1.54683 1.94537 2.49816 + vertex 1.55 1.945 2.49759 + endloop + endfacet + facet normal -0.854631 0.0245708 -0.518654 + outer loop + vertex 1.54668 1.94098 2.4982 + vertex 1.54496 1.94143 2.50107 + vertex 1.54683 1.94537 2.49816 + endloop + endfacet + facet normal -0.891407 0.0983041 -0.442413 + outer loop + vertex 1.54683 1.94537 2.49816 + vertex 1.54496 1.94143 2.50107 + vertex 1.54531 1.94652 2.50149 + endloop + endfacet + facet normal -0.987331 0.0793951 -0.137386 + outer loop + vertex 1.54496 1.94143 2.50107 + vertex 1.54436 1.94209 2.5057 + vertex 1.54531 1.94652 2.50149 + endloop + endfacet + facet normal -0.987885 0.131039 -0.0831334 + outer loop + vertex 1.54531 1.94652 2.50149 + vertex 1.54436 1.94209 2.5057 + vertex 1.54503 1.94744 2.50617 + endloop + endfacet + facet normal -0.986341 0.113154 0.119699 + outer loop + vertex 1.54436 1.94209 2.5057 + vertex 1.54502 1.9428 2.51042 + vertex 1.54503 1.94744 2.50617 + endloop + endfacet + facet normal -0.94807 0.216646 0.232868 + outer loop + vertex 1.54503 1.94744 2.50617 + vertex 1.54502 1.9428 2.51042 + vertex 1.54633 1.94828 2.51065 + endloop + endfacet + facet normal -0.443565 0.299412 0.84475 + outer loop + vertex 1.54946 1.94675 2.51379 + vertex 1.54696 1.94297 2.51381 + vertex 1.54945 1.94235 2.51534 + endloop + endfacet + facet normal -0.557882 0.374285 0.740728 + outer loop + vertex 1.54946 1.94675 2.51379 + vertex 1.54633 1.94828 2.51065 + vertex 1.54696 1.94297 2.51381 + endloop + endfacet + facet normal -0.856497 0.184511 0.482046 + outer loop + vertex 1.54633 1.94828 2.51065 + vertex 1.54502 1.9428 2.51042 + vertex 1.54696 1.94297 2.51381 + endloop + endfacet + facet normal -0.441016 0.306607 0.843503 + outer loop + vertex 1.54945 1.94235 2.51534 + vertex 1.54696 1.94297 2.51381 + vertex 1.54813 1.93911 2.51582 + endloop + endfacet + facet normal 0.0895244 0.126484 -0.987921 + outer loop + vertex 1.55 1.95 2.49801 + vertex 1.54705 1.95108 2.49788 + vertex 1.55 1.955 2.49865 + endloop + endfacet + facet normal 0.0253566 -0.04978 -0.998438 + outer loop + vertex 1.54683 1.94537 2.49816 + vertex 1.54705 1.95108 2.49788 + vertex 1.55 1.95 2.49801 + endloop + endfacet + facet normal -0.907258 0.0135332 -0.420356 + outer loop + vertex 1.54683 1.94537 2.49816 + vertex 1.54531 1.94652 2.50149 + vertex 1.54705 1.95108 2.49788 + endloop + endfacet + facet normal -0.933188 0.0785661 -0.350696 + outer loop + vertex 1.54705 1.95108 2.49788 + vertex 1.54531 1.94652 2.50149 + vertex 1.54563 1.95179 2.5018 + endloop + endfacet + facet normal -0.995289 0.0661604 -0.0708719 + outer loop + vertex 1.54531 1.94652 2.50149 + vertex 1.54503 1.94744 2.50617 + vertex 1.54563 1.95179 2.5018 + endloop + endfacet + facet normal -0.99323 0.113835 -0.0231299 + outer loop + vertex 1.54563 1.95179 2.5018 + vertex 1.54503 1.94744 2.50617 + vertex 1.54562 1.95257 2.50626 + endloop + endfacet + facet normal -0.960518 0.105079 0.257612 + outer loop + vertex 1.54503 1.94744 2.50617 + vertex 1.54633 1.94828 2.51065 + vertex 1.54562 1.95257 2.50626 + endloop + endfacet + facet normal -0.96025 0.105831 0.258303 + outer loop + vertex 1.54562 1.95257 2.50626 + vertex 1.54633 1.94828 2.51065 + vertex 1.54662 1.95366 2.50953 + endloop + endfacet + facet normal -0.723222 0.177807 0.667334 + outer loop + vertex 1.54633 1.94828 2.51065 + vertex 1.54843 1.95162 2.51204 + vertex 1.54662 1.95366 2.50953 + endloop + endfacet + facet normal -0.672457 0.119362 0.730448 + outer loop + vertex 1.54946 1.94675 2.51379 + vertex 1.54843 1.95162 2.51204 + vertex 1.54633 1.94828 2.51065 + endloop + endfacet + facet normal 0.529397 -0.573183 -0.62546 + outer loop + vertex 1.55 1.95916 2.495 + vertex 1.54813 1.95691 2.49548 + vertex 1.55 1.96 2.49423 + endloop + endfacet + facet normal 0.515168 -0.565296 -0.644238 + outer loop + vertex 1.55 1.955 2.49865 + vertex 1.54813 1.95691 2.49548 + vertex 1.55 1.95916 2.495 + endloop + endfacet + facet normal 0.674654 -0.384958 -0.629801 + outer loop + vertex 1.55 1.955 2.49865 + vertex 1.54705 1.95108 2.49788 + vertex 1.54813 1.95691 2.49548 + endloop + endfacet + facet normal -0.84342 -0.0639566 -0.533434 + outer loop + vertex 1.54705 1.95108 2.49788 + vertex 1.54649 1.95524 2.49826 + vertex 1.54813 1.95691 2.49548 + endloop + endfacet + facet normal -0.941731 -0.0963142 -0.322284 + outer loop + vertex 1.54705 1.95108 2.49788 + vertex 1.54563 1.95179 2.5018 + vertex 1.54649 1.95524 2.49826 + endloop + endfacet + facet normal -0.985277 0.117395 -0.124287 + outer loop + vertex 1.54649 1.95524 2.49826 + vertex 1.54563 1.95179 2.5018 + vertex 1.54625 1.95733 2.50212 + endloop + endfacet + facet normal -0.9934 0.1124 -0.0228793 + outer loop + vertex 1.54563 1.95179 2.5018 + vertex 1.54562 1.95257 2.50626 + vertex 1.54625 1.95733 2.50212 + endloop + endfacet + facet normal -0.986202 0.161799 0.0350202 + outer loop + vertex 1.54625 1.95733 2.50212 + vertex 1.54562 1.95257 2.50626 + vertex 1.54625 1.95633 2.50665 + endloop + endfacet + facet normal -0.959233 0.135345 0.2481 + outer loop + vertex 1.54562 1.95257 2.50626 + vertex 1.54662 1.95366 2.50953 + vertex 1.54625 1.95633 2.50665 + endloop + endfacet + facet normal -0.879836 0.287229 0.378665 + outer loop + vertex 1.54625 1.95633 2.50665 + vertex 1.54662 1.95366 2.50953 + vertex 1.54762 1.9576 2.50886 + endloop + endfacet + facet normal -0.735342 0.290169 0.612433 + outer loop + vertex 1.54662 1.95366 2.50953 + vertex 1.54838 1.95527 2.51089 + vertex 1.54762 1.9576 2.50886 + endloop + endfacet + facet normal -0.70705 0.204092 0.677073 + outer loop + vertex 1.54843 1.95162 2.51204 + vertex 1.54838 1.95527 2.51089 + vertex 1.54662 1.95366 2.50953 + endloop + endfacet + facet normal -0.714008 0.158155 -0.682041 + outer loop + vertex 1.55 1.96 2.49423 + vertex 1.54813 1.95691 2.49548 + vertex 1.55 1.96332 2.495 + endloop + endfacet + facet normal -0.0565029 -0.44928 -0.891603 + outer loop + vertex 1.55 1.96332 2.495 + vertex 1.54728 1.95965 2.49702 + vertex 1.5483 1.96295 2.4953 + endloop + endfacet + facet normal -0.717878 0.159614 -0.677624 + outer loop + vertex 1.55 1.96332 2.495 + vertex 1.54813 1.95691 2.49548 + vertex 1.54728 1.95965 2.49702 + endloop + endfacet + facet normal -0.86585 0.0135434 -0.50012 + outer loop + vertex 1.54813 1.95691 2.49548 + vertex 1.54649 1.95524 2.49826 + vertex 1.54728 1.95965 2.49702 + endloop + endfacet + facet normal -0.981397 0.191964 -0.00303558 + outer loop + vertex 1.54699 1.96104 2.49977 + vertex 1.54625 1.95733 2.50212 + vertex 1.54702 1.96127 2.50248 + endloop + endfacet + facet normal -0.983439 0.0972974 -0.152905 + outer loop + vertex 1.54699 1.96104 2.49977 + vertex 1.54728 1.95965 2.49702 + vertex 1.54625 1.95733 2.50212 + endloop + endfacet + facet normal -0.981425 0.13677 -0.134536 + outer loop + vertex 1.54728 1.95965 2.49702 + vertex 1.54649 1.95524 2.49826 + vertex 1.54625 1.95733 2.50212 + endloop + endfacet + facet normal -0.946107 0.271205 0.177 + outer loop + vertex 1.54702 1.96127 2.50248 + vertex 1.54732 1.96019 2.50572 + vertex 1.54793 1.96342 2.50404 + endloop + endfacet + facet normal -0.973139 0.176482 0.147836 + outer loop + vertex 1.54702 1.96127 2.50248 + vertex 1.54625 1.95733 2.50212 + vertex 1.54732 1.96019 2.50572 + endloop + endfacet + facet normal -0.958068 0.279961 0.0610487 + outer loop + vertex 1.54625 1.95733 2.50212 + vertex 1.54625 1.95633 2.50665 + vertex 1.54732 1.96019 2.50572 + endloop + endfacet + facet normal -0.533902 0.392434 0.748962 + outer loop + vertex 1.54967 1.96144 2.50832 + vertex 1.54762 1.9576 2.50886 + vertex 1.55027 1.95834 2.51037 + endloop + endfacet + facet normal -0.754872 0.469074 0.458408 + outer loop + vertex 1.54967 1.96144 2.50832 + vertex 1.54732 1.96019 2.50572 + vertex 1.54762 1.9576 2.50886 + endloop + endfacet + facet normal -0.8762 0.327809 0.353292 + outer loop + vertex 1.54732 1.96019 2.50572 + vertex 1.54625 1.95633 2.50665 + vertex 1.54762 1.9576 2.50886 + endloop + endfacet + facet normal -0.532161 0.448819 0.71789 + outer loop + vertex 1.55027 1.95834 2.51037 + vertex 1.54762 1.9576 2.50886 + vertex 1.54838 1.95527 2.51089 + endloop + endfacet + facet normal -0.942537 0.130469 -0.307575 + outer loop + vertex 1.5483 1.96295 2.4953 + vertex 1.54728 1.95965 2.49702 + vertex 1.54758 1.96272 2.49739 + endloop + endfacet + facet normal -0.97981 0.116688 -0.162346 + outer loop + vertex 1.54758 1.96272 2.49739 + vertex 1.54728 1.95965 2.49702 + vertex 1.54699 1.96104 2.49977 + endloop + endfacet + facet normal -0.859508 0.35418 0.368514 + outer loop + vertex 1.54793 1.96342 2.50404 + vertex 1.54732 1.96019 2.50572 + vertex 1.54904 1.9638 2.50625 + endloop + endfacet + facet normal -0.774719 0.284846 0.564511 + outer loop + vertex 1.54904 1.9638 2.50625 + vertex 1.54732 1.96019 2.50572 + vertex 1.54967 1.96144 2.50832 + endloop + endfacet + facet normal -0.89827 -0.387293 0.207643 + outer loop + vertex 1.54865 1.9863 2.50031 + vertex 1.54721 1.98969 2.50038 + vertex 1.54736 1.98818 2.49821 + endloop + endfacet + facet normal -0.694672 -0.309474 0.649351 + outer loop + vertex 1.54865 1.9863 2.50031 + vertex 1.55019 1.98715 2.50236 + vertex 1.54721 1.98969 2.50038 + endloop + endfacet + facet normal -0.171446 -0.139167 -0.975315 + outer loop + vertex 1.54831 1.99029 2.49073 + vertex 1.54862 1.995 2.49 + vertex 1.55 1.9933 2.49 + endloop + endfacet + facet normal -0.563794 -0.0891619 -0.821088 + outer loop + vertex 1.54608 1.99307 2.49195 + vertex 1.54862 1.995 2.49 + vertex 1.54831 1.99029 2.49073 + endloop + endfacet + facet normal -0.795985 -0.469866 -0.38162 + outer loop + vertex 1.54732 1.9888 2.49462 + vertex 1.54608 1.99307 2.49195 + vertex 1.54831 1.99029 2.49073 + endloop + endfacet + facet normal -0.878729 -0.409125 -0.245871 + outer loop + vertex 1.54513 1.99214 2.49689 + vertex 1.54608 1.99307 2.49195 + vertex 1.54732 1.9888 2.49462 + endloop + endfacet + facet normal -0.857402 -0.508553 -0.0789665 + outer loop + vertex 1.54736 1.98818 2.49821 + vertex 1.54513 1.99214 2.49689 + vertex 1.54732 1.9888 2.49462 + endloop + endfacet + facet normal -0.879021 -0.417607 0.230059 + outer loop + vertex 1.54736 1.98818 2.49821 + vertex 1.54721 1.98969 2.50038 + vertex 1.54513 1.99214 2.49689 + endloop + endfacet + facet normal -0.837878 -0.531068 0.126201 + outer loop + vertex 1.54721 1.98969 2.50038 + vertex 1.54501 1.99315 2.50031 + vertex 1.54513 1.99214 2.49689 + endloop + endfacet + facet normal -0.553382 -0.336269 0.762031 + outer loop + vertex 1.54721 1.98969 2.50038 + vertex 1.54756 1.99267 2.50195 + vertex 1.54501 1.99315 2.50031 + endloop + endfacet + facet normal -0.683453 -0.27563 0.675958 + outer loop + vertex 1.55019 1.98715 2.50236 + vertex 1.54756 1.99267 2.50195 + vertex 1.54721 1.98969 2.50038 + endloop + endfacet + facet normal -0.438245 -0.285737 -0.85223 + outer loop + vertex 1.54862 1.995 2.49 + vertex 1.54608 1.99307 2.49195 + vertex 1.54536 2 2.49 + endloop + endfacet + facet normal -0.603858 -0.273734 -0.748616 + outer loop + vertex 1.54536 2 2.49 + vertex 1.54608 1.99307 2.49195 + vertex 1.54342 1.99563 2.49316 + endloop + endfacet + facet normal -0.641127 -0.725521 -0.250153 + outer loop + vertex 1.5425 1.99534 2.49638 + vertex 1.54113 1.99719 2.49453 + vertex 1.54342 1.99563 2.49316 + endloop + endfacet + facet normal -0.72344 -0.637307 -0.265469 + outer loop + vertex 1.5425 1.99534 2.49638 + vertex 1.54342 1.99563 2.49316 + vertex 1.54513 1.99214 2.49689 + endloop + endfacet + facet normal -0.728843 -0.633597 -0.259505 + outer loop + vertex 1.54513 1.99214 2.49689 + vertex 1.54342 1.99563 2.49316 + vertex 1.54608 1.99307 2.49195 + endloop + endfacet + facet normal -0.722905 -0.669386 0.17126 + outer loop + vertex 1.54513 1.99214 2.49689 + vertex 1.54501 1.99315 2.50031 + vertex 1.54269 1.99534 2.4991 + endloop + endfacet + facet normal -0.775464 -0.629023 0.0546425 + outer loop + vertex 1.5425 1.99534 2.49638 + vertex 1.54513 1.99214 2.49689 + vertex 1.54269 1.99534 2.4991 + endloop + endfacet + facet normal -0.717435 -0.479502 0.505336 + outer loop + vertex 1.54501 1.99315 2.50031 + vertex 1.54328 1.99675 2.50128 + vertex 1.54269 1.99534 2.4991 + endloop + endfacet + facet normal -0.541404 -0.450137 0.710112 + outer loop + vertex 1.54501 1.99315 2.50031 + vertex 1.54756 1.99267 2.50195 + vertex 1.54328 1.99675 2.50128 + endloop + endfacet + facet normal -0.139847 -0.539221 -0.830472 + outer loop + vertex 1.54536 2 2.49 + vertex 1.54342 1.99563 2.49316 + vertex 1.54132 1.99914 2.49124 + endloop + endfacet + facet normal -0.238197 -0.238197 -0.941554 + outer loop + vertex 1.545 2.00036 2.49 + vertex 1.54536 2 2.49 + vertex 1.54132 1.99914 2.49124 + endloop + endfacet + facet normal -0.666366 -0.623788 -0.408465 + outer loop + vertex 1.54342 1.99563 2.49316 + vertex 1.54113 1.99719 2.49453 + vertex 1.54132 1.99914 2.49124 + endloop + endfacet + facet normal 0.153413 0.462802 0.873086 + outer loop + vertex 1.54827 2.10195 2.46946 + vertex 1.54596 2.10604 2.4677 + vertex 1.54222 2.10372 2.46958 + endloop + endfacet + facet normal 0.144976 0.473087 0.869006 + outer loop + vertex 1.54222 2.10372 2.46958 + vertex 1.54596 2.10604 2.4677 + vertex 1.54164 2.10736 2.4677 + endloop + endfacet + facet normal 0.171911 0.667951 0.724078 + outer loop + vertex 1.54387 2.10932 2.46587 + vertex 1.5486 2.1084 2.4656 + vertex 1.54633 2.1113 2.46346 + endloop + endfacet + facet normal 0.177817 0.663668 0.726585 + outer loop + vertex 1.54167 2.11191 2.46404 + vertex 1.54387 2.10932 2.46587 + vertex 1.54633 2.1113 2.46346 + endloop + endfacet + facet normal 0.171641 0.5603 0.810311 + outer loop + vertex 1.54596 2.10604 2.4677 + vertex 1.54387 2.10932 2.46587 + vertex 1.54164 2.10736 2.4677 + endloop + endfacet + facet normal 0.154884 0.553944 0.81802 + outer loop + vertex 1.5486 2.1084 2.4656 + vertex 1.54387 2.10932 2.46587 + vertex 1.54596 2.10604 2.4677 + endloop + endfacet + facet normal 0.187849 0.892093 0.410953 + outer loop + vertex 1.54875 2.11472 2.45756 + vertex 1.54651 2.11649 2.45476 + vertex 1.5444 2.11578 2.45727 + endloop + endfacet + facet normal 0.181438 0.858733 0.479227 + outer loop + vertex 1.5444 2.11578 2.45727 + vertex 1.54035 2.11592 2.45854 + vertex 1.544 2.11393 2.46073 + endloop + endfacet + facet normal 0.175432 0.859996 0.479198 + outer loop + vertex 1.5444 2.11578 2.45727 + vertex 1.544 2.11393 2.46073 + vertex 1.54875 2.11472 2.45756 + endloop + endfacet + facet normal 0.18431 0.851759 0.490445 + outer loop + vertex 1.54875 2.11472 2.45756 + vertex 1.544 2.11393 2.46073 + vertex 1.54867 2.11277 2.46099 + endloop + endfacet + facet normal 0.177348 0.780117 0.599971 + outer loop + vertex 1.54633 2.1113 2.46346 + vertex 1.544 2.11393 2.46073 + vertex 1.54167 2.11191 2.46404 + endloop + endfacet + facet normal 0.158484 0.77527 0.611424 + outer loop + vertex 1.54867 2.11277 2.46099 + vertex 1.544 2.11393 2.46073 + vertex 1.54633 2.1113 2.46346 + endloop + endfacet + facet normal 0.0177077 0.340383 0.94012 + outer loop + vertex 1.55 2.12214 2.45 + vertex 1.545 2.1224 2.45 + vertex 1.54674 2.11846 2.45139 + endloop + endfacet + facet normal -0.0187821 0.325994 0.945185 + outer loop + vertex 1.54674 2.11846 2.45139 + vertex 1.545 2.1224 2.45 + vertex 1.54231 2.11961 2.45091 + endloop + endfacet + facet normal 0.164022 0.904179 0.394406 + outer loop + vertex 1.54651 2.11649 2.45476 + vertex 1.54226 2.11746 2.45429 + vertex 1.5444 2.11578 2.45727 + endloop + endfacet + facet normal 0.139028 0.849669 0.508659 + outer loop + vertex 1.54651 2.11649 2.45476 + vertex 1.54674 2.11846 2.45139 + vertex 1.54226 2.11746 2.45429 + endloop + endfacet + facet normal 0.157718 0.832209 0.531558 + outer loop + vertex 1.54674 2.11846 2.45139 + vertex 1.54231 2.11961 2.45091 + vertex 1.54226 2.11746 2.45429 + endloop + endfacet + facet normal 0.157756 0.903481 0.398541 + outer loop + vertex 1.5444 2.11578 2.45727 + vertex 1.54226 2.11746 2.45429 + vertex 1.54035 2.11592 2.45854 + endloop + endfacet + facet normal 0.188991 -0.677884 0.710462 + outer loop + vertex 1.555 0.912242 2.45 + vertex 1.55245 0.91233 2.45076 + vertex 1.55 0.910848 2.45 + endloop + endfacet + facet normal 0.249242 -0.735712 0.629767 + outer loop + vertex 1.55245 0.91233 2.45076 + vertex 1.5467 0.911746 2.45235 + vertex 1.55 0.910848 2.45 + endloop + endfacet + facet normal 0.210092 -0.874345 0.437473 + outer loop + vertex 1.55245 0.91233 2.45076 + vertex 1.54947 0.913317 2.45416 + vertex 1.5467 0.911746 2.45235 + endloop + endfacet + facet normal 0.205544 -0.877017 0.434272 + outer loop + vertex 1.55339 0.913606 2.45289 + vertex 1.54947 0.913317 2.45416 + vertex 1.55245 0.91233 2.45076 + endloop + endfacet + facet normal 0.210656 -0.866578 0.452402 + outer loop + vertex 1.54947 0.913317 2.45416 + vertex 1.55339 0.913606 2.45289 + vertex 1.55243 0.915033 2.45607 + endloop + endfacet + facet normal 0.178736 -0.85328 0.489864 + outer loop + vertex 1.54713 0.915037 2.45802 + vertex 1.54947 0.913317 2.45416 + vertex 1.55243 0.915033 2.45607 + endloop + endfacet + facet normal 0.198319 -0.815804 0.543262 + outer loop + vertex 1.55243 0.915033 2.45607 + vertex 1.55147 0.917382 2.45995 + vertex 1.54713 0.915037 2.45802 + endloop + endfacet + facet normal 0.161463 -0.788758 0.59312 + outer loop + vertex 1.55147 0.917382 2.45995 + vertex 1.5466 0.917392 2.46129 + vertex 1.54713 0.915037 2.45802 + endloop + endfacet + facet normal 0.181426 -0.724281 0.665208 + outer loop + vertex 1.55147 0.917382 2.45995 + vertex 1.54913 0.920026 2.46347 + vertex 1.5466 0.917392 2.46129 + endloop + endfacet + facet normal 0.123749 -0.751853 0.647614 + outer loop + vertex 1.554 0.919937 2.46243 + vertex 1.54913 0.920026 2.46347 + vertex 1.55147 0.917382 2.45995 + endloop + endfacet + facet normal 0.125801 -0.649963 0.749481 + outer loop + vertex 1.5497 0.922738 2.46573 + vertex 1.546 0.922077 2.46577 + vertex 1.54913 0.920026 2.46347 + endloop + endfacet + facet normal 0.12184 -0.649798 0.750279 + outer loop + vertex 1.5497 0.922738 2.46573 + vertex 1.54913 0.920026 2.46347 + vertex 1.55306 0.922415 2.4649 + endloop + endfacet + facet normal 0.142384 -0.670363 0.728245 + outer loop + vertex 1.55306 0.922415 2.4649 + vertex 1.54913 0.920026 2.46347 + vertex 1.554 0.919937 2.46243 + endloop + endfacet + facet normal 0.108944 -0.549818 0.828149 + outer loop + vertex 1.5497 0.922738 2.46573 + vertex 1.54864 0.925048 2.4674 + vertex 1.546 0.922077 2.46577 + endloop + endfacet + facet normal 0.141641 -0.578805 0.803071 + outer loop + vertex 1.55306 0.922415 2.4649 + vertex 1.55204 0.92472 2.46674 + vertex 1.5497 0.922738 2.46573 + endloop + endfacet + facet normal 0.106921 -0.550572 0.827912 + outer loop + vertex 1.55204 0.92472 2.46674 + vertex 1.54864 0.925048 2.4674 + vertex 1.5497 0.922738 2.46573 + endloop + endfacet + facet normal 0.119967 -0.488413 0.864327 + outer loop + vertex 1.55204 0.92472 2.46674 + vertex 1.55309 0.928495 2.46873 + vertex 1.54864 0.925048 2.4674 + endloop + endfacet + facet normal 0.100691 -0.31991 0.942082 + outer loop + vertex 1.55367 0.950187 2.47675 + vertex 1.54903 0.949777 2.47711 + vertex 1.5503 0.946498 2.47586 + endloop + endfacet + facet normal 0.100545 -0.317546 0.942897 + outer loop + vertex 1.55367 0.950187 2.47675 + vertex 1.55329 0.953989 2.47807 + vertex 1.54903 0.949777 2.47711 + endloop + endfacet + facet normal 0.101338 -0.326189 0.939857 + outer loop + vertex 1.54699 0.957386 2.47991 + vertex 1.55265 0.958429 2.47966 + vertex 1.55045 0.961406 2.48093 + endloop + endfacet + facet normal 0.103013 -0.302334 0.94762 + outer loop + vertex 1.55378 0.965134 2.4818 + vertex 1.55329 0.968997 2.48309 + vertex 1.54913 0.964711 2.48217 + endloop + endfacet + facet normal 0.116143 -0.310742 0.943372 + outer loop + vertex 1.54802 0.968556 2.48356 + vertex 1.55251 0.973515 2.48464 + vertex 1.54691 0.972361 2.48495 + endloop + endfacet + facet normal -0.10497 0.102973 -0.98913 + outer loop + vertex 1.55051 1.035 2.485 + vertex 1.55 1.03448 2.485 + vertex 1.54815 1.03455 2.4852 + endloop + endfacet + facet normal 0.11963 -0.227839 0.966322 + outer loop + vertex 1.55318 1.03031 2.50148 + vertex 1.55269 1.03377 2.50236 + vertex 1.54796 1.02866 2.50174 + endloop + endfacet + facet normal -0.0987976 -0.029221 0.994678 + outer loop + vertex 1.54796 1.02866 2.50174 + vertex 1.55269 1.03377 2.50236 + vertex 1.54757 1.03269 2.50182 + endloop + endfacet + facet normal -0.815568 0.439641 -0.37625 + outer loop + vertex 1.54815 1.03455 2.4852 + vertex 1.54725 1.03527 2.48799 + vertex 1.54925 1.03708 2.48577 + endloop + endfacet + facet normal -0.133798 0.272311 -0.952861 + outer loop + vertex 1.54815 1.03455 2.4852 + vertex 1.54925 1.03708 2.48577 + vertex 1.55051 1.035 2.485 + endloop + endfacet + facet normal -0.372473 0.11621 -0.920738 + outer loop + vertex 1.55051 1.035 2.485 + vertex 1.54925 1.03708 2.48577 + vertex 1.55207 1.04 2.485 + endloop + endfacet + facet normal -0.808522 0.485491 -0.332552 + outer loop + vertex 1.54869 1.03871 2.48952 + vertex 1.54925 1.03708 2.48577 + vertex 1.54725 1.03527 2.48799 + endloop + endfacet + facet normal -0.881079 0.442351 -0.167405 + outer loop + vertex 1.54691 1.03631 2.49254 + vertex 1.54869 1.03871 2.48952 + vertex 1.54725 1.03527 2.48799 + endloop + endfacet + facet normal -0.878293 0.450937 -0.158928 + outer loop + vertex 1.54855 1.04037 2.49496 + vertex 1.54869 1.03871 2.48952 + vertex 1.54691 1.03631 2.49254 + endloop + endfacet + facet normal -0.914908 0.400653 -0.0491976 + outer loop + vertex 1.5471 1.03724 2.4965 + vertex 1.54855 1.04037 2.49496 + vertex 1.54691 1.03631 2.49254 + endloop + endfacet + facet normal -0.901698 0.431584 0.0260003 + outer loop + vertex 1.54855 1.04037 2.49496 + vertex 1.5471 1.03724 2.4965 + vertex 1.54828 1.03956 2.4988 + endloop + endfacet + facet normal -0.0657797 -0.178992 0.981649 + outer loop + vertex 1.55269 1.03377 2.50236 + vertex 1.55265 1.03801 2.50313 + vertex 1.54757 1.03269 2.50182 + endloop + endfacet + facet normal -0.338747 0.0928288 0.936287 + outer loop + vertex 1.54757 1.03269 2.50182 + vertex 1.55265 1.03801 2.50313 + vertex 1.54895 1.0372 2.50187 + endloop + endfacet + facet normal -0.492273 0.620366 -0.610584 + outer loop + vertex 1.555 1.04311 2.485 + vertex 1.55125 1.04152 2.48641 + vertex 1.555 1.045 2.48692 + endloop + endfacet + facet normal -0.474126 0.446666 -0.758745 + outer loop + vertex 1.555 1.04311 2.485 + vertex 1.55207 1.04 2.485 + vertex 1.55125 1.04152 2.48641 + endloop + endfacet + facet normal -0.577483 0.364771 -0.73038 + outer loop + vertex 1.55207 1.04 2.485 + vertex 1.54925 1.03708 2.48577 + vertex 1.55125 1.04152 2.48641 + endloop + endfacet + facet normal -0.848135 0.42727 -0.313221 + outer loop + vertex 1.54925 1.03708 2.48577 + vertex 1.54869 1.03871 2.48952 + vertex 1.55125 1.04152 2.48641 + endloop + endfacet + facet normal -0.853116 0.35145 -0.385586 + outer loop + vertex 1.55125 1.04152 2.48641 + vertex 1.54869 1.03871 2.48952 + vertex 1.54993 1.04301 2.49068 + endloop + endfacet + facet normal -0.945028 0.305639 -0.11622 + outer loop + vertex 1.54869 1.03871 2.48952 + vertex 1.54855 1.04037 2.49496 + vertex 1.54993 1.04301 2.49068 + endloop + endfacet + facet normal -0.955362 0.253572 -0.151609 + outer loop + vertex 1.54993 1.04301 2.49068 + vertex 1.54855 1.04037 2.49496 + vertex 1.54967 1.04457 2.49493 + endloop + endfacet + facet normal -0.913599 0.243946 0.325312 + outer loop + vertex 1.54828 1.03956 2.4988 + vertex 1.54924 1.03998 2.5012 + vertex 1.55006 1.04438 2.50021 + endloop + endfacet + facet normal -0.937991 0.346618 0.00543525 + outer loop + vertex 1.54828 1.03956 2.4988 + vertex 1.55006 1.04438 2.50021 + vertex 1.54855 1.04037 2.49496 + endloop + endfacet + facet normal -0.962993 0.257124 0.0808243 + outer loop + vertex 1.54855 1.04037 2.49496 + vertex 1.55006 1.04438 2.50021 + vertex 1.54967 1.04457 2.49493 + endloop + endfacet + facet normal -0.702047 0.278334 0.655484 + outer loop + vertex 1.54924 1.03998 2.5012 + vertex 1.55266 1.04281 2.50366 + vertex 1.55006 1.04438 2.50021 + endloop + endfacet + facet normal -0.689694 0.239138 0.683472 + outer loop + vertex 1.54924 1.03998 2.5012 + vertex 1.54895 1.0372 2.50187 + vertex 1.55266 1.04281 2.50366 + endloop + endfacet + facet normal -0.3001 -0.103338 0.948294 + outer loop + vertex 1.54895 1.0372 2.50187 + vertex 1.55265 1.03801 2.50313 + vertex 1.55266 1.04281 2.50366 + endloop + endfacet + facet normal -0.22801 0.0388754 -0.972882 + outer loop + vertex 1.555 1.045 2.48692 + vertex 1.55195 1.04629 2.48769 + vertex 1.555 1.05 2.48712 + endloop + endfacet + facet normal -0.12381 0.274296 -0.953642 + outer loop + vertex 1.55125 1.04152 2.48641 + vertex 1.55195 1.04629 2.48769 + vertex 1.555 1.045 2.48692 + endloop + endfacet + facet normal -0.904808 0.229061 -0.358961 + outer loop + vertex 1.55125 1.04152 2.48641 + vertex 1.54993 1.04301 2.49068 + vertex 1.55195 1.04629 2.48769 + endloop + endfacet + facet normal -0.896257 0.182513 -0.404242 + outer loop + vertex 1.55195 1.04629 2.48769 + vertex 1.54993 1.04301 2.49068 + vertex 1.55052 1.04767 2.49149 + endloop + endfacet + facet normal -0.983329 0.142786 -0.112593 + outer loop + vertex 1.54993 1.04301 2.49068 + vertex 1.54967 1.04457 2.49493 + vertex 1.55052 1.04767 2.49149 + endloop + endfacet + facet normal -0.983587 0.104649 -0.146988 + outer loop + vertex 1.55052 1.04767 2.49149 + vertex 1.54967 1.04457 2.49493 + vertex 1.54992 1.04852 2.49612 + endloop + endfacet + facet normal -0.996416 0.0385582 0.075291 + outer loop + vertex 1.54967 1.04457 2.49493 + vertex 1.55006 1.04438 2.50021 + vertex 1.54992 1.04852 2.49612 + endloop + endfacet + facet normal -0.999583 -0.0275957 0.0085013 + outer loop + vertex 1.54992 1.04852 2.49612 + vertex 1.55006 1.04438 2.50021 + vertex 1.54992 1.04953 2.50005 + endloop + endfacet + facet normal -0.821867 -0.159086 0.547016 + outer loop + vertex 1.55243 1.04657 2.50441 + vertex 1.55006 1.04438 2.50021 + vertex 1.55266 1.04281 2.50366 + endloop + endfacet + facet normal -0.815389 -0.175169 0.551776 + outer loop + vertex 1.55243 1.04657 2.50441 + vertex 1.55138 1.04999 2.50393 + vertex 1.55006 1.04438 2.50021 + endloop + endfacet + facet normal -0.935741 -0.0149748 0.352369 + outer loop + vertex 1.55138 1.04999 2.50393 + vertex 1.54992 1.04953 2.50005 + vertex 1.55006 1.04438 2.50021 + endloop + endfacet + facet normal -0.586745 -0.0687215 0.806851 + outer loop + vertex 1.55243 1.04657 2.50441 + vertex 1.55441 1.04993 2.50613 + vertex 1.55138 1.04999 2.50393 + endloop + endfacet + facet normal -0.435256 -0.00360609 -0.900299 + outer loop + vertex 1.555 1.05 2.48712 + vertex 1.55226 1.05168 2.48844 + vertex 1.555 1.055 2.4871 + endloop + endfacet + facet normal -0.352826 0.148864 -0.923771 + outer loop + vertex 1.55195 1.04629 2.48769 + vertex 1.55226 1.05168 2.48844 + vertex 1.555 1.05 2.48712 + endloop + endfacet + facet normal -0.917125 0.105887 -0.384279 + outer loop + vertex 1.55195 1.04629 2.48769 + vertex 1.55052 1.04767 2.49149 + vertex 1.55226 1.05168 2.48844 + endloop + endfacet + facet normal -0.918861 0.110891 -0.378678 + outer loop + vertex 1.55226 1.05168 2.48844 + vertex 1.55052 1.04767 2.49149 + vertex 1.55083 1.05331 2.49238 + endloop + endfacet + facet normal -0.986813 0.0770501 -0.142352 + outer loop + vertex 1.55052 1.04767 2.49149 + vertex 1.54992 1.04852 2.49612 + vertex 1.55083 1.05331 2.49238 + endloop + endfacet + facet normal -0.975387 0.0143772 -0.220029 + outer loop + vertex 1.55083 1.05331 2.49238 + vertex 1.54992 1.04852 2.49612 + vertex 1.54983 1.05357 2.49684 + endloop + endfacet + facet normal -0.99981 -0.0185098 0.0061516 + outer loop + vertex 1.54992 1.04852 2.49612 + vertex 1.54992 1.04953 2.50005 + vertex 1.54983 1.05357 2.49684 + endloop + endfacet + facet normal -0.996881 -0.0620767 -0.0487415 + outer loop + vertex 1.54983 1.05357 2.49684 + vertex 1.54992 1.04953 2.50005 + vertex 1.54961 1.05349 2.50131 + endloop + endfacet + facet normal -0.912418 -0.187152 0.363961 + outer loop + vertex 1.54992 1.04953 2.50005 + vertex 1.55138 1.04999 2.50393 + vertex 1.54961 1.05349 2.50131 + endloop + endfacet + facet normal -0.916118 -0.202414 0.34606 + outer loop + vertex 1.54961 1.05349 2.50131 + vertex 1.55138 1.04999 2.50393 + vertex 1.55074 1.05494 2.50513 + endloop + endfacet + facet normal -0.486955 -0.264858 0.832301 + outer loop + vertex 1.55138 1.04999 2.50393 + vertex 1.55403 1.05402 2.50676 + vertex 1.55074 1.05494 2.50513 + endloop + endfacet + facet normal -0.580364 -0.177097 0.794868 + outer loop + vertex 1.55441 1.04993 2.50613 + vertex 1.55403 1.05402 2.50676 + vertex 1.55138 1.04999 2.50393 + endloop + endfacet + facet normal -0.777788 0.0785905 -0.623594 + outer loop + vertex 1.555 1.055 2.4871 + vertex 1.55318 1.06 2.49 + vertex 1.555 1.06 2.48773 + endloop + endfacet + facet normal -0.622622 0.210519 -0.753673 + outer loop + vertex 1.55226 1.05168 2.48844 + vertex 1.55318 1.06 2.49 + vertex 1.555 1.055 2.4871 + endloop + endfacet + facet normal -0.900528 0.174549 -0.398223 + outer loop + vertex 1.55226 1.05168 2.48844 + vertex 1.55083 1.05331 2.49238 + vertex 1.55318 1.06 2.49 + endloop + endfacet + facet normal -0.941186 0.249582 -0.227768 + outer loop + vertex 1.55318 1.06 2.49 + vertex 1.55083 1.05331 2.49238 + vertex 1.55197 1.06 2.495 + endloop + endfacet + facet normal -0.941748 0.249011 -0.226061 + outer loop + vertex 1.55083 1.05331 2.49238 + vertex 1.54983 1.05357 2.49684 + vertex 1.55197 1.06 2.495 + endloop + endfacet + facet normal -0.695475 0.0260676 -0.718078 + outer loop + vertex 1.55197 1.06 2.495 + vertex 1.54983 1.05357 2.49684 + vertex 1.54908 1.05855 2.49775 + endloop + endfacet + facet normal -0.988993 -0.139381 -0.049663 + outer loop + vertex 1.54983 1.05357 2.49684 + vertex 1.54961 1.05349 2.50131 + vertex 1.54908 1.05855 2.49775 + endloop + endfacet + facet normal -0.975516 -0.185819 -0.117641 + outer loop + vertex 1.54908 1.05855 2.49775 + vertex 1.54961 1.05349 2.50131 + vertex 1.54872 1.0574 2.50251 + endloop + endfacet + facet normal -0.871982 -0.314051 0.375526 + outer loop + vertex 1.54961 1.05349 2.50131 + vertex 1.55074 1.05494 2.50513 + vertex 1.54872 1.0574 2.50251 + endloop + endfacet + facet normal -0.872302 -0.329994 0.360823 + outer loop + vertex 1.54872 1.0574 2.50251 + vertex 1.55074 1.05494 2.50513 + vertex 1.54962 1.05847 2.50566 + endloop + endfacet + facet normal -0.482594 -0.277105 0.830852 + outer loop + vertex 1.55074 1.05494 2.50513 + vertex 1.55288 1.05905 2.50775 + vertex 1.54962 1.05847 2.50566 + endloop + endfacet + facet normal -0.487745 -0.273295 0.829105 + outer loop + vertex 1.55403 1.05402 2.50676 + vertex 1.55288 1.05905 2.50775 + vertex 1.55074 1.05494 2.50513 + endloop + endfacet + facet normal -0.224787 -0.307618 -0.924577 + outer loop + vertex 1.54806 1.06232 2.49671 + vertex 1.54794 1.06589 2.49555 + vertex 1.55143 1.065 2.495 + endloop + endfacet + facet normal -0.21956 -0.313698 -0.92379 + outer loop + vertex 1.54806 1.06232 2.49671 + vertex 1.55143 1.065 2.495 + vertex 1.54908 1.05855 2.49775 + endloop + endfacet + facet normal -0.667897 -0.0721336 -0.74075 + outer loop + vertex 1.54908 1.05855 2.49775 + vertex 1.55143 1.065 2.495 + vertex 1.55197 1.06 2.495 + endloop + endfacet + facet normal -0.872227 -0.456534 -0.175491 + outer loop + vertex 1.54908 1.05855 2.49775 + vertex 1.54872 1.0574 2.50251 + vertex 1.54752 1.06072 2.49989 + endloop + endfacet + facet normal -0.889527 -0.32848 -0.317557 + outer loop + vertex 1.54806 1.06232 2.49671 + vertex 1.54908 1.05855 2.49775 + vertex 1.54752 1.06072 2.49989 + endloop + endfacet + facet normal -0.87094 -0.332911 0.361433 + outer loop + vertex 1.54872 1.0574 2.50251 + vertex 1.54962 1.05847 2.50566 + vertex 1.54789 1.06091 2.50373 + endloop + endfacet + facet normal -0.958423 -0.265041 0.105729 + outer loop + vertex 1.54752 1.06072 2.49989 + vertex 1.54872 1.0574 2.50251 + vertex 1.54789 1.06091 2.50373 + endloop + endfacet + facet normal -0.839886 -0.196431 0.505971 + outer loop + vertex 1.54962 1.05847 2.50566 + vertex 1.54961 1.06209 2.50705 + vertex 1.54789 1.06091 2.50373 + endloop + endfacet + facet normal -0.47084 -0.316793 0.823378 + outer loop + vertex 1.54962 1.05847 2.50566 + vertex 1.55288 1.05905 2.50775 + vertex 1.54961 1.06209 2.50705 + endloop + endfacet + facet normal -0.450217 -0.28969 0.844621 + outer loop + vertex 1.55288 1.05905 2.50775 + vertex 1.55288 1.06442 2.50959 + vertex 1.54961 1.06209 2.50705 + endloop + endfacet + facet normal -0.167333 -0.0441762 -0.98491 + outer loop + vertex 1.55011 1.07 2.495 + vertex 1.55143 1.065 2.495 + vertex 1.54794 1.06589 2.49555 + endloop + endfacet + facet normal -0.112492 -0.0738537 -0.990904 + outer loop + vertex 1.54775 1.07022 2.49525 + vertex 1.55011 1.07 2.495 + vertex 1.54794 1.06589 2.49555 + endloop + endfacet + facet normal -0.495525 -0.454182 0.740387 + outer loop + vertex 1.55157 1.06725 2.51074 + vertex 1.55007 1.06919 2.51092 + vertex 1.54909 1.06659 2.50868 + endloop + endfacet + facet normal -0.466213 -0.509854 0.722976 + outer loop + vertex 1.55157 1.06725 2.51074 + vertex 1.54909 1.06659 2.50868 + vertex 1.55288 1.06442 2.50959 + endloop + endfacet + facet normal -0.404999 -0.352387 0.843682 + outer loop + vertex 1.55288 1.06442 2.50959 + vertex 1.54909 1.06659 2.50868 + vertex 1.54961 1.06209 2.50705 + endloop + endfacet + facet normal -0.180103 -0.230851 0.956175 + outer loop + vertex 1.55157 1.06725 2.51074 + vertex 1.55324 1.07039 2.51181 + vertex 1.55007 1.06919 2.51092 + endloop + endfacet + facet normal -0.105611 0.00506866 -0.994395 + outer loop + vertex 1.55035 1.075 2.495 + vertex 1.55011 1.07 2.495 + vertex 1.54775 1.07022 2.49525 + endloop + endfacet + facet normal -0.203551 0.0593091 -0.977266 + outer loop + vertex 1.54828 1.07511 2.49544 + vertex 1.55035 1.075 2.495 + vertex 1.54775 1.07022 2.49525 + endloop + endfacet + facet normal -0.65132 -0.341316 0.677706 + outer loop + vertex 1.54909 1.06659 2.50868 + vertex 1.55007 1.06919 2.51092 + vertex 1.54812 1.0704 2.50966 + endloop + endfacet + facet normal -0.608026 -0.169571 0.775596 + outer loop + vertex 1.55007 1.06919 2.51092 + vertex 1.55025 1.07335 2.51198 + vertex 1.54812 1.0704 2.50966 + endloop + endfacet + facet normal -0.179005 -0.233432 0.955755 + outer loop + vertex 1.55007 1.06919 2.51092 + vertex 1.55324 1.07039 2.51181 + vertex 1.55025 1.07335 2.51198 + endloop + endfacet + facet normal -0.143529 -0.198335 0.969568 + outer loop + vertex 1.55324 1.07039 2.51181 + vertex 1.55417 1.07448 2.51279 + vertex 1.55025 1.07335 2.51198 + endloop + endfacet + facet normal -0.202873 0.0701974 -0.976686 + outer loop + vertex 1.55208 1.08 2.495 + vertex 1.55035 1.075 2.495 + vertex 1.54828 1.07511 2.49544 + endloop + endfacet + facet normal -0.704764 0.502996 -0.500302 + outer loop + vertex 1.55 1.08 2.49793 + vertex 1.55208 1.08 2.495 + vertex 1.54828 1.07511 2.49544 + endloop + endfacet + facet normal -0.119315 -0.271904 0.954899 + outer loop + vertex 1.55417 1.07448 2.51279 + vertex 1.55328 1.07824 2.51375 + vertex 1.55025 1.07335 2.51198 + endloop + endfacet + facet normal -0.121045 -0.270858 0.954978 + outer loop + vertex 1.55025 1.07335 2.51198 + vertex 1.55328 1.07824 2.51375 + vertex 1.54907 1.07883 2.51338 + endloop + endfacet + facet normal 0.19171 -0.153348 0.969398 + outer loop + vertex 1.54999 1.24695 2.54595 + vertex 1.54719 1.24464 2.54614 + vertex 1.54956 1.24381 2.54554 + endloop + endfacet + facet normal -0.813697 -0.383391 -0.43693 + outer loop + vertex 1.55196 1.955 2.495 + vertex 1.55 1.955 2.49865 + vertex 1.55 1.95916 2.495 + endloop + endfacet + facet normal -0.178197 0.0360743 -0.983333 + outer loop + vertex 1.55034 1.965 2.495 + vertex 1.55 1.96332 2.495 + vertex 1.5483 1.96295 2.4953 + endloop + endfacet + facet normal -0.961859 0.273354 -0.0102101 + outer loop + vertex 1.54792 1.96434 2.5005 + vertex 1.54699 1.96104 2.49977 + vertex 1.54702 1.96127 2.50248 + endloop + endfacet + facet normal -0.939224 0.331323 0.0899086 + outer loop + vertex 1.54792 1.96434 2.5005 + vertex 1.54702 1.96127 2.50248 + vertex 1.54793 1.96342 2.50404 + endloop + endfacet + facet normal -0.138719 0.363899 0.921051 + outer loop + vertex 1.55027 1.95834 2.51037 + vertex 1.5534 1.95825 2.51087 + vertex 1.5538 1.96208 2.50942 + endloop + endfacet + facet normal -0.296062 0.487169 0.821592 + outer loop + vertex 1.54967 1.96144 2.50832 + vertex 1.55027 1.95834 2.51037 + vertex 1.5538 1.96208 2.50942 + endloop + endfacet + facet normal -0.250989 0.309903 0.917041 + outer loop + vertex 1.55136 1.95468 2.5119 + vertex 1.55027 1.95834 2.51037 + vertex 1.54838 1.95527 2.51089 + endloop + endfacet + facet normal -0.140229 0.346991 0.927326 + outer loop + vertex 1.5534 1.95825 2.51087 + vertex 1.55027 1.95834 2.51037 + vertex 1.55136 1.95468 2.5119 + endloop + endfacet + facet normal -0.932648 0.20613 -0.296103 + outer loop + vertex 1.5483 1.96295 2.4953 + vertex 1.54758 1.96272 2.49739 + vertex 1.54892 1.96687 2.49606 + endloop + endfacet + facet normal -0.364426 0.233406 -0.901507 + outer loop + vertex 1.5483 1.96295 2.4953 + vertex 1.54892 1.96687 2.49606 + vertex 1.55034 1.965 2.495 + endloop + endfacet + facet normal -0.512709 0.0933053 -0.853478 + outer loop + vertex 1.55034 1.965 2.495 + vertex 1.54892 1.96687 2.49606 + vertex 1.55125 1.97 2.495 + endloop + endfacet + facet normal -0.959189 0.279667 -0.0417458 + outer loop + vertex 1.54758 1.96272 2.49739 + vertex 1.54699 1.96104 2.49977 + vertex 1.54792 1.96434 2.5005 + endloop + endfacet + facet normal -0.954887 0.292888 -0.0490699 + outer loop + vertex 1.54758 1.96272 2.49739 + vertex 1.54792 1.96434 2.5005 + vertex 1.54892 1.96687 2.49606 + endloop + endfacet + facet normal -0.971367 0.217507 -0.0955912 + outer loop + vertex 1.54892 1.96687 2.49606 + vertex 1.54792 1.96434 2.5005 + vertex 1.54892 1.96841 2.49959 + endloop + endfacet + facet normal -0.863856 0.338092 0.373425 + outer loop + vertex 1.54793 1.96342 2.50404 + vertex 1.54904 1.9638 2.50625 + vertex 1.54962 1.96776 2.50403 + endloop + endfacet + facet normal -0.926973 0.362145 0.0978358 + outer loop + vertex 1.54793 1.96342 2.50404 + vertex 1.54962 1.96776 2.50403 + vertex 1.54792 1.96434 2.5005 + endloop + endfacet + facet normal -0.942544 0.274542 0.190359 + outer loop + vertex 1.54792 1.96434 2.5005 + vertex 1.54962 1.96776 2.50403 + vertex 1.54892 1.96841 2.49959 + endloop + endfacet + facet normal -0.612429 0.454177 0.647034 + outer loop + vertex 1.54904 1.9638 2.50625 + vertex 1.55214 1.96627 2.50746 + vertex 1.54962 1.96776 2.50403 + endloop + endfacet + facet normal -0.601824 0.427232 0.674745 + outer loop + vertex 1.54904 1.9638 2.50625 + vertex 1.54967 1.96144 2.50832 + vertex 1.55214 1.96627 2.50746 + endloop + endfacet + facet normal -0.290944 0.309095 0.905435 + outer loop + vertex 1.54967 1.96144 2.50832 + vertex 1.5538 1.96208 2.50942 + vertex 1.55214 1.96627 2.50746 + endloop + endfacet + facet normal -0.428338 0.013705 -0.903515 + outer loop + vertex 1.55125 1.97 2.495 + vertex 1.54892 1.96687 2.49606 + vertex 1.55141 1.975 2.495 + endloop + endfacet + facet normal -0.677509 0.112951 -0.72679 + outer loop + vertex 1.55141 1.975 2.495 + vertex 1.54892 1.96687 2.49606 + vertex 1.54952 1.97221 2.49633 + endloop + endfacet + facet normal -0.992322 0.113117 -0.0500091 + outer loop + vertex 1.54892 1.96687 2.49606 + vertex 1.54892 1.96841 2.49959 + vertex 1.54952 1.97221 2.49633 + endloop + endfacet + facet normal -0.984097 0.175908 0.0247035 + outer loop + vertex 1.54952 1.97221 2.49633 + vertex 1.54892 1.96841 2.49959 + vertex 1.54966 1.97243 2.50063 + endloop + endfacet + facet normal -0.975155 0.135543 0.175217 + outer loop + vertex 1.54892 1.96841 2.49959 + vertex 1.54962 1.96776 2.50403 + vertex 1.54966 1.97243 2.50063 + endloop + endfacet + facet normal -0.939173 0.207213 0.273892 + outer loop + vertex 1.54966 1.97243 2.50063 + vertex 1.54962 1.96776 2.50403 + vertex 1.55093 1.97335 2.50427 + endloop + endfacet + facet normal -0.760565 0.150542 0.631568 + outer loop + vertex 1.54962 1.96776 2.50403 + vertex 1.55209 1.97063 2.50631 + vertex 1.55093 1.97335 2.50427 + endloop + endfacet + facet normal -0.762953 0.155924 0.627368 + outer loop + vertex 1.55214 1.96627 2.50746 + vertex 1.55209 1.97063 2.50631 + vertex 1.54962 1.96776 2.50403 + endloop + endfacet + facet normal -0.990065 0.00198282 -0.140595 + outer loop + vertex 1.55212 1.975 2.49 + vertex 1.55141 1.975 2.495 + vertex 1.55213 1.98 2.49 + endloop + endfacet + facet normal -0.0775541 -0.699362 -0.710547 + outer loop + vertex 1.55213 1.98 2.49 + vertex 1.55141 1.975 2.495 + vertex 1.55034 1.97765 2.49251 + endloop + endfacet + facet normal 0.321023 -0.576839 -0.751133 + outer loop + vertex 1.55141 1.975 2.495 + vertex 1.54952 1.97221 2.49633 + vertex 1.55034 1.97765 2.49251 + endloop + endfacet + facet normal -0.987888 0.0456313 -0.148308 + outer loop + vertex 1.55034 1.97765 2.49251 + vertex 1.54952 1.97221 2.49633 + vertex 1.54968 1.97679 2.49662 + endloop + endfacet + facet normal -0.998871 0.0347209 0.0324223 + outer loop + vertex 1.54952 1.97221 2.49633 + vertex 1.54966 1.97243 2.50063 + vertex 1.54968 1.97679 2.49662 + endloop + endfacet + facet normal -0.989329 0.101184 0.104834 + outer loop + vertex 1.54968 1.97679 2.49662 + vertex 1.54966 1.97243 2.50063 + vertex 1.5502 1.97724 2.50107 + endloop + endfacet + facet normal -0.947673 0.0774101 0.309716 + outer loop + vertex 1.54966 1.97243 2.50063 + vertex 1.55093 1.97335 2.50427 + vertex 1.5502 1.97724 2.50107 + endloop + endfacet + facet normal -0.875598 0.198289 0.440465 + outer loop + vertex 1.5502 1.97724 2.50107 + vertex 1.55093 1.97335 2.50427 + vertex 1.55195 1.97793 2.50423 + endloop + endfacet + facet normal -0.668015 0.15418 0.728 + outer loop + vertex 1.55093 1.97335 2.50427 + vertex 1.55325 1.97446 2.50616 + vertex 1.55195 1.97793 2.50423 + endloop + endfacet + facet normal -0.679428 0.233334 0.695652 + outer loop + vertex 1.55209 1.97063 2.50631 + vertex 1.55325 1.97446 2.50616 + vertex 1.55093 1.97335 2.50427 + endloop + endfacet + facet normal -0.818212 0.00981238 -0.574833 + outer loop + vertex 1.55213 1.98 2.49 + vertex 1.55034 1.97765 2.49251 + vertex 1.55219 1.985 2.49 + endloop + endfacet + facet normal -0.739041 -0.0433441 -0.672265 + outer loop + vertex 1.55219 1.985 2.49 + vertex 1.55034 1.97765 2.49251 + vertex 1.55 1.98212 2.49259 + endloop + endfacet + facet normal -0.98257 -0.0709168 -0.171837 + outer loop + vertex 1.55034 1.97765 2.49251 + vertex 1.54968 1.97679 2.49662 + vertex 1.55 1.98212 2.49259 + endloop + endfacet + facet normal -0.993393 -0.0250098 -0.112007 + outer loop + vertex 1.55 1.98212 2.49259 + vertex 1.54968 1.97679 2.49662 + vertex 1.54951 1.98135 2.49713 + endloop + endfacet + facet normal -0.991442 -0.0507767 0.120271 + outer loop + vertex 1.54968 1.97679 2.49662 + vertex 1.5502 1.97724 2.50107 + vertex 1.54951 1.98135 2.49713 + endloop + endfacet + facet normal -0.983243 0.00994256 0.182029 + outer loop + vertex 1.54951 1.98135 2.49713 + vertex 1.5502 1.97724 2.50107 + vertex 1.5503 1.98237 2.50132 + endloop + endfacet + facet normal -0.479343 0.242909 0.843342 + outer loop + vertex 1.55389 1.98258 2.504 + vertex 1.55195 1.97793 2.50423 + vertex 1.55438 1.97793 2.50562 + endloop + endfacet + facet normal -0.583331 0.28225 0.761616 + outer loop + vertex 1.55389 1.98258 2.504 + vertex 1.5503 1.98237 2.50132 + vertex 1.55195 1.97793 2.50423 + endloop + endfacet + facet normal -0.874613 -0.00678228 0.484775 + outer loop + vertex 1.5503 1.98237 2.50132 + vertex 1.5502 1.97724 2.50107 + vertex 1.55195 1.97793 2.50423 + endloop + endfacet + facet normal -0.473584 0.28573 0.833112 + outer loop + vertex 1.55438 1.97793 2.50562 + vertex 1.55195 1.97793 2.50423 + vertex 1.55325 1.97446 2.50616 + endloop + endfacet + facet normal -0.705365 -0.0959255 -0.702323 + outer loop + vertex 1.55219 1.985 2.49 + vertex 1.55 1.98212 2.49259 + vertex 1.55151 1.99 2.49 + endloop + endfacet + facet normal -0.742759 -0.0765717 -0.665166 + outer loop + vertex 1.55151 1.99 2.49 + vertex 1.55 1.98212 2.49259 + vertex 1.54897 1.9858 2.49332 + endloop + endfacet + facet normal -0.959794 -0.240287 -0.14511 + outer loop + vertex 1.55 1.98212 2.49259 + vertex 1.54951 1.98135 2.49713 + vertex 1.54897 1.9858 2.49332 + endloop + endfacet + facet normal -0.972479 -0.20781 -0.105359 + outer loop + vertex 1.54897 1.9858 2.49332 + vertex 1.54951 1.98135 2.49713 + vertex 1.54863 1.98524 2.49762 + endloop + endfacet + facet normal -0.890896 -0.419397 0.174387 + outer loop + vertex 1.54865 1.9863 2.50031 + vertex 1.54736 1.98818 2.49821 + vertex 1.54863 1.98524 2.49762 + endloop + endfacet + facet normal -0.925197 -0.349738 0.147286 + outer loop + vertex 1.54865 1.9863 2.50031 + vertex 1.54863 1.98524 2.49762 + vertex 1.5503 1.98237 2.50132 + endloop + endfacet + facet normal -0.940651 -0.243672 0.23622 + outer loop + vertex 1.5503 1.98237 2.50132 + vertex 1.54863 1.98524 2.49762 + vertex 1.54951 1.98135 2.49713 + endloop + endfacet + facet normal -0.758398 -0.154728 0.63316 + outer loop + vertex 1.5503 1.98237 2.50132 + vertex 1.55019 1.98715 2.50236 + vertex 1.54865 1.9863 2.50031 + endloop + endfacet + facet normal -0.580336 -0.185433 0.792985 + outer loop + vertex 1.5503 1.98237 2.50132 + vertex 1.55389 1.98258 2.504 + vertex 1.55019 1.98715 2.50236 + endloop + endfacet + facet normal -0.272665 0.121399 0.954419 + outer loop + vertex 1.55389 1.98258 2.504 + vertex 1.55337 1.98727 2.50325 + vertex 1.55019 1.98715 2.50236 + endloop + endfacet + facet normal -0.23446 -0.51111 -0.826919 + outer loop + vertex 1.55151 1.99 2.49 + vertex 1.54897 1.9858 2.49332 + vertex 1.54831 1.99029 2.49073 + endloop + endfacet + facet normal -0.229108 -0.104838 -0.967739 + outer loop + vertex 1.55 1.9933 2.49 + vertex 1.55151 1.99 2.49 + vertex 1.54831 1.99029 2.49073 + endloop + endfacet + facet normal -0.89132 -0.43482 -0.128378 + outer loop + vertex 1.54897 1.9858 2.49332 + vertex 1.54863 1.98524 2.49762 + vertex 1.54732 1.9888 2.49462 + endloop + endfacet + facet normal -0.876829 -0.33101 -0.348718 + outer loop + vertex 1.54831 1.99029 2.49073 + vertex 1.54897 1.9858 2.49332 + vertex 1.54732 1.9888 2.49462 + endloop + endfacet + facet normal -0.920832 -0.38574 -0.0572003 + outer loop + vertex 1.54863 1.98524 2.49762 + vertex 1.54736 1.98818 2.49821 + vertex 1.54732 1.9888 2.49462 + endloop + endfacet + facet normal -0.270884 0.0139858 0.96251 + outer loop + vertex 1.55337 1.98727 2.50325 + vertex 1.55144 1.9904 2.50267 + vertex 1.55019 1.98715 2.50236 + endloop + endfacet + facet normal -0.191791 -0.0181852 0.981267 + outer loop + vertex 1.55019 1.98715 2.50236 + vertex 1.55144 1.9904 2.50267 + vertex 1.54756 1.99267 2.50195 + endloop + endfacet + facet normal 0.127086 0.460447 0.878543 + outer loop + vertex 1.55214 2.10203 2.46886 + vertex 1.55128 2.10491 2.46747 + vertex 1.54827 2.10195 2.46946 + endloop + endfacet + facet normal 0.133776 0.454906 0.880434 + outer loop + vertex 1.54827 2.10195 2.46946 + vertex 1.55128 2.10491 2.46747 + vertex 1.54596 2.10604 2.4677 + endloop + endfacet + facet normal 0.154781 0.672447 0.72378 + outer loop + vertex 1.5486 2.1084 2.4656 + vertex 1.55258 2.10756 2.46553 + vertex 1.55163 2.1103 2.46318 + endloop + endfacet + facet normal 0.163515 0.664901 0.728813 + outer loop + vertex 1.54633 2.1113 2.46346 + vertex 1.5486 2.1084 2.4656 + vertex 1.55163 2.1103 2.46318 + endloop + endfacet + facet normal 0.152464 0.555883 0.817159 + outer loop + vertex 1.55128 2.10491 2.46747 + vertex 1.5486 2.1084 2.4656 + vertex 1.54596 2.10604 2.4677 + endloop + endfacet + facet normal 0.129688 0.544488 0.828682 + outer loop + vertex 1.55258 2.10756 2.46553 + vertex 1.5486 2.1084 2.4656 + vertex 1.55128 2.10491 2.46747 + endloop + endfacet + facet normal 0.184353 0.890184 0.416637 + outer loop + vertex 1.54875 2.11472 2.45756 + vertex 1.5545 2.11444 2.45562 + vertex 1.55053 2.11629 2.45343 + endloop + endfacet + facet normal 0.181245 0.891256 0.415708 + outer loop + vertex 1.54651 2.11649 2.45476 + vertex 1.54875 2.11472 2.45756 + vertex 1.55053 2.11629 2.45343 + endloop + endfacet + facet normal 0.198009 0.86511 0.460844 + outer loop + vertex 1.5545 2.11444 2.45562 + vertex 1.54875 2.11472 2.45756 + vertex 1.5529 2.11262 2.45973 + endloop + endfacet + facet normal 0.176115 0.853146 0.491045 + outer loop + vertex 1.5529 2.11262 2.45973 + vertex 1.54875 2.11472 2.45756 + vertex 1.54867 2.11277 2.46099 + endloop + endfacet + facet normal 0.176535 0.763323 0.621429 + outer loop + vertex 1.55163 2.1103 2.46318 + vertex 1.54867 2.11277 2.46099 + vertex 1.54633 2.1113 2.46346 + endloop + endfacet + facet normal 0.204935 0.775667 0.596945 + outer loop + vertex 1.5529 2.11262 2.45973 + vertex 1.54867 2.11277 2.46099 + vertex 1.55163 2.1103 2.46318 + endloop + endfacet + facet normal 0.00246588 0.0684944 0.997648 + outer loop + vertex 1.555 2.12196 2.45 + vertex 1.55 2.12214 2.45 + vertex 1.55292 2.11845 2.45025 + endloop + endfacet + facet normal 0.17906 0.205781 0.962077 + outer loop + vertex 1.55292 2.11845 2.45025 + vertex 1.55 2.12214 2.45 + vertex 1.54674 2.11846 2.45139 + endloop + endfacet + facet normal 0.208397 0.836936 0.506072 + outer loop + vertex 1.55053 2.11629 2.45343 + vertex 1.54674 2.11846 2.45139 + vertex 1.54651 2.11649 2.45476 + endloop + endfacet + facet normal 0.116062 0.779308 0.6158 + outer loop + vertex 1.55292 2.11845 2.45025 + vertex 1.54674 2.11846 2.45139 + vertex 1.55053 2.11629 2.45343 + endloop + endfacet + facet normal 0.223074 -0.0690377 0.972354 + outer loop + vertex 1.55617 0.913332 2.45089 + vertex 1.56 0.913154 2.45 + vertex 1.56015 0.913911 2.45002 + endloop + endfacet + facet normal 0.146029 -0.639048 0.755177 + outer loop + vertex 1.55617 0.913332 2.45089 + vertex 1.55245 0.91233 2.45076 + vertex 1.56 0.913154 2.45 + endloop + endfacet + facet normal 0.146051 -0.800708 0.580978 + outer loop + vertex 1.55245 0.91233 2.45076 + vertex 1.555 0.912242 2.45 + vertex 1.56 0.913154 2.45 + endloop + endfacet + facet normal 0.221277 -0.87671 0.427101 + outer loop + vertex 1.55617 0.913332 2.45089 + vertex 1.55339 0.913606 2.45289 + vertex 1.55245 0.91233 2.45076 + endloop + endfacet + facet normal 0.218019 -0.887399 0.40619 + outer loop + vertex 1.56015 0.913911 2.45002 + vertex 1.55737 0.914818 2.45349 + vertex 1.55617 0.913332 2.45089 + endloop + endfacet + facet normal 0.208427 -0.887604 0.410751 + outer loop + vertex 1.55339 0.913606 2.45289 + vertex 1.55617 0.913332 2.45089 + vertex 1.55737 0.914818 2.45349 + endloop + endfacet + facet normal 0.197364 -0.870802 0.45028 + outer loop + vertex 1.55339 0.913606 2.45289 + vertex 1.55737 0.914818 2.45349 + vertex 1.55243 0.915033 2.45607 + endloop + endfacet + facet normal 0.203584 -0.863424 0.461576 + outer loop + vertex 1.55243 0.915033 2.45607 + vertex 1.55737 0.914818 2.45349 + vertex 1.55606 0.91669 2.45757 + endloop + endfacet + facet normal 0.155077 -0.826176 0.54165 + outer loop + vertex 1.55552 0.918341 2.46024 + vertex 1.55606 0.91669 2.45757 + vertex 1.55911 0.918386 2.45928 + endloop + endfacet + facet normal 0.156381 -0.825878 0.54173 + outer loop + vertex 1.55552 0.918341 2.46024 + vertex 1.55147 0.917382 2.45995 + vertex 1.55606 0.91669 2.45757 + endloop + endfacet + facet normal 0.155041 -0.827509 0.539621 + outer loop + vertex 1.55147 0.917382 2.45995 + vertex 1.55243 0.915033 2.45607 + vertex 1.55606 0.91669 2.45757 + endloop + endfacet + facet normal 0.132377 -0.75508 0.64213 + outer loop + vertex 1.55552 0.918341 2.46024 + vertex 1.554 0.919937 2.46243 + vertex 1.55147 0.917382 2.45995 + endloop + endfacet + facet normal 0.171899 -0.776026 0.606823 + outer loop + vertex 1.55911 0.918386 2.45928 + vertex 1.55751 0.919812 2.46156 + vertex 1.55552 0.918341 2.46024 + endloop + endfacet + facet normal 0.13272 -0.754918 0.642249 + outer loop + vertex 1.55751 0.919812 2.46156 + vertex 1.554 0.919937 2.46243 + vertex 1.55552 0.918341 2.46024 + endloop + endfacet + facet normal 0.149877 -0.695419 0.7028 + outer loop + vertex 1.55751 0.919812 2.46156 + vertex 1.55801 0.922346 2.46396 + vertex 1.554 0.919937 2.46243 + endloop + endfacet + facet normal 0.128102 -0.674571 0.72701 + outer loop + vertex 1.55801 0.922346 2.46396 + vertex 1.55306 0.922415 2.4649 + vertex 1.554 0.919937 2.46243 + endloop + endfacet + facet normal 0.142003 -0.590619 0.794358 + outer loop + vertex 1.55306 0.922415 2.4649 + vertex 1.55801 0.922346 2.46396 + vertex 1.55597 0.925386 2.46659 + endloop + endfacet + facet normal 0.129933 -0.583088 0.801951 + outer loop + vertex 1.55204 0.92472 2.46674 + vertex 1.55306 0.922415 2.4649 + vertex 1.55597 0.925386 2.46659 + endloop + endfacet + facet normal 0.116297 -0.487829 0.865158 + outer loop + vertex 1.55597 0.925386 2.46659 + vertex 1.55309 0.928495 2.46873 + vertex 1.55204 0.92472 2.46674 + endloop + endfacet + facet normal 0.100124 -0.499593 0.860454 + outer loop + vertex 1.55896 0.928968 2.46832 + vertex 1.55309 0.928495 2.46873 + vertex 1.55597 0.925386 2.46659 + endloop + endfacet + facet normal 0.0973442 -0.317158 0.943364 + outer loop + vertex 1.55415 0.947411 2.47577 + vertex 1.55367 0.950187 2.47675 + vertex 1.5503 0.946498 2.47586 + endloop + endfacet + facet normal 0.107776 -0.319897 0.941302 + outer loop + vertex 1.55744 0.947183 2.47531 + vertex 1.55688 0.94987 2.47629 + vertex 1.55415 0.947411 2.47577 + endloop + endfacet + facet normal 0.103879 -0.315943 0.943074 + outer loop + vertex 1.55688 0.94987 2.47629 + vertex 1.55367 0.950187 2.47675 + vertex 1.55415 0.947411 2.47577 + endloop + endfacet + facet normal 0.105315 -0.305953 0.946204 + outer loop + vertex 1.55688 0.94987 2.47629 + vertex 1.55849 0.953805 2.47738 + vertex 1.55367 0.950187 2.47675 + endloop + endfacet + facet normal 0.113365 -0.315928 0.941986 + outer loop + vertex 1.55849 0.953805 2.47738 + vertex 1.55329 0.953989 2.47807 + vertex 1.55367 0.950187 2.47675 + endloop + endfacet + facet normal 0.104717 -0.323869 0.940289 + outer loop + vertex 1.55429 0.962344 2.48083 + vertex 1.55045 0.961406 2.48093 + vertex 1.55265 0.958429 2.47966 + endloop + endfacet + facet normal 0.130808 -0.332897 0.933846 + outer loop + vertex 1.55429 0.962344 2.48083 + vertex 1.55265 0.958429 2.47966 + vertex 1.55754 0.962184 2.48032 + endloop + endfacet + facet normal 0.132632 -0.225667 0.965134 + outer loop + vertex 1.55774 1.03417 2.50176 + vertex 1.55269 1.03377 2.50236 + vertex 1.55318 1.03031 2.50148 + endloop + endfacet + facet normal 0.148035 0.130547 0.980328 + outer loop + vertex 1.5546 1.77355 2.54533 + vertex 1.55873 1.76904 2.54531 + vertex 1.55907 1.77378 2.54463 + endloop + endfacet + facet normal 0.20448 0.197147 0.958812 + outer loop + vertex 1.55861 1.91328 2.5205 + vertex 1.55443 1.91478 2.52108 + vertex 1.55594 1.90973 2.5218 + endloop + endfacet + facet normal 0.133042 0.259887 0.95643 + outer loop + vertex 1.55949 1.97446 2.50621 + vertex 1.55803 1.97909 2.50516 + vertex 1.55595 1.97551 2.50642 + endloop + endfacet + facet normal 0.105322 0.161646 0.981213 + outer loop + vertex 1.55595 1.97551 2.50642 + vertex 1.55563 1.9712 2.50717 + vertex 1.55949 1.97446 2.50621 + endloop + endfacet + facet normal -0.162952 0.17949 0.97017 + outer loop + vertex 1.55595 1.97551 2.50642 + vertex 1.55325 1.97446 2.50616 + vertex 1.55563 1.9712 2.50717 + endloop + endfacet + facet normal 0.0157265 0.324578 0.945728 + outer loop + vertex 1.55438 1.97793 2.50562 + vertex 1.55595 1.97551 2.50642 + vertex 1.55803 1.97909 2.50516 + endloop + endfacet + facet normal 0.0136582 0.33032 0.94377 + outer loop + vertex 1.55438 1.97793 2.50562 + vertex 1.55803 1.97909 2.50516 + vertex 1.55389 1.98258 2.504 + endloop + endfacet + facet normal -0.173326 0.207889 0.962673 + outer loop + vertex 1.55595 1.97551 2.50642 + vertex 1.55438 1.97793 2.50562 + vertex 1.55325 1.97446 2.50616 + endloop + endfacet + facet normal 0.184198 0.582962 0.791345 + outer loop + vertex 1.55893 2.10478 2.46614 + vertex 1.556 2.10785 2.46456 + vertex 1.55505 2.10557 2.46646 + endloop + endfacet + facet normal 0.166664 0.466121 0.868881 + outer loop + vertex 1.55505 2.10557 2.46646 + vertex 1.55584 2.10215 2.46814 + vertex 1.55893 2.10478 2.46614 + endloop + endfacet + facet normal 0.152677 0.464571 0.872275 + outer loop + vertex 1.55505 2.10557 2.46646 + vertex 1.55128 2.10491 2.46747 + vertex 1.55584 2.10215 2.46814 + endloop + endfacet + facet normal 0.152965 0.464982 0.872006 + outer loop + vertex 1.55128 2.10491 2.46747 + vertex 1.55214 2.10203 2.46886 + vertex 1.55584 2.10215 2.46814 + endloop + endfacet + facet normal 0.173709 0.58689 0.790813 + outer loop + vertex 1.55258 2.10756 2.46553 + vertex 1.55505 2.10557 2.46646 + vertex 1.556 2.10785 2.46456 + endloop + endfacet + facet normal 0.148123 0.671834 0.72574 + outer loop + vertex 1.55258 2.10756 2.46553 + vertex 1.556 2.10785 2.46456 + vertex 1.55163 2.1103 2.46318 + endloop + endfacet + facet normal 0.179682 0.705435 0.685621 + outer loop + vertex 1.55163 2.1103 2.46318 + vertex 1.556 2.10785 2.46456 + vertex 1.5565 2.1103 2.4619 + endloop + endfacet + facet normal 0.1266 0.545741 0.828335 + outer loop + vertex 1.55505 2.10557 2.46646 + vertex 1.55258 2.10756 2.46553 + vertex 1.55128 2.10491 2.46747 + endloop + endfacet + facet normal 0.0444811 0.745499 0.665021 + outer loop + vertex 1.55957 2.11555 2.45235 + vertex 1.5575 2.1176 2.45019 + vertex 1.55469 2.11613 2.45203 + endloop + endfacet + facet normal 0.177451 0.886951 0.426415 + outer loop + vertex 1.55469 2.11613 2.45203 + vertex 1.55053 2.11629 2.45343 + vertex 1.5545 2.11444 2.45562 + endloop + endfacet + facet normal 0.0784021 0.900598 0.427524 + outer loop + vertex 1.55469 2.11613 2.45203 + vertex 1.5545 2.11444 2.45562 + vertex 1.55957 2.11555 2.45235 + endloop + endfacet + facet normal 0.164409 0.827913 0.536218 + outer loop + vertex 1.55957 2.11555 2.45235 + vertex 1.5545 2.11444 2.45562 + vertex 1.55823 2.11369 2.45565 + endloop + endfacet + facet normal 0.174079 0.873399 0.45483 + outer loop + vertex 1.55823 2.11369 2.45565 + vertex 1.5545 2.11444 2.45562 + vertex 1.55782 2.11225 2.45856 + endloop + endfacet + facet normal 0.173834 0.87333 0.455056 + outer loop + vertex 1.55782 2.11225 2.45856 + vertex 1.5545 2.11444 2.45562 + vertex 1.5529 2.11262 2.45973 + endloop + endfacet + facet normal 0.154389 0.792626 0.589837 + outer loop + vertex 1.5565 2.1103 2.4619 + vertex 1.5529 2.11262 2.45973 + vertex 1.55163 2.1103 2.46318 + endloop + endfacet + facet normal 0.1918 0.813166 0.549522 + outer loop + vertex 1.55782 2.11225 2.45856 + vertex 1.5529 2.11262 2.45973 + vertex 1.5565 2.1103 2.4619 + endloop + endfacet + facet normal 0.131714 0.66597 0.734258 + outer loop + vertex 1.5575 2.1176 2.45019 + vertex 1.55292 2.11845 2.45025 + vertex 1.55469 2.11613 2.45203 + endloop + endfacet + facet normal 0.0185715 0.0366477 0.999156 + outer loop + vertex 1.5575 2.1176 2.45019 + vertex 1.56 2.12157 2.45 + vertex 1.55292 2.11845 2.45025 + endloop + endfacet + facet normal 0.00521343 0.0668706 0.997748 + outer loop + vertex 1.56 2.12157 2.45 + vertex 1.555 2.12196 2.45 + vertex 1.55292 2.11845 2.45025 + endloop + endfacet + facet normal 0.250385 0.703443 0.665188 + outer loop + vertex 1.55469 2.11613 2.45203 + vertex 1.55292 2.11845 2.45025 + vertex 1.55053 2.11629 2.45343 + endloop + endfacet + facet normal -0.35675 0.908167 -0.219001 + outer loop + vertex 1.56 0.913154 2.45 + vertex 1.565 0.915 2.44951 + vertex 1.56283 0.91394 2.44866 + endloop + endfacet + facet normal 0.178064 -0.672871 -0.718009 + outer loop + vertex 1.56 0.915 2.44827 + vertex 1.565 0.915 2.44951 + vertex 1.56 0.913154 2.45 + endloop + endfacet + facet normal 0.451452 -0.111065 0.885356 + outer loop + vertex 1.56283 0.91394 2.44866 + vertex 1.56015 0.913911 2.45002 + vertex 1.56 0.913154 2.45 + endloop + endfacet + facet normal 0.158142 -0.943729 0.290458 + outer loop + vertex 1.5645 0.914395 2.44923 + vertex 1.56015 0.913911 2.45002 + vertex 1.56283 0.91394 2.44866 + endloop + endfacet + facet normal 0.169238 -0.913599 0.369724 + outer loop + vertex 1.56015 0.913911 2.45002 + vertex 1.5645 0.914395 2.44923 + vertex 1.56361 0.915281 2.45182 + endloop + endfacet + facet normal 0.167498 -0.912807 0.372463 + outer loop + vertex 1.55737 0.914818 2.45349 + vertex 1.56015 0.913911 2.45002 + vertex 1.56361 0.915281 2.45182 + endloop + endfacet + facet normal 0.181755 -0.882323 0.434133 + outer loop + vertex 1.56361 0.915281 2.45182 + vertex 1.56096 0.916751 2.45592 + vertex 1.55737 0.914818 2.45349 + endloop + endfacet + facet normal 0.164316 -0.875468 0.454484 + outer loop + vertex 1.56096 0.916751 2.45592 + vertex 1.55606 0.91669 2.45757 + vertex 1.55737 0.914818 2.45349 + endloop + endfacet + facet normal 0.182165 -0.841499 0.508621 + outer loop + vertex 1.56096 0.916751 2.45592 + vertex 1.55911 0.918386 2.45928 + vertex 1.55606 0.91669 2.45757 + endloop + endfacet + facet normal 0.154766 -0.852677 0.498988 + outer loop + vertex 1.56375 0.918709 2.4584 + vertex 1.55911 0.918386 2.45928 + vertex 1.56096 0.916751 2.45592 + endloop + endfacet + facet normal 0.168402 -0.78613 0.594676 + outer loop + vertex 1.55911 0.918386 2.45928 + vertex 1.56375 0.918709 2.4584 + vertex 1.56143 0.920492 2.46141 + endloop + endfacet + facet normal 0.158802 -0.782714 0.601782 + outer loop + vertex 1.55751 0.919812 2.46156 + vertex 1.55911 0.918386 2.45928 + vertex 1.56143 0.920492 2.46141 + endloop + endfacet + facet normal 0.14765 -0.695422 0.70327 + outer loop + vertex 1.56143 0.920492 2.46141 + vertex 1.55801 0.922346 2.46396 + vertex 1.55751 0.919812 2.46156 + endloop + endfacet + facet normal 0.129308 -0.711699 0.690481 + outer loop + vertex 1.56369 0.923203 2.46378 + vertex 1.55801 0.922346 2.46396 + vertex 1.56143 0.920492 2.46141 + endloop + endfacet + facet normal 0.116569 -0.607201 0.785951 + outer loop + vertex 1.55801 0.922346 2.46396 + vertex 1.56369 0.923203 2.46378 + vertex 1.5611 0.925877 2.46623 + endloop + endfacet + facet normal 0.112488 -0.605067 0.788188 + outer loop + vertex 1.55597 0.925386 2.46659 + vertex 1.55801 0.922346 2.46396 + vertex 1.5611 0.925877 2.46623 + endloop + endfacet + facet normal 0.107568 -0.504098 0.856921 + outer loop + vertex 1.5611 0.925877 2.46623 + vertex 1.55896 0.928968 2.46832 + vertex 1.55597 0.925386 2.46659 + endloop + endfacet + facet normal 0.110441 -0.5025 0.857494 + outer loop + vertex 1.56419 0.929549 2.46799 + vertex 1.55896 0.928968 2.46832 + vertex 1.5611 0.925877 2.46623 + endloop + endfacet + facet normal 0.193846 0.20081 0.96026 + outer loop + vertex 1.56042 1.91023 2.52079 + vertex 1.55594 1.90973 2.5218 + vertex 1.56052 1.90543 2.52177 + endloop + endfacet + facet normal 0.176613 0.196648 0.964436 + outer loop + vertex 1.55861 1.91328 2.5205 + vertex 1.56042 1.91023 2.52079 + vertex 1.56358 1.91345 2.51955 + endloop + endfacet + facet normal 0.193061 0.205945 0.95933 + outer loop + vertex 1.56042 1.91023 2.52079 + vertex 1.55861 1.91328 2.5205 + vertex 1.55594 1.90973 2.5218 + endloop + endfacet + facet normal 0.167718 0.269003 0.948424 + outer loop + vertex 1.55803 1.97909 2.50516 + vertex 1.55949 1.97446 2.50621 + vertex 1.56359 1.9774 2.50466 + endloop + endfacet + facet normal 0.0769531 0.194256 0.977928 + outer loop + vertex 1.56098 1.96974 2.50703 + vertex 1.55949 1.97446 2.50621 + vertex 1.55563 1.9712 2.50717 + endloop + endfacet + facet normal 0.182869 0.593814 0.783546 + outer loop + vertex 1.55893 2.10478 2.46614 + vertex 1.56381 2.10379 2.46575 + vertex 1.56092 2.1076 2.46354 + endloop + endfacet + facet normal 0.19301 0.588273 0.785291 + outer loop + vertex 1.556 2.10785 2.46456 + vertex 1.55893 2.10478 2.46614 + vertex 1.56092 2.1076 2.46354 + endloop + endfacet + facet normal 0.16006 0.472305 0.866781 + outer loop + vertex 1.56124 2.10103 2.46775 + vertex 1.55893 2.10478 2.46614 + vertex 1.55584 2.10215 2.46814 + endloop + endfacet + facet normal 0.165271 0.474562 0.864567 + outer loop + vertex 1.56381 2.10379 2.46575 + vertex 1.55893 2.10478 2.46614 + vertex 1.56124 2.10103 2.46775 + endloop + endfacet + facet normal 0.209952 0.80314 0.557572 + outer loop + vertex 1.56396 2.10921 2.46102 + vertex 1.56168 2.11115 2.4591 + vertex 1.56008 2.11024 2.46101 + endloop + endfacet + facet normal 0.184914 0.709733 0.679769 + outer loop + vertex 1.56008 2.11024 2.46101 + vertex 1.56092 2.1076 2.46354 + vertex 1.56396 2.10921 2.46102 + endloop + endfacet + facet normal 0.182488 0.709662 0.680499 + outer loop + vertex 1.56008 2.11024 2.46101 + vertex 1.5565 2.1103 2.4619 + vertex 1.56092 2.1076 2.46354 + endloop + endfacet + facet normal 0.178195 0.705779 0.685655 + outer loop + vertex 1.5565 2.1103 2.4619 + vertex 1.556 2.10785 2.46456 + vertex 1.56092 2.1076 2.46354 + endloop + endfacet + facet normal -0.21594 0.596541 0.772987 + outer loop + vertex 1.56343 2.12 2.45 + vertex 1.5575 2.1176 2.45019 + vertex 1.55957 2.11555 2.45235 + endloop + endfacet + facet normal 0.197312 0.31942 0.926843 + outer loop + vertex 1.56343 2.12 2.45 + vertex 1.55957 2.11555 2.45235 + vertex 1.565 2.11903 2.45 + endloop + endfacet + facet normal 0.105039 0.439819 0.891923 + outer loop + vertex 1.565 2.11903 2.45 + vertex 1.55957 2.11555 2.45235 + vertex 1.56394 2.11436 2.45243 + endloop + endfacet + facet normal 0.216538 0.828146 0.516996 + outer loop + vertex 1.56394 2.11436 2.45243 + vertex 1.55957 2.11555 2.45235 + vertex 1.56179 2.11278 2.45586 + endloop + endfacet + facet normal 0.176548 0.823737 0.538784 + outer loop + vertex 1.56179 2.11278 2.45586 + vertex 1.55957 2.11555 2.45235 + vertex 1.55823 2.11369 2.45565 + endloop + endfacet + facet normal 0.163487 0.830861 0.531922 + outer loop + vertex 1.56168 2.11115 2.4591 + vertex 1.55782 2.11225 2.45856 + vertex 1.56008 2.11024 2.46101 + endloop + endfacet + facet normal 0.187558 0.874067 0.448139 + outer loop + vertex 1.56168 2.11115 2.4591 + vertex 1.56179 2.11278 2.45586 + vertex 1.55782 2.11225 2.45856 + endloop + endfacet + facet normal 0.193176 0.869067 0.455419 + outer loop + vertex 1.56179 2.11278 2.45586 + vertex 1.55823 2.11369 2.45565 + vertex 1.55782 2.11225 2.45856 + endloop + endfacet + facet normal 0.150096 0.827292 0.541349 + outer loop + vertex 1.56008 2.11024 2.46101 + vertex 1.55782 2.11225 2.45856 + vertex 1.5565 2.1103 2.4619 + endloop + endfacet + facet normal 0.0171788 0.0375254 0.999148 + outer loop + vertex 1.56343 2.12 2.45 + vertex 1.56 2.12157 2.45 + vertex 1.5575 2.1176 2.45019 + endloop + endfacet + facet normal 0.104311 0.484363 -0.868626 + outer loop + vertex 1.56908 0.915 2.45 + vertex 1.56283 0.91394 2.44866 + vertex 1.565 0.915 2.44951 + endloop + endfacet + facet normal -0.00443394 -0.77465 0.632375 + outer loop + vertex 1.56908 0.915 2.45 + vertex 1.5645 0.914395 2.44923 + vertex 1.56283 0.91394 2.44866 + endloop + endfacet + facet normal -0.17011 0.948632 0.266759 + outer loop + vertex 1.5645 0.914395 2.44923 + vertex 1.56908 0.915 2.45 + vertex 1.57 0.915165 2.45 + endloop + endfacet + facet normal 0.0819436 -0.934326 0.346872 + outer loop + vertex 1.5645 0.914395 2.44923 + vertex 1.57 0.915165 2.45 + vertex 1.56361 0.915281 2.45182 + endloop + endfacet + facet normal 0.137385 -0.833578 0.535045 + outer loop + vertex 1.56361 0.915281 2.45182 + vertex 1.57 0.915165 2.45 + vertex 1.56759 0.915884 2.45174 + endloop + endfacet + facet normal 0.144004 -0.891971 0.428544 + outer loop + vertex 1.56759 0.915884 2.45174 + vertex 1.5664 0.917108 2.45469 + vertex 1.56361 0.915281 2.45182 + endloop + endfacet + facet normal 0.153845 -0.89421 0.42038 + outer loop + vertex 1.5664 0.917108 2.45469 + vertex 1.56096 0.916751 2.45592 + vertex 1.56361 0.915281 2.45182 + endloop + endfacet + facet normal 0.166766 -0.856487 0.488487 + outer loop + vertex 1.5664 0.917108 2.45469 + vertex 1.56375 0.918709 2.4584 + vertex 1.56096 0.916751 2.45592 + endloop + endfacet + facet normal 0.141501 -0.868232 0.475553 + outer loop + vertex 1.56793 0.918961 2.45761 + vertex 1.56375 0.918709 2.4584 + vertex 1.5664 0.917108 2.45469 + endloop + endfacet + facet normal 0.15514 -0.808812 0.567234 + outer loop + vertex 1.56375 0.918709 2.4584 + vertex 1.56793 0.918961 2.45761 + vertex 1.56701 0.920982 2.46075 + endloop + endfacet + facet normal 0.139618 -0.801431 0.581563 + outer loop + vertex 1.56143 0.920492 2.46141 + vertex 1.56375 0.918709 2.4584 + vertex 1.56701 0.920982 2.46075 + endloop + endfacet + facet normal 0.144143 -0.716798 0.68222 + outer loop + vertex 1.56701 0.920982 2.46075 + vertex 1.56369 0.923203 2.46378 + vertex 1.56143 0.920492 2.46141 + endloop + endfacet + facet normal 0.120776 -0.733482 0.668893 + outer loop + vertex 1.56873 0.923835 2.46357 + vertex 1.56369 0.923203 2.46378 + vertex 1.56701 0.920982 2.46075 + endloop + endfacet + facet normal 0.110745 -0.614606 0.781022 + outer loop + vertex 1.56369 0.923203 2.46378 + vertex 1.56873 0.923835 2.46357 + vertex 1.56625 0.926386 2.46592 + endloop + endfacet + facet normal 0.107437 -0.613065 0.782693 + outer loop + vertex 1.5611 0.925877 2.46623 + vertex 1.56369 0.923203 2.46378 + vertex 1.56625 0.926386 2.46592 + endloop + endfacet + facet normal 0.100696 -0.49653 0.862159 + outer loop + vertex 1.56625 0.926386 2.46592 + vertex 1.56419 0.929549 2.46799 + vertex 1.5611 0.925877 2.46623 + endloop + endfacet + facet normal 0.117067 -0.487758 0.865094 + outer loop + vertex 1.56927 0.929984 2.46755 + vertex 1.56419 0.929549 2.46799 + vertex 1.56625 0.926386 2.46592 + endloop + endfacet + facet normal 0.129957 -0.402279 0.906247 + outer loop + vertex 1.56419 0.929549 2.46799 + vertex 1.56778 0.933937 2.46942 + vertex 1.56229 0.932774 2.46969 + endloop + endfacet + facet normal 0.0553131 -0.0759367 0.995577 + outer loop + vertex 1.56243 1.37762 2.5591 + vertex 1.56758 1.38275 2.55921 + vertex 1.56236 1.38263 2.55949 + endloop + endfacet + facet normal 0.0552844 -0.074406 0.995694 + outer loop + vertex 1.56758 1.38275 2.55921 + vertex 1.56739 1.38782 2.5596 + vertex 1.56236 1.38263 2.55949 + endloop + endfacet + facet normal 0.0542704 -0.0734265 0.995823 + outer loop + vertex 1.56236 1.38263 2.55949 + vertex 1.56739 1.38782 2.5596 + vertex 1.56213 1.38766 2.55987 + endloop + endfacet + facet normal 0.0547142 -0.0898006 0.994456 + outer loop + vertex 1.56739 1.38782 2.5596 + vertex 1.5668 1.39359 2.56015 + vertex 1.56213 1.38766 2.55987 + endloop + endfacet + facet normal 0.029725 -0.0702547 0.997086 + outer loop + vertex 1.56213 1.38766 2.55987 + vertex 1.5668 1.39359 2.56015 + vertex 1.56138 1.39174 2.56018 + endloop + endfacet + facet normal -0.031129 -0.0626486 0.99755 + outer loop + vertex 1.56643 1.39734 2.56065 + vertex 1.56556 1.4006 2.56083 + vertex 1.56274 1.39668 2.56049 + endloop + endfacet + facet normal -0.0180332 -0.133554 0.990877 + outer loop + vertex 1.56643 1.39734 2.56065 + vertex 1.56274 1.39668 2.56049 + vertex 1.5668 1.39359 2.56015 + endloop + endfacet + facet normal 0.0300038 -0.0710712 0.99702 + outer loop + vertex 1.5668 1.39359 2.56015 + vertex 1.56274 1.39668 2.56049 + vertex 1.56138 1.39174 2.56018 + endloop + endfacet + facet normal -0.0421152 -0.0655593 0.99696 + outer loop + vertex 1.56643 1.39734 2.56065 + vertex 1.568 1.39967 2.56087 + vertex 1.56556 1.4006 2.56083 + endloop + endfacet + facet normal -0.0571423 -0.0439824 0.997397 + outer loop + vertex 1.56204 1.40239 2.56071 + vertex 1.56274 1.39668 2.56049 + vertex 1.56556 1.4006 2.56083 + endloop + endfacet + facet normal -0.0507587 -0.0313673 0.998218 + outer loop + vertex 1.56533 1.40532 2.56096 + vertex 1.56204 1.40239 2.56071 + vertex 1.56556 1.4006 2.56083 + endloop + endfacet + facet normal -0.035155 -0.0306528 0.998912 + outer loop + vertex 1.56556 1.4006 2.56083 + vertex 1.56855 1.40361 2.56103 + vertex 1.56533 1.40532 2.56096 + endloop + endfacet + facet normal -0.0305728 -0.0352253 0.998912 + outer loop + vertex 1.568 1.39967 2.56087 + vertex 1.56855 1.40361 2.56103 + vertex 1.56556 1.4006 2.56083 + endloop + endfacet + facet normal -0.0556375 -0.0258898 0.998115 + outer loop + vertex 1.5626 1.40739 2.56087 + vertex 1.56204 1.40239 2.56071 + vertex 1.56533 1.40532 2.56096 + endloop + endfacet + facet normal -0.0601942 -0.0319423 0.997675 + outer loop + vertex 1.56503 1.40987 2.56109 + vertex 1.5626 1.40739 2.56087 + vertex 1.56533 1.40532 2.56096 + endloop + endfacet + facet normal -0.0397093 -0.0305993 0.998743 + outer loop + vertex 1.56533 1.40532 2.56096 + vertex 1.56802 1.40866 2.56117 + vertex 1.56503 1.40987 2.56109 + endloop + endfacet + facet normal -0.0365039 -0.033184 0.998782 + outer loop + vertex 1.56855 1.40361 2.56103 + vertex 1.56802 1.40866 2.56117 + vertex 1.56533 1.40532 2.56096 + endloop + endfacet + facet normal -0.0543376 -0.0376849 0.997811 + outer loop + vertex 1.5628 1.41072 2.561 + vertex 1.5626 1.40739 2.56087 + vertex 1.56503 1.40987 2.56109 + endloop + endfacet + facet normal -0.0625607 -0.0594089 0.996271 + outer loop + vertex 1.56407 1.41299 2.56122 + vertex 1.5628 1.41072 2.561 + vertex 1.56503 1.40987 2.56109 + endloop + endfacet + facet normal -0.02998 -0.0494802 0.998325 + outer loop + vertex 1.56503 1.40987 2.56109 + vertex 1.56725 1.41389 2.56136 + vertex 1.56407 1.41299 2.56122 + endloop + endfacet + facet normal -0.0441588 -0.0416305 0.998157 + outer loop + vertex 1.56802 1.40866 2.56117 + vertex 1.56725 1.41389 2.56136 + vertex 1.56503 1.40987 2.56109 + endloop + endfacet + facet normal -0.00527656 -0.091189 0.99582 + outer loop + vertex 1.5628 1.41072 2.561 + vertex 1.56407 1.41299 2.56122 + vertex 1.56176 1.41278 2.56119 + endloop + endfacet + facet normal -0.00524875 -0.0914911 0.995792 + outer loop + vertex 1.56407 1.41299 2.56122 + vertex 1.56343 1.41695 2.56158 + vertex 1.56176 1.41278 2.56119 + endloop + endfacet + facet normal -0.0174623 -0.0934402 0.995472 + outer loop + vertex 1.56407 1.41299 2.56122 + vertex 1.56725 1.41389 2.56136 + vertex 1.56343 1.41695 2.56158 + endloop + endfacet + facet normal 0.0149809 -0.0531063 0.998476 + outer loop + vertex 1.56725 1.41389 2.56136 + vertex 1.56815 1.41878 2.5616 + vertex 1.56343 1.41695 2.56158 + endloop + endfacet + facet normal 0.0142235 -0.0511437 0.99859 + outer loop + vertex 1.56815 1.41878 2.5616 + vertex 1.56746 1.42281 2.56182 + vertex 1.56343 1.41695 2.56158 + endloop + endfacet + facet normal 0.0348392 -0.0652941 0.997258 + outer loop + vertex 1.56343 1.41695 2.56158 + vertex 1.56746 1.42281 2.56182 + vertex 1.56278 1.42285 2.56199 + endloop + endfacet + facet normal 0.035062 -0.0443399 0.998401 + outer loop + vertex 1.56746 1.42281 2.56182 + vertex 1.56731 1.42782 2.56205 + vertex 1.56278 1.42285 2.56199 + endloop + endfacet + facet normal 0.0413291 -0.0500564 0.997891 + outer loop + vertex 1.56278 1.42285 2.56199 + vertex 1.56731 1.42782 2.56205 + vertex 1.56265 1.42799 2.56225 + endloop + endfacet + facet normal 0.0417577 -0.038952 0.998368 + outer loop + vertex 1.56731 1.42782 2.56205 + vertex 1.56736 1.43282 2.56224 + vertex 1.56265 1.42799 2.56225 + endloop + endfacet + facet normal 0.166958 0.178229 0.969721 + outer loop + vertex 1.56406 1.85927 2.53028 + vertex 1.56473 1.85473 2.531 + vertex 1.56906 1.85764 2.52972 + endloop + endfacet + facet normal 0.156097 0.25675 0.953789 + outer loop + vertex 1.56212 2.00186 2.49813 + vertex 1.56608 2.00451 2.49677 + vertex 1.56051 2.00645 2.49715 + endloop + endfacet + facet normal 0.156751 0.261646 0.95235 + outer loop + vertex 1.56445 2.00928 2.49575 + vertex 1.56848 2.00784 2.49549 + vertex 1.56836 2.01216 2.49432 + endloop + endfacet + facet normal 0.155913 0.256185 0.953971 + outer loop + vertex 1.56608 2.00451 2.49677 + vertex 1.56445 2.00928 2.49575 + vertex 1.56051 2.00645 2.49715 + endloop + endfacet + facet normal 0.154804 0.255863 0.954238 + outer loop + vertex 1.56848 2.00784 2.49549 + vertex 1.56445 2.00928 2.49575 + vertex 1.56608 2.00451 2.49677 + endloop + endfacet + facet normal 0.184521 0.590026 0.786016 + outer loop + vertex 1.56381 2.10379 2.46575 + vertex 1.56776 2.10276 2.4656 + vertex 1.567 2.10597 2.46336 + endloop + endfacet + facet normal 0.181248 0.593111 0.784454 + outer loop + vertex 1.56092 2.1076 2.46354 + vertex 1.56381 2.10379 2.46575 + vertex 1.567 2.10597 2.46336 + endloop + endfacet + facet normal 0.167893 0.472554 0.865162 + outer loop + vertex 1.56626 2.09992 2.46739 + vertex 1.56381 2.10379 2.46575 + vertex 1.56124 2.10103 2.46775 + endloop + endfacet + facet normal 0.155624 0.467007 0.870452 + outer loop + vertex 1.56776 2.10276 2.4656 + vertex 1.56381 2.10379 2.46575 + vertex 1.56626 2.09992 2.46739 + endloop + endfacet + facet normal 0.206404 0.813684 0.54343 + outer loop + vertex 1.56396 2.10921 2.46102 + vertex 1.56914 2.10865 2.4599 + vertex 1.56536 2.11084 2.45806 + endloop + endfacet + facet normal 0.22202 0.807047 0.547159 + outer loop + vertex 1.56168 2.11115 2.4591 + vertex 1.56396 2.10921 2.46102 + vertex 1.56536 2.11084 2.45806 + endloop + endfacet + facet normal 0.205023 0.691653 0.692519 + outer loop + vertex 1.567 2.10597 2.46336 + vertex 1.56396 2.10921 2.46102 + vertex 1.56092 2.1076 2.46354 + endloop + endfacet + facet normal 0.223534 0.699244 0.679037 + outer loop + vertex 1.56914 2.10865 2.4599 + vertex 1.56396 2.10921 2.46102 + vertex 1.567 2.10597 2.46336 + endloop + endfacet + facet normal 0.101441 0.286553 0.952679 + outer loop + vertex 1.57 2.11726 2.45 + vertex 1.565 2.11903 2.45 + vertex 1.56724 2.11459 2.4511 + endloop + endfacet + facet normal 0.323662 0.37765 0.867538 + outer loop + vertex 1.56724 2.11459 2.4511 + vertex 1.565 2.11903 2.45 + vertex 1.56394 2.11436 2.45243 + endloop + endfacet + facet normal 0.173956 0.803071 0.569926 + outer loop + vertex 1.56724 2.11459 2.4511 + vertex 1.56394 2.11436 2.45243 + vertex 1.56703 2.11233 2.45435 + endloop + endfacet + facet normal 0.221027 0.825856 0.518757 + outer loop + vertex 1.56703 2.11233 2.45435 + vertex 1.56394 2.11436 2.45243 + vertex 1.56179 2.11278 2.45586 + endloop + endfacet + facet normal 0.199209 0.871854 0.447422 + outer loop + vertex 1.56536 2.11084 2.45806 + vertex 1.56179 2.11278 2.45586 + vertex 1.56168 2.11115 2.4591 + endloop + endfacet + facet normal 0.203173 0.873491 0.442418 + outer loop + vertex 1.56703 2.11233 2.45435 + vertex 1.56179 2.11278 2.45586 + vertex 1.56536 2.11084 2.45806 + endloop + endfacet + facet normal 0.143341 -0.837287 0.527641 + outer loop + vertex 1.575 0.916021 2.45 + vertex 1.57127 0.916646 2.452 + vertex 1.57 0.915165 2.45 + endloop + endfacet + facet normal 0.134607 -0.83588 0.532151 + outer loop + vertex 1.57127 0.916646 2.452 + vertex 1.56759 0.915884 2.45174 + vertex 1.57 0.915165 2.45 + endloop + endfacet + facet normal 0.174928 -0.880855 0.43988 + outer loop + vertex 1.57038 0.918172 2.45541 + vertex 1.57127 0.916646 2.452 + vertex 1.57435 0.918382 2.45426 + endloop + endfacet + facet normal 0.156707 -0.885594 0.437226 + outer loop + vertex 1.57038 0.918172 2.45541 + vertex 1.5664 0.917108 2.45469 + vertex 1.57127 0.916646 2.452 + endloop + endfacet + facet normal 0.15296 -0.889269 0.43105 + outer loop + vertex 1.5664 0.917108 2.45469 + vertex 1.56759 0.915884 2.45174 + vertex 1.57127 0.916646 2.452 + endloop + endfacet + facet normal 0.145509 -0.868594 0.473679 + outer loop + vertex 1.57038 0.918172 2.45541 + vertex 1.56793 0.918961 2.45761 + vertex 1.5664 0.917108 2.45469 + endloop + endfacet + facet normal 0.188518 -0.849896 0.492075 + outer loop + vertex 1.57435 0.918382 2.45426 + vertex 1.57212 0.920138 2.45814 + vertex 1.57038 0.918172 2.45541 + endloop + endfacet + facet normal 0.175208 -0.848417 0.499491 + outer loop + vertex 1.56793 0.918961 2.45761 + vertex 1.57038 0.918172 2.45541 + vertex 1.57212 0.920138 2.45814 + endloop + endfacet + facet normal 0.15544 -0.80873 0.567269 + outer loop + vertex 1.56793 0.918961 2.45761 + vertex 1.57212 0.920138 2.45814 + vertex 1.56701 0.920982 2.46075 + endloop + endfacet + facet normal 0.15506 -0.809215 0.56668 + outer loop + vertex 1.56701 0.920982 2.46075 + vertex 1.57212 0.920138 2.45814 + vertex 1.57144 0.922243 2.46134 + endloop + endfacet + facet normal 0.119784 -0.733279 0.669294 + outer loop + vertex 1.57144 0.922243 2.46134 + vertex 1.56873 0.923835 2.46357 + vertex 1.56701 0.920982 2.46075 + endloop + endfacet + facet normal 0.139496 -0.717772 0.682161 + outer loop + vertex 1.57317 0.924406 2.46326 + vertex 1.56873 0.923835 2.46357 + vertex 1.57144 0.922243 2.46134 + endloop + endfacet + facet normal 0.132834 -0.615517 0.776849 + outer loop + vertex 1.56873 0.923835 2.46357 + vertex 1.57317 0.924406 2.46326 + vertex 1.57103 0.926795 2.46552 + endloop + endfacet + facet normal 0.118894 -0.609372 0.783919 + outer loop + vertex 1.56625 0.926386 2.46592 + vertex 1.56873 0.923835 2.46357 + vertex 1.57103 0.926795 2.46552 + endloop + endfacet + facet normal 0.115337 -0.486685 0.86593 + outer loop + vertex 1.57103 0.926795 2.46552 + vertex 1.56927 0.929984 2.46755 + vertex 1.56625 0.926386 2.46592 + endloop + endfacet + facet normal 0.130246 -0.479626 0.867753 + outer loop + vertex 1.57398 0.930218 2.46697 + vertex 1.56927 0.929984 2.46755 + vertex 1.57103 0.926795 2.46552 + endloop + endfacet + facet normal 0.131168 -0.380887 0.91527 + outer loop + vertex 1.57398 0.930218 2.46697 + vertex 1.57298 0.933977 2.46867 + vertex 1.56927 0.929984 2.46755 + endloop + endfacet + facet normal 0.0905276 -0.166103 0.981944 + outer loop + vertex 1.57324 1.17832 2.53155 + vertex 1.5726 1.18315 2.53243 + vertex 1.5676 1.17829 2.53207 + endloop + endfacet + facet normal 0.0839147 -0.159438 0.983635 + outer loop + vertex 1.5676 1.17829 2.53207 + vertex 1.5726 1.18315 2.53243 + vertex 1.56739 1.18315 2.53287 + endloop + endfacet + facet normal 0.0478883 -0.116266 0.992063 + outer loop + vertex 1.56778 1.30788 2.55219 + vertex 1.57253 1.31296 2.55255 + vertex 1.56748 1.31284 2.55278 + endloop + endfacet + facet normal 0.0476589 -0.103713 0.993465 + outer loop + vertex 1.57253 1.31296 2.55255 + vertex 1.57257 1.31798 2.55308 + vertex 1.56748 1.31284 2.55278 + endloop + endfacet + facet normal 0.0503944 -0.106404 0.993045 + outer loop + vertex 1.56748 1.31284 2.55278 + vertex 1.57257 1.31798 2.55308 + vertex 1.56751 1.31782 2.55332 + endloop + endfacet + facet normal 0.0501767 -0.0977103 0.993949 + outer loop + vertex 1.57257 1.31798 2.55308 + vertex 1.57269 1.32299 2.55356 + vertex 1.56751 1.31782 2.55332 + endloop + endfacet + facet normal 0.0510534 -0.0985833 0.993818 + outer loop + vertex 1.56751 1.31782 2.55332 + vertex 1.57269 1.32299 2.55356 + vertex 1.56754 1.32282 2.55381 + endloop + endfacet + facet normal 0.0510592 -0.0987887 0.993798 + outer loop + vertex 1.57269 1.32299 2.55356 + vertex 1.57258 1.32807 2.55407 + vertex 1.56754 1.32282 2.55381 + endloop + endfacet + facet normal 0.052191 -0.0998671 0.993631 + outer loop + vertex 1.56754 1.32282 2.55381 + vertex 1.57258 1.32807 2.55407 + vertex 1.5673 1.32775 2.55432 + endloop + endfacet + facet normal 0.0535189 -0.123503 0.9909 + outer loop + vertex 1.57258 1.32807 2.55407 + vertex 1.57192 1.3338 2.55482 + vertex 1.5673 1.32775 2.55432 + endloop + endfacet + facet normal 0.0283316 -0.104545 0.994116 + outer loop + vertex 1.5673 1.32775 2.55432 + vertex 1.57192 1.3338 2.55482 + vertex 1.56645 1.33161 2.55475 + endloop + endfacet + facet normal -0.0253205 -0.116449 0.992874 + outer loop + vertex 1.57135 1.33754 2.55552 + vertex 1.56996 1.34024 2.55581 + vertex 1.56753 1.3363 2.55528 + endloop + endfacet + facet normal -0.00272008 -0.18451 0.982827 + outer loop + vertex 1.57135 1.33754 2.55552 + vertex 1.56753 1.3363 2.55528 + vertex 1.57192 1.3338 2.55482 + endloop + endfacet + facet normal 0.0347412 -0.12054 0.9921 + outer loop + vertex 1.57192 1.3338 2.55482 + vertex 1.56753 1.3363 2.55528 + vertex 1.56645 1.33161 2.55475 + endloop + endfacet + facet normal -0.0124937 -0.109971 0.993856 + outer loop + vertex 1.57135 1.33754 2.55552 + vertex 1.5726 1.34003 2.55582 + vertex 1.56996 1.34024 2.55581 + endloop + endfacet + facet normal -0.0490103 -0.101891 0.993588 + outer loop + vertex 1.56638 1.34073 2.55568 + vertex 1.56753 1.3363 2.55528 + vertex 1.56996 1.34024 2.55581 + endloop + endfacet + facet normal -0.0468473 -0.0855022 0.995236 + outer loop + vertex 1.56875 1.34344 2.55602 + vertex 1.56638 1.34073 2.55568 + vertex 1.56996 1.34024 2.55581 + endloop + endfacet + facet normal -0.00917825 -0.071354 0.997409 + outer loop + vertex 1.56996 1.34024 2.55581 + vertex 1.5721 1.34377 2.55608 + vertex 1.56875 1.34344 2.55602 + endloop + endfacet + facet normal -0.00943303 -0.0712001 0.997417 + outer loop + vertex 1.5726 1.34003 2.55582 + vertex 1.5721 1.34377 2.55608 + vertex 1.56996 1.34024 2.55581 + endloop + endfacet + facet normal -0.0391596 -0.0921848 0.994972 + outer loop + vertex 1.56638 1.34073 2.55568 + vertex 1.56875 1.34344 2.55602 + vertex 1.56547 1.34444 2.55599 + endloop + endfacet + facet normal -0.0331114 -0.0723824 0.996827 + outer loop + vertex 1.56875 1.34344 2.55602 + vertex 1.56915 1.3477 2.55635 + vertex 1.56547 1.34444 2.55599 + endloop + endfacet + facet normal -0.0088477 -0.0746523 0.99717 + outer loop + vertex 1.56875 1.34344 2.55602 + vertex 1.5721 1.34377 2.55608 + vertex 1.56915 1.3477 2.55635 + endloop + endfacet + facet normal 0.0208438 -0.0524098 0.998408 + outer loop + vertex 1.5721 1.34377 2.55608 + vertex 1.57313 1.34815 2.55629 + vertex 1.56915 1.3477 2.55635 + endloop + endfacet + facet normal 0.0208429 -0.0524011 0.998409 + outer loop + vertex 1.57313 1.34815 2.55629 + vertex 1.57299 1.35281 2.55653 + vertex 1.56915 1.3477 2.55635 + endloop + endfacet + facet normal 0.0401601 -0.0668935 0.996952 + outer loop + vertex 1.56915 1.3477 2.55635 + vertex 1.57299 1.35281 2.55653 + vertex 1.56803 1.35299 2.55675 + endloop + endfacet + facet normal 0.0400464 -0.0697986 0.996757 + outer loop + vertex 1.57299 1.35281 2.55653 + vertex 1.57225 1.35785 2.55692 + vertex 1.56803 1.35299 2.55675 + endloop + endfacet + facet normal 0.0512008 -0.0794475 0.995523 + outer loop + vertex 1.56803 1.35299 2.55675 + vertex 1.57225 1.35785 2.55692 + vertex 1.56761 1.35803 2.55717 + endloop + endfacet + facet normal 0.0515671 -0.0708078 0.996156 + outer loop + vertex 1.57225 1.35785 2.55692 + vertex 1.57226 1.36279 2.55727 + vertex 1.56761 1.35803 2.55717 + endloop + endfacet + facet normal 0.0921444 -0.0803611 0.992498 + outer loop + vertex 1.56767 1.3729 2.55844 + vertex 1.57265 1.37799 2.55839 + vertex 1.56764 1.37782 2.55884 + endloop + endfacet + facet normal 0.0918823 -0.0707076 0.993256 + outer loop + vertex 1.57265 1.37799 2.55839 + vertex 1.57265 1.38292 2.55874 + vertex 1.56764 1.37782 2.55884 + endloop + endfacet + facet normal 0.0948545 -0.0736391 0.992764 + outer loop + vertex 1.56764 1.37782 2.55884 + vertex 1.57265 1.38292 2.55874 + vertex 1.56758 1.38275 2.55921 + endloop + endfacet + facet normal 0.0945633 -0.0624257 0.99356 + outer loop + vertex 1.57265 1.38292 2.55874 + vertex 1.57262 1.38788 2.55905 + vertex 1.56758 1.38275 2.55921 + endloop + endfacet + facet normal 0.10454 -0.0722996 0.991889 + outer loop + vertex 1.56758 1.38275 2.55921 + vertex 1.57262 1.38788 2.55905 + vertex 1.56739 1.38782 2.5596 + endloop + endfacet + facet normal 0.10453 -0.0691493 0.992115 + outer loop + vertex 1.57262 1.38788 2.55905 + vertex 1.57252 1.39304 2.55942 + vertex 1.56739 1.38782 2.5596 + endloop + endfacet + facet normal 0.118317 -0.0828054 0.989517 + outer loop + vertex 1.56739 1.38782 2.5596 + vertex 1.57252 1.39304 2.55942 + vertex 1.5668 1.39359 2.56015 + endloop + endfacet + facet normal 0.0462496 -0.127223 0.990795 + outer loop + vertex 1.5689 1.39767 2.56058 + vertex 1.56643 1.39734 2.56065 + vertex 1.5668 1.39359 2.56015 + endloop + endfacet + facet normal 0.202038 -0.203941 0.957908 + outer loop + vertex 1.5689 1.39767 2.56058 + vertex 1.5668 1.39359 2.56015 + vertex 1.5726 1.39841 2.55995 + endloop + endfacet + facet normal 0.116503 -0.0996494 0.988179 + outer loop + vertex 1.5726 1.39841 2.55995 + vertex 1.5668 1.39359 2.56015 + vertex 1.57252 1.39304 2.55942 + endloop + endfacet + facet normal 0.0459165 -0.124629 0.99114 + outer loop + vertex 1.5689 1.39767 2.56058 + vertex 1.568 1.39967 2.56087 + vertex 1.56643 1.39734 2.56065 + endloop + endfacet + facet normal 0.229696 -0.110429 0.966977 + outer loop + vertex 1.5726 1.39841 2.55995 + vertex 1.57387 1.40354 2.56024 + vertex 1.57055 1.4009 2.56072 + endloop + endfacet + facet normal 0.192002 -0.142609 0.970978 + outer loop + vertex 1.5689 1.39767 2.56058 + vertex 1.5726 1.39841 2.55995 + vertex 1.57055 1.4009 2.56072 + endloop + endfacet + facet normal 0.104169 -0.0984053 0.989679 + outer loop + vertex 1.57055 1.4009 2.56072 + vertex 1.568 1.39967 2.56087 + vertex 1.5689 1.39767 2.56058 + endloop + endfacet + facet normal 0.0814238 -0.0507381 0.995387 + outer loop + vertex 1.56855 1.40361 2.56103 + vertex 1.568 1.39967 2.56087 + vertex 1.57055 1.4009 2.56072 + endloop + endfacet + facet normal 0.21964 -0.0971099 0.970736 + outer loop + vertex 1.57387 1.40354 2.56024 + vertex 1.57148 1.40428 2.56085 + vertex 1.57055 1.4009 2.56072 + endloop + endfacet + facet normal 0.0721269 -0.0576532 0.995728 + outer loop + vertex 1.57148 1.40428 2.56085 + vertex 1.56855 1.40361 2.56103 + vertex 1.57055 1.4009 2.56072 + endloop + endfacet + facet normal 0.0675667 -0.0375201 0.997009 + outer loop + vertex 1.57148 1.40428 2.56085 + vertex 1.57109 1.4076 2.561 + vertex 1.56855 1.40361 2.56103 + endloop + endfacet + facet normal 0.0468906 -0.0243524 0.998603 + outer loop + vertex 1.57109 1.4076 2.561 + vertex 1.56802 1.40866 2.56117 + vertex 1.56855 1.40361 2.56103 + endloop + endfacet + facet normal 0.0485336 -0.0196007 0.998629 + outer loop + vertex 1.57109 1.4076 2.561 + vertex 1.57103 1.41233 2.5611 + vertex 1.56802 1.40866 2.56117 + endloop + endfacet + facet normal 0.0573047 -0.0268149 0.997997 + outer loop + vertex 1.56802 1.40866 2.56117 + vertex 1.57103 1.41233 2.5611 + vertex 1.56725 1.41389 2.56136 + endloop + endfacet + facet normal 0.0543299 -0.0339792 0.997945 + outer loop + vertex 1.57103 1.41233 2.5611 + vertex 1.5712 1.41739 2.56126 + vertex 1.56725 1.41389 2.56136 + endloop + endfacet + facet normal 0.0818617 -0.0651388 0.994513 + outer loop + vertex 1.56725 1.41389 2.56136 + vertex 1.5712 1.41739 2.56126 + vertex 1.56815 1.41878 2.5616 + endloop + endfacet + facet normal 0.0907762 -0.0455001 0.994831 + outer loop + vertex 1.5712 1.41739 2.56126 + vertex 1.57139 1.42228 2.56147 + vertex 1.56815 1.41878 2.5616 + endloop + endfacet + facet normal 0.0839454 -0.0391591 0.995701 + outer loop + vertex 1.56815 1.41878 2.5616 + vertex 1.57139 1.42228 2.56147 + vertex 1.56746 1.42281 2.56182 + endloop + endfacet + facet normal 0.0840355 -0.0385008 0.995719 + outer loop + vertex 1.57139 1.42228 2.56147 + vertex 1.57141 1.42715 2.56166 + vertex 1.56746 1.42281 2.56182 + endloop + endfacet + facet normal 0.0884603 -0.0425484 0.995171 + outer loop + vertex 1.56746 1.42281 2.56182 + vertex 1.57141 1.42715 2.56166 + vertex 1.56731 1.42782 2.56205 + endloop + endfacet + facet normal 0.0896611 -0.0352621 0.995348 + outer loop + vertex 1.57141 1.42715 2.56166 + vertex 1.57152 1.43214 2.56182 + vertex 1.56731 1.42782 2.56205 + endloop + endfacet + facet normal 0.0938512 -0.0393691 0.994808 + outer loop + vertex 1.56731 1.42782 2.56205 + vertex 1.57152 1.43214 2.56182 + vertex 1.56736 1.43282 2.56224 + endloop + endfacet + facet normal 0.0951138 -0.0317642 0.994959 + outer loop + vertex 1.57152 1.43214 2.56182 + vertex 1.57165 1.43711 2.56197 + vertex 1.56736 1.43282 2.56224 + endloop + endfacet + facet normal 0.100016 -0.0367093 0.994308 + outer loop + vertex 1.56736 1.43282 2.56224 + vertex 1.57165 1.43711 2.56197 + vertex 1.56744 1.43777 2.56242 + endloop + endfacet + facet normal 0.101262 -0.0288773 0.994441 + outer loop + vertex 1.57165 1.43711 2.56197 + vertex 1.57177 1.44203 2.5621 + vertex 1.56744 1.43777 2.56242 + endloop + endfacet + facet normal 0.10608 -0.0338162 0.993782 + outer loop + vertex 1.56744 1.43777 2.56242 + vertex 1.57177 1.44203 2.5621 + vertex 1.56753 1.4427 2.56258 + endloop + endfacet + facet normal 0.108172 -0.0206514 0.993918 + outer loop + vertex 1.57177 1.44203 2.5621 + vertex 1.572 1.44703 2.56218 + vertex 1.56753 1.4427 2.56258 + endloop + endfacet + facet normal 0.115992 -0.0288393 0.992831 + outer loop + vertex 1.56753 1.4427 2.56258 + vertex 1.572 1.44703 2.56218 + vertex 1.56767 1.44775 2.56271 + endloop + endfacet + facet normal 0.118107 -0.0162232 0.992868 + outer loop + vertex 1.572 1.44703 2.56218 + vertex 1.57269 1.45265 2.56219 + vertex 1.56767 1.44775 2.56271 + endloop + endfacet + facet normal 0.131329 -0.0299855 0.990885 + outer loop + vertex 1.56767 1.44775 2.56271 + vertex 1.57269 1.45265 2.56219 + vertex 1.56769 1.45285 2.56286 + endloop + endfacet + facet normal 0.13126 -0.0315873 0.990845 + outer loop + vertex 1.57269 1.45265 2.56219 + vertex 1.57215 1.45776 2.56242 + vertex 1.56769 1.45285 2.56286 + endloop + endfacet + facet normal 0.130224 -0.0306315 0.991011 + outer loop + vertex 1.56769 1.45285 2.56286 + vertex 1.57215 1.45776 2.56242 + vertex 1.56759 1.45786 2.56302 + endloop + endfacet + facet normal 0.13034 -0.0261125 0.991125 + outer loop + vertex 1.57215 1.45776 2.56242 + vertex 1.57209 1.46273 2.56256 + vertex 1.56759 1.45786 2.56302 + endloop + endfacet + facet normal 0.130617 -0.0263724 0.991082 + outer loop + vertex 1.56759 1.45786 2.56302 + vertex 1.57209 1.46273 2.56256 + vertex 1.56758 1.46286 2.56316 + endloop + endfacet + facet normal 0.130785 -0.0208367 0.991192 + outer loop + vertex 1.57209 1.46273 2.56256 + vertex 1.57211 1.46774 2.56266 + vertex 1.56758 1.46286 2.56316 + endloop + endfacet + facet normal 0.133386 -0.023296 0.99079 + outer loop + vertex 1.56758 1.46286 2.56316 + vertex 1.57211 1.46774 2.56266 + vertex 1.5676 1.46785 2.56327 + endloop + endfacet + facet normal 0.133527 -0.0182817 0.990876 + outer loop + vertex 1.57211 1.46774 2.56266 + vertex 1.57215 1.47274 2.56275 + vertex 1.5676 1.46785 2.56327 + endloop + endfacet + facet normal 0.134736 -0.0194271 0.990691 + outer loop + vertex 1.5676 1.46785 2.56327 + vertex 1.57215 1.47274 2.56275 + vertex 1.5676 1.47283 2.56337 + endloop + endfacet + facet normal 0.134824 -0.0152716 0.990752 + outer loop + vertex 1.57215 1.47274 2.56275 + vertex 1.57217 1.47772 2.56282 + vertex 1.5676 1.47283 2.56337 + endloop + endfacet + facet normal 0.138152 -0.0184376 0.990239 + outer loop + vertex 1.5676 1.47283 2.56337 + vertex 1.57217 1.47772 2.56282 + vertex 1.56761 1.4778 2.56346 + endloop + endfacet + facet normal 0.138236 -0.0138479 0.990303 + outer loop + vertex 1.57217 1.47772 2.56282 + vertex 1.5722 1.4827 2.56289 + vertex 1.56761 1.4778 2.56346 + endloop + endfacet + facet normal 0.138419 -0.0140223 0.990275 + outer loop + vertex 1.56761 1.4778 2.56346 + vertex 1.5722 1.4827 2.56289 + vertex 1.56759 1.48275 2.56354 + endloop + endfacet + facet normal 0.138477 -0.00911638 0.990324 + outer loop + vertex 1.5722 1.4827 2.56289 + vertex 1.5722 1.48768 2.56294 + vertex 1.56759 1.48275 2.56354 + endloop + endfacet + facet normal 0.141715 -0.0122067 0.989832 + outer loop + vertex 1.56759 1.48275 2.56354 + vertex 1.5722 1.48768 2.56294 + vertex 1.56757 1.48772 2.5636 + endloop + endfacet + facet normal 0.141771 -0.00620575 0.98988 + outer loop + vertex 1.5722 1.48768 2.56294 + vertex 1.57219 1.49266 2.56297 + vertex 1.56757 1.48772 2.5636 + endloop + endfacet + facet normal 0.144204 -0.00852963 0.989511 + outer loop + vertex 1.56757 1.48772 2.5636 + vertex 1.57219 1.49266 2.56297 + vertex 1.56754 1.49269 2.56365 + endloop + endfacet + facet normal 0.14423 -0.00489849 0.989532 + outer loop + vertex 1.57219 1.49266 2.56297 + vertex 1.57219 1.49766 2.56299 + vertex 1.56754 1.49269 2.56365 + endloop + endfacet + facet normal 0.147131 -0.00767405 0.989087 + outer loop + vertex 1.56754 1.49269 2.56365 + vertex 1.57219 1.49766 2.56299 + vertex 1.56753 1.49768 2.56369 + endloop + endfacet + facet normal 0.147151 -0.00384386 0.989107 + outer loop + vertex 1.57219 1.49766 2.56299 + vertex 1.5722 1.50265 2.56301 + vertex 1.56753 1.49768 2.56369 + endloop + endfacet + facet normal 0.14834 -0.00498239 0.988924 + outer loop + vertex 1.56753 1.49768 2.56369 + vertex 1.5722 1.50265 2.56301 + vertex 1.56752 1.50267 2.56371 + endloop + endfacet + facet normal 0.148352 -0.00193773 0.988933 + outer loop + vertex 1.5722 1.50265 2.56301 + vertex 1.57219 1.50765 2.56302 + vertex 1.56752 1.50267 2.56371 + endloop + endfacet + facet normal 0.1497 -0.00323062 0.988726 + outer loop + vertex 1.56752 1.50267 2.56371 + vertex 1.57219 1.50765 2.56302 + vertex 1.56752 1.50767 2.56373 + endloop + endfacet + facet normal 0.149711 -0.000591684 0.98873 + outer loop + vertex 1.57219 1.50765 2.56302 + vertex 1.57219 1.51265 2.56303 + vertex 1.56752 1.50767 2.56373 + endloop + endfacet + facet normal 0.148487 0.000582275 0.988914 + outer loop + vertex 1.56752 1.50767 2.56373 + vertex 1.57219 1.51265 2.56303 + vertex 1.56751 1.51266 2.56373 + endloop + endfacet + facet normal 0.148493 0.00294507 0.988909 + outer loop + vertex 1.57219 1.51265 2.56303 + vertex 1.57218 1.51763 2.56301 + vertex 1.56751 1.51266 2.56373 + endloop + endfacet + facet normal 0.14847 0.0029675 0.988912 + outer loop + vertex 1.56751 1.51266 2.56373 + vertex 1.57218 1.51763 2.56301 + vertex 1.56751 1.51766 2.56371 + endloop + endfacet + facet normal 0.148467 0.00235159 0.988915 + outer loop + vertex 1.57218 1.51763 2.56301 + vertex 1.57218 1.52263 2.563 + vertex 1.56751 1.51766 2.56371 + endloop + endfacet + facet normal 0.146035 0.00468572 0.989268 + outer loop + vertex 1.56751 1.51766 2.56371 + vertex 1.57218 1.52263 2.563 + vertex 1.56751 1.52265 2.56369 + endloop + endfacet + facet normal 0.146035 0.00459182 0.989269 + outer loop + vertex 1.57218 1.52263 2.563 + vertex 1.57217 1.52762 2.56298 + vertex 1.56751 1.52265 2.56369 + endloop + endfacet + facet normal 0.143998 0.00654241 0.989556 + outer loop + vertex 1.56751 1.52265 2.56369 + vertex 1.57217 1.52762 2.56298 + vertex 1.5675 1.52764 2.56366 + endloop + endfacet + facet normal 0.143997 0.00600781 0.98956 + outer loop + vertex 1.57217 1.52762 2.56298 + vertex 1.57216 1.53261 2.56295 + vertex 1.5675 1.52764 2.56366 + endloop + endfacet + facet normal 0.141793 0.00811393 0.989863 + outer loop + vertex 1.5675 1.52764 2.56366 + vertex 1.57216 1.53261 2.56295 + vertex 1.56751 1.53262 2.56362 + endloop + endfacet + facet normal 0.141795 0.00926175 0.989853 + outer loop + vertex 1.57216 1.53261 2.56295 + vertex 1.57215 1.5376 2.56291 + vertex 1.56751 1.53262 2.56362 + endloop + endfacet + facet normal 0.138388 0.0125047 0.990299 + outer loop + vertex 1.56751 1.53262 2.56362 + vertex 1.57215 1.5376 2.56291 + vertex 1.56751 1.53761 2.56355 + endloop + endfacet + facet normal 0.138389 0.0138603 0.990281 + outer loop + vertex 1.57215 1.5376 2.56291 + vertex 1.57213 1.54259 2.56284 + vertex 1.56751 1.53761 2.56355 + endloop + endfacet + facet normal 0.137464 0.0147349 0.990397 + outer loop + vertex 1.56751 1.53761 2.56355 + vertex 1.57213 1.54259 2.56284 + vertex 1.56753 1.54262 2.56348 + endloop + endfacet + facet normal 0.137464 0.0148026 0.990396 + outer loop + vertex 1.57213 1.54259 2.56284 + vertex 1.57211 1.54761 2.56277 + vertex 1.56753 1.54262 2.56348 + endloop + endfacet + facet normal 0.136137 0.0160445 0.99056 + outer loop + vertex 1.56753 1.54262 2.56348 + vertex 1.57211 1.54761 2.56277 + vertex 1.56753 1.54765 2.56339 + endloop + endfacet + facet normal 0.136139 0.0165671 0.990551 + outer loop + vertex 1.57211 1.54761 2.56277 + vertex 1.57201 1.55262 2.5627 + vertex 1.56753 1.54765 2.56339 + endloop + endfacet + facet normal 0.134582 0.0180008 0.990739 + outer loop + vertex 1.56753 1.54765 2.56339 + vertex 1.57201 1.55262 2.5627 + vertex 1.56746 1.55263 2.56331 + endloop + endfacet + facet normal 0.134582 0.0184951 0.99073 + outer loop + vertex 1.57201 1.55262 2.5627 + vertex 1.57179 1.55749 2.56263 + vertex 1.56746 1.55263 2.56331 + endloop + endfacet + facet normal 0.132182 0.0206754 0.99101 + outer loop + vertex 1.56746 1.55263 2.56331 + vertex 1.57179 1.55749 2.56263 + vertex 1.56732 1.55743 2.56323 + endloop + endfacet + facet normal 0.132233 0.0174711 0.991065 + outer loop + vertex 1.57179 1.55749 2.56263 + vertex 1.5712 1.56148 2.56264 + vertex 1.56732 1.55743 2.56323 + endloop + endfacet + facet normal 0.119564 0.0297772 0.99238 + outer loop + vertex 1.56732 1.55743 2.56323 + vertex 1.5712 1.56148 2.56264 + vertex 1.56748 1.56227 2.56307 + endloop + endfacet + facet normal 0.124685 0.0547742 0.990683 + outer loop + vertex 1.5712 1.56148 2.56264 + vertex 1.5728 1.56667 2.56215 + vertex 1.56748 1.56227 2.56307 + endloop + endfacet + facet normal 0.146896 0.0274758 0.98877 + outer loop + vertex 1.56748 1.56227 2.56307 + vertex 1.5728 1.56667 2.56215 + vertex 1.5676 1.56736 2.56291 + endloop + endfacet + facet normal 0.143958 0.0043937 0.989574 + outer loop + vertex 1.5728 1.56667 2.56215 + vertex 1.57198 1.57202 2.56225 + vertex 1.5676 1.56736 2.56291 + endloop + endfacet + facet normal 0.122947 0.0244637 0.992112 + outer loop + vertex 1.5676 1.56736 2.56291 + vertex 1.57198 1.57202 2.56225 + vertex 1.56746 1.57245 2.5628 + endloop + endfacet + facet normal 0.122684 0.0215885 0.992211 + outer loop + vertex 1.57198 1.57202 2.56225 + vertex 1.57176 1.57697 2.56217 + vertex 1.56746 1.57245 2.5628 + endloop + endfacet + facet normal 0.112074 0.0318209 0.99319 + outer loop + vertex 1.56746 1.57245 2.5628 + vertex 1.57176 1.57697 2.56217 + vertex 1.5674 1.57749 2.56264 + endloop + endfacet + facet normal 0.112029 0.0314286 0.993208 + outer loop + vertex 1.57176 1.57697 2.56217 + vertex 1.57164 1.58194 2.56203 + vertex 1.5674 1.57749 2.56264 + endloop + endfacet + facet normal 0.105512 0.0377092 0.993703 + outer loop + vertex 1.5674 1.57749 2.56264 + vertex 1.57164 1.58194 2.56203 + vertex 1.56736 1.58252 2.56246 + endloop + endfacet + facet normal 0.105254 0.0357356 0.993803 + outer loop + vertex 1.57164 1.58194 2.56203 + vertex 1.57153 1.58694 2.56186 + vertex 1.56736 1.58252 2.56246 + endloop + endfacet + facet normal 0.0999164 0.0408163 0.994158 + outer loop + vertex 1.56736 1.58252 2.56246 + vertex 1.57153 1.58694 2.56186 + vertex 1.56731 1.58753 2.56226 + endloop + endfacet + facet normal 0.0994615 0.0374779 0.994335 + outer loop + vertex 1.57153 1.58694 2.56186 + vertex 1.57142 1.59194 2.56168 + vertex 1.56731 1.58753 2.56226 + endloop + endfacet + facet normal 0.0960859 0.0406544 0.994542 + outer loop + vertex 1.56731 1.58753 2.56226 + vertex 1.57142 1.59194 2.56168 + vertex 1.56729 1.59254 2.56205 + endloop + endfacet + facet normal 0.0957459 0.0382176 0.994672 + outer loop + vertex 1.57142 1.59194 2.56168 + vertex 1.57136 1.59694 2.56149 + vertex 1.56729 1.59254 2.56205 + endloop + endfacet + facet normal 0.0924005 0.0413364 0.994864 + outer loop + vertex 1.56729 1.59254 2.56205 + vertex 1.57136 1.59694 2.56149 + vertex 1.5673 1.59754 2.56185 + endloop + endfacet + facet normal 0.0917946 0.037111 0.995086 + outer loop + vertex 1.57136 1.59694 2.56149 + vertex 1.57125 1.60192 2.56132 + vertex 1.5673 1.59754 2.56185 + endloop + endfacet + facet normal 0.0818347 0.0461467 0.995577 + outer loop + vertex 1.5673 1.59754 2.56185 + vertex 1.57125 1.60192 2.56132 + vertex 1.56714 1.60254 2.56163 + endloop + endfacet + facet normal 0.0807614 0.0388494 0.995976 + outer loop + vertex 1.57125 1.60192 2.56132 + vertex 1.57078 1.60683 2.56117 + vertex 1.56714 1.60254 2.56163 + endloop + endfacet + facet normal 0.0620489 0.0547487 0.99657 + outer loop + vertex 1.56714 1.60254 2.56163 + vertex 1.57078 1.60683 2.56117 + vertex 1.56651 1.60748 2.5614 + endloop + endfacet + facet normal 0.0592303 0.0358571 0.9976 + outer loop + vertex 1.57078 1.60683 2.56117 + vertex 1.56976 1.61176 2.56105 + vertex 1.56651 1.60748 2.5614 + endloop + endfacet + facet normal 0.0321794 0.0564552 0.997886 + outer loop + vertex 1.56651 1.60748 2.5614 + vertex 1.56976 1.61176 2.56105 + vertex 1.56565 1.61175 2.56118 + endloop + endfacet + facet normal 0.1761 0.0951702 0.979761 + outer loop + vertex 1.57288 1.61431 2.5605 + vertex 1.57324 1.6187 2.56001 + vertex 1.57037 1.61558 2.56083 + endloop + endfacet + facet normal 0.146552 0.0345031 0.988601 + outer loop + vertex 1.57037 1.61558 2.56083 + vertex 1.56976 1.61176 2.56105 + vertex 1.57288 1.61431 2.5605 + endloop + endfacet + facet normal 0.0690551 0.0472459 0.996493 + outer loop + vertex 1.57037 1.61558 2.56083 + vertex 1.5675 1.61496 2.56105 + vertex 1.56976 1.61176 2.56105 + endloop + endfacet + facet normal 0.032293 0.0212608 0.999252 + outer loop + vertex 1.5675 1.61496 2.56105 + vertex 1.56565 1.61175 2.56118 + vertex 1.56976 1.61176 2.56105 + endloop + endfacet + facet normal 0.146734 0.122689 0.981538 + outer loop + vertex 1.56892 1.61776 2.56077 + vertex 1.57037 1.61558 2.56083 + vertex 1.57324 1.6187 2.56001 + endloop + endfacet + facet normal 0.148036 0.117108 0.982024 + outer loop + vertex 1.56892 1.61776 2.56077 + vertex 1.57324 1.6187 2.56001 + vertex 1.56832 1.62186 2.56037 + endloop + endfacet + facet normal 0.123096 0.0773772 0.989374 + outer loop + vertex 1.56832 1.62186 2.56037 + vertex 1.57324 1.6187 2.56001 + vertex 1.5736 1.6237 2.55957 + endloop + endfacet + facet normal 0.0644283 0.0682718 0.995584 + outer loop + vertex 1.57037 1.61558 2.56083 + vertex 1.56892 1.61776 2.56077 + vertex 1.5675 1.61496 2.56105 + endloop + endfacet + facet normal 0.128955 0.0607741 0.989786 + outer loop + vertex 1.5736 1.6237 2.55957 + vertex 1.57254 1.62753 2.55947 + vertex 1.56832 1.62186 2.56037 + endloop + endfacet + facet normal 0.11053 0.074695 0.991062 + outer loop + vertex 1.56832 1.62186 2.56037 + vertex 1.57254 1.62753 2.55947 + vertex 1.56763 1.62749 2.56002 + endloop + endfacet + facet normal 0.1107 0.0642337 0.991776 + outer loop + vertex 1.57254 1.62753 2.55947 + vertex 1.5723 1.63238 2.55918 + vertex 1.56763 1.62749 2.56002 + endloop + endfacet + facet normal 0.10143 0.0731509 0.99215 + outer loop + vertex 1.56763 1.62749 2.56002 + vertex 1.5723 1.63238 2.55918 + vertex 1.56737 1.63237 2.55969 + endloop + endfacet + facet normal 0.101539 0.0626002 0.99286 + outer loop + vertex 1.5723 1.63238 2.55918 + vertex 1.57232 1.63734 2.55887 + vertex 1.56737 1.63237 2.55969 + endloop + endfacet + facet normal 0.0927095 0.071432 0.993128 + outer loop + vertex 1.56737 1.63237 2.55969 + vertex 1.57232 1.63734 2.55887 + vertex 1.5674 1.63725 2.55934 + endloop + endfacet + facet normal 0.0929254 0.0622691 0.993724 + outer loop + vertex 1.57232 1.63734 2.55887 + vertex 1.57228 1.64218 2.55857 + vertex 1.5674 1.63725 2.55934 + endloop + endfacet + facet normal 0.06258 0.0783031 0.994964 + outer loop + vertex 1.56757 1.65239 2.55818 + vertex 1.57222 1.65741 2.55749 + vertex 1.56759 1.65747 2.55778 + endloop + endfacet + facet normal 0.0624957 0.0697368 0.995606 + outer loop + vertex 1.57222 1.65741 2.55749 + vertex 1.57187 1.66233 2.55717 + vertex 1.56759 1.65747 2.55778 + endloop + endfacet + facet normal 0.045355 0.0848517 0.995361 + outer loop + vertex 1.56759 1.65747 2.55778 + vertex 1.57187 1.66233 2.55717 + vertex 1.56748 1.66235 2.55737 + endloop + endfacet + facet normal 0.0453299 0.0758136 0.996091 + outer loop + vertex 1.57187 1.66233 2.55717 + vertex 1.57106 1.66629 2.55691 + vertex 1.56748 1.66235 2.55737 + endloop + endfacet + facet normal 0.0267199 0.0926183 0.995343 + outer loop + vertex 1.56748 1.66235 2.55737 + vertex 1.57106 1.66629 2.55691 + vertex 1.56726 1.66727 2.55692 + endloop + endfacet + facet normal 0.0268752 0.0932203 0.995283 + outer loop + vertex 1.57106 1.66629 2.55691 + vertex 1.57194 1.67121 2.55642 + vertex 1.56726 1.66727 2.55692 + endloop + endfacet + facet normal 0.0250368 0.0953837 0.995126 + outer loop + vertex 1.56726 1.66727 2.55692 + vertex 1.57194 1.67121 2.55642 + vertex 1.56614 1.67301 2.55639 + endloop + endfacet + facet normal -0.0451856 0.0705135 0.996487 + outer loop + vertex 1.56916 1.67975 2.55596 + vertex 1.56607 1.67962 2.55583 + vertex 1.5675 1.67716 2.55607 + endloop + endfacet + facet normal -0.00532679 0.0451193 0.998967 + outer loop + vertex 1.5675 1.67716 2.55607 + vertex 1.57093 1.6767 2.5561 + vertex 1.56916 1.67975 2.55596 + endloop + endfacet + facet normal -0.000715864 0.0792112 0.996858 + outer loop + vertex 1.5675 1.67716 2.55607 + vertex 1.56614 1.67301 2.55639 + vertex 1.57093 1.6767 2.5561 + endloop + endfacet + facet normal 0.0140985 0.0601072 0.998092 + outer loop + vertex 1.56614 1.67301 2.55639 + vertex 1.57194 1.67121 2.55642 + vertex 1.57093 1.6767 2.5561 + endloop + endfacet + facet normal -0.0463885 0.100915 0.993813 + outer loop + vertex 1.56832 1.68291 2.5556 + vertex 1.56607 1.67962 2.55583 + vertex 1.56916 1.67975 2.55596 + endloop + endfacet + facet normal -0.0246068 0.106683 0.993989 + outer loop + vertex 1.57101 1.68233 2.55573 + vertex 1.56832 1.68291 2.5556 + vertex 1.56916 1.67975 2.55596 + endloop + endfacet + facet normal -0.00217363 0.0907446 0.995872 + outer loop + vertex 1.56916 1.67975 2.55596 + vertex 1.5717 1.68022 2.55592 + vertex 1.57101 1.68233 2.55573 + endloop + endfacet + facet normal 0.00516508 0.0511831 0.998676 + outer loop + vertex 1.57093 1.6767 2.5561 + vertex 1.5717 1.68022 2.55592 + vertex 1.56916 1.67975 2.55596 + endloop + endfacet + facet normal 0.0685419 0.143049 0.987339 + outer loop + vertex 1.57101 1.68233 2.55573 + vertex 1.57344 1.68257 2.55552 + vertex 1.5732 1.68646 2.55498 + endloop + endfacet + facet normal -0.00784946 0.18281 0.983117 + outer loop + vertex 1.57101 1.68233 2.55573 + vertex 1.5732 1.68646 2.55498 + vertex 1.56832 1.68291 2.5556 + endloop + endfacet + facet normal 0.0446499 0.112452 0.992654 + outer loop + vertex 1.56832 1.68291 2.5556 + vertex 1.5732 1.68646 2.55498 + vertex 1.56781 1.68724 2.55513 + endloop + endfacet + facet normal 0.0715862 0.114325 0.990861 + outer loop + vertex 1.57344 1.68257 2.55552 + vertex 1.57101 1.68233 2.55573 + vertex 1.5717 1.68022 2.55592 + endloop + endfacet + facet normal 0.0436378 0.105335 0.993479 + outer loop + vertex 1.5732 1.68646 2.55498 + vertex 1.57258 1.69206 2.55441 + vertex 1.56781 1.68724 2.55513 + endloop + endfacet + facet normal 0.205092 0.502099 0.840139 + outer loop + vertex 1.5738 2.09967 2.46596 + vertex 1.57115 2.10302 2.46461 + vertex 1.57004 2.10052 2.46637 + endloop + endfacet + facet normal 0.187564 0.396708 0.898578 + outer loop + vertex 1.57004 2.10052 2.46637 + vertex 1.57061 2.09678 2.46791 + vertex 1.5738 2.09967 2.46596 + endloop + endfacet + facet normal 0.178603 0.39618 0.900634 + outer loop + vertex 1.57004 2.10052 2.46637 + vertex 1.56626 2.09992 2.46739 + vertex 1.57061 2.09678 2.46791 + endloop + endfacet + facet normal 0.205929 0.501734 0.840152 + outer loop + vertex 1.56776 2.10276 2.4656 + vertex 1.57004 2.10052 2.46637 + vertex 1.57115 2.10302 2.46461 + endloop + endfacet + facet normal 0.183431 0.589971 0.786312 + outer loop + vertex 1.56776 2.10276 2.4656 + vertex 1.57115 2.10302 2.46461 + vertex 1.567 2.10597 2.46336 + endloop + endfacet + facet normal 0.204986 0.611173 0.764493 + outer loop + vertex 1.567 2.10597 2.46336 + vertex 1.57115 2.10302 2.46461 + vertex 1.5721 2.10573 2.46219 + endloop + endfacet + facet normal 0.159556 0.465117 0.870751 + outer loop + vertex 1.57004 2.10052 2.46637 + vertex 1.56776 2.10276 2.4656 + vertex 1.56626 2.09992 2.46739 + endloop + endfacet + facet normal 0.213585 0.869181 0.445989 + outer loop + vertex 1.57278 2.10971 2.45694 + vertex 1.57104 2.11128 2.45471 + vertex 1.56905 2.1106 2.45699 + endloop + endfacet + facet normal 0.208904 0.815238 0.540135 + outer loop + vertex 1.56905 2.1106 2.45699 + vertex 1.56536 2.11084 2.45806 + vertex 1.56914 2.10865 2.4599 + endloop + endfacet + facet normal 0.202035 0.816334 0.541091 + outer loop + vertex 1.56905 2.1106 2.45699 + vertex 1.56914 2.10865 2.4599 + vertex 1.57278 2.10971 2.45694 + endloop + endfacet + facet normal 0.208294 0.810904 0.546853 + outer loop + vertex 1.57278 2.10971 2.45694 + vertex 1.56914 2.10865 2.4599 + vertex 1.57416 2.10763 2.4595 + endloop + endfacet + facet normal 0.188308 0.717113 0.671036 + outer loop + vertex 1.5721 2.10573 2.46219 + vertex 1.56914 2.10865 2.4599 + vertex 1.567 2.10597 2.46336 + endloop + endfacet + facet normal 0.199178 0.721734 0.662893 + outer loop + vertex 1.57416 2.10763 2.4595 + vertex 1.56914 2.10865 2.4599 + vertex 1.5721 2.10573 2.46219 + endloop + endfacet + facet normal 0.0200165 0.345211 0.938312 + outer loop + vertex 1.575 2.11697 2.45 + vertex 1.57 2.11726 2.45 + vertex 1.57151 2.11326 2.45144 + endloop + endfacet + facet normal 0.033917 0.34973 0.936236 + outer loop + vertex 1.57151 2.11326 2.45144 + vertex 1.57 2.11726 2.45 + vertex 1.56724 2.11459 2.4511 + endloop + endfacet + facet normal 0.191405 0.882092 0.43044 + outer loop + vertex 1.57104 2.11128 2.45471 + vertex 1.56703 2.11233 2.45435 + vertex 1.56905 2.1106 2.45699 + endloop + endfacet + facet normal 0.169671 0.831964 0.52825 + outer loop + vertex 1.57104 2.11128 2.45471 + vertex 1.57151 2.11326 2.45144 + vertex 1.56703 2.11233 2.45435 + endloop + endfacet + facet normal 0.202688 0.79766 0.568028 + outer loop + vertex 1.57151 2.11326 2.45144 + vertex 1.56724 2.11459 2.4511 + vertex 1.56703 2.11233 2.45435 + endloop + endfacet + facet normal 0.182858 0.881021 0.436307 + outer loop + vertex 1.56905 2.1106 2.45699 + vertex 1.56703 2.11233 2.45435 + vertex 1.56536 2.11084 2.45806 + endloop + endfacet + facet normal 0.125634 -0.702645 0.700362 + outer loop + vertex 1.58 0.916915 2.45 + vertex 1.57727 0.917173 2.45075 + vertex 1.575 0.916021 2.45 + endloop + endfacet + facet normal 0.194159 -0.774204 0.602421 + outer loop + vertex 1.57727 0.917173 2.45075 + vertex 1.57127 0.916646 2.452 + vertex 1.575 0.916021 2.45 + endloop + endfacet + facet normal 0.170392 -0.879248 0.444848 + outer loop + vertex 1.57727 0.917173 2.45075 + vertex 1.57435 0.918382 2.45426 + vertex 1.57127 0.916646 2.452 + endloop + endfacet + facet normal 0.193262 -0.866838 0.45961 + outer loop + vertex 1.57834 0.91861 2.45301 + vertex 1.57435 0.918382 2.45426 + vertex 1.57727 0.917173 2.45075 + endloop + endfacet + facet normal 0.197371 -0.857905 0.474388 + outer loop + vertex 1.57435 0.918382 2.45426 + vertex 1.57834 0.91861 2.45301 + vertex 1.57742 0.920212 2.45629 + endloop + endfacet + facet normal 0.183451 -0.852107 0.490162 + outer loop + vertex 1.57212 0.920138 2.45814 + vertex 1.57435 0.918382 2.45426 + vertex 1.57742 0.920212 2.45629 + endloop + endfacet + facet normal 0.202308 -0.813274 0.54558 + outer loop + vertex 1.57742 0.920212 2.45629 + vertex 1.57607 0.922579 2.46032 + vertex 1.57212 0.920138 2.45814 + endloop + endfacet + facet normal 0.183119 -0.802303 0.568135 + outer loop + vertex 1.57607 0.922579 2.46032 + vertex 1.57144 0.922243 2.46134 + vertex 1.57212 0.920138 2.45814 + endloop + endfacet + facet normal 0.196168 -0.73434 0.649817 + outer loop + vertex 1.57607 0.922579 2.46032 + vertex 1.57317 0.924406 2.46326 + vertex 1.57144 0.922243 2.46134 + endloop + endfacet + facet normal 0.181542 -0.744938 0.641958 + outer loop + vertex 1.57673 0.925052 2.463 + vertex 1.57317 0.924406 2.46326 + vertex 1.57607 0.922579 2.46032 + endloop + endfacet + facet normal 0.168172 -0.622043 0.764709 + outer loop + vertex 1.57317 0.924406 2.46326 + vertex 1.57673 0.925052 2.463 + vertex 1.57525 0.92714 2.46502 + endloop + endfacet + facet normal 0.14088 -0.610618 0.779293 + outer loop + vertex 1.57103 0.926795 2.46552 + vertex 1.57317 0.924406 2.46326 + vertex 1.57525 0.92714 2.46502 + endloop + endfacet + facet normal 0.140437 -0.4862 0.862489 + outer loop + vertex 1.57525 0.92714 2.46502 + vertex 1.57398 0.930218 2.46697 + vertex 1.57103 0.926795 2.46552 + endloop + endfacet + facet normal 0.15446 -0.480805 0.863116 + outer loop + vertex 1.57827 0.930333 2.46626 + vertex 1.57398 0.930218 2.46697 + vertex 1.57525 0.92714 2.46502 + endloop + endfacet + facet normal 0.159374 -0.386133 0.908571 + outer loop + vertex 1.57827 0.930333 2.46626 + vertex 1.57787 0.9342 2.46798 + vertex 1.57398 0.930218 2.46697 + endloop + endfacet + facet normal 0.147648 -0.37623 0.914686 + outer loop + vertex 1.57398 0.930218 2.46697 + vertex 1.57787 0.9342 2.46798 + vertex 1.57298 0.933977 2.46867 + endloop + endfacet + facet normal 0.167132 -0.281693 0.944837 + outer loop + vertex 1.57367 1.00619 2.49111 + vertex 1.57288 1.00316 2.49034 + vertex 1.57708 1.00774 2.49097 + endloop + endfacet + facet normal 0.163587 -0.273599 0.94783 + outer loop + vertex 1.57708 1.00774 2.49097 + vertex 1.57289 1.00857 2.49193 + vertex 1.57367 1.00619 2.49111 + endloop + endfacet + facet normal 0.169542 -0.249397 0.953445 + outer loop + vertex 1.57819 1.0653 2.50628 + vertex 1.57292 1.06373 2.50681 + vertex 1.57528 1.06128 2.50575 + endloop + endfacet + facet normal 0.0493636 -0.17192 0.983873 + outer loop + vertex 1.57324 1.17832 2.53155 + vertex 1.57801 1.18334 2.53219 + vertex 1.5726 1.18315 2.53243 + endloop + endfacet + facet normal 0.0893014 -0.0887257 0.992045 + outer loop + vertex 1.57386 1.30435 2.55158 + vertex 1.57762 1.30809 2.55158 + vertex 1.57293 1.30809 2.552 + endloop + endfacet + facet normal 0.0892202 -0.0995429 0.991025 + outer loop + vertex 1.57762 1.30809 2.55158 + vertex 1.57714 1.31296 2.55211 + vertex 1.57293 1.30809 2.552 + endloop + endfacet + facet normal 0.0952593 -0.10474 0.989927 + outer loop + vertex 1.57293 1.30809 2.552 + vertex 1.57714 1.31296 2.55211 + vertex 1.57253 1.31296 2.55255 + endloop + endfacet + facet normal 0.0953642 -0.0939154 0.991002 + outer loop + vertex 1.57714 1.31296 2.55211 + vertex 1.57734 1.31801 2.55257 + vertex 1.57253 1.31296 2.55255 + endloop + endfacet + facet normal 0.105702 -0.10377 0.988969 + outer loop + vertex 1.57253 1.31296 2.55255 + vertex 1.57734 1.31801 2.55257 + vertex 1.57257 1.31798 2.55308 + endloop + endfacet + facet normal 0.105747 -0.093589 0.989979 + outer loop + vertex 1.57734 1.31801 2.55257 + vertex 1.57761 1.32311 2.55302 + vertex 1.57257 1.31798 2.55308 + endloop + endfacet + facet normal 0.110868 -0.0986153 0.98893 + outer loop + vertex 1.57257 1.31798 2.55308 + vertex 1.57761 1.32311 2.55302 + vertex 1.57269 1.32299 2.55356 + endloop + endfacet + facet normal 0.110761 -0.0911852 0.989655 + outer loop + vertex 1.57761 1.32311 2.55302 + vertex 1.57763 1.32809 2.55348 + vertex 1.57269 1.32299 2.55356 + endloop + endfacet + facet normal 0.116586 -0.096852 0.988447 + outer loop + vertex 1.57269 1.32299 2.55356 + vertex 1.57763 1.32809 2.55348 + vertex 1.57258 1.32807 2.55407 + endloop + endfacet + facet normal 0.116594 -0.0958229 0.988546 + outer loop + vertex 1.57763 1.32809 2.55348 + vertex 1.57752 1.33319 2.55399 + vertex 1.57258 1.32807 2.55407 + endloop + endfacet + facet normal 0.134638 -0.113304 0.984396 + outer loop + vertex 1.57258 1.32807 2.55407 + vertex 1.57752 1.33319 2.55399 + vertex 1.57192 1.3338 2.55482 + endloop + endfacet + facet normal 0.134016 -0.118318 0.983891 + outer loop + vertex 1.57752 1.33869 2.55465 + vertex 1.57192 1.3338 2.55482 + vertex 1.57752 1.33319 2.55399 + endloop + endfacet + facet normal 0.291244 -0.0236363 0.956357 + outer loop + vertex 1.57937 1.44934 2.56036 + vertex 1.57936 1.45383 2.56047 + vertex 1.57598 1.45052 2.56142 + endloop + endfacet + facet normal 0.277029 0.0306085 0.960374 + outer loop + vertex 1.57902 1.56831 2.56049 + vertex 1.57572 1.56242 2.56163 + vertex 1.57921 1.56411 2.56057 + endloop + endfacet + facet normal 0.220615 0.0938413 0.970836 + outer loop + vertex 1.57861 1.66952 2.5556 + vertex 1.57965 1.67381 2.55495 + vertex 1.57623 1.67151 2.55595 + endloop + endfacet + facet normal 0.194923 0.0617631 0.978872 + outer loop + vertex 1.57623 1.67151 2.55595 + vertex 1.57518 1.66706 2.55644 + vertex 1.57861 1.66952 2.5556 + endloop + endfacet + facet normal 0.103505 0.0846593 0.991019 + outer loop + vertex 1.57623 1.67151 2.55595 + vertex 1.57194 1.67121 2.55642 + vertex 1.57518 1.66706 2.55644 + endloop + endfacet + facet normal 0.209521 0.0707789 0.975239 + outer loop + vertex 1.57965 1.67381 2.55495 + vertex 1.5786 1.67901 2.5548 + vertex 1.57533 1.67542 2.55576 + endloop + endfacet + facet normal 0.218496 0.0970707 0.970998 + outer loop + vertex 1.57623 1.67151 2.55595 + vertex 1.57965 1.67381 2.55495 + vertex 1.57533 1.67542 2.55576 + endloop + endfacet + facet normal 0.104511 0.0717907 0.991929 + outer loop + vertex 1.57533 1.67542 2.55576 + vertex 1.57194 1.67121 2.55642 + vertex 1.57623 1.67151 2.55595 + endloop + endfacet + facet normal 0.099871 0.0755666 0.992127 + outer loop + vertex 1.57093 1.6767 2.5561 + vertex 1.57194 1.67121 2.55642 + vertex 1.57533 1.67542 2.55576 + endloop + endfacet + facet normal 0.205822 0.0817166 0.975172 + outer loop + vertex 1.5786 1.67901 2.5548 + vertex 1.57736 1.68393 2.55464 + vertex 1.57449 1.67971 2.5556 + endloop + endfacet + facet normal 0.20485 0.0752122 0.975899 + outer loop + vertex 1.57533 1.67542 2.55576 + vertex 1.5786 1.67901 2.5548 + vertex 1.57449 1.67971 2.5556 + endloop + endfacet + facet normal 0.0938395 0.0543099 0.994105 + outer loop + vertex 1.57449 1.67971 2.5556 + vertex 1.57093 1.6767 2.5561 + vertex 1.57533 1.67542 2.55576 + endloop + endfacet + facet normal 0.117372 0.0262124 0.992742 + outer loop + vertex 1.5717 1.68022 2.55592 + vertex 1.57093 1.6767 2.5561 + vertex 1.57449 1.67971 2.5556 + endloop + endfacet + facet normal 0.185788 0.0959315 0.977896 + outer loop + vertex 1.57344 1.68257 2.55552 + vertex 1.57449 1.67971 2.5556 + vertex 1.57736 1.68393 2.55464 + endloop + endfacet + facet normal 0.167186 0.147304 0.974859 + outer loop + vertex 1.57344 1.68257 2.55552 + vertex 1.57736 1.68393 2.55464 + vertex 1.5732 1.68646 2.55498 + endloop + endfacet + facet normal 0.140275 0.101683 0.984877 + outer loop + vertex 1.5732 1.68646 2.55498 + vertex 1.57736 1.68393 2.55464 + vertex 1.57822 1.68848 2.55405 + endloop + endfacet + facet normal 0.12567 0.0739818 0.98931 + outer loop + vertex 1.57449 1.67971 2.5556 + vertex 1.57344 1.68257 2.55552 + vertex 1.5717 1.68022 2.55592 + endloop + endfacet + facet normal 0.14318 0.0946108 0.985164 + outer loop + vertex 1.57822 1.68848 2.55405 + vertex 1.5775 1.69209 2.55381 + vertex 1.5732 1.68646 2.55498 + endloop + endfacet + facet normal 0.119442 0.113007 0.986389 + outer loop + vertex 1.5732 1.68646 2.55498 + vertex 1.5775 1.69209 2.55381 + vertex 1.57258 1.69206 2.55441 + endloop + endfacet + facet normal 0.119805 0.093355 0.988399 + outer loop + vertex 1.5775 1.69209 2.55381 + vertex 1.57724 1.69705 2.55337 + vertex 1.57258 1.69206 2.55441 + endloop + endfacet + facet normal 0.11667 0.0963019 0.988491 + outer loop + vertex 1.57258 1.69206 2.55441 + vertex 1.57724 1.69705 2.55337 + vertex 1.57235 1.6972 2.55394 + endloop + endfacet + facet normal 0.1164 0.0825971 0.989762 + outer loop + vertex 1.57724 1.69705 2.55337 + vertex 1.57676 1.70214 2.55301 + vertex 1.57235 1.6972 2.55394 + endloop + endfacet + facet normal 0.101594 0.0959118 0.990192 + outer loop + vertex 1.57235 1.6972 2.55394 + vertex 1.57676 1.70214 2.55301 + vertex 1.57223 1.70216 2.55347 + endloop + endfacet + facet normal 0.101636 0.0872363 0.990989 + outer loop + vertex 1.57676 1.70214 2.55301 + vertex 1.57601 1.70624 2.55272 + vertex 1.57223 1.70216 2.55347 + endloop + endfacet + facet normal 0.0765455 0.110413 0.990934 + outer loop + vertex 1.57223 1.70216 2.55347 + vertex 1.57601 1.70624 2.55272 + vertex 1.57237 1.70712 2.5529 + endloop + endfacet + facet normal 0.0804534 0.127117 0.988619 + outer loop + vertex 1.57601 1.70624 2.55272 + vertex 1.57719 1.71123 2.55198 + vertex 1.57237 1.70712 2.5529 + endloop + endfacet + facet normal 0.0899633 0.11611 0.989154 + outer loop + vertex 1.57237 1.70712 2.5529 + vertex 1.57719 1.71123 2.55198 + vertex 1.57233 1.71219 2.55231 + endloop + endfacet + facet normal 0.0873317 0.102176 0.990925 + outer loop + vertex 1.57719 1.71123 2.55198 + vertex 1.57618 1.71646 2.55153 + vertex 1.57233 1.71219 2.55231 + endloop + endfacet + facet normal 0.0718704 0.116049 0.99064 + outer loop + vertex 1.57233 1.71219 2.55231 + vertex 1.57618 1.71646 2.55153 + vertex 1.57168 1.71692 2.55181 + endloop + endfacet + facet normal 0.0707129 0.103913 0.992069 + outer loop + vertex 1.57618 1.71646 2.55153 + vertex 1.57511 1.72071 2.55116 + vertex 1.57168 1.71692 2.55181 + endloop + endfacet + facet normal 0.0500484 0.122482 0.991208 + outer loop + vertex 1.57168 1.71692 2.55181 + vertex 1.57511 1.72071 2.55116 + vertex 1.57068 1.72106 2.55134 + endloop + endfacet + facet normal 0.112051 0.154879 0.981558 + outer loop + vertex 1.57421 1.72448 2.55073 + vertex 1.57793 1.72361 2.55044 + vertex 1.57865 1.72772 2.54971 + endloop + endfacet + facet normal 0.114293 0.15187 0.98177 + outer loop + vertex 1.57335 1.72834 2.55023 + vertex 1.57421 1.72448 2.55073 + vertex 1.57865 1.72772 2.54971 + endloop + endfacet + facet normal 0.0503185 0.126102 0.99074 + outer loop + vertex 1.57511 1.72071 2.55116 + vertex 1.57421 1.72448 2.55073 + vertex 1.57068 1.72106 2.55134 + endloop + endfacet + facet normal 0.108591 0.139204 0.984292 + outer loop + vertex 1.57793 1.72361 2.55044 + vertex 1.57421 1.72448 2.55073 + vertex 1.57511 1.72071 2.55116 + endloop + endfacet + facet normal 0.110715 0.117288 0.986907 + outer loop + vertex 1.57865 1.72772 2.54971 + vertex 1.57747 1.73228 2.5493 + vertex 1.57335 1.72834 2.55023 + endloop + endfacet + facet normal -0.0147451 0.14905 0.98872 + outer loop + vertex 1.57254 1.79503 2.54066 + vertex 1.5773 1.79737 2.54038 + vertex 1.57367 1.79888 2.5401 + endloop + endfacet + facet normal -0.00403445 0.173971 0.984743 + outer loop + vertex 1.5773 1.79737 2.54038 + vertex 1.57774 1.80216 2.53953 + vertex 1.57367 1.79888 2.5401 + endloop + endfacet + facet normal 0.00991141 0.157144 0.987526 + outer loop + vertex 1.57367 1.79888 2.5401 + vertex 1.57774 1.80216 2.53953 + vertex 1.573 1.8027 2.5395 + endloop + endfacet + facet normal 0.0114639 0.17068 0.98526 + outer loop + vertex 1.57774 1.80216 2.53953 + vertex 1.57748 1.80704 2.53869 + vertex 1.573 1.8027 2.5395 + endloop + endfacet + facet normal 0.0165157 0.165614 0.986052 + outer loop + vertex 1.573 1.8027 2.5395 + vertex 1.57748 1.80704 2.53869 + vertex 1.57262 1.80729 2.53873 + endloop + endfacet + facet normal 0.0171007 0.177016 0.984059 + outer loop + vertex 1.57748 1.80704 2.53869 + vertex 1.57703 1.81198 2.53781 + vertex 1.57262 1.80729 2.53873 + endloop + endfacet + facet normal 0.021826 0.172701 0.984732 + outer loop + vertex 1.57262 1.80729 2.53873 + vertex 1.57703 1.81198 2.53781 + vertex 1.57192 1.81184 2.53795 + endloop + endfacet + facet normal 0.0213476 0.187562 0.982021 + outer loop + vertex 1.57703 1.81198 2.53781 + vertex 1.57591 1.81732 2.53681 + vertex 1.57192 1.81184 2.53795 + endloop + endfacet + facet normal 0.185351 0.515471 0.836621 + outer loop + vertex 1.5738 2.09967 2.46596 + vertex 1.5786 2.09867 2.46552 + vertex 1.576 2.10271 2.4636 + endloop + endfacet + facet normal 0.206138 0.502681 0.839535 + outer loop + vertex 1.57115 2.10302 2.46461 + vertex 1.5738 2.09967 2.46596 + vertex 1.576 2.10271 2.4636 + endloop + endfacet + facet normal 0.172696 0.410827 0.895208 + outer loop + vertex 1.57599 2.09573 2.46735 + vertex 1.5738 2.09967 2.46596 + vertex 1.57061 2.09678 2.46791 + endloop + endfacet + facet normal 0.168613 0.409115 0.896769 + outer loop + vertex 1.5786 2.09867 2.46552 + vertex 1.5738 2.09967 2.46596 + vertex 1.57599 2.09573 2.46735 + endloop + endfacet + facet normal 0.211796 0.717189 0.663915 + outer loop + vertex 1.57922 2.10449 2.46141 + vertex 1.57758 2.10666 2.45959 + vertex 1.57564 2.10557 2.46139 + endloop + endfacet + facet normal 0.180795 0.616957 0.765948 + outer loop + vertex 1.57564 2.10557 2.46139 + vertex 1.576 2.10271 2.4636 + vertex 1.57922 2.10449 2.46141 + endloop + endfacet + facet normal 0.200485 0.616146 0.761689 + outer loop + vertex 1.57564 2.10557 2.46139 + vertex 1.5721 2.10573 2.46219 + vertex 1.576 2.10271 2.4636 + endloop + endfacet + facet normal 0.19759 0.613687 0.764426 + outer loop + vertex 1.5721 2.10573 2.46219 + vertex 1.57115 2.10302 2.46461 + vertex 1.576 2.10271 2.4636 + endloop + endfacet + facet normal 0.209835 0.871544 0.443148 + outer loop + vertex 1.57278 2.10971 2.45694 + vertex 1.57841 2.10877 2.45611 + vertex 1.57501 2.11096 2.45343 + endloop + endfacet + facet normal 0.214528 0.869288 0.445328 + outer loop + vertex 1.57104 2.11128 2.45471 + vertex 1.57278 2.10971 2.45694 + vertex 1.57501 2.11096 2.45343 + endloop + endfacet + facet normal 0.19137 0.733713 0.651953 + outer loop + vertex 1.57758 2.10666 2.45959 + vertex 1.57416 2.10763 2.4595 + vertex 1.57564 2.10557 2.46139 + endloop + endfacet + facet normal 0.215782 0.810267 0.54489 + outer loop + vertex 1.57758 2.10666 2.45959 + vertex 1.57841 2.10877 2.45611 + vertex 1.57416 2.10763 2.4595 + endloop + endfacet + facet normal 0.214624 0.811314 0.543789 + outer loop + vertex 1.57841 2.10877 2.45611 + vertex 1.57278 2.10971 2.45694 + vertex 1.57416 2.10763 2.4595 + endloop + endfacet + facet normal 0.182238 0.731638 0.656883 + outer loop + vertex 1.57564 2.10557 2.46139 + vertex 1.57416 2.10763 2.4595 + vertex 1.5721 2.10573 2.46219 + endloop + endfacet + facet normal -0.00318095 -0.0795106 0.996829 + outer loop + vertex 1.58 2.11677 2.45 + vertex 1.575 2.11697 2.45 + vertex 1.57753 2.11293 2.44969 + endloop + endfacet + facet normal 0.283274 0.10347 0.953441 + outer loop + vertex 1.57753 2.11293 2.44969 + vertex 1.575 2.11697 2.45 + vertex 1.57151 2.11326 2.45144 + endloop + endfacet + facet normal 0.236797 0.815527 0.528056 + outer loop + vertex 1.57501 2.11096 2.45343 + vertex 1.57151 2.11326 2.45144 + vertex 1.57104 2.11128 2.45471 + endloop + endfacet + facet normal 0.208005 0.800823 0.56162 + outer loop + vertex 1.57753 2.11293 2.44969 + vertex 1.57151 2.11326 2.45144 + vertex 1.57501 2.11096 2.45343 + endloop + endfacet + facet normal 0.175536 0.724922 0.666089 + outer loop + vertex 1.58117 0.918111 2.45078 + vertex 1.585 0.917899 2.45 + vertex 1.58531 0.918443 2.44933 + endloop + endfacet + facet normal 0.132204 -0.575175 0.807277 + outer loop + vertex 1.58117 0.918111 2.45078 + vertex 1.57727 0.917173 2.45075 + vertex 1.585 0.917899 2.45 + endloop + endfacet + facet normal 0.133682 -0.679268 0.721613 + outer loop + vertex 1.57727 0.917173 2.45075 + vertex 1.58 0.916915 2.45 + vertex 1.585 0.917899 2.45 + endloop + endfacet + facet normal 0.205112 -0.867002 0.454133 + outer loop + vertex 1.58117 0.918111 2.45078 + vertex 1.57834 0.91861 2.45301 + vertex 1.57727 0.917173 2.45075 + endloop + endfacet + facet normal 0.230191 -0.857301 0.460486 + outer loop + vertex 1.58531 0.918443 2.44933 + vertex 1.58242 0.919814 2.45333 + vertex 1.58117 0.918111 2.45078 + endloop + endfacet + facet normal 0.216917 -0.857269 0.466944 + outer loop + vertex 1.57834 0.91861 2.45301 + vertex 1.58117 0.918111 2.45078 + vertex 1.58242 0.919814 2.45333 + endloop + endfacet + facet normal 0.214751 -0.852485 0.476604 + outer loop + vertex 1.57834 0.91861 2.45301 + vertex 1.58242 0.919814 2.45333 + vertex 1.57742 0.920212 2.45629 + endloop + endfacet + facet normal 0.231692 -0.832922 0.502554 + outer loop + vertex 1.57742 0.920212 2.45629 + vertex 1.58242 0.919814 2.45333 + vertex 1.58115 0.922144 2.45777 + endloop + endfacet + facet normal 0.201588 -0.777102 0.596217 + outer loop + vertex 1.58052 0.924785 2.46143 + vertex 1.58115 0.922144 2.45777 + vertex 1.58431 0.923998 2.45912 + endloop + endfacet + facet normal 0.232743 -0.768813 0.595615 + outer loop + vertex 1.58052 0.924785 2.46143 + vertex 1.57607 0.922579 2.46032 + vertex 1.58115 0.922144 2.45777 + endloop + endfacet + facet normal 0.20402 -0.812691 0.545811 + outer loop + vertex 1.57607 0.922579 2.46032 + vertex 1.57742 0.920212 2.45629 + vertex 1.58115 0.922144 2.45777 + endloop + endfacet + facet normal 0.2109 -0.74405 0.633965 + outer loop + vertex 1.58052 0.924785 2.46143 + vertex 1.57673 0.925052 2.463 + vertex 1.57607 0.922579 2.46032 + endloop + endfacet + facet normal 0.224637 -0.748234 0.624247 + outer loop + vertex 1.58431 0.923998 2.45912 + vertex 1.58368 0.925561 2.46122 + vertex 1.58052 0.924785 2.46143 + endloop + endfacet + facet normal 0.191107 -0.610017 0.768998 + outer loop + vertex 1.57673 0.925052 2.463 + vertex 1.57913 0.927351 2.46423 + vertex 1.57525 0.92714 2.46502 + endloop + endfacet + facet normal 0.252857 -0.647743 0.718674 + outer loop + vertex 1.58052 0.924785 2.46143 + vertex 1.57913 0.927351 2.46423 + vertex 1.57673 0.925052 2.463 + endloop + endfacet + facet normal 0.225823 -0.660007 0.716515 + outer loop + vertex 1.58052 0.924785 2.46143 + vertex 1.58354 0.927785 2.46324 + vertex 1.57913 0.927351 2.46423 + endloop + endfacet + facet normal 0.207556 -0.650229 0.730837 + outer loop + vertex 1.58052 0.924785 2.46143 + vertex 1.58368 0.925561 2.46122 + vertex 1.58354 0.927785 2.46324 + endloop + endfacet + facet normal 0.199411 -0.512518 0.835201 + outer loop + vertex 1.57913 0.927351 2.46423 + vertex 1.57827 0.930333 2.46626 + vertex 1.57525 0.92714 2.46502 + endloop + endfacet + facet normal 0.233797 -0.555999 0.797624 + outer loop + vertex 1.58354 0.927785 2.46324 + vertex 1.58163 0.930083 2.4654 + vertex 1.57913 0.927351 2.46423 + endloop + endfacet + facet normal 0.176123 -0.519731 0.835979 + outer loop + vertex 1.58163 0.930083 2.4654 + vertex 1.57827 0.930333 2.46626 + vertex 1.57913 0.927351 2.46423 + endloop + endfacet + facet normal 0.195528 -0.424782 0.883928 + outer loop + vertex 1.58163 0.930083 2.4654 + vertex 1.58291 0.934071 2.46703 + vertex 1.57827 0.930333 2.46626 + endloop + endfacet + facet normal 0.161777 -0.24413 0.956153 + outer loop + vertex 1.57908 1.06291 2.50552 + vertex 1.57819 1.0653 2.50628 + vertex 1.57528 1.06128 2.50575 + endloop + endfacet + facet normal 0.163084 -0.243613 0.956063 + outer loop + vertex 1.58146 1.06566 2.50582 + vertex 1.57819 1.0653 2.50628 + vertex 1.57908 1.06291 2.50552 + endloop + endfacet + facet normal 0.0417633 -0.16567 0.985297 + outer loop + vertex 1.58329 1.18355 2.532 + vertex 1.58267 1.18811 2.53279 + vertex 1.57801 1.18334 2.53219 + endloop + endfacet + facet normal 0.0499534 -0.173455 0.983574 + outer loop + vertex 1.57801 1.18334 2.53219 + vertex 1.58267 1.18811 2.53279 + vertex 1.57747 1.18806 2.53305 + endloop + endfacet + facet normal 0.0499581 -0.177939 0.982772 + outer loop + vertex 1.58267 1.18811 2.53279 + vertex 1.58238 1.19312 2.53372 + vertex 1.57747 1.18806 2.53305 + endloop + endfacet + facet normal 0.0521892 -0.180035 0.982275 + outer loop + vertex 1.57747 1.18806 2.53305 + vertex 1.58238 1.19312 2.53372 + vertex 1.57717 1.19295 2.53396 + endloop + endfacet + facet normal 0.0525497 -0.195513 0.979292 + outer loop + vertex 1.58238 1.19312 2.53372 + vertex 1.58187 1.19878 2.53487 + vertex 1.57717 1.19295 2.53396 + endloop + endfacet + facet normal 0.0365166 -0.183076 0.98242 + outer loop + vertex 1.57717 1.19295 2.53396 + vertex 1.58187 1.19878 2.53487 + vertex 1.57639 1.19669 2.53469 + endloop + endfacet + facet normal 0.0118449 -0.196005 0.980531 + outer loop + vertex 1.58132 1.20245 2.53575 + vertex 1.57952 1.20431 2.53615 + vertex 1.57732 1.20086 2.53548 + endloop + endfacet + facet normal 0.0255272 -0.22909 0.973071 + outer loop + vertex 1.58132 1.20245 2.53575 + vertex 1.57732 1.20086 2.53548 + vertex 1.58187 1.19878 2.53487 + endloop + endfacet + facet normal 0.0415416 -0.196061 0.979711 + outer loop + vertex 1.58187 1.19878 2.53487 + vertex 1.57732 1.20086 2.53548 + vertex 1.57639 1.19669 2.53469 + endloop + endfacet + facet normal 0.0307259 -0.17828 0.9835 + outer loop + vertex 1.58132 1.20245 2.53575 + vertex 1.58311 1.20574 2.53629 + vertex 1.57952 1.20431 2.53615 + endloop + endfacet + facet normal 0.00794242 -0.193624 0.981044 + outer loop + vertex 1.57732 1.20086 2.53548 + vertex 1.57952 1.20431 2.53615 + vertex 1.57581 1.20447 2.53621 + endloop + endfacet + facet normal 0.00887401 -0.172692 0.984936 + outer loop + vertex 1.57952 1.20431 2.53615 + vertex 1.57955 1.20823 2.53683 + vertex 1.57581 1.20447 2.53621 + endloop + endfacet + facet normal 0.0284872 -0.172772 0.98455 + outer loop + vertex 1.57952 1.20431 2.53615 + vertex 1.58311 1.20574 2.53629 + vertex 1.57955 1.20823 2.53683 + endloop + endfacet + facet normal 0.0475316 -0.146233 0.988108 + outer loop + vertex 1.58311 1.20574 2.53629 + vertex 1.584 1.20961 2.53682 + vertex 1.57955 1.20823 2.53683 + endloop + endfacet + facet normal 0.0473228 -0.145562 0.988217 + outer loop + vertex 1.584 1.20961 2.53682 + vertex 1.58314 1.21326 2.5374 + vertex 1.57955 1.20823 2.53683 + endloop + endfacet + facet normal 0.0683084 -0.160159 0.984725 + outer loop + vertex 1.57955 1.20823 2.53683 + vertex 1.58314 1.21326 2.5374 + vertex 1.57805 1.21297 2.53771 + endloop + endfacet + facet normal 0.0682056 -0.157925 0.985093 + outer loop + vertex 1.58314 1.21326 2.5374 + vertex 1.58262 1.21802 2.5382 + vertex 1.57805 1.21297 2.53771 + endloop + endfacet + facet normal 0.080551 -0.168845 0.982346 + outer loop + vertex 1.57805 1.21297 2.53771 + vertex 1.58262 1.21802 2.5382 + vertex 1.57756 1.21796 2.5386 + endloop + endfacet + facet normal 0.0805529 -0.165289 0.98295 + outer loop + vertex 1.58262 1.21802 2.5382 + vertex 1.58252 1.22305 2.53905 + vertex 1.57756 1.21796 2.5386 + endloop + endfacet + facet normal 0.0863641 -0.170827 0.981509 + outer loop + vertex 1.57756 1.21796 2.5386 + vertex 1.58252 1.22305 2.53905 + vertex 1.5774 1.22289 2.53948 + endloop + endfacet + facet normal 0.0864891 -0.17832 0.980164 + outer loop + vertex 1.58252 1.22305 2.53905 + vertex 1.5824 1.22832 2.54002 + vertex 1.5774 1.22289 2.53948 + endloop + endfacet + facet normal 0.0995449 -0.138194 0.98539 + outer loop + vertex 1.57825 1.23845 2.54204 + vertex 1.58256 1.24307 2.54225 + vertex 1.5777 1.24305 2.54274 + endloop + endfacet + facet normal 0.0996231 -0.130766 0.986395 + outer loop + vertex 1.58256 1.24307 2.54225 + vertex 1.58253 1.24803 2.54292 + vertex 1.5777 1.24305 2.54274 + endloop + endfacet + facet normal 0.115564 -0.1461 0.982497 + outer loop + vertex 1.5777 1.24305 2.54274 + vertex 1.58253 1.24803 2.54292 + vertex 1.57754 1.24799 2.5435 + endloop + endfacet + facet normal 0.115616 -0.139883 0.983395 + outer loop + vertex 1.58253 1.24803 2.54292 + vertex 1.58258 1.25307 2.54363 + vertex 1.57754 1.24799 2.5435 + endloop + endfacet + facet normal 0.122037 -0.146224 0.981695 + outer loop + vertex 1.57754 1.24799 2.5435 + vertex 1.58258 1.25307 2.54363 + vertex 1.57747 1.25312 2.54427 + endloop + endfacet + facet normal 0.122226 -0.139633 0.982631 + outer loop + vertex 1.58258 1.25307 2.54363 + vertex 1.58264 1.2582 2.54435 + vertex 1.57747 1.25312 2.54427 + endloop + endfacet + facet normal 0.130642 -0.148166 0.980296 + outer loop + vertex 1.57747 1.25312 2.54427 + vertex 1.58264 1.2582 2.54435 + vertex 1.57692 1.2587 2.54518 + endloop + endfacet + facet normal 0.146997 0.136725 0.979642 + outer loop + vertex 1.57901 1.76267 2.54501 + vertex 1.58346 1.75894 2.54486 + vertex 1.5836 1.76355 2.5442 + endloop + endfacet + facet normal 0.148918 0.127499 0.980595 + outer loop + vertex 1.5836 1.76355 2.5442 + vertex 1.58251 1.76717 2.54389 + vertex 1.57901 1.76267 2.54501 + endloop + endfacet + facet normal 0.120078 0.150124 0.981348 + outer loop + vertex 1.57901 1.76267 2.54501 + vertex 1.58251 1.76717 2.54389 + vertex 1.57768 1.76744 2.54444 + endloop + endfacet + facet normal 0.11905 0.123933 0.985123 + outer loop + vertex 1.58251 1.76717 2.54389 + vertex 1.58205 1.77195 2.54335 + vertex 1.57768 1.76744 2.54444 + endloop + endfacet + facet normal 0.104257 0.138254 0.984894 + outer loop + vertex 1.57768 1.76744 2.54444 + vertex 1.58205 1.77195 2.54335 + vertex 1.57725 1.77215 2.54383 + endloop + endfacet + facet normal 0.103434 0.108931 0.988653 + outer loop + vertex 1.58205 1.77195 2.54335 + vertex 1.58163 1.77696 2.54284 + vertex 1.57725 1.77215 2.54383 + endloop + endfacet + facet normal 0.0788597 0.131214 0.988212 + outer loop + vertex 1.57725 1.77215 2.54383 + vertex 1.58163 1.77696 2.54284 + vertex 1.57717 1.77694 2.5432 + endloop + endfacet + facet normal 0.0791941 0.105869 0.991222 + outer loop + vertex 1.58163 1.77696 2.54284 + vertex 1.58096 1.78103 2.54246 + vertex 1.57717 1.77694 2.5432 + endloop + endfacet + facet normal 0.051727 0.131127 0.990015 + outer loop + vertex 1.57717 1.77694 2.5432 + vertex 1.58096 1.78103 2.54246 + vertex 1.57731 1.78186 2.54254 + endloop + endfacet + facet normal 0.05091 0.127473 0.990535 + outer loop + vertex 1.58096 1.78103 2.54246 + vertex 1.58219 1.78598 2.54176 + vertex 1.57731 1.78186 2.54254 + endloop + endfacet + facet normal 0.0488997 0.129813 0.990332 + outer loop + vertex 1.57731 1.78186 2.54254 + vertex 1.58219 1.78598 2.54176 + vertex 1.57718 1.78691 2.54188 + endloop + endfacet + facet normal 0.043006 0.09764 0.994292 + outer loop + vertex 1.58219 1.78598 2.54176 + vertex 1.58136 1.79089 2.54131 + vertex 1.57718 1.78691 2.54188 + endloop + endfacet + facet normal -0.0355592 0.184164 0.982252 + outer loop + vertex 1.58056 1.79704 2.54056 + vertex 1.5773 1.79737 2.54038 + vertex 1.57832 1.7948 2.5409 + endloop + endfacet + facet normal -0.0026316 0.152246 0.988339 + outer loop + vertex 1.57832 1.7948 2.5409 + vertex 1.58089 1.79448 2.54095 + vertex 1.58056 1.79704 2.54056 + endloop + endfacet + facet normal -0.00638627 0.123126 0.99237 + outer loop + vertex 1.57832 1.7948 2.5409 + vertex 1.57705 1.79157 2.54129 + vertex 1.58089 1.79448 2.54095 + endloop + endfacet + facet normal 0.0108965 0.100537 0.994874 + outer loop + vertex 1.57705 1.79157 2.54129 + vertex 1.58136 1.79089 2.54131 + vertex 1.58089 1.79448 2.54095 + endloop + endfacet + facet normal 0.0476093 0.202493 0.978126 + outer loop + vertex 1.58056 1.79704 2.54056 + vertex 1.58327 1.79733 2.54037 + vertex 1.58301 1.80123 2.53957 + endloop + endfacet + facet normal -0.0287742 0.245072 0.969078 + outer loop + vertex 1.58056 1.79704 2.54056 + vertex 1.58301 1.80123 2.53957 + vertex 1.5773 1.79737 2.54038 + endloop + endfacet + facet normal 0.023348 0.171501 0.984907 + outer loop + vertex 1.5773 1.79737 2.54038 + vertex 1.58301 1.80123 2.53957 + vertex 1.57774 1.80216 2.53953 + endloop + endfacet + facet normal 0.0527045 0.159073 0.985859 + outer loop + vertex 1.58327 1.79733 2.54037 + vertex 1.58056 1.79704 2.54056 + vertex 1.58089 1.79448 2.54095 + endloop + endfacet + facet normal 0.0225918 0.167232 0.985659 + outer loop + vertex 1.58301 1.80123 2.53957 + vertex 1.58234 1.80677 2.53865 + vertex 1.57774 1.80216 2.53953 + endloop + endfacet + facet normal 0.0186637 0.171033 0.985088 + outer loop + vertex 1.57774 1.80216 2.53953 + vertex 1.58234 1.80677 2.53865 + vertex 1.57748 1.80704 2.53869 + endloop + endfacet + facet normal 0.0185967 0.169759 0.98531 + outer loop + vertex 1.58234 1.80677 2.53865 + vertex 1.58202 1.81166 2.53781 + vertex 1.57748 1.80704 2.53869 + endloop + endfacet + facet normal 0.0114768 0.176532 0.984228 + outer loop + vertex 1.57748 1.80704 2.53869 + vertex 1.58202 1.81166 2.53781 + vertex 1.57703 1.81198 2.53781 + endloop + endfacet + facet normal 0.0113288 0.174164 0.984651 + outer loop + vertex 1.58202 1.81166 2.53781 + vertex 1.58153 1.81641 2.53697 + vertex 1.57703 1.81198 2.53781 + endloop + endfacet + facet normal 0.0016977 0.183613 0.982997 + outer loop + vertex 1.57703 1.81198 2.53781 + vertex 1.58153 1.81641 2.53697 + vertex 1.57591 1.81732 2.53681 + endloop + endfacet + facet normal -0.0169817 0.187738 0.982072 + outer loop + vertex 1.58071 1.82336 2.53567 + vertex 1.57744 1.82447 2.5354 + vertex 1.57806 1.82129 2.53602 + endloop + endfacet + facet normal -0.0209687 0.192663 0.981041 + outer loop + vertex 1.57806 1.82129 2.53602 + vertex 1.58107 1.82045 2.53625 + vertex 1.58071 1.82336 2.53567 + endloop + endfacet + facet normal -0.0170622 0.206004 0.978402 + outer loop + vertex 1.57806 1.82129 2.53602 + vertex 1.57591 1.81732 2.53681 + vertex 1.58107 1.82045 2.53625 + endloop + endfacet + facet normal 0.000709371 0.177706 0.984083 + outer loop + vertex 1.57591 1.81732 2.53681 + vertex 1.58153 1.81641 2.53697 + vertex 1.58107 1.82045 2.53625 + endloop + endfacet + facet normal 0.00915154 0.20109 0.97953 + outer loop + vertex 1.58071 1.82336 2.53567 + vertex 1.58441 1.82365 2.53557 + vertex 1.58277 1.82724 2.53485 + endloop + endfacet + facet normal -0.00892067 0.210283 0.9776 + outer loop + vertex 1.58071 1.82336 2.53567 + vertex 1.58277 1.82724 2.53485 + vertex 1.57744 1.82447 2.5354 + endloop + endfacet + facet normal 0.00591826 0.182815 0.98313 + outer loop + vertex 1.57744 1.82447 2.5354 + vertex 1.58277 1.82724 2.53485 + vertex 1.57881 1.82855 2.53463 + endloop + endfacet + facet normal 0.00954471 0.19633 0.980491 + outer loop + vertex 1.58441 1.82365 2.53557 + vertex 1.58071 1.82336 2.53567 + vertex 1.58107 1.82045 2.53625 + endloop + endfacet + facet normal 0.00812336 0.189318 0.981882 + outer loop + vertex 1.58277 1.82724 2.53485 + vertex 1.58259 1.83217 2.5339 + vertex 1.57881 1.82855 2.53463 + endloop + endfacet + facet normal 0.0115159 0.185902 0.982501 + outer loop + vertex 1.57881 1.82855 2.53463 + vertex 1.58259 1.83217 2.5339 + vertex 1.57783 1.83228 2.53394 + endloop + endfacet + facet normal 0.0115521 0.187685 0.982161 + outer loop + vertex 1.58259 1.83217 2.5339 + vertex 1.58194 1.83678 2.53303 + vertex 1.57783 1.83228 2.53394 + endloop + endfacet + facet normal 0.0113759 0.187841 0.982134 + outer loop + vertex 1.57783 1.83228 2.53394 + vertex 1.58194 1.83678 2.53303 + vertex 1.57694 1.83697 2.53305 + endloop + endfacet + facet normal 0.0115303 0.19195 0.981337 + outer loop + vertex 1.58194 1.83678 2.53303 + vertex 1.58132 1.84185 2.53205 + vertex 1.57694 1.83697 2.53305 + endloop + endfacet + facet normal 0.0167819 0.187404 0.98214 + outer loop + vertex 1.57694 1.83697 2.53305 + vertex 1.58132 1.84185 2.53205 + vertex 1.57515 1.84193 2.53214 + endloop + endfacet + facet normal -0.0124706 0.215133 0.976505 + outer loop + vertex 1.5792 1.84573 2.53123 + vertex 1.58313 1.84587 2.53125 + vertex 1.58272 1.84893 2.53057 + endloop + endfacet + facet normal 0.00319647 0.19862 0.980071 + outer loop + vertex 1.57776 1.84988 2.53039 + vertex 1.5792 1.84573 2.53123 + vertex 1.58272 1.84893 2.53057 + endloop + endfacet + facet normal 0.0170695 0.215184 0.976424 + outer loop + vertex 1.58132 1.84185 2.53205 + vertex 1.5792 1.84573 2.53123 + vertex 1.57515 1.84193 2.53214 + endloop + endfacet + facet normal -0.0119444 0.20007 0.979709 + outer loop + vertex 1.58313 1.84587 2.53125 + vertex 1.5792 1.84573 2.53123 + vertex 1.58132 1.84185 2.53205 + endloop + endfacet + facet normal 0.00574912 0.211535 0.977353 + outer loop + vertex 1.58272 1.84893 2.53057 + vertex 1.58272 1.85294 2.5297 + vertex 1.57776 1.84988 2.53039 + endloop + endfacet + facet normal 0.0111041 0.203255 0.979063 + outer loop + vertex 1.57776 1.84988 2.53039 + vertex 1.58272 1.85294 2.5297 + vertex 1.57867 1.85398 2.52953 + endloop + endfacet + facet normal 0.164825 0.503682 0.84802 + outer loop + vertex 1.5786 2.09867 2.46552 + vertex 1.58259 2.09759 2.46538 + vertex 1.58192 2.10102 2.46348 + endloop + endfacet + facet normal 0.16269 0.505908 0.847106 + outer loop + vertex 1.576 2.10271 2.4636 + vertex 1.5786 2.09867 2.46552 + vertex 1.58192 2.10102 2.46348 + endloop + endfacet + facet normal 0.161361 0.414765 0.895507 + outer loop + vertex 1.58105 2.09466 2.46694 + vertex 1.5786 2.09867 2.46552 + vertex 1.57599 2.09573 2.46735 + endloop + endfacet + facet normal 0.140148 0.404684 0.903653 + outer loop + vertex 1.58259 2.09759 2.46538 + vertex 1.5786 2.09867 2.46552 + vertex 1.58105 2.09466 2.46694 + endloop + endfacet + facet normal 0.181652 0.727908 0.661175 + outer loop + vertex 1.57922 2.10449 2.46141 + vertex 1.58388 2.10391 2.46077 + vertex 1.58127 2.10635 2.4588 + endloop + endfacet + facet normal 0.203354 0.714983 0.668915 + outer loop + vertex 1.57758 2.10666 2.45959 + vertex 1.57922 2.10449 2.46141 + vertex 1.58127 2.10635 2.4588 + endloop + endfacet + facet normal 0.190051 0.607093 0.771569 + outer loop + vertex 1.58192 2.10102 2.46348 + vertex 1.57922 2.10449 2.46141 + vertex 1.576 2.10271 2.4636 + endloop + endfacet + facet normal 0.182013 0.603603 0.776231 + outer loop + vertex 1.58388 2.10391 2.46077 + vertex 1.57922 2.10449 2.46141 + vertex 1.58192 2.10102 2.46348 + endloop + endfacet + facet normal 0.0641077 0.863438 0.500365 + outer loop + vertex 1.58433 2.11032 2.45199 + vertex 1.58205 2.112 2.44939 + vertex 1.57935 2.11073 2.45192 + endloop + endfacet + facet normal 0.20231 0.869346 0.450897 + outer loop + vertex 1.57935 2.11073 2.45192 + vertex 1.57501 2.11096 2.45343 + vertex 1.57841 2.10877 2.45611 + endloop + endfacet + facet normal 0.067896 0.898187 0.43434 + outer loop + vertex 1.57935 2.11073 2.45192 + vertex 1.57841 2.10877 2.45611 + vertex 1.58433 2.11032 2.45199 + endloop + endfacet + facet normal 0.171896 0.81556 0.552551 + outer loop + vertex 1.58433 2.11032 2.45199 + vertex 1.57841 2.10877 2.45611 + vertex 1.58345 2.10782 2.45595 + endloop + endfacet + facet normal 0.184889 0.819211 0.542871 + outer loop + vertex 1.58127 2.10635 2.4588 + vertex 1.57841 2.10877 2.45611 + vertex 1.57758 2.10666 2.45959 + endloop + endfacet + facet normal 0.171845 0.815196 0.553105 + outer loop + vertex 1.58345 2.10782 2.45595 + vertex 1.57841 2.10877 2.45611 + vertex 1.58127 2.10635 2.4588 + endloop + endfacet + facet normal -0.0405945 0.52069 0.85278 + outer loop + vertex 1.585 2.11703 2.445 + vertex 1.58 2.11664 2.445 + vertex 1.58324 2.11416 2.44667 + endloop + endfacet + facet normal 0.61526 0.788059 -0.0204793 + outer loop + vertex 1.58324 2.11416 2.44667 + vertex 1.58 2.11664 2.445 + vertex 1.58 2.11677 2.45 + endloop + endfacet + facet normal 0.199045 0.774732 0.600142 + outer loop + vertex 1.58205 2.112 2.44939 + vertex 1.57753 2.11293 2.44969 + vertex 1.57935 2.11073 2.45192 + endloop + endfacet + facet normal 0.192898 0.72583 0.660273 + outer loop + vertex 1.58205 2.112 2.44939 + vertex 1.58324 2.11416 2.44667 + vertex 1.57753 2.11293 2.44969 + endloop + endfacet + facet normal 0.494795 -0.381591 0.780747 + outer loop + vertex 1.58324 2.11416 2.44667 + vertex 1.58 2.11677 2.45 + vertex 1.57753 2.11293 2.44969 + endloop + endfacet + facet normal 0.240677 0.782652 0.574047 + outer loop + vertex 1.57935 2.11073 2.45192 + vertex 1.57753 2.11293 2.44969 + vertex 1.57501 2.11096 2.45343 + endloop + endfacet + facet normal 0.171426 -0.937738 0.302093 + outer loop + vertex 1.59 0.917648 2.445 + vertex 1.5886 0.917849 2.44642 + vertex 1.585 0.916734 2.445 + endloop + endfacet + facet normal 0.207572 -0.952701 0.22198 + outer loop + vertex 1.5886 0.917849 2.44642 + vertex 1.585 0.917899 2.45 + vertex 1.585 0.916734 2.445 + endloop + endfacet + facet normal 0.64108 0.426398 0.638123 + outer loop + vertex 1.5886 0.917849 2.44642 + vertex 1.58531 0.918443 2.44933 + vertex 1.585 0.917899 2.45 + endloop + endfacet + facet normal 0.166807 -0.911974 0.374806 + outer loop + vertex 1.58975 0.918894 2.44845 + vertex 1.58531 0.918443 2.44933 + vertex 1.5886 0.917849 2.44642 + endloop + endfacet + facet normal 0.178747 -0.872039 0.455628 + outer loop + vertex 1.58531 0.918443 2.44933 + vertex 1.58975 0.918894 2.44845 + vertex 1.58808 0.919927 2.45108 + endloop + endfacet + facet normal 0.191791 -0.877463 0.43963 + outer loop + vertex 1.58242 0.919814 2.45333 + vertex 1.58531 0.918443 2.44933 + vertex 1.58808 0.919927 2.45108 + endloop + endfacet + facet normal 0.213489 -0.841581 0.496148 + outer loop + vertex 1.58808 0.919927 2.45108 + vertex 1.58638 0.921984 2.4553 + vertex 1.58242 0.919814 2.45333 + endloop + endfacet + facet normal 0.210562 -0.839916 0.500205 + outer loop + vertex 1.58638 0.921984 2.4553 + vertex 1.58115 0.922144 2.45777 + vertex 1.58242 0.919814 2.45333 + endloop + endfacet + facet normal 0.235348 -0.801176 0.550208 + outer loop + vertex 1.58638 0.921984 2.4553 + vertex 1.58431 0.923998 2.45912 + vertex 1.58115 0.922144 2.45777 + endloop + endfacet + facet normal 0.213537 -0.811566 0.54384 + outer loop + vertex 1.58773 0.923943 2.4577 + vertex 1.58431 0.923998 2.45912 + vertex 1.58638 0.921984 2.4553 + endloop + endfacet + facet normal 0.249696 -0.737217 0.627824 + outer loop + vertex 1.58431 0.923998 2.45912 + vertex 1.58773 0.923943 2.4577 + vertex 1.58715 0.926121 2.46048 + endloop + endfacet + facet normal 0.251958 -0.738611 0.625277 + outer loop + vertex 1.58368 0.925561 2.46122 + vertex 1.58431 0.923998 2.45912 + vertex 1.58715 0.926121 2.46048 + endloop + endfacet + facet normal 0.25701 -0.640614 0.723574 + outer loop + vertex 1.58715 0.926121 2.46048 + vertex 1.58354 0.927785 2.46324 + vertex 1.58368 0.925561 2.46122 + endloop + endfacet + facet normal 0.248145 -0.650429 0.71789 + outer loop + vertex 1.58899 0.92991 2.46328 + vertex 1.58354 0.927785 2.46324 + vertex 1.58715 0.926121 2.46048 + endloop + endfacet + facet normal 0.208052 -0.549365 0.809267 + outer loop + vertex 1.58354 0.927785 2.46324 + vertex 1.58899 0.92991 2.46328 + vertex 1.5855 0.931609 2.46533 + endloop + endfacet + facet normal 0.233697 -0.556066 0.797607 + outer loop + vertex 1.58163 0.930083 2.4654 + vertex 1.58354 0.927785 2.46324 + vertex 1.5855 0.931609 2.46533 + endloop + endfacet + facet normal 0.182504 -0.422246 0.887919 + outer loop + vertex 1.5855 0.931609 2.46533 + vertex 1.58291 0.934071 2.46703 + vertex 1.58163 0.930083 2.4654 + endloop + endfacet + facet normal 0.174562 -0.429346 0.886109 + outer loop + vertex 1.58809 0.935319 2.46662 + vertex 1.58291 0.934071 2.46703 + vertex 1.5855 0.931609 2.46533 + endloop + endfacet + facet normal 0.0240801 -0.210504 0.977296 + outer loop + vertex 1.58234 1.12254 2.51959 + vertex 1.58712 1.12601 2.52022 + vertex 1.5824 1.1265 2.52045 + endloop + endfacet + facet normal 0.0222047 -0.226973 0.973648 + outer loop + vertex 1.5824 1.1265 2.52045 + vertex 1.58712 1.12601 2.52022 + vertex 1.5856 1.1297 2.52112 + endloop + endfacet + facet normal 0.0270857 -0.231596 0.972435 + outer loop + vertex 1.58167 1.12922 2.52111 + vertex 1.5824 1.1265 2.52045 + vertex 1.5856 1.1297 2.52112 + endloop + endfacet + facet normal 0.0290186 -0.247324 0.968498 + outer loop + vertex 1.5856 1.1297 2.52112 + vertex 1.58321 1.13305 2.52205 + vertex 1.58167 1.12922 2.52111 + endloop + endfacet + facet normal 0.024617 -0.250287 0.967859 + outer loop + vertex 1.58951 1.13341 2.52198 + vertex 1.58321 1.13305 2.52205 + vertex 1.5856 1.1297 2.52112 + endloop + endfacet + facet normal 0.022916 -0.218558 0.975555 + outer loop + vertex 1.58951 1.13341 2.52198 + vertex 1.58802 1.13807 2.52306 + vertex 1.58321 1.13305 2.52205 + endloop + endfacet + facet normal 0.0355537 -0.230062 0.972526 + outer loop + vertex 1.58321 1.13305 2.52205 + vertex 1.58802 1.13807 2.52306 + vertex 1.58263 1.13812 2.52327 + endloop + endfacet + facet normal 0.0357958 -0.216766 0.975567 + outer loop + vertex 1.58802 1.13807 2.52306 + vertex 1.58747 1.14286 2.52414 + vertex 1.58263 1.13812 2.52327 + endloop + endfacet + facet normal 0.0344937 -0.215498 0.975895 + outer loop + vertex 1.58263 1.13812 2.52327 + vertex 1.58747 1.14286 2.52414 + vertex 1.58232 1.1428 2.52431 + endloop + endfacet + facet normal 0.0345267 -0.221264 0.974603 + outer loop + vertex 1.58747 1.14286 2.52414 + vertex 1.58678 1.14712 2.52513 + vertex 1.58232 1.1428 2.52431 + endloop + endfacet + facet normal 0.0240947 -0.210979 0.977194 + outer loop + vertex 1.58232 1.1428 2.52431 + vertex 1.58678 1.14712 2.52513 + vertex 1.58183 1.14691 2.52521 + endloop + endfacet + facet normal 0.0244367 -0.220113 0.975168 + outer loop + vertex 1.58183 1.14691 2.52521 + vertex 1.58678 1.14712 2.52513 + vertex 1.58561 1.1507 2.52597 + endloop + endfacet + facet normal 0.0227553 -0.218518 0.975568 + outer loop + vertex 1.58073 1.1503 2.526 + vertex 1.58183 1.14691 2.52521 + vertex 1.58561 1.1507 2.52597 + endloop + endfacet + facet normal 0.0221521 -0.211053 0.977224 + outer loop + vertex 1.58561 1.1507 2.52597 + vertex 1.58416 1.15421 2.52676 + vertex 1.58073 1.1503 2.526 + endloop + endfacet + facet normal 0.0293414 -0.208163 0.977654 + outer loop + vertex 1.58919 1.15457 2.52669 + vertex 1.58416 1.15421 2.52676 + vertex 1.58561 1.1507 2.52597 + endloop + endfacet + facet normal 0.0271674 -0.176567 0.983914 + outer loop + vertex 1.58919 1.15457 2.52669 + vertex 1.58823 1.15855 2.52743 + vertex 1.58416 1.15421 2.52676 + endloop + endfacet + facet normal 0.0445016 -0.192292 0.980328 + outer loop + vertex 1.58416 1.15421 2.52676 + vertex 1.58823 1.15855 2.52743 + vertex 1.58297 1.15829 2.52761 + endloop + endfacet + facet normal 0.0433683 -0.166281 0.985124 + outer loop + vertex 1.58823 1.15855 2.52743 + vertex 1.58768 1.16313 2.52822 + vertex 1.58297 1.15829 2.52761 + endloop + endfacet + facet normal 0.057222 -0.179363 0.982117 + outer loop + vertex 1.58297 1.15829 2.52761 + vertex 1.58768 1.16313 2.52822 + vertex 1.58253 1.16306 2.52851 + endloop + endfacet + facet normal 0.05718 -0.164982 0.984638 + outer loop + vertex 1.58768 1.16313 2.52822 + vertex 1.58753 1.1681 2.52907 + vertex 1.58253 1.16306 2.52851 + endloop + endfacet + facet normal 0.0640928 -0.17167 0.983067 + outer loop + vertex 1.58253 1.16306 2.52851 + vertex 1.58753 1.1681 2.52907 + vertex 1.5824 1.168 2.52938 + endloop + endfacet + facet normal 0.0641002 -0.17256 0.982911 + outer loop + vertex 1.58753 1.1681 2.52907 + vertex 1.58743 1.17342 2.53001 + vertex 1.5824 1.168 2.52938 + endloop + endfacet + facet normal 0.0601796 -0.169017 0.983774 + outer loop + vertex 1.5824 1.168 2.52938 + vertex 1.58743 1.17342 2.53001 + vertex 1.5818 1.17235 2.53017 + endloop + endfacet + facet normal 0.0670023 -0.206064 0.976242 + outer loop + vertex 1.5818 1.17235 2.53017 + vertex 1.58743 1.17342 2.53001 + vertex 1.58518 1.17633 2.53078 + endloop + endfacet + facet normal 0.0262214 -0.172672 0.98463 + outer loop + vertex 1.58063 1.17593 2.53083 + vertex 1.5818 1.17235 2.53017 + vertex 1.58518 1.17633 2.53078 + endloop + endfacet + facet normal 0.0258742 -0.168675 0.985332 + outer loop + vertex 1.58518 1.17633 2.53078 + vertex 1.58407 1.17958 2.53136 + vertex 1.58063 1.17593 2.53083 + endloop + endfacet + facet normal 0.0449057 -0.16226 0.985726 + outer loop + vertex 1.58749 1.17948 2.53119 + vertex 1.58407 1.17958 2.53136 + vertex 1.58518 1.17633 2.53078 + endloop + endfacet + facet normal 0.0463061 -0.121497 0.991511 + outer loop + vertex 1.58749 1.17948 2.53119 + vertex 1.58826 1.18345 2.53164 + vertex 1.58407 1.17958 2.53136 + endloop + endfacet + facet normal 0.0688709 -0.145528 0.986954 + outer loop + vertex 1.58407 1.17958 2.53136 + vertex 1.58826 1.18345 2.53164 + vertex 1.58329 1.18355 2.532 + endloop + endfacet + facet normal 0.0690012 -0.141236 0.987568 + outer loop + vertex 1.58826 1.18345 2.53164 + vertex 1.58771 1.18822 2.53236 + vertex 1.58329 1.18355 2.532 + endloop + endfacet + facet normal 0.0881539 -0.159046 0.983328 + outer loop + vertex 1.58329 1.18355 2.532 + vertex 1.58771 1.18822 2.53236 + vertex 1.58267 1.18811 2.53279 + endloop + endfacet + facet normal 0.0881759 -0.161812 0.982874 + outer loop + vertex 1.58771 1.18822 2.53236 + vertex 1.58752 1.1931 2.53318 + vertex 1.58267 1.18811 2.53279 + endloop + endfacet + facet normal 0.10138 -0.174373 0.979447 + outer loop + vertex 1.58267 1.18811 2.53279 + vertex 1.58752 1.1931 2.53318 + vertex 1.58238 1.19312 2.53372 + endloop + endfacet + facet normal 0.101284 -0.178515 0.97871 + outer loop + vertex 1.58752 1.1931 2.53318 + vertex 1.58753 1.1982 2.53411 + vertex 1.58238 1.19312 2.53372 + endloop + endfacet + facet normal 0.112193 -0.189308 0.975487 + outer loop + vertex 1.58238 1.19312 2.53372 + vertex 1.58753 1.1982 2.53411 + vertex 1.58187 1.19878 2.53487 + endloop + endfacet + facet normal 0.0613633 -0.223723 0.972719 + outer loop + vertex 1.58416 1.20295 2.53569 + vertex 1.58132 1.20245 2.53575 + vertex 1.58187 1.19878 2.53487 + endloop + endfacet + facet normal 0.16927 -0.277766 0.945618 + outer loop + vertex 1.58416 1.20295 2.53569 + vertex 1.58187 1.19878 2.53487 + vertex 1.58779 1.2033 2.53514 + endloop + endfacet + facet normal 0.11054 -0.202416 0.973041 + outer loop + vertex 1.58779 1.2033 2.53514 + vertex 1.58187 1.19878 2.53487 + vertex 1.58753 1.1982 2.53411 + endloop + endfacet + facet normal 0.0557904 -0.191283 0.979948 + outer loop + vertex 1.58416 1.20295 2.53569 + vertex 1.58311 1.20574 2.53629 + vertex 1.58132 1.20245 2.53575 + endloop + endfacet + facet normal 0.167795 -0.248868 0.953892 + outer loop + vertex 1.58779 1.2033 2.53514 + vertex 1.58617 1.2053 2.53595 + vertex 1.58416 1.20295 2.53569 + endloop + endfacet + facet normal 0.0843639 -0.180484 0.979953 + outer loop + vertex 1.58617 1.2053 2.53595 + vertex 1.58311 1.20574 2.53629 + vertex 1.58416 1.20295 2.53569 + endloop + endfacet + facet normal 0.0903642 -0.14341 0.985529 + outer loop + vertex 1.58617 1.2053 2.53595 + vertex 1.58667 1.20845 2.53636 + vertex 1.58311 1.20574 2.53629 + endloop + endfacet + facet normal 0.101362 -0.157811 0.982253 + outer loop + vertex 1.58667 1.20845 2.53636 + vertex 1.584 1.20961 2.53682 + vertex 1.58311 1.20574 2.53629 + endloop + endfacet + facet normal 0.119606 -0.117439 0.985851 + outer loop + vertex 1.58667 1.20845 2.53636 + vertex 1.58771 1.21316 2.5368 + vertex 1.584 1.20961 2.53682 + endloop + endfacet + facet normal 0.127698 -0.125911 0.983788 + outer loop + vertex 1.584 1.20961 2.53682 + vertex 1.58771 1.21316 2.5368 + vertex 1.58314 1.21326 2.5374 + endloop + endfacet + facet normal 0.127323 -0.135728 0.982531 + outer loop + vertex 1.58771 1.21316 2.5368 + vertex 1.58741 1.21806 2.53751 + vertex 1.58314 1.21326 2.5374 + endloop + endfacet + facet normal 0.0596819 0.172089 0.983272 + outer loop + vertex 1.58234 1.80677 2.53865 + vertex 1.5859 1.81084 2.53772 + vertex 1.58202 1.81166 2.53781 + endloop + endfacet + facet normal 0.0605018 0.17606 0.982518 + outer loop + vertex 1.5859 1.81084 2.53772 + vertex 1.58671 1.81559 2.53682 + vertex 1.58202 1.81166 2.53781 + endloop + endfacet + facet normal 0.0583308 0.178573 0.982196 + outer loop + vertex 1.58202 1.81166 2.53781 + vertex 1.58671 1.81559 2.53682 + vertex 1.58153 1.81641 2.53697 + endloop + endfacet + facet normal 0.0542988 0.152225 0.986853 + outer loop + vertex 1.58671 1.81559 2.53682 + vertex 1.58535 1.82007 2.5362 + vertex 1.58153 1.81641 2.53697 + endloop + endfacet + facet normal 0.0264785 0.180475 0.983223 + outer loop + vertex 1.58153 1.81641 2.53697 + vertex 1.58535 1.82007 2.5362 + vertex 1.58107 1.82045 2.53625 + endloop + endfacet + facet normal 0.0837297 0.204428 0.975294 + outer loop + vertex 1.58441 1.82365 2.53557 + vertex 1.58809 1.82306 2.53538 + vertex 1.58846 1.8271 2.5345 + endloop + endfacet + facet normal 0.0652256 0.225128 0.972144 + outer loop + vertex 1.58277 1.82724 2.53485 + vertex 1.58441 1.82365 2.53557 + vertex 1.58846 1.8271 2.5345 + endloop + endfacet + facet normal 0.0263797 0.179332 0.983435 + outer loop + vertex 1.58535 1.82007 2.5362 + vertex 1.58441 1.82365 2.53557 + vertex 1.58107 1.82045 2.53625 + endloop + endfacet + facet normal 0.0820253 0.19292 0.97778 + outer loop + vertex 1.58809 1.82306 2.53538 + vertex 1.58441 1.82365 2.53557 + vertex 1.58535 1.82007 2.5362 + endloop + endfacet + facet normal 0.0645882 0.173415 0.982729 + outer loop + vertex 1.58846 1.8271 2.5345 + vertex 1.58733 1.83182 2.53374 + vertex 1.58277 1.82724 2.53485 + endloop + endfacet + facet normal 0.0469053 0.190472 0.980571 + outer loop + vertex 1.58277 1.82724 2.53485 + vertex 1.58733 1.83182 2.53374 + vertex 1.58259 1.83217 2.5339 + endloop + endfacet + facet normal 0.0460236 0.177444 0.983054 + outer loop + vertex 1.58733 1.83182 2.53374 + vertex 1.58669 1.83662 2.53291 + vertex 1.58259 1.83217 2.5339 + endloop + endfacet + facet normal 0.0315606 0.190349 0.981209 + outer loop + vertex 1.58259 1.83217 2.5339 + vertex 1.58669 1.83662 2.53291 + vertex 1.58194 1.83678 2.53303 + endloop + endfacet + facet normal 0.0310073 0.170728 0.98483 + outer loop + vertex 1.58669 1.83662 2.53291 + vertex 1.58549 1.84049 2.53227 + vertex 1.58194 1.83678 2.53303 + endloop + endfacet + facet normal 0.00842771 0.191588 0.981439 + outer loop + vertex 1.58194 1.83678 2.53303 + vertex 1.58549 1.84049 2.53227 + vertex 1.58132 1.84185 2.53205 + endloop + endfacet + facet normal -0.0100269 0.215452 0.976463 + outer loop + vertex 1.58587 1.84789 2.53083 + vertex 1.58272 1.84893 2.53057 + vertex 1.58313 1.84587 2.53125 + endloop + endfacet + facet normal 0.00799215 0.192127 0.981337 + outer loop + vertex 1.58313 1.84587 2.53125 + vertex 1.58654 1.84464 2.53146 + vertex 1.58587 1.84789 2.53083 + endloop + endfacet + facet normal 0.0077645 0.191519 0.981458 + outer loop + vertex 1.58313 1.84587 2.53125 + vertex 1.58132 1.84185 2.53205 + vertex 1.58654 1.84464 2.53146 + endloop + endfacet + facet normal 0.00816353 0.190801 0.981595 + outer loop + vertex 1.58132 1.84185 2.53205 + vertex 1.58549 1.84049 2.53227 + vertex 1.58654 1.84464 2.53146 + endloop + endfacet + facet normal 0.0501879 0.228087 0.972346 + outer loop + vertex 1.58587 1.84789 2.53083 + vertex 1.5889 1.84785 2.53068 + vertex 1.58823 1.85167 2.52982 + endloop + endfacet + facet normal 0.00400429 0.255524 0.966794 + outer loop + vertex 1.58587 1.84789 2.53083 + vertex 1.58823 1.85167 2.52982 + vertex 1.58272 1.84893 2.53057 + endloop + endfacet + facet normal 0.0272959 0.211496 0.976998 + outer loop + vertex 1.58272 1.84893 2.53057 + vertex 1.58823 1.85167 2.52982 + vertex 1.58272 1.85294 2.5297 + endloop + endfacet + facet normal 0.0500824 0.20031 0.978452 + outer loop + vertex 1.5889 1.84785 2.53068 + vertex 1.58587 1.84789 2.53083 + vertex 1.58654 1.84464 2.53146 + endloop + endfacet + facet normal 0.0223657 0.190495 0.981433 + outer loop + vertex 1.58823 1.85167 2.52982 + vertex 1.58715 1.85684 2.52884 + vertex 1.58272 1.85294 2.5297 + endloop + endfacet + facet normal 0.0114507 0.202405 0.979235 + outer loop + vertex 1.58272 1.85294 2.5297 + vertex 1.58715 1.85684 2.52884 + vertex 1.58244 1.85727 2.52881 + endloop + endfacet + facet normal 0.0107525 0.194863 0.980772 + outer loop + vertex 1.58715 1.85684 2.52884 + vertex 1.58675 1.86149 2.52792 + vertex 1.58244 1.85727 2.52881 + endloop + endfacet + facet normal 0.00315291 0.202323 0.979314 + outer loop + vertex 1.58244 1.85727 2.52881 + vertex 1.58675 1.86149 2.52792 + vertex 1.58186 1.86171 2.52789 + endloop + endfacet + facet normal 0.00300152 0.199089 0.979977 + outer loop + vertex 1.58675 1.86149 2.52792 + vertex 1.58634 1.86654 2.5269 + vertex 1.58186 1.86171 2.52789 + endloop + endfacet + facet normal -0.0012687 0.202896 0.979199 + outer loop + vertex 1.58186 1.86171 2.52789 + vertex 1.58634 1.86654 2.5269 + vertex 1.58073 1.86607 2.52699 + endloop + endfacet + facet normal -0.0298074 0.242507 0.969692 + outer loop + vertex 1.58428 1.87004 2.52612 + vertex 1.58795 1.87062 2.52608 + vertex 1.58777 1.8735 2.52536 + endloop + endfacet + facet normal -0.0111327 0.224715 0.974361 + outer loop + vertex 1.58333 1.87374 2.52525 + vertex 1.58428 1.87004 2.52612 + vertex 1.58777 1.8735 2.52536 + endloop + endfacet + facet normal -0.00239545 0.215916 0.976409 + outer loop + vertex 1.58634 1.86654 2.5269 + vertex 1.58428 1.87004 2.52612 + vertex 1.58073 1.86607 2.52699 + endloop + endfacet + facet normal -0.0235829 0.203941 0.978699 + outer loop + vertex 1.58795 1.87062 2.52608 + vertex 1.58428 1.87004 2.52612 + vertex 1.58634 1.86654 2.5269 + endloop + endfacet + facet normal -0.0101288 0.241142 0.970437 + outer loop + vertex 1.58777 1.8735 2.52536 + vertex 1.58764 1.87743 2.52438 + vertex 1.58333 1.87374 2.52525 + endloop + endfacet + facet normal 0.0053617 0.22403 0.974567 + outer loop + vertex 1.58333 1.87374 2.52525 + vertex 1.58764 1.87743 2.52438 + vertex 1.58283 1.87787 2.52431 + endloop + endfacet + facet normal 0.00548033 0.225303 0.974273 + outer loop + vertex 1.58764 1.87743 2.52438 + vertex 1.58692 1.88187 2.52336 + vertex 1.58283 1.87787 2.52431 + endloop + endfacet + facet normal 0.0137169 0.217312 0.976006 + outer loop + vertex 1.58283 1.87787 2.52431 + vertex 1.58692 1.88187 2.52336 + vertex 1.58216 1.88205 2.52339 + endloop + endfacet + facet normal 0.0137723 0.218814 0.975669 + outer loop + vertex 1.58692 1.88187 2.52336 + vertex 1.58581 1.8871 2.5222 + vertex 1.58216 1.88205 2.52339 + endloop + endfacet + facet normal 0.0297896 0.207742 0.97773 + outer loop + vertex 1.58216 1.88205 2.52339 + vertex 1.58581 1.8871 2.5222 + vertex 1.5807 1.88542 2.52271 + endloop + endfacet + facet normal 0.0298441 0.207587 0.977761 + outer loop + vertex 1.58086 1.88985 2.52177 + vertex 1.5807 1.88542 2.52271 + vertex 1.58581 1.8871 2.5222 + endloop + endfacet + facet normal 0.175787 0.429646 0.885722 + outer loop + vertex 1.58259 2.09759 2.46538 + vertex 1.58491 2.09524 2.46606 + vertex 1.58626 2.09783 2.46454 + endloop + endfacet + facet normal 0.162362 0.503518 0.848592 + outer loop + vertex 1.58259 2.09759 2.46538 + vertex 1.58626 2.09783 2.46454 + vertex 1.58192 2.10102 2.46348 + endloop + endfacet + facet normal 0.17961 0.522081 0.833769 + outer loop + vertex 1.58192 2.10102 2.46348 + vertex 1.58626 2.09783 2.46454 + vertex 1.58729 2.10104 2.46231 + endloop + endfacet + facet normal 0.143357 0.403101 0.903858 + outer loop + vertex 1.58491 2.09524 2.46606 + vertex 1.58259 2.09759 2.46538 + vertex 1.58105 2.09466 2.46694 + endloop + endfacet + facet normal 0.161716 0.738326 0.65477 + outer loop + vertex 1.58388 2.10391 2.46077 + vertex 1.5885 2.10386 2.45969 + vertex 1.5857 2.10598 2.45798 + endloop + endfacet + facet normal 0.182328 0.728211 0.660655 + outer loop + vertex 1.58127 2.10635 2.4588 + vertex 1.58388 2.10391 2.46077 + vertex 1.5857 2.10598 2.45798 + endloop + endfacet + facet normal 0.166212 0.611692 0.773438 + outer loop + vertex 1.58729 2.10104 2.46231 + vertex 1.58388 2.10391 2.46077 + vertex 1.58192 2.10102 2.46348 + endloop + endfacet + facet normal 0.184804 0.625491 0.758029 + outer loop + vertex 1.5885 2.10386 2.45969 + vertex 1.58388 2.10391 2.46077 + vertex 1.58729 2.10104 2.46231 + endloop + endfacet + facet normal -0.418419 0.550913 0.722095 + outer loop + vertex 1.58706 2.115 2.45 + vertex 1.58205 2.112 2.44939 + vertex 1.58433 2.11032 2.45199 + endloop + endfacet + facet normal 0.13408 0.320491 0.937714 + outer loop + vertex 1.58706 2.115 2.45 + vertex 1.58433 2.11032 2.45199 + vertex 1.59 2.11377 2.45 + endloop + endfacet + facet normal 0.164562 0.275767 0.947033 + outer loop + vertex 1.59 2.11377 2.45 + vertex 1.58433 2.11032 2.45199 + vertex 1.58819 2.10975 2.45148 + endloop + endfacet + facet normal 0.192045 0.797734 0.571611 + outer loop + vertex 1.58819 2.10975 2.45148 + vertex 1.58433 2.11032 2.45199 + vertex 1.5878 2.10774 2.45443 + endloop + endfacet + facet normal 0.20972 0.805328 0.554495 + outer loop + vertex 1.5878 2.10774 2.45443 + vertex 1.58433 2.11032 2.45199 + vertex 1.58345 2.10782 2.45595 + endloop + endfacet + facet normal 0.169644 0.816386 0.552028 + outer loop + vertex 1.5857 2.10598 2.45798 + vertex 1.58345 2.10782 2.45595 + vertex 1.58127 2.10635 2.4588 + endloop + endfacet + facet normal 0.200392 0.826035 0.526791 + outer loop + vertex 1.5878 2.10774 2.45443 + vertex 1.58345 2.10782 2.45595 + vertex 1.5857 2.10598 2.45798 + endloop + endfacet + facet normal -0.0864584 0.984838 -0.150397 + outer loop + vertex 1.59 2.115 2.44831 + vertex 1.58324 2.11416 2.44667 + vertex 1.58706 2.115 2.45 + endloop + endfacet + facet normal -0.21057 0.886348 0.412369 + outer loop + vertex 1.59 2.115 2.44831 + vertex 1.59 2.11654 2.445 + vertex 1.58324 2.11416 2.44667 + endloop + endfacet + facet normal 0.047067 0.480324 0.875827 + outer loop + vertex 1.59 2.11654 2.445 + vertex 1.585 2.11703 2.445 + vertex 1.58324 2.11416 2.44667 + endloop + endfacet + facet normal -0.508273 0.768449 0.388774 + outer loop + vertex 1.58706 2.115 2.45 + vertex 1.58324 2.11416 2.44667 + vertex 1.58205 2.112 2.44939 + endloop + endfacet + facet normal 0.105102 -0.938125 0.329963 + outer loop + vertex 1.59478 0.92 2.45 + vertex 1.595 0.918266 2.445 + vertex 1.595 0.92 2.44993 + endloop + endfacet + facet normal 0.133994 -0.934438 0.329956 + outer loop + vertex 1.59478 0.92 2.45 + vertex 1.5886 0.917849 2.44642 + vertex 1.595 0.918266 2.445 + endloop + endfacet + facet normal 0.118668 -0.960123 0.253143 + outer loop + vertex 1.5886 0.917849 2.44642 + vertex 1.59 0.917648 2.445 + vertex 1.595 0.918266 2.445 + endloop + endfacet + facet normal 0.0667992 -0.902071 0.426387 + outer loop + vertex 1.59478 0.92 2.45 + vertex 1.58975 0.918894 2.44845 + vertex 1.5886 0.917849 2.44642 + endloop + endfacet + facet normal -0.22546 0.973566 0.0365709 + outer loop + vertex 1.58975 0.918894 2.44845 + vertex 1.59478 0.92 2.45 + vertex 1.595 0.920051 2.45 + endloop + endfacet + facet normal 0.0799835 -0.909648 0.407606 + outer loop + vertex 1.58975 0.918894 2.44845 + vertex 1.595 0.920051 2.45 + vertex 1.58808 0.919927 2.45108 + endloop + endfacet + facet normal 0.111993 -0.769772 0.628418 + outer loop + vertex 1.58808 0.919927 2.45108 + vertex 1.595 0.920051 2.45 + vertex 1.59149 0.921539 2.45245 + endloop + endfacet + facet normal 0.229029 -0.821712 0.521858 + outer loop + vertex 1.59008 0.923072 2.45548 + vertex 1.59149 0.921539 2.45245 + vertex 1.59393 0.923357 2.45424 + endloop + endfacet + facet normal 0.217953 -0.826449 0.519113 + outer loop + vertex 1.59008 0.923072 2.45548 + vertex 1.58638 0.921984 2.4553 + vertex 1.59149 0.921539 2.45245 + endloop + endfacet + facet normal 0.202028 -0.845875 0.49364 + outer loop + vertex 1.58638 0.921984 2.4553 + vertex 1.58808 0.919927 2.45108 + vertex 1.59149 0.921539 2.45245 + endloop + endfacet + facet normal 0.212313 -0.811477 0.544453 + outer loop + vertex 1.59008 0.923072 2.45548 + vertex 1.58773 0.923943 2.4577 + vertex 1.58638 0.921984 2.4553 + endloop + endfacet + facet normal 0.238609 -0.795015 0.557689 + outer loop + vertex 1.59393 0.923357 2.45424 + vertex 1.59116 0.924875 2.45759 + vertex 1.59008 0.923072 2.45548 + endloop + endfacet + facet normal 0.233316 -0.794812 0.560212 + outer loop + vertex 1.58773 0.923943 2.4577 + vertex 1.59008 0.923072 2.45548 + vertex 1.59116 0.924875 2.45759 + endloop + endfacet + facet normal 0.222022 -0.74542 0.628534 + outer loop + vertex 1.58773 0.923943 2.4577 + vertex 1.59116 0.924875 2.45759 + vertex 1.58715 0.926121 2.46048 + endloop + endfacet + facet normal 0.229693 -0.737092 0.63556 + outer loop + vertex 1.58715 0.926121 2.46048 + vertex 1.59116 0.924875 2.45759 + vertex 1.59206 0.927442 2.46024 + endloop + endfacet + facet normal 0.209714 -0.644553 0.735236 + outer loop + vertex 1.59206 0.927442 2.46024 + vertex 1.58899 0.92991 2.46328 + vertex 1.58715 0.926121 2.46048 + endloop + endfacet + facet normal 0.192062 -0.657867 0.728233 + outer loop + vertex 1.59407 0.930357 2.46234 + vertex 1.58899 0.92991 2.46328 + vertex 1.59206 0.927442 2.46024 + endloop + endfacet + facet normal 0.211609 -0.54472 0.811481 + outer loop + vertex 1.58924 0.933122 2.46537 + vertex 1.5855 0.931609 2.46533 + vertex 1.58899 0.92991 2.46328 + endloop + endfacet + facet normal 0.208784 -0.5449 0.812092 + outer loop + vertex 1.58924 0.933122 2.46537 + vertex 1.58899 0.92991 2.46328 + vertex 1.59326 0.933681 2.46471 + endloop + endfacet + facet normal 0.198309 -0.536226 0.820448 + outer loop + vertex 1.59326 0.933681 2.46471 + vertex 1.58899 0.92991 2.46328 + vertex 1.59407 0.930357 2.46234 + endloop + endfacet + facet normal 0.161228 -0.422106 0.892094 + outer loop + vertex 1.58924 0.933122 2.46537 + vertex 1.58809 0.935319 2.46662 + vertex 1.5855 0.931609 2.46533 + endloop + endfacet + facet normal 0.173418 -0.282639 0.94342 + outer loop + vertex 1.59328 0.985416 2.48147 + vertex 1.58812 0.984055 2.48201 + vertex 1.59025 0.981429 2.48083 + endloop + endfacet + facet normal 0.0312361 -0.243883 0.969301 + outer loop + vertex 1.59421 1.09412 2.51211 + vertex 1.59276 1.09827 2.5132 + vertex 1.58848 1.09343 2.51212 + endloop + endfacet + facet normal 0.0369552 -0.248629 0.967894 + outer loop + vertex 1.58848 1.09343 2.51212 + vertex 1.59276 1.09827 2.5132 + vertex 1.58756 1.09809 2.51335 + endloop + endfacet + facet normal 0.0367983 -0.242839 0.969368 + outer loop + vertex 1.59276 1.09827 2.5132 + vertex 1.59129 1.10178 2.51413 + vertex 1.58756 1.09809 2.51335 + endloop + endfacet + facet normal 0.0333152 -0.239521 0.970319 + outer loop + vertex 1.58756 1.09809 2.51335 + vertex 1.59129 1.10178 2.51413 + vertex 1.58721 1.1025 2.51445 + endloop + endfacet + facet normal 0.0297462 -0.257685 0.965771 + outer loop + vertex 1.59129 1.10178 2.51413 + vertex 1.59198 1.10597 2.51523 + vertex 1.58721 1.1025 2.51445 + endloop + endfacet + facet normal 0.00847525 -0.230083 0.973134 + outer loop + vertex 1.58721 1.1025 2.51445 + vertex 1.59198 1.10597 2.51523 + vertex 1.58722 1.10657 2.51541 + endloop + endfacet + facet normal 0.00658011 -0.243942 0.969767 + outer loop + vertex 1.58722 1.10657 2.51541 + vertex 1.59198 1.10597 2.51523 + vertex 1.59052 1.10975 2.51619 + endloop + endfacet + facet normal 0.000977298 -0.238457 0.971153 + outer loop + vertex 1.58675 1.10951 2.51613 + vertex 1.58722 1.10657 2.51541 + vertex 1.59052 1.10975 2.51619 + endloop + endfacet + facet normal 0.00198084 -0.253579 0.967313 + outer loop + vertex 1.59052 1.10975 2.51619 + vertex 1.58832 1.11327 2.51712 + vertex 1.58675 1.10951 2.51613 + endloop + endfacet + facet normal 0.0139831 -0.246518 0.969037 + outer loop + vertex 1.59443 1.11342 2.51707 + vertex 1.58832 1.11327 2.51712 + vertex 1.59052 1.10975 2.51619 + endloop + endfacet + facet normal 0.0134467 -0.221312 0.97511 + outer loop + vertex 1.59443 1.11342 2.51707 + vertex 1.59295 1.1183 2.51819 + vertex 1.58832 1.11327 2.51712 + endloop + endfacet + facet normal 0.0339488 -0.239197 0.970377 + outer loop + vertex 1.58832 1.11327 2.51712 + vertex 1.59295 1.1183 2.51819 + vertex 1.58743 1.11819 2.51836 + endloop + endfacet + facet normal 0.0338989 -0.23501 0.971402 + outer loop + vertex 1.59295 1.1183 2.51819 + vertex 1.59189 1.12387 2.51958 + vertex 1.58743 1.11819 2.51836 + endloop + endfacet + facet normal 0.0257484 -0.228963 0.973094 + outer loop + vertex 1.58743 1.11819 2.51836 + vertex 1.59189 1.12387 2.51958 + vertex 1.58628 1.12184 2.51925 + endloop + endfacet + facet normal 0.000368636 -0.237226 0.971454 + outer loop + vertex 1.59127 1.12759 2.52061 + vertex 1.58942 1.12949 2.52107 + vertex 1.58712 1.12601 2.52022 + endloop + endfacet + facet normal 0.0115113 -0.264784 0.964239 + outer loop + vertex 1.59127 1.12759 2.52061 + vertex 1.58712 1.12601 2.52022 + vertex 1.59189 1.12387 2.51958 + endloop + endfacet + facet normal 0.0270804 -0.232494 0.972221 + outer loop + vertex 1.59189 1.12387 2.51958 + vertex 1.58712 1.12601 2.52022 + vertex 1.58628 1.12184 2.51925 + endloop + endfacet + facet normal 0.01417 -0.22446 0.97438 + outer loop + vertex 1.59127 1.12759 2.52061 + vertex 1.59327 1.13096 2.52135 + vertex 1.58942 1.12949 2.52107 + endloop + endfacet + facet normal -0.00126683 -0.236206 0.971702 + outer loop + vertex 1.58712 1.12601 2.52022 + vertex 1.58942 1.12949 2.52107 + vertex 1.5856 1.1297 2.52112 + endloop + endfacet + facet normal -0.000623677 -0.225126 0.974329 + outer loop + vertex 1.58942 1.12949 2.52107 + vertex 1.58951 1.13341 2.52198 + vertex 1.5856 1.1297 2.52112 + endloop + endfacet + facet normal 0.0145672 -0.225455 0.974145 + outer loop + vertex 1.58942 1.12949 2.52107 + vertex 1.59327 1.13096 2.52135 + vertex 1.58951 1.13341 2.52198 + endloop + endfacet + facet normal 0.033829 -0.197261 0.979767 + outer loop + vertex 1.59327 1.13096 2.52135 + vertex 1.59419 1.13487 2.52211 + vertex 1.58951 1.13341 2.52198 + endloop + endfacet + facet normal 0.0337294 -0.196949 0.979833 + outer loop + vertex 1.59419 1.13487 2.52211 + vertex 1.59318 1.13835 2.52285 + vertex 1.58951 1.13341 2.52198 + endloop + endfacet + facet normal 0.0515611 -0.209577 0.976432 + outer loop + vertex 1.58951 1.13341 2.52198 + vertex 1.59318 1.13835 2.52285 + vertex 1.58802 1.13807 2.52306 + endloop + endfacet + facet normal 0.0512294 -0.202418 0.977958 + outer loop + vertex 1.59318 1.13835 2.52285 + vertex 1.59268 1.14303 2.52384 + vertex 1.58802 1.13807 2.52306 + endloop + endfacet + facet normal 0.0634602 -0.21345 0.974891 + outer loop + vertex 1.58802 1.13807 2.52306 + vertex 1.59268 1.14303 2.52384 + vertex 1.58747 1.14286 2.52414 + endloop + endfacet + facet normal 0.063578 -0.219997 0.973427 + outer loop + vertex 1.59268 1.14303 2.52384 + vertex 1.59251 1.14818 2.52502 + vertex 1.58747 1.14286 2.52414 + endloop + endfacet + facet normal 0.0602682 -0.217005 0.974308 + outer loop + vertex 1.58747 1.14286 2.52414 + vertex 1.59251 1.14818 2.52502 + vertex 1.58678 1.14712 2.52513 + endloop + endfacet + facet normal 0.0667046 -0.25256 0.965279 + outer loop + vertex 1.58678 1.14712 2.52513 + vertex 1.59251 1.14818 2.52502 + vertex 1.5904 1.15119 2.52595 + endloop + endfacet + facet normal 0.026976 -0.219315 0.975281 + outer loop + vertex 1.58561 1.1507 2.52597 + vertex 1.58678 1.14712 2.52513 + vertex 1.5904 1.15119 2.52595 + endloop + endfacet + facet normal 0.0255044 -0.204766 0.978479 + outer loop + vertex 1.5904 1.15119 2.52595 + vertex 1.58919 1.15457 2.52669 + vertex 1.58561 1.1507 2.52597 + endloop + endfacet + facet normal 0.0559518 -0.194061 0.979393 + outer loop + vertex 1.5934 1.15486 2.5265 + vertex 1.58919 1.15457 2.52669 + vertex 1.5904 1.15119 2.52595 + endloop + endfacet + facet normal 0.0527732 -0.143342 0.988265 + outer loop + vertex 1.5934 1.15486 2.5265 + vertex 1.59296 1.15868 2.52708 + vertex 1.58919 1.15457 2.52669 + endloop + endfacet + facet normal 0.0764991 -0.164648 0.983381 + outer loop + vertex 1.58919 1.15457 2.52669 + vertex 1.59296 1.15868 2.52708 + vertex 1.58823 1.15855 2.52743 + endloop + endfacet + facet normal 0.0760785 -0.136968 0.98765 + outer loop + vertex 1.59296 1.15868 2.52708 + vertex 1.59263 1.16324 2.52774 + vertex 1.58823 1.15855 2.52743 + endloop + endfacet + facet normal 0.0998363 -0.158884 0.982236 + outer loop + vertex 1.58823 1.15855 2.52743 + vertex 1.59263 1.16324 2.52774 + vertex 1.58768 1.16313 2.52822 + endloop + endfacet + facet normal 0.0997091 -0.143158 0.984664 + outer loop + vertex 1.59263 1.16324 2.52774 + vertex 1.59249 1.16813 2.52846 + vertex 1.58768 1.16313 2.52822 + endloop + endfacet + facet normal 0.119886 -0.162319 0.979428 + outer loop + vertex 1.58768 1.16313 2.52822 + vertex 1.59249 1.16813 2.52846 + vertex 1.58753 1.1681 2.52907 + endloop + endfacet + facet normal 0.120077 -0.148528 0.981591 + outer loop + vertex 1.59249 1.16813 2.52846 + vertex 1.59262 1.17325 2.52922 + vertex 1.58753 1.1681 2.52907 + endloop + endfacet + facet normal 0.141662 -0.169664 0.975267 + outer loop + vertex 1.58753 1.1681 2.52907 + vertex 1.59262 1.17325 2.52922 + vertex 1.58743 1.17342 2.53001 + endloop + endfacet + facet normal 0.0858018 -0.191909 0.977655 + outer loop + vertex 1.58884 1.17767 2.53072 + vertex 1.58518 1.17633 2.53078 + vertex 1.58743 1.17342 2.53001 + endloop + endfacet + facet normal 0.20445 -0.227155 0.952156 + outer loop + vertex 1.58884 1.17767 2.53072 + vertex 1.58743 1.17342 2.53001 + vertex 1.59289 1.17865 2.53008 + endloop + endfacet + facet normal 0.142083 -0.162343 0.976451 + outer loop + vertex 1.59289 1.17865 2.53008 + vertex 1.58743 1.17342 2.53001 + vertex 1.59262 1.17325 2.52922 + endloop + endfacet + facet normal 0.0854814 -0.191025 0.977856 + outer loop + vertex 1.58884 1.17767 2.53072 + vertex 1.58749 1.17948 2.53119 + vertex 1.58518 1.17633 2.53078 + endloop + endfacet + facet normal 0.299468 0.0235107 0.953817 + outer loop + vertex 1.5936 1.57465 2.55552 + vertex 1.59488 1.57905 2.55501 + vertex 1.59128 1.57655 2.5562 + endloop + endfacet + facet normal 0.29845 0.0251129 0.954095 + outer loop + vertex 1.59128 1.57655 2.5562 + vertex 1.59488 1.57905 2.55501 + vertex 1.59072 1.58059 2.55627 + endloop + endfacet + facet normal 0.113041 0.18953 0.975346 + outer loop + vertex 1.58823 1.85167 2.52982 + vertex 1.59333 1.84853 2.52984 + vertex 1.59348 1.85307 2.52894 + endloop + endfacet + facet normal 0.117794 0.173242 0.97781 + outer loop + vertex 1.59348 1.85307 2.52894 + vertex 1.59202 1.85682 2.52845 + vertex 1.58823 1.85167 2.52982 + endloop + endfacet + facet normal 0.079003 0.201388 0.97632 + outer loop + vertex 1.58823 1.85167 2.52982 + vertex 1.59202 1.85682 2.52845 + vertex 1.58715 1.85684 2.52884 + endloop + endfacet + facet normal 0.0793744 0.166237 0.982886 + outer loop + vertex 1.59202 1.85682 2.52845 + vertex 1.59064 1.86065 2.52791 + vertex 1.58715 1.85684 2.52884 + endloop + endfacet + facet normal 0.0443413 0.19746 0.979308 + outer loop + vertex 1.58715 1.85684 2.52884 + vertex 1.59064 1.86065 2.52791 + vertex 1.58675 1.86149 2.52792 + endloop + endfacet + facet normal 0.0442456 0.197012 0.979402 + outer loop + vertex 1.59064 1.86065 2.52791 + vertex 1.59159 1.86542 2.52691 + vertex 1.58675 1.86149 2.52792 + endloop + endfacet + facet normal 0.0401773 0.201814 0.978599 + outer loop + vertex 1.58675 1.86149 2.52792 + vertex 1.59159 1.86542 2.52691 + vertex 1.58634 1.86654 2.5269 + endloop + endfacet + facet normal -0.0117203 0.243674 0.969786 + outer loop + vertex 1.59055 1.87277 2.52558 + vertex 1.58777 1.8735 2.52536 + vertex 1.58795 1.87062 2.52608 + endloop + endfacet + facet normal 0.0249775 0.201536 0.979162 + outer loop + vertex 1.58795 1.87062 2.52608 + vertex 1.59079 1.86983 2.52618 + vertex 1.59055 1.87277 2.52558 + endloop + endfacet + facet normal 0.020867 0.187116 0.982116 + outer loop + vertex 1.58795 1.87062 2.52608 + vertex 1.58634 1.86654 2.5269 + vertex 1.59079 1.86983 2.52618 + endloop + endfacet + facet normal 0.0335095 0.170621 0.984767 + outer loop + vertex 1.58634 1.86654 2.5269 + vertex 1.59159 1.86542 2.52691 + vertex 1.59079 1.86983 2.52618 + endloop + endfacet + facet normal 0.084711 0.243898 0.966094 + outer loop + vertex 1.59055 1.87277 2.52558 + vertex 1.59332 1.87267 2.52536 + vertex 1.59286 1.87645 2.52444 + endloop + endfacet + facet normal 0.00219855 0.29271 0.956199 + outer loop + vertex 1.59055 1.87277 2.52558 + vertex 1.59286 1.87645 2.52444 + vertex 1.58777 1.8735 2.52536 + endloop + endfacet + facet normal 0.0338419 0.24233 0.969604 + outer loop + vertex 1.58777 1.8735 2.52536 + vertex 1.59286 1.87645 2.52444 + vertex 1.58764 1.87743 2.52438 + endloop + endfacet + facet normal 0.0841153 0.205568 0.975021 + outer loop + vertex 1.59332 1.87267 2.52536 + vertex 1.59055 1.87277 2.52558 + vertex 1.59079 1.86983 2.52618 + endloop + endfacet + facet normal 0.0287378 0.21558 0.976063 + outer loop + vertex 1.59286 1.87645 2.52444 + vertex 1.59178 1.88149 2.52336 + vertex 1.58764 1.87743 2.52438 + endloop + endfacet + facet normal 0.0169031 0.227052 0.973736 + outer loop + vertex 1.58764 1.87743 2.52438 + vertex 1.59178 1.88149 2.52336 + vertex 1.58692 1.88187 2.52336 + endloop + endfacet + facet normal 0.0159311 0.214409 0.976614 + outer loop + vertex 1.59178 1.88149 2.52336 + vertex 1.59054 1.88537 2.52253 + vertex 1.58692 1.88187 2.52336 + endloop + endfacet + facet normal 0.0118504 0.218433 0.97578 + outer loop + vertex 1.58692 1.88187 2.52336 + vertex 1.59054 1.88537 2.52253 + vertex 1.58581 1.8871 2.5222 + endloop + endfacet + facet normal -0.00609657 0.214843 0.97663 + outer loop + vertex 1.5908 1.89316 2.52087 + vertex 1.58742 1.89456 2.52054 + vertex 1.58808 1.89121 2.52128 + endloop + endfacet + facet normal 0.0024462 0.203456 0.979081 + outer loop + vertex 1.58808 1.89121 2.52128 + vertex 1.5916 1.88965 2.52159 + vertex 1.5908 1.89316 2.52087 + endloop + endfacet + facet normal 0.00771881 0.214899 0.976606 + outer loop + vertex 1.58808 1.89121 2.52128 + vertex 1.58581 1.8871 2.5222 + vertex 1.5916 1.88965 2.52159 + endloop + endfacet + facet normal 0.00924382 0.2116 0.977313 + outer loop + vertex 1.58581 1.8871 2.5222 + vertex 1.59054 1.88537 2.52253 + vertex 1.5916 1.88965 2.52159 + endloop + endfacet + facet normal 0.0367472 0.222822 0.974166 + outer loop + vertex 1.5908 1.89316 2.52087 + vertex 1.59402 1.89294 2.5208 + vertex 1.59335 1.89693 2.51991 + endloop + endfacet + facet normal 0.00601257 0.242582 0.970112 + outer loop + vertex 1.5908 1.89316 2.52087 + vertex 1.59335 1.89693 2.51991 + vertex 1.58742 1.89456 2.52054 + endloop + endfacet + facet normal 0.0232717 0.201822 0.979146 + outer loop + vertex 1.58742 1.89456 2.52054 + vertex 1.59335 1.89693 2.51991 + vertex 1.58877 1.89859 2.51967 + endloop + endfacet + facet normal 0.0359681 0.210702 0.976888 + outer loop + vertex 1.59402 1.89294 2.5208 + vertex 1.5908 1.89316 2.52087 + vertex 1.5916 1.88965 2.52159 + endloop + endfacet + facet normal 0.0220853 0.19865 0.979822 + outer loop + vertex 1.59335 1.89693 2.51991 + vertex 1.59238 1.90196 2.51891 + vertex 1.58877 1.89859 2.51967 + endloop + endfacet + facet normal 0.0142613 0.206688 0.978303 + outer loop + vertex 1.58877 1.89859 2.51967 + vertex 1.59238 1.90196 2.51891 + vertex 1.58765 1.90223 2.51892 + endloop + endfacet + facet normal 0.014348 0.208223 0.977976 + outer loop + vertex 1.59238 1.90196 2.51891 + vertex 1.59187 1.90644 2.51796 + vertex 1.58765 1.90223 2.51892 + endloop + endfacet + facet normal 0.0143856 0.208186 0.977983 + outer loop + vertex 1.58765 1.90223 2.51892 + vertex 1.59187 1.90644 2.51796 + vertex 1.58681 1.90676 2.51797 + endloop + endfacet + facet normal 0.0145565 0.210967 0.977385 + outer loop + vertex 1.59187 1.90644 2.51796 + vertex 1.59137 1.91155 2.51687 + vertex 1.58681 1.90676 2.51797 + endloop + endfacet + facet normal 0.0165271 0.209173 0.977739 + outer loop + vertex 1.58681 1.90676 2.51797 + vertex 1.59137 1.91155 2.51687 + vertex 1.58521 1.91143 2.517 + endloop + endfacet + facet normal -0.013149 0.247628 0.968766 + outer loop + vertex 1.58932 1.91528 2.51601 + vertex 1.59307 1.91559 2.51598 + vertex 1.59278 1.91859 2.51521 + endloop + endfacet + facet normal 0.00359686 0.23113 0.972916 + outer loop + vertex 1.58797 1.9193 2.51506 + vertex 1.58932 1.91528 2.51601 + vertex 1.59278 1.91859 2.51521 + endloop + endfacet + facet normal 0.0159588 0.23353 0.972219 + outer loop + vertex 1.59137 1.91155 2.51687 + vertex 1.58932 1.91528 2.51601 + vertex 1.58521 1.91143 2.517 + endloop + endfacet + facet normal -0.0108081 0.219589 0.975533 + outer loop + vertex 1.59307 1.91559 2.51598 + vertex 1.58932 1.91528 2.51601 + vertex 1.59137 1.91155 2.51687 + endloop + endfacet + facet normal 0.00668248 0.250888 0.967993 + outer loop + vertex 1.59278 1.91859 2.51521 + vertex 1.59265 1.92257 2.51418 + vertex 1.58797 1.9193 2.51506 + endloop + endfacet + facet normal 0.0164563 0.237753 0.971186 + outer loop + vertex 1.58797 1.9193 2.51506 + vertex 1.59265 1.92257 2.51418 + vertex 1.58863 1.92347 2.51402 + endloop + endfacet + facet normal 0.0168333 0.23936 0.970785 + outer loop + vertex 1.59265 1.92257 2.51418 + vertex 1.59188 1.92677 2.51315 + vertex 1.58863 1.92347 2.51402 + endloop + endfacet + facet normal 0.0335172 0.223748 0.97407 + outer loop + vertex 1.58863 1.92347 2.51402 + vertex 1.59188 1.92677 2.51315 + vertex 1.58699 1.92696 2.51328 + endloop + endfacet + facet normal 0.158801 0.278017 0.947359 + outer loop + vertex 1.59455 2.02505 2.48619 + vertex 1.59288 2.02957 2.48514 + vertex 1.59053 2.02632 2.48649 + endloop + endfacet + facet normal 0.162488 0.275409 0.947495 + outer loop + vertex 1.58867 2.02903 2.48602 + vertex 1.59053 2.02632 2.48649 + vertex 1.59288 2.02957 2.48514 + endloop + endfacet + facet normal 0.161312 0.292995 0.942408 + outer loop + vertex 1.59431 2.05925 2.47603 + vertex 1.59262 2.06373 2.47492 + vertex 1.59039 2.06053 2.4763 + endloop + endfacet + facet normal 0.161015 0.292003 0.942766 + outer loop + vertex 1.59039 2.06053 2.4763 + vertex 1.5905 2.05662 2.47749 + vertex 1.59431 2.05925 2.47603 + endloop + endfacet + facet normal 0.156862 0.292086 0.943441 + outer loop + vertex 1.59039 2.06053 2.4763 + vertex 1.58628 2.06011 2.47712 + vertex 1.5905 2.05662 2.47749 + endloop + endfacet + facet normal 0.158034 0.295223 0.942268 + outer loop + vertex 1.58837 2.06317 2.47581 + vertex 1.59039 2.06053 2.4763 + vertex 1.59262 2.06373 2.47492 + endloop + endfacet + facet normal 0.157882 0.296021 0.942043 + outer loop + vertex 1.58837 2.06317 2.47581 + vertex 1.59262 2.06373 2.47492 + vertex 1.58824 2.06723 2.47456 + endloop + endfacet + facet normal 0.15653 0.294181 0.942844 + outer loop + vertex 1.59039 2.06053 2.4763 + vertex 1.58837 2.06317 2.47581 + vertex 1.58628 2.06011 2.47712 + endloop + endfacet + facet normal 0.160774 0.29781 0.940989 + outer loop + vertex 1.59126 2.0855 2.46831 + vertex 1.59108 2.08955 2.46706 + vertex 1.58714 2.08697 2.46855 + endloop + endfacet + facet normal 0.184805 0.427137 0.885099 + outer loop + vertex 1.58883 2.09412 2.46577 + vertex 1.59302 2.09282 2.46552 + vertex 1.592 2.09727 2.46359 + endloop + endfacet + facet normal 0.188169 0.424237 0.885785 + outer loop + vertex 1.58626 2.09783 2.46454 + vertex 1.58883 2.09412 2.46577 + vertex 1.592 2.09727 2.46359 + endloop + endfacet + facet normal 0.160284 0.339945 0.926686 + outer loop + vertex 1.59302 2.09282 2.46552 + vertex 1.58883 2.09412 2.46577 + vertex 1.59108 2.08955 2.46706 + endloop + endfacet + facet normal 0.191465 0.596426 0.779498 + outer loop + vertex 1.59489 2.10002 2.4613 + vertex 1.59406 2.10207 2.45993 + vertex 1.59159 2.10154 2.46094 + endloop + endfacet + facet normal 0.155255 0.530627 0.833265 + outer loop + vertex 1.59159 2.10154 2.46094 + vertex 1.592 2.09727 2.46359 + vertex 1.59489 2.10002 2.4613 + endloop + endfacet + facet normal 0.199601 0.529454 0.824523 + outer loop + vertex 1.59159 2.10154 2.46094 + vertex 1.58729 2.10104 2.46231 + vertex 1.592 2.09727 2.46359 + endloop + endfacet + facet normal 0.188815 0.51904 0.833635 + outer loop + vertex 1.58729 2.10104 2.46231 + vertex 1.58626 2.09783 2.46454 + vertex 1.592 2.09727 2.46359 + endloop + endfacet + facet normal 0.243752 0.806465 0.538702 + outer loop + vertex 1.59337 2.10413 2.45779 + vertex 1.59171 2.10649 2.455 + vertex 1.58945 2.10573 2.45716 + endloop + endfacet + facet normal 0.188621 0.753632 0.629652 + outer loop + vertex 1.58945 2.10573 2.45716 + vertex 1.5857 2.10598 2.45798 + vertex 1.5885 2.10386 2.45969 + endloop + endfacet + facet normal 0.20478 0.747851 0.631493 + outer loop + vertex 1.59337 2.10413 2.45779 + vertex 1.58945 2.10573 2.45716 + vertex 1.5885 2.10386 2.45969 + endloop + endfacet + facet normal 0.231583 0.684361 0.69139 + outer loop + vertex 1.59337 2.10413 2.45779 + vertex 1.5885 2.10386 2.45969 + vertex 1.59159 2.10154 2.46094 + endloop + endfacet + facet normal 0.116165 0.735077 0.667958 + outer loop + vertex 1.59337 2.10413 2.45779 + vertex 1.59159 2.10154 2.46094 + vertex 1.59406 2.10207 2.45993 + endloop + endfacet + facet normal 0.166001 0.632327 0.756707 + outer loop + vertex 1.59159 2.10154 2.46094 + vertex 1.5885 2.10386 2.45969 + vertex 1.58729 2.10104 2.46231 + endloop + endfacet + facet normal 0.540726 0.680154 0.49498 + outer loop + vertex 1.59303 2.115 2.445 + vertex 1.59 2.115 2.44831 + vertex 1.59 2.11377 2.45 + endloop + endfacet + facet normal 0.447625 0.766892 0.459901 + outer loop + vertex 1.59303 2.115 2.445 + vertex 1.59 2.11377 2.45 + vertex 1.595 2.11385 2.445 + endloop + endfacet + facet normal 0.677208 0.277071 0.681631 + outer loop + vertex 1.595 2.11385 2.445 + vertex 1.59 2.11377 2.45 + vertex 1.59395 2.11019 2.44753 + endloop + endfacet + facet normal 0.721617 0.413164 0.555486 + outer loop + vertex 1.59395 2.11019 2.44753 + vertex 1.59 2.11377 2.45 + vertex 1.59193 2.10858 2.45135 + endloop + endfacet + facet normal 0.125975 0.293366 0.947664 + outer loop + vertex 1.59193 2.10858 2.45135 + vertex 1.59 2.11377 2.45 + vertex 1.58819 2.10975 2.45148 + endloop + endfacet + facet normal 0.195801 0.842678 0.501554 + outer loop + vertex 1.59171 2.10649 2.455 + vertex 1.5878 2.10774 2.45443 + vertex 1.58945 2.10573 2.45716 + endloop + endfacet + facet normal 0.197326 0.845213 0.496667 + outer loop + vertex 1.59171 2.10649 2.455 + vertex 1.59193 2.10858 2.45135 + vertex 1.5878 2.10774 2.45443 + endloop + endfacet + facet normal 0.264335 0.779075 0.568479 + outer loop + vertex 1.59193 2.10858 2.45135 + vertex 1.58819 2.10975 2.45148 + vertex 1.5878 2.10774 2.45443 + endloop + endfacet + facet normal 0.169563 0.839983 0.515439 + outer loop + vertex 1.58945 2.10573 2.45716 + vertex 1.5878 2.10774 2.45443 + vertex 1.5857 2.10598 2.45798 + endloop + endfacet + facet normal 0.418514 0.823453 0.383108 + outer loop + vertex 1.59303 2.115 2.445 + vertex 1.59 2.11654 2.445 + vertex 1.59 2.115 2.44831 + endloop + endfacet + facet normal 0.224664 -0.919234 0.323319 + outer loop + vertex 1.6 0.919488 2.445 + vertex 1.595 0.92 2.44993 + vertex 1.595 0.918266 2.445 + endloop + endfacet + facet normal 0.218947 0.968141 0.121509 + outer loop + vertex 1.59912 0.919684 2.44503 + vertex 1.595 0.92 2.44993 + vertex 1.6 0.919488 2.445 + endloop + endfacet + facet normal 0.543837 -0.67367 0.50041 + outer loop + vertex 1.595 0.92 2.44993 + vertex 1.59912 0.919684 2.44503 + vertex 1.59817 0.920339 2.44694 + endloop + endfacet + facet normal 0.539601 -0.680967 0.495091 + outer loop + vertex 1.595 0.920051 2.45 + vertex 1.595 0.92 2.44993 + vertex 1.59817 0.920339 2.44694 + endloop + endfacet + facet normal 0.559579 -0.646093 0.519072 + outer loop + vertex 1.59817 0.920339 2.44694 + vertex 1.59673 0.921763 2.45027 + vertex 1.595 0.920051 2.45 + endloop + endfacet + facet normal 0.354296 -0.482245 0.801195 + outer loop + vertex 1.59673 0.921763 2.45027 + vertex 1.59149 0.921539 2.45245 + vertex 1.595 0.920051 2.45 + endloop + endfacet + facet normal 0.245638 -0.827441 0.504978 + outer loop + vertex 1.59673 0.921763 2.45027 + vertex 1.59393 0.923357 2.45424 + vertex 1.59149 0.921539 2.45245 + endloop + endfacet + facet normal 0.208702 -0.847983 0.487204 + outer loop + vertex 1.59795 0.923637 2.453 + vertex 1.59393 0.923357 2.45424 + vertex 1.59673 0.921763 2.45027 + endloop + endfacet + facet normal 0.220847 -0.81614 0.533988 + outer loop + vertex 1.59393 0.923357 2.45424 + vertex 1.59795 0.923637 2.453 + vertex 1.5966 0.925803 2.45687 + endloop + endfacet + facet normal 0.210068 -0.813443 0.542385 + outer loop + vertex 1.59116 0.924875 2.45759 + vertex 1.59393 0.923357 2.45424 + vertex 1.5966 0.925803 2.45687 + endloop + endfacet + facet normal 0.165817 -0.766037 0.621042 + outer loop + vertex 1.59565 0.928245 2.46014 + vertex 1.5966 0.925803 2.45687 + vertex 1.59914 0.928296 2.45927 + endloop + endfacet + facet normal 0.187445 -0.759746 0.622616 + outer loop + vertex 1.59565 0.928245 2.46014 + vertex 1.59206 0.927442 2.46024 + vertex 1.5966 0.925803 2.45687 + endloop + endfacet + facet normal 0.210175 -0.737119 0.642248 + outer loop + vertex 1.59206 0.927442 2.46024 + vertex 1.59116 0.924875 2.45759 + vertex 1.5966 0.925803 2.45687 + endloop + endfacet + facet normal 0.166235 -0.649792 0.741712 + outer loop + vertex 1.59565 0.928245 2.46014 + vertex 1.59407 0.930357 2.46234 + vertex 1.59206 0.927442 2.46024 + endloop + endfacet + facet normal 0.189157 -0.666843 0.720791 + outer loop + vertex 1.59914 0.928296 2.45927 + vertex 1.59749 0.930125 2.4614 + vertex 1.59565 0.928245 2.46014 + endloop + endfacet + facet normal 0.160938 -0.652495 0.740506 + outer loop + vertex 1.59749 0.930125 2.4614 + vertex 1.59407 0.930357 2.46234 + vertex 1.59565 0.928245 2.46014 + endloop + endfacet + facet normal 0.190449 -0.54047 0.819525 + outer loop + vertex 1.59749 0.930125 2.4614 + vertex 1.59847 0.933522 2.46341 + vertex 1.59407 0.930357 2.46234 + endloop + endfacet + facet normal 0.188946 -0.538852 0.820937 + outer loop + vertex 1.59847 0.933522 2.46341 + vertex 1.59326 0.933681 2.46471 + vertex 1.59407 0.930357 2.46234 + endloop + endfacet + facet normal 0.177712 -0.285622 0.941721 + outer loop + vertex 1.59409 0.982969 2.48057 + vertex 1.59328 0.985416 2.48147 + vertex 1.59025 0.981429 2.48083 + endloop + endfacet + facet normal 0.177099 -0.285842 0.94177 + outer loop + vertex 1.59653 0.985685 2.48094 + vertex 1.59328 0.985416 2.48147 + vertex 1.59409 0.982969 2.48057 + endloop + endfacet + facet normal 0.0371761 -0.268617 0.962529 + outer loop + vertex 1.5907 1.07062 2.50601 + vertex 1.59183 1.06716 2.505 + vertex 1.59558 1.07095 2.50591 + endloop + endfacet + facet normal 0.0372666 -0.270095 0.962112 + outer loop + vertex 1.59558 1.07095 2.50591 + vertex 1.59414 1.07454 2.50697 + vertex 1.5907 1.07062 2.50601 + endloop + endfacet + facet normal 0.0247154 -0.274842 0.961172 + outer loop + vertex 1.59924 1.07471 2.50689 + vertex 1.59414 1.07454 2.50697 + vertex 1.59558 1.07095 2.50591 + endloop + endfacet + facet normal 0.024173 -0.255836 0.966418 + outer loop + vertex 1.59924 1.07471 2.50689 + vertex 1.59822 1.07868 2.50797 + vertex 1.59414 1.07454 2.50697 + endloop + endfacet + facet normal 0.0371046 -0.267735 0.962778 + outer loop + vertex 1.59414 1.07454 2.50697 + vertex 1.59822 1.07868 2.50797 + vertex 1.59296 1.07849 2.50812 + endloop + endfacet + facet normal 0.0367016 -0.253694 0.966588 + outer loop + vertex 1.59822 1.07868 2.50797 + vertex 1.59752 1.08293 2.50911 + vertex 1.59296 1.07849 2.50812 + endloop + endfacet + facet normal 0.0374886 -0.25445 0.966359 + outer loop + vertex 1.59296 1.07849 2.50812 + vertex 1.59752 1.08293 2.50911 + vertex 1.59236 1.08274 2.50926 + endloop + endfacet + facet normal 0.0375674 -0.257023 0.965675 + outer loop + vertex 1.59752 1.08293 2.50911 + vertex 1.59672 1.0869 2.5102 + vertex 1.59236 1.08274 2.50926 + endloop + endfacet + facet normal 0.0248232 -0.244519 0.969327 + outer loop + vertex 1.59236 1.08274 2.50926 + vertex 1.59672 1.0869 2.5102 + vertex 1.59182 1.08669 2.51027 + endloop + endfacet + facet normal 0.0251525 -0.252808 0.967189 + outer loop + vertex 1.59182 1.08669 2.51027 + vertex 1.59672 1.0869 2.5102 + vertex 1.59559 1.09045 2.51116 + endloop + endfacet + facet normal 0.0152113 -0.243449 0.969794 + outer loop + vertex 1.59085 1.0902 2.51117 + vertex 1.59182 1.08669 2.51027 + vertex 1.59559 1.09045 2.51116 + endloop + endfacet + facet normal 0.0153093 -0.245294 0.969328 + outer loop + vertex 1.59559 1.09045 2.51116 + vertex 1.59421 1.09412 2.51211 + vertex 1.59085 1.0902 2.51117 + endloop + endfacet + facet normal 0.0343566 -0.238414 0.970556 + outer loop + vertex 1.59922 1.09441 2.512 + vertex 1.59421 1.09412 2.51211 + vertex 1.59559 1.09045 2.51116 + endloop + endfacet + facet normal 0.0340315 -0.232243 0.972062 + outer loop + vertex 1.59922 1.09441 2.512 + vertex 1.59816 1.09861 2.51304 + vertex 1.59421 1.09412 2.51211 + endloop + endfacet + facet normal 0.0432029 -0.239856 0.969847 + outer loop + vertex 1.59421 1.09412 2.51211 + vertex 1.59816 1.09861 2.51304 + vertex 1.59276 1.09827 2.5132 + endloop + endfacet + facet normal 0.0440165 -0.25418 0.966155 + outer loop + vertex 1.59816 1.09861 2.51304 + vertex 1.59686 1.10389 2.51449 + vertex 1.59276 1.09827 2.5132 + endloop + endfacet + facet normal 0.0308391 -0.245222 0.968976 + outer loop + vertex 1.59276 1.09827 2.5132 + vertex 1.59686 1.10389 2.51449 + vertex 1.59129 1.10178 2.51413 + endloop + endfacet + facet normal -0.00242533 -0.260017 0.965601 + outer loop + vertex 1.59606 1.10752 2.51566 + vertex 1.59424 1.10943 2.51617 + vertex 1.59198 1.10597 2.51523 + endloop + endfacet + facet normal 0.015306 -0.303042 0.952854 + outer loop + vertex 1.59606 1.10752 2.51566 + vertex 1.59198 1.10597 2.51523 + vertex 1.59686 1.10389 2.51449 + endloop + endfacet + facet normal 0.0361364 -0.258606 0.965307 + outer loop + vertex 1.59686 1.10389 2.51449 + vertex 1.59198 1.10597 2.51523 + vertex 1.59129 1.10178 2.51413 + endloop + endfacet + facet normal 0.0264718 -0.234022 0.971871 + outer loop + vertex 1.59606 1.10752 2.51566 + vertex 1.59794 1.11084 2.51641 + vertex 1.59424 1.10943 2.51617 + endloop + endfacet + facet normal -0.0156604 -0.251935 0.967617 + outer loop + vertex 1.59198 1.10597 2.51523 + vertex 1.59424 1.10943 2.51617 + vertex 1.59052 1.10975 2.51619 + endloop + endfacet + facet normal -0.0128507 -0.219475 0.975534 + outer loop + vertex 1.59424 1.10943 2.51617 + vertex 1.59443 1.11342 2.51707 + vertex 1.59052 1.10975 2.51619 + endloop + endfacet + facet normal 0.0213327 -0.221056 0.975028 + outer loop + vertex 1.59424 1.10943 2.51617 + vertex 1.59794 1.11084 2.51641 + vertex 1.59443 1.11342 2.51707 + endloop + endfacet + facet normal 0.0472228 -0.187366 0.981154 + outer loop + vertex 1.59794 1.11084 2.51641 + vertex 1.599 1.11472 2.51709 + vertex 1.59443 1.11342 2.51707 + endloop + endfacet + facet normal 0.0473172 -0.187695 0.981087 + outer loop + vertex 1.599 1.11472 2.51709 + vertex 1.59821 1.11838 2.51783 + vertex 1.59443 1.11342 2.51707 + endloop + endfacet + facet normal 0.0701722 -0.204369 0.976376 + outer loop + vertex 1.59443 1.11342 2.51707 + vertex 1.59821 1.11838 2.51783 + vertex 1.59295 1.1183 2.51819 + endloop + endfacet + facet normal 0.0701735 -0.206896 0.975843 + outer loop + vertex 1.59821 1.11838 2.51783 + vertex 1.59768 1.12324 2.5189 + vertex 1.59295 1.1183 2.51819 + endloop + endfacet + facet normal 0.0891546 -0.224286 0.970437 + outer loop + vertex 1.59295 1.1183 2.51819 + vertex 1.59768 1.12324 2.5189 + vertex 1.59189 1.12387 2.51958 + endloop + endfacet + facet normal 0.0395799 -0.260229 0.964735 + outer loop + vertex 1.59423 1.12807 2.52062 + vertex 1.59127 1.12759 2.52061 + vertex 1.59189 1.12387 2.51958 + endloop + endfacet + facet normal 0.140948 -0.310524 0.940058 + outer loop + vertex 1.59423 1.12807 2.52062 + vertex 1.59189 1.12387 2.51958 + vertex 1.59789 1.12828 2.52013 + endloop + endfacet + facet normal 0.086972 -0.240417 0.966766 + outer loop + vertex 1.59789 1.12828 2.52013 + vertex 1.59189 1.12387 2.51958 + vertex 1.59768 1.12324 2.5189 + endloop + endfacet + facet normal 0.0357119 -0.236496 0.970976 + outer loop + vertex 1.59423 1.12807 2.52062 + vertex 1.59327 1.13096 2.52135 + vertex 1.59127 1.12759 2.52061 + endloop + endfacet + facet normal 0.140669 -0.291091 0.946297 + outer loop + vertex 1.59789 1.12828 2.52013 + vertex 1.59648 1.13047 2.52102 + vertex 1.59423 1.12807 2.52062 + endloop + endfacet + facet normal 0.0669979 -0.22635 0.971739 + outer loop + vertex 1.59648 1.13047 2.52102 + vertex 1.59327 1.13096 2.52135 + vertex 1.59423 1.12807 2.52062 + endloop + endfacet + facet normal 0.0753941 -0.177627 0.981206 + outer loop + vertex 1.59648 1.13047 2.52102 + vertex 1.59758 1.13406 2.52159 + vertex 1.59327 1.13096 2.52135 + endloop + endfacet + facet normal 0.100184 -0.211356 0.972261 + outer loop + vertex 1.59758 1.13406 2.52159 + vertex 1.59419 1.13487 2.52211 + vertex 1.59327 1.13096 2.52135 + endloop + endfacet + facet normal 0.111252 -0.169389 0.97925 + outer loop + vertex 1.59758 1.13406 2.52159 + vertex 1.59769 1.13849 2.52234 + vertex 1.59419 1.13487 2.52211 + endloop + endfacet + facet normal 0.115177 -0.173104 0.978146 + outer loop + vertex 1.59419 1.13487 2.52211 + vertex 1.59769 1.13849 2.52234 + vertex 1.59318 1.13835 2.52285 + endloop + endfacet + facet normal 0.1152 -0.175241 0.977763 + outer loop + vertex 1.59769 1.13849 2.52234 + vertex 1.59766 1.14317 2.52318 + vertex 1.59318 1.13835 2.52285 + endloop + endfacet + facet normal 0.134008 -0.192329 0.972137 + outer loop + vertex 1.59318 1.13835 2.52285 + vertex 1.59766 1.14317 2.52318 + vertex 1.59268 1.14303 2.52384 + endloop + endfacet + facet normal 0.134015 -0.194437 0.971717 + outer loop + vertex 1.59766 1.14317 2.52318 + vertex 1.59767 1.14814 2.52417 + vertex 1.59268 1.14303 2.52384 + endloop + endfacet + facet normal 0.155403 -0.214781 0.964219 + outer loop + vertex 1.59268 1.14303 2.52384 + vertex 1.59767 1.14814 2.52417 + vertex 1.59251 1.14818 2.52502 + endloop + endfacet + facet normal 0.085512 -0.239907 0.967022 + outer loop + vertex 1.59424 1.15236 2.5259 + vertex 1.5904 1.15119 2.52595 + vertex 1.59251 1.14818 2.52502 + endloop + endfacet + facet normal 0.230675 -0.291682 0.928284 + outer loop + vertex 1.59424 1.15236 2.5259 + vertex 1.59251 1.14818 2.52502 + vertex 1.59795 1.15323 2.52525 + endloop + endfacet + facet normal 0.155508 -0.212291 0.964754 + outer loop + vertex 1.59795 1.15323 2.52525 + vertex 1.59251 1.14818 2.52502 + vertex 1.59767 1.14814 2.52417 + endloop + endfacet + facet normal 0.0765879 -0.210211 0.974652 + outer loop + vertex 1.59424 1.15236 2.5259 + vertex 1.5934 1.15486 2.5265 + vertex 1.5904 1.15119 2.52595 + endloop + endfacet + facet normal 0.22504 -0.259289 0.939216 + outer loop + vertex 1.59795 1.15323 2.52525 + vertex 1.59633 1.15507 2.52614 + vertex 1.59424 1.15236 2.5259 + endloop + endfacet + facet normal 0.132839 -0.190897 0.97258 + outer loop + vertex 1.59633 1.15507 2.52614 + vertex 1.5934 1.15486 2.5265 + vertex 1.59424 1.15236 2.5259 + endloop + endfacet + facet normal 0.129997 -0.131012 0.982821 + outer loop + vertex 1.59633 1.15507 2.52614 + vertex 1.59662 1.1583 2.52654 + vertex 1.5934 1.15486 2.5265 + endloop + endfacet + facet normal 0.132351 -0.133218 0.98221 + outer loop + vertex 1.59662 1.1583 2.52654 + vertex 1.59296 1.15868 2.52708 + vertex 1.5934 1.15486 2.5265 + endloop + endfacet + facet normal 0.136525 -0.098048 0.985773 + outer loop + vertex 1.59662 1.1583 2.52654 + vertex 1.59744 1.16325 2.52692 + vertex 1.59296 1.15868 2.52708 + endloop + endfacet + facet normal 0.16784 -0.129001 0.977337 + outer loop + vertex 1.59296 1.15868 2.52708 + vertex 1.59744 1.16325 2.52692 + vertex 1.59263 1.16324 2.52774 + endloop + endfacet + facet normal 0.123999 0.235306 0.963979 + outer loop + vertex 1.59402 1.89294 2.5208 + vertex 1.59873 1.89361 2.52003 + vertex 1.59335 1.89693 2.51991 + endloop + endfacet + facet normal 0.0900631 0.180785 0.97939 + outer loop + vertex 1.59335 1.89693 2.51991 + vertex 1.59873 1.89361 2.52003 + vertex 1.5984 1.89833 2.51919 + endloop + endfacet + facet normal 0.0894295 0.182905 0.979055 + outer loop + vertex 1.5984 1.89833 2.51919 + vertex 1.59695 1.90182 2.51867 + vertex 1.59335 1.89693 2.51991 + endloop + endfacet + facet normal 0.0586668 0.205075 0.976986 + outer loop + vertex 1.59335 1.89693 2.51991 + vertex 1.59695 1.90182 2.51867 + vertex 1.59238 1.90196 2.51891 + endloop + endfacet + facet normal 0.0584325 0.193749 0.979309 + outer loop + vertex 1.59695 1.90182 2.51867 + vertex 1.59585 1.90548 2.51801 + vertex 1.59238 1.90196 2.51891 + endloop + endfacet + facet normal 0.0403147 0.210911 0.976674 + outer loop + vertex 1.59238 1.90196 2.51891 + vertex 1.59585 1.90548 2.51801 + vertex 1.59187 1.90644 2.51796 + endloop + endfacet + facet normal 0.0401662 0.210301 0.976811 + outer loop + vertex 1.59585 1.90548 2.51801 + vertex 1.59685 1.91019 2.51695 + vertex 1.59187 1.90644 2.51796 + endloop + endfacet + facet normal 0.0380113 0.213029 0.976306 + outer loop + vertex 1.59187 1.90644 2.51796 + vertex 1.59685 1.91019 2.51695 + vertex 1.59137 1.91155 2.51687 + endloop + endfacet + facet normal -0.00683101 0.248221 0.968679 + outer loop + vertex 1.59567 1.91762 2.51548 + vertex 1.59278 1.91859 2.51521 + vertex 1.59307 1.91559 2.51598 + endloop + endfacet + facet normal 0.0183104 0.217853 0.97581 + outer loop + vertex 1.59307 1.91559 2.51598 + vertex 1.59597 1.91465 2.51613 + vertex 1.59567 1.91762 2.51548 + endloop + endfacet + facet normal 0.0153858 0.209086 0.977776 + outer loop + vertex 1.59307 1.91559 2.51598 + vertex 1.59137 1.91155 2.51687 + vertex 1.59597 1.91465 2.51613 + endloop + endfacet + facet normal 0.0313297 0.186467 0.981962 + outer loop + vertex 1.59137 1.91155 2.51687 + vertex 1.59685 1.91019 2.51695 + vertex 1.59597 1.91465 2.51613 + endloop + endfacet + facet normal 0.066965 0.253338 0.965057 + outer loop + vertex 1.59567 1.91762 2.51548 + vertex 1.59846 1.91747 2.51532 + vertex 1.59786 1.92131 2.51435 + endloop + endfacet + facet normal 0.00695465 0.28669 0.957998 + outer loop + vertex 1.59567 1.91762 2.51548 + vertex 1.59786 1.92131 2.51435 + vertex 1.59278 1.91859 2.51521 + endloop + endfacet + facet normal 0.0274925 0.251418 0.967488 + outer loop + vertex 1.59278 1.91859 2.51521 + vertex 1.59786 1.92131 2.51435 + vertex 1.59265 1.92257 2.51418 + endloop + endfacet + facet normal 0.0656601 0.221979 0.972838 + outer loop + vertex 1.59846 1.91747 2.51532 + vertex 1.59567 1.91762 2.51548 + vertex 1.59597 1.91465 2.51613 + endloop + endfacet + facet normal 0.023369 0.234926 0.971732 + outer loop + vertex 1.59786 1.92131 2.51435 + vertex 1.5967 1.92627 2.51319 + vertex 1.59265 1.92257 2.51418 + endloop + endfacet + facet normal 0.0187654 0.239687 0.970669 + outer loop + vertex 1.59265 1.92257 2.51418 + vertex 1.5967 1.92627 2.51319 + vertex 1.59188 1.92677 2.51315 + endloop + endfacet + facet normal 0.0184942 0.237126 0.971303 + outer loop + vertex 1.5967 1.92627 2.51319 + vertex 1.59568 1.93061 2.51214 + vertex 1.59188 1.92677 2.51315 + endloop + endfacet + facet normal 0.0217768 0.234055 0.971979 + outer loop + vertex 1.59188 1.92677 2.51315 + vertex 1.59568 1.93061 2.51214 + vertex 1.59056 1.93092 2.51218 + endloop + endfacet + facet normal 0.0358644 0.239579 0.970214 + outer loop + vertex 1.59439 1.93473 2.51116 + vertex 1.59945 1.93431 2.51108 + vertex 1.59836 1.93841 2.5101 + endloop + endfacet + facet normal 0.0279676 0.247605 0.968457 + outer loop + vertex 1.59327 1.93878 2.51016 + vertex 1.59439 1.93473 2.51116 + vertex 1.59836 1.93841 2.5101 + endloop + endfacet + facet normal 0.0220675 0.238895 0.970795 + outer loop + vertex 1.59568 1.93061 2.51214 + vertex 1.59439 1.93473 2.51116 + vertex 1.59056 1.93092 2.51218 + endloop + endfacet + facet normal 0.0361304 0.242933 0.96937 + outer loop + vertex 1.59945 1.93431 2.51108 + vertex 1.59439 1.93473 2.51116 + vertex 1.59568 1.93061 2.51214 + endloop + endfacet + facet normal 0.0276676 0.243265 0.969565 + outer loop + vertex 1.59836 1.93841 2.5101 + vertex 1.59737 1.94252 2.5091 + vertex 1.59327 1.93878 2.51016 + endloop + endfacet + facet normal 0.0179096 0.253301 0.967222 + outer loop + vertex 1.59327 1.93878 2.51016 + vertex 1.59737 1.94252 2.5091 + vertex 1.59257 1.94278 2.50912 + endloop + endfacet + facet normal 0.0177898 0.251094 0.967799 + outer loop + vertex 1.59737 1.94252 2.5091 + vertex 1.59655 1.94656 2.50807 + vertex 1.59257 1.94278 2.50912 + endloop + endfacet + facet normal 0.0177916 0.251092 0.9678 + outer loop + vertex 1.59257 1.94278 2.50912 + vertex 1.59655 1.94656 2.50807 + vertex 1.59187 1.94668 2.50812 + endloop + endfacet + facet normal 0.0178667 0.254131 0.967005 + outer loop + vertex 1.59655 1.94656 2.50807 + vertex 1.59562 1.95051 2.50705 + vertex 1.59187 1.94668 2.50812 + endloop + endfacet + facet normal 0.147782 0.274589 0.950137 + outer loop + vertex 1.59288 2.02957 2.48514 + vertex 1.59455 2.02505 2.48619 + vertex 1.59799 2.02797 2.48481 + endloop + endfacet + facet normal 0.186039 0.360655 0.913957 + outer loop + vertex 1.59847 2.08873 2.46603 + vertex 1.59766 2.09293 2.46454 + vertex 1.59532 2.08997 2.46618 + endloop + endfacet + facet normal 0.164138 0.301693 0.93917 + outer loop + vertex 1.59532 2.08997 2.46618 + vertex 1.59594 2.08572 2.46744 + vertex 1.59847 2.08873 2.46603 + endloop + endfacet + facet normal 0.163382 0.301627 0.939323 + outer loop + vertex 1.59532 2.08997 2.46618 + vertex 1.59108 2.08955 2.46706 + vertex 1.59594 2.08572 2.46744 + endloop + endfacet + facet normal 0.160235 0.297814 0.94108 + outer loop + vertex 1.59108 2.08955 2.46706 + vertex 1.59126 2.0855 2.46831 + vertex 1.59594 2.08572 2.46744 + endloop + endfacet + facet normal 0.184815 0.361561 0.913847 + outer loop + vertex 1.59302 2.09282 2.46552 + vertex 1.59532 2.08997 2.46618 + vertex 1.59766 2.09293 2.46454 + endloop + endfacet + facet normal 0.177608 0.426293 0.886978 + outer loop + vertex 1.59302 2.09282 2.46552 + vertex 1.59766 2.09293 2.46454 + vertex 1.592 2.09727 2.46359 + endloop + endfacet + facet normal 0.185833 0.435641 0.880729 + outer loop + vertex 1.592 2.09727 2.46359 + vertex 1.59766 2.09293 2.46454 + vertex 1.59684 2.09712 2.46264 + endloop + endfacet + facet normal 0.156773 0.341968 0.926542 + outer loop + vertex 1.59532 2.08997 2.46618 + vertex 1.59302 2.09282 2.46552 + vertex 1.59108 2.08955 2.46706 + endloop + endfacet + facet normal 0.231438 0.631377 0.740135 + outer loop + vertex 1.59489 2.10002 2.4613 + vertex 1.59887 2.09936 2.46061 + vertex 1.59679 2.10201 2.459 + endloop + endfacet + facet normal 0.267549 0.606645 0.748598 + outer loop + vertex 1.59406 2.10207 2.45993 + vertex 1.59489 2.10002 2.4613 + vertex 1.59679 2.10201 2.459 + endloop + endfacet + facet normal 0.180308 0.510493 0.840765 + outer loop + vertex 1.59684 2.09712 2.46264 + vertex 1.59489 2.10002 2.4613 + vertex 1.592 2.09727 2.46359 + endloop + endfacet + facet normal 0.228079 0.531248 0.815939 + outer loop + vertex 1.59887 2.09936 2.46061 + vertex 1.59489 2.10002 2.4613 + vertex 1.59684 2.09712 2.46264 + endloop + endfacet + facet normal 0.210033 0.827525 0.520661 + outer loop + vertex 1.59337 2.10413 2.45779 + vertex 1.5991 2.10412 2.45548 + vertex 1.59561 2.10618 2.45362 + endloop + endfacet + facet normal 0.252968 0.806976 0.533664 + outer loop + vertex 1.59171 2.10649 2.455 + vertex 1.59337 2.10413 2.45779 + vertex 1.59561 2.10618 2.45362 + endloop + endfacet + facet normal 0.230987 0.738134 0.633879 + outer loop + vertex 1.59679 2.10201 2.459 + vertex 1.59337 2.10413 2.45779 + vertex 1.59406 2.10207 2.45993 + endloop + endfacet + facet normal 0.246808 0.751318 0.612052 + outer loop + vertex 1.5991 2.10412 2.45548 + vertex 1.59337 2.10413 2.45779 + vertex 1.59679 2.10201 2.459 + endloop + endfacet + facet normal 0.0680153 0.251878 0.965366 + outer loop + vertex 1.6 2.1125 2.445 + vertex 1.595 2.11385 2.445 + vertex 1.59731 2.10995 2.44585 + endloop + endfacet + facet normal 0.428026 0.427924 0.796037 + outer loop + vertex 1.59731 2.10995 2.44585 + vertex 1.595 2.11385 2.445 + vertex 1.59395 2.11019 2.44753 + endloop + endfacet + facet normal 0.308784 0.807361 0.502813 + outer loop + vertex 1.59731 2.10995 2.44585 + vertex 1.59395 2.11019 2.44753 + vertex 1.59737 2.10777 2.44932 + endloop + endfacet + facet normal 0.308507 0.807239 0.503178 + outer loop + vertex 1.59737 2.10777 2.44932 + vertex 1.59395 2.11019 2.44753 + vertex 1.59193 2.10858 2.45135 + endloop + endfacet + facet normal 0.241145 0.835488 0.49377 + outer loop + vertex 1.59561 2.10618 2.45362 + vertex 1.59193 2.10858 2.45135 + vertex 1.59171 2.10649 2.455 + endloop + endfacet + facet normal 0.289487 0.853147 0.433978 + outer loop + vertex 1.59737 2.10777 2.44932 + vertex 1.59193 2.10858 2.45135 + vertex 1.59561 2.10618 2.45362 + endloop + endfacet + facet normal 0.20445 -0.690797 -0.693542 + outer loop + vertex 1.60173 0.92 2.445 + vertex 1.6 0.919488 2.445 + vertex 1.6 0.92 2.44449 + endloop + endfacet + facet normal 0.0184995 -0.0625065 0.997873 + outer loop + vertex 1.60173 0.92 2.445 + vertex 1.59912 0.919684 2.44503 + vertex 1.6 0.919488 2.445 + endloop + endfacet + facet normal 0.0188966 -0.0658059 0.997653 + outer loop + vertex 1.59912 0.919684 2.44503 + vertex 1.60173 0.92 2.445 + vertex 1.605 0.920939 2.445 + endloop + endfacet + facet normal 0.192958 -0.894995 0.402184 + outer loop + vertex 1.59912 0.919684 2.44503 + vertex 1.605 0.920939 2.445 + vertex 1.59817 0.920339 2.44694 + endloop + endfacet + facet normal 0.230505 -0.791238 0.5664 + outer loop + vertex 1.59817 0.920339 2.44694 + vertex 1.605 0.920939 2.445 + vertex 1.60179 0.921735 2.44742 + endloop + endfacet + facet normal 0.214509 -0.879263 0.425303 + outer loop + vertex 1.60055 0.922929 2.45051 + vertex 1.60179 0.921735 2.44742 + vertex 1.60453 0.923246 2.44916 + endloop + endfacet + facet normal 0.23775 -0.870365 0.431206 + outer loop + vertex 1.60055 0.922929 2.45051 + vertex 1.59673 0.921763 2.45027 + vertex 1.60179 0.921735 2.44742 + endloop + endfacet + facet normal 0.261795 -0.840905 0.473647 + outer loop + vertex 1.59673 0.921763 2.45027 + vertex 1.59817 0.920339 2.44694 + vertex 1.60179 0.921735 2.44742 + endloop + endfacet + facet normal 0.227843 -0.847939 0.478631 + outer loop + vertex 1.60055 0.922929 2.45051 + vertex 1.59795 0.923637 2.453 + vertex 1.59673 0.921763 2.45027 + endloop + endfacet + facet normal 0.22301 -0.862499 0.454271 + outer loop + vertex 1.60453 0.923246 2.44916 + vertex 1.6021 0.924791 2.45329 + vertex 1.60055 0.922929 2.45051 + endloop + endfacet + facet normal 0.208241 -0.861984 0.46219 + outer loop + vertex 1.59795 0.923637 2.453 + vertex 1.60055 0.922929 2.45051 + vertex 1.6021 0.924791 2.45329 + endloop + endfacet + facet normal 0.193576 -0.825731 0.529809 + outer loop + vertex 1.59795 0.923637 2.453 + vertex 1.6021 0.924791 2.45329 + vertex 1.5966 0.925803 2.45687 + endloop + endfacet + facet normal 0.183243 -0.836196 0.516912 + outer loop + vertex 1.5966 0.925803 2.45687 + vertex 1.6021 0.924791 2.45329 + vertex 1.60144 0.9268 2.45677 + endloop + endfacet + facet normal 0.17134 -0.767949 0.617169 + outer loop + vertex 1.60144 0.9268 2.45677 + vertex 1.59914 0.928296 2.45927 + vertex 1.5966 0.925803 2.45687 + endloop + endfacet + facet normal 0.192088 -0.754157 0.627972 + outer loop + vertex 1.60334 0.928909 2.45872 + vertex 1.59914 0.928296 2.45927 + vertex 1.60144 0.9268 2.45677 + endloop + endfacet + facet normal 0.191092 -0.654716 0.731321 + outer loop + vertex 1.59914 0.928296 2.45927 + vertex 1.60334 0.928909 2.45872 + vertex 1.60118 0.931041 2.4612 + endloop + endfacet + facet normal 0.202926 -0.65871 0.724515 + outer loop + vertex 1.59749 0.930125 2.4614 + vertex 1.59914 0.928296 2.45927 + vertex 1.60118 0.931041 2.4612 + endloop + endfacet + facet normal 0.178619 -0.539125 0.823067 + outer loop + vertex 1.60118 0.931041 2.4612 + vertex 1.59847 0.933522 2.46341 + vertex 1.59749 0.930125 2.4614 + endloop + endfacet + facet normal 0.18954 -0.53021 0.826409 + outer loop + vertex 1.60402 0.934693 2.46289 + vertex 1.59847 0.933522 2.46341 + vertex 1.60118 0.931041 2.4612 + endloop + endfacet + facet normal 0.171651 -0.416064 0.892988 + outer loop + vertex 1.60402 0.934693 2.46289 + vertex 1.60292 0.938519 2.46488 + vertex 1.59847 0.933522 2.46341 + endloop + endfacet + facet normal 0.0350293 -0.307149 0.951016 + outer loop + vertex 1.6036 1.04272 2.49763 + vertex 1.59785 1.04329 2.49803 + vertex 1.59857 1.03958 2.4968 + endloop + endfacet + facet normal 0.0369952 -0.29081 0.956065 + outer loop + vertex 1.6036 1.04272 2.49763 + vertex 1.60153 1.04674 2.49893 + vertex 1.59785 1.04329 2.49803 + endloop + endfacet + facet normal 0.0317912 -0.285703 0.957791 + outer loop + vertex 1.59785 1.04329 2.49803 + vertex 1.60153 1.04674 2.49893 + vertex 1.59727 1.04754 2.49931 + endloop + endfacet + facet normal 0.0299436 -0.294343 0.955231 + outer loop + vertex 1.60153 1.04674 2.49893 + vertex 1.60192 1.05095 2.50022 + vertex 1.59727 1.04754 2.49931 + endloop + endfacet + facet normal 0.00610567 -0.264297 0.964422 + outer loop + vertex 1.59727 1.04754 2.49931 + vertex 1.60192 1.05095 2.50022 + vertex 1.59714 1.05154 2.50041 + endloop + endfacet + facet normal 0.00533715 -0.270008 0.962843 + outer loop + vertex 1.59714 1.05154 2.50041 + vertex 1.60192 1.05095 2.50022 + vertex 1.60043 1.05473 2.50129 + endloop + endfacet + facet normal -0.00376792 -0.261273 0.965258 + outer loop + vertex 1.59669 1.0545 2.50121 + vertex 1.59714 1.05154 2.50041 + vertex 1.60043 1.05473 2.50129 + endloop + endfacet + facet normal -0.00294628 -0.27361 0.961836 + outer loop + vertex 1.60043 1.05473 2.50129 + vertex 1.59835 1.05826 2.50229 + vertex 1.59669 1.0545 2.50121 + endloop + endfacet + facet normal 0.0177882 -0.262226 0.964843 + outer loop + vertex 1.60435 1.05844 2.50222 + vertex 1.59835 1.05826 2.50229 + vertex 1.60043 1.05473 2.50129 + endloop + endfacet + facet normal 0.0175448 -0.2533 0.967229 + outer loop + vertex 1.60435 1.05844 2.50222 + vertex 1.60292 1.06311 2.50347 + vertex 1.59835 1.05826 2.50229 + endloop + endfacet + facet normal 0.0358215 -0.269362 0.962372 + outer loop + vertex 1.59835 1.05826 2.50229 + vertex 1.60292 1.06311 2.50347 + vertex 1.59757 1.06301 2.50364 + endloop + endfacet + facet normal 0.0359116 -0.277495 0.960056 + outer loop + vertex 1.60292 1.06311 2.50347 + vertex 1.60171 1.06733 2.50474 + vertex 1.59757 1.06301 2.50364 + endloop + endfacet + facet normal 0.0258313 -0.268559 0.962917 + outer loop + vertex 1.59757 1.06301 2.50364 + vertex 1.60171 1.06733 2.50474 + vertex 1.59669 1.06718 2.50483 + endloop + endfacet + facet normal 0.0261605 -0.28182 0.959111 + outer loop + vertex 1.59669 1.06718 2.50483 + vertex 1.60171 1.06733 2.50474 + vertex 1.60041 1.07102 2.50586 + endloop + endfacet + facet normal 0.0144398 -0.271347 0.962373 + outer loop + vertex 1.59558 1.07095 2.50591 + vertex 1.59669 1.06718 2.50483 + vertex 1.60041 1.07102 2.50586 + endloop + endfacet + facet normal 0.0143807 -0.265516 0.963999 + outer loop + vertex 1.60041 1.07102 2.50586 + vertex 1.59924 1.07471 2.50689 + vertex 1.59558 1.07095 2.50591 + endloop + endfacet + facet normal 0.0380207 -0.258416 0.965285 + outer loop + vertex 1.60385 1.07469 2.5067 + vertex 1.59924 1.07471 2.50689 + vertex 1.60041 1.07102 2.50586 + endloop + endfacet + facet normal 0.0384846 -0.227379 0.973046 + outer loop + vertex 1.60385 1.07469 2.5067 + vertex 1.60324 1.07871 2.50767 + vertex 1.59924 1.07471 2.50689 + endloop + endfacet + facet normal 0.0593152 -0.247058 0.967183 + outer loop + vertex 1.59924 1.07471 2.50689 + vertex 1.60324 1.07871 2.50767 + vertex 1.59822 1.07868 2.50797 + endloop + endfacet + facet normal 0.0594184 -0.233574 0.970522 + outer loop + vertex 1.60324 1.07871 2.50767 + vertex 1.60273 1.08317 2.50877 + vertex 1.59822 1.07868 2.50797 + endloop + endfacet + facet normal 0.0740031 -0.2474 0.966083 + outer loop + vertex 1.59822 1.07868 2.50797 + vertex 1.60273 1.08317 2.50877 + vertex 1.59752 1.08293 2.50911 + endloop + endfacet + facet normal 0.0740756 -0.249934 0.965425 + outer loop + vertex 1.60273 1.08317 2.50877 + vertex 1.60248 1.08807 2.51006 + vertex 1.59752 1.08293 2.50911 + endloop + endfacet + facet normal 0.0737679 -0.249655 0.965521 + outer loop + vertex 1.59752 1.08293 2.50911 + vertex 1.60248 1.08807 2.51006 + vertex 1.59672 1.0869 2.5102 + endloop + endfacet + facet normal 0.0808 -0.285739 0.954895 + outer loop + vertex 1.59672 1.0869 2.5102 + vertex 1.60248 1.08807 2.51006 + vertex 1.60038 1.09097 2.51111 + endloop + endfacet + facet normal 0.0370035 -0.249197 0.967746 + outer loop + vertex 1.59559 1.09045 2.51116 + vertex 1.59672 1.0869 2.5102 + vertex 1.60038 1.09097 2.51111 + endloop + endfacet + facet normal 0.0360249 -0.239856 0.97014 + outer loop + vertex 1.60038 1.09097 2.51111 + vertex 1.59922 1.09441 2.512 + vertex 1.59559 1.09045 2.51116 + endloop + endfacet + facet normal 0.0842107 -0.223934 0.970959 + outer loop + vertex 1.60361 1.09483 2.51171 + vertex 1.59922 1.09441 2.512 + vertex 1.60038 1.09097 2.51111 + endloop + endfacet + facet normal 0.0823295 -0.200222 0.976285 + outer loop + vertex 1.60361 1.09483 2.51171 + vertex 1.60316 1.0987 2.51255 + vertex 1.59922 1.09441 2.512 + endloop + endfacet + facet normal 0.0995937 -0.215451 0.971423 + outer loop + vertex 1.59922 1.09441 2.512 + vertex 1.60316 1.0987 2.51255 + vertex 1.59816 1.09861 2.51304 + endloop + endfacet + facet normal 0.0995905 -0.216039 0.971292 + outer loop + vertex 1.60316 1.0987 2.51255 + vertex 1.60268 1.10338 2.51364 + vertex 1.59816 1.09861 2.51304 + endloop + endfacet + facet normal 0.120341 -0.234907 0.96454 + outer loop + vertex 1.59816 1.09861 2.51304 + vertex 1.60268 1.10338 2.51364 + vertex 1.59686 1.10389 2.51449 + endloop + endfacet + facet normal 0.0681637 -0.291899 0.954017 + outer loop + vertex 1.59897 1.10804 2.51561 + vertex 1.59606 1.10752 2.51566 + vertex 1.59686 1.10389 2.51449 + endloop + endfacet + facet normal 0.190928 -0.344952 0.918996 + outer loop + vertex 1.59897 1.10804 2.51561 + vertex 1.59686 1.10389 2.51449 + vertex 1.60269 1.10839 2.51497 + endloop + endfacet + facet normal 0.117912 -0.254724 0.959798 + outer loop + vertex 1.60269 1.10839 2.51497 + vertex 1.59686 1.10389 2.51449 + vertex 1.60268 1.10338 2.51364 + endloop + endfacet + facet normal 0.0613945 -0.252367 0.965682 + outer loop + vertex 1.59897 1.10804 2.51561 + vertex 1.59794 1.11084 2.51641 + vertex 1.59606 1.10752 2.51566 + endloop + endfacet + facet normal 0.189926 -0.313234 0.930491 + outer loop + vertex 1.60269 1.10839 2.51497 + vertex 1.60102 1.11041 2.51599 + vertex 1.59897 1.10804 2.51561 + endloop + endfacet + facet normal 0.097755 -0.23914 0.966052 + outer loop + vertex 1.60102 1.11041 2.51599 + vertex 1.59794 1.11084 2.51641 + vertex 1.59897 1.10804 2.51561 + endloop + endfacet + facet normal 0.105678 -0.192288 0.975632 + outer loop + vertex 1.60102 1.11041 2.51599 + vertex 1.60165 1.11355 2.51654 + vertex 1.59794 1.11084 2.51641 + endloop + endfacet + facet normal 0.114488 -0.2042 0.972211 + outer loop + vertex 1.60165 1.11355 2.51654 + vertex 1.599 1.11472 2.51709 + vertex 1.59794 1.11084 2.51641 + endloop + endfacet + facet normal 0.138639 -0.152419 0.978544 + outer loop + vertex 1.60165 1.11355 2.51654 + vertex 1.60297 1.11832 2.51709 + vertex 1.599 1.11472 2.51709 + endloop + endfacet + facet normal 0.149518 -0.164416 0.974993 + outer loop + vertex 1.599 1.11472 2.51709 + vertex 1.60297 1.11832 2.51709 + vertex 1.59821 1.11838 2.51783 + endloop + endfacet + facet normal 0.148963 -0.178293 0.972636 + outer loop + vertex 1.60297 1.11832 2.51709 + vertex 1.60267 1.12323 2.51804 + vertex 1.59821 1.11838 2.51783 + endloop + endfacet + facet normal 0.118385 0.213593 0.969723 + outer loop + vertex 1.59786 1.92131 2.51435 + vertex 1.60254 1.9184 2.51442 + vertex 1.60276 1.92287 2.51341 + endloop + endfacet + facet normal 0.12159 0.204466 0.971293 + outer loop + vertex 1.60276 1.92287 2.51341 + vertex 1.60079 1.92565 2.51308 + vertex 1.59786 1.92131 2.51435 + endloop + endfacet + facet normal 0.0627894 0.243203 0.967941 + outer loop + vertex 1.59786 1.92131 2.51435 + vertex 1.60079 1.92565 2.51308 + vertex 1.5967 1.92627 2.51319 + endloop + endfacet + facet normal 0.0621752 0.238932 0.969044 + outer loop + vertex 1.60079 1.92565 2.51308 + vertex 1.60101 1.92995 2.512 + vertex 1.5967 1.92627 2.51319 + endloop + endfacet + facet normal 0.0564343 0.245251 0.967816 + outer loop + vertex 1.5967 1.92627 2.51319 + vertex 1.60101 1.92995 2.512 + vertex 1.59568 1.93061 2.51214 + endloop + endfacet + facet normal 0.0978326 0.242722 0.96515 + outer loop + vertex 1.59945 1.93431 2.51108 + vertex 1.60358 1.93353 2.51085 + vertex 1.60377 1.93752 2.50983 + endloop + endfacet + facet normal 0.0901782 0.252366 0.963421 + outer loop + vertex 1.59836 1.93841 2.5101 + vertex 1.59945 1.93431 2.51108 + vertex 1.60377 1.93752 2.50983 + endloop + endfacet + facet normal 0.0541267 0.225582 0.972719 + outer loop + vertex 1.60101 1.92995 2.512 + vertex 1.59945 1.93431 2.51108 + vertex 1.59568 1.93061 2.51214 + endloop + endfacet + facet normal 0.0972748 0.239552 0.965998 + outer loop + vertex 1.60358 1.93353 2.51085 + vertex 1.59945 1.93431 2.51108 + vertex 1.60101 1.92995 2.512 + endloop + endfacet + facet normal 0.0857003 0.222965 0.971052 + outer loop + vertex 1.60377 1.93752 2.50983 + vertex 1.60232 1.94204 2.50892 + vertex 1.59836 1.93841 2.5101 + endloop + endfacet + facet normal 0.0593671 0.250177 0.966378 + outer loop + vertex 1.59836 1.93841 2.5101 + vertex 1.60232 1.94204 2.50892 + vertex 1.59737 1.94252 2.5091 + endloop + endfacet + facet normal 0.0580748 0.235408 0.97016 + outer loop + vertex 1.60232 1.94204 2.50892 + vertex 1.60142 1.94635 2.50793 + vertex 1.59737 1.94252 2.5091 + endloop + endfacet + facet normal 0.0385176 0.254903 0.966199 + outer loop + vertex 1.59737 1.94252 2.5091 + vertex 1.60142 1.94635 2.50793 + vertex 1.59655 1.94656 2.50807 + endloop + endfacet + facet normal 0.0379912 0.23992 0.970049 + outer loop + vertex 1.60142 1.94635 2.50793 + vertex 1.60041 1.95048 2.50695 + vertex 1.59655 1.94656 2.50807 + endloop + endfacet + facet normal 0.0217385 0.254963 0.966706 + outer loop + vertex 1.59655 1.94656 2.50807 + vertex 1.60041 1.95048 2.50695 + vertex 1.59562 1.95051 2.50705 + endloop + endfacet + facet normal 0.0509454 0.254413 0.965753 + outer loop + vertex 1.59942 1.9544 2.50594 + vertex 1.60412 1.95415 2.50576 + vertex 1.60325 1.95815 2.50476 + endloop + endfacet + facet normal 0.0386287 0.266169 0.963152 + outer loop + vertex 1.59832 1.95832 2.5049 + vertex 1.59942 1.9544 2.50594 + vertex 1.60325 1.95815 2.50476 + endloop + endfacet + facet normal 0.0217348 0.253074 0.967203 + outer loop + vertex 1.60041 1.95048 2.50695 + vertex 1.59942 1.9544 2.50594 + vertex 1.59562 1.95051 2.50705 + endloop + endfacet + facet normal 0.0511731 0.259723 0.964326 + outer loop + vertex 1.60412 1.95415 2.50576 + vertex 1.59942 1.9544 2.50594 + vertex 1.60041 1.95048 2.50695 + endloop + endfacet + facet normal 0.038291 0.253701 0.966525 + outer loop + vertex 1.60325 1.95815 2.50476 + vertex 1.60206 1.9622 2.50374 + vertex 1.59832 1.95832 2.5049 + endloop + endfacet + facet normal 0.023769 0.266766 0.963468 + outer loop + vertex 1.59832 1.95832 2.5049 + vertex 1.60206 1.9622 2.50374 + vertex 1.5971 1.96241 2.5038 + endloop + endfacet + facet normal 0.0236419 0.26361 0.96434 + outer loop + vertex 1.60206 1.9622 2.50374 + vertex 1.60119 1.96678 2.50251 + vertex 1.5971 1.96241 2.5038 + endloop + endfacet + facet normal 0.0179265 0.268592 0.963087 + outer loop + vertex 1.5971 1.96241 2.5038 + vertex 1.60119 1.96678 2.50251 + vertex 1.59529 1.96678 2.50262 + endloop + endfacet + facet normal 0.000482389 0.285229 0.958459 + outer loop + vertex 1.59921 1.97048 2.50147 + vertex 1.60297 1.9707 2.5014 + vertex 1.60263 1.97376 2.50049 + endloop + endfacet + facet normal 0.0119225 0.274219 0.961593 + outer loop + vertex 1.59789 1.97445 2.50035 + vertex 1.59921 1.97048 2.50147 + vertex 1.60263 1.97376 2.50049 + endloop + endfacet + facet normal 0.017859 0.279876 0.95987 + outer loop + vertex 1.60119 1.96678 2.50251 + vertex 1.59921 1.97048 2.50147 + vertex 1.59529 1.96678 2.50262 + endloop + endfacet + facet normal 0.00135124 0.271702 0.96238 + outer loop + vertex 1.60297 1.9707 2.5014 + vertex 1.59921 1.97048 2.50147 + vertex 1.60119 1.96678 2.50251 + endloop + endfacet + facet normal 0.0128701 0.280332 0.959817 + outer loop + vertex 1.60263 1.97376 2.50049 + vertex 1.60251 1.97765 2.49935 + vertex 1.59789 1.97445 2.50035 + endloop + endfacet + facet normal 0.0210372 0.269456 0.962783 + outer loop + vertex 1.59789 1.97445 2.50035 + vertex 1.60251 1.97765 2.49935 + vertex 1.59856 1.97849 2.4992 + endloop + endfacet + facet normal 0.0208086 0.268435 0.963073 + outer loop + vertex 1.60251 1.97765 2.49935 + vertex 1.60181 1.98163 2.49826 + vertex 1.59856 1.97849 2.4992 + endloop + endfacet + facet normal 0.0289215 0.260627 0.965006 + outer loop + vertex 1.59856 1.97849 2.4992 + vertex 1.60181 1.98163 2.49826 + vertex 1.59707 1.98174 2.49837 + endloop + endfacet + facet normal 0.0291172 0.273641 0.961391 + outer loop + vertex 1.60181 1.98163 2.49826 + vertex 1.60066 1.9855 2.49719 + vertex 1.59707 1.98174 2.49837 + endloop + endfacet + facet normal 0.176345 0.457608 0.871491 + outer loop + vertex 1.60178 2.09255 2.4639 + vertex 1.60134 2.09576 2.46231 + vertex 1.59766 2.09293 2.46454 + endloop + endfacet + facet normal 0.19651 0.436481 0.877991 + outer loop + vertex 1.59766 2.09293 2.46454 + vertex 1.60134 2.09576 2.46231 + vertex 1.59684 2.09712 2.46264 + endloop + endfacet + facet normal 0.216588 0.659645 0.719693 + outer loop + vertex 1.59887 2.09936 2.46061 + vertex 1.60318 2.09911 2.45955 + vertex 1.60099 2.10162 2.4579 + endloop + endfacet + facet normal 0.249868 0.638409 0.728011 + outer loop + vertex 1.59679 2.10201 2.459 + vertex 1.59887 2.09936 2.46061 + vertex 1.60099 2.10162 2.4579 + endloop + endfacet + facet normal 0.221988 0.535668 0.814728 + outer loop + vertex 1.60134 2.09576 2.46231 + vertex 1.59887 2.09936 2.46061 + vertex 1.59684 2.09712 2.46264 + endloop + endfacet + facet normal 0.231656 0.539753 0.809322 + outer loop + vertex 1.60318 2.09911 2.45955 + vertex 1.59887 2.09936 2.46061 + vertex 1.60134 2.09576 2.46231 + endloop + endfacet + facet normal 0.227386 0.880042 0.416919 + outer loop + vertex 1.60308 2.10507 2.45205 + vertex 1.60151 2.10662 2.44963 + vertex 1.59951 2.10596 2.45212 + endloop + endfacet + facet normal 0.235046 0.840479 0.488209 + outer loop + vertex 1.59951 2.10596 2.45212 + vertex 1.59561 2.10618 2.45362 + vertex 1.5991 2.10412 2.45548 + endloop + endfacet + facet normal 0.220009 0.844373 0.488497 + outer loop + vertex 1.59951 2.10596 2.45212 + vertex 1.5991 2.10412 2.45548 + vertex 1.60308 2.10507 2.45205 + endloop + endfacet + facet normal 0.230572 0.835753 0.49835 + outer loop + vertex 1.60308 2.10507 2.45205 + vertex 1.5991 2.10412 2.45548 + vertex 1.60388 2.10315 2.4549 + endloop + endfacet + facet normal 0.229584 0.761108 0.606635 + outer loop + vertex 1.60099 2.10162 2.4579 + vertex 1.5991 2.10412 2.45548 + vertex 1.59679 2.10201 2.459 + endloop + endfacet + facet normal 0.228595 0.760934 0.607226 + outer loop + vertex 1.60388 2.10315 2.4549 + vertex 1.5991 2.10412 2.45548 + vertex 1.60099 2.10162 2.4579 + endloop + endfacet + facet normal 0.0161329 0.336313 0.941612 + outer loop + vertex 1.605 2.11226 2.445 + vertex 1.6 2.1125 2.445 + vertex 1.60177 2.10858 2.44637 + endloop + endfacet + facet normal -0.00878376 0.326306 0.945223 + outer loop + vertex 1.60177 2.10858 2.44637 + vertex 1.6 2.1125 2.445 + vertex 1.59731 2.10995 2.44585 + endloop + endfacet + facet normal 0.215234 0.886813 0.408947 + outer loop + vertex 1.60151 2.10662 2.44963 + vertex 1.59737 2.10777 2.44932 + vertex 1.59951 2.10596 2.45212 + endloop + endfacet + facet normal 0.192431 0.834409 0.516461 + outer loop + vertex 1.60151 2.10662 2.44963 + vertex 1.60177 2.10858 2.44637 + vertex 1.59737 2.10777 2.44932 + endloop + endfacet + facet normal 0.195369 0.831492 0.520051 + outer loop + vertex 1.60177 2.10858 2.44637 + vertex 1.59731 2.10995 2.44585 + vertex 1.59737 2.10777 2.44932 + endloop + endfacet + facet normal 0.208971 0.886262 0.413366 + outer loop + vertex 1.59951 2.10596 2.45212 + vertex 1.59737 2.10777 2.44932 + vertex 1.59561 2.10618 2.45362 + endloop + endfacet + facet normal 0.215038 -0.720654 0.659103 + outer loop + vertex 1.61 0.922431 2.445 + vertex 1.60755 0.922414 2.44578 + vertex 1.605 0.920939 2.445 + endloop + endfacet + facet normal 0.258672 -0.761709 0.594044 + outer loop + vertex 1.60755 0.922414 2.44578 + vertex 1.60179 0.921735 2.44742 + vertex 1.605 0.920939 2.445 + endloop + endfacet + facet normal 0.222152 -0.881977 0.415651 + outer loop + vertex 1.60755 0.922414 2.44578 + vertex 1.60453 0.923246 2.44916 + vertex 1.60179 0.921735 2.44742 + endloop + endfacet + facet normal 0.204356 -0.892396 0.402329 + outer loop + vertex 1.60849 0.923562 2.44785 + vertex 1.60453 0.923246 2.44916 + vertex 1.60755 0.922414 2.44578 + endloop + endfacet + facet normal 0.209931 -0.882122 0.421652 + outer loop + vertex 1.60453 0.923246 2.44916 + vertex 1.60849 0.923562 2.44785 + vertex 1.6075 0.924894 2.45113 + endloop + endfacet + facet normal 0.193173 -0.876079 0.441781 + outer loop + vertex 1.6021 0.924791 2.45329 + vertex 1.60453 0.923246 2.44916 + vertex 1.6075 0.924894 2.45113 + endloop + endfacet + facet normal 0.215354 -0.839382 0.499059 + outer loop + vertex 1.6075 0.924894 2.45113 + vertex 1.60621 0.927131 2.45545 + vertex 1.6021 0.924791 2.45329 + endloop + endfacet + facet normal 0.201129 -0.8316 0.517676 + outer loop + vertex 1.60621 0.927131 2.45545 + vertex 1.60144 0.9268 2.45677 + vertex 1.6021 0.924791 2.45329 + endloop + endfacet + facet normal 0.221391 -0.762307 0.608173 + outer loop + vertex 1.60621 0.927131 2.45545 + vertex 1.60334 0.928909 2.45872 + vertex 1.60144 0.9268 2.45677 + endloop + endfacet + facet normal 0.209839 -0.770182 0.602318 + outer loop + vertex 1.60704 0.929655 2.45839 + vertex 1.60334 0.928909 2.45872 + vertex 1.60621 0.927131 2.45545 + endloop + endfacet + facet normal 0.197897 -0.6536 0.730509 + outer loop + vertex 1.60334 0.928909 2.45872 + vertex 1.60704 0.929655 2.45839 + vertex 1.60552 0.931756 2.46068 + endloop + endfacet + facet normal 0.194626 -0.652422 0.732439 + outer loop + vertex 1.60118 0.931041 2.4612 + vertex 1.60334 0.928909 2.45872 + vertex 1.60552 0.931756 2.46068 + endloop + endfacet + facet normal 0.185633 -0.528182 0.828592 + outer loop + vertex 1.60552 0.931756 2.46068 + vertex 1.60402 0.934693 2.46289 + vertex 1.60118 0.931041 2.4612 + endloop + endfacet + facet normal 0.183865 -0.528995 0.828467 + outer loop + vertex 1.60868 0.935087 2.46211 + vertex 1.60402 0.934693 2.46289 + vertex 1.60552 0.931756 2.46068 + endloop + endfacet + facet normal 0.184776 -0.429054 0.884178 + outer loop + vertex 1.60868 0.935087 2.46211 + vertex 1.60815 0.938818 2.46403 + vertex 1.60402 0.934693 2.46289 + endloop + endfacet + facet normal 0.169901 -0.416607 0.893069 + outer loop + vertex 1.60402 0.934693 2.46289 + vertex 1.60815 0.938818 2.46403 + vertex 1.60292 0.938519 2.46488 + endloop + endfacet + facet normal 0.0349445 -0.292286 0.955692 + outer loop + vertex 1.60785 1.01321 2.48854 + vertex 1.60675 1.01718 2.4898 + vertex 1.60261 1.01316 2.48872 + endloop + endfacet + facet normal 0.0287331 -0.286413 0.957675 + outer loop + vertex 1.60261 1.01316 2.48872 + vertex 1.60675 1.01718 2.4898 + vertex 1.60184 1.01717 2.48994 + endloop + endfacet + facet normal 0.0287078 -0.289862 0.956638 + outer loop + vertex 1.60184 1.01717 2.48994 + vertex 1.60675 1.01718 2.4898 + vertex 1.60561 1.02092 2.49097 + endloop + endfacet + facet normal 0.0290055 -0.290136 0.956546 + outer loop + vertex 1.60077 1.0207 2.49104 + vertex 1.60184 1.01717 2.48994 + vertex 1.60561 1.02092 2.49097 + endloop + endfacet + facet normal 0.0290845 -0.292019 0.95597 + outer loop + vertex 1.60561 1.02092 2.49097 + vertex 1.60417 1.02458 2.49213 + vertex 1.60077 1.0207 2.49104 + endloop + endfacet + facet normal 0.0236527 -0.294011 0.955509 + outer loop + vertex 1.60927 1.02473 2.49205 + vertex 1.60417 1.02458 2.49213 + vertex 1.60561 1.02092 2.49097 + endloop + endfacet + facet normal 0.0233989 -0.283387 0.95872 + outer loop + vertex 1.60927 1.02473 2.49205 + vertex 1.60803 1.02883 2.49329 + vertex 1.60417 1.02458 2.49213 + endloop + endfacet + facet normal 0.0323464 -0.290838 0.956226 + outer loop + vertex 1.60417 1.02458 2.49213 + vertex 1.60803 1.02883 2.49329 + vertex 1.60266 1.02843 2.49335 + endloop + endfacet + facet normal 0.0324095 -0.291724 0.955953 + outer loop + vertex 1.60803 1.02883 2.49329 + vertex 1.60624 1.03316 2.49467 + vertex 1.60266 1.02843 2.49335 + endloop + endfacet + facet normal 0.0224346 -0.284815 0.95832 + outer loop + vertex 1.60266 1.02843 2.49335 + vertex 1.60624 1.03316 2.49467 + vertex 1.60131 1.03178 2.49438 + endloop + endfacet + facet normal 0.00362613 -0.287954 0.957637 + outer loop + vertex 1.60642 1.03699 2.49588 + vertex 1.60459 1.03895 2.49647 + vertex 1.60247 1.0357 2.4955 + endloop + endfacet + facet normal 0.00801826 -0.300281 0.953817 + outer loop + vertex 1.60642 1.03699 2.49588 + vertex 1.60247 1.0357 2.4955 + vertex 1.60624 1.03316 2.49467 + endloop + endfacet + facet normal 0.0215777 -0.281931 0.959192 + outer loop + vertex 1.60624 1.03316 2.49467 + vertex 1.60247 1.0357 2.4955 + vertex 1.60131 1.03178 2.49438 + endloop + endfacet + facet normal 0.0217529 -0.272268 0.961976 + outer loop + vertex 1.60642 1.03699 2.49588 + vertex 1.60851 1.04058 2.49684 + vertex 1.60459 1.03895 2.49647 + endloop + endfacet + facet normal -0.00118702 -0.285077 0.958504 + outer loop + vertex 1.60247 1.0357 2.4955 + vertex 1.60459 1.03895 2.49647 + vertex 1.60174 1.03884 2.49644 + endloop + endfacet + facet normal -0.0007868 -0.294376 0.955689 + outer loop + vertex 1.60459 1.03895 2.49647 + vertex 1.6036 1.04272 2.49763 + vertex 1.60174 1.03884 2.49644 + endloop + endfacet + facet normal 0.0284071 -0.287263 0.957431 + outer loop + vertex 1.60459 1.03895 2.49647 + vertex 1.60851 1.04058 2.49684 + vertex 1.6036 1.04272 2.49763 + endloop + endfacet + facet normal 0.0403218 -0.26242 0.964111 + outer loop + vertex 1.60851 1.04058 2.49684 + vertex 1.60894 1.04489 2.498 + vertex 1.6036 1.04272 2.49763 + endloop + endfacet + facet normal 0.052794 -0.29159 0.955085 + outer loop + vertex 1.60894 1.04489 2.498 + vertex 1.60701 1.04903 2.49937 + vertex 1.6036 1.04272 2.49763 + endloop + endfacet + facet normal 0.0441182 -0.287376 0.956801 + outer loop + vertex 1.6036 1.04272 2.49763 + vertex 1.60701 1.04903 2.49937 + vertex 1.60153 1.04674 2.49893 + endloop + endfacet + facet normal 0.00719573 -0.286673 0.958001 + outer loop + vertex 1.60593 1.05256 2.50067 + vertex 1.60409 1.05444 2.50125 + vertex 1.60192 1.05095 2.50022 + endloop + endfacet + facet normal 0.0296726 -0.337751 0.940768 + outer loop + vertex 1.60593 1.05256 2.50067 + vertex 1.60192 1.05095 2.50022 + vertex 1.60701 1.04903 2.49937 + endloop + endfacet + facet normal 0.0478025 -0.295668 0.954094 + outer loop + vertex 1.60701 1.04903 2.49937 + vertex 1.60192 1.05095 2.50022 + vertex 1.60153 1.04674 2.49893 + endloop + endfacet + facet normal 0.04573 -0.25151 0.966774 + outer loop + vertex 1.60593 1.05256 2.50067 + vertex 1.60776 1.0559 2.50145 + vertex 1.60409 1.05444 2.50125 + endloop + endfacet + facet normal -0.011337 -0.276103 0.961061 + outer loop + vertex 1.60192 1.05095 2.50022 + vertex 1.60409 1.05444 2.50125 + vertex 1.60043 1.05473 2.50129 + endloop + endfacet + facet normal -0.00812856 -0.236557 0.971584 + outer loop + vertex 1.60409 1.05444 2.50125 + vertex 1.60435 1.05844 2.50222 + vertex 1.60043 1.05473 2.50129 + endloop + endfacet + facet normal 0.0407445 -0.239432 0.970058 + outer loop + vertex 1.60409 1.05444 2.50125 + vertex 1.60776 1.0559 2.50145 + vertex 1.60435 1.05844 2.50222 + endloop + endfacet + facet normal 0.0670962 -0.205921 0.976266 + outer loop + vertex 1.60776 1.0559 2.50145 + vertex 1.60889 1.05982 2.5022 + vertex 1.60435 1.05844 2.50222 + endloop + endfacet + facet normal 0.0720589 -0.22234 0.972303 + outer loop + vertex 1.60889 1.05982 2.5022 + vertex 1.60815 1.06349 2.5031 + vertex 1.60435 1.05844 2.50222 + endloop + endfacet + facet normal 0.0865546 -0.232619 0.968709 + outer loop + vertex 1.60435 1.05844 2.50222 + vertex 1.60815 1.06349 2.5031 + vertex 1.60292 1.06311 2.50347 + endloop + endfacet + facet normal 0.0879233 -0.258343 0.962044 + outer loop + vertex 1.60815 1.06349 2.5031 + vertex 1.60737 1.06849 2.50451 + vertex 1.60292 1.06311 2.50347 + endloop + endfacet + facet normal 0.0921056 -0.261559 0.960783 + outer loop + vertex 1.60292 1.06311 2.50347 + vertex 1.60737 1.06849 2.50451 + vertex 1.60171 1.06733 2.50474 + endloop + endfacet + facet normal 0.102857 -0.317668 0.942607 + outer loop + vertex 1.60171 1.06733 2.50474 + vertex 1.60737 1.06849 2.50451 + vertex 1.60489 1.07136 2.50575 + endloop + endfacet + facet normal 0.044192 -0.275759 0.96021 + outer loop + vertex 1.60041 1.07102 2.50586 + vertex 1.60171 1.06733 2.50474 + vertex 1.60489 1.07136 2.50575 + endloop + endfacet + facet normal 0.0433089 -0.263038 0.963813 + outer loop + vertex 1.60489 1.07136 2.50575 + vertex 1.60385 1.07469 2.5067 + vertex 1.60041 1.07102 2.50586 + endloop + endfacet + facet normal 0.084711 -0.250307 0.964454 + outer loop + vertex 1.60717 1.07455 2.50638 + vertex 1.60385 1.07469 2.5067 + vertex 1.60489 1.07136 2.50575 + endloop + endfacet + facet normal 0.0892055 -0.17794 0.97999 + outer loop + vertex 1.60717 1.07455 2.50638 + vertex 1.60809 1.07857 2.50702 + vertex 1.60385 1.07469 2.5067 + endloop + endfacet + facet normal 0.122737 -0.213619 0.969176 + outer loop + vertex 1.60385 1.07469 2.5067 + vertex 1.60809 1.07857 2.50702 + vertex 1.60324 1.07871 2.50767 + endloop + endfacet + facet normal 0.124026 0.247106 0.961018 + outer loop + vertex 1.60232 1.94204 2.50892 + vertex 1.60674 1.94543 2.50748 + vertex 1.60142 1.94635 2.50793 + endloop + endfacet + facet normal 0.118474 0.210503 0.970388 + outer loop + vertex 1.60674 1.94543 2.50748 + vertex 1.60506 1.95013 2.50666 + vertex 1.60142 1.94635 2.50793 + endloop + endfacet + facet normal 0.0772926 0.248499 0.965543 + outer loop + vertex 1.60142 1.94635 2.50793 + vertex 1.60506 1.95013 2.50666 + vertex 1.60041 1.95048 2.50695 + endloop + endfacet + facet normal 0.129028 0.254774 0.958354 + outer loop + vertex 1.60412 1.95415 2.50576 + vertex 1.60789 1.95323 2.5055 + vertex 1.60839 1.95724 2.50437 + endloop + endfacet + facet normal 0.119558 0.266928 0.956272 + outer loop + vertex 1.60325 1.95815 2.50476 + vertex 1.60412 1.95415 2.50576 + vertex 1.60839 1.95724 2.50437 + endloop + endfacet + facet normal 0.0765359 0.235566 0.96884 + outer loop + vertex 1.60506 1.95013 2.50666 + vertex 1.60412 1.95415 2.50576 + vertex 1.60041 1.95048 2.50695 + endloop + endfacet + facet normal 0.127002 0.245697 0.960991 + outer loop + vertex 1.60789 1.95323 2.5055 + vertex 1.60412 1.95415 2.50576 + vertex 1.60506 1.95013 2.50666 + endloop + endfacet + facet normal 0.114302 0.233058 0.965722 + outer loop + vertex 1.60839 1.95724 2.50437 + vertex 1.60686 1.96185 2.50343 + vertex 1.60325 1.95815 2.50476 + endloop + endfacet + facet normal 0.0801581 0.264622 0.961015 + outer loop + vertex 1.60325 1.95815 2.50476 + vertex 1.60686 1.96185 2.50343 + vertex 1.60206 1.9622 2.50374 + endloop + endfacet + facet normal 0.0783455 0.231772 0.96961 + outer loop + vertex 1.60686 1.96185 2.50343 + vertex 1.60529 1.96543 2.50271 + vertex 1.60206 1.9622 2.50374 + endloop + endfacet + facet normal 0.0414006 0.266575 0.962925 + outer loop + vertex 1.60206 1.9622 2.50374 + vertex 1.60529 1.96543 2.50271 + vertex 1.60119 1.96678 2.50251 + endloop + endfacet + facet normal 0.0165679 0.286828 0.957839 + outer loop + vertex 1.60563 1.97271 2.50075 + vertex 1.60263 1.97376 2.50049 + vertex 1.60297 1.9707 2.5014 + endloop + endfacet + facet normal 0.0433515 0.254093 0.966208 + outer loop + vertex 1.60297 1.9707 2.5014 + vertex 1.60625 1.96941 2.50159 + vertex 1.60563 1.97271 2.50075 + endloop + endfacet + facet normal 0.0432463 0.253837 0.96628 + outer loop + vertex 1.60297 1.9707 2.5014 + vertex 1.60119 1.96678 2.50251 + vertex 1.60625 1.96941 2.50159 + endloop + endfacet + facet normal 0.0393748 0.260716 0.964612 + outer loop + vertex 1.60119 1.96678 2.50251 + vertex 1.60529 1.96543 2.50271 + vertex 1.60625 1.96941 2.50159 + endloop + endfacet + facet normal 0.0902308 0.283453 0.954732 + outer loop + vertex 1.60563 1.97271 2.50075 + vertex 1.60857 1.97258 2.50051 + vertex 1.60779 1.97633 2.49947 + endloop + endfacet + facet normal 0.0283079 0.318025 0.94766 + outer loop + vertex 1.60563 1.97271 2.50075 + vertex 1.60779 1.97633 2.49947 + vertex 1.60263 1.97376 2.50049 + endloop + endfacet + facet normal 0.0488228 0.281043 0.958452 + outer loop + vertex 1.60263 1.97376 2.50049 + vertex 1.60779 1.97633 2.49947 + vertex 1.60251 1.97765 2.49935 + endloop + endfacet + facet normal 0.0897228 0.261468 0.961033 + outer loop + vertex 1.60857 1.97258 2.50051 + vertex 1.60563 1.97271 2.50075 + vertex 1.60625 1.96941 2.50159 + endloop + endfacet + facet normal 0.0425104 0.256504 0.965608 + outer loop + vertex 1.60779 1.97633 2.49947 + vertex 1.60656 1.98117 2.49824 + vertex 1.60251 1.97765 2.49935 + endloop + endfacet + facet normal 0.0300436 0.269872 0.962427 + outer loop + vertex 1.60251 1.97765 2.49935 + vertex 1.60656 1.98117 2.49824 + vertex 1.60181 1.98163 2.49826 + endloop + endfacet + facet normal 0.029776 0.267125 0.963202 + outer loop + vertex 1.60656 1.98117 2.49824 + vertex 1.60563 1.98533 2.49711 + vertex 1.60181 1.98163 2.49826 + endloop + endfacet + facet normal 0.0243198 0.272352 0.96189 + outer loop + vertex 1.60181 1.98163 2.49826 + vertex 1.60563 1.98533 2.49711 + vertex 1.60066 1.9855 2.49719 + endloop + endfacet + facet normal 0.0434616 0.276605 0.96 + outer loop + vertex 1.6044 1.98931 2.496 + vertex 1.60938 1.989 2.49587 + vertex 1.60819 1.99303 2.49476 + endloop + endfacet + facet normal 0.0302231 0.28903 0.956843 + outer loop + vertex 1.60314 1.99321 2.49487 + vertex 1.6044 1.98931 2.496 + vertex 1.60819 1.99303 2.49476 + endloop + endfacet + facet normal 0.0244116 0.275558 0.960974 + outer loop + vertex 1.60563 1.98533 2.49711 + vertex 1.6044 1.98931 2.496 + vertex 1.60066 1.9855 2.49719 + endloop + endfacet + facet normal 0.0436942 0.280882 0.958747 + outer loop + vertex 1.60938 1.989 2.49587 + vertex 1.6044 1.98931 2.496 + vertex 1.60563 1.98533 2.49711 + endloop + endfacet + facet normal 0.0300311 0.282624 0.95876 + outer loop + vertex 1.60819 1.99303 2.49476 + vertex 1.60683 1.99699 2.49364 + vertex 1.60314 1.99321 2.49487 + endloop + endfacet + facet normal 0.023265 0.288709 0.957134 + outer loop + vertex 1.60314 1.99321 2.49487 + vertex 1.60683 1.99699 2.49364 + vertex 1.60181 1.99717 2.49371 + endloop + endfacet + facet normal 0.0231889 0.286212 0.957886 + outer loop + vertex 1.60683 1.99699 2.49364 + vertex 1.6055 2.00098 2.49248 + vertex 1.60181 1.99717 2.49371 + endloop + endfacet + facet normal 0.0288964 0.281117 0.959238 + outer loop + vertex 1.60181 1.99717 2.49371 + vertex 1.6055 2.00098 2.49248 + vertex 1.60011 2.0015 2.49249 + endloop + endfacet + facet normal 0.02676 0.281731 0.95912 + outer loop + vertex 1.60436 2.00501 2.49129 + vertex 1.60933 2.00465 2.49126 + vertex 1.60813 2.00864 2.49012 + endloop + endfacet + facet normal 0.0251113 0.283305 0.958701 + outer loop + vertex 1.60283 2.00921 2.49009 + vertex 1.60436 2.00501 2.49129 + vertex 1.60813 2.00864 2.49012 + endloop + endfacet + facet normal 0.0296694 0.289192 0.956811 + outer loop + vertex 1.6055 2.00098 2.49248 + vertex 1.60436 2.00501 2.49129 + vertex 1.60011 2.0015 2.49249 + endloop + endfacet + facet normal 0.0272353 0.288581 0.957068 + outer loop + vertex 1.60933 2.00465 2.49126 + vertex 1.60436 2.00501 2.49129 + vertex 1.6055 2.00098 2.49248 + endloop + endfacet + facet normal 0.0259801 0.291296 0.95628 + outer loop + vertex 1.60813 2.00864 2.49012 + vertex 1.60711 2.0126 2.48894 + vertex 1.60283 2.00921 2.49009 + endloop + endfacet + facet normal 0.0242933 0.293233 0.955732 + outer loop + vertex 1.60283 2.00921 2.49009 + vertex 1.60711 2.0126 2.48894 + vertex 1.60312 2.01322 2.48885 + endloop + endfacet + facet normal 0.025564 0.301073 0.953258 + outer loop + vertex 1.60711 2.0126 2.48894 + vertex 1.60604 2.01713 2.48754 + vertex 1.60312 2.01322 2.48885 + endloop + endfacet + facet normal 0.0449965 0.287696 0.956664 + outer loop + vertex 1.60312 2.01322 2.48885 + vertex 1.60604 2.01713 2.48754 + vertex 1.60114 2.01563 2.48822 + endloop + endfacet + facet normal 0.0131659 0.306754 0.951698 + outer loop + vertex 1.60828 2.0208 2.4863 + vertex 1.60744 2.02411 2.48525 + vertex 1.60523 2.02084 2.48633 + endloop + endfacet + facet normal 0.0132243 0.312724 0.949752 + outer loop + vertex 1.60523 2.02084 2.48633 + vertex 1.60604 2.01713 2.48754 + vertex 1.60828 2.0208 2.4863 + endloop + endfacet + facet normal 0.0572235 0.320921 0.945376 + outer loop + vertex 1.60523 2.02084 2.48633 + vertex 1.60112 2.0196 2.487 + vertex 1.60604 2.01713 2.48754 + endloop + endfacet + facet normal 0.042766 0.29415 0.954802 + outer loop + vertex 1.60112 2.0196 2.487 + vertex 1.60114 2.01563 2.48822 + vertex 1.60604 2.01713 2.48754 + endloop + endfacet + facet normal 0.0359073 0.292645 0.955547 + outer loop + vertex 1.60325 2.02299 2.48575 + vertex 1.60523 2.02084 2.48633 + vertex 1.60744 2.02411 2.48525 + endloop + endfacet + facet normal 0.0373357 0.287933 0.956923 + outer loop + vertex 1.60325 2.02299 2.48575 + vertex 1.60744 2.02411 2.48525 + vertex 1.60323 2.02703 2.48453 + endloop + endfacet + facet normal 0.0447203 0.297772 0.953589 + outer loop + vertex 1.60323 2.02703 2.48453 + vertex 1.60744 2.02411 2.48525 + vertex 1.60815 2.02825 2.48392 + endloop + endfacet + facet normal 0.0601062 0.31277 0.947925 + outer loop + vertex 1.60523 2.02084 2.48633 + vertex 1.60325 2.02299 2.48575 + vertex 1.60112 2.0196 2.487 + endloop + endfacet + facet normal 0.0420435 0.307108 0.950745 + outer loop + vertex 1.60815 2.02825 2.48392 + vertex 1.60562 2.03194 2.48284 + vertex 1.60323 2.02703 2.48453 + endloop + endfacet + facet normal 0.172412 0.53544 0.826788 + outer loop + vertex 1.60948 2.09474 2.46119 + vertex 1.60871 2.0971 2.45982 + vertex 1.60598 2.09655 2.46075 + endloop + endfacet + facet normal 0.141646 0.484658 0.863159 + outer loop + vertex 1.60598 2.09655 2.46075 + vertex 1.60576 2.09245 2.46309 + vertex 1.60948 2.09474 2.46119 + endloop + endfacet + facet normal 0.206498 0.476385 0.854644 + outer loop + vertex 1.60598 2.09655 2.46075 + vertex 1.60134 2.09576 2.46231 + vertex 1.60576 2.09245 2.46309 + endloop + endfacet + facet normal 0.190303 0.457986 0.868351 + outer loop + vertex 1.60134 2.09576 2.46231 + vertex 1.60178 2.09255 2.4639 + vertex 1.60576 2.09245 2.46309 + endloop + endfacet + facet normal 0.253968 0.739109 0.623874 + outer loop + vertex 1.60814 2.09942 2.45784 + vertex 1.60713 2.10206 2.45511 + vertex 1.60456 2.10123 2.45714 + endloop + endfacet + facet normal 0.224085 0.662778 0.714501 + outer loop + vertex 1.60456 2.10123 2.45714 + vertex 1.60099 2.10162 2.4579 + vertex 1.60318 2.09911 2.45955 + endloop + endfacet + facet normal 0.203454 0.672688 0.711405 + outer loop + vertex 1.60814 2.09942 2.45784 + vertex 1.60456 2.10123 2.45714 + vertex 1.60318 2.09911 2.45955 + endloop + endfacet + facet normal 0.225789 0.604675 0.763799 + outer loop + vertex 1.60814 2.09942 2.45784 + vertex 1.60318 2.09911 2.45955 + vertex 1.60598 2.09655 2.46075 + endloop + endfacet + facet normal 0.117767 0.662071 0.74013 + outer loop + vertex 1.60814 2.09942 2.45784 + vertex 1.60598 2.09655 2.46075 + vertex 1.60871 2.0971 2.45982 + endloop + endfacet + facet normal 0.174218 0.567487 0.80474 + outer loop + vertex 1.60598 2.09655 2.46075 + vertex 1.60318 2.09911 2.45955 + vertex 1.60134 2.09576 2.46231 + endloop + endfacet + facet normal 0.226128 0.871164 0.435821 + outer loop + vertex 1.60308 2.10507 2.45205 + vertex 1.60845 2.10407 2.45126 + vertex 1.60532 2.10627 2.44849 + endloop + endfacet + facet normal 0.209433 0.879187 0.427981 + outer loop + vertex 1.60151 2.10662 2.44963 + vertex 1.60308 2.10507 2.45205 + vertex 1.60532 2.10627 2.44849 + endloop + endfacet + facet normal 0.219533 0.77365 0.594366 + outer loop + vertex 1.60713 2.10206 2.45511 + vertex 1.60388 2.10315 2.4549 + vertex 1.60456 2.10123 2.45714 + endloop + endfacet + facet normal 0.241776 0.824138 0.512192 + outer loop + vertex 1.60713 2.10206 2.45511 + vertex 1.60845 2.10407 2.45126 + vertex 1.60388 2.10315 2.4549 + endloop + endfacet + facet normal 0.228846 0.835885 0.498924 + outer loop + vertex 1.60845 2.10407 2.45126 + vertex 1.60308 2.10507 2.45205 + vertex 1.60388 2.10315 2.4549 + endloop + endfacet + facet normal 0.211214 0.773877 0.597078 + outer loop + vertex 1.60456 2.10123 2.45714 + vertex 1.60388 2.10315 2.4549 + vertex 1.60099 2.10162 2.4579 + endloop + endfacet + facet normal 0.006521 0.0959012 0.995369 + outer loop + vertex 1.61 2.11192 2.445 + vertex 1.605 2.11226 2.445 + vertex 1.60786 2.10837 2.44536 + endloop + endfacet + facet normal 0.167613 0.211305 0.962941 + outer loop + vertex 1.60786 2.10837 2.44536 + vertex 1.605 2.11226 2.445 + vertex 1.60177 2.10858 2.44637 + endloop + endfacet + facet normal 0.230376 0.826013 0.514422 + outer loop + vertex 1.60532 2.10627 2.44849 + vertex 1.60177 2.10858 2.44637 + vertex 1.60151 2.10662 2.44963 + endloop + endfacet + facet normal 0.130341 0.771741 0.622437 + outer loop + vertex 1.60786 2.10837 2.44536 + vertex 1.60177 2.10858 2.44637 + vertex 1.60532 2.10627 2.44849 + endloop + endfacet + facet normal 0.236214 -0.408536 0.881647 + outer loop + vertex 1.61134 0.92338 2.44588 + vertex 1.615 0.92359 2.445 + vertex 1.61547 0.923933 2.44503 + endloop + endfacet + facet normal 0.185961 -0.791415 0.582306 + outer loop + vertex 1.61134 0.92338 2.44588 + vertex 1.60755 0.922414 2.44578 + vertex 1.615 0.92359 2.445 + endloop + endfacet + facet normal 0.1861 -0.802837 0.566409 + outer loop + vertex 1.60755 0.922414 2.44578 + vertex 1.61 0.922431 2.445 + vertex 1.615 0.92359 2.445 + endloop + endfacet + facet normal 0.216731 -0.892079 0.396512 + outer loop + vertex 1.61134 0.92338 2.44588 + vertex 1.60849 0.923562 2.44785 + vertex 1.60755 0.922414 2.44578 + endloop + endfacet + facet normal 0.20197 -0.894295 0.399304 + outer loop + vertex 1.61547 0.923933 2.44503 + vertex 1.61252 0.924723 2.44829 + vertex 1.61134 0.92338 2.44588 + endloop + endfacet + facet normal 0.214287 -0.894148 0.393167 + outer loop + vertex 1.60849 0.923562 2.44785 + vertex 1.61134 0.92338 2.44588 + vertex 1.61252 0.924723 2.44829 + endloop + endfacet + facet normal 0.207903 -0.882771 0.421299 + outer loop + vertex 1.60849 0.923562 2.44785 + vertex 1.61252 0.924723 2.44829 + vertex 1.6075 0.924894 2.45113 + endloop + endfacet + facet normal 0.227163 -0.861486 0.454134 + outer loop + vertex 1.6075 0.924894 2.45113 + vertex 1.61252 0.924723 2.44829 + vertex 1.61134 0.926759 2.45274 + endloop + endfacet + facet normal 0.190557 -0.805307 0.561398 + outer loop + vertex 1.61092 0.929379 2.45665 + vertex 1.61134 0.926759 2.45274 + vertex 1.61468 0.928618 2.45428 + endloop + endfacet + facet normal 0.236999 -0.794447 0.559183 + outer loop + vertex 1.61092 0.929379 2.45665 + vertex 1.60621 0.927131 2.45545 + vertex 1.61134 0.926759 2.45274 + endloop + endfacet + facet normal 0.200713 -0.844121 0.497166 + outer loop + vertex 1.60621 0.927131 2.45545 + vertex 1.6075 0.924894 2.45113 + vertex 1.61134 0.926759 2.45274 + endloop + endfacet + facet normal 0.214704 -0.770018 0.600811 + outer loop + vertex 1.61092 0.929379 2.45665 + vertex 1.60704 0.929655 2.45839 + vertex 1.60621 0.927131 2.45545 + endloop + endfacet + facet normal 0.216087 -0.776012 0.592547 + outer loop + vertex 1.61468 0.928618 2.45428 + vertex 1.61416 0.930148 2.45647 + vertex 1.61092 0.929379 2.45665 + endloop + endfacet + facet normal 0.210913 -0.646816 0.732901 + outer loop + vertex 1.60704 0.929655 2.45839 + vertex 1.6096 0.932057 2.45977 + vertex 1.60552 0.931756 2.46068 + endloop + endfacet + facet normal 0.261206 -0.675518 0.689527 + outer loop + vertex 1.61092 0.929379 2.45665 + vertex 1.6096 0.932057 2.45977 + vertex 1.60704 0.929655 2.45839 + endloop + endfacet + facet normal 0.217123 -0.693812 0.686645 + outer loop + vertex 1.61092 0.929379 2.45665 + vertex 1.61404 0.932307 2.45862 + vertex 1.6096 0.932057 2.45977 + endloop + endfacet + facet normal 0.200343 -0.685109 0.700349 + outer loop + vertex 1.61092 0.929379 2.45665 + vertex 1.61416 0.930148 2.45647 + vertex 1.61404 0.932307 2.45862 + endloop + endfacet + facet normal 0.219799 -0.552523 0.803994 + outer loop + vertex 1.6096 0.932057 2.45977 + vertex 1.60868 0.935087 2.46211 + vertex 1.60552 0.931756 2.46068 + endloop + endfacet + facet normal 0.233364 -0.592165 0.771286 + outer loop + vertex 1.61404 0.932307 2.45862 + vertex 1.61221 0.934789 2.46108 + vertex 1.6096 0.932057 2.45977 + endloop + endfacet + facet normal 0.18645 -0.5634 0.804871 + outer loop + vertex 1.61221 0.934789 2.46108 + vertex 1.60868 0.935087 2.46211 + vertex 1.6096 0.932057 2.45977 + endloop + endfacet + facet normal 0.205781 -0.486544 0.849075 + outer loop + vertex 1.61221 0.934789 2.46108 + vertex 1.61338 0.938653 2.46301 + vertex 1.60868 0.935087 2.46211 + endloop + endfacet + facet normal 0.158746 -0.434072 0.886781 + outer loop + vertex 1.61338 0.938653 2.46301 + vertex 1.60815 0.938818 2.46403 + vertex 1.60868 0.935087 2.46211 + endloop + endfacet + facet normal 0.0334482 -0.304127 0.952044 + outer loop + vertex 1.6076 0.983101 2.47883 + vertex 1.61171 0.987026 2.47994 + vertex 1.60687 0.987026 2.48011 + endloop + endfacet + facet normal 0.0333778 -0.310348 0.950037 + outer loop + vertex 1.60687 0.987026 2.48011 + vertex 1.61171 0.987026 2.47994 + vertex 1.61058 0.990711 2.48118 + endloop + endfacet + facet normal 0.0347686 -0.311613 0.949573 + outer loop + vertex 1.60579 0.990465 2.48128 + vertex 1.60687 0.987026 2.48011 + vertex 1.61058 0.990711 2.48118 + endloop + endfacet + facet normal 0.0349202 -0.314989 0.948453 + outer loop + vertex 1.61058 0.990711 2.48118 + vertex 1.60919 0.994297 2.48243 + vertex 1.60579 0.990465 2.48128 + endloop + endfacet + facet normal 0.0252422 -0.318441 0.947607 + outer loop + vertex 1.61425 0.994477 2.48235 + vertex 1.60919 0.994297 2.48243 + vertex 1.61058 0.990711 2.48118 + endloop + endfacet + facet normal 0.0249433 -0.308734 0.950821 + outer loop + vertex 1.61425 0.994477 2.48235 + vertex 1.61316 0.998381 2.48365 + vertex 1.60919 0.994297 2.48243 + endloop + endfacet + facet normal 0.0331206 -0.315903 0.948213 + outer loop + vertex 1.60919 0.994297 2.48243 + vertex 1.61316 0.998381 2.48365 + vertex 1.60786 0.998095 2.48374 + endloop + endfacet + facet normal 0.0330069 -0.313555 0.948996 + outer loop + vertex 1.61316 0.998381 2.48365 + vertex 1.6119 1.00216 2.48494 + vertex 1.60786 0.998095 2.48374 + endloop + endfacet + facet normal 0.0246579 -0.306057 0.951694 + outer loop + vertex 1.60786 0.998095 2.48374 + vertex 1.6119 1.00216 2.48494 + vertex 1.60685 1.00198 2.48501 + endloop + endfacet + facet normal 0.0248075 -0.310711 0.950181 + outer loop + vertex 1.60685 1.00198 2.48501 + vertex 1.6119 1.00216 2.48494 + vertex 1.61055 1.0057 2.48613 + endloop + endfacet + facet normal 0.0159775 -0.302764 0.952932 + outer loop + vertex 1.60571 1.0055 2.48615 + vertex 1.60685 1.00198 2.48501 + vertex 1.61055 1.0057 2.48613 + endloop + endfacet + facet normal 0.0159151 -0.301222 0.953421 + outer loop + vertex 1.61055 1.0057 2.48613 + vertex 1.60916 1.00931 2.4873 + vertex 1.60571 1.0055 2.48615 + endloop + endfacet + facet normal 0.0314762 -0.295704 0.954761 + outer loop + vertex 1.61419 1.00954 2.4872 + vertex 1.60916 1.00931 2.4873 + vertex 1.61055 1.0057 2.48613 + endloop + endfacet + facet normal 0.0310473 -0.285033 0.958015 + outer loop + vertex 1.61419 1.00954 2.4872 + vertex 1.61312 1.01352 2.48842 + vertex 1.60916 1.00931 2.4873 + endloop + endfacet + facet normal 0.0390992 -0.291978 0.955626 + outer loop + vertex 1.60916 1.00931 2.4873 + vertex 1.61312 1.01352 2.48842 + vertex 1.60785 1.01321 2.48854 + endloop + endfacet + facet normal 0.0396043 -0.301778 0.952555 + outer loop + vertex 1.61312 1.01352 2.48842 + vertex 1.61179 1.01739 2.4897 + vertex 1.60785 1.01321 2.48854 + endloop + endfacet + facet normal 0.0300276 -0.293571 0.955466 + outer loop + vertex 1.60785 1.01321 2.48854 + vertex 1.61179 1.01739 2.4897 + vertex 1.60675 1.01718 2.4898 + endloop + endfacet + facet normal 0.0304645 -0.305545 0.95169 + outer loop + vertex 1.60675 1.01718 2.4898 + vertex 1.61179 1.01739 2.4897 + vertex 1.61042 1.02098 2.4909 + endloop + endfacet + facet normal 0.0165593 -0.293346 0.955863 + outer loop + vertex 1.60561 1.02092 2.49097 + vertex 1.60675 1.01718 2.4898 + vertex 1.61042 1.02098 2.4909 + endloop + endfacet + facet normal 0.0165186 -0.287721 0.957572 + outer loop + vertex 1.61042 1.02098 2.4909 + vertex 1.60927 1.02473 2.49205 + vertex 1.60561 1.02092 2.49097 + endloop + endfacet + facet normal 0.0502378 -0.277906 0.959294 + outer loop + vertex 1.61387 1.02469 2.49179 + vertex 1.60927 1.02473 2.49205 + vertex 1.61042 1.02098 2.4909 + endloop + endfacet + facet normal 0.0507296 -0.255791 0.9654 + outer loop + vertex 1.61387 1.02469 2.49179 + vertex 1.61326 1.02886 2.49293 + vertex 1.60927 1.02473 2.49205 + endloop + endfacet + facet normal 0.0672608 -0.270631 0.960331 + outer loop + vertex 1.60927 1.02473 2.49205 + vertex 1.61326 1.02886 2.49293 + vertex 1.60803 1.02883 2.49329 + endloop + endfacet + facet normal 0.0671596 -0.278294 0.958145 + outer loop + vertex 1.61326 1.02886 2.49293 + vertex 1.61243 1.03379 2.49442 + vertex 1.60803 1.02883 2.49329 + endloop + endfacet + facet normal 0.0669839 -0.27815 0.958199 + outer loop + vertex 1.60803 1.02883 2.49329 + vertex 1.61243 1.03379 2.49442 + vertex 1.60624 1.03316 2.49467 + endloop + endfacet + facet normal 0.0716526 -0.330848 0.94096 + outer loop + vertex 1.60624 1.03316 2.49467 + vertex 1.61243 1.03379 2.49442 + vertex 1.61009 1.03695 2.49571 + endloop + endfacet + facet normal 0.0394462 -0.301412 0.952678 + outer loop + vertex 1.60642 1.03699 2.49588 + vertex 1.60624 1.03316 2.49467 + vertex 1.61009 1.03695 2.49571 + endloop + endfacet + facet normal 0.0399349 -0.281922 0.958606 + outer loop + vertex 1.61009 1.03695 2.49571 + vertex 1.60851 1.04058 2.49684 + vertex 1.60642 1.03699 2.49588 + endloop + endfacet + facet normal 0.081598 -0.264455 0.96094 + outer loop + vertex 1.61293 1.04037 2.49641 + vertex 1.60851 1.04058 2.49684 + vertex 1.61009 1.03695 2.49571 + endloop + endfacet + facet normal 0.0840468 -0.230539 0.969427 + outer loop + vertex 1.61293 1.04037 2.49641 + vertex 1.61286 1.04421 2.49733 + vertex 1.60851 1.04058 2.49684 + endloop + endfacet + facet normal 0.11673 -0.267958 0.956333 + outer loop + vertex 1.60851 1.04058 2.49684 + vertex 1.61286 1.04421 2.49733 + vertex 1.60894 1.04489 2.498 + endloop + endfacet + facet normal 0.123396 -0.23679 0.963693 + outer loop + vertex 1.61286 1.04421 2.49733 + vertex 1.61276 1.04874 2.49846 + vertex 1.60894 1.04489 2.498 + endloop + endfacet + facet normal 0.1395 -0.252068 0.957602 + outer loop + vertex 1.60894 1.04489 2.498 + vertex 1.61276 1.04874 2.49846 + vertex 1.60701 1.04903 2.49937 + endloop + endfacet + facet normal 0.0944962 -0.318846 0.943084 + outer loop + vertex 1.60883 1.05312 2.50057 + vertex 1.60593 1.05256 2.50067 + vertex 1.60701 1.04903 2.49937 + endloop + endfacet + facet normal 0.212848 -0.361113 0.907906 + outer loop + vertex 1.60883 1.05312 2.50057 + vertex 1.60701 1.04903 2.49937 + vertex 1.61259 1.05352 2.49985 + endloop + endfacet + facet normal 0.137627 -0.272506 0.95226 + outer loop + vertex 1.61259 1.05352 2.49985 + vertex 1.60701 1.04903 2.49937 + vertex 1.61276 1.04874 2.49846 + endloop + endfacet + facet normal 0.0859548 -0.271602 0.958563 + outer loop + vertex 1.60883 1.05312 2.50057 + vertex 1.60776 1.0559 2.50145 + vertex 1.60593 1.05256 2.50067 + endloop + endfacet + facet normal 0.290248 0.063237 0.95486 + outer loop + vertex 1.61131 1.65648 2.54639 + vertex 1.61486 1.6589 2.54515 + vertex 1.61069 1.66049 2.54631 + endloop + endfacet + facet normal 0.0836966 0.265652 0.960429 + outer loop + vertex 1.60779 1.97633 2.49947 + vertex 1.61065 1.98049 2.49807 + vertex 1.60656 1.98117 2.49824 + endloop + endfacet + facet normal 0.0830986 0.261743 0.961554 + outer loop + vertex 1.61065 1.98049 2.49807 + vertex 1.61088 1.98468 2.49691 + vertex 1.60656 1.98117 2.49824 + endloop + endfacet + facet normal 0.0712636 0.275207 0.95874 + outer loop + vertex 1.60656 1.98117 2.49824 + vertex 1.61088 1.98468 2.49691 + vertex 1.60563 1.98533 2.49711 + endloop + endfacet + facet normal 0.110378 0.274052 0.95536 + outer loop + vertex 1.60938 1.989 2.49587 + vertex 1.61347 1.98821 2.49562 + vertex 1.61356 1.99222 2.49446 + endloop + endfacet + facet normal 0.0968215 0.290213 0.952052 + outer loop + vertex 1.60819 1.99303 2.49476 + vertex 1.60938 1.989 2.49587 + vertex 1.61356 1.99222 2.49446 + endloop + endfacet + facet normal 0.0691752 0.256614 0.964035 + outer loop + vertex 1.61088 1.98468 2.49691 + vertex 1.60938 1.989 2.49587 + vertex 1.60563 1.98533 2.49711 + endloop + endfacet + facet normal 0.109471 0.268902 0.956926 + outer loop + vertex 1.61347 1.98821 2.49562 + vertex 1.60938 1.989 2.49587 + vertex 1.61088 1.98468 2.49691 + endloop + endfacet + facet normal 0.0924168 0.25736 0.961886 + outer loop + vertex 1.61356 1.99222 2.49446 + vertex 1.61181 1.99661 2.49345 + vertex 1.60819 1.99303 2.49476 + endloop + endfacet + facet normal 0.0568933 0.290781 0.955097 + outer loop + vertex 1.60819 1.99303 2.49476 + vertex 1.61181 1.99661 2.49345 + vertex 1.60683 1.99699 2.49364 + endloop + endfacet + facet normal 0.0559195 0.275784 0.959592 + outer loop + vertex 1.61181 1.99661 2.49345 + vertex 1.61059 2.00065 2.49236 + vertex 1.60683 1.99699 2.49364 + endloop + endfacet + facet normal 0.0396868 0.29114 0.955857 + outer loop + vertex 1.60683 1.99699 2.49364 + vertex 1.61059 2.00065 2.49236 + vertex 1.6055 2.00098 2.49248 + endloop + endfacet + facet normal 0.07561 0.269218 0.960107 + outer loop + vertex 1.60933 2.00465 2.49126 + vertex 1.61428 2.00411 2.49102 + vertex 1.61319 2.00822 2.48996 + endloop + endfacet + facet normal 0.0554081 0.289382 0.955609 + outer loop + vertex 1.60813 2.00864 2.49012 + vertex 1.60933 2.00465 2.49126 + vertex 1.61319 2.00822 2.48996 + endloop + endfacet + facet normal 0.0389102 0.27738 0.959972 + outer loop + vertex 1.61059 2.00065 2.49236 + vertex 1.60933 2.00465 2.49126 + vertex 1.6055 2.00098 2.49248 + endloop + endfacet + facet normal 0.0773873 0.287978 0.954505 + outer loop + vertex 1.61428 2.00411 2.49102 + vertex 1.60933 2.00465 2.49126 + vertex 1.61059 2.00065 2.49236 + endloop + endfacet + facet normal 0.0540429 0.270608 0.961171 + outer loop + vertex 1.61319 2.00822 2.48996 + vertex 1.61189 2.01228 2.48889 + vertex 1.60813 2.00864 2.49012 + endloop + endfacet + facet normal 0.0311379 0.292469 0.955768 + outer loop + vertex 1.60813 2.00864 2.49012 + vertex 1.61189 2.01228 2.48889 + vertex 1.60711 2.0126 2.48894 + endloop + endfacet + facet normal 0.0305543 0.283392 0.958517 + outer loop + vertex 1.61189 2.01228 2.48889 + vertex 1.61046 2.01558 2.48795 + vertex 1.60711 2.0126 2.48894 + endloop + endfacet + facet normal 0.0154377 0.298949 0.954144 + outer loop + vertex 1.60711 2.0126 2.48894 + vertex 1.61046 2.01558 2.48795 + vertex 1.60604 2.01713 2.48754 + endloop + endfacet + facet normal 0.0029064 0.304405 0.952538 + outer loop + vertex 1.61091 2.02272 2.48568 + vertex 1.60744 2.02411 2.48525 + vertex 1.60828 2.0208 2.4863 + endloop + endfacet + facet normal 0.00388628 0.303187 0.952923 + outer loop + vertex 1.60828 2.0208 2.4863 + vertex 1.61161 2.01944 2.48672 + vertex 1.61091 2.02272 2.48568 + endloop + endfacet + facet normal 0.00918808 0.314961 0.94906 + outer loop + vertex 1.60828 2.0208 2.4863 + vertex 1.60604 2.01713 2.48754 + vertex 1.61161 2.01944 2.48672 + endloop + endfacet + facet normal 0.0159542 0.300311 0.953708 + outer loop + vertex 1.60604 2.01713 2.48754 + vertex 1.61046 2.01558 2.48795 + vertex 1.61161 2.01944 2.48672 + endloop + endfacet + facet normal 0.0172902 0.314877 0.948975 + outer loop + vertex 1.61091 2.02272 2.48568 + vertex 1.61392 2.02268 2.48564 + vertex 1.61298 2.02651 2.48439 + endloop + endfacet + facet normal 0.00931025 0.318833 0.947765 + outer loop + vertex 1.61091 2.02272 2.48568 + vertex 1.61298 2.02651 2.48439 + vertex 1.60744 2.02411 2.48525 + endloop + endfacet + facet normal 0.0172563 0.302322 0.95305 + outer loop + vertex 1.60744 2.02411 2.48525 + vertex 1.61298 2.02651 2.48439 + vertex 1.60815 2.02825 2.48392 + endloop + endfacet + facet normal 0.0172289 0.305727 0.951963 + outer loop + vertex 1.61392 2.02268 2.48564 + vertex 1.61091 2.02272 2.48568 + vertex 1.61161 2.01944 2.48672 + endloop + endfacet + facet normal 0.018336 0.305076 0.952152 + outer loop + vertex 1.61298 2.02651 2.48439 + vertex 1.6116 2.03184 2.4827 + vertex 1.60815 2.02825 2.48392 + endloop + endfacet + facet normal 0.0267849 0.29768 0.95429 + outer loop + vertex 1.60815 2.02825 2.48392 + vertex 1.6116 2.03184 2.4827 + vertex 1.60562 2.03194 2.48284 + endloop + endfacet + facet normal 0.00803716 0.318943 0.94774 + outer loop + vertex 1.60927 2.03555 2.48151 + vertex 1.61304 2.03567 2.48144 + vertex 1.61262 2.03871 2.48042 + endloop + endfacet + facet normal 0.0232387 0.304416 0.952256 + outer loop + vertex 1.60787 2.03946 2.48029 + vertex 1.60927 2.03555 2.48151 + vertex 1.61262 2.03871 2.48042 + endloop + endfacet + facet normal 0.0270307 0.321226 0.946617 + outer loop + vertex 1.6116 2.03184 2.4827 + vertex 1.60927 2.03555 2.48151 + vertex 1.60562 2.03194 2.48284 + endloop + endfacet + facet normal 0.00837059 0.310744 0.950457 + outer loop + vertex 1.61304 2.03567 2.48144 + vertex 1.60927 2.03555 2.48151 + vertex 1.6116 2.03184 2.4827 + endloop + endfacet + facet normal 0.0249031 0.314283 0.949003 + outer loop + vertex 1.61262 2.03871 2.48042 + vertex 1.61253 2.04252 2.47916 + vertex 1.60787 2.03946 2.48029 + endloop + endfacet + facet normal 0.130191 0.330951 0.934624 + outer loop + vertex 1.60837 2.08734 2.4647 + vertex 1.61278 2.08397 2.46528 + vertex 1.61307 2.08766 2.46394 + endloop + endfacet + facet normal 0.178735 0.559302 0.809466 + outer loop + vertex 1.60948 2.09474 2.46119 + vertex 1.61398 2.09369 2.46092 + vertex 1.61179 2.0969 2.45918 + endloop + endfacet + facet normal 0.2034 0.539806 0.816847 + outer loop + vertex 1.60871 2.0971 2.45982 + vertex 1.60948 2.09474 2.46119 + vertex 1.61179 2.0969 2.45918 + endloop + endfacet + facet normal 0.167158 0.453421 0.875481 + outer loop + vertex 1.61118 2.09098 2.46281 + vertex 1.60948 2.09474 2.46119 + vertex 1.60576 2.09245 2.46309 + endloop + endfacet + facet normal 0.157584 0.450511 0.878753 + outer loop + vertex 1.61398 2.09369 2.46092 + vertex 1.60948 2.09474 2.46119 + vertex 1.61118 2.09098 2.46281 + endloop + endfacet + facet normal 0.177474 0.7692 0.613868 + outer loop + vertex 1.60814 2.09942 2.45784 + vertex 1.6138 2.09926 2.4564 + vertex 1.61103 2.10167 2.45418 + endloop + endfacet + facet normal 0.226473 0.739253 0.634205 + outer loop + vertex 1.60713 2.10206 2.45511 + vertex 1.60814 2.09942 2.45784 + vertex 1.61103 2.10167 2.45418 + endloop + endfacet + facet normal 0.191559 0.664779 0.722063 + outer loop + vertex 1.61179 2.0969 2.45918 + vertex 1.60814 2.09942 2.45784 + vertex 1.60871 2.0971 2.45982 + endloop + endfacet + facet normal 0.199776 0.671931 0.713161 + outer loop + vertex 1.6138 2.09926 2.4564 + vertex 1.60814 2.09942 2.45784 + vertex 1.61179 2.0969 2.45918 + endloop + endfacet + facet normal 0.0929519 0.723488 0.68405 + outer loop + vertex 1.61445 2.10532 2.44723 + vertex 1.61228 2.10743 2.44529 + vertex 1.60949 2.10596 2.44723 + endloop + endfacet + facet normal 0.20357 0.8658 0.45711 + outer loop + vertex 1.60949 2.10596 2.44723 + vertex 1.60532 2.10627 2.44849 + vertex 1.60845 2.10407 2.45126 + endloop + endfacet + facet normal 0.114156 0.888379 0.444692 + outer loop + vertex 1.60949 2.10596 2.44723 + vertex 1.60845 2.10407 2.45126 + vertex 1.61445 2.10532 2.44723 + endloop + endfacet + facet normal 0.191763 0.820084 0.539156 + outer loop + vertex 1.61445 2.10532 2.44723 + vertex 1.60845 2.10407 2.45126 + vertex 1.61344 2.10304 2.45106 + endloop + endfacet + facet normal 0.205839 0.837201 0.50668 + outer loop + vertex 1.61103 2.10167 2.45418 + vertex 1.60845 2.10407 2.45126 + vertex 1.60713 2.10206 2.45511 + endloop + endfacet + facet normal 0.193857 0.834801 0.515293 + outer loop + vertex 1.61344 2.10304 2.45106 + vertex 1.60845 2.10407 2.45126 + vertex 1.61103 2.10167 2.45418 + endloop + endfacet + facet normal 0.15267 0.668041 0.728295 + outer loop + vertex 1.61228 2.10743 2.44529 + vertex 1.60786 2.10837 2.44536 + vertex 1.60949 2.10596 2.44723 + endloop + endfacet + facet normal 0.026079 0.0576965 0.997993 + outer loop + vertex 1.61228 2.10743 2.44529 + vertex 1.615 2.1113 2.445 + vertex 1.60786 2.10837 2.44536 + endloop + endfacet + facet normal 0.0115227 0.0929056 0.995608 + outer loop + vertex 1.615 2.1113 2.445 + vertex 1.61 2.11192 2.445 + vertex 1.60786 2.10837 2.44536 + endloop + endfacet + facet normal 0.2561 0.694504 0.672367 + outer loop + vertex 1.60949 2.10596 2.44723 + vertex 1.60786 2.10837 2.44536 + vertex 1.60532 2.10627 2.44849 + endloop + endfacet + facet normal 0.0253622 -0.129799 0.991216 + outer loop + vertex 1.62 0.924567 2.445 + vertex 1.61547 0.923933 2.44503 + vertex 1.615 0.92359 2.445 + endloop + endfacet + facet normal -0.137078 0.969017 -0.205466 + outer loop + vertex 1.61977 0.924358 2.44417 + vertex 1.61547 0.923933 2.44503 + vertex 1.62 0.924567 2.445 + endloop + endfacet + facet normal 0.172034 -0.892687 0.416551 + outer loop + vertex 1.61547 0.923933 2.44503 + vertex 1.61977 0.924358 2.44417 + vertex 1.61818 0.924991 2.44618 + endloop + endfacet + facet normal 0.187724 -0.902195 0.388335 + outer loop + vertex 1.61252 0.924723 2.44829 + vertex 1.61547 0.923933 2.44503 + vertex 1.61818 0.924991 2.44618 + endloop + endfacet + facet normal 0.20632 -0.873053 0.441827 + outer loop + vertex 1.61818 0.924991 2.44618 + vertex 1.6166 0.926739 2.45037 + vertex 1.61252 0.924723 2.44829 + endloop + endfacet + facet normal 0.200158 -0.869881 0.450826 + outer loop + vertex 1.6166 0.926739 2.45037 + vertex 1.61134 0.926759 2.45274 + vertex 1.61252 0.924723 2.44829 + endloop + endfacet + facet normal 0.227251 -0.829278 0.510543 + outer loop + vertex 1.6166 0.926739 2.45037 + vertex 1.61468 0.928618 2.45428 + vertex 1.61134 0.926759 2.45274 + endloop + endfacet + facet normal 0.194856 -0.843056 0.501286 + outer loop + vertex 1.61817 0.928695 2.45305 + vertex 1.61468 0.928618 2.45428 + vertex 1.6166 0.926739 2.45037 + endloop + endfacet + facet normal 0.225349 -0.773423 0.592482 + outer loop + vertex 1.61468 0.928618 2.45428 + vertex 1.61817 0.928695 2.45305 + vertex 1.6175 0.930697 2.45592 + endloop + endfacet + facet normal 0.225061 -0.773274 0.592785 + outer loop + vertex 1.61416 0.930148 2.45647 + vertex 1.61468 0.928618 2.45428 + vertex 1.6175 0.930697 2.45592 + endloop + endfacet + facet normal 0.226948 -0.680293 0.696918 + outer loop + vertex 1.6175 0.930697 2.45592 + vertex 1.61404 0.932307 2.45862 + vertex 1.61416 0.930148 2.45647 + endloop + endfacet + facet normal 0.201358 -0.705684 0.679312 + outer loop + vertex 1.61879 0.933592 2.45855 + vertex 1.61404 0.932307 2.45862 + vertex 1.6175 0.930697 2.45592 + endloop + endfacet + facet normal 0.17417 -0.599742 0.781008 + outer loop + vertex 1.61404 0.932307 2.45862 + vertex 1.61879 0.933592 2.45855 + vertex 1.61621 0.9359 2.46089 + endloop + endfacet + facet normal 0.204426 -0.608806 0.766528 + outer loop + vertex 1.61221 0.934789 2.46108 + vertex 1.61404 0.932307 2.45862 + vertex 1.61621 0.9359 2.46089 + endloop + endfacet + facet normal 0.173321 -0.481727 0.85901 + outer loop + vertex 1.61621 0.9359 2.46089 + vertex 1.61338 0.938653 2.46301 + vertex 1.61221 0.934789 2.46108 + endloop + endfacet + facet normal 0.129028 -0.517321 0.846009 + outer loop + vertex 1.61886 0.939405 2.46263 + vertex 1.61338 0.938653 2.46301 + vertex 1.61621 0.9359 2.46089 + endloop + endfacet + facet normal 0.030335 -0.32364 0.945694 + outer loop + vertex 1.61913 0.964799 2.47216 + vertex 1.61807 0.968629 2.4735 + vertex 1.61409 0.964631 2.47226 + endloop + endfacet + facet normal 0.0383225 -0.330743 0.942943 + outer loop + vertex 1.61409 0.964631 2.47226 + vertex 1.61807 0.968629 2.4735 + vertex 1.61281 0.968338 2.47361 + endloop + endfacet + facet normal 0.0380843 -0.325765 0.944683 + outer loop + vertex 1.61807 0.968629 2.4735 + vertex 1.61686 0.972336 2.47483 + vertex 1.61281 0.968338 2.47361 + endloop + endfacet + facet normal 0.0318695 -0.320119 0.946841 + outer loop + vertex 1.61281 0.968338 2.47361 + vertex 1.61686 0.972336 2.47483 + vertex 1.61181 0.972126 2.47493 + endloop + endfacet + facet normal 0.0320077 -0.324076 0.945489 + outer loop + vertex 1.61181 0.972126 2.47493 + vertex 1.61686 0.972336 2.47483 + vertex 1.61552 0.975824 2.47607 + endloop + endfacet + facet normal 0.0259192 -0.318603 0.947534 + outer loop + vertex 1.61067 0.975588 2.47612 + vertex 1.61181 0.972126 2.47493 + vertex 1.61552 0.975824 2.47607 + endloop + endfacet + facet normal 0.0260081 -0.320583 0.946863 + outer loop + vertex 1.61552 0.975824 2.47607 + vertex 1.61413 0.979365 2.47731 + vertex 1.61067 0.975588 2.47612 + endloop + endfacet + facet normal 0.0338529 -0.317747 0.947571 + outer loop + vertex 1.6192 0.979612 2.47721 + vertex 1.61413 0.979365 2.47731 + vertex 1.61552 0.975824 2.47607 + endloop + endfacet + facet normal 0.0334948 -0.309261 0.950387 + outer loop + vertex 1.6192 0.979612 2.47721 + vertex 1.61814 0.983476 2.4785 + vertex 1.61413 0.979365 2.47731 + endloop + endfacet + facet normal 0.0401677 -0.315131 0.948198 + outer loop + vertex 1.61413 0.979365 2.47731 + vertex 1.61814 0.983476 2.4785 + vertex 1.61281 0.983155 2.47862 + endloop + endfacet + facet normal 0.0405725 -0.322809 0.945594 + outer loop + vertex 1.61814 0.983476 2.4785 + vertex 1.61681 0.987255 2.47985 + vertex 1.61281 0.983155 2.47862 + endloop + endfacet + facet normal 0.0312823 -0.314674 0.948684 + outer loop + vertex 1.61281 0.983155 2.47862 + vertex 1.61681 0.987255 2.47985 + vertex 1.61171 0.987026 2.47994 + endloop + endfacet + facet normal 0.0317167 -0.325912 0.944868 + outer loop + vertex 1.61171 0.987026 2.47994 + vertex 1.61681 0.987255 2.47985 + vertex 1.61542 0.9908 2.48112 + endloop + endfacet + facet normal 0.0187787 -0.314523 0.949064 + outer loop + vertex 1.61058 0.990711 2.48118 + vertex 1.61171 0.987026 2.47994 + vertex 1.61542 0.9908 2.48112 + endloop + endfacet + facet normal 0.0187541 -0.31275 0.94965 + outer loop + vertex 1.61542 0.9908 2.48112 + vertex 1.61425 0.994477 2.48235 + vertex 1.61058 0.990711 2.48118 + endloop + endfacet + facet normal 0.0542904 -0.30214 0.951716 + outer loop + vertex 1.61901 0.994689 2.48215 + vertex 1.61425 0.994477 2.48235 + vertex 1.61542 0.9908 2.48112 + endloop + endfacet + facet normal 0.0538165 -0.286963 0.956429 + outer loop + vertex 1.61901 0.994689 2.48215 + vertex 1.61825 0.998651 2.48338 + vertex 1.61425 0.994477 2.48235 + endloop + endfacet + facet normal 0.0661237 -0.297775 0.952343 + outer loop + vertex 1.61425 0.994477 2.48235 + vertex 1.61825 0.998651 2.48338 + vertex 1.61316 0.998381 2.48365 + endloop + endfacet + facet normal 0.0662715 -0.301865 0.951045 + outer loop + vertex 1.61825 0.998651 2.48338 + vertex 1.61766 1.00321 2.48487 + vertex 1.61316 0.998381 2.48365 + endloop + endfacet + facet normal 0.0673016 -0.302737 0.950695 + outer loop + vertex 1.61316 0.998381 2.48365 + vertex 1.61766 1.00321 2.48487 + vertex 1.6119 1.00216 2.48494 + endloop + endfacet + facet normal 0.0738485 -0.339533 0.937691 + outer loop + vertex 1.6119 1.00216 2.48494 + vertex 1.61766 1.00321 2.48487 + vertex 1.61537 1.00609 2.48609 + endloop + endfacet + facet normal 0.0333645 -0.307673 0.950907 + outer loop + vertex 1.61055 1.0057 2.48613 + vertex 1.6119 1.00216 2.48494 + vertex 1.61537 1.00609 2.48609 + endloop + endfacet + facet normal 0.0324844 -0.296574 0.954457 + outer loop + vertex 1.61537 1.00609 2.48609 + vertex 1.61419 1.00954 2.4872 + vertex 1.61055 1.0057 2.48613 + endloop + endfacet + facet normal 0.0856946 -0.278932 0.95648 + outer loop + vertex 1.6186 1.00987 2.4869 + vertex 1.61419 1.00954 2.4872 + vertex 1.61537 1.00609 2.48609 + endloop + endfacet + facet normal 0.0843056 -0.253174 0.96374 + outer loop + vertex 1.6186 1.00987 2.4869 + vertex 1.61815 1.01382 2.48798 + vertex 1.61419 1.00954 2.4872 + endloop + endfacet + facet normal 0.0999364 -0.266748 0.958571 + outer loop + vertex 1.61419 1.00954 2.4872 + vertex 1.61815 1.01382 2.48798 + vertex 1.61312 1.01352 2.48842 + endloop + endfacet + facet normal 0.100285 -0.276902 0.955651 + outer loop + vertex 1.61815 1.01382 2.48798 + vertex 1.6174 1.01859 2.48944 + vertex 1.61312 1.01352 2.48842 + endloop + endfacet + facet normal 0.104315 -0.280027 0.954308 + outer loop + vertex 1.61312 1.01352 2.48842 + vertex 1.6174 1.01859 2.48944 + vertex 1.61179 1.01739 2.4897 + endloop + endfacet + facet normal 0.115442 -0.336209 0.934685 + outer loop + vertex 1.61179 1.01739 2.4897 + vertex 1.6174 1.01859 2.48944 + vertex 1.61488 1.02135 2.49075 + endloop + endfacet + facet normal 0.293676 0.0465483 0.954771 + outer loop + vertex 1.61652 1.63616 2.546 + vertex 1.61663 1.63112 2.54621 + vertex 1.61869 1.63507 2.54539 + endloop + endfacet + facet normal 0.111248 0.2901 0.950508 + outer loop + vertex 1.61181 1.99661 2.49345 + vertex 1.61583 1.99983 2.492 + vertex 1.61059 2.00065 2.49236 + endloop + endfacet + facet normal 0.152633 0.271859 0.950156 + outer loop + vertex 1.61428 2.00411 2.49102 + vertex 1.61827 2.00317 2.49065 + vertex 1.61855 2.0071 2.48948 + endloop + endfacet + facet normal 0.143248 0.28415 0.948018 + outer loop + vertex 1.61319 2.00822 2.48996 + vertex 1.61428 2.00411 2.49102 + vertex 1.61855 2.0071 2.48948 + endloop + endfacet + facet normal 0.106943 0.258572 0.960054 + outer loop + vertex 1.61583 1.99983 2.492 + vertex 1.61428 2.00411 2.49102 + vertex 1.61059 2.00065 2.49236 + endloop + endfacet + facet normal 0.152821 0.272762 0.949867 + outer loop + vertex 1.61827 2.00317 2.49065 + vertex 1.61428 2.00411 2.49102 + vertex 1.61583 1.99983 2.492 + endloop + endfacet + facet normal 0.136793 0.248732 0.958864 + outer loop + vertex 1.61855 2.0071 2.48948 + vertex 1.61691 2.01188 2.48848 + vertex 1.61319 2.00822 2.48996 + endloop + endfacet + facet normal 0.100636 0.283473 0.953685 + outer loop + vertex 1.61319 2.00822 2.48996 + vertex 1.61691 2.01188 2.48848 + vertex 1.61189 2.01228 2.48889 + endloop + endfacet + facet normal 0.0993477 0.260685 0.960299 + outer loop + vertex 1.61691 2.01188 2.48848 + vertex 1.61526 2.01652 2.48739 + vertex 1.61189 2.01228 2.48889 + endloop + endfacet + facet normal 0.0558232 0.293191 0.954423 + outer loop + vertex 1.61189 2.01228 2.48889 + vertex 1.61526 2.01652 2.48739 + vertex 1.61046 2.01558 2.48795 + endloop + endfacet + facet normal 0.132117 0.286599 0.948897 + outer loop + vertex 1.61929 2.01967 2.48597 + vertex 1.61783 2.02384 2.48491 + vertex 1.61571 2.02054 2.4862 + endloop + endfacet + facet normal 0.12777 0.267148 0.955148 + outer loop + vertex 1.61571 2.02054 2.4862 + vertex 1.61526 2.01652 2.48739 + vertex 1.61929 2.01967 2.48597 + endloop + endfacet + facet normal 0.0470997 0.27753 0.959562 + outer loop + vertex 1.61571 2.02054 2.4862 + vertex 1.61161 2.01944 2.48672 + vertex 1.61526 2.01652 2.48739 + endloop + endfacet + facet normal 0.0568288 0.288795 0.955703 + outer loop + vertex 1.61161 2.01944 2.48672 + vertex 1.61046 2.01558 2.48795 + vertex 1.61526 2.01652 2.48739 + endloop + endfacet + facet normal 0.0819398 0.317197 0.944813 + outer loop + vertex 1.61392 2.02268 2.48564 + vertex 1.61571 2.02054 2.4862 + vertex 1.61783 2.02384 2.48491 + endloop + endfacet + facet normal 0.0783569 0.327355 0.941647 + outer loop + vertex 1.61392 2.02268 2.48564 + vertex 1.61783 2.02384 2.48491 + vertex 1.61298 2.02651 2.48439 + endloop + endfacet + facet normal 0.057489 0.29209 0.954662 + outer loop + vertex 1.61298 2.02651 2.48439 + vertex 1.61783 2.02384 2.48491 + vertex 1.61783 2.02774 2.48372 + endloop + endfacet + facet normal 0.0438293 0.288308 0.956534 + outer loop + vertex 1.61571 2.02054 2.4862 + vertex 1.61392 2.02268 2.48564 + vertex 1.61161 2.01944 2.48672 + endloop + endfacet + facet normal 0.0581556 0.289815 0.955314 + outer loop + vertex 1.61783 2.02774 2.48372 + vertex 1.61597 2.03038 2.48303 + vertex 1.61298 2.02651 2.48439 + endloop + endfacet + facet normal 0.0321697 0.308236 0.950766 + outer loop + vertex 1.61298 2.02651 2.48439 + vertex 1.61597 2.03038 2.48303 + vertex 1.6116 2.03184 2.4827 + endloop + endfacet + facet normal 0.00877044 0.319032 0.947703 + outer loop + vertex 1.61565 2.03763 2.48076 + vertex 1.61262 2.03871 2.48042 + vertex 1.61304 2.03567 2.48144 + endloop + endfacet + facet normal 0.028127 0.295599 0.954898 + outer loop + vertex 1.61304 2.03567 2.48144 + vertex 1.61657 2.0343 2.48176 + vertex 1.61565 2.03763 2.48076 + endloop + endfacet + facet normal 0.0311645 0.302876 0.95252 + outer loop + vertex 1.61304 2.03567 2.48144 + vertex 1.6116 2.03184 2.4827 + vertex 1.61657 2.0343 2.48176 + endloop + endfacet + facet normal 0.0306095 0.30388 0.952218 + outer loop + vertex 1.6116 2.03184 2.4827 + vertex 1.61597 2.03038 2.48303 + vertex 1.61657 2.0343 2.48176 + endloop + endfacet + facet normal 0.0593262 0.319303 0.945794 + outer loop + vertex 1.61565 2.03763 2.48076 + vertex 1.61871 2.03749 2.48061 + vertex 1.61783 2.04118 2.47942 + endloop + endfacet + facet normal 0.0179418 0.342284 0.939425 + outer loop + vertex 1.61565 2.03763 2.48076 + vertex 1.61783 2.04118 2.47942 + vertex 1.61262 2.03871 2.48042 + endloop + endfacet + facet normal 0.0329638 0.314373 0.948727 + outer loop + vertex 1.61262 2.03871 2.48042 + vertex 1.61783 2.04118 2.47942 + vertex 1.61253 2.04252 2.47916 + endloop + endfacet + facet normal 0.0588708 0.30296 0.951183 + outer loop + vertex 1.61871 2.03749 2.48061 + vertex 1.61565 2.03763 2.48076 + vertex 1.61657 2.0343 2.48176 + endloop + endfacet + facet normal 0.0288263 0.299006 0.953816 + outer loop + vertex 1.61783 2.04118 2.47942 + vertex 1.61663 2.04587 2.47799 + vertex 1.61253 2.04252 2.47916 + endloop + endfacet + facet normal 0.0244445 0.303877 0.952398 + outer loop + vertex 1.61253 2.04252 2.47916 + vertex 1.61663 2.04587 2.47799 + vertex 1.61186 2.04639 2.47794 + endloop + endfacet + facet normal 0.0244035 0.303509 0.952516 + outer loop + vertex 1.61663 2.04587 2.47799 + vertex 1.61565 2.04992 2.47672 + vertex 1.61186 2.04639 2.47794 + endloop + endfacet + facet normal 0.0284064 0.299602 0.953641 + outer loop + vertex 1.61186 2.04639 2.47794 + vertex 1.61565 2.04992 2.47672 + vertex 1.61065 2.05015 2.4768 + endloop + endfacet + facet normal 0.0273764 0.31506 0.948677 + outer loop + vertex 1.61425 2.05381 2.47549 + vertex 1.61924 2.05348 2.47546 + vertex 1.61773 2.05745 2.47418 + endloop + endfacet + facet normal 0.0243553 0.317666 0.94789 + outer loop + vertex 1.61269 2.05762 2.47426 + vertex 1.61425 2.05381 2.47549 + vertex 1.61773 2.05745 2.47418 + endloop + endfacet + facet normal 0.0288685 0.310765 0.950048 + outer loop + vertex 1.61565 2.04992 2.47672 + vertex 1.61425 2.05381 2.47549 + vertex 1.61065 2.05015 2.4768 + endloop + endfacet + facet normal 0.0270669 0.310192 0.950289 + outer loop + vertex 1.61924 2.05348 2.47546 + vertex 1.61425 2.05381 2.47549 + vertex 1.61565 2.04992 2.47672 + endloop + endfacet + facet normal 0.0245233 0.323738 0.945829 + outer loop + vertex 1.61773 2.05745 2.47418 + vertex 1.61597 2.06213 2.47263 + vertex 1.61269 2.05762 2.47426 + endloop + endfacet + facet normal 0.0876546 0.335454 0.93797 + outer loop + vertex 1.61278 2.08397 2.46528 + vertex 1.61636 2.08644 2.46407 + vertex 1.61307 2.08766 2.46394 + endloop + endfacet + facet normal 0.143087 0.582078 0.800445 + outer loop + vertex 1.61398 2.09369 2.46092 + vertex 1.61782 2.0929 2.46081 + vertex 1.61722 2.09606 2.45862 + endloop + endfacet + facet normal 0.17108 0.556155 0.81328 + outer loop + vertex 1.61179 2.0969 2.45918 + vertex 1.61398 2.09369 2.46092 + vertex 1.61722 2.09606 2.45862 + endloop + endfacet + facet normal 0.131055 0.472761 0.871391 + outer loop + vertex 1.61635 2.09002 2.46256 + vertex 1.61398 2.09369 2.46092 + vertex 1.61118 2.09098 2.46281 + endloop + endfacet + facet normal 0.121615 0.468341 0.875138 + outer loop + vertex 1.61782 2.0929 2.46081 + vertex 1.61398 2.09369 2.46092 + vertex 1.61635 2.09002 2.46256 + endloop + endfacet + facet normal 0.158728 0.79168 0.589956 + outer loop + vertex 1.6138 2.09926 2.4564 + vertex 1.61946 2.09901 2.45521 + vertex 1.61579 2.10127 2.45316 + endloop + endfacet + facet normal 0.193256 0.775488 0.601058 + outer loop + vertex 1.61103 2.10167 2.45418 + vertex 1.6138 2.09926 2.4564 + vertex 1.61579 2.10127 2.45316 + endloop + endfacet + facet normal 0.17996 0.682825 0.708071 + outer loop + vertex 1.61722 2.09606 2.45862 + vertex 1.6138 2.09926 2.4564 + vertex 1.61179 2.0969 2.45918 + endloop + endfacet + facet normal 0.178962 0.682291 0.708838 + outer loop + vertex 1.61946 2.09901 2.45521 + vertex 1.6138 2.09926 2.4564 + vertex 1.61722 2.09606 2.45862 + endloop + endfacet + facet normal -0.226206 0.5219 0.822467 + outer loop + vertex 1.61715 2.11 2.445 + vertex 1.61228 2.10743 2.44529 + vertex 1.61445 2.10532 2.44723 + endloop + endfacet + facet normal 0.211141 0.318403 0.924142 + outer loop + vertex 1.61715 2.11 2.445 + vertex 1.61445 2.10532 2.44723 + vertex 1.62 2.10811 2.445 + endloop + endfacet + facet normal 0.195792 0.344202 0.918254 + outer loop + vertex 1.62 2.10811 2.445 + vertex 1.61445 2.10532 2.44723 + vertex 1.61844 2.10453 2.44668 + endloop + endfacet + facet normal 0.23539 0.821156 0.519898 + outer loop + vertex 1.61844 2.10453 2.44668 + vertex 1.61445 2.10532 2.44723 + vertex 1.61785 2.10287 2.44956 + endloop + endfacet + facet normal 0.214965 0.813026 0.541091 + outer loop + vertex 1.61785 2.10287 2.44956 + vertex 1.61445 2.10532 2.44723 + vertex 1.61344 2.10304 2.45106 + endloop + endfacet + facet normal 0.178788 0.843033 0.507278 + outer loop + vertex 1.61579 2.10127 2.45316 + vertex 1.61344 2.10304 2.45106 + vertex 1.61103 2.10167 2.45418 + endloop + endfacet + facet normal 0.198958 0.848911 0.489659 + outer loop + vertex 1.61785 2.10287 2.44956 + vertex 1.61344 2.10304 2.45106 + vertex 1.61579 2.10127 2.45316 + endloop + endfacet + facet normal 0.0322685 0.0533617 0.998054 + outer loop + vertex 1.61715 2.11 2.445 + vertex 1.615 2.1113 2.445 + vertex 1.61228 2.10743 2.44529 + endloop + endfacet + facet normal 0.104104 -0.894331 -0.435127 + outer loop + vertex 1.62372 0.925 2.445 + vertex 1.62 0.924567 2.445 + vertex 1.62 0.925 2.44411 + endloop + endfacet + facet normal -0.11298 0.970586 -0.212597 + outer loop + vertex 1.62372 0.925 2.445 + vertex 1.61977 0.924358 2.44417 + vertex 1.62 0.924567 2.445 + endloop + endfacet + facet normal -0.154296 0.987585 -0.029458 + outer loop + vertex 1.61977 0.924358 2.44417 + vertex 1.62372 0.925 2.445 + vertex 1.625 0.9252 2.445 + endloop + endfacet + facet normal 0.0913988 -0.927027 0.363684 + outer loop + vertex 1.61977 0.924358 2.44417 + vertex 1.625 0.9252 2.445 + vertex 1.61818 0.924991 2.44618 + endloop + endfacet + facet normal 0.118652 -0.834986 0.537328 + outer loop + vertex 1.61818 0.924991 2.44618 + vertex 1.625 0.9252 2.445 + vertex 1.62163 0.926426 2.44765 + endloop + endfacet + facet normal 0.175901 -0.869267 0.46199 + outer loop + vertex 1.62048 0.927906 2.45087 + vertex 1.62163 0.926426 2.44765 + vertex 1.6244 0.928164 2.44986 + endloop + endfacet + facet normal 0.199132 -0.861651 0.466803 + outer loop + vertex 1.62048 0.927906 2.45087 + vertex 1.6166 0.926739 2.45037 + vertex 1.62163 0.926426 2.44765 + endloop + endfacet + facet normal 0.18115 -0.881576 0.435899 + outer loop + vertex 1.6166 0.926739 2.45037 + vertex 1.61818 0.924991 2.44618 + vertex 1.62163 0.926426 2.44765 + endloop + endfacet + facet normal 0.188497 -0.842509 0.504627 + outer loop + vertex 1.62048 0.927906 2.45087 + vertex 1.61817 0.928695 2.45305 + vertex 1.6166 0.926739 2.45037 + endloop + endfacet + facet normal 0.188172 -0.833984 0.518712 + outer loop + vertex 1.6244 0.928164 2.44986 + vertex 1.62205 0.929924 2.45354 + vertex 1.62048 0.927906 2.45087 + endloop + endfacet + facet normal 0.199036 -0.834972 0.513036 + outer loop + vertex 1.61817 0.928695 2.45305 + vertex 1.62048 0.927906 2.45087 + vertex 1.62205 0.929924 2.45354 + endloop + endfacet + facet normal 0.174307 -0.787942 0.590563 + outer loop + vertex 1.61817 0.928695 2.45305 + vertex 1.62205 0.929924 2.45354 + vertex 1.6175 0.930697 2.45592 + endloop + endfacet + facet normal 0.187372 -0.770085 0.609804 + outer loop + vertex 1.6175 0.930697 2.45592 + vertex 1.62205 0.929924 2.45354 + vertex 1.62137 0.932055 2.45645 + endloop + endfacet + facet normal 0.150855 -0.700059 0.697968 + outer loop + vertex 1.62137 0.932055 2.45645 + vertex 1.61879 0.933592 2.45855 + vertex 1.6175 0.930697 2.45592 + endloop + endfacet + facet normal 0.130991 -0.716273 0.685416 + outer loop + vertex 1.62342 0.934228 2.45833 + vertex 1.61879 0.933592 2.45855 + vertex 1.62137 0.932055 2.45645 + endloop + endfacet + facet normal 0.122251 -0.621959 0.773448 + outer loop + vertex 1.61879 0.933592 2.45855 + vertex 1.62342 0.934228 2.45833 + vertex 1.62104 0.936611 2.46062 + endloop + endfacet + facet normal 0.136106 -0.627566 0.766574 + outer loop + vertex 1.61621 0.9359 2.46089 + vertex 1.61879 0.933592 2.45855 + vertex 1.62104 0.936611 2.46062 + endloop + endfacet + facet normal 0.124142 -0.514767 0.848295 + outer loop + vertex 1.62104 0.936611 2.46062 + vertex 1.61886 0.939405 2.46263 + vertex 1.61621 0.9359 2.46089 + endloop + endfacet + facet normal 0.086772 -0.537223 0.838965 + outer loop + vertex 1.62386 0.939914 2.46244 + vertex 1.61886 0.939405 2.46263 + vertex 1.62104 0.936611 2.46062 + endloop + endfacet + facet normal 0.0792929 -0.443346 0.892836 + outer loop + vertex 1.62386 0.939914 2.46244 + vertex 1.62185 0.942471 2.46389 + vertex 1.61886 0.939405 2.46263 + endloop + endfacet + facet normal 0.0619404 -0.379705 0.923032 + outer loop + vertex 1.62185 0.942471 2.46389 + vertex 1.62214 0.946046 2.46534 + vertex 1.61767 0.942816 2.46431 + endloop + endfacet + facet normal 0.0245156 -0.334034 0.942242 + outer loop + vertex 1.61767 0.942816 2.46431 + vertex 1.62214 0.946046 2.46534 + vertex 1.61743 0.946547 2.46564 + endloop + endfacet + facet normal 0.0252056 -0.328674 0.944107 + outer loop + vertex 1.61743 0.946547 2.46564 + vertex 1.62214 0.946046 2.46534 + vertex 1.62059 0.949621 2.46663 + endloop + endfacet + facet normal 0.00961113 -0.314306 0.949273 + outer loop + vertex 1.61694 0.949417 2.4666 + vertex 1.61743 0.946547 2.46564 + vertex 1.62059 0.949621 2.46663 + endloop + endfacet + facet normal 0.0113421 -0.343897 0.938939 + outer loop + vertex 1.62059 0.949621 2.46663 + vertex 1.61826 0.952998 2.46789 + vertex 1.61694 0.949417 2.4666 + endloop + endfacet + facet normal 0.0208392 -0.338065 0.940892 + outer loop + vertex 1.62435 0.953266 2.46785 + vertex 1.61826 0.952998 2.46789 + vertex 1.62059 0.949621 2.46663 + endloop + endfacet + facet normal 0.0209979 -0.341881 0.939509 + outer loop + vertex 1.62435 0.953266 2.46785 + vertex 1.62214 0.957424 2.46942 + vertex 1.61826 0.952998 2.46789 + endloop + endfacet + facet normal 0.0269239 -0.346456 0.93768 + outer loop + vertex 1.61826 0.952998 2.46789 + vertex 1.62214 0.957424 2.46942 + vertex 1.61688 0.957326 2.46953 + endloop + endfacet + facet normal 0.0269304 -0.34709 0.937445 + outer loop + vertex 1.61688 0.957326 2.46953 + vertex 1.62214 0.957424 2.46942 + vertex 1.62042 0.961122 2.47083 + endloop + endfacet + facet normal 0.0218309 -0.342907 0.939116 + outer loop + vertex 1.61552 0.961081 2.47093 + vertex 1.61688 0.957326 2.46953 + vertex 1.62042 0.961122 2.47083 + endloop + endfacet + facet normal 0.0218176 -0.331216 0.943303 + outer loop + vertex 1.62042 0.961122 2.47083 + vertex 1.61913 0.964799 2.47216 + vertex 1.61552 0.961081 2.47093 + endloop + endfacet + facet normal 0.0415603 -0.324873 0.944844 + outer loop + vertex 1.62392 0.964931 2.47199 + vertex 1.61913 0.964799 2.47216 + vertex 1.62042 0.961122 2.47083 + endloop + endfacet + facet normal 0.0412395 -0.305037 0.951447 + outer loop + vertex 1.62392 0.964931 2.47199 + vertex 1.62317 0.968838 2.47328 + vertex 1.61913 0.964799 2.47216 + endloop + endfacet + facet normal 0.054758 -0.317251 0.946759 + outer loop + vertex 1.61913 0.964799 2.47216 + vertex 1.62317 0.968838 2.47328 + vertex 1.61807 0.968629 2.4735 + endloop + endfacet + facet normal 0.0546927 -0.314775 0.947589 + outer loop + vertex 1.62317 0.968838 2.47328 + vertex 1.62266 0.97334 2.4748 + vertex 1.61807 0.968629 2.4735 + endloop + endfacet + facet normal 0.0596767 -0.319141 0.945826 + outer loop + vertex 1.61807 0.968629 2.4735 + vertex 1.62266 0.97334 2.4748 + vertex 1.61686 0.972336 2.47483 + endloop + endfacet + facet normal 0.0651184 -0.35087 0.934157 + outer loop + vertex 1.61686 0.972336 2.47483 + vertex 1.62266 0.97334 2.4748 + vertex 1.62039 0.976206 2.47604 + endloop + endfacet + facet normal 0.0318666 -0.324126 0.945477 + outer loop + vertex 1.61552 0.975824 2.47607 + vertex 1.61686 0.972336 2.47483 + vertex 1.62039 0.976206 2.47604 + endloop + endfacet + facet normal 0.0312048 -0.315433 0.948435 + outer loop + vertex 1.62039 0.976206 2.47604 + vertex 1.6192 0.979612 2.47721 + vertex 1.61552 0.975824 2.47607 + endloop + endfacet + facet normal 0.0746058 -0.30108 0.950676 + outer loop + vertex 1.62369 0.979892 2.47694 + vertex 1.6192 0.979612 2.47721 + vertex 1.62039 0.976206 2.47604 + endloop + endfacet + facet normal 0.0735256 -0.276791 0.958113 + outer loop + vertex 1.62369 0.979892 2.47694 + vertex 1.62326 0.983774 2.4781 + vertex 1.6192 0.979612 2.47721 + endloop + endfacet + facet normal 0.0921201 -0.293507 0.951508 + outer loop + vertex 1.6192 0.979612 2.47721 + vertex 1.62326 0.983774 2.4781 + vertex 1.61814 0.983476 2.4785 + endloop + endfacet + facet normal 0.0923354 -0.299971 0.949469 + outer loop + vertex 1.62326 0.983774 2.4781 + vertex 1.62259 0.988442 2.47964 + vertex 1.61814 0.983476 2.4785 + endloop + endfacet + facet normal 0.0969573 -0.303737 0.947809 + outer loop + vertex 1.61814 0.983476 2.4785 + vertex 1.62259 0.988442 2.47964 + vertex 1.61681 0.987255 2.47985 + endloop + endfacet + facet normal 0.10554 -0.348503 0.931347 + outer loop + vertex 1.61681 0.987255 2.47985 + vertex 1.62259 0.988442 2.47964 + vertex 1.62016 0.991297 2.48098 + endloop + endfacet + facet normal 0.0604143 -0.315431 0.947023 + outer loop + vertex 1.61542 0.9908 2.48112 + vertex 1.61681 0.987255 2.47985 + vertex 1.62016 0.991297 2.48098 + endloop + endfacet + facet normal 0.0595717 -0.306561 0.949985 + outer loop + vertex 1.62016 0.991297 2.48098 + vertex 1.61901 0.994689 2.48215 + vertex 1.61542 0.9908 2.48112 + endloop + endfacet + facet normal 0.125572 -0.284297 0.950477 + outer loop + vertex 1.62329 0.995181 2.48173 + vertex 1.61901 0.994689 2.48215 + vertex 1.62016 0.991297 2.48098 + endloop + endfacet + facet normal 0.123138 -0.25604 0.958791 + outer loop + vertex 1.62329 0.995181 2.48173 + vertex 1.62299 0.998953 2.48278 + vertex 1.61901 0.994689 2.48215 + endloop + endfacet + facet normal 0.138685 -0.269699 0.952905 + outer loop + vertex 1.61901 0.994689 2.48215 + vertex 1.62299 0.998953 2.48278 + vertex 1.61825 0.998651 2.48338 + endloop + endfacet + facet normal 0.292153 0.216207 0.931612 + outer loop + vertex 1.62415 1.97404 2.4961 + vertex 1.62427 1.97819 2.4951 + vertex 1.62126 1.97607 2.49654 + endloop + endfacet + facet normal 0.29246 0.216688 0.931404 + outer loop + vertex 1.62126 1.97607 2.49654 + vertex 1.62118 1.97147 2.49763 + vertex 1.62415 1.97404 2.4961 + endloop + endfacet + facet normal 0.291603 0.216982 0.931604 + outer loop + vertex 1.62126 1.97607 2.49654 + vertex 1.62427 1.97819 2.4951 + vertex 1.61964 1.98007 2.49611 + endloop + endfacet + facet normal 0.106106 0.320023 0.941449 + outer loop + vertex 1.61783 2.02774 2.48372 + vertex 1.62094 2.03081 2.48232 + vertex 1.61597 2.03038 2.48303 + endloop + endfacet + facet normal 0.175989 0.290436 0.940572 + outer loop + vertex 1.62373 2.0339 2.48094 + vertex 1.62324 2.03811 2.47973 + vertex 1.6206 2.03516 2.48114 + endloop + endfacet + facet normal 0.168958 0.271773 0.947414 + outer loop + vertex 1.6206 2.03516 2.48114 + vertex 1.62094 2.03081 2.48232 + vertex 1.62373 2.0339 2.48094 + endloop + endfacet + facet normal 0.0908557 0.268713 0.958926 + outer loop + vertex 1.6206 2.03516 2.48114 + vertex 1.61657 2.0343 2.48176 + vertex 1.62094 2.03081 2.48232 + endloop + endfacet + facet normal 0.109858 0.291094 0.950366 + outer loop + vertex 1.61657 2.0343 2.48176 + vertex 1.61597 2.03038 2.48303 + vertex 1.62094 2.03081 2.48232 + endloop + endfacet + facet normal 0.137725 0.322727 0.936418 + outer loop + vertex 1.61871 2.03749 2.48061 + vertex 1.6206 2.03516 2.48114 + vertex 1.62324 2.03811 2.47973 + endloop + endfacet + facet normal 0.135615 0.333319 0.93301 + outer loop + vertex 1.61871 2.03749 2.48061 + vertex 1.62324 2.03811 2.47973 + vertex 1.61783 2.04118 2.47942 + endloop + endfacet + facet normal 0.0994023 0.271922 0.957172 + outer loop + vertex 1.61783 2.04118 2.47942 + vertex 1.62324 2.03811 2.47973 + vertex 1.62276 2.0425 2.47853 + endloop + endfacet + facet normal 0.0865933 0.285543 0.954446 + outer loop + vertex 1.6206 2.03516 2.48114 + vertex 1.61871 2.03749 2.48061 + vertex 1.61657 2.0343 2.48176 + endloop + endfacet + facet normal 0.0972373 0.278799 0.955414 + outer loop + vertex 1.62276 2.0425 2.47853 + vertex 1.62082 2.04512 2.47797 + vertex 1.61783 2.04118 2.47942 + endloop + endfacet + facet normal 0.0591937 0.305688 0.95029 + outer loop + vertex 1.61783 2.04118 2.47942 + vertex 1.62082 2.04512 2.47797 + vertex 1.61663 2.04587 2.47799 + endloop + endfacet + facet normal 0.0579159 0.298516 0.952646 + outer loop + vertex 1.62082 2.04512 2.47797 + vertex 1.62101 2.04922 2.47667 + vertex 1.61663 2.04587 2.47799 + endloop + endfacet + facet normal 0.0492743 0.308729 0.949873 + outer loop + vertex 1.61663 2.04587 2.47799 + vertex 1.62101 2.04922 2.47667 + vertex 1.61565 2.04992 2.47672 + endloop + endfacet + facet normal 0.0749168 0.310458 0.94763 + outer loop + vertex 1.61924 2.05348 2.47546 + vertex 1.62336 2.05272 2.47538 + vertex 1.62318 2.0566 2.47412 + endloop + endfacet + facet normal 0.0610385 0.32616 0.943342 + outer loop + vertex 1.61773 2.05745 2.47418 + vertex 1.61924 2.05348 2.47546 + vertex 1.62318 2.0566 2.47412 + endloop + endfacet + facet normal 0.0470885 0.291791 0.955322 + outer loop + vertex 1.62101 2.04922 2.47667 + vertex 1.61924 2.05348 2.47546 + vertex 1.61565 2.04992 2.47672 + endloop + endfacet + facet normal 0.0732898 0.301315 0.950704 + outer loop + vertex 1.62336 2.05272 2.47538 + vertex 1.61924 2.05348 2.47546 + vertex 1.62101 2.04922 2.47667 + endloop + endfacet + facet normal 0.0572409 0.301279 0.951816 + outer loop + vertex 1.62318 2.0566 2.47412 + vertex 1.62088 2.06041 2.47306 + vertex 1.61773 2.05745 2.47418 + endloop + endfacet + facet normal 0.0315325 0.326041 0.94483 + outer loop + vertex 1.61773 2.05745 2.47418 + vertex 1.62088 2.06041 2.47306 + vertex 1.61597 2.06213 2.47263 + endloop + endfacet + facet normal 0.008054 0.338042 0.941097 + outer loop + vertex 1.62051 2.06769 2.47061 + vertex 1.6171 2.06905 2.47015 + vertex 1.618 2.06586 2.47128 + endloop + endfacet + facet normal 0.0216649 0.321378 0.946703 + outer loop + vertex 1.618 2.06586 2.47128 + vertex 1.62149 2.06434 2.47172 + vertex 1.62051 2.06769 2.47061 + endloop + endfacet + facet normal 0.0241423 0.32654 0.944875 + outer loop + vertex 1.618 2.06586 2.47128 + vertex 1.61597 2.06213 2.47263 + vertex 1.62149 2.06434 2.47172 + endloop + endfacet + facet normal 0.0282696 0.317478 0.947844 + outer loop + vertex 1.61597 2.06213 2.47263 + vertex 1.62088 2.06041 2.47306 + vertex 1.62149 2.06434 2.47172 + endloop + endfacet + facet normal 0.0482366 0.346452 0.936827 + outer loop + vertex 1.62051 2.06769 2.47061 + vertex 1.62361 2.06744 2.47054 + vertex 1.62261 2.07122 2.46919 + endloop + endfacet + facet normal 0.0188411 0.361982 0.931995 + outer loop + vertex 1.62051 2.06769 2.47061 + vertex 1.62261 2.07122 2.46919 + vertex 1.6171 2.06905 2.47015 + endloop + endfacet + facet normal 0.0314838 0.334199 0.941977 + outer loop + vertex 1.6171 2.06905 2.47015 + vertex 1.62261 2.07122 2.46919 + vertex 1.61782 2.07282 2.46879 + endloop + endfacet + facet normal 0.0468463 0.327683 0.943626 + outer loop + vertex 1.62361 2.06744 2.47054 + vertex 1.62051 2.06769 2.47061 + vertex 1.62149 2.06434 2.47172 + endloop + endfacet + facet normal 0.0290344 0.327498 0.944406 + outer loop + vertex 1.62261 2.07122 2.46919 + vertex 1.62087 2.07584 2.46764 + vertex 1.61782 2.07282 2.46879 + endloop + endfacet + facet normal 0.0303953 0.326269 0.944788 + outer loop + vertex 1.61782 2.07282 2.46879 + vertex 1.62087 2.07584 2.46764 + vertex 1.61594 2.07608 2.46772 + endloop + endfacet + facet normal 0.0318572 0.336043 0.941308 + outer loop + vertex 1.61934 2.07963 2.46637 + vertex 1.62427 2.07946 2.46626 + vertex 1.62292 2.08328 2.46494 + endloop + endfacet + facet normal 0.0305447 0.329707 0.943589 + outer loop + vertex 1.62087 2.07584 2.46764 + vertex 1.61934 2.07963 2.46637 + vertex 1.61594 2.07608 2.46772 + endloop + endfacet + facet normal 0.0316898 0.330109 0.943411 + outer loop + vertex 1.62427 2.07946 2.46626 + vertex 1.61934 2.07963 2.46637 + vertex 1.62087 2.07584 2.46764 + endloop + endfacet + facet normal 0.0762934 0.53547 0.841101 + outer loop + vertex 1.6228 2.09112 2.46135 + vertex 1.62102 2.09347 2.46002 + vertex 1.62003 2.09102 2.46167 + endloop + endfacet + facet normal 0.0856798 0.443461 0.892189 + outer loop + vertex 1.62003 2.09102 2.46167 + vertex 1.62127 2.08771 2.46319 + vertex 1.6228 2.09112 2.46135 + endloop + endfacet + facet normal 0.0940207 0.44568 0.890241 + outer loop + vertex 1.62003 2.09102 2.46167 + vertex 1.61635 2.09002 2.46256 + vertex 1.62127 2.08771 2.46319 + endloop + endfacet + facet normal 0.116567 0.52191 0.844998 + outer loop + vertex 1.61782 2.0929 2.46081 + vertex 1.62003 2.09102 2.46167 + vertex 1.62102 2.09347 2.46002 + endloop + endfacet + facet normal 0.0973645 0.579381 0.80922 + outer loop + vertex 1.61782 2.0929 2.46081 + vertex 1.62102 2.09347 2.46002 + vertex 1.61722 2.09606 2.45862 + endloop + endfacet + facet normal 0.131152 0.61287 0.779224 + outer loop + vertex 1.61722 2.09606 2.45862 + vertex 1.62102 2.09347 2.46002 + vertex 1.6227 2.0962 2.45759 + endloop + endfacet + facet normal 0.0777779 0.487552 0.869623 + outer loop + vertex 1.62003 2.09102 2.46167 + vertex 1.61782 2.0929 2.46081 + vertex 1.61635 2.09002 2.46256 + endloop + endfacet + facet normal 0.168404 0.866077 0.470693 + outer loop + vertex 1.62315 2.10017 2.4527 + vertex 1.62161 2.10183 2.45018 + vertex 1.61956 2.10111 2.45224 + endloop + endfacet + facet normal 0.174396 0.801179 0.57245 + outer loop + vertex 1.61956 2.10111 2.45224 + vertex 1.61579 2.10127 2.45316 + vertex 1.61946 2.09901 2.45521 + endloop + endfacet + facet normal 0.139484 0.806286 0.574846 + outer loop + vertex 1.61956 2.10111 2.45224 + vertex 1.61946 2.09901 2.45521 + vertex 1.62315 2.10017 2.4527 + endloop + endfacet + facet normal 0.139688 0.806099 0.575058 + outer loop + vertex 1.62315 2.10017 2.4527 + vertex 1.61946 2.09901 2.45521 + vertex 1.62428 2.098 2.45546 + endloop + endfacet + facet normal 0.111965 0.713401 0.691753 + outer loop + vertex 1.6227 2.0962 2.45759 + vertex 1.61946 2.09901 2.45521 + vertex 1.61722 2.09606 2.45862 + endloop + endfacet + facet normal 0.114747 0.714908 0.689739 + outer loop + vertex 1.62428 2.098 2.45546 + vertex 1.61946 2.09901 2.45521 + vertex 1.6227 2.0962 2.45759 + endloop + endfacet + facet normal 0.0850765 0.425413 0.900992 + outer loop + vertex 1.625 2.10711 2.445 + vertex 1.62 2.10811 2.445 + vertex 1.62202 2.10375 2.44687 + endloop + endfacet + facet normal 0.0396481 0.408926 0.911706 + outer loop + vertex 1.62202 2.10375 2.44687 + vertex 1.62 2.10811 2.445 + vertex 1.61844 2.10453 2.44668 + endloop + endfacet + facet normal 0.162776 0.869522 0.466299 + outer loop + vertex 1.62161 2.10183 2.45018 + vertex 1.61785 2.10287 2.44956 + vertex 1.61956 2.10111 2.45224 + endloop + endfacet + facet normal 0.149539 0.847352 0.509542 + outer loop + vertex 1.62161 2.10183 2.45018 + vertex 1.62202 2.10375 2.44687 + vertex 1.61785 2.10287 2.44956 + endloop + endfacet + facet normal 0.154551 0.842683 0.515751 + outer loop + vertex 1.62202 2.10375 2.44687 + vertex 1.61844 2.10453 2.44668 + vertex 1.61785 2.10287 2.44956 + endloop + endfacet + facet normal 0.152892 0.868336 0.471823 + outer loop + vertex 1.61956 2.10111 2.45224 + vertex 1.61785 2.10287 2.44956 + vertex 1.61579 2.10127 2.45316 + endloop + endfacet + facet normal 0.383099 0.817751 0.429556 + outer loop + vertex 1.62111 2.11 2.44 + vertex 1.62 2.11052 2.44 + vertex 1.62 2.11 2.44099 + endloop + endfacet + facet normal 0.0905971 -0.699028 0.709332 + outer loop + vertex 1.63 0.925848 2.445 + vertex 1.6265 0.926632 2.44622 + vertex 1.625 0.9252 2.445 + endloop + endfacet + facet normal 0.214246 -0.753664 0.621361 + outer loop + vertex 1.6265 0.926632 2.44622 + vertex 1.62163 0.926426 2.44765 + vertex 1.625 0.9252 2.445 + endloop + endfacet + facet normal 0.173141 -0.868359 0.46473 + outer loop + vertex 1.6265 0.926632 2.44622 + vertex 1.6244 0.928164 2.44986 + vertex 1.62163 0.926426 2.44765 + endloop + endfacet + facet normal 0.147957 -0.878406 0.454435 + outer loop + vertex 1.62922 0.928482 2.44891 + vertex 1.6244 0.928164 2.44986 + vertex 1.6265 0.926632 2.44622 + endloop + endfacet + facet normal 0.151849 -0.864754 0.478689 + outer loop + vertex 1.6244 0.928164 2.44986 + vertex 1.62922 0.928482 2.44891 + vertex 1.62736 0.930195 2.4526 + endloop + endfacet + facet normal 0.132534 -0.858682 0.495075 + outer loop + vertex 1.62205 0.929924 2.45354 + vertex 1.6244 0.928164 2.44986 + vertex 1.62736 0.930195 2.4526 + endloop + endfacet + facet normal 0.145037 -0.80036 0.581712 + outer loop + vertex 1.62736 0.930195 2.4526 + vertex 1.62551 0.932137 2.45573 + vertex 1.62205 0.929924 2.45354 + endloop + endfacet + facet normal 0.120679 -0.786302 0.605942 + outer loop + vertex 1.62551 0.932137 2.45573 + vertex 1.62137 0.932055 2.45645 + vertex 1.62205 0.929924 2.45354 + endloop + endfacet + facet normal 0.132902 -0.717053 0.684231 + outer loop + vertex 1.62551 0.932137 2.45573 + vertex 1.62342 0.934228 2.45833 + vertex 1.62137 0.932055 2.45645 + endloop + endfacet + facet normal 0.0922984 -0.738 0.668459 + outer loop + vertex 1.62834 0.934565 2.45802 + vertex 1.62342 0.934228 2.45833 + vertex 1.62551 0.932137 2.45573 + endloop + endfacet + facet normal 0.0915811 -0.647021 0.756952 + outer loop + vertex 1.62342 0.934228 2.45833 + vertex 1.62834 0.934565 2.45802 + vertex 1.62599 0.936997 2.46038 + endloop + endfacet + facet normal 0.0865597 -0.644431 0.759748 + outer loop + vertex 1.62104 0.936611 2.46062 + vertex 1.62342 0.934228 2.45833 + vertex 1.62599 0.936997 2.46038 + endloop + endfacet + facet normal 0.0819015 -0.534339 0.841293 + outer loop + vertex 1.62599 0.936997 2.46038 + vertex 1.62386 0.939914 2.46244 + vertex 1.62104 0.936611 2.46062 + endloop + endfacet + facet normal 0.0762071 -0.537465 0.839836 + outer loop + vertex 1.62901 0.940317 2.46223 + vertex 1.62386 0.939914 2.46244 + vertex 1.62599 0.936997 2.46038 + endloop + endfacet + facet normal 0.0705491 -0.435071 0.897628 + outer loop + vertex 1.62901 0.940317 2.46223 + vertex 1.6272 0.94441 2.46436 + vertex 1.62386 0.939914 2.46244 + endloop + endfacet + facet normal 0.0818412 -0.441674 0.893435 + outer loop + vertex 1.62386 0.939914 2.46244 + vertex 1.6272 0.94441 2.46436 + vertex 1.62185 0.942471 2.46389 + endloop + endfacet + facet normal 0.0142084 -0.349637 0.936778 + outer loop + vertex 1.62615 0.947505 2.46583 + vertex 1.62427 0.949306 2.46653 + vertex 1.62214 0.946046 2.46534 + endloop + endfacet + facet normal 0.0418961 -0.416256 0.908282 + outer loop + vertex 1.62615 0.947505 2.46583 + vertex 1.62214 0.946046 2.46534 + vertex 1.6272 0.94441 2.46436 + endloop + endfacet + facet normal 0.0567205 -0.379457 0.923469 + outer loop + vertex 1.6272 0.94441 2.46436 + vertex 1.62214 0.946046 2.46534 + vertex 1.62185 0.942471 2.46389 + endloop + endfacet + facet normal 0.0454448 -0.32066 0.946104 + outer loop + vertex 1.62615 0.947505 2.46583 + vertex 1.62817 0.950806 2.46685 + vertex 1.62427 0.949306 2.46653 + endloop + endfacet + facet normal -0.00317654 -0.339648 0.940547 + outer loop + vertex 1.62214 0.946046 2.46534 + vertex 1.62427 0.949306 2.46653 + vertex 1.62059 0.949621 2.46663 + endloop + endfacet + facet normal -0.0011053 -0.317876 0.948132 + outer loop + vertex 1.62427 0.949306 2.46653 + vertex 1.62435 0.953266 2.46785 + vertex 1.62059 0.949621 2.46663 + endloop + endfacet + facet normal 0.0445229 -0.318431 0.9469 + outer loop + vertex 1.62427 0.949306 2.46653 + vertex 1.62817 0.950806 2.46685 + vertex 1.62435 0.953266 2.46785 + endloop + endfacet + facet normal 0.0652946 -0.289472 0.954957 + outer loop + vertex 1.62817 0.950806 2.46685 + vertex 1.62921 0.954901 2.46802 + vertex 1.62435 0.953266 2.46785 + endloop + endfacet + facet normal 0.076468 -0.32155 0.9438 + outer loop + vertex 1.62921 0.954901 2.46802 + vertex 1.62792 0.958668 2.46941 + vertex 1.62435 0.953266 2.46785 + endloop + endfacet + facet normal 0.0703048 -0.317969 0.945491 + outer loop + vertex 1.62435 0.953266 2.46785 + vertex 1.62792 0.958668 2.46941 + vertex 1.62214 0.957424 2.46942 + endloop + endfacet + facet normal 0.08059 -0.365807 0.927195 + outer loop + vertex 1.62214 0.957424 2.46942 + vertex 1.62792 0.958668 2.46941 + vertex 1.62519 0.961514 2.47076 + endloop + endfacet + facet normal 0.0417601 -0.34083 0.939197 + outer loop + vertex 1.62042 0.961122 2.47083 + vertex 1.62214 0.957424 2.46942 + vertex 1.62519 0.961514 2.47076 + endloop + endfacet + facet normal 0.0404673 -0.323976 0.945199 + outer loop + vertex 1.62519 0.961514 2.47076 + vertex 1.62392 0.964931 2.47199 + vertex 1.62042 0.961122 2.47083 + endloop + endfacet + facet normal 0.0955437 -0.304338 0.94776 + outer loop + vertex 1.6282 0.965265 2.47167 + vertex 1.62392 0.964931 2.47199 + vertex 1.62519 0.961514 2.47076 + endloop + endfacet + facet normal 0.0936125 -0.269063 0.958562 + outer loop + vertex 1.6282 0.965265 2.47167 + vertex 1.62792 0.969042 2.47275 + vertex 1.62392 0.964931 2.47199 + endloop + endfacet + facet normal 0.116821 -0.290063 0.949851 + outer loop + vertex 1.62392 0.964931 2.47199 + vertex 1.62792 0.969042 2.47275 + vertex 1.62317 0.968838 2.47328 + endloop + endfacet + facet normal 0.116697 -0.277518 0.953607 + outer loop + vertex 1.62792 0.969042 2.47275 + vertex 1.62782 0.973371 2.47403 + vertex 1.62317 0.968838 2.47328 + endloop + endfacet + facet normal 0.143261 -0.302895 0.942195 + outer loop + vertex 1.62317 0.968838 2.47328 + vertex 1.62782 0.973371 2.47403 + vertex 1.62266 0.97334 2.4748 + endloop + endfacet + facet normal 0.279107 -0.14041 0.949939 + outer loop + vertex 1.62885 1.21454 2.52503 + vertex 1.62951 1.21907 2.52551 + vertex 1.62566 1.21583 2.52616 + endloop + endfacet + facet normal 0.2793 -0.140657 0.949846 + outer loop + vertex 1.62951 1.21907 2.52551 + vertex 1.62693 1.21973 2.52636 + vertex 1.62566 1.21583 2.52616 + endloop + endfacet + facet normal 0.281657 0.195342 0.93942 + outer loop + vertex 1.62832 1.93326 2.50393 + vertex 1.62665 1.93647 2.50376 + vertex 1.62443 1.93314 2.50512 + endloop + endfacet + facet normal 0.285869 0.216837 0.933413 + outer loop + vertex 1.62415 1.97404 2.4961 + vertex 1.62854 1.97348 2.49489 + vertex 1.62427 1.97819 2.4951 + endloop + endfacet + facet normal 0.173973 0.312155 0.933966 + outer loop + vertex 1.62336 2.05272 2.47538 + vertex 1.62531 2.05009 2.4759 + vertex 1.6279 2.05292 2.47447 + endloop + endfacet + facet normal 0.174122 0.310756 0.934405 + outer loop + vertex 1.62336 2.05272 2.47538 + vertex 1.6279 2.05292 2.47447 + vertex 1.62318 2.0566 2.47412 + endloop + endfacet + facet normal 0.138752 0.267116 0.953623 + outer loop + vertex 1.62318 2.0566 2.47412 + vertex 1.6279 2.05292 2.47447 + vertex 1.62704 2.05687 2.47348 + endloop + endfacet + facet normal 0.116622 0.27374 0.954707 + outer loop + vertex 1.62531 2.05009 2.4759 + vertex 1.62336 2.05272 2.47538 + vertex 1.62101 2.04922 2.47667 + endloop + endfacet + facet normal 0.135497 0.294929 0.945863 + outer loop + vertex 1.62704 2.05687 2.47348 + vertex 1.62605 2.06076 2.47242 + vertex 1.62318 2.0566 2.47412 + endloop + endfacet + facet normal 0.0949868 0.321347 0.942186 + outer loop + vertex 1.62318 2.0566 2.47412 + vertex 1.62605 2.06076 2.47242 + vertex 1.62088 2.06041 2.47306 + endloop + endfacet + facet normal 0.166477 0.317544 0.933516 + outer loop + vertex 1.6287 2.06384 2.47103 + vertex 1.62812 2.06799 2.46972 + vertex 1.62556 2.06508 2.47116 + endloop + endfacet + facet normal 0.156279 0.290636 0.943985 + outer loop + vertex 1.62556 2.06508 2.47116 + vertex 1.62605 2.06076 2.47242 + vertex 1.6287 2.06384 2.47103 + endloop + endfacet + facet normal 0.0783655 0.285164 0.95527 + outer loop + vertex 1.62556 2.06508 2.47116 + vertex 1.62149 2.06434 2.47172 + vertex 1.62605 2.06076 2.47242 + endloop + endfacet + facet normal 0.0965629 0.306659 0.946909 + outer loop + vertex 1.62149 2.06434 2.47172 + vertex 1.62088 2.06041 2.47306 + vertex 1.62605 2.06076 2.47242 + endloop + endfacet + facet normal 0.1258 0.35056 0.928053 + outer loop + vertex 1.62361 2.06744 2.47054 + vertex 1.62556 2.06508 2.47116 + vertex 1.62812 2.06799 2.46972 + endloop + endfacet + facet normal 0.123658 0.361869 0.923991 + outer loop + vertex 1.62361 2.06744 2.47054 + vertex 1.62812 2.06799 2.46972 + vertex 1.62261 2.07122 2.46919 + endloop + endfacet + facet normal 0.0863619 0.30225 0.949309 + outer loop + vertex 1.62261 2.07122 2.46919 + vertex 1.62812 2.06799 2.46972 + vertex 1.62765 2.07232 2.46839 + endloop + endfacet + facet normal 0.0724998 0.311536 0.947465 + outer loop + vertex 1.62556 2.06508 2.47116 + vertex 1.62361 2.06744 2.47054 + vertex 1.62149 2.06434 2.47172 + endloop + endfacet + facet normal 0.0836695 0.31234 0.946279 + outer loop + vertex 1.62765 2.07232 2.46839 + vertex 1.62584 2.07559 2.46746 + vertex 1.62261 2.07122 2.46919 + endloop + endfacet + facet normal 0.0507675 0.33453 0.941017 + outer loop + vertex 1.62261 2.07122 2.46919 + vertex 1.62584 2.07559 2.46746 + vertex 1.62087 2.07584 2.46764 + endloop + endfacet + facet normal 0.0844495 0.313659 0.945773 + outer loop + vertex 1.62427 2.07946 2.46626 + vertex 1.62915 2.07895 2.466 + vertex 1.62784 2.08277 2.46485 + endloop + endfacet + facet normal 0.0543223 0.342743 0.937857 + outer loop + vertex 1.62292 2.08328 2.46494 + vertex 1.62427 2.07946 2.46626 + vertex 1.62784 2.08277 2.46485 + endloop + endfacet + facet normal 0.0500228 0.314585 0.94791 + outer loop + vertex 1.62584 2.07559 2.46746 + vertex 1.62427 2.07946 2.46626 + vertex 1.62087 2.07584 2.46764 + endloop + endfacet + facet normal 0.0855657 0.326948 0.941161 + outer loop + vertex 1.62915 2.07895 2.466 + vertex 1.62427 2.07946 2.46626 + vertex 1.62584 2.07559 2.46746 + endloop + endfacet + facet normal 0.0566772 0.367351 0.928354 + outer loop + vertex 1.62784 2.08277 2.46485 + vertex 1.6267 2.08659 2.46341 + vertex 1.62292 2.08328 2.46494 + endloop + endfacet + facet normal 0.0425515 0.381218 0.923505 + outer loop + vertex 1.62292 2.08328 2.46494 + vertex 1.6267 2.08659 2.46341 + vertex 1.62127 2.08771 2.46319 + endloop + endfacet + facet normal 0.0918481 0.543434 0.834412 + outer loop + vertex 1.62478 2.09332 2.4597 + vertex 1.62102 2.09347 2.46002 + vertex 1.6228 2.09112 2.46135 + endloop + endfacet + facet normal 0.0845958 0.548205 0.832055 + outer loop + vertex 1.6228 2.09112 2.46135 + vertex 1.62591 2.09019 2.46165 + vertex 1.62478 2.09332 2.4597 + endloop + endfacet + facet normal 0.0518287 0.456488 0.888219 + outer loop + vertex 1.6228 2.09112 2.46135 + vertex 1.62127 2.08771 2.46319 + vertex 1.62591 2.09019 2.46165 + endloop + endfacet + facet normal 0.0576326 0.448062 0.892143 + outer loop + vertex 1.62127 2.08771 2.46319 + vertex 1.6267 2.08659 2.46341 + vertex 1.62591 2.09019 2.46165 + endloop + endfacet + facet normal 0.0904243 0.641362 0.761891 + outer loop + vertex 1.62478 2.09332 2.4597 + vertex 1.62823 2.09266 2.45984 + vertex 1.62734 2.09606 2.45709 + endloop + endfacet + facet normal 0.100949 0.635183 0.765736 + outer loop + vertex 1.62478 2.09332 2.4597 + vertex 1.62734 2.09606 2.45709 + vertex 1.6227 2.0962 2.45759 + endloop + endfacet + facet normal 0.0897702 0.630765 0.770764 + outer loop + vertex 1.62478 2.09332 2.4597 + vertex 1.6227 2.0962 2.45759 + vertex 1.62102 2.09347 2.46002 + endloop + endfacet + facet normal 0.100034 0.650321 0.753044 + outer loop + vertex 1.6227 2.0962 2.45759 + vertex 1.62734 2.09606 2.45709 + vertex 1.62474 2.09685 2.45675 + endloop + endfacet + facet normal 0.0687206 0.544801 0.835745 + outer loop + vertex 1.62823 2.09266 2.45984 + vertex 1.62478 2.09332 2.4597 + vertex 1.62591 2.09019 2.46165 + endloop + endfacet + facet normal 0.151219 0.873879 0.462026 + outer loop + vertex 1.62315 2.10017 2.4527 + vertex 1.62842 2.09907 2.45305 + vertex 1.62543 2.10149 2.44945 + endloop + endfacet + facet normal 0.168228 0.866059 0.470788 + outer loop + vertex 1.62161 2.10183 2.45018 + vertex 1.62315 2.10017 2.4527 + vertex 1.62543 2.10149 2.44945 + endloop + endfacet + facet normal 0.151594 0.765777 0.624984 + outer loop + vertex 1.62734 2.09606 2.45709 + vertex 1.62428 2.098 2.45546 + vertex 1.62474 2.09685 2.45675 + endloop + endfacet + facet normal 0.15979 0.771282 0.61611 + outer loop + vertex 1.62734 2.09606 2.45709 + vertex 1.62842 2.09907 2.45305 + vertex 1.62428 2.098 2.45546 + endloop + endfacet + facet normal 0.129192 0.805245 0.578697 + outer loop + vertex 1.62842 2.09907 2.45305 + vertex 1.62315 2.10017 2.4527 + vertex 1.62428 2.098 2.45546 + endloop + endfacet + facet normal 0.0279298 0.753007 0.65742 + outer loop + vertex 1.62474 2.09685 2.45675 + vertex 1.62428 2.098 2.45546 + vertex 1.6227 2.0962 2.45759 + endloop + endfacet + facet normal 0.0146358 0.228714 0.973384 + outer loop + vertex 1.63 2.10679 2.445 + vertex 1.625 2.10711 2.445 + vertex 1.62717 2.10344 2.44583 + endloop + endfacet + facet normal 0.20557 0.329863 0.921375 + outer loop + vertex 1.62717 2.10344 2.44583 + vertex 1.625 2.10711 2.445 + vertex 1.62202 2.10375 2.44687 + endloop + endfacet + facet normal 0.173628 0.842608 0.509769 + outer loop + vertex 1.62543 2.10149 2.44945 + vertex 1.62202 2.10375 2.44687 + vertex 1.62161 2.10183 2.45018 + endloop + endfacet + facet normal 0.156672 0.835822 0.526171 + outer loop + vertex 1.62717 2.10344 2.44583 + vertex 1.62202 2.10375 2.44687 + vertex 1.62543 2.10149 2.44945 + endloop + endfacet + facet normal 0.266075 -0.961984 0.0615718 + outer loop + vertex 1.635 0.926927 2.44 + vertex 1.635 0.927247 2.445 + vertex 1.63 0.925544 2.44 + endloop + endfacet + facet normal 0.268987 -0.961369 0.0584495 + outer loop + vertex 1.635 0.927247 2.445 + vertex 1.63 0.925848 2.445 + vertex 1.63 0.925544 2.44 + endloop + endfacet + facet normal 0.134472 -0.480606 0.866565 + outer loop + vertex 1.635 0.927247 2.445 + vertex 1.63151 0.927238 2.44554 + vertex 1.63 0.925848 2.445 + endloop + endfacet + facet normal 0.176647 -0.515652 0.838391 + outer loop + vertex 1.63151 0.927238 2.44554 + vertex 1.6265 0.926632 2.44622 + vertex 1.63 0.925848 2.445 + endloop + endfacet + facet normal 0.166612 -0.883012 0.438783 + outer loop + vertex 1.63151 0.927238 2.44554 + vertex 1.62922 0.928482 2.44891 + vertex 1.6265 0.926632 2.44622 + endloop + endfacet + facet normal 0.148058 -0.891034 0.429113 + outer loop + vertex 1.63405 0.928884 2.44808 + vertex 1.62922 0.928482 2.44891 + vertex 1.63151 0.927238 2.44554 + endloop + endfacet + facet normal 0.150904 -0.879629 0.451088 + outer loop + vertex 1.62922 0.928482 2.44891 + vertex 1.63405 0.928884 2.44808 + vertex 1.63244 0.930482 2.45173 + endloop + endfacet + facet normal 0.129199 -0.872659 0.470928 + outer loop + vertex 1.62736 0.930195 2.4526 + vertex 1.62922 0.928482 2.44891 + vertex 1.63244 0.930482 2.45173 + endloop + endfacet + facet normal 0.139469 -0.825305 0.547193 + outer loop + vertex 1.63244 0.930482 2.45173 + vertex 1.63063 0.932449 2.45516 + vertex 1.62736 0.930195 2.4526 + endloop + endfacet + facet normal 0.1128 -0.813355 0.570727 + outer loop + vertex 1.63063 0.932449 2.45516 + vertex 1.62551 0.932137 2.45573 + vertex 1.62736 0.930195 2.4526 + endloop + endfacet + facet normal 0.117794 -0.75055 0.65023 + outer loop + vertex 1.63063 0.932449 2.45516 + vertex 1.62834 0.934565 2.45802 + vertex 1.62551 0.932137 2.45573 + endloop + endfacet + facet normal 0.122082 -0.748315 0.652013 + outer loop + vertex 1.63377 0.935331 2.45788 + vertex 1.62834 0.934565 2.45802 + vertex 1.63063 0.932449 2.45516 + endloop + endfacet + facet normal 0.113361 -0.672261 0.731583 + outer loop + vertex 1.62834 0.934565 2.45802 + vertex 1.63377 0.935331 2.45788 + vertex 1.63084 0.937374 2.46021 + endloop + endfacet + facet normal 0.0771748 -0.655428 0.751305 + outer loop + vertex 1.62599 0.936997 2.46038 + vertex 1.62834 0.934565 2.45802 + vertex 1.63084 0.937374 2.46021 + endloop + endfacet + facet normal 0.070916 -0.534099 0.842442 + outer loop + vertex 1.63084 0.937374 2.46021 + vertex 1.62901 0.940317 2.46223 + vertex 1.62599 0.936997 2.46038 + endloop + endfacet + facet normal 0.0943237 -0.522843 0.847194 + outer loop + vertex 1.63364 0.940408 2.46177 + vertex 1.62901 0.940317 2.46223 + vertex 1.63084 0.937374 2.46021 + endloop + endfacet + facet normal 0.0982836 -0.398918 0.911704 + outer loop + vertex 1.63364 0.940408 2.46177 + vertex 1.63307 0.944113 2.46346 + vertex 1.62901 0.940317 2.46223 + endloop + endfacet + facet normal 0.117612 -0.416312 0.901583 + outer loop + vertex 1.62901 0.940317 2.46223 + vertex 1.63307 0.944113 2.46346 + vertex 1.6272 0.94441 2.46436 + endloop + endfacet + facet normal 0.0798115 -0.40459 0.911009 + outer loop + vertex 1.62915 0.948013 2.46579 + vertex 1.62615 0.947505 2.46583 + vertex 1.6272 0.94441 2.46436 + endloop + endfacet + facet normal 0.185981 -0.447481 0.874741 + outer loop + vertex 1.62915 0.948013 2.46579 + vertex 1.6272 0.94441 2.46436 + vertex 1.633 0.948413 2.46517 + endloop + endfacet + facet normal 0.123316 -0.366384 0.922256 + outer loop + vertex 1.633 0.948413 2.46517 + vertex 1.6272 0.94441 2.46436 + vertex 1.63307 0.944113 2.46346 + endloop + endfacet + facet normal 0.0680476 -0.332792 0.940542 + outer loop + vertex 1.62915 0.948013 2.46579 + vertex 1.62817 0.950806 2.46685 + vertex 1.62615 0.947505 2.46583 + endloop + endfacet + facet normal 0.18415 -0.382942 0.905232 + outer loop + vertex 1.633 0.948413 2.46517 + vertex 1.63147 0.950373 2.46631 + vertex 1.62915 0.948013 2.46579 + endloop + endfacet + facet normal 0.110162 -0.318413 0.941529 + outer loop + vertex 1.63147 0.950373 2.46631 + vertex 1.62817 0.950806 2.46685 + vertex 1.62915 0.948013 2.46579 + endloop + endfacet + facet normal 0.120555 -0.259726 0.958128 + outer loop + vertex 1.63147 0.950373 2.46631 + vertex 1.63285 0.95412 2.46716 + vertex 1.62817 0.950806 2.46685 + endloop + endfacet + facet normal 0.279536 -0.139805 0.949902 + outer loop + vertex 1.62952 1.22217 2.52596 + vertex 1.62693 1.21973 2.52636 + vertex 1.62951 1.21907 2.52551 + endloop + endfacet + facet normal 0.285415 0.165866 0.943942 + outer loop + vertex 1.6341 1.85915 2.51601 + vertex 1.63457 1.86346 2.51511 + vertex 1.63131 1.8611 2.51651 + endloop + endfacet + facet normal 0.2854 0.165887 0.943943 + outer loop + vertex 1.63131 1.8611 2.51651 + vertex 1.63457 1.86346 2.51511 + vertex 1.6299 1.86518 2.51622 + endloop + endfacet + facet normal 0.285458 0.197226 0.937878 + outer loop + vertex 1.62832 1.93326 2.50393 + vertex 1.63107 1.93624 2.50246 + vertex 1.62665 1.93647 2.50376 + endloop + endfacet + facet normal 0.167477 0.305278 0.93742 + outer loop + vertex 1.62915 2.07895 2.466 + vertex 1.63319 2.07796 2.4656 + vertex 1.63305 2.0818 2.46437 + endloop + endfacet + facet normal 0.146618 0.330886 0.932211 + outer loop + vertex 1.62784 2.08277 2.46485 + vertex 1.62915 2.07895 2.466 + vertex 1.63305 2.0818 2.46437 + endloop + endfacet + facet normal 0.166819 0.302128 0.938557 + outer loop + vertex 1.63319 2.07796 2.4656 + vertex 1.62915 2.07895 2.466 + vertex 1.63103 2.07475 2.46702 + endloop + endfacet + facet normal 0.145316 0.322386 0.935388 + outer loop + vertex 1.63305 2.0818 2.46437 + vertex 1.63087 2.08551 2.46343 + vertex 1.62784 2.08277 2.46485 + endloop + endfacet + facet normal 0.0912059 0.375452 0.922343 + outer loop + vertex 1.62784 2.08277 2.46485 + vertex 1.63087 2.08551 2.46343 + vertex 1.6267 2.08659 2.46341 + endloop + endfacet + facet normal 0.108144 0.440594 0.891169 + outer loop + vertex 1.63087 2.08551 2.46343 + vertex 1.63077 2.08948 2.46148 + vertex 1.6267 2.08659 2.46341 + endloop + endfacet + facet normal 0.096478 0.453579 0.885979 + outer loop + vertex 1.6267 2.08659 2.46341 + vertex 1.63077 2.08948 2.46148 + vertex 1.62591 2.09019 2.46165 + endloop + endfacet + facet normal 0.0565398 0.734752 0.675976 + outer loop + vertex 1.63116 2.09631 2.4565 + vertex 1.62992 2.09743 2.45539 + vertex 1.62734 2.09606 2.45709 + endloop + endfacet + facet normal 0.0787739 0.628456 0.773846 + outer loop + vertex 1.63116 2.09631 2.4565 + vertex 1.62734 2.09606 2.45709 + vertex 1.63202 2.09372 2.45851 + endloop + endfacet + facet normal 0.0886718 0.641191 0.762241 + outer loop + vertex 1.63202 2.09372 2.45851 + vertex 1.62734 2.09606 2.45709 + vertex 1.62823 2.09266 2.45984 + endloop + endfacet + facet normal 0.104914 0.519699 0.847884 + outer loop + vertex 1.63077 2.08948 2.46148 + vertex 1.62823 2.09266 2.45984 + vertex 1.62591 2.09019 2.46165 + endloop + endfacet + facet normal 0.140972 0.539342 0.830203 + outer loop + vertex 1.63202 2.09372 2.45851 + vertex 1.62823 2.09266 2.45984 + vertex 1.63077 2.08948 2.46148 + endloop + endfacet + facet normal 0.111428 0.879931 0.46185 + outer loop + vertex 1.62842 2.09907 2.45305 + vertex 1.63383 2.09972 2.45049 + vertex 1.63031 2.10127 2.44839 + endloop + endfacet + facet normal 0.140228 0.871642 0.469655 + outer loop + vertex 1.62543 2.10149 2.44945 + vertex 1.62842 2.09907 2.45305 + vertex 1.63031 2.10127 2.44839 + endloop + endfacet + facet normal -0.0381989 0.80661 0.589848 + outer loop + vertex 1.62992 2.09743 2.45539 + vertex 1.62842 2.09907 2.45305 + vertex 1.62734 2.09606 2.45709 + endloop + endfacet + facet normal 0.107298 0.845358 0.523314 + outer loop + vertex 1.62992 2.09743 2.45539 + vertex 1.63295 2.09774 2.45427 + vertex 1.62842 2.09907 2.45305 + endloop + endfacet + facet normal 0.123787 0.866 0.48448 + outer loop + vertex 1.63295 2.09774 2.45427 + vertex 1.63383 2.09972 2.45049 + vertex 1.62842 2.09907 2.45305 + endloop + endfacet + facet normal 0.148313 0.774975 0.614343 + outer loop + vertex 1.63295 2.09774 2.45427 + vertex 1.62992 2.09743 2.45539 + vertex 1.63116 2.09631 2.4565 + endloop + endfacet + facet normal 0.134602 0.989762 -0.0474799 + outer loop + vertex 1.635 2.10644 2.44 + vertex 1.63 2.10712 2.44 + vertex 1.635 2.10668 2.445 + endloop + endfacet + facet normal 0.0219768 0.997588 0.0658367 + outer loop + vertex 1.635 2.10668 2.445 + vertex 1.63 2.10712 2.44 + vertex 1.63 2.10679 2.445 + endloop + endfacet + facet normal 0.000140076 0.00635846 0.99998 + outer loop + vertex 1.635 2.10668 2.445 + vertex 1.63 2.10679 2.445 + vertex 1.63296 2.10346 2.44502 + endloop + endfacet + facet normal 0.136699 0.127822 0.982331 + outer loop + vertex 1.63296 2.10346 2.44502 + vertex 1.63 2.10679 2.445 + vertex 1.62717 2.10344 2.44583 + endloop + endfacet + facet normal 0.150631 0.838015 0.524443 + outer loop + vertex 1.63031 2.10127 2.44839 + vertex 1.62717 2.10344 2.44583 + vertex 1.62543 2.10149 2.44945 + endloop + endfacet + facet normal 0.078695 0.806461 0.586027 + outer loop + vertex 1.63296 2.10346 2.44502 + vertex 1.62717 2.10344 2.44583 + vertex 1.63031 2.10127 2.44839 + endloop + endfacet + facet normal 0.0146973 -0.149063 0.988718 + outer loop + vertex 1.64 0.92774 2.445 + vertex 1.63716 0.928102 2.4451 + vertex 1.635 0.927247 2.445 + endloop + endfacet + facet normal 0.137104 -0.446471 0.884232 + outer loop + vertex 1.63716 0.928102 2.4451 + vertex 1.63151 0.927238 2.44554 + vertex 1.635 0.927247 2.445 + endloop + endfacet + facet normal 0.169016 -0.895726 0.411227 + outer loop + vertex 1.63716 0.928102 2.4451 + vertex 1.63405 0.928884 2.44808 + vertex 1.63151 0.927238 2.44554 + endloop + endfacet + facet normal 0.184479 -0.886256 0.424875 + outer loop + vertex 1.63797 0.929264 2.44717 + vertex 1.63405 0.928884 2.44808 + vertex 1.63716 0.928102 2.4451 + endloop + endfacet + facet normal 0.188209 -0.875265 0.445521 + outer loop + vertex 1.63405 0.928884 2.44808 + vertex 1.63797 0.929264 2.44717 + vertex 1.63727 0.930647 2.45018 + endloop + endfacet + facet normal 0.177076 -0.870745 0.458745 + outer loop + vertex 1.63244 0.930482 2.45173 + vertex 1.63405 0.928884 2.44808 + vertex 1.63727 0.930647 2.45018 + endloop + endfacet + facet normal 0.193323 -0.836343 0.512988 + outer loop + vertex 1.63727 0.930647 2.45018 + vertex 1.63624 0.932893 2.45423 + vertex 1.63244 0.930482 2.45173 + endloop + endfacet + facet normal 0.1563 -0.818823 0.552358 + outer loop + vertex 1.63624 0.932893 2.45423 + vertex 1.63063 0.932449 2.45516 + vertex 1.63244 0.930482 2.45173 + endloop + endfacet + facet normal 0.163651 -0.765519 0.622253 + outer loop + vertex 1.63624 0.932893 2.45423 + vertex 1.63377 0.935331 2.45788 + vertex 1.63063 0.932449 2.45516 + endloop + endfacet + facet normal 0.177452 -0.758582 0.626949 + outer loop + vertex 1.63828 0.935638 2.45698 + vertex 1.63377 0.935331 2.45788 + vertex 1.63624 0.932893 2.45423 + endloop + endfacet + facet normal 0.112735 -0.672754 0.731227 + outer loop + vertex 1.63447 0.93801 2.46024 + vertex 1.63084 0.937374 2.46021 + vertex 1.63377 0.935331 2.45788 + endloop + endfacet + facet normal 0.196538 -0.676114 0.710101 + outer loop + vertex 1.63447 0.93801 2.46024 + vertex 1.63377 0.935331 2.45788 + vertex 1.63735 0.93792 2.45935 + endloop + endfacet + facet normal 0.189597 -0.670555 0.717223 + outer loop + vertex 1.63735 0.93792 2.45935 + vertex 1.63377 0.935331 2.45788 + vertex 1.63828 0.935638 2.45698 + endloop + endfacet + facet normal 0.0845007 -0.516351 0.852198 + outer loop + vertex 1.63447 0.93801 2.46024 + vertex 1.63364 0.940408 2.46177 + vertex 1.63084 0.937374 2.46021 + endloop + endfacet + facet normal 0.227946 -0.554783 0.80016 + outer loop + vertex 1.63735 0.93792 2.45935 + vertex 1.63666 0.940086 2.46105 + vertex 1.63447 0.93801 2.46024 + endloop + endfacet + facet normal 0.150963 -0.4954 0.855447 + outer loop + vertex 1.63666 0.940086 2.46105 + vertex 1.63364 0.940408 2.46177 + vertex 1.63447 0.93801 2.46024 + endloop + endfacet + facet normal 0.178333 -0.366966 0.91298 + outer loop + vertex 1.63666 0.940086 2.46105 + vertex 1.63798 0.943791 2.46229 + vertex 1.63364 0.940408 2.46177 + endloop + endfacet + facet normal 0.190676 -0.3815 0.904489 + outer loop + vertex 1.63798 0.943791 2.46229 + vertex 1.63307 0.944113 2.46346 + vertex 1.63364 0.940408 2.46177 + endloop + endfacet + facet normal 0.28445 0.166028 0.944205 + outer loop + vertex 1.6341 1.85915 2.51601 + vertex 1.6384 1.85877 2.51479 + vertex 1.63457 1.86346 2.51511 + endloop + endfacet + facet normal 0.288029 0.176798 0.94116 + outer loop + vertex 1.63907 1.87909 2.51094 + vertex 1.63952 1.88338 2.51 + vertex 1.63628 1.88103 2.51143 + endloop + endfacet + facet normal 0.287625 0.177364 0.941177 + outer loop + vertex 1.63628 1.88103 2.51143 + vertex 1.63952 1.88338 2.51 + vertex 1.63485 1.88506 2.51111 + endloop + endfacet + facet normal 0.290225 0.178237 0.940213 + outer loop + vertex 1.63438 1.91821 2.50506 + vertex 1.63826 1.91367 2.50472 + vertex 1.63827 1.91827 2.50385 + endloop + endfacet + facet normal 0.272686 0.264233 0.925107 + outer loop + vertex 1.63328 2.06354 2.46994 + vertex 1.63833 2.05843 2.46991 + vertex 1.63791 2.06299 2.46874 + endloop + endfacet + facet normal 0.229106 0.499315 0.835581 + outer loop + vertex 1.63846 2.08819 2.46063 + vertex 1.6391 2.09043 2.45912 + vertex 1.63555 2.09054 2.46003 + endloop + endfacet + facet normal 0.159705 0.427306 0.88989 + outer loop + vertex 1.63555 2.09054 2.46003 + vertex 1.63578 2.08578 2.46227 + vertex 1.63846 2.08819 2.46063 + endloop + endfacet + facet normal 0.17547 0.426797 0.887161 + outer loop + vertex 1.63555 2.09054 2.46003 + vertex 1.63077 2.08948 2.46148 + vertex 1.63578 2.08578 2.46227 + endloop + endfacet + facet normal 0.184275 0.437267 0.88025 + outer loop + vertex 1.63077 2.08948 2.46148 + vertex 1.63087 2.08551 2.46343 + vertex 1.63578 2.08578 2.46227 + endloop + endfacet + facet normal 0.266587 0.668413 0.694374 + outer loop + vertex 1.63762 2.09376 2.45698 + vertex 1.6363 2.09655 2.4548 + vertex 1.63391 2.09583 2.45641 + endloop + endfacet + facet normal 0.134926 0.636208 0.759628 + outer loop + vertex 1.63391 2.09583 2.45641 + vertex 1.63116 2.09631 2.4565 + vertex 1.63202 2.09372 2.45851 + endloop + endfacet + facet normal 0.209432 0.589871 0.779865 + outer loop + vertex 1.63762 2.09376 2.45698 + vertex 1.63391 2.09583 2.45641 + vertex 1.63202 2.09372 2.45851 + endloop + endfacet + facet normal 0.207758 0.59824 0.773915 + outer loop + vertex 1.63762 2.09376 2.45698 + vertex 1.63202 2.09372 2.45851 + vertex 1.63555 2.09054 2.46003 + endloop + endfacet + facet normal 0.216639 0.593596 0.775056 + outer loop + vertex 1.63762 2.09376 2.45698 + vertex 1.63555 2.09054 2.46003 + vertex 1.6391 2.09043 2.45912 + endloop + endfacet + facet normal 0.132526 0.541725 0.830042 + outer loop + vertex 1.63555 2.09054 2.46003 + vertex 1.63202 2.09372 2.45851 + vertex 1.63077 2.08948 2.46148 + endloop + endfacet + facet normal 0.0801669 0.74849 0.658282 + outer loop + vertex 1.63936 2.10063 2.44735 + vertex 1.6374 2.10272 2.44521 + vertex 1.6346 2.10132 2.44715 + endloop + endfacet + facet normal 0.120206 0.884598 0.450597 + outer loop + vertex 1.6346 2.10132 2.44715 + vertex 1.63031 2.10127 2.44839 + vertex 1.63383 2.09972 2.45049 + endloop + endfacet + facet normal 0.109203 0.886776 0.449113 + outer loop + vertex 1.6346 2.10132 2.44715 + vertex 1.63383 2.09972 2.45049 + vertex 1.63936 2.10063 2.44735 + endloop + endfacet + facet normal 0.163197 0.83302 0.528625 + outer loop + vertex 1.63936 2.10063 2.44735 + vertex 1.63383 2.09972 2.45049 + vertex 1.63742 2.09818 2.45181 + endloop + endfacet + facet normal 0.177083 0.773615 0.608408 + outer loop + vertex 1.6363 2.09655 2.4548 + vertex 1.63295 2.09774 2.45427 + vertex 1.63391 2.09583 2.45641 + endloop + endfacet + facet normal 0.207764 0.823612 0.527729 + outer loop + vertex 1.6363 2.09655 2.4548 + vertex 1.63742 2.09818 2.45181 + vertex 1.63295 2.09774 2.45427 + endloop + endfacet + facet normal 0.184881 0.851305 0.491017 + outer loop + vertex 1.63742 2.09818 2.45181 + vertex 1.63383 2.09972 2.45049 + vertex 1.63295 2.09774 2.45427 + endloop + endfacet + facet normal 0.154148 0.771739 0.616974 + outer loop + vertex 1.63391 2.09583 2.45641 + vertex 1.63295 2.09774 2.45427 + vertex 1.63116 2.09631 2.4565 + endloop + endfacet + facet normal 0.0935783 0.736989 0.669395 + outer loop + vertex 1.6374 2.10272 2.44521 + vertex 1.63296 2.10346 2.44502 + vertex 1.6346 2.10132 2.44715 + endloop + endfacet + facet normal -0.0308128 0.0731479 0.996845 + outer loop + vertex 1.6374 2.10272 2.44521 + vertex 1.64 2.10671 2.445 + vertex 1.63296 2.10346 2.44502 + endloop + endfacet + facet normal -3.88836e-05 0.0064718 0.999979 + outer loop + vertex 1.64 2.10671 2.445 + vertex 1.635 2.10668 2.445 + vertex 1.63296 2.10346 2.44502 + endloop + endfacet + facet normal 0.173404 0.757872 0.628937 + outer loop + vertex 1.6346 2.10132 2.44715 + vertex 1.63296 2.10346 2.44502 + vertex 1.63031 2.10127 2.44839 + endloop + endfacet + facet normal -0.0368671 0.854169 0.518688 + outer loop + vertex 1.64062 0.929073 2.44533 + vertex 1.645 0.929461 2.445 + vertex 1.64417 0.929656 2.44462 + endloop + endfacet + facet normal 0.111768 -0.587707 0.801317 + outer loop + vertex 1.64062 0.929073 2.44533 + vertex 1.63716 0.928102 2.4451 + vertex 1.645 0.929461 2.445 + endloop + endfacet + facet normal 0.0248004 -0.0720512 0.997093 + outer loop + vertex 1.63716 0.928102 2.4451 + vertex 1.64 0.92774 2.445 + vertex 1.645 0.929461 2.445 + endloop + endfacet + facet normal 0.22132 -0.884972 0.409685 + outer loop + vertex 1.64062 0.929073 2.44533 + vertex 1.63797 0.929264 2.44717 + vertex 1.63716 0.928102 2.4451 + endloop + endfacet + facet normal 0.233068 -0.852963 0.467047 + outer loop + vertex 1.64417 0.929656 2.44462 + vertex 1.6422 0.930443 2.44704 + vertex 1.64062 0.929073 2.44533 + endloop + endfacet + facet normal 0.252478 -0.855822 0.451468 + outer loop + vertex 1.63797 0.929264 2.44717 + vertex 1.64062 0.929073 2.44533 + vertex 1.6422 0.930443 2.44704 + endloop + endfacet + facet normal 0.252463 -0.855756 0.451601 + outer loop + vertex 1.63797 0.929264 2.44717 + vertex 1.6422 0.930443 2.44704 + vertex 1.63727 0.930647 2.45018 + endloop + endfacet + facet normal 0.273952 -0.831251 0.483706 + outer loop + vertex 1.63727 0.930647 2.45018 + vertex 1.6422 0.930443 2.44704 + vertex 1.64136 0.932757 2.45149 + endloop + endfacet + facet normal 0.359927 -0.775469 0.518749 + outer loop + vertex 1.63991 0.93431 2.45482 + vertex 1.64136 0.932757 2.45149 + vertex 1.6425 0.935167 2.4543 + endloop + endfacet + facet normal 0.242861 -0.834192 0.495119 + outer loop + vertex 1.63991 0.93431 2.45482 + vertex 1.63624 0.932893 2.45423 + vertex 1.64136 0.932757 2.45149 + endloop + endfacet + facet normal 0.255463 -0.816471 0.517796 + outer loop + vertex 1.63624 0.932893 2.45423 + vertex 1.63727 0.930647 2.45018 + vertex 1.64136 0.932757 2.45149 + endloop + endfacet + facet normal 0.195735 -0.762241 0.61699 + outer loop + vertex 1.63991 0.93431 2.45482 + vertex 1.63828 0.935638 2.45698 + vertex 1.63624 0.932893 2.45423 + endloop + endfacet + facet normal 0.356359 -0.71407 0.602588 + outer loop + vertex 1.6425 0.935167 2.4543 + vertex 1.64126 0.936222 2.45629 + vertex 1.63991 0.93431 2.45482 + endloop + endfacet + facet normal 0.288084 -0.702875 0.650365 + outer loop + vertex 1.64126 0.936222 2.45629 + vertex 1.63828 0.935638 2.45698 + vertex 1.63991 0.93431 2.45482 + endloop + endfacet + facet normal 0.289955 -0.61478 0.733466 + outer loop + vertex 1.64126 0.936222 2.45629 + vertex 1.64084 0.938448 2.45832 + vertex 1.63828 0.935638 2.45698 + endloop + endfacet + facet normal 0.307751 -0.623835 0.718414 + outer loop + vertex 1.64084 0.938448 2.45832 + vertex 1.63735 0.93792 2.45935 + vertex 1.63828 0.935638 2.45698 + endloop + endfacet + facet normal 0.314073 -0.530963 0.787043 + outer loop + vertex 1.63735 0.93792 2.45935 + vertex 1.64084 0.938448 2.45832 + vertex 1.63974 0.941047 2.46051 + endloop + endfacet + facet normal 0.303889 -0.525908 0.794401 + outer loop + vertex 1.63666 0.940086 2.46105 + vertex 1.63735 0.93792 2.45935 + vertex 1.63974 0.941047 2.46051 + endloop + endfacet + facet normal 0.276401 -0.390291 0.878223 + outer loop + vertex 1.63974 0.941047 2.46051 + vertex 1.63798 0.943791 2.46229 + vertex 1.63666 0.940086 2.46105 + endloop + endfacet + facet normal 0.273915 -0.391923 0.878275 + outer loop + vertex 1.64192 0.944385 2.46132 + vertex 1.63798 0.943791 2.46229 + vertex 1.63974 0.941047 2.46051 + endloop + endfacet + facet normal 0.300025 -0.144913 0.94286 + outer loop + vertex 1.64104 1.18007 2.5159 + vertex 1.64098 1.18325 2.51641 + vertex 1.6371 1.17836 2.51689 + endloop + endfacet + facet normal 0.289723 -0.123357 0.949128 + outer loop + vertex 1.63907 1.24219 2.52586 + vertex 1.63657 1.23951 2.52628 + vertex 1.63932 1.23903 2.52538 + endloop + endfacet + facet normal 0.28677 0.177005 0.941505 + outer loop + vertex 1.63907 1.87909 2.51094 + vertex 1.64335 1.8787 2.50971 + vertex 1.63952 1.88338 2.51 + endloop + endfacet + facet normal 0.286453 0.19252 0.938552 + outer loop + vertex 1.63825 1.93862 2.49975 + vertex 1.64237 1.93381 2.49948 + vertex 1.64269 1.93836 2.49844 + endloop + endfacet + facet normal 0.279921 0.251038 0.92662 + outer loop + vertex 1.63988 2.03528 2.47583 + vertex 1.63982 2.03125 2.47694 + vertex 1.64276 2.03344 2.47545 + endloop + endfacet + facet normal 0.286263 0.255407 0.923483 + outer loop + vertex 1.6437 2.04875 2.47094 + vertex 1.64326 2.05331 2.46981 + vertex 1.64056 2.05065 2.47138 + endloop + endfacet + facet normal 0.286477 0.255801 0.923308 + outer loop + vertex 1.64056 2.05065 2.47138 + vertex 1.64106 2.04615 2.47247 + vertex 1.6437 2.04875 2.47094 + endloop + endfacet + facet normal 0.289637 0.255906 0.922292 + outer loop + vertex 1.64056 2.05065 2.47138 + vertex 1.63609 2.05132 2.4726 + vertex 1.64106 2.04615 2.47247 + endloop + endfacet + facet normal 0.288962 0.264455 0.920089 + outer loop + vertex 1.63833 2.05843 2.46991 + vertex 1.64108 2.06106 2.4683 + vertex 1.63791 2.06299 2.46874 + endloop + endfacet + facet normal 0.336042 0.375601 0.863713 + outer loop + vertex 1.64299 2.08357 2.46096 + vertex 1.64226 2.08718 2.45968 + vertex 1.64001 2.08545 2.46131 + endloop + endfacet + facet normal 0.293875 0.300711 0.907309 + outer loop + vertex 1.64001 2.08545 2.46131 + vertex 1.64077 2.08121 2.46247 + vertex 1.64299 2.08357 2.46096 + endloop + endfacet + facet normal 0.234672 0.295281 0.926142 + outer loop + vertex 1.64001 2.08545 2.46131 + vertex 1.63578 2.08578 2.46227 + vertex 1.64077 2.08121 2.46247 + endloop + endfacet + facet normal 0.321103 0.393021 0.861642 + outer loop + vertex 1.63846 2.08819 2.46063 + vertex 1.64001 2.08545 2.46131 + vertex 1.64226 2.08718 2.45968 + endloop + endfacet + facet normal 0.329829 0.462143 0.823187 + outer loop + vertex 1.63846 2.08819 2.46063 + vertex 1.64226 2.08718 2.45968 + vertex 1.6391 2.09043 2.45912 + endloop + endfacet + facet normal 0.364612 0.490584 0.791445 + outer loop + vertex 1.6391 2.09043 2.45912 + vertex 1.64226 2.08718 2.45968 + vertex 1.64227 2.09085 2.4574 + endloop + endfacet + facet normal 0.234542 0.35462 0.905116 + outer loop + vertex 1.64001 2.08545 2.46131 + vertex 1.63846 2.08819 2.46063 + vertex 1.63578 2.08578 2.46227 + endloop + endfacet + facet normal 0.314526 0.678214 0.664153 + outer loop + vertex 1.63762 2.09376 2.45698 + vertex 1.64289 2.09372 2.45453 + vertex 1.64 2.09614 2.45342 + endloop + endfacet + facet normal 0.322592 0.67272 0.665869 + outer loop + vertex 1.6363 2.09655 2.4548 + vertex 1.63762 2.09376 2.45698 + vertex 1.64 2.09614 2.45342 + endloop + endfacet + facet normal 0.315038 0.607627 0.729068 + outer loop + vertex 1.64227 2.09085 2.4574 + vertex 1.63762 2.09376 2.45698 + vertex 1.6391 2.09043 2.45912 + endloop + endfacet + facet normal 0.331733 0.630424 0.701797 + outer loop + vertex 1.64289 2.09372 2.45453 + vertex 1.63762 2.09376 2.45698 + vertex 1.64227 2.09085 2.4574 + endloop + endfacet + facet normal -0.215332 0.592527 0.776237 + outer loop + vertex 1.6429 2.105 2.445 + vertex 1.6374 2.10272 2.44521 + vertex 1.63936 2.10063 2.44735 + endloop + endfacet + facet normal 0.227564 0.312356 0.922306 + outer loop + vertex 1.6429 2.105 2.445 + vertex 1.63936 2.10063 2.44735 + vertex 1.645 2.10347 2.445 + endloop + endfacet + facet normal 0.244514 0.282932 0.927449 + outer loop + vertex 1.645 2.10347 2.445 + vertex 1.63936 2.10063 2.44735 + vertex 1.64328 2.09972 2.4466 + endloop + endfacet + facet normal 0.28872 0.754585 0.589273 + outer loop + vertex 1.64328 2.09972 2.4466 + vertex 1.63936 2.10063 2.44735 + vertex 1.64238 2.09783 2.44946 + endloop + endfacet + facet normal 0.319369 0.765044 0.559205 + outer loop + vertex 1.64238 2.09783 2.44946 + vertex 1.63936 2.10063 2.44735 + vertex 1.63742 2.09818 2.45181 + endloop + endfacet + facet normal 0.288948 0.79038 0.540194 + outer loop + vertex 1.64 2.09614 2.45342 + vertex 1.63742 2.09818 2.45181 + vertex 1.6363 2.09655 2.4548 + endloop + endfacet + facet normal 0.304329 0.796195 0.522931 + outer loop + vertex 1.64238 2.09783 2.44946 + vertex 1.63742 2.09818 2.45181 + vertex 1.64 2.09614 2.45342 + endloop + endfacet + facet normal 0.0226609 0.0384322 0.999004 + outer loop + vertex 1.6429 2.105 2.445 + vertex 1.64 2.10671 2.445 + vertex 1.6374 2.10272 2.44521 + endloop + endfacet + facet normal 0.271671 -0.922354 -0.274695 + outer loop + vertex 1.64683 0.93 2.445 + vertex 1.645 0.929461 2.445 + vertex 1.645 0.93 2.44319 + endloop + endfacet + facet normal -0.189285 0.642642 0.742417 + outer loop + vertex 1.64683 0.93 2.445 + vertex 1.64417 0.929656 2.44462 + vertex 1.645 0.929461 2.445 + endloop + endfacet + facet normal -0.186225 0.51333 0.837743 + outer loop + vertex 1.64417 0.929656 2.44462 + vertex 1.64683 0.93 2.445 + vertex 1.65 0.93115 2.445 + endloop + endfacet + facet normal 0.195189 -0.874875 0.443277 + outer loop + vertex 1.64417 0.929656 2.44462 + vertex 1.65 0.93115 2.445 + vertex 1.6422 0.930443 2.44704 + endloop + endfacet + facet normal 0.244167 -0.669105 0.701913 + outer loop + vertex 1.6422 0.930443 2.44704 + vertex 1.65 0.93115 2.445 + vertex 1.64705 0.932451 2.44727 + endloop + endfacet + facet normal 0.373344 -0.755652 0.538148 + outer loop + vertex 1.64572 0.93503 2.45181 + vertex 1.64705 0.932451 2.44727 + vertex 1.64856 0.933972 2.44835 + endloop + endfacet + facet normal 0.35855 -0.762926 0.537947 + outer loop + vertex 1.64572 0.93503 2.45181 + vertex 1.64136 0.932757 2.45149 + vertex 1.64705 0.932451 2.44727 + endloop + endfacet + facet normal 0.315398 -0.81641 0.483735 + outer loop + vertex 1.64136 0.932757 2.45149 + vertex 1.6422 0.930443 2.44704 + vertex 1.64705 0.932451 2.44727 + endloop + endfacet + facet normal 0.366344 -0.774662 0.515452 + outer loop + vertex 1.64572 0.93503 2.45181 + vertex 1.6425 0.935167 2.4543 + vertex 1.64136 0.932757 2.45149 + endloop + endfacet + facet normal 0.353516 -0.772792 0.527086 + outer loop + vertex 1.64856 0.933972 2.44835 + vertex 1.64916 0.935662 2.45043 + vertex 1.64572 0.93503 2.45181 + endloop + endfacet + facet normal 0.438569 -0.65023 0.620369 + outer loop + vertex 1.6425 0.935167 2.4543 + vertex 1.64472 0.938542 2.45627 + vertex 1.64126 0.936222 2.45629 + endloop + endfacet + facet normal 0.447117 -0.651492 0.612899 + outer loop + vertex 1.64572 0.93503 2.45181 + vertex 1.64472 0.938542 2.45627 + vertex 1.6425 0.935167 2.4543 + endloop + endfacet + facet normal 0.330924 -0.703999 0.628391 + outer loop + vertex 1.64572 0.93503 2.45181 + vertex 1.64859 0.938129 2.45377 + vertex 1.64472 0.938542 2.45627 + endloop + endfacet + facet normal 0.369194 -0.716412 0.591988 + outer loop + vertex 1.64572 0.93503 2.45181 + vertex 1.64916 0.935662 2.45043 + vertex 1.64859 0.938129 2.45377 + endloop + endfacet + facet normal 0.39157 -0.579174 0.715004 + outer loop + vertex 1.64472 0.938542 2.45627 + vertex 1.64084 0.938448 2.45832 + vertex 1.64126 0.936222 2.45629 + endloop + endfacet + facet normal 0.372639 -0.630611 0.680786 + outer loop + vertex 1.64859 0.938129 2.45377 + vertex 1.64785 0.940416 2.45629 + vertex 1.64472 0.938542 2.45627 + endloop + endfacet + facet normal 0.361283 -0.507102 0.78251 + outer loop + vertex 1.64084 0.938448 2.45832 + vertex 1.64349 0.942094 2.45946 + vertex 1.63974 0.941047 2.46051 + endloop + endfacet + facet normal 0.406409 -0.528326 0.745455 + outer loop + vertex 1.64472 0.938542 2.45627 + vertex 1.64349 0.942094 2.45946 + vertex 1.64084 0.938448 2.45832 + endloop + endfacet + facet normal 0.379151 -0.541894 0.750064 + outer loop + vertex 1.64472 0.938542 2.45627 + vertex 1.64837 0.943984 2.45836 + vertex 1.64349 0.942094 2.45946 + endloop + endfacet + facet normal 0.299557 -0.510198 0.806203 + outer loop + vertex 1.64472 0.938542 2.45627 + vertex 1.64785 0.940416 2.45629 + vertex 1.64837 0.943984 2.45836 + endloop + endfacet + facet normal 0.353593 -0.432114 0.829608 + outer loop + vertex 1.64349 0.942094 2.45946 + vertex 1.64192 0.944385 2.46132 + vertex 1.63974 0.941047 2.46051 + endloop + endfacet + facet normal 0.363052 -0.405799 0.838761 + outer loop + vertex 1.64837 0.943984 2.45836 + vertex 1.64947 0.949201 2.46041 + vertex 1.64548 0.946402 2.46078 + endloop + endfacet + facet normal 0.351064 -0.418817 0.837465 + outer loop + vertex 1.64349 0.942094 2.45946 + vertex 1.64837 0.943984 2.45836 + vertex 1.64548 0.946402 2.46078 + endloop + endfacet + facet normal 0.365959 -0.423053 0.828915 + outer loop + vertex 1.64548 0.946402 2.46078 + vertex 1.64192 0.944385 2.46132 + vertex 1.64349 0.942094 2.45946 + endloop + endfacet + facet normal 0.29261 -0.145407 0.945112 + outer loop + vertex 1.64362 1.18267 2.5155 + vertex 1.64098 1.18325 2.51641 + vertex 1.64104 1.18007 2.5159 + endloop + endfacet + facet normal 0.290261 -0.154845 0.944337 + outer loop + vertex 1.64486 1.18629 2.51571 + vertex 1.64098 1.18325 2.51641 + vertex 1.64362 1.18267 2.5155 + endloop + endfacet + facet normal 0.281758 0.19315 0.939843 + outer loop + vertex 1.64237 1.93381 2.49948 + vertex 1.64692 1.93605 2.49765 + vertex 1.64269 1.93836 2.49844 + endloop + endfacet + facet normal 0.282574 0.223596 0.932822 + outer loop + vertex 1.64917 1.984 2.48613 + vertex 1.64922 1.9881 2.48514 + vertex 1.64626 1.98591 2.48656 + endloop + endfacet + facet normal 0.282234 0.224052 0.932815 + outer loop + vertex 1.64626 1.98591 2.48656 + vertex 1.64922 1.9881 2.48514 + vertex 1.64457 1.98982 2.48613 + endloop + endfacet + facet normal 0.279684 0.251348 0.926607 + outer loop + vertex 1.64446 2.02961 2.47598 + vertex 1.64276 2.03344 2.47545 + vertex 1.63982 2.03125 2.47694 + endloop + endfacet + facet normal 0.283041 0.256154 0.924269 + outer loop + vertex 1.6437 2.04875 2.47094 + vertex 1.64549 2.04558 2.47127 + vertex 1.64823 2.04819 2.4697 + endloop + endfacet + facet normal 0.283006 0.255344 0.924504 + outer loop + vertex 1.6437 2.04875 2.47094 + vertex 1.64823 2.04819 2.4697 + vertex 1.64326 2.05331 2.46981 + endloop + endfacet + facet normal 0.283813 0.256138 0.924037 + outer loop + vertex 1.64326 2.05331 2.46981 + vertex 1.64823 2.04819 2.4697 + vertex 1.64783 2.05293 2.46851 + endloop + endfacet + facet normal 0.285104 0.257216 0.92334 + outer loop + vertex 1.64549 2.04558 2.47127 + vertex 1.6437 2.04875 2.47094 + vertex 1.64106 2.04615 2.47247 + endloop + endfacet + facet normal 0.290859 0.26918 0.918119 + outer loop + vertex 1.64688 2.07189 2.46328 + vertex 1.64589 2.07607 2.46236 + vertex 1.64274 2.07288 2.4643 + endloop + endfacet + facet normal 0.327939 0.311675 0.891804 + outer loop + vertex 1.64299 2.08357 2.46096 + vertex 1.64501 2.08049 2.4613 + vertex 1.64698 2.08274 2.45978 + endloop + endfacet + facet normal 0.333225 0.37544 0.864873 + outer loop + vertex 1.64299 2.08357 2.46096 + vertex 1.64698 2.08274 2.45978 + vertex 1.64226 2.08718 2.45968 + endloop + endfacet + facet normal 0.360462 0.403853 0.840815 + outer loop + vertex 1.64226 2.08718 2.45968 + vertex 1.64698 2.08274 2.45978 + vertex 1.64664 2.08741 2.45769 + endloop + endfacet + facet normal 0.299887 0.294997 0.907218 + outer loop + vertex 1.64501 2.08049 2.4613 + vertex 1.64299 2.08357 2.46096 + vertex 1.64077 2.08121 2.46247 + endloop + endfacet + facet normal 0.357355 0.619187 0.699217 + outer loop + vertex 1.6485 2.08894 2.45596 + vertex 1.64912 2.09061 2.45417 + vertex 1.64609 2.09104 2.45534 + endloop + endfacet + facet normal 0.275871 0.551884 0.786969 + outer loop + vertex 1.64609 2.09104 2.45534 + vertex 1.64664 2.08741 2.45769 + vertex 1.6485 2.08894 2.45596 + endloop + endfacet + facet normal 0.377614 0.543101 0.749966 + outer loop + vertex 1.64609 2.09104 2.45534 + vertex 1.64227 2.09085 2.4574 + vertex 1.64664 2.08741 2.45769 + endloop + endfacet + facet normal 0.337191 0.496058 0.800143 + outer loop + vertex 1.64227 2.09085 2.4574 + vertex 1.64226 2.08718 2.45968 + vertex 1.64664 2.08741 2.45769 + endloop + endfacet + facet normal 0.409311 0.736858 0.538057 + outer loop + vertex 1.6483 2.09355 2.45122 + vertex 1.64608 2.0963 2.44913 + vertex 1.64386 2.09564 2.45172 + endloop + endfacet + facet normal 0.359223 0.706599 0.609653 + outer loop + vertex 1.64386 2.09564 2.45172 + vertex 1.64 2.09614 2.45342 + vertex 1.64289 2.09372 2.45453 + endloop + endfacet + facet normal 0.394407 0.68807 0.6091 + outer loop + vertex 1.6483 2.09355 2.45122 + vertex 1.64386 2.09564 2.45172 + vertex 1.64289 2.09372 2.45453 + endloop + endfacet + facet normal 0.402862 0.669686 0.623877 + outer loop + vertex 1.6483 2.09355 2.45122 + vertex 1.64289 2.09372 2.45453 + vertex 1.64609 2.09104 2.45534 + endloop + endfacet + facet normal 0.338292 0.712176 0.615112 + outer loop + vertex 1.6483 2.09355 2.45122 + vertex 1.64609 2.09104 2.45534 + vertex 1.64912 2.09061 2.45417 + endloop + endfacet + facet normal 0.346429 0.624996 0.699548 + outer loop + vertex 1.64609 2.09104 2.45534 + vertex 1.64289 2.09372 2.45453 + vertex 1.64227 2.09085 2.4574 + endloop + endfacet + facet normal 0.0633768 0.223154 0.972721 + outer loop + vertex 1.65 2.10205 2.445 + vertex 1.645 2.10347 2.445 + vertex 1.64731 2.09872 2.44594 + endloop + endfacet + facet normal 0.224709 0.292825 0.929387 + outer loop + vertex 1.64731 2.09872 2.44594 + vertex 1.645 2.10347 2.445 + vertex 1.64328 2.09972 2.4466 + endloop + endfacet + facet normal 0.366664 0.776975 0.51173 + outer loop + vertex 1.64608 2.0963 2.44913 + vertex 1.64238 2.09783 2.44946 + vertex 1.64386 2.09564 2.45172 + endloop + endfacet + facet normal 0.339523 0.683069 0.646639 + outer loop + vertex 1.64608 2.0963 2.44913 + vertex 1.64731 2.09872 2.44594 + vertex 1.64238 2.09783 2.44946 + endloop + endfacet + facet normal 0.285405 0.755954 0.589132 + outer loop + vertex 1.64731 2.09872 2.44594 + vertex 1.64328 2.09972 2.4466 + vertex 1.64238 2.09783 2.44946 + endloop + endfacet + facet normal 0.334471 0.777249 0.53293 + outer loop + vertex 1.64386 2.09564 2.45172 + vertex 1.64238 2.09783 2.44946 + vertex 1.64 2.09614 2.45342 + endloop + endfacet + facet normal 0.0492048 0.826141 0.56131 + outer loop + vertex 1.65073 0.933212 2.4457 + vertex 1.655 0.933436 2.445 + vertex 1.65455 0.933849 2.44443 + endloop + endfacet + facet normal 0.0388967 0.85957 0.509535 + outer loop + vertex 1.65073 0.933212 2.4457 + vertex 1.64705 0.932451 2.44727 + vertex 1.655 0.933436 2.445 + endloop + endfacet + facet normal 0.284853 -0.623048 0.728471 + outer loop + vertex 1.64705 0.932451 2.44727 + vertex 1.65 0.93115 2.445 + vertex 1.655 0.933436 2.445 + endloop + endfacet + facet normal 0.380894 -0.757512 0.530184 + outer loop + vertex 1.65073 0.933212 2.4457 + vertex 1.64856 0.933972 2.44835 + vertex 1.64705 0.932451 2.44727 + endloop + endfacet + facet normal 0.312083 -0.776747 0.547054 + outer loop + vertex 1.65455 0.933849 2.44443 + vertex 1.65258 0.93489 2.44704 + vertex 1.65073 0.933212 2.4457 + endloop + endfacet + facet normal 0.347151 -0.786485 0.510811 + outer loop + vertex 1.64856 0.933972 2.44835 + vertex 1.65073 0.933212 2.4457 + vertex 1.65258 0.93489 2.44704 + endloop + endfacet + facet normal 0.349968 -0.773386 0.52858 + outer loop + vertex 1.64856 0.933972 2.44835 + vertex 1.65258 0.93489 2.44704 + vertex 1.64916 0.935662 2.45043 + endloop + endfacet + facet normal 0.373094 -0.74975 0.546513 + outer loop + vertex 1.64916 0.935662 2.45043 + vertex 1.65258 0.93489 2.44704 + vertex 1.65213 0.937295 2.45064 + endloop + endfacet + facet normal 0.354628 -0.722239 0.593809 + outer loop + vertex 1.65213 0.937295 2.45064 + vertex 1.64859 0.938129 2.45377 + vertex 1.64916 0.935662 2.45043 + endloop + endfacet + facet normal 0.365803 -0.708993 0.602924 + outer loop + vertex 1.65194 0.939642 2.45352 + vertex 1.64859 0.938129 2.45377 + vertex 1.65213 0.937295 2.45064 + endloop + endfacet + facet normal 0.337103 -0.628711 0.700773 + outer loop + vertex 1.64859 0.938129 2.45377 + vertex 1.65194 0.939642 2.45352 + vertex 1.65047 0.941497 2.45589 + endloop + endfacet + facet normal 0.366895 -0.633225 0.681479 + outer loop + vertex 1.64785 0.940416 2.45629 + vertex 1.64859 0.938129 2.45377 + vertex 1.65047 0.941497 2.45589 + endloop + endfacet + facet normal 0.332681 -0.508152 0.794421 + outer loop + vertex 1.65047 0.941497 2.45589 + vertex 1.64837 0.943984 2.45836 + vertex 1.64785 0.940416 2.45629 + endloop + endfacet + facet normal 0.319842 -0.517951 0.793365 + outer loop + vertex 1.65322 0.945159 2.45717 + vertex 1.64837 0.943984 2.45836 + vertex 1.65047 0.941497 2.45589 + endloop + endfacet + facet normal 0.309386 -0.40874 0.85861 + outer loop + vertex 1.65322 0.945159 2.45717 + vertex 1.65324 0.949054 2.45902 + vertex 1.64837 0.943984 2.45836 + endloop + endfacet + facet normal 0.302587 -0.402876 0.863789 + outer loop + vertex 1.64837 0.943984 2.45836 + vertex 1.65324 0.949054 2.45902 + vertex 1.64947 0.949201 2.46041 + endloop + endfacet + facet normal 0.279959 -0.209725 0.936824 + outer loop + vertex 1.65063 1.0854 2.49575 + vertex 1.65098 1.08853 2.49635 + vertex 1.64696 1.08407 2.49655 + endloop + endfacet + facet normal 0.346343 -0.0319704 0.937563 + outer loop + vertex 1.64647 1.40223 2.5374 + vertex 1.64636 1.39722 2.53727 + vertex 1.65013 1.40106 2.53601 + endloop + endfacet + facet normal 0.420118 -0.0201148 0.907247 + outer loop + vertex 1.65357 1.40464 2.53451 + vertex 1.65369 1.40958 2.53457 + vertex 1.65023 1.40601 2.53609 + endloop + endfacet + facet normal 0.418779 -0.0239974 0.907771 + outer loop + vertex 1.65013 1.40106 2.53601 + vertex 1.65357 1.40464 2.53451 + vertex 1.65023 1.40601 2.53609 + endloop + endfacet + facet normal 0.348943 -0.0230545 0.93686 + outer loop + vertex 1.65023 1.40601 2.53609 + vertex 1.64647 1.40223 2.5374 + vertex 1.65013 1.40106 2.53601 + endloop + endfacet + facet normal 0.35468 -0.029575 0.93452 + outer loop + vertex 1.64661 1.40723 2.5375 + vertex 1.64647 1.40223 2.5374 + vertex 1.65023 1.40601 2.53609 + endloop + endfacet + facet normal 0.427287 -0.0276693 0.903692 + outer loop + vertex 1.65369 1.40958 2.53457 + vertex 1.65382 1.41444 2.53465 + vertex 1.65041 1.41094 2.53616 + endloop + endfacet + facet normal 0.427059 -0.0283194 0.90378 + outer loop + vertex 1.65023 1.40601 2.53609 + vertex 1.65369 1.40958 2.53457 + vertex 1.65041 1.41094 2.53616 + endloop + endfacet + facet normal 0.355744 -0.0260541 0.93422 + outer loop + vertex 1.65041 1.41094 2.53616 + vertex 1.64661 1.40723 2.5375 + vertex 1.65023 1.40601 2.53609 + endloop + endfacet + facet normal 0.360402 -0.0315326 0.932264 + outer loop + vertex 1.64685 1.41228 2.53758 + vertex 1.64661 1.40723 2.5375 + vertex 1.65041 1.41094 2.53616 + endloop + endfacet + facet normal 0.433753 -0.0320614 0.900461 + outer loop + vertex 1.65382 1.41444 2.53465 + vertex 1.65376 1.41898 2.53485 + vertex 1.65069 1.41573 2.53621 + endloop + endfacet + facet normal 0.432935 -0.0344275 0.900768 + outer loop + vertex 1.65041 1.41094 2.53616 + vertex 1.65382 1.41444 2.53465 + vertex 1.65069 1.41573 2.53621 + endloop + endfacet + facet normal 0.360702 -0.0306391 0.932178 + outer loop + vertex 1.65069 1.41573 2.53621 + vertex 1.64685 1.41228 2.53758 + vertex 1.65041 1.41094 2.53616 + endloop + endfacet + facet normal 0.361304 -0.0314113 0.931919 + outer loop + vertex 1.64733 1.41775 2.53758 + vertex 1.64685 1.41228 2.53758 + vertex 1.65069 1.41573 2.53621 + endloop + endfacet + facet normal 0.442366 -0.0421371 0.895844 + outer loop + vertex 1.65376 1.41898 2.53485 + vertex 1.65114 1.41955 2.53617 + vertex 1.65069 1.41573 2.53621 + endloop + endfacet + facet normal 0.360962 -0.0320533 0.932029 + outer loop + vertex 1.65114 1.41955 2.53617 + vertex 1.64733 1.41775 2.53758 + vertex 1.65069 1.41573 2.53621 + endloop + endfacet + facet normal 0.356806 -0.0217677 0.933925 + outer loop + vertex 1.65114 1.41955 2.53617 + vertex 1.65003 1.42287 2.53667 + vertex 1.64733 1.41775 2.53758 + endloop + endfacet + facet normal 0.353028 -0.0195042 0.935409 + outer loop + vertex 1.65003 1.42287 2.53667 + vertex 1.64615 1.42179 2.53811 + vertex 1.64733 1.41775 2.53758 + endloop + endfacet + facet normal 0.44767 0.0227952 0.893908 + outer loop + vertex 1.65311 1.42493 2.53528 + vertex 1.65435 1.42893 2.53455 + vertex 1.65124 1.42691 2.53616 + endloop + endfacet + facet normal 0.41787 -0.0117676 0.908431 + outer loop + vertex 1.65124 1.42691 2.53616 + vertex 1.65003 1.42287 2.53667 + vertex 1.65311 1.42493 2.53528 + endloop + endfacet + facet normal 0.372526 0.00423865 0.928012 + outer loop + vertex 1.65124 1.42691 2.53616 + vertex 1.64728 1.42669 2.53775 + vertex 1.65003 1.42287 2.53667 + endloop + endfacet + facet normal 0.351529 -0.0131742 0.936084 + outer loop + vertex 1.64728 1.42669 2.53775 + vertex 1.64615 1.42179 2.53811 + vertex 1.65003 1.42287 2.53667 + endloop + endfacet + facet normal 0.447868 0.00462999 0.894088 + outer loop + vertex 1.65435 1.42893 2.53455 + vertex 1.65395 1.43437 2.53473 + vertex 1.65079 1.43093 2.53633 + endloop + endfacet + facet normal 0.452138 0.0142259 0.891835 + outer loop + vertex 1.65124 1.42691 2.53616 + vertex 1.65435 1.42893 2.53455 + vertex 1.65079 1.43093 2.53633 + endloop + endfacet + facet normal 0.372555 0.00366998 0.928003 + outer loop + vertex 1.65079 1.43093 2.53633 + vertex 1.64728 1.42669 2.53775 + vertex 1.65124 1.42691 2.53616 + endloop + endfacet + facet normal 0.386599 -0.00989696 0.922195 + outer loop + vertex 1.6469 1.43241 2.53798 + vertex 1.64728 1.42669 2.53775 + vertex 1.65079 1.43093 2.53633 + endloop + endfacet + facet normal 0.453679 0.00148774 0.891164 + outer loop + vertex 1.65395 1.43437 2.53473 + vertex 1.65378 1.43946 2.53481 + vertex 1.65053 1.43603 2.53647 + endloop + endfacet + facet normal 0.452734 -0.000973816 0.891645 + outer loop + vertex 1.65079 1.43093 2.53633 + vertex 1.65395 1.43437 2.53473 + vertex 1.65053 1.43603 2.53647 + endloop + endfacet + facet normal 0.388173 -0.00505341 0.921573 + outer loop + vertex 1.65053 1.43603 2.53647 + vertex 1.6469 1.43241 2.53798 + vertex 1.65079 1.43093 2.53633 + endloop + endfacet + facet normal 0.397693 -0.0163575 0.917373 + outer loop + vertex 1.64695 1.43771 2.53805 + vertex 1.6469 1.43241 2.53798 + vertex 1.65053 1.43603 2.53647 + endloop + endfacet + facet normal 0.463492 -0.00423326 0.886091 + outer loop + vertex 1.65378 1.43946 2.53481 + vertex 1.65378 1.44438 2.53483 + vertex 1.65054 1.44106 2.53651 + endloop + endfacet + facet normal 0.461888 -0.00833198 0.886899 + outer loop + vertex 1.65053 1.43603 2.53647 + vertex 1.65378 1.43946 2.53481 + vertex 1.65054 1.44106 2.53651 + endloop + endfacet + facet normal 0.400869 -0.00841673 0.916097 + outer loop + vertex 1.65054 1.44106 2.53651 + vertex 1.64695 1.43771 2.53805 + vertex 1.65053 1.43603 2.53647 + endloop + endfacet + facet normal 0.407955 -0.0175121 0.912834 + outer loop + vertex 1.64719 1.44282 2.53804 + vertex 1.64695 1.43771 2.53805 + vertex 1.65054 1.44106 2.53651 + endloop + endfacet + facet normal 0.472826 -0.00929564 0.881107 + outer loop + vertex 1.65378 1.44438 2.53483 + vertex 1.65378 1.44889 2.53487 + vertex 1.6508 1.44585 2.53644 + endloop + endfacet + facet normal 0.471097 -0.0137497 0.881974 + outer loop + vertex 1.65054 1.44106 2.53651 + vertex 1.65378 1.44438 2.53483 + vertex 1.6508 1.44585 2.53644 + endloop + endfacet + facet normal 0.411222 -0.0101129 0.911479 + outer loop + vertex 1.6508 1.44585 2.53644 + vertex 1.64719 1.44282 2.53804 + vertex 1.65054 1.44106 2.53651 + endloop + endfacet + facet normal 0.415701 -0.016583 0.90935 + outer loop + vertex 1.64783 1.44834 2.53785 + vertex 1.64719 1.44282 2.53804 + vertex 1.6508 1.44585 2.53644 + endloop + endfacet + facet normal 0.483084 -0.0223517 0.875289 + outer loop + vertex 1.65378 1.44889 2.53487 + vertex 1.65137 1.44961 2.53622 + vertex 1.6508 1.44585 2.53644 + endloop + endfacet + facet normal 0.419679 -0.0108628 0.907607 + outer loop + vertex 1.65137 1.44961 2.53622 + vertex 1.64783 1.44834 2.53785 + vertex 1.6508 1.44585 2.53644 + endloop + endfacet + facet normal 0.420011 -0.0120017 0.90744 + outer loop + vertex 1.65137 1.44961 2.53622 + vertex 1.65078 1.45281 2.53654 + vertex 1.64783 1.44834 2.53785 + endloop + endfacet + facet normal 0.417165 -0.00973998 0.908779 + outer loop + vertex 1.65078 1.45281 2.53654 + vertex 1.64731 1.45344 2.53814 + vertex 1.64783 1.44834 2.53785 + endloop + endfacet + facet normal 0.418589 -0.000332579 0.908176 + outer loop + vertex 1.65078 1.45281 2.53654 + vertex 1.65066 1.45731 2.5366 + vertex 1.64731 1.45344 2.53814 + endloop + endfacet + facet normal 0.424246 -0.00629222 0.905525 + outer loop + vertex 1.64731 1.45344 2.53814 + vertex 1.65066 1.45731 2.5366 + vertex 1.6472 1.45835 2.53822 + endloop + endfacet + facet normal 0.426486 0.00276669 0.90449 + outer loop + vertex 1.65066 1.45731 2.5366 + vertex 1.65065 1.46222 2.53659 + vertex 1.6472 1.45835 2.53822 + endloop + endfacet + facet normal 0.432618 -0.00393118 0.901569 + outer loop + vertex 1.6472 1.45835 2.53822 + vertex 1.65065 1.46222 2.53659 + vertex 1.64721 1.46334 2.53824 + endloop + endfacet + facet normal 0.434654 0.00379055 0.90059 + outer loop + vertex 1.65065 1.46222 2.53659 + vertex 1.65064 1.46723 2.53657 + vertex 1.64721 1.46334 2.53824 + endloop + endfacet + facet normal 0.440997 -0.00313242 0.897503 + outer loop + vertex 1.64721 1.46334 2.53824 + vertex 1.65064 1.46723 2.53657 + vertex 1.64725 1.46835 2.53824 + endloop + endfacet + facet normal 0.4428 0.00365195 0.896613 + outer loop + vertex 1.65064 1.46723 2.53657 + vertex 1.65064 1.47223 2.53655 + vertex 1.64725 1.46835 2.53824 + endloop + endfacet + facet normal 0.447907 -0.00191012 0.894078 + outer loop + vertex 1.64725 1.46835 2.53824 + vertex 1.65064 1.47223 2.53655 + vertex 1.64727 1.47335 2.53824 + endloop + endfacet + facet normal 0.448628 0.000799386 0.893718 + outer loop + vertex 1.65064 1.47223 2.53655 + vertex 1.65064 1.47723 2.53655 + vertex 1.64727 1.47335 2.53824 + endloop + endfacet + facet normal 0.452448 -0.00336343 0.891785 + outer loop + vertex 1.64727 1.47335 2.53824 + vertex 1.65064 1.47723 2.53655 + vertex 1.64729 1.47834 2.53825 + endloop + endfacet + facet normal 0.453567 0.000881627 0.891222 + outer loop + vertex 1.65064 1.47723 2.53655 + vertex 1.65063 1.48221 2.53655 + vertex 1.64729 1.47834 2.53825 + endloop + endfacet + facet normal 0.456634 -0.00245504 0.889651 + outer loop + vertex 1.64729 1.47834 2.53825 + vertex 1.65063 1.48221 2.53655 + vertex 1.6473 1.48331 2.53826 + endloop + endfacet + facet normal 0.457566 0.00108813 0.889175 + outer loop + vertex 1.65063 1.48221 2.53655 + vertex 1.65062 1.48719 2.53655 + vertex 1.6473 1.48331 2.53826 + endloop + endfacet + facet normal 0.460168 -0.00173115 0.88783 + outer loop + vertex 1.6473 1.48331 2.53826 + vertex 1.65062 1.48719 2.53655 + vertex 1.64731 1.48829 2.53826 + endloop + endfacet + facet normal 0.46184 0.00468389 0.886951 + outer loop + vertex 1.65062 1.48719 2.53655 + vertex 1.65062 1.49222 2.53652 + vertex 1.64731 1.48829 2.53826 + endloop + endfacet + facet normal 0.467841 -0.00176469 0.883811 + outer loop + vertex 1.64731 1.48829 2.53826 + vertex 1.65062 1.49222 2.53652 + vertex 1.64733 1.49331 2.53826 + endloop + endfacet + facet normal 0.469827 0.00597853 0.882738 + outer loop + vertex 1.65062 1.49222 2.53652 + vertex 1.65068 1.49739 2.53645 + vertex 1.64733 1.49331 2.53826 + endloop + endfacet + facet normal 0.479207 -0.00393894 0.877693 + outer loop + vertex 1.64733 1.49331 2.53826 + vertex 1.65068 1.49739 2.53645 + vertex 1.64735 1.49836 2.53828 + endloop + endfacet + facet normal 0.479321 -0.00342732 0.877633 + outer loop + vertex 1.65068 1.49739 2.53645 + vertex 1.65064 1.50256 2.53649 + vertex 1.64735 1.49836 2.53828 + endloop + endfacet + facet normal 0.479473 -0.00358161 0.877549 + outer loop + vertex 1.64735 1.49836 2.53828 + vertex 1.65064 1.50256 2.53649 + vertex 1.64732 1.50336 2.53831 + endloop + endfacet + facet normal 0.478695 -0.00769334 0.877948 + outer loop + vertex 1.65064 1.50256 2.53649 + vertex 1.6505 1.50745 2.53661 + vertex 1.64732 1.50336 2.53831 + endloop + endfacet + facet normal 0.468984 0.00204783 0.883204 + outer loop + vertex 1.64732 1.50336 2.53831 + vertex 1.6505 1.50745 2.53661 + vertex 1.6473 1.50832 2.53831 + endloop + endfacet + facet normal 0.470901 0.0112391 0.882115 + outer loop + vertex 1.6505 1.50745 2.53661 + vertex 1.65061 1.51235 2.53649 + vertex 1.6473 1.50832 2.53831 + endloop + endfacet + facet normal 0.475741 0.00611257 0.879564 + outer loop + vertex 1.6473 1.50832 2.53831 + vertex 1.65061 1.51235 2.53649 + vertex 1.64731 1.51331 2.53827 + endloop + endfacet + facet normal 0.475921 0.00691851 0.879461 + outer loop + vertex 1.65061 1.51235 2.53649 + vertex 1.65071 1.51748 2.5364 + vertex 1.64731 1.51331 2.53827 + endloop + endfacet + facet normal 0.479904 0.00272146 0.877317 + outer loop + vertex 1.64731 1.51331 2.53827 + vertex 1.65071 1.51748 2.5364 + vertex 1.6473 1.51833 2.53826 + endloop + endfacet + facet normal 0.478142 -0.00646277 0.878259 + outer loop + vertex 1.65071 1.51748 2.5364 + vertex 1.6506 1.52259 2.5365 + vertex 1.6473 1.51833 2.53826 + endloop + endfacet + facet normal 0.471122 0.000539483 0.882068 + outer loop + vertex 1.6473 1.51833 2.53826 + vertex 1.6506 1.52259 2.5365 + vertex 1.64728 1.52332 2.53827 + endloop + endfacet + facet normal 0.470839 -0.0011105 0.882218 + outer loop + vertex 1.6506 1.52259 2.5365 + vertex 1.65056 1.52759 2.53652 + vertex 1.64728 1.52332 2.53827 + endloop + endfacet + facet normal 0.467285 0.00238501 0.884103 + outer loop + vertex 1.64728 1.52332 2.53827 + vertex 1.65056 1.52759 2.53652 + vertex 1.64729 1.52829 2.53825 + endloop + endfacet + facet normal 0.467496 0.0036586 0.883988 + outer loop + vertex 1.65056 1.52759 2.53652 + vertex 1.65057 1.53258 2.5365 + vertex 1.64729 1.52829 2.53825 + endloop + endfacet + facet normal 0.465521 0.00558992 0.885019 + outer loop + vertex 1.64729 1.52829 2.53825 + vertex 1.65057 1.53258 2.5365 + vertex 1.6473 1.53329 2.53821 + endloop + endfacet + facet normal 0.46539 0.00480617 0.885093 + outer loop + vertex 1.65057 1.53258 2.5365 + vertex 1.65058 1.53759 2.53646 + vertex 1.6473 1.53329 2.53821 + endloop + endfacet + facet normal 0.468273 0.00199387 0.883581 + outer loop + vertex 1.6473 1.53329 2.53821 + vertex 1.65058 1.53759 2.53646 + vertex 1.6473 1.53831 2.5382 + endloop + endfacet + facet normal 0.467521 -0.00238907 0.883979 + outer loop + vertex 1.65058 1.53759 2.53646 + vertex 1.65056 1.54257 2.53649 + vertex 1.6473 1.53831 2.5382 + endloop + endfacet + facet normal 0.468243 -0.00309812 0.883594 + outer loop + vertex 1.6473 1.53831 2.5382 + vertex 1.65056 1.54257 2.53649 + vertex 1.6473 1.54331 2.53822 + endloop + endfacet + facet normal 0.467496 -0.00724724 0.883965 + outer loop + vertex 1.65056 1.54257 2.53649 + vertex 1.65051 1.54735 2.53655 + vertex 1.6473 1.54331 2.53822 + endloop + endfacet + facet normal 0.46367 -0.003355 0.886002 + outer loop + vertex 1.6473 1.54331 2.53822 + vertex 1.65051 1.54735 2.53655 + vertex 1.64732 1.54827 2.53822 + endloop + endfacet + facet normal 0.464814 0.00169566 0.885407 + outer loop + vertex 1.65051 1.54735 2.53655 + vertex 1.65063 1.55208 2.53648 + vertex 1.64732 1.54827 2.53822 + endloop + endfacet + facet normal 0.467526 -0.00130893 0.883979 + outer loop + vertex 1.64732 1.54827 2.53822 + vertex 1.65063 1.55208 2.53648 + vertex 1.64737 1.55324 2.53821 + endloop + endfacet + facet normal 0.468357 0.00170162 0.883538 + outer loop + vertex 1.65063 1.55208 2.53648 + vertex 1.65072 1.55704 2.53643 + vertex 1.64737 1.55324 2.53821 + endloop + endfacet + facet normal 0.471463 -0.00181617 0.881884 + outer loop + vertex 1.64737 1.55324 2.53821 + vertex 1.65072 1.55704 2.53643 + vertex 1.64729 1.55823 2.53826 + endloop + endfacet + facet normal 0.469849 -0.00768624 0.882714 + outer loop + vertex 1.65072 1.55704 2.53643 + vertex 1.65047 1.56208 2.5366 + vertex 1.64729 1.55823 2.53826 + endloop + endfacet + facet normal 0.460289 0.00240592 0.887766 + outer loop + vertex 1.64729 1.55823 2.53826 + vertex 1.65047 1.56208 2.5366 + vertex 1.64699 1.56311 2.5384 + endloop + endfacet + facet normal 0.457875 -0.00781669 0.888982 + outer loop + vertex 1.65047 1.56208 2.5366 + vertex 1.65 1.56738 2.53689 + vertex 1.64699 1.56311 2.5384 + endloop + endfacet + facet normal 0.43889 0.00893016 0.898497 + outer loop + vertex 1.64699 1.56311 2.5384 + vertex 1.65 1.56738 2.53689 + vertex 1.64641 1.56716 2.53864 + endloop + endfacet + facet normal 0.531073 -0.00303019 0.847321 + outer loop + vertex 1.65306 1.56964 2.53509 + vertex 1.65421 1.57384 2.53438 + vertex 1.65129 1.57174 2.53621 + endloop + endfacet + facet normal 0.517221 -0.0191522 0.855638 + outer loop + vertex 1.65129 1.57174 2.53621 + vertex 1.65 1.56738 2.53689 + vertex 1.65306 1.56964 2.53509 + endloop + endfacet + facet normal 0.448982 0.0068983 0.893514 + outer loop + vertex 1.65129 1.57174 2.53621 + vertex 1.64776 1.57191 2.53798 + vertex 1.65 1.56738 2.53689 + endloop + endfacet + facet normal 0.439304 0.000949925 0.898338 + outer loop + vertex 1.64776 1.57191 2.53798 + vertex 1.64641 1.56716 2.53864 + vertex 1.65 1.56738 2.53689 + endloop + endfacet + facet normal 0.521799 -0.0304627 0.852524 + outer loop + vertex 1.65421 1.57384 2.53438 + vertex 1.65389 1.57863 2.53475 + vertex 1.65114 1.57564 2.53633 + endloop + endfacet + facet normal 0.532472 -0.00575377 0.846428 + outer loop + vertex 1.65129 1.57174 2.53621 + vertex 1.65421 1.57384 2.53438 + vertex 1.65114 1.57564 2.53633 + endloop + endfacet + facet normal 0.448296 -0.0103409 0.893825 + outer loop + vertex 1.65114 1.57564 2.53633 + vertex 1.64776 1.57191 2.53798 + vertex 1.65129 1.57174 2.53621 + endloop + endfacet + facet normal 0.438388 0.000820436 0.898785 + outer loop + vertex 1.64799 1.57807 2.53786 + vertex 1.64776 1.57191 2.53798 + vertex 1.65114 1.57564 2.53633 + endloop + endfacet + facet normal 0.519448 -0.0274899 0.85406 + outer loop + vertex 1.65389 1.57863 2.53475 + vertex 1.65148 1.57941 2.53624 + vertex 1.65114 1.57564 2.53633 + endloop + endfacet + facet normal 0.42654 -0.0180405 0.904289 + outer loop + vertex 1.65148 1.57941 2.53624 + vertex 1.64799 1.57807 2.53786 + vertex 1.65114 1.57564 2.53633 + endloop + endfacet + facet normal 0.424355 -0.0109956 0.905429 + outer loop + vertex 1.65148 1.57941 2.53624 + vertex 1.65077 1.58261 2.53662 + vertex 1.64799 1.57807 2.53786 + endloop + endfacet + facet normal 0.400288 0.00669398 0.916365 + outer loop + vertex 1.65077 1.58261 2.53662 + vertex 1.64723 1.58328 2.53816 + vertex 1.64799 1.57807 2.53786 + endloop + endfacet + facet normal 0.400686 0.00927447 0.916169 + outer loop + vertex 1.65077 1.58261 2.53662 + vertex 1.65044 1.58712 2.53672 + vertex 1.64723 1.58328 2.53816 + endloop + endfacet + facet normal 0.392472 0.017412 0.919599 + outer loop + vertex 1.64723 1.58328 2.53816 + vertex 1.65044 1.58712 2.53672 + vertex 1.6468 1.58805 2.53825 + endloop + endfacet + facet normal 0.390846 0.00975873 0.920404 + outer loop + vertex 1.65044 1.58712 2.53672 + vertex 1.64998 1.59232 2.53686 + vertex 1.6468 1.58805 2.53825 + endloop + endfacet + facet normal 0.374624 0.0239298 0.926868 + outer loop + vertex 1.6468 1.58805 2.53825 + vertex 1.64998 1.59232 2.53686 + vertex 1.64615 1.59206 2.53841 + endloop + endfacet + facet normal 0.482313 0.021946 0.875724 + outer loop + vertex 1.65326 1.5946 2.53518 + vertex 1.65443 1.5988 2.53443 + vertex 1.65135 1.59671 2.53618 + endloop + endfacet + facet normal 0.458265 -0.00595489 0.888795 + outer loop + vertex 1.65135 1.59671 2.53618 + vertex 1.64998 1.59232 2.53686 + vertex 1.65326 1.5946 2.53518 + endloop + endfacet + facet normal 0.385168 0.0222693 0.922578 + outer loop + vertex 1.65135 1.59671 2.53618 + vertex 1.64751 1.59687 2.53778 + vertex 1.64998 1.59232 2.53686 + endloop + endfacet + facet normal 0.375156 0.0159682 0.926824 + outer loop + vertex 1.64751 1.59687 2.53778 + vertex 1.64615 1.59206 2.53841 + vertex 1.64998 1.59232 2.53686 + endloop + endfacet + facet normal 0.477183 -0.0120805 0.878721 + outer loop + vertex 1.65443 1.5988 2.53443 + vertex 1.65396 1.60358 2.53475 + vertex 1.65114 1.60059 2.53624 + endloop + endfacet + facet normal 0.487359 0.0123699 0.873114 + outer loop + vertex 1.65135 1.59671 2.53618 + vertex 1.65443 1.5988 2.53443 + vertex 1.65114 1.60059 2.53624 + endloop + endfacet + facet normal 0.38466 0.00588465 0.923039 + outer loop + vertex 1.65114 1.60059 2.53624 + vertex 1.64751 1.59687 2.53778 + vertex 1.65135 1.59671 2.53618 + endloop + endfacet + facet normal 0.380296 0.0108778 0.924801 + outer loop + vertex 1.64776 1.60293 2.5376 + vertex 1.64751 1.59687 2.53778 + vertex 1.65114 1.60059 2.53624 + endloop + endfacet + facet normal 0.476809 -0.0116231 0.87893 + outer loop + vertex 1.65396 1.60358 2.53475 + vertex 1.65139 1.6043 2.53615 + vertex 1.65114 1.60059 2.53624 + endloop + endfacet + facet normal 0.371852 -0.00333237 0.928286 + outer loop + vertex 1.65139 1.6043 2.53615 + vertex 1.64776 1.60293 2.5376 + vertex 1.65114 1.60059 2.53624 + endloop + endfacet + facet normal 0.369128 0.00502795 0.929365 + outer loop + vertex 1.65139 1.6043 2.53615 + vertex 1.65047 1.60736 2.5365 + vertex 1.64776 1.60293 2.5376 + endloop + endfacet + facet normal 0.402719 0.0420325 0.914358 + outer loop + vertex 1.65276 1.6392 2.53404 + vertex 1.65225 1.64461 2.53402 + vertex 1.64905 1.64044 2.53562 + endloop + endfacet + facet normal 0.33016 0.0531508 0.942427 + outer loop + vertex 1.64498 1.64198 2.53696 + vertex 1.64569 1.63678 2.537 + vertex 1.64905 1.64044 2.53562 + endloop + endfacet + facet normal 0.394655 0.0494339 0.917499 + outer loop + vertex 1.6485 1.64445 2.53564 + vertex 1.64905 1.64044 2.53562 + vertex 1.65225 1.64461 2.53402 + endloop + endfacet + facet normal 0.395249 0.038217 0.917779 + outer loop + vertex 1.6485 1.64445 2.53564 + vertex 1.65225 1.64461 2.53402 + vertex 1.64967 1.64891 2.53495 + endloop + endfacet + facet normal 0.401943 0.0429092 0.914659 + outer loop + vertex 1.64967 1.64891 2.53495 + vertex 1.65225 1.64461 2.53402 + vertex 1.65336 1.64924 2.53331 + endloop + endfacet + facet normal 0.325837 0.0397671 0.944589 + outer loop + vertex 1.64905 1.64044 2.53562 + vertex 1.6485 1.64445 2.53564 + vertex 1.64498 1.64198 2.53696 + endloop + endfacet + facet normal 0.402893 0.0323979 0.914674 + outer loop + vertex 1.65336 1.64924 2.53331 + vertex 1.65265 1.65322 2.53348 + vertex 1.64967 1.64891 2.53495 + endloop + endfacet + facet normal 0.381218 0.0502508 0.923119 + outer loop + vertex 1.64967 1.64891 2.53495 + vertex 1.65265 1.65322 2.53348 + vertex 1.64892 1.65419 2.53497 + endloop + endfacet + facet normal 0.378234 0.0357988 0.925018 + outer loop + vertex 1.65265 1.65322 2.53348 + vertex 1.65205 1.65798 2.53354 + vertex 1.64892 1.65419 2.53497 + endloop + endfacet + facet normal 0.361971 0.0514124 0.93077 + outer loop + vertex 1.64892 1.65419 2.53497 + vertex 1.65205 1.65798 2.53354 + vertex 1.64842 1.65903 2.5349 + endloop + endfacet + facet normal 0.359072 0.0392732 0.932483 + outer loop + vertex 1.65205 1.65798 2.53354 + vertex 1.6513 1.66201 2.53366 + vertex 1.64842 1.65903 2.5349 + endloop + endfacet + facet normal 0.283473 0.223522 0.932567 + outer loop + vertex 1.64917 1.984 2.48613 + vertex 1.65353 1.98352 2.48492 + vertex 1.64922 1.9881 2.48514 + endloop + endfacet + facet normal 0.368299 0.526866 0.766008 + outer loop + vertex 1.6538 2.08489 2.45621 + vertex 1.65154 2.08822 2.455 + vertex 1.65017 2.08668 2.45672 + endloop + endfacet + facet normal 0.328694 0.424167 0.843826 + outer loop + vertex 1.65017 2.08668 2.45672 + vertex 1.65107 2.08342 2.45801 + vertex 1.6538 2.08489 2.45621 + endloop + endfacet + facet normal 0.319474 0.423205 0.847841 + outer loop + vertex 1.65017 2.08668 2.45672 + vertex 1.64664 2.08741 2.45769 + vertex 1.65107 2.08342 2.45801 + endloop + endfacet + facet normal 0.305308 0.408461 0.860202 + outer loop + vertex 1.64664 2.08741 2.45769 + vertex 1.64698 2.08274 2.45978 + vertex 1.65107 2.08342 2.45801 + endloop + endfacet + facet normal 0.366671 0.528179 0.765885 + outer loop + vertex 1.6485 2.08894 2.45596 + vertex 1.65017 2.08668 2.45672 + vertex 1.65154 2.08822 2.455 + endloop + endfacet + facet normal 0.365896 0.615134 0.698377 + outer loop + vertex 1.6485 2.08894 2.45596 + vertex 1.65154 2.08822 2.455 + vertex 1.64912 2.09061 2.45417 + endloop + endfacet + facet normal 0.386157 0.62787 0.675768 + outer loop + vertex 1.64912 2.09061 2.45417 + vertex 1.65154 2.08822 2.455 + vertex 1.65225 2.09048 2.4525 + endloop + endfacet + facet normal 0.323389 0.507336 0.798768 + outer loop + vertex 1.65017 2.08668 2.45672 + vertex 1.6485 2.08894 2.45596 + vertex 1.64664 2.08741 2.45769 + endloop + endfacet + facet normal 0.411227 0.632743 0.656146 + outer loop + vertex 1.65297 2.09476 2.44593 + vertex 1.65121 2.09708 2.44479 + vertex 1.64901 2.09595 2.44726 + endloop + endfacet + facet normal 0.424379 0.738441 0.52403 + outer loop + vertex 1.64901 2.09595 2.44726 + vertex 1.64608 2.0963 2.44913 + vertex 1.6483 2.09355 2.45122 + endloop + endfacet + facet normal 0.402718 0.748771 0.526461 + outer loop + vertex 1.64901 2.09595 2.44726 + vertex 1.6483 2.09355 2.45122 + vertex 1.65297 2.09476 2.44593 + endloop + endfacet + facet normal 0.351824 0.796092 0.4924 + outer loop + vertex 1.65297 2.09476 2.44593 + vertex 1.6483 2.09355 2.45122 + vertex 1.65375 2.09233 2.44929 + endloop + endfacet + facet normal 0.353759 0.710091 0.60879 + outer loop + vertex 1.65225 2.09048 2.4525 + vertex 1.6483 2.09355 2.45122 + vertex 1.64912 2.09061 2.45417 + endloop + endfacet + facet normal 0.36869 0.72038 0.587469 + outer loop + vertex 1.65375 2.09233 2.44929 + vertex 1.6483 2.09355 2.45122 + vertex 1.65225 2.09048 2.4525 + endloop + endfacet + facet normal 0.446391 0.593541 0.66966 + outer loop + vertex 1.65121 2.09708 2.44479 + vertex 1.64731 2.09872 2.44594 + vertex 1.64901 2.09595 2.44726 + endloop + endfacet + facet normal 0.186492 -0.228694 0.955468 + outer loop + vertex 1.65121 2.09708 2.44479 + vertex 1.655 2.10106 2.445 + vertex 1.64731 2.09872 2.44594 + endloop + endfacet + facet normal 0.0467365 0.236007 0.970627 + outer loop + vertex 1.655 2.10106 2.445 + vertex 1.65 2.10205 2.445 + vertex 1.64731 2.09872 2.44594 + endloop + endfacet + facet normal 0.481302 0.600286 0.638753 + outer loop + vertex 1.64901 2.09595 2.44726 + vertex 1.64731 2.09872 2.44594 + vertex 1.64608 2.0963 2.44913 + endloop + endfacet + facet normal 0.295037 -0.875273 0.38321 + outer loop + vertex 1.659 0.935 2.445 + vertex 1.66 0.933148 2.44 + vertex 1.66 0.935 2.44423 + endloop + endfacet + facet normal 0.336006 -0.859352 0.385506 + outer loop + vertex 1.659 0.935 2.445 + vertex 1.655 0.933436 2.445 + vertex 1.66 0.933148 2.44 + endloop + endfacet + facet normal 0.334448 -0.860624 0.38402 + outer loop + vertex 1.655 0.933436 2.445 + vertex 1.655 0.931205 2.44 + vertex 1.66 0.933148 2.44 + endloop + endfacet + facet normal -0.262473 0.671286 0.693169 + outer loop + vertex 1.659 0.935 2.445 + vertex 1.65455 0.933849 2.44443 + vertex 1.655 0.933436 2.445 + endloop + endfacet + facet normal -0.203288 0.329439 0.922032 + outer loop + vertex 1.65455 0.933849 2.44443 + vertex 1.659 0.935 2.445 + vertex 1.66 0.935617 2.445 + endloop + endfacet + facet normal 0.219415 -0.837211 0.500935 + outer loop + vertex 1.65455 0.933849 2.44443 + vertex 1.66 0.935617 2.445 + vertex 1.65258 0.93489 2.44704 + endloop + endfacet + facet normal 0.264432 -0.611975 0.745361 + outer loop + vertex 1.65258 0.93489 2.44704 + vertex 1.66 0.935617 2.445 + vertex 1.65694 0.937023 2.44724 + endloop + endfacet + facet normal 0.308401 -0.752128 0.582403 + outer loop + vertex 1.65575 0.939744 2.45139 + vertex 1.65694 0.937023 2.44724 + vertex 1.65858 0.938849 2.44873 + endloop + endfacet + facet normal 0.370491 -0.724041 0.581809 + outer loop + vertex 1.65575 0.939744 2.45139 + vertex 1.65213 0.937295 2.45064 + vertex 1.65694 0.937023 2.44724 + endloop + endfacet + facet normal 0.345979 -0.760103 0.550037 + outer loop + vertex 1.65213 0.937295 2.45064 + vertex 1.65258 0.93489 2.44704 + vertex 1.65694 0.937023 2.44724 + endloop + endfacet + facet normal 0.357493 -0.711759 0.604647 + outer loop + vertex 1.65575 0.939744 2.45139 + vertex 1.65194 0.939642 2.45352 + vertex 1.65213 0.937295 2.45064 + endloop + endfacet + facet normal 0.3381 -0.721841 0.60385 + outer loop + vertex 1.65858 0.938849 2.44873 + vertex 1.65927 0.940683 2.45054 + vertex 1.65575 0.939744 2.45139 + endloop + endfacet + facet normal 0.349267 -0.620629 0.70202 + outer loop + vertex 1.65194 0.939642 2.45352 + vertex 1.65424 0.942393 2.4548 + vertex 1.65047 0.941497 2.45589 + endloop + endfacet + facet normal 0.389442 -0.636949 0.665305 + outer loop + vertex 1.65575 0.939744 2.45139 + vertex 1.65424 0.942393 2.4548 + vertex 1.65194 0.939642 2.45352 + endloop + endfacet + facet normal 0.358423 -0.654784 0.665425 + outer loop + vertex 1.65575 0.939744 2.45139 + vertex 1.65906 0.943681 2.45348 + vertex 1.65424 0.942393 2.4548 + endloop + endfacet + facet normal 0.337391 -0.646902 0.683875 + outer loop + vertex 1.65575 0.939744 2.45139 + vertex 1.65927 0.940683 2.45054 + vertex 1.65906 0.943681 2.45348 + endloop + endfacet + facet normal 0.348255 -0.531776 0.771967 + outer loop + vertex 1.65424 0.942393 2.4548 + vertex 1.65322 0.945159 2.45717 + vertex 1.65047 0.941497 2.45589 + endloop + endfacet + facet normal 0.356238 -0.566919 0.742764 + outer loop + vertex 1.65906 0.943681 2.45348 + vertex 1.65648 0.9454 2.45602 + vertex 1.65424 0.942393 2.4548 + endloop + endfacet + facet normal 0.313041 -0.547993 0.775699 + outer loop + vertex 1.65648 0.9454 2.45602 + vertex 1.65322 0.945159 2.45717 + vertex 1.65424 0.942393 2.4548 + endloop + endfacet + facet normal 0.32553 -0.44918 0.832026 + outer loop + vertex 1.65648 0.9454 2.45602 + vertex 1.65761 0.949068 2.45756 + vertex 1.65322 0.945159 2.45717 + endloop + endfacet + facet normal 0.289029 -0.411371 0.864428 + outer loop + vertex 1.65761 0.949068 2.45756 + vertex 1.65324 0.949054 2.45902 + vertex 1.65322 0.945159 2.45717 + endloop + endfacet + facet normal 0.280467 -0.20975 0.936666 + outer loop + vertex 1.65342 1.08772 2.49544 + vertex 1.65098 1.08853 2.49635 + vertex 1.65063 1.0854 2.49575 + endloop + endfacet + facet normal 0.281087 -0.208083 0.936852 + outer loop + vertex 1.65503 1.09144 2.49578 + vertex 1.65098 1.08853 2.49635 + vertex 1.65342 1.08772 2.49544 + endloop + endfacet + facet normal 0.342791 -0.0680655 0.936943 + outer loop + vertex 1.65596 1.29745 2.52688 + vertex 1.65612 1.30244 2.52718 + vertex 1.65214 1.29826 2.52834 + endloop + endfacet + facet normal 0.358479 -0.0850157 0.929659 + outer loop + vertex 1.65214 1.29826 2.52834 + vertex 1.65612 1.30244 2.52718 + vertex 1.65238 1.30349 2.52872 + endloop + endfacet + facet normal 0.362411 -0.0704886 0.929349 + outer loop + vertex 1.65612 1.30244 2.52718 + vertex 1.6563 1.30751 2.5275 + vertex 1.65238 1.30349 2.52872 + endloop + endfacet + facet normal 0.379365 -0.0895914 0.920899 + outer loop + vertex 1.65238 1.30349 2.52872 + vertex 1.6563 1.30751 2.5275 + vertex 1.6527 1.30864 2.52909 + endloop + endfacet + facet normal 0.383417 -0.0759674 0.920446 + outer loop + vertex 1.6563 1.30751 2.5275 + vertex 1.65652 1.31259 2.52783 + vertex 1.6527 1.30864 2.52909 + endloop + endfacet + facet normal 0.392462 -0.0862352 0.915717 + outer loop + vertex 1.6527 1.30864 2.52909 + vertex 1.65652 1.31259 2.52783 + vertex 1.6526 1.31381 2.52962 + endloop + endfacet + facet normal 0.393025 -0.0843426 0.915652 + outer loop + vertex 1.65652 1.31259 2.52783 + vertex 1.65703 1.31779 2.52809 + vertex 1.6526 1.31381 2.52962 + endloop + endfacet + facet normal 0.410162 -0.107275 0.905682 + outer loop + vertex 1.6526 1.31381 2.52962 + vertex 1.65703 1.31779 2.52809 + vertex 1.65375 1.31943 2.52976 + endloop + endfacet + facet normal 0.415502 -0.0954989 0.904565 + outer loop + vertex 1.65703 1.31779 2.52809 + vertex 1.65801 1.32352 2.52824 + vertex 1.65375 1.31943 2.52976 + endloop + endfacet + facet normal 0.405527 -0.0408732 0.913169 + outer loop + vertex 1.65606 1.36729 2.53196 + vertex 1.65613 1.37224 2.53215 + vertex 1.65246 1.36848 2.53361 + endloop + endfacet + facet normal 0.410014 -0.0461244 0.910912 + outer loop + vertex 1.65246 1.36848 2.53361 + vertex 1.65613 1.37224 2.53215 + vertex 1.65251 1.37343 2.53383 + endloop + endfacet + facet normal 0.41324 -0.0349375 0.909952 + outer loop + vertex 1.65613 1.37224 2.53215 + vertex 1.65615 1.3773 2.53233 + vertex 1.65251 1.37343 2.53383 + endloop + endfacet + facet normal 0.419882 -0.0424827 0.906584 + outer loop + vertex 1.65251 1.37343 2.53383 + vertex 1.65615 1.3773 2.53233 + vertex 1.65219 1.37868 2.53423 + endloop + endfacet + facet normal 0.422782 -0.0328416 0.905636 + outer loop + vertex 1.65615 1.3773 2.53233 + vertex 1.65633 1.38255 2.53244 + vertex 1.65219 1.37868 2.53423 + endloop + endfacet + facet normal 0.435321 -0.0493176 0.898924 + outer loop + vertex 1.65219 1.37868 2.53423 + vertex 1.65633 1.38255 2.53244 + vertex 1.653 1.38442 2.53415 + endloop + endfacet + facet normal 0.442959 -0.0329353 0.895937 + outer loop + vertex 1.65633 1.38255 2.53244 + vertex 1.65659 1.3878 2.5325 + vertex 1.653 1.38442 2.53415 + endloop + endfacet + facet normal 0.449399 -0.0415323 0.892365 + outer loop + vertex 1.653 1.38442 2.53415 + vertex 1.65659 1.3878 2.5325 + vertex 1.65333 1.38962 2.53423 + endloop + endfacet + facet normal 0.456787 -0.0253403 0.889215 + outer loop + vertex 1.65659 1.3878 2.5325 + vertex 1.65669 1.39287 2.53259 + vertex 1.65333 1.38962 2.53423 + endloop + endfacet + facet normal 0.462049 -0.0322822 0.886267 + outer loop + vertex 1.65333 1.38962 2.53423 + vertex 1.65669 1.39287 2.53259 + vertex 1.65347 1.39468 2.53434 + endloop + endfacet + facet normal 0.469525 -0.0156235 0.882781 + outer loop + vertex 1.65669 1.39287 2.53259 + vertex 1.65672 1.39788 2.53267 + vertex 1.65347 1.39468 2.53434 + endloop + endfacet + facet normal 0.475127 -0.0229569 0.879618 + outer loop + vertex 1.65347 1.39468 2.53434 + vertex 1.65672 1.39788 2.53267 + vertex 1.65352 1.39968 2.53444 + endloop + endfacet + facet normal 0.480658 -0.0103942 0.876846 + outer loop + vertex 1.65672 1.39788 2.53267 + vertex 1.6567 1.40292 2.53274 + vertex 1.65352 1.39968 2.53444 + endloop + endfacet + facet normal 0.486192 -0.0175047 0.873677 + outer loop + vertex 1.65352 1.39968 2.53444 + vertex 1.6567 1.40292 2.53274 + vertex 1.65357 1.40464 2.53451 + endloop + endfacet + facet normal 0.488071 -0.0131034 0.872706 + outer loop + vertex 1.6567 1.40292 2.53274 + vertex 1.65673 1.40793 2.5328 + vertex 1.65357 1.40464 2.53451 + endloop + endfacet + facet normal 0.494605 -0.0213819 0.868855 + outer loop + vertex 1.65357 1.40464 2.53451 + vertex 1.65673 1.40793 2.5328 + vertex 1.65369 1.40958 2.53457 + endloop + endfacet + facet normal 0.495404 -0.0194662 0.868445 + outer loop + vertex 1.65673 1.40793 2.5328 + vertex 1.65681 1.4129 2.53287 + vertex 1.65369 1.40958 2.53457 + endloop + endfacet + facet normal 0.503049 -0.0290401 0.86377 + outer loop + vertex 1.65369 1.40958 2.53457 + vertex 1.65681 1.4129 2.53287 + vertex 1.65382 1.41444 2.53465 + endloop + endfacet + facet normal 0.505931 -0.0217426 0.8623 + outer loop + vertex 1.65681 1.4129 2.53287 + vertex 1.65675 1.41791 2.53303 + vertex 1.65382 1.41444 2.53465 + endloop + endfacet + facet normal 0.512445 -0.0291439 0.858225 + outer loop + vertex 1.65382 1.41444 2.53465 + vertex 1.65675 1.41791 2.53303 + vertex 1.65376 1.41898 2.53485 + endloop + endfacet + facet normal 0.444199 -0.0326757 0.895332 + outer loop + vertex 1.65302 1.42207 2.53533 + vertex 1.65114 1.41955 2.53617 + vertex 1.65376 1.41898 2.53485 + endloop + endfacet + facet normal 0.51179 -0.0109175 0.859041 + outer loop + vertex 1.65302 1.42207 2.53533 + vertex 1.65376 1.41898 2.53485 + vertex 1.6561 1.42363 2.53351 + endloop + endfacet + facet normal 0.516529 -0.0141272 0.856153 + outer loop + vertex 1.6561 1.42363 2.53351 + vertex 1.65376 1.41898 2.53485 + vertex 1.65675 1.41791 2.53303 + endloop + endfacet + facet normal 0.40934 -0.000942454 0.912382 + outer loop + vertex 1.65302 1.42207 2.53533 + vertex 1.65003 1.42287 2.53667 + vertex 1.65114 1.41955 2.53617 + endloop + endfacet + facet normal 0.508358 -0.001717 0.861144 + outer loop + vertex 1.65311 1.42493 2.53528 + vertex 1.65302 1.42207 2.53533 + vertex 1.6561 1.42363 2.53351 + endloop + endfacet + facet normal 0.508252 -0.00204041 0.861206 + outer loop + vertex 1.65311 1.42493 2.53528 + vertex 1.6561 1.42363 2.53351 + vertex 1.65435 1.42893 2.53455 + endloop + endfacet + facet normal 0.524195 0.00509034 0.851583 + outer loop + vertex 1.65435 1.42893 2.53455 + vertex 1.6561 1.42363 2.53351 + vertex 1.65746 1.42855 2.53264 + endloop + endfacet + facet normal 0.410057 0.00228481 0.912057 + outer loop + vertex 1.65302 1.42207 2.53533 + vertex 1.65311 1.42493 2.53528 + vertex 1.65003 1.42287 2.53667 + endloop + endfacet + facet normal 0.524153 0.0046064 0.851612 + outer loop + vertex 1.65746 1.42855 2.53264 + vertex 1.65704 1.43281 2.53288 + vertex 1.65435 1.42893 2.53455 + endloop + endfacet + facet normal 0.517394 0.0110417 0.855676 + outer loop + vertex 1.65435 1.42893 2.53455 + vertex 1.65704 1.43281 2.53288 + vertex 1.65395 1.43437 2.53473 + endloop + endfacet + facet normal 0.51608 0.00745534 0.856508 + outer loop + vertex 1.65704 1.43281 2.53288 + vertex 1.65681 1.43778 2.53297 + vertex 1.65395 1.43437 2.53473 + endloop + endfacet + facet normal 0.518847 0.00428172 0.854856 + outer loop + vertex 1.65395 1.43437 2.53473 + vertex 1.65681 1.43778 2.53297 + vertex 1.65378 1.43946 2.53481 + endloop + endfacet + facet normal 0.518238 0.00276639 0.855232 + outer loop + vertex 1.65681 1.43778 2.53297 + vertex 1.65673 1.44282 2.53301 + vertex 1.65378 1.43946 2.53481 + endloop + endfacet + facet normal 0.524017 -0.00419649 0.851697 + outer loop + vertex 1.65378 1.43946 2.53481 + vertex 1.65673 1.44282 2.53301 + vertex 1.65378 1.44438 2.53483 + endloop + endfacet + facet normal 0.525558 -0.000180679 0.850758 + outer loop + vertex 1.65673 1.44282 2.53301 + vertex 1.65665 1.44783 2.53306 + vertex 1.65378 1.44438 2.53483 + endloop + endfacet + facet normal 0.533154 -0.00892286 0.845971 + outer loop + vertex 1.65378 1.44438 2.53483 + vertex 1.65665 1.44783 2.53306 + vertex 1.65378 1.44889 2.53487 + endloop + endfacet + facet normal 0.485071 -0.0139596 0.874363 + outer loop + vertex 1.65328 1.45215 2.53521 + vertex 1.65137 1.44961 2.53622 + vertex 1.65378 1.44889 2.53487 + endloop + endfacet + facet normal 0.53723 -0.00278948 0.843431 + outer loop + vertex 1.65328 1.45215 2.53521 + vertex 1.65378 1.44889 2.53487 + vertex 1.65622 1.45315 2.53334 + endloop + endfacet + facet normal 0.535212 -0.00117055 0.844717 + outer loop + vertex 1.65622 1.45315 2.53334 + vertex 1.65378 1.44889 2.53487 + vertex 1.65665 1.44783 2.53306 + endloop + endfacet + facet normal 0.47078 -4.16755e-05 0.882251 + outer loop + vertex 1.65328 1.45215 2.53521 + vertex 1.65078 1.45281 2.53654 + vertex 1.65137 1.44961 2.53622 + endloop + endfacet + facet normal 0.540861 0.00901146 0.841064 + outer loop + vertex 1.65622 1.45315 2.53334 + vertex 1.65662 1.45882 2.53302 + vertex 1.65368 1.45596 2.53494 + endloop + endfacet + facet normal 0.535902 0.00267522 0.844276 + outer loop + vertex 1.65328 1.45215 2.53521 + vertex 1.65622 1.45315 2.53334 + vertex 1.65368 1.45596 2.53494 + endloop + endfacet + facet normal 0.473185 0.0117735 0.880884 + outer loop + vertex 1.65368 1.45596 2.53494 + vertex 1.65078 1.45281 2.53654 + vertex 1.65328 1.45215 2.53521 + endloop + endfacet + facet normal 0.481672 0.00161967 0.87635 + outer loop + vertex 1.65066 1.45731 2.5366 + vertex 1.65078 1.45281 2.53654 + vertex 1.65368 1.45596 2.53494 + endloop + endfacet + facet normal 0.546102 0.0165985 0.837554 + outer loop + vertex 1.65662 1.45882 2.53302 + vertex 1.65665 1.46398 2.5329 + vertex 1.65379 1.46084 2.53482 + endloop + endfacet + facet normal 0.541706 0.0077868 0.840532 + outer loop + vertex 1.65368 1.45596 2.53494 + vertex 1.65662 1.45882 2.53302 + vertex 1.65379 1.46084 2.53482 + endloop + endfacet + facet normal 0.484512 0.00991797 0.874728 + outer loop + vertex 1.65379 1.46084 2.53482 + vertex 1.65066 1.45731 2.5366 + vertex 1.65368 1.45596 2.53494 + endloop + endfacet + facet normal 0.490569 0.00287055 0.871397 + outer loop + vertex 1.65065 1.46222 2.53659 + vertex 1.65066 1.45731 2.5366 + vertex 1.65379 1.46084 2.53482 + endloop + endfacet + facet normal 0.553873 0.0210448 0.832335 + outer loop + vertex 1.65665 1.46398 2.5329 + vertex 1.65655 1.46901 2.53283 + vertex 1.65378 1.46586 2.53476 + endloop + endfacet + facet normal 0.549745 0.0118747 0.835248 + outer loop + vertex 1.65379 1.46084 2.53482 + vertex 1.65665 1.46398 2.5329 + vertex 1.65378 1.46586 2.53476 + endloop + endfacet + facet normal 0.493629 0.0121274 0.869588 + outer loop + vertex 1.65378 1.46586 2.53476 + vertex 1.65065 1.46222 2.53659 + vertex 1.65379 1.46084 2.53482 + endloop + endfacet + facet normal 0.500981 0.0037359 0.86545 + outer loop + vertex 1.65064 1.46723 2.53657 + vertex 1.65065 1.46222 2.53659 + vertex 1.65378 1.46586 2.53476 + endloop + endfacet + facet normal 0.563056 0.0176294 0.82623 + outer loop + vertex 1.65655 1.46901 2.53283 + vertex 1.65646 1.474 2.53279 + vertex 1.65372 1.47088 2.53472 + endloop + endfacet + facet normal 0.560695 0.012331 0.827931 + outer loop + vertex 1.65378 1.46586 2.53476 + vertex 1.65655 1.46901 2.53283 + vertex 1.65372 1.47088 2.53472 + endloop + endfacet + facet normal 0.503651 0.0120129 0.863824 + outer loop + vertex 1.65372 1.47088 2.53472 + vertex 1.65064 1.46723 2.53657 + vertex 1.65378 1.46586 2.53476 + endloop + endfacet + facet normal 0.511022 0.00363904 0.85956 + outer loop + vertex 1.65064 1.47223 2.53655 + vertex 1.65064 1.46723 2.53657 + vertex 1.65372 1.47088 2.53472 + endloop + endfacet + facet normal 0.570241 0.0113069 0.8214 + outer loop + vertex 1.65646 1.474 2.53279 + vertex 1.65641 1.47898 2.53276 + vertex 1.65368 1.47587 2.5347 + endloop + endfacet + facet normal 0.569408 0.0094476 0.822001 + outer loop + vertex 1.65372 1.47088 2.53472 + vertex 1.65646 1.474 2.53279 + vertex 1.65368 1.47587 2.5347 + endloop + endfacet + facet normal 0.512786 0.00912359 0.858468 + outer loop + vertex 1.65368 1.47587 2.5347 + vertex 1.65064 1.47223 2.53655 + vertex 1.65372 1.47088 2.53472 + endloop + endfacet + facet normal 0.520111 0.000761769 0.854098 + outer loop + vertex 1.65064 1.47723 2.53655 + vertex 1.65064 1.47223 2.53655 + vertex 1.65368 1.47587 2.5347 + endloop + endfacet + facet normal 0.575601 0.00691968 0.817701 + outer loop + vertex 1.65641 1.47898 2.53276 + vertex 1.65637 1.48398 2.53274 + vertex 1.65365 1.48085 2.53469 + endloop + endfacet + facet normal 0.574865 0.00528869 0.818231 + outer loop + vertex 1.65368 1.47587 2.5347 + vertex 1.65641 1.47898 2.53276 + vertex 1.65365 1.48085 2.53469 + endloop + endfacet + facet normal 0.521505 0.00504714 0.853233 + outer loop + vertex 1.65365 1.48085 2.53469 + vertex 1.65064 1.47723 2.53655 + vertex 1.65368 1.47587 2.5347 + endloop + endfacet + facet normal 0.525007 0.00103778 0.851097 + outer loop + vertex 1.65063 1.48221 2.53655 + vertex 1.65064 1.47723 2.53655 + vertex 1.65365 1.48085 2.53469 + endloop + endfacet + facet normal 0.578944 0.0113606 0.815288 + outer loop + vertex 1.65637 1.48398 2.53274 + vertex 1.65631 1.48896 2.53272 + vertex 1.65361 1.48584 2.53468 + endloop + endfacet + facet normal 0.576468 0.00579294 0.817099 + outer loop + vertex 1.65365 1.48085 2.53469 + vertex 1.65637 1.48398 2.53274 + vertex 1.65361 1.48584 2.53468 + endloop + endfacet + facet normal 0.526448 0.00550431 0.85019 + outer loop + vertex 1.65361 1.48584 2.53468 + vertex 1.65063 1.48221 2.53655 + vertex 1.65365 1.48085 2.53469 + endloop + endfacet + facet normal 0.530201 0.00121723 0.847871 + outer loop + vertex 1.65062 1.48719 2.53655 + vertex 1.65063 1.48221 2.53655 + vertex 1.65361 1.48584 2.53468 + endloop + endfacet + facet normal 0.583677 0.0180179 0.811786 + outer loop + vertex 1.65631 1.48896 2.53272 + vertex 1.65626 1.49393 2.53264 + vertex 1.65358 1.49084 2.53464 + endloop + endfacet + facet normal 0.580047 0.00992887 0.814523 + outer loop + vertex 1.65361 1.48584 2.53468 + vertex 1.65631 1.48896 2.53272 + vertex 1.65358 1.49084 2.53464 + endloop + endfacet + facet normal 0.532981 0.00984452 0.84607 + outer loop + vertex 1.65358 1.49084 2.53464 + vertex 1.65062 1.48719 2.53655 + vertex 1.65361 1.48584 2.53468 + endloop + endfacet + facet normal 0.537781 0.00437491 0.843073 + outer loop + vertex 1.65062 1.49222 2.53652 + vertex 1.65062 1.48719 2.53655 + vertex 1.65358 1.49084 2.53464 + endloop + endfacet + facet normal 0.591775 0.0204784 0.805843 + outer loop + vertex 1.65626 1.49393 2.53264 + vertex 1.65631 1.49878 2.53249 + vertex 1.65362 1.49595 2.53453 + endloop + endfacet + facet normal 0.587843 0.0125311 0.808878 + outer loop + vertex 1.65358 1.49084 2.53464 + vertex 1.65626 1.49393 2.53264 + vertex 1.65362 1.49595 2.53453 + endloop + endfacet + facet normal 0.540805 0.0136051 0.841038 + outer loop + vertex 1.65362 1.49595 2.53453 + vertex 1.65062 1.49222 2.53652 + vertex 1.65358 1.49084 2.53464 + endloop + endfacet + facet normal 0.548743 0.00452731 0.835979 + outer loop + vertex 1.65068 1.49739 2.53645 + vertex 1.65062 1.49222 2.53652 + vertex 1.65362 1.49595 2.53453 + endloop + endfacet + facet normal 0.60618 0.0145653 0.795194 + outer loop + vertex 1.65631 1.49878 2.53249 + vertex 1.65664 1.50265 2.53216 + vertex 1.65397 1.50164 2.53421 + endloop + endfacet + facet normal 0.600648 0.00745519 0.799479 + outer loop + vertex 1.65362 1.49595 2.53453 + vertex 1.65631 1.49878 2.53249 + vertex 1.65397 1.50164 2.53421 + endloop + endfacet + facet normal 0.551388 0.0123859 0.834157 + outer loop + vertex 1.65397 1.50164 2.53421 + vertex 1.65068 1.49739 2.53645 + vertex 1.65362 1.49595 2.53453 + endloop + endfacet + facet normal 0.564541 -0.00241232 0.825402 + outer loop + vertex 1.65064 1.50256 2.53649 + vertex 1.65068 1.49739 2.53645 + vertex 1.65397 1.50164 2.53421 + endloop + endfacet + facet normal 0.614869 -0.00307167 0.788624 + outer loop + vertex 1.65828 1.5047 2.53088 + vertex 1.65908 1.50888 2.53028 + vertex 1.6562 1.50621 2.53251 + endloop + endfacet + facet normal 0.615745 -0.00113107 0.787944 + outer loop + vertex 1.65664 1.50265 2.53216 + vertex 1.65828 1.5047 2.53088 + vertex 1.6562 1.50621 2.53251 + endloop + endfacet + facet normal 0.610222 -0.00224032 0.792228 + outer loop + vertex 1.65664 1.50265 2.53216 + vertex 1.6562 1.50621 2.53251 + vertex 1.65397 1.50164 2.53421 + endloop + endfacet + facet normal 0.609327 -0.00154576 0.792917 + outer loop + vertex 1.65397 1.50164 2.53421 + vertex 1.6562 1.50621 2.53251 + vertex 1.65345 1.50686 2.53463 + endloop + endfacet + facet normal 0.563326 -0.0087914 0.826188 + outer loop + vertex 1.65345 1.50686 2.53463 + vertex 1.65064 1.50256 2.53649 + vertex 1.65397 1.50164 2.53421 + endloop + endfacet + facet normal 0.558547 -0.00425856 0.829462 + outer loop + vertex 1.6505 1.50745 2.53661 + vertex 1.65064 1.50256 2.53649 + vertex 1.65345 1.50686 2.53463 + endloop + endfacet + facet normal 0.614866 0.0107228 0.788559 + outer loop + vertex 1.65908 1.50888 2.53028 + vertex 1.65861 1.51418 2.53057 + vertex 1.6559 1.51146 2.53272 + endloop + endfacet + facet normal 0.611152 0.00333768 0.791506 + outer loop + vertex 1.6562 1.50621 2.53251 + vertex 1.65908 1.50888 2.53028 + vertex 1.6559 1.51146 2.53272 + endloop + endfacet + facet normal 0.610037 0.00323799 0.792366 + outer loop + vertex 1.6562 1.50621 2.53251 + vertex 1.6559 1.51146 2.53272 + vertex 1.65345 1.50686 2.53463 + endloop + endfacet + facet normal 0.60898 0.00413751 0.793175 + outer loop + vertex 1.6559 1.51146 2.53272 + vertex 1.65302 1.51101 2.53493 + vertex 1.65345 1.50686 2.53463 + endloop + endfacet + facet normal 0.558628 -0.00368148 0.82941 + outer loop + vertex 1.65302 1.51101 2.53493 + vertex 1.6505 1.50745 2.53661 + vertex 1.65345 1.50686 2.53463 + endloop + endfacet + facet normal 0.546759 0.0084449 0.837247 + outer loop + vertex 1.65061 1.51235 2.53649 + vertex 1.6505 1.50745 2.53661 + vertex 1.65302 1.51101 2.53493 + endloop + endfacet + facet normal 0.607713 0.0220454 0.793851 + outer loop + vertex 1.65861 1.51418 2.53057 + vertex 1.65665 1.51567 2.53203 + vertex 1.6559 1.51146 2.53272 + endloop + endfacet + facet normal 0.621062 0.00893441 0.783711 + outer loop + vertex 1.65665 1.51567 2.53203 + vertex 1.65661 1.51825 2.53203 + vertex 1.65421 1.51629 2.53395 + endloop + endfacet + facet normal 0.622335 0.0175844 0.782553 + outer loop + vertex 1.65665 1.51567 2.53203 + vertex 1.65421 1.51629 2.53395 + vertex 1.6559 1.51146 2.53272 + endloop + endfacet + facet normal 0.608385 0.00992317 0.79358 + outer loop + vertex 1.6559 1.51146 2.53272 + vertex 1.65421 1.51629 2.53395 + vertex 1.65302 1.51101 2.53493 + endloop + endfacet + facet normal 0.554634 0.0291094 0.831585 + outer loop + vertex 1.65421 1.51629 2.53395 + vertex 1.65061 1.51235 2.53649 + vertex 1.65302 1.51101 2.53493 + endloop + endfacet + facet normal 0.573366 0.00403857 0.81929 + outer loop + vertex 1.65071 1.51748 2.5364 + vertex 1.65061 1.51235 2.53649 + vertex 1.65421 1.51629 2.53395 + endloop + endfacet + facet normal 0.614937 -0.02876 0.788052 + outer loop + vertex 1.65808 1.51993 2.53093 + vertex 1.65907 1.52373 2.53029 + vertex 1.65628 1.52114 2.53238 + endloop + endfacet + facet normal 0.617167 -0.0235596 0.786479 + outer loop + vertex 1.65661 1.51825 2.53203 + vertex 1.65808 1.51993 2.53093 + vertex 1.65628 1.52114 2.53238 + endloop + endfacet + facet normal 0.635134 -0.0197251 0.77215 + outer loop + vertex 1.65661 1.51825 2.53203 + vertex 1.65628 1.52114 2.53238 + vertex 1.65421 1.51629 2.53395 + endloop + endfacet + facet normal 0.613578 -0.00488398 0.789619 + outer loop + vertex 1.65421 1.51629 2.53395 + vertex 1.65628 1.52114 2.53238 + vertex 1.65364 1.52182 2.53443 + endloop + endfacet + facet normal 0.569588 -0.0122867 0.821839 + outer loop + vertex 1.65364 1.52182 2.53443 + vertex 1.65071 1.51748 2.5364 + vertex 1.65421 1.51629 2.53395 + endloop + endfacet + facet normal 0.560939 -0.00372356 0.827849 + outer loop + vertex 1.6506 1.52259 2.5365 + vertex 1.65071 1.51748 2.5364 + vertex 1.65364 1.52182 2.53443 + endloop + endfacet + facet normal 0.613005 -0.00541547 0.790061 + outer loop + vertex 1.65907 1.52373 2.53029 + vertex 1.65883 1.5293 2.53051 + vertex 1.65622 1.5258 2.53252 + endloop + endfacet + facet normal 0.60789 -0.0165123 0.793849 + outer loop + vertex 1.65628 1.52114 2.53238 + vertex 1.65907 1.52373 2.53029 + vertex 1.65622 1.5258 2.53252 + endloop + endfacet + facet normal 0.611643 -0.0163829 0.790964 + outer loop + vertex 1.65628 1.52114 2.53238 + vertex 1.65622 1.5258 2.53252 + vertex 1.65364 1.52182 2.53443 + endloop + endfacet + facet normal 0.602839 -0.00734665 0.797829 + outer loop + vertex 1.65622 1.5258 2.53252 + vertex 1.6535 1.52689 2.53458 + vertex 1.65364 1.52182 2.53443 + endloop + endfacet + facet normal 0.559939 -0.00939832 0.82848 + outer loop + vertex 1.6535 1.52689 2.53458 + vertex 1.6506 1.52259 2.5365 + vertex 1.65364 1.52182 2.53443 + endloop + endfacet + facet normal 0.550577 -0.000257133 0.834784 + outer loop + vertex 1.65056 1.52759 2.53652 + vertex 1.6506 1.52259 2.5365 + vertex 1.6535 1.52689 2.53458 + endloop + endfacet + facet normal 0.614679 0.0072572 0.788744 + outer loop + vertex 1.65883 1.5293 2.53051 + vertex 1.65874 1.53443 2.53054 + vertex 1.65614 1.53089 2.5326 + endloop + endfacet + facet normal 0.610937 -0.00294591 0.791674 + outer loop + vertex 1.65622 1.5258 2.53252 + vertex 1.65883 1.5293 2.53051 + vertex 1.65614 1.53089 2.5326 + endloop + endfacet + facet normal 0.60391 -0.00315718 0.797046 + outer loop + vertex 1.65622 1.5258 2.53252 + vertex 1.65614 1.53089 2.5326 + vertex 1.6535 1.52689 2.53458 + endloop + endfacet + facet normal 0.599874 0.00101122 0.800094 + outer loop + vertex 1.65614 1.53089 2.5326 + vertex 1.65347 1.5319 2.5346 + vertex 1.6535 1.52689 2.53458 + endloop + endfacet + facet normal 0.550725 0.00062854 0.834687 + outer loop + vertex 1.65347 1.5319 2.5346 + vertex 1.65056 1.52759 2.53652 + vertex 1.6535 1.52689 2.53458 + endloop + endfacet + facet normal 0.54809 0.00318136 0.836413 + outer loop + vertex 1.65057 1.53258 2.5365 + vertex 1.65056 1.52759 2.53652 + vertex 1.65347 1.5319 2.5346 + endloop + endfacet + facet normal 0.617375 0.00953887 0.786611 + outer loop + vertex 1.65874 1.53443 2.53054 + vertex 1.65874 1.53945 2.53048 + vertex 1.65612 1.53592 2.53258 + endloop + endfacet + facet normal 0.616024 0.00566351 0.787707 + outer loop + vertex 1.65614 1.53089 2.5326 + vertex 1.65874 1.53443 2.53054 + vertex 1.65612 1.53592 2.53258 + endloop + endfacet + facet normal 0.601001 0.00566215 0.799228 + outer loop + vertex 1.65614 1.53089 2.5326 + vertex 1.65612 1.53592 2.53258 + vertex 1.65347 1.5319 2.5346 + endloop + endfacet + facet normal 0.601633 0.00500908 0.798757 + outer loop + vertex 1.65612 1.53592 2.53258 + vertex 1.65348 1.53691 2.53456 + vertex 1.65347 1.5319 2.5346 + endloop + endfacet + facet normal 0.548453 0.00542588 0.836164 + outer loop + vertex 1.65348 1.53691 2.53456 + vertex 1.65057 1.53258 2.5365 + vertex 1.65347 1.5319 2.5346 + endloop + endfacet + facet normal 0.54957 0.00434753 0.835436 + outer loop + vertex 1.65058 1.53759 2.53646 + vertex 1.65057 1.53258 2.5365 + vertex 1.65348 1.53691 2.53456 + endloop + endfacet + facet normal 0.621177 0.00453179 0.783657 + outer loop + vertex 1.65874 1.53945 2.53048 + vertex 1.65876 1.54445 2.53044 + vertex 1.65613 1.54094 2.53254 + endloop + endfacet + facet normal 0.621281 0.00483078 0.783573 + outer loop + vertex 1.65612 1.53592 2.53258 + vertex 1.65874 1.53945 2.53048 + vertex 1.65613 1.54094 2.53254 + endloop + endfacet + facet normal 0.601637 0.00502378 0.798754 + outer loop + vertex 1.65612 1.53592 2.53258 + vertex 1.65613 1.54094 2.53254 + vertex 1.65348 1.53691 2.53456 + endloop + endfacet + facet normal 0.605113 0.00142527 0.796138 + outer loop + vertex 1.65613 1.54094 2.53254 + vertex 1.65348 1.54191 2.53455 + vertex 1.65348 1.53691 2.53456 + endloop + endfacet + facet normal 0.549093 0.00142842 0.83576 + outer loop + vertex 1.65348 1.54191 2.53455 + vertex 1.65058 1.53759 2.53646 + vertex 1.65348 1.53691 2.53456 + endloop + endfacet + facet normal 0.552555 -0.00191264 0.833474 + outer loop + vertex 1.65056 1.54257 2.53649 + vertex 1.65058 1.53759 2.53646 + vertex 1.65348 1.54191 2.53455 + endloop + endfacet + facet normal 0.624451 0.000109311 0.781064 + outer loop + vertex 1.65876 1.54445 2.53044 + vertex 1.65873 1.54946 2.53046 + vertex 1.6561 1.54597 2.53256 + endloop + endfacet + facet normal 0.624555 0.00040498 0.780981 + outer loop + vertex 1.65613 1.54094 2.53254 + vertex 1.65876 1.54445 2.53044 + vertex 1.6561 1.54597 2.53256 + endloop + endfacet + facet normal 0.60483 0.000200842 0.796354 + outer loop + vertex 1.65613 1.54094 2.53254 + vertex 1.6561 1.54597 2.53256 + vertex 1.65348 1.54191 2.53455 + endloop + endfacet + facet normal 0.608183 -0.00321324 0.793791 + outer loop + vertex 1.6561 1.54597 2.53256 + vertex 1.65338 1.54678 2.53465 + vertex 1.65348 1.54191 2.53455 + endloop + endfacet + facet normal 0.552029 -0.00519621 0.833808 + outer loop + vertex 1.65338 1.54678 2.53465 + vertex 1.65056 1.54257 2.53649 + vertex 1.65348 1.54191 2.53455 + endloop + endfacet + facet normal 0.552498 -0.00564667 0.833495 + outer loop + vertex 1.65051 1.54735 2.53655 + vertex 1.65056 1.54257 2.53649 + vertex 1.65338 1.54678 2.53465 + endloop + endfacet + facet normal 0.625768 -0.00241257 0.780006 + outer loop + vertex 1.65873 1.54946 2.53046 + vertex 1.6587 1.55425 2.53049 + vertex 1.65587 1.55136 2.53276 + endloop + endfacet + facet normal 0.626007 -0.00181988 0.779815 + outer loop + vertex 1.6561 1.54597 2.53256 + vertex 1.65873 1.54946 2.53046 + vertex 1.65587 1.55136 2.53276 + endloop + endfacet + facet normal 0.6082 -0.00312135 0.793778 + outer loop + vertex 1.6561 1.54597 2.53256 + vertex 1.65587 1.55136 2.53276 + vertex 1.65338 1.54678 2.53465 + endloop + endfacet + facet normal 0.607635 -0.00263555 0.794212 + outer loop + vertex 1.65587 1.55136 2.53276 + vertex 1.65301 1.55073 2.53495 + vertex 1.65338 1.54678 2.53465 + endloop + endfacet + facet normal 0.551757 -0.0108164 0.833935 + outer loop + vertex 1.65301 1.55073 2.53495 + vertex 1.65051 1.54735 2.53655 + vertex 1.65338 1.54678 2.53465 + endloop + endfacet + facet normal 0.542361 -0.000936158 0.840145 + outer loop + vertex 1.65063 1.55208 2.53648 + vertex 1.65051 1.54735 2.53655 + vertex 1.65301 1.55073 2.53495 + endloop + endfacet + facet normal 0.625868 -0.00257428 0.779925 + outer loop + vertex 1.6587 1.55425 2.53049 + vertex 1.65669 1.55577 2.53211 + vertex 1.65587 1.55136 2.53276 + endloop + endfacet + facet normal 0.614944 -0.0151021 0.788426 + outer loop + vertex 1.65669 1.55577 2.53211 + vertex 1.65634 1.5593 2.53245 + vertex 1.65396 1.55542 2.53423 + endloop + endfacet + facet normal 0.613698 0.00110269 0.78954 + outer loop + vertex 1.65669 1.55577 2.53211 + vertex 1.65396 1.55542 2.53423 + vertex 1.65587 1.55136 2.53276 + endloop + endfacet + facet normal 0.607733 -0.00335661 0.794134 + outer loop + vertex 1.65587 1.55136 2.53276 + vertex 1.65396 1.55542 2.53423 + vertex 1.65301 1.55073 2.53495 + endloop + endfacet + facet normal 0.548697 0.0150118 0.835887 + outer loop + vertex 1.65396 1.55542 2.53423 + vertex 1.65063 1.55208 2.53648 + vertex 1.65301 1.55073 2.53495 + endloop + endfacet + facet normal 0.559419 -0.000420753 0.828885 + outer loop + vertex 1.65072 1.55704 2.53643 + vertex 1.65063 1.55208 2.53648 + vertex 1.65396 1.55542 2.53423 + endloop + endfacet + facet normal 0.602932 -0.0208852 0.797519 + outer loop + vertex 1.65634 1.5593 2.53245 + vertex 1.65625 1.56388 2.53264 + vertex 1.65365 1.56067 2.53453 + endloop + endfacet + facet normal 0.607276 -0.00765166 0.794454 + outer loop + vertex 1.65396 1.55542 2.53423 + vertex 1.65634 1.5593 2.53245 + vertex 1.65365 1.56067 2.53453 + endloop + endfacet + facet normal 0.555101 -0.0128758 0.831683 + outer loop + vertex 1.65365 1.56067 2.53453 + vertex 1.65072 1.55704 2.53643 + vertex 1.65396 1.55542 2.53423 + endloop + endfacet + facet normal 0.546101 -0.00245964 0.837716 + outer loop + vertex 1.65047 1.56208 2.5366 + vertex 1.65072 1.55704 2.53643 + vertex 1.65365 1.56067 2.53453 + endloop + endfacet + facet normal 0.588869 -0.0229939 0.807902 + outer loop + vertex 1.65625 1.56388 2.53264 + vertex 1.65605 1.56926 2.53294 + vertex 1.65335 1.56558 2.5348 + endloop + endfacet + facet normal 0.594058 -0.00967865 0.804364 + outer loop + vertex 1.65365 1.56067 2.53453 + vertex 1.65625 1.56388 2.53264 + vertex 1.65335 1.56558 2.5348 + endloop + endfacet + facet normal 0.54219 -0.0148234 0.840125 + outer loop + vertex 1.65335 1.56558 2.5348 + vertex 1.65047 1.56208 2.5366 + vertex 1.65365 1.56067 2.53453 + endloop + endfacet + facet normal 0.528707 0.000702963 0.848804 + outer loop + vertex 1.65 1.56738 2.53689 + vertex 1.65047 1.56208 2.5366 + vertex 1.65335 1.56558 2.5348 + endloop + endfacet + facet normal 0.582174 -0.0155531 0.812916 + outer loop + vertex 1.65306 1.56964 2.53509 + vertex 1.65335 1.56558 2.5348 + vertex 1.65605 1.56926 2.53294 + endloop + endfacet + facet normal 0.581501 -0.02268 0.813229 + outer loop + vertex 1.65306 1.56964 2.53509 + vertex 1.65605 1.56926 2.53294 + vertex 1.65421 1.57384 2.53438 + endloop + endfacet + facet normal 0.587097 -0.0191864 0.809289 + outer loop + vertex 1.65421 1.57384 2.53438 + vertex 1.65605 1.56926 2.53294 + vertex 1.6571 1.57369 2.53228 + endloop + endfacet + facet normal 0.519323 -0.0230836 0.854266 + outer loop + vertex 1.65335 1.56558 2.5348 + vertex 1.65306 1.56964 2.53509 + vertex 1.65 1.56738 2.53689 + endloop + endfacet + facet normal 0.586643 -0.0288954 0.80933 + outer loop + vertex 1.6571 1.57369 2.53228 + vertex 1.65671 1.57773 2.53271 + vertex 1.65421 1.57384 2.53438 + endloop + endfacet + facet normal 0.581083 -0.0235386 0.813504 + outer loop + vertex 1.65421 1.57384 2.53438 + vertex 1.65671 1.57773 2.53271 + vertex 1.65389 1.57863 2.53475 + endloop + endfacet + facet normal 0.518785 -0.0301503 0.854373 + outer loop + vertex 1.65328 1.58191 2.53524 + vertex 1.65148 1.57941 2.53624 + vertex 1.65389 1.57863 2.53475 + endloop + endfacet + facet normal 0.570417 -0.0156578 0.821206 + outer loop + vertex 1.65328 1.58191 2.53524 + vertex 1.65389 1.57863 2.53475 + vertex 1.65619 1.58286 2.53323 + endloop + endfacet + facet normal 0.580948 -0.0241374 0.813582 + outer loop + vertex 1.65619 1.58286 2.53323 + vertex 1.65389 1.57863 2.53475 + vertex 1.65671 1.57773 2.53271 + endloop + endfacet + facet normal 0.482065 0.00522005 0.87612 + outer loop + vertex 1.65328 1.58191 2.53524 + vertex 1.65077 1.58261 2.53662 + vertex 1.65148 1.57941 2.53624 + endloop + endfacet + facet normal 0.562392 -0.00691533 0.826842 + outer loop + vertex 1.65619 1.58286 2.53323 + vertex 1.65655 1.58852 2.53304 + vertex 1.65359 1.58567 2.53502 + endloop + endfacet + facet normal 0.567132 -0.000493533 0.823627 + outer loop + vertex 1.65328 1.58191 2.53524 + vertex 1.65619 1.58286 2.53323 + vertex 1.65359 1.58567 2.53502 + endloop + endfacet + facet normal 0.48294 0.00934309 0.875603 + outer loop + vertex 1.65359 1.58567 2.53502 + vertex 1.65077 1.58261 2.53662 + vertex 1.65328 1.58191 2.53524 + endloop + endfacet + facet normal 0.477616 0.0157358 0.878428 + outer loop + vertex 1.65044 1.58712 2.53672 + vertex 1.65077 1.58261 2.53662 + vertex 1.65359 1.58567 2.53502 + endloop + endfacet + facet normal 0.550129 0.00186486 0.835077 + outer loop + vertex 1.65655 1.58852 2.53304 + vertex 1.65642 1.59417 2.53311 + vertex 1.65352 1.5905 2.53503 + endloop + endfacet + facet normal 0.552744 0.00763868 0.833316 + outer loop + vertex 1.65359 1.58567 2.53502 + vertex 1.65655 1.58852 2.53304 + vertex 1.65352 1.5905 2.53503 + endloop + endfacet + facet normal 0.474308 0.0062853 0.880337 + outer loop + vertex 1.65352 1.5905 2.53503 + vertex 1.65044 1.58712 2.53672 + vertex 1.65359 1.58567 2.53502 + endloop + endfacet + facet normal 0.464903 0.0172724 0.885193 + outer loop + vertex 1.64998 1.59232 2.53686 + vertex 1.65044 1.58712 2.53672 + vertex 1.65352 1.5905 2.53503 + endloop + endfacet + facet normal 0.547714 0.00460042 0.836653 + outer loop + vertex 1.65326 1.5946 2.53518 + vertex 1.65352 1.5905 2.53503 + vertex 1.65642 1.59417 2.53311 + endloop + endfacet + facet normal 0.546985 -0.00300823 0.837137 + outer loop + vertex 1.65326 1.5946 2.53518 + vertex 1.65642 1.59417 2.53311 + vertex 1.65443 1.5988 2.53443 + endloop + endfacet + facet normal 0.565478 0.00843517 0.82472 + outer loop + vertex 1.65443 1.5988 2.53443 + vertex 1.65642 1.59417 2.53311 + vertex 1.65745 1.59862 2.53236 + endloop + endfacet + facet normal 0.45669 -0.00307487 0.889621 + outer loop + vertex 1.65352 1.5905 2.53503 + vertex 1.65326 1.5946 2.53518 + vertex 1.64998 1.59232 2.53686 + endloop + endfacet + facet normal 0.564978 -0.00372788 0.825098 + outer loop + vertex 1.65745 1.59862 2.53236 + vertex 1.65692 1.60265 2.53274 + vertex 1.65443 1.5988 2.53443 + endloop + endfacet + facet normal 0.561382 -0.000325495 0.827556 + outer loop + vertex 1.65443 1.5988 2.53443 + vertex 1.65692 1.60265 2.53274 + vertex 1.65396 1.60358 2.53475 + endloop + endfacet + facet normal 0.476516 -0.012947 0.87907 + outer loop + vertex 1.65318 1.60677 2.53522 + vertex 1.65139 1.6043 2.53615 + vertex 1.65396 1.60358 2.53475 + endloop + endfacet + facet normal 0.546884 0.0104263 0.837144 + outer loop + vertex 1.65318 1.60677 2.53522 + vertex 1.65396 1.60358 2.53475 + vertex 1.65618 1.6078 2.53325 + endloop + endfacet + facet normal 0.561332 -0.000560046 0.827591 + outer loop + vertex 1.65618 1.6078 2.53325 + vertex 1.65396 1.60358 2.53475 + vertex 1.65692 1.60265 2.53274 + endloop + endfacet + facet normal 0.432452 0.0271738 0.901247 + outer loop + vertex 1.65318 1.60677 2.53522 + vertex 1.65047 1.60736 2.5365 + vertex 1.65139 1.6043 2.53615 + endloop + endfacet + facet normal 0.533375 0.0139617 0.845764 + outer loop + vertex 1.65618 1.6078 2.53325 + vertex 1.65628 1.61392 2.53308 + vertex 1.65328 1.61043 2.53503 + endloop + endfacet + facet normal 0.542442 0.028108 0.839623 + outer loop + vertex 1.65318 1.60677 2.53522 + vertex 1.65618 1.6078 2.53325 + vertex 1.65328 1.61043 2.53503 + endloop + endfacet + facet normal 0.433621 0.0343122 0.900442 + outer loop + vertex 1.65328 1.61043 2.53503 + vertex 1.65047 1.60736 2.5365 + vertex 1.65318 1.60677 2.53522 + endloop + endfacet + facet normal 0.4301 0.0382604 0.90197 + outer loop + vertex 1.64976 1.61196 2.53664 + vertex 1.65047 1.60736 2.5365 + vertex 1.65328 1.61043 2.53503 + endloop + endfacet + facet normal 0.523223 0.0260522 0.851798 + outer loop + vertex 1.65302 1.61436 2.53507 + vertex 1.65328 1.61043 2.53503 + vertex 1.65628 1.61392 2.53308 + endloop + endfacet + facet normal 0.523238 0.0262359 0.851783 + outer loop + vertex 1.65302 1.61436 2.53507 + vertex 1.65628 1.61392 2.53308 + vertex 1.65415 1.61871 2.53424 + endloop + endfacet + facet normal 0.526781 0.0283602 0.849528 + outer loop + vertex 1.65415 1.61871 2.53424 + vertex 1.65628 1.61392 2.53308 + vertex 1.6574 1.61849 2.53224 + endloop + endfacet + facet normal 0.423435 0.0188749 0.90573 + outer loop + vertex 1.65328 1.61043 2.53503 + vertex 1.65302 1.61436 2.53507 + vertex 1.64976 1.61196 2.53664 + endloop + endfacet + facet normal 0.526515 0.0207016 0.849914 + outer loop + vertex 1.6574 1.61849 2.53224 + vertex 1.65685 1.62257 2.53248 + vertex 1.65415 1.61871 2.53424 + endloop + endfacet + facet normal 0.50791 0.0385576 0.860547 + outer loop + vertex 1.65415 1.61871 2.53424 + vertex 1.65685 1.62257 2.53248 + vertex 1.65357 1.62412 2.53434 + endloop + endfacet + facet normal 0.504205 0.0275507 0.863144 + outer loop + vertex 1.65685 1.62257 2.53248 + vertex 1.65654 1.62745 2.5325 + vertex 1.65357 1.62412 2.53434 + endloop + endfacet + facet normal 0.494108 0.0394713 0.868504 + outer loop + vertex 1.65357 1.62412 2.53434 + vertex 1.65654 1.62745 2.5325 + vertex 1.65326 1.6292 2.53429 + endloop + endfacet + facet normal 0.491875 0.0337172 0.870013 + outer loop + vertex 1.65654 1.62745 2.5325 + vertex 1.65636 1.63249 2.53241 + vertex 1.65326 1.6292 2.53429 + endloop + endfacet + facet normal 0.485233 0.0418923 0.873381 + outer loop + vertex 1.65326 1.6292 2.53429 + vertex 1.65636 1.63249 2.53241 + vertex 1.65305 1.6342 2.53416 + endloop + endfacet + facet normal 0.484777 0.04069 0.873691 + outer loop + vertex 1.65636 1.63249 2.53241 + vertex 1.65619 1.63753 2.53227 + vertex 1.65305 1.6342 2.53416 + endloop + endfacet + facet normal 0.477528 0.0495191 0.87722 + outer loop + vertex 1.65305 1.6342 2.53416 + vertex 1.65619 1.63753 2.53227 + vertex 1.65276 1.6392 2.53404 + endloop + endfacet + facet normal 0.474638 0.0414815 0.879203 + outer loop + vertex 1.65619 1.63753 2.53227 + vertex 1.65599 1.64257 2.53214 + vertex 1.65276 1.6392 2.53404 + endloop + endfacet + facet normal 0.469258 0.0480855 0.881751 + outer loop + vertex 1.65276 1.6392 2.53404 + vertex 1.65599 1.64257 2.53214 + vertex 1.65225 1.64461 2.53402 + endloop + endfacet + facet normal 0.463074 0.0330941 0.885702 + outer loop + vertex 1.65599 1.64257 2.53214 + vertex 1.65602 1.64748 2.53194 + vertex 1.65225 1.64461 2.53402 + endloop + endfacet + facet normal 0.469878 0.0218259 0.882461 + outer loop + vertex 1.65225 1.64461 2.53402 + vertex 1.65602 1.64748 2.53194 + vertex 1.65336 1.64924 2.53331 + endloop + endfacet + facet normal 0.472023 0.0260399 0.881202 + outer loop + vertex 1.65602 1.64748 2.53194 + vertex 1.656 1.65216 2.53181 + vertex 1.65336 1.64924 2.53331 + endloop + endfacet + facet normal 0.457142 0.0431998 0.888344 + outer loop + vertex 1.65336 1.64924 2.53331 + vertex 1.656 1.65216 2.53181 + vertex 1.65265 1.65322 2.53348 + endloop + endfacet + facet normal 0.453477 0.0276579 0.890839 + outer loop + vertex 1.656 1.65216 2.53181 + vertex 1.65562 1.65695 2.53185 + vertex 1.65265 1.65322 2.53348 + endloop + endfacet + facet normal 0.437483 0.0435943 0.898169 + outer loop + vertex 1.65265 1.65322 2.53348 + vertex 1.65562 1.65695 2.53185 + vertex 1.65205 1.65798 2.53354 + endloop + endfacet + facet normal 0.434554 0.0300999 0.900143 + outer loop + vertex 1.65562 1.65695 2.53185 + vertex 1.65501 1.66226 2.53197 + vertex 1.65205 1.65798 2.53354 + endloop + endfacet + facet normal 0.41153 0.0496478 0.910043 + outer loop + vertex 1.65205 1.65798 2.53354 + vertex 1.65501 1.66226 2.53197 + vertex 1.6513 1.66201 2.53366 + endloop + endfacet + facet normal 0.486841 0.0370311 0.872705 + outer loop + vertex 1.65817 1.66457 2.53021 + vertex 1.65922 1.66885 2.52944 + vertex 1.6562 1.66669 2.53122 + endloop + endfacet + facet normal 0.474628 0.022183 0.879907 + outer loop + vertex 1.6562 1.66669 2.53122 + vertex 1.65501 1.66226 2.53197 + vertex 1.65817 1.66457 2.53021 + endloop + endfacet + facet normal 0.410859 0.0445019 0.910612 + outer loop + vertex 1.6562 1.66669 2.53122 + vertex 1.6524 1.66669 2.53293 + vertex 1.65501 1.66226 2.53197 + endloop + endfacet + facet normal 0.41186 0.0451954 0.910126 + outer loop + vertex 1.6524 1.66669 2.53293 + vertex 1.6513 1.66201 2.53366 + vertex 1.65501 1.66226 2.53197 + endloop + endfacet + facet normal 0.473218 0.0155725 0.880808 + outer loop + vertex 1.65922 1.66885 2.52944 + vertex 1.65872 1.6741 2.52962 + vertex 1.65568 1.67072 2.53131 + endloop + endfacet + facet normal 0.483858 0.042366 0.874121 + outer loop + vertex 1.6562 1.66669 2.53122 + vertex 1.65922 1.66885 2.52944 + vertex 1.65568 1.67072 2.53131 + endloop + endfacet + facet normal 0.411039 0.0321212 0.911051 + outer loop + vertex 1.65568 1.67072 2.53131 + vertex 1.6524 1.66669 2.53293 + vertex 1.6562 1.66669 2.53122 + endloop + endfacet + facet normal 0.394448 0.0482368 0.917651 + outer loop + vertex 1.65179 1.67222 2.53291 + vertex 1.6524 1.66669 2.53293 + vertex 1.65568 1.67072 2.53131 + endloop + endfacet + facet normal 0.454921 0.021212 0.890279 + outer loop + vertex 1.65872 1.6741 2.52962 + vertex 1.65848 1.67907 2.52962 + vertex 1.6553 1.67562 2.53133 + endloop + endfacet + facet normal 0.458722 0.0322672 0.887994 + outer loop + vertex 1.65568 1.67072 2.53131 + vertex 1.65872 1.6741 2.52962 + vertex 1.6553 1.67562 2.53133 + endloop + endfacet + facet normal 0.387725 0.0267164 0.921388 + outer loop + vertex 1.6553 1.67562 2.53133 + vertex 1.65179 1.67222 2.53291 + vertex 1.65568 1.67072 2.53131 + endloop + endfacet + facet normal 0.373829 0.0433965 0.926482 + outer loop + vertex 1.65165 1.6772 2.53273 + vertex 1.65179 1.67222 2.53291 + vertex 1.6553 1.67562 2.53133 + endloop + endfacet + facet normal 0.441641 0.0429289 0.896164 + outer loop + vertex 1.65848 1.67907 2.52962 + vertex 1.65827 1.68407 2.52949 + vertex 1.6551 1.68053 2.53122 + endloop + endfacet + facet normal 0.440085 0.0382744 0.89714 + outer loop + vertex 1.6553 1.67562 2.53133 + vertex 1.65848 1.67907 2.52962 + vertex 1.6551 1.68053 2.53122 + endloop + endfacet + facet normal 0.371233 0.0361746 0.927835 + outer loop + vertex 1.6551 1.68053 2.53122 + vertex 1.65165 1.6772 2.53273 + vertex 1.6553 1.67562 2.53133 + endloop + endfacet + facet normal 0.40999 0.0779753 0.908751 + outer loop + vertex 1.6545 1.69857 2.53003 + vertex 1.65704 1.69446 2.52924 + vertex 1.65744 1.69814 2.52874 + endloop + endfacet + facet normal 0.351058 0.537132 0.766973 + outer loop + vertex 1.6538 2.08489 2.45621 + vertex 1.65771 2.08303 2.45572 + vertex 1.6566 2.08692 2.45351 + endloop + endfacet + facet normal 0.362998 0.524716 0.770003 + outer loop + vertex 1.65154 2.08822 2.455 + vertex 1.6538 2.08489 2.45621 + vertex 1.6566 2.08692 2.45351 + endloop + endfacet + facet normal 0.326045 0.427988 0.842924 + outer loop + vertex 1.65628 2.08041 2.45752 + vertex 1.6538 2.08489 2.45621 + vertex 1.65107 2.08342 2.45801 + endloop + endfacet + facet normal 0.306458 0.420374 0.854031 + outer loop + vertex 1.65771 2.08303 2.45572 + vertex 1.6538 2.08489 2.45621 + vertex 1.65628 2.08041 2.45752 + endloop + endfacet + facet normal 0.343968 0.728359 0.592604 + outer loop + vertex 1.6594 2.08917 2.45005 + vertex 1.65693 2.09132 2.44883 + vertex 1.65553 2.09024 2.45096 + endloop + endfacet + facet normal 0.341837 0.637468 0.690494 + outer loop + vertex 1.65553 2.09024 2.45096 + vertex 1.6566 2.08692 2.45351 + vertex 1.6594 2.08917 2.45005 + endloop + endfacet + facet normal 0.363841 0.636512 0.680053 + outer loop + vertex 1.65553 2.09024 2.45096 + vertex 1.65225 2.09048 2.4525 + vertex 1.6566 2.08692 2.45351 + endloop + endfacet + facet normal 0.365036 0.637521 0.678466 + outer loop + vertex 1.65225 2.09048 2.4525 + vertex 1.65154 2.08822 2.455 + vertex 1.6566 2.08692 2.45351 + endloop + endfacet + facet normal 0.358881 0.549216 0.754696 + outer loop + vertex 1.65818 2.09563 2.44181 + vertex 1.65682 2.09793 2.44078 + vertex 1.65423 2.09678 2.44285 + endloop + endfacet + facet normal 0.455922 0.645296 0.612967 + outer loop + vertex 1.65423 2.09678 2.44285 + vertex 1.65121 2.09708 2.44479 + vertex 1.65297 2.09476 2.44593 + endloop + endfacet + facet normal 0.365655 0.700893 0.61241 + outer loop + vertex 1.65423 2.09678 2.44285 + vertex 1.65297 2.09476 2.44593 + vertex 1.65818 2.09563 2.44181 + endloop + endfacet + facet normal 0.319399 0.759738 0.566377 + outer loop + vertex 1.65818 2.09563 2.44181 + vertex 1.65297 2.09476 2.44593 + vertex 1.65765 2.09289 2.44579 + endloop + endfacet + facet normal 0.320926 0.74434 0.585632 + outer loop + vertex 1.65693 2.09132 2.44883 + vertex 1.65375 2.09233 2.44929 + vertex 1.65553 2.09024 2.45096 + endloop + endfacet + facet normal 0.327167 0.806001 0.493279 + outer loop + vertex 1.65693 2.09132 2.44883 + vertex 1.65765 2.09289 2.44579 + vertex 1.65375 2.09233 2.44929 + endloop + endfacet + facet normal 0.333424 0.799714 0.499285 + outer loop + vertex 1.65765 2.09289 2.44579 + vertex 1.65297 2.09476 2.44593 + vertex 1.65375 2.09233 2.44929 + endloop + endfacet + facet normal 0.325618 0.74529 0.581821 + outer loop + vertex 1.65553 2.09024 2.45096 + vertex 1.65375 2.09233 2.44929 + vertex 1.65225 2.09048 2.4525 + endloop + endfacet + facet normal 0.67284 -0.424795 0.605669 + outer loop + vertex 1.65682 2.09793 2.44078 + vertex 1.655 2.10106 2.445 + vertex 1.65423 2.09678 2.44285 + endloop + endfacet + facet normal 0.596225 -0.499849 0.628226 + outer loop + vertex 1.65682 2.09793 2.44078 + vertex 1.66 2.10074 2.44 + vertex 1.655 2.10106 2.445 + endloop + endfacet + facet normal 0.242121 0.953189 0.181129 + outer loop + vertex 1.66 2.10074 2.44 + vertex 1.655 2.10201 2.44 + vertex 1.655 2.10106 2.445 + endloop + endfacet + facet normal 0.444877 -0.464411 0.765772 + outer loop + vertex 1.65423 2.09678 2.44285 + vertex 1.655 2.10106 2.445 + vertex 1.65121 2.09708 2.44479 + endloop + endfacet + facet normal 0.351393 -0.857632 0.375486 + outer loop + vertex 1.66452 0.935 2.44 + vertex 1.66 0.935 2.44423 + vertex 1.66 0.933148 2.44 + endloop + endfacet + facet normal 0.466171 -0.731127 0.498134 + outer loop + vertex 1.66 0.935 2.44423 + vertex 1.66452 0.935 2.44 + vertex 1.665 0.935306 2.44 + endloop + endfacet + facet normal 0.499675 -0.675908 0.541731 + outer loop + vertex 1.66 0.935 2.44423 + vertex 1.665 0.935306 2.44 + vertex 1.66 0.935617 2.445 + endloop + endfacet + facet normal 0.687731 -0.193262 0.699769 + outer loop + vertex 1.66 0.935617 2.445 + vertex 1.665 0.935306 2.44 + vertex 1.66188 0.936785 2.44348 + endloop + endfacet + facet normal 0.37124 -0.76754 0.522555 + outer loop + vertex 1.66037 0.938019 2.44636 + vertex 1.66188 0.936785 2.44348 + vertex 1.66382 0.938744 2.44497 + endloop + endfacet + facet normal 0.358269 -0.775842 0.519339 + outer loop + vertex 1.66037 0.938019 2.44636 + vertex 1.65694 0.937023 2.44724 + vertex 1.66188 0.936785 2.44348 + endloop + endfacet + facet normal 0.6068 0.0579729 0.792738 + outer loop + vertex 1.65694 0.937023 2.44724 + vertex 1.66 0.935617 2.445 + vertex 1.66188 0.936785 2.44348 + endloop + endfacet + facet normal 0.359234 -0.762102 0.538657 + outer loop + vertex 1.66037 0.938019 2.44636 + vertex 1.65858 0.938849 2.44873 + vertex 1.65694 0.937023 2.44724 + endloop + endfacet + facet normal 0.371732 -0.765866 0.524656 + outer loop + vertex 1.66382 0.938744 2.44497 + vertex 1.66151 0.939794 2.44814 + vertex 1.66037 0.938019 2.44636 + endloop + endfacet + facet normal 0.354154 -0.766174 0.536239 + outer loop + vertex 1.65858 0.938849 2.44873 + vertex 1.66037 0.938019 2.44636 + vertex 1.66151 0.939794 2.44814 + endloop + endfacet + facet normal 0.351765 -0.720642 0.597442 + outer loop + vertex 1.65858 0.938849 2.44873 + vertex 1.66151 0.939794 2.44814 + vertex 1.65927 0.940683 2.45054 + endloop + endfacet + facet normal 0.36547 -0.707145 0.605292 + outer loop + vertex 1.65927 0.940683 2.45054 + vertex 1.66151 0.939794 2.44814 + vertex 1.66231 0.942202 2.45047 + endloop + endfacet + facet normal 0.337108 -0.646983 0.683938 + outer loop + vertex 1.66231 0.942202 2.45047 + vertex 1.65906 0.943681 2.45348 + vertex 1.65927 0.940683 2.45054 + endloop + endfacet + facet normal 0.348724 -0.634082 0.690168 + outer loop + vertex 1.66408 0.945179 2.45232 + vertex 1.65906 0.943681 2.45348 + vertex 1.66231 0.942202 2.45047 + endloop + endfacet + facet normal 0.363669 -0.559163 0.745038 + outer loop + vertex 1.65927 0.947065 2.45591 + vertex 1.65648 0.9454 2.45602 + vertex 1.65906 0.943681 2.45348 + endloop + endfacet + facet normal 0.346439 -0.562286 0.750876 + outer loop + vertex 1.65927 0.947065 2.45591 + vertex 1.65906 0.943681 2.45348 + vertex 1.66264 0.947659 2.4548 + endloop + endfacet + facet normal 0.341477 -0.559311 0.755358 + outer loop + vertex 1.66264 0.947659 2.4548 + vertex 1.65906 0.943681 2.45348 + vertex 1.66408 0.945179 2.45232 + endloop + endfacet + facet normal 0.299938 -0.446034 0.843262 + outer loop + vertex 1.65927 0.947065 2.45591 + vertex 1.65761 0.949068 2.45756 + vertex 1.65648 0.9454 2.45602 + endloop + endfacet + facet normal 0.349827 -0.465665 0.812882 + outer loop + vertex 1.66264 0.947659 2.4548 + vertex 1.66132 0.949734 2.45656 + vertex 1.65927 0.947065 2.45591 + endloop + endfacet + facet normal 0.307197 -0.440336 0.843643 + outer loop + vertex 1.66132 0.949734 2.45656 + vertex 1.65761 0.949068 2.45756 + vertex 1.65927 0.947065 2.45591 + endloop + endfacet + facet normal 0.302437 -0.347796 0.887451 + outer loop + vertex 1.66132 0.949734 2.45656 + vertex 1.66271 0.953634 2.45761 + vertex 1.65761 0.949068 2.45756 + endloop + endfacet + facet normal 0.350855 -0.0691572 0.933873 + outer loop + vertex 1.66077 1.26312 2.52152 + vertex 1.66079 1.26759 2.52184 + vertex 1.65704 1.26326 2.52293 + endloop + endfacet + facet normal 0.374091 -0.0920402 0.922813 + outer loop + vertex 1.65704 1.26326 2.52293 + vertex 1.66079 1.26759 2.52184 + vertex 1.65709 1.26827 2.52341 + endloop + endfacet + facet normal 0.377645 -0.0732083 0.923052 + outer loop + vertex 1.66079 1.26759 2.52184 + vertex 1.66096 1.27256 2.52216 + vertex 1.65709 1.26827 2.52341 + endloop + endfacet + facet normal 0.402045 -0.0989169 0.910261 + outer loop + vertex 1.65709 1.26827 2.52341 + vertex 1.66096 1.27256 2.52216 + vertex 1.65735 1.27347 2.52386 + endloop + endfacet + facet normal 0.405944 -0.0832169 0.910101 + outer loop + vertex 1.66096 1.27256 2.52216 + vertex 1.66117 1.27772 2.52254 + vertex 1.65735 1.27347 2.52386 + endloop + endfacet + facet normal 0.426791 -0.105662 0.898157 + outer loop + vertex 1.65735 1.27347 2.52386 + vertex 1.66117 1.27772 2.52254 + vertex 1.65743 1.27888 2.52445 + endloop + endfacet + facet normal 0.431862 -0.0883704 0.8976 + outer loop + vertex 1.66117 1.27772 2.52254 + vertex 1.66154 1.28295 2.52288 + vertex 1.65743 1.27888 2.52445 + endloop + endfacet + facet normal 0.452904 -0.114834 0.884133 + outer loop + vertex 1.65743 1.27888 2.52445 + vertex 1.66154 1.28295 2.52288 + vertex 1.65848 1.28447 2.52464 + endloop + endfacet + facet normal 0.464276 -0.0886878 0.881239 + outer loop + vertex 1.66154 1.28295 2.52288 + vertex 1.66191 1.28808 2.5232 + vertex 1.65848 1.28447 2.52464 + endloop + endfacet + facet normal 0.477966 -0.105344 0.872039 + outer loop + vertex 1.65848 1.28447 2.52464 + vertex 1.66191 1.28808 2.5232 + vertex 1.65893 1.28911 2.52496 + endloop + endfacet + facet normal 0.409162 -0.0955538 0.907445 + outer loop + vertex 1.65861 1.29239 2.52545 + vertex 1.65645 1.28978 2.52615 + vertex 1.65893 1.28911 2.52496 + endloop + endfacet + facet normal 0.490984 -0.0816549 0.867334 + outer loop + vertex 1.65861 1.29239 2.52545 + vertex 1.65893 1.28911 2.52496 + vertex 1.66178 1.29336 2.52375 + endloop + endfacet + facet normal 0.486412 -0.0777659 0.870262 + outer loop + vertex 1.66178 1.29336 2.52375 + vertex 1.65893 1.28911 2.52496 + vertex 1.66191 1.28808 2.5232 + endloop + endfacet + facet normal 0.377571 -0.0650639 0.923692 + outer loop + vertex 1.65861 1.29239 2.52545 + vertex 1.65593 1.29293 2.52658 + vertex 1.65645 1.28978 2.52615 + endloop + endfacet + facet normal 0.491836 -0.0546482 0.868971 + outer loop + vertex 1.66178 1.29336 2.52375 + vertex 1.66248 1.2989 2.5237 + vertex 1.6592 1.29614 2.52538 + endloop + endfacet + facet normal 0.486775 -0.0607715 0.871411 + outer loop + vertex 1.65861 1.29239 2.52545 + vertex 1.66178 1.29336 2.52375 + vertex 1.6592 1.29614 2.52538 + endloop + endfacet + facet normal 0.381701 -0.0433311 0.923269 + outer loop + vertex 1.6592 1.29614 2.52538 + vertex 1.65593 1.29293 2.52658 + vertex 1.65861 1.29239 2.52545 + endloop + endfacet + facet normal 0.398166 -0.0631011 0.915141 + outer loop + vertex 1.65596 1.29745 2.52688 + vertex 1.65593 1.29293 2.52658 + vertex 1.6592 1.29614 2.52538 + endloop + endfacet + facet normal 0.496146 -0.0475745 0.866935 + outer loop + vertex 1.66248 1.2989 2.5237 + vertex 1.66278 1.30397 2.5238 + vertex 1.65952 1.30097 2.5255 + endloop + endfacet + facet normal 0.492075 -0.055028 0.868812 + outer loop + vertex 1.6592 1.29614 2.52538 + vertex 1.66248 1.2989 2.5237 + vertex 1.65952 1.30097 2.5255 + endloop + endfacet + facet normal 0.402758 -0.0503029 0.913923 + outer loop + vertex 1.65952 1.30097 2.5255 + vertex 1.65596 1.29745 2.52688 + vertex 1.6592 1.29614 2.52538 + endloop + endfacet + facet normal 0.41775 -0.0685297 0.905974 + outer loop + vertex 1.65612 1.30244 2.52718 + vertex 1.65596 1.29745 2.52688 + vertex 1.65952 1.30097 2.5255 + endloop + endfacet + facet normal 0.507254 -0.0441023 0.860667 + outer loop + vertex 1.66278 1.30397 2.5238 + vertex 1.66296 1.30893 2.52395 + vertex 1.65971 1.30597 2.52571 + endloop + endfacet + facet normal 0.50153 -0.0554633 0.863361 + outer loop + vertex 1.65952 1.30097 2.5255 + vertex 1.66278 1.30397 2.5238 + vertex 1.65971 1.30597 2.52571 + endloop + endfacet + facet normal 0.42319 -0.0541829 0.904419 + outer loop + vertex 1.65971 1.30597 2.52571 + vertex 1.65612 1.30244 2.52718 + vertex 1.65952 1.30097 2.5255 + endloop + endfacet + facet normal 0.436714 -0.071175 0.89678 + outer loop + vertex 1.6563 1.30751 2.5275 + vertex 1.65612 1.30244 2.52718 + vertex 1.65971 1.30597 2.52571 + endloop + endfacet + facet normal 0.523828 -0.047032 0.850525 + outer loop + vertex 1.66296 1.30893 2.52395 + vertex 1.66324 1.31386 2.52405 + vertex 1.65991 1.31095 2.52594 + endloop + endfacet + facet normal 0.517526 -0.059578 0.853591 + outer loop + vertex 1.65971 1.30597 2.52571 + vertex 1.66296 1.30893 2.52395 + vertex 1.65991 1.31095 2.52594 + endloop + endfacet + facet normal 0.441672 -0.058513 0.895266 + outer loop + vertex 1.65991 1.31095 2.52594 + vertex 1.6563 1.30751 2.5275 + vertex 1.65971 1.30597 2.52571 + endloop + endfacet + facet normal 0.455526 -0.0768372 0.8869 + outer loop + vertex 1.65652 1.31259 2.52783 + vertex 1.6563 1.30751 2.5275 + vertex 1.65991 1.31095 2.52594 + endloop + endfacet + facet normal 0.541698 -0.0609836 0.838358 + outer loop + vertex 1.66324 1.31386 2.52405 + vertex 1.66393 1.31917 2.52399 + vertex 1.66027 1.31596 2.52612 + endloop + endfacet + facet normal 0.537421 -0.0691098 0.840478 + outer loop + vertex 1.65991 1.31095 2.52594 + vertex 1.66324 1.31386 2.52405 + vertex 1.66027 1.31596 2.52612 + endloop + endfacet + facet normal 0.460324 -0.0651159 0.88536 + outer loop + vertex 1.66027 1.31596 2.52612 + vertex 1.65652 1.31259 2.52783 + vertex 1.65991 1.31095 2.52594 + endloop + endfacet + facet normal 0.477896 -0.090535 0.873739 + outer loop + vertex 1.65703 1.31779 2.52809 + vertex 1.65652 1.31259 2.52783 + vertex 1.66027 1.31596 2.52612 + endloop + endfacet + facet normal 0.558961 -0.103421 0.822719 + outer loop + vertex 1.66393 1.31917 2.52399 + vertex 1.66372 1.32396 2.52473 + vertex 1.66078 1.32091 2.52635 + endloop + endfacet + facet normal 0.562284 -0.0956171 0.821398 + outer loop + vertex 1.66027 1.31596 2.52612 + vertex 1.66393 1.31917 2.52399 + vertex 1.66078 1.32091 2.52635 + endloop + endfacet + facet normal 0.478438 -0.0893816 0.873561 + outer loop + vertex 1.66078 1.32091 2.52635 + vertex 1.65703 1.31779 2.52809 + vertex 1.66027 1.31596 2.52612 + endloop + endfacet + facet normal 0.489487 -0.107221 0.865394 + outer loop + vertex 1.65801 1.32352 2.52824 + vertex 1.65703 1.31779 2.52809 + vertex 1.66078 1.32091 2.52635 + endloop + endfacet + facet normal 0.569196 -0.118061 0.813681 + outer loop + vertex 1.66372 1.32396 2.52473 + vertex 1.66144 1.32481 2.52645 + vertex 1.66078 1.32091 2.52635 + endloop + endfacet + facet normal 0.490352 -0.106053 0.865048 + outer loop + vertex 1.66144 1.32481 2.52645 + vertex 1.65801 1.32352 2.52824 + vertex 1.66078 1.32091 2.52635 + endloop + endfacet + facet normal 0.489374 -0.102017 0.866086 + outer loop + vertex 1.66144 1.32481 2.52645 + vertex 1.66097 1.32818 2.52711 + vertex 1.65801 1.32352 2.52824 + endloop + endfacet + facet normal 0.475555 -0.0910826 0.874958 + outer loop + vertex 1.66097 1.32818 2.52711 + vertex 1.65739 1.32894 2.52914 + vertex 1.65801 1.32352 2.52824 + endloop + endfacet + facet normal 0.478022 -0.0790665 0.874782 + outer loop + vertex 1.66097 1.32818 2.52711 + vertex 1.66115 1.33294 2.52745 + vertex 1.65739 1.32894 2.52914 + endloop + endfacet + facet normal 0.478505 -0.0796547 0.874465 + outer loop + vertex 1.65739 1.32894 2.52914 + vertex 1.66115 1.33294 2.52745 + vertex 1.65814 1.33459 2.52924 + endloop + endfacet + facet normal 0.487867 -0.058712 0.870941 + outer loop + vertex 1.66115 1.33294 2.52745 + vertex 1.66146 1.33807 2.52762 + vertex 1.65814 1.33459 2.52924 + endloop + endfacet + facet normal 0.486094 -0.0564863 0.872079 + outer loop + vertex 1.65814 1.33459 2.52924 + vertex 1.66146 1.33807 2.52762 + vertex 1.65849 1.33968 2.52938 + endloop + endfacet + facet normal 0.493826 -0.0385209 0.868707 + outer loop + vertex 1.66146 1.33807 2.52762 + vertex 1.66162 1.34311 2.52775 + vertex 1.65849 1.33968 2.52938 + endloop + endfacet + facet normal 0.499064 -0.0448638 0.865403 + outer loop + vertex 1.65849 1.33968 2.52938 + vertex 1.66162 1.34311 2.52775 + vertex 1.6587 1.34458 2.52951 + endloop + endfacet + facet normal 0.505351 -0.0287903 0.862433 + outer loop + vertex 1.66162 1.34311 2.52775 + vertex 1.66165 1.34809 2.5279 + vertex 1.6587 1.34458 2.52951 + endloop + endfacet + facet normal 0.519389 -0.0447235 0.853367 + outer loop + vertex 1.6587 1.34458 2.52951 + vertex 1.66165 1.34809 2.5279 + vertex 1.65882 1.34911 2.52968 + endloop + endfacet + facet normal 0.457526 -0.050364 0.887769 + outer loop + vertex 1.65839 1.35237 2.53008 + vertex 1.65636 1.3497 2.53098 + vertex 1.65882 1.34911 2.52968 + endloop + endfacet + facet normal 0.52248 -0.0374832 0.851827 + outer loop + vertex 1.65839 1.35237 2.53008 + vertex 1.65882 1.34911 2.52968 + vertex 1.66139 1.35338 2.52829 + endloop + endfacet + facet normal 0.521621 -0.0367843 0.852384 + outer loop + vertex 1.66139 1.35338 2.52829 + vertex 1.65882 1.34911 2.52968 + vertex 1.66165 1.34809 2.5279 + endloop + endfacet + facet normal 0.437351 -0.0313528 0.898744 + outer loop + vertex 1.65839 1.35237 2.53008 + vertex 1.65578 1.35287 2.53137 + vertex 1.65636 1.3497 2.53098 + endloop + endfacet + facet normal 0.520303 -0.0434833 0.852874 + outer loop + vertex 1.66139 1.35338 2.52829 + vertex 1.66207 1.35892 2.52816 + vertex 1.65892 1.35615 2.52994 + endloop + endfacet + facet normal 0.523071 -0.0401003 0.851345 + outer loop + vertex 1.65839 1.35237 2.53008 + vertex 1.66139 1.35338 2.52829 + vertex 1.65892 1.35615 2.52994 + endloop + endfacet + facet normal 0.438168 -0.0264716 0.898503 + outer loop + vertex 1.65892 1.35615 2.52994 + vertex 1.65578 1.35287 2.53137 + vertex 1.65839 1.35237 2.53008 + endloop + endfacet + facet normal 0.448397 -0.0387179 0.892996 + outer loop + vertex 1.65575 1.3574 2.53158 + vertex 1.65578 1.35287 2.53137 + vertex 1.65892 1.35615 2.52994 + endloop + endfacet + facet normal 0.517363 -0.0594725 0.853697 + outer loop + vertex 1.66207 1.35892 2.52816 + vertex 1.6625 1.36396 2.52824 + vertex 1.65926 1.36095 2.53 + endloop + endfacet + facet normal 0.523405 -0.0483853 0.850709 + outer loop + vertex 1.65892 1.35615 2.52994 + vertex 1.66207 1.35892 2.52816 + vertex 1.65926 1.36095 2.53 + endloop + endfacet + facet normal 0.446796 -0.043521 0.893577 + outer loop + vertex 1.65926 1.36095 2.53 + vertex 1.65575 1.3574 2.53158 + vertex 1.65892 1.35615 2.52994 + endloop + endfacet + facet normal 0.450519 -0.0481367 0.891468 + outer loop + vertex 1.65592 1.36233 2.53177 + vertex 1.65575 1.3574 2.53158 + vertex 1.65926 1.36095 2.53 + endloop + endfacet + facet normal 0.514484 -0.0431585 0.856413 + outer loop + vertex 1.6625 1.36396 2.52824 + vertex 1.66315 1.36936 2.52813 + vertex 1.65954 1.36592 2.53013 + endloop + endfacet + facet normal 0.511014 -0.050032 0.858115 + outer loop + vertex 1.65926 1.36095 2.53 + vertex 1.6625 1.36396 2.52824 + vertex 1.65954 1.36592 2.53013 + endloop + endfacet + facet normal 0.450739 -0.0475061 0.891391 + outer loop + vertex 1.65954 1.36592 2.53013 + vertex 1.65592 1.36233 2.53177 + vertex 1.65926 1.36095 2.53 + endloop + endfacet + facet normal 0.450533 -0.0472447 0.891509 + outer loop + vertex 1.65606 1.36729 2.53196 + vertex 1.65592 1.36233 2.53177 + vertex 1.65954 1.36592 2.53013 + endloop + endfacet + facet normal 0.51761 -0.0316225 0.855032 + outer loop + vertex 1.66315 1.36936 2.52813 + vertex 1.66282 1.37467 2.52853 + vertex 1.65965 1.37094 2.53031 + endloop + endfacet + facet normal 0.513898 -0.0423129 0.856807 + outer loop + vertex 1.65954 1.36592 2.53013 + vertex 1.66315 1.36936 2.52813 + vertex 1.65965 1.37094 2.53031 + endloop + endfacet + facet normal 0.452216 -0.0421815 0.890911 + outer loop + vertex 1.65965 1.37094 2.53031 + vertex 1.65606 1.36729 2.53196 + vertex 1.65954 1.36592 2.53013 + endloop + endfacet + facet normal 0.450975 -0.0406437 0.891611 + outer loop + vertex 1.65613 1.37224 2.53215 + vertex 1.65606 1.36729 2.53196 + vertex 1.65965 1.37094 2.53031 + endloop + endfacet + facet normal 0.519485 -0.0168223 0.854314 + outer loop + vertex 1.66282 1.37467 2.52853 + vertex 1.66278 1.37964 2.52864 + vertex 1.65964 1.37593 2.53048 + endloop + endfacet + facet normal 0.515708 -0.0294249 0.856259 + outer loop + vertex 1.65965 1.37094 2.53031 + vertex 1.66282 1.37467 2.52853 + vertex 1.65964 1.37593 2.53048 + endloop + endfacet + facet normal 0.45404 -0.0307414 0.890451 + outer loop + vertex 1.65964 1.37593 2.53048 + vertex 1.65613 1.37224 2.53215 + vertex 1.65965 1.37094 2.53031 + endloop + endfacet + facet normal 0.457063 -0.0343825 0.88877 + outer loop + vertex 1.65615 1.3773 2.53233 + vertex 1.65613 1.37224 2.53215 + vertex 1.65964 1.37593 2.53048 + endloop + endfacet + facet normal 0.5289 -0.010747 0.848616 + outer loop + vertex 1.66278 1.37964 2.52864 + vertex 1.66281 1.38457 2.52869 + vertex 1.65972 1.38095 2.53057 + endloop + endfacet + facet normal 0.524966 -0.023201 0.850807 + outer loop + vertex 1.65964 1.37593 2.53048 + vertex 1.66278 1.37964 2.52864 + vertex 1.65972 1.38095 2.53057 + endloop + endfacet + facet normal 0.460776 -0.0228635 0.887222 + outer loop + vertex 1.65972 1.38095 2.53057 + vertex 1.65615 1.3773 2.53233 + vertex 1.65964 1.37593 2.53048 + endloop + endfacet + facet normal 0.469673 -0.0339774 0.882187 + outer loop + vertex 1.65633 1.38255 2.53244 + vertex 1.65615 1.3773 2.53233 + vertex 1.65972 1.38095 2.53057 + endloop + endfacet + facet normal 0.539899 -0.011323 0.841654 + outer loop + vertex 1.66281 1.38457 2.52869 + vertex 1.66267 1.3894 2.52885 + vertex 1.65979 1.386 2.53065 + endloop + endfacet + facet normal 0.536846 -0.0202075 0.843438 + outer loop + vertex 1.65972 1.38095 2.53057 + vertex 1.66281 1.38457 2.52869 + vertex 1.65979 1.386 2.53065 + endloop + endfacet + facet normal 0.475033 -0.0198329 0.879745 + outer loop + vertex 1.65979 1.386 2.53065 + vertex 1.65633 1.38255 2.53244 + vertex 1.65972 1.38095 2.53057 + endloop + endfacet + facet normal 0.486459 -0.0347983 0.87301 + outer loop + vertex 1.65659 1.3878 2.5325 + vertex 1.65633 1.38255 2.53244 + vertex 1.65979 1.386 2.53065 + endloop + endfacet + facet normal 0.547437 -0.00773991 0.836811 + outer loop + vertex 1.66267 1.3894 2.52885 + vertex 1.66218 1.39346 2.5292 + vertex 1.65975 1.39088 2.53077 + endloop + endfacet + facet normal 0.544253 -0.0165433 0.838758 + outer loop + vertex 1.65979 1.386 2.53065 + vertex 1.66267 1.3894 2.52885 + vertex 1.65975 1.39088 2.53077 + endloop + endfacet + facet normal 0.493901 -0.0177601 0.869337 + outer loop + vertex 1.65975 1.39088 2.53077 + vertex 1.65659 1.3878 2.5325 + vertex 1.65979 1.386 2.53065 + endloop + endfacet + facet normal 0.499799 -0.0258095 0.865757 + outer loop + vertex 1.65669 1.39287 2.53259 + vertex 1.65659 1.3878 2.5325 + vertex 1.65975 1.39088 2.53077 + endloop + endfacet + facet normal 0.562429 0.0197799 0.826609 + outer loop + vertex 1.66218 1.39346 2.5292 + vertex 1.66302 1.39801 2.52852 + vertex 1.65978 1.39569 2.53078 + endloop + endfacet + facet normal 0.546039 -0.00585594 0.83774 + outer loop + vertex 1.65975 1.39088 2.53077 + vertex 1.66218 1.39346 2.5292 + vertex 1.65978 1.39569 2.53078 + endloop + endfacet + facet normal 0.509643 -0.0056916 0.860367 + outer loop + vertex 1.65978 1.39569 2.53078 + vertex 1.65669 1.39287 2.53259 + vertex 1.65975 1.39088 2.53077 + endloop + endfacet + facet normal 0.516184 -0.0154284 0.856339 + outer loop + vertex 1.65672 1.39788 2.53267 + vertex 1.65669 1.39287 2.53259 + vertex 1.65978 1.39569 2.53078 + endloop + endfacet + facet normal 0.578173 0.0124386 0.815819 + outer loop + vertex 1.66302 1.39801 2.52852 + vertex 1.66261 1.40363 2.52873 + vertex 1.65979 1.40074 2.53077 + endloop + endfacet + facet normal 0.571683 0.000896447 0.820474 + outer loop + vertex 1.65978 1.39569 2.53078 + vertex 1.66302 1.39801 2.52852 + vertex 1.65979 1.40074 2.53077 + endloop + endfacet + facet normal 0.52486 0.00109092 0.851188 + outer loop + vertex 1.65979 1.40074 2.53077 + vertex 1.65672 1.39788 2.53267 + vertex 1.65978 1.39569 2.53078 + endloop + endfacet + facet normal 0.5322 -0.00987227 0.846561 + outer loop + vertex 1.6567 1.40292 2.53274 + vertex 1.65672 1.39788 2.53267 + vertex 1.65979 1.40074 2.53077 + endloop + endfacet + facet normal 0.590055 0.00424998 0.807352 + outer loop + vertex 1.66261 1.40363 2.52873 + vertex 1.66247 1.40881 2.5288 + vertex 1.65968 1.40592 2.53086 + endloop + endfacet + facet normal 0.587335 -0.00109431 0.809343 + outer loop + vertex 1.65979 1.40074 2.53077 + vertex 1.66261 1.40363 2.52873 + vertex 1.65968 1.40592 2.53086 + endloop + endfacet + facet normal 0.535802 -0.0027608 0.844339 + outer loop + vertex 1.65968 1.40592 2.53086 + vertex 1.6567 1.40292 2.53274 + vertex 1.65979 1.40074 2.53077 + endloop + endfacet + facet normal 0.543114 -0.0130059 0.839558 + outer loop + vertex 1.65673 1.40793 2.5328 + vertex 1.6567 1.40292 2.53274 + vertex 1.65968 1.40592 2.53086 + endloop + endfacet + facet normal 0.600123 -0.00329 0.799901 + outer loop + vertex 1.66247 1.40881 2.5288 + vertex 1.66246 1.41386 2.52883 + vertex 1.65967 1.41097 2.53091 + endloop + endfacet + facet normal 0.597995 -0.00757755 0.801464 + outer loop + vertex 1.65968 1.40592 2.53086 + vertex 1.66247 1.40881 2.5288 + vertex 1.65967 1.41097 2.53091 + endloop + endfacet + facet normal 0.545498 -0.0080931 0.838073 + outer loop + vertex 1.65967 1.41097 2.53091 + vertex 1.65673 1.40793 2.5328 + vertex 1.65968 1.40592 2.53086 + endloop + endfacet + facet normal 0.553936 -0.0198223 0.832323 + outer loop + vertex 1.65681 1.4129 2.53287 + vertex 1.65673 1.40793 2.5328 + vertex 1.65967 1.41097 2.53091 + endloop + endfacet + facet normal 0.611413 -0.00336265 0.791305 + outer loop + vertex 1.66246 1.41386 2.52883 + vertex 1.66246 1.41886 2.52885 + vertex 1.65969 1.41598 2.53098 + endloop + endfacet + facet normal 0.606649 -0.0132215 0.79486 + outer loop + vertex 1.65967 1.41097 2.53091 + vertex 1.66246 1.41386 2.52883 + vertex 1.65969 1.41598 2.53098 + endloop + endfacet + facet normal 0.556898 -0.0135575 0.83047 + outer loop + vertex 1.65969 1.41598 2.53098 + vertex 1.65681 1.4129 2.53287 + vertex 1.65967 1.41097 2.53091 + endloop + endfacet + facet normal 0.561583 -0.0199588 0.82718 + outer loop + vertex 1.65675 1.41791 2.53303 + vertex 1.65681 1.4129 2.53287 + vertex 1.65969 1.41598 2.53098 + endloop + endfacet + facet normal 0.6184 0.00154761 0.785862 + outer loop + vertex 1.66246 1.41886 2.52885 + vertex 1.66245 1.42384 2.52885 + vertex 1.6596 1.42108 2.5311 + endloop + endfacet + facet normal 0.614055 -0.00744432 0.789228 + outer loop + vertex 1.65969 1.41598 2.53098 + vertex 1.66246 1.41886 2.52885 + vertex 1.6596 1.42108 2.5311 + endloop + endfacet + facet normal 0.566539 -0.00904281 0.823985 + outer loop + vertex 1.6596 1.42108 2.5311 + vertex 1.65675 1.41791 2.53303 + vertex 1.65969 1.41598 2.53098 + endloop + endfacet + facet normal 0.564307 -0.00609 0.825542 + outer loop + vertex 1.6561 1.42363 2.53351 + vertex 1.65675 1.41791 2.53303 + vertex 1.6596 1.42108 2.5311 + endloop + endfacet + facet normal 0.626602 0.00914465 0.779286 + outer loop + vertex 1.66245 1.42384 2.52885 + vertex 1.66242 1.42878 2.52882 + vertex 1.65969 1.42616 2.53104 + endloop + endfacet + facet normal 0.620718 -0.00233999 0.78403 + outer loop + vertex 1.6596 1.42108 2.5311 + vertex 1.66245 1.42384 2.52885 + vertex 1.65969 1.42616 2.53104 + endloop + endfacet + facet normal 0.56684 -0.000976678 0.823827 + outer loop + vertex 1.65969 1.42616 2.53104 + vertex 1.6561 1.42363 2.53351 + vertex 1.6596 1.42108 2.5311 + endloop + endfacet + facet normal 0.57308 -0.0141755 0.819377 + outer loop + vertex 1.65746 1.42855 2.53264 + vertex 1.6561 1.42363 2.53351 + vertex 1.65969 1.42616 2.53104 + endloop + endfacet + facet normal 0.63641 0.0151941 0.771202 + outer loop + vertex 1.66242 1.42878 2.52882 + vertex 1.66234 1.4337 2.52879 + vertex 1.65979 1.431 2.53095 + endloop + endfacet + facet normal 0.630234 0.00291108 0.7764 + outer loop + vertex 1.65969 1.42616 2.53104 + vertex 1.66242 1.42878 2.52882 + vertex 1.65979 1.431 2.53095 + endloop + endfacet + facet normal 0.58636 0.00447344 0.810038 + outer loop + vertex 1.65979 1.431 2.53095 + vertex 1.65746 1.42855 2.53264 + vertex 1.65969 1.42616 2.53104 + endloop + endfacet + facet normal 0.580954 0.0122122 0.813845 + outer loop + vertex 1.65704 1.43281 2.53288 + vertex 1.65746 1.42855 2.53264 + vertex 1.65979 1.431 2.53095 + endloop + endfacet + facet normal 0.638267 0.0114366 0.76973 + outer loop + vertex 1.66234 1.4337 2.52879 + vertex 1.66226 1.43865 2.52878 + vertex 1.65964 1.43587 2.53099 + endloop + endfacet + facet normal 0.638484 0.0118975 0.769543 + outer loop + vertex 1.65979 1.431 2.53095 + vertex 1.66234 1.4337 2.52879 + vertex 1.65964 1.43587 2.53099 + endloop + endfacet + facet normal 0.579868 0.00969823 0.814653 + outer loop + vertex 1.65964 1.43587 2.53099 + vertex 1.65704 1.43281 2.53288 + vertex 1.65979 1.431 2.53095 + endloop + endfacet + facet normal 0.578711 0.0111752 0.815456 + outer loop + vertex 1.65681 1.43778 2.53297 + vertex 1.65704 1.43281 2.53288 + vertex 1.65964 1.43587 2.53099 + endloop + endfacet + facet normal 0.639872 0.0103978 0.768411 + outer loop + vertex 1.66226 1.43865 2.52878 + vertex 1.66221 1.44365 2.52875 + vertex 1.65954 1.44088 2.53101 + endloop + endfacet + facet normal 0.639462 0.00954494 0.768763 + outer loop + vertex 1.65964 1.43587 2.53099 + vertex 1.66226 1.43865 2.52878 + vertex 1.65954 1.44088 2.53101 + endloop + endfacet + facet normal 0.577352 0.00814077 0.816455 + outer loop + vertex 1.65954 1.44088 2.53101 + vertex 1.65681 1.43778 2.53297 + vertex 1.65964 1.43587 2.53099 + endloop + endfacet + facet normal 0.580388 0.00412325 0.81433 + outer loop + vertex 1.65673 1.44282 2.53301 + vertex 1.65681 1.43778 2.53297 + vertex 1.65954 1.44088 2.53101 + endloop + endfacet + facet normal 0.642797 0.00608761 0.766012 + outer loop + vertex 1.66221 1.44365 2.52875 + vertex 1.66219 1.44869 2.52873 + vertex 1.65949 1.44594 2.53101 + endloop + endfacet + facet normal 0.642671 0.00583045 0.76612 + outer loop + vertex 1.65954 1.44088 2.53101 + vertex 1.66221 1.44365 2.52875 + vertex 1.65949 1.44594 2.53101 + endloop + endfacet + facet normal 0.580897 0.0052414 0.81396 + outer loop + vertex 1.65949 1.44594 2.53101 + vertex 1.65673 1.44282 2.53301 + vertex 1.65954 1.44088 2.53101 + endloop + endfacet + facet normal 0.583987 0.00109512 0.811762 + outer loop + vertex 1.65665 1.44783 2.53306 + vertex 1.65673 1.44282 2.53301 + vertex 1.65949 1.44594 2.53101 + endloop + endfacet + facet normal 0.642824 0.00479608 0.765999 + outer loop + vertex 1.66219 1.44869 2.52873 + vertex 1.66216 1.45377 2.52872 + vertex 1.65941 1.45108 2.53105 + endloop + endfacet + facet normal 0.643165 0.00547481 0.765708 + outer loop + vertex 1.65949 1.44594 2.53101 + vertex 1.66219 1.44869 2.52873 + vertex 1.65941 1.45108 2.53105 + endloop + endfacet + facet normal 0.585354 0.00422224 0.810767 + outer loop + vertex 1.65941 1.45108 2.53105 + vertex 1.65665 1.44783 2.53306 + vertex 1.65949 1.44594 2.53101 + endloop + endfacet + facet normal 0.585064 0.00459784 0.810974 + outer loop + vertex 1.65622 1.45315 2.53334 + vertex 1.65665 1.44783 2.53306 + vertex 1.65941 1.45108 2.53105 + endloop + endfacet + facet normal 0.642735 0.0103637 0.766018 + outer loop + vertex 1.66216 1.45377 2.52872 + vertex 1.6621 1.45884 2.5287 + vertex 1.65938 1.45633 2.53102 + endloop + endfacet + facet normal 0.641227 0.00756812 0.767314 + outer loop + vertex 1.65941 1.45108 2.53105 + vertex 1.66216 1.45377 2.52872 + vertex 1.65938 1.45633 2.53102 + endloop + endfacet + facet normal 0.586273 0.00744657 0.81008 + outer loop + vertex 1.65938 1.45633 2.53102 + vertex 1.65622 1.45315 2.53334 + vertex 1.65941 1.45108 2.53105 + endloop + endfacet + facet normal 0.588661 0.00383681 0.808371 + outer loop + vertex 1.65662 1.45882 2.53302 + vertex 1.65622 1.45315 2.53334 + vertex 1.65938 1.45633 2.53102 + endloop + endfacet + facet normal 0.643616 0.018273 0.765131 + outer loop + vertex 1.6621 1.45884 2.5287 + vertex 1.662 1.46387 2.52867 + vertex 1.65938 1.46154 2.53093 + endloop + endfacet + facet normal 0.640946 0.013647 0.767465 + outer loop + vertex 1.65938 1.45633 2.53102 + vertex 1.6621 1.45884 2.5287 + vertex 1.65938 1.46154 2.53093 + endloop + endfacet + facet normal 0.594765 0.0143084 0.803772 + outer loop + vertex 1.65938 1.46154 2.53093 + vertex 1.65662 1.45882 2.53302 + vertex 1.65938 1.45633 2.53102 + endloop + endfacet + facet normal 0.593939 0.0155955 0.804359 + outer loop + vertex 1.65665 1.46398 2.5329 + vertex 1.65662 1.45882 2.53302 + vertex 1.65938 1.46154 2.53093 + endloop + endfacet + facet normal 0.641158 0.023076 0.767061 + outer loop + vertex 1.662 1.46387 2.52867 + vertex 1.66188 1.46884 2.52862 + vertex 1.65928 1.46659 2.53086 + endloop + endfacet + facet normal 0.641119 0.0230079 0.767097 + outer loop + vertex 1.65938 1.46154 2.53093 + vertex 1.662 1.46387 2.52867 + vertex 1.65928 1.46659 2.53086 + endloop + endfacet + facet normal 0.597924 0.0225879 0.801234 + outer loop + vertex 1.65928 1.46659 2.53086 + vertex 1.65665 1.46398 2.5329 + vertex 1.65938 1.46154 2.53093 + endloop + endfacet + facet normal 0.59866 0.0214432 0.800716 + outer loop + vertex 1.65655 1.46901 2.53283 + vertex 1.65665 1.46398 2.5329 + vertex 1.65928 1.46659 2.53086 + endloop + endfacet + facet normal 0.637388 0.0191962 0.770304 + outer loop + vertex 1.66188 1.46884 2.52862 + vertex 1.66179 1.47381 2.52857 + vertex 1.65915 1.47158 2.53081 + endloop + endfacet + facet normal 0.640464 0.0244177 0.7676 + outer loop + vertex 1.65928 1.46659 2.53086 + vertex 1.66188 1.46884 2.52862 + vertex 1.65915 1.47158 2.53081 + endloop + endfacet + facet normal 0.599977 0.0237835 0.799664 + outer loop + vertex 1.65915 1.47158 2.53081 + vertex 1.65655 1.46901 2.53283 + vertex 1.65928 1.46659 2.53086 + endloop + endfacet + facet normal 0.603589 0.0180946 0.79709 + outer loop + vertex 1.65646 1.474 2.53279 + vertex 1.65655 1.46901 2.53283 + vertex 1.65915 1.47158 2.53081 + endloop + endfacet + facet normal 0.634996 0.010577 0.772443 + outer loop + vertex 1.66179 1.47381 2.52857 + vertex 1.66175 1.47879 2.52853 + vertex 1.65907 1.47656 2.53077 + endloop + endfacet + facet normal 0.63866 0.0166935 0.769308 + outer loop + vertex 1.65915 1.47158 2.53081 + vertex 1.66179 1.47381 2.52857 + vertex 1.65907 1.47656 2.53077 + endloop + endfacet + facet normal 0.602601 0.0163576 0.797875 + outer loop + vertex 1.65907 1.47656 2.53077 + vertex 1.65646 1.474 2.53279 + vertex 1.65915 1.47158 2.53081 + endloop + endfacet + facet normal 0.605599 0.0115604 0.795686 + outer loop + vertex 1.65641 1.47898 2.53276 + vertex 1.65646 1.474 2.53279 + vertex 1.65907 1.47656 2.53077 + endloop + endfacet + facet normal 0.633752 0.00613868 0.773512 + outer loop + vertex 1.66175 1.47879 2.52853 + vertex 1.66173 1.48379 2.52851 + vertex 1.65903 1.48155 2.53074 + endloop + endfacet + facet normal 0.635647 0.00927893 0.771924 + outer loop + vertex 1.65907 1.47656 2.53077 + vertex 1.66175 1.47879 2.52853 + vertex 1.65903 1.48155 2.53074 + endloop + endfacet + facet normal 0.604224 0.00916346 0.796762 + outer loop + vertex 1.65903 1.48155 2.53074 + vertex 1.65641 1.47898 2.53276 + vertex 1.65907 1.47656 2.53077 + endloop + endfacet + facet normal 0.605513 0.00708575 0.795804 + outer loop + vertex 1.65637 1.48398 2.53274 + vertex 1.65641 1.47898 2.53276 + vertex 1.65903 1.48155 2.53074 + endloop + endfacet + facet normal 0.631779 0.0077527 0.77511 + outer loop + vertex 1.66173 1.48379 2.52851 + vertex 1.66169 1.48878 2.52849 + vertex 1.65899 1.48654 2.53071 + endloop + endfacet + facet normal 0.632412 0.0088103 0.774582 + outer loop + vertex 1.65903 1.48155 2.53074 + vertex 1.66173 1.48379 2.52851 + vertex 1.65899 1.48654 2.53071 + endloop + endfacet + facet normal 0.606435 0.00868839 0.795085 + outer loop + vertex 1.65899 1.48654 2.53071 + vertex 1.65637 1.48398 2.53274 + vertex 1.65903 1.48155 2.53074 + endloop + endfacet + facet normal 0.604668 0.0115433 0.796394 + outer loop + vertex 1.65631 1.48896 2.53272 + vertex 1.65637 1.48398 2.53274 + vertex 1.65899 1.48654 2.53071 + endloop + endfacet + facet normal 0.628527 0.0165143 0.777613 + outer loop + vertex 1.66169 1.48878 2.52849 + vertex 1.66161 1.49374 2.52846 + vertex 1.65892 1.4915 2.53068 + endloop + endfacet + facet normal 0.627895 0.0154425 0.778145 + outer loop + vertex 1.65899 1.48654 2.53071 + vertex 1.66169 1.48878 2.52849 + vertex 1.65892 1.4915 2.53068 + endloop + endfacet + facet normal 0.606774 0.0152474 0.794728 + outer loop + vertex 1.65892 1.4915 2.53068 + vertex 1.65631 1.48896 2.53272 + vertex 1.65899 1.48654 2.53071 + endloop + endfacet + facet normal 0.605055 0.0180135 0.79598 + outer loop + vertex 1.65626 1.49393 2.53264 + vertex 1.65631 1.48896 2.53272 + vertex 1.65892 1.4915 2.53068 + endloop + endfacet + facet normal 0.623373 0.0190906 0.781692 + outer loop + vertex 1.66161 1.49374 2.52846 + vertex 1.66146 1.49872 2.52845 + vertex 1.65882 1.49639 2.53061 + endloop + endfacet + facet normal 0.625396 0.0226132 0.77998 + outer loop + vertex 1.65892 1.4915 2.53068 + vertex 1.66161 1.49374 2.52846 + vertex 1.65882 1.49639 2.53061 + endloop + endfacet + facet normal 0.607592 0.0224528 0.793932 + outer loop + vertex 1.65882 1.49639 2.53061 + vertex 1.65626 1.49393 2.53264 + vertex 1.65892 1.4915 2.53068 + endloop + endfacet + facet normal 0.60916 0.0198839 0.792798 + outer loop + vertex 1.65631 1.49878 2.53249 + vertex 1.65626 1.49393 2.53264 + vertex 1.65882 1.49639 2.53061 + endloop + endfacet + facet normal 0.617409 0.00804781 0.786601 + outer loop + vertex 1.66146 1.49872 2.52845 + vertex 1.66116 1.5041 2.52863 + vertex 1.65871 1.501 2.53059 + endloop + endfacet + facet normal 0.623169 0.0194639 0.781845 + outer loop + vertex 1.65882 1.49639 2.53061 + vertex 1.66146 1.49872 2.52845 + vertex 1.65871 1.501 2.53059 + endloop + endfacet + facet normal 0.608728 0.0191557 0.793148 + outer loop + vertex 1.65871 1.501 2.53059 + vertex 1.65631 1.49878 2.53249 + vertex 1.65882 1.49639 2.53061 + endloop + endfacet + facet normal 0.61193 0.0136886 0.790793 + outer loop + vertex 1.65664 1.50265 2.53216 + vertex 1.65631 1.49878 2.53249 + vertex 1.65871 1.501 2.53059 + endloop + endfacet + facet normal 0.616688 0.00896925 0.787156 + outer loop + vertex 1.65828 1.5047 2.53088 + vertex 1.65871 1.501 2.53059 + vertex 1.66116 1.5041 2.52863 + endloop + endfacet + facet normal 0.615145 -0.00315537 0.788407 + outer loop + vertex 1.65828 1.5047 2.53088 + vertex 1.66116 1.5041 2.52863 + vertex 1.65908 1.50888 2.53028 + endloop + endfacet + facet normal 0.618219 -0.000989572 0.786005 + outer loop + vertex 1.65908 1.50888 2.53028 + vertex 1.66116 1.5041 2.52863 + vertex 1.66213 1.5084 2.52787 + endloop + endfacet + facet normal 0.608911 0.00760491 0.793202 + outer loop + vertex 1.65871 1.501 2.53059 + vertex 1.65828 1.5047 2.53088 + vertex 1.65664 1.50265 2.53216 + endloop + endfacet + facet normal 0.618508 0.00200265 0.785776 + outer loop + vertex 1.66213 1.5084 2.52787 + vertex 1.66154 1.51269 2.52833 + vertex 1.65908 1.50888 2.53028 + endloop + endfacet + facet normal 0.610669 0.0101783 0.791821 + outer loop + vertex 1.65908 1.50888 2.53028 + vertex 1.66154 1.51269 2.52833 + vertex 1.65861 1.51418 2.53057 + endloop + endfacet + facet normal 0.606455 0.0193796 0.794882 + outer loop + vertex 1.65807 1.51742 2.5309 + vertex 1.65665 1.51567 2.53203 + vertex 1.65861 1.51418 2.53057 + endloop + endfacet + facet normal 0.590535 0.0154599 0.806864 + outer loop + vertex 1.65807 1.51742 2.5309 + vertex 1.65861 1.51418 2.53057 + vertex 1.66072 1.51848 2.52894 + endloop + endfacet + facet normal 0.60806 0.00196307 0.793889 + outer loop + vertex 1.66072 1.51848 2.52894 + vertex 1.65861 1.51418 2.53057 + vertex 1.66154 1.51269 2.52833 + endloop + endfacet + facet normal 0.614559 0.00885568 0.788822 + outer loop + vertex 1.65807 1.51742 2.5309 + vertex 1.65661 1.51825 2.53203 + vertex 1.65665 1.51567 2.53203 + endloop + endfacet + facet normal 0.597273 -0.010355 0.801971 + outer loop + vertex 1.65808 1.51993 2.53093 + vertex 1.65807 1.51742 2.5309 + vertex 1.66072 1.51848 2.52894 + endloop + endfacet + facet normal 0.593617 -0.0204981 0.804486 + outer loop + vertex 1.65808 1.51993 2.53093 + vertex 1.66072 1.51848 2.52894 + vertex 1.65907 1.52373 2.53029 + endloop + endfacet + facet normal 0.610459 -0.0119618 0.791958 + outer loop + vertex 1.65907 1.52373 2.53029 + vertex 1.66072 1.51848 2.52894 + vertex 1.66206 1.52325 2.52798 + endloop + endfacet + facet normal 0.607714 -0.0103299 0.794089 + outer loop + vertex 1.65807 1.51742 2.5309 + vertex 1.65808 1.51993 2.53093 + vertex 1.65661 1.51825 2.53203 + endloop + endfacet + facet normal 0.611449 -0.00267113 0.79128 + outer loop + vertex 1.66206 1.52325 2.52798 + vertex 1.6617 1.52755 2.52828 + vertex 1.65907 1.52373 2.53029 + endloop + endfacet + facet normal 0.613884 -0.00535127 0.789378 + outer loop + vertex 1.65907 1.52373 2.53029 + vertex 1.6617 1.52755 2.52828 + vertex 1.65883 1.5293 2.53051 + endloop + endfacet + facet normal 0.61979 0.010342 0.784699 + outer loop + vertex 1.6617 1.52755 2.52828 + vertex 1.66153 1.53257 2.52834 + vertex 1.65883 1.5293 2.53051 + endloop + endfacet + facet normal 0.621976 0.00741351 0.783002 + outer loop + vertex 1.65883 1.5293 2.53051 + vertex 1.66153 1.53257 2.52834 + vertex 1.65874 1.53443 2.53054 + endloop + endfacet + facet normal 0.624786 0.0143817 0.780664 + outer loop + vertex 1.66153 1.53257 2.52834 + vertex 1.66148 1.5376 2.52829 + vertex 1.65874 1.53443 2.53054 + endloop + endfacet + facet normal 0.628262 0.00944805 0.777944 + outer loop + vertex 1.65874 1.53443 2.53054 + vertex 1.66148 1.5376 2.52829 + vertex 1.65874 1.53945 2.53048 + endloop + endfacet + facet normal 0.628555 0.0101691 0.777699 + outer loop + vertex 1.66148 1.5376 2.52829 + vertex 1.6615 1.54258 2.52821 + vertex 1.65874 1.53945 2.53048 + endloop + endfacet + facet normal 0.632495 0.00440573 0.774552 + outer loop + vertex 1.65874 1.53945 2.53048 + vertex 1.6615 1.54258 2.52821 + vertex 1.65876 1.54445 2.53044 + endloop + endfacet + facet normal 0.631399 0.00172482 0.775456 + outer loop + vertex 1.6615 1.54258 2.52821 + vertex 1.66152 1.54755 2.52818 + vertex 1.65876 1.54445 2.53044 + endloop + endfacet + facet normal 0.63244 0.00018036 0.774609 + outer loop + vertex 1.65876 1.54445 2.53044 + vertex 1.66152 1.54755 2.52818 + vertex 1.65873 1.54946 2.53046 + endloop + endfacet + facet normal 0.631198 -0.00284161 0.775617 + outer loop + vertex 1.66152 1.54755 2.52818 + vertex 1.66147 1.55257 2.52824 + vertex 1.65873 1.54946 2.53046 + endloop + endfacet + facet normal 0.630862 -0.00235094 0.775891 + outer loop + vertex 1.65873 1.54946 2.53046 + vertex 1.66147 1.55257 2.52824 + vertex 1.6587 1.55425 2.53049 + endloop + endfacet + facet normal 0.623202 -0.00831818 0.782017 + outer loop + vertex 1.65833 1.55785 2.53083 + vertex 1.65669 1.55577 2.53211 + vertex 1.6587 1.55425 2.53049 + endloop + endfacet + facet normal 0.625711 -0.00787515 0.780015 + outer loop + vertex 1.65833 1.55785 2.53083 + vertex 1.6587 1.55425 2.53049 + vertex 1.6611 1.55801 2.52861 + endloop + endfacet + facet normal 0.62796 -0.0102296 0.778178 + outer loop + vertex 1.6611 1.55801 2.52861 + vertex 1.6587 1.55425 2.53049 + vertex 1.66147 1.55257 2.52824 + endloop + endfacet + facet normal 0.626822 -0.0130284 0.779053 + outer loop + vertex 1.65833 1.55785 2.53083 + vertex 1.65634 1.5593 2.53245 + vertex 1.65669 1.55577 2.53211 + endloop + endfacet + facet normal 0.628392 -0.0216156 0.777596 + outer loop + vertex 1.6611 1.55801 2.52861 + vertex 1.66161 1.56351 2.52835 + vertex 1.65878 1.56153 2.53058 + endloop + endfacet + facet normal 0.626128 -0.0240925 0.779348 + outer loop + vertex 1.65833 1.55785 2.53083 + vertex 1.6611 1.55801 2.52861 + vertex 1.65878 1.56153 2.53058 + endloop + endfacet + facet normal 0.62212 -0.0233913 0.782572 + outer loop + vertex 1.65878 1.56153 2.53058 + vertex 1.65634 1.5593 2.53245 + vertex 1.65833 1.55785 2.53083 + endloop + endfacet + facet normal 0.62023 -0.0199749 0.784166 + outer loop + vertex 1.65625 1.56388 2.53264 + vertex 1.65634 1.5593 2.53245 + vertex 1.65878 1.56153 2.53058 + endloop + endfacet + facet normal 0.631784 -0.0244513 0.774758 + outer loop + vertex 1.66161 1.56351 2.52835 + vertex 1.66182 1.56859 2.52834 + vertex 1.65895 1.56637 2.53061 + endloop + endfacet + facet normal 0.630422 -0.0265409 0.775799 + outer loop + vertex 1.65878 1.56153 2.53058 + vertex 1.66161 1.56351 2.52835 + vertex 1.65895 1.56637 2.53061 + endloop + endfacet + facet normal 0.616674 -0.0261078 0.786785 + outer loop + vertex 1.65895 1.56637 2.53061 + vertex 1.65625 1.56388 2.53264 + vertex 1.65878 1.56153 2.53058 + endloop + endfacet + facet normal 0.613816 -0.0210493 0.789169 + outer loop + vertex 1.65605 1.56926 2.53294 + vertex 1.65625 1.56388 2.53264 + vertex 1.65895 1.56637 2.53061 + endloop + endfacet + facet normal 0.63446 -0.0238573 0.772587 + outer loop + vertex 1.66182 1.56859 2.52834 + vertex 1.66199 1.57357 2.52836 + vertex 1.65919 1.57128 2.53058 + endloop + endfacet + facet normal 0.632765 -0.0266037 0.773887 + outer loop + vertex 1.65895 1.56637 2.53061 + vertex 1.66182 1.56859 2.52834 + vertex 1.65919 1.57128 2.53058 + endloop + endfacet + facet normal 0.611057 -0.0254335 0.791178 + outer loop + vertex 1.65919 1.57128 2.53058 + vertex 1.65605 1.56926 2.53294 + vertex 1.65895 1.56637 2.53061 + endloop + endfacet + facet normal 0.612026 -0.0279257 0.790344 + outer loop + vertex 1.6571 1.57369 2.53228 + vertex 1.65605 1.56926 2.53294 + vertex 1.65919 1.57128 2.53058 + endloop + endfacet + facet normal 0.636594 -0.0243391 0.770815 + outer loop + vertex 1.66199 1.57357 2.52836 + vertex 1.66211 1.57853 2.52841 + vertex 1.65939 1.57599 2.53058 + endloop + endfacet + facet normal 0.635571 -0.0261618 0.771599 + outer loop + vertex 1.65919 1.57128 2.53058 + vertex 1.66199 1.57357 2.52836 + vertex 1.65939 1.57599 2.53058 + endloop + endfacet + facet normal 0.613943 -0.0252782 0.788945 + outer loop + vertex 1.65939 1.57599 2.53058 + vertex 1.6571 1.57369 2.53228 + vertex 1.65919 1.57128 2.53058 + endloop + endfacet + facet normal 0.613263 -0.024184 0.789508 + outer loop + vertex 1.65671 1.57773 2.53271 + vertex 1.6571 1.57369 2.53228 + vertex 1.65939 1.57599 2.53058 + endloop + endfacet + facet normal 0.637039 -0.0226753 0.770498 + outer loop + vertex 1.66211 1.57853 2.52841 + vertex 1.66219 1.58354 2.52849 + vertex 1.65935 1.58084 2.53076 + endloop + endfacet + facet normal 0.636386 -0.0239608 0.770998 + outer loop + vertex 1.65939 1.57599 2.53058 + vertex 1.66211 1.57853 2.52841 + vertex 1.65935 1.58084 2.53076 + endloop + endfacet + facet normal 0.612995 -0.0248271 0.789696 + outer loop + vertex 1.65935 1.58084 2.53076 + vertex 1.65671 1.57773 2.53271 + vertex 1.65939 1.57599 2.53058 + endloop + endfacet + facet normal 0.608887 -0.0192476 0.793023 + outer loop + vertex 1.65619 1.58286 2.53323 + vertex 1.65671 1.57773 2.53271 + vertex 1.65935 1.58084 2.53076 + endloop + endfacet + facet normal 0.636116 -0.0165558 0.771416 + outer loop + vertex 1.66219 1.58354 2.52849 + vertex 1.66225 1.58858 2.52855 + vertex 1.6594 1.586 2.53085 + endloop + endfacet + facet normal 0.634899 -0.0188503 0.772365 + outer loop + vertex 1.65935 1.58084 2.53076 + vertex 1.66219 1.58354 2.52849 + vertex 1.6594 1.586 2.53085 + endloop + endfacet + facet normal 0.609006 -0.0189583 0.792939 + outer loop + vertex 1.6594 1.586 2.53085 + vertex 1.65619 1.58286 2.53323 + vertex 1.65935 1.58084 2.53076 + endloop + endfacet + facet normal 0.60383 -0.0105514 0.797043 + outer loop + vertex 1.65655 1.58852 2.53304 + vertex 1.65619 1.58286 2.53323 + vertex 1.6594 1.586 2.53085 + endloop + endfacet + facet normal 0.631198 -0.00886326 0.775571 + outer loop + vertex 1.66225 1.58858 2.52855 + vertex 1.66229 1.59355 2.52857 + vertex 1.65949 1.59122 2.53083 + endloop + endfacet + facet normal 0.631605 -0.00815684 0.775248 + outer loop + vertex 1.6594 1.586 2.53085 + vertex 1.66225 1.58858 2.52855 + vertex 1.65949 1.59122 2.53083 + endloop + endfacet + facet normal 0.605462 -0.00765802 0.795838 + outer loop + vertex 1.65949 1.59122 2.53083 + vertex 1.65655 1.58852 2.53304 + vertex 1.6594 1.586 2.53085 + endloop + endfacet + facet normal 0.598944 0.00347588 0.800783 + outer loop + vertex 1.65642 1.59417 2.53311 + vertex 1.65655 1.58852 2.53304 + vertex 1.65949 1.59122 2.53083 + endloop + endfacet + facet normal 0.625522 -0.00210413 0.780204 + outer loop + vertex 1.66229 1.59355 2.52857 + vertex 1.66232 1.59845 2.52856 + vertex 1.65964 1.59617 2.53071 + endloop + endfacet + facet normal 0.626769 -2.13453e-05 0.779205 + outer loop + vertex 1.65949 1.59122 2.53083 + vertex 1.66229 1.59355 2.52857 + vertex 1.65964 1.59617 2.53071 + endloop + endfacet + facet normal 0.597676 0.00141866 0.801736 + outer loop + vertex 1.65964 1.59617 2.53071 + vertex 1.65642 1.59417 2.53311 + vertex 1.65949 1.59122 2.53083 + endloop + endfacet + facet normal 0.599708 -0.00368425 0.800211 + outer loop + vertex 1.65745 1.59862 2.53236 + vertex 1.65642 1.59417 2.53311 + vertex 1.65964 1.59617 2.53071 + endloop + endfacet + facet normal 0.621596 -0.00396565 0.783328 + outer loop + vertex 1.66232 1.59845 2.52856 + vertex 1.66234 1.60339 2.52857 + vertex 1.65971 1.60085 2.53065 + endloop + endfacet + facet normal 0.624141 0.000562668 0.781311 + outer loop + vertex 1.65964 1.59617 2.53071 + vertex 1.66232 1.59845 2.52856 + vertex 1.65971 1.60085 2.53065 + endloop + endfacet + facet normal 0.60312 0.00108878 0.797649 + outer loop + vertex 1.65971 1.60085 2.53065 + vertex 1.65745 1.59862 2.53236 + vertex 1.65964 1.59617 2.53071 + endloop + endfacet + facet normal 0.601526 0.00361498 0.798845 + outer loop + vertex 1.65692 1.60265 2.53274 + vertex 1.65745 1.59862 2.53236 + vertex 1.65971 1.60085 2.53065 + endloop + endfacet + facet normal 0.616441 -0.00823371 0.787358 + outer loop + vertex 1.66234 1.60339 2.52857 + vertex 1.66239 1.60847 2.52859 + vertex 1.65954 1.60572 2.53079 + endloop + endfacet + facet normal 0.620014 -0.00129605 0.784589 + outer loop + vertex 1.65971 1.60085 2.53065 + vertex 1.66234 1.60339 2.52857 + vertex 1.65954 1.60572 2.53079 + endloop + endfacet + facet normal 0.599004 -0.00249913 0.800742 + outer loop + vertex 1.65954 1.60572 2.53079 + vertex 1.65692 1.60265 2.53274 + vertex 1.65971 1.60085 2.53065 + endloop + endfacet + facet normal 0.592521 0.00608667 0.805532 + outer loop + vertex 1.65618 1.6078 2.53325 + vertex 1.65692 1.60265 2.53274 + vertex 1.65954 1.60572 2.53079 + endloop + endfacet + facet normal 0.607523 -0.00974873 0.794242 + outer loop + vertex 1.66239 1.60847 2.52859 + vertex 1.66254 1.61361 2.52853 + vertex 1.65951 1.61098 2.53082 + endloop + endfacet + facet normal 0.612214 -0.0011991 0.790691 + outer loop + vertex 1.65954 1.60572 2.53079 + vertex 1.66239 1.60847 2.52859 + vertex 1.65951 1.61098 2.53082 + endloop + endfacet + facet normal 0.589492 -0.00144487 0.807773 + outer loop + vertex 1.65951 1.61098 2.53082 + vertex 1.65618 1.6078 2.53325 + vertex 1.65954 1.60572 2.53079 + endloop + endfacet + facet normal 0.580839 0.0123125 0.813925 + outer loop + vertex 1.65628 1.61392 2.53308 + vertex 1.65618 1.6078 2.53325 + vertex 1.65951 1.61098 2.53082 + endloop + endfacet + facet normal 0.597662 -0.00623376 0.801724 + outer loop + vertex 1.66254 1.61361 2.52853 + vertex 1.66292 1.61898 2.5283 + vertex 1.65978 1.61616 2.53061 + endloop + endfacet + facet normal 0.60179 0.000724995 0.798654 + outer loop + vertex 1.65951 1.61098 2.53082 + vertex 1.66254 1.61361 2.52853 + vertex 1.65978 1.61616 2.53061 + endloop + endfacet + facet normal 0.57516 0.00291866 0.818036 + outer loop + vertex 1.65978 1.61616 2.53061 + vertex 1.65628 1.61392 2.53308 + vertex 1.65951 1.61098 2.53082 + endloop + endfacet + facet normal 0.571161 0.0121555 0.820748 + outer loop + vertex 1.6574 1.61849 2.53224 + vertex 1.65628 1.61392 2.53308 + vertex 1.65978 1.61616 2.53061 + endloop + endfacet + facet normal 0.583908 -0.0084104 0.811776 + outer loop + vertex 1.66292 1.61898 2.5283 + vertex 1.66207 1.6233 2.52895 + vertex 1.65978 1.62084 2.53057 + endloop + endfacet + facet normal 0.589933 0.007061 0.807422 + outer loop + vertex 1.65978 1.61616 2.53061 + vertex 1.66292 1.61898 2.5283 + vertex 1.65978 1.62084 2.53057 + endloop + endfacet + facet normal 0.567913 0.00722671 0.823057 + outer loop + vertex 1.65978 1.62084 2.53057 + vertex 1.6574 1.61849 2.53224 + vertex 1.65978 1.61616 2.53061 + endloop + endfacet + facet normal 0.555405 0.0257117 0.831182 + outer loop + vertex 1.65685 1.62257 2.53248 + vertex 1.6574 1.61849 2.53224 + vertex 1.65978 1.62084 2.53057 + endloop + endfacet + facet normal 0.570924 0.018752 0.820789 + outer loop + vertex 1.66207 1.6233 2.52895 + vertex 1.66286 1.62783 2.5283 + vertex 1.65962 1.62543 2.53061 + endloop + endfacet + facet normal 0.567978 0.0136978 0.82293 + outer loop + vertex 1.65978 1.62084 2.53057 + vertex 1.66207 1.6233 2.52895 + vertex 1.65962 1.62543 2.53061 + endloop + endfacet + facet normal 0.550287 0.0129626 0.834875 + outer loop + vertex 1.65962 1.62543 2.53061 + vertex 1.65685 1.62257 2.53248 + vertex 1.65978 1.62084 2.53057 + endloop + endfacet + facet normal 0.538021 0.029798 0.842405 + outer loop + vertex 1.65654 1.62745 2.5325 + vertex 1.65685 1.62257 2.53248 + vertex 1.65962 1.62543 2.53061 + endloop + endfacet + facet normal 0.568358 0.0241703 0.822427 + outer loop + vertex 1.66286 1.62783 2.5283 + vertex 1.66245 1.63337 2.52842 + vertex 1.65957 1.63041 2.5305 + endloop + endfacet + facet normal 0.568262 0.0239886 0.822498 + outer loop + vertex 1.65962 1.62543 2.53061 + vertex 1.66286 1.62783 2.5283 + vertex 1.65957 1.63041 2.5305 + endloop + endfacet + facet normal 0.535433 0.0241465 0.844233 + outer loop + vertex 1.65957 1.63041 2.5305 + vertex 1.65654 1.62745 2.5325 + vertex 1.65962 1.62543 2.53061 + endloop + endfacet + facet normal 0.528074 0.0345718 0.848495 + outer loop + vertex 1.65636 1.63249 2.53241 + vertex 1.65654 1.62745 2.5325 + vertex 1.65957 1.63041 2.5305 + endloop + endfacet + facet normal 0.561694 0.0360402 0.82656 + outer loop + vertex 1.66245 1.63337 2.52842 + vertex 1.66224 1.63855 2.52834 + vertex 1.6594 1.63558 2.5304 + endloop + endfacet + facet normal 0.561004 0.0346088 0.827089 + outer loop + vertex 1.65957 1.63041 2.5305 + vertex 1.66245 1.63337 2.52842 + vertex 1.6594 1.63558 2.5304 + endloop + endfacet + facet normal 0.527772 0.0339106 0.848709 + outer loop + vertex 1.6594 1.63558 2.5304 + vertex 1.65636 1.63249 2.53241 + vertex 1.65957 1.63041 2.5305 + endloop + endfacet + facet normal 0.522198 0.0414105 0.851818 + outer loop + vertex 1.65619 1.63753 2.53227 + vertex 1.65636 1.63249 2.53241 + vertex 1.6594 1.63558 2.5304 + endloop + endfacet + facet normal 0.557745 0.0376193 0.829159 + outer loop + vertex 1.66224 1.63855 2.52834 + vertex 1.66209 1.64362 2.52821 + vertex 1.65924 1.64067 2.53026 + endloop + endfacet + facet normal 0.558853 0.0399687 0.828303 + outer loop + vertex 1.6594 1.63558 2.5304 + vertex 1.66224 1.63855 2.52834 + vertex 1.65924 1.64067 2.53026 + endloop + endfacet + facet normal 0.521354 0.0394381 0.852428 + outer loop + vertex 1.65924 1.64067 2.53026 + vertex 1.65619 1.63753 2.53227 + vertex 1.6594 1.63558 2.5304 + endloop + endfacet + facet normal 0.519002 0.0425503 0.853713 + outer loop + vertex 1.65599 1.64257 2.53214 + vertex 1.65619 1.63753 2.53227 + vertex 1.65924 1.64067 2.53026 + endloop + endfacet + facet normal 0.556376 0.0283086 0.830448 + outer loop + vertex 1.66209 1.64362 2.52821 + vertex 1.66199 1.6486 2.5281 + vertex 1.65913 1.64566 2.53012 + endloop + endfacet + facet normal 0.55953 0.0351263 0.828065 + outer loop + vertex 1.65924 1.64067 2.53026 + vertex 1.66209 1.64362 2.52821 + vertex 1.65913 1.64566 2.53012 + endloop + endfacet + facet normal 0.515854 0.0349463 0.855964 + outer loop + vertex 1.65913 1.64566 2.53012 + vertex 1.65599 1.64257 2.53214 + vertex 1.65924 1.64067 2.53026 + endloop + endfacet + facet normal 0.518376 0.0314719 0.854574 + outer loop + vertex 1.65602 1.64748 2.53194 + vertex 1.65599 1.64257 2.53214 + vertex 1.65913 1.64566 2.53012 + endloop + endfacet + facet normal 0.556825 0.0202354 0.830383 + outer loop + vertex 1.66199 1.6486 2.5281 + vertex 1.66187 1.65356 2.52806 + vertex 1.65906 1.65056 2.53002 + endloop + endfacet + facet normal 0.558886 0.0247918 0.828874 + outer loop + vertex 1.65913 1.64566 2.53012 + vertex 1.66199 1.6486 2.5281 + vertex 1.65906 1.65056 2.53002 + endloop + endfacet + facet normal 0.515577 0.024791 0.856485 + outer loop + vertex 1.65906 1.65056 2.53002 + vertex 1.65602 1.64748 2.53194 + vertex 1.65913 1.64566 2.53012 + endloop + endfacet + facet normal 0.515041 0.0255082 0.856786 + outer loop + vertex 1.656 1.65216 2.53181 + vertex 1.65602 1.64748 2.53194 + vertex 1.65906 1.65056 2.53002 + endloop + endfacet + facet normal 0.554701 0.0193522 0.831825 + outer loop + vertex 1.66187 1.65356 2.52806 + vertex 1.66167 1.65862 2.52808 + vertex 1.6589 1.65547 2.53 + endloop + endfacet + facet normal 0.555728 0.0217158 0.83108 + outer loop + vertex 1.65906 1.65056 2.53002 + vertex 1.66187 1.65356 2.52806 + vertex 1.6589 1.65547 2.53 + endloop + endfacet + facet normal 0.513129 0.0204302 0.858068 + outer loop + vertex 1.6589 1.65547 2.53 + vertex 1.656 1.65216 2.53181 + vertex 1.65906 1.65056 2.53002 + endloop + endfacet + facet normal 0.503415 0.0319024 0.863456 + outer loop + vertex 1.65562 1.65695 2.53185 + vertex 1.656 1.65216 2.53181 + vertex 1.6589 1.65547 2.53 + endloop + endfacet + facet normal 0.546989 0.0192945 0.836917 + outer loop + vertex 1.66167 1.65862 2.52808 + vertex 1.6613 1.66415 2.52819 + vertex 1.65856 1.66043 2.53007 + endloop + endfacet + facet normal 0.549583 0.0258051 0.835041 + outer loop + vertex 1.6589 1.65547 2.53 + vertex 1.66167 1.65862 2.52808 + vertex 1.65856 1.66043 2.53007 + endloop + endfacet + facet normal 0.500151 0.0219658 0.86566 + outer loop + vertex 1.65856 1.66043 2.53007 + vertex 1.65562 1.65695 2.53185 + vertex 1.6589 1.65547 2.53 + endloop + endfacet + facet normal 0.486923 0.0367465 0.872672 + outer loop + vertex 1.65501 1.66226 2.53197 + vertex 1.65562 1.65695 2.53185 + vertex 1.65856 1.66043 2.53007 + endloop + endfacet + facet normal 0.54386 0.0225867 0.838872 + outer loop + vertex 1.65817 1.66457 2.53021 + vertex 1.65856 1.66043 2.53007 + vertex 1.6613 1.66415 2.52819 + endloop + endfacet + facet normal 0.543406 0.0171603 0.839294 + outer loop + vertex 1.65817 1.66457 2.53021 + vertex 1.6613 1.66415 2.52819 + vertex 1.65922 1.66885 2.52944 + endloop + endfacet + facet normal 0.554653 0.0241506 0.831731 + outer loop + vertex 1.65922 1.66885 2.52944 + vertex 1.6613 1.66415 2.52819 + vertex 1.66224 1.66857 2.52744 + endloop + endfacet + facet normal 0.478619 0.0151893 0.877891 + outer loop + vertex 1.65856 1.66043 2.53007 + vertex 1.65817 1.66457 2.53021 + vertex 1.65501 1.66226 2.53197 + endloop + endfacet + facet normal 0.554138 0.0145796 0.832297 + outer loop + vertex 1.66224 1.66857 2.52744 + vertex 1.66175 1.67261 2.52769 + vertex 1.65922 1.66885 2.52944 + endloop + endfacet + facet normal 0.544563 0.0238442 0.838381 + outer loop + vertex 1.65922 1.66885 2.52944 + vertex 1.66175 1.67261 2.52769 + vertex 1.65872 1.6741 2.52962 + endloop + endfacet + facet normal 0.542102 0.0165355 0.84015 + outer loop + vertex 1.66175 1.67261 2.52769 + vertex 1.66151 1.67746 2.52775 + vertex 1.65872 1.6741 2.52962 + endloop + endfacet + facet normal 0.534714 0.0251647 0.844658 + outer loop + vertex 1.65872 1.6741 2.52962 + vertex 1.66151 1.67746 2.52775 + vertex 1.65848 1.67907 2.52962 + endloop + endfacet + facet normal 0.536521 0.0300914 0.84335 + outer loop + vertex 1.66151 1.67746 2.52775 + vertex 1.66138 1.68247 2.52766 + vertex 1.65848 1.67907 2.52962 + endloop + endfacet + facet normal 0.523815 0.0451731 0.850634 + outer loop + vertex 1.65848 1.67907 2.52962 + vertex 1.66138 1.68247 2.52766 + vertex 1.65827 1.68407 2.52949 + endloop + endfacet + facet normal 0.52825 0.0578252 0.847117 + outer loop + vertex 1.66138 1.68247 2.52766 + vertex 1.66118 1.68747 2.52744 + vertex 1.65827 1.68407 2.52949 + endloop + endfacet + facet normal 0.517232 0.0707838 0.852913 + outer loop + vertex 1.65827 1.68407 2.52949 + vertex 1.66118 1.68747 2.52744 + vertex 1.65786 1.68912 2.52931 + endloop + endfacet + facet normal 0.52102 0.0821681 0.84958 + outer loop + vertex 1.66118 1.68747 2.52744 + vertex 1.66084 1.69248 2.52716 + vertex 1.65786 1.68912 2.52931 + endloop + endfacet + facet normal 0.513577 0.0910943 0.853194 + outer loop + vertex 1.65786 1.68912 2.52931 + vertex 1.66084 1.69248 2.52716 + vertex 1.65704 1.69446 2.52924 + endloop + endfacet + facet normal 0.508812 0.0774959 0.857383 + outer loop + vertex 1.66084 1.69248 2.52716 + vertex 1.66031 1.69764 2.52701 + vertex 1.65704 1.69446 2.52924 + endloop + endfacet + facet normal 0.523158 0.0577929 0.850274 + outer loop + vertex 1.65704 1.69446 2.52924 + vertex 1.66031 1.69764 2.52701 + vertex 1.65744 1.69814 2.52874 + endloop + endfacet + facet normal 0.596515 0.0510349 0.800977 + outer loop + vertex 1.66358 1.69976 2.52444 + vertex 1.66329 1.70374 2.5244 + vertex 1.66107 1.70159 2.52619 + endloop + endfacet + facet normal 0.596617 0.0512628 0.800887 + outer loop + vertex 1.66107 1.70159 2.52619 + vertex 1.66031 1.69764 2.52701 + vertex 1.66358 1.69976 2.52444 + endloop + endfacet + facet normal 0.514826 0.0779768 0.853741 + outer loop + vertex 1.66107 1.70159 2.52619 + vertex 1.65775 1.70176 2.52818 + vertex 1.66031 1.69764 2.52701 + endloop + endfacet + facet normal 0.525725 0.0868692 0.846207 + outer loop + vertex 1.65775 1.70176 2.52818 + vertex 1.65744 1.69814 2.52874 + vertex 1.66031 1.69764 2.52701 + endloop + endfacet + facet normal 0.571303 0.0553578 0.81887 + outer loop + vertex 1.66329 1.70374 2.5244 + vertex 1.66303 1.70821 2.52428 + vertex 1.66032 1.70542 2.52636 + endloop + endfacet + facet normal 0.579112 0.0778117 0.811526 + outer loop + vertex 1.66107 1.70159 2.52619 + vertex 1.66329 1.70374 2.5244 + vertex 1.66032 1.70542 2.52636 + endloop + endfacet + facet normal 0.514793 0.0633775 0.854969 + outer loop + vertex 1.66032 1.70542 2.52636 + vertex 1.65775 1.70176 2.52818 + vertex 1.66107 1.70159 2.52619 + endloop + endfacet + facet normal 0.492229 0.0848967 0.866316 + outer loop + vertex 1.65684 1.70714 2.52817 + vertex 1.65775 1.70176 2.52818 + vertex 1.66032 1.70542 2.52636 + endloop + endfacet + facet normal 0.554058 0.0481622 0.831084 + outer loop + vertex 1.66303 1.70821 2.52428 + vertex 1.66283 1.71321 2.52412 + vertex 1.65987 1.71031 2.52627 + endloop + endfacet + facet normal 0.562566 0.06765 0.82398 + outer loop + vertex 1.66032 1.70542 2.52636 + vertex 1.66303 1.70821 2.52428 + vertex 1.65987 1.71031 2.52627 + endloop + endfacet + facet normal 0.483997 0.0613226 0.872918 + outer loop + vertex 1.65987 1.71031 2.52627 + vertex 1.65684 1.70714 2.52817 + vertex 1.66032 1.70542 2.52636 + endloop + endfacet + facet normal 0.472278 0.0756598 0.878197 + outer loop + vertex 1.65634 1.71235 2.52799 + vertex 1.65684 1.70714 2.52817 + vertex 1.65987 1.71031 2.52627 + endloop + endfacet + facet normal 0.540455 0.0423265 0.840307 + outer loop + vertex 1.66283 1.71321 2.52412 + vertex 1.66271 1.7183 2.52394 + vertex 1.65965 1.71541 2.52606 + endloop + endfacet + facet normal 0.547608 0.0574911 0.834758 + outer loop + vertex 1.65987 1.71031 2.52627 + vertex 1.66283 1.71321 2.52412 + vertex 1.65965 1.71541 2.52606 + endloop + endfacet + facet normal 0.46385 0.0560188 0.884141 + outer loop + vertex 1.65965 1.71541 2.52606 + vertex 1.65634 1.71235 2.52799 + vertex 1.65987 1.71031 2.52627 + endloop + endfacet + facet normal 0.457575 0.0644881 0.886829 + outer loop + vertex 1.65629 1.71737 2.52765 + vertex 1.65634 1.71235 2.52799 + vertex 1.65965 1.71541 2.52606 + endloop + endfacet + facet normal 0.527294 0.0436645 0.84856 + outer loop + vertex 1.66271 1.7183 2.52394 + vertex 1.66255 1.72333 2.52378 + vertex 1.65953 1.7204 2.52581 + endloop + endfacet + facet normal 0.5322 0.0543965 0.844869 + outer loop + vertex 1.65965 1.71541 2.52606 + vertex 1.66271 1.7183 2.52394 + vertex 1.65953 1.7204 2.52581 + endloop + endfacet + facet normal 0.453192 0.054558 0.889742 + outer loop + vertex 1.65953 1.7204 2.52581 + vertex 1.65629 1.71737 2.52765 + vertex 1.65965 1.71541 2.52606 + endloop + endfacet + facet normal 0.441084 0.0705002 0.894692 + outer loop + vertex 1.65618 1.72203 2.52733 + vertex 1.65629 1.71737 2.52765 + vertex 1.65953 1.7204 2.52581 + endloop + endfacet + facet normal 0.507543 0.0505161 0.860144 + outer loop + vertex 1.66255 1.72333 2.52378 + vertex 1.66221 1.72837 2.52369 + vertex 1.65925 1.72528 2.52562 + endloop + endfacet + facet normal 0.512971 0.0636288 0.856044 + outer loop + vertex 1.65953 1.7204 2.52581 + vertex 1.66255 1.72333 2.52378 + vertex 1.65925 1.72528 2.52562 + endloop + endfacet + facet normal 0.43753 0.060934 0.897137 + outer loop + vertex 1.65925 1.72528 2.52562 + vertex 1.65618 1.72203 2.52733 + vertex 1.65953 1.7204 2.52581 + endloop + endfacet + facet normal 0.411255 0.0909273 0.906974 + outer loop + vertex 1.65562 1.72669 2.52712 + vertex 1.65618 1.72203 2.52733 + vertex 1.65925 1.72528 2.52562 + endloop + endfacet + facet normal 0.479586 0.0576695 0.875598 + outer loop + vertex 1.66221 1.72837 2.52369 + vertex 1.6616 1.73388 2.52366 + vertex 1.65871 1.73014 2.52549 + endloop + endfacet + facet normal 0.486551 0.0768783 0.870263 + outer loop + vertex 1.65925 1.72528 2.52562 + vertex 1.66221 1.72837 2.52369 + vertex 1.65871 1.73014 2.52549 + endloop + endfacet + facet normal 0.404675 0.0689174 0.91186 + outer loop + vertex 1.65871 1.73014 2.52549 + vertex 1.65562 1.72669 2.52712 + vertex 1.65925 1.72528 2.52562 + endloop + endfacet + facet normal 0.37944 0.0954891 0.920276 + outer loop + vertex 1.6548 1.73183 2.52693 + vertex 1.65562 1.72669 2.52712 + vertex 1.65871 1.73014 2.52549 + endloop + endfacet + facet normal 0.45894 0.0782762 0.885012 + outer loop + vertex 1.6581 1.7342 2.52545 + vertex 1.65871 1.73014 2.52549 + vertex 1.6616 1.73388 2.52366 + endloop + endfacet + facet normal 0.458797 0.0745962 0.885404 + outer loop + vertex 1.6581 1.7342 2.52545 + vertex 1.6616 1.73388 2.52366 + vertex 1.65904 1.73852 2.5246 + endloop + endfacet + facet normal 0.455583 0.0724508 0.88724 + outer loop + vertex 1.65904 1.73852 2.5246 + vertex 1.6616 1.73388 2.52366 + vertex 1.66249 1.73838 2.52284 + endloop + endfacet + facet normal 0.368902 0.0652373 0.927176 + outer loop + vertex 1.65871 1.73014 2.52549 + vertex 1.6581 1.7342 2.52545 + vertex 1.6548 1.73183 2.52693 + endloop + endfacet + facet normal 0.455582 0.0694798 0.887478 + outer loop + vertex 1.66249 1.73838 2.52284 + vertex 1.66173 1.74246 2.52291 + vertex 1.65904 1.73852 2.5246 + endloop + endfacet + facet normal 0.404328 0.0915528 0.91002 + outer loop + vertex 1.66077 1.7662 2.52106 + vertex 1.65987 1.76182 2.5219 + vertex 1.66305 1.76414 2.52025 + endloop + endfacet + facet normal 0.334123 0.451588 0.827303 + outer loop + vertex 1.66321 2.07847 2.45602 + vertex 1.66187 2.08219 2.45454 + vertex 1.6601 2.08015 2.45636 + endloop + endfacet + facet normal 0.287784 0.353098 0.890226 + outer loop + vertex 1.6601 2.08015 2.45636 + vertex 1.66114 2.07605 2.45765 + vertex 1.66321 2.07847 2.45602 + endloop + endfacet + facet normal 0.293615 0.353877 0.88801 + outer loop + vertex 1.6601 2.08015 2.45636 + vertex 1.65628 2.08041 2.45752 + vertex 1.66114 2.07605 2.45765 + endloop + endfacet + facet normal 0.327877 0.456712 0.826989 + outer loop + vertex 1.65771 2.08303 2.45572 + vertex 1.6601 2.08015 2.45636 + vertex 1.66187 2.08219 2.45454 + endloop + endfacet + facet normal 0.329755 0.536603 0.776736 + outer loop + vertex 1.65771 2.08303 2.45572 + vertex 1.66187 2.08219 2.45454 + vertex 1.6566 2.08692 2.45351 + endloop + endfacet + facet normal 0.328843 0.535791 0.777683 + outer loop + vertex 1.6566 2.08692 2.45351 + vertex 1.66187 2.08219 2.45454 + vertex 1.66212 2.0857 2.45201 + endloop + endfacet + facet normal 0.288946 0.43059 0.855045 + outer loop + vertex 1.6601 2.08015 2.45636 + vertex 1.65771 2.08303 2.45572 + vertex 1.65628 2.08041 2.45752 + endloop + endfacet + facet normal 0.348446 0.793099 0.49958 + outer loop + vertex 1.66268 2.08999 2.44709 + vertex 1.66125 2.09174 2.44532 + vertex 1.65941 2.09115 2.44753 + endloop + endfacet + facet normal 0.354011 0.733109 0.580713 + outer loop + vertex 1.65941 2.09115 2.44753 + vertex 1.65693 2.09132 2.44883 + vertex 1.6594 2.08917 2.45005 + endloop + endfacet + facet normal 0.339992 0.73722 0.583876 + outer loop + vertex 1.65941 2.09115 2.44753 + vertex 1.6594 2.08917 2.45005 + vertex 1.66268 2.08999 2.44709 + endloop + endfacet + facet normal 0.342561 0.734387 0.585942 + outer loop + vertex 1.66268 2.08999 2.44709 + vertex 1.6594 2.08917 2.45005 + vertex 1.66405 2.08752 2.44938 + endloop + endfacet + facet normal 0.328852 0.648096 0.686897 + outer loop + vertex 1.66212 2.0857 2.45201 + vertex 1.6594 2.08917 2.45005 + vertex 1.6566 2.08692 2.45351 + endloop + endfacet + facet normal 0.326469 0.647292 0.68879 + outer loop + vertex 1.66405 2.08752 2.44938 + vertex 1.6594 2.08917 2.45005 + vertex 1.66212 2.0857 2.45201 + endloop + endfacet + facet normal -0.02504 0.396051 0.917887 + outer loop + vertex 1.66079 2.1 2.44 + vertex 1.65682 2.09793 2.44078 + vertex 1.65818 2.09563 2.44181 + endloop + endfacet + facet normal 0.179776 0.283487 0.941975 + outer loop + vertex 1.66079 2.1 2.44 + vertex 1.65818 2.09563 2.44181 + vertex 1.665 2.09733 2.44 + endloop + endfacet + facet normal 0.126076 0.441901 0.88816 + outer loop + vertex 1.665 2.09733 2.44 + vertex 1.65818 2.09563 2.44181 + vertex 1.66222 2.09341 2.44234 + endloop + endfacet + facet normal 0.323626 0.812901 0.484208 + outer loop + vertex 1.66125 2.09174 2.44532 + vertex 1.65765 2.09289 2.44579 + vertex 1.65941 2.09115 2.44753 + endloop + endfacet + facet normal 0.319847 0.777002 0.542186 + outer loop + vertex 1.66125 2.09174 2.44532 + vertex 1.66222 2.09341 2.44234 + vertex 1.65765 2.09289 2.44579 + endloop + endfacet + facet normal 0.339212 0.752759 0.564171 + outer loop + vertex 1.66222 2.09341 2.44234 + vertex 1.65818 2.09563 2.44181 + vertex 1.65765 2.09289 2.44579 + endloop + endfacet + facet normal 0.313681 0.811558 0.492927 + outer loop + vertex 1.65941 2.09115 2.44753 + vertex 1.65765 2.09289 2.44579 + vertex 1.65693 2.09132 2.44883 + endloop + endfacet + facet normal 0.124752 0.133172 0.98321 + outer loop + vertex 1.66079 2.1 2.44 + vertex 1.66 2.10074 2.44 + vertex 1.65682 2.09793 2.44078 + endloop + endfacet + facet normal 0.23212 -0.573708 0.78548 + outer loop + vertex 1.67 0.937329 2.44 + vertex 1.66729 0.937864 2.44119 + vertex 1.665 0.935306 2.44 + endloop + endfacet + facet normal 0.400743 -0.656558 0.639012 + outer loop + vertex 1.66729 0.937864 2.44119 + vertex 1.66188 0.936785 2.44348 + vertex 1.665 0.935306 2.44 + endloop + endfacet + facet normal 0.372994 -0.76791 0.520758 + outer loop + vertex 1.66729 0.937864 2.44119 + vertex 1.66382 0.938744 2.44497 + vertex 1.66188 0.936785 2.44348 + endloop + endfacet + facet normal 0.37052 -0.77027 0.519038 + outer loop + vertex 1.66728 0.939815 2.44409 + vertex 1.66382 0.938744 2.44497 + vertex 1.66729 0.937864 2.44119 + endloop + endfacet + facet normal 0.370579 -0.769244 0.520515 + outer loop + vertex 1.66382 0.938744 2.44497 + vertex 1.66728 0.939815 2.44409 + vertex 1.66529 0.941193 2.44755 + endloop + endfacet + facet normal 0.36726 -0.769434 0.522581 + outer loop + vertex 1.66151 0.939794 2.44814 + vertex 1.66382 0.938744 2.44497 + vertex 1.66529 0.941193 2.44755 + endloop + endfacet + facet normal 0.337161 -0.720349 0.606151 + outer loop + vertex 1.66535 0.94335 2.45008 + vertex 1.66529 0.941193 2.44755 + vertex 1.66769 0.943174 2.44857 + endloop + endfacet + facet normal 0.349299 -0.717132 0.603086 + outer loop + vertex 1.66535 0.94335 2.45008 + vertex 1.66231 0.942202 2.45047 + vertex 1.66529 0.941193 2.44755 + endloop + endfacet + facet normal 0.357962 -0.708013 0.608753 + outer loop + vertex 1.66231 0.942202 2.45047 + vertex 1.66151 0.939794 2.44814 + vertex 1.66529 0.941193 2.44755 + endloop + endfacet + facet normal 0.329586 -0.63051 0.702731 + outer loop + vertex 1.66535 0.94335 2.45008 + vertex 1.66408 0.945179 2.45232 + vertex 1.66231 0.942202 2.45047 + endloop + endfacet + facet normal 0.377735 -0.648695 0.66069 + outer loop + vertex 1.66769 0.943174 2.44857 + vertex 1.66787 0.945374 2.45063 + vertex 1.66535 0.94335 2.45008 + endloop + endfacet + facet normal 0.345692 -0.620604 0.70381 + outer loop + vertex 1.66787 0.945374 2.45063 + vertex 1.66408 0.945179 2.45232 + vertex 1.66535 0.94335 2.45008 + endloop + endfacet + facet normal 0.363396 -0.550492 0.7516 + outer loop + vertex 1.66787 0.945374 2.45063 + vertex 1.66808 0.949293 2.45339 + vertex 1.66408 0.945179 2.45232 + endloop + endfacet + facet normal 0.360064 -0.548121 0.754929 + outer loop + vertex 1.66808 0.949293 2.45339 + vertex 1.66264 0.947659 2.4548 + vertex 1.66408 0.945179 2.45232 + endloop + endfacet + facet normal 0.349393 -0.459388 0.816632 + outer loop + vertex 1.66264 0.947659 2.4548 + vertex 1.66808 0.949293 2.45339 + vertex 1.6649 0.951321 2.45589 + endloop + endfacet + facet normal 0.355395 -0.461898 0.812616 + outer loop + vertex 1.66132 0.949734 2.45656 + vertex 1.66264 0.947659 2.4548 + vertex 1.6649 0.951321 2.45589 + endloop + endfacet + facet normal 0.319069 -0.351703 0.880057 + outer loop + vertex 1.6649 0.951321 2.45589 + vertex 1.66271 0.953634 2.45761 + vertex 1.66132 0.949734 2.45656 + endloop + endfacet + facet normal 0.307366 -0.362615 0.879794 + outer loop + vertex 1.66678 0.954632 2.4566 + vertex 1.66271 0.953634 2.45761 + vertex 1.6649 0.951321 2.45589 + endloop + endfacet + facet normal 0.351099 -0.13508 0.926543 + outer loop + vertex 1.66224 1.20342 2.51337 + vertex 1.66644 1.20763 2.51239 + vertex 1.66265 1.20861 2.51397 + endloop + endfacet + facet normal 0.357822 -0.11037 0.927244 + outer loop + vertex 1.66644 1.20763 2.51239 + vertex 1.66688 1.21284 2.51284 + vertex 1.66265 1.20861 2.51397 + endloop + endfacet + facet normal 0.378128 -0.13368 0.916051 + outer loop + vertex 1.66265 1.20861 2.51397 + vertex 1.66688 1.21284 2.51284 + vertex 1.66292 1.21401 2.51465 + endloop + endfacet + facet normal 0.38749 -0.102258 0.916185 + outer loop + vertex 1.66688 1.21284 2.51284 + vertex 1.66784 1.21868 2.51309 + vertex 1.66292 1.21401 2.51465 + endloop + endfacet + facet normal 0.426016 -0.150868 0.892048 + outer loop + vertex 1.66292 1.21401 2.51465 + vertex 1.66784 1.21868 2.51309 + vertex 1.66407 1.21938 2.51501 + endloop + endfacet + facet normal 0.367807 -0.140918 0.919163 + outer loop + vertex 1.66384 1.22267 2.5156 + vertex 1.66143 1.21991 2.51615 + vertex 1.66407 1.21938 2.51501 + endloop + endfacet + facet normal 0.448139 -0.129122 0.88459 + outer loop + vertex 1.66384 1.22267 2.5156 + vertex 1.66407 1.21938 2.51501 + vertex 1.66735 1.22423 2.51405 + endloop + endfacet + facet normal 0.433139 -0.117137 0.893683 + outer loop + vertex 1.66735 1.22423 2.51405 + vertex 1.66407 1.21938 2.51501 + vertex 1.66784 1.21868 2.51309 + endloop + endfacet + facet normal 0.343094 -0.116874 0.932002 + outer loop + vertex 1.66384 1.22267 2.5156 + vertex 1.66104 1.22297 2.51667 + vertex 1.66143 1.21991 2.51615 + endloop + endfacet + facet normal 0.455095 -0.102148 0.884564 + outer loop + vertex 1.66735 1.22423 2.51405 + vertex 1.66817 1.22982 2.51428 + vertex 1.66462 1.22647 2.51572 + endloop + endfacet + facet normal 0.444551 -0.117567 0.888005 + outer loop + vertex 1.66384 1.22267 2.5156 + vertex 1.66735 1.22423 2.51405 + vertex 1.66462 1.22647 2.51572 + endloop + endfacet + facet normal 0.345517 -0.0986128 0.933217 + outer loop + vertex 1.66462 1.22647 2.51572 + vertex 1.66104 1.22297 2.51667 + vertex 1.66384 1.22267 2.5156 + endloop + endfacet + facet normal 0.360149 -0.115615 0.925703 + outer loop + vertex 1.66128 1.22741 2.51714 + vertex 1.66104 1.22297 2.51667 + vertex 1.66462 1.22647 2.51572 + endloop + endfacet + facet normal 0.465217 -0.0932022 0.880277 + outer loop + vertex 1.66817 1.22982 2.51428 + vertex 1.6686 1.23473 2.51457 + vertex 1.66516 1.23121 2.51602 + endloop + endfacet + facet normal 0.459289 -0.107824 0.881719 + outer loop + vertex 1.66462 1.22647 2.51572 + vertex 1.66817 1.22982 2.51428 + vertex 1.66516 1.23121 2.51602 + endloop + endfacet + facet normal 0.364664 -0.0997738 0.925778 + outer loop + vertex 1.66516 1.23121 2.51602 + vertex 1.66128 1.22741 2.51714 + vertex 1.66462 1.22647 2.51572 + endloop + endfacet + facet normal 0.374284 -0.11113 0.920631 + outer loop + vertex 1.66175 1.23243 2.51755 + vertex 1.66128 1.22741 2.51714 + vertex 1.66516 1.23121 2.51602 + endloop + endfacet + facet normal 0.479297 -0.0877148 0.873259 + outer loop + vertex 1.6686 1.23473 2.51457 + vertex 1.66882 1.23922 2.5149 + vertex 1.66571 1.236 2.51629 + endloop + endfacet + facet normal 0.473324 -0.103387 0.8748 + outer loop + vertex 1.66516 1.23121 2.51602 + vertex 1.6686 1.23473 2.51457 + vertex 1.66571 1.236 2.51629 + endloop + endfacet + facet normal 0.379773 -0.0952433 0.920164 + outer loop + vertex 1.66571 1.236 2.51629 + vertex 1.66175 1.23243 2.51755 + vertex 1.66516 1.23121 2.51602 + endloop + endfacet + facet normal 0.387414 -0.105208 0.915883 + outer loop + vertex 1.66267 1.23824 2.51783 + vertex 1.66175 1.23243 2.51755 + vertex 1.66571 1.236 2.51629 + endloop + endfacet + facet normal 0.493716 -0.106028 0.863135 + outer loop + vertex 1.66882 1.23922 2.5149 + vertex 1.66645 1.23988 2.51633 + vertex 1.66571 1.236 2.51629 + endloop + endfacet + facet normal 0.398422 -0.0882151 0.91295 + outer loop + vertex 1.66645 1.23988 2.51633 + vertex 1.66267 1.23824 2.51783 + vertex 1.66571 1.236 2.51629 + endloop + endfacet + facet normal 0.396019 -0.0811008 0.914654 + outer loop + vertex 1.66645 1.23988 2.51633 + vertex 1.66595 1.24314 2.51684 + vertex 1.66267 1.23824 2.51783 + endloop + endfacet + facet normal 0.418061 -0.0981995 0.903096 + outer loop + vertex 1.66595 1.24314 2.51684 + vertex 1.6624 1.24363 2.51854 + vertex 1.66267 1.23824 2.51783 + endloop + endfacet + facet normal 0.421411 -0.0761167 0.90367 + outer loop + vertex 1.66595 1.24314 2.51684 + vertex 1.66602 1.24785 2.51721 + vertex 1.6624 1.24363 2.51854 + endloop + endfacet + facet normal 0.447226 -0.103111 0.888458 + outer loop + vertex 1.6624 1.24363 2.51854 + vertex 1.66602 1.24785 2.51721 + vertex 1.66232 1.24902 2.5192 + endloop + endfacet + facet normal 0.45256 -0.0850153 0.887672 + outer loop + vertex 1.66602 1.24785 2.51721 + vertex 1.66637 1.25306 2.51753 + vertex 1.66232 1.24902 2.5192 + endloop + endfacet + facet normal 0.474854 -0.113581 0.872705 + outer loop + vertex 1.66232 1.24902 2.5192 + vertex 1.66637 1.25306 2.51753 + vertex 1.66334 1.25467 2.51939 + endloop + endfacet + facet normal 0.487016 -0.0865841 0.869091 + outer loop + vertex 1.66637 1.25306 2.51753 + vertex 1.6667 1.25827 2.51786 + vertex 1.66334 1.25467 2.51939 + endloop + endfacet + facet normal 0.504878 -0.108747 0.856313 + outer loop + vertex 1.66334 1.25467 2.51939 + vertex 1.6667 1.25827 2.51786 + vertex 1.66376 1.25939 2.51973 + endloop + endfacet + facet normal 0.445092 -0.0967718 0.89024 + outer loop + vertex 1.66341 1.26267 2.52027 + vertex 1.66129 1.26001 2.52104 + vertex 1.66376 1.25939 2.51973 + endloop + endfacet + facet normal 0.522978 -0.0814922 0.848442 + outer loop + vertex 1.66341 1.26267 2.52027 + vertex 1.66376 1.25939 2.51973 + vertex 1.66653 1.26363 2.51844 + endloop + endfacet + facet normal 0.515775 -0.0752792 0.85341 + outer loop + vertex 1.66653 1.26363 2.51844 + vertex 1.66376 1.25939 2.51973 + vertex 1.6667 1.25827 2.51786 + endloop + endfacet + facet normal 0.416675 -0.0695747 0.906389 + outer loop + vertex 1.66341 1.26267 2.52027 + vertex 1.66077 1.26312 2.52152 + vertex 1.66129 1.26001 2.52104 + endloop + endfacet + facet normal 0.527142 -0.0485513 0.848389 + outer loop + vertex 1.66653 1.26363 2.51844 + vertex 1.66716 1.26919 2.51836 + vertex 1.66395 1.26642 2.5202 + endloop + endfacet + facet normal 0.51874 -0.0591775 0.852881 + outer loop + vertex 1.66341 1.26267 2.52027 + vertex 1.66653 1.26363 2.51844 + vertex 1.66395 1.26642 2.5202 + endloop + endfacet + facet normal 0.420882 -0.0439228 0.906052 + outer loop + vertex 1.66395 1.26642 2.5202 + vertex 1.66077 1.26312 2.52152 + vertex 1.66341 1.26267 2.52027 + endloop + endfacet + facet normal 0.440147 -0.0667704 0.89544 + outer loop + vertex 1.66079 1.26759 2.52184 + vertex 1.66077 1.26312 2.52152 + vertex 1.66395 1.26642 2.5202 + endloop + endfacet + facet normal 0.536424 -0.0455543 0.842718 + outer loop + vertex 1.66716 1.26919 2.51836 + vertex 1.66742 1.27429 2.51847 + vertex 1.66424 1.27124 2.52033 + endloop + endfacet + facet normal 0.531318 -0.0553904 0.84536 + outer loop + vertex 1.66395 1.26642 2.5202 + vertex 1.66716 1.26919 2.51836 + vertex 1.66424 1.27124 2.52033 + endloop + endfacet + facet normal 0.445079 -0.0515089 0.894009 + outer loop + vertex 1.66424 1.27124 2.52033 + vertex 1.66079 1.26759 2.52184 + vertex 1.66395 1.26642 2.5202 + endloop + endfacet + facet normal 0.463469 -0.0734456 0.883064 + outer loop + vertex 1.66096 1.27256 2.52216 + vertex 1.66079 1.26759 2.52184 + vertex 1.66424 1.27124 2.52033 + endloop + endfacet + facet normal 0.550579 -0.0514902 0.833193 + outer loop + vertex 1.66742 1.27429 2.51847 + vertex 1.66759 1.27929 2.51867 + vertex 1.66444 1.27625 2.52056 + endloop + endfacet + facet normal 0.54631 -0.0603334 0.835408 + outer loop + vertex 1.66424 1.27124 2.52033 + vertex 1.66742 1.27429 2.51847 + vertex 1.66444 1.27625 2.52056 + endloop + endfacet + facet normal 0.468284 -0.0593585 0.881582 + outer loop + vertex 1.66444 1.27625 2.52056 + vertex 1.66096 1.27256 2.52216 + vertex 1.66424 1.27124 2.52033 + endloop + endfacet + facet normal 0.488148 -0.0836971 0.868738 + outer loop + vertex 1.66117 1.27772 2.52254 + vertex 1.66096 1.27256 2.52216 + vertex 1.66444 1.27625 2.52056 + endloop + endfacet + facet normal 0.570173 -0.0546074 0.819708 + outer loop + vertex 1.66759 1.27929 2.51867 + vertex 1.66781 1.2843 2.51885 + vertex 1.66467 1.28132 2.52083 + endloop + endfacet + facet normal 0.562642 -0.069793 0.823749 + outer loop + vertex 1.66444 1.27625 2.52056 + vertex 1.66759 1.27929 2.51867 + vertex 1.66467 1.28132 2.52083 + endloop + endfacet + facet normal 0.493658 -0.0690079 0.866914 + outer loop + vertex 1.66467 1.28132 2.52083 + vertex 1.66117 1.27772 2.52254 + vertex 1.66444 1.27625 2.52056 + endloop + endfacet + facet normal 0.510622 -0.0911655 0.854958 + outer loop + vertex 1.66154 1.28295 2.52288 + vertex 1.66117 1.27772 2.52254 + vertex 1.66467 1.28132 2.52083 + endloop + endfacet + facet normal 0.593456 -0.0455885 0.803574 + outer loop + vertex 1.66781 1.2843 2.51885 + vertex 1.6684 1.28977 2.51873 + vertex 1.66497 1.28644 2.52107 + endloop + endfacet + facet normal 0.580367 -0.0709423 0.811259 + outer loop + vertex 1.66467 1.28132 2.52083 + vertex 1.66781 1.2843 2.51885 + vertex 1.66497 1.28644 2.52107 + endloop + endfacet + facet normal 0.519822 -0.0691715 0.851469 + outer loop + vertex 1.66497 1.28644 2.52107 + vertex 1.66154 1.28295 2.52288 + vertex 1.66467 1.28132 2.52083 + endloop + endfacet + facet normal 0.535834 -0.0911821 0.839386 + outer loop + vertex 1.66191 1.28808 2.5232 + vertex 1.66154 1.28295 2.52288 + vertex 1.66497 1.28644 2.52107 + endloop + endfacet + facet normal 0.612305 -0.0477191 0.78918 + outer loop + vertex 1.6684 1.28977 2.51873 + vertex 1.66812 1.29509 2.51927 + vertex 1.66514 1.29161 2.52137 + endloop + endfacet + facet normal 0.60556 -0.0653549 0.793111 + outer loop + vertex 1.66497 1.28644 2.52107 + vertex 1.6684 1.28977 2.51873 + vertex 1.66514 1.29161 2.52137 + endloop + endfacet + facet normal 0.546333 -0.0659178 0.83497 + outer loop + vertex 1.66514 1.29161 2.52137 + vertex 1.66191 1.28808 2.5232 + vertex 1.66497 1.28644 2.52107 + endloop + endfacet + facet normal 0.551021 -0.0720814 0.831372 + outer loop + vertex 1.66178 1.29336 2.52375 + vertex 1.66191 1.28808 2.5232 + vertex 1.66514 1.29161 2.52137 + endloop + endfacet + facet normal 0.625157 -0.0429914 0.779314 + outer loop + vertex 1.66812 1.29509 2.51927 + vertex 1.66816 1.30002 2.5195 + vertex 1.66528 1.29676 2.52163 + endloop + endfacet + facet normal 0.619481 -0.0576613 0.782891 + outer loop + vertex 1.66514 1.29161 2.52137 + vertex 1.66812 1.29509 2.51927 + vertex 1.66528 1.29676 2.52163 + endloop + endfacet + facet normal 0.556427 -0.0582926 0.828849 + outer loop + vertex 1.66528 1.29676 2.52163 + vertex 1.66178 1.29336 2.52375 + vertex 1.66514 1.29161 2.52137 + endloop + endfacet + facet normal 0.560011 -0.0637428 0.826029 + outer loop + vertex 1.66248 1.2989 2.5237 + vertex 1.66178 1.29336 2.52375 + vertex 1.66528 1.29676 2.52163 + endloop + endfacet + facet normal 0.637324 -0.0344366 0.769826 + outer loop + vertex 1.66816 1.30002 2.5195 + vertex 1.66829 1.30493 2.51961 + vertex 1.66554 1.30183 2.52175 + endloop + endfacet + facet normal 0.630329 -0.050605 0.774677 + outer loop + vertex 1.66528 1.29676 2.52163 + vertex 1.66816 1.30002 2.5195 + vertex 1.66554 1.30183 2.52175 + endloop + endfacet + facet normal 0.568259 -0.048504 0.821419 + outer loop + vertex 1.66554 1.30183 2.52175 + vertex 1.66248 1.2989 2.5237 + vertex 1.66528 1.29676 2.52163 + endloop + endfacet + facet normal 0.569807 -0.0509315 0.820198 + outer loop + vertex 1.66278 1.30397 2.5238 + vertex 1.66248 1.2989 2.5237 + vertex 1.66554 1.30183 2.52175 + endloop + endfacet + facet normal 0.648508 -0.0267522 0.760737 + outer loop + vertex 1.66829 1.30493 2.51961 + vertex 1.6684 1.30984 2.5197 + vertex 1.66572 1.3068 2.52187 + endloop + endfacet + facet normal 0.642024 -0.0415427 0.765558 + outer loop + vertex 1.66554 1.30183 2.52175 + vertex 1.66829 1.30493 2.51961 + vertex 1.66572 1.3068 2.52187 + endloop + endfacet + facet normal 0.575529 -0.0402733 0.816789 + outer loop + vertex 1.66572 1.3068 2.52187 + vertex 1.66278 1.30397 2.5238 + vertex 1.66554 1.30183 2.52175 + endloop + endfacet + facet normal 0.578734 -0.0453452 0.814255 + outer loop + vertex 1.66296 1.30893 2.52395 + vertex 1.66278 1.30397 2.5238 + vertex 1.66572 1.3068 2.52187 + endloop + endfacet + facet normal 0.659196 -0.0256168 0.751535 + outer loop + vertex 1.6684 1.30984 2.5197 + vertex 1.66849 1.31465 2.51978 + vertex 1.66589 1.31167 2.52196 + endloop + endfacet + facet normal 0.654671 -0.036212 0.755046 + outer loop + vertex 1.66572 1.3068 2.52187 + vertex 1.6684 1.30984 2.5197 + vertex 1.66589 1.31167 2.52196 + endloop + endfacet + facet normal 0.584199 -0.0349569 0.810857 + outer loop + vertex 1.66589 1.31167 2.52196 + vertex 1.66296 1.30893 2.52395 + vertex 1.66572 1.3068 2.52187 + endloop + endfacet + facet normal 0.593217 -0.0499339 0.803493 + outer loop + vertex 1.66324 1.31386 2.52405 + vertex 1.66296 1.30893 2.52395 + vertex 1.66589 1.31167 2.52196 + endloop + endfacet + facet normal 0.672118 -0.0429403 0.739198 + outer loop + vertex 1.66849 1.31465 2.51978 + vertex 1.66856 1.31908 2.51997 + vertex 1.66617 1.31633 2.52199 + endloop + endfacet + facet normal 0.671329 -0.0448322 0.739803 + outer loop + vertex 1.66589 1.31167 2.52196 + vertex 1.66849 1.31465 2.51978 + vertex 1.66617 1.31633 2.52199 + endloop + endfacet + facet normal 0.598231 -0.0408169 0.800283 + outer loop + vertex 1.66617 1.31633 2.52199 + vertex 1.66324 1.31386 2.52405 + vertex 1.66589 1.31167 2.52196 + endloop + endfacet + facet normal 0.613725 -0.0708819 0.786332 + outer loop + vertex 1.66393 1.31917 2.52399 + vertex 1.66324 1.31386 2.52405 + vertex 1.66617 1.31633 2.52199 + endloop + endfacet + facet normal 0.688262 -0.0694668 0.722129 + outer loop + vertex 1.66856 1.31908 2.51997 + vertex 1.66668 1.31998 2.52185 + vertex 1.66617 1.31633 2.52199 + endloop + endfacet + facet normal 0.623704 -0.0582225 0.779489 + outer loop + vertex 1.66668 1.31998 2.52185 + vertex 1.66393 1.31917 2.52399 + vertex 1.66617 1.31633 2.52199 + endloop + endfacet + facet normal 0.62767 -0.0877253 0.773521 + outer loop + vertex 1.66668 1.31998 2.52185 + vertex 1.6663 1.3233 2.52254 + vertex 1.66393 1.31917 2.52399 + endloop + endfacet + facet normal 0.632446 -0.0920199 0.769119 + outer loop + vertex 1.6663 1.3233 2.52254 + vertex 1.66372 1.32396 2.52473 + vertex 1.66393 1.31917 2.52399 + endloop + endfacet + facet normal 0.570788 -0.112972 0.813288 + outer loop + vertex 1.66333 1.32731 2.52547 + vertex 1.66144 1.32481 2.52645 + vertex 1.66372 1.32396 2.52473 + endloop + endfacet + facet normal 0.630406 -0.0964301 0.770253 + outer loop + vertex 1.66333 1.32731 2.52547 + vertex 1.66372 1.32396 2.52473 + vertex 1.6661 1.32821 2.52332 + endloop + endfacet + facet normal 0.631337 -0.0972381 0.769388 + outer loop + vertex 1.6661 1.32821 2.52332 + vertex 1.66372 1.32396 2.52473 + vertex 1.6663 1.3233 2.52254 + endloop + endfacet + facet normal 0.546963 -0.0874205 0.83258 + outer loop + vertex 1.66333 1.32731 2.52547 + vertex 1.66097 1.32818 2.52711 + vertex 1.66144 1.32481 2.52645 + endloop + endfacet + facet normal 0.633809 -0.0830376 0.769019 + outer loop + vertex 1.6661 1.32821 2.52332 + vertex 1.66678 1.3338 2.52336 + vertex 1.66389 1.33117 2.52546 + endloop + endfacet + facet normal 0.629294 -0.0886303 0.772097 + outer loop + vertex 1.66333 1.32731 2.52547 + vertex 1.6661 1.32821 2.52332 + vertex 1.66389 1.33117 2.52546 + endloop + endfacet + facet normal 0.550082 -0.0770101 0.831552 + outer loop + vertex 1.66389 1.33117 2.52546 + vertex 1.66097 1.32818 2.52711 + vertex 1.66333 1.32731 2.52547 + endloop + endfacet + facet normal 0.551244 -0.0786477 0.830629 + outer loop + vertex 1.66115 1.33294 2.52745 + vertex 1.66097 1.32818 2.52711 + vertex 1.66389 1.33117 2.52546 + endloop + endfacet + facet normal 0.635047 -0.0571697 0.770355 + outer loop + vertex 1.66678 1.3338 2.52336 + vertex 1.66705 1.33894 2.52352 + vertex 1.66425 1.33613 2.52563 + endloop + endfacet + facet normal 0.627301 -0.0706678 0.775564 + outer loop + vertex 1.66389 1.33117 2.52546 + vertex 1.66678 1.3338 2.52336 + vertex 1.66425 1.33613 2.52563 + endloop + endfacet + facet normal 0.556683 -0.0672953 0.827995 + outer loop + vertex 1.66425 1.33613 2.52563 + vertex 1.66115 1.33294 2.52745 + vertex 1.66389 1.33117 2.52546 + endloop + endfacet + facet normal 0.552499 -0.0613643 0.831252 + outer loop + vertex 1.66146 1.33807 2.52762 + vertex 1.66115 1.33294 2.52745 + vertex 1.66425 1.33613 2.52563 + endloop + endfacet + facet normal 0.636718 -0.0238294 0.770729 + outer loop + vertex 1.66705 1.33894 2.52352 + vertex 1.66713 1.34396 2.52361 + vertex 1.66441 1.34119 2.52577 + endloop + endfacet + facet normal 0.626664 -0.0429952 0.778103 + outer loop + vertex 1.66425 1.33613 2.52563 + vertex 1.66705 1.33894 2.52352 + vertex 1.66441 1.34119 2.52577 + endloop + endfacet + facet normal 0.562061 -0.0422393 0.826017 + outer loop + vertex 1.66441 1.34119 2.52577 + vertex 1.66146 1.33807 2.52762 + vertex 1.66425 1.33613 2.52563 + endloop + endfacet + facet normal 0.560093 -0.0395128 0.827487 + outer loop + vertex 1.66162 1.34311 2.52775 + vertex 1.66146 1.33807 2.52762 + vertex 1.66441 1.34119 2.52577 + endloop + endfacet + facet normal 0.642272 -0.00334586 0.76647 + outer loop + vertex 1.66713 1.34396 2.52361 + vertex 1.66714 1.34895 2.52362 + vertex 1.66445 1.34622 2.52586 + endloop + endfacet + facet normal 0.634105 -0.0194923 0.773001 + outer loop + vertex 1.66441 1.34119 2.52577 + vertex 1.66713 1.34396 2.52361 + vertex 1.66445 1.34622 2.52586 + endloop + endfacet + facet normal 0.56952 -0.019876 0.821737 + outer loop + vertex 1.66445 1.34622 2.52586 + vertex 1.66162 1.34311 2.52775 + vertex 1.66441 1.34119 2.52577 + endloop + endfacet + facet normal 0.575416 -0.027884 0.817385 + outer loop + vertex 1.66165 1.34809 2.5279 + vertex 1.66162 1.34311 2.52775 + vertex 1.66445 1.34622 2.52586 + endloop + endfacet + facet normal 0.652854 -0.00973834 0.757421 + outer loop + vertex 1.66714 1.34895 2.52362 + vertex 1.66721 1.35396 2.52363 + vertex 1.66446 1.35131 2.52596 + endloop + endfacet + facet normal 0.649686 -0.015942 0.760036 + outer loop + vertex 1.66445 1.34622 2.52586 + vertex 1.66714 1.34895 2.52362 + vertex 1.66446 1.35131 2.52596 + endloop + endfacet + facet normal 0.580412 -0.0169092 0.814147 + outer loop + vertex 1.66446 1.35131 2.52596 + vertex 1.66165 1.34809 2.5279 + vertex 1.66445 1.34622 2.52586 + endloop + endfacet + facet normal 0.590228 -0.0299864 0.806679 + outer loop + vertex 1.66139 1.35338 2.52829 + vertex 1.66165 1.34809 2.5279 + vertex 1.66446 1.35131 2.52596 + endloop + endfacet + facet normal 0.667729 -0.0352863 0.743567 + outer loop + vertex 1.66721 1.35396 2.52363 + vertex 1.66732 1.35896 2.52376 + vertex 1.66464 1.35647 2.52606 + endloop + endfacet + facet normal 0.667171 -0.0362946 0.74402 + outer loop + vertex 1.66446 1.35131 2.52596 + vertex 1.66721 1.35396 2.52363 + vertex 1.66464 1.35647 2.52606 + endloop + endfacet + facet normal 0.588047 -0.0347807 0.808078 + outer loop + vertex 1.66464 1.35647 2.52606 + vertex 1.66139 1.35338 2.52829 + vertex 1.66446 1.35131 2.52596 + endloop + endfacet + facet normal 0.600015 -0.0545301 0.798128 + outer loop + vertex 1.66207 1.35892 2.52816 + vertex 1.66139 1.35338 2.52829 + vertex 1.66464 1.35647 2.52606 + endloop + endfacet + facet normal 0.686917 -0.055491 0.724614 + outer loop + vertex 1.66732 1.35896 2.52376 + vertex 1.6674 1.3638 2.52406 + vertex 1.66496 1.36149 2.5262 + endloop + endfacet + facet normal 0.681807 -0.0642295 0.728707 + outer loop + vertex 1.66464 1.35647 2.52606 + vertex 1.66732 1.35896 2.52376 + vertex 1.66496 1.36149 2.5262 + endloop + endfacet + facet normal 0.596047 -0.0608329 0.800642 + outer loop + vertex 1.66496 1.36149 2.5262 + vertex 1.66207 1.35892 2.52816 + vertex 1.66464 1.35647 2.52606 + endloop + endfacet + facet normal 0.598672 -0.0655763 0.798305 + outer loop + vertex 1.6625 1.36396 2.52824 + vertex 1.66207 1.35892 2.52816 + vertex 1.66496 1.36149 2.5262 + endloop + endfacet + facet normal 0.703222 -0.0621049 0.708252 + outer loop + vertex 1.6674 1.3638 2.52406 + vertex 1.6673 1.36772 2.52451 + vertex 1.66529 1.36609 2.52636 + endloop + endfacet + facet normal 0.695963 -0.0747558 0.714176 + outer loop + vertex 1.66496 1.36149 2.5262 + vertex 1.6674 1.3638 2.52406 + vertex 1.66529 1.36609 2.52636 + endloop + endfacet + facet normal 0.595401 -0.0704966 0.80033 + outer loop + vertex 1.66529 1.36609 2.52636 + vertex 1.6625 1.36396 2.52824 + vertex 1.66496 1.36149 2.5262 + endloop + endfacet + facet normal 0.586986 -0.0528629 0.807869 + outer loop + vertex 1.66315 1.36936 2.52813 + vertex 1.6625 1.36396 2.52824 + vertex 1.66529 1.36609 2.52636 + endloop + endfacet + facet normal 0.699076 -0.0513752 0.713199 + outer loop + vertex 1.6673 1.36772 2.52451 + vertex 1.66594 1.36978 2.52598 + vertex 1.66529 1.36609 2.52636 + endloop + endfacet + facet normal 0.611314 -0.0277964 0.7909 + outer loop + vertex 1.66594 1.36978 2.52598 + vertex 1.66315 1.36936 2.52813 + vertex 1.66529 1.36609 2.52636 + endloop + endfacet + facet normal 0.60936 -0.00481475 0.792879 + outer loop + vertex 1.66594 1.36978 2.52598 + vertex 1.6656 1.37366 2.52627 + vertex 1.66315 1.36936 2.52813 + endloop + endfacet + facet normal 0.625189 -0.0192752 0.780236 + outer loop + vertex 1.6656 1.37366 2.52627 + vertex 1.66282 1.37467 2.52853 + vertex 1.66315 1.36936 2.52813 + endloop + endfacet + facet normal 0.627608 -0.0086693 0.778481 + outer loop + vertex 1.6656 1.37366 2.52627 + vertex 1.66543 1.37861 2.52646 + vertex 1.66282 1.37467 2.52853 + endloop + endfacet + facet normal 0.632658 -0.0142181 0.774301 + outer loop + vertex 1.66282 1.37467 2.52853 + vertex 1.66543 1.37861 2.52646 + vertex 1.66278 1.37964 2.52864 + endloop + endfacet + facet normal 0.634329 -0.0072228 0.773029 + outer loop + vertex 1.66543 1.37861 2.52646 + vertex 1.66542 1.38354 2.52651 + vertex 1.66278 1.37964 2.52864 + endloop + endfacet + facet normal 0.637135 -0.0104043 0.770682 + outer loop + vertex 1.66278 1.37964 2.52864 + vertex 1.66542 1.38354 2.52651 + vertex 1.66281 1.38457 2.52869 + endloop + endfacet + facet normal 0.637843 -0.00744478 0.77013 + outer loop + vertex 1.66542 1.38354 2.52651 + vertex 1.66535 1.38841 2.52662 + vertex 1.66281 1.38457 2.52869 + endloop + endfacet + facet normal 0.636858 -0.0063451 0.770955 + outer loop + vertex 1.66281 1.38457 2.52869 + vertex 1.66535 1.38841 2.52662 + vertex 1.66267 1.3894 2.52885 + endloop + endfacet + facet normal 0.636514 -0.00788121 0.771225 + outer loop + vertex 1.66535 1.38841 2.52662 + vertex 1.66498 1.39351 2.52698 + vertex 1.66267 1.3894 2.52885 + endloop + endfacet + facet normal 0.621715 0.00589109 0.783222 + outer loop + vertex 1.66267 1.3894 2.52885 + vertex 1.66498 1.39351 2.52698 + vertex 1.66218 1.39346 2.5292 + endloop + endfacet + facet normal 0.779055 0.0568337 0.624375 + outer loop + vertex 1.66713 1.39593 2.52467 + vertex 1.66741 1.39976 2.52397 + vertex 1.66574 1.39767 2.52624 + endloop + endfacet + facet normal 0.740871 -0.016129 0.671454 + outer loop + vertex 1.66574 1.39767 2.52624 + vertex 1.66498 1.39351 2.52698 + vertex 1.66713 1.39593 2.52467 + endloop + endfacet + facet normal 0.644064 0.0182385 0.764754 + outer loop + vertex 1.66574 1.39767 2.52624 + vertex 1.66302 1.39801 2.52852 + vertex 1.66498 1.39351 2.52698 + endloop + endfacet + facet normal 0.621761 0.00226122 0.783204 + outer loop + vertex 1.66302 1.39801 2.52852 + vertex 1.66218 1.39346 2.5292 + vertex 1.66498 1.39351 2.52698 + endloop + endfacet + facet normal 0.780507 0.0620116 0.622063 + outer loop + vertex 1.66741 1.39976 2.52397 + vertex 1.66722 1.40453 2.52373 + vertex 1.66531 1.40164 2.52641 + endloop + endfacet + facet normal 0.778931 0.0570756 0.624507 + outer loop + vertex 1.66574 1.39767 2.52624 + vertex 1.66741 1.39976 2.52397 + vertex 1.66531 1.40164 2.52641 + endloop + endfacet + facet normal 0.645117 0.0367704 0.763199 + outer loop + vertex 1.66531 1.40164 2.52641 + vertex 1.66302 1.39801 2.52852 + vertex 1.66574 1.39767 2.52624 + endloop + endfacet + facet normal 0.659559 0.0207644 0.751366 + outer loop + vertex 1.66261 1.40363 2.52873 + vertex 1.66302 1.39801 2.52852 + vertex 1.66531 1.40164 2.52641 + endloop + endfacet + facet normal -0.0417349 -0.0145879 0.999022 + outer loop + vertex 1.67 1.40897 2.515 + vertex 1.66964 1.41 2.515 + vertex 1.66891 1.40958 2.51496 + endloop + endfacet + facet normal 0.796133 0.0323425 0.604256 + outer loop + vertex 1.66722 1.40453 2.52373 + vertex 1.66707 1.40957 2.52365 + vertex 1.66508 1.40662 2.52644 + endloop + endfacet + facet normal 0.796718 0.0340595 0.603391 + outer loop + vertex 1.66531 1.40164 2.52641 + vertex 1.66722 1.40453 2.52373 + vertex 1.66508 1.40662 2.52644 + endloop + endfacet + facet normal 0.662015 0.0268328 0.74901 + outer loop + vertex 1.66508 1.40662 2.52644 + vertex 1.66261 1.40363 2.52873 + vertex 1.66531 1.40164 2.52641 + endloop + endfacet + facet normal 0.674965 0.00762152 0.73781 + outer loop + vertex 1.66247 1.40881 2.5288 + vertex 1.66261 1.40363 2.52873 + vertex 1.66508 1.40662 2.52644 + endloop + endfacet + facet normal 0.88608 -0.00354914 -0.463518 + outer loop + vertex 1.66964 1.41 2.515 + vertex 1.66966 1.415 2.515 + vertex 1.67 1.415 2.51565 + endloop + endfacet + facet normal 0.0258822 -0.130691 0.991085 + outer loop + vertex 1.66891 1.40958 2.51496 + vertex 1.66964 1.41 2.515 + vertex 1.67 1.415 2.51565 + endloop + endfacet + facet normal 0.807164 0.0101247 0.590241 + outer loop + vertex 1.66707 1.40957 2.52365 + vertex 1.66705 1.41464 2.52361 + vertex 1.66501 1.41171 2.52644 + endloop + endfacet + facet normal 0.807469 0.0109828 0.589807 + outer loop + vertex 1.66508 1.40662 2.52644 + vertex 1.66707 1.40957 2.52365 + vertex 1.66501 1.41171 2.52644 + endloop + endfacet + facet normal 0.675769 0.00939691 0.737054 + outer loop + vertex 1.66501 1.41171 2.52644 + vertex 1.66247 1.40881 2.5288 + vertex 1.66508 1.40662 2.52644 + endloop + endfacet + facet normal 0.683236 -0.00275714 0.730192 + outer loop + vertex 1.66246 1.41386 2.52883 + vertex 1.66247 1.40881 2.5288 + vertex 1.66501 1.41171 2.52644 + endloop + endfacet + facet normal 0.812909 -0.00276025 0.582384 + outer loop + vertex 1.66705 1.41464 2.52361 + vertex 1.66708 1.41965 2.52359 + vertex 1.66503 1.41674 2.52642 + endloop + endfacet + facet normal 0.81318 -0.00199699 0.582009 + outer loop + vertex 1.66501 1.41171 2.52644 + vertex 1.66705 1.41464 2.52361 + vertex 1.66503 1.41674 2.52642 + endloop + endfacet + facet normal 0.683988 -0.00108799 0.729493 + outer loop + vertex 1.66503 1.41674 2.52642 + vertex 1.66246 1.41386 2.52883 + vertex 1.66501 1.41171 2.52644 + endloop + endfacet + facet normal 0.685193 -0.0031185 0.728355 + outer loop + vertex 1.66246 1.41886 2.52885 + vertex 1.66246 1.41386 2.52883 + vertex 1.66503 1.41674 2.52642 + endloop + endfacet + facet normal 0.810812 0.00962017 0.585227 + outer loop + vertex 1.66708 1.41965 2.52359 + vertex 1.66704 1.42458 2.52355 + vertex 1.66503 1.4217 2.52639 + endloop + endfacet + facet normal 0.809193 0.00486102 0.587523 + outer loop + vertex 1.66503 1.41674 2.52642 + vertex 1.66708 1.41965 2.52359 + vertex 1.66503 1.4217 2.52639 + endloop + endfacet + facet normal 0.688953 0.00552081 0.724785 + outer loop + vertex 1.66503 1.4217 2.52639 + vertex 1.66246 1.41886 2.52885 + vertex 1.66503 1.41674 2.52642 + endloop + endfacet + facet normal 0.69111 0.00180401 0.722747 + outer loop + vertex 1.66245 1.42384 2.52885 + vertex 1.66246 1.41886 2.52885 + vertex 1.66503 1.4217 2.52639 + endloop + endfacet + facet normal 0.811007 0.0193182 0.584717 + outer loop + vertex 1.66704 1.42458 2.52355 + vertex 1.66697 1.42951 2.52349 + vertex 1.66498 1.42661 2.52635 + endloop + endfacet + facet normal 0.809009 0.0132582 0.587647 + outer loop + vertex 1.66503 1.4217 2.52639 + vertex 1.66704 1.42458 2.52355 + vertex 1.66498 1.42661 2.52635 + endloop + endfacet + facet normal 0.696013 0.0132491 0.717907 + outer loop + vertex 1.66498 1.42661 2.52635 + vertex 1.66245 1.42384 2.52885 + vertex 1.66503 1.4217 2.52639 + endloop + endfacet + facet normal 0.698342 0.00913692 0.715706 + outer loop + vertex 1.66242 1.42878 2.52882 + vertex 1.66245 1.42384 2.52885 + vertex 1.66498 1.42661 2.52635 + endloop + endfacet + facet normal 0.811517 0.026815 0.583713 + outer loop + vertex 1.66697 1.42951 2.52349 + vertex 1.66687 1.43448 2.5234 + vertex 1.66489 1.43152 2.52629 + endloop + endfacet + facet normal 0.80986 0.0215941 0.586225 + outer loop + vertex 1.66498 1.42661 2.52635 + vertex 1.66697 1.42951 2.52349 + vertex 1.66489 1.43152 2.52629 + endloop + endfacet + facet normal 0.70343 0.0211342 0.71045 + outer loop + vertex 1.66489 1.43152 2.52629 + vertex 1.66242 1.42878 2.52882 + vertex 1.66498 1.42661 2.52635 + endloop + endfacet + facet normal 0.706373 0.0159008 0.707661 + outer loop + vertex 1.66234 1.4337 2.52879 + vertex 1.66242 1.42878 2.52882 + vertex 1.66489 1.43152 2.52629 + endloop + endfacet + facet normal 0.814006 0.0159038 0.580639 + outer loop + vertex 1.66687 1.43448 2.5234 + vertex 1.66683 1.43941 2.52332 + vertex 1.66481 1.43642 2.52623 + endloop + endfacet + facet normal 0.815166 0.0196657 0.578894 + outer loop + vertex 1.66489 1.43152 2.52629 + vertex 1.66687 1.43448 2.5234 + vertex 1.66481 1.43642 2.52623 + endloop + endfacet + facet normal 0.707884 0.0194984 0.70606 + outer loop + vertex 1.66481 1.43642 2.52623 + vertex 1.66234 1.4337 2.52879 + vertex 1.66489 1.43152 2.52629 + endloop + endfacet + facet normal 0.711733 0.0125203 0.702339 + outer loop + vertex 1.66226 1.43865 2.52878 + vertex 1.66234 1.4337 2.52879 + vertex 1.66481 1.43642 2.52623 + endloop + endfacet + facet normal 0.813672 0.0108718 0.581223 + outer loop + vertex 1.66683 1.43941 2.52332 + vertex 1.66681 1.44432 2.52325 + vertex 1.66476 1.44135 2.52618 + endloop + endfacet + facet normal 0.81476 0.0144003 0.57962 + outer loop + vertex 1.66481 1.43642 2.52623 + vertex 1.66683 1.43941 2.52332 + vertex 1.66476 1.44135 2.52618 + endloop + endfacet + facet normal 0.712727 0.0148641 0.701284 + outer loop + vertex 1.66476 1.44135 2.52618 + vertex 1.66226 1.43865 2.52878 + vertex 1.66481 1.43642 2.52623 + endloop + endfacet + facet normal 0.714972 0.0106373 0.699072 + outer loop + vertex 1.66221 1.44365 2.52875 + vertex 1.66226 1.43865 2.52878 + vertex 1.66476 1.44135 2.52618 + endloop + endfacet + facet normal 0.813678 0.00753817 0.581268 + outer loop + vertex 1.66681 1.44432 2.52325 + vertex 1.6668 1.44925 2.5232 + vertex 1.66474 1.4463 2.52613 + endloop + endfacet + facet normal 0.814317 0.00956015 0.580341 + outer loop + vertex 1.66476 1.44135 2.52618 + vertex 1.66681 1.44432 2.52325 + vertex 1.66474 1.4463 2.52613 + endloop + endfacet + facet normal 0.714822 0.0102936 0.699231 + outer loop + vertex 1.66474 1.4463 2.52613 + vertex 1.66221 1.44365 2.52875 + vertex 1.66476 1.44135 2.52618 + endloop + endfacet + facet normal 0.716926 0.00618667 0.697122 + outer loop + vertex 1.66219 1.44869 2.52873 + vertex 1.66221 1.44365 2.52875 + vertex 1.66474 1.4463 2.52613 + endloop + endfacet + facet normal 0.814244 0.00200138 0.58052 + outer loop + vertex 1.6668 1.44925 2.5232 + vertex 1.6668 1.4542 2.52319 + vertex 1.66473 1.45127 2.5261 + endloop + endfacet + facet normal 0.815095 0.00461394 0.579309 + outer loop + vertex 1.66474 1.4463 2.52613 + vertex 1.6668 1.44925 2.5232 + vertex 1.66473 1.45127 2.5261 + endloop + endfacet + facet normal 0.71634 0.0048957 0.697734 + outer loop + vertex 1.66473 1.45127 2.5261 + vertex 1.66219 1.44869 2.52873 + vertex 1.66474 1.4463 2.52613 + endloop + endfacet + facet normal 0.716201 0.00517555 0.697875 + outer loop + vertex 1.66216 1.45377 2.52872 + vertex 1.66219 1.44869 2.52873 + vertex 1.66473 1.45127 2.5261 + endloop + endfacet + facet normal 0.810806 0.00201784 0.585312 + outer loop + vertex 1.6668 1.4542 2.52319 + vertex 1.66677 1.45917 2.52321 + vertex 1.66469 1.45627 2.5261 + endloop + endfacet + facet normal 0.812209 0.00623366 0.583333 + outer loop + vertex 1.66473 1.45127 2.5261 + vertex 1.6668 1.4542 2.52319 + vertex 1.66469 1.45627 2.5261 + endloop + endfacet + facet normal 0.716377 0.00555061 0.697691 + outer loop + vertex 1.66469 1.45627 2.5261 + vertex 1.66216 1.45377 2.52872 + vertex 1.66473 1.45127 2.5261 + endloop + endfacet + facet normal 0.713814 0.0108382 0.700251 + outer loop + vertex 1.6621 1.45884 2.5287 + vertex 1.66216 1.45377 2.52872 + vertex 1.66469 1.45627 2.5261 + endloop + endfacet + facet normal 0.805577 0.00958802 0.592413 + outer loop + vertex 1.66677 1.45917 2.52321 + vertex 1.66671 1.46415 2.52321 + vertex 1.66462 1.46125 2.5261 + endloop + endfacet + facet normal 0.806214 0.0114972 0.591512 + outer loop + vertex 1.66469 1.45627 2.5261 + vertex 1.66677 1.45917 2.52321 + vertex 1.66462 1.46125 2.5261 + endloop + endfacet + facet normal 0.713522 0.0102347 0.700558 + outer loop + vertex 1.66462 1.46125 2.5261 + vertex 1.6621 1.45884 2.5287 + vertex 1.66469 1.45627 2.5261 + endloop + endfacet + facet normal 0.709275 0.0191246 0.704673 + outer loop + vertex 1.662 1.46387 2.52867 + vertex 1.6621 1.45884 2.5287 + vertex 1.66462 1.46125 2.5261 + endloop + endfacet + facet normal 0.800184 0.0133832 0.599605 + outer loop + vertex 1.66671 1.46415 2.52321 + vertex 1.66665 1.46914 2.52318 + vertex 1.66453 1.46622 2.52608 + endloop + endfacet + facet normal 0.801593 0.0176446 0.597609 + outer loop + vertex 1.66462 1.46125 2.5261 + vertex 1.66671 1.46415 2.52321 + vertex 1.66453 1.46622 2.52608 + endloop + endfacet + facet normal 0.707913 0.016353 0.70611 + outer loop + vertex 1.66453 1.46622 2.52608 + vertex 1.662 1.46387 2.52867 + vertex 1.66462 1.46125 2.5261 + endloop + endfacet + facet normal 0.704221 0.024122 0.709571 + outer loop + vertex 1.66188 1.46884 2.52862 + vertex 1.662 1.46387 2.52867 + vertex 1.66453 1.46622 2.52608 + endloop + endfacet + facet normal 0.795548 0.00949113 0.605817 + outer loop + vertex 1.66665 1.46914 2.52318 + vertex 1.66662 1.47411 2.52314 + vertex 1.66445 1.47118 2.52604 + endloop + endfacet + facet normal 0.798172 0.0173997 0.602178 + outer loop + vertex 1.66453 1.46622 2.52608 + vertex 1.66665 1.46914 2.52318 + vertex 1.66445 1.47118 2.52604 + endloop + endfacet + facet normal 0.700549 0.0166928 0.713409 + outer loop + vertex 1.66445 1.47118 2.52604 + vertex 1.66188 1.46884 2.52862 + vertex 1.66453 1.46622 2.52608 + endloop + endfacet + facet normal 0.699084 0.0197932 0.714765 + outer loop + vertex 1.66179 1.47381 2.52857 + vertex 1.66188 1.46884 2.52862 + vertex 1.66445 1.47118 2.52604 + endloop + endfacet + facet normal 0.792252 0.00549425 0.610169 + outer loop + vertex 1.66662 1.47411 2.52314 + vertex 1.66661 1.47912 2.52312 + vertex 1.66441 1.47616 2.526 + endloop + endfacet + facet normal 0.794393 0.0118041 0.60729 + outer loop + vertex 1.66445 1.47118 2.52604 + vertex 1.66662 1.47411 2.52314 + vertex 1.66441 1.47616 2.526 + endloop + endfacet + facet normal 0.695151 0.0119605 0.718764 + outer loop + vertex 1.66441 1.47616 2.526 + vertex 1.66179 1.47381 2.52857 + vertex 1.66445 1.47118 2.52604 + endloop + endfacet + facet normal 0.695768 0.0106453 0.718187 + outer loop + vertex 1.66175 1.47879 2.52853 + vertex 1.66179 1.47381 2.52857 + vertex 1.66441 1.47616 2.526 + endloop + endfacet + facet normal 0.790474 -0.00338522 0.612487 + outer loop + vertex 1.66661 1.47912 2.52312 + vertex 1.66663 1.4841 2.52312 + vertex 1.6644 1.48116 2.52597 + endloop + endfacet + facet normal 0.793018 0.00396509 0.609185 + outer loop + vertex 1.66441 1.47616 2.526 + vertex 1.66661 1.47912 2.52312 + vertex 1.6644 1.48116 2.52597 + endloop + endfacet + facet normal 0.692576 0.00438363 0.721332 + outer loop + vertex 1.6644 1.48116 2.52597 + vertex 1.66175 1.47879 2.52853 + vertex 1.66441 1.47616 2.526 + endloop + endfacet + facet normal 0.691783 0.00607687 0.722079 + outer loop + vertex 1.66173 1.48379 2.52851 + vertex 1.66175 1.47879 2.52853 + vertex 1.6644 1.48116 2.52597 + endloop + endfacet + facet normal 0.787535 0.00123734 0.616268 + outer loop + vertex 1.66663 1.4841 2.52312 + vertex 1.66661 1.48911 2.52313 + vertex 1.6644 1.48616 2.52596 + endloop + endfacet + facet normal 0.787798 0.00198659 0.615931 + outer loop + vertex 1.6644 1.48116 2.52597 + vertex 1.66663 1.4841 2.52312 + vertex 1.6644 1.48616 2.52596 + endloop + endfacet + facet normal 0.689787 0.00218871 0.724009 + outer loop + vertex 1.6644 1.48616 2.52596 + vertex 1.66173 1.48379 2.52851 + vertex 1.6644 1.48116 2.52597 + endloop + endfacet + facet normal 0.687058 0.00799713 0.726558 + outer loop + vertex 1.66169 1.48878 2.52849 + vertex 1.66173 1.48379 2.52851 + vertex 1.6644 1.48616 2.52596 + endloop + endfacet + facet normal 0.783358 0.00319694 0.621563 + outer loop + vertex 1.66661 1.48911 2.52313 + vertex 1.66659 1.49409 2.52313 + vertex 1.66436 1.49115 2.52595 + endloop + endfacet + facet normal 0.784643 0.00690416 0.619909 + outer loop + vertex 1.6644 1.48616 2.52596 + vertex 1.66661 1.48911 2.52313 + vertex 1.66436 1.49115 2.52595 + endloop + endfacet + facet normal 0.686287 0.00648129 0.727302 + outer loop + vertex 1.66436 1.49115 2.52595 + vertex 1.66169 1.48878 2.52849 + vertex 1.6644 1.48616 2.52596 + endloop + endfacet + facet normal 0.681195 0.0171528 0.731901 + outer loop + vertex 1.66161 1.49374 2.52846 + vertex 1.66169 1.48878 2.52849 + vertex 1.66436 1.49115 2.52595 + endloop + endfacet + facet normal 0.775745 0.00953084 0.630974 + outer loop + vertex 1.66659 1.49409 2.52313 + vertex 1.66654 1.4991 2.52312 + vertex 1.66429 1.49614 2.52593 + endloop + endfacet + facet normal 0.777472 0.0145198 0.62875 + outer loop + vertex 1.66436 1.49115 2.52595 + vertex 1.66659 1.49409 2.52313 + vertex 1.66429 1.49614 2.52593 + endloop + endfacet + facet normal 0.679273 0.0133114 0.733765 + outer loop + vertex 1.66429 1.49614 2.52593 + vertex 1.66161 1.49374 2.52846 + vertex 1.66436 1.49115 2.52595 + endloop + endfacet + facet normal 0.675719 0.0205667 0.736873 + outer loop + vertex 1.66146 1.49872 2.52845 + vertex 1.66161 1.49374 2.52846 + vertex 1.66429 1.49614 2.52593 + endloop + endfacet + facet normal 0.771765 0.00528973 0.635886 + outer loop + vertex 1.66654 1.4991 2.52312 + vertex 1.66654 1.50407 2.52307 + vertex 1.66421 1.50117 2.52593 + endloop + endfacet + facet normal 0.774255 0.0123561 0.632754 + outer loop + vertex 1.66429 1.49614 2.52593 + vertex 1.66654 1.4991 2.52312 + vertex 1.66421 1.50117 2.52593 + endloop + endfacet + facet normal 0.670906 0.0108351 0.741463 + outer loop + vertex 1.66421 1.50117 2.52593 + vertex 1.66146 1.49872 2.52845 + vertex 1.66429 1.49614 2.52593 + endloop + endfacet + facet normal 0.67009 0.012488 0.742175 + outer loop + vertex 1.66116 1.5041 2.52863 + vertex 1.66146 1.49872 2.52845 + vertex 1.66421 1.50117 2.52593 + endloop + endfacet + facet normal 0.77753 -0.00127965 0.628845 + outer loop + vertex 1.66654 1.50407 2.52307 + vertex 1.66658 1.50899 2.52303 + vertex 1.66433 1.50605 2.52581 + endloop + endfacet + facet normal 0.776489 -0.00419595 0.630116 + outer loop + vertex 1.66421 1.50117 2.52593 + vertex 1.66654 1.50407 2.52307 + vertex 1.66433 1.50605 2.52581 + endloop + endfacet + facet normal 0.664225 0.00147002 0.747531 + outer loop + vertex 1.66433 1.50605 2.52581 + vertex 1.66116 1.5041 2.52863 + vertex 1.66421 1.50117 2.52593 + endloop + endfacet + facet normal 0.671824 -0.0212253 0.740407 + outer loop + vertex 1.66213 1.5084 2.52787 + vertex 1.66116 1.5041 2.52863 + vertex 1.66433 1.50605 2.52581 + endloop + endfacet + facet normal 0.781798 -0.00204122 0.623528 + outer loop + vertex 1.66658 1.50899 2.52303 + vertex 1.66657 1.51396 2.52306 + vertex 1.6644 1.51077 2.52577 + endloop + endfacet + facet normal 0.780307 -0.00669509 0.625361 + outer loop + vertex 1.66433 1.50605 2.52581 + vertex 1.66658 1.50899 2.52303 + vertex 1.6644 1.51077 2.52577 + endloop + endfacet + facet normal 0.681633 -0.00443538 0.73168 + outer loop + vertex 1.6644 1.51077 2.52577 + vertex 1.66213 1.5084 2.52787 + vertex 1.66433 1.50605 2.52581 + endloop + endfacet + facet normal 0.671131 0.0140206 0.741206 + outer loop + vertex 1.66154 1.51269 2.52833 + vertex 1.66213 1.5084 2.52787 + vertex 1.6644 1.51077 2.52577 + endloop + endfacet + facet normal 0.768476 -0.00719917 0.639838 + outer loop + vertex 1.66657 1.51396 2.52306 + vertex 1.66657 1.51899 2.52312 + vertex 1.66418 1.51579 2.52595 + endloop + endfacet + facet normal 0.774139 0.0111743 0.632917 + outer loop + vertex 1.6644 1.51077 2.52577 + vertex 1.66657 1.51396 2.52306 + vertex 1.66418 1.51579 2.52595 + endloop + endfacet + facet normal 0.666897 0.00245353 0.745146 + outer loop + vertex 1.66418 1.51579 2.52595 + vertex 1.66154 1.51269 2.52833 + vertex 1.6644 1.51077 2.52577 + endloop + endfacet + facet normal 0.659471 0.0137054 0.751605 + outer loop + vertex 1.66072 1.51848 2.52894 + vertex 1.66154 1.51269 2.52833 + vertex 1.66418 1.51579 2.52595 + endloop + endfacet + facet normal 0.770118 -0.00572912 0.637876 + outer loop + vertex 1.66657 1.51899 2.52312 + vertex 1.6666 1.52402 2.52313 + vertex 1.66425 1.5209 2.52594 + endloop + endfacet + facet normal 0.769182 -0.00849234 0.638974 + outer loop + vertex 1.66418 1.51579 2.52595 + vertex 1.66657 1.51899 2.52312 + vertex 1.66425 1.5209 2.52594 + endloop + endfacet + facet normal 0.650526 -0.00647722 0.759456 + outer loop + vertex 1.66425 1.5209 2.52594 + vertex 1.66072 1.51848 2.52894 + vertex 1.66418 1.51579 2.52595 + endloop + endfacet + facet normal 0.661279 -0.0347249 0.749336 + outer loop + vertex 1.66206 1.52325 2.52798 + vertex 1.66072 1.51848 2.52894 + vertex 1.66425 1.5209 2.52594 + endloop + endfacet + facet normal 0.779879 0.00395003 0.625918 + outer loop + vertex 1.6666 1.52402 2.52313 + vertex 1.66658 1.52902 2.52313 + vertex 1.66441 1.52577 2.52585 + endloop + endfacet + facet normal 0.774311 -0.0135685 0.63266 + outer loop + vertex 1.66425 1.5209 2.52594 + vertex 1.6666 1.52402 2.52313 + vertex 1.66441 1.52577 2.52585 + endloop + endfacet + facet normal 0.676842 -0.00859524 0.736078 + outer loop + vertex 1.66441 1.52577 2.52585 + vertex 1.66206 1.52325 2.52798 + vertex 1.66425 1.5209 2.52594 + endloop + endfacet + facet normal 0.668683 0.00532118 0.743529 + outer loop + vertex 1.6617 1.52755 2.52828 + vertex 1.66206 1.52325 2.52798 + vertex 1.66441 1.52577 2.52585 + endloop + endfacet + facet normal 0.774265 0.015282 0.632677 + outer loop + vertex 1.66658 1.52902 2.52313 + vertex 1.66651 1.53403 2.52309 + vertex 1.6643 1.53066 2.52588 + endloop + endfacet + facet normal 0.773906 0.0140003 0.633146 + outer loop + vertex 1.66441 1.52577 2.52585 + vertex 1.66658 1.52902 2.52313 + vertex 1.6643 1.53066 2.52588 + endloop + endfacet + facet normal 0.6708 0.0112148 0.741553 + outer loop + vertex 1.6643 1.53066 2.52588 + vertex 1.6617 1.52755 2.52828 + vertex 1.66441 1.52577 2.52585 + endloop + endfacet + facet normal 0.669915 0.0125565 0.742332 + outer loop + vertex 1.66153 1.53257 2.52834 + vertex 1.6617 1.52755 2.52828 + vertex 1.6643 1.53066 2.52588 + endloop + endfacet + facet normal 0.771498 0.0125319 0.636108 + outer loop + vertex 1.66651 1.53403 2.52309 + vertex 1.66649 1.53902 2.52301 + vertex 1.66422 1.53566 2.52583 + endloop + endfacet + facet normal 0.772893 0.0175201 0.634295 + outer loop + vertex 1.6643 1.53066 2.52588 + vertex 1.66651 1.53403 2.52309 + vertex 1.66422 1.53566 2.52583 + endloop + endfacet + facet normal 0.671566 0.0169954 0.740749 + outer loop + vertex 1.66422 1.53566 2.52583 + vertex 1.66153 1.53257 2.52834 + vertex 1.6643 1.53066 2.52588 + endloop + endfacet + facet normal 0.673161 0.0144722 0.739354 + outer loop + vertex 1.66148 1.5376 2.52829 + vertex 1.66153 1.53257 2.52834 + vertex 1.66422 1.53566 2.52583 + endloop + endfacet + facet normal 0.770317 0.00490796 0.637642 + outer loop + vertex 1.66649 1.53902 2.52301 + vertex 1.66653 1.54401 2.52293 + vertex 1.66422 1.54065 2.52574 + endloop + endfacet + facet normal 0.772172 0.0114094 0.635311 + outer loop + vertex 1.66422 1.53566 2.52583 + vertex 1.66649 1.53902 2.52301 + vertex 1.66422 1.54065 2.52574 + endloop + endfacet + facet normal 0.672634 0.0130814 0.73986 + outer loop + vertex 1.66422 1.54065 2.52574 + vertex 1.66148 1.5376 2.52829 + vertex 1.66422 1.53566 2.52583 + endloop + endfacet + facet normal 0.67492 0.0093412 0.737832 + outer loop + vertex 1.6615 1.54258 2.52821 + vertex 1.66148 1.5376 2.52829 + vertex 1.66422 1.54065 2.52574 + endloop + endfacet + facet normal 0.770251 -0.000602299 0.637741 + outer loop + vertex 1.66653 1.54401 2.52293 + vertex 1.66656 1.54901 2.52289 + vertex 1.66426 1.54563 2.52567 + endloop + endfacet + facet normal 0.771339 0.00318205 0.636416 + outer loop + vertex 1.66422 1.54065 2.52574 + vertex 1.66653 1.54401 2.52293 + vertex 1.66426 1.54563 2.52567 + endloop + endfacet + facet normal 0.673412 0.00539272 0.739248 + outer loop + vertex 1.66426 1.54563 2.52567 + vertex 1.6615 1.54258 2.52821 + vertex 1.66422 1.54065 2.52574 + endloop + endfacet + facet normal 0.675921 0.00123013 0.736973 + outer loop + vertex 1.66152 1.54755 2.52818 + vertex 1.6615 1.54258 2.52821 + vertex 1.66426 1.54563 2.52567 + endloop + endfacet + facet normal 0.770558 -0.00943713 0.637299 + outer loop + vertex 1.66656 1.54901 2.52289 + vertex 1.66661 1.554 2.52291 + vertex 1.66429 1.55061 2.52567 + endloop + endfacet + facet normal 0.772177 -0.00383927 0.635396 + outer loop + vertex 1.66426 1.54563 2.52567 + vertex 1.66656 1.54901 2.52289 + vertex 1.66429 1.55061 2.52567 + endloop + endfacet + facet normal 0.674257 -0.00310646 0.73849 + outer loop + vertex 1.66429 1.55061 2.52567 + vertex 1.66152 1.54755 2.52818 + vertex 1.66426 1.54563 2.52567 + endloop + endfacet + facet normal 0.673565 -0.00196051 0.739125 + outer loop + vertex 1.66147 1.55257 2.52824 + vertex 1.66152 1.54755 2.52818 + vertex 1.66429 1.55061 2.52567 + endloop + endfacet + facet normal 0.76498 -0.0131849 0.643919 + outer loop + vertex 1.66661 1.554 2.52291 + vertex 1.66665 1.55902 2.52296 + vertex 1.66425 1.5557 2.52575 + endloop + endfacet + facet normal 0.767615 -0.00449297 0.640895 + outer loop + vertex 1.66429 1.55061 2.52567 + vertex 1.66661 1.554 2.52291 + vertex 1.66425 1.5557 2.52575 + endloop + endfacet + facet normal 0.671644 -0.00696506 0.740841 + outer loop + vertex 1.66425 1.5557 2.52575 + vertex 1.66147 1.55257 2.52824 + vertex 1.66429 1.55061 2.52567 + endloop + endfacet + facet normal 0.670343 -0.00486592 0.742036 + outer loop + vertex 1.6611 1.55801 2.52861 + vertex 1.66147 1.55257 2.52824 + vertex 1.66425 1.5557 2.52575 + endloop + endfacet + facet normal 0.766201 -0.0153851 0.642417 + outer loop + vertex 1.66665 1.55902 2.52296 + vertex 1.66672 1.56406 2.52301 + vertex 1.6643 1.5609 2.52581 + endloop + endfacet + facet normal 0.766211 -0.0153566 0.642406 + outer loop + vertex 1.66425 1.5557 2.52575 + vertex 1.66665 1.55902 2.52296 + vertex 1.6643 1.5609 2.52581 + endloop + endfacet + facet normal 0.666037 -0.0153608 0.745761 + outer loop + vertex 1.6643 1.5609 2.52581 + vertex 1.6611 1.55801 2.52861 + vertex 1.66425 1.5557 2.52575 + endloop + endfacet + facet normal 0.671963 -0.0274313 0.740076 + outer loop + vertex 1.66161 1.56351 2.52835 + vertex 1.6611 1.55801 2.52861 + vertex 1.6643 1.5609 2.52581 + endloop + endfacet + facet normal 0.772616 -0.0183218 0.634609 + outer loop + vertex 1.66672 1.56406 2.52301 + vertex 1.66679 1.56907 2.52306 + vertex 1.66446 1.56606 2.52581 + endloop + endfacet + facet normal 0.770622 -0.0237045 0.636851 + outer loop + vertex 1.6643 1.5609 2.52581 + vertex 1.66672 1.56406 2.52301 + vertex 1.66446 1.56606 2.52581 + endloop + endfacet + facet normal 0.67558 -0.0206984 0.736996 + outer loop + vertex 1.66446 1.56606 2.52581 + vertex 1.66161 1.56351 2.52835 + vertex 1.6643 1.5609 2.52581 + endloop + endfacet + facet normal 0.678336 -0.0265 0.734274 + outer loop + vertex 1.66182 1.56859 2.52834 + vertex 1.66161 1.56351 2.52835 + vertex 1.66446 1.56606 2.52581 + endloop + endfacet + facet normal 0.776014 -0.0206963 0.630377 + outer loop + vertex 1.66679 1.56907 2.52306 + vertex 1.66686 1.57405 2.52313 + vertex 1.66459 1.57112 2.52584 + endloop + endfacet + facet normal 0.775087 -0.0231269 0.631431 + outer loop + vertex 1.66446 1.56606 2.52581 + vertex 1.66679 1.56907 2.52306 + vertex 1.66459 1.57112 2.52584 + endloop + endfacet + facet normal 0.681017 -0.0213963 0.731955 + outer loop + vertex 1.66459 1.57112 2.52584 + vertex 1.66182 1.56859 2.52834 + vertex 1.66446 1.56606 2.52581 + endloop + endfacet + facet normal 0.682872 -0.0252602 0.730102 + outer loop + vertex 1.66199 1.57357 2.52836 + vertex 1.66182 1.56859 2.52834 + vertex 1.66459 1.57112 2.52584 + endloop + endfacet + facet normal 0.777922 -0.0231419 0.627935 + outer loop + vertex 1.66686 1.57405 2.52313 + vertex 1.66693 1.57898 2.52323 + vertex 1.6647 1.57613 2.52589 + endloop + endfacet + facet normal 0.777626 -0.0238936 0.628272 + outer loop + vertex 1.66459 1.57112 2.52584 + vertex 1.66686 1.57405 2.52313 + vertex 1.6647 1.57613 2.52589 + endloop + endfacet + facet normal 0.684131 -0.0227975 0.729003 + outer loop + vertex 1.6647 1.57613 2.52589 + vertex 1.66199 1.57357 2.52836 + vertex 1.66459 1.57112 2.52584 + endloop + endfacet + facet normal 0.685224 -0.0250183 0.727903 + outer loop + vertex 1.66211 1.57853 2.52841 + vertex 1.66199 1.57357 2.52836 + vertex 1.6647 1.57613 2.52589 + endloop + endfacet + facet normal 0.782206 -0.0103616 0.622933 + outer loop + vertex 1.66693 1.57898 2.52323 + vertex 1.66691 1.58401 2.52334 + vertex 1.66478 1.58114 2.52596 + endloop + endfacet + facet normal 0.77744 -0.0221749 0.628566 + outer loop + vertex 1.6647 1.57613 2.52589 + vertex 1.66693 1.57898 2.52323 + vertex 1.66478 1.58114 2.52596 + endloop + endfacet + facet normal 0.68662 -0.0222132 0.726677 + outer loop + vertex 1.66478 1.58114 2.52596 + vertex 1.66211 1.57853 2.52841 + vertex 1.6647 1.57613 2.52589 + endloop + endfacet + facet normal 0.686951 -0.0228649 0.726344 + outer loop + vertex 1.66219 1.58354 2.52849 + vertex 1.66211 1.57853 2.52841 + vertex 1.66478 1.58114 2.52596 + endloop + endfacet + facet normal 0.793294 -0.00262423 0.608833 + outer loop + vertex 1.66691 1.58401 2.52334 + vertex 1.66687 1.58917 2.52341 + vertex 1.66483 1.58617 2.52606 + endloop + endfacet + facet normal 0.786758 -0.0192203 0.616962 + outer loop + vertex 1.66478 1.58114 2.52596 + vertex 1.66691 1.58401 2.52334 + vertex 1.66483 1.58617 2.52606 + endloop + endfacet + facet normal 0.688105 -0.0205389 0.72532 + outer loop + vertex 1.66483 1.58617 2.52606 + vertex 1.66219 1.58354 2.52849 + vertex 1.66478 1.58114 2.52596 + endloop + endfacet + facet normal 0.68608 -0.0166474 0.727336 + outer loop + vertex 1.66225 1.58858 2.52855 + vertex 1.66219 1.58354 2.52849 + vertex 1.66483 1.58617 2.52606 + endloop + endfacet + facet normal 0.801363 -0.0052484 0.598155 + outer loop + vertex 1.66687 1.58917 2.52341 + vertex 1.66688 1.59432 2.52344 + vertex 1.66483 1.59118 2.52616 + endloop + endfacet + facet normal 0.79869 -0.0126717 0.601609 + outer loop + vertex 1.66483 1.58617 2.52606 + vertex 1.66687 1.58917 2.52341 + vertex 1.66483 1.59118 2.52616 + endloop + endfacet + facet normal 0.686958 -0.0148942 0.726544 + outer loop + vertex 1.66483 1.59118 2.52616 + vertex 1.66225 1.58858 2.52855 + vertex 1.66483 1.58617 2.52606 + endloop + endfacet + facet normal 0.68387 -0.00908261 0.729547 + outer loop + vertex 1.66229 1.59355 2.52857 + vertex 1.66225 1.58858 2.52855 + vertex 1.66483 1.59118 2.52616 + endloop + endfacet + facet normal 0.803507 -0.00527364 0.595272 + outer loop + vertex 1.66688 1.59432 2.52344 + vertex 1.66693 1.59934 2.52343 + vertex 1.66484 1.59616 2.52622 + endloop + endfacet + facet normal 0.802717 -0.00772745 0.59631 + outer loop + vertex 1.66483 1.59118 2.52616 + vertex 1.66688 1.59432 2.52344 + vertex 1.66484 1.59616 2.52622 + endloop + endfacet + facet normal 0.683867 -0.00908955 0.72955 + outer loop + vertex 1.66484 1.59616 2.52622 + vertex 1.66229 1.59355 2.52857 + vertex 1.66483 1.59118 2.52616 + endloop + endfacet + facet normal 0.680292 -0.00253587 0.732937 + outer loop + vertex 1.66232 1.59845 2.52856 + vertex 1.66229 1.59355 2.52857 + vertex 1.66484 1.59616 2.52622 + endloop + endfacet + facet normal 0.800517 -0.0251619 0.598781 + outer loop + vertex 1.66693 1.59934 2.52343 + vertex 1.66705 1.60424 2.52347 + vertex 1.66488 1.60112 2.52624 + endloop + endfacet + facet normal 0.805606 -0.00918354 0.59238 + outer loop + vertex 1.66484 1.59616 2.52622 + vertex 1.66693 1.59934 2.52343 + vertex 1.66488 1.60112 2.52624 + endloop + endfacet + facet normal 0.677198 -0.00880469 0.735748 + outer loop + vertex 1.66488 1.60112 2.52624 + vertex 1.66232 1.59845 2.52856 + vertex 1.66484 1.59616 2.52622 + endloop + endfacet + facet normal 0.674515 -0.00406057 0.73825 + outer loop + vertex 1.66234 1.60339 2.52857 + vertex 1.66232 1.59845 2.52856 + vertex 1.66488 1.60112 2.52624 + endloop + endfacet + facet normal 0.782889 -0.0457892 0.620474 + outer loop + vertex 1.66705 1.60424 2.52347 + vertex 1.66721 1.60918 2.52364 + vertex 1.66495 1.60616 2.52626 + endloop + endfacet + facet normal 0.794534 -0.0136493 0.607066 + outer loop + vertex 1.66488 1.60112 2.52624 + vertex 1.66705 1.60424 2.52347 + vertex 1.66495 1.60616 2.52626 + endloop + endfacet + facet normal 0.670406 -0.0123975 0.741891 + outer loop + vertex 1.66495 1.60616 2.52626 + vertex 1.66234 1.60339 2.52857 + vertex 1.66488 1.60112 2.52624 + endloop + endfacet + facet normal 0.668159 -0.00853952 0.74397 + outer loop + vertex 1.66239 1.60847 2.52859 + vertex 1.66234 1.60339 2.52857 + vertex 1.66495 1.60616 2.52626 + endloop + endfacet + facet normal 0.86602 -0.294286 -0.404234 + outer loop + vertex 1.67 1.61103 2.515 + vertex 1.67 1.61 2.51575 + vertex 1.66965 1.61 2.515 + endloop + endfacet + facet normal 0.757097 -0.0556327 0.650929 + outer loop + vertex 1.66721 1.60918 2.52364 + vertex 1.66731 1.61406 2.52394 + vertex 1.66506 1.61119 2.52631 + endloop + endfacet + facet normal 0.770614 -0.0224031 0.636909 + outer loop + vertex 1.66495 1.60616 2.52626 + vertex 1.66721 1.60918 2.52364 + vertex 1.66506 1.61119 2.52631 + endloop + endfacet + facet normal 0.661645 -0.0213282 0.749514 + outer loop + vertex 1.66506 1.61119 2.52631 + vertex 1.66239 1.60847 2.52859 + vertex 1.66495 1.60616 2.52626 + endloop + endfacet + facet normal 0.656115 -0.0116498 0.754571 + outer loop + vertex 1.66254 1.61361 2.52853 + vertex 1.66239 1.60847 2.52859 + vertex 1.66506 1.61119 2.52631 + endloop + endfacet + facet normal 0.732376 -0.0498448 0.679073 + outer loop + vertex 1.66731 1.61406 2.52394 + vertex 1.66716 1.61786 2.52438 + vertex 1.66521 1.61589 2.52634 + endloop + endfacet + facet normal 0.74165 -0.0275553 0.67022 + outer loop + vertex 1.66506 1.61119 2.52631 + vertex 1.66731 1.61406 2.52394 + vertex 1.66521 1.61589 2.52634 + endloop + endfacet + facet normal 0.648658 -0.0250034 0.760669 + outer loop + vertex 1.66521 1.61589 2.52634 + vertex 1.66254 1.61361 2.52853 + vertex 1.66506 1.61119 2.52631 + endloop + endfacet + facet normal 0.641692 -0.0108596 0.766885 + outer loop + vertex 1.66292 1.61898 2.5283 + vertex 1.66254 1.61361 2.52853 + vertex 1.66521 1.61589 2.52634 + endloop + endfacet + facet normal 0.720025 -0.0233103 0.693556 + outer loop + vertex 1.66716 1.61786 2.52438 + vertex 1.66569 1.61961 2.52596 + vertex 1.66521 1.61589 2.52634 + endloop + endfacet + facet normal 0.645185 -0.0064447 0.763999 + outer loop + vertex 1.66569 1.61961 2.52596 + vertex 1.66292 1.61898 2.5283 + vertex 1.66521 1.61589 2.52634 + endloop + endfacet + facet normal 0.645194 -0.00651004 0.763991 + outer loop + vertex 1.66569 1.61961 2.52596 + vertex 1.66497 1.6235 2.5266 + vertex 1.66292 1.61898 2.5283 + endloop + endfacet + facet normal 0.629164 0.0057571 0.777251 + outer loop + vertex 1.66497 1.6235 2.5266 + vertex 1.66207 1.6233 2.52895 + vertex 1.66292 1.61898 2.5283 + endloop + endfacet + facet normal 0.753016 0.0196647 0.657709 + outer loop + vertex 1.66729 1.62563 2.52419 + vertex 1.66761 1.62944 2.52371 + vertex 1.66568 1.62751 2.52598 + endloop + endfacet + facet normal 0.730569 -0.0230929 0.682448 + outer loop + vertex 1.66568 1.62751 2.52598 + vertex 1.66497 1.6235 2.5266 + vertex 1.66729 1.62563 2.52419 + endloop + endfacet + facet normal 0.635745 0.00738803 0.771864 + outer loop + vertex 1.66568 1.62751 2.52598 + vertex 1.66286 1.62783 2.5283 + vertex 1.66497 1.6235 2.5266 + endloop + endfacet + facet normal 0.629317 0.00219368 0.777146 + outer loop + vertex 1.66286 1.62783 2.5283 + vertex 1.66207 1.6233 2.52895 + vertex 1.66497 1.6235 2.5266 + endloop + endfacet + facet normal 0.737559 0.0226062 0.674904 + outer loop + vertex 1.66761 1.62944 2.52371 + vertex 1.6674 1.63418 2.52378 + vertex 1.66525 1.63141 2.52623 + endloop + endfacet + facet normal 0.743848 0.0400282 0.66715 + outer loop + vertex 1.66568 1.62751 2.52598 + vertex 1.66761 1.62944 2.52371 + vertex 1.66525 1.63141 2.52623 + endloop + endfacet + facet normal 0.636587 0.0217154 0.7709 + outer loop + vertex 1.66525 1.63141 2.52623 + vertex 1.66286 1.62783 2.5283 + vertex 1.66568 1.62751 2.52598 + endloop + endfacet + facet normal 0.629499 0.0296446 0.776435 + outer loop + vertex 1.66245 1.63337 2.52842 + vertex 1.66286 1.62783 2.5283 + vertex 1.66525 1.63141 2.52623 + endloop + endfacet + facet normal 0.721854 0.0227882 0.69167 + outer loop + vertex 1.6674 1.63418 2.52378 + vertex 1.66718 1.63896 2.52386 + vertex 1.66497 1.63632 2.52625 + endloop + endfacet + facet normal 0.728119 0.0382968 0.68438 + outer loop + vertex 1.66525 1.63141 2.52623 + vertex 1.6674 1.63418 2.52378 + vertex 1.66497 1.63632 2.52625 + endloop + endfacet + facet normal 0.6306 0.0323248 0.775435 + outer loop + vertex 1.66497 1.63632 2.52625 + vertex 1.66245 1.63337 2.52842 + vertex 1.66525 1.63141 2.52623 + endloop + endfacet + facet normal 0.626561 0.0379877 0.778446 + outer loop + vertex 1.66224 1.63855 2.52834 + vertex 1.66245 1.63337 2.52842 + vertex 1.66497 1.63632 2.52625 + endloop + endfacet + facet normal 0.707556 0.0240034 0.706249 + outer loop + vertex 1.66718 1.63896 2.52386 + vertex 1.66719 1.64366 2.52369 + vertex 1.6648 1.64131 2.52616 + endloop + endfacet + facet normal 0.713654 0.0367628 0.699533 + outer loop + vertex 1.66497 1.63632 2.52625 + vertex 1.66718 1.63896 2.52386 + vertex 1.6648 1.64131 2.52616 + endloop + endfacet + facet normal 0.625229 0.0352378 0.779645 + outer loop + vertex 1.6648 1.64131 2.52616 + vertex 1.66224 1.63855 2.52834 + vertex 1.66497 1.63632 2.52625 + endloop + endfacet + facet normal 0.623193 0.0383037 0.781129 + outer loop + vertex 1.66209 1.64362 2.52821 + vertex 1.66224 1.63855 2.52834 + vertex 1.6648 1.64131 2.52616 + endloop + endfacet + facet normal 0.696093 0.014725 0.717801 + outer loop + vertex 1.66719 1.64366 2.52369 + vertex 1.66726 1.64855 2.52351 + vertex 1.66472 1.64626 2.52603 + endloop + endfacet + facet normal 0.704358 0.0303325 0.709197 + outer loop + vertex 1.6648 1.64131 2.52616 + vertex 1.66719 1.64366 2.52369 + vertex 1.66472 1.64626 2.52603 + endloop + endfacet + facet normal 0.619384 0.0308591 0.784481 + outer loop + vertex 1.66472 1.64626 2.52603 + vertex 1.66209 1.64362 2.52821 + vertex 1.6648 1.64131 2.52616 + endloop + endfacet + facet normal 0.620755 0.0286763 0.78348 + outer loop + vertex 1.66199 1.6486 2.5281 + vertex 1.66209 1.64362 2.52821 + vertex 1.66472 1.64626 2.52603 + endloop + endfacet + facet normal 0.682655 -0.00476168 0.730725 + outer loop + vertex 1.66726 1.64855 2.52351 + vertex 1.6672 1.65354 2.5236 + vertex 1.66464 1.65123 2.52598 + endloop + endfacet + facet normal 0.694686 0.0177128 0.719095 + outer loop + vertex 1.66472 1.64626 2.52603 + vertex 1.66726 1.64855 2.52351 + vertex 1.66464 1.65123 2.52598 + endloop + endfacet + facet normal 0.614802 0.0172763 0.788492 + outer loop + vertex 1.66464 1.65123 2.52598 + vertex 1.66199 1.6486 2.5281 + vertex 1.66472 1.64626 2.52603 + endloop + endfacet + facet normal 0.612378 0.0211792 0.790282 + outer loop + vertex 1.66187 1.65356 2.52806 + vertex 1.66199 1.6486 2.5281 + vertex 1.66464 1.65123 2.52598 + endloop + endfacet + facet normal 0.665913 0.00293394 0.746024 + outer loop + vertex 1.6672 1.65354 2.5236 + vertex 1.66712 1.65847 2.52366 + vertex 1.66452 1.65619 2.52598 + endloop + endfacet + facet normal 0.672717 0.0154435 0.739739 + outer loop + vertex 1.66464 1.65123 2.52598 + vertex 1.6672 1.65354 2.5236 + vertex 1.66452 1.65619 2.52598 + endloop + endfacet + facet normal 0.608552 0.0138691 0.793393 + outer loop + vertex 1.66452 1.65619 2.52598 + vertex 1.66187 1.65356 2.52806 + vertex 1.66464 1.65123 2.52598 + endloop + endfacet + facet normal 0.60376 0.021458 0.796877 + outer loop + vertex 1.66167 1.65862 2.52808 + vertex 1.66187 1.65356 2.52806 + vertex 1.66452 1.65619 2.52598 + endloop + endfacet + facet normal 0.655391 0.0178515 0.755079 + outer loop + vertex 1.66712 1.65847 2.52366 + vertex 1.66703 1.66337 2.52361 + vertex 1.66438 1.66121 2.52597 + endloop + endfacet + facet normal 0.657036 0.020762 0.753573 + outer loop + vertex 1.66452 1.65619 2.52598 + vertex 1.66712 1.65847 2.52366 + vertex 1.66438 1.66121 2.52597 + endloop + endfacet + facet normal 0.602557 0.0192028 0.797845 + outer loop + vertex 1.66438 1.66121 2.52597 + vertex 1.66167 1.65862 2.52808 + vertex 1.66452 1.65619 2.52598 + endloop + endfacet + facet normal 0.599868 0.0235553 0.799752 + outer loop + vertex 1.6613 1.66415 2.52819 + vertex 1.66167 1.65862 2.52808 + vertex 1.66438 1.66121 2.52597 + endloop + endfacet + facet normal 0.657779 0.0255505 0.752778 + outer loop + vertex 1.66703 1.66337 2.52361 + vertex 1.66696 1.66827 2.52351 + vertex 1.6644 1.66609 2.52582 + endloop + endfacet + facet normal 0.654453 0.0198397 0.755842 + outer loop + vertex 1.66438 1.66121 2.52597 + vertex 1.66703 1.66337 2.52361 + vertex 1.6644 1.66609 2.52582 + endloop + endfacet + facet normal 0.598605 0.0214768 0.800756 + outer loop + vertex 1.6644 1.66609 2.52582 + vertex 1.6613 1.66415 2.52819 + vertex 1.66438 1.66121 2.52597 + endloop + endfacet + facet normal 0.604201 0.00771519 0.796795 + outer loop + vertex 1.66224 1.66857 2.52744 + vertex 1.6613 1.66415 2.52819 + vertex 1.6644 1.66609 2.52582 + endloop + endfacet + facet normal 0.664723 0.0261998 0.746631 + outer loop + vertex 1.66696 1.66827 2.52351 + vertex 1.66686 1.67322 2.52343 + vertex 1.66441 1.67075 2.52569 + endloop + endfacet + facet normal 0.660915 0.0191371 0.750216 + outer loop + vertex 1.6644 1.66609 2.52582 + vertex 1.66696 1.66827 2.52351 + vertex 1.66441 1.67075 2.52569 + endloop + endfacet + facet normal 0.613302 0.020367 0.789586 + outer loop + vertex 1.66441 1.67075 2.52569 + vertex 1.66224 1.66857 2.52744 + vertex 1.6644 1.66609 2.52582 + endloop + endfacet + facet normal 0.611008 0.0239998 0.79126 + outer loop + vertex 1.66175 1.67261 2.52769 + vertex 1.66224 1.66857 2.52744 + vertex 1.66441 1.67075 2.52569 + endloop + endfacet + facet normal 0.669843 0.029486 0.741917 + outer loop + vertex 1.66686 1.67322 2.52343 + vertex 1.66675 1.67832 2.52332 + vertex 1.66426 1.67554 2.52568 + endloop + endfacet + facet normal 0.666639 0.0228444 0.745031 + outer loop + vertex 1.66441 1.67075 2.52569 + vertex 1.66686 1.67322 2.52343 + vertex 1.66426 1.67554 2.52568 + endloop + endfacet + facet normal 0.609783 0.0211497 0.792286 + outer loop + vertex 1.66426 1.67554 2.52568 + vertex 1.66175 1.67261 2.52769 + vertex 1.66441 1.67075 2.52569 + endloop + endfacet + facet normal 0.610273 0.0204827 0.791926 + outer loop + vertex 1.66151 1.67746 2.52775 + vertex 1.66175 1.67261 2.52769 + vertex 1.66426 1.67554 2.52568 + endloop + endfacet + facet normal 0.677163 0.0393637 0.734779 + outer loop + vertex 1.66675 1.67832 2.52332 + vertex 1.66666 1.68345 2.52313 + vertex 1.66416 1.68056 2.52559 + endloop + endfacet + facet normal 0.671449 0.0268976 0.740563 + outer loop + vertex 1.66426 1.67554 2.52568 + vertex 1.66675 1.67832 2.52332 + vertex 1.66416 1.68056 2.52559 + endloop + endfacet + facet normal 0.61292 0.026661 0.789695 + outer loop + vertex 1.66416 1.68056 2.52559 + vertex 1.66151 1.67746 2.52775 + vertex 1.66426 1.67554 2.52568 + endloop + endfacet + facet normal 0.609695 0.0310423 0.792028 + outer loop + vertex 1.66138 1.68247 2.52766 + vertex 1.66151 1.67746 2.52775 + vertex 1.66416 1.68056 2.52559 + endloop + endfacet + facet normal 0.678776 0.0546714 0.732308 + outer loop + vertex 1.66666 1.68345 2.52313 + vertex 1.66655 1.68837 2.52286 + vertex 1.66407 1.68559 2.52537 + endloop + endfacet + facet normal 0.674213 0.0440009 0.737225 + outer loop + vertex 1.66416 1.68056 2.52559 + vertex 1.66666 1.68345 2.52313 + vertex 1.66407 1.68559 2.52537 + endloop + endfacet + facet normal 0.615472 0.0450885 0.786868 + outer loop + vertex 1.66407 1.68559 2.52537 + vertex 1.66138 1.68247 2.52766 + vertex 1.66416 1.68056 2.52559 + endloop + endfacet + facet normal 0.605622 0.0584802 0.793601 + outer loop + vertex 1.66118 1.68747 2.52744 + vertex 1.66138 1.68247 2.52766 + vertex 1.66407 1.68559 2.52537 + endloop + endfacet + facet normal 0.671598 0.0671501 0.737866 + outer loop + vertex 1.66655 1.68837 2.52286 + vertex 1.66645 1.69274 2.52256 + vertex 1.66396 1.69046 2.52503 + endloop + endfacet + facet normal 0.671356 0.0665643 0.73814 + outer loop + vertex 1.66407 1.68559 2.52537 + vertex 1.66655 1.68837 2.52286 + vertex 1.66396 1.69046 2.52503 + endloop + endfacet + facet normal 0.609576 0.0688336 0.789734 + outer loop + vertex 1.66396 1.69046 2.52503 + vertex 1.66118 1.68747 2.52744 + vertex 1.66407 1.68559 2.52537 + endloop + endfacet + facet normal 0.598627 0.0845117 0.796557 + outer loop + vertex 1.66084 1.69248 2.52716 + vertex 1.66118 1.68747 2.52744 + vertex 1.66396 1.69046 2.52503 + endloop + endfacet + facet normal 0.658557 0.0688546 0.749374 + outer loop + vertex 1.66645 1.69274 2.52256 + vertex 1.66649 1.69551 2.52227 + vertex 1.66413 1.69534 2.52436 + endloop + endfacet + facet normal 0.665039 0.0793543 0.742581 + outer loop + vertex 1.66396 1.69046 2.52503 + vertex 1.66645 1.69274 2.52256 + vertex 1.66413 1.69534 2.52436 + endloop + endfacet + facet normal 0.600197 0.0886426 0.794925 + outer loop + vertex 1.66413 1.69534 2.52436 + vertex 1.66084 1.69248 2.52716 + vertex 1.66396 1.69046 2.52503 + endloop + endfacet + facet normal 0.602114 0.085373 0.793833 + outer loop + vertex 1.66031 1.69764 2.52701 + vertex 1.66084 1.69248 2.52716 + vertex 1.66413 1.69534 2.52436 + endloop + endfacet + facet normal 0.692915 0.0473419 0.719463 + outer loop + vertex 1.6668 1.69861 2.52167 + vertex 1.66857 1.70361 2.51964 + vertex 1.66567 1.7022 2.52252 + endloop + endfacet + facet normal 0.640565 0.053935 0.766008 + outer loop + vertex 1.66567 1.7022 2.52252 + vertex 1.66329 1.70374 2.5244 + vertex 1.66358 1.69976 2.52444 + endloop + endfacet + facet normal 0.657842 0.0286028 0.752613 + outer loop + vertex 1.6668 1.69861 2.52167 + vertex 1.66567 1.7022 2.52252 + vertex 1.66358 1.69976 2.52444 + endloop + endfacet + facet normal 0.664844 0.0693567 0.743755 + outer loop + vertex 1.6668 1.69861 2.52167 + vertex 1.66358 1.69976 2.52444 + vertex 1.66413 1.69534 2.52436 + endloop + endfacet + facet normal 0.657594 0.0797144 0.749144 + outer loop + vertex 1.6668 1.69861 2.52167 + vertex 1.66413 1.69534 2.52436 + vertex 1.66649 1.69551 2.52227 + endloop + endfacet + facet normal 0.592936 0.0595728 0.803043 + outer loop + vertex 1.66413 1.69534 2.52436 + vertex 1.66358 1.69976 2.52444 + vertex 1.66031 1.69764 2.52701 + endloop + endfacet + facet normal 0.685301 0.020317 0.727977 + outer loop + vertex 1.66857 1.70361 2.51964 + vertex 1.66844 1.70902 2.5196 + vertex 1.66585 1.70612 2.52212 + endloop + endfacet + facet normal 0.694834 0.0404879 0.71803 + outer loop + vertex 1.66567 1.7022 2.52252 + vertex 1.66857 1.70361 2.51964 + vertex 1.66585 1.70612 2.52212 + endloop + endfacet + facet normal 0.638486 0.0481184 0.768128 + outer loop + vertex 1.66585 1.70612 2.52212 + vertex 1.66329 1.70374 2.5244 + vertex 1.66567 1.7022 2.52252 + endloop + endfacet + facet normal 0.633034 0.0576618 0.771974 + outer loop + vertex 1.66303 1.70821 2.52428 + vertex 1.66329 1.70374 2.5244 + vertex 1.66585 1.70612 2.52212 + endloop + endfacet + facet normal 0.668365 0.0206899 0.743545 + outer loop + vertex 1.66844 1.70902 2.5196 + vertex 1.66822 1.71409 2.51966 + vertex 1.66574 1.71099 2.52198 + endloop + endfacet + facet normal 0.674867 0.0375072 0.736985 + outer loop + vertex 1.66585 1.70612 2.52212 + vertex 1.66844 1.70902 2.5196 + vertex 1.66574 1.71099 2.52198 + endloop + endfacet + facet normal 0.62444 0.0375724 0.780169 + outer loop + vertex 1.66574 1.71099 2.52198 + vertex 1.66303 1.70821 2.52428 + vertex 1.66585 1.70612 2.52212 + endloop + endfacet + facet normal 0.616905 0.0492959 0.785492 + outer loop + vertex 1.66283 1.71321 2.52412 + vertex 1.66303 1.70821 2.52428 + vertex 1.66574 1.71099 2.52198 + endloop + endfacet + facet normal 0.652413 0.0166849 0.75768 + outer loop + vertex 1.66822 1.71409 2.51966 + vertex 1.66782 1.71844 2.51991 + vertex 1.66557 1.71598 2.5219 + endloop + endfacet + facet normal 0.659186 0.0337828 0.751221 + outer loop + vertex 1.66574 1.71099 2.52198 + vertex 1.66822 1.71409 2.51966 + vertex 1.66557 1.71598 2.5219 + endloop + endfacet + facet normal 0.609305 0.032784 0.792258 + outer loop + vertex 1.66557 1.71598 2.5219 + vertex 1.66283 1.71321 2.52412 + vertex 1.66574 1.71099 2.52198 + endloop + endfacet + facet normal 0.603172 0.0422444 0.796492 + outer loop + vertex 1.66271 1.7183 2.52394 + vertex 1.66283 1.71321 2.52412 + vertex 1.66557 1.71598 2.5219 + endloop + endfacet + facet normal 0.643762 0.0353765 0.764408 + outer loop + vertex 1.66782 1.71844 2.51991 + vertex 1.66884 1.72325 2.51883 + vertex 1.66558 1.72094 2.52169 + endloop + endfacet + facet normal 0.642081 0.0327821 0.765935 + outer loop + vertex 1.66557 1.71598 2.5219 + vertex 1.66782 1.71844 2.51991 + vertex 1.66558 1.72094 2.52169 + endloop + endfacet + facet normal 0.599152 0.034289 0.799901 + outer loop + vertex 1.66558 1.72094 2.52169 + vertex 1.66271 1.7183 2.52394 + vertex 1.66557 1.71598 2.5219 + endloop + endfacet + facet normal 0.5931 0.044299 0.803909 + outer loop + vertex 1.66255 1.72333 2.52378 + vertex 1.66271 1.7183 2.52394 + vertex 1.66558 1.72094 2.52169 + endloop + endfacet + facet normal 0.635295 0.0181832 0.772056 + outer loop + vertex 1.66884 1.72325 2.51883 + vertex 1.66768 1.72826 2.51967 + vertex 1.66541 1.72594 2.52159 + endloop + endfacet + facet normal 0.64343 0.036145 0.764651 + outer loop + vertex 1.66558 1.72094 2.52169 + vertex 1.66884 1.72325 2.51883 + vertex 1.66541 1.72594 2.52159 + endloop + endfacet + facet normal 0.58851 0.0351671 0.807725 + outer loop + vertex 1.66541 1.72594 2.52159 + vertex 1.66255 1.72333 2.52378 + vertex 1.66558 1.72094 2.52169 + endloop + endfacet + facet normal 0.576645 0.0544575 0.815178 + outer loop + vertex 1.66221 1.72837 2.52369 + vertex 1.66255 1.72333 2.52378 + vertex 1.66541 1.72594 2.52159 + endloop + endfacet + facet normal 0.62119 0.0481164 0.782181 + outer loop + vertex 1.66768 1.72826 2.51967 + vertex 1.66827 1.73283 2.51892 + vertex 1.6651 1.73094 2.52155 + endloop + endfacet + facet normal 0.618837 0.0443914 0.784264 + outer loop + vertex 1.66541 1.72594 2.52159 + vertex 1.66768 1.72826 2.51967 + vertex 1.6651 1.73094 2.52155 + endloop + endfacet + facet normal 0.570306 0.041622 0.820377 + outer loop + vertex 1.6651 1.73094 2.52155 + vertex 1.66221 1.72837 2.52369 + vertex 1.66541 1.72594 2.52159 + endloop + endfacet + facet normal 0.555321 0.0657196 0.829036 + outer loop + vertex 1.6616 1.73388 2.52366 + vertex 1.66221 1.72837 2.52369 + vertex 1.6651 1.73094 2.52155 + endloop + endfacet + facet normal 0.618862 0.0444149 0.784243 + outer loop + vertex 1.66827 1.73283 2.51892 + vertex 1.66778 1.73833 2.51899 + vertex 1.66505 1.73591 2.52128 + endloop + endfacet + facet normal 0.621116 0.048308 0.782229 + outer loop + vertex 1.6651 1.73094 2.52155 + vertex 1.66827 1.73283 2.51892 + vertex 1.66505 1.73591 2.52128 + endloop + endfacet + facet normal 0.546635 0.0504909 0.835847 + outer loop + vertex 1.66505 1.73591 2.52128 + vertex 1.6616 1.73388 2.52366 + vertex 1.6651 1.73094 2.52155 + endloop + endfacet + facet normal 0.549335 0.0442565 0.834429 + outer loop + vertex 1.66249 1.73838 2.52284 + vertex 1.6616 1.73388 2.52366 + vertex 1.66505 1.73591 2.52128 + endloop + endfacet + facet normal 0.611238 0.0509708 0.789804 + outer loop + vertex 1.66778 1.73833 2.51899 + vertex 1.66754 1.74337 2.51885 + vertex 1.66488 1.74074 2.52108 + endloop + endfacet + facet normal 0.613083 0.0546423 0.788127 + outer loop + vertex 1.66505 1.73591 2.52128 + vertex 1.66778 1.73833 2.51899 + vertex 1.66488 1.74074 2.52108 + endloop + endfacet + facet normal 0.555968 0.054297 0.829428 + outer loop + vertex 1.66488 1.74074 2.52108 + vertex 1.66249 1.73838 2.52284 + vertex 1.66505 1.73591 2.52128 + endloop + endfacet + facet normal 0.53417 0.0849267 0.841101 + outer loop + vertex 1.66173 1.74246 2.52291 + vertex 1.66249 1.73838 2.52284 + vertex 1.66488 1.74074 2.52108 + endloop + endfacet + facet normal 0.593609 0.0508282 0.803147 + outer loop + vertex 1.66754 1.74337 2.51885 + vertex 1.66738 1.74837 2.51865 + vertex 1.66455 1.74555 2.52092 + endloop + endfacet + facet normal 0.600884 0.0671344 0.796512 + outer loop + vertex 1.66488 1.74074 2.52108 + vertex 1.66754 1.74337 2.51885 + vertex 1.66455 1.74555 2.52092 + endloop + endfacet + facet normal 0.526526 0.0638118 0.847761 + outer loop + vertex 1.66455 1.74555 2.52092 + vertex 1.66173 1.74246 2.52291 + vertex 1.66488 1.74074 2.52108 + endloop + endfacet + facet normal 0.50636 0.0886117 0.857757 + outer loop + vertex 1.6612 1.74733 2.52272 + vertex 1.66173 1.74246 2.52291 + vertex 1.66455 1.74555 2.52092 + endloop + endfacet + facet normal 0.578518 0.0502383 0.814121 + outer loop + vertex 1.66738 1.74837 2.51865 + vertex 1.66723 1.75333 2.51845 + vertex 1.66435 1.75045 2.52068 + endloop + endfacet + facet normal 0.584605 0.0643667 0.808761 + outer loop + vertex 1.66455 1.74555 2.52092 + vertex 1.66738 1.74837 2.51865 + vertex 1.66435 1.75045 2.52068 + endloop + endfacet + facet normal 0.497091 0.0635126 0.865371 + outer loop + vertex 1.66435 1.75045 2.52068 + vertex 1.6612 1.74733 2.52272 + vertex 1.66455 1.74555 2.52092 + endloop + endfacet + facet normal 0.487354 0.0762855 0.869866 + outer loop + vertex 1.66106 1.7522 2.52237 + vertex 1.6612 1.74733 2.52272 + vertex 1.66435 1.75045 2.52068 + endloop + endfacet + facet normal 0.563597 0.0544619 0.824253 + outer loop + vertex 1.66723 1.75333 2.51845 + vertex 1.66696 1.75833 2.51831 + vertex 1.66414 1.75529 2.52043 + endloop + endfacet + facet normal 0.568093 0.0654817 0.820355 + outer loop + vertex 1.66435 1.75045 2.52068 + vertex 1.66723 1.75333 2.51845 + vertex 1.66414 1.75529 2.52043 + endloop + endfacet + facet normal 0.482894 0.064598 0.873293 + outer loop + vertex 1.66414 1.75529 2.52043 + vertex 1.66106 1.7522 2.52237 + vertex 1.66435 1.75045 2.52068 + endloop + endfacet + facet normal 0.465938 0.0860831 0.88062 + outer loop + vertex 1.66078 1.75684 2.52206 + vertex 1.66106 1.7522 2.52237 + vertex 1.66414 1.75529 2.52043 + endloop + endfacet + facet normal 0.540311 0.0637033 0.83905 + outer loop + vertex 1.66696 1.75833 2.51831 + vertex 1.66639 1.76381 2.51826 + vertex 1.66369 1.7601 2.52028 + endloop + endfacet + facet normal 0.545484 0.0783754 0.834449 + outer loop + vertex 1.66414 1.75529 2.52043 + vertex 1.66696 1.75833 2.51831 + vertex 1.66369 1.7601 2.52028 + endloop + endfacet + facet normal 0.461221 0.0719434 0.884364 + outer loop + vertex 1.66369 1.7601 2.52028 + vertex 1.66078 1.75684 2.52206 + vertex 1.66414 1.75529 2.52043 + endloop + endfacet + facet normal 0.428553 0.107989 0.89704 + outer loop + vertex 1.65987 1.76182 2.5219 + vertex 1.66078 1.75684 2.52206 + vertex 1.66369 1.7601 2.52028 + endloop + endfacet + facet normal 0.516678 0.087846 0.851661 + outer loop + vertex 1.66305 1.76414 2.52025 + vertex 1.66369 1.7601 2.52028 + vertex 1.66639 1.76381 2.51826 + endloop + endfacet + facet normal 0.516794 0.0921745 0.851133 + outer loop + vertex 1.66305 1.76414 2.52025 + vertex 1.66639 1.76381 2.51826 + vertex 1.6638 1.76852 2.51932 + endloop + endfacet + facet normal 0.506382 0.0848616 0.858123 + outer loop + vertex 1.6638 1.76852 2.51932 + vertex 1.66639 1.76381 2.51826 + vertex 1.66719 1.76827 2.51735 + endloop + endfacet + facet normal 0.416381 0.0723768 0.906305 + outer loop + vertex 1.66369 1.7601 2.52028 + vertex 1.66305 1.76414 2.52025 + vertex 1.65987 1.76182 2.5219 + endloop + endfacet + facet normal 0.506292 0.0784757 0.858784 + outer loop + vertex 1.66719 1.76827 2.51735 + vertex 1.66635 1.7724 2.51747 + vertex 1.6638 1.76852 2.51932 + endloop + endfacet + facet normal 0.46393 0.115657 0.878289 + outer loop + vertex 1.6638 1.76852 2.51932 + vertex 1.66635 1.7724 2.51747 + vertex 1.66239 1.77432 2.5193 + endloop + endfacet + facet normal 0.450983 0.0786412 0.889061 + outer loop + vertex 1.66635 1.7724 2.51747 + vertex 1.66578 1.77725 2.51733 + vertex 1.66239 1.77432 2.5193 + endloop + endfacet + facet normal 0.446948 0.0843432 0.890575 + outer loop + vertex 1.66239 1.77432 2.5193 + vertex 1.66578 1.77725 2.51733 + vertex 1.66287 1.77887 2.51863 + endloop + endfacet + facet normal 0.444085 0.0775763 0.89262 + outer loop + vertex 1.66578 1.77725 2.51733 + vertex 1.66508 1.78223 2.51724 + vertex 1.66287 1.77887 2.51863 + endloop + endfacet + facet normal 0.402071 0.111908 0.908744 + outer loop + vertex 1.66287 1.77887 2.51863 + vertex 1.66508 1.78223 2.51724 + vertex 1.66159 1.78196 2.51882 + endloop + endfacet + facet normal 0.496062 0.0666637 0.865724 + outer loop + vertex 1.66805 1.78429 2.51544 + vertex 1.66906 1.78855 2.51453 + vertex 1.66605 1.78642 2.51642 + endloop + endfacet + facet normal 0.488973 0.0579008 0.870375 + outer loop + vertex 1.66605 1.78642 2.51642 + vertex 1.66508 1.78223 2.51724 + vertex 1.66805 1.78429 2.51544 + endloop + endfacet + facet normal 0.400354 0.0865462 0.912264 + outer loop + vertex 1.66605 1.78642 2.51642 + vertex 1.66228 1.78654 2.51806 + vertex 1.66508 1.78223 2.51724 + endloop + endfacet + facet normal 0.404401 0.0895658 0.910186 + outer loop + vertex 1.66228 1.78654 2.51806 + vertex 1.66159 1.78196 2.51882 + vertex 1.66508 1.78223 2.51724 + endloop + endfacet + facet normal 0.470879 0.0311846 0.881646 + outer loop + vertex 1.66906 1.78855 2.51453 + vertex 1.66853 1.79387 2.51462 + vertex 1.66548 1.79047 2.51637 + endloop + endfacet + facet normal 0.489441 0.0784633 0.8685 + outer loop + vertex 1.66605 1.78642 2.51642 + vertex 1.66906 1.78855 2.51453 + vertex 1.66548 1.79047 2.51637 + endloop + endfacet + facet normal 0.400429 0.0665291 0.91391 + outer loop + vertex 1.66548 1.79047 2.51637 + vertex 1.66228 1.78654 2.51806 + vertex 1.66605 1.78642 2.51642 + endloop + endfacet + facet normal 0.382187 0.0841262 0.920248 + outer loop + vertex 1.66169 1.79202 2.5178 + vertex 1.66228 1.78654 2.51806 + vertex 1.66548 1.79047 2.51637 + endloop + endfacet + facet normal 0.430027 0.0530988 0.901253 + outer loop + vertex 1.66853 1.79387 2.51462 + vertex 1.66807 1.79892 2.51455 + vertex 1.66496 1.7954 2.51623 + endloop + endfacet + facet normal 0.435777 0.0706578 0.897277 + outer loop + vertex 1.66548 1.79047 2.51637 + vertex 1.66853 1.79387 2.51462 + vertex 1.66496 1.7954 2.51623 + endloop + endfacet + facet normal 0.375948 0.0650724 0.924353 + outer loop + vertex 1.66496 1.7954 2.51623 + vertex 1.66169 1.79202 2.5178 + vertex 1.66548 1.79047 2.51637 + endloop + endfacet + facet normal 0.354779 0.0885472 0.930748 + outer loop + vertex 1.66121 1.79684 2.51753 + vertex 1.66169 1.79202 2.5178 + vertex 1.66496 1.7954 2.51623 + endloop + endfacet + facet normal 0.393633 0.0840226 0.91542 + outer loop + vertex 1.66807 1.79892 2.51455 + vertex 1.66729 1.80432 2.51438 + vertex 1.66431 1.80028 2.51604 + endloop + endfacet + facet normal 0.395264 0.0899208 0.914156 + outer loop + vertex 1.66496 1.7954 2.51623 + vertex 1.66807 1.79892 2.51455 + vertex 1.66431 1.80028 2.51604 + endloop + endfacet + facet normal 0.353695 0.0850823 0.931483 + outer loop + vertex 1.66431 1.80028 2.51604 + vertex 1.66121 1.79684 2.51753 + vertex 1.66496 1.7954 2.51623 + endloop + endfacet + facet normal 0.332884 0.37696 0.864343 + outer loop + vertex 1.66321 2.07847 2.45602 + vertex 1.66534 2.07557 2.45647 + vertex 1.66711 2.0778 2.45481 + endloop + endfacet + facet normal 0.334274 0.451613 0.827228 + outer loop + vertex 1.66321 2.07847 2.45602 + vertex 1.66711 2.0778 2.45481 + vertex 1.66187 2.08219 2.45454 + endloop + endfacet + facet normal 0.33171 0.448717 0.829832 + outer loop + vertex 1.66187 2.08219 2.45454 + vertex 1.66711 2.0778 2.45481 + vertex 1.66644 2.08221 2.4527 + endloop + endfacet + facet normal 0.291155 0.350241 0.890258 + outer loop + vertex 1.66534 2.07557 2.45647 + vertex 1.66321 2.07847 2.45602 + vertex 1.66114 2.07605 2.45765 + endloop + endfacet + facet normal 0.346899 0.635599 0.689692 + outer loop + vertex 1.668 2.08368 2.45114 + vertex 1.66786 2.08568 2.44936 + vertex 1.66549 2.08512 2.45107 + endloop + endfacet + facet normal 0.286998 0.536729 0.793445 + outer loop + vertex 1.66549 2.08512 2.45107 + vertex 1.66644 2.08221 2.4527 + vertex 1.668 2.08368 2.45114 + endloop + endfacet + facet normal 0.310808 0.538663 0.783097 + outer loop + vertex 1.66549 2.08512 2.45107 + vertex 1.66212 2.0857 2.45201 + vertex 1.66644 2.08221 2.4527 + endloop + endfacet + facet normal 0.312045 0.539919 0.781739 + outer loop + vertex 1.66212 2.0857 2.45201 + vertex 1.66187 2.08219 2.45454 + vertex 1.66644 2.08221 2.4527 + endloop + endfacet + facet normal 0.352323 0.785182 0.509272 + outer loop + vertex 1.66268 2.08999 2.44709 + vertex 1.66809 2.08852 2.44562 + vertex 1.66495 2.09121 2.44363 + endloop + endfacet + facet normal 0.341516 0.792772 0.504856 + outer loop + vertex 1.66125 2.09174 2.44532 + vertex 1.66268 2.08999 2.44709 + vertex 1.66495 2.09121 2.44363 + endloop + endfacet + facet normal 0.325761 0.666558 0.670507 + outer loop + vertex 1.66786 2.08568 2.44936 + vertex 1.66405 2.08752 2.44938 + vertex 1.66549 2.08512 2.45107 + endloop + endfacet + facet normal 0.35767 0.733655 0.577774 + outer loop + vertex 1.66786 2.08568 2.44936 + vertex 1.66809 2.08852 2.44562 + vertex 1.66405 2.08752 2.44938 + endloop + endfacet + facet normal 0.357041 0.734348 0.577282 + outer loop + vertex 1.66809 2.08852 2.44562 + vertex 1.66268 2.08999 2.44709 + vertex 1.66405 2.08752 2.44938 + endloop + endfacet + facet normal 0.30459 0.663136 0.683722 + outer loop + vertex 1.66549 2.08512 2.45107 + vertex 1.66405 2.08752 2.44938 + vertex 1.66212 2.0857 2.45201 + endloop + endfacet + facet normal 0.00283648 0.026759 0.999638 + outer loop + vertex 1.67 2.0968 2.44 + vertex 1.665 2.09733 2.44 + vertex 1.66771 2.09343 2.4401 + endloop + endfacet + facet normal 0.363812 0.274687 0.890049 + outer loop + vertex 1.66771 2.09343 2.4401 + vertex 1.665 2.09733 2.44 + vertex 1.66222 2.09341 2.44234 + endloop + endfacet + facet normal 0.35479 0.760239 0.544207 + outer loop + vertex 1.66495 2.09121 2.44363 + vertex 1.66222 2.09341 2.44234 + vertex 1.66125 2.09174 2.44532 + endloop + endfacet + facet normal 0.264738 0.711188 0.65125 + outer loop + vertex 1.66771 2.09343 2.4401 + vertex 1.66222 2.09341 2.44234 + vertex 1.66495 2.09121 2.44363 + endloop + endfacet + facet normal 0.279844 0.896112 0.344485 + outer loop + vertex 1.67133 0.94008 2.44156 + vertex 1.675 0.939534 2.44 + vertex 1.67476 0.939916 2.4392 + endloop + endfacet + facet normal 0.245411 -0.577303 0.778777 + outer loop + vertex 1.67133 0.94008 2.44156 + vertex 1.66729 0.937864 2.44119 + vertex 1.675 0.939534 2.44 + endloop + endfacet + facet normal 0.242671 -0.55027 0.798945 + outer loop + vertex 1.66729 0.937864 2.44119 + vertex 1.67 0.937329 2.44 + vertex 1.675 0.939534 2.44 + endloop + endfacet + facet normal 0.374289 -0.769011 0.518199 + outer loop + vertex 1.67133 0.94008 2.44156 + vertex 1.66728 0.939815 2.44409 + vertex 1.66729 0.937864 2.44119 + endloop + endfacet + facet normal 0.362272 -0.732163 0.576798 + outer loop + vertex 1.67476 0.939916 2.4392 + vertex 1.67495 0.940972 2.44042 + vertex 1.67133 0.94008 2.44156 + endloop + endfacet + facet normal 0.359891 -0.776501 0.517229 + outer loop + vertex 1.66728 0.939815 2.44409 + vertex 1.66932 0.94183 2.4457 + vertex 1.66529 0.941193 2.44755 + endloop + endfacet + facet normal 0.368711 -0.77825 0.50831 + outer loop + vertex 1.67133 0.94008 2.44156 + vertex 1.66932 0.94183 2.4457 + vertex 1.66728 0.939815 2.44409 + endloop + endfacet + facet normal 0.36795 -0.778721 0.508139 + outer loop + vertex 1.67133 0.94008 2.44156 + vertex 1.67383 0.942701 2.44377 + vertex 1.66932 0.94183 2.4457 + endloop + endfacet + facet normal 0.355373 -0.776719 0.520016 + outer loop + vertex 1.67133 0.94008 2.44156 + vertex 1.67495 0.940972 2.44042 + vertex 1.67383 0.942701 2.44377 + endloop + endfacet + facet normal 0.373357 -0.740254 0.559133 + outer loop + vertex 1.66932 0.94183 2.4457 + vertex 1.66769 0.943174 2.44857 + vertex 1.66529 0.941193 2.44755 + endloop + endfacet + facet normal 0.382412 -0.733206 0.56229 + outer loop + vertex 1.67383 0.942701 2.44377 + vertex 1.671 0.944364 2.44786 + vertex 1.66932 0.94183 2.4457 + endloop + endfacet + facet normal 0.383423 -0.733247 0.561548 + outer loop + vertex 1.66769 0.943174 2.44857 + vertex 1.66932 0.94183 2.4457 + vertex 1.671 0.944364 2.44786 + endloop + endfacet + facet normal 0.374643 -0.649428 0.66173 + outer loop + vertex 1.66769 0.943174 2.44857 + vertex 1.671 0.944364 2.44786 + vertex 1.66787 0.945374 2.45063 + endloop + endfacet + facet normal 0.371773 -0.653036 0.659795 + outer loop + vertex 1.66787 0.945374 2.45063 + vertex 1.671 0.944364 2.44786 + vertex 1.67178 0.947313 2.45034 + endloop + endfacet + facet normal 0.331255 -0.5562 0.762176 + outer loop + vertex 1.67178 0.947313 2.45034 + vertex 1.66808 0.949293 2.45339 + vertex 1.66787 0.945374 2.45063 + endloop + endfacet + facet normal 0.324451 -0.564272 0.759163 + outer loop + vertex 1.67342 0.950636 2.45211 + vertex 1.66808 0.949293 2.45339 + vertex 1.67178 0.947313 2.45034 + endloop + endfacet + facet normal 0.355745 -0.451486 0.818294 + outer loop + vertex 1.66845 0.953176 2.45537 + vertex 1.6649 0.951321 2.45589 + vertex 1.66808 0.949293 2.45339 + endloop + endfacet + facet normal 0.342464 -0.452742 0.823251 + outer loop + vertex 1.66845 0.953176 2.45537 + vertex 1.66808 0.949293 2.45339 + vertex 1.67272 0.954409 2.45428 + endloop + endfacet + facet normal 0.311704 -0.42908 0.84778 + outer loop + vertex 1.67272 0.954409 2.45428 + vertex 1.66808 0.949293 2.45339 + vertex 1.67342 0.950636 2.45211 + endloop + endfacet + facet normal 0.320301 -0.36842 0.872739 + outer loop + vertex 1.66845 0.953176 2.45537 + vertex 1.66678 0.954632 2.4566 + vertex 1.6649 0.951321 2.45589 + endloop + endfacet + facet normal 0.283466 -0.249381 0.925989 + outer loop + vertex 1.67301 1.00856 2.47004 + vertex 1.67119 1.0104 2.47109 + vertex 1.66918 1.00737 2.47088 + endloop + endfacet + facet normal 0.283108 -0.249156 0.92616 + outer loop + vertex 1.67119 1.0104 2.47109 + vertex 1.66735 1.00917 2.47193 + vertex 1.66918 1.00737 2.47088 + endloop + endfacet + facet normal 0.282383 -0.246198 0.927171 + outer loop + vertex 1.67119 1.0104 2.47109 + vertex 1.67224 1.01425 2.47179 + vertex 1.66735 1.00917 2.47193 + endloop + endfacet + facet normal 0.432409 -0.106747 0.895337 + outer loop + vertex 1.67243 1.16902 2.50435 + vertex 1.67345 1.17464 2.50453 + vertex 1.66981 1.17133 2.50589 + endloop + endfacet + facet normal 0.42417 -0.117789 0.89789 + outer loop + vertex 1.66893 1.16749 2.5058 + vertex 1.67243 1.16902 2.50435 + vertex 1.66981 1.17133 2.50589 + endloop + endfacet + facet normal 0.338454 -0.0989832 0.935762 + outer loop + vertex 1.66981 1.17133 2.50589 + vertex 1.66617 1.16789 2.50684 + vertex 1.66893 1.16749 2.5058 + endloop + endfacet + facet normal 0.351056 -0.114081 0.929379 + outer loop + vertex 1.66655 1.17249 2.50726 + vertex 1.66617 1.16789 2.50684 + vertex 1.66981 1.17133 2.50589 + endloop + endfacet + facet normal 0.449703 -0.115598 0.885666 + outer loop + vertex 1.67345 1.17464 2.50453 + vertex 1.6739 1.17931 2.5049 + vertex 1.67059 1.17606 2.50616 + endloop + endfacet + facet normal 0.44558 -0.124856 0.886493 + outer loop + vertex 1.66981 1.17133 2.50589 + vertex 1.67345 1.17464 2.50453 + vertex 1.67059 1.17606 2.50616 + endloop + endfacet + facet normal 0.351821 -0.111911 0.929353 + outer loop + vertex 1.67059 1.17606 2.50616 + vertex 1.66655 1.17249 2.50726 + vertex 1.66981 1.17133 2.50589 + endloop + endfacet + facet normal 0.361534 -0.124564 0.924 + outer loop + vertex 1.66755 1.17819 2.50764 + vertex 1.66655 1.17249 2.50726 + vertex 1.67059 1.17606 2.50616 + endloop + endfacet + facet normal 0.467197 -0.138216 0.873283 + outer loop + vertex 1.6739 1.17931 2.5049 + vertex 1.67148 1.17995 2.5063 + vertex 1.67059 1.17606 2.50616 + endloop + endfacet + facet normal 0.366351 -0.117058 0.923084 + outer loop + vertex 1.67148 1.17995 2.5063 + vertex 1.66755 1.17819 2.50764 + vertex 1.67059 1.17606 2.50616 + endloop + endfacet + facet normal 0.366338 -0.117023 0.923094 + outer loop + vertex 1.67148 1.17995 2.5063 + vertex 1.67101 1.1832 2.5069 + vertex 1.66755 1.17819 2.50764 + endloop + endfacet + facet normal 0.375533 -0.124041 0.918471 + outer loop + vertex 1.67101 1.1832 2.5069 + vertex 1.66722 1.18348 2.50849 + vertex 1.66755 1.17819 2.50764 + endloop + endfacet + facet normal 0.377155 -0.109294 0.919679 + outer loop + vertex 1.67101 1.1832 2.5069 + vertex 1.67111 1.18791 2.50742 + vertex 1.66722 1.18348 2.50849 + endloop + endfacet + facet normal 0.407496 -0.140118 0.902394 + outer loop + vertex 1.66722 1.18348 2.50849 + vertex 1.67111 1.18791 2.50742 + vertex 1.66725 1.18894 2.50932 + endloop + endfacet + facet normal 0.412421 -0.122196 0.902761 + outer loop + vertex 1.67111 1.18791 2.50742 + vertex 1.67153 1.19317 2.50794 + vertex 1.66725 1.18894 2.50932 + endloop + endfacet + facet normal 0.451133 -0.170072 0.876102 + outer loop + vertex 1.66725 1.18894 2.50932 + vertex 1.67153 1.19317 2.50794 + vertex 1.66854 1.19439 2.50972 + endloop + endfacet + facet normal 0.397608 -0.155212 0.904332 + outer loop + vertex 1.66854 1.19781 2.5103 + vertex 1.66622 1.19525 2.51088 + vertex 1.66854 1.19439 2.50972 + endloop + endfacet + facet normal 0.487229 -0.147843 0.860669 + outer loop + vertex 1.66854 1.19781 2.5103 + vertex 1.66854 1.19439 2.50972 + vertex 1.67174 1.19869 2.50865 + endloop + endfacet + facet normal 0.466968 -0.129262 0.874776 + outer loop + vertex 1.67174 1.19869 2.50865 + vertex 1.66854 1.19439 2.50972 + vertex 1.67153 1.19317 2.50794 + endloop + endfacet + facet normal 0.368095 -0.124599 0.921402 + outer loop + vertex 1.66854 1.19781 2.5103 + vertex 1.66592 1.19831 2.51142 + vertex 1.66622 1.19525 2.51088 + endloop + endfacet + facet normal 0.497028 -0.102425 0.861668 + outer loop + vertex 1.67174 1.19869 2.50865 + vertex 1.67264 1.2042 2.50878 + vertex 1.66931 1.20147 2.51037 + endloop + endfacet + facet normal 0.482791 -0.118547 0.867675 + outer loop + vertex 1.66854 1.19781 2.5103 + vertex 1.67174 1.19869 2.50865 + vertex 1.66931 1.20147 2.51037 + endloop + endfacet + facet normal 0.373883 -0.0968249 0.922408 + outer loop + vertex 1.66931 1.20147 2.51037 + vertex 1.66592 1.19831 2.51142 + vertex 1.66854 1.19781 2.5103 + endloop + endfacet + facet normal 0.391785 -0.119381 0.912279 + outer loop + vertex 1.66613 1.2027 2.5119 + vertex 1.66592 1.19831 2.51142 + vertex 1.66931 1.20147 2.51037 + endloop + endfacet + facet normal 0.507694 -0.0872892 0.857104 + outer loop + vertex 1.67264 1.2042 2.50878 + vertex 1.67304 1.20923 2.50906 + vertex 1.66979 1.2062 2.51067 + endloop + endfacet + facet normal 0.498177 -0.104353 0.860773 + outer loop + vertex 1.66931 1.20147 2.51037 + vertex 1.67264 1.2042 2.50878 + vertex 1.66979 1.2062 2.51067 + endloop + endfacet + facet normal 0.399724 -0.0977145 0.911413 + outer loop + vertex 1.66979 1.2062 2.51067 + vertex 1.66613 1.2027 2.5119 + vertex 1.66931 1.20147 2.51037 + endloop + endfacet + facet normal 0.414201 -0.1159 0.902776 + outer loop + vertex 1.66644 1.20763 2.51239 + vertex 1.66613 1.2027 2.5119 + vertex 1.66979 1.2062 2.51067 + endloop + endfacet + facet normal 0.525091 -0.076069 0.847639 + outer loop + vertex 1.67304 1.20923 2.50906 + vertex 1.67323 1.2142 2.50939 + vertex 1.67013 1.21116 2.51103 + endloop + endfacet + facet normal 0.51429 -0.0970235 0.852111 + outer loop + vertex 1.66979 1.2062 2.51067 + vertex 1.67304 1.20923 2.50906 + vertex 1.67013 1.21116 2.51103 + endloop + endfacet + facet normal 0.422716 -0.0942447 0.901348 + outer loop + vertex 1.67013 1.21116 2.51103 + vertex 1.66644 1.20763 2.51239 + vertex 1.66979 1.2062 2.51067 + endloop + endfacet + facet normal 0.438039 -0.113956 0.891704 + outer loop + vertex 1.66688 1.21284 2.51284 + vertex 1.66644 1.20763 2.51239 + vertex 1.67013 1.21116 2.51103 + endloop + endfacet + facet normal 0.547749 -0.0813366 0.83268 + outer loop + vertex 1.67323 1.2142 2.50939 + vertex 1.67305 1.21806 2.50988 + vertex 1.67053 1.21596 2.51133 + endloop + endfacet + facet normal 0.539847 -0.0972818 0.836123 + outer loop + vertex 1.67013 1.21116 2.51103 + vertex 1.67323 1.2142 2.50939 + vertex 1.67053 1.21596 2.51133 + endloop + endfacet + facet normal 0.447625 -0.0928872 0.889384 + outer loop + vertex 1.67053 1.21596 2.51133 + vertex 1.66688 1.21284 2.51284 + vertex 1.67013 1.21116 2.51103 + endloop + endfacet + facet normal 0.460922 -0.112863 0.880235 + outer loop + vertex 1.66784 1.21868 2.51309 + vertex 1.66688 1.21284 2.51284 + vertex 1.67053 1.21596 2.51133 + endloop + endfacet + facet normal 0.554771 -0.0938833 0.826689 + outer loop + vertex 1.67305 1.21806 2.50988 + vertex 1.67132 1.21974 2.51123 + vertex 1.67053 1.21596 2.51133 + endloop + endfacet + facet normal 0.488165 -0.0787622 0.86919 + outer loop + vertex 1.67132 1.21974 2.51123 + vertex 1.66784 1.21868 2.51309 + vertex 1.67053 1.21596 2.51133 + endloop + endfacet + facet normal 0.488696 -0.0814771 0.868641 + outer loop + vertex 1.67132 1.21974 2.51123 + vertex 1.67097 1.22333 2.51177 + vertex 1.66784 1.21868 2.51309 + endloop + endfacet + facet normal 0.513454 -0.10285 0.851931 + outer loop + vertex 1.67097 1.22333 2.51177 + vertex 1.66735 1.22423 2.51405 + vertex 1.66784 1.21868 2.51309 + endloop + endfacet + facet normal 0.517554 -0.0849558 0.851423 + outer loop + vertex 1.67097 1.22333 2.51177 + vertex 1.67108 1.22823 2.51219 + vertex 1.66735 1.22423 2.51405 + endloop + endfacet + facet normal 0.538775 -0.112369 0.834922 + outer loop + vertex 1.66735 1.22423 2.51405 + vertex 1.67108 1.22823 2.51219 + vertex 1.66817 1.22982 2.51428 + endloop + endfacet + facet normal 0.550384 -0.0853745 0.830535 + outer loop + vertex 1.67108 1.22823 2.51219 + vertex 1.67139 1.23327 2.5125 + vertex 1.66817 1.22982 2.51428 + endloop + endfacet + facet normal 0.559799 -0.0981072 0.8228 + outer loop + vertex 1.66817 1.22982 2.51428 + vertex 1.67139 1.23327 2.5125 + vertex 1.6686 1.23473 2.51457 + endloop + endfacet + facet normal 0.567957 -0.0776707 0.819385 + outer loop + vertex 1.67139 1.23327 2.5125 + vertex 1.67155 1.23821 2.51285 + vertex 1.6686 1.23473 2.51457 + endloop + endfacet + facet normal 0.57611 -0.0879141 0.812631 + outer loop + vertex 1.6686 1.23473 2.51457 + vertex 1.67155 1.23821 2.51285 + vertex 1.66882 1.23922 2.5149 + endloop + endfacet + facet normal 0.499301 -0.084088 0.862338 + outer loop + vertex 1.66845 1.24249 2.51544 + vertex 1.66645 1.23988 2.51633 + vertex 1.66882 1.23922 2.5149 + endloop + endfacet + facet normal 0.577323 -0.0672027 0.813745 + outer loop + vertex 1.66845 1.24249 2.51544 + vertex 1.66882 1.23922 2.5149 + vertex 1.67134 1.24344 2.51346 + endloop + endfacet + facet normal 0.581149 -0.0705212 0.810736 + outer loop + vertex 1.67134 1.24344 2.51346 + vertex 1.66882 1.23922 2.5149 + vertex 1.67155 1.23821 2.51285 + endloop + endfacet + facet normal 0.477427 -0.0626156 0.876438 + outer loop + vertex 1.66845 1.24249 2.51544 + vertex 1.66595 1.24314 2.51684 + vertex 1.66645 1.23988 2.51633 + endloop + endfacet + facet normal 0.577224 -0.0632281 0.814134 + outer loop + vertex 1.67134 1.24344 2.51346 + vertex 1.67203 1.24904 2.51341 + vertex 1.66899 1.24633 2.51535 + endloop + endfacet + facet normal 0.57671 -0.0638548 0.814449 + outer loop + vertex 1.66845 1.24249 2.51544 + vertex 1.67134 1.24344 2.51346 + vertex 1.66899 1.24633 2.51535 + endloop + endfacet + facet normal 0.4805 -0.0489885 0.875625 + outer loop + vertex 1.66899 1.24633 2.51535 + vertex 1.66595 1.24314 2.51684 + vertex 1.66845 1.24249 2.51544 + endloop + endfacet + facet normal 0.500448 -0.074039 0.862595 + outer loop + vertex 1.66602 1.24785 2.51721 + vertex 1.66595 1.24314 2.51684 + vertex 1.66899 1.24633 2.51535 + endloop + endfacet + facet normal 0.581366 -0.0674176 0.810844 + outer loop + vertex 1.67203 1.24904 2.51341 + vertex 1.67241 1.25417 2.51356 + vertex 1.66936 1.25128 2.5155 + endloop + endfacet + facet normal 0.580498 -0.0689114 0.811341 + outer loop + vertex 1.66899 1.24633 2.51535 + vertex 1.67203 1.24904 2.51341 + vertex 1.66936 1.25128 2.5155 + endloop + endfacet + facet normal 0.504347 -0.0645808 0.861083 + outer loop + vertex 1.66936 1.25128 2.5155 + vertex 1.66602 1.24785 2.51721 + vertex 1.66899 1.24633 2.51535 + endloop + endfacet + facet normal 0.521334 -0.0872127 0.848885 + outer loop + vertex 1.66637 1.25306 2.51753 + vertex 1.66602 1.24785 2.51721 + vertex 1.66936 1.25128 2.5155 + endloop + endfacet + facet normal 0.592819 -0.0592169 0.803156 + outer loop + vertex 1.67241 1.25417 2.51356 + vertex 1.67265 1.25918 2.51375 + vertex 1.66967 1.25639 2.51574 + endloop + endfacet + facet normal 0.584984 -0.073327 0.807723 + outer loop + vertex 1.66936 1.25128 2.5155 + vertex 1.67241 1.25417 2.51356 + vertex 1.66967 1.25639 2.51574 + endloop + endfacet + facet normal 0.528496 -0.0717496 0.845898 + outer loop + vertex 1.66967 1.25639 2.51574 + vertex 1.66637 1.25306 2.51753 + vertex 1.66936 1.25128 2.5155 + endloop + endfacet + facet normal 0.540087 -0.0880047 0.836995 + outer loop + vertex 1.6667 1.25827 2.51786 + vertex 1.66637 1.25306 2.51753 + vertex 1.66967 1.25639 2.51574 + endloop + endfacet + facet normal 0.605846 -0.0451474 0.7943 + outer loop + vertex 1.67265 1.25918 2.51375 + vertex 1.67282 1.26416 2.51391 + vertex 1.66984 1.26153 2.51603 + endloop + endfacet + facet normal 0.595521 -0.0637814 0.800804 + outer loop + vertex 1.66967 1.25639 2.51574 + vertex 1.67265 1.25918 2.51375 + vertex 1.66984 1.26153 2.51603 + endloop + endfacet + facet normal 0.551484 -0.0640452 0.831723 + outer loop + vertex 1.66984 1.26153 2.51603 + vertex 1.6667 1.25827 2.51786 + vertex 1.66967 1.25639 2.51574 + endloop + endfacet + facet normal 0.556582 -0.0711852 0.827738 + outer loop + vertex 1.66653 1.26363 2.51844 + vertex 1.6667 1.25827 2.51786 + vertex 1.66984 1.26153 2.51603 + endloop + endfacet + facet normal 0.618894 -0.0257276 0.785053 + outer loop + vertex 1.67282 1.26416 2.51391 + vertex 1.67295 1.26914 2.51397 + vertex 1.67001 1.2667 2.5162 + endloop + endfacet + facet normal 0.606758 -0.0468153 0.793507 + outer loop + vertex 1.66984 1.26153 2.51603 + vertex 1.67282 1.26416 2.51391 + vertex 1.67001 1.2667 2.5162 + endloop + endfacet + facet normal 0.567961 -0.0464607 0.821743 + outer loop + vertex 1.67001 1.2667 2.5162 + vertex 1.66653 1.26363 2.51844 + vertex 1.66984 1.26153 2.51603 + endloop + endfacet + facet normal 0.572421 -0.0541271 0.818172 + outer loop + vertex 1.66716 1.26919 2.51836 + vertex 1.66653 1.26363 2.51844 + vertex 1.67001 1.2667 2.5162 + endloop + endfacet + facet normal 0.636687 -0.0150072 0.770976 + outer loop + vertex 1.67295 1.26914 2.51397 + vertex 1.67302 1.27412 2.51401 + vertex 1.67023 1.27181 2.51627 + endloop + endfacet + facet normal 0.624063 -0.0360919 0.78054 + outer loop + vertex 1.67001 1.2667 2.5162 + vertex 1.67295 1.26914 2.51397 + vertex 1.67023 1.27181 2.51627 + endloop + endfacet + facet normal 0.583932 -0.0348244 0.811055 + outer loop + vertex 1.67023 1.27181 2.51627 + vertex 1.66716 1.26919 2.51836 + vertex 1.67001 1.2667 2.5162 + endloop + endfacet + facet normal 0.590881 -0.0474856 0.80536 + outer loop + vertex 1.66742 1.27429 2.51847 + vertex 1.66716 1.26919 2.51836 + vertex 1.67023 1.27181 2.51627 + endloop + endfacet + facet normal 0.656675 -0.0154063 0.754016 + outer loop + vertex 1.67302 1.27412 2.51401 + vertex 1.673 1.27914 2.51413 + vertex 1.67034 1.27683 2.5164 + endloop + endfacet + facet normal 0.645751 -0.0339966 0.762791 + outer loop + vertex 1.67023 1.27181 2.51627 + vertex 1.67302 1.27412 2.51401 + vertex 1.67034 1.27683 2.5164 + endloop + endfacet + facet normal 0.598784 -0.0339147 0.800192 + outer loop + vertex 1.67034 1.27683 2.5164 + vertex 1.66742 1.27429 2.51847 + vertex 1.67023 1.27181 2.51627 + endloop + endfacet + facet normal 0.608424 -0.0517313 0.791924 + outer loop + vertex 1.66759 1.27929 2.51867 + vertex 1.66742 1.27429 2.51847 + vertex 1.67034 1.27683 2.5164 + endloop + endfacet + facet normal 0.677592 -0.0225387 0.735093 + outer loop + vertex 1.673 1.27914 2.51413 + vertex 1.67291 1.28409 2.51436 + vertex 1.67041 1.28178 2.51659 + endloop + endfacet + facet normal 0.668105 -0.0392998 0.743029 + outer loop + vertex 1.67034 1.27683 2.5164 + vertex 1.673 1.27914 2.51413 + vertex 1.67041 1.28178 2.51659 + endloop + endfacet + facet normal 0.615049 -0.0402389 0.787461 + outer loop + vertex 1.67041 1.28178 2.51659 + vertex 1.66759 1.27929 2.51867 + vertex 1.67034 1.27683 2.5164 + endloop + endfacet + facet normal 0.623133 -0.0555866 0.780138 + outer loop + vertex 1.66781 1.2843 2.51885 + vertex 1.66759 1.27929 2.51867 + vertex 1.67041 1.28178 2.51659 + endloop + endfacet + facet normal 0.696005 -0.0270706 0.717526 + outer loop + vertex 1.67291 1.28409 2.51436 + vertex 1.67267 1.28809 2.51474 + vertex 1.67058 1.28646 2.51671 + endloop + endfacet + facet normal 0.687438 -0.0428681 0.724976 + outer loop + vertex 1.67041 1.28178 2.51659 + vertex 1.67291 1.28409 2.51436 + vertex 1.67058 1.28646 2.51671 + endloop + endfacet + facet normal 0.631288 -0.0420707 0.774407 + outer loop + vertex 1.67058 1.28646 2.51671 + vertex 1.66781 1.2843 2.51885 + vertex 1.67041 1.28178 2.51659 + endloop + endfacet + facet normal 0.635207 -0.0508106 0.770669 + outer loop + vertex 1.6684 1.28977 2.51873 + vertex 1.66781 1.2843 2.51885 + vertex 1.67058 1.28646 2.51671 + endloop + endfacet + facet normal 0.699188 -0.0353425 0.714064 + outer loop + vertex 1.67267 1.28809 2.51474 + vertex 1.6712 1.29015 2.51629 + vertex 1.67058 1.28646 2.51671 + endloop + endfacet + facet normal 0.658495 -0.024221 0.752195 + outer loop + vertex 1.6712 1.29015 2.51629 + vertex 1.6684 1.28977 2.51873 + vertex 1.67058 1.28646 2.51671 + endloop + endfacet + facet normal 0.658212 -0.0196936 0.752575 + outer loop + vertex 1.6712 1.29015 2.51629 + vertex 1.67085 1.29389 2.51669 + vertex 1.6684 1.28977 2.51873 + endloop + endfacet + facet normal 0.67633 -0.0388617 0.735573 + outer loop + vertex 1.67085 1.29389 2.51669 + vertex 1.66812 1.29509 2.51927 + vertex 1.6684 1.28977 2.51873 + endloop + endfacet + facet normal 0.679997 -0.0245293 0.732805 + outer loop + vertex 1.67085 1.29389 2.51669 + vertex 1.67071 1.29866 2.51698 + vertex 1.66812 1.29509 2.51927 + endloop + endfacet + facet normal 0.691925 -0.0408688 0.720812 + outer loop + vertex 1.66812 1.29509 2.51927 + vertex 1.67071 1.29866 2.51698 + vertex 1.66816 1.30002 2.5195 + endloop + endfacet + facet normal 0.697661 -0.0214654 0.716107 + outer loop + vertex 1.67071 1.29866 2.51698 + vertex 1.67074 1.30351 2.51709 + vertex 1.66816 1.30002 2.5195 + endloop + endfacet + facet normal 0.706804 -0.0348133 0.706552 + outer loop + vertex 1.66816 1.30002 2.5195 + vertex 1.67074 1.30351 2.51709 + vertex 1.66829 1.30493 2.51961 + endloop + endfacet + facet normal 0.712145 -0.0172534 0.701821 + outer loop + vertex 1.67074 1.30351 2.51709 + vertex 1.67082 1.30842 2.51713 + vertex 1.66829 1.30493 2.51961 + endloop + endfacet + facet normal 0.718795 -0.0271563 0.694692 + outer loop + vertex 1.66829 1.30493 2.51961 + vertex 1.67082 1.30842 2.51713 + vertex 1.6684 1.30984 2.5197 + endloop + endfacet + facet normal 0.723146 -0.012417 0.690583 + outer loop + vertex 1.67082 1.30842 2.51713 + vertex 1.67087 1.31333 2.51717 + vertex 1.6684 1.30984 2.5197 + endloop + endfacet + facet normal 0.732046 -0.0258365 0.680765 + outer loop + vertex 1.6684 1.30984 2.5197 + vertex 1.67087 1.31333 2.51717 + vertex 1.66849 1.31465 2.51978 + endloop + endfacet + facet normal 0.733363 -0.0210066 0.679513 + outer loop + vertex 1.67087 1.31333 2.51717 + vertex 1.67087 1.31822 2.51732 + vertex 1.66849 1.31465 2.51978 + endloop + endfacet + facet normal 0.746761 -0.0407228 0.663845 + outer loop + vertex 1.66849 1.31465 2.51978 + vertex 1.67087 1.31822 2.51732 + vertex 1.66856 1.31908 2.51997 + endloop + endfacet + facet normal 0.687299 -0.0727258 0.722724 + outer loop + vertex 1.66824 1.32236 2.52061 + vertex 1.66668 1.31998 2.52185 + vertex 1.66856 1.31908 2.51997 + endloop + endfacet + facet normal 0.751533 -0.0539776 0.657483 + outer loop + vertex 1.66824 1.32236 2.52061 + vertex 1.66856 1.31908 2.51997 + vertex 1.67068 1.32344 2.51791 + endloop + endfacet + facet normal 0.745429 -0.0475078 0.66489 + outer loop + vertex 1.67068 1.32344 2.51791 + vertex 1.66856 1.31908 2.51997 + vertex 1.67087 1.31822 2.51732 + endloop + endfacet + facet normal 0.685815 -0.0709236 0.724312 + outer loop + vertex 1.66824 1.32236 2.52061 + vertex 1.6663 1.3233 2.52254 + vertex 1.66668 1.31998 2.52185 + endloop + endfacet + facet normal 0.768525 -0.0571294 0.637264 + outer loop + vertex 1.67068 1.32344 2.51791 + vertex 1.67126 1.32916 2.51771 + vertex 1.66872 1.3263 2.52053 + endloop + endfacet + facet normal 0.755115 -0.0787564 0.650844 + outer loop + vertex 1.66824 1.32236 2.52061 + vertex 1.67068 1.32344 2.51791 + vertex 1.66872 1.3263 2.52053 + endloop + endfacet + facet normal 0.686346 -0.0691452 0.723981 + outer loop + vertex 1.66872 1.3263 2.52053 + vertex 1.6663 1.3233 2.52254 + vertex 1.66824 1.32236 2.52061 + endloop + endfacet + facet normal 0.696741 -0.0854094 0.71222 + outer loop + vertex 1.6661 1.32821 2.52332 + vertex 1.6663 1.3233 2.52254 + vertex 1.66872 1.3263 2.52053 + endloop + endfacet + facet normal 0.796341 -0.0466512 0.603046 + outer loop + vertex 1.67126 1.32916 2.51771 + vertex 1.67149 1.33437 2.51782 + vertex 1.66912 1.3314 2.52072 + endloop + endfacet + facet normal 0.780138 -0.0846554 0.619853 + outer loop + vertex 1.66872 1.3263 2.52053 + vertex 1.67126 1.32916 2.51771 + vertex 1.66912 1.3314 2.52072 + endloop + endfacet + facet normal 0.698342 -0.0815811 0.7111 + outer loop + vertex 1.66912 1.3314 2.52072 + vertex 1.6661 1.32821 2.52332 + vertex 1.66872 1.3263 2.52053 + endloop + endfacet + facet normal 0.703199 -0.0910302 0.705142 + outer loop + vertex 1.66678 1.3338 2.52336 + vertex 1.6661 1.32821 2.52332 + vertex 1.66912 1.3314 2.52072 + endloop + endfacet + facet normal 0.821728 -0.0329705 0.568926 + outer loop + vertex 1.67149 1.33437 2.51782 + vertex 1.67155 1.33941 2.51803 + vertex 1.66944 1.33657 2.52091 + endloop + endfacet + facet normal 0.806899 -0.0714183 0.586356 + outer loop + vertex 1.66912 1.3314 2.52072 + vertex 1.67149 1.33437 2.51782 + vertex 1.66944 1.33657 2.52091 + endloop + endfacet + facet normal 0.714765 -0.0695799 0.695895 + outer loop + vertex 1.66944 1.33657 2.52091 + vertex 1.66678 1.3338 2.52336 + vertex 1.66912 1.3314 2.52072 + endloop + endfacet + facet normal 0.709589 -0.0590424 0.702138 + outer loop + vertex 1.66705 1.33894 2.52352 + vertex 1.66678 1.3338 2.52336 + vertex 1.66944 1.33657 2.52091 + endloop + endfacet + facet normal 0.831123 -0.0202563 0.55572 + outer loop + vertex 1.67155 1.33941 2.51803 + vertex 1.67156 1.34441 2.51819 + vertex 1.66958 1.34158 2.52106 + endloop + endfacet + facet normal 0.824308 -0.0390706 0.564792 + outer loop + vertex 1.66944 1.33657 2.52091 + vertex 1.67155 1.33941 2.51803 + vertex 1.66958 1.34158 2.52106 + endloop + endfacet + facet normal 0.71916 -0.040101 0.693686 + outer loop + vertex 1.66958 1.34158 2.52106 + vertex 1.66705 1.33894 2.52352 + vertex 1.66944 1.33657 2.52091 + endloop + endfacet + facet normal 0.710927 -0.023691 0.702867 + outer loop + vertex 1.66713 1.34396 2.52361 + vertex 1.66705 1.33894 2.52352 + vertex 1.66958 1.34158 2.52106 + endloop + endfacet + facet normal 0.826361 -0.00609158 0.563107 + outer loop + vertex 1.67156 1.34441 2.51819 + vertex 1.67161 1.34945 2.51818 + vertex 1.66961 1.34656 2.52107 + endloop + endfacet + facet normal 0.825697 -0.00796763 0.564058 + outer loop + vertex 1.66958 1.34158 2.52106 + vertex 1.67156 1.34441 2.51819 + vertex 1.66961 1.34656 2.52107 + endloop + endfacet + facet normal 0.718687 -0.00751292 0.695293 + outer loop + vertex 1.66961 1.34656 2.52107 + vertex 1.66713 1.34396 2.52361 + vertex 1.66958 1.34158 2.52106 + endloop + endfacet + facet normal 0.716646 -0.00347707 0.697429 + outer loop + vertex 1.66714 1.34895 2.52362 + vertex 1.66713 1.34396 2.52361 + vertex 1.66961 1.34656 2.52107 + endloop + endfacet + facet normal 0.821545 0.00696287 0.570102 + outer loop + vertex 1.67161 1.34945 2.51818 + vertex 1.67164 1.35448 2.51806 + vertex 1.66964 1.35153 2.52099 + endloop + endfacet + facet normal 0.821009 0.00539803 0.57089 + outer loop + vertex 1.66961 1.34656 2.52107 + vertex 1.67161 1.34945 2.51818 + vertex 1.66964 1.35153 2.52099 + endloop + endfacet + facet normal 0.721915 0.00783184 0.691938 + outer loop + vertex 1.66964 1.35153 2.52099 + vertex 1.66714 1.34895 2.52362 + vertex 1.66961 1.34656 2.52107 + endloop + endfacet + facet normal 0.730897 -0.0105246 0.682407 + outer loop + vertex 1.66721 1.35396 2.52363 + vertex 1.66714 1.34895 2.52362 + vertex 1.66964 1.35153 2.52099 + endloop + endfacet + facet normal 0.830153 0.0116483 0.557415 + outer loop + vertex 1.67164 1.35448 2.51806 + vertex 1.6716 1.35952 2.51802 + vertex 1.66966 1.35651 2.52097 + endloop + endfacet + facet normal 0.82578 -0.00200004 0.563988 + outer loop + vertex 1.66964 1.35153 2.52099 + vertex 1.67164 1.35448 2.51806 + vertex 1.66966 1.35651 2.52097 + endloop + endfacet + facet normal 0.735291 -0.0010495 0.67775 + outer loop + vertex 1.66966 1.35651 2.52097 + vertex 1.66721 1.35396 2.52363 + vertex 1.66964 1.35153 2.52099 + endloop + endfacet + facet normal 0.750868 -0.0350861 0.65952 + outer loop + vertex 1.66732 1.35896 2.52376 + vertex 1.66721 1.35396 2.52363 + vertex 1.66966 1.35651 2.52097 + endloop + endfacet + facet normal 0.848543 0.00801672 0.529065 + outer loop + vertex 1.6716 1.35952 2.51802 + vertex 1.67152 1.36461 2.51807 + vertex 1.66964 1.36157 2.52113 + endloop + endfacet + facet normal 0.842 -0.0137926 0.539301 + outer loop + vertex 1.66966 1.35651 2.52097 + vertex 1.6716 1.35952 2.51802 + vertex 1.66964 1.36157 2.52113 + endloop + endfacet + facet normal 0.75885 -0.0177372 0.651024 + outer loop + vertex 1.66964 1.36157 2.52113 + vertex 1.66732 1.35896 2.52376 + vertex 1.66966 1.35651 2.52097 + endloop + endfacet + facet normal 0.773956 -0.0511564 0.63117 + outer loop + vertex 1.6674 1.3638 2.52406 + vertex 1.66732 1.35896 2.52376 + vertex 1.66964 1.36157 2.52113 + endloop + endfacet + facet normal 0.865357 0.011566 0.501022 + outer loop + vertex 1.67152 1.36461 2.51807 + vertex 1.67156 1.36961 2.51789 + vertex 1.66951 1.36712 2.52149 + endloop + endfacet + facet normal 0.857594 -0.0125783 0.514174 + outer loop + vertex 1.66964 1.36157 2.52113 + vertex 1.67152 1.36461 2.51807 + vertex 1.66951 1.36712 2.52149 + endloop + endfacet + facet normal 0.786183 -0.021064 0.617634 + outer loop + vertex 1.66951 1.36712 2.52149 + vertex 1.6674 1.3638 2.52406 + vertex 1.66964 1.36157 2.52113 + endloop + endfacet + facet normal 0.80123 -0.0468767 0.596518 + outer loop + vertex 1.6673 1.36772 2.52451 + vertex 1.6674 1.3638 2.52406 + vertex 1.66951 1.36712 2.52149 + endloop + endfacet + facet normal 0.889419 0.0206164 0.456627 + outer loop + vertex 1.67156 1.36961 2.51789 + vertex 1.67164 1.37428 2.51753 + vertex 1.67029 1.37177 2.52027 + endloop + endfacet + facet normal 0.874376 -0.0193704 0.484863 + outer loop + vertex 1.66951 1.36712 2.52149 + vertex 1.67156 1.36961 2.51789 + vertex 1.67029 1.37177 2.52027 + endloop + endfacet + facet normal 0.750042 0.0196602 0.661098 + outer loop + vertex 1.6673 1.36772 2.52451 + vertex 1.66812 1.37199 2.52345 + vertex 1.66594 1.36978 2.52598 + endloop + endfacet + facet normal 0.805798 -0.00809908 0.592135 + outer loop + vertex 1.6673 1.36772 2.52451 + vertex 1.66951 1.36712 2.52149 + vertex 1.66812 1.37199 2.52345 + endloop + endfacet + facet normal 0.826273 0.00937627 0.563191 + outer loop + vertex 1.66951 1.36712 2.52149 + vertex 1.67029 1.37177 2.52027 + vertex 1.66812 1.37199 2.52345 + endloop + endfacet + facet normal 0.750997 0.0175428 0.660073 + outer loop + vertex 1.66812 1.37199 2.52345 + vertex 1.6656 1.37366 2.52627 + vertex 1.66594 1.36978 2.52598 + endloop + endfacet + facet normal 0.885984 0.0407953 0.461918 + outer loop + vertex 1.67164 1.37428 2.51753 + vertex 1.67172 1.37806 2.51704 + vertex 1.67014 1.37666 2.52019 + endloop + endfacet + facet normal 0.883856 0.0343471 0.466497 + outer loop + vertex 1.67029 1.37177 2.52027 + vertex 1.67164 1.37428 2.51753 + vertex 1.67014 1.37666 2.52019 + endloop + endfacet + facet normal 0.826634 0.0342447 0.561697 + outer loop + vertex 1.67029 1.37177 2.52027 + vertex 1.67014 1.37666 2.52019 + vertex 1.66812 1.37199 2.52345 + endloop + endfacet + facet normal 0.836189 0.0205662 0.548055 + outer loop + vertex 1.67014 1.37666 2.52019 + vertex 1.6678 1.37759 2.52373 + vertex 1.66812 1.37199 2.52345 + endloop + endfacet + facet normal 0.748834 0.00989368 0.662684 + outer loop + vertex 1.6678 1.37759 2.52373 + vertex 1.6656 1.37366 2.52627 + vertex 1.66812 1.37199 2.52345 + endloop + endfacet + facet normal 0.756206 0.000366582 0.654333 + outer loop + vertex 1.66543 1.37861 2.52646 + vertex 1.6656 1.37366 2.52627 + vertex 1.6678 1.37759 2.52373 + endloop + endfacet + facet normal 0.925569 0.0450513 0.375889 + outer loop + vertex 1.67228 1.3809 2.51525 + vertex 1.67225 1.38493 2.51483 + vertex 1.67131 1.38138 2.51758 + endloop + endfacet + facet normal 0.925797 0.0537453 0.374181 + outer loop + vertex 1.67172 1.37806 2.51704 + vertex 1.67228 1.3809 2.51525 + vertex 1.67131 1.38138 2.51758 + endloop + endfacet + facet normal 0.887202 0.0352049 0.460035 + outer loop + vertex 1.67172 1.37806 2.51704 + vertex 1.67131 1.38138 2.51758 + vertex 1.67014 1.37666 2.52019 + endloop + endfacet + facet normal 0.8896 0.032167 0.455606 + outer loop + vertex 1.67014 1.37666 2.52019 + vertex 1.67131 1.38138 2.51758 + vertex 1.66966 1.38191 2.52076 + endloop + endfacet + facet normal 0.835826 0.0171126 0.548728 + outer loop + vertex 1.67014 1.37666 2.52019 + vertex 1.66966 1.38191 2.52076 + vertex 1.6678 1.37759 2.52373 + endloop + endfacet + facet normal 0.843181 0.00629 0.537594 + outer loop + vertex 1.66966 1.38191 2.52076 + vertex 1.66766 1.38271 2.52389 + vertex 1.6678 1.37759 2.52373 + endloop + endfacet + facet normal 0.756184 0.000246331 0.654359 + outer loop + vertex 1.66766 1.38271 2.52389 + vertex 1.66543 1.37861 2.52646 + vertex 1.6678 1.37759 2.52373 + endloop + endfacet + facet normal 0.76076 -0.0055948 0.649009 + outer loop + vertex 1.66542 1.38354 2.52651 + vertex 1.66543 1.37861 2.52646 + vertex 1.66766 1.38271 2.52389 + endloop + endfacet + facet normal 0.933263 0.00940415 0.359071 + outer loop + vertex 1.67225 1.38493 2.51483 + vertex 1.67227 1.3898 2.51465 + vertex 1.67116 1.38598 2.51764 + endloop + endfacet + facet normal 0.934983 0.0254119 0.353782 + outer loop + vertex 1.67131 1.38138 2.51758 + vertex 1.67225 1.38493 2.51483 + vertex 1.67116 1.38598 2.51764 + endloop + endfacet + facet normal 0.889179 0.0224163 0.457011 + outer loop + vertex 1.67131 1.38138 2.51758 + vertex 1.67116 1.38598 2.51764 + vertex 1.66966 1.38191 2.52076 + endloop + endfacet + facet normal 0.899314 0.00357227 0.437289 + outer loop + vertex 1.67116 1.38598 2.51764 + vertex 1.66958 1.38685 2.52088 + vertex 1.66966 1.38191 2.52076 + endloop + endfacet + facet normal 0.842485 0.000101433 0.53872 + outer loop + vertex 1.66966 1.38191 2.52076 + vertex 1.66958 1.38685 2.52088 + vertex 1.66766 1.38271 2.52389 + endloop + endfacet + facet normal 0.846862 -0.00698623 0.531767 + outer loop + vertex 1.66958 1.38685 2.52088 + vertex 1.66765 1.38758 2.52397 + vertex 1.66766 1.38271 2.52389 + endloop + endfacet + facet normal 0.76017 -0.00924034 0.649659 + outer loop + vertex 1.66765 1.38758 2.52397 + vertex 1.66542 1.38354 2.52651 + vertex 1.66766 1.38271 2.52389 + endloop + endfacet + facet normal 0.755467 -0.00318172 0.655179 + outer loop + vertex 1.66535 1.38841 2.52662 + vertex 1.66542 1.38354 2.52651 + vertex 1.66765 1.38758 2.52397 + endloop + endfacet + facet normal 0.937637 0.00325287 0.347601 + outer loop + vertex 1.67227 1.3898 2.51465 + vertex 1.67229 1.39464 2.51456 + vertex 1.67117 1.39078 2.51763 + endloop + endfacet + facet normal 0.937291 -1.04917e-05 0.348549 + outer loop + vertex 1.67116 1.38598 2.51764 + vertex 1.67227 1.3898 2.51465 + vertex 1.67117 1.39078 2.51763 + endloop + endfacet + facet normal 0.898983 0.000360536 0.437984 + outer loop + vertex 1.67116 1.38598 2.51764 + vertex 1.67117 1.39078 2.51763 + vertex 1.66958 1.38685 2.52088 + endloop + endfacet + facet normal 0.896391 0.00573924 0.443227 + outer loop + vertex 1.67117 1.39078 2.51763 + vertex 1.6695 1.39169 2.52098 + vertex 1.66958 1.38685 2.52088 + endloop + endfacet + facet normal 0.847979 0.00330504 0.530019 + outer loop + vertex 1.66958 1.38685 2.52088 + vertex 1.6695 1.39169 2.52098 + vertex 1.66765 1.38758 2.52397 + endloop + endfacet + facet normal 0.846284 0.00602364 0.532699 + outer loop + vertex 1.6695 1.39169 2.52098 + vertex 1.66747 1.39228 2.5242 + vertex 1.66765 1.38758 2.52397 + endloop + endfacet + facet normal 0.755456 -0.0032481 0.655191 + outer loop + vertex 1.66747 1.39228 2.5242 + vertex 1.66535 1.38841 2.52662 + vertex 1.66765 1.38758 2.52397 + endloop + endfacet + facet normal 0.746746 0.00769185 0.665065 + outer loop + vertex 1.66498 1.39351 2.52698 + vertex 1.66535 1.38841 2.52662 + vertex 1.66747 1.39228 2.5242 + endloop + endfacet + facet normal 0.919722 0.0872969 0.382741 + outer loop + vertex 1.67229 1.39464 2.51456 + vertex 1.67201 1.39949 2.51413 + vertex 1.67097 1.39573 2.51749 + endloop + endfacet + facet normal 0.916912 0.0478953 0.396205 + outer loop + vertex 1.67117 1.39078 2.51763 + vertex 1.67229 1.39464 2.51456 + vertex 1.67097 1.39573 2.51749 + endloop + endfacet + facet normal 0.899891 0.048271 0.433435 + outer loop + vertex 1.67117 1.39078 2.51763 + vertex 1.67097 1.39573 2.51749 + vertex 1.6695 1.39169 2.52098 + endloop + endfacet + facet normal 0.895233 0.0572695 0.441902 + outer loop + vertex 1.67097 1.39573 2.51749 + vertex 1.66901 1.39696 2.52129 + vertex 1.6695 1.39169 2.52098 + endloop + endfacet + facet normal 0.869737 0.0262406 0.492818 + outer loop + vertex 1.66713 1.39593 2.52467 + vertex 1.66901 1.39696 2.52129 + vertex 1.66741 1.39976 2.52397 + endloop + endfacet + facet normal 0.870904 0.0185126 0.491105 + outer loop + vertex 1.66713 1.39593 2.52467 + vertex 1.66747 1.39228 2.5242 + vertex 1.66901 1.39696 2.52129 + endloop + endfacet + facet normal 0.848768 0.0478718 0.526594 + outer loop + vertex 1.66747 1.39228 2.5242 + vertex 1.6695 1.39169 2.52098 + vertex 1.66901 1.39696 2.52129 + endloop + endfacet + facet normal 0.741269 -0.0169213 0.670995 + outer loop + vertex 1.66747 1.39228 2.5242 + vertex 1.66713 1.39593 2.52467 + vertex 1.66498 1.39351 2.52698 + endloop + endfacet + facet normal 0.87586 0.189048 0.443994 + outer loop + vertex 1.67201 1.39949 2.51413 + vertex 1.6714 1.40453 2.51318 + vertex 1.67024 1.40171 2.51668 + endloop + endfacet + facet normal 0.872182 0.168664 0.459186 + outer loop + vertex 1.67097 1.39573 2.51749 + vertex 1.67201 1.39949 2.51413 + vertex 1.67024 1.40171 2.51668 + endloop + endfacet + facet normal 0.897732 0.164928 0.408505 + outer loop + vertex 1.67097 1.39573 2.51749 + vertex 1.67024 1.40171 2.51668 + vertex 1.66901 1.39696 2.52129 + endloop + endfacet + facet normal 0.936012 0.0889686 0.340537 + outer loop + vertex 1.67024 1.40171 2.51668 + vertex 1.66875 1.4026 2.52054 + vertex 1.66901 1.39696 2.52129 + endloop + endfacet + facet normal 0.896235 0.0992941 0.432323 + outer loop + vertex 1.66875 1.4026 2.52054 + vertex 1.66741 1.39976 2.52397 + vertex 1.66901 1.39696 2.52129 + endloop + endfacet + facet normal 0.913279 0.0563735 0.403415 + outer loop + vertex 1.66722 1.40453 2.52373 + vertex 1.66741 1.39976 2.52397 + vertex 1.66875 1.4026 2.52054 + endloop + endfacet + facet normal 0.792972 0.161601 0.587436 + outer loop + vertex 1.66904 1.40641 2.517 + vertex 1.67024 1.40171 2.51668 + vertex 1.67 1.40897 2.515 + endloop + endfacet + facet normal 0.269115 0.52781 0.805602 + outer loop + vertex 1.66904 1.40641 2.517 + vertex 1.67 1.40897 2.515 + vertex 1.66891 1.40958 2.51496 + endloop + endfacet + facet normal 0.908008 0.12226 0.400716 + outer loop + vertex 1.67024 1.40171 2.51668 + vertex 1.6714 1.40453 2.51318 + vertex 1.67 1.40897 2.515 + endloop + endfacet + facet normal 0.825973 -0.441093 0.351007 + outer loop + vertex 1.67055 1.41 2.515 + vertex 1.67 1.40897 2.515 + vertex 1.67101 1.40877 2.51238 + endloop + endfacet + facet normal 0.926685 0.151398 0.343997 + outer loop + vertex 1.6714 1.40453 2.51318 + vertex 1.67101 1.40877 2.51238 + vertex 1.67 1.40897 2.515 + endloop + endfacet + facet normal 0.9269 0.21468 0.307846 + outer loop + vertex 1.67024 1.40171 2.51668 + vertex 1.66904 1.40641 2.517 + vertex 1.66875 1.4026 2.52054 + endloop + endfacet + facet normal 0.98286 0.0788892 0.166621 + outer loop + vertex 1.66904 1.40641 2.517 + vertex 1.66837 1.40757 2.52041 + vertex 1.66875 1.4026 2.52054 + endloop + endfacet + facet normal 0.916947 0.0799803 0.390912 + outer loop + vertex 1.66837 1.40757 2.52041 + vertex 1.66722 1.40453 2.52373 + vertex 1.66875 1.4026 2.52054 + endloop + endfacet + facet normal 0.934878 0.0322842 0.353498 + outer loop + vertex 1.66707 1.40957 2.52365 + vertex 1.66722 1.40453 2.52373 + vertex 1.66837 1.40757 2.52041 + endloop + endfacet + facet normal 0.996942 0.066607 0.0408699 + outer loop + vertex 1.66891 1.40958 2.51496 + vertex 1.66874 1.41078 2.51712 + vertex 1.66904 1.40641 2.517 + endloop + endfacet + facet normal 0.956491 -0.216451 0.195639 + outer loop + vertex 1.66891 1.40958 2.51496 + vertex 1.67 1.415 2.51565 + vertex 1.66874 1.41078 2.51712 + endloop + endfacet + facet normal 0.985528 0.00461281 0.169448 + outer loop + vertex 1.67101 1.40877 2.51238 + vertex 1.67101 1.41285 2.51225 + vertex 1.67055 1.41 2.515 + endloop + endfacet + facet normal 0.985646 0.00394794 0.16878 + outer loop + vertex 1.67101 1.41285 2.51225 + vertex 1.67053 1.415 2.515 + vertex 1.67055 1.41 2.515 + endloop + endfacet + facet normal 0.98307 0.0618769 0.172467 + outer loop + vertex 1.66904 1.40641 2.517 + vertex 1.66874 1.41078 2.51712 + vertex 1.66837 1.40757 2.52041 + endloop + endfacet + facet normal 0.989979 0.0265478 0.138697 + outer loop + vertex 1.66874 1.41078 2.51712 + vertex 1.66824 1.41256 2.52036 + vertex 1.66837 1.40757 2.52041 + endloop + endfacet + facet normal 0.933961 0.0270521 0.356349 + outer loop + vertex 1.66824 1.41256 2.52036 + vertex 1.66707 1.40957 2.52365 + vertex 1.66837 1.40757 2.52041 + endloop + endfacet + facet normal 0.939782 0.00860424 0.341665 + outer loop + vertex 1.66705 1.41464 2.52361 + vertex 1.66707 1.40957 2.52365 + vertex 1.66824 1.41256 2.52036 + endloop + endfacet + facet normal 0.797738 -0.0270277 0.602398 + outer loop + vertex 1.67 1.415 2.51565 + vertex 1.66879 1.41579 2.51729 + vertex 1.66874 1.41078 2.51712 + endloop + endfacet + facet normal 0.786985 -0.06625 0.613405 + outer loop + vertex 1.67 1.415 2.51565 + vertex 1.67 1.42 2.51619 + vertex 1.66879 1.41579 2.51729 + endloop + endfacet + facet normal 0.978773 -0.039018 0.201199 + outer loop + vertex 1.67101 1.41285 2.51225 + vertex 1.67121 1.41784 2.51225 + vertex 1.67053 1.415 2.515 + endloop + endfacet + facet normal 0.985353 -0.135976 0.102905 + outer loop + vertex 1.67121 1.41784 2.51225 + vertex 1.67122 1.42 2.515 + vertex 1.67053 1.415 2.515 + endloop + endfacet + facet normal 0.987002 -0.0134728 0.16014 + outer loop + vertex 1.66874 1.41078 2.51712 + vertex 1.66879 1.41579 2.51729 + vertex 1.66824 1.41256 2.52036 + endloop + endfacet + facet normal 0.984595 0.000867739 0.174848 + outer loop + vertex 1.66879 1.41579 2.51729 + vertex 1.66824 1.41758 2.52038 + vertex 1.66824 1.41256 2.52036 + endloop + endfacet + facet normal 0.938055 0.000110034 0.346485 + outer loop + vertex 1.66824 1.41758 2.52038 + vertex 1.66705 1.41464 2.52361 + vertex 1.66824 1.41256 2.52036 + endloop + endfacet + facet normal 0.939369 -0.0043692 0.34288 + outer loop + vertex 1.66708 1.41965 2.52359 + vertex 1.66705 1.41464 2.52361 + vertex 1.66824 1.41758 2.52038 + endloop + endfacet + facet normal 0.75207 -0.0445701 0.657574 + outer loop + vertex 1.67 1.42 2.51619 + vertex 1.6688 1.42076 2.51762 + vertex 1.66879 1.41579 2.51729 + endloop + endfacet + facet normal 0.707469 -0.168826 0.686283 + outer loop + vertex 1.67 1.42 2.51619 + vertex 1.67 1.425 2.51742 + vertex 1.6688 1.42076 2.51762 + endloop + endfacet + facet normal 0.994505 -0.0842078 0.0621967 + outer loop + vertex 1.67121 1.41784 2.51225 + vertex 1.67167 1.42335 2.51228 + vertex 1.67122 1.42 2.515 + endloop + endfacet + facet normal 0.930821 -0.297868 -0.211769 + outer loop + vertex 1.67167 1.42335 2.51228 + vertex 1.67282 1.425 2.515 + vertex 1.67122 1.42 2.515 + endloop + endfacet + facet normal 0.982974 -0.0140509 0.183207 + outer loop + vertex 1.66879 1.41579 2.51729 + vertex 1.6688 1.42076 2.51762 + vertex 1.66824 1.41758 2.52038 + endloop + endfacet + facet normal 0.98104 -0.0045428 0.193751 + outer loop + vertex 1.6688 1.42076 2.51762 + vertex 1.66824 1.42257 2.52047 + vertex 1.66824 1.41758 2.52038 + endloop + endfacet + facet normal 0.938742 -0.0073076 0.344542 + outer loop + vertex 1.66824 1.42257 2.52047 + vertex 1.66708 1.41965 2.52359 + vertex 1.66824 1.41758 2.52038 + endloop + endfacet + facet normal 0.933688 0.00900283 0.357975 + outer loop + vertex 1.66704 1.42458 2.52355 + vertex 1.66708 1.41965 2.52359 + vertex 1.66824 1.42257 2.52047 + endloop + endfacet + facet normal 0.319766 -0.0464564 0.946357 + outer loop + vertex 1.67 1.425 2.51742 + vertex 1.66879 1.42575 2.51787 + vertex 1.6688 1.42076 2.51762 + endloop + endfacet + facet normal 0.384013 0.0718112 0.920531 + outer loop + vertex 1.67 1.425 2.51742 + vertex 1.67 1.43 2.51703 + vertex 1.66879 1.42575 2.51787 + endloop + endfacet + facet normal 0.933484 -0.0672707 -0.352254 + outer loop + vertex 1.67167 1.42335 2.51228 + vertex 1.6721 1.42889 2.51235 + vertex 1.67282 1.425 2.515 + endloop + endfacet + facet normal 0.986009 0.0847945 -0.143512 + outer loop + vertex 1.6721 1.42889 2.51235 + vertex 1.67239 1.43 2.515 + vertex 1.67282 1.425 2.515 + endloop + endfacet + facet normal 0.980525 -0.00858393 0.196208 + outer loop + vertex 1.6688 1.42076 2.51762 + vertex 1.66879 1.42575 2.51787 + vertex 1.66824 1.42257 2.52047 + endloop + endfacet + facet normal 0.976361 0.00833541 0.215987 + outer loop + vertex 1.66879 1.42575 2.51787 + vertex 1.66819 1.42756 2.52051 + vertex 1.66824 1.42257 2.52047 + endloop + endfacet + facet normal 0.933267 0.00700534 0.359115 + outer loop + vertex 1.66819 1.42756 2.52051 + vertex 1.66704 1.42458 2.52355 + vertex 1.66824 1.42257 2.52047 + endloop + endfacet + facet normal 0.929366 0.0183181 0.368705 + outer loop + vertex 1.66697 1.42951 2.52349 + vertex 1.66704 1.42458 2.52355 + vertex 1.66819 1.42756 2.52051 + endloop + endfacet + facet normal 0.599699 -0.0133642 0.800114 + outer loop + vertex 1.67 1.43 2.51703 + vertex 1.66874 1.43096 2.51799 + vertex 1.66879 1.42575 2.51787 + endloop + endfacet + facet normal 0.512186 -0.170048 0.841872 + outer loop + vertex 1.67 1.43 2.51703 + vertex 1.67 1.435 2.51804 + vertex 1.66874 1.43096 2.51799 + endloop + endfacet + facet normal 0.993056 -0.0954608 -0.0687509 + outer loop + vertex 1.6721 1.42889 2.51235 + vertex 1.67256 1.43363 2.51245 + vertex 1.67239 1.43 2.515 + endloop + endfacet + facet normal 0.860236 -0.320012 -0.39697 + outer loop + vertex 1.67256 1.43363 2.51245 + vertex 1.67425 1.435 2.515 + vertex 1.67239 1.43 2.515 + endloop + endfacet + facet normal 0.975758 0.00400582 0.218815 + outer loop + vertex 1.66879 1.42575 2.51787 + vertex 1.66874 1.43096 2.51799 + vertex 1.66819 1.42756 2.52051 + endloop + endfacet + facet normal 0.970972 0.0193027 0.238412 + outer loop + vertex 1.66874 1.43096 2.51799 + vertex 1.6681 1.43276 2.52044 + vertex 1.66819 1.42756 2.52051 + endloop + endfacet + facet normal 0.929789 0.0203881 0.367529 + outer loop + vertex 1.6681 1.43276 2.52044 + vertex 1.66697 1.42951 2.52349 + vertex 1.66819 1.42756 2.52051 + endloop + endfacet + facet normal 0.927869 0.0253131 0.372046 + outer loop + vertex 1.66687 1.43448 2.5234 + vertex 1.66697 1.42951 2.52349 + vertex 1.6681 1.43276 2.52044 + endloop + endfacet + facet normal -0.0440936 0.00130043 0.999027 + outer loop + vertex 1.67 1.435 2.51804 + vertex 1.66875 1.43731 2.51798 + vertex 1.66874 1.43096 2.51799 + endloop + endfacet + facet normal -0.148216 -0.0553215 0.987407 + outer loop + vertex 1.67 1.435 2.51804 + vertex 1.67 1.44 2.51832 + vertex 1.66875 1.43731 2.51798 + endloop + endfacet + facet normal 0.85669 -0.120385 -0.501587 + outer loop + vertex 1.67256 1.43363 2.51245 + vertex 1.67329 1.43702 2.51288 + vertex 1.67425 1.435 2.515 + endloop + endfacet + facet normal 0.85516 -0.123144 -0.503525 + outer loop + vertex 1.67329 1.43702 2.51288 + vertex 1.67497 1.44 2.515 + vertex 1.67425 1.435 2.515 + endloop + endfacet + facet normal 0.967592 -0.0010674 0.252518 + outer loop + vertex 1.66874 1.43096 2.51799 + vertex 1.66875 1.43731 2.51798 + vertex 1.6681 1.43276 2.52044 + endloop + endfacet + facet normal 0.96026 0.0141083 0.27875 + outer loop + vertex 1.66875 1.43731 2.51798 + vertex 1.66805 1.43805 2.52037 + vertex 1.6681 1.43276 2.52044 + endloop + endfacet + facet normal 0.925988 0.0149591 0.377256 + outer loop + vertex 1.66805 1.43805 2.52037 + vertex 1.66687 1.43448 2.5234 + vertex 1.6681 1.43276 2.52044 + endloop + endfacet + facet normal 0.926686 0.0133219 0.3756 + outer loop + vertex 1.66683 1.43941 2.52332 + vertex 1.66687 1.43448 2.5234 + vertex 1.66805 1.43805 2.52037 + endloop + endfacet + facet normal 0.122536 -0.026131 0.99212 + outer loop + vertex 1.66875 1.43731 2.51798 + vertex 1.67 1.445 2.51803 + vertex 1.66867 1.44307 2.51814 + endloop + endfacet + facet normal -0.367287 0.0538845 0.928545 + outer loop + vertex 1.66875 1.43731 2.51798 + vertex 1.67 1.44 2.51832 + vertex 1.67 1.445 2.51803 + endloop + endfacet + facet normal 0.886784 -0.204204 -0.414626 + outer loop + vertex 1.67497 1.44 2.515 + vertex 1.67329 1.43702 2.51288 + vertex 1.675 1.44013 2.515 + endloop + endfacet + facet normal 0.959579 0.00487577 0.281396 + outer loop + vertex 1.66875 1.43731 2.51798 + vertex 1.66867 1.44307 2.51814 + vertex 1.66805 1.43805 2.52037 + endloop + endfacet + facet normal 0.960638 0.00314326 0.277785 + outer loop + vertex 1.66867 1.44307 2.51814 + vertex 1.66804 1.44314 2.52034 + vertex 1.66805 1.43805 2.52037 + endloop + endfacet + facet normal 0.925204 0.00367732 0.379452 + outer loop + vertex 1.66804 1.44314 2.52034 + vertex 1.66683 1.43941 2.52332 + vertex 1.66805 1.43805 2.52037 + endloop + endfacet + facet normal 0.923046 0.00849164 0.384595 + outer loop + vertex 1.66681 1.44432 2.52325 + vertex 1.66683 1.43941 2.52332 + vertex 1.66804 1.44314 2.52034 + endloop + endfacet + facet normal 0.164176 -0.0551816 0.984886 + outer loop + vertex 1.67 1.45 2.51831 + vertex 1.66867 1.44307 2.51814 + vertex 1.67 1.445 2.51803 + endloop + endfacet + facet normal -0.135536 0.0020481 0.99077 + outer loop + vertex 1.66869 1.44816 2.51813 + vertex 1.66867 1.44307 2.51814 + vertex 1.67 1.45 2.51831 + endloop + endfacet + facet normal 0.960601 -0.00185886 0.277924 + outer loop + vertex 1.66867 1.44307 2.51814 + vertex 1.66869 1.44816 2.51813 + vertex 1.66804 1.44314 2.52034 + endloop + endfacet + facet normal 0.958695 0.00124506 0.284432 + outer loop + vertex 1.66869 1.44816 2.51813 + vertex 1.66805 1.44807 2.52028 + vertex 1.66804 1.44314 2.52034 + endloop + endfacet + facet normal 0.922213 0.00253001 0.386673 + outer loop + vertex 1.66805 1.44807 2.52028 + vertex 1.66681 1.44432 2.52325 + vertex 1.66804 1.44314 2.52034 + endloop + endfacet + facet normal 0.92063 0.00599487 0.390391 + outer loop + vertex 1.6668 1.44925 2.5232 + vertex 1.66681 1.44432 2.52325 + vertex 1.66805 1.44807 2.52028 + endloop + endfacet + facet normal -0.210073 0.0566409 0.976044 + outer loop + vertex 1.67 1.455 2.51802 + vertex 1.66869 1.44816 2.51813 + vertex 1.67 1.45 2.51831 + endloop + endfacet + facet normal 0.0102332 0.0147244 0.999839 + outer loop + vertex 1.6687 1.45312 2.51806 + vertex 1.66869 1.44816 2.51813 + vertex 1.67 1.455 2.51802 + endloop + endfacet + facet normal 0.958692 0.00154756 0.284443 + outer loop + vertex 1.66869 1.44816 2.51813 + vertex 1.6687 1.45312 2.51806 + vertex 1.66805 1.44807 2.52028 + endloop + endfacet + facet normal 0.95919 0.00074291 0.282761 + outer loop + vertex 1.6687 1.45312 2.51806 + vertex 1.66805 1.45302 2.52025 + vertex 1.66805 1.44807 2.52028 + endloop + endfacet + facet normal 0.91998 0.00140472 0.391963 + outer loop + vertex 1.66805 1.45302 2.52025 + vertex 1.6668 1.44925 2.5232 + vertex 1.66805 1.44807 2.52028 + endloop + endfacet + facet normal 0.91986 0.00166404 0.392244 + outer loop + vertex 1.6668 1.4542 2.52319 + vertex 1.6668 1.44925 2.5232 + vertex 1.66805 1.45302 2.52025 + endloop + endfacet + facet normal 0.0344129 -0.00200153 0.999406 + outer loop + vertex 1.67 1.46 2.51803 + vertex 1.6687 1.45312 2.51806 + vertex 1.67 1.455 2.51802 + endloop + endfacet + facet normal -0.0287875 0.00994253 0.999536 + outer loop + vertex 1.6687 1.45809 2.51801 + vertex 1.6687 1.45312 2.51806 + vertex 1.67 1.46 2.51803 + endloop + endfacet + facet normal 0.959175 0.00193228 0.282808 + outer loop + vertex 1.6687 1.45312 2.51806 + vertex 1.6687 1.45809 2.51801 + vertex 1.66805 1.45302 2.52025 + endloop + endfacet + facet normal 0.960727 -0.000615523 0.277495 + outer loop + vertex 1.6687 1.45809 2.51801 + vertex 1.66805 1.458 2.52027 + vertex 1.66805 1.45302 2.52025 + endloop + endfacet + facet normal 0.919487 -0.000924828 0.39312 + outer loop + vertex 1.66805 1.458 2.52027 + vertex 1.6668 1.4542 2.52319 + vertex 1.66805 1.45302 2.52025 + endloop + endfacet + facet normal 0.917571 0.00312237 0.39756 + outer loop + vertex 1.66677 1.45917 2.52321 + vertex 1.6668 1.4542 2.52319 + vertex 1.66805 1.458 2.52027 + endloop + endfacet + facet normal -0.107459 0.0634912 0.99218 + outer loop + vertex 1.67 1.465 2.51771 + vertex 1.6687 1.45809 2.51801 + vertex 1.67 1.46 2.51803 + endloop + endfacet + facet normal 0.263833 -0.00738039 0.96454 + outer loop + vertex 1.66871 1.46309 2.51805 + vertex 1.6687 1.45809 2.51801 + vertex 1.67 1.465 2.51771 + endloop + endfacet + facet normal 0.960742 -0.00231299 0.277433 + outer loop + vertex 1.6687 1.45809 2.51801 + vertex 1.66871 1.46309 2.51805 + vertex 1.66805 1.458 2.52027 + endloop + endfacet + facet normal 0.957817 0.00239679 0.287369 + outer loop + vertex 1.66871 1.46309 2.51805 + vertex 1.66803 1.463 2.52029 + vertex 1.66805 1.458 2.52027 + endloop + endfacet + facet normal 0.917381 0.00178552 0.398006 + outer loop + vertex 1.66803 1.463 2.52029 + vertex 1.66677 1.45917 2.52321 + vertex 1.66805 1.458 2.52027 + endloop + endfacet + facet normal 0.912918 0.0108782 0.407999 + outer loop + vertex 1.66671 1.46415 2.52321 + vertex 1.66677 1.45917 2.52321 + vertex 1.66803 1.463 2.52029 + endloop + endfacet + facet normal 0.404385 -0.11257 0.907635 + outer loop + vertex 1.67 1.47 2.51833 + vertex 1.66871 1.46309 2.51805 + vertex 1.67 1.465 2.51771 + endloop + endfacet + facet normal -0.140356 -0.0138987 0.990004 + outer loop + vertex 1.6687 1.46809 2.51812 + vertex 1.66871 1.46309 2.51805 + vertex 1.67 1.47 2.51833 + endloop + endfacet + facet normal 0.957867 -0.00210572 0.287205 + outer loop + vertex 1.66871 1.46309 2.51805 + vertex 1.6687 1.46809 2.51812 + vertex 1.66803 1.463 2.52029 + endloop + endfacet + facet normal 0.951654 0.00716321 0.307087 + outer loop + vertex 1.6687 1.46809 2.51812 + vertex 1.668 1.46798 2.52027 + vertex 1.66803 1.463 2.52029 + endloop + endfacet + facet normal 0.912416 0.00725753 0.409201 + outer loop + vertex 1.668 1.46798 2.52027 + vertex 1.66671 1.46415 2.52321 + vertex 1.66803 1.463 2.52029 + endloop + endfacet + facet normal 0.909089 0.0138745 0.416372 + outer loop + vertex 1.66665 1.46914 2.52318 + vertex 1.66671 1.46415 2.52321 + vertex 1.668 1.46798 2.52027 + endloop + endfacet + facet normal -0.160214 0 0.987082 + outer loop + vertex 1.67 1.475 2.51833 + vertex 1.6687 1.46809 2.51812 + vertex 1.67 1.47 2.51833 + endloop + endfacet + facet normal -0.22786 0.0131859 0.973605 + outer loop + vertex 1.66867 1.4731 2.51805 + vertex 1.6687 1.46809 2.51812 + vertex 1.67 1.475 2.51833 + endloop + endfacet + facet normal 0.951628 0.00837047 0.307139 + outer loop + vertex 1.6687 1.46809 2.51812 + vertex 1.66867 1.4731 2.51805 + vertex 1.668 1.46798 2.52027 + endloop + endfacet + facet normal 0.950799 0.00957425 0.309661 + outer loop + vertex 1.66867 1.4731 2.51805 + vertex 1.66797 1.47298 2.52022 + vertex 1.668 1.46798 2.52027 + endloop + endfacet + facet normal 0.908592 0.010288 0.417559 + outer loop + vertex 1.66797 1.47298 2.52022 + vertex 1.66665 1.46914 2.52318 + vertex 1.668 1.46798 2.52027 + endloop + endfacet + facet normal 0.909455 0.00856841 0.415713 + outer loop + vertex 1.66662 1.47411 2.52314 + vertex 1.66665 1.46914 2.52318 + vertex 1.66797 1.47298 2.52022 + endloop + endfacet + facet normal -0.360382 0.112985 0.925937 + outer loop + vertex 1.67 1.48 2.51772 + vertex 1.66867 1.4731 2.51805 + vertex 1.67 1.475 2.51833 + endloop + endfacet + facet normal 0.188005 0.01026 0.982114 + outer loop + vertex 1.66867 1.4781 2.518 + vertex 1.66867 1.4731 2.51805 + vertex 1.67 1.48 2.51772 + endloop + endfacet + facet normal 0.950916 0.00478504 0.309413 + outer loop + vertex 1.66867 1.4731 2.51805 + vertex 1.66867 1.4781 2.518 + vertex 1.66797 1.47298 2.52022 + endloop + endfacet + facet normal 0.952682 0.00217558 0.303962 + outer loop + vertex 1.66867 1.4781 2.518 + vertex 1.66796 1.47798 2.52021 + vertex 1.66797 1.47298 2.52022 + endloop + endfacet + facet normal 0.908587 0.00246465 0.417687 + outer loop + vertex 1.66796 1.47798 2.52021 + vertex 1.66662 1.47411 2.52314 + vertex 1.66797 1.47298 2.52022 + endloop + endfacet + facet normal 0.907363 0.00488679 0.42032 + outer loop + vertex 1.66661 1.47912 2.52312 + vertex 1.66662 1.47411 2.52314 + vertex 1.66796 1.47798 2.52021 + endloop + endfacet + facet normal 0.28694 -0.0630819 0.955869 + outer loop + vertex 1.67 1.485 2.51805 + vertex 1.66867 1.4781 2.518 + vertex 1.67 1.48 2.51772 + endloop + endfacet + facet normal -0.000170449 -0.00791688 0.999969 + outer loop + vertex 1.66866 1.4831 2.51803 + vertex 1.66867 1.4781 2.518 + vertex 1.67 1.485 2.51805 + endloop + endfacet + facet normal 0.952747 -0.00176873 0.303761 + outer loop + vertex 1.66867 1.4781 2.518 + vertex 1.66866 1.4831 2.51803 + vertex 1.66796 1.47798 2.52021 + endloop + endfacet + facet normal 0.952648 -0.00162325 0.304072 + outer loop + vertex 1.66866 1.4831 2.51803 + vertex 1.66796 1.48299 2.52023 + vertex 1.66796 1.47798 2.52021 + endloop + endfacet + facet normal 0.90634 -0.00200733 0.422544 + outer loop + vertex 1.66796 1.48299 2.52023 + vertex 1.66661 1.47912 2.52312 + vertex 1.66796 1.47798 2.52021 + endloop + endfacet + facet normal 0.90728 -0.00385843 0.420509 + outer loop + vertex 1.66663 1.4841 2.52312 + vertex 1.66661 1.47912 2.52312 + vertex 1.66796 1.48299 2.52023 + endloop + endfacet + facet normal -0.00572467 -0.00400534 0.999976 + outer loop + vertex 1.67 1.49 2.51807 + vertex 1.66866 1.4831 2.51803 + vertex 1.67 1.485 2.51805 + endloop + endfacet + facet normal 0.015562 -0.0081304 0.999846 + outer loop + vertex 1.66867 1.48809 2.51808 + vertex 1.66866 1.4831 2.51803 + vertex 1.67 1.49 2.51807 + endloop + endfacet + facet normal 0.952668 -0.00324161 0.303994 + outer loop + vertex 1.66866 1.4831 2.51803 + vertex 1.66867 1.48809 2.51808 + vertex 1.66796 1.48299 2.52023 + endloop + endfacet + facet normal 0.952936 -0.00363461 0.303149 + outer loop + vertex 1.66867 1.48809 2.51808 + vertex 1.66797 1.48798 2.52026 + vertex 1.66796 1.48299 2.52023 + endloop + endfacet + facet normal 0.907195 -0.00441912 0.420686 + outer loop + vertex 1.66797 1.48798 2.52026 + vertex 1.66663 1.4841 2.52312 + vertex 1.66796 1.48299 2.52023 + endloop + endfacet + facet normal 0.903842 0.00203197 0.427861 + outer loop + vertex 1.66661 1.48911 2.52313 + vertex 1.66663 1.4841 2.52312 + vertex 1.66797 1.48798 2.52026 + endloop + endfacet + facet normal 0.00966276 -0.00400522 0.999945 + outer loop + vertex 1.67 1.495 2.51809 + vertex 1.66867 1.48809 2.51808 + vertex 1.67 1.49 2.51807 + endloop + endfacet + facet normal 0.0788221 -0.0173467 0.996738 + outer loop + vertex 1.66867 1.49309 2.51816 + vertex 1.66867 1.48809 2.51808 + vertex 1.67 1.495 2.51809 + endloop + endfacet + facet normal 0.952952 -0.00500857 0.303081 + outer loop + vertex 1.66867 1.48809 2.51808 + vertex 1.66867 1.49309 2.51816 + vertex 1.66797 1.48798 2.52026 + endloop + endfacet + facet normal 0.948715 0.000930202 0.316131 + outer loop + vertex 1.66867 1.49309 2.51816 + vertex 1.66796 1.49297 2.52029 + vertex 1.66797 1.48798 2.52026 + endloop + endfacet + facet normal 0.903543 6.38046e-05 0.428497 + outer loop + vertex 1.66796 1.49297 2.52029 + vertex 1.66661 1.48911 2.52313 + vertex 1.66797 1.48798 2.52026 + endloop + endfacet + facet normal 0.901545 0.00382808 0.432668 + outer loop + vertex 1.66659 1.49409 2.52313 + vertex 1.66661 1.48911 2.52313 + vertex 1.66796 1.49297 2.52029 + endloop + endfacet + facet normal 0.141278 -0.0612496 0.988073 + outer loop + vertex 1.67 1.5 2.5184 + vertex 1.66867 1.49309 2.51816 + vertex 1.67 1.495 2.51809 + endloop + endfacet + facet normal -0.0965251 -0.0155887 0.995208 + outer loop + vertex 1.66865 1.49809 2.51824 + vertex 1.66867 1.49309 2.51816 + vertex 1.67 1.5 2.5184 + endloop + endfacet + facet normal 0.948775 -0.00280032 0.315941 + outer loop + vertex 1.66867 1.49309 2.51816 + vertex 1.66865 1.49809 2.51824 + vertex 1.66796 1.49297 2.52029 + endloop + endfacet + facet normal 0.945654 0.00133003 0.325173 + outer loop + vertex 1.66865 1.49809 2.51824 + vertex 1.66794 1.49797 2.52032 + vertex 1.66796 1.49297 2.52029 + endloop + endfacet + facet normal 0.901067 0.000700317 0.433679 + outer loop + vertex 1.66794 1.49797 2.52032 + vertex 1.66659 1.49409 2.52313 + vertex 1.66796 1.49297 2.52029 + endloop + endfacet + facet normal 0.895784 0.0103153 0.44437 + outer loop + vertex 1.66654 1.4991 2.52312 + vertex 1.66659 1.49409 2.52313 + vertex 1.66794 1.49797 2.52032 + endloop + endfacet + facet normal -0.110045 -0.00597156 0.993909 + outer loop + vertex 1.67 1.505 2.51843 + vertex 1.66865 1.49809 2.51824 + vertex 1.67 1.5 2.5184 + endloop + endfacet + facet normal -0.139748 -8.83578e-05 0.990187 + outer loop + vertex 1.66865 1.50308 2.51824 + vertex 1.66865 1.49809 2.51824 + vertex 1.67 1.505 2.51843 + endloop + endfacet + facet normal 0.945648 0.00160415 0.325187 + outer loop + vertex 1.66865 1.49809 2.51824 + vertex 1.66865 1.50308 2.51824 + vertex 1.66794 1.49797 2.52032 + endloop + endfacet + facet normal 0.942317 0.00591575 0.334668 + outer loop + vertex 1.66865 1.50308 2.51824 + vertex 1.66792 1.50295 2.52028 + vertex 1.66794 1.49797 2.52032 + endloop + endfacet + facet normal 0.895218 0.00662135 0.44558 + outer loop + vertex 1.66792 1.50295 2.52028 + vertex 1.66654 1.4991 2.52312 + vertex 1.66794 1.49797 2.52032 + endloop + endfacet + facet normal 0.89703 0.00329566 0.441957 + outer loop + vertex 1.66654 1.50407 2.52307 + vertex 1.66654 1.4991 2.52312 + vertex 1.66792 1.50295 2.52028 + endloop + endfacet + facet normal -0.142625 0.00198224 0.989775 + outer loop + vertex 1.67 1.51 2.51842 + vertex 1.66865 1.50308 2.51824 + vertex 1.67 1.505 2.51843 + endloop + endfacet + facet normal -0.177513 0.00895663 0.984078 + outer loop + vertex 1.66864 1.50809 2.51819 + vertex 1.66865 1.50308 2.51824 + vertex 1.67 1.51 2.51842 + endloop + endfacet + facet normal 0.942343 0.00488452 0.334612 + outer loop + vertex 1.66865 1.50308 2.51824 + vertex 1.66864 1.50809 2.51819 + vertex 1.66792 1.50295 2.52028 + endloop + endfacet + facet normal 0.943519 0.00337571 0.3313 + outer loop + vertex 1.66864 1.50809 2.51819 + vertex 1.66793 1.50794 2.52022 + vertex 1.66792 1.50295 2.52028 + endloop + endfacet + facet normal 0.89724 0.00465356 0.441519 + outer loop + vertex 1.66793 1.50794 2.52022 + vertex 1.66654 1.50407 2.52307 + vertex 1.66792 1.50295 2.52028 + endloop + endfacet + facet normal 0.90183 -0.00393008 0.432074 + outer loop + vertex 1.66658 1.50899 2.52303 + vertex 1.66654 1.50407 2.52307 + vertex 1.66793 1.50794 2.52022 + endloop + endfacet + facet normal -0.165294 0 0.986244 + outer loop + vertex 1.67 1.515 2.51842 + vertex 1.66864 1.50809 2.51819 + vertex 1.67 1.51 2.51842 + endloop + endfacet + facet normal -0.306619 0.029006 0.95139 + outer loop + vertex 1.66864 1.51309 2.51804 + vertex 1.66864 1.50809 2.51819 + vertex 1.67 1.515 2.51842 + endloop + endfacet + facet normal 0.943362 0.00903532 0.331641 + outer loop + vertex 1.66864 1.50809 2.51819 + vertex 1.66864 1.51309 2.51804 + vertex 1.66793 1.50794 2.52022 + endloop + endfacet + facet normal 0.951504 -0.00226954 0.307629 + outer loop + vertex 1.66864 1.51309 2.51804 + vertex 1.66795 1.51295 2.5202 + vertex 1.66793 1.50794 2.52022 + endloop + endfacet + facet normal 0.902196 -0.00145324 0.431324 + outer loop + vertex 1.66795 1.51295 2.5202 + vertex 1.66658 1.50899 2.52303 + vertex 1.66793 1.50794 2.52022 + endloop + endfacet + facet normal 0.901796 -0.000715216 0.432161 + outer loop + vertex 1.66657 1.51396 2.52306 + vertex 1.66658 1.50899 2.52303 + vertex 1.66795 1.51295 2.5202 + endloop + endfacet + facet normal -0.469649 0.161454 0.867964 + outer loop + vertex 1.67 1.52 2.51749 + vertex 1.66864 1.51309 2.51804 + vertex 1.67 1.515 2.51842 + endloop + endfacet + facet normal 0.354457 0.00488329 0.93506 + outer loop + vertex 1.66866 1.5181 2.51801 + vertex 1.66864 1.51309 2.51804 + vertex 1.67 1.52 2.51749 + endloop + endfacet + facet normal 0.951476 -0.000739185 0.307722 + outer loop + vertex 1.66864 1.51309 2.51804 + vertex 1.66866 1.5181 2.51801 + vertex 1.66795 1.51295 2.5202 + endloop + endfacet + facet normal 0.952805 -0.00268539 0.303572 + outer loop + vertex 1.66866 1.5181 2.51801 + vertex 1.66795 1.51797 2.52021 + vertex 1.66795 1.51295 2.5202 + endloop + endfacet + facet normal 0.901465 -0.00308009 0.43284 + outer loop + vertex 1.66795 1.51797 2.52021 + vertex 1.66657 1.51396 2.52306 + vertex 1.66795 1.51295 2.5202 + endloop + endfacet + facet normal 0.902445 -0.00488341 0.430777 + outer loop + vertex 1.66657 1.51899 2.52312 + vertex 1.66657 1.51396 2.52306 + vertex 1.66795 1.51797 2.52021 + endloop + endfacet + facet normal 0.538602 -0.154085 0.828351 + outer loop + vertex 1.67 1.525 2.51842 + vertex 1.66866 1.5181 2.51801 + vertex 1.67 1.52 2.51749 + endloop + endfacet + facet normal -0.249051 -0.00915376 0.968447 + outer loop + vertex 1.66866 1.52311 2.51806 + vertex 1.66866 1.5181 2.51801 + vertex 1.67 1.525 2.51842 + endloop + endfacet + facet normal 0.952828 -0.00443712 0.303477 + outer loop + vertex 1.66866 1.5181 2.51801 + vertex 1.66866 1.52311 2.51806 + vertex 1.66795 1.51797 2.52021 + endloop + endfacet + facet normal 0.951374 -0.00232844 0.308028 + outer loop + vertex 1.66866 1.52311 2.51806 + vertex 1.66796 1.52299 2.52025 + vertex 1.66795 1.51797 2.52021 + endloop + endfacet + facet normal 0.902699 -0.00308046 0.430261 + outer loop + vertex 1.66796 1.52299 2.52025 + vertex 1.66657 1.51899 2.52312 + vertex 1.66795 1.51797 2.52021 + endloop + endfacet + facet normal 0.904077 -0.00565916 0.427332 + outer loop + vertex 1.6666 1.52402 2.52313 + vertex 1.66657 1.51899 2.52312 + vertex 1.66796 1.52299 2.52025 + endloop + endfacet + facet normal -0.394371 0.104097 0.913036 + outer loop + vertex 1.67 1.53 2.51785 + vertex 1.66866 1.52311 2.51806 + vertex 1.67 1.525 2.51842 + endloop + endfacet + facet normal 0.167343 -0.00259652 0.985895 + outer loop + vertex 1.66865 1.52813 2.51807 + vertex 1.66866 1.52311 2.51806 + vertex 1.67 1.53 2.51785 + endloop + endfacet + facet normal 0.951326 0.000831845 0.308184 + outer loop + vertex 1.66866 1.52311 2.51806 + vertex 1.66865 1.52813 2.51807 + vertex 1.66796 1.52299 2.52025 + endloop + endfacet + facet normal 0.950828 0.00154707 0.309716 + outer loop + vertex 1.66865 1.52813 2.51807 + vertex 1.66794 1.52801 2.52027 + vertex 1.66796 1.52299 2.52025 + endloop + endfacet + facet normal 0.904993 0.000876352 0.425425 + outer loop + vertex 1.66794 1.52801 2.52027 + vertex 1.6666 1.52402 2.52313 + vertex 1.66796 1.52299 2.52025 + endloop + endfacet + facet normal 0.903185 0.00422161 0.42923 + outer loop + vertex 1.66658 1.52902 2.52313 + vertex 1.6666 1.52402 2.52313 + vertex 1.66794 1.52801 2.52027 + endloop + endfacet + facet normal 0.24421 -0.0600428 0.967862 + outer loop + vertex 1.67 1.535 2.51816 + vertex 1.66865 1.52813 2.51807 + vertex 1.67 1.53 2.51785 + endloop + endfacet + facet normal -0.0015331 -0.0123312 0.999923 + outer loop + vertex 1.66864 1.53314 2.51814 + vertex 1.66865 1.52813 2.51807 + vertex 1.67 1.535 2.51816 + endloop + endfacet + facet normal 0.950881 -0.00166636 0.309551 + outer loop + vertex 1.66865 1.52813 2.51807 + vertex 1.66864 1.53314 2.51814 + vertex 1.66794 1.52801 2.52027 + endloop + endfacet + facet normal 0.946319 0.00463275 0.323201 + outer loop + vertex 1.66864 1.53314 2.51814 + vertex 1.66791 1.53303 2.52028 + vertex 1.66794 1.52801 2.52027 + endloop + endfacet + facet normal 0.903165 0.00407179 0.429273 + outer loop + vertex 1.66791 1.53303 2.52028 + vertex 1.66658 1.52902 2.52313 + vertex 1.66794 1.52801 2.52027 + endloop + endfacet + facet normal 0.896615 0.0156397 0.442535 + outer loop + vertex 1.66651 1.53403 2.52309 + vertex 1.66658 1.52902 2.52313 + vertex 1.66791 1.53303 2.52028 + endloop + endfacet + facet normal -0.0184519 0 0.99983 + outer loop + vertex 1.67 1.54 2.51816 + vertex 1.66864 1.53314 2.51814 + vertex 1.67 1.535 2.51816 + endloop + endfacet + facet normal 0.0189046 -0.00738524 0.999794 + outer loop + vertex 1.66862 1.53816 2.51817 + vertex 1.66864 1.53314 2.51814 + vertex 1.67 1.54 2.51816 + endloop + endfacet + facet normal 0.946379 0.00134517 0.323055 + outer loop + vertex 1.66864 1.53314 2.51814 + vertex 1.66862 1.53816 2.51817 + vertex 1.66791 1.53303 2.52028 + endloop + endfacet + facet normal 0.941011 0.00835991 0.338273 + outer loop + vertex 1.66862 1.53816 2.51817 + vertex 1.66789 1.53803 2.52023 + vertex 1.66791 1.53303 2.52028 + endloop + endfacet + facet normal 0.895796 0.00931108 0.444369 + outer loop + vertex 1.66789 1.53803 2.52023 + vertex 1.66651 1.53403 2.52309 + vertex 1.66791 1.53303 2.52028 + endloop + endfacet + facet normal 0.895541 0.0097579 0.444872 + outer loop + vertex 1.66649 1.53902 2.52301 + vertex 1.66651 1.53403 2.52309 + vertex 1.66789 1.53803 2.52023 + endloop + endfacet + facet normal 0.0888978 -0.0596415 0.994254 + outer loop + vertex 1.67 1.545 2.51846 + vertex 1.66862 1.53816 2.51817 + vertex 1.67 1.54 2.51816 + endloop + endfacet + facet normal -0.23023 0.00541749 0.973121 + outer loop + vertex 1.66862 1.54317 2.51814 + vertex 1.66862 1.53816 2.51817 + vertex 1.67 1.545 2.51846 + endloop + endfacet + facet normal 0.941148 0.00268263 0.337984 + outer loop + vertex 1.66862 1.53816 2.51817 + vertex 1.66862 1.54317 2.51814 + vertex 1.66789 1.53803 2.52023 + endloop + endfacet + facet normal 0.940711 0.00323548 0.339193 + outer loop + vertex 1.66862 1.54317 2.51814 + vertex 1.66789 1.54306 2.52017 + vertex 1.66789 1.53803 2.52023 + endloop + endfacet + facet normal 0.894827 0.00448584 0.446391 + outer loop + vertex 1.66789 1.54306 2.52017 + vertex 1.66649 1.53902 2.52301 + vertex 1.66789 1.53803 2.52023 + endloop + endfacet + facet normal 0.896763 0.00108752 0.44251 + outer loop + vertex 1.66653 1.54401 2.52293 + vertex 1.66649 1.53902 2.52301 + vertex 1.66789 1.54306 2.52017 + endloop + endfacet + facet normal -0.294517 0.0572227 0.953931 + outer loop + vertex 1.67 1.55 2.51816 + vertex 1.66862 1.54317 2.51814 + vertex 1.67 1.545 2.51846 + endloop + endfacet + facet normal -0.077928 0.0133478 0.99687 + outer loop + vertex 1.66863 1.54819 2.51808 + vertex 1.66862 1.54317 2.51814 + vertex 1.67 1.55 2.51816 + endloop + endfacet + facet normal 0.940732 0.00219871 0.339145 + outer loop + vertex 1.66862 1.54317 2.51814 + vertex 1.66863 1.54819 2.51808 + vertex 1.66789 1.54306 2.52017 + endloop + endfacet + facet normal 0.94549 -0.00400602 0.325627 + outer loop + vertex 1.66863 1.54819 2.51808 + vertex 1.66793 1.54807 2.52012 + vertex 1.66789 1.54306 2.52017 + endloop + endfacet + facet normal 0.896278 -0.00243675 0.443486 + outer loop + vertex 1.66793 1.54807 2.52012 + vertex 1.66653 1.54401 2.52293 + vertex 1.66789 1.54306 2.52017 + endloop + endfacet + facet normal 0.896633 -0.00306031 0.442764 + outer loop + vertex 1.66656 1.54901 2.52289 + vertex 1.66653 1.54401 2.52293 + vertex 1.66793 1.54807 2.52012 + endloop + endfacet + facet normal -0.0577242 -0.00199937 0.998331 + outer loop + vertex 1.67 1.555 2.51817 + vertex 1.66863 1.54819 2.51808 + vertex 1.67 1.55 2.51816 + endloop + endfacet + facet normal -0.0914355 0.00480888 0.995799 + outer loop + vertex 1.66866 1.5532 2.51806 + vertex 1.66863 1.54819 2.51808 + vertex 1.67 1.555 2.51817 + endloop + endfacet + facet normal 0.945493 -0.00418851 0.325617 + outer loop + vertex 1.66863 1.54819 2.51808 + vertex 1.66866 1.5532 2.51806 + vertex 1.66793 1.54807 2.52012 + endloop + endfacet + facet normal 0.949404 -0.00945812 0.313915 + outer loop + vertex 1.66866 1.5532 2.51806 + vertex 1.66798 1.55307 2.52012 + vertex 1.66793 1.54807 2.52012 + endloop + endfacet + facet normal 0.895814 -0.00888891 0.44434 + outer loop + vertex 1.66798 1.55307 2.52012 + vertex 1.66656 1.54901 2.52289 + vertex 1.66793 1.54807 2.52012 + endloop + endfacet + facet normal 0.896476 -0.0100521 0.442978 + outer loop + vertex 1.66661 1.554 2.52291 + vertex 1.66656 1.54901 2.52289 + vertex 1.66798 1.55307 2.52012 + endloop + endfacet + facet normal -0.085006 0 0.99638 + outer loop + vertex 1.67 1.56 2.51817 + vertex 1.66866 1.5532 2.51806 + vertex 1.67 1.555 2.51817 + endloop + endfacet + facet normal -0.08281 -0.000435165 0.996565 + outer loop + vertex 1.6687 1.55816 2.51806 + vertex 1.66866 1.5532 2.51806 + vertex 1.67 1.56 2.51817 + endloop + endfacet + facet normal 0.949395 -0.00855372 0.313969 + outer loop + vertex 1.66866 1.5532 2.51806 + vertex 1.6687 1.55816 2.51806 + vertex 1.66798 1.55307 2.52012 + endloop + endfacet + facet normal 0.950798 -0.0105062 0.309634 + outer loop + vertex 1.6687 1.55816 2.51806 + vertex 1.66803 1.55802 2.52014 + vertex 1.66798 1.55307 2.52012 + endloop + endfacet + facet normal 0.896413 -0.0104951 0.443095 + outer loop + vertex 1.66803 1.55802 2.52014 + vertex 1.66661 1.554 2.52291 + vertex 1.66798 1.55307 2.52012 + endloop + endfacet + facet normal 0.897442 -0.0123305 0.440959 + outer loop + vertex 1.66665 1.55902 2.52296 + vertex 1.66661 1.554 2.52291 + vertex 1.66803 1.55802 2.52014 + endloop + endfacet + facet normal -0.0834248 0 0.996514 + outer loop + vertex 1.67 1.565 2.51817 + vertex 1.6687 1.55816 2.51806 + vertex 1.67 1.56 2.51817 + endloop + endfacet + facet normal -0.00951674 -0.0140472 0.999856 + outer loop + vertex 1.66874 1.56307 2.51813 + vertex 1.6687 1.55816 2.51806 + vertex 1.67 1.565 2.51817 + endloop + endfacet + facet normal 0.950802 -0.0109652 0.309604 + outer loop + vertex 1.6687 1.55816 2.51806 + vertex 1.66874 1.56307 2.51813 + vertex 1.66803 1.55802 2.52014 + endloop + endfacet + facet normal 0.951269 -0.0116103 0.308145 + outer loop + vertex 1.66874 1.56307 2.51813 + vertex 1.66807 1.56294 2.52018 + vertex 1.66803 1.55802 2.52014 + endloop + endfacet + facet normal 0.89745 -0.0122779 0.440945 + outer loop + vertex 1.66807 1.56294 2.52018 + vertex 1.66665 1.55902 2.52296 + vertex 1.66803 1.55802 2.52014 + endloop + endfacet + facet normal 0.898938 -0.0150312 0.437817 + outer loop + vertex 1.66672 1.56406 2.52301 + vertex 1.66665 1.55902 2.52296 + vertex 1.66807 1.56294 2.52018 + endloop + endfacet + facet normal 0.0634997 -0.0617453 0.99607 + outer loop + vertex 1.67 1.57 2.51848 + vertex 1.66874 1.56307 2.51813 + vertex 1.67 1.565 2.51817 + endloop + endfacet + facet normal -0.18922 -0.0150049 0.98182 + outer loop + vertex 1.66877 1.56795 2.51821 + vertex 1.66874 1.56307 2.51813 + vertex 1.67 1.57 2.51848 + endloop + endfacet + facet normal 0.951272 -0.0119706 0.308122 + outer loop + vertex 1.66874 1.56307 2.51813 + vertex 1.66877 1.56795 2.51821 + vertex 1.66807 1.56294 2.52018 + endloop + endfacet + facet normal 0.952943 -0.0142899 0.302814 + outer loop + vertex 1.66877 1.56795 2.51821 + vertex 1.66812 1.56786 2.52025 + vertex 1.66807 1.56294 2.52018 + endloop + endfacet + facet normal 0.898826 -0.0156913 0.438025 + outer loop + vertex 1.66812 1.56786 2.52025 + vertex 1.66672 1.56406 2.52301 + vertex 1.66807 1.56294 2.52018 + endloop + endfacet + facet normal 0.900217 -0.0183538 0.435054 + outer loop + vertex 1.66679 1.56907 2.52306 + vertex 1.66672 1.56406 2.52301 + vertex 1.66812 1.56786 2.52025 + endloop + endfacet + facet normal -0.213249 0 0.976998 + outer loop + vertex 1.67 1.575 2.51848 + vertex 1.66877 1.56795 2.51821 + vertex 1.67 1.57 2.51848 + endloop + endfacet + facet normal -0.170852 -0.00769049 0.985267 + outer loop + vertex 1.66879 1.57284 2.51825 + vertex 1.66877 1.56795 2.51821 + vertex 1.67 1.575 2.51848 + endloop + endfacet + facet normal 0.952924 -0.00634055 0.303143 + outer loop + vertex 1.66877 1.56795 2.51821 + vertex 1.66879 1.57284 2.51825 + vertex 1.66812 1.56786 2.52025 + endloop + endfacet + facet normal 0.958913 -0.0151274 0.283297 + outer loop + vertex 1.66879 1.57284 2.51825 + vertex 1.66818 1.57273 2.52034 + vertex 1.66812 1.56786 2.52025 + endloop + endfacet + facet normal 0.900454 -0.0170768 0.434616 + outer loop + vertex 1.66818 1.57273 2.52034 + vertex 1.66679 1.56907 2.52306 + vertex 1.66812 1.56786 2.52025 + endloop + endfacet + facet normal 0.901637 -0.0194239 0.432057 + outer loop + vertex 1.66686 1.57405 2.52313 + vertex 1.66679 1.56907 2.52306 + vertex 1.66818 1.57273 2.52034 + endloop + endfacet + facet normal -0.285565 0.0592938 0.956523 + outer loop + vertex 1.67 1.58 2.51817 + vertex 1.66879 1.57284 2.51825 + vertex 1.67 1.575 2.51848 + endloop + endfacet + facet normal 0.207828 -0.0236001 0.977881 + outer loop + vertex 1.66882 1.57757 2.51836 + vertex 1.66879 1.57284 2.51825 + vertex 1.67 1.58 2.51817 + endloop + endfacet + facet normal 0.958911 -0.0113885 0.283477 + outer loop + vertex 1.66879 1.57284 2.51825 + vertex 1.66882 1.57757 2.51836 + vertex 1.66818 1.57273 2.52034 + endloop + endfacet + facet normal 0.96387 -0.01931 0.265672 + outer loop + vertex 1.66882 1.57757 2.51836 + vertex 1.66822 1.57743 2.52051 + vertex 1.66818 1.57273 2.52034 + endloop + endfacet + facet normal 0.900478 -0.0251059 0.434176 + outer loop + vertex 1.66822 1.57743 2.52051 + vertex 1.66686 1.57405 2.52313 + vertex 1.66818 1.57273 2.52034 + endloop + endfacet + facet normal 0.898442 -0.0208777 0.438595 + outer loop + vertex 1.66693 1.57898 2.52323 + vertex 1.66686 1.57405 2.52313 + vertex 1.66822 1.57743 2.52051 + endloop + endfacet + facet normal 0.168661 -0.00390102 0.985666 + outer loop + vertex 1.67 1.585 2.51819 + vertex 1.66882 1.57757 2.51836 + vertex 1.67 1.58 2.51817 + endloop + endfacet + facet normal 0.533141 -0.0652716 0.843505 + outer loop + vertex 1.67 1.585 2.51819 + vertex 1.66873 1.58112 2.51869 + vertex 1.66882 1.57757 2.51836 + endloop + endfacet + facet normal 0.877713 0.0746719 -0.473333 + outer loop + vertex 1.67333 1.58413 2.51229 + vertex 1.67472 1.585 2.515 + vertex 1.675 1.58171 2.515 + endloop + endfacet + facet normal 0.963758 -0.00137601 0.266775 + outer loop + vertex 1.66882 1.57757 2.51836 + vertex 1.66873 1.58112 2.51869 + vertex 1.66822 1.57743 2.52051 + endloop + endfacet + facet normal 0.9621 0.0017759 0.27269 + outer loop + vertex 1.66873 1.58112 2.51869 + vertex 1.66819 1.58217 2.5206 + vertex 1.66822 1.57743 2.52051 + endloop + endfacet + facet normal 0.902928 -0.00157513 0.429789 + outer loop + vertex 1.66819 1.58217 2.5206 + vertex 1.66693 1.57898 2.52323 + vertex 1.66822 1.57743 2.52051 + endloop + endfacet + facet normal 0.904946 -0.00591839 0.425485 + outer loop + vertex 1.66691 1.58401 2.52334 + vertex 1.66693 1.57898 2.52323 + vertex 1.66819 1.58217 2.5206 + endloop + endfacet + facet normal 0.192004 0.0640185 0.979304 + outer loop + vertex 1.67 1.585 2.51819 + vertex 1.66871 1.58578 2.51839 + vertex 1.66873 1.58112 2.51869 + endloop + endfacet + facet normal 0.186758 0.0549098 0.98087 + outer loop + vertex 1.67 1.585 2.51819 + vertex 1.67 1.59 2.51791 + vertex 1.66871 1.58578 2.51839 + endloop + endfacet + facet normal 0.881681 0.0540425 -0.46874 + outer loop + vertex 1.67333 1.58413 2.51229 + vertex 1.67302 1.58782 2.51213 + vertex 1.67472 1.585 2.515 + endloop + endfacet + facet normal 0.910759 0.162118 -0.379783 + outer loop + vertex 1.67302 1.58782 2.51213 + vertex 1.67383 1.59 2.515 + vertex 1.67472 1.585 2.515 + endloop + endfacet + facet normal 0.964529 0.0204561 0.263182 + outer loop + vertex 1.66873 1.58112 2.51869 + vertex 1.66871 1.58578 2.51839 + vertex 1.66819 1.58217 2.5206 + endloop + endfacet + facet normal 0.964906 0.0195925 0.261862 + outer loop + vertex 1.66871 1.58578 2.51839 + vertex 1.66809 1.58735 2.52056 + vertex 1.66819 1.58217 2.5206 + endloop + endfacet + facet normal 0.91134 0.0197325 0.411181 + outer loop + vertex 1.66809 1.58735 2.52056 + vertex 1.66691 1.58401 2.52334 + vertex 1.66819 1.58217 2.5206 + endloop + endfacet + facet normal 0.919607 0.00161172 0.392836 + outer loop + vertex 1.66687 1.58917 2.52341 + vertex 1.66691 1.58401 2.52334 + vertex 1.66809 1.58735 2.52056 + endloop + endfacet + facet normal 0.1911 0.0535017 0.980111 + outer loop + vertex 1.67 1.59 2.51791 + vertex 1.66866 1.59124 2.5181 + vertex 1.66871 1.58578 2.51839 + endloop + endfacet + facet normal 0.141012 -0.0019827 0.990006 + outer loop + vertex 1.67 1.59 2.51791 + vertex 1.67 1.595 2.51792 + vertex 1.66866 1.59124 2.5181 + endloop + endfacet + facet normal 0.943254 0.0754939 -0.323378 + outer loop + vertex 1.67302 1.58782 2.51213 + vertex 1.67258 1.59333 2.51213 + vertex 1.67383 1.59 2.515 + endloop + endfacet + facet normal 0.926484 0.0240992 -0.375561 + outer loop + vertex 1.67258 1.59333 2.51213 + vertex 1.6737 1.595 2.515 + vertex 1.67383 1.59 2.515 + endloop + endfacet + facet normal 0.965445 0.0229272 0.259595 + outer loop + vertex 1.66871 1.58578 2.51839 + vertex 1.66866 1.59124 2.5181 + vertex 1.66809 1.58735 2.52056 + endloop + endfacet + facet normal 0.969525 0.0128762 0.244652 + outer loop + vertex 1.66866 1.59124 2.5181 + vertex 1.66807 1.59285 2.52037 + vertex 1.66809 1.58735 2.52056 + endloop + endfacet + facet normal 0.92312 0.0176563 0.384107 + outer loop + vertex 1.66807 1.59285 2.52037 + vertex 1.66687 1.58917 2.52341 + vertex 1.66809 1.58735 2.52056 + endloop + endfacet + facet normal 0.932436 -0.00424888 0.36131 + outer loop + vertex 1.66688 1.59432 2.52344 + vertex 1.66687 1.58917 2.52341 + vertex 1.66807 1.59285 2.52037 + endloop + endfacet + facet normal -0.267386 0.14169 0.953115 + outer loop + vertex 1.67 1.595 2.51792 + vertex 1.66885 1.59753 2.51722 + vertex 1.66866 1.59124 2.5181 + endloop + endfacet + facet normal -0.52198 -0.00170823 0.852956 + outer loop + vertex 1.67 1.595 2.51792 + vertex 1.67 1.6 2.51793 + vertex 1.66885 1.59753 2.51722 + endloop + endfacet + facet normal 0.890505 0.144298 -0.431485 + outer loop + vertex 1.67258 1.59333 2.51213 + vertex 1.67175 1.5996 2.51251 + vertex 1.6737 1.595 2.515 + endloop + endfacet + facet normal 0.800776 0.0160182 -0.59875 + outer loop + vertex 1.67175 1.5996 2.51251 + vertex 1.6736 1.6 2.515 + vertex 1.6737 1.595 2.515 + endloop + endfacet + facet normal 0.96844 0.0061032 0.249173 + outer loop + vertex 1.66866 1.59124 2.5181 + vertex 1.66885 1.59753 2.51722 + vertex 1.66807 1.59285 2.52037 + endloop + endfacet + facet normal 0.973529 -0.0087081 0.228397 + outer loop + vertex 1.66885 1.59753 2.51722 + vertex 1.66819 1.5982 2.52007 + vertex 1.66807 1.59285 2.52037 + endloop + endfacet + facet normal 0.933036 -0.000582254 0.359782 + outer loop + vertex 1.66819 1.5982 2.52007 + vertex 1.66688 1.59432 2.52344 + vertex 1.66807 1.59285 2.52037 + endloop + endfacet + facet normal 0.935547 -0.00720657 0.353129 + outer loop + vertex 1.66693 1.59934 2.52343 + vertex 1.66688 1.59432 2.52344 + vertex 1.66819 1.5982 2.52007 + endloop + endfacet + facet normal 0.942042 0.19307 0.274373 + outer loop + vertex 1.67175 1.5996 2.51251 + vertex 1.67057 1.60491 2.51285 + vertex 1.67 1.60461 2.515 + endloop + endfacet + facet normal 0.650327 0.507854 -0.564942 + outer loop + vertex 1.67175 1.5996 2.51251 + vertex 1.67 1.60461 2.515 + vertex 1.6736 1.6 2.515 + endloop + endfacet + facet normal -0.915654 0.35302 -0.192236 + outer loop + vertex 1.67057 1.60491 2.51285 + vertex 1.6691 1.60288 2.51611 + vertex 1.67 1.60461 2.515 + endloop + endfacet + facet normal -0.857992 0.275527 0.433514 + outer loop + vertex 1.67 1.6 2.51793 + vertex 1.67 1.60461 2.515 + vertex 1.66885 1.59753 2.51722 + endloop + endfacet + facet normal 0.671258 0.12031 0.731394 + outer loop + vertex 1.6691 1.60288 2.51611 + vertex 1.66885 1.59753 2.51722 + vertex 1.67 1.60461 2.515 + endloop + endfacet + facet normal 0.974073 0.00105188 0.226233 + outer loop + vertex 1.66885 1.59753 2.51722 + vertex 1.6691 1.60288 2.51611 + vertex 1.66819 1.5982 2.52007 + endloop + endfacet + facet normal 0.979368 -0.0213911 0.20095 + outer loop + vertex 1.6691 1.60288 2.51611 + vertex 1.66832 1.60303 2.51995 + vertex 1.66819 1.5982 2.52007 + endloop + endfacet + facet normal 0.934436 -0.0161823 0.355763 + outer loop + vertex 1.66832 1.60303 2.51995 + vertex 1.66693 1.59934 2.52343 + vertex 1.66819 1.5982 2.52007 + endloop + endfacet + facet normal 0.937642 -0.0259993 0.346629 + outer loop + vertex 1.66705 1.60424 2.52347 + vertex 1.66693 1.59934 2.52343 + vertex 1.66832 1.60303 2.51995 + endloop + endfacet + facet normal 0.837327 -0.0357465 0.545533 + outer loop + vertex 1.66911 1.60703 2.51636 + vertex 1.6691 1.60288 2.51611 + vertex 1.67 1.60701 2.515 + endloop + endfacet + facet normal 0.829586 -0.135823 0.541607 + outer loop + vertex 1.66911 1.60703 2.51636 + vertex 1.67 1.60701 2.515 + vertex 1.67 1.61 2.51575 + endloop + endfacet + facet normal 0.930206 -0.108312 0.350692 + outer loop + vertex 1.6691 1.60288 2.51611 + vertex 1.67057 1.60491 2.51285 + vertex 1.67 1.60701 2.515 + endloop + endfacet + facet normal 0.95961 -0.279213 -0.0344837 + outer loop + vertex 1.67087 1.61 2.515 + vertex 1.67 1.60701 2.515 + vertex 1.67062 1.6094 2.51284 + endloop + endfacet + facet normal 0.964468 -0.0105274 0.263991 + outer loop + vertex 1.67057 1.60491 2.51285 + vertex 1.67062 1.6094 2.51284 + vertex 1.67 1.60701 2.515 + endloop + endfacet + facet normal 0.979526 -0.0152023 0.200745 + outer loop + vertex 1.6691 1.60288 2.51611 + vertex 1.66911 1.60703 2.51636 + vertex 1.66832 1.60303 2.51995 + endloop + endfacet + facet normal 0.987032 -0.0652807 0.146652 + outer loop + vertex 1.66911 1.60703 2.51636 + vertex 1.66858 1.60759 2.52019 + vertex 1.66832 1.60303 2.51995 + endloop + endfacet + facet normal 0.930011 -0.07347 0.360113 + outer loop + vertex 1.66858 1.60759 2.52019 + vertex 1.66705 1.60424 2.52347 + vertex 1.66832 1.60303 2.51995 + endloop + endfacet + facet normal 0.920968 -0.042723 0.38729 + outer loop + vertex 1.66721 1.60918 2.52364 + vertex 1.66705 1.60424 2.52347 + vertex 1.66858 1.60759 2.52019 + endloop + endfacet + facet normal 0.873477 -0.234215 0.426827 + outer loop + vertex 1.67062 1.6094 2.51284 + vertex 1.67115 1.61362 2.51406 + vertex 1.67 1.61103 2.515 + endloop + endfacet + facet normal 0.737555 0.622995 -0.260558 + outer loop + vertex 1.67062 1.6094 2.51284 + vertex 1.67 1.61103 2.515 + vertex 1.67087 1.61 2.515 + endloop + endfacet + facet normal 0.92058 -0.383464 0.0740764 + outer loop + vertex 1.67115 1.61362 2.51406 + vertex 1.66976 1.61083 2.517 + vertex 1.67 1.61103 2.515 + endloop + endfacet + facet normal -0.817426 0.339031 0.465696 + outer loop + vertex 1.67 1.61 2.51575 + vertex 1.67 1.61103 2.515 + vertex 1.66911 1.60703 2.51636 + endloop + endfacet + facet normal 0.978073 -0.181864 0.101483 + outer loop + vertex 1.66976 1.61083 2.517 + vertex 1.66911 1.60703 2.51636 + vertex 1.67 1.61103 2.515 + endloop + endfacet + facet normal 0.968184 -0.190405 0.162374 + outer loop + vertex 1.66911 1.60703 2.51636 + vertex 1.66976 1.61083 2.517 + vertex 1.66858 1.60759 2.52019 + endloop + endfacet + facet normal 0.964 -0.110544 0.241833 + outer loop + vertex 1.66976 1.61083 2.517 + vertex 1.66901 1.61244 2.52071 + vertex 1.66858 1.60759 2.52019 + endloop + endfacet + facet normal 0.900665 -0.123373 0.416631 + outer loop + vertex 1.66901 1.61244 2.52071 + vertex 1.66721 1.60918 2.52364 + vertex 1.66858 1.60759 2.52019 + endloop + endfacet + facet normal 0.873733 -0.0477443 0.484056 + outer loop + vertex 1.66731 1.61406 2.52394 + vertex 1.66721 1.60918 2.52364 + vertex 1.66901 1.61244 2.52071 + endloop + endfacet + facet normal 0.948541 -0.1875 0.255174 + outer loop + vertex 1.67115 1.61362 2.51406 + vertex 1.67206 1.61919 2.51478 + vertex 1.67061 1.61571 2.51761 + endloop + endfacet + facet normal 0.944683 -0.198508 0.261092 + outer loop + vertex 1.66976 1.61083 2.517 + vertex 1.67115 1.61362 2.51406 + vertex 1.67061 1.61571 2.51761 + endloop + endfacet + facet normal 0.940292 -0.199557 0.275731 + outer loop + vertex 1.66976 1.61083 2.517 + vertex 1.67061 1.61571 2.51761 + vertex 1.66901 1.61244 2.52071 + endloop + endfacet + facet normal 0.915842 -0.0752576 0.394424 + outer loop + vertex 1.67061 1.61571 2.51761 + vertex 1.66914 1.61785 2.52143 + vertex 1.66901 1.61244 2.52071 + endloop + endfacet + facet normal 0.862557 -0.087795 0.498284 + outer loop + vertex 1.66914 1.61785 2.52143 + vertex 1.66731 1.61406 2.52394 + vertex 1.66901 1.61244 2.52071 + endloop + endfacet + facet normal 0.829083 -0.0318818 0.558217 + outer loop + vertex 1.66716 1.61786 2.52438 + vertex 1.66731 1.61406 2.52394 + vertex 1.66914 1.61785 2.52143 + endloop + endfacet + facet normal 0.933705 -0.101599 0.343325 + outer loop + vertex 1.67206 1.61919 2.51478 + vertex 1.67236 1.62321 2.51515 + vertex 1.67105 1.62123 2.51813 + endloop + endfacet + facet normal 0.932126 -0.106803 0.346026 + outer loop + vertex 1.67061 1.61571 2.51761 + vertex 1.67206 1.61919 2.51478 + vertex 1.67105 1.62123 2.51813 + endloop + endfacet + facet normal 0.905254 -0.110752 0.410182 + outer loop + vertex 1.67061 1.61571 2.51761 + vertex 1.67105 1.62123 2.51813 + vertex 1.66914 1.61785 2.52143 + endloop + endfacet + facet normal 0.889127 -0.0590559 0.453835 + outer loop + vertex 1.67105 1.62123 2.51813 + vertex 1.66965 1.62176 2.52095 + vertex 1.66914 1.61785 2.52143 + endloop + endfacet + facet normal 0.744501 0.020997 0.667291 + outer loop + vertex 1.66716 1.61786 2.52438 + vertex 1.6678 1.62177 2.52354 + vertex 1.66569 1.61961 2.52596 + endloop + endfacet + facet normal 0.829428 -0.0163087 0.558376 + outer loop + vertex 1.66716 1.61786 2.52438 + vertex 1.66914 1.61785 2.52143 + vertex 1.6678 1.62177 2.52354 + endloop + endfacet + facet normal 0.81347 -0.033761 0.580626 + outer loop + vertex 1.66914 1.61785 2.52143 + vertex 1.66965 1.62176 2.52095 + vertex 1.6678 1.62177 2.52354 + endloop + endfacet + facet normal 0.741728 0.0269015 0.670161 + outer loop + vertex 1.6678 1.62177 2.52354 + vertex 1.66497 1.6235 2.5266 + vertex 1.66569 1.61961 2.52596 + endloop + endfacet + facet normal 0.925773 -0.0487959 0.374918 + outer loop + vertex 1.67236 1.62321 2.51515 + vertex 1.6718 1.62503 2.51678 + vertex 1.67105 1.62123 2.51813 + endloop + endfacet + facet normal 0.884434 0.0170597 0.466353 + outer loop + vertex 1.6718 1.62503 2.51678 + vertex 1.67183 1.6278 2.51661 + vertex 1.66992 1.62613 2.5203 + endloop + endfacet + facet normal 0.881592 -0.00566468 0.471979 + outer loop + vertex 1.6718 1.62503 2.51678 + vertex 1.66992 1.62613 2.5203 + vertex 1.67105 1.62123 2.51813 + endloop + endfacet + facet normal 0.895904 0.0099386 0.444136 + outer loop + vertex 1.67105 1.62123 2.51813 + vertex 1.66992 1.62613 2.5203 + vertex 1.66965 1.62176 2.52095 + endloop + endfacet + facet normal 0.828245 0.000788957 0.560366 + outer loop + vertex 1.66729 1.62563 2.52419 + vertex 1.66992 1.62613 2.5203 + vertex 1.66761 1.62944 2.52371 + endloop + endfacet + facet normal 0.827327 0.0146114 0.561531 + outer loop + vertex 1.66729 1.62563 2.52419 + vertex 1.6678 1.62177 2.52354 + vertex 1.66992 1.62613 2.5203 + endloop + endfacet + facet normal 0.813547 0.035369 0.580423 + outer loop + vertex 1.6678 1.62177 2.52354 + vertex 1.66965 1.62176 2.52095 + vertex 1.66992 1.62613 2.5203 + endloop + endfacet + facet normal 0.728938 -0.019224 0.68431 + outer loop + vertex 1.6678 1.62177 2.52354 + vertex 1.66729 1.62563 2.52419 + vertex 1.66497 1.6235 2.5266 + endloop + endfacet + facet normal 0.926796 0.027115 0.374586 + outer loop + vertex 1.6724 1.63041 2.51493 + vertex 1.67233 1.63429 2.51482 + vertex 1.67137 1.63089 2.51745 + endloop + endfacet + facet normal 0.927221 0.0388189 0.372498 + outer loop + vertex 1.67183 1.6278 2.51661 + vertex 1.6724 1.63041 2.51493 + vertex 1.67137 1.63089 2.51745 + endloop + endfacet + facet normal 0.886218 0.0080306 0.463199 + outer loop + vertex 1.67183 1.6278 2.51661 + vertex 1.67137 1.63089 2.51745 + vertex 1.66992 1.62613 2.5203 + endloop + endfacet + facet normal 0.88001 0.0167597 0.474658 + outer loop + vertex 1.66992 1.62613 2.5203 + vertex 1.67137 1.63089 2.51745 + vertex 1.66957 1.63212 2.52075 + endloop + endfacet + facet normal 0.83135 0.00778509 0.555695 + outer loop + vertex 1.66957 1.63212 2.52075 + vertex 1.66761 1.62944 2.52371 + vertex 1.66992 1.62613 2.5203 + endloop + endfacet + facet normal 0.822383 0.0281328 0.568239 + outer loop + vertex 1.6674 1.63418 2.52378 + vertex 1.66761 1.62944 2.52371 + vertex 1.66957 1.63212 2.52075 + endloop + endfacet + facet normal 0.925378 -0.00595308 0.379 + outer loop + vertex 1.67233 1.63429 2.51482 + vertex 1.6723 1.63907 2.51497 + vertex 1.67112 1.63554 2.51779 + endloop + endfacet + facet normal 0.929237 0.0219692 0.36883 + outer loop + vertex 1.67137 1.63089 2.51745 + vertex 1.67233 1.63429 2.51482 + vertex 1.67112 1.63554 2.51779 + endloop + endfacet + facet normal 0.879263 0.0115453 0.476196 + outer loop + vertex 1.67137 1.63089 2.51745 + vertex 1.67112 1.63554 2.51779 + vertex 1.66957 1.63212 2.52075 + endloop + endfacet + facet normal 0.876767 0.0165115 0.480631 + outer loop + vertex 1.67112 1.63554 2.51779 + vertex 1.66931 1.63705 2.52105 + vertex 1.66957 1.63212 2.52075 + endloop + endfacet + facet normal 0.816146 0.00745805 0.577797 + outer loop + vertex 1.66931 1.63705 2.52105 + vertex 1.6674 1.63418 2.52378 + vertex 1.66957 1.63212 2.52075 + endloop + endfacet + facet normal 0.805375 0.0282368 0.592093 + outer loop + vertex 1.66718 1.63896 2.52386 + vertex 1.6674 1.63418 2.52378 + vertex 1.66931 1.63705 2.52105 + endloop + endfacet + facet normal 0.91512 -0.0464497 0.400498 + outer loop + vertex 1.6723 1.63907 2.51497 + vertex 1.67238 1.643 2.51523 + vertex 1.67097 1.64075 2.51821 + endloop + endfacet + facet normal 0.924257 -0.00337322 0.381757 + outer loop + vertex 1.67112 1.63554 2.51779 + vertex 1.6723 1.63907 2.51497 + vertex 1.67097 1.64075 2.51821 + endloop + endfacet + facet normal 0.87086 -0.0136508 0.491342 + outer loop + vertex 1.67112 1.63554 2.51779 + vertex 1.67097 1.64075 2.51821 + vertex 1.66931 1.63705 2.52105 + endloop + endfacet + facet normal 0.857019 0.0108385 0.515171 + outer loop + vertex 1.67097 1.64075 2.51821 + vertex 1.66898 1.64116 2.52151 + vertex 1.66931 1.63705 2.52105 + endloop + endfacet + facet normal 0.795121 -0.00436743 0.606435 + outer loop + vertex 1.66898 1.64116 2.52151 + vertex 1.66718 1.63896 2.52386 + vertex 1.66931 1.63705 2.52105 + endloop + endfacet + facet normal 0.783553 0.0207248 0.62098 + outer loop + vertex 1.66719 1.64366 2.52369 + vertex 1.66718 1.63896 2.52386 + vertex 1.66898 1.64116 2.52151 + endloop + endfacet + facet normal 0.917331 -0.0562751 0.394129 + outer loop + vertex 1.67238 1.643 2.51523 + vertex 1.67174 1.64496 2.51701 + vertex 1.67097 1.64075 2.51821 + endloop + endfacet + facet normal 0.858859 -0.043237 0.510384 + outer loop + vertex 1.67174 1.64496 2.51701 + vertex 1.67166 1.64902 2.51749 + vertex 1.66978 1.64549 2.52036 + endloop + endfacet + facet normal 0.86163 -0.0139016 0.507346 + outer loop + vertex 1.67174 1.64496 2.51701 + vertex 1.66978 1.64549 2.52036 + vertex 1.67097 1.64075 2.51821 + endloop + endfacet + facet normal 0.855217 -0.0202848 0.517873 + outer loop + vertex 1.67097 1.64075 2.51821 + vertex 1.66978 1.64549 2.52036 + vertex 1.66898 1.64116 2.52151 + endloop + endfacet + facet normal 0.783369 0.0203825 0.621223 + outer loop + vertex 1.66978 1.64549 2.52036 + vertex 1.66719 1.64366 2.52369 + vertex 1.66898 1.64116 2.52151 + endloop + endfacet + facet normal 0.786331 0.009821 0.617727 + outer loop + vertex 1.66726 1.64855 2.52351 + vertex 1.66719 1.64366 2.52369 + vertex 1.66978 1.64549 2.52036 + endloop + endfacet + facet normal 0.840812 -0.0440138 0.539535 + outer loop + vertex 1.67166 1.64902 2.51749 + vertex 1.67164 1.6539 2.51792 + vertex 1.66968 1.65094 2.52074 + endloop + endfacet + facet normal 0.847621 -0.021168 0.53018 + outer loop + vertex 1.66978 1.64549 2.52036 + vertex 1.67166 1.64902 2.51749 + vertex 1.66968 1.65094 2.52074 + endloop + endfacet + facet normal 0.766775 -0.0305449 0.641189 + outer loop + vertex 1.66968 1.65094 2.52074 + vertex 1.66726 1.64855 2.52351 + vertex 1.66978 1.64549 2.52036 + endloop + endfacet + facet normal 0.75532 -0.00256222 0.655352 + outer loop + vertex 1.6672 1.65354 2.5236 + vertex 1.66726 1.64855 2.52351 + vertex 1.66968 1.65094 2.52074 + endloop + endfacet + facet normal 0.827476 -0.0192587 0.561171 + outer loop + vertex 1.67164 1.6539 2.51792 + vertex 1.6716 1.6588 2.51814 + vertex 1.66962 1.65591 2.52097 + endloop + endfacet + facet normal 0.828415 -0.0163621 0.559876 + outer loop + vertex 1.66968 1.65094 2.52074 + vertex 1.67164 1.6539 2.51792 + vertex 1.66962 1.65591 2.52097 + endloop + endfacet + facet normal 0.746298 -0.0220473 0.665247 + outer loop + vertex 1.66962 1.65591 2.52097 + vertex 1.6672 1.65354 2.5236 + vertex 1.66968 1.65094 2.52074 + endloop + endfacet + facet normal 0.734501 0.00489185 0.67859 + outer loop + vertex 1.66712 1.65847 2.52366 + vertex 1.6672 1.65354 2.5236 + vertex 1.66962 1.65591 2.52097 + endloop + endfacet + facet normal 0.821454 0.018059 0.569988 + outer loop + vertex 1.6716 1.6588 2.51814 + vertex 1.67149 1.66381 2.51814 + vertex 1.66955 1.66082 2.52103 + endloop + endfacet + facet normal 0.816803 0.00339627 0.576907 + outer loop + vertex 1.66962 1.65591 2.52097 + vertex 1.6716 1.6588 2.51814 + vertex 1.66955 1.66082 2.52103 + endloop + endfacet + facet normal 0.732577 0.000802164 0.680684 + outer loop + vertex 1.66955 1.66082 2.52103 + vertex 1.66712 1.65847 2.52366 + vertex 1.66962 1.65591 2.52097 + endloop + endfacet + facet normal 0.724528 0.0184315 0.688999 + outer loop + vertex 1.66703 1.66337 2.52361 + vertex 1.66712 1.65847 2.52366 + vertex 1.66955 1.66082 2.52103 + endloop + endfacet + facet normal 0.821068 0.0355586 0.569722 + outer loop + vertex 1.67149 1.66381 2.51814 + vertex 1.67136 1.6689 2.51802 + vertex 1.66944 1.66579 2.52098 + endloop + endfacet + facet normal 0.817904 0.0250166 0.57481 + outer loop + vertex 1.66955 1.66082 2.52103 + vertex 1.67149 1.66381 2.51814 + vertex 1.66944 1.66579 2.52098 + endloop + endfacet + facet normal 0.727251 0.0242054 0.685945 + outer loop + vertex 1.66944 1.66579 2.52098 + vertex 1.66703 1.66337 2.52361 + vertex 1.66955 1.66082 2.52103 + endloop + endfacet + facet normal 0.726746 0.0252499 0.686442 + outer loop + vertex 1.66696 1.66827 2.52351 + vertex 1.66703 1.66337 2.52361 + vertex 1.66944 1.66579 2.52098 + endloop + endfacet + facet normal 0.823716 0.0341532 0.565973 + outer loop + vertex 1.67136 1.6689 2.51802 + vertex 1.67125 1.67404 2.51786 + vertex 1.66931 1.67084 2.52088 + endloop + endfacet + facet normal 0.823047 0.0318141 0.567081 + outer loop + vertex 1.66944 1.66579 2.52098 + vertex 1.67136 1.6689 2.51802 + vertex 1.66931 1.67084 2.52088 + endloop + endfacet + facet normal 0.729688 0.0316808 0.683046 + outer loop + vertex 1.66931 1.67084 2.52088 + vertex 1.66696 1.66827 2.52351 + vertex 1.66944 1.66579 2.52098 + endloop + endfacet + facet normal 0.732428 0.0263903 0.680333 + outer loop + vertex 1.66686 1.67322 2.52343 + vertex 1.66696 1.66827 2.52351 + vertex 1.66931 1.67084 2.52088 + endloop + endfacet + facet normal 0.821768 0.0205931 0.56945 + outer loop + vertex 1.67125 1.67404 2.51786 + vertex 1.6712 1.67912 2.51776 + vertex 1.66919 1.67598 2.52077 + endloop + endfacet + facet normal 0.824976 0.031784 0.564273 + outer loop + vertex 1.66931 1.67084 2.52088 + vertex 1.67125 1.67404 2.51786 + vertex 1.66919 1.67598 2.52077 + endloop + endfacet + facet normal 0.73483 0.0318809 0.677502 + outer loop + vertex 1.66919 1.67598 2.52077 + vertex 1.66686 1.67322 2.52343 + vertex 1.66931 1.67084 2.52088 + endloop + endfacet + facet normal 0.736174 0.0294422 0.676152 + outer loop + vertex 1.66675 1.67832 2.52332 + vertex 1.66686 1.67322 2.52343 + vertex 1.66919 1.67598 2.52077 + endloop + endfacet + facet normal 0.811621 0.0189465 0.583877 + outer loop + vertex 1.6712 1.67912 2.51776 + vertex 1.67116 1.68412 2.51764 + vertex 1.66908 1.68115 2.52064 + endloop + endfacet + facet normal 0.815737 0.0321935 0.577526 + outer loop + vertex 1.66919 1.67598 2.52077 + vertex 1.6712 1.67912 2.51776 + vertex 1.66908 1.68115 2.52064 + endloop + endfacet + facet normal 0.737748 0.0331244 0.674263 + outer loop + vertex 1.66908 1.68115 2.52064 + vertex 1.66675 1.67832 2.52332 + vertex 1.66919 1.67598 2.52077 + endloop + endfacet + facet normal 0.734828 0.0382715 0.677173 + outer loop + vertex 1.66666 1.68345 2.52313 + vertex 1.66675 1.67832 2.52332 + vertex 1.66908 1.68115 2.52064 + endloop + endfacet + facet normal 0.796963 0.0342341 0.603058 + outer loop + vertex 1.67116 1.68412 2.51764 + vertex 1.67108 1.68907 2.51747 + vertex 1.66896 1.68624 2.52043 + endloop + endfacet + facet normal 0.799687 0.0425107 0.598911 + outer loop + vertex 1.66908 1.68115 2.52064 + vertex 1.67116 1.68412 2.51764 + vertex 1.66896 1.68624 2.52043 + endloop + endfacet + facet normal 0.737254 0.0440697 0.674177 + outer loop + vertex 1.66896 1.68624 2.52043 + vertex 1.66666 1.68345 2.52313 + vertex 1.66908 1.68115 2.52064 + endloop + endfacet + facet normal 0.732173 0.0529681 0.679056 + outer loop + vertex 1.66655 1.68837 2.52286 + vertex 1.66666 1.68345 2.52313 + vertex 1.66896 1.68624 2.52043 + endloop + endfacet + facet normal 0.783031 0.040266 0.620677 + outer loop + vertex 1.67108 1.68907 2.51747 + vertex 1.67086 1.69391 2.51743 + vertex 1.66877 1.69101 2.52026 + endloop + endfacet + facet normal 0.787024 0.0537969 0.614573 + outer loop + vertex 1.66896 1.68624 2.52043 + vertex 1.67108 1.68907 2.51747 + vertex 1.66877 1.69101 2.52026 + endloop + endfacet + facet normal 0.732605 0.0540872 0.678501 + outer loop + vertex 1.66877 1.69101 2.52026 + vertex 1.66655 1.68837 2.52286 + vertex 1.66896 1.68624 2.52043 + endloop + endfacet + facet normal 0.72648 0.0648256 0.684123 + outer loop + vertex 1.66645 1.69274 2.52256 + vertex 1.66655 1.68837 2.52286 + vertex 1.66877 1.69101 2.52026 + endloop + endfacet + facet normal 0.766599 0.0345363 0.641196 + outer loop + vertex 1.67086 1.69391 2.51743 + vertex 1.67036 1.69908 2.51775 + vertex 1.66835 1.69519 2.52037 + endloop + endfacet + facet normal 0.771238 0.0612758 0.633591 + outer loop + vertex 1.66877 1.69101 2.52026 + vertex 1.67086 1.69391 2.51743 + vertex 1.66835 1.69519 2.52037 + endloop + endfacet + facet normal 0.723296 0.0549319 0.68835 + outer loop + vertex 1.66835 1.69519 2.52037 + vertex 1.66645 1.69274 2.52256 + vertex 1.66877 1.69101 2.52026 + endloop + endfacet + facet normal 0.718987 0.0618131 0.692269 + outer loop + vertex 1.66649 1.69551 2.52227 + vertex 1.66645 1.69274 2.52256 + vertex 1.66835 1.69519 2.52037 + endloop + endfacet + facet normal 0.73304 0.0752112 0.676015 + outer loop + vertex 1.6668 1.69861 2.52167 + vertex 1.66835 1.69519 2.52037 + vertex 1.67036 1.69908 2.51775 + endloop + endfacet + facet normal 0.738877 0.0124966 0.673725 + outer loop + vertex 1.6668 1.69861 2.52167 + vertex 1.67036 1.69908 2.51775 + vertex 1.66857 1.70361 2.51964 + endloop + endfacet + facet normal 0.748455 0.0208161 0.662859 + outer loop + vertex 1.66857 1.70361 2.51964 + vertex 1.67036 1.69908 2.51775 + vertex 1.67134 1.70367 2.51651 + endloop + endfacet + facet normal 0.719021 0.0626935 0.692155 + outer loop + vertex 1.66835 1.69519 2.52037 + vertex 1.6668 1.69861 2.52167 + vertex 1.66649 1.69551 2.52227 + endloop + endfacet + facet normal 0.74879 0.00108707 0.662806 + outer loop + vertex 1.67134 1.70367 2.51651 + vertex 1.67101 1.70768 2.51687 + vertex 1.66857 1.70361 2.51964 + endloop + endfacet + facet normal 0.733866 0.0210729 0.678967 + outer loop + vertex 1.66857 1.70361 2.51964 + vertex 1.67101 1.70768 2.51687 + vertex 1.66844 1.70902 2.5196 + endloop + endfacet + facet normal 0.72991 0.00420992 0.68353 + outer loop + vertex 1.67101 1.70768 2.51687 + vertex 1.67078 1.71264 2.51708 + vertex 1.66844 1.70902 2.5196 + endloop + endfacet + facet normal 0.715763 0.0233729 0.697952 + outer loop + vertex 1.66844 1.70902 2.5196 + vertex 1.67078 1.71264 2.51708 + vertex 1.66822 1.71409 2.51966 + endloop + endfacet + facet normal 0.710031 0.00210447 0.704167 + outer loop + vertex 1.67078 1.71264 2.51708 + vertex 1.67043 1.71803 2.51743 + vertex 1.66822 1.71409 2.51966 + endloop + endfacet + facet normal 0.691769 0.0223436 0.721773 + outer loop + vertex 1.66822 1.71409 2.51966 + vertex 1.67043 1.71803 2.51743 + vertex 1.66782 1.71844 2.51991 + endloop + endfacet + facet normal 0.750342 -0.0048046 0.661032 + outer loop + vertex 1.6725 1.71995 2.51518 + vertex 1.67273 1.72263 2.51494 + vertex 1.67127 1.72167 2.51659 + endloop + endfacet + facet normal 0.742369 -0.0176136 0.66976 + outer loop + vertex 1.67127 1.72167 2.51659 + vertex 1.67043 1.71803 2.51743 + vertex 1.6725 1.71995 2.51518 + endloop + endfacet + facet normal 0.68188 0.0105729 0.731387 + outer loop + vertex 1.67127 1.72167 2.51659 + vertex 1.66884 1.72325 2.51883 + vertex 1.67043 1.71803 2.51743 + endloop + endfacet + facet normal 0.691316 0.0158683 0.722378 + outer loop + vertex 1.66884 1.72325 2.51883 + vertex 1.66782 1.71844 2.51991 + vertex 1.67043 1.71803 2.51743 + endloop + endfacet + facet normal 0.744436 0.0153574 0.667517 + outer loop + vertex 1.67273 1.72263 2.51494 + vertex 1.67141 1.72435 2.51637 + vertex 1.67127 1.72167 2.51659 + endloop + endfacet + facet normal 0.686109 0.0231606 0.72713 + outer loop + vertex 1.67141 1.72435 2.51637 + vertex 1.66884 1.72325 2.51883 + vertex 1.67127 1.72167 2.51659 + endloop + endfacet + facet normal 0.686399 0.0219597 0.726894 + outer loop + vertex 1.67141 1.72435 2.51637 + vertex 1.6705 1.7281 2.51711 + vertex 1.66884 1.72325 2.51883 + endloop + endfacet + facet normal 0.671463 0.0318476 0.740354 + outer loop + vertex 1.6705 1.7281 2.51711 + vertex 1.66768 1.72826 2.51967 + vertex 1.66884 1.72325 2.51883 + endloop + endfacet + facet normal 0.726668 0.0329641 0.686198 + outer loop + vertex 1.67263 1.72994 2.51487 + vertex 1.67295 1.73357 2.51435 + vertex 1.67101 1.73206 2.51648 + endloop + endfacet + facet normal 0.718266 0.0194851 0.695496 + outer loop + vertex 1.67101 1.73206 2.51648 + vertex 1.6705 1.7281 2.51711 + vertex 1.67263 1.72994 2.51487 + endloop + endfacet + facet normal 0.669577 0.0331559 0.742002 + outer loop + vertex 1.67101 1.73206 2.51648 + vertex 1.66827 1.73283 2.51892 + vertex 1.6705 1.7281 2.51711 + endloop + endfacet + facet normal 0.671485 0.0347454 0.740203 + outer loop + vertex 1.66827 1.73283 2.51892 + vertex 1.66768 1.72826 2.51967 + vertex 1.6705 1.7281 2.51711 + endloop + endfacet + facet normal 0.713583 0.0350365 0.699694 + outer loop + vertex 1.67295 1.73357 2.51435 + vertex 1.67288 1.73818 2.51419 + vertex 1.67056 1.73596 2.51667 + endloop + endfacet + facet normal 0.720284 0.0492889 0.691926 + outer loop + vertex 1.67101 1.73206 2.51648 + vertex 1.67295 1.73357 2.51435 + vertex 1.67056 1.73596 2.51667 + endloop + endfacet + facet normal 0.670614 0.0411312 0.740665 + outer loop + vertex 1.67056 1.73596 2.51667 + vertex 1.66827 1.73283 2.51892 + vertex 1.67101 1.73206 2.51648 + endloop + endfacet + facet normal 0.66467 0.0489567 0.745532 + outer loop + vertex 1.66778 1.73833 2.51899 + vertex 1.66827 1.73283 2.51892 + vertex 1.67056 1.73596 2.51667 + endloop + endfacet + facet normal 0.700709 0.0340952 0.712632 + outer loop + vertex 1.67288 1.73818 2.51419 + vertex 1.67275 1.74316 2.51408 + vertex 1.67031 1.74083 2.51659 + endloop + endfacet + facet normal 0.707486 0.0474937 0.705129 + outer loop + vertex 1.67056 1.73596 2.51667 + vertex 1.67288 1.73818 2.51419 + vertex 1.67031 1.74083 2.51659 + endloop + endfacet + facet normal 0.663287 0.0459422 0.746954 + outer loop + vertex 1.67031 1.74083 2.51659 + vertex 1.66778 1.73833 2.51899 + vertex 1.67056 1.73596 2.51667 + endloop + endfacet + facet normal 0.659693 0.0522033 0.74972 + outer loop + vertex 1.66754 1.74337 2.51885 + vertex 1.66778 1.73833 2.51899 + vertex 1.67031 1.74083 2.51659 + endloop + endfacet + facet normal 0.686998 0.0251175 0.726226 + outer loop + vertex 1.67275 1.74316 2.51408 + vertex 1.67263 1.74822 2.51402 + vertex 1.67016 1.74586 2.51644 + endloop + endfacet + facet normal 0.696384 0.0426988 0.716398 + outer loop + vertex 1.67031 1.74083 2.51659 + vertex 1.67275 1.74316 2.51408 + vertex 1.67016 1.74586 2.51644 + endloop + endfacet + facet normal 0.654847 0.0426148 0.754559 + outer loop + vertex 1.67016 1.74586 2.51644 + vertex 1.66754 1.74337 2.51885 + vertex 1.67031 1.74083 2.51659 + endloop + endfacet + facet normal 0.650219 0.0508619 0.758042 + outer loop + vertex 1.66738 1.74837 2.51865 + vertex 1.66754 1.74337 2.51885 + vertex 1.67016 1.74586 2.51644 + endloop + endfacet + facet normal 0.672752 0.0243921 0.739465 + outer loop + vertex 1.67263 1.74822 2.51402 + vertex 1.67252 1.75328 2.51396 + vertex 1.67004 1.75089 2.51629 + endloop + endfacet + facet normal 0.680289 0.0380727 0.731955 + outer loop + vertex 1.67016 1.74586 2.51644 + vertex 1.67263 1.74822 2.51402 + vertex 1.67004 1.75089 2.51629 + endloop + endfacet + facet normal 0.643745 0.0381799 0.764287 + outer loop + vertex 1.67004 1.75089 2.51629 + vertex 1.66738 1.74837 2.51865 + vertex 1.67016 1.74586 2.51644 + endloop + endfacet + facet normal 0.636873 0.0501563 0.769336 + outer loop + vertex 1.66723 1.75333 2.51845 + vertex 1.66738 1.74837 2.51865 + vertex 1.67004 1.75089 2.51629 + endloop + endfacet + facet normal 0.660862 0.0321048 0.749821 + outer loop + vertex 1.67252 1.75328 2.51396 + vertex 1.67237 1.75834 2.51387 + vertex 1.66988 1.75591 2.51617 + endloop + endfacet + facet normal 0.664735 0.0391521 0.746053 + outer loop + vertex 1.67004 1.75089 2.51629 + vertex 1.67252 1.75328 2.51396 + vertex 1.66988 1.75591 2.51617 + endloop + endfacet + facet normal 0.631145 0.0387948 0.774694 + outer loop + vertex 1.66988 1.75591 2.51617 + vertex 1.66723 1.75333 2.51845 + vertex 1.67004 1.75089 2.51629 + endloop + endfacet + facet normal 0.620488 0.0563857 0.782186 + outer loop + vertex 1.66696 1.75833 2.51831 + vertex 1.66723 1.75333 2.51845 + vertex 1.66988 1.75591 2.51617 + endloop + endfacet + facet normal 0.649937 0.044468 0.758686 + outer loop + vertex 1.67237 1.75834 2.51387 + vertex 1.67222 1.7634 2.5137 + vertex 1.66965 1.76097 2.51604 + endloop + endfacet + facet normal 0.651838 0.0479613 0.75684 + outer loop + vertex 1.66988 1.75591 2.51617 + vertex 1.67237 1.75834 2.51387 + vertex 1.66965 1.76097 2.51604 + endloop + endfacet + facet normal 0.615867 0.0470248 0.786446 + outer loop + vertex 1.66965 1.76097 2.51604 + vertex 1.66696 1.75833 2.51831 + vertex 1.66988 1.75591 2.51617 + endloop + endfacet + facet normal 0.601553 0.0695931 0.795796 + outer loop + vertex 1.66639 1.76381 2.51826 + vertex 1.66696 1.75833 2.51831 + vertex 1.66965 1.76097 2.51604 + endloop + endfacet + facet normal 0.645299 0.0518267 0.76217 + outer loop + vertex 1.67222 1.7634 2.5137 + vertex 1.67208 1.76839 2.51348 + vertex 1.66957 1.76591 2.51578 + endloop + endfacet + facet normal 0.64554 0.0522756 0.761936 + outer loop + vertex 1.66965 1.76097 2.51604 + vertex 1.67222 1.7634 2.5137 + vertex 1.66957 1.76591 2.51578 + endloop + endfacet + facet normal 0.592896 0.0536311 0.803491 + outer loop + vertex 1.66957 1.76591 2.51578 + vertex 1.66639 1.76381 2.51826 + vertex 1.66965 1.76097 2.51604 + endloop + endfacet + facet normal 0.590461 0.0589738 0.804909 + outer loop + vertex 1.66719 1.76827 2.51735 + vertex 1.66639 1.76381 2.51826 + vertex 1.66957 1.76591 2.51578 + endloop + endfacet + facet normal 0.637008 0.0577807 0.768688 + outer loop + vertex 1.67208 1.76839 2.51348 + vertex 1.67188 1.77333 2.51328 + vertex 1.66941 1.77061 2.51552 + endloop + endfacet + facet normal 0.639108 0.062229 0.766595 + outer loop + vertex 1.66957 1.76591 2.51578 + vertex 1.67208 1.76839 2.51348 + vertex 1.66941 1.77061 2.51552 + endloop + endfacet + facet normal 0.592827 0.0626976 0.802885 + outer loop + vertex 1.66941 1.77061 2.51552 + vertex 1.66719 1.76827 2.51735 + vertex 1.66957 1.76591 2.51578 + endloop + endfacet + facet normal 0.571229 0.09301 0.815504 + outer loop + vertex 1.66635 1.7724 2.51747 + vertex 1.66719 1.76827 2.51735 + vertex 1.66941 1.77061 2.51552 + endloop + endfacet + facet normal 0.622296 0.0547772 0.780863 + outer loop + vertex 1.67188 1.77333 2.51328 + vertex 1.67158 1.77835 2.51316 + vertex 1.669 1.77538 2.51542 + endloop + endfacet + facet normal 0.628592 0.0702615 0.774555 + outer loop + vertex 1.66941 1.77061 2.51552 + vertex 1.67188 1.77333 2.51328 + vertex 1.669 1.77538 2.51542 + endloop + endfacet + facet normal 0.561203 0.0654496 0.825087 + outer loop + vertex 1.669 1.77538 2.51542 + vertex 1.66635 1.7724 2.51747 + vertex 1.66941 1.77061 2.51552 + endloop + endfacet + facet normal 0.543455 0.0879747 0.834816 + outer loop + vertex 1.66578 1.77725 2.51733 + vertex 1.66635 1.7724 2.51747 + vertex 1.669 1.77538 2.51542 + endloop + endfacet + facet normal 0.600981 0.0400929 0.798257 + outer loop + vertex 1.67158 1.77835 2.51316 + vertex 1.67116 1.78386 2.5132 + vertex 1.66852 1.78025 2.51537 + endloop + endfacet + facet normal 0.611731 0.0693875 0.788017 + outer loop + vertex 1.669 1.77538 2.51542 + vertex 1.67158 1.77835 2.51316 + vertex 1.66852 1.78025 2.51537 + endloop + endfacet + facet normal 0.533633 0.0622709 0.843421 + outer loop + vertex 1.66852 1.78025 2.51537 + vertex 1.66578 1.77725 2.51733 + vertex 1.669 1.77538 2.51542 + endloop + endfacet + facet normal 0.514084 0.0866164 0.853355 + outer loop + vertex 1.66508 1.78223 2.51724 + vertex 1.66578 1.77725 2.51733 + vertex 1.66852 1.78025 2.51537 + endloop + endfacet + facet normal 0.587621 0.0552633 0.807247 + outer loop + vertex 1.66805 1.78429 2.51544 + vertex 1.66852 1.78025 2.51537 + vertex 1.67116 1.78386 2.5132 + endloop + endfacet + facet normal 0.586188 0.0333141 0.80949 + outer loop + vertex 1.66805 1.78429 2.51544 + vertex 1.67116 1.78386 2.5132 + vertex 1.66906 1.78855 2.51453 + endloop + endfacet + facet normal 0.580196 0.0293811 0.813947 + outer loop + vertex 1.66906 1.78855 2.51453 + vertex 1.67116 1.78386 2.5132 + vertex 1.67212 1.78831 2.51236 + endloop + endfacet + facet normal 0.496681 0.0437175 0.866831 + outer loop + vertex 1.66852 1.78025 2.51537 + vertex 1.66805 1.78429 2.51544 + vertex 1.66508 1.78223 2.51724 + endloop + endfacet + facet normal 0.578845 -0.00046401 0.815438 + outer loop + vertex 1.67212 1.78831 2.51236 + vertex 1.67168 1.79237 2.51267 + vertex 1.66906 1.78855 2.51453 + endloop + endfacet + facet normal 0.539653 0.0388344 0.840991 + outer loop + vertex 1.66906 1.78855 2.51453 + vertex 1.67168 1.79237 2.51267 + vertex 1.66853 1.79387 2.51462 + endloop + endfacet + facet normal 0.530098 0.00970088 0.847881 + outer loop + vertex 1.67168 1.79237 2.51267 + vertex 1.67144 1.79722 2.51277 + vertex 1.66853 1.79387 2.51462 + endloop + endfacet + facet normal 0.488846 0.0579627 0.870442 + outer loop + vertex 1.66853 1.79387 2.51462 + vertex 1.67144 1.79722 2.51277 + vertex 1.66807 1.79892 2.51455 + endloop + endfacet + facet normal 0.481702 0.0385005 0.875489 + outer loop + vertex 1.67144 1.79722 2.51277 + vertex 1.67116 1.80221 2.5127 + vertex 1.66807 1.79892 2.51455 + endloop + endfacet + facet normal 0.438261 0.0897814 0.894353 + outer loop + vertex 1.66807 1.79892 2.51455 + vertex 1.67116 1.80221 2.5127 + vertex 1.66729 1.80432 2.51438 + endloop + endfacet + facet normal 0.429849 0.0697121 0.900205 + outer loop + vertex 1.67116 1.80221 2.5127 + vertex 1.67087 1.80711 2.51246 + vertex 1.66729 1.80432 2.51438 + endloop + endfacet + facet normal 0.414037 0.0936067 0.905434 + outer loop + vertex 1.66729 1.80432 2.51438 + vertex 1.67087 1.80711 2.51246 + vertex 1.66794 1.8088 2.51362 + endloop + endfacet + facet normal 0.416576 0.0992183 0.90367 + outer loop + vertex 1.67087 1.80711 2.51246 + vertex 1.67017 1.81204 2.51224 + vertex 1.66794 1.8088 2.51362 + endloop + endfacet + facet normal 0.373681 0.134583 0.917742 + outer loop + vertex 1.66794 1.8088 2.51362 + vertex 1.67017 1.81204 2.51224 + vertex 1.66656 1.81195 2.51372 + endloop + endfacet + facet normal 0.452757 0.119169 0.883635 + outer loop + vertex 1.67313 1.81398 2.51057 + vertex 1.67397 1.81821 2.50957 + vertex 1.67102 1.81615 2.51136 + endloop + endfacet + facet normal 0.43778 0.101071 0.893383 + outer loop + vertex 1.67102 1.81615 2.51136 + vertex 1.67017 1.81204 2.51224 + vertex 1.67313 1.81398 2.51057 + endloop + endfacet + facet normal 0.369071 0.12145 0.921432 + outer loop + vertex 1.67102 1.81615 2.51136 + vertex 1.66727 1.81637 2.51283 + vertex 1.67017 1.81204 2.51224 + endloop + endfacet + facet normal 0.374342 0.125337 0.918781 + outer loop + vertex 1.66727 1.81637 2.51283 + vertex 1.66656 1.81195 2.51372 + vertex 1.67017 1.81204 2.51224 + endloop + endfacet + facet normal 0.432871 0.105126 0.895305 + outer loop + vertex 1.67397 1.81821 2.50957 + vertex 1.67298 1.8236 2.50941 + vertex 1.67018 1.82017 2.51117 + endloop + endfacet + facet normal 0.44388 0.133905 0.886025 + outer loop + vertex 1.67102 1.81615 2.51136 + vertex 1.67397 1.81821 2.50957 + vertex 1.67018 1.82017 2.51117 + endloop + endfacet + facet normal 0.36906 0.119962 0.921631 + outer loop + vertex 1.67018 1.82017 2.51117 + vertex 1.66727 1.81637 2.51283 + vertex 1.67102 1.81615 2.51136 + endloop + endfacet + facet normal 0.335135 0.386643 0.859181 + outer loop + vertex 1.66711 2.0778 2.45481 + vertex 1.67288 2.0732 2.45463 + vertex 1.67108 2.07843 2.45298 + endloop + endfacet + facet normal 0.358768 0.535488 0.764551 + outer loop + vertex 1.67369 2.0798 2.45122 + vertex 1.67111 2.08309 2.45012 + vertex 1.66997 2.08156 2.45173 + endloop + endfacet + facet normal 0.326962 0.448808 0.831665 + outer loop + vertex 1.66997 2.08156 2.45173 + vertex 1.67108 2.07843 2.45298 + vertex 1.67369 2.0798 2.45122 + endloop + endfacet + facet normal 0.312214 0.446372 0.838615 + outer loop + vertex 1.66997 2.08156 2.45173 + vertex 1.66644 2.08221 2.4527 + vertex 1.67108 2.07843 2.45298 + endloop + endfacet + facet normal 0.314627 0.449162 0.83622 + outer loop + vertex 1.66644 2.08221 2.4527 + vertex 1.66711 2.0778 2.45481 + vertex 1.67108 2.07843 2.45298 + endloop + endfacet + facet normal 0.352042 0.54025 0.764327 + outer loop + vertex 1.668 2.08368 2.45114 + vertex 1.66997 2.08156 2.45173 + vertex 1.67111 2.08309 2.45012 + endloop + endfacet + facet normal 0.345913 0.635803 0.689999 + outer loop + vertex 1.668 2.08368 2.45114 + vertex 1.67111 2.08309 2.45012 + vertex 1.66786 2.08568 2.44936 + endloop + endfacet + facet normal 0.357646 0.645939 0.674427 + outer loop + vertex 1.66786 2.08568 2.44936 + vertex 1.67111 2.08309 2.45012 + vertex 1.67174 2.08533 2.44765 + endloop + endfacet + facet normal 0.313579 0.51388 0.798496 + outer loop + vertex 1.66997 2.08156 2.45173 + vertex 1.668 2.08368 2.45114 + vertex 1.66644 2.08221 2.4527 + endloop + endfacet + facet normal 0.211722 0.64521 0.734083 + outer loop + vertex 1.67319 2.09019 2.44097 + vertex 1.67163 2.09242 2.43945 + vertex 1.66881 2.09087 2.44163 + endloop + endfacet + facet normal 0.341138 0.781652 0.522154 + outer loop + vertex 1.66881 2.09087 2.44163 + vertex 1.66495 2.09121 2.44363 + vertex 1.66809 2.08852 2.44562 + endloop + endfacet + facet normal 0.207926 0.825961 0.523981 + outer loop + vertex 1.66881 2.09087 2.44163 + vertex 1.66809 2.08852 2.44562 + vertex 1.67319 2.09019 2.44097 + endloop + endfacet + facet normal 0.333366 0.710156 0.620118 + outer loop + vertex 1.67319 2.09019 2.44097 + vertex 1.66809 2.08852 2.44562 + vertex 1.67335 2.08721 2.44429 + endloop + endfacet + facet normal 0.326386 0.74368 0.583449 + outer loop + vertex 1.67174 2.08533 2.44765 + vertex 1.66809 2.08852 2.44562 + vertex 1.66786 2.08568 2.44936 + endloop + endfacet + facet normal 0.331627 0.745942 0.577576 + outer loop + vertex 1.67335 2.08721 2.44429 + vertex 1.66809 2.08852 2.44562 + vertex 1.67174 2.08533 2.44765 + endloop + endfacet + facet normal 0.274498 0.578815 0.76787 + outer loop + vertex 1.67163 2.09242 2.43945 + vertex 1.66771 2.09343 2.4401 + vertex 1.66881 2.09087 2.44163 + endloop + endfacet + facet normal 0.0979514 -0.236517 0.966677 + outer loop + vertex 1.67163 2.09242 2.43945 + vertex 1.675 2.09605 2.44 + vertex 1.66771 2.09343 2.4401 + endloop + endfacet + facet normal 0.00390543 0.0260339 0.999653 + outer loop + vertex 1.675 2.09605 2.44 + vertex 1.67 2.0968 2.44 + vertex 1.66771 2.09343 2.4401 + endloop + endfacet + facet normal 0.412201 0.592652 0.691993 + outer loop + vertex 1.66881 2.09087 2.44163 + vertex 1.66771 2.09343 2.4401 + vertex 1.66495 2.09121 2.44363 + endloop + endfacet + facet normal 0.325688 -0.869071 0.372347 + outer loop + vertex 1.67617 0.94 2.44 + vertex 1.68 0.939293 2.435 + vertex 1.68 0.94 2.43665 + endloop + endfacet + facet normal 0.341771 -0.858144 0.383121 + outer loop + vertex 1.67617 0.94 2.44 + vertex 1.675 0.939534 2.44 + vertex 1.68 0.939293 2.435 + endloop + endfacet + facet normal 0.302005 -0.888755 0.344831 + outer loop + vertex 1.675 0.939534 2.44 + vertex 1.675 0.937594 2.435 + vertex 1.68 0.939293 2.435 + endloop + endfacet + facet normal -0.323582 0.812473 0.484957 + outer loop + vertex 1.67617 0.94 2.44 + vertex 1.67476 0.939916 2.4392 + vertex 1.675 0.939534 2.44 + endloop + endfacet + facet normal -0.339148 0.787236 0.515013 + outer loop + vertex 1.67476 0.939916 2.4392 + vertex 1.67617 0.94 2.44 + vertex 1.68 0.94165 2.44 + endloop + endfacet + facet normal 0.15453 -0.758944 0.632554 + outer loop + vertex 1.67476 0.939916 2.4392 + vertex 1.68 0.94165 2.44 + vertex 1.67495 0.940972 2.44042 + endloop + endfacet + facet normal 0.124067 -0.348436 0.929086 + outer loop + vertex 1.67495 0.940972 2.44042 + vertex 1.68 0.94165 2.44 + vertex 1.67777 0.94228 2.44053 + endloop + endfacet + facet normal 0.342305 -0.783233 0.519012 + outer loop + vertex 1.67777 0.94228 2.44053 + vertex 1.67383 0.942701 2.44377 + vertex 1.67495 0.940972 2.44042 + endloop + endfacet + facet normal 0.349898 -0.774414 0.527119 + outer loop + vertex 1.67778 0.943915 2.44293 + vertex 1.67383 0.942701 2.44377 + vertex 1.67777 0.94228 2.44053 + endloop + endfacet + facet normal 0.34951 -0.743509 0.57012 + outer loop + vertex 1.67383 0.942701 2.44377 + vertex 1.67778 0.943915 2.44293 + vertex 1.67632 0.946132 2.44672 + endloop + endfacet + facet normal 0.367456 -0.744998 0.556735 + outer loop + vertex 1.671 0.944364 2.44786 + vertex 1.67383 0.942701 2.44377 + vertex 1.67632 0.946132 2.44672 + endloop + endfacet + facet normal 0.341531 -0.67874 0.650129 + outer loop + vertex 1.67517 0.948754 2.45006 + vertex 1.67632 0.946132 2.44672 + vertex 1.67909 0.94969 2.44898 + endloop + endfacet + facet normal 0.342544 -0.678259 0.650099 + outer loop + vertex 1.67517 0.948754 2.45006 + vertex 1.67178 0.947313 2.45034 + vertex 1.67632 0.946132 2.44672 + endloop + endfacet + facet normal 0.360523 -0.654272 0.664795 + outer loop + vertex 1.67178 0.947313 2.45034 + vertex 1.671 0.944364 2.44786 + vertex 1.67632 0.946132 2.44672 + endloop + endfacet + facet normal 0.302426 -0.559935 0.77137 + outer loop + vertex 1.67517 0.948754 2.45006 + vertex 1.67342 0.950636 2.45211 + vertex 1.67178 0.947313 2.45034 + endloop + endfacet + facet normal 0.342568 -0.582833 0.736854 + outer loop + vertex 1.67909 0.94969 2.44898 + vertex 1.67659 0.95089 2.45109 + vertex 1.67517 0.948754 2.45006 + endloop + endfacet + facet normal 0.293912 -0.566351 0.769975 + outer loop + vertex 1.67659 0.95089 2.45109 + vertex 1.67342 0.950636 2.45211 + vertex 1.67517 0.948754 2.45006 + endloop + endfacet + facet normal 0.30678 -0.450064 0.838647 + outer loop + vertex 1.67659 0.95089 2.45109 + vertex 1.67749 0.954167 2.45252 + vertex 1.67342 0.950636 2.45211 + endloop + endfacet + facet normal 0.292358 -0.434895 0.8517 + outer loop + vertex 1.67749 0.954167 2.45252 + vertex 1.67272 0.954409 2.45428 + vertex 1.67342 0.950636 2.45211 + endloop + endfacet + facet normal 0.30762 -0.3563 0.882281 + outer loop + vertex 1.67749 0.954167 2.45252 + vertex 1.67799 0.958754 2.45419 + vertex 1.67272 0.954409 2.45428 + endloop + endfacet + facet normal 0.283093 -0.252642 0.925219 + outer loop + vertex 1.67927 0.998976 2.46553 + vertex 1.67688 0.999868 2.46651 + vertex 1.67519 0.996264 2.46604 + endloop + endfacet + facet normal 0.337267 -0.175091 0.924983 + outer loop + vertex 1.67756 1.11912 2.49443 + vertex 1.67882 1.1245 2.49498 + vertex 1.67495 1.12142 2.49581 + endloop + endfacet + facet normal 0.306021 -0.180405 0.934775 + outer loop + vertex 1.67226 1.12348 2.49709 + vertex 1.671 1.11839 2.49652 + vertex 1.67495 1.12142 2.49581 + endloop + endfacet + facet normal 0.345239 -0.186483 0.919801 + outer loop + vertex 1.67882 1.1245 2.49498 + vertex 1.6763 1.12517 2.49607 + vertex 1.67495 1.12142 2.49581 + endloop + endfacet + facet normal 0.310102 -0.174888 0.934479 + outer loop + vertex 1.6763 1.12517 2.49607 + vertex 1.67226 1.12348 2.49709 + vertex 1.67495 1.12142 2.49581 + endloop + endfacet + facet normal 0.308031 -0.168849 0.936273 + outer loop + vertex 1.6763 1.12517 2.49607 + vertex 1.67627 1.12842 2.49666 + vertex 1.67226 1.12348 2.49709 + endloop + endfacet + facet normal 0.317216 -0.176691 0.931748 + outer loop + vertex 1.67627 1.12842 2.49666 + vertex 1.67236 1.12866 2.49804 + vertex 1.67226 1.12348 2.49709 + endloop + endfacet + facet normal 0.319041 -0.160231 0.934098 + outer loop + vertex 1.67627 1.12842 2.49666 + vertex 1.67736 1.13365 2.49719 + vertex 1.67236 1.12866 2.49804 + endloop + endfacet + facet normal 0.337468 -0.180456 0.923878 + outer loop + vertex 1.67236 1.12866 2.49804 + vertex 1.67736 1.13365 2.49719 + vertex 1.67285 1.13386 2.49887 + endloop + endfacet + facet normal 0.33911 -0.164408 0.926269 + outer loop + vertex 1.67736 1.13365 2.49719 + vertex 1.67718 1.13877 2.49816 + vertex 1.67285 1.13386 2.49887 + endloop + endfacet + facet normal 0.357693 -0.182288 0.915875 + outer loop + vertex 1.67285 1.13386 2.49887 + vertex 1.67718 1.13877 2.49816 + vertex 1.67299 1.13883 2.49981 + endloop + endfacet + facet normal 0.341392 -0.180062 0.922512 + outer loop + vertex 1.67343 1.14272 2.5004 + vertex 1.67089 1.14027 2.50087 + vertex 1.67299 1.13883 2.49981 + endloop + endfacet + facet normal 0.388063 -0.182455 0.903392 + outer loop + vertex 1.67343 1.14272 2.5004 + vertex 1.67299 1.13883 2.49981 + vertex 1.67715 1.14414 2.4991 + endloop + endfacet + facet normal 0.359501 -0.157903 0.919688 + outer loop + vertex 1.67715 1.14414 2.4991 + vertex 1.67299 1.13883 2.49981 + vertex 1.67718 1.13877 2.49816 + endloop + endfacet + facet normal 0.329224 -0.166105 0.929527 + outer loop + vertex 1.67343 1.14272 2.5004 + vertex 1.67085 1.14332 2.50143 + vertex 1.67089 1.14027 2.50087 + endloop + endfacet + facet normal 0.401753 -0.138375 0.905233 + outer loop + vertex 1.67715 1.14414 2.4991 + vertex 1.67831 1.14989 2.49946 + vertex 1.67454 1.14663 2.50063 + endloop + endfacet + facet normal 0.382343 -0.161558 0.909787 + outer loop + vertex 1.67343 1.14272 2.5004 + vertex 1.67715 1.14414 2.4991 + vertex 1.67454 1.14663 2.50063 + endloop + endfacet + facet normal 0.33368 -0.14904 0.93083 + outer loop + vertex 1.67454 1.14663 2.50063 + vertex 1.67085 1.14332 2.50143 + vertex 1.67343 1.14272 2.5004 + endloop + endfacet + facet normal 0.339151 -0.155893 0.927725 + outer loop + vertex 1.67125 1.14768 2.50202 + vertex 1.67085 1.14332 2.50143 + vertex 1.67454 1.14663 2.50063 + endloop + endfacet + facet normal 0.417711 -0.101425 0.902901 + outer loop + vertex 1.67831 1.14989 2.49946 + vertex 1.67875 1.15485 2.49981 + vertex 1.67522 1.1514 2.50106 + endloop + endfacet + facet normal 0.401308 -0.137755 0.905525 + outer loop + vertex 1.67454 1.14663 2.50063 + vertex 1.67831 1.14989 2.49946 + vertex 1.67522 1.1514 2.50106 + endloop + endfacet + facet normal 0.347111 -0.132029 0.928484 + outer loop + vertex 1.67522 1.1514 2.50106 + vertex 1.67125 1.14768 2.50202 + vertex 1.67454 1.14663 2.50063 + endloop + endfacet + facet normal 0.355112 -0.141733 0.924017 + outer loop + vertex 1.67181 1.15263 2.50256 + vertex 1.67125 1.14768 2.50202 + vertex 1.67522 1.1514 2.50106 + endloop + endfacet + facet normal 0.444316 -0.0722571 0.892951 + outer loop + vertex 1.67875 1.15485 2.49981 + vertex 1.67887 1.15936 2.50012 + vertex 1.67577 1.15619 2.50141 + endloop + endfacet + facet normal 0.427723 -0.113901 0.896705 + outer loop + vertex 1.67522 1.1514 2.50106 + vertex 1.67875 1.15485 2.49981 + vertex 1.67577 1.15619 2.50141 + endloop + endfacet + facet normal 0.366864 -0.108933 0.923875 + outer loop + vertex 1.67577 1.15619 2.50141 + vertex 1.67181 1.15263 2.50256 + vertex 1.67522 1.1514 2.50106 + endloop + endfacet + facet normal 0.374958 -0.119423 0.919318 + outer loop + vertex 1.67273 1.15837 2.50293 + vertex 1.67181 1.15263 2.50256 + vertex 1.67577 1.15619 2.50141 + endloop + endfacet + facet normal 0.463191 -0.0955097 0.881097 + outer loop + vertex 1.67887 1.15936 2.50012 + vertex 1.67646 1.16005 2.50146 + vertex 1.67577 1.15619 2.50141 + endloop + endfacet + facet normal 0.397466 -0.0842831 0.913738 + outer loop + vertex 1.67646 1.16005 2.50146 + vertex 1.67273 1.15837 2.50293 + vertex 1.67577 1.15619 2.50141 + endloop + endfacet + facet normal 0.39329 -0.0725676 0.916546 + outer loop + vertex 1.67646 1.16005 2.50146 + vertex 1.67593 1.16328 2.50194 + vertex 1.67273 1.15837 2.50293 + endloop + endfacet + facet normal 0.435972 -0.104931 0.893822 + outer loop + vertex 1.67593 1.16328 2.50194 + vertex 1.67249 1.16369 2.50367 + vertex 1.67273 1.15837 2.50293 + endloop + endfacet + facet normal 0.440594 -0.0706471 0.894922 + outer loop + vertex 1.67593 1.16328 2.50194 + vertex 1.676 1.16794 2.50228 + vertex 1.67249 1.16369 2.50367 + endloop + endfacet + facet normal 0.474772 -0.105759 0.873731 + outer loop + vertex 1.67249 1.16369 2.50367 + vertex 1.676 1.16794 2.50228 + vertex 1.67243 1.16902 2.50435 + endloop + endfacet + facet normal 0.481553 -0.0811046 0.872656 + outer loop + vertex 1.676 1.16794 2.50228 + vertex 1.67634 1.17309 2.50257 + vertex 1.67243 1.16902 2.50435 + endloop + endfacet + facet normal 0.511722 -0.119607 0.850785 + outer loop + vertex 1.67243 1.16902 2.50435 + vertex 1.67634 1.17309 2.50257 + vertex 1.67345 1.17464 2.50453 + endloop + endfacet + facet normal 0.52261 -0.0948432 0.84728 + outer loop + vertex 1.67634 1.17309 2.50257 + vertex 1.67672 1.17825 2.50291 + vertex 1.67345 1.17464 2.50453 + endloop + endfacet + facet normal 0.542748 -0.120285 0.831237 + outer loop + vertex 1.67345 1.17464 2.50453 + vertex 1.67672 1.17825 2.50291 + vertex 1.6739 1.17931 2.5049 + endloop + endfacet + facet normal 0.471606 -0.121769 0.873361 + outer loop + vertex 1.67361 1.18262 2.50552 + vertex 1.67148 1.17995 2.5063 + vertex 1.6739 1.17931 2.5049 + endloop + endfacet + facet normal 0.560817 -0.104168 0.821361 + outer loop + vertex 1.67361 1.18262 2.50552 + vertex 1.6739 1.17931 2.5049 + vertex 1.67663 1.18359 2.50358 + endloop + endfacet + facet normal 0.550701 -0.0952942 0.829245 + outer loop + vertex 1.67663 1.18359 2.50358 + vertex 1.6739 1.17931 2.5049 + vertex 1.67672 1.17825 2.50291 + endloop + endfacet + facet normal 0.448353 -0.0987785 0.888382 + outer loop + vertex 1.67361 1.18262 2.50552 + vertex 1.67101 1.1832 2.5069 + vertex 1.67148 1.17995 2.5063 + endloop + endfacet + facet normal 0.568979 -0.081064 0.818347 + outer loop + vertex 1.67663 1.18359 2.50358 + vertex 1.67735 1.18924 2.50365 + vertex 1.67421 1.18647 2.50555 + endloop + endfacet + facet normal 0.558971 -0.0933014 0.823921 + outer loop + vertex 1.67361 1.18262 2.50552 + vertex 1.67663 1.18359 2.50358 + vertex 1.67421 1.18647 2.50555 + endloop + endfacet + facet normal 0.452981 -0.0773447 0.888159 + outer loop + vertex 1.67421 1.18647 2.50555 + vertex 1.67101 1.1832 2.5069 + vertex 1.67361 1.18262 2.50552 + endloop + endfacet + facet normal 0.476238 -0.106399 0.872856 + outer loop + vertex 1.67111 1.18791 2.50742 + vertex 1.67101 1.1832 2.5069 + vertex 1.67421 1.18647 2.50555 + endloop + endfacet + facet normal 0.587038 -0.0786442 0.80573 + outer loop + vertex 1.67735 1.18924 2.50365 + vertex 1.67777 1.19445 2.50385 + vertex 1.67463 1.19147 2.50584 + endloop + endfacet + facet normal 0.577295 -0.0956057 0.810919 + outer loop + vertex 1.67421 1.18647 2.50555 + vertex 1.67735 1.18924 2.50365 + vertex 1.67463 1.19147 2.50584 + endloop + endfacet + facet normal 0.482404 -0.091061 0.871203 + outer loop + vertex 1.67463 1.19147 2.50584 + vertex 1.67111 1.18791 2.50742 + vertex 1.67421 1.18647 2.50555 + endloop + endfacet + facet normal 0.507976 -0.12475 0.85229 + outer loop + vertex 1.67153 1.19317 2.50794 + vertex 1.67111 1.18791 2.50742 + vertex 1.67463 1.19147 2.50584 + endloop + endfacet + facet normal 0.617437 -0.0669318 0.783768 + outer loop + vertex 1.67777 1.19445 2.50385 + vertex 1.67845 1.19997 2.50378 + vertex 1.67503 1.19674 2.5062 + endloop + endfacet + facet normal 0.59936 -0.0992503 0.794303 + outer loop + vertex 1.67463 1.19147 2.50584 + vertex 1.67777 1.19445 2.50385 + vertex 1.67503 1.19674 2.5062 + endloop + endfacet + facet normal 0.520577 -0.0968986 0.848298 + outer loop + vertex 1.67503 1.19674 2.5062 + vertex 1.67153 1.19317 2.50794 + vertex 1.67463 1.19147 2.50584 + endloop + endfacet + facet normal 0.542015 -0.126449 0.830801 + outer loop + vertex 1.67174 1.19869 2.50865 + vertex 1.67153 1.19317 2.50794 + vertex 1.67503 1.19674 2.5062 + endloop + endfacet + facet normal 0.642157 -0.0764706 0.76275 + outer loop + vertex 1.67845 1.19997 2.50378 + vertex 1.67831 1.20523 2.50443 + vertex 1.6754 1.20203 2.50655 + endloop + endfacet + facet normal 0.633515 -0.0959892 0.767753 + outer loop + vertex 1.67503 1.19674 2.5062 + vertex 1.67845 1.19997 2.50378 + vertex 1.6754 1.20203 2.50655 + endloop + endfacet + facet normal 0.556777 -0.0944379 0.825276 + outer loop + vertex 1.6754 1.20203 2.50655 + vertex 1.67174 1.19869 2.50865 + vertex 1.67503 1.19674 2.5062 + endloop + endfacet + facet normal 0.567956 -0.112989 0.815266 + outer loop + vertex 1.67264 1.2042 2.50878 + vertex 1.67174 1.19869 2.50865 + vertex 1.6754 1.20203 2.50655 + endloop + endfacet + facet normal 0.658458 -0.0619129 0.750067 + outer loop + vertex 1.67831 1.20523 2.50443 + vertex 1.67842 1.21011 2.50473 + vertex 1.6757 1.20712 2.50687 + endloop + endfacet + facet normal 0.647855 -0.0854718 0.756953 + outer loop + vertex 1.6754 1.20203 2.50655 + vertex 1.67831 1.20523 2.50443 + vertex 1.6757 1.20712 2.50687 + endloop + endfacet + facet normal 0.583793 -0.0848391 0.807457 + outer loop + vertex 1.6757 1.20712 2.50687 + vertex 1.67264 1.2042 2.50878 + vertex 1.6754 1.20203 2.50655 + endloop + endfacet + facet normal 0.587329 -0.090635 0.804257 + outer loop + vertex 1.67304 1.20923 2.50906 + vertex 1.67264 1.2042 2.50878 + vertex 1.6757 1.20712 2.50687 + endloop + endfacet + facet normal 0.670809 -0.0464628 0.740174 + outer loop + vertex 1.67842 1.21011 2.50473 + vertex 1.67857 1.21509 2.50491 + vertex 1.67591 1.21223 2.50714 + endloop + endfacet + facet normal 0.661085 -0.0662155 0.747383 + outer loop + vertex 1.6757 1.20712 2.50687 + vertex 1.67842 1.21011 2.50473 + vertex 1.67591 1.21223 2.50714 + endloop + endfacet + facet normal 0.600477 -0.0664503 0.796877 + outer loop + vertex 1.67591 1.21223 2.50714 + vertex 1.67304 1.20923 2.50906 + vertex 1.6757 1.20712 2.50687 + endloop + endfacet + facet normal 0.606313 -0.0753864 0.791645 + outer loop + vertex 1.67323 1.2142 2.50939 + vertex 1.67304 1.20923 2.50906 + vertex 1.67591 1.21223 2.50714 + endloop + endfacet + facet normal 0.682739 -0.0404617 0.729541 + outer loop + vertex 1.67857 1.21509 2.50491 + vertex 1.6788 1.21959 2.50494 + vertex 1.67599 1.21812 2.50749 + endloop + endfacet + facet normal 0.674615 -0.0530564 0.736261 + outer loop + vertex 1.67591 1.21223 2.50714 + vertex 1.67857 1.21509 2.50491 + vertex 1.67599 1.21812 2.50749 + endloop + endfacet + facet normal 0.616212 -0.0551505 0.785647 + outer loop + vertex 1.67599 1.21812 2.50749 + vertex 1.67323 1.2142 2.50939 + vertex 1.67591 1.21223 2.50714 + endloop + endfacet + facet normal 0.629384 -0.0701099 0.773926 + outer loop + vertex 1.67305 1.21806 2.50988 + vertex 1.67323 1.2142 2.50939 + vertex 1.67599 1.21812 2.50749 + endloop + endfacet + facet normal 0.693515 -0.0859303 0.715299 + outer loop + vertex 1.6788 1.21959 2.50494 + vertex 1.67755 1.2209 2.50631 + vertex 1.67599 1.21812 2.50749 + endloop + endfacet + facet normal 0.580878 -0.0551433 0.812121 + outer loop + vertex 1.67305 1.21806 2.50988 + vertex 1.67371 1.22166 2.50965 + vertex 1.67132 1.21974 2.51123 + endloop + endfacet + facet normal 0.629498 -0.0663897 0.774161 + outer loop + vertex 1.67599 1.21812 2.50749 + vertex 1.67371 1.22166 2.50965 + vertex 1.67305 1.21806 2.50988 + endloop + endfacet + facet normal 0.644499 -0.0498521 0.762978 + outer loop + vertex 1.67599 1.21812 2.50749 + vertex 1.67654 1.22362 2.50738 + vertex 1.67371 1.22166 2.50965 + endloop + endfacet + facet normal 0.658868 -0.0515434 0.750491 + outer loop + vertex 1.67599 1.21812 2.50749 + vertex 1.67755 1.2209 2.50631 + vertex 1.67654 1.22362 2.50738 + endloop + endfacet + facet normal 0.584916 -0.0629932 0.808644 + outer loop + vertex 1.67371 1.22166 2.50965 + vertex 1.67097 1.22333 2.51177 + vertex 1.67132 1.21974 2.51123 + endloop + endfacet + facet normal 0.65436 -0.050082 0.754523 + outer loop + vertex 1.67654 1.22362 2.50738 + vertex 1.67666 1.22901 2.50764 + vertex 1.67391 1.22634 2.50985 + endloop + endfacet + facet normal 0.648314 -0.0599869 0.759007 + outer loop + vertex 1.67371 1.22166 2.50965 + vertex 1.67654 1.22362 2.50738 + vertex 1.67391 1.22634 2.50985 + endloop + endfacet + facet normal 0.586466 -0.0593834 0.807794 + outer loop + vertex 1.67391 1.22634 2.50985 + vertex 1.67097 1.22333 2.51177 + vertex 1.67371 1.22166 2.50965 + endloop + endfacet + facet normal 0.601198 -0.0819807 0.794884 + outer loop + vertex 1.67108 1.22823 2.51219 + vertex 1.67097 1.22333 2.51177 + vertex 1.67391 1.22634 2.50985 + endloop + endfacet + facet normal 0.671743 -0.0500773 0.739089 + outer loop + vertex 1.67666 1.22901 2.50764 + vertex 1.67682 1.23411 2.50784 + vertex 1.67408 1.23138 2.51014 + endloop + endfacet + facet normal 0.663053 -0.066448 0.745618 + outer loop + vertex 1.67391 1.22634 2.50985 + vertex 1.67666 1.22901 2.50764 + vertex 1.67408 1.23138 2.51014 + endloop + endfacet + facet normal 0.607968 -0.0671436 0.791117 + outer loop + vertex 1.67408 1.23138 2.51014 + vertex 1.67108 1.22823 2.51219 + vertex 1.67391 1.22634 2.50985 + endloop + endfacet + facet normal 0.620355 -0.0865061 0.779536 + outer loop + vertex 1.67139 1.23327 2.5125 + vertex 1.67108 1.22823 2.51219 + vertex 1.67408 1.23138 2.51014 + endloop + endfacet + facet normal 0.686588 -0.0502561 0.725308 + outer loop + vertex 1.67682 1.23411 2.50784 + vertex 1.67694 1.23908 2.50808 + vertex 1.67424 1.23638 2.51044 + endloop + endfacet + facet normal 0.679447 -0.064711 0.730865 + outer loop + vertex 1.67408 1.23138 2.51014 + vertex 1.67682 1.23411 2.50784 + vertex 1.67424 1.23638 2.51044 + endloop + endfacet + facet normal 0.630003 -0.0656859 0.77381 + outer loop + vertex 1.67424 1.23638 2.51044 + vertex 1.67139 1.23327 2.5125 + vertex 1.67408 1.23138 2.51014 + endloop + endfacet + facet normal 0.636744 -0.0762237 0.767298 + outer loop + vertex 1.67155 1.23821 2.51285 + vertex 1.67139 1.23327 2.5125 + vertex 1.67424 1.23638 2.51044 + endloop + endfacet + facet normal 0.695694 -0.0528412 0.716392 + outer loop + vertex 1.67694 1.23908 2.50808 + vertex 1.67709 1.24405 2.5083 + vertex 1.67433 1.24139 2.51077 + endloop + endfacet + facet normal 0.691898 -0.060674 0.719441 + outer loop + vertex 1.67424 1.23638 2.51044 + vertex 1.67694 1.23908 2.50808 + vertex 1.67433 1.24139 2.51077 + endloop + endfacet + facet normal 0.642627 -0.0627101 0.763608 + outer loop + vertex 1.67433 1.24139 2.51077 + vertex 1.67155 1.23821 2.51285 + vertex 1.67424 1.23638 2.51044 + endloop + endfacet + facet normal 0.642601 -0.062671 0.763633 + outer loop + vertex 1.67134 1.24344 2.51346 + vertex 1.67155 1.23821 2.51285 + vertex 1.67433 1.24139 2.51077 + endloop + endfacet + facet normal 0.713209 -0.0411136 0.699745 + outer loop + vertex 1.67709 1.24405 2.5083 + vertex 1.6773 1.24918 2.50838 + vertex 1.67456 1.24654 2.51102 + endloop + endfacet + facet normal 0.701234 -0.0644983 0.710008 + outer loop + vertex 1.67433 1.24139 2.51077 + vertex 1.67709 1.24405 2.5083 + vertex 1.67456 1.24654 2.51102 + endloop + endfacet + facet normal 0.641819 -0.0644764 0.764141 + outer loop + vertex 1.67456 1.24654 2.51102 + vertex 1.67134 1.24344 2.51346 + vertex 1.67433 1.24139 2.51077 + endloop + endfacet + facet normal 0.645971 -0.0720786 0.759952 + outer loop + vertex 1.67203 1.24904 2.51341 + vertex 1.67134 1.24344 2.51346 + vertex 1.67456 1.24654 2.51102 + endloop + endfacet + facet normal 0.747127 -0.0183912 0.664427 + outer loop + vertex 1.6773 1.24918 2.50838 + vertex 1.67734 1.25435 2.50848 + vertex 1.67489 1.2517 2.51116 + endloop + endfacet + facet normal 0.723943 -0.065199 0.686772 + outer loop + vertex 1.67456 1.24654 2.51102 + vertex 1.6773 1.24918 2.50838 + vertex 1.67489 1.2517 2.51116 + endloop + endfacet + facet normal 0.651628 -0.0625071 0.755959 + outer loop + vertex 1.67489 1.2517 2.51116 + vertex 1.67203 1.24904 2.51341 + vertex 1.67456 1.24654 2.51102 + endloop + endfacet + facet normal 0.656069 -0.0711811 0.751336 + outer loop + vertex 1.67241 1.25417 2.51356 + vertex 1.67203 1.24904 2.51341 + vertex 1.67489 1.2517 2.51116 + endloop + endfacet + facet normal 0.78794 -0.00457542 0.615735 + outer loop + vertex 1.67734 1.25435 2.50848 + vertex 1.67723 1.2594 2.50865 + vertex 1.67512 1.25672 2.51134 + endloop + endfacet + facet normal 0.764775 -0.0576043 0.641717 + outer loop + vertex 1.67489 1.2517 2.51116 + vertex 1.67734 1.25435 2.50848 + vertex 1.67512 1.25672 2.51134 + endloop + endfacet + facet normal 0.664499 -0.0566636 0.745138 + outer loop + vertex 1.67512 1.25672 2.51134 + vertex 1.67241 1.25417 2.51356 + vertex 1.67489 1.2517 2.51116 + endloop + endfacet + facet normal 0.6664 -0.0604135 0.743143 + outer loop + vertex 1.67265 1.25918 2.51375 + vertex 1.67241 1.25417 2.51356 + vertex 1.67512 1.25672 2.51134 + endloop + endfacet + facet normal 0.813007 -0.0184911 0.581961 + outer loop + vertex 1.67723 1.2594 2.50865 + vertex 1.67726 1.26437 2.50877 + vertex 1.67527 1.26167 2.51147 + endloop + endfacet + facet normal 0.804106 -0.0400526 0.593135 + outer loop + vertex 1.67512 1.25672 2.51134 + vertex 1.67723 1.2594 2.50865 + vertex 1.67527 1.26167 2.51147 + endloop + endfacet + facet normal 0.677834 -0.0400066 0.734125 + outer loop + vertex 1.67527 1.26167 2.51147 + vertex 1.67265 1.25918 2.51375 + vertex 1.67512 1.25672 2.51134 + endloop + endfacet + facet normal 0.680743 -0.0458581 0.731086 + outer loop + vertex 1.67282 1.26416 2.51391 + vertex 1.67265 1.25918 2.51375 + vertex 1.67527 1.26167 2.51147 + endloop + endfacet + facet normal 0.823305 -0.0179314 0.567316 + outer loop + vertex 1.67726 1.26437 2.50877 + vertex 1.67737 1.26941 2.50877 + vertex 1.67541 1.26659 2.51152 + endloop + endfacet + facet normal 0.818309 -0.0303771 0.573975 + outer loop + vertex 1.67527 1.26167 2.51147 + vertex 1.67726 1.26437 2.50877 + vertex 1.67541 1.26659 2.51152 + endloop + endfacet + facet normal 0.690485 -0.0282096 0.722797 + outer loop + vertex 1.67541 1.26659 2.51152 + vertex 1.67282 1.26416 2.51391 + vertex 1.67527 1.26167 2.51147 + endloop + endfacet + facet normal 0.689828 -0.0268387 0.723476 + outer loop + vertex 1.67295 1.26914 2.51397 + vertex 1.67282 1.26416 2.51391 + vertex 1.67541 1.26659 2.51152 + endloop + endfacet + facet normal 0.824517 0.00054224 0.565836 + outer loop + vertex 1.67737 1.26941 2.50877 + vertex 1.67743 1.27453 2.50868 + vertex 1.6755 1.27154 2.51149 + endloop + endfacet + facet normal 0.820167 -0.0111773 0.572014 + outer loop + vertex 1.67541 1.26659 2.51152 + vertex 1.67737 1.26941 2.50877 + vertex 1.6755 1.27154 2.51149 + endloop + endfacet + facet normal 0.699896 -0.00823331 0.714197 + outer loop + vertex 1.6755 1.27154 2.51149 + vertex 1.67295 1.26914 2.51397 + vertex 1.67541 1.26659 2.51152 + endloop + endfacet + facet normal 0.703298 -0.0154043 0.710728 + outer loop + vertex 1.67302 1.27412 2.51401 + vertex 1.67295 1.26914 2.51397 + vertex 1.6755 1.27154 2.51149 + endloop + endfacet + facet normal 0.827053 0.021356 0.561718 + outer loop + vertex 1.67743 1.27453 2.50868 + vertex 1.67734 1.27969 2.50861 + vertex 1.67548 1.27659 2.51147 + endloop + endfacet + facet normal 0.821899 0.00578984 0.569604 + outer loop + vertex 1.6755 1.27154 2.51149 + vertex 1.67743 1.27453 2.50868 + vertex 1.67548 1.27659 2.51147 + endloop + endfacet + facet normal 0.714328 0.00588392 0.699786 + outer loop + vertex 1.67548 1.27659 2.51147 + vertex 1.67302 1.27412 2.51401 + vertex 1.6755 1.27154 2.51149 + endloop + endfacet + facet normal 0.723742 -0.0136507 0.689936 + outer loop + vertex 1.673 1.27914 2.51413 + vertex 1.67302 1.27412 2.51401 + vertex 1.67548 1.27659 2.51147 + endloop + endfacet + facet normal 0.836611 0.0290905 0.547024 + outer loop + vertex 1.67734 1.27969 2.50861 + vertex 1.67713 1.28485 2.50866 + vertex 1.67534 1.28177 2.51157 + endloop + endfacet + facet normal 0.831608 0.012624 0.555219 + outer loop + vertex 1.67548 1.27659 2.51147 + vertex 1.67734 1.27969 2.50861 + vertex 1.67534 1.28177 2.51157 + endloop + endfacet + facet normal 0.7341 0.00773563 0.678998 + outer loop + vertex 1.67534 1.28177 2.51157 + vertex 1.673 1.27914 2.51413 + vertex 1.67548 1.27659 2.51147 + endloop + endfacet + facet normal 0.747004 -0.0178515 0.664579 + outer loop + vertex 1.67291 1.28409 2.51436 + vertex 1.673 1.27914 2.51413 + vertex 1.67534 1.28177 2.51157 + endloop + endfacet + facet normal 0.845091 0.0222839 0.534158 + outer loop + vertex 1.67713 1.28485 2.50866 + vertex 1.67701 1.28967 2.50866 + vertex 1.67503 1.28738 2.51188 + endloop + endfacet + facet normal 0.843101 0.016369 0.537507 + outer loop + vertex 1.67534 1.28177 2.51157 + vertex 1.67713 1.28485 2.50866 + vertex 1.67503 1.28738 2.51188 + endloop + endfacet + facet normal 0.756663 0.00520928 0.653784 + outer loop + vertex 1.67503 1.28738 2.51188 + vertex 1.67291 1.28409 2.51436 + vertex 1.67534 1.28177 2.51157 + endloop + endfacet + facet normal 0.769815 -0.0151902 0.638086 + outer loop + vertex 1.67267 1.28809 2.51474 + vertex 1.67291 1.28409 2.51436 + vertex 1.67503 1.28738 2.51188 + endloop + endfacet + facet normal 0.873483 0.0300641 0.485925 + outer loop + vertex 1.67701 1.28967 2.50866 + vertex 1.67687 1.29435 2.50862 + vertex 1.67569 1.29178 2.51089 + endloop + endfacet + facet normal 0.856349 -0.0126078 0.516244 + outer loop + vertex 1.67503 1.28738 2.51188 + vertex 1.67701 1.28967 2.50866 + vertex 1.67569 1.29178 2.51089 + endloop + endfacet + facet normal 0.730097 0.00976629 0.683274 + outer loop + vertex 1.67267 1.28809 2.51474 + vertex 1.67346 1.29211 2.51384 + vertex 1.6712 1.29015 2.51629 + endloop + endfacet + facet normal 0.770678 -0.00862088 0.637167 + outer loop + vertex 1.67267 1.28809 2.51474 + vertex 1.67503 1.28738 2.51188 + vertex 1.67346 1.29211 2.51384 + endloop + endfacet + facet normal 0.798485 0.0152319 0.601822 + outer loop + vertex 1.67503 1.28738 2.51188 + vertex 1.67569 1.29178 2.51089 + vertex 1.67346 1.29211 2.51384 + endloop + endfacet + facet normal 0.735719 -0.00428252 0.677274 + outer loop + vertex 1.67346 1.29211 2.51384 + vertex 1.67085 1.29389 2.51669 + vertex 1.6712 1.29015 2.51629 + endloop + endfacet + facet normal 0.86192 0.371793 -0.344768 + outer loop + vertex 1.68 1.29847 2.505 + vertex 1.67934 1.3 2.505 + vertex 1.68 1.3 2.50665 + endloop + endfacet + facet normal 0.866591 0.0201621 0.498612 + outer loop + vertex 1.67687 1.29435 2.50862 + vertex 1.67665 1.29937 2.5088 + vertex 1.67527 1.29593 2.51133 + endloop + endfacet + facet normal 0.870222 0.036333 0.491319 + outer loop + vertex 1.67569 1.29178 2.51089 + vertex 1.67687 1.29435 2.50862 + vertex 1.67527 1.29593 2.51133 + endloop + endfacet + facet normal 0.798575 0.0174992 0.601641 + outer loop + vertex 1.67569 1.29178 2.51089 + vertex 1.67527 1.29593 2.51133 + vertex 1.67346 1.29211 2.51384 + endloop + endfacet + facet normal 0.805608 0.00808707 0.592394 + outer loop + vertex 1.67527 1.29593 2.51133 + vertex 1.67313 1.29732 2.51422 + vertex 1.67346 1.29211 2.51384 + endloop + endfacet + facet normal 0.736296 -0.00244473 0.676655 + outer loop + vertex 1.67313 1.29732 2.51422 + vertex 1.67085 1.29389 2.51669 + vertex 1.67346 1.29211 2.51384 + endloop + endfacet + facet normal 0.747089 -0.0184351 0.664468 + outer loop + vertex 1.67071 1.29866 2.51698 + vertex 1.67085 1.29389 2.51669 + vertex 1.67313 1.29732 2.51422 + endloop + endfacet + facet normal 0.865398 0.00339516 0.501074 + outer loop + vertex 1.67665 1.29937 2.5088 + vertex 1.67652 1.30452 2.50897 + vertex 1.67508 1.30088 2.5115 + endloop + endfacet + facet normal 0.868542 0.0169689 0.495325 + outer loop + vertex 1.67527 1.29593 2.51133 + vertex 1.67665 1.29937 2.5088 + vertex 1.67508 1.30088 2.5115 + endloop + endfacet + facet normal 0.806279 0.0111112 0.591431 + outer loop + vertex 1.67527 1.29593 2.51133 + vertex 1.67508 1.30088 2.5115 + vertex 1.67313 1.29732 2.51422 + endloop + endfacet + facet normal 0.814464 -0.00194613 0.580211 + outer loop + vertex 1.67508 1.30088 2.5115 + vertex 1.67306 1.30226 2.51434 + vertex 1.67313 1.29732 2.51422 + endloop + endfacet + facet normal 0.750439 -0.00499438 0.660921 + outer loop + vertex 1.67306 1.30226 2.51434 + vertex 1.67071 1.29866 2.51698 + vertex 1.67313 1.29732 2.51422 + endloop + endfacet + facet normal 0.76058 -0.0203849 0.648924 + outer loop + vertex 1.67074 1.30351 2.51709 + vertex 1.67071 1.29866 2.51698 + vertex 1.67306 1.30226 2.51434 + endloop + endfacet + facet normal 0.863124 0.00481086 0.504969 + outer loop + vertex 1.67652 1.30452 2.50897 + vertex 1.6765 1.30962 2.50897 + vertex 1.67504 1.3059 2.5115 + endloop + endfacet + facet normal 0.863495 0.00639958 0.504318 + outer loop + vertex 1.67508 1.30088 2.5115 + vertex 1.67652 1.30452 2.50897 + vertex 1.67504 1.3059 2.5115 + endloop + endfacet + facet normal 0.816288 0.00603537 0.577614 + outer loop + vertex 1.67508 1.30088 2.5115 + vertex 1.67504 1.3059 2.5115 + vertex 1.67306 1.30226 2.51434 + endloop + endfacet + facet normal 0.822098 -0.00359147 0.569335 + outer loop + vertex 1.67504 1.3059 2.5115 + vertex 1.67309 1.3072 2.51433 + vertex 1.67306 1.30226 2.51434 + endloop + endfacet + facet normal 0.764649 -0.00296298 0.64444 + outer loop + vertex 1.67309 1.3072 2.51433 + vertex 1.67074 1.30351 2.51709 + vertex 1.67306 1.30226 2.51434 + endloop + endfacet + facet normal 0.774048 -0.0176225 0.632882 + outer loop + vertex 1.67082 1.30842 2.51713 + vertex 1.67074 1.30351 2.51709 + vertex 1.67309 1.3072 2.51433 + endloop + endfacet + facet normal 0.862553 0.0194673 0.505592 + outer loop + vertex 1.6765 1.30962 2.50897 + vertex 1.67648 1.31467 2.50881 + vertex 1.67505 1.3109 2.51139 + endloop + endfacet + facet normal 0.860306 0.00913766 0.509696 + outer loop + vertex 1.67504 1.3059 2.5115 + vertex 1.6765 1.30962 2.50897 + vertex 1.67505 1.3109 2.51139 + endloop + endfacet + facet normal 0.825065 0.0104774 0.56494 + outer loop + vertex 1.67504 1.3059 2.5115 + vertex 1.67505 1.3109 2.51139 + vertex 1.67309 1.3072 2.51433 + endloop + endfacet + facet normal 0.830812 0.000777763 0.556553 + outer loop + vertex 1.67505 1.3109 2.51139 + vertex 1.67312 1.31213 2.51427 + vertex 1.67309 1.3072 2.51433 + endloop + endfacet + facet normal 0.77831 0.00184572 0.627877 + outer loop + vertex 1.67312 1.31213 2.51427 + vertex 1.67082 1.30842 2.51713 + vertex 1.67309 1.3072 2.51433 + endloop + endfacet + facet normal 0.787243 -0.0124403 0.616517 + outer loop + vertex 1.67087 1.31333 2.51717 + vertex 1.67082 1.30842 2.51713 + vertex 1.67312 1.31213 2.51427 + endloop + endfacet + facet normal 0.866203 0.00641209 0.499651 + outer loop + vertex 1.67648 1.31467 2.50881 + vertex 1.67649 1.31973 2.50873 + vertex 1.67505 1.31585 2.51127 + endloop + endfacet + facet normal 0.867345 0.0121426 0.497559 + outer loop + vertex 1.67505 1.3109 2.51139 + vertex 1.67648 1.31467 2.50881 + vertex 1.67505 1.31585 2.51127 + endloop + endfacet + facet normal 0.833212 0.0133901 0.552792 + outer loop + vertex 1.67505 1.3109 2.51139 + vertex 1.67505 1.31585 2.51127 + vertex 1.67312 1.31213 2.51427 + endloop + endfacet + facet normal 0.842005 -0.00190284 0.539467 + outer loop + vertex 1.67505 1.31585 2.51127 + vertex 1.67313 1.31705 2.51427 + vertex 1.67312 1.31213 2.51427 + endloop + endfacet + facet normal 0.789472 -0.00162193 0.613784 + outer loop + vertex 1.67313 1.31705 2.51427 + vertex 1.67087 1.31333 2.51717 + vertex 1.67312 1.31213 2.51427 + endloop + endfacet + facet normal 0.79981 -0.0187144 0.599961 + outer loop + vertex 1.67087 1.31822 2.51732 + vertex 1.67087 1.31333 2.51717 + vertex 1.67313 1.31705 2.51427 + endloop + endfacet + facet normal 0.86967 -0.00843173 0.493561 + outer loop + vertex 1.67649 1.31973 2.50873 + vertex 1.67656 1.32481 2.5087 + vertex 1.67508 1.3208 2.51123 + endloop + endfacet + facet normal 0.871072 -0.000962681 0.491154 + outer loop + vertex 1.67505 1.31585 2.51127 + vertex 1.67649 1.31973 2.50873 + vertex 1.67508 1.3208 2.51123 + endloop + endfacet + facet normal 0.842284 -0.000371892 0.539033 + outer loop + vertex 1.67505 1.31585 2.51127 + vertex 1.67508 1.3208 2.51123 + vertex 1.67313 1.31705 2.51427 + endloop + endfacet + facet normal 0.850648 -0.0156495 0.525503 + outer loop + vertex 1.67508 1.3208 2.51123 + vertex 1.67316 1.32205 2.51438 + vertex 1.67313 1.31705 2.51427 + endloop + endfacet + facet normal 0.800133 -0.0170912 0.599579 + outer loop + vertex 1.67316 1.32205 2.51438 + vertex 1.67087 1.31822 2.51732 + vertex 1.67313 1.31705 2.51427 + endloop + endfacet + facet normal 0.81115 -0.0358339 0.583739 + outer loop + vertex 1.67068 1.32344 2.51791 + vertex 1.67087 1.31822 2.51732 + vertex 1.67316 1.32205 2.51438 + endloop + endfacet + facet normal 0.873945 -0.00685863 0.485977 + outer loop + vertex 1.67656 1.32481 2.5087 + vertex 1.67662 1.32993 2.50865 + vertex 1.67516 1.32584 2.51123 + endloop + endfacet + facet normal 0.872799 -0.0131585 0.487903 + outer loop + vertex 1.67508 1.3208 2.51123 + vertex 1.67656 1.32481 2.5087 + vertex 1.67516 1.32584 2.51123 + endloop + endfacet + facet normal 0.851183 -0.0128234 0.524713 + outer loop + vertex 1.67508 1.3208 2.51123 + vertex 1.67516 1.32584 2.51123 + vertex 1.67316 1.32205 2.51438 + endloop + endfacet + facet normal 0.858727 -0.0275945 0.51169 + outer loop + vertex 1.67516 1.32584 2.51123 + vertex 1.67329 1.32725 2.51443 + vertex 1.67316 1.32205 2.51438 + endloop + endfacet + facet normal 0.813011 -0.0271275 0.581616 + outer loop + vertex 1.67329 1.32725 2.51443 + vertex 1.67068 1.32344 2.51791 + vertex 1.67316 1.32205 2.51438 + endloop + endfacet + facet normal 0.831118 -0.066518 0.552103 + outer loop + vertex 1.67126 1.32916 2.51771 + vertex 1.67068 1.32344 2.51791 + vertex 1.67329 1.32725 2.51443 + endloop + endfacet + facet normal 0.864337 0.0538004 0.500028 + outer loop + vertex 1.67662 1.32993 2.50865 + vertex 1.67645 1.33502 2.5084 + vertex 1.67513 1.3311 2.5111 + endloop + endfacet + facet normal 0.857729 0.01657 0.513835 + outer loop + vertex 1.67516 1.32584 2.51123 + vertex 1.67662 1.32993 2.50865 + vertex 1.67513 1.3311 2.5111 + endloop + endfacet + facet normal 0.867323 0.0161991 0.497482 + outer loop + vertex 1.67516 1.32584 2.51123 + vertex 1.67513 1.3311 2.5111 + vertex 1.67329 1.32725 2.51443 + endloop + endfacet + facet normal 0.876691 -0.00250541 0.481047 + outer loop + vertex 1.67513 1.3311 2.5111 + vertex 1.67335 1.33261 2.51435 + vertex 1.67329 1.32725 2.51443 + endloop + endfacet + facet normal 0.850391 -0.00149632 0.526149 + outer loop + vertex 1.67335 1.33261 2.51435 + vertex 1.67126 1.32916 2.51771 + vertex 1.67329 1.32725 2.51443 + endloop + endfacet + facet normal 0.869916 -0.0476619 0.490891 + outer loop + vertex 1.67149 1.33437 2.51782 + vertex 1.67126 1.32916 2.51771 + vertex 1.67335 1.33261 2.51435 + endloop + endfacet + facet normal 0.846165 0.117493 0.519808 + outer loop + vertex 1.67645 1.33502 2.5084 + vertex 1.67616 1.33967 2.50782 + vertex 1.67474 1.33724 2.51068 + endloop + endfacet + facet normal 0.837107 0.090227 0.539547 + outer loop + vertex 1.67513 1.3311 2.5111 + vertex 1.67645 1.33502 2.5084 + vertex 1.67474 1.33724 2.51068 + endloop + endfacet + facet normal 0.890394 0.087397 0.446722 + outer loop + vertex 1.67513 1.3311 2.5111 + vertex 1.67474 1.33724 2.51068 + vertex 1.67335 1.33261 2.51435 + endloop + endfacet + facet normal 0.917686 0.0386366 0.395424 + outer loop + vertex 1.67474 1.33724 2.51068 + vertex 1.67308 1.33789 2.51448 + vertex 1.67335 1.33261 2.51435 + endloop + endfacet + facet normal 0.888052 0.0355144 0.458369 + outer loop + vertex 1.67308 1.33789 2.51448 + vertex 1.67149 1.33437 2.51782 + vertex 1.67335 1.33261 2.51435 + endloop + endfacet + facet normal 0.914031 -0.0271055 0.404738 + outer loop + vertex 1.67155 1.33941 2.51803 + vertex 1.67149 1.33437 2.51782 + vertex 1.67308 1.33789 2.51448 + endloop + endfacet + facet normal 0.796707 0.0304223 0.603599 + outer loop + vertex 1.67383 1.34295 2.5116 + vertex 1.67474 1.33724 2.51068 + vertex 1.675 1.34393 2.51 + endloop + endfacet + facet normal 0.847137 -0.259924 0.463464 + outer loop + vertex 1.67383 1.34295 2.5116 + vertex 1.675 1.34393 2.51 + vertex 1.675 1.345 2.5106 + endloop + endfacet + facet normal 0.89191 0.0112137 0.452074 + outer loop + vertex 1.67474 1.33724 2.51068 + vertex 1.67616 1.33967 2.50782 + vertex 1.675 1.34393 2.51 + endloop + endfacet + facet normal 0.298634 -0.747983 0.592739 + outer loop + vertex 1.67768 1.345 2.51 + vertex 1.675 1.34393 2.51 + vertex 1.67666 1.34294 2.50791 + endloop + endfacet + facet normal 0.744336 -0.132405 0.654548 + outer loop + vertex 1.67616 1.33967 2.50782 + vertex 1.67666 1.34294 2.50791 + vertex 1.675 1.34393 2.51 + endloop + endfacet + facet normal 0.917903 0.0844534 0.387714 + outer loop + vertex 1.67474 1.33724 2.51068 + vertex 1.67383 1.34295 2.5116 + vertex 1.67308 1.33789 2.51448 + endloop + endfacet + facet normal 0.954338 0.0277464 0.297438 + outer loop + vertex 1.67383 1.34295 2.5116 + vertex 1.67279 1.34291 2.51491 + vertex 1.67308 1.33789 2.51448 + endloop + endfacet + facet normal 0.921274 0.0180884 0.388493 + outer loop + vertex 1.67279 1.34291 2.51491 + vertex 1.67155 1.33941 2.51803 + vertex 1.67308 1.33789 2.51448 + endloop + endfacet + facet normal 0.933869 -0.0141491 0.357334 + outer loop + vertex 1.67156 1.34441 2.51819 + vertex 1.67155 1.33941 2.51803 + vertex 1.67279 1.34291 2.51491 + endloop + endfacet + facet normal 0.340487 -0.195139 0.919777 + outer loop + vertex 1.67383 1.34295 2.5116 + vertex 1.675 1.35 2.51266 + vertex 1.67347 1.34783 2.51277 + endloop + endfacet + facet normal 0.823275 -0.21623 0.524845 + outer loop + vertex 1.67383 1.34295 2.5116 + vertex 1.675 1.345 2.5106 + vertex 1.675 1.35 2.51266 + endloop + endfacet + facet normal 0.595549 -0.697813 0.397967 + outer loop + vertex 1.67768 1.345 2.51 + vertex 1.67666 1.34294 2.50791 + vertex 1.68 1.34698 2.51 + endloop + endfacet + facet normal 0.954811 -0.000701623 0.297213 + outer loop + vertex 1.67383 1.34295 2.5116 + vertex 1.67347 1.34783 2.51277 + vertex 1.67279 1.34291 2.51491 + endloop + endfacet + facet normal 0.962888 -0.0138547 0.269546 + outer loop + vertex 1.67347 1.34783 2.51277 + vertex 1.67277 1.34797 2.51526 + vertex 1.67279 1.34291 2.51491 + endloop + endfacet + facet normal 0.932843 -0.0202061 0.359716 + outer loop + vertex 1.67277 1.34797 2.51526 + vertex 1.67156 1.34441 2.51819 + vertex 1.67279 1.34291 2.51491 + endloop + endfacet + facet normal 0.9277 -0.00732879 0.373254 + outer loop + vertex 1.67161 1.34945 2.51818 + vertex 1.67156 1.34441 2.51819 + vertex 1.67277 1.34797 2.51526 + endloop + endfacet + facet normal 0.234071 -0.117714 0.965067 + outer loop + vertex 1.675 1.355 2.51327 + vertex 1.67347 1.34783 2.51277 + vertex 1.675 1.35 2.51266 + endloop + endfacet + facet normal -0.000515722 -0.0697939 0.997561 + outer loop + vertex 1.67348 1.35291 2.51312 + vertex 1.67347 1.34783 2.51277 + vertex 1.675 1.355 2.51327 + endloop + endfacet + facet normal 0.962669 -0.0207573 0.269885 + outer loop + vertex 1.67347 1.34783 2.51277 + vertex 1.67348 1.35291 2.51312 + vertex 1.67277 1.34797 2.51526 + endloop + endfacet + facet normal 0.958721 -0.0140888 0.284 + outer loop + vertex 1.67348 1.35291 2.51312 + vertex 1.67284 1.35314 2.51528 + vertex 1.67277 1.34797 2.51526 + endloop + endfacet + facet normal 0.926458 -0.0140275 0.376137 + outer loop + vertex 1.67284 1.35314 2.51528 + vertex 1.67161 1.34945 2.51818 + vertex 1.67277 1.34797 2.51526 + endloop + endfacet + facet normal 0.919242 0.00215812 0.393688 + outer loop + vertex 1.67164 1.35448 2.51806 + vertex 1.67161 1.34945 2.51818 + vertex 1.67284 1.35314 2.51528 + endloop + endfacet + facet normal -0.0987358 0.00199293 0.995112 + outer loop + vertex 1.675 1.36 2.51326 + vertex 1.67348 1.35291 2.51312 + vertex 1.675 1.355 2.51327 + endloop + endfacet + facet normal -0.0671336 -0.00485301 0.997732 + outer loop + vertex 1.67356 1.35816 2.51315 + vertex 1.67348 1.35291 2.51312 + vertex 1.675 1.36 2.51326 + endloop + endfacet + facet normal 0.958585 -0.0171441 0.284289 + outer loop + vertex 1.67348 1.35291 2.51312 + vertex 1.67356 1.35816 2.51315 + vertex 1.67284 1.35314 2.51528 + endloop + endfacet + facet normal 0.945298 0.00250638 0.326199 + outer loop + vertex 1.67356 1.35816 2.51315 + vertex 1.67287 1.35828 2.51516 + vertex 1.67284 1.35314 2.51528 + endloop + endfacet + facet normal 0.919588 0.00418559 0.392862 + outer loop + vertex 1.67287 1.35828 2.51516 + vertex 1.67164 1.35448 2.51806 + vertex 1.67284 1.35314 2.51528 + endloop + endfacet + facet normal 0.916314 0.010925 0.400312 + outer loop + vertex 1.6716 1.35952 2.51802 + vertex 1.67164 1.35448 2.51806 + vertex 1.67287 1.35828 2.51516 + endloop + endfacet + facet normal -0.083389 0.0079352 0.996485 + outer loop + vertex 1.675 1.365 2.51322 + vertex 1.67356 1.35816 2.51315 + vertex 1.675 1.36 2.51326 + endloop + endfacet + facet normal -0.116649 0.0149703 0.99306 + outer loop + vertex 1.67358 1.36334 2.51308 + vertex 1.67356 1.35816 2.51315 + vertex 1.675 1.365 2.51322 + endloop + endfacet + facet normal 0.945288 0.00190994 0.326232 + outer loop + vertex 1.67356 1.35816 2.51315 + vertex 1.67358 1.36334 2.51308 + vertex 1.67287 1.35828 2.51516 + endloop + endfacet + facet normal 0.933013 0.0172866 0.359427 + outer loop + vertex 1.67358 1.36334 2.51308 + vertex 1.67281 1.36334 2.51507 + vertex 1.67287 1.35828 2.51516 + endloop + endfacet + facet normal 0.917307 0.017795 0.397782 + outer loop + vertex 1.67281 1.36334 2.51507 + vertex 1.6716 1.35952 2.51802 + vertex 1.67287 1.35828 2.51516 + endloop + endfacet + facet normal 0.920801 0.0106064 0.389888 + outer loop + vertex 1.67152 1.36461 2.51807 + vertex 1.6716 1.35952 2.51802 + vertex 1.67281 1.36334 2.51507 + endloop + endfacet + facet normal -0.101731 0.00199232 0.99481 + outer loop + vertex 1.675 1.37 2.51321 + vertex 1.67358 1.36334 2.51308 + vertex 1.675 1.365 2.51322 + endloop + endfacet + facet normal -0.161396 0.0149188 0.986777 + outer loop + vertex 1.67353 1.36839 2.51299 + vertex 1.67358 1.36334 2.51308 + vertex 1.675 1.37 2.51321 + endloop + endfacet + facet normal 0.933054 0.0145948 0.359441 + outer loop + vertex 1.67358 1.36334 2.51308 + vertex 1.67353 1.36839 2.51299 + vertex 1.67281 1.36334 2.51507 + endloop + endfacet + facet normal 0.928813 0.0195542 0.370033 + outer loop + vertex 1.67353 1.36839 2.51299 + vertex 1.67272 1.36835 2.51502 + vertex 1.67281 1.36334 2.51507 + endloop + endfacet + facet normal 0.922029 0.0195859 0.386626 + outer loop + vertex 1.67272 1.36835 2.51502 + vertex 1.67152 1.36461 2.51807 + vertex 1.67281 1.36334 2.51507 + endloop + endfacet + facet normal 0.927918 0.00638054 0.372729 + outer loop + vertex 1.67156 1.36961 2.51789 + vertex 1.67152 1.36461 2.51807 + vertex 1.67272 1.36835 2.51502 + endloop + endfacet + facet normal -0.14969 0.00396027 0.988725 + outer loop + vertex 1.675 1.375 2.51319 + vertex 1.67353 1.36839 2.51299 + vertex 1.675 1.37 2.51321 + endloop + endfacet + facet normal -0.176084 0.00996477 0.984325 + outer loop + vertex 1.67345 1.37334 2.51293 + vertex 1.67353 1.36839 2.51299 + vertex 1.675 1.375 2.51319 + endloop + endfacet + facet normal 0.928788 0.0205339 0.370043 + outer loop + vertex 1.67353 1.36839 2.51299 + vertex 1.67345 1.37334 2.51293 + vertex 1.67272 1.36835 2.51502 + endloop + endfacet + facet normal 0.923767 0.0262999 0.38205 + outer loop + vertex 1.67345 1.37334 2.51293 + vertex 1.67263 1.37321 2.51491 + vertex 1.67272 1.36835 2.51502 + endloop + endfacet + facet normal 0.930566 0.0260173 0.365199 + outer loop + vertex 1.67263 1.37321 2.51491 + vertex 1.67156 1.36961 2.51789 + vertex 1.67272 1.36835 2.51502 + endloop + endfacet + facet normal 0.936616 0.0117968 0.350158 + outer loop + vertex 1.67164 1.37428 2.51753 + vertex 1.67156 1.36961 2.51789 + vertex 1.67263 1.37321 2.51491 + endloop + endfacet + facet normal -0.169861 0.0039472 0.98546 + outer loop + vertex 1.675 1.38 2.51317 + vertex 1.67345 1.37334 2.51293 + vertex 1.675 1.375 2.51319 + endloop + endfacet + facet normal -0.14295 -0.00249176 0.989727 + outer loop + vertex 1.67334 1.37825 2.51293 + vertex 1.67345 1.37334 2.51293 + vertex 1.675 1.38 2.51317 + endloop + endfacet + facet normal 0.924031 0.0203862 0.381773 + outer loop + vertex 1.67345 1.37334 2.51293 + vertex 1.67334 1.37825 2.51293 + vertex 1.67263 1.37321 2.51491 + endloop + endfacet + facet normal 0.918785 0.0258908 0.393909 + outer loop + vertex 1.67334 1.37825 2.51293 + vertex 1.67253 1.37771 2.51485 + vertex 1.67263 1.37321 2.51491 + endloop + endfacet + facet normal 0.938213 0.0257778 0.345097 + outer loop + vertex 1.67253 1.37771 2.51485 + vertex 1.67164 1.37428 2.51753 + vertex 1.67263 1.37321 2.51491 + endloop + endfacet + facet normal 0.938902 0.0242214 0.343333 + outer loop + vertex 1.67172 1.37806 2.51704 + vertex 1.67164 1.37428 2.51753 + vertex 1.67253 1.37771 2.51485 + endloop + endfacet + facet normal -0.147552 0.00198079 0.989052 + outer loop + vertex 1.675 1.385 2.51316 + vertex 1.67334 1.37825 2.51293 + vertex 1.675 1.38 2.51317 + endloop + endfacet + facet normal 0.0285362 -0.0417214 0.998722 + outer loop + vertex 1.67312 1.38329 2.51314 + vertex 1.67334 1.37825 2.51293 + vertex 1.675 1.385 2.51316 + endloop + endfacet + facet normal 0.907213 0.0493485 0.417768 + outer loop + vertex 1.67228 1.3809 2.51525 + vertex 1.67312 1.38329 2.51314 + vertex 1.67225 1.38493 2.51483 + endloop + endfacet + facet normal 0.919264 0.02321 0.392956 + outer loop + vertex 1.67228 1.3809 2.51525 + vertex 1.67253 1.37771 2.51485 + vertex 1.67312 1.38329 2.51314 + endloop + endfacet + facet normal 0.919103 0.0233402 0.393325 + outer loop + vertex 1.67253 1.37771 2.51485 + vertex 1.67334 1.37825 2.51293 + vertex 1.67312 1.38329 2.51314 + endloop + endfacet + facet normal 0.939074 0.0310454 0.34231 + outer loop + vertex 1.67253 1.37771 2.51485 + vertex 1.67228 1.3809 2.51525 + vertex 1.67172 1.37806 2.51704 + endloop + endfacet + facet normal -0.0130108 0.00400506 0.999907 + outer loop + vertex 1.675 1.39 2.51314 + vertex 1.67312 1.38329 2.51314 + vertex 1.675 1.385 2.51316 + endloop + endfacet + facet normal -0.205944 0.0581184 0.976836 + outer loop + vertex 1.67317 1.38913 2.51281 + vertex 1.67312 1.38329 2.51314 + vertex 1.675 1.39 2.51314 + endloop + endfacet + facet normal 0.896348 0.0177924 0.442993 + outer loop + vertex 1.67317 1.38913 2.51281 + vertex 1.67225 1.38493 2.51483 + vertex 1.67312 1.38329 2.51314 + endloop + endfacet + facet normal 0.901063 0.0122048 0.433517 + outer loop + vertex 1.67227 1.3898 2.51465 + vertex 1.67225 1.38493 2.51483 + vertex 1.67317 1.38913 2.51281 + endloop + endfacet + facet normal -0.181457 0.00393891 0.983391 + outer loop + vertex 1.675 1.395 2.51312 + vertex 1.67317 1.38913 2.51281 + vertex 1.675 1.39 2.51314 + endloop + endfacet + facet normal -0.257714 0.0286835 0.965795 + outer loop + vertex 1.67321 1.39417 2.51267 + vertex 1.67317 1.38913 2.51281 + vertex 1.675 1.395 2.51312 + endloop + endfacet + facet normal 0.900137 0.00530925 0.435574 + outer loop + vertex 1.67321 1.39417 2.51267 + vertex 1.67227 1.3898 2.51465 + vertex 1.67317 1.38913 2.51281 + endloop + endfacet + facet normal 0.900425 0.0049783 0.434982 + outer loop + vertex 1.67229 1.39464 2.51456 + vertex 1.67227 1.3898 2.51465 + vertex 1.67321 1.39417 2.51267 + endloop + endfacet + facet normal -0.247014 0.00388128 0.969004 + outer loop + vertex 1.675 1.4 2.5131 + vertex 1.67321 1.39417 2.51267 + vertex 1.675 1.395 2.51312 + endloop + endfacet + facet normal -0.291562 0.0185222 0.956372 + outer loop + vertex 1.67319 1.39901 2.51257 + vertex 1.67321 1.39417 2.51267 + vertex 1.675 1.4 2.5131 + endloop + endfacet + facet normal 0.900985 0.0111719 0.433705 + outer loop + vertex 1.67319 1.39901 2.51257 + vertex 1.67229 1.39464 2.51456 + vertex 1.67321 1.39417 2.51267 + endloop + endfacet + facet normal 0.807066 0.0983919 0.582205 + outer loop + vertex 1.67201 1.39949 2.51413 + vertex 1.67229 1.39464 2.51456 + vertex 1.67319 1.39901 2.51257 + endloop + endfacet + facet normal -0.282286 0 0.95933 + outer loop + vertex 1.675 1.405 2.5131 + vertex 1.67319 1.39901 2.51257 + vertex 1.675 1.4 2.5131 + endloop + endfacet + facet normal -0.401058 0.0397462 0.91519 + outer loop + vertex 1.67298 1.40376 2.51227 + vertex 1.67319 1.39901 2.51257 + vertex 1.675 1.405 2.5131 + endloop + endfacet + facet normal 0.805099 0.072356 0.588711 + outer loop + vertex 1.67298 1.40376 2.51227 + vertex 1.67201 1.39949 2.51413 + vertex 1.67319 1.39901 2.51257 + endloop + endfacet + facet normal 0.564261 0.218135 0.796258 + outer loop + vertex 1.6714 1.40453 2.51318 + vertex 1.67201 1.39949 2.51413 + vertex 1.67298 1.40376 2.51227 + endloop + endfacet + facet normal -0.381493 0.00185125 0.92437 + outer loop + vertex 1.675 1.41 2.51309 + vertex 1.67298 1.40376 2.51227 + vertex 1.675 1.405 2.5131 + endloop + endfacet + facet normal -0.490888 0.0443073 0.870095 + outer loop + vertex 1.67268 1.40838 2.51186 + vertex 1.67298 1.40376 2.51227 + vertex 1.675 1.41 2.51309 + endloop + endfacet + facet normal 0.534878 0.108902 0.837882 + outer loop + vertex 1.67268 1.40838 2.51186 + vertex 1.6714 1.40453 2.51318 + vertex 1.67298 1.40376 2.51227 + endloop + endfacet + facet normal 0.330254 0.205554 0.921238 + outer loop + vertex 1.67101 1.40877 2.51238 + vertex 1.6714 1.40453 2.51318 + vertex 1.67268 1.40838 2.51186 + endloop + endfacet + facet normal -0.46535 -0.00354529 0.88512 + outer loop + vertex 1.675 1.415 2.51311 + vertex 1.67268 1.40838 2.51186 + vertex 1.675 1.41 2.51309 + endloop + endfacet + facet normal -0.508942 0.0163263 0.860646 + outer loop + vertex 1.6725 1.41295 2.51167 + vertex 1.67268 1.40838 2.51186 + vertex 1.675 1.415 2.51311 + endloop + endfacet + facet normal 0.303626 0.0519022 0.951377 + outer loop + vertex 1.6725 1.41295 2.51167 + vertex 1.67101 1.40877 2.51238 + vertex 1.67268 1.40838 2.51186 + endloop + endfacet + facet normal 0.357632 0.0295606 0.933395 + outer loop + vertex 1.67101 1.41285 2.51225 + vertex 1.67101 1.40877 2.51238 + vertex 1.6725 1.41295 2.51167 + endloop + endfacet + facet normal -0.465217 -0.0530463 0.883606 + outer loop + vertex 1.675 1.42 2.51341 + vertex 1.6725 1.41295 2.51167 + vertex 1.675 1.415 2.51311 + endloop + endfacet + facet normal -0.552242 -0.00988757 0.833625 + outer loop + vertex 1.6725 1.41786 2.51173 + vertex 1.6725 1.41295 2.51167 + vertex 1.675 1.42 2.51341 + endloop + endfacet + facet normal 0.360211 -0.0106841 0.93281 + outer loop + vertex 1.6725 1.41786 2.51173 + vertex 1.67101 1.41285 2.51225 + vertex 1.6725 1.41295 2.51167 + endloop + endfacet + facet normal 0.372938 -0.0149888 0.927735 + outer loop + vertex 1.67121 1.41784 2.51225 + vertex 1.67101 1.41285 2.51225 + vertex 1.6725 1.41786 2.51173 + endloop + endfacet + facet normal -0.529216 -0.0474247 0.847161 + outer loop + vertex 1.675 1.425 2.51369 + vertex 1.6725 1.41786 2.51173 + vertex 1.675 1.42 2.51341 + endloop + endfacet + facet normal -0.610127 -0.00402041 0.792293 + outer loop + vertex 1.67263 1.42327 2.51185 + vertex 1.6725 1.41786 2.51173 + vertex 1.675 1.425 2.51369 + endloop + endfacet + facet normal 0.373043 -0.0302617 0.92732 + outer loop + vertex 1.67263 1.42327 2.51185 + vertex 1.67121 1.41784 2.51225 + vertex 1.6725 1.41786 2.51173 + endloop + endfacet + facet normal 0.403476 -0.0391567 0.914152 + outer loop + vertex 1.67167 1.42335 2.51228 + vertex 1.67121 1.41784 2.51225 + vertex 1.67263 1.42327 2.51185 + endloop + endfacet + facet normal -0.61483 0.00631765 0.788635 + outer loop + vertex 1.675 1.43 2.51365 + vertex 1.67263 1.42327 2.51185 + vertex 1.675 1.425 2.51369 + endloop + endfacet + facet normal -0.595053 -0.00466984 0.803673 + outer loop + vertex 1.6728 1.42879 2.51202 + vertex 1.67263 1.42327 2.51185 + vertex 1.675 1.43 2.51365 + endloop + endfacet + facet normal 0.403431 -0.0396573 0.91415 + outer loop + vertex 1.6728 1.42879 2.51202 + vertex 1.67167 1.42335 2.51228 + vertex 1.67263 1.42327 2.51185 + endloop + endfacet + facet normal 0.422084 -0.0439498 0.905491 + outer loop + vertex 1.6721 1.42889 2.51235 + vertex 1.67167 1.42335 2.51228 + vertex 1.6728 1.42879 2.51202 + endloop + endfacet + facet normal -0.547034 -0.124188 0.827847 + outer loop + vertex 1.675 1.435 2.5144 + vertex 1.6728 1.42879 2.51202 + vertex 1.675 1.43 2.51365 + endloop + endfacet + facet normal -0.730051 -0.00402662 0.683381 + outer loop + vertex 1.67299 1.43377 2.51225 + vertex 1.6728 1.42879 2.51202 + vertex 1.675 1.435 2.5144 + endloop + endfacet + facet normal 0.420127 -0.0578273 0.905621 + outer loop + vertex 1.67299 1.43377 2.51225 + vertex 1.6721 1.42889 2.51235 + vertex 1.6728 1.42879 2.51202 + endloop + endfacet + facet normal 0.436982 -0.0610798 0.897394 + outer loop + vertex 1.67256 1.43363 2.51245 + vertex 1.6721 1.42889 2.51235 + vertex 1.67299 1.43377 2.51225 + endloop + endfacet + facet normal -0.705481 -0.0802815 0.704167 + outer loop + vertex 1.675 1.44 2.51497 + vertex 1.67299 1.43377 2.51225 + vertex 1.675 1.435 2.5144 + endloop + endfacet + facet normal -0.813732 0.00833384 0.58118 + outer loop + vertex 1.67322 1.43685 2.51252 + vertex 1.67299 1.43377 2.51225 + vertex 1.675 1.44 2.51497 + endloop + endfacet + facet normal 0.448008 -0.111752 0.887018 + outer loop + vertex 1.67322 1.43685 2.51252 + vertex 1.67256 1.43363 2.51245 + vertex 1.67299 1.43377 2.51225 + endloop + endfacet + facet normal 0.974386 -0.195813 -0.110583 + outer loop + vertex 1.67329 1.43702 2.51288 + vertex 1.67256 1.43363 2.51245 + vertex 1.67322 1.43685 2.51252 + endloop + endfacet + facet normal -0.685567 -0.163985 0.7093 + outer loop + vertex 1.675 1.44 2.51497 + vertex 1.675 1.44013 2.515 + vertex 1.67322 1.43685 2.51252 + endloop + endfacet + facet normal 0.857108 -0.511615 0.0601393 + outer loop + vertex 1.67322 1.43685 2.51252 + vertex 1.675 1.44013 2.515 + vertex 1.67329 1.43702 2.51288 + endloop + endfacet + facet normal -0.855695 0.0345352 0.516326 + outer loop + vertex 1.67363 1.58441 2.51256 + vertex 1.675 1.58171 2.515 + vertex 1.675 1.585 2.51478 + endloop + endfacet + facet normal -0.745915 0.198305 0.635835 + outer loop + vertex 1.67363 1.58441 2.51256 + vertex 1.67333 1.58413 2.51229 + vertex 1.675 1.58171 2.515 + endloop + endfacet + facet normal -0.857388 0.0562776 0.511585 + outer loop + vertex 1.675 1.59 2.51423 + vertex 1.67363 1.58441 2.51256 + vertex 1.675 1.585 2.51478 + endloop + endfacet + facet normal -0.812374 0.0240126 0.582642 + outer loop + vertex 1.67331 1.58774 2.51197 + vertex 1.67363 1.58441 2.51256 + vertex 1.675 1.59 2.51423 + endloop + endfacet + facet normal -0.692028 0.0600316 0.719371 + outer loop + vertex 1.67331 1.58774 2.51197 + vertex 1.67333 1.58413 2.51229 + vertex 1.67363 1.58441 2.51256 + endloop + endfacet + facet normal 0.499604 0.0804915 0.862506 + outer loop + vertex 1.67302 1.58782 2.51213 + vertex 1.67333 1.58413 2.51229 + vertex 1.67331 1.58774 2.51197 + endloop + endfacet + facet normal -0.806819 0.0118015 0.590681 + outer loop + vertex 1.675 1.595 2.51413 + vertex 1.67331 1.58774 2.51197 + vertex 1.675 1.59 2.51423 + endloop + endfacet + facet normal -0.772562 -0.00935396 0.634871 + outer loop + vertex 1.67315 1.59287 2.51185 + vertex 1.67331 1.58774 2.51197 + vertex 1.675 1.595 2.51413 + endloop + endfacet + facet normal 0.490643 0.0340079 0.870697 + outer loop + vertex 1.67315 1.59287 2.51185 + vertex 1.67302 1.58782 2.51213 + vertex 1.67331 1.58774 2.51197 + endloop + endfacet + facet normal 0.452205 0.0361472 0.891181 + outer loop + vertex 1.67258 1.59333 2.51213 + vertex 1.67302 1.58782 2.51213 + vertex 1.67315 1.59287 2.51185 + endloop + endfacet + facet normal -0.78141 0.00999657 0.623938 + outer loop + vertex 1.675 1.6 2.51405 + vertex 1.67315 1.59287 2.51185 + vertex 1.675 1.595 2.51413 + endloop + endfacet + facet normal -0.702031 -0.0374343 0.711162 + outer loop + vertex 1.67286 1.59866 2.51187 + vertex 1.67315 1.59287 2.51185 + vertex 1.675 1.6 2.51405 + endloop + endfacet + facet normal 0.442034 0.0200254 0.896775 + outer loop + vertex 1.67286 1.59866 2.51187 + vertex 1.67258 1.59333 2.51213 + vertex 1.67315 1.59287 2.51185 + endloop + endfacet + facet normal 0.512493 0.0144406 0.85857 + outer loop + vertex 1.67175 1.5996 2.51251 + vertex 1.67258 1.59333 2.51213 + vertex 1.67286 1.59866 2.51187 + endloop + endfacet + facet normal -0.710188 -0.0126538 0.703898 + outer loop + vertex 1.675 1.605 2.51414 + vertex 1.67286 1.59866 2.51187 + vertex 1.675 1.6 2.51405 + endloop + endfacet + facet normal -0.644564 -0.0557789 0.762513 + outer loop + vertex 1.67249 1.6042 2.51196 + vertex 1.67286 1.59866 2.51187 + vertex 1.675 1.605 2.51414 + endloop + endfacet + facet normal 0.515917 0.0199258 0.856407 + outer loop + vertex 1.67249 1.6042 2.51196 + vertex 1.67175 1.5996 2.51251 + vertex 1.67286 1.59866 2.51187 + endloop + endfacet + facet normal 0.430725 0.0391243 0.901635 + outer loop + vertex 1.67057 1.60491 2.51285 + vertex 1.67175 1.5996 2.51251 + vertex 1.67249 1.6042 2.51196 + endloop + endfacet + facet normal -0.666339 0.066823 0.742648 + outer loop + vertex 1.675 1.61 2.51369 + vertex 1.67249 1.6042 2.51196 + vertex 1.675 1.605 2.51414 + endloop + endfacet + facet normal -0.532382 -0.0220107 0.846218 + outer loop + vertex 1.6723 1.60913 2.51197 + vertex 1.67249 1.6042 2.51196 + vertex 1.675 1.61 2.51369 + endloop + endfacet + facet normal 0.423596 0.0144556 0.905736 + outer loop + vertex 1.6723 1.60913 2.51197 + vertex 1.67057 1.60491 2.51285 + vertex 1.67249 1.6042 2.51196 + endloop + endfacet + facet normal 0.458493 -0.00346487 0.888691 + outer loop + vertex 1.67062 1.6094 2.51284 + vertex 1.67057 1.60491 2.51285 + vertex 1.6723 1.60913 2.51197 + endloop + endfacet + facet normal -0.547724 0.0467636 0.835351 + outer loop + vertex 1.675 1.615 2.51341 + vertex 1.6723 1.60913 2.51197 + vertex 1.675 1.61 2.51369 + endloop + endfacet + facet normal -0.429614 -0.0239775 0.902694 + outer loop + vertex 1.67248 1.61375 2.51218 + vertex 1.6723 1.60913 2.51197 + vertex 1.675 1.615 2.51341 + endloop + endfacet + facet normal 0.451067 -0.0563309 0.890711 + outer loop + vertex 1.67248 1.61375 2.51218 + vertex 1.67062 1.6094 2.51284 + vertex 1.6723 1.60913 2.51197 + endloop + endfacet + facet normal 0.799024 -0.25827 0.543008 + outer loop + vertex 1.67115 1.61362 2.51406 + vertex 1.67062 1.6094 2.51284 + vertex 1.67248 1.61375 2.51218 + endloop + endfacet + facet normal -0.443659 0.0107682 0.896131 + outer loop + vertex 1.675 1.62 2.51335 + vertex 1.67248 1.61375 2.51218 + vertex 1.675 1.615 2.51341 + endloop + endfacet + facet normal -0.264398 -0.0738895 0.961579 + outer loop + vertex 1.6729 1.61874 2.51268 + vertex 1.67248 1.61375 2.51218 + vertex 1.675 1.62 2.51335 + endloop + endfacet + facet normal 0.816039 -0.126757 0.563926 + outer loop + vertex 1.6729 1.61874 2.51268 + vertex 1.67115 1.61362 2.51406 + vertex 1.67248 1.61375 2.51218 + endloop + endfacet + facet normal 0.894626 -0.197628 0.400734 + outer loop + vertex 1.67206 1.61919 2.51478 + vertex 1.67115 1.61362 2.51406 + vertex 1.6729 1.61874 2.51268 + endloop + endfacet + facet normal -0.310889 0.0095169 0.950399 + outer loop + vertex 1.675 1.625 2.5133 + vertex 1.6729 1.61874 2.51268 + vertex 1.675 1.62 2.51335 + endloop + endfacet + facet normal -0.153345 -0.0468799 0.98706 + outer loop + vertex 1.67317 1.62417 2.51298 + vertex 1.6729 1.61874 2.51268 + vertex 1.675 1.625 2.5133 + endloop + endfacet + facet normal 0.921191 -0.065642 0.383533 + outer loop + vertex 1.67317 1.62417 2.51298 + vertex 1.67206 1.61919 2.51478 + vertex 1.6729 1.61874 2.51268 + endloop + endfacet + facet normal 0.946707 -0.0992425 0.306427 + outer loop + vertex 1.67236 1.62321 2.51515 + vertex 1.67206 1.61919 2.51478 + vertex 1.67317 1.62417 2.51298 + endloop + endfacet + facet normal -0.177536 0.00788336 0.984083 + outer loop + vertex 1.675 1.63 2.51326 + vertex 1.67317 1.62417 2.51298 + vertex 1.675 1.625 2.5133 + endloop + endfacet + facet normal -0.498184 0.114805 0.859437 + outer loop + vertex 1.67343 1.62928 2.51245 + vertex 1.67317 1.62417 2.51298 + vertex 1.675 1.63 2.51326 + endloop + endfacet + facet normal 0.94668 0.0051193 0.322136 + outer loop + vertex 1.67236 1.62321 2.51515 + vertex 1.67268 1.62726 2.51416 + vertex 1.6718 1.62503 2.51678 + endloop + endfacet + facet normal 0.935794 0.0132987 0.352298 + outer loop + vertex 1.67236 1.62321 2.51515 + vertex 1.67317 1.62417 2.51298 + vertex 1.67268 1.62726 2.51416 + endloop + endfacet + facet normal 0.917819 -0.00668758 0.396942 + outer loop + vertex 1.67317 1.62417 2.51298 + vertex 1.67343 1.62928 2.51245 + vertex 1.67268 1.62726 2.51416 + endloop + endfacet + facet normal 0.945972 0.00776549 0.324154 + outer loop + vertex 1.67268 1.62726 2.51416 + vertex 1.67183 1.6278 2.51661 + vertex 1.6718 1.62503 2.51678 + endloop + endfacet + facet normal -0.459063 -0.00355842 0.888397 + outer loop + vertex 1.675 1.635 2.51328 + vertex 1.67343 1.62928 2.51245 + vertex 1.675 1.63 2.51326 + endloop + endfacet + facet normal -0.024461 -0.137505 0.990199 + outer loop + vertex 1.67319 1.63304 2.51296 + vertex 1.67343 1.62928 2.51245 + vertex 1.675 1.635 2.51328 + endloop + endfacet + facet normal 0.914502 0.0277084 0.403631 + outer loop + vertex 1.6724 1.63041 2.51493 + vertex 1.67319 1.63304 2.51296 + vertex 1.67233 1.63429 2.51482 + endloop + endfacet + facet normal 0.931299 -0.00682936 0.36419 + outer loop + vertex 1.6724 1.63041 2.51493 + vertex 1.67268 1.62726 2.51416 + vertex 1.67319 1.63304 2.51296 + endloop + endfacet + facet normal 0.91333 0.00368539 0.407203 + outer loop + vertex 1.67268 1.62726 2.51416 + vertex 1.67343 1.62928 2.51245 + vertex 1.67319 1.63304 2.51296 + endloop + endfacet + facet normal 0.945745 0.00407045 0.324884 + outer loop + vertex 1.67268 1.62726 2.51416 + vertex 1.6724 1.63041 2.51493 + vertex 1.67183 1.6278 2.51661 + endloop + endfacet + facet normal -0.168375 -0.00394822 0.985715 + outer loop + vertex 1.675 1.64 2.5133 + vertex 1.67319 1.63304 2.51296 + vertex 1.675 1.635 2.51328 + endloop + endfacet + facet normal -0.203494 0.0055122 0.979061 + outer loop + vertex 1.67322 1.63868 2.51294 + vertex 1.67319 1.63304 2.51296 + vertex 1.675 1.64 2.5133 + endloop + endfacet + facet normal 0.906879 -0.00374162 0.421376 + outer loop + vertex 1.67322 1.63868 2.51294 + vertex 1.67233 1.63429 2.51482 + vertex 1.67319 1.63304 2.51296 + endloop + endfacet + facet normal 0.90989 -0.00718594 0.414787 + outer loop + vertex 1.6723 1.63907 2.51497 + vertex 1.67233 1.63429 2.51482 + vertex 1.67322 1.63868 2.51294 + endloop + endfacet + facet normal -0.200965 0.00196186 0.979596 + outer loop + vertex 1.675 1.645 2.51329 + vertex 1.67322 1.63868 2.51294 + vertex 1.675 1.64 2.5133 + endloop + endfacet + facet normal -0.124352 -0.0202708 0.992031 + outer loop + vertex 1.67326 1.64409 2.51305 + vertex 1.67322 1.63868 2.51294 + vertex 1.675 1.645 2.51329 + endloop + endfacet + facet normal 0.909215 -0.0154086 0.416042 + outer loop + vertex 1.67326 1.64409 2.51305 + vertex 1.6723 1.63907 2.51497 + vertex 1.67322 1.63868 2.51294 + endloop + endfacet + facet normal 0.934128 -0.0438092 0.354238 + outer loop + vertex 1.67238 1.643 2.51523 + vertex 1.6723 1.63907 2.51497 + vertex 1.67326 1.64409 2.51305 + endloop + endfacet + facet normal -0.133803 -0.00198471 0.991006 + outer loop + vertex 1.675 1.65 2.5133 + vertex 1.67326 1.64409 2.51305 + vertex 1.675 1.645 2.51329 + endloop + endfacet + facet normal -0.548566 0.126832 0.826431 + outer loop + vertex 1.67357 1.64924 2.51247 + vertex 1.67326 1.64409 2.51305 + vertex 1.675 1.65 2.5133 + endloop + endfacet + facet normal 0.933574 -0.0181435 0.357924 + outer loop + vertex 1.67238 1.643 2.51523 + vertex 1.67282 1.64761 2.51433 + vertex 1.67174 1.64496 2.51701 + endloop + endfacet + facet normal 0.930278 -0.0161513 0.366499 + outer loop + vertex 1.67238 1.643 2.51523 + vertex 1.67326 1.64409 2.51305 + vertex 1.67282 1.64761 2.51433 + endloop + endfacet + facet normal 0.931148 -0.015252 0.364323 + outer loop + vertex 1.67326 1.64409 2.51305 + vertex 1.67357 1.64924 2.51247 + vertex 1.67282 1.64761 2.51433 + endloop + endfacet + facet normal 0.935123 -0.0231985 0.353563 + outer loop + vertex 1.67282 1.64761 2.51433 + vertex 1.67166 1.64902 2.51749 + vertex 1.67174 1.64496 2.51701 + endloop + endfacet + facet normal -0.501071 -0.0051994 0.865391 + outer loop + vertex 1.675 1.655 2.51333 + vertex 1.67357 1.64924 2.51247 + vertex 1.675 1.65 2.5133 + endloop + endfacet + facet normal -0.206979 -0.0942034 0.973799 + outer loop + vertex 1.67355 1.6531 2.51284 + vertex 1.67357 1.64924 2.51247 + vertex 1.675 1.655 2.51333 + endloop + endfacet + facet normal 0.934659 -0.0281104 0.354432 + outer loop + vertex 1.67357 1.64924 2.51247 + vertex 1.67355 1.6531 2.51284 + vertex 1.67282 1.64761 2.51433 + endloop + endfacet + facet normal 0.947442 -0.0398525 0.317435 + outer loop + vertex 1.67355 1.6531 2.51284 + vertex 1.67285 1.65278 2.5149 + vertex 1.67282 1.64761 2.51433 + endloop + endfacet + facet normal 0.931209 -0.0446494 0.361741 + outer loop + vertex 1.67285 1.65278 2.5149 + vertex 1.67166 1.64902 2.51749 + vertex 1.67282 1.64761 2.51433 + endloop + endfacet + facet normal 0.924297 -0.0295437 0.380528 + outer loop + vertex 1.67164 1.6539 2.51792 + vertex 1.67166 1.64902 2.51749 + vertex 1.67285 1.65278 2.5149 + endloop + endfacet + facet normal -0.321271 0 0.946987 + outer loop + vertex 1.675 1.66 2.51333 + vertex 1.67355 1.6531 2.51284 + vertex 1.675 1.655 2.51333 + endloop + endfacet + facet normal -0.0749734 -0.0552097 0.995656 + outer loop + vertex 1.67355 1.65793 2.51311 + vertex 1.67355 1.6531 2.51284 + vertex 1.675 1.66 2.51333 + endloop + endfacet + facet normal 0.946992 -0.0169501 0.320808 + outer loop + vertex 1.67355 1.6531 2.51284 + vertex 1.67355 1.65793 2.51311 + vertex 1.67285 1.65278 2.5149 + endloop + endfacet + facet normal 0.94815 -0.0183327 0.317295 + outer loop + vertex 1.67355 1.65793 2.51311 + vertex 1.67283 1.65772 2.51522 + vertex 1.67285 1.65278 2.5149 + endloop + endfacet + facet normal 0.925403 -0.0223542 0.378326 + outer loop + vertex 1.67283 1.65772 2.51522 + vertex 1.67164 1.6539 2.51792 + vertex 1.67285 1.65278 2.5149 + endloop + endfacet + facet normal 0.919925 -0.0110336 0.39194 + outer loop + vertex 1.6716 1.6588 2.51814 + vertex 1.67164 1.6539 2.51792 + vertex 1.67283 1.65772 2.51522 + endloop + endfacet + facet normal -0.157905 0.00395515 0.987446 + outer loop + vertex 1.675 1.665 2.51331 + vertex 1.67355 1.65793 2.51311 + vertex 1.675 1.66 2.51333 + endloop + endfacet + facet normal -0.0354698 -0.0215562 0.999138 + outer loop + vertex 1.67349 1.66297 2.51321 + vertex 1.67355 1.65793 2.51311 + vertex 1.675 1.665 2.51331 + endloop + endfacet + facet normal 0.947609 0.00469956 0.319397 + outer loop + vertex 1.67355 1.65793 2.51311 + vertex 1.67349 1.66297 2.51321 + vertex 1.67283 1.65772 2.51522 + endloop + endfacet + facet normal 0.939718 0.0141979 0.341655 + outer loop + vertex 1.67349 1.66297 2.51321 + vertex 1.67274 1.66274 2.51528 + vertex 1.67283 1.65772 2.51522 + endloop + endfacet + facet normal 0.923133 0.0133833 0.384248 + outer loop + vertex 1.67274 1.66274 2.51528 + vertex 1.6716 1.6588 2.51814 + vertex 1.67283 1.65772 2.51522 + endloop + endfacet + facet normal 0.919556 0.0203678 0.39243 + outer loop + vertex 1.67149 1.66381 2.51814 + vertex 1.6716 1.6588 2.51814 + vertex 1.67274 1.66274 2.51528 + endloop + endfacet + facet normal -0.0722564 0.00599234 0.997368 + outer loop + vertex 1.675 1.67 2.51328 + vertex 1.67349 1.66297 2.51321 + vertex 1.675 1.665 2.51331 + endloop + endfacet + facet normal -0.201094 0.0339263 0.978984 + outer loop + vertex 1.67339 1.66802 2.51302 + vertex 1.67349 1.66297 2.51321 + vertex 1.675 1.67 2.51328 + endloop + endfacet + facet normal 0.938759 0.0307988 0.343194 + outer loop + vertex 1.67349 1.66297 2.51321 + vertex 1.67339 1.66802 2.51302 + vertex 1.67274 1.66274 2.51528 + endloop + endfacet + facet normal 0.936988 0.0329882 0.3478 + outer loop + vertex 1.67339 1.66802 2.51302 + vertex 1.67262 1.66785 2.5151 + vertex 1.67274 1.66274 2.51528 + endloop + endfacet + facet normal 0.921046 0.0340391 0.387964 + outer loop + vertex 1.67262 1.66785 2.5151 + vertex 1.67149 1.66381 2.51814 + vertex 1.67274 1.66274 2.51528 + endloop + endfacet + facet normal 0.921336 0.0334762 0.387324 + outer loop + vertex 1.67136 1.6689 2.51802 + vertex 1.67149 1.66381 2.51814 + vertex 1.67262 1.66785 2.5151 + endloop + endfacet + facet normal -0.220785 0.0506243 0.974008 + outer loop + vertex 1.675 1.675 2.51302 + vertex 1.67339 1.66802 2.51302 + vertex 1.675 1.67 2.51328 + endloop + endfacet + facet normal -0.40891 0.0940357 0.907717 + outer loop + vertex 1.67342 1.67318 2.5125 + vertex 1.67339 1.66802 2.51302 + vertex 1.675 1.675 2.51302 + endloop + endfacet + facet normal 0.937133 0.030427 0.347645 + outer loop + vertex 1.67339 1.66802 2.51302 + vertex 1.67342 1.67318 2.5125 + vertex 1.67262 1.66785 2.5151 + endloop + endfacet + facet normal 0.940135 0.0261419 0.339798 + outer loop + vertex 1.67342 1.67318 2.5125 + vertex 1.67262 1.67305 2.51471 + vertex 1.67262 1.66785 2.5151 + endloop + endfacet + facet normal 0.920972 0.0297677 0.38849 + outer loop + vertex 1.67262 1.67305 2.51471 + vertex 1.67136 1.6689 2.51802 + vertex 1.67262 1.66785 2.5151 + endloop + endfacet + facet normal 0.920415 0.0309137 0.389718 + outer loop + vertex 1.67125 1.67404 2.51786 + vertex 1.67136 1.6689 2.51802 + vertex 1.67262 1.67305 2.51471 + endloop + endfacet + facet normal -0.4808 0.170331 0.860127 + outer loop + vertex 1.675 1.68 2.51203 + vertex 1.67342 1.67318 2.5125 + vertex 1.675 1.675 2.51302 + endloop + endfacet + facet normal -0.662278 0.202967 0.721243 + outer loop + vertex 1.67399 1.67881 2.51143 + vertex 1.67342 1.67318 2.5125 + vertex 1.675 1.68 2.51203 + endloop + endfacet + facet normal 0.941116 -0.0313441 0.336628 + outer loop + vertex 1.67342 1.67318 2.5125 + vertex 1.67399 1.67881 2.51143 + vertex 1.67262 1.67305 2.51471 + endloop + endfacet + facet normal 0.932074 -0.0147911 0.361965 + outer loop + vertex 1.67399 1.67881 2.51143 + vertex 1.67279 1.67805 2.51448 + vertex 1.67262 1.67305 2.51471 + endloop + endfacet + facet normal 0.915837 -0.0124289 0.401357 + outer loop + vertex 1.67279 1.67805 2.51448 + vertex 1.67125 1.67404 2.51786 + vertex 1.67262 1.67305 2.51471 + endloop + endfacet + facet normal 0.901673 0.0188144 0.432008 + outer loop + vertex 1.6712 1.67912 2.51776 + vertex 1.67125 1.67404 2.51786 + vertex 1.67279 1.67805 2.51448 + endloop + endfacet + facet normal -0.728731 0.317445 0.606778 + outer loop + vertex 1.675 1.68388 2.51 + vertex 1.67399 1.67881 2.51143 + vertex 1.675 1.68 2.51203 + endloop + endfacet + facet normal 0.152576 -0.297 -0.942609 + outer loop + vertex 1.675 1.68388 2.51 + vertex 1.67718 1.685 2.51 + vertex 1.67399 1.67881 2.51143 + endloop + endfacet + facet normal 0.554533 -0.0949699 0.826725 + outer loop + vertex 1.67718 1.685 2.51 + vertex 1.67472 1.68287 2.51141 + vertex 1.67399 1.67881 2.51143 + endloop + endfacet + facet normal 0.931471 -0.166039 0.323716 + outer loop + vertex 1.67399 1.67881 2.51143 + vertex 1.67472 1.68287 2.51141 + vertex 1.67279 1.67805 2.51448 + endloop + endfacet + facet normal 0.869154 -0.032836 0.49345 + outer loop + vertex 1.67472 1.68287 2.51141 + vertex 1.67295 1.68259 2.51449 + vertex 1.67279 1.67805 2.51448 + endloop + endfacet + facet normal 0.894557 -0.0336555 0.445685 + outer loop + vertex 1.67295 1.68259 2.51449 + vertex 1.6712 1.67912 2.51776 + vertex 1.67279 1.67805 2.51448 + endloop + endfacet + facet normal 0.872735 0.0170977 0.487895 + outer loop + vertex 1.67116 1.68412 2.51764 + vertex 1.6712 1.67912 2.51776 + vertex 1.67295 1.68259 2.51449 + endloop + endfacet + facet normal 0.620292 -0.219566 0.753013 + outer loop + vertex 1.67718 1.685 2.51 + vertex 1.67895 1.69 2.51 + vertex 1.67472 1.68287 2.51141 + endloop + endfacet + facet normal 0.466745 -0.103718 0.878289 + outer loop + vertex 1.67895 1.69 2.51 + vertex 1.6748 1.68608 2.51174 + vertex 1.67472 1.68287 2.51141 + endloop + endfacet + facet normal 0.86882 -0.0734353 0.489653 + outer loop + vertex 1.67472 1.68287 2.51141 + vertex 1.6748 1.68608 2.51174 + vertex 1.67295 1.68259 2.51449 + endloop + endfacet + facet normal 0.83931 -0.0154701 0.543433 + outer loop + vertex 1.6748 1.68608 2.51174 + vertex 1.67314 1.68718 2.51434 + vertex 1.67295 1.68259 2.51449 + endloop + endfacet + facet normal 0.865423 -0.0179735 0.500719 + outer loop + vertex 1.67314 1.68718 2.51434 + vertex 1.67116 1.68412 2.51764 + vertex 1.67295 1.68259 2.51449 + endloop + endfacet + facet normal 0.844347 0.0325374 0.534808 + outer loop + vertex 1.67108 1.68907 2.51747 + vertex 1.67116 1.68412 2.51764 + vertex 1.67314 1.68718 2.51434 + endloop + endfacet + facet normal -0.0188424 0.487939 0.872674 + outer loop + vertex 1.68 1.69214 2.51 + vertex 1.67694 1.69455 2.50859 + vertex 1.6757 1.6905 2.51082 + endloop + endfacet + facet normal 0.227815 -0.111782 0.967267 + outer loop + vertex 1.68 1.69214 2.51 + vertex 1.6757 1.6905 2.51082 + vertex 1.67895 1.69 2.51 + endloop + endfacet + facet normal 0.263902 0.144766 0.953624 + outer loop + vertex 1.67895 1.69 2.51 + vertex 1.6757 1.6905 2.51082 + vertex 1.6748 1.68608 2.51174 + endloop + endfacet + facet normal 0.830689 -0.0539049 0.554121 + outer loop + vertex 1.6748 1.68608 2.51174 + vertex 1.6757 1.6905 2.51082 + vertex 1.67314 1.68718 2.51434 + endloop + endfacet + facet normal 0.801335 0.0151001 0.598025 + outer loop + vertex 1.6757 1.6905 2.51082 + vertex 1.67318 1.69204 2.51416 + vertex 1.67314 1.68718 2.51434 + endloop + endfacet + facet normal 0.839357 0.0128406 0.543429 + outer loop + vertex 1.67318 1.69204 2.51416 + vertex 1.67108 1.68907 2.51747 + vertex 1.67314 1.68718 2.51434 + endloop + endfacet + facet normal 0.826541 0.0418018 0.561322 + outer loop + vertex 1.67086 1.69391 2.51743 + vertex 1.67108 1.68907 2.51747 + vertex 1.67318 1.69204 2.51416 + endloop + endfacet + facet normal 0.800249 0.0692053 0.595661 + outer loop + vertex 1.67694 1.69455 2.50859 + vertex 1.67647 1.69906 2.5087 + vertex 1.67507 1.69532 2.51101 + endloop + endfacet + facet normal 0.801366 0.0815941 0.592584 + outer loop + vertex 1.6757 1.6905 2.51082 + vertex 1.67694 1.69455 2.50859 + vertex 1.67507 1.69532 2.51101 + endloop + endfacet + facet normal 0.813437 0.0838345 0.575579 + outer loop + vertex 1.6757 1.6905 2.51082 + vertex 1.67507 1.69532 2.51101 + vertex 1.67318 1.69204 2.51416 + endloop + endfacet + facet normal 0.84843 0.0189241 0.528969 + outer loop + vertex 1.67507 1.69532 2.51101 + vertex 1.67302 1.69702 2.51424 + vertex 1.67318 1.69204 2.51416 + endloop + endfacet + facet normal 0.820651 0.017428 0.571164 + outer loop + vertex 1.67302 1.69702 2.51424 + vertex 1.67086 1.69391 2.51743 + vertex 1.67318 1.69204 2.51416 + endloop + endfacet + facet normal 0.808577 0.0419822 0.58689 + outer loop + vertex 1.67036 1.69908 2.51775 + vertex 1.67086 1.69391 2.51743 + vertex 1.67302 1.69702 2.51424 + endloop + endfacet + facet normal 0.852692 0.00185877 0.522411 + outer loop + vertex 1.67647 1.69906 2.5087 + vertex 1.67639 1.7041 2.5088 + vertex 1.67497 1.70029 2.51114 + endloop + endfacet + facet normal 0.85313 0.00384059 0.521684 + outer loop + vertex 1.67507 1.69532 2.51101 + vertex 1.67647 1.69906 2.5087 + vertex 1.67497 1.70029 2.51114 + endloop + endfacet + facet normal 0.844879 0.00333361 0.534947 + outer loop + vertex 1.67507 1.69532 2.51101 + vertex 1.67497 1.70029 2.51114 + vertex 1.67302 1.69702 2.51424 + endloop + endfacet + facet normal 0.845821 0.00136776 0.533466 + outer loop + vertex 1.67497 1.70029 2.51114 + vertex 1.6731 1.7019 2.5141 + vertex 1.67302 1.69702 2.51424 + endloop + endfacet + facet normal 0.798738 0.00411182 0.601665 + outer loop + vertex 1.6731 1.7019 2.5141 + vertex 1.67036 1.69908 2.51775 + vertex 1.67302 1.69702 2.51424 + endloop + endfacet + facet normal 0.803666 -0.00930617 0.595008 + outer loop + vertex 1.67134 1.70367 2.51651 + vertex 1.67036 1.69908 2.51775 + vertex 1.6731 1.7019 2.5141 + endloop + endfacet + facet normal 0.860391 -0.00561027 0.509603 + outer loop + vertex 1.67639 1.7041 2.5088 + vertex 1.67641 1.7092 2.50884 + vertex 1.675 1.70526 2.51116 + endloop + endfacet + facet normal 0.859833 -0.00811803 0.510511 + outer loop + vertex 1.67497 1.70029 2.51114 + vertex 1.67639 1.7041 2.5088 + vertex 1.675 1.70526 2.51116 + endloop + endfacet + facet normal 0.843445 -0.00812733 0.537154 + outer loop + vertex 1.67497 1.70029 2.51114 + vertex 1.675 1.70526 2.51116 + vertex 1.6731 1.7019 2.5141 + endloop + endfacet + facet normal 0.844189 -0.00959423 0.535959 + outer loop + vertex 1.675 1.70526 2.51116 + vertex 1.67323 1.70658 2.51398 + vertex 1.6731 1.7019 2.5141 + endloop + endfacet + facet normal 0.80445 -0.00711481 0.593978 + outer loop + vertex 1.67323 1.70658 2.51398 + vertex 1.67134 1.70367 2.51651 + vertex 1.6731 1.7019 2.5141 + endloop + endfacet + facet normal 0.794972 0.00995896 0.606565 + outer loop + vertex 1.67101 1.70768 2.51687 + vertex 1.67134 1.70367 2.51651 + vertex 1.67323 1.70658 2.51398 + endloop + endfacet + facet normal 0.866907 -0.00709957 0.498419 + outer loop + vertex 1.67641 1.7092 2.50884 + vertex 1.67645 1.71425 2.50882 + vertex 1.67502 1.71023 2.51126 + endloop + endfacet + facet normal 0.865765 -0.0130233 0.500281 + outer loop + vertex 1.675 1.70526 2.51116 + vertex 1.67641 1.7092 2.50884 + vertex 1.67502 1.71023 2.51126 + endloop + endfacet + facet normal 0.84328 -0.0136692 0.5373 + outer loop + vertex 1.675 1.70526 2.51116 + vertex 1.67502 1.71023 2.51126 + vertex 1.67323 1.70658 2.51398 + endloop + endfacet + facet normal 0.837962 -0.00476744 0.545707 + outer loop + vertex 1.67502 1.71023 2.51126 + vertex 1.67312 1.71137 2.51419 + vertex 1.67323 1.70658 2.51398 + endloop + endfacet + facet normal 0.791568 -0.00874198 0.611019 + outer loop + vertex 1.67312 1.71137 2.51419 + vertex 1.67101 1.70768 2.51687 + vertex 1.67323 1.70658 2.51398 + endloop + endfacet + facet normal 0.779749 0.00887497 0.626029 + outer loop + vertex 1.67078 1.71264 2.51708 + vertex 1.67101 1.70768 2.51687 + vertex 1.67312 1.71137 2.51419 + endloop + endfacet + facet normal 0.872064 -0.00838191 0.48932 + outer loop + vertex 1.67645 1.71425 2.50882 + vertex 1.67654 1.71938 2.50876 + vertex 1.67494 1.71534 2.51153 + endloop + endfacet + facet normal 0.87118 -0.01324 0.490785 + outer loop + vertex 1.67502 1.71023 2.51126 + vertex 1.67645 1.71425 2.50882 + vertex 1.67494 1.71534 2.51153 + endloop + endfacet + facet normal 0.835679 -0.0169045 0.548958 + outer loop + vertex 1.67502 1.71023 2.51126 + vertex 1.67494 1.71534 2.51153 + vertex 1.67312 1.71137 2.51419 + endloop + endfacet + facet normal 0.827075 -0.00415927 0.562076 + outer loop + vertex 1.67494 1.71534 2.51153 + vertex 1.67286 1.71635 2.51461 + vertex 1.67312 1.71137 2.51419 + endloop + endfacet + facet normal 0.775102 -0.0125878 0.631711 + outer loop + vertex 1.67286 1.71635 2.51461 + vertex 1.67078 1.71264 2.51708 + vertex 1.67312 1.71137 2.51419 + endloop + endfacet + facet normal 0.759366 0.00882 0.650604 + outer loop + vertex 1.67043 1.71803 2.51743 + vertex 1.67078 1.71264 2.51708 + vertex 1.67286 1.71635 2.51461 + endloop + endfacet + facet normal 0.871175 -0.0154556 0.49073 + outer loop + vertex 1.67654 1.71938 2.50876 + vertex 1.67682 1.72419 2.50842 + vertex 1.67459 1.72112 2.51228 + endloop + endfacet + facet normal 0.872564 -0.00920034 0.488414 + outer loop + vertex 1.67494 1.71534 2.51153 + vertex 1.67654 1.71938 2.50876 + vertex 1.67459 1.72112 2.51228 + endloop + endfacet + facet normal 0.814463 -0.0176131 0.579948 + outer loop + vertex 1.6725 1.71995 2.51518 + vertex 1.67459 1.72112 2.51228 + vertex 1.67273 1.72263 2.51494 + endloop + endfacet + facet normal 0.81321 -0.0105704 0.581875 + outer loop + vertex 1.6725 1.71995 2.51518 + vertex 1.67286 1.71635 2.51461 + vertex 1.67459 1.72112 2.51228 + endloop + endfacet + facet normal 0.824108 -0.0222496 0.565996 + outer loop + vertex 1.67286 1.71635 2.51461 + vertex 1.67494 1.71534 2.51153 + vertex 1.67459 1.72112 2.51228 + endloop + endfacet + facet normal 0.747483 -0.0302829 0.663591 + outer loop + vertex 1.67286 1.71635 2.51461 + vertex 1.6725 1.71995 2.51518 + vertex 1.67043 1.71803 2.51743 + endloop + endfacet + facet normal 0.893138 -0.0280458 0.448907 + outer loop + vertex 1.67682 1.72419 2.50842 + vertex 1.67702 1.7287 2.50829 + vertex 1.67558 1.72586 2.51099 + endloop + endfacet + facet normal 0.883877 -0.0582269 0.464081 + outer loop + vertex 1.67459 1.72112 2.51228 + vertex 1.67682 1.72419 2.50842 + vertex 1.67558 1.72586 2.51099 + endloop + endfacet + facet normal 0.752167 0.0288543 0.658341 + outer loop + vertex 1.67273 1.72263 2.51494 + vertex 1.67332 1.72599 2.51411 + vertex 1.67141 1.72435 2.51637 + endloop + endfacet + facet normal 0.818354 -0.00357899 0.574704 + outer loop + vertex 1.67273 1.72263 2.51494 + vertex 1.67459 1.72112 2.51228 + vertex 1.67332 1.72599 2.51411 + endloop + endfacet + facet normal 0.810584 -0.00966773 0.585542 + outer loop + vertex 1.67459 1.72112 2.51228 + vertex 1.67558 1.72586 2.51099 + vertex 1.67332 1.72599 2.51411 + endloop + endfacet + facet normal 0.744548 0.0481505 0.665831 + outer loop + vertex 1.67332 1.72599 2.51411 + vertex 1.6705 1.7281 2.51711 + vertex 1.67141 1.72435 2.51637 + endloop + endfacet + facet normal 0.866785 -0.010239 0.498577 + outer loop + vertex 1.67702 1.7287 2.50829 + vertex 1.677 1.7335 2.50843 + vertex 1.675 1.73026 2.51184 + endloop + endfacet + facet normal 0.872375 0.0200731 0.488425 + outer loop + vertex 1.67558 1.72586 2.51099 + vertex 1.67702 1.7287 2.50829 + vertex 1.675 1.73026 2.51184 + endloop + endfacet + facet normal 0.785888 0.0179844 0.618107 + outer loop + vertex 1.67263 1.72994 2.51487 + vertex 1.675 1.73026 2.51184 + vertex 1.67295 1.73357 2.51435 + endloop + endfacet + facet normal 0.785741 0.0201835 0.618226 + outer loop + vertex 1.67263 1.72994 2.51487 + vertex 1.67332 1.72599 2.51411 + vertex 1.675 1.73026 2.51184 + endloop + endfacet + facet normal 0.810653 -0.0069784 0.585485 + outer loop + vertex 1.67332 1.72599 2.51411 + vertex 1.67558 1.72586 2.51099 + vertex 1.675 1.73026 2.51184 + endloop + endfacet + facet normal 0.727619 -0.00301368 0.685975 + outer loop + vertex 1.67332 1.72599 2.51411 + vertex 1.67263 1.72994 2.51487 + vertex 1.6705 1.7281 2.51711 + endloop + endfacet + facet normal 0.859661 -0.00562158 0.510835 + outer loop + vertex 1.677 1.7335 2.50843 + vertex 1.67699 1.73861 2.5085 + vertex 1.67518 1.73556 2.51152 + endloop + endfacet + facet normal 0.861856 0.00184823 0.50715 + outer loop + vertex 1.675 1.73026 2.51184 + vertex 1.677 1.7335 2.50843 + vertex 1.67518 1.73556 2.51152 + endloop + endfacet + facet normal 0.781869 0.0115292 0.623336 + outer loop + vertex 1.67518 1.73556 2.51152 + vertex 1.67295 1.73357 2.51435 + vertex 1.675 1.73026 2.51184 + endloop + endfacet + facet normal 0.773819 0.0335345 0.632519 + outer loop + vertex 1.67288 1.73818 2.51419 + vertex 1.67295 1.73357 2.51435 + vertex 1.67518 1.73556 2.51152 + endloop + endfacet + facet normal 0.8421 -0.00825979 0.539259 + outer loop + vertex 1.67699 1.73861 2.5085 + vertex 1.67696 1.74392 2.50862 + vertex 1.67511 1.74063 2.51147 + endloop + endfacet + facet normal 0.849603 0.016573 0.527162 + outer loop + vertex 1.67518 1.73556 2.51152 + vertex 1.67699 1.73861 2.5085 + vertex 1.67511 1.74063 2.51147 + endloop + endfacet + facet normal 0.766106 0.0166505 0.642498 + outer loop + vertex 1.67511 1.74063 2.51147 + vertex 1.67288 1.73818 2.51419 + vertex 1.67518 1.73556 2.51152 + endloop + endfacet + facet normal 0.757776 0.0343505 0.65161 + outer loop + vertex 1.67275 1.74316 2.51408 + vertex 1.67288 1.73818 2.51419 + vertex 1.67511 1.74063 2.51147 + endloop + endfacet + facet normal 0.819636 -0.0217932 0.57247 + outer loop + vertex 1.67696 1.74392 2.50862 + vertex 1.67703 1.74919 2.50873 + vertex 1.675 1.74576 2.5115 + endloop + endfacet + facet normal 0.830363 0.013773 0.557052 + outer loop + vertex 1.67511 1.74063 2.51147 + vertex 1.67696 1.74392 2.50862 + vertex 1.675 1.74576 2.5115 + endloop + endfacet + facet normal 0.747296 0.0113788 0.664394 + outer loop + vertex 1.675 1.74576 2.5115 + vertex 1.67275 1.74316 2.51408 + vertex 1.67511 1.74063 2.51147 + endloop + endfacet + facet normal 0.739885 0.0256157 0.672245 + outer loop + vertex 1.67263 1.74822 2.51402 + vertex 1.67275 1.74316 2.51408 + vertex 1.675 1.74576 2.5115 + endloop + endfacet + facet normal 0.793372 -0.0211818 0.608368 + outer loop + vertex 1.67703 1.74919 2.50873 + vertex 1.67714 1.7542 2.50876 + vertex 1.67492 1.75086 2.51154 + endloop + endfacet + facet normal 0.802026 0.00851524 0.597229 + outer loop + vertex 1.675 1.74576 2.5115 + vertex 1.67703 1.74919 2.50873 + vertex 1.67492 1.75086 2.51154 + endloop + endfacet + facet normal 0.731006 0.00675584 0.682337 + outer loop + vertex 1.67492 1.75086 2.51154 + vertex 1.67263 1.74822 2.51402 + vertex 1.675 1.74576 2.5115 + endloop + endfacet + facet normal 0.720962 0.0249778 0.692524 + outer loop + vertex 1.67252 1.75328 2.51396 + vertex 1.67263 1.74822 2.51402 + vertex 1.67492 1.75086 2.51154 + endloop + endfacet + facet normal 0.771141 0.00830704 0.63661 + outer loop + vertex 1.67714 1.7542 2.50876 + vertex 1.67717 1.75902 2.50867 + vertex 1.67485 1.75592 2.51152 + endloop + endfacet + facet normal 0.772849 0.0140842 0.634434 + outer loop + vertex 1.67492 1.75086 2.51154 + vertex 1.67714 1.7542 2.50876 + vertex 1.67485 1.75592 2.51152 + endloop + endfacet + facet normal 0.715476 0.0135421 0.698506 + outer loop + vertex 1.67485 1.75592 2.51152 + vertex 1.67252 1.75328 2.51396 + vertex 1.67492 1.75086 2.51154 + endloop + endfacet + facet normal 0.704658 0.0326432 0.708796 + outer loop + vertex 1.67237 1.75834 2.51387 + vertex 1.67252 1.75328 2.51396 + vertex 1.67485 1.75592 2.51152 + endloop + endfacet + facet normal 0.759983 0.0322676 0.649142 + outer loop + vertex 1.67717 1.75902 2.50867 + vertex 1.67708 1.76391 2.50852 + vertex 1.67475 1.76098 2.5114 + endloop + endfacet + facet normal 0.759155 0.0297262 0.65023 + outer loop + vertex 1.67485 1.75592 2.51152 + vertex 1.67717 1.75902 2.50867 + vertex 1.67475 1.76098 2.5114 + endloop + endfacet + facet normal 0.703422 0.0300831 0.710136 + outer loop + vertex 1.67475 1.76098 2.5114 + vertex 1.67237 1.75834 2.51387 + vertex 1.67485 1.75592 2.51152 + endloop + endfacet + facet normal 0.695184 0.0443894 0.71746 + outer loop + vertex 1.67222 1.7634 2.5137 + vertex 1.67237 1.75834 2.51387 + vertex 1.67475 1.76098 2.5114 + endloop + endfacet + facet normal 0.75117 0.032905 0.659288 + outer loop + vertex 1.67708 1.76391 2.50852 + vertex 1.67695 1.76888 2.50843 + vertex 1.67463 1.76607 2.51121 + endloop + endfacet + facet normal 0.75455 0.042218 0.654883 + outer loop + vertex 1.67475 1.76098 2.5114 + vertex 1.67708 1.76391 2.50852 + vertex 1.67463 1.76607 2.51121 + endloop + endfacet + facet normal 0.694596 0.0431631 0.718104 + outer loop + vertex 1.67463 1.76607 2.51121 + vertex 1.67222 1.7634 2.5137 + vertex 1.67475 1.76098 2.5114 + endloop + endfacet + facet normal 0.689812 0.0512829 0.72217 + outer loop + vertex 1.67208 1.76839 2.51348 + vertex 1.67222 1.7634 2.5137 + vertex 1.67463 1.76607 2.51121 + endloop + endfacet + facet normal 0.734601 0.0321887 0.677736 + outer loop + vertex 1.67695 1.76888 2.50843 + vertex 1.6768 1.77368 2.50836 + vertex 1.67449 1.77109 2.51099 + endloop + endfacet + facet normal 0.741648 0.0502212 0.668907 + outer loop + vertex 1.67463 1.76607 2.51121 + vertex 1.67695 1.76888 2.50843 + vertex 1.67449 1.77109 2.51099 + endloop + endfacet + facet normal 0.689708 0.051057 0.722285 + outer loop + vertex 1.67449 1.77109 2.51099 + vertex 1.67208 1.76839 2.51348 + vertex 1.67463 1.76607 2.51121 + endloop + endfacet + facet normal 0.685448 0.0580733 0.725802 + outer loop + vertex 1.67188 1.77333 2.51328 + vertex 1.67208 1.76839 2.51348 + vertex 1.67449 1.77109 2.51099 + endloop + endfacet + facet normal 0.71742 0.0331171 0.695854 + outer loop + vertex 1.6768 1.77368 2.50836 + vertex 1.67683 1.7783 2.50811 + vertex 1.67434 1.77602 2.51078 + endloop + endfacet + facet normal 0.724938 0.0502343 0.68698 + outer loop + vertex 1.67449 1.77109 2.51099 + vertex 1.6768 1.77368 2.50836 + vertex 1.67434 1.77602 2.51078 + endloop + endfacet + facet normal 0.682249 0.050704 0.729359 + outer loop + vertex 1.67434 1.77602 2.51078 + vertex 1.67188 1.77333 2.51328 + vertex 1.67449 1.77109 2.51099 + endloop + endfacet + facet normal 0.67845 0.0570261 0.73243 + outer loop + vertex 1.67158 1.77835 2.51316 + vertex 1.67188 1.77333 2.51328 + vertex 1.67434 1.77602 2.51078 + endloop + endfacet + facet normal 0.703168 0.0187859 0.710775 + outer loop + vertex 1.67683 1.7783 2.50811 + vertex 1.6769 1.78314 2.50791 + vertex 1.67421 1.78098 2.51063 + endloop + endfacet + facet normal 0.713984 0.0405351 0.698988 + outer loop + vertex 1.67434 1.77602 2.51078 + vertex 1.67683 1.7783 2.50811 + vertex 1.67421 1.78098 2.51063 + endloop + endfacet + facet normal 0.671247 0.0406473 0.740118 + outer loop + vertex 1.67421 1.78098 2.51063 + vertex 1.67158 1.77835 2.51316 + vertex 1.67434 1.77602 2.51078 + endloop + endfacet + facet normal 0.66842 0.0456565 0.742381 + outer loop + vertex 1.67116 1.78386 2.5132 + vertex 1.67158 1.77835 2.51316 + vertex 1.67421 1.78098 2.51063 + endloop + endfacet + facet normal 0.693074 -0.0111666 0.72078 + outer loop + vertex 1.6769 1.78314 2.50791 + vertex 1.67688 1.78813 2.50801 + vertex 1.67427 1.78586 2.51048 + endloop + endfacet + facet normal 0.705694 0.0126472 0.708404 + outer loop + vertex 1.67421 1.78098 2.51063 + vertex 1.6769 1.78314 2.50791 + vertex 1.67427 1.78586 2.51048 + endloop + endfacet + facet normal 0.652338 0.0148891 0.757782 + outer loop + vertex 1.67427 1.78586 2.51048 + vertex 1.67116 1.78386 2.5132 + vertex 1.67421 1.78098 2.51063 + endloop + endfacet + facet normal 0.65742 0.00124517 0.753524 + outer loop + vertex 1.67212 1.78831 2.51236 + vertex 1.67116 1.78386 2.5132 + vertex 1.67427 1.78586 2.51048 + endloop + endfacet + facet normal 0.68374 -0.0340467 0.728931 + outer loop + vertex 1.67688 1.78813 2.50801 + vertex 1.67692 1.79309 2.5082 + vertex 1.67437 1.79055 2.51048 + endloop + endfacet + facet normal 0.694203 -0.0136961 0.719649 + outer loop + vertex 1.67427 1.78586 2.51048 + vertex 1.67688 1.78813 2.50801 + vertex 1.67437 1.79055 2.51048 + endloop + endfacet + facet normal 0.648305 -0.012736 0.761274 + outer loop + vertex 1.67437 1.79055 2.51048 + vertex 1.67212 1.78831 2.51236 + vertex 1.67427 1.78586 2.51048 + endloop + endfacet + facet normal 0.635548 0.00906957 0.772008 + outer loop + vertex 1.67168 1.79237 2.51267 + vertex 1.67212 1.78831 2.51236 + vertex 1.67437 1.79055 2.51048 + endloop + endfacet + facet normal 0.669534 -0.0374839 0.741835 + outer loop + vertex 1.67692 1.79309 2.5082 + vertex 1.677 1.79806 2.50839 + vertex 1.67433 1.7953 2.51065 + endloop + endfacet + facet normal 0.677177 -0.0215461 0.735504 + outer loop + vertex 1.67437 1.79055 2.51048 + vertex 1.67692 1.79309 2.5082 + vertex 1.67433 1.7953 2.51065 + endloop + endfacet + facet normal 0.62203 -0.0236605 0.782635 + outer loop + vertex 1.67433 1.7953 2.51065 + vertex 1.67168 1.79237 2.51267 + vertex 1.67437 1.79055 2.51048 + endloop + endfacet + facet normal 0.596002 0.0138572 0.802864 + outer loop + vertex 1.67144 1.79722 2.51277 + vertex 1.67168 1.79237 2.51267 + vertex 1.67433 1.7953 2.51065 + endloop + endfacet + facet normal 0.647342 -0.019291 0.761956 + outer loop + vertex 1.677 1.79806 2.50839 + vertex 1.677 1.80304 2.50851 + vertex 1.67429 1.80022 2.51074 + endloop + endfacet + facet normal 0.652564 -0.00808449 0.757691 + outer loop + vertex 1.67433 1.7953 2.51065 + vertex 1.677 1.79806 2.50839 + vertex 1.67429 1.80022 2.51074 + endloop + endfacet + facet normal 0.585889 -0.00964805 0.810334 + outer loop + vertex 1.67429 1.80022 2.51074 + vertex 1.67144 1.79722 2.51277 + vertex 1.67433 1.7953 2.51065 + endloop + endfacet + facet normal 0.54914 0.0417453 0.834687 + outer loop + vertex 1.67116 1.80221 2.5127 + vertex 1.67144 1.79722 2.51277 + vertex 1.67429 1.80022 2.51074 + endloop + endfacet + facet normal 0.616118 0.0214976 0.787361 + outer loop + vertex 1.677 1.80304 2.50851 + vertex 1.67678 1.80807 2.50854 + vertex 1.67411 1.80514 2.51071 + endloop + endfacet + facet normal 0.618513 0.0269293 0.785313 + outer loop + vertex 1.67429 1.80022 2.51074 + vertex 1.677 1.80304 2.50851 + vertex 1.67411 1.80514 2.51071 + endloop + endfacet + facet normal 0.541639 0.0244837 0.840255 + outer loop + vertex 1.67411 1.80514 2.51071 + vertex 1.67116 1.80221 2.5127 + vertex 1.67429 1.80022 2.51074 + endloop + endfacet + facet normal 0.506899 0.0722416 0.858973 + outer loop + vertex 1.67087 1.80711 2.51246 + vertex 1.67116 1.80221 2.5127 + vertex 1.67411 1.80514 2.51071 + endloop + endfacet + facet normal 0.579894 0.0541624 0.812889 + outer loop + vertex 1.67678 1.80807 2.50854 + vertex 1.67629 1.81355 2.50853 + vertex 1.67369 1.80999 2.51062 + endloop + endfacet + facet normal 0.584524 0.0661855 0.808672 + outer loop + vertex 1.67411 1.80514 2.51071 + vertex 1.67678 1.80807 2.50854 + vertex 1.67369 1.80999 2.51062 + endloop + endfacet + facet normal 0.501645 0.0599959 0.862991 + outer loop + vertex 1.67369 1.80999 2.51062 + vertex 1.67087 1.80711 2.51246 + vertex 1.67411 1.80514 2.51071 + endloop + endfacet + facet normal 0.465859 0.105095 0.878596 + outer loop + vertex 1.67017 1.81204 2.51224 + vertex 1.67087 1.80711 2.51246 + vertex 1.67369 1.80999 2.51062 + endloop + endfacet + facet normal 0.549286 0.0871597 0.831077 + outer loop + vertex 1.67313 1.81398 2.51057 + vertex 1.67369 1.80999 2.51062 + vertex 1.67629 1.81355 2.50853 + endloop + endfacet + facet normal 0.549309 0.0876544 0.831009 + outer loop + vertex 1.67313 1.81398 2.51057 + vertex 1.67629 1.81355 2.50853 + vertex 1.67397 1.81821 2.50957 + endloop + endfacet + facet normal 0.538659 0.0806468 0.838655 + outer loop + vertex 1.67397 1.81821 2.50957 + vertex 1.67629 1.81355 2.50853 + vertex 1.67712 1.81803 2.50756 + endloop + endfacet + facet normal 0.45253 0.0743537 0.888644 + outer loop + vertex 1.67369 1.80999 2.51062 + vertex 1.67313 1.81398 2.51057 + vertex 1.67017 1.81204 2.51224 + endloop + endfacet + facet normal 0.538651 0.0835642 0.838375 + outer loop + vertex 1.67712 1.81803 2.50756 + vertex 1.67642 1.8221 2.50761 + vertex 1.67397 1.81821 2.50957 + endloop + endfacet + facet normal 0.50138 0.116545 0.857342 + outer loop + vertex 1.67397 1.81821 2.50957 + vertex 1.67642 1.8221 2.50761 + vertex 1.67298 1.8236 2.50941 + endloop + endfacet + facet normal 0.496996 0.101076 0.861846 + outer loop + vertex 1.67642 1.8221 2.50761 + vertex 1.67572 1.82704 2.50743 + vertex 1.67298 1.8236 2.50941 + endloop + endfacet + facet normal 0.472024 0.127004 0.872389 + outer loop + vertex 1.67298 1.8236 2.50941 + vertex 1.67572 1.82704 2.50743 + vertex 1.67187 1.829 2.50923 + endloop + endfacet + facet normal 0.463418 0.103109 0.880121 + outer loop + vertex 1.67572 1.82704 2.50743 + vertex 1.67505 1.8322 2.50718 + vertex 1.67187 1.829 2.50923 + endloop + endfacet + facet normal 0.456416 0.111724 0.882724 + outer loop + vertex 1.67187 1.829 2.50923 + vertex 1.67505 1.8322 2.50718 + vertex 1.67218 1.83273 2.5086 + endloop + endfacet + facet normal 0.527024 0.108319 0.842919 + outer loop + vertex 1.67796 1.83403 2.50519 + vertex 1.6788 1.83818 2.50413 + vertex 1.67598 1.8362 2.50615 + endloop + endfacet + facet normal 0.518534 0.0976433 0.849464 + outer loop + vertex 1.67598 1.8362 2.50615 + vertex 1.67505 1.8322 2.50718 + vertex 1.67796 1.83403 2.50519 + endloop + endfacet + facet normal 0.439792 0.126311 0.889173 + outer loop + vertex 1.67598 1.8362 2.50615 + vertex 1.6724 1.83648 2.50788 + vertex 1.67505 1.8322 2.50718 + endloop + endfacet + facet normal 0.458947 0.140099 0.877348 + outer loop + vertex 1.6724 1.83648 2.50788 + vertex 1.67218 1.83273 2.5086 + vertex 1.67505 1.8322 2.50718 + endloop + endfacet + facet normal 0.498383 0.0888065 0.862396 + outer loop + vertex 1.6788 1.83818 2.50413 + vertex 1.67774 1.84357 2.50419 + vertex 1.67514 1.84023 2.50604 + endloop + endfacet + facet normal 0.514318 0.131072 0.847524 + outer loop + vertex 1.67598 1.8362 2.50615 + vertex 1.6788 1.83818 2.50413 + vertex 1.67514 1.84023 2.50604 + endloop + endfacet + facet normal 0.439691 0.116665 0.89054 + outer loop + vertex 1.67514 1.84023 2.50604 + vertex 1.6724 1.83648 2.50788 + vertex 1.67598 1.8362 2.50615 + endloop + endfacet + facet normal 0.413672 0.140092 0.899583 + outer loop + vertex 1.67126 1.8419 2.50756 + vertex 1.6724 1.83648 2.50788 + vertex 1.67514 1.84023 2.50604 + endloop + endfacet + facet normal 0.456622 0.10469 0.88348 + outer loop + vertex 1.67774 1.84357 2.50419 + vertex 1.67633 1.84848 2.50434 + vertex 1.67404 1.84508 2.50592 + endloop + endfacet + facet normal 0.462417 0.125327 0.87776 + outer loop + vertex 1.67514 1.84023 2.50604 + vertex 1.67774 1.84357 2.50419 + vertex 1.67404 1.84508 2.50592 + endloop + endfacet + facet normal 0.405077 0.113089 0.907262 + outer loop + vertex 1.67404 1.84508 2.50592 + vertex 1.67126 1.8419 2.50756 + vertex 1.67514 1.84023 2.50604 + endloop + endfacet + facet normal 0.373293 0.145495 0.916233 + outer loop + vertex 1.67007 1.84702 2.50723 + vertex 1.67126 1.8419 2.50756 + vertex 1.67404 1.84508 2.50592 + endloop + endfacet + facet normal 0.422398 0.133754 0.896487 + outer loop + vertex 1.67312 1.84907 2.50576 + vertex 1.67404 1.84508 2.50592 + vertex 1.67633 1.84848 2.50434 + endloop + endfacet + facet normal 0.423294 0.143003 0.894635 + outer loop + vertex 1.67312 1.84907 2.50576 + vertex 1.67633 1.84848 2.50434 + vertex 1.67397 1.85323 2.5047 + endloop + endfacet + facet normal 0.426119 0.144519 0.893049 + outer loop + vertex 1.67397 1.85323 2.5047 + vertex 1.67633 1.84848 2.50434 + vertex 1.67826 1.85215 2.50283 + endloop + endfacet + facet normal 0.363904 0.121338 0.923499 + outer loop + vertex 1.67404 1.84508 2.50592 + vertex 1.67312 1.84907 2.50576 + vertex 1.67007 1.84702 2.50723 + endloop + endfacet + facet normal 0.423517 0.127645 0.89685 + outer loop + vertex 1.67826 1.85215 2.50283 + vertex 1.67687 1.85699 2.50279 + vertex 1.67397 1.85323 2.5047 + endloop + endfacet + facet normal 0.389039 0.159524 0.907304 + outer loop + vertex 1.67397 1.85323 2.5047 + vertex 1.67687 1.85699 2.50279 + vertex 1.6724 1.85906 2.50435 + endloop + endfacet + facet normal 0.379385 0.132404 0.915716 + outer loop + vertex 1.67687 1.85699 2.50279 + vertex 1.67599 1.86194 2.50244 + vertex 1.6724 1.85906 2.50435 + endloop + endfacet + facet normal 0.37059 0.144547 0.91748 + outer loop + vertex 1.6724 1.85906 2.50435 + vertex 1.67599 1.86194 2.50244 + vertex 1.67275 1.86357 2.50349 + endloop + endfacet + facet normal 0.36915 0.140949 0.918619 + outer loop + vertex 1.67599 1.86194 2.50244 + vertex 1.67499 1.8669 2.50208 + vertex 1.67275 1.86357 2.50349 + endloop + endfacet + facet normal 0.286886 0.260712 0.921806 + outer loop + vertex 1.67506 2.0501 2.46085 + vertex 1.67538 2.04567 2.462 + vertex 1.67811 2.04827 2.46041 + endloop + endfacet + facet normal 0.306613 0.368518 0.8776 + outer loop + vertex 1.67717 2.07202 2.45363 + vertex 1.67629 2.07544 2.4525 + vertex 1.67288 2.0732 2.45463 + endloop + endfacet + facet normal 0.298434 0.379282 0.875833 + outer loop + vertex 1.67288 2.0732 2.45463 + vertex 1.67629 2.07544 2.4525 + vertex 1.67108 2.07843 2.45298 + endloop + endfacet + facet normal 0.347924 0.539414 0.766799 + outer loop + vertex 1.67369 2.0798 2.45122 + vertex 1.67761 2.07792 2.45076 + vertex 1.67638 2.08171 2.44865 + endloop + endfacet + facet normal 0.354021 0.533058 0.768452 + outer loop + vertex 1.67111 2.08309 2.45012 + vertex 1.67369 2.0798 2.45122 + vertex 1.67638 2.08171 2.44865 + endloop + endfacet + facet normal 0.331017 0.443004 0.833172 + outer loop + vertex 1.67629 2.07544 2.4525 + vertex 1.67369 2.0798 2.45122 + vertex 1.67108 2.07843 2.45298 + endloop + endfacet + facet normal 0.306277 0.432614 0.847962 + outer loop + vertex 1.67761 2.07792 2.45076 + vertex 1.67369 2.0798 2.45122 + vertex 1.67629 2.07544 2.4525 + endloop + endfacet + facet normal 0.36616 0.733988 0.572004 + outer loop + vertex 1.67926 2.08388 2.44499 + vertex 1.67655 2.08608 2.44391 + vertex 1.67519 2.08497 2.4462 + endloop + endfacet + facet normal 0.371246 0.64064 0.672129 + outer loop + vertex 1.67519 2.08497 2.4462 + vertex 1.67638 2.08171 2.44865 + vertex 1.67926 2.08388 2.44499 + endloop + endfacet + facet normal 0.351779 0.641029 0.682153 + outer loop + vertex 1.67519 2.08497 2.4462 + vertex 1.67174 2.08533 2.44765 + vertex 1.67638 2.08171 2.44865 + endloop + endfacet + facet normal 0.357368 0.646056 0.674462 + outer loop + vertex 1.67174 2.08533 2.44765 + vertex 1.67111 2.08309 2.45012 + vertex 1.67638 2.08171 2.44865 + endloop + endfacet + facet normal -0.31905 0.369256 0.872844 + outer loop + vertex 1.67611 2.095 2.44 + vertex 1.67163 2.09242 2.43945 + vertex 1.67319 2.09019 2.44097 + endloop + endfacet + facet normal 0.110522 0.131077 0.985192 + outer loop + vertex 1.67611 2.095 2.44 + vertex 1.67319 2.09019 2.44097 + vertex 1.68 2.09172 2.44 + endloop + endfacet + facet normal 0.115452 0.110419 0.987157 + outer loop + vertex 1.68 2.09172 2.44 + vertex 1.67319 2.09019 2.44097 + vertex 1.67741 2.08799 2.44072 + endloop + endfacet + facet normal 0.334166 0.755561 0.563436 + outer loop + vertex 1.67655 2.08608 2.44391 + vertex 1.67335 2.08721 2.44429 + vertex 1.67519 2.08497 2.4462 + endloop + endfacet + facet normal 0.335931 0.765672 0.54854 + outer loop + vertex 1.67655 2.08608 2.44391 + vertex 1.67741 2.08799 2.44072 + vertex 1.67335 2.08721 2.44429 + endloop + endfacet + facet normal 0.396797 0.693142 0.601752 + outer loop + vertex 1.67741 2.08799 2.44072 + vertex 1.67319 2.09019 2.44097 + vertex 1.67335 2.08721 2.44429 + endloop + endfacet + facet normal 0.318752 0.75317 0.575441 + outer loop + vertex 1.67519 2.08497 2.4462 + vertex 1.67335 2.08721 2.44429 + vertex 1.67174 2.08533 2.44765 + endloop + endfacet + facet normal 0.640736 0.677399 0.361369 + outer loop + vertex 1.67893 2.095 2.435 + vertex 1.675 2.09605 2.44 + vertex 1.67611 2.095 2.44 + endloop + endfacet + facet normal 0.437105 0.885492 0.157617 + outer loop + vertex 1.675 2.09694 2.435 + vertex 1.675 2.09605 2.44 + vertex 1.67893 2.095 2.435 + endloop + endfacet + facet normal -0.0753726 -0.0796855 0.993966 + outer loop + vertex 1.67611 2.095 2.44 + vertex 1.675 2.09605 2.44 + vertex 1.67163 2.09242 2.43945 + endloop + endfacet + facet normal 0.323604 -0.869729 0.372629 + outer loop + vertex 1.6819 0.94 2.435 + vertex 1.68 0.94 2.43665 + vertex 1.68 0.939293 2.435 + endloop + endfacet + facet normal 0.331073 -0.863166 0.381229 + outer loop + vertex 1.68 0.94 2.43665 + vertex 1.6819 0.94 2.435 + vertex 1.685 0.941189 2.435 + endloop + endfacet + facet normal 0.338006 -0.844293 0.415837 + outer loop + vertex 1.68 0.94 2.43665 + vertex 1.685 0.941189 2.435 + vertex 1.68 0.94165 2.44 + endloop + endfacet + facet normal 0.707296 0.00404282 0.706906 + outer loop + vertex 1.68 0.94165 2.44 + vertex 1.685 0.941189 2.435 + vertex 1.68261 0.942399 2.43738 + endloop + endfacet + facet normal 0.389507 -0.739628 0.548849 + outer loop + vertex 1.68035 0.943451 2.44041 + vertex 1.68261 0.942399 2.43738 + vertex 1.68336 0.943826 2.43877 + endloop + endfacet + facet normal 0.37015 -0.755885 0.540026 + outer loop + vertex 1.68035 0.943451 2.44041 + vertex 1.67777 0.94228 2.44053 + vertex 1.68261 0.942399 2.43738 + endloop + endfacet + facet normal 0.347057 0.751256 0.561397 + outer loop + vertex 1.67777 0.94228 2.44053 + vertex 1.68 0.94165 2.44 + vertex 1.68261 0.942399 2.43738 + endloop + endfacet + facet normal 0.374158 -0.766678 0.521739 + outer loop + vertex 1.68035 0.943451 2.44041 + vertex 1.67778 0.943915 2.44293 + vertex 1.67777 0.94228 2.44053 + endloop + endfacet + facet normal 0.37102 -0.778831 0.505733 + outer loop + vertex 1.68336 0.943826 2.43877 + vertex 1.68175 0.945273 2.44219 + vertex 1.68035 0.943451 2.44041 + endloop + endfacet + facet normal 0.362579 -0.778612 0.512151 + outer loop + vertex 1.67778 0.943915 2.44293 + vertex 1.68035 0.943451 2.44041 + vertex 1.68175 0.945273 2.44219 + endloop + endfacet + facet normal 0.359686 -0.738065 0.570865 + outer loop + vertex 1.67778 0.943915 2.44293 + vertex 1.68175 0.945273 2.44219 + vertex 1.67632 0.946132 2.44672 + endloop + endfacet + facet normal 0.345574 -0.755071 0.557177 + outer loop + vertex 1.67632 0.946132 2.44672 + vertex 1.68175 0.945273 2.44219 + vertex 1.68193 0.947813 2.44552 + endloop + endfacet + facet normal 0.342518 -0.679004 0.649334 + outer loop + vertex 1.68193 0.947813 2.44552 + vertex 1.67909 0.94969 2.44898 + vertex 1.67632 0.946132 2.44672 + endloop + endfacet + facet normal 0.343129 -0.678485 0.649554 + outer loop + vertex 1.68393 0.950521 2.44729 + vertex 1.67909 0.94969 2.44898 + vertex 1.68193 0.947813 2.44552 + endloop + endfacet + facet normal 0.351065 -0.572431 0.740996 + outer loop + vertex 1.67913 0.952244 2.45093 + vertex 1.67659 0.95089 2.45109 + vertex 1.67909 0.94969 2.44898 + endloop + endfacet + facet normal 0.341872 -0.574405 0.743762 + outer loop + vertex 1.67913 0.952244 2.45093 + vertex 1.67909 0.94969 2.44898 + vertex 1.68251 0.952787 2.4498 + endloop + endfacet + facet normal 0.354898 -0.584958 0.729295 + outer loop + vertex 1.68251 0.952787 2.4498 + vertex 1.67909 0.94969 2.44898 + vertex 1.68393 0.950521 2.44729 + endloop + endfacet + facet normal 0.291389 -0.448566 0.844914 + outer loop + vertex 1.67913 0.952244 2.45093 + vertex 1.67749 0.954167 2.45252 + vertex 1.67659 0.95089 2.45109 + endloop + endfacet + facet normal 0.347617 -0.474288 0.808834 + outer loop + vertex 1.68251 0.952787 2.4498 + vertex 1.6812 0.954694 2.45148 + vertex 1.67913 0.952244 2.45093 + endloop + endfacet + facet normal 0.299607 -0.44204 0.84548 + outer loop + vertex 1.6812 0.954694 2.45148 + vertex 1.67749 0.954167 2.45252 + vertex 1.67913 0.952244 2.45093 + endloop + endfacet + facet normal 0.298907 -0.369919 0.879667 + outer loop + vertex 1.6812 0.954694 2.45148 + vertex 1.68272 0.958693 2.45264 + vertex 1.67749 0.954167 2.45252 + endloop + endfacet + facet normal 0.287087 -0.356548 0.889075 + outer loop + vertex 1.68272 0.958693 2.45264 + vertex 1.67799 0.958754 2.45419 + vertex 1.67749 0.954167 2.45252 + endloop + endfacet + facet normal 0.283571 -0.251534 0.925375 + outer loop + vertex 1.6797 1.00208 2.46624 + vertex 1.67688 0.999868 2.46651 + vertex 1.67927 0.998976 2.46553 + endloop + endfacet + facet normal 0.381955 -0.183596 0.905761 + outer loop + vertex 1.67756 1.11912 2.49443 + vertex 1.68228 1.12391 2.49341 + vertex 1.67882 1.1245 2.49498 + endloop + endfacet + facet normal 0.348852 -0.174437 0.920801 + outer loop + vertex 1.67887 1.12783 2.4956 + vertex 1.6763 1.12517 2.49607 + vertex 1.67882 1.1245 2.49498 + endloop + endfacet + facet normal 0.408589 -0.170706 0.896613 + outer loop + vertex 1.67887 1.12783 2.4956 + vertex 1.67882 1.1245 2.49498 + vertex 1.68236 1.12918 2.49426 + endloop + endfacet + facet normal 0.388399 -0.153558 0.908607 + outer loop + vertex 1.68236 1.12918 2.49426 + vertex 1.67882 1.1245 2.49498 + vertex 1.68228 1.12391 2.49341 + endloop + endfacet + facet normal 0.3414 -0.166496 0.925054 + outer loop + vertex 1.67887 1.12783 2.4956 + vertex 1.67627 1.12842 2.49666 + vertex 1.6763 1.12517 2.49607 + endloop + endfacet + facet normal 0.428939 -0.148644 0.89102 + outer loop + vertex 1.68236 1.12918 2.49426 + vertex 1.6834 1.13444 2.49464 + vertex 1.68005 1.13156 2.49577 + endloop + endfacet + facet normal 0.408817 -0.171564 0.896345 + outer loop + vertex 1.67887 1.12783 2.4956 + vertex 1.68236 1.12918 2.49426 + vertex 1.68005 1.13156 2.49577 + endloop + endfacet + facet normal 0.344989 -0.152724 0.926098 + outer loop + vertex 1.68005 1.13156 2.49577 + vertex 1.67627 1.12842 2.49666 + vertex 1.67887 1.12783 2.4956 + endloop + endfacet + facet normal 0.354809 -0.166274 0.920035 + outer loop + vertex 1.67736 1.13365 2.49719 + vertex 1.67627 1.12842 2.49666 + vertex 1.68005 1.13156 2.49577 + endloop + endfacet + facet normal 0.445148 -0.172375 0.87871 + outer loop + vertex 1.6834 1.13444 2.49464 + vertex 1.68117 1.13533 2.49594 + vertex 1.68005 1.13156 2.49577 + endloop + endfacet + facet normal 0.366067 -0.150611 0.91832 + outer loop + vertex 1.68117 1.13533 2.49594 + vertex 1.67736 1.13365 2.49719 + vertex 1.68005 1.13156 2.49577 + endloop + endfacet + facet normal 0.363427 -0.142931 0.920593 + outer loop + vertex 1.68117 1.13533 2.49594 + vertex 1.68085 1.13853 2.49657 + vertex 1.67736 1.13365 2.49719 + endloop + endfacet + facet normal 0.384657 -0.159586 0.90916 + outer loop + vertex 1.68085 1.13853 2.49657 + vertex 1.67718 1.13877 2.49816 + vertex 1.67736 1.13365 2.49719 + endloop + endfacet + facet normal 0.388262 -0.128288 0.912576 + outer loop + vertex 1.68085 1.13853 2.49657 + vertex 1.681 1.1431 2.49715 + vertex 1.67718 1.13877 2.49816 + endloop + endfacet + facet normal 0.41315 -0.153721 0.897595 + outer loop + vertex 1.67718 1.13877 2.49816 + vertex 1.681 1.1431 2.49715 + vertex 1.67715 1.14414 2.4991 + endloop + endfacet + facet normal 0.423798 -0.115534 0.898358 + outer loop + vertex 1.681 1.1431 2.49715 + vertex 1.68135 1.1482 2.49764 + vertex 1.67715 1.14414 2.4991 + endloop + endfacet + facet normal 0.447835 -0.146199 0.882082 + outer loop + vertex 1.67715 1.14414 2.4991 + vertex 1.68135 1.1482 2.49764 + vertex 1.67831 1.14989 2.49946 + endloop + endfacet + facet normal 0.474193 -0.0917169 0.875631 + outer loop + vertex 1.68135 1.1482 2.49764 + vertex 1.6817 1.15332 2.49799 + vertex 1.67831 1.14989 2.49946 + endloop + endfacet + facet normal 0.484497 -0.104972 0.868472 + outer loop + vertex 1.67831 1.14989 2.49946 + vertex 1.6817 1.15332 2.49799 + vertex 1.67875 1.15485 2.49981 + endloop + endfacet + facet normal 0.507752 -0.0502859 0.860034 + outer loop + vertex 1.6817 1.15332 2.49799 + vertex 1.68173 1.15829 2.49825 + vertex 1.67875 1.15485 2.49981 + endloop + endfacet + facet normal 0.525609 -0.0713675 0.847727 + outer loop + vertex 1.67875 1.15485 2.49981 + vertex 1.68173 1.15829 2.49825 + vertex 1.67887 1.15936 2.50012 + endloop + endfacet + facet normal 0.472728 -0.0582402 0.879282 + outer loop + vertex 1.67841 1.16264 2.50058 + vertex 1.67646 1.16005 2.50146 + vertex 1.67887 1.15936 2.50012 + endloop + endfacet + facet normal 0.555897 -0.0396369 0.830306 + outer loop + vertex 1.67841 1.16264 2.50058 + vertex 1.67887 1.15936 2.50012 + vertex 1.68134 1.16355 2.49866 + endloop + endfacet + facet normal 0.539048 -0.0256649 0.841884 + outer loop + vertex 1.68134 1.16355 2.49866 + vertex 1.67887 1.15936 2.50012 + vertex 1.68173 1.15829 2.49825 + endloop + endfacet + facet normal 0.469401 -0.0550578 0.881267 + outer loop + vertex 1.67841 1.16264 2.50058 + vertex 1.67593 1.16328 2.50194 + vertex 1.67646 1.16005 2.50146 + endloop + endfacet + facet normal 0.572237 -0.0177931 0.819895 + outer loop + vertex 1.68134 1.16355 2.49866 + vertex 1.68188 1.16911 2.49841 + vertex 1.6789 1.16644 2.50043 + endloop + endfacet + facet normal 0.555639 -0.0382965 0.830541 + outer loop + vertex 1.67841 1.16264 2.50058 + vertex 1.68134 1.16355 2.49866 + vertex 1.6789 1.16644 2.50043 + endloop + endfacet + facet normal 0.475718 -0.0261275 0.87921 + outer loop + vertex 1.6789 1.16644 2.50043 + vertex 1.67593 1.16328 2.50194 + vertex 1.67841 1.16264 2.50058 + endloop + endfacet + facet normal 0.510145 -0.0689197 0.857323 + outer loop + vertex 1.676 1.16794 2.50228 + vertex 1.67593 1.16328 2.50194 + vertex 1.6789 1.16644 2.50043 + endloop + endfacet + facet normal 0.598505 -0.0330024 0.800439 + outer loop + vertex 1.68188 1.16911 2.49841 + vertex 1.68218 1.17419 2.49839 + vertex 1.67923 1.17135 2.50048 + endloop + endfacet + facet normal 0.590002 -0.0481936 0.805962 + outer loop + vertex 1.6789 1.16644 2.50043 + vertex 1.68188 1.16911 2.49841 + vertex 1.67923 1.17135 2.50048 + endloop + endfacet + facet normal 0.520254 -0.0439483 0.85288 + outer loop + vertex 1.67923 1.17135 2.50048 + vertex 1.676 1.16794 2.50228 + vertex 1.6789 1.16644 2.50043 + endloop + endfacet + facet normal 0.549623 -0.0832976 0.83125 + outer loop + vertex 1.67634 1.17309 2.50257 + vertex 1.676 1.16794 2.50228 + vertex 1.67923 1.17135 2.50048 + endloop + endfacet + facet normal 0.626867 -0.0451964 0.777815 + outer loop + vertex 1.68218 1.17419 2.49839 + vertex 1.68243 1.1792 2.49848 + vertex 1.67953 1.1764 2.50066 + endloop + endfacet + facet normal 0.616924 -0.0638715 0.784426 + outer loop + vertex 1.67923 1.17135 2.50048 + vertex 1.68218 1.17419 2.49839 + vertex 1.67953 1.1764 2.50066 + endloop + endfacet + facet normal 0.559214 -0.0619517 0.826706 + outer loop + vertex 1.67953 1.1764 2.50066 + vertex 1.67634 1.17309 2.50257 + vertex 1.67923 1.17135 2.50048 + endloop + endfacet + facet normal 0.583214 -0.0966329 0.806551 + outer loop + vertex 1.67672 1.17825 2.50291 + vertex 1.67634 1.17309 2.50257 + vertex 1.67953 1.1764 2.50066 + endloop + endfacet + facet normal 0.652887 -0.0456348 0.756079 + outer loop + vertex 1.68243 1.1792 2.49848 + vertex 1.68262 1.18425 2.49863 + vertex 1.67974 1.18152 2.50095 + endloop + endfacet + facet normal 0.640461 -0.0693937 0.764849 + outer loop + vertex 1.67953 1.1764 2.50066 + vertex 1.68243 1.1792 2.49848 + vertex 1.67974 1.18152 2.50095 + endloop + endfacet + facet normal 0.595822 -0.0696111 0.800094 + outer loop + vertex 1.67974 1.18152 2.50095 + vertex 1.67672 1.17825 2.50291 + vertex 1.67953 1.1764 2.50066 + endloop + endfacet + facet normal 0.609102 -0.0890716 0.788074 + outer loop + vertex 1.67663 1.18359 2.50358 + vertex 1.67672 1.17825 2.50291 + vertex 1.67974 1.18152 2.50095 + endloop + endfacet + facet normal 0.679537 -0.0417414 0.732452 + outer loop + vertex 1.68262 1.18425 2.49863 + vertex 1.68272 1.18936 2.49882 + vertex 1.67997 1.18674 2.50123 + endloop + endfacet + facet normal 0.664995 -0.0689455 0.743659 + outer loop + vertex 1.67974 1.18152 2.50095 + vertex 1.68262 1.18425 2.49863 + vertex 1.67997 1.18674 2.50123 + endloop + endfacet + facet normal 0.618197 -0.0689879 0.78299 + outer loop + vertex 1.67997 1.18674 2.50123 + vertex 1.67663 1.18359 2.50358 + vertex 1.67974 1.18152 2.50095 + endloop + endfacet + facet normal 0.628879 -0.0881379 0.772491 + outer loop + vertex 1.67735 1.18924 2.50365 + vertex 1.67663 1.18359 2.50358 + vertex 1.67997 1.18674 2.50123 + endloop + endfacet + facet normal 0.705407 -0.0382408 0.707771 + outer loop + vertex 1.68272 1.18936 2.49882 + vertex 1.68269 1.19433 2.49912 + vertex 1.68022 1.19189 2.50145 + endloop + endfacet + facet normal 0.690912 -0.0651961 0.719993 + outer loop + vertex 1.67997 1.18674 2.50123 + vertex 1.68272 1.18936 2.49882 + vertex 1.68022 1.19189 2.50145 + endloop + endfacet + facet normal 0.642756 -0.0646939 0.763334 + outer loop + vertex 1.68022 1.19189 2.50145 + vertex 1.67735 1.18924 2.50365 + vertex 1.67997 1.18674 2.50123 + endloop + endfacet + facet normal 0.651599 -0.0818607 0.754133 + outer loop + vertex 1.67777 1.19445 2.50385 + vertex 1.67735 1.18924 2.50365 + vertex 1.68022 1.19189 2.50145 + endloop + endfacet + facet normal 0.728333 -0.0401224 0.684048 + outer loop + vertex 1.68269 1.19433 2.49912 + vertex 1.68249 1.19826 2.49956 + vertex 1.68048 1.19664 2.50162 + endloop + endfacet + facet normal 0.71675 -0.0625139 0.694523 + outer loop + vertex 1.68022 1.19189 2.50145 + vertex 1.68269 1.19433 2.49912 + vertex 1.68048 1.19664 2.50162 + endloop + endfacet + facet normal 0.664082 -0.0614271 0.745132 + outer loop + vertex 1.68048 1.19664 2.50162 + vertex 1.67777 1.19445 2.50385 + vertex 1.68022 1.19189 2.50145 + endloop + endfacet + facet normal 0.669346 -0.0739038 0.739266 + outer loop + vertex 1.67845 1.19997 2.50378 + vertex 1.67777 1.19445 2.50385 + vertex 1.68048 1.19664 2.50162 + endloop + endfacet + facet normal 0.733474 -0.0548045 0.677505 + outer loop + vertex 1.68249 1.19826 2.49956 + vertex 1.68111 1.20029 2.50122 + vertex 1.68048 1.19664 2.50162 + endloop + endfacet + facet normal 0.695289 -0.043857 0.717391 + outer loop + vertex 1.68111 1.20029 2.50122 + vertex 1.67845 1.19997 2.50378 + vertex 1.68048 1.19664 2.50162 + endloop + endfacet + facet normal 0.69543 -0.0485129 0.716955 + outer loop + vertex 1.68111 1.20029 2.50122 + vertex 1.68086 1.20393 2.50172 + vertex 1.67845 1.19997 2.50378 + endloop + endfacet + facet normal 0.711073 -0.0668959 0.699928 + outer loop + vertex 1.68086 1.20393 2.50172 + vertex 1.67831 1.20523 2.50443 + vertex 1.67845 1.19997 2.50378 + endloop + endfacet + facet normal 0.715071 -0.0530868 0.697034 + outer loop + vertex 1.68086 1.20393 2.50172 + vertex 1.68083 1.20856 2.5021 + vertex 1.67831 1.20523 2.50443 + endloop + endfacet + facet normal 0.719294 -0.0597161 0.692134 + outer loop + vertex 1.67831 1.20523 2.50443 + vertex 1.68083 1.20856 2.5021 + vertex 1.67842 1.21011 2.50473 + endloop + endfacet + facet normal 0.727447 -0.0353678 0.685252 + outer loop + vertex 1.68083 1.20856 2.5021 + vertex 1.68091 1.21335 2.50226 + vertex 1.67842 1.21011 2.50473 + endloop + endfacet + facet normal 0.733882 -0.0460543 0.677714 + outer loop + vertex 1.67842 1.21011 2.50473 + vertex 1.68091 1.21335 2.50226 + vertex 1.67857 1.21509 2.50491 + endloop + endfacet + facet normal 0.744966 -0.0146427 0.666942 + outer loop + vertex 1.68091 1.21335 2.50226 + vertex 1.6809 1.21828 2.50238 + vertex 1.67857 1.21509 2.50491 + endloop + endfacet + facet normal 0.762262 -0.0440486 0.645768 + outer loop + vertex 1.67857 1.21509 2.50491 + vertex 1.6809 1.21828 2.50238 + vertex 1.6788 1.21959 2.50494 + endloop + endfacet + facet normal 0.715454 -0.0458991 0.69715 + outer loop + vertex 1.67859 1.22272 2.50537 + vertex 1.67755 1.2209 2.50631 + vertex 1.6788 1.21959 2.50494 + endloop + endfacet + facet normal 0.778321 -0.0319585 0.627053 + outer loop + vertex 1.67859 1.22272 2.50537 + vertex 1.6788 1.21959 2.50494 + vertex 1.68063 1.22356 2.50287 + endloop + endfacet + facet normal 0.768668 -0.0211303 0.639298 + outer loop + vertex 1.68063 1.22356 2.50287 + vertex 1.6788 1.21959 2.50494 + vertex 1.6809 1.21828 2.50238 + endloop + endfacet + facet normal 0.696387 -0.0246177 0.717244 + outer loop + vertex 1.67859 1.22272 2.50537 + vertex 1.67654 1.22362 2.50738 + vertex 1.67755 1.2209 2.50631 + endloop + endfacet + facet normal 0.788659 -0.0272964 0.614225 + outer loop + vertex 1.68063 1.22356 2.50287 + vertex 1.68102 1.22931 2.50264 + vertex 1.67891 1.22657 2.50521 + endloop + endfacet + facet normal 0.779523 -0.040887 0.625037 + outer loop + vertex 1.67859 1.22272 2.50537 + vertex 1.68063 1.22356 2.50287 + vertex 1.67891 1.22657 2.50521 + endloop + endfacet + facet normal 0.69509 -0.0299272 0.7183 + outer loop + vertex 1.67891 1.22657 2.50521 + vertex 1.67654 1.22362 2.50738 + vertex 1.67859 1.22272 2.50537 + endloop + endfacet + facet normal 0.707024 -0.0488919 0.705498 + outer loop + vertex 1.67666 1.22901 2.50764 + vertex 1.67654 1.22362 2.50738 + vertex 1.67891 1.22657 2.50521 + endloop + endfacet + facet normal 0.800292 -0.0335091 0.598673 + outer loop + vertex 1.68102 1.22931 2.50264 + vertex 1.68125 1.23458 2.50262 + vertex 1.67917 1.23167 2.50523 + endloop + endfacet + facet normal 0.795933 -0.0426165 0.603883 + outer loop + vertex 1.67891 1.22657 2.50521 + vertex 1.68102 1.22931 2.50264 + vertex 1.67917 1.23167 2.50523 + endloop + endfacet + facet normal 0.712666 -0.0386433 0.700438 + outer loop + vertex 1.67917 1.23167 2.50523 + vertex 1.67666 1.22901 2.50764 + vertex 1.67891 1.22657 2.50521 + endloop + endfacet + facet normal 0.718235 -0.0496993 0.694023 + outer loop + vertex 1.67682 1.23411 2.50784 + vertex 1.67666 1.22901 2.50764 + vertex 1.67917 1.23167 2.50523 + endloop + endfacet + facet normal 0.805242 -0.0249902 0.592419 + outer loop + vertex 1.68125 1.23458 2.50262 + vertex 1.68139 1.23969 2.50264 + vertex 1.67933 1.23672 2.50532 + endloop + endfacet + facet normal 0.801092 -0.0351273 0.597509 + outer loop + vertex 1.67917 1.23167 2.50523 + vertex 1.68125 1.23458 2.50262 + vertex 1.67933 1.23672 2.50532 + endloop + endfacet + facet normal 0.726004 -0.0344354 0.686828 + outer loop + vertex 1.67933 1.23672 2.50532 + vertex 1.67682 1.23411 2.50784 + vertex 1.67917 1.23167 2.50523 + endloop + endfacet + facet normal 0.732971 -0.0491711 0.67848 + outer loop + vertex 1.67694 1.23908 2.50808 + vertex 1.67682 1.23411 2.50784 + vertex 1.67933 1.23672 2.50532 + endloop + endfacet + facet normal 0.813315 -0.0268923 0.581201 + outer loop + vertex 1.68139 1.23969 2.50264 + vertex 1.68152 1.24469 2.50269 + vertex 1.67945 1.24167 2.50545 + endloop + endfacet + facet normal 0.810292 -0.03523 0.584967 + outer loop + vertex 1.67933 1.23672 2.50532 + vertex 1.68139 1.23969 2.50264 + vertex 1.67945 1.24167 2.50545 + endloop + endfacet + facet normal 0.739192 -0.0358947 0.672538 + outer loop + vertex 1.67945 1.24167 2.50545 + vertex 1.67694 1.23908 2.50808 + vertex 1.67933 1.23672 2.50532 + endloop + endfacet + facet normal 0.746385 -0.0520356 0.663477 + outer loop + vertex 1.67709 1.24405 2.5083 + vertex 1.67694 1.23908 2.50808 + vertex 1.67945 1.24167 2.50545 + endloop + endfacet + facet normal 0.824574 -0.00459777 0.565736 + outer loop + vertex 1.68152 1.24469 2.50269 + vertex 1.68163 1.2495 2.50257 + vertex 1.67961 1.24668 2.50549 + endloop + endfacet + facet normal 0.81533 -0.0310544 0.578164 + outer loop + vertex 1.67945 1.24167 2.50545 + vertex 1.68152 1.24469 2.50269 + vertex 1.67961 1.24668 2.50549 + endloop + endfacet + facet normal 0.756582 -0.0296947 0.653224 + outer loop + vertex 1.67961 1.24668 2.50549 + vertex 1.67709 1.24405 2.5083 + vertex 1.67945 1.24167 2.50545 + endloop + endfacet + facet normal 0.761918 -0.0422267 0.646296 + outer loop + vertex 1.6773 1.24918 2.50838 + vertex 1.67709 1.24405 2.5083 + vertex 1.67961 1.24668 2.50549 + endloop + endfacet + facet normal 0.829203 0.0946687 0.550873 + outer loop + vertex 1.68163 1.2495 2.50257 + vertex 1.68165 1.25336 2.50188 + vertex 1.67973 1.25233 2.50494 + endloop + endfacet + facet normal 0.803047 0.0406577 0.594527 + outer loop + vertex 1.67961 1.24668 2.50549 + vertex 1.68163 1.2495 2.50257 + vertex 1.67973 1.25233 2.50494 + endloop + endfacet + facet normal 0.797309 0.0415264 0.602142 + outer loop + vertex 1.67973 1.25233 2.50494 + vertex 1.6773 1.24918 2.50838 + vertex 1.67961 1.24668 2.50549 + endloop + endfacet + facet normal 0.823566 -0.0171549 0.566962 + outer loop + vertex 1.67734 1.25435 2.50848 + vertex 1.6773 1.24918 2.50838 + vertex 1.67973 1.25233 2.50494 + endloop + endfacet + facet normal 0.792418 0.307239 0.526951 + outer loop + vertex 1.68213 1.25607 2.49997 + vertex 1.68157 1.25957 2.49877 + vertex 1.68048 1.25751 2.50161 + endloop + endfacet + facet normal 0.785077 0.257774 0.563211 + outer loop + vertex 1.68165 1.25336 2.50188 + vertex 1.68213 1.25607 2.49997 + vertex 1.68048 1.25751 2.50161 + endloop + endfacet + facet normal 0.778242 0.256509 0.573186 + outer loop + vertex 1.68165 1.25336 2.50188 + vertex 1.68048 1.25751 2.50161 + vertex 1.67973 1.25233 2.50494 + endloop + endfacet + facet normal 0.904581 0.130441 0.405854 + outer loop + vertex 1.67973 1.25233 2.50494 + vertex 1.68048 1.25751 2.50161 + vertex 1.67882 1.25781 2.50523 + endloop + endfacet + facet normal 0.852137 0.116118 0.510273 + outer loop + vertex 1.67882 1.25781 2.50523 + vertex 1.67734 1.25435 2.50848 + vertex 1.67973 1.25233 2.50494 + endloop + endfacet + facet normal 0.908596 0.00475856 0.417649 + outer loop + vertex 1.67723 1.2594 2.50865 + vertex 1.67734 1.25435 2.50848 + vertex 1.67882 1.25781 2.50523 + endloop + endfacet + facet normal 0.879767 0.194689 0.433712 + outer loop + vertex 1.67914 1.26284 2.50193 + vertex 1.68048 1.25751 2.50161 + vertex 1.68 1.26327 2.5 + endloop + endfacet + facet normal 0.903402 -0.255052 0.344693 + outer loop + vertex 1.67914 1.26284 2.50193 + vertex 1.68 1.26327 2.5 + vertex 1.68 1.265 2.50128 + endloop + endfacet + facet normal 0.855238 0.204475 0.476191 + outer loop + vertex 1.68048 1.25751 2.50161 + vertex 1.68157 1.25957 2.49877 + vertex 1.68 1.26327 2.5 + endloop + endfacet + facet normal 0.436233 -0.595131 0.674921 + outer loop + vertex 1.68236 1.265 2.5 + vertex 1.68 1.26327 2.5 + vertex 1.68172 1.26255 2.49825 + endloop + endfacet + facet normal 0.727746 0.0823147 0.680889 + outer loop + vertex 1.68157 1.25957 2.49877 + vertex 1.68172 1.26255 2.49825 + vertex 1.68 1.26327 2.5 + endloop + endfacet + facet normal 0.895951 0.201034 0.396052 + outer loop + vertex 1.68048 1.25751 2.50161 + vertex 1.67914 1.26284 2.50193 + vertex 1.67882 1.25781 2.50523 + endloop + endfacet + facet normal 0.972111 0.0808383 0.220149 + outer loop + vertex 1.67914 1.26284 2.50193 + vertex 1.67834 1.26286 2.50549 + vertex 1.67882 1.25781 2.50523 + endloop + endfacet + facet normal 0.917183 0.0667655 0.392832 + outer loop + vertex 1.67834 1.26286 2.50549 + vertex 1.67723 1.2594 2.50865 + vertex 1.67882 1.25781 2.50523 + endloop + endfacet + facet normal 0.948524 -0.0130765 0.316435 + outer loop + vertex 1.67726 1.26437 2.50877 + vertex 1.67723 1.2594 2.50865 + vertex 1.67834 1.26286 2.50549 + endloop + endfacet + facet normal 0.804718 -0.0367687 0.592518 + outer loop + vertex 1.67914 1.26284 2.50193 + vertex 1.68 1.27 2.50121 + vertex 1.67875 1.2678 2.50278 + endloop + endfacet + facet normal 0.585635 0.0113623 0.810495 + outer loop + vertex 1.67914 1.26284 2.50193 + vertex 1.68 1.265 2.50128 + vertex 1.68 1.27 2.50121 + endloop + endfacet + facet normal 0.196372 -0.602807 0.773344 + outer loop + vertex 1.68236 1.265 2.5 + vertex 1.68172 1.26255 2.49825 + vertex 1.685 1.26586 2.5 + endloop + endfacet + facet normal 0.974474 0.0401927 0.220873 + outer loop + vertex 1.67914 1.26284 2.50193 + vertex 1.67875 1.2678 2.50278 + vertex 1.67834 1.26286 2.50549 + endloop + endfacet + facet normal 0.989328 -0.0022686 0.145689 + outer loop + vertex 1.67875 1.2678 2.50278 + vertex 1.67831 1.26796 2.50573 + vertex 1.67834 1.26286 2.50549 + endloop + endfacet + facet normal 0.948882 -0.0106843 0.31545 + outer loop + vertex 1.67831 1.26796 2.50573 + vertex 1.67726 1.26437 2.50877 + vertex 1.67834 1.26286 2.50549 + endloop + endfacet + facet normal 0.952218 -0.0207391 0.304714 + outer loop + vertex 1.67737 1.26941 2.50877 + vertex 1.67726 1.26437 2.50877 + vertex 1.67831 1.26796 2.50573 + endloop + endfacet + facet normal 0.853742 -0.127242 0.504911 + outer loop + vertex 1.68 1.275 2.50247 + vertex 1.67875 1.2678 2.50278 + vertex 1.68 1.27 2.50121 + endloop + endfacet + facet normal 0.620817 -0.0749735 0.780363 + outer loop + vertex 1.67878 1.27305 2.50325 + vertex 1.67875 1.2678 2.50278 + vertex 1.68 1.275 2.50247 + endloop + endfacet + facet normal 0.988999 -0.0199532 0.146571 + outer loop + vertex 1.67875 1.2678 2.50278 + vertex 1.67878 1.27305 2.50325 + vertex 1.67831 1.26796 2.50573 + endloop + endfacet + facet normal 0.989457 -0.0216419 0.143199 + outer loop + vertex 1.67878 1.27305 2.50325 + vertex 1.67842 1.27323 2.50577 + vertex 1.67831 1.26796 2.50573 + endloop + endfacet + facet normal 0.952015 -0.0220119 0.30526 + outer loop + vertex 1.67842 1.27323 2.50577 + vertex 1.67737 1.26941 2.50877 + vertex 1.67831 1.26796 2.50573 + endloop + endfacet + facet normal 0.945778 -0.0049878 0.324774 + outer loop + vertex 1.67743 1.27453 2.50868 + vertex 1.67737 1.26941 2.50877 + vertex 1.67842 1.27323 2.50577 + endloop + endfacet + facet normal 0.661014 -0.11564 0.741409 + outer loop + vertex 1.68 1.28 2.50325 + vertex 1.67878 1.27305 2.50325 + vertex 1.68 1.275 2.50247 + endloop + endfacet + facet normal 0.177207 -0.0308397 0.98369 + outer loop + vertex 1.67888 1.27844 2.5034 + vertex 1.67878 1.27305 2.50325 + vertex 1.68 1.28 2.50325 + endloop + endfacet + facet normal 0.989445 -0.0220215 0.143225 + outer loop + vertex 1.67878 1.27305 2.50325 + vertex 1.67888 1.27844 2.5034 + vertex 1.67842 1.27323 2.50577 + endloop + endfacet + facet normal 0.983634 -0.00472576 0.180114 + outer loop + vertex 1.67888 1.27844 2.5034 + vertex 1.67846 1.27855 2.50572 + vertex 1.67842 1.27323 2.50577 + endloop + endfacet + facet normal 0.946029 -0.00319809 0.324065 + outer loop + vertex 1.67846 1.27855 2.50572 + vertex 1.67743 1.27453 2.50868 + vertex 1.67842 1.27323 2.50577 + endloop + endfacet + facet normal 0.935576 0.0204073 0.352535 + outer loop + vertex 1.67734 1.27969 2.50861 + vertex 1.67743 1.27453 2.50868 + vertex 1.67846 1.27855 2.50572 + endloop + endfacet + facet normal 0.127141 0.00591199 0.991867 + outer loop + vertex 1.68 1.285 2.50322 + vertex 1.67888 1.27844 2.5034 + vertex 1.68 1.28 2.50325 + endloop + endfacet + facet normal 0.189089 -0.00493912 0.981948 + outer loop + vertex 1.67888 1.28371 2.50343 + vertex 1.67888 1.27844 2.5034 + vertex 1.68 1.285 2.50322 + endloop + endfacet + facet normal 0.983683 -4.59756e-05 0.17991 + outer loop + vertex 1.67888 1.27844 2.5034 + vertex 1.67888 1.28371 2.50343 + vertex 1.67846 1.27855 2.50572 + endloop + endfacet + facet normal 0.970899 0.0268015 0.237983 + outer loop + vertex 1.67888 1.28371 2.50343 + vertex 1.67832 1.2837 2.50571 + vertex 1.67846 1.27855 2.50572 + endloop + endfacet + facet normal 0.936195 0.0261461 0.350508 + outer loop + vertex 1.67832 1.2837 2.50571 + vertex 1.67734 1.27969 2.50861 + vertex 1.67846 1.27855 2.50572 + endloop + endfacet + facet normal 0.931883 0.0348442 0.361081 + outer loop + vertex 1.67713 1.28485 2.50866 + vertex 1.67734 1.27969 2.50861 + vertex 1.67832 1.2837 2.50571 + endloop + endfacet + facet normal 0.196603 -0.0117342 0.980413 + outer loop + vertex 1.68 1.29 2.50328 + vertex 1.67888 1.28371 2.50343 + vertex 1.68 1.285 2.50322 + endloop + endfacet + facet normal 0.316437 -0.0339282 0.948007 + outer loop + vertex 1.67873 1.28875 2.50366 + vertex 1.67888 1.28371 2.50343 + vertex 1.68 1.29 2.50328 + endloop + endfacet + facet normal 0.971122 0.016959 0.237981 + outer loop + vertex 1.67888 1.28371 2.50343 + vertex 1.67873 1.28875 2.50366 + vertex 1.67832 1.2837 2.50571 + endloop + endfacet + facet normal 0.960026 0.0340435 0.277832 + outer loop + vertex 1.67873 1.28875 2.50366 + vertex 1.67807 1.28859 2.50595 + vertex 1.67832 1.2837 2.50571 + endloop + endfacet + facet normal 0.931235 0.0285023 0.363302 + outer loop + vertex 1.67807 1.28859 2.50595 + vertex 1.67713 1.28485 2.50866 + vertex 1.67832 1.2837 2.50571 + endloop + endfacet + facet normal 0.93334 0.0242438 0.358174 + outer loop + vertex 1.67701 1.28967 2.50866 + vertex 1.67713 1.28485 2.50866 + vertex 1.67807 1.28859 2.50595 + endloop + endfacet + facet normal 0.36125 -0.0854537 0.928545 + outer loop + vertex 1.68 1.295 2.50374 + vertex 1.67873 1.28875 2.50366 + vertex 1.68 1.29 2.50328 + endloop + endfacet + facet normal 0.554525 -0.123333 0.822977 + outer loop + vertex 1.67857 1.29402 2.50456 + vertex 1.67873 1.28875 2.50366 + vertex 1.68 1.295 2.50374 + endloop + endfacet + facet normal 0.961419 -0.0173375 0.27454 + outer loop + vertex 1.67873 1.28875 2.50366 + vertex 1.67857 1.29402 2.50456 + vertex 1.67807 1.28859 2.50595 + endloop + endfacet + facet normal 0.922182 0.0148797 0.38647 + outer loop + vertex 1.67857 1.29402 2.50456 + vertex 1.67778 1.2926 2.5065 + vertex 1.67807 1.28859 2.50595 + endloop + endfacet + facet normal 0.932783 0.0193047 0.359922 + outer loop + vertex 1.67778 1.2926 2.5065 + vertex 1.67701 1.28967 2.50866 + vertex 1.67807 1.28859 2.50595 + endloop + endfacet + facet normal 0.927125 0.0307942 0.373485 + outer loop + vertex 1.67687 1.29435 2.50862 + vertex 1.67701 1.28967 2.50866 + vertex 1.67778 1.2926 2.5065 + endloop + endfacet + facet normal 0.610309 -0.270375 0.744594 + outer loop + vertex 1.68 1.295 2.50374 + vertex 1.68 1.29847 2.505 + vertex 1.67857 1.29402 2.50456 + endloop + endfacet + facet normal 0.900435 -0.318958 0.295774 + outer loop + vertex 1.68 1.3 2.50665 + vertex 1.67857 1.29402 2.50456 + vertex 1.68 1.29847 2.505 + endloop + endfacet + facet normal 0.339323 -0.382098 0.85957 + outer loop + vertex 1.68 1.3 2.50665 + vertex 1.67798 1.29807 2.50659 + vertex 1.67857 1.29402 2.50456 + endloop + endfacet + facet normal 0.935364 -0.0401516 0.3514 + outer loop + vertex 1.67798 1.29807 2.50659 + vertex 1.67778 1.2926 2.5065 + vertex 1.67857 1.29402 2.50456 + endloop + endfacet + facet normal 0.905327 -0.0402767 0.422801 + outer loop + vertex 1.67798 1.29807 2.50659 + vertex 1.67687 1.29435 2.50862 + vertex 1.67778 1.2926 2.5065 + endloop + endfacet + facet normal 0.860926 0.0195659 0.508354 + outer loop + vertex 1.67665 1.29937 2.5088 + vertex 1.67687 1.29435 2.50862 + vertex 1.67798 1.29807 2.50659 + endloop + endfacet + facet normal 0.298768 -0.340547 0.891496 + outer loop + vertex 1.68 1.305 2.50856 + vertex 1.67798 1.29807 2.50659 + vertex 1.68 1.3 2.50665 + endloop + endfacet + facet normal -0.38364 -0.147237 0.91167 + outer loop + vertex 1.67783 1.30379 2.50745 + vertex 1.67798 1.29807 2.50659 + vertex 1.68 1.305 2.50856 + endloop + endfacet + facet normal 0.83853 -0.0600673 0.541534 + outer loop + vertex 1.67783 1.30379 2.50745 + vertex 1.67665 1.29937 2.5088 + vertex 1.67798 1.29807 2.50659 + endloop + endfacet + facet normal 0.757393 -0.00434185 0.652945 + outer loop + vertex 1.67652 1.30452 2.50897 + vertex 1.67665 1.29937 2.5088 + vertex 1.67783 1.30379 2.50745 + endloop + endfacet + facet normal -0.433804 -0.0468098 0.89979 + outer loop + vertex 1.68 1.31 2.50882 + vertex 1.67783 1.30379 2.50745 + vertex 1.68 1.305 2.50856 + endloop + endfacet + facet normal -0.449674 -0.0396286 0.892313 + outer loop + vertex 1.67777 1.30887 2.50764 + vertex 1.67783 1.30379 2.50745 + vertex 1.68 1.31 2.50882 + endloop + endfacet + facet normal 0.754763 -0.0150151 0.655825 + outer loop + vertex 1.67777 1.30887 2.50764 + vertex 1.67652 1.30452 2.50897 + vertex 1.67783 1.30379 2.50745 + endloop + endfacet + facet normal 0.723467 0.0044442 0.690345 + outer loop + vertex 1.6765 1.30962 2.50897 + vertex 1.67652 1.30452 2.50897 + vertex 1.67777 1.30887 2.50764 + endloop + endfacet + facet normal -0.462931 -0.00710039 0.886366 + outer loop + vertex 1.68 1.315 2.50886 + vertex 1.67777 1.30887 2.50764 + vertex 1.68 1.31 2.50882 + endloop + endfacet + facet normal -0.476346 -0.000798675 0.879257 + outer loop + vertex 1.67775 1.31398 2.50764 + vertex 1.67777 1.30887 2.50764 + vertex 1.68 1.315 2.50886 + endloop + endfacet + facet normal 0.723145 0.00329413 0.690688 + outer loop + vertex 1.67775 1.31398 2.50764 + vertex 1.6765 1.30962 2.50897 + vertex 1.67777 1.30887 2.50764 + endloop + endfacet + facet normal 0.684586 0.0258455 0.728473 + outer loop + vertex 1.67648 1.31467 2.50881 + vertex 1.6765 1.30962 2.50897 + vertex 1.67775 1.31398 2.50764 + endloop + endfacet + facet normal -0.479078 0.00703149 0.877744 + outer loop + vertex 1.68 1.32 2.50882 + vertex 1.67775 1.31398 2.50764 + vertex 1.68 1.315 2.50886 + endloop + endfacet + facet normal -0.486429 0.0105815 0.873656 + outer loop + vertex 1.67774 1.31913 2.50757 + vertex 1.67775 1.31398 2.50764 + vertex 1.68 1.32 2.50882 + endloop + endfacet + facet normal 0.680075 0.0097095 0.733078 + outer loop + vertex 1.67774 1.31913 2.50757 + vertex 1.67648 1.31467 2.50881 + vertex 1.67775 1.31398 2.50764 + endloop + endfacet + facet normal 0.679321 0.0101141 0.733772 + outer loop + vertex 1.67649 1.31973 2.50873 + vertex 1.67648 1.31467 2.50881 + vertex 1.67774 1.31913 2.50757 + endloop + endfacet + facet normal -0.480742 -0.00873829 0.876819 + outer loop + vertex 1.68 1.325 2.50887 + vertex 1.67774 1.31913 2.50757 + vertex 1.68 1.32 2.50882 + endloop + endfacet + facet normal -0.495912 -0.00104301 0.868372 + outer loop + vertex 1.67779 1.32434 2.50761 + vertex 1.67774 1.31913 2.50757 + vertex 1.68 1.325 2.50887 + endloop + endfacet + facet normal 0.673914 -0.0108045 0.738731 + outer loop + vertex 1.67779 1.32434 2.50761 + vertex 1.67649 1.31973 2.50873 + vertex 1.67774 1.31913 2.50757 + endloop + endfacet + facet normal 0.660023 -0.003819 0.751236 + outer loop + vertex 1.67656 1.32481 2.5087 + vertex 1.67649 1.31973 2.50873 + vertex 1.67779 1.32434 2.50761 + endloop + endfacet + facet normal -0.477084 -0.0770628 0.875473 + outer loop + vertex 1.68 1.33 2.50931 + vertex 1.67779 1.32434 2.50761 + vertex 1.68 1.325 2.50887 + endloop + endfacet + facet normal -0.607701 -0.00171341 0.794164 + outer loop + vertex 1.67788 1.32952 2.50769 + vertex 1.67779 1.32434 2.50761 + vertex 1.68 1.33 2.50931 + endloop + endfacet + facet normal 0.655724 -0.0227329 0.754658 + outer loop + vertex 1.67788 1.32952 2.50769 + vertex 1.67656 1.32481 2.5087 + vertex 1.67779 1.32434 2.50761 + endloop + endfacet + facet normal 0.607134 -0.000525174 0.794599 + outer loop + vertex 1.67662 1.32993 2.50865 + vertex 1.67656 1.32481 2.5087 + vertex 1.67788 1.32952 2.50769 + endloop + endfacet + facet normal -0.604637 -0.0222856 0.796189 + outer loop + vertex 1.68 1.335 2.50945 + vertex 1.67788 1.32952 2.50769 + vertex 1.68 1.33 2.50931 + endloop + endfacet + facet normal -0.63801 -0.000943743 0.770027 + outer loop + vertex 1.67789 1.33454 2.5077 + vertex 1.67788 1.32952 2.50769 + vertex 1.68 1.335 2.50945 + endloop + endfacet + facet normal 0.606597 -0.00317184 0.795004 + outer loop + vertex 1.67789 1.33454 2.5077 + vertex 1.67662 1.32993 2.50865 + vertex 1.67788 1.32952 2.50769 + endloop + endfacet + facet normal 0.450687 0.059363 0.890706 + outer loop + vertex 1.67645 1.33502 2.5084 + vertex 1.67662 1.32993 2.50865 + vertex 1.67789 1.33454 2.5077 + endloop + endfacet + facet normal -0.630606 -0.0511072 0.774418 + outer loop + vertex 1.68 1.34 2.50978 + vertex 1.67789 1.33454 2.5077 + vertex 1.68 1.335 2.50945 + endloop + endfacet + facet normal -0.697522 -0.00324099 0.716556 + outer loop + vertex 1.6777 1.33901 2.50754 + vertex 1.67789 1.33454 2.5077 + vertex 1.68 1.34 2.50978 + endloop + endfacet + facet normal 0.448504 0.0504681 0.892355 + outer loop + vertex 1.6777 1.33901 2.50754 + vertex 1.67645 1.33502 2.5084 + vertex 1.67789 1.33454 2.5077 + endloop + endfacet + facet normal 0.233853 0.13293 0.963142 + outer loop + vertex 1.67616 1.33967 2.50782 + vertex 1.67645 1.33502 2.5084 + vertex 1.6777 1.33901 2.50754 + endloop + endfacet + facet normal -0.70041 0.00997094 0.713671 + outer loop + vertex 1.68 1.345 2.50971 + vertex 1.6777 1.33901 2.50754 + vertex 1.68 1.34 2.50978 + endloop + endfacet + facet normal -0.655803 -0.0219524 0.754613 + outer loop + vertex 1.67754 1.34207 2.50749 + vertex 1.6777 1.33901 2.50754 + vertex 1.68 1.345 2.50971 + endloop + endfacet + facet normal 0.191282 0.0262257 0.981185 + outer loop + vertex 1.67754 1.34207 2.50749 + vertex 1.67616 1.33967 2.50782 + vertex 1.6777 1.33901 2.50754 + endloop + endfacet + facet normal 0.364072 -0.0811882 0.927826 + outer loop + vertex 1.67666 1.34294 2.50791 + vertex 1.67616 1.33967 2.50782 + vertex 1.67754 1.34207 2.50749 + endloop + endfacet + facet normal -0.585123 -0.117491 0.802388 + outer loop + vertex 1.68 1.345 2.50971 + vertex 1.68 1.34698 2.51 + vertex 1.67754 1.34207 2.50749 + endloop + endfacet + facet normal -0.0136763 -0.449883 0.892983 + outer loop + vertex 1.67754 1.34207 2.50749 + vertex 1.68 1.34698 2.51 + vertex 1.67666 1.34294 2.50791 + endloop + endfacet + facet normal -0.733667 0.0591944 0.676926 + outer loop + vertex 1.67835 1.69525 2.50794 + vertex 1.68 1.69214 2.51 + vertex 1.68 1.695 2.50975 + endloop + endfacet + facet normal 0.0836277 0.581091 0.809531 + outer loop + vertex 1.67835 1.69525 2.50794 + vertex 1.67694 1.69455 2.50859 + vertex 1.68 1.69214 2.51 + endloop + endfacet + facet normal -0.73602 0.0364878 0.675976 + outer loop + vertex 1.68 1.7 2.50948 + vertex 1.67835 1.69525 2.50794 + vertex 1.68 1.695 2.50975 + endloop + endfacet + facet normal -0.613408 -0.0425562 0.788619 + outer loop + vertex 1.67786 1.69883 2.50775 + vertex 1.67835 1.69525 2.50794 + vertex 1.68 1.7 2.50948 + endloop + endfacet + facet normal 0.373994 0.0997181 0.922055 + outer loop + vertex 1.67786 1.69883 2.50775 + vertex 1.67694 1.69455 2.50859 + vertex 1.67835 1.69525 2.50794 + endloop + endfacet + facet normal 0.566939 0.0390183 0.822835 + outer loop + vertex 1.67647 1.69906 2.5087 + vertex 1.67694 1.69455 2.50859 + vertex 1.67786 1.69883 2.50775 + endloop + endfacet + facet normal -0.626047 -0.00624656 0.77976 + outer loop + vertex 1.68 1.705 2.50952 + vertex 1.67786 1.69883 2.50775 + vertex 1.68 1.7 2.50948 + endloop + endfacet + facet normal -0.587437 -0.0279745 0.808787 + outer loop + vertex 1.67773 1.70369 2.50783 + vertex 1.67786 1.69883 2.50775 + vertex 1.68 1.705 2.50952 + endloop + endfacet + facet normal 0.563188 0.00197276 0.826327 + outer loop + vertex 1.67773 1.70369 2.50783 + vertex 1.67647 1.69906 2.5087 + vertex 1.67786 1.69883 2.50775 + endloop + endfacet + facet normal 0.587217 -0.00779556 0.809392 + outer loop + vertex 1.67639 1.7041 2.5088 + vertex 1.67647 1.69906 2.5087 + vertex 1.67773 1.70369 2.50783 + endloop + endfacet + facet normal -0.617379 0.054932 0.784746 + outer loop + vertex 1.68 1.71 2.50917 + vertex 1.67773 1.70369 2.50783 + vertex 1.68 1.705 2.50952 + endloop + endfacet + facet normal -0.515596 0.00299966 0.856827 + outer loop + vertex 1.67768 1.70879 2.50778 + vertex 1.67773 1.70369 2.50783 + vertex 1.68 1.71 2.50917 + endloop + endfacet + facet normal 0.591369 0.0133599 0.806291 + outer loop + vertex 1.67768 1.70879 2.50778 + vertex 1.67639 1.7041 2.5088 + vertex 1.67773 1.70369 2.50783 + endloop + endfacet + facet normal 0.636958 -0.00685656 0.770868 + outer loop + vertex 1.67641 1.7092 2.50884 + vertex 1.67639 1.7041 2.5088 + vertex 1.67768 1.70879 2.50778 + endloop + endfacet + facet normal -0.509129 -0.013747 0.86058 + outer loop + vertex 1.68 1.715 2.50925 + vertex 1.67768 1.70879 2.50778 + vertex 1.68 1.71 2.50917 + endloop + endfacet + facet normal -0.570894 0.0187474 0.82081 + outer loop + vertex 1.67771 1.71388 2.50768 + vertex 1.67768 1.70879 2.50778 + vertex 1.68 1.715 2.50925 + endloop + endfacet + facet normal 0.640226 0.0106125 0.768113 + outer loop + vertex 1.67771 1.71388 2.50768 + vertex 1.67641 1.7092 2.50884 + vertex 1.67768 1.70879 2.50778 + endloop + endfacet + facet normal 0.671151 -0.00460737 0.741306 + outer loop + vertex 1.67645 1.71425 2.50882 + vertex 1.67641 1.7092 2.50884 + vertex 1.67771 1.71388 2.50768 + endloop + endfacet + facet normal -0.575295 0.0326972 0.817293 + outer loop + vertex 1.68 1.72 2.50905 + vertex 1.67771 1.71388 2.50768 + vertex 1.68 1.715 2.50925 + endloop + endfacet + facet normal -0.643355 0.0704377 0.76232 + outer loop + vertex 1.67781 1.71887 2.50731 + vertex 1.67771 1.71388 2.50768 + vertex 1.68 1.72 2.50905 + endloop + endfacet + facet normal 0.677875 0.0410164 0.734032 + outer loop + vertex 1.67781 1.71887 2.50731 + vertex 1.67645 1.71425 2.50882 + vertex 1.67771 1.71388 2.50768 + endloop + endfacet + facet normal 0.750571 -0.00437579 0.660775 + outer loop + vertex 1.67654 1.71938 2.50876 + vertex 1.67645 1.71425 2.50882 + vertex 1.67781 1.71887 2.50731 + endloop + endfacet + facet normal -0.642484 0.0671569 0.76335 + outer loop + vertex 1.68 1.725 2.50861 + vertex 1.67781 1.71887 2.50731 + vertex 1.68 1.72 2.50905 + endloop + endfacet + facet normal -0.809577 0.169493 0.562011 + outer loop + vertex 1.67802 1.72412 2.50602 + vertex 1.67781 1.71887 2.50731 + vertex 1.68 1.725 2.50861 + endloop + endfacet + facet normal 0.76677 0.125203 0.629593 + outer loop + vertex 1.67802 1.72412 2.50602 + vertex 1.67654 1.71938 2.50876 + vertex 1.67781 1.71887 2.50731 + endloop + endfacet + facet normal 0.893983 -0.0199003 0.447659 + outer loop + vertex 1.67682 1.72419 2.50842 + vertex 1.67654 1.71938 2.50876 + vertex 1.67802 1.72412 2.50602 + endloop + endfacet + facet normal -0.621677 0.413083 0.665492 + outer loop + vertex 1.67861 1.72911 2.50372 + vertex 1.68 1.72913 2.505 + vertex 1.68 1.73 2.50446 + endloop + endfacet + facet normal -0.787001 0.40602 0.464518 + outer loop + vertex 1.68 1.72913 2.505 + vertex 1.67802 1.72412 2.50602 + vertex 1.68 1.725 2.50861 + endloop + endfacet + facet normal -0.629376 0.386303 0.674282 + outer loop + vertex 1.68 1.72913 2.505 + vertex 1.67861 1.72911 2.50372 + vertex 1.67802 1.72412 2.50602 + endloop + endfacet + facet normal 0.889258 0.099829 0.446379 + outer loop + vertex 1.67861 1.72911 2.50372 + vertex 1.67791 1.72802 2.50535 + vertex 1.67802 1.72412 2.50602 + endloop + endfacet + facet normal 0.891127 0.099263 0.442764 + outer loop + vertex 1.67791 1.72802 2.50535 + vertex 1.67682 1.72419 2.50842 + vertex 1.67802 1.72412 2.50602 + endloop + endfacet + facet normal 0.954167 -0.035017 0.297219 + outer loop + vertex 1.67702 1.7287 2.50829 + vertex 1.67682 1.72419 2.50842 + vertex 1.67791 1.72802 2.50535 + endloop + endfacet + facet normal -0.512202 0.0854946 0.854599 + outer loop + vertex 1.68 1.735 2.50396 + vertex 1.67861 1.72911 2.50372 + vertex 1.68 1.73 2.50446 + endloop + endfacet + facet normal -0.562298 0.0986682 0.821027 + outer loop + vertex 1.67855 1.73297 2.50321 + vertex 1.67861 1.72911 2.50372 + vertex 1.68 1.735 2.50396 + endloop + endfacet + facet normal 0.898676 0.0728387 0.432522 + outer loop + vertex 1.67861 1.72911 2.50372 + vertex 1.67855 1.73297 2.50321 + vertex 1.67791 1.72802 2.50535 + endloop + endfacet + facet normal 0.971537 -0.0217686 0.235885 + outer loop + vertex 1.67855 1.73297 2.50321 + vertex 1.67804 1.73251 2.50526 + vertex 1.67791 1.72802 2.50535 + endloop + endfacet + facet normal 0.955525 -0.0201692 0.294221 + outer loop + vertex 1.67804 1.73251 2.50526 + vertex 1.67702 1.7287 2.50829 + vertex 1.67791 1.72802 2.50535 + endloop + endfacet + facet normal 0.950067 -0.00458579 0.312014 + outer loop + vertex 1.677 1.7335 2.50843 + vertex 1.67702 1.7287 2.50829 + vertex 1.67804 1.73251 2.50526 + endloop + endfacet + facet normal -0.567992 0.104482 0.816375 + outer loop + vertex 1.68 1.74 2.50332 + vertex 1.67855 1.73297 2.50321 + vertex 1.68 1.735 2.50396 + endloop + endfacet + facet normal -0.216527 0.0291641 0.975841 + outer loop + vertex 1.67859 1.7377 2.50308 + vertex 1.67855 1.73297 2.50321 + vertex 1.68 1.74 2.50332 + endloop + endfacet + facet normal 0.970797 -0.003259 0.239882 + outer loop + vertex 1.67855 1.73297 2.50321 + vertex 1.67859 1.7377 2.50308 + vertex 1.67804 1.73251 2.50526 + endloop + endfacet + facet normal 0.974309 -0.00990676 0.224999 + outer loop + vertex 1.67859 1.7377 2.50308 + vertex 1.67806 1.73747 2.50538 + vertex 1.67804 1.73251 2.50526 + endloop + endfacet + facet normal 0.949338 -0.0117968 0.314035 + outer loop + vertex 1.67806 1.73747 2.50538 + vertex 1.677 1.7335 2.50843 + vertex 1.67804 1.73251 2.50526 + endloop + endfacet + facet normal 0.945935 -0.00298155 0.324342 + outer loop + vertex 1.67699 1.73861 2.5085 + vertex 1.677 1.7335 2.50843 + vertex 1.67806 1.73747 2.50538 + endloop + endfacet + facet normal -0.198377 0.0176167 0.979967 + outer loop + vertex 1.68 1.745 2.50323 + vertex 1.67859 1.7377 2.50308 + vertex 1.68 1.74 2.50332 + endloop + endfacet + facet normal 0.0335303 -0.0274823 0.99906 + outer loop + vertex 1.67869 1.74284 2.50321 + vertex 1.67859 1.7377 2.50308 + vertex 1.68 1.745 2.50323 + endloop + endfacet + facet normal 0.974382 -0.0237511 0.223641 + outer loop + vertex 1.67859 1.7377 2.50308 + vertex 1.67869 1.74284 2.50321 + vertex 1.67806 1.73747 2.50538 + endloop + endfacet + facet normal 0.97403 -0.0230657 0.225241 + outer loop + vertex 1.67869 1.74284 2.50321 + vertex 1.67814 1.74284 2.50557 + vertex 1.67806 1.73747 2.50538 + endloop + endfacet + facet normal 0.942947 -0.0264656 0.331889 + outer loop + vertex 1.67814 1.74284 2.50557 + vertex 1.67699 1.73861 2.5085 + vertex 1.67806 1.73747 2.50538 + endloop + endfacet + facet normal 0.932528 -0.00345945 0.36108 + outer loop + vertex 1.67696 1.74392 2.50862 + vertex 1.67699 1.73861 2.5085 + vertex 1.67814 1.74284 2.50557 + endloop + endfacet + facet normal 0.00145828 -0.00796293 0.999967 + outer loop + vertex 1.68 1.75 2.50327 + vertex 1.67869 1.74284 2.50321 + vertex 1.68 1.745 2.50323 + endloop + endfacet + facet normal 0.473034 -0.0935259 0.876066 + outer loop + vertex 1.67932 1.74842 2.50347 + vertex 1.67869 1.74284 2.50321 + vertex 1.68 1.75 2.50327 + endloop + endfacet + facet normal 0.967189 -0.120632 0.22359 + outer loop + vertex 1.67869 1.74284 2.50321 + vertex 1.67932 1.74842 2.50347 + vertex 1.67814 1.74284 2.50557 + endloop + endfacet + facet normal 0.966187 -0.118346 0.229079 + outer loop + vertex 1.67932 1.74842 2.50347 + vertex 1.67877 1.74853 2.50586 + vertex 1.67814 1.74284 2.50557 + endloop + endfacet + facet normal 0.911119 -0.120633 0.394094 + outer loop + vertex 1.67877 1.74853 2.50586 + vertex 1.67696 1.74392 2.50862 + vertex 1.67814 1.74284 2.50557 + endloop + endfacet + facet normal 0.852699 -0.0211465 0.521974 + outer loop + vertex 1.67703 1.74919 2.50873 + vertex 1.67696 1.74392 2.50862 + vertex 1.67877 1.74853 2.50586 + endloop + endfacet + facet normal -0.0739632 0.153688 0.985347 + outer loop + vertex 1.68 1.755 2.50249 + vertex 1.67932 1.74842 2.50347 + vertex 1.68 1.75 2.50327 + endloop + endfacet + facet normal 0.596948 -0.177294 -0.782445 + outer loop + vertex 1.68329 1.755 2.505 + vertex 1.67932 1.74842 2.50347 + vertex 1.68 1.755 2.50249 + endloop + endfacet + facet normal 0.814022 -0.540222 0.213374 + outer loop + vertex 1.67932 1.74842 2.50347 + vertex 1.68329 1.755 2.505 + vertex 1.67877 1.74853 2.50586 + endloop + endfacet + facet normal 0.277787 -0.0666031 0.958331 + outer loop + vertex 1.68329 1.755 2.505 + vertex 1.67948 1.75382 2.50602 + vertex 1.67877 1.74853 2.50586 + endloop + endfacet + facet normal 0.834493 -0.128552 0.535813 + outer loop + vertex 1.67948 1.75382 2.50602 + vertex 1.67703 1.74919 2.50873 + vertex 1.67877 1.74853 2.50586 + endloop + endfacet + facet normal 0.758557 -0.0206897 0.651278 + outer loop + vertex 1.67714 1.7542 2.50876 + vertex 1.67703 1.74919 2.50873 + vertex 1.67948 1.75382 2.50602 + endloop + endfacet + facet normal 0.262842 -0.0126148 0.964756 + outer loop + vertex 1.68329 1.755 2.505 + vertex 1.68353 1.76 2.505 + vertex 1.67948 1.75382 2.50602 + endloop + endfacet + facet normal 0.238141 0.00464614 0.97122 + outer loop + vertex 1.68353 1.76 2.505 + vertex 1.67979 1.75843 2.50592 + vertex 1.67948 1.75382 2.50602 + endloop + endfacet + facet normal 0.75708 -0.0370697 0.65227 + outer loop + vertex 1.67979 1.75843 2.50592 + vertex 1.67714 1.7542 2.50876 + vertex 1.67948 1.75382 2.50602 + endloop + endfacet + facet normal 0.723423 0.00965796 0.690338 + outer loop + vertex 1.67717 1.75902 2.50867 + vertex 1.67714 1.7542 2.50876 + vertex 1.67979 1.75843 2.50592 + endloop + endfacet + facet normal 0.250205 -0.0260209 0.967843 + outer loop + vertex 1.68353 1.76 2.505 + vertex 1.68405 1.765 2.505 + vertex 1.67979 1.75843 2.50592 + endloop + endfacet + facet normal 0.0498567 0.107316 0.992974 + outer loop + vertex 1.68405 1.765 2.505 + vertex 1.67967 1.76254 2.50549 + vertex 1.67979 1.75843 2.50592 + endloop + endfacet + facet normal 0.729298 0.0933272 0.677801 + outer loop + vertex 1.67967 1.76254 2.50549 + vertex 1.67717 1.75902 2.50867 + vertex 1.67979 1.75843 2.50592 + endloop + endfacet + facet normal 0.767519 0.0321348 0.640221 + outer loop + vertex 1.67708 1.76391 2.50852 + vertex 1.67717 1.75902 2.50867 + vertex 1.67967 1.76254 2.50549 + endloop + endfacet + facet normal 0.490677 0.485282 0.723698 + outer loop + vertex 1.685 1.76515 2.5 + vertex 1.68264 1.7689 2.49908 + vertex 1.68201 1.76555 2.50176 + endloop + endfacet + facet normal 0.44001 -0.351868 0.826184 + outer loop + vertex 1.685 1.76515 2.5 + vertex 1.68201 1.76555 2.50176 + vertex 1.68488 1.765 2.5 + endloop + endfacet + facet normal 0.207373 0.977656 0.0344253 + outer loop + vertex 1.68488 1.765 2.5 + vertex 1.68201 1.76555 2.50176 + vertex 1.68405 1.765 2.505 + endloop + endfacet + facet normal -0.414793 0.818012 0.398501 + outer loop + vertex 1.68405 1.765 2.505 + vertex 1.68201 1.76555 2.50176 + vertex 1.67967 1.76254 2.50549 + endloop + endfacet + facet normal 0.806009 0.096452 0.583991 + outer loop + vertex 1.68201 1.76555 2.50176 + vertex 1.6793 1.76689 2.50528 + vertex 1.67967 1.76254 2.50549 + endloop + endfacet + facet normal 0.778164 0.0958529 0.620703 + outer loop + vertex 1.6793 1.76689 2.50528 + vertex 1.67708 1.76391 2.50852 + vertex 1.67967 1.76254 2.50549 + endloop + endfacet + facet normal 0.810262 0.033107 0.585132 + outer loop + vertex 1.67695 1.76888 2.50843 + vertex 1.67708 1.76391 2.50852 + vertex 1.6793 1.76689 2.50528 + endloop + endfacet + facet normal 0.89757 0.00294766 0.440863 + outer loop + vertex 1.68264 1.7689 2.49908 + vertex 1.68232 1.77351 2.4997 + vertex 1.68111 1.77001 2.50219 + endloop + endfacet + facet normal 0.907088 0.145345 0.395052 + outer loop + vertex 1.68201 1.76555 2.50176 + vertex 1.68264 1.7689 2.49908 + vertex 1.68111 1.77001 2.50219 + endloop + endfacet + facet normal 0.807012 0.106913 0.580777 + outer loop + vertex 1.68201 1.76555 2.50176 + vertex 1.68111 1.77001 2.50219 + vertex 1.6793 1.76689 2.50528 + endloop + endfacet + facet normal 0.85907 0.00864007 0.511786 + outer loop + vertex 1.68111 1.77001 2.50219 + vertex 1.67909 1.7717 2.50556 + vertex 1.6793 1.76689 2.50528 + endloop + endfacet + facet normal 0.801033 0.000871411 0.598619 + outer loop + vertex 1.67909 1.7717 2.50556 + vertex 1.67695 1.76888 2.50843 + vertex 1.6793 1.76689 2.50528 + endloop + endfacet + facet normal 0.785282 0.032816 0.618268 + outer loop + vertex 1.6768 1.77368 2.50836 + vertex 1.67695 1.76888 2.50843 + vertex 1.67909 1.7717 2.50556 + endloop + endfacet + facet normal 0.899256 -0.0678348 0.432131 + outer loop + vertex 1.68232 1.77351 2.4997 + vertex 1.68235 1.77756 2.50028 + vertex 1.68092 1.77525 2.5029 + endloop + endfacet + facet normal 0.910808 -0.021981 0.412244 + outer loop + vertex 1.68111 1.77001 2.50219 + vertex 1.68232 1.77351 2.4997 + vertex 1.68092 1.77525 2.5029 + endloop + endfacet + facet normal 0.8475 -0.0399418 0.529291 + outer loop + vertex 1.68111 1.77001 2.50219 + vertex 1.68092 1.77525 2.5029 + vertex 1.67909 1.7717 2.50556 + endloop + endfacet + facet normal 0.820483 0.00583073 0.57164 + outer loop + vertex 1.68092 1.77525 2.5029 + vertex 1.67876 1.77578 2.50598 + vertex 1.67909 1.7717 2.50556 + endloop + endfacet + facet normal 0.772889 -0.00444624 0.634526 + outer loop + vertex 1.67876 1.77578 2.50598 + vertex 1.6768 1.77368 2.50836 + vertex 1.67909 1.7717 2.50556 + endloop + endfacet + facet normal 0.757174 0.0305421 0.652499 + outer loop + vertex 1.67683 1.7783 2.50811 + vertex 1.6768 1.77368 2.50836 + vertex 1.67876 1.77578 2.50598 + endloop + endfacet + facet normal 0.895566 -0.0548884 0.44153 + outer loop + vertex 1.68235 1.77756 2.50028 + vertex 1.68165 1.77958 2.50194 + vertex 1.68092 1.77525 2.5029 + endloop + endfacet + facet normal 0.818966 0.00347692 0.573832 + outer loop + vertex 1.68165 1.77958 2.50194 + vertex 1.68137 1.78392 2.50232 + vertex 1.67957 1.78009 2.50491 + endloop + endfacet + facet normal 0.81765 -0.0120292 0.57559 + outer loop + vertex 1.68165 1.77958 2.50194 + vertex 1.67957 1.78009 2.50491 + vertex 1.68092 1.77525 2.5029 + endloop + endfacet + facet normal 0.819104 -0.0107733 0.573544 + outer loop + vertex 1.68092 1.77525 2.5029 + vertex 1.67957 1.78009 2.50491 + vertex 1.67876 1.77578 2.50598 + endloop + endfacet + facet normal 0.752799 0.0226734 0.65786 + outer loop + vertex 1.67957 1.78009 2.50491 + vertex 1.67683 1.7783 2.50811 + vertex 1.67876 1.77578 2.50598 + endloop + endfacet + facet normal 0.754819 0.0157793 0.655743 + outer loop + vertex 1.6769 1.78314 2.50791 + vertex 1.67683 1.7783 2.50811 + vertex 1.67957 1.78009 2.50491 + endloop + endfacet + facet normal 0.81711 -0.0100183 0.576395 + outer loop + vertex 1.68137 1.78392 2.50232 + vertex 1.68125 1.78904 2.50258 + vertex 1.67935 1.78568 2.50522 + endloop + endfacet + facet normal 0.820406 0.00141244 0.571779 + outer loop + vertex 1.67957 1.78009 2.50491 + vertex 1.68137 1.78392 2.50232 + vertex 1.67935 1.78568 2.50522 + endloop + endfacet + facet normal 0.743404 -0.00709205 0.668805 + outer loop + vertex 1.67935 1.78568 2.50522 + vertex 1.6769 1.78314 2.50791 + vertex 1.67957 1.78009 2.50491 + endloop + endfacet + facet normal 0.744689 -0.00987661 0.667338 + outer loop + vertex 1.67688 1.78813 2.50801 + vertex 1.6769 1.78314 2.50791 + vertex 1.67935 1.78568 2.50522 + endloop + endfacet + facet normal 0.81768 -0.0311961 0.574827 + outer loop + vertex 1.68125 1.78904 2.50258 + vertex 1.68133 1.79406 2.50274 + vertex 1.67929 1.79083 2.50546 + endloop + endfacet + facet normal 0.8218 -0.0181115 0.569488 + outer loop + vertex 1.67935 1.78568 2.50522 + vertex 1.68125 1.78904 2.50258 + vertex 1.67929 1.79083 2.50546 + endloop + endfacet + facet normal 0.73836 -0.0238141 0.673986 + outer loop + vertex 1.67929 1.79083 2.50546 + vertex 1.67688 1.78813 2.50801 + vertex 1.67935 1.78568 2.50522 + endloop + endfacet + facet normal 0.742564 -0.0322795 0.668997 + outer loop + vertex 1.67692 1.79309 2.5082 + vertex 1.67688 1.78813 2.50801 + vertex 1.67929 1.79083 2.50546 + endloop + endfacet + facet normal 0.81651 -0.0576776 0.574442 + outer loop + vertex 1.68133 1.79406 2.50274 + vertex 1.68157 1.79898 2.50289 + vertex 1.67939 1.79588 2.50568 + endloop + endfacet + facet normal 0.822362 -0.0403188 0.567534 + outer loop + vertex 1.67929 1.79083 2.50546 + vertex 1.68133 1.79406 2.50274 + vertex 1.67939 1.79588 2.50568 + endloop + endfacet + facet normal 0.737655 -0.0432649 0.673791 + outer loop + vertex 1.67939 1.79588 2.50568 + vertex 1.67692 1.79309 2.5082 + vertex 1.67929 1.79083 2.50546 + endloop + endfacet + facet normal 0.734 -0.0360703 0.678191 + outer loop + vertex 1.677 1.79806 2.50839 + vertex 1.67692 1.79309 2.5082 + vertex 1.67939 1.79588 2.50568 + endloop + endfacet + facet normal 0.804381 -0.0540946 0.591646 + outer loop + vertex 1.68157 1.79898 2.50289 + vertex 1.68175 1.80391 2.5031 + vertex 1.67951 1.80089 2.50587 + endloop + endfacet + facet normal 0.808839 -0.0413647 0.586574 + outer loop + vertex 1.67939 1.79588 2.50568 + vertex 1.68157 1.79898 2.50289 + vertex 1.67951 1.80089 2.50587 + endloop + endfacet + facet normal 0.730861 -0.0432033 0.681158 + outer loop + vertex 1.67951 1.80089 2.50587 + vertex 1.677 1.79806 2.50839 + vertex 1.67939 1.79588 2.50568 + endloop + endfacet + facet normal 0.717432 -0.0176917 0.696404 + outer loop + vertex 1.677 1.80304 2.50851 + vertex 1.677 1.79806 2.50839 + vertex 1.67951 1.80089 2.50587 + endloop + endfacet + facet normal 0.781046 -0.029228 0.62379 + outer loop + vertex 1.68175 1.80391 2.5031 + vertex 1.68178 1.80888 2.50329 + vertex 1.67949 1.80588 2.50602 + endloop + endfacet + facet normal 0.785747 -0.0157637 0.618347 + outer loop + vertex 1.67951 1.80089 2.50587 + vertex 1.68175 1.80391 2.5031 + vertex 1.67949 1.80588 2.50602 + endloop + endfacet + facet normal 0.717188 -0.0182651 0.69664 + outer loop + vertex 1.67949 1.80588 2.50602 + vertex 1.677 1.80304 2.50851 + vertex 1.67951 1.80089 2.50587 + endloop + endfacet + facet normal 0.692224 0.0252224 0.721242 + outer loop + vertex 1.67678 1.80807 2.50854 + vertex 1.677 1.80304 2.50851 + vertex 1.67949 1.80588 2.50602 + endloop + endfacet + facet normal 0.750228 -0.00120668 0.661178 + outer loop + vertex 1.68178 1.80888 2.50329 + vertex 1.68173 1.81384 2.50336 + vertex 1.67933 1.81094 2.50607 + endloop + endfacet + facet normal 0.756635 0.016589 0.653627 + outer loop + vertex 1.67949 1.80588 2.50602 + vertex 1.68178 1.80888 2.50329 + vertex 1.67933 1.81094 2.50607 + endloop + endfacet + facet normal 0.687441 0.0136692 0.726112 + outer loop + vertex 1.67933 1.81094 2.50607 + vertex 1.67678 1.80807 2.50854 + vertex 1.67949 1.80588 2.50602 + endloop + endfacet + facet normal 0.657886 0.061044 0.750639 + outer loop + vertex 1.67629 1.81355 2.50853 + vertex 1.67678 1.80807 2.50854 + vertex 1.67933 1.81094 2.50607 + endloop + endfacet + facet normal 0.728385 0.0229217 0.684784 + outer loop + vertex 1.68173 1.81384 2.50336 + vertex 1.68167 1.81876 2.50326 + vertex 1.67931 1.81589 2.50587 + endloop + endfacet + facet normal 0.731876 0.0320943 0.680681 + outer loop + vertex 1.67933 1.81094 2.50607 + vertex 1.68173 1.81384 2.50336 + vertex 1.67931 1.81589 2.50587 + endloop + endfacet + facet normal 0.645529 0.0350457 0.762931 + outer loop + vertex 1.67931 1.81589 2.50587 + vertex 1.67629 1.81355 2.50853 + vertex 1.67933 1.81094 2.50607 + endloop + endfacet + facet normal 0.640315 0.0461128 0.766727 + outer loop + vertex 1.67712 1.81803 2.50756 + vertex 1.67629 1.81355 2.50853 + vertex 1.67931 1.81589 2.50587 + endloop + endfacet + facet normal 0.707289 0.0385258 0.705874 + outer loop + vertex 1.68167 1.81876 2.50326 + vertex 1.68156 1.82362 2.50311 + vertex 1.67924 1.82058 2.50559 + endloop + endfacet + facet normal 0.711682 0.0510347 0.700646 + outer loop + vertex 1.67931 1.81589 2.50587 + vertex 1.68167 1.81876 2.50326 + vertex 1.67924 1.82058 2.50559 + endloop + endfacet + facet normal 0.644637 0.0537977 0.762594 + outer loop + vertex 1.67924 1.82058 2.50559 + vertex 1.67712 1.81803 2.50756 + vertex 1.67931 1.81589 2.50587 + endloop + endfacet + facet normal 0.612741 0.0970586 0.784301 + outer loop + vertex 1.67642 1.8221 2.50761 + vertex 1.67712 1.81803 2.50756 + vertex 1.67924 1.82058 2.50559 + endloop + endfacet + facet normal 0.672659 0.0514337 0.738163 + outer loop + vertex 1.68156 1.82362 2.50311 + vertex 1.68131 1.8285 2.50299 + vertex 1.67889 1.82531 2.50542 + endloop + endfacet + facet normal 0.680674 0.0772822 0.728498 + outer loop + vertex 1.67924 1.82058 2.50559 + vertex 1.68156 1.82362 2.50311 + vertex 1.67889 1.82531 2.50542 + endloop + endfacet + facet normal 0.605897 0.074016 0.792093 + outer loop + vertex 1.67889 1.82531 2.50542 + vertex 1.67642 1.8221 2.50761 + vertex 1.67924 1.82058 2.50559 + endloop + endfacet + facet normal 0.575225 0.110355 0.810517 + outer loop + vertex 1.67572 1.82704 2.50743 + vertex 1.67642 1.8221 2.50761 + vertex 1.67889 1.82531 2.50542 + endloop + endfacet + facet normal 0.635768 0.0536442 0.770014 + outer loop + vertex 1.68131 1.8285 2.50299 + vertex 1.68088 1.83366 2.50298 + vertex 1.67843 1.8301 2.50526 + endloop + endfacet + facet normal 0.645613 0.0874605 0.75864 + outer loop + vertex 1.67889 1.82531 2.50542 + vertex 1.68131 1.8285 2.50299 + vertex 1.67843 1.8301 2.50526 + endloop + endfacet + facet normal 0.565942 0.0818655 0.82037 + outer loop + vertex 1.67843 1.8301 2.50526 + vertex 1.67572 1.82704 2.50743 + vertex 1.67889 1.82531 2.50542 + endloop + endfacet + facet normal 0.542788 0.111026 0.832499 + outer loop + vertex 1.67505 1.8322 2.50718 + vertex 1.67572 1.82704 2.50743 + vertex 1.67843 1.8301 2.50526 + endloop + endfacet + facet normal 0.607837 0.0853205 0.789465 + outer loop + vertex 1.67796 1.83403 2.50519 + vertex 1.67843 1.8301 2.50526 + vertex 1.68088 1.83366 2.50298 + endloop + endfacet + facet normal 0.607625 0.0785537 0.790329 + outer loop + vertex 1.67796 1.83403 2.50519 + vertex 1.68088 1.83366 2.50298 + vertex 1.6788 1.83818 2.50413 + endloop + endfacet + facet normal 0.595054 0.0701335 0.80062 + outer loop + vertex 1.6788 1.83818 2.50413 + vertex 1.68088 1.83366 2.50298 + vertex 1.68178 1.83781 2.50195 + endloop + endfacet + facet normal 0.528784 0.0767889 0.845276 + outer loop + vertex 1.67843 1.8301 2.50526 + vertex 1.67796 1.83403 2.50519 + vertex 1.67505 1.8322 2.50718 + endloop + endfacet + facet normal 0.594717 0.0620104 0.80154 + outer loop + vertex 1.68178 1.83781 2.50195 + vertex 1.68114 1.84196 2.50211 + vertex 1.6788 1.83818 2.50413 + endloop + endfacet + facet normal 0.554253 0.100225 0.826292 + outer loop + vertex 1.6788 1.83818 2.50413 + vertex 1.68114 1.84196 2.50211 + vertex 1.67774 1.84357 2.50419 + endloop + endfacet + facet normal 0.545849 0.0712686 0.834847 + outer loop + vertex 1.68114 1.84196 2.50211 + vertex 1.68023 1.8474 2.50224 + vertex 1.67774 1.84357 2.50419 + endloop + endfacet + facet normal 0.495957 0.116701 0.86047 + outer loop + vertex 1.67774 1.84357 2.50419 + vertex 1.68023 1.8474 2.50224 + vertex 1.67633 1.84848 2.50434 + endloop + endfacet + facet normal 0.59177 0.091062 0.800947 + outer loop + vertex 1.68279 1.84912 2.50033 + vertex 1.68325 1.85269 2.49958 + vertex 1.68112 1.85131 2.50131 + endloop + endfacet + facet normal 0.568717 0.0650328 0.819958 + outer loop + vertex 1.68112 1.85131 2.50131 + vertex 1.68023 1.8474 2.50224 + vertex 1.68279 1.84912 2.50033 + endloop + endfacet + facet normal 0.48755 0.0950406 0.867907 + outer loop + vertex 1.68112 1.85131 2.50131 + vertex 1.67826 1.85215 2.50283 + vertex 1.68023 1.8474 2.50224 + endloop + endfacet + facet normal 0.492911 0.0976752 0.86458 + outer loop + vertex 1.67826 1.85215 2.50283 + vertex 1.67633 1.84848 2.50434 + vertex 1.68023 1.8474 2.50224 + endloop + endfacet + facet normal 0.562896 0.112026 0.818901 + outer loop + vertex 1.68325 1.85269 2.49958 + vertex 1.68341 1.85752 2.49881 + vertex 1.68052 1.85514 2.50112 + endloop + endfacet + facet normal 0.573319 0.129833 0.80898 + outer loop + vertex 1.68112 1.85131 2.50131 + vertex 1.68325 1.85269 2.49958 + vertex 1.68052 1.85514 2.50112 + endloop + endfacet + facet normal 0.491865 0.119768 0.862395 + outer loop + vertex 1.68052 1.85514 2.50112 + vertex 1.67826 1.85215 2.50283 + vertex 1.68112 1.85131 2.50131 + endloop + endfacet + facet normal 0.470455 0.140965 0.871092 + outer loop + vertex 1.67687 1.85699 2.50279 + vertex 1.67826 1.85215 2.50283 + vertex 1.68052 1.85514 2.50112 + endloop + endfacet + facet normal 0.534314 0.096214 0.839792 + outer loop + vertex 1.68341 1.85752 2.49881 + vertex 1.68247 1.86288 2.49879 + vertex 1.67976 1.85995 2.50085 + endloop + endfacet + facet normal 0.550166 0.132893 0.824413 + outer loop + vertex 1.68052 1.85514 2.50112 + vertex 1.68341 1.85752 2.49881 + vertex 1.67976 1.85995 2.50085 + endloop + endfacet + facet normal 0.463876 0.122128 0.877441 + outer loop + vertex 1.67976 1.85995 2.50085 + vertex 1.67687 1.85699 2.50279 + vertex 1.68052 1.85514 2.50112 + endloop + endfacet + facet normal 0.447251 0.142031 0.883059 + outer loop + vertex 1.67599 1.86194 2.50244 + vertex 1.67687 1.85699 2.50279 + vertex 1.67976 1.85995 2.50085 + endloop + endfacet + facet normal 0.499535 0.101415 0.860337 + outer loop + vertex 1.68247 1.86288 2.49879 + vertex 1.6816 1.86842 2.49864 + vertex 1.67891 1.86489 2.50063 + endloop + endfacet + facet normal 0.509373 0.127275 0.851082 + outer loop + vertex 1.67976 1.85995 2.50085 + vertex 1.68247 1.86288 2.49879 + vertex 1.67891 1.86489 2.50063 + endloop + endfacet + facet normal 0.437489 0.116691 0.89162 + outer loop + vertex 1.67891 1.86489 2.50063 + vertex 1.67599 1.86194 2.50244 + vertex 1.67976 1.85995 2.50085 + endloop + endfacet + facet normal 0.410809 0.147985 0.899632 + outer loop + vertex 1.67499 1.8669 2.50208 + vertex 1.67599 1.86194 2.50244 + vertex 1.67891 1.86489 2.50063 + endloop + endfacet + facet normal 0.471782 0.129233 0.872193 + outer loop + vertex 1.6781 1.86892 2.50046 + vertex 1.67891 1.86489 2.50063 + vertex 1.6816 1.86842 2.49864 + endloop + endfacet + facet normal 0.472041 0.134376 0.871275 + outer loop + vertex 1.6781 1.86892 2.50046 + vertex 1.6816 1.86842 2.49864 + vertex 1.67872 1.8732 2.49947 + endloop + endfacet + facet normal 0.450908 0.119312 0.88456 + outer loop + vertex 1.67872 1.8732 2.49947 + vertex 1.6816 1.86842 2.49864 + vertex 1.68228 1.87286 2.4977 + endloop + endfacet + facet normal 0.398309 0.116173 0.909865 + outer loop + vertex 1.67891 1.86489 2.50063 + vertex 1.6781 1.86892 2.50046 + vertex 1.67499 1.8669 2.50208 + endloop + endfacet + facet normal 0.282178 0.259995 0.92346 + outer loop + vertex 1.6797 2.04524 2.46078 + vertex 1.67966 2.04125 2.46191 + vertex 1.6826 2.04341 2.46041 + endloop + endfacet + facet normal 0.285655 0.259685 0.922477 + outer loop + vertex 1.6797 2.04524 2.46078 + vertex 1.67538 2.04567 2.462 + vertex 1.67966 2.04125 2.46191 + endloop + endfacet + facet normal 0.285694 0.26197 0.921819 + outer loop + vertex 1.6797 2.04524 2.46078 + vertex 1.67811 2.04827 2.46041 + vertex 1.67538 2.04567 2.462 + endloop + endfacet + facet normal 0.290833 0.313353 0.904005 + outer loop + vertex 1.68213 2.06721 2.45369 + vertex 1.6811 2.07108 2.45268 + vertex 1.67804 2.06814 2.45468 + endloop + endfacet + facet normal 0.330348 0.457577 0.825526 + outer loop + vertex 1.68307 2.07338 2.45109 + vertex 1.68175 2.07705 2.44959 + vertex 1.68002 2.07507 2.45138 + endloop + endfacet + facet normal 0.284775 0.365048 0.886365 + outer loop + vertex 1.68002 2.07507 2.45138 + vertex 1.6811 2.07108 2.45268 + vertex 1.68307 2.07338 2.45109 + endloop + endfacet + facet normal 0.301301 0.367419 0.879898 + outer loop + vertex 1.68002 2.07507 2.45138 + vertex 1.67629 2.07544 2.4525 + vertex 1.6811 2.07108 2.45268 + endloop + endfacet + facet normal 0.301754 0.367905 0.87954 + outer loop + vertex 1.67629 2.07544 2.4525 + vertex 1.67717 2.07202 2.45363 + vertex 1.6811 2.07108 2.45268 + endloop + endfacet + facet normal 0.329708 0.458105 0.825489 + outer loop + vertex 1.67761 2.07792 2.45076 + vertex 1.68002 2.07507 2.45138 + vertex 1.68175 2.07705 2.44959 + endloop + endfacet + facet normal 0.332107 0.538507 0.774413 + outer loop + vertex 1.67761 2.07792 2.45076 + vertex 1.68175 2.07705 2.44959 + vertex 1.67638 2.08171 2.44865 + endloop + endfacet + facet normal 0.34148 0.54726 0.764132 + outer loop + vertex 1.67638 2.08171 2.44865 + vertex 1.68175 2.07705 2.44959 + vertex 1.68202 2.08054 2.44697 + endloop + endfacet + facet normal 0.298776 0.436948 0.848416 + outer loop + vertex 1.68002 2.07507 2.45138 + vertex 1.67761 2.07792 2.45076 + vertex 1.67629 2.07544 2.4525 + endloop + endfacet + facet normal 0.370548 0.800957 0.470279 + outer loop + vertex 1.68315 2.0848 2.44098 + vertex 1.68084 2.08672 2.43954 + vertex 1.67917 2.08594 2.44219 + endloop + endfacet + facet normal 0.392068 0.748079 0.535407 + outer loop + vertex 1.67917 2.08594 2.44219 + vertex 1.67655 2.08608 2.44391 + vertex 1.67926 2.08388 2.44499 + endloop + endfacet + facet normal 0.377725 0.752672 0.539267 + outer loop + vertex 1.67917 2.08594 2.44219 + vertex 1.67926 2.08388 2.44499 + vertex 1.68315 2.0848 2.44098 + endloop + endfacet + facet normal 0.35578 0.774532 0.522993 + outer loop + vertex 1.68315 2.0848 2.44098 + vertex 1.67926 2.08388 2.44499 + vertex 1.68393 2.08234 2.44409 + endloop + endfacet + facet normal 0.336219 0.669894 0.661966 + outer loop + vertex 1.68202 2.08054 2.44697 + vertex 1.67926 2.08388 2.44499 + vertex 1.67638 2.08171 2.44865 + endloop + endfacet + facet normal 0.347165 0.673427 0.652666 + outer loop + vertex 1.68393 2.08234 2.44409 + vertex 1.67926 2.08388 2.44499 + vertex 1.68202 2.08054 2.44697 + endloop + endfacet + facet normal 0.149101 0.349997 0.924809 + outer loop + vertex 1.685 2.09211 2.435 + vertex 1.68 2.09424 2.435 + vertex 1.68224 2.08913 2.43657 + endloop + endfacet + facet normal 0.864293 0.449173 0.226364 + outer loop + vertex 1.68224 2.08913 2.43657 + vertex 1.68 2.09424 2.435 + vertex 1.68 2.09172 2.44 + endloop + endfacet + facet normal 0.446132 0.741977 0.500437 + outer loop + vertex 1.68084 2.08672 2.43954 + vertex 1.67741 2.08799 2.44072 + vertex 1.67917 2.08594 2.44219 + endloop + endfacet + facet normal 0.448082 0.578109 0.681918 + outer loop + vertex 1.68084 2.08672 2.43954 + vertex 1.68224 2.08913 2.43657 + vertex 1.67741 2.08799 2.44072 + endloop + endfacet + facet normal 0.658864 -0.326879 0.677531 + outer loop + vertex 1.68224 2.08913 2.43657 + vertex 1.68 2.09172 2.44 + vertex 1.67741 2.08799 2.44072 + endloop + endfacet + facet normal 0.399295 0.735416 0.547474 + outer loop + vertex 1.67917 2.08594 2.44219 + vertex 1.67741 2.08799 2.44072 + vertex 1.67655 2.08608 2.44391 + endloop + endfacet + facet normal 0.326886 0.119159 0.937522 + outer loop + vertex 1.68611 0.94344 2.43632 + vertex 1.69 0.94311 2.435 + vertex 1.68981 0.944026 2.43495 + endloop + endfacet + facet normal 0.313012 -0.0798283 0.946388 + outer loop + vertex 1.68611 0.94344 2.43632 + vertex 1.68261 0.942399 2.43738 + vertex 1.69 0.94311 2.435 + endloop + endfacet + facet normal 0.275526 -0.717159 0.640132 + outer loop + vertex 1.68261 0.942399 2.43738 + vertex 1.685 0.941189 2.435 + vertex 1.69 0.94311 2.435 + endloop + endfacet + facet normal 0.388288 -0.739714 0.549596 + outer loop + vertex 1.68611 0.94344 2.43632 + vertex 1.68336 0.943826 2.43877 + vertex 1.68261 0.942399 2.43738 + endloop + endfacet + facet normal 0.320253 -0.783658 0.532277 + outer loop + vertex 1.68981 0.944026 2.43495 + vertex 1.68748 0.944985 2.43776 + vertex 1.68611 0.94344 2.43632 + endloop + endfacet + facet normal 0.346687 -0.786857 0.510553 + outer loop + vertex 1.68336 0.943826 2.43877 + vertex 1.68611 0.94344 2.43632 + vertex 1.68748 0.944985 2.43776 + endloop + endfacet + facet normal 0.346084 -0.793704 0.500259 + outer loop + vertex 1.68336 0.943826 2.43877 + vertex 1.68748 0.944985 2.43776 + vertex 1.68175 0.945273 2.44219 + endloop + endfacet + facet normal 0.354721 -0.78313 0.510764 + outer loop + vertex 1.68175 0.945273 2.44219 + vertex 1.68748 0.944985 2.43776 + vertex 1.68653 0.947134 2.44172 + endloop + endfacet + facet normal 0.332279 -0.767573 0.548108 + outer loop + vertex 1.68549 0.94886 2.44477 + vertex 1.68653 0.947134 2.44172 + vertex 1.68824 0.948824 2.44305 + endloop + endfacet + facet normal 0.340161 -0.76373 0.548641 + outer loop + vertex 1.68549 0.94886 2.44477 + vertex 1.68193 0.947813 2.44552 + vertex 1.68653 0.947134 2.44172 + endloop + endfacet + facet normal 0.348052 -0.754407 0.556535 + outer loop + vertex 1.68193 0.947813 2.44552 + vertex 1.68175 0.945273 2.44219 + vertex 1.68653 0.947134 2.44172 + endloop + endfacet + facet normal 0.336816 -0.676991 0.654399 + outer loop + vertex 1.68549 0.94886 2.44477 + vertex 1.68393 0.950521 2.44729 + vertex 1.68193 0.947813 2.44552 + endloop + endfacet + facet normal 0.377799 -0.6883 0.619283 + outer loop + vertex 1.68824 0.948824 2.44305 + vertex 1.68805 0.950681 2.44523 + vertex 1.68549 0.94886 2.44477 + endloop + endfacet + facet normal 0.354401 -0.66503 0.657369 + outer loop + vertex 1.68805 0.950681 2.44523 + vertex 1.68393 0.950521 2.44729 + vertex 1.68549 0.94886 2.44477 + endloop + endfacet + facet normal 0.379329 -0.589537 0.713131 + outer loop + vertex 1.68805 0.950681 2.44523 + vertex 1.68814 0.954343 2.44821 + vertex 1.68393 0.950521 2.44729 + endloop + endfacet + facet normal 0.365571 -0.578308 0.729327 + outer loop + vertex 1.68814 0.954343 2.44821 + vertex 1.68251 0.952787 2.4498 + vertex 1.68393 0.950521 2.44729 + endloop + endfacet + facet normal 0.358684 -0.482059 0.799353 + outer loop + vertex 1.68251 0.952787 2.4498 + vertex 1.68814 0.954343 2.44821 + vertex 1.68502 0.956357 2.45082 + endloop + endfacet + facet normal 0.345684 -0.475648 0.808864 + outer loop + vertex 1.6812 0.954694 2.45148 + vertex 1.68251 0.952787 2.4498 + vertex 1.68502 0.956357 2.45082 + endloop + endfacet + facet normal 0.312311 -0.373244 0.873585 + outer loop + vertex 1.68502 0.956357 2.45082 + vertex 1.68272 0.958693 2.45264 + vertex 1.6812 0.954694 2.45148 + endloop + endfacet + facet normal 0.298232 -0.386486 0.872747 + outer loop + vertex 1.68761 0.960204 2.45164 + vertex 1.68272 0.958693 2.45264 + vertex 1.68502 0.956357 2.45082 + endloop + endfacet + facet normal 0.378376 -0.218368 0.899526 + outer loop + vertex 1.6889 1.06957 2.47988 + vertex 1.68636 1.07025 2.48112 + vertex 1.68499 1.0665 2.48078 + endloop + endfacet + facet normal 0.328854 -0.20237 0.922443 + outer loop + vertex 1.68636 1.07025 2.48112 + vertex 1.68232 1.06858 2.48219 + vertex 1.68499 1.0665 2.48078 + endloop + endfacet + facet normal 0.325108 -0.190965 0.926195 + outer loop + vertex 1.68636 1.07025 2.48112 + vertex 1.68632 1.07356 2.48181 + vertex 1.68232 1.06858 2.48219 + endloop + endfacet + facet normal 0.395281 -0.21297 0.89353 + outer loop + vertex 1.6826 1.07915 2.48441 + vertex 1.68742 1.08408 2.48345 + vertex 1.68397 1.08447 2.48507 + endloop + endfacet + facet normal 0.467972 -0.148808 0.871125 + outer loop + vertex 1.68228 1.12391 2.49341 + vertex 1.68588 1.12812 2.49219 + vertex 1.68236 1.12918 2.49426 + endloop + endfacet + facet normal 0.478246 -0.113962 0.8708 + outer loop + vertex 1.68588 1.12812 2.49219 + vertex 1.68617 1.13324 2.4927 + vertex 1.68236 1.12918 2.49426 + endloop + endfacet + facet normal 0.517466 -0.162435 0.840145 + outer loop + vertex 1.68236 1.12918 2.49426 + vertex 1.68617 1.13324 2.4927 + vertex 1.6834 1.13444 2.49464 + endloop + endfacet + facet normal 0.455388 -0.145943 0.87825 + outer loop + vertex 1.68332 1.13787 2.49525 + vertex 1.68117 1.13533 2.49594 + vertex 1.6834 1.13444 2.49464 + endloop + endfacet + facet normal 0.559606 -0.132558 0.818089 + outer loop + vertex 1.68332 1.13787 2.49525 + vertex 1.6834 1.13444 2.49464 + vertex 1.68621 1.13869 2.4934 + endloop + endfacet + facet normal 0.536677 -0.112088 0.83631 + outer loop + vertex 1.68621 1.13869 2.4934 + vertex 1.6834 1.13444 2.49464 + vertex 1.68617 1.13324 2.4927 + endloop + endfacet + facet normal 0.43906 -0.12922 0.889117 + outer loop + vertex 1.68332 1.13787 2.49525 + vertex 1.68085 1.13853 2.49657 + vertex 1.68117 1.13533 2.49594 + endloop + endfacet + facet normal 0.586506 -0.0832234 0.805658 + outer loop + vertex 1.68621 1.13869 2.4934 + vertex 1.68691 1.14421 2.49347 + vertex 1.68397 1.14164 2.49534 + endloop + endfacet + facet normal 0.557473 -0.115978 0.822054 + outer loop + vertex 1.68332 1.13787 2.49525 + vertex 1.68621 1.13869 2.4934 + vertex 1.68397 1.14164 2.49534 + endloop + endfacet + facet normal 0.447206 -0.0982964 0.889013 + outer loop + vertex 1.68397 1.14164 2.49534 + vertex 1.68085 1.13853 2.49657 + vertex 1.68332 1.13787 2.49525 + endloop + endfacet + facet normal 0.469003 -0.126009 0.874161 + outer loop + vertex 1.681 1.1431 2.49715 + vertex 1.68085 1.13853 2.49657 + vertex 1.68397 1.14164 2.49534 + endloop + endfacet + facet normal 0.615351 -0.0537223 0.78642 + outer loop + vertex 1.68691 1.14421 2.49347 + vertex 1.68714 1.14922 2.49363 + vertex 1.68433 1.14645 2.49564 + endloop + endfacet + facet normal 0.592246 -0.0936923 0.800291 + outer loop + vertex 1.68397 1.14164 2.49534 + vertex 1.68691 1.14421 2.49347 + vertex 1.68433 1.14645 2.49564 + endloop + endfacet + facet normal 0.48433 -0.0900382 0.87024 + outer loop + vertex 1.68433 1.14645 2.49564 + vertex 1.681 1.1431 2.49715 + vertex 1.68397 1.14164 2.49534 + endloop + endfacet + facet normal 0.504667 -0.11697 0.855353 + outer loop + vertex 1.68135 1.1482 2.49764 + vertex 1.681 1.1431 2.49715 + vertex 1.68433 1.14645 2.49564 + endloop + endfacet + facet normal 0.649935 -0.0163485 0.759814 + outer loop + vertex 1.68714 1.14922 2.49363 + vertex 1.68721 1.15423 2.49368 + vertex 1.68452 1.15143 2.49592 + endloop + endfacet + facet normal 0.623512 -0.0674658 0.778898 + outer loop + vertex 1.68433 1.14645 2.49564 + vertex 1.68714 1.14922 2.49363 + vertex 1.68452 1.15143 2.49592 + endloop + endfacet + facet normal 0.527835 -0.0675444 0.846657 + outer loop + vertex 1.68452 1.15143 2.49592 + vertex 1.68135 1.1482 2.49764 + vertex 1.68433 1.14645 2.49564 + endloop + endfacet + facet normal 0.546558 -0.0936719 0.832166 + outer loop + vertex 1.6817 1.15332 2.49799 + vertex 1.68135 1.1482 2.49764 + vertex 1.68452 1.15143 2.49592 + endloop + endfacet + facet normal 0.679123 0.0144186 0.733883 + outer loop + vertex 1.68721 1.15423 2.49368 + vertex 1.68725 1.15941 2.49354 + vertex 1.68457 1.15645 2.49607 + endloop + endfacet + facet normal 0.658212 -0.0303749 0.752219 + outer loop + vertex 1.68452 1.15143 2.49592 + vertex 1.68721 1.15423 2.49368 + vertex 1.68457 1.15645 2.49607 + endloop + endfacet + facet normal 0.576519 -0.0315729 0.816473 + outer loop + vertex 1.68457 1.15645 2.49607 + vertex 1.6817 1.15332 2.49799 + vertex 1.68452 1.15143 2.49592 + endloop + endfacet + facet normal 0.588276 -0.0480325 0.807232 + outer loop + vertex 1.68173 1.15829 2.49825 + vertex 1.6817 1.15332 2.49799 + vertex 1.68457 1.15645 2.49607 + endloop + endfacet + facet normal 0.698566 0.0312549 0.714862 + outer loop + vertex 1.68725 1.15941 2.49354 + vertex 1.68715 1.16464 2.4934 + vertex 1.68449 1.16155 2.49615 + endloop + endfacet + facet normal 0.686791 0.00146945 0.726853 + outer loop + vertex 1.68457 1.15645 2.49607 + vertex 1.68725 1.15941 2.49354 + vertex 1.68449 1.16155 2.49615 + endloop + endfacet + facet normal 0.608389 -0.000816962 0.793638 + outer loop + vertex 1.68449 1.16155 2.49615 + vertex 1.68173 1.15829 2.49825 + vertex 1.68457 1.15645 2.49607 + endloop + endfacet + facet normal 0.619118 -0.0153246 0.785149 + outer loop + vertex 1.68134 1.16355 2.49866 + vertex 1.68173 1.15829 2.49825 + vertex 1.68449 1.16155 2.49615 + endloop + endfacet + facet normal 0.72618 0.0355226 0.686586 + outer loop + vertex 1.68715 1.16464 2.4934 + vertex 1.68697 1.16974 2.49334 + vertex 1.68449 1.16675 2.49612 + endloop + endfacet + facet normal 0.714491 0.00396527 0.699633 + outer loop + vertex 1.68449 1.16155 2.49615 + vertex 1.68715 1.16464 2.4934 + vertex 1.68449 1.16675 2.49612 + endloop + endfacet + facet normal 0.626822 0.00440432 0.77915 + outer loop + vertex 1.68449 1.16675 2.49612 + vertex 1.68134 1.16355 2.49866 + vertex 1.68449 1.16155 2.49615 + endloop + endfacet + facet normal 0.646102 -0.027528 0.762755 + outer loop + vertex 1.68188 1.16911 2.49841 + vertex 1.68134 1.16355 2.49866 + vertex 1.68449 1.16675 2.49612 + endloop + endfacet + facet normal 0.765833 0.0234864 0.642611 + outer loop + vertex 1.68697 1.16974 2.49334 + vertex 1.68689 1.17474 2.49325 + vertex 1.68465 1.17186 2.49602 + endloop + endfacet + facet normal 0.752226 -0.0119165 0.658797 + outer loop + vertex 1.68449 1.16675 2.49612 + vertex 1.68697 1.16974 2.49334 + vertex 1.68465 1.17186 2.49602 + endloop + endfacet + facet normal 0.656858 -0.00712677 0.75398 + outer loop + vertex 1.68465 1.17186 2.49602 + vertex 1.68188 1.16911 2.49841 + vertex 1.68449 1.16675 2.49612 + endloop + endfacet + facet normal 0.673569 -0.0376989 0.738162 + outer loop + vertex 1.68218 1.17419 2.49839 + vertex 1.68188 1.16911 2.49841 + vertex 1.68465 1.17186 2.49602 + endloop + endfacet + facet normal 0.799501 -0.00527493 0.600641 + outer loop + vertex 1.68689 1.17474 2.49325 + vertex 1.68695 1.17974 2.49321 + vertex 1.68484 1.17683 2.49599 + endloop + endfacet + facet normal 0.791274 -0.0267154 0.610877 + outer loop + vertex 1.68465 1.17186 2.49602 + vertex 1.68689 1.17474 2.49325 + vertex 1.68484 1.17683 2.49599 + endloop + endfacet + facet normal 0.682033 -0.0214894 0.731006 + outer loop + vertex 1.68484 1.17683 2.49599 + vertex 1.68218 1.17419 2.49839 + vertex 1.68465 1.17186 2.49602 + endloop + endfacet + facet normal 0.695302 -0.0474487 0.71715 + outer loop + vertex 1.68243 1.1792 2.49848 + vertex 1.68218 1.17419 2.49839 + vertex 1.68484 1.17683 2.49599 + endloop + endfacet + facet normal 0.817544 -0.0176081 0.575597 + outer loop + vertex 1.68695 1.17974 2.49321 + vertex 1.68707 1.18478 2.49319 + vertex 1.68504 1.18182 2.49598 + endloop + endfacet + facet normal 0.812198 -0.0317403 0.582518 + outer loop + vertex 1.68484 1.17683 2.49599 + vertex 1.68695 1.17974 2.49321 + vertex 1.68504 1.18182 2.49598 + endloop + endfacet + facet normal 0.705536 -0.0274754 0.708141 + outer loop + vertex 1.68504 1.18182 2.49598 + vertex 1.68243 1.1792 2.49848 + vertex 1.68484 1.17683 2.49599 + endloop + endfacet + facet normal 0.714659 -0.0462882 0.69794 + outer loop + vertex 1.68262 1.18425 2.49863 + vertex 1.68243 1.1792 2.49848 + vertex 1.68504 1.18182 2.49598 + endloop + endfacet + facet normal 0.825025 -0.0060814 0.565064 + outer loop + vertex 1.68707 1.18478 2.49319 + vertex 1.68706 1.18982 2.49326 + vertex 1.68514 1.18688 2.49603 + endloop + endfacet + facet normal 0.81943 -0.0215674 0.572773 + outer loop + vertex 1.68504 1.18182 2.49598 + vertex 1.68707 1.18478 2.49319 + vertex 1.68514 1.18688 2.49603 + endloop + endfacet + facet normal 0.72725 -0.0208231 0.686056 + outer loop + vertex 1.68514 1.18688 2.49603 + vertex 1.68262 1.18425 2.49863 + vertex 1.68504 1.18182 2.49598 + endloop + endfacet + facet normal 0.736656 -0.0407045 0.675041 + outer loop + vertex 1.68272 1.18936 2.49882 + vertex 1.68262 1.18425 2.49863 + vertex 1.68514 1.18688 2.49603 + endloop + endfacet + facet normal 0.83189 0.00836418 0.554878 + outer loop + vertex 1.68706 1.18982 2.49326 + vertex 1.68684 1.19478 2.49351 + vertex 1.68507 1.19202 2.49621 + endloop + endfacet + facet normal 0.826125 -0.00834298 0.563426 + outer loop + vertex 1.68514 1.18688 2.49603 + vertex 1.68706 1.18982 2.49326 + vertex 1.68507 1.19202 2.49621 + endloop + endfacet + facet normal 0.74966 -0.0129227 0.661697 + outer loop + vertex 1.68507 1.19202 2.49621 + vertex 1.68272 1.18936 2.49882 + vertex 1.68514 1.18688 2.49603 + endloop + endfacet + facet normal 0.759985 -0.0344561 0.649027 + outer loop + vertex 1.68269 1.19433 2.49912 + vertex 1.68272 1.18936 2.49882 + vertex 1.68507 1.19202 2.49621 + endloop + endfacet + facet normal 0.839374 0.01478 0.543353 + outer loop + vertex 1.68684 1.19478 2.49351 + vertex 1.68672 1.19964 2.49357 + vertex 1.68478 1.19752 2.49662 + endloop + endfacet + facet normal 0.834602 0.00268501 0.550847 + outer loop + vertex 1.68507 1.19202 2.49621 + vertex 1.68684 1.19478 2.49351 + vertex 1.68478 1.19752 2.49662 + endloop + endfacet + facet normal 0.771295 -0.00699335 0.636439 + outer loop + vertex 1.68478 1.19752 2.49662 + vertex 1.68269 1.19433 2.49912 + vertex 1.68507 1.19202 2.49621 + endloop + endfacet + facet normal 0.785081 -0.0298599 0.618673 + outer loop + vertex 1.68249 1.19826 2.49956 + vertex 1.68269 1.19433 2.49912 + vertex 1.68478 1.19752 2.49662 + endloop + endfacet + facet normal 0.855361 -0.00341879 0.518021 + outer loop + vertex 1.68672 1.19964 2.49357 + vertex 1.68664 1.20464 2.49373 + vertex 1.68542 1.20188 2.49572 + endloop + endfacet + facet normal 0.849181 -0.0164773 0.527844 + outer loop + vertex 1.68478 1.19752 2.49662 + vertex 1.68672 1.19964 2.49357 + vertex 1.68542 1.20188 2.49572 + endloop + endfacet + facet normal 0.759154 -0.0152662 0.650732 + outer loop + vertex 1.68249 1.19826 2.49956 + vertex 1.68331 1.20218 2.4987 + vertex 1.68111 1.20029 2.50122 + endloop + endfacet + facet normal 0.78538 -0.0278188 0.618388 + outer loop + vertex 1.68249 1.19826 2.49956 + vertex 1.68478 1.19752 2.49662 + vertex 1.68331 1.20218 2.4987 + endloop + endfacet + facet normal 0.815202 -0.000861952 0.579177 + outer loop + vertex 1.68478 1.19752 2.49662 + vertex 1.68542 1.20188 2.49572 + vertex 1.68331 1.20218 2.4987 + endloop + endfacet + facet normal 0.76548 -0.0335069 0.642586 + outer loop + vertex 1.68331 1.20218 2.4987 + vertex 1.68086 1.20393 2.50172 + vertex 1.68111 1.20029 2.50122 + endloop + endfacet + facet normal 0.853969 -0.0182592 0.520003 + outer loop + vertex 1.68664 1.20464 2.49373 + vertex 1.68657 1.20978 2.49403 + vertex 1.68512 1.206 2.49628 + endloop + endfacet + facet normal 0.856986 -0.00610233 0.515303 + outer loop + vertex 1.68542 1.20188 2.49572 + vertex 1.68664 1.20464 2.49373 + vertex 1.68512 1.206 2.49628 + endloop + endfacet + facet normal 0.814254 -0.0180355 0.580229 + outer loop + vertex 1.68542 1.20188 2.49572 + vertex 1.68512 1.206 2.49628 + vertex 1.68331 1.20218 2.4987 + endloop + endfacet + facet normal 0.8195 -0.0253992 0.572516 + outer loop + vertex 1.68512 1.206 2.49628 + vertex 1.68311 1.20724 2.49921 + vertex 1.68331 1.20218 2.4987 + endloop + endfacet + facet normal 0.76517 -0.0344875 0.642904 + outer loop + vertex 1.68311 1.20724 2.49921 + vertex 1.68086 1.20393 2.50172 + vertex 1.68331 1.20218 2.4987 + endloop + endfacet + facet normal 0.77291 -0.047451 0.632739 + outer loop + vertex 1.68083 1.20856 2.5021 + vertex 1.68086 1.20393 2.50172 + vertex 1.68311 1.20724 2.49921 + endloop + endfacet + facet normal 0.856489 -0.00812864 0.516101 + outer loop + vertex 1.68657 1.20978 2.49403 + vertex 1.68661 1.21505 2.49405 + vertex 1.68508 1.21094 2.49652 + endloop + endfacet + facet normal 0.854205 -0.0185873 0.519603 + outer loop + vertex 1.68512 1.206 2.49628 + vertex 1.68657 1.20978 2.49403 + vertex 1.68508 1.21094 2.49652 + endloop + endfacet + facet normal 0.820386 -0.0213624 0.571411 + outer loop + vertex 1.68512 1.206 2.49628 + vertex 1.68508 1.21094 2.49652 + vertex 1.68311 1.20724 2.49921 + endloop + endfacet + facet normal 0.820916 -0.0222211 0.570617 + outer loop + vertex 1.68508 1.21094 2.49652 + vertex 1.68312 1.21211 2.49938 + vertex 1.68311 1.20724 2.49921 + endloop + endfacet + facet normal 0.778812 -0.0241646 0.626792 + outer loop + vertex 1.68312 1.21211 2.49938 + vertex 1.68083 1.20856 2.5021 + vertex 1.68311 1.20724 2.49921 + endloop + endfacet + facet normal 0.784752 -0.034075 0.618873 + outer loop + vertex 1.68091 1.21335 2.50226 + vertex 1.68083 1.20856 2.5021 + vertex 1.68312 1.21211 2.49938 + endloop + endfacet + facet normal 0.840466 0.0613499 0.538379 + outer loop + vertex 1.68661 1.21505 2.49405 + vertex 1.68648 1.22022 2.49367 + vertex 1.68503 1.21613 2.49639 + endloop + endfacet + facet normal 0.833563 0.0219388 0.551988 + outer loop + vertex 1.68508 1.21094 2.49652 + vertex 1.68661 1.21505 2.49405 + vertex 1.68503 1.21613 2.49639 + endloop + endfacet + facet normal 0.829307 0.0220559 0.558358 + outer loop + vertex 1.68508 1.21094 2.49652 + vertex 1.68503 1.21613 2.49639 + vertex 1.68312 1.21211 2.49938 + endloop + endfacet + facet normal 0.830111 0.0208223 0.557209 + outer loop + vertex 1.68503 1.21613 2.49639 + vertex 1.68303 1.21718 2.49933 + vertex 1.68312 1.21211 2.49938 + endloop + endfacet + facet normal 0.796538 0.0206927 0.604235 + outer loop + vertex 1.68303 1.21718 2.49933 + vertex 1.68091 1.21335 2.50226 + vertex 1.68312 1.21211 2.49938 + endloop + endfacet + facet normal 0.817249 -0.0122797 0.576154 + outer loop + vertex 1.6809 1.21828 2.50238 + vertex 1.68091 1.21335 2.50226 + vertex 1.68303 1.21718 2.49933 + endloop + endfacet + facet normal 0.815898 0.127982 0.563854 + outer loop + vertex 1.68648 1.22022 2.49367 + vertex 1.68623 1.22483 2.49298 + vertex 1.68462 1.22218 2.49591 + endloop + endfacet + facet normal 0.807849 0.101053 0.580662 + outer loop + vertex 1.68503 1.21613 2.49639 + vertex 1.68648 1.22022 2.49367 + vertex 1.68462 1.22218 2.49591 + endloop + endfacet + facet normal 0.838869 0.0995175 0.535159 + outer loop + vertex 1.68503 1.21613 2.49639 + vertex 1.68462 1.22218 2.49591 + vertex 1.68303 1.21718 2.49933 + endloop + endfacet + facet normal 0.872432 0.054919 0.485641 + outer loop + vertex 1.68462 1.22218 2.49591 + vertex 1.68263 1.22242 2.49946 + vertex 1.68303 1.21718 2.49933 + endloop + endfacet + facet normal 0.82671 0.0496213 0.560436 + outer loop + vertex 1.68263 1.22242 2.49946 + vertex 1.6809 1.21828 2.50238 + vertex 1.68303 1.21718 2.49933 + endloop + endfacet + facet normal 0.862618 -0.00388549 0.50584 + outer loop + vertex 1.68063 1.22356 2.50287 + vertex 1.6809 1.21828 2.50238 + vertex 1.68263 1.22242 2.49946 + endloop + endfacet + facet normal 0.818444 0.0339599 0.573581 + outer loop + vertex 1.68365 1.22779 2.49696 + vertex 1.68462 1.22218 2.49591 + vertex 1.685 1.22839 2.495 + endloop + endfacet + facet normal 0.794379 -0.447043 0.411235 + outer loop + vertex 1.68365 1.22779 2.49696 + vertex 1.685 1.22839 2.495 + vertex 1.685 1.23 2.49675 + endloop + endfacet + facet normal 0.868895 0.0193227 0.49462 + outer loop + vertex 1.68462 1.22218 2.49591 + vertex 1.68623 1.22483 2.49298 + vertex 1.685 1.22839 2.495 + endloop + endfacet + facet normal 0.397431 -0.762758 0.510146 + outer loop + vertex 1.68809 1.23 2.495 + vertex 1.685 1.22839 2.495 + vertex 1.68678 1.22794 2.49294 + endloop + endfacet + facet normal 0.737273 -0.122719 0.664356 + outer loop + vertex 1.68623 1.22483 2.49298 + vertex 1.68678 1.22794 2.49294 + vertex 1.685 1.22839 2.495 + endloop + endfacet + facet normal 0.872331 0.059883 0.485235 + outer loop + vertex 1.68462 1.22218 2.49591 + vertex 1.68365 1.22779 2.49696 + vertex 1.68263 1.22242 2.49946 + endloop + endfacet + facet normal 0.908478 0.0215314 0.417378 + outer loop + vertex 1.68365 1.22779 2.49696 + vertex 1.68234 1.22769 2.49982 + vertex 1.68263 1.22242 2.49946 + endloop + endfacet + facet normal 0.865022 0.0132887 0.501557 + outer loop + vertex 1.68234 1.22769 2.49982 + vertex 1.68063 1.22356 2.50287 + vertex 1.68263 1.22242 2.49946 + endloop + endfacet + facet normal 0.894981 -0.0414334 0.444176 + outer loop + vertex 1.68102 1.22931 2.50264 + vertex 1.68063 1.22356 2.50287 + vertex 1.68234 1.22769 2.49982 + endloop + endfacet + facet normal -0.0924501 -0.210261 0.973264 + outer loop + vertex 1.68365 1.22779 2.49696 + vertex 1.685 1.235 2.49865 + vertex 1.68324 1.23279 2.498 + endloop + endfacet + facet normal 0.588437 -0.287204 0.755815 + outer loop + vertex 1.68365 1.22779 2.49696 + vertex 1.685 1.23 2.49675 + vertex 1.685 1.235 2.49865 + endloop + endfacet + facet normal 0.568324 -0.733488 0.372832 + outer loop + vertex 1.68809 1.23 2.495 + vertex 1.68678 1.22794 2.49294 + vertex 1.69 1.23148 2.495 + endloop + endfacet + facet normal 0.90908 -0.0120524 0.416446 + outer loop + vertex 1.68365 1.22779 2.49696 + vertex 1.68324 1.23279 2.498 + vertex 1.68234 1.22769 2.49982 + endloop + endfacet + facet normal 0.920769 -0.0237664 0.389384 + outer loop + vertex 1.68324 1.23279 2.498 + vertex 1.68239 1.23299 2.50001 + vertex 1.68234 1.22769 2.49982 + endloop + endfacet + facet normal 0.899192 -0.0252148 0.436827 + outer loop + vertex 1.68239 1.23299 2.50001 + vertex 1.68102 1.22931 2.50264 + vertex 1.68234 1.22769 2.49982 + endloop + endfacet + facet normal 0.906112 -0.0389267 0.421244 + outer loop + vertex 1.68125 1.23458 2.50262 + vertex 1.68102 1.22931 2.50264 + vertex 1.68239 1.23299 2.50001 + endloop + endfacet + facet normal -0.35813 0.0130879 0.93358 + outer loop + vertex 1.685 1.24 2.49858 + vertex 1.68324 1.23279 2.498 + vertex 1.685 1.235 2.49865 + endloop + endfacet + facet normal -0.179247 -0.0345923 0.983196 + outer loop + vertex 1.68328 1.23802 2.4982 + vertex 1.68324 1.23279 2.498 + vertex 1.685 1.24 2.49858 + endloop + endfacet + facet normal 0.920926 -0.0209971 0.38917 + outer loop + vertex 1.68324 1.23279 2.498 + vertex 1.68328 1.23802 2.4982 + vertex 1.68239 1.23299 2.50001 + endloop + endfacet + facet normal 0.931589 -0.0326602 0.362042 + outer loop + vertex 1.68328 1.23802 2.4982 + vertex 1.68257 1.23834 2.50005 + vertex 1.68239 1.23299 2.50001 + endloop + endfacet + facet normal 0.907888 -0.0322733 0.417969 + outer loop + vertex 1.68257 1.23834 2.50005 + vertex 1.68125 1.23458 2.50262 + vertex 1.68239 1.23299 2.50001 + endloop + endfacet + facet normal 0.905146 -0.0270315 0.42424 + outer loop + vertex 1.68139 1.23969 2.50264 + vertex 1.68125 1.23458 2.50262 + vertex 1.68257 1.23834 2.50005 + endloop + endfacet + facet normal -0.236506 0.017464 0.971473 + outer loop + vertex 1.685 1.245 2.49849 + vertex 1.68328 1.23802 2.4982 + vertex 1.685 1.24 2.49858 + endloop + endfacet + facet normal -0.182219 0.00356407 0.983251 + outer loop + vertex 1.68345 1.24347 2.49821 + vertex 1.68328 1.23802 2.4982 + vertex 1.685 1.245 2.49849 + endloop + endfacet + facet normal 0.931826 -0.0299993 0.361664 + outer loop + vertex 1.68328 1.23802 2.4982 + vertex 1.68345 1.24347 2.49821 + vertex 1.68257 1.23834 2.50005 + endloop + endfacet + facet normal 0.93136 -0.0294752 0.362904 + outer loop + vertex 1.68345 1.24347 2.49821 + vertex 1.68274 1.24362 2.50003 + vertex 1.68257 1.23834 2.50005 + endloop + endfacet + facet normal 0.904828 -0.028433 0.424826 + outer loop + vertex 1.68274 1.24362 2.50003 + vertex 1.68139 1.23969 2.50264 + vertex 1.68257 1.23834 2.50005 + endloop + endfacet + facet normal 0.904444 -0.0277277 0.42569 + outer loop + vertex 1.68152 1.24469 2.50269 + vertex 1.68139 1.23969 2.50264 + vertex 1.68274 1.24362 2.50003 + endloop + endfacet + facet normal -0.193735 0.0157162 0.980928 + outer loop + vertex 1.685 1.25 2.49841 + vertex 1.68345 1.24347 2.49821 + vertex 1.685 1.245 2.49849 + endloop + endfacet + facet normal -0.154321 0.00611678 0.988002 + outer loop + vertex 1.68361 1.24883 2.4982 + vertex 1.68345 1.24347 2.49821 + vertex 1.685 1.25 2.49841 + endloop + endfacet + facet normal 0.931488 -0.0270664 0.362763 + outer loop + vertex 1.68345 1.24347 2.49821 + vertex 1.68361 1.24883 2.4982 + vertex 1.68274 1.24362 2.50003 + endloop + endfacet + facet normal 0.92931 -0.0246966 0.368474 + outer loop + vertex 1.68361 1.24883 2.4982 + vertex 1.68286 1.24866 2.50007 + vertex 1.68274 1.24362 2.50003 + endloop + endfacet + facet normal 0.905015 -0.0245615 0.424671 + outer loop + vertex 1.68286 1.24866 2.50007 + vertex 1.68152 1.24469 2.50269 + vertex 1.68274 1.24362 2.50003 + endloop + endfacet + facet normal 0.896284 -0.00927857 0.443383 + outer loop + vertex 1.68163 1.2495 2.50257 + vertex 1.68152 1.24469 2.50269 + vertex 1.68286 1.24866 2.50007 + endloop + endfacet + facet normal -0.154173 0.00593621 0.988026 + outer loop + vertex 1.685 1.255 2.49838 + vertex 1.68361 1.24883 2.4982 + vertex 1.685 1.25 2.49841 + endloop + endfacet + facet normal -0.0767572 -0.011822 0.99698 + outer loop + vertex 1.68361 1.25378 2.49826 + vertex 1.68361 1.24883 2.4982 + vertex 1.685 1.255 2.49838 + endloop + endfacet + facet normal 0.928964 -0.00487323 0.370137 + outer loop + vertex 1.68361 1.24883 2.4982 + vertex 1.68361 1.25378 2.49826 + vertex 1.68286 1.24866 2.50007 + endloop + endfacet + facet normal 0.895628 0.0261661 0.444033 + outer loop + vertex 1.68361 1.25378 2.49826 + vertex 1.68275 1.25303 2.50003 + vertex 1.68286 1.24866 2.50007 + endloop + endfacet + facet normal 0.900701 0.0261975 0.43365 + outer loop + vertex 1.68275 1.25303 2.50003 + vertex 1.68163 1.2495 2.50257 + vertex 1.68286 1.24866 2.50007 + endloop + endfacet + facet normal 0.862424 0.0852547 0.498955 + outer loop + vertex 1.68165 1.25336 2.50188 + vertex 1.68163 1.2495 2.50257 + vertex 1.68275 1.25303 2.50003 + endloop + endfacet + facet normal -0.0748789 -0.0139783 0.997095 + outer loop + vertex 1.685 1.26 2.49845 + vertex 1.68361 1.25378 2.49826 + vertex 1.685 1.255 2.49838 + endloop + endfacet + facet normal -0.0659362 -0.0159981 0.997696 + outer loop + vertex 1.68311 1.25814 2.4983 + vertex 1.68361 1.25378 2.49826 + vertex 1.685 1.26 2.49845 + endloop + endfacet + facet normal 0.556373 0.347901 0.754596 + outer loop + vertex 1.68213 1.25607 2.49997 + vertex 1.68311 1.25814 2.4983 + vertex 1.68157 1.25957 2.49877 + endloop + endfacet + facet normal 0.748014 0.16581 0.642637 + outer loop + vertex 1.68213 1.25607 2.49997 + vertex 1.68275 1.25303 2.50003 + vertex 1.68311 1.25814 2.4983 + endloop + endfacet + facet normal 0.879475 0.0965334 0.466053 + outer loop + vertex 1.68275 1.25303 2.50003 + vertex 1.68361 1.25378 2.49826 + vertex 1.68311 1.25814 2.4983 + endloop + endfacet + facet normal 0.858237 0.185411 0.478594 + outer loop + vertex 1.68275 1.25303 2.50003 + vertex 1.68213 1.25607 2.49997 + vertex 1.68165 1.25336 2.50188 + endloop + endfacet + facet normal 0.0727576 -0.155628 0.985133 + outer loop + vertex 1.685 1.265 2.49924 + vertex 1.68311 1.25814 2.4983 + vertex 1.685 1.26 2.49845 + endloop + endfacet + facet normal -0.532277 0.0300867 0.846036 + outer loop + vertex 1.68276 1.26169 2.49795 + vertex 1.68311 1.25814 2.4983 + vertex 1.685 1.265 2.49924 + endloop + endfacet + facet normal 0.397986 0.126782 0.908589 + outer loop + vertex 1.68276 1.26169 2.49795 + vertex 1.68157 1.25957 2.49877 + vertex 1.68311 1.25814 2.4983 + endloop + endfacet + facet normal 0.376908 0.141349 0.915402 + outer loop + vertex 1.68172 1.26255 2.49825 + vertex 1.68157 1.25957 2.49877 + vertex 1.68276 1.26169 2.49795 + endloop + endfacet + facet normal 0.481764 -0.580327 0.6566 + outer loop + vertex 1.685 1.265 2.49924 + vertex 1.685 1.26586 2.5 + vertex 1.68276 1.26169 2.49795 + endloop + endfacet + facet normal -0.0749677 -0.406754 0.910457 + outer loop + vertex 1.68276 1.26169 2.49795 + vertex 1.685 1.26586 2.5 + vertex 1.68172 1.26255 2.49825 + endloop + endfacet + facet normal -0.588453 0.234536 0.773767 + outer loop + vertex 1.68361 1.7696 2.4976 + vertex 1.685 1.76515 2.5 + vertex 1.685 1.77 2.49853 + endloop + endfacet + facet normal 0.583019 0.519191 0.624924 + outer loop + vertex 1.68361 1.7696 2.4976 + vertex 1.68264 1.7689 2.49908 + vertex 1.685 1.76515 2.5 + endloop + endfacet + facet normal -0.560977 0.0165363 0.827666 + outer loop + vertex 1.685 1.775 2.49843 + vertex 1.68361 1.7696 2.4976 + vertex 1.685 1.77 2.49853 + endloop + endfacet + facet normal -0.359534 -0.0510916 0.931732 + outer loop + vertex 1.68327 1.77344 2.49767 + vertex 1.68361 1.7696 2.4976 + vertex 1.685 1.775 2.49843 + endloop + endfacet + facet normal 0.820586 0.0634277 0.567992 + outer loop + vertex 1.68327 1.77344 2.49767 + vertex 1.68264 1.7689 2.49908 + vertex 1.68361 1.7696 2.4976 + endloop + endfacet + facet normal 0.906696 0.00615577 0.421741 + outer loop + vertex 1.68232 1.77351 2.4997 + vertex 1.68264 1.7689 2.49908 + vertex 1.68327 1.77344 2.49767 + endloop + endfacet + facet normal -0.396332 -0.00367739 0.9181 + outer loop + vertex 1.685 1.78 2.49845 + vertex 1.68327 1.77344 2.49767 + vertex 1.685 1.775 2.49843 + endloop + endfacet + facet normal -0.0968554 -0.0914455 0.991089 + outer loop + vertex 1.68317 1.77883 2.49816 + vertex 1.68327 1.77344 2.49767 + vertex 1.685 1.78 2.49845 + endloop + endfacet + facet normal 0.906114 -0.0216976 0.422477 + outer loop + vertex 1.68317 1.77883 2.49816 + vertex 1.68232 1.77351 2.4997 + vertex 1.68327 1.77344 2.49767 + endloop + endfacet + facet normal 0.942017 -0.0538472 0.331217 + outer loop + vertex 1.68235 1.77756 2.50028 + vertex 1.68232 1.77351 2.4997 + vertex 1.68317 1.77883 2.49816 + endloop + endfacet + facet normal -0.14371 -0.0177873 0.98946 + outer loop + vertex 1.685 1.785 2.49854 + vertex 1.68317 1.77883 2.49816 + vertex 1.685 1.78 2.49845 + endloop + endfacet + facet normal -0.432619 0.0735631 0.898571 + outer loop + vertex 1.68333 1.78449 2.49778 + vertex 1.68317 1.77883 2.49816 + vertex 1.685 1.785 2.49854 + endloop + endfacet + facet normal 0.927709 0.0126146 0.373092 + outer loop + vertex 1.68235 1.77756 2.50028 + vertex 1.68259 1.78262 2.49951 + vertex 1.68165 1.77958 2.50194 + endloop + endfacet + facet normal 0.930552 0.0113993 0.365982 + outer loop + vertex 1.68235 1.77756 2.50028 + vertex 1.68317 1.77883 2.49816 + vertex 1.68259 1.78262 2.49951 + endloop + endfacet + facet normal 0.919133 -0.000246632 0.393947 + outer loop + vertex 1.68317 1.77883 2.49816 + vertex 1.68333 1.78449 2.49778 + vertex 1.68259 1.78262 2.49951 + endloop + endfacet + facet normal 0.921398 0.0262524 0.387733 + outer loop + vertex 1.68259 1.78262 2.49951 + vertex 1.68137 1.78392 2.50232 + vertex 1.68165 1.77958 2.50194 + endloop + endfacet + facet normal -0.412383 -0.0109462 0.910945 + outer loop + vertex 1.685 1.79 2.4986 + vertex 1.68333 1.78449 2.49778 + vertex 1.685 1.785 2.49854 + endloop + endfacet + facet normal -0.280576 -0.0578422 0.958087 + outer loop + vertex 1.68323 1.78855 2.49799 + vertex 1.68333 1.78449 2.49778 + vertex 1.685 1.79 2.4986 + endloop + endfacet + facet normal 0.918052 0.00250015 0.396452 + outer loop + vertex 1.68333 1.78449 2.49778 + vertex 1.68323 1.78855 2.49799 + vertex 1.68259 1.78262 2.49951 + endloop + endfacet + facet normal 0.921309 0.000202342 0.38883 + outer loop + vertex 1.68323 1.78855 2.49799 + vertex 1.68246 1.78812 2.49982 + vertex 1.68259 1.78262 2.49951 + endloop + endfacet + facet normal 0.917251 -0.000440519 0.39831 + outer loop + vertex 1.68246 1.78812 2.49982 + vertex 1.68137 1.78392 2.50232 + vertex 1.68259 1.78262 2.49951 + endloop + endfacet + facet normal 0.916175 0.00130466 0.400776 + outer loop + vertex 1.68125 1.78904 2.50258 + vertex 1.68137 1.78392 2.50232 + vertex 1.68246 1.78812 2.49982 + endloop + endfacet + facet normal -0.343064 0.0262814 0.938944 + outer loop + vertex 1.685 1.795 2.49846 + vertex 1.68323 1.78855 2.49799 + vertex 1.685 1.79 2.4986 + endloop + endfacet + facet normal -0.366809 0.0334655 0.929694 + outer loop + vertex 1.68334 1.79321 2.49787 + vertex 1.68323 1.78855 2.49799 + vertex 1.685 1.795 2.49846 + endloop + endfacet + facet normal 0.9222 -0.0110698 0.386556 + outer loop + vertex 1.68323 1.78855 2.49799 + vertex 1.68334 1.79321 2.49787 + vertex 1.68246 1.78812 2.49982 + endloop + endfacet + facet normal 0.932444 -0.0227953 0.360594 + outer loop + vertex 1.68334 1.79321 2.49787 + vertex 1.68257 1.79297 2.49984 + vertex 1.68246 1.78812 2.49982 + endloop + endfacet + facet normal 0.912988 -0.0225089 0.407365 + outer loop + vertex 1.68257 1.79297 2.49984 + vertex 1.68125 1.78904 2.50258 + vertex 1.68246 1.78812 2.49982 + endloop + endfacet + facet normal 0.915425 -0.0273704 0.401558 + outer loop + vertex 1.68133 1.79406 2.50274 + vertex 1.68125 1.78904 2.50258 + vertex 1.68257 1.79297 2.49984 + endloop + endfacet + facet normal -0.43672 0.110725 0.892757 + outer loop + vertex 1.685 1.8 2.49784 + vertex 1.68334 1.79321 2.49787 + vertex 1.685 1.795 2.49846 + endloop + endfacet + facet normal -0.656311 0.163848 0.736485 + outer loop + vertex 1.685 1.8 2.49784 + vertex 1.68371 1.79729 2.49729 + vertex 1.68334 1.79321 2.49787 + endloop + endfacet + facet normal 0.718068 0.215109 -0.661896 + outer loop + vertex 1.68713 1.80058 2.49278 + vertex 1.68935 1.8 2.495 + vertex 1.69 1.79783 2.495 + endloop + endfacet + facet normal 0.932608 -0.0342476 0.359264 + outer loop + vertex 1.68334 1.79321 2.49787 + vertex 1.68371 1.79729 2.49729 + vertex 1.68257 1.79297 2.49984 + endloop + endfacet + facet normal 0.9521 -0.076739 0.296002 + outer loop + vertex 1.68371 1.79729 2.49729 + vertex 1.68296 1.79756 2.49979 + vertex 1.68257 1.79297 2.49984 + endloop + endfacet + facet normal 0.907182 -0.0715893 0.414604 + outer loop + vertex 1.68296 1.79756 2.49979 + vertex 1.68133 1.79406 2.50274 + vertex 1.68257 1.79297 2.49984 + endloop + endfacet + facet normal 0.901602 -0.057066 0.428786 + outer loop + vertex 1.68157 1.79898 2.50289 + vertex 1.68133 1.79406 2.50274 + vertex 1.68296 1.79756 2.49979 + endloop + endfacet + facet normal 0.707503 -0.0282629 0.706145 + outer loop + vertex 1.68713 1.80058 2.49278 + vertex 1.68621 1.80393 2.49384 + vertex 1.685 1.80261 2.495 + endloop + endfacet + facet normal 0.494233 0.823707 -0.277921 + outer loop + vertex 1.68713 1.80058 2.49278 + vertex 1.685 1.80261 2.495 + vertex 1.68935 1.8 2.495 + endloop + endfacet + facet normal 0.291181 -0.769041 -0.569024 + outer loop + vertex 1.68621 1.80393 2.49384 + vertex 1.68443 1.80107 2.49678 + vertex 1.685 1.80261 2.495 + endloop + endfacet + facet normal -0.877945 0.352506 0.323964 + outer loop + vertex 1.685 1.8 2.49784 + vertex 1.685 1.80261 2.495 + vertex 1.68371 1.79729 2.49729 + endloop + endfacet + facet normal 0.971445 -0.160215 0.175002 + outer loop + vertex 1.68443 1.80107 2.49678 + vertex 1.68371 1.79729 2.49729 + vertex 1.685 1.80261 2.495 + endloop + endfacet + facet normal 0.943814 -0.138117 0.30023 + outer loop + vertex 1.68371 1.79729 2.49729 + vertex 1.68443 1.80107 2.49678 + vertex 1.68296 1.79756 2.49979 + endloop + endfacet + facet normal 0.936143 -0.104559 0.335714 + outer loop + vertex 1.68443 1.80107 2.49678 + vertex 1.68344 1.80226 2.4999 + vertex 1.68296 1.79756 2.49979 + endloop + endfacet + facet normal 0.889979 -0.102514 0.44433 + outer loop + vertex 1.68344 1.80226 2.4999 + vertex 1.68157 1.79898 2.50289 + vertex 1.68296 1.79756 2.49979 + endloop + endfacet + facet normal 0.871376 -0.0523092 0.48782 + outer loop + vertex 1.68175 1.80391 2.5031 + vertex 1.68157 1.79898 2.50289 + vertex 1.68344 1.80226 2.4999 + endloop + endfacet + facet normal 0.886265 -0.205603 0.415044 + outer loop + vertex 1.68621 1.80393 2.49384 + vertex 1.68715 1.80952 2.49461 + vertex 1.68516 1.80562 2.49691 + endloop + endfacet + facet normal 0.904764 -0.158375 0.395373 + outer loop + vertex 1.68443 1.80107 2.49678 + vertex 1.68621 1.80393 2.49384 + vertex 1.68516 1.80562 2.49691 + endloop + endfacet + facet normal 0.92208 -0.159985 0.352382 + outer loop + vertex 1.68443 1.80107 2.49678 + vertex 1.68516 1.80562 2.49691 + vertex 1.68344 1.80226 2.4999 + endloop + endfacet + facet normal 0.899847 -0.0804738 0.428718 + outer loop + vertex 1.68516 1.80562 2.49691 + vertex 1.68375 1.80717 2.50017 + vertex 1.68344 1.80226 2.4999 + endloop + endfacet + facet normal 0.862906 -0.081991 0.498669 + outer loop + vertex 1.68375 1.80717 2.50017 + vertex 1.68175 1.80391 2.5031 + vertex 1.68344 1.80226 2.4999 + endloop + endfacet + facet normal 0.838649 -0.0264811 0.544029 + outer loop + vertex 1.68178 1.80888 2.50329 + vertex 1.68175 1.80391 2.5031 + vertex 1.68375 1.80717 2.50017 + endloop + endfacet + facet normal 0.821666 -0.156578 0.548041 + outer loop + vertex 1.68715 1.80952 2.49461 + vertex 1.68784 1.8147 2.49506 + vertex 1.68558 1.8107 2.49729 + endloop + endfacet + facet normal 0.836988 -0.109314 0.536192 + outer loop + vertex 1.68516 1.80562 2.49691 + vertex 1.68715 1.80952 2.49461 + vertex 1.68558 1.8107 2.49729 + endloop + endfacet + facet normal 0.892654 -0.106484 0.437985 + outer loop + vertex 1.68516 1.80562 2.49691 + vertex 1.68558 1.8107 2.49729 + vertex 1.68375 1.80717 2.50017 + endloop + endfacet + facet normal 0.865118 -0.0416737 0.499834 + outer loop + vertex 1.68558 1.8107 2.49729 + vertex 1.68385 1.81212 2.50042 + vertex 1.68375 1.80717 2.50017 + endloop + endfacet + facet normal 0.833827 -0.0435201 0.550308 + outer loop + vertex 1.68385 1.81212 2.50042 + vertex 1.68178 1.80888 2.50329 + vertex 1.68375 1.80717 2.50017 + endloop + endfacet + facet normal 0.811668 0.000577539 0.584118 + outer loop + vertex 1.68173 1.81384 2.50336 + vertex 1.68178 1.80888 2.50329 + vertex 1.68385 1.81212 2.50042 + endloop + endfacet + facet normal 0.757037 -0.0259255 0.652857 + outer loop + vertex 1.68784 1.8147 2.49506 + vertex 1.68802 1.81931 2.49502 + vertex 1.68577 1.81553 2.49749 + endloop + endfacet + facet normal 0.751093 -0.0554401 0.657864 + outer loop + vertex 1.68558 1.8107 2.49729 + vertex 1.68784 1.8147 2.49506 + vertex 1.68577 1.81553 2.49749 + endloop + endfacet + facet normal 0.862265 -0.0535005 0.503624 + outer loop + vertex 1.68558 1.8107 2.49729 + vertex 1.68577 1.81553 2.49749 + vertex 1.68385 1.81212 2.50042 + endloop + endfacet + facet normal 0.841181 -0.00984812 0.540664 + outer loop + vertex 1.68577 1.81553 2.49749 + vertex 1.68385 1.817 2.5005 + vertex 1.68385 1.81212 2.50042 + endloop + endfacet + facet normal 0.808504 -0.0106104 0.588395 + outer loop + vertex 1.68385 1.817 2.5005 + vertex 1.68173 1.81384 2.50336 + vertex 1.68385 1.81212 2.50042 + endloop + endfacet + facet normal 0.790934 0.0221973 0.611499 + outer loop + vertex 1.68167 1.81876 2.50326 + vertex 1.68173 1.81384 2.50336 + vertex 1.68385 1.817 2.5005 + endloop + endfacet + facet normal 0.755811 0.0854838 0.649186 + outer loop + vertex 1.68802 1.81931 2.49502 + vertex 1.68793 1.8239 2.49453 + vertex 1.68583 1.82024 2.49746 + endloop + endfacet + facet normal 0.74154 -0.00492621 0.670891 + outer loop + vertex 1.68577 1.81553 2.49749 + vertex 1.68802 1.81931 2.49502 + vertex 1.68583 1.82024 2.49746 + endloop + endfacet + facet normal 0.841813 -0.00709708 0.539723 + outer loop + vertex 1.68577 1.81553 2.49749 + vertex 1.68583 1.82024 2.49746 + vertex 1.68385 1.817 2.5005 + endloop + endfacet + facet normal 0.833622 0.00964574 0.552251 + outer loop + vertex 1.68583 1.82024 2.49746 + vertex 1.68383 1.82187 2.50044 + vertex 1.68385 1.817 2.5005 + endloop + endfacet + facet normal 0.787403 0.0101674 0.616354 + outer loop + vertex 1.68383 1.82187 2.50044 + vertex 1.68167 1.81876 2.50326 + vertex 1.68385 1.817 2.5005 + endloop + endfacet + facet normal 0.77175 0.0377256 0.634806 + outer loop + vertex 1.68156 1.82362 2.50311 + vertex 1.68167 1.81876 2.50326 + vertex 1.68383 1.82187 2.50044 + endloop + endfacet + facet normal 0.81956 0.067619 0.56899 + outer loop + vertex 1.68793 1.8239 2.49453 + vertex 1.68777 1.82884 2.49418 + vertex 1.68584 1.82512 2.4974 + endloop + endfacet + facet normal 0.809162 0.00567517 0.587558 + outer loop + vertex 1.68583 1.82024 2.49746 + vertex 1.68793 1.8239 2.49453 + vertex 1.68584 1.82512 2.4974 + endloop + endfacet + facet normal 0.832547 0.00526002 0.553929 + outer loop + vertex 1.68583 1.82024 2.49746 + vertex 1.68584 1.82512 2.4974 + vertex 1.68383 1.82187 2.50044 + endloop + endfacet + facet normal 0.825481 0.0191691 0.564104 + outer loop + vertex 1.68584 1.82512 2.4974 + vertex 1.68375 1.82678 2.50039 + vertex 1.68383 1.82187 2.50044 + endloop + endfacet + facet normal 0.766203 0.0189985 0.642318 + outer loop + vertex 1.68375 1.82678 2.50039 + vertex 1.68156 1.82362 2.50311 + vertex 1.68383 1.82187 2.50044 + endloop + endfacet + facet normal 0.744874 0.0533197 0.665071 + outer loop + vertex 1.68131 1.8285 2.50299 + vertex 1.68156 1.82362 2.50311 + vertex 1.68375 1.82678 2.50039 + endloop + endfacet + facet normal 0.854095 -0.0276939 0.51938 + outer loop + vertex 1.68777 1.82884 2.49418 + vertex 1.68771 1.83403 2.49454 + vertex 1.68577 1.83018 2.49754 + endloop + endfacet + facet normal 0.858938 -0.00206959 0.512076 + outer loop + vertex 1.68584 1.82512 2.4974 + vertex 1.68777 1.82884 2.49418 + vertex 1.68577 1.83018 2.49754 + endloop + endfacet + facet normal 0.819555 -0.00423363 0.572985 + outer loop + vertex 1.68584 1.82512 2.4974 + vertex 1.68577 1.83018 2.49754 + vertex 1.68375 1.82678 2.50039 + endloop + endfacet + facet normal 0.803904 0.0229905 0.594314 + outer loop + vertex 1.68577 1.83018 2.49754 + vertex 1.68356 1.83165 2.50047 + vertex 1.68375 1.82678 2.50039 + endloop + endfacet + facet normal 0.734595 0.0188693 0.678244 + outer loop + vertex 1.68356 1.83165 2.50047 + vertex 1.68131 1.8285 2.50299 + vertex 1.68375 1.82678 2.50039 + endloop + endfacet + facet normal 0.707217 0.0594481 0.704492 + outer loop + vertex 1.68088 1.83366 2.50298 + vertex 1.68131 1.8285 2.50299 + vertex 1.68356 1.83165 2.50047 + endloop + endfacet + facet normal 0.835132 -0.0478506 0.547965 + outer loop + vertex 1.68771 1.83403 2.49454 + vertex 1.68754 1.83813 2.49516 + vertex 1.68555 1.8355 2.49796 + endloop + endfacet + facet normal 0.843739 -0.00904447 0.536677 + outer loop + vertex 1.68577 1.83018 2.49754 + vertex 1.68771 1.83403 2.49454 + vertex 1.68555 1.8355 2.49796 + endloop + endfacet + facet normal 0.794469 -0.0166651 0.607076 + outer loop + vertex 1.68577 1.83018 2.49754 + vertex 1.68555 1.8355 2.49796 + vertex 1.68356 1.83165 2.50047 + endloop + endfacet + facet normal 0.768702 0.0176451 0.639364 + outer loop + vertex 1.68555 1.8355 2.49796 + vertex 1.68331 1.83562 2.50066 + vertex 1.68356 1.83165 2.50047 + endloop + endfacet + facet normal 0.688356 0.00848312 0.725323 + outer loop + vertex 1.68331 1.83562 2.50066 + vertex 1.68088 1.83366 2.50298 + vertex 1.68356 1.83165 2.50047 + endloop + endfacet + facet normal 0.675873 0.036652 0.736106 + outer loop + vertex 1.68178 1.83781 2.50195 + vertex 1.68088 1.83366 2.50298 + vertex 1.68331 1.83562 2.50066 + endloop + endfacet + facet normal 0.828053 -0.0298056 0.559856 + outer loop + vertex 1.68754 1.83813 2.49516 + vertex 1.68633 1.83993 2.49705 + vertex 1.68555 1.8355 2.49796 + endloop + endfacet + facet normal 0.757026 0.00615334 0.653356 + outer loop + vertex 1.68633 1.83993 2.49705 + vertex 1.68596 1.84398 2.49744 + vertex 1.68404 1.83991 2.4997 + endloop + endfacet + facet normal 0.757058 0.00204233 0.653345 + outer loop + vertex 1.68633 1.83993 2.49705 + vertex 1.68404 1.83991 2.4997 + vertex 1.68555 1.8355 2.49796 + endloop + endfacet + facet normal 0.768637 0.0114492 0.639583 + outer loop + vertex 1.68555 1.8355 2.49796 + vertex 1.68404 1.83991 2.4997 + vertex 1.68331 1.83562 2.50066 + endloop + endfacet + facet normal 0.683167 0.0460589 0.728808 + outer loop + vertex 1.68404 1.83991 2.4997 + vertex 1.68178 1.83781 2.50195 + vertex 1.68331 1.83562 2.50066 + endloop + endfacet + facet normal 0.66758 0.075575 0.740692 + outer loop + vertex 1.68114 1.84196 2.50211 + vertex 1.68178 1.83781 2.50195 + vertex 1.68404 1.83991 2.4997 + endloop + endfacet + facet normal 0.718737 0.021864 0.694938 + outer loop + vertex 1.68596 1.84398 2.49744 + vertex 1.68535 1.84914 2.49791 + vertex 1.68338 1.84519 2.50007 + endloop + endfacet + facet normal 0.722948 0.0423372 0.689604 + outer loop + vertex 1.68404 1.83991 2.4997 + vertex 1.68596 1.84398 2.49744 + vertex 1.68338 1.84519 2.50007 + endloop + endfacet + facet normal 0.649776 0.0283097 0.759599 + outer loop + vertex 1.68338 1.84519 2.50007 + vertex 1.68114 1.84196 2.50211 + vertex 1.68404 1.83991 2.4997 + endloop + endfacet + facet normal 0.603266 0.0818967 0.793324 + outer loop + vertex 1.68023 1.8474 2.50224 + vertex 1.68114 1.84196 2.50211 + vertex 1.68338 1.84519 2.50007 + endloop + endfacet + facet normal 0.685263 0.0556583 0.726166 + outer loop + vertex 1.68279 1.84912 2.50033 + vertex 1.68338 1.84519 2.50007 + vertex 1.68535 1.84914 2.49791 + endloop + endfacet + facet normal 0.684927 0.0631509 0.72587 + outer loop + vertex 1.68279 1.84912 2.50033 + vertex 1.68535 1.84914 2.49791 + vertex 1.68325 1.85269 2.49958 + endloop + endfacet + facet normal 0.672683 0.0501333 0.73823 + outer loop + vertex 1.68325 1.85269 2.49958 + vertex 1.68535 1.84914 2.49791 + vertex 1.68565 1.85394 2.4973 + endloop + endfacet + facet normal 0.582937 0.0346982 0.811776 + outer loop + vertex 1.68338 1.84519 2.50007 + vertex 1.68279 1.84912 2.50033 + vertex 1.68023 1.8474 2.50224 + endloop + endfacet + facet normal 0.75458 0.0638584 0.653093 + outer loop + vertex 1.68744 1.85537 2.49522 + vertex 1.68773 1.85867 2.49456 + vertex 1.68606 1.8572 2.49663 + endloop + endfacet + facet normal 0.743553 0.0447236 0.667179 + outer loop + vertex 1.68606 1.8572 2.49663 + vertex 1.68565 1.85394 2.4973 + vertex 1.68744 1.85537 2.49522 + endloop + endfacet + facet normal 0.638168 0.0782487 0.765911 + outer loop + vertex 1.68606 1.8572 2.49663 + vertex 1.68341 1.85752 2.49881 + vertex 1.68565 1.85394 2.4973 + endloop + endfacet + facet normal 0.656834 0.0976017 0.747691 + outer loop + vertex 1.68341 1.85752 2.49881 + vertex 1.68325 1.85269 2.49958 + vertex 1.68565 1.85394 2.4973 + endloop + endfacet + facet normal 0.71944 0.0589337 0.69205 + outer loop + vertex 1.68773 1.85867 2.49456 + vertex 1.68761 1.86308 2.49431 + vertex 1.6855 1.86076 2.4967 + endloop + endfacet + facet normal 0.737512 0.103498 0.667356 + outer loop + vertex 1.68606 1.8572 2.49663 + vertex 1.68773 1.85867 2.49456 + vertex 1.6855 1.86076 2.4967 + endloop + endfacet + facet normal 0.638306 0.085796 0.764986 + outer loop + vertex 1.6855 1.86076 2.4967 + vertex 1.68341 1.85752 2.49881 + vertex 1.68606 1.8572 2.49663 + endloop + endfacet + facet normal 0.615584 0.11034 0.780308 + outer loop + vertex 1.68247 1.86288 2.49879 + vertex 1.68341 1.85752 2.49881 + vertex 1.6855 1.86076 2.4967 + endloop + endfacet + facet normal 0.684726 0.0546505 0.726749 + outer loop + vertex 1.68761 1.86308 2.49431 + vertex 1.68743 1.86791 2.49412 + vertex 1.68502 1.86553 2.49656 + endloop + endfacet + facet normal 0.701446 0.0906206 0.706938 + outer loop + vertex 1.6855 1.86076 2.4967 + vertex 1.68761 1.86308 2.49431 + vertex 1.68502 1.86553 2.49656 + endloop + endfacet + facet normal 0.604853 0.0835306 0.791944 + outer loop + vertex 1.68502 1.86553 2.49656 + vertex 1.68247 1.86288 2.49879 + vertex 1.6855 1.86076 2.4967 + endloop + endfacet + facet normal 0.66542 0.0604981 0.744013 + outer loop + vertex 1.68743 1.86791 2.49412 + vertex 1.68721 1.87283 2.49391 + vertex 1.68481 1.8704 2.49626 + endloop + endfacet + facet normal 0.673041 0.0756509 0.735726 + outer loop + vertex 1.68502 1.86553 2.49656 + vertex 1.68743 1.86791 2.49412 + vertex 1.68481 1.8704 2.49626 + endloop + endfacet + facet normal 0.422333 0.126069 0.897631 + outer loop + vertex 1.68378 1.91787 2.48939 + vertex 1.68724 1.91255 2.48851 + vertex 1.6876 1.91758 2.48764 + endloop + endfacet + facet normal 0.282027 0.255507 0.924758 + outer loop + vertex 1.67966 2.04125 2.46191 + vertex 1.68201 2.03588 2.46268 + vertex 1.68433 2.03958 2.46095 + endloop + endfacet + facet normal 0.282996 0.258922 0.923511 + outer loop + vertex 1.68433 2.03958 2.46095 + vertex 1.6826 2.04341 2.46041 + vertex 1.67966 2.04125 2.46191 + endloop + endfacet + facet normal 0.288732 0.313004 0.9048 + outer loop + vertex 1.6811 2.07108 2.45268 + vertex 1.68213 2.06721 2.45369 + vertex 1.68612 2.06628 2.45273 + endloop + endfacet + facet normal 0.322292 0.386498 0.864145 + outer loop + vertex 1.68307 2.07338 2.45109 + vertex 1.68521 2.07052 2.45158 + vertex 1.68697 2.07275 2.44992 + endloop + endfacet + facet normal 0.323032 0.456404 0.829064 + outer loop + vertex 1.68307 2.07338 2.45109 + vertex 1.68697 2.07275 2.44992 + vertex 1.68175 2.07705 2.44959 + endloop + endfacet + facet normal 0.3422 0.47809 0.808906 + outer loop + vertex 1.68175 2.07705 2.44959 + vertex 1.68697 2.07275 2.44992 + vertex 1.68655 2.07728 2.44743 + endloop + endfacet + facet normal 0.286595 0.363518 0.886407 + outer loop + vertex 1.68521 2.07052 2.45158 + vertex 1.68307 2.07338 2.45109 + vertex 1.6811 2.07108 2.45268 + endloop + endfacet + facet normal 0.359952 0.671743 0.647454 + outer loop + vertex 1.68853 2.07934 2.44486 + vertex 1.68688 2.08121 2.44384 + vertex 1.68539 2.08025 2.44566 + endloop + endfacet + facet normal 0.354854 0.575931 0.736466 + outer loop + vertex 1.68539 2.08025 2.44566 + vertex 1.68655 2.07728 2.44743 + vertex 1.68853 2.07934 2.44486 + endloop + endfacet + facet normal 0.339293 0.574762 0.744667 + outer loop + vertex 1.68539 2.08025 2.44566 + vertex 1.68202 2.08054 2.44697 + vertex 1.68655 2.07728 2.44743 + endloop + endfacet + facet normal 0.320808 0.552656 0.76919 + outer loop + vertex 1.68202 2.08054 2.44697 + vertex 1.68175 2.07705 2.44959 + vertex 1.68655 2.07728 2.44743 + endloop + endfacet + facet normal 0.231448 0.665246 0.709845 + outer loop + vertex 1.68835 2.08568 2.43693 + vertex 1.68661 2.08779 2.43551 + vertex 1.68389 2.08648 2.43763 + endloop + endfacet + facet normal 0.362993 0.798878 0.479615 + outer loop + vertex 1.68389 2.08648 2.43763 + vertex 1.68084 2.08672 2.43954 + vertex 1.68315 2.0848 2.44098 + endloop + endfacet + facet normal 0.227924 0.849784 0.475309 + outer loop + vertex 1.68389 2.08648 2.43763 + vertex 1.68315 2.0848 2.44098 + vertex 1.68835 2.08568 2.43693 + endloop + endfacet + facet normal 0.329285 0.743174 0.582464 + outer loop + vertex 1.68835 2.08568 2.43693 + vertex 1.68315 2.0848 2.44098 + vertex 1.68787 2.08278 2.4409 + endloop + endfacet + facet normal 0.325456 0.701017 0.63455 + outer loop + vertex 1.68688 2.08121 2.44384 + vertex 1.68393 2.08234 2.44409 + vertex 1.68539 2.08025 2.44566 + endloop + endfacet + facet normal 0.344655 0.774698 0.530147 + outer loop + vertex 1.68688 2.08121 2.44384 + vertex 1.68787 2.08278 2.4409 + vertex 1.68393 2.08234 2.44409 + endloop + endfacet + facet normal 0.342782 0.776895 0.528142 + outer loop + vertex 1.68787 2.08278 2.4409 + vertex 1.68315 2.0848 2.44098 + vertex 1.68393 2.08234 2.44409 + endloop + endfacet + facet normal 0.311176 0.69847 0.644445 + outer loop + vertex 1.68539 2.08025 2.44566 + vertex 1.68393 2.08234 2.44409 + vertex 1.68202 2.08054 2.44697 + endloop + endfacet + facet normal 0.349557 0.52596 0.775355 + outer loop + vertex 1.68661 2.08779 2.43551 + vertex 1.68224 2.08913 2.43657 + vertex 1.68389 2.08648 2.43763 + endloop + endfacet + facet normal 0.216777 -0.0644139 0.974094 + outer loop + vertex 1.68661 2.08779 2.43551 + vertex 1.69 2.09148 2.435 + vertex 1.68224 2.08913 2.43657 + endloop + endfacet + facet normal 0.0537542 0.426696 0.902796 + outer loop + vertex 1.69 2.09148 2.435 + vertex 1.685 2.09211 2.435 + vertex 1.68224 2.08913 2.43657 + endloop + endfacet + facet normal 0.470172 0.56275 0.67989 + outer loop + vertex 1.68389 2.08648 2.43763 + vertex 1.68224 2.08913 2.43657 + vertex 1.68084 2.08672 2.43954 + endloop + endfacet + facet normal -0.0222035 0.0496923 0.998518 + outer loop + vertex 1.69423 0.945 2.435 + vertex 1.68981 0.944026 2.43495 + vertex 1.69 0.94311 2.435 + endloop + endfacet + facet normal -0.0165139 0.0238151 0.99958 + outer loop + vertex 1.68981 0.944026 2.43495 + vertex 1.69423 0.945 2.435 + vertex 1.695 0.945534 2.435 + endloop + endfacet + facet normal 0.239654 -0.840957 0.485136 + outer loop + vertex 1.68981 0.944026 2.43495 + vertex 1.695 0.945534 2.435 + vertex 1.68748 0.944985 2.43776 + endloop + endfacet + facet normal 0.301363 -0.658916 0.689209 + outer loop + vertex 1.68748 0.944985 2.43776 + vertex 1.695 0.945534 2.435 + vertex 1.69223 0.946775 2.4374 + endloop + endfacet + facet normal 0.388487 -0.745758 0.541224 + outer loop + vertex 1.69022 0.948083 2.44064 + vertex 1.69223 0.946775 2.4374 + vertex 1.6931 0.948273 2.43884 + endloop + endfacet + facet normal 0.35261 -0.771633 0.529385 + outer loop + vertex 1.69022 0.948083 2.44064 + vertex 1.68653 0.947134 2.44172 + vertex 1.69223 0.946775 2.4374 + endloop + endfacet + facet normal 0.337285 -0.790805 0.510751 + outer loop + vertex 1.68653 0.947134 2.44172 + vertex 1.68748 0.944985 2.43776 + vertex 1.69223 0.946775 2.4374 + endloop + endfacet + facet normal 0.3525 -0.772416 0.528316 + outer loop + vertex 1.69022 0.948083 2.44064 + vertex 1.68824 0.948824 2.44305 + vertex 1.68653 0.947134 2.44172 + endloop + endfacet + facet normal 0.384589 -0.752761 0.534267 + outer loop + vertex 1.6931 0.948273 2.43884 + vertex 1.69187 0.949881 2.44199 + vertex 1.69022 0.948083 2.44064 + endloop + endfacet + facet normal 0.376813 -0.751296 0.541817 + outer loop + vertex 1.68824 0.948824 2.44305 + vertex 1.69022 0.948083 2.44064 + vertex 1.69187 0.949881 2.44199 + endloop + endfacet + facet normal 0.380544 -0.687318 0.618692 + outer loop + vertex 1.68824 0.948824 2.44305 + vertex 1.69187 0.949881 2.44199 + vertex 1.68805 0.950681 2.44523 + endloop + endfacet + facet normal 0.377102 -0.691843 0.615749 + outer loop + vertex 1.68805 0.950681 2.44523 + vertex 1.69187 0.949881 2.44199 + vertex 1.69196 0.952588 2.44498 + endloop + endfacet + facet normal 0.338765 -0.59879 0.725733 + outer loop + vertex 1.69196 0.952588 2.44498 + vertex 1.68814 0.954343 2.44821 + vertex 1.68805 0.950681 2.44523 + endloop + endfacet + facet normal 0.336127 -0.601959 0.724337 + outer loop + vertex 1.6935 0.955671 2.44683 + vertex 1.68814 0.954343 2.44821 + vertex 1.69196 0.952588 2.44498 + endloop + endfacet + facet normal 0.346013 -0.497013 0.795772 + outer loop + vertex 1.68877 0.958099 2.45028 + vertex 1.68502 0.956357 2.45082 + vertex 1.68814 0.954343 2.44821 + endloop + endfacet + facet normal 0.350336 -0.496776 0.794027 + outer loop + vertex 1.68877 0.958099 2.45028 + vertex 1.68814 0.954343 2.44821 + vertex 1.69276 0.959192 2.4492 + endloop + endfacet + facet normal 0.328909 -0.480237 0.813137 + outer loop + vertex 1.69276 0.959192 2.4492 + vertex 1.68814 0.954343 2.44821 + vertex 1.6935 0.955671 2.44683 + endloop + endfacet + facet normal 0.307191 -0.391373 0.867445 + outer loop + vertex 1.68877 0.958099 2.45028 + vertex 1.68761 0.960204 2.45164 + vertex 1.68502 0.956357 2.45082 + endloop + endfacet + facet normal 0.341713 -0.418118 0.841671 + outer loop + vertex 1.69276 0.959192 2.4492 + vertex 1.69073 0.960766 2.45081 + vertex 1.68877 0.958099 2.45028 + endloop + endfacet + facet normal 0.302329 -0.394301 0.867827 + outer loop + vertex 1.69073 0.960766 2.45081 + vertex 1.68761 0.960204 2.45164 + vertex 1.68877 0.958099 2.45028 + endloop + endfacet + facet normal 0.297837 -0.325358 0.89746 + outer loop + vertex 1.69073 0.960766 2.45081 + vertex 1.6912 0.963708 2.45172 + vertex 1.68761 0.960204 2.45164 + endloop + endfacet + facet normal 0.383941 -0.200834 0.901252 + outer loop + vertex 1.68891 1.07294 2.48063 + vertex 1.68636 1.07025 2.48112 + vertex 1.6889 1.06957 2.47988 + endloop + endfacet + facet normal 0.43982 -0.19538 0.876576 + outer loop + vertex 1.68891 1.07294 2.48063 + vertex 1.6889 1.06957 2.47988 + vertex 1.69242 1.07432 2.47918 + endloop + endfacet + facet normal 0.370902 -0.186918 0.909667 + outer loop + vertex 1.68891 1.07294 2.48063 + vertex 1.68632 1.07356 2.48181 + vertex 1.68636 1.07025 2.48112 + endloop + endfacet + facet normal 0.537137 -0.139685 0.831848 + outer loop + vertex 1.68812 1.12288 2.49015 + vertex 1.6861 1.12024 2.49102 + vertex 1.68826 1.11948 2.4895 + endloop + endfacet + facet normal 0.659329 -0.117601 0.7426 + outer loop + vertex 1.68812 1.12288 2.49015 + vertex 1.68826 1.11948 2.4895 + vertex 1.69082 1.1241 2.48795 + endloop + endfacet + facet normal 0.614373 -0.0783956 0.785111 + outer loop + vertex 1.69082 1.1241 2.48795 + vertex 1.68826 1.11948 2.4895 + vertex 1.69098 1.11873 2.48729 + endloop + endfacet + facet normal 0.513533 -0.115506 0.85026 + outer loop + vertex 1.68812 1.12288 2.49015 + vertex 1.68576 1.12349 2.49166 + vertex 1.6861 1.12024 2.49102 + endloop + endfacet + facet normal 0.678693 -0.0530802 0.732502 + outer loop + vertex 1.69082 1.1241 2.48795 + vertex 1.69136 1.12973 2.48785 + vertex 1.68867 1.12674 2.49014 + endloop + endfacet + facet normal 0.653693 -0.0892319 0.75148 + outer loop + vertex 1.68812 1.12288 2.49015 + vertex 1.69082 1.1241 2.48795 + vertex 1.68867 1.12674 2.49014 + endloop + endfacet + facet normal 0.524243 -0.0704991 0.848645 + outer loop + vertex 1.68867 1.12674 2.49014 + vertex 1.68576 1.12349 2.49166 + vertex 1.68812 1.12288 2.49015 + endloop + endfacet + facet normal 0.554344 -0.108384 0.8252 + outer loop + vertex 1.68588 1.12812 2.49219 + vertex 1.68576 1.12349 2.49166 + vertex 1.68867 1.12674 2.49014 + endloop + endfacet + facet normal 0.706299 -0.0430008 0.706606 + outer loop + vertex 1.69136 1.12973 2.48785 + vertex 1.69156 1.13476 2.48796 + vertex 1.68896 1.13164 2.49038 + endloop + endfacet + facet normal 0.691939 -0.0761364 0.71793 + outer loop + vertex 1.68867 1.12674 2.49014 + vertex 1.69136 1.12973 2.48785 + vertex 1.68896 1.13164 2.49038 + endloop + endfacet + facet normal 0.567613 -0.0738292 0.819978 + outer loop + vertex 1.68896 1.13164 2.49038 + vertex 1.68588 1.12812 2.49219 + vertex 1.68867 1.12674 2.49014 + endloop + endfacet + facet normal 0.597109 -0.112943 0.79417 + outer loop + vertex 1.68617 1.13324 2.4927 + vertex 1.68588 1.12812 2.49219 + vertex 1.68896 1.13164 2.49038 + endloop + endfacet + facet normal 0.738084 -0.0291467 0.674079 + outer loop + vertex 1.69156 1.13476 2.48796 + vertex 1.69164 1.13969 2.48809 + vertex 1.68913 1.13671 2.49071 + endloop + endfacet + facet normal 0.721825 -0.0698994 0.688537 + outer loop + vertex 1.68896 1.13164 2.49038 + vertex 1.69156 1.13476 2.48796 + vertex 1.68913 1.13671 2.49071 + endloop + endfacet + facet normal 0.613633 -0.0726384 0.786243 + outer loop + vertex 1.68913 1.13671 2.49071 + vertex 1.68617 1.13324 2.4927 + vertex 1.68896 1.13164 2.49038 + endloop + endfacet + facet normal 0.6357 -0.103713 0.764937 + outer loop + vertex 1.68621 1.13869 2.4934 + vertex 1.68617 1.13324 2.4927 + vertex 1.68913 1.13671 2.49071 + endloop + endfacet + facet normal 0.776443 0.00248617 0.630183 + outer loop + vertex 1.69164 1.13969 2.48809 + vertex 1.69158 1.14461 2.48814 + vertex 1.68931 1.14181 2.49095 + endloop + endfacet + facet normal 0.752858 -0.0578344 0.655637 + outer loop + vertex 1.68913 1.13671 2.49071 + vertex 1.69164 1.13969 2.48809 + vertex 1.68931 1.14181 2.49095 + endloop + endfacet + facet normal 0.655184 -0.0589572 0.753165 + outer loop + vertex 1.68931 1.14181 2.49095 + vertex 1.68621 1.13869 2.4934 + vertex 1.68913 1.13671 2.49071 + endloop + endfacet + facet normal 0.673897 -0.0934434 0.732893 + outer loop + vertex 1.68691 1.14421 2.49347 + vertex 1.68621 1.13869 2.4934 + vertex 1.68931 1.14181 2.49095 + endloop + endfacet + facet normal 0.816177 0.0158222 0.577585 + outer loop + vertex 1.69158 1.14461 2.48814 + vertex 1.69147 1.14961 2.48817 + vertex 1.68948 1.14683 2.49106 + endloop + endfacet + facet normal 0.795724 -0.0389747 0.604404 + outer loop + vertex 1.68931 1.14181 2.49095 + vertex 1.69158 1.14461 2.48814 + vertex 1.68948 1.14683 2.49106 + endloop + endfacet + facet normal 0.70411 -0.038237 0.709061 + outer loop + vertex 1.68948 1.14683 2.49106 + vertex 1.68691 1.14421 2.49347 + vertex 1.68931 1.14181 2.49095 + endloop + endfacet + facet normal 0.712583 -0.0554209 0.699395 + outer loop + vertex 1.68714 1.14922 2.49363 + vertex 1.68691 1.14421 2.49347 + vertex 1.68948 1.14683 2.49106 + endloop + endfacet + facet normal 0.835314 0.00448637 0.549754 + outer loop + vertex 1.69147 1.14961 2.48817 + vertex 1.69148 1.15473 2.48811 + vertex 1.68954 1.15183 2.49107 + endloop + endfacet + facet normal 0.829115 -0.0128509 0.558931 + outer loop + vertex 1.68948 1.14683 2.49106 + vertex 1.69147 1.14961 2.48817 + vertex 1.68954 1.15183 2.49107 + endloop + endfacet + facet normal 0.734443 -0.0118122 0.678568 + outer loop + vertex 1.68954 1.15183 2.49107 + vertex 1.68714 1.14922 2.49363 + vertex 1.68948 1.14683 2.49106 + endloop + endfacet + facet normal 0.736891 -0.016786 0.675804 + outer loop + vertex 1.68721 1.15423 2.49368 + vertex 1.68714 1.14922 2.49363 + vertex 1.68954 1.15183 2.49107 + endloop + endfacet + facet normal 0.834301 0.00307081 0.551301 + outer loop + vertex 1.69148 1.15473 2.48811 + vertex 1.69168 1.15985 2.48777 + vertex 1.68966 1.15701 2.49085 + endloop + endfacet + facet normal 0.835053 0.00506055 0.550146 + outer loop + vertex 1.68954 1.15183 2.49107 + vertex 1.69148 1.15473 2.48811 + vertex 1.68966 1.15701 2.49085 + endloop + endfacet + facet normal 0.750093 0.0117911 0.661227 + outer loop + vertex 1.68966 1.15701 2.49085 + vertex 1.68721 1.15423 2.49368 + vertex 1.68954 1.15183 2.49107 + endloop + endfacet + facet normal 0.750008 0.01196 0.66132 + outer loop + vertex 1.68725 1.15941 2.49354 + vertex 1.68721 1.15423 2.49368 + vertex 1.68966 1.15701 2.49085 + endloop + endfacet + facet normal 0.82231 0.028463 0.568327 + outer loop + vertex 1.69168 1.15985 2.48777 + vertex 1.692 1.16384 2.48711 + vertex 1.68995 1.16274 2.49014 + endloop + endfacet + facet normal 0.822697 0.0291822 0.56773 + outer loop + vertex 1.68966 1.15701 2.49085 + vertex 1.69168 1.15985 2.48777 + vertex 1.68995 1.16274 2.49014 + endloop + endfacet + facet normal 0.762405 0.0418902 0.645742 + outer loop + vertex 1.68995 1.16274 2.49014 + vertex 1.68725 1.15941 2.49354 + vertex 1.68966 1.15701 2.49085 + endloop + endfacet + facet normal 0.768278 0.0306395 0.639383 + outer loop + vertex 1.68715 1.16464 2.4934 + vertex 1.68725 1.15941 2.49354 + vertex 1.68995 1.16274 2.49014 + endloop + endfacet + facet normal 0.860765 0.184085 0.474549 + outer loop + vertex 1.6926 1.16653 2.48539 + vertex 1.69209 1.17012 2.48491 + vertex 1.69135 1.16709 2.48743 + endloop + endfacet + facet normal 0.861858 0.123774 0.491814 + outer loop + vertex 1.692 1.16384 2.48711 + vertex 1.6926 1.16653 2.48539 + vertex 1.69135 1.16709 2.48743 + endloop + endfacet + facet normal 0.805218 0.103522 0.583873 + outer loop + vertex 1.692 1.16384 2.48711 + vertex 1.69135 1.16709 2.48743 + vertex 1.68995 1.16274 2.49014 + endloop + endfacet + facet normal 0.821243 0.0860321 0.564055 + outer loop + vertex 1.68995 1.16274 2.49014 + vertex 1.69135 1.16709 2.48743 + vertex 1.68926 1.16803 2.49033 + endloop + endfacet + facet normal 0.779629 0.0784689 0.621306 + outer loop + vertex 1.68926 1.16803 2.49033 + vertex 1.68715 1.16464 2.4934 + vertex 1.68995 1.16274 2.49014 + endloop + endfacet + facet normal 0.80448 0.0372106 0.592813 + outer loop + vertex 1.68697 1.16974 2.49334 + vertex 1.68715 1.16464 2.4934 + vertex 1.68926 1.16803 2.49033 + endloop + endfacet + facet normal 0.850543 0.16251 0.500167 + outer loop + vertex 1.69209 1.17012 2.48491 + vertex 1.69136 1.17461 2.48469 + vertex 1.69048 1.17162 2.48717 + endloop + endfacet + facet normal 0.854238 0.192606 0.482888 + outer loop + vertex 1.69135 1.16709 2.48743 + vertex 1.69209 1.17012 2.48491 + vertex 1.69048 1.17162 2.48717 + endloop + endfacet + facet normal 0.8246 0.189757 0.532942 + outer loop + vertex 1.69135 1.16709 2.48743 + vertex 1.69048 1.17162 2.48717 + vertex 1.68926 1.16803 2.49033 + endloop + endfacet + facet normal 0.87361 0.119194 0.471803 + outer loop + vertex 1.69048 1.17162 2.48717 + vertex 1.68866 1.17313 2.49015 + vertex 1.68926 1.16803 2.49033 + endloop + endfacet + facet normal 0.820296 0.116114 0.560029 + outer loop + vertex 1.68866 1.17313 2.49015 + vertex 1.68697 1.16974 2.49334 + vertex 1.68926 1.16803 2.49033 + endloop + endfacet + facet normal 0.872402 0.0224121 0.488275 + outer loop + vertex 1.68689 1.17474 2.49325 + vertex 1.68697 1.16974 2.49334 + vertex 1.68866 1.17313 2.49015 + endloop + endfacet + facet normal 0.845946 0.168617 0.505908 + outer loop + vertex 1.69136 1.17461 2.48469 + vertex 1.68944 1.17767 2.48688 + vertex 1.69048 1.17162 2.48717 + endloop + endfacet + facet normal 0.889048 0.403757 0.21581 + outer loop + vertex 1.69136 1.17461 2.48469 + vertex 1.69 1.17745 2.485 + vertex 1.68944 1.17767 2.48688 + endloop + endfacet + facet normal 0.0421948 -0.0875391 0.995267 + outer loop + vertex 1.69136 1.17461 2.48469 + vertex 1.695 1.17986 2.485 + vertex 1.69 1.17745 2.485 + endloop + endfacet + facet normal 0.904247 -0.301949 0.301935 + outer loop + vertex 1.69 1.17745 2.485 + vertex 1.69 1.18 2.48755 + vertex 1.68944 1.17767 2.48688 + endloop + endfacet + facet normal 0.877556 0.171263 0.447845 + outer loop + vertex 1.69048 1.17162 2.48717 + vertex 1.68944 1.17767 2.48688 + vertex 1.68866 1.17313 2.49015 + endloop + endfacet + facet normal 0.939624 0.0781161 0.333175 + outer loop + vertex 1.68944 1.17767 2.48688 + vertex 1.68823 1.17833 2.49015 + vertex 1.68866 1.17313 2.49015 + endloop + endfacet + facet normal 0.881305 0.073204 0.466844 + outer loop + vertex 1.68823 1.17833 2.49015 + vertex 1.68689 1.17474 2.49325 + vertex 1.68866 1.17313 2.49015 + endloop + endfacet + facet normal 0.920908 -0.0083535 0.389692 + outer loop + vertex 1.68695 1.17974 2.49321 + vertex 1.68689 1.17474 2.49325 + vertex 1.68823 1.17833 2.49015 + endloop + endfacet + facet normal -0.632909 -0.069384 0.771111 + outer loop + vertex 1.69 1.185 2.488 + vertex 1.68944 1.17767 2.48688 + vertex 1.69 1.18 2.48755 + endloop + endfacet + facet normal 0.177997 -0.161291 0.970722 + outer loop + vertex 1.68874 1.18327 2.48794 + vertex 1.68944 1.17767 2.48688 + vertex 1.69 1.185 2.488 + endloop + endfacet + facet normal 0.939581 0.0535847 0.338107 + outer loop + vertex 1.68944 1.17767 2.48688 + vertex 1.68874 1.18327 2.48794 + vertex 1.68823 1.17833 2.49015 + endloop + endfacet + facet normal 0.969006 0.00974085 0.246846 + outer loop + vertex 1.68874 1.18327 2.48794 + vertex 1.68813 1.18344 2.49035 + vertex 1.68823 1.17833 2.49015 + endloop + endfacet + facet normal 0.922914 0.00363327 0.384989 + outer loop + vertex 1.68813 1.18344 2.49035 + vertex 1.68695 1.17974 2.49321 + vertex 1.68823 1.17833 2.49015 + endloop + endfacet + facet normal 0.933686 -0.021175 0.357467 + outer loop + vertex 1.68707 1.18478 2.49319 + vertex 1.68695 1.17974 2.49321 + vertex 1.68813 1.18344 2.49035 + endloop + endfacet + facet normal 0.0618348 -0.0776237 0.995063 + outer loop + vertex 1.69 1.19 2.48839 + vertex 1.68874 1.18327 2.48794 + vertex 1.69 1.185 2.488 + endloop + endfacet + facet normal 0.0181764 -0.0696233 0.997408 + outer loop + vertex 1.68865 1.18829 2.4883 + vertex 1.68874 1.18327 2.48794 + vertex 1.69 1.19 2.48839 + endloop + endfacet + facet normal 0.968886 -0.000278503 0.247506 + outer loop + vertex 1.68874 1.18327 2.48794 + vertex 1.68865 1.18829 2.4883 + vertex 1.68813 1.18344 2.49035 + endloop + endfacet + facet normal 0.974232 -0.010232 0.225315 + outer loop + vertex 1.68865 1.18829 2.4883 + vertex 1.68815 1.18846 2.49047 + vertex 1.68813 1.18344 2.49035 + endloop + endfacet + facet normal 0.935048 -0.0132986 0.354272 + outer loop + vertex 1.68815 1.18846 2.49047 + vertex 1.68707 1.18478 2.49319 + vertex 1.68813 1.18344 2.49035 + endloop + endfacet + facet normal 0.930514 -0.00311873 0.366242 + outer loop + vertex 1.68706 1.18982 2.49326 + vertex 1.68707 1.18478 2.49319 + vertex 1.68815 1.18846 2.49047 + endloop + endfacet + facet normal -0.0929595 0.017896 0.995509 + outer loop + vertex 1.69 1.195 2.4883 + vertex 1.68865 1.18829 2.4883 + vertex 1.69 1.19 2.48839 + endloop + endfacet + facet normal 0.370421 -0.0749618 0.925834 + outer loop + vertex 1.68864 1.19329 2.4887 + vertex 1.68865 1.18829 2.4883 + vertex 1.69 1.195 2.4883 + endloop + endfacet + facet normal 0.974053 -0.0161705 0.22574 + outer loop + vertex 1.68865 1.18829 2.4883 + vertex 1.68864 1.19329 2.4887 + vertex 1.68815 1.18846 2.49047 + endloop + endfacet + facet normal 0.96169 0.00279001 0.274126 + outer loop + vertex 1.68864 1.19329 2.4887 + vertex 1.68804 1.19337 2.49082 + vertex 1.68815 1.18846 2.49047 + endloop + endfacet + facet normal 0.930289 -0.00444568 0.3668 + outer loop + vertex 1.68804 1.19337 2.49082 + vertex 1.68706 1.18982 2.49326 + vertex 1.68815 1.18846 2.49047 + endloop + endfacet + facet normal 0.917519 0.0200372 0.397187 + outer loop + vertex 1.68684 1.19478 2.49351 + vertex 1.68706 1.18982 2.49326 + vertex 1.68804 1.19337 2.49082 + endloop + endfacet + facet normal 0.401846 -0.103687 0.909818 + outer loop + vertex 1.69 1.2 2.48887 + vertex 1.68864 1.19329 2.4887 + vertex 1.69 1.195 2.4883 + endloop + endfacet + facet normal 0.675556 -0.154403 0.720961 + outer loop + vertex 1.68858 1.19858 2.48989 + vertex 1.68864 1.19329 2.4887 + vertex 1.69 1.2 2.48887 + endloop + endfacet + facet normal 0.959886 -0.0511089 0.275695 + outer loop + vertex 1.68864 1.19329 2.4887 + vertex 1.68858 1.19858 2.48989 + vertex 1.68804 1.19337 2.49082 + endloop + endfacet + facet normal 0.889504 -0.0116899 0.456778 + outer loop + vertex 1.68858 1.19858 2.48989 + vertex 1.68776 1.19752 2.49148 + vertex 1.68804 1.19337 2.49082 + endloop + endfacet + facet normal 0.913439 -0.00214853 0.40697 + outer loop + vertex 1.68776 1.19752 2.49148 + vertex 1.68684 1.19478 2.49351 + vertex 1.68804 1.19337 2.49082 + endloop + endfacet + facet normal 0.903093 0.017732 0.42908 + outer loop + vertex 1.68672 1.19964 2.49357 + vertex 1.68684 1.19478 2.49351 + vertex 1.68776 1.19752 2.49148 + endloop + endfacet + facet normal 0.756678 -0.363435 0.543465 + outer loop + vertex 1.69 1.2 2.48887 + vertex 1.69 1.20169 2.49 + vertex 1.68858 1.19858 2.48989 + endloop + endfacet + facet normal 0.840522 -0.395732 0.370026 + outer loop + vertex 1.69 1.205 2.49354 + vertex 1.68858 1.19858 2.48989 + vertex 1.69 1.20169 2.49 + endloop + endfacet + facet normal -0.305406 -0.418404 0.855374 + outer loop + vertex 1.69 1.205 2.49354 + vertex 1.68798 1.20306 2.49187 + vertex 1.68858 1.19858 2.48989 + endloop + endfacet + facet normal 0.901931 -0.0663222 0.426756 + outer loop + vertex 1.68798 1.20306 2.49187 + vertex 1.68776 1.19752 2.49148 + vertex 1.68858 1.19858 2.48989 + endloop + endfacet + facet normal 0.864087 -0.0699085 0.498465 + outer loop + vertex 1.68798 1.20306 2.49187 + vertex 1.68672 1.19964 2.49357 + vertex 1.68776 1.19752 2.49148 + endloop + endfacet + facet normal 0.810029 -0.00625633 0.586357 + outer loop + vertex 1.68664 1.20464 2.49373 + vertex 1.68672 1.19964 2.49357 + vertex 1.68798 1.20306 2.49187 + endloop + endfacet + facet normal -0.596267 -0.0671744 0.799971 + outer loop + vertex 1.69 1.21 2.49396 + vertex 1.68798 1.20306 2.49187 + vertex 1.69 1.205 2.49354 + endloop + endfacet + facet normal -0.492632 -0.116205 0.862444 + outer loop + vertex 1.68787 1.20907 2.49262 + vertex 1.68798 1.20306 2.49187 + vertex 1.69 1.21 2.49396 + endloop + endfacet + facet normal 0.785519 -0.0617 0.615754 + outer loop + vertex 1.68787 1.20907 2.49262 + vertex 1.68664 1.20464 2.49373 + vertex 1.68798 1.20306 2.49187 + endloop + endfacet + facet normal 0.730175 -0.0296901 0.682615 + outer loop + vertex 1.68657 1.20978 2.49403 + vertex 1.68664 1.20464 2.49373 + vertex 1.68787 1.20907 2.49262 + endloop + endfacet + facet normal -0.538512 0.0185181 0.842414 + outer loop + vertex 1.69 1.215 2.49385 + vertex 1.68787 1.20907 2.49262 + vertex 1.69 1.21 2.49396 + endloop + endfacet + facet normal -0.433337 -0.0315048 0.900681 + outer loop + vertex 1.68789 1.21446 2.49282 + vertex 1.68787 1.20907 2.49262 + vertex 1.69 1.215 2.49385 + endloop + endfacet + facet normal 0.73037 -0.0289768 0.682437 + outer loop + vertex 1.68789 1.21446 2.49282 + vertex 1.68657 1.20978 2.49403 + vertex 1.68787 1.20907 2.49262 + endloop + endfacet + facet normal 0.691846 -0.00779547 0.722003 + outer loop + vertex 1.68661 1.21505 2.49405 + vertex 1.68657 1.20978 2.49403 + vertex 1.68789 1.21446 2.49282 + endloop + endfacet + facet normal -0.44331 0.0161112 0.896224 + outer loop + vertex 1.69 1.22 2.49376 + vertex 1.68789 1.21446 2.49282 + vertex 1.69 1.215 2.49385 + endloop + endfacet + facet normal -0.445343 0.0170605 0.895197 + outer loop + vertex 1.68792 1.21963 2.49273 + vertex 1.68789 1.21446 2.49282 + vertex 1.69 1.22 2.49376 + endloop + endfacet + facet normal 0.695666 0.0082988 0.718318 + outer loop + vertex 1.68792 1.21963 2.49273 + vertex 1.68661 1.21505 2.49405 + vertex 1.68789 1.21446 2.49282 + endloop + endfacet + facet normal 0.565045 0.0755294 0.821596 + outer loop + vertex 1.68648 1.22022 2.49367 + vertex 1.68661 1.21505 2.49405 + vertex 1.68792 1.21963 2.49273 + endloop + endfacet + facet normal -0.439533 -0.0233349 0.897923 + outer loop + vertex 1.69 1.225 2.49389 + vertex 1.68792 1.21963 2.49273 + vertex 1.69 1.22 2.49376 + endloop + endfacet + facet normal -0.53738 0.0264913 0.842924 + outer loop + vertex 1.68777 1.2242 2.4925 + vertex 1.68792 1.21963 2.49273 + vertex 1.69 1.225 2.49389 + endloop + endfacet + facet normal 0.561202 0.0599435 0.825506 + outer loop + vertex 1.68777 1.2242 2.4925 + vertex 1.68648 1.22022 2.49367 + vertex 1.68792 1.21963 2.49273 + endloop + endfacet + facet normal 0.350983 0.15737 0.923063 + outer loop + vertex 1.68623 1.22483 2.49298 + vertex 1.68648 1.22022 2.49367 + vertex 1.68777 1.2242 2.4925 + endloop + endfacet + facet normal -0.500431 -0.104826 0.859407 + outer loop + vertex 1.69 1.23 2.4945 + vertex 1.68777 1.2242 2.4925 + vertex 1.69 1.225 2.49389 + endloop + endfacet + facet normal -0.635967 -0.0224349 0.77139 + outer loop + vertex 1.68765 1.2272 2.49248 + vertex 1.68777 1.2242 2.4925 + vertex 1.69 1.23 2.4945 + endloop + endfacet + facet normal 0.303222 0.0180313 0.952749 + outer loop + vertex 1.68765 1.2272 2.49248 + vertex 1.68623 1.22483 2.49298 + vertex 1.68777 1.2242 2.4925 + endloop + endfacet + facet normal 0.423142 -0.0637813 0.903816 + outer loop + vertex 1.68678 1.22794 2.49294 + vertex 1.68623 1.22483 2.49298 + vertex 1.68765 1.2272 2.49248 + endloop + endfacet + facet normal -0.397565 -0.293668 0.869311 + outer loop + vertex 1.69 1.23 2.4945 + vertex 1.69 1.23148 2.495 + vertex 1.68765 1.2272 2.49248 + endloop + endfacet + facet normal 0.0153268 -0.513896 0.857716 + outer loop + vertex 1.68765 1.2272 2.49248 + vertex 1.69 1.23148 2.495 + vertex 1.68678 1.22794 2.49294 + endloop + endfacet + facet normal -0.767468 0.118979 0.62995 + outer loop + vertex 1.68827 1.80067 2.49236 + vertex 1.69 1.79783 2.495 + vertex 1.69 1.8 2.49459 + endloop + endfacet + facet normal 0.191836 0.729032 0.657047 + outer loop + vertex 1.68827 1.80067 2.49236 + vertex 1.68713 1.80058 2.49278 + vertex 1.69 1.79783 2.495 + endloop + endfacet + facet normal -0.773589 0.0927816 0.626859 + outer loop + vertex 1.69 1.805 2.49385 + vertex 1.68827 1.80067 2.49236 + vertex 1.69 1.8 2.49459 + endloop + endfacet + facet normal -0.589867 -0.0424817 0.806382 + outer loop + vertex 1.68781 1.80386 2.49219 + vertex 1.68827 1.80067 2.49236 + vertex 1.69 1.805 2.49385 + endloop + endfacet + facet normal 0.342847 0.0972461 0.934344 + outer loop + vertex 1.68781 1.80386 2.49219 + vertex 1.68713 1.80058 2.49278 + vertex 1.68827 1.80067 2.49236 + endloop + endfacet + facet normal 0.716191 -0.0231514 0.69752 + outer loop + vertex 1.68621 1.80393 2.49384 + vertex 1.68713 1.80058 2.49278 + vertex 1.68781 1.80386 2.49219 + endloop + endfacet + facet normal -0.620176 0.0500966 0.782861 + outer loop + vertex 1.69 1.81 2.49353 + vertex 1.68781 1.80386 2.49219 + vertex 1.69 1.805 2.49385 + endloop + endfacet + facet normal -0.271247 -0.111955 0.955976 + outer loop + vertex 1.68827 1.80875 2.49289 + vertex 1.68781 1.80386 2.49219 + vertex 1.69 1.81 2.49353 + endloop + endfacet + facet normal 0.70387 -0.164062 0.691123 + outer loop + vertex 1.68827 1.80875 2.49289 + vertex 1.68621 1.80393 2.49384 + vertex 1.68781 1.80386 2.49219 + endloop + endfacet + facet normal 0.773271 -0.21205 0.597567 + outer loop + vertex 1.68715 1.80952 2.49461 + vertex 1.68621 1.80393 2.49384 + vertex 1.68827 1.80875 2.49289 + endloop + endfacet + facet normal -0.362138 0.0260797 0.93176 + outer loop + vertex 1.69 1.815 2.49339 + vertex 1.68827 1.80875 2.49289 + vertex 1.69 1.81 2.49353 + endloop + endfacet + facet normal 0.700281 -0.138349 -0.700333 + outer loop + vertex 1.69161 1.815 2.495 + vertex 1.68827 1.80875 2.49289 + vertex 1.69 1.815 2.49339 + endloop + endfacet + facet normal 0.588201 -0.522654 0.617132 + outer loop + vertex 1.69161 1.815 2.495 + vertex 1.68715 1.80952 2.49461 + vertex 1.68827 1.80875 2.49289 + endloop + endfacet + facet normal 0.0222179 -0.0881713 0.995858 + outer loop + vertex 1.68784 1.8147 2.49506 + vertex 1.68715 1.80952 2.49461 + vertex 1.69161 1.815 2.495 + endloop + endfacet + facet normal 0.0153016 -0.000122579 0.999883 + outer loop + vertex 1.69165 1.82 2.495 + vertex 1.68784 1.8147 2.49506 + vertex 1.69161 1.815 2.495 + endloop + endfacet + facet normal 0.00544723 0.00696862 0.999961 + outer loop + vertex 1.68802 1.81931 2.49502 + vertex 1.68784 1.8147 2.49506 + vertex 1.69165 1.82 2.495 + endloop + endfacet + facet normal 0.0067642 4.06404e-05 0.999977 + outer loop + vertex 1.69162 1.825 2.495 + vertex 1.68802 1.81931 2.49502 + vertex 1.69165 1.82 2.495 + endloop + endfacet + facet normal -0.155352 0.102439 0.982533 + outer loop + vertex 1.68793 1.8239 2.49453 + vertex 1.68802 1.81931 2.49502 + vertex 1.69162 1.825 2.495 + endloop + endfacet + facet normal 0.944546 -0.326806 0.0321139 + outer loop + vertex 1.69179 1.825 2.49 + vertex 1.69352 1.83 2.49 + vertex 1.69162 1.825 2.495 + endloop + endfacet + facet normal 0.0318421 0.700664 0.712781 + outer loop + vertex 1.69352 1.83 2.49 + vertex 1.69022 1.82859 2.49154 + vertex 1.69162 1.825 2.495 + endloop + endfacet + facet normal -0.275474 0.609764 0.74317 + outer loop + vertex 1.69022 1.82859 2.49154 + vertex 1.68793 1.8239 2.49453 + vertex 1.69162 1.825 2.495 + endloop + endfacet + facet normal 0.734367 0.072389 0.674882 + outer loop + vertex 1.68777 1.82884 2.49418 + vertex 1.68793 1.8239 2.49453 + vertex 1.69022 1.82859 2.49154 + endloop + endfacet + facet normal 0.43348 -0.0329479 0.900561 + outer loop + vertex 1.69352 1.83 2.49 + vertex 1.6939 1.835 2.49 + vertex 1.69022 1.82859 2.49154 + endloop + endfacet + facet normal 0.315179 0.0463246 0.947901 + outer loop + vertex 1.6939 1.835 2.49 + vertex 1.69013 1.83376 2.49131 + vertex 1.69022 1.82859 2.49154 + endloop + endfacet + facet normal 0.734177 0.0413979 0.677695 + outer loop + vertex 1.69013 1.83376 2.49131 + vertex 1.68777 1.82884 2.49418 + vertex 1.69022 1.82859 2.49154 + endloop + endfacet + facet normal 0.798392 -0.0340649 0.601173 + outer loop + vertex 1.68771 1.83403 2.49454 + vertex 1.68777 1.82884 2.49418 + vertex 1.69013 1.83376 2.49131 + endloop + endfacet + facet normal 0.328213 0.00327877 0.944598 + outer loop + vertex 1.6939 1.835 2.49 + vertex 1.69385 1.84 2.49 + vertex 1.69013 1.83376 2.49131 + endloop + endfacet + facet normal 0.446808 -0.0785905 0.891171 + outer loop + vertex 1.69385 1.84 2.49 + vertex 1.69007 1.83933 2.49184 + vertex 1.69013 1.83376 2.49131 + endloop + endfacet + facet normal 0.797428 -0.0472588 0.601561 + outer loop + vertex 1.69007 1.83933 2.49184 + vertex 1.68771 1.83403 2.49454 + vertex 1.69013 1.83376 2.49131 + endloop + endfacet + facet normal 0.804466 -0.0555814 0.591392 + outer loop + vertex 1.68754 1.83813 2.49516 + vertex 1.68771 1.83403 2.49454 + vertex 1.69007 1.83933 2.49184 + endloop + endfacet + facet normal 0.445814 -0.0695458 0.89242 + outer loop + vertex 1.69385 1.84 2.49 + vertex 1.69463 1.845 2.49 + vertex 1.69007 1.83933 2.49184 + endloop + endfacet + facet normal 0.256736 0.104768 0.960786 + outer loop + vertex 1.69463 1.845 2.49 + vertex 1.69106 1.84424 2.49104 + vertex 1.69007 1.83933 2.49184 + endloop + endfacet + facet normal 0.831588 -0.022264 0.554946 + outer loop + vertex 1.68754 1.83813 2.49516 + vertex 1.68831 1.84268 2.49419 + vertex 1.68633 1.83993 2.49705 + endloop + endfacet + facet normal 0.79719 -0.00609286 0.603697 + outer loop + vertex 1.68754 1.83813 2.49516 + vertex 1.69007 1.83933 2.49184 + vertex 1.68831 1.84268 2.49419 + endloop + endfacet + facet normal 0.765248 -0.0496279 0.641819 + outer loop + vertex 1.69007 1.83933 2.49184 + vertex 1.69106 1.84424 2.49104 + vertex 1.68831 1.84268 2.49419 + endloop + endfacet + facet normal 0.813386 0.0183853 0.581434 + outer loop + vertex 1.68831 1.84268 2.49419 + vertex 1.68596 1.84398 2.49744 + vertex 1.68633 1.83993 2.49705 + endloop + endfacet + facet normal 0.280595 -0.00841591 0.959789 + outer loop + vertex 1.69463 1.845 2.49 + vertex 1.69478 1.85 2.49 + vertex 1.69106 1.84424 2.49104 + endloop + endfacet + facet normal 0.488138 -0.160899 0.857807 + outer loop + vertex 1.69478 1.85 2.49 + vertex 1.69018 1.84658 2.49197 + vertex 1.69106 1.84424 2.49104 + endloop + endfacet + facet normal 0.750301 0.0153762 0.660918 + outer loop + vertex 1.69106 1.84424 2.49104 + vertex 1.69018 1.84658 2.49197 + vertex 1.68831 1.84268 2.49419 + endloop + endfacet + facet normal 0.776402 -0.0146591 0.630067 + outer loop + vertex 1.69018 1.84658 2.49197 + vertex 1.68797 1.84737 2.49471 + vertex 1.68831 1.84268 2.49419 + endloop + endfacet + facet normal 0.808565 -0.0076958 0.588357 + outer loop + vertex 1.68797 1.84737 2.49471 + vertex 1.68596 1.84398 2.49744 + vertex 1.68831 1.84268 2.49419 + endloop + endfacet + facet normal 0.781627 0.0358889 0.622713 + outer loop + vertex 1.68535 1.84914 2.49791 + vertex 1.68596 1.84398 2.49744 + vertex 1.68797 1.84737 2.49471 + endloop + endfacet + facet normal 0.182795 0.602664 0.776776 + outer loop + vertex 1.695 1.85082 2.49 + vertex 1.69208 1.85387 2.48832 + vertex 1.69068 1.8504 2.49134 + endloop + endfacet + facet normal 0.302585 -0.0812113 0.949656 + outer loop + vertex 1.695 1.85082 2.49 + vertex 1.69068 1.8504 2.49134 + vertex 1.69478 1.85 2.49 + endloop + endfacet + facet normal 0.318925 0.114675 0.940817 + outer loop + vertex 1.69478 1.85 2.49 + vertex 1.69068 1.8504 2.49134 + vertex 1.69018 1.84658 2.49197 + endloop + endfacet + facet normal 0.778909 0.00249327 0.627132 + outer loop + vertex 1.69018 1.84658 2.49197 + vertex 1.69068 1.8504 2.49134 + vertex 1.68797 1.84737 2.49471 + endloop + endfacet + facet normal 0.774516 0.0123302 0.632434 + outer loop + vertex 1.69068 1.8504 2.49134 + vertex 1.68778 1.85188 2.49487 + vertex 1.68797 1.84737 2.49471 + endloop + endfacet + facet normal 0.775801 0.0124406 0.630855 + outer loop + vertex 1.68778 1.85188 2.49487 + vertex 1.68535 1.84914 2.49791 + vertex 1.68797 1.84737 2.49471 + endloop + endfacet + facet normal 0.76675 0.0318486 0.641155 + outer loop + vertex 1.68565 1.85394 2.4973 + vertex 1.68535 1.84914 2.49791 + vertex 1.68778 1.85188 2.49487 + endloop + endfacet + facet normal 0.83838 0.0626483 0.541474 + outer loop + vertex 1.69208 1.85387 2.48832 + vertex 1.69155 1.85907 2.48852 + vertex 1.68952 1.85552 2.49209 + endloop + endfacet + facet normal 0.844682 0.115603 0.522636 + outer loop + vertex 1.69068 1.8504 2.49134 + vertex 1.69208 1.85387 2.48832 + vertex 1.68952 1.85552 2.49209 + endloop + endfacet + facet normal 0.831588 0.0370222 0.554158 + outer loop + vertex 1.68744 1.85537 2.49522 + vertex 1.68952 1.85552 2.49209 + vertex 1.68773 1.85867 2.49456 + endloop + endfacet + facet normal 0.83216 0.0250253 0.553971 + outer loop + vertex 1.68744 1.85537 2.49522 + vertex 1.68778 1.85188 2.49487 + vertex 1.68952 1.85552 2.49209 + endloop + endfacet + facet normal 0.787082 0.0896327 0.610302 + outer loop + vertex 1.68778 1.85188 2.49487 + vertex 1.69068 1.8504 2.49134 + vertex 1.68952 1.85552 2.49209 + endloop + endfacet + facet normal 0.75712 0.00759123 0.653231 + outer loop + vertex 1.68778 1.85188 2.49487 + vertex 1.68744 1.85537 2.49522 + vertex 1.68565 1.85394 2.4973 + endloop + endfacet + facet normal 0.85505 -0.013037 0.518381 + outer loop + vertex 1.69155 1.85907 2.48852 + vertex 1.69158 1.86441 2.48862 + vertex 1.68965 1.86086 2.49171 + endloop + endfacet + facet normal 0.861856 0.0145298 0.506945 + outer loop + vertex 1.68952 1.85552 2.49209 + vertex 1.69155 1.85907 2.48852 + vertex 1.68965 1.86086 2.49171 + endloop + endfacet + facet normal 0.822122 0.0200263 0.568959 + outer loop + vertex 1.68965 1.86086 2.49171 + vertex 1.68773 1.85867 2.49456 + vertex 1.68952 1.85552 2.49209 + endloop + endfacet + facet normal 0.807963 0.0553764 0.586626 + outer loop + vertex 1.68761 1.86308 2.49431 + vertex 1.68773 1.85867 2.49456 + vertex 1.68965 1.86086 2.49171 + endloop + endfacet + facet normal 0.834749 -0.00422274 0.550615 + outer loop + vertex 1.69158 1.86441 2.48862 + vertex 1.69164 1.86947 2.48857 + vertex 1.68965 1.86584 2.49156 + endloop + endfacet + facet normal 0.839392 0.0171666 0.543256 + outer loop + vertex 1.68965 1.86086 2.49171 + vertex 1.69158 1.86441 2.48862 + vertex 1.68965 1.86584 2.49156 + endloop + endfacet + facet normal 0.794416 0.0189357 0.607078 + outer loop + vertex 1.68965 1.86584 2.49156 + vertex 1.68761 1.86308 2.49431 + vertex 1.68965 1.86086 2.49171 + endloop + endfacet + facet normal 0.775822 0.0541566 0.628624 + outer loop + vertex 1.68743 1.86791 2.49412 + vertex 1.68761 1.86308 2.49431 + vertex 1.68965 1.86584 2.49156 + endloop + endfacet + facet normal 0.812686 0.0111679 0.582594 + outer loop + vertex 1.69164 1.86947 2.48857 + vertex 1.69165 1.87435 2.48846 + vertex 1.68957 1.87081 2.49143 + endloop + endfacet + facet normal 0.816099 0.027909 0.577238 + outer loop + vertex 1.68965 1.86584 2.49156 + vertex 1.69164 1.86947 2.48857 + vertex 1.68957 1.87081 2.49143 + endloop + endfacet + facet normal 0.766785 0.0289119 0.641253 + outer loop + vertex 1.68957 1.87081 2.49143 + vertex 1.68743 1.86791 2.49412 + vertex 1.68965 1.86584 2.49156 + endloop + endfacet + facet normal 0.748144 0.0607746 0.660747 + outer loop + vertex 1.68721 1.87283 2.49391 + vertex 1.68743 1.86791 2.49412 + vertex 1.68957 1.87081 2.49143 + endloop + endfacet + facet normal 0.789905 0.023288 0.612787 + outer loop + vertex 1.69165 1.87435 2.48846 + vertex 1.69159 1.87916 2.48836 + vertex 1.68942 1.87579 2.49127 + endloop + endfacet + facet normal 0.794025 0.0420611 0.606428 + outer loop + vertex 1.68957 1.87081 2.49143 + vertex 1.69165 1.87435 2.48846 + vertex 1.68942 1.87579 2.49127 + endloop + endfacet + facet normal 0.741657 0.0424631 0.669434 + outer loop + vertex 1.68942 1.87579 2.49127 + vertex 1.68721 1.87283 2.49391 + vertex 1.68957 1.87081 2.49143 + endloop + endfacet + facet normal 0.71478 0.08466 0.694206 + outer loop + vertex 1.68682 1.87783 2.4937 + vertex 1.68721 1.87283 2.49391 + vertex 1.68942 1.87579 2.49127 + endloop + endfacet + facet normal 0.760596 0.0244223 0.648766 + outer loop + vertex 1.69159 1.87916 2.48836 + vertex 1.69154 1.88398 2.48823 + vertex 1.68922 1.88082 2.49107 + endloop + endfacet + facet normal 0.769228 0.0569666 0.636429 + outer loop + vertex 1.68942 1.87579 2.49127 + vertex 1.69159 1.87916 2.48836 + vertex 1.68922 1.88082 2.49107 + endloop + endfacet + facet normal 0.705037 0.0570916 0.706869 + outer loop + vertex 1.68922 1.88082 2.49107 + vertex 1.68682 1.87783 2.4937 + vertex 1.68942 1.87579 2.49127 + endloop + endfacet + facet normal 0.675078 0.102 0.730661 + outer loop + vertex 1.68621 1.88329 2.49351 + vertex 1.68682 1.87783 2.4937 + vertex 1.68922 1.88082 2.49107 + endloop + endfacet + facet normal 0.734074 0.0307269 0.678374 + outer loop + vertex 1.69154 1.88398 2.48823 + vertex 1.6915 1.88871 2.48806 + vertex 1.68918 1.88568 2.49071 + endloop + endfacet + facet normal 0.741724 0.0559165 0.66837 + outer loop + vertex 1.68922 1.88082 2.49107 + vertex 1.69154 1.88398 2.48823 + vertex 1.68918 1.88568 2.49071 + endloop + endfacet + facet normal 0.657878 0.0614237 0.750615 + outer loop + vertex 1.68918 1.88568 2.49071 + vertex 1.68621 1.88329 2.49351 + vertex 1.68922 1.88082 2.49107 + endloop + endfacet + facet normal 0.651376 0.0746978 0.755069 + outer loop + vertex 1.68698 1.88772 2.49241 + vertex 1.68621 1.88329 2.49351 + vertex 1.68918 1.88568 2.49071 + endloop + endfacet + facet normal 0.702419 0.0441632 0.710393 + outer loop + vertex 1.6915 1.88871 2.48806 + vertex 1.69132 1.89345 2.48794 + vertex 1.68904 1.89029 2.49039 + endloop + endfacet + facet normal 0.709754 0.0692317 0.701039 + outer loop + vertex 1.68918 1.88568 2.49071 + vertex 1.6915 1.88871 2.48806 + vertex 1.68904 1.89029 2.49039 + endloop + endfacet + facet normal 0.649655 0.0713327 0.756875 + outer loop + vertex 1.68904 1.89029 2.49039 + vertex 1.68698 1.88772 2.49241 + vertex 1.68918 1.88568 2.49071 + endloop + endfacet + facet normal 0.610652 0.122627 0.782347 + outer loop + vertex 1.68611 1.89185 2.49243 + vertex 1.68698 1.88772 2.49241 + vertex 1.68904 1.89029 2.49039 + endloop + endfacet + facet normal 0.657427 0.0641675 0.750781 + outer loop + vertex 1.69132 1.89345 2.48794 + vertex 1.69083 1.89872 2.48792 + vertex 1.68851 1.89499 2.49027 + endloop + endfacet + facet normal 0.665356 0.094253 0.740553 + outer loop + vertex 1.68904 1.89029 2.49039 + vertex 1.69132 1.89345 2.48794 + vertex 1.68851 1.89499 2.49027 + endloop + endfacet + facet normal 0.600898 0.0882754 0.794437 + outer loop + vertex 1.68851 1.89499 2.49027 + vertex 1.68611 1.89185 2.49243 + vertex 1.68904 1.89029 2.49039 + endloop + endfacet + facet normal 0.557254 0.138326 0.818739 + outer loop + vertex 1.68507 1.89718 2.49224 + vertex 1.68611 1.89185 2.49243 + vertex 1.68851 1.89499 2.49027 + endloop + endfacet + facet normal 0.620358 0.104002 0.777393 + outer loop + vertex 1.6879 1.89896 2.49023 + vertex 1.68851 1.89499 2.49027 + vertex 1.69083 1.89872 2.48792 + endloop + endfacet + facet normal 0.620325 0.10614 0.77713 + outer loop + vertex 1.6879 1.89896 2.49023 + vertex 1.69083 1.89872 2.48792 + vertex 1.68848 1.90309 2.4892 + endloop + endfacet + facet normal 0.593314 0.0847734 0.800495 + outer loop + vertex 1.68848 1.90309 2.4892 + vertex 1.69083 1.89872 2.48792 + vertex 1.69146 1.90324 2.48698 + endloop + endfacet + facet normal 0.53853 0.0921287 0.837555 + outer loop + vertex 1.68851 1.89499 2.49027 + vertex 1.6879 1.89896 2.49023 + vertex 1.68507 1.89718 2.49224 + endloop + endfacet + facet normal 0.592665 0.0924109 0.800131 + outer loop + vertex 1.69146 1.90324 2.48698 + vertex 1.69031 1.90757 2.48733 + vertex 1.68848 1.90309 2.4892 + endloop + endfacet + facet normal 0.53408 0.13097 0.835228 + outer loop + vertex 1.68848 1.90309 2.4892 + vertex 1.69031 1.90757 2.48733 + vertex 1.68709 1.9075 2.4894 + endloop + endfacet + facet normal 0.595779 0.091008 0.797976 + outer loop + vertex 1.69272 1.90963 2.48533 + vertex 1.69304 1.91338 2.48466 + vertex 1.69088 1.91164 2.48648 + endloop + endfacet + facet normal 0.591401 0.0847421 0.801912 + outer loop + vertex 1.69088 1.91164 2.48648 + vertex 1.69031 1.90757 2.48733 + vertex 1.69272 1.90963 2.48533 + endloop + endfacet + facet normal 0.506077 0.107996 0.8557 + outer loop + vertex 1.69088 1.91164 2.48648 + vertex 1.68724 1.91255 2.48851 + vertex 1.69031 1.90757 2.48733 + endloop + endfacet + facet normal 0.534154 0.130113 0.835314 + outer loop + vertex 1.68724 1.91255 2.48851 + vertex 1.68709 1.9075 2.4894 + vertex 1.69031 1.90757 2.48733 + endloop + endfacet + facet normal 0.577826 0.0938653 0.810745 + outer loop + vertex 1.69304 1.91338 2.48466 + vertex 1.6928 1.91803 2.4843 + vertex 1.69037 1.9155 2.48633 + endloop + endfacet + facet normal 0.585465 0.109357 0.803288 + outer loop + vertex 1.69088 1.91164 2.48648 + vertex 1.69304 1.91338 2.48466 + vertex 1.69037 1.9155 2.48633 + endloop + endfacet + facet normal 0.505079 0.100759 0.857171 + outer loop + vertex 1.69037 1.9155 2.48633 + vertex 1.68724 1.91255 2.48851 + vertex 1.69088 1.91164 2.48648 + endloop + endfacet + facet normal 0.495003 0.114517 0.861312 + outer loop + vertex 1.6876 1.91758 2.48764 + vertex 1.68724 1.91255 2.48851 + vertex 1.69037 1.9155 2.48633 + endloop + endfacet + facet normal 0.55624 0.110486 0.823645 + outer loop + vertex 1.6928 1.91803 2.4843 + vertex 1.69227 1.92295 2.48399 + vertex 1.68983 1.92013 2.48602 + endloop + endfacet + facet normal 0.559866 0.118584 0.820054 + outer loop + vertex 1.69037 1.9155 2.48633 + vertex 1.6928 1.91803 2.4843 + vertex 1.68983 1.92013 2.48602 + endloop + endfacet + facet normal 0.494632 0.113836 0.861615 + outer loop + vertex 1.68983 1.92013 2.48602 + vertex 1.6876 1.91758 2.48764 + vertex 1.69037 1.9155 2.48633 + endloop + endfacet + facet normal 0.467154 0.144691 0.872256 + outer loop + vertex 1.68627 1.92192 2.48763 + vertex 1.6876 1.91758 2.48764 + vertex 1.68983 1.92013 2.48602 + endloop + endfacet + facet normal 0.527265 0.121828 0.840922 + outer loop + vertex 1.69227 1.92295 2.48399 + vertex 1.69147 1.92839 2.48371 + vertex 1.68895 1.92492 2.4858 + endloop + endfacet + facet normal 0.533369 0.13804 0.834544 + outer loop + vertex 1.68983 1.92013 2.48602 + vertex 1.69227 1.92295 2.48399 + vertex 1.68895 1.92492 2.4858 + endloop + endfacet + facet normal 0.460854 0.126618 0.878397 + outer loop + vertex 1.68895 1.92492 2.4858 + vertex 1.68627 1.92192 2.48763 + vertex 1.68983 1.92013 2.48602 + endloop + endfacet + facet normal 0.438439 0.151213 0.885949 + outer loop + vertex 1.68506 1.92714 2.48734 + vertex 1.68627 1.92192 2.48763 + vertex 1.68895 1.92492 2.4858 + endloop + endfacet + facet normal 0.508002 0.141074 0.849725 + outer loop + vertex 1.68811 1.92898 2.48562 + vertex 1.68895 1.92492 2.4858 + vertex 1.69147 1.92839 2.48371 + endloop + endfacet + facet normal 0.508064 0.14214 0.84951 + outer loop + vertex 1.68811 1.92898 2.48562 + vertex 1.69147 1.92839 2.48371 + vertex 1.68874 1.93318 2.48454 + endloop + endfacet + facet normal 0.503414 0.138918 0.852805 + outer loop + vertex 1.68874 1.93318 2.48454 + vertex 1.69147 1.92839 2.48371 + vertex 1.69213 1.93275 2.48261 + endloop + endfacet + facet normal 0.42784 0.126437 0.894967 + outer loop + vertex 1.68895 1.92492 2.4858 + vertex 1.68811 1.92898 2.48562 + vertex 1.68506 1.92714 2.48734 + endloop + endfacet + facet normal 0.503314 0.135289 0.853447 + outer loop + vertex 1.69213 1.93275 2.48261 + vertex 1.6911 1.9369 2.48256 + vertex 1.68874 1.93318 2.48454 + endloop + endfacet + facet normal 0.467861 0.165694 0.868131 + outer loop + vertex 1.68874 1.93318 2.48454 + vertex 1.6911 1.9369 2.48256 + vertex 1.68713 1.93886 2.48432 + endloop + endfacet + facet normal 0.458362 0.137375 0.878084 + outer loop + vertex 1.6911 1.9369 2.48256 + vertex 1.69009 1.94203 2.48229 + vertex 1.68713 1.93886 2.48432 + endloop + endfacet + facet normal 0.443963 0.153799 0.882747 + outer loop + vertex 1.68713 1.93886 2.48432 + vertex 1.69009 1.94203 2.48229 + vertex 1.68718 1.94259 2.48365 + endloop + endfacet + facet normal 0.509136 0.146344 0.848153 + outer loop + vertex 1.69289 1.94375 2.48036 + vertex 1.69336 1.94803 2.47934 + vertex 1.69072 1.94603 2.48127 + endloop + endfacet + facet normal 0.50213 0.137434 0.853802 + outer loop + vertex 1.69072 1.94603 2.48127 + vertex 1.69009 1.94203 2.48229 + vertex 1.69289 1.94375 2.48036 + endloop + endfacet + facet normal 0.418082 0.160925 0.894041 + outer loop + vertex 1.69072 1.94603 2.48127 + vertex 1.68709 1.94635 2.48291 + vertex 1.69009 1.94203 2.48229 + endloop + endfacet + facet normal 0.44645 0.1832 0.875854 + outer loop + vertex 1.68709 1.94635 2.48291 + vertex 1.68718 1.94259 2.48365 + vertex 1.69009 1.94203 2.48229 + endloop + endfacet + facet normal 0.474305 0.140658 0.869051 + outer loop + vertex 1.69336 1.94803 2.47934 + vertex 1.69154 1.95324 2.47949 + vertex 1.68951 1.94995 2.48113 + endloop + endfacet + facet normal 0.487499 0.180854 0.854188 + outer loop + vertex 1.69072 1.94603 2.48127 + vertex 1.69336 1.94803 2.47934 + vertex 1.68951 1.94995 2.48113 + endloop + endfacet + facet normal 0.418082 0.160833 0.894058 + outer loop + vertex 1.68951 1.94995 2.48113 + vertex 1.68709 1.94635 2.48291 + vertex 1.69072 1.94603 2.48127 + endloop + endfacet + facet normal 0.383631 0.188787 0.903984 + outer loop + vertex 1.68535 1.95197 2.48247 + vertex 1.68709 1.94635 2.48291 + vertex 1.68951 1.94995 2.48113 + endloop + endfacet + facet normal 0.430605 0.17575 0.885263 + outer loop + vertex 1.68832 1.95389 2.48093 + vertex 1.68951 1.94995 2.48113 + vertex 1.69154 1.95324 2.47949 + endloop + endfacet + facet normal 0.431848 0.189717 0.881768 + outer loop + vertex 1.68832 1.95389 2.48093 + vertex 1.69154 1.95324 2.47949 + vertex 1.68887 1.95797 2.47978 + endloop + endfacet + facet normal 0.423428 0.184652 0.886912 + outer loop + vertex 1.68887 1.95797 2.47978 + vertex 1.69154 1.95324 2.47949 + vertex 1.69317 1.95696 2.47794 + endloop + endfacet + facet normal 0.372863 0.159866 0.914011 + outer loop + vertex 1.68951 1.94995 2.48113 + vertex 1.68832 1.95389 2.48093 + vertex 1.68535 1.95197 2.48247 + endloop + endfacet + facet normal 0.421966 0.172928 0.889966 + outer loop + vertex 1.69317 1.95696 2.47794 + vertex 1.69142 1.96174 2.47784 + vertex 1.68887 1.95797 2.47978 + endloop + endfacet + facet normal 0.377805 0.209034 0.90198 + outer loop + vertex 1.68887 1.95797 2.47978 + vertex 1.69142 1.96174 2.47784 + vertex 1.68682 1.96373 2.4793 + endloop + endfacet + facet normal 0.368546 0.180214 0.911974 + outer loop + vertex 1.69142 1.96174 2.47784 + vertex 1.69001 1.9669 2.47739 + vertex 1.68682 1.96373 2.4793 + endloop + endfacet + facet normal 0.352659 0.197788 0.91461 + outer loop + vertex 1.68682 1.96373 2.4793 + vertex 1.69001 1.9669 2.47739 + vertex 1.68672 1.96748 2.47853 + endloop + endfacet + facet normal 0.402729 0.182566 0.896928 + outer loop + vertex 1.69308 1.96873 2.47567 + vertex 1.69366 1.97296 2.47456 + vertex 1.69067 1.97087 2.47632 + endloop + endfacet + facet normal 0.397549 0.175591 0.900623 + outer loop + vertex 1.69067 1.97087 2.47632 + vertex 1.69001 1.9669 2.47739 + vertex 1.69308 1.96873 2.47567 + endloop + endfacet + facet normal 0.335982 0.191615 0.922171 + outer loop + vertex 1.69067 1.97087 2.47632 + vertex 1.68686 1.97108 2.47767 + vertex 1.69001 1.9669 2.47739 + endloop + endfacet + facet normal 0.353323 0.205291 0.912699 + outer loop + vertex 1.68686 1.97108 2.47767 + vertex 1.68672 1.96748 2.47853 + vertex 1.69001 1.9669 2.47739 + endloop + endfacet + facet normal 0.374801 0.1811 0.909245 + outer loop + vertex 1.69366 1.97296 2.47456 + vertex 1.69182 1.97867 2.47418 + vertex 1.6894 1.97476 2.47595 + endloop + endfacet + facet normal 0.384005 0.210994 0.8989 + outer loop + vertex 1.69067 1.97087 2.47632 + vertex 1.69366 1.97296 2.47456 + vertex 1.6894 1.97476 2.47595 + endloop + endfacet + facet normal 0.33589 0.197362 0.920992 + outer loop + vertex 1.6894 1.97476 2.47595 + vertex 1.68686 1.97108 2.47767 + vertex 1.69067 1.97087 2.47632 + endloop + endfacet + facet normal 0.312509 0.215483 0.925151 + outer loop + vertex 1.6849 1.97647 2.47707 + vertex 1.68686 1.97108 2.47767 + vertex 1.6894 1.97476 2.47595 + endloop + endfacet + facet normal 0.336008 0.209258 0.918319 + outer loop + vertex 1.68794 1.9787 2.47559 + vertex 1.6894 1.97476 2.47595 + vertex 1.69182 1.97867 2.47418 + endloop + endfacet + facet normal 0.335383 0.218613 0.916366 + outer loop + vertex 1.68794 1.9787 2.47559 + vertex 1.69182 1.97867 2.47418 + vertex 1.688 1.98328 2.47447 + endloop + endfacet + facet normal 0.306513 0.193688 0.931952 + outer loop + vertex 1.688 1.98328 2.47447 + vertex 1.69182 1.97867 2.47418 + vertex 1.69182 1.98244 2.47339 + endloop + endfacet + facet normal 0.30785 0.199957 0.930186 + outer loop + vertex 1.6894 1.97476 2.47595 + vertex 1.68794 1.9787 2.47559 + vertex 1.6849 1.97647 2.47707 + endloop + endfacet + facet normal 0.310008 0.217798 0.925451 + outer loop + vertex 1.69182 1.98244 2.47339 + vertex 1.69191 1.98602 2.47252 + vertex 1.688 1.98328 2.47447 + endloop + endfacet + facet normal 0.305264 0.217889 0.927005 + outer loop + vertex 1.69191 1.98602 2.47252 + vertex 1.68981 1.99138 2.47195 + vertex 1.68787 1.98804 2.47338 + endloop + endfacet + facet normal 0.306073 0.222042 0.925752 + outer loop + vertex 1.68986 1.9955 2.47095 + vertex 1.68981 1.99138 2.47195 + vertex 1.69263 1.9935 2.47051 + endloop + endfacet + facet normal 0.336988 0.417477 0.843891 + outer loop + vertex 1.68697 2.07275 2.44992 + vertex 1.6927 2.06828 2.44984 + vertex 1.69117 2.07355 2.44785 + endloop + endfacet + facet normal 0.347814 0.573322 0.741841 + outer loop + vertex 1.69418 2.07497 2.44571 + vertex 1.69335 2.07701 2.44453 + vertex 1.69095 2.07691 2.44573 + endloop + endfacet + facet normal 0.316362 0.520606 0.793022 + outer loop + vertex 1.69095 2.07691 2.44573 + vertex 1.69117 2.07355 2.44785 + vertex 1.69418 2.07497 2.44571 + endloop + endfacet + facet normal 0.344653 0.516633 0.783776 + outer loop + vertex 1.69095 2.07691 2.44573 + vertex 1.68655 2.07728 2.44743 + vertex 1.69117 2.07355 2.44785 + endloop + endfacet + facet normal 0.312704 0.480937 0.819094 + outer loop + vertex 1.68655 2.07728 2.44743 + vertex 1.68697 2.07275 2.44992 + vertex 1.69117 2.07355 2.44785 + endloop + endfacet + facet normal 0.392824 0.736237 0.55104 + outer loop + vertex 1.69277 2.07911 2.44262 + vertex 1.69153 2.08142 2.44041 + vertex 1.68945 2.08084 2.44268 + endloop + endfacet + facet normal 0.380952 0.679197 0.627349 + outer loop + vertex 1.68945 2.08084 2.44268 + vertex 1.68688 2.08121 2.44384 + vertex 1.68853 2.07934 2.44486 + endloop + endfacet + facet normal 0.368352 0.686443 0.626987 + outer loop + vertex 1.69277 2.07911 2.44262 + vertex 1.68945 2.08084 2.44268 + vertex 1.68853 2.07934 2.44486 + endloop + endfacet + facet normal 0.389135 0.629941 0.672122 + outer loop + vertex 1.69277 2.07911 2.44262 + vertex 1.68853 2.07934 2.44486 + vertex 1.69095 2.07691 2.44573 + endloop + endfacet + facet normal 0.30272 0.686273 0.661354 + outer loop + vertex 1.69277 2.07911 2.44262 + vertex 1.69095 2.07691 2.44573 + vertex 1.69335 2.07701 2.44453 + endloop + endfacet + facet normal 0.331432 0.594061 0.732969 + outer loop + vertex 1.69095 2.07691 2.44573 + vertex 1.68853 2.07934 2.44486 + vertex 1.68655 2.07728 2.44743 + endloop + endfacet + facet normal -0.115757 0.484305 0.867208 + outer loop + vertex 1.69201 2.09 2.435 + vertex 1.68661 2.08779 2.43551 + vertex 1.68835 2.08568 2.43693 + endloop + endfacet + facet normal 0.196598 0.255575 0.946589 + outer loop + vertex 1.69201 2.09 2.435 + vertex 1.68835 2.08568 2.43693 + vertex 1.695 2.0877 2.435 + endloop + endfacet + facet normal 0.143784 0.39264 0.908383 + outer loop + vertex 1.695 2.0877 2.435 + vertex 1.68835 2.08568 2.43693 + vertex 1.69242 2.08337 2.43728 + endloop + endfacet + facet normal 0.355829 0.772177 0.526429 + outer loop + vertex 1.69153 2.08142 2.44041 + vertex 1.68787 2.08278 2.4409 + vertex 1.68945 2.08084 2.44268 + endloop + endfacet + facet normal 0.351551 0.746857 0.564461 + outer loop + vertex 1.69153 2.08142 2.44041 + vertex 1.69242 2.08337 2.43728 + vertex 1.68787 2.08278 2.4409 + endloop + endfacet + facet normal 0.364093 0.730628 0.577597 + outer loop + vertex 1.69242 2.08337 2.43728 + vertex 1.68835 2.08568 2.43693 + vertex 1.68787 2.08278 2.4409 + endloop + endfacet + facet normal 0.350644 0.771725 0.530556 + outer loop + vertex 1.68945 2.08084 2.44268 + vertex 1.68787 2.08278 2.4409 + vertex 1.68688 2.08121 2.44384 + endloop + endfacet + facet normal 0.0605312 0.0822017 0.994776 + outer loop + vertex 1.69201 2.09 2.435 + vertex 1.69 2.09148 2.435 + vertex 1.68661 2.08779 2.43551 + endloop + endfacet + facet normal 0.306414 0.515558 0.800194 + outer loop + vertex 1.69582 0.947772 2.43628 + vertex 1.7 0.947267 2.435 + vertex 1.6994 0.948412 2.43449 + endloop + endfacet + facet normal 0.293809 0.0172652 0.955708 + outer loop + vertex 1.69582 0.947772 2.43628 + vertex 1.69223 0.946775 2.4374 + vertex 1.7 0.947267 2.435 + endloop + endfacet + facet normal 0.247377 -0.713723 0.655289 + outer loop + vertex 1.69223 0.946775 2.4374 + vertex 1.695 0.945534 2.435 + vertex 1.7 0.947267 2.435 + endloop + endfacet + facet normal 0.378648 -0.746196 0.547555 + outer loop + vertex 1.69582 0.947772 2.43628 + vertex 1.6931 0.948273 2.43884 + vertex 1.69223 0.946775 2.4374 + endloop + endfacet + facet normal 0.397204 -0.750548 0.528116 + outer loop + vertex 1.6994 0.948412 2.43449 + vertex 1.69618 0.949445 2.43838 + vertex 1.69582 0.947772 2.43628 + endloop + endfacet + facet normal 0.368302 -0.757645 0.53882 + outer loop + vertex 1.6931 0.948273 2.43884 + vertex 1.69582 0.947772 2.43628 + vertex 1.69618 0.949445 2.43838 + endloop + endfacet + facet normal 0.368915 -0.761665 0.532698 + outer loop + vertex 1.6931 0.948273 2.43884 + vertex 1.69618 0.949445 2.43838 + vertex 1.69187 0.949881 2.44199 + endloop + endfacet + facet normal 0.375625 -0.7534 0.539718 + outer loop + vertex 1.69187 0.949881 2.44199 + vertex 1.69618 0.949445 2.43838 + vertex 1.69626 0.952059 2.44198 + endloop + endfacet + facet normal 0.339037 -0.708822 0.618567 + outer loop + vertex 1.69497 0.953906 2.4448 + vertex 1.69626 0.952059 2.44198 + vertex 1.69746 0.954376 2.44397 + endloop + endfacet + facet normal 0.345381 -0.705262 0.619126 + outer loop + vertex 1.69497 0.953906 2.4448 + vertex 1.69196 0.952588 2.44498 + vertex 1.69626 0.952059 2.44198 + endloop + endfacet + facet normal 0.349156 -0.699511 0.623518 + outer loop + vertex 1.69196 0.952588 2.44498 + vertex 1.69187 0.949881 2.44199 + vertex 1.69626 0.952059 2.44198 + endloop + endfacet + facet normal 0.305384 -0.597044 0.741808 + outer loop + vertex 1.69497 0.953906 2.4448 + vertex 1.6935 0.955671 2.44683 + vertex 1.69196 0.952588 2.44498 + endloop + endfacet + facet normal 0.351185 -0.607318 0.712625 + outer loop + vertex 1.69746 0.954376 2.44397 + vertex 1.69647 0.955801 2.44567 + vertex 1.69497 0.953906 2.4448 + endloop + endfacet + facet normal 0.313577 -0.591439 0.742879 + outer loop + vertex 1.69647 0.955801 2.44567 + vertex 1.6935 0.955671 2.44683 + vertex 1.69497 0.953906 2.4448 + endloop + endfacet + facet normal 0.333582 -0.488866 0.80606 + outer loop + vertex 1.69647 0.955801 2.44567 + vertex 1.69764 0.959201 2.44725 + vertex 1.6935 0.955671 2.44683 + endloop + endfacet + facet normal 0.326223 -0.481159 0.813674 + outer loop + vertex 1.69764 0.959201 2.44725 + vertex 1.69276 0.959192 2.4492 + vertex 1.6935 0.955671 2.44683 + endloop + endfacet + facet normal 0.357312 -0.400231 0.843886 + outer loop + vertex 1.69349 0.962776 2.45059 + vertex 1.69073 0.960766 2.45081 + vertex 1.69276 0.959192 2.4492 + endloop + endfacet + facet normal 0.347327 -0.399891 0.848205 + outer loop + vertex 1.69349 0.962776 2.45059 + vertex 1.69276 0.959192 2.4492 + vertex 1.69769 0.964103 2.4495 + endloop + endfacet + facet normal 0.34176 -0.394593 0.852934 + outer loop + vertex 1.69769 0.964103 2.4495 + vertex 1.69276 0.959192 2.4492 + vertex 1.69764 0.959201 2.44725 + endloop + endfacet + facet normal 0.30697 -0.325799 0.894217 + outer loop + vertex 1.69349 0.962776 2.45059 + vertex 1.6912 0.963708 2.45172 + vertex 1.69073 0.960766 2.45081 + endloop + endfacet + facet normal 0.336147 -0.227017 0.91404 + outer loop + vertex 1.69593 1.02366 2.46656 + vertex 1.69219 1.02386 2.46799 + vertex 1.69213 1.01925 2.46687 + endloop + endfacet + facet normal 0.339069 -0.203837 0.918413 + outer loop + vertex 1.69593 1.02366 2.46656 + vertex 1.6966 1.02808 2.4673 + vertex 1.69219 1.02386 2.46799 + endloop + endfacet + facet normal 0.359195 -0.227056 0.905221 + outer loop + vertex 1.69219 1.02386 2.46799 + vertex 1.6966 1.02808 2.4673 + vertex 1.69285 1.02875 2.46896 + endloop + endfacet + facet normal 0.366079 -0.198457 0.909176 + outer loop + vertex 1.6966 1.02808 2.4673 + vertex 1.69774 1.0336 2.46804 + vertex 1.69285 1.02875 2.46896 + endloop + endfacet + facet normal 0.39372 -0.230015 0.889988 + outer loop + vertex 1.69285 1.02875 2.46896 + vertex 1.69774 1.0336 2.46804 + vertex 1.69322 1.03362 2.47005 + endloop + endfacet + facet normal 0.479843 -0.155158 0.863526 + outer loop + vertex 1.69333 1.08306 2.4803 + vertex 1.69118 1.08055 2.48104 + vertex 1.69339 1.07958 2.47964 + endloop + endfacet + facet normal 0.567755 -0.143746 0.81055 + outer loop + vertex 1.69333 1.08306 2.4803 + vertex 1.69339 1.07958 2.47964 + vertex 1.69616 1.08365 2.47842 + endloop + endfacet + facet normal 0.543011 -0.120733 0.831001 + outer loop + vertex 1.69616 1.08365 2.47842 + vertex 1.69339 1.07958 2.47964 + vertex 1.69609 1.07828 2.47769 + endloop + endfacet + facet normal 0.470243 -0.144857 0.870568 + outer loop + vertex 1.69333 1.08306 2.4803 + vertex 1.69093 1.08378 2.48172 + vertex 1.69118 1.08055 2.48104 + endloop + endfacet + facet normal 0.593839 -0.103587 0.797888 + outer loop + vertex 1.69616 1.08365 2.47842 + vertex 1.6969 1.08911 2.47858 + vertex 1.69402 1.08679 2.48042 + endloop + endfacet + facet normal 0.566964 -0.131559 0.813169 + outer loop + vertex 1.69333 1.08306 2.4803 + vertex 1.69616 1.08365 2.47842 + vertex 1.69402 1.08679 2.48042 + endloop + endfacet + facet normal 0.478451 -0.11696 0.87029 + outer loop + vertex 1.69402 1.08679 2.48042 + vertex 1.69093 1.08378 2.48172 + vertex 1.69333 1.08306 2.4803 + endloop + endfacet + facet normal 0.501392 -0.148233 0.852428 + outer loop + vertex 1.69118 1.08833 2.48236 + vertex 1.69093 1.08378 2.48172 + vertex 1.69402 1.08679 2.48042 + endloop + endfacet + facet normal 0.625933 -0.0938221 0.774213 + outer loop + vertex 1.6969 1.08911 2.47858 + vertex 1.69721 1.09413 2.47893 + vertex 1.69446 1.09159 2.48085 + endloop + endfacet + facet normal 0.604645 -0.126106 0.786448 + outer loop + vertex 1.69402 1.08679 2.48042 + vertex 1.6969 1.08911 2.47858 + vertex 1.69446 1.09159 2.48085 + endloop + endfacet + facet normal 0.512854 -0.123454 0.849553 + outer loop + vertex 1.69446 1.09159 2.48085 + vertex 1.69118 1.08833 2.48236 + vertex 1.69402 1.08679 2.48042 + endloop + endfacet + facet normal 0.534803 -0.154285 0.830772 + outer loop + vertex 1.69159 1.09338 2.48303 + vertex 1.69118 1.08833 2.48236 + vertex 1.69446 1.09159 2.48085 + endloop + endfacet + facet normal 0.668877 -0.0846756 0.738535 + outer loop + vertex 1.69721 1.09413 2.47893 + vertex 1.69744 1.09915 2.4793 + vertex 1.69478 1.09656 2.48142 + endloop + endfacet + facet normal 0.643321 -0.127178 0.754959 + outer loop + vertex 1.69446 1.09159 2.48085 + vertex 1.69721 1.09413 2.47893 + vertex 1.69478 1.09656 2.48142 + endloop + endfacet + facet normal 0.547441 -0.129259 0.826801 + outer loop + vertex 1.69478 1.09656 2.48142 + vertex 1.69159 1.09338 2.48303 + vertex 1.69446 1.09159 2.48085 + endloop + endfacet + facet normal 0.56396 -0.15364 0.811384 + outer loop + vertex 1.69185 1.09879 2.48388 + vertex 1.69159 1.09338 2.48303 + vertex 1.69478 1.09656 2.48142 + endloop + endfacet + facet normal 0.717219 -0.0890683 0.691132 + outer loop + vertex 1.69744 1.09915 2.4793 + vertex 1.69745 1.10322 2.47981 + vertex 1.69526 1.10134 2.48185 + endloop + endfacet + facet normal 0.692826 -0.13371 0.7086 + outer loop + vertex 1.69478 1.09656 2.48142 + vertex 1.69744 1.09915 2.4793 + vertex 1.69526 1.10134 2.48185 + endloop + endfacet + facet normal 0.577037 -0.130714 0.80619 + outer loop + vertex 1.69526 1.10134 2.48185 + vertex 1.69185 1.09879 2.48388 + vertex 1.69478 1.09656 2.48142 + endloop + endfacet + facet normal 0.585871 -0.15037 0.796332 + outer loop + vertex 1.69335 1.10472 2.48389 + vertex 1.69185 1.09879 2.48388 + vertex 1.69526 1.10134 2.48185 + endloop + endfacet + facet normal 0.726439 -0.114494 0.677626 + outer loop + vertex 1.69745 1.10322 2.47981 + vertex 1.69611 1.10517 2.48158 + vertex 1.69526 1.10134 2.48185 + endloop + endfacet + facet normal 0.647544 -0.091391 0.756528 + outer loop + vertex 1.69611 1.10517 2.48158 + vertex 1.69335 1.10472 2.48389 + vertex 1.69526 1.10134 2.48185 + endloop + endfacet + facet normal 0.646281 -0.062801 0.760511 + outer loop + vertex 1.69611 1.10517 2.48158 + vertex 1.69588 1.10906 2.4821 + vertex 1.69335 1.10472 2.48389 + endloop + endfacet + facet normal 0.69226 -0.109034 0.713363 + outer loop + vertex 1.69588 1.10906 2.4821 + vertex 1.69342 1.10973 2.48459 + vertex 1.69335 1.10472 2.48389 + endloop + endfacet + facet normal 0.595029 -0.097061 0.797822 + outer loop + vertex 1.69317 1.11319 2.4852 + vertex 1.69125 1.11045 2.48629 + vertex 1.69342 1.10973 2.48459 + endloop + endfacet + facet normal 0.721951 -0.0686951 0.688526 + outer loop + vertex 1.69317 1.11319 2.4852 + vertex 1.69342 1.10973 2.48459 + vertex 1.69562 1.1142 2.48273 + endloop + endfacet + facet normal 0.703434 -0.0511309 0.708919 + outer loop + vertex 1.69562 1.1142 2.48273 + vertex 1.69342 1.10973 2.48459 + vertex 1.69588 1.10906 2.4821 + endloop + endfacet + facet normal 0.575487 -0.0768665 0.814191 + outer loop + vertex 1.69317 1.11319 2.4852 + vertex 1.69088 1.11386 2.48688 + vertex 1.69125 1.11045 2.48629 + endloop + endfacet + facet normal 0.744564 -0.00720745 0.667513 + outer loop + vertex 1.69562 1.1142 2.48273 + vertex 1.69628 1.11872 2.48204 + vertex 1.69394 1.11768 2.48464 + endloop + endfacet + facet normal 0.716659 -0.0365928 0.696463 + outer loop + vertex 1.69317 1.11319 2.4852 + vertex 1.69562 1.1142 2.48273 + vertex 1.69394 1.11768 2.48464 + endloop + endfacet + facet normal 0.591617 -0.00156217 0.806218 + outer loop + vertex 1.69394 1.11768 2.48464 + vertex 1.69088 1.11386 2.48688 + vertex 1.69317 1.11319 2.4852 + endloop + endfacet + facet normal 0.649607 -0.0770664 0.756354 + outer loop + vertex 1.69098 1.11873 2.48729 + vertex 1.69088 1.11386 2.48688 + vertex 1.69394 1.11768 2.48464 + endloop + endfacet + facet normal 0.836775 0.0956799 0.539123 + outer loop + vertex 1.69741 1.12147 2.48008 + vertex 1.6974 1.12518 2.47944 + vertex 1.69589 1.12211 2.48232 + endloop + endfacet + facet normal 0.83362 0.050109 0.550061 + outer loop + vertex 1.69628 1.11872 2.48204 + vertex 1.69741 1.12147 2.48008 + vertex 1.69589 1.12211 2.48232 + endloop + endfacet + facet normal 0.737167 0.0283904 0.675114 + outer loop + vertex 1.69628 1.11872 2.48204 + vertex 1.69589 1.12211 2.48232 + vertex 1.69394 1.11768 2.48464 + endloop + endfacet + facet normal 0.765828 -0.00105095 0.643044 + outer loop + vertex 1.69394 1.11768 2.48464 + vertex 1.69589 1.12211 2.48232 + vertex 1.69364 1.12287 2.485 + endloop + endfacet + facet normal 0.664018 -0.014061 0.747584 + outer loop + vertex 1.69364 1.12287 2.485 + vertex 1.69098 1.11873 2.48729 + vertex 1.69394 1.11768 2.48464 + endloop + endfacet + facet normal 0.707106 -0.0657298 0.704046 + outer loop + vertex 1.69082 1.1241 2.48795 + vertex 1.69098 1.11873 2.48729 + vertex 1.69364 1.12287 2.485 + endloop + endfacet + facet normal 0.862796 0.0830662 0.498682 + outer loop + vertex 1.6974 1.12518 2.47944 + vertex 1.69717 1.12982 2.47907 + vertex 1.69569 1.12653 2.48218 + endloop + endfacet + facet normal 0.858782 0.056754 0.509187 + outer loop + vertex 1.69589 1.12211 2.48232 + vertex 1.6974 1.12518 2.47944 + vertex 1.69569 1.12653 2.48218 + endloop + endfacet + facet normal 0.772651 0.0568438 0.632281 + outer loop + vertex 1.69589 1.12211 2.48232 + vertex 1.69569 1.12653 2.48218 + vertex 1.69364 1.12287 2.485 + endloop + endfacet + facet normal 0.813121 -0.00450002 0.582077 + outer loop + vertex 1.69569 1.12653 2.48218 + vertex 1.69361 1.12792 2.48508 + vertex 1.69364 1.12287 2.485 + endloop + endfacet + facet normal 0.721089 -0.00668398 0.69281 + outer loop + vertex 1.69361 1.12792 2.48508 + vertex 1.69082 1.1241 2.48795 + vertex 1.69364 1.12287 2.485 + endloop + endfacet + facet normal 0.755174 -0.0617862 0.652606 + outer loop + vertex 1.69136 1.12973 2.48785 + vertex 1.69082 1.1241 2.48795 + vertex 1.69361 1.12792 2.48508 + endloop + endfacet + facet normal 0.89118 0.0292978 0.452703 + outer loop + vertex 1.69717 1.12982 2.47907 + vertex 1.69701 1.13488 2.47904 + vertex 1.6956 1.1313 2.48206 + endloop + endfacet + facet normal 0.890892 0.0276302 0.453375 + outer loop + vertex 1.69569 1.12653 2.48218 + vertex 1.69717 1.12982 2.47907 + vertex 1.6956 1.1313 2.48206 + endloop + endfacet + facet normal 0.820381 0.0293305 0.571065 + outer loop + vertex 1.69569 1.12653 2.48218 + vertex 1.6956 1.1313 2.48206 + vertex 1.69361 1.12792 2.48508 + endloop + endfacet + facet normal 0.844672 -0.0172244 0.535007 + outer loop + vertex 1.6956 1.1313 2.48206 + vertex 1.69373 1.13291 2.48506 + vertex 1.69361 1.12792 2.48508 + endloop + endfacet + facet normal 0.771737 -0.0153018 0.635757 + outer loop + vertex 1.69373 1.13291 2.48506 + vertex 1.69136 1.12973 2.48785 + vertex 1.69361 1.12792 2.48508 + endloop + endfacet + facet normal 0.786829 -0.0441957 0.615587 + outer loop + vertex 1.69156 1.13476 2.48796 + vertex 1.69136 1.12973 2.48785 + vertex 1.69373 1.13291 2.48506 + endloop + endfacet + facet normal 0.903922 0.00205709 0.427693 + outer loop + vertex 1.69701 1.13488 2.47904 + vertex 1.69693 1.14 2.47918 + vertex 1.6956 1.1362 2.48202 + endloop + endfacet + facet normal 0.904058 0.00286736 0.4274 + outer loop + vertex 1.6956 1.1313 2.48206 + vertex 1.69701 1.13488 2.47904 + vertex 1.6956 1.1362 2.48202 + endloop + endfacet + facet normal 0.849814 0.00356185 0.52707 + outer loop + vertex 1.6956 1.1313 2.48206 + vertex 1.6956 1.1362 2.48202 + vertex 1.69373 1.13291 2.48506 + endloop + endfacet + facet normal 0.854686 -0.00659848 0.519104 + outer loop + vertex 1.6956 1.1362 2.48202 + vertex 1.69377 1.13781 2.48506 + vertex 1.69373 1.13291 2.48506 + endloop + endfacet + facet normal 0.799489 -0.00597647 0.600652 + outer loop + vertex 1.69377 1.13781 2.48506 + vertex 1.69156 1.13476 2.48796 + vertex 1.69373 1.13291 2.48506 + endloop + endfacet + facet normal 0.810173 -0.0281154 0.585517 + outer loop + vertex 1.69164 1.13969 2.48809 + vertex 1.69156 1.13476 2.48796 + vertex 1.69377 1.13781 2.48506 + endloop + endfacet + facet normal 0.886152 0.0617942 0.459256 + outer loop + vertex 1.69693 1.14 2.47918 + vertex 1.6967 1.14507 2.47895 + vertex 1.69546 1.14129 2.48185 + endloop + endfacet + facet normal 0.882784 0.0396065 0.468106 + outer loop + vertex 1.6956 1.1362 2.48202 + vertex 1.69693 1.14 2.47918 + vertex 1.69546 1.14129 2.48185 + endloop + endfacet + facet normal 0.864908 0.0401818 0.50032 + outer loop + vertex 1.6956 1.1362 2.48202 + vertex 1.69546 1.14129 2.48185 + vertex 1.69377 1.13781 2.48506 + endloop + endfacet + facet normal 0.86062 0.0483696 0.506946 + outer loop + vertex 1.69546 1.14129 2.48185 + vertex 1.69357 1.14286 2.48492 + vertex 1.69377 1.13781 2.48506 + endloop + endfacet + facet normal 0.831625 0.0484537 0.55322 + outer loop + vertex 1.69357 1.14286 2.48492 + vertex 1.69164 1.13969 2.48809 + vertex 1.69377 1.13781 2.48506 + endloop + endfacet + facet normal 0.852847 0.00461619 0.52214 + outer loop + vertex 1.69158 1.14461 2.48814 + vertex 1.69164 1.13969 2.48809 + vertex 1.69357 1.14286 2.48492 + endloop + endfacet + facet normal 0.839556 0.145692 0.523373 + outer loop + vertex 1.6967 1.14507 2.47895 + vertex 1.69632 1.14972 2.47826 + vertex 1.69488 1.14729 2.48125 + endloop + endfacet + facet normal 0.836143 0.134093 0.531869 + outer loop + vertex 1.69546 1.14129 2.48185 + vertex 1.6967 1.14507 2.47895 + vertex 1.69488 1.14729 2.48125 + endloop + endfacet + facet normal 0.872077 0.131506 0.471367 + outer loop + vertex 1.69546 1.14129 2.48185 + vertex 1.69488 1.14729 2.48125 + vertex 1.69357 1.14286 2.48492 + endloop + endfacet + facet normal 0.899165 0.0881018 0.42865 + outer loop + vertex 1.69488 1.14729 2.48125 + vertex 1.69308 1.14803 2.48488 + vertex 1.69357 1.14286 2.48492 + endloop + endfacet + facet normal 0.868693 0.0857423 0.487873 + outer loop + vertex 1.69308 1.14803 2.48488 + vertex 1.69158 1.14461 2.48814 + vertex 1.69357 1.14286 2.48492 + endloop + endfacet + facet normal 0.901364 0.0186789 0.43266 + outer loop + vertex 1.69147 1.14961 2.48817 + vertex 1.69158 1.14461 2.48814 + vertex 1.69308 1.14803 2.48488 + endloop + endfacet + facet normal 0.866469 0.0844301 0.49204 + outer loop + vertex 1.69383 1.15309 2.4821 + vertex 1.69488 1.14729 2.48125 + vertex 1.695 1.15336 2.48 + endloop + endfacet + facet normal 0.793473 -0.475238 0.380196 + outer loop + vertex 1.69383 1.15309 2.4821 + vertex 1.695 1.15336 2.48 + vertex 1.695 1.155 2.48205 + endloop + endfacet + facet normal 0.869265 0.0833882 0.487262 + outer loop + vertex 1.69488 1.14729 2.48125 + vertex 1.69632 1.14972 2.47826 + vertex 1.695 1.15336 2.48 + endloop + endfacet + facet normal 0.449096 -0.703759 0.550488 + outer loop + vertex 1.69757 1.155 2.48 + vertex 1.695 1.15336 2.48 + vertex 1.69669 1.15295 2.47809 + endloop + endfacet + facet normal 0.741309 -0.0499099 0.669306 + outer loop + vertex 1.69632 1.14972 2.47826 + vertex 1.69669 1.15295 2.47809 + vertex 1.695 1.15336 2.48 + endloop + endfacet + facet normal 0.899088 0.10001 0.42619 + outer loop + vertex 1.69488 1.14729 2.48125 + vertex 1.69383 1.15309 2.4821 + vertex 1.69308 1.14803 2.48488 + endloop + endfacet + facet normal 0.937016 0.0502769 0.34565 + outer loop + vertex 1.69383 1.15309 2.4821 + vertex 1.69272 1.15321 2.48509 + vertex 1.69308 1.14803 2.48488 + endloop + endfacet + facet normal 0.905422 0.0448688 0.422135 + outer loop + vertex 1.69272 1.15321 2.48509 + vertex 1.69147 1.14961 2.48817 + vertex 1.69308 1.14803 2.48488 + endloop + endfacet + facet normal 0.925012 0.0020087 0.379933 + outer loop + vertex 1.69148 1.15473 2.48811 + vertex 1.69147 1.14961 2.48817 + vertex 1.69272 1.15321 2.48509 + endloop + endfacet + facet normal -0.00148015 -0.178574 0.983925 + outer loop + vertex 1.69383 1.15309 2.4821 + vertex 1.695 1.16 2.48336 + vertex 1.69348 1.15825 2.48304 + endloop + endfacet + facet normal 0.417084 -0.230367 0.879188 + outer loop + vertex 1.69383 1.15309 2.4821 + vertex 1.695 1.155 2.48205 + vertex 1.695 1.16 2.48336 + endloop + endfacet + facet normal 0.598816 -0.667516 0.442539 + outer loop + vertex 1.69757 1.155 2.48 + vertex 1.69669 1.15295 2.47809 + vertex 1.7 1.15718 2.48 + endloop + endfacet + facet normal 0.937558 0.00022129 0.347828 + outer loop + vertex 1.69383 1.15309 2.4821 + vertex 1.69348 1.15825 2.48304 + vertex 1.69272 1.15321 2.48509 + endloop + endfacet + facet normal 0.946329 -0.0112047 0.32301 + outer loop + vertex 1.69348 1.15825 2.48304 + vertex 1.69274 1.15844 2.48521 + vertex 1.69272 1.15321 2.48509 + endloop + endfacet + facet normal 0.92235 -0.0124755 0.386155 + outer loop + vertex 1.69274 1.15844 2.48521 + vertex 1.69148 1.15473 2.48811 + vertex 1.69272 1.15321 2.48509 + endloop + endfacet + facet normal 0.921716 -0.0110445 0.387709 + outer loop + vertex 1.69168 1.15985 2.48777 + vertex 1.69148 1.15473 2.48811 + vertex 1.69274 1.15844 2.48521 + endloop + endfacet + facet normal -0.155392 -0.0453609 0.986811 + outer loop + vertex 1.695 1.165 2.48359 + vertex 1.69348 1.15825 2.48304 + vertex 1.695 1.16 2.48336 + endloop + endfacet + facet normal -0.116871 -0.0544201 0.991655 + outer loop + vertex 1.6935 1.16346 2.48333 + vertex 1.69348 1.15825 2.48304 + vertex 1.695 1.165 2.48359 + endloop + endfacet + facet normal 0.94596 -0.0202192 0.323653 + outer loop + vertex 1.69348 1.15825 2.48304 + vertex 1.6935 1.16346 2.48333 + vertex 1.69274 1.15844 2.48521 + endloop + endfacet + facet normal 0.942332 -0.0156834 0.334311 + outer loop + vertex 1.6935 1.16346 2.48333 + vertex 1.69285 1.16327 2.48513 + vertex 1.69274 1.15844 2.48521 + endloop + endfacet + facet normal 0.921023 -0.014364 0.389244 + outer loop + vertex 1.69285 1.16327 2.48513 + vertex 1.69168 1.15985 2.48777 + vertex 1.69274 1.15844 2.48521 + endloop + endfacet + facet normal 0.917846 -0.00741423 0.396866 + outer loop + vertex 1.692 1.16384 2.48711 + vertex 1.69168 1.15985 2.48777 + vertex 1.69285 1.16327 2.48513 + endloop + endfacet + facet normal -0.147814 -0.0237618 0.98873 + outer loop + vertex 1.695 1.17 2.48371 + vertex 1.6935 1.16346 2.48333 + vertex 1.695 1.165 2.48359 + endloop + endfacet + facet normal -0.025964 -0.052337 0.998292 + outer loop + vertex 1.69325 1.16848 2.48358 + vertex 1.6935 1.16346 2.48333 + vertex 1.695 1.17 2.48371 + endloop + endfacet + facet normal 0.842741 0.185642 0.505296 + outer loop + vertex 1.6926 1.16653 2.48539 + vertex 1.69325 1.16848 2.48358 + vertex 1.69209 1.17012 2.48491 + endloop + endfacet + facet normal 0.923804 0.0424629 0.380504 + outer loop + vertex 1.6926 1.16653 2.48539 + vertex 1.69285 1.16327 2.48513 + vertex 1.69325 1.16848 2.48358 + endloop + endfacet + facet normal 0.940635 0.0285846 0.338213 + outer loop + vertex 1.69285 1.16327 2.48513 + vertex 1.6935 1.16346 2.48333 + vertex 1.69325 1.16848 2.48358 + endloop + endfacet + facet normal 0.922103 0.0420009 0.384659 + outer loop + vertex 1.69285 1.16327 2.48513 + vertex 1.6926 1.16653 2.48539 + vertex 1.692 1.16384 2.48711 + endloop + endfacet + facet normal -0.0715031 0 0.99744 + outer loop + vertex 1.695 1.175 2.48371 + vertex 1.69325 1.16848 2.48358 + vertex 1.695 1.17 2.48371 + endloop + endfacet + facet normal -0.065267 -0.00168032 0.997866 + outer loop + vertex 1.69288 1.17309 2.48357 + vertex 1.69325 1.16848 2.48358 + vertex 1.695 1.175 2.48371 + endloop + endfacet + facet normal 0.790693 0.0655998 0.608689 + outer loop + vertex 1.69288 1.17309 2.48357 + vertex 1.69209 1.17012 2.48491 + vertex 1.69325 1.16848 2.48358 + endloop + endfacet + facet normal 0.679022 0.145468 0.719562 + outer loop + vertex 1.69136 1.17461 2.48469 + vertex 1.69209 1.17012 2.48491 + vertex 1.69288 1.17309 2.48357 + endloop + endfacet + facet normal 0.163869 -0.25305 0.953474 + outer loop + vertex 1.695 1.175 2.48371 + vertex 1.695 1.17986 2.485 + vertex 1.69288 1.17309 2.48357 + endloop + endfacet + facet normal 0.356487 -0.298938 0.885185 + outer loop + vertex 1.69288 1.17309 2.48357 + vertex 1.695 1.17986 2.485 + vertex 1.69136 1.17461 2.48469 + endloop + endfacet + facet normal 0.676516 -0.698039 0.234664 + outer loop + vertex 1.69662 1.85 2.485 + vertex 1.695 1.85 2.48967 + vertex 1.695 1.84843 2.485 + endloop + endfacet + facet normal 0.993344 0.0430041 -0.106858 + outer loop + vertex 1.695 1.85 2.48967 + vertex 1.69445 1.85291 2.48569 + vertex 1.695 1.85082 2.49 + endloop + endfacet + facet normal 0.800341 0.531399 0.277615 + outer loop + vertex 1.695 1.85 2.48967 + vertex 1.69662 1.85 2.485 + vertex 1.69445 1.85291 2.48569 + endloop + endfacet + facet normal 0.259633 -0.0347886 0.965081 + outer loop + vertex 1.69662 1.85 2.485 + vertex 1.69729 1.855 2.485 + vertex 1.69445 1.85291 2.48569 + endloop + endfacet + facet normal 0.611339 0.739851 0.280865 + outer loop + vertex 1.69445 1.85291 2.48569 + vertex 1.69208 1.85387 2.48832 + vertex 1.695 1.85082 2.49 + endloop + endfacet + facet normal 0.231579 0.0060182 0.972797 + outer loop + vertex 1.69729 1.855 2.485 + vertex 1.69716 1.86 2.485 + vertex 1.69445 1.85291 2.48569 + endloop + endfacet + facet normal 0.163058 0.0335558 0.986046 + outer loop + vertex 1.69716 1.86 2.485 + vertex 1.69381 1.85834 2.48561 + vertex 1.69445 1.85291 2.48569 + endloop + endfacet + facet normal 0.75677 0.0982038 0.646262 + outer loop + vertex 1.69381 1.85834 2.48561 + vertex 1.69208 1.85387 2.48832 + vertex 1.69445 1.85291 2.48569 + endloop + endfacet + facet normal 0.79643 0.0560292 0.60213 + outer loop + vertex 1.69155 1.85907 2.48852 + vertex 1.69208 1.85387 2.48832 + vertex 1.69381 1.85834 2.48561 + endloop + endfacet + facet normal 0.180336 -0.00216268 0.983603 + outer loop + vertex 1.69716 1.86 2.485 + vertex 1.69722 1.865 2.485 + vertex 1.69381 1.85834 2.48561 + endloop + endfacet + facet normal 0.26303 -0.046317 0.963675 + outer loop + vertex 1.69722 1.865 2.485 + vertex 1.6938 1.86386 2.48588 + vertex 1.69381 1.85834 2.48561 + endloop + endfacet + facet normal 0.786996 -0.0288985 0.616281 + outer loop + vertex 1.6938 1.86386 2.48588 + vertex 1.69155 1.85907 2.48852 + vertex 1.69381 1.85834 2.48561 + endloop + endfacet + facet normal 0.774916 -0.0145767 0.631896 + outer loop + vertex 1.69158 1.86441 2.48862 + vertex 1.69155 1.85907 2.48852 + vertex 1.6938 1.86386 2.48588 + endloop + endfacet + facet normal 0.252732 -0.0126357 0.967454 + outer loop + vertex 1.69722 1.865 2.485 + vertex 1.69747 1.87 2.485 + vertex 1.6938 1.86386 2.48588 + endloop + endfacet + facet normal 0.255925 -0.0146653 0.966585 + outer loop + vertex 1.69747 1.87 2.485 + vertex 1.69391 1.8691 2.48593 + vertex 1.6938 1.86386 2.48588 + endloop + endfacet + facet normal 0.774038 -0.0223633 0.632744 + outer loop + vertex 1.69391 1.8691 2.48593 + vertex 1.69158 1.86441 2.48862 + vertex 1.6938 1.86386 2.48588 + endloop + endfacet + facet normal 0.75731 -0.00240857 0.653052 + outer loop + vertex 1.69164 1.86947 2.48857 + vertex 1.69158 1.86441 2.48862 + vertex 1.69391 1.8691 2.48593 + endloop + endfacet + facet normal 0.253309 -0.00355115 0.967379 + outer loop + vertex 1.69747 1.87 2.485 + vertex 1.69754 1.875 2.485 + vertex 1.69391 1.8691 2.48593 + endloop + endfacet + facet normal 0.232945 0.00975534 0.972441 + outer loop + vertex 1.69754 1.875 2.485 + vertex 1.69405 1.87392 2.48585 + vertex 1.69391 1.8691 2.48593 + endloop + endfacet + facet normal 0.756711 -0.0103176 0.653668 + outer loop + vertex 1.69405 1.87392 2.48585 + vertex 1.69164 1.86947 2.48857 + vertex 1.69391 1.8691 2.48593 + endloop + endfacet + facet normal 0.737493 0.0133234 0.675223 + outer loop + vertex 1.69165 1.87435 2.48846 + vertex 1.69164 1.86947 2.48857 + vertex 1.69405 1.87392 2.48585 + endloop + endfacet + facet normal 0.238879 -0.0105079 0.970993 + outer loop + vertex 1.69754 1.875 2.485 + vertex 1.69776 1.88 2.485 + vertex 1.69405 1.87392 2.48585 + endloop + endfacet + facet normal 0.112976 0.0691117 0.991191 + outer loop + vertex 1.69776 1.88 2.485 + vertex 1.69389 1.8782 2.48557 + vertex 1.69405 1.87392 2.48585 + endloop + endfacet + facet normal 0.740446 0.0714985 0.668302 + outer loop + vertex 1.69389 1.8782 2.48557 + vertex 1.69165 1.87435 2.48846 + vertex 1.69405 1.87392 2.48585 + endloop + endfacet + facet normal 0.775144 0.0234997 0.631347 + outer loop + vertex 1.69159 1.87916 2.48836 + vertex 1.69165 1.87435 2.48846 + vertex 1.69389 1.8782 2.48557 + endloop + endfacet + facet normal 0.319995 0.42242 0.848035 + outer loop + vertex 1.7 1.88 2.48202 + vertex 1.69802 1.88466 2.48045 + vertex 1.69601 1.88136 2.48285 + endloop + endfacet + facet normal 0.36055 0.892496 0.271026 + outer loop + vertex 1.69776 1.88 2.485 + vertex 1.7 1.88 2.48202 + vertex 1.69601 1.88136 2.48285 + endloop + endfacet + facet normal -0.240012 0.72114 0.649885 + outer loop + vertex 1.69776 1.88 2.485 + vertex 1.69601 1.88136 2.48285 + vertex 1.69389 1.8782 2.48557 + endloop + endfacet + facet normal 0.746346 0.0678492 0.662091 + outer loop + vertex 1.69601 1.88136 2.48285 + vertex 1.69365 1.8826 2.48538 + vertex 1.69389 1.8782 2.48557 + endloop + endfacet + facet normal 0.780974 0.0679664 0.620854 + outer loop + vertex 1.69365 1.8826 2.48538 + vertex 1.69159 1.87916 2.48836 + vertex 1.69389 1.8782 2.48557 + endloop + endfacet + facet normal 0.80838 0.0232649 0.588201 + outer loop + vertex 1.69154 1.88398 2.48823 + vertex 1.69159 1.87916 2.48836 + vertex 1.69365 1.8826 2.48538 + endloop + endfacet + facet normal 0.6684 0.0682495 0.740664 + outer loop + vertex 1.69802 1.88466 2.48045 + vertex 1.69782 1.8895 2.48018 + vertex 1.69559 1.88592 2.48253 + endloop + endfacet + facet normal 0.679064 0.114407 0.725109 + outer loop + vertex 1.69601 1.88136 2.48285 + vertex 1.69802 1.88466 2.48045 + vertex 1.69559 1.88592 2.48253 + endloop + endfacet + facet normal 0.754456 0.115883 0.64604 + outer loop + vertex 1.69601 1.88136 2.48285 + vertex 1.69559 1.88592 2.48253 + vertex 1.69365 1.8826 2.48538 + endloop + endfacet + facet normal 0.825691 0.0036617 0.564111 + outer loop + vertex 1.69559 1.88592 2.48253 + vertex 1.69365 1.88732 2.48536 + vertex 1.69365 1.8826 2.48538 + endloop + endfacet + facet normal 0.804121 0.00378026 0.594454 + outer loop + vertex 1.69365 1.88732 2.48536 + vertex 1.69154 1.88398 2.48823 + vertex 1.69365 1.8826 2.48538 + endloop + endfacet + facet normal 0.789586 0.0288696 0.61296 + outer loop + vertex 1.6915 1.88871 2.48806 + vertex 1.69154 1.88398 2.48823 + vertex 1.69365 1.88732 2.48536 + endloop + endfacet + facet normal 0.735077 0.108085 0.669313 + outer loop + vertex 1.69782 1.8895 2.48018 + vertex 1.69768 1.89405 2.4796 + vertex 1.6956 1.89058 2.48244 + endloop + endfacet + facet normal 0.716457 0.010129 0.697558 + outer loop + vertex 1.69559 1.88592 2.48253 + vertex 1.69782 1.8895 2.48018 + vertex 1.6956 1.89058 2.48244 + endloop + endfacet + facet normal 0.826518 0.00732765 0.562862 + outer loop + vertex 1.69559 1.88592 2.48253 + vertex 1.6956 1.89058 2.48244 + vertex 1.69365 1.88732 2.48536 + endloop + endfacet + facet normal 0.827423 0.00560851 0.561551 + outer loop + vertex 1.6956 1.89058 2.48244 + vertex 1.69366 1.89195 2.4853 + vertex 1.69365 1.88732 2.48536 + endloop + endfacet + facet normal 0.784349 0.006459 0.620286 + outer loop + vertex 1.69366 1.89195 2.4853 + vertex 1.6915 1.88871 2.48806 + vertex 1.69365 1.88732 2.48536 + endloop + endfacet + facet normal 0.761115 0.0447723 0.64707 + outer loop + vertex 1.69132 1.89345 2.48794 + vertex 1.6915 1.88871 2.48806 + vertex 1.69366 1.89195 2.4853 + endloop + endfacet + facet normal 0.81937 0.057866 0.570337 + outer loop + vertex 1.69768 1.89405 2.4796 + vertex 1.69768 1.89879 2.47912 + vertex 1.69569 1.89518 2.48235 + endloop + endfacet + facet normal 0.809071 -0.0027489 0.587704 + outer loop + vertex 1.6956 1.89058 2.48244 + vertex 1.69768 1.89405 2.4796 + vertex 1.69569 1.89518 2.48235 + endloop + endfacet + facet normal 0.825388 -0.00354054 0.564555 + outer loop + vertex 1.6956 1.89058 2.48244 + vertex 1.69569 1.89518 2.48235 + vertex 1.69366 1.89195 2.4853 + endloop + endfacet + facet normal 0.815215 0.0160084 0.578937 + outer loop + vertex 1.69569 1.89518 2.48235 + vertex 1.69361 1.89666 2.48524 + vertex 1.69366 1.89195 2.4853 + endloop + endfacet + facet normal 0.753836 0.0162919 0.656861 + outer loop + vertex 1.69361 1.89666 2.48524 + vertex 1.69132 1.89345 2.48794 + vertex 1.69366 1.89195 2.4853 + endloop + endfacet + facet normal 0.719454 0.0696424 0.69104 + outer loop + vertex 1.69083 1.89872 2.48792 + vertex 1.69132 1.89345 2.48794 + vertex 1.69361 1.89666 2.48524 + endloop + endfacet + facet normal 0.852482 -0.0369444 0.521449 + outer loop + vertex 1.69768 1.89879 2.47912 + vertex 1.69787 1.90385 2.47917 + vertex 1.69578 1.89992 2.48231 + endloop + endfacet + facet normal 0.856934 -0.0121522 0.515283 + outer loop + vertex 1.69569 1.89518 2.48235 + vertex 1.69768 1.89879 2.47912 + vertex 1.69578 1.89992 2.48231 + endloop + endfacet + facet normal 0.808789 -0.0108056 0.587999 + outer loop + vertex 1.69569 1.89518 2.48235 + vertex 1.69578 1.89992 2.48231 + vertex 1.69361 1.89666 2.48524 + endloop + endfacet + facet normal 0.79165 0.0208321 0.61062 + outer loop + vertex 1.69578 1.89992 2.48231 + vertex 1.6936 1.90141 2.48509 + vertex 1.69361 1.89666 2.48524 + endloop + endfacet + facet normal 0.703752 0.0239033 0.710043 + outer loop + vertex 1.6936 1.90141 2.48509 + vertex 1.69083 1.89872 2.48792 + vertex 1.69361 1.89666 2.48524 + endloop + endfacet + facet normal 0.687167 0.0560042 0.724338 + outer loop + vertex 1.69146 1.90324 2.48698 + vertex 1.69083 1.89872 2.48792 + vertex 1.6936 1.90141 2.48509 + endloop + endfacet + facet normal 0.828692 -0.0327313 0.558747 + outer loop + vertex 1.69787 1.90385 2.47917 + vertex 1.69788 1.90909 2.47946 + vertex 1.69572 1.9049 2.48242 + endloop + endfacet + facet normal 0.833663 -0.00228137 0.552269 + outer loop + vertex 1.69578 1.89992 2.48231 + vertex 1.69787 1.90385 2.47917 + vertex 1.69572 1.9049 2.48242 + endloop + endfacet + facet normal 0.785301 -0.0043104 0.619099 + outer loop + vertex 1.69578 1.89992 2.48231 + vertex 1.69572 1.9049 2.48242 + vertex 1.6936 1.90141 2.48509 + endloop + endfacet + facet normal 0.75055 0.0473791 0.659113 + outer loop + vertex 1.69572 1.9049 2.48242 + vertex 1.69332 1.90601 2.48507 + vertex 1.6936 1.90141 2.48509 + endloop + endfacet + facet normal 0.681747 0.0434856 0.730295 + outer loop + vertex 1.69332 1.90601 2.48507 + vertex 1.69146 1.90324 2.48698 + vertex 1.6936 1.90141 2.48509 + endloop + endfacet + facet normal 0.630279 0.104853 0.769256 + outer loop + vertex 1.69031 1.90757 2.48733 + vertex 1.69146 1.90324 2.48698 + vertex 1.69332 1.90601 2.48507 + endloop + endfacet + facet normal 0.783858 0.00360845 0.620929 + outer loop + vertex 1.69788 1.90909 2.47946 + vertex 1.69772 1.91412 2.47963 + vertex 1.69523 1.91029 2.4828 + endloop + endfacet + facet normal 0.787811 0.0283181 0.615265 + outer loop + vertex 1.69572 1.9049 2.48242 + vertex 1.69788 1.90909 2.47946 + vertex 1.69523 1.91029 2.4828 + endloop + endfacet + facet normal 0.699906 0.0664259 0.71114 + outer loop + vertex 1.69272 1.90963 2.48533 + vertex 1.69523 1.91029 2.4828 + vertex 1.69304 1.91338 2.48466 + endloop + endfacet + facet normal 0.700101 0.0653233 0.71105 + outer loop + vertex 1.69272 1.90963 2.48533 + vertex 1.69332 1.90601 2.48507 + vertex 1.69523 1.91029 2.4828 + endloop + endfacet + facet normal 0.745745 0.020947 0.665902 + outer loop + vertex 1.69332 1.90601 2.48507 + vertex 1.69572 1.9049 2.48242 + vertex 1.69523 1.91029 2.4828 + endloop + endfacet + facet normal 0.613765 0.0453936 0.788183 + outer loop + vertex 1.69332 1.90601 2.48507 + vertex 1.69272 1.90963 2.48533 + vertex 1.69031 1.90757 2.48733 + endloop + endfacet + facet normal 0.755324 0.040677 0.654087 + outer loop + vertex 1.69772 1.91412 2.47963 + vertex 1.69764 1.91884 2.47943 + vertex 1.69536 1.91584 2.48225 + endloop + endfacet + facet normal 0.757004 0.0465343 0.651751 + outer loop + vertex 1.69523 1.91029 2.4828 + vertex 1.69772 1.91412 2.47963 + vertex 1.69536 1.91584 2.48225 + endloop + endfacet + facet normal 0.6914 0.0548444 0.720388 + outer loop + vertex 1.69536 1.91584 2.48225 + vertex 1.69304 1.91338 2.48466 + vertex 1.69523 1.91029 2.4828 + endloop + endfacet + facet normal 0.668855 0.0927971 0.737579 + outer loop + vertex 1.6928 1.91803 2.4843 + vertex 1.69304 1.91338 2.48466 + vertex 1.69536 1.91584 2.48225 + endloop + endfacet + facet normal 0.731018 0.0708238 0.678673 + outer loop + vertex 1.69764 1.91884 2.47943 + vertex 1.69742 1.92353 2.47918 + vertex 1.69513 1.92078 2.48193 + endloop + endfacet + facet normal 0.733218 0.077713 0.675538 + outer loop + vertex 1.69536 1.91584 2.48225 + vertex 1.69764 1.91884 2.47943 + vertex 1.69513 1.92078 2.48193 + endloop + endfacet + facet normal 0.66271 0.0789686 0.744701 + outer loop + vertex 1.69513 1.92078 2.48193 + vertex 1.6928 1.91803 2.4843 + vertex 1.69536 1.91584 2.48225 + endloop + endfacet + facet normal 0.63729 0.115402 0.761934 + outer loop + vertex 1.69227 1.92295 2.48399 + vertex 1.6928 1.91803 2.4843 + vertex 1.69513 1.92078 2.48193 + endloop + endfacet + facet normal 0.70342 0.0755335 0.706749 + outer loop + vertex 1.69742 1.92353 2.47918 + vertex 1.69709 1.92824 2.47901 + vertex 1.69474 1.92567 2.48162 + endloop + endfacet + facet normal 0.712638 0.101536 0.694145 + outer loop + vertex 1.69513 1.92078 2.48193 + vertex 1.69742 1.92353 2.47918 + vertex 1.69474 1.92567 2.48162 + endloop + endfacet + facet normal 0.630854 0.0998344 0.769452 + outer loop + vertex 1.69474 1.92567 2.48162 + vertex 1.69227 1.92295 2.48399 + vertex 1.69513 1.92078 2.48193 + endloop + endfacet + facet normal 0.609018 0.130917 0.782277 + outer loop + vertex 1.69147 1.92839 2.48371 + vertex 1.69227 1.92295 2.48399 + vertex 1.69474 1.92567 2.48162 + endloop + endfacet + facet normal 0.680754 0.0843254 0.727642 + outer loop + vertex 1.69709 1.92824 2.47901 + vertex 1.69687 1.93285 2.47868 + vertex 1.69452 1.9304 2.48116 + endloop + endfacet + facet normal 0.687901 0.101793 0.718631 + outer loop + vertex 1.69474 1.92567 2.48162 + vertex 1.69709 1.92824 2.47901 + vertex 1.69452 1.9304 2.48116 + endloop + endfacet + facet normal 0.596213 0.10507 0.795921 + outer loop + vertex 1.69452 1.9304 2.48116 + vertex 1.69147 1.92839 2.48371 + vertex 1.69474 1.92567 2.48162 + endloop + endfacet + facet normal 0.593257 0.111311 0.79728 + outer loop + vertex 1.69213 1.93275 2.48261 + vertex 1.69147 1.92839 2.48371 + vertex 1.69452 1.9304 2.48116 + endloop + endfacet + facet normal 0.655174 0.0909111 0.749988 + outer loop + vertex 1.69687 1.93285 2.47868 + vertex 1.69657 1.93765 2.47835 + vertex 1.69425 1.93495 2.48072 + endloop + endfacet + facet normal 0.66395 0.112177 0.739315 + outer loop + vertex 1.69452 1.9304 2.48116 + vertex 1.69687 1.93285 2.47868 + vertex 1.69425 1.93495 2.48072 + endloop + endfacet + facet normal 0.594593 0.113474 0.795979 + outer loop + vertex 1.69425 1.93495 2.48072 + vertex 1.69213 1.93275 2.48261 + vertex 1.69452 1.9304 2.48116 + endloop + endfacet + facet normal 0.567868 0.150621 0.809221 + outer loop + vertex 1.6911 1.9369 2.48256 + vertex 1.69213 1.93275 2.48261 + vertex 1.69425 1.93495 2.48072 + endloop + endfacet + facet normal 0.618758 0.0940821 0.779928 + outer loop + vertex 1.69657 1.93765 2.47835 + vertex 1.69598 1.94317 2.47816 + vertex 1.69361 1.93968 2.48046 + endloop + endfacet + facet normal 0.630554 0.126037 0.765844 + outer loop + vertex 1.69425 1.93495 2.48072 + vertex 1.69657 1.93765 2.47835 + vertex 1.69361 1.93968 2.48046 + endloop + endfacet + facet normal 0.556034 0.118937 0.822606 + outer loop + vertex 1.69361 1.93968 2.48046 + vertex 1.6911 1.9369 2.48256 + vertex 1.69425 1.93495 2.48072 + endloop + endfacet + facet normal 0.531485 0.149518 0.833767 + outer loop + vertex 1.69009 1.94203 2.48229 + vertex 1.6911 1.9369 2.48256 + vertex 1.69361 1.93968 2.48046 + endloop + endfacet + facet normal 0.590943 0.124336 0.797074 + outer loop + vertex 1.69289 1.94375 2.48036 + vertex 1.69361 1.93968 2.48046 + vertex 1.69598 1.94317 2.47816 + endloop + endfacet + facet normal 0.590974 0.124956 0.796954 + outer loop + vertex 1.69289 1.94375 2.48036 + vertex 1.69598 1.94317 2.47816 + vertex 1.69336 1.94803 2.47934 + endloop + endfacet + facet normal 0.563309 0.10454 0.819606 + outer loop + vertex 1.69336 1.94803 2.47934 + vertex 1.69598 1.94317 2.47816 + vertex 1.69659 1.94779 2.47715 + endloop + endfacet + facet normal 0.514915 0.112273 0.849857 + outer loop + vertex 1.69361 1.93968 2.48046 + vertex 1.69289 1.94375 2.48036 + vertex 1.69009 1.94203 2.48229 + endloop + endfacet + facet normal 0.563294 0.106136 0.819411 + outer loop + vertex 1.69659 1.94779 2.47715 + vertex 1.69542 1.95235 2.47736 + vertex 1.69336 1.94803 2.47934 + endloop + endfacet + facet normal 0.501342 0.150597 0.852042 + outer loop + vertex 1.69336 1.94803 2.47934 + vertex 1.69542 1.95235 2.47736 + vertex 1.69154 1.95324 2.47949 + endloop + endfacet + facet normal 0.590017 0.126505 0.797419 + outer loop + vertex 1.69789 1.954 2.47541 + vertex 1.69821 1.95749 2.47462 + vertex 1.69607 1.95617 2.47641 + endloop + endfacet + facet normal 0.573599 0.105989 0.81225 + outer loop + vertex 1.69607 1.95617 2.47641 + vertex 1.69542 1.95235 2.47736 + vertex 1.69789 1.954 2.47541 + endloop + endfacet + facet normal 0.490453 0.132339 0.861361 + outer loop + vertex 1.69607 1.95617 2.47641 + vertex 1.69317 1.95696 2.47794 + vertex 1.69542 1.95235 2.47736 + endloop + endfacet + facet normal 0.500006 0.137815 0.854986 + outer loop + vertex 1.69317 1.95696 2.47794 + vertex 1.69154 1.95324 2.47949 + vertex 1.69542 1.95235 2.47736 + endloop + endfacet + facet normal 0.553438 0.141769 0.820736 + outer loop + vertex 1.69821 1.95749 2.47462 + vertex 1.69812 1.96235 2.47383 + vertex 1.69525 1.95994 2.47619 + endloop + endfacet + facet normal 0.568836 0.170688 0.804544 + outer loop + vertex 1.69607 1.95617 2.47641 + vertex 1.69821 1.95749 2.47462 + vertex 1.69525 1.95994 2.47619 + endloop + endfacet + facet normal 0.493902 0.157154 0.855198 + outer loop + vertex 1.69525 1.95994 2.47619 + vertex 1.69317 1.95696 2.47794 + vertex 1.69607 1.95617 2.47641 + endloop + endfacet + facet normal 0.461462 0.186846 0.867261 + outer loop + vertex 1.69142 1.96174 2.47784 + vertex 1.69317 1.95696 2.47794 + vertex 1.69525 1.95994 2.47619 + endloop + endfacet + facet normal 0.515153 0.135047 0.846392 + outer loop + vertex 1.69812 1.96235 2.47383 + vertex 1.69668 1.9682 2.47378 + vertex 1.69414 1.96468 2.47589 + endloop + endfacet + facet normal 0.530622 0.176973 0.828927 + outer loop + vertex 1.69525 1.95994 2.47619 + vertex 1.69812 1.96235 2.47383 + vertex 1.69414 1.96468 2.47589 + endloop + endfacet + facet normal 0.453699 0.162064 0.876295 + outer loop + vertex 1.69414 1.96468 2.47589 + vertex 1.69142 1.96174 2.47784 + vertex 1.69525 1.95994 2.47619 + endloop + endfacet + facet normal 0.425418 0.193407 0.884089 + outer loop + vertex 1.69001 1.9669 2.47739 + vertex 1.69142 1.96174 2.47784 + vertex 1.69414 1.96468 2.47589 + endloop + endfacet + facet normal 0.478985 0.170036 0.861197 + outer loop + vertex 1.69308 1.96873 2.47567 + vertex 1.69414 1.96468 2.47589 + vertex 1.69668 1.9682 2.47378 + endloop + endfacet + facet normal 0.478733 0.163176 0.862664 + outer loop + vertex 1.69308 1.96873 2.47567 + vertex 1.69668 1.9682 2.47378 + vertex 1.69366 1.97296 2.47456 + endloop + endfacet + facet normal 0.455826 0.146121 0.877993 + outer loop + vertex 1.69366 1.97296 2.47456 + vertex 1.69668 1.9682 2.47378 + vertex 1.69724 1.97265 2.47275 + endloop + endfacet + facet normal 0.409671 0.153914 0.899155 + outer loop + vertex 1.69414 1.96468 2.47589 + vertex 1.69308 1.96873 2.47567 + vertex 1.69001 1.9669 2.47739 + endloop + endfacet + facet normal 0.455833 0.149081 0.877492 + outer loop + vertex 1.69724 1.97265 2.47275 + vertex 1.69611 1.97679 2.47263 + vertex 1.69366 1.97296 2.47456 + endloop + endfacet + facet normal 0.405294 0.189905 0.894244 + outer loop + vertex 1.69366 1.97296 2.47456 + vertex 1.69611 1.97679 2.47263 + vertex 1.69182 1.97867 2.47418 + endloop + endfacet + facet normal 0.39655 0.162317 0.903549 + outer loop + vertex 1.69611 1.97679 2.47263 + vertex 1.69502 1.98184 2.4722 + vertex 1.69182 1.97867 2.47418 + endloop + endfacet + facet normal 0.373192 0.188858 0.908328 + outer loop + vertex 1.69182 1.97867 2.47418 + vertex 1.69502 1.98184 2.4722 + vertex 1.69182 1.98244 2.47339 + endloop + endfacet + facet normal 0.440825 0.191315 0.876967 + outer loop + vertex 1.69798 1.98357 2.47044 + vertex 1.69835 1.9877 2.46935 + vertex 1.69567 1.98574 2.47113 + endloop + endfacet + facet normal 0.427367 0.173738 0.887227 + outer loop + vertex 1.69567 1.98574 2.47113 + vertex 1.69502 1.98184 2.4722 + vertex 1.69798 1.98357 2.47044 + endloop + endfacet + facet normal 0.353631 0.193652 0.91512 + outer loop + vertex 1.69567 1.98574 2.47113 + vertex 1.69191 1.98602 2.47252 + vertex 1.69502 1.98184 2.4722 + endloop + endfacet + facet normal 0.375164 0.21062 0.902713 + outer loop + vertex 1.69191 1.98602 2.47252 + vertex 1.69182 1.98244 2.47339 + vertex 1.69502 1.98184 2.4722 + endloop + endfacet + facet normal 0.406767 0.192163 0.893092 + outer loop + vertex 1.69835 1.9877 2.46935 + vertex 1.69609 1.99292 2.46926 + vertex 1.69422 1.98955 2.47083 + endloop + endfacet + facet normal 0.417344 0.226285 0.880124 + outer loop + vertex 1.69567 1.98574 2.47113 + vertex 1.69835 1.9877 2.46935 + vertex 1.69422 1.98955 2.47083 + endloop + endfacet + facet normal 0.353572 0.204636 0.912749 + outer loop + vertex 1.69422 1.98955 2.47083 + vertex 1.69191 1.98602 2.47252 + vertex 1.69567 1.98574 2.47113 + endloop + endfacet + facet normal 0.326252 0.225151 0.918078 + outer loop + vertex 1.68981 1.99138 2.47195 + vertex 1.69191 1.98602 2.47252 + vertex 1.69422 1.98955 2.47083 + endloop + endfacet + facet normal 0.36473 0.22073 0.904572 + outer loop + vertex 1.69263 1.9935 2.47051 + vertex 1.69422 1.98955 2.47083 + vertex 1.69609 1.99292 2.46926 + endloop + endfacet + facet normal 0.364948 0.223901 0.903704 + outer loop + vertex 1.69263 1.9935 2.47051 + vertex 1.69609 1.99292 2.46926 + vertex 1.6926 1.99811 2.46938 + endloop + endfacet + facet normal 0.362244 0.222046 0.905248 + outer loop + vertex 1.6926 1.99811 2.46938 + vertex 1.69609 1.99292 2.46926 + vertex 1.6976 1.99669 2.46773 + endloop + endfacet + facet normal 0.319364 0.20411 0.92539 + outer loop + vertex 1.69422 1.98955 2.47083 + vertex 1.69263 1.9935 2.47051 + vertex 1.68981 1.99138 2.47195 + endloop + endfacet + facet normal 0.357957 0.19851 0.912393 + outer loop + vertex 1.6976 1.99669 2.46773 + vertex 1.69549 2.00181 2.46744 + vertex 1.6926 1.99811 2.46938 + endloop + endfacet + facet normal 0.304697 0.41555 0.857017 + outer loop + vertex 1.69694 2.06724 2.44884 + vertex 1.69632 2.07088 2.44729 + vertex 1.6927 2.06828 2.44984 + endloop + endfacet + facet normal 0.306291 0.413668 0.857359 + outer loop + vertex 1.6927 2.06828 2.44984 + vertex 1.69632 2.07088 2.44729 + vertex 1.69117 2.07355 2.44785 + endloop + endfacet + facet normal 0.3515 0.606016 0.713578 + outer loop + vertex 1.69418 2.07497 2.44571 + vertex 1.69827 2.07425 2.44431 + vertex 1.69595 2.07693 2.44318 + endloop + endfacet + facet normal 0.390138 0.576638 0.717831 + outer loop + vertex 1.69335 2.07701 2.44453 + vertex 1.69418 2.07497 2.44571 + vertex 1.69595 2.07693 2.44318 + endloop + endfacet + facet normal 0.339277 0.488506 0.803899 + outer loop + vertex 1.69632 2.07088 2.44729 + vertex 1.69418 2.07497 2.44571 + vertex 1.69117 2.07355 2.44785 + endloop + endfacet + facet normal 0.358706 0.494071 0.791975 + outer loop + vertex 1.69827 2.07425 2.44431 + vertex 1.69418 2.07497 2.44571 + vertex 1.69632 2.07088 2.44729 + endloop + endfacet + facet normal 0.33861 0.764535 0.54848 + outer loop + vertex 1.69277 2.07911 2.44262 + vertex 1.69766 2.07899 2.43977 + vertex 1.69515 2.08106 2.43843 + endloop + endfacet + facet normal 0.379825 0.736966 0.559119 + outer loop + vertex 1.69153 2.08142 2.44041 + vertex 1.69277 2.07911 2.44262 + vertex 1.69515 2.08106 2.43843 + endloop + endfacet + facet normal 0.353374 0.681484 0.640864 + outer loop + vertex 1.69595 2.07693 2.44318 + vertex 1.69277 2.07911 2.44262 + vertex 1.69335 2.07701 2.44453 + endloop + endfacet + facet normal 0.372134 0.700632 0.608795 + outer loop + vertex 1.69766 2.07899 2.43977 + vertex 1.69277 2.07911 2.44262 + vertex 1.69595 2.07693 2.44318 + endloop + endfacet + facet normal -0.0204789 -0.100391 0.994737 + outer loop + vertex 1.7 2.08668 2.435 + vertex 1.695 2.0877 2.435 + vertex 1.69756 2.08311 2.43459 + endloop + endfacet + facet normal 0.463588 0.180612 0.867448 + outer loop + vertex 1.69756 2.08311 2.43459 + vertex 1.695 2.0877 2.435 + vertex 1.69242 2.08337 2.43728 + endloop + endfacet + facet normal 0.381976 0.732146 0.563966 + outer loop + vertex 1.69515 2.08106 2.43843 + vertex 1.69242 2.08337 2.43728 + vertex 1.69153 2.08142 2.44041 + endloop + endfacet + facet normal 0.352203 0.716218 0.602482 + outer loop + vertex 1.69756 2.08311 2.43459 + vertex 1.69242 2.08337 2.43728 + vertex 1.69515 2.08106 2.43843 + endloop + endfacet + facet normal 0.547647 0.685899 0.479192 + outer loop + vertex 1.69619 2.09 2.43 + vertex 1.695 2.09095 2.43 + vertex 1.695 2.09 2.43136 + endloop + endfacet + facet normal 0.254934 -0.61047 0.74989 + outer loop + vertex 1.705 0.947617 2.43 + vertex 1.7025 0.947616 2.43085 + vertex 1.7 0.945529 2.43 + endloop + endfacet + facet normal 0.561074 -0.781874 0.271788 + outer loop + vertex 1.7025 0.947616 2.43085 + vertex 1.7 0.947267 2.435 + vertex 1.7 0.945529 2.43 + endloop + endfacet + facet normal 0.686061 0.563627 0.460049 + outer loop + vertex 1.7025 0.947616 2.43085 + vertex 1.6994 0.948412 2.43449 + vertex 1.7 0.947267 2.435 + endloop + endfacet + facet normal 0.427539 -0.736235 0.524565 + outer loop + vertex 1.70279 0.94902 2.43258 + vertex 1.6994 0.948412 2.43449 + vertex 1.7025 0.947616 2.43085 + endloop + endfacet + facet normal 0.407168 -0.780524 0.474337 + outer loop + vertex 1.6994 0.948412 2.43449 + vertex 1.70279 0.94902 2.43258 + vertex 1.70145 0.951077 2.43711 + endloop + endfacet + facet normal 0.363716 -0.780553 0.508378 + outer loop + vertex 1.69618 0.949445 2.43838 + vertex 1.6994 0.948412 2.43449 + vertex 1.70145 0.951077 2.43711 + endloop + endfacet + facet normal 0.282376 -0.777578 0.561815 + outer loop + vertex 1.70078 0.954346 2.44198 + vertex 1.70145 0.951077 2.43711 + vertex 1.70404 0.953837 2.43963 + endloop + endfacet + facet normal 0.376101 -0.744053 0.552207 + outer loop + vertex 1.70078 0.954346 2.44198 + vertex 1.69626 0.952059 2.44198 + vertex 1.70145 0.951077 2.43711 + endloop + endfacet + facet normal 0.36456 -0.756861 0.542456 + outer loop + vertex 1.69626 0.952059 2.44198 + vertex 1.69618 0.949445 2.43838 + vertex 1.70145 0.951077 2.43711 + endloop + endfacet + facet normal 0.358466 -0.709131 0.607154 + outer loop + vertex 1.70078 0.954346 2.44198 + vertex 1.69746 0.954376 2.44397 + vertex 1.69626 0.952059 2.44198 + endloop + endfacet + facet normal 0.331031 -0.714874 0.615933 + outer loop + vertex 1.70404 0.953837 2.43963 + vertex 1.70356 0.955458 2.44177 + vertex 1.70078 0.954346 2.44198 + endloop + endfacet + facet normal 0.370379 -0.594886 0.713393 + outer loop + vertex 1.69746 0.954376 2.44397 + vertex 1.69954 0.956802 2.44491 + vertex 1.69647 0.955801 2.44567 + endloop + endfacet + facet normal 0.403736 -0.610922 0.681008 + outer loop + vertex 1.70078 0.954346 2.44198 + vertex 1.69954 0.956802 2.44491 + vertex 1.69746 0.954376 2.44397 + endloop + endfacet + facet normal 0.379585 -0.624725 0.682374 + outer loop + vertex 1.70078 0.954346 2.44198 + vertex 1.70404 0.958329 2.44381 + vertex 1.69954 0.956802 2.44491 + endloop + endfacet + facet normal 0.289685 -0.585569 0.757094 + outer loop + vertex 1.70078 0.954346 2.44198 + vertex 1.70356 0.955458 2.44177 + vertex 1.70404 0.958329 2.44381 + endloop + endfacet + facet normal 0.356729 -0.491423 0.794511 + outer loop + vertex 1.69954 0.956802 2.44491 + vertex 1.69764 0.959201 2.44725 + vertex 1.69647 0.955801 2.44567 + endloop + endfacet + facet normal 0.367101 -0.527387 0.766224 + outer loop + vertex 1.70404 0.958329 2.44381 + vertex 1.70161 0.959907 2.44606 + vertex 1.69954 0.956802 2.44491 + endloop + endfacet + facet normal 0.329121 -0.512205 0.7933 + outer loop + vertex 1.70161 0.959907 2.44606 + vertex 1.69764 0.959201 2.44725 + vertex 1.69954 0.956802 2.44491 + endloop + endfacet + facet normal 0.328218 -0.409893 0.851035 + outer loop + vertex 1.70161 0.959907 2.44606 + vertex 1.70262 0.963924 2.4476 + vertex 1.69764 0.959201 2.44725 + endloop + endfacet + facet normal 0.316303 -0.398059 0.861105 + outer loop + vertex 1.70262 0.963924 2.4476 + vertex 1.69769 0.964103 2.4495 + vertex 1.69764 0.959201 2.44725 + endloop + endfacet + facet normal 0.332874 -0.219958 0.916959 + outer loop + vertex 1.70137 0.993632 2.45685 + vertex 1.7026 0.998897 2.45766 + vertex 1.6975 0.993894 2.45832 + endloop + endfacet + facet normal 0.351627 -0.240669 0.904675 + outer loop + vertex 1.6975 0.993894 2.45832 + vertex 1.7026 0.998897 2.45766 + vertex 1.69769 0.998971 2.45959 + endloop + endfacet + facet normal 0.339541 -0.243852 0.908432 + outer loop + vertex 1.6984 1.00301 2.46041 + vertex 1.69562 1.00063 2.46081 + vertex 1.69769 0.998971 2.45959 + endloop + endfacet + facet normal 0.376356 -0.247204 0.892886 + outer loop + vertex 1.6984 1.00301 2.46041 + vertex 1.69769 0.998971 2.45959 + vertex 1.70236 1.00435 2.45911 + endloop + endfacet + facet normal 0.353137 -0.225675 0.907946 + outer loop + vertex 1.70236 1.00435 2.45911 + vertex 1.69769 0.998971 2.45959 + vertex 1.7026 0.998897 2.45766 + endloop + endfacet + facet normal 0.328724 -0.229961 0.916001 + outer loop + vertex 1.6984 1.00301 2.46041 + vertex 1.69594 1.0038 2.46149 + vertex 1.69562 1.00063 2.46081 + endloop + endfacet + facet normal 0.333116 -0.218098 0.917315 + outer loop + vertex 1.69994 1.00681 2.46076 + vertex 1.69594 1.0038 2.46149 + vertex 1.6984 1.00301 2.46041 + endloop + endfacet + facet normal 0.339492 -0.227716 0.912629 + outer loop + vertex 1.69727 1.00879 2.46224 + vertex 1.69594 1.0038 2.46149 + vertex 1.69994 1.00681 2.46076 + endloop + endfacet + facet normal 0.348024 -0.215959 0.912272 + outer loop + vertex 1.7013 1.01053 2.46112 + vertex 1.69727 1.00879 2.46224 + vertex 1.69994 1.00681 2.46076 + endloop + endfacet + facet normal 0.346665 -0.211865 0.913749 + outer loop + vertex 1.7013 1.01053 2.46112 + vertex 1.70114 1.01364 2.4619 + vertex 1.69727 1.00879 2.46224 + endloop + endfacet + facet normal 0.364136 -0.226551 0.903371 + outer loop + vertex 1.70114 1.01364 2.4619 + vertex 1.69733 1.0137 2.46345 + vertex 1.69727 1.00879 2.46224 + endloop + endfacet + facet normal 0.56598 -0.126449 0.814664 + outer loop + vertex 1.7018 1.04866 2.46896 + vertex 1.70263 1.05428 2.46926 + vertex 1.69961 1.05173 2.47096 + endloop + endfacet + facet normal 0.530991 -0.162428 0.831664 + outer loop + vertex 1.69884 1.04793 2.47071 + vertex 1.7018 1.04866 2.46896 + vertex 1.69961 1.05173 2.47096 + endloop + endfacet + facet normal 0.443655 -0.14816 0.883866 + outer loop + vertex 1.69961 1.05173 2.47096 + vertex 1.69635 1.04864 2.47208 + vertex 1.69884 1.04793 2.47071 + endloop + endfacet + facet normal 0.463555 -0.174715 0.868672 + outer loop + vertex 1.69661 1.05322 2.47286 + vertex 1.69635 1.04864 2.47208 + vertex 1.69961 1.05173 2.47096 + endloop + endfacet + facet normal 0.604604 -0.0938934 0.790973 + outer loop + vertex 1.70263 1.05428 2.46926 + vertex 1.70291 1.05936 2.46965 + vertex 1.70008 1.05661 2.47149 + endloop + endfacet + facet normal 0.574314 -0.141896 0.806244 + outer loop + vertex 1.69961 1.05173 2.47096 + vertex 1.70263 1.05428 2.46926 + vertex 1.70008 1.05661 2.47149 + endloop + endfacet + facet normal 0.479639 -0.139401 0.866322 + outer loop + vertex 1.70008 1.05661 2.47149 + vertex 1.69661 1.05322 2.47286 + vertex 1.69961 1.05173 2.47096 + endloop + endfacet + facet normal 0.498346 -0.16471 0.851188 + outer loop + vertex 1.69685 1.05862 2.47377 + vertex 1.69661 1.05322 2.47286 + vertex 1.70008 1.05661 2.47149 + endloop + endfacet + facet normal 0.651724 -0.0831045 0.75389 + outer loop + vertex 1.70291 1.05936 2.46965 + vertex 1.70288 1.06335 2.47011 + vertex 1.70062 1.06146 2.47186 + endloop + endfacet + facet normal 0.624999 -0.12897 0.769898 + outer loop + vertex 1.70008 1.05661 2.47149 + vertex 1.70291 1.05936 2.46965 + vertex 1.70062 1.06146 2.47186 + endloop + endfacet + facet normal 0.520084 -0.123131 0.845193 + outer loop + vertex 1.70062 1.06146 2.47186 + vertex 1.69685 1.05862 2.47377 + vertex 1.70008 1.05661 2.47149 + endloop + endfacet + facet normal 0.534592 -0.151628 0.831396 + outer loop + vertex 1.69854 1.06471 2.47379 + vertex 1.69685 1.05862 2.47377 + vertex 1.70062 1.06146 2.47186 + endloop + endfacet + facet normal 0.660855 -0.103917 0.743284 + outer loop + vertex 1.70288 1.06335 2.47011 + vertex 1.7015 1.06528 2.47161 + vertex 1.70062 1.06146 2.47186 + endloop + endfacet + facet normal 0.601541 -0.0867823 0.794114 + outer loop + vertex 1.7015 1.06528 2.47161 + vertex 1.69854 1.06471 2.47379 + vertex 1.70062 1.06146 2.47186 + endloop + endfacet + facet normal 0.601044 -0.0800041 0.795201 + outer loop + vertex 1.7015 1.06528 2.47161 + vertex 1.7012 1.06896 2.47221 + vertex 1.69854 1.06471 2.47379 + endloop + endfacet + facet normal 0.652579 -0.130372 0.746421 + outer loop + vertex 1.7012 1.06896 2.47221 + vertex 1.69856 1.06962 2.47463 + vertex 1.69854 1.06471 2.47379 + endloop + endfacet + facet normal 0.570191 -0.144809 0.808649 + outer loop + vertex 1.6982 1.07286 2.47547 + vertex 1.69632 1.07038 2.47634 + vertex 1.69856 1.06962 2.47463 + endloop + endfacet + facet normal 0.689842 -0.107352 0.715957 + outer loop + vertex 1.6982 1.07286 2.47547 + vertex 1.69856 1.06962 2.47463 + vertex 1.70079 1.07391 2.47312 + endloop + endfacet + facet normal 0.662603 -0.0832354 0.744332 + outer loop + vertex 1.70079 1.07391 2.47312 + vertex 1.69856 1.06962 2.47463 + vertex 1.7012 1.06896 2.47221 + endloop + endfacet + facet normal 0.549739 -0.123166 0.826207 + outer loop + vertex 1.6982 1.07286 2.47547 + vertex 1.69589 1.07363 2.47711 + vertex 1.69632 1.07038 2.47634 + endloop + endfacet + facet normal 0.71321 -0.0576539 0.698575 + outer loop + vertex 1.70079 1.07391 2.47312 + vertex 1.70127 1.07941 2.47309 + vertex 1.69868 1.07658 2.4755 + endloop + endfacet + facet normal 0.688138 -0.095821 0.719225 + outer loop + vertex 1.6982 1.07286 2.47547 + vertex 1.70079 1.07391 2.47312 + vertex 1.69868 1.07658 2.4755 + endloop + endfacet + facet normal 0.561859 -0.0802798 0.823329 + outer loop + vertex 1.69868 1.07658 2.4755 + vertex 1.69589 1.07363 2.47711 + vertex 1.6982 1.07286 2.47547 + endloop + endfacet + facet normal 0.591765 -0.123084 0.796659 + outer loop + vertex 1.69609 1.07828 2.47769 + vertex 1.69589 1.07363 2.47711 + vertex 1.69868 1.07658 2.4755 + endloop + endfacet + facet normal 0.739384 -0.042248 0.671958 + outer loop + vertex 1.70127 1.07941 2.47309 + vertex 1.70146 1.08451 2.4732 + vertex 1.69895 1.08142 2.47577 + endloop + endfacet + facet normal 0.723753 -0.0783516 0.685596 + outer loop + vertex 1.69868 1.07658 2.4755 + vertex 1.70127 1.07941 2.47309 + vertex 1.69895 1.08142 2.47577 + endloop + endfacet + facet normal 0.612725 -0.0778798 0.786449 + outer loop + vertex 1.69895 1.08142 2.47577 + vertex 1.69609 1.07828 2.47769 + vertex 1.69868 1.07658 2.4755 + endloop + endfacet + facet normal 0.635746 -0.112814 0.76361 + outer loop + vertex 1.69616 1.08365 2.47842 + vertex 1.69609 1.07828 2.47769 + vertex 1.69895 1.08142 2.47577 + endloop + endfacet + facet normal 0.77039 -0.0326364 0.636737 + outer loop + vertex 1.70146 1.08451 2.4732 + vertex 1.70152 1.08943 2.47338 + vertex 1.69919 1.08647 2.47605 + endloop + endfacet + facet normal 0.755084 -0.0719073 0.651673 + outer loop + vertex 1.69895 1.08142 2.47577 + vertex 1.70146 1.08451 2.4732 + vertex 1.69919 1.08647 2.47605 + endloop + endfacet + facet normal 0.655949 -0.0727887 0.751288 + outer loop + vertex 1.69919 1.08647 2.47605 + vertex 1.69616 1.08365 2.47842 + vertex 1.69895 1.08142 2.47577 + endloop + endfacet + facet normal 0.675505 -0.112749 0.728685 + outer loop + vertex 1.6969 1.08911 2.47858 + vertex 1.69616 1.08365 2.47842 + vertex 1.69919 1.08647 2.47605 + endloop + endfacet + facet normal 0.800241 -0.0163634 0.599455 + outer loop + vertex 1.70152 1.08943 2.47338 + vertex 1.70154 1.0944 2.47349 + vertex 1.6994 1.0915 2.47627 + endloop + endfacet + facet normal 0.783665 -0.059743 0.618304 + outer loop + vertex 1.69919 1.08647 2.47605 + vertex 1.70152 1.08943 2.47338 + vertex 1.6994 1.0915 2.47627 + endloop + endfacet + facet normal 0.708196 -0.0603386 0.703433 + outer loop + vertex 1.6994 1.0915 2.47627 + vertex 1.6969 1.08911 2.47858 + vertex 1.69919 1.08647 2.47605 + endloop + endfacet + facet normal 0.722713 -0.0934477 0.684802 + outer loop + vertex 1.69721 1.09413 2.47893 + vertex 1.6969 1.08911 2.47858 + vertex 1.6994 1.0915 2.47627 + endloop + endfacet + facet normal 0.827529 -0.00106441 0.561423 + outer loop + vertex 1.70154 1.0944 2.47349 + vertex 1.70165 1.09967 2.47334 + vertex 1.69956 1.09674 2.47641 + endloop + endfacet + facet normal 0.811677 -0.0409758 0.582668 + outer loop + vertex 1.6994 1.0915 2.47627 + vertex 1.70154 1.0944 2.47349 + vertex 1.69956 1.09674 2.47641 + endloop + endfacet + facet normal 0.752342 -0.0412007 0.657484 + outer loop + vertex 1.69956 1.09674 2.47641 + vertex 1.69721 1.09413 2.47893 + vertex 1.6994 1.0915 2.47627 + endloop + endfacet + facet normal 0.770321 -0.0814766 0.63243 + outer loop + vertex 1.69744 1.09915 2.4793 + vertex 1.69721 1.09413 2.47893 + vertex 1.69956 1.09674 2.47641 + endloop + endfacet + facet normal 0.844576 -0.0757135 0.530055 + outer loop + vertex 1.70165 1.09967 2.47334 + vertex 1.70235 1.1044 2.4729 + vertex 1.70009 1.10342 2.47635 + endloop + endfacet + facet normal 0.852439 -0.0635376 0.518951 + outer loop + vertex 1.69956 1.09674 2.47641 + vertex 1.70165 1.09967 2.47334 + vertex 1.70009 1.10342 2.47635 + endloop + endfacet + facet normal 0.782083 -0.0569324 0.620568 + outer loop + vertex 1.70009 1.10342 2.47635 + vertex 1.69744 1.09915 2.4793 + vertex 1.69956 1.09674 2.47641 + endloop + endfacet + facet normal 0.794952 -0.0780004 0.601638 + outer loop + vertex 1.69745 1.10322 2.47981 + vertex 1.69744 1.09915 2.4793 + vertex 1.70009 1.10342 2.47635 + endloop + endfacet + facet normal 0.44133 -0.755653 0.483959 + outer loop + vertex 1.70391 1.10736 2.47167 + vertex 1.705 1.11 2.47479 + vertex 1.70477 1.11 2.475 + endloop + endfacet + facet normal 0.89693 -0.428836 0.107781 + outer loop + vertex 1.70235 1.1044 2.4729 + vertex 1.70391 1.10736 2.47167 + vertex 1.70477 1.11 2.475 + endloop + endfacet + facet normal 0.789451 -0.483555 0.378076 + outer loop + vertex 1.70235 1.1044 2.4729 + vertex 1.70477 1.11 2.475 + vertex 1.70009 1.10342 2.47635 + endloop + endfacet + facet normal 0.207294 0.0533922 0.976821 + outer loop + vertex 1.70009 1.10342 2.47635 + vertex 1.70477 1.11 2.475 + vertex 1.70102 1.10936 2.47583 + endloop + endfacet + facet normal 0.783357 -0.0243003 0.621097 + outer loop + vertex 1.69745 1.10322 2.47981 + vertex 1.69832 1.10776 2.47889 + vertex 1.69611 1.10517 2.48158 + endloop + endfacet + facet normal 0.795633 -0.0299059 0.60504 + outer loop + vertex 1.69745 1.10322 2.47981 + vertex 1.70009 1.10342 2.47635 + vertex 1.69832 1.10776 2.47889 + endloop + endfacet + facet normal 0.76551 -0.0629058 0.640341 + outer loop + vertex 1.70009 1.10342 2.47635 + vertex 1.70102 1.10936 2.47583 + vertex 1.69832 1.10776 2.47889 + endloop + endfacet + facet normal 0.787819 -0.0344906 0.61494 + outer loop + vertex 1.69832 1.10776 2.47889 + vertex 1.69588 1.10906 2.4821 + vertex 1.69611 1.10517 2.48158 + endloop + endfacet + facet normal 0.210261 0.0361639 0.976976 + outer loop + vertex 1.70477 1.11 2.475 + vertex 1.70391 1.115 2.475 + vertex 1.70102 1.10936 2.47583 + endloop + endfacet + facet normal 0.380665 -0.0592192 0.922815 + outer loop + vertex 1.70391 1.115 2.475 + vertex 1.70038 1.11326 2.47635 + vertex 1.70102 1.10936 2.47583 + endloop + endfacet + facet normal 0.741675 0.0336763 0.669914 + outer loop + vertex 1.70102 1.10936 2.47583 + vertex 1.70038 1.11326 2.47635 + vertex 1.69832 1.10776 2.47889 + endloop + endfacet + facet normal 0.787705 -0.00844822 0.615995 + outer loop + vertex 1.70038 1.11326 2.47635 + vertex 1.69795 1.11316 2.47944 + vertex 1.69832 1.10776 2.47889 + endloop + endfacet + facet normal 0.793647 -0.00726488 0.608335 + outer loop + vertex 1.69795 1.11316 2.47944 + vertex 1.69588 1.10906 2.4821 + vertex 1.69832 1.10776 2.47889 + endloop + endfacet + facet normal 0.810231 -0.0306396 0.585309 + outer loop + vertex 1.69562 1.1142 2.48273 + vertex 1.69588 1.10906 2.4821 + vertex 1.69795 1.11316 2.47944 + endloop + endfacet + facet normal 0.339041 0.0386466 0.939978 + outer loop + vertex 1.70391 1.115 2.475 + vertex 1.70334 1.12 2.475 + vertex 1.70038 1.11326 2.47635 + endloop + endfacet + facet normal 0.42348 -0.00530632 0.90589 + outer loop + vertex 1.70334 1.12 2.475 + vertex 1.69998 1.11825 2.47656 + vertex 1.70038 1.11326 2.47635 + endloop + endfacet + facet normal 0.786552 0.0354333 0.616507 + outer loop + vertex 1.70038 1.11326 2.47635 + vertex 1.69998 1.11825 2.47656 + vertex 1.69795 1.11316 2.47944 + endloop + endfacet + facet normal 0.811774 0.00691694 0.58393 + outer loop + vertex 1.69998 1.11825 2.47656 + vertex 1.69777 1.11807 2.47964 + vertex 1.69795 1.11316 2.47944 + endloop + endfacet + facet normal 0.816297 0.00733661 0.577586 + outer loop + vertex 1.69777 1.11807 2.47964 + vertex 1.69562 1.1142 2.48273 + vertex 1.69795 1.11316 2.47944 + endloop + endfacet + facet normal 0.843826 -0.0422149 0.534954 + outer loop + vertex 1.69628 1.11872 2.48204 + vertex 1.69562 1.1142 2.48273 + vertex 1.69777 1.11807 2.47964 + endloop + endfacet + facet normal 0.420487 0.00168424 0.907297 + outer loop + vertex 1.70334 1.12 2.475 + vertex 1.70332 1.125 2.475 + vertex 1.69998 1.11825 2.47656 + endloop + endfacet + facet normal 0.454496 -0.0189867 0.890546 + outer loop + vertex 1.70332 1.125 2.475 + vertex 1.69936 1.12336 2.47699 + vertex 1.69998 1.11825 2.47656 + endloop + endfacet + facet normal 0.812705 0.101554 0.573758 + outer loop + vertex 1.69741 1.12147 2.48008 + vertex 1.69936 1.12336 2.47699 + vertex 1.6974 1.12518 2.47944 + endloop + endfacet + facet normal 0.840859 0.0190412 0.540919 + outer loop + vertex 1.69741 1.12147 2.48008 + vertex 1.69777 1.11807 2.47964 + vertex 1.69936 1.12336 2.47699 + endloop + endfacet + facet normal 0.809529 0.050417 0.584911 + outer loop + vertex 1.69777 1.11807 2.47964 + vertex 1.69998 1.11825 2.47656 + vertex 1.69936 1.12336 2.47699 + endloop + endfacet + facet normal 0.852362 0.022669 0.522461 + outer loop + vertex 1.69777 1.11807 2.47964 + vertex 1.69741 1.12147 2.48008 + vertex 1.69628 1.11872 2.48204 + endloop + endfacet + facet normal 0.449791 -0.00449329 0.893123 + outer loop + vertex 1.70332 1.125 2.475 + vertex 1.70337 1.13 2.475 + vertex 1.69936 1.12336 2.47699 + endloop + endfacet + facet normal 0.33803 0.0765083 0.93802 + outer loop + vertex 1.70337 1.13 2.475 + vertex 1.6988 1.12811 2.4768 + vertex 1.69936 1.12336 2.47699 + endloop + endfacet + facet normal 0.816567 0.117195 0.565229 + outer loop + vertex 1.6988 1.12811 2.4768 + vertex 1.6974 1.12518 2.47944 + vertex 1.69936 1.12336 2.47699 + endloop + endfacet + facet normal 0.836998 0.0851231 0.540545 + outer loop + vertex 1.69717 1.12982 2.47907 + vertex 1.6974 1.12518 2.47944 + vertex 1.6988 1.12811 2.4768 + endloop + endfacet + facet normal 0.784397 0.531868 -0.319121 + outer loop + vertex 1.7 1.135 2.47505 + vertex 1.70337 1.13 2.475 + vertex 1.7 1.13497 2.475 + endloop + endfacet + facet normal 0.496919 0.326867 0.803884 + outer loop + vertex 1.7 1.135 2.47505 + vertex 1.6987 1.13366 2.4764 + vertex 1.70337 1.13 2.475 + endloop + endfacet + facet normal 0.33884 0.0744346 0.937895 + outer loop + vertex 1.6987 1.13366 2.4764 + vertex 1.6988 1.12811 2.4768 + vertex 1.70337 1.13 2.475 + endloop + endfacet + facet normal 0.828769 0.055759 0.556806 + outer loop + vertex 1.6987 1.13366 2.4764 + vertex 1.69717 1.12982 2.47907 + vertex 1.6988 1.12811 2.4768 + endloop + endfacet + facet normal 0.848254 0.0284778 0.528824 + outer loop + vertex 1.69701 1.13488 2.47904 + vertex 1.69717 1.12982 2.47907 + vertex 1.6987 1.13366 2.4764 + endloop + endfacet + facet normal 0.819151 -0.308506 0.483545 + outer loop + vertex 1.7 1.14 2.47824 + vertex 1.6987 1.13366 2.4764 + vertex 1.7 1.135 2.47505 + endloop + endfacet + facet normal -0.396154 -0.180942 0.900179 + outer loop + vertex 1.69811 1.13947 2.4773 + vertex 1.6987 1.13366 2.4764 + vertex 1.7 1.14 2.47824 + endloop + endfacet + facet normal 0.843266 0.00271677 0.53749 + outer loop + vertex 1.69811 1.13947 2.4773 + vertex 1.69701 1.13488 2.47904 + vertex 1.6987 1.13366 2.4764 + endloop + endfacet + facet normal 0.848535 -0.00169841 0.529136 + outer loop + vertex 1.69693 1.14 2.47918 + vertex 1.69701 1.13488 2.47904 + vertex 1.69811 1.13947 2.4773 + endloop + endfacet + facet normal -0.438799 -0.0251419 0.898234 + outer loop + vertex 1.7 1.145 2.47838 + vertex 1.69811 1.13947 2.4773 + vertex 1.7 1.14 2.47824 + endloop + endfacet + facet normal -0.373166 -0.0530782 0.926245 + outer loop + vertex 1.69804 1.14451 2.47756 + vertex 1.69811 1.13947 2.4773 + vertex 1.7 1.145 2.47838 + endloop + endfacet + facet normal 0.846586 -0.016143 0.532008 + outer loop + vertex 1.69804 1.14451 2.47756 + vertex 1.69693 1.14 2.47918 + vertex 1.69811 1.13947 2.4773 + endloop + endfacet + facet normal 0.731249 0.0649403 0.679012 + outer loop + vertex 1.6967 1.14507 2.47895 + vertex 1.69693 1.14 2.47918 + vertex 1.69804 1.14451 2.47756 + endloop + endfacet + facet normal -0.384559 -0.00184871 0.923099 + outer loop + vertex 1.7 1.15 2.47839 + vertex 1.69804 1.14451 2.47756 + vertex 1.7 1.145 2.47838 + endloop + endfacet + facet normal -0.376956 -0.00503711 0.926217 + outer loop + vertex 1.69785 1.14904 2.47751 + vertex 1.69804 1.14451 2.47756 + vertex 1.7 1.15 2.47839 + endloop + endfacet + facet normal 0.727017 0.038513 0.685539 + outer loop + vertex 1.69785 1.14904 2.47751 + vertex 1.6967 1.14507 2.47895 + vertex 1.69804 1.14451 2.47756 + endloop + endfacet + facet normal 0.495074 0.166196 0.852807 + outer loop + vertex 1.69632 1.14972 2.47826 + vertex 1.6967 1.14507 2.47895 + vertex 1.69785 1.14904 2.47751 + endloop + endfacet + facet normal -0.348974 -0.0747442 0.934147 + outer loop + vertex 1.7 1.155 2.47879 + vertex 1.69785 1.14904 2.47751 + vertex 1.7 1.15 2.47839 + endloop + endfacet + facet normal -0.426773 -0.0400936 0.90347 + outer loop + vertex 1.69765 1.15216 2.47755 + vertex 1.69785 1.14904 2.47751 + vertex 1.7 1.155 2.47879 + endloop + endfacet + facet normal 0.448765 0.0172312 0.893484 + outer loop + vertex 1.69765 1.15216 2.47755 + vertex 1.69632 1.14972 2.47826 + vertex 1.69785 1.14904 2.47751 + endloop + endfacet + facet normal 0.488806 -0.0106027 0.872328 + outer loop + vertex 1.69669 1.15295 2.47809 + vertex 1.69632 1.14972 2.47826 + vertex 1.69765 1.15216 2.47755 + endloop + endfacet + facet normal 0.125 -0.481492 0.867491 + outer loop + vertex 1.7 1.155 2.47879 + vertex 1.7 1.15718 2.48 + vertex 1.69765 1.15216 2.47755 + endloop + endfacet + facet normal 0.103574 -0.474648 0.87406 + outer loop + vertex 1.69765 1.15216 2.47755 + vertex 1.7 1.15718 2.48 + vertex 1.69669 1.15295 2.47809 + endloop + endfacet + facet normal -0.844765 0.143221 0.515615 + outer loop + vertex 1.69935 1.87575 2.47838 + vertex 1.7 1.87374 2.48 + vertex 1.7 1.875 2.47965 + endloop + endfacet + facet normal 0.961791 0.106153 -0.25237 + outer loop + vertex 1.69935 1.87575 2.47838 + vertex 1.7 1.875 2.48053 + vertex 1.7 1.87374 2.48 + endloop + endfacet + facet normal -0.865052 0.0888774 0.493746 + outer loop + vertex 1.7 1.88 2.47875 + vertex 1.69935 1.87575 2.47838 + vertex 1.7 1.875 2.47965 + endloop + endfacet + facet normal 0.706382 -0.0462906 -0.706315 + outer loop + vertex 1.70125 1.88 2.48 + vertex 1.69935 1.87575 2.47838 + vertex 1.7 1.88 2.47875 + endloop + endfacet + facet normal 0.894967 -0.262002 -0.361094 + outer loop + vertex 1.70125 1.88 2.48 + vertex 1.7 1.875 2.48053 + vertex 1.69935 1.87575 2.47838 + endloop + endfacet + facet normal 0.840094 -0.154904 0.519853 + outer loop + vertex 1.7 1.88 2.48202 + vertex 1.7 1.875 2.48053 + vertex 1.70125 1.88 2.48 + endloop + endfacet + facet normal 0.849914 -0.0323001 0.52593 + outer loop + vertex 1.70144 1.885 2.48 + vertex 1.7 1.88 2.48202 + vertex 1.70125 1.88 2.48 + endloop + endfacet + facet normal 0.0866792 0.351597 0.93213 + outer loop + vertex 1.69802 1.88466 2.48045 + vertex 1.7 1.88 2.48202 + vertex 1.70144 1.885 2.48 + endloop + endfacet + facet normal 0.130333 -0.00443111 0.99146 + outer loop + vertex 1.70161 1.89 2.48 + vertex 1.69802 1.88466 2.48045 + vertex 1.70144 1.885 2.48 + endloop + endfacet + facet normal 0.040345 0.0565209 0.997586 + outer loop + vertex 1.69782 1.8895 2.48018 + vertex 1.69802 1.88466 2.48045 + vertex 1.70161 1.89 2.48 + endloop + endfacet + facet normal 0.0478405 -9.5811e-05 0.998855 + outer loop + vertex 1.70162 1.895 2.48 + vertex 1.69782 1.8895 2.48018 + vertex 1.70161 1.89 2.48 + endloop + endfacet + facet normal -0.128828 0.121511 0.984194 + outer loop + vertex 1.69768 1.89405 2.4796 + vertex 1.69782 1.8895 2.48018 + vertex 1.70162 1.895 2.48 + endloop + endfacet + facet normal 0.686553 -0.566462 -0.455813 + outer loop + vertex 1.7 1.89706 2.475 + vertex 1.70162 1.895 2.48 + vertex 1.7 1.895 2.47756 + endloop + endfacet + facet normal 0.59653 -0.65538 -0.463281 + outer loop + vertex 1.7 1.89706 2.475 + vertex 1.70323 1.9 2.475 + vertex 1.70162 1.895 2.48 + endloop + endfacet + facet normal 0.0243683 0.702971 0.710801 + outer loop + vertex 1.70323 1.9 2.475 + vertex 1.69999 1.89856 2.47653 + vertex 1.70162 1.895 2.48 + endloop + endfacet + facet normal -0.225712 0.624435 0.747753 + outer loop + vertex 1.69999 1.89856 2.47653 + vertex 1.69768 1.89405 2.4796 + vertex 1.70162 1.895 2.48 + endloop + endfacet + facet normal 0.747077 0.0672461 0.661328 + outer loop + vertex 1.69768 1.89879 2.47912 + vertex 1.69768 1.89405 2.4796 + vertex 1.69999 1.89856 2.47653 + endloop + endfacet + facet normal 0.451262 -0.0676844 0.889821 + outer loop + vertex 1.70323 1.9 2.475 + vertex 1.70398 1.905 2.475 + vertex 1.69999 1.89856 2.47653 + endloop + endfacet + facet normal 0.258148 0.069578 0.963597 + outer loop + vertex 1.70398 1.905 2.475 + vertex 1.70016 1.90356 2.47613 + vertex 1.69999 1.89856 2.47653 + endloop + endfacet + facet normal 0.746792 0.0286784 0.664439 + outer loop + vertex 1.70016 1.90356 2.47613 + vertex 1.69768 1.89879 2.47912 + vertex 1.69999 1.89856 2.47653 + endloop + endfacet + facet normal 0.796995 -0.0358156 0.602923 + outer loop + vertex 1.69787 1.90385 2.47917 + vertex 1.69768 1.89879 2.47912 + vertex 1.70016 1.90356 2.47613 + endloop + endfacet + facet normal 0.282387 0.00168989 0.959299 + outer loop + vertex 1.70398 1.905 2.475 + vertex 1.70395 1.91 2.475 + vertex 1.70016 1.90356 2.47613 + endloop + endfacet + facet normal 0.366598 -0.0532476 0.928854 + outer loop + vertex 1.70395 1.91 2.475 + vertex 1.70048 1.90879 2.4763 + vertex 1.70016 1.90356 2.47613 + endloop + endfacet + facet normal 0.794115 -0.0686057 0.603883 + outer loop + vertex 1.70048 1.90879 2.4763 + vertex 1.69787 1.90385 2.47917 + vertex 1.70016 1.90356 2.47613 + endloop + endfacet + facet normal 0.770184 -0.0368018 0.636759 + outer loop + vertex 1.69788 1.90909 2.47946 + vertex 1.69787 1.90385 2.47917 + vertex 1.70048 1.90879 2.4763 + endloop + endfacet + facet normal 0.371054 -0.0690126 0.926043 + outer loop + vertex 1.70395 1.91 2.475 + vertex 1.70488 1.915 2.475 + vertex 1.70048 1.90879 2.4763 + endloop + endfacet + facet normal 0.363968 -0.0633202 0.929256 + outer loop + vertex 1.70488 1.915 2.475 + vertex 1.70053 1.91373 2.47662 + vertex 1.70048 1.90879 2.4763 + endloop + endfacet + facet normal 0.769176 -0.0492017 0.63714 + outer loop + vertex 1.70053 1.91373 2.47662 + vertex 1.69788 1.90909 2.47946 + vertex 1.70048 1.90879 2.4763 + endloop + endfacet + facet normal 0.731424 -0.000202058 0.681923 + outer loop + vertex 1.69772 1.91412 2.47963 + vertex 1.69788 1.90909 2.47946 + vertex 1.70053 1.91373 2.47662 + endloop + endfacet + facet normal 0.341537 0.0266435 0.939491 + outer loop + vertex 1.70488 1.915 2.475 + vertex 1.70449 1.92 2.475 + vertex 1.70053 1.91373 2.47662 + endloop + endfacet + facet normal 0.437469 -0.0445777 0.898128 + outer loop + vertex 1.70449 1.92 2.475 + vertex 1.69992 1.91742 2.4771 + vertex 1.70053 1.91373 2.47662 + endloop + endfacet + facet normal 0.733193 0.0338242 0.679179 + outer loop + vertex 1.69992 1.91742 2.4771 + vertex 1.69772 1.91412 2.47963 + vertex 1.70053 1.91373 2.47662 + endloop + endfacet + facet normal 0.727838 0.0414684 0.684494 + outer loop + vertex 1.69764 1.91884 2.47943 + vertex 1.69772 1.91412 2.47963 + vertex 1.69992 1.91742 2.4771 + endloop + endfacet + facet normal 0.091869 0.61018 0.786918 + outer loop + vertex 1.705 1.92241 2.475 + vertex 1.70199 1.92502 2.47332 + vertex 1.70052 1.92158 2.47617 + endloop + endfacet + facet normal 0.26101 -0.0552436 0.963754 + outer loop + vertex 1.705 1.92241 2.475 + vertex 1.70052 1.92158 2.47617 + vertex 1.70449 1.92 2.475 + endloop + endfacet + facet normal 0.336064 0.159571 0.928223 + outer loop + vertex 1.70449 1.92 2.475 + vertex 1.70052 1.92158 2.47617 + vertex 1.69992 1.91742 2.4771 + endloop + endfacet + facet normal 0.729433 0.0474573 0.682404 + outer loop + vertex 1.70052 1.92158 2.47617 + vertex 1.69764 1.91884 2.47943 + vertex 1.69992 1.91742 2.4771 + endloop + endfacet + facet normal 0.718185 0.0709668 0.692224 + outer loop + vertex 1.69742 1.92353 2.47918 + vertex 1.69764 1.91884 2.47943 + vertex 1.70052 1.92158 2.47617 + endloop + endfacet + facet normal 0.780853 0.0965818 0.617204 + outer loop + vertex 1.70199 1.92502 2.47332 + vertex 1.70141 1.92982 2.47331 + vertex 1.69949 1.92645 2.47627 + endloop + endfacet + facet normal 0.788295 0.154251 0.595649 + outer loop + vertex 1.70052 1.92158 2.47617 + vertex 1.70199 1.92502 2.47332 + vertex 1.69949 1.92645 2.47627 + endloop + endfacet + facet normal 0.734696 0.141507 0.663474 + outer loop + vertex 1.69949 1.92645 2.47627 + vertex 1.69742 1.92353 2.47918 + vertex 1.70052 1.92158 2.47617 + endloop + endfacet + facet normal 0.774477 0.0776608 0.627817 + outer loop + vertex 1.69709 1.92824 2.47901 + vertex 1.69742 1.92353 2.47918 + vertex 1.69949 1.92645 2.47627 + endloop + endfacet + facet normal 0.804021 0.0267142 0.594 + outer loop + vertex 1.70141 1.92982 2.47331 + vertex 1.70134 1.93437 2.4732 + vertex 1.69921 1.93111 2.47622 + endloop + endfacet + facet normal 0.808668 0.0532572 0.585849 + outer loop + vertex 1.69949 1.92645 2.47627 + vertex 1.70141 1.92982 2.47331 + vertex 1.69921 1.93111 2.47622 + endloop + endfacet + facet normal 0.767548 0.0513466 0.638931 + outer loop + vertex 1.69921 1.93111 2.47622 + vertex 1.69709 1.92824 2.47901 + vertex 1.69949 1.92645 2.47627 + endloop + endfacet + facet normal 0.749178 0.0826632 0.65719 + outer loop + vertex 1.69687 1.93285 2.47868 + vertex 1.69709 1.92824 2.47901 + vertex 1.69921 1.93111 2.47622 + endloop + endfacet + facet normal 0.783777 0.0298424 0.620324 + outer loop + vertex 1.70134 1.93437 2.4732 + vertex 1.70132 1.93893 2.473 + vertex 1.6991 1.93571 2.47596 + endloop + endfacet + facet normal 0.788598 0.0539173 0.612541 + outer loop + vertex 1.69921 1.93111 2.47622 + vertex 1.70134 1.93437 2.4732 + vertex 1.6991 1.93571 2.47596 + endloop + endfacet + facet normal 0.741417 0.0559719 0.668706 + outer loop + vertex 1.6991 1.93571 2.47596 + vertex 1.69687 1.93285 2.47868 + vertex 1.69921 1.93111 2.47622 + endloop + endfacet + facet normal 0.720221 0.0906324 0.687799 + outer loop + vertex 1.69657 1.93765 2.47835 + vertex 1.69687 1.93285 2.47868 + vertex 1.6991 1.93571 2.47596 + endloop + endfacet + facet normal 0.759127 0.0282807 0.650328 + outer loop + vertex 1.70132 1.93893 2.473 + vertex 1.70129 1.94369 2.47283 + vertex 1.69897 1.94059 2.47567 + endloop + endfacet + facet normal 0.767186 0.0582987 0.63877 + outer loop + vertex 1.6991 1.93571 2.47596 + vertex 1.70132 1.93893 2.473 + vertex 1.69897 1.94059 2.47567 + endloop + endfacet + facet normal 0.710093 0.0604245 0.70151 + outer loop + vertex 1.69897 1.94059 2.47567 + vertex 1.69657 1.93765 2.47835 + vertex 1.6991 1.93571 2.47596 + endloop + endfacet + facet normal 0.685103 0.0991321 0.72167 + outer loop + vertex 1.69598 1.94317 2.47816 + vertex 1.69657 1.93765 2.47835 + vertex 1.69897 1.94059 2.47567 + endloop + endfacet + facet normal 0.736758 0.0312534 0.675433 + outer loop + vertex 1.70129 1.94369 2.47283 + vertex 1.70114 1.94859 2.47277 + vertex 1.6989 1.94554 2.47535 + endloop + endfacet + facet normal 0.744115 0.0537946 0.665882 + outer loop + vertex 1.69897 1.94059 2.47567 + vertex 1.70129 1.94369 2.47283 + vertex 1.6989 1.94554 2.47535 + endloop + endfacet + facet normal 0.666982 0.0577262 0.742835 + outer loop + vertex 1.6989 1.94554 2.47535 + vertex 1.69598 1.94317 2.47816 + vertex 1.69897 1.94059 2.47567 + endloop + endfacet + facet normal 0.657732 0.076764 0.74933 + outer loop + vertex 1.69659 1.94779 2.47715 + vertex 1.69598 1.94317 2.47816 + vertex 1.6989 1.94554 2.47535 + endloop + endfacet + facet normal 0.706826 0.0529108 0.705406 + outer loop + vertex 1.70114 1.94859 2.47277 + vertex 1.70054 1.95383 2.47297 + vertex 1.69856 1.95027 2.47523 + endloop + endfacet + facet normal 0.71168 0.0696983 0.699038 + outer loop + vertex 1.6989 1.94554 2.47535 + vertex 1.70114 1.94859 2.47277 + vertex 1.69856 1.95027 2.47523 + endloop + endfacet + facet normal 0.652441 0.0668629 0.754884 + outer loop + vertex 1.69856 1.95027 2.47523 + vertex 1.69659 1.94779 2.47715 + vertex 1.6989 1.94554 2.47535 + endloop + endfacet + facet normal 0.611538 0.120214 0.782029 + outer loop + vertex 1.69542 1.95235 2.47736 + vertex 1.69659 1.94779 2.47715 + vertex 1.69856 1.95027 2.47523 + endloop + endfacet + facet normal 0.6759 0.0869595 0.731845 + outer loop + vertex 1.69789 1.954 2.47541 + vertex 1.69856 1.95027 2.47523 + vertex 1.70054 1.95383 2.47297 + endloop + endfacet + facet normal 0.675402 0.103497 0.730151 + outer loop + vertex 1.69789 1.954 2.47541 + vertex 1.70054 1.95383 2.47297 + vertex 1.69821 1.95749 2.47462 + endloop + endfacet + facet normal 0.655496 0.0814638 0.750792 + outer loop + vertex 1.69821 1.95749 2.47462 + vertex 1.70054 1.95383 2.47297 + vertex 1.70071 1.95862 2.47231 + endloop + endfacet + facet normal 0.591683 0.0683715 0.803266 + outer loop + vertex 1.69856 1.95027 2.47523 + vertex 1.69789 1.954 2.47541 + vertex 1.69542 1.95235 2.47736 + endloop + endfacet + facet normal 0.712948 0.093935 0.694896 + outer loop + vertex 1.7026 1.96001 2.47026 + vertex 1.7028 1.96341 2.4696 + vertex 1.70102 1.96192 2.47163 + endloop + endfacet + facet normal 0.704684 0.0798728 0.705011 + outer loop + vertex 1.70102 1.96192 2.47163 + vertex 1.70071 1.95862 2.47231 + vertex 1.7026 1.96001 2.47026 + endloop + endfacet + facet normal 0.612474 0.104443 0.783561 + outer loop + vertex 1.70102 1.96192 2.47163 + vertex 1.69812 1.96235 2.47383 + vertex 1.70071 1.95862 2.47231 + endloop + endfacet + facet normal 0.638607 0.133122 0.757931 + outer loop + vertex 1.69812 1.96235 2.47383 + vertex 1.69821 1.95749 2.47462 + vertex 1.70071 1.95862 2.47231 + endloop + endfacet + facet normal 0.674465 0.0871305 0.733148 + outer loop + vertex 1.7028 1.96341 2.4696 + vertex 1.70256 1.96792 2.46929 + vertex 1.70025 1.96562 2.47168 + endloop + endfacet + facet normal 0.69401 0.133891 0.707406 + outer loop + vertex 1.70102 1.96192 2.47163 + vertex 1.7028 1.96341 2.4696 + vertex 1.70025 1.96562 2.47168 + endloop + endfacet + facet normal 0.612769 0.116058 0.781693 + outer loop + vertex 1.70025 1.96562 2.47168 + vertex 1.69812 1.96235 2.47383 + vertex 1.70102 1.96192 2.47163 + endloop + endfacet + facet normal 0.579519 0.150465 0.800948 + outer loop + vertex 1.69668 1.9682 2.47378 + vertex 1.69812 1.96235 2.47383 + vertex 1.70025 1.96562 2.47168 + endloop + endfacet + facet normal 0.643831 0.080405 0.760931 + outer loop + vertex 1.70256 1.96792 2.46929 + vertex 1.70227 1.97273 2.46902 + vertex 1.69983 1.97029 2.47135 + endloop + endfacet + facet normal 0.65911 0.11321 0.743476 + outer loop + vertex 1.70025 1.96562 2.47168 + vertex 1.70256 1.96792 2.46929 + vertex 1.69983 1.97029 2.47135 + endloop + endfacet + facet normal 0.561445 0.109762 0.820203 + outer loop + vertex 1.69983 1.97029 2.47135 + vertex 1.69668 1.9682 2.47378 + vertex 1.70025 1.96562 2.47168 + endloop + endfacet + facet normal 0.555812 0.120862 0.822475 + outer loop + vertex 1.69724 1.97265 2.47275 + vertex 1.69668 1.9682 2.47378 + vertex 1.69983 1.97029 2.47135 + endloop + endfacet + facet normal 0.61037 0.088899 0.787112 + outer loop + vertex 1.70227 1.97273 2.46902 + vertex 1.7019 1.97764 2.46876 + vertex 1.69946 1.97492 2.47095 + endloop + endfacet + facet normal 0.622087 0.115097 0.774442 + outer loop + vertex 1.69983 1.97029 2.47135 + vertex 1.70227 1.97273 2.46902 + vertex 1.69946 1.97492 2.47095 + endloop + endfacet + facet normal 0.551559 0.1139 0.826323 + outer loop + vertex 1.69946 1.97492 2.47095 + vertex 1.69724 1.97265 2.47275 + vertex 1.69983 1.97029 2.47135 + endloop + endfacet + facet normal 0.513522 0.16378 0.842301 + outer loop + vertex 1.69611 1.97679 2.47263 + vertex 1.69724 1.97265 2.47275 + vertex 1.69946 1.97492 2.47095 + endloop + endfacet + facet normal 0.566025 0.114227 0.816436 + outer loop + vertex 1.7019 1.97764 2.46876 + vertex 1.7012 1.98303 2.46848 + vertex 1.69876 1.97961 2.47066 + endloop + endfacet + facet normal 0.574537 0.136993 0.806933 + outer loop + vertex 1.69946 1.97492 2.47095 + vertex 1.7019 1.97764 2.46876 + vertex 1.69876 1.97961 2.47066 + endloop + endfacet + facet normal 0.500898 0.129043 0.855832 + outer loop + vertex 1.69876 1.97961 2.47066 + vertex 1.69611 1.97679 2.47263 + vertex 1.69946 1.97492 2.47095 + endloop + endfacet + facet normal 0.46316 0.173741 0.869078 + outer loop + vertex 1.69502 1.98184 2.4722 + vertex 1.69611 1.97679 2.47263 + vertex 1.69876 1.97961 2.47066 + endloop + endfacet + facet normal 0.531043 0.150307 0.833907 + outer loop + vertex 1.69798 1.98357 2.47044 + vertex 1.69876 1.97961 2.47066 + vertex 1.7012 1.98303 2.46848 + endloop + endfacet + facet normal 0.531775 0.170598 0.829525 + outer loop + vertex 1.69798 1.98357 2.47044 + vertex 1.7012 1.98303 2.46848 + vertex 1.69835 1.9877 2.46935 + endloop + endfacet + facet normal 0.500284 0.146987 0.853294 + outer loop + vertex 1.69835 1.9877 2.46935 + vertex 1.7012 1.98303 2.46848 + vertex 1.70173 1.98745 2.46741 + endloop + endfacet + facet normal 0.447145 0.136632 0.883964 + outer loop + vertex 1.69876 1.97961 2.47066 + vertex 1.69798 1.98357 2.47044 + vertex 1.69502 1.98184 2.4722 + endloop + endfacet + facet normal 0.499942 0.162164 0.850741 + outer loop + vertex 1.70173 1.98745 2.46741 + vertex 1.70032 1.99191 2.46739 + vertex 1.69835 1.9877 2.46935 + endloop + endfacet + facet normal 0.435518 0.204371 0.876674 + outer loop + vertex 1.69835 1.9877 2.46935 + vertex 1.70032 1.99191 2.46739 + vertex 1.69609 1.99292 2.46926 + endloop + endfacet + facet normal 0.539277 0.183614 0.821868 + outer loop + vertex 1.70285 1.99354 2.4655 + vertex 1.70298 1.99719 2.4646 + vertex 1.70081 1.99572 2.46634 + endloop + endfacet + facet normal 0.522424 0.161985 0.837158 + outer loop + vertex 1.70081 1.99572 2.46634 + vertex 1.70032 1.99191 2.46739 + vertex 1.70285 1.99354 2.4655 + endloop + endfacet + facet normal 0.435081 0.185324 0.881113 + outer loop + vertex 1.70081 1.99572 2.46634 + vertex 1.6976 1.99669 2.46773 + vertex 1.70032 1.99191 2.46739 + endloop + endfacet + facet normal 0.433202 0.184173 0.882279 + outer loop + vertex 1.6976 1.99669 2.46773 + vertex 1.69609 1.99292 2.46926 + vertex 1.70032 1.99191 2.46739 + endloop + endfacet + facet normal 0.505695 0.183526 0.842965 + outer loop + vertex 1.70298 1.99719 2.4646 + vertex 1.70243 2.00271 2.46372 + vertex 1.69971 1.99961 2.46603 + endloop + endfacet + facet normal 0.521342 0.214807 0.825869 + outer loop + vertex 1.70081 1.99572 2.46634 + vertex 1.70298 1.99719 2.4646 + vertex 1.69971 1.99961 2.46603 + endloop + endfacet + facet normal 0.436734 0.194946 0.878214 + outer loop + vertex 1.69971 1.99961 2.46603 + vertex 1.6976 1.99669 2.46773 + vertex 1.70081 1.99572 2.46634 + endloop + endfacet + facet normal 0.409992 0.218473 0.885537 + outer loop + vertex 1.69549 2.00181 2.46744 + vertex 1.6976 1.99669 2.46773 + vertex 1.69971 1.99961 2.46603 + endloop + endfacet + facet normal 0.480194 0.212081 0.851138 + outer loop + vertex 1.69845 2.0036 2.46575 + vertex 1.69971 1.99961 2.46603 + vertex 1.70243 2.00271 2.46372 + endloop + endfacet + facet normal 0.479983 0.209296 0.851946 + outer loop + vertex 1.69845 2.0036 2.46575 + vertex 1.70243 2.00271 2.46372 + vertex 1.69857 2.00783 2.46464 + endloop + endfacet + facet normal 0.439018 0.173078 0.88165 + outer loop + vertex 1.69857 2.00783 2.46464 + vertex 1.70243 2.00271 2.46372 + vertex 1.70227 2.00764 2.46284 + endloop + endfacet + facet normal 0.398852 0.189599 0.897201 + outer loop + vertex 1.69971 1.99961 2.46603 + vertex 1.69845 2.0036 2.46575 + vertex 1.69549 2.00181 2.46744 + endloop + endfacet + facet normal 0.43835 0.189205 0.878664 + outer loop + vertex 1.70227 2.00764 2.46284 + vertex 1.70054 2.01219 2.46272 + vertex 1.69857 2.00783 2.46464 + endloop + endfacet + facet normal 0.37811 0.224896 0.898028 + outer loop + vertex 1.69857 2.00783 2.46464 + vertex 1.70054 2.01219 2.46272 + vertex 1.69605 2.01299 2.46441 + endloop + endfacet + facet normal 0.448818 0.198425 0.871315 + outer loop + vertex 1.70348 2.01381 2.46088 + vertex 1.70393 2.01797 2.4597 + vertex 1.70112 2.01618 2.46156 + endloop + endfacet + facet normal 0.442021 0.190116 0.876626 + outer loop + vertex 1.70112 2.01618 2.46156 + vertex 1.70054 2.01219 2.46272 + vertex 1.70348 2.01381 2.46088 + endloop + endfacet + facet normal 0.366014 0.209718 0.906671 + outer loop + vertex 1.70112 2.01618 2.46156 + vertex 1.69758 2.01686 2.46283 + vertex 1.70054 2.01219 2.46272 + endloop + endfacet + facet normal 0.377537 0.2172 0.900161 + outer loop + vertex 1.69758 2.01686 2.46283 + vertex 1.69605 2.01299 2.46441 + vertex 1.70054 2.01219 2.46272 + endloop + endfacet + facet normal 0.411251 0.193731 0.890697 + outer loop + vertex 1.70393 2.01797 2.4597 + vertex 1.70193 2.02375 2.45937 + vertex 1.69972 2.02006 2.4612 + endloop + endfacet + facet normal 0.426105 0.236132 0.873314 + outer loop + vertex 1.70112 2.01618 2.46156 + vertex 1.70393 2.01797 2.4597 + vertex 1.69972 2.02006 2.4612 + endloop + endfacet + facet normal 0.366756 0.21769 0.904489 + outer loop + vertex 1.69972 2.02006 2.4612 + vertex 1.69758 2.01686 2.46283 + vertex 1.70112 2.01618 2.46156 + endloop + endfacet + facet normal 0.334992 0.242019 0.910608 + outer loop + vertex 1.69515 2.02184 2.4624 + vertex 1.69758 2.01686 2.46283 + vertex 1.69972 2.02006 2.4612 + endloop + endfacet + facet normal 0.3609 0.230454 0.903683 + outer loop + vertex 1.6981 2.02392 2.46086 + vertex 1.69972 2.02006 2.4612 + vertex 1.70193 2.02375 2.45937 + endloop + endfacet + facet normal 0.360738 0.23395 0.902849 + outer loop + vertex 1.6981 2.02392 2.46086 + vertex 1.70193 2.02375 2.45937 + vertex 1.69807 2.02838 2.45972 + endloop + endfacet + facet normal 0.325809 0.203304 0.923318 + outer loop + vertex 1.69807 2.02838 2.45972 + vertex 1.70193 2.02375 2.45937 + vertex 1.70184 2.02746 2.45858 + endloop + endfacet + facet normal 0.3279 0.217955 0.919227 + outer loop + vertex 1.69972 2.02006 2.4612 + vertex 1.6981 2.02392 2.46086 + vertex 1.69515 2.02184 2.4624 + endloop + endfacet + facet normal 0.32953 0.227215 0.916397 + outer loop + vertex 1.70184 2.02746 2.45858 + vertex 1.70192 2.03102 2.45768 + vertex 1.69807 2.02838 2.45972 + endloop + endfacet + facet normal 0.326468 0.483971 0.811905 + outer loop + vertex 1.70358 2.06834 2.44595 + vertex 1.70428 2.07057 2.44434 + vertex 1.70092 2.07096 2.44546 + endloop + endfacet + facet normal 0.266597 0.432354 0.861392 + outer loop + vertex 1.70092 2.07096 2.44546 + vertex 1.70102 2.06636 2.44774 + vertex 1.70358 2.06834 2.44595 + endloop + endfacet + facet normal 0.329898 0.424713 0.843082 + outer loop + vertex 1.70092 2.07096 2.44546 + vertex 1.69632 2.07088 2.44729 + vertex 1.70102 2.06636 2.44774 + endloop + endfacet + facet normal 0.320492 0.415734 0.851146 + outer loop + vertex 1.69632 2.07088 2.44729 + vertex 1.69694 2.06724 2.44884 + vertex 1.70102 2.06636 2.44774 + endloop + endfacet + facet normal 0.346355 0.664251 0.662427 + outer loop + vertex 1.70326 2.0741 2.44208 + vertex 1.70291 2.07679 2.43956 + vertex 1.70007 2.07683 2.44101 + endloop + endfacet + facet normal 0.37816 0.618593 0.688722 + outer loop + vertex 1.70007 2.07683 2.44101 + vertex 1.69595 2.07693 2.44318 + vertex 1.69827 2.07425 2.44431 + endloop + endfacet + facet normal 0.326782 0.65053 0.685583 + outer loop + vertex 1.70326 2.0741 2.44208 + vertex 1.70007 2.07683 2.44101 + vertex 1.69827 2.07425 2.44431 + endloop + endfacet + facet normal 0.355212 0.549258 0.756399 + outer loop + vertex 1.70326 2.0741 2.44208 + vertex 1.69827 2.07425 2.44431 + vertex 1.70092 2.07096 2.44546 + endloop + endfacet + facet normal 0.317701 0.574819 0.754088 + outer loop + vertex 1.70326 2.0741 2.44208 + vertex 1.70092 2.07096 2.44546 + vertex 1.70428 2.07057 2.44434 + endloop + endfacet + facet normal 0.308385 0.524599 0.793533 + outer loop + vertex 1.70092 2.07096 2.44546 + vertex 1.69827 2.07425 2.44431 + vertex 1.69632 2.07088 2.44729 + endloop + endfacet + facet normal 0.343227 0.803364 0.486622 + outer loop + vertex 1.70299 2.07893 2.43639 + vertex 1.70113 2.08127 2.43384 + vertex 1.69892 2.08063 2.43647 + endloop + endfacet + facet normal 0.360087 0.773319 0.521839 + outer loop + vertex 1.69892 2.08063 2.43647 + vertex 1.69515 2.08106 2.43843 + vertex 1.69766 2.07899 2.43977 + endloop + endfacet + facet normal 0.336498 0.785751 0.519004 + outer loop + vertex 1.70299 2.07893 2.43639 + vertex 1.69892 2.08063 2.43647 + vertex 1.69766 2.07899 2.43977 + endloop + endfacet + facet normal 0.367188 0.736398 0.568234 + outer loop + vertex 1.70299 2.07893 2.43639 + vertex 1.69766 2.07899 2.43977 + vertex 1.70007 2.07683 2.44101 + endloop + endfacet + facet normal 0.286413 0.790243 0.541742 + outer loop + vertex 1.70299 2.07893 2.43639 + vertex 1.70007 2.07683 2.44101 + vertex 1.70291 2.07679 2.43956 + endloop + endfacet + facet normal 0.336383 0.722474 0.604051 + outer loop + vertex 1.70007 2.07683 2.44101 + vertex 1.69766 2.07899 2.43977 + vertex 1.69595 2.07693 2.44318 + endloop + endfacet + facet normal 0.0324662 0.289853 0.95652 + outer loop + vertex 1.705 2.087 2.43 + vertex 1.7 2.08756 2.43 + vertex 1.70248 2.08362 2.43111 + endloop + endfacet + facet normal 0.82974 0.549701 0.09675 + outer loop + vertex 1.70248 2.08362 2.43111 + vertex 1.7 2.08756 2.43 + vertex 1.7 2.08668 2.435 + endloop + endfacet + facet normal 0.467628 0.682558 0.561639 + outer loop + vertex 1.70113 2.08127 2.43384 + vertex 1.69756 2.08311 2.43459 + vertex 1.69892 2.08063 2.43647 + endloop + endfacet + facet normal 0.436182 0.564937 0.700422 + outer loop + vertex 1.70113 2.08127 2.43384 + vertex 1.70248 2.08362 2.43111 + vertex 1.69756 2.08311 2.43459 + endloop + endfacet + facet normal 0.545645 -0.454043 0.704355 + outer loop + vertex 1.70248 2.08362 2.43111 + vertex 1.7 2.08668 2.435 + vertex 1.69756 2.08311 2.43459 + endloop + endfacet + facet normal 0.397461 0.682859 0.612967 + outer loop + vertex 1.69892 2.08063 2.43647 + vertex 1.69756 2.08311 2.43459 + vertex 1.69515 2.08106 2.43843 + endloop + endfacet + facet normal -0.0983835 0.90847 0.406206 + outer loop + vertex 1.70551 0.948829 2.43028 + vertex 1.71 0.949441 2.43 + vertex 1.70904 0.949586 2.42944 + endloop + endfacet + facet normal -0.00185464 0.42849 0.903545 + outer loop + vertex 1.70551 0.948829 2.43028 + vertex 1.7025 0.947616 2.43085 + vertex 1.71 0.949441 2.43 + endloop + endfacet + facet normal 0.241377 -0.66166 0.709889 + outer loop + vertex 1.7025 0.947616 2.43085 + vertex 1.705 0.947617 2.43 + vertex 1.71 0.949441 2.43 + endloop + endfacet + facet normal 0.400401 -0.743734 0.535293 + outer loop + vertex 1.70551 0.948829 2.43028 + vertex 1.70279 0.94902 2.43258 + vertex 1.7025 0.947616 2.43085 + endloop + endfacet + facet normal 0.291608 -0.823687 0.486317 + outer loop + vertex 1.70904 0.949586 2.42944 + vertex 1.70702 0.95043 2.43209 + vertex 1.70551 0.948829 2.43028 + endloop + endfacet + facet normal 0.328786 -0.826232 0.457429 + outer loop + vertex 1.70279 0.94902 2.43258 + vertex 1.70551 0.948829 2.43028 + vertex 1.70702 0.95043 2.43209 + endloop + endfacet + facet normal 0.32807 -0.820056 0.468913 + outer loop + vertex 1.70279 0.94902 2.43258 + vertex 1.70702 0.95043 2.43209 + vertex 1.70145 0.951077 2.43711 + endloop + endfacet + facet normal 0.335722 -0.812592 0.476429 + outer loop + vertex 1.70145 0.951077 2.43711 + vertex 1.70702 0.95043 2.43209 + vertex 1.70662 0.952635 2.43613 + endloop + endfacet + facet normal 0.335857 -0.787172 0.517262 + outer loop + vertex 1.70662 0.952635 2.43613 + vertex 1.70404 0.953837 2.43963 + vertex 1.70145 0.951077 2.43711 + endloop + endfacet + facet normal 0.348722 -0.777463 0.523397 + outer loop + vertex 1.707 0.954693 2.43893 + vertex 1.70404 0.953837 2.43963 + vertex 1.70662 0.952635 2.43613 + endloop + endfacet + facet normal 0.349541 -0.690903 0.63283 + outer loop + vertex 1.70404 0.953837 2.43963 + vertex 1.707 0.954693 2.43893 + vertex 1.70593 0.956295 2.44127 + endloop + endfacet + facet normal 0.374969 -0.696444 0.611853 + outer loop + vertex 1.70356 0.955458 2.44177 + vertex 1.70404 0.953837 2.43963 + vertex 1.70593 0.956295 2.44127 + endloop + endfacet + facet normal 0.358935 -0.579201 0.73191 + outer loop + vertex 1.70593 0.956295 2.44127 + vertex 1.70404 0.958329 2.44381 + vertex 1.70356 0.955458 2.44177 + endloop + endfacet + facet normal 0.381839 -0.56106 0.734446 + outer loop + vertex 1.70862 0.959785 2.44254 + vertex 1.70404 0.958329 2.44381 + vertex 1.70593 0.956295 2.44127 + endloop + endfacet + facet normal 0.385967 -0.505798 0.77149 + outer loop + vertex 1.70461 0.962042 2.44596 + vertex 1.70161 0.959907 2.44606 + vertex 1.70404 0.958329 2.44381 + endloop + endfacet + facet normal 0.415318 -0.502597 0.758226 + outer loop + vertex 1.70461 0.962042 2.44596 + vertex 1.70404 0.958329 2.44381 + vertex 1.70843 0.963553 2.44487 + endloop + endfacet + facet normal 0.371824 -0.474174 0.798064 + outer loop + vertex 1.70843 0.963553 2.44487 + vertex 1.70404 0.958329 2.44381 + vertex 1.70862 0.959785 2.44254 + endloop + endfacet + facet normal 0.320087 -0.409154 0.854481 + outer loop + vertex 1.70461 0.962042 2.44596 + vertex 1.70262 0.963924 2.4476 + vertex 1.70161 0.959907 2.44606 + endloop + endfacet + facet normal 0.405321 -0.203258 0.891292 + outer loop + vertex 1.70385 1.01313 2.46055 + vertex 1.70114 1.01364 2.4619 + vertex 1.7013 1.01053 2.46112 + endloop + endfacet + facet normal 0.411339 -0.1781 0.893913 + outer loop + vertex 1.70479 1.01688 2.46087 + vertex 1.70114 1.01364 2.4619 + vertex 1.70385 1.01313 2.46055 + endloop + endfacet + facet normal 0.431229 -0.205311 0.878572 + outer loop + vertex 1.70164 1.01819 2.46272 + vertex 1.70114 1.01364 2.4619 + vertex 1.70479 1.01688 2.46087 + endloop + endfacet + facet normal 0.443417 -0.176226 0.87882 + outer loop + vertex 1.70548 1.02153 2.46145 + vertex 1.70164 1.01819 2.46272 + vertex 1.70479 1.01688 2.46087 + endloop + endfacet + facet normal 0.457365 -0.196648 0.867264 + outer loop + vertex 1.70251 1.02409 2.46359 + vertex 1.70164 1.01819 2.46272 + vertex 1.70548 1.02153 2.46145 + endloop + endfacet + facet normal 0.482691 -0.161716 0.860731 + outer loop + vertex 1.70633 1.02532 2.46168 + vertex 1.70251 1.02409 2.46359 + vertex 1.70548 1.02153 2.46145 + endloop + endfacet + facet normal 0.478589 -0.139481 0.86689 + outer loop + vertex 1.70633 1.02532 2.46168 + vertex 1.70609 1.02871 2.46236 + vertex 1.70251 1.02409 2.46359 + endloop + endfacet + facet normal 0.520344 -0.180381 0.834688 + outer loop + vertex 1.70609 1.02871 2.46236 + vertex 1.70332 1.02991 2.46435 + vertex 1.70251 1.02409 2.46359 + endloop + endfacet + facet normal 0.545715 -0.11444 0.83012 + outer loop + vertex 1.70609 1.02871 2.46236 + vertex 1.70638 1.03343 2.46282 + vertex 1.70332 1.02991 2.46435 + endloop + endfacet + facet normal 0.583335 -0.16199 0.795915 + outer loop + vertex 1.70332 1.02991 2.46435 + vertex 1.70638 1.03343 2.46282 + vertex 1.70373 1.03453 2.46499 + endloop + endfacet + facet normal 0.522855 -0.170485 0.835199 + outer loop + vertex 1.70352 1.03783 2.46579 + vertex 1.70148 1.03529 2.46655 + vertex 1.70373 1.03453 2.46499 + endloop + endfacet + facet normal 0.634419 -0.144677 0.759329 + outer loop + vertex 1.70352 1.03783 2.46579 + vertex 1.70373 1.03453 2.46499 + vertex 1.70627 1.03872 2.46367 + endloop + endfacet + facet normal 0.600095 -0.113672 0.791811 + outer loop + vertex 1.70627 1.03872 2.46367 + vertex 1.70373 1.03453 2.46499 + vertex 1.70638 1.03343 2.46282 + endloop + endfacet + facet normal 0.515353 -0.162626 0.841406 + outer loop + vertex 1.70352 1.03783 2.46579 + vertex 1.70115 1.03853 2.46738 + vertex 1.70148 1.03529 2.46655 + endloop + endfacet + facet normal 0.673512 -0.0911927 0.733529 + outer loop + vertex 1.70627 1.03872 2.46367 + vertex 1.7069 1.04439 2.46379 + vertex 1.70416 1.04158 2.46595 + endloop + endfacet + facet normal 0.634087 -0.141611 0.760184 + outer loop + vertex 1.70352 1.03783 2.46579 + vertex 1.70627 1.03872 2.46367 + vertex 1.70416 1.04158 2.46595 + endloop + endfacet + facet normal 0.525798 -0.126423 0.841162 + outer loop + vertex 1.70416 1.04158 2.46595 + vertex 1.70115 1.03853 2.46738 + vertex 1.70352 1.03783 2.46579 + endloop + endfacet + facet normal 0.555444 -0.168061 0.814394 + outer loop + vertex 1.70153 1.04322 2.46809 + vertex 1.70115 1.03853 2.46738 + vertex 1.70416 1.04158 2.46595 + endloop + endfacet + facet normal 0.719032 -0.0654507 0.691888 + outer loop + vertex 1.7069 1.04439 2.46379 + vertex 1.70724 1.04966 2.46394 + vertex 1.70461 1.04651 2.46637 + endloop + endfacet + facet normal 0.690032 -0.122899 0.713268 + outer loop + vertex 1.70416 1.04158 2.46595 + vertex 1.7069 1.04439 2.46379 + vertex 1.70461 1.04651 2.46637 + endloop + endfacet + facet normal 0.578532 -0.120836 0.806659 + outer loop + vertex 1.70461 1.04651 2.46637 + vertex 1.70153 1.04322 2.46809 + vertex 1.70416 1.04158 2.46595 + endloop + endfacet + facet normal 0.602581 -0.1557 0.782722 + outer loop + vertex 1.7018 1.04866 2.46896 + vertex 1.70153 1.04322 2.46809 + vertex 1.70461 1.04651 2.46637 + endloop + endfacet + facet normal 0.765837 -0.0279984 0.642424 + outer loop + vertex 1.70724 1.04966 2.46394 + vertex 1.70735 1.05489 2.46403 + vertex 1.70496 1.05176 2.46674 + endloop + endfacet + facet normal 0.736155 -0.0968041 0.669854 + outer loop + vertex 1.70461 1.04651 2.46637 + vertex 1.70724 1.04966 2.46394 + vertex 1.70496 1.05176 2.46674 + endloop + endfacet + facet normal 0.633689 -0.0966375 0.767528 + outer loop + vertex 1.70496 1.05176 2.46674 + vertex 1.7018 1.04866 2.46896 + vertex 1.70461 1.04651 2.46637 + endloop + endfacet + facet normal 0.655139 -0.135959 0.743174 + outer loop + vertex 1.70263 1.05428 2.46926 + vertex 1.7018 1.04866 2.46896 + vertex 1.70496 1.05176 2.46674 + endloop + endfacet + facet normal 0.80882 0.0107916 0.587957 + outer loop + vertex 1.70735 1.05489 2.46403 + vertex 1.70727 1.06019 2.46405 + vertex 1.70517 1.05713 2.46699 + endloop + endfacet + facet normal 0.781747 -0.0589125 0.620806 + outer loop + vertex 1.70496 1.05176 2.46674 + vertex 1.70735 1.05489 2.46403 + vertex 1.70517 1.05713 2.46699 + endloop + endfacet + facet normal 0.701506 -0.0600518 0.710129 + outer loop + vertex 1.70517 1.05713 2.46699 + vertex 1.70263 1.05428 2.46926 + vertex 1.70496 1.05176 2.46674 + endloop + endfacet + facet normal 0.718804 -0.0922109 0.68907 + outer loop + vertex 1.70291 1.05936 2.46965 + vertex 1.70263 1.05428 2.46926 + vertex 1.70517 1.05713 2.46699 + endloop + endfacet + facet normal 0.843966 0.0308344 0.53551 + outer loop + vertex 1.70727 1.06019 2.46405 + vertex 1.70721 1.06535 2.46384 + vertex 1.70509 1.06284 2.46733 + endloop + endfacet + facet normal 0.824627 -0.0218884 0.565253 + outer loop + vertex 1.70517 1.05713 2.46699 + vertex 1.70727 1.06019 2.46405 + vertex 1.70509 1.06284 2.46733 + endloop + endfacet + facet normal 0.749271 -0.0285328 0.661648 + outer loop + vertex 1.70509 1.06284 2.46733 + vertex 1.70291 1.05936 2.46965 + vertex 1.70517 1.05713 2.46699 + endloop + endfacet + facet normal 0.775648 -0.0677962 0.627514 + outer loop + vertex 1.70288 1.06335 2.47011 + vertex 1.70291 1.05936 2.46965 + vertex 1.70509 1.06284 2.46733 + endloop + endfacet + facet normal 0.876442 0.0316706 0.480465 + outer loop + vertex 1.70721 1.06535 2.46384 + vertex 1.70708 1.07004 2.46378 + vertex 1.70579 1.06737 2.4663 + endloop + endfacet + facet normal 0.859654 -0.0169484 0.510596 + outer loop + vertex 1.70509 1.06284 2.46733 + vertex 1.70721 1.06535 2.46384 + vertex 1.70579 1.06737 2.4663 + endloop + endfacet + facet normal 0.724821 -0.0156205 0.68876 + outer loop + vertex 1.70288 1.06335 2.47011 + vertex 1.70372 1.06741 2.46933 + vertex 1.7015 1.06528 2.47161 + endloop + endfacet + facet normal 0.779429 -0.039112 0.625268 + outer loop + vertex 1.70288 1.06335 2.47011 + vertex 1.70509 1.06284 2.46733 + vertex 1.70372 1.06741 2.46933 + endloop + endfacet + facet normal 0.824881 0.000822606 0.565306 + outer loop + vertex 1.70509 1.06284 2.46733 + vertex 1.70579 1.06737 2.4663 + vertex 1.70372 1.06741 2.46933 + endloop + endfacet + facet normal 0.739003 -0.0483868 0.671962 + outer loop + vertex 1.70372 1.06741 2.46933 + vertex 1.7012 1.06896 2.47221 + vertex 1.7015 1.06528 2.47161 + endloop + endfacet + facet normal 0.883806 0.0259963 0.467132 + outer loop + vertex 1.70708 1.07004 2.46378 + vertex 1.70685 1.07483 2.46394 + vertex 1.70546 1.07136 2.46677 + endloop + endfacet + facet normal 0.882599 0.0185857 0.469758 + outer loop + vertex 1.70579 1.06737 2.4663 + vertex 1.70708 1.07004 2.46378 + vertex 1.70546 1.07136 2.46677 + endloop + endfacet + facet normal 0.824889 0.00264569 0.565288 + outer loop + vertex 1.70579 1.06737 2.4663 + vertex 1.70546 1.07136 2.46677 + vertex 1.70372 1.06741 2.46933 + endloop + endfacet + facet normal 0.834644 -0.0111003 0.550677 + outer loop + vertex 1.70546 1.07136 2.46677 + vertex 1.70342 1.07254 2.46988 + vertex 1.70372 1.06741 2.46933 + endloop + endfacet + facet normal 0.74486 -0.0288377 0.666597 + outer loop + vertex 1.70342 1.07254 2.46988 + vertex 1.7012 1.06896 2.47221 + vertex 1.70372 1.06741 2.46933 + endloop + endfacet + facet normal 0.764104 -0.0563248 0.64263 + outer loop + vertex 1.70079 1.07391 2.47312 + vertex 1.7012 1.06896 2.47221 + vertex 1.70342 1.07254 2.46988 + endloop + endfacet + facet normal 0.89364 0.00130511 0.448783 + outer loop + vertex 1.70685 1.07483 2.46394 + vertex 1.70672 1.08009 2.46418 + vertex 1.70532 1.07628 2.46699 + endloop + endfacet + facet normal 0.89442 0.00546136 0.447194 + outer loop + vertex 1.70546 1.07136 2.46677 + vertex 1.70685 1.07483 2.46394 + vertex 1.70532 1.07628 2.46699 + endloop + endfacet + facet normal 0.836504 -0.000719112 0.547961 + outer loop + vertex 1.70546 1.07136 2.46677 + vertex 1.70532 1.07628 2.46699 + vertex 1.70342 1.07254 2.46988 + endloop + endfacet + facet normal 0.84936 -0.0232216 0.527302 + outer loop + vertex 1.70532 1.07628 2.46699 + vertex 1.70341 1.07773 2.47012 + vertex 1.70342 1.07254 2.46988 + endloop + endfacet + facet normal 0.77089 -0.0283969 0.636335 + outer loop + vertex 1.70341 1.07773 2.47012 + vertex 1.70079 1.07391 2.47312 + vertex 1.70342 1.07254 2.46988 + endloop + endfacet + facet normal 0.791449 -0.0649006 0.60778 + outer loop + vertex 1.70127 1.07941 2.47309 + vertex 1.70079 1.07391 2.47312 + vertex 1.70341 1.07773 2.47012 + endloop + endfacet + facet normal 0.901076 -0.126333 0.414853 + outer loop + vertex 1.70672 1.08009 2.46418 + vertex 1.70716 1.08548 2.46487 + vertex 1.70555 1.08199 2.46731 + endloop + endfacet + facet normal 0.922387 -0.0585957 0.381797 + outer loop + vertex 1.70532 1.07628 2.46699 + vertex 1.70672 1.08009 2.46418 + vertex 1.70555 1.08199 2.46731 + endloop + endfacet + facet normal 0.839163 -0.0642649 0.54007 + outer loop + vertex 1.70532 1.07628 2.46699 + vertex 1.70555 1.08199 2.46731 + vertex 1.70341 1.07773 2.47012 + endloop + endfacet + facet normal 0.846164 -0.0760871 0.527463 + outer loop + vertex 1.70555 1.08199 2.46731 + vertex 1.70376 1.08346 2.47038 + vertex 1.70341 1.07773 2.47012 + endloop + endfacet + facet normal 0.787589 -0.0763377 0.611454 + outer loop + vertex 1.70376 1.08346 2.47038 + vertex 1.70127 1.07941 2.47309 + vertex 1.70341 1.07773 2.47012 + endloop + endfacet + facet normal 0.765679 -0.0425494 0.641814 + outer loop + vertex 1.70146 1.08451 2.4732 + vertex 1.70127 1.07941 2.47309 + vertex 1.70376 1.08346 2.47038 + endloop + endfacet + facet normal 0.692536 -0.565569 0.447801 + outer loop + vertex 1.70716 1.08548 2.46487 + vertex 1.71 1.09 2.46618 + vertex 1.70753 1.09 2.47 + endloop + endfacet + facet normal 0.935052 -0.296813 0.193855 + outer loop + vertex 1.70555 1.08199 2.46731 + vertex 1.70716 1.08548 2.46487 + vertex 1.70753 1.09 2.47 + endloop + endfacet + facet normal 0.712315 -0.37556 0.592927 + outer loop + vertex 1.70555 1.08199 2.46731 + vertex 1.70753 1.09 2.47 + vertex 1.70376 1.08346 2.47038 + endloop + endfacet + facet normal 0.220748 -0.0701018 0.972808 + outer loop + vertex 1.70753 1.09 2.47 + vertex 1.70401 1.08888 2.47072 + vertex 1.70376 1.08346 2.47038 + endloop + endfacet + facet normal 0.758295 -0.0745539 0.647635 + outer loop + vertex 1.70401 1.08888 2.47072 + vertex 1.70146 1.08451 2.4732 + vertex 1.70376 1.08346 2.47038 + endloop + endfacet + facet normal 0.726313 -0.0337855 0.686533 + outer loop + vertex 1.70152 1.08943 2.47338 + vertex 1.70146 1.08451 2.4732 + vertex 1.70401 1.08888 2.47072 + endloop + endfacet + facet normal 0.200252 -0.00119837 0.979744 + outer loop + vertex 1.70753 1.09 2.47 + vertex 1.70756 1.095 2.47 + vertex 1.70401 1.08888 2.47072 + endloop + endfacet + facet normal 0.233913 -0.0216332 0.972017 + outer loop + vertex 1.70756 1.095 2.47 + vertex 1.70396 1.09372 2.47084 + vertex 1.70401 1.08888 2.47072 + endloop + endfacet + facet normal 0.729226 -0.0094757 0.684208 + outer loop + vertex 1.70396 1.09372 2.47084 + vertex 1.70152 1.08943 2.47338 + vertex 1.70401 1.08888 2.47072 + endloop + endfacet + facet normal 0.736072 -0.0178246 0.676669 + outer loop + vertex 1.70154 1.0944 2.47349 + vertex 1.70152 1.08943 2.47338 + vertex 1.70396 1.09372 2.47084 + endloop + endfacet + facet normal 0.228542 -0.00548701 0.973519 + outer loop + vertex 1.70756 1.095 2.47 + vertex 1.70768 1.1 2.47 + vertex 1.70396 1.09372 2.47084 + endloop + endfacet + facet normal 0.222025 -0.00142118 0.97504 + outer loop + vertex 1.70768 1.1 2.47 + vertex 1.70392 1.09878 2.47085 + vertex 1.70396 1.09372 2.47084 + endloop + endfacet + facet normal 0.738875 0.00339368 0.673834 + outer loop + vertex 1.70392 1.09878 2.47085 + vertex 1.70154 1.0944 2.47349 + vertex 1.70396 1.09372 2.47084 + endloop + endfacet + facet normal 0.738389 0.00397495 0.674363 + outer loop + vertex 1.70165 1.09967 2.47334 + vertex 1.70154 1.0944 2.47349 + vertex 1.70392 1.09878 2.47085 + endloop + endfacet + facet normal 0.221723 -0.000444049 0.97511 + outer loop + vertex 1.70768 1.1 2.47 + vertex 1.70769 1.105 2.47 + vertex 1.70392 1.09878 2.47085 + endloop + endfacet + facet normal 0.191022 0.019016 0.981402 + outer loop + vertex 1.70769 1.105 2.47 + vertex 1.7039 1.1037 2.47076 + vertex 1.70392 1.09878 2.47085 + endloop + endfacet + facet normal 0.740415 0.0158433 0.671963 + outer loop + vertex 1.7039 1.1037 2.47076 + vertex 1.70165 1.09967 2.47334 + vertex 1.70392 1.09878 2.47085 + endloop + endfacet + facet normal 0.797831 -0.0624659 0.599637 + outer loop + vertex 1.70235 1.1044 2.4729 + vertex 1.70165 1.09967 2.47334 + vertex 1.7039 1.1037 2.47076 + endloop + endfacet + facet normal 0.645104 -0.679837 0.348801 + outer loop + vertex 1.70391 1.10736 2.47167 + vertex 1.70759 1.11 2.47 + vertex 1.705 1.11 2.47479 + endloop + endfacet + facet normal 0.522115 -0.20548 0.827752 + outer loop + vertex 1.70391 1.10736 2.47167 + vertex 1.7039 1.1037 2.47076 + vertex 1.70759 1.11 2.47 + endloop + endfacet + facet normal 0.196046 0.00392158 0.980587 + outer loop + vertex 1.7039 1.1037 2.47076 + vertex 1.70769 1.105 2.47 + vertex 1.70759 1.11 2.47 + endloop + endfacet + facet normal 0.775031 -0.15321 0.613069 + outer loop + vertex 1.7039 1.1037 2.47076 + vertex 1.70391 1.10736 2.47167 + vertex 1.70235 1.1044 2.4729 + endloop + endfacet + facet normal 0.875414 0.0980336 0.473328 + outer loop + vertex 1.70703 1.115 2.47 + vertex 1.705 1.11 2.47479 + vertex 1.70759 1.11 2.47 + endloop + endfacet + facet normal 0.860857 0.123416 0.493653 + outer loop + vertex 1.705 1.115 2.47354 + vertex 1.705 1.11 2.47479 + vertex 1.70703 1.115 2.47 + endloop + endfacet + facet normal 0.579323 0.744326 0.33221 + outer loop + vertex 1.70703 1.115 2.47 + vertex 1.705 1.11658 2.47 + vertex 1.705 1.115 2.47354 + endloop + endfacet + facet normal 0.700316 -0.700316 0.138254 + outer loop + vertex 1.70592 1.915 2.47 + vertex 1.705 1.915 2.47466 + vertex 1.705 1.91408 2.47 + endloop + endfacet + facet normal 0.963062 -0.190693 0.190124 + outer loop + vertex 1.70691 1.92 2.47 + vertex 1.705 1.915 2.47466 + vertex 1.70592 1.915 2.47 + endloop + endfacet + facet normal 0.919794 0.0141178 0.392148 + outer loop + vertex 1.705 1.92 2.47448 + vertex 1.705 1.915 2.47466 + vertex 1.70691 1.92 2.47 + endloop + endfacet + facet normal 0.991063 0.0281334 -0.130393 + outer loop + vertex 1.705 1.92 2.47448 + vertex 1.70443 1.92349 2.47088 + vertex 1.705 1.92241 2.475 + endloop + endfacet + facet normal 0.803665 0.486541 0.342638 + outer loop + vertex 1.705 1.92 2.47448 + vertex 1.70691 1.92 2.47 + vertex 1.70443 1.92349 2.47088 + endloop + endfacet + facet normal 0.327596 -0.00392869 0.94481 + outer loop + vertex 1.70691 1.92 2.47 + vertex 1.70697 1.925 2.47 + vertex 1.70443 1.92349 2.47088 + endloop + endfacet + facet normal 0.612826 0.781285 0.11848 + outer loop + vertex 1.70443 1.92349 2.47088 + vertex 1.70199 1.92502 2.47332 + vertex 1.705 1.92241 2.475 + endloop + endfacet + facet normal 0.334712 -0.0174047 0.94216 + outer loop + vertex 1.70697 1.925 2.47 + vertex 1.70723 1.93 2.47 + vertex 1.70443 1.92349 2.47088 + endloop + endfacet + facet normal 0.179734 0.0546555 0.982196 + outer loop + vertex 1.70723 1.93 2.47 + vertex 1.70386 1.92904 2.47067 + vertex 1.70443 1.92349 2.47088 + endloop + endfacet + facet normal 0.736144 0.099698 0.669442 + outer loop + vertex 1.70386 1.92904 2.47067 + vertex 1.70199 1.92502 2.47332 + vertex 1.70443 1.92349 2.47088 + endloop + endfacet + facet normal 0.743007 0.0921861 0.662905 + outer loop + vertex 1.70141 1.92982 2.47331 + vertex 1.70199 1.92502 2.47332 + vertex 1.70386 1.92904 2.47067 + endloop + endfacet + facet normal 0.200213 -0.0192227 0.979564 + outer loop + vertex 1.70723 1.93 2.47 + vertex 1.70771 1.935 2.47 + vertex 1.70386 1.92904 2.47067 + endloop + endfacet + facet normal 0.153604 0.0118423 0.988062 + outer loop + vertex 1.70771 1.935 2.47 + vertex 1.70387 1.93389 2.47061 + vertex 1.70386 1.92904 2.47067 + endloop + endfacet + facet normal 0.733635 0.00689331 0.679509 + outer loop + vertex 1.70387 1.93389 2.47061 + vertex 1.70141 1.92982 2.47331 + vertex 1.70386 1.92904 2.47067 + endloop + endfacet + facet normal 0.717318 0.0278245 0.69619 + outer loop + vertex 1.70134 1.93437 2.4732 + vertex 1.70141 1.92982 2.47331 + vertex 1.70387 1.93389 2.47061 + endloop + endfacet + facet normal 0.155898 0.00374283 0.987766 + outer loop + vertex 1.70771 1.935 2.47 + vertex 1.70759 1.94 2.47 + vertex 1.70387 1.93389 2.47061 + endloop + endfacet + facet normal 0.0191526 0.0877957 0.995954 + outer loop + vertex 1.70759 1.94 2.47 + vertex 1.70367 1.93803 2.47025 + vertex 1.70387 1.93389 2.47061 + endloop + endfacet + facet normal 0.720573 0.09486 0.686859 + outer loop + vertex 1.70367 1.93803 2.47025 + vertex 1.70134 1.93437 2.4732 + vertex 1.70387 1.93389 2.47061 + endloop + endfacet + facet normal 0.765429 0.0307482 0.642786 + outer loop + vertex 1.70132 1.93893 2.473 + vertex 1.70134 1.93437 2.4732 + vertex 1.70367 1.93803 2.47025 + endloop + endfacet + facet normal 0.440865 0.350891 0.826144 + outer loop + vertex 1.71 1.94 2.46563 + vertex 1.70761 1.94451 2.46499 + vertex 1.70582 1.9412 2.46735 + endloop + endfacet + facet normal 0.341655 0.920743 0.188424 + outer loop + vertex 1.70759 1.94 2.47 + vertex 1.71 1.94 2.46563 + vertex 1.70582 1.9412 2.46735 + endloop + endfacet + facet normal -0.340821 0.749445 0.567603 + outer loop + vertex 1.70759 1.94 2.47 + vertex 1.70582 1.9412 2.46735 + vertex 1.70367 1.93803 2.47025 + endloop + endfacet + facet normal 0.752426 0.0868646 0.652924 + outer loop + vertex 1.70582 1.9412 2.46735 + vertex 1.70342 1.94226 2.46997 + vertex 1.70367 1.93803 2.47025 + endloop + endfacet + facet normal 0.771796 0.0865091 0.629958 + outer loop + vertex 1.70342 1.94226 2.46997 + vertex 1.70132 1.93893 2.473 + vertex 1.70367 1.93803 2.47025 + endloop + endfacet + facet normal 0.807859 0.0263797 0.588785 + outer loop + vertex 1.70129 1.94369 2.47283 + vertex 1.70132 1.93893 2.473 + vertex 1.70342 1.94226 2.46997 + endloop + endfacet + facet normal 0.678223 0.0538401 0.732881 + outer loop + vertex 1.70761 1.94451 2.46499 + vertex 1.70736 1.94914 2.46488 + vertex 1.70527 1.94551 2.46708 + endloop + endfacet + facet normal 0.691471 0.132976 0.71006 + outer loop + vertex 1.70582 1.9412 2.46735 + vertex 1.70761 1.94451 2.46499 + vertex 1.70527 1.94551 2.46708 + endloop + endfacet + facet normal 0.757967 0.136935 0.637758 + outer loop + vertex 1.70582 1.9412 2.46735 + vertex 1.70527 1.94551 2.46708 + vertex 1.70342 1.94226 2.46997 + endloop + endfacet + facet normal 0.836161 0.0129361 0.548332 + outer loop + vertex 1.70527 1.94551 2.46708 + vertex 1.70336 1.94696 2.46996 + vertex 1.70342 1.94226 2.46997 + endloop + endfacet + facet normal 0.804811 0.0126938 0.593395 + outer loop + vertex 1.70336 1.94696 2.46996 + vertex 1.70129 1.94369 2.47283 + vertex 1.70342 1.94226 2.46997 + endloop + endfacet + facet normal 0.793637 0.0321708 0.607541 + outer loop + vertex 1.70114 1.94859 2.47277 + vertex 1.70129 1.94369 2.47283 + vertex 1.70336 1.94696 2.46996 + endloop + endfacet + facet normal 0.733592 0.0960683 0.672766 + outer loop + vertex 1.70736 1.94914 2.46488 + vertex 1.70725 1.95379 2.46433 + vertex 1.70523 1.95018 2.46706 + endloop + endfacet + facet normal 0.716777 0.00995498 0.697231 + outer loop + vertex 1.70527 1.94551 2.46708 + vertex 1.70736 1.94914 2.46488 + vertex 1.70523 1.95018 2.46706 + endloop + endfacet + facet normal 0.83554 0.0101385 0.549337 + outer loop + vertex 1.70527 1.94551 2.46708 + vertex 1.70523 1.95018 2.46706 + vertex 1.70336 1.94696 2.46996 + endloop + endfacet + facet normal 0.830642 0.0194213 0.556468 + outer loop + vertex 1.70523 1.95018 2.46706 + vertex 1.70322 1.95178 2.47 + vertex 1.70336 1.94696 2.46996 + endloop + endfacet + facet normal 0.78992 0.0177676 0.612952 + outer loop + vertex 1.70322 1.95178 2.47 + vertex 1.70114 1.94859 2.47277 + vertex 1.70336 1.94696 2.46996 + endloop + endfacet + facet normal 0.763075 0.0617598 0.643352 + outer loop + vertex 1.70054 1.95383 2.47297 + vertex 1.70114 1.94859 2.47277 + vertex 1.70322 1.95178 2.47 + endloop + endfacet + facet normal 0.804557 0.0793972 0.588545 + outer loop + vertex 1.70725 1.95379 2.46433 + vertex 1.7071 1.95881 2.46386 + vertex 1.70515 1.955 2.46704 + endloop + endfacet + facet normal 0.793228 0.014405 0.608755 + outer loop + vertex 1.70523 1.95018 2.46706 + vertex 1.70725 1.95379 2.46433 + vertex 1.70515 1.955 2.46704 + endloop + endfacet + facet normal 0.82955 0.0147932 0.558236 + outer loop + vertex 1.70523 1.95018 2.46706 + vertex 1.70515 1.955 2.46704 + vertex 1.70322 1.95178 2.47 + endloop + endfacet + facet normal 0.819284 0.0339259 0.572383 + outer loop + vertex 1.70515 1.955 2.46704 + vertex 1.703 1.95647 2.47004 + vertex 1.70322 1.95178 2.47 + endloop + endfacet + facet normal 0.753546 0.0299998 0.65671 + outer loop + vertex 1.703 1.95647 2.47004 + vertex 1.70054 1.95383 2.47297 + vertex 1.70322 1.95178 2.47 + endloop + endfacet + facet normal 0.734514 0.0681622 0.675162 + outer loop + vertex 1.70071 1.95862 2.47231 + vertex 1.70054 1.95383 2.47297 + vertex 1.703 1.95647 2.47004 + endloop + endfacet + facet normal 0.833566 0.00647143 0.552382 + outer loop + vertex 1.7071 1.95881 2.46386 + vertex 1.70712 1.96408 2.46378 + vertex 1.70477 1.96027 2.46736 + endloop + endfacet + facet normal 0.837245 0.0272466 0.546148 + outer loop + vertex 1.70515 1.955 2.46704 + vertex 1.7071 1.95881 2.46386 + vertex 1.70477 1.96027 2.46736 + endloop + endfacet + facet normal 0.795568 0.0709181 0.6017 + outer loop + vertex 1.7026 1.96001 2.47026 + vertex 1.70477 1.96027 2.46736 + vertex 1.7028 1.96341 2.4696 + endloop + endfacet + facet normal 0.797397 0.0511702 0.601282 + outer loop + vertex 1.7026 1.96001 2.47026 + vertex 1.703 1.95647 2.47004 + vertex 1.70477 1.96027 2.46736 + endloop + endfacet + facet normal 0.817242 0.0239655 0.575797 + outer loop + vertex 1.703 1.95647 2.47004 + vertex 1.70515 1.955 2.46704 + vertex 1.70477 1.96027 2.46736 + endloop + endfacet + facet normal 0.721413 0.0371005 0.691511 + outer loop + vertex 1.703 1.95647 2.47004 + vertex 1.7026 1.96001 2.47026 + vertex 1.70071 1.95862 2.47231 + endloop + endfacet + facet normal 0.810686 0.00160426 0.585479 + outer loop + vertex 1.70712 1.96408 2.46378 + vertex 1.70712 1.96927 2.46375 + vertex 1.70492 1.96571 2.46681 + endloop + endfacet + facet normal 0.818665 0.0352557 0.573188 + outer loop + vertex 1.70477 1.96027 2.46736 + vertex 1.70712 1.96408 2.46378 + vertex 1.70492 1.96571 2.46681 + endloop + endfacet + facet normal 0.777931 0.0418544 0.626955 + outer loop + vertex 1.70492 1.96571 2.46681 + vertex 1.7028 1.96341 2.4696 + vertex 1.70477 1.96027 2.46736 + endloop + endfacet + facet normal 0.757233 0.0857387 0.647493 + outer loop + vertex 1.70256 1.96792 2.46929 + vertex 1.7028 1.96341 2.4696 + vertex 1.70492 1.96571 2.46681 + endloop + endfacet + facet normal 0.780143 0.0156833 0.625405 + outer loop + vertex 1.70712 1.96927 2.46375 + vertex 1.70699 1.97422 2.4638 + vertex 1.70478 1.97073 2.46664 + endloop + endfacet + facet normal 0.786249 0.0432927 0.616391 + outer loop + vertex 1.70492 1.96571 2.46681 + vertex 1.70712 1.96927 2.46375 + vertex 1.70478 1.97073 2.46664 + endloop + endfacet + facet normal 0.741355 0.0439077 0.669676 + outer loop + vertex 1.70478 1.97073 2.46664 + vertex 1.70256 1.96792 2.46929 + vertex 1.70492 1.96571 2.46681 + endloop + endfacet + facet normal 0.719074 0.08099 0.690198 + outer loop + vertex 1.70227 1.97273 2.46902 + vertex 1.70256 1.96792 2.46929 + vertex 1.70478 1.97073 2.46664 + endloop + endfacet + facet normal 0.754131 0.031124 0.655986 + outer loop + vertex 1.70699 1.97422 2.4638 + vertex 1.70682 1.9791 2.46376 + vertex 1.70458 1.97567 2.4665 + endloop + endfacet + facet normal 0.758388 0.0494081 0.649928 + outer loop + vertex 1.70478 1.97073 2.46664 + vertex 1.70699 1.97422 2.4638 + vertex 1.70458 1.97567 2.4665 + endloop + endfacet + facet normal 0.707529 0.0488095 0.704996 + outer loop + vertex 1.70458 1.97567 2.4665 + vertex 1.70227 1.97273 2.46902 + vertex 1.70478 1.97073 2.46664 + endloop + endfacet + facet normal 0.679188 0.0909324 0.728309 + outer loop + vertex 1.7019 1.97764 2.46876 + vertex 1.70227 1.97273 2.46902 + vertex 1.70458 1.97567 2.4665 + endloop + endfacet + facet normal 0.72564 0.0499838 0.686256 + outer loop + vertex 1.70682 1.9791 2.46376 + vertex 1.70671 1.98394 2.46352 + vertex 1.70434 1.98063 2.46627 + endloop + endfacet + facet normal 0.729836 0.066477 0.680382 + outer loop + vertex 1.70458 1.97567 2.4665 + vertex 1.70682 1.9791 2.46376 + vertex 1.70434 1.98063 2.46627 + endloop + endfacet + facet normal 0.670257 0.0662927 0.739162 + outer loop + vertex 1.70434 1.98063 2.46627 + vertex 1.7019 1.97764 2.46876 + vertex 1.70458 1.97567 2.4665 + endloop + endfacet + facet normal 0.631583 0.120115 0.765948 + outer loop + vertex 1.7012 1.98303 2.46848 + vertex 1.7019 1.97764 2.46876 + vertex 1.70434 1.98063 2.46627 + endloop + endfacet + facet normal 0.699227 0.0808235 0.710316 + outer loop + vertex 1.70671 1.98394 2.46352 + vertex 1.70648 1.98871 2.46321 + vertex 1.70418 1.98542 2.46585 + endloop + endfacet + facet normal 0.700579 0.0862616 0.708342 + outer loop + vertex 1.70434 1.98063 2.46627 + vertex 1.70671 1.98394 2.46352 + vertex 1.70418 1.98542 2.46585 + endloop + endfacet + facet normal 0.618673 0.0899058 0.780487 + outer loop + vertex 1.70418 1.98542 2.46585 + vertex 1.7012 1.98303 2.46848 + vertex 1.70434 1.98063 2.46627 + endloop + endfacet + facet normal 0.602776 0.119091 0.788973 + outer loop + vertex 1.70173 1.98745 2.46741 + vertex 1.7012 1.98303 2.46848 + vertex 1.70418 1.98542 2.46585 + endloop + endfacet + facet normal 0.663811 0.111958 0.739473 + outer loop + vertex 1.70648 1.98871 2.46321 + vertex 1.70569 1.99369 2.46317 + vertex 1.7037 1.98993 2.46552 + endloop + endfacet + facet normal 0.665983 0.124314 0.735535 + outer loop + vertex 1.70418 1.98542 2.46585 + vertex 1.70648 1.98871 2.46321 + vertex 1.7037 1.98993 2.46552 + endloop + endfacet + facet normal 0.604034 0.121637 0.787622 + outer loop + vertex 1.7037 1.98993 2.46552 + vertex 1.70173 1.98745 2.46741 + vertex 1.70418 1.98542 2.46585 + endloop + endfacet + facet normal 0.555094 0.179431 0.812204 + outer loop + vertex 1.70032 1.99191 2.46739 + vertex 1.70173 1.98745 2.46741 + vertex 1.7037 1.98993 2.46552 + endloop + endfacet + facet normal 0.622652 0.15131 0.76773 + outer loop + vertex 1.70285 1.99354 2.4655 + vertex 1.7037 1.98993 2.46552 + vertex 1.70569 1.99369 2.46317 + endloop + endfacet + facet normal 0.620523 0.16711 0.766175 + outer loop + vertex 1.70285 1.99354 2.4655 + vertex 1.70569 1.99369 2.46317 + vertex 1.70298 1.99719 2.4646 + endloop + endfacet + facet normal 0.598734 0.141167 0.78841 + outer loop + vertex 1.70298 1.99719 2.4646 + vertex 1.70569 1.99369 2.46317 + vertex 1.70568 1.99859 2.4623 + endloop + endfacet + facet normal 0.538273 0.131742 0.83241 + outer loop + vertex 1.7037 1.98993 2.46552 + vertex 1.70285 1.99354 2.4655 + vertex 1.70032 1.99191 2.46739 + endloop + endfacet + facet normal 0.627789 0.12554 0.768194 + outer loop + vertex 1.70789 2.00011 2.46023 + vertex 1.70837 2.00383 2.45923 + vertex 1.70602 2.00205 2.46144 + endloop + endfacet + facet normal 0.628505 0.126712 0.767415 + outer loop + vertex 1.70602 2.00205 2.46144 + vertex 1.70568 1.99859 2.4623 + vertex 1.70789 2.00011 2.46023 + endloop + endfacet + facet normal 0.549605 0.148171 0.822179 + outer loop + vertex 1.70602 2.00205 2.46144 + vertex 1.70243 2.00271 2.46372 + vertex 1.70568 1.99859 2.4623 + endloop + endfacet + facet normal 0.581022 0.183007 0.793046 + outer loop + vertex 1.70243 2.00271 2.46372 + vertex 1.70298 1.99719 2.4646 + vertex 1.70568 1.99859 2.4623 + endloop + endfacet + facet normal 0.601957 0.106437 0.791403 + outer loop + vertex 1.70837 2.00383 2.45923 + vertex 1.70712 2.00794 2.45963 + vertex 1.70517 2.00563 2.46142 + endloop + endfacet + facet normal 0.61483 0.15014 0.774237 + outer loop + vertex 1.70602 2.00205 2.46144 + vertex 1.70837 2.00383 2.45923 + vertex 1.70517 2.00563 2.46142 + endloop + endfacet + facet normal 0.548913 0.134712 0.824953 + outer loop + vertex 1.70517 2.00563 2.46142 + vertex 1.70243 2.00271 2.46372 + vertex 1.70602 2.00205 2.46144 + endloop + endfacet + facet normal 0.522825 0.167691 0.835783 + outer loop + vertex 1.70227 2.00764 2.46284 + vertex 1.70243 2.00271 2.46372 + vertex 1.70517 2.00563 2.46142 + endloop + endfacet + facet normal 0.556666 0.149225 0.817224 + outer loop + vertex 1.70712 2.00794 2.45963 + vertex 1.70716 2.01273 2.45873 + vertex 1.70435 2.00997 2.46115 + endloop + endfacet + facet normal 0.560597 0.157801 0.812914 + outer loop + vertex 1.70517 2.00563 2.46142 + vertex 1.70712 2.00794 2.45963 + vertex 1.70435 2.00997 2.46115 + endloop + endfacet + facet normal 0.515171 0.151132 0.843658 + outer loop + vertex 1.70435 2.00997 2.46115 + vertex 1.70227 2.00764 2.46284 + vertex 1.70517 2.00563 2.46142 + endloop + endfacet + facet normal 0.471352 0.2012 0.858688 + outer loop + vertex 1.70054 2.01219 2.46272 + vertex 1.70227 2.00764 2.46284 + vertex 1.70435 2.00997 2.46115 + endloop + endfacet + facet normal 0.535719 0.177861 0.825452 + outer loop + vertex 1.70348 2.01381 2.46088 + vertex 1.70435 2.00997 2.46115 + vertex 1.70716 2.01273 2.45873 + endloop + endfacet + facet normal 0.535508 0.176156 0.825954 + outer loop + vertex 1.70348 2.01381 2.46088 + vertex 1.70716 2.01273 2.45873 + vertex 1.70393 2.01797 2.4597 + endloop + endfacet + facet normal 0.497611 0.14748 0.854771 + outer loop + vertex 1.70393 2.01797 2.4597 + vertex 1.70716 2.01273 2.45873 + vertex 1.70738 2.01752 2.45777 + endloop + endfacet + facet normal 0.455897 0.163139 0.874953 + outer loop + vertex 1.70435 2.00997 2.46115 + vertex 1.70348 2.01381 2.46088 + vertex 1.70054 2.01219 2.46272 + endloop + endfacet + facet normal 0.497869 0.158803 0.852589 + outer loop + vertex 1.70738 2.01752 2.45777 + vertex 1.70615 2.02174 2.45771 + vertex 1.70393 2.01797 2.4597 + endloop + endfacet + facet normal 0.441614 0.203271 0.873875 + outer loop + vertex 1.70393 2.01797 2.4597 + vertex 1.70615 2.02174 2.45771 + vertex 1.70193 2.02375 2.45937 + endloop + endfacet + facet normal 0.43068 0.169809 0.886386 + outer loop + vertex 1.70615 2.02174 2.45771 + vertex 1.70499 2.02681 2.4573 + vertex 1.70193 2.02375 2.45937 + endloop + endfacet + facet normal 0.405776 0.198579 0.892139 + outer loop + vertex 1.70193 2.02375 2.45937 + vertex 1.70499 2.02681 2.4573 + vertex 1.70184 2.02746 2.45858 + endloop + endfacet + facet normal 0.477832 0.186553 0.858414 + outer loop + vertex 1.70788 2.02852 2.45541 + vertex 1.70829 2.03266 2.45429 + vertex 1.70564 2.03069 2.45619 + endloop + endfacet + facet normal 0.465744 0.170428 0.868353 + outer loop + vertex 1.70564 2.03069 2.45619 + vertex 1.70499 2.02681 2.4573 + vertex 1.70788 2.02852 2.45541 + endloop + endfacet + facet normal 0.378608 0.195225 0.904734 + outer loop + vertex 1.70564 2.03069 2.45619 + vertex 1.70192 2.03102 2.45768 + vertex 1.70499 2.02681 2.4573 + endloop + endfacet + facet normal 0.407617 0.218073 0.886731 + outer loop + vertex 1.70192 2.03102 2.45768 + vertex 1.70184 2.02746 2.45858 + vertex 1.70499 2.02681 2.4573 + endloop + endfacet + facet normal 0.437195 0.193841 0.878229 + outer loop + vertex 1.70829 2.03266 2.45429 + vertex 1.70609 2.03781 2.45424 + vertex 1.70423 2.03448 2.4559 + endloop + endfacet + facet normal 0.448178 0.231337 0.863492 + outer loop + vertex 1.70564 2.03069 2.45619 + vertex 1.70829 2.03266 2.45429 + vertex 1.70423 2.03448 2.4559 + endloop + endfacet + facet normal 0.378599 0.208501 0.901771 + outer loop + vertex 1.70423 2.03448 2.4559 + vertex 1.70192 2.03102 2.45768 + vertex 1.70564 2.03069 2.45619 + endloop + endfacet + facet normal 0.342846 0.236193 0.909214 + outer loop + vertex 1.69985 2.03636 2.45707 + vertex 1.70192 2.03102 2.45768 + vertex 1.70423 2.03448 2.4559 + endloop + endfacet + facet normal 0.383338 0.231804 0.894046 + outer loop + vertex 1.70265 2.03841 2.45556 + vertex 1.70423 2.03448 2.4559 + vertex 1.70609 2.03781 2.45424 + endloop + endfacet + facet normal 0.38436 0.248658 0.889065 + outer loop + vertex 1.70265 2.03841 2.45556 + vertex 1.70609 2.03781 2.45424 + vertex 1.70251 2.04297 2.45435 + endloop + endfacet + facet normal 0.371879 0.239833 0.896764 + outer loop + vertex 1.70251 2.04297 2.45435 + vertex 1.70609 2.03781 2.45424 + vertex 1.70757 2.04154 2.45263 + endloop + endfacet + facet normal 0.335757 0.214669 0.917161 + outer loop + vertex 1.70423 2.03448 2.4559 + vertex 1.70265 2.03841 2.45556 + vertex 1.69985 2.03636 2.45707 + endloop + endfacet + facet normal 0.369362 0.225144 0.901599 + outer loop + vertex 1.70757 2.04154 2.45263 + vertex 1.70521 2.04667 2.45232 + vertex 1.70251 2.04297 2.45435 + endloop + endfacet + facet normal 0.384933 0.392282 0.835429 + outer loop + vertex 1.70804 2.06361 2.44621 + vertex 1.7073 2.0672 2.44486 + vertex 1.70513 2.06554 2.44663 + endloop + endfacet + facet normal 0.340852 0.314965 0.885786 + outer loop + vertex 1.70513 2.06554 2.44663 + vertex 1.70585 2.06142 2.44782 + vertex 1.70804 2.06361 2.44621 + endloop + endfacet + facet normal 0.303278 0.312592 0.900171 + outer loop + vertex 1.70513 2.06554 2.44663 + vertex 1.70102 2.06636 2.44774 + vertex 1.70585 2.06142 2.44782 + endloop + endfacet + facet normal 0.370407 0.409501 0.833731 + outer loop + vertex 1.70358 2.06834 2.44595 + vertex 1.70513 2.06554 2.44663 + vertex 1.7073 2.0672 2.44486 + endloop + endfacet + facet normal 0.3774 0.46149 0.802867 + outer loop + vertex 1.70358 2.06834 2.44595 + vertex 1.7073 2.0672 2.44486 + vertex 1.70428 2.07057 2.44434 + endloop + endfacet + facet normal 0.393995 0.473941 0.787495 + outer loop + vertex 1.70428 2.07057 2.44434 + vertex 1.7073 2.0672 2.44486 + vertex 1.70741 2.07093 2.44255 + endloop + endfacet + facet normal 0.309411 0.384554 0.869703 + outer loop + vertex 1.70513 2.06554 2.44663 + vertex 1.70358 2.06834 2.44595 + vertex 1.70102 2.06636 2.44774 + endloop + endfacet + facet normal 0.331461 0.677956 0.656132 + outer loop + vertex 1.70326 2.0741 2.44208 + vertex 1.70809 2.07391 2.43983 + vertex 1.7057 2.07643 2.43843 + endloop + endfacet + facet normal 0.352095 0.663175 0.660476 + outer loop + vertex 1.70291 2.07679 2.43956 + vertex 1.70326 2.0741 2.44208 + vertex 1.7057 2.07643 2.43843 + endloop + endfacet + facet normal 0.354024 0.574856 0.737705 + outer loop + vertex 1.70741 2.07093 2.44255 + vertex 1.70326 2.0741 2.44208 + vertex 1.70428 2.07057 2.44434 + endloop + endfacet + facet normal 0.361305 0.582936 0.727767 + outer loop + vertex 1.70809 2.07391 2.43983 + vertex 1.70326 2.0741 2.44208 + vertex 1.70741 2.07093 2.44255 + endloop + endfacet + facet normal 0.196471 0.676963 0.70931 + outer loop + vertex 1.70833 2.08036 2.43166 + vertex 1.70664 2.08243 2.43016 + vertex 1.70413 2.081 2.43221 + endloop + endfacet + facet normal 0.338933 0.803307 0.489716 + outer loop + vertex 1.70413 2.081 2.43221 + vertex 1.70113 2.08127 2.43384 + vertex 1.70299 2.07893 2.43639 + endloop + endfacet + facet normal 0.193352 0.857347 0.477044 + outer loop + vertex 1.70413 2.081 2.43221 + vertex 1.70299 2.07893 2.43639 + vertex 1.70833 2.08036 2.43166 + endloop + endfacet + facet normal 0.323495 0.740875 0.588605 + outer loop + vertex 1.70833 2.08036 2.43166 + vertex 1.70299 2.07893 2.43639 + vertex 1.70826 2.07771 2.43503 + endloop + endfacet + facet normal 0.317139 0.781792 0.536865 + outer loop + vertex 1.7057 2.07643 2.43843 + vertex 1.70299 2.07893 2.43639 + vertex 1.70291 2.07679 2.43956 + endloop + endfacet + facet normal 0.319216 0.782359 0.534804 + outer loop + vertex 1.70826 2.07771 2.43503 + vertex 1.70299 2.07893 2.43639 + vertex 1.7057 2.07643 2.43843 + endloop + endfacet + facet normal 0.331476 0.535766 0.776582 + outer loop + vertex 1.70664 2.08243 2.43016 + vertex 1.70248 2.08362 2.43111 + vertex 1.70413 2.081 2.43221 + endloop + endfacet + facet normal 0.185481 -0.129178 0.97412 + outer loop + vertex 1.70664 2.08243 2.43016 + vertex 1.71 2.08606 2.43 + vertex 1.70248 2.08362 2.43111 + endloop + endfacet + facet normal 0.0519437 0.276342 0.959655 + outer loop + vertex 1.71 2.08606 2.43 + vertex 1.705 2.087 2.43 + vertex 1.70248 2.08362 2.43111 + endloop + endfacet + facet normal 0.432526 0.56738 0.700715 + outer loop + vertex 1.70413 2.081 2.43221 + vertex 1.70248 2.08362 2.43111 + vertex 1.70113 2.08127 2.43384 + endloop + endfacet + facet normal 0.229223 -0.688939 -0.687619 + outer loop + vertex 1.71168 0.95 2.43 + vertex 1.71 0.949441 2.43 + vertex 1.71 0.95 2.42944 + endloop + endfacet + facet normal -0.247655 0.744337 0.620185 + outer loop + vertex 1.71168 0.95 2.43 + vertex 1.70904 0.949586 2.42944 + vertex 1.71 0.949441 2.43 + endloop + endfacet + facet normal -0.252632 0.664601 0.703194 + outer loop + vertex 1.70904 0.949586 2.42944 + vertex 1.71168 0.95 2.43 + vertex 1.715 0.951262 2.43 + endloop + endfacet + facet normal 0.205602 -0.875589 0.437118 + outer loop + vertex 1.70904 0.949586 2.42944 + vertex 1.715 0.951262 2.43 + vertex 1.70702 0.95043 2.43209 + endloop + endfacet + facet normal 0.25293 -0.666106 0.701662 + outer loop + vertex 1.70702 0.95043 2.43209 + vertex 1.715 0.951262 2.43 + vertex 1.71189 0.952521 2.43232 + endloop + endfacet + facet normal 0.342708 -0.776195 0.529219 + outer loop + vertex 1.71041 0.954854 2.4367 + vertex 1.71189 0.952521 2.43232 + vertex 1.71315 0.954029 2.43371 + endloop + endfacet + facet normal 0.367626 -0.763529 0.530918 + outer loop + vertex 1.71041 0.954854 2.4367 + vertex 1.70662 0.952635 2.43613 + vertex 1.71189 0.952521 2.43232 + endloop + endfacet + facet normal 0.327621 -0.815449 0.477186 + outer loop + vertex 1.70662 0.952635 2.43613 + vertex 1.70702 0.95043 2.43209 + vertex 1.71189 0.952521 2.43232 + endloop + endfacet + facet normal 0.374377 -0.770986 0.515192 + outer loop + vertex 1.71041 0.954854 2.4367 + vertex 1.707 0.954693 2.43893 + vertex 1.70662 0.952635 2.43613 + endloop + endfacet + facet normal 0.365118 -0.755443 0.544054 + outer loop + vertex 1.71315 0.954029 2.43371 + vertex 1.71387 0.955818 2.43572 + vertex 1.71041 0.954854 2.4367 + endloop + endfacet + facet normal 0.396005 -0.663212 0.635083 + outer loop + vertex 1.707 0.954693 2.43893 + vertex 1.70938 0.957232 2.4401 + vertex 1.70593 0.956295 2.44127 + endloop + endfacet + facet normal 0.426265 -0.675895 0.601219 + outer loop + vertex 1.71041 0.954854 2.4367 + vertex 1.70938 0.957232 2.4401 + vertex 1.707 0.954693 2.43893 + endloop + endfacet + facet normal 0.431197 -0.673143 0.60079 + outer loop + vertex 1.71041 0.954854 2.4367 + vertex 1.71391 0.95889 2.43871 + vertex 1.70938 0.957232 2.4401 + endloop + endfacet + facet normal 0.369818 -0.650797 0.663097 + outer loop + vertex 1.71041 0.954854 2.4367 + vertex 1.71387 0.955818 2.43572 + vertex 1.71391 0.95889 2.43871 + endloop + endfacet + facet normal 0.398844 -0.568664 0.719406 + outer loop + vertex 1.70938 0.957232 2.4401 + vertex 1.70862 0.959785 2.44254 + vertex 1.70593 0.956295 2.44127 + endloop + endfacet + facet normal 0.426263 -0.582881 0.691773 + outer loop + vertex 1.71391 0.95889 2.43871 + vertex 1.71173 0.960326 2.44126 + vertex 1.70938 0.957232 2.4401 + endloop + endfacet + facet normal 0.395667 -0.570156 0.719979 + outer loop + vertex 1.71173 0.960326 2.44126 + vertex 1.70862 0.959785 2.44254 + vertex 1.70938 0.957232 2.4401 + endloop + endfacet + facet normal 0.405741 -0.452481 0.794125 + outer loop + vertex 1.71173 0.960326 2.44126 + vertex 1.71276 0.964103 2.44289 + vertex 1.70862 0.959785 2.44254 + endloop + endfacet + facet normal 0.416965 -0.462312 0.782565 + outer loop + vertex 1.71276 0.964103 2.44289 + vertex 1.70843 0.963553 2.44487 + vertex 1.70862 0.959785 2.44254 + endloop + endfacet + facet normal 0.423157 -0.396934 0.814483 + outer loop + vertex 1.70938 0.967342 2.44622 + vertex 1.70652 0.965096 2.44661 + vertex 1.70843 0.963553 2.44487 + endloop + endfacet + facet normal 0.47669 -0.399246 0.783179 + outer loop + vertex 1.70938 0.967342 2.44622 + vertex 1.70843 0.963553 2.44487 + vertex 1.71294 0.968825 2.44481 + endloop + endfacet + facet normal 0.426027 -0.355284 0.832031 + outer loop + vertex 1.71294 0.968825 2.44481 + vertex 1.70843 0.963553 2.44487 + vertex 1.71276 0.964103 2.44289 + endloop + endfacet + facet normal 0.359858 -0.304517 0.881914 + outer loop + vertex 1.70938 0.967342 2.44622 + vertex 1.70747 0.968973 2.44756 + vertex 1.70652 0.965096 2.44661 + endloop + endfacet + facet normal 0.461614 -0.321579 0.82674 + outer loop + vertex 1.71294 0.968825 2.44481 + vertex 1.71113 0.970379 2.44643 + vertex 1.70938 0.967342 2.44622 + endloop + endfacet + facet normal 0.3813 -0.278962 0.881357 + outer loop + vertex 1.71113 0.970379 2.44643 + vertex 1.70747 0.968973 2.44756 + vertex 1.70938 0.967342 2.44622 + endloop + endfacet + facet normal 0.369342 -0.233096 0.899585 + outer loop + vertex 1.71113 0.970379 2.44643 + vertex 1.71144 0.973696 2.44716 + vertex 1.70747 0.968973 2.44756 + endloop + endfacet + facet normal 0.388065 -0.249888 0.887109 + outer loop + vertex 1.71144 0.973696 2.44716 + vertex 1.70773 0.973752 2.4488 + vertex 1.70747 0.968973 2.44756 + endloop + endfacet + facet normal 0.39322 -0.201413 0.897113 + outer loop + vertex 1.71144 0.973696 2.44716 + vertex 1.71252 0.978915 2.44786 + vertex 1.70773 0.973752 2.4488 + endloop + endfacet + facet normal 0.429375 -0.239758 0.87072 + outer loop + vertex 1.70773 0.973752 2.4488 + vertex 1.71252 0.978915 2.44786 + vertex 1.70798 0.978678 2.45003 + endloop + endfacet + facet normal 0.411821 -0.24146 0.878692 + outer loop + vertex 1.7087 0.982779 2.45082 + vertex 1.70609 0.980251 2.45135 + vertex 1.70798 0.978678 2.45003 + endloop + endfacet + facet normal 0.472879 -0.245939 0.846108 + outer loop + vertex 1.7087 0.982779 2.45082 + vertex 1.70798 0.978678 2.45003 + vertex 1.71225 0.984211 2.44925 + endloop + endfacet + facet normal 0.431124 -0.209275 0.877688 + outer loop + vertex 1.71225 0.984211 2.44925 + vertex 1.70798 0.978678 2.45003 + vertex 1.71252 0.978915 2.44786 + endloop + endfacet + facet normal 0.396925 -0.223614 0.890195 + outer loop + vertex 1.7087 0.982779 2.45082 + vertex 1.70639 0.983618 2.45206 + vertex 1.70609 0.980251 2.45135 + endloop + endfacet + facet normal 0.492706 -0.199399 0.847043 + outer loop + vertex 1.71225 0.984211 2.44925 + vertex 1.71339 0.989523 2.44984 + vertex 1.71009 0.986728 2.4511 + endloop + endfacet + facet normal 0.468299 -0.225651 0.85427 + outer loop + vertex 1.7087 0.982779 2.45082 + vertex 1.71225 0.984211 2.44925 + vertex 1.71009 0.986728 2.4511 + endloop + endfacet + facet normal 0.404016 -0.205709 0.891322 + outer loop + vertex 1.71009 0.986728 2.4511 + vertex 1.70639 0.983618 2.45206 + vertex 1.7087 0.982779 2.45082 + endloop + endfacet + facet normal 0.417102 -0.224587 0.880674 + outer loop + vertex 1.70757 0.988891 2.45284 + vertex 1.70639 0.983618 2.45206 + vertex 1.71009 0.986728 2.4511 + endloop + endfacet + facet normal 0.509623 -0.227154 0.829871 + outer loop + vertex 1.71339 0.989523 2.44984 + vertex 1.71127 0.990525 2.45141 + vertex 1.71009 0.986728 2.4511 + endloop + endfacet + facet normal 0.430945 -0.206647 0.878398 + outer loop + vertex 1.71127 0.990525 2.45141 + vertex 1.70757 0.988891 2.45284 + vertex 1.71009 0.986728 2.4511 + endloop + endfacet + facet normal 0.429968 -0.203343 0.879647 + outer loop + vertex 1.71127 0.990525 2.45141 + vertex 1.71105 0.993716 2.45226 + vertex 1.70757 0.988891 2.45284 + endloop + endfacet + facet normal 0.453052 -0.221942 0.863415 + outer loop + vertex 1.71105 0.993716 2.45226 + vertex 1.70746 0.994206 2.45427 + vertex 1.70757 0.988891 2.45284 + endloop + endfacet + facet normal 0.460101 -0.187985 0.867738 + outer loop + vertex 1.71105 0.993716 2.45226 + vertex 1.71145 0.998297 2.45304 + vertex 1.70746 0.994206 2.45427 + endloop + endfacet + facet normal 0.494218 -0.230173 0.838313 + outer loop + vertex 1.70746 0.994206 2.45427 + vertex 1.71145 0.998297 2.45304 + vertex 1.70878 0.999497 2.45494 + endloop + endfacet + facet normal 0.546305 -0.201689 0.812941 + outer loop + vertex 1.70884 1.00295 2.45576 + vertex 1.70878 0.999497 2.45494 + vertex 1.71171 1.00368 2.45402 + endloop + endfacet + facet normal 0.517647 -0.176251 0.837244 + outer loop + vertex 1.71171 1.00368 2.45402 + vertex 1.70878 0.999497 2.45494 + vertex 1.71145 0.998297 2.45304 + endloop + endfacet + facet normal 0.589319 -0.135216 0.796505 + outer loop + vertex 1.71171 1.00368 2.45402 + vertex 1.71248 1.00926 2.45439 + vertex 1.70963 1.00672 2.45607 + endloop + endfacet + facet normal 0.544635 -0.180989 0.818911 + outer loop + vertex 1.70884 1.00295 2.45576 + vertex 1.71171 1.00368 2.45402 + vertex 1.70963 1.00672 2.45607 + endloop + endfacet + facet normal 0.628681 -0.110701 0.769744 + outer loop + vertex 1.71248 1.00926 2.45439 + vertex 1.71258 1.01337 2.4549 + vertex 1.71022 1.01137 2.45654 + endloop + endfacet + facet normal 0.600424 -0.155737 0.78437 + outer loop + vertex 1.70963 1.00672 2.45607 + vertex 1.71248 1.00926 2.45439 + vertex 1.71022 1.01137 2.45654 + endloop + endfacet + facet normal 0.490366 -0.14919 0.858652 + outer loop + vertex 1.71022 1.01137 2.45654 + vertex 1.70683 1.00851 2.45798 + vertex 1.70963 1.00672 2.45607 + endloop + endfacet + facet normal 0.501179 -0.166777 0.84912 + outer loop + vertex 1.7076 1.01434 2.45867 + vertex 1.70683 1.00851 2.45798 + vertex 1.71022 1.01137 2.45654 + endloop + endfacet + facet normal 0.629225 -0.111849 0.769133 + outer loop + vertex 1.71258 1.01337 2.4549 + vertex 1.71109 1.01523 2.45639 + vertex 1.71022 1.01137 2.45654 + endloop + endfacet + facet normal 0.561245 -0.0944409 0.822244 + outer loop + vertex 1.71109 1.01523 2.45639 + vertex 1.7076 1.01434 2.45867 + vertex 1.71022 1.01137 2.45654 + endloop + endfacet + facet normal 0.558897 -0.0762756 0.825722 + outer loop + vertex 1.71109 1.01523 2.45639 + vertex 1.71085 1.01896 2.45689 + vertex 1.7076 1.01434 2.45867 + endloop + endfacet + facet normal 0.629086 -0.149823 0.762761 + outer loop + vertex 1.71085 1.01896 2.45689 + vertex 1.70815 1.02002 2.45933 + vertex 1.7076 1.01434 2.45867 + endloop + endfacet + facet normal 0.650445 -0.0784119 0.755495 + outer loop + vertex 1.71085 1.01896 2.45689 + vertex 1.71086 1.02374 2.45738 + vertex 1.70815 1.02002 2.45933 + endloop + endfacet + facet normal 0.692635 -0.13354 0.708819 + outer loop + vertex 1.70815 1.02002 2.45933 + vertex 1.71086 1.02374 2.45738 + vertex 1.70844 1.0245 2.45989 + endloop + endfacet + facet normal 0.611048 -0.132945 0.78035 + outer loop + vertex 1.70822 1.02776 2.46062 + vertex 1.70633 1.02532 2.46168 + vertex 1.70844 1.0245 2.45989 + endloop + endfacet + facet normal 0.733156 -0.100159 0.672645 + outer loop + vertex 1.70822 1.02776 2.46062 + vertex 1.70844 1.0245 2.45989 + vertex 1.71068 1.02887 2.4581 + endloop + endfacet + facet normal 0.706464 -0.0736937 0.703901 + outer loop + vertex 1.71068 1.02887 2.4581 + vertex 1.70844 1.0245 2.45989 + vertex 1.71086 1.02374 2.45738 + endloop + endfacet + facet normal 0.597135 -0.116389 0.793652 + outer loop + vertex 1.70822 1.02776 2.46062 + vertex 1.70609 1.02871 2.46236 + vertex 1.70633 1.02532 2.46168 + endloop + endfacet + facet normal 0.749698 -0.0493655 0.659937 + outer loop + vertex 1.71068 1.02887 2.4581 + vertex 1.71123 1.0343 2.45788 + vertex 1.70876 1.03161 2.46049 + endloop + endfacet + facet normal 0.730083 -0.07945 0.678724 + outer loop + vertex 1.70822 1.02776 2.46062 + vertex 1.71068 1.02887 2.4581 + vertex 1.70876 1.03161 2.46049 + endloop + endfacet + facet normal 0.615848 -0.0596491 0.785604 + outer loop + vertex 1.70876 1.03161 2.46049 + vertex 1.70609 1.02871 2.46236 + vertex 1.70822 1.02776 2.46062 + endloop + endfacet + facet normal 0.649944 -0.113117 0.751517 + outer loop + vertex 1.70638 1.03343 2.46282 + vertex 1.70609 1.02871 2.46236 + vertex 1.70876 1.03161 2.46049 + endloop + endfacet + facet normal 0.769848 -0.0343748 0.637301 + outer loop + vertex 1.71123 1.0343 2.45788 + vertex 1.71162 1.03807 2.45761 + vertex 1.70927 1.03696 2.4604 + endloop + endfacet + facet normal 0.754749 -0.0605332 0.653215 + outer loop + vertex 1.70876 1.03161 2.46049 + vertex 1.71123 1.0343 2.45788 + vertex 1.70927 1.03696 2.4604 + endloop + endfacet + facet normal 0.678483 -0.0518636 0.732784 + outer loop + vertex 1.70927 1.03696 2.4604 + vertex 1.70638 1.03343 2.46282 + vertex 1.70876 1.03161 2.46049 + endloop + endfacet + facet normal 0.706776 -0.0970729 0.700746 + outer loop + vertex 1.70627 1.03872 2.46367 + vertex 1.70638 1.03343 2.46282 + vertex 1.70927 1.03696 2.4604 + endloop + endfacet + facet normal 0.740236 -0.0315894 0.671605 + outer loop + vertex 1.71315 1.04111 2.45605 + vertex 1.71354 1.04529 2.45582 + vertex 1.71121 1.04136 2.4582 + endloop + endfacet + facet normal 0.740633 -0.0267009 0.671379 + outer loop + vertex 1.71162 1.03807 2.45761 + vertex 1.71315 1.04111 2.45605 + vertex 1.71121 1.04136 2.4582 + endloop + endfacet + facet normal 0.767013 -0.0180616 0.641378 + outer loop + vertex 1.71162 1.03807 2.45761 + vertex 1.71121 1.04136 2.4582 + vertex 1.70927 1.03696 2.4604 + endloop + endfacet + facet normal 0.788976 -0.0419158 0.612993 + outer loop + vertex 1.70927 1.03696 2.4604 + vertex 1.71121 1.04136 2.4582 + vertex 1.70909 1.04248 2.461 + endloop + endfacet + facet normal 0.721558 -0.0525978 0.690354 + outer loop + vertex 1.70909 1.04248 2.461 + vertex 1.70627 1.03872 2.46367 + vertex 1.70927 1.03696 2.4604 + endloop + endfacet + facet normal 0.748902 -0.0978884 0.655411 + outer loop + vertex 1.7069 1.04439 2.46379 + vertex 1.70627 1.03872 2.46367 + vertex 1.70909 1.04248 2.461 + endloop + endfacet + facet normal 0.748143 -0.0982418 0.656225 + outer loop + vertex 1.71354 1.04529 2.45582 + vertex 1.71396 1.05079 2.45615 + vertex 1.71153 1.0468 2.45834 + endloop + endfacet + facet normal 0.761967 -0.0607393 0.644761 + outer loop + vertex 1.71121 1.04136 2.4582 + vertex 1.71354 1.04529 2.45582 + vertex 1.71153 1.0468 2.45834 + endloop + endfacet + facet normal 0.784352 -0.0613563 0.617274 + outer loop + vertex 1.71121 1.04136 2.4582 + vertex 1.71153 1.0468 2.45834 + vertex 1.70909 1.04248 2.461 + endloop + endfacet + facet normal 0.797481 -0.0806909 0.597923 + outer loop + vertex 1.71153 1.0468 2.45834 + vertex 1.70958 1.04836 2.46115 + vertex 1.70909 1.04248 2.461 + endloop + endfacet + facet normal 0.757041 -0.0786358 0.648618 + outer loop + vertex 1.70958 1.04836 2.46115 + vertex 1.7069 1.04439 2.46379 + vertex 1.70909 1.04248 2.461 + endloop + endfacet + facet normal 0.749206 -0.0664636 0.658993 + outer loop + vertex 1.70724 1.04966 2.46394 + vertex 1.7069 1.04439 2.46379 + vertex 1.70958 1.04836 2.46115 + endloop + endfacet + facet normal 0.592986 -0.551603 0.586602 + outer loop + vertex 1.71396 1.05079 2.45615 + vertex 1.715 1.055 2.45907 + vertex 1.71408 1.055 2.46 + endloop + endfacet + facet normal 0.872191 -0.342591 0.349163 + outer loop + vertex 1.71153 1.0468 2.45834 + vertex 1.71396 1.05079 2.45615 + vertex 1.71408 1.055 2.46 + endloop + endfacet + facet normal 0.672337 -0.342634 0.656175 + outer loop + vertex 1.71153 1.0468 2.45834 + vertex 1.71408 1.055 2.46 + vertex 1.70958 1.04836 2.46115 + endloop + endfacet + facet normal 0.290856 -0.0317122 0.956241 + outer loop + vertex 1.71408 1.055 2.46 + vertex 1.70987 1.05397 2.46125 + vertex 1.70958 1.04836 2.46115 + endloop + endfacet + facet normal 0.753673 -0.0505392 0.655304 + outer loop + vertex 1.70987 1.05397 2.46125 + vertex 1.70724 1.04966 2.46394 + vertex 1.70958 1.04836 2.46115 + endloop + endfacet + facet normal 0.737091 -0.0279735 0.675214 + outer loop + vertex 1.70735 1.05489 2.46403 + vertex 1.70724 1.04966 2.46394 + vertex 1.70987 1.05397 2.46125 + endloop + endfacet + facet normal 0.272571 0.0485186 0.960912 + outer loop + vertex 1.71408 1.055 2.46 + vertex 1.71319 1.06 2.46 + vertex 1.70987 1.05397 2.46125 + endloop + endfacet + facet normal 0.326153 0.0157475 0.945186 + outer loop + vertex 1.71319 1.06 2.46 + vertex 1.70968 1.05898 2.46123 + vertex 1.70987 1.05397 2.46125 + endloop + endfacet + facet normal 0.746636 0.0304871 0.664534 + outer loop + vertex 1.70968 1.05898 2.46123 + vertex 1.70735 1.05489 2.46403 + vertex 1.70987 1.05397 2.46125 + endloop + endfacet + facet normal 0.762138 0.00990048 0.647339 + outer loop + vertex 1.70727 1.06019 2.46405 + vertex 1.70735 1.05489 2.46403 + vertex 1.70968 1.05898 2.46123 + endloop + endfacet + facet normal 0.329421 0.00329075 0.944177 + outer loop + vertex 1.71319 1.06 2.46 + vertex 1.71314 1.065 2.46 + vertex 1.70968 1.05898 2.46123 + endloop + endfacet + facet normal 0.287339 0.030176 0.957353 + outer loop + vertex 1.71314 1.065 2.46 + vertex 1.70944 1.06409 2.46114 + vertex 1.70968 1.05898 2.46123 + endloop + endfacet + facet normal 0.769233 0.0475236 0.637199 + outer loop + vertex 1.70944 1.06409 2.46114 + vertex 1.70727 1.06019 2.46405 + vertex 1.70968 1.05898 2.46123 + endloop + endfacet + facet normal 0.77911 0.0336577 0.625982 + outer loop + vertex 1.70721 1.06535 2.46384 + vertex 1.70727 1.06019 2.46405 + vertex 1.70944 1.06409 2.46114 + endloop + endfacet + facet normal 0.2911 0.0139709 0.956591 + outer loop + vertex 1.71314 1.065 2.46 + vertex 1.7129 1.07 2.46 + vertex 1.70944 1.06409 2.46114 + endloop + endfacet + facet normal 0.2785 0.0220457 0.960183 + outer loop + vertex 1.7129 1.07 2.46 + vertex 1.70909 1.06907 2.46113 + vertex 1.70944 1.06409 2.46114 + endloop + endfacet + facet normal 0.783455 0.0564336 0.618881 + outer loop + vertex 1.70909 1.06907 2.46113 + vertex 1.70721 1.06535 2.46384 + vertex 1.70944 1.06409 2.46114 + endloop + endfacet + facet normal 0.801623 0.0312439 0.597014 + outer loop + vertex 1.70708 1.07004 2.46378 + vertex 1.70721 1.06535 2.46384 + vertex 1.70909 1.06907 2.46113 + endloop + endfacet + facet normal 0.276926 0.0287998 0.96046 + outer loop + vertex 1.7129 1.07 2.46 + vertex 1.71238 1.075 2.46 + vertex 1.70909 1.06907 2.46113 + endloop + endfacet + facet normal 0.378153 -0.0340757 0.925116 + outer loop + vertex 1.71238 1.075 2.46 + vertex 1.70838 1.0732 2.46157 + vertex 1.70909 1.06907 2.46113 + endloop + endfacet + facet normal 0.807377 0.0751482 0.585231 + outer loop + vertex 1.70838 1.0732 2.46157 + vertex 1.70708 1.07004 2.46378 + vertex 1.70909 1.06907 2.46113 + endloop + endfacet + facet normal 0.846256 0.02201 0.532321 + outer loop + vertex 1.70685 1.07483 2.46394 + vertex 1.70708 1.07004 2.46378 + vertex 1.70838 1.0732 2.46157 + endloop + endfacet + facet normal 0.459785 0.639961 -0.615668 + outer loop + vertex 1.71 1.08 2.46342 + vertex 1.71238 1.075 2.46 + vertex 1.71 1.07671 2.46 + endloop + endfacet + facet normal -0.229916 -0.621616 0.74882 + outer loop + vertex 1.71 1.08 2.46342 + vertex 1.7084 1.07872 2.46187 + vertex 1.71238 1.075 2.46 + endloop + endfacet + facet normal 0.384376 -0.0507434 0.921781 + outer loop + vertex 1.7084 1.07872 2.46187 + vertex 1.70838 1.0732 2.46157 + vertex 1.71238 1.075 2.46 + endloop + endfacet + facet normal 0.82897 -0.0319728 0.558378 + outer loop + vertex 1.7084 1.07872 2.46187 + vertex 1.70685 1.07483 2.46394 + vertex 1.70838 1.0732 2.46157 + endloop + endfacet + facet normal 0.808058 -0.00733515 0.589057 + outer loop + vertex 1.70672 1.08009 2.46418 + vertex 1.70685 1.07483 2.46394 + vertex 1.7084 1.07872 2.46187 + endloop + endfacet + facet normal -0.685349 -0.0247439 0.727794 + outer loop + vertex 1.71 1.085 2.46359 + vertex 1.7084 1.07872 2.46187 + vertex 1.71 1.08 2.46342 + endloop + endfacet + facet normal -0.270673 -0.189961 0.943743 + outer loop + vertex 1.70787 1.08422 2.46282 + vertex 1.7084 1.07872 2.46187 + vertex 1.71 1.085 2.46359 + endloop + endfacet + facet normal 0.802154 -0.0270945 0.596502 + outer loop + vertex 1.70787 1.08422 2.46282 + vertex 1.70672 1.08009 2.46418 + vertex 1.7084 1.07872 2.46187 + endloop + endfacet + facet normal 0.910922 -0.124407 0.393374 + outer loop + vertex 1.70716 1.08548 2.46487 + vertex 1.70672 1.08009 2.46418 + vertex 1.70787 1.08422 2.46282 + endloop + endfacet + facet normal -0.292855 -0.132569 0.946922 + outer loop + vertex 1.71 1.09 2.46429 + vertex 1.70787 1.08422 2.46282 + vertex 1.71 1.085 2.46359 + endloop + endfacet + facet normal -0.106174 -0.207796 0.972393 + outer loop + vertex 1.70821 1.08813 2.46369 + vertex 1.70787 1.08422 2.46282 + vertex 1.71 1.09 2.46429 + endloop + endfacet + facet normal 0.893797 -0.169418 0.41524 + outer loop + vertex 1.70821 1.08813 2.46369 + vertex 1.70716 1.08548 2.46487 + vertex 1.70787 1.08422 2.46282 + endloop + endfacet + facet normal 0.848669 -0.455302 -0.269185 + outer loop + vertex 1.71 1.09 2.46618 + vertex 1.70716 1.08548 2.46487 + vertex 1.70821 1.08813 2.46369 + endloop + endfacet + facet normal -0.170118 -0.147196 0.974368 + outer loop + vertex 1.71 1.09 2.46429 + vertex 1.71 1.0947 2.465 + vertex 1.70821 1.08813 2.46369 + endloop + endfacet + facet normal 0.847839 -0.129139 -0.514288 + outer loop + vertex 1.70821 1.08813 2.46369 + vertex 1.71 1.0947 2.465 + vertex 1.71 1.09 2.46618 + endloop + endfacet + facet normal -0.631514 0.242883 0.736341 + outer loop + vertex 1.70916 1.94091 2.46366 + vertex 1.71 1.93903 2.465 + vertex 1.71 1.94 2.46468 + endloop + endfacet + facet normal 0.931363 0.198346 -0.305324 + outer loop + vertex 1.70916 1.94091 2.46366 + vertex 1.71 1.94 2.46563 + vertex 1.71 1.93903 2.465 + endloop + endfacet + facet normal -0.748729 0.0502389 0.660969 + outer loop + vertex 1.71 1.945 2.4643 + vertex 1.70916 1.94091 2.46366 + vertex 1.71 1.94 2.46468 + endloop + endfacet + facet normal 0.706687 -0.0344424 -0.706687 + outer loop + vertex 1.7107 1.945 2.465 + vertex 1.70916 1.94091 2.46366 + vertex 1.71 1.945 2.4643 + endloop + endfacet + facet normal 0.87238 -0.179438 -0.454704 + outer loop + vertex 1.7107 1.945 2.465 + vertex 1.71 1.94 2.46563 + vertex 1.70916 1.94091 2.46366 + endloop + endfacet + facet normal -0.02313 0.128193 0.99148 + outer loop + vertex 1.70761 1.94451 2.46499 + vertex 1.71 1.94 2.46563 + vertex 1.7107 1.945 2.465 + endloop + endfacet + facet normal -0.0030098 3.00671e-05 0.999995 + outer loop + vertex 1.71075 1.95 2.465 + vertex 1.70761 1.94451 2.46499 + vertex 1.7107 1.945 2.465 + endloop + endfacet + facet normal -0.0424356 0.0226263 0.998843 + outer loop + vertex 1.70736 1.94914 2.46488 + vertex 1.70761 1.94451 2.46499 + vertex 1.71075 1.95 2.465 + endloop + endfacet + facet normal -0.0375747 0.00338184 0.999288 + outer loop + vertex 1.7112 1.955 2.465 + vertex 1.70736 1.94914 2.46488 + vertex 1.71075 1.95 2.465 + endloop + endfacet + facet normal -0.19818 0.109109 0.974074 + outer loop + vertex 1.70725 1.95379 2.46433 + vertex 1.70736 1.94914 2.46488 + vertex 1.7112 1.955 2.465 + endloop + endfacet + facet normal 0.675798 -0.605601 -0.420172 + outer loop + vertex 1.71 1.95713 2.46 + vertex 1.7112 1.955 2.465 + vertex 1.71 1.955 2.46307 + endloop + endfacet + facet normal 0.574319 -0.694354 -0.433625 + outer loop + vertex 1.71 1.95713 2.46 + vertex 1.71347 1.96 2.46 + vertex 1.7112 1.955 2.465 + endloop + endfacet + facet normal -0.00421489 0.708048 0.706152 + outer loop + vertex 1.71347 1.96 2.46 + vertex 1.70962 1.95855 2.46143 + vertex 1.7112 1.955 2.465 + endloop + endfacet + facet normal -0.308937 0.602519 0.735886 + outer loop + vertex 1.70962 1.95855 2.46143 + vertex 1.70725 1.95379 2.46433 + vertex 1.7112 1.955 2.465 + endloop + endfacet + facet normal 0.696054 0.087849 0.712595 + outer loop + vertex 1.7071 1.95881 2.46386 + vertex 1.70725 1.95379 2.46433 + vertex 1.70962 1.95855 2.46143 + endloop + endfacet + facet normal 0.348006 0.00139392 0.937491 + outer loop + vertex 1.71347 1.96 2.46 + vertex 1.71345 1.965 2.46 + vertex 1.70962 1.95855 2.46143 + endloop + endfacet + facet normal 0.201503 0.0965987 0.974713 + outer loop + vertex 1.71345 1.965 2.46 + vertex 1.7096 1.96365 2.46093 + vertex 1.70962 1.95855 2.46143 + endloop + endfacet + facet normal 0.696109 0.0734573 0.714168 + outer loop + vertex 1.7096 1.96365 2.46093 + vertex 1.7071 1.95881 2.46386 + vertex 1.70962 1.95855 2.46143 + endloop + endfacet + facet normal 0.754491 0.00836528 0.656257 + outer loop + vertex 1.70712 1.96408 2.46378 + vertex 1.7071 1.95881 2.46386 + vertex 1.7096 1.96365 2.46093 + endloop + endfacet + facet normal 0.237545 -0.0085519 0.971339 + outer loop + vertex 1.71345 1.965 2.46 + vertex 1.71363 1.97 2.46 + vertex 1.7096 1.96365 2.46093 + endloop + endfacet + facet normal 0.247332 -0.0151373 0.968813 + outer loop + vertex 1.71363 1.97 2.46 + vertex 1.70975 1.96882 2.46097 + vertex 1.7096 1.96365 2.46093 + endloop + endfacet + facet normal 0.751582 -0.027038 0.659085 + outer loop + vertex 1.70975 1.96882 2.46097 + vertex 1.70712 1.96408 2.46378 + vertex 1.7096 1.96365 2.46093 + endloop + endfacet + facet normal 0.727661 0.0020888 0.685933 + outer loop + vertex 1.70712 1.96927 2.46375 + vertex 1.70712 1.96408 2.46378 + vertex 1.70975 1.96882 2.46097 + endloop + endfacet + facet normal 0.244153 -0.00390594 0.969729 + outer loop + vertex 1.71363 1.97 2.46 + vertex 1.71371 1.975 2.46 + vertex 1.70975 1.96882 2.46097 + endloop + endfacet + facet normal 0.26602 -0.0188725 0.963783 + outer loop + vertex 1.71371 1.975 2.46 + vertex 1.70976 1.97369 2.46106 + vertex 1.70975 1.96882 2.46097 + endloop + endfacet + facet normal 0.726187 -0.0152585 0.687328 + outer loop + vertex 1.70976 1.97369 2.46106 + vertex 1.70712 1.96927 2.46375 + vertex 1.70975 1.96882 2.46097 + endloop + endfacet + facet normal 0.703107 0.0128924 0.710967 + outer loop + vertex 1.70699 1.97422 2.4638 + vertex 1.70712 1.96927 2.46375 + vertex 1.70976 1.97369 2.46106 + endloop + endfacet + facet normal 0.262827 -0.00841564 0.964806 + outer loop + vertex 1.71371 1.975 2.46 + vertex 1.71387 1.98 2.46 + vertex 1.70976 1.97369 2.46106 + endloop + endfacet + facet normal 0.213014 0.0260233 0.976703 + outer loop + vertex 1.71387 1.98 2.46 + vertex 1.70937 1.97812 2.46103 + vertex 1.70976 1.97369 2.46106 + endloop + endfacet + facet normal 0.706781 0.067382 0.704216 + outer loop + vertex 1.70937 1.97812 2.46103 + vertex 1.70699 1.97422 2.4638 + vertex 1.70976 1.97369 2.46106 + endloop + endfacet + facet normal 0.735416 0.0306094 0.676924 + outer loop + vertex 1.70682 1.9791 2.46376 + vertex 1.70699 1.97422 2.4638 + vertex 1.70937 1.97812 2.46103 + endloop + endfacet + facet normal 0.118142 0.58717 0.800796 + outer loop + vertex 1.715 1.98 2.45891 + vertex 1.71371 1.98452 2.45579 + vertex 1.71153 1.98134 2.45844 + endloop + endfacet + facet normal 0.303553 0.899353 0.314674 + outer loop + vertex 1.71387 1.98 2.46 + vertex 1.715 1.98 2.45891 + vertex 1.71153 1.98134 2.45844 + endloop + endfacet + facet normal -0.109421 0.666992 0.736986 + outer loop + vertex 1.71387 1.98 2.46 + vertex 1.71153 1.98134 2.45844 + vertex 1.70937 1.97812 2.46103 + endloop + endfacet + facet normal 0.706979 0.0910512 0.701349 + outer loop + vertex 1.71153 1.98134 2.45844 + vertex 1.709 1.98273 2.4608 + vertex 1.70937 1.97812 2.46103 + endloop + endfacet + facet normal 0.743467 0.0920461 0.662408 + outer loop + vertex 1.709 1.98273 2.4608 + vertex 1.70682 1.9791 2.46376 + vertex 1.70937 1.97812 2.46103 + endloop + endfacet + facet normal 0.773959 0.0483236 0.631389 + outer loop + vertex 1.70671 1.98394 2.46352 + vertex 1.70682 1.9791 2.46376 + vertex 1.709 1.98273 2.4608 + endloop + endfacet + facet normal 0.623212 0.0750663 0.778442 + outer loop + vertex 1.71371 1.98452 2.45579 + vertex 1.714 1.98903 2.45512 + vertex 1.71131 1.98621 2.45755 + endloop + endfacet + facet normal 0.655865 0.164708 0.73669 + outer loop + vertex 1.71153 1.98134 2.45844 + vertex 1.71371 1.98452 2.45579 + vertex 1.71131 1.98621 2.45755 + endloop + endfacet + facet normal 0.719723 0.156528 0.676386 + outer loop + vertex 1.71153 1.98134 2.45844 + vertex 1.71131 1.98621 2.45755 + vertex 1.709 1.98273 2.4608 + endloop + endfacet + facet normal 0.794132 0.0419136 0.606298 + outer loop + vertex 1.71131 1.98621 2.45755 + vertex 1.70909 1.98774 2.46034 + vertex 1.709 1.98273 2.4608 + endloop + endfacet + facet normal 0.773298 0.0446657 0.632467 + outer loop + vertex 1.70909 1.98774 2.46034 + vertex 1.70671 1.98394 2.46352 + vertex 1.709 1.98273 2.4608 + endloop + endfacet + facet normal 0.749754 0.0798207 0.656885 + outer loop + vertex 1.70648 1.98871 2.46321 + vertex 1.70671 1.98394 2.46352 + vertex 1.70909 1.98774 2.46034 + endloop + endfacet + facet normal 0.644508 0.04178 0.763455 + outer loop + vertex 1.71131 1.98621 2.45755 + vertex 1.714 1.98903 2.45512 + vertex 1.71228 1.99236 2.45639 + endloop + endfacet + facet normal 0.782004 -0.00656841 0.623239 + outer loop + vertex 1.71131 1.98621 2.45755 + vertex 1.71228 1.99236 2.45639 + vertex 1.70909 1.98774 2.46034 + endloop + endfacet + facet normal 0.74171 0.0596779 0.66806 + outer loop + vertex 1.71228 1.99236 2.45639 + vertex 1.70881 1.99244 2.46023 + vertex 1.70909 1.98774 2.46034 + endloop + endfacet + facet normal 0.747512 0.059862 0.661546 + outer loop + vertex 1.70881 1.99244 2.46023 + vertex 1.70648 1.98871 2.46321 + vertex 1.70909 1.98774 2.46034 + endloop + endfacet + facet normal 0.704066 0.118004 0.700262 + outer loop + vertex 1.70569 1.99369 2.46317 + vertex 1.70648 1.98871 2.46321 + vertex 1.70881 1.99244 2.46023 + endloop + endfacet + facet normal 0.761611 0.0951374 0.641013 + outer loop + vertex 1.71228 1.99236 2.45639 + vertex 1.71266 1.99789 2.45512 + vertex 1.71057 1.99587 2.4579 + endloop + endfacet + facet normal 0.741142 0.0737991 0.66728 + outer loop + vertex 1.71228 1.99236 2.45639 + vertex 1.71057 1.99587 2.4579 + vertex 1.70881 1.99244 2.46023 + endloop + endfacet + facet normal 0.735361 0.0805408 0.672873 + outer loop + vertex 1.71057 1.99587 2.4579 + vertex 1.7083 1.99669 2.46029 + vertex 1.70881 1.99244 2.46023 + endloop + endfacet + facet normal 0.698079 0.0754995 0.712029 + outer loop + vertex 1.7083 1.99669 2.46029 + vertex 1.70569 1.99369 2.46317 + vertex 1.70881 1.99244 2.46023 + endloop + endfacet + facet normal 0.66162 0.132333 0.738069 + outer loop + vertex 1.70568 1.99859 2.4623 + vertex 1.70569 1.99369 2.46317 + vertex 1.7083 1.99669 2.46029 + endloop + endfacet + facet normal 0.766918 0.0362441 0.640721 + outer loop + vertex 1.71266 1.99789 2.45512 + vertex 1.7125 2.0017 2.45509 + vertex 1.71034 1.99998 2.45778 + endloop + endfacet + facet normal 0.775769 0.0623488 0.627929 + outer loop + vertex 1.71057 1.99587 2.4579 + vertex 1.71266 1.99789 2.45512 + vertex 1.71034 1.99998 2.45778 + endloop + endfacet + facet normal 0.707009 0.0972265 0.700489 + outer loop + vertex 1.70789 2.00011 2.46023 + vertex 1.71034 1.99998 2.45778 + vertex 1.70837 2.00383 2.45923 + endloop + endfacet + facet normal 0.707079 0.0955288 0.700652 + outer loop + vertex 1.70789 2.00011 2.46023 + vertex 1.7083 1.99669 2.46029 + vertex 1.71034 1.99998 2.45778 + endloop + endfacet + facet normal 0.733167 0.0614831 0.677264 + outer loop + vertex 1.7083 1.99669 2.46029 + vertex 1.71057 1.99587 2.4579 + vertex 1.71034 1.99998 2.45778 + endloop + endfacet + facet normal 0.645772 0.0891673 0.758306 + outer loop + vertex 1.7083 1.99669 2.46029 + vertex 1.70789 2.00011 2.46023 + vertex 1.70568 1.99859 2.4623 + endloop + endfacet + facet normal 0.762266 0.0493468 0.64538 + outer loop + vertex 1.7125 2.0017 2.45509 + vertex 1.71103 2.00375 2.45668 + vertex 1.71034 1.99998 2.45778 + endloop + endfacet + facet normal 0.691797 0.0830778 0.717297 + outer loop + vertex 1.71103 2.00375 2.45668 + vertex 1.70837 2.00383 2.45923 + vertex 1.71034 1.99998 2.45778 + endloop + endfacet + facet normal 0.691737 0.0845019 0.717189 + outer loop + vertex 1.71103 2.00375 2.45668 + vertex 1.71004 2.00777 2.45715 + vertex 1.70837 2.00383 2.45923 + endloop + endfacet + facet normal 0.645578 0.123338 0.753669 + outer loop + vertex 1.71004 2.00777 2.45715 + vertex 1.70712 2.00794 2.45963 + vertex 1.70837 2.00383 2.45923 + endloop + endfacet + facet normal 0.713673 0.0867897 0.695082 + outer loop + vertex 1.7122 2.00942 2.45482 + vertex 1.71234 2.01301 2.45422 + vertex 1.71043 2.01158 2.45636 + endloop + endfacet + facet normal 0.706488 0.0747006 0.703771 + outer loop + vertex 1.71043 2.01158 2.45636 + vertex 1.71004 2.00777 2.45715 + vertex 1.7122 2.00942 2.45482 + endloop + endfacet + facet normal 0.606922 0.102509 0.788123 + outer loop + vertex 1.71043 2.01158 2.45636 + vertex 1.70716 2.01273 2.45873 + vertex 1.71004 2.00777 2.45715 + endloop + endfacet + facet normal 0.644926 0.136126 0.752024 + outer loop + vertex 1.70716 2.01273 2.45873 + vertex 1.70712 2.00794 2.45963 + vertex 1.71004 2.00777 2.45715 + endloop + endfacet + facet normal 0.688294 0.0952876 0.719146 + outer loop + vertex 1.71234 2.01301 2.45422 + vertex 1.71206 2.01761 2.45388 + vertex 1.70988 2.01532 2.45627 + endloop + endfacet + facet normal 0.699376 0.12002 0.704605 + outer loop + vertex 1.71043 2.01158 2.45636 + vertex 1.71234 2.01301 2.45422 + vertex 1.70988 2.01532 2.45627 + endloop + endfacet + facet normal 0.607883 0.108413 0.78659 + outer loop + vertex 1.70988 2.01532 2.45627 + vertex 1.70716 2.01273 2.45873 + vertex 1.71043 2.01158 2.45636 + endloop + endfacet + facet normal 0.593327 0.130917 0.794244 + outer loop + vertex 1.70738 2.01752 2.45777 + vertex 1.70716 2.01273 2.45873 + vertex 1.70988 2.01532 2.45627 + endloop + endfacet + facet normal 0.653217 0.101658 0.750315 + outer loop + vertex 1.71206 2.01761 2.45388 + vertex 1.71165 2.02258 2.45356 + vertex 1.70939 2.01984 2.45591 + endloop + endfacet + facet normal 0.666189 0.131869 0.734032 + outer loop + vertex 1.70988 2.01532 2.45627 + vertex 1.71206 2.01761 2.45388 + vertex 1.70939 2.01984 2.45591 + endloop + endfacet + facet normal 0.592151 0.128749 0.795475 + outer loop + vertex 1.70939 2.01984 2.45591 + vertex 1.70738 2.01752 2.45777 + vertex 1.70988 2.01532 2.45627 + endloop + endfacet + facet normal 0.555133 0.174916 0.813161 + outer loop + vertex 1.70615 2.02174 2.45771 + vertex 1.70738 2.01752 2.45777 + vertex 1.70939 2.01984 2.45591 + endloop + endfacet + facet normal 0.606926 0.109891 0.787124 + outer loop + vertex 1.71165 2.02258 2.45356 + vertex 1.71101 2.02804 2.45329 + vertex 1.70864 2.02455 2.45561 + endloop + endfacet + facet normal 0.619986 0.146726 0.770771 + outer loop + vertex 1.70939 2.01984 2.45591 + vertex 1.71165 2.02258 2.45356 + vertex 1.70864 2.02455 2.45561 + endloop + endfacet + facet normal 0.542174 0.138031 0.828851 + outer loop + vertex 1.70864 2.02455 2.45561 + vertex 1.70615 2.02174 2.45771 + vertex 1.70939 2.01984 2.45591 + endloop + endfacet + facet normal 0.503967 0.183163 0.844078 + outer loop + vertex 1.70499 2.02681 2.4573 + vertex 1.70615 2.02174 2.45771 + vertex 1.70864 2.02455 2.45561 + endloop + endfacet + facet normal 0.569829 0.149107 0.808123 + outer loop + vertex 1.70788 2.02852 2.45541 + vertex 1.70864 2.02455 2.45561 + vertex 1.71101 2.02804 2.45329 + endloop + endfacet + facet normal 0.570045 0.16304 0.805274 + outer loop + vertex 1.70788 2.02852 2.45541 + vertex 1.71101 2.02804 2.45329 + vertex 1.70829 2.03266 2.45429 + endloop + endfacet + facet normal 0.531833 0.133817 0.83621 + outer loop + vertex 1.70829 2.03266 2.45429 + vertex 1.71101 2.02804 2.45329 + vertex 1.71161 2.03249 2.4522 + endloop + endfacet + facet normal 0.483961 0.135533 0.86453 + outer loop + vertex 1.70864 2.02455 2.45561 + vertex 1.70788 2.02852 2.45541 + vertex 1.70499 2.02681 2.4573 + endloop + endfacet + facet normal 0.53109 0.151758 0.833614 + outer loop + vertex 1.71161 2.03249 2.4522 + vertex 1.71029 2.03686 2.45225 + vertex 1.70829 2.03266 2.45429 + endloop + endfacet + facet normal 0.457497 0.202387 0.865873 + outer loop + vertex 1.70829 2.03266 2.45429 + vertex 1.71029 2.03686 2.45225 + vertex 1.70609 2.03781 2.45424 + endloop + endfacet + facet normal 0.548177 0.182058 0.816307 + outer loop + vertex 1.71282 2.03848 2.45032 + vertex 1.71296 2.04203 2.44944 + vertex 1.71081 2.04059 2.4512 + endloop + endfacet + facet normal 0.531103 0.159205 0.832216 + outer loop + vertex 1.71081 2.04059 2.4512 + vertex 1.71029 2.03686 2.45225 + vertex 1.71282 2.03848 2.45032 + endloop + endfacet + facet normal 0.442172 0.184616 0.877725 + outer loop + vertex 1.71081 2.04059 2.4512 + vertex 1.70757 2.04154 2.45263 + vertex 1.71029 2.03686 2.45225 + endloop + endfacet + facet normal 0.456694 0.193835 0.86825 + outer loop + vertex 1.70757 2.04154 2.45263 + vertex 1.70609 2.03781 2.45424 + vertex 1.71029 2.03686 2.45225 + endloop + endfacet + facet normal 0.505718 0.195429 0.840272 + outer loop + vertex 1.71296 2.04203 2.44944 + vertex 1.71233 2.04747 2.44855 + vertex 1.70964 2.04441 2.45088 + endloop + endfacet + facet normal 0.521627 0.228618 0.821973 + outer loop + vertex 1.71081 2.04059 2.4512 + vertex 1.71296 2.04203 2.44944 + vertex 1.70964 2.04441 2.45088 + endloop + endfacet + facet normal 0.446039 0.209415 0.870169 + outer loop + vertex 1.70964 2.04441 2.45088 + vertex 1.70757 2.04154 2.45263 + vertex 1.71081 2.04059 2.4512 + endloop + endfacet + facet normal 0.408939 0.242064 0.879872 + outer loop + vertex 1.70521 2.04667 2.45232 + vertex 1.70757 2.04154 2.45263 + vertex 1.70964 2.04441 2.45088 + endloop + endfacet + facet normal 0.468561 0.236394 0.851216 + outer loop + vertex 1.70817 2.04844 2.45057 + vertex 1.70964 2.04441 2.45088 + vertex 1.71233 2.04747 2.44855 + endloop + endfacet + facet normal 0.468902 0.240881 0.849769 + outer loop + vertex 1.70817 2.04844 2.45057 + vertex 1.71233 2.04747 2.44855 + vertex 1.70782 2.05312 2.44944 + endloop + endfacet + facet normal 0.411232 0.188287 0.891872 + outer loop + vertex 1.70782 2.05312 2.44944 + vertex 1.71233 2.04747 2.44855 + vertex 1.71212 2.05239 2.44761 + endloop + endfacet + facet normal 0.398522 0.213911 0.891864 + outer loop + vertex 1.70964 2.04441 2.45088 + vertex 1.70817 2.04844 2.45057 + vertex 1.70521 2.04667 2.45232 + endloop + endfacet + facet normal 0.412845 0.214559 0.885169 + outer loop + vertex 1.71212 2.05239 2.44761 + vertex 1.7101 2.05687 2.44747 + vertex 1.70782 2.05312 2.44944 + endloop + endfacet + facet normal 0.3791 0.239591 0.8938 + outer loop + vertex 1.70782 2.05312 2.44944 + vertex 1.7101 2.05687 2.44747 + vertex 1.70685 2.0574 2.4487 + endloop + endfacet + facet normal 0.454752 0.316255 0.832576 + outer loop + vertex 1.71257 2.05861 2.44576 + vertex 1.71164 2.06276 2.44469 + vertex 1.70983 2.06066 2.44648 + endloop + endfacet + facet normal 0.420078 0.256538 0.870473 + outer loop + vertex 1.70983 2.06066 2.44648 + vertex 1.7101 2.05687 2.44747 + vertex 1.71257 2.05861 2.44576 + endloop + endfacet + facet normal 0.35338 0.25917 0.898862 + outer loop + vertex 1.70983 2.06066 2.44648 + vertex 1.70585 2.06142 2.44782 + vertex 1.7101 2.05687 2.44747 + endloop + endfacet + facet normal 0.381163 0.286674 0.878939 + outer loop + vertex 1.70585 2.06142 2.44782 + vertex 1.70685 2.0574 2.4487 + vertex 1.7101 2.05687 2.44747 + endloop + endfacet + facet normal 0.430961 0.339756 0.835966 + outer loop + vertex 1.70804 2.06361 2.44621 + vertex 1.70983 2.06066 2.44648 + vertex 1.71164 2.06276 2.44469 + endloop + endfacet + facet normal 0.433104 0.393087 0.811113 + outer loop + vertex 1.70804 2.06361 2.44621 + vertex 1.71164 2.06276 2.44469 + vertex 1.7073 2.0672 2.44486 + endloop + endfacet + facet normal 0.419966 0.379731 0.824277 + outer loop + vertex 1.7073 2.0672 2.44486 + vertex 1.71164 2.06276 2.44469 + vertex 1.71157 2.06737 2.4426 + endloop + endfacet + facet normal 0.356371 0.298988 0.885215 + outer loop + vertex 1.70983 2.06066 2.44648 + vertex 1.70804 2.06361 2.44621 + vertex 1.70585 2.06142 2.44782 + endloop + endfacet + facet normal 0.39975 0.530744 0.747336 + outer loop + vertex 1.71356 2.06897 2.44077 + vertex 1.71393 2.07086 2.43922 + vertex 1.71107 2.07109 2.44058 + endloop + endfacet + facet normal 0.353701 0.481643 0.80182 + outer loop + vertex 1.71107 2.07109 2.44058 + vertex 1.71157 2.06737 2.4426 + vertex 1.71356 2.06897 2.44077 + endloop + endfacet + facet normal 0.399882 0.477317 0.782472 + outer loop + vertex 1.71107 2.07109 2.44058 + vertex 1.70741 2.07093 2.44255 + vertex 1.71157 2.06737 2.4426 + endloop + endfacet + facet normal 0.39642 0.47334 0.786639 + outer loop + vertex 1.70741 2.07093 2.44255 + vertex 1.7073 2.0672 2.44486 + vertex 1.71157 2.06737 2.4426 + endloop + endfacet + facet normal 0.416014 0.704814 0.574604 + outer loop + vertex 1.71272 2.07372 2.43724 + vertex 1.71143 2.07633 2.43497 + vertex 1.7092 2.07582 2.43721 + endloop + endfacet + facet normal 0.345395 0.683743 0.642804 + outer loop + vertex 1.7092 2.07582 2.43721 + vertex 1.7057 2.07643 2.43843 + vertex 1.70809 2.07391 2.43983 + endloop + endfacet + facet normal 0.388468 0.659567 0.643478 + outer loop + vertex 1.71272 2.07372 2.43724 + vertex 1.7092 2.07582 2.43721 + vertex 1.70809 2.07391 2.43983 + endloop + endfacet + facet normal 0.406275 0.611535 0.678944 + outer loop + vertex 1.71272 2.07372 2.43724 + vertex 1.70809 2.07391 2.43983 + vertex 1.71107 2.07109 2.44058 + endloop + endfacet + facet normal 0.375557 0.63081 0.678996 + outer loop + vertex 1.71272 2.07372 2.43724 + vertex 1.71107 2.07109 2.44058 + vertex 1.71393 2.07086 2.43922 + endloop + endfacet + facet normal 0.365564 0.581254 0.726985 + outer loop + vertex 1.71107 2.07109 2.44058 + vertex 1.70809 2.07391 2.43983 + vertex 1.70741 2.07093 2.44255 + endloop + endfacet + facet normal -0.227255 0.443888 0.866787 + outer loop + vertex 1.71106 2.085 2.43 + vertex 1.70664 2.08243 2.43016 + vertex 1.70833 2.08036 2.43166 + endloop + endfacet + facet normal 0.173391 0.2397 0.955238 + outer loop + vertex 1.71106 2.085 2.43 + vertex 1.70833 2.08036 2.43166 + vertex 1.715 2.08215 2.43 + endloop + endfacet + facet normal 0.124525 0.384505 0.914686 + outer loop + vertex 1.715 2.08215 2.43 + vertex 1.70833 2.08036 2.43166 + vertex 1.71222 2.07821 2.43203 + endloop + endfacet + facet normal 0.350199 0.775633 0.525124 + outer loop + vertex 1.71143 2.07633 2.43497 + vertex 1.70826 2.07771 2.43503 + vertex 1.7092 2.07582 2.43721 + endloop + endfacet + facet normal 0.338872 0.747702 0.571059 + outer loop + vertex 1.71143 2.07633 2.43497 + vertex 1.71222 2.07821 2.43203 + vertex 1.70826 2.07771 2.43503 + endloop + endfacet + facet normal 0.349819 0.73322 0.583109 + outer loop + vertex 1.71222 2.07821 2.43203 + vertex 1.70833 2.08036 2.43166 + vertex 1.70826 2.07771 2.43503 + endloop + endfacet + facet normal 0.325303 0.777858 0.537695 + outer loop + vertex 1.7092 2.07582 2.43721 + vertex 1.70826 2.07771 2.43503 + vertex 1.7057 2.07643 2.43843 + endloop + endfacet + facet normal 0.0226227 0.0226227 0.999488 + outer loop + vertex 1.71106 2.085 2.43 + vertex 1.71 2.08606 2.43 + vertex 1.70664 2.08243 2.43016 + endloop + endfacet + facet normal 0.137202 0.674933 0.725011 + outer loop + vertex 1.71554 0.953412 2.43106 + vertex 1.72 0.953645 2.43 + vertex 1.71946 0.954124 2.42966 + endloop + endfacet + facet normal 0.180083 0.475034 0.861344 + outer loop + vertex 1.71554 0.953412 2.43106 + vertex 1.71189 0.952521 2.43232 + vertex 1.72 0.953645 2.43 + endloop + endfacet + facet normal 0.294016 -0.616904 0.730057 + outer loop + vertex 1.71189 0.952521 2.43232 + vertex 1.715 0.951262 2.43 + vertex 1.72 0.953645 2.43 + endloop + endfacet + facet normal 0.365554 -0.778136 0.510759 + outer loop + vertex 1.71554 0.953412 2.43106 + vertex 1.71315 0.954029 2.43371 + vertex 1.71189 0.952521 2.43232 + endloop + endfacet + facet normal 0.331771 -0.780898 0.52927 + outer loop + vertex 1.71946 0.954124 2.42966 + vertex 1.71732 0.955098 2.43243 + vertex 1.71554 0.953412 2.43106 + endloop + endfacet + facet normal 0.356314 -0.786541 0.504374 + outer loop + vertex 1.71315 0.954029 2.43371 + vertex 1.71554 0.953412 2.43106 + vertex 1.71732 0.955098 2.43243 + endloop + endfacet + facet normal 0.361223 -0.755972 0.545916 + outer loop + vertex 1.71315 0.954029 2.43371 + vertex 1.71732 0.955098 2.43243 + vertex 1.71387 0.955818 2.43572 + endloop + endfacet + facet normal 0.39473 -0.718288 0.572931 + outer loop + vertex 1.71387 0.955818 2.43572 + vertex 1.71732 0.955098 2.43243 + vertex 1.71704 0.95748 2.43561 + endloop + endfacet + facet normal 0.363404 -0.652509 0.664958 + outer loop + vertex 1.71704 0.95748 2.43561 + vertex 1.71391 0.95889 2.43871 + vertex 1.71387 0.955818 2.43572 + endloop + endfacet + facet normal 0.414125 -0.594061 0.689632 + outer loop + vertex 1.71829 0.960472 2.43744 + vertex 1.71391 0.95889 2.43871 + vertex 1.71704 0.95748 2.43561 + endloop + endfacet + facet normal 0.467573 -0.537632 0.70166 + outer loop + vertex 1.71447 0.962437 2.44105 + vertex 1.71173 0.960326 2.44126 + vertex 1.71391 0.95889 2.43871 + endloop + endfacet + facet normal 0.513028 -0.528242 0.676581 + outer loop + vertex 1.71447 0.962437 2.44105 + vertex 1.71391 0.95889 2.43871 + vertex 1.71778 0.963891 2.43968 + endloop + endfacet + facet normal 0.396146 -0.460687 0.794252 + outer loop + vertex 1.71778 0.963891 2.43968 + vertex 1.71391 0.95889 2.43871 + vertex 1.71829 0.960472 2.43744 + endloop + endfacet + facet normal 0.409155 -0.45262 0.792293 + outer loop + vertex 1.71447 0.962437 2.44105 + vertex 1.71276 0.964103 2.44289 + vertex 1.71173 0.960326 2.44126 + endloop + endfacet + facet normal 0.501803 -0.436465 0.746788 + outer loop + vertex 1.71778 0.963891 2.43968 + vertex 1.71616 0.965413 2.44165 + vertex 1.71447 0.962437 2.44105 + endloop + endfacet + facet normal 0.446681 -0.414559 0.792854 + outer loop + vertex 1.71616 0.965413 2.44165 + vertex 1.71276 0.964103 2.44289 + vertex 1.71447 0.962437 2.44105 + endloop + endfacet + facet normal 0.428341 -0.316535 0.846362 + outer loop + vertex 1.71616 0.965413 2.44165 + vertex 1.7165 0.968781 2.44274 + vertex 1.71276 0.964103 2.44289 + endloop + endfacet + facet normal 0.467369 -0.348889 0.812307 + outer loop + vertex 1.7165 0.968781 2.44274 + vertex 1.71294 0.968825 2.44481 + vertex 1.71276 0.964103 2.44289 + endloop + endfacet + facet normal 0.486676 -0.289684 0.824154 + outer loop + vertex 1.71382 0.972935 2.44573 + vertex 1.71113 0.970379 2.44643 + vertex 1.71294 0.968825 2.44481 + endloop + endfacet + facet normal 0.546488 -0.293511 0.784348 + outer loop + vertex 1.71382 0.972935 2.44573 + vertex 1.71294 0.968825 2.44481 + vertex 1.71755 0.974419 2.44369 + endloop + endfacet + facet normal 0.486267 -0.232379 0.842345 + outer loop + vertex 1.71755 0.974419 2.44369 + vertex 1.71294 0.968825 2.44481 + vertex 1.7165 0.968781 2.44274 + endloop + endfacet + facet normal 0.443002 -0.232434 0.865866 + outer loop + vertex 1.71382 0.972935 2.44573 + vertex 1.71144 0.973696 2.44716 + vertex 1.71113 0.970379 2.44643 + endloop + endfacet + facet normal 0.565341 -0.190096 0.802654 + outer loop + vertex 1.71755 0.974419 2.44369 + vertex 1.71832 0.980003 2.44447 + vertex 1.71516 0.976911 2.44597 + endloop + endfacet + facet normal 0.535938 -0.227676 0.812979 + outer loop + vertex 1.71382 0.972935 2.44573 + vertex 1.71755 0.974419 2.44369 + vertex 1.71516 0.976911 2.44597 + endloop + endfacet + facet normal 0.453518 -0.203091 0.867799 + outer loop + vertex 1.71516 0.976911 2.44597 + vertex 1.71144 0.973696 2.44716 + vertex 1.71382 0.972935 2.44573 + endloop + endfacet + facet normal 0.458467 -0.210443 0.863436 + outer loop + vertex 1.71252 0.978915 2.44786 + vertex 1.71144 0.973696 2.44716 + vertex 1.71516 0.976911 2.44597 + endloop + endfacet + facet normal 0.577856 -0.209567 0.788774 + outer loop + vertex 1.71832 0.980003 2.44447 + vertex 1.71619 0.980723 2.44622 + vertex 1.71516 0.976911 2.44597 + endloop + endfacet + facet normal 0.474443 -0.186442 0.860316 + outer loop + vertex 1.71619 0.980723 2.44622 + vertex 1.71252 0.978915 2.44786 + vertex 1.71516 0.976911 2.44597 + endloop + endfacet + facet normal 0.468632 -0.168438 0.867187 + outer loop + vertex 1.71619 0.980723 2.44622 + vertex 1.71585 0.983817 2.44701 + vertex 1.71252 0.978915 2.44786 + endloop + endfacet + facet normal 0.502943 -0.196178 0.841761 + outer loop + vertex 1.71585 0.983817 2.44701 + vertex 1.71225 0.984211 2.44925 + vertex 1.71252 0.978915 2.44786 + endloop + endfacet + facet normal 0.512738 -0.138311 0.847331 + outer loop + vertex 1.71585 0.983817 2.44701 + vertex 1.71614 0.988368 2.44758 + vertex 1.71225 0.984211 2.44925 + endloop + endfacet + facet normal 0.567292 -0.209868 0.796326 + outer loop + vertex 1.71225 0.984211 2.44925 + vertex 1.71614 0.988368 2.44758 + vertex 1.71339 0.989523 2.44984 + endloop + endfacet + facet normal 0.523561 -0.196367 0.82905 + outer loop + vertex 1.71336 0.99292 2.45066 + vertex 1.71127 0.990525 2.45141 + vertex 1.71339 0.989523 2.44984 + endloop + endfacet + facet normal 0.64472 -0.174697 0.744189 + outer loop + vertex 1.71336 0.99292 2.45066 + vertex 1.71339 0.989523 2.44984 + vertex 1.71618 0.993772 2.44842 + endloop + endfacet + facet normal 0.597698 -0.128074 0.791426 + outer loop + vertex 1.71618 0.993772 2.44842 + vertex 1.71339 0.989523 2.44984 + vertex 1.71614 0.988368 2.44758 + endloop + endfacet + facet normal 0.514663 -0.18612 0.836947 + outer loop + vertex 1.71336 0.99292 2.45066 + vertex 1.71105 0.993716 2.45226 + vertex 1.71127 0.990525 2.45141 + endloop + endfacet + facet normal 0.693716 -0.0914784 0.714416 + outer loop + vertex 1.71618 0.993772 2.44842 + vertex 1.71679 0.999508 2.44857 + vertex 1.71405 0.996612 2.45085 + endloop + endfacet + facet normal 0.643527 -0.158548 0.748822 + outer loop + vertex 1.71336 0.99292 2.45066 + vertex 1.71618 0.993772 2.44842 + vertex 1.71405 0.996612 2.45085 + endloop + endfacet + facet normal 0.529535 -0.141713 0.836367 + outer loop + vertex 1.71405 0.996612 2.45085 + vertex 1.71105 0.993716 2.45226 + vertex 1.71336 0.99292 2.45066 + endloop + endfacet + facet normal 0.559276 -0.186492 0.807732 + outer loop + vertex 1.71145 0.998297 2.45304 + vertex 1.71105 0.993716 2.45226 + vertex 1.71405 0.996612 2.45085 + endloop + endfacet + facet normal 0.743179 -0.0515723 0.667102 + outer loop + vertex 1.71679 0.999508 2.44857 + vertex 1.71696 1.0048 2.44878 + vertex 1.71445 1.00155 2.45133 + endloop + endfacet + facet normal 0.710312 -0.124126 0.692856 + outer loop + vertex 1.71405 0.996612 2.45085 + vertex 1.71679 0.999508 2.44857 + vertex 1.71445 1.00155 2.45133 + endloop + endfacet + facet normal 0.590541 -0.124732 0.79731 + outer loop + vertex 1.71445 1.00155 2.45133 + vertex 1.71145 0.998297 2.45304 + vertex 1.71405 0.996612 2.45085 + endloop + endfacet + facet normal 0.620059 -0.168218 0.766309 + outer loop + vertex 1.71171 1.00368 2.45402 + vertex 1.71145 0.998297 2.45304 + vertex 1.71445 1.00155 2.45133 + endloop + endfacet + facet normal 0.79569 -0.0123022 0.605579 + outer loop + vertex 1.71696 1.0048 2.44878 + vertex 1.71697 1.0102 2.44888 + vertex 1.71473 1.00698 2.45176 + endloop + endfacet + facet normal 0.76415 -0.0899276 0.63874 + outer loop + vertex 1.71445 1.00155 2.45133 + vertex 1.71696 1.0048 2.44878 + vertex 1.71473 1.00698 2.45176 + endloop + endfacet + facet normal 0.659052 -0.0930965 0.746313 + outer loop + vertex 1.71473 1.00698 2.45176 + vertex 1.71171 1.00368 2.45402 + vertex 1.71445 1.00155 2.45133 + endloop + endfacet + facet normal 0.687785 -0.143085 0.711673 + outer loop + vertex 1.71248 1.00926 2.45439 + vertex 1.71171 1.00368 2.45402 + vertex 1.71473 1.00698 2.45176 + endloop + endfacet + facet normal 0.839167 0.0124778 0.543731 + outer loop + vertex 1.71697 1.0102 2.44888 + vertex 1.717 1.01552 2.44871 + vertex 1.71482 1.01291 2.45214 + endloop + endfacet + facet normal 0.814075 -0.0492699 0.578665 + outer loop + vertex 1.71473 1.00698 2.45176 + vertex 1.71697 1.0102 2.44888 + vertex 1.71482 1.01291 2.45214 + endloop + endfacet + facet normal 0.735412 -0.0541374 0.675454 + outer loop + vertex 1.71482 1.01291 2.45214 + vertex 1.71248 1.00926 2.45439 + vertex 1.71473 1.00698 2.45176 + endloop + endfacet + facet normal 0.765489 -0.0977956 0.635973 + outer loop + vertex 1.71258 1.01337 2.4549 + vertex 1.71248 1.00926 2.45439 + vertex 1.71482 1.01291 2.45214 + endloop + endfacet + facet normal 0.871237 0.0322079 0.489805 + outer loop + vertex 1.717 1.01552 2.44871 + vertex 1.71688 1.02029 2.44861 + vertex 1.71558 1.01758 2.45111 + endloop + endfacet + facet normal 0.850999 -0.0224239 0.524688 + outer loop + vertex 1.71482 1.01291 2.45214 + vertex 1.717 1.01552 2.44871 + vertex 1.71558 1.01758 2.45111 + endloop + endfacet + facet normal 0.701221 -0.00891159 0.712888 + outer loop + vertex 1.71258 1.01337 2.4549 + vertex 1.71346 1.01753 2.45409 + vertex 1.71109 1.01523 2.45639 + endloop + endfacet + facet normal 0.773329 -0.039713 0.63276 + outer loop + vertex 1.71258 1.01337 2.4549 + vertex 1.71482 1.01291 2.45214 + vertex 1.71346 1.01753 2.45409 + endloop + endfacet + facet normal 0.815314 -0.00465461 0.579 + outer loop + vertex 1.71482 1.01291 2.45214 + vertex 1.71558 1.01758 2.45111 + vertex 1.71346 1.01753 2.45409 + endloop + endfacet + facet normal 0.719698 -0.0482046 0.692612 + outer loop + vertex 1.71346 1.01753 2.45409 + vertex 1.71085 1.01896 2.45689 + vertex 1.71109 1.01523 2.45639 + endloop + endfacet + facet normal 0.874205 0.0365105 0.484183 + outer loop + vertex 1.71688 1.02029 2.44861 + vertex 1.71662 1.02502 2.44873 + vertex 1.71522 1.02159 2.4515 + endloop + endfacet + facet normal 0.872955 0.0287667 0.486951 + outer loop + vertex 1.71558 1.01758 2.45111 + vertex 1.71688 1.02029 2.44861 + vertex 1.71522 1.02159 2.4515 + endloop + endfacet + facet normal 0.815084 0.0146485 0.579158 + outer loop + vertex 1.71558 1.01758 2.45111 + vertex 1.71522 1.02159 2.4515 + vertex 1.71346 1.01753 2.45409 + endloop + endfacet + facet normal 0.828788 -0.00377071 0.559551 + outer loop + vertex 1.71522 1.02159 2.4515 + vertex 1.7132 1.02264 2.4545 + vertex 1.71346 1.01753 2.45409 + endloop + endfacet + facet normal 0.727911 -0.0191964 0.685402 + outer loop + vertex 1.7132 1.02264 2.4545 + vertex 1.71085 1.01896 2.45689 + vertex 1.71346 1.01753 2.45409 + endloop + endfacet + facet normal 0.76153 -0.0671388 0.644643 + outer loop + vertex 1.71086 1.02374 2.45738 + vertex 1.71085 1.01896 2.45689 + vertex 1.7132 1.02264 2.4545 + endloop + endfacet + facet normal 0.882135 0.00148424 0.470994 + outer loop + vertex 1.71662 1.02502 2.44873 + vertex 1.71649 1.03004 2.44896 + vertex 1.71505 1.02642 2.45166 + endloop + endfacet + facet normal 0.885032 0.0167745 0.465228 + outer loop + vertex 1.71522 1.02159 2.4515 + vertex 1.71662 1.02502 2.44873 + vertex 1.71505 1.02642 2.45166 + endloop + endfacet + facet normal 0.831235 0.0117297 0.555797 + outer loop + vertex 1.71522 1.02159 2.4515 + vertex 1.71505 1.02642 2.45166 + vertex 1.7132 1.02264 2.4545 + endloop + endfacet + facet normal 0.848944 -0.017653 0.528188 + outer loop + vertex 1.71505 1.02642 2.45166 + vertex 1.71314 1.0277 2.45478 + vertex 1.7132 1.02264 2.4545 + endloop + endfacet + facet normal 0.771148 -0.0244517 0.636187 + outer loop + vertex 1.71314 1.0277 2.45478 + vertex 1.71086 1.02374 2.45738 + vertex 1.7132 1.02264 2.4545 + endloop + endfacet + facet normal 0.793246 -0.0569029 0.606237 + outer loop + vertex 1.71068 1.02887 2.4581 + vertex 1.71086 1.02374 2.45738 + vertex 1.71314 1.0277 2.45478 + endloop + endfacet + facet normal 0.885539 -0.145647 0.441144 + outer loop + vertex 1.71649 1.03004 2.44896 + vertex 1.71699 1.03517 2.44964 + vertex 1.71527 1.03196 2.45203 + endloop + endfacet + facet normal 0.913868 -0.0634955 0.401015 + outer loop + vertex 1.71505 1.02642 2.45166 + vertex 1.71649 1.03004 2.44896 + vertex 1.71527 1.03196 2.45203 + endloop + endfacet + facet normal 0.837228 -0.0698974 0.542368 + outer loop + vertex 1.71505 1.02642 2.45166 + vertex 1.71527 1.03196 2.45203 + vertex 1.71314 1.0277 2.45478 + endloop + endfacet + facet normal 0.844994 -0.0828024 0.528327 + outer loop + vertex 1.71527 1.03196 2.45203 + vertex 1.71344 1.03333 2.45517 + vertex 1.71314 1.0277 2.45478 + endloop + endfacet + facet normal 0.786666 -0.0855081 0.611428 + outer loop + vertex 1.71344 1.03333 2.45517 + vertex 1.71068 1.02887 2.4581 + vertex 1.71314 1.0277 2.45478 + endloop + endfacet + facet normal 0.76472 -0.0516335 0.64229 + outer loop + vertex 1.71123 1.0343 2.45788 + vertex 1.71068 1.02887 2.4581 + vertex 1.71344 1.03333 2.45517 + endloop + endfacet + facet normal 0.733874 -0.520152 0.436889 + outer loop + vertex 1.71699 1.03517 2.44964 + vertex 1.72 1.04 2.45033 + vertex 1.71722 1.04 2.455 + endloop + endfacet + facet normal 0.918796 -0.31211 0.241664 + outer loop + vertex 1.71527 1.03196 2.45203 + vertex 1.71699 1.03517 2.44964 + vertex 1.71722 1.04 2.455 + endloop + endfacet + facet normal 0.712733 -0.388424 0.584071 + outer loop + vertex 1.71527 1.03196 2.45203 + vertex 1.71722 1.04 2.455 + vertex 1.71344 1.03333 2.45517 + endloop + endfacet + facet normal 0.198031 -0.0868702 0.976339 + outer loop + vertex 1.71722 1.04 2.455 + vertex 1.71372 1.03831 2.45556 + vertex 1.71344 1.03333 2.45517 + endloop + endfacet + facet normal 0.754909 -0.0930779 0.649191 + outer loop + vertex 1.71372 1.03831 2.45556 + vertex 1.71123 1.0343 2.45788 + vertex 1.71344 1.03333 2.45517 + endloop + endfacet + facet normal 0.700129 -0.0218555 0.713682 + outer loop + vertex 1.71162 1.03807 2.45761 + vertex 1.71123 1.0343 2.45788 + vertex 1.71372 1.03831 2.45556 + endloop + endfacet + facet normal 0.212597 0.0345153 0.97653 + outer loop + vertex 1.71315 1.04111 2.45605 + vertex 1.71734 1.045 2.455 + vertex 1.71354 1.04529 2.45582 + endloop + endfacet + facet normal 0.326639 -0.098059 0.940049 + outer loop + vertex 1.71315 1.04111 2.45605 + vertex 1.71372 1.03831 2.45556 + vertex 1.71734 1.045 2.455 + endloop + endfacet + facet normal 0.159701 -0.00383422 0.987158 + outer loop + vertex 1.71372 1.03831 2.45556 + vertex 1.71722 1.04 2.455 + vertex 1.71734 1.045 2.455 + endloop + endfacet + facet normal 0.697815 0.0178259 0.716056 + outer loop + vertex 1.71372 1.03831 2.45556 + vertex 1.71315 1.04111 2.45605 + vertex 1.71162 1.03807 2.45761 + endloop + endfacet + facet normal 0.210056 -0.00168273 0.977688 + outer loop + vertex 1.71738 1.05 2.455 + vertex 1.71354 1.04529 2.45582 + vertex 1.71734 1.045 2.455 + endloop + endfacet + facet normal 0.302087 -0.0816428 0.949778 + outer loop + vertex 1.71396 1.05079 2.45615 + vertex 1.71354 1.04529 2.45582 + vertex 1.71738 1.05 2.455 + endloop + endfacet + facet normal 0.321506 0.00707507 0.946881 + outer loop + vertex 1.71727 1.055 2.455 + vertex 1.71396 1.05079 2.45615 + vertex 1.71738 1.05 2.455 + endloop + endfacet + facet normal 0.764708 -0.483032 0.4265 + outer loop + vertex 1.715 1.055 2.45907 + vertex 1.71396 1.05079 2.45615 + vertex 1.71727 1.055 2.455 + endloop + endfacet + facet normal 0.863881 0.146853 0.481812 + outer loop + vertex 1.71642 1.06 2.455 + vertex 1.715 1.055 2.45907 + vertex 1.71727 1.055 2.455 + endloop + endfacet + facet normal 0.827513 0.193888 0.526905 + outer loop + vertex 1.715 1.06 2.45723 + vertex 1.715 1.055 2.45907 + vertex 1.71642 1.06 2.455 + endloop + endfacet + facet normal 0.483738 0.618802 -0.618935 + outer loop + vertex 1.715 1.06 2.45389 + vertex 1.715 1.06111 2.455 + vertex 1.71642 1.06 2.455 + endloop + endfacet + facet normal 0.573369 0.733459 0.365083 + outer loop + vertex 1.71642 1.06 2.455 + vertex 1.715 1.06111 2.455 + vertex 1.715 1.06 2.45723 + endloop + endfacet + facet normal 0.798462 -0.503861 0.32952 + outer loop + vertex 1.7163 1.975 2.455 + vertex 1.715 1.975 2.45815 + vertex 1.715 1.97294 2.455 + endloop + endfacet + facet normal 0.916293 -0.131951 0.378148 + outer loop + vertex 1.71702 1.98 2.455 + vertex 1.715 1.975 2.45815 + vertex 1.7163 1.975 2.455 + endloop + endfacet + facet normal 0.88629 -0.0696037 0.457871 + outer loop + vertex 1.715 1.98 2.45891 + vertex 1.715 1.975 2.45815 + vertex 1.71702 1.98 2.455 + endloop + endfacet + facet normal 0.888275 0.0195474 0.458897 + outer loop + vertex 1.71691 1.985 2.455 + vertex 1.715 1.98 2.45891 + vertex 1.71702 1.98 2.455 + endloop + endfacet + facet normal 0.109339 0.586071 0.802848 + outer loop + vertex 1.71371 1.98452 2.45579 + vertex 1.715 1.98 2.45891 + vertex 1.71691 1.985 2.455 + endloop + endfacet + facet normal 0.242923 -0.0267231 0.969677 + outer loop + vertex 1.71746 1.99 2.455 + vertex 1.71371 1.98452 2.45579 + vertex 1.71691 1.985 2.455 + endloop + endfacet + facet normal -0.00761078 0.147469 0.989037 + outer loop + vertex 1.714 1.98903 2.45512 + vertex 1.71371 1.98452 2.45579 + vertex 1.71746 1.99 2.455 + endloop + endfacet + facet normal 0.0343944 -0.00123824 0.999408 + outer loop + vertex 1.71764 1.995 2.455 + vertex 1.714 1.98903 2.45512 + vertex 1.71746 1.99 2.455 + endloop + endfacet + facet normal 0.329652 -0.182616 0.926273 + outer loop + vertex 1.71228 1.99236 2.45639 + vertex 1.714 1.98903 2.45512 + vertex 1.71764 1.995 2.455 + endloop + endfacet + facet normal 0.353164 0.641875 0.680641 + outer loop + vertex 1.72 1.995 2.45132 + vertex 1.71682 1.99912 2.44909 + vertex 1.71535 1.99625 2.45255 + endloop + endfacet + facet normal 0.302456 0.933219 0.193966 + outer loop + vertex 1.71764 1.995 2.455 + vertex 1.72 1.995 2.45132 + vertex 1.71535 1.99625 2.45255 + endloop + endfacet + facet normal -0.222091 0.767487 0.601365 + outer loop + vertex 1.71535 1.99625 2.45255 + vertex 1.71228 1.99236 2.45639 + vertex 1.71764 1.995 2.455 + endloop + endfacet + facet normal 0.720377 0.108057 0.685114 + outer loop + vertex 1.71266 1.99789 2.45512 + vertex 1.71228 1.99236 2.45639 + vertex 1.71535 1.99625 2.45255 + endloop + endfacet + facet normal 0.832282 0.100841 0.545104 + outer loop + vertex 1.71682 1.99912 2.44909 + vertex 1.71669 2.00399 2.44839 + vertex 1.71465 2.00126 2.452 + endloop + endfacet + facet normal 0.846879 0.172987 0.502864 + outer loop + vertex 1.71535 1.99625 2.45255 + vertex 1.71682 1.99912 2.44909 + vertex 1.71465 2.00126 2.452 + endloop + endfacet + facet normal 0.733626 0.174141 0.656862 + outer loop + vertex 1.71465 2.00126 2.452 + vertex 1.71266 1.99789 2.45512 + vertex 1.71535 1.99625 2.45255 + endloop + endfacet + facet normal 0.82309 0.0380731 0.566634 + outer loop + vertex 1.7125 2.0017 2.45509 + vertex 1.71266 1.99789 2.45512 + vertex 1.71465 2.00126 2.452 + endloop + endfacet + facet normal 0.861283 -0.0087209 0.50805 + outer loop + vertex 1.71669 2.00399 2.44839 + vertex 1.71678 2.00876 2.44832 + vertex 1.71524 2.00558 2.45087 + endloop + endfacet + facet normal 0.867126 0.0123629 0.497935 + outer loop + vertex 1.71465 2.00126 2.452 + vertex 1.71669 2.00399 2.44839 + vertex 1.71524 2.00558 2.45087 + endloop + endfacet + facet normal 0.769101 0.0613739 0.636174 + outer loop + vertex 1.7125 2.0017 2.45509 + vertex 1.71303 2.00552 2.45408 + vertex 1.71103 2.00375 2.45668 + endloop + endfacet + facet normal 0.823 0.0355468 0.566928 + outer loop + vertex 1.7125 2.0017 2.45509 + vertex 1.71465 2.00126 2.452 + vertex 1.71303 2.00552 2.45408 + endloop + endfacet + facet normal 0.823579 0.0361969 0.566045 + outer loop + vertex 1.71465 2.00126 2.452 + vertex 1.71524 2.00558 2.45087 + vertex 1.71303 2.00552 2.45408 + endloop + endfacet + facet normal 0.750329 0.106449 0.652438 + outer loop + vertex 1.71303 2.00552 2.45408 + vertex 1.71004 2.00777 2.45715 + vertex 1.71103 2.00375 2.45668 + endloop + endfacet + facet normal 0.83472 -0.00110764 0.550674 + outer loop + vertex 1.71678 2.00876 2.44832 + vertex 1.71668 2.01379 2.44848 + vertex 1.71448 2.0099 2.4518 + endloop + endfacet + facet normal 0.839067 0.0303307 0.543182 + outer loop + vertex 1.71524 2.00558 2.45087 + vertex 1.71678 2.00876 2.44832 + vertex 1.71448 2.0099 2.4518 + endloop + endfacet + facet normal 0.790034 0.0694367 0.609118 + outer loop + vertex 1.7122 2.00942 2.45482 + vertex 1.71448 2.0099 2.4518 + vertex 1.71234 2.01301 2.45422 + endloop + endfacet + facet normal 0.791834 0.0553395 0.608224 + outer loop + vertex 1.7122 2.00942 2.45482 + vertex 1.71303 2.00552 2.45408 + vertex 1.71448 2.0099 2.4518 + endloop + endfacet + facet normal 0.824028 0.0227648 0.566092 + outer loop + vertex 1.71303 2.00552 2.45408 + vertex 1.71524 2.00558 2.45087 + vertex 1.71448 2.0099 2.4518 + endloop + endfacet + facet normal 0.725806 0.0262168 0.6874 + outer loop + vertex 1.71303 2.00552 2.45408 + vertex 1.7122 2.00942 2.45482 + vertex 1.71004 2.00777 2.45715 + endloop + endfacet + facet normal 0.801135 0.0151232 0.598293 + outer loop + vertex 1.71668 2.01379 2.44848 + vertex 1.71662 2.01899 2.44843 + vertex 1.71444 2.01533 2.45144 + endloop + endfacet + facet normal 0.807924 0.0455815 0.587522 + outer loop + vertex 1.71448 2.0099 2.4518 + vertex 1.71668 2.01379 2.44848 + vertex 1.71444 2.01533 2.45144 + endloop + endfacet + facet normal 0.778177 0.0479423 0.626212 + outer loop + vertex 1.71444 2.01533 2.45144 + vertex 1.71234 2.01301 2.45422 + vertex 1.71448 2.0099 2.4518 + endloop + endfacet + facet normal 0.755793 0.0942741 0.647989 + outer loop + vertex 1.71206 2.01761 2.45388 + vertex 1.71234 2.01301 2.45422 + vertex 1.71444 2.01533 2.45144 + endloop + endfacet + facet normal 0.766915 0.0306119 0.641018 + outer loop + vertex 1.71662 2.01899 2.44843 + vertex 1.71653 2.02405 2.44829 + vertex 1.71425 2.02049 2.45119 + endloop + endfacet + facet normal 0.773331 0.0588007 0.63127 + outer loop + vertex 1.71444 2.01533 2.45144 + vertex 1.71662 2.01899 2.44843 + vertex 1.71425 2.02049 2.45119 + endloop + endfacet + facet normal 0.74239 0.0593525 0.667333 + outer loop + vertex 1.71425 2.02049 2.45119 + vertex 1.71206 2.01761 2.45388 + vertex 1.71444 2.01533 2.45144 + endloop + endfacet + facet normal 0.714945 0.102864 0.691572 + outer loop + vertex 1.71165 2.02258 2.45356 + vertex 1.71206 2.01761 2.45388 + vertex 1.71425 2.02049 2.45119 + endloop + endfacet + facet normal 0.737796 0.0370613 0.674006 + outer loop + vertex 1.71653 2.02405 2.44829 + vertex 1.71642 2.02892 2.44814 + vertex 1.71404 2.02562 2.45092 + endloop + endfacet + facet normal 0.744665 0.0638998 0.664372 + outer loop + vertex 1.71425 2.02049 2.45119 + vertex 1.71653 2.02405 2.44829 + vertex 1.71404 2.02562 2.45092 + endloop + endfacet + facet normal 0.701095 0.0645694 0.710138 + outer loop + vertex 1.71404 2.02562 2.45092 + vertex 1.71165 2.02258 2.45356 + vertex 1.71425 2.02049 2.45119 + endloop + endfacet + facet normal 0.666708 0.114385 0.736489 + outer loop + vertex 1.71101 2.02804 2.45329 + vertex 1.71165 2.02258 2.45356 + vertex 1.71404 2.02562 2.45092 + endloop + endfacet + facet normal 0.714381 0.0524013 0.697792 + outer loop + vertex 1.71642 2.02892 2.44814 + vertex 1.71621 2.03365 2.448 + vertex 1.71396 2.0305 2.45055 + endloop + endfacet + facet normal 0.718347 0.0667212 0.692478 + outer loop + vertex 1.71404 2.02562 2.45092 + vertex 1.71642 2.02892 2.44814 + vertex 1.71396 2.0305 2.45055 + endloop + endfacet + facet normal 0.648512 0.0705429 0.757928 + outer loop + vertex 1.71396 2.0305 2.45055 + vertex 1.71101 2.02804 2.45329 + vertex 1.71404 2.02562 2.45092 + endloop + endfacet + facet normal 0.630806 0.104108 0.768925 + outer loop + vertex 1.71161 2.03249 2.4522 + vertex 1.71101 2.02804 2.45329 + vertex 1.71396 2.0305 2.45055 + endloop + endfacet + facet normal 0.678902 0.088581 0.728866 + outer loop + vertex 1.71621 2.03365 2.448 + vertex 1.71554 2.03858 2.44802 + vertex 1.71358 2.03497 2.45029 + endloop + endfacet + facet normal 0.681036 0.0985404 0.725589 + outer loop + vertex 1.71396 2.0305 2.45055 + vertex 1.71621 2.03365 2.448 + vertex 1.71358 2.03497 2.45029 + endloop + endfacet + facet normal 0.62725 0.0967302 0.772788 + outer loop + vertex 1.71358 2.03497 2.45029 + vertex 1.71161 2.03249 2.4522 + vertex 1.71396 2.0305 2.45055 + endloop + endfacet + facet normal 0.572128 0.164496 0.803499 + outer loop + vertex 1.71029 2.03686 2.45225 + vertex 1.71161 2.03249 2.4522 + vertex 1.71358 2.03497 2.45029 + endloop + endfacet + facet normal 0.636639 0.130981 0.759957 + outer loop + vertex 1.71282 2.03848 2.45032 + vertex 1.71358 2.03497 2.45029 + vertex 1.71554 2.03858 2.44802 + endloop + endfacet + facet normal 0.632721 0.16413 0.756786 + outer loop + vertex 1.71282 2.03848 2.45032 + vertex 1.71554 2.03858 2.44802 + vertex 1.71296 2.04203 2.44944 + endloop + endfacet + facet normal 0.605158 0.131794 0.785121 + outer loop + vertex 1.71296 2.04203 2.44944 + vertex 1.71554 2.03858 2.44802 + vertex 1.71558 2.04335 2.4472 + endloop + endfacet + facet normal 0.554744 0.112746 0.824346 + outer loop + vertex 1.71358 2.03497 2.45029 + vertex 1.71282 2.03848 2.45032 + vertex 1.71029 2.03686 2.45225 + endloop + endfacet + facet normal 0.631566 0.116507 0.766518 + outer loop + vertex 1.71766 2.04478 2.44526 + vertex 1.7179 2.04813 2.44456 + vertex 1.7159 2.04663 2.44642 + endloop + endfacet + facet normal 0.632129 0.11742 0.765915 + outer loop + vertex 1.7159 2.04663 2.44642 + vertex 1.71558 2.04335 2.4472 + vertex 1.71766 2.04478 2.44526 + endloop + endfacet + facet normal 0.530646 0.143819 0.835303 + outer loop + vertex 1.7159 2.04663 2.44642 + vertex 1.71233 2.04747 2.44855 + vertex 1.71558 2.04335 2.4472 + endloop + endfacet + facet normal 0.578637 0.195883 0.791713 + outer loop + vertex 1.71233 2.04747 2.44855 + vertex 1.71296 2.04203 2.44944 + vertex 1.71558 2.04335 2.4472 + endloop + endfacet + facet normal 0.599655 0.13757 0.788345 + outer loop + vertex 1.7179 2.04813 2.44456 + vertex 1.7174 2.05269 2.44414 + vertex 1.71515 2.05022 2.44628 + endloop + endfacet + facet normal 0.6091 0.15935 0.77692 + outer loop + vertex 1.7159 2.04663 2.44642 + vertex 1.7179 2.04813 2.44456 + vertex 1.71515 2.05022 2.44628 + endloop + endfacet + facet normal 0.530794 0.145368 0.834941 + outer loop + vertex 1.71515 2.05022 2.44628 + vertex 1.71233 2.04747 2.44855 + vertex 1.7159 2.04663 2.44642 + endloop + endfacet + facet normal 0.502183 0.183196 0.845134 + outer loop + vertex 1.71212 2.05239 2.44761 + vertex 1.71233 2.04747 2.44855 + vertex 1.71515 2.05022 2.44628 + endloop + endfacet + facet normal 0.565036 0.209528 0.798018 + outer loop + vertex 1.7174 2.05269 2.44414 + vertex 1.71598 2.05826 2.44368 + vertex 1.71412 2.05475 2.44592 + endloop + endfacet + facet normal 0.558499 0.191171 0.807176 + outer loop + vertex 1.71515 2.05022 2.44628 + vertex 1.7174 2.05269 2.44414 + vertex 1.71412 2.05475 2.44592 + endloop + endfacet + facet normal 0.501172 0.181141 0.846176 + outer loop + vertex 1.71412 2.05475 2.44592 + vertex 1.71212 2.05239 2.44761 + vertex 1.71515 2.05022 2.44628 + endloop + endfacet + facet normal 0.453352 0.23209 0.860585 + outer loop + vertex 1.7101 2.05687 2.44747 + vertex 1.71212 2.05239 2.44761 + vertex 1.71412 2.05475 2.44592 + endloop + endfacet + facet normal 0.523259 0.24357 0.816623 + outer loop + vertex 1.71257 2.05861 2.44576 + vertex 1.71412 2.05475 2.44592 + vertex 1.71598 2.05826 2.44368 + endloop + endfacet + facet normal 0.517157 0.320276 0.793708 + outer loop + vertex 1.71257 2.05861 2.44576 + vertex 1.71598 2.05826 2.44368 + vertex 1.71164 2.06276 2.44469 + endloop + endfacet + facet normal 0.485153 0.281699 0.827811 + outer loop + vertex 1.71164 2.06276 2.44469 + vertex 1.71598 2.05826 2.44368 + vertex 1.71543 2.06347 2.44223 + endloop + endfacet + facet normal 0.447382 0.215327 0.868035 + outer loop + vertex 1.71412 2.05475 2.44592 + vertex 1.71257 2.05861 2.44576 + vertex 1.7101 2.05687 2.44747 + endloop + endfacet + facet normal 0.519947 0.394777 0.7575 + outer loop + vertex 1.71824 2.06525 2.43969 + vertex 1.71664 2.06876 2.43897 + vertex 1.71506 2.06671 2.44112 + endloop + endfacet + facet normal 0.507604 0.330609 0.795636 + outer loop + vertex 1.71506 2.06671 2.44112 + vertex 1.71543 2.06347 2.44223 + vertex 1.71824 2.06525 2.43969 + endloop + endfacet + facet normal 0.422014 0.336879 0.841675 + outer loop + vertex 1.71506 2.06671 2.44112 + vertex 1.71157 2.06737 2.4426 + vertex 1.71543 2.06347 2.44223 + endloop + endfacet + facet normal 0.455403 0.373061 0.808353 + outer loop + vertex 1.71157 2.06737 2.4426 + vertex 1.71164 2.06276 2.44469 + vertex 1.71543 2.06347 2.44223 + endloop + endfacet + facet normal 0.475658 0.435732 0.764126 + outer loop + vertex 1.71356 2.06897 2.44077 + vertex 1.71506 2.06671 2.44112 + vertex 1.71664 2.06876 2.43897 + endloop + endfacet + facet normal 0.460428 0.504759 0.730223 + outer loop + vertex 1.71356 2.06897 2.44077 + vertex 1.71664 2.06876 2.43897 + vertex 1.71393 2.07086 2.43922 + endloop + endfacet + facet normal 0.47657 0.529099 0.702094 + outer loop + vertex 1.71393 2.07086 2.43922 + vertex 1.71664 2.06876 2.43897 + vertex 1.71608 2.07152 2.43727 + endloop + endfacet + facet normal 0.421762 0.406899 0.810278 + outer loop + vertex 1.71506 2.06671 2.44112 + vertex 1.71356 2.06897 2.44077 + vertex 1.71157 2.06737 2.4426 + endloop + endfacet + facet normal 0.398572 0.710064 0.580473 + outer loop + vertex 1.71272 2.07372 2.43724 + vertex 1.71744 2.07349 2.43427 + vertex 1.71482 2.07586 2.43317 + endloop + endfacet + facet normal 0.405191 0.705477 0.581483 + outer loop + vertex 1.71143 2.07633 2.43497 + vertex 1.71272 2.07372 2.43724 + vertex 1.71482 2.07586 2.43317 + endloop + endfacet + facet normal 0.40686 0.63119 0.660352 + outer loop + vertex 1.71608 2.07152 2.43727 + vertex 1.71272 2.07372 2.43724 + vertex 1.71393 2.07086 2.43922 + endloop + endfacet + facet normal 0.4236 0.656398 0.624263 + outer loop + vertex 1.71744 2.07349 2.43427 + vertex 1.71272 2.07372 2.43724 + vertex 1.71608 2.07152 2.43727 + endloop + endfacet + facet normal 0.00659934 0.0423106 0.999083 + outer loop + vertex 1.72 2.08137 2.43 + vertex 1.715 2.08215 2.43 + vertex 1.71686 2.07835 2.43015 + endloop + endfacet + facet normal 0.362311 0.212913 0.907413 + outer loop + vertex 1.71686 2.07835 2.43015 + vertex 1.715 2.08215 2.43 + vertex 1.71222 2.07821 2.43203 + endloop + endfacet + facet normal 0.400265 0.718509 0.568799 + outer loop + vertex 1.71482 2.07586 2.43317 + vertex 1.71222 2.07821 2.43203 + vertex 1.71143 2.07633 2.43497 + endloop + endfacet + facet normal 0.271007 0.645603 0.713969 + outer loop + vertex 1.71686 2.07835 2.43015 + vertex 1.71222 2.07821 2.43203 + vertex 1.71482 2.07586 2.43317 + endloop + endfacet + facet normal 0.344596 -0.855717 0.386009 + outer loop + vertex 1.72295 0.955 2.43 + vertex 1.725 0.95357 2.425 + vertex 1.725 0.955 2.42817 + endloop + endfacet + facet normal 0.383311 -0.834507 0.395817 + outer loop + vertex 1.72295 0.955 2.43 + vertex 1.72 0.953645 2.43 + vertex 1.725 0.95357 2.425 + endloop + endfacet + facet normal 0.132899 -0.980079 0.147594 + outer loop + vertex 1.72 0.953645 2.43 + vertex 1.72 0.952892 2.425 + vertex 1.725 0.95357 2.425 + endloop + endfacet + facet normal -0.192711 0.419551 0.88704 + outer loop + vertex 1.72295 0.955 2.43 + vertex 1.71946 0.954124 2.42966 + vertex 1.72 0.953645 2.43 + endloop + endfacet + facet normal -0.161007 0.268572 0.949708 + outer loop + vertex 1.71946 0.954124 2.42966 + vertex 1.72295 0.955 2.43 + vertex 1.725 0.956229 2.43 + endloop + endfacet + facet normal 0.279661 -0.818249 0.502254 + outer loop + vertex 1.71946 0.954124 2.42966 + vertex 1.725 0.956229 2.43 + vertex 1.71732 0.955098 2.43243 + endloop + endfacet + facet normal 0.315598 -0.644417 0.696509 + outer loop + vertex 1.71732 0.955098 2.43243 + vertex 1.725 0.956229 2.43 + vertex 1.72168 0.957396 2.43258 + endloop + endfacet + facet normal 0.477652 -0.606853 0.635277 + outer loop + vertex 1.71968 0.958851 2.43548 + vertex 1.72168 0.957396 2.43258 + vertex 1.72182 0.959449 2.43444 + endloop + endfacet + facet normal 0.388343 -0.687191 0.613969 + outer loop + vertex 1.71968 0.958851 2.43548 + vertex 1.71704 0.95748 2.43561 + vertex 1.72168 0.957396 2.43258 + endloop + endfacet + facet normal 0.364555 -0.729523 0.578702 + outer loop + vertex 1.71704 0.95748 2.43561 + vertex 1.71732 0.955098 2.43243 + vertex 1.72168 0.957396 2.43258 + endloop + endfacet + facet normal 0.343619 -0.589862 0.730746 + outer loop + vertex 1.71968 0.958851 2.43548 + vertex 1.71829 0.960472 2.43744 + vertex 1.71704 0.95748 2.43561 + endloop + endfacet + facet normal 0.484455 -0.541979 0.686704 + outer loop + vertex 1.72182 0.959449 2.43444 + vertex 1.72078 0.96077 2.43622 + vertex 1.71968 0.958851 2.43548 + endloop + endfacet + facet normal 0.424624 -0.526945 0.736222 + outer loop + vertex 1.72078 0.96077 2.43622 + vertex 1.71829 0.960472 2.43744 + vertex 1.71968 0.958851 2.43548 + endloop + endfacet + facet normal 0.445344 -0.363945 0.818054 + outer loop + vertex 1.72078 0.96077 2.43622 + vertex 1.721 0.963738 2.43742 + vertex 1.71829 0.960472 2.43744 + endloop + endfacet + facet normal 0.50866 -0.417103 0.753187 + outer loop + vertex 1.721 0.963738 2.43742 + vertex 1.71778 0.963891 2.43968 + vertex 1.71829 0.960472 2.43744 + endloop + endfacet + facet normal 0.553476 -0.376473 0.742921 + outer loop + vertex 1.71857 0.967775 2.44106 + vertex 1.71616 0.965413 2.44165 + vertex 1.71778 0.963891 2.43968 + endloop + endfacet + facet normal 0.626273 -0.370833 0.685759 + outer loop + vertex 1.71857 0.967775 2.44106 + vertex 1.71778 0.963891 2.43968 + vertex 1.72137 0.968698 2.439 + endloop + endfacet + facet normal 0.540058 -0.291776 0.789433 + outer loop + vertex 1.72137 0.968698 2.439 + vertex 1.71778 0.963891 2.43968 + vertex 1.721 0.963738 2.43742 + endloop + endfacet + facet normal 0.504677 -0.311075 0.805316 + outer loop + vertex 1.71857 0.967775 2.44106 + vertex 1.7165 0.968781 2.44274 + vertex 1.71616 0.965413 2.44165 + endloop + endfacet + facet normal 0.67568 -0.221954 0.702989 + outer loop + vertex 1.72137 0.968698 2.439 + vertex 1.72232 0.973565 2.43962 + vertex 1.71984 0.971638 2.4414 + endloop + endfacet + facet normal 0.626489 -0.270477 0.730995 + outer loop + vertex 1.71857 0.967775 2.44106 + vertex 1.72137 0.968698 2.439 + vertex 1.71984 0.971638 2.4414 + endloop + endfacet + facet normal 0.536749 -0.247525 0.806618 + outer loop + vertex 1.71984 0.971638 2.4414 + vertex 1.7165 0.968781 2.44274 + vertex 1.71857 0.967775 2.44106 + endloop + endfacet + facet normal 0.529891 -0.235755 0.814638 + outer loop + vertex 1.71755 0.974419 2.44369 + vertex 1.7165 0.968781 2.44274 + vertex 1.71984 0.971638 2.4414 + endloop + endfacet + facet normal 0.661964 -0.182079 0.727084 + outer loop + vertex 1.72232 0.973565 2.43962 + vertex 1.72107 0.975617 2.44127 + vertex 1.71984 0.971638 2.4414 + endloop + endfacet + facet normal 0.595238 -0.159541 0.787552 + outer loop + vertex 1.72107 0.975617 2.44127 + vertex 1.71755 0.974419 2.44369 + vertex 1.71984 0.971638 2.4414 + endloop + endfacet + facet normal 0.589092 -0.117304 0.799506 + outer loop + vertex 1.72107 0.975617 2.44127 + vertex 1.72091 0.979457 2.44195 + vertex 1.71755 0.974419 2.44369 + endloop + endfacet + facet normal 0.662529 -0.192502 0.723878 + outer loop + vertex 1.72091 0.979457 2.44195 + vertex 1.71832 0.980003 2.44447 + vertex 1.71755 0.974419 2.44369 + endloop + endfacet + facet normal 0.592292 -0.166076 0.788422 + outer loop + vertex 1.71815 0.983259 2.44528 + vertex 1.71619 0.980723 2.44622 + vertex 1.71832 0.980003 2.44447 + endloop + endfacet + facet normal 0.72366 -0.131744 0.677465 + outer loop + vertex 1.71815 0.983259 2.44528 + vertex 1.71832 0.980003 2.44447 + vertex 1.72063 0.984359 2.44286 + endloop + endfacet + facet normal 0.683517 -0.0932007 0.72396 + outer loop + vertex 1.72063 0.984359 2.44286 + vertex 1.71832 0.980003 2.44447 + vertex 1.72091 0.979457 2.44195 + endloop + endfacet + facet normal 0.571155 -0.142341 0.808406 + outer loop + vertex 1.71815 0.983259 2.44528 + vertex 1.71585 0.983817 2.44701 + vertex 1.71619 0.980723 2.44622 + endloop + endfacet + facet normal 0.759154 -0.0396061 0.649705 + outer loop + vertex 1.72063 0.984359 2.44286 + vertex 1.72106 0.989275 2.44264 + vertex 1.71874 0.986835 2.44521 + endloop + endfacet + facet normal 0.719938 -0.104137 0.686182 + outer loop + vertex 1.71815 0.983259 2.44528 + vertex 1.72063 0.984359 2.44286 + vertex 1.71874 0.986835 2.44521 + endloop + endfacet + facet normal 0.585322 -0.0793687 0.806907 + outer loop + vertex 1.71874 0.986835 2.44521 + vertex 1.71585 0.983817 2.44701 + vertex 1.71815 0.983259 2.44528 + endloop + endfacet + facet normal 0.621911 -0.13563 0.771253 + outer loop + vertex 1.71614 0.988368 2.44758 + vertex 1.71585 0.983817 2.44701 + vertex 1.71874 0.986835 2.44521 + endloop + endfacet + facet normal 0.800644 -0.00754727 0.599093 + outer loop + vertex 1.72106 0.989275 2.44264 + vertex 1.72139 0.992983 2.44225 + vertex 1.71931 0.992093 2.44502 + endloop + endfacet + facet normal 0.767896 -0.0605353 0.637707 + outer loop + vertex 1.71874 0.986835 2.44521 + vertex 1.72106 0.989275 2.44264 + vertex 1.71931 0.992093 2.44502 + endloop + endfacet + facet normal 0.657845 -0.0446196 0.75183 + outer loop + vertex 1.71931 0.992093 2.44502 + vertex 1.71614 0.988368 2.44758 + vertex 1.71874 0.986835 2.44521 + endloop + endfacet + facet normal 0.7016 -0.115192 0.703199 + outer loop + vertex 1.71618 0.993772 2.44842 + vertex 1.71614 0.988368 2.44758 + vertex 1.71931 0.992093 2.44502 + endloop + endfacet + facet normal 0.918229 -0.0984086 0.38363 + outer loop + vertex 1.72209 0.99592 2.44059 + vertex 1.72255 1.00072 2.44073 + vertex 1.72126 0.99712 2.4429 + endloop + endfacet + facet normal 0.935774 -0.0248084 0.351726 + outer loop + vertex 1.72139 0.992983 2.44225 + vertex 1.72209 0.99592 2.44059 + vertex 1.72126 0.99712 2.4429 + endloop + endfacet + facet normal 0.807775 -0.0655129 0.585839 + outer loop + vertex 1.72139 0.992983 2.44225 + vertex 1.72126 0.99712 2.4429 + vertex 1.71931 0.992093 2.44502 + endloop + endfacet + facet normal 0.809057 -0.0668219 0.583919 + outer loop + vertex 1.71931 0.992093 2.44502 + vertex 1.72126 0.99712 2.4429 + vertex 1.7193 0.998245 2.44574 + endloop + endfacet + facet normal 0.713161 -0.0799603 0.696425 + outer loop + vertex 1.7193 0.998245 2.44574 + vertex 1.71618 0.993772 2.44842 + vertex 1.71931 0.992093 2.44502 + endloop + endfacet + facet normal 0.722828 -0.0937723 0.684636 + outer loop + vertex 1.71679 0.999508 2.44857 + vertex 1.71618 0.993772 2.44842 + vertex 1.7193 0.998245 2.44574 + endloop + endfacet + facet normal 0.550629 -0.635572 0.541161 + outer loop + vertex 1.72255 1.00072 2.44073 + vertex 1.725 1.005 2.44326 + vertex 1.72329 1.005 2.445 + endloop + endfacet + facet normal 0.954802 -0.275783 0.110895 + outer loop + vertex 1.72126 0.99712 2.4429 + vertex 1.72255 1.00072 2.44073 + vertex 1.72329 1.005 2.445 + endloop + endfacet + facet normal 0.702449 -0.346838 0.621506 + outer loop + vertex 1.72126 0.99712 2.4429 + vertex 1.72329 1.005 2.445 + vertex 1.7193 0.998245 2.44574 + endloop + endfacet + facet normal 0.278069 -0.0595999 0.95871 + outer loop + vertex 1.72329 1.005 2.445 + vertex 1.71949 1.00393 2.44603 + vertex 1.7193 0.998245 2.44574 + endloop + endfacet + facet normal 0.732416 -0.0602259 0.678189 + outer loop + vertex 1.71949 1.00393 2.44603 + vertex 1.71679 0.999508 2.44857 + vertex 1.7193 0.998245 2.44574 + endloop + endfacet + facet normal 0.725845 -0.0517806 0.685907 + outer loop + vertex 1.71696 1.0048 2.44878 + vertex 1.71679 0.999508 2.44857 + vertex 1.71949 1.00393 2.44603 + endloop + endfacet + facet normal 0.258806 0.0155248 0.965805 + outer loop + vertex 1.72329 1.005 2.445 + vertex 1.72299 1.01 2.445 + vertex 1.71949 1.00393 2.44603 + endloop + endfacet + facet normal 0.284769 -0.000652301 0.958596 + outer loop + vertex 1.72299 1.01 2.445 + vertex 1.71934 1.00897 2.44608 + vertex 1.71949 1.00393 2.44603 + endloop + endfacet + facet normal 0.737559 0.0162742 0.675087 + outer loop + vertex 1.71934 1.00897 2.44608 + vertex 1.71696 1.0048 2.44878 + vertex 1.71949 1.00393 2.44603 + endloop + endfacet + facet normal 0.760055 -0.0130148 0.649728 + outer loop + vertex 1.71697 1.0102 2.44888 + vertex 1.71696 1.0048 2.44878 + vertex 1.71934 1.00897 2.44608 + endloop + endfacet + facet normal 0.279459 0.0195621 0.959958 + outer loop + vertex 1.72299 1.01 2.445 + vertex 1.72264 1.015 2.445 + vertex 1.71934 1.00897 2.44608 + endloop + endfacet + facet normal 0.280167 0.0191391 0.95976 + outer loop + vertex 1.72264 1.015 2.445 + vertex 1.71916 1.01414 2.44603 + vertex 1.71934 1.00897 2.44608 + endloop + endfacet + facet normal 0.769622 0.0329393 0.63765 + outer loop + vertex 1.71916 1.01414 2.44603 + vertex 1.71697 1.0102 2.44888 + vertex 1.71934 1.00897 2.44608 + endloop + endfacet + facet normal 0.782132 0.0153586 0.622924 + outer loop + vertex 1.717 1.01552 2.44871 + vertex 1.71697 1.0102 2.44888 + vertex 1.71916 1.01414 2.44603 + endloop + endfacet + facet normal 0.286269 -0.00743945 0.95812 + outer loop + vertex 1.72264 1.015 2.445 + vertex 1.72277 1.02 2.445 + vertex 1.71916 1.01414 2.44603 + endloop + endfacet + facet normal 0.257535 0.0116842 0.966198 + outer loop + vertex 1.72277 1.02 2.445 + vertex 1.71892 1.01921 2.44604 + vertex 1.71916 1.01414 2.44603 + endloop + endfacet + facet normal 0.786995 0.036584 0.615874 + outer loop + vertex 1.71892 1.01921 2.44604 + vertex 1.717 1.01552 2.44871 + vertex 1.71916 1.01414 2.44603 + endloop + endfacet + facet normal 0.789882 0.0325623 0.612394 + outer loop + vertex 1.71688 1.02029 2.44861 + vertex 1.717 1.01552 2.44871 + vertex 1.71892 1.01921 2.44604 + endloop + endfacet + facet normal 0.257305 0.0128643 0.966245 + outer loop + vertex 1.72277 1.02 2.445 + vertex 1.72252 1.025 2.445 + vertex 1.71892 1.01921 2.44604 + endloop + endfacet + facet normal 0.338091 -0.0420183 0.940175 + outer loop + vertex 1.72252 1.025 2.445 + vertex 1.71823 1.02337 2.44647 + vertex 1.71892 1.01921 2.44604 + endloop + endfacet + facet normal 0.795771 0.0692706 0.601623 + outer loop + vertex 1.71823 1.02337 2.44647 + vertex 1.71688 1.02029 2.44861 + vertex 1.71892 1.01921 2.44604 + endloop + endfacet + facet normal 0.824047 0.0317473 0.565632 + outer loop + vertex 1.71662 1.02502 2.44873 + vertex 1.71688 1.02029 2.44861 + vertex 1.71823 1.02337 2.44647 + endloop + endfacet + facet normal 0.482259 0.67513 -0.558234 + outer loop + vertex 1.72 1.03 2.44887 + vertex 1.72252 1.025 2.445 + vertex 1.72 1.0268 2.445 + endloop + endfacet + facet normal -0.275982 -0.671426 0.687766 + outer loop + vertex 1.72 1.03 2.44887 + vertex 1.71828 1.02871 2.44692 + vertex 1.72252 1.025 2.445 + endloop + endfacet + facet normal 0.350885 -0.0823516 0.93279 + outer loop + vertex 1.71828 1.02871 2.44692 + vertex 1.71823 1.02337 2.44647 + vertex 1.72252 1.025 2.445 + endloop + endfacet + facet normal 0.79133 -0.0590972 0.608526 + outer loop + vertex 1.71828 1.02871 2.44692 + vertex 1.71662 1.02502 2.44873 + vertex 1.71823 1.02337 2.44647 + endloop + endfacet + facet normal 0.746315 -0.0109176 0.665503 + outer loop + vertex 1.71649 1.03004 2.44896 + vertex 1.71662 1.02502 2.44873 + vertex 1.71828 1.02871 2.44692 + endloop + endfacet + facet normal -0.732801 -0.0488671 0.678686 + outer loop + vertex 1.72 1.035 2.44923 + vertex 1.71828 1.02871 2.44692 + vertex 1.72 1.03 2.44887 + endloop + endfacet + facet normal -0.428319 -0.205885 0.87986 + outer loop + vertex 1.71776 1.03388 2.44788 + vertex 1.71828 1.02871 2.44692 + vertex 1.72 1.035 2.44923 + endloop + endfacet + facet normal 0.732105 -0.0512176 0.679263 + outer loop + vertex 1.71776 1.03388 2.44788 + vertex 1.71649 1.03004 2.44896 + vertex 1.71828 1.02871 2.44692 + endloop + endfacet + facet normal 0.862075 -0.149087 0.484355 + outer loop + vertex 1.71699 1.03517 2.44964 + vertex 1.71649 1.03004 2.44896 + vertex 1.71776 1.03388 2.44788 + endloop + endfacet + facet normal -0.480323 -0.0924546 0.872205 + outer loop + vertex 1.72 1.04 2.44976 + vertex 1.71776 1.03388 2.44788 + vertex 1.72 1.035 2.44923 + endloop + endfacet + facet normal -0.325919 -0.166986 0.930533 + outer loop + vertex 1.71814 1.03715 2.4486 + vertex 1.71776 1.03388 2.44788 + vertex 1.72 1.04 2.44976 + endloop + endfacet + facet normal 0.829899 -0.211611 0.516225 + outer loop + vertex 1.71814 1.03715 2.4486 + vertex 1.71699 1.03517 2.44964 + vertex 1.71776 1.03388 2.44788 + endloop + endfacet + facet normal 0.850638 -0.523345 -0.0502488 + outer loop + vertex 1.72 1.04 2.45033 + vertex 1.71699 1.03517 2.44964 + vertex 1.71814 1.03715 2.4486 + endloop + endfacet + facet normal 0.245869 -0.498775 0.831127 + outer loop + vertex 1.72 1.04 2.44976 + vertex 1.72 1.0404 2.45 + vertex 1.71814 1.03715 2.4486 + endloop + endfacet + facet normal 0.861511 -0.323068 -0.391696 + outer loop + vertex 1.71814 1.03715 2.4486 + vertex 1.72 1.0404 2.45 + vertex 1.72 1.04 2.45033 + endloop + endfacet + facet normal -0.417862 0.424444 0.803267 + outer loop + vertex 1.71865 1.99559 2.44834 + vertex 1.72 1.99377 2.45 + vertex 1.72 1.995 2.44935 + endloop + endfacet + facet normal 0.877554 0.350775 -0.326888 + outer loop + vertex 1.71865 1.99559 2.44834 + vertex 1.72 1.995 2.45132 + vertex 1.72 1.99377 2.45 + endloop + endfacet + facet normal -0.593814 0.02416 0.804239 + outer loop + vertex 1.72 2 2.4492 + vertex 1.71865 1.99559 2.44834 + vertex 1.72 1.995 2.44935 + endloop + endfacet + facet normal -0.656225 0.0532762 0.752682 + outer loop + vertex 1.71822 1.99857 2.44775 + vertex 1.71865 1.99559 2.44834 + vertex 1.72 2 2.4492 + endloop + endfacet + facet normal 0.914017 0.0530618 -0.402191 + outer loop + vertex 1.71822 1.99857 2.44775 + vertex 1.72 1.995 2.45132 + vertex 1.71865 1.99559 2.44834 + endloop + endfacet + facet normal 0.623375 0.685706 0.37578 + outer loop + vertex 1.71682 1.99912 2.44909 + vertex 1.72 1.995 2.45132 + vertex 1.71822 1.99857 2.44775 + endloop + endfacet + facet normal -0.618558 -0.0266979 0.785286 + outer loop + vertex 1.72 2.005 2.44937 + vertex 1.71822 1.99857 2.44775 + vertex 1.72 2 2.4492 + endloop + endfacet + facet normal -0.909751 0.154565 0.385309 + outer loop + vertex 1.71847 2.00373 2.44626 + vertex 1.71822 1.99857 2.44775 + vertex 1.72 2.005 2.44937 + endloop + endfacet + facet normal 0.712989 0.162188 0.68216 + outer loop + vertex 1.71847 2.00373 2.44626 + vertex 1.71682 1.99912 2.44909 + vertex 1.71822 1.99857 2.44775 + endloop + endfacet + facet normal 0.767516 0.111533 0.631253 + outer loop + vertex 1.71669 2.00399 2.44839 + vertex 1.71682 1.99912 2.44909 + vertex 1.71847 2.00373 2.44626 + endloop + endfacet + facet normal -0.882518 0.37695 0.281196 + outer loop + vertex 1.72 2.00826 2.445 + vertex 1.71847 2.00373 2.44626 + vertex 1.72 2.005 2.44937 + endloop + endfacet + facet normal 0.215748 -0.329815 -0.919062 + outer loop + vertex 1.72 2.00826 2.445 + vertex 1.72266 2.01 2.445 + vertex 1.71847 2.00373 2.44626 + endloop + endfacet + facet normal 0.168594 0.0855098 0.981969 + outer loop + vertex 1.72266 2.01 2.445 + vertex 1.71892 2.00853 2.44577 + vertex 1.71847 2.00373 2.44626 + endloop + endfacet + facet normal 0.765312 -0.00577133 0.643633 + outer loop + vertex 1.71892 2.00853 2.44577 + vertex 1.71669 2.00399 2.44839 + vertex 1.71847 2.00373 2.44626 + endloop + endfacet + facet normal 0.764505 -0.00481485 0.6446 + outer loop + vertex 1.71678 2.00876 2.44832 + vertex 1.71669 2.00399 2.44839 + vertex 1.71892 2.00853 2.44577 + endloop + endfacet + facet normal 0.207901 -0.0162181 0.978015 + outer loop + vertex 1.72266 2.01 2.445 + vertex 1.72305 2.015 2.445 + vertex 1.71892 2.00853 2.44577 + endloop + endfacet + facet normal 0.197642 -0.00941365 0.980229 + outer loop + vertex 1.72305 2.015 2.445 + vertex 1.71914 2.01359 2.44578 + vertex 1.71892 2.00853 2.44577 + endloop + endfacet + facet normal 0.762833 -0.0330836 0.645749 + outer loop + vertex 1.71914 2.01359 2.44578 + vertex 1.71678 2.00876 2.44832 + vertex 1.71892 2.00853 2.44577 + endloop + endfacet + facet normal 0.739103 -0.00688405 0.673557 + outer loop + vertex 1.71668 2.01379 2.44848 + vertex 1.71678 2.00876 2.44832 + vertex 1.71914 2.01359 2.44578 + endloop + endfacet + facet normal 0.194792 -0.00117037 0.980844 + outer loop + vertex 1.72305 2.015 2.445 + vertex 1.72308 2.02 2.445 + vertex 1.71914 2.01359 2.44578 + endloop + endfacet + facet normal 0.211047 -0.0115839 0.977407 + outer loop + vertex 1.72308 2.02 2.445 + vertex 1.7192 2.01867 2.44582 + vertex 1.71914 2.01359 2.44578 + endloop + endfacet + facet normal 0.738728 -0.0152575 0.673831 + outer loop + vertex 1.7192 2.01867 2.44582 + vertex 1.71668 2.01379 2.44848 + vertex 1.71914 2.01359 2.44578 + endloop + endfacet + facet normal 0.710906 0.0150529 0.703126 + outer loop + vertex 1.71662 2.01899 2.44843 + vertex 1.71668 2.01379 2.44848 + vertex 1.7192 2.01867 2.44582 + endloop + endfacet + facet normal 0.204419 0.00858732 0.978846 + outer loop + vertex 1.72308 2.02 2.445 + vertex 1.72287 2.025 2.445 + vertex 1.7192 2.01867 2.44582 + endloop + endfacet + facet normal 0.200401 0.0110205 0.979652 + outer loop + vertex 1.72287 2.025 2.445 + vertex 1.71924 2.02353 2.44576 + vertex 1.7192 2.01867 2.44582 + endloop + endfacet + facet normal 0.710276 0.00379882 0.703913 + outer loop + vertex 1.71924 2.02353 2.44576 + vertex 1.71662 2.01899 2.44843 + vertex 1.7192 2.01867 2.44582 + endloop + endfacet + facet normal 0.685914 0.0314037 0.727005 + outer loop + vertex 1.71653 2.02405 2.44829 + vertex 1.71662 2.01899 2.44843 + vertex 1.71924 2.02353 2.44576 + endloop + endfacet + facet normal 0.212014 -0.0190824 0.97708 + outer loop + vertex 1.72287 2.025 2.445 + vertex 1.72332 2.03 2.445 + vertex 1.71924 2.02353 2.44576 + endloop + endfacet + facet normal 0.104417 0.0507803 0.993236 + outer loop + vertex 1.72332 2.03 2.445 + vertex 1.719 2.02794 2.44556 + vertex 1.71924 2.02353 2.44576 + endloop + endfacet + facet normal 0.688442 0.0699261 0.721913 + outer loop + vertex 1.719 2.02794 2.44556 + vertex 1.71653 2.02405 2.44829 + vertex 1.71924 2.02353 2.44576 + endloop + endfacet + facet normal 0.714268 0.0373537 0.698875 + outer loop + vertex 1.71642 2.02892 2.44814 + vertex 1.71653 2.02405 2.44829 + vertex 1.719 2.02794 2.44556 + endloop + endfacet + facet normal 0.13425 0.555138 0.820852 + outer loop + vertex 1.725 2.03 2.44311 + vertex 1.72339 2.03423 2.44051 + vertex 1.72122 2.03105 2.44302 + endloop + endfacet + facet normal 0.256 0.939509 0.227565 + outer loop + vertex 1.72332 2.03 2.445 + vertex 1.725 2.03 2.44311 + vertex 1.72122 2.03105 2.44302 + endloop + endfacet + facet normal -0.256554 0.71461 0.650778 + outer loop + vertex 1.72332 2.03 2.445 + vertex 1.72122 2.03105 2.44302 + vertex 1.719 2.02794 2.44556 + endloop + endfacet + facet normal 0.690919 0.0924668 0.716994 + outer loop + vertex 1.72122 2.03105 2.44302 + vertex 1.71862 2.03232 2.44536 + vertex 1.719 2.02794 2.44556 + endloop + endfacet + facet normal 0.722175 0.0937317 0.68533 + outer loop + vertex 1.71862 2.03232 2.44536 + vertex 1.71642 2.02892 2.44814 + vertex 1.719 2.02794 2.44556 + endloop + endfacet + facet normal 0.750973 0.0529456 0.658207 + outer loop + vertex 1.71621 2.03365 2.448 + vertex 1.71642 2.02892 2.44814 + vertex 1.71862 2.03232 2.44536 + endloop + endfacet + facet normal 0.640629 0.168392 0.749158 + outer loop + vertex 1.72339 2.03423 2.44051 + vertex 1.72294 2.0388 2.43987 + vertex 1.7207 2.03551 2.44253 + endloop + endfacet + facet normal 0.638559 0.157496 0.753285 + outer loop + vertex 1.72122 2.03105 2.44302 + vertex 1.72339 2.03423 2.44051 + vertex 1.7207 2.03551 2.44253 + endloop + endfacet + facet normal 0.702285 0.158434 0.694042 + outer loop + vertex 1.72122 2.03105 2.44302 + vertex 1.7207 2.03551 2.44253 + vertex 1.71862 2.03232 2.44536 + endloop + endfacet + facet normal 0.778672 0.0478113 0.625607 + outer loop + vertex 1.7207 2.03551 2.44253 + vertex 1.71837 2.03697 2.44531 + vertex 1.71862 2.03232 2.44536 + endloop + endfacet + facet normal 0.749657 0.04667 0.660179 + outer loop + vertex 1.71837 2.03697 2.44531 + vertex 1.71621 2.03365 2.448 + vertex 1.71862 2.03232 2.44536 + endloop + endfacet + facet normal 0.716343 0.0937777 0.691418 + outer loop + vertex 1.71554 2.03858 2.44802 + vertex 1.71621 2.03365 2.448 + vertex 1.71837 2.03697 2.44531 + endloop + endfacet + facet normal 0.755972 0.11531 0.644368 + outer loop + vertex 1.72294 2.0388 2.43987 + vertex 1.72266 2.04314 2.43943 + vertex 1.72051 2.04016 2.44248 + endloop + endfacet + facet normal 0.740544 0.0371005 0.670983 + outer loop + vertex 1.7207 2.03551 2.44253 + vertex 1.72294 2.0388 2.43987 + vertex 1.72051 2.04016 2.44248 + endloop + endfacet + facet normal 0.77654 0.0381583 0.628911 + outer loop + vertex 1.7207 2.03551 2.44253 + vertex 1.72051 2.04016 2.44248 + vertex 1.71837 2.03697 2.44531 + endloop + endfacet + facet normal 0.761441 0.062688 0.645196 + outer loop + vertex 1.72051 2.04016 2.44248 + vertex 1.71809 2.04142 2.44521 + vertex 1.71837 2.03697 2.44531 + endloop + endfacet + facet normal 0.708609 0.0606981 0.702985 + outer loop + vertex 1.71809 2.04142 2.44521 + vertex 1.71554 2.03858 2.44802 + vertex 1.71837 2.03697 2.44531 + endloop + endfacet + facet normal 0.671493 0.121886 0.730918 + outer loop + vertex 1.71558 2.04335 2.4472 + vertex 1.71554 2.03858 2.44802 + vertex 1.71809 2.04142 2.44521 + endloop + endfacet + facet normal 0.78719 0.0238758 0.616248 + outer loop + vertex 1.72266 2.04314 2.43943 + vertex 1.7226 2.04783 2.43932 + vertex 1.72005 2.04503 2.44268 + endloop + endfacet + facet normal 0.793534 0.0492853 0.606527 + outer loop + vertex 1.72051 2.04016 2.44248 + vertex 1.72266 2.04314 2.43943 + vertex 1.72005 2.04503 2.44268 + endloop + endfacet + facet normal 0.725338 0.092133 0.682199 + outer loop + vertex 1.71766 2.04478 2.44526 + vertex 1.72005 2.04503 2.44268 + vertex 1.7179 2.04813 2.44456 + endloop + endfacet + facet normal 0.726323 0.0833722 0.682278 + outer loop + vertex 1.71766 2.04478 2.44526 + vertex 1.71809 2.04142 2.44521 + vertex 1.72005 2.04503 2.44268 + endloop + endfacet + facet normal 0.758038 0.0441279 0.650716 + outer loop + vertex 1.71809 2.04142 2.44521 + vertex 1.72051 2.04016 2.44248 + vertex 1.72005 2.04503 2.44268 + endloop + endfacet + facet normal 0.652367 0.0726669 0.754411 + outer loop + vertex 1.71809 2.04142 2.44521 + vertex 1.71766 2.04478 2.44526 + vertex 1.71558 2.04335 2.4472 + endloop + endfacet + facet normal 0.761284 0.0300952 0.64772 + outer loop + vertex 1.7226 2.04783 2.43932 + vertex 1.72247 2.05277 2.43925 + vertex 1.72017 2.05019 2.44206 + endloop + endfacet + facet normal 0.771914 0.0580186 0.633074 + outer loop + vertex 1.72005 2.04503 2.44268 + vertex 1.7226 2.04783 2.43932 + vertex 1.72017 2.05019 2.44206 + endloop + endfacet + facet normal 0.70828 0.067915 0.702657 + outer loop + vertex 1.72017 2.05019 2.44206 + vertex 1.7179 2.04813 2.44456 + vertex 1.72005 2.04503 2.44268 + endloop + endfacet + facet normal 0.671069 0.139919 0.728073 + outer loop + vertex 1.7174 2.05269 2.44414 + vertex 1.7179 2.04813 2.44456 + vertex 1.72017 2.05019 2.44206 + endloop + endfacet + facet normal 0.702584 0.0856922 0.706422 + outer loop + vertex 1.72247 2.05277 2.43925 + vertex 1.72234 2.0576 2.43878 + vertex 1.71982 2.05529 2.44157 + endloop + endfacet + facet normal 0.715624 0.115517 0.688867 + outer loop + vertex 1.72017 2.05019 2.44206 + vertex 1.72247 2.05277 2.43925 + vertex 1.71982 2.05529 2.44157 + endloop + endfacet + facet normal 0.660449 0.116777 0.741734 + outer loop + vertex 1.71982 2.05529 2.44157 + vertex 1.7174 2.05269 2.44414 + vertex 1.72017 2.05019 2.44206 + endloop + endfacet + facet normal 0.592407 0.214682 0.776509 + outer loop + vertex 1.71598 2.05826 2.44368 + vertex 1.7174 2.05269 2.44414 + vertex 1.71982 2.05529 2.44157 + endloop + endfacet + facet normal 0.617652 0.154148 0.771196 + outer loop + vertex 1.72234 2.0576 2.43878 + vertex 1.72235 2.06088 2.43812 + vertex 1.71963 2.06072 2.44033 + endloop + endfacet + facet normal 0.643629 0.191682 0.740945 + outer loop + vertex 1.71982 2.05529 2.44157 + vertex 1.72234 2.0576 2.43878 + vertex 1.71963 2.06072 2.44033 + endloop + endfacet + facet normal 0.585825 0.199839 0.785413 + outer loop + vertex 1.71963 2.06072 2.44033 + vertex 1.71598 2.05826 2.44368 + vertex 1.71982 2.05529 2.44157 + endloop + endfacet + facet normal 0.540659 0.278225 0.793901 + outer loop + vertex 1.71543 2.06347 2.44223 + vertex 1.71598 2.05826 2.44368 + vertex 1.71963 2.06072 2.44033 + endloop + endfacet + facet normal 0.605088 0.32119 0.728495 + outer loop + vertex 1.7224 2.06454 2.43668 + vertex 1.72237 2.06869 2.43488 + vertex 1.71995 2.06759 2.43737 + endloop + endfacet + facet normal 0.507512 0.391205 0.767718 + outer loop + vertex 1.71995 2.06759 2.43737 + vertex 1.71664 2.06876 2.43897 + vertex 1.71824 2.06525 2.43969 + endloop + endfacet + facet normal 0.592072 0.306963 0.745134 + outer loop + vertex 1.7224 2.06454 2.43668 + vertex 1.71995 2.06759 2.43737 + vertex 1.71824 2.06525 2.43969 + endloop + endfacet + facet normal 0.5935 0.287651 0.751674 + outer loop + vertex 1.7224 2.06454 2.43668 + vertex 1.71824 2.06525 2.43969 + vertex 1.71963 2.06072 2.44033 + endloop + endfacet + facet normal 0.594077 0.287025 0.751458 + outer loop + vertex 1.7224 2.06454 2.43668 + vertex 1.71963 2.06072 2.44033 + vertex 1.72235 2.06088 2.43812 + endloop + endfacet + facet normal 0.540325 0.277339 0.794438 + outer loop + vertex 1.71963 2.06072 2.44033 + vertex 1.71824 2.06525 2.43969 + vertex 1.71543 2.06347 2.44223 + endloop + endfacet + facet normal 0.511146 0.485058 0.709541 + outer loop + vertex 1.72237 2.06869 2.43488 + vertex 1.72233 2.07089 2.43341 + vertex 1.71969 2.07066 2.43547 + endloop + endfacet + facet normal 0.511073 0.484914 0.709692 + outer loop + vertex 1.71995 2.06759 2.43737 + vertex 1.72237 2.06869 2.43488 + vertex 1.71969 2.07066 2.43547 + endloop + endfacet + facet normal 0.512283 0.484608 0.709028 + outer loop + vertex 1.71969 2.07066 2.43547 + vertex 1.71664 2.06876 2.43897 + vertex 1.71995 2.06759 2.43737 + endloop + endfacet + facet normal 0.476563 0.5291 0.702098 + outer loop + vertex 1.71608 2.07152 2.43727 + vertex 1.71664 2.06876 2.43897 + vertex 1.71969 2.07066 2.43547 + endloop + endfacet + facet normal 0.100214 0.141041 0.984919 + outer loop + vertex 1.72256 2.07371 2.43099 + vertex 1.725 2.07892 2.43 + vertex 1.72348 2.08 2.43 + endloop + endfacet + facet normal 0.147884 0.133306 0.97998 + outer loop + vertex 1.71883 2.07588 2.43126 + vertex 1.72256 2.07371 2.43099 + vertex 1.72348 2.08 2.43 + endloop + endfacet + facet normal 0.318581 0.66543 0.675062 + outer loop + vertex 1.71883 2.07588 2.43126 + vertex 1.71482 2.07586 2.43317 + vertex 1.71744 2.07349 2.43427 + endloop + endfacet + facet normal 0.405547 0.615532 0.67576 + outer loop + vertex 1.72256 2.07371 2.43099 + vertex 1.71883 2.07588 2.43126 + vertex 1.71744 2.07349 2.43427 + endloop + endfacet + facet normal 0.407818 0.610473 0.678975 + outer loop + vertex 1.72256 2.07371 2.43099 + vertex 1.71744 2.07349 2.43427 + vertex 1.71969 2.07066 2.43547 + endloop + endfacet + facet normal 0.486212 0.543865 0.683965 + outer loop + vertex 1.72256 2.07371 2.43099 + vertex 1.71969 2.07066 2.43547 + vertex 1.72233 2.07089 2.43341 + endloop + endfacet + facet normal 0.461755 0.63014 0.624264 + outer loop + vertex 1.71969 2.07066 2.43547 + vertex 1.71744 2.07349 2.43427 + vertex 1.71608 2.07152 2.43727 + endloop + endfacet + facet normal 0.324984 0.825381 0.461661 + outer loop + vertex 1.725 2.08 2.42893 + vertex 1.72 2.08137 2.43 + vertex 1.72348 2.08 2.43 + endloop + endfacet + facet normal 0.321531 0.854183 0.408644 + outer loop + vertex 1.725 2.08 2.42893 + vertex 1.725 2.08188 2.425 + vertex 1.72 2.08137 2.43 + endloop + endfacet + facet normal -0.00797547 0.995581 0.0935671 + outer loop + vertex 1.725 2.08188 2.425 + vertex 1.72 2.08184 2.425 + vertex 1.72 2.08137 2.43 + endloop + endfacet + facet normal -0.0699179 0.363418 0.928999 + outer loop + vertex 1.72348 2.08 2.43 + vertex 1.71686 2.07835 2.43015 + vertex 1.71883 2.07588 2.43126 + endloop + endfacet + facet normal 0.0137443 0.0349072 0.999296 + outer loop + vertex 1.72 2.08137 2.43 + vertex 1.71686 2.07835 2.43015 + vertex 1.72348 2.08 2.43 + endloop + endfacet + facet normal 0.342115 0.599217 0.723807 + outer loop + vertex 1.71883 2.07588 2.43126 + vertex 1.71686 2.07835 2.43015 + vertex 1.71482 2.07586 2.43317 + endloop + endfacet + facet normal 0.335506 -0.858713 0.387361 + outer loop + vertex 1.72866 0.955 2.425 + vertex 1.725 0.955 2.42817 + vertex 1.725 0.95357 2.425 + endloop + endfacet + facet normal 0.393778 0.783929 0.479994 + outer loop + vertex 1.72485 0.959843 2.43204 + vertex 1.73 0.958506 2.43 + vertex 1.72744 0.960147 2.42942 + endloop + endfacet + facet normal 0.314934 -0.201798 0.927412 + outer loop + vertex 1.72485 0.959843 2.43204 + vertex 1.72168 0.957396 2.43258 + vertex 1.73 0.958506 2.43 + endloop + endfacet + facet normal 0.301455 -0.66195 0.686256 + outer loop + vertex 1.72168 0.957396 2.43258 + vertex 1.725 0.956229 2.43 + vertex 1.73 0.958506 2.43 + endloop + endfacet + facet normal 0.550738 -0.580091 0.600152 + outer loop + vertex 1.72485 0.959843 2.43204 + vertex 1.72182 0.959449 2.43444 + vertex 1.72168 0.957396 2.43258 + endloop + endfacet + facet normal 0.701546 -0.260741 0.66321 + outer loop + vertex 1.72744 0.960147 2.42942 + vertex 1.72651 0.961383 2.43089 + vertex 1.72485 0.959843 2.43204 + endloop + endfacet + facet normal 0.614476 -0.416593 0.669977 + outer loop + vertex 1.72182 0.959449 2.43444 + vertex 1.7231 0.962217 2.43499 + vertex 1.72078 0.96077 2.43622 + endloop + endfacet + facet normal 0.597962 -0.412383 0.687301 + outer loop + vertex 1.72485 0.959843 2.43204 + vertex 1.7231 0.962217 2.43499 + vertex 1.72182 0.959449 2.43444 + endloop + endfacet + facet normal 0.72854 -0.252997 0.63657 + outer loop + vertex 1.72485 0.959843 2.43204 + vertex 1.72597 0.964327 2.43254 + vertex 1.7231 0.962217 2.43499 + endloop + endfacet + facet normal 0.697053 -0.249101 0.672359 + outer loop + vertex 1.72485 0.959843 2.43204 + vertex 1.72651 0.961383 2.43089 + vertex 1.72597 0.964327 2.43254 + endloop + endfacet + facet normal 0.596614 -0.339021 0.727404 + outer loop + vertex 1.7231 0.962217 2.43499 + vertex 1.721 0.963738 2.43742 + vertex 1.72078 0.96077 2.43622 + endloop + endfacet + facet normal 0.7909 -0.143344 0.594919 + outer loop + vertex 1.72597 0.964327 2.43254 + vertex 1.72641 0.97016 2.43336 + vertex 1.72392 0.966875 2.43588 + endloop + endfacet + facet normal 0.728044 -0.250538 0.638108 + outer loop + vertex 1.7231 0.962217 2.43499 + vertex 1.72597 0.964327 2.43254 + vertex 1.72392 0.966875 2.43588 + endloop + endfacet + facet normal 0.648943 -0.251832 0.717951 + outer loop + vertex 1.72392 0.966875 2.43588 + vertex 1.721 0.963738 2.43742 + vertex 1.7231 0.962217 2.43499 + endloop + endfacet + facet normal 0.660898 -0.272024 0.69944 + outer loop + vertex 1.72137 0.968698 2.439 + vertex 1.721 0.963738 2.43742 + vertex 1.72392 0.966875 2.43588 + endloop + endfacet + facet normal 0.839631 -0.0629821 0.539493 + outer loop + vertex 1.72641 0.97016 2.43336 + vertex 1.72669 0.975387 2.43354 + vertex 1.72447 0.972991 2.43672 + endloop + endfacet + facet normal 0.794561 -0.15142 0.588001 + outer loop + vertex 1.72392 0.966875 2.43588 + vertex 1.72641 0.97016 2.43336 + vertex 1.72447 0.972991 2.43672 + endloop + endfacet + facet normal 0.717581 -0.156975 0.678555 + outer loop + vertex 1.72447 0.972991 2.43672 + vertex 1.72137 0.968698 2.439 + vertex 1.72392 0.966875 2.43588 + endloop + endfacet + facet normal 0.761434 -0.226404 0.60742 + outer loop + vertex 1.72232 0.973565 2.43962 + vertex 1.72137 0.968698 2.439 + vertex 1.72447 0.972991 2.43672 + endloop + endfacet + facet normal 0.881512 0.00190381 0.472158 + outer loop + vertex 1.72669 0.975387 2.43354 + vertex 1.72678 0.98002 2.43335 + vertex 1.72551 0.977932 2.43573 + endloop + endfacet + facet normal 0.841773 -0.0706743 0.535185 + outer loop + vertex 1.72447 0.972991 2.43672 + vertex 1.72669 0.975387 2.43354 + vertex 1.72551 0.977932 2.43573 + endloop + endfacet + facet normal 0.750863 -0.0711996 0.656609 + outer loop + vertex 1.72232 0.973565 2.43962 + vertex 1.72345 0.978093 2.43882 + vertex 1.72107 0.975617 2.44127 + endloop + endfacet + facet normal 0.792202 -0.0910056 0.603435 + outer loop + vertex 1.72232 0.973565 2.43962 + vertex 1.72447 0.972991 2.43672 + vertex 1.72345 0.978093 2.43882 + endloop + endfacet + facet normal 0.829061 -0.0639415 0.55549 + outer loop + vertex 1.72447 0.972991 2.43672 + vertex 1.72551 0.977932 2.43573 + vertex 1.72345 0.978093 2.43882 + endloop + endfacet + facet normal 0.756133 -0.0837933 0.649031 + outer loop + vertex 1.72345 0.978093 2.43882 + vertex 1.72091 0.979457 2.44195 + vertex 1.72107 0.975617 2.44127 + endloop + endfacet + facet normal 0.828581 -0.124417 0.54587 + outer loop + vertex 1.72678 0.98002 2.43335 + vertex 1.72741 0.984499 2.43341 + vertex 1.72554 0.982929 2.43589 + endloop + endfacet + facet normal 0.889402 -0.0205509 0.456664 + outer loop + vertex 1.72551 0.977932 2.43573 + vertex 1.72678 0.98002 2.43335 + vertex 1.72554 0.982929 2.43589 + endloop + endfacet + facet normal 0.831514 -0.0234295 0.555009 + outer loop + vertex 1.72551 0.977932 2.43573 + vertex 1.72554 0.982929 2.43589 + vertex 1.72345 0.978093 2.43882 + endloop + endfacet + facet normal 0.822329 -0.0110692 0.568905 + outer loop + vertex 1.72554 0.982929 2.43589 + vertex 1.72306 0.983369 2.4395 + vertex 1.72345 0.978093 2.43882 + endloop + endfacet + facet normal 0.771763 -0.023472 0.635477 + outer loop + vertex 1.72306 0.983369 2.4395 + vertex 1.72091 0.979457 2.44195 + vertex 1.72345 0.978093 2.43882 + endloop + endfacet + facet normal 0.799799 -0.0630203 0.59695 + outer loop + vertex 1.72063 0.984359 2.44286 + vertex 1.72091 0.979457 2.44195 + vertex 1.72306 0.983369 2.4395 + endloop + endfacet + facet normal -0.332429 -0.135914 0.933284 + outer loop + vertex 1.72741 0.984499 2.43341 + vertex 1.73 0.989095 2.435 + vertex 1.72963 0.99 2.435 + endloop + endfacet + facet normal 0.829414 -0.435368 0.350039 + outer loop + vertex 1.72741 0.984499 2.43341 + vertex 1.72963 0.99 2.435 + vertex 1.72554 0.982929 2.43589 + endloop + endfacet + facet normal 0.455616 -0.152532 0.877011 + outer loop + vertex 1.72554 0.982929 2.43589 + vertex 1.72963 0.99 2.435 + vertex 1.72463 0.987255 2.43712 + endloop + endfacet + facet normal 0.823704 0.0134217 0.566861 + outer loop + vertex 1.72554 0.982929 2.43589 + vertex 1.72463 0.987255 2.43712 + vertex 1.72306 0.983369 2.4395 + endloop + endfacet + facet normal 0.813732 0.0258827 0.580663 + outer loop + vertex 1.72463 0.987255 2.43712 + vertex 1.72266 0.988114 2.43983 + vertex 1.72306 0.983369 2.4395 + endloop + endfacet + facet normal 0.813653 0.0258681 0.580776 + outer loop + vertex 1.72266 0.988114 2.43983 + vertex 1.72063 0.984359 2.44286 + vertex 1.72306 0.983369 2.4395 + endloop + endfacet + facet normal 0.857909 -0.0543867 0.510916 + outer loop + vertex 1.72106 0.989275 2.44264 + vertex 1.72063 0.984359 2.44286 + vertex 1.72266 0.988114 2.43983 + endloop + endfacet + facet normal 0.605299 0.666002 -0.435952 + outer loop + vertex 1.725 0.995 2.43621 + vertex 1.72963 0.99 2.435 + vertex 1.725 0.994208 2.435 + endloop + endfacet + facet normal 0.434786 0.189568 0.880355 + outer loop + vertex 1.725 0.995 2.43621 + vertex 1.72408 0.992838 2.43713 + vertex 1.72963 0.99 2.435 + endloop + endfacet + facet normal 0.373713 0.0353646 0.92687 + outer loop + vertex 1.72408 0.992838 2.43713 + vertex 1.72463 0.987255 2.43712 + vertex 1.72963 0.99 2.435 + endloop + endfacet + facet normal 0.819303 0.0788442 0.567913 + outer loop + vertex 1.72463 0.987255 2.43712 + vertex 1.72408 0.992838 2.43713 + vertex 1.72266 0.988114 2.43983 + endloop + endfacet + facet normal 0.858985 0.0342266 0.510856 + outer loop + vertex 1.72408 0.992838 2.43713 + vertex 1.72239 0.992594 2.43999 + vertex 1.72266 0.988114 2.43983 + endloop + endfacet + facet normal 0.874797 0.0361348 0.48314 + outer loop + vertex 1.72239 0.992594 2.43999 + vertex 1.72106 0.989275 2.44264 + vertex 1.72266 0.988114 2.43983 + endloop + endfacet + facet normal 0.911456 -0.0373254 0.409701 + outer loop + vertex 1.72139 0.992983 2.44225 + vertex 1.72106 0.989275 2.44264 + vertex 1.72239 0.992594 2.43999 + endloop + endfacet + facet normal 0.881981 -0.190537 0.431051 + outer loop + vertex 1.725 1 2.43842 + vertex 1.72408 0.992838 2.43713 + vertex 1.725 0.995 2.43621 + endloop + endfacet + facet normal 0.12132 -0.191284 0.974008 + outer loop + vertex 1.72302 0.998459 2.43836 + vertex 1.72408 0.992838 2.43713 + vertex 1.725 1 2.43842 + endloop + endfacet + facet normal 0.953505 -0.0989273 0.284679 + outer loop + vertex 1.72209 0.99592 2.44059 + vertex 1.72302 0.998459 2.43836 + vertex 1.72255 1.00072 2.44073 + endloop + endfacet + facet normal 0.918433 0.0110484 0.395422 + outer loop + vertex 1.72209 0.99592 2.44059 + vertex 1.72239 0.992594 2.43999 + vertex 1.72302 0.998459 2.43836 + endloop + endfacet + facet normal 0.857845 0.0496833 0.511501 + outer loop + vertex 1.72239 0.992594 2.43999 + vertex 1.72408 0.992838 2.43713 + vertex 1.72302 0.998459 2.43836 + endloop + endfacet + facet normal 0.91503 0.00931622 0.403278 + outer loop + vertex 1.72239 0.992594 2.43999 + vertex 1.72209 0.99592 2.44059 + vertex 1.72139 0.992983 2.44225 + endloop + endfacet + facet normal -0.0471013 0.023999 0.998602 + outer loop + vertex 1.725 1.005 2.4383 + vertex 1.72302 0.998459 2.43836 + vertex 1.725 1 2.43842 + endloop + endfacet + facet normal 0.266911 -0.0713306 0.961078 + outer loop + vertex 1.72326 1.00414 2.43872 + vertex 1.72302 0.998459 2.43836 + vertex 1.725 1.005 2.4383 + endloop + endfacet + facet normal 0.967337 -0.0567496 0.24706 + outer loop + vertex 1.72326 1.00414 2.43872 + vertex 1.72255 1.00072 2.44073 + vertex 1.72302 0.998459 2.43836 + endloop + endfacet + facet normal 0.895404 -0.349613 -0.27572 + outer loop + vertex 1.725 1.005 2.44326 + vertex 1.72255 1.00072 2.44073 + vertex 1.72326 1.00414 2.43872 + endloop + endfacet + facet normal 0.23869 -0.00972367 0.971047 + outer loop + vertex 1.725 1.01 2.43835 + vertex 1.72326 1.00414 2.43872 + vertex 1.725 1.005 2.4383 + endloop + endfacet + facet normal 0.836467 -0.216007 0.50365 + outer loop + vertex 1.72372 1.0076 2.43944 + vertex 1.72326 1.00414 2.43872 + vertex 1.725 1.01 2.43835 + endloop + endfacet + facet normal 0.936108 -0.0506795 -0.348043 + outer loop + vertex 1.72372 1.0076 2.43944 + vertex 1.725 1.005 2.44326 + vertex 1.72326 1.00414 2.43872 + endloop + endfacet + facet normal 0.940529 -0.0338004 -0.338028 + outer loop + vertex 1.725 1.01 2.44276 + vertex 1.725 1.005 2.44326 + vertex 1.72372 1.0076 2.43944 + endloop + endfacet + facet normal 0.881887 -0.306374 0.358343 + outer loop + vertex 1.725 1.01 2.43835 + vertex 1.725 1.01193 2.44 + vertex 1.72372 1.0076 2.43944 + endloop + endfacet + facet normal 0.949494 -0.257148 -0.179821 + outer loop + vertex 1.72372 1.0076 2.43944 + vertex 1.725 1.01193 2.44 + vertex 1.725 1.01 2.44276 + endloop + endfacet + facet normal 0.52762 -0.537257 -0.658006 + outer loop + vertex 1.72611 2.025 2.44 + vertex 1.725 2.02391 2.44 + vertex 1.725 2.025 2.43911 + endloop + endfacet + facet normal 0.646954 -0.658769 0.384023 + outer loop + vertex 1.72611 2.025 2.44 + vertex 1.725 2.025 2.44187 + vertex 1.725 2.02391 2.44 + endloop + endfacet + facet normal 0.854753 -0.109417 0.50737 + outer loop + vertex 1.72675 2.03 2.44 + vertex 1.725 2.025 2.44187 + vertex 1.72611 2.025 2.44 + endloop + endfacet + facet normal 0.865122 -0.120734 0.486813 + outer loop + vertex 1.725 2.03 2.44311 + vertex 1.725 2.025 2.44187 + vertex 1.72675 2.03 2.44 + endloop + endfacet + facet normal 0.871019 -0.0331014 0.490132 + outer loop + vertex 1.72694 2.035 2.44 + vertex 1.725 2.03 2.44311 + vertex 1.72675 2.03 2.44 + endloop + endfacet + facet normal 0.0086962 0.525694 0.850629 + outer loop + vertex 1.72339 2.03423 2.44051 + vertex 1.725 2.03 2.44311 + vertex 1.72694 2.035 2.44 + endloop + endfacet + facet normal 0.142632 -0.000285658 0.989776 + outer loop + vertex 1.72695 2.04 2.44 + vertex 1.72339 2.03423 2.44051 + vertex 1.72694 2.035 2.44 + endloop + endfacet + facet normal -0.0718889 0.131963 0.988644 + outer loop + vertex 1.72294 2.0388 2.43987 + vertex 1.72339 2.03423 2.44051 + vertex 1.72695 2.04 2.44 + endloop + endfacet + facet normal 0.90784 0.0381153 0.41758 + outer loop + vertex 1.72925 2.04 2.435 + vertex 1.72904 2.045 2.435 + vertex 1.72695 2.04 2.44 + endloop + endfacet + facet normal -0.163512 0.730925 0.66258 + outer loop + vertex 1.72904 2.045 2.435 + vertex 1.72499 2.04197 2.43735 + vertex 1.72695 2.04 2.44 + endloop + endfacet + facet normal -0.230445 0.692642 0.683478 + outer loop + vertex 1.72499 2.04197 2.43735 + vertex 1.72294 2.0388 2.43987 + vertex 1.72695 2.04 2.44 + endloop + endfacet + facet normal 0.692703 0.117965 0.711511 + outer loop + vertex 1.72266 2.04314 2.43943 + vertex 1.72294 2.0388 2.43987 + vertex 1.72499 2.04197 2.43735 + endloop + endfacet + facet normal -0.125094 0.616841 0.777083 + outer loop + vertex 1.73 2.0483 2.435 + vertex 1.72697 2.05 2.43316 + vertex 1.72548 2.04613 2.43599 + endloop + endfacet + facet normal 0.246729 -0.0717763 0.966423 + outer loop + vertex 1.73 2.0483 2.435 + vertex 1.72548 2.04613 2.43599 + vertex 1.72904 2.045 2.435 + endloop + endfacet + facet normal 0.334269 0.255722 0.907122 + outer loop + vertex 1.72904 2.045 2.435 + vertex 1.72548 2.04613 2.43599 + vertex 1.72499 2.04197 2.43735 + endloop + endfacet + facet normal 0.697758 0.146566 0.701179 + outer loop + vertex 1.72548 2.04613 2.43599 + vertex 1.72266 2.04314 2.43943 + vertex 1.72499 2.04197 2.43735 + endloop + endfacet + facet normal 0.761904 0.0243084 0.647233 + outer loop + vertex 1.7226 2.04783 2.43932 + vertex 1.72266 2.04314 2.43943 + vertex 1.72548 2.04613 2.43599 + endloop + endfacet + facet normal 0.811071 0.0591422 0.58195 + outer loop + vertex 1.72697 2.05 2.43316 + vertex 1.72656 2.05421 2.43332 + vertex 1.72471 2.05078 2.43624 + endloop + endfacet + facet normal 0.813402 0.104154 0.572301 + outer loop + vertex 1.72548 2.04613 2.43599 + vertex 1.72697 2.05 2.43316 + vertex 1.72471 2.05078 2.43624 + endloop + endfacet + facet normal 0.776132 0.0952911 0.623329 + outer loop + vertex 1.72471 2.05078 2.43624 + vertex 1.7226 2.04783 2.43932 + vertex 1.72548 2.04613 2.43599 + endloop + endfacet + facet normal 0.810549 0.0305466 0.584874 + outer loop + vertex 1.72247 2.05277 2.43925 + vertex 1.7226 2.04783 2.43932 + vertex 1.72471 2.05078 2.43624 + endloop + endfacet + facet normal 0.834227 -0.00151733 0.551419 + outer loop + vertex 1.72656 2.05421 2.43332 + vertex 1.72654 2.05861 2.43336 + vertex 1.72458 2.05563 2.43632 + endloop + endfacet + facet normal 0.837598 0.014393 0.546097 + outer loop + vertex 1.72471 2.05078 2.43624 + vertex 1.72656 2.05421 2.43332 + vertex 1.72458 2.05563 2.43632 + endloop + endfacet + facet normal 0.8053 0.0127643 0.59273 + outer loop + vertex 1.72458 2.05563 2.43632 + vertex 1.72247 2.05277 2.43925 + vertex 1.72471 2.05078 2.43624 + endloop + endfacet + facet normal 0.769805 0.0803608 0.6332 + outer loop + vertex 1.72234 2.0576 2.43878 + vertex 1.72247 2.05277 2.43925 + vertex 1.72458 2.05563 2.43632 + endloop + endfacet + facet normal 0.78477 0.0534143 0.617481 + outer loop + vertex 1.72654 2.05861 2.43336 + vertex 1.72654 2.0615 2.43311 + vertex 1.72454 2.06052 2.43573 + endloop + endfacet + facet normal 0.792905 0.0782508 0.604299 + outer loop + vertex 1.72458 2.05563 2.43632 + vertex 1.72654 2.05861 2.43336 + vertex 1.72454 2.06052 2.43573 + endloop + endfacet + facet normal 0.770169 0.0815107 0.632611 + outer loop + vertex 1.72454 2.06052 2.43573 + vertex 1.72234 2.0576 2.43878 + vertex 1.72458 2.05563 2.43632 + endloop + endfacet + facet normal 0.740779 0.131166 0.658819 + outer loop + vertex 1.72235 2.06088 2.43812 + vertex 1.72234 2.0576 2.43878 + vertex 1.72454 2.06052 2.43573 + endloop + endfacet + facet normal 0.665446 0.29491 0.685719 + outer loop + vertex 1.72661 2.06482 2.43259 + vertex 1.72718 2.06894 2.43026 + vertex 1.72468 2.06753 2.4333 + endloop + endfacet + facet normal 0.638627 0.310823 0.703949 + outer loop + vertex 1.72468 2.06753 2.4333 + vertex 1.72237 2.06869 2.43488 + vertex 1.7224 2.06454 2.43668 + endloop + endfacet + facet normal 0.65812 0.287019 0.696059 + outer loop + vertex 1.72661 2.06482 2.43259 + vertex 1.72468 2.06753 2.4333 + vertex 1.7224 2.06454 2.43668 + endloop + endfacet + facet normal 0.677666 0.192316 0.709777 + outer loop + vertex 1.72661 2.06482 2.43259 + vertex 1.7224 2.06454 2.43668 + vertex 1.72454 2.06052 2.43573 + endloop + endfacet + facet normal 0.778318 0.0805463 0.622682 + outer loop + vertex 1.72661 2.06482 2.43259 + vertex 1.72454 2.06052 2.43573 + vertex 1.72654 2.0615 2.43311 + endloop + endfacet + facet normal 0.733606 0.239607 0.635932 + outer loop + vertex 1.72454 2.06052 2.43573 + vertex 1.7224 2.06454 2.43668 + vertex 1.72235 2.06088 2.43812 + endloop + endfacet + facet normal 0.601331 0.543275 0.585878 + outer loop + vertex 1.72718 2.06894 2.43026 + vertex 1.72604 2.0715 2.42906 + vertex 1.7243 2.07028 2.43197 + endloop + endfacet + facet normal 0.599563 0.412185 0.686023 + outer loop + vertex 1.72468 2.06753 2.4333 + vertex 1.72718 2.06894 2.43026 + vertex 1.7243 2.07028 2.43197 + endloop + endfacet + facet normal 0.646475 0.400838 0.649153 + outer loop + vertex 1.7243 2.07028 2.43197 + vertex 1.72237 2.06869 2.43488 + vertex 1.72468 2.06753 2.4333 + endloop + endfacet + facet normal 0.61178 0.448027 0.651918 + outer loop + vertex 1.72233 2.07089 2.43341 + vertex 1.72237 2.06869 2.43488 + vertex 1.7243 2.07028 2.43197 + endloop + endfacet + facet normal 0.63017 0.546475 0.551589 + outer loop + vertex 1.72844 2.08 2.425 + vertex 1.725 2.08 2.42893 + vertex 1.725 2.07892 2.43 + endloop + endfacet + facet normal 0.575055 0.623048 0.530211 + outer loop + vertex 1.72844 2.08 2.425 + vertex 1.725 2.07892 2.43 + vertex 1.73 2.07856 2.425 + endloop + endfacet + facet normal 0.69962 -0.103169 0.707027 + outer loop + vertex 1.73 2.07856 2.425 + vertex 1.725 2.07892 2.43 + vertex 1.72743 2.07421 2.42691 + endloop + endfacet + facet normal 0.641 0.492759 0.588479 + outer loop + vertex 1.72604 2.0715 2.42906 + vertex 1.72256 2.07371 2.43099 + vertex 1.7243 2.07028 2.43197 + endloop + endfacet + facet normal 0.598714 0.286674 0.747904 + outer loop + vertex 1.72604 2.0715 2.42906 + vertex 1.72743 2.07421 2.42691 + vertex 1.72256 2.07371 2.43099 + endloop + endfacet + facet normal 0.644219 -0.158801 0.748174 + outer loop + vertex 1.72743 2.07421 2.42691 + vertex 1.725 2.07892 2.43 + vertex 1.72256 2.07371 2.43099 + endloop + endfacet + facet normal 0.606627 0.486731 0.628567 + outer loop + vertex 1.7243 2.07028 2.43197 + vertex 1.72256 2.07371 2.43099 + vertex 1.72233 2.07089 2.43341 + endloop + endfacet + facet normal 0.442213 0.809088 0.387071 + outer loop + vertex 1.72844 2.08 2.425 + vertex 1.725 2.08188 2.425 + vertex 1.725 2.08 2.42893 + endloop + endfacet + facet normal 0.471233 0.541873 0.695926 + outer loop + vertex 1.73016 0.961021 2.42702 + vertex 1.735 0.9594 2.425 + vertex 1.7324 0.96228 2.42452 + endloop + endfacet + facet normal 0.465849 0.664246 0.584604 + outer loop + vertex 1.73016 0.961021 2.42702 + vertex 1.73 0.958506 2.43 + vertex 1.735 0.9594 2.425 + endloop + endfacet + facet normal 0.535648 -0.7421 0.40295 + outer loop + vertex 1.73 0.958506 2.43 + vertex 1.73 0.955791 2.425 + vertex 1.735 0.9594 2.425 + endloop + endfacet + facet normal 0.318529 0.716385 0.62075 + outer loop + vertex 1.73016 0.961021 2.42702 + vertex 1.72744 0.960147 2.42942 + vertex 1.73 0.958506 2.43 + endloop + endfacet + facet normal 0.412102 -0.816523 0.404305 + outer loop + vertex 1.7324 0.96228 2.42452 + vertex 1.735 0.965 2.42736 + vertex 1.73241 0.965 2.43 + endloop + endfacet + facet normal 0.706062 -0.63487 0.313713 + outer loop + vertex 1.73016 0.961021 2.42702 + vertex 1.7324 0.96228 2.42452 + vertex 1.73241 0.965 2.43 + endloop + endfacet + facet normal 0.713749 -0.243684 0.656643 + outer loop + vertex 1.72744 0.960147 2.42942 + vertex 1.72865 0.96392 2.42951 + vertex 1.72651 0.961383 2.43089 + endloop + endfacet + facet normal 0.685356 -0.235379 0.689119 + outer loop + vertex 1.72744 0.960147 2.42942 + vertex 1.73016 0.961021 2.42702 + vertex 1.72865 0.96392 2.42951 + endloop + endfacet + facet normal 0.0783778 -0.626131 0.775769 + outer loop + vertex 1.73016 0.961021 2.42702 + vertex 1.73241 0.965 2.43 + vertex 1.72865 0.96392 2.42951 + endloop + endfacet + facet normal 0.711582 -0.239799 0.660415 + outer loop + vertex 1.72865 0.96392 2.42951 + vertex 1.72597 0.964327 2.43254 + vertex 1.72651 0.961383 2.43089 + endloop + endfacet + facet normal -0.129148 -0.00103149 0.991625 + outer loop + vertex 1.73241 0.965 2.43 + vertex 1.73237 0.97 2.43 + vertex 1.72865 0.96392 2.42951 + endloop + endfacet + facet normal 0.201569 -0.200868 0.958656 + outer loop + vertex 1.73237 0.97 2.43 + vertex 1.72868 0.969047 2.43058 + vertex 1.72865 0.96392 2.42951 + endloop + endfacet + facet normal 0.732293 -0.143308 0.66574 + outer loop + vertex 1.72868 0.969047 2.43058 + vertex 1.72597 0.964327 2.43254 + vertex 1.72865 0.96392 2.42951 + endloop + endfacet + facet normal 0.736767 -0.148401 0.65966 + outer loop + vertex 1.72641 0.97016 2.43336 + vertex 1.72597 0.964327 2.43254 + vertex 1.72868 0.969047 2.43058 + endloop + endfacet + facet normal 0.155586 -0.0052897 0.987808 + outer loop + vertex 1.73237 0.97 2.43 + vertex 1.73254 0.975 2.43 + vertex 1.72868 0.969047 2.43058 + endloop + endfacet + facet normal 0.270615 -0.0826372 0.959134 + outer loop + vertex 1.73254 0.975 2.43 + vertex 1.72865 0.974066 2.43102 + vertex 1.72868 0.969047 2.43058 + endloop + endfacet + facet normal 0.763964 -0.0517627 0.64318 + outer loop + vertex 1.72865 0.974066 2.43102 + vertex 1.72641 0.97016 2.43336 + vertex 1.72868 0.969047 2.43058 + endloop + endfacet + facet normal 0.771921 -0.0626519 0.632623 + outer loop + vertex 1.72669 0.975387 2.43354 + vertex 1.72641 0.97016 2.43336 + vertex 1.72865 0.974066 2.43102 + endloop + endfacet + facet normal 0.246533 0.0281077 0.968727 + outer loop + vertex 1.73254 0.975 2.43 + vertex 1.73197 0.98 2.43 + vertex 1.72865 0.974066 2.43102 + endloop + endfacet + facet normal 0.388914 -0.0600426 0.919316 + outer loop + vertex 1.73197 0.98 2.43 + vertex 1.72815 0.977956 2.43148 + vertex 1.72865 0.974066 2.43102 + endloop + endfacet + facet normal 0.796847 0.0301214 0.60343 + outer loop + vertex 1.72815 0.977956 2.43148 + vertex 1.72669 0.975387 2.43354 + vertex 1.72865 0.974066 2.43102 + endloop + endfacet + facet normal 0.81059 0.00797611 0.585559 + outer loop + vertex 1.72678 0.98002 2.43335 + vertex 1.72669 0.975387 2.43354 + vertex 1.72815 0.977956 2.43148 + endloop + endfacet + facet normal 0.490909 0.649034 -0.581174 + outer loop + vertex 1.73 0.985 2.43392 + vertex 1.73197 0.98 2.43 + vertex 1.73 0.98149 2.43 + endloop + endfacet + facet normal 0.0390003 -0.606941 0.79379 + outer loop + vertex 1.73 0.985 2.43392 + vertex 1.72843 0.982284 2.43192 + vertex 1.73197 0.98 2.43 + endloop + endfacet + facet normal 0.41364 -0.118297 0.902723 + outer loop + vertex 1.72843 0.982284 2.43192 + vertex 1.72815 0.977956 2.43148 + vertex 1.73197 0.98 2.43 + endloop + endfacet + facet normal 0.735901 -0.115509 0.667163 + outer loop + vertex 1.72843 0.982284 2.43192 + vertex 1.72678 0.98002 2.43335 + vertex 1.72815 0.977956 2.43148 + endloop + endfacet + facet normal 0.734108 -0.112646 0.669624 + outer loop + vertex 1.72741 0.984499 2.43341 + vertex 1.72678 0.98002 2.43335 + vertex 1.72843 0.982284 2.43192 + endloop + endfacet + facet normal -0.620519 -0.19999 0.758261 + outer loop + vertex 1.73 0.985 2.43392 + vertex 1.73 0.989095 2.435 + vertex 1.72843 0.982284 2.43192 + endloop + endfacet + facet normal 0.271756 -0.447737 0.851869 + outer loop + vertex 1.72843 0.982284 2.43192 + vertex 1.73 0.989095 2.435 + vertex 1.72741 0.984499 2.43341 + endloop + endfacet + facet normal -0.949083 0.075537 0.305837 + outer loop + vertex 1.72896 2.05083 2.43115 + vertex 1.73 2.0483 2.435 + vertex 1.73 2.05 2.43458 + endloop + endfacet + facet normal 0.165964 0.844688 0.50888 + outer loop + vertex 1.72896 2.05083 2.43115 + vertex 1.72697 2.05 2.43316 + vertex 1.73 2.0483 2.435 + endloop + endfacet + facet normal -0.803751 0.475217 0.357984 + outer loop + vertex 1.73 2.05345 2.43 + vertex 1.72896 2.05083 2.43115 + vertex 1.73 2.05 2.43458 + endloop + endfacet + facet normal 0.285048 -0.476307 -0.831793 + outer loop + vertex 1.73 2.05345 2.43 + vertex 1.73259 2.055 2.43 + vertex 1.72896 2.05083 2.43115 + endloop + endfacet + facet normal 0.158072 0.131122 0.978683 + outer loop + vertex 1.73259 2.055 2.43 + vertex 1.72884 2.0541 2.43073 + vertex 1.72896 2.05083 2.43115 + endloop + endfacet + facet normal 0.683661 0.116826 0.720388 + outer loop + vertex 1.72884 2.0541 2.43073 + vertex 1.72697 2.05 2.43316 + vertex 1.72896 2.05083 2.43115 + endloop + endfacet + facet normal 0.750201 0.0502006 0.659301 + outer loop + vertex 1.72656 2.05421 2.43332 + vertex 1.72697 2.05 2.43316 + vertex 1.72884 2.0541 2.43073 + endloop + endfacet + facet normal 0.19454 -0.0190681 0.980709 + outer loop + vertex 1.73259 2.055 2.43 + vertex 1.73308 2.06 2.43 + vertex 1.72884 2.0541 2.43073 + endloop + endfacet + facet normal 0.198462 -0.0219895 0.979862 + outer loop + vertex 1.73308 2.06 2.43 + vertex 1.72891 2.05849 2.43081 + vertex 1.72884 2.0541 2.43073 + endloop + endfacet + facet normal 0.749349 -0.0239573 0.661741 + outer loop + vertex 1.72891 2.05849 2.43081 + vertex 1.72656 2.05421 2.43332 + vertex 1.72884 2.0541 2.43073 + endloop + endfacet + facet normal 0.732143 -0.0031279 0.681144 + outer loop + vertex 1.72654 2.05861 2.43336 + vertex 1.72656 2.05421 2.43332 + vertex 1.72891 2.05849 2.43081 + endloop + endfacet + facet normal 0.18692 0.0112168 0.982311 + outer loop + vertex 1.73308 2.06 2.43 + vertex 1.73278 2.065 2.43 + vertex 1.72891 2.05849 2.43081 + endloop + endfacet + facet normal 0.263391 -0.0365588 0.963996 + outer loop + vertex 1.73278 2.065 2.43 + vertex 1.72868 2.06248 2.43102 + vertex 1.72891 2.05849 2.43081 + endloop + endfacet + facet normal 0.73233 0.00515514 0.68093 + outer loop + vertex 1.72868 2.06248 2.43102 + vertex 1.72654 2.05861 2.43336 + vertex 1.72891 2.05849 2.43081 + endloop + endfacet + facet normal 0.680638 0.0633712 0.729874 + outer loop + vertex 1.72654 2.0615 2.43311 + vertex 1.72654 2.05861 2.43336 + vertex 1.72868 2.06248 2.43102 + endloop + endfacet + facet normal -0.0556081 0.497534 0.86566 + outer loop + vertex 1.72661 2.06482 2.43259 + vertex 1.7326 2.07 2.43 + vertex 1.72718 2.06894 2.43026 + endloop + endfacet + facet normal 0.492465 -0.139558 0.85907 + outer loop + vertex 1.72661 2.06482 2.43259 + vertex 1.72868 2.06248 2.43102 + vertex 1.7326 2.07 2.43 + endloop + endfacet + facet normal 0.237448 0.00854863 0.971363 + outer loop + vertex 1.72868 2.06248 2.43102 + vertex 1.73278 2.065 2.43 + vertex 1.7326 2.07 2.43 + endloop + endfacet + facet normal 0.66966 0.100138 0.735885 + outer loop + vertex 1.72868 2.06248 2.43102 + vertex 1.72661 2.06482 2.43259 + vertex 1.72654 2.0615 2.43311 + endloop + endfacet + facet normal 0.681238 0.248944 0.688434 + outer loop + vertex 1.735 2.07 2.42662 + vertex 1.735 2.07448 2.425 + vertex 1.73481 2.075 2.425 + endloop + endfacet + facet normal 0.796556 0.213528 0.565601 + outer loop + vertex 1.735 2.07 2.42662 + vertex 1.73481 2.075 2.425 + vertex 1.7326 2.07 2.43 + endloop + endfacet + facet normal -0.225849 0.736938 0.637114 + outer loop + vertex 1.7326 2.07 2.43 + vertex 1.73481 2.075 2.425 + vertex 1.72922 2.07129 2.42731 + endloop + endfacet + facet normal -0.13307 0.818106 0.55946 + outer loop + vertex 1.72922 2.07129 2.42731 + vertex 1.72718 2.06894 2.43026 + vertex 1.7326 2.07 2.43 + endloop + endfacet + facet normal 0.433938 0.534433 0.725313 + outer loop + vertex 1.72604 2.0715 2.42906 + vertex 1.72718 2.06894 2.43026 + vertex 1.72922 2.07129 2.42731 + endloop + endfacet + facet normal 0.214905 0.26211 0.940805 + outer loop + vertex 1.73481 2.075 2.425 + vertex 1.72743 2.07421 2.42691 + vertex 1.72922 2.07129 2.42731 + endloop + endfacet + facet normal 0.210954 0.285018 0.935021 + outer loop + vertex 1.73 2.07856 2.425 + vertex 1.72743 2.07421 2.42691 + vertex 1.73481 2.075 2.425 + endloop + endfacet + facet normal 0.462559 0.393515 0.794472 + outer loop + vertex 1.72922 2.07129 2.42731 + vertex 1.72743 2.07421 2.42691 + vertex 1.72604 2.0715 2.42906 + endloop + endfacet + facet normal -0.0220051 0.706865 0.707006 + outer loop + vertex 1.7334 0.961594 2.42276 + vertex 1.735 0.9594 2.425 + vertex 1.735 0.96 2.4244 + endloop + endfacet + facet normal 0.722245 0.676138 0.145602 + outer loop + vertex 1.7334 0.961594 2.42276 + vertex 1.7324 0.96228 2.42452 + vertex 1.735 0.9594 2.425 + endloop + endfacet + facet normal -0.615755 0.173709 0.768551 + outer loop + vertex 1.735 0.965 2.42327 + vertex 1.7334 0.961594 2.42276 + vertex 1.735 0.96 2.4244 + endloop + endfacet + facet normal 0.20245 -0.238339 0.949846 + outer loop + vertex 1.73346 0.963816 2.4233 + vertex 1.7334 0.961594 2.42276 + vertex 1.735 0.965 2.42327 + endloop + endfacet + facet normal 0.832434 -0.154728 0.532083 + outer loop + vertex 1.73346 0.963816 2.4233 + vertex 1.7324 0.96228 2.42452 + vertex 1.7334 0.961594 2.42276 + endloop + endfacet + facet normal 0.773788 -0.623667 -0.110867 + outer loop + vertex 1.735 0.965 2.42736 + vertex 1.7324 0.96228 2.42452 + vertex 1.73346 0.963816 2.4233 + endloop + endfacet + facet normal 0.303703 -0.371545 0.877336 + outer loop + vertex 1.735 0.965 2.42327 + vertex 1.735 0.969085 2.425 + vertex 1.73346 0.963816 2.4233 + endloop + endfacet + facet normal 0.936654 -0.175218 -0.303278 + outer loop + vertex 1.73346 0.963816 2.4233 + vertex 1.735 0.969085 2.425 + vertex 1.735 0.965 2.42736 + endloop + endfacet + facet normal 0.743099 -0.507869 0.435744 + outer loop + vertex 1.73595 2.07 2.425 + vertex 1.735 2.07 2.42662 + vertex 1.735 2.06861 2.425 + endloop + endfacet + facet normal 0.848552 0.179929 0.49758 + outer loop + vertex 1.73595 2.07 2.425 + vertex 1.735 2.07448 2.425 + vertex 1.735 2.07 2.42662 + endloop + endfacet +endsolid diff --git a/noether_examples/src/coverage_simulator_client.cpp b/noether_examples/src/coverage_simulator_client.cpp index feae5a87..eaa5e040 100644 --- a/noether_examples/src/coverage_simulator_client.cpp +++ b/noether_examples/src/coverage_simulator_client.cpp @@ -44,6 +44,7 @@ #include #include +#include /*This example shows how the thickness_simulator_node.cpp works. * First, it creates 3 meshes and three paths. @@ -76,7 +77,14 @@ vtkSmartPointer createPlaneMod(unsigned int grid_size_x, unsigned int switch (type) { case vtk_viewer::FLAT: - points->InsertNextPoint(x, y, vtkMath::Random(0.0, 0.001)); + if(x==grid_size_x) + { + points->InsertNextPoint(x, y, vtkMath::Random(0.0, 0.001)); + } + else + { + points->InsertNextPoint(x+0.25, y, vtkMath::Random(0.0, 0.001)); + } break; case vtk_viewer::SINUSOIDAL_1D: if(x==grid_size_x) @@ -85,7 +93,8 @@ vtkSmartPointer createPlaneMod(unsigned int grid_size_x, unsigned int } else { - points->InsertNextPoint(x+0.25, y, sin(double(y) / 2.0) + vtkMath::Random(0.0, 0.001)); } + points->InsertNextPoint(x+0.25, y, sin(double(y) / 2.0) + vtkMath::Random(0.0, 0.001)); + } break; case vtk_viewer::SINUSOIDAL_2D: if(x==grid_size_x) @@ -100,7 +109,6 @@ vtkSmartPointer createPlaneMod(unsigned int grid_size_x, unsigned int } } } - // Add the grid points to a polydata object vtkSmartPointer polydata = vtkSmartPointer::New(); polydata->SetPoints(points); @@ -108,6 +116,67 @@ vtkSmartPointer createPlaneMod(unsigned int grid_size_x, unsigned int return points; } +static std::string toLower(const std::string& in) +{ + std::string copy = in; + std::transform(copy.begin(), copy.end(), copy.begin(), ::tolower); + return copy; +} +//@brief This a helper function to read meshs from file +static bool readFile(std::string& file, std::vector >& mesh) +{ + if (!file.empty()) + { + // read data file + vtkSmartPointer data = vtkSmartPointer::New(); + std::vector buffer(file.size() + 1, '\0'); + char* str = buffer.data(); + strcpy(str, file.c_str()); + + char* pch; + pch = strtok(str, " ,.-"); + while (pch != NULL) + { + std::string extension(pch); + if (extension == "pcd" || extension == "stl" || extension == "STL" || extension == "ply") + { + break; + } + pch = strtok(NULL, " ,.-"); + } + + std::string extension = std::string(pch); + if (extension == "pcd") + { + vtk_viewer::loadPCDFile(file, data); + } + else if (extension == "STL" || extension == "stl") + { + data = vtk_viewer::readSTLFile(file); + } + else if (toLower(extension) == "ply") // PCL polygon mesh + { + pcl::PolygonMesh pcl_mesh; + vtk_viewer::loadPolygonMeshFromPLY(file, pcl_mesh); + vtk_viewer::pclEncodeMeshAndNormals(pcl_mesh, data); + } + else + { + ROS_ERROR("Unrecognized extension: '%s'. Program supports 'pcd', 'stl', 'STL', 'ply'", extension.c_str()); + return false; + } + + vtk_viewer::generateNormals(data); + mesh.push_back(data); + return true; + } + else + { + ROS_WARN_STREAM("'filename' parameter must be set to the path of a pcd or stl file"); + return false; + } +} + int main (int argc, char **argv) { ros::init(argc, argv, "test_noether_simulator"); @@ -127,12 +196,14 @@ int main (int argc, char **argv) std::vector myMeshs; std::vector myPath; - //......setup test meshes and path - pcl_msgs::PolygonMesh myMesh; - vtkSmartPointer points2 = vtkSmartPointer::New(); + //......setup test meshes and paths + pcl_msgs::PolygonMesh myMesh; + vtkSmartPointer points2 = vtkSmartPointer::New(); + if(argc ==1)//if no file name given + { //.......create control meshes - for(int count = 0; count<2; count++)//start multimesh creation loop + for(int count = 0; count<1; count++)//start multimesh creation loop { vtkSmartPointer points; //if(count==0) @@ -141,11 +212,13 @@ int main (int argc, char **argv) //} if(count==0) { - points = vtk_viewer::createPlane(19,10,vtk_viewer::SINUSOIDAL_1D); + //points = vtk_viewer::createPlane(19,10,vtk_viewer::SINUSOIDAL_1D); + points = vtk_viewer::createPlane(19,10,vtk_viewer::FLAT); } if(count==1) { points = createPlaneMod(19,10,vtk_viewer::SINUSOIDAL_1D); + //points = createPlaneMod(19,10,vtk_viewer::FLAT); } vtkSmartPointer data = vtkSmartPointer::New(); @@ -170,16 +243,16 @@ int main (int argc, char **argv) planner.setInputMesh(cut); tool_path_planner::ProcessTool tool; - tool.pt_spacing = 0.5; - tool.line_spacing = 0.75; - tool.tool_offset = 0.0; - tool.intersecting_plane_height = 0.15; + tool.pt_spacing = 5.0; + tool.line_spacing = 1.0; + tool.tool_offset = 1.0; + tool.intersecting_plane_height = 0.5; tool.simulator_nearest_neighbors = 30; tool.min_hole_size = 0.1; tool.min_segment_size = 1; tool.raster_angle = 0; tool.raster_wrt_global_axes = 0; - tool.simulator_tool_radius = 10.0; + tool.simulator_tool_radius = 3.0; tool.simulator_tool_height = 1; planner.setTool(tool); planner.setDebugMode(false); @@ -217,16 +290,110 @@ int main (int argc, char **argv) rasterPath.paths = myPath; goal.path.push_back(rasterPath); + //........end robot path + }//end multimesh creation loop + }//end no file name given + + else //.......read mesh from file + { + std::vector > fileMesh; + std::string fileLocation = argv[1]; + std::string fileType = ".stl"; + std::string curFile = " "; + //.......create control meshes + int numMeshs = 25; + for(int count = 0; count cut = vtkSmartPointer::New(); + cut = vtk_viewer::cutMesh(fileMesh[count], points2, false); + pcl::PolygonMesh *test = new(pcl::PolygonMesh); + pcl::VTKUtils::convertToPCL(cut, *test); + pcl_conversions::fromPCL(*test, myMesh); + if(count==4 ||count == 5||count==6|| count ==7 || count ==9 || count== 10 || (count >= 13&& count<24) ) + //if(count==22) + { + ROS_INFO("here"); + myMeshs.push_back(myMesh); + } + //........end create control meshes + //........create robot path + cut = vtk_viewer::cutMesh(fileMesh[count], points2, false);//possible redundant + pcl::VTKUtils::convertToPCL(cut, *test);//posible redundant + + // Run tool path planner on mesh + tool_path_planner::RasterToolPathPlanner planner; + planner.setInputMesh(cut); + + tool_path_planner::ProcessTool tool; + tool.pt_spacing = 50.0; + tool.line_spacing = 50.0; + tool.tool_offset = 0.0; + tool.intersecting_plane_height = 0.5; + tool.simulator_nearest_neighbors = 30; + tool.min_hole_size = 0.1; + tool.min_segment_size = 1; + tool.raster_angle = 0; + tool.raster_wrt_global_axes = 0; + tool.simulator_tool_radius = 100.0; + tool.simulator_tool_height = 20; + planner.setTool(tool); + planner.setDebugMode(false); + planner.computePaths(); + std::vector paths = planner.getPaths(); + //display path + vtk_viewer::VTKViewer viz; + std::vector color(3); + + double scale = 1.0; + + // Display mesh results + color[0] = 0.9; + color[1] = 0.9; + color[2] = 0.9; + viz.addPolyDataDisplay(cut, color); + + for(int i = 0; i < paths.size(); ++i) + { + color[0] = 0.2; + color[1] = 0.9; + color[2] = 0.2; + viz.addPolyNormalsDisplay(paths[i].line, color, scale); + + color[0] = 0.9; + color[1] = 0.9; + color[2] = 0.2; + viz.addPolyNormalsDisplay(paths[i].derivatives, color, scale); + } + viz.renderDisplay(); + //end display path + + myPath = tool_path_planner::toPosesMsgs(paths); + noether_msgs::ToolRasterPath rasterPath; + if(count==4 ||count == 5|| count == 6|| count ==7 || count ==9 || count== 10 || (count >= 13&& count<24) ) + //if(count==22) + { + ROS_INFO("here path"); + rasterPath.paths = myPath; + goal.path.push_back(rasterPath); + } + //........end robot path }//end multimesh creation loop + }//end else //set goal values goal.input_mesh = myMeshs; ac.sendGoal(goal); ROS_INFO(" sent mesh and path generation"); ROS_INFO("number of paths sent: %d ",goal.path.size()); //wait for the action to return - bool finished_before_timeout = ac.waitForResult(ros::Duration(300.0)); + bool finished_before_timeout = ac.waitForResult(); if (finished_before_timeout) { diff --git a/noether_simulator/src/coverage_simulator_node.cpp b/noether_simulator/src/coverage_simulator_node.cpp index b4c05997..efb058ac 100644 --- a/noether_simulator/src/coverage_simulator_node.cpp +++ b/noether_simulator/src/coverage_simulator_node.cpp @@ -146,17 +146,17 @@ class ProcessSimulatorNode{ //add tool tool_path_planner::ProcessTool tool; - nh_.param("/noether_simulator/pt_spacing",tool.pt_spacing, 0.5); - nh_.param("/noether_simulator/line_spacing",tool.line_spacing,10.75); + nh_.param("/noether_simulator/pt_spacing",tool.pt_spacing,50.0); + nh_.param("/noether_simulator/line_spacing",tool.line_spacing, 50.0); nh_.param("/noether_simulator/tool_offset",tool.tool_offset, 0.0); - nh_.param("/noether_simulator/intersecting_plane_hiehgt",tool.intersecting_plane_height,0.15); + nh_.param("/noether_simulator/intersecting_plane_hiehgt",tool.intersecting_plane_height,0.5); nh_.param("/noether_simulator/nearest_neighbors",tool.simulator_nearest_neighbors,30); nh_.param("/noether_simulator/min_hole_size",tool.min_hole_size,0.1); nh_.param("/noether_simulator/min_segment_size",tool.min_segment_size,1.0); nh_.param("/noether_simulator/raster_angle",tool.raster_angle,0.0); nh_.param("/noether_simulator/raster_wrt_global_axes",tool.raster_wrt_global_axes ,false); - nh_.param("/noether_simulator/tool_radius",tool.simulator_tool_radius,1.0); - nh_.param("/noether_simulator/tool_height",tool.simulator_tool_height,2.0); + nh_.param("/noether_simulator/tool_radius",tool.simulator_tool_radius,100.0); + nh_.param("/noether_simulator/tool_height",tool.simulator_tool_height,20.0); sim.setTool(tool); for(int i=0; i pointTree = vtkSmartPointer::New(); diff --git a/noether_simulator/src/noether_simulator.cpp b/noether_simulator/src/noether_simulator.cpp index c84ad2ad..587047cd 100644 --- a/noether_simulator/src/noether_simulator.cpp +++ b/noether_simulator/src/noether_simulator.cpp @@ -65,9 +65,9 @@ void NoetherSimulator::runSimulation() color[0] = 0.9; color[1] = 0.9; color[2] = 0.9; // densly sample surface based upon point spacing - double spacing = tool_.pt_spacing /10.0; + double meshSubSpacing = tool_.pt_spacing /10.0; vtkSmartPointer simulation_points;//output stored as private member variable - simulation_points = vtk_viewer::sampleMesh(input_mesh_, spacing); + simulation_points = vtk_viewer::sampleMesh(input_mesh_, meshSubSpacing); // add scalar data for all points // where color information is stored @@ -84,36 +84,39 @@ void NoetherSimulator::runSimulation() // the cylinder is defined in a different frame than the mesh or path vtkSmartPointer cylinder = vtkSmartPointer::New(); cylinder->SetCenter(0.0, 0.0,0.0); - cylinder->SetRadius(tool_.simulator_tool_radius*3); + cylinder->SetRadius(tool_.simulator_tool_radius); cylinder->SetHeight(tool_.simulator_tool_height); cylinder->SetResolution(20); cylinder->Update(); //test cone vtkSmartPointer cone = vtkSmartPointer::New(); - cone->SetCenter(0.0, 0.0, (double(tool_.simulator_tool_height)/2.0)); + cone->SetCenter(0.0, 0.0, (double(tool_.simulator_tool_height))); cone->SetRadius(tool_.simulator_tool_radius); double temp [3]; cone->GetDirection(temp); cone->SetDirection(0,0,1); + cone->GetDirection(temp); cone->SetHeight(tool_.simulator_tool_height); cone->SetResolution(20); cone->Update(); vtkSmartPointer cone_poly = vtkSmartPointer::New(); - cone_poly->DeepCopy(cone->GetOutput()); + //cone_poly->DeepCopy(cone->GetOutput()); + cone_poly->DeepCopy(cylinder->GetOutput()); + ////display cone - vtk_viewer::VTKViewer viewer; - std::vector color2(3); - color2[0] = 0.1; color2[1] = 0.1; color2[2] = 0.1; - viewer.addPolyDataDisplay(cone_poly, color2); - viewer.renderDisplay(); + //vtk_viewer::VTKViewer viewer; + //std::vector color2(3); + //color2[0] = 0.1; color2[1] = 0.1; color2[2] = 0.1; + //viewer.addPolyDataDisplay(cone_poly, color2); + //viewer.renderDisplay(); ////end display cone vtkSmartPointer tree = vtkSmartPointer::New(); - //tree->SetDataSet(cylinder->GetOutput()); - tree->SetDataSet(cone->GetOutput()); + tree->SetDataSet(cylinder->GetOutput()); + //tree->SetDataSet(cone->GetOutput()); tree->BuildLocator(); // use tool to integrate over time and distance @@ -128,8 +131,9 @@ void NoetherSimulator::runSimulation() double path_pt1[3], norm1[3], derv1[3]; this_path.line->GetPoints()->GetPoint(j, path_pt1); this_path.line->GetPointData()->GetNormals()->GetTuple(j, norm1); + printf("norm: %lf %lf %lf ", norm1[0],norm1[1],norm1[2]); this_path.derivatives->GetPointData()->GetNormals()->GetTuple(j, derv1); - + printf("direv: %f %f %f\n", derv1[0],derv1[1],derv1[2]); double path_pt2[3], norm2[3], derv2[3]; this_path.line->GetPoints()->GetPoint(j+1, path_pt2); this_path.line->GetPointData()->GetNormals()->GetTuple(j+1, norm2); @@ -146,8 +150,8 @@ void NoetherSimulator::runSimulation() vtkSmartPointer transform_filter = vtkSmartPointer::New(); vtkSmartPointer cylinder_poly = vtkSmartPointer::New(); - //cylinder_poly->DeepCopy(cylinder->GetOutput()); - cylinder_poly->DeepCopy(cone->GetOutput()); + cylinder_poly->DeepCopy(cylinder->GetOutput()); + //cylinder_poly->DeepCopy(cone->GetOutput()); transform_filter->SetInputData(cylinder_poly);//set data to be transformed (tool) transform_filter->SetTransform(trans);//set transform (tramsform tool to pt1 frame) @@ -247,13 +251,18 @@ void NoetherSimulator::runSimulation() // get scalar value, color data is stored in scalars double *tmp_value = scalars->GetTuple(index); //double value = *tmp_value + integral_sum; - double process_sum = 0.75; + double process_sum = 1; double value = *tmp_value + process_sum; scalars->SetTuple1(index, value);//update intensity values }// end loop through all tool points found - }// end loop through all process points in this path + simulation_points->GetPointData()->SetScalars(scalars); + + //display intermediate results + // simulation_points_ = simulation_points; + // displayResults(); + }// end loop through all process points in this path }// end loop through all paths // display of simulation points @@ -268,6 +277,7 @@ void NoetherSimulator::runSimulation() } // end runSimulation() + vtk_viewer::VTKViewer Fviewer; void NoetherSimulator::displayResults() { if(!simulation_points_) @@ -312,11 +322,11 @@ void NoetherSimulator::runSimulation() lower_bound = 0.0; } - vtk_viewer::VTKViewer viewer; + std::vector color2(3); color2[0] = 0.1; color2[1] = 0.1; color2[2] = 0.1; - viewer.addPolyDataDisplay(simulation_points_, color2, lower_bound, upper_bound); - viewer.renderDisplay(); + Fviewer.addPolyDataDisplay(simulation_points_, color2, lower_bound, upper_bound); + Fviewer.renderDisplay(); } vtkSmartPointer NoetherSimulator::createMatrix(double pt[3], double norm[3], double derv[3]) @@ -346,21 +356,37 @@ void NoetherSimulator::runSimulation() epose.matrix().col(2).head<3>() = -v; epose.matrix().col(3).head<3>() = Eigen::Vector3d(pt[0], pt[1], pt[2]); - //print out transforms - Eigen::Vector4d a1(0,0,0,0); - Eigen::Vector4d b1(0,0,0,0); - Eigen::Vector4d c1(0,0,0,0); - Eigen::Vector4d d1(0,0,0,0); - - a1 = epose*a; - b1 = epose*b; - c1 = epose*c; - d1 = epose*d; - ROS_INFO("w0: %f w1: %f w2: %f w3: %f\n",a1[0], a1[1], a1[2],a1[3]); - ROS_INFO("u0: %f u1: %f u2: %f u3: %f\n",b1[0], b1[1], b1[2],b1[3]); - ROS_INFO("-v0: %f -v1: %f -v2: %f -v3: %f\n",c1[0], c1[1], c1[2],c1[3]); - ROS_INFO("pt x:%f y:%f Z:%f last:%f\n",d1[0], d1[1], d1[2],d1[3]); - ROS_INFO(""); + //test transform cone z plane + //Eigen::Affine3d zpose = Eigen::Affine3d::Identity(); + //Eigen::Vector4d z0(1, 0, 0, 0); + //Eigen::Vector4d z1(0, 0, -1, 0); + //Eigen::Vector4d z2(0, 1, 0, 0); + //Eigen::Vector4d z3(0, 0, 0, 1); + + //zpose.matrix().col(0).head<4>() = z0; + //zpose.matrix().col(1).head<4>() = z1; + //zpose.matrix().col(2).head<4>() = z2; + //zpose.matrix().col(3).head<4>() = z3; + + //epose = epose*zpose; + + //setup to print out transforms + //Eigen::Vector4d a1(0,0,0,0); + //Eigen::Vector4d b1(0,0,0,0); + //Eigen::Vector4d c1(0,0,0,0); + //Eigen::Vector4d d1(0,0,0,0); + + //a1 = epose*a; + //b1 = epose*b; + //c1 = epose*c; + //d1 = epose*d; + + //print transform information + // ROS_INFO("w0: %f u0: %f -v0: %f x: %f\n",a1[0], b1[0], c1[0],d1[0]); + // ROS_INFO("w1: %f u1: %f -v1: %f y: %f\n",a1[1], b1[1], c1[1],d1[1]); + // ROS_INFO("w2: %f u2: %f -v2: %f z: %f\n",a1[2], b1[2], c1[2],d1[2]); + // ROS_INFO("t0: %f t1: %f t2: %f t3: %f\n",a1[3], b1[3], c1[3],d1[3]); + // ROS_INFO(""); // the eigen epose.data() returns column major data whereas the vtk matrix DeepCopy() // takes row major data, need to transpose the data before setting the vtk matrix diff --git a/tool_path_planner/src/raster_tool_path_planner.cpp b/tool_path_planner/src/raster_tool_path_planner.cpp index e1e9be35..ae47fc95 100644 --- a/tool_path_planner/src/raster_tool_path_planner.cpp +++ b/tool_path_planner/src/raster_tool_path_planner.cpp @@ -1276,8 +1276,13 @@ namespace tool_path_planner new_pt.normalize(); // insert the next derivative - double new_ptr[3] = {new_pt[0], new_pt[1], new_pt[2]}; + double new_ptr[3]; + new_ptr[0] = new_pt[0]; + new_ptr[1] = new_pt[1]; + new_ptr[2] = new_pt[2]; + derv->InsertNextTuple(&new_ptr[0]); + printf("new_ptr: %lf %lf %lf\n",new_ptr[0], new_ptr[1], new_ptr[2]); } // Set points and normals points->SetPoints(new_points);